From cc604d7fb55d7d39f353bcbea015e6f3e3731bf1 Mon Sep 17 00:00:00 2001 From: proctornt <78769699+proctornt@users.noreply.github.com> Date: Thu, 5 Jun 2025 17:49:22 -0400 Subject: [PATCH 001/180] added v3 manipulator --- .../frc/robot/commands/CompositeCommands.java | 187 +++++++++--------- .../manipulator/V3_EpsilonManipulator.java | 42 ++++ .../V3_EpsilonManipulatorConstants.java | 35 ++++ .../manipulator/V3_EpsilonManipulatorIO.java | 31 +++ .../V3_EpsilonManipulatorIOSim.java | 40 ++++ .../V3_EpsilonManipulatorIOTalonFX.java | 89 +++++++++ 6 files changed, 330 insertions(+), 94 deletions(-) create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 2e221326..ebfb5421 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -185,24 +185,24 @@ public static final Command twerk( cameras)); } - public static final Command twerk( - Drive drive, - Elevator elevator, - V1_StackUpManipulator manipulator, - ReefHeight level, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefAlgae(drive, cameras), - elevator.setPosition(() -> ReefHeight.L4), - Commands.waitUntil(elevator::atGoal), - manipulator.toggleAlgaeArm(), - Commands.waitSeconds(0.1), - elevator.setPosition(() -> level), - manipulator.removeAlgae().until(elevator::atGoal), - manipulator.removeAlgae().withTimeout(0.35), - manipulator.toggleAlgaeArm()); - } + public static final Command twerk( + Drive drive, + Elevator elevator, + V1_StackUpManipulator manipulator, + ReefHeight level, + Camera... cameras) { + return Commands.sequence( + DriveCommands.autoAlignReefAlgae(drive, cameras), + elevator.setPosition(() -> ReefHeight.L4), + Commands.waitUntil(elevator::atGoal), + manipulator.toggleAlgaeArm(), + Commands.waitSeconds(0.1), + elevator.setPosition(() -> level), + manipulator.removeAlgae().until(elevator::atGoal), + manipulator.removeAlgae().withTimeout(0.35), + manipulator.toggleAlgaeArm()); } + } public static final class V2_RedundancyCompositeCommands { public static final Command intakeCoralAuto( @@ -428,51 +428,50 @@ public static final Command autoScoreCoralSequence( () -> RobotState.getOIData().currentReefHeight().equals(ReefHeight.L1)); } - public static final Command intakeAlgaeFromReefSequence( - Drive drive, - Elevator elevator, - V2_RedundancyManipulator manipulator, - V2_RedundancyIntake intake, - Supplier level, - Camera... cameras) { - return Commands.sequence( - Commands.parallel( - DriveCommands.autoAlignReefAlgae(drive, cameras), - Commands.sequence( - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - level, - ArmState.STOW_DOWN, - IntakeState.STOW), - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - level, - ArmState.REEF_INTAKE, - IntakeState.STOW)), - manipulator.intakeReefAlgae()) - .until(() -> RobotState.isHasAlgae()), - Commands.parallel( - Commands.sequence( - Commands.waitSeconds(0.25), - Commands.either( - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.STOW, - ArmState.STOW_UP, - IntakeState.STOW), - Commands.none(), - RobotState::isHasAlgae)), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), - () -> drive.stop()) - .withTimeout(0.5))); - } + public static final Command intakeAlgaeFromReefSequence( + Drive drive, + Elevator elevator, + V2_RedundancyManipulator manipulator, + V2_RedundancyIntake intake, + Supplier level, + Camera... cameras) { + return Commands.sequence( + Commands.parallel( + DriveCommands.autoAlignReefAlgae(drive, cameras), + Commands.sequence( + DecisionTree.moveSequence( + elevator, + manipulator, + intake, + level, + ArmState.STOW_DOWN, + IntakeState.STOW), + DecisionTree.moveSequence( + elevator, + manipulator, + intake, + level, + ArmState.REEF_INTAKE, + IntakeState.STOW)), + manipulator.intakeReefAlgae()) + .until(() -> RobotState.isHasAlgae()), + Commands.parallel( + Commands.sequence( + Commands.waitSeconds(0.25), + Commands.either( + DecisionTree.moveSequence( + elevator, + manipulator, + intake, + () -> ReefHeight.STOW, + ArmState.STOW_UP, + IntakeState.STOW), + Commands.none(), + RobotState::isHasAlgae)), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) + .withTimeout(0.5))); + } public static final Command scoreAlgae( Elevator elevator, V2_RedundancyManipulator manipulator, V2_RedundancyIntake intake) { @@ -519,21 +518,21 @@ public static final Command dropAlgae( IntakeState.STOW)); } - public static final Command netHeight( - Elevator elevator, - Funnel funnel, - V2_RedundancyManipulator manipulator, - V2_RedundancyIntake intake) { - return Commands.sequence( - funnel.setClapDaddyGoal(FunnelState.CLOSED), - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.ALGAE_SCORE, - ArmState.STOW_UP, - IntakeState.STOW)); - } + public static final Command netHeight( + Elevator elevator, + Funnel funnel, + V2_RedundancyManipulator manipulator, + V2_RedundancyIntake intake) { + return Commands.sequence( + funnel.setClapDaddyGoal(FunnelState.CLOSED), + DecisionTree.moveSequence( + elevator, + manipulator, + intake, + () -> ReefHeight.ALGAE_SCORE, + ArmState.STOW_UP, + IntakeState.STOW)); + } public static final Command scoreProcessorNew( Elevator elevator, V2_RedundancyManipulator manipulator, V2_RedundancyIntake intake) { @@ -559,23 +558,23 @@ public static final Command scoreProcessor( IntakeState.STOW); } - public static final Command floorIntakeSequence( - V2_RedundancyManipulator manipulator, Elevator elevator, V2_RedundancyIntake intake) { - return Commands.sequence( - Commands.sequence( - Commands.deadline( - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.ALGAE_FLOOR_INTAKE, - ArmState.FLOOR_INTAKE, - IntakeState.INTAKE), - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - intake.setRollerVoltage(6.0)), - Commands.parallel(intake.intakeAlgae(), manipulator.intakeFloorAlgae())) - .until(() -> RobotState.isHasAlgae())); - } + public static final Command floorIntakeSequence( + V2_RedundancyManipulator manipulator, Elevator elevator, V2_RedundancyIntake intake) { + return Commands.sequence( + Commands.sequence( + Commands.deadline( + DecisionTree.moveSequence( + elevator, + manipulator, + intake, + () -> ReefHeight.ALGAE_FLOOR_INTAKE, + ArmState.FLOOR_INTAKE, + IntakeState.INTAKE), + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + intake.setRollerVoltage(6.0)), + Commands.parallel(intake.intakeAlgae(), manipulator.intakeFloorAlgae())) + .until(() -> RobotState.isHasAlgae())); + } public static final Command postFloorIntakeSequence( V2_RedundancyManipulator manipulator, Elevator elevator, V2_RedundancyIntake intake) { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java new file mode 100644 index 00000000..95958d5b --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java @@ -0,0 +1,42 @@ +package frc.robot.subsystems.v3_Epsilon.manipulator; + +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import org.littletonrobotics.junction.AutoLogOutput; +import org.littletonrobotics.junction.Logger; + +public class V3_EpsilonManipulator extends SubsystemBase { + private final V3_EpsilonManipulatorIO io; + private final ManipulatorIOInputsAutoLogged inputs; + + private final Timer currentTimer; + private Rotation2d previousPosition; + private Rotation2d desiredRotations; + + public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { + this.io = io; + inputs = new ManipulatorIOInputsAutoLogged(); + + currentTimer = new Timer(); + previousPosition = inputs.position; + desiredRotations = new Rotation2d(); + } + + @Override + public void periodic() { + io.updateInputs(inputs); + Logger.processInputs("Manipulator", inputs); + } + + @AutoLogOutput(key = "Manipulator/Has Coral") + public boolean hasCoral() { + return Math.abs(inputs.torqueCurrentAmps) + > V3_EpsilonManipulatorConstants.MANIPULATOR_CURRENT_THRESHOLD; + } + + public Command runManipulator(double volts) { + return this.runEnd(() -> io.setVoltage(volts), () -> io.setVoltage(0)); + } +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java new file mode 100644 index 00000000..8535e953 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java @@ -0,0 +1,35 @@ +package frc.robot.subsystems.v3_Epsilon.manipulator; + +import edu.wpi.first.math.geometry.Rotation2d; +import frc.robot.util.LoggedTunableNumber; + +public class V3_EpsilonManipulatorConstants { + public static final int MANIPULATOR_CAN_ID; + public static final double SUPPLY_CURRENT_LIMIT; + public static final double MANIPULATOR_CURRENT_THRESHOLD; + public static final Rotation2d MANIPULATOR_TOGGLE_ARM_ROTATION; + public static final Voltages VOLTAGES; + + static { + MANIPULATOR_CAN_ID = 30; + SUPPLY_CURRENT_LIMIT = 40.0; + MANIPULATOR_CURRENT_THRESHOLD = 39.0; + MANIPULATOR_TOGGLE_ARM_ROTATION = Rotation2d.fromRadians(10); + VOLTAGES = + new Voltages( + new LoggedTunableNumber("Manipulator/Intake Volts", 6.0), + new LoggedTunableNumber("Manipulator/L4 Volts", 4.0), + new LoggedTunableNumber("Manipulator/Score Volts", 10.0), + new LoggedTunableNumber("Manipulator/Remove Algae Volts", 12), + new LoggedTunableNumber("Manipulator/HalfScore Volts", 1.0), + new LoggedTunableNumber("Manipulator/L1 Volts", 3.5)); + } + + public static final record Voltages( + LoggedTunableNumber INTAKE_VOLTS, + LoggedTunableNumber L4_VOLTS, + LoggedTunableNumber SCORE_VOLTS, + LoggedTunableNumber REMOVE_ALGAE, + LoggedTunableNumber HALF_VOLTS, + LoggedTunableNumber L1_VOLTS) {} +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java new file mode 100644 index 00000000..2030ce22 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java @@ -0,0 +1,31 @@ +package frc.robot.subsystems.v3_Epsilon.manipulator; + +import edu.wpi.first.math.geometry.Rotation2d; +import org.littletonrobotics.junction.AutoLog; + +public interface V3_EpsilonManipulatorIO { + + @AutoLog + public static class ManipulatorIOInputs { + public Rotation2d position = new Rotation2d(); + public double velocityRadiansPerSecond = 0.0; + public double appliedVolts = 0.0; + public double supplyCurrentAmps = 0.0; + public double torqueCurrentAmps = 0.0; + public double temperatureCelsius = 0.0; + } + + /** + * Updates the inputs for the manipulator subsystem. + * + * @param inputs The inputs to update. + */ + public default void updateInputs(ManipulatorIOInputs inputs) {} + + /** + * Sets the voltage for the manipulator. + * + * @param volts The voltage to set. + */ + public default void setVoltage(double volts) {} +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java new file mode 100644 index 00000000..405c461b --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java @@ -0,0 +1,40 @@ +package frc.robot.subsystems.v3_Epsilon.manipulator; + +import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.system.plant.DCMotor; +import edu.wpi.first.math.system.plant.LinearSystemId; +import edu.wpi.first.wpilibj.simulation.DCMotorSim; +import frc.robot.Constants; + +public class V3_EpsilonManipulatorIOSim implements V3_EpsilonManipulatorIO { + private final DCMotorSim sim; + + private double appliedVolts; + + public V3_EpsilonManipulatorIOSim() { + sim = + new DCMotorSim( + LinearSystemId.createDCMotorSystem(DCMotor.getKrakenX60Foc(1), 0.004, 3.0), + DCMotor.getKrakenX60Foc(1)); + + appliedVolts = 0.0; + } + + @Override + public void updateInputs(ManipulatorIOInputs inputs) { + appliedVolts = MathUtil.clamp(appliedVolts, -12.0, 12.0); + + sim.setInputVoltage(appliedVolts); + sim.update(Constants.LOOP_PERIOD_SECONDS); + + inputs.position = Rotation2d.fromRadians(sim.getAngularPositionRad()); + inputs.velocityRadiansPerSecond = sim.getAngularVelocityRadPerSec(); + inputs.appliedVolts = appliedVolts; + inputs.supplyCurrentAmps = sim.getCurrentDrawAmps(); + } + + public void setVoltage(double volts) { + appliedVolts = volts; + } +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java new file mode 100644 index 00000000..99046887 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java @@ -0,0 +1,89 @@ +package frc.robot.subsystems.v3_Epsilon.manipulator; + +import static frc.robot.util.PhoenixUtil.*; + +import com.ctre.phoenix6.BaseStatusSignal; +import com.ctre.phoenix6.StatusSignal; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.controls.VoltageOut; +import com.ctre.phoenix6.hardware.TalonFX; +import com.ctre.phoenix6.signals.InvertedValue; +import com.ctre.phoenix6.signals.NeutralModeValue; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.util.Units; +import edu.wpi.first.units.measure.Angle; +import edu.wpi.first.units.measure.AngularVelocity; +import edu.wpi.first.units.measure.Current; +import edu.wpi.first.units.measure.Temperature; +import edu.wpi.first.units.measure.Voltage; +import frc.robot.subsystems.v1_StackUp.manipulator.V1_StackUpManipulatorConstants; + +public class V3_EpsilonManipulatorIOTalonFX implements V3_EpsilonManipulatorIO { + + private final TalonFX talonFX; + private final StatusSignal positionRotations; + private final StatusSignal velocityRotationsPerSecond; + private final StatusSignal appliedVoltage; + private final StatusSignal supplyCurrentAmps; + private final StatusSignal torqueCurrentAmps; + private final StatusSignal temperatureCelsius; + private final VoltageOut voltageRequest; + private final TalonFXConfiguration config; + + public V3_EpsilonManipulatorIOTalonFX() { + talonFX = new TalonFX(V1_StackUpManipulatorConstants.MANIPULATOR_CAN_ID); + + config = new TalonFXConfiguration(); + + config.MotorOutput.NeutralMode = NeutralModeValue.Brake; + config.CurrentLimits.SupplyCurrentLimit = V1_StackUpManipulatorConstants.SUPPLY_CURRENT_LIMIT; + config.CurrentLimits.SupplyCurrentLimitEnable = true; + config.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; + + tryUntilOk(5, () -> talonFX.getConfigurator().apply(config, 0.25)); + + positionRotations = talonFX.getPosition(); + velocityRotationsPerSecond = talonFX.getVelocity(); + appliedVoltage = talonFX.getMotorVoltage(); + supplyCurrentAmps = talonFX.getSupplyCurrent(); + torqueCurrentAmps = talonFX.getTorqueCurrent(); + temperatureCelsius = talonFX.getDeviceTemp(); + + voltageRequest = new VoltageOut(0); + + BaseStatusSignal.setUpdateFrequencyForAll( + 50.0, + positionRotations, + velocityRotationsPerSecond, + appliedVoltage, + supplyCurrentAmps, + torqueCurrentAmps, + temperatureCelsius); + + talonFX.optimizeBusUtilization(); + } + + @Override + public void updateInputs(ManipulatorIOInputs inputs) { + BaseStatusSignal.refreshAll( + positionRotations, + velocityRotationsPerSecond, + appliedVoltage, + supplyCurrentAmps, + torqueCurrentAmps, + temperatureCelsius); + + inputs.position = Rotation2d.fromRotations(positionRotations.getValueAsDouble()); + inputs.velocityRadiansPerSecond = + Units.rotationsToRadians(velocityRotationsPerSecond.getValueAsDouble()); + inputs.appliedVolts = appliedVoltage.getValueAsDouble(); + inputs.supplyCurrentAmps = supplyCurrentAmps.getValueAsDouble(); + inputs.torqueCurrentAmps = torqueCurrentAmps.getValueAsDouble(); + inputs.temperatureCelsius = temperatureCelsius.getValueAsDouble(); + } + + @Override + public void setVoltage(double volts) { + talonFX.setControl(voltageRequest.withOutput(volts).withEnableFOC(true)); + } +} From d5fae0c6da1b4b409813f58b7887bcb4bfc62acb Mon Sep 17 00:00:00 2001 From: proctornt <78769699+proctornt@users.noreply.github.com> Date: Thu, 5 Jun 2025 18:59:30 -0400 Subject: [PATCH 002/180] intake IO --- .../v3_Epsilon/intake/V3_EpsilonIntakeIO.java | 80 +++++++++++++++++++ 1 file changed, 80 insertions(+) create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java new file mode 100644 index 00000000..1d53bc97 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java @@ -0,0 +1,80 @@ +package frc.robot.subsystems.v3_Epsilon.intake; + +import edu.wpi.first.math.geometry.Rotation2d; +import org.littletonrobotics.junction.AutoLog; + +public interface V3_EpsilonIntakeIO{ + @AutoLog + public static class IntakeIOInputs{ + public Rotation2d intakePosition= new Rotation2d(); + public double intakeVelocityRadiansPerSecond=0.0; + public double intakeAppliedVolts=0.0; + public double intakeSupplyCurrentAmps=0.0; + public double intakeTorqueCurrentAmps=0.0; + public double intakeTemperatureCelsius=0.0; + public Rotation2d intakePositionGoal = new Rotation2d(); + public Rotation2d intakePositionSetpoint = new Rotation2d(); + public Rotation2d intakePositionError = new Rotation2d(); + + public Rotation2d rollerPosition = new Rotation2d(); + public double rollerVelocityRadiansPerSecond = 0.0; + public double rollerAccelerationRadiansPerSecondSquared = 0.0; + public double rollerAppliedVolts = 0.0; + public double rollerSupplyCurrentAmps = 0.0; + public double rollerTorqueCurrentAmps = 0.0; + public double rollerTemperatureCelsius = 0.0; + } + + /** + * Updates the inputs for the manipulator subsystem. + * + * @param inputs The inputs to update. + */ + public default void updateInputs(IntakeIOInputs inputs) {} + + /** + * Sets the voltage for the intake. + * + * @param volts The voltage to set. + */ + public default void setIntakeVoltage(double volts) {} + + /** + * Sets the voltage for the manipulator. + * + * @param volts The voltage to set. + */ + public default void setRollerVoltage(double volts) {} + + /** + * Sets the position goal for the intake. + * + * @param meters The position goal to set in meters. + */ + public default void setIntakePositionGoal(Rotation2d rotatoion) {} + + /** + * Sets the gains for the intake + * + * + * @param kP The proportional gain. + * @param kD The derivative gain. + * @param kS The static gain. + * @param kV The velocity gain. + * @param kA The acceleration gain. + * @param kG The gravity gain. + */ + public default void updateSlot0IntakeGains( + double kP, double kD, double kS, double kV, double kA, double kG) {} + + public default void updateSlot1IntakeGains( + double kP, double kD, double kS, double kV, double kA, double kG) {} + + /** + * Sets the constraints for the intake. + * + * @param maxAcceleration The maximum acceleration. + * @param cruisingVelocity The cruising velocity. + */ + +} \ No newline at end of file From e055443cc8dd53b4ea08cef62afc0bb90803deda Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sun, 20 Jul 2025 12:53:54 -0400 Subject: [PATCH 003/180] Finished files for epsilon manipulator IO + constant; some errors that need to be debugged --- .../manipulator/V3_EpsilonManipulator.java | 182 +++++++ .../V3_EpsilonManipulatorConstants.java | 132 ++++- .../manipulator/V3_EpsilonManipulatorIO.java | 21 +- vendordeps/Phoenix6-frc2025-latest.json | 479 ++++++++++++++++++ 4 files changed, 797 insertions(+), 17 deletions(-) create mode 100644 vendordeps/Phoenix6-frc2025-latest.json diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java index 95958d5b..5f4eb257 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java @@ -1,11 +1,21 @@ package frc.robot.subsystems.v3_Epsilon.manipulator; +import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; + +import java.util.function.BooleanSupplier; + import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; +import frc.robot.RobotState; +import frc.robot.subsystems.v2_Redundancy.manipulator.V2_RedundancyManipulatorConstants; +import frc.robot.subsystems.v2_Redundancy.manipulator.V2_RedundancyManipulatorConstants.ArmState; public class V3_EpsilonManipulator extends SubsystemBase { private final V3_EpsilonManipulatorIO io; @@ -15,6 +25,8 @@ public class V3_EpsilonManipulator extends SubsystemBase { private Rotation2d previousPosition; private Rotation2d desiredRotations; + private boolean isClosedLoop; + public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { this.io = io; inputs = new ManipulatorIOInputsAutoLogged(); @@ -22,6 +34,16 @@ public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { currentTimer = new Timer(); previousPosition = inputs.position; desiredRotations = new Rotation2d(); + + isClosedLoop = true; + algaeCharacterizationRoutine = + new SysIdRoutine( + new SysIdRoutine.Config( + Volts.of(0.2).per(Second), + Volts.of(3.5), + Seconds.of(5), + (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), + new SysIdRoutine.Mechanism((volts) -> io.setVoltage(volts.in(Volts)), null, this)); } @Override @@ -36,7 +58,167 @@ public boolean hasCoral() { > V3_EpsilonManipulatorConstants.MANIPULATOR_CURRENT_THRESHOLD; } + @AutoLogOutput(key = "Manipulator/Has Algae") + public boolean hasAlgae() { + return Math.abs(inputs.torqueCurrentAmps) + > V3_EpsilonManipulatorConstants.MANIPULATOR_CURRENT_THRESHOLD; + } + + public Command runArmToPositionCommand( + Rotation2d position, + double maxVelocity, + double maxAcceleration, + BooleanSupplier isFinished) { + return this.runEnd( + () -> { + io.setArmPositionGoal(position); + isClosedLoop = true; + }, + () -> { + io.setArmPositionGoal(inputs.armPosition); + isClosedLoop = false; + }, + isFinished); + } public Command runManipulator(double volts) { return this.runEnd(() -> io.setVoltage(volts), () -> io.setVoltage(0)); } + + public Command intakeCoral(BooleanSupplier shouldStop) { + Command cmd = + Commands.sequence( + runManipulator( + V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.CORAL_INTAKE_VOLTS().get()) + .until(shouldStop)); + cmd.addRequirements(this); + return cmd; + } + + public Command intakeReefAlgae() { + return Commands.sequence( + Commands.parallel( + Commands.sequence( + Commands.waitUntil(() -> isIntakingAlgae()), + Commands.runOnce(() -> RobotState.setIntakingAlgae(true))), + runManipulator( + V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().get()))) + .finallyDo(() -> RobotState.setIntakingAlgae(false)); + } + + public Command intakeFloorAlgae() { + return Commands.sequence( + Commands.parallel( + Commands.sequence( + Commands.waitUntil(() -> isIntakingAlgae()), + Commands.runOnce(() -> RobotState.setIntakingAlgae(true))), + runManipulator( + V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().get()))) + .finallyDo(() -> RobotState.setIntakingAlgae(false)); + } + + public Command scoreCoral() { + return runManipulator( + V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.SCORE_CORAL_VOLTS().get()); + } + + public Command scoreAlgae() { + Command cmd = + runManipulator(V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.SCORE_ALGAE_VOLTS().get()); + cmd.addRequirements(this); + return cmd.finallyDo(() -> RobotState.setHasAlgae(false)); + } + + public Command scoreL1Coral() { + return runManipulator(V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.L1_VOLTS().get()); + } + + public Command scoreL4Coral() { + return runManipulator(V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.L4_VOLTS().get()); + } + + public Command halfScoreCoral() { + return runManipulator(V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.HALF_VOLTS().get()); + } + + public Command unHalfScoreCoral() { + return runManipulator(-V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.HALF_VOLTS().get()); + } + + public Command sysIdRoutine() { + return Commands.sequence( + Commands.runOnce(() -> isClosedLoop = false), + algaeCharacterizationRoutine.quasistatic(Direction.kForward), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.quasistatic(Direction.kReverse), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.dynamic(Direction.kForward), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.dynamic(Direction.kReverse)); + } + + public Command setAlgaeArmGoal(ArmState goal) { + return this.runOnce( + () -> { + isClosedLoop = true; + state = goal; + }); + } + + public void updateArmGains( + double kP0, + double kD0, + double kS0, + double kV0, + double kA0, + double kG0, + double kP1, + double kD1, + double kS1, + double kV1, + double kA1, + double kG1) { + io.updateSlot0ArmGains(kP0, kD0, kS0, kV0, kA0, kG0); + io.updateSlot1ArmGains(kP1, kD1, kS1, kV1, kA1, kG1); + } + + public void updateArmConstraints(double maxAcceleration, double maxVelocity) { + io.updateArmConstraints(maxAcceleration, maxVelocity); + } + + @AutoLogOutput(key = "Manipulator/Arm At Goal") + public boolean algaeArmAtGoal() { + return inputs.armPosition.getRadians() - state.getAngle().getRadians() + <= V2_RedundancyManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); + } + + public Command waitUntilAlgaeArmAtGoal() { + return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::algaeArmAtGoal)); + } + + public Command homingSequence() { + return Commands.sequence( + Commands.runOnce( + () -> { + isClosedLoop = false; + io.armMax(); + }), + Commands.runEnd(() -> io.setArmVoltage(-6), () -> io.setArmVoltage(0)) + .until(() -> Math.abs(inputs.armTorqueCurrentAmps) > 40), + Commands.runOnce(() -> io.zeroArmPosition())); + } + + private double holdVoltage() { + double y; + double x = Math.abs(inputs.rollerTorqueCurrentAmps); + if (x <= 20) { + y = -0.0003 * Math.pow(x, 3) + 0.0124286 * Math.pow(x, 2) - 0.241071 * x + 4.00643; + } else { + y = 0.0005 * Math.pow(x, 2) - 0.1015 * x + 3.7425; + } + return MathUtil.clamp( + 1.25 * y, + 0.10, + V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().get() / 1.5); + } +} } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java index 8535e953..931b7f01 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java @@ -1,28 +1,80 @@ package frc.robot.subsystems.v3_Epsilon.manipulator; import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.system.plant.DCMotor; +import edu.wpi.first.math.util.Units; +import frc.robot.subsystems.shared.drive.DriveConstants; +import frc.robot.subsystems.v2_Redundancy.manipulator.V2_RedundancyManipulatorConstants.ArmParameters; +import frc.robot.subsystems.v2_Redundancy.manipulator.V2_RedundancyManipulatorConstants.ManipulatorCurrentLimits; import frc.robot.util.LoggedTunableNumber; +import lombok.RequiredArgsConstructor; public class V3_EpsilonManipulatorConstants { - public static final int MANIPULATOR_CAN_ID; - public static final double SUPPLY_CURRENT_LIMIT; - public static final double MANIPULATOR_CURRENT_THRESHOLD; + public static final int ARM_CAN_ID = 31; + public static final ArmParameters ARM_PARAMETERS; + public static final Gains WITHOUT_ALGAE_GAINS; + public static final Gains WITH_ALGAE_GAINS; + public static final Constraints CONSTRAINTS; + + public static final int ROLLER_CAN_ID; + public static final double ROLLER_CURRENT_THRESHOLD; + public static final Rotation2d ROLLER_TOGGLE_ARM_ROTATION; + public static final Voltages ROLLER_VOLTAGES; + + public static final ManipulatorCurrentLimits CURRENT_LIMITS; + + public static final int MANIPULATOR_CAN_ID = 42; + public static final double SUPPLY_CURRENT_LIMIT = 56; + public static final double MANIPULATOR_CURRENT_THRESHOLD = 23; public static final Rotation2d MANIPULATOR_TOGGLE_ARM_ROTATION; public static final Voltages VOLTAGES; - static { - MANIPULATOR_CAN_ID = 30; - SUPPLY_CURRENT_LIMIT = 40.0; - MANIPULATOR_CURRENT_THRESHOLD = 39.0; - MANIPULATOR_TOGGLE_ARM_ROTATION = Rotation2d.fromRadians(10); - VOLTAGES = + static { + ARM_PARAMETERS = + new ArmParameters( + DCMotor.getKrakenX60Foc(1), + Rotation2d.fromDegrees(-77.0), + Rotation2d.fromDegrees(75.0), + 1, + 90.0, + 0.5); + WITHOUT_ALGAE_GAINS = + new Gains( + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kP", 125), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kD", 0), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kS", 0.24274), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kG", 0.66177), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kV", 0.0), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kA", 0.0)); + WITH_ALGAE_GAINS = + new Gains( + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kP", 125), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kD", 0), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kS", 0.65347), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kG", 2.0762), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kV", 0.0), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kA", 0.0)); + CONSTRAINTS = + new Constraints( + new LoggedTunableNumber("Manipulator/Arm/MaxAcceleration", 2.0), + new LoggedTunableNumber("Manipulator/Arm/CruisingVelocity", 5.0), + new LoggedTunableNumber("Manipulator/Arm/GoalTolerance", Units.degreesToRadians(1.5))); + + ROLLER_CAN_ID = 30; + ROLLER_CURRENT_THRESHOLD = 60.0; + ROLLER_TOGGLE_ARM_ROTATION = Rotation2d.fromRadians(10); + ROLLER_VOLTAGES = new Voltages( - new LoggedTunableNumber("Manipulator/Intake Volts", 6.0), - new LoggedTunableNumber("Manipulator/L4 Volts", 4.0), - new LoggedTunableNumber("Manipulator/Score Volts", 10.0), + new LoggedTunableNumber("Manipulator/Coral Intake Volts", 6.0), + new LoggedTunableNumber("Manipulator/Algae Intake Volts", 12.0), + new LoggedTunableNumber("Manipulator/L4 Volts", 4.6 * 1.56), + new LoggedTunableNumber("Manipulator/Score Coral Volts", 4.8 * 1.56), + new LoggedTunableNumber("Manipulator/Score Algae Volts", -6), new LoggedTunableNumber("Manipulator/Remove Algae Volts", 12), - new LoggedTunableNumber("Manipulator/HalfScore Volts", 1.0), - new LoggedTunableNumber("Manipulator/L1 Volts", 3.5)); + new LoggedTunableNumber("Manipulator/HalfScore Volts", 1.0 * 1.56), + new LoggedTunableNumber("Manipulator/L1 Volts", 3.5 * 1.56)); + + CURRENT_LIMITS = new ManipulatorCurrentLimits(40, 40, 40, 40); } public static final record Voltages( @@ -32,4 +84,56 @@ public static final record Voltages( LoggedTunableNumber REMOVE_ALGAE, LoggedTunableNumber HALF_VOLTS, LoggedTunableNumber L1_VOLTS) {} + + public static record Gains( + LoggedTunableNumber kP, + LoggedTunableNumber kD, + LoggedTunableNumber kS, + LoggedTunableNumber kG, + LoggedTunableNumber kV, + LoggedTunableNumber kA) {} + + public static record Constraints( + LoggedTunableNumber maxAcceleration, + LoggedTunableNumber cruisingVelocity, + LoggedTunableNumber goalTolerance) {} + + public static final record ManipulatorCurrentLimits( + double MANIPULATOR_SUPPLY_CURRENT_LIMIT, + double ROLLER_SUPPLY_CURRENT_LIMIT, + double MANIPULATOR_STATOR_CURRENT_LIMIT, + double ROLLER_STATOR_CURRENT_LIMIT) {} + + public static record Constraints( + LoggedTunableNumber maxAccelerationRotationsPerSecondSquared, + LoggedTunableNumber cruisingVelocityRotationsPerSecond, + LoggedTunableNumber goalToleranceRadians) {} + + public static final record Voltages( + LoggedTunableNumber CORAL_INTAKE_VOLTS, + LoggedTunableNumber ALGAE_INTAKE_VOLTS, + LoggedTunableNumber L4_VOLTS, + LoggedTunableNumber SCORE_CORAL_VOLTS, + LoggedTunableNumber SCORE_ALGAE_VOLTS, + LoggedTunableNumber REMOVE_ALGAE, + LoggedTunableNumber HALF_VOLTS, + LoggedTunableNumber L1_VOLTS) {} + + @RequiredArgsConstructor + public static enum ArmState { + STOW_UP(Rotation2d.fromDegrees(75)), + PRE_SCORE(Rotation2d.fromDegrees(50.0)), + PROCESSOR(Rotation2d.fromDegrees(-61.279296875 + 20)), + REEF_INTAKE(Rotation2d.fromDegrees(-61.279296875 + 15)), + INTAKE_OUT_LINE(Rotation2d.fromDegrees(-61)), + FLOOR_INTAKE(Rotation2d.fromDegrees(-68.5 - 5)), + STOW_LINE(Rotation2d.fromDegrees(-75)), + STOW_DOWN(Rotation2d.fromDegrees(-77)); + + private final Rotation2d angle; + + public Rotation2d getAngle() { + return angle; + } + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java index 2030ce22..845942c5 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java @@ -1,19 +1,34 @@ package frc.robot.subsystems.v3_Epsilon.manipulator; -import edu.wpi.first.math.geometry.Rotation2d; import org.littletonrobotics.junction.AutoLog; +import edu.wpi.first.math.geometry.Rotation2d; + public interface V3_EpsilonManipulatorIO { @AutoLog public static class ManipulatorIOInputs { - public Rotation2d position = new Rotation2d(); + public Rotation2d armPosition = new Rotation2d(); public double velocityRadiansPerSecond = 0.0; public double appliedVolts = 0.0; public double supplyCurrentAmps = 0.0; public double torqueCurrentAmps = 0.0; public double temperatureCelsius = 0.0; - } + + + public Rotation2d armPositionGoal = new Rotation2d(); + public Rotation2d armPositionSetpoint = new Rotation2d(); + public Rotation2d armPositionError = new Rotation2d(); + public Rotation2d rollerPosition = new Rotation2d(); + + + public double rollerVelocityRadiansPerSecond = 0.0; + public double rollerAccelerationRadiansPerSecondSquared = 0.0; + public double rollerAppliedVolts = 0.0; + public double rollerSupplyCurrentAmps = 0.0; + public double rollerTorqueCurrentAmps = 0.0; + public double rollerTemperatureCelsius = 0.0; + } /** * Updates the inputs for the manipulator subsystem. diff --git a/vendordeps/Phoenix6-frc2025-latest.json b/vendordeps/Phoenix6-frc2025-latest.json new file mode 100644 index 00000000..ce44ce4f --- /dev/null +++ b/vendordeps/Phoenix6-frc2025-latest.json @@ -0,0 +1,479 @@ +{ + "fileName": "Phoenix6-frc2025-latest.json", + "name": "CTRE-Phoenix (v6)", + "version": "25.4.0", + "frcYear": "2025", + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json", + "conflictsWith": [ + { + "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", + "errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.", + "offlineFileName": "Phoenix6-replay-frc2025-latest.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-java", + "version": "25.4.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "api-cpp", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "api-cpp-sim", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFXS", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANrange", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdi", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdle", + "version": "25.4.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-cpp", + "version": "25.4.0", + "libName": "CTRE_Phoenix6_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "25.4.0", + "libName": "CTRE_PhoenixTools", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "25.4.0", + "libName": "CTRE_Phoenix6_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "25.4.0", + "libName": "CTRE_PhoenixTools_Sim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "25.4.0", + "libName": "CTRE_SimTalonSRX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "25.4.0", + "libName": "CTRE_SimVictorSPX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "25.4.0", + "libName": "CTRE_SimPigeonIMU", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "25.4.0", + "libName": "CTRE_SimCANCoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "25.4.0", + "libName": "CTRE_SimProTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFXS", + "version": "25.4.0", + "libName": "CTRE_SimProTalonFXS", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "25.4.0", + "libName": "CTRE_SimProCANcoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "25.4.0", + "libName": "CTRE_SimProPigeon2", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANrange", + "version": "25.4.0", + "libName": "CTRE_SimProCANrange", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdi", + "version": "25.4.0", + "libName": "CTRE_SimProCANdi", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANdle", + "version": "25.4.0", + "libName": "CTRE_SimProCANdle", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxarm64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +} From 96a370317454c82ac54c661231291c74217c0f24 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Fri, 1 Aug 2025 17:57:10 -0400 Subject: [PATCH 004/180] Add V3 Epsilon intake subsystem and constants; finished manipulator subsystem Co-authored-by: iamabhiveni --- src/main/java/frc/robot/Robot.java | 1 + .../v3_Epsilon/intake/V3_EpsilonIntake.java | 91 ++++ .../intake/V3_EpsilonIntakeConstants.java | 106 +++++ .../v3_Epsilon/intake/V3_EpsilonIntakeIO.java | 57 ++- .../intake/V3_EpsilonIntakeIOSim.java | 137 ++++++ .../intake/V3_EpsilonIntakeIOTalonFX.java | 142 ++++++ .../manipulator/V3_EpsilonManipulator.java | 160 ++----- .../V3_EpsilonManipulatorConstants.java | 68 +-- .../manipulator/V3_EpsilonManipulatorIO.java | 59 ++- .../V3_EpsilonManipulatorIOSim.java | 120 ++++- .../V3_EpsilonManipulatorIOTalonFX.java | 188 ++++++-- vendordeps/Phoenix6-25.3.2.json | 449 ------------------ 12 files changed, 880 insertions(+), 698 deletions(-) create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOSim.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java delete mode 100644 vendordeps/Phoenix6-25.3.2.json diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 61072110..eafdc06b 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -11,6 +11,7 @@ import edu.wpi.first.wpilibj.Watchdog; import edu.wpi.first.wpilibj.livewindow.LiveWindow; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; +import edu.wpi.first.wpilibj.simulation.BatterySim; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; import frc.robot.FieldConstants.Reef.ReefHeight; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java new file mode 100644 index 00000000..453c40a7 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java @@ -0,0 +1,91 @@ +package frc.robot.subsystems.v3_Epsilon.intake; + +import static edu.wpi.first.units.Units.*; + +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants.IntakeState; +import lombok.Getter; +import org.littletonrobotics.junction.AutoLogOutput; +import org.littletonrobotics.junction.Logger; + + + +public class V3_EpsilonIntake extends SubsystemBase { + private final V3_EpsilonIntakeIO io; + private final IntakeIOInputsAutoLogged inputs; + private final SysIdRoutine characterizationRoutine; + + @Getter @AutoLogOutput(key = "Intake/Goal") + private IntakeState goal; + + private boolean isClosedLoop; + + public V3_EpsilonIntake(V3_EpsilonIntakeIO io) { + this.io = io; + inputs = new IntakeIOInputsAutoLogged(); + + characterizationRoutine = new SysIdRoutine( + new SysIdRoutine.Config( + Volts.of(0.2).per(Second), + Volts.of(3.5), + Seconds.of(8), + (state) -> Logger.recordOutput("Intake/SysID State", state.toString())), + new SysIdRoutine.Mechanism( + (volts) -> io.setPivotVoltage(volts.in(Volts)), null, this)); + + isClosedLoop = true; + } + + @Override + public void periodic() { + io.updateInputs(inputs); + Logger.processInputs("Intake", inputs); + + if (isClosedLoop) { + io.setPivotGoal(goal.getAngle()); + } + } + + @AutoLogOutput(key = "Intake/Has Coral") + public boolean hasCoral() { + return false; // Udpate later + } + + @AutoLogOutput(key = "Intake/At Goal") + public boolean atGoal() { + return Math.abs(inputs.pivotPosition.getRadians() - goal.getAngle().getRadians()) < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); + } + + public void setGoal(IntakeState goal) { + isClosedLoop = true; + this.goal = goal; + } + + public void setRollerVoltage(double volts) { + io.setRollerVoltage(volts); + } + + public void setPivotVoltage(double volts) { + isClosedLoop = false; + io.setPivotVoltage(volts); + } + + public Command sysIdRoutine() { + return Commands.sequence( + Commands.runOnce(() -> isClosedLoop = false), + Commands.runOnce(() -> characterizationRoutine.quasistatic(Direction.kForward)), + Commands.waitSeconds(0.25), + Commands.runOnce(() -> characterizationRoutine.quasistatic(Direction.kReverse)), + Commands.waitSeconds(0.25), + Commands.runOnce(() -> characterizationRoutine.dynamic(Direction.kForward)), + Commands.waitSeconds(0.25), + Commands.runOnce(() -> characterizationRoutine.dynamic(Direction.kReverse)) + ); + } + + +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java new file mode 100644 index 00000000..52c03d90 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java @@ -0,0 +1,106 @@ +package frc.robot.subsystems.v3_Epsilon.intake; + +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.system.plant.DCMotor; +import edu.wpi.first.math.util.Units; +import lombok.RequiredArgsConstructor; +import lombok.Getter; + +public class V3_EpsilonIntakeConstants { + public static final int PIVOT_CAN_ID; + + public static final int ROLLER_CAN_ID; + + public static final IntakeCurrentLimits CURRENT_LIMITS = new IntakeCurrentLimits( + 40.0, + 40.0, + 40.0, + 40.0 + ); + + public static final Gains PIVOT_GAINS = new Gains( + 100.0, + 0.0, + 0.5, + 0.0, + 0.0, + 0.0 + ); + public static final Constraints PIVOT_CONSTRAINTS = new Constraints( + 500.0, + 500.0, + Rotation2d.fromDegrees(0.01) + ); + + public static final IntakeParems PIVOT_PARAMS = new IntakeParems( + 3.0, + DCMotor.getKrakenX60Foc(1), + 0.0042, + Rotation2d.fromDegrees(-90.0), + Rotation2d.fromDegrees(90.0) + ); + public static final IntakeParems ROLLER_PARAMS = new IntakeParems( + 1, + DCMotor.getKrakenX60Foc(1), + 0, + new Rotation2d(), + Rotation2d.fromDegrees(90.0) + ); + + + static { + PIVOT_CAN_ID = 60; + ROLLER_CAN_ID = 61; + } + + @RequiredArgsConstructor + public enum IntakeState { + STOW(new Rotation2d()), + INTAKE_CORAL(new Rotation2d()), + HANDOFF(new Rotation2d(Units.degreesToRadians(90))), + L1(new Rotation2d()), + INTAKE_ALGAE(new Rotation2d()); + + @Getter private final Rotation2d angle; + } + + public static record IntakeCurrentLimits( + double PIVOT_SUPPLY_CURRENT_LIMIT, + double PIVOT_STATOR_CURRENT_LIMIT, + double ROLLER_SUPPLY_CURRENT_LIMIT, + double ROLLER_STATOR_CURRENT_LIMIT + ) { + } + + public static record Gains( + double kP, + double kD, + double kS, + double kV, + double kA, + double kG + ) { + } + + public static record Constraints( + double MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED, + double CRUISING_VELOCITY_RADIANS_PER_SECOND, + Rotation2d GOAL_TOLERANCE + ) { + public edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints getTrapezoidConstraints() { + return new edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints( + CRUISING_VELOCITY_RADIANS_PER_SECOND, + MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED + ); + } + } + + public static record IntakeParems( + double PIVOT_GEAR_RATIO, + DCMotor MOTOR, + double MASS_KG, + Rotation2d MIN_ANGLE, + Rotation2d MAX_ANGLE + ) { + } +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java index 1d53bc97..7027d25a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java @@ -3,29 +3,29 @@ import edu.wpi.first.math.geometry.Rotation2d; import org.littletonrobotics.junction.AutoLog; -public interface V3_EpsilonIntakeIO{ - @AutoLog - public static class IntakeIOInputs{ - public Rotation2d intakePosition= new Rotation2d(); - public double intakeVelocityRadiansPerSecond=0.0; - public double intakeAppliedVolts=0.0; - public double intakeSupplyCurrentAmps=0.0; - public double intakeTorqueCurrentAmps=0.0; - public double intakeTemperatureCelsius=0.0; - public Rotation2d intakePositionGoal = new Rotation2d(); - public Rotation2d intakePositionSetpoint = new Rotation2d(); - public Rotation2d intakePositionError = new Rotation2d(); +public interface V3_EpsilonIntakeIO { + @AutoLog + public static class IntakeIOInputs { + public Rotation2d pivotPosition = new Rotation2d(); + public double pivotVelocityRadiansPerSecond = 0.0; + public double pivotAppliedVolts = 0.0; + public double pivotSupplyCurrentAmps = 0.0; + public double pivotTorqueCurrentAmps = 0.0; + public double pivotTemperatureCelsius = 0.0; - public Rotation2d rollerPosition = new Rotation2d(); - public double rollerVelocityRadiansPerSecond = 0.0; - public double rollerAccelerationRadiansPerSecondSquared = 0.0; - public double rollerAppliedVolts = 0.0; - public double rollerSupplyCurrentAmps = 0.0; - public double rollerTorqueCurrentAmps = 0.0; - public double rollerTemperatureCelsius = 0.0; - } + public Rotation2d pivotPositionGoal = new Rotation2d(); + public Rotation2d pivotPositionSetpoint = new Rotation2d(); + public Rotation2d pivotPositionError = new Rotation2d(); - /** + public Rotation2d rollerPosition = new Rotation2d(); + public double rollerVelocityRadiansPerSecond = 0.0; + public double rollerAppliedVolts = 0.0; + public double rollerSupplyCurrentAmps = 0.0; + public double rollerTorqueCurrentAmps = 0.0; + public double rollerTemperatureCelsius = 0.0; + } + + /** * Updates the inputs for the manipulator subsystem. * * @param inputs The inputs to update. @@ -37,7 +37,7 @@ public default void updateInputs(IntakeIOInputs inputs) {} * * @param volts The voltage to set. */ - public default void setIntakeVoltage(double volts) {} + public default void setPivotVoltage(double volts) {} /** * Sets the voltage for the manipulator. @@ -51,12 +51,12 @@ public default void setRollerVoltage(double volts) {} * * @param meters The position goal to set in meters. */ - public default void setIntakePositionGoal(Rotation2d rotatoion) {} + public default void setPivotGoal(Rotation2d rotatoion) {} + /** * Sets the gains for the intake * - * * @param kP The proportional gain. * @param kD The derivative gain. * @param kS The static gain. @@ -64,10 +64,7 @@ public default void setIntakePositionGoal(Rotation2d rotatoion) {} * @param kA The acceleration gain. * @param kG The gravity gain. */ - public default void updateSlot0IntakeGains( - double kP, double kD, double kS, double kV, double kA, double kG) {} - - public default void updateSlot1IntakeGains( + public default void updateIntakeGains( double kP, double kD, double kS, double kV, double kA, double kG) {} /** @@ -76,5 +73,5 @@ public default void updateSlot1IntakeGains( * @param maxAcceleration The maximum acceleration. * @param cruisingVelocity The cruising velocity. */ - -} \ No newline at end of file + public default void updateIntakeConstraints(double maxAcceleration, double cruisingVelocity) {} +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOSim.java new file mode 100644 index 00000000..e5d76e7d --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOSim.java @@ -0,0 +1,137 @@ +package frc.robot.subsystems.v3_Epsilon.intake; + +import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.controller.ArmFeedforward; +import edu.wpi.first.math.controller.ProfiledPIDController; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.system.plant.LinearSystemId; +import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints; +import edu.wpi.first.wpilibj.simulation.DCMotorSim; +import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim; +import frc.robot.Constants; + +public class V3_EpsilonIntakeIOSim implements V3_EpsilonIntakeIO { + private SingleJointedArmSim pivotMotorSim; + private DCMotorSim rollerMotorSim; + + private final ProfiledPIDController armFeedbackController; + private final ArmFeedforward armFeedforwardController; + + private double pivotAppliedVoltage; + private double rollerAppliedVoltage; + + private boolean isClosedLoop; + + public V3_EpsilonIntakeIOSim() { + pivotMotorSim = + new SingleJointedArmSim( + LinearSystemId.createSingleJointedArmSystem( + V3_EpsilonIntakeConstants.PIVOT_PARAMS.MOTOR(), + V3_EpsilonIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO(), + V3_EpsilonIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO()), + V3_EpsilonIntakeConstants.PIVOT_PARAMS.MOTOR(), + V3_EpsilonIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO(), + 0.1, + V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getRadians(), + V3_EpsilonIntakeConstants.PIVOT_PARAMS.MAX_ANGLE().getRadians(), + true, + V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getRadians()); + + rollerMotorSim = + new DCMotorSim( + LinearSystemId.createDCMotorSystem( + V3_EpsilonIntakeConstants.ROLLER_PARAMS.MOTOR(), + 0.04, + V3_EpsilonIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO()), + V3_EpsilonIntakeConstants.ROLLER_PARAMS.MOTOR()); + + armFeedbackController = + new ProfiledPIDController( + V3_EpsilonIntakeConstants.PIVOT_GAINS.kP(), + 0.0, + V3_EpsilonIntakeConstants.PIVOT_GAINS.kD(), + V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.getTrapezoidConstraints()); + armFeedbackController.disableContinuousInput(); + + armFeedforwardController = + new ArmFeedforward( + V3_EpsilonIntakeConstants.PIVOT_GAINS.kS(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kA(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kV(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kA()); + + pivotAppliedVoltage = 0.0; + rollerAppliedVoltage = 0.0; + isClosedLoop = false; + } + + @Override + public void updateInputs(IntakeIOInputs inputs) { + if (isClosedLoop) { + pivotAppliedVoltage = armFeedbackController.calculate(pivotMotorSim.getAngleRads())+ + armFeedforwardController.calculate(pivotMotorSim.getAngleRads(), pivotMotorSim.getVelocityRadPerSec()); + } + + pivotAppliedVoltage = MathUtil.clamp(pivotAppliedVoltage, -12.0, 12.0); + rollerAppliedVoltage = MathUtil.clamp(rollerAppliedVoltage, -12.0, 12.0); + + pivotMotorSim.setInputVoltage(pivotAppliedVoltage); + pivotMotorSim.update(Constants.LOOP_PERIOD_SECONDS); + + rollerMotorSim.setInputVoltage(rollerAppliedVoltage); + rollerMotorSim.update(Constants.LOOP_PERIOD_SECONDS); + + inputs.pivotPosition = new Rotation2d(pivotMotorSim.getAngleRads()); + inputs.pivotVelocityRadiansPerSecond = pivotMotorSim.getVelocityRadPerSec(); + inputs.pivotAppliedVolts = pivotAppliedVoltage; + inputs.pivotSupplyCurrentAmps = pivotMotorSim.getCurrentDrawAmps(); + + inputs.pivotPositionGoal = new Rotation2d(armFeedbackController.getGoal().position); + inputs.pivotPositionSetpoint = new Rotation2d(armFeedbackController.getSetpoint().position); + inputs.pivotPositionError = new Rotation2d(armFeedbackController.getPositionError()); + + inputs.rollerPosition = new Rotation2d(rollerMotorSim.getAngularPosition()); + inputs.rollerVelocityRadiansPerSecond = rollerMotorSim.getAngularVelocityRadPerSec(); + inputs.rollerAppliedVolts = rollerAppliedVoltage; + inputs.rollerSupplyCurrentAmps = rollerMotorSim.getCurrentDrawAmps(); + } + + @Override + public void setPivotVoltage(double voltage) { + isClosedLoop = false; + pivotAppliedVoltage = voltage; + } + + @Override + public void setRollerVoltage(double voltage) { + rollerAppliedVoltage = voltage; + } + + @Override + public void setPivotGoal(Rotation2d rotation) { + isClosedLoop = true; + armFeedbackController.setGoal(rotation.getRadians()); + } + + @Override + public void updateIntakeGains( + double kP, + double kD, + double kS, + double kV, + double kA, + double kG) { + armFeedbackController.setPID(kP, 0.0, kD); + armFeedforwardController.setKa(kA); + armFeedforwardController.setKs(kS); + armFeedforwardController.setKv(kV); + armFeedforwardController.setKg(kG); + } + + @Override + public void updateIntakeConstraints( + double maxVelocityRadiansPerSecond, + double maxAccelerationRadiansPerSecondSquared) { + armFeedbackController.setConstraints(new Constraints(maxVelocityRadiansPerSecond, maxAccelerationRadiansPerSecondSquared)); +} +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java new file mode 100644 index 00000000..94d6bb4b --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java @@ -0,0 +1,142 @@ +package frc.robot.subsystems.v3_Epsilon.intake; + +import static edu.wpi.first.units.Units.RadiansPerSecond; +import static edu.wpi.first.units.Units.RadiansPerSecondPerSecond; +import static frc.robot.util.PhoenixUtil.*; + +import com.ctre.phoenix6.BaseStatusSignal; +import com.ctre.phoenix6.Orchestra; +import com.ctre.phoenix6.StatusSignal; +import com.ctre.phoenix6.configs.MotionMagicConfigs; +import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.configs.TalonFXConfigurator; +import com.ctre.phoenix6.controls.MotionMagicVoltage; +import com.ctre.phoenix6.controls.NeutralOut; +import com.ctre.phoenix6.controls.VoltageOut; +import com.ctre.phoenix6.hardware.TalonFX; +import com.ctre.phoenix6.hardware.TalonFXS; +import com.ctre.phoenix6.hardware.core.CoreTalonFX; +import com.ctre.phoenix6.signals.GravityTypeValue; +import com.ctre.phoenix6.signals.InvertedValue; +import com.ctre.phoenix6.signals.NeutralModeValue; +import com.ctre.phoenix6.signals.StaticFeedforwardSignValue; +import com.ctre.phoenix6.sim.TalonFXSimState; + +import edu.wpi.first.units.measure.Angle; +import edu.wpi.first.units.measure.AngularAcceleration; +import edu.wpi.first.units.measure.AngularVelocity; +import edu.wpi.first.units.measure.Current; +import edu.wpi.first.units.measure.Temperature; +import edu.wpi.first.units.measure.Voltage; +import frc.robot.util.PhoenixUtil; + +public class V3_EpsilonIntakeIOTalonFX implements V3_EpsilonIntakeIO { + private final TalonFX pivotTalonFX; + + private final StatusSignal pivotPositionRotations; + private final StatusSignal pivotVelocityRotationsPerSecond; + private final StatusSignal pivotAppliedVoltage; + private final StatusSignal pivotSupplyCurrentAmps; + private final StatusSignal pivotTorqueCurrentAmps; + private final StatusSignal pivotTemperatureCelsius; + + private final VoltageOut pivotVoltageRequest; + private final MotionMagicVoltage pivotMotionMagicRequest; + + private final TalonFXConfiguration pivotConfig; + + + private final TalonFX rollerTalonFX; + + private final StatusSignal rollerPositionRotations; + private final StatusSignal rollerVelocityRotationsPerSecond; + private final StatusSignal rollerAppliedVoltage; + private final StatusSignal rollerSupplyCurrentAmps; + private final StatusSignal rollerTorqueCurrentAmps; + private final StatusSignal rollerTemperatureCelsius; + + private final VoltageOut rollerVoltageRequest; + private final NeutralOut rollerNeutralRequest; + + private final TalonFXConfiguration rollerConfig; + + + + public V3_EpsilonIntakeIOTalonFX() { + pivotTalonFX = new TalonFX(V3_EpsilonIntakeConstants.PIVOT_CAN_ID); + rollerTalonFX = new TalonFX(V3_EpsilonIntakeConstants.ROLLER_CAN_ID); + + pivotConfig = new TalonFXConfiguration(); + pivotConfig.CurrentLimits.SupplyCurrentLimitEnable = true; + pivotConfig.CurrentLimits.SupplyCurrentLimit = V3_EpsilonIntakeConstants.CURRENT_LIMITS.PIVOT_SUPPLY_CURRENT_LIMIT(); + pivotConfig.CurrentLimits.StatorCurrentLimitEnable = true; + pivotConfig.CurrentLimits.StatorCurrentLimit = V3_EpsilonIntakeConstants.CURRENT_LIMITS.PIVOT_STATOR_CURRENT_LIMIT(); + pivotConfig.Feedback.SensorToMechanismRatio = V3_EpsilonIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO(); + pivotConfig.SoftwareLimitSwitch.ForwardSoftLimitEnable = true; + pivotConfig.SoftwareLimitSwitch.ForwardSoftLimitThreshold = V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getRotations(); + pivotConfig.SoftwareLimitSwitch.ReverseSoftLimitEnable = true; + pivotConfig.SoftwareLimitSwitch.ReverseSoftLimitThreshold = V3_EpsilonIntakeConstants.PIVOT_PARAMS.MAX_ANGLE().getRotations(); + pivotConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; + pivotConfig.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive; + pivotConfig.Slot0 = new Slot0Configs().withGravityType(GravityTypeValue.Arm_Cosine) + .withKP(V3_EpsilonIntakeConstants.PIVOT_GAINS.kP()) + .withKD(V3_EpsilonIntakeConstants.PIVOT_GAINS.kD()) + .withKA(V3_EpsilonIntakeConstants.PIVOT_GAINS.kA()) + .withKV(V3_EpsilonIntakeConstants.PIVOT_GAINS.kV()) + .withKS(V3_EpsilonIntakeConstants.PIVOT_GAINS.kS()) + .withKG(V3_EpsilonIntakeConstants.PIVOT_GAINS.kG()); + pivotConfig.MotionMagic = new MotionMagicConfigs() + .withMotionMagicCruiseVelocity(AngularVelocity.ofRelativeUnits(V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.CRUISING_VELOCITY_RADIANS_PER_SECOND(), RadiansPerSecond)) + .withMotionMagicAcceleration(AngularAcceleration.ofRelativeUnits(V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED(), RadiansPerSecondPerSecond)); + + tryUntilOk(5, () -> pivotTalonFX.getConfigurator().apply(pivotConfig, 0.25)); + + pivotPositionRotations = pivotTalonFX.getPosition(); + pivotVelocityRotationsPerSecond = pivotTalonFX.getVelocity(); + pivotAppliedVoltage = pivotTalonFX.getSupplyVoltage(); + pivotSupplyCurrentAmps = pivotTalonFX.getSupplyCurrent(); + pivotTorqueCurrentAmps = pivotTalonFX.getTorqueCurrent(); + pivotTemperatureCelsius = pivotTalonFX.getDeviceTemp(); + + rollerConfig = new TalonFXConfiguration(); + rollerConfig.CurrentLimits.SupplyCurrentLimitEnable = true; + rollerConfig.CurrentLimits.SupplyCurrentLimit = V3_EpsilonIntakeConstants.CURRENT_LIMITS.ROLLER_SUPPLY_CURRENT_LIMIT(); + rollerConfig.CurrentLimits.StatorCurrentLimitEnable = true; + rollerConfig.CurrentLimits.StatorCurrentLimit = V3_EpsilonIntakeConstants.CURRENT_LIMITS.ROLLER_STATOR_CURRENT_LIMIT(); + rollerConfig.Feedback.SensorToMechanismRatio = V3_EpsilonIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO(); + rollerConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; + rollerConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; + + tryUntilOk(5, () -> rollerTalonFX.getConfigurator().apply(rollerConfig, 0.25)); + + rollerPositionRotations = pivotTalonFX.getPosition(); + rollerVelocityRotationsPerSecond = pivotTalonFX.getVelocity(); + rollerAppliedVoltage = pivotTalonFX.getSupplyVoltage(); + rollerSupplyCurrentAmps = pivotTalonFX.getSupplyCurrent(); + rollerTorqueCurrentAmps = pivotTalonFX.getTorqueCurrent(); + rollerTemperatureCelsius = pivotTalonFX.getDeviceTemp(); + + pivotVoltageRequest = new VoltageOut(0); + pivotMotionMagicRequest = new MotionMagicVoltage(V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getMeasure()); + + rollerVoltageRequest = new VoltageOut(0); + rollerNeutralRequest = new NeutralOut(); + + PhoenixUtil.registerSignals( + false, + pivotPositionRotations, + pivotVelocityRotationsPerSecond, + pivotAppliedVoltage, + pivotSupplyCurrentAmps, + pivotTorqueCurrentAmps, + pivotTemperatureCelsius, + rollerPositionRotations, + rollerVelocityRotationsPerSecond, + rollerAppliedVoltage, + rollerSupplyCurrentAmps, + rollerTorqueCurrentAmps, + rollerTemperatureCelsius); + } + +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java index 5f4eb257..5349612e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java @@ -1,147 +1,77 @@ package frc.robot.subsystems.v3_Epsilon.manipulator; +import static edu.wpi.first.units.Units.*; + import edu.wpi.first.math.MathUtil; -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; - -import java.util.function.BooleanSupplier; - -import org.littletonrobotics.junction.AutoLogOutput; -import org.littletonrobotics.junction.Logger; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; -import frc.robot.RobotState; import frc.robot.subsystems.v2_Redundancy.manipulator.V2_RedundancyManipulatorConstants; import frc.robot.subsystems.v2_Redundancy.manipulator.V2_RedundancyManipulatorConstants.ArmState; +import org.littletonrobotics.junction.AutoLogOutput; +import org.littletonrobotics.junction.Logger; public class V3_EpsilonManipulator extends SubsystemBase { private final V3_EpsilonManipulatorIO io; private final ManipulatorIOInputsAutoLogged inputs; - private final Timer currentTimer; - private Rotation2d previousPosition; - private Rotation2d desiredRotations; + private final SysIdRoutine algaeCharacterizationRoutine; + private ArmState state; private boolean isClosedLoop; public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { this.io = io; inputs = new ManipulatorIOInputsAutoLogged(); - currentTimer = new Timer(); - previousPosition = inputs.position; - desiredRotations = new Rotation2d(); - isClosedLoop = true; - algaeCharacterizationRoutine = + algaeCharacterizationRoutine = new SysIdRoutine( new SysIdRoutine.Config( Volts.of(0.2).per(Second), Volts.of(3.5), Seconds.of(5), (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), - new SysIdRoutine.Mechanism((volts) -> io.setVoltage(volts.in(Volts)), null, this)); + new SysIdRoutine.Mechanism((volts) -> io.setPivotVoltage(volts.in(Volts)), null, this)); + state = ArmState.STOW_DOWN; } @Override public void periodic() { io.updateInputs(inputs); Logger.processInputs("Manipulator", inputs); + + if (isClosedLoop) { + setSlot(); + io.setPivotGoal(state.getAngle()); + } + + if (hasAlgae()) { + io.setRollerVoltage(holdVoltage()); + } } @AutoLogOutput(key = "Manipulator/Has Coral") public boolean hasCoral() { - return Math.abs(inputs.torqueCurrentAmps) - > V3_EpsilonManipulatorConstants.MANIPULATOR_CURRENT_THRESHOLD; + return inputs.canRangeDistanceMeters < V3_EpsilonManipulatorConstants.CORAL_CAN_RANGE_THRESHOLD + && inputs.canRangeDistanceMeters > 0; } @AutoLogOutput(key = "Manipulator/Has Algae") public boolean hasAlgae() { - return Math.abs(inputs.torqueCurrentAmps) - > V3_EpsilonManipulatorConstants.MANIPULATOR_CURRENT_THRESHOLD; + return inputs.canRangeDistanceMeters < V3_EpsilonManipulatorConstants.ALGAE_CAN_RANGE_THRESHOLD + && inputs.canRangeDistanceMeters > 0; } - public Command runArmToPositionCommand( - Rotation2d position, - double maxVelocity, - double maxAcceleration, - BooleanSupplier isFinished) { + public Command runPivot(double volts) { return this.runEnd( () -> { - io.setArmPositionGoal(position); - isClosedLoop = true; - }, - () -> { - io.setArmPositionGoal(inputs.armPosition); isClosedLoop = false; + io.setPivotVoltage(volts); }, - isFinished); - } - public Command runManipulator(double volts) { - return this.runEnd(() -> io.setVoltage(volts), () -> io.setVoltage(0)); - } - - public Command intakeCoral(BooleanSupplier shouldStop) { - Command cmd = - Commands.sequence( - runManipulator( - V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.CORAL_INTAKE_VOLTS().get()) - .until(shouldStop)); - cmd.addRequirements(this); - return cmd; - } - - public Command intakeReefAlgae() { - return Commands.sequence( - Commands.parallel( - Commands.sequence( - Commands.waitUntil(() -> isIntakingAlgae()), - Commands.runOnce(() -> RobotState.setIntakingAlgae(true))), - runManipulator( - V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().get()))) - .finallyDo(() -> RobotState.setIntakingAlgae(false)); - } - - public Command intakeFloorAlgae() { - return Commands.sequence( - Commands.parallel( - Commands.sequence( - Commands.waitUntil(() -> isIntakingAlgae()), - Commands.runOnce(() -> RobotState.setIntakingAlgae(true))), - runManipulator( - V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().get()))) - .finallyDo(() -> RobotState.setIntakingAlgae(false)); - } - - public Command scoreCoral() { - return runManipulator( - V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.SCORE_CORAL_VOLTS().get()); - } - - public Command scoreAlgae() { - Command cmd = - runManipulator(V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.SCORE_ALGAE_VOLTS().get()); - cmd.addRequirements(this); - return cmd.finallyDo(() -> RobotState.setHasAlgae(false)); - } - - public Command scoreL1Coral() { - return runManipulator(V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.L1_VOLTS().get()); - } - - public Command scoreL4Coral() { - return runManipulator(V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.L4_VOLTS().get()); - } - - public Command halfScoreCoral() { - return runManipulator(V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.HALF_VOLTS().get()); - } - - public Command unHalfScoreCoral() { - return runManipulator(-V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.HALF_VOLTS().get()); + () -> io.setPivotVoltage(0)); } public Command sysIdRoutine() { @@ -156,7 +86,7 @@ public Command sysIdRoutine() { algaeCharacterizationRoutine.dynamic(Direction.kReverse)); } - public Command setAlgaeArmGoal(ArmState goal) { + public Command setPivotGoal(ArmState goal) { return this.runOnce( () -> { isClosedLoop = true; @@ -176,9 +106,16 @@ public void updateArmGains( double kS1, double kV1, double kA1, - double kG1) { + double kG1, + double kP2, + double kD2, + double kS2, + double kV2, + double kA2, + double kG2) { io.updateSlot0ArmGains(kP0, kD0, kS0, kV0, kA0, kG0); io.updateSlot1ArmGains(kP1, kD1, kS1, kV1, kA1, kG1); + io.updateSlot2ArmGains(kP2, kD2, kS2, kV2, kA2, kG2); } public void updateArmConstraints(double maxAcceleration, double maxVelocity) { @@ -186,25 +123,13 @@ public void updateArmConstraints(double maxAcceleration, double maxVelocity) { } @AutoLogOutput(key = "Manipulator/Arm At Goal") - public boolean algaeArmAtGoal() { + public boolean pivotAtGoal() { return inputs.armPosition.getRadians() - state.getAngle().getRadians() <= V2_RedundancyManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); } - public Command waitUntilAlgaeArmAtGoal() { - return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::algaeArmAtGoal)); - } - - public Command homingSequence() { - return Commands.sequence( - Commands.runOnce( - () -> { - isClosedLoop = false; - io.armMax(); - }), - Commands.runEnd(() -> io.setArmVoltage(-6), () -> io.setArmVoltage(0)) - .until(() -> Math.abs(inputs.armTorqueCurrentAmps) > 40), - Commands.runOnce(() -> io.zeroArmPosition())); + public Command waitUntilPivotAtGoal() { + return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::pivotAtGoal)); } private double holdVoltage() { @@ -220,5 +145,14 @@ private double holdVoltage() { 0.10, V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().get() / 1.5); } -} + + public void setSlot() { + if (hasAlgae()) { + io.setSlot(2); + } else if (hasCoral()) { + io.setSlot(1); + } else { + io.setSlot(0); + } + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java index 931b7f01..68d147b0 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java @@ -1,19 +1,21 @@ package frc.robot.subsystems.v3_Epsilon.manipulator; +import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.configs.SlotConfigs; +import com.ctre.phoenix6.signals.GravityTypeValue; + import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.util.Units; -import frc.robot.subsystems.shared.drive.DriveConstants; import frc.robot.subsystems.v2_Redundancy.manipulator.V2_RedundancyManipulatorConstants.ArmParameters; -import frc.robot.subsystems.v2_Redundancy.manipulator.V2_RedundancyManipulatorConstants.ManipulatorCurrentLimits; import frc.robot.util.LoggedTunableNumber; import lombok.RequiredArgsConstructor; public class V3_EpsilonManipulatorConstants { - public static final int ARM_CAN_ID = 31; public static final ArmParameters ARM_PARAMETERS; - public static final Gains WITHOUT_ALGAE_GAINS; - public static final Gains WITH_ALGAE_GAINS; + public static final Gains EMPTY_GAINS; + public static final Gains CORAL_GAINS; + public static final Gains ALGAE_GAINS; public static final Constraints CONSTRAINTS; public static final int ROLLER_CAN_ID; @@ -23,13 +25,15 @@ public class V3_EpsilonManipulatorConstants { public static final ManipulatorCurrentLimits CURRENT_LIMITS; - public static final int MANIPULATOR_CAN_ID = 42; - public static final double SUPPLY_CURRENT_LIMIT = 56; - public static final double MANIPULATOR_CURRENT_THRESHOLD = 23; - public static final Rotation2d MANIPULATOR_TOGGLE_ARM_ROTATION; - public static final Voltages VOLTAGES; + public static final int PIVOT_CAN_ID = 42; + public static final Rotation2d PIVOT_TOGGLE_ARM_ROTATION; + + public static final int CAN_RANGE_ID = 41; + + public static final double ALGAE_CAN_RANGE_THRESHOLD = 0.5; + public static final double CORAL_CAN_RANGE_THRESHOLD = 0.5; - static { + static { ARM_PARAMETERS = new ArmParameters( DCMotor.getKrakenX60Foc(1), @@ -38,7 +42,15 @@ public class V3_EpsilonManipulatorConstants { 1, 90.0, 0.5); - WITHOUT_ALGAE_GAINS = + EMPTY_GAINS = + new Gains( + new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 0), + new LoggedTunableNumber("Manipulator/Arm/Empty/kD", 0), + new LoggedTunableNumber("Manipulator/Arm/Empty/kS", 0), + new LoggedTunableNumber("Manipulator/Arm/Empty/kG", 0), + new LoggedTunableNumber("Manipulator/Arm/Empty/kV", 0), + new LoggedTunableNumber("Manipulator/Arm/Empty/kA", 0)); + CORAL_GAINS = new Gains( new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kP", 125), new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kD", 0), @@ -46,7 +58,7 @@ public class V3_EpsilonManipulatorConstants { new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kG", 0.66177), new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kV", 0.0), new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kA", 0.0)); - WITH_ALGAE_GAINS = + ALGAE_GAINS = new Gains( new LoggedTunableNumber("Manipulator/ArmWithAlgae/kP", 125), new LoggedTunableNumber("Manipulator/ArmWithAlgae/kD", 0), @@ -75,15 +87,9 @@ public class V3_EpsilonManipulatorConstants { new LoggedTunableNumber("Manipulator/L1 Volts", 3.5 * 1.56)); CURRENT_LIMITS = new ManipulatorCurrentLimits(40, 40, 40, 40); - } - public static final record Voltages( - LoggedTunableNumber INTAKE_VOLTS, - LoggedTunableNumber L4_VOLTS, - LoggedTunableNumber SCORE_VOLTS, - LoggedTunableNumber REMOVE_ALGAE, - LoggedTunableNumber HALF_VOLTS, - LoggedTunableNumber L1_VOLTS) {} + PIVOT_TOGGLE_ARM_ROTATION = new Rotation2d(); + } public static record Gains( LoggedTunableNumber kP, @@ -91,12 +97,18 @@ public static record Gains( LoggedTunableNumber kS, LoggedTunableNumber kG, LoggedTunableNumber kV, - LoggedTunableNumber kA) {} - - public static record Constraints( - LoggedTunableNumber maxAcceleration, - LoggedTunableNumber cruisingVelocity, - LoggedTunableNumber goalTolerance) {} + LoggedTunableNumber kA) { + public SlotConfigs toTalonFXSlotConfigs() { + return new SlotConfigs() + .withKP(kP.get()) + .withKD(kD.get()) + .withKS(kS.get()) + .withKG(kG.get()) + .withKV(kV.get()) + .withKA(kA.get()) + .withGravityType(GravityTypeValue.Arm_Cosine); + } + } public static final record ManipulatorCurrentLimits( double MANIPULATOR_SUPPLY_CURRENT_LIMIT, @@ -120,7 +132,7 @@ public static final record Voltages( LoggedTunableNumber L1_VOLTS) {} @RequiredArgsConstructor - public static enum ArmState { + public static enum PivotState { STOW_UP(Rotation2d.fromDegrees(75)), PRE_SCORE(Rotation2d.fromDegrees(50.0)), PROCESSOR(Rotation2d.fromDegrees(-61.279296875 + 20)), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java index 845942c5..7fc16cf8 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java @@ -1,34 +1,32 @@ package frc.robot.subsystems.v3_Epsilon.manipulator; -import org.littletonrobotics.junction.AutoLog; - import edu.wpi.first.math.geometry.Rotation2d; +import org.littletonrobotics.junction.AutoLog; public interface V3_EpsilonManipulatorIO { @AutoLog public static class ManipulatorIOInputs { public Rotation2d armPosition = new Rotation2d(); - public double velocityRadiansPerSecond = 0.0; - public double appliedVolts = 0.0; - public double supplyCurrentAmps = 0.0; - public double torqueCurrentAmps = 0.0; - public double temperatureCelsius = 0.0; - - + public double armVelocityRadiansPerSecond = 0.0; + public double armAppliedVolts = 0.0; + public double armSupplyCurrentAmps = 0.0; + public double armTorqueCurrentAmps = 0.0; + public double armTemperatureCelsius = 0.0; + public Rotation2d armPositionGoal = new Rotation2d(); public Rotation2d armPositionSetpoint = new Rotation2d(); public Rotation2d armPositionError = new Rotation2d(); + public Rotation2d rollerPosition = new Rotation2d(); - - public double rollerVelocityRadiansPerSecond = 0.0; - public double rollerAccelerationRadiansPerSecondSquared = 0.0; public double rollerAppliedVolts = 0.0; public double rollerSupplyCurrentAmps = 0.0; public double rollerTorqueCurrentAmps = 0.0; public double rollerTemperatureCelsius = 0.0; - } + + public double canRangeDistanceMeters = 0.0; + } /** * Updates the inputs for the manipulator subsystem. @@ -42,5 +40,38 @@ public default void updateInputs(ManipulatorIOInputs inputs) {} * * @param volts The voltage to set. */ - public default void setVoltage(double volts) {} + public default void setPivotVoltage(double volts) {} + + public default void setRollerVoltage(double volts) {} + + public default void setPivotGoal(Rotation2d rotation) {} + + /** + * Sets the gains for the arm. + * + * @param kP The proportional gain. + * @param kD The derivative gain. + * @param kS The static gain. + * @param kV The velocity gain. + * @param kA The acceleration gain. + * @param kG The gravity gain. + */ + public default void updateSlot0ArmGains( + double kP, double kD, double kS, double kV, double kA, double kG) {} + + public default void updateSlot1ArmGains( + double kP, double kD, double kS, double kV, double kA, double kG) {} + + public default void updateSlot2ArmGains( + double kP, double kD, double kS, double kV, double kA, double kG) {} + + /** + * Sets the constraints for the arm. + * + * @param maxAcceleration The maximum acceleration. + * @param cruisingVelocity The cruising velocity. + */ + public default void updateArmConstraints(double maxAcceleration, double cruisingVelocity) {} + + public default void setSlot(int slot) {} } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java index 405c461b..adf82a49 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java @@ -1,40 +1,134 @@ package frc.robot.subsystems.v3_Epsilon.manipulator; import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.controller.ArmFeedforward; +import edu.wpi.first.math.controller.ProfiledPIDController; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.system.plant.LinearSystemId; +import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints; import edu.wpi.first.wpilibj.simulation.DCMotorSim; +import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim; import frc.robot.Constants; public class V3_EpsilonManipulatorIOSim implements V3_EpsilonManipulatorIO { - private final DCMotorSim sim; + private final SingleJointedArmSim armMotorSim; + private final DCMotorSim rollerMotorSim; - private double appliedVolts; + private final ProfiledPIDController armFeedbackController; + private final ArmFeedforward armFeedforwardController; + + private double armAppliedVolts; + private double rollerAppliedVolts; + + private boolean isClosedLoop; public V3_EpsilonManipulatorIOSim() { - sim = + armMotorSim = + new SingleJointedArmSim( + LinearSystemId.createSingleJointedArmSystem( + V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MOTOR_CONFIG(), + 0.004, + V3_EpsilonManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO()), + V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MOTOR_CONFIG(), + V3_EpsilonManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO(), + V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS(), + V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MIN_ANGLE().getRadians(), + V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MAX_ANGLE().getRadians(), + true, + V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MIN_ANGLE().getRadians()); + rollerMotorSim = new DCMotorSim( LinearSystemId.createDCMotorSystem(DCMotor.getKrakenX60Foc(1), 0.004, 3.0), DCMotor.getKrakenX60Foc(1)); - appliedVolts = 0.0; + armFeedbackController = + new ProfiledPIDController( + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kP().get(), + 0.0, + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kD().get(), + new Constraints( + V3_EpsilonManipulatorConstants.CONSTRAINTS + .cruisingVelocityRotationsPerSecond() + .get(), + V3_EpsilonManipulatorConstants.CONSTRAINTS + .maxAccelerationRotationsPerSecondSquared() + .get())); + armFeedforwardController = + new ArmFeedforward( + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kS().get(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kG().get(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kV().get(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kA().get()); + + armAppliedVolts = 0.0; + rollerAppliedVolts = 0.0; + isClosedLoop = true; } @Override public void updateInputs(ManipulatorIOInputs inputs) { - appliedVolts = MathUtil.clamp(appliedVolts, -12.0, 12.0); + if (isClosedLoop) { + armAppliedVolts = + armFeedbackController.calculate( + armMotorSim.getAngleRads()) + + armFeedforwardController.calculate( + armMotorSim.getAngleRads(), armMotorSim.getVelocityRadPerSec()); + } + + armAppliedVolts = MathUtil.clamp(armAppliedVolts, -12.0, 12.0); + rollerAppliedVolts = MathUtil.clamp(rollerAppliedVolts, -12.0, 12.0); + + armMotorSim.setInputVoltage(armAppliedVolts); + armMotorSim.update(Constants.LOOP_PERIOD_SECONDS); + + rollerMotorSim.setInputVoltage(rollerAppliedVolts); + rollerMotorSim.update(Constants.LOOP_PERIOD_SECONDS); + + inputs.armPosition = Rotation2d.fromRadians(armMotorSim.getAngleRads()); + inputs.armVelocityRadiansPerSecond = armMotorSim.getVelocityRadPerSec(); + inputs.armAppliedVolts = armAppliedVolts; + inputs.armSupplyCurrentAmps = armMotorSim.getCurrentDrawAmps(); + + inputs.armPositionGoal = Rotation2d.fromRadians(armFeedbackController.getGoal().position); + inputs.armPositionSetpoint = + Rotation2d.fromRadians(armFeedbackController.getSetpoint().position); + inputs.armPositionError = + Rotation2d.fromRadians(armFeedbackController.getPositionError()); - sim.setInputVoltage(appliedVolts); - sim.update(Constants.LOOP_PERIOD_SECONDS); + inputs.rollerPosition = new Rotation2d(rollerMotorSim.getAngularPositionRad()); + inputs.rollerVelocityRadiansPerSecond = rollerMotorSim.getAngularVelocityRadPerSec(); + inputs.rollerAppliedVolts = rollerAppliedVolts; + inputs.rollerSupplyCurrentAmps = rollerMotorSim.getCurrentDrawAmps(); + } + + public void setPivotVoltage(double volts) { + isClosedLoop = false; + armAppliedVolts = volts; + } + + public void setRollerVoltage(double volts) { + rollerAppliedVolts = volts; + } + + public void setPivotGoal(Rotation2d rotation) { + isClosedLoop = true; + armFeedbackController.setGoal(rotation.getRadians()); + } - inputs.position = Rotation2d.fromRadians(sim.getAngularPositionRad()); - inputs.velocityRadiansPerSecond = sim.getAngularVelocityRadPerSec(); - inputs.appliedVolts = appliedVolts; - inputs.supplyCurrentAmps = sim.getCurrentDrawAmps(); + public void updateSlot0ArmGains( + double kP, double kD, double kS, double kV, double kA, double kG) { + armFeedbackController.setPID(kP, 0.0, kD); + armFeedforwardController.setKa(kA); + armFeedforwardController.setKs(kS); + armFeedforwardController.setKv(kV); + armFeedforwardController.setKg(kG); } - public void setVoltage(double volts) { - appliedVolts = volts; + public void updateArmConstraints( + double cruisingVelocityRotationsPerSecond, + double maxAccelerationRotationsPerSecondSquared) { + armFeedbackController.setConstraints( + new Constraints(cruisingVelocityRotationsPerSecond, maxAccelerationRotationsPerSecondSquared)); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java index 99046887..0ad181c4 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java @@ -1,10 +1,14 @@ package frc.robot.subsystems.v3_Epsilon.manipulator; +import static edu.wpi.first.units.Units.RadiansPerSecond; import static frc.robot.util.PhoenixUtil.*; -import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.StatusSignal; +import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.configs.Slot1Configs; +import com.ctre.phoenix6.configs.Slot2Configs; import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.controls.MotionMagicVoltage; import com.ctre.phoenix6.controls.VoltageOut; import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.InvertedValue; @@ -16,74 +20,156 @@ import edu.wpi.first.units.measure.Current; import edu.wpi.first.units.measure.Temperature; import edu.wpi.first.units.measure.Voltage; -import frc.robot.subsystems.v1_StackUp.manipulator.V1_StackUpManipulatorConstants; +// import frc.robot.subsystems.v1_StackUp.manipulator.V3_EpsilonManipulatorConstants; public class V3_EpsilonManipulatorIOTalonFX implements V3_EpsilonManipulatorIO { - private final TalonFX talonFX; - private final StatusSignal positionRotations; - private final StatusSignal velocityRotationsPerSecond; - private final StatusSignal appliedVoltage; - private final StatusSignal supplyCurrentAmps; - private final StatusSignal torqueCurrentAmps; - private final StatusSignal temperatureCelsius; - private final VoltageOut voltageRequest; - private final TalonFXConfiguration config; + private final TalonFX pivotTalonFX; + private final StatusSignal pivotPositionRotations; + private final StatusSignal pivotVelocityRotationsPerSecond; + private final StatusSignal pivotAppliedVoltage; + private final StatusSignal pivotSupplyCurrentAmps; + private final StatusSignal pivotTorqueCurrentAmps; + private final StatusSignal pivotTemperatureCelsius; + private final StatusSignal pivotPositionSetpointRotations; + private final StatusSignal pivotPositionErrorRotations; + + private final VoltageOut pivotVoltageRequest; + private final MotionMagicVoltage pivotMotionMagicRequest; + + private final TalonFXConfiguration pivotConfig; + + private final TalonFX rollerTalonFX; + private final StatusSignal rollerPositionRotations; + private final StatusSignal rollerVelocityRotationsPerSecond; + private final StatusSignal rollerAppliedVoltage; + private final StatusSignal rollerSupplyCurrentAmps; + private final StatusSignal rollerTorqueCurrentAmps; + private final StatusSignal rollerTemperatureCelsius; + + private final VoltageOut rollerVoltageRequest; + private final TalonFXConfiguration rollerConfig; public V3_EpsilonManipulatorIOTalonFX() { - talonFX = new TalonFX(V1_StackUpManipulatorConstants.MANIPULATOR_CAN_ID); + pivotTalonFX = new TalonFX(V3_EpsilonManipulatorConstants.PIVOT_CAN_ID); + rollerTalonFX = new TalonFX(V3_EpsilonManipulatorConstants.ROLLER_CAN_ID); + + pivotConfig = new TalonFXConfiguration(); - config = new TalonFXConfiguration(); + pivotConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; + pivotConfig.CurrentLimits.SupplyCurrentLimit = + V3_EpsilonManipulatorConstants.CURRENT_LIMITS.MANIPULATOR_SUPPLY_CURRENT_LIMIT(); + pivotConfig.CurrentLimits.SupplyCurrentLimitEnable = true; + pivotConfig.Feedback.SensorToMechanismRatio = + V3_EpsilonManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO(); + pivotConfig.Slot0 = + Slot0Configs.from(V3_EpsilonManipulatorConstants.EMPTY_GAINS.toTalonFXSlotConfigs()); + pivotConfig.Slot1 = + Slot1Configs.from(V3_EpsilonManipulatorConstants.CORAL_GAINS.toTalonFXSlotConfigs()); + pivotConfig.Slot2 = + Slot2Configs.from(V3_EpsilonManipulatorConstants.ALGAE_GAINS.toTalonFXSlotConfigs()); + pivotConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; - config.MotorOutput.NeutralMode = NeutralModeValue.Brake; - config.CurrentLimits.SupplyCurrentLimit = V1_StackUpManipulatorConstants.SUPPLY_CURRENT_LIMIT; - config.CurrentLimits.SupplyCurrentLimitEnable = true; - config.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; + tryUntilOk(5, () -> pivotTalonFX.getConfigurator().apply(pivotConfig, 0.25)); - tryUntilOk(5, () -> talonFX.getConfigurator().apply(config, 0.25)); + pivotPositionRotations = pivotTalonFX.getPosition(); + pivotVelocityRotationsPerSecond = pivotTalonFX.getVelocity(); + pivotAppliedVoltage = pivotTalonFX.getMotorVoltage(); + pivotSupplyCurrentAmps = pivotTalonFX.getSupplyCurrent(); + pivotTorqueCurrentAmps = pivotTalonFX.getTorqueCurrent(); + pivotTemperatureCelsius = pivotTalonFX.getDeviceTemp(); - positionRotations = talonFX.getPosition(); - velocityRotationsPerSecond = talonFX.getVelocity(); - appliedVoltage = talonFX.getMotorVoltage(); - supplyCurrentAmps = talonFX.getSupplyCurrent(); - torqueCurrentAmps = talonFX.getTorqueCurrent(); - temperatureCelsius = talonFX.getDeviceTemp(); + pivotPositionSetpointRotations = pivotTalonFX.getClosedLoopReference(); + pivotPositionErrorRotations = pivotTalonFX.getClosedLoopError(); - voltageRequest = new VoltageOut(0); + rollerConfig = new TalonFXConfiguration(); + rollerConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; + rollerConfig.CurrentLimits.SupplyCurrentLimit = + V3_EpsilonManipulatorConstants.CURRENT_LIMITS.ROLLER_SUPPLY_CURRENT_LIMIT(); + rollerConfig.CurrentLimits.SupplyCurrentLimitEnable = true; - BaseStatusSignal.setUpdateFrequencyForAll( - 50.0, - positionRotations, - velocityRotationsPerSecond, - appliedVoltage, - supplyCurrentAmps, - torqueCurrentAmps, - temperatureCelsius); + tryUntilOk(5, () -> rollerTalonFX.getConfigurator().apply(rollerConfig, 0.25)); - talonFX.optimizeBusUtilization(); + rollerPositionRotations = rollerTalonFX.getPosition(); + rollerVelocityRotationsPerSecond = rollerTalonFX.getVelocity(); + rollerAppliedVoltage = rollerTalonFX.getMotorVoltage(); + rollerSupplyCurrentAmps = rollerTalonFX.getSupplyCurrent(); + rollerTorqueCurrentAmps = rollerTalonFX.getTorqueCurrent(); + rollerTemperatureCelsius = rollerTalonFX.getDeviceTemp(); + + rollerVoltageRequest = new VoltageOut(0); + pivotVoltageRequest = new VoltageOut(0); + pivotMotionMagicRequest = new MotionMagicVoltage(0); + + registerSignals( + false, + pivotPositionRotations, + pivotVelocityRotationsPerSecond, + pivotAppliedVoltage, + pivotSupplyCurrentAmps, + pivotTorqueCurrentAmps, + pivotTemperatureCelsius, + rollerPositionRotations, + rollerVelocityRotationsPerSecond, + rollerAppliedVoltage, + rollerSupplyCurrentAmps, + rollerTorqueCurrentAmps, + rollerTemperatureCelsius); + + pivotTalonFX.optimizeBusUtilization(); + rollerTalonFX.optimizeBusUtilization(); } @Override public void updateInputs(ManipulatorIOInputs inputs) { - BaseStatusSignal.refreshAll( - positionRotations, - velocityRotationsPerSecond, - appliedVoltage, - supplyCurrentAmps, - torqueCurrentAmps, - temperatureCelsius); - - inputs.position = Rotation2d.fromRotations(positionRotations.getValueAsDouble()); - inputs.velocityRadiansPerSecond = - Units.rotationsToRadians(velocityRotationsPerSecond.getValueAsDouble()); - inputs.appliedVolts = appliedVoltage.getValueAsDouble(); - inputs.supplyCurrentAmps = supplyCurrentAmps.getValueAsDouble(); - inputs.torqueCurrentAmps = torqueCurrentAmps.getValueAsDouble(); - inputs.temperatureCelsius = temperatureCelsius.getValueAsDouble(); + + inputs.armPosition = new Rotation2d(pivotPositionRotations.getValue()); + inputs.armVelocityRadiansPerSecond = + pivotVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); + inputs.armAppliedVolts = pivotAppliedVoltage.getValueAsDouble(); + inputs.armSupplyCurrentAmps = pivotSupplyCurrentAmps.getValueAsDouble(); + inputs.armTorqueCurrentAmps = pivotTorqueCurrentAmps.getValueAsDouble(); + inputs.armTemperatureCelsius = pivotTemperatureCelsius.getValueAsDouble(); + + inputs.rollerPosition = new Rotation2d(rollerPositionRotations.getValue()); + inputs.rollerVelocityRadiansPerSecond = + Units.rotationsToRadians(rollerVelocityRotationsPerSecond.getValueAsDouble()); + inputs.rollerAppliedVolts = rollerAppliedVoltage.getValueAsDouble(); + inputs.rollerSupplyCurrentAmps = rollerSupplyCurrentAmps.getValueAsDouble(); + inputs.rollerTorqueCurrentAmps = rollerTorqueCurrentAmps.getValueAsDouble(); + inputs.rollerTemperatureCelsius = rollerTemperatureCelsius.getValueAsDouble(); + + inputs.armPositionGoal = new Rotation2d(pivotMotionMagicRequest.getPositionMeasure()); + inputs.armPositionSetpoint = + Rotation2d.fromRotations(pivotPositionSetpointRotations.getValueAsDouble()); + inputs.armPositionError = + Rotation2d.fromRotations(pivotPositionErrorRotations.getValueAsDouble()); + } + + @Override + public void setPivotVoltage(double volts) { + pivotTalonFX.setControl(pivotVoltageRequest.withOutput(volts).withEnableFOC(true)); + } + + @Override + public void setRollerVoltage(double volts) { + rollerTalonFX.setControl(rollerVoltageRequest.withOutput(volts).withEnableFOC(true)); + } + + @Override + public void setPivotGoal(Rotation2d rotation) { + pivotTalonFX.setControl( + pivotMotionMagicRequest + .withPosition(rotation.getRotations()) + .withEnableFOC(true)); } @Override - public void setVoltage(double volts) { - talonFX.setControl(voltageRequest.withOutput(volts).withEnableFOC(true)); + public void setSlot(int slot) { + if (slot >= 0 && slot <= 2) { + pivotTalonFX.setControl(pivotMotionMagicRequest.withSlot(slot)); + } else { + throw new IllegalArgumentException("Invalid slot: " + slot); + } } } diff --git a/vendordeps/Phoenix6-25.3.2.json b/vendordeps/Phoenix6-25.3.2.json deleted file mode 100644 index 368e61cb..00000000 --- a/vendordeps/Phoenix6-25.3.2.json +++ /dev/null @@ -1,449 +0,0 @@ -{ - "fileName": "Phoenix6-25.3.2.json", - "name": "CTRE-Phoenix (v6)", - "version": "25.3.2", - "frcYear": "2025", - "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", - "mavenUrls": [ - "https://maven.ctr-electronics.com/release/" - ], - "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json", - "conflictsWith": [ - { - "uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af", - "errorMessage": "Users can not have both the replay and regular Phoenix 6 vendordeps in their robot program.", - "offlineFileName": "Phoenix6-replay-frc2025-latest.json" - } - ], - "javaDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "wpiapi-java", - "version": "25.3.2" - } - ], - "jniDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "api-cpp", - "version": "25.3.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6", - "artifactId": "tools", - "version": "25.3.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "api-cpp-sim", - "version": "25.3.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "tools-sim", - "version": "25.3.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonSRX", - "version": "25.3.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simVictorSPX", - "version": "25.3.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simPigeonIMU", - "version": "25.3.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simCANCoder", - "version": "25.3.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFX", - "version": "25.3.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFXS", - "version": "25.3.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANcoder", - "version": "25.3.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProPigeon2", - "version": "25.3.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANrange", - "version": "25.3.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANdi", - "version": "25.3.2", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - } - ], - "cppDependencies": [ - { - "groupId": "com.ctre.phoenix6", - "artifactId": "wpiapi-cpp", - "version": "25.3.2", - "libName": "CTRE_Phoenix6_WPI", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6", - "artifactId": "tools", - "version": "25.3.2", - "libName": "CTRE_PhoenixTools", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "wpiapi-cpp-sim", - "version": "25.3.2", - "libName": "CTRE_Phoenix6_WPISim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "tools-sim", - "version": "25.3.2", - "libName": "CTRE_PhoenixTools_Sim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simTalonSRX", - "version": "25.3.2", - "libName": "CTRE_SimTalonSRX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simVictorSPX", - "version": "25.3.2", - "libName": "CTRE_SimVictorSPX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simPigeonIMU", - "version": "25.3.2", - "libName": "CTRE_SimPigeonIMU", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simCANCoder", - "version": "25.3.2", - "libName": "CTRE_SimCANCoder", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFX", - "version": "25.3.2", - "libName": "CTRE_SimProTalonFX", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProTalonFXS", - "version": "25.3.2", - "libName": "CTRE_SimProTalonFXS", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANcoder", - "version": "25.3.2", - "libName": "CTRE_SimProCANcoder", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProPigeon2", - "version": "25.3.2", - "libName": "CTRE_SimProPigeon2", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANrange", - "version": "25.3.2", - "libName": "CTRE_SimProCANrange", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix6.sim", - "artifactId": "simProCANdi", - "version": "25.3.2", - "libName": "CTRE_SimProCANdi", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxarm64", - "osxuniversal" - ], - "simMode": "swsim" - } - ] -} From 199d927561c6d33d8d7af8c8e750b3975462a785 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Fri, 1 Aug 2025 18:19:12 -0400 Subject: [PATCH 005/180] Merge branch 'main' into feature-v3 --- src/main/java/frc/robot/Robot.java | 1 - .../frc/robot/commands/CompositeCommands.java | 792 +++++++++--------- .../V2_RedundancyCompositeCommands.java | 652 -------------- .../v3_Epsilon/intake/V3_EpsilonIntake.java | 125 ++- .../intake/V3_EpsilonIntakeConstants.java | 106 +-- .../v3_Epsilon/intake/V3_EpsilonIntakeIO.java | 1 - .../intake/V3_EpsilonIntakeIOSim.java | 24 +- .../intake/V3_EpsilonIntakeIOTalonFX.java | 218 ++--- .../manipulator/V3_EpsilonManipulator.java | 17 +- .../V3_EpsilonManipulatorConstants.java | 33 +- .../V3_EpsilonManipulatorIOSim.java | 15 +- .../V3_EpsilonManipulatorIOTalonFX.java | 4 +- 12 files changed, 672 insertions(+), 1316 deletions(-) delete mode 100644 src/main/java/frc/robot/commands/V2_RedundancyCompositeCommands.java diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 28a693ed..e6d08f36 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -11,7 +11,6 @@ import edu.wpi.first.wpilibj.Watchdog; import edu.wpi.first.wpilibj.livewindow.LiveWindow; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; -import edu.wpi.first.wpilibj.simulation.BatterySim; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; import frc.robot.FieldConstants.Reef.ReefState; diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index ebfb5421..ac5b808a 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -5,28 +5,39 @@ import edu.wpi.first.math.kinematics.ChassisSpeeds; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; -import frc.robot.FieldConstants.Reef.ReefHeight; import frc.robot.FieldConstants.Reef.ReefPose; +import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotState; import frc.robot.subsystems.shared.climber.Climber; import frc.robot.subsystems.shared.climber.ClimberConstants; import frc.robot.subsystems.shared.drive.Drive; -import frc.robot.subsystems.shared.elevator.Elevator; +import frc.robot.subsystems.shared.elevator.Elevator.ElevatorCSB; +import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions; -import frc.robot.subsystems.shared.funnel.Funnel; +import frc.robot.subsystems.shared.funnel.Funnel.FunnelCSB; import frc.robot.subsystems.shared.funnel.FunnelConstants.FunnelState; -import frc.robot.subsystems.shared.vision.Camera; +import frc.robot.subsystems.shared.visionlimelight.Camera; import frc.robot.subsystems.v1_StackUp.manipulator.V1_StackUpManipulator; -import frc.robot.subsystems.v2_Redundancy.intake.V2_RedundancyIntake; -import frc.robot.subsystems.v2_Redundancy.intake.V2_RedundancyIntakeConstants.IntakeState; -import frc.robot.subsystems.v2_Redundancy.manipulator.V2_RedundancyManipulator; -import frc.robot.subsystems.v2_Redundancy.manipulator.V2_RedundancyManipulatorConstants.ArmState; +import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructure; +import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; +import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; +import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; import frc.robot.util.AllianceFlipUtil; import java.util.function.BooleanSupplier; import java.util.function.Supplier; +/** + * A class that holds composite commands, which are sequences of commands for complex robot actions. + */ public class CompositeCommands { + /** A class that holds composite commands that are shared across different robot versions. */ public static final class SharedCommands { + /** + * Creates a command to reset the robot's heading to the alliance-specific zero. + * + * @param drive The drive subsystem. + * @return A command to reset the heading. + */ public static final Command resetHeading(Drive drive) { return Commands.runOnce( () -> { @@ -38,64 +49,83 @@ public static final Command resetHeading(Drive drive) { .ignoringDisable(true); } - public static final Command climb( - Elevator elevator, Funnel funnel, Climber climber, Drive drive) { - return Commands.sequence( - elevator.setPosition(() -> ReefHeight.STOW), - Commands.waitSeconds(0.02), - Commands.waitUntil(elevator::atGoal), - funnel.setClapDaddyGoal(FunnelState.CLIMB), - Commands.parallel( - climber.releaseClimber(), - Commands.waitSeconds(ClimberConstants.WAIT_AFTER_RELEASE_SECONDS)), - Commands.waitUntil(climber::climberReady), - Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); - } - - public static final Command setStaticReefHeight(ReefHeight height) { + /** + * Creates a command to set a static reef height in the robot state. This does not move any + * mechanisms. + * + * @param height The reef height to set. + * @return A command to set the reef height. + */ + public static final Command setStaticReefHeight(ReefState height) { return Commands.runOnce(() -> RobotState.setReefHeight(height)); } - - public static final Command setDynamicReefHeight(ReefHeight height, Elevator elevator) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setReefHeight(height)), elevator.setPosition()); - } } + /** A class that holds composite commands for the V1_StackUp robot. */ public static final class V1_StackUpCompositeCommands { + /** + * Creates a command to intake coral from the station. + * + * @param elevator The elevator subsystem. + * @param funnel The funnel subsystem. + * @param manipulator The manipulator subsystem. + * @return A command to intake coral. + */ public static final Command intakeCoral( - Elevator elevator, Funnel funnel, V1_StackUpManipulator manipulator) { + ElevatorCSB elevator, FunnelCSB funnel, V1_StackUpManipulator manipulator) { return Commands.sequence( Commands.runOnce(() -> RobotState.setIntakingCoral(true)), - elevator.setPosition(() -> ReefHeight.CORAL_INTAKE), + elevator.setPosition(() -> ReefState.CORAL_INTAKE), Commands.waitUntil(elevator::atGoal), Commands.race( manipulator.intakeCoral(), funnel.intakeCoral(() -> manipulator.hasCoral()))) .finallyDo(() -> RobotState.setIntakingCoral(false)); } + /** + * Creates a command to intake coral from the station with an override. + * + * @param elevator The elevator subsystem. + * @param funnel The funnel subsystem. + * @param manipulator The manipulator subsystem. + * @return A command to intake coral with an override. + */ public static final Command intakeCoralOverride( - Elevator elevator, Funnel funnel, V1_StackUpManipulator manipulator) { + ElevatorCSB elevator, FunnelCSB funnel, V1_StackUpManipulator manipulator) { return Commands.sequence( Commands.runOnce(() -> RobotState.setIntakingCoral(true)), - elevator.setPosition(() -> ReefHeight.CORAL_INTAKE), + elevator.setPosition(() -> ReefState.CORAL_INTAKE), Commands.waitUntil(elevator::atGoal), Commands.parallel(manipulator.intakeCoral(), funnel.intakeCoral(() -> false))) .finallyDo(() -> RobotState.setIntakingCoral(false)); } + /** + * Creates a command to score coral. + * + * @param manipulator The manipulator subsystem. + * @return A command to score coral. + */ public static final Command scoreCoral(V1_StackUpManipulator manipulator) { return manipulator.scoreCoral().withTimeout(0.4); } + /** + * Creates a command sequence to score coral, waiting for auto-alignment. + * + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param autoAligned A supplier that returns true when the robot is aligned. + * @return A command sequence to score coral. + */ public static final Command scoreCoralSequence( - Elevator elevator, V1_StackUpManipulator manipulator, BooleanSupplier autoAligned) { + ElevatorCSB elevator, V1_StackUpManipulator manipulator, BooleanSupplier autoAligned) { return Commands.sequence( Commands.either( - elevator.setPosition(() -> ReefHeight.L3), + elevator.setPosition(() -> ReefState.L3), elevator.setPosition(), () -> - RobotState.getOIData().currentReefHeight().equals(ReefHeight.L4) + RobotState.getOIData().currentReefHeight().equals(ReefState.L4) && !elevator.getPosition().equals(ElevatorPositions.L4)), Commands.waitUntil(() -> autoAligned.getAsBoolean()), elevator.setPosition(), @@ -104,23 +134,32 @@ public static final Command scoreCoralSequence( Commands.either( manipulator.scoreL4Coral().withTimeout(0.4), manipulator.scoreCoral().withTimeout(0.15), - () -> RobotState.getOIData().currentReefHeight().equals(ReefHeight.L4))); - } - + () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L4))); + } + + /** + * Creates a command sequence to automatically score coral. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param cameras The vision cameras. + * @return A command sequence to auto-score coral. + */ public static final Command autoScoreCoralSequence( - Drive drive, Elevator elevator, V1_StackUpManipulator manipulator, Camera... cameras) { + Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { return Commands.either( autoScoreL1CoralSequence(drive, elevator, manipulator, cameras), Commands.sequence( Commands.either( - elevator.setPosition(() -> ReefHeight.L2), + elevator.setPosition(() -> ReefState.L2), Commands.none(), () -> - RobotState.getOIData().currentReefHeight().equals(ReefHeight.L1) - || RobotState.getOIData().currentReefHeight().equals(ReefHeight.STOW) + RobotState.getOIData().currentReefHeight().equals(ReefState.L1) + || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) || RobotState.getOIData() .currentReefHeight() - .equals(ReefHeight.CORAL_INTAKE)), + .equals(ReefState.CORAL_INTAKE)), Commands.parallel( DriveCommands.autoAlignReefCoral(drive, cameras), scoreCoralSequence( @@ -128,23 +167,40 @@ public static final Command autoScoreCoralSequence( manipulator, () -> RobotState.getReefAlignData().atCoralSetpoint())), elevator - .setPosition(() -> ReefHeight.STOW) + .setPosition(() -> ReefState.STOW) .onlyIf( () -> elevator.getPosition().equals(ElevatorPositions.L3) || elevator.getPosition().equals(ElevatorPositions.L2))), - () -> RobotState.getOIData().currentReefHeight().equals(ReefHeight.L1)); - } - + () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); + } + + /** + * Creates a command sequence to automatically score coral at L1. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param cameras The vision cameras. + * @return A command sequence to auto-score coral at L1. + */ public static final Command autoScoreL1CoralSequence( - Drive drive, Elevator elevator, V1_StackUpManipulator manipulator, Camera... cameras) { + Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { return Commands.sequence( DriveCommands.autoAlignReefCoral(drive, cameras), scoreL1Coral(drive, elevator, manipulator)); } + /** + * Creates a command to score coral at L1. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @return A command to score coral at L1. + */ public static final Command scoreL1Coral( - Drive drive, Elevator elevator, V1_StackUpManipulator manipulator) { + Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator) { return Commands.sequence( elevator.setPosition(), Commands.waitSeconds(0.02), @@ -159,18 +215,35 @@ public static final Command scoreL1Coral( () -> RobotState.getOIData().currentReefPost() == ReefPose.LEFT)))); } + /** + * Creates a command for an emergency eject of coral. + * + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @return A command to eject coral. + */ public static final Command emergencyEject( - Elevator elevator, V1_StackUpManipulator manipulator) { + ElevatorCSB elevator, V1_StackUpManipulator manipulator) { return Commands.sequence( - elevator.setPosition(() -> ReefHeight.L1), + elevator.setPosition(() -> ReefState.L1), Commands.waitSeconds(0.125), Commands.waitUntil(elevator::atGoal), manipulator.scoreCoral().withTimeout(0.4), - elevator.setPosition(() -> ReefHeight.STOW)); - } - + elevator.setPosition(() -> ReefState.STOW)); + } + + /** + * Creates a command to remove algae from the reef. This uses the closest reef tag to + * automatically pick the reef height. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param cameras The vision cameras. + * @return A command to remove algae. + */ public static final Command twerk( - Drive drive, Elevator elevator, V1_StackUpManipulator manipulator, Camera... cameras) { + Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { return Commands.deferredProxy( () -> twerk( @@ -178,22 +251,31 @@ public static final Command twerk( elevator, manipulator, switch (RobotState.getReefAlignData().closestReefTag()) { - case 10, 6, 8, 21, 17, 19 -> ReefHeight.ASS_BOT; - case 9, 11, 7, 22, 20, 18 -> ReefHeight.ASS_TOP; - default -> ReefHeight.ASS_BOT; + case 10, 6, 8, 21, 17, 19 -> ReefState.ASS_BOT; + case 9, 11, 7, 22, 20, 18 -> ReefState.ASS_TOP; + default -> ReefState.ASS_BOT; }, cameras)); } + /** + * Creates a command to remove algae from the reef. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param cameras The vision cameras. + * @return A command to remove algae. + */ public static final Command twerk( Drive drive, - Elevator elevator, + ElevatorCSB elevator, V1_StackUpManipulator manipulator, - ReefHeight level, + ReefState level, Camera... cameras) { return Commands.sequence( DriveCommands.autoAlignReefAlgae(drive, cameras), - elevator.setPosition(() -> ReefHeight.L4), + elevator.setPosition(() -> ReefState.L4), Commands.waitUntil(elevator::atGoal), manipulator.toggleAlgaeArm(), Commands.waitSeconds(0.1), @@ -202,408 +284,368 @@ public static final Command twerk( manipulator.removeAlgae().withTimeout(0.35), manipulator.toggleAlgaeArm()); } - } - public static final class V2_RedundancyCompositeCommands { - public static final Command intakeCoralAuto( - Elevator elevator, - Funnel funnel, - V2_RedundancyManipulator manipulator, - V2_RedundancyIntake intake) { + /** + * Creates a command to set the dynamic reef height in the robot state. This sets the height and + * then moves the elevator to that position. + * + * @param height The reef height to set. + * @param elevator The elevator subsystem. + * @return A command to set the dynamic reef height. + */ + public static final Command setDynamicReefHeight(ReefState height, ElevatorCSB elevator) { return Commands.sequence( - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - Commands.runOnce(() -> RobotState.setIntakingCoral(true)), - Commands.parallel( - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.CORAL_INTAKE, - ArmState.STOW_DOWN, - IntakeState.STOW)), - Commands.race( - manipulator.intakeCoral(() -> intake.hasCoral()), - funnel.intakeCoral(() -> manipulator.hasCoral()))) - .finallyDo(() -> RobotState.setIntakingCoral(false)); + Commands.runOnce(() -> RobotState.setReefHeight(height)), elevator.setPosition()); } - public static final Command intakeCoralDriverSequence( - Elevator elevator, - Funnel funnel, - V2_RedundancyManipulator manipulator, - V2_RedundancyIntake intake) { + /** + * Creates a command to climb the robot. + * + * @param elevator The elevator subsystem. + * @param funnel The funnel subsystem. + * @param climber The climber subsystem. + * @param drive The drive subsystem. + * @return A command to climb. + */ + public static final Command climb( + ElevatorCSB elevator, FunnelCSB funnel, Climber climber, Drive drive) { return Commands.sequence( - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - Commands.runOnce(() -> RobotState.setIntakingCoral(true)), - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.CORAL_INTAKE, - ArmState.STOW_DOWN, - IntakeState.STOW), - Commands.race( - manipulator.intakeCoral(() -> intake.hasCoral()), - funnel.intakeCoral(() -> intake.hasCoral())) - .until(intake::hasCoral)) - .finallyDo(() -> RobotState.setIntakingCoral(false)); + elevator.setPosition(() -> ReefState.STOW), + Commands.waitSeconds(0.02), + Commands.waitUntil(elevator::atGoal), + funnel.setClapDaddyGoal(FunnelState.CLIMB), + Commands.parallel( + climber.releaseClimber(), + Commands.waitSeconds( + ClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), + Commands.waitUntil(climber::climberReady), + Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); } + } + public static final class V2_RedundancyCompositeCommands { + /** + * Creates a command to intake coral from the station. + * + * @param superstructure The superstructure subsystem. + * @param intake The intake subsystem. + * @return A command to intake coral. + */ + public static final Command intakeCoralDriverSequence( + V2_RedundancySuperstructure superstructure, V2_RedundancyIntake intake) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoalUntil( + V2_RedundancySuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); + } + + /** + * Creates a command to intake coral from the station using the operator sequence. + * + * @param superstructure The superstructure subsystem. + * @param intake The intake subsystem. + * @return A command to intake coral using the operator sequence. + */ public static final Command intakeCoralOperatorSequence( - Elevator elevator, - Funnel funnel, - V2_RedundancyManipulator manipulator, - V2_RedundancyIntake intake) { + V2_RedundancySuperstructure superstructure, V2_RedundancyIntake intake) { return Commands.sequence( - Commands.runOnce(() -> RobotState.setIntakingCoral(true)), - Commands.parallel( - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.CORAL_INTAKE, - ArmState.STOW_DOWN, - IntakeState.STOW)), - Commands.parallel( - manipulator.intakeCoral(() -> false), funnel.intakeCoral(() -> false))) - .until(intake::hasCoral) - .finallyDo(() -> RobotState.setIntakingCoral(false)); - } - - public static final Command intakeCoralOperatorOverrideSequence( - Elevator elevator, - Funnel funnel, - V2_RedundancyManipulator manipulator, - V2_RedundancyIntake intake) { - return funnel.setClapDaddyGoal(FunnelState.CLOSED); - } - - public static final Command scoreCoral(V2_RedundancyManipulator manipulator) { - return manipulator.scoreCoral().withTimeout(0.4); - } - + superstructure.runGoalUntil( + V2_RedundancySuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); + } + + /** + * Creates a command to score coral at L1. + * + * @param drive The drive subsystem. + * @param superstructure The superstructure subsystem. + * @return A command to score coral at L1. + */ public static final Command scoreL1Coral( - Drive drive, - Elevator elevator, - V2_RedundancyManipulator manipulator, - V2_RedundancyIntake intake) { + Drive drive, V2_RedundancySuperstructure superstructure) { return Commands.sequence( - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> RobotState.getOIData().currentReefHeight(), - ArmState.STOW_DOWN, - IntakeState.STOW), + superstructure.runGoal(V2_RedundancySuperstructureStates.L1), Commands.parallel( - manipulator.scoreL1Coral().withTimeout(0.8), + superstructure.runReefScoreGoal(() -> ReefState.L1), Commands.sequence( Commands.waitSeconds(0.05), Commands.either( DriveCommands.inchMovement(drive, -1, 0.1), DriveCommands.inchMovement(drive, 1, 0.1), - () -> RobotState.getOIData().currentReefPost() == ReefPose.LEFT)), - intake.setExtensionGoal(IntakeState.L1_EXT))); + () -> RobotState.getOIData().currentReefPost() == ReefPose.LEFT)))); } + /** + * Creates a command sequence to score coral at L1, waiting for auto-alignment. + * + * @param drive The drive subsystem. + * @param superstructure The superstructure subsystem. + * @return A command sequence to score coral at L1. + */ public static final Command autoScoreL1CoralSequence( Drive drive, - Elevator elevator, - V2_RedundancyManipulator manipulator, - V2_RedundancyIntake intake, + ElevatorFSM elevator, + V2_RedundancySuperstructure superstructure, Camera... cameras) { return Commands.sequence( - DriveCommands.autoAlignReefCoral(drive, cameras), - scoreL1Coral(drive, elevator, manipulator, intake)) - .finallyDo( - () -> { - elevator.setPosition(() -> ReefHeight.STOW); - manipulator.setAlgaeArmGoal(ArmState.STOW_DOWN); - intake.setExtensionGoal(IntakeState.STOW); - }); - } - - public static final Command postL1Score( - Elevator elevator, V2_RedundancyManipulator manipulator, V2_RedundancyIntake intake) { - return Commands.sequence( - elevator.setPosition(() -> ReefHeight.STOW), - manipulator.setAlgaeArmGoal(ArmState.STOW_DOWN), - intake.setExtensionGoal(IntakeState.STOW)); + DriveCommands.autoAlignReefCoral(drive, cameras), scoreL1Coral(drive, superstructure)); } + /** + * Creates a command sequence to score coral, waiting for auto-alignment. + * + * @param elevator The elevator subsystem. + * @param superstructure The superstructure subsystem. + * @param autoAligned A supplier that returns true when the robot is aligned. + * @return A command sequence to score coral. + */ public static final Command scoreCoralSequence( - Elevator elevator, - V2_RedundancyManipulator manipulator, - V2_RedundancyIntake intake, + ElevatorFSM elevator, + V2_RedundancySuperstructure superstructure, BooleanSupplier autoAligned) { return Commands.sequence( Commands.either( - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.L3, - ArmState.STOW_DOWN, - IntakeState.STOW), - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> RobotState.getOIData().currentReefHeight(), - ArmState.STOW_DOWN, - IntakeState.STOW), + superstructure.runGoal(V2_RedundancySuperstructureStates.L3), + superstructure.runReefGoal(() -> RobotState.getOIData().currentReefHeight()), () -> - RobotState.getOIData().currentReefHeight().equals(ReefHeight.L4) - && !elevator.getPosition().equals(ElevatorPositions.L4)), + RobotState.getOIData().currentReefHeight().equals(ReefState.L4) + && !superstructure + .getCurrentState() + .equals(V2_RedundancySuperstructureStates.L4)), Commands.waitUntil(() -> autoAligned.getAsBoolean()), - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> RobotState.getOIData().currentReefHeight(), - ArmState.STOW_DOWN, - IntakeState.STOW), - Commands.parallel( - Commands.either( - manipulator.scoreL4Coral().withTimeout(0.4), - manipulator.scoreCoral().withTimeout(0.15), - () -> RobotState.getOIData().currentReefHeight().equals(ReefHeight.L4))), - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.STOW, - ArmState.STOW_DOWN, - IntakeState.STOW) + superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight()), + superstructure + .runGoal(V2_RedundancySuperstructureStates.STOW_DOWN) .onlyIf( () -> elevator.getPosition().equals(ElevatorPositions.L3) || elevator.getPosition().equals(ElevatorPositions.L2))); } + /** + * Creates a command sequence to automatically score coral. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param superstructure The superstructure subsystem. + * @param cameras The vision cameras. + * @return A command sequence to auto-score coral. + */ public static final Command autoScoreCoralSequence( Drive drive, - Elevator elevator, - V2_RedundancyManipulator manipulator, - V2_RedundancyIntake intake, + ElevatorFSM elevator, + V2_RedundancySuperstructure superstructure, Camera... cameras) { return Commands.either( Commands.sequence( - autoScoreL1CoralSequence(drive, elevator, manipulator, intake, cameras), - postL1Score(elevator, manipulator, intake)), + autoScoreL1CoralSequence(drive, elevator, superstructure, cameras), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)), Commands.sequence( Commands.either( - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.L2, - ArmState.STOW_DOWN, - IntakeState.STOW), + superstructure.runGoal(V2_RedundancySuperstructureStates.L2), Commands.none(), () -> - RobotState.getOIData().currentReefHeight().equals(ReefHeight.L1) - || RobotState.getOIData().currentReefHeight().equals(ReefHeight.STOW) + RobotState.getOIData().currentReefHeight().equals(ReefState.L1) + || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) || RobotState.getOIData() .currentReefHeight() - .equals(ReefHeight.CORAL_INTAKE)), + .equals(ReefState.CORAL_INTAKE)), Commands.parallel( DriveCommands.autoAlignReefCoral(drive, cameras), scoreCoralSequence( elevator, - manipulator, - intake, + superstructure, () -> RobotState.getReefAlignData().atCoralSetpoint())), - Commands.sequence( - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.L4_PLUS, - ArmState.STOW_DOWN, - IntakeState.STOW), - manipulator.scoreCoral().withTimeout(0.5)) - .onlyIf(() -> elevator.getPosition().equals(ElevatorPositions.L4))), - () -> RobotState.getOIData().currentReefHeight().equals(ReefHeight.L1)); - } - + superstructure + .l4PlusSequence() + .onlyIf(() -> RobotState.getOIData().currentReefHeight() == ReefState.L4)), + () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); + } + + /** + * Creates a command to intake algae from the reef. This uses the closest reef tag to + * automatically pick the reef height and reef face. + * + * @param drive The drive subsystem. + * @param superstructure The superstructure subsystem. + * @param cameras The vision cameras. + * @return A command to remove algae. + */ public static final Command intakeAlgaeFromReefSequence( Drive drive, - Elevator elevator, - V2_RedundancyManipulator manipulator, - V2_RedundancyIntake intake, - Supplier level, + V2_RedundancySuperstructure superstructure, + Supplier level, Camera... cameras) { return Commands.sequence( - Commands.parallel( - DriveCommands.autoAlignReefAlgae(drive, cameras), - Commands.sequence( - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - level, - ArmState.STOW_DOWN, - IntakeState.STOW), - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - level, - ArmState.REEF_INTAKE, - IntakeState.STOW)), - manipulator.intakeReefAlgae()) - .until(() -> RobotState.isHasAlgae()), + DriveCommands.autoAlignReefAlgae(drive, cameras), + superstructure.runGoalUntil( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V2_RedundancySuperstructureStates.INTAKE_REEF_L3; + case ALGAE_INTAKE_BOTTOM: + return V2_RedundancySuperstructureStates.INTAKE_REEF_L2; + default: + return V2_RedundancySuperstructureStates.STOW_DOWN; + } + }, + () -> RobotState.isHasAlgae()), Commands.parallel( Commands.sequence( Commands.waitSeconds(0.25), Commands.either( - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.STOW, - ArmState.STOW_UP, - IntakeState.STOW), - Commands.none(), - RobotState::isHasAlgae)), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_UP), + superstructure.runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V2_RedundancySuperstructureStates.REEF_ACQUISITION_L3; + default: + return V2_RedundancySuperstructureStates.REEF_ACQUISITION_L2; + } + }), + () -> RobotState.isHasAlgae())), Commands.runEnd( () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) .withTimeout(0.5))); } - public static final Command scoreAlgae( - Elevator elevator, V2_RedundancyManipulator manipulator, V2_RedundancyIntake intake) { - return Commands.sequence( - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.ALGAE_SCORE, - ArmState.STOW_UP, - IntakeState.STOW), - Commands.waitSeconds(0.5), - manipulator.scoreAlgae().withTimeout(0.5)); - } - + /** + * Creates a command to drop algae from the reef. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param intake The intake subsystem. + * @param superstructure The superstructure subsystem. + * @param level A supplier that provides the current reef level. + * @param cameras The vision cameras. + * @return A command to drop algae from the reef. + */ public static final Command dropAlgae( Drive drive, - Elevator elevator, + ElevatorFSM elevator, V2_RedundancyManipulator manipulator, V2_RedundancyIntake intake, - Supplier level, + V2_RedundancySuperstructure superstructure, + Supplier level, Camera... cameras) { return Commands.sequence( DriveCommands.autoAlignReefAlgae(drive, cameras), - Commands.deadline( - Commands.sequence( - DecisionTree.moveSequence( - elevator, manipulator, intake, level, ArmState.STOW_DOWN, IntakeState.STOW), - DecisionTree.moveSequence( - elevator, manipulator, intake, level, ArmState.REEF_INTAKE, IntakeState.STOW), - Commands.waitSeconds(1.0), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), - () -> drive.stop()) - .withTimeout(0.5)), - manipulator.intakeReefAlgae()), - manipulator.scoreAlgae().withTimeout(0.75), - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.CORAL_INTAKE, - ArmState.STOW_DOWN, - IntakeState.STOW)); - } - - public static final Command netHeight( - Elevator elevator, - Funnel funnel, - V2_RedundancyManipulator manipulator, - V2_RedundancyIntake intake) { + Commands.sequence( + superstructure + .runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V2_RedundancySuperstructureStates.INTAKE_REEF_L3; + case ALGAE_INTAKE_BOTTOM: + return V2_RedundancySuperstructureStates.INTAKE_REEF_L2; + default: + return V2_RedundancySuperstructureStates.STOW_DOWN; + } + }) + .until(() -> RobotState.isHasAlgae()), + Commands.waitSeconds(2.0), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) + .withTimeout(0.5)), + superstructure.runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V2_RedundancySuperstructureStates.DROP_REEF_L3; + case ALGAE_INTAKE_BOTTOM: + return V2_RedundancySuperstructureStates.DROP_REEF_L2; + default: + return V2_RedundancySuperstructureStates.STOW_DOWN; + } + }), + Commands.waitSeconds(1.0), + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); + } + + /** + * Creates a command sequence for the floor intake of algae. + * + * @param superstructure The superstructure subsystem. + * @return A command sequence for the floor intake. + */ + public static final Command floorIntakeSequence(V2_RedundancySuperstructure superstructure) { return Commands.sequence( - funnel.setClapDaddyGoal(FunnelState.CLOSED), - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.ALGAE_SCORE, - ArmState.STOW_UP, - IntakeState.STOW)); + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoalUntil( + V2_RedundancySuperstructureStates.INTAKE_FLOOR, () -> RobotState.isHasAlgae())); + } + + /** + * Creates a command that posts the floor intake sequence, which can either go up or down based + * on whether the robot has algae. + * + * @param superstructure The superstructure subsystem. + * @return A command that posts the floor intake sequence. + */ + public static final Command postFloorIntakeSequence( + V2_RedundancySuperstructure superstructure) { + return Commands.either( + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_UP), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN), + RobotState::isHasAlgae); } - public static final Command scoreProcessorNew( - Elevator elevator, V2_RedundancyManipulator manipulator, V2_RedundancyIntake intake) { + /** + * Creates a command to set the dynamic reef height in the robot state. This sets the height and + * then moves the superstructure to that position. + * + * @param height The reef height to set. + * @param superstructure The superstructure subsystem. + * @return A command to set the dynamic reef height. + */ + public static final Command setDynamicReefHeight( + ReefState height, V2_RedundancySuperstructure superstructure) { return Commands.sequence( - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.ALGAE_FLOOR_INTAKE, - ArmState.STOW_DOWN, - IntakeState.INTAKE), - intake.setRollerVoltage(-6)); - } - - public static final Command scoreProcessor( - Elevator elevator, V2_RedundancyManipulator manipulator, V2_RedundancyIntake intake) { - return DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.STOW, - ArmState.PROCESSOR, - IntakeState.STOW); + Commands.runOnce(() -> RobotState.setReefHeight(height)), superstructure.setPosition()); } - public static final Command floorIntakeSequence( - V2_RedundancyManipulator manipulator, Elevator elevator, V2_RedundancyIntake intake) { + /** + * Creates a command to climb the robot. + * + * @param superstructure The superstructure subsystem. + * @param climber The climber subsystem. + * @param drive The drive subsystem. + * @return A command to climb. + */ + public static final Command climb( + V2_RedundancySuperstructure superstructure, Climber climber, Drive drive) { return Commands.sequence( - Commands.sequence( - Commands.deadline( - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.ALGAE_FLOOR_INTAKE, - ArmState.FLOOR_INTAKE, - IntakeState.INTAKE), - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - intake.setRollerVoltage(6.0)), - Commands.parallel(intake.intakeAlgae(), manipulator.intakeFloorAlgae())) - .until(() -> RobotState.isHasAlgae())); - } - - public static final Command postFloorIntakeSequence( - V2_RedundancyManipulator manipulator, Elevator elevator, V2_RedundancyIntake intake) { - return Commands.either( - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.STOW, - ArmState.STOW_UP, - IntakeState.STOW), - DecisionTree.moveSequence( - elevator, - manipulator, - intake, - () -> ReefHeight.STOW, - ArmState.STOW_DOWN, - IntakeState.STOW), - RobotState::isHasAlgae); + superstructure.runGoal(V2_RedundancySuperstructureStates.CLIMB), + Commands.parallel( + climber.releaseClimber(), + Commands.waitSeconds( + ClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), + Commands.waitUntil(climber::climberReady), + Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); } } + /** + * Creates a command sequence for homing all subsystems in the V2_Redundancy robot. + * + * @param manipulator The manipulator subsystem. + * @param intake The intake subsystem. + * @param elevator The elevator subsystem. + * @return A command sequence to home all subsystems. + */ public static final Command homingSequences( - V2_RedundancyManipulator manipulator, V2_RedundancyIntake intake, Elevator elevator) { + V2_RedundancyManipulator manipulator, V2_RedundancyIntake intake, ElevatorFSM elevator) { return Commands.sequence( - elevator.setPosition(() -> ReefHeight.ALGAE_MID), + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.ALGAE_MID)), elevator.waitUntilAtGoal(), manipulator.homingSequence(), intake.homingSequence(), - elevator.setPosition(() -> RobotState.getOIData().currentReefHeight())); + Commands.runOnce(() -> elevator.setPosition())); } } diff --git a/src/main/java/frc/robot/commands/V2_RedundancyCompositeCommands.java b/src/main/java/frc/robot/commands/V2_RedundancyCompositeCommands.java deleted file mode 100644 index bf74a255..00000000 --- a/src/main/java/frc/robot/commands/V2_RedundancyCompositeCommands.java +++ /dev/null @@ -1,652 +0,0 @@ -package frc.robot.commands; - -import edu.wpi.first.math.geometry.Pose2d; -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.kinematics.ChassisSpeeds; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; -import frc.robot.FieldConstants.Reef.ReefPose; -import frc.robot.FieldConstants.Reef.ReefState; -import frc.robot.RobotState; -import frc.robot.subsystems.shared.climber.Climber; -import frc.robot.subsystems.shared.climber.ClimberConstants; -import frc.robot.subsystems.shared.drive.Drive; -import frc.robot.subsystems.shared.elevator.Elevator.ElevatorCSB; -import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; -import frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions; -import frc.robot.subsystems.shared.funnel.Funnel.FunnelCSB; -import frc.robot.subsystems.shared.funnel.FunnelConstants.FunnelState; -import frc.robot.subsystems.shared.visionlimelight.Camera; -import frc.robot.subsystems.v1_StackUp.manipulator.V1_StackUpManipulator; -import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructure; -import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; -import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; -import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; -import frc.robot.util.AllianceFlipUtil; -import java.util.function.BooleanSupplier; -import java.util.function.Supplier; - -/** - * A class that holds composite commands, which are sequences of commands for complex robot actions. - */ -public class CompositeCommands { - /** A class that holds composite commands that are shared across different robot versions. */ - public static final class SharedCommands { - /** - * Creates a command to reset the robot's heading to the alliance-specific zero. - * - * @param drive The drive subsystem. - * @return A command to reset the heading. - */ - public static final Command resetHeading(Drive drive) { - return Commands.runOnce( - () -> { - RobotState.resetRobotPose( - new Pose2d( - RobotState.getRobotPoseField().getTranslation(), - AllianceFlipUtil.apply(new Rotation2d()))); - }) - .ignoringDisable(true); - } - - /** - * Creates a command to set a static reef height in the robot state. This does not move any - * mechanisms. - * - * @param height The reef height to set. - * @return A command to set the reef height. - */ - public static final Command setStaticReefHeight(ReefState height) { - return Commands.runOnce(() -> RobotState.setReefHeight(height)); - } - } - - /** A class that holds composite commands for the V1_StackUp robot. */ - public static final class V1_StackUpCompositeCommands { - /** - * Creates a command to intake coral from the station. - * - * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. - * @param manipulator The manipulator subsystem. - * @return A command to intake coral. - */ - public static final Command intakeCoral( - ElevatorCSB elevator, FunnelCSB funnel, V1_StackUpManipulator manipulator) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setIntakingCoral(true)), - elevator.setPosition(() -> ReefState.CORAL_INTAKE), - Commands.waitUntil(elevator::atGoal), - Commands.race( - manipulator.intakeCoral(), funnel.intakeCoral(() -> manipulator.hasCoral()))) - .finallyDo(() -> RobotState.setIntakingCoral(false)); - } - - /** - * Creates a command to intake coral from the station with an override. - * - * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. - * @param manipulator The manipulator subsystem. - * @return A command to intake coral with an override. - */ - public static final Command intakeCoralOverride( - ElevatorCSB elevator, FunnelCSB funnel, V1_StackUpManipulator manipulator) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setIntakingCoral(true)), - elevator.setPosition(() -> ReefState.CORAL_INTAKE), - Commands.waitUntil(elevator::atGoal), - Commands.parallel(manipulator.intakeCoral(), funnel.intakeCoral(() -> false))) - .finallyDo(() -> RobotState.setIntakingCoral(false)); - } - - /** - * Creates a command to score coral. - * - * @param manipulator The manipulator subsystem. - * @return A command to score coral. - */ - public static final Command scoreCoral(V1_StackUpManipulator manipulator) { - return manipulator.scoreCoral().withTimeout(0.4); - } - - /** - * Creates a command sequence to score coral, waiting for auto-alignment. - * - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param autoAligned A supplier that returns true when the robot is aligned. - * @return A command sequence to score coral. - */ - public static final Command scoreCoralSequence( - ElevatorCSB elevator, V1_StackUpManipulator manipulator, BooleanSupplier autoAligned) { - return Commands.sequence( - Commands.either( - elevator.setPosition(() -> ReefState.L3), - elevator.setPosition(), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L4) - && !elevator.getPosition().equals(ElevatorPositions.L4)), - Commands.waitUntil(() -> autoAligned.getAsBoolean()), - elevator.setPosition(), - Commands.waitSeconds(0.05), - Commands.waitUntil(elevator::atGoal), - Commands.either( - manipulator.scoreL4Coral().withTimeout(0.4), - manipulator.scoreCoral().withTimeout(0.15), - () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L4))); - } - - /** - * Creates a command sequence to automatically score coral. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. - * @return A command sequence to auto-score coral. - */ - public static final Command autoScoreCoralSequence( - Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { - return Commands.either( - autoScoreL1CoralSequence(drive, elevator, manipulator, cameras), - Commands.sequence( - Commands.either( - elevator.setPosition(() -> ReefState.L2), - Commands.none(), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L1) - || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) - || RobotState.getOIData() - .currentReefHeight() - .equals(ReefState.CORAL_INTAKE)), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - scoreCoralSequence( - elevator, - manipulator, - () -> RobotState.getReefAlignData().atCoralSetpoint())), - elevator - .setPosition(() -> ReefState.STOW) - .onlyIf( - () -> - elevator.getPosition().equals(ElevatorPositions.L3) - || elevator.getPosition().equals(ElevatorPositions.L2))), - () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); - } - - /** - * Creates a command sequence to automatically score coral at L1. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. - * @return A command sequence to auto-score coral at L1. - */ - public static final Command autoScoreL1CoralSequence( - Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefCoral(drive, cameras), - scoreL1Coral(drive, elevator, manipulator)); - } - - /** - * Creates a command to score coral at L1. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @return A command to score coral at L1. - */ - public static final Command scoreL1Coral( - Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator) { - return Commands.sequence( - elevator.setPosition(), - Commands.waitSeconds(0.02), - Commands.waitUntil(elevator::atGoal), - Commands.parallel( - manipulator.scoreL1Coral().withTimeout(0.8), - Commands.sequence( - Commands.waitSeconds(0.05), - Commands.either( - DriveCommands.inchMovement(drive, -1, 0.1), - DriveCommands.inchMovement(drive, 1, 0.1), - () -> RobotState.getOIData().currentReefPost() == ReefPose.LEFT)))); - } - - /** - * Creates a command for an emergency eject of coral. - * - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @return A command to eject coral. - */ - public static final Command emergencyEject( - ElevatorCSB elevator, V1_StackUpManipulator manipulator) { - return Commands.sequence( - elevator.setPosition(() -> ReefState.L1), - Commands.waitSeconds(0.125), - Commands.waitUntil(elevator::atGoal), - manipulator.scoreCoral().withTimeout(0.4), - elevator.setPosition(() -> ReefState.STOW)); - } - - /** - * Creates a command to remove algae from the reef. This uses the closest reef tag to - * automatically pick the reef height. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. - * @return A command to remove algae. - */ - public static final Command twerk( - Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { - return Commands.deferredProxy( - () -> - twerk( - drive, - elevator, - manipulator, - switch (RobotState.getReefAlignData().closestReefTag()) { - case 10, 6, 8, 21, 17, 19 -> ReefState.ASS_BOT; - case 9, 11, 7, 22, 20, 18 -> ReefState.ASS_TOP; - default -> ReefState.ASS_BOT; - }, - cameras)); - } - - /** - * Creates a command to remove algae from the reef. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. - * @return A command to remove algae. - */ - public static final Command twerk( - Drive drive, - ElevatorCSB elevator, - V1_StackUpManipulator manipulator, - ReefState level, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefAlgae(drive, cameras), - elevator.setPosition(() -> ReefState.L4), - Commands.waitUntil(elevator::atGoal), - manipulator.toggleAlgaeArm(), - Commands.waitSeconds(0.1), - elevator.setPosition(() -> level), - manipulator.removeAlgae().until(elevator::atGoal), - manipulator.removeAlgae().withTimeout(0.35), - manipulator.toggleAlgaeArm()); - } - } - - /** - * Creates a command to set the dynamic reef height in the robot state. This sets the height and - * then moves the elevator to that position. - * - * @param height The reef height to set. - * @param elevator The elevator subsystem. - * @return A command to set the dynamic reef height. - */ - public static final Command setDynamicReefHeight(ReefState height, ElevatorCSB elevator) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setReefHeight(height)), elevator.setPosition()); - } - - /** - * Creates a command to climb the robot. - * - * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. - * @param climber The climber subsystem. - * @param drive The drive subsystem. - * @return A command to climb. - */ - public static final Command climb( - ElevatorCSB elevator, FunnelCSB funnel, Climber climber, Drive drive) { - return Commands.sequence( - elevator.setPosition(() -> ReefState.STOW), - Commands.waitSeconds(0.02), - Commands.waitUntil(elevator::atGoal), - funnel.setClapDaddyGoal(FunnelState.CLIMB), - Commands.parallel( - climber.releaseClimber(), - Commands.waitSeconds( - ClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), - Commands.waitUntil(climber::climberReady), - Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); - } - } - - public static final class V2_RedundancyCompositeCommands { - /** - * Creates a command to intake coral from the station. - * - * @param superstructure The superstructure subsystem. - * @param intake The intake subsystem. - * @return A command to intake coral. - */ - public static final Command intakeCoralDriverSequence( - V2_RedundancySuperstructure superstructure, V2_RedundancyIntake intake) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoalUntil( - V2_RedundancySuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); - } - - /** - * Creates a command to intake coral from the station using the operator sequence. - * - * @param superstructure The superstructure subsystem. - * @param intake The intake subsystem. - * @return A command to intake coral using the operator sequence. - */ - public static final Command intakeCoralOperatorSequence( - V2_RedundancySuperstructure superstructure, V2_RedundancyIntake intake) { - return Commands.sequence( - superstructure.runGoalUntil( - V2_RedundancySuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); - } - - /** - * Creates a command to score coral at L1. - * - * @param drive The drive subsystem. - * @param superstructure The superstructure subsystem. - * @return A command to score coral at L1. - */ - public static final Command scoreL1Coral( - Drive drive, V2_RedundancySuperstructure superstructure) { - return Commands.sequence( - superstructure.runGoal(V2_RedundancySuperstructureStates.L1), - Commands.parallel( - superstructure.runReefScoreGoal(() -> ReefState.L1), - Commands.sequence( - Commands.waitSeconds(0.05), - Commands.either( - DriveCommands.inchMovement(drive, -1, 0.1), - DriveCommands.inchMovement(drive, 1, 0.1), - () -> RobotState.getOIData().currentReefPost() == ReefPose.LEFT)))); - } - - /** - * Creates a command sequence to score coral at L1, waiting for auto-alignment. - * - * @param drive The drive subsystem. - * @param superstructure The superstructure subsystem. - * @return A command sequence to score coral at L1. - */ - public static final Command autoScoreL1CoralSequence( - Drive drive, - ElevatorFSM elevator, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefCoral(drive, cameras), scoreL1Coral(drive, superstructure)); - } - - /** - * Creates a command sequence to score coral, waiting for auto-alignment. - * - * @param elevator The elevator subsystem. - * @param superstructure The superstructure subsystem. - * @param autoAligned A supplier that returns true when the robot is aligned. - * @return A command sequence to score coral. - */ - public static final Command scoreCoralSequence( - ElevatorFSM elevator, - V2_RedundancySuperstructure superstructure, - BooleanSupplier autoAligned) { - return Commands.sequence( - Commands.either( - superstructure.runGoal(V2_RedundancySuperstructureStates.L3), - superstructure.runReefGoal(() -> RobotState.getOIData().currentReefHeight()), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L4) - && !superstructure - .getCurrentState() - .equals(V2_RedundancySuperstructureStates.L4)), - Commands.waitUntil(() -> autoAligned.getAsBoolean()), - superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight()), - superstructure - .runGoal(V2_RedundancySuperstructureStates.STOW_DOWN) - .onlyIf( - () -> - elevator.getPosition().equals(ElevatorPositions.L3) - || elevator.getPosition().equals(ElevatorPositions.L2))); - } - - /** - * Creates a command sequence to automatically score coral. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param superstructure The superstructure subsystem. - * @param cameras The vision cameras. - * @return A command sequence to auto-score coral. - */ - public static final Command autoScoreCoralSequence( - Drive drive, - ElevatorFSM elevator, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - return Commands.either( - Commands.sequence( - autoScoreL1CoralSequence(drive, elevator, superstructure, cameras), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)), - Commands.sequence( - Commands.either( - superstructure.runGoal(V2_RedundancySuperstructureStates.L2), - Commands.none(), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L1) - || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) - || RobotState.getOIData() - .currentReefHeight() - .equals(ReefState.CORAL_INTAKE)), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - scoreCoralSequence( - elevator, - superstructure, - () -> RobotState.getReefAlignData().atCoralSetpoint())), - superstructure - .l4PlusSequence() - .onlyIf(() -> RobotState.getOIData().currentReefHeight() == ReefState.L4)), - () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); - } - - /** - * Creates a command to intake algae from the reef. This uses the closest reef tag to - * automatically pick the reef height and reef face. - * - * @param drive The drive subsystem. - * @param superstructure The superstructure subsystem. - * @param cameras The vision cameras. - * @return A command to remove algae. - */ - public static final Command intakeAlgaeFromReefSequence( - Drive drive, - V2_RedundancySuperstructure superstructure, - Supplier level, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefAlgae(drive, cameras), - superstructure.runGoalUntil( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V2_RedundancySuperstructureStates.INTAKE_REEF_L3; - case ALGAE_INTAKE_BOTTOM: - return V2_RedundancySuperstructureStates.INTAKE_REEF_L2; - default: - return V2_RedundancySuperstructureStates.STOW_DOWN; - } - }, - () -> RobotState.isHasAlgae()), - Commands.parallel( - Commands.sequence( - Commands.waitSeconds(0.25), - Commands.either( - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_UP), - superstructure.runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V2_RedundancySuperstructureStates.REEF_ACQUISITION_L3; - default: - return V2_RedundancySuperstructureStates.REEF_ACQUISITION_L2; - } - }), - () -> RobotState.isHasAlgae())), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) - .withTimeout(0.5))); - } - - /** - * Creates a command to drop algae from the reef. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. - * @param superstructure The superstructure subsystem. - * @param level A supplier that provides the current reef level. - * @param cameras The vision cameras. - * @return A command to drop algae from the reef. - */ - public static final Command dropAlgae( - Drive drive, - ElevatorFSM elevator, - V2_RedundancyManipulator manipulator, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Supplier level, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefAlgae(drive, cameras), - Commands.sequence( - superstructure - .runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V2_RedundancySuperstructureStates.INTAKE_REEF_L3; - case ALGAE_INTAKE_BOTTOM: - return V2_RedundancySuperstructureStates.INTAKE_REEF_L2; - default: - return V2_RedundancySuperstructureStates.STOW_DOWN; - } - }) - .until(() -> RobotState.isHasAlgae()), - Commands.waitSeconds(2.0), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) - .withTimeout(0.5)), - superstructure.runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V2_RedundancySuperstructureStates.DROP_REEF_L3; - case ALGAE_INTAKE_BOTTOM: - return V2_RedundancySuperstructureStates.DROP_REEF_L2; - default: - return V2_RedundancySuperstructureStates.STOW_DOWN; - } - }), - Commands.waitSeconds(1.0), - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); - } - - /** - * Creates a command sequence for the floor intake of algae. - * - * @param superstructure The superstructure subsystem. - * @return A command sequence for the floor intake. - */ - public static final Command floorIntakeSequence(V2_RedundancySuperstructure superstructure) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoalUntil( - V2_RedundancySuperstructureStates.INTAKE_FLOOR, () -> RobotState.isHasAlgae())); - } - - /** - * Creates a command that posts the floor intake sequence, which can either go up or down based - * on whether the robot has algae. - * - * @param superstructure The superstructure subsystem. - * @return A command that posts the floor intake sequence. - */ - public static final Command postFloorIntakeSequence( - V2_RedundancySuperstructure superstructure) { - return Commands.either( - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_UP), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN), - RobotState::isHasAlgae); - } - - /** - * Creates a command to set the dynamic reef height in the robot state. This sets the height and - * then moves the superstructure to that position. - * - * @param height The reef height to set. - * @param superstructure The superstructure subsystem. - * @return A command to set the dynamic reef height. - */ - public static final Command setDynamicReefHeight( - ReefState height, V2_RedundancySuperstructure superstructure) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setReefHeight(height)), superstructure.setPosition()); - } - - /** - * Creates a command to climb the robot. - * - * @param superstructure The superstructure subsystem. - * @param climber The climber subsystem. - * @param drive The drive subsystem. - * @return A command to climb. - */ - public static final Command climb( - V2_RedundancySuperstructure superstructure, Climber climber, Drive drive) { - return Commands.sequence( - superstructure.runGoal(V2_RedundancySuperstructureStates.CLIMB), - Commands.parallel( - climber.releaseClimber(), - Commands.waitSeconds( - ClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), - Commands.waitUntil(climber::climberReady), - Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); - } - } - - /** - * Creates a command sequence for homing all subsystems in the V2_Redundancy robot. - * - * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. - * @param elevator The elevator subsystem. - * @return A command sequence to home all subsystems. - */ - public static final Command homingSequences( - V2_RedundancyManipulator manipulator, V2_RedundancyIntake intake, ElevatorFSM elevator) { - return Commands.sequence( - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.ALGAE_MID)), - elevator.waitUntilAtGoal(), - manipulator.homingSequence(), - intake.homingSequence(), - Commands.runOnce(() -> elevator.setPosition())); - } -} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java index 453c40a7..285cf949 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java @@ -2,90 +2,87 @@ import static edu.wpi.first.units.Units.*; -import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants.IntakeState; import lombok.Getter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; - - public class V3_EpsilonIntake extends SubsystemBase { - private final V3_EpsilonIntakeIO io; - private final IntakeIOInputsAutoLogged inputs; - private final SysIdRoutine characterizationRoutine; + private final V3_EpsilonIntakeIO io; + private final IntakeIOInputsAutoLogged inputs; + private final SysIdRoutine characterizationRoutine; - @Getter @AutoLogOutput(key = "Intake/Goal") - private IntakeState goal; + @Getter + @AutoLogOutput(key = "Intake/Goal") + private IntakeState goal; - private boolean isClosedLoop; + private boolean isClosedLoop; - public V3_EpsilonIntake(V3_EpsilonIntakeIO io) { - this.io = io; - inputs = new IntakeIOInputsAutoLogged(); + public V3_EpsilonIntake(V3_EpsilonIntakeIO io) { + this.io = io; + inputs = new IntakeIOInputsAutoLogged(); - characterizationRoutine = new SysIdRoutine( + characterizationRoutine = + new SysIdRoutine( new SysIdRoutine.Config( Volts.of(0.2).per(Second), Volts.of(3.5), Seconds.of(8), (state) -> Logger.recordOutput("Intake/SysID State", state.toString())), - new SysIdRoutine.Mechanism( - (volts) -> io.setPivotVoltage(volts.in(Volts)), null, this)); - - isClosedLoop = true; - } - - @Override - public void periodic() { - io.updateInputs(inputs); - Logger.processInputs("Intake", inputs); - - if (isClosedLoop) { - io.setPivotGoal(goal.getAngle()); - } - } + new SysIdRoutine.Mechanism((volts) -> io.setPivotVoltage(volts.in(Volts)), null, this)); - @AutoLogOutput(key = "Intake/Has Coral") - public boolean hasCoral() { - return false; // Udpate later - } + isClosedLoop = true; + } - @AutoLogOutput(key = "Intake/At Goal") - public boolean atGoal() { - return Math.abs(inputs.pivotPosition.getRadians() - goal.getAngle().getRadians()) < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); - } + @Override + public void periodic() { + io.updateInputs(inputs); + Logger.processInputs("Intake", inputs); - public void setGoal(IntakeState goal) { - isClosedLoop = true; - this.goal = goal; + if (isClosedLoop) { + io.setPivotGoal(goal.getAngle()); } - - public void setRollerVoltage(double volts) { - io.setRollerVoltage(volts); - } - - public void setPivotVoltage(double volts) { - isClosedLoop = false; - io.setPivotVoltage(volts); - } - - public Command sysIdRoutine() { - return Commands.sequence( - Commands.runOnce(() -> isClosedLoop = false), - Commands.runOnce(() -> characterizationRoutine.quasistatic(Direction.kForward)), - Commands.waitSeconds(0.25), - Commands.runOnce(() -> characterizationRoutine.quasistatic(Direction.kReverse)), - Commands.waitSeconds(0.25), - Commands.runOnce(() -> characterizationRoutine.dynamic(Direction.kForward)), - Commands.waitSeconds(0.25), - Commands.runOnce(() -> characterizationRoutine.dynamic(Direction.kReverse)) - ); - } - - -} \ No newline at end of file + } + + @AutoLogOutput(key = "Intake/Has Coral") + public boolean hasCoral() { + return false; // Udpate later + } + + @AutoLogOutput(key = "Intake/At Goal") + public boolean atGoal() { + return Math.abs(inputs.pivotPosition.getRadians() - goal.getAngle().getRadians()) + < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); + } + + public void setGoal(IntakeState goal) { + isClosedLoop = true; + this.goal = goal; + } + + public void setRollerVoltage(double volts) { + io.setRollerVoltage(volts); + } + + public void setPivotVoltage(double volts) { + isClosedLoop = false; + io.setPivotVoltage(volts); + } + + public Command sysIdRoutine() { + return Commands.sequence( + Commands.runOnce(() -> isClosedLoop = false), + Commands.runOnce(() -> characterizationRoutine.quasistatic(Direction.kForward)), + Commands.waitSeconds(0.25), + Commands.runOnce(() -> characterizationRoutine.quasistatic(Direction.kReverse)), + Commands.waitSeconds(0.25), + Commands.runOnce(() -> characterizationRoutine.dynamic(Direction.kForward)), + Commands.waitSeconds(0.25), + Commands.runOnce(() -> characterizationRoutine.dynamic(Direction.kReverse))); + } +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java index 52c03d90..a10cf1b7 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java @@ -3,55 +3,36 @@ import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.util.Units; -import lombok.RequiredArgsConstructor; import lombok.Getter; +import lombok.RequiredArgsConstructor; public class V3_EpsilonIntakeConstants { - public static final int PIVOT_CAN_ID; - - public static final int ROLLER_CAN_ID; + public static final int PIVOT_CAN_ID; - public static final IntakeCurrentLimits CURRENT_LIMITS = new IntakeCurrentLimits( - 40.0, - 40.0, - 40.0, - 40.0 - ); + public static final int ROLLER_CAN_ID; - public static final Gains PIVOT_GAINS = new Gains( - 100.0, - 0.0, - 0.5, - 0.0, - 0.0, - 0.0 - ); - public static final Constraints PIVOT_CONSTRAINTS = new Constraints( - 500.0, - 500.0, - Rotation2d.fromDegrees(0.01) - ); + public static final IntakeCurrentLimits CURRENT_LIMITS = + new IntakeCurrentLimits(40.0, 40.0, 40.0, 40.0); - public static final IntakeParems PIVOT_PARAMS = new IntakeParems( - 3.0, - DCMotor.getKrakenX60Foc(1), - 0.0042, - Rotation2d.fromDegrees(-90.0), - Rotation2d.fromDegrees(90.0) - ); - public static final IntakeParems ROLLER_PARAMS = new IntakeParems( - 1, - DCMotor.getKrakenX60Foc(1), - 0, - new Rotation2d(), - Rotation2d.fromDegrees(90.0) - ); + public static final Gains PIVOT_GAINS = new Gains(100.0, 0.0, 0.5, 0.0, 0.0, 0.0); + public static final Constraints PIVOT_CONSTRAINTS = + new Constraints(500.0, 500.0, Rotation2d.fromDegrees(0.01)); + public static final IntakeParems PIVOT_PARAMS = + new IntakeParems( + 3.0, + DCMotor.getKrakenX60Foc(1), + 0.0042, + Rotation2d.fromDegrees(-90.0), + Rotation2d.fromDegrees(90.0)); + public static final IntakeParems ROLLER_PARAMS = + new IntakeParems( + 1, DCMotor.getKrakenX60Foc(1), 0, new Rotation2d(), Rotation2d.fromDegrees(90.0)); - static { - PIVOT_CAN_ID = 60; - ROLLER_CAN_ID = 61; - } + static { + PIVOT_CAN_ID = 60; + ROLLER_CAN_ID = 61; + } @RequiredArgsConstructor public enum IntakeState { @@ -65,42 +46,27 @@ public enum IntakeState { } public static record IntakeCurrentLimits( - double PIVOT_SUPPLY_CURRENT_LIMIT, - double PIVOT_STATOR_CURRENT_LIMIT, - double ROLLER_SUPPLY_CURRENT_LIMIT, - double ROLLER_STATOR_CURRENT_LIMIT - ) { - } + double PIVOT_SUPPLY_CURRENT_LIMIT, + double PIVOT_STATOR_CURRENT_LIMIT, + double ROLLER_SUPPLY_CURRENT_LIMIT, + double ROLLER_STATOR_CURRENT_LIMIT) {} - public static record Gains( - double kP, - double kD, - double kS, - double kV, - double kA, - double kG - ) { - } + public static record Gains(double kP, double kD, double kS, double kV, double kA, double kG) {} public static record Constraints( - double MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED, - double CRUISING_VELOCITY_RADIANS_PER_SECOND, - Rotation2d GOAL_TOLERANCE - ) { + double MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED, + double CRUISING_VELOCITY_RADIANS_PER_SECOND, + Rotation2d GOAL_TOLERANCE) { public edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints getTrapezoidConstraints() { return new edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints( - CRUISING_VELOCITY_RADIANS_PER_SECOND, - MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED - ); + CRUISING_VELOCITY_RADIANS_PER_SECOND, MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED); } } public static record IntakeParems( - double PIVOT_GEAR_RATIO, - DCMotor MOTOR, - double MASS_KG, - Rotation2d MIN_ANGLE, - Rotation2d MAX_ANGLE - ) { - } + double PIVOT_GEAR_RATIO, + DCMotor MOTOR, + double MASS_KG, + Rotation2d MIN_ANGLE, + Rotation2d MAX_ANGLE) {} } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java index 7027d25a..595fd338 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java @@ -53,7 +53,6 @@ public default void setRollerVoltage(double volts) {} */ public default void setPivotGoal(Rotation2d rotatoion) {} - /** * Sets the gains for the intake * diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOSim.java index e5d76e7d..dd44389b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOSim.java @@ -68,9 +68,11 @@ public V3_EpsilonIntakeIOSim() { @Override public void updateInputs(IntakeIOInputs inputs) { if (isClosedLoop) { - pivotAppliedVoltage = armFeedbackController.calculate(pivotMotorSim.getAngleRads())+ - armFeedforwardController.calculate(pivotMotorSim.getAngleRads(), pivotMotorSim.getVelocityRadPerSec()); - } + pivotAppliedVoltage = + armFeedbackController.calculate(pivotMotorSim.getAngleRads()) + + armFeedforwardController.calculate( + pivotMotorSim.getAngleRads(), pivotMotorSim.getVelocityRadPerSec()); + } pivotAppliedVoltage = MathUtil.clamp(pivotAppliedVoltage, -12.0, 12.0); rollerAppliedVoltage = MathUtil.clamp(rollerAppliedVoltage, -12.0, 12.0); @@ -114,13 +116,7 @@ public void setPivotGoal(Rotation2d rotation) { } @Override - public void updateIntakeGains( - double kP, - double kD, - double kS, - double kV, - double kA, - double kG) { + public void updateIntakeGains(double kP, double kD, double kS, double kV, double kA, double kG) { armFeedbackController.setPID(kP, 0.0, kD); armFeedforwardController.setKa(kA); armFeedforwardController.setKs(kS); @@ -130,8 +126,8 @@ public void updateIntakeGains( @Override public void updateIntakeConstraints( - double maxVelocityRadiansPerSecond, - double maxAccelerationRadiansPerSecondSquared) { - armFeedbackController.setConstraints(new Constraints(maxVelocityRadiansPerSecond, maxAccelerationRadiansPerSecondSquared)); -} + double maxVelocityRadiansPerSecond, double maxAccelerationRadiansPerSecondSquared) { + armFeedbackController.setConstraints( + new Constraints(maxVelocityRadiansPerSecond, maxAccelerationRadiansPerSecondSquared)); + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java index 94d6bb4b..f3f16b63 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java @@ -4,25 +4,17 @@ import static edu.wpi.first.units.Units.RadiansPerSecondPerSecond; import static frc.robot.util.PhoenixUtil.*; -import com.ctre.phoenix6.BaseStatusSignal; -import com.ctre.phoenix6.Orchestra; import com.ctre.phoenix6.StatusSignal; import com.ctre.phoenix6.configs.MotionMagicConfigs; import com.ctre.phoenix6.configs.Slot0Configs; import com.ctre.phoenix6.configs.TalonFXConfiguration; -import com.ctre.phoenix6.configs.TalonFXConfigurator; import com.ctre.phoenix6.controls.MotionMagicVoltage; import com.ctre.phoenix6.controls.NeutralOut; import com.ctre.phoenix6.controls.VoltageOut; import com.ctre.phoenix6.hardware.TalonFX; -import com.ctre.phoenix6.hardware.TalonFXS; -import com.ctre.phoenix6.hardware.core.CoreTalonFX; import com.ctre.phoenix6.signals.GravityTypeValue; import com.ctre.phoenix6.signals.InvertedValue; import com.ctre.phoenix6.signals.NeutralModeValue; -import com.ctre.phoenix6.signals.StaticFeedforwardSignValue; -import com.ctre.phoenix6.sim.TalonFXSimState; - import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.AngularAcceleration; import edu.wpi.first.units.measure.AngularVelocity; @@ -32,111 +24,127 @@ import frc.robot.util.PhoenixUtil; public class V3_EpsilonIntakeIOTalonFX implements V3_EpsilonIntakeIO { - private final TalonFX pivotTalonFX; + private final TalonFX pivotTalonFX; - private final StatusSignal pivotPositionRotations; - private final StatusSignal pivotVelocityRotationsPerSecond; - private final StatusSignal pivotAppliedVoltage; - private final StatusSignal pivotSupplyCurrentAmps; - private final StatusSignal pivotTorqueCurrentAmps; - private final StatusSignal pivotTemperatureCelsius; + private final StatusSignal pivotPositionRotations; + private final StatusSignal pivotVelocityRotationsPerSecond; + private final StatusSignal pivotAppliedVoltage; + private final StatusSignal pivotSupplyCurrentAmps; + private final StatusSignal pivotTorqueCurrentAmps; + private final StatusSignal pivotTemperatureCelsius; - private final VoltageOut pivotVoltageRequest; + private final VoltageOut pivotVoltageRequest; private final MotionMagicVoltage pivotMotionMagicRequest; - private final TalonFXConfiguration pivotConfig; - - - private final TalonFX rollerTalonFX; - - private final StatusSignal rollerPositionRotations; - private final StatusSignal rollerVelocityRotationsPerSecond; - private final StatusSignal rollerAppliedVoltage; - private final StatusSignal rollerSupplyCurrentAmps; - private final StatusSignal rollerTorqueCurrentAmps; - private final StatusSignal rollerTemperatureCelsius; - - private final VoltageOut rollerVoltageRequest; - private final NeutralOut rollerNeutralRequest; - - private final TalonFXConfiguration rollerConfig; - - - - public V3_EpsilonIntakeIOTalonFX() { - pivotTalonFX = new TalonFX(V3_EpsilonIntakeConstants.PIVOT_CAN_ID); - rollerTalonFX = new TalonFX(V3_EpsilonIntakeConstants.ROLLER_CAN_ID); - - pivotConfig = new TalonFXConfiguration(); - pivotConfig.CurrentLimits.SupplyCurrentLimitEnable = true; - pivotConfig.CurrentLimits.SupplyCurrentLimit = V3_EpsilonIntakeConstants.CURRENT_LIMITS.PIVOT_SUPPLY_CURRENT_LIMIT(); - pivotConfig.CurrentLimits.StatorCurrentLimitEnable = true; - pivotConfig.CurrentLimits.StatorCurrentLimit = V3_EpsilonIntakeConstants.CURRENT_LIMITS.PIVOT_STATOR_CURRENT_LIMIT(); - pivotConfig.Feedback.SensorToMechanismRatio = V3_EpsilonIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO(); - pivotConfig.SoftwareLimitSwitch.ForwardSoftLimitEnable = true; - pivotConfig.SoftwareLimitSwitch.ForwardSoftLimitThreshold = V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getRotations(); - pivotConfig.SoftwareLimitSwitch.ReverseSoftLimitEnable = true; - pivotConfig.SoftwareLimitSwitch.ReverseSoftLimitThreshold = V3_EpsilonIntakeConstants.PIVOT_PARAMS.MAX_ANGLE().getRotations(); - pivotConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; - pivotConfig.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive; - pivotConfig.Slot0 = new Slot0Configs().withGravityType(GravityTypeValue.Arm_Cosine) + private final TalonFXConfiguration pivotConfig; + + private final TalonFX rollerTalonFX; + + private final StatusSignal rollerPositionRotations; + private final StatusSignal rollerVelocityRotationsPerSecond; + private final StatusSignal rollerAppliedVoltage; + private final StatusSignal rollerSupplyCurrentAmps; + private final StatusSignal rollerTorqueCurrentAmps; + private final StatusSignal rollerTemperatureCelsius; + + private final VoltageOut rollerVoltageRequest; + private final NeutralOut rollerNeutralRequest; + + private final TalonFXConfiguration rollerConfig; + + public V3_EpsilonIntakeIOTalonFX() { + pivotTalonFX = new TalonFX(V3_EpsilonIntakeConstants.PIVOT_CAN_ID); + rollerTalonFX = new TalonFX(V3_EpsilonIntakeConstants.ROLLER_CAN_ID); + + pivotConfig = new TalonFXConfiguration(); + pivotConfig.CurrentLimits.SupplyCurrentLimitEnable = true; + pivotConfig.CurrentLimits.SupplyCurrentLimit = + V3_EpsilonIntakeConstants.CURRENT_LIMITS.PIVOT_SUPPLY_CURRENT_LIMIT(); + pivotConfig.CurrentLimits.StatorCurrentLimitEnable = true; + pivotConfig.CurrentLimits.StatorCurrentLimit = + V3_EpsilonIntakeConstants.CURRENT_LIMITS.PIVOT_STATOR_CURRENT_LIMIT(); + pivotConfig.Feedback.SensorToMechanismRatio = + V3_EpsilonIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO(); + pivotConfig.SoftwareLimitSwitch.ForwardSoftLimitEnable = true; + pivotConfig.SoftwareLimitSwitch.ForwardSoftLimitThreshold = + V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getRotations(); + pivotConfig.SoftwareLimitSwitch.ReverseSoftLimitEnable = true; + pivotConfig.SoftwareLimitSwitch.ReverseSoftLimitThreshold = + V3_EpsilonIntakeConstants.PIVOT_PARAMS.MAX_ANGLE().getRotations(); + pivotConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; + pivotConfig.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive; + pivotConfig.Slot0 = + new Slot0Configs() + .withGravityType(GravityTypeValue.Arm_Cosine) .withKP(V3_EpsilonIntakeConstants.PIVOT_GAINS.kP()) .withKD(V3_EpsilonIntakeConstants.PIVOT_GAINS.kD()) .withKA(V3_EpsilonIntakeConstants.PIVOT_GAINS.kA()) .withKV(V3_EpsilonIntakeConstants.PIVOT_GAINS.kV()) .withKS(V3_EpsilonIntakeConstants.PIVOT_GAINS.kS()) .withKG(V3_EpsilonIntakeConstants.PIVOT_GAINS.kG()); - pivotConfig.MotionMagic = new MotionMagicConfigs() - .withMotionMagicCruiseVelocity(AngularVelocity.ofRelativeUnits(V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.CRUISING_VELOCITY_RADIANS_PER_SECOND(), RadiansPerSecond)) - .withMotionMagicAcceleration(AngularAcceleration.ofRelativeUnits(V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED(), RadiansPerSecondPerSecond)); - - tryUntilOk(5, () -> pivotTalonFX.getConfigurator().apply(pivotConfig, 0.25)); - - pivotPositionRotations = pivotTalonFX.getPosition(); - pivotVelocityRotationsPerSecond = pivotTalonFX.getVelocity(); - pivotAppliedVoltage = pivotTalonFX.getSupplyVoltage(); - pivotSupplyCurrentAmps = pivotTalonFX.getSupplyCurrent(); - pivotTorqueCurrentAmps = pivotTalonFX.getTorqueCurrent(); - pivotTemperatureCelsius = pivotTalonFX.getDeviceTemp(); - - rollerConfig = new TalonFXConfiguration(); - rollerConfig.CurrentLimits.SupplyCurrentLimitEnable = true; - rollerConfig.CurrentLimits.SupplyCurrentLimit = V3_EpsilonIntakeConstants.CURRENT_LIMITS.ROLLER_SUPPLY_CURRENT_LIMIT(); - rollerConfig.CurrentLimits.StatorCurrentLimitEnable = true; - rollerConfig.CurrentLimits.StatorCurrentLimit = V3_EpsilonIntakeConstants.CURRENT_LIMITS.ROLLER_STATOR_CURRENT_LIMIT(); - rollerConfig.Feedback.SensorToMechanismRatio = V3_EpsilonIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO(); - rollerConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; - rollerConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; - - tryUntilOk(5, () -> rollerTalonFX.getConfigurator().apply(rollerConfig, 0.25)); - - rollerPositionRotations = pivotTalonFX.getPosition(); - rollerVelocityRotationsPerSecond = pivotTalonFX.getVelocity(); - rollerAppliedVoltage = pivotTalonFX.getSupplyVoltage(); - rollerSupplyCurrentAmps = pivotTalonFX.getSupplyCurrent(); - rollerTorqueCurrentAmps = pivotTalonFX.getTorqueCurrent(); - rollerTemperatureCelsius = pivotTalonFX.getDeviceTemp(); - - pivotVoltageRequest = new VoltageOut(0); - pivotMotionMagicRequest = new MotionMagicVoltage(V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getMeasure()); - - rollerVoltageRequest = new VoltageOut(0); - rollerNeutralRequest = new NeutralOut(); - - PhoenixUtil.registerSignals( - false, - pivotPositionRotations, - pivotVelocityRotationsPerSecond, - pivotAppliedVoltage, - pivotSupplyCurrentAmps, - pivotTorqueCurrentAmps, - pivotTemperatureCelsius, - rollerPositionRotations, - rollerVelocityRotationsPerSecond, - rollerAppliedVoltage, - rollerSupplyCurrentAmps, - rollerTorqueCurrentAmps, - rollerTemperatureCelsius); - } - + pivotConfig.MotionMagic = + new MotionMagicConfigs() + .withMotionMagicCruiseVelocity( + AngularVelocity.ofRelativeUnits( + V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS + .CRUISING_VELOCITY_RADIANS_PER_SECOND(), + RadiansPerSecond)) + .withMotionMagicAcceleration( + AngularAcceleration.ofRelativeUnits( + V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS + .MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED(), + RadiansPerSecondPerSecond)); + + tryUntilOk(5, () -> pivotTalonFX.getConfigurator().apply(pivotConfig, 0.25)); + + pivotPositionRotations = pivotTalonFX.getPosition(); + pivotVelocityRotationsPerSecond = pivotTalonFX.getVelocity(); + pivotAppliedVoltage = pivotTalonFX.getSupplyVoltage(); + pivotSupplyCurrentAmps = pivotTalonFX.getSupplyCurrent(); + pivotTorqueCurrentAmps = pivotTalonFX.getTorqueCurrent(); + pivotTemperatureCelsius = pivotTalonFX.getDeviceTemp(); + + rollerConfig = new TalonFXConfiguration(); + rollerConfig.CurrentLimits.SupplyCurrentLimitEnable = true; + rollerConfig.CurrentLimits.SupplyCurrentLimit = + V3_EpsilonIntakeConstants.CURRENT_LIMITS.ROLLER_SUPPLY_CURRENT_LIMIT(); + rollerConfig.CurrentLimits.StatorCurrentLimitEnable = true; + rollerConfig.CurrentLimits.StatorCurrentLimit = + V3_EpsilonIntakeConstants.CURRENT_LIMITS.ROLLER_STATOR_CURRENT_LIMIT(); + rollerConfig.Feedback.SensorToMechanismRatio = + V3_EpsilonIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO(); + rollerConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; + rollerConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; + + tryUntilOk(5, () -> rollerTalonFX.getConfigurator().apply(rollerConfig, 0.25)); + + rollerPositionRotations = pivotTalonFX.getPosition(); + rollerVelocityRotationsPerSecond = pivotTalonFX.getVelocity(); + rollerAppliedVoltage = pivotTalonFX.getSupplyVoltage(); + rollerSupplyCurrentAmps = pivotTalonFX.getSupplyCurrent(); + rollerTorqueCurrentAmps = pivotTalonFX.getTorqueCurrent(); + rollerTemperatureCelsius = pivotTalonFX.getDeviceTemp(); + + pivotVoltageRequest = new VoltageOut(0); + pivotMotionMagicRequest = + new MotionMagicVoltage(V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getMeasure()); + + rollerVoltageRequest = new VoltageOut(0); + rollerNeutralRequest = new NeutralOut(); + + PhoenixUtil.registerSignals( + false, + pivotPositionRotations, + pivotVelocityRotationsPerSecond, + pivotAppliedVoltage, + pivotSupplyCurrentAmps, + pivotTorqueCurrentAmps, + pivotTemperatureCelsius, + rollerPositionRotations, + rollerVelocityRotationsPerSecond, + rollerAppliedVoltage, + rollerSupplyCurrentAmps, + rollerTorqueCurrentAmps, + rollerTemperatureCelsius); + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java index 5349612e..f006845a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java @@ -8,8 +8,8 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; -import frc.robot.subsystems.v2_Redundancy.manipulator.V2_RedundancyManipulatorConstants; -import frc.robot.subsystems.v2_Redundancy.manipulator.V2_RedundancyManipulatorConstants.ArmState; +import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants.PivotState; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; @@ -19,7 +19,7 @@ public class V3_EpsilonManipulator extends SubsystemBase { private final SysIdRoutine algaeCharacterizationRoutine; - private ArmState state; + private PivotState state; private boolean isClosedLoop; public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { @@ -35,7 +35,7 @@ public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { Seconds.of(5), (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), new SysIdRoutine.Mechanism((volts) -> io.setPivotVoltage(volts.in(Volts)), null, this)); - state = ArmState.STOW_DOWN; + state = PivotState.STOW_DOWN; } @Override @@ -86,7 +86,7 @@ public Command sysIdRoutine() { algaeCharacterizationRoutine.dynamic(Direction.kReverse)); } - public Command setPivotGoal(ArmState goal) { + public Command setPivotGoal(PivotState goal) { return this.runOnce( () -> { isClosedLoop = true; @@ -125,7 +125,7 @@ public void updateArmConstraints(double maxAcceleration, double maxVelocity) { @AutoLogOutput(key = "Manipulator/Arm At Goal") public boolean pivotAtGoal() { return inputs.armPosition.getRadians() - state.getAngle().getRadians() - <= V2_RedundancyManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); + <= V2_RedundancyManipulatorConstants.CONSTRAINTS.GOAL_TOLERANCE_RADIANS().get(); } public Command waitUntilPivotAtGoal() { @@ -140,10 +140,7 @@ private double holdVoltage() { } else { y = 0.0005 * Math.pow(x, 2) - 0.1015 * x + 3.7425; } - return MathUtil.clamp( - 1.25 * y, - 0.10, - V2_RedundancyManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().get() / 1.5); + return MathUtil.clamp(1.25 * y, 0.10, V3_EpsilonManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().getAsDouble() / 1.5); } public void setSlot() { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java index 68d147b0..fd975e79 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java @@ -1,13 +1,10 @@ package frc.robot.subsystems.v3_Epsilon.manipulator; -import com.ctre.phoenix6.configs.Slot0Configs; import com.ctre.phoenix6.configs.SlotConfigs; import com.ctre.phoenix6.signals.GravityTypeValue; - import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.util.Units; -import frc.robot.subsystems.v2_Redundancy.manipulator.V2_RedundancyManipulatorConstants.ArmParameters; import frc.robot.util.LoggedTunableNumber; import lombok.RequiredArgsConstructor; @@ -98,17 +95,17 @@ public static record Gains( LoggedTunableNumber kG, LoggedTunableNumber kV, LoggedTunableNumber kA) { - public SlotConfigs toTalonFXSlotConfigs() { - return new SlotConfigs() - .withKP(kP.get()) - .withKD(kD.get()) - .withKS(kS.get()) - .withKG(kG.get()) - .withKV(kV.get()) - .withKA(kA.get()) - .withGravityType(GravityTypeValue.Arm_Cosine); - } - } + public SlotConfigs toTalonFXSlotConfigs() { + return new SlotConfigs() + .withKP(kP.get()) + .withKD(kD.get()) + .withKS(kS.get()) + .withKG(kG.get()) + .withKV(kV.get()) + .withKA(kA.get()) + .withGravityType(GravityTypeValue.Arm_Cosine); + } + } public static final record ManipulatorCurrentLimits( double MANIPULATOR_SUPPLY_CURRENT_LIMIT, @@ -131,6 +128,14 @@ public static final record Voltages( LoggedTunableNumber HALF_VOLTS, LoggedTunableNumber L1_VOLTS) {} + public static record ArmParameters( + DCMotor MOTOR_CONFIG, + Rotation2d MIN_ANGLE, + Rotation2d MAX_ANGLE, + int NUM_MOTORS, + double GEAR_RATIO, + double LENGTH_METERS) {} + @RequiredArgsConstructor public static enum PivotState { STOW_UP(Rotation2d.fromDegrees(75)), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java index adf82a49..b9a4a452 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java @@ -60,6 +60,9 @@ public V3_EpsilonManipulatorIOSim() { V3_EpsilonManipulatorConstants.EMPTY_GAINS.kG().get(), V3_EpsilonManipulatorConstants.EMPTY_GAINS.kV().get(), V3_EpsilonManipulatorConstants.EMPTY_GAINS.kA().get()); + armFeedbackController.enableContinuousInput( + V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MIN_ANGLE().getRadians(), + V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MAX_ANGLE().getRadians()); armAppliedVolts = 0.0; rollerAppliedVolts = 0.0; @@ -70,8 +73,7 @@ public V3_EpsilonManipulatorIOSim() { public void updateInputs(ManipulatorIOInputs inputs) { if (isClosedLoop) { armAppliedVolts = - armFeedbackController.calculate( - armMotorSim.getAngleRads()) + armFeedbackController.calculate(armMotorSim.getAngleRads()) + armFeedforwardController.calculate( armMotorSim.getAngleRads(), armMotorSim.getVelocityRadPerSec()); } @@ -93,8 +95,7 @@ public void updateInputs(ManipulatorIOInputs inputs) { inputs.armPositionGoal = Rotation2d.fromRadians(armFeedbackController.getGoal().position); inputs.armPositionSetpoint = Rotation2d.fromRadians(armFeedbackController.getSetpoint().position); - inputs.armPositionError = - Rotation2d.fromRadians(armFeedbackController.getPositionError()); + inputs.armPositionError = Rotation2d.fromRadians(armFeedbackController.getPositionError()); inputs.rollerPosition = new Rotation2d(rollerMotorSim.getAngularPositionRad()); inputs.rollerVelocityRadiansPerSecond = rollerMotorSim.getAngularVelocityRadPerSec(); @@ -126,9 +127,9 @@ public void updateSlot0ArmGains( } public void updateArmConstraints( - double cruisingVelocityRotationsPerSecond, - double maxAccelerationRotationsPerSecondSquared) { + double cruisingVelocityRotationsPerSecond, double maxAccelerationRotationsPerSecondSquared) { armFeedbackController.setConstraints( - new Constraints(cruisingVelocityRotationsPerSecond, maxAccelerationRotationsPerSecondSquared)); + new Constraints( + cruisingVelocityRotationsPerSecond, maxAccelerationRotationsPerSecondSquared)); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java index 0ad181c4..bd6fa35e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java @@ -159,9 +159,7 @@ public void setRollerVoltage(double volts) { @Override public void setPivotGoal(Rotation2d rotation) { pivotTalonFX.setControl( - pivotMotionMagicRequest - .withPosition(rotation.getRotations()) - .withEnableFOC(true)); + pivotMotionMagicRequest.withPosition(rotation.getRotations()).withEnableFOC(true)); } @Override From b7e7a7ee675b720db37e3a4ca492c9d774d642d9 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Mon, 4 Aug 2025 16:32:08 -0400 Subject: [PATCH 006/180] finish intake and manipulator --- .../intake/V3_EpsilonIntakeIOTalonFX.java | 48 ++++++++++- .../manipulator/V3_EpsilonManipulator.java | 5 +- .../V3_EpsilonManipulatorIOSim.java | 82 +++++++++++++++++-- 3 files changed, 126 insertions(+), 9 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java index f3f16b63..9e29b2e2 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java @@ -9,12 +9,12 @@ import com.ctre.phoenix6.configs.Slot0Configs; import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.MotionMagicVoltage; -import com.ctre.phoenix6.controls.NeutralOut; import com.ctre.phoenix6.controls.VoltageOut; import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.GravityTypeValue; import com.ctre.phoenix6.signals.InvertedValue; import com.ctre.phoenix6.signals.NeutralModeValue; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.AngularAcceleration; import edu.wpi.first.units.measure.AngularVelocity; @@ -33,6 +33,9 @@ public class V3_EpsilonIntakeIOTalonFX implements V3_EpsilonIntakeIO { private final StatusSignal pivotTorqueCurrentAmps; private final StatusSignal pivotTemperatureCelsius; + private final StatusSignal pivotPositionSetpoint; + private final StatusSignal pivotPositionError; + private final VoltageOut pivotVoltageRequest; private final MotionMagicVoltage pivotMotionMagicRequest; @@ -48,7 +51,6 @@ public class V3_EpsilonIntakeIOTalonFX implements V3_EpsilonIntakeIO { private final StatusSignal rollerTemperatureCelsius; private final VoltageOut rollerVoltageRequest; - private final NeutralOut rollerNeutralRequest; private final TalonFXConfiguration rollerConfig; @@ -104,6 +106,9 @@ public V3_EpsilonIntakeIOTalonFX() { pivotTorqueCurrentAmps = pivotTalonFX.getTorqueCurrent(); pivotTemperatureCelsius = pivotTalonFX.getDeviceTemp(); + pivotPositionSetpoint = pivotTalonFX.getClosedLoopReference(); + pivotPositionError = pivotTalonFX.getClosedLoopError(); + rollerConfig = new TalonFXConfiguration(); rollerConfig.CurrentLimits.SupplyCurrentLimitEnable = true; rollerConfig.CurrentLimits.SupplyCurrentLimit = @@ -130,7 +135,6 @@ public V3_EpsilonIntakeIOTalonFX() { new MotionMagicVoltage(V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getMeasure()); rollerVoltageRequest = new VoltageOut(0); - rollerNeutralRequest = new NeutralOut(); PhoenixUtil.registerSignals( false, @@ -147,4 +151,42 @@ public V3_EpsilonIntakeIOTalonFX() { rollerTorqueCurrentAmps, rollerTemperatureCelsius); } + + @Override + public void updateInputs(IntakeIOInputs inputs) { + inputs.pivotPosition = new Rotation2d(pivotPositionRotations.getValue()); + inputs.pivotVelocityRadiansPerSecond = + pivotVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); + inputs.pivotAppliedVolts = pivotAppliedVoltage.getValueAsDouble(); + inputs.pivotSupplyCurrentAmps = pivotSupplyCurrentAmps.getValueAsDouble(); + inputs.pivotTorqueCurrentAmps = pivotTorqueCurrentAmps.getValueAsDouble(); + inputs.pivotTemperatureCelsius = pivotTemperatureCelsius.getValueAsDouble(); + + inputs.pivotPositionGoal = new Rotation2d(pivotMotionMagicRequest.getPositionMeasure()); + inputs.pivotPositionSetpoint = + Rotation2d.fromRotations(pivotPositionSetpoint.getValueAsDouble()); + inputs.pivotPositionError = Rotation2d.fromRotations(pivotPositionError.getValueAsDouble()); + + inputs.rollerPosition = new Rotation2d(rollerPositionRotations.getValue()); + inputs.rollerVelocityRadiansPerSecond = + rollerVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); + inputs.rollerAppliedVolts = rollerAppliedVoltage.getValueAsDouble(); + inputs.rollerAppliedVolts = rollerAppliedVoltage.getValueAsDouble(); + inputs.rollerSupplyCurrentAmps = rollerSupplyCurrentAmps.getValueAsDouble(); + inputs.rollerTorqueCurrentAmps = rollerTorqueCurrentAmps.getValueAsDouble(); + inputs.rollerTemperatureCelsius = rollerTemperatureCelsius.getValueAsDouble(); + } + + public void setPivotVoltage(double volts) { + pivotTalonFX.setControl(pivotVoltageRequest.withOutput(volts).withEnableFOC(true)); + } + + public void setRollerVoltage(double volts) { + rollerTalonFX.setControl(rollerVoltageRequest.withOutput(volts).withEnableFOC(true)); + } + + public void setPivotMotionMagic(Rotation2d position) { + pivotTalonFX.setControl( + pivotMotionMagicRequest.withPosition(position.getMeasure()).withEnableFOC(true)); + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java index f006845a..1953e5f1 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java @@ -140,7 +140,10 @@ private double holdVoltage() { } else { y = 0.0005 * Math.pow(x, 2) - 0.1015 * x + 3.7425; } - return MathUtil.clamp(1.25 * y, 0.10, V3_EpsilonManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().getAsDouble() / 1.5); + return MathUtil.clamp( + 1.25 * y, + 0.10, + V3_EpsilonManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().getAsDouble() / 1.5); } public void setSlot() { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java index b9a4a452..d353faf7 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java @@ -18,6 +18,10 @@ public class V3_EpsilonManipulatorIOSim implements V3_EpsilonManipulatorIO { private final ProfiledPIDController armFeedbackController; private final ArmFeedforward armFeedforwardController; + private double[] slot0; + private double[] slot1; + private double[] slot2; + private double armAppliedVolts; private double rollerAppliedVolts; @@ -42,6 +46,33 @@ public V3_EpsilonManipulatorIOSim() { LinearSystemId.createDCMotorSystem(DCMotor.getKrakenX60Foc(1), 0.004, 3.0), DCMotor.getKrakenX60Foc(1)); + slot0 = + new double[] { + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kP().get(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kD().get(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kS().get(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kV().get(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kA().get(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kG().get() + }; + slot1 = + new double[] { + V3_EpsilonManipulatorConstants.CORAL_GAINS.kP().get(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kD().get(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kS().get(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kV().get(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kA().get(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kG().get() + }; + slot2 = + new double[] { + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kP().get(), + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kD().get(), + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kS().get(), + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kV().get(), + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kA().get(), + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kG().get() + }; armFeedbackController = new ProfiledPIDController( V3_EpsilonManipulatorConstants.EMPTY_GAINS.kP().get(), @@ -119,11 +150,52 @@ public void setPivotGoal(Rotation2d rotation) { public void updateSlot0ArmGains( double kP, double kD, double kS, double kV, double kA, double kG) { - armFeedbackController.setPID(kP, 0.0, kD); - armFeedforwardController.setKa(kA); - armFeedforwardController.setKs(kS); - armFeedforwardController.setKv(kV); - armFeedforwardController.setKg(kG); + slot0[0] = kP; + slot0[1] = kD; + slot0[2] = kS; + slot0[3] = kV; + slot0[4] = kA; + slot0[5] = kG; + } + + public void updateSlot1ArmGains( + double kP, double kD, double kS, double kV, double kA, double kG) { + slot1[0] = kP; + slot1[1] = kD; + slot1[2] = kS; + slot1[3] = kV; + slot1[4] = kA; + slot1[5] = kG; + } + + public void updateSlot2ArmGains( + double kP, double kD, double kS, double kV, double kA, double kG) { + slot2[0] = kP; + slot2[1] = kD; + slot2[2] = kS; + slot2[3] = kV; + slot2[4] = kA; + slot2[5] = kG; + } + + public void setSlot(int slot) { + if (slot >= 0 && slot <= 2) { + double[] gains; + if (slot == 0) { + gains = slot0; + } else if (slot == 1) { + gains = slot1; + } else { + gains = slot2; + } + armFeedbackController.setPID(gains[0], 0.0, gains[1]); + armFeedforwardController.setKa(gains[4]); + armFeedforwardController.setKs(gains[2]); + armFeedforwardController.setKv(gains[3]); + armFeedforwardController.setKg(gains[5]); + } else { + throw new IllegalArgumentException("Slot must be between 0 and 2"); + } } public void updateArmConstraints( From db38a105bb67b5f1849aa4da378fba0521167419 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Mon, 4 Aug 2025 19:08:54 -0400 Subject: [PATCH 007/180] Co-authored-by: Anshu Co-authored-by: iamabhiveni --- .../superstructure/Superstructure.dot | 0 .../superstructure/Superstructure.dot | 136 ++++++++++++++++++ 2 files changed, 136 insertions(+) rename Superstructure.dot => src/main/java/frc/robot/subsystems/v2_Redundancy/superstructure/Superstructure.dot (100%) create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot diff --git a/Superstructure.dot b/src/main/java/frc/robot/subsystems/v2_Redundancy/superstructure/Superstructure.dot similarity index 100% rename from Superstructure.dot rename to src/main/java/frc/robot/subsystems/v2_Redundancy/superstructure/Superstructure.dot diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot new file mode 100644 index 00000000..2dd5d44d --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -0,0 +1,136 @@ +digraph Superstructure { + /* + * Graphviz DOT file for the superstructure state machine. + * States are represented as nodes, and transitions are represented as edges. + */ + + // Node definitions + start [color = red] + + stow_down [color = green] + + ground_intake [color = green] + + L1_score [color = green] + L2_score [color = green] + L3_score [color = green] + L4_score [color = green] + + stow_up [color = cyan] + + L2_algae_prep [color = blue] + L3_algae_prep [color = blue] + + L2_algae_intake [color = blue] + L3_algae_intake [color = blue] + + barge_prep [color = blue] + barge_score [color = blue] + + processor_prep [color = blue] + processor_score [color = blue] + + # Prep states + L1_prep [color = green] + L2_prep [color = green] + L3_prep [color = green] + L4_prep [color = green] + + # Transition States + L2_transition [color = green] + L3_transition [color = green] + L4_transition [color = green] + # Transition states are inherently wait_for_elevator states but for different levels + + intermediate_wait_for_elevator [color = green] + + stow_down -> stow_up [color = green] + handoff -> stow_up [color = green] + + stow_up -> L2_transition [color = green] + stow_up -> L3_transition [color = green] + stow_up -> L4_transition [color = green] + + # Coral Edges + handoff -> L1_prep [color = green] + handoff -> L2_transition [color = green] + handoff -> L3_transition [color = green] + handoff -> L4_transition [color = green] + + handoff -> L2_prep [color = green] + handoff -> L3_prep [color = green] + handoff -> L4_prep [color = green] + + stow_down -> intermediate_wait_for_elevator [color = green] + intermediate_wait_for_elevator -> handoff [color = green] + ground_intake -> L1_prep [color = green] + stow_down -> ground_intake [color = green] + + L1_prep -> ground_intake [color = green] + + L1_prep -> L1_score [color = green] + L2_prep -> L2_score [color = green] + L3_prep -> L3_score [color = green] + L4_prep -> L4_score [color = green] + + L2_prep -> intermediate_wait_for_elevator [color = green] + L3_prep -> intermediate_wait_for_elevator [color = green] + L4_prep -> intermediate_wait_for_elevator [color = green] + + L1_score -> ground_intake [color = green] + L1_prep -> handoff [color = green] + L1_score -> handoff [color = green] + + L2_score -> intermediate_wait_for_elevator [color = green] + L3_score -> intermediate_wait_for_elevator [color = green] + L4_score -> intermediate_wait_for_elevator [color = green] + + L2_prep -> L3_transition [color = green] + L2_prep -> L4_transition [color = green] + L3_prep -> L2_transition [color = green] + L3_prep -> L4_transition [color = green] + L4_prep -> L3_transition [color = green] + L4_prep -> L2_transition [color = green] + + L2_transition -> L2_prep [color = green] + L3_transition -> L3_prep [color = green] + L4_transition -> L4_prep [color = green] + + # Algae Edges + stow_up -> L2_algae_prep [color = blue] + stow_up -> L3_algae_prep [color = blue] + stow_up -> barge_prep [color = blue] + stow_up -> processor_prep [color = blue] + + stow_down -> L2_algae_prep [color = blue] + stow_down -> L3_algae_prep [color = blue] + + L2_algae_prep -> barge_prep [color = blue] + L3_algae_prep -> barge_prep [color = blue] + + L2_algae_prep -> processor_prep [color = blue] + L3_algae_prep -> processor_prep [color = blue] + + L2_algae_prep -> stow_up [color = blue] + L3_algae_prep -> stow_up [color = blue] + + L2_algae_prep -> L2_algae_intake [color = blue] + L3_algae_prep -> L3_algae_intake [color = blue] + + L2_algae_intake -> stow_up [color = blue] + L3_algae_intake -> stow_up [color = blue] + + barge_prep -> barge_score [color = blue] + processor_prep -> processor_score [color = blue] + + processor_score -> stow_up [color = blue] + processor_score -> stow_down [color = blue] + processor_score -> handoff [color = blue] + + barge_score -> stow_up [color = blue] + barge_score -> stow_down [color = blue] + barge_score -> handoff [color = blue] + + L2_algae_prep -> L3_algae_prep [color = blue] + L3_algae_prep -> L2_algae_prep [color = blue] +} \ No newline at end of file From e0fd44607bf5937801b7bc2d2be647f5e16702fb Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sat, 9 Aug 2025 10:36:16 -0400 Subject: [PATCH 008/180] Started work on V3 superstructure implementation --- .../v3_Epsilon/intake/V3_EpsilonIntake.java | 4 + .../manipulator/V3_EpsilonManipulator.java | 4 + .../manipulator/V3_EpsilonManipulatorIO.java | 5 +- .../V3_SuperstructureActions.java | 23 ++++++ .../V3_SuperstructureEdges.java | 5 ++ .../V3_SuperstructurePoses.java | 79 +++++++++++++++++++ 6 files changed, 119 insertions(+), 1 deletion(-) create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java index 285cf949..201db3a8 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java @@ -60,6 +60,10 @@ public boolean atGoal() { < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); } + public void waitUntilIntakeAtGoal() { + Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::atGoal)); + } + public void setGoal(IntakeState goal) { isClosedLoop = true; this.goal = goal; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java index 1953e5f1..0fd4fdd9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java @@ -155,4 +155,8 @@ public void setSlot() { io.setSlot(0); } } + + public void setManipulatorState(V3_EpsilonManipulatorConstants.PivotState state) { + io.setManipulatorState(state); + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java index 7fc16cf8..5baaee28 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java @@ -1,8 +1,9 @@ package frc.robot.subsystems.v3_Epsilon.manipulator; -import edu.wpi.first.math.geometry.Rotation2d; import org.littletonrobotics.junction.AutoLog; +import edu.wpi.first.math.geometry.Rotation2d; + public interface V3_EpsilonManipulatorIO { @AutoLog @@ -46,6 +47,8 @@ public default void setRollerVoltage(double volts) {} public default void setPivotGoal(Rotation2d rotation) {} + public default void setManipulatorState(V3_EpsilonManipulatorConstants.PivotState state) {} + /** * Sets the gains for the arm. * diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java new file mode 100644 index 00000000..084e9b1d --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java @@ -0,0 +1,23 @@ +package frc.robot.subsystems.v3_Epsilon.superstructure; + +import frc.robot.FieldConstants.Reef.ReefState; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; +import lombok.Getter; + +public class V3_SuperstructureActions{ + + @Getter private final ReefState elevatorHeight; + @Getter private final V3_EpsilonManipulatorConstants.PivotState armState; + @Getter private final V3_EpsilonIntakeConstants.IntakeState intakeState; + + + + + + public record SubsystemActions( + ReefState elevatorHeight, + V3_EpsilonManipulatorConstants.PivotState manipulatorArmState, + V3_EpsilonIntakeConstants.IntakeState intakeState) { + } +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java new file mode 100644 index 00000000..168e6839 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java @@ -0,0 +1,5 @@ +package frc.robot.subsystems.v3_Epsilon.superstructure; + +public class V3_SuperstructureEdges { + // Will add code later once all edges are set in stone +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java new file mode 100644 index 00000000..5b28e777 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java @@ -0,0 +1,79 @@ +package frc.robot.subsystems.v3_Epsilon.superstructure; + +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; +import edu.wpi.first.wpilibj2.command.Subsystem; +import frc.robot.FieldConstants.Reef.ReefState; +import frc.robot.subsystems.shared.elevator.Elevator; +import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; +import frc.robot.subsystems.shared.funnel.FunnelConstants.FunnelState; +import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructurePose; +import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructurePose.SubsystemPoses; +import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntakeConstants.IntakeExtensionState; +import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants.ManipulatorArmState; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; +import lombok.Getter; + +public class V3_SuperstructurePoses { + private String key; + + @Getter private final ReefState elevatorHeight; + @Getter private final V3_EpsilonManipulatorConstants.PivotState armState; + @Getter private final V3_EpsilonIntakeConstants.IntakeState intakeState; + + public V3_SuperstructurePoses(String key, SubsystemPoses poses) { + this.key = key; + + this.elevatorHeight = poses.elevatorHeight(); + this.armState = poses.manipulatorArmState(); + this.intakeState = poses.intakeState(); + } + + public Command setElevatorHeight(ElevatorFSM elevator) { + return Commands.parallel( + Commands.runOnce(() -> elevator.setPosition(() -> elevatorHeight)), + elevator.waitUntilAtGoal()); + } + + public Command setIntakeState(V3_EpsilonIntake intake) { + Commands.parallel(Command.runOnce(() -> intake.setGoal(intakeState), + () -> intake.atGoal())); + } + + public Command setManipulatorState(V3_EpsilonManipulator manipulator) { + return Commands.parallel( + Commands.runOnce(() -> manipulator.setManipulatorState(armState)), + manipulator.waitUntilPivotAtGoal()); + } + + public Command asCommand(ElevatorFSM elevator, V3_EpsilonManipulator manipulator, V3_EpsilonIntake intake) { + return Commands.parallel( + setElevatorHeight(elevator), + setManipulatorState(manipulator), + setIntakeState(intake) + ); + } + + public String toString() { + return key; + } + + public record SubsystemPoses( + ReefState elevatorHeight, + V3_EpsilonManipulatorConstants.PivotState manipulatorArmState, + V3_EpsilonIntakeConstants.IntakeState intakeState) { + + /** + * Creates a SubsystemPoses instance with default states (STOW for elevator, arm, and intake; + * OPENED for funnel). + */ + public SubsystemPoses() { + this(ReefState.STOW, + V3_EpsilonManipulatorConstants.PivotState.STOW_DOWN, + V3_EpsilonIntakeConstants.IntakeState.STOW); + } + } +} From 6c039052428007dc7895eb14e3e389536f0489cb Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sat, 9 Aug 2025 10:37:25 -0400 Subject: [PATCH 009/180] V3 superstructure initial --- .../superstructure/V3_SuperstructureActions.java | 8 -------- 1 file changed, 8 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java index 084e9b1d..4651a97c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java @@ -6,15 +6,7 @@ import lombok.Getter; public class V3_SuperstructureActions{ - - @Getter private final ReefState elevatorHeight; - @Getter private final V3_EpsilonManipulatorConstants.PivotState armState; - @Getter private final V3_EpsilonIntakeConstants.IntakeState intakeState; - - - - public record SubsystemActions( ReefState elevatorHeight, V3_EpsilonManipulatorConstants.PivotState manipulatorArmState, From 84d400fafcedafd836ff70e1875b794acf73dd73 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 9 Aug 2025 12:45:56 -0400 Subject: [PATCH 010/180] format and build --- .../v3_Epsilon/intake/V3_EpsilonIntake.java | 4 + .../manipulator/V3_EpsilonManipulatorIO.java | 3 +- .../V3_SuperstructureActions.java | 12 ++- .../V3_SuperstructureEdges.java | 2 +- .../V3_SuperstructurePoses.java | 79 +++++++++---------- 5 files changed, 47 insertions(+), 53 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java index 201db3a8..db678bd0 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java @@ -78,6 +78,10 @@ public void setPivotVoltage(double volts) { io.setPivotVoltage(volts); } + public Command waitUntilPivotAtGoal() { + return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::atGoal)); + } + public Command sysIdRoutine() { return Commands.sequence( Commands.runOnce(() -> isClosedLoop = false), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java index 5baaee28..378d44df 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java @@ -1,8 +1,7 @@ package frc.robot.subsystems.v3_Epsilon.manipulator; -import org.littletonrobotics.junction.AutoLog; - import edu.wpi.first.math.geometry.Rotation2d; +import org.littletonrobotics.junction.AutoLog; public interface V3_EpsilonManipulatorIO { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java index 4651a97c..4e84b1fe 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java @@ -3,13 +3,11 @@ import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; -import lombok.Getter; -public class V3_SuperstructureActions{ +public class V3_SuperstructureActions { - public record SubsystemActions( - ReefState elevatorHeight, - V3_EpsilonManipulatorConstants.PivotState manipulatorArmState, - V3_EpsilonIntakeConstants.IntakeState intakeState) { - } + public record SubsystemActions( + ReefState elevatorHeight, + V3_EpsilonManipulatorConstants.PivotState manipulatorArmState, + V3_EpsilonIntakeConstants.IntakeState intakeState) {} } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java index 168e6839..b79d7a55 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java @@ -1,5 +1,5 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; public class V3_SuperstructureEdges { - // Will add code later once all edges are set in stone + // Will add code later once all edges are set in stone } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java index 5b28e777..13c164ec 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java @@ -2,15 +2,9 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; -import edu.wpi.first.wpilibj2.command.Subsystem; import frc.robot.FieldConstants.Reef.ReefState; -import frc.robot.subsystems.shared.elevator.Elevator; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; -import frc.robot.subsystems.shared.funnel.FunnelConstants.FunnelState; -import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructurePose; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructurePose.SubsystemPoses; -import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntakeConstants.IntakeExtensionState; -import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; @@ -18,50 +12,48 @@ import lombok.Getter; public class V3_SuperstructurePoses { - private String key; + private String key; - @Getter private final ReefState elevatorHeight; - @Getter private final V3_EpsilonManipulatorConstants.PivotState armState; - @Getter private final V3_EpsilonIntakeConstants.IntakeState intakeState; + @Getter private final ReefState elevatorHeight; + @Getter private final V3_EpsilonManipulatorConstants.PivotState armState; + @Getter private final V3_EpsilonIntakeConstants.IntakeState intakeState; - public V3_SuperstructurePoses(String key, SubsystemPoses poses) { - this.key = key; + public V3_SuperstructurePoses(String key, SubsystemPoses poses) { + this.key = key; - this.elevatorHeight = poses.elevatorHeight(); - this.armState = poses.manipulatorArmState(); - this.intakeState = poses.intakeState(); - } + this.elevatorHeight = poses.elevatorHeight(); + this.armState = poses.manipulatorArmState(); + this.intakeState = poses.intakeState(); + } - public Command setElevatorHeight(ElevatorFSM elevator) { - return Commands.parallel( - Commands.runOnce(() -> elevator.setPosition(() -> elevatorHeight)), - elevator.waitUntilAtGoal()); - } + public Command setElevatorHeight(ElevatorFSM elevator) { + return Commands.parallel( + Commands.runOnce(() -> elevator.setPosition(() -> elevatorHeight)), + elevator.waitUntilAtGoal()); + } - public Command setIntakeState(V3_EpsilonIntake intake) { - Commands.parallel(Command.runOnce(() -> intake.setGoal(intakeState), - () -> intake.atGoal())); - } + public Command setIntakeState(V3_EpsilonIntake intake) { + return Commands.parallel( + Commands.runOnce(()->intake.setGoal(intakeState)), intake.waitUntilPivotAtGoal()); + } - public Command setManipulatorState(V3_EpsilonManipulator manipulator) { - return Commands.parallel( - Commands.runOnce(() -> manipulator.setManipulatorState(armState)), - manipulator.waitUntilPivotAtGoal()); - } + public Command setManipulatorState(V3_EpsilonManipulator manipulator) { + return Commands.parallel( + Commands.runOnce(() -> manipulator.setManipulatorState(armState)), + manipulator.waitUntilPivotAtGoal()); + } - public Command asCommand(ElevatorFSM elevator, V3_EpsilonManipulator manipulator, V3_EpsilonIntake intake) { - return Commands.parallel( - setElevatorHeight(elevator), - setManipulatorState(manipulator), - setIntakeState(intake) - ); - } - - public String toString() { + public Command asCommand( + ElevatorFSM elevator, V3_EpsilonManipulator manipulator, V3_EpsilonIntake intake) { + return Commands.parallel( + setElevatorHeight(elevator), setManipulatorState(manipulator), setIntakeState(intake)); + } + + public String toString() { return key; } - public record SubsystemPoses( + public record SubsystemPoses( ReefState elevatorHeight, V3_EpsilonManipulatorConstants.PivotState manipulatorArmState, V3_EpsilonIntakeConstants.IntakeState intakeState) { @@ -71,9 +63,10 @@ public record SubsystemPoses( * OPENED for funnel). */ public SubsystemPoses() { - this(ReefState.STOW, - V3_EpsilonManipulatorConstants.PivotState.STOW_DOWN, - V3_EpsilonIntakeConstants.IntakeState.STOW); + this( + ReefState.STOW, + V3_EpsilonManipulatorConstants.PivotState.STOW_DOWN, + V3_EpsilonIntakeConstants.IntakeState.STOW); } } } From e2c9f63306397c5ba8ced4208b2ea45af245031b Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sat, 9 Aug 2025 12:54:43 -0400 Subject: [PATCH 011/180] Added comments --- .../V3_SuperstructurePoses.java | 43 ++++++++++++++++++- 1 file changed, 41 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java index 13c164ec..8efa2d18 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java @@ -4,7 +4,6 @@ import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; -import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructurePose.SubsystemPoses; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; @@ -26,33 +25,73 @@ public V3_SuperstructurePoses(String key, SubsystemPoses poses) { this.intakeState = poses.intakeState(); } + /** + * Creates a command to set the elevator to the specified height for this pose. + * @param elevator + * @return + */ + public Command setElevatorHeight(ElevatorFSM elevator) { return Commands.parallel( Commands.runOnce(() -> elevator.setPosition(() -> elevatorHeight)), elevator.waitUntilAtGoal()); } + /** + * Creates a command to set the intake to the specified state for this pose. + * @param intake + * @return + */ + public Command setIntakeState(V3_EpsilonIntake intake) { return Commands.parallel( - Commands.runOnce(()->intake.setGoal(intakeState)), intake.waitUntilPivotAtGoal()); + Commands.runOnce(() -> intake.setGoal(intakeState)), intake.waitUntilPivotAtGoal()); } + /** + * Creates a command to set the manipulator arm to the specified state for this pose. + * This command will also wait until the manipulator arm reaches its goal position. + * @param manipulator + * @return + */ + public Command setManipulatorState(V3_EpsilonManipulator manipulator) { return Commands.parallel( Commands.runOnce(() -> manipulator.setManipulatorState(armState)), manipulator.waitUntilPivotAtGoal()); } + /** + * Creates a command that sets the elevator, manipulator, and intake to their respective states + * defined in this pose. This command runs all three subsystem commands in parallel. + * @param elevator + * @param manipulator + * @param intake + * @return + */ + public Command asCommand( ElevatorFSM elevator, V3_EpsilonManipulator manipulator, V3_EpsilonIntake intake) { return Commands.parallel( setElevatorHeight(elevator), setManipulatorState(manipulator), setIntakeState(intake)); } + /** + * Returns a string representation of this pose, which is simply the key. + * This is useful for debugging and logging purposes. + * @return A string representation of the pose. + */ + public String toString() { return key; } + /** + * A record that holds the states of the subsystems (elevator, manipulator arm, and intake) + * for a specific superstructure pose. This record is used to encapsulate the states + * of the subsystems in a single object, making it easier to manage and pass around. + */ + public record SubsystemPoses( ReefState elevatorHeight, V3_EpsilonManipulatorConstants.PivotState manipulatorArmState, From fde1009ca78a7eed5139c8043a39102ab34567fe Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sat, 9 Aug 2025 17:35:31 -0400 Subject: [PATCH 012/180] Finished with V3_EpsilonSuperstructureActions --- .../manipulator/V2_RedundancyManipulator.java | 3 +- .../v3_Epsilon/intake/V3_EpsilonIntake.java | 29 +++++++++++++ .../intake/V3_EpsilonIntakeConstants.java | 13 ++++++ .../manipulator/V3_EpsilonManipulator.java | 20 ++++++++- .../V3_EpsilonManipulatorConstants.java | 19 +++++++++ .../V3_SuperstructureActions.java | 42 +++++++++++++++++-- .../V3_SuperstructureStates.java | 5 +++ 7 files changed, 124 insertions(+), 7 deletions(-) create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java diff --git a/src/main/java/frc/robot/subsystems/v2_Redundancy/superstructure/manipulator/V2_RedundancyManipulator.java b/src/main/java/frc/robot/subsystems/v2_Redundancy/superstructure/manipulator/V2_RedundancyManipulator.java index 22cd2649..b71bc242 100644 --- a/src/main/java/frc/robot/subsystems/v2_Redundancy/superstructure/manipulator/V2_RedundancyManipulator.java +++ b/src/main/java/frc/robot/subsystems/v2_Redundancy/superstructure/manipulator/V2_RedundancyManipulator.java @@ -77,8 +77,7 @@ public Rotation2d getArmAngle() { return inputs.armPosition; } - public void setRollerGoal(ManipulatorRollerState goal) { - rollerGoal = goal; + public void setRollerGoal(ManipulatorRollerState rollerGoal) { if (RobotState.isHasAlgae() && Set.of( ManipulatorRollerState.STOP, diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java index db678bd0..c56bcaac 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java @@ -2,12 +2,16 @@ import static edu.wpi.first.units.Units.*; +import java.util.Set; + +import edu.wpi.first.math.MathUtil; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants.IntakeState; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; import lombok.Getter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; @@ -93,4 +97,29 @@ public Command sysIdRoutine() { Commands.waitSeconds(0.25), Commands.runOnce(() -> characterizationRoutine.dynamic(Direction.kReverse))); } + + private double holdVoltage() { + double y; + double x = Math.abs(inputs.rollerTorqueCurrentAmps); + if (x <= 20) { + y = -0.0003 * Math.pow(x, 3) + 0.0124286 * Math.pow(x, 2) - 0.241071 * x + 4.00643; + } else { + y = 0.0005 * Math.pow(x, 2) - 0.1015 * x + 3.7425; + } + return MathUtil.clamp( + 1.25 * y, + 0.10, + V3_EpsilonManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().getAsDouble() / 1.5); + } + + public void setRollerGoal(V3_EpsilonIntakeConstants.IntakeRollerStates rollerGoal) { + if (hasCoral() && Set.of( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.CORAL_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP).contains(rollerGoal)) { + + io.setRollerVoltage(holdVoltage()); + } else { + io.setRollerVoltage(rollerGoal.getVoltage()); + } + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java index a10cf1b7..84778ab2 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java @@ -69,4 +69,17 @@ public static record IntakeParems( double MASS_KG, Rotation2d MIN_ANGLE, Rotation2d MAX_ANGLE) {} + + // Will add more states later + @RequiredArgsConstructor + public static enum IntakeRollerStates { + STOP(0.0), + CORAL_INTAKE(6.0); + + private final double voltage; + + public double getVoltage() { + return voltage; + } + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java index 0fd4fdd9..a051658c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java @@ -1,5 +1,7 @@ package frc.robot.subsystems.v3_Epsilon.manipulator; +import java.util.Set; + import static edu.wpi.first.units.Units.*; import edu.wpi.first.math.MathUtil; @@ -10,9 +12,13 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants.PivotState; + import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; +import edu.wpi.first.units.measure.Voltage; +import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; + public class V3_EpsilonManipulator extends SubsystemBase { private final V3_EpsilonManipulatorIO io; private final ManipulatorIOInputsAutoLogged inputs; @@ -159,4 +165,16 @@ public void setSlot() { public void setManipulatorState(V3_EpsilonManipulatorConstants.PivotState state) { io.setManipulatorState(state); } -} + + public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerStates rollerGoal) { + if (hasAlgae() && Set.of( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.ALGAE_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.CORAL_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP).contains(rollerGoal)) { + + io.setRollerVoltage(holdVoltage()); + } else { + io.setRollerVoltage(rollerGoal.getVoltage()); + } + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java index fd975e79..b0fce6bb 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java @@ -2,9 +2,12 @@ import com.ctre.phoenix6.configs.SlotConfigs; import com.ctre.phoenix6.signals.GravityTypeValue; + import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.util.Units; +import edu.wpi.first.units.measure.Voltage; +import frc.robot.subsystems.v1_StackUp.manipulator.V1_StackUpManipulatorConstants; import frc.robot.util.LoggedTunableNumber; import lombok.RequiredArgsConstructor; @@ -153,4 +156,20 @@ public Rotation2d getAngle() { return angle; } } + + // Will add more states later + @RequiredArgsConstructor + public static enum ManipulatorRollerStates { + STOP(0.0), + CORAL_INTAKE(6.0), + ALGAE_INTAKE(12.0) + + private final double voltage; + + public double getVoltage() { + return voltage; + } + } + + } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java index 4e84b1fe..e4356d3b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java @@ -1,13 +1,47 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; import frc.robot.FieldConstants.Reef.ReefState; +import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; +import lombok.Getter; public class V3_SuperstructureActions { + + @Getter private final V3_EpsilonManipulatorConstants.ManipulatorRollerStates manipulatorRollerState; + @Getter private final V3_EpsilonIntakeConstants.IntakeRollerStates intakeRollerStates; - public record SubsystemActions( - ReefState elevatorHeight, - V3_EpsilonManipulatorConstants.PivotState manipulatorArmState, - V3_EpsilonIntakeConstants.IntakeState intakeState) {} + public V3_SuperstructureActions(String key, SubsystemActions subsystemActions) { + this.manipulatorRollerState = V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP; + this.intakeRollerStates = V3_EpsilonIntakeConstants.IntakeRollerStates.STOP; + } + + public void runManipulator(V3_EpsilonManipulator manipulator) { + manipulator.setRollerGoal(manipulatorRollerState); + } + + public void runIntake(V3_EpsilonIntake intake) { + intake.setRollerGoal(intakeRollerStates); + } + + public void get(V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { + // Run all actions simultaneously + runIntake(intake); + runManipulator(manipulator); + } + + public record SubsystemActions ( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates manipulatorRollerState, + V3_EpsilonIntakeConstants.IntakeRollerStates intakeRollerStates + ) { + + public static SubsystemActions empty() { + return new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP, + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP + ); + } + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java new file mode 100644 index 00000000..4c4a3375 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -0,0 +1,5 @@ +package frc.robot.subsystems.v3_Epsilon.superstructure; + +public enum V3_SuperstructureStates { + // Start when actions are finishedf +} From 56f84b72d1e84b2ec82ee671a843fcec1248db6d Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sat, 9 Aug 2025 17:43:50 -0400 Subject: [PATCH 013/180] Started V3_SuperstructureStates --- .../V3_SuperstructureStates.java | 30 ++++++++++++++++++- 1 file changed, 29 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index 4c4a3375..6fc4bbf1 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -1,5 +1,33 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; +import edu.wpi.first.wpilibj2.command.Subsystem; // Adjust the package path as needed +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureActions.SubsystemActions; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructurePoses.SubsystemPoses; // Ensure this is the correct package path + public enum V3_SuperstructureStates { - // Start when actions are finishedf + START("START", new SubsystemPoses(), SubsystemActions.empty()), + STOW_DOWN("STOW_DOWN", new SubsystemPoses(), SubsystemActions.empty()), + STOW_UP("STOW_UP", new SubsystemPoses(), SubsystemActions.empty()); + + private final String name; + private final SubsystemPoses pose; + private final SubsystemActions action; + + V3_SuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { + this.name = name; + this.pose = pose; + this.action = action; + } + + public String getName() { + return name; + } + + public SubsystemPoses getPose() { + return pose; + } + + public SubsystemActions getAction() { + return action; + } } From 6a6488bbab327af1ca9c5bb35865ac145bae38cb Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sat, 9 Aug 2025 18:11:37 -0400 Subject: [PATCH 014/180] Fixed a bunch of errors --> hopefully no build errors --- .../v3_Epsilon/intake/V3_EpsilonIntake.java | 15 ++++---- .../intake/V3_EpsilonIntakeConstants.java | 2 +- .../manipulator/V3_EpsilonManipulator.java | 23 ++++++------ .../V3_EpsilonManipulatorConstants.java | 16 ++++----- .../V3_SuperstructureActions.java | 20 +++++------ .../V3_SuperstructurePoses.java | 25 +++++++------ .../V3_SuperstructureStates.java | 36 +++++++------------ 7 files changed, 59 insertions(+), 78 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java index c56bcaac..4696f390 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java @@ -2,8 +2,6 @@ import static edu.wpi.first.units.Units.*; -import java.util.Set; - import edu.wpi.first.math.MathUtil; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; @@ -12,6 +10,7 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants.IntakeState; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; +import java.util.Set; import lombok.Getter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; @@ -113,12 +112,14 @@ private double holdVoltage() { } public void setRollerGoal(V3_EpsilonIntakeConstants.IntakeRollerStates rollerGoal) { - if (hasCoral() && Set.of( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.CORAL_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP).contains(rollerGoal)) { - + if (hasCoral() + && Set.of( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.CORAL_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP) + .contains(rollerGoal)) { + io.setRollerVoltage(holdVoltage()); - } else { + } else { io.setRollerVoltage(rollerGoal.getVoltage()); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java index 84778ab2..993e3041 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java @@ -79,7 +79,7 @@ public static enum IntakeRollerStates { private final double voltage; public double getVoltage() { - return voltage; + return voltage; } } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java index a051658c..277f9afe 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java @@ -1,7 +1,5 @@ package frc.robot.subsystems.v3_Epsilon.manipulator; -import java.util.Set; - import static edu.wpi.first.units.Units.*; import edu.wpi.first.math.MathUtil; @@ -12,13 +10,10 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants.PivotState; - +import java.util.Set; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; -import edu.wpi.first.units.measure.Voltage; -import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; - public class V3_EpsilonManipulator extends SubsystemBase { private final V3_EpsilonManipulatorIO io; private final ManipulatorIOInputsAutoLogged inputs; @@ -167,14 +162,16 @@ public void setManipulatorState(V3_EpsilonManipulatorConstants.PivotState state) } public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerStates rollerGoal) { - if (hasAlgae() && Set.of( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.ALGAE_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.CORAL_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP).contains(rollerGoal)) { - + if (hasAlgae() + && Set.of( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.ALGAE_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.CORAL_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP) + .contains(rollerGoal)) { + io.setRollerVoltage(holdVoltage()); - } else { + } else { io.setRollerVoltage(rollerGoal.getVoltage()); } } -} \ No newline at end of file +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java index b0fce6bb..fe6e303e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java @@ -2,12 +2,9 @@ import com.ctre.phoenix6.configs.SlotConfigs; import com.ctre.phoenix6.signals.GravityTypeValue; - import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.util.Units; -import edu.wpi.first.units.measure.Voltage; -import frc.robot.subsystems.v1_StackUp.manipulator.V1_StackUpManipulatorConstants; import frc.robot.util.LoggedTunableNumber; import lombok.RequiredArgsConstructor; @@ -156,20 +153,21 @@ public Rotation2d getAngle() { return angle; } } - + // Will add more states later - @RequiredArgsConstructor public static enum ManipulatorRollerStates { STOP(0.0), - CORAL_INTAKE(6.0), - ALGAE_INTAKE(12.0) + CORAL_INTAKE(6.0), + ALGAE_INTAKE(12.0); private final double voltage; + ManipulatorRollerStates(double voltage) { + this.voltage = voltage; + } + public double getVoltage() { return voltage; } } - - } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java index e4356d3b..ad72a1d9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java @@ -1,16 +1,16 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; -import frc.robot.FieldConstants.Reef.ReefState; -import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; import lombok.Getter; public class V3_SuperstructureActions { - - @Getter private final V3_EpsilonManipulatorConstants.ManipulatorRollerStates manipulatorRollerState; + + @Getter + private final V3_EpsilonManipulatorConstants.ManipulatorRollerStates manipulatorRollerState; + @Getter private final V3_EpsilonIntakeConstants.IntakeRollerStates intakeRollerStates; public V3_SuperstructureActions(String key, SubsystemActions subsystemActions) { @@ -31,17 +31,15 @@ public void get(V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { runIntake(intake); runManipulator(manipulator); } - - public record SubsystemActions ( + + public record SubsystemActions( V3_EpsilonManipulatorConstants.ManipulatorRollerStates manipulatorRollerState, - V3_EpsilonIntakeConstants.IntakeRollerStates intakeRollerStates - ) { + V3_EpsilonIntakeConstants.IntakeRollerStates intakeRollerStates) { public static SubsystemActions empty() { return new SubsystemActions( V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP, - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP - ); + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP); } } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java index 8efa2d18..4fd57633 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java @@ -27,10 +27,10 @@ public V3_SuperstructurePoses(String key, SubsystemPoses poses) { /** * Creates a command to set the elevator to the specified height for this pose. + * * @param elevator * @return */ - public Command setElevatorHeight(ElevatorFSM elevator) { return Commands.parallel( Commands.runOnce(() -> elevator.setPosition(() -> elevatorHeight)), @@ -39,22 +39,22 @@ public Command setElevatorHeight(ElevatorFSM elevator) { /** * Creates a command to set the intake to the specified state for this pose. + * * @param intake * @return */ - public Command setIntakeState(V3_EpsilonIntake intake) { return Commands.parallel( Commands.runOnce(() -> intake.setGoal(intakeState)), intake.waitUntilPivotAtGoal()); } /** - * Creates a command to set the manipulator arm to the specified state for this pose. - * This command will also wait until the manipulator arm reaches its goal position. + * Creates a command to set the manipulator arm to the specified state for this pose. This command + * will also wait until the manipulator arm reaches its goal position. + * * @param manipulator * @return */ - public Command setManipulatorState(V3_EpsilonManipulator manipulator) { return Commands.parallel( Commands.runOnce(() -> manipulator.setManipulatorState(armState)), @@ -64,12 +64,12 @@ public Command setManipulatorState(V3_EpsilonManipulator manipulator) { /** * Creates a command that sets the elevator, manipulator, and intake to their respective states * defined in this pose. This command runs all three subsystem commands in parallel. + * * @param elevator * @param manipulator * @param intake * @return */ - public Command asCommand( ElevatorFSM elevator, V3_EpsilonManipulator manipulator, V3_EpsilonIntake intake) { return Commands.parallel( @@ -77,21 +77,20 @@ public Command asCommand( } /** - * Returns a string representation of this pose, which is simply the key. - * This is useful for debugging and logging purposes. + * Returns a string representation of this pose, which is simply the key. This is useful for + * debugging and logging purposes. + * * @return A string representation of the pose. */ - public String toString() { return key; } /** - * A record that holds the states of the subsystems (elevator, manipulator arm, and intake) - * for a specific superstructure pose. This record is used to encapsulate the states - * of the subsystems in a single object, making it easier to manage and pass around. + * A record that holds the states of the subsystems (elevator, manipulator arm, and intake) for a + * specific superstructure pose. This record is used to encapsulate the states of the subsystems + * in a single object, making it easier to manage and pass around. */ - public record SubsystemPoses( ReefState elevatorHeight, V3_EpsilonManipulatorConstants.PivotState manipulatorArmState, diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index 6fc4bbf1..823a1b1a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -1,33 +1,21 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; -import edu.wpi.first.wpilibj2.command.Subsystem; // Adjust the package path as needed +// Adjust the package path as needed import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureActions.SubsystemActions; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructurePoses.SubsystemPoses; // Ensure this is the correct package path public enum V3_SuperstructureStates { - START("START", new SubsystemPoses(), SubsystemActions.empty()), - STOW_DOWN("STOW_DOWN", new SubsystemPoses(), SubsystemActions.empty()), - STOW_UP("STOW_UP", new SubsystemPoses(), SubsystemActions.empty()); + START("START", new SubsystemPoses(), SubsystemActions.empty()), + STOW_DOWN("STOW_DOWN", new SubsystemPoses(), SubsystemActions.empty()), + STOW_UP("STOW_UP", new SubsystemPoses(), SubsystemActions.empty()); - private final String name; - private final SubsystemPoses pose; - private final SubsystemActions action; + private final String name; + private final SubsystemPoses pose; + private final SubsystemActions action; - V3_SuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { - this.name = name; - this.pose = pose; - this.action = action; - } - - public String getName() { - return name; - } - - public SubsystemPoses getPose() { - return pose; - } - - public SubsystemActions getAction() { - return action; - } + V3_SuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { + this.name = name; + this.pose = pose; + this.action = action; + } } From e843a3ab650cbd2eeabd01cb68503d49ea72b3df Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sat, 9 Aug 2025 18:14:21 -0400 Subject: [PATCH 015/180] Fixed another error --- .../v3_Epsilon/intake/V3_EpsilonIntakeConstants.java | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java index 993e3041..7b6e825a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java @@ -71,13 +71,17 @@ public static record IntakeParems( Rotation2d MAX_ANGLE) {} // Will add more states later - @RequiredArgsConstructor public static enum IntakeRollerStates { STOP(0.0), - CORAL_INTAKE(6.0); + CORAL_INTAKE(6.0), + ALGAE_INTAKE(12.0); private final double voltage; + IntakeRollerStates(double voltage) { + this.voltage = voltage; + } + public double getVoltage() { return voltage; } From e99085ae57f6e1f6a9b28bbddecd508ba7a40fe0 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sat, 9 Aug 2025 18:19:31 -0400 Subject: [PATCH 016/180] Added comments fo V3_SuperstructureActions --- .../V3_SuperstructureActions.java | 27 ++++++++++++++++--- 1 file changed, 24 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java index ad72a1d9..eda931cc 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java @@ -8,30 +8,51 @@ public class V3_SuperstructureActions { - @Getter - private final V3_EpsilonManipulatorConstants.ManipulatorRollerStates manipulatorRollerState; - + @Getter private final V3_EpsilonManipulatorConstants.ManipulatorRollerStates manipulatorRollerState; @Getter private final V3_EpsilonIntakeConstants.IntakeRollerStates intakeRollerStates; + /** + * Creates a new instance of V3_SuperstructureActions with the specified key and subsystem actions. + * @param key + * @param subsystemActions + */ + public V3_SuperstructureActions(String key, SubsystemActions subsystemActions) { this.manipulatorRollerState = V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP; this.intakeRollerStates = V3_EpsilonIntakeConstants.IntakeRollerStates.STOP; } + /** + * Runs the manipulator with the specified roller state. + * @param manipulator + */ public void runManipulator(V3_EpsilonManipulator manipulator) { manipulator.setRollerGoal(manipulatorRollerState); } + /** + * Runs the intake with the specified roller state. + * @param intake + */ public void runIntake(V3_EpsilonIntake intake) { intake.setRollerGoal(intakeRollerStates); } + /** + * Runs both the intake and manipulator simultaneously with their respective roller states. + * @param intake + * @param manipulator + */ public void get(V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { // Run all actions simultaneously runIntake(intake); runManipulator(manipulator); } + /** + * Represents the actions for the subsystems in the superstructure. + * This record holds the states for the manipulator roller and intake roller. + */ public record SubsystemActions( V3_EpsilonManipulatorConstants.ManipulatorRollerStates manipulatorRollerState, V3_EpsilonIntakeConstants.IntakeRollerStates intakeRollerStates) { From 3fb6ab60d6714f380ac6655891b2f336e6b62cdc Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sun, 10 Aug 2025 12:54:51 -0400 Subject: [PATCH 017/180] Worked on V3_SuperstructureStates --- .../superstructure/V3_SuperstructureStates.java | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index 823a1b1a..444f61ce 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -1,13 +1,20 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; // Adjust the package path as needed +import frc.robot.FieldConstants; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureActions.SubsystemActions; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructurePoses.SubsystemPoses; // Ensure this is the correct package path public enum V3_SuperstructureStates { START("START", new SubsystemPoses(), SubsystemActions.empty()), STOW_DOWN("STOW_DOWN", new SubsystemPoses(), SubsystemActions.empty()), - STOW_UP("STOW_UP", new SubsystemPoses(), SubsystemActions.empty()); + STOW_UP("STOW_UP", new SubsystemPoses( + FieldConstants.Reef.ReefState.STOW, + V3_EpsilonManipulatorConstants.PivotState.STOW_UP, + V3_EpsilonIntakeConstants.IntakeState.STOW + ), SubsystemActions.empty()); private final String name; private final SubsystemPoses pose; From 590c3c2706fbe80470ec265e0fff3838d51fbf0a Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sun, 10 Aug 2025 13:13:07 -0400 Subject: [PATCH 018/180] Added edge from L2_prep back to L2_transition and so on for L3 and L4 --- .../subsystems/v3_Epsilon/superstructure/Superstructure.dot | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index 2dd5d44d..d79ebff7 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -95,6 +95,10 @@ digraph Superstructure { L2_transition -> L2_prep [color = green] L3_transition -> L3_prep [color = green] L4_transition -> L4_prep [color = green] + + L2_prep -> L2_transition [color = green] + L3_prep -> L3_transition [color = green] + L4_prep -> L4_transition [color = green] # Algae Edges stow_up -> L2_algae_prep [color = blue] From 1f5eccb178e4556d4ee1e620e61abecb3e7ec2ec Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sun, 10 Aug 2025 13:14:46 -0400 Subject: [PATCH 019/180] Added comments for superstructure dot file for V3 --- .../subsystems/v3_Epsilon/superstructure/Superstructure.dot | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index d79ebff7..d2fdae14 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -40,10 +40,11 @@ digraph Superstructure { L2_transition [color = green] L3_transition [color = green] L4_transition [color = green] + # Transition states are inherently wait_for_elevator states but for different levels - intermediate_wait_for_elevator [color = green] + # Basic Handoff Edges stow_down -> stow_up [color = green] handoff -> stow_up [color = green] From 40a6204f9d76f16c461927b4baede690f6862d7e Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sun, 10 Aug 2025 13:29:41 -0400 Subject: [PATCH 020/180] Added more superstructure states for V3 --- .../V3_SuperstructureStates.java | 23 ++++++++++++++++++- 1 file changed, 22 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index 444f61ce..03c7811a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -14,7 +14,28 @@ public enum V3_SuperstructureStates { FieldConstants.Reef.ReefState.STOW, V3_EpsilonManipulatorConstants.PivotState.STOW_UP, V3_EpsilonIntakeConstants.IntakeState.STOW - ), SubsystemActions.empty()); + ), SubsystemActions.empty()), + + // Coral States - Setpoints + L1( + "L1", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L1, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.L1 + ), + SubsystemActions.empty() + ), + + L2( + "L2", new SubsystemPoses( + FieldConstants.Reef.ReefState.L2, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.L1 + ), + SubsystemActions.empty() + ); + private final String name; private final SubsystemPoses pose; From 43ec0616b1eeb55e0408f122607544747a29e85f Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sun, 10 Aug 2025 14:49:44 -0400 Subject: [PATCH 021/180] Added more states + updated manipulator constants for V3 --- .../V3_EpsilonManipulatorConstants.java | 7 +- .../V3_SuperstructureActions.java | 16 +++- .../V3_SuperstructureStates.java | 93 ++++++++++++++----- 3 files changed, 86 insertions(+), 30 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java index fe6e303e..94db87b4 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java @@ -158,7 +158,12 @@ public Rotation2d getAngle() { public static enum ManipulatorRollerStates { STOP(0.0), CORAL_INTAKE(6.0), - ALGAE_INTAKE(12.0); + ALGAE_INTAKE(12.0), + L4_SCORE(4.6 * 1.56), + SCORE_CORAL(4.8 * 1.56), + SCORE_ALGAE(-6), + REMOVE_ALGAE(-12), + L1_SCORE(3.5 * 1.56); private final double voltage; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java index eda931cc..f5fb9370 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java @@ -8,15 +8,18 @@ public class V3_SuperstructureActions { - @Getter private final V3_EpsilonManipulatorConstants.ManipulatorRollerStates manipulatorRollerState; + @Getter + private final V3_EpsilonManipulatorConstants.ManipulatorRollerStates manipulatorRollerState; + @Getter private final V3_EpsilonIntakeConstants.IntakeRollerStates intakeRollerStates; /** - * Creates a new instance of V3_SuperstructureActions with the specified key and subsystem actions. + * Creates a new instance of V3_SuperstructureActions with the specified key and subsystem + * actions. + * * @param key * @param subsystemActions */ - public V3_SuperstructureActions(String key, SubsystemActions subsystemActions) { this.manipulatorRollerState = V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP; this.intakeRollerStates = V3_EpsilonIntakeConstants.IntakeRollerStates.STOP; @@ -24,6 +27,7 @@ public V3_SuperstructureActions(String key, SubsystemActions subsystemActions) { /** * Runs the manipulator with the specified roller state. + * * @param manipulator */ public void runManipulator(V3_EpsilonManipulator manipulator) { @@ -32,6 +36,7 @@ public void runManipulator(V3_EpsilonManipulator manipulator) { /** * Runs the intake with the specified roller state. + * * @param intake */ public void runIntake(V3_EpsilonIntake intake) { @@ -40,6 +45,7 @@ public void runIntake(V3_EpsilonIntake intake) { /** * Runs both the intake and manipulator simultaneously with their respective roller states. + * * @param intake * @param manipulator */ @@ -50,8 +56,8 @@ public void get(V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { } /** - * Represents the actions for the subsystems in the superstructure. - * This record holds the states for the manipulator roller and intake roller. + * Represents the actions for the subsystems in the superstructure. This record holds the states + * for the manipulator roller and intake roller. */ public record SubsystemActions( V3_EpsilonManipulatorConstants.ManipulatorRollerStates manipulatorRollerState, diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index 03c7811a..ebcc426b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -10,32 +10,77 @@ public enum V3_SuperstructureStates { START("START", new SubsystemPoses(), SubsystemActions.empty()), STOW_DOWN("STOW_DOWN", new SubsystemPoses(), SubsystemActions.empty()), - STOW_UP("STOW_UP", new SubsystemPoses( - FieldConstants.Reef.ReefState.STOW, - V3_EpsilonManipulatorConstants.PivotState.STOW_UP, - V3_EpsilonIntakeConstants.IntakeState.STOW - ), SubsystemActions.empty()), - - // Coral States - Setpoints - L1( - "L1", + STOW_UP( + "STOW_UP", new SubsystemPoses( - FieldConstants.Reef.ReefState.L1, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.L1 - ), - SubsystemActions.empty() - ), - - L2( - "L2", new SubsystemPoses( - FieldConstants.Reef.ReefState.L2, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.L1 - ), - SubsystemActions.empty() - ); + FieldConstants.Reef.ReefState.STOW, + V3_EpsilonManipulatorConstants.PivotState.STOW_UP, + V3_EpsilonIntakeConstants.IntakeState.STOW), + SubsystemActions.empty()), + // Coral Prep States + L1_PREP( + "L1", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L1, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.L1), + SubsystemActions.empty()), + + L2_PREP( + "L2", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L2, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.L1), + SubsystemActions.empty()), + + L3_PREP( + "L3", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L3, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.L1), + SubsystemActions.empty()), + + L4_PREP( + "L4", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L4, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.L1), + SubsystemActions.empty()), + + // Coral Score States + L1_SCORE( + "L1_SCORE", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L1, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.L1), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), + + L2_SCORE( + "L2_SCORE", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L2, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.L1), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), + + L3_SCORE( + "L3_SCORE", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L3, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.L1), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)); private final String name; private final SubsystemPoses pose; From b0250237ff13f0686f7c997355aab0b2f482a3b2 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sun, 10 Aug 2025 19:52:21 -0400 Subject: [PATCH 022/180] Changed intake states to STOW for L1, 2, 3, 4 PREP --- .../v3_Epsilon/superstructure/V3_SuperstructureStates.java | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index ebcc426b..da8b182a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -32,7 +32,7 @@ public enum V3_SuperstructureStates { new SubsystemPoses( FieldConstants.Reef.ReefState.L2, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.L1), + V3_EpsilonIntakeConstants.IntakeState.STOW), SubsystemActions.empty()), L3_PREP( @@ -40,7 +40,7 @@ public enum V3_SuperstructureStates { new SubsystemPoses( FieldConstants.Reef.ReefState.L3, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.L1), + V3_EpsilonIntakeConstants.IntakeState.STOW), SubsystemActions.empty()), L4_PREP( @@ -48,7 +48,7 @@ public enum V3_SuperstructureStates { new SubsystemPoses( FieldConstants.Reef.ReefState.L4, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.L1), + V3_EpsilonIntakeConstants.IntakeState.STOW), SubsystemActions.empty()), // Coral Score States From 65407b882bd4dc49f4cbd24bcc324a7df4529ebf Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sun, 10 Aug 2025 19:57:03 -0400 Subject: [PATCH 023/180] Updated states for V3 superstructure --- .../v3_Epsilon/intake/V3_EpsilonIntakeConstants.java | 3 ++- .../superstructure/V3_SuperstructureStates.java | 8 ++++---- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java index 7b6e825a..a9cea76e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java @@ -74,7 +74,8 @@ public static record IntakeParems( public static enum IntakeRollerStates { STOP(0.0), CORAL_INTAKE(6.0), - ALGAE_INTAKE(12.0); + ALGAE_INTAKE(12.0), + SCORE_CORAL(6.0); private final double voltage; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index da8b182a..62a694dc 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -59,15 +59,15 @@ public enum V3_SuperstructureStates { V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, V3_EpsilonIntakeConstants.IntakeState.L1), new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP, + V3_EpsilonIntakeConstants.IntakeRollerStates.SCORE_CORAL)), L2_SCORE( "L2_SCORE", new SubsystemPoses( FieldConstants.Reef.ReefState.L2, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.L1), + V3_EpsilonIntakeConstants.IntakeState.STOW), new SubsystemActions( V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), @@ -77,7 +77,7 @@ public enum V3_SuperstructureStates { new SubsystemPoses( FieldConstants.Reef.ReefState.L3, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.L1), + V3_EpsilonIntakeConstants.IntakeState.STOW), new SubsystemActions( V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)); From 74d6d612b9108b94be4521290018ce7c4de5206c Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sun, 10 Aug 2025 22:50:21 -0400 Subject: [PATCH 024/180] Will work on more states for V3 later. This is a good baseline for now --- src/main/java/frc/robot/FieldConstants.java | 4 +- .../V3_SuperstructureStates.java | 91 ++++++++++++++++++- 2 files changed, 92 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/FieldConstants.java b/src/main/java/frc/robot/FieldConstants.java index c85ad048..4bf7eea8 100644 --- a/src/main/java/frc/robot/FieldConstants.java +++ b/src/main/java/frc/robot/FieldConstants.java @@ -60,8 +60,8 @@ public static enum ReefState { CORAL_INTAKE, ALGAE_FLOOR_INTAKE, ALGAE_MID, - ASS_TOP, - ASS_BOT, + ASS_TOP, + ASS_BOT, ALGAE_INTAKE_TOP, ALGAE_INTAKE_BOTTOM, L1, diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index 62a694dc..6da9be75 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -80,7 +80,96 @@ public enum V3_SuperstructureStates { V3_EpsilonIntakeConstants.IntakeState.STOW), new SubsystemActions( V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)); + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), + + L4_SCORE( + "L4_SCORE", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L4, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, // Determine whether PRE_SCORE is accurate for all scoring states + V3_EpsilonIntakeConstants.IntakeState.STOW), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP) + ), + + // Algae Prep States + L2_ALGAE_PREP( + "L2_ALGAE_PREP", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L2, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.STOW), + SubsystemActions.empty()), + + L3_ALGAE_PREP( + "L3_ALGAE_PREP", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L3, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.STOW), + SubsystemActions.empty()), + + // Algae Scoring States + L2_ALGAE_SCORE( + "L2_ALGAE_SCORE", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L2, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.STOW), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), + + L3_ALGAE_SCORE( + "L3_ALGAE_SCORE", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L3, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.STOW), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), + + // Miscelaneous States (Barge + Processor) + BARGE_PREP( + "BARGE_PREP", + new SubsystemPoses( + FieldConstants.Reef.ReefState.ASS_TOP, + V3_EpsilonManipulatorConstants.PivotState.REEF_INTAKE, // Assuming REEF_INTAKE and BARGE_PREP have same rotation values + V3_EpsilonIntakeConstants.IntakeState.STOW), + SubsystemActions.empty()), + + PROCESSOR_PREP( + "PROCESSOR_PREP", + new SubsystemPoses( + FieldConstants.Reef.ReefState.ASS_BOT, + V3_EpsilonManipulatorConstants.PivotState.PROCESSOR, + V3_EpsilonIntakeConstants.IntakeState.STOW), + SubsystemActions.empty()), + + BARGE_SCORE( + "BARGE_SCORE", + new SubsystemPoses( + FieldConstants.Reef.ReefState.ASS_TOP, // Assuming ASS_TOP is the max height the elevator can reach. Check later + V3_EpsilonManipulatorConstants.PivotState.REEF_INTAKE, + V3_EpsilonIntakeConstants.IntakeState.STOW), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, // Assuming you score in the barge by stowing intake and moving manipulator to desired position and then scoring + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP + )), + + PROCESSOR_SCORE( + "PROCESSOR_SCORE", + new SubsystemPoses( + FieldConstants.Reef.ReefState.ASS_BOT, + V3_EpsilonManipulatorConstants.PivotState.PROCESSOR, + V3_EpsilonIntakeConstants.IntakeState.STOW + ), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP + )); private final String name; private final SubsystemPoses pose; From a875a7d19a24782c2c5c3428e8432d3e1c4e7c71 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Mon, 11 Aug 2025 18:01:31 -0400 Subject: [PATCH 025/180] Finished superstructure states baseline for V3! (Added transition states) --- .../V3_EpsilonManipulatorConstants.java | 1 + .../V3_SuperstructureStates.java | 35 +++++++++++++++++-- 2 files changed, 33 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java index 94db87b4..959dbc38 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java @@ -145,6 +145,7 @@ public static enum PivotState { INTAKE_OUT_LINE(Rotation2d.fromDegrees(-61)), FLOOR_INTAKE(Rotation2d.fromDegrees(-68.5 - 5)), STOW_LINE(Rotation2d.fromDegrees(-75)), + TRANSITION(Rotation2d.fromDegrees(-32)), // Placeholder value. Make sure to test STOW_DOWN(Rotation2d.fromDegrees(-77)); private final Rotation2d angle; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index 6da9be75..24a4ba8d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -151,7 +151,7 @@ public enum V3_SuperstructureStates { BARGE_SCORE( "BARGE_SCORE", new SubsystemPoses( - FieldConstants.Reef.ReefState.ASS_TOP, // Assuming ASS_TOP is the max height the elevator can reach. Check later + FieldConstants.Reef.ReefState.ALGAE_SCORE, // Assuming ASS_TOP is the max height the elevator can reach. Check later V3_EpsilonManipulatorConstants.PivotState.REEF_INTAKE, V3_EpsilonIntakeConstants.IntakeState.STOW), new SubsystemActions( @@ -162,14 +162,43 @@ public enum V3_SuperstructureStates { PROCESSOR_SCORE( "PROCESSOR_SCORE", new SubsystemPoses( - FieldConstants.Reef.ReefState.ASS_BOT, + FieldConstants.Reef.ReefState.ALGAE_SCORE, V3_EpsilonManipulatorConstants.PivotState.PROCESSOR, V3_EpsilonIntakeConstants.IntakeState.STOW ), new SubsystemActions( V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, V3_EpsilonIntakeConstants.IntakeRollerStates.STOP - )); + )), + + // Transition States + L2_TRANSITION( + "L2_TRANSITION", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L2, + V3_EpsilonManipulatorConstants.PivotState.TRANSITION, + V3_EpsilonIntakeConstants.IntakeState.STOW + ), SubsystemActions.empty()), + + L3_TRANSITION( + "L3_TRANSITION", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L3, + V3_EpsilonManipulatorConstants.PivotState.TRANSITION, + V3_EpsilonIntakeConstants.IntakeState.STOW + ), + SubsystemActions.empty() + ), + + L4_TRANSITION( + "L4_TRANSITION", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L4, + V3_EpsilonManipulatorConstants.PivotState.TRANSITION, + V3_EpsilonIntakeConstants.IntakeState.STOW + ), + SubsystemActions.empty() + ); private final String name; private final SubsystemPoses pose; From 4cfaa4f8e2249b38f3494395981d98fe538927e5 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Mon, 11 Aug 2025 20:36:00 -0400 Subject: [PATCH 026/180] Added comments for V3_SuperstructureStates and methods --- .../V3_SuperstructureStates.java | 61 ++++++++++++++++--- 1 file changed, 51 insertions(+), 10 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index 24a4ba8d..445bd723 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -5,7 +5,8 @@ import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureActions.SubsystemActions; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructurePoses.SubsystemPoses; // Ensure this is the correct package path +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructurePoses.SubsystemPoses; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructurePoses; // Ensure this is the correct package path public enum V3_SuperstructureStates { START("START", new SubsystemPoses(), SubsystemActions.empty()), @@ -131,7 +132,7 @@ public enum V3_SuperstructureStates { V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), - // Miscelaneous States (Barge + Processor) + // Miscelaneous States (Barge + Processor Prep and Score States) BARGE_PREP( "BARGE_PREP", new SubsystemPoses( @@ -151,11 +152,11 @@ public enum V3_SuperstructureStates { BARGE_SCORE( "BARGE_SCORE", new SubsystemPoses( - FieldConstants.Reef.ReefState.ALGAE_SCORE, // Assuming ASS_TOP is the max height the elevator can reach. Check later + FieldConstants.Reef.ReefState.ALGAE_SCORE, V3_EpsilonManipulatorConstants.PivotState.REEF_INTAKE, V3_EpsilonIntakeConstants.IntakeState.STOW), new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, // Assuming you score in the barge by stowing intake and moving manipulator to desired position and then scoring + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, // Assuming you score in the barge by stowing intake and moving manipulator to desired position V3_EpsilonIntakeConstants.IntakeRollerStates.STOP )), @@ -180,7 +181,7 @@ public enum V3_SuperstructureStates { V3_EpsilonIntakeConstants.IntakeState.STOW ), SubsystemActions.empty()), - L3_TRANSITION( + L3_TRANSITION( "L3_TRANSITION", new SubsystemPoses( FieldConstants.Reef.ReefState.L3, @@ -190,7 +191,7 @@ public enum V3_SuperstructureStates { SubsystemActions.empty() ), - L4_TRANSITION( + L4_TRANSITION( "L4_TRANSITION", new SubsystemPoses( FieldConstants.Reef.ReefState.L4, @@ -200,13 +201,53 @@ public enum V3_SuperstructureStates { SubsystemActions.empty() ); + // Readable name for state private final String name; - private final SubsystemPoses pose; - private final SubsystemActions action; + // Target positions for all subsystems in this state + private final SubsystemPoses subsystemPoses; + + // Actions to perform for all subsystems in this state + private final SubsystemActions subsystemActions; + + /** + * Constructor for V3_SuperstructureStates. + * + * @param name The name of the state. + * @param pose The subsystem poses for this state. + * @param action The subsystem actions for this state. + */ V3_SuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { this.name = name; - this.pose = pose; - this.action = action; + this.subsystemPoses = pose; + this.subsystemActions = action; + } + + /** + * Constructor for V3_SuperstructureStates with empty actions. + * + * @param name The name of the state. + * @param pose The subsystem poses for this state. + */ + public V3_SuperstructurePoses getPose() { + return new V3_SuperstructurePoses(name, subsystemPoses); + } + + /** + * Returns the actions associated with this superstructure state. + * + * @return The actions for this state. + */ + public V3_SuperstructureActions getActions() { + return new V3_SuperstructureActions(name, subsystemActions); + } + + /** + * Returns the name of the superstructure state. + * + * @return The name of the state. + */ + public String getName() { + return name; } } From 4ba1c3f0881ea86b6f12a84feff23882284c90c3 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Mon, 11 Aug 2025 20:37:27 -0400 Subject: [PATCH 027/180] Changes --- src/main/java/frc/robot/FieldConstants.java | 4 +- .../V3_SuperstructureStates.java | 269 +++++++++--------- 2 files changed, 136 insertions(+), 137 deletions(-) diff --git a/src/main/java/frc/robot/FieldConstants.java b/src/main/java/frc/robot/FieldConstants.java index 4bf7eea8..c85ad048 100644 --- a/src/main/java/frc/robot/FieldConstants.java +++ b/src/main/java/frc/robot/FieldConstants.java @@ -60,8 +60,8 @@ public static enum ReefState { CORAL_INTAKE, ALGAE_FLOOR_INTAKE, ALGAE_MID, - ASS_TOP, - ASS_BOT, + ASS_TOP, + ASS_BOT, ALGAE_INTAKE_TOP, ALGAE_INTAKE_BOTTOM, L1, diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index 445bd723..3acf3de9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -6,7 +6,10 @@ import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureActions.SubsystemActions; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructurePoses.SubsystemPoses; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructurePoses; // Ensure this is the correct package path +// Ensure this is the + +// correct package +// path public enum V3_SuperstructureStates { START("START", new SubsystemPoses(), SubsystemActions.empty()), @@ -43,7 +46,7 @@ public enum V3_SuperstructureStates { V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, V3_EpsilonIntakeConstants.IntakeState.STOW), SubsystemActions.empty()), - + L4_PREP( "L4", new SubsystemPoses( @@ -64,142 +67,138 @@ public enum V3_SuperstructureStates { V3_EpsilonIntakeConstants.IntakeRollerStates.SCORE_CORAL)), L2_SCORE( - "L2_SCORE", - new SubsystemPoses( - FieldConstants.Reef.ReefState.L2, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), + "L2_SCORE", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L2, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.STOW), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), L3_SCORE( - "L3_SCORE", - new SubsystemPoses( - FieldConstants.Reef.ReefState.L3, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), + "L3_SCORE", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L3, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.STOW), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), L4_SCORE( - "L4_SCORE", - new SubsystemPoses( - FieldConstants.Reef.ReefState.L4, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, // Determine whether PRE_SCORE is accurate for all scoring states - V3_EpsilonIntakeConstants.IntakeState.STOW), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP) - ), + "L4_SCORE", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L4, + V3_EpsilonManipulatorConstants.PivotState + .PRE_SCORE, // Determine whether PRE_SCORE is accurate for all scoring states + V3_EpsilonIntakeConstants.IntakeState.STOW), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), // Algae Prep States L2_ALGAE_PREP( - "L2_ALGAE_PREP", - new SubsystemPoses( - FieldConstants.Reef.ReefState.L2, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), + "L2_ALGAE_PREP", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L2, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.STOW), + SubsystemActions.empty()), L3_ALGAE_PREP( - "L3_ALGAE_PREP", - new SubsystemPoses( - FieldConstants.Reef.ReefState.L3, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), + "L3_ALGAE_PREP", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L3, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.STOW), + SubsystemActions.empty()), // Algae Scoring States L2_ALGAE_SCORE( - "L2_ALGAE_SCORE", - new SubsystemPoses( - FieldConstants.Reef.ReefState.L2, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), - + "L2_ALGAE_SCORE", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L2, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.STOW), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), + L3_ALGAE_SCORE( - "L3_ALGAE_SCORE", - new SubsystemPoses( - FieldConstants.Reef.ReefState.L3, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), + "L3_ALGAE_SCORE", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L3, + V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, + V3_EpsilonIntakeConstants.IntakeState.STOW), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), // Miscelaneous States (Barge + Processor Prep and Score States) BARGE_PREP( - "BARGE_PREP", - new SubsystemPoses( - FieldConstants.Reef.ReefState.ASS_TOP, - V3_EpsilonManipulatorConstants.PivotState.REEF_INTAKE, // Assuming REEF_INTAKE and BARGE_PREP have same rotation values - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), + "BARGE_PREP", + new SubsystemPoses( + FieldConstants.Reef.ReefState.ASS_TOP, + V3_EpsilonManipulatorConstants.PivotState + .REEF_INTAKE, // Assuming REEF_INTAKE and BARGE_PREP have same rotation values + V3_EpsilonIntakeConstants.IntakeState.STOW), + SubsystemActions.empty()), PROCESSOR_PREP( - "PROCESSOR_PREP", - new SubsystemPoses( - FieldConstants.Reef.ReefState.ASS_BOT, - V3_EpsilonManipulatorConstants.PivotState.PROCESSOR, - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), + "PROCESSOR_PREP", + new SubsystemPoses( + FieldConstants.Reef.ReefState.ASS_BOT, + V3_EpsilonManipulatorConstants.PivotState.PROCESSOR, + V3_EpsilonIntakeConstants.IntakeState.STOW), + SubsystemActions.empty()), BARGE_SCORE( - "BARGE_SCORE", - new SubsystemPoses( - FieldConstants.Reef.ReefState.ALGAE_SCORE, - V3_EpsilonManipulatorConstants.PivotState.REEF_INTAKE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, // Assuming you score in the barge by stowing intake and moving manipulator to desired position - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP - )), - - PROCESSOR_SCORE( - "PROCESSOR_SCORE", - new SubsystemPoses( - FieldConstants.Reef.ReefState.ALGAE_SCORE, - V3_EpsilonManipulatorConstants.PivotState.PROCESSOR, - V3_EpsilonIntakeConstants.IntakeState.STOW - ), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP - )), - - // Transition States - L2_TRANSITION( - "L2_TRANSITION", - new SubsystemPoses( - FieldConstants.Reef.ReefState.L2, - V3_EpsilonManipulatorConstants.PivotState.TRANSITION, - V3_EpsilonIntakeConstants.IntakeState.STOW - ), SubsystemActions.empty()), - - L3_TRANSITION( - "L3_TRANSITION", - new SubsystemPoses( - FieldConstants.Reef.ReefState.L3, - V3_EpsilonManipulatorConstants.PivotState.TRANSITION, - V3_EpsilonIntakeConstants.IntakeState.STOW - ), - SubsystemActions.empty() - ), - - L4_TRANSITION( - "L4_TRANSITION", - new SubsystemPoses( - FieldConstants.Reef.ReefState.L4, - V3_EpsilonManipulatorConstants.PivotState.TRANSITION, - V3_EpsilonIntakeConstants.IntakeState.STOW - ), - SubsystemActions.empty() - ); + "BARGE_SCORE", + new SubsystemPoses( + FieldConstants.Reef.ReefState.ALGAE_SCORE, + V3_EpsilonManipulatorConstants.PivotState.REEF_INTAKE, + V3_EpsilonIntakeConstants.IntakeState.STOW), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates + .SCORE_ALGAE, // Assuming you score in the barge by stowing intake and moving + // manipulator to desired position + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), + + PROCESSOR_SCORE( + "PROCESSOR_SCORE", + new SubsystemPoses( + FieldConstants.Reef.ReefState.ALGAE_SCORE, + V3_EpsilonManipulatorConstants.PivotState.PROCESSOR, + V3_EpsilonIntakeConstants.IntakeState.STOW), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, + V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), + + // Transition States + L2_TRANSITION( + "L2_TRANSITION", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L2, + V3_EpsilonManipulatorConstants.PivotState.TRANSITION, + V3_EpsilonIntakeConstants.IntakeState.STOW), + SubsystemActions.empty()), + + L3_TRANSITION( + "L3_TRANSITION", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L3, + V3_EpsilonManipulatorConstants.PivotState.TRANSITION, + V3_EpsilonIntakeConstants.IntakeState.STOW), + SubsystemActions.empty()), + + L4_TRANSITION( + "L4_TRANSITION", + new SubsystemPoses( + FieldConstants.Reef.ReefState.L4, + V3_EpsilonManipulatorConstants.PivotState.TRANSITION, + V3_EpsilonIntakeConstants.IntakeState.STOW), + SubsystemActions.empty()); // Readable name for state private final String name; @@ -210,13 +209,13 @@ public enum V3_SuperstructureStates { // Actions to perform for all subsystems in this state private final SubsystemActions subsystemActions; - /** - * Constructor for V3_SuperstructureStates. - * - * @param name The name of the state. - * @param pose The subsystem poses for this state. - * @param action The subsystem actions for this state. - */ + /** + * Constructor for V3_SuperstructureStates. + * + * @param name The name of the state. + * @param pose The subsystem poses for this state. + * @param action The subsystem actions for this state. + */ V3_SuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { this.name = name; this.subsystemPoses = pose; @@ -233,20 +232,20 @@ public V3_SuperstructurePoses getPose() { return new V3_SuperstructurePoses(name, subsystemPoses); } - /** - * Returns the actions associated with this superstructure state. - * - * @return The actions for this state. - */ + /** + * Returns the actions associated with this superstructure state. + * + * @return The actions for this state. + */ public V3_SuperstructureActions getActions() { return new V3_SuperstructureActions(name, subsystemActions); } - /** - * Returns the name of the superstructure state. - * - * @return The name of the state. - */ + /** + * Returns the name of the superstructure state. + * + * @return The name of the state. + */ public String getName() { return name; } From 2b98fa887bd2385449df84e07e1c2f37b47d5479 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Tue, 12 Aug 2025 12:53:12 -0400 Subject: [PATCH 028/180] Worked on bare bones for V3 superstructure edges --- .../V3_SuperstructureEdges.java | 46 ++++++++++++++++++- 1 file changed, 45 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java index b79d7a55..396c5f33 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java @@ -1,5 +1,49 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; +import java.util.ArrayList; +import java.util.List; +import java.util.Map; +import lombok.Builder; +import lombok.Getter; +import org.jgrapht.Graph; +import org.jgrapht.graph.DefaultEdge; public class V3_SuperstructureEdges { - // Will add code later once all edges are set in stone + + public static final ArrayList AlgaeEdges = new ArrayList<>(); + public static final ArrayList CoralEdges = new ArrayList<>(); + + public record Edge(V3_SuperstructureStates from, V3_SuperstructureStates to, String action) { + public Edge(V3_SuperstructureStates from, V3_SuperstructureStates to) { + this(from, to, ""); + } + + public String toString() { + return String.format( + "Edge[from=%s, to=%s, action=%s]", from.name(), to.name(), action); + } + } + + public enum AlgaeEdge { + NONE, + NO_ALGAE, + ALGAE + } + + @Builder(toBuilder = true) + @Getter + public static class EdgeCommand extends DefaultEdge { + private final Command command; + @Builder.Default private final AlgaeEdge algaeEdgeType = AlgaeEdge.NONE; + } + + private static Command getEdgeCommand( + V3_SuperstructureStates from, V3_SuperstructureStates to, AlgaeEdge algaeEdgeType) { + return Command.builder() + .from(from) + .to(to) + .algaeEdgeType(algaeEdgeType) + .build(); + } + + } From 1dcb7fa8ae78ae60cd5f5c40ec43cee2e210ea6b Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Tue, 12 Aug 2025 12:54:36 -0400 Subject: [PATCH 029/180] Commented code because of build errors --- .../V3_SuperstructureEdges.java | 40 +++++++------------ 1 file changed, 14 insertions(+), 26 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java index 396c5f33..7b3b3c9a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java @@ -1,14 +1,9 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; + import java.util.ArrayList; -import java.util.List; -import java.util.Map; -import lombok.Builder; -import lombok.Getter; -import org.jgrapht.Graph; -import org.jgrapht.graph.DefaultEdge; public class V3_SuperstructureEdges { - + public static final ArrayList AlgaeEdges = new ArrayList<>(); public static final ArrayList CoralEdges = new ArrayList<>(); @@ -18,32 +13,25 @@ public Edge(V3_SuperstructureStates from, V3_SuperstructureStates to) { } public String toString() { - return String.format( - "Edge[from=%s, to=%s, action=%s]", from.name(), to.name(), action); + return String.format("Edge[from=%s, to=%s, action=%s]", from.name(), to.name(), action); } } - + public enum AlgaeEdge { NONE, NO_ALGAE, ALGAE } - @Builder(toBuilder = true) - @Getter - public static class EdgeCommand extends DefaultEdge { - private final Command command; - @Builder.Default private final AlgaeEdge algaeEdgeType = AlgaeEdge.NONE; - } - - private static Command getEdgeCommand( - V3_SuperstructureStates from, V3_SuperstructureStates to, AlgaeEdge algaeEdgeType) { - return Command.builder() - .from(from) - .to(to) - .algaeEdgeType(algaeEdgeType) - .build(); - } + // @Builder(toBuilder = true) + // @Getter + // public static class EdgeCommand extends DefaultEdge { + // private final Command command; + // @Builder.Default private final AlgaeEdge algaeEdgeType = AlgaeEdge.NONE; + // } - + // private static Command getEdgeCommand( + // V3_SuperstructureStates from, V3_SuperstructureStates to, AlgaeEdge algaeEdgeType) { + // return Command.builder().from(from).to(to).algaeEdgeType(algaeEdgeType).build(); + // } } From 7118ba7ec6d86625eb61b0ec48355db805ef1226 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Tue, 12 Aug 2025 18:17:21 -0400 Subject: [PATCH 030/180] Worked on edges for V3 Superstructure w/Anshu + Elliot Co-authored-by: Anshu --- .../V3_EpsilonManipulatorConstants.java | 3 +- .../superstructure/Superstructure.dot | 2 +- .../V3_SuperstructureEdges.java | 115 ++++++++++++++++-- .../V3_SuperstructurePoses.java | 6 +- .../V3_SuperstructureStates.java | 65 ++++++---- 5 files changed, 154 insertions(+), 37 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java index 959dbc38..ac60ffd0 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java @@ -146,7 +146,8 @@ public static enum PivotState { FLOOR_INTAKE(Rotation2d.fromDegrees(-68.5 - 5)), STOW_LINE(Rotation2d.fromDegrees(-75)), TRANSITION(Rotation2d.fromDegrees(-32)), // Placeholder value. Make sure to test - STOW_DOWN(Rotation2d.fromDegrees(-77)); + STOW_DOWN(Rotation2d.fromDegrees(-77)), + HANDOFF(new Rotation2d()); private final Rotation2d angle; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index d2fdae14..931a2dd7 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -51,7 +51,7 @@ digraph Superstructure { stow_up -> L2_transition [color = green] stow_up -> L3_transition [color = green] stow_up -> L4_transition [color = green] - + # Coral Edges handoff -> L1_prep [color = green] handoff -> L2_transition [color = green] diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java index 7b3b3c9a..68267fc6 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java @@ -1,11 +1,22 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; import java.util.ArrayList; +import java.util.List; +import org.jgrapht.graph.DefaultEdge; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; +import frc.robot.subsystems.shared.elevator.Elevator; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; +import lombok.Builder; +import lombok.Getter; public class V3_SuperstructureEdges { public static final ArrayList AlgaeEdges = new ArrayList<>(); public static final ArrayList CoralEdges = new ArrayList<>(); + public static final ArrayList UnconstrainedEdges = new ArrayList<>(); + public static final ArrayList NoneEdges = new ArrayList<>(); public record Edge(V3_SuperstructureStates from, V3_SuperstructureStates to, String action) { public Edge(V3_SuperstructureStates from, V3_SuperstructureStates to) { @@ -23,15 +34,97 @@ public enum AlgaeEdge { ALGAE } - // @Builder(toBuilder = true) - // @Getter - // public static class EdgeCommand extends DefaultEdge { - // private final Command command; - // @Builder.Default private final AlgaeEdge algaeEdgeType = AlgaeEdge.NONE; - // } - - // private static Command getEdgeCommand( - // V3_SuperstructureStates from, V3_SuperstructureStates to, AlgaeEdge algaeEdgeType) { - // return Command.builder().from(from).to(to).algaeEdgeType(algaeEdgeType).build(); - // } + public enum CoralEdge { + NONE, + NO_CORAL, + CORAL + } + + @Builder(toBuilder = true) + @Getter + public static class EdgeCommand extends DefaultEdge { + private final Command command; + @Builder.Default private final AlgaeEdge algaeEdgeType = AlgaeEdge.NONE; + @Builder.Default private final CoralEdge coralEdgeType = CoralEdge.NONE; + } + + private static Command getEdgeCommand( + V3_SuperstructureStates from, + V3_SuperstructureStates to, + Elevator.ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + + // TODO: Implement the actual command logic + + return Commands.none(); + } + + public static void createEdges () { + List coralPrepLevels = List.of( + V3_SuperstructureStates.L1_PREP, + V3_SuperstructureStates.L2_PREP, + V3_SuperstructureStates.L3_PREP, + V3_SuperstructureStates.L4_PREP + ); + + List coralTransitionLevels = List.of( + V3_SuperstructureStates.L2_TRANSITION, + V3_SuperstructureStates.L3_TRANSITION, + V3_SuperstructureStates.L4_TRANSITION + ); + + // Coral Edges + + // Level to level edges + for (V3_SuperstructureStates from : coralPrepLevels) { + for (V3_SuperstructureStates to : coralPrepLevels) { + if (from != to) { + CoralEdges.add(new Edge(from, to, "Coral Level Transition")); + } + } + } + + // Handoff -> transition + for (V3_SuperstructureStates to: coralTransitionLevels) { + CoralEdges.add(new Edge(V3_SuperstructureStates.HANDOFF, to, "Coral Transition")); + } + + // Handoff -> L1_PREP + CoralEdges.add(new Edge(V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.HANDOFF, "Coral Handoff L1 Prep")); + + // Transition -> handoff + for (V3_SuperstructureStates from: coralTransitionLevels) { + CoralEdges.add(new Edge(from, V3_SuperstructureStates.HANDOFF, "Coral Handoff")); + } + + // Coral Prep to Transition + for (V3_SuperstructureStates from : coralPrepLevels) { + for (V3_SuperstructureStates to : coralTransitionLevels) { + CoralEdges.add(new Edge(from, to, "Coral Transition")); + } + } + + // Coral Transition to Prep + CoralEdges.add(new Edge(V3_SuperstructureStates.L2_TRANSITION, V3_SuperstructureStates.L2_PREP, "Coral Transition L2")); + CoralEdges.add(new Edge(V3_SuperstructureStates.L3_TRANSITION, V3_SuperstructureStates.L3_PREP, "Coral Transition L3")); + CoralEdges.add(new Edge(V3_SuperstructureStates.L4_TRANSITION, V3_SuperstructureStates.L4_PREP, "Coral Transition L3")); + + + // Prep to score states + CoralEdges.add(new Edge(V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.L1_SCORE, "Coral Score L1")); + CoralEdges.add(new Edge(V3_SuperstructureStates.L2_PREP, V3_SuperstructureStates.L2_SCORE, "Coral Score L2")); + CoralEdges.add(new Edge(V3_SuperstructureStates.L3_PREP, V3_SuperstructureStates.L3_SCORE, "Coral Score L3")); + CoralEdges.add(new Edge(V3_SuperstructureStates.L4_PREP, V3_SuperstructureStates.L4_SCORE, "Coral Score L4")); + + // L1_SCORE -> GROUND_INTAKE + CoralEdges.add(new Edge(V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.GROUND_INTAKE, "Coral Transition L1")); + + } } + + + + + + diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java index 4fd57633..014135c9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java @@ -14,14 +14,14 @@ public class V3_SuperstructurePoses { private String key; @Getter private final ReefState elevatorHeight; - @Getter private final V3_EpsilonManipulatorConstants.PivotState armState; + @Getter private final V3_EpsilonManipulatorConstants.PivotState pivotState; @Getter private final V3_EpsilonIntakeConstants.IntakeState intakeState; public V3_SuperstructurePoses(String key, SubsystemPoses poses) { this.key = key; this.elevatorHeight = poses.elevatorHeight(); - this.armState = poses.manipulatorArmState(); + this.pivotState = poses.manipulatorArmState(); this.intakeState = poses.intakeState(); } @@ -57,7 +57,7 @@ public Command setIntakeState(V3_EpsilonIntake intake) { */ public Command setManipulatorState(V3_EpsilonManipulator manipulator) { return Commands.parallel( - Commands.runOnce(() -> manipulator.setManipulatorState(armState)), + Commands.runOnce(() -> manipulator.setManipulatorState(pivotState)), manipulator.waitUntilPivotAtGoal()); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index 3acf3de9..0a40cbce 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -1,7 +1,7 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; // Adjust the package path as needed -import frc.robot.FieldConstants; +import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureActions.SubsystemActions; @@ -17,16 +17,39 @@ public enum V3_SuperstructureStates { STOW_UP( "STOW_UP", new SubsystemPoses( - FieldConstants.Reef.ReefState.STOW, + ReefState.STOW, V3_EpsilonManipulatorConstants.PivotState.STOW_UP, V3_EpsilonIntakeConstants.IntakeState.STOW), SubsystemActions.empty()), + HANDOFF( + "HANDOFF", + new SubsystemPoses( + ReefState.STOW, + V3_EpsilonManipulatorConstants.PivotState.HANDOFF, + V3_EpsilonIntakeConstants.IntakeState.HANDOFF + ), + SubsystemActions.empty() + ), + + GROUND_INTAKE( + "GROUND_INTAKE", + new SubsystemPoses( + ReefState.STOW, + V3_EpsilonManipulatorConstants.PivotState.FLOOR_INTAKE, + V3_EpsilonIntakeConstants.IntakeState.INTAKE_CORAL + ), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP, + V3_EpsilonIntakeConstants.IntakeRollerStates.CORAL_INTAKE + ) + ), + // Coral Prep States L1_PREP( "L1", new SubsystemPoses( - FieldConstants.Reef.ReefState.L1, + ReefState.L1, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, V3_EpsilonIntakeConstants.IntakeState.L1), SubsystemActions.empty()), @@ -34,7 +57,7 @@ public enum V3_SuperstructureStates { L2_PREP( "L2", new SubsystemPoses( - FieldConstants.Reef.ReefState.L2, + ReefState.L2, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, V3_EpsilonIntakeConstants.IntakeState.STOW), SubsystemActions.empty()), @@ -42,7 +65,7 @@ public enum V3_SuperstructureStates { L3_PREP( "L3", new SubsystemPoses( - FieldConstants.Reef.ReefState.L3, + ReefState.L3, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, V3_EpsilonIntakeConstants.IntakeState.STOW), SubsystemActions.empty()), @@ -50,7 +73,7 @@ public enum V3_SuperstructureStates { L4_PREP( "L4", new SubsystemPoses( - FieldConstants.Reef.ReefState.L4, + ReefState.L4, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, V3_EpsilonIntakeConstants.IntakeState.STOW), SubsystemActions.empty()), @@ -59,7 +82,7 @@ public enum V3_SuperstructureStates { L1_SCORE( "L1_SCORE", new SubsystemPoses( - FieldConstants.Reef.ReefState.L1, + ReefState.L1, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, V3_EpsilonIntakeConstants.IntakeState.L1), new SubsystemActions( @@ -69,7 +92,7 @@ public enum V3_SuperstructureStates { L2_SCORE( "L2_SCORE", new SubsystemPoses( - FieldConstants.Reef.ReefState.L2, + ReefState.L2, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, V3_EpsilonIntakeConstants.IntakeState.STOW), new SubsystemActions( @@ -79,7 +102,7 @@ public enum V3_SuperstructureStates { L3_SCORE( "L3_SCORE", new SubsystemPoses( - FieldConstants.Reef.ReefState.L3, + ReefState.L3, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, V3_EpsilonIntakeConstants.IntakeState.STOW), new SubsystemActions( @@ -89,7 +112,7 @@ public enum V3_SuperstructureStates { L4_SCORE( "L4_SCORE", new SubsystemPoses( - FieldConstants.Reef.ReefState.L4, + ReefState.L4, V3_EpsilonManipulatorConstants.PivotState .PRE_SCORE, // Determine whether PRE_SCORE is accurate for all scoring states V3_EpsilonIntakeConstants.IntakeState.STOW), @@ -101,7 +124,7 @@ public enum V3_SuperstructureStates { L2_ALGAE_PREP( "L2_ALGAE_PREP", new SubsystemPoses( - FieldConstants.Reef.ReefState.L2, + ReefState.L2, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, V3_EpsilonIntakeConstants.IntakeState.STOW), SubsystemActions.empty()), @@ -109,7 +132,7 @@ public enum V3_SuperstructureStates { L3_ALGAE_PREP( "L3_ALGAE_PREP", new SubsystemPoses( - FieldConstants.Reef.ReefState.L3, + ReefState.L3, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, V3_EpsilonIntakeConstants.IntakeState.STOW), SubsystemActions.empty()), @@ -118,7 +141,7 @@ public enum V3_SuperstructureStates { L2_ALGAE_SCORE( "L2_ALGAE_SCORE", new SubsystemPoses( - FieldConstants.Reef.ReefState.L2, + ReefState.L2, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, V3_EpsilonIntakeConstants.IntakeState.STOW), new SubsystemActions( @@ -128,7 +151,7 @@ public enum V3_SuperstructureStates { L3_ALGAE_SCORE( "L3_ALGAE_SCORE", new SubsystemPoses( - FieldConstants.Reef.ReefState.L3, + ReefState.L3, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, V3_EpsilonIntakeConstants.IntakeState.STOW), new SubsystemActions( @@ -139,7 +162,7 @@ public enum V3_SuperstructureStates { BARGE_PREP( "BARGE_PREP", new SubsystemPoses( - FieldConstants.Reef.ReefState.ASS_TOP, + ReefState.ALGAE_SCORE, V3_EpsilonManipulatorConstants.PivotState .REEF_INTAKE, // Assuming REEF_INTAKE and BARGE_PREP have same rotation values V3_EpsilonIntakeConstants.IntakeState.STOW), @@ -148,7 +171,7 @@ public enum V3_SuperstructureStates { PROCESSOR_PREP( "PROCESSOR_PREP", new SubsystemPoses( - FieldConstants.Reef.ReefState.ASS_BOT, + ReefState.STOW, V3_EpsilonManipulatorConstants.PivotState.PROCESSOR, V3_EpsilonIntakeConstants.IntakeState.STOW), SubsystemActions.empty()), @@ -156,7 +179,7 @@ public enum V3_SuperstructureStates { BARGE_SCORE( "BARGE_SCORE", new SubsystemPoses( - FieldConstants.Reef.ReefState.ALGAE_SCORE, + ReefState.ALGAE_SCORE, V3_EpsilonManipulatorConstants.PivotState.REEF_INTAKE, V3_EpsilonIntakeConstants.IntakeState.STOW), new SubsystemActions( @@ -168,7 +191,7 @@ public enum V3_SuperstructureStates { PROCESSOR_SCORE( "PROCESSOR_SCORE", new SubsystemPoses( - FieldConstants.Reef.ReefState.ALGAE_SCORE, + ReefState.ALGAE_SCORE, V3_EpsilonManipulatorConstants.PivotState.PROCESSOR, V3_EpsilonIntakeConstants.IntakeState.STOW), new SubsystemActions( @@ -179,7 +202,7 @@ public enum V3_SuperstructureStates { L2_TRANSITION( "L2_TRANSITION", new SubsystemPoses( - FieldConstants.Reef.ReefState.L2, + ReefState.L2, V3_EpsilonManipulatorConstants.PivotState.TRANSITION, V3_EpsilonIntakeConstants.IntakeState.STOW), SubsystemActions.empty()), @@ -187,7 +210,7 @@ public enum V3_SuperstructureStates { L3_TRANSITION( "L3_TRANSITION", new SubsystemPoses( - FieldConstants.Reef.ReefState.L3, + ReefState.L3, V3_EpsilonManipulatorConstants.PivotState.TRANSITION, V3_EpsilonIntakeConstants.IntakeState.STOW), SubsystemActions.empty()), @@ -195,7 +218,7 @@ public enum V3_SuperstructureStates { L4_TRANSITION( "L4_TRANSITION", new SubsystemPoses( - FieldConstants.Reef.ReefState.L4, + ReefState.L4, V3_EpsilonManipulatorConstants.PivotState.TRANSITION, V3_EpsilonIntakeConstants.IntakeState.STOW), SubsystemActions.empty()); From f226fd2f1e314a0d18ce5576411c894396b918b9 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Wed, 13 Aug 2025 17:10:33 -0400 Subject: [PATCH 031/180] more edges --- .../superstructure/Superstructure.dot | 2 + .../superstructure/V3_Superstructure.java | 367 ++++++++++++++++++ .../V3_SuperstructureEdges.java | 96 +++-- .../V3_SuperstructureStates.java | 27 +- 4 files changed, 464 insertions(+), 28 deletions(-) create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index 931a2dd7..ab3d8fe5 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -40,6 +40,8 @@ digraph Superstructure { L2_transition [color = green] L3_transition [color = green] L4_transition [color = green] + + climb [color = red] # Transition states are inherently wait_for_elevator states but for different levels intermediate_wait_for_elevator [color = green] diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java new file mode 100644 index 00000000..6cf44530 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java @@ -0,0 +1,367 @@ +package frc.robot.subsystems.v3_Epsilon.superstructure; + +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.RobotState; +import frc.robot.RobotState.RobotMode; +import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureEdges.EdgeCommand; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureEdges.GamePieceEdge; +import frc.robot.util.NTPrefixes; +import java.util.HashMap; +import java.util.LinkedList; +import java.util.Map; +import java.util.Optional; +import java.util.Queue; +import java.util.function.BooleanSupplier; +import java.util.function.Supplier; +import lombok.Getter; +import org.jgrapht.Graph; +import org.jgrapht.graph.DefaultDirectedGraph; +import org.littletonrobotics.junction.AutoLogOutput; +import org.littletonrobotics.junction.Logger; + +/** + * The V3_Superstructure class manages the coordinated movement and state transitions of + * the robot's major subsystems including elevator, funnel, manipulator, and intake. + */ +public class V3_Superstructure extends SubsystemBase { + + private final Graph graph; + private final ElevatorFSM elevator; + private final V3_EpsilonIntake intake; + private final V3_EpsilonManipulator manipulator; + + /** + * The previous, current, and next states of the superstructure. These are used to track the state + * transitions and manage the command scheduling. + */ + @Getter private V3_SuperstructureStates previousState; + + /** + * The current state of the superstructure, which is updated periodically based on the command + * scheduling and state transitions. + */ + @Getter private V3_SuperstructureStates currentState; + + /** + * The next state that the superstructure is transitioning to. This is determined by the command + * scheduling and the current target state. + */ + @Getter private V3_SuperstructureStates nextState; + + /** + * The target state that the superstructure is trying to achieve. This is set by the robot and + * determines the next action to be taken. + */ + @Getter private V3_SuperstructureStates targetState; + + /** The command that is currently being executed to transition between states. */ + private EdgeCommand edgeCommand; + + /** + * Constructs a V3_Superstructure. + * + * @param elevator The elevator subsystem. + * @param funnel The funnel subsystem. + * @param intake The intake subsystem. + * @param manipulator The manipulator subsystem. + */ + public V3_Superstructure( + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + this.elevator = elevator; + this.intake = intake; + this.manipulator = manipulator; + + previousState = null; + currentState = V3_SuperstructureStates.START; + nextState = null; + + targetState = V3_SuperstructureStates.START; + + // Initialize the graph + graph = new DefaultDirectedGraph<>(EdgeCommand.class); + + for (V3_SuperstructureStates vertex : V3_SuperstructureStates.values()) { + graph.addVertex(vertex); + } + } + + /** + * Periodic method that handles state transitions and subsystem updates. Updates robot state + * variables and manages command scheduling based on current state. + */ + @Override + public void periodic() { + + if (RobotMode.disabled()) { + nextState = null; + } else if (edgeCommand == null || !edgeCommand.getCommand().isScheduled()) { + // Update edge to new state + if (nextState != null) { + previousState = currentState; + currentState = nextState; + nextState = null; + } + + // Schedule next command in sequence + if (currentState != targetState) { + bfs(currentState, targetState) + .ifPresent( + next -> { + this.nextState = next; + edgeCommand = graph.getEdge(currentState, next); + edgeCommand.getCommand().schedule(); + }); + } + } + + // Log the current state of the superstructure and edge command + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "Goal", targetState == null ? "NULL" : targetState.toString()); + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "Previous State", + previousState == null ? "NULL" : previousState.toString()); + Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Current State", currentState.toString()); + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "Next State", + nextState == null ? "NULL" : nextState.toString()); + if (edgeCommand != null) { + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "EdgeCommand", + graph.getEdgeSource(edgeCommand) + " --> " + graph.getEdgeTarget(edgeCommand)); + } else { + Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "EdgeCommand", "NO EDGES SCHEDULED"); + } + + elevator.periodic(); + intake.periodic(); + manipulator.periodic(); + } + + /** + * Updates the target state and handles command rescheduling for optimal path. + * + * @param goal New target state to achieve + */ + private void setGoal(V3_SuperstructureStates goal) { + // Don't do anything if goal is the same + if (this.targetState == goal) return; + else { + this.targetState = goal; + } + + if (nextState == null) return; + + var edgeToCurrentState = graph.getEdge(nextState, currentState); + // Figure out if we should schedule a different command to get to goal faster + if (edgeCommand.getCommand().isScheduled() + && edgeToCurrentState != null + && isEdgeAllowed(edgeToCurrentState, goal)) { + // Figure out where we would have gone from the previous state + bfs(currentState, goal) + .ifPresent( + newNext -> { + if (newNext == nextState) { + // We are already on track + return; + } + + if (newNext != currentState && graph.getEdge(nextState, newNext) != null) { + // We can skip directly to the newNext edge + edgeCommand.getCommand().cancel(); + edgeCommand = graph.getEdge(currentState, newNext); + edgeCommand.getCommand().schedule(); + nextState = newNext; + } else { + // Follow the reverse edge from next back to the current edge + edgeCommand.getCommand().cancel(); + edgeCommand = graph.getEdge(nextState, currentState); + edgeCommand.getCommand().schedule(); + var temp = currentState; + previousState = currentState; + currentState = nextState; + nextState = temp; + } + }); + } + } + + /** + * Performs breadth-first search to find the next state in the path to the goal. + * + * @param start Starting state + * @param goal Target state + * @return Optional containing the next state in the path, empty if no path exists + */ + private Optional bfs( + V3_SuperstructureStates start, V3_SuperstructureStates goal) { + Map parents = + new HashMap<>(); + Queue queue = new LinkedList<>(); + queue.add(start); + parents.put(start, null); + while (!queue.isEmpty()) { + V3_SuperstructureStates current = queue.poll(); + if (current == goal) break; + for (EdgeCommand edge : + graph.outgoingEdgesOf(current).stream() + .filter(edge -> isEdgeAllowed(edge, goal)) + .toList()) { + V3_SuperstructureStates neighbor = graph.getEdgeTarget(edge); + if (!parents.containsKey(neighbor)) { + parents.put(neighbor, current); + queue.add(neighbor); + } + } + } + + if (!parents.containsKey(goal)) return Optional.empty(); + + V3_SuperstructureStates nextState = goal; + while (!nextState.equals(start)) { + V3_SuperstructureStates parent = parents.get(nextState); + if (parent == null) return Optional.empty(); + else if (parent.equals(start)) return Optional.of(nextState); + nextState = parent; + } + return Optional.of(nextState); + } + + /** + * Checks if a state transition is allowed based on algae presence. + * + * @param edge The transition edge to check + * @param goal The target state + * @return true if the transition is allowed + */ + private boolean isEdgeAllowed(EdgeCommand edge, V3_SuperstructureStates goal) { // Change later + return edge.getEdgeType() == GamePieceEdge.NONE + || RobotState.isHasAlgae() == (edge.getEdgeType() == GamePieceEdge.ALGAE); + } + + /** Resets the superstructure to initial auto state. */ + public void setAutoStart() { + currentState = V3_SuperstructureStates.START; + nextState = null; + targetState = V3_SuperstructureStates.STOW_DOWN; + if (edgeCommand != null) { + edgeCommand.getCommand().cancel(); + } + } + // --- Control Commands --- + + /** + * Returns a command that sets the superstructure to the given goal state. + * + * @param goal The desired superstructure state + * @return Command to run the goal + */ + public Command runGoal(V3_SuperstructureStates goal) { + return runOnce(() -> setGoal(goal)); + } + + /** + * Returns a command that sets the superstructure to the goal provided by a supplier. + * + * @param goal Supplier providing the desired superstructure state + * @return Command to run the goal + */ + public Command runGoal(Supplier goal) { + return runOnce(() -> setGoal(goal.get())); + } + + /** + * Checks whether the superstructure has reached its target state. + * + * @return true if current state matches the target state + */ + @AutoLogOutput(key = NTPrefixes.SUPERSTRUCTURE + "At Goal") + public boolean atGoal() { + return currentState == targetState; + } + + /** + * Runs a temporary override action, returning to a previous goal after. + * + * @param action The override action to perform + * @param oldGoal The goal to return to after override + * @return Command that runs the override and resumes the old goal + */ + public Command override(Runnable action) { + return Commands.sequence( + runGoal(V3_SuperstructureStates.OVERRIDE), Commands.run(action)) + .finallyDo(() -> setGoal(currentState)); + } + + /** + * Runs a temporary override action, returning to a previous goal after. + * + * @param action The override action to perform + * @param oldGoal The goal to return to after override + * @return Command that runs the override and resumes the old goal + */ + public Command override(Runnable action, double timeSeconds) { + return override(action).withTimeout(timeSeconds); + } + + /** + * Runs the goal state and waits until a given condition becomes true. + * + * @param goal The desired superstructure state + * @param condition The condition to wait for after running the goal + * @return Combined command for running and waiting + */ + public Command runGoalUntil(V3_SuperstructureStates goal, BooleanSupplier condition) { + return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); + } + + public Command runGoalUntil( + Supplier goal, BooleanSupplier condition) { + return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); + } + + /** + * Returns a short command to run the previous state, useful for temporary state restoration. + * + * @return Command to go back to the previous state + */ + public Command runPreviousState() { + return runGoal(() -> previousState); + } + + /** + * Runs an action by going to a pose, performing the action, waiting, and returning. + * + * @param pose The pose to return to after action + * @param action The action to perform + * @param timeout How long to wait during the action phase (in seconds) + * @return Full command sequence + */ + public Command runActionWithTimeout( + V3_SuperstructureStates pose, + V3_SuperstructureStates action, + double timeout) { + return Commands.sequence( + runGoal(action), // Run the action + Commands.waitUntil(() -> atGoal()), + Commands.waitSeconds(timeout), + runGoal(pose)) + .finallyDo(() -> setGoal(pose)); // Return to original pose + } + + + /** + * Checks if the elevator is at its goal position. + * + * @return True if the elevator is at its goal, false otherwise. + */ + public boolean elevatorAtGoal() { + return elevator.atGoal(); + } +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java index 68267fc6..d9fff1a9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java @@ -2,7 +2,13 @@ import java.util.ArrayList; import java.util.List; +import java.util.Map; +import java.util.stream.Stream; + import org.jgrapht.graph.DefaultEdge; + +import com.fasterxml.jackson.annotation.JsonTypeInfo.None; + import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.subsystems.shared.elevator.Elevator; @@ -24,28 +30,22 @@ public Edge(V3_SuperstructureStates from, V3_SuperstructureStates to) { } public String toString() { - return String.format("Edge[from=%s, to=%s, action=%s]", from.name(), to.name(), action); + return from + " -> " + to + (action.isEmpty() ? "" : " : " + action); } } - public enum AlgaeEdge { - NONE, - NO_ALGAE, - ALGAE - } - - public enum CoralEdge { - NONE, - NO_CORAL, - CORAL + public enum GamePieceEdge { + NONE, // No game pieces + ALGAE, // Algae only + CORAL, // Coral only + ALGAE_CORAL // Can have either algae or coral } @Builder(toBuilder = true) @Getter public static class EdgeCommand extends DefaultEdge { private final Command command; - @Builder.Default private final AlgaeEdge algaeEdgeType = AlgaeEdge.NONE; - @Builder.Default private final CoralEdge coralEdgeType = CoralEdge.NONE; + @Builder.Default private final GamePieceEdge edgeType = GamePieceEdge.NONE; } private static Command getEdgeCommand( @@ -61,8 +61,7 @@ private static Command getEdgeCommand( } public static void createEdges () { - List coralPrepLevels = List.of( - V3_SuperstructureStates.L1_PREP, + List coralPrepLevels = List.of( // Except L1_PREP, which is handled separately V3_SuperstructureStates.L2_PREP, V3_SuperstructureStates.L3_PREP, V3_SuperstructureStates.L4_PREP @@ -92,24 +91,32 @@ public static void createEdges () { // Handoff -> L1_PREP CoralEdges.add(new Edge(V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.HANDOFF, "Coral Handoff L1 Prep")); + UnconstrainedEdges.add(new Edge(V3_SuperstructureStates.L1_SCORE, V3_SuperstructureStates.HANDOFF, "Coral Handoff L1 Score")); // Transition -> handoff for (V3_SuperstructureStates from: coralTransitionLevels) { CoralEdges.add(new Edge(from, V3_SuperstructureStates.HANDOFF, "Coral Handoff")); } - // Coral Prep to Transition + // Coral Transition to Prep and reverse + for (V3_SuperstructureStates from : coralTransitionLevels) { + for (V3_SuperstructureStates to : coralPrepLevels) { + CoralEdges.add(new Edge(from, to, "Coral Transition")); + CoralEdges.add(new Edge(to, from, "Coral Transition Reverse")); + } + } + + // Prep to other transition states for (V3_SuperstructureStates from : coralPrepLevels) { for (V3_SuperstructureStates to : coralTransitionLevels) { - CoralEdges.add(new Edge(from, to, "Coral Transition")); + if ((from == V3_SuperstructureStates.L2_PREP && to == V3_SuperstructureStates.L2_TRANSITION) || + (from == V3_SuperstructureStates.L3_PREP && to == V3_SuperstructureStates.L3_TRANSITION) || + (from == V3_SuperstructureStates.L4_PREP && to == V3_SuperstructureStates.L4_TRANSITION)) { + continue; + } + CoralEdges.add(new Edge(from, to, "Coral Prep Transition")); } - } - - // Coral Transition to Prep - CoralEdges.add(new Edge(V3_SuperstructureStates.L2_TRANSITION, V3_SuperstructureStates.L2_PREP, "Coral Transition L2")); - CoralEdges.add(new Edge(V3_SuperstructureStates.L3_TRANSITION, V3_SuperstructureStates.L3_PREP, "Coral Transition L3")); - CoralEdges.add(new Edge(V3_SuperstructureStates.L4_TRANSITION, V3_SuperstructureStates.L4_PREP, "Coral Transition L3")); - + } // Prep to score states CoralEdges.add(new Edge(V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.L1_SCORE, "Coral Score L1")); @@ -117,8 +124,47 @@ public static void createEdges () { CoralEdges.add(new Edge(V3_SuperstructureStates.L3_PREP, V3_SuperstructureStates.L3_SCORE, "Coral Score L3")); CoralEdges.add(new Edge(V3_SuperstructureStates.L4_PREP, V3_SuperstructureStates.L4_SCORE, "Coral Score L4")); - // L1_SCORE -> GROUND_INTAKE + // L1_SCORE <-> GROUND_INTAKE CoralEdges.add(new Edge(V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.GROUND_INTAKE, "Coral Transition L1")); + NoneEdges.add(new Edge(V3_SuperstructureStates.L1_SCORE, V3_SuperstructureStates.GROUND_INTAKE, "Coral Transition L1 Score")); + CoralEdges.add(new Edge(V3_SuperstructureStates.GROUND_INTAKE, V3_SuperstructureStates.L1_PREP, "Coral Transition L1 Ground Intake")); + + // IWFE states + for (V3_SuperstructureStates from : Stream.concat(coralPrepLevels.stream(), Stream.of(V3_SuperstructureStates.L2_SCORE,V3_SuperstructureStates.L3_SCORE,V3_SuperstructureStates.L4_SCORE)).toList()) { + UnconstrainedEdges.add(new Edge(from, V3_SuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR, "Coral IWFE Transition")); + } + UnconstrainedEdges.add(new Edge(V3_SuperstructureStates.STOW_DOWN, V3_SuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR, "Coral IWFE Transition Stow Down")); + UnconstrainedEdges.add(new Edge(V3_SuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR, V3_SuperstructureStates.HANDOFF, "Coral IWFE Transition Handoff")); + + // Stow Down to Ground Intake and Stow Up + NoneEdges.add(new Edge(V3_SuperstructureStates.STOW_DOWN, V3_SuperstructureStates.GROUND_INTAKE, "Coral Stow Down Ground Intake")); + NoneEdges.add(new Edge(V3_SuperstructureStates.STOW_DOWN, V3_SuperstructureStates.STOW_UP, "Coral Stow Down Stow Up")); //Optional coral + + + // Algae Edges + List algaePrepStates = List.of( + V3_SuperstructureStates.L2_ALGAE_PREP, + V3_SuperstructureStates.L3_ALGAE_PREP, + V3_SuperstructureStates.BARGE_PREP, + V3_SuperstructureStates.PROCESSOR_PREP + ); + List algaeScoreStates = List.of( + V3_SuperstructureStates.L2_ALGAE_SCORE, + V3_SuperstructureStates.L3_ALGAE_SCORE, + V3_SuperstructureStates.BARGE_SCORE, + V3_SuperstructureStates.PROCESSOR_SCORE + ); + + for (int i = 0; i < 4; i++) { + NoneEdges.add(new Edge(algaePrepStates.get(i), algaeScoreStates.get(i), "Algae Score Transition")); + NoneEdges.add(new Edge(algaeScoreStates.get(i), algaePrepStates.get(i), "Algae Prep Transition")); + } + + for (V3_SuperstructureStates to : algaePrepStates) { + NoneEdges.add(new Edge(V3_SuperstructureStates.STOW_UP, to, "Algae Stow Up Transition")); + } + + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index 0a40cbce..5650bdc8 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -44,7 +44,15 @@ public enum V3_SuperstructureStates { V3_EpsilonIntakeConstants.IntakeRollerStates.CORAL_INTAKE ) ), - + INTERMIDIATE_WAIT_FOR_ELEVATOR( + "INTERMIDIATE_WAIT_FOR_ELEVATOR", + new SubsystemPoses( + ReefState.STOW, + V3_EpsilonManipulatorConstants.PivotState.STOW_UP, + V3_EpsilonIntakeConstants.IntakeState.STOW + ), + SubsystemActions.empty() + ), // Coral Prep States L1_PREP( "L1", @@ -221,7 +229,20 @@ public enum V3_SuperstructureStates { ReefState.L4, V3_EpsilonManipulatorConstants.PivotState.TRANSITION, V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()); + SubsystemActions.empty()), + + CLIMB( + "CLIMB", + new SubsystemPoses( + ReefState.STOW, + V3_EpsilonManipulatorConstants.PivotState.STOW_UP, + V3_EpsilonIntakeConstants.IntakeState.STOW), + SubsystemActions.empty()), + + OVERRIDE( + "OVERRIDE", + new SubsystemPoses(), + SubsystemActions.empty()); // Readable name for state private final String name; @@ -260,7 +281,7 @@ public V3_SuperstructurePoses getPose() { * * @return The actions for this state. */ - public V3_SuperstructureActions getActions() { + public V3_SuperstructureActions getAction() { return new V3_SuperstructureActions(name, subsystemActions); } From 846eb3f63678c701983ed54562f580aa5c680ed8 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Fri, 15 Aug 2025 18:04:24 -0400 Subject: [PATCH 032/180] Worked on edges for V3 Superstructure w/Anshu + Elliot Co-authored-by: Anshu --- .../V3_SuperstructureEdges.java | 94 +++++-------------- .../V3_SuperstructureStates.java | 10 +- 2 files changed, 25 insertions(+), 79 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java index d9fff1a9..e17c6f48 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java @@ -2,13 +2,7 @@ import java.util.ArrayList; import java.util.List; -import java.util.Map; -import java.util.stream.Stream; - import org.jgrapht.graph.DefaultEdge; - -import com.fasterxml.jackson.annotation.JsonTypeInfo.None; - import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.subsystems.shared.elevator.Elevator; @@ -34,18 +28,24 @@ public String toString() { } } - public enum GamePieceEdge { - NONE, // No game pieces - ALGAE, // Algae only - CORAL, // Coral only - ALGAE_CORAL // Can have either algae or coral + public enum AlgaeEdge { + NONE, + NO_ALGAE, + ALGAE + } + + public enum CoralEdge { + NONE, + NO_CORAL, + CORAL } @Builder(toBuilder = true) @Getter public static class EdgeCommand extends DefaultEdge { private final Command command; - @Builder.Default private final GamePieceEdge edgeType = GamePieceEdge.NONE; + @Builder.Default private final AlgaeEdge algaeEdgeType = AlgaeEdge.NONE; + @Builder.Default private final CoralEdge coralEdgeType = CoralEdge.NONE; } private static Command getEdgeCommand( @@ -61,7 +61,8 @@ private static Command getEdgeCommand( } public static void createEdges () { - List coralPrepLevels = List.of( // Except L1_PREP, which is handled separately + List coralPrepLevels = List.of( + V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.L2_PREP, V3_SuperstructureStates.L3_PREP, V3_SuperstructureStates.L4_PREP @@ -91,32 +92,24 @@ public static void createEdges () { // Handoff -> L1_PREP CoralEdges.add(new Edge(V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.HANDOFF, "Coral Handoff L1 Prep")); - UnconstrainedEdges.add(new Edge(V3_SuperstructureStates.L1_SCORE, V3_SuperstructureStates.HANDOFF, "Coral Handoff L1 Score")); // Transition -> handoff for (V3_SuperstructureStates from: coralTransitionLevels) { CoralEdges.add(new Edge(from, V3_SuperstructureStates.HANDOFF, "Coral Handoff")); } - // Coral Transition to Prep and reverse - for (V3_SuperstructureStates from : coralTransitionLevels) { - for (V3_SuperstructureStates to : coralPrepLevels) { - CoralEdges.add(new Edge(from, to, "Coral Transition")); - CoralEdges.add(new Edge(to, from, "Coral Transition Reverse")); - } - } - - // Prep to other transition states + // Coral Prep to Transition for (V3_SuperstructureStates from : coralPrepLevels) { for (V3_SuperstructureStates to : coralTransitionLevels) { - if ((from == V3_SuperstructureStates.L2_PREP && to == V3_SuperstructureStates.L2_TRANSITION) || - (from == V3_SuperstructureStates.L3_PREP && to == V3_SuperstructureStates.L3_TRANSITION) || - (from == V3_SuperstructureStates.L4_PREP && to == V3_SuperstructureStates.L4_TRANSITION)) { - continue; - } - CoralEdges.add(new Edge(from, to, "Coral Prep Transition")); + CoralEdges.add(new Edge(from, to, "Coral Transition")); } - } + } + + // Coral Transition to Prep + CoralEdges.add(new Edge(V3_SuperstructureStates.L2_TRANSITION, V3_SuperstructureStates.L2_PREP, "Coral Transition L2")); + CoralEdges.add(new Edge(V3_SuperstructureStates.L3_TRANSITION, V3_SuperstructureStates.L3_PREP, "Coral Transition L3")); + CoralEdges.add(new Edge(V3_SuperstructureStates.L4_TRANSITION, V3_SuperstructureStates.L4_PREP, "Coral Transition L3")); + // Prep to score states CoralEdges.add(new Edge(V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.L1_SCORE, "Coral Score L1")); @@ -124,47 +117,8 @@ public static void createEdges () { CoralEdges.add(new Edge(V3_SuperstructureStates.L3_PREP, V3_SuperstructureStates.L3_SCORE, "Coral Score L3")); CoralEdges.add(new Edge(V3_SuperstructureStates.L4_PREP, V3_SuperstructureStates.L4_SCORE, "Coral Score L4")); - // L1_SCORE <-> GROUND_INTAKE + // L1_SCORE -> GROUND_INTAKE CoralEdges.add(new Edge(V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.GROUND_INTAKE, "Coral Transition L1")); - NoneEdges.add(new Edge(V3_SuperstructureStates.L1_SCORE, V3_SuperstructureStates.GROUND_INTAKE, "Coral Transition L1 Score")); - CoralEdges.add(new Edge(V3_SuperstructureStates.GROUND_INTAKE, V3_SuperstructureStates.L1_PREP, "Coral Transition L1 Ground Intake")); - - // IWFE states - for (V3_SuperstructureStates from : Stream.concat(coralPrepLevels.stream(), Stream.of(V3_SuperstructureStates.L2_SCORE,V3_SuperstructureStates.L3_SCORE,V3_SuperstructureStates.L4_SCORE)).toList()) { - UnconstrainedEdges.add(new Edge(from, V3_SuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR, "Coral IWFE Transition")); - } - UnconstrainedEdges.add(new Edge(V3_SuperstructureStates.STOW_DOWN, V3_SuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR, "Coral IWFE Transition Stow Down")); - UnconstrainedEdges.add(new Edge(V3_SuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR, V3_SuperstructureStates.HANDOFF, "Coral IWFE Transition Handoff")); - - // Stow Down to Ground Intake and Stow Up - NoneEdges.add(new Edge(V3_SuperstructureStates.STOW_DOWN, V3_SuperstructureStates.GROUND_INTAKE, "Coral Stow Down Ground Intake")); - NoneEdges.add(new Edge(V3_SuperstructureStates.STOW_DOWN, V3_SuperstructureStates.STOW_UP, "Coral Stow Down Stow Up")); //Optional coral - - - // Algae Edges - List algaePrepStates = List.of( - V3_SuperstructureStates.L2_ALGAE_PREP, - V3_SuperstructureStates.L3_ALGAE_PREP, - V3_SuperstructureStates.BARGE_PREP, - V3_SuperstructureStates.PROCESSOR_PREP - ); - List algaeScoreStates = List.of( - V3_SuperstructureStates.L2_ALGAE_SCORE, - V3_SuperstructureStates.L3_ALGAE_SCORE, - V3_SuperstructureStates.BARGE_SCORE, - V3_SuperstructureStates.PROCESSOR_SCORE - ); - - for (int i = 0; i < 4; i++) { - NoneEdges.add(new Edge(algaePrepStates.get(i), algaeScoreStates.get(i), "Algae Score Transition")); - NoneEdges.add(new Edge(algaeScoreStates.get(i), algaePrepStates.get(i), "Algae Prep Transition")); - } - - for (V3_SuperstructureStates to : algaePrepStates) { - NoneEdges.add(new Edge(V3_SuperstructureStates.STOW_UP, to, "Algae Stow Up Transition")); - } - - } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index 5650bdc8..eb8479ac 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -44,15 +44,7 @@ public enum V3_SuperstructureStates { V3_EpsilonIntakeConstants.IntakeRollerStates.CORAL_INTAKE ) ), - INTERMIDIATE_WAIT_FOR_ELEVATOR( - "INTERMIDIATE_WAIT_FOR_ELEVATOR", - new SubsystemPoses( - ReefState.STOW, - V3_EpsilonManipulatorConstants.PivotState.STOW_UP, - V3_EpsilonIntakeConstants.IntakeState.STOW - ), - SubsystemActions.empty() - ), + // Coral Prep States L1_PREP( "L1", From fa2f3e7dd3cf21c2fa0ee61ed5617af0f19e1842 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Fri, 15 Aug 2025 18:09:12 -0400 Subject: [PATCH 033/180] Intermediate_wait_for_elevator state added --- .../superstructure/V3_SuperstructureStates.java | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index eb8479ac..de870c45 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -197,6 +197,16 @@ public enum V3_SuperstructureStates { new SubsystemActions( V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), + + INTERMIDIATE_WAIT_FOR_ELEVATOR( + "INTERMIDIATE_WAIT_FOR_ELEVATOR", + new SubsystemPoses( + ReefState.STOW, + V3_EpsilonManipulatorConstants.PivotState.STOW_UP, + V3_EpsilonIntakeConstants.IntakeState.STOW + ), + SubsystemActions.empty() + ), // Transition States L2_TRANSITION( From 84af1b16540c40c3349b199481f0d3c7d3bc029b Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Fri, 15 Aug 2025 21:22:55 -0400 Subject: [PATCH 034/180] Worked on more edges --- .../V3_SuperstructureEdges.java | 31 +++++++++++++++++++ .../V3_SuperstructureStates.java | 8 ++--- 2 files changed, 35 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java index e17c6f48..740c4ec3 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java @@ -120,6 +120,37 @@ public static void createEdges () { // L1_SCORE -> GROUND_INTAKE CoralEdges.add(new Edge(V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.GROUND_INTAKE, "Coral Transition L1")); + // Algae Edges + + // STOW_DOWN --> L2_ALGAE_PREP + AlgaeEdges.add(new Edge(V3_SuperstructureStates.STOW_DOWN, V3_SuperstructureStates.L2_ALGAE_PREP, "Algae Prep L2 from STOW DOWN")); + + // Prep --> intake states + AlgaeEdges.add(new Edge(V3_SuperstructureStates.L2_ALGAE_PREP, V3_SuperstructureStates.L2_ALGAE_INTAKE, "Algae Intake L2")); + AlgaeEdges.add(new Edge(V3_SuperstructureStates.L3_ALGAE_PREP, V3_SuperstructureStates.L3_ALGAE_INTAKE, "Algae Intake L3")); + + // Prep <-> Prep States + AlgaeEdges.add(new Edge(V3_SuperstructureStates.L2_ALGAE_PREP, V3_SuperstructureStates.L3_ALGAE_PREP, "Algae Prep L2 to L3")); + AlgaeEdges.add(new Edge(V3_SuperstructureStates.L3_ALGAE_PREP, V3_SuperstructureStates.L2_ALGAE_PREP, "Algae Prep L3 to L2")); + + // BARGE_PREP Edges + AlgaeEdges.add(new Edge(V3_SuperstructureStates.L2_ALGAE_PREP, V3_SuperstructureStates.BARGE_PREP, "Algae Prep Barge to L2")); + AlgaeEdges.add(new Edge(V3_SuperstructureStates.L3_ALGAE_PREP, V3_SuperstructureStates.BARGE_PREP, "Algae Prep Barge to L3")); + AlgaeEdges.add(new Edge(V3_SuperstructureStates.STOW_UP, V3_SuperstructureStates.BARGE_PREP, "Algae Prep L2 to Barge")); + AlgaeEdges.add(new Edge(V3_SuperstructureStates.BARGE_PREP, V3_SuperstructureStates.BARGE_SCORE, "Algae Prep L2 to Barge")); + + // PROCESSOR Edges + AlgaeEdges.add(new Edge(V3_SuperstructureStates.PROCESSOR_PREP, V3_SuperstructureStates.PROCESSOR_SCORE, "Algae Processor L2")); + AlgaeEdges.add(new Edge(V3_SuperstructureStates.L2_ALGAE_PREP, V3_SuperstructureStates.PROCESSOR_PREP, "Algae Processor L2 Prep")); + AlgaeEdges.add(new Edge(V3_SuperstructureStates.L3_ALGAE_PREP, V3_SuperstructureStates.PROCESSOR_PREP, "Algae Processor L3 Prep")); + AlgaeEdges.add(new Edge(V3_SuperstructureStates.PROCESSOR_SCORE, V3_SuperstructureStates.STOW_DOWN, "Algae Processor Barge Prep")); + + // Unconstrained Edges + + // BARGE_SCORE -> STOW_DOWN + AlgaeEdges.add(new Edge(V3_SuperstructureStates.BARGE_SCORE, V3_SuperstructureStates.STOW_DOWN, "BARGE_SCORE to Stow Down")); + + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index de870c45..cdb71574 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -138,8 +138,8 @@ public enum V3_SuperstructureStates { SubsystemActions.empty()), // Algae Scoring States - L2_ALGAE_SCORE( - "L2_ALGAE_SCORE", + L2_ALGAE_INTAKE( + "L2_ALGAE_INTAKE", new SubsystemPoses( ReefState.L2, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, @@ -148,8 +148,8 @@ public enum V3_SuperstructureStates { V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), - L3_ALGAE_SCORE( - "L3_ALGAE_SCORE", + L3_ALGAE_INTAKE( + "L3_ALGAE_INTAKE", new SubsystemPoses( ReefState.L3, V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, From 2fb96e7bd147b3fb59fbf956f39259eea8fdc4a5 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sat, 16 Aug 2025 07:32:32 -0400 Subject: [PATCH 035/180] Organized edges --- .../v3_Epsilon/superstructure/V3_SuperstructureEdges.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java index 740c4ec3..1435021a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java @@ -143,12 +143,12 @@ public static void createEdges () { AlgaeEdges.add(new Edge(V3_SuperstructureStates.PROCESSOR_PREP, V3_SuperstructureStates.PROCESSOR_SCORE, "Algae Processor L2")); AlgaeEdges.add(new Edge(V3_SuperstructureStates.L2_ALGAE_PREP, V3_SuperstructureStates.PROCESSOR_PREP, "Algae Processor L2 Prep")); AlgaeEdges.add(new Edge(V3_SuperstructureStates.L3_ALGAE_PREP, V3_SuperstructureStates.PROCESSOR_PREP, "Algae Processor L3 Prep")); - AlgaeEdges.add(new Edge(V3_SuperstructureStates.PROCESSOR_SCORE, V3_SuperstructureStates.STOW_DOWN, "Algae Processor Barge Prep")); // Unconstrained Edges // BARGE_SCORE -> STOW_DOWN AlgaeEdges.add(new Edge(V3_SuperstructureStates.BARGE_SCORE, V3_SuperstructureStates.STOW_DOWN, "BARGE_SCORE to Stow Down")); + AlgaeEdges.add(new Edge(V3_SuperstructureStates.PROCESSOR_SCORE, V3_SuperstructureStates.STOW_DOWN, "Algae Processor Barge Prep")); } From 75c73d422d036c2b8b53583e99580c22fbcf38ba Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sat, 16 Aug 2025 07:36:23 -0400 Subject: [PATCH 036/180] Added more states --- .../v3_Epsilon/superstructure/V3_SuperstructureEdges.java | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java index 1435021a..6541b988 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java @@ -148,6 +148,7 @@ public static void createEdges () { // BARGE_SCORE -> STOW_DOWN AlgaeEdges.add(new Edge(V3_SuperstructureStates.BARGE_SCORE, V3_SuperstructureStates.STOW_DOWN, "BARGE_SCORE to Stow Down")); + AlgaeEdges.add(new Edge(V3_SuperstructureStates.BARGE_SCORE, V3_SuperstructureStates.STOW_UP, "BARGE_SCORE to Stow Up")); AlgaeEdges.add(new Edge(V3_SuperstructureStates.PROCESSOR_SCORE, V3_SuperstructureStates.STOW_DOWN, "Algae Processor Barge Prep")); From 1914bf8d44b4ca34b045ba6d8c6a12a706f787b9 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sat, 16 Aug 2025 11:06:11 -0400 Subject: [PATCH 037/180] Superstructure changes --- .../superstructure/V3_Superstructure.java | 22 +- .../V3_SuperstructureEdges.java | 209 ++++++++++++------ .../V3_SuperstructureStates.java | 76 +++---- 3 files changed, 184 insertions(+), 123 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java index 6cf44530..d490a8ce 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java @@ -25,8 +25,8 @@ import org.littletonrobotics.junction.Logger; /** - * The V3_Superstructure class manages the coordinated movement and state transitions of - * the robot's major subsystems including elevator, funnel, manipulator, and intake. + * The V3_Superstructure class manages the coordinated movement and state transitions of the robot's + * major subsystems including elevator, funnel, manipulator, and intake. */ public class V3_Superstructure extends SubsystemBase { @@ -71,9 +71,7 @@ public class V3_Superstructure extends SubsystemBase { * @param manipulator The manipulator subsystem. */ public V3_Superstructure( - ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { + ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { this.elevator = elevator; this.intake = intake; this.manipulator = manipulator; @@ -201,8 +199,7 @@ && isEdgeAllowed(edgeToCurrentState, goal)) { */ private Optional bfs( V3_SuperstructureStates start, V3_SuperstructureStates goal) { - Map parents = - new HashMap<>(); + Map parents = new HashMap<>(); Queue queue = new LinkedList<>(); queue.add(start); parents.put(start, null); @@ -294,8 +291,7 @@ public boolean atGoal() { * @return Command that runs the override and resumes the old goal */ public Command override(Runnable action) { - return Commands.sequence( - runGoal(V3_SuperstructureStates.OVERRIDE), Commands.run(action)) + return Commands.sequence(runGoal(V3_SuperstructureStates.OVERRIDE), Commands.run(action)) .finallyDo(() -> setGoal(currentState)); } @@ -321,8 +317,7 @@ public Command runGoalUntil(V3_SuperstructureStates goal, BooleanSupplier condit return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); } - public Command runGoalUntil( - Supplier goal, BooleanSupplier condition) { + public Command runGoalUntil(Supplier goal, BooleanSupplier condition) { return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); } @@ -344,9 +339,7 @@ public Command runPreviousState() { * @return Full command sequence */ public Command runActionWithTimeout( - V3_SuperstructureStates pose, - V3_SuperstructureStates action, - double timeout) { + V3_SuperstructureStates pose, V3_SuperstructureStates action, double timeout) { return Commands.sequence( runGoal(action), // Run the action Commands.waitUntil(() -> atGoal()), @@ -355,7 +348,6 @@ public Command runActionWithTimeout( .finallyDo(() -> setGoal(pose)); // Return to original pose } - /** * Checks if the elevator is at its goal position. * diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java index 6541b988..f9b95a20 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java @@ -1,15 +1,15 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; -import java.util.ArrayList; -import java.util.List; -import org.jgrapht.graph.DefaultEdge; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.subsystems.shared.elevator.Elevator; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; +import java.util.ArrayList; +import java.util.List; import lombok.Builder; import lombok.Getter; +import org.jgrapht.graph.DefaultEdge; public class V3_SuperstructureEdges { @@ -40,7 +40,7 @@ public enum CoralEdge { CORAL } - @Builder(toBuilder = true) + @Builder(toBuilder = true) @Getter public static class EdgeCommand extends DefaultEdge { private final Command command; @@ -49,33 +49,33 @@ public static class EdgeCommand extends DefaultEdge { } private static Command getEdgeCommand( - V3_SuperstructureStates from, - V3_SuperstructureStates to, - Elevator.ElevatorFSM elevator, - V3_EpsilonIntake intake, + V3_SuperstructureStates from, + V3_SuperstructureStates to, + Elevator.ElevatorFSM elevator, + V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { - // TODO: Implement the actual command logic - - return Commands.none(); - } + // TODO: Implement the actual command logic - public static void createEdges () { - List coralPrepLevels = List.of( - V3_SuperstructureStates.L1_PREP, - V3_SuperstructureStates.L2_PREP, - V3_SuperstructureStates.L3_PREP, - V3_SuperstructureStates.L4_PREP - ); + return Commands.none(); + } - List coralTransitionLevels = List.of( - V3_SuperstructureStates.L2_TRANSITION, - V3_SuperstructureStates.L3_TRANSITION, - V3_SuperstructureStates.L4_TRANSITION - ); + public static void createEdges() { + List coralPrepLevels = + List.of( + V3_SuperstructureStates.L1_PREP, + V3_SuperstructureStates.L2_PREP, + V3_SuperstructureStates.L3_PREP, + V3_SuperstructureStates.L4_PREP); + + List coralTransitionLevels = + List.of( + V3_SuperstructureStates.L2_TRANSITION, + V3_SuperstructureStates.L3_TRANSITION, + V3_SuperstructureStates.L4_TRANSITION); // Coral Edges - + // Level to level edges for (V3_SuperstructureStates from : coralPrepLevels) { for (V3_SuperstructureStates to : coralPrepLevels) { @@ -85,16 +85,20 @@ public static void createEdges () { } } - // Handoff -> transition - for (V3_SuperstructureStates to: coralTransitionLevels) { + // Handoff -> transition + for (V3_SuperstructureStates to : coralTransitionLevels) { CoralEdges.add(new Edge(V3_SuperstructureStates.HANDOFF, to, "Coral Transition")); } // Handoff -> L1_PREP - CoralEdges.add(new Edge(V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.HANDOFF, "Coral Handoff L1 Prep")); + CoralEdges.add( + new Edge( + V3_SuperstructureStates.L1_PREP, + V3_SuperstructureStates.HANDOFF, + "Coral Handoff L1 Prep")); // Transition -> handoff - for (V3_SuperstructureStates from: coralTransitionLevels) { + for (V3_SuperstructureStates from : coralTransitionLevels) { CoralEdges.add(new Edge(from, V3_SuperstructureStates.HANDOFF, "Coral Handoff")); } @@ -103,60 +107,135 @@ public static void createEdges () { for (V3_SuperstructureStates to : coralTransitionLevels) { CoralEdges.add(new Edge(from, to, "Coral Transition")); } - } - + } + // Coral Transition to Prep - CoralEdges.add(new Edge(V3_SuperstructureStates.L2_TRANSITION, V3_SuperstructureStates.L2_PREP, "Coral Transition L2")); - CoralEdges.add(new Edge(V3_SuperstructureStates.L3_TRANSITION, V3_SuperstructureStates.L3_PREP, "Coral Transition L3")); - CoralEdges.add(new Edge(V3_SuperstructureStates.L4_TRANSITION, V3_SuperstructureStates.L4_PREP, "Coral Transition L3")); - + CoralEdges.add( + new Edge( + V3_SuperstructureStates.L2_TRANSITION, + V3_SuperstructureStates.L2_PREP, + "Coral Transition L2")); + CoralEdges.add( + new Edge( + V3_SuperstructureStates.L3_TRANSITION, + V3_SuperstructureStates.L3_PREP, + "Coral Transition L3")); + CoralEdges.add( + new Edge( + V3_SuperstructureStates.L4_TRANSITION, + V3_SuperstructureStates.L4_PREP, + "Coral Transition L3")); // Prep to score states - CoralEdges.add(new Edge(V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.L1_SCORE, "Coral Score L1")); - CoralEdges.add(new Edge(V3_SuperstructureStates.L2_PREP, V3_SuperstructureStates.L2_SCORE, "Coral Score L2")); - CoralEdges.add(new Edge(V3_SuperstructureStates.L3_PREP, V3_SuperstructureStates.L3_SCORE, "Coral Score L3")); - CoralEdges.add(new Edge(V3_SuperstructureStates.L4_PREP, V3_SuperstructureStates.L4_SCORE, "Coral Score L4")); - + CoralEdges.add( + new Edge( + V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.L1_SCORE, "Coral Score L1")); + CoralEdges.add( + new Edge( + V3_SuperstructureStates.L2_PREP, V3_SuperstructureStates.L2_SCORE, "Coral Score L2")); + CoralEdges.add( + new Edge( + V3_SuperstructureStates.L3_PREP, V3_SuperstructureStates.L3_SCORE, "Coral Score L3")); + CoralEdges.add( + new Edge( + V3_SuperstructureStates.L4_PREP, V3_SuperstructureStates.L4_SCORE, "Coral Score L4")); + // L1_SCORE -> GROUND_INTAKE - CoralEdges.add(new Edge(V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.GROUND_INTAKE, "Coral Transition L1")); + CoralEdges.add( + new Edge( + V3_SuperstructureStates.L1_PREP, + V3_SuperstructureStates.GROUND_INTAKE, + "Coral Transition L1")); // Algae Edges // STOW_DOWN --> L2_ALGAE_PREP - AlgaeEdges.add(new Edge(V3_SuperstructureStates.STOW_DOWN, V3_SuperstructureStates.L2_ALGAE_PREP, "Algae Prep L2 from STOW DOWN")); + AlgaeEdges.add( + new Edge( + V3_SuperstructureStates.STOW_DOWN, + V3_SuperstructureStates.L2_ALGAE_PREP, + "Algae Prep L2 from STOW DOWN")); // Prep --> intake states - AlgaeEdges.add(new Edge(V3_SuperstructureStates.L2_ALGAE_PREP, V3_SuperstructureStates.L2_ALGAE_INTAKE, "Algae Intake L2")); - AlgaeEdges.add(new Edge(V3_SuperstructureStates.L3_ALGAE_PREP, V3_SuperstructureStates.L3_ALGAE_INTAKE, "Algae Intake L3")); + AlgaeEdges.add( + new Edge( + V3_SuperstructureStates.L2_ALGAE_PREP, + V3_SuperstructureStates.L2_ALGAE_INTAKE, + "Algae Intake L2")); + AlgaeEdges.add( + new Edge( + V3_SuperstructureStates.L3_ALGAE_PREP, + V3_SuperstructureStates.L3_ALGAE_INTAKE, + "Algae Intake L3")); // Prep <-> Prep States - AlgaeEdges.add(new Edge(V3_SuperstructureStates.L2_ALGAE_PREP, V3_SuperstructureStates.L3_ALGAE_PREP, "Algae Prep L2 to L3")); - AlgaeEdges.add(new Edge(V3_SuperstructureStates.L3_ALGAE_PREP, V3_SuperstructureStates.L2_ALGAE_PREP, "Algae Prep L3 to L2")); + AlgaeEdges.add( + new Edge( + V3_SuperstructureStates.L2_ALGAE_PREP, + V3_SuperstructureStates.L3_ALGAE_PREP, + "Algae Prep L2 to L3")); + AlgaeEdges.add( + new Edge( + V3_SuperstructureStates.L3_ALGAE_PREP, + V3_SuperstructureStates.L2_ALGAE_PREP, + "Algae Prep L3 to L2")); // BARGE_PREP Edges - AlgaeEdges.add(new Edge(V3_SuperstructureStates.L2_ALGAE_PREP, V3_SuperstructureStates.BARGE_PREP, "Algae Prep Barge to L2")); - AlgaeEdges.add(new Edge(V3_SuperstructureStates.L3_ALGAE_PREP, V3_SuperstructureStates.BARGE_PREP, "Algae Prep Barge to L3")); - AlgaeEdges.add(new Edge(V3_SuperstructureStates.STOW_UP, V3_SuperstructureStates.BARGE_PREP, "Algae Prep L2 to Barge")); - AlgaeEdges.add(new Edge(V3_SuperstructureStates.BARGE_PREP, V3_SuperstructureStates.BARGE_SCORE, "Algae Prep L2 to Barge")); + AlgaeEdges.add( + new Edge( + V3_SuperstructureStates.L2_ALGAE_PREP, + V3_SuperstructureStates.BARGE_PREP, + "Algae Prep Barge to L2")); + AlgaeEdges.add( + new Edge( + V3_SuperstructureStates.L3_ALGAE_PREP, + V3_SuperstructureStates.BARGE_PREP, + "Algae Prep Barge to L3")); + AlgaeEdges.add( + new Edge( + V3_SuperstructureStates.STOW_UP, + V3_SuperstructureStates.BARGE_PREP, + "Algae Prep L2 to Barge")); + AlgaeEdges.add( + new Edge( + V3_SuperstructureStates.BARGE_PREP, + V3_SuperstructureStates.BARGE_SCORE, + "Algae Prep L2 to Barge")); // PROCESSOR Edges - AlgaeEdges.add(new Edge(V3_SuperstructureStates.PROCESSOR_PREP, V3_SuperstructureStates.PROCESSOR_SCORE, "Algae Processor L2")); - AlgaeEdges.add(new Edge(V3_SuperstructureStates.L2_ALGAE_PREP, V3_SuperstructureStates.PROCESSOR_PREP, "Algae Processor L2 Prep")); - AlgaeEdges.add(new Edge(V3_SuperstructureStates.L3_ALGAE_PREP, V3_SuperstructureStates.PROCESSOR_PREP, "Algae Processor L3 Prep")); + AlgaeEdges.add( + new Edge( + V3_SuperstructureStates.PROCESSOR_PREP, + V3_SuperstructureStates.PROCESSOR_SCORE, + "Algae Processor L2")); + AlgaeEdges.add( + new Edge( + V3_SuperstructureStates.L2_ALGAE_PREP, + V3_SuperstructureStates.PROCESSOR_PREP, + "Algae Processor L2 Prep")); + AlgaeEdges.add( + new Edge( + V3_SuperstructureStates.L3_ALGAE_PREP, + V3_SuperstructureStates.PROCESSOR_PREP, + "Algae Processor L3 Prep")); // Unconstrained Edges - - // BARGE_SCORE -> STOW_DOWN - AlgaeEdges.add(new Edge(V3_SuperstructureStates.BARGE_SCORE, V3_SuperstructureStates.STOW_DOWN, "BARGE_SCORE to Stow Down")); - AlgaeEdges.add(new Edge(V3_SuperstructureStates.BARGE_SCORE, V3_SuperstructureStates.STOW_UP, "BARGE_SCORE to Stow Up")); - AlgaeEdges.add(new Edge(V3_SuperstructureStates.PROCESSOR_SCORE, V3_SuperstructureStates.STOW_DOWN, "Algae Processor Barge Prep")); - + // BARGE_SCORE -> STOW_DOWN + AlgaeEdges.add( + new Edge( + V3_SuperstructureStates.BARGE_SCORE, + V3_SuperstructureStates.STOW_DOWN, + "BARGE_SCORE to Stow Down")); + AlgaeEdges.add( + new Edge( + V3_SuperstructureStates.BARGE_SCORE, + V3_SuperstructureStates.STOW_UP, + "BARGE_SCORE to Stow Up")); + AlgaeEdges.add( + new Edge( + V3_SuperstructureStates.PROCESSOR_SCORE, + V3_SuperstructureStates.STOW_DOWN, + "Algae Processor Barge Prep")); } } - - - - - - diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java index cdb71574..0205fe6a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java @@ -22,28 +22,23 @@ public enum V3_SuperstructureStates { V3_EpsilonIntakeConstants.IntakeState.STOW), SubsystemActions.empty()), - HANDOFF( - "HANDOFF", - new SubsystemPoses( - ReefState.STOW, - V3_EpsilonManipulatorConstants.PivotState.HANDOFF, - V3_EpsilonIntakeConstants.IntakeState.HANDOFF - ), - SubsystemActions.empty() - ), - - GROUND_INTAKE( - "GROUND_INTAKE", - new SubsystemPoses( - ReefState.STOW, - V3_EpsilonManipulatorConstants.PivotState.FLOOR_INTAKE, - V3_EpsilonIntakeConstants.IntakeState.INTAKE_CORAL - ), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP, - V3_EpsilonIntakeConstants.IntakeRollerStates.CORAL_INTAKE - ) - ), + HANDOFF( + "HANDOFF", + new SubsystemPoses( + ReefState.STOW, + V3_EpsilonManipulatorConstants.PivotState.HANDOFF, + V3_EpsilonIntakeConstants.IntakeState.HANDOFF), + SubsystemActions.empty()), + + GROUND_INTAKE( + "GROUND_INTAKE", + new SubsystemPoses( + ReefState.STOW, + V3_EpsilonManipulatorConstants.PivotState.FLOOR_INTAKE, + V3_EpsilonIntakeConstants.IntakeState.INTAKE_CORAL), + new SubsystemActions( + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP, + V3_EpsilonIntakeConstants.IntakeRollerStates.CORAL_INTAKE)), // Coral Prep States L1_PREP( @@ -197,16 +192,14 @@ public enum V3_SuperstructureStates { new SubsystemActions( V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), - + INTERMIDIATE_WAIT_FOR_ELEVATOR( - "INTERMIDIATE_WAIT_FOR_ELEVATOR", - new SubsystemPoses( - ReefState.STOW, - V3_EpsilonManipulatorConstants.PivotState.STOW_UP, - V3_EpsilonIntakeConstants.IntakeState.STOW - ), - SubsystemActions.empty() - ), + "INTERMIDIATE_WAIT_FOR_ELEVATOR", + new SubsystemPoses( + ReefState.STOW, + V3_EpsilonManipulatorConstants.PivotState.STOW_UP, + V3_EpsilonIntakeConstants.IntakeState.STOW), + SubsystemActions.empty()), // Transition States L2_TRANSITION( @@ -233,18 +226,15 @@ public enum V3_SuperstructureStates { V3_EpsilonIntakeConstants.IntakeState.STOW), SubsystemActions.empty()), - CLIMB( - "CLIMB", - new SubsystemPoses( - ReefState.STOW, - V3_EpsilonManipulatorConstants.PivotState.STOW_UP, - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), - - OVERRIDE( - "OVERRIDE", - new SubsystemPoses(), - SubsystemActions.empty()); + CLIMB( + "CLIMB", + new SubsystemPoses( + ReefState.STOW, + V3_EpsilonManipulatorConstants.PivotState.STOW_UP, + V3_EpsilonIntakeConstants.IntakeState.STOW), + SubsystemActions.empty()), + + OVERRIDE("OVERRIDE", new SubsystemPoses(), SubsystemActions.empty()); // Readable name for state private final String name; From 77628c72a9c576e829b49939340c64677639f8b9 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sat, 16 Aug 2025 11:24:46 -0400 Subject: [PATCH 038/180] Further organization --- .../superstructure/V3_SuperstructureEdges.java | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java index f9b95a20..fa0c4415 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java @@ -222,20 +222,25 @@ public static void createEdges() { // Unconstrained Edges // BARGE_SCORE -> STOW_DOWN - AlgaeEdges.add( + UnconstrainedEdges.add( new Edge( V3_SuperstructureStates.BARGE_SCORE, V3_SuperstructureStates.STOW_DOWN, "BARGE_SCORE to Stow Down")); - AlgaeEdges.add( + UnconstrainedEdges.add( new Edge( V3_SuperstructureStates.BARGE_SCORE, V3_SuperstructureStates.STOW_UP, "BARGE_SCORE to Stow Up")); - AlgaeEdges.add( + UnconstrainedEdges.add( new Edge( V3_SuperstructureStates.PROCESSOR_SCORE, V3_SuperstructureStates.STOW_DOWN, "Algae Processor Barge Prep")); + UnconstrainedEdges.add( + new Edge( + V3_SuperstructureStates.STOW_UP, + V3_SuperstructureStates.STOW_DOWN, + "Algae Processor Barge Prep")); } } From e35bacca5bb2c88835c7bf800ca30ddf3d6031ee Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Tue, 19 Aug 2025 19:02:35 -0400 Subject: [PATCH 039/180] Added transition --- .../subsystems/v3_Epsilon/superstructure/Superstructure.dot | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index ab3d8fe5..4ca17570 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -122,6 +122,8 @@ digraph Superstructure { L3_algae_prep -> stow_up [color = blue] L2_algae_prep -> L2_algae_intake [color = blue] + L2_algae_intake -> L2_algae_prep [color = blue] + L3_algae_intake -> L3_algae_prep [color = blue] L3_algae_prep -> L3_algae_intake [color = blue] L2_algae_intake -> stow_up [color = blue] From 0bb5fc6cc518875ea06a5b78fbf610127e71da53 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Mon, 25 Aug 2025 19:18:51 -0400 Subject: [PATCH 040/180] lkjhkjhljkhljhlkj --- .../v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java index 378d44df..032f294b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java @@ -1,8 +1,9 @@ package frc.robot.subsystems.v3_Epsilon.manipulator; -import edu.wpi.first.math.geometry.Rotation2d; import org.littletonrobotics.junction.AutoLog; +import edu.wpi.first.math.geometry.Rotation2d; + public interface V3_EpsilonManipulatorIO { @AutoLog @@ -29,7 +30,7 @@ public static class ManipulatorIOInputs { } /** - * Updates the inputs for the manipulator subsystem. + * Updates the inputs for the manipulator subsystem . * * @param inputs The inputs to update. */ From 725a29349bf2de58c98bd52d7beb9a15a6aa02e2 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Mon, 25 Aug 2025 22:47:01 -0400 Subject: [PATCH 041/180] merge development --- .../v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java | 5 ++--- .../v3_Epsilon/superstructure/V3_Superstructure.java | 6 +++--- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java index 032f294b..2627908e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java @@ -1,8 +1,7 @@ package frc.robot.subsystems.v3_Epsilon.manipulator; -import org.littletonrobotics.junction.AutoLog; - import edu.wpi.first.math.geometry.Rotation2d; +import org.littletonrobotics.junction.AutoLog; public interface V3_EpsilonManipulatorIO { @@ -30,7 +29,7 @@ public static class ManipulatorIOInputs { } /** - * Updates the inputs for the manipulator subsystem . + * Updates the inputs for the manipulator subsystem . * * @param inputs The inputs to update. */ diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java index d490a8ce..60764026 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java @@ -8,8 +8,8 @@ import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureEdges.AlgaeEdge; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureEdges.EdgeCommand; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureEdges.GamePieceEdge; import frc.robot.util.NTPrefixes; import java.util.HashMap; import java.util.LinkedList; @@ -238,8 +238,8 @@ private Optional bfs( * @return true if the transition is allowed */ private boolean isEdgeAllowed(EdgeCommand edge, V3_SuperstructureStates goal) { // Change later - return edge.getEdgeType() == GamePieceEdge.NONE - || RobotState.isHasAlgae() == (edge.getEdgeType() == GamePieceEdge.ALGAE); + return edge.getAlgaeEdgeType() == AlgaeEdge.NONE + || RobotState.isHasAlgae() == (edge.getAlgaeEdgeType() == AlgaeEdge.ALGAE); } /** Resets the superstructure to initial auto state. */ From 85df130fe0695dae609df12b9df58c94976b3a49 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Wed, 27 Aug 2025 18:34:06 -0400 Subject: [PATCH 042/180] Add mechanism 3d --- .../v3_Epsilon/V3_EpsilonMechanism3d.java | 73 +++++++++++++++++++ 1 file changed, 73 insertions(+) create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonMechanism3d.java diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonMechanism3d.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonMechanism3d.java new file mode 100644 index 00000000..916d314d --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonMechanism3d.java @@ -0,0 +1,73 @@ +package frc.robot.subsystems.v3_Epsilon; + +import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.geometry.Pose3d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Rotation3d; +import edu.wpi.first.math.geometry.Transform3d; +import org.littletonrobotics.junction.Logger; + +public class V3_EpsilonMechanism3d { + private static final double ELEVATOR_STAGE_1_MIN_HEIGHT = 0.095250; // Meters off the ground + private static final double ELEVATOR_STAGE_1_MAX_HEIGHT = 0.7809; + private static final double ELEVATOR_CARRIAGE_MANIPULATOR_MIN_HEIGHT = 0.120650; + private static final double ELEVATOR_CARRIAGE_MANIPULATOR_MAX_HEIGHT = 0.877522325; + + private static final double MIN_EXTENSION_METERS = ELEVATOR_CARRIAGE_MANIPULATOR_MIN_HEIGHT; + private static final double MAX_EXTENSION_METERS = + ELEVATOR_STAGE_1_MAX_HEIGHT + ELEVATOR_CARRIAGE_MANIPULATOR_MAX_HEIGHT; + + private static final Pose3d ELEVATOR_STAGE_1 = + new Pose3d(-0.177800, 0, 0.095250, new Rotation3d()); + private static final Pose3d ELEVATOR_CARRIAGE_MANIPULATOR = + new Pose3d(-0.15381615, 0, 0.120650, new Rotation3d()); + + public static final Pose3d[] getPoses( + double elevatorExtensionMeters, Rotation2d intakeAngle, Rotation2d armAngle) { + double extensionMeters = + MathUtil.clamp(elevatorExtensionMeters, MIN_EXTENSION_METERS, MAX_EXTENSION_METERS); + + double stage1Height = ELEVATOR_STAGE_1_MIN_HEIGHT; + double carriageHeight = ELEVATOR_CARRIAGE_MANIPULATOR_MIN_HEIGHT; + + // If extension is within the first stage's range, only move carriage + if (extensionMeters <= ELEVATOR_STAGE_1_MAX_HEIGHT) { + carriageHeight = extensionMeters; + } else { + // Carriage is fully extended, start moving stage 1 + double remainingExtension = extensionMeters - ELEVATOR_CARRIAGE_MANIPULATOR_MAX_HEIGHT; + stage1Height = ELEVATOR_STAGE_1_MIN_HEIGHT + remainingExtension; + carriageHeight = ELEVATOR_CARRIAGE_MANIPULATOR_MAX_HEIGHT + remainingExtension; + } + + // Create transformed poses + Pose3d ELEVATOR_STAGE_1_POSE = + ELEVATOR_STAGE_1.transformBy( + new Transform3d(0, 0, stage1Height - ELEVATOR_STAGE_1_MIN_HEIGHT, new Rotation3d())); + Pose3d ELEVATOR_CARRIAGE_POSE = + ELEVATOR_CARRIAGE_MANIPULATOR.transformBy( + new Transform3d( + 0, 0, carriageHeight - ELEVATOR_CARRIAGE_MANIPULATOR_MIN_HEIGHT, new Rotation3d())); + + Logger.recordOutput( + "Zero Poses", + new Pose3d[] { + new Pose3d(), new Pose3d(), new Pose3d(), new Pose3d(), new Pose3d(), new Pose3d() + }); + + return new Pose3d[] { + new Pose3d(0.1875, 0, 0.1363, new Rotation3d(0.0, intakeAngle.getRadians(), 0.0)), + ELEVATOR_STAGE_1_POSE, + ELEVATOR_CARRIAGE_POSE, + new Pose3d(-0.15381615, + 0, +0.270855, new Rotation3d()) + .transformBy( + new Transform3d( + 0, + 0, + carriageHeight - ELEVATOR_CARRIAGE_MANIPULATOR_MIN_HEIGHT, + new Rotation3d(armAngle.getRadians(), 0.0, 0.0))), + }; + } +} From 6b68545a74177d3fb73bf41b0356b1f1bd811905 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Wed, 27 Aug 2025 18:35:03 -0400 Subject: [PATCH 043/180] Add epsilon model --- .../Robot_Epsilon/config.json | 93 ++++++++++++++++++ advantagescopeassets/Robot_Epsilon/model.glb | Bin 0 -> 38682964 bytes .../Robot_Epsilon/model_0.glb | Bin 0 -> 8059300 bytes .../Robot_Epsilon/model_1.glb | Bin 0 -> 3379232 bytes .../Robot_Epsilon/model_2.glb | Bin 0 -> 5766692 bytes .../Robot_Epsilon/model_3.glb | Bin 0 -> 7611684 bytes 6 files changed, 93 insertions(+) create mode 100644 advantagescopeassets/Robot_Epsilon/config.json create mode 100644 advantagescopeassets/Robot_Epsilon/model.glb create mode 100644 advantagescopeassets/Robot_Epsilon/model_0.glb create mode 100644 advantagescopeassets/Robot_Epsilon/model_1.glb create mode 100644 advantagescopeassets/Robot_Epsilon/model_2.glb create mode 100644 advantagescopeassets/Robot_Epsilon/model_3.glb diff --git a/advantagescopeassets/Robot_Epsilon/config.json b/advantagescopeassets/Robot_Epsilon/config.json new file mode 100644 index 00000000..d22a5fdf --- /dev/null +++ b/advantagescopeassets/Robot_Epsilon/config.json @@ -0,0 +1,93 @@ +{ + "name": "Epsilon", + "sourceUrl": "https://frc190.onshape.com/documents/fffbf0683934212b94752d43/w/aa43f9bee049f3b1d51e0915/e/de81482fe4fd1694f19df80a", + "disableSimplification": true, + "rotations": [ + { + "axis": "x", + "degrees": 90 + }, + { + "axis": "z", + "degrees": -90 + } + ], + "position": [ + 0, + 0, + 0 + ], + "cameras": [ + ], + "components": [ + { + "zeroedRotations": [ + { + "axis": "x", + "degrees": 90 + }, + { + "axis": "z", + "degrees": -90 + } + ], + "zeroedPosition": [ + -0.1875, + 0, + -0.1363 + ] + }, + { + "zeroedRotations": [ + { + "axis": "x", + "degrees": 90 + }, + { + "axis": "z", + "degrees": -90 + } + ], + "zeroedPosition": [ + 0.177800, + 0, + -0.095250 + ] + }, + { + "zeroedRotations": [ + { + "axis": "x", + "degrees": 90 + }, + { + "axis": "z", + "degrees": -90 + } + ], + "zeroedPosition": [ + 0.15381615, + 0, + -0.120650 + ] + }, + { + "zeroedRotations": [ + { + "axis": "x", + "degrees": 90 + }, + { + "axis": "z", + "degrees": -90 + } + ], + "zeroedPosition": [ + 0.15381615, + 0, +-0.270855 + + ] + } + ] +} diff --git a/advantagescopeassets/Robot_Epsilon/model.glb b/advantagescopeassets/Robot_Epsilon/model.glb new file mode 100644 index 0000000000000000000000000000000000000000..55f0efc5daac48cb5d0ecaedbe327a8d0bd6a4d2 GIT binary patch literal 38682964 zcmd44%dT`gj^A1EQ+RyFS&6t`a@H{14R~M=obbf(z)qYp40N4LxU$e)F#L-BO#P!S zOQfW=C`D+yyiex&z7soQ1^*&N@h0-W{@;K6KmWzw{LSC|@&EX@|KeZ%U;p3V{F{IO z@BZ!o_~k$U=}*7@!$17_zyHH8fB29836^Umw)=} zumA4v{_Y=s{cHHoKmGad|MKVGe*NvQfBdJv{QAou?&r(ncfb7U&;R%vzkc3+_sie^ z=l_?doPK|~oZip3`uW}I_ov6@ay^xwGq0WRm)n2hWB={9@Uipje!Iw9FOSDF{Q7i0 z%Nzb0zV4U*@UQ>X^_TzoyF)5pua}UtPv;d_h0fRQc|F~)m)q%dxye`G&d=xN@p@j~ z_xt5^eYaFzE|=%|@;trXuk-D8l@DFt*XQ$odfe~V^XvTjko5EA=FooO_Z#ik+v#zB zylHT`J{6fg(d4Igmm-|VUU)Hi(Vp#Bcp6>7S{R!>&(_KDwc|Ko!=2NooFIa!H z``*J?LZ?6kq$nu^~as6)B)Ae>aKVH|cpf%B#)A{v&Tu)$qTy9U1jT8TMe?PCc z`|bXCoaHg+`@FcEUnk_@ka#24hzm=8eV@;ea*D$GzC16`a09{#P;niNU?Vbu_5J1} z@7rU+n!g{8sF)>hzP-126~!GkUAjo;7yWX2I1;1R{Cd4#ueTTfdLXf~cCymQIs5JM zINu}dE9#ql-P;)-P<}pNj>W~U`-q~bC`V78-{;fm{$P^?L2ow42XtRfj=Y!^cXUKW zac@t2rBN*d%lm{T3R>tpHF)7!$3*Ls z=lr^cL*|TTyWgKt4fRWBd^NYQ8LV?4o>+`<1y(*&bkbHigUo8DY%z;HG z&lP=kEH8%gAu1}$2bnalPB^60s1Ksk2Wv2=?BWn1?A{cP;hI+oS@DKSDW2doX&zQW)YQ-RUu&XiK*_&5P+)tecya4BzGzZV?iv5u- zaO6hlew@#!ijEB^mS(ZM!&2WLXN2VSyuB~@MW4D2Hrsg3G>;;bkWHk_CHL}S2I zhU@+PxIAwdW$y>}_s2xzJ5CVIVWVtpS?4>3_;v#IoCYl)caiVy;E8V0yi6m8jwaE& zv1RwcDmy&+fL1p4@%n07)mG{)l~s1?&Amb>dtqrdal!l{XKA_cg4wZK9ZKaN-Q!Q^J_q{Fq z0p)~3kGG!$-m~?5AqGaY`uu!fG3HON5D>$n6o2)J;e@vx9GN<*dM42Hx}sCDVz0qu zKHqP6OV>N0?AJX8=szG{9P7i7svJF;cp@6F%UyH^cJt##U_pPoS?=@m_J~pHHFQ3` z80uBYGUhu08^RWlOXyeVeV^{H*Xez~y{=cGC>Rkt6u&ULG1NI?Bsw47Ilr>c^Nflk z9F8zN$#1+aF+NUigaeciG=cI*kdiw8(qQb0(Fc@YCRAMEb7$3d*0&=&pHMlY+=jMK zMQ)Mx6+7*Db&WWqCNOj_lJgP2n)qSZbF$O#dC#3XNx94U%+ZL*gpUQm7rEyddZT`@ z*ywvlO(^1t9g=goVXtFm#N^=FCH?$-JxSE$4+X1^|6D=*+w-}#f+nVMM=cX-dGc3s zFRc9Obs`P&y61#wXXVfDD?auKF5_|qOX>L{>GAkfeaPlNUU9AO>M!ptTqWIaxbwnF zl2B=&w~KLJR0z~V*-?^C5q=@2LUclQ+L`l2guKIYOZhN=KB3(UtQ*>!y*41_gInVR z+KGo9uX}YuVuMREnJg%Z6dC7iyu3LaNt8eF5TXZVmp-5Ar#JRBT)UkK+>lWI%pvDI z_G}Mj^KpVxY4F0)yOBSNj%qMRVm!bSO4=MB2T8%KiYX6H){l?!H>Cr|OWQY+Bmthx zrRwb77V;~yu3j!*N$Yk__jqR)uMk(rpO;50DCfw~)EzObqAnlH=-Mw>>LwZtb?+DP z1@;NMm$O1P3o(;Buf`3~JBqPE>m8=V^@H{FEp>GSOV<8$qr?F!aVuhOM18+mQ&J}v z_Emnf;QMNASuAI}sC|tl!Q4LM)Nlv{r32kB{Gb>4!si7)DX14qFiHwF@Hk&6>v@JZ zpvs6=T+j{VHb2!!BzQfeU7HFLV<1gHGKK)%i+Y%_a?c0J8EiM|0ViFpjr~OT-U)PvqA9gqKOxyQ*>w>h=lC5Gvw@rR z1v1^MO9RN`98zFN?lb=Fqk1la9FC^Y5`iO3z?3q^#|4juy~g1xg?;1`uV?B>T0Mbo zAn13Z{)&P%%#C2n<7K>&3(7Lc=RraE*ar)Y_2-x`?gEpP^A?ze{$hbI#K@23*3d|S zjTVBiT)Q-~o=FJ4qfxTS<1}6<#u=uOP|9ryjW^Dg2^z_bN4`?^*5@#hVU$Ej0(`f6 zq-LEhq&a*klwBm$*fH`IWtR(Q*r!S3^TW;08_Ifo-KDYc^-CJ5R2}Cl#$UTX_Gmnp z{qY@*90L>kqpQewX)KETI~oa=Oze*yjhJqjf#m>-CY(9l%dtZ&oPu6bf9dCAdk+I_ zV)u0ECeTI1O)ORZiAPKoyH|8$Q%Mj%z4^nF2V32%J=Z&{M>V+w$^svxQ01TA$+<}e zfi0W~+*tM2`O^|j>=}P9%^dpJ8xSu4un3*=zEDj`{Y8rY)0;mH!%+dpHC&^>XtscRNqBVsg(==#2T%g-AG1@)Hd~t>a8D02oC6%dy$ay ziHgKXhxosT62kYrg*D-yPc;a)Ks@iuU1^FJiNq$3<7ymIP2C)uH^2E)`MBd3O`Llj z=YRy@o%-CkztSz5J^46a2`xU%TR)HwcE*?IAZsfIP}F3|N-vCGGzjsK$30wGkq^Xt z#0QsFxa8vnl|2bLz0YsJ$5VrUAJR=A;*IICz4=rB1|Q1{=g}PF?rPNCsY8 z<;W4NCDoPOwCBgy$u1O{Ibv=7$wYGR+iQx`TXQ(~1NnWqF$5h&7S}c|X#Pq|(e1{q z8n*vQGTWc30aDD)meT9hex)Jl%x<}h5>G#(Qop3mGb;6hb-%v5cIP{3$(4i>y>zT! zwT!)Q7b~Nu_Ire8NFPYx8=vf0>w61&AuSq&&2qj&XMywyp>XGzP`#j>PAm$s_$S#! zaaVV!?8xW#&X0)ntZ=CdDy1`RC~Et5yP6$5ZJg^9g8kaYvp~uuZz^bq&JNeheh-i) zt^!kUf$m&u`v4cO&~wPS)9a+?gmc0&REP$c+$w2f_0H z@QdpPs>M`)E+CbFY@f=GmA{dGSNK+=)Vg;tW zRqnyWpXb$buKOS=FXSrhgNo4CS?*Q@jKnlZ98v6b;V;BQ-*X@-Ht~!f`F-BpfpALP zf*{KM^G6cTTBs7n{8p*A4y46xmMACV=Rc|Y-bs*BVR6jKfjtQJTFQdJezXbe?HuK` z+WNC7iAx=$d}mIEuj8^h$>#j?yok-eE3Z%532>_tee%*skPHV)E~i-!rDX zt(qOk6^;Uv;;eA_Of)%_5ZsBA;uZ4xmkrVGgIYjQI6F_8IK#NG>eIxIr1dfG%i;c$eo7GC zBD@VHdt`@iyIaDl{t?cFM_CzooJ8|X?JiEtW38w`_0RB@a}LV9JUfi~8q>|w81_8F za?tisRP-$bFkv4Yll8U*hK%!=(N?5zio^ zA0S!+0MF7njz^eOFYSjsT7rnG8fPof+ex#8igI-tABr7s)%NhS61%Y{MG>vuJ1KW$ z0vuaWxs!M>6GoKX_Ubqebk97AphaVj%_v3bWpu0*4alxP(&{#m%^qc&%`vlDvuq=^ z`y+@pK@@bOJc`G|w@i8s+w)6kQwQ`EPAk^)Cp4Es9bx>~Z`qg^88YUdFJYd4i_&WU ze%Ob$Dx@cK*e6tq+E9%&l(QiF529P23SM*7B!H~nJGti`G&?)qbJF}x9SG+;eKWSG z59N`O47ng!UX8~DZ@p5)d7?Oih$78eEXtiHN#i7XjF3B{_Y+^1p5J-ajJ70q>YU_O zTTY-PuShV5dqd=)DOxTl!;a<^I)|j6*9ONd7Y?47Ig_j-bL?1G)+%lw@s+{4BFji5 zFRwVEsf|y9V24dL!-FvPo;1ZJDi4mOaS#$UWzw>R66weDNd-!=MFe!x4z0v~O}`s% z)bwxW?LM`U(uQ*#07-^8-dbi(v4CvzAPaVg^TlfCgB?^ULi#l*w&x(IARqVNKe*z2 zqmoaG%}`&z{wZLh#c z^CV)(lORJ6fx{ai6i8`{iQ7H}4&RpzHErPjCvcsF*`(dVWh&~jA=re0@M06+lv%YSdkrh5DOL_U%z*foAj!1LIqZ2 z>#s`~jmjX6w<(|hEkM$B#MzfN=tD{Pg|>d%kD!U-DZkjP|9hRRu0Qs-=ii?ReoQIAohzUU=H|DKao~cbn4cW0g+B2XwAmSN7Wj1lMTvfrz zDKP4{ZWseA>ffdZQPh@?M%=k{!hBU%z@f3cLsp8Ll-p0} zK0zS0E3KV0g=J+gSKoQkEGAkj9&1kH33ay(Icx208N9MX^TodOv^9sD8@r_0Mq;)aw zi{bu*+8w$^4yh3RmTkL)%y^CF z*QKKp>vvjO-dBfTYiB|YsaT)(s8(9mQ zGc=)-d4b%Q*j%x6H;GgZGr{r?9hWv_uwL$~&?0X82_Y^Sv4j9gik|Lwbcu^68fBAo z;M{(s{$fTZxftN6#~v(M(H(jwfytBlEA%BWdJ#H8Xpd?JP|~+|`w2JF`h@Kx41(5s z5JQ-xFYxx0N~FJpNS6{%B;jo-k!~mpZ0wUZ3-ZVKNcR@+9DvUeWWdwgJD)Hz>|njK z#PG~Q&qfsHB~>= zGww5Ca)j&J{K<8^ZAa0s)N0Txdh)?DnDRz5zvRBWXevUxDC*Vd!O9b&ry~<*w+Dr? z>sMzi(9a}_>)`=PbxB?S;zXt6_R%M->{B0kfUdMAjclTamnLJ zza1R()d=i4-gcEjiWj=uV?R9UOXVUKg9CCqCCZuy2{T6`Hx52S7C^|^Q^WCCq|%nmVx0>!Rl*d;Y*lE`7liQ7G>)*Xnedn;us?FbI9)K zXGb=*QJs(pk^P0<=a~YQ4Cpu!_-FPUU8g+7vhBITG5&@d-`gk0xQdeOfBH-Dd(Nh~ zjoQd<5NcckcJ~Ai8?bAxwhJT=`tlr*S;vkTZtM!1p{p@kQF1Z%t*=(N7ht3zqqo%@ zj1bYM?2wHuM0rlLfZrp;c5>q@#^sA(#A=#^wFls5P>E4EDx4dZ9qlixyvwaFtiJA- z=X|&4XaY#Xxno>ROUS1;UwC2GPn?kx|F)g7(SqKEB?zidq^>vBtGmyc@CFb8w_)2A z({H)4h(?(1E z*>D;#$ff@96qevs9hSmaEX>2w2$BaG$sENMHqY2|mSE)0n{$pSjA38c*kp1;EX8SC z?D4Mum=5w3`23cSl72c?8w#UrD~l$ycWon%veje+NLM^NV0IoO@8ojCcaq9|I_IP= zUJc(TvmvuyG$NZ9d@oEAI2S)${;EVff@wcJwe7g?>435E;K~vwAVBmhUtjn#ygH5$H#C5 zX2)Pz!Z>=-I*fa2#uaVf=ruvr@s_qK3ek@-#rq?=o@B8bjoLhtAb1rSA&Jn}`@68h zbM_DO$f55JWUd9cA&m_eJcu0X0o+X{R4mG%>^ZRn3qz+J{a#`hJqYPctvKfZ%Xs!q z_9e*f56{xDnu4t&m;I=8pd$ve7E;#}lkLJS4XUCwPK$GVGC8%|cBQoUppF>Nn1=M1 z^l~gFwl+iBu?2#)(@AsE1%(ksEWC_-U>I`B41SXG86F!ZMx4+cL1n7_$~3 zpV>BlOy;mJKN1S8cVV} z1T~OmRl@NmItFQ!RF?VvYJDrKjLUIUjtBBXMphVO{mYLi9O-0s%*P{P4PI(rz>b-y zB~?;hA%E4~)L-+E21cU*yZT00*wque2<0)gy4e+kZ}Gic2XB*6p{tUtgM~kYXSefF z`PcXOyzEUeyak}yC1Nkjixs(!-7TN6<~tWCI$CUzVM7(2<1}dw_BEYhYqpgSIXJ#f zUvrRVv=cipI=I4vN=Za5cm%4yHq};4b(deG8h4h!(o(iBPe%w_@ea@Fvj2O8Ucr`@ z%NWxNdc2Ng1`<2@q%AIyl0Wjkoe*v7B2QT>Z!$5*B50II!g4@Q8&2K8R0uGW$? zi}Of0UX-bgPyZh!GB-tH%CO2DkzXt_wnmI&kreG8JVgQIGt5AriUwithEFLIa2D=yyz zwQRc&PJ!@Y%cR7*9U1tJbqpo;F2ZfNHXe0h@!P{zRPPFixFCh|&K?V|3^YfAPDrb;QFKVJjbNM3e#)2jI2`1z#mcJBj)aIauxRRRFz~_!~f3W5&nE5KxnH z75MvA4B@l+W@B9$mC_I$KX&S5J734Gs|`z#$`8Qsk(@tfw!13XOLs262E%mG(Vew{ zNq^~)({A)~Ob0CT*`0N0x8fXMUZUrYl!Os6wX(JtGF=}(E?BJ~Z_$|NONL6)i_1C<5HE;4gK@2E^ddYw5iSd`v@Le5?!-MuI|2)O{EigJM z4T@r1-s#$_;xWfVAUtM=$KQgvd55m_qssR$VCnU8<%&ErO^K3VQl5X$AQRe@%O<&S zS6cV+)c56Op78B;eWAVY4?3*!x#vs5$x=l^yDIrO14Pa6p1DRNXJ*`Zext?`42ZYf zed4x0180Y!aDSDWAs{m+`NljFlEOcMMq05PiAN zO8sU2Y$$I(V$kVzWxzWXICn~;E<~5*^E~p(Y$E!B1@iuieyX5ICUPn zK*P}#-!bosh7+P5s3&O}9h5G^(4gr?Nj#{oTuA1<9x7P@GlNOq+3x{fUzXUE6r2BNc#pWSVIj7D=d99qqm`NEaAdX*WyaZ_-5&&FLY*7gv zF=L~9ojehgaR@Ft3xT4z;KDylMheCvZE2>IR(Jw)DxVxj!A`CA)whyFcPPhtF@nU% zLZ+iUZr2knfP;zoyuMy{T0!xzXv7b(<9UAFxa`Q(OUlSsh!LF*9j-Vy9(40#OUOVV z9HP+{3d82Pq8CCW^=oJBPS3ex zz3Xs<`zmZ4LUWvu5`P_2P|UI=9Ef_t?Fr`1*E_`RDW}hmP2n_>F|;ol?tM!=3V-7C z+o*3=afte&lfNf>I8rVea`$u^BD+yxUsHeftaKwXc;37E{Sd%*7A`ZE9&W!+OZlDn z!ih?3@kYaOKvP-bFpnFTzX_6go3^z}mYYfscbbObw@iM z@}#IkDkO(Q+Kh;|IKb!Ot@?HMG+ zL{}P&QQgCKIUj2`&~gJEFV$g6G0+u|auyu%V7&%oprJ$VW_BoQnUSDIF$((Mc zR3i|_7-DpwVc*xZyXnz#%!Tb-+|${ETRz@7`x{<<3+d&yN;rfxerWFiYShHnfarF8 zyhr$TPE&32)rk3se3e7xd!i?@HXG5+;W|QebGCdDn1W{1~$ujw@6uXsNb@=4+^!e-Q z`4k3^&HTlvvR?@x?z$-=AetPEsMW;)oE(l?Dk(r&VUwASA?D%idHB4}zhAF{X?^&-rYTei}LO6e~(uL>@0J$5so0~nu4E6pTEZo0t8TJXOHQG!~OR) zSEgzJ7!&af>7h3j8(0HJaUb^o_I47W67S~i-_z@zA*H#I7)F#ZVeaLhv|G>QBRtxl z*dTFtUl_iMsrEhbY=Eie;O9aEl|3HK$XFNdI`RqlIhxj8dm{GCZn(yu&~act+AnxE zCUB3I%w+oD3SMAUI38aC6P9)(Wd_3@QsD{EO2%Ng(;{HD)!J?{Jfpa(IKWBzQ$7Hiu%)DG>C&ilXJA4sUP**Ah^88-?B zPHpr4WykjILAdsVC7va?y#Mlu9W?YhI1-bM7 znOiJ(tjP(@Na^M6tOqNm7HL$~5x&4c$m87Vw{7FxknX*Qycz9Qe$w6a&Vy#~QCaHc zR2Ym-_d4jq)K4 zYiCHXrtNYP(*YV8#9A(?+|)GF0IB;VGPqI_|Dg1Wyc%|0dMnaJ^%4dARQ5ivkI8EW zl+Ai-R?PXV0s`sG$qRBwyHWIqka4aBD}l`KB%jVSL(5G-=3gH?D6dC;>-MB6UWV%6 z!;56)G~eAlVb-ALX1qt)**=>F+}np{GY5#Br%WNlO?OVqu^GY|-zKeQj`K-GOd;$F zE2Y5O24@kX*w2b47jc~P^j=A3F#<&o2q$kZYWudIcm?%zKHsh{ZXV!jor!yzS;Ap& zZnk88Op7N9X8WKyu01>-;6sFzbv_^5cf{GbN^oFf8EX>Or3DnW?6-Ja3rOSHXV5PB zSsk>D{vkjwukc|5v`^Zc4DLUtg}6ot-IVHvF-uQ_XpfM2JrSPN;s4yeV*2f|C9Wa$ zxBMi=yfiyZ`W}&|DeMV`v7oIYai({ap}cc5x?W+Nui{$&In)(%>n8o6R0GpG51L}y z-H#v`d#guUfY~9$L9_+{{-1LOkMO8oTVdQk7b09AXCK`xOBmCv&dwvLGw-}tw&B(M zHa2Z-kMbyW=B?pDQ&LCkM<*`A3Ka7fGnSHv@)M^>x0_zL*4gt)4riW3&K{GSQg9ml zKRMKAEh$>JI(#%B$4xp+i-xj@Q5IkV;xr;RO#dMwZ7B@{h{s>M6mybz8#du*7I%-f z4@5CMsw35NFz=o$e(b4iyo;D|vXwGQ-df|B?5)onD7Txwl-_M>= zqZpqFFUl1hI;&LgG#H!ThV!p^jzDbQI=kcEZW7f(yx%E24$L3^I-cUp+` zZzII|IRRq*)=7vAY;c4AhKu$01=4UU3u^-l>$eTyvkzGUj*C>z8DRNGHoLG&a0D#o zRSU%YDtsW&ZC;+`$c4sG$A-Kiy6TS@@_VP#Q-nnbYJP11G`|fWi60gu&F`nd&@99O zv!yiB_a#wc2PtBj-!(9{k73xyh+|hL2qN>=SwuupCX(g!gs=C8;*I&8MPz=pNtS)u zEa^Ay3QsWOY{WP)qoK;a$3U>Z+924MXCcsfX2#!W^lTBSqNYFA$aXcBXe$vSXLnJ7n%jUFZ7k-k}TD0FA22I?3WjX zCNqTFrH?yykIpD79iWRSC%6 zfpV{9JVq^Sfsq}&b9BEw8>X;8*0)Em(s6&iMz z@2qJyA%y&6eYNv|4pU_8Y|Y#`Y?Plk;%3h69nvzkz4cbgc;^Wj8c?qE+ zgW(Hzh|BO`-6n+*YEPduyJv4z=CJsN%2wnxh@~ezic@{nQZp*9$s82sW;#MQ0!6wG z663tlcT6r7zM=!x*%1yVQJK@)jSF5s1;H1wczSk_&avU`YUqKz-*RD3+!Y(T`)r9> z{HBqI<6MWWpg&8j0~c(=Eon_>zA>nL3t$*u z>ff4=2MtlbV^#%|fOasnE6E!u=FavbAdeUF9LpNN!LUzUcF_ON3XMY#Mp`) znm^p>4*udA93IH!9&;xeQu7Xrsrj{lO3r5e>{&3>SUYDv%VyYfw7x+pwacp{uFIb- zUbBQh(#iQ)tI1)yX*EQRTM##?o|dlrKnSngsfT}YYmz33acTzvyPUfWf!KTL-7jQU zkJ(9K;ZS_vmL%AQM6xuBkZ-z zbG?Wr)o&-^}K!ijT(X8_WW*h>Rj`Mfd#DF|Ws7xR$9Aw;1rMIdhyM8R;!XqLUh zd$(f(SK(IQ64-eZJ!i`g9r*(zd(WBzdUN}jS|bFPm`djYH9(56s$WZKccg}@l^}@^tbu38Wk-=KqPhu3qp|_W$AR^$Dx0bsSTmrQ~yHCQb zp+o-b_I}FzGb&aC`rebKVAA{A3D($K&cpyfnZ*%fK1pdUS|X**dn=fOkBUI+H&2?% zs9~?|-N<(2+G`_jUu?*FZ?D;q+~9S1YA+IS<6e@==|{vmK95QNx|9P0Rv)l?0VJ=EQ}ZoQ(r42?f=v+)YTxfMxqVAEO#8I;QTAvn z#>?m#vq%~V5|3}W9oFrV@*%387|iW4_cHCqyl{r~G+N6$2j>1JivrTwopYev;v{>x zNp7|1!Z4dj?jV$xP?JeL+B9t4kfr+|rfMilmXd-1vh$!RjPIA{ryE}=B>D=Vh%pFh zhY%%@8>#@Y-()gWY!Jj`tQRx|dcYQJ4mw zw7t1{)Qsd&iRGD&IzB`bl?ijIv-6cOPCcr%%;r$KvEdIVn=Gx{g9C#(N7i z2a1s8vAUG{qMY2IgifLbGR~7LO~ip@0-@yH8Qw=>!INyo^U1(ZC5#;4AumOA|Heo- z^BHQF7^GA_Ge@~wRd?-C&OBtfYECOqK23^VEkZXT~}0Wr=uD4o;if z+idodPFCKk_h_g68{OoH;ZdBBa_R%?PEd!*9gJ6G81r4SxKK=i5(ACpZrXV^OHRbg zD+3?|UJFcz2wz})A)6AI>-acc7AZ+OX<>x)K`eqBnG!#1S1;~dezQq>D`T8N+~hjH zm_P8Cymmxf3&}j*qn#BW*lsQ1^%iY6$J~m$U18;xdo3$hnx{O8bSmXS+ZVCPxMLt1 zqu5<)(HSPpL}C3YQBVYhP*GH(%%0QS5cBjRzjsN8D5j!Pcr4c=9%F=GD4C(WOMPZ) z(FvwFkv1Z}4dpT+gb@!p;3nZVWcJPod3FLtVpko4+9aJ!9+TONM-%iZ*YB7RE=JV* zEwQ*c>N!}ZWxe4&g=`fOjjVS7v+xgM#&m=v{!DXo`SG>jy`HhH7; zdHEu&Z)q3hLizx6f%E?)RRS_80P}_3@HDBvitR8({oU=C(cP&x@@{gDUr2eJv8kAe zO@T>Qw~!c)-85Kd`e;%Cw!L?bQg>2H&t5@0yf9W!++>!d|1LD&?+huy{y@Xg1h==& zg=XwA=HSpq7bSFgO&cl%0$~21{`~iU`SWkT{`S{D{?lK6{pAnz;thKJAAkGnFMsIC z26z0iuTW}?2M-iCJZ>bTi&H8PNtJVQQQtK!85~{Hq?d(jnB9Ycf6R^aWy%M?Nr7S}QqoOX?1!>=4?p)%Vj6 zm@rB22kIA2QqX@ShRynJdV$?W9vJ6d%FD#up4Gbaj&QWD4u<2yQ=eIS)`>xI=B(3& z#KGOhc;{&!)E2IJ=1C_|I8NPvV+{}IxQ&@R0t>CAn_Nfq!f9w zU8RG{au`HdoQ-L?5m$Mf2lXod6pXh!jd%h^G|GUg(Rjy3Nr!0S=nrCKc;Z};Dvd5N0E4jpZkF+#Wa5 zlg!;BOdIIfn6S~#jSRv-PsXf~I+xGLbpc}G7+nkopFYzh{d_D-okf3;Z6XYZ#IV{D zwI^Tol9r^zs^kuhRZ#wQx5}icG0zLHyr+ETf~|SuwfLFo5Ez+UFL~Tsb-AKIq?`3+Tg#bB&jNByEFfJ3`D>SUT6R1D zpgw~eMeMJ9W@gpV1YW|vM>$zQG#Cde5`y(4lwUZ!Id5)KHfW5@EbC8NVbM%MeTH@_ zQfW{=GetR?b$(|K943uQ>1@&utYeNZZ)a-jCT~pU-jfp`l}F=-P+ia*APv0(hwR)! zQ?PZsF*}5J7ENk{dLrG6g2uN_lKDwSqP49OZ<}T9kol1q`1y#7>Zh6us;X}f+M-&| zLCfzGqA>$J5ujSJ7)^Q44@g0m>RqnPNQAV}aj0g}vZ6ZgxsItWl#S}5{K3H8! zcf24mZJHFFd38kt*EVTIXnt#l5uZ@XEL=zD+AF5jJrp^grLJMCmtp}qF2bD*eCOAr zltdNhGt}!=58^^gdU^0sGjfB))nLC2WTJWg{~m4oTK8;5;i^nG`?h0IHf%B zSh0V^O~5Z=X8%cZ7;zepG15N5@KVVjnaUlB?Nb)dj5&ejNj;gE0!b>;2{Dus`zPT_ z`oBG|)cKH3JzakN+jF{sZrcaEG5iEdk2(d^Hj8|x8)E%E-h0#>P>jf9Zf-!KJnD!R z)hsAHqMgmT^Q1XU)J+{@Qgt;HrQ^j@s!HSm$2_*K5*h6+Z8l+ud{Lo^t4~P{HJU`F z6T^RsOYT&8gJ_tzLzsa>_E8KD*x}orTu(9X%Cycw#&w7rVO{uG&F~+EM1|SskPs_a z)H$qt#?>JC#IEw0V-lr2gNTH7D?qYQK1EbLNeuSh(yWohi)WUZ4cA%hS*Go-)grDD zh&txlc4&v~U=N`X!Kyp!$Z-bM`+9PJvkjjhbCO9-@i9homi5KQNA%s&%pu}#(m0~3 z&GcImFufge2$5fgkNpsf$i^Q7+Qd+3@9nE$!pdQ7ImWsK$sB&r9Lp#bKSrp9uw~gC zX&c79b9sl?bCBFdYa7!#x&s4NSlO<&ymyWA*n83(N;l%H8Mm{w_9!_r@8?!$3X=rw zzY#_uZQP_S!uXSrs0cWQvVCA;q#E*54jWIJ-#6|w@ceu_Zpz1EY58F)-fo4Ik&&@e&PC*Vlfl^Eh{ww_cv zBRE#H&d82{lbuudLi$L@d?}W1I&*Upj20)z;0!5WDt}7XyYh3cIu^>i!|ur+`<7h# zR66S3aKezgw~dQHg|~0?hQD<1P3;T+>LztcKq?2+gTm(*4UZ{OdR>ACMx%x8CEC#@ z@8ei}dLOBt6FJj)%mhFRmPia93(y=uFh{pj2-{LgRPWgBq40%I2(vW4v~;~qHUp2Y zuwJR4NytC~%`wQyNdY^>5VBRcmr6f}8)rFrX1bSz7Y#a^f^O&p2PXm7zo_-143AFS z;RD2zFj(mQMj0~SurCC2@ZMg0pn@m8EVzjMpfoTIjUfMs7bf>h2xwEZw85)1Zro-8 z9=DR8clx|jnu~4?Mwlc`smtTeCbfv~8yTRuUBA-Y%t{J}>XCZ0_}F$2u4q#*e50kU zKw+vER7v|%E}=45G4iytYYM)z%yPlPBzH4L@8^bDt?kk3C^h8MTr`Sx=t#*@d8$$+JZ#fdW3WeBOd zaKpaML(Q2UnJGyXzRTAXKLTl&dda=rc7UtAv5 zg;Co$gurB#mWU_SZO-Xy-~oz$XbSE0bz?0%7 zeo4~;u1s8*T_lf@(Ht*o$!TuD!&7#xBjr=t1%2SyO%@)rL8P+-*E3*RPzx9Jl1z;% z@bP51XEco7ZO^#$!h*adUv$#x$fw2IT9(pU&B6sOpe)p?5)jGxu?(%Hzu+@gK@PnZ%=m`D z4+gUMCYUHWwd_9S1q8<^Z@w=7!ilXOLpz&vJa7|(=nS*=m~q8qA4(6 zg>q$ZiI8IYd$o9F7Y5RdnSYC^IeiFjeuV?E=XJ2$+Oaqco}%qg zyo)trD$`eIbg8xXaoGZC%9p_KQ=a^$YPgJNd8j_JxgX}?G^APt(Vd`Eu~08G27f@< zb1-^VWH~Q1*EjdWh)3`+M4)>QnmI0{@AI&`6n2m?`e`E?Fe-;07b7}RJ< zV!e#lWsOxM!+@uBjaGS7|Hm>Z>t}HJTX5T*$bDBMs9FVYen{nNEZU25+i7MmnuCk6 zZvjom)vy3{NK|Bjd1G5-ZgWJ;aZ7-0%}yj~JEd%l>4AY7xTS2A3)qD|iDZ!Cex#l9&;Q``RnP&o?XZz#`q zJ1uIvt#L;J81Sj9g@W%|0X&G^J@OAAt1X)J zh}>WVskuvrr5yd+!B}VOwVxOh9|5FtIB{UtFw$>XVHK+N14!OSjMnog`eygc&>Jth zB?8fU9%~}QS7yge=^LXwQ|8k89UPU-xnC>P)+q@9m70~VH1b+cZ%z4$3@(_`H|F@u zZb0pJvXgLmSOSlE9Fu`zZNcCNq?)R(+tE3#iyvGkKmx+b?^wY= zDhnp#!rBZiet{SlI~3z9(QfiPz9M7`48U2WgSm>YX?|OgdzVw4%C) z)s0YQ9f26ZHJee?m%OnfU~x0bFZHGlZb@XJ_B__aGpJ)34-P|_(u129V3a9u*x+qP zK6$xqC(1)~7ML_agrb8u+3D!5($qGjT5Q;;5z0C)fIbb`P(Js}kxFx)ECi((p!ghL z1C-d_sMQ8QZHX}aqp@eCq^T&Gu0a!)$rLu^wF*UBf| z6|{Vs2sa6kWcDeGRO+jis22vr%&3>T;wc&(wZG8w5fOsYpiXN=wPrCfwJvQcA1O zDIKEw(i9nOHq%jZc50xvisQz^^XB+~~(Ez2+HtnZjsVNW%qz z3~!Us>Il@Lo(qdC_Z9`60Ov&yEx2->Co@lrXFm_qfU};EEJnq-Rer9_4LCmk3_6Yz zE=*iVGvarIlK?)_V2y%j8n8&y^J1RuN~VgtWd2*_vZ#bjrUyG4&w#_2BRfpclawcE za8{kUh1}GVD{$bAMYBDfzBzvS_}q%6e&l4Jw%9ot3^WSvWVdl4fPVsu=%g*1kXy*a z9Lu4%?YH{kgtmO*?F)ONOC`e+ZOMR?8D%180vk+1mHa78qs2Lm8o9+pV_)v8uzMS2 zQiIcWYrcEYl%lLb#~7FK{f4)LNK#ip<-s%Zjk~Vg2BCbH`2gGsX|d@yZF7RXD= z%UWnk)1-Jpm1rFASn;dTa(716;q9rC7DC27`ENmEf4=_5TZltyzfpCZ;!Dh(qt+tDZ$JgYv!Sz>fdD8yXDId@pI z=A6;_=^}_a8KUm%E%|l|)CwQQwFko*WbQy@gUlS&fkPA{ZwES<@P#3^l1h8SOh-ub zMT_b{Ujxl8Ue?g6h-)k&xZ*x#LsJ@@HP9-*$HceGHH+d?VQ3~tq2pW3?Kn5CY0y~< zlEQz%g6iH<0^yppi?6aF1GBYDwUzvQ3y&6?qY5PmizSTRR^uDI0AklE+M+)L&~0_S z@htTt%PM4D5xNRUzoVtFXJT zKI6MShqc~Um0(Hi4goxB?_=dt<%Tv##*&sC3ky*f52Tga+^W)$%dXX;4o!D*RZ|M4 zmQkU%@>*2_bK8V1#Nrr7&m%mjaxT`S__)M39M28QU#Xcunbi;FmdA!r$Clz#N?b!+ z4|&aMt2G5KcT~iTpVS@^fwD@yXDzc2Pn{6re1wPSgC^Bv^>o#Y6+_FR;h1h%c3ncW z1@P?Y+&KW7LqeVL@2fZ;0ig9Sm@h$L{gYBh_E|ut8`IYH>aS4{c6k5kzMA4sJl9+ftTHeIKAwF!GdY zonmo>cAxMq7Qu5H!EGEA!gfT9b7SlM+LO=fM zwtls*qKb0K4#n3e-v!fgTrf=}DPOwq4+iZTfxLUXsAD0!6W@blPWA-2*0|p}(z~Hg z0jBPL1!ReW=csSP-jD~PAlfG1R6WvCpB08Y6<#dr9AzhNzn@3)>M zUyB)x2vlumSPianDgrp`H>^1VsL!5IC3@3mBfeG+4YW#2R=P)!^*x5~+2*za)lzv? znmQTqwL*8HHAhB3XZ?jmd~>e~8*HjvfMty&n8@F~cbB~?;;9e&0M7Uei#!7wdX2_b zV2L)3q!vlY8i?H1;7kBGJ*8{VeJ_`^FP=~*J-fXzfwO4t9pSZ+9Tur;j(-i03Pney z-0&H;I}2vkh`{KK4k<|>J8ER-?Nf1B3YHyiAd96{Ddf>lw~TIyCI$^mUfjyN(Bqy? z@N`89r}HtA=0Slc?UTaGokz`~bX%BgC|T4%J%c5fRWD&1F6`gql>~=54J2XEk0El! zEb}djNr!E75c9(P6d*~h9VX>8i;VQ}8%3oddXnciKiw z$~hb=M=o62$`Z%urx+h2e|53#Ud`LWR%~AhpGwb?=gSl3@VJ>lnnZ(GNuwhE5D`c5 zJRtedwl@4lS~brAdWDHxhX<2k5Q*yibqs7`2iO;)(5SZvVvDN%K>G^gL&~@0M@+$D zBp5!@QTETkGLj-+DA2ku_9RGeEXD1P49bFu;3jmRh~SH8f)kd%aL37tAO&MLQVBB5 zO43dd95a)!XRmmN@5sxZFge)tGvcZxF`nSojj?H-b!50@1*Q=~Ug!!?fnpyZLTg{y zd%_eb1~xe&XwF$$BZmEyGSAA!3H0Tc^Pge@O_77&;)snlWf<{HxJ?=?KN!yTrkRMW z2|2GUx+1~BJyL|qTku7h8gjcmxJXYWVZ3P>c0zdL9LX2235OxM`_&%JL1WoZ(kr}= zHZWp-;W=%ORndlGh8PjrVh4v$_IUQ`(o3-AP=5{(9pu@gF;LzJ)`v@d^V26(_)!h9T$PS{I8I6zfkKa6Ls%sExF(l)OW`+ zE|hcN(=#-=6{$r<$ez(yCq5Ns`b^9njSOJl`*)?(w=AI%vvph$QgIc#%(tSgzTc6 z9HdKo%upeyMom;a%+^Dc(}{Je@#P22$teRDX8?*GivF++fd4dl+EP}>DWRo0eCri%Cs1# zVe!SLEK>SN2xn~5@R*T>S_AMrY`O_yH0^ze;hc719Ai9Zdmk;+{dHb!d|#xi`r&D4 z)aZq97bvf^-sS(yONCnC8M*{O#}X-8bZ?Q)SDtlYcF3vgs`H`$JkvcqRBWHk1K9VYMa?vsHsx|_Ra8*3N`{sG|}O6*i(UfhA0=< z&H~+O(ntqiR_;bnGu?0b8rSP9)zmPjq=}g1~#Pm5W6eI z#Gn)H0HxO^2v==DDf>QDFxC_$`2roZBxJBQ%N&D5p-4fKRv|PFh5YVH@3D5Fa0m&c z(PEf;VI2;BVrer*z|k+pn}Dp>iAg+2Bv;?qx)95jG-P?$x+`?Ya9}Fjjh^(V&~&d= z%lT*Eyo8A59fk+tW%LVWwODA8cXtkaDJ~_|alf%M>kZiOuD?cf+vn&*2C(86d4jmB zGZr=z5W+zxjH7jL(hK)D!>nj1z&y7HnzVtJZU1uojjhrW>qXT4@#Zt?g&|0f8?9U) z6g5i+*C3tT#-zO~=pMAcKBqx59nG!*4lUFggjD6uAf(*!OeT|5FIl@729?&rZ?qK3 zk8?v5U$p~U7LF~{8i2Pc0}cMM_nvpzh0+lvu#oT*6|?LftRX-KzG~gj0XVcyYXD+0 z9COfGXk@~v$Rzzk_7!1`06E?16D>FTFAP11w{#C>bZnj00Ccn5W)pI4A6*j6$J>pX zy#$apz07%rEl&x!4TxxOnb^}0j9QKy&Y#X9kp*GO1jRyf7-;c5-uE*$#+jnED|T6u z(26p53wD=@o&3N$dq~ar4J&3%SQJ~tIVY@y;tvUr?$`#95yu{hlCh-u2zv`fNj@nL ztnC+dV>0$@iHKq}PqC2h=bU?Q{(q7P2T<656=6QU?lPgIUd$ij7Bc1et3;HcYYqpk zi1zT+g!%ZWvZR|fH6n7mEA`mMETzNc7NcBqBT<`7b5jM za|()1#nJH<%#%j5RIiW~p+Zike2Nqx^SnkN@`8#^*K|92cuK!uUpYs-wL)n;j}^?K z%W;#kWK&S9|i_M7eN3|*k;U8W7|ZX0yXFWLi8y6JN8U1 zlnvjyD?4T%CfIeyFS?Gv8(O6`@Ln@vGcv41gfN^j zb*_&zY?CMvS_XAVX($tCYT3-D)aDiqt2*B^S1tD26N-S$BbC zW~v0-Fc2<_%r8li&+v`fW<0R_9aD*zUD$D!Djyk(gI_@=ja0&B=>$>qUY#l|7g@urnFiNi%Z&aKk42BysWC1t|C z$B@hxN<&(OuQo85-QBFvg(MY*D*xl%xOWY_^pGjWvFeUoYR`b=5V*x~g(% z2y?;pmI$*)>^I=y)U_(*GjLw-NXt4dVH3S1BTMcr${^SbRUWeb`tU%E0tu#Y>Hpkj z^ghDIE}qbqgfZD|j8-OhBc(`T&&k|08lVjCx!(F*#pXU=Ls+Jf$d7c%18p^fj9tNw zkX#;pG?R{_x|9CEn~tm4mdPq6^T_fnvAu|j&e&e04@tA(E3>}L(*?%`bCR;;d_MV# zlK#x@`mBKlu@ih_HxLStn1E>hWOu=OJh)_5_^}~sX1w)T1C2b)F*NHAz%#B}@o%&x zk*`?)z)V{HhhKi?CVMQoI<}d2R){{Q1c#zg*-21l;hsAN@WPG(8c&XWMo67ud6F7Q zVo4az(Bn@L|7(6E2L9#7tz;XA_*>qMWyVxvUJ~(1z zB*Op#0~6;j+}0$6ATtvdIdNpSXU=XMtz)8mSeV%at7YUSIkDs{k$XR%$_>0>>_Uf8Xdtj-T+^W zLX%{S+%k@0)e=@QuZ7nv5q%plRN-Za47Ho?6MI?0jK^|m8An(eoiD+KcN&6SQ|037 zt_}=?e43*1!*q13vbM7kF_Zdw03deHo?6s zWvp!5Rl5x{VTxy1CM1f5MQ}SZt){C|lvxRs1Fl^kwrqJWneaB5nx8V|=HN9u=bP4) z7r6nPS6B{Nf!9*z!&6w|8li5BL=X^IBb9E2zL83N&?16_rSdso2=lP*EK!lwRoDm$ zjh_MHUT=Csf^LyV7nMSg znbTVz)qSdbV9Jz<^+nh!CpAYXDp^v8a5HDoLAStGsW5`_4IF zTmkKlV1R|=`>g$gcq?6>ag8IOt^TNuwD;6WRefSCQ-I*eqwxbS%3H&6jxho1>WWtf zT@}|_V9Hl3i=(_c?3OiN4xybHJ*jRk*=c@4g)ynu<4pA+k9x?H*JuaU|)gpA4>cvG1HbZg0RAl1<()RF$2 z>v5!00Aii0atO4y?1P&SdTzusMvb((h@FE$z=u7Tn2WRNhh-iT&~fZToIq~ zR$<_lUQAJNsRrKCkby2Ao=U(nA&U3wG$hq0OST@K)s(NQ)53kKTwpqBPThChzdC(P zgm8^y;-JlB2~e9Qoxe|+4^Y)RY{#Zf{S#eZ6=~j?+rBHlcML4g!!=uPL=!bQhU~jOUG82SJy1anCoz zz|IY273(_q2omMuuDC+F1dN)iR;_&C{?MFgPGPF5Jc?wayV(#{forYk{usmlbE z{+3GCoX*yjrI+)_1y344_=~iLc~jR3$O&vE$oViQ2))$=ryH%uyc=7hCFrEY{8(jL zW9+V~$Jri1HdQfqdr7I4%-#yAYInITxJEFgT=f{6Iqh_Hz0ABx8?V&i2g+Qn(pe#0 zg-_59X>TDXmr9o9b3%E*I16UT~-zwlt%_B(K0V7PP)y z%n;ZZmDksh$>p|*pHFOPN}Rl~it&E*op5SvB9w+QA78j`6|RM+HPW}oaXFgf;1h6Y z6~|05f=T#fyUovy8v#*MRRPP}r6dr#>!WY|zi0r_fXmOBI?3@PowLrOQ%w}Ms;GuC zA7E#Zh}FwLO{^cf$t)@XxX}FFkxTX?vqrjQ74@!*Y!za)&XHg}S1LR0)5VjT+TgY6s9)nL=oY4@+$dBx zJADu|XyAQfOj8T*$fnID==QVO&66pCSXG=_G^!1hRs8GVYZeJYwl=j)Mk3)-$232J zH#Hi81CBz6)Y&+uC{6p^NLK|e8&btv=&q6K$jo)iW%e{T9Osnh)&iPZ+_Z06(gq;5 z3#EEROWV|je|e#%+#wl3G@(16czYaOq4{>~O3O9E(&w9+fdOxUdqP;1p-;A2B<^aw z>Fkmd?!XOVCsw`Tq1^j4khl07>HXpTN+M5EoDAFHN!*( zRs|CQyK@_N0z&%4*QeiS2;B=8mVaZU`4H83HXug#kut4qXblh-=}&CsDc5L-G9RFt zC6pzBQ$Zvo{LmMD6~3vd2t*~y)VN*3TzCYOwvlm2Xw<`aY0`x@16<@AaV>D>d>^B1 z0AQKQMi?ON!7}+vVgrkIAdU5oHK+;1>se~7eDohMt+&x~G~AEVJP!Sb<}pE=nCBp& z3{$MN%qKQB#feiUXf0fU1~qmK%H+Dy922F#T6~b25lCX}wa5--jNgo$R{L;=vH^(I zMvM;Z4qNbnvb!+SYo-;2pMlnW4h+=(rL-tmbnr{x*<*l~fkTw}0B!su0#pGIu1+s<4Y|tYFwo-b z5>`SgFY0olo!Kd;DgtUkGjiAQClTVMOmJ|Qv~7YK6Cws$ESn%CG10W)bdZi1)FQJ+ z`pM5=RPoUR(p)js5mFLy$$&8-V8X#`G!6IPki^3vlr_N#W#`#%2eeff4@2BJ)1u?# zBnR94%O~bH-EbT+HSlzPVwWx-9EybWw2WBGN4m~((CWVB-e=&Zv}l!E3d+G`g_zsr zI~LM4dP^?JY{>MSGRlhy(TmimRH`0Jr%|JN0@;0^w2FWEgf4otw@`YL7j+4Xyb5{% zIpS#n>g;Y@_=YYQU4ND6C9(}Xdq1)n*g0;d3>hgconWBJ&2JZi8q$1-opn<4&hPq= zy^2BFe2it{7iGa4Mpf!YlZHhn1}$x8_^8Y04oLGM>Pk!u&?Kw6Sn;(gsLyITY&4>3 z>K_Yfy1bK$*nx9jRf%%Z`ez~1@_ORf&;_iDG+m-Q6f>=gp`*T`*L|K|#$}mBsV7M? z&j7Rq$bG_GA=P!-xbhnZ%Luaz?G+d4Q@7!lt(+O8t-{#&6?)1UO_Gy3HMRPk!n{vx zZ>|A3B5E9qF~WR!Wdd8S;KCfw!`=|`HiGyWxG61aZnwy=aS>2^GbPP3I}WgMff}!g zpuQaPx&Nq{iH1Y9>Y#9MxEL*J?kDBS+?KS8fvsz?vsC&D)*=-4M07l>=C8N z3?fTcRyuZ8@tbxQNe%s4b<9hl$c+BPqmy!7K1M(3B%YQmmvg-Z;yB$VqA@fuY1Gad zO*u_3E^Hrzvv!)f&`JN^h_9i|N7z{JAjiI*`G3YL(W&lg2XRJI^%6$YfC&zxDkH@6x3@ zwhVL_)NNnnwpu(`bo-c9`7-WXIOn-_7ltUS zDj!%GdY0^EGx?1Q@Yag{#7|%f;f%i2^UBgz(e15b!@6S^fzdbHyt4BqlBNe(>jGsn ze98)A=;w^CG%e2L?m+N?D#9wpWx9$5-CH3VOW|ePB?}!Oesm-P%v4R6%2M=x>+a^{nb>Hej7=O#t$#|U0J>Awjsims-^%~Y)Jy+FW>rthq zlF=#L2WFa$r~0e9W%(Lxl$T8K&Gw1k2(vxj2V7NYxv`Bt%c)({ay~`ZdPdxg^+hSH z*T%*=1VfZn46GdjGx{ufHfB@+?qJQm53FYDwY?6d+94RB$_1w8v4wldQK6^-XPx=> zpFx{Zmv*E^E`K(Y$>JcXo;YnrGfz=7HDrukKxb!$G>pr(_ncI^_f@n?sYbM9|G6Tp z;$5ao!z-iRaN|;J-pqPggpRpu6G}yoElYXPv!%+1rUtuFX`BuNJq2vplpeZ0OsPyW zf+&epLzo9pnt*Sk-SQf#F=_E+?@9NRSaK=fF`cbzU?xY=nkDQPL)HMWGFmII&ia{H z3?`rQRQ15GK2;ttgs==QOVPpm(zqKRwafRL&Appp&ww6bN-I3${ojrkrcMAgw(ObB zZZjlpQC-RvBiLb`1=k}CSuNu_2hiy=gA%yt5*p3P8r61JJ|^e%B=;!B4>)s}ZG;({ zB~Cc&iBw^pKJMv$lY&fkjn<%hduFBK-40#KmKqUFJ-Q4_byK>IUEj_oVl%|yBWhzOar~;y5(Q?0SvsLAs(frE3aC~{M+_IunYfaxbxv_>fa&pU8Jvo+j`-jzviwRNX!Ni& zZqKKa?|ZqN$`hQ22=jTTassJD)(lI-YFZ2P>7sId@op@c;!}-c}QP^{I zAJ%ZMPngc)-v>@TT_qqbO(OrAWm>ZZr!oiU9nw@4#>nYlsyt4q_=Ilf%qXNQG!v$| ze7H!%%;gQtcr}i^7z?|g+i8h$qRNQj<79*D4cK@IdKwxOTo)7qfbmuI$ApN zX}p9Xx+?9`fYZa!=mM2?pRQASwMN-z;5^l7J%u5{Tyz)dBu+<5q86#*i#Gh|%U5Xa zeBx3}b(N=D^&>8~Te2nULPpS{5Sx_0CcDb+Gf>YNHFigs=qm3>#wCt5eTlbWDIT=ps z{?j&UPtQ+_tF*-EWX&878WHW2rf-+wZ@cW{jDBLrNn49MrNU7d%@nn;P-_5A-8?WC z>k4W5Zs1d_4j&@36Bs*781hLhJL}PEp_Tw-OwP>tu7|EE!qojvbfOPWrh9W~@BG4E zN#W9Fkru&oBWA{~CehqdcBLsd$w9jQFha}q8O($N~LM+|c{@6T|a9bpc_I zF3v8dnvi2+u5NSZCy}*j7c|s`_D9SYAh){(T=XUAj_&*jn|lMnxC}#dRdU&2(*x2@ zT%?cYtG>aWEbXruH`V^g3~t+{s{)rTj>0)T9*s7mY1<+0+nl&`OHrfCkC`%D?o-W= zfVYkQLPk?bvl(7SKOG;QYJ8E0yj*mTjK?C6h$PK~S+;|&BFsm(HC3S*b)KKA$EYm} z!^1o0NH<2AnrwDJnU7Bm5hD~5S!D*PEoxvP%5I8%BZT?zRC6PiDTR?Ru(x4qtLkgz zGW@aEr!BJ3kRi`q+a=6}r)P+9jwi*b$EmII*cr>_6$`-Ktt}T*ye@A7E@VC41YI`D z&f5etOsoNy!3;RNUQ+`u)AUQGT`e(LI9q2psC$eR%1G31gUqmid=9EEaSUQehl6TH z7T0MFz^Oh*+>k2`>lk(_zwpYuv2HsSUqaDI@r^43c%%^fW-1Uqz zY}FXH#XP)I*i7jc&h4sNEA9zQq``=jm;RB3Fx_iXN&|cW)%`4)b(8>B%e01na~+OA zc)QXB{6PYaz{y4#t@*E<^7N@E<=~bh5sju_IB65&)ig9op~YsIYJi_u)B_m76SmKoPnZun#UZF z=0j97+&IRc$zxZot)*nDme0=+PK{zPQ`|^mWy1;;%*jP6i<0&M-Kl%M-!JH^xc~IP zuvM;KsA4`$vs>?Bj5L>nx?4YS@YF(0=GJYE{TGFFpHm|kPD6zG@MN4AnK1cz<$`z6 zm62h|WBPsvP7Pq7a(93*7aqv4Ruepl`-J0x7q;mY%iy^+{#HD9C{r^(pv=do#+<#l zuavj(PXL^nzrcA?2C!+$)ZmtjbX)WxqE!+HQB3EgPA*V`vlJ(gEaTzS2nM-1)TK;~ z3>)I18gz!{O#upGB{Hh>PIb{KEYzAqVrm2fIsY<)t&oQ8xlJ=0=%aShgU+~4k-S+m zT5S~vUsK~3_9)}d1#bKq4~Ks@QTcp27Z-`Q%7s!XLnbO91N4HLsn%%;0}%=3nFf;i zW|`Ii^ad~#2F}n{=~2VN@Ej!xPi_R{IcicJ+a#6G zNu<80D@H}HF}De?IvcS9IY`_9Oi{{d0+@`}&PI(rcEXB$TeIJ}_9LbZbGjY9TFle9nTBW^z^JCe2`hij z0vE+SC9FG?8P~@LsOQxIFyCbP2_J*|_6`%Rr0$Ydd{@tY3$mbHO}zXxivCBuL?*&J zXGbNcd$f@O%X8hmK0E=V4i~(rjM)U$tW|jHw_5dm8yV-N+apfJterBhD63>G-VZ8) zkc|7OM84_QCN>WS`?}b$j8i>^SefKHEMJIIgW#kkLB+?`AlDg!m)ztQ;K)M>?#EQ3 zj=X*1Qn8MXpl&WzSo%I)6lRsY%y|G^$vVAI#SvV!M74l^fQ}0|o-(bNr_y1HFr8Ct z&x@9M*nnGV4o5oYod`Cv0dCYe)B8VQ{*rq)sO0J@mw_@%0jUXd& zHxiKKj%)tq=geegNV3eCZ9|m#09DqWyBfW$_L{s5m5g&n+X!I;@JeX|$9uW~FI7*a zcB8$b^cnxg?-B%gQAHQ~lnnq>!}*w~ml$ZuO4<$h8Ni9V1QFo~X#)sVff02j**R3x z00}9qiDpoNJZG=z;wMF$tvd4|>dAZ*k>>1$ng+<;S)*mfuM>pt>r=-5*+%aXpm4Gm z@jai)Alxk4ipdoN&GG9ptS8KEe9+j_CPLsX@QAjiQJ8FQf*{$!0JabrB zU!&->@`e`&ba0jI|DrIB20=3udri6ZLM9EG1j^VDbMFbM%D zP|SY*NW1Q)FD~KzRGOv1rYHN|rBy=QclzcM)3+A^#2-7BOtbMuNvj}ctsb+$vZc&u zKcblO8oTy(mNo%2a?0|mJ;MByDUazqe$QZ(t^siBY9w{1nSt*YrKwjcA*A(1hk+jf zyo}#8hycfE8vv;;xH1+b)m!Q@ex0@zpFwnQ8&pC%LYWVclVzJeNbPVw{`5WPb`yRE z5GEe)LTikgE6Tg14Iosv%qeTk2=yK8MHPvdSyMKenLnsVt8e%ZU{pg0w;7T|zR&L~ z#j0$^SLYb~jEmzp4#G~$ZWbYxueQ7^6zQ@iMaN~7yR zczH}8{nGMdbd!};ItIIc4q%zo_n`hPF1_h(GbWv-i_Gpi30J>9>AA7t7}+%kOY5Eu zo@z`4)Fv^}-F~Hy&@+$3wmpDWiKv^Ku*Rrqaa2gtjiq?CVPb2K>ON4+TTCatZsHWy zs^;P+1~(n)9Vs=wgqbH;NTau^7+F}%RD()W;Yz+*h^mnn?LDKcHw(1}pqHYknAoKZ zr(o-!M(L}MPj`sRmq(gaT7vI7RnKM`#BGG>_IHiH)Y*f&i(c**V7lKe+JV?G=#ZiA zg|e2WyWb97m1Oq7sab&71nGz{-3#MuUu#ghC(XpsOxws^%6x!&ARzgz1kiM!TyzGK zl$|={hbS8WsM@1S5qvsI%WOn3h3d_hC1J|jm0aVofL4wKCfznkQIn>+)4IK!f~c!D zw}gXI;V2aeC;lfFPU!{IiOGBha{T7O0cm;$AdBX6QO_;RH?t|YIFsy8#`>aiS*m;H zOtl_mgh8dD0Od1eB}R0pYUC^zWo6}lq6ITPl4qt>BHATPx6f{l_bgS)NzyI2AIX5J zmT1WayvdD?i4#H(=A)P;D|a;qkPc)6vZ+QhZt(0Ht%2vZ1F|-@?l+%{J@p_!uO~v- zze8)Z2HyCH}6@U(r*X+E35f^Y^jn;r0A2^V~;d_%NBW3U;d!FEx5rxtdbU-xA zw1~}3HZvI(886&`bk6q5ux8K$&E04iaO0LvBtq_XUfy&VBLwq!HF~9W8}uv^1N5nK@-{ z-sf%+Ff(X?vWj<^Fm;&giB>7KZH8jqo+(E0wMRtx{?u_kM41mz4MNTF83ULoW7m{vj9dX6V4nKG2G6e18gO$L1`Lo5oSJ($ zQ0$^-BEs!_CYS|UgKh4XfEm>%g-eMtH5(9zcpy}5c3G_VBs-2=zMi;xuWM@I`@L3i zuLx9Hg_J)R`k;bV`tjT~vjHg%cLj5Fk=8Kq<#n^I0Me_H%)hjh;xGC9$luYxHnH3acvVY^_ag zS*9R&yGS*_PwY)v?l|^J1y9Xc%!Fy@fjE~BPWepPQK%MZ2{g%$9-7jXqo94cjjrPJ z-P#!#4dX84kmxD`-?@1~pXIc7s})*;Zth~h9$^&1W|y5>s>aJ}^@<5sq@l*Wu&jqJT8Dc(pkYP zgB$ng^1SZfkhQ^}*wD_1xea}7owqtkS`hkF&amMoRMqN9N~NmZzpmWNyFXFEFW3avrs&Mmg+ zbl&ux8+z(Ff%G>W;2phu@OtF}9F3ck*`t$%gh>}^7bdQOU^uA`HP~d_LgZR=)aQCg zAa-_RvUHAxp+#E5K5o8Fp;JTqQkch-5m2c#u<_g_T7zwTenQwX7gg7BPj0L(OnKm; zj-d0GXbn7feuA|)%~(Ucy<{z_0v_%^wT^mgb?U+#4x03wW~FM7pEwNE**oINuVWwg z$U;?FRY=nXV%Ns%>;aT>Q|hzC@sGQ>S*A7cJa4vUAr0wj%Jif_Vu6i_w)k{uTq-Rz zm1?Zf5_FW^&*+veS!#eGm0P}U(G{Si1=BWe)~LppmGG3)fZ;H8vhUGWDp_enFo01S z8pkr;bj0Xt-%hWB&%kjg&v4Hp%4eM(k(e5!GhptCL4d=D5q;+7XCs)OVH+Qw5Y);L zWdi`!oWyLj=xLGCiD3~y_c}x6G3dhgjWi|$+_+^ze{%VA#H7}x@2?c2))OPS)Ub+$ zGMi|^EbCFGZ#aY*cs>jD3`dE)#KS?~aR@85M!iV)(HV&9_DP{lk3*C;=mYvi-#$s* z7#PC#pzr{zn}%B3yuhzLTN$!D2a%~_To1-M6R%2^nZMAil~nKbDgPURr>;m{qLXKC zETy}s--DaG(!lVUaslt2=;H9+rWjtw>`#5gZD)0PF;k}58x!eRu~^5!-0x0Dl)eZ~m2ktp4m@?kJ5SQ7*JuqoPi@xh z>ky_d@v{?~EM^N&U(V0nYMMn_f^Y631NL+2t&j=RgA8BqkuufLe=ql+$TJ+9RjToQ zWPp;lbM~LrE`+wW&KMhIrH96qJADoRGGQv+pnHf=kC<{N%}T9-ICq)BOmbATsa`0T zA?Jt|(ex1|D8)^me8XGKj+B&HwA#Kt-(_^uv5v7!>{C`6+Rz8F)}S38>W)4s#Q8(; z=;%e%Y(1ZNa?~51CQd4Hg!bR zdK9|JZfdo3((QOjHVrsTy36k6l5#C(+G1F#H2^(rT62+x2^3d7&e-3DHr-H}#LGba z8An6ulbo8hw@bAIqB}XEIxsqf>899BogLFRgv@fU>*QRv%Txo*ih0KGl^z3*(N-gD zDN}O}uk?c&Fluyn_j9_u(XP`PfOL_cIWfAVsSfqe7Z%q5#3wEo_Jd4QL>0vIU3aKI zGnHe_sV{voW)OBMVcfZc}um!~YG%Yw+#ooFwLl`O?VfCMs+0alKM z9zmH&)3YLIlrnT8>OqgU#4SB5BCOOJDW$CF7^2;VJ<9aN4?2erS*B{%W18-4W=qC} zT7!^K=N!T^izSn$=O*He4TUf$OlSI4oTZna)2!4Qgw%viAygBMGG$yn*~SVA!XZtg zrXg<6Q4<(>PPPNSoL<89vAG;Cou#>MWEWr06~t>8s@~EA5jTjlQp7kTr&w*iDP&L9&d<(2+$EdNsg~ca83_La=R+x`ZO+?&X zr8V$8O?t>b0ipzy+hFL_0eD)@<8pLXX$d~;qmOrBq)g_j;tR(g>6u^S>*$zj1NN7x z#+RQnEX0mQHz09Yx}0I*r7H2|5^F~h+gWt?9bALZBh2-OD6 zE3Z!pZ8C)Shto7ah8$*FiI*QU$3O_4!q*a}W(cwYF~bMoSxYAHuUVxv{F@sIVaDBY zb_r$1h#U;D8Dli^PYohO3eZz)@JVoMq7=yZ6VY=p4ii20n*$;XmX=TJPxO~*2|x+7 z90NS|357K6%E?&Vp&j@xGXYcZzg?&`2lJ9p}E^NMxpRo%_qQ2H)HW z2s05dvFa0iy;Umn2N}EbUZg^=b2A_aYL>_vH;=>0ON}fs86qkKTNt_}FLr!5wF6D~ zDhf2KB-6>m@Imf;uE~bpX(2InLYSCsM505QAe!_`>*TiB#+GOaI`I!!tF#2(+z<#F|EjcC#)hJMov#F7D0Uj@l|sQy8334i z$22QcqsunJl<~<$9B1!Y@1aAO8l*?YWn|DXsq;Gps-zjY;F;VhHEu92(i(Vk;~#p2 znIeQc*EL5D1}QA0CWCB5in%q5v<99#{K0Zh7g=P&)DS(h4W#lLbdg#LlIiNQGa>N-`5aiLHSlEq-h|($OAJ$t%oGPQfO`ZTMHP2$ z<2_yv?tMfdP=oiv8m)oHdb(#~R4X54YtZv@@I8ZD7cqQ{O!UD=#^ zyc>POL^ySEJZ&-??saTxe~oH%pSTNmcM`RA7xeXrbWum&Yq-2<49Y5($fwl2 z>sT!MVp42P)h_o!S2b0P z9)-43o}TU{LOvm!a%{hfG+(>)mWj^n7bYv*Y0!Q{3oqi|-0+Hv?go=K--W75x=PCo zUWz3~PQIO0DwFl7VqA1t2a24-p|U#l{I)Dwa%|D^_(G{MR$dcHYK_i;RjPMiddQq~ zVl5n>eAZvkEuvzeoirkvl7Y?}{v9Xb$n-^h5ZG)uGw+}!L6Gt2B2^?{z7#&rT; zFm=z*WRRQAp`xwUfOBV8SkCEDX55$siS4w?M7aTYdL&+diPnH~?`~9n0&dXOZ8t>^ z^gOrtk`9e!U8hy1ZfLu+LTk{?O|IZ#9}Qj!{)-_j=T&5$ZgV`6&+9GGouD+=10P(A zpcVKUaFe4e)T}om4-uLr%inbU1)>`~H999I$h=cGpq>Cs9dr2j6tmb_!n772 z%2W0hNDY!;<@(LM>nXKYjbO)(w$jhEle}VjCf&Cm*g$! zPeZeir?h>o#Im)X*{R!Pfc^s2&^~bs7>?$Mq;U(dKi;%#IA5jZb}TtL>ro7Cz@Y&) zur^D8xfe2OmSNOFY#8xI>0i_(dR!Wf4;!KEpmP^!3A*c);l*gCJ4Gos%4b5`V39{N zABF*pwM4c@oSEZEi4yIkM?h5j9FVwgO>3 zIDIn4Tq{jaxAAd=(N>|G8%$wMiKH)U!hCf4)Xr<9jGyP$vhCY+4}pHia;^+aZ70WO zmWWlcrirUJc1mkr8iO=1QZZb~__Rktddidq_NM0gSY=wjKu;_~8wJr+W7`IL2pKJ8VFP+>Q(>|gUuaio4Ys*46lTC&B1{J#+u`e3po+s|W}MxFJ!8V4Yeo(} zxN+<#$;z&LsQGOS3uJFGY>FE$Ofh>i_om4f4)cxS%hQdWKUL;N6p0H>l%C*+ z5e|;XINkDawkwsDBdWw(pEUyM-Z-#|QfFY^A$%^EK)2a!oa;l_23BYdJa_0sC6zh_ zcavFzB9~VTC0ZabP5i|znUM?#RzHpNi7`v`br=S7)D9(sc zJSqO!=FhPp{yEoQCK`PpPFLEsuvkmn0@6DeapPA;&L+1@L@2JjC2Rm*Z;^C9I*l9a z9V;_Oxy%7_3}?IjbY?zYtWy*ExW?01%^j`TT_Rme!1238G^GRI6z}9JI0wm_s1-9& z(wU&<&q0{ayWSG1QFyIOke6tRaim+kFp6~wbU92?2)eAOZST;U&bln8tdFYSp{-%V zxevSoN-sTk&SKLO>7sU|=8o`Q8amf&qt>GH7pNA>kD#IIj%BiPc=W6_nOzeV3ImDm zGVKT3neHo1kf=pBvP4Vp&D}Sk#{iD?{UJ-;|4aJafbHX*do>VKHGS6cMbqp z%0Kaf0zO?OI;1j9C2G1pL&pKLN^8)~T{^HOvY9Yl<=bXg^QtQkL64=A!2rEQS_99$ za!{FLdK6i_sb%W)BR_kmaD|SR1oTp;D-SiB5uF-d$M0613KWALYZrT*>oH`>Q_vR( zXoE45iu4z03G)bzPnlwRR2x~JU{=zB_srD1^9uu6@;`wY4*y0LX$?U4%0VTa`hHJr z$^bq>p>GD*(4_&hdc&J?m%t)smMVFJS6w#LpN<)5ZZ;{khsgB8# zHPn6Y#i>1%GC;j{TMbMWQ{FPIB|%#ac!Ad1RM+dpI zNb1@vzgSbl@nGXQ=Yq95xwc!b+Ok>FiCoiGA#APA-ZGWj!3+aS!%?*c{=}+gG?nA& z8Hd5%B#*8S4GTjHn2Y$t_s+rBpxap_Ojah}a1hhNULyJR(eN2QPjgoM({t8nZWj5c z=enV-8ehGGkg7{=l`?FS3q*VCv;rUju9^LZdk(i~??Ai-Rg;c()ysg$l59#XS6S^9 z?a5P0zl8l&s`2FqP3ceWqd7a!C>Z7=((RL(Zv=u+a#1(vRunX;9>M3Y(i(JgLly*` zRP(+m>;@&Q2aEIy=MG>TH5av^%f1&QUWwK-o#7k{aLwF1)@Thncfvx&JJsEVTAYMV zb%7zEKVVlQo-Mv=k=Ee5dD_$3oo2!s2UzrIbQ2#51dWJinbxS4lUgrxvdqH%o8W%$^N64FlWR_+urU<(ej^AF$(K?JFS`@L7lT#3}N+* zYT`x;o%2PssP6R^Nb~n$ccIwMxg#EtxJ8Q8E#0pGk~^mQ_)7C(mO0*@llYJ(Yycke z4Er(9vB&Z<>3)Vd8EXpUIIpKJh>{80`b?5(T7QPy7iw@3PbW^yk0-%b$Py^|!zN@t^+k>o0$x7eH{L{_(fJ{_+Rw zFX>LbjQEN?grtjQL4Z z4wG~tIu=oTR+v8C?`W{Ww+nvPgEODT0IkED2{RCf)@lvJxk`UrTJ)w zi&$o>#k2=f4WeVzd2&$d#ae^WE%&e3s7CE^IL6~bx81*tcow?#{RXgEs3ic|IgTo= z%u+oNfpa6B`Fg~}C0$YRxHzy>Yaq^*{hQez=R=|Mh?SfBy1M|53lt%t-muTp@L44hb7o{AxRm!<6a} zuC3-c9imgelZ#~5V+M3)Nz>)`}E7dULh}QRQuePqg!nOT9|15#! zmdn{RxvoEiw?hMFwGDeb3b<=`D%-P=az6Y+`BNTxy@!d<=;h0v#-<8J52hTV6)!zS ze}adtkg~sI`5rn?G!?L8Gzr)RaFd*dX!DN5*3J-libR%`se8d&a zF5g0;32Asp;LvyNxI*}&K3Yd$>nH&976Mxf&(@V{ejE*I#MF3-rCew*=r88$ZsH-U zG*iB!ncIFYyTq)MF5z3?D%z1_DgyPQ$Ze>s!NZ4^v)-eGNkDcRsKJC<9^x;_c~>O- z2{U8jv>%Z9g&1^?wI`+8O0j%|_O9kC70S>|3D~zKgt8rNCP(qM##1WD?1_D#g7sVW z%vnvOo1ouR8=Xomp6at*Gprw-BF*OxvYpH()^eoiU@ zy=?x9I+{3v+uLgPTsvWfURkH@t@o5Z7RO*9OYbA}d?4?mL2H4rs%mDRD!@kHLtywQ zt7Tu?`k{5USb(Mz!zdu8kh^HrZ=jF}kDKL@_7}V5)_0=XMhs?oRKMSFkfF2y<75e> zX1%>E4{m%pgseS}VDN|Ui=QT!D75dJKhVL-F7pOB{`4LtWMm^K+fRs8y+r&nM?1m8 zfk1tUxv00*D>|}}3SVB~-fc^tkNG($I9Lg#W*FMR zyL*VE3^}(bEpaWf7xdiHJ2I)vG6dOL^7YnhMFL7}O0<$^@~XQM+Mn~=n{_ag&@PQ5 z&IPK8(E*SPVF$NIq80rR~6(HDHY{?kAFCF9Kj0!CvWhBi{X_4g4}F6$oszns!Genb?He|rm! z)OG^n`6MaZ8A$N85m|1vxGV23-TU8*g64|~2kqa8y8dfFvmE>+x}94WOPvuS=sXtB zfI9O<2l9EDI;Kbh>Wq9cq_MNE8uacj0-ZCTFIs5+rU)ssQp+!qbYvL@^ef8J4N1aa zt$+0Uip6yQa!#80NMV=#n>$EDfde;AOwnkXIl+`RqAPRjAE?Q$Xy$u-+B|2Ov6OUU zB4q2|i*4TBq)2-*eK$8DhBOqvsMZ?%y-NjlX6T<6|5g6;@kp99_AN)lUgkVVU9r#y z=g~he-sP9)`TUBUq&2a|$|Ke#v>g9ZhjQ)zewXG$%js9+!)MFiV5YMd%-~oMky?U! zj(cW(KXfku`2!MBMhm};1Yq_TW4~}3V_{`-sk-V1i!5Yi^5=u65)(R7dKODJ@ohI< zB-9^Y=4AC}mY+hmM=B{+rF;Od&3YUT7;#l9p(3<=Ab%l2SB_paU1w^qPS3pz%Y z-qbp5bgUKu>|ZWd$hM@_GnfDTHk>VA1Y~{r!#lu5;oWay&p)7z^+$hxBqJFU&fcle zWN!EqnH?(P`)~VUgi!a--|mD%5fei?vUj*$+nui}be{jN6rn$wUrBKD??&k3J871= z`e)P`mf5ZlzBCi-d4A2eUy#G&v>B5L^`P*#KMb@MndEObidrfD$# zfj!WhY2^P4BD(zClMBFb^*@(7^ zbjr`Zu_1&#Z<{DxJwFhDg#UQ353xP}$GP)ku>REfVP6ohjaAjT||7aA(zkl6Cusb1s@%wJMIV1ZAo_iz;UBg&Rp+yj-Ji^ zd5=u=)$3*DZIF7l*SmU(Sbo=^9OUNufg^+GUhr8T=umd~#CWl}#m*@THTNThlKB5BWa)E#L8VD~fS>xXY*=b;vHZGVz|7UqNn z#GhKhE?zuMq<6Hx50OmTM}lWFZQ#0lXh8N^lhE;R6}tz#^gpDf;oWbj$-^~n>ZQjh zh%kxT-$P`*3(G`$tYVC+p6mnNVpDpN1lp`LV!E1E`~u>9)1t|DmXA;l0$N(vsL|(p zv3?TZ;JfzQf-bKrb{g?~kfrYo7nbCWn6Xj&74D|(+q^Qamr;3zkmX6qOzy#~ zX<#isznd5wI$5K!#?5R$*V|V{F>t7JBuhN_70RfUp3rW zA>aF|6hDPknVTRQrG}wToGC>hreeTEF-}+cz{BQml+*~5cu_%nEEY=NUVxO?I71Kr z$)saPDL1By5dQ`rc>uD0m$@~b&RbYb%+EFunEC<+{sBNS$y87(VU?)u_)>lQ0)4OJMa7zwu8 zDCz?!;ESEEd=ifF6oD96m#E+}xTfS4ife*FVS3yniP&k{LS0VU{#Z{8FPkZUL*{s4_fV;~f-+R% z=y->nms~)!Gse4^nkU{Kc=YnOMMCWlGLdE_)c*7OJ$P1gTZKmZqxG9o604{rL!&Ea z`0!tA9<3O2Kew=s=2S9$q`lWzl43~83O}Ns)xH!G$!pty^JzJ!f8Bl_CDuoDIfW?a zqZw9dXIbDBh?-m1=bi>+HZgJKmvf@Vq_`i~TEq5EZlO#u@>~dsO*+b0M@1F+i`gP# z>3Y$g!-EL>lLN!-KNpUzceD~`e}r$y@a+RxjEtoTJF)&+!N2|~IYW`X{vRwU{lEUh zKR*7dU5=~>glW`iP~E@%BaQz;RsYjjqPUWPC<8Gd$thvj$CJ@n%ICG$MTnyJA08wR zlv3*I29m=sJ+?spM#=g4*fk7YTEAwEbq=DrLZSCXDZUY&1|%Ap^y5Q^LIP&83I-#Y z>i-4?vL{6fL}W3%==3@{p{4(6RIKX3$e!cFmrM6A;m^<$8jX!T+tD_)Voth1CPN7% z{O!{7b0pp*f+5H};@ROj8bhC;$YXy_saWeUH}xCWj`h7$s({8Lt*TPtC}WNwiUf0l zS{9u&V1;zjQwm}{jKxz5?9?)5f)KMwUjd;OFX0)Ev|$hTNOU!6dPI974M0x@Y>5Zi zkKg{A3O0?{b^p43vhbz*$84?VgKe=dUX9bU0zEOZvs-;5XoWxDFZa7*andb~5f}T|_s+VVtMUEn?S?A7Qe#3Pp zg>Q`fLJkj))-dUuMAvU}L^>yl;Rxv_iN$pLrNXi1xUo&2$`Eu_wN#IotCk9o%U;08 zU#TL28zUO0B%+PuEg#T29@1L2 zATL`NcuIiXN?HJ_RfJ4lW>t(XQxIT$Z-f>K!c zP=(nYa1| zPk}+u>1hXI@l|9jhsB)e|F_cEwbkgAt3-$0FQvTYA&McBso&%j^K!IMbeX%omKJ2w zJ=;n0*4yZ-A9s-wL7Yud@qiTnYgta zCyh9A;t+x@DOXYY8dS=gQH@jl0UVJ7^I%;;F&xPvD_M9x8c@eKZ@^^})PgL?h$7Gz zVKqLa@WtU*AHG>;#%3vocXjFn!Zku*CaodEYh9(|E= z^3an2*Pe7z$a+5Mks};>{kgL+MEM#Y!p@MNkYiK>>|c}K2nWi>{4334#@*8L86woI z@&T#kMQ79xso}w6KWYicb8pBePdH2JIPZXfHNrWkBdoRvf+v{1u=7g1D$k)`_P} zoPV_2ICzyt9_YxJPp(nI0t$uqzPMR0_%uI5Qq$Esk#5$(f++?=f@`Z-y#x7de;fHj z+QKkiobnFl=u|o!=U{$hIa8y3=AX9<@`a$i2=;8GodY$UAak$+nmL3k`WBr0%s zma-(YCii%`LCfodTBkbT{6Z+ar@sBbN z`XZd3Wn3HLzuqev&Gt!*8zhq49C#7QHV&s}TO$DXf~>3m$wpvIwx6zzm6I8FP82GmphNHq!hE(1E=(DaM5r3_TQZT3T-B-0IHKVl(e4bzRifG$uu|G{A+KI zc7??DI)BB!@R3z3nMTp^4322pB!#Mrv6j8XDPQ2;ktr;_BWG#$g%}4*o2hNodG{`; zw21(w{eCKA^Gt+A zG2W17V>2Ls6Tvi*9!34MV3K*x?TV$%2D0^JHbAjq@tX}$GNd_oloQNXQ~@(46D~9r z{aNSjHVQ8@?-g~qEb~kP2_g}F>;%*1>2KDR_j&BGSkjZ+yI{Ptlg|sNpk&0-_z?03h!Zsyqv=Hstm-XeL58roD=0^5 zjer20zog8$pq#a2qIphP-df&C-(}7*V>74E+R8Re(IcSHvWJ!;%tn^XL0QIi&7bml zPibwG^GxSETA7!j%Y@8ziDE~W375V)O*>7Ni7M;u6=`@V-f+rGBeOg~yo)%~`}qaa!i`8q5^a}d1ymScZEKWFDH*Pvs!%kJF4JsGc*%s-H4PGQ6TzR6=LGZ7TCkcXTb`XOnV zWCS5YnR_xLlYJk=Qr3n~%;(fZ&tv^{%Gh5qr_9Qv%QN?6CgALPZzib!(*))qlqM5n zhQ|>~ldamOqRGE`cIR-@Ro4qC6KW~{_6!$n8fEhjW<|2iRtutYx01FXz?0j@x@MB` zU(ki_Bm~m-z*c^_0{QQRyi@_%wo-Wd#t}zT&g<&_wxz?nNXL9L<;wJa308KdN?HEF ztUPuFSYsk>yMs39pCgQ^@`OP89CHQo-wS;y@TBcmkUlt7$f51gvhJ8swb#+E-pE-* z_Vdgc)mlVHk(`Ac)dD&Vh>dWUvsWqkjA~ZKDIc)JJsEAAZpX#ni^OOn$i^&Zvi((` zvFL(Dt518qv3`N+MI6lBC=9lJ?(|SJa}B5Qk;ezKhR|4ediR?;)h{s3n&-08z~#QN z@xLIA8=h;}CYKYYxhI?R?%$BYsNrPA(#A!+NavW9HtwKlW0_~-G9EEL8(5VkOF8q% z#*Zk9SauDZjxdwI z^32zbS()@X=E~%ZasP(&Mg6CabEb3Ran6+KG#1;j&OoR?d4EggBJYAs zp^oZFS}4Qi^F3*8?_@ohkxElt{b2iJN1N?&949lENn<-gN-90Bxp&^yARXrY+YuPG zp)BuA#eN-DwybL_{vWR$XWOl*>03 z(}GASh*|FSO`T)znP4y9N&H}C+ufv%M`|o)-_$v#%rtm-Ixj7kAymuCrO!22FiiwG zGS38`2lG413`{)B%CIzv;JMG1^NJ^Shf9oH+Jux|K_{0cn_UKXyel#}`->HXS?;mh z7^OO&^_(EBP1ctqwSw8Eu`K#K6ikyDGx{l5O3IUehRCf>Fiq;e%x<`sZgTCBdH;44 zg1k#H&lKGjXJzEFYZ>%!67ZI9vmzA?`%&IwdMZ3&kcM7x?>S!(lh#&Umm{@uY0G}c z@t1A)5bdPpGK6n+a_N!g$z{a6e>)0UhM$s4Z?we9Wjk^Kq`P0VHne$M$^6HUzq0J- z`-isLeHLRJvXRB8R_&!lX@YjmG1Vc z-e1)`@FhkrIQ`>?eenCkPwC);Dqdh5 zIyUf@o!)m_(N={Ygp`DJ1wiuPjWjke@9eRhU{&JJ_jX=&QQ1`gY>bArHyppNg(A3Exp7UdwRAtDrtXnHKBT1ME?01hyO+IT2e!?f{P96B|b2vtHa$uN?lxL*& zhc{KOTinrr?x%Gv?&vCWhvrH2xmfJ4m@ATa4?1cYNOnWBRif+Jai&gI$RGi+I%Tyy@27wbn-2j^LyjFZu(%^~b?LZ9Z?PT1kN z{M4a|L?fwbZ=2U?c*^)|^W6g8{`|asDeC0E(&HNAJzk#uSga}UGc_TS`VP$}Qs;hQ zb_3;Y^B>QnzmINZziZD8jea$CWYDsae4M@NMQcj}=DMZ+$}4kz-t|9Y%+B68$Cye3IdLj~`fX8UV>t{wZm1xa;E zmeL+ut9U|{($)uAzNyX}e^GZ|MMJx9N~Z3V#=#f|R7y&>wUZ;2(zbyEeS~d6Aml&HP0VjO8xv+%#?kMi(i3a&sk}yWY`umLEQ6#BF8__%0h;7w8js--r0Ss z_bl;QuTLiAE9t#{m%sf2SIpit8e7ES*+;9Ok>^_HGYD*1~!);B7RM7iX-Zcgd@sVs;K_qF_oJh+^-k!&@e(}C1$@ufDOhAq* zS?kG>?cjQENW{OP1fsZ;#eukBl?l-0MuWL%=&dTM!GEvX_E4iN8 zDAUJ;le}QtmA<@`qZCII* z=-gF`i}={U?idoSYnxKodT%_qp>VjV35C`}7KzVMNIZGgvX+>u4N)E+HF-S|?0hyT zX?>3kn!b?u36UnCsJE3Nl4eGP#A(^s1+8_Z)Pccye1B4$Cr_aQjsf0VX6{{0NPMTr zPdW7UqOy-meI#cTz6e;Nu9~r`9g%f6^+=@1Ff=|1cC4^I3DBtKzsckg3(fdwzA61I z4>W>lo(t=Qk24bO?eln(A@O8besotkQ6);6lW5rZHk_>pULQ>BFO3rYymuSktUi*& z__C@mvPleq6PJ~uk*GYdIV~H>6xxL0Rfb`FNwvn%x(#DgSwu4-(7UM|fxN<*Vd8MM zLna!BMi)6q=}{r_h8q%3Y47)VZk?59#9s zw#F*raI_-|O(_1dp5Mmd44oa**JUk9sK6I+uc&`#7&x44LY_$vY_-bCSq@3G7nKI3 zK_Ug2vuapQVTe3Vs36@tTaz0bVNl9)NF?($P4-FBki>~YC!_f}eXuaa+?la0&S?@ZtsKzZ)<498&j(2xlv@wZtghLvgvo&lqL6VY| zLiv!j=-W+j^NDU|sib=m7#+*U;cSOA+936*``>Bo;(3ymV;W5u{(LLg#FTI3&F0hb zO*zK5NfPQ-R9_#xvmH{ocTKzsx&0~t&{!9%!&Ep`lO5T0MW__)CWJk zsiX*`fk5e52-Hss!vfhIQ~3V#fwWNppqlw0N^Dh7%(3!nX?z@1Itr)E*?#s?NBKuf)w`8DXTmhA)5*-@X!O(Q@_aw{zvKZrEJePij$F7V|$RDS;JhF^DP04=yE_uh;(@EIQrVb)T-`3S<%?QJf%Jcq8Rt{U;KCM=!OHS#M3q>56Ikv&vU>;lHY4-BjS=ajq!VZM96-lxIg=&x z6ZAao`8Q@|v`6EBOwmD3MMIwz9H0h4cJAh0A?r+ zX=qJ26kjb5IIxQ==CzXupOwcKma?#%H;`9LB~d!D458hFb3SL{%7ieJMp)z@B30mM z7>tI>A#L-i)O8t7R>9Aa_>5{7$e0Qp^qP; zK`IL%_^2zSg95mD+WJ%_8KTc)LP0||*<}r~D?`gy@s{cj6^AbjnamXV&4f_UmCOl~ z9(+-3`es5TE4U2e1|iUM=nK_o0BbR z{vnZ+JAGE_o9u1Xd4wF5Us0p0qY~M%1sj)@`b#Ti#Jz}FL#2^eEX$E@mJ2h&UkWTa zDpe+&M(iDxHUnnkg&!a2Y}Ra0aT}5 zNPo$=W9tX@%5#xU<5EiD^H^wY#h_L`b7TrAf0CU#x`_}6|RoX_3ri1{3s$P@r83tHJWg;6LX@rP)PQZGxRf3!S} zfDu)~!RsP^l+G8;c4;KR!%WkLs6`5dKF3DdGZ{8gi>1`Y0xY6PHliFffvT(yC##Ww z_?4khg$e02i{Yqhl>O{U5~But$Hns`I!9}0q}K;>mN`pI(hrB9Nh)^nlOiSo6iwWp zY*DL>x+T~s2snRK&|-fxZMunF#TxcU`z4L^=V|ehPlD`trBf|vi~=3Y$As_bEWYs^ z2Y2NvBjE9CB$8{-*@$D=OOprg(LEYX;$x%A>c#V-dX+{T?wm%$M*JC=2Wr~*?ys`K z=O9+4^-c;5#zS6>$ydWfoE5kLLMA~ako*JpFVm!=2Wj$y@1uy4Z4@vc9!=L-^604l zaQmnPkQeZJ9b3LQIW$Cs45!mB*s-3AD${8a0t>xQVGsSkYE+iy{11xUWjY? zC3)WuuqZ^H0)~M0wd669PaaMrP2G`l|HQsfBk!*%7tUb5GWOFySs#=Z0i9Y<&kno% z8}BJcUkKUxZhfFDp8mOR@(&m73sBgM|HG&dkAe{;Z)LpkXeEO9$D}>^Egq2km-NVv zmoXAAo--YfjlrePB$O;t&JTg+A@?-Y^Me2(BcTT;b0rkU0<$B%B{2lVXmk*)8UF$p ziZU@bwH6CpS-47JxE0#in1hq$Dbzj-mek?^*i)fELu?0gY>ODx*=S?UQ*B`88VYnG zrG=!OkTAnLSPD7U7uY#)sw5Rh)AI)h+v6B2N~Z}#n;+j_G;IW%D?3hd1cs}0eoNqZ zu!cb43pHr+p$W7V{o*oET`9VZFDh2Af}l*2mrHu7Xnznkl_hsaVfJvY-%!Wc z8?hd6WVD%XUKUwJX)c1}Sni<<>`r1M32++l!v}T5BA*E0HF?17GE;azYAhI%8z`6;!#Nz=U`0eJL`logNA$*J&ij6|?7fJPQ^ z-NaLjSCwO8xYW;5=%38d?xxwn}uxWz2RkRL%f&K zL=t(n7`-T_Xvg$ydmb-D(PU(`7GlD7t$m(Mrihq;Q>^5Pj16Jq)tkJbb>85%FjDb=q8 ziR^cjWP!${YQ)y*HS6)%NC}i~COW4YUTyj9BvPNEP4S?4s9k@o8a!yMNo_IAY#?M- zj%unBuCy+O&`f|DAdHUua!*@L{h2uq~VjF6Tfu(`LO=Hxh&^_3k!t*|nC8gI4 zO}Of4^N9srf$4o$(}k8)8o1qzdAf#R!$v5FlHyL^u@-Lc|L>u zZbl(17S77*DD+7ZPj^YDY;;BJHX^SoBwRV^7z>d^EDSRdMrj`fTcjs-RIMgfwhmwm zPfZ@oKuL?p!lmdvB1<|YK}<+WJZC2870+v z_|LTO_>LBkDNwH=Kov3nY%Y=G*=n{?zKEr#Dy7oYB>bcqb4(*uII?%rRHhl}-DG#< zFyMQ-3Rg+Q*@3lCpvqQn5X<#w9*NG;8WM5)><*x?#yl+;sa+dMeCr>g+w$cck;Il# z7aYg<VaKt zeFw=>VSqI`{p87^tZpE>qp@JSeRbouxp#)1QqpI=!IfW1Yy|p<0*<2#Wv$aH0 z8wK^j&wQx3-t_qgHVXdDYz^=;?MlecoanaaM0RZCT$+XF`54NLynAzOa-5?X8f)!| zun-tAbWS`!`+_CwIV&!uYqeS*4a4q#ZpYY2o8NKou~_LE&N6XdKUGh;(nu zBT^t&TAMUM_@!t{I=ND;mEt6qNgM}MkKYMPj~PjUknvpB27yRmLsu8%_;=-!2)F}T z)d)4nl=OxQndHECbh3Jy!ocPj({(sqtIkF;1@ zMheEma*_2TC^U8i=FpR?vf%L$Wd)$hOqN!fvhFM!#<4mqa2tSPTBC{ur__NVcQDOKH|vq02r5o z1xA%Dk#wHH_c7b1JqNh;dRZ+WmkT7X?(Zr`Vz{5GS4Q__K85H3RUev(#C&upI}))T zAXE4xZA83_lX0vxf^;X$Aoa)A5tgU@A_08Prczha`_b^H6gg+kUwu>>$E@(AOxcwG zYaKze3`E&wc18a=@{v)fMOLp8`4vUu8)&+ojqwjWI`4`QT9K*F%qk;ntX{xiz(=Cd zj*H#NlDKBa6gPN7 zj`Enck5c{Ou5u(&JD8Jb?J9kG*8I@k0;>ps<~gHrJX&K{-K%mbq$5HEL9K_4uD^&< zsl^4_*u~=XU$wSGi)iSw&7nr)*;*2bUNr-!VjZq?R>uLXM985UC!}((SvCriH)rG4 zt*YASAI%ljc^K!%gD}!extF90pojdZ@<)P?w5XC*2ZAN!)zP^|S|Wh}ct`6sayie;D=$+Sm2)~O{j>dsN-_#f!?TKt#anc) zwuo+2OJWM`hyx=-r4kWH`w#->oWu(5MGgN&os5k6U{B>DXT#ZAN131!<3kn(PL44S z&G)9Mq^_5v(lv}OFP*csR0?!F-j^$}mrX38(ws^gogbK3_iO~GGZUNRq!vh+tmTH`C;?Ir^`Pk@os`EZ%U zM)R=8xv!kS=5|q052WNtkr*GMM)pB1vhtFWG3nHzOJCQh?C&c_Bo=UPUo9(BM3xu6 zf$6H={br~BWy2U=q*TOw3(y8q|B3C<2uychNh(h_2Z}Ns9nN)@oL`I94(Zf09wZ9X zv#==a;M8vzpk=Fya}Vq=qR|70HgA1$8>!%ddp4g+p%ySb!1@91Hry;HCvXKKKsJWe z`~gJRR3)AG4o7m0%+sjr>EV7wCyQ>Gl*a%)0dul%eZozgmfC)5FX2?uu7nHEXl7Z3 zuN8jOOI4LvC!~EUhqE>D9sD~@q@FkYrl_?jc{+-H_wpF-Vr_dU1h!wnOu?$bN>G7b85%{&Om=FJT!hqg24J*igh^F(|-! zjK{pAEDYX64~?Nut<16?oOZgp9sCe84|`k0F+hwbQ6$jnsIo>(pL2Q-qeiOc(+T zBap{+xuh$#M4Ntqjqe^PvW&Vj2-TaO)0pltXp4mQ4S`{tT50yU(xdz-gwayiaJ=YOyz#i-ABMCFn$S&d({&rg;7N&tCRr zlW~`q=9KZWf&J;)&WuK$#PL{^OEYj*jI2h19nhIa<7KQ8%Y6U6iEB@1xs$8LheYqJ zxKm>dl&1a{oYNZF!4IKUM&6C+#P#E7`WddsMy&AV}qzV2;b|y3h2b{rmD> zYIQCwWqVZ0Ica+e3%C`g1Kt6u&}jQ&+w!^v-X)Ww07iQZ!0)Q#;1axspmITXK}`(eA0u--TNBLUmI^S2%VMPf zf$Dl;9+@=vY2K58k(O$?n*!sUa?;68(Rp+_M{1cL#~f=USPMv+t#eg5so_xp()fjz zT77Tw|A**|hM78BdvrRF&cO{d>?Ay(&;n9h@CoH8Gj=*Rmg6SKwmCPk#4YlkvOYjq z`t@40LV$Fvn>Z7URaqj1Y3{uyMoC+LnLYq_H-FNUNf~|@1zvz+w7>G2$r9{2jay<; zs9`IaUlAK zd8MyJ^$~~#7(6bGbajylmrNDnfhbTCQ@QOGOmrT>m7MuL!!`Ddo}GJSqWp3UA3OIrWgdi0|PeRMy{kYvrO}1XfdEXRY3D}(Hv z)(>qysk1-jiv?cZKBNjvd<111TF=!)%rR7ep#^Tk^z=G62OXGM~8N0)jQRFMPU5YjA!4!h2 z1hYZ*BV6s`#z!tPR)%nCF(~e^zTD7?>d{>}eAJGK{<3mJB1>~d!sjM_C0GGCs*V+8 zDw)`+#Ol^R)Z9xcnk)(aF(X(O3Jy6mu7jvYaT`iT-m-p^M<%k4K&a`a+;!3; z*0m=9=ce1IQaW)Unr|YS2Qv8%9-W1@*6?VFn^s4V_yaP4fImtm#l*SD_GAjTh5utA z5HoKZ3mRUMeH4i$pi{<0K82%1HZ7Ip)m#_cWOpWlvDZ93iG2|;Xv`VQr}AN%m+=yb zZiIxqQt2RdEv;B2WI8rK4{Z-!2R)=z|J1pJt6`7UhiBxKNRUvO7+pC8Rl`|K zKw=Ma6aXe$hyk)#rDSQj-b2<998X3tUbtB?PhfGZdg_PdfIX?{XXu!Lh}s8TV^2;2 zWCtJ@onC3ovF#bp)~F@#W|3R)Rm_tzTC;wQMmWdw%gY}C% ztt79ZlSd0k)1Hqk2#+t1N+1{o!^{MgI1^Wse{5+DWbc4 z5kxDZ=X%)@d33f>VA&+ZJ}-JxT9e5fZRbVcGPm%9KoG^V8f(VNt3={|=0tY#dUUoX zOxKWODG@BWGft6c{A-|+c$={a{GZ&&VLPvU(|BJgt)y`rlzKW=f|Nth@D1|i%-XFS zaHy0AVWkg32@vVkuU^not*5CR?<+}Vkw@3%*`Cpg<%mRK<^ubC zSlh#R1eg#0XxfL)&5W17bR^A%y;mqZzw1)q!+xqjVmG~%f-r|J;+Vh&=*b)scXaGW z2zuziG2qYgO|~p{#)k=6Y77`3t)QSq!YYU5t2}NJJJ790^zlffv+}$-b`ng_*=gw{ z$-`i#mVGTv?7vV&Dvw^sQtwDMx7yBelGh1&#fI zLA4liL}!tUqx*7r$*cnL5e4g*NR zqDkPSs5Vkm1@S`b(DRf#k;B;+EfVX*MgKbxnK!_gWVDYCOIhYf4m4-brGW_4(0 zlEO+{nQ?fe3q7=`0;^-=fTN>1B%q*y5x}9PTO==V;1zPU60&xX^g)AGa7_vp7d_PH}~L`t2ZWZSG6k zF!g&?JG~UPq7xZj5^-z0Ez5^#`qLTRGWzChtB<7r$hr-PVTUTkM3L^j08(ZDXby?As|Yj++1R2+lg~1dQk_a@syZ{4@!Dbuhl!U-q{2N{NXtdS z8^RXhK{<>b7d*@&X@lVQ^hnVgIFV++K>9_A`ZS5)v-`Wsago3wLn3N}#itpefe}>l zw)%zqFbAQ7-}??N>x@=Bz0wuZR!Nv%1TC0Tu2$o zD8+IOi4fAIXSeV)r+csEXdr0l%iyU{4E1MzOXAU0d0c$aFakEA6|h3vr$sef|BhR! zt*k;~d7^++fh3^78+Q_`Is)F%TeA9DF1|lnBdJGs<G;@%q&OhoQiL z#xB4C97op!?5Ad8kKk9u%u@2zY6V;%C@TR+NnY&gR=@Q|t?4}V7@@lSJU z?Kug&n&e$OXL$VeAdV~dPr@XaAo0F>!rxsueso(NC!OocaS{WWArh;~c1)y(YBdS# zfpS{j>1b{wKfbLcI;qr=@*j0HA(pkJbkihHT3HiKW=N+31QYF9 zE3HSD^=D{I<&I@J1||Rrqzv_(YNU23gV5sXDLNEia@~#DIk+p2M3ArjW#wcQeM!hF z7KCYY1~LRPWOd@4j}sb??#iQ4t7<^*@tf5f$>YliS2IQ@L!)!FosU3%w5%C$FDPv) zkDFrqM2a{Zhh9^MR3swDNStJbkw<6q6cXo0nhE5Jd1W?b8ewIRE6`4|5&R@78_b_+ zRly}9qtc^sABShl6G^_rmL)6_Fs{QsKrzwU(+J$0rx}Pne*saZFqjE;l#hEyb4YYf zwhJq1ARv~KV1hl{VdHV3tH%T_n+ar_ZC4fb|`LDL#iH?;{=A32~g^=i%v^qPfOGiz0icYbXU( z511ZJXImk)vBMFG`dxZdkc@2++^h{^(`X>KmZ67dbLph|DwZuqXfK^F=8UokZ{qk{Ko7qgVMe3DG-b+R0$oRD3iz(REXuD!N zURci7@|)&T+mYEEP6A&}?5+c&AWX=Hn?ou!f7KHyF9_5_ja*GMuixYnx!)IK8Ts<^ z7gdlsk(z>Y=gJz%KItSQ zR#<0-Lac656Jo9e@G~MykUR~4=uThQ?Zz*P%IZ7NrRwI<@MK4(ta31?h50!>jCOIb zP;36?y4j5p909XkDsRKPUPCRjLM4#cZQ@Sc0UhPTBpe!V1oT`25in33_)ELijfs8q z2ZW548q_zqG_gfxm1+s{`J-pK9uz%{0#af40LMpZL%Rvf`ymQr%S$5UUPSbJAvV3F zg>rkqCHpEhXljm02aC!S*nWH%%wx^4HbBCuvQf_^g0Wu4rv$PBcvq0dkWT+YTFLwd za9v2hObtdXP%L96St&>Hg+!fBE=3#Bf(=l|pEn6KUREBM7&xM#6XX?qoy=Xi0!lzk z1Kr~BF2!@5pU>$G7#d(kYL{{y|5cy6Dq-qM&Y9BjBsi9!Z4O6-OVg+k=|d&Paq+<`y%oPMKCYY;;VTPk3kxPddN3I-cyi5vJGex;C(ud8Fb8OFIj^?I6zw7+_lK(hLu=rjl4k4ND@Hwm5bL5n>xy%ubSx!sY@{s!=in@ig@VRJuUo;BzUrk)j zzu+a7v>Q}|W=!|ITgLfn1VxQ4+Ad+-gSNN;ujkzt3=@fh4iCl@a0#7COdGxUIS~ZJ z0Q1TO6`4DLv|EUX_n)=4i0q%7Q++-1y;>IlvM#VAz(_3}E~#`ULKJOSvPhn*Rsc|s zLOHlvX4**jNSQ$P6=Qr=iUbjyOOcH|cvwf$1B{sh56_3_U@WqvOhjjgih)KdN4e4) zWON%@g)fwL@$-zv(vD`_nSnGw{C6-$JA4zgU|OI6wy<}YAyiRvtQkU5GDWA^ao{CI z5?L^$Z=mc-WvJ%tm$^ZGcuqkpS?6xGldN;%c$pB|K<5eZE>}|K+bGwNT|e;Ys>caC z+1+_#Rvq(o`RHMlqm40K%fbW=;14jntONs9;ApUGiW#8--pw*fkPEMS%n|NqE;lVL z8j>K#X82#LRgRRhV}_&ljsd&Oln@kYI7AZl0#YhMO7G>3Smh(fe^!?Zj^I{WGf zq{G0g_LYrzfn2qe(107o{gj#vjY;oQ*NKU8Qj^M^H2WQ2JP$668Y4HXI!78chjxR; zGwc;b;n=q=FFmKa9WCcn>oQxy&asg(CqvjZw<7=`|CWvKKXm!Pxo6w=WZ!XP{ekx% zZk+n{14pPsBlsHo6(o;MfjmN8%)Fj!GYShgq%~~ju2P9i1mrzsfkjAy2WiX zB_3#sLF_r|E1*!>Get&3RN={%Cy}G2xXhFDPdj3&9QSa-shqSFmq{Ugo?BwnsBtRb z*4X-l83JL%gLuBH>*UMvs-7phOp40bC;Jrz`MO6O2W8pvQ%xZCCps1ga&YP$XHd@L z74GNdetpcV%KnLRKVX=kF1!1~jtNfXvK6HA)3#qz7uQhZg zs;PMNocJ?^9N`^;vl{hoI}$rY$o;(x#yA2Av(z{-N6^eDs_j55?kjiF>dd(9lXB8)czGqw zc0v9?KZ8vX&ZTE;$^!^Nwb!bXrl?~U>LMen=ZKx-}57N%z}E|a6d znoQ#A1SpzU)Vb^btqMzdgZatwET2REL5gh$<|=xnpi9C=R`9Iw_Nz44umpT8_L zK=tNF-rquzH1k{_Me{FSlH`92Yy()FwnMO-hBY3v(MvnNKRmCAP;@Tu*F2xBw^PN3 zCo$NG2_}tt+>#SsrG~Ex7@%_QZk?#$GuThzm6pJ>^zik7kU9Z?1>s3w8`KTZpP>oK zL;&?_rnN;0AJ8H(06t)Y%Usjt)`s8>bH3Pm4!oes%8|ig*Ed?IDKoqGMz4lV=XJ1X zL5&pGK0w?Mg9-m(G6VY3b2R_Eqam?R1l3BmT;6oDrVkkQ2+{1 z=@t$4_@WsYz3xbg#przLZHNl(#b9j`6T7#dUTDw-R!RPGmoVT>;77ss>P%RNqC)KH zX6_se8|0L~Gw6zDW zrO446KpKgLVcc@*#0=yxy{p$(h#hFzRWW082+$cs6!9$Znd`(L%Na5I!u+Tisg16@ zB~k8}Zmo8bYxyY{9#_t^ZXGBRC}Bd=@7mkcBfR>I_FwCjwd+a)hA5iIuz@dInAw^| zbxmX;YGMr=!bkL1kw za>v9vH{6rr@l$)3_1c?Sp4jJG7?Yek21l;$vL^2FGzS;l({jc!T{O$I@S{-PGG)+V zwZHLztwHMPaLk`)FRqgk;VBI%o~sz$UQf&DVjZt^nUc77Zt^Q27>=XB?c;G60|4t# z++I%$)DB@B1wm~@*VAoy**m-?rK~6(GvOFFj8oKB3Y>rG5_mykPYcKl_F8Lw1u$#Y zLdwOCvCmb;=&`W5cd;EQ`f=bFu%v9$()$}amJ^Tk#5l2!oxl_T&wpu=)Ri&Ie)6o%lc-Ypnu;8tvI zC4zT`=O6<&%#tjC)BH&Jj245UaV%V6lI<2$ICdqB_BR7o?rjt;^6N&l>alv346+4A ztC6ij|7D(pW0-s50x2vAlr;sgPtacPm$5iDMY6_40$*a>jt(Wp=pu3C1MgFLqUDPu z3IMao4{njIu%Y;Db%dD^=HS>wgI_5_5@&RTN*_BoDRApOfyH(U1W5A2OFm3dK;bR4 zC?lL!?6$B)EE%rXJ5$FKR6#IQ3k&{=YizJt${_p?CfBkR&$G`mTU;g!f z{U87BZ-4nGpjw5z|Nbxk`j>w)dNK<9XoNaKMq}q`)@3@digP+T%hh`YM{@^4G>9WU zI9})S`NPrDIUkgzbWW{5{uyI^nT&W-RjcHlGtiTQUtbs^kfhbCb%Zz;PCG&Ifs|!g z-*t;8RPZyGr&hxU-+aQKpEGcm84@P&d-RK`k~i0mYl^~bxR$Ilp@u79r5O*eQelzx z?D)Yt*0RHm0vJp=@=8RV*u;%98;^A8 z0n_KWj!vHfD9=`M)+tjyt_#zs6fsXv48s>{DV@l=Ow32PP=ALA@aw2e!I3sjs8TW!drG9_j^ICPEKNmIF76o=tG z73)0}SK(NKMJFGFQ7cSGG0jR0rZP_s~JKfK)2jb~Xe-~p*RMvZ&%cO*9hDl;c#o5oxW?VvvWdRJ% zgPw-oil7CxxByEEb22>cNHj%rmnw;@Et$B|L4p*xe9Pb(jg`pS8dYIiu>crs)ZuLt z9Vw1P-k}j!Pp^SiYW>V@imuAU+&G!jk2z?3{2`{lFOXssIy!x$5f44drB`oRg+i%s zS(dDpIeH~41$a;Xx0520c>1GiVl%B%qzJ5!dIUf^h(gLouBw9?!*e$1-&fV9?nz|M z(=lvNptmO}qWAeOBnL~H^q5KMe)fdG2rvy)Zy1=YD;ya>;t3iQ9bZBiBjPVp5@N7S zJP0pPPQW9)lvWxwjM{SH#HqB^iQB!%oL%s=Y^g)bQj2)4Jy6a;@0T>I%&1a`r3^0O!*V+8b}SC7cN?rEc| z(KQ#X*8dH6>zt_54~^g=Rfrw+IT%nlVwiZ3iiF|0DNLQw+K!M@#_g(pkS+y2yq(_k zTo_0(7OZGZ9gm&4f^|X`FOv}l=cXJonjXg!ckCE_K8Kc_#_0=!gQ!ZYE>jYg)2+c8 zoUvzpI#Na}=eW(wglMP!={#fNmHWdF5zB4S2N7MOI7md!G&3qeWe~QFemy-R_AIhN0r+RB132kIOG^0|E`|@#Pi9V@%}X-0_r+2_ z#Mc24o5L#rJ>Kop^L513R2CN+h?H>S`~xOvXpogp;UlSa;Nz%8Er8S8#EJT3AWnN- zt@43o5L7im)>C_`btRR^FfTlmh6Bbu%ft+ffNnjoLF}Y`5-QpdgHY6=-bUevC;x8o zcmO9Nj%?9wxmyZSYF_Yw5*_Z3dMw&AhzpS_6(^q5@W>H16QCu62==eQD&NpFN<4rT z@ap#jRA6$Y1he|{7Kem_GBCtbsJq09lSeI#y%1HzijpLGDnK4k#}z;5iN`<$En2}a z!GjVI5(P-T$ELwWW2G``pd?nP9N{3~W63Xx1Z`!S3Z8~g4;(a$!Y3u)A0QTWA&{HZ;Von_&X^0E@%xHHCk7AeHcF zA3wOG2a8xlrq|NZ&Jh$Z;=nvxEfJk&VxeTf4%Y9gk_bjT_aTN57pOkRw?m4DqISU7 zmuZP-LYk5fup0;F%8ts}9EFH6(-);w3W$`8z?w>gzyNKG%Tf}u*QaVb`aq==x!Xf*XkkK_bciYhcM6sVy z7+uhHGNNjAOU6kv)DhzO(%UCM^frBme~97V`9CzROQy+KGLy5syv_ctTd?^wF{5bM^w71Joq7VDGWy7c zDYOqkRB85{2^|-huh$yjh=$si$`Db7c*-E3irRP7xtMec%XUp9tRW}5)}%<9)~eD4 z1WeEKa7bFab(Yo&7qBvw>GentKT`NX`V4UlPzXeTeBL2k;0syCJOsJ%OloDPqTUziActS9;wb9FFQvn==k3fNLSq`r1XJEY=7Y|DYIVtba zu~~wfKR_s+qW-EC#u5d!h?WirDXWmBzx7E2N8Sg~>h;PI$IE1dQ}@Q1NU|tRGsQ^1 zgb^Z{U`I$SCFsW~V|SGn#+stAtBF-y)m7=8(I`+_JgOnh?J4m*5O=}DVrV;2$}NUV zaJ9L*H*^Si+xxfCCvzhUgG0^wGyI^Cbj0S%(57hF{4;J|IYzt-=~b#F^kW02#Tuf;%DLLi-w=uo23{lr#Edi;UB z4#{W&Pf(Qx*j27*I(x47jZXpEgP*2QM*xfKE~c2ksXJ1q_mFXdk(cQJ3zwi{yxKE5 zf6`Q3rzP_9#umFWFYFeEO%`q3d?I7zm%2iExUVj7IM=Pr_+#$=`-*q~(rlpdm+qU)Q&&tDyN?`A*^(VLm!f4~(MXIS8Ny zHm{Km_8ht>v(o3gf!Fdc=@vlb`Z3 z1s0?Bj|l83<0_uhY`8vil`Et`f!14OBNJfkZUGVSLtjXe0{BWBn8-NF^tnfeI3ZWa zoJ%#`qyW50LGGwmUP%^iAtZ$MH;MwD{lwi`JyBBA(@w-mc+bKhvb5q~uJa>oo;2Qs z#=FLjaPCal704)|3KNBzAwo6AU0Mi?qgRe7UKXnm1l5vJbk$18sI)ydD4$@s2p*|D zRN6;LyiP_GrtC!(z#d-aJFlvg4~?am`^zd+LQV%LhR6x1a4424rU8L(4f==kE5$^Jyii+Rkzo9r1%xnZw- zHLZEoPqme@(hsubj9aoTkbnVSHWOCa(ieVgv8W_qCSK8}#uAgm%&S(6iKjsKTS_$Y z))XSk^^yQHUAxxriW4758LNI{_3}C;QQ);Vgo>m%=ICcyE~=~?%EMo`my5XNKvnh{ zULnOXMvl~XieH%7*Z!QA#YM*8?IUH`qAwBSRkG&guW|)r&CK&jmuU&3d+YSgU}1^V zKihFcQkXs{mXMi&1_jb)2I7`=8+4(erGl^CSaVwybCMLYL954(LTtx-2Xn4R}8P2ZCY-_0mQDPvwu zOsEG&@LCgdF_ke4O4i(*fEW)y4p)j2cP8`h`AWt3SQaz>{&#FqlrPJc;SQ>OYuP4YCsx zq&RyERhzIQ#XV0(?Ye)4Oe-6L2-phOIYH@3Ic2mj^CTV)*ou$7?zV%LV=G>tapHi{ zNL(f)tkRpX@l=@6bHvPNRyRaOu+Ca4O1LAzqRSMCm(lo%pLPhaOFi!kNdUhjaw$8T zf8?6`I=2erDL6b^i)5+Ge`=b3n9msBwALd?{P`khjb2_PuPVYm`zMtL5xv8&|A#5~j6u z-4e9>7n)IB3~SgeC1=IHr-i9qDou8U)%|m%JkN6)JRo72d4++3Kel?2Q%4rdRIR`; z56iGTN6=B=`km3vT{T#2&dC%@T(>sg(^fb)nz{S;vyM*rzABQSJQL3;A=qfSKt z42GOqu0Se310}9M;JDPc?qhSB~CJ%BZ@`)#SAPRO={2G8f@mP;XfnMiYu2Z7{gn7hb zID_rvGKnXjz~C!mz&X&2EXXb}E;>}F|0<4?)Cg=ZYHJ%2OM;BCiA8gjm7)MOK;K)Z`(R1dUEx%4m%8ohD>Nt-gbfjQx$7fcYhYPOK zqBle4Y%!6{*i7_fWuRr~Cf@%Z4>3}h54XDSaK(FTV<5$0i}M`DWwwNQWY=xjUkWO5 zm8R#`w}n&^933U}HxClg4we-ImbyJJ#CV!~?q#o!&kannvVtv!F)zT>$812RYV~A! zl!r*oBgVXQQE-Dy7HqHb2&;AnDe*h)7DJ#!gza>Mk>GJ@oa&0t=*#%rh2o%_ALh|k zx*!~DEi#?r@sSdcwhGRwHF~#RnHPK&XJ7TJ8S%XEs-k?&}7cA!cu|TuINx z9FlF)Y}lGJrqzB|_)jtB96v8}ChUV5Df35?r-RIeHD>;~@bm6LW*8IZkd_p0D4B{1 zqspYpPbMx)$zf1`XQ{+!G%m9xIZ)$>{&eQQFa5Z<>9n;W7DY(tBqsLtyJ9VyNxcqYwylWFRw zlxG>AysCY$FDM3@lhaVspK>PMnD&BR()|GJm ztfLLLi8ymH?SYliqbQM-axaxhE#-e~xLDHUm7h+$| zb>dwYZWDCc2GJDCe$InS14!riMSj@h2MauTE&T=+<>1k_j`rk@k3KptiOlNiZ#-oP z(r!-)Xp~@sNl>;Jv(UHLVAe>N?Y{g4HvQdu4wagg)=F<5EA=U00c0l_vhulGuACiM zrxgR~!7Rf|@1ZuI zxk?F(nlm0%DER`YM1NE$+x|EN0CfbIt$2qbDdg^dN&s>7kW})1a{*loh13@ z`Ro02GB8(V1Ss`s9VFcIoX6bZln;4+>UN)lTZ_;sJ3n+R?}`g+hJ;Q(y|b^d;f{28J*}gh#tj0);IVvg3_9-*9#uKXq^1Bm90Taubg^Q$ zQ1==27&C4}#*bX*@ou?(FHF8Y;AIBqd<{uA>fQgbD(v@vp8~L8_;g^a6YnbPdsY36 zr?U4+4EwKAD!Yf*Q7kS&*(3Kq5R3!bOqGtB+xBDdquahM9H+vPst+|Mj-v3Rv)>kw zGq#wk4|%l|zmOqG@oHPQ)ihYw7S)Ulv`Y!TLMl)XuD4%%6HDvjVwm-OhUxIuIFUUF z&SwAl`q`qI)qZn2+|tzXZf-yOUH5i=2|{zU<(GGLkM-d9w3{fpM6GQ1+LqtmpRKZ# z&5(D*l}r;yH33K5)?eNpt=OEq&lc6|_Iqo7y>oBnUl(ay4}Vn|cyK1jhgb&BPi&7W ztWxEvgLlAsyZ`z>{@dUF@=t&H5C8N3^!&^J_YeQ?U;gud|L1@H+yD6={>$I~@4x&L z0qKAKAOHHd|K*?m`TzRczy9T)zQ2BA(>6bob1DDzzx>Nz{^>t@2XuZoaoU$ArGk*U z1rIT$CETNC`56?G@Ut0_sdMmi?Azy&hEmg`mByYB9{SVcL!bYN>o3Pgg2yZLItn`_t05Q&&(XkAgn2<_U%13wjzqABgjbE|^HLL~d8C2^03N*<$>2I< zJRct}9Wm`WI?j(TyJWB@Lr<0H#Y}2=g^KUbPx{JK^l4tW0_Bm;yHlUM3L!y!f29Q~ ztZp%*xZ9PH8KAdO2<>2a{4k(g$mmZrh}0*nVEBn0Pw=etTTmdRjCcgg`3bZ)ONSl{ zoeR~R4Ch3>qK;IICgDr(hskI>89z*Gw=Qx{L~G+mUJx}>x+AR9YpMz)**wCM54FsJ zWqkV*rTsa46*|QtmhzboT47+Av=92{nPvp8WKP4J5tJ=H0iU89z$J?~foibl85uFq zO)rgAsHuvP(H&&@R%dL zG|U@@PF5{PM;Hw5RTU=1y3ny|Bi~D?_Uq^{H$<&e`EVL4;Eo%MYV)T{pC*R#%jo_aUgL zF@GhktS~R24U8`8l|jN0mj@#a1Kmj)qJ+{Y1HViUB{vZu?=NYc4cE@)miUg2HqVd2 zV(sO4TBTs?4Skj6<7Jfs=y;3)Jkz?e1qQ+v060Ws$@=}TELVsn1D_XAq}^#mO&o&F z5cQokT0khh9+i@g7};_t($=Bp1JZe_jHsp9IlfWvEh93Y#p9%y#9;z;2}mLo5_(VY zU|3T`A7{dgWvqGnctYx1$R;TcTghM_rW@n~+Jg@TJdH~NSD{Nu(L|UNG-$0A8zc`L zke-T$1Y#seD^?8b2Ot-uhB@+xPpmP3NxbRFVlwP=xfS$LqosftaS~b2!dHbf1!j%i zP+i;+n}pGf4Dn5hGbA;Ep9iko7-uC(t25(2B^pxb-qpv1jJEBft0&-#8UU7*(a)p^ z89ojQYj8Q&q8B-^KyPeGrX<}D;JaUv=wgdLckig80;fiM_z~XsTYe;6_+U1RN0R2z zp?@x7K|L72IRKh%merg~9c6~Q1 z=8#++lauAg)kgYc{|;eAv8x&F<1xSJ9@S;pw*YPDWw9@ZB>%@AYXXLY|9m_TuCyVJ zrxrkXKehIc!LV#JsuhaC{cf3!?rS^lE=qibYv3; zq<2AcF2B~fRpLQbhXMsH^{hgY^1y8NL3|Lca`Q!&TVp%B6l?vp&LMX~)*ni#KVuhx zIvrdfiGx<(;=GAFYc_FwlOrX$L$Y^g&SeR$W1}Q?6|<`XpD%!%jq(6^41(|FXMZ7x z&r)TdEqy;YqVAEtFp5HGS%Y`r#s@}!peJ>WSh0ZD2WQ-WEuQK0H7;c2ju^h~esDzR z8udE&0n0bBSm?=}G53_32joJ76W zCO+8?OaTW}7=4Axbn39m;JE;{<@>&ikXmaW-ocudA>(%{en<<2KUThE8+I(#j~vCp z$(g*R*N1*mPpv{Cz%t1P*>!1G?RI3#_vr&Lzr#Dv6v3*b5I<@*>5H!_t^3riBVvJF z@hbpy(Rp!(XpbIzwJOZ)6Z=sh1TIR0!oT=$JwibEqY?w#oMkLnN(VlJ+l7FGBoQT1fK2a)Qb#$x2Gu`)swk!P^%;(Fby@kMuMAxv zAe0={QY+mA2GXdxGsnovf9#fj_fJxCz2`>N7d_SS1w|p|=f`srulb;yUW3cefoIMbrUG%bX5gHnX z)EY>95&Mtu*z`c~!{iSr0l>KL?0w@ugJZj9W_oXqh1q|8ATMQD*kTYEmILt~w5+!g z&Y=fur22``=iJ%DM+4of)}vXNKokrcQLIXDAe^H+#>i3U-0=bV{K6p()>&X^+RJqB zK&2m<^g)|@Kaf0ngjYSd`N*_6H&060>9ew7&{ni3pJ{W>%gI5p5LlX1ztT&$9G>Pl zaxS4k&#`Ss*G)CLGzyy^OI*o=pM@t^oQ~5GOyB%&GeDK3uKg=;$^n{EmNKeP<4-|cgw&lP9GY`AF~$<5MYcdJ%ZV6-sj@^ z!$p*;+cs5B@-v(?;A0K47Kn=@0giC*2ZnuubguQ=ba_+0d2UVE71SPiE%Zzesx=#k z{TnzwP%QR}FQ1q?P=U;z*(Bzb9!G8Uw1T>Y@{kVZv_BJSY@@Etgc1CgSJs`el7mX@{(kd?$ z9zZ&Qb0v&9D8v$_6TSlGSIK$#7@-3YT}E3z$kwxwVVPE%mNflPOHDm;Nh+0;B}=>l zpj%L3Mgu|I`<9$+mvO(ZCv2;gf2KLOK8;L}hopf$xZvL2@quMMf6!Vk(QKc5RpbB9*xq)SKL*pl)N`Sz}lx(v$ad0m@$;?4;I|pJz zy_~6j0!PQ`8PtRRNX3{@Bs7mTudVyGL?74Z;urgp!8WIPcAB_+&Kw2-l ze25261!7enAdR>rERE3h2WO`Tf>Ey*U7I+Awcc&c)^#KJ={*CIgW1=TeL{q!;84sD zlOt>78-qjHgQdM>{{`sU#DUJahv1TRZt8C#MZ!3zk4@@4mv`UL#A@f9Jyw#8u70rR zGYAUY8$Y9U&fy)?N`r%`843lA)1@ySb1}bo|L}vY?v>6t`l#N$SIFHv4aWJ=eVG{y zMz3(*(MRnbY*Xs+8gZH*-bU-2nu0wC*sU5!DFh5^=Nw*Tf3P{2BWzolY@sFEMH9Kh z=iTcu!8uw;cp902#6Vs%+I&l3*t~GE=uq3Ll7wduqnFv^e4Q zA-^wYP9patDxfyO@ZBNk2Dk!P1$3&yT`01UA(7bXVXCwXKakakQXEYQPLM9pamC?o|GxYlJCct_>Dd+!CFUIm>K zMxW6WH9@imC&~_7>4C_1iYFMQ5diP-gRE&SDGdN%ek9B3qlZDSd*y@Zj;#02&MXwk znN+mA*#UHD(36zRYb)hkV*JxH);TvD-r-N^N%HWKeLp8P7)mTQGifq;2VN<*uDPSr z@S5NIkMT@S^^>#>>ro87R)Qn9`<Xc+Eix=sVze>;e%SYM*Nkl8kT6P1k_>UjF( z=R|!!`bAOKl88V{AN#(C76G~qy=QHS_wyOU@=2x>h`4L~vIpLN{ujoNkUWxQ_l*6T zfIY6*Z1TPY0hmoPWad~=@Y4yZS@O(q^JOL7q}RfS(&h7Es+p2pYY-9&WzoK z=f#C1Mnwf`GwmTaDczLE({@LyuN;$|5fSvx9|oYb$YfgCxGM=1Mn$awnxX^P7v@ zrS#lE8!2@@kUMhtwv&Ik^CNhgwHt$9UT&Bcxl-B~q3!q1kGGk$+(m}FnRf45mh6*z z)A*&EsP|!C3JB<>vMit!!l~pGWY>bUO| zdD*7499PNZx{{yaJ9}0|2F;I_ScgtOmHuCz6|_QNN%ilwBy#6j7s^s%zy`V?JUM&T zg{xIoB?GtLD_wxVTb|e8qAdv;=CWFLJf*92=q&38<4i;i&dn5D}B2H}f zq8yCs2|$`J8X#;*Bv35GiJ}KBDXo+tGcIz^l1`QhD@`W%lMQK3&*3I3kyERdAv z`ZdCG6?~HhwF`X|H1*`Oeyb({vS=;s3Jf$DFjb=#YzUVEzUhApAe(BqFa(6l63fmK&6!|hSQPqFp%r>0lSU-g^|gx{=rr~h0Y$@|+(KKFCRj~ktXUhk8N}B*_n&$$Bn@afOFLl|5m!Cd z1DS-0Aiq?(>?{RvaS$U6pVD|@@ml#BYR*E8GvT8Fd%m)K4{Jzhh~XxvW2O~JTd4x~ zV#vcQa0)gF0n7kSU5};5P?4ISPfQw>ci9evl7s7wMvNUmGixTGTiqzYy?UuvKTko5 z2e?s2tOheD^*gvQYHYwf>C~pTr(*#lkiMY|X0ZJM^9MWFXHgHu@^&R{<-RMi;v&dX zmU(b8gZe#{_H?WAuat7g$|9%wh(R zFGHQ|g^r~KF(@L9?x!-OlqM4a1N9Z|KujZ=?cKRsPa^51C}zR#H|Dobwsp zVfeJ3T-$mVw~Eo+E?&*=jXn|2EolQRm`p4S4Sho&NPCpGI%mnH&;k&Q;QnOud9GNY z#Vq`^=F*o;hq_%~KAR3*p-s~`JhMkw!D`r6Gy%<8(oi+Vl{8+L?SQDs4PUMiCOg2| zNFokwM=@~nbWDfx4|ut1;7>KHOkT#fgHl=32Z~87w~<1%M#&5?|IHd;aS)wk5)BW}dq!0Dmw<<_Ax2%l1{juvgNx#8Sa*sbgAzzH zkc!)!fvwNeI&u6R9uJ?z-PbTfH_w~~5PF;&G2(bGf*RfYW?;5^!qVgLm(ax0w|z~K z14#h``DyqgHHOG~8U?gB&)w*bcmCnah&merC;ZdfDpD>bjmx(<>?6w{SVfZcB1v96 ziHQ^J(*r!qa92@Jm6v@~qBekEQ} z*G(b+N+2soHPB4u2|{}f#5bO@p;wIzRmLDlvpTpq`2**L`6Fhm3@pxh^AR~STFMcN zjk)F}w19DLV@3h>f>6beq^Po(iJ zz2;gR%E&=LVVnHbICM}!s>gx?Xzz@M7grS|D`lpXXPq<_Yr~jnq-}2s3Y7@!6(Fv$ zY@tk511S*%k#hyrMzutXh6y zmU0{pMzfo{E@;*AA}E6hvQoPeWa~U1AKRkmm|XY8U5hvj}XhqJL@+d_TEh8TQ!KPf;4Kj-mxVkULtx z#0H_;mk`uzsWC$r>B<==4eY0(PQ0T*2?&Yb#a7macWZJ(7FZ5eZXMl2`q4ETqA3eh z8pwnUHIl_;Zdo9*ugt%Gjdo|Ddg@mwL&-)kdN*?}o7O*YDs3PEWuTaBw|h#G=>2H8 zxYWGFJr1UI9>lAAU9dP&CHx9A@uvjqs}t=qz+1SdLjN=Z<)6Cc`Qi*%MCfs6aZ+?B1#+#wgCvK$o~{$ILl zN9rHJa1HnHRi))d`JJSI*UhT#@s~hLae!1-h}m@UgdG~RA&AByTG^EDQC{amdfx0~ z6#<8Pc=j*)piEd&-iFg@*+fd_+%vkjAB-SV)10eSSWJsH4ip3c)>0=UNi0bag9k%& zmM|`>g(8bj6UaKAIe~_KgqC`01Etbq#Y+XPwF=@$VIO{viacR8#q2SC_?`OU-m~<5 zQ>e?(hkv7Ps|t#CGkJL%l_81edH$h|h`FYAo)*n;uiu#2jzO7R1JM-=vWcL} z6FivCscSegz~qX?GZYP0>PQ&?N10bWs=IU58}g!&ytS@QghGR7Q9XIRqoA``C@(xH zC7e6s7F=jRAOF02b|jO6JHeTD>mk-f^GeA?ktkMGZ+0$Xh3_Vl2Do^rzdacdoCuM*YsAAflHcSB4Xg+ufa zWNwxfpA$}Ch1)-SEuoxr{p8Mw^h?+p-VS1Uds@}@_df;sgsQJMFDyy(=W7oE>wy6} zHGc{&XcWQnqeNKyugTB!GfNl+NhU{8!pNeEQrRHuqX8p9A`fXKn{tExlC+S9fqJ|^ zg48s{5>;zf4vxNK^z{5Pzyz#Fe?@xyL0|~}hiXCjbf&CBeKab2(35G6v>p?t=}Q@c zZUbqrh!FB|)O(G{E3+W0pcC9wt_orNs}_nV7}01$#UVlqIUMnWunNMPRD;0pq&0+p zqoJZD*-2x~I7bAxx7?E%W6YE=m%tqiU7@i#8Yy$--A>_4&l7d5qsj)Tk2FqYb^56_ zEtUIDN8Of*BJ3JqCIqp=DC;CgrT(m#=ZRQMAyc)kpMTOOr_y3;d zTv;+YtqoYZ*f-sp+XIszz0+pu#(3-v#v+~m_mF$5ry#S#Xl*TM70h^JTe1l>rH7~k zeul*UXul(|s#`~VnxZeFnR#rqQ>5Fb{S35ozr&(jMZpjsCXcs2%^T?DbJPkJI5Iw* zdj9qmHJy}n{s8e=|CFchQ`QkHciNrlL+p&bcI>LXf70-ck|%JQB#-|seAsk|q{28Ud-ZFd zW*|x5BRSZ@v802-WYWP((PPA}#o|hJ{p~lMGiZ5}gF|tdVnv*$}xrE^OQRX%- zU?DdCc#_h@e@0fzLx8T#>1v7<&C&r(?6f%;q>1r^Rm?17h}<^DjIy)T)MCCQlO;kh zFy&{ZY>*~RyYZKs(rlgsA7rTMWM_#3dTYJXy*aitj-OB%4AHOYp*&vb@vOM1D_E~3 zRJAK(<$JEVAM6q}p#()%qe-E5iVPRp{cgj>WATqEvVvPNE{Pa{eNG^~<`e<+*{fU_ z4h@*m9Os=#ReDyL1K~>|#{&y=+o&df?;50w=U-{(@PE{Eq-U`32>1>O2Jh`^WSt&W z^|IbqrD)O^{hTIKQ)XKs)m8qNLMSP0y=?zz6oYBK676W@Kt{CHtnqG&ATlMWtcVbi zW-B?%g59AvB+xXi2>epofD7z-KZ)X$J=ZTO^%iZ&*SU;G<=S9;2%fpokVoV;c|9WIVvlp--+anvcFN1;6#^Au9a z@nE}GKA^BF-}u1{MFkKtXBsu2ooB2L1op`#mtjnr*@bBsm~nzNn79BH2X?v?D=5m8 zuc>$zi;2K%)A6NP!R8$mW0Kh+1s`fva{}ASxv((;`BQ766h;J9=_3iEWy&}pkB0D# zVi+ZHZI9Hx3yLkZQMk1QD2=%jd}M1v*noZ;h6uQxi`tOW!bH3`=Ywuh&)j{)Pp}*{FDk(LA}>pW^Os$;Bb#i@$m8S z@}Af`05jxRfE~=ia;l2Ln}&BY^a5rzfv){hx`Ff*LSv5#linhN5fE}%<01v=i+Em( zZUIjMq<^b1CryTu8S9DQG`kU#P}g$ycv?z%6fmh=BB)G6A1uxS@@DWup* z2e0xetp&uf+Dv_kpzeC%SA*!3rSb-V`{Oe9 z4B|CfR}Pb)hiE9TP^bc?mZ@kX2|~6VW(OpjW@6}P!6-1Ju_C}k{SUc8Qh#dRWOiR!9!wUoSNK?>Bz`BqHQM+Wi(cxs-Xj)5I6dl92eO@0?#9l_Jz`dc z??6nM#zw>^CjTSv(M8`>Ci4Y|Hf*Gz+e9Em#4IKUVbx^f11{I|im9Yq1Fl?REvUKM zDtVX7dS0Lt&jlaHOrFmoQtF+Ykt_;{n9B7#X9U#c*+sH3Wv`L~ueNAF8=Dy0B6QTq8Nznhi|Hm|gYK?e zBz_z~Yg$j)5-5UoK1}Z#NG+!Nh<6rWq{F~B;vF@VL<2ZHe@WSZP=3!Kn>z*uffNbH zMxjd2U0D3(COns;BuM>J`qrsuJ8(#=P>&@d?HmrST1vXGm^2qJOY~3C6sR?T?HlSy zMz&`XJl?=0cswokU#50dXz!V@zt+t}h!AIi!p~`zvo%s{|g`pREPgKNC z)Ckqm78JybT_E5Y7#3X^B&`BMf*hz1Qv;nzQuRez!Xq~&8^vH|wAY36@?ejBL71=# z1w!$Gxaa~I%{a9b+QC5Wg%k>9pu@QEC@}|3M0Ta*Vk7Zd^Pu$`fNZp_A*zdX^Bk-C zHsn|0kvV%Yh*w~UVZ$R)3@4AlXN%DQfy}lNK_~xW!GvbyETt|B07$UNxQQY#(Sj9) zdBj{flFAumdy@?uBV3X|_Ilyd4h|`35MGnhr$-Ibztp&!a9eT2U_5GGA_CU{KIwbql@;$#Akqbwp43671k0siBp59P6Y)K7%yfvo^JwTJKOR zF}M}D0xh0(G2bGEVhm_{WEu|nYD7?#Dy)TZiJDcX)sH<&ZU)dIb#y|MWR#+4r%FK zj7fa&-ZvUda)nBewVs7G%PEsMQ4P>hXvWhJNlobn(VhAwdPW*IsS@}<%BKg`tbAfj zUMT!fGSfgUdc=-~M@(`xjP=mW($LsR z3=zpPqF1uAK7u=LkOCDu!dQerLk=AF4Gz7I_{yOgy1ZARZsDn!QPhR((KshSV{>c6 z+LSnu1{NU^bZa|koADp3;yR7TEK*Y2U!wlLuiXgg#C9xNj!Kfwc}zb-07O*=$xesg z)%`IS$Q(w7j+Y*|KfcGfM9sc~Dj-~<5~s0^sGQOwbyys?6p=t&WKpE)6)VDUhNHUZ zCdnxke3i>_tU$+hhUSf67z2vT5DyVEh8e^P?C)?CQ;kS4;7^+xC(PKy`5i(T1vb(j zEg~eiY?_z_6_2WVg{s9`+_OEl}-$Xf&u|37c6z;gru)N}NBJzsmreLdicEY%`gevohc~Bh=3>={} zV3Xx43D30#h%k zm>h|E5YB@QDF^mtNvn<%gHFsCwPordU*Wt8>+P^9OiNz@AjGC-!BS>^pL$#(V+wO} z8wXv&IuTo9T8T3|< zl$KP`Vud82IvVOz+KAX)WRau7Lz0+u7 ztp_1G$B_?9mRXGi#Z3J3aaxT>d~jxwWu4Rpgz&|eW6h)Y=r7h(9Mq>BC?ft`sj+C= z++!w<;0rz}SvB8yTqE^$w3!B?JY%Vn6c&5Tr0~WB2?TUnG#%#9ZQ%?Ia^}SUtURT4 zOH^LVy_2y?lFA4p(`Q7N+FFp)+CE;TL8=BFJqv|$dYn7!waFv#0Y9&m{}hp5!(Kz{ z6!xMzM>%RnX=FwVmMIpV7}dllD~r@Ez-7>2hAFO~X^Y1zRET2U?g@0bkZ-((NH*;6KWRIh?5$5aBYNmzwEd)1lzT zZE6?mwxZLtGBFC)kggFxYfK5PdHyzwn#HKP*=cR2Hs~;I))ezNGt80-JHmP#qe^zj zT22i6s`_zQW>xOmb6IcmFd1||^-fiWVH9<;c$D8D&e7liu*bCXyOUT>OSLGb;fZ5Z zA=*eRrwSlMdvZzEZxlVS%1$J(I7%HRWqJOKtnQ>JpsPZtIS;G`AV8tUTar~RELC9* z(*cM7n4L&xVTEDl94ND5g|ucZs+TCVBd_yKswhRf50wAXZgkZA-g_(e^ z0(r=)91FIGBLk>azQ{1JuqZD{Kb@ZkY#A3;(!qoh2~8%p|8p;fh>S2vPuB;d=}=0?3l-($JuzMMso;k|`%yy}%==DG=vc zM0yM`nr25`M~;=FMO4X|Z!j4uU%t@g5UWOAj3&7StEE*LWCc)E;R~b?H!J4)^33 zongwDDh95bNKiNg9@?mN;7L~HJ6I1$c&h|nAj~SL>1LEUD+8tsLJNhyVsW*TsHX41 z!R7^z{9j5e;aj8(y1&I%w@O+>YERTk+5jShYQ60{HXQ0pj&lO@_RC->CimnLD}%%c zM2Adn#~EZ6@oLN}(!k-;Pt)KOe*{|2M#8#5VWHRzMn+A}TW?Tb0-%o4vKl&6YvHk+ zl5u~yO-9WL_)uA5Q3eqv4j7D*_NoYPKtKPwCNi z7JtHFtZS8YhvEw&ifcr+8-pX9`jo$9V^Ud7Ph9JJ@B`=k0R=_M^ehsYS#IuyjHm!7 z7jN*O41+*|fce9N9S;=cz-?ks`>VC!S4crRBUJ?(g9Hv3V}W!lY{}5U#~fa7RwdG~ z?_}Qq_2GwHk@&N_L`YS^UlXg6E*g(Cd+2U}&^`30%cRmRUSkq*Rx2F^p(Vt@hAoZT ztQvixK*dB_3DGV{+ezF8k7$@)7*aYy96LXyCHuk7PAXn1UTR6hsi+DUFVwgqep2T! zhwe*nqbocp!(C_sSkJGXUSnnv4@TWoz3nOI=WR2RTeWy_8~iy7YSLjn8}nEe?jqs%%1=OP|l={$S;Uq&Pre+{$X>8q;1$GwQ$H$!?`f1ldJyz zuoEZ)o}SzQFaRCE^Gl>5!2zW14EW?31OPPSDvO+y3h~UJ$&4r06EmrJ=Zm+9$l%}* zsWcLkPym~-RLeF!7TG5tAqA1N@rnqkR#8%8q!02M&Ji{16JU@Kgfb7MB8n%ZeXMKH z)h@}t)Q36-F(+vcq{)?5F+C276-R`%=%|{<8_3^N2En)eKVXo-D!Pj_A>mHXcofI8 zIz{3h+$!xnAT5k}hHa@ruWbc&3ft6w(=#vJq(YMO3xqCih-wtZhTOH;8C{@!4oD1; z=Xe3U!FgCCiwxSAgjA~|;@;35607`Wm(Pd=r>UMaq*LCt8Pv~ego+k7j!cE5p2Ndl z(M=O_h)NB~W-(XO4W=(*?GFBz;0Mn_7!+>ZaQRowOqfZ{z)8=zGQFYF@~84mw2@ij zj5(q|RZElxmnx<6V|qso^L-=9XH{a%)&NzcOvAXPU?sLYc~n7z5qWWpCAtQ7LKC!pP=6f%ttQZCeA;e$>R;dEHsAks>Y zi)@6hWq58AF^QQRSky*yk{eF;WX32_rlu6#3{Cv=-yMhT8uj`aN(hpvglDHC#WRmBH||2>9YRxO}Its=okdeB&o1-oR?*Ho^$CT#zq$cZIFa~X$n`? z^ZYI^xR9${a$dAXD7WH>2%O@E2gTptWdj}ODfGpl?!zQ?CD#b`Q5C;^q z6{*T)GUY17lIj*`XdL}0m@Js2H$_xHH6&gr7GllelE3fKf8tVO(8Mv??zUkPh$9OO zR98loFfuh_jWU@|i-1S51#P{sR#K+i^H}9ITYjMoSag>fz-7sz=_mOa(o5=z)KPF5 zvw%VtZ(PEdItopK!Zf?fziOAw~>$3{sH*w4qc5p`ICJ=$sG_T?Kbt_r+Ko z{&E=PgDg_TzPw^2`7sh>t;Czx z8cZt}&{(<&s+N)>VBn|44U~KoxbbWZKSPnKguDG69>=Gz(TWR|m2oQJz=jafLs5^_ zV!|0^|I8aPcTt}8*0Y0$I)k(wgy>qssZ_F&!DTU(L}ER#5m@v$Yev)-aY8o~uiU0w zKe;@jMu@>=CTiH{dPAd;P+cX$WP1_f4pvkx*RoW{)JLrYlEc9AGA0qeM6y4}?|)T& z6n~%(04H!?WW4m9vL1mILw>LZDablrt5nR%)E~Wk<~Z}dg=TQhWHnhXz*+Q#j)0Dz zWD|g}4_cEPXHW}1_JK`JqNHJI$cHp4q1X#B3>Mg{TAHX7W7192|6mmWfFdFCy4 zYn?Ms*-(iDSyi?onco76K>#!$<=E@=(o;wWIVi`R4mz0FOC$GakjB%qshQbJB1kO5 zv6DFweFOWN_`}=lJx(DUaho~7T^P)w4C+PUE5|3eXVl7Qns$GGeORMX48IRM3JOXc zRGUHFAD5=B9CD##5^p1aVEh$Oqo9n|lEvq*Va2f_2HY?Gc3M)v1-_ycMhNyS%*da% zyi;qU5+*Q84n~%Pzs8>y-=fLmPQmJ`YI(3F^G}-XRHe}kyZ(tPKopDyHye4K3QRw{R>(`AIH7GXAHX0XcxXD z^GOGnLXaH#iTWk8u7O(N^{6$H_;opx7}P@)bZ0nRqLPxAEav6-9!kJe5hy|v)W_`$ z>4@V22m7ghg(6F;^l2jB_7B+s(qhua7$vt{Vi%&_VUbZWgqjE~?jqp=H$xPIol&euX3rur!Ml!}@Sox@GCQ2r@G*ZXf78q$e`3subj=Q8vaIWV^$TTp zv8B-xFeN!}c6d-jIYN3)7(vFh$d)#0D8wxntr0P5y`v$Ga3}YUbAizsbmEO@#_ZXBVLnrW{Ya)Q@ba`qJN(@;4iDquZ^Erc;@ufL_ z`n!A%H9|)78j9$D+=jLK+oq6mdFwE%YEDf-bPz7=})D$Qp_3j?_f|EIB*XH0VtsAX;A^CTolni3PD6J^mv6z%xIay-yof;@4`8e zby`2ybBC$tHV_KHA*g04c8uJmW#Dw!bOIz~1b9@E6ILT+UGOf>1@@wevqtVP?W7O* z_kzx+dM8{fp(cszu|bNv!Pc!V=2szBI^f?gv3{7-JT#VicalRbaE`jPKwyAiMt?H#P?Uv?0a0mTHV zmm*f=?0V@GmK5ts`kprO785!$n4<)uRDtloJCF!svcuZv?r)pAod3x{+RvxjFg*1E#%UlqtnY_MPo7~;?aS?m23t|H34sQ-x9 zJ<^Ekz77dZ9Hxl_E!L6mB9Iw4)WuR9!GKdn!;x4VX0|2j8iu7~Azz!$>7^I9t`A>2HaH(7&)<`Q~6T0#+tl)2P ztb&387kz=vsFc!g#R>d>|KtDvpa0|E|Lx!Z*MI*%|MTDe%YP%JP1)i9{`dd&U;f)_ zL&5b>{9-n%01a0+*dnzt1?b{z+uLAR(Kc$3vhC?xu*HVjUv3U$x)FGUzYLY=)zGAnyH zI5`V&dqfa6f4V;%6X6gAW2(zS8$}H%;gS=s^{5zX^yEpD3MF9zHYLi0GejkE3OFmU z7U}*7L`kSHhrmY0VoZWYaX<(hXC$=Y@hv^9>ByxO&dO0RuYvnbIZ4P75_>s*qIZNC z7o|gjP=O|__0U;ybnY6-;>)$fgbPSXK-Ir=N*t2PEGk@NDKDqQ0xaUx@=BYQ5dv@k zLCrhy;ZzA{)>+{o8yQl4oTWF zhgdG^ohk7F2s&ni90_#@QemtIDtLsoVo^ODbvRSGI14V35LE;U4>~k#X}IM=hse>v z;TA_GkBD)&Mzx6%QY@ryoL6+1y;IG-x1oF>#d=r`;V%v)EVoE=1(%>*Y~`@}ZwfaB z^~8+Q8zoj2jQissxB!AdrYSx?%@Zo$woYDs>01+Z7dE&5Jp0?)L=zYG&5;p z_gFGF4Dbne15QS+^>`Ze+-MDY7Qw%OmX*UZc;{2eIoHf ze~tNjmRn3;GfG3)oZ@gINT-Rg^j<*LI}$iW1DdkOA`Ag2#m2Nk5Z_63a!ghT&edH# zJ~m4wQ8?RZ5mYKcOjt%04{z#Oma(NYiW4G>j3r9Q34mBIpo4Ee#uwZDP`t(qD3gAA)uSgAnQAPRh}7GfLYSpU^6MpUKj6qJ!gQdQ7@IX__9pzk2%10!<+ z-$Bh%(;s9-(J+y&idVLr$|XmXKE`*_u7MQlAVaPB3QPIj7#$1&y|$Cdbw*8{c5m*L zYN#Gm85~1$3bOj6bvu+2nHiH98qr)Qg-8@_EUH$jIUlg%B8Q;+1k64%1j4ha=NA)0 zkTDL2gWb5IW!aFVLYQhqD%Yib0waIaFIDgmVju}|VUOGlw?xC`5bZUOjWNiY%m z6MdQNWHC8dd^%vfdr!ZoPd=xwLGKfX`WkjfQq-e7NXaMPA>V^-Rwi5{ncEHHxeW$i#Q%kdy{VCv^x{@rXh_H5|%Z!AsP1 z=yCY-CH{vo=oY$qXTG_@sFYr3klKB{!KkB9YP7d97w!)NQjVN(d0<&&k1!!*+A*aG&1r|Udy=52==hf8T9Y1)L!Id(0s&ILPA~Y~`^3@McVqUDMXi>{2Is5xH?l;}JK4q8@Q{z*W>7&)>p56D{yPu?UUuaW9=u*b{6{ zyAub?La_=|c{(E!eJZ%eAzAE=hjb%4LjwZr^^_H|PVerVx#R9gI7^%M{O;1Xpy)Y` zjNP5T1EkB+&!o!YFG45qjz;A>FwGm~3tiypF%|aiy`I1TZ^d$g`%9jY@5KfGU zbfT7pUZ}{@gl>VAOvipg*eIOG*ZAClgQ9mwG#bxr$*>}ZMQ-7^I>39`$1RdsuP)O? zTXT%5lYARzbar`<*z=$%gIiz>y|AYt1KaCeV=v2hcSr_znz0q^k2;lB3Wl8?wLr(L z^cfLTKnX|za2@;?8Uom?Po~7?mJ%S*8G$49q3*CJf<(fTq~~ zJYD~MJ|TZcJR8O7qg<3zqH4s!Zjb#f!TM(GsXRVwL1ve{Yt$QAB|UM6LyQgpCYAhEvD-`JVW`!CE}&0_e3U=oW^!e2c)0AZeNPk3W)!e&{epO*7-oJh{T&~~ zz_4=;Ft?hRQD2~)x{fa(j>!-y$_=vvf^M-U z^3(c_o-f*x^jGPBKt0*l`4^$LT%$BxBUjvbm`$>^J)1SV%STRrK(T_Z6uwCK9Nhpl z0XkHa;+X(>Kj2 ztGnfR(n<^>$I9fk3R>C=aC(y%CU&DJQzv)<%suKPop^1SWy279E0p*7_aOHI3xU+e zjU)>e%Hy@oDWZ|62644kRxwM5K|j65#vm_jf^)jfAPx&rrlpPXLA1k;pONpFIuh$A zEGZaQtO+5<`RVH=i?m`I=fZiU{db*@R2+os#CQ=@bEg|44Q`uo6*sIFlZv2GSw)XS z7YTR3$+R1R<^$!e(~GP;Qg@?`J>H{^h)OtN5u>BD7&a209@J&znU_ZOu0=cm7sg~S zs!bcEFM75~h-n57_3}4Z+EXo}Uw|0|w5i~dSYc$6CprO^6DaUZ7bc0y zN^e?luFNU$pRni9bmsmZtLG3AWadPnfF3n%iS(QX0T6Z0AKr&xkMI}jnITPCrR`%i zz(*~IGJxJ@jic+pRfcYmUIddKT3s!_t_kAvqsN|b00cz1He#@$f(SAm7eLg)R0fSu zyx#d2VZt?$uLws8j$|R^HCQ+ixx&Vx(#HJ8!W@vNtKRd+{#}wJ!cWRCq?+gKB}h5> zo8Aayx-lG$qe-zVBqLS4rpI9PPv?|@=w~fdno!mxaPx{{pJT#;5;+hL;Olm7pB4xs zaU2EiiEuMMCPWY!y1~k!UT=hcv1nbP;4ND10(_Y)3`qH4W;D-_3L~QU3~=k`2gMh# zToA{kxjl^!L`4+a8@odiMQ#QRH8`C!6Q7a^j3vIDW9KDXTH6ffk33R7)7O9x6cp>k zlBRDG(wB!GSZ;~o)=*!VNy3JJDaFmtJkEERIn=vN>|s#~%_j)HMh>x|xYwl0_#f)4 zrp3x%#ST8^5D*^%Ai(zFxCZ+ayGN*%^~M)aTM@GVoH%V?)s`|PkHXfE>WDX_Fv_+C z{u_&m#XJ8davG!tkhV6!#+M8UO&YpLi^<_CF+y3yFz_5dc2I~w=FP{ORNaZ)A1tob zr22_TO<&YF) zssb2IfE(vBp_E3OiE#f~3=^)c^0-dqB5_q5y?hoXKwD2m+IW$$mUWWi1~H#zg`o_k z9Ig@(CMVOtB+|^4UgMFfGWY$v2aM*>07qZ=g8eA4S68r4Bi2t$qYSE+E54H&vXwgUu3u@jmZwmV>4oJ+)j z_S|9K)JDWI;sD9&vaF`2jhgz9O2MT>JS3SUz#5mNKk_}<9k4y6IYjxAEv-o*d)^LN zClJso_-F*6>VX3u8ZS%YM(yPr`$Yd+qBz42h z@Q0cjPM_w%s&1N*hav8bbcUY@izL)}n4#s`G(CB$NLeZVe-zRHtjQ5Z6%s zoNvwQE~Z;cM^hSi#1$wj71rpj5iNyWI}wK_k->p*FDEITC{vF^fg@L@>~IcWNH0+( zzCoEgH+O_DjWMBw&_r!;)q>qPUjkKZCnaW8(^KFADy3FFd&rDC%T57ZEG-rM|HrIn zwNXbwSUu*>Lgs^El8w+7c_1~Tz81YPT!tf!qn^N z5)r4?ZP$*$a#H-|_OVHvZf`-vn1BxQpc+mmaR{#>$C-MTf4;J=eL_-01ZCXWp=VwD zM5VEA1|<9J(wEcLYucXqrc<*eofiw2)!=97SfN+As*Q>A()aPwkVASBWH-Wf(dgXV zn!GiS{Akg$%EPlfVtt6LK?(6xGyl728b(TOV*ZLfI}~(+;)u3*W}oKq;L|V;95InU zW}ja!Su^e}cZv3$rP_pJZv&O>V_QeNHG*#Dr>UB;T9HsDy#AkK4Txmc?%F6}0}U%z z`In>N&&(!nYw*WJd-9r|!qk={y8SMF@;iRxfP+)kB-Wi_PF^*Ll zlV*z`{0r$By~mRRgnp13g~~|az4C5P5!MxwX!Q~}!@4{IvORI7;)@oL5X%Y96%MbI z-#QUUXFw8TttFy|8#3U-zOLHUA{E8@wWwI%LtscuNj{(U^yn#f{o8h5ENsO(Vmb(z zv94jX2vs?yWxIt@v<-ys_?m94>wpN9lEQ}Z!b)IOn^=^SL0feOKi#}!jrS;tU-pqw!AbjZ7p?FGzsx|%|Xd<0_^{! z@=6?|r^2TjBT2v&r33&?#Ii)gd}0VM{OIhxj@s&)n4xg(SrMXBv7XuqFh-^9leCAf zQCe})bS$}W{7~t-03eEUhH`qsI9-{#&McJ1CJJq3-&iJ%(iKT1VJ#`Jl;2M)dh^FsLsG)C0m)1V1N!|Bp$k4kcxv74iw9V>RIwH_TRpaEF# z2^fL2$!%a{R8uI$>n`hT{S~SqVK4;s8c!O>JCo?B;z-DY7VV0r{3LLHstVL{h@4x} znal@Iy^<_Y0X>5@L}7?MgN9LaJ&wVj4P$LZX$hGM)6hBIm@MN# z9Q&Sxb|WoTuYNEfAXxOG559n_q4qj+)-_VpY!5%_34A3Mdiy5PAofI8ew#4pAb;%WhO~!4nQ(*t!Khg(r`Nm4;czT=vfK- zi}tHaL)9hIGrO})8o99g8vY-L{m4&%8XUeVA15xn{WJ~nY0P)2_ zklJBF!^w1w+@+XCZIJ=xMQB6_rnY*$v&6WDTXL5K_n_q_3v0CpcdI`|wt6`R$pjI{ z;W@P|n$N1xySp|$7C<`1;QroMiW_Xj-O0#uCPo_`qYen`l7D!BXH_+ZMCPROHHX=h%?of z_Cc|HL*0zc>JhqU_%zZGb&2z(DT7=lZN{JcYO#J|Yy8`@?=gNfj4ndPJaeMfLgVpd z^}0@85eCd-u_@b-f{aR*0%`@-`OmRyh@&wUs&-$b=P#m>F_mo3lF$(Bc%oa6|HW5h zx2R3@Bgq++m?9X3$}_LoI74B+4crX-EhFA)}%0z{ROoRf6}x;Nra^*?aoV91c| zXt4*9Jc~lc(O9HDr+Etk4}Kl&ByOgm?A&&OmQ-0JHekYtq@h|9nR_}P+%o_aRGJ{T ze2>Bt>I4do2}9GDYwb)+1)%CXY8-u=WON4vPfH zR8Lj&!%7_|Wql1-AUGJ&8Raj!bWsk;^_}9+c!$(3n7l8Cf6Vb}w>g!bck;|H~rQ^ z+QcCkM`E?g;rThKE8Z~}_3}7CZ&Ai5p#La?<~cp)(48_FuFw=v{9fHd`u3knK()~@ zkOU^~K;7vjJ>Zngl`0-1(jPT2C2#1CmXI<@OzBpu>=zwW&++)8&G#r^Csr@t6O2QD zfLk~?hT;A|=V7obVJ8Zh7^Lq(EL{m3dUa$;fVj%npuZaiH5S|$jMi|mWFDS$Rl$FZ z!9@krNj>FIHhSB>8?Nw7NGC1)&m^RT*iHyK+#!HqAz%Q_Q|hFknbnXtrBuZ%e^SAS z7C6=4`ma)hu>~?D^vtFmUqi@~gw*^R#h}1J^B>9}Q7shWXMcqQgNba6O8!F-drH}O z6x1^YD?yERulS&g?#3x$#7Er)5)xGY5-a+m zdc9Ql&n1Dpj4KS@8{vglr)Z3cpp>jsLCFD{B~atFA$kK_qtp@-ogR-iy7VF(P5x*c zcn)x4aQKBK`?FXaWf*TTus9w-c`w)eo>7RSH<+F$-Wt!5!7L|5)k_R&5jILO=h8g9 zL?KJAeRHeqs>~B+&8^Lktc}7#tNfg}QI3haHXhCIiPmi*>ul#UO9xVKhlpxT3O3!T){~1IB10szdzIdqJ@{$g!Ya zy7|RoCGB{sj`U)kIEMalm(hbIdx4u(TD*nQGovMyqSh>%kbCTrxS~yvYKe; zZbnEZncj4a%TRow)1N3Xn|=Tc`ah$$JN;y0BMgDia)yX9NzYXc;ZtnLqkJniXek%K z^Z3`POqYY?MBezf!-vhkkE)HzyL-#PCDj@qkZtYOBG3nSNtNfwECo4{IDpEdpq?9g z%&E}DK?2n-Szd|)tp(HroC-BAdO^p7w-mR*f@3v-K~T`l-4lQ@3=&W%r3c8dg&AZZ zAjlwef#7BGkgHDWoah1)kCdrvp70rv1ssE^4=vYYe6ad2sg~GdhJgH>4iEc`+PAi z07uZ*g1k~@07}$iWJxb^oo)zlHo$rfSxXkro)Z*m7@bKgY@)YEVBm;n|0pR99_RuA z#kGL@M6yK}=nL>U)Jp)l37wr3(BTgc$fPz1boG%AOxZbqw5(P2WdtG2AApVh{kL|!j{5^GK(ieD8qnUM)y%y!lBU*`6c&9er=+DO z=r^l4!AU3N$ok+^NIKOV+jDp6_GqwUMCtkqy7Qk(IvGme^EWgn&!kgZ{sbaJNisZ6 zkA4Vfs#!m7uQx4Rp1ls&5^>5iD#O$N(dwAEaAI@!>6ekx z`X^l$V0JPBTMqnbYkH3*cN@t-Kv z10vl5L#KQij6(5PQOx=*z#a$ILkt3K5loI_raYAhb2${Ef~bj4gH*{Hc)}rlS|mr9 zmT2V*y1dF)?;g_0t0S$&On^soYGYm?0}-_5usJaCe)0OSI1EfPgHCZiACgwiFht6u zyqZr)Ibh7bu;gSfpuK&8(8~fU%J3GNqE@AS@P6r-ECJ>2Q{19O2jt~)ln>>T_Sl}k ze@p?di{~Q+Wc+o{U@xBuwM|P~jd5Ia4mvc@N1GVry?~er7)X>uj~w4aNX5S$?I!~v z^kh}S)_&q6Ut=It8%ycx5+cz)(cN*2{F@(4DE~I$tYfn2&cRQtX&@baCGLW~%G^N~ z|4QE{vQo=bQ5i<>b*MO#E70=Qj5?t?7S{^PREIv8!_hMjERX?ldNgps3_F46@De#! zN25+4Xo4gRM>Z{HM3sir_(=>4G2DcePBVAxZ6E|Cr@;HJf#;ubD3Hd!X3{x_GX}}B zc^(}*z<=dM?+6$hIKY0AK#)ZZ&Yd7Yd+ouR$ABV~P3D6&YsDQZMYb!HO+w+J00yj&>jz;}DZo>PYP9!2@VNXn%od>4sk*_xPhW!=V0raZB;Vl&WI7#;+{sT%RzVYJu8lDIFv7Ek ziK!nlv9~S19fJvvh?66@;2()K&kcj7gTO^;T_JEYG_4oV{5^~HoPpxVCsK*kQb5bm zhLJ~_h;iJymWp-yXZkI|MdXSumw-?$uBHrx^TP#Dc$xTPa+WESbh}ijaOXvlU8p{dV%{U2vd=4+Qg{jFUOuNsiIbP*qCXSA&Ds8j0x6S zO2H7qxe=!lxIiJ}sP$3HQ;^6&XyK5`gn)3$3iB!i)+y)>XU1Z*8X8O5-yb$q%h3c6 z#|aV}j80JLuwv58Us_c{2+B_b`{ZjvHbxQc{swy&&js?kDM3(rRT1~t<3(Uh)+=B$ zwuJX55@qD6xJp8BA&>#-j|@_ck|j62 zXe*+t`A`_U@FO`N+7@ac=%FuF~zI9P-K%YPvbKRohizuncdC- zO6djTK?gO4-K@*Z9OXeRxu?7j(_|*Gt4rv54;emKPs9e%k%6N&PiAvahV`Vlt9lFt z<{ZFqX^L^+4|LoVz@S8Q9MCVl)K1H&x`%X1q+LvNa98_K?I0Z{*VvsCs ze|>#vkihViLHLDc>VBC)s%yG90&MI{)|z^Q3{a5(VqjsPGdSws=K@1Z1>=}F=7-U}= z8JWh&K|5e0igl+Pkyh~Hh+*^a5xX>rss+&yb0tIs+T54FNa?<2p;;%zpn5(j%20rP zl`Ja&jQT+FczvZ9YH=o}x+#Xdp9_DInh;uBPwp{X;WmvRG$)ilJYnfUP(vn+h|Ult20d3HkY`PH zQ5|iXCzBWQtUM!I_#>Afh&+N2gp>d-6?N%=&W0u*6lnyNBpUj|IgNP)^lZ9`@@x#!&41qdXVuf~&xeeFia{x$P zS5ku+YBp5Cm6=dfK3qK+;}adk6z=)!bHNkBiiw#R%pF*j?59@-k_knvvVozS)2rZQ zLLYHQ+~M5b$Q`@#Df6Q3m6B}ELS4yD5ICl2BncbxbB?t1k*X(QEIcIpEr z1BybDCZV8&5ZHwd;V;`mt(YJU9`JfMoc_9OE_~UY`^%P+g6SQhSwMx1g z1EpEQExISUJOqE#a{2#hT}%)dRb|*CO@^DEeCr}v>?EmU>y3-ai$(a5zLP;)Fvz!Iw{XBHcRQn*>vu zaP+fB7!q+(^&;$~O`){`$u3wy0MAL(l{v!`{Cogf3a#E#$v`4}l}-mpPiF>U5V zDQFwsIB5+n?`3%)93!E@dWmGAmmVhHfliX?5zh2U9_>&D-?W*Ix=QlVm0p3As8aI? zAvr==J_th{s{7uhOxsK~;e!w=V3nv+QqJoSS_$hnOUp3#LZyn=a?CW0*i{DTgE%{i zL&b8ii_r-&M!LCa%HXR0Q&8v+oqtX21H_nCM>o0j@-J-^Q$LDwB*+_qb9?e{O9@K8 zmy#}c(E8r_{EBSP$5-M!c4;oGmNQ>?jipvtf5(<|uG5g%LOP&yvMRdPRF-;a!PAl( zb3s}hMwl=h_^iw^($Nn`%m>m9DW9~g9e4M$<(v(bh?46$@_}4SP>;iIa#|@iO=cmz z{d|yOBBZ@s57v({{NB{11hkq#z(QEYUNW$J&BhI4L6yGQ#dxxbF^!PTOhEG}y%k}< zS?`7hBbZjN=hp(7^#df(d7yZ~pI_(@KG;8^yUs}Wlv5X;Pn$MxXPU?3rj^qSdf40G z;hgYkpc;&HXPXDAb*ROj529k7Hl5|(lE;fm>XYuJyVpm7G>U=C73wP5v$R&FTqUb$ zr1n8{R`CY$k&K5jz^rPAB{2lWkg7s;`{|e+(E^m~C*5CmA#=U!cF1}JVb;V|bAuF9 z*xXaxdvrs$3gNSAHL_PVsK-3(L6CNeD0|vRtF3-v3ATH6oSkze9neU#bE%bEP2gQm zLvRqG89c!pv5s-};Ag;K*C;z>#+BS>VYc4v-XHW}_za?rn4+Gto_}gqc`(=y!)!`Z zPTVxoO}Jdm^2IP40B&cT2jcIFh@Ms3pLVa3#_1g@xg1_Q@s-h{k`IGyk~qgj4z6Yu z*h2eRlnuJK`IF(eXDyD|5-RYHi1&nB5`Gq9_di=s*-(clxn7;KC)W_tXw_*-wI(ADO4PIqt{GTb zU3wo}3+)#=Y!XkmLE4K3$jIxVHTT#;>zwrz*#LCV8SyyPz%%wXZ?M#4*;hjAA(64p z`e|rQ%_w5;5_0FL9b65q4Z$jB{xr4*p%*cFtE!dQZ%x7su_{zIB@PNUn6JHv^m5(b zb|G^UTlYU+2sIQpNHI=qPjTL_NdQf3qFcVft00bQ84w2rQKLFWd z1);avvtusQGu<+l5e9dD)7c0K9wGdY#-85O09%t~|44w%1e%8$=*=HJyHxe)i8dmN zdd{P59!`0Q5n~drht~H}GSc14)O=cmz{d|yOH{P3LU)=tEp5hu>cP%==lwX|1}uKv_%SieyK6Px z9^31S#5O@$q^oGITJnKS`b~gv^jUX5ny@FY>BZDoOy>yXn8T&u3 zXaiUGRB|92?D+MHHeuR76L5p-aO_BLw>8Q<6Kw<+^^}1Ibj6UtQ9cZ~wF_`B-viwY zKer@skdP$^t;7=!bQSFh$8a|;!CO0)q|-}wt}W+x=;d;JjqH`xqL&M=F}-95rsFFI zqrHl3q5UM_X66948ge9U)oGoZ2?iFV-5pErX}84uB;X!Yq8zlL6H#(KfMQRsDXGU{ zH$iO@Vj0Xrdi(hx#cl>XSUFK zXw1zJI>SPL9diqb9|c27)$HOajgGL%+36;6PpaSTYK&rwC_^PZJzhzm>c+G z!2SV)?_=(4%t}->)X%!8iYMe|=_-o(IOYc9?zsBirkEO6$X~*4flXH7Dx^2*ifN{{ z0_+96r?}U#Lg;zeZHma_u$u)Oj!O3KU3;A-6)S|Fh25G?pS7VL^Ruv<3Wy`#y&VKn z+f}-Itvrjld1I(6bN>m7gvoSIC3%au&Vf+QW1bUuGYbLOo;(oEOgTtl_NL$f5#>%N z8RlUC4UiO*p9~HRu7|xGsB-ECve_Y_rh_8xHglB6l|dFQ*<&9Ri-y^Op+!7h*+dlb zOuD9W`1_uIZ5LBh7W2h&iIIMmd}^Hrpn1YIJ`|&#a4lfTSwz;?g7dlJtHd!r-y6_r2b+@zAnMF%_3-ufWOS9Nu zcI*JJ)HC1K0`cL*XXOr3?gG_@b7$!vJBR>}@()>V3+1cYRoV?5FXz6fNRWCI{jxi< z#P*=RNo^&1HKv8;_QO$PBh?5EEOzmDZ&#Z0ZqzbjQKRueJRXMPjJ-M`O7DWSlBb2@ zgj+q?hAS`hE0I(*UdH6I87&7sH)F#_k>%MA6Mc9~nAi{A^en6=&%|#xZZo=~u{jr~ z+Fe}IQ%$+8pSKyP?xT*UivwZy9#O%?m8>pbaJtnh3cC^t%XXC%j``y>pQLoN2T6SdOPbIHfEv!|yFNt3mo8{OB(n($Qk1O7dt} z2Fjm>;jB-I41{V#e69u-s`~(=AFVXc`)Tw|r!rvmSliH|@4N<~P<y@q)m&|Gksm8tsZcz ziVr2uMYpO#8hTKu9|5S*w2Wu0B0UIe*#x^OQ|GUoZD;$;y(h1fP9vIa|*70lTY9I^i%@X*8+_xf#e_c4-vqN4bg9PXA$l)V-H6 zc6wCe7eb0?oBK;D`899}iip3&)s>OSV-DxN>^mt0kGdT{?`Nw^>S+)Dr>ET7T~cX( z6k3D9bW*WCk}}nD3<;gZLY3-1Gz=fOIsr=lC(pg&aXd7@MWRD^ zZ&lWD{z~n%8jwQs<5-nqt|QljLRt%Y8vVv; z&uc>p;m;a7Y?1QRaUgp+ze=+qs@0BIlKpV5fq26!F$^AlmDWmm6W2!YvZ1FQ_gqts z`FCx(-|OQ*^=io))n{p>Wk()ok*tXiSiW_dzmnbDMm_9hoWGoP``OqbvyVPt^t$Z_ zmCDmNyZhln<>NS;r@kGt*L%cun?|GhG|pygDsgPTp07~9gtx(?cHhMq`YX-n(e=97q7Xeq*8&*Cgajm<;~RVF?)D)xqBqfX_w$8bBV>tE>;X!8 zikIyajqWwxTh~(*s#~}cB$o5ti$+iEx(K9Edm3G@n?MTDkHc$L^gDt*DC4-H=XhWT z4pRNDonSTD%iR>hABNYwk{2O+J-~YEhOk!ZE!pnl>+p^q8pmF#a`2F=v{t&U!(Nv3 z)YEa1GstFVgCo=<-Ps4KfmjJP?!A#bm zxoZS@H_suww<_x>e>?L*mb(mr*GBb_dcW49ocR!JhX+J>_SEZo^adPBE~V*4^yG#H zvfIxWdgp5krw58i_p;qlyl$pwbT7g7tF`o`(B0yfnAzqzp6h1B+yl}m9&F5T&hsLW zLiOW#n*iF8?cS1@YkC^}%ZaboQwV<;Z~wSSPEYo_rl-S%zpSNBd30MVa-kMmFe?b?HeV_+iMcdkiS! zvcIGr_bGhDT3}L%pJK+KtYC`vwD%sTSG7v@X~?Z5kZp1z;mIq}PeSf@jw3>}waBSb ze_GvMH#rsJZ<;_R+r5~ow<+rof2DbGdQ~mgDgHwAvw&N#r#h9u!F;#1B#r3vfVICh^cyE`tm-MWKMT9l{(yiHTz08cvJIhas@Zg+ko`35W^IF4#~eJSCA5|HCbgC1 z)dUsF7Yh`VbWDMho(*)bR;^Ke7Is@UQ!xQ6XiVx?vYQJjhrRASDQDe&Hh9SH z3Xsm-@PzHW6rmDpEF-B@uUioc+0T|DymRM{j~}RCR%tZqL%TEz^-JU%JNvg#UTH2c zsSGTn)Wcslm{jubh2TQzIU%^WHl~uj+xbuQmnVA5#6zQLrD z{v-_Ns?@KGPl8A9wt4zIVl{S+{^=a6)T~>c3h{RhB=b&=uy-cL z7}T#cFW#^aZLG5>L=W+J7;WHfgfHZ1PLvw2nNFn=ibk12j!ageKu(u~KJ!mW# z2R`3UA^c%z{_gH{?8!Da_f)bCfo+OvXh>neP-+%<%^ve2ZrQNFD1DReJp zDJJn$5wU-};ftPX!_+mZ`yhRQqwMU<<7oZE&5k;i1=KU|o2c|R2UAad*?dwCz5Q(P zwB6RvKx|u)P^mnvk9Ru~3YAameKqTu}hHq68JvH(^IId?mW*ub*RKg$C$UogC&`9{am!y(^S|GPpIThOPT0x!z zc8J48FhKJ#8F_9xTOh;)bMF;tx|X2zHPD{`%G9X)#G*?XY7;dQWKz>-M~d zn5CzDF*`xJeIziV%K`Zr)u-a4ol@0ZbC0)6xI{(~^-$Ui`Il61WC0D@LiziLY>1)Z0-xaDRu zw<9jfgev*u_8(|i^4;_?v@83yycaps&E~sLwZVVkm0d<@wJOBI>CZPjL+=y10Tu2u zw7y#V_6>%U8NB!O$Dy0U{^EqYpT#xv|JUWVYUkfPZor!k*_z&{$GwvM$s+Z4YQ0}? zEaL%tAxcJZ`6ifU$MZYO)AJ2|eyX8>obX1;%NKR#2jue**Z$NyH)IH|b^Rmtyr}Sv zxO{+m13W7MBbZ~)x?U9dCF+s<-#vS`z~2+UO2N6L@3rEVUeYmj1Z5z05pPpu$D_U` zT=%GVA!MVNUlZAh{41999`$Z7rME3qXIZx-KcYW*Me3PN1ir)825MsMXU&VcN4CFL zp|dSK9U<)U8)ot4{VO4qM%$9j#Bk;o`Gawh!rs-+AGa^wIUd4`GJfiXH!OJm;XeI1MW@i&J5t)7 zA3Qt(?Y!CanW$$$2kA0@K{)X7oqfzmJ*xn|kv5IFydR(W(vHP9>^jd>d>k8JN>JhLc?xd z=g>PVX-Ti;*r!7`G`4ra54kS z+S8lFdQoogkI=!{Ojr^-9Xj00OWqIX}usov5UVcYw68m-A@`is)?$2;xw7o~kk z1_rs|w!WDGBmpF^c|C+)sVqS|do9UW)BOHT$>A916##q9X0-l-}a}b+!wXKZ* zzMqD-4BM>00XUEPwKSNA2P&M6@_3Z!U&|9*bIrPx3zN!X1M9WZd8QY+lcJ*RuEz zt9HRI=>iB6no2~mN2bAxa5%>*lAkUPQ}Mh+E1@`R#gcMC!TI zvYF_0v;SkAL@ooSudC!+>NV2a{qVaXNB2(Go%rb8AZj80S&K#dCoY~{U2zW>-! zX94@w$)oA}%9+7HIZ-XMZ=^wd4C0a^{FMnLIdDv1?{R2402VFL_-C?qzQP?^qg*Y>GMeU4^^!1^s6mZo8)BKX>Mu7E%_#u zajZ$Fp2h}zi;#)4L3cCfVJmSj_>btJp5r;v={s|h||nQ}qU zr|I|eC$}ez6n&Hz`a*h3`{RQpKd(4Cn6=aCTMT@<+lmKMZcR*{AN@Kn`DgVMa;Aua zz7v3#C_FhLO9IAoHUc3{DA$^og*Z7F2$WTJsxQnkn%ojUH3J_x#hh&YMQ6 z6S?%Qesv~jl;-f38W#1OHK*?heH>YRxoJbMe*2ppjYh}Hb1J{Q0jr)$?;9J@Xy* z?bcaSD+`2sD>!xy_Y9&hpbT#k?>WN3fA0@(7LaRz+Iw_=dJnG*4*UX&**Nq|IOcog z`?*;k^sUIporJGQP}3OQ&`Y{lPT15X2L>u-1$Hc_ZUM~}XveKH2ZD~(*tWSbI;G8R zP`_eo4C*hSYVJ|*=4G8pG$3pnf!P8=?-BcV;Jo#SufX%}QSCOMdg;CbZ!?I$0C2lU zyxZRyiC{Q?HQN4=X(_DPweZj%$e1_HfB zHgH(Sn)klnGRzAC*f{hn7~p&4yHohg8Flvj5&(N;V8vEiUhIZ5Wya-t+-M@eHa2~W z>$`W{?f_F~U@qa5ma_(6=p&VG5+7;9I)^uD=tWrM9lCi+((A%@B7PCvwjTQ>4C_7m z-Kn6yxOoX$XpnyaTzHRqI`R96vG1T!v(2-`ULD=_R^^fNx{j(bHw-6NX=-~0Sd#P{f$<&gUyx463_9lW+2Aol{2X{GuKmg(ME zBdL4hdyVW*&j59*&@oqQC^>#RP!N?_S z;Yv1Rv1oAr?DwAqBWzB0VyWJcTtuQ89Bi-YhHAdY9yZ-#?+kJ;U{UW$i#w0h`~5bP0K9(0>h9dy9cjcf5V@rk>%L0`iMi^@cZP&@`Z~SD;YqxnBW8-8*!5 zJ#%l|_jt3F?C$3q;_N1!-hAw!oa=dwae0D8Zs{F!ZKVQQ(!;d#cc$uR<{^)}^nEW|vE#2S!M3-M`2Z2*08A#Vs#g5LL zOco|I{L=m9u)F=8W%Ox#VI>`SBmX8$Ffq1chOZMmo%(x!>MOxan%p6n$8H^&9tfs> zHXPz0Cc6`UegF8I6J{HjlL+(#GtsYGAIO}}wU=g!WV-ghlws-`UazAkn5hNn+CcDh zu06qTKfk*6p5P?8okB)snAKhalk9+C9>JRvHV96V+XxOToo1{eN@p0j-3fnf4BX?h zX0j=uezPIYqs+y?O{d=5i`Q%&dNH|YFSNHdpnmL!lQSufBaZ|@Z+0uwsrMH7_5B;S zvdVQ_I6mF&J-syV3ErLXO7P7S{=&%z)NgB%Hw5$k?QD^663paJK>a{$jDC1$>IRX> zF1eTCdrn%54kJppC3thf+M+ed@XZq@I*BOVOw;8P&gA{U32Sumx(r)RdOGyp=NV4= zsU6mov7>Z->cK2;-ZuKhI1$ICi9NvZ{ooBs%u*vArIyI%A7V<5T?$cu%tCTyl{&XwC*w9LPvi=X^ zaK?~5Ti}w;NEEAH>P;xXomOmhQu4`m))XV&TN}qy2_87WrB^V8%kx;*==}k+XHw-G`Aki_rhl4f1LIH%H7w7|!PU*n|8^ghI-!jb zZjUxn@<+7c@ExZ*&}OCpXD8Ug{--C1+y}yF62Y}}bb6MJ%7+2_lxXzL9>E#rU#QrIjUoHr0I7^Gl zQ(0|PK9yA-A_@2-Ehal|{FFB9#-CD2_b{MQX5?&ypG$+z3PA7l<&d{XDb=Lc2tRl9 z)&TSty}#~@F1@Up^jhKPj^G-A-XWN^ccDtE5q>VTSpn!R+FsoiJN;pHp>b8I9c@*W zZqY_{RpWV!O3K#(H)K+|Im<@nv$JG({?owj{4BfB?%7!~=N$>` zrkY6J;#kt6<;FWIpPePSXv7U!f!*dTTWI&}EZGen&>k~LK9|d`k@xH@*)JH-9w+=< zul!m7dQ0yKVj~*Wf|1SLTj9tvDWHxO(I_jh+tAxWyC+ogKB+s+(|aK^NZ!b5qweVLb*x&zZ*7L!GB5kxBK7-M9@O(( zWxqZI1Z-^&qi>%_Vn^$~q2siUKEgy%Im<`nXhZL|%?6a{ zDnaWJ9TbNyj`x5)E5cNfLDSLj*@;vw``;2Nsux~LXjA41ROu7l5GX1np69i1u(Zd@ zN&LA2^75_cv$mA&?y;DL`ZFO3`(mrLql7kPM{_h^lW|}VG*M4XJDO-)(&KkdwqaGp z8({|>{!kAT4BdySb?-dl$qRx<)lEk!w7~EC(1huFpzKEHMq1@gp|y}j{LA!7R(XWm zp|89w9!f%Xw6k`;r+onE>}jX5e~b1|KlGKJUSIjl=NG(#kFV6Tetz!$lGGt^xk~%) z4p!Q4o;&-}B5904yGG_2c;M|`wC6Q}-4X8Zj{! z9Gu>PLHENuz$b;etR@Gm6kWIjL!NHk0ox_qUTi<~QSCnPN*=iXxca5 zy_$B{aHpn z5|8i5=Wv$^x2|Gd1gQZJxxIezI5m&^=^}o3gMpbay4OFyp!5cFWVtYY}%ZaG*l&(NYE2X5kGaj+BPEeD1jxGDcAqvMcG`Dgp~3;IWHq!PH! zo)>|E@w;OGLfndi;J65>lH%xDk`FXSk2dnuM_l~BJ&=QGhB!h-HXs^7rj7vz7!-BG zAz*v=lUHb+_UYLkbkhc=T~6@;d%*EVv&v>$7AYk_=cM{l1PQa-9hCo8_Bz{ z-(SBxB>9Efk%#E?4L`HH22`Av*5B~8FMxA?va)~OuoR!4_ z>#2C`jj;cPjZefo;~{RjSg+5J!5|NA6UyXaE6Q6Q3|nwl2i#@zrZGZ=zk!8Q3MS~u zC5KC~LegJ+boaq#e}jka7OYI|#qdjAfuVimVCzzpMtV(#Nn(S|AtjNxJ&n?Mp3jRj zjb!oTgO2hWxh|vsFX@fli&2_@ji2m@?ml?;HBS&NAbOA4JM zHwkCO8QKNf^_%^9$PjUOC4D<2a9*CYkC;PF*_bNgUpIYzmv5Ke$&DCZlHXa=ud$iJ`-$thh+ z0%(klX-msG{}ORk(h`7&e4C<%b|jdwV&z($qD>;$< z5dyQdi#(oOGMSp2DbzPzroH@Fg1`Iyd#T~Le@Gqa6}-QkWxz4j#oNTA8k{UG4o1b) zy_=KJ9S3jgof%>m<-qf{)*bAmcgKOH`*+3u*Tb7wV$Zs1AbY>x{LcsRxTM!O!W|1= zv>SeZiO=#kJnHxSymL6-Lu{>f{FtEw+u!d95RV*DJXZaiw%v&g z#?)ACzOX3;MndbAfk$B%sHlx+xaDEJK0^XyEU-E}?hU9#oeT1o1H%y9)Bu0KoT#hg+Pd6uxSaLzerk<$h2;7koe_gV-la^POq`)nB2F6?xrUMmuS{LE;Zzqhvb4VHK z)u&+Pn&hNB@slK_eX!kJ@B-YoRm}?^N8-1Cd@$buTq{>FFVaqGhHQj`s zP1Fs!H$|XPu$P`!a1@j^Xx&oymXU15xY)r1gO1x8(mjK&+m84 z4Rxt+j&bxb+f(1Gdyx1yZ!E*|s~^;5cp8UjLc@1I{0LWXM20&y=#}u6pKvhbHc!$k zhJxJG#HdfnSU>^*4-)jBlA2tojDUinBc}@P&j&$Ky10883E$w2ftsf;|E|guaTz;d z?wq|kMd&RUeR@A!V)~AIaWPNHr<|=vgqDj{+@8!`5&o%&VzGj z3KLUalqa4IqPq$XKYx{2{05RiLtzY+k8*G)A>n0<7g8Bu61bjQkYvi5STO3K-8bA7 zBR?}StPj5!)1zK7c%#ppUtFroDifoT0ebNlXZr-hOVH{$F4Ovuz+*RPrSa=oVU|cR z1YxTTSX?=8rg>oI?Fl0M_1#6a8*040|1ISv_cul7{oQk12I*S?*pf~K2s9H9Ef0q{T7D14-P)!o}m4?a_O+?Spp@Ur>T@H5Rd-fB!|ow-Of<8=xP~nHyUB zLG_ssMiVq2KeO0wrDi8?LBicN4;JC8)V3?%5}smgUMR;^fgH&u^KOa@F8D?Vh2Q`& zrw@y+GHiQY&KV5i=TURAG%}S8g1uS7q(0;bx@97He}@c-ZY-qGM89rjs9<7a7&#+S zr6!j?_-tT9bJ8~|-wcQ_13>fsjSaihXaYqkt!{kL$aMawcxW;glX-^ut9XixPgP-@i)jMZ&=e(CAS%C$PwS?_om z7RRJUrTiOf&650Hi{=fvGdPcF0D~`%tFmm)<^Z<`Z;0RBlXo{fT6FL9Z%;V$0gMTK z&|cOsreuB{bqb#RtyF|=8!&r1P=xVl;Rz*MUWCnKV5a|uo0lL|?mnP5;~YXX7M(C8 z^YKDEhen2doLeTKpIuc1di1e!J?O3xB2e)xsZo$Z6a>HLmn+mnHpIk5F90rwksn&^ zH1A@bTwah1_x(?c3*cTrc7fKbF_N6w zMLTNU-D7=LYiF+vCJ!4q-rvJ&2kvUIpRE`QAj|@5{e||RE_+9ZDTsov(u{fghMO$l z%$>8h;THPMGjy|@>puj#(gM zF%g|kN0^Lw!W4W@s1Vrh|PJl4AK{5jlP-Kunf~3;zGbi+xp5A?ids{ zXYpw!R}ZAon(Ll3p|5yngoCvpyu)xrhWFe9Mn0Zk^7|=E@!qD2Jl}cyAhA`q`0IDS zflXgPl?;$5;ZXq_+>4F$8evq4_rL!9++Y4h!{hZEu#9TiuLnqJy}6hkfEEz-H?>#Blgc=oZwtukTHu^?Mvs%W z58kGnWylWYOUTCcGcob+m8P~gjS<_&bQm3^odrjt+)Z}Atv0pRf-K;DvkEWN3~6S!zT{#hWo?aG3LyIY&g6DQ9Ywe6~~ zZ?q&zxM$}rHKqR`R3>F(En5g6Otg9blXXem2isi*DR;LvnUrfu9px%o=M0gh?6BSW zPRdp7WC=4{^uM%dEAN(jiX+rcB}d?`=AHZznH~S3>hu1cg8OTdLo&dqBU=htufnF2 zd2dzh1}H!}hSCsvlY)!H@1!nDy62rt(t#jTA3@@2br52vr0P<2N^p_;1I6{tJz6m#_3D+46p!!(6W6lNIrm- zxUQ~3ODZ&yu~pcW{iZEZ`foJl`r}*ge@}UnocY3ngu9Pq8}{8$wW|_us7RFH8x9Gh z!pkV~Elk8`oOQDe+k@U2)F9#Rl3ObbBmM()1pJ8*9Qa+p9#U5QVMo^R$;Nb$c6Uz` zOVp?0{L8-pyl4&#Uxp_>f`GZpv^#vT7H_~mf2po95tu?yD%?zkP-kaKj&gUnQKEQo zZ)YsaZZL99-l^@N69hXwO07DBFau#>+a<#+bp8fULnPgCc0FGju? zMj5$b?Ja4(6cT^)juyodRU8To`&qY8n{VPu@XJ)$FT=$wAwdEowK8Q=OsaGrG;T0> z1MZvjmO&B{o_%9@0s{2{g%98`w0nQ%L0fxHnYOj`8;F%Ga&^NU zyWRysJU)3$h*vR;T>`4<$dO@*ECQ~Qz7fD6<#4<|b&GNqef~1J0-%}f?r7Q6quW^^ zOYWYjFhewPCt!(h%#>Q+FnjdiO}KD8Oa2Kg)HjTHXuF;{Q0& zCFyW3!>UaQub>CX31f)sj(0N&75oQ-D9ABSLfeoE3kx5{;!5oJ$v~a9n|b_{-!)YO zc%&>py{5vvUqTF?p4ciMyc?3Lbs1J+#Q>va;IwF6T2 zH_K(IN_$Sq(q28t_p5HJ1Sn_V^#peukfBdkW(ZyA3Yeq3Veq%IyJbLV!ddz6Nj;Q% z7T?lbf?Y-^_0X{5^(6Mq$=?j|kutpl*k{}u)dFkdw zr$to6+(iGu<}`v*Nq7Q# z_=dYI`1@szCLA;EOvNyt2x5X{@Ca`@0J!_|v$kysh>svL&2WHFtDBCAk`}tebzn=t z_Vif;LwbN535|RP0gke8W61amNTm??lqqplmr>v^|1z%6kiZ}ZLd|T8f<~;S-1=0I z_ji!;lcL2*hi+;Ba|@2?w;~--l;jtL*qY|ZTMvyR+_6Ar$w0GKWwZL~D_h~4NMs(; z@k(o!AyS`?PL&KIQP-UTWA*F!)#V$qExUUUZn|Rf0P#%pP*ei?#UWr!uVLB0$+37E zSKR@^y=k^RCi-;z90@W+fBXBla-+9PSWZnXT`QnY+((oH&yiUiuvkL&hnhaU&I5@- zv+~P($w@CePIqSLPLP8;n`igpyT620{cp-WI6J2(Xv#ewQ^en>(n!5X33todl?|1}c><>XY%6qA<$bQm34@XXzP zQ${pn-1)^L-`!P|@H^lH8p>=t#Fa5Cljp%Mp7>71gM@#2*aTC`dA*m=f#?xulIP&B z#qQt(HBE>^qTqTo=x){yz+^dQ-K0EiVAXpgALV^;BZA$UNnu)OvGw0@Gl1mL49~hWpsq&Sa-JXp5GC&WV2D;<6?;K?h>eY zundjfc>adGo#}4%iSZjp@~t#VkIuZjzYru6BU8;d5ri!lbgRK=u+^H9>}xKC+|&V; z0`?bS*dJJ+kgs_dGT7X5Yl5&Pe33lk{$i3uCDn0cCIg!T+%jND;N6qIvmbY>f?L8> zwEw1b#(ndDPJ}La^zNoy)B5NL_3nryIKMb^E#OSL3$Ud7U<>$Slv55sDz->oBXr=6 zF|4HCW9L!x-=ub}8n8Wl5;7HCQFlzP&i-kWA0*}-`>B#8+YLEFHryrye(~tv_!Pye z{6TiICEI^9HKc#(m`zJ#mm_RK$$|{W@SA2xZzBSP zr20{WWePfy}e2JJrBd|l}5>6qThP%t!fX-JVkRWrRe`pm8PsB%u1N*G?2|D+E- zLo+Jk@XY6#?fIZt%nX2xkSMu$__8@{AIYE0$??57hu-jwRuytT|Ne`F@5C)AHFx&I zCI~Tt&Qom1g3>0mTbbDjTa0e4TZ>zoRc0>|{sIa|&#;kJX_cj-`g@V3#>?(FSj9QK zCq`!#vmFp|1ve;o{@kP8&ZyX(4i!tO5iw@`slzfIH6GnoSSX&cf|96$3JPOQ>5~t; zZ1gwXR+W(qrdJAxGkN|MNXu_3<6P8KE#BbTC;<`OeZR%Af18aA`E!Tx-E_Xxf}PV} zUl@S`J&i)|AG8PUXDKj~%2%Hk5d*ZXX<-dNtT__z{8hyi+t z%y4x4uX_z*B7`-I+98XMtMs2sUX*OFy1AH7>)4I`Eay6Ge!(n%K{npK>Y&BOD#ld{ zx771G92$-oe}wTV~Vy3ny_$P;gwh z+7JQREPRkj9%s+KxD&dTYuMdckcm)J$l^ieK^7HJLXd2WgBBStgk$wt)=F)ZR48Xa zkK-TBlJ0|up+RA>unGrww$rJ&B2qiXW0&yhKE>g(U?}EV_%^QNl?gEVZG5s%2zhq{RAlwJu7I*3I#_t zR%nC`kCx14qh*$I+HW8=7?cBC{l=;`?&r3wxUUJiinZkD_3ZC z5*i7#xUI}4vJKxk4KPL$3Lb*&m2owrM6zPGzpKu&y!ELtS&uY4B zSWiPdF2p+@8_t6qxS_vigDlOKWd>n>s$$UqVmXNx#gaU#eVc4I$al&9U`G+T zD{BM~^!j;_CQGGZXH}|sja8S^emE%Wu{jk>Qa)HWz~d&@D2L>U&Aa|qLG82fa(j%6 zsL0F{5qD>Pn{qc5ab4B9+%9yliu^Q2V~*~blcLX{z#ibHy3IK!KQ%7=C{tXF?twMo z0U8PWT`f%&;mZvbL)L*xQ62^~$otduC-zoRtIFu-@tBCV^(E(eoA40E%Oo6$;ZfbU zAO4F7d$1U@$WTBhEC$;M)P!;2@rPsPMf(;#Pcn<`m0S_lW_ln%${UU$`L+)w6QEdMq4*_~e zaYmG%w@bcMs{)=!s{~YSN)n%1A3+u$dR?^;G5yEk=Ssan)^ZKIJBz6RN9U-3CqHj` zn}bm@#@h69-~JZV^JG|*tI)vT8E7fUf`0ARjd?kWAsiQ~IA1%?gDen!J1q3b7fTxq z&GZe?7Y#%WgC6=kwX9=2&=+vxXHSxNa}sbMkw04DrCO9s)HY|SKRvfcsg?=?&f&X+ zbBY21(-q-qVyQr@am>04XB4Y2Ts%htXleZ6;EB6%HP3w|d#-@&3gt;yMmBFo{bbV~ z&e}V27EZEukw`{>d8g(_Z;K@*yt+-GdLSilX16R;ci&+06m=)Kv#`+NpV@qxuF#@& z7ezQl@2v>WEO7YbT($=aNEiFSp@Bctt(f|MhEd&(U{^UBby_Ou8qj=RYjt zy6Io+WyZ^>EMok01b2n#HMF=KFQewfq7_NcK7R42cP{#bdLigZNDQvtxRw6S;xhjnXt z%lyXtP!8gC!4H_l;1(@d1uu9DZnomNFymx52584|kn+%Ldxqsq3kZl@VE}NTXMyw- zfF9hVu8A7waQS9)f^B9`(-dMhgPc_u7WKvVD%M7Kki5K>>Mj?^t`k4FqNBJ$D%;(F z&%^fKVlt$G*}XIHG#Feo@GS~|yh!%uAWTWK@L%k-;{5gY-IFFdvDCu`mmU=%oFQ@H z+05*Y&SQV!AOVF^Xa<#>8`pPp#n@xvhTdvYm>v~~Iku+E*yu&z<>w&%o4$1cMcqvm zaWam*_XIwvEqmp!k-qZTE+{DHexl;kMTqq`=eV9au^mpCsUg;>arjRvBT}xtlDfyf zlir2)Riz&%ilE>e$#LuqshZY9;W=pLpFZhTx`=eHsUH$rtM{H75qFhU>$>-6?-5QH zi#cG5OrR?A)I$^E`RLg-OdduTSBuSZ*Xusv4=p=K_re@74|THKC}WJ8-B<|M19iOr z%=mzw-gr{@{?;$s)&V_ff5Q{;++U$QyO|B`E2Hg(VrGUXLLGNX#IeO36PlkNokBZEe%|SI zAoiGuzo><KX3@=$gRV*EH* z7V1@Rp0h0m&X30b&58oAWj!?Xzr00``KFjq*QcC|PueN3E+;E8@__T>Z2T9PymJlw z{chkv`*tW!_VRP#7B)f`lOy&|I#=LY{`FYTQ*q{m&hyN~Kal*>By13i~} z()s=2d$mA0UAAj5Fve3IT0M1Q&X;_L>kGnp~dM#!2Z4Z~gnQ1$~V-?mr z*LxNm6{Z;e3Rn&3Iu$csZv)r?#5Y!PPLI9j`WQWIlv?d4`(?d6$b_e1Gs8=D> z#1vBE^V$Q+JNP`hD*Q-pskEPs2@nVHQ1Ur`8J|MBM>y7V=JRIpf&23uuO~SgKjoF3 ze2ionIe$tns-=d$M509W~>kc4^p7C{`t~IC!{ejgp@yOvB1Mqeo#Y=X|o) zxOuqvPLDW0F-+Pa_s*7j7F_%?6flK3GYcTD1t@!^>VNFVZZ(*gM(g?A2liBCrzKv( zI1m*jl{j(6{4C`Yy-rE}===XN_byA)QKctWH^3$?MQgE18T-4!NMrq`Uv0 z7l;E8aKOU@QD1kB#ObNdM8V)%%@3=lWSsgsM2NK*}*Y1sA6jl2HHdEiDRl0!wbBAE@pSAAcFYBLkaF%I*FJ~ zG#g#CUbgQWsEoS{aq#uAOXpsn+z1&L>ZhpwS~}6XUVYjtO>GgOjI}P}GU+o7X?$_d zC$=tgf_?GIa;PzZkO^o5IQaNv@F!uAD3ME(UO#UsF`}N03>qOV2E&7@l`#yS2$DQx z$rQ6hRjxPo4Ukv(^n`ey+U#@qaPZ>HxR|>*p-`1qVL?!!lm}4(3DrZ5+LEB9cM<-O zBeWF6T};0-L(i+(a9 z{SoJAr6sJZUL?=t37et43I0dV*sy0yS(7Pjnvgt4#eMq`>opKazyL+Tr&r$|c5$f2 zA$NrV8SMK_zp;8Ym&tuyf~T&Eo2%G_aevxYIYaUa)r?8ryF4913SGS^jjgJgWTEvh zuQ7K-thhMsM`_B(Rc@tzb55}18`9s(2t-C2F?!?}gF2E7StFHT6EDWKESYr>Rm3TJW3`F}*v*yT0WN+zV2=^g80Ofnv)4qvi)cC^uhDRRZLU%ffK0-ls~ z94gj9_sO@pxy9GB<%G=l^SnZbW0{<#g@ZssTU@SJ+aI)n0qXi7!%ed#N$x38!?Zl- z_1%kOMJft~k4K51L-IcwnwauPSGkm!*Ce5*A!SrFp1N@wJz0ad<0WP~J~jSzm{D<_ zTC?q-kR;37fNDb|#iwZpe5s*@0N(REI&zAwF(Ng2ga%3Cf z2fmWrtF_W|E^o+iF2|U0uTS|N70Z~Stjx*=Wc#K^3{ZR3eCwEF3F5(ZqL>UnB%L#N zYT;;+M~l5GQ<*44eeFkBin5E^VPO{z0(gu;FEFwz(H4NTPZ^=FNjZ6A$NuRU3N({q z%nFJIj=0xA!G4+c>J6Mm<}?U`>rr_s083X3syh$b!tlnLEL!l3=f7$<;F8S|jz+gL zQG_A}b$Xq(AFOZ9v9dak#&qOx02?nD?ZJ!(CN7Y6NXF*=sz)5C^p;^^TH{TJWe!-) z303N;=X3%VpbAqdGGg@+0)K2R10+L$ReZAHZReUG{rg!fhlPiiX`lWK#f3niSIKqH zVUv**f_xwbO$XBJ=P_RUgSIfVxY~&=cz0&*jVa$#ViqwUxv_3n3>^U;O0ed_$kcdGdS8UbXhgu#C#**A<(PHxnb;CdXE6aR zBH{IigS6v%UtU;Br3&QymGZ|D_)fJ*eY!W`yh`?(nKveTN8ppR!I@&@vGxTm^KAOm zf|Wt(KND>rmYc^ITmbb_%@pGhZQOfN%uo}cU8T$|BeN(>@4yrq2j zA`dEbG(=ziH4zdci5n9(jLml3MpxKq*kGA4!?+K!k z;Ud}f?bNBg{ezEEa!pVZK}Ce>9xTjzD-CJ%>q3U$2A|$_RXmwva-&~gA*Dr|$Sq9F z^0v7+Ep>~`<)C?(oD|lkNMaX-N5WUajFp&8ajV-`o-S+E6En z&-@?yq?1*--=(1ylG4<}(gsCKW-f}oOe=`z@x?tsKP24d<}H|Lt(o?EO*8RSmE#X; z9(tF88wi+~K_a0f_Z?9&qES|3{PrHvU~4hjJQZ=F@{`W#+BaeiOdC92V#|wy+CCh- zI6Wbg7iYvB1>MA=kT1gua5SqZsu{X^%wr^0$XLb&Vvr)hsz18*m>(9*`h z)f&MYdwcrDowxU7sKt)H{2^$|EFaCPXX@a0_HM3nF+IL>stgclX=NV|B2km4hn^N? zRb<&U@&o%hPbs`=J=412C@@d_X!;suuGs?By?5WK;aJKDa1bS{)`=$jhl51px+|X2 z644NeJ$La2$g37J^9m>5TSd8qk(u)d6=cJ+8%TyK-q8(e^jT-$TqYC@t4aAXqS}^J z8Za@GrWOt|aL=m{bOp_bfEy5SQj}kz*iGK5=3Nvk0tG$0Th zC*-|S%|ZFb7*)BNG1+)}DYfOnewpAiE$l?x++FQ>HG5oDP0Z?_lrbcgpef1GE*v}ew<_#JB2VO~&IyYaVbwKeRS# zaWu7G1dr|@A9hQ7p+L_+N!#l_IR}IDL3pWit%j0DWEVt&KcdO8J_%zU9=0!ih8!Qf zIK4S@yi3%c<{C%{dd}&E-4bhFoLyh!*5w^gWRe*DqP-8LdRog9I$}afZ<6H6J$QY4 zlL_j$D9qFn9dKZq7h_fIX+?h)r6Du-IK13y@%MjMS@*)@nzy!c?wP>53QC^=cP?#fpRT#5}{ENn= ztVaj;MpI(o@QpVLOQw|W=d4?j2$&fhOu1Tz7w#rkL+xl*8a4zQpmo@JK<`m)bTtrA%c3#os$SQ~r5OQ+UdHT;;0NkTrMnNslBAE2kKR*a6Biz2Yu6nu|+|{qSjSpPkqJvoS_R z6gxuQC3jK{(y8pZeG<}3A&>nw&CNBYqXu)wPw?u~zDP0#I?vc#Tvi(@DL?r#sC3Kw z2XF3rBCZ)TqTKfCEkDnu2vxV^5RM~dNSCl6flw2f1TeWw#P6o7V9_Vh9fs}Dt^K&A zcvNAn$$+K&Q)U6GzJR_936MQ_dPD;XjgAP?wY0<295xqg#U`1w4eaaq=6u=$fNisa zaez9;37T#;HgP;E!bl7YM`VdoOZpBemeoeV>JJc|UJ% z5zhXK?ahzaF^DV(08O%EijiLs1Ay**ns1>b+S`8Kn~BK6R>SI(+c;DX?1&#K|8_X2 zhkX1i7x`qQjyhtNpG?GzDxjxk`KcBWsK<|+u0LPth%f5Fv+^U2`Sufz?9+4Mq*Tsc zoe7rZ)s0j|I(6d+PD&?zJJxkWB z?^nl`lPR?Rgp)$5)pE?A7KpchFpC2}{f$TigP5>?64j%>@g>)*jHzBnC?K~Tk@X$5 zOBzO>f5HYOhC^Yg@*I2=Kl`5ZLUTsV@ z_-@q<^u$w+oWkGVG^D?~Y|Y1W&E`o#>n)RvPT%A=s^9E$>&ipY)Xj+y6S4YAm^oFlIgf@D4x5(Oh zaCjec_tNbPz^^`d$TeJPq`30-cl&Y=Nl|=Zqw@5I6}M9kdmp&LhHbiMI?qLV^r*NUlhm3jN!DA*L{Ci>Sqk3o#+R~2V_ z(R%m6_bazX!FJ{SLmOPti+VyO^0*^=al7+w5^R74?@VTT9LaMZcfZ4#D;Lykd^~!2 zPZYWjKE6&v*Ry^E)I3*xj=Hz*FuLefYWAzmOP|3K6~*Ijml)o3&N3vMh^s%Q=1Q#` z^|b=C%1qU=_Vxw^m$XR{7Iq&Q;wB7gmxH`5nWdkZ}RK^GnXSUWZYz}r74 z)uX1Sh(w=+fN!#uh2E~ssZPn6D?pG=LTHTY;Ko?cRcJFKF~rUowQON#o`+R02W8C-@HmlnqfD`3#yi& zdV~@Q{U;T@og*X$SdgErzIOo!lxj>eGf6W>Ot8f?{YO6IX+mO*Fq@**Z(hX#L97rn zzf#jCZ!xlS0~&r zCCWFcNXY+0t7=%2!E&M4zjgH|+BA<`J9lBSxf2(rqim8>DQZ4*;q3S8h376zo6jU? zLL6*nW0=?SpOgk0z4d-|O<7mL|N5Vcyh*9M7n!aoys_92CG>x5#O$ImbEW4gAYd+H z^K1~!|H(BSS7@E@M?x|d5EL`IsO=Y&zo|{c2C9HMFfAHR& zrd~A*Nvq%R zzWN{-4%a*oY#5nhXGFW*|{`)4%ZMzsz5l zzc$IKyZ3dx@b0zTcwxHWCe^Ivef6(yI9&6uPJ>p6H;)#Z?R|BDupF*wAQ&V#9ieKx zuRaKk!!-}UySpO0Vphw2G`z1q2#v!v4+29rBJA798`JwbLeO`(<^f=;RD_)e-dB6; zGY;201Ppd`csYeywx$fL$Q<8L1p-Q=w7%5lf;Fi=6dk9@<+r{U%IQ*E?omW2*GlB>Iue||AY`S+f|pRU!5Qn2@-|}=<*s_ zET4+0P8#TU>hd(4(y7E0JGTAM^z{{OkNWy1^LOd`-wgGp5tG5*T4YH({HfRfW~8hd zu}Rs&=;=E&U6U9fnaHehwU)$QpMej~_0h8J;~V$zDaWU_;N966HKrW4m$W;J)_mM~-b7CHU^NQH}4ukH{%GmQlu< zcvp%J#v4(ojE6~bhS#)smcbMZ;VQo+k;OP+gcieR;xGT>$(wyP#qjpri=`wFx~kP! zeeUibG%9~Fu4VsD?CD{AM=RQwXS57q_$_s#nMBYp<9_%L-aR>5>*?Q_Ii@9I>kr>z zpfEKPRE+U&C}aq~KBJBt+A(>yA%gZE4c!|s^Ze9FQpHYEm%%gf+ao!~lz;B_>Mz!s z68daJ+veM!!B~)ZG!}elciXpb*!IYP&C@rW-ttQD>X-@RtIHc~^%Uerc@9&5nPBpc zaUcptl;Z@eUJA{>H#Qd1o@xCb+6sm}fq{@bFzt`V#GxjG#cZE4E`k7{=N$k5um#|q zSz>8~9Q`zDH2^yts3SF{4K5OXMFNpI8f0en&&DqMMWOBZvbITvyda7yfli%kp6A5W zcdb*A*~q+T)1ut3joHTN7<>oB5<~dIkNm}`m+`%AB4JpKMp?fzUnP}8wa9KL+yqs1 zx!+W>eQK6%{Pr5x5@*l-`F@UAZ*IMRwn0mfLKvWV;jR{AVS&s2kjM9x45{YUI}bFh z8@x4E#`xA9?YS}`$wGSi*!WDroiIG2jhaVE6?N!zA6MJIdcebBVrKlI_tgA*L*6ldK8`Qe=rriorFm-ja*RtE0ADSIDA?| za(p^O;aTitgrzV122P-Chl{U4k`YkR*%*=|vcr6WmT_#ZYmgk-BLGuo#V8~wOD`mI z4HBG)lF|1;K`FYB1VfL`-mv+@qswr4h$2U1*GWEMvT`-ZthVNdbjAx@m}Ew*fYRUJ zfP~hmqdXqpA0N0BieV{?BkAewOVq_?NQSo6nq>?L`?X6*!mg}3)_#NIKS;opd{Vo( zW0)S&^KqQ8Vk)HL&+-ZRh^vs`LYCMG2bSpr^J>H^`;gRwrmJJ?6Oc;nDVC}ySW?U1 zC4ppWc^aY^;z_l{ld1DzDXhuYV~(%x&vg5qfkJ8nw_yJ{5L6!oCcua7MGC4tjn4MO z!r`GWC!2h&wMeL>4ohu7wx);$WXL+F;>@cBKYedPnKU~QM!}0rPq0l_Cet6RA)#x12W@rf{+oD9Ycn(-^MzANI??qB%DheT18=6Z3X4A6zC0? z)l3WEl@cz)r+p_blVdxOC7EQxCLgH5u)HN#?sy{n8SC;t>_SNk3kZp07wY=tG|7po z4OuG*DvhyJ53u-+Yd+Ydg5F8jXJaYYC6`M2FP=w5#dzw@e0n<16)S*pc=MEdXD`%K z>s^>BnX`&J6)krMI980n|11hjo<8|BiqO=<&$gGhaKKkf(aXo6Wl$Z+I{*md7@&kRytsS3ciuP$quq!ezf0;ZO)Wtq4Stf^;&F1ePFL zi_W1-#BB8)G$P57{X4PCKbapp7BL6+VKHx@Oj5Xn)}LwC15B#S3U{Lz;}bPzU7obj z&l{iFzr(`Mcj~d0@5G~N+}_Ju+t(+1hk#;P8?|OB4@V@8ycW;MsuKRuy#A9Y2rv}i zVWk3*#Qi(5w`V7z!>9J;$vYy}(6^8ZWn&VM9~xVLiA(a`&f&4rg^32`cbJN=YKQ$h zq00-Aj<;qq>Ips52pNNCub9$Y*<)1u%Azvncziw>AeSl}8r{-d`Gg7%J~wq;V?H(S zZakd|?kw`Qe6IY_=uNLBJq&*(`%BH^8aKU04}QvnCDDbAVp@*1;U^a$@WPkwjc4W2 z0(F?)z1#P0?!8(D1{GboI4-q!@z46f7o{y>ceDx5Q}Ly%ez`+M7@uFh@%mP0?z(>V zu6M=4bY$^fR{?pxqp2|=`2Q3u$+g2%K&?}Pj3bMGkX)jq${Fr}BxBpgUdF}u)iXl9 zs1_GuxuowC z!GH?Jw5L_?sCCVSBRj?dkcR?DS+MBKbfMN?X0$r9AyAjlK`Mu30TH7%DCeM{AcaLk zLXqtPo}IGS83{u~PtfO#c2JT$FVEGBU@%fe{YIf_()vAsDCi-mfJaWNBR(LXW%EM| z5w4xWf?vcg!X;}|WqZcUrjQaqU#caRp#r63l6kNmSk;4!=*wOn6%Z-`q+$T#dfT%A z7Rln<641Z`f`>Rp&!NrJ3;<-oBw>py0D0}s6+rC^Yg62((o1kry3l~&8ftCPgI&px zSs0Mwr*OEITX+oxB{T*{V`Ne&LJ)yTWXb4}*^YP+8ZkRlRD5S3O7{sLr08_2=7-?5 zzWYP2a9YYnBVmbmJlzkm!Ajo2D|Lj2?I2w||MyBM1=v6Y2shpxQjvh5ROSoCd zY^K2aL1cjt7S}5U0)E+(3KhBR%xV(&d;)o(AcKT${xOBo#o$enSkPMniCb#46LloXLrJ26*e8)4p#mz}oimAUUIH|;)D<+6 z;SgM)4(9|h!h(*Z448xmFw|F(1JPu}AoT&3Z*i@*K<`de27@)iSSX|{uGsTJQQ`+_ zHu$`vJ~V9d)~GaIuuLgC@5JiG4-QE-rbYpY0GU)7W+wo0n>8!(peBF%Nq)Fbnyktb zv-lUI0gDcmn51u-c1XC8;`!I^VCXpvBoo7H7ghZn&UWvl*Xi2 zfn;z4A$l^yTA7|+xW`GBaA}1DiN!aH!D-y2tnUIao-*27Aw=;gPV5{sB2TxV2t`U| zGT|M??~yeLNtA`d3ve6zFKe1pK{62?8k`v8!5`<;55*ZUKs2A~kwu4b%`N)w&RiB#Any z{ST#@=nB!Cu;W5w#qM zm`BFsBY&uI#=6Bico3};)lia+d4n~i&AIS3dwbE5n55t{C2n`Kp?wYn2$esSjACpj z!y7KtafI@zAdSYtk(ch={6Z@5H;)e-fCk5|Y;UH*@(Hr^OoKkw&ZKtWZwAY_t% zq;pKSXu{Eh-rTXlmEitBQZG4G*< zZ-pn3DA+opIcC7&CgK#4aLRr!rVw_ICY)n~&zIbp-da&3@T7G06f-+Gz zcp)T6vdkuPiEB;?B2qtYZNm+YOen!2je%l#lkkN{G7E5RiV@gTtZZ2_E-UYK&rXSj zjw}edHqI;B6#4~p+{L&xhrV`9Q&m#uL_RmdX2A>NRWZ_2G>zZz?6Sq^Cr@2lJTzN9 zX?&vR?5I>RUu9IQN-D*ED6d3y;-rEg@RS)4fk81D7gOH(0z{$xyD2JC%(9l5qQU~Y zRhg=QHwr`WD+D{C6B2M(vk1k)@+qp|kzx!HAhyMSFZK?d_WT0qph|j6!p1gpcpZA% z^KjfUiL<=`ECD06qMlu>YP_UJCOJBE5W={!Oj9gtV|2z=)z7tQdu9NvhCt-+k)}fY zqmw}pj2VUpT5-s&gr}*#jUs2M!PVD(0Xg5H#l0plLF5$h`~q?mml(_H3OTt9H;j^F zG43xRN2cy2V4^6o;Q0mQNR9;H$@RD`a$vuaG$R&?L6$6=Utkz)#R&KBFdT3q5QygW zL|6etg@|lEOo}k%zn9S}xda1Q3!$-^^G^yvlj}j-DHuvbDeXcR%84_89+rrgkir1cR0pZ#4+=v3G5`{J0ihlN#U`;Q1$2ZnyOPixKF;Q~#g1gI_Q!&xA4E3@Uh4Mc_p85L;CR}dbgEatzxbmA2 z27Zt*!3|fra9DTZiFsw>72y#c;O%L!*3yj}q2ihfv@3=|xpLwn&`D!20Ubg&wORAR zUwf5bmm>()F*GUoNbw*bR7DjQ!vkFyj^_Z6XM9!=;fYWOK>VDbA%vJ=VtqWB6q(u3 z-VzGLa>G@lljyrj4rAJYjph3kDDeQmC@)tY2H9CmSUn1VfNn-2d)S}ED5FLWSQ>~~6sT8sIN|L4(u!%}cM~L_My~{l z_h)#*dO!k-=&q`wl{e3|sQeK`9}ZvIFLnVa2BSoz1PKx1qr?vtj!Gdw;vl>*&_a>? zLxPDkILTt=S~Z%hgb70Bi|h9V6Zr%(5E@dW93r$pgn|=)Kr#X~oLg0ewCA5z9EB{0 z>XdAUffD86?+|81-@=-U>jQTvmO&SRYVt~eB(ljl=C7xw6uGQg*da>JQ$GpC;bY+L zCWUbUB+ZvNZ}>pmkT)Si+&2Vxf=Tk5nKKU*7G7PpfJgxo5`fbQ=_+qkf~BtJ7fL%H zAv~eOiBWy=GQ{mOIpb?lAWOF%sWLRe1?poWk5d{`;fmPa>0`Rio5(*a~XkTa}$N#PPC5$A~}`5@{%EG1Mx;Yf)hJc2$0 zBH}SvFg&iv9|}`aoK!q-o8mPnC)yzh4d}OUQ~{C|jNoywVA0vYnH~i3g33laVH92h z$deHJm_f0x(j7A3w5%>!+IkTsjbSp8U;3R27Zh22z-M2z(mlQiVHD6wpi5FNmoG_R zViyrup!^{o@qq;b5jo6k*h$r;h`1cW!YHCP3mL9j=>!kR!cbs52!i;%5)jRMz(DYw z!q~`n^g*(WNVRY)>W74*aKMMJdNL3Bu|}}uH;6E}2tMA~{K-X^h!o z=+jqadavI>dy3InDoWA9Vy+8$q$}`AM32FnV|t7Qbj2gvHMlwU4FwX47>fI4naEBN zfnhaQ2*^u_Fg+>Lf&=glklOj(72`$xk<~`_#cxk?bA0>i-IsfyX;l*d#ij@B-&~E2 zA~);i^xyE{;Twzn$2TtDd%XZ!?(}ox-6iR1-Wo??=DivA;oQD>@9iRliy2==)RFK6 z=75N$N9WsjEILOGXtX~XG#*(-VtXN&LeP9*QbCYdWYogs1#)O=ttC?pA^z7Ya_}=` zG!YpuMa~9=YP!g|V>ROQCzXivhzp7FAj<_-j}s6nurUFZC}0A@F=&sQt1yJLn5qDU z4vaK{=6EftAgJ$eMPE$_}AwI(lc!W7naz z?+o!%z)5+qb}EZraJEt2c%sCLNt-U8&GV67lEmPsYuOf`0}b2bU3(> zM7(Y`d2kc3P6^=PMJHPh2ry3ZC$KSzOYw#)$@86q-G`6Bw*?0bokJ3QNhcDF!Q~C> zF>22|J=XVs$Sm^oSky!~)C0haHk99A~B3_6__f7l0sD#RJ9YHPf+nW z`bU8ws4~A5+LNd%C0#i7agyU!5jPyMUIc&y70QANVX8$HK}m{?!jFVIBw(r`DWR(4 zKS{^n9VoIufL2A`n2qUW2%b=HgAV}ng{?o5(Vo>^VXKZn3MyP)oK>R7im1{NtvktO zRa-S76#^%f4PJ#H1pvOFgaJ)_%yS`!KBC|r!0Cxd3 zghyGSt4=K?-jao_npL<-g+I#~TEeS}JH;i#1~he3t~pdV1+vojG~k-XgV->|2%vDa zWX*9=bTHbB5E7hM!Br&!Qz8)^kfP7{5KJ1#;vHfqm`8CFy5l1bm1;)=%$0MsPzljG zd5MY}Bft`l;BS&N>SR}MLoNSuf_6>uW*p(^si#H5GB_$jgQ1O?rDzjW9fpSaC|;ne zqP<)Ul%T{{KD2a5j5R()x zSbjvoBJupC97yPifU{HpZMc!iO83|=fCD!NtcU^}*f>IMCPc`PyQz)B$$%^%kwuUc zl3RZAI|t|vBMH^>d+3q2J}=r#aH5FXA^HXM(8U$77gUm%Q>NI-F>>20oPGleI_3gc z*`Wx@fE|Qi;d~rLhx1EQpotU^-B2Ez^axmbB)bj65>KOZlsSEZ`M_hq=eP2sgsD#79Ji6JyMqT-*MLotM^)0LBR{=LPb0OkPl=YpfCAEqbk*LE-{LZNxhuL~?oN>V#UItC!EeCN4Bz zgrF?JT8&N7H6RmsIPoz)nRRsnPz0d}Zxi0h(p%bb@BjSo|MCC+>)-$7-!OU;2><7w|NSrjRzCEW;|RR; z4q|ij$%j5a%ndT$vNLEfg27T+h{_>>Z{INpTnT2S#;DheM;Iu$bZn(P!oa-9#dQ;% zAg)nC1l6F;r4$W)CC#eAtthXJKlMF60ts(UY!dTSB@_N4yg=}Xcz${Sf_;QlQC$R6 z!YK=e>Una$3k@U1DWRi+kXjlFrgRxqIZ=T?D-;Po9~^`gLLYQew#cL4@>Co)tR+!zRZ&_!TM?^-H;55i;rFM+;uaeTrAs_BI8b2@#V% zBjpxO020yj1X2$g#J-9l;WPZL_x!dPK&1T`)9(Ybh7aDm1r01Y6m?z^#HN2n(d4W+^BFBUV4kHDNO(L45{V<`2 zupEjX&xPvbxJ8Z}I^RgCNw|9#WQcRj4$S*GM}$9Cjx~06Xd;|r19Ly;5c_ZplO8l7 ztz&|7zt$m_84X_7BEz4f z&N_u}YnI9F132m(ZBqbIa*9rx)-g!W^F*k?Ns2mZ*Zqbaj2l{*B4 zR|!PTAn8f_R@n~3Z*Yamgd%*N^8vVk>kqdl^AoYk_J-@*H447r`Qi#umeuuKGm2xC z6~L5ya*Hj76g^*5(SxSqm~52|IA#auz%e3H4ZgYV$EeFFqU}xG#B@te7v-${FZeOE zlZ2`$ER&a7os&j02-t1y+bv}^I-iyUx{6`G6JtJUGFPztf}Jei?zFDwGC3!|Ir3tY zfKbx`+q9AUWg7m*X_eoB<+MnvLAhU|QD1mk26SLKFVHGr?v`gHdfgc6Zi@9_sV#v~ zfTjZG7c2qbA=-Ap^BDg7{ZujGcQnUd7n}NK5s^K*hz{z&@ui%DpumKrh!gJn8 ztH8Nip3!fpc+oH#rfAjsLifH0Hy-r zH@Jb0C@-K#-)!4-sDuhVYb34kAgTY&p1o#IQat>vVG~vMXiv3jm=$SDD(;x@ki2?k zARsUGnB+5q`67;?mU@hY&iyG{q$`I36Kd^BC?J=L6PlWVQ#nko;ZPc5O)fL3f#N$V z2gu69f%-SpvonE2U5FHaL~oCl@MICdHA5GSYn-@y`|?M0MM?{#;XK>Jx;w@1$9F$I zVf*eTu}#qp89vY3=+I4D`(xL1lytL|e;n(zLN88!*z;aHccuzNooIA3Qq~}{-DW1V zZ*7fOz|5q`O0-YM0IB#Wos+Ql;vuNyhR#uQ<9ipZdCwD5?%|~dETXpFZ1BX}U5}I# zA_o@2cvgUQ*Y;5j?6zcK)Vxg*Gq?B5{f#6_R%)+*=AkFA>PEoIA}We_NU{Ix`#%I7@+W1`u3#O3cBSKS^_O9#Su*1WShN?iV|akJ(T837-EL>l!S zUOCIp5Lx>B=2f#?qFsZs?C>j6w(cO>#Pcpi)<4@`Z4-x=ujYA3_Vew3xBF^1u196E z!VweM6bL$;EIw+*A$O#hh0zcQMfTn#LxDvQ6lGF>&Er<1CkrK*nn2R0uMi})jm~Y$ z4Su`wL$6Svsy|B$HG^XC;3@DfmXViY9J?luMIw)h!$;GDrh6y?9wtsYC!G75#JS&q zszvQGQR^6i3jTgerTd2)*kYtWe}%_MCrBX`Om$V{j)=TiL-7Y10BJuDzpeU##^TeX z1x=EJh-vwvEx+n|+X;4m-3Ar0*Hxrxd|jG53QpVX#*lHeU-yzYpv=z`S!IH0XE0jR zigJGW=`S#Lp71z6XS7-7L&O%gVFy_G%83M?HX;skx4ccBS zsl2{2-KcVri57n)r;F&a=7=x}g{sl`#W82Smo_g>=L+@zuqMIoOd&+DnZ!*w6pfeG z&DBg#cP+VQhI6E^;F!_sOJfjDMc6*$;k>An?dj8J!>|%ODaLALc|y1wze>I{eXK>h zigfq#>{!%_;cE;Me>Jf(_6<^nsW|kKzJ&u7WIH?~-6k2verh2BQ55c+Z$kGf&ObCn zj3wP<*X8T=X}LfkGDa$Q=#a)rljIW_{lwp%aHq?l7TIXe6=T|v6U)SB$c3pY>e!+; zpRkWbI53D@PkL`KSrXwW)1a;kQBs^))&DW3`Hp^P(vV8Mbr1BqZh{^ndq}G&4_kDf z6of-Egk%yD6_|66KHLk-UU+jizF-p!0q!L}qd{;?T*Xu(&L~;Y& zNT&}!h$II5sEIr*V6am?>%_GE_FHQK2%KqN7kQKCzg>P*w|A#Bowgw6emmoVnpfRF zy~7f+@n{zG%5%y=2D|ly#C7<-x$GGh4PM@@`!L_Q6}cJ@g;!4d7n8azdN?B+gLh|~ zz*tt;cR%Vnbn{VNG%w#MChBEtof^Hnml?B(MthiR6XU3;o2%1|cQ6NzhD`A4ZnLoY z?2Y(38b|HLk?ExY)`-aHy}hzv``(5eYp#lAe^c@8a++mV>;V58tQL~X9g}6_KjSlUOyh&S{Fv&+DE}Uro zK1ax?U}6Q{v0`7OT5O|_+7T_k!Fxlnq%VO9g(k62$Ww*w5X7%T@*Sg3!*Vq6d9{cX zkdWPvVWjEQrXIo*Ub1$Wdcda4-O&X%7^C8jTA!q z)QlXwI^M;YE6s;y-~=W$6=|&9O5DY~s#-WSH#dZk!N|W7!rNoiP5g~ zaQ6D{1PH0pHkg@*NY!ZH$r+yw1x_Z>~m>@qGKGM{Idy=9o~CtvP=5^4>OAo&uqvmqrRjFYZOUZE46fPqaGa z=o;al!g(4pMUt9P0hlgkuoasedsVADi7GE&!dgi4c1Toy#hDY!^OAL?oE@Gc0ZF2d zk}3>l!YXC?fV5CKPjHLUquZDTMC<^IF2TzlNVbI#q9qp$%SXKis`9USY%=-@4QJm{ zch}5KLdVPuWaOoJcP*-Ap+fR46S#biA4OwHCWniFh%kHpn(b`LPNIS$d6qd%gIZ*E z6*ti=F3Y$g9?q=HB?Yzkry9$T>y`x7h07zF$E<2!o}4?;D`uXGgcHpm;u!vx6Aort zirJ{7ACw&7nbTLu52#pGVg8gZj4>+bE-szXcROov71_==&iLpJBP??uJAqeL)i#0RhGthlxe2UB=ID-@TF2M~-W5 z-tzTP7X)9OYUlCIJ0Aa0SRA>ny?M*lM1pFW6ui6EA`Sy_{Oi^_*K#lPk=7_;zQdml z&oy^fR9{8mlpa$MnwYvVAYyk%1v>9;Qp_2nq`AGXgQIu%1iSg}d-CtWD0AB6G!&D0 zx0WK^Ka1nZej+BEVmy(ejEh9@=1_@}LoJ!?SHRh)xIqIsna)n&!n!bJ;K+OhqQy`m zsw0fSH^vjbLfhy&{S~2EM){R1KW4fSFjrSECwTbD6TkZ z*L0i<+hU;~oEpVN?du-c>YA~howH6khr$`En2>dqzC%Tv_SQ+~e}=2E2?TmvX-h** zu~Xv-`2R|#BGipaV8bBOUwfq}D0)gF2x-Z>$@OATIx>-H7IkJA{o#rZGCOXj)08Va zu^ar>2$Y7{$wV-pK?}?=Ur2C-6(}J*M}e9=YFy-i|Mu<;nNdN9c}x2vCgz2kyH>9G z;0@unm~XF6jWQunac5qsU~ouG%8;ILc-6kVD>B-Q5Zw5rIPvAILqSO^$+jF zOuXfI&kqUyiF>L%c&z9#KAek2-*)oOtb+2qOjB&2(Q`kmbb6l{)}Z0~>7_k3#ADjK z;{+evr8eb`nr=Zc zTcmKmIhC1nH;02Ama}ip=wlUmuRnUlGdHJOh_}+G=Wia`D7IG>8aL-w#hWXXu#1m{ zviFOVxGbMMY;051;Bn&VCqF~x`^~4x96!oo(B!vm0(uMhZ2jpmDPny(CQ@+h9P&1$ zUhKZxr!Pr8Rb-8oiFw6iM}I@H`=|oa(NW``7_4XSR7AR~VwRVZ1)!UspJeR}^@gFG z6?@kP)BS)gS0BSYmZ3wf9S~@mqR@=4d;R2$KokgeE8$k=6H;7$k0-}~z~^u@3!P1+ zsjERkNjYk>UNR=gfT*`-`3XO#xF;a9wtG_TN$E)M3JuCju%>TJHR@P| z*-uNBnr;^7X~%GdxJhMW&P7W)-Jf>9r&dGTMOqdx!P^lqn|wwRP^Fb_y2izWZqNiT z>dy7GpK+(qGxsbg)cAPx#$MHjO`+pEv`n>&fs0SeiZ4fLnNM5DpY0EiZb#TVzL<*e z1u>rLF z96QLOnoE6QbMWXI?d3d((zlM!a1%uCsHUCJ^%tAh_903aZ7`d@_d77DH}ovknJ@`S z$E%e%vLVv9eu?hL?KlvXrm4+GTuv_c`t$S5JVD9677pegrVmuCMP(_WtM!LE&h%XN zK@?FH$H&W$REXo)F*}gy9?k7UpZ4XtP}->cJuuaq?-@U8`C08s8<#Zd5T#u4LVv~? zTq6E>;x9FtP?92Fi^IYGJ}!X3b9#?SRC1u(?!Cj9QE6Q+2&9e5UxbnfsmGNYCO0Ux z8k>C@6z;L~J73wv!3B!#P{lMhKTvyPdAegWJ@-+IUjb9ROpzcYdVDXNET*9(2H{xK zPsG#4m#v`T#*Nn4AU8#9B8o;}=?M|U1>~=Vzo%iOF4LpfF^mZw`*K5qZC^_#+0Qi% zCCPQqYlEJ5Og4HXL5YuAn2-b{61FHQDxLMxxks?8?se6rsx8dVr8dOmebR&x%oQa{V%TX-d!KMwS4l>_s9-FxGj`6cY$u*d% zQ9d@7*##hVPD2#G2_r?)V?9!K3U%&gQkjED6G-zQx=WY^&thtdlE`0%TUZ%E;TChh zHW3@7G6%|rBy{|5(W^QWrf``qXX3yCvq5J6qn;-j!m&sgM%&#`cRtZ{30&j z$+0^6vP#o+puB?1=DGT~wB9Qc(U1t*N80 znU2;xOgIt_eYP;!F@VYoG-0aWA`|5CG13DVS~Z3#)9AH09>ZF5>D{o95EO^A92#b6{SgKjbV;U#ZUK_P(UM-FTWO{4+azQ8uC(TMlZDMd7w~zOoUYYt#P??FX^wcn- z7ORQ>Aw%VhF`TsDahB@&@L!o^K-G@A@v6Lo>K6Af3N^y%2%4j5-g{#x5*-L?zhU|b zNj}ZnqB!>zt()MF5E=i#i zZORyuYGZlQsQ&zB_HXJ{NTWWrQH`f&Y9%m++Y|(li>5-X7!c79M2jEo2gs+?;e^Rd z)g~SF+U7<_LJg9ICE^%hRX{L?Ga>p#t1-5MtZ&?-V9GU-hC_R$El7_I{Y44@vc-d9 ztW;6P-(~tdo%#B;?nKY7W`kmW({)V6R@v>ukKo{WY ze-e~|mMV0Sbo@XHm)|Eq%l}0F(8`y__rQ#F7E-;t|g!iC8Cj9v+peWP$d}>5L zF$tbGy)?Dhbnqen$OvwZiNI|^q9~U#FDCkdu#6_EiYdu}umO&)#4uk$(T?=12$0cw zX~Y8!+{}8&!j9@Fgcq|AxP#b)8Nquk^L;+dR10pPt{a82 z)1Dnj7Ys3qh{=y%z!|O2U|f*xLe% z{#7-LFiiw0o-`LT&v*|FapskHvFJ<@9tgS#K&46e&@1hph=44D8M4nnJo*m7if~7f zDBZ5ijsQ<8TrH_jLm$O?>FY>s;YvdQ`6OdhsD{sy22Al#h(M+{UBHyODd%7!ps!Y4 zg=na;OZ11%Q3p5kTSSu8UK0BLTCh;m8a>ZwaV;@TxW;T{TsTG~!5^BD!)%52j|d7# zi!G?IHgou)t|b4&74#|cD|!|avr`+4Rzk5dnNd5jYIIRPsv6LA0x<9_boEkt4>KSl z5($HC&6D9TY53Cxbn&DSX<>o&K*`YVgI$E(ldlC(;&l3$C0~#DI>H5FY3heB@&73A z(pxbKL-q+iE?OBa5XKiw?X@UWVvzlp=ppn0y~oIMJvRe}i0*+qfWxNE?+sEJIe?&i z5Gb$M>m4b_&vHV-7n%u5e#bNf!zs+jBwvcbwQrMwnBk=^*Z`>Y0C!nX!9f}pg9M>G zA?qtB2eE=?W<@4KyQIPvD%3g}Pcui*S@er1Y|#M(>KRz1)anIn(dr(N8puHqrLtVL zoa?O-&WvbWTnckbn#e8@RwZayzpH`$eUKS=NB*R3XZMiN+{eMk!y{#EgU|Xq0IJ z_%gTwKVdZtNZvrh3MQ;G95|X*(L``p!V}|T@%3b_Vcw)yMvo@`M-+k55+;Tj@x}G~ z>Fc0I{tyn848a5xrHgPEr=v_pkJgn?Qz)N%;)1i%E z249t6H=z1fHyprX5Txl%7!`Dj<8ew1qL0JGCyO!y6a`PDMe*$Dv5-uVbkG0?>?L|V zg(p-I_8Uez7yF=NxWp6oABObub+oiTu4T~7S<2Uk|2vW5ZF_#xn`3jr1YGjH? z36*gjpwhM!ishgjBu5f{SnhC=Ml@?am^`m_yE^S0g;}snlL?Q-AQqz#7^C7a zPY2tNiRsG;`aXzDnIJt22F05kp)iZ@%KK|l};vT(_J_^4*<6xmb1M1Cr3SuZijr(q%dlQFi`F!fA3<3LS{4gw^$ETWZ2F#W?}AA}XVUbB(Q zTA&+ssdy50RMM;}#+TEm`H)26Q+#~y@M(w;@ss>B>_yG_NxX#tkGO#}aoI2rqtczH zh{QNeY$<~v_ZY3imcGPWn7OE6%qHXs$peSE)L9H;srp0KpWs3R%YQ_&!kHa(BRqjl!)>d1cMgEBXLY_hme!zQxgCavM>SF>CKH08O;)|V~z*MUPip8V}qlt z3&9o+K5%_A`C0QLqEO*PdzO<26}}yDT8-yb>M_BEu9ksBs1plXa%^Xp&mdcqc22Ams0i}-5KI9Pt52}!wTuMAX$fC6|r`3e)`cTj~#?TB|&WeHWD&aadr zQXMl2(~Y=zB0Pi_Ry-LFECao6i6B|@K!6HDEMVq+rz|C(2EADM@D#sEtCvGb9Z1wO z{p|aTw6WMQ6`=F94^`AnWNfvTy0T`mgc!Qd_62H$9 z7x_5P_9+kpVWi9#TBV?oyvK0_42CpCB7}Vu>s!>ykxwwf4!jlO5(TE5pu;Oo$MXy{)S&H?b#1Acxmp6P;&W7IIZ3*G^6!>I%und<?!o&Z z!k6?Cv4$zNpQ={QN9?doUU_He`cJ7u3h!C<80*g-AWr`_f93FxlsjlO!TOV6kFh;u z=vmDKSXa%m-d7b}`-QAqWJPkguJfJX%{BIINIs>1MtF>BioM^9h%H2%e!CM0?qZ%v zph(657wu6AP=0NkWxY-eQmkA@G%H&+#*qWjj?4l_)^}nz$7pj*#~MdS+H%r_#HC_U zdE-+a#B;Y9Q9=srt~PW!cTL#E|k{Y3eIW{`b{Va z%Q(uk#wC7yA+!J10;X|R2$v*OJwq46sKg~P zj=eQUB@@C7<)l;)Z1-c1upmvjUShLKo#D4X50chC37MEm`j!XEa9StD;8cmmSm#Tx z7pjnW97Kf8EY*$$pNBiNcu0T}kHI%3F0O7MT)fKUpGiRTQe$ zTA40YSA;VlgdIJMzKWn9EJt~qvY{$9C9JjRHiG{(9u|aR#<)*M+4C7z}OE6RMQ%EU-dl>+Tn@lB{E2@s=yDra0=CnO5M5)BgBE=RMIVpRy zKJSl$6B#c3i;X2Q_BXH+p*3Giza{lWncRjiio~`LAC8IvMLm(jeh@;*erK;I6kP$- zKHoSg0;dXqU4y#NL76XH%p#ug=YY*kMP^5db*GnK9xBCk*hMDf@r$Za=jCeCFc|FNI|4=UG z1Yau;Wm3NV9vD=iIP9~f_cEz>v0=SwNoFM#%D-Hg?w4FGa`SjP4rrydo-pLdfzAu$ zZ*>5f7jd-UIkMpl!#JRABF-SS40egX#g+)lILbA~2%&nr5OVYx;rVP9^2S2-?^Bm@ zL1*>9%?@({p#B%(=4MJ(wZU+c`x_wDI5k(TI=R9Frh#&WS-tmA&Hu)?;IE`^n#v6aHbYI>E6dxad~dBPm$_ zqE6LhYB{%>`e=AO1PVDu_5FmNsj)+Wk0NM%mbOToXqr)Rn^RG82uKRuya-w<5#Om* zMVji_Q$-(p)|ZLX*d-JJQ=zP;ELvq3Fx3XL{jO+5$dZDSK4=G$$3aar*#iCg@L+3< zTOBpDZxC0b>WFU;5{LmxgPViR1E6+f+Je&xOc!ivA5_!D0;Y9R2u#i2@W6ajUZH)v zzdM)&aUC!#ot@~7`d}5;uD&>0KmD4v49Wx709o36Qy`C+IH7b5W*Rvu!lv$Y`4(zi zgBlhQz5bTA8P=()A)MZxk7(SUKj3D(OSq6E_U)peZdzTvT)zR9t1K#w-UF+1yL%C+ zURa8Olz$4h^@Bh+#dHeNC;~Hq2dM$No`cnm4b;S{R$OYVekk83@k5boW~DByv`y3f zK*KVEUz30`TS|c<yC&LrQrfZE+8_p{T?a)St<0&SgS(^e<1>MsCqnMV&ZgEWXGx)p$ zXNPcmN6}6)MY%*DJZEIXXqF)*BIw-M!qq+HX%lZgt0WJNa9SAtcaRFG-jt3Fsf)NQ zg$PD>UX-EKtEB@wYam1+7DEwt&kHeMNV zq1h;uf#Z(xPf>r2QZO%mP@}a2Y3Ft~0*V%=u#5^RBKKi~UUTT2Fv)Ks6qkiGFUTYY zfgTv)a}rD@!;A&eDQwc;^+77Mt3=-Aj~+y2ctY` zvw1UnGP;kNLVDP+WHohch)+r()K^b`tQup(EtVR`=29D> zcam=JtZ7Ky9;^dODfnf8k){VQMuqVe84tbdQFG3qCk?>`b;m+ww3WtQQpZf;u7Y+W zCZ&CmHcllO@eDtrbH?CNcVPbkr8b})CcO_%l5waZ;^8D3d7HQ{Wdes|2mT&L)!a-I zF18Nc|BPW6V)O<`y^4raD7}$(dq>TK>h5r@k;)VlW;cTc)!J(u%aBbO!3WkDyH5QA z3DU1aI+SJt&6L-acpAjl%6pp=DC=i~8Z(;kZ(;j5pYnHN29gbF?{@bAsy+=``DxGQ zpXi|oYf~QGfpiY14I+x18a?Cm(r7wl>V_HdDTFZ%s5j)c=F>kwyd6fp0anHfL`)=d z_}|2M(UM=dA^i84Q5m|zNCs3BV;uQf?VU2`mWf+mDo4+T zAWpsvF&smBz^V;t_jb1dn#RRpWH2m=i9peP78sq_%ws?gd};&QCAkqwVFeA;LNYTW z00BH?)M-FT!H)qwh0#lZc4)VE);y@*G@b)aX)jAl1&BlvhFlDr-tB%U)npD7b}}^! z=+l}_X~1M2A=7P`UZHWC!-xYz0vVU8h9=mW@rM`eL87K1teT*9*z`t7wQYtiCkneU zGcT`h2&EKpCp>%b7m=#jP|PDCbb)HcQyFpU4WJTzoJZ=d^xHY?4p=>l@PJl2XcW6; zIfKR-Ei$unJ%)rpZ?tzYsh5JlLu<6WT;@G$-4ceL77PtsRE=zAKZQnJD!p?-(U2+# zA=L!5!>KpINfJi0-Vuf5sW9^6rh~in;P){46mt^(Qc6kFQ%4A$2b37eJVx&%-QHO@ zfa;lpHBPZ$@g~J51brFP?gWw;jjmzz_*+^h(1d%x#ih*a<0Dv0W8s@dE^1N*_5P4= zn0iTuhs>l7q&A;w2K-Hc5++sgKc)t*f&!;;NZm2^zll@EwrP)y_PY}2A2I43ka{&b zwdvczX@|QmA+>YX4X{G{W1)1wDjR#0!^B%u1b)qsb?!$&J-s04RHg`1ZglLAM<25f zgMSV8F(7)3RqSIH`H@AXMm@fS2JUueQyj1=5yH%AqScI;bEL>^U@}w~#}qd~+bhzT z?3mf>&m?c~*+O{@n>J*2qWa$(sEoCu-UzA1C1shZV#8>ZtTdB+T@a2Z=HDR5-WOuPm(O+g<+T4NNh zBtWh4=_(l*-|a>)@wz|K76p~vy{lFvSu>~!<|TA?NTb7`^Kg2FIVaG03C<4L z_Rg9HlmJBtp-fn!VjgxODMA(eIDGU4{t54rzabUK7MYquQBm5<$LuHVO{Lmqs6wfN zU>+FN4Gc-T#GyFSV@MAurF?>|Wb_57(tsUG!`s~msAgx;iI;Y)rnq=ehbp!@EXz5t zs10Y2;KqR3)X`zmX+XWAoKpzB2B=NCy|ZQ^W#D`WrC8QPW;KMHK%}-L4Am%sS&DBd zZ@|T8UBQ7#8IVtriqEhnY<-CfiO~;_s8IlA(Il3CrpVIM2{#7K@LosdY;ultwcDM^N>jyFRr!T zbd9UrFx>pim~yWy=YUgcVoCLC2q3#qNEZ!ncO#(Mmqr^qo$uP+7B6eSLXH_nHlRI< z8$)W7M~6+PA;qQ|%cD~$y#}dGyuGvLLG|pw+CEZ+rUJZlhBDp&p+DwRX$3;Sc%=#s z9rC46Kh;OZ-C#m^*dNihu$DGs=EyBh&T zv|(1JbR&It@$MhOc@Cfll-hvyC~gR8hderbIt?kL7~#_nN-sg$A>Q6u)1cyejX^yi zmBtvx1QTXuA_@y$7cJAf9+oOzoi?OVyKqdxPzA4cV4{4)Xs|Dbbq%aFMSHVOiL|Tw zy5fB5j_g11DNXF^^q}m5`{QAc#mJqI5+I|vQdJ-1nXiZ>EusrJr-b87P_JRtrjQ=1 z&co^z=A1+8HCSy5?wv)+-XvlPT0{`5E-M%in-=9pOmSrUs#;0K_k>DuyBKCv8^1Vz zWLFq=qJ^W>{f=}h>T|lCBwYD7|awU3J>fYQwVA zxH@GQ@fgwrN=-;@dZR!7HbBWhQ(;Z~ik{j_wMXR296%2|Y699JIQ0-7@lY};CO36c z2t%gtkQ*PO^ae=1ikvej?Lm44r@gc0L3I~|9*|0im!+hHTZu#BC64)&$#{f@F{&t( zmzjLfqzoFPXa}`H`99&>AyP?}GW~(o4*I_rMm7+hb}WViPE9~NYj=a5*G9}a`Z&F3~jMIdv4@^oa1Nl_gQ(Qc*$uV ztsQY{0BSSoop8cpyccbnDv70_BF?0!vN7#mN2rB`ib-FrpV#nHd};=E45jWopbxJk z=LAAKe02$ebF?-k*Jw)g{pu}V5G1>$43QBut&4cQ$w>sh!#-nzZ zVp;-1t1sER9)rmUBCumw<}9(?V>>veFw>8ivd!ExoXsIt@nD&ct2QyJ_At8R6d8(wMRZ7=VxKX#LGy_; z+iKm7*kK097N3pwMH(&?1C8@4a}6Ei;eb~Y*3R|r1QlaN8D%n0?@X&miL6+pmo%3H z>48^GNPAedFi|mULKLI^$u5GZu>`&WR%|3kzzRObu%1EcMe4P%+8&i-I5(h`H0T)ABct-Z zXhEe<@k+Y&NQr>)RcMjHZ(;5NgFp{GGGCOnGu2hO8UC?bKATRWfQ~aL!dK1f74MD7 zl#Wr@2wwwEn@>G33Gwq0Tyjv`3$SE{r>Y@^%#cJWyAkKo?_lPX*FTL;0|^zA{!utR zX>45o^Lk$;DR)q1<>$J&~ zK^wSYyku2q<$YeT?0MmnF@~3*3 zNQw}>#dI9%PeKS>Pc?SbH<4~X*tw({sCi(m8a0G8v2|>sM7Jbp$&?3}J663Y~CYHi&GD1*t;)M9uJnG}gN zI4HRjvE7Grvv6;M^WBS(9l6uOrp;1U&}pBWNX6NIcgrE(EAwB142LWq^PdP0%N?wdv_vP;!ifMQFVx$s*ybe zT@L(7TQwf6Sd*C3^FX*YLUF}Z?m*b&2V?nlfj`M(jNv>W)P&RKPX|oehnUI68!-BX z#-I^@5(mZ3XR0D?yNuquz@Mn;F_;tRG>}m8=Mc^VI;Y`G>s9~vfBwgR{pUab{h$B+ zKmOl;{rkWC82Yi}f+Ls$c zsl|`7R+R>(!+pe^THBxSc!g#rLwR zXV3xjz@8?U9dsH>P|+Kw?z}0|c;@@j`38QsI-)eylvqjv7vFJff*W;Rt)$VA|~I zKuNq7SXf_0Jrq`J4Q1tf&O?dcG={R~P8&*_(u~WM%sGVeW?bT+kD;tZZ3xOM$UOaE zv8odS5DuIhHswkZw@{5h-aUzf)Z@$)E$S~O%|~rZP8s5~rso^#&nL~Tcf^Nt?1K%N z>1Nf&RAo!kB|2BrObB!P>YoNuQMz;Ku@=Z}`&mn7ccXH4#VjScj&(3V=5N5+d$LKI z{qk(Rnlb6ogbtUTlRpk)YO1xhku(!Vx!ZKy#?53CH5~I-udeCTc-k@5*4V7JrLLAi zhco|9P>V{twZtbP+*vJ{q=H~<)ArVK zCg!Xbd_KnvFulN0^WDdAR`{$|qauV3A)Ety{(ZotFUbM3V$TkkJz~2J&e>(M%AC(* z^FAIXpSEw!#1?mb9zN3F=@w0sMxdKh`N^j+m>y$ zT$P2adpXo!0Vm1hG2zzutTw-{aCY%YaDCk(I|=CQ7Fks-kKsIl&pYAloi$In1c%3v zRv4`pN>Z1S47~2`irthH4QA}A=%dW z)VNQzX==&q24;`gZbPSPjj0NmSQksDwPPWiKf3uVzmZ%nq&Hh|Xd~ES{+ips(b$q+O5twxH z1+b}BQUlCu=qz{3u7uHHPJ+Kv>tHE~3|T^Vf@x80@4@EDmVp`pd@_P$TOazv9;78^ z(z~8|Uaj?^i9O4`m7fGvtDhww&8S$?QaAn0}94aR%Vb5 z`t@2qo#@W$20e8be5YTnLj;_3^7B? zUK^U2v)WhbjEh3^?b|e|C5$uYk5@@k<5S~Q)|I9#VH|tKeY1W&EeWZa2YNmJvKIgkiw`n{;w0EVGn|2skHnS3=eO(=VmHU!foiwe zXli^G3rsbxV|=;46PTXGSD~|9by^Zse6%W@dp*e%jOK{RLxh;>~ z$+maYG~KGFGQgkZ>PO{QvQp{YuD3EX@n^Y`QguMXyak5P+-60F|9GV|6-uksrOKWU z)#u*}P|xhEc(eoPC6wCK(c#g_b+2EVb2uj5GYGu|XNPoqXU)?tZ#4$BLMd(6#pcJg z+NX27{uW7bX}ymUziCi7RP9!zq#-<+naSW@MNNg$dSfZuP)4`wZw37e;QaBdzZ#zu z*zKEHH#oZp?XAm<0&0;)C_;q0>s8d8LFkQuc8UR6zv(Q;+!YuHg!?F3~Z=04`^&qK*3h=^HKEoNPz z>>-nA$F}2j4oqXUXpB7>{2Pf7{Wh4r7n>$p1{peV*34O~dn6$;j^Dyh#|55y&kFOt zimjrIVHs+u*>#E(MtcP{HFK7GN*Mt48JbU61P=f!^)XMD%)lXUU@Frpl0GWs1anq8S$I zzrB*08lmNmQtbj8Sl|7nk(ojND3qSnS0mGevV+VU!8FJs$es_cq~-)RZ-ldR)I8O? z8%GZKEOtC%oGxVBxgA5Nk83*%=BzePj@2iYDMb_$dolU0S5#Buvs_Nf7N;S1c9%sa z?)<}GdRAYJP7}-?Ht&P8rHdeUG8=2GQchs=MlgFv&6BOWaO8;3VzDFhAT!q3v2&qLKL6j1jn?~uK zkoL~HfqLEjBS)l?*KXE1w)Yc#;ySiFItyKTZl7jy0p~YE(of*k*&O*4&l*M;37B#SWADHb)x8c)W zKyt)qyRx#qUBW`S6jDZcqeclB9M^?5YBV#z?6O3T^$Kkc+-YobwC`4~_@t$-o;~!1 zN%seVbhnQjaA|E>?I80uFfFPG^5(;`L;aIm5`ogIt~ns{{7TO5GRQv<I#l9es zg%9uX*pQYrMQ~Xzsoa1xWkz=mWM<1h3ZrM_9S~`)Rkf+?HXzI0pqU_IJW0OY36#|G z)x_g%Fxm%|>pZVfD_b%hC=Zylc2nAyvvzP6PG+?)vzxOJX-{u|r1-(BqB-Ewg3{*6 z?k>;7lz$dT&$_EoX>L>Ppz<~-jg_E5w*2raXilK=J}5gU&93ppxAd&L12W5Fyb+QCV$K{pu#g zl4QIO%3>euLK8v0+XQeVjCsnxJD){qw+SBb=1vOumyC^p(?Ys51JtnsNqcFNVMruq}+f&y*xel4#24qVS zL9Wyc$6;612}IroWaprHa&^~>98g*Apj?Ms+LyC-Z5B*fEmEY)W5AS?yANsq_KIa{ zR91@_S0GKE?62%hO!+5abT^CCh%9%ee)Wql1;%YaS`-mv%AZ(qw28?Mxpud8_EBk{ zG`p+wOCkNS=&5m8?PSE37zBH|+Z_dDy+E!d9u6O@lV5u z>*pADH69_SeNSq4hJSkgzYmP;7ar5<2|U_-)L$#xM`Y)u$+fZ!-tw%v3X`925BfNm z5AglLR%*7!k64mDQiOMzHl-OKkH>4@o|`cJq-Oj@`498?HS@WzCO;|Q*Usm6miB55 zZMf>^>myVO-2u|%Nj6Hn2%0=88$fQnK6Sa>7Wf#!SZ&U|0Y=ZNs}T7?+Y)^$KcGh8 zzPBM$P5`;>)ku^*jYt+S1$eT9NSl=|0NFWc9!k%ut5C@xo!9dd5@ePRX7kXW{QP=+ zsNpg!9h&zwji?FPs>FI6Xz$hSBCoGHq^T-iDz7S8W^8Hr!w9t@47;A={hS6OW zQX`V>VBa9|`|(cwnkp*>?#Bd>HA~I|=@q(EW@`tLHY;5K(mseC=#%8?ZV9PT$-X>> zzq4fR?Okj#!sI9OG}&PN)JTr67bH;AD^XA;qH@&dH@ddl^p%*BGYHVIH;{-Ml;aX z;w#_OdgC}&oT(|-Y@|k2VwOU`y^hE1dw!Dj`NsXka{fXug;^7qFJ$@HaGJdNfs>2c z0TDEL~+a#3kZjc(APXr^Y4|!Fj?P{>tlr{rp#hG_N>D9YbtQn)(3&`v| z*gQ7f#UK?nNm0KOA9y`J3DDq~j0Eim70u{Ny274xVX#cKCR+XSgD3;1J)f&ZY!g2e zj6+E~3XF`#jt6@l*xX|YRAJMG(!SdhBNq8a5P~xF$E&ssAp1WEq`McSLM1N27Xcq4 zZQqRLc{rT;cLLL^csYT~9y`U6**R&RWZktOH8wFzS($)S#dP_#*~z{eE)3?<8!C|! z*B>ftYQCgL=!qhGzMy9UnIn}6(bK)jthaCW5WeC8A61qG*z(hY(d0^iV!kb!=OJ^P zcyzb5L<^fOW z`C=REBMsJsqj#gjJxsTIsazpLg-8&Xo zR0kt^*g^UB`A%B$5T_(M|AYPf{!WS5i)Q%&U-Bs+{ds;o@JXMqc-)8GMUgaD2TGGI zvE!K|gje|XRNk^ymdriDq)<^Cj`Zs=^19;68$k3dyBd-9^V?*09ma|&r(yhl^Qv7c zp6sCUE*LxK%+l(&yZ7UONPJ0xcc=s{#T?gXebFMs+F`PIFBY{uYNwKV0K#7HxQOf# zA%Z#NNJ6kgI|<^yDVy?$o3BKiBJmzt8Z0nvmed3zQWGqSB&KyJy~jZR!O&+m5yk)( z#-W_BX3BXe-NhdjGCL^fP}&5THDBHUrdRY*Gp3Eq`@rm+G!Lh{_oGH9+a1XNe^4#+ zF3Yq#T2>)cCGe>?P`TR^AG1!g(-Mj{#j7O8K)7tAD=9=E1%ZZENdG5p!jgxH7(V1v zEf{Uad}u!4589H%*LSTdF((j8q=1;OLN4pL*ShA*X&BvwA2lAW*YD8Sbr5TwoCndX zd8t^kgT~u{>>M-=rMu>%M&#F%P$~fzb{*3ewbqh%E=TNDxkly<5LfuABRz7%DC&Wd z<$1EwZ^V+)G@2;2$))#xPJ$s&8|so_$lFK|$-sDK)XNX&=2 zTMNhzbF%2+frdrzBZ}&3rZ=*@M8;G}^FwImxbm;&&3Pa_3$Mat2LT;AqbTSqlsBVN zQ@76teLAST56aF-)5vtUdeq1y4F?wyk^LlUKy-A>mQSTP8LX!fA_wP-04>1~@+TA= z5VGwq0n7F<`3Ian26{2Z@>BM3j4!Eehy;C*6&92>Us8yOcmfhKx`eQ5;UmGMF=V8I zNN*my!VY{n4Wwu0)u^-)(4n&lC=Yx&3nk^%0lw^@@;)d#Cw)zW>6v*oG8NXug8rer z4s&+#3Ojd8!P6f?AD@J62u9WB}=@R4D<8oZ>Y?SNooY8OVn21ibrFyGb5p& zHxtYbUlP_)G?`>BqseO@nkY2#gaxuMls%;dUk9t;z?joOdNy8-%MJ#5*qng#z?!pg zk`9QlrisiOq3j%mi#A8I?kbNOovd=9Uz#`vS(0xUYFt&xMlb4LFhPG5oILO*$?Ok& zP>K#T8%%lBerFeD?Wk1+iax0fPX#qWrAe|ig3b<{9qvS0VPSo|(9EQSY7wM(Eon_H zZ{pEV_=ocRnmwoCbeDP5`0OB|Lv6$jt^->0=RBaHlIOP$Lhl5$bJjGZ?mmwVrP-}4 zDUKixgXo5aZ4asWu!=wwFZoq2RmuH1KV=MRj8F4fC55oNc%0UpMyk8k~QH2%*xIpXH<)$TA5CR=`Qv-pwq@dhuFHFOMbF3pf}_52W}(je`!ceRm>$8J%M|Z$>BUXl_7f2hLtNYy@ZL zs4`M?iEiC>9tVV$xdJL1#|pF;kI#UXxfQx54pEc?LML-88mbXOs12vhpF=RK*gomk zVdir-AWw^z1LhH(MSg3?L5J8niL!)E2h5wX$=sM5u-OB%lSLZA**R(&pYA@78lPpF zosl7{OVznuH1!4;wjCKHZXxBz*=d5|0Y6is+)B{d2tG608 z;zdIvw^Im~FhVsCoCX_aZ4uPyH1D`_$It`<{+v9*q8vz|c z19r1AGvjgyX3d=QV4g0TUL?m|1Zx7>d9G_Z7zY%+u{YICdq<3u$NTL10=)rHckRavO1s_jiAO)jklu|_UT!RmPNCFh zt!p^7&$ntCgoR?{tLoC&8`uyI2XBDO9T zGgLM>Z7!v#%N|vd!K`MUth3P8lPV^?0Zh;Mn?YxH>dXl^Z$>92Xdw=@(Rqz*O?-Ba zDhHNaqFZ+r$N{0{xGE~wM{1OzUi;vyCw(UeHCj!V8nXbS?N za#clb4xIIHu25**rpNSDZ(v%~sbi+Bxe6NIeVi zfYNHDC57NaChbic%rdte&4?d!D6pwfIy-5QhdNzloo{CYx^h;1yD^;ApiPGO)V4y+ zqw{dOJ3?j<+8uYA-)szN{bn~n>Q&erq^^z84rg6KY3HbUNZn;2HBRec$*j2BP zZ^9`v?26&W+KiokZSukFs9q-Zo-VasE>}*4-T*Z(=fPP{s%8e+A)!=p={%em%VYgA zflxaBI@7}Qn~edjnDhofV`bL2QmzfC&7|{?LUbXNVzUw*w#_SQ12%)W22;L&O*YX+T$(%m9*U{D)Mo7M=c z?;AE4Y*xE2u)qM!nmy;ij8#{6kl6wA0ygcFG~RlSXx&vJH9G5^Jj^~HDbVifn?$v0 z_@-Dp@6cfs=RvR3_$>FrFp?n}DPjbPS7K8$X9rG`IUO*|jZg1~a9GWo(?BvdI3j5~ zKz2y2w~Z_FMuWYmYUb5M!Q3rn}?A@nT1nlnMbzM@Y%8it(N z-GrAFO0{r~wScuosqtBEQ2S&-M4UI7{t!WE2U43i$AH#L=U#6^)p-M;p3OId(sF?# zo#?ghbO5~>qomJ6QKAk;JDhb1rJb{;ar*A=7I|(+O%o1MtLJO^`FZ{8`pc{e*rmX_ z=EQCcANthzto5fxC_@Mowp@PJdcpd)>p>b{UHpW{5HVcLD<+cZ`yc=7|NhIr{ZGO3 zP0M-l^Od2jf4jEFeHgdPE60*3s=q|ZSr$e0uSaKvdeo^n_MDX(o%KC*y%zq_?Jh&g zU?wJBuRod+69W|Y%3;w7l(v`q%iv_gkYg>>2xS%E{;aqo&xBAd2;2#p1j`8yZBNQJ zgnd-|WHEd`R1q=EwAA>Nq}V~4lS9=x2}oNGwE`^$<2R!c$1pP3p%6oCY*-m2{r9Tf zKbaB5=x|0RQri3eNEl{DDl;M&-N*z{{{7dUHWNd4PC_v5Kabbi<6j&_9^gAXClx=} zBU)larJnE@^e;7*F;!(-G2jvy2wc+HE-k?rs z9qQjUBeS043zG#7gOs7_IMtHGaFAJ1t;tfX9G8#9!T@HvQ5mx+$S;Q3y=f0DwKU9f z=57vaYQY!nu3sPTaPxCp*+x8WKZxb)VIaTUg$=a?vN3Q0O8cN+1JkXxJwdWeSt|VH zEwzg)`i@{EO3sc>Y`i_GU>kNxmi-nw5&90z`mEW&sT*U76{L2gSs$AWE&tBMU%i*s z=fsJY>4*-LK4((Ve^8qVU52uAShGDoXY7Fv zlqI7cF=<2jTc~uq%1^LlDMnTAl5M*oxki9ITD4&0KEs4x( zdoQhJ-Ze;b&Kk+t?FTxKGgDUf9wD3DL1|0tX?@9d2TgvMvq4@k<2g5cjfGDEypsak6&gJd{^S7|+ zR*RhB&B|&aGP2NY%>4OHqGhP6XXI7rv{|#{9oGC%dDfciMc9;>=1wH+-QSfg0do&9Po_U>%^=*C@WNUE_WlCrD(nnneM=uGmLq( zHZuy^5bAE`b)M^2D3)zF-t3^y6BJw7VVYVh#;c4!KNy>Y5B6`7(|ar#L+hjv$&#sY z?Y!RsvxCgqW+LL59;~#lz8PN>ZmWL2xvSM`bat+H0iT_dehZ<*>^;N%3PKYRR?fzm z!1F@7rB|~Bu}jxrVS*UxvPap2w34>AzH5bTx^$)S{9I=GP9=!;v}k1>eK4{wYVlEo z;9BozaC$I2&m?U-#M^=sz0$EiguA%*nYN=RLT(=D}hShVprcfKk`)CWPMS{5}ds*|b*!&15nO4kUi zp={aeGMM&JzXT^v6jV8k!;h&}V0I|&U_>A!cX9h?fuz!P8pw`>9FwdKW=C$9kp@cU z;>MpEh8;M^X0DJ~If}HeuH8>%Q3yL&Rn4=bvti97YdS|637VKW&kXn*?4im<$@!2h zA%~E*7#)L(L$lSjeuO(W`R*Oni5)~#E^33*D5PaAS<1S_kovfzJn<$#6Cae3gn~R$ z*kKB#ZiQmit3ZkP_SfJ}Tz1_K9@>BV{!qt1!;rpHn;j+C(`qOS5 zL16C}q{=kk@4f8IgroOXToHTc+2ob1us-M+%12>x6-fQ~3A>*^yp&@p^crlgz-B+w zZ^4F_?@?^sCS@CGSFpIX*!&i3%>8v_PR)%S&@M2eeG-Ld8-3o&ixibO1X=^y@=vl= zu;g^VpEp+HAbnPwU3Ja7*r_Y|+mn*iQ77Q`^Yi|*boHspsE|5g-{gn+b}?#gg-(KW z?SMN6%=+mRNeC%~7o(RP5^P1s=!Uj%AlZ~<-Gv*{Rprr+BLD{X-B^6)hF{duMU-m8 zd{>FPIp{ZO8w1I+kj^kMiXDl*GjT4OMeLv_>ae z3(Mq-I0$>-pR^wS#67gv*VCIKbZF_cS-8^bAKEUaOP87iaJ>fP1n1Gx$Z(dLJ0BEd z{O5<47PT4w3S5m)_(izb{o)9;1Ns^!(&a8dDN*ukaJ}$_U30eTi#Nf#z2?*7%`a{C*J3#@k|0+{)W2M}pAdh?&PHP7e*Vwh4NFpU{Zc-V#)s;+>HP0?-tXrF zzeh*qA4#hS^Rds!-7|X$&P2KG-EwrKg2#a}9b~*$49d@kXSyGt{9MC5G>g7oEH%xd zZv8D*Bt?1)W*l_3Mub+?I&`I>Uo%BcGr03hC z+bR&0nsp;;W6hh@YRRK;M zp+@Cuy^QUko*F2jTnsA5K*&(eS_tnS?yj*oDie@*V6t;i43VGi@cJ5&=XkPnwE~aZ zIf>}Ik|!NBD|p@sfOyn;LBRIz_Lo8F4@j))4mKq>vl^JknVQP)klI+F ztd3_IQC|-GO|P^9k4*Hjt8$yHGhHINM`>Rc>>=~gCeAXXMQTe`GHclIWY5mA#zqQ;YMnw| z#An#PKHp;27Kx0ty5}S`l~~+{`Pb$l3?&B|ZK6#c&4Q87*PjJHM5}E5{?60MutxlXj4pU1yXCZ!e(TmZ#(0rB6 zXJuAY#Z!~)nbhY*NyYaViCgZdtaEa+@R>ZQ(#xiFNyXo9(P}+BMYhH`TCY^?yC}H? zjV)J{-@XSLC;)3~+*(tbW1T4*S76)Z%5Bi#smJPLZ2@qJ#q6VgiNlyV8!IPh1%NbB zRZqaq>Q(2JML48BD}T;DN#@7u*1st$n3%2-Bn%gh3KC6=jZtT7lL*eX93;zxLbrdj zBxWxuNM9--5@<$w2z5b4!{S;Ryc7n7tgkO5x@Su_Qsp{mja1Q5@bHeq8$tVGNb{VC zxeTaT)N>eK?s-~jxNr6cuLLwk{1irJL z%~Pyfx&KV!NLMym_&fzj*OX+|*n}3SX zFkK=iFt05AWpg-u_e$kPS-Y@U0<0t`cy>HQNu0T0;y81#&t2jPGs zzN26&t5aP`9T!>E}NxJ)uU3YbNQzXaIp$DPhlBg{M-8uzoH7`9ZtfVSiotFu zsyF7!@>+CN)xV-nm1s3)4gnMOsKzUO9$9jx&a?7CIiFR&ODpWKcziJ*eMCIoE}7^= zL@PMOfe!)MTviNRmf(C5$OpBpecqFAp9X@MK(fsAmau#M&|D}?R_{uKm1arvoB(9_ zO6YS#*U{>>q$aDkKab&cf?~(J5r0BI8VWUZZNkl^Si*0g!#3rX;vtVn+Xh^;CK0awEcJo3hd8Sx}$mVpD zm~5W&tEj{$b0RF4pIgC|)a??ml>%UgH`Z!ozzd^@GHMoN)^FbKRay4Wl|Fw^#_T`6 z2wny-^_@iI@)z^l`T0L#F5nn8shW1MS^0YQ=|a8sdOT`-gAZHEnn9?jE@mVYOJW{B zL~MrVNqvxCUcS86`YaJxHKYE$WGe#eRWlzh%?Be923#%w(4Oq}T`b4pl2SCh>&%s` zMiF`i#$zdCE~P`NDczKK)v=1#3o%s2%Nf83Jju^q_=%R! zh@1+9gtF@08NjY?F;op$dpb$SGGU#o(Ki^Q&OQLP7|rYO-3o;70mdjVN40T)Y^10> zesj72ShnRc&z8Z7&!1Ivh=XeVZ9FH^W%Zr4z^i`J@K7JM1$(C0tTg=5ZiOV&-Ww10 zuzchahndZv1B3=h=4E>nAue|0EHV;*X5pd=s6|pIKd*gKKwYaW!rPbkjlnn+9^6?R zq88_IIN3_jx1;;W6P&efjtaZ4$Odm`Oite2O7uaHZd`LvYZc~vaB_i3^0<7+u3oMLM{#uI-o)Si>R4R$6nwt})1yVpNo zU#jgSrFp;Mas0gh`cK3hzr}N8*UrG%I~^0Zh9Hd~?HI}xZA?iQa(`zaZBK_4AA1OD zKySx1;EqR7KP!^QAn86mP2VTo9hCYU+S2aeoejeI@{H>~oDGX+*;*0XRuHvdc5bXj zXC#e5Fp2q{q1$~ht+Qq2--6jZi3dbER6l8oXy2Y3s_gF8kJI5IH&zax;dun2EJ7>z znyX(_y*uUcJrqIj7G73xw4oot(GDPL->rpAdmjSzn7WPSA&jaR^Wd)IR z8c23EII^b>(rbVs_r1JUwrrS5Kwc=T$(X#?onBOuyfPw}6n1-A0mvsiM6$LC3DhCQ z$T&hTqF7_nmOTwCMIa|+Pb0-5m}g}VnPMkh7L;g;G9rASDoUr=hw(%QMHvX%*s`Aa zG8$skWYDUxeDo65vSv2}WRefPf56|3GN70)yOcug0o6pdd|nW3>w~VN`=E%kBhE%L z^~{kYl)s9G&msXEkrB93L$s2rc!t8i3?$_zw}N5=G|gioQ>s)qiLlGhU=$S?x$ARU z1aMkrnxR)c=r_m}Aa8DKzQdI|+gF$}JZP(Ozrd3KNtda^lQocy65(tOmGR!F3gIii zp+SI<_ApO_^i2WlXmb#@Bp>yd76=XPEAt{1hi%^c}$MBe~nq3fiPCZiO zKD4{REF!f{fGYi{fgY8c^<*$d@uG}T@U%|~P(B_6h?0h6+z5{vFzK%B0Hl<%?=x5R zdaV_};cU4&WCU1Gi4dN(0q8*RG)J}W0L0T@h2?f-dK)X&LirB`7x>E$cCI}iH(KSF zLc%w7pp4hmpcm4-*DBbGxk6tRpSaL|j$Ic5dN&sBJl+=^X7X6HS}z4rAEX);Sg1J4 zt=`YUwrF9I@LnH_vh}jTO5ltG&`I`rLVte{jEbvV_}_Q<^>IpdC#lzX#Q3{EZkG$z zHqKe}iZ^(CESdigy%g&G1rJ0Ni$Us;B>{Zu8_@YTl-KhOEs0il@JI;z!-NiUlVI^a zSl|sFDH<5UBQ(cAY!oYv&JInNj8AUcDn)>bAN-tN7mk$=z_fE9BXwp zoJPgz?a3b>oUJPJCin&y(vQPGiRdw(R}X?Y=>~u|aV&3iD6CQy-&-P;OT{lAtm_jq zx(;$BRGDNz%?^T|hAfp8hnVV(mV;k~ksdq57A1jKGBMCL(_u#K0ju}35bA-ITEBI6ha zVRjfROIAcGe?jo=Nhdnh)e?z0E{AeNj*#TR7keOkqh!TU#6zGd^A^4LNDzw3k!EH@ zjNTo$SDDt}#O1(qGFK6(PYg3MN+e#8@ga>vUyymU*sy>G(Gs#S`8b29>?bvu4EZFS zM1-;j;+u3@x$wOIT%=JZq2SYkz(FW1J zs?&se_tawr;s`HZF`pR>49?Mdm&$j^s0@11wN;O6!aag- z#nxDmgDY|hIySs$h}6Ba_0Wh(rk%++m$-v?pD+O7^Yn%a)M%_k zDhgV5G*-0Y5V&?E{~t>|8{-Ak0>=OH*5gwXswq+9V-}^c)L6pf}~Uf{#yMFUUq1NXt25T!JoH z8Fn|EA@um#a7W~XFd@Ws|S;1 zLs8mdq7ryv%oP!WJ4?&!E^m+mItaWmkQI%HdlH<_^*PF)JsEEJGr~NCAz<_~33a&C)X!_IF&U@y+QW|iizUxYdBuvSWWBU{WYs-ficc(<@ z(~ZK_079n39SGk-d`QbE<%2!a-aTZBe3zAt+N%q!w8D{S2r(HXExDffoEr{0q2fDH z52$-J0dcM%YwTENcw9r%?U+U+3Ohum#H%0tp5}KFPF*hlMkJR=C{CHGtd^KKW;qOs zpu_^_v$c;wJ*wj6#BYdsA+;hBHB(}J4xzh+Oey>Y<>;LYA%S2Y4T9)S+mvZn(5VUI z>xwZ=9w4|(D+Bc)gx9EugM@AX@Qhv*P+Jh*X?4fB;PT|BjYo?iI>%EilW=I@Z!w|; zA{WK*M2vZy5`32Bs!oG=_jF=~LY>%0K^hyo z#^Ob~)={{)(1dU|51d>eKwMV%!^y|qB$XN{5@w9IWJ5>FAKMhKTf5O`pmS#uGXN+H8YEl;9#+|# zP;o70df?$qP%uKQ0B2vdSiyP^EXXK0H99b(a3ynXOa|Q=)D*Uxjfqi$?T(Ns4I0Q3 z3Zm~op$R1y!pYF<1i_Q0SPsSrA8asa5QeIgH9WfISb#_Yr)ybPYXT{MiLdG3K`WEdp+>(+>+$c z6Dwe0U|R*A&LR&z&>Y&}o7mYEeOh?`ct=?ClxM5))lU%N6!#70kk#XX%OAHbQIN8Di8}&v)2eq5dDls4F1!NkSJk(!WwI<5Gr|B zisCEX)qo+~lAnlvJzk?}Ym*qk2$A(9TV~wp^?SlfH3;L$@}T8g@?ojV!0W;1Ug2AD z_@r6^0|LKD6(*IG;eE6`7A^fXWZ*=iXi+3oddM20Q@B{)z9EnQgrVc`)?7%D7Q%rdt&f)alIYjvn-uz> z0~E8747}oNqO2@sYye5wBbZ+hKP3#9NK2CSEQIbTvq}|`>E%w<5=?yaxojx3A-p4U z6=swsG8 zn%otH3J4;ar06OCT)w5en0o3Cx4AFs~4% zx(q}eA!Gc8=onJtc%>GFtSVUzhIX$a3%~G$LL|}X`Gu9=WLq>l5Ryq#zYf@7fM;!# z#+r8AFH}1bi$x*YoJh?I8XuPifkk=sxG?n{i%Qm*X16#|rN7Aj#D`t0G!*S`0W=lj zS@`e{9GeC#myQ#P9#25FDSi(*p};_N%uwZy>c-E-&xY&D z^tgy91~0fJRVt`}nz&su-#^$!L^|L@e)Tn+4<(=H*)$~r)hj`%u98H=t93atyKVT? z%B<80L7NSQzNrJp?V@iM#|jeNeFzSr3XK%ir{-;(Ja4p!^ks}%`cjGs>*px;I5{CV z+7;;j{ZtJ?T#?G9iI{3=7VD@p}*k}n=-KSc!k6k1^rM;GRU+0j_URl1S^@>7*`k$Ubf?nxnz`IRfFwyqm0ATNmI@_Z>O8=s!kQ8n?&0vP48`(yKrE3+H3ZJ>M!b`+P<;&1 z3@s5P>bZcZ04ZJ>?k|C(I>ya&ED+6`It?L;=s1}|b%;ROhv+a&us~m?mH=iPW85Vv z!rGy*pxe8p^Wb?idsNq6=m`KsC(*X15wc78kU~S!or{QHdn^!@3S6L_u`p3(HH~5* zP=tXbg2TxFMHo9v zXc-}W01ZOlQ>Zx8uss~{ByBui4+ODzQnZJ|2;$z^I$TI})YA4A7oODh7`+2(Ld)q5 zU2mOhSkqe%IjiRh4mc{JLf_Z){BapdJte*}NPM6=heas!qa6536+!x$UKTP-ge_3_ zm@E>0FHX1c~l84BFHaFUpKQ(K{R;)^bGb4 zN-z$G(r5w7XbDe|u3>vij0jL326gcNQ_G0?J5HgXqOT(Q5DJ0j!A8LA+|p_IZ~^-8 zalM6=rWUjOS{zksbP1rK`oW`WvE$tn%%Fn+r%$7=ZgnAE#NhfMY5@h}0}pt8i+?XU zLUrwF)E~v{ip~vZvE}+WD&plrh*5*9nqCWyQXYigv5d2;I}24LT#Oa$LP(yV7-%vP zZ{ngIB>F@ujUDl3%~wg%Wd|;~vgr?Yq01I)L1y7u&G>9zfGy70Y2t^%DaiM%P)VhnUR_+H7Y2V4x13^11 zJ>=E*L9D7@O!0x;P$@j=DO@tbvK)_sSfZKR-NT3Ez8<5L8=>k&KTg;tl;k=LR~nbc z;X~DB3<9E$K`JB)Wfx*D)-4T^D9&#mf0grd96kyPi|Nqs1MsO9c2#8jJH$^Bl+87b z0Z4Mv0no>vd9pD8gAr~%CrFuLzN0ACv9}z&?H_0YFpGiDV~+S+pEUcJ3lLgNW1OsG zn8e2%lTd@C=`M?NWM?>9W6+OF&s`8tOV2kRVIPNm4Y&{CpbCr++Bz8D(SamO9YXCJ zFY#=K1u|%q={eDc4se||U+B1V;Og6&^?7E1+4>a$uJhLBo2tA%RXV;wfXq7Fpq~() z6PyhF7ZYzzdIze2>H~HZWAQvg9-Mh8D_kd?R7y8IjCGwk9iuVw`k}DXGg8DvFl$l%1)Nwx_@oRFPOTXez(rC@dSW z`slZuMUM|6?3|wyQ}Hci#vOzQ4OwFJ`FJ7rJOh3oN(-f%_go+ic$P??aa&_R(jeh* zVFps#sQ$q~pyqpH^l1X9pPQpk;{J}t%Rud5F1&5BOnn1~aMx100q_Kc681YKUG{+- zM_&u$JpLGFcUZpYS4iAZw3c2}zXZt0k5Xo`zGBi+U6mBKt*;y-3*WFGbRjrfx_Y7X zBbFMk4<8?eN@<}Nw9Q1i0+}OX$kPxJ(}~-6T_EePB-rb>^{b(v`UI4kQ{Fc|4?wv= zK$JRzFa}^Mf`}DL=OJ|KATorJELEePUm?}JfpAf5H91m#mg0f&K_po7bK=N%^()sz zpOBk5BtB_OQINDbENgbbG&pr7?d|EJxoyK~fJ9?;WP0n)#vsM`J}iA~NaMR(M9f0k z(uM*51WIY-^IFAg%55_~vw*e{V?F8D0HuN9un-Cdu~NuWv}*%uJnBm*rFUV-@@Y|O z;=w1~7EpcXmxNIm)$=P_g>L>rqSDS$OWYl8TXA|+E1QcQ&Y`LD_OKLM(bKAL^T5ME zCgN;<;53*NQaPElEQ3}s3lyzVzaca}djQP#Nv#YDPpVRjtO7Ps8GtJN-zdL!?UA#CmNbPsUsuM zfsaKDDl=l<$c_G}&~e4QQ{nnmehiT8w&%*FW3kuT-mXHd;kfWFt{-^M9?Nc>$#8wxHN+=5Hjq|1(1anxW&}>Xuv3>uv`?QKbXk| zaP*T?i#Y+HXY?qD?4VGifEEbpc8NpY_PKD6Mm4&qe1%ArI_GJhSs@JVF+*mZT6-PU z=%Ua**{;ek0hBD=dCo~8Lsre9Q3r*cqZNWuBXasws^{Q$8??DaIWa`O>dT3OL|W3l6hI$D zaZy`I7z9PPpt&W8_@pgG#3!At{Ux#H)qFYRYQyQ{vZ2>s1(O*=jukM2O&`jJVr?kD zL$a6_4v^Vv4CEtP%PB})f#4Tlq%cW*? zV|jYgHM$+NKNKbKbXW{468uI-#=3xV3H}vNqQ*gsI4)~H%$2q% zMwHSDPH*&cxTT5C;={@$ovnqE*>|`cbYRn(gE<`YK*9|truUP1japopO!V+1#yv8~ z@y)bk$x+SO(AzZjFocaRFxjm1fJdsuc46ixbKYPwJTVGzN68jIJ(ZH`R}!EF;#Q`j zhl!D^T(&%SjvvoQ=MQNQ`qf}W1`OmT^zbOAm=IoNzyMINC^y2C0i`dWfiLkvm_S^B zMyykmOaOBnOe~Q;*(L+12WCi}25+8*70-!lCL-ho&kq5~#s)Q`fiGIs34TOmwHU~GAAXo<2AwfsI03<&2&GLF3>~0b zgna<80gmuEZ)#djAD67!SghF&GABe3yVK~Vq=`r)Gc=?t!f8N&1u9Jt+q;THfv6&<&m21jdLyuhwI&qegB735EfAUuhtW14AMi^YW_naINb_2f!NX*)2$BZTy_n{P4q}oBV^HFg%3oy<#xR^r{&V1jtaETu zYkyhFfexqGLu)w%4xOHwo&!_}PHit*aG=mK-LD)QJ+M)md=?q3rD}MbsL%&(>4 zUk*B7iOPhQaINDBBLxY4j@N@Q!9(G>-UPvfN+Acuj|sr8a3Z6mWmXUs^`;$A>wwm7 zP>nCg{Kaaen>z!jhlEYu@EXOdKbJ_U!e9fPc3Nqr6ERrYrs%64#~@}$AG&PeaWV`K zx-64PuqbRMKoR8Ln0K|~Az_i3(R_?1FNHl8tBD^Ju2Jzc#*6TZL!-KZM5N}?G?iowQRHCL}lNK*RoUqpPF8dl^M|CR zAGV&0f3KVB+gP0r*K4gk2xDaWs412f-SHu;_|;w}vTj$YvSy1`H?Q9y$~rljXxb!7 zYypPtFr=T}QFj!0`~31qoq3(V$@0@GP>_A$|d@N!T6JU$It+9ck~U=yzp?P5Nz1W6Los~c2NFXNOQL|9fr(jHJg~XkcH=*?lTp^I|5~f9A|;d z^IC#>lw#3qB9BNs)(hfq8v0DlZ5IDjre|4yvY3l_w$#8ePgSw)=%w!zptR*ygL0CN zzP>OyM3=cZhB&jlE<1wxcwgYwx>y+};E0>vnr8v>FTv=@qCihI_1 zJ7T3OSR_6q65TK83wlgDY&B|-0I@b&MYTXYgK;Yg<^wuE96our1cmw-uQL-<-h)w# zbhTt87GhFAK##`h3K$6}wH#Sr7Rk7P$=U>uygf**EWqfq#7GvHG1!} z-*7A*5uUR|b*FuG7A$$%Fy|izfZU_34CK+s#@=;}(I|NYN9k`ug7hZVoq0iKGO=G9 z?Uz?{Z<&hBD8%#%VTDSNZf04A2N9=YS6F&2PQ3M~K{%<5?ek)WGvH`@_$bj0I5*_I zNhLKWkI!kq)Ni(JpJOnhR2}pC2+5iWGYz)fl#OOo+W9i8AEVNU6WKD=b2uR0N|8$F z5Br)9lmupkpEGiH8rBX7y5LPKH$u!8mdD0lUa-oiTtXYyIjTtngxS$ATFNJO_vB-sP zahGy|PC5KJ{+Md!*lN2($f-Bt-IR~J4JYa;cJS(iAY?aB&pxV&Iw8$QroM(E8b+Hh zIbyTyiy{QAsJUwgq_)pM4P!VYoa~TlZHL>%ZFbq$gK}uBFj$p1T4-!4FbMi^<)A?7 z4DdHFNJR4`knFOeZ#?kF`LZvHsl1-W8ql4pG-kvzzM4ooi%@W3BzRaHMp_P~r>#>^ za>bF_JN3Y=V!IY8e>&JAnD{a5($TbfYQiXP({rpcxj|$yc(ku0a{wURtN4zsR761u zbjq;~IIyaFhzF_+Luqe%4{|G*zCdmQQf1SaLj4rOEsmq4bR~5JBx`C^>d1wtRvtrP zoMOp>^?}R*fOtBqAPqrD@g$34=qn`XMWd%qr@l2vm8AjNrL-w*BN(CuGlcrVI6N0G zi=qQ2%kwCx0AD#grY$!b#N+Xn%m86k!L*k3*bufy%RH%YPYdC1RYHM$F9vW!G-U~E z*W9&W>PjdcX$!SHNZBCA;)Kr)6wLvk(^RM}2~%qS5!OF=iCPW;{mex;31%Cj)T`H9zrmC`yc|1U_s@ zl~SSe_>BoDJzbgYod9O3EUCtdjl+eCV^B5wNWUJAD|P1hO4hBxMy7oXMa>!UVS? zS8r3M{*F9`OR-jgYpr6@k{X`VRDlP!G|fbV_{TH}62y@{o)K$dfcHj=!1Wl*uCOR# z5JY#a>JboaGu^oVOs=gy5|EXkUWM4%3UCrgUe&N$0ltTUZVO6X|1Hyk$Fvp!Z^Eai z>c6#bde{?b*zxGm3M@9plL=wuT*IgsBUUZ3?HjLd^|$a?5!qU??U_7fCI2oa1Dt1T zzj0nY-??_S+IkWp!3<>eqjh%S_s)Zg*yc>0+QAbR)(2L@Bf+ak0*bX3S>twQ$y~81z;`V(2{n~bvKBh~s04WPJ>f_JWw&P%X zX}WB)0!dT(Er`vU^tvu(6ZF_t$m_{w(ec^J_7|-w4te$~+kY9p_Lhe91$Oh;2rBF1 zt@qk-y!I($$RjlCDEkauxa0ZQar^+MOjb~Cdm@5-R-J3E z6bY^GnHWtV%a#+Pg=P>iw^bw=$ADl;cjr7A8q0ea=nWbK%ympF&1^$vVvMOqyIYty zj$QPSoC_L+%Wo7(N$FjTZQA(u8Jj0Z4ie%VEG-@GJ!cGEB>5e| zk@Rp72bN#f*4YIUs0!8|>+3o2q=`T?wI*&^kFtDymDZjO3{>TuT;-;MpsEmDo0kqh zXbh7SusJTa)1d`8c3;&XB6*GtqA?D85JY#U#Q~XVwN(*yhY{kW?gQ;vo102qUS zAc*c>vRfTYuPpKC&QNhnZ6H;@)TdH97%Q^|o3jMsw#O?70HgnD3_?`{^)q-*-%E3} z{jRYblcnY(cVZ zvJp6X&`y)r$;1|O1U*Df*qof#(e%4EXR-Nfsd_bR*Fjn(=W>=-O-J(!(G%U&=?*Ps zDSBZBr$b8wwjHUVqt)S)c-YM>6@B$r!d`EJd5%?cK;LhniuMm>etAmOE6*Fp-YkJ`wi-2U zNeRkmyc&9y641KGD^P^>pfM=lu3585jx-%;0c}mcmiev&rVUc8|2z*VHUAD@W=PG` zhf>ex9C~*{;D?&fRHa@w=!NH>>_Q{B=>^aZKxtC#D3H3BEz#;;&q7E<$kmIg7ATcAc8pzm#At7!4ktHEzBDKGr7ChA#jGck>~st zGg2MvBxq}?x|3zW)nB{C1{)-GN9@K?%h&o^C#;=pm89j%<3m6%Qhn-+NETYEq|amR z@9%Yrj8{s(ZIldzV3yLK?UbZ3$}4oKo#KJ!4;XN$Q&Ld=Qdb0EdQC1hm^(ciMt|dA zpQL~^x-AvtvHB_LkkM-IaUNhp@7x+DXYS>26eU6Oi?)e~{LN0PBTp0M$H zBy~2cwQ;ONlBcx&dAtevo@y4LZS!zCLnu7e#*j6C+aPHI7>VX=uK=^yyxfM@AIa&g zo<^@xAa#Kf zL-AVUQZPCRD$}1L-LtMUP5GP9hfgywaRKTuuj4Z>7_s72EZ0C*=Cu-pfb%sNcOKMQ z^n;l6D;H`Y8%zdSVcq{AB6lxKwJa+hF;>Pss<*r2$m2)BD6v{Nd%Sg=9f=f##9hVH zIFhmUh*>?2>p6x+rlL4y=Lw0NTSFs1q|h`~h4B?=t>7}!7|(ta8V|ML2Jx>qSq&mF zMCH%z&WMlarnANNiV3MBw+NIl(}RRV_(c|7Jc)07K}W#8p0V)#Cri&^e5qJ7tmlFsurT$U z(>Y^eqHfBnGUP@Q+HAgKNDyPznTT{}Q_Lm@u+@)(vI)&bC{N~$VJy#Ft;n?wKke$r zc(zurm6+TDsqg#_lvOSY2Agj|MUuz zad7w0+A>`z5MiiM^bA3!%21KvBq^{23)4>bWj{&tUGTj%;`_z-?rUj|avjv%@wXc$ zZrC9)#+b}cb{La(_6kxau;rJk&>|@p=esZSXD(X3nqK%jNn>^Z#ePkIvWYcHGKN=; z8m@SuPcPz8r#eUmOv7Sc3TeS_!NPPnj~;6@;h1DBNs&%sX}y#$!h(8rEYX^`Y)~dx z%Y4wUaTdXEM@}+!vEVESw%`^mNfXM7GARnxmYx~jELn-zRf+6%T4l|BEKZVA&;tj< zqsrBKzC*=HvNwwt1=GhN+1|l&=Hh1X*ykak{a_3!lz$yQd;|7(53kXV4&ziEa>&eh z_EHp(Kw91`u9U!OMNfP&9)0`G_FY06qvXU=ZcpcI$SJ~sO<0_nnt%XE{q6=3n=$II z=s^K4-Y(dPQw{^Bxq*GFp+-=1yg+K(OOJ0Bpl{LDJf=mH(B8f~gFLKoM-$b^W4c|1 zwr~t0l+1BWuUH;Ju$=*8wPd>!Ny4yMUyJd`US~|S^|g-3)QHQ3z~KQr7~&XG4)&6h z0#0!LFyGgct?Olv0!BWvcr8&L!eqYz7=tD~vUCAcPYW}Z(rann{4hT_Q)U?18C}e9 zK_-mMG+ox#uuqMcRzlfuq5$I)Q8I!ulNe_}v+44ipuGqgj)7)z3R9Cx8$2583@c(a z^U6N#N3MmxLDpfs#md_tuH3AN&b@`U?%YTX3WKSj7G#4brhsNqq3>(S-&0@L=L%$VB9MLs5P6(XfvRh z4?^)Kt)Sp>(Z`Eg+A?0CkdXVK7@yk|VkljHU$t0*j24}wE-*LnO2UY+J?({o zU6hNtJfK#pWyE{au(&3BRow(*P}V?gjPjc#H^W(m$&7I_7lL)vIHHNeg)lyl9Wy`d zW>l&+?Dd^O4T{4NX35f%EW5n5DS;&e59SRp>Rq@okJ4kBW9XfbWfIK}oz+aE+1DZ1 zUhw}YxmEz)Dq z${*HkV-{bSS_I!l`O^hvt7uh9hf1M*9!q~(vG~n36~niZXIOY0)3P&2q3EH{D_PwK z9fBQ(^Md@MJU>X$Az1W?J2ihOBJ{@%^aSaL+9ZvKl&6|6n0Iq>nC96&ELlYcSRkSs zw(jFi7CSD2rC>t)eV9qiN(?rPb(N%^f$_+%Vp5VqqLYQU0F50JPs)m@V+=WfDPS<= z4%?LcDh3pdJXBTEP{WQ#9Ry8xXCSkZo!Y(SfpVu~6@{p_EKJe(0K8ku?XUNj_OC^Y zVS>h3Fyfh%iC;K3BY?0a1qFN8=V$ud2Y0gpKsY1s4o(qr=7of?6C?54N5nh8X1W#OFfj;%bG3VNo#{TCPK3r2n?6*3?cju(*pjv(i^6%TU=vmTjbiJ!4a6kEs0!jbS@{NAXjb>G6M}G#$kd00#H&5t^Q0%ChgMe!4jwZ&DH> zMJ-SehTO8NIyW_W~QKYT~~qo*87+u){D z-T{{SRu_}1M`{P}V?qjGZ#z<;0>&VbVKO@^7H6Pw2UJxuz|s|laP48n)L52SoPowo zUuTnMpX84lHG0M|u{Z+^jUjz?QxTdWTrCf=i<;KSl&ALvTa$*)!{UrPMU=5>SOdVw zCbONAw}zNTk04`%Q-)q3rO6Zt-g+~a3Zt3K&WEr}@Cv4!8BMC_BPLrl{48xgnis7T z5Y{Hd-516BMi|N#zCi|Eg%82Bo}eLoHs`2WjqtL~5*73w zQ|L;VP7(&kfRlI3qDkOU@k<>t&s?xMgB!(hy5?jySws|cODW^UR5R4+Bi<|Rb5~Z> zvrtyCmwu|HCM*~LuZ?^J7^m@Q8Y8|FnG^^IfG`xo;__}BJ*ajH4#>Y#T z<9DpEZzDs-1<^4bGIRg#Xs=2E992asf*=tHt*(9&sb38Z!BFu*eGQGDc3m=_Jq<(hGz?wf~*`-u^ASW47HW`YI=B7rDb zrUgJzcJ4{vcpYKZ9Q8&qYlw5lh=2S(j7$3QrxS^s%VGT*Dak6mqMtz^{MhZBuaaDIcBuYz=GE83*(CGd!}FS{H@KVX+E>j zD(nrnMyNDX2<~uMV6?`TF^WhjwZto;lQ8c0>l!Mwg469m`8<&&g-~KhLZQO< z^}`%OQTJT13M0ppSC!GlY#CDNvY1q99wjIGP$kaPopVge89e5|(xHTg5FR!T_0=Kj ziSd8Ooo2KPz3J1I3V}2)f?Hd|)STeMbB)9jW7rJ4jY3pH3a>Y}?JE++=!j`yoM=yi zbgHIwNZ!ycp^B7Q#87|jFvpdEP_~ANykR5JxRLg#Q~ORBlMVr9=rG2~LyP9msZ5i4 z9)geyTBtjszlq`M$Y7PiPEr{~*G}}Rl3KyjB_f39ON5pfx$af28f64j^WPaqb%4tF zP0V2e)2agtRwOW}$p9{dgdfw|gb@%PYD&Rna<6riju7KUaM_7T2CId}2;E36MW(?K zKljCOWwMy;%lJx22MtO3JWMw0$}_sI>XA3PUwV6p~}ax?`zpCw#635 zzhYkZeNV1-5pz%=&H(f9=&U3&P37u}BHy!DEt(1>rLls*08gz9nS$hSWEE2~5c`I8 z@ru>2`#@{nl&13xuvW6y@?%z#k??aol^j(SD8yD6LXVzeV{gY3r-K?$f7 zLpUZRK=l`jgsGtP!m5>)QOPDHvE-@LSN2#{CV>(<(#SkfZR$+6(ci?V>;k}|A^wfIO9Mu<5ixJ*EMvEc zx*iB?1orKK0|XkIOlTZ$U@^QA)*u?oiXQF|H=GH*;_wc6njA!tFv=k0{DwROLv!Uf zY62M<3nDh25r8p6H3y$27r)MdMe*QPAQ4qtIb9b);MVgrH-Tg!L>f+W*n*Bw;{~&T zlqN^C`W6jd4CO|MagrOcF_HCk(s`fn z8+KDEG;R^}3fo0)n}KAky344lqh|^F!Y)z0?2=#H0|jC-Dj81YSV_|yk6!5awJb_~ z?)Xlz@(S@Ot_kf{gogTL6(B&JDAqwpjpThyOmYjPU5UqF8sV5l zasq69n%)3RJVIPXi(?3rVK)=F3n%H|gZ3YA!U!hCU7||4;S)iy@1F+@xI_$RNDI@n z&+a)zp@Rz_KtukEZrTt+;RqPGYt3KZcL|^qNCUBNjOnFg>l|q@ros`u6*d^EPJ9%_ ztj_(V8YE21CATN@No`*}r3eTFH31p@2TL(mTL=xVHF`;H#4#Q_rQqo;bSNuXUI7^t z1!{k@X3npm$j9Ftq(fNNZPWQH!zCpo z@J5HkJJ_%U_o+k+krszHk_v>LEU9lu%pL#)zL=3CuOeNg;j@D&|QW$ z9?<9kipnU6>}`*xk6QqZ*ce`sgQ7TQVJ*c{h~ zx{e(V`+`Cws53-Sts1C(p}w6cSPc37B|{NK>(E%83?jCOsl;k00*uk~pk$UDHLf0i zBFYx(CHp~bDqd-TBX&x-k0^MkprG>e!cZIv8B~WcU8qADhl83r8H58xX^-ldDK8A3 zE=8J}TR`4n+5Xsvg`^K5J-kf9bYxuu)2oVA6>MZ?qfI>Ct|c(04pSI)qkRkp!bD zl)^J)xTI=SbQEgNL+>RuWXgB(mV+E6CyBiXgj>1e-_?Flm30^Y1;a+>-+zFQv|5X({cnHuC3l;5B&(Bn_ z>A60L_mN0Fk}DZ4H#tZo~w-FM`2Y{9W?sva;T_^&(!wkL)Y8^tVHI8J258oXdwRf|t0t!0O( zAc{0Q+1yy$+1D_LipElvN2P)t3OUeIvpPmYy*$&b@@5Q?`ZNrY9&YHoql8LR8FiPT zNZFL^Gsy9)jw`OA1cb&9sWqx5mRZEobX(=!1IMr+EPH4M8rR*=!6dPbQuCzl(3W5+ z*4e4#ScFe9P9+pwjTtyknv&XL=FQ>31RLU1v{Izuh_UR&aDXsrjc5TAbMR!A^bUy< z+!ECrU?BEQWj%ttyi6YL62h7c1{qZcJRLi$=?PhjVriY@?$O_kq3hhP7h*qz_U6}~CaNp-Xayu`Z%7!`7|eU?gR z^4dO838By=RwcH*3^^XEu3dy5zQgqJP9EmrBXPTc0e}v1@A0_MU?B2Lh!s*4=l+j> z{g;3H*T4PsZ-4)<|M72s{nKA42?}wgfB)Ox|MZtUJz2lsl7U6hJqVDq+J2>}rO=Xa zpusF#Qk)P{RGy50f^nowJfx#u*iZyzQbPw8#cSx@#zerS!9$3^v~q3+7}tBOxP$7F zEnySzWpE6sXj0ru!(Rs!Q`})d;$MVKPQf*v3As>m=9!OmjKT<)4%e$1@n$sXH^xB` z)ABgIu3OLH>O=FOWOWuJq|Oauk-T&Q#GAW^FL6}kIH$;*!*`F%zMU!s5f*bcrY%Ie z?;WqIhQ^v*GB6G*#E8wAQeT+}C4J@?yxFJi`UixjL3M?kH)KVWO?W98rPQNf3ijb4X z$rW-8B|EGvj?ey@U=aBQj%^Fm=VXr|R;=NFJ?t1N#}aNcz>rbv1Cw)#h)6RXIFeK3 z8CI~T$|z22a$GG(bXC5%5g#4MC<2L*k^D+Nk&KOJ4axwEB&Hj+LU1GbM4n-#B)^hP z1hroKLe}IQqz?3kkU$-#bps@3I?{;YO|T0C5Io*b!c3QHOf+MeOa-{8MF{;?Mty5k~#|*DgmnKxgYV_CL-%> z*E~u{y*q%E4!RMn9!VjB6Dtd8rMo7OLMg1nDA!{Tk7p1M)8`Z*9-owev`V4A zPd6s2ZONMiq@k8(;Bad<Y)Vr93!l$s)e zaX7>!N;gt|BWXh(aZr}e5ZUn>NX}6kg3@H0vN8qN_tUxIGPbGu+JKwSvs3Hr==tm# zbC5FPsnL{6tzw6wim)o92buMm_cKSZC$67SQ_i6))9t2Fh)Eg0Oxau6}Y3^nW(9DA!tM9tR5tx z;80a*niLdabLlY-x9D(!zZvl1sEYFJ)*T*{O+}=&_{P+Uy^6TfdNRccwV;$RXhs4P zADp4olEju6U?vJxp)<;S83d9njT!hNbSm zrK?GpIsu++kZ;gn$;LfW3SX@me6cycq^&iYywBoU!Ras-YYZss_y|kme@9=_d*djK z8k|X$AutSKWr@297N-o)p{<%#a+Y~aWe4KQU$*FS>hzvXUZ1`YHihc#F@%G(nKR=^ z^tqrqb1hh8Wz$*E+M7KXNnXXbeTGCYmW0JX0b@kCW#Y zmFYl@R&A$|S%a_kFr(EP1PV7p(FoX`pJzq^yc=7q@Y2qkQhD*gab^Of9h~)@X=WM{ zdz4!aUuX{_?M-}TZk9F^I-HWkF>tga)u5E4GugsDG>m4E=D08h4zJv#gu|cpBPowp}?;uPun=v5%E7y7h?Qm=MR5pgKN#ffY-X(&N3|pVEPZ zASC4_^`-!G@yQG*YGLeBSg9cm`9p;A=xqE2uX(!uuHcvfgsBt90cp1l)T>kaqfksy zZV8PkI6M=wlwRgQdw6&|%(_Qi)>wU-@91kdI}@LDoEMDGu~Mkx^x$K||tv zv+tmqc23>etTU_;^nJ_}LJXIn9GV{5>8gXcN!xmE`z~fDNQ`#yo=(NUxv=C~PP z+(b#GB~4;KzNH|D4{OoE7q%2U?(Y1P5|o1?s4J6=H3x=RpTUZ|3nLq1#1^$qEKFYx z9jN%zinWe3riW)B3h5SN+ySlnak|x+4qS4aUZrwYE8+J^e$hnF@Onlu1ON~LBb%Sq zJH=!k0t5t_;uB5*@SsJ%FR-%sRe+ayP0Z5J5?aQA#lgw+WK%}-q;r<-F)TO;vU885 z!ZV1-u@Z`TD8ylR4u8@_?AbCPimg3^cmoe(tQo@3&(mVhXma6%06zJ0 zHgwZK%YqLd9*hf#aadD;mHyB7m65WYnAeTSxU{ zz>9N^z7H9m0H+e4(E`?ZZ0%|*FdJ=!2{Fvz1P?38W(nMTklK4hMoF6Fu(oHhtun5h zvPAg|I3xo4M3!eFgnMlSD&=ntwfBH&dG0&AhgBHqfKnnxRet-rtp|YSbJR-dlu99o zax^9p=m`&)fh>>#<1XX69$Oo9Krq#kA;o9t$!!v=G`xgUqul7}VHdrE`V=9?L|X?K zOYSj?Q-U3}OC99A1SVwbNUbVLTrIN>Uf%8@z$qpPLcH(x z!bB+pd?%KSfl-=$W9P@Fp^UIJJWm~8qlEfWwj5!E(Mnd7FwRY0ly0A(p;q*AtIX^Q zCR0Csjla%_AZBVZ?d5|Np+{V`NJT69uq3A^eQJM;BdxN9B|2y~iPPi4K3zeblZ42>zM!DO4VdKvWV;3OOI;N-!NJ(#IMS-@NE zmf==oy#q-ts4Q@N7Zgy)j4zD~{=n!FEe{RF131iqXlPDo59(hXK1nJ(079C8-JjHM zL1qCb)rH2eR7cw4h;5L{C|ooWa1{421&3?8mw>dCVM+ZCAg$(sKLiA-M>CM&BCcnO zxDXhQRV4#5@rj|p=x|}jvwBDFnmpn%`~lfFgA!)+^+j;5Zxn4Eq3{kyj%lD7IDCV> zB&}8vn*y{0Nh`uFTVMtf*YGU?>1pKN=^I1llp;qPIa;GUbECX0CEPhY{U;1Gam9t?4X~(Sf?|S5nt8{&((lj)JW+QPo z(PJCA`%2i2o=Vrqt>l#z%&fv@F#y;TS#3nsh!2emEUg!J^!EmmP57@4WcCAyprl3W zcjAZ7i@O@B7F9;*&t%hmoLIu*JJCbBPQ67ol@c+MA*KfC!D58J48b=+U~IS?Q0+aD zvwwU`^PEx}M9Cbks3ff+Xa<69(i%p%?mNLYidj6VnnRM@0&o+XVAY#Qq2fM7D~O6mSvLd7P(M1;0JI}lLseOk9zrB+-601UvgEG3r_a0YZR-{(i=x z6XqdPcxR!J3k(%hq%#$|Vjqftd1K=-yO78ijr+HF8xvTehS8Bzl_P7x!qD3imT^$D zh9rYB8}0$CUO7M&gCoJLy%JP3g*y;^5Xr7-DgOz8*w}3BO$lF%sdMjf}FF z!P6#r6%$T6Erl)c;(G=VRXcVQQI(ZqsWe8js9T7w5kp)8fQgT9CX?iu-Q*op|Bqf_SHpZyLIwg7+HA|uwpGv zfywgHlW9|hsicks&KcZrv+eQ_YxT#T3=5AyD{dFroFXyJeeH96mR;ch?fR0D1t7l_C7w7QcdLv00hC4KvbYS6$9$|9VH#VNgL36}bO;hkV6wo5f=zzm2td#AO{H@VfbjAT1X|@^a@;DXwM|f zS1lSgE^6ee^#}`HU%G6zq&woMh6ZzpJzR3zh<31%!@F`8%2H(+iyX8gJAPq;DhS{? zW?y|!s?Mpi(LvG1p$3&QRK5BU5M8%Ii*Y$OPI{hMNmL|2J9Bt(7PVM>>J%p$MmJ?ko;UTkD1-q&|=~=;}DkG9bIsm;L zY<~{-*b$XfZ6k(o7nWCGa16fqkePZA{6Q}|uyMSd zPmd0r3)EJt{uGfRLPrnMH`|LG2T?=ICH{2zMK1k5TlGYpl9vps4o+l|n(Qp%Vr-G< z@gk>tEK0XY6z7y^Qt&w|*x9n^Mx3QaH+jJdaM5egxGV&>tiU#D3A1Qu>(U6If0zS_6S}WYy1@0milOD@+tp zos-Xs$ScIZtUjDLGTE6CMkVfyY+1ERROp1(56O3i!Z3nF*L_Z^lW00@ss|CFdR=l! zjGw-ec?c{jD_dP_%o3rEElP_HuaZeu-Ew+HuqRNacTD~28RHlrIpmeT)a?{pm0NXDMzH0K8igHDvge-VKB+!_QH1RoRqVsC@uhY{wFU4N`l zEu>Z)CDcD4KM;KxiE$7fxMau(b>uWvQBgurHo>$$Co^W81!zDNS+9PQ9yBC5F-Sb8 zZW2Z&vw=1y(@_gX=f+1uebEosKfmegVrCtU42(?tx%~B?LgIP{Z{~H4Lg_`5N+^SP zG!fSUYQve0TEVw|KC7TAz&XVB*_bdl1`Zs?Sc)9{oX%MOk>nK!?@Ew5a8U>JMjYrJTUDgj^vnPa1GzEQZJF zV6y_VR#3aLTu`zQuP`oemxN3Gap1a!l{e7|$6=iWX$pd5UPRd_MbmfLdRs<{F0KTuJi{L zPDKPW%OBAxrHh!Swevq+kN0zFE%H=>9ExPgqiW6$6;}Ed!9S+UQB)5TXr{a3Mq`Agp4h&2 zc5y?o%acqDSx(h+#?Z(VG>imbeFQ0028c89VK_ubOm@V2vN3}mBKFRRWbQe#4P8ZV zrqeTRlO}D(BqzC0U`7+{uZ#jx6RR;7jF(sf>6$ng9);wIgy5AGHA>ZKH>7GbKpuQM`LAsiQQxkgz9&9I# za)DxB*Wrl$n~~j~d`3oeH>mKg%i@c&j}o$jf*3ehbX7sROcLUlK!X z-^j7>MfSO1wCh>Q(2a{UV$7Z;?()rzYzyaLgg7j$iBF<6ZfOppD}q^-+RVCTrrM~8 zX6MLAF(F0v3^DWw_HgfzV-z4Q=LRoZ!p zb45-eq83>X@sf{%Aur?bXr#5Haw>95@Gvt5caYoEa0=8!fJbkT^3Xs^CM@I>5oBh8 z13F2YpsU!QLIy6}2K`9Lb#J4@sW}}C8J^Dc~YS_F3STU%>ei(&UDR9H! z0f8R5feVJ|F#Lj=e|o8ah@tSq(6IBl z(SOYHb=blKh;CzwAK^jS1IwMz27?uTS1Zl!GOkKL?i8mIL0IkLV;ls*!GtY5f^e_o zJj%l_pMwV&p9KxEYd3xnAwi)qEhMt+T%A zqANXpYh333k7q9~Qufy=R?6LBuzDl}ja=H3Li3}R5-_|@QWm)&#Y)Q(`%kp-ExaoS zHOuUvElCs>ujua8am)N=L`HteaT+5SM$b8bF^Fw3Oaly9)3WNZS1?+zgd$|syQstj z8NrbBN}@2R9DG2W24ptg8$XhnxwUNwOtey88fm`QBrR% zYDG1sUiliQLwDAG#ZyEEsGthufw7so6L3PK&lC_=OTi76A}5s?o}eYFmzDQn$ z@aW3Z=&XRWOm&Tbv-iwCg5D+VZ#m@Y>+>_Ts{sgp7#18 zKole0BB=4hyA2Elb3Fcx7fK8#G~H>BM<{CQa!LiyF2)See4agUnEPnSkO>1N7IrnF zJdgF_`FG3~;8R=gPT_+ffph9aOzVO7etlzMa$J*cwsK*WaudX)wXOXt=g-l>3p$V- z2_Z8qW1@n%!cixOm=RG+C2VMFTg+%Cap(RvDKRKL=SK0UiCtmwT^QX>3_CIe<|=_` ziglSv#$>XkgqB}o71S`JD1p?6Et69Kj=3JJNz-gPg2+T)f~X~=L`@`N0Cp0}kd6oK z14nX-hv-oxw-^JpJc+y^aUXg}iQy2NikCMFoZA*54>MzqE_No4JgD%b{E0AOfQ=w0 zInMN2lql)5F6M~2kY!^;Ig83*sQ4tJI0RNeD9{44gYm4oO7(6DuU2!ZtZpvmr7U{1dGL`NZFj(k^8FLN40 zN?1>>*gXHo`63zhuvXgmm5?OaU=aX$Bx;zIW7R(+1D*#{wB5Cd@<9ARoa7GRb0*@G zpdv^el@KB8u-u7+F9~`Ovak!ttZ9?@7BN`vh={mWFNDt_WvN3za8f8oSeaVO%xq^c z=tkRe!j&I{2;b$*z(rP8^BR`EhpwbV5weytyKfOuXt?Ul`1I50!ya?cSHno9L} z#VZ)8sL0qW;HVTiz*O)=JpK-h66}2vtzcyCN(EyCXN%p)o?S$$Ag{$)KyOxV3j>@) zBq1%L1LuLP(Yx|dSESZ3GE!8mAnbl0MvP9!>O?gZB2}T6!oZJaA)y!2oXUo&<_2XD zNDpNYw8_eLl{~ehV@wc$P?m3#@)|TWwHUFvHXo7&)j&M;1Xh zbiXo0L;D!s29579gsNsHB+`}eVE?`=z0uPB{^<)E|MHpLB9cluw6UG?%w=+?)NC@L zw?f~f{n?ABMX7)BCDp7%UY@)n^cKjD@SHtz7`*U5{`Ft}?O*@)*T4P!zlNCv7(gMO z@b72`>QaxDKpdwGwJmcGC~+>ra)g)z4@N(0nDi)1a@5}@CR|5q~NX$yAjL}z_A;wjnEmmGGlFaSZ)?oZaHa{ zn%E>E7N6s4CM+CWRY`~?2Vv(cWc=_ zmj-*T#xe@mW>Mu9JXWYOjVA0X^FY05;T~jFM6L{N4{K_+dwCpIfu?bnM=Kut3|3b+ zE~S&^o2Nx2rR0u?+?XTmgaJ&Nn<(jHj&k6A+dl5YxPw1Z<{z5m=<(CC=rwG7Dv7HV z+HSNLOy>mJhS8$WRTW4ko(w=%Mx;&5w&i~weM;?j9hn+^WTlaB$^VNXc8b^7;6eoi zp&5LyHJ#VxK9&kRXrqdBz#dkFy;e=FGU+73=!$m0DmicO#;ZcyWZG`U|CV?o_&t0L zOA?HA$J#2vA)0R>skmH0P5k`RyrHrXf~nG-CLX~?9-S%*l|DUMT?G<@5HQeP{KFo=~RaWsn+b_*Sc zq9CHZyWDbf!NQpsr|;Yy(^ktfNIOi=z=#ECEunUbCCExbs6`D5pJZ#u8nrA>gl?-TdsCCf=DSh{%-G07` zFczaUiHv9;sF}RH>GWsxQ7z|9%ZE`(WeM1dvMIZiGG9mcR`9GDLJ>)3ToVC_NP72Q z+2doyAPl5%PF|6`X&~^Xd6fy*_%bN+y;Dk$i%kS8{< zh{pq>r76`FoQKA46#>NJDhMD&V?9n%OHNx=H_6UG~1IY-x4 zfE9SK+|S4ud+Z&kulVEQr&&C|=!JQ9;l{kiRso)aIai8cwT)Y=eTgjvPm8K4wIyqo z1kFin(4vbjYImMbECMWCS^@%UteS^8%ZS-w-U@ zR4oFHCyV7LWfX<($wU&&+KRlufF9<{(K$h8ZPg839Mx5gu~x!vMw~?x17i9HY|T{m zRU6?QhrbN5aINJ>YI&NGf>b1X(;!|YzIsiR35`cEwu5-9&2kcBv`jhLsFD_zVAu$d zRA${FMN2X;rmT=4?Dx*XJ>A)Gc?30YUL|SGYIRN4ji#h7uT_%cSS#k4P}T)8VnpsiUfwra=}uQeLkfNEYONTldlm;NYXQC%9fF6colzxKg{h-SC??!wMooN_0-i zZ*8vclT@Xbs4qnaDF)AN$^eR2T4}571$5*bgUwXupKl|;gAm=ZVoz|5Hu&{Hqz)lV z2FU=N8O@fZ|C4dK5lwW&(GSb9>99p?MBAqyT_Abr1WsCL!)n^c*;D-FhYd zEK8!6hzuND#BqniEK8ymhXnB)r3+g z@wtXrChcyG_B?*x;Lt`9ZHfWMJ*wF}AghOlVatbZZby<8G_~J7RD^Q7Du=okjT17k zS0g2TV4T+(BYzyCif|SxS$>=Je&&sA2Gr5t3cIow5@=uJ4wl* zMADW2(4ZYzDz{V3vI^_ljvl^7g-Irsvd2PU?!HoQl}5;k?dkK5Xs|U`R^4%Rx)lrZ zXl>q{zgbUr6=bbnFBIo~DbSvDTzsgFOe`|l@xGJf85j22G}xz<3Z5kgT;2TM;a4;T zBGMhwSqT>yFU?p63m3KVxz2Cg!{r=nyu9kHiq(nL z8$50Ezr!Xw*fc_mvnpMay85WeuqE7Fnbk%)JWCi@uHjpHl6^2Z>EZaIc2!@p#}Z5$ zQN%9~!x4VFnNYLq{x~=?*&g*&iimZq(JXKjuR2IV*yXe__e~5pwC&tDO7WMbin@0+W3AtE*;qI<1o?^xlOHByAq_p2jiA_PCBe9c^Xo=@P z{nIr18bW}~ziT$LzU-*@12VWpD?Kh@R-*n9hY+cKfqRe0W2{kOzGdZEhZjH}G(h?f z-k_jkoo1wIiJIoeJ{qzkr)rusyw;;kKu?rOXKZA$z#5g`(Q3SVCHR7@jgJ z;Or4MuIBz_u)&U`2mtM3sAB)M$z>xcmL+_FcQy|iD&a(kd3C_qyx0-pEAqNf?M#i{ zL--uV-X2pWksv;4<}>ZU=kgSizmN>E!VV>23Xxf9htxdCOFC|Qtre20Xq0gedV)JN;rK(`!Gvwsv8cqfIabkWD@*X${;6HMJv9Ri zo#Xo46*xuO$EsJ(C(lv(uO62PxqYIqm1K?x_fK1d-M@NV)=iEaw~57fXr27$nnBwM ztj$pbtyE5U&${A6?0F!-I(gLr_Wa=H?s=@;mWk#!N z3u#nc9lE0E#vHR@MaqP&Q$RAxa)h6Y?v^61oHS69KEMDg<=5Jrocp}y=#2T`Bm7(* zw-B6`iRK+WGyC~F_wBnR@)y1+(^JN6+w!LnP?NXK#)qTQb3JGl_{Yy#2>-c*YI*GF zK~1~BJhLTUY{Ovk^lsJlwHilhw42oR`>{4QMmIOoA(6RN3Pw>m%UsF1u-cp&tXK41 zCxK$>hJz9hC<@%JES_Zt$DNr+lz|o{(<5Nj^{J@>YYr}s;*nYj7cf+vS+TRiD(7>A zQiU1{p%o9Xa5xDS(s2M=s>Uu*!`}AgJXSS!Pu10^SxbkF@uQPqv4`0KtC6(ZXd8mf zmI_9+SoT$ufSEfwp>U7R($PfyfXf$(hzYZ43+9(@eZGm?X9D6%^XZ`cOM zstIcSmq2Un_^vb6SoU+(lJX?e*zmxT4hpLY+cJtO4zakx@Kh|ak(u@Jq*G#yFnl-L zC&OhB+Oz7&w<@qv4{oGeFh=d+ze9H=xr#AUN>YJ8LU7{p<4#|X6&-r)5V0_?6pSL0;>(2;|!^GS_e%2p0X-1 z3RwikY9c6T38JMaa^%j!A4s*1&VDuk;_+)BA*1u-F04lLTL2(muhG8nc4+AiB!T5vN?cxmuG zk3DzVM6KR!aBO-FhpW{4M*1(C%q?(F1BMuI3}Q)}EKO{{Oq2$?+(q67Q45V8fN_FC zY1kX#JsU=oBMsiOzir;o276PGd2!!bV%mqZ>C(ZUsX)w2IuGUtN3t(G6|FC*)IOZ4 z2@Mo(Y=GXh?G0?>>KuK`(YyODYQ>;#-fW+wvsJdtJ1Th#G;^z_ZNQv|jWVM?Y&B@r z+3xFPd(*fwK*KM&Eh<7+T;Y72B-La+gBg6}?5QuZO+_zQ>6W&u`vc8fZ&9fvP~ zMm0enw94Vz$nizt+J_6U?P>(o%x2e)U}V6c?FN1U%(0F~wLas8KVM8fW!Awm7gw2T zHUqCOf{NkHS~OFpHcI7=8Az!k1{X#4RB$epcC=hm{Dhr%2Qua|ME(s6YqD)NEL^nW z&T)yV)DBgEMfF!I|A+;H+c-%VncFapOxoXqkqB;|UMnGE*Grg1b$tl!yCR@NL38MS zr@p1Yu2w-BA;H&)&pr^O<(XeYLu%tlT@*#0@ufUiyk=AyNNi*8=9nfy2i9vez=T6DN712saIEJrkM`rEp2nX6o z+7vY>Y>DA~W28>l^c|kl!Ppr&z}!4XC)LO^TJh_QQA+0Zb&`=W{UrzqQ8*A*92RC( zbZ$I=RRtcc5fdF)hWQI!;E3uPMY%4*7PbZi9?+-7oXW2U)J*|Gr|C3FJgnNva4o(b zTXz=@q4XzNy;>JJCJZQ`aYVH%4D2b4y4?{`u$e8qSoo)LM0^cS==t|Gqoi89y}_=X zWKvNGQ&b@a5Qg!BvF0%N9)H;A=nF2fN3oKgntK!aph8*sP5g6%hYtHvfFV9oJ)gp^Vn&RN^R8*n!AH^k@^ zPFd@+$lIOqqZv-@08=>!%k3s!h+V!`{6KfRX9Vo9x)D7H7&-+XTN}rbwS})T>GA~H z7Fl(PZd#tu4D~+^7mG0*xC}Phg4LgInZi0-mRjVyc`0)&MMH{X7#xvt*?qPovMJ5X z8<>Q_%^*}5v6V_6gk)J3Zs_D;{VppIl0wjMpqYlNQ+7)}Q778v{3=DoK9OMS+Znq6 z*%{tv+=ioSQch=0-!yq0c_Ici?X-SZsjqd2z+5Kh`Sz+7Dsmb*kOfbbRf8*n1y?2D z)=?Fc1o!cRG*zBdGi!{hc=JF3oFv*dF*Q3UY9&uklN(if4!PAK1@_`IQEUAUf2j}km4Jr4JTiecJ_+nD; zno=9Ko+B|Oz+>Lj%DtWDcn0i^SeZKr=^8a9Lh=XCpPVHNecaR*rG1PUe)ytE$#^FR zh>9Oe1OVxgDc_Ab_&dq;_Xc54%60O$7yp~xAypV4Tu}UWlE;_VXogCC?hgAS za_2yEI14DtutvP18ptIj8m{ORkZv&W2>z%sW+r2Lm4_=+yqM_*Wb_o4;Fe!bPn z!%IO=FEM%qeI{fR==&ugugpkufNa>WK-Ai9jJzn`U5Z0(_G<`}^*bf{$}gWmA5CSB zdC{V;fT0K35c;sm6wd!8C>h=45ow7(H50ai@&}pPfd12pPo`$xO7R)Rti_Ydm(Spj zen-cet?;*nEH+Epkah7FfZP)4R`5imegVoSWkdt~r@eqD@FyWssK2G5)R3uPfQ*81 z$NH-AHvm~5e}5>Du67basD0iCAZYCL27$4Vt}b|7ItU* zQvY_l(5(lw_8ke+bAzNo&w;pb4!kE?!ai&k-g?4UW+WD;4M?U&9h*QW{#SjI*^g zgH-RbIQ9T&o7;$`hMPB+(h3q#>LOfU6GZAxEUxjlIYvAiBYg~{w$g+eaRWUjQ^s+* zD_s100yKAVPzBn^;SA6=>=lJb2ee^Mqy5iuLMuUOYtSS;`yyo7gPpEFs)w&abMuDh zm&{e}<#zV$rizd)42vJ8?T~>7=cEFiLylB%u&^3P771Be)dqL+@NU9^xqGEd+sOt& z7iOsiJLAh>_oj0sEdS1y$ZChM5q$F|gnrL&5#Sx>6?(HBUeTquiq!J$}X2RqNWA>=HzF+^o3erB=^RkD!a822oMmssjc;GpzJ z!nqNgtz4in8xkCZCs1CN5vz(lC&#s$Xhaz7z*A6OD*|vR4e3VJgh(&pXSt1&dg(=~ z)DZ?bk|GJ+Mp1g^L+uY^@9YLM=9W>s@NJwxP#zQZ^Jk_ta3XEeV3XxbO9$cmpLZm6 z_T}9efkL~VZuyD^jD}nJHR6WbuYE2!i0NyWVSn|dRb`GiP8JYnffL~Fe=r#CZaloG z8FfHlZ9Um01{t$|E;sttkh290Iay-wO@~BAgRnQ$?n_|LOB)st+^%$KM$kl&RO-5PT40@=j? zVLaEL_i)ek>%lb8Z-Jm;4q6ZUW>)u8_Il#x0)$oyw4e{tk(<6ej0HkBg!AuM1jLns zV6i}Gv4Ek!0euhzw{v#~g!U+hKrn=A4Z=7xyXgTNf+Hs}aA19{;h;er+&!gWLx6p< zWy+SKkAZNSnIE3pgkfmOqgJ@@lTjhZj!5D`B)CN~woWi4>Jgow-Ig0wa#|;_Dzh(8 zcW__`#zw)eWK`h500BMnR^EXs1z8ya_O#heip@bu={bA@9OFWM12CFL z&<(x%#e(NcTfF6$eYsnF&!Evp+Ko{fcA(?b6&yc!l9gG?ueHolGud#om*Ie35XZ)W zahL5;j)8ER-(T*gK^qIlbbtj!>q?!KyY%-sOm5@B(BL&5s_;PJP_#UB9uJ7oK0gEE zYDZx}5D{S{9_ehtu1xoq+`VW3PL{>&=H|`9B_h`V$!h78s_~d38)76OR7*P{De?T> zas4e}FmQhBB<=ZQD5^bLB&+aO>p@=v>Fov!5=wTD(!x~YBz(<6<<}ta43bF*EP5%B zVuBO_AJY+ZkvTdd0l?!o^nGKP2Jf0EZ~!o=O22TLPu_&e2l&Lg$w7d2FJ=)BgBZDb zk^Xy1aO#)qBCsf^^uu*}IaUA_6l8uau*>!@!(ju-Oa}ul1U3pdT9t-Qve!JgO`GON zhhh9MW}pva&XMh5>02;HS#}m}2xG4oLix_5A)mCvGqjn2GI4$sWYTR?daPYyIzv$p z${i4XyV7sQf3XvR0lw)A*Xj#H+=4gk=mtck6;kP_wIPeM$a_c9N-Tki6H|#AJ@3wu>~I!TTDhiMKzUku>9k*8A7!qsW)JgacaK!fgsX?a_ptekNLO}o3^IXr zh-gubt^T1qbMd+M$;cS_f+;aKcHrjI)5m?f-E5WCTOFh30HgPtKR+fn*aPj{@1Sf>xTe#F;Pex6kfLj{58?_aW+5|Ng;F?HyqU zgO)By;5uYvOdt+Yh1)?>A9SUPV+SohHG4cShG!G4@xvCvzju$!#dB1}_8v*3GHz8( zB2sR2t{6D|V`zY$nJLLoT=M8a*Uyg;E6rI$mRieIOb*|5^eqgWHX-N+9i)p;BS8Pq zDhPT9Q45#Lqy$ODkzB2jER@!GyWpm^~y7WH}dJ3O6%J5x( zpZcA9{`3+bASj&+U54wq-?ZF1OlhC|jj=~q5G07tIb_}U8PAbBv#b%w%^3AJN4-T*ubf>(xO2a+h^d$2q=2o;7b z?D-XU%XLDt?)6W&Em%%3naK*mV2g%JpS#UB zwHbZ-+#)>RQ};TV&b3@;hH37IH0KQ-alOy-dW`#AX;R}~e~RMTV9(R0G@(>Kl;1mt z-B2eC*W8nF*7Z6|kS0&~@dAIF6Xt7T-br&!##vVi`R2W{b;7yVJvuFK%s6bm*zXYm z!;l9LOU8T=kJ!D7@OjgWm*eRhQI?sC!NlVs1{!p{BkoYa^{0En75Ak&m^|UAoX>Zd zFUPn;OE}D(kO|I%XwJ9Oy+j~yWWwAL87Vn<#Pt?SwlQuo3k4=v6+$5dZ=Q39eYz`- zH#E8OF2lEyQDK~Qz0MM($rFxB_k2y3bTQ7lQV26Qzjv>$#CK%pT1ptJ6qr!c2&R0+ z-#hl3NA*pUnjA>#$M!?W;YK&#?auBzI`@KgMB-{AOjEZaD{(J03qILdO|2Zmz{3|- zAcyQ{2CI5vb#vA9Nm8)99yMlxt>bjgZ*^Oe8<|oIjQ4l$+&#b5ElLyO{{36%nmIj% z^duIJQVhNexT51C-MvKD&*$EBu3Cq0(e^zoP?h4YhRT$0!*LV|EgZ^WY@2=Os0lbm zv=4whG)OTwxy3e8lRIm2vhU!V7`eKtso;wpNRHsdhU9x3f|)tOAr?Zc!!+n%R6m%6 zp}r?vX@hoGX>O39iLue8-!r#_D$T6lh9+jr1IE9E-|y9tR(xCha_4-g2ek{=5thmG zxdSWf^X2>7v#)f2*X5SanpfQ4i1y*9i>v8fAcexq1!gejE|3ZshkbS^u)Ld9x23RS zqJ!@leb|m4@2C~7@62XuE~z;wwLkGwB|LLi`F86}s`C|h*`(V_m29w>-vtF zZ3@F$PSfCoq@EEy5^=aQFxZo$WggdXc`dhOJ8S4T)Y(}c1moomMa#>%gaX4;JOT(` zwXUEOFd77dC3}5RDzRZgVV$LE3(B^maS^u9wfbmd0MY5_@df~=A`uHB>o{8iv+-hk z@RNXC38{CPyu^$_B-UZJVAyIR@SC7vkjQ;Tx7OFF} z^3uBcbYu(0=^OV;BJ!0>G_9eJek3h&Z~$_RTie0M)n6FnTfYWDCQs(u)iAXT=Ok>B z;X|iVm7SQ+nBSRbFl2n0X5#9Crjr&XkYy*VcE#YGy54^xUeQ6{Qf-c07(ib?&|*eN+>4J zH&lI?XtRGjEAlvbJh$4gy1vBZ-SZVtv_AJ3YqNF&^6I$&CG{1@%Rk&;H+{kWo`8uuu(F|N4M* zjz2UFjSi`Hc?&x=$2wVA*vm)M*;F& zf(jt(A_oz&cQ1=@7(71XdivV=AA5BRY0IZeQK-YDs?FsyHU`F5x3td*0^#JI6ZX0? zjHHjHY6{w~!uXZdEsQ#Gr|@5jaPAESP6p%2z)Ag&%J48(C`)+U>2@W5sZ(7UU&e|K zCNE#E`a&_Ljv35h#1Fdk!q)Ef6~9JXE(_3J3_E99?&u~IAi=ZiBj=hn^yTAJ?)*PefqF@%d^K- z8&TJNDATA6a1X>muKszwQeAnW1tVaYqUdYxJ>s&dTiHFVpau%@oS})c= zX*l`bwN9Os<>(H@mIqz2%J529?}tmJ`{K4ounTqDB(T!=*u^qP#UX+6xR;mKgfM+Y z(HQMNLU3S;KPYh_H3Q&q8jxH+XugNK8$Q)W$CWH7_9-PrU{Ib)KLxeqbmQOO!vw+- zWXCZp8IM&MR~khxZ}ofx9z>)81)*ryYh*`okj{SW;(z(@Q1Hmb zqX7mk9;fs-FaD;P4PASul11t4$1eVt4}W(j9#<5uU_sQ3zX!Fscw35Ilqg3l0+>e>5Dl0*)|(1&6v$=>obu(A~E?ZfG!{Bz%tJBS?o~ zBrq&_gcGd8n@9-4=eG}!wR!sHF?4Pp7UI$Qiwzz*Au#aq!w2y&eDe$>{*{{#hhKef z;=sQS$Cv`PDCkPt342FhA4YItQ3s>@{ldvPe0H8dkYW@E8VLLwIKTtr@EHfM--d&r z%2`IBS@(LuBiDXjY6l|{Sg1OJ1RTB6)*W_rG@JKV@bO2(A>HQK7yP~J>kze43FjRZ z{r)_dZYocdaLWijh_;pZ_zd$0+uMExAAd9){~vL0lH|aWoN3;L>mnr(n0b!c^{S;L zmql{H66v~qf4`XzHmIAL0v;ri%zQ5ZI8;sN(J-%H(}Ub7b^_-@gZ6Y&iyjh>fRbWk z;0HMtr?pBOXoxT^~-@Mc+P;kzl zMEED?k1yktL?Y+^-~y)**F3P^A8?Id`;I{U#KmRh)b1ps&)ANx6&*bd+N)_1KP3>=RvpySBX1O~|osuOy*A4{nJpl;YOVsfJc?#c}%yC-I(-hsWL1 z0Ma(bHSM(a&=*@@*4%&;$lWi! zYESZ?59-Y3>AuKmV1G#O5hZcWF-QF^{N%74;k@#G2S0tg-1VY{!YfZm3hs@4UT9$&5V+Z6A^Q_H7;+1}+;6Tt{83gC4V(m*K2W~(Ik!LG z+$cC7z){}1q*dKqUP#L*e%1{shYAZ9u$KGIy)4Wc;-^+Dui9_k6ntlMF}K5TE!JC; z=h7~;vZ{kzkD_DpqA$jT_QlD3ga&0}wKx)dt9dp9bLU7^cw$b6RF2Yyn_}Ow0B;IZ z3_YTbbl-0JDkGYYH&@2fXr`N1l{Sds!72xbq3YblMh+Yiu84TtGJMKJx<%3{{syKhE#YM3-q72B;){#D_IaQfr-dBFTmVk6gq65 zPYO^JL2PP}H9{h=@kD+!q)Uxn(8inzrB9lT>79gx{i6uQn^nsI=~V*AnQ)B~%Y zicJjCP)-K({lh7TfrDb73GNCUs?Y}xZS@Io=-JPtarK%o?LKhK<$nSk{Vqi3!|Pe9^;fM2KI8B@_z0iB|i3@6@x@VXTx=b{28Unoy%dU?v!goj=Xn zj`&&UZv;w*fwpnxYXBAn)$<|ElitK1H_D2iw)el(WQ>1#^*QS(t>|qG=YmJ<@Zc>+ z&dkHppcmH?aWevGiX{r|V#}UQr{cgE0-8n}+lkWNaw|G}wKwzrbIBo)+-5=vLL7Wm z-c@Hv`e;#-V=Q^|9TdYIJPFN}q7l8_eLIF4o~$E-tb^ZGG!W4@L0(~b@g87iOn5_6 z%FC<6r2SsPkG7v2TI2_}-;d!!&c`8>a_5`5Vdj@?Iz`9zm2d$;l{@-3Yr>dcC3t-( zCQ+uI-7-r6%g>O8&=@;Gj3V@)LyuGX^rX95a3j3P;UrFbLXMnmyohTS#Hx2Y#Hx1_ zqowaAg0+th<3eoVI5HEm1a-tWi-dF{kd?wffI3lJKifSj!hv^E177^_UimMxKZymB z3(Jce>p>0u&1eTYXty9MDGs?eOcpIk7^}FV{Ll+Wg8TL&zmPbLglD=~ zT!Y2f;Bs#I;JcE#jFs`-AQ31uoQ8@vEzooI)F?M;sH)1j>b-?p-vdsHeID@o$dBQ4 zc?APil8c0OoO@7wlaL>SbHF|soXUEN+;b#6S=zFQl)_T5ZGl8M>PWSXvic32=ZSUMJnayS=f zu=zm&lz?jA@bSoM)c9VElWsWQ4hBU?VPn9W1|6wPf&ot<((Stm{ltRpJ7G#t5OP#g zy|;=I%)RglTefQ6ZOGBQn=nr-nQ>{}j^pBPn=I<>NXF2+uq3u1$@t3`!!?QV7X=iD zE)_0^NFGM2g%v1BgBvGIp89EEzyqQwQz zbfu_xkM2p?Uy8BJic$TejY6j3^7Ei8nJ2N<^c7xWrpm52HAB1L7GtmAtIF;}vdZj^ zz@4gTN|LcgN!L>+1eAb%5EoI!Of4Wm&Y^rbKK`l^a%sV1ij~?lW}Q7rD1Zcqio8Vn z#AlQktH@wOz#7c;RA=l7 zK#dPqMx%0cRBqo=+Jxp@vVnMD@q7l4i%S6G@dU{1djh1j8c(ADSB>0hj?t!M69F4- zAfOlF@*uMk9VB%Vxu8oejfuEBunZ{0$>vCtIW zF%h7f#1Vng)m~(nW_T6N6YKW{;zi~B(5FD1K7Z(w0x^kfbxIApXZpisc|5J+v?^22 z&_wM5B(llOt+?Z{=T3J0_(O-w^Z8b9tv0wVy#Z`^yh9)@x#r!UXmwTyc)@VJu#%i4 z26q;gRzxW|lkt9#Wr3&AT+&RJC#@37rBYydMH_!Wz;&4m7iZ&+2`~)UHA_f43>Rjs z9e(sLX^jTyQdIs2z)L+3*{AA{%)+Tdq;&t#&qDL14XlHthoAl`j_Zzs>Krh`oL1sUql-Ws&MfTu=;8p$4Jp2W2i@Xm2MiY?Na8R zKK{ijkVpqB#GMYHX!{B5Ly!BI0v7uSOj71F>hS-$g^lrn29TZr7S^ymB0z60?MiX+ zrSHr+ep7rOG)JK?X!D|ZGAkgoQVmECzJ)d2h%6l7RvL)FQHJ^FO>TUA{+0s8E4h`%s_#@29gC>B)L`eKV~9en)G5D50tq4SYD28 z{?N>{x6!TmLZQdGh&q--1VfD3&PlEutwEPI4myV*d-O{y5nM?K!)9iai}2&_>I@}P zfgt%?c-pxCYC~2dVjKa&90vhI4%qy!?Ll|?0wH0hfLe;BTycP3G)$UoM86pw6leem z5z$vdn}1?AD~1gn`+*oB2Mz)j1zr?2sXptp*}t1@lGcL1e}Ii~EwWptDYz4&sq2<* zS$4K9-{TPkEBL1i=Y^yIe)f3iYLbBNJ;t}NNH}g85H==jVFC!?9+u^#O^#V@`^?9V zyNB<97N@)QgK8@dqgU-$=Bl;7m>aG3_@yaTZDlz^!B6HNF+_LzKWx6)z{ZQf0us(> z0acXS*=6A!wRO^mKi*lY;&@w91bM=34>Xv1O1gTOr$`b6A8q6arNJDQY<23bgCC(I zxu6DRlBN7lQYwZh$1w2Mo*0~B>1RS$Qc<`)YzH8qH1)cvPFrgbgdYn(rho-M4n7Ob zSPO@<`^xSa`KVgCbp&7*q1Qw-l55n0$-759eTE8i9Rq{^8R1~_wla5oeR0mT<_>R@ z72jlVF!Yvl2GSTW_C65>Typ3RD>B|fY)H5hckX$L*WGJ4HdKF;NGa=idsWa28()^$iaN<}z>4k8l-}q-Pqj-Zy904~xw9G56mBxaSbzDZtNzf26 zYTOI6TQtWM2_B+at)I%~H>ZyYFcG6L)clxt?1tWF^`Tbtzo>%}={=J>IRW+)&zIB1 ze+Ke(Pv3`dhx*2sY{>BUJ1uFF=Cea~qb5T)nlx^;Ldp6+xvOtqW>f=lLQ z*e;7gSG^#ccV(`@;g`TuW49&}q@vL4WQ;YTy?l>3Yn8B+UI<^W0tQT^jwQfy3h;hk zICRQVu%v^lW0bUD;#;GZs^dJ!AepWi#-DLi^2Ikctze|`7r_8x@;y)wr)xA*>*ya7 z1ziU7#5qHkC^wTJVWlDC!ki{$pNGjuIKQM4u6zm>}IVPM74T-B0AUN|(=CV15bXcn1^g8H?_7w4MRE_Yc^Vdi=Q@TJrl)MT%IGVd2 zvyh>J)aBl@GGGu7>XNn8>)wMugLF&;GQGsj* zwwBmI%AVE`@pD1}?M@+DOC(J{j%wErwu{6v;|_}3()T!eRVq|AVLd~-I3vhPZgg&? z?D55bfqE;x8{Sk#0)xmZ7r2~c85I?imB{_1pdO%USV%aK)FP#oQdBfuh07*nOFdyW z8Ob_LpOKFEuO?oM1Skl{mRSfGCus;}r;bb|09HtbZc$Z7!3Q}WQe_|518MaMsqAr} z{f?^+Sr8+OeyGTTRN$h6u}!c%3L*lsR9f+ZTb3`pK(X{f+2LTSfnI`wIG`NHI9M8q zUuD09G>=lRIorwq;#1Hpll0`HT0T>y$TKvP9G&y zZ1A;V8qZj*3`=B54v?lUvJIr{?Z}ch_zHP_{AzsK1U_btGCZw2phs+6`w&6lc7KnXq}KoG}dJi1u}sF=w(2Gp({ z0vJM&JTV}~hoB)N8zwcRX&D;ohM3Xr#-qrWI)EsHO6g={p!_b0er+70S1FDG@wtP6 zp-jmzU`Fxt`DwC5i5Vzy!9ipvz|799(D(?6@SCW$W6kroxY_`MV5#wqs653HaJS4_ zVX=0Ik(R)Nz?{Qn@{upXM!hh!%K}EHfi(52JJR8KiEI82b$IMLl``(2j)w&}1D^gd zlICV5of-`8)t1UPMPRE@6Vl_oZq;B zh)ZkivgRe#zx}vzW*v)cAMTKfX-4$0rx^{tuo$#Gu^wcz2cVIKAoT8hsG(Bkl-nHm zhAadz@T;Kc{Wjj6vhW=SQ@S(=K7#;brEXXyWy?Fapf&Iv^i#f25PCOEG@!R^3k%q4 z<=jDUnE|=Vy3L$KZG6z1B&k<@wtzQW6Rvfm@}kyb%xYRB*gJXsg6z_!!ADa0^fk#%j^F(9tlPYimE6b9bHh0;fzx2XOA*Sv=Qd@IcwG-qc+9Dhz3_(Vp(9i-mpm~@m zOek=(A0ZM=CD*iV*}?$BO-WDGA|u2VTEbjZ(aaDn|LC^3v!f@C5in-3NNA8HC#)h} z%*;a$F}S0W;XMwK)FE6WE`nTYmk zlHfRFOVUrUk@GGToBR?Tb9Dd-TGwthhx$g3JA2&)D6IpigygvTJ) z7{?Rqo3sg&1$1iiCst&WJxh(TEf%SblY|OQ4j62*bCP2^{Hc6k*2%1p9gUKKu1ik{ z*s0ZqV%nljJEoGV8tfp~E=bgi!k7~+&Q!jvz6~;RYS`9oM>ufFcxc#_htRchCG+zE z_^5#~1&s6*2Z=Gl0}&|fLR=wXS_P>l+hmu#XltS}gtaD(h(Eo2P5TJ&0r7@FDl7&h zR9!XN%P}3lctUs+WC(#Moj$G{nO4j&S4H3)TP`&zILM8|pdx_==kpiw%;m$ee$jNbg)lvg? zHRSu6yo26UKon$Zy%jurKb$lWn9<}N_%lKu1RhN`Rz9Zs$7pE%4E0_vXUTemJP@@v z)HqFVCf}#p@P)Fp+EUVY$c4xPqI9u$;Rq4|^K$%#74NcyP%0&$+fk`yeKVK%8bhns=VzrH6H0gXK|(YS_kcpgc(WC-VT_FJn0v12s(o zNyqdcM6$T-$;rg7K%)+tz5i^t80WC;k`^-u-dde!s{uERl3GNdQ z^k3k!!Ltk*!w>7>x2M=~zeTg2>4NZIJa55BfT~BnX9GhLI~3#yk$1z*LuDf_nSWZg z3!;ER8*3ng1gIa4Q_|K$9xdt6RfBghqf!MX?<>DXmX-|-@u6-yK|DoiifOMfS}=Nm z4cyqePg@>I8XAn_I+D=N(UAu1`?)2{*n)XreLpdyT*K;U5DPr@r;UA(9%PdJS7s$K zIb^ODwrKr@Aor3h9doY%yI}|Mo?1iRf=`vMa~za$s%&l)dQbgX##8&DFg>LG)nv1# z3^1KqYf0S7EU{tzVHm8gra{!+uzrgWoq&UW9^$VLJTT>e$H#9vy_Bl7#GL_VbyrJ0 z5QXqJr7mcAwHKohAX2MkY!_MN1Qraynp^`pEE>rZ-Z2U&_w@k+6hP?WB6+5{?ZuAM zcCV5kt}TY#q5%A(MINcmcNx#&Ah6%*iURULVdsUza}18y5et4~5bSWm4QG-rZSYpyc~rbG<{ry-PO)*TeI|E0#kimD z&JXxUdsa~;>gK~;U-LB@(W+Oybtssdf3 zpja8-u>5x|&h0p_S6op9yj|}-0=6!1WwAehOYjxoU6Y)mF$Nu`cF0osS$^$ zyjmcdmQIlNP7Aey2r%0@761zY0M$Mhw)m={WYOhn2xsLNO)x1A?arU-c+s4lUMwmT=p%D!HDiieUUn4CA2VL{EQwK zbyU!kmkK$ZD3JfbQzGM}eY!c1qutkZgdxQ2%_E-^CxKhOGAO`OQ>2j}Q~@p@e|L-> z^d{N*{mU^$#Grt~K}HvbngY9ngnh{EP>=&83ZRBF%Ab4vMS@3shjR-jg-@R@E(iQx z4`Ij*F6P2`268niKtbC8eqMXU2%!CnWBxZVpz2L#L+yW~welSYK{u`D!~)XJzh=Wb z0~mzgjl~T9H*8X8P7iQ5TN0=%aLBK?mP`|M!-|P<&ZL|uap0xU z;+qo=XiQezD2SK7Hd{m}PH8*57EjTsnxU8PpyEEMpj$j%*A}-Aj+h)bIXW$3<+t-Z z8v{+~TYN_XT4uLRH-Qv6;r;f-$Li+sjqQtJHObHv=Q}D`nOwpN;vsP0av2ssf%FxX z9F_nOnBzNGjH6|bYI4cn%Y2S^1j{Yox`c^9zQt4Y1_tDAxWNgB3}XfD6C|(@{-!qY zQH;Z5Gg%)ICFxLok8UL$!t%XvIvJDmfuJ(3ph!*L4FQ8T3R3YS!?NluT${0&eADN_j-BQF_`EGG4`s|=pi;vm8frpSfi_G!Km=5NACmS z+m924p)sE^aP%KDxf}-$bL2Qs#v$qo9`cSXGen6kYhC#ZfhK~Z1>lwg#bFbq50F5+fY6H3RV|qMn8|B)WM(bGsDt=@*CH`!u?KNe$jVaPkdd?)`4gsy z*Wb6B3|Zscq1ucHt z(!Ywp#Mkmm8BL*6+hWW8MSMGQs zw;6AZ))fGbaWKxEaOL>-J7~#-XAb@pLaz>DjiYWqN;GGQ6|v4DS06(4$zaa*qqqcS zDRuh*`K@pOL$=jxbGLYqoGR%|zKgFSHxgZ=sbk_>gbP2N-n!udF1Um=B{sv0wG6h? zty6S2VFL;Nmf{@Yu2$>gACYXbw}8zd7=__tiv`jS8t}aevBm~Y26^dz7kSf@#fiI8`hERzu@!&zBcMBK83;Sr?yZrbSaY1JQ^{KXcI4tgs`gr(PRQNneN>4XilR^mHqm(ZcO zLY)efZop#(MtlA%1Ud$i@!gQf-@_C7O5Nex2jRs#NY|^*09?YmeD7O;nc4RMHrT`H z!{OjHbPj{(3!=7zT@keJqiS1zLfVC3)e9;tMLyHU(t?j%YE+u47I!&P#9a#3D3t0> zyde0PjIq~gXcpoyUQF!Kxs5qW9s`Pl+D&~AY>NS1_T8_JN7WkBA2l+RlMRV@yFZ*rTRw-cFhyBCr73@^Jd| zAK~OBAvQ7{z$Sc7#Ik?XNyO9k)M2r4Lllg{T4VZfmL7FWR)YfO7Jv(vgDJQR%TJkj zgNN1ip7f&H_nAV}_Az?T`M-oV2RL&QD`fkuEqlf4%5 z5j$(x(I=p8K8OBF~~cRM?G% z5|$Hi{5KyxB_WZX!XvZ-7|d1e%y!3Mf*|$Wh@hk%y(0{JXqW~Lr8brr ztNbH8H-VngT(r}psW=y;IWxijM>G%QJqtrOp;%$K(~77~gF5hMNmE*A7T3}^`%S@! z-V3paqKV}4V>YU)31pc=IY9!+md#6GA#B_)u5JrqScs*jtND`!*N$HyYt(u`MGx79 zlD72I2?XSw#htrPL%ZZz){jLFPDZQ5PL`M8R6}?uIMU-8JM=u$q$K)D84|qu__0Tl z4ItclKqdt)&q|8Mb6PxUO{d$C#9f|KIDvkYWahOCwiow>z7X}y;iY8(r0&b;H^Uyf zp4+$X%A9K5lP-e5;Ut%y&Pg+f;D%JIv~iMoUj>5IvoLfMV;hSm*mmZEX3#K!Mm1^WQB6NMG|XXA$?H^k@^dyO)k+i; zYx<~RN`p$qZO5x|EEGhJWuzbqEwjZ=mi%NZD8TE;YSmV|qRGM2NhsnOPs(8et%_%K zqk>Q@4FzP>-y95gdqZqRTWx+!9X_3eAQ~`&;BKSU`L}4A!qji^lY^lZUC~Kc1W=SA z&*D=Cw*xq8%%ToyM8v{Z<1Xn5A{H(m@zo-UyR$|Fm9OPCc_Ai<_>;5VjJT%olT%P5 z^!fm5OhD#P^q3{QBJq+Qvbov>P-?z9heuHnPFARUSg<|Fl1vzfJ3PwuaW8!(+J0%B6|=u#<8UO7Gf3Lu|!cP;fPZh!EqNAq5^H6 z6pnk&Vh^Jn91Fo+f~-=&a~yRNhN$fbhP%2Wv{}McBa(9PE0ize$?2H-Na`d6@h~F@ z?g_sf+d#o0ZMcV04u+-uq~S=6P{&eiB{@sgxZ43MRnvwyf~<0I*CaY>%17JU?wQL(ty4eZ)43Da2Xs5GcYu#Z*jXB*cxNVE4QW z6cuqLdQ~Sy7CCn;evczvzad?-bE?Jw7vOdlgEC9a!2+#7vEbBYPjbWXtmHXK*)We1 z@oNfYLx{6()G5<0TU6!YSkW>6A*@rz(-O(3n$8o1u!8 zc(t%SDXcmxzMxwxq;Yn;pX)>kwkoi4iiJtt6m~xcUFk7hT&2HSXBE>p>|z~y zalJu8rirf3LQpQ{yn9m$-5%>yMWgJE4b^EMcZphMPGs2*e1@vQ@&^#CW1W0CJ(I~> zCP`Hz-?M4Lt|guzvA;D2P{TThf@%CXf?%0bOl6~V_PeFrVym&DDXbrn7hZdQOwrkK zmhT3J-r!xOXG#}l4|WQ7CzXy|V^MoB$_pn9o8U@+vkod`4;gm}<%R25N6T*(*tW#H zsz*MXHlf!N7S_?#Nkukdg-~X=h$q(aQ9AxAyqZC=3MgnN&nMLcS0_=C!q}uFifby! zQvImHFh^HoBI+@FP`DPe@?*B}af_`Cog8FSch%M=h=Qytl&W}?0IMS_AHOQ-!qHxy zvS$EP%SwMdK@Qm^HBZ3<4bhg44m3pe+4N?SoY|Z5`bySGOv-p{0L8j=lrPGm1Xb6L zJPiAYD{(>G$n@d8NmO4{(+cvio43f`zlZH0CAVs)H#Xzb4Mgcq&yhbm z&jKo@iE40V1w|1vQ8#iN?)vkogq5CA6r_0GNwi~)K|s4SA7Vl(JXK#~RU;lC*W*SxRBkE`_WvrK?20J!`Slu1?}l_b#sr!z!f7SGq7E zW^~?-QLF;2L@PUlvYrz2VYESfUb|Gy7Hd0CWzJ}IcCz^hU|}%#w!AumQXAk&6lAAS z07EOFDLfJ)C@+^U1b3%rYs{_NdAJwYT(cy=w*L{{mbst|?2-Lry0|K_nu$rMCX5k;s}N53?t zjq%$_m@7JZ%FYN&o7_nf=&tIckrEl*hje!uF1?3MZEQ$A0o{Dw_|y6b<_?xu{NfCz z79!C@1C$^rIEvF}-GncD6=UY)+s@vKd1;wFNAj2v^@0bMj_+iv=4ct5&VF<=a=T~+ zV@fm2UShfCJ4a)>>9cxLGw>TSfy@hdMC6{29ZPP%Tbq)1$=NN0mJH?2#IgLbvz;jp z@@TY3v##6}HLk8VGCb1j^sL2C?m>qRLvW#|hV&uusSU&E&xV7me(Gt4xM z)|9esA$Lf#9guLFovrK)XG8l^swmEBdrXjmZVO_KUlFgfgGQ*7J{rrh@&t(m*p45) zVcN@*?jgIu~AbyA-9SM$?RwKCkkK7Nyu3RuI9PKC9^L1X@ z2HB1wTQL}nq7cD$do>BBb0VKW$&4Fgl!xxTnC&Ss0{Xk;YW#`rk@&NSS}C4&MY9dEok0s;WN#DIg`(0B-DDUv4>qFxVLaW^JG?$A$+oZDI2qq__2t2)g!FgC5sJm4E}8T zhSeG87(d2l-TvkZxzZ9~)t70>!eY=%DrhaOun|u)J*yo^v%v|!(qdo&Pq7W)=SF}v zetW@_#cW*QmO!g4KGR7JhW$8wY07CjU@?d&SlE2#pm92qhh{KBj6Zd`dw@TS3WDy{ zT}W8DZCFDW#WJX(cV!tj+5I*Y@p5O2#S1|U-HG#xh-IY491NQS(($jML8_Ip(a=Y+ zia)sVHa$i+!QrS$4=Wjd4h@M1B08q5<7qMDqD8yF&^r1oh6(H{H!qdF(=Y+IA3k+FjCD&xZWZfj*cgiRoFZ(eyg|XGr6Qu(Wwf^k#TfPG zu2OE0EHV>#APlLB0EH|PAGD&lfmRT*4zSWgc1hF~@nC%pqmnM1RyO*@QWFx?a7Vl_ ztQ2aiP7MU>04pC!sZI%@PV?BLvPNR^rDY=QWUSQi+ zk7y0v44)Q^O}ur_0$oagE*3mV+2AdOlufA*xZ)!z!b)+pEtQ)9?FO;XO+;La8(&9N z+-q|Zf?P`Cl+bEE)rCM?ZY=M1Dz*O>RykZ+2VH%JEk{=8Sbg0#IU8c=7faiWADJwC zX~Pu-JB85nn95I}>#=btm|R`@ovpKq=~LZ%8$xk+un2XK7GP^atBH=o($^!V$SSyS z3U%$xNuj>Br-gJ4I<$y%xWQ5w7T)w8S{0|?#KMV+Rp7{Z)w9} z6Uk*C3lTK8Wh@~@!4cTpen4$|P)Ht?zl*7yT^jMI;L}q3=-EuWDDIySlO04I97T!V_2$ZQs5^QFCI{TK0T~ct*j##`z_E_ zK^7j^1R)CpsSr#LFYT-r44mZSC_nMBkHc=noMS2clUzOWd9|%%3CGG;N~NrGn3c#=3sx!)|6P)k|qMjGUiYu zmN2ZUS|@p{^fk?Ai}N{exKNMB@}xf&Xp^~?$-IhbTW57MYP;bmI#G2^cBWw+Xq`nv?cI-XX`xxDC#{iB9cWS1^>u2c zTPSd6<=jMDCy|i`vXH*1t4jGM+uE8e-5M5$?PM%X#2eOL=vWvNasp?u>cd?oSi5qi ztNar;152d99Tj8lcmMzZ3@mnYs-uDuZr3Y0Z*I8-@GES=BF&> zj?}wOVpeXvns#yoTNV3o?^Gt^E{-ZNjftqI)S=jIc}gLT&(qv-rnsjS4xrVckJ|Ur z*;m09I;fb@z}1W>o60lUqMp*l(Gn;h!?M!FU9bx$Y!m%z7(7P`2|nl3#t^1-FI8F+ zAC+F})~072eRgm3jVk6Er;g)Tm>8O{VO z8t90w&eAhlNX?c8F#di)3k(p_~2Dl4GTIxy( z!-DB3EaBF>DB{1Y{in(VW^OMceoX2)2;#Rz)JzlV(10Q^n)oW0<%TpY6%$3Sj7_D( zP6{!&fMPydEDAP(&Vpc}_^B&#U%E%Z%DB+%x17^H>zB)1=MeGg4w6>Zur|qSoKu=_ zVyiCXZ@h1vRpB9!$y(B}b!c@Go3iUDq-hGbDwUPeITs!nbtNZ&5`MdjmrGpfDTOyk z`yfgBb7+Vb3~8Dw!dbT&?_RX3N)s4X0oT%VTDbHIsj>uE(j0PVxJP9^N36rID@u~L zCZ2NY;Ce;$~ikCLCVa{G4z-E4#w6N~Vf7s6>PhbWraq#VaJ)nZzPQ=ebxc3OF{{BIwm6dMNyc%-DEZ5- zj&atl!V+VKVb8;!xec}a1Ini{`5S-j_|=a{JX${k8zxTpnt)foGfbh!HZeT^Uc+g&&roys5eqgBnuu*Wtq188%Vygav$YlzC zjoh8BdR@0G#T$mq&*}bHBug889HJiml&(Kh zQP1R}{*Qv!dRYjK1-p7=olR98+-ti(Q|hMF|r(ICu}P zOsc(oqrs{DT4KQ;qBmVoy}W3`N`E#U6~l_?%+a4*Nm*j0tCWL=r&PErg$1vkYMn`$-{muNb@{zW<%z9Fd zS;a8|n**fw-3~MRyBqmsSrWyJ2gUGWJjBr@6M_af6+bQ0%bh^gXtpwxFsfu0cXMIP zM!du1SK&W+^+P&(9xm)2<{%`a_hLAQ$P2 zCt#(~mf;ff+Q?wU3-^R-i*Vi8OYiQU(9iEC-wE3G-TYl`Nh?%f)?)2P!^)X!U>$d- z^25m=)sPFe1Yi4xgVH}={)Lq;zua9;gEeb4@NNF_&ueqI@vImR(wOep%AQ&!J+>3i zKDPl+AyDnR|Km?_|dEmB5y&Rl~fmEC}ZePVT4jYFBK+f8~$2~>}e=qLlK@VVC{l^}f4;btm>%{F* z9*b?5rC&Va|0Fycf%2(a?)dIS_oon~iF=P^t*P0>_he5Nu`#txij+x2?_7U+S$aF$ z57gMS@8+*l7*K0yCPwoEVNqcho0Ar4EGprbpkE^6WngXrNql(CA6W8=ua`;}1*?W*{GQWRA31Qh6LRn9UVfA#A ztu>{_K#5cqOa-aN4@k7Ko)E)|Zf7SQa;Zu6#Q)kTm8%?d5tm0zm(crhr5f@iOLBib zc4C3FL@0|6UAe4uV62IG82WFn`dAQl=1j(XR>7X6cNWxqyauwT0q<`1+<`v?W(J2nd!)UaFJP|AWui6fkYpu5}iD$t82jU)!k0QM>Yg6SBS z1@**<7PW$qyJe9m-PTCX1li1nR4I+2(+AwQ7K1)s&T3GJyD zB*V+AXv_$IkHP`Fds^TmH<=qwyj;ajnxsQ58Sb$vWnW)2HQ70Yxii}~tF~eo97_B# zMj7uIXK9hTgFqD`nrBI3!jf;xD!8nbPN`E2L8O?n7$YS|p-52}e3b*ru$#HCRsX#h z1~f99kU1(GW-IYi(8A6fE#FUC!g@dqC-ktBIjVCkHcV{FqW3RR#{$X4Y5D$HIBA8! z&~3q!uUHL%qp63z@h@%u&((%|ffU#kA9y$27&qN5z|99_J{eC~<`M7Y1-WZx^NbcVTF+c4jS%-d+f(9HeS)T?+H6+uuHVmcRK1nI7~;A2FZ+7O z^x@bFT*l{{bW?x41<#q^uhUZPN5b^sR%Z{Vl0K}|Dsp=2aupf`jVaF0|8>z-wfwpJ zY(=T=-T(2=_kUp_>6M0f<>2|xFO}P6;;a4HFrKUo^mJf}CwJNw7_D0@Z9KU$Wz9FI z|E9ZKAf7w@M|O=?)JwT$z_kVI8r;UYwGCD z0pBfOh^dJuo24B!QL(j6-Sq-@qoNEr;U>%8{O zq+U#v+E0ctdbn4qO!itZtdc=?8^Mj zACCyi6W_y|cCKo)%r%#0W~nIAnvsl6`(_1v|J8xecOMS27R4<07Q_azeDDvHk%YBT zQkpoIWTU>SgXfZqB-`oZv6H8o=BcQ%*QZk-f+vA$*yWwq`>%~o-FQ?CDdMzSAX zX>7rz#bSKKphkp`7T}gXksi2#=%x?HfRomY*x{@?F6n=4*a)Nx8sDyqn-)Jemia}L z%6h>FrGH7D?VIWFxc{YiZ2)FpE_QmfzlTVB&BwP`#MU6@H*LZHy~Yoa1ZIe~3v`Rw z$iKL2U;aI5w1eY|!$+H&>)38qLzaoQ$85UD0;GSSg9ATd3#=}P<_<46Ic8DPKa?Z~ zi~Pl?B-3o~ZKm8kpdR22PDX720jQ4Q)lu__DiDm$8j#X*TX1*3LGY$#sAc+G&?Y|R zj#5ns8W2Ay2j{i*d`F?;#|P`LIH>`xIU#be=P<(U$MZCCrnbxtOKM)FtC{48lo(a> zD?1!+Y+7RNjGQlKDCrht!vnjLp7iJKf*l27oC;F6J*}a&x zOJO{Z!hTq9uZ2`+YI*9m3F0lpYyy`&WtOg`zlO*Wx0%XQgh^#C(6jUcA+bNcSH zYszxI-}j3KueVy+B|RZ+jk0h{@E+A30_sgeAOR`+Ep*x}xc$n2no0F9ly^DDNZMth6H1F1QgDitF##C{MisAUrOmGIB=dA>$n6fU^wGu<^ZTbff^id(SdLq`U?$dv zX3Y2(z_Nx6 zAZFQpL;)~U#F9X6-R3%=8NJBJsAQD{ur9Dky7kFMzzd5*82n0U{undjtT?`&-2Aoj zVCsChhmCWnX*3b*fihI|js3t5ocZJJ>U(?{=6_M_V(UfOGsmmlCej|4Tby86ig5s- z(B46dxmHXW*Z#0z=dqkNoP+wgNs_>7-D6L=y!Yw8#=*?rxDY>wpQj_PiTl1 z){0~+^(Kb2=?~BH*=wE{xp1l-jp!lv#4VsP34cneJylYB;TR$|rFep9VFSlpsNRjS z-k7qiW5klffk3ezO}a6YtW`Zh%-pclldmb?b%@t=bPz?&8=Ln~Grc^POH%oN;sCOf z4+}Iz&32(1Pcw*?dkwaS7Ty%WthO`Y;}In!H?j4EhGqgE*1hgex9t;XI z5qHbcH*;QZJUv}fNc&&d{gvbF@S>+X@LY(La9(MPTRBO|8}g`>YqYq=BiWrK5bn=~ zN&&$QeOFRHO#RWb#A6v*{J^h&x;K-#%7b`9OU6myaHT>%?dP2xHpDQrByjK^UI>mMdt$XBpS{8`R)Qj#(l=b`V^P#0wTPqku%gu6l>JUdJ+U=dR00WGZr>p3RAzuYR04v(Yi~)vmJp1>ko<5 zY`a?X7o?WER*F?#W1YbjpI0intX@IUDZ8C_Xl}@08gfQp>Ms%B)T)a%tecH;QQf_UiP`bZRwTYOf7rwX~-j@exdIvMoj2LKFb6ms)I}djmb$$ zX~ZJ$MG#Aq5?Q!#<0VxacWskPH#~Xz-0&I{$kUjZ=mx5I4wPrfT5~;=tMH|M5H$*9 zlqHg&A$bp~NWxlIOvOz!(huza>)-$PfBgHu{o~*M^MC%||M!RMXWUB~ z22A8qsViq5A$$(_gyYbz&dUb`a>wU9B|kdbvB_GA(&HXe>EtXOCUbdgPGgPHnd8$S zYVL(~K5CX&H#`$Z48FrjCc~zNfM>WDR(iovc^= zTF>D{7q2M;Go~0Don2!P#mmiyx{<&72Jub_@)=Sfot_kO@AC{%BV>~YffZLo&2UG0 zNN>Y~*kQFDGv$#@4Ko-OS}j!R$&J2@Kd7?=lYv*|_i(TYlB;5Fq|)e%&~uUv#+{_8 z^@a~76PVh&gUHdSFh))VieZ)c%6tt$I?fZdxO~F{qEG8FJ?9K|DBtGhvNt=ym5k)H zwU3n%7|tr}R4DozBjmbE^g+?L0a2LPqtug6nuOFtJICa|7IWbTO;XrvTuG`Iy5lEb zH&0)R(j=r@h;rfs0$euYwZjT=hf->XqWOXx1};wGAhoKHs-da}2TdeIH@nQ3gKBBa zg5dne!x44DjOpYF)y6XvKpIenT4MX2#icRn(H%l#B-|N*DNY&UgY+Y0l!6EtHLQ~r zL#teZh|!BMM$Dtmw7weRX6lw3Q#)vQ25%^#hZO`pOb*RF)QItLsY%A-OpvC?Vx)T~ zskaheai^abCo+N531X*Uf)qo~jw$A5a-SMJL}fEmgXgy7&yZoK0pG9$U!tZSLsBqoxL3b)zMURVkTNSPvboHi^0JE? zF+HQ)jO9W3WgsqPdYB-kxf0(l%!)V#4lBC0is?t@nurcDw)wbWP5fKk;EuoRQjFr9 zr0I!yq1e8fI$R1GG11VNz&KX!jUO&2zL}(D=8PQWm72iX8bjubu2cLUQeqypR4T#S zhuj=aPUdJC4A~i)B)EAKPLCr7BYw+=ln<03lfMo-(@{M^tyW}wNwe%F9< zz=?Ll{KMp9AnBW6KD2F2fKj({G`WS6jj$VoH+_ z3kr?{JgKS2h|L(nC|=(-_0oOUxp;>6Iz$ZX{KRn~FxL9X>_m5tW)Lwq@^=WPjV8XA zH$=_C%Z$p?C#O#@>-q*Ogr^eXUBYGuxc@iQ7J^J#a^&=9eypeIHzO&^UB z^AsXJhpttis|R;#9nU3rq342eFAan-&Ewc+YJ0?Dx=D`~A!5~>45c*2)(h@`kco~j z;Gn4eb;B~Z`%%CK0$O8!VIg_2ssvN7qo3qOHpgG*z&WV4hbE#Khy67985D2H0OM;i z@b^-NKS(!s?Uze8GS_%7suxp7Bq5OC;tn4z(vk~E@aa|_w90|>Bi<$L$!vnj&!BQk zix*Ep^@qDDXx6~4u4tvDwc*CHBANo^CF2YewK>@7Ajt9) zG?R_jW~t1TWInk32^4Akdd9g@bG6@T6Skb7l62%$8VEBNj>0_$E}9AnxKaQz(vvvE zq`gVIF%C;F+Y-Z2t>MVj%7zerKsfkljGD`oD#_6%NEAZ2vd|3zHYYyD%%VNPbaOgE zo+LgSqvrO}o7{u~(1;srV`w9~xx?C%x;BU#XEVml571_qX-qX!9ZA8cf0)G2Bc2*o zug@4Uhaai#P1&UpW>`k1Zm43>?m?C)Hxc!wKS(k+58_~EYHsE*8>=)#%rcIslFotz zQ6sfHCYo=xNfy%J#k9XV;By5f}V#_JT+;vK!{)hSRPxJFtNh>X!wxloKC zhg7)k#l%7N7?CzV>aCjC!_!1!6V2prE4#|!!_o0MMfsfHG9x_jHD`T>^qMm8QOvx7FmE;yWrlO0loJ|}&XnwTP}3tBPF_yyhGJNBP`G2xHY$?MjOx{#S^dMqx{Ok}6{Xs5H!a)lXqMqRqBm?kgjLLzoi6G_so zC?g6KWT@x}#*dD7ZIdncJYYA1X7N5lZG;?*@lvWxoJ4OD!83^uT|nTv_Am736&vxS zfllpy`4LJCpqkj{kF17OJ`Hw`%J;0<&zqhawRivpU5u&fr5pikR-h(bSAH5F6-bOq zh)Kep@MWPHnQr`G3?j*8{yC1CdtTIi+&r`wOJ&-pi0BSm*+vRZ>=a;b)icslavIb4WdFX#%M_7btqnZCp zEpRgLK{T)HWN24Sc@w2^F#qTz0z8(z#dXK`ed}lrX%DuDqOw)!P7MW&aFc$clN9Xy zxfYrc(1}=d>h2U?@*}ihK#6Adw2(rLqxOB@I@4bC0no02eqY-O=m(+o0rScqvAv!G z(Xbz?o>+(efu$xbi%mh8(1D@={&pBOlr$>+yPJsDz%W9D|RyDJnKhoX^zMV@4UNq;5GFhaTmCwWVl zOE)1*%NSkRl%rTZf|bb6AkR&|6Do?zRB}CII^>2#I7IVe7#u|A@)!`-j_o|hNWFrl z7VxEKSpVbkBdsx7qjtf%l6P3hdP?WPwX=@DE~#3UILVybwzXu(Y{3^r7yz zXb&kHRTRX`4P<<>S(0KL`4BgX($I(k8(c~H!YV`X!Ea}nA6cmyo5;*QUo5_RB zF?A3z_fl&&_?$AfLxRm&k04^`*0Gp*6k|d~;U$AP(rvlFfl#Y4wL`>wS0>ydhrRIX z6dq!hrR~kp5HZ?mJEMq=)_qC}{MfY?&&V-!;$-CZJ0dmCtQN!lX2^8sB6B@>AFRJp zrjd-UL|<+RgGe-h;Dn&~U6aOL!^{wF4@u7;Jwj-oo$bZi5YC*Btl%wNQ97mM`JUX#e8?B z87q*vzg&aq{D6xX1Dov=sC6^QQamAs7oM!6K3u%$7sB_zsb&0)tVL!akT5r@dwHxHCvc;mQRRLL%(S*-<%q|Jk4)xQ+XN<1 z!w+L_WO+ui(&Ejum?}LXzE6?qJ+GzRLrqCRymD39>2O2h6JQ7kaScU5Y7L6J+?oY0 zh}z#%t2hx&dI*_SR*K<~U|3R%Oo%0!*!E%>A2+%($v7%~r5l}cDwG(TW-@gGv!%o9 zZb1nWJ(Fy#AAu6VOzw|}VW#%1FBy^sL|tMmeUCDLDLuhr(p#;s=?f719ky4*?4F0= z(?h9sa!G70BiEjQ;V*Bk1*2n(3YCKe%!-Qvn-&ki_QAXB1L8@0ExhpEMrI-g<1q0tg zt(Q^zA{WdNXD1HCw9)Y-hl`fGH5r7)!ggxV5dYOpl<5(K#28-%fmzPAvMF8cAYJtV zTJC~F$MF_SWVmp@SkAEM-WH^h*R6hfv;&nP+9Q|sh~!?Fz0zJ8BtAT}L1y3cxhHUH z&RK15YEQ=ek<@hOzf!jhmn`EdVQq7*s3UdEo)Awv667)9%t?<)rS+WXW@^1|%~~LI(3rh)YmH0y|!mqc`QtnIZh@5*`YJ1g|XDRNUa{aB`MJ zoNCl1v6Lq&Pr%3>6>{&#w&23~^UxvM`CZ7;9z#$uxEE785~RQ@gMt9NnS|}b1hL_= z4C_R^7DqQVN59mYq6{q|Fi&n~CwNh9o~c$^2k^V6&wfETcHpq9qlvu(XU`K`I%Um? z7PB73Sg7+$AqVEq&wI?BLJ%>G`B)b##&))U5Fb`{4{siFkrY;=ttJrsl#X#az4;BI z#sy7d)L10tkj?bq9Q2HQ-Y!7j>SGk47ZtQv(c)9&7vKLwp{3!Mc38R9>GQBcI6V0( zV;$@ml0-Utd69%li3!@G&KHS^VftRj6*QM^O)5UrWK3EMhjG?fZCk zd_Ba7w6c1+MPmJ3$oNTJpSwatg;r=}RCt3+W!G1SO8dQpAQ3rfMV#7Pq#EXT12gZtAb3Br;9B!3*rw7jLc38V#V8Oonm(87HGLnEb}jsIK6?zw~Y@F zO2+ZQa~^BOPSSeu0L_-C5-lsKoRzdzW)q^dRDK|JxCLHz_`T9C{UXgMN{B8mTKg7> zD@A8xPs#-}a;T(6O9-y%1b@<+wDbPT=wb3{#mJa^_Z2HkjuKAkHku8V1yODFV9b=V zoW@skC;A#@WO<}$vmVa%;A}FF8czx-Of7)>8zk8;0ok-8m{3i(L2Y#7unura$M`i$ zOm+lNIwsRG2CIH3R4nW{jTDKFFf-ELG>eo09Zs;$c7hu-Y_*=8Let>K&+zoJOPkRB z{tLwiUHqdZllM%&NUDz(N_~$(6X^B3+`N;xfD{p?eR<_3{_a6>FGV_gOgU{U-o2C> zHrzB|OYpUCYzopqY5AJg;7?td9c5Dmvg(#^zB zZT0i0`ei}TqhV>L_iS34(eApME{+Zj$7+jhY{_4sqp{(6fgVyv+Y5H;6m>^Y zb(TELzZK+RejrRB8ny#6J|xfpqj?H_jgdO@17c50^syg8D-2sfRxjdF);4Ax5k_6L zt7&mW*c%_E5CvXu*FmMmD2o&#ROy35uS$D~b^)T!e{58~^{d#J;AQ?xbTk%0qj8A_ znv4ElfLvZBRZs%-lo#(EA_8gYqT2m{V9zDv8}thYbb*BkbNVH)Wp_vbk=%;CIW!+2 zLijbW)GS1Fp+j-%l`;!pqWQ(INFv7n3KM2|7&_YdN4eWI^q5D4rWxG>v5_R~#p^b^ zfEQqpgd0Uzvc4lyHY5fRq3~8B5=Of#9n>ZSV-V34;N|(193p5PnA4kKm zLoqbC_T@`4XVLlhVvdv(K<=jS8n%V>oz5rXl&l{u~^!sp$S_AzNIbBrWhOz?$SCkbbqWmwuR zvc}MOx+|Z?Cd6d!I39+e#qiM8yPrGo$_5+iCXR=p`eJx+-QgFK4jx7*6i34f%Yt~g z{WcC?8Nq2B4@b75yiyNAXojBjMM4cg>qputf(@E2KCfwTb^pe%CPPAHn{3gIMT;=cdSdu>$`m} zF9yDDN}FXS8~j5RH39zDnu+{4IZho+fd6I2fb|D~wM91ghbnXe{Im>cj|!vV967MSZXz3e zBL|i(fDb;skzE!p#QVCe>pRgsb|)sl|JI90O&(u}E+ASduesw-U;Zwm%nB5D?09!d z(}C88S1=d~WF7%SbHx~lEfU|DULjzlx#kft5^XUAv`_jA7Q%fw4mT6U#=g&&Q6_7q zNvwSbzm?OPBLK*M8SUf$vbpj*`0MNo0BtG!iStj%v~6;T4N}287*%t>qZbLuy`u@B zT7)^nIuXX|_GtuoUjFtr--1dFW57y@FJ-t%UKQP%9tng&BH)feS_u^sV)jCQBg6v2 zVB|R=NMHUkEzHy<`>nnZ0|8;El6ed)B^IIqH?q&Cy8t(5c=s4m7+9gmJPJk-6vIHv zR=%Wx5ev>EU<9Et1Q^ixR*;QYd>#QK2@phptEj%DfZp1q)yjEmtnYF?bc^LPZ7GR*r-g51JHjNd<7I%Fid&suv>irys zMuRU-W4`f=pZUG>J4NXw{qj*mNcuc?qZQUH4e-Ju&3NFBz}B!D?P25ABygFPUw$wr zezw> z)gqjQzSH{ejbHwfv$WtYK#gUqd;^+>bq#T;Ijh^xemYsWxFq6XXLmZlSxZUze7N0x zvsJ1(3vdALMS-3THw&#p*)67x>0%wiy?5M6!Lkt#G4R0NcrmP2Z)od?IbICt{(}j$ zDdunOwky(6wW_-pB7&S-1BS$?#dqmL@Td`n8*2~|T9)qXl95knknSb$`6-Nn?(GPu z&|Fsf2!pnV+m($lE_ZiQ;cRZMz5JJGBXamMp_;gBqi1Di`wr?b z?RltE`TTsSby@a2>)5F|pK-Q);OVT-&gf~8Rf07oOh>1_E7Ce2J7AU1wWn^&i%4#v zKV}YnQBWIvX`S*YK8T9ygVbF_R80*&gUMnx&SswnS0GOtV)!B3)oJ!A%=X`~4+b$H zy`?uZbLgeJG=M+MG+bgBklD6_eKw3i=cNAi({(17IL_y}U>b$=ogY7Q{!8$1I@3!D z&g=X#lA3{f3Dq{GGuXfPVOoWo73b4kuz?xO&Y+UJEzW14C-(=>6QE2i96((et(3Re z8xoFJJ$>!`v$1zRzl9{2`L+X;3eQ>JOi8}eB|&02PlzSmHmm+=*xRys1NFHHO1OBS z``;phTok!y4t=SjZ}2T)!T^=1CE&`B`HYr)$a+~(y)^8&z|S|+9L4E^%sS8cEEZg> zTZs!xkSj1Vq*zK0XY)Tx1?IC^#4Nc5bj1Ia)RqOFGr5NQ$^uer*S%&=-7dDBi3u0L z2L!mRMjpUl8G=;o+zo-t{+p!7H4$l`fFHdWo_R*_&n5h`@;ga&5r+h?rF8Z2YwnhIM6v~fd674dqiZLw#D7}I*3eKfm2Yr z#5U{~-6@jd6_LGdONxB$md(8{t~u!OkW7Ub>-Ed+NCC#m&6S&2uV@^}MaTHITIvyr zi^z*XrhtUEX2HQ^XcbNY{}x!akAKQ``qDq$Gc67xL-TM7BIwD0thdQ^2mG?XvojQ@ zfX|id0Xu!1Wp@x+nr{D49vFuWNOqfUU%@|6P(}Ci1R3ILiC)2gFfYpwrqxoKP1_5b z2f6lB*y$D8xo_7^OM`KsX@^PoQxMTzkn@J3O}{(rG|ImB(1+QH1B@iUj?>sH8b?$Z zWwCoa;zsU$iS5%r%x61@4Aa@CAi@oC5dqI5xzhrk#(#GKKgw&Lg2^?sL;pC#?T}=c z;64Qrt_q4sc+o>wDyRd4F_-D?@rcX%Ewn+uZAoybFziU^q5nX_*#QwT+lP622NB4m zUfjR)Ki+i9M$unS>Q*7tTTYuqM%tfa2xW(PFNSIQggvU1 znccrZfE7s723%}X#6Bf0Eajw+&-DwRA?l2XMMV9$UD%_E9rgYVbsm9j`C_k}D(JND zq5dk`{{9AmXJARb_@&6y%&=GPy4(sa2a|_qu-7ZFCLctOr_^2cYIYMIG^6)8eV~Zn zft~qcucB4Bq|PCGO-`$yfeV}3=W}r2Qu<9LE(eNia%{cFBWexOi5MWba$j~YN~BlarC zH~t0zc8^R8J)v()6~z&FzK{CylI zQag6d1D{s$zgHHM!Mu8s#vbqzy^M7XS3G9k;&0ghtEO21$OSkr_D|W2jn76 zdm@Y60$cV0x$A)%s*&jys84z1j*gl&qq6ITX7D&XeLP*|aklPz#MbKf`T65B7tqt` z`A-l18QZGgxYqN&OFiv!;6{EftgqO1{XX|QCPU#PoG7mE*hc+6xiAEJI=Ap4>qtLF z0Z}<*a~Qwn>{T(Z6?M37x7gPFb~$pN2CEQp zYDwRNe-AFt?|NQ_beQgW`5uu+Y;}HL^KOe>RZ3vG=Ka~_3%|E#Y+HVxG#=BTX!$mT z`1{j;1vljv&5kqTJX>7(9uXY-h^;l~(2T%VY~&>GKV+Ue3AKo=?HkvIygx6*+vPE# zwBDV~O|cyCzVc;Zp3#|4?r&BidA&6$2L9!{_4xeo2z<{1d7s5^?8^RTbdA~_V|hsM?r1YJJGw!epw3{Ni~f|R!6`) z6RV#Be-G@#=j00$QzXbN!bM##$VFdDY zCE-)xe*=r_(S3(oXUBTc8Grv2_-kNiJ({kY)M`(@(u+m#a;RFqut+j})BZ4Q(-lNo z;439FE{J@3-rT4+-SY&h4sD|E zSIe~LU2%Fbuyn{QU+6{JD(Cx`5YujP*AV!*J&r5ee1pa%w2t1M;Pe@&oD@BzMwt7b zzoA|9eG5uUgUU7)h2|4Mre`of2TCK{nN^xZiRg1(Xli()xBPJP}& z+vuC|nkw7WHVtptCfthDj=D8q<*%Jc0V?S^?)2+?(9PB>_d^<7Lo4WqMUnyV&hEJnD?I8r3z*$uz%>Hi z3AjEyc`|?j(KQ0D2IPwSoq+3Wo`1v^&i7fJ2KbWGXK%0};`;FDpRsN8O%b;8`v-VT zZ?66njTicSwp-V!PYuv;Hh+Bz{5!OJzHCLDaLtOv2q(G<@6f(^qbfBxWv?pr8K-l| z^FwsF=6#)E1oG_4-49vheTi+DC;M7<_LbwNo#Rs))?#tidCbBzTqGrBr0Pc}@1*KK zWEOg%1Lo8yVU9p{N|+ylOeHE}L`Oxy0q|ZC@I&D5vGwqM*0KS)@&Kl@mI?ST{9o=y zjx2{aY9u2ximuW_;rs^pCk4KM4ebj&jdQR!^(oK1-y3ZK|5=09`x#mSZ&WY`AeXx> zP6YWCTK#S`ql`dyno&MH<#%YwyHQdYfINK{$Y+g*SBBO@i=_HloGwb;45l)8Me~Zq zBp;>iuF8r|iy}~rws;P~w}aRd5n(82+K%cti{ge?O-LUfPSJf<|GTmPU_O&1D2j>C z381GZp*{uw7TDMh_@m8(L*}tNEl*^gdthU`5HX8OGZbm`lQRettp{Fz?tz`{ATrv} zH>8N&*>xgC9)a!cLS(R2X^e=u_x(gfo`LP{Akq)Y4#A%vl>Jo3UxA(NB1Dk{vjt*z znA6A8<@C!6lAq;5ufyZtozA#uyaPMiMTl;ga7>7zQS%V|FwmEuzEnC%(TPAaY8o-c3ukUTP~{LtMa_;N=a$JStHpM-FDaJ~5NU$3!^OHE3h@QQFkPG# z?|0L`-BDMrX_3J?k&Uk3?qVMTZ8!3q2tMhekY}AI5;o>3w+amrSwk`gLqvNNA{N=u|06n-6^s*sCVZVv zGwTpXLD>j=yT$NKL}F{xhi=3Wk@n3)oA4nU{l-?M8`Ibggmo-Xj3geO{vH8Ddq%Fm z*KZf44~5uE(0zF3x7c!Y!wxrRzE}O_=@m@^hi4uRTbQH`<+Y5Uu>rbfl-avAvLt=O zGLP6AbR(;_#t4!5g2rcT#BHea zGkj?BVFq-F$aDtuLqvXK8_Y*nNem6J7YKg{{x!I(d=QF_$S@s>eTc>_u(4d;^e8kQ z;V~Z?e~8FEwxWDk;us+^U*h->kw!0*LQ4Fc{97T zw*sT5_9dRpzIg0mei4k=K1TZX{rY0T|N7D?MCK6q_1FgUB2z9p7zk|H_Z9x1%O8S& ziLEfVw%H!zQCq^t`}o!eYfop44!^O*=4i*&i9UwEh$}i}bPDraW2?=J4xnS8M=hVH z0DX(CG%v!HL!iqL=xu@rVudsEPR$_F(_&w1q|2 z6=m~7_L#lN;S~7Ug)ton*ZH$!_$N1}oC5zVxY)c|KWuOfe;TF9+$4OlIBAAO!HwrlAbY?rg=P2~uy3)Q=WS8+0PMoU{~NH`5I${S zfw65fKLES%E&m2=)-*YG6$kBq|G)p=KmF_f1Be&+`Ii?=Ks}&}_!xY-+{-qAEAtbF z>YRJwXbpYbU)RfnUb<*}cYnm%AB_v~hL^O>UyS$db#2%CGtdAD1(@8v(S*y3g2UcX zl30p;89G<8JJ)BKIk;R1KM0ERmq^qc(uFkr{S8FRGk$b+T`1y%qTV1b{I)X`qggcD zKj9u0_w4t#fKJaMTPnd~LrXkZw|;-US;WC=h~M`IxVZJwN;s5uc>n&so=**H%Dq|C ze-Fowig5rYD(tZR3Ke$`j0R42x*+2XdvTw61Hq0&kGYA%o94Cs^#MIx9b3`Ez@dj= zN22(+1^xB*{*{6Yii6u{zJV;^?oNIE)jtRG>9{y!Fn^B@wnpm2b9H-Oc76tioCV*ZaegwcnzjsF_cz*7RmJ+=6=f#!BUeqLeeh#viY?)9AK;OyprrKsSf`xwY z=-sO)ileu*)Ix=0E7M!1j<2nAh@#;w_nfenfbpS~=bPOD1QBqzTa|QZ+^9uqY{4l^ zU3|hi?jFx5xL&q80IuThF}$mj7zEOt>feBDK*&tJ{_31-YI08$U~g<;=VBA$L;lsL z=LGRvK6d;0sx$9l8tW6`F{v0k%^IYIyRUFl@CQIGm~?RL?8GP9WRoSV-?>lpaeG@& zDv}sLEtqt0Y?vJTRM2bjZ$iia_;D{_D}mmAKSR3y z?gbKuXIT8^%pn#Z50cq!8BaF~=ClpxpsaFE%Rb)xuYULP<}#km^zj!`d@rWK6$7jv z5`RQ98xNdPMErmK`~UurfB(0C{M&;R=$|M;hWrAC$V2><8b{_~&y^$4~#EjEO0 z{m@6Sk%e?>eH&>xhBs$+tqz3c^Y`M^s?ThI(GeTY2a)lPl?k{Z7y_2Wy3kYeVqMnu zs)&0NU5YGQl~Sb;_k2V3?G+|E`qv@)b30k_+Ve)IoD*L{9j%Hiv?eTOcaFd%M^)`auxlT~}{bahT_%ZMz#B>%LX?4i`@LtGPi zuWB)0OByqAUMFcSXm_}w(qX^97s?kE&+eLkRbtzRLUsw@Jdvt^+kbaG&h2+M^I4ds z6}V4S|C6N(jtp&}iPt)Vx%}uKz~yB`#&9(!R>A(=fw>#H!hrqU7cXQ5Yy&>XW})m0 zYie5O=f&o_T?CSDSwHhNXkJETd}@@^T+p`91W(PiA`WP^%V=`i$Dnz|;SgxGH@i}F zb1Q?#HlJdue|Obs+wYEa$EOG9wm)tMm)x$-8f?G&7r=!QNk6m~G^WY`ZvW6q)=zba zd++pia#->{6kt9*x%vCKJ&9``$<(f(t)B@p+Vq zWrMbTD0pse4z2W(b;S-o!S=db6c%$8{Ecl&H0562S6ZVlsU@cSXyrY1?=BB|Uud;k zU))$vF`Lz1zRT~Ld2*!** z4WKoi2T$VCk(*+-`|lNzxGs;c9>oTLFrqZgII;ScNsOX-0 z0~qhGbfX99@Vw$E;dzhaxciuLz?TTc3YW)z zhTPRe$m9&705eZ=mH`}7aT`_^EW3?sw8XYm$;lapvIRLOi&BaylK5D8(Q52YbZ z{-Z(VAZ^@erDU(>gjdoW9%x2O*#9XGcTdPK*Gs9pZVXx$3B{ei+BY^KPvE!jW~AtC zeHNzl_nrUTemJbUSU=}ve{@OSnnjm4K!56Tp6 zel(6{U}v~MZ(Wpy24pdJ8qhYIbYT108qN0I1LOE zdqEenWEqe)I9gt)vVvZ9iHg+P-`6 zpoC`o*(jDTd;p?}Q6;H%=-VG$fa{cpbt38 zrmtmwY#taU)aB)M3BOChoA-`$Sk6`sMNF6vzW==h&-*hdzrv-86v=%*m!wCdVEWez`9%oS$K*vzOi2gB$@wyIRhAk|{2{ z4BU<6Pth(wnr45gL1@?EjBWm|tpwJWA50+b-%UpmlYDHO6SD0-;fdG~m2dtQ|Bw>~ zm#?w8yEbU24Wvn@TO8loTF{)dq}c#%(*&Y0GlSb}ok=tvV-Pz=ue%?qY8`CvlxfM8l0WKB037-^OC8hfZARbRMRNLf#b zk?nC0HF8{zkxDx5d#sKg6GZFb`3 zsjzY&JC_?zq8mnIY>+n$r9=>u(nRI4_U-7W5R_7X=xUX2^LAZP30T+xAtq7Mv$+FRvG~Wkq?_KeyYBeFg`dcqAm7#qL<~bV_Nx z-Z0hnTjrp&oa1?aUa;;L%H;3VY?@;U362pIZK!Z{pAm~~VF*&EB_0%?e`r}}n@6~C zOa*b;b_rN!CI~w=RGP2|%S@J-wbRtZac%EuTf~M8!$B{0bza!k@putk<#>{RW_o0O ztvM;0co|z+p7VIe6HqKkfVD>HP$h-8pm$6odVX*84!xda2NDhUTL00ZKqCXM`h1=r z1Sl-UaPTT6iU5PAYpv~gllFQ4e9L+rR-kVlPE7UDLEs2fh1BouRs|Sx?KXL$C{FkO z{@N21g4L3z4ymkR*eSD%Ry>k?;>Sc7&=QV4;egF)!P(`?I*$XSzSkEt!i>?nZYfV4 zIR4ywC&o{b`P&T@JrN&!Up6#njPG9bqyM)elhbPAH}2yrcJ;DuC!B{tx6TStVsM8t z20WSL4!>L=bHBagrszdc@$ zQ)e5wB+D_aj8tZVPNO^U@-K|dSp}xLUH?sWUUrm%1ue~!fefKz}ptnz;5K-n> zpk|Rd0B0AdE+$>`$ti-e&LK#bhgY}QQ32QuoR0U0nCP1;LCsw135dMC-nmIc5{n%2 z*BFy?*h`~>WA>^Pn<*tja#TXnQSu}th{4B5RP?a3iA%<;=J~@yGB}&Ho0P$C%WP3M znX!kEq)Z}|Nzs%5w_@KRM(5Dzs`AFrG1zIOU)<}C9bv|Jq%T|f;uOq%uaK_id(D>x=$&tWmH>u>^@OF49M2#Ix|*`x?NO59~+oeIfWjRr|S@4)Fg4-nTS%i6c+5dfS>k%luLgten zxM%%yPNEv+>9Nsa`gkt|n8$5O(=m<`wP8y0>-Nz13;j06>cRV4f#dVsY%(ydeL9CS zZ|=1n@)e({>AX3=>1 zOL974^u9BX0)@a6!X>`r?(7%fu%?2JPeHVC9z9KOE@p#R?621V3Oe-mW(O2yg_TSPfQo%8LTsnp@bUg{f2!c6ZQ7^Jbw4Jmq1 z5fN^QzulojIuw`>@su=CR3>u{T3UyEy)yYuN)0yu04cAqQ}Q0Z`{TmJo9xKaRYGFD zCk?EeC(^^htqjqF_In6LgEWoLC7tegkst)X%oVS6;z?|Le%!7sMixRa-jiD|xzUmz z`2ZolJZ8MI1)NQHG&8?`k!Xf-Go9d=m-hC)Ucj4K2l>7;I!vGR{Z(PqaUKG9MP+hP z9u3)~UJ{Ye5VyqPs8e)eoJd^QF~+IlJUkAr>4Q>i;7dx+zzDU#THiY=8j-1J^mDoW zYSS~~mzqMQ6VdH-v!gH`3)4}og~F(j+bcRNd}F9ZRnJjou~v9@Zsvo(Xxjx0FE|POaY;1OOF) z6=7`)NJ?QL`REX$1|&{aWkZQKUVIy#eIjF^#Qm3y8LT5&EQ-x?$a-?APmCQyTw$iW z`d84ErnUzPZOqjFgNbS&N|sW1*C1^;p(TI0)su@?nLkLX;ZJaK!&nyOZvh|2)&Pa3 zCh_=$c$iQQHjTdhq5z-l3B)O2SfLUoR0iG<{?tvMPNwZoXoZb;tZkWs5Wwg$utR*` z(h#^HS50PX_JjXQ><5-CG}j%rZ)j5TAMZ#Z;I`o2Ngz#}`eTWiTgFTrkt$bpiM4+5 zKD7w(H*GtTgY-sKNNZuF7MzeJZqq>LJ+F-_?+?Y|K=H&6jsR0I5IgQfaNv$AFBs6& z6F8o*R9fMlacTitWy&}b6Qfqo1j+RFawxK0YYqhxU6>bS!3!QNKP-Lxi&2%oz%EO6 zS><~@6g03!k<8>1KfCBr=JR-e$QwP?e3o4TdIT2*@M)=k*pl|_r2jDJL@FG(EY%0D z5db+tg+QN+*%hAG9TX&yX`EGiCP4j7cAscHKWi*Wv4SnP`1@;crDY#N>jqK;kf~{MQlPh`;cGQ4Vm3eiXv(MielVZf_WqQ zhtjWY8{e0_7#x&qTx4qaOKd7&Qge0R@SS6TheH*qOw=C8K1Jjgwb`jF6MG3RyM4 zTCKH`1!MqFc_hd1ED~x4)f8J|{BZaYHk^?#W>7q0*3Q7pFl!do*gIdEwdiOuTIb@< zNtM0`>ql^-Boz!0=S&*;7y?M7?-w;jIF{vv{0y2=+fm8#J?jJ^i38ngu46(NQ=W!F z>?=+Ujv9m3EIY~%A<2Nhe8u%7ITgK+4EaO>I1E{OBd6fT;3MaPJ}1d^&$@_Q4XI#e z<*x+ecmgT2mQ>RN?uR39V(O3!Nf_l77b^{k8$_a+>`K0)O==sPTZF&qz?B$74MLdQ zC?f5)%NpLv#3Rs-WSn_K7$wZ96TDRG?NRlQtKxjQtm)1xVo6=NaY31*!x^hiCoQiE z9^^A((R+>44aXYQf|eyOd>m`ajUQb3}u8GjR1rs(y&QVW2~r60%P11zOA_7FmZ&c9N;40smq1Hk5V=fOO41N zIvF`=qm(qk2~3%`Jg&S*l*XINqi*bMqXviIoah2P?w5-T8S2TQ8u3Pj8RATotIQ{X zHkj35tzh!O)jo`xBBU`pQXCnhW>HP>6F;&G7HJ|s^5214Y}!Xl zXOa`Vbp7SwEE4j% zwz;TwarGWW9BNUx-DD933)QOz6WHrPB^IRzYG756NZ|=-cT&KZjQstY$Qc*(5IJ%5 zJYhSTkudM+OJm-vO05zfJXcD)+Qf2zRH}nufbfH|c3!n0RAD{jl|z9ub0|hAN+AOL zF@@;7q(=#+Dd%!MpM34G>x*=I@d`zrLY~A86oRfKSx6!YCw#!t)5zLg*%{S!Fgwa@ zm82q$GbN4U2lNUZ zl`zTqLM=*r1AJ8IQnf~fyn8rirYh&n1?_#ODj8yLXVfwNd9j|RlqpFt@2ythkWTug zu<}-$Z@rYFXlM8 zC6$!2pq2&ij2)c}f67MeI8jWkziMHG%Gbfg6B%q_@md_|AbY; zqL4~`bMPy_6emoVc<36B)l-EFgep+a68;xnf29NEY>HebrUk>G^dLOH2|8V+O%*Er?zexj0Wuea}OC}N6aS?6JY1{ZOggx=;5BML;g7{bOO3Bk<3OL zE;b|zS!1Bkkzm7k6n$Lj;nI^MCUGdKfy9}hp zd^OqOt>J7;rEsNkc`+6kKRtXa2kzIn3%ACKT%UTg39sd@PEDsD2uq!xYy|F8?(j^V zt?FDQ&rBY=*61wP)HM&ZOMl65r|5$MD@|@Hqbi?9AyuI~dYr@)I{!nX!-o?ZW*DR$ z=!)8BCkCUvJ2kCyex8YCRCsW}(F)Y!=r)?*LOgTjUf7vbEnzAA;GEJsiSA2Hy`<7U zh#q}n@(^b9s18C737ue<>fjmIOk9-2}uOGku_@UMP?VZs`_d~PMJ3sHv)c2 z29#;3*op}8qXypxO2p_#&Jeh%^@=V~U+V)3+Jy1|nM}A`qlKEVDd;}!tFEteDqm9{ z`|a3UX*#+j2#aZz^D&}=oiZyZZ)MuI4Vjn9K9`8rksqX)=oqWx60(ye0hUfYXAF)| z>t~ZHW;+?6|IGR@h2Bv_!o^%$p_c2}jY2JDWyof;c^n$7C1%dWS`;-#I$m9s;UE(J zk&LEGiD1&$E)JPmn$X{hg#HSt=cp`6!sTm5aSRjtbtcSYNg`PzC0&cSJZSG0I)42`44oUvRMEf!X#w6_gsbIXk=j?b-F_=i-$Zz`XpW!r`gk0F<11EegL$Z6(^qt))4IVcI zw)+_;lq|W2`XWG^t56z+`S$vDVyT6QN5|k_Z-6zh(;>LV5sJM#a8q&sh268NBZXA zEJ^m{(36(Sr>KIh!x1)VI!`MA2ochBx%wHXKG653OsZ0hm*GhBW<*X6I!bhFn^lcA z)x)GGHZV-Na?nU)%}h2cJZJk5^F(ALNk{4eGc?^rT>Kp-4ww~MLLE`M7RppvqS9Im zFSA=i6eW`?5E9SnP$%WdXpAajOl#5zPA=>!3`q$_bPfGky<)Kni11;IqE##~EC~ZS zazp|$;t-SWy9`I}MGVL(AkZ!fVK{qatMK>}bR0@b6)z$LTB}k8YD3>7`LpjK)JgAA z(wq>2rUvSASMd?LjpDo_sR=mCfiz~=Sdt+l(|fEypt@#O7HgvIu-6<&m1%aXocxuw zekT!;pbMSI^cs7x=M!1mlSi6dv?6iHbTGy+>fCNvY4khhICCJRS%suEH~B5ro?K=+ zu-c?vqN{xc- zRY*R@_bM!oKmyKc`D_ubJ)ls$2g%y%U==e${hK;wPOf1n@?gEgu=;4xv{A!k&3Z0~ z!vSVamfy&Pf|zTNWWs2-%aeF%1BXS?*Oo<*LyP3BGfEt3T|phpgpobrOM0qOKZlq} zZZoERtg=VPPS91+0|RG!@a(i~qNDNurLNQaYq^+77L!_b2ZS_G8$+aSEfYjwVz6~P z7-~?O-eZubIi$n#5I1QPihDjKikS3$7egDKzd@LPFH)e3q*&{4DXroSpKZ%b4m-)(TBp)rP8$20C;$S>m!=0SPp# z@bey9_BNXQRGMt|PgKFtWUmz6B#|}lpL;fsVae#>UPlist#>~0(U=%yW1wR*v1TPh7`PjcEvDcwijE{`$4zv!XxheBqE;Y6(n?F($gkUGVew_E^^VV>>qjt5L~A!q=US3dE3HNhf+ET~?QJ*Cphs&i zvj-F_7zyGIh0H(e+c5z!#?ZJjlQ(GJ&9u=)3>;=84TcVttzVZ0Jgnhw#j|ngCo!jU zv678hI%<=6>;zKN-_Jpfes!m$iQiMV=m5j+$YwoS9dDM(JGJE_DAJ)Zs`Jz=Y+}6} z*0nluq(fUrXpXU6`*GUfvm;|J$qXdWHqcswoplrSjcNtnA zORF&x_;%S2{)zS1y%T$#o5TQf_Sl!0aqQ0N@I;!kr+YKrLYY^yx8Nc<9k=Y5vuNo&*@)f>j0Lsv03-@lKD^GW zLk>CDd4a-KPqM|(oEDtj%*NUQyAx85+1N!d!qGQMr?ri4&Whk@wcg%7!Om+e*S)LA!z0k8ZA^QvsSEnfSd|rb#mA(E<(gMcS%DN=tujw7e z9OOczJ&+e7H%blHTi7)rw9Fdixgo%Vp+3(Q2Glde ziDheVnHoEt567@#etw``xWJ&QB(l7R>rM(@>6YX?>#V=9c4_*lhM_Ye-RIJ;Q8rrB zHUCV0i}R`&TFmwgn8i4DjTXb@x*BT!$y$N2?WAGaKQ3E-5(@2K^G6C*5mRH zB|o)^Nt_4!YuzKb7va%^>riI9;-DBL_^^Dv_@)Qp*(E&*8&CFv*k~Q|rmwVMlfH4C zydb+UB9q$lZ5Km#f#iQitv$vzu#6arvZ3F4ktRdP1|tk$o)lFS#2%m+0yzdmP)pW*po1BpmBUu*)Y94yB)HA5 z!&1i<*@1mDP-|1^($B4wRFRhSZ`w9K5mx^wcbf=Qec1f9`mp==Fg71@@Y^cRdSC@0 z?j|K=PyuA&&3`uhsIaL&+$xy{F`d=uhR_$g-bXn|ib zjf+b;Vs0T8SoRr%gZEI0hb)>O^~|U6e?Sp`~Dm3J~ja zb;IiXj%(21m~LCfT98U?P%e5> zTZp69gwduUIgbdJF>utk`VJROV4&%>lE;n(cn{kvfFC)NrM8=(e{vV2jPi|SDn?r* z$B=clyFA8y)#)*AU6>w=**XHt0eOon6@rjVdq(6egxq8{P&I2bfS{2Wh$!;+eLWLCn^IgEUU}y>r7|{u$Dk3o*#5RF5B}F&Bm%r14IOXBuAy z@rQn;ZAG>w$9Tl-OI#e0f>4j`PVc^X1SK?XELFiId%Xv5mM zPmUzW0}+X>kdS3Z^JD6v(_=By#np3rV+3ot1^~_!tN@(xhyplDv93_i`Q}o2;Y3cR zwR-Fz1;<<1hb*4I`Huh`X`dAe?qqTG*o;Sz#q5ngrqsEpm6h{J(WHFE$|>PC#`&>B z5V9QOsG%G{I7{Ja2*Vh?YlO{;+)yU^+Iwm!QvkycU-SpT|2#13(Yd+8b!udFzhL9^$2kKo#@Fi!-b>ZOQV+ z^e6YY4+=C2MHW?GSN-M_>rw3=Q=6m(4hf4-L#y?DvH6=bOTu=bgv6)i$Ue9eDOHf) zc==SHpWIBwWuIw-4tI=j^Af#y&orWEx_fw7*7k?~7rX>+J>V8~0+F=8@1|v(m}N?K zOsQ+MB_>M0!~KD`MU==)EGRs_Y%!$XLPnqLU7E^bg^3`!Gh4_gez~wsADb{>t)dEI zOoDPNFl7U^Sg0s)Bge$B+UG}i*as2#9fjRK0-x8DF(#%*f%d};R|19QkH0T0GS}TQ zEL4ZNGX@mv8Q!B5!?miaW@H5Jl%8l7(|A!F16FbkoCpT;9Vz-~Umr8OznaQR^Gb?t zxS9AxefthTF8nNK{AfUpTkEAo68v0Er*@Jzqv)UL#nH@z-A9&7rlCItPsR|TwMMcK zmSe zz^=2{!N2F&1i>HQ^X19^iaO^kQ(buca_NF6|GN}#5dP1|o$$r~rPeg{trhINs*0tzx1mPbh|9lVamuoc3 ziA!4;xCDXzzXz@ZF7Mktr|bv6Cx=>=n9GtMB$`p0ajUJ-#!t=f9Q(755x%9Lk^C2P>)C6%^SYY_ap(361TjTSq-|?<>&^Tix-9Z`mQ{jMH>NYXuE))SKc_3CDkw+Vp%fXvxjc7*Ike z0=vY3j+U+9Yy4ZokpVV4q^v!dvQ z_l0rE(*7i)qx%)`SWy1Xab-&+iGp{UI#uo_e~c)ed@hGw(QjDc5P}b+-Bmc#?2`OP zHUd33u^QFl{Q9v683N`Pp6KW2izg?*X~w7Vj2m2TFR9lc?YYr@oAx9B5xM2c0NN(0 z^*wOfJ&I#PF%A%xhiOqwfOAg;V#Yn?B-7Y>6L)>d-VVgZ_iEC(SRy%6U`W>;*5W}r zSjGtb0Lg7a`_OtUCp|{02)eOM-X*ttFnR$CVxS$#agAQ;B38Y{T{AL^ht4bGQ}7={L&*01olYRV`X4e$A671lqMj&m zW*M&3X;C;rqKNRCL^(${tZFbWgY)XE8YvZSfu_R6j*-d<%r;c|JiDA?1T4{$k zpV*l~jjVn4Q?S;`Rmuo`T}|^Lm#?`zf_7ZwtnfMJWTtdIBUU8t+~AZAq}~s}QTD`d zzkD-34Zf+UiJp0(_Xq=tuWn_B9e-OC4$YbJp1=5=9F6?ByQUV%_t5Cf1(0DLu#;eb zf?wPr?5DIyl0zG0U-{%Rpiib*l>EU607`cP&@b8<#^ol|)+h0!tfr&`=~fjS;s_k9 z?KqI&wWE)oB*lsoW=xv<7~ZA#EjXV_6+K@1pqK480c>5~ovUjeJ|Peno(ug29V8UKO% zV45rER0#eJB>`$|sKh7BMY0I#YDBdvD&S*jmgoMXcv&)h$KwR%CqkI?mlkiLTVDz^ z@9|?yI$*#AH^8ONO(u(zpoMREYf}yu&ljJX0ETL@9LbgqxH%kKKqmA0m<|svDmg-4 zLz$U0Xjl>PqQOCSjRCQ?>;Q>iR6q5bY+8w1afmd-Pa}wj01x0&-(N(K>>WrS!dJyO zV^_GK@jx~i|7iffcaSL&GNX?jWeA(8&nyaRPEe+nK!j+@)1>$7SzU_nT zsZwDuBxNr^zT9!8`0E!wQe%ue(bQ}PXTarvBg@@k?BFN4NX`U_`QpS;?#~j`o|_>3 zhf5rVUuVk@a;i3W#8;DOS~-T#qog+3E1*-gO0?`yV8sPpF8mNGQ%}#mI;bStmN@#1 z%!Q9I4k8rZ$|?Iw2;UjORlkMS(@fysDO8aN#K#37&l>`7Zg^(~m71->r-U`zD@Yvz z2%SIiiV#|FWD5AZ!vR#N;0GkN2xU;vOH^63ZigiUE(198Z*nJ!{9h^ifaXD*=o3@9 zA5#!7l+&9vz`#8N9x3@91!eq7(2zmu1&CSV1m)+ zU)Io2&GLnz$G{Q1mTf`!Id0qV`}B82!Jfn(cK6ilUS>A;a4g98h7T|nXrMv;HVcI? zCGkCF>_4buazN+=?DA(&$|YCI;&kF;RMCNoC|@-Ydxl{8gZrb)tWcgfVcgBkwx6s+ z2*`vGCdiRyH31aCSJ0(0U9w0DoJN>XIYfCW*VD6a+`+~%hW+^*Xu z6QKqBG{xv^C#6YcB`oSHiESTLGhLv;vWhiR9m`ga|a6kTJ*C`ZC5RB zvAYKwlUd^xQ`}$7_W=l9zEU9+Z{R8^DbMudW%UZP6QU>rqfC@X;;KmBso;*nmEKdi zrPh&ASV#RI9<0f~9c!-^Y`pZbrU}AN@VhN6ipCv35r2?UEOj%&e@Z(NS61aUTA)LK zETQ5J#7W8n2SXq0lzk9|VYq4rHfQ~Zyx`Jiz}fdl#O#OPYHA3H#*f zlACQ>`+#BuCqRjFXgY8KB?&eGiZpA5;S6W0n}jHe(HccRKA?r78-Nyyo(Gh%%z-j? z0p)5o6*nb&M7)?m0yF;UPO{*IPR~*YY@Ur#^)W2&`M{DyK*yx>#i_wJn}GGxDQs9F zfXk0lMc}947K4|B(;$HH;l&4~geC}(0`62%??9riTfx(eA|6M6oMrRMAuY^^0Zh4m z;6?ZVQ#Gd+v75rm3r_m(9D!fMW>X*DLSWTP=xCoQHX<;oMMzEQ=pccq#}AI1YwX09 zBn`>AZEZsF;z$KXonL0wM_B^Tb0kE={Y!3*D&14SpTEC_PeykJ|4Y*)4Hh`};fPd= zOb62Grj%OpwBX@@-Eh&gSOeRduaqPvqV0nKS|eidQNgE<;Wd8w%m5>@SA#8xwlcG|4Tp9&LOCCUAlp69yf#`S#EIkUi58Tx}Eg#Mp zkP)CRLg=i9W1P4+4vH8zGo+p_p!?K;h2u!6Mb-C}Nd=;7k}t&4^cPSVPdvB)gOQZG zakE1G4j2v`6znL^bnFz#(K%~zjG4CI;bvQx+ROLrYO`$sGX_DZup`?t;3wHgG3hc_ zlCeaJQ}+V-VicC{e;|KO?ram<37sIc)TOqeb!qrZ8oUBFTYl^> z91&josVD-Y;Wy9L{m`$A;-E8)%p!@VoGI%-=@4-7=FpL4B%QBLEnWxaF&w@>qlGXY z6R7KuiAWhi{x{ba9Z-54Jk(Vwy<>W4G^6t=j=^}=20PzJ%+g)>!_04}!Z6j!J6Kv2 z(0NaivLrhRx2K8{hKTmaUo8hvw(|fAuaV|+nc#tf+Auy*2fy!W5h2{^xT2AaUZpq- zh-=#?c9jJDCzKum~ViZ4Z-ftZUe8QHgfKUILB`HmT;Z*d!WoMt$hH}FVrxQgj= z8BUQ}x|zhF=ZPV|96M4VCKjL%idWD?5tS*u2%+Dq_?BSo8qA~#=-;DY3?9UEA`Za@ zw4w8iFoUFI$^xswNgF6|I@Dqcy&VV=S4RPuSJ`^vm=cw#V84r)!L3i4JfP% zM3m8SGN^$m&5F;odxBsVsE|5*W9GxL=5yX6dHeidO7^;Zx70y+9`A%qn~GKRwxqk8 zXwD%DNBUH$hpCA;j1|%arF;$2dLRfx07mZ03(V)E1|2jYK>n3>CVI%SG`%R1arh|c zp`ksAR6w*2&2u?MvvuKxOo# zaX3ea)hCUnP;Zb4*DhT9oOJrE!Z<@hpq9f2jYJmSzr7nr~l(k!YBBpUN$k zpK-+`i?pZGJ4jE%orXJ>^(aBXzHul=F_PX$7WRZ|pjuNgi1907q_=|-8fpteNMK2p z84#olI88_tXk@5JlS_%h3ib}5H0xvLFpc29<2v}`FxwmghUMXzG+RrMh@xQ3NTCU%}m|W zk&WOJ`zN4KS!!@2wS$627f6T@9`L6PUKdpGV2u}5ZpL?M>p?X#SHe5&5u5tv82^!I zXnr3>9Pb~a@p8m5>g+{#U^{8*NBe1`&~G{)XfX;UoGH{Jw9i(0OA?uy;c@L8KzdR9 zq7R`u|6z`Y8XFiT`e?F%a*IadDI4V+Q7DAqbPh{y%N?8m0lC%E1ORH7PYXmzp=;Ed zOTLsJ%UnaPld7f%TeWR_$mD<%e^B5iWy10hUdmfxIE{^zkjSBA7epEe>&RpTCmYEK zA2bAhaL|lqL_@IN36+J5L_!I$a1aQRB$NDC_dO(mRKl7=qc%*4SIZ+iA}~+F0Wl*H zq<5fZ82W@Yq=v-4tQk?EoILG4A&nF_)A$jCjG|GDh!SC@h8f=Y90{{p9%uhUJ55x{ z0ZO`l?NQ_80q#?l{hf><23h8qf8Zfb8ssd)$P5g;kCH-yv>Xc#G;S;h>ZvIwkz3$ zEv4K*Ct*fj8kr;GM-z{3xs)*C7D{O%c+@L#Bn@VqD4Kq-hPZXpeOc}~!>z>g)QH0o z#D>GAOBO{elij7W2L*r;&Y~D}g?sg3mHzBk;iz$T36(TDiG;*iHcZJHj}djn#3)^x z%IVZ`m zVY8fE2pOA%meGsZV+1R-gKCx93dp!pjheQ$@aZ(8k0+Mp*-?xnk_dqC&Tv#vL2<>% z#|DbA-lhs}MAT%G`3K%e!p$lW9WrKZN%rC9lklvwlM-iY&?tA_Kpey#gEf|MbQv9H z4<(~?@%CwolB0gET6vJ2#9hMUV7Hutjl{89-%tLBR?RPaGAzX^x@W#K3tm+%Ndd+F6bC61(&A!G zGZ~?@9fGJ#PI7m~rXc#XR#aMVTM$RM^$Ab>qxF<2W40>}k^;N>ZZ@<+>{+-=s{{qJ*fB&d|}>z$|UGgzoaWvucg0MeM~u z9xF=*EKKL+1XRjGrIp=uM`7BC_6cP;U2O0}!t^N7b$UwwQ(fzm|Jb|-FHDVh^^2yw zu=}PUlFa#S3+5O}>Ljc{zjH5dDrjITV6!lT9mcO27Uy){(~8i72pVdFf#}j8-EC69u}18WcxD+Wk27I>aHk zBx@7Ng*bnN(XifMRc+;Rpr@xFlwAV7`CY*$^%(OoO7UBK;Y5V$Gdg>zoYB3#ys1&I zF|OfUj3hCRLx!QII+qi6r{!v}KW5;yhYR)I!~v z@eOM07;<`fvTS0aaW~VC>gbj84|A!EslZA2P1KXB0q~Qu0m~4nHNblUfyo^7?}_2~ zOx5VE0Knp?yd1+E1e72t&7NpYCV^~+uBRZ$PoGSdV#a6IkxaKGknW%}g*oimys1n; zd`#G+v8GvwofieM#H|f*GOfj-kU^f6Y&W%&j3poulEE7C+BAZX8OfqJ^@1V;B)z5) zb(QpScC?O1l{--DIY}Bho$eTtq*?}^ieV+;Cs2`3%NgR_=n3gztky~qa?|-s6I4>A zTbyK*2^~PW2bwrLuf>3kq_n7S5C%iR+<|~FS1&q-C85_q^%N|VY}VjW1)abXo{aZE z0X5gr53!ABdXpg-0e4oh4Wifalk~`L^^@RZgqM;t@i|#i!h%V#G)~R*u1feMTT(n= z`C#-pqs&MQT!4n7${?$oo#IEDV99`_Y$jS(+Zoji zGG?fHe->qiew~z=(LwVsFF$b@_Nd~oDeTg7QH%G9X}hxG)t(l zD8&9(@soYWyY)~KAvG`2B7;?<S4A6H;WiFmgH5*$X-D3v87jXRploEA1?PxKn& zXOPrOI2t#DewM3_rK*ns*S)dnla$p_1%rAC;M$^hC>j@oB1HOx@i2&4u0ruK?1nbN zYPCPf-U+xWKBO~tjAQLzFvXrl)ff>v867@O#0mu`c%EcsHVaJ+j z2`BNS46R6CtBV0oC1GAm{q&+BBlmCGf@KVxF?v9Y8(|5NR>nn*aa#C@lSVY%M_wI* zlOI4c1p)bFX_tfu8Fiw%+*E8?cnrT`TVTyWQX!00sN#-_!Ffx_;IPsv$ci?$>nSTY z#&FTh)CbUaRFfs{lgFe^Y%&jd+V}ztY1SKPRD&Tqm1u56=hG)fZYLWJz*N|*?ILtk z4@Gpbui$~}kgGh4ucUku^N1G-C`I#uQ8ehy7MnIj?ki$kLC7ekr%RlE5=zh-mE6WK zoh(hoh~!Uv+q~%kc`r{I$e-Vz|HhV4Y;Hk2JIXiTCC#<`vpkuyMHi#jtU9Zn7do>1462 z^(k4!v8-CHOrJ*j$Q+0!g-Y|_Rp)V-MYlLkS@dkp=A&n9BKl)s6(y?HxaJanaUoRRvFkD!Uc$wwYzB~2j#92?U;C)bR=m@++^C^nu%qLkHM zzj-9=3bjMBK7wLxJ!nkJY;3gt9=${Iq4Fi@md`qdicjrLV23h)tDNQ`PHN5NPBi6i z83RrNJ$ua7f@{=S&u+8Qya`t@yEeU3aS@vMngKKo59k)nk~U`nk}o#Ll&e^Z1hr7m z{g!u$qIC@~^EMxsUa_!4^A!OkjayC*Jxi21lqif%PU?@=qsY6i8=rz|=T+i5++@EP zN?@}#oDe8OG3(Z)OgzHT>S$v737bl}(o=nvb55|ZSMvzRIX>19pi+(*wmEvwHk`W~ zhK#f!G82&bMYWZr6Zx_jlF)CUc$gV8odZ)IV8JsX-^L(|x}XJM`YFTG`r|?`QvmrJ zy@PH*Wo{qI6)Y2UQ%@?KG^zA`y}de8_Bx$+jOX?*D*LN>JsG$IzzpTpHZ;sM0yMC>0t(*djUKG>TtJ64Js}t+hCZPOMOYJ`eOrr zM-u5aK(dIp7zNJZ+c6npTgSFBG?;XnaG(0w)LTdBPpx4aYOP3FWQ7^kRPNLCBKcox zMogtm>p?a(KXcOLBUtXh{B5qLVK|tSSJNkzj?am+%M9QEgUX#`FKNbr>yRe(w;?So zQILZ%|0LDRLWARali8C2u*S~fBQiUT=GW!ksZxRh)G89qOKXAOP;XMtUMT|(n zEbHD=7-(1eX05Uo^KAldP~O4(6x0&B{ZP+R?uqCI(7kLOIFWdp0}-hS?3^o{3z9n+ zN9r{>gRyxs<*zYL$gmg7nUZhg%GeQ1Fz?$$FS-0%>^2|ZCZuZmX&YVVuPzHjrhFY5YQ>?HBw<}N! z#s?&tzTv$#en_`1z;Sf5G@YU{9rWAB&rrEPHk%Mmhpd>Pn9hQ7jZsC!(q#jg>V+FT?&*Y zO=~5NkZ^e0fRRH6ozptH9qAZUETKo%l&A7BEVmk*Y^#TGM~WrIGtpTchi|e7Y{N-z zJYLP=gG~x#Ad^ePmMNs{9-bhvbJj;*=)NJR3yrTz9x**LA~y);m{UZf=}bd#TEj5+ zAaO@2BLeK&pmjl+L>}983Q6K>`!O#0Ha%t z5i*Wbi)z8u7a9o~m%7_*X&CDg<-m#6Amx6gw}?kMg4P6V@n2Y65KiEkB9M z`@m(}R^_Q#_8bA6uFGw}t-+zRne^g5VCkT&gVdA~Dw2N$+~H0+qt0h&?fDsp#Vk@H z`(DZjQy5hzty81bA!%j?Y9uR0|FPGA?pO*CG^=TokqoHSUK1=^ngj=z@&``2_OB=J z-stla#UxFmZ%dF>=etR}i4N12x-Llz%(M?>l_m#djION#LbbMGkh`Jm;;w8Vpnb%N z4Ms&CPwX=O9>@}CQCL34OJ!~g*!gMq7#*ST{_MY;GFOWXE2#S9wwgTxd8h(F^L|=` zOX5C~m*af19kN!O=L1~2c?UvW^gQ1`17706HTe**^t&fnJ`ZO0HoSyWwqc=7WN0LXyJAjMG>1>Z@Cv0tZQ zJu8Eped0yfkH9)~-j@IoP-j|N$9C8u#^)HBn$mZ|`4AZOlNpp`0jd`Rh zmsDMzW46KJK;cP9_{x$p%$*Z;bjV2M(fli`MMvqe5*;Rn>?7=&Hqk3+{;Sf3$z-_{ zIUrpOv<*%|tyUbmE~34G0CH7nQAP)ngJR;ut|0I&zg)F0~F@ODX`*^k*=;9&wR+Zf;2Ig3KA#(?z#8GXzN( zY@Tw;qn?p9Flja0+so z0{2?g@%L{*zTF~vK%y0<@AL-}nXqco}&DL^h?;1fF6B-QkqobE-T1ZrR##_7JTt3lQE3!x)MS0ogk37hD)@60a{e~b%4G;$`x+4jvI;=i?#)5F^|^)s>_4|fEF)d3((?nTn8w3y6(1m zu)cU+3D6w}tGIO60Zn>jx6LCRS3KJ->K2#zIzXxR1rC<(Jf4j12B4(J=P=|lK&kQU zPp?2xFD}~xxrBSyfec#%M~sCwwR4btgDsFtSbZVL!#;#secik~Ljrkx?5b48b>K7f z5jl2VZfA?)C4F=q$OLJT1L)<`wm|k0cGm%~Eol3Vh?~pY0=}e3uLD^kyB}nAvY_x5 zao$dN>eBEf6@4AZ>@f>iK(t7oo8NgT*$6YIH?9MpHTHo+sk`Aq6fY&0>p*7gBycF* z8q|hdSEa4%KxX1=_fah6H7nR8m}*RuT$CM;EooO9Mp_Z7Php4>bK<8LsbWns4^7EiMGwVx-RclS4#pf-0K zXkn78cnc<@6Ysj&e}f5EQ$$WY3*_nqXzsw=k}faC`5R1FsUAA>!l-wP}M2!380 z(7jd6y#;@X-~R?`Jod<$uBw1rP^a|BlIhJ$p8p1ZwgE*>a#ar8fWOK~{Rz|`iZ+o` z%NX5U8Qg-pr2PH{YOU%GNO)Bw+=9AfRR0EQF5rrs%c@?u1$9bTR}!8IjDLdwoe-fT zTGIJj2$a&m-$1SV-6FzLiilfKmnzKPK+T z6c&egG<8K?b^cdzCcDieDJ!qYxF%45?A93nMzla=_b~>tO43(?d_A;O-v0(>O?vG; z#DG)jly#W1dRlzxzZ4zTP47Owtg6Fi1Lj>kc2(}r zJdv*Ps+=3pmmclEk#;sz2COK;-Z!vsKwoN{e*-=HHUmb~Pe-oHy_@a)lM}!~wSY_P zCy3YaD3#AY;lfwf2JW}3ZWVN0hN>dy-$2jMb-?#^3!)p)mm26FL9Z)=cejYS_0SFI zOF8s!peK+BoL{#zx&eI|`uiK`Sr|7swYM~;I4=(29+|w?*9C`L59&&&?uc6MTHF4l zbD>$}ay8O-Lld@wh~EjY3zJgPJ`4W+GYq93?Ab31T(+qhgx+~PM0{?k8hQ9@(9atG z@pE^DW$6dV4@AIHsJFk!iCY61Qss%QHhFK&+6b_M6amgZAHTX#vHTppT<@1%RuK)hBW1jQJh6ao&{z;4vhnrpLnibDbUq&TRF>ZF^&%HTbM zQ9wQ^7~eqkkR$Fj!t4}`;^UnYj2pKkM-H6_@=n1hAfFQq-L4loejdm>1*3p`PB6#< zj@&kL{Jg%Roq|#NH%|%%w|_>Cp9k_z!6+b~6b!BkkAzho$U6n2fP7LgUV*Y8E|0fN zVV_`B>l#i91~(H2j-LziJ}OrrpQQ3TRQ_{wHan^80LlRM`e~KM+$pxK6odUOK$iam1!D|)b(7DcT%~4 ze3Hss${RU|UaR0vDwoNqlT>EwSLFD4An&Ad0r@1ApRxL#S6A9e0%je3HuFQ1z|qP1s3WuTS9|l}Us~QZE(AJ8A2Ie2&TwZj1;Vx@rT@ zPAZoUmXoxlQWvmq6`(t5TL3*tQI_ch(kxXQ(@u)IElnqh%VNraS*u{)Nn97^lXQL# z>tnSR&Mj_j+wxA5m(I77bbbx*E*-HJI35ukJFlHEz?(lL9IxNO4<6d0;@-kroPfS#i$TNESdl&M91f8DNW zp{CN9K6|Q!M@2u9MX6xkNnG3ZJ;8jE&fFmoIc>J(p0!S?DR++)Qy0w*`#1yB&+C;x zeU9q);hm{QFZ&qm;lMfuCwaiVrMnNMfNb(SZp*}}zw)XDtbrG%ISZOcW%Sh=t zTE9rchfbpl^=+Pc_)r!`2LO;iAMo? zCw*O@Pg0tYC35_#8LPdNF7=6%lFV_6n7s8{X0^xDPt(%jq9c9Q0hJai;I@b^;R1OFuTf1jbGOw}B@m*#Hs=&4N7`#ZcS z(;A#I7P^NkI&(|OZSS02lPqt_zm7yS_a1V zibt7yJgGCj!COiTsC$K?fO=9CzOlPWs|DqIMWKLtP5_ty93^HriT!xKH&~5Pp2zo> zxoVn)7`zV6RWtHDG7c-V_RFG!wQ=v|fdgQDX)haS(iN~4VyuC+JP-%#%T~`=x{5ow z_Kl(AWZk%M;?gL&SXn3Nk{hWBr23jXB&gYPYN zcT_bJU+HKIW2JE_t$Z5L*xgYTph-hl8U1f2T(z|US*R3xncP1ObL{G<3g${xuM)RX z&Zhy5T^;4l#IMUk<@OcV?JUUm*dr@|7|YyF|)OS*+`kGHHILj9hSu z)Giq*&|fJd!TY2JbN+~)l zUrFW2El_~$Rb$twT$QLVq;llCrxlRbsa!z5lFE^LodDVEE?B2>>0Y={cd$!gf6ZbA zxcMHu5$g5PYK)z6JpOL$jlp(z7 z%GlJlTDEIix%C^6uhR~!8rN9)A(NAxaK#KCKh%KY3qab1`%q%%fqf5Rwxqs&*X)43Wjy^grA;Dts7 z&~@S#K(C}|@D`&o2fR*Ee?0m^;>PYS^5^^;ug8V?N;*G6%g>st^_)5X8h#B1*}L_A z`qBQg9{nqJlhFzWE8@M5!IeB<+G@~AVcKwqbN($4s>5-iv`20+5*=Mp-k^Jd`bt_y zZZ8tlMZ2vimh{l)caC2!Byi-aA`9vURf|TylB$v0hybkiMV5+O##GHz-|zzLL_vffZ^3x{S=P)7Q^GUr6b1V4a!;dY!&5&{tCW z8`!4?&~?efPcNs3-khPY++!=! zDxf#$>j8ZwrCEX;v2^~Nf8)XVb?gf%%@&@B&8vXkptM(fzmn3g*s8Q!=}6d+X}2%q zLQ3O~g$`l?dV|s)&{tCW9ov~!jm&RQ+U+yCkkW+hp@Uf3f;K4a0evNkSM1LQ{C2NoO zlihLs-h%tj=QXe0r!>BOt+|xNJb-@Z=e72DV86lh=ka-uhELX@pSLdLJpupyzx~I* z{M-Lm19^Or01H>R+I3_r*h4jwl)1C-T95H<_iA(8lv z-raDF_SeH5xv@dic|WSt$4z6IX1}lBn)GSo1dkR`fiKUml_mF05=2Lq+GoRJHNN8E zw>}!TpD&Zx%g=2S&CjDcI^UPUQZK^T%|G||La$ozk`{xuAAE%6=l%#|`5O8y9M0+R zBw7DOZVQuMS-gIppHI!rd%98P=gwM;!u#9n1ft%nV#n<@%!84T%vvHL3TZ1QJw9nY z1xH>Bn3tcMqQU{5_yG5JMFx+bx99SrLfqd^oSolM0{bwMmL84JN)Rh*v27*`%j>r$ z)@4YJcEm17CjH}r=1XjghB=uLB%K$<#C3dy`SnQl)LO(Ib^QmNd=J-q86@3<CUGz>!!wOB8UY3*3$&h&T3JUD-PVx<2zCT%E^vq0pM9?*Q zagCY2>bVfj;VvtKCVHSU(61B=^+x1cB<*(|a0=eT8!GqV*a)m+R*#sGnV09${EU+C z3z`n-i)xI@tn)5kXmJYWXDb;x!p~tf?e7p>(?PXtOy0r;I%v4!VL?=yma%}vVgG)) zkS~#&q*#hZ6j(2g-p|j?_yWxziK3U!md~)JH~qSKSZ@mI)?x1BMHy)caog|9u=R49 zX|NkfS9v|Mec~%?TK>w_kKy=vj#_gX-Wj;p$iIc+x(Gn3%G)U@ny-vw$Yj#?H31EV zHAQRbbS12QIFY|3VOHhgPmmmSxGqTQ#Q30{If84v>*x~{&-bY4x#0EBpw&z7kwZ6Z zRFH|Rqv9`j0KC3f&d2ZP#^A`TTbQvbKhH@iyzeh^uhY}`a7Kmx{J!q&2A$uwM{bG>3S(BH2+k%*tPK=@(#W8R_x-2#P(=-O2(0dDROpTc?3cXx`ZTS8hyaIw=0&P*)cI*t6_JFLZ*xtx}N>N!NVP5m|oC{Z85Yimr^r9#u zN1dk&ita&M!_w8pi@bVD(>s-uyk5XbhJSW)GQnneuwuZgS9oud?ssqFr`BCg$+W=}YX=5RBK zVdXlO9V@LSu2KU%wE%n_$BrCvR(^K(1&F5Rc(63kW8~wZmIbRnZI0Z&rX-8(k<6X- z_C3jS3UYBcgt~CClbQ{GM<^P9v(935FIr^YqKIPEd#v{n_s_rdx()PdIgtGqR_;zO zsSa%UIL2_ahvRlY>D+!oWdOsQ^?0(wq7Ip7Qq?Z4cNnvzUVvg?h+cqy-c>)?&wC1* z8RRaxNG_^M4Mg_QpQrHwnioyoi#JxUR^>%nXp?qw-V{5Kf_d8sFhgWNx73YUGQU&t z)60I`fVhf^?>4X8{WT%fqbauQI}6)C;gFejtNk6``ob3SMYGx?nM}O{+;S#;YV}B_ z7qwp+HXo0na&>rF==xl`J6fM^!L#Hz8lm+m_E(5<$J9W>7DNN=oF6SDdD|$&mHh@u z8n0)OZKxGHn6KeFfplYXRZV^|$MyT-vZ9 z?El+m-|0;;G#S1a=$~RNlNf^9qv}eS^v~nBFpVo7-xr}dc~9+khEFEj2?tm%Zcjqe zFzEGgk^D}~bbzZ|bo(ZsnP9n)w$z$cA`9~JInuHRcqud&=xW9rqiF?kMQCR{4NVRS zZOBi*wH(UU#ER^KrU4E_ESh>%VbPQZ@iSwVB*)O)pHc7C%B+D_@N9{);HfvYe_ZTu zl^eT=n{ui~LqE&m+`_Wb_N;15j$Xo}u*(#kEqhiZmTsLQ{PsnWqbVFm7PB19EhK9# zJ1d}7i4Abldo-wjKr&gx|Nnpd_y74n{^Q^OHuI-Cwh0 zc5%rytbC0UcLhtn(1(rYms(ycB#RySEy0%u_@Cm)iiYjbs}|Q?D9%T+742HNrWX|g zOc|}li=E=jP7%k?S4=faFD2VNXvDSoTP9UkIuJ3MC&LHw9oX)`*R?}vQ%;6k_Fi1w%u=5h zv)P2?-lGP?^rDizeljwh(0P16#TEV`rqOS^Zw;f#dSRq-%TK@6Y6ribeFh64_s4uF z`NNGciaq-Htz4(Zvap2foe^&>lKwDz^nCO03$g-VZ(~K^^z&vfYDUZE-S2a%#Jr3P zj^fx3S3(tR6Ma_!H0XlGG^o3Z?eaF4c&2o)g6=z98e#?4@Qk947u&hcTy}BHO#0GM zK5Q8`8ZkrjLGy*-MyIAXc>3R_=nHlg!}d9tF=--YI6Z|MQk^vhVs)_AJKH*u~GiGMrT8 zy+-quE6a_Ry?xc|Q6XwqN)#nrsq@#;`eYx@?+Ri%Tte`9SlOi`v*ukk1}>&_P5wS~ z!wxt7F{hWbNQJ5X{6@OzFGm$m6B=BBQS=l?`FGOG`C$eWssGc?lQNr;y2LCf4fZ~noClF2?8^;=mR4%_eN@#23z&rcG$jOwPbsgL|k0+OhygInJ9_(Z#b z*e@Q?NQ-?aY^}^;4IwS^`K)@1#4xtjZ*zh)>TytT;&W>%A$amwtx{ zz*5E*Q}2%l?!gR4#)nNeHI}z2#`$@3WDD|5wf_Ej;(aWCo?2D>Gy|l?6fMvG+`~2% zj*OCH1y7-Ap__VUqIi1rN+)9%nvbxbe~07)52++m1W2DB;Fmr-yGM=V&#!?G*uA1Hy**^(a3&yQ`eZRj;GFS2^p$204)n4*2W zM)wmIW0ELKr$Ob*POB9?JULCbPw{%&{1B?C${T2R*Zp5qvA&1pX9Y+2sIEB};{5{-dhupG;D0Kcz_JC7rL)N8=8dJPleTS%VfX{ifk+n zqFAX5cDRYqo@SM_R@ATThX??U)oV1i_ZKk*V=|wzLVyxuf$4vig=*TrVea$x# z1NkKH@vt~r3OqJ50)~vQ_kk0r=wW}++A=`v_}6i?cvPGe0Sw^ce|DZs7`b$*8oD0g zWUMmZ$RHd5;v}4n_$_>!<*no8%%*p&@!U|Ex(D=BkJ z8bA7IeA!Hjq@~Eh%3jUPmrgVdYfF;Dk@J|Mc@HmRE{Jx@ zWBm+nZ%x~%ya}dqpVg`$*rR#JG6DWq!S?euvup{fB+VE~gMC0m{OJ4@+ zv(x|ty4oPB@Q`i7`lV;yxv+oQue zqzpW0=`L6bpI;O6Q5cOQnP_DKzIpf2AK^#@JSaudtW#Cf>9)c>nSbV~psKfrNP+8G z5(9Mcb;&OZwHFJVt5)Vs_T7Imm-83l^`WX_2k$$~)mZj*sQG#nJkmYc=P)ZST6hr( z1=aDLxC_(L0YO<*S4GTgFZOUPef-NXd|~?BV&_Yw*medv{NqvcYhjy@++M!@^SIrH zZl}eK<)W{9iFT-?yDCM9q(_V5Y-+@WkfcbKD1J#FDi&RSrgg{Nv(c0HxKsVu_O1(> z0$sorI8eGhmMZvfqdC){U^%xUX|wTyB<5l2UTaAbMicWe(w$hzrLSQRnmOg|aiCcG zP9~BZ_ejnJsc;W_qq0qOCVpFfS#Gur+Ca@0dqBHn~1J;ap{zS!tn{mai(lBVOj@??KXB`v*4e=RP;XHIc@K27_jVP?_- zyxRx&(ew|ew9I)d<%H`^r_rSUV<5AIn=|Mx3(7CaUu3_sW!ECKGvvjyp889CC;T*$ zbPDfIx6Mcv*w9S}Sou%mNO5ZB~T z`kdT{WF_LRyk3Uo_#Vx2C|%Ge0}y0pdR5D!1>}g^nlJz7O%NvFti3 zq=LMvhWaTg2Bhl*tAx(ZrUkv->3#^JI4tikp_XXcB^{jH+?3C8_5l<|Ht(5TAG6YD zT2bJ&C`WM|*^&iE(bTqa(bBw*qjDQ1mDu=qKeh>y_P~{TGhd3&cdD(AR_KxAQ{$Kh z6-vmwwAWOVP`|kjniy3Q_)UX&H}J6Ksy93jFJHca;YCpbrr|Tetsue z^{5q;)!_Xv_`6jlm4VxJVWmH|>HutSMv3&G(#=}6Rei!~WQK!B1>>5LkrTPvgevV7 zI+0Fea*&m=>tATJt#rv&6Y44>g<{vQyP>+S?Es?O1F1*t*b}9r1xf!!iD$MYbxEf?o?#G8dJVP<$_tu+-f(io zo!dsTf6Y8Y^mjN8i*qGv7K3mEYMGk%Io)bq`JvH#dbWx`np;s;-t>Ib<293esAsD; zr75KtFF#yiyUj~hUe)K4;gJuBGPbDBlAoz(_U7SvZ=bb7+x|5>uP&a=o8mK^tS}hG zk|R7}9L?Sh6C{`|9s?}(o}OIk7~3};z>?klgOh2o>}72Y%kD{oW%t*lt$i#{%k1YC zY$YQtRB8Kp_l?I(Cey3VDqIhPW%Jir1(Di+mJn^)t=K%9-V{2SEZZ2Z={3p8P7GI$ z(*cQ1#^lLPv!dXpHDAq_#wC_z@1q6*gC%5bcqxJHIG|q+S(!bG_CzOSozKRY#|_N` zx7DE4&=IYg&S6XP1H4P`@o;Ru@&N0YryuyOY)pa*OCIv^RGNilL{Ba~XT9uXJ37e% zX8UMfuwQZl-CrkJhhB>{WZhHxZTl=II>gG~Uz)iG7SbX~E|kg#3v)g%+HZVLCMjbm zOOxI&rf7lkS*pzc$&C&a+7%gko?89debVsCa1T@>&ZcbVo4BQ_@hD;hB^pJ(Fj2nWI+eyKm!lql@tIvY7VgIz1e}t zu03{_zTWH=+c5kvj$v%f0{?+o7Cl(|#E7uUm-Q%|FbBbjgK!TA8j1OG-7pv)K#{4} z2nTDxNgS@LnR`o&#rsa|t>Few2gQkpcT0`9@BKyl4qO|{MI(CeEfiaEu2HnI$0}J5 z#h;X+wepPiiW&==yhgbygQ8U+I5(^3kUU?dlb%*k8~wp%l3vx!Tr^sV?So+yS^5-F zHP!~ORbU;()~*;X8YAGH#2G!u?0D-<8Ss>R8;SVwFgeRnamPWnAuiTkqRETU){cUqe| z1+nLswsBAKOVf$7?zCRCdJwIbPRC}Lk+^!hL#PCXWdYiF15M+nSFUM#Q6~}`Sek$< zeBB}~CBrNFibhRfv?pnmm21Z_y~XTGZ{ zUa>rrHCgTa^~H9GV~vl#g`;uU(-NdusQ97zG$N{vU;JJdRqLkS>@X5RQSGLC7|xEk z@lsPoFNonV$7q?@xW%;2uQJghQMqu5iN;N*-OM?QIhe9E{T$#TTX;eW$NI%9$u~z3 zt(3M-x`W{y58HzgPuj3}Xp{hNxMT36k*jMMUq z#@~o~tJ*NIKTRy9VAG$JU{@JgXHn-AcAf99oji6@t{=$8dyjjoU^!eP*09oMvDc-w z@!q*X%8IKgk5Kb)uvF-n)NSX#^QwsX08N(IM+~H8=8E1)uvzcDamkz5t5Q5Bp_g7% zdGB*-J%;0rb%HePy~?`q;ZmF~G1{Lt);Bgz^2)i? zlh%W8`i^!e*c+NHy~ld+VQIyA*`3Qt7+N#Qbvq!_>(>ODHE=2ETj?H~&Z^|q5NH-cQj@j-B-zUa6fRrgr#D$meN1=Dgz2x0KcetTt1N zJB+HTZPGFdmY#rFGbOc)GEw8Iqo9%8^=QJ;(oyD;r1L()h}s@0PP;EF{}MYH4jOEn(2Y$l|z8G01rn$rX4Jy<>fp)xLnlN#pE5PJ^V$ zGH$iWop*KU@Y)?{NdjwMbG^GGp=cA{RRp5&$v;TN*&KyBnx8okxIHV*- zS5u&LOQSsPl_U=s%+(!tG+VBp#>VTeX31PqIeeUqV-xHoTE+ON`oQ*iG&q`Uw}t^` z5$m!Yjn~c9*M^T;K2n-_wk${E+NO^CD2}6?&T!_zMN`Z&1R0M!xbG2v+ZREs5RxeI zQFL{HkpkBi26Bu0VjXQLF<-`Ey;bz8-ebeLJX8=wk(q>mtnNFH0?le18+7!V%Q=n{ zif2n7w7ide9K%HHzxu-Ik7m74ULlk8y*Z2^$ZCKmjpj(mWZsA$E`X;6o;`^x(T4D2l#l!Awbqb*2`1F&9Ecvhxtx5i*ulKPsBBg9 zj$UP^I)8Po?how*7#ay;7s?7b(Eof`*TkR$14?#Q#d?71v|q>11aEnoAa?%VsLB28 zyOSljKY$!t$R!du&TANQUlVg0tjE_ZN7b6c^Su|pieKZJ#&fBRkc?W74F`1(I7@fA z%$De%Z(ql+eX>4)eJr+)p$#vNV2J+|;GpHpnrA9DwY)YMc8&HuhDyJA><+7#aU)>O zLvywmR9aUt-FdAsY(s`M*IO92ZAu3)9C)z{{ajeEJ>8*hV;c;57`olHAfn9hmy zeFdCA_N;x2-YLI39`ojT?u|AsaDmr)l;jmR`YG?MU8hJW+E3!?Nv6yu}ciC3#u^}B}tRs z(ixpZKQAn7tVMXiA-*w(B5)S1t)^pt?Ibo9|5n0^gktTLC(mIO#q%bgLHmfhX*}T# z6s_CV%r-P`InGg!;uJesH$A!VF_Zs!jtWsm*BGanpl_Xt*7Yu-uTWvSy7u6`B-D)G zY0vvZA45P&TY|15*!t+kU^IUD7KX-2k0PyyozDtqc`WUIi(vIHV6Me z^h7Kh(KL-}Td8_W={D-pYMRC`_Y9(+!AOnu!DBd_5;sh2N*C+La4i9)Q`i{G4g9Q^ zeouXZLHroM4V=Q(!&rCQS}(m}p>=q?n*PMX#!nA#g<)UdaBS1E(71`}(qFTOO(Hlq z>6fmz)^Xji7LBi-Tk2zs{7p-Wwx+1Juv`(;WZpVg-6+%+OUEQCj7o3nob|BtHXfw1 zST-Z4E8?1ftDN<@OTXgfSY8(_jk`W|)CYM<@+@*FZ2-Q-OXIL(M=UF?lkVxA8OcU{ z9S9iN0TNO?ZU4G^D8$JxkiL|^hqHp#^QwcPuFTcXkvSu}$N^i0pKM)l&+7wYZjdQ%kNaMKY zzWjn@qNPL17&>+L-g$sLHiexai-w?v1osfBofha@IPH_a0WP)XhL* zx1-az$ZP9j5{}l68q3ibJU>M>`8los9!F8@*#an5uFFQAF`;N2qTH8XWVQ9#H+;D! zx31Rfn5d4gR5ha7c*ts5U-bZN3x@S^8lQc2ElwgPG;gYHcOY`D_q4nIu3vnnZ zymlvyfx;?^Z6;cMlbq;+W9zCrT$~L@qi|AoJ$M?2JGg2#T6M3>yl3*8KAR+9)^D%u zhG?~?hPrgU*S#;f7#qZKcptFAv2l*qQM9gmZU2R$an>~;(2MG98PD7Q?{FbbjiOCw z|9m%wi>>FLo7ERlwf>;y12%9x?ZyK-P zDSX=H;s`cN(yh~IIhAtSg^R{l_os>%Nj083k`pzJR48_5j)mgB-Z1gR9=K|qL3&NS zg>|(zGrguh{`6rfeHl_WkMTX$^;vAZ;*D^_D$QoZ#=7ZD2ds;!RpQYlYHWHX7rb9c zt%;Hg4?p^Pe*)K7zSO0@2x*gF-wZUYCFcLdSvZ`}RJnZVcfYfXPL~VhOGW18qW$#| zl0@@py~tP;X#Sdop?{C_XuO8Qez8$pJU}w>tcR}0qcZ*u=uoS+{hbo&T&(<@qPPs^IY$ zc4-hHFDH+d=nr!-9PgoW!b4lp5OTqC0(NKXGDa50MDT{#u``9$ z2-+|;8MO_s)o4In0dq&4SL zI0;n)+$xeDY?XS^dES9#`cnIgp+maGC(p)7wBmli!+s1Kh|JwR zxU1U7KmSboFmH5|F=NTSC*OxMEqU3deU#b0MTI7W?4Or6RX5DCK7TF=n{UmpiZPEl zkb%PCx{Fy#C68oXYS~KORpP1sP#KYS{Ym$^ge=#`u?DLAOm2*QINo^j;0B0+u^_Wj zqebF@MdQm)b{g*$reHobGqjId_O*Xaw7Kba4kneK+|P4UX)__uc#7_O;Nl1Vg&QCw z2r=%x=@i^PdWtfNp$9k`=x2Gva}^xiby7@!k}dJMdQ@5QM=|sh?7QC7KD)dshUe!o z8b;i48o{X*wj|Kb8LD*Y%5iKDc0$xXd*nD0HxC&4o%xx*kwn8!xkDVkWIBrVnOfu) z1OIuG|3MRR9aFk8xG$HHlt-7N1NbEXVU_x>Ad9hpSeI2Jv{g zCo7E*W|UUn(_@rn)Ok}(M)8UVX7C`A^kBg@F0&!U#6Wn(H;~-o_j#0tL-{pI2^5!2 z>ln=Xq33tcr^Hf=Q~26*f)B2!+E$qhPV2zAST@2~@oD`-PEpR!p6B1N zZdc4e`bt9lZ_!{=<&I_TTvIv!RsVp43{t zZFY5dana-q4iRPck+6~_nZQM=`t9Sxjg)2jUsM4dBDV7BDXY%@zvpM6fHG71ICQD2 zNntg@b(w>fhXyt7!>oZzm{G9he%$5fJz<8IQoNqOizX7q&X{_7 zwwd;LJZAHjq!H)095VLAtn>jUu5ID=#1|;+qxU7h-MJbWkLP`_1trWsm_P6xZ%`rI z@O31!C~@bN)gB+RBh{7m^P&bW+kP^_@XM4Xy_)&6G)6w@X`~$<ieYE;AYn5EBVnuL%+@J4M!mM2=r|7CU0{4+H$IAo^G2i2L3 zq_EEOWy_mrLi7(V{7d4<5k&{*Mnn3IHV7P<37}$hGrZH;;NEO1pQKHd>`kQr{O`D` ze$hWRIQ1oCpNQtsJ`r#StuyQnpN@f!+1plFR%|$%&GCfyKWu+uHzl`0b4N2ftn(I6 zGQ?YgR7Ul|1oTC zqb8b$Bdv%8a9KQ(6$Tzd;2t~W0-|!qr_mQ*K00nxr`-R>2QP<)^bNGU}(l?!%4Zjr4Rr%BnFFDoY4S3c!RSJq0$5heh%m?i_gC z-=hUNjfwQNmdk+Fj`Zer;cdmM12NT$Ev|zk(}-8wM?JtSy~w3Tg`x~`TpqRRbhEum z>5UTp_HwieTFac%uiq+BFz@Gu2gQNWWjLV2WZ*{P<$=#L z2b%nI9vWVKQT3%^?mW0EW1Bk-l7Zxsazcv)w%WpGm$(Bbk?_Lo5)GlFrGyP?G#%Cn zudS5eAlLbiB?n)x_sH{M$h8!R)Tc0Aut*J-VXe=X)>@K8&ncp319SCLGJ-mTpBwGZ zte1N+$o3}dlvzg85IH6;)SwGYA#6^1vc_xFcxCK9DdF#9*HboPc%AcPyGLzWz<@Vs%R zaF^2Na@d*2_Gr7(>gC&q%#)g>=Y6y)KC%lOw){M4GO7{1u}S;)b%Wve=Yy`Q+}!!| zVl@j(r-{>OtKCD9*8b6i2k;aV!0H?rryq%bMwleo@FvmcsYn6H_Cm)jX@ zlxPjSlYAp#PVSBD+nlm)KbAO34;FjI=N~>7o)CgmBS*dD;>5aLI3?gnWK?->d&^J= zONCoAj+_UjR%4mcFWO;XAmV&;7@*1Z!@PuCr?7mF$MtA_uB7uHQlqKmvox+C$5H;V zqkh=;VKMvS$bK=N%E-fdsYGgqHySVV@5(A+M<!bI>%ppyr+=)QVmKoy71{jUb-{+}NV;bJ2<|2ku@np1&Nle|xfFw*d&=?tR zmRM{<#l85TC7C>NXKUb@L6>s)e&l{Yew88azjz&qeRQEeo)1c#p9h(Bx=bhF44T#g z@+eskauvVa7ozJY@<-MPW;E#$G=~>P-;AMm?K2Y@-#08_1nq@6nHLHeET5(5l$aSI zmq9XaE+~r+i=8zu@n-OU=xV@2xj)|9K8Qh*psGHc)X1f$=mK~%2=mTtIp*YP;GDF)~5;_)-ZHHsJ=nVYUs(s@7F4Gxd^~0;G zroQ;DWe)!SqMo4hd9b229O#OT{D;--chpBxl1)*)aRAK~f}K8_6jevo1gS1!yP{^@ zcxoF>qi26}V76wK%-KAkfyOu18)k;0MzCBzoK4u62hG-bSw}JPsFC1(=o%Pix;n@} zS7O?2G>yt;Y$f{!hMmTsoJI5zQbIe-UGaf7rPkMGHlMJl?em9oxEFQt4u}_6qKP~a0wPMroW zl@!g#uw@b_@Ao5u@MZ$TI7-q`n<4Fzl@~_OuWkk8e{|npA}Zk>gMRP_I1}CP>@4~H zqUwnI7%FMx?#*c@oypV@(Q)Du;X55NPhF{)B4n~TsCwwZ+7pywTrtqVJ@Bi{QDWp- zN>2G&_>h>?qJ%m_Y2Cl~7n3}%lKm4!AOx#K-eNL+hw0-fEA`bmq7F@F1YL*HO+gxho4pE{W_aOH^af#d(sr47KuX%iFU$ic3AHQIPRyT6T3@lB5_#gZw z^#>?R&A+O{n13pb0mn#1z$ET3CFK?tyEp#NHbRU|R41vIJEY|oQ6tCB;%t!}C6#0g zMTjc12%$o#lb{U9Y)nid1EbWnZvTY1SwEm$UX)}=w9%^-$B9nnZJdnUk-fw|Vrf-- zls(Y}a-(G zxAba;|0A)#aR4~Lm>_m=Brui7<4pXL8KOtR=x_ZA3xH~)beU>EI7^tg;@V}o6??G9 zzZ|&(C=J)5mEvO(9Li9jIU!H-f`D^mB3wI5_5%FKp6>cW8-@CNVZ4-UEc>GcCPMx+fD+ zC(kXffj(Fy?T%5D#V2GVwVzg?Jv1KAEkGI^(zYUFbcyLc)OKK#k~GO85#%zLp*TgC zmL+B@;LxlF8W1-35k%2Zuw1*+LM*q zFDf3ty7QZto<&UH4dN%uvJXxum(^f=af9HV5L4p}ktODbz=wUGf{Vde+zd5y;CkR7 zTBhN8-=s_Ft$?9CFFz7~r+tDiG;PwPH*_Ef@=Dq-;^zx@WHe7lR$2}P+%nS?(_&}u4c8ppG`9XGq6ZJcPrVmAcn&w*&k)}<0{J4;(V;-^t)Paa;=dC7 z@*L5MJ!%|P23p<-C1#!fSz#NELU_R_Ok8_j6!vhHSr~ZjbVOHdOERYXB!N?E+wlaF zcn@U{@ud`qMvOeVm{I#yFA%bhg-F`?QScmO-#eez6eoLNV}M{yHay4YJ^s52SY{a@$}lWsJ#?i zZ|5$oQF{`OA8fQRlE>b&WWpCB85dl<7wONqJDxRUOk{opN(( z%F|qHoN06o3_L~4G_7fFjhctrhD~!(>zQ^MHKhw8Oe1ZM>p@-+nsW$}b5Amb_)k|B zaq5W1B%`HGLrk=V+izq(hT#|Vr#!MQ6bS>TsnXCIlNq}^MnTXeJ1T9x2$M^}S zX^@stR>QK5v!K*JDx2I8T@u2>!;SNwpvOrksV;FUXN`u04!4v9rm>aAaJ=Y5owKNs z&KgOiJ!{ZHQ*S6~-4Y-_0=r$szM{AqU>FmIw+5vT9{%{VkPIEnXLF$>+!V<<9w~iY zTvDkC2O1zREr{gInJr^-VMs+RUv~s zA|a1Ae9A{3uuBT2^7qwOq?TM%Bps&Wmkq2qv^r#9Mj3}DT&cEnLW(4U?LUDU-BSat zFSahI5nsVJvdu*j@qv^J#7uMOID82+fXA)CE~t&SYV*KUYl}AdRI*bzDkQji>ii_W zOFlG9PfUVn-omZqBiUoB6_z*&GYFtBT7Kd@ zqxv!MiH++xec=eK4EzFC=^zu^{~^q9kp>6NrWRF2f#QlVn39pkC$ET(CEOr_OtF<} z#;kXv_fDESb(0kR@k@N6<3)aeftYjy9xbBkbHyi9#(@v=TA@#{Lmh?{ou9bcPwn>G zUZX8}DRQR7hC|5Z94=ny6Y|pNYXWDWw_-@}j52?!Y`&fZCUZcrfC2_}`XP8jD8Hjp z`#=h9u@yZ|wGOb*S2st34y0b9eebh>nZj+|lF>2?5110DUJ~XKremP~8nmb+ z>g+0Z%pR{}Zzi~#Q~-f6<)8VZ$uN1yOq5F>4ygx@;;8UtaN*i3?FFiRCKs0kHs_nf z73E@)c+uv{^Aa=6uh_sTk!^WNxX(l>qk-yUj<9wuh?LPt^q5i~P1?)FjdU9MTp~_# zAtvHdW`M%Jl7!S}lQZZDo^%Ocq~TFm8xAGueHghF2xsLlbuf8Ik%q@@$F!<1!Kglv zLfK1wa)eU2=Hk>6B_@TWzy^A6RDN}k66BmazW}=jsg5W?q`1ytTbb94BJZw+d_)~8 zDJ!P({Ot{#oC>VNss05~q(+I}GU$SZatvpTQw~{NtXk6@!-`DnK>pNGxEw0t0@9$$ zNvjuWm05IQkbUE15kqnPNUa3r%*jucrlIXe+;-3+`=rTawF@!$L332pRFS_LwL;Q; zRw2e0q64Mcls-v5t;a7l<`Np><6yRo4g}WT+44|3>noAM8tK7Wxl`d_vnP%?$$1*p z){fVDn$_dRx6W{SBN8wV|Zbyr$m~QvzX5 z7x`<#+FE76>y|9uxjGpylFu5M;+j{gwb>Y$!awz2g|#%?Fndo}z8TxAla*dQg@ouz z9tUw!qv}_q$fUKi`W=x0nn_I)xb5MNHIN!sUJX{P(fHK`Eu{KMI!vWk6acyd=FquC zB2oDUQV#?oxaW#ye~p_YC{#Y7$isD2ZcIx?vTs zV0&8*jR%iKKn^+gv;d+AQ^|u;2@W}jo0^oyods4Zfv7oItqu>1n))7e83FGhGnttN za}Zv7rQ`x9w#$FXMRcJSPkO2iec(V@%t!;_?P2lgew>Oqj6gL^Qx1xgq=Xb{&8EIU z?=g)UXgX{K+4~iik>Q4eFif1qbqKSJ{MkUuTf~$YgB65c2vDwTJ1oPeP#KexqP^DG z@LGG^)h40r+JjsS@+;KHI5s@PU88YS4J))JYN19LH4+O0Ps*ak!Bj?t@&Va~l-VO; z#%ZFcM6PE39R`Ff8b%6rpk>|$GY%>z2d%?P5LaQQ{D7DX!iackG2(t=4kTk5yqAoB zJno`4Gtl=IGX{;g=~$(0welw0>Y;`eA^A?JlI*3>wI_|{4+@i<1ZYFlsB`5ZhkgWI z3K6tS$gK>sjh7FUh|!O2LN}`P@h@q!VibV#*h=Q~WHOfnFj5`{qaAi^BbQ6BIGICQ z9te@?dV@=SiW_GhUK9J1&Q&ry&ZA+gKmA+AnQtqtX;gvyI2CU;W@2>#^gpxGiVH7W zv6;zbMMD*zDDYB-28Z=dpdkd@!0A6b^3wJ2BOR}9hZ0g^r_|bm3MWq}v>ZqNf`F1p zlBkV*3xQ?SaPhfeIB5$%iUr3$ZebY}af}hfV3^;?-zwme3)`w3MCI8bgUg z87-s!h%qRSD8QmKDwmiY`NN%UQj9TH5ql53b)u=7RZiy9Nw4(d_Qh89YTbE(Qpc)) zk#nP;H|zx}$QczMtprlY-yF+TlD?m-U9cjO?#FV~&W105DoVQ*y}8~Pw+P<`TF};i z=q{l1Lt7PT(Z|~9WHkfS6J8uU6_uB^Z~TV+ zC9+i`_txUYL12q1=@r^Wa)Y&<{8Y`K*g-{d4i6qeQ&i|jC2{mMr$e=Z?nEsB;Tvc& zR8KHL<8L%lBq|$v7BXnXua&pH41cEJT&vlbl%zC5r*7JEg^rL!F>Q<|cDLGsWQCEhPPbc`$ntis+F!7;ak7E4pP3Ax%z`;mAE=P^2s6JSRQeEcg>3-T|LsQ6ZOEo_ayTskb# zqv}{D-6BVVj%0fWXIGJSvONk6WOXy~@l_L$r<=NUDLlnm{2aUfu(y4H4E>4yT&Vd8E7AD6Ij=~Hii-_v-fhfeitV$;E&@9A+ zxii{Ps`iqKgP9hlqd#+4eWDw@f~R59^f-z<+PFZz-J?0za2W>jI^SRMTTouT9Uc zgFvBKCPRo+u=v{ZQ-^fnjl9cQ8;t~MwYl)Ks4c*%RB_Z^9fN&C1o#-H6fUa*Q+&q{ znTmkn!giyxQb!GWzB+0?O*yU#8v>s|xeqRhF9LE{Q$vNc2oe)FN>^m65QEA6*Qaxa#~bDYZ6%c zoYC{PIA_>8m2miE#BXIVakdHDYheV6)t!q^gdUbte`ICbgS=W&AR_@rcmV5y?UeP~3CBV=Vpo)+Q>#aPA((x; zq0QW=ov!0M?!ksGT43vjp%B!jkmeUR0&Nr3LQ1ybc@TL;Vkny9NJbKhesK(SD9u#2 zGgy2Lw+G@! z%#2p;+{_HfF(bROz}1zBl1(Sx#$-Q2_r{7{HJb#8CLe3Kf>Q3C)YpVZxgvN1Waa-F zy_l1*bix$-uLM)ED0VJ~Z6A^zs@cW>QMk}WJ_2Tp-tjUsTKmP^265#os+M1M{u|lG z7XCwBoB!t(V~A}ZACTfgY>!pgn-U98EZj>(f--G31+J5bn=~sWrGQ5hS-stXhoCVP znQBN;j?EZ3#?!NM4j6KK;Way47utG7DA%j(^Aw{W7s49ekcG99hK>Q%k)<+}ZH!l$ z)euTEq_eL0Ad)}Yi|X;J?})3pB~@(06>?)UBN9dP|fYBy$;2vSe&aCq~Sbq`P!K z7O^7IL@nLWVnmZQ&{nBi^IN0yhDpke37SD9%QKx`(rD`iN48?bFDkGXH|aPm>LA!f zO*R^4NoK_EnIAMiZs?lvFs>?#>vauH0bPP%Snj=574c!tu8R2Z4q!`?VNX{1G3uiT znX1U@ND)`3C}p=8DH5v0949IdFy};nz^rk#o!t_mLY+%s#M56cpc=O&i)w8IH^kCR zD>8D^nKq_i`V?#r7>g3`{AV`N%b4($!6LYO zc!P6TKD0QlD#A6LR5px}38lu1)*?n*;&82}1c-yMD1DFr!GqX;s=TDO<9tYfh!qSP z$Z;XH?h6_3jo>SD0<PrLY(ti0Y*BCwCpalW86Rv8&&#?D3!-{VO9Xk!Vl;>{VTF7!vge z8d;Zx4DrwiFD<79*t+1#uGhbUBNAH21(botIMr@kfW2cJIgkQJS>j5NcyL$d1+cK7 z+rMJFGB7~z7>5qzu&pPxd2E*^258sEZvP7I(!>BG-8gq32an{*LY%nDztzkDqgp?} zwc=X#!WqTJDY8jS%Q?%f(Rfj>4SlZ_)pBltQR=05Fj3o8B#yHC*0!>-HN;HlP}>r> zkqPntM0fxjf0cRZ4J@YFFol!oAtOW1LmymHp)u>!4N(@`h6l(O{v&}8x}8_1BLOi- zw^a+bcu7}mk~yQOmdgcP_BIF*gtjN~74iU@GJ+AFoe8V#!7`rX(-Ru2L3Ia&)+nNr zKJEpy!Ql*%y=D`W$Xc0KtiL7LwSsx-Umd!ZnCe`0GTC;e|OBtZ5qPnegC1Hk~+%_f(!tj){6GIvVnUMXE&U(+_xQ>o?Rg6~@GcXhN#%L4j#CjB?m9 zacQT*!!*E94%OoCVA1G#JVLq+3ZK1*?V*$M_(?-V*(_oO)eIIybQJvo`;Q6$m^vbt zX8%Z2g9=1E&iYMHIGk4+GLD}O;mLcnRasmVo2@h%-BJ576EM;Vs^{B(3_2G*O@MP{F4p4NGgL+$W>?f)y1uFVz3BYjf2`~Z zJV+}Pyh@&Rp;>v9o)B_&N-&aPN+(xPKdY1&F70OWo?(b7qwTFMm!nMCkCc3%c4=wf z9>s3r4lXe(eL028H0LkgViI5MxQ4mwVw&G-@7rkqo3w@BZc=9QFXTmX;`R*xH>$q%90t;0vX@fnUVG8%=`4gepwF}C$CppBh zq{F!8d)bTn>V+=%gc#WCbU8ChjK|Af6SL`a47Qx?*~8B< z7a^m?$#*h2lwR@X4!ku`=6oZb!@}(-2`uA5(RwaoF-!O6_2WgR)~_|xbIyG+=j$10 zQ7!eD6Q3f0YTOqDXw}FlIsss6WU}19VUlB!FC1Neq7%+S=Vy$NC)$E0zn44>)fOkn zF^XOBQ@Gz9s?mEo2>B`mO7s>GoOl{2BM29d^kp;gWxA~A|8a~CJ9y-ot8^*a{5D$P zTh3{raT~|7nRr1XQ~lXO3VhJG*<|ThUKdmF!4iy>>eSNJwZ#`s-_ryb(qR+I;ua^y zLrjE&W)ZKy9uHzN#xm&OXh%QV#ZcZnK>3eF@^m}#Liae*F&k))MJSDCx7O>1&*sCz zXd0|qm{{K<7JbAjCAotq{6~7TiTLO}sc?&~R9?u!bA%MR6#vWtlpKlHb>sv(eB0sc z5t`i*y(fnc_iZ6xK3X1Sy2~zJj50;Ov>yVx#F%LPp|wdr_Dxq(ttm0xdyHP)rzQBH z7u8!Q^C5K#fmR`Pd>Jh5fHdxlk<7n{`o_CJVj0X8-yG!0;#Mfj>OHl0Z$8+a zB;l5~xwe?fQvCi}`@w`xhI(LN`}A*NBC&gsPVwSIkq#s$WlE>`MfPd;rrVAjH~U;f z$;xf@e!rgqH1159tryZi$%#v^ooM$V5-GAE<^Rd-8H)4%*mY3c2t0F6P;tSlzv5G!Y* z1?G~mY4DmPKC0E{4C(M;soAcRtWx)D!KcP##PWggKI;` z=rL@rkdJ0C+S%YyUITNK(JSF=lH}76q3NV0M?Sb2!f8+=L!h>mQ30hMY*B!jUKgmR zDHM!r;LyU=Sgq`bX7Z`7j4~WD`n#7mp5Y|8rB~p<5pE$k&bVY2rG&68j5(dV81uh;**gF?3Z^Xz%t^ajYkn1*%o}P{Al-wH){cb9qWdVQ|3TZ4Cuf?VaVIj939!`FVkQqL_1MKX z$P=dL(gK4`#Z4v@EUqDPN5%&;)2Pf)n1K;-dW83AL=vN0zjQt1eHfSFu!Bd9Y5d}- z@F{ECF>()XF+|Q!p}nTrD}qWT!1UK3GKT1)n6b6REOziI1Bq7Z-Ck4K9h8k0gPq;u>Er!Em?3DdoJ_Pdms)Ho%@_rg6 zYDU6pscGJ}KAPk6KBHMbh~d^Lyo-K6tD*x(zs^nDtgLEd%PG8ou3GBmF_u00D^@nM zOaL$&B<%5dH*NDFs*8kQXp3D?uR2=t8H=UuJ*3+#ZDIi#3DY@h1)z5f%eBV~294at z&NIA;Llx*tP_T2>Z125is3F(O14wjf4|K?HEU)pt;U0{C*<8ag%1D?_5R|2P_iz=Z zkf2g7YKv9Ldn~W<9wPe3EP~e&E^9O0DI6p@%k6x`3lywc1^U4xNt{cWY8RLbSzglxdGGR=h?8fejQ87$0Bp^!2PH!bpGk}tI+5N8yi3dD z;bf$Yw}&^ItQyYdCtgs5ofl~&>^#MCV@xQGbH?`9vU$dx!O^LKAl_AE*zO|NVnhrb zN$-vk&$>y_EbCckAh%WcwG~%!eiR#Lxj2%B#`%g&%CNf??w}-hktD>;z^k@6?=1f0 zn6(u0O&0mtiY@|`*bnylm(`-W zAQOb_^u`wM3w_2pyH?GiBqKQ+!_%rD=JeiX-f+oP%DnNpy%MwS^mg$(79gws-@Hl@ ztuZ5t<9HJ#nFE!fr1#}EXP|c-FW5NMhO>O5(XsO#H#UhjE2lv4gEL}hFvPXfq5l{y ztscq75-%x7d(YrO-b6>HU}xy)ojS~TTU_KsEKN}AX;o`gA@Yx zf{NbH+^ATkkml>7XK%vDB?}2g?Q}%h{Z5%&2;MXrVoOHaUR76L z*{Fij=K+fw5m+ZxsJ6OZ6Nd`Ps$Eb#%DV{3bi|Cr8B>AU>)xllLdqdCSzhE)lXul( zz#thjr*rc#z-?_V&vGT!KV~P(dyce^(vzEG6R}DHxy=aTNtLzr8NsF4 z>HN-3!Zco&Qk1uWe7_tr*22A)Cng9$E{>$$N!8w`H2#RxZ1OCAU5*;Fv{vAk zl%Tk@^C;I`+UuXpi0_&R_7GIK3~ud+}{3Tl%(ZdFFqx> zwfl_%V@W|Tk_s=jvWqISx4UAfOn^&B7z*9?_5(eqP4@DB>qv+=t8%D!Dhs~OZKU-7 zCJIu?oZwJjR=O?CB?VP|zNBF9P})W{T_{RX-iGk=a(tL|H`WySYZd9+K6}dx>vjdP zv+fEjIDb(o%A0720ezi@jY({!rM8C7cwWQn9Z7pjHRP3{{Jg7PSYu!_`1;CHTif9O zEGg(KOE-nyxMN(Bbz3azciDE=3etvzwd%5NJ|cCitDMT2A#tZ2@r^@2RTWOVL9;&RbW2?M3xV zj<+Q7i4s$f$>Xba%k-L+8Yidj)#xeS4HniIG^8&{jZ!L1fRBC@JwZ@}5m~a{@ygit zp`-FifD{Zb*wg`RLKNhx>A|qIb-kWTfH<{^&fxfM?G23eV0t;XzcAsJD`J?2dk^{6 z(>Xo5YD$tg`7HgSt_V+^o=bR)gFso(w#bEtpIF3YkMO-8nBrs@ARxWc_aNlrgpivqj1n z6I7xy{7C`#o8T?8qKk7yX@=o z@T#yxcX8#Zv1gU48V|5mfRFDgE75?ZtWiUDHmQo){rfR^gHIm7^^`G(u#Hd9{crfZ zdyZ&WNtjmMp%F@(6qo02T2a@a(fM}|ha#(1?yd(|?G-LLX9SDTc=x=B{3(mJ=86ru zEsRhN8(LGL>n&#xo?8WF9Kt3q^hP3P>peUS)2;V&MZ+cyw^^K$#MLqdD(rC+z-5W4 z2iSO}T+jAd24CRZAq?Br&m~0XVePG`%$h(E%Fv}HV~a{gypS@qHR&Z|$GH6LC)2l# zOREzcHpw0mqVblz`&X)qnOwr%GjHq`_r!DE$xT#zpm(m?GR8M<`@c(|u%V(2`IyTZ zdriX)w6JcorW+#CdoqN7kFCm45thH~F4@|=+h*4XVkRGFQBLB@;h8m+Arg^a=}`mYhFauly%^vT}68x>RT@D(2jdfSb_yG+t?*{4?pj$w5E z8`q_qxUYJ#`ihaHsK>F@u1pOosmC@KLx*xU7 zHk&hQV-eXDNXe(xbi#|gi;7&wwn&hAVbd6rZwwtWozXdweTF-rVPn?H#VolGZ~xv# zLn6;PVbiz+y7|zQL*qB#MH145A`2RZE@tP(+~)Rw<7}tIjdSZZ0<`|$CzF~kf!xOw zZC<8MfpbXV+q-ymUE|&JYW2<$ji?A)ou`2Y{bYz)JWYF1!xT7^W5WAj{G7uGP7? z*sn%PGsILLrIGk`m>8_7gLy=buXU>cJNI^Gp^WPI24z_FImTCBT=7dn)4B|`jppR6Qz zvz*Ar^3_1vyV7rrN4y?7wymyy2f0Be>)DZMdy&wt8g;|$_GvcC+< zERn2;0#)wxZl__aKemlb3cWr_b~6GBzgCg z+!-^6MgpHYynwQEL5s&Rc$qg*a@iQ|HAr8aS@zne4u|>Qflb#I*y4mTt=}j)_?h>h zBxZYA@<=ha&Lc+MewNzo;UzukUZmU2OCF~w#|=AbkNwJ71K9VMeJ!E%F5lKE+L97K zb0K&18t;OB;v#gUG%xd}lFr8UdObx8us+8LN8llaYIcj^4qv&!Vl$Q4w=4BXAn0;kbdM zaXoM@F?E)V+PE+{o*!GFs!3~Y`AqHJ4G@<-?$rq34|e&(y>+zlB8zW%vbKX$TW^#a znoY}wuI1|(xe(&AizSSKpVttD`qPqqjTTk`HZCVa?2GJd7{m%;?;#;qa%E&q=i-&E zZ%&ochi_}G=siwy33le1LvFROHz6cApOB`Fz$@89tzz^jS3K&x&Ce|@-biXWl-mJ_ zSRp5B=#t2YnnrI`=dM+8Umw)EEoF_*Wm1}5cB)?UwL6nH09;NCbAqO^J(M~u3u~;D zPs$z_(JCEf=VorBGaH*p)v)CNybO>#Y*&NrJiuBJS5k*|R60|0;V}wfHD{5jAA4bA zHGQod_9nOZon6X^nx?Q(HAOzIn$DlwivGM4 zsRqO)MxV&swyJ#(*QSjFL!WaO6~oC$n~shf$c6wVZMekP(2=8QRRx_3d6SR91cFuE z_`KP+))|k)J@i@EC|mTtej7j2eLBb-`XI^;nklV8@yROS_>JXrbQF&_F^gnv8|j@l zI&Vz>{@8Ap7siL0K64m}Y%F;78H|OH`T54Lj_wO|-u7`-As~c9;EoTLvZqxoP?J3=ddkNCGwu;d` z0u?tCr+vG9s?B=!hV>6xD3?~8L+ST=Bx9lB44;3)-ow~^T4?w>JldBR>i>*M#i+K5 zW@Y8G{UClHm#}l4?$H_EF{C}R1xM-$Xg)Rlf5>LoCM#~}om@sW90^ATgO%Ke$kZ+5 z5>X(}s{4+;bRfToUap*ChjSpD7ZnXL=P3L4%&AE?ddC+j%N+8{U@qTeaA#so7tLt7}}9dLcI%-^jxP}k`qAdjC% zhm%e;9^0PTtB!{^{ny98xT{%LV>9c3A{4grKmKdp79fzaN|qB~+w7e}&M&U#rrle` z0AIAS7obearZ(z>mT0^q_MlMbgQhwzl}6ff6$@1i4k^h5u8Jl$qH7b-)x~RpE6ANw zd;j(JjzPNxL8u6`%fa_eOWQmYv#!!PRnQtv+Q#WZ;_hKCHmCe}b2#3A*fHIbOxF!o zUZJytrCX(caO$?N?Dv0;587XWbqP=JKbkkr%TfoD;>DGQoFUt)<4=}n4LtQMeaw*V zQ?1TkvKpIc9=WNczW(k{^KH+Eg}JX za0a9P^Ng#>eJPl_jFmQRT57or_wA=-sE`s2DquP`&F+j=E7qvw#pkiQ-`{sxEv;QZ z)x_`q5EuR0Sv-ByYt;Ne+%I4rW_po46nARI<2$(x{&aCW-ccc+ptq}cRsDG?{~MU^ zRN1jx+e7=fk@i)^em{Lzj&Cv67k(v^I9k4iWXOMnE8N6AuO%jlsn@80uR6nErc55{ z-)3gGx)p!9A#QsW(lyjeugW4CpBJ*oYt3y^=C|Yo32z4Zll=>MN97P}98GVpPLv2$~0AGo-W?SZPJ|S{HmodtYbx9dM ze#zkThe5Yl2aXDj@#1j4dtZ#x*%?$O1Za3_c!MzCW>LKg^lMpM?>Uzq4ax#Bxqs=N zqR(#+qn<3!Asr09@VK8bheP@V>oRs>A$K{#C6H%3?tx;$ir-Ea$GkBt+x_Rq8@3O} zxkMp1S0$E3yh^Uk_VbW8kdwM!j47Jymj~hZ253s^2Fq&{jF-CG^zyS!d)bDk1SEy@ ziqt($mM1BbWxT}@)Aa1Xzs$Spv6>Fl>uH)0yB_J1c`u9IXU-@=lN3%bEK3{Z8NW?& zUhqB})8l1&B3yDfoz&fg(FwOrkLWAvIgvSFEc>5ku3DP@}d4;zi0yazuxMNAG71qzc9~J-%Fla zB8Yh^4{3bQJs5x9Raf12R|5AvMpR)`BHLqw5-oL^I%N< z-Q?ni{mm}!y8N|W(R}$Tt}Gcrn6ioGl)%p$(~7(O#8+>gv?2}|piO>TMq=la91gON zi<9Iwxe~Y8zhT99@#hC=o2NLSITwF%aZBITRW?-qlz}60|Hj-{pE<1GLA%*^-bw1D zy)|S=imKzE9hb)3_U|HeUR>I83Z`SYy0r6M8<(~(KY13o6%&4TPTit@o|+q1uw30 z-})rMX@+`=D>ucq|JB7Jcd7X#!6~eoFY;t7_dk1aD|dOYgUW3sMJTVWa^IZQUUpI| zxk{=|=6lJ=sE94&y>z1LwF5)+d%=nn_B1+~vd+ynikBvxT)*?$+8Ct1(0%>d0{t;t zX7KgbR!sHGiq3vBgB8^CfNA~d?bo`qyHwR7E8og-Bz2xEaefHOLepre+&4gIm*3ZA zwCCtxmF@66cf{8P>xX*0w9-*o9_u{t>{21Osp}rsDl#uDbzj76OJx>O3X(Q>sZw2> ztqYsl$i%XSXr()+KE2ZAq@rqgoNj7e#At-<)aU4Pl6G73sZGT(Ux@kT@vp1cPfN6^ z^;}Mj-KSyhMp(parJ;$+!h9S!X{=+*D4i-zgxq5 zReHBF-utt4Y3=T&W991mUYu|8+s)eQ-#u5D^*eRjo-oqc@>NK@XTF`J``UJD7J9oazyEUn%XduXTExVF3Yjmq3b{A9Inqe(vQ+jFP%u`GK#Tid>Gs(!P{j-OH(!{qHs`cWm8}8hCQ+;E;rs5~L(%i#t*SPcDuY zuf*c2_-g*{C9)RIOpa(=_z0LQ|>~QNnHwmno0mUwz=J>e|~l3cUgJ1l5zcKORMLugQPJA zy#6*!D|6$ZiLKOc@3xiz)oBY+gUi*JeU@RvcfnfL56oZ{t{G9CaM2Rd>1HJP?`Jig z^8hvS-zllqpghgDBX#mv5|PGx%}deR6V)-yxkRv1y6&tODxGf3CP=dDUm5|2v97-? zgQ%vL$|zs`;r&{1Wc#E`e133TLkJgSt00Ajfd_SOpY-7~^3AfEw8avES6k?V277Ba zI>ed&H?tEM@nHYa3t(RA?+z9&ufWQnD4pxpzG>=DM*^vSTGcXe)pPYhb}U>B_QzU| zxpJ}0VSOW2O>ypF4!}J&I^cBSlvpwxHEjnlieO>CG6la`Fn3kU24iZ+l@+U%^lYb} zU9e{QPQ|Q?V7@Vc!4|9uhi}{^`v+g=t0cjN#ci@u`oWM@q=;?_LZ>_*2o!g?hY(GatEj9^wl@Tr*lSV7ku!6#+FkW z@%UiKTA9ZQ0};I-U)+RbXR?vO_*}B zupHbGBsj!m8Ae7txMxO_MIOjD5NYNBP4PvJac?zKxZbI=D-}GAAf!#_myUFt5AF;+ zg`~@TJ|)j6PkMU>)5QqJxSg^u~CKO8cC>|X-Q&- zCESCTNdk_=$@e5VfP~8#N%Bu2!S+DBWJtn^&yYmdWf%oR;4jhv5u*F`<_zVI#jI&e47jdUOe(YEv0 z(1hwq^ajKk9iBu&944ioD;>Um-Wa;|g$wch!v!5u5%?6p&k_Q^u(fQn&XBr1@1)7U z6UqCtYMba5r1<6v!*{Nsd@oI41Z1A22@$%MCfVAQPj0`slP3R8B+R9H@|+M7)iAzK z(!`X*l)!1i=6M|NI~S>wo^| zfBfhF{{Q~(|N4*r^53vUEY$pe{_}tTm;aVpH(Q-tHzfIFKEd&mM!>@>#ny)S-#M|f zok!>M>%*z&e2O^@h@wA30|urqQky9nFef)j19tG4b+0q&sdY1?m#N_gBXnAAzVo!5 zKZAh&*hNkyg#ep1x%131X59z3<~~>_Gfh>*>Dj66nZw=^6jTrxlyXbU zeu6Nm^IMqXIV^=uZbrZj607cMFM$f1Jcpn#%-slx=iYgKO+BCS)7%Dnl8ea3uS$!Y z0kPG8yqD`9wla!paL%e2o~XGXaj>jqQDZ_)E+3}yypE!-_}(HB&A?wtm2@!uw?qXq_h}Tl!NL80C{@m2W(Z=?gc&Nv!G9GE7u+Z6$AY-7|*Q@y+U?_g@@_`C>o0 z-6vq0k`{0%-yAiDT4rOXA zH*jG^l}~gitz4Yh5$te*qYB<{3KZyT+J3myv=rzLkKS{?mTu=t-p-^2HaE1XG(|U3 zhRAjp`sbtKgra4Kn$DU1zO?>Dci|*)aoH9XB3&L{Y4vBn%!iAOw0drwV2*Hw*NvLh z!!>Bab=~D5Vp!#02t>4(Dr7r(fV?O`A?dDATrh)E%ofZwm zWD{D0>87l^M$*fTpk+Cy9V~}nC{NeY@CBOm)pUgTmo6sp%uTCk$NTNGlXLJy|J#Ew z$JV=@uuqSNgWiUme8VeW9FNaKLylPX3#vMnI#xcR!mBH%f^8+4=PQrSLcH+(oA%q+ z*G-~ru2HywvSFXc?}M56#}8Jn)?>wN8qRwBf`92nt)47`Xa9O-B?5XsY0n;uc-5ti zv(PS{g6j{hkzi6?wqtS9Hpf?Nhgs`Q!k;+eDumk}RIXBSJH1`yy6;`5$Mof6b8X?6 zGz~fELdnWWHHj}y<9xk!i(B(Ti!*FH3GQ0$vO}Wv1-QEqLN^R(tJy#JDyD_qwdvWT zdurSB;kg}C^9Ss5;gmSUNnS+{JtR(8)%U-@c0D&nkwI$=JflE8jb$h+hk{0>8dxW9 znP-@FCno0W;nNQ^D0iFc#EEtMdb+!rC5Jp#d!~8zMdqja5bmDkypFvWLl1l*1Or>} z;lWPfQwCyqEZB}`$U~v*;ygP@;*cuOH%UKolW+`QwH3#V^~5>&;AcULqZKY(4j)QK z1^d{r)j2_$M_=VCF5jFZ@#9z|C|fq)FpN|XG$X^^N`UT}7gxM(zWxykA^oCZl^1sy z{k>Z6oL6?%?bgfxELzKce;-HC8oH1(l_Ru<;izeyEaz;w`uxV-UFL=AYKqgDjGSW~H@E03@D!G@)*?JpYs7f0%+)f|6xt?e(@+y79YPoZDAdH07TQ`0$Gh{@G-jbZ)c zidImHv>#iPk6WgH=({ZvhPS`H{rTd`aNbWP=P6g@KvK@Qh#;%bqMGRRVskYsT?k}( zh(>N97I^cUrhW9eW+rUjv@WM1y!rL17H)Dw9;UjYLHSO^@td(r8%Xu%(&+F@E=Kbf z%BRtbawvZ&mYkbeGQ%p$2MyrAm|8S%Q&zrNS0A(=eNi~}!E*Vys92IKzw8B~^Y>d3 zaz6){ld2g|TmsC%1;Vde#Fel8ux0qu#HUHrA{2~gqn9OtLYX;GSi0cU$^2s64OjCJ zry*d)-JW79#$C}}2vrz@!O#n916S|{?~`va1B1qG7JkSddk;XdOX1NE=6hLh;-3eB zqBjba-e4Clb18}M_(e&KblJ}_b}UQlJh=ft7ocAgxky??oyCZsij zPt6`AT}a(o&ps!VE#aM+caRp9U37#ha+TKTN zOG32w1iC0iL+)r@r9RV4H=mf!@16({94X^enw3e3Isa5Qu3;zJln7wOv&l_fn?%EOHAq< z2pf`h#=0vR2(&qZ5Yfu5dMFE$ceb>E0xd}Yo}HG|zcAZ_#!LzoP%fu$%7H{rF028k zK2Vb6z%gbx%Z#6VFGdLl$`6f0KiIak86u^mA&^76*Pz&bXAB@ln>XqHK6{Az9<~ml z{6*Qz?=N|)Ld)P?S)8lLm&eH*DHQ*oZ;p@xFy#;;7%_NIE+{!=5CwBCd)S8hqEF^A z6+nZ8HI&h-k|0sQOjMG|jR{$d@AoSPtv-jqa{8_nxiM-ff{Q`JjrYWfZPWZqoauomZL4%~op zS@L<%(pJHI9S+$CCK(D`o~7{=O_699mCot5sqd`-BwAgSK#@(rQRg9u%lqCn$fvwM zdQp;?bk$yDS%V3m(WN6dR;2`+6^Co9x?AcIC0mm)E@?#MF7}OuLbi?;4yvXIQ<*@dQfQUgRiAx8^2eZveThs&F7% z0wC*))^L<$obm;bo+CDS7 zCQI=THC{&E-fz2!TV=ys#AtspUR>mhoP)F%x!q#c)`*gL%Ux$uUfo5MI%(HI&OPTh zVktDaVi8h!@x$#>qU0OM--z;PaM>OjiC&YFt-s5@rRp~e;+3W8d(LSd;ym4Jh&C8R zW}q;AmZ=taNxwDz(Rj__)L)(auRXFez3M#?zi>A z#zCk`OQyL-Rt3C?@kG>|J2aR^bQ3L!8LnEg50u($zqU=k0g}ScUq&<{G4@#2DJ4bc zX0LE1OK3>(+5_QFxiBo=s}#2~iC`56@q#BmMQF|8(L^NqE#1gSfQzlahLl>Z_2^;>-8G0@;yw%M*EDVH}hJL%Kqr6`)Sb+`-{ z(^n6kjWb-@1cH|zn!-Y977Y~dTgrdfuY+UzHzi?WGtN(@?$YpY>v$+FurmuT#D7jUj2-5?Mfy(mY_ zb&o++CkFEk>x7y<944l5siRY$(n5(4`jEAQsY8v2QL{B?hwO8_UEDlC37)DC7^sf* zu<`8prXRYMbFAj>Y~aPlw$`$9=Whd%LBAytrEhWy`Y9#C}wi zbJaEgq|XB#St=)f)CWK3*m1X*4P*zLTA?7_^*SvXJh7lEVd%z%gQBJ^qEPXGiTuVbPuI*(1>xp!EcFWk?;X6sR-+=ORI!{Z#yt*k) zL*!m%1qB<>wl;ypN%{0;mR;Vedr)(>I?rpHDH{->nm!%VlF;2?hJ_QstCC!c^qDJ? z<7nDCJlpQ8%N@;tLVJ>O*stKb`HChIF{{!vPt8#Ri9bEcO_Kx^Xo%^5yQB0kLXzEu z@^b2Oq$O=9rWrj2Hvihg@HdSqEZfWLaJOy(`MI)uj-oC5gQM6mQ8Uybtp$){{nPEb z2_==8^J96S)WY4;r0AZ&s7Ksp9pzu1CHB&gfG3io=X&I4Bu+_GQ61ar@|Ao&-Ky?D zZt>XH5iX-XhuAqqI4o`aW^*3PFZ<(YJlVbIHlf4VsyU}VQxZD`X>eqW*V5Y4idelU zD6P$LD(=xjNxC5fC&x%RD?%ew-l;hMU3XrwwxIH{(I4(WPO2!+UX{ejjxK1qo3KT; zVpi9Va>6?X3Cc9}&5!b7aF$w_dQq)fX1=)qQG$==CO!KF@-5aG?N<&Y`L0D-NLz)k zTepIxd5oA)TJI@F{nFlZ9L#;MJVcuW9rHvI<1#<%Zb{u%cZmR}APYxatopr&U)NJ_ zD@>z7yShWYg)}&Yc}~mG<+=$aq5k=)d`kKly`tmPp38Q_CgSJxT}igpgu7|&-7`n? zba4gfIY9@;ur~#qkwi)6<|0b_gR$iB5(p`~fLUL)JmxpSq#Lj<2TwtM9 zDa11$)J{@ZNIeuyD8}jf5Fbug*%A<>xA7()nts29IZK&+Lrs;X3z!P68n8d5(ub~z zrdOC5q%Jc%J|jYnpNiCP-J8;x+205D=bU_3kr_Kh3#v35LB!DPRnab`M5;O?7TAs` zmY5K8o;u?<3iY@M8Fn=5O$|?^)M+%Ja939$FKs#sl4zRvq7IRJM|8DF;lc4mhVoT8 zqwAFy*^oL*K`1$38Wl?tm(FY0$IhQ6Ea^Mv)t##%tErjGt11)wB{5d(zxAK%P)2iu$ z2Ca6>9-;7pfmsh~epDMyq3KN^m%+#hNLIOJgx%^`Vix5Om8J#zU!vu*d}+e2^r!`k zgA8+&#u5#`QbD^FA$Y#uTHzwb&j}uK4-3IVeyQqyX{|;}usE%lSp#@r`_JCR(+Pa9 zI>Kkd4_}UcP`k1!>3Kiw8!;5~0SIe+F|3b1dj4<2_>GdM^ON7vzFy8G%`Sf^zhAmt=*b3(~mtw?$D`5j*{y^>)ed-O-YzED=(}7PfR*HRccKsGJXi> zMhuHh1A%oNAo=3G(q&v(V-EaKd_^>e!4b$(RUGpg^euH}pM=67FI%|xQUtq|#K_G9 zDU9DgFd&%7g~5p2<6i7FX%%c~-Zt*ui()zp2aUMM;!QN=T8@ogJJ|({j;qU7+kv zb9qmDT49YXJ$nO63Kdc)IhbavVy$4u9%T&8nWBvB64$!JiDg`Xxpt%Vh!$ydKedv~zzUGH`& z2@eZ-4v)!0jm?AlV8R*7f*x+0FeQB9hoO^Oh0gel4)*vdA7UK5Hq8bnU|BDT36h7Y zC5NlarZg`5G9P?FN;0Y5}C|5z9(dZovSiR=e=)l)Q16t-B`-c0}Sn14Tqlrnw z24ra#1D3`X`VHx6p-YlBS5uOwezR#D|Ca57jR*GbZt3fvrGh_rQI3e3VYYxs?5@Tj zAGEMge~xJ_n^gl~*=icGh!bF>(=ot*UBHO%Qr|;7ulU~#UcjJZirOy%7vrvIj+Zeq zE^iSWcqaZR77LbEk0VTZCH#28@i{X7*fjgu@PQ{d)#St+qG#33oEus7>`f_<4B=YU zwj9Aa{XumTkOiiM88<QzKh%g8NLJ`-c1u zN@}dyv?9W>tCxUV4Afk=)s-8@?%dB57E>PDg)e zq61m%gK%L7M1O<}FSs`|zjzBpMq8Bx$YkXNz)-$BnlQ+wq(Y*#RgBKCdEcT}o=3Rs z^fsaMy}FG05IXSKiF|KQmpXJ7lGR?+noWCUNUKu5_emMiZY3$X%n{5n>gcuVj?ryP z^L)Tqq*S|8-((-Qkn#-}e^(c~v>3h2r~OzI^E_69716?CRxP;%$M8tktxO_%O^$}R zInRn4;yNWp>U_crTEmMQl!$i8f4HT0ZotRQ0N16BClx^rTiGCj#JJJY4hlMQ;Vc>- zc+EpR`X;T&SfH!+jTYXXI4&$O&uWxEONgWD=Mir}Y~m-{sU(v!V*Mf!ZBLyvkS%UY z>y45*M0-)YSEM-X?0Ss*MHDxH#Lk$5)JZ+Uk96?^(<;$=6qMdJ6-03EIx-*lLWEV-)dfkaao)4)B{yI~TX_!JH_U9=s?=MJ9VM zlt!)dD73k>IDIur0#{z`V3t}n>LI$)1LOMWO-Y!HFuzF2?VPnR-%NSLk~N?}12Pg{ z?D*dyCAo(T#!C{>2s!3R8;GuK<+n`3CoJC;xD+~$FG`YeSzBJY)&AnO#jUy3*Z3&? z&ocy++nR$-N50Oi)G=JO0tC{p&5QtVylzo%tk)seUFqoToFf)ZnE_Q@R2-0aM6_p5JZHpx~Ts^Ih-1nerwEKERkI@5hglu(YX+UuQw<2EIEbb0-o=h3#*3q#8!peu1( zmRCW*w&qTAmWy%YN@S@nEXMBZl9U+VRh7uvoL9Fw>y%qzTgocIQzyM|2I`E0zRc*O zc*Nv*VTi5XifiR|fUlAe=2~b9N5Xh*EnR_F5YD8Guf{FizP|of*Y_2TAG{~WrRue~ zXw`^>Z2+T2HQJPUNoq_<*d92leC^n}lc{aG$D+}s*z54T!&<~iEAqL;Y@^@ES%-}A z;SyGgA_Wr6gYFfPZN zdqy1=Cl+%U8Pl+dnm`8D!^m}#+*?5<9i?@;YdYSn0uojurNn)mT-?e1RoSLT%3YTC z_qGy7dC4T^9S$A=?fxB8GSJXgtgQDAgwvIJ&ZDCjELTAIffR$ z3{VlmxyJCE>O`u7i^fZ>)}RKnXo1M!s+{WGh)n}_Teb7)(8rV`qVC(9WAuFLod{b* ztI^(-DO+;s#f>TuNBx>as2i=Ol?;xG-uj@W)~Fa6Vsq8#&9rS+uQv;C3uACK+X7-s zMDITB_*&0r3))Xb&B;D_t8h<%zkU=`H-I_YbgKq(>!n6NX`Irbz3r5%3O(9zUgT1o zmQ~8laj9pdy-KF-P$Y^}4&qcNI(KkOeT+MGkF24hXjMn;*z~0Kpz-h29=(<}&U46F;`|N zPX%jg!wSyeT}gV92AW$rEysG-Vkbh9n%V@<7G&=PXY^)nA|`ItMU47`UG!zEefGjq z1>Q!?kXTjDwKTr(Te3IkaZ3*3m}kZUm41&l48y?(b%{~U$zFVm45oHH`V zr5}DYI>azK{#|4?Y^xYfQSDPXu=W~n5#L3{S90KGT}}uow6-Ln6D+m8rB5^qbtJcP zx)FzWA#JJ=V1Kcd?OYvHK>DD}mS7C@cGVkR441b!g6M z8Lu(-X(_=Osu-PNzVDS!p6p?cQN<=9UeAJWr==_Y5i>dKQ%!6q999vI){Gu;hL47{ z+{CKOu}+SRqs3;+aEr6KFHfMfH@WRnU)@bGmkDtXGZHYJ2r1($B4JTU=~F^`i>jM9 za#tjPV8_+qxVAJtc}@-?Ij%5kYpR}gfZjtyE=gL5RYydx8kxc=G_DYUNn97Se`m36 z1!7La?s_-khMdfy7$IZEc@t-Awsj`i(K0@jsy;-!x1Kvo>8`vuC9s!0N8?ntip^dN z*BkAAa~9i3@xCkF{%tdNq8BB}cs=rH7zb{GRW&fI+GLCHvAxBaYe#2&8^7H8!vbDN z;!DLHxi5-hWJ(Q5N7;RUMXG;NYQ$VG0(_hwW^|aeIUV1i9T|pKnqYDBAwTz8|KLSQ zjLXQQJg%eE|LWqvaXyAaAl;F1EbE@cZ}2TA|_MYqw`c5US33L}F@nK(+C zn*mbX0J(dg3`PAEiPZ+L3jMn<%0rkY;pp6^|W7+8oVgStsl!91Rb}YEsobP1BOfIRDZ?{hvk{{ zgK>Ts#!>in*e*M&uft?g;hdI-4ImP@sXcXZ!`z-J!`jN-n;61dP$K3(n2pSQ56qzZ zL=R&y7gj(e=4^E-V%m!w&uT=QJ|(r>@xFccbz&~#tMy=JR=1|6lRwNVDKOp1qzB19 zjf8dbXkIVPDf`+A$76BBT;C0wK!YcU8SmFUC>ap9K)E`bTHSD> z)+h(&*CWGj-30P26<+pYmZ-i-8Ydiet-%`OAZ5e7x(Va^s>`ZlSAyur1r-QK3kf`& zT|l|a1&~f*;%Vs-?_laKiJL%vuG;0CzVyx)Q{`-J&SbfQ@Y+t@gzzh;M7-<8ee?yQ z^9r{%_rSug0j+qeys5q?(1RD{Y*>!eLW6jr<2|o^Uh1&8<$;VhYw%LiGx&Eji zwerSUqKmfB(L>zkItANb!vw8oNnEnD7I3UPNBky;%a)cZbBs8xFG7#8g*~w3nh=H@ zr70aRZ`Dl@mv`$O5{H#_Zpe1)j}tgsr(fghdVm8c z`>htt8ZT}MayZrYo`LIc0=c}wT(&_?66iL8KXkt_FW`V!c zo=(RUeFIw!UG%D)CC8}x1<$rO1jM&FlQyL`W4zpwtl%+}>6a48_F|HgHxWMn^Tp*z z^j&M1{#{`@vW-_!8vle>&!%BcUiG(dk||r5tgW>}0cFIt@!}$0s|HWJV=>nTdN;|m z%Y6FdfSD%3IZk`k$(Du3^L3zHfi|b-Q({Q6_8ypLZ%Wd0=}sO(XhP0G3QbkYd{bKFAGwdXnZ^+V7T6R<$W}_mFkX(4+Jk2o=8c>j=ArVeAO4`-6u0A z<>*qCOK|3cyAx@t|NLz6eCd8~{C{BZV{srZBgS~3=81MN&28s-ZW^*0fp5&6ckM?K z5HXiI3sNk5*r!Z%qhk1tgy1g;WQ*_yOFAb}1j$kNMKqf7IY)EI|3Cj?92rGoKUAe~ z`?&&8T+U2w90ofVRsArElusD?#w{d|5AI)shJQ2=be9!a&mUZ-&VPM>b5%6ohDk+k z6#-HSA{Hb|$vxS>Tz91^wVynBm|MC4^oE_byAOyH8Z^06nv#*<0^rZPaUkJCMu8b5 z_=ox-+~^-p%9{tol{)|>e*krv8YW1f}gd$~~A%bxx z61Z=duh8xHt}Dv&a45u@^IU6My>Trbg6a!)C^!4UdsL7jw{+VOMz@YMNEnClOQeI^ zl9&!bw~) z$$GV>kv?oWhd@_Q{j|4A(*2L<`ylGbsk4bh;wV1-;$>WNRru|lswE}|!it=;G#b_X zCCKwlQQZdo_#rL;s6RhcokNP-hD?%?Raz+0Z`-G%1l^YGzIUz-%NL5E$&Y*QYQW0J*lF^KPPJ zMB`ZPEiVet*qO7#jo9c)I}P8c9fO0err?r+ z^+Zs(fI1HdsWJ!TH0mJSxEJ=JQ_i6={+|gqCcnX$7&aW5U7w0$0mBujA{ZAIe19V; z5F=d8Akml;ZP+ghG)S;Uom$pS_j^)LUI^67HeIl8W(0fBVP{3>_CX}9VQAGP!3hMu ze$oTSKi*~QPK%Jq`Bp@jh#Wag05m*WQ!J-x?~IX=5s7a9GzrJAF#@>E@)OhD8QFYJ z2LKrljO_1XV$eQ={iIe_ER0XP*%Pajl_3k!KUhfVv18~j#eQe^IJTqW;f`ytfz0%Ip~F~=71rvRZMH%FLXt4a0l-< zl3W+kzyk~lWC|z_E`}4AZ>Qy;RyXHDN3V;hzCXFQk)}3-U9B`EK8G+3FiC3@ObVsm@z_4?%rVxm{o>YmW7?K+X z#M5JhB(yUWn6{{6eH{)*){7NiMMiomqE$f4^qO62Kk&c}aQDFsXwr~FNKtHs=Na6tnLC2RkpvB2V zC-M#zHlYX1lPARS2eFEt!@c1rD;7~Qt7wZO*;Qy9`%gF)8y{!NE|sa`UabW9=}-+e zvnx%+*BDL&qUe*tuQ#+WBZC5SfiE-vFgt!Jtp9-&#ExJmNX8*xF>Ehwb&Q=A5%~_6 z>2UT4cUj=^0QD_JU}g$R%5)fE7&_KCx#gz_4!D7ON?t+mBW?H+s9P0fD=c#$0t=kO z()nBFnoGsXoj?)OddHMp9S*q`@Fo9~c0p(NVxV)c4n`ub2X}yKOCnIirlkB6VqB}U z^>{R(@Xzt*i6|)~UQ8g21g7C@M6gu+98$j}5u$NRl8BZ!TDAd9{WaL^i}2;2GNKyw ztZ*3)3ziPqkSU^ZKSCNQki*S3+kaEkFb*G-~^A~NpL^Lux>%%J-B9EI*BP1Y+);JKk|Z>g`+m z^JZV=kP%o|Fknlq5Ls~8|6f3+OwwEgVgnsCBbI_KgS03#Gd_G^m=Y(~_#13kvvI|y z>I}z=LK8Ri!l@!YD?18lLTKG2MzAvkWYFsPk`|dOiIWt?Fl$z#{ToZZp05FyUlo3u z{Jj}2EII5xOb;xoQ^OBjm{O#DNaK-*OPhXQSYiuKRE%xMMM4G(8`E2!h9%92DJxAw zz*gZdvnga7;)xPp!Nl`v5R68KDloc$+G@*4MP||)J_wOfc1N+2bYL10yb9yW|KB0; zXRyqfYerQ1b4$(ikQB#5*tPoPLX^n+b zu(Hsd&mj_Fl<~JP%1ija$7ID4fF>5JJ~c~c9H@|(%9c}&uiTa$OU@V6BMw9OQ^$;8 zG^q&a!w-S?tPUnSz6vifWbdGok_{hg!K`n!@&TV#mf@}w1SGI0wr?HsJe}E5iNeB< zZ!13t&7ox$l(IR6inSgrM-ZA)5rTs9zidw;N)6BFr1;0zDnQmU9hNU% z^`V_g)lh&+aXUOKN(^KukpymWp~F-Wv1z#C!UxERv0*bG??@jfk$O%nkIbyp-F`EE zi!Hz(GI6m5sP#GvFhGTf!1mgoM@OY`k&9W_wQ?b=Fekf-q+>G}_+r79kX}UnsEGTJ z3xb?;vDz=9C~VFLwPdiW-CPnLE{SwPONuMOCRS~h<3%!^3yM7&HH9re;PeyCs>I;A zouerZq;iM^A)6aM+#ECX915${Qv~$Fvr+=`3nd5V=hYO^$pxlHWCX@UM6AIY*hPll zk~5Kk-s-j_Nha!5<_C+REe8W$!!%Y-9++IkrfJ@YOv9ceF{zbsnh|ab5r$gOfJ*0x zu*UGz@za%uJ{RnRvP&XbrtW=cjA)f2J(xFUvxfS2&^0@e0$mpp2_uZO3K|}BIUO9s zMp#vgv}cLME)i+nenmSXr9ea_4R$HTaG}gYM@uZIppM{sT9#8Sv9OYS*kxE#z<5{- z-I^+ z-KPxZ98yar5uh{NLQLm|->@eErg2YlWKs-&j;T3J*mHcJYAdRd2t{I_lQE`R1&e_? z0TMOl{$RqNxle;rNNP@n>y%=WrGc&Oomhq(S!z#6cUxgl64E-2-C`mVhGl~-_CwVT zu8vTl>5(!BLTW!WAw$72!pb;X3MX=Pr{(?j1BFGTgbnqW42ER5fHW=^FELykV)`-r-cmrTnE0GwHzp%n6_ofJEpu3s>%o#P{2p7 zkeGq(_CPSg7mNp$yH2qTEZUfSRIV!wPem|xE;i~3x$r!o9>fx3Q1+N57cI6a*Mle? zZXU%Fgygnffq+~ZF^bych@iD#Eay|{+(AhVz$7?kz(#t#sUQ^QM!fI}vZ!fbDi5Cv z4bO*o^&AD2&xy;l-PARI!$V}@Ir*Rw8(AnxcOtSVYED~%p;V<8cz*vjg%3EzDjZQB zp0JtTfNrL%;9aj(vNi45!`Q2?0wjrooUf`+T8g|ls8exPxD2*t>&N=kYQl&L}udX`G8 zAo5z0N=-43%J|b}I=<*?yulHIv3`BbP#oTG zX%Vbd(!~f0qI6hkM+T78wS7pb9OZxNUsSC*eJckWZf~MqkUCWE3Sj;chp^0!8(vlB z4Y+q%2S$o~(jE&5kDE}*r_yefy3;O7laVY0TgI?Bf%o4um%Zp@d&K|t>^;F(pCBet z%*DC0LX174)-PS2{s}ETiWSE2HFrQHT(Wd4sbxG)p}MRHIFOUVz<|KpomMd!$;A_( zARDD}Zr5z4CK#M%a_H36kR77neZmiFzff0~e0!uuR&x^|#?zaNn&V7rr?C&%6m`Ip z@1y2+awJd5sP`x%iDu!1tC9_~cY+bCtlzB6c@)M~d77u=xVVtX^x-K;^1(E zSQrz8t*AqFC4D=~}ejk30ejJ-6Ofb@d+Gn*L%BmwfwksQ``N=JX@ z_+Q@M@nUI4$WBB(vVjMpx=6t}$c~a;(sBFNDavSZEh#UVO~%CjO^i}VGb|C@g-!0y zGZ zBFOxFf}HVw{Z*72#5FJNdcwK16?>uV+EmTEJnUf#1n4uLp>!5;x-^-@$8t8Qqh&Ai zCZy~|%)zlDW&g_=M*laTz_@P8_2;seDHD)hBAW$T#E*gOeE%89enZkiR`B)@Fsl~?NaH+6hPll_c9iT4&`|IMqQ$K23epQ-y6q<*qwUH$ zm#Q3|gUnM>82$FQ)o?fnPL42wDMom+Pb@w};!dOph z3g^8_iqRID!x7NSH*1^NfHqOB{4y{4}+!B1tUyBq81`?5E(f^ zSm}){8+A*R_np`|A^;Uv9~Af#eo`}KTe*Z)$hZamLmE;O>PQGq&LV|&oF!Fty_5VQ z0h6aB>AeI-jaZ}Rj5#UTx>T#FFy@4ks*;45YP}*sPW`Q;Bzr|BA2MP#Q%ph}ZUU1o z6uwEH3He;mrt7pIMe_aUI4Q$YPpo8*3Q;S^+MB4=V#{D9 zg7TVbG)op(g`Td^X3sb>d18`UyGTr18#QrkEPY}eN*hvj3X;M{hB1-v&|Z-DKWJIr zL$#hAG7YFAT{|Hqdqg22e9HtEO_$AMB)gHpNcQFrm8P0ZOM}r_07SsyQCv8UtYGwD zD|rkfi)9a};h{iH4gM313`#>55bmd8QU(5b`O0|8tCFWI&VjV%?ch|}SKZh%lzfNQi zWvr@oJ)@?V7-$ZEFum|WZO(wIp0o-w%AM0^6QzAs{s@v+CP0}1^(w$yuTGgTrQ%d) z8bKq)lrvx{!?-Gggwq)Y8aOz?={0(ncy^`%!;zud}S5Xh60Lfea?RxrJlR|-VW z_|_X|6jvO4Ya7;@c~p6A7wrwEdO4r1#fTx4hl%FS!2G1%-YU2mQ-diqF@eauJZP$- zypn<=1_OAMm{3-|PfY^$G&RNsX8>s@g+W?e1;(gk=0DS6mdB{dscA6lkU>VuYZz_8 z^!BuCYit91Qwx$l`?K7$y~^#E=FH@A((EwDDGRCAyijUJbBJbeFzQ;@dBjKaga$Q2 zfRWcRMNG_K$4Yl`P5?2f|G9U}Js>Gp~(VzCM zr6exPqO!i;$2bS-Jx_C_8j2E4q@R!m19~)Qm!#=uLQy;$4movH`ZmT%+Eid%#mZFZ zNIH1N=RkcGa5FpI5Gk)n6CMTbXetWUXE-A_HpjZ`&t+j`%e#hC;N9Z306;^~i#YWr zzhR|pItlY@H5{cQr}K>!%n8Y<4?V9j4jDn&z;t|zcsbLdwqq`okS}tgV_;Rf-of;O zhyc+!PA@zN0C}8V5S_{)+c6hQFjF~4O%%&zDWpH>G)oDy>f^yA(uWYRR|X9=onEns zXe@>FCLc*CA<-mGS`0H9)L9A^G(U&ww7XpoRAA}}Zzm|eJwZ7H@sk+Ua+9zUywzvT z!zYyVmYQp2@1hZwrZ|V_jK?h-lLJZr^}-Z#{uo&SY+EKP;4P!-&N@nL#cF=WT_Np3 z<2^=E6+fb+n$;Pphh%5ZIc z-^>M+SS1V+)NC-QgX^)C`^PBBO_6aSb4J%Y|4f^;n#wk3ScmdtZ6QjQPA4h_&$PYk zrj$d%+M(1SYU2jt@|smpMD^bSx$?z4$arl}fTX2B<}`T&q9mN)2}trx+$X@~ez+X> zFK^5eYh8#Q50ab>fhR^KXd?BgOQtgR8R36L-;2D<_?Ka4R<51rspF4OQ&gACTz zfYeM4O#xxn2;9848J)1J?o;4$AR>g!7Ehf;>plw#>yKPsuzjq~ol#5@VoW z+mj$QfeD39HVirYMEFuO2Qrc;rA0>B-=Yk+D<P<-uNj7Y9VLP* zp+)G1XE+8HB^Qg)pnAfvQWMBrCMv(tKuVh_!JEz=z(T-{mLEb3YMC&M`PA>0UPLgS znaS4o%xLECbQD@`$(cjRm=;F!Q|UoqmRbocU#%jx(Z{7#Zp8q&4)GlkK;B=$JPzhF z7+13&oZwMe9CJfZ;|L$!LUfLiIF!=am~eK-girOI>{U$0moYA@Mm$Dh7oq@V1Pm6X zwB=ch@m_@(sfkem2O5M5j^8KrhvG?7C&WP{U`(4fFs0a(m^)W zmyF1WDayPFCI4VaWUu$G@VxM&slrojWtr1_rWkdT8)M1HtZ5KTUTNrpyaYs?Jsb4T z8KT<32KSxm#c^d-+Wbi%BAW~)R(8rzC7g%Z|3G8lTcM55<*9Ns5RnO? zbO$p9-O(`KsEFS+Z}ByNDfjr10LV;T)Pkli@Gm|BKrjcHrPP3i(y8#}RGJ3+loK`h z0~w8Yvb0c|;@dO%l+%OL#z-DVLc4Z^l0nr5Q~okj7|^xbsU$*F()<)Mf2Apspo185 znxQP53wUo*BOxd6p^-e8vWS$f>*;!;2AUQp5ZmrzMUUL zFcL^(9uZYN+;G$}YPeO=K_uEEGLled!Ut(dm>~%f({D~ir!H`zJ{Tyc45G$}+x>|r z!ZcV~6{eKkQ*S}Ni^2QxSs#2LB$}Ygi*wrMCPNfZ1iLXJFJ3WWk9mQ~IS%l0m zMCmia23d-6YIm2O=zLxcd*aRzY-d(OK5DFsZRQ9Ox3wY*38$`iKX$meVtEUkeUZ&h>@Au(1B_MgQ@ z-t*FieEfonPeYs;)lo{TOtg0g-iCk`k zV^lXPL$lfJexx&<0fR7ynXyxZKaeU;psG}WSU#N% zTw8+@XN+7Umbj{sa05?Lj^=mLctu1^bp>1^obC^ic3zxFPf6CTOBAr+G(rha;GB|N zZrd&GS%{opQkGm{q=4!Zf)!&wLr11-%e*GCgh#B}>vN2%59P8L{B_Kk(g4|jJlU*B zd{H_4D#+C+aZgC>Qw~3gF}r7Y7TTC&JlU)WBkhxPTjF}D%!^{dw6V(Fa4E4v^c|+r zFn0=hA?AdR)G$!z0M#KqgFU@$jrZy=K};C|+=g)(;#_^idMLy=?p4mMBCNfTInD?; z!5A)WjxnJkUp|kp(N#mhlKQHpQQt3xHiVvJNlv(x3;Kxsm#ZM#(V6?3><(>(IIJ^v zratV>R$`Nc{>bR%Wh=?Pt4Fddj?x%SsYQ-6gus*pTPs7~MwSCR3z)?Z#!$o8T)W@zJ85F284BZghsuLz~C?;`Nf?pN+$ zGK_U`Fb^FvU0moZPf_9{>)Q7#EKB`P&-_W0*K4e%v@ng1lG&%p z6={OoH50GcH4GafAH_U`X2kn!uUe)*FzWhFrD)MfL_hKvmqS20u|s(aE*;r4UEo8m zWrC6QsK!A-bu2*Xw}y_81<9+@FjDPs^T?{@mUft(Q7PSCC3$sOk~7dTT3aYtDVNu! zK)TwDqMVv~EOdnbu=ELlj;?=;&B6QbkT&neZ7I%)G6mtN!K~65-iZ6U~EZH;KfiNuPas1Dgg&|_8tfoKILJ{`pgm`zV` zD>v25L3Z5A)g%_L;4fls|4!JJ5`x$YQmWy}2~xs`m) z9Ar<)SYAYwB<V9%4xj1TpQkkGegPcg7R)y?CvlfSP z&9J*oXO*2Vp`>$SPRovAxnD^Q!$eysEz+cwbL*T?3}*=!imdckEiN;4OM3`8Dn=i0 zE;*H(YE^~R(eJrq{KQt(HIt;b8CRIU$wviX3q9#=x|6j<>>8}CWmi>_YtAQL3R))6 zAUj4cpW*0ZFB2FsJLe0aygXoezhUgcT&9vHDyyHL5rQBurs#`CR@FUkYb~1j}9~9P`DvVL6pajA6mF zodAj#7oJV1xx$G!!EPWyhb6a-MvHM0bcf)SOQ~4vkr%WCL~}Y59gZTzH&JdK`{}Gt zs~894@>(gR(x;0+aaft_N)Xpo_MKLX*TMqjZKvxwZOh<0|3v}Phb)>dB6+ZJAF|E#c=l&Ch3jNThPKbo? z&Wv?oAX<@`MTEWvZ@y##r+p!BD^TM`0u|x%VwzHfXwgREMs#|0nFIpKG}bZvLp2k8 zZ6Br)lk{bz%9v+NzLV9R0i`dA(gAfEqCYy4lB-jT1g&+FzkB9B#yM_TQs`nV&T)1D zS}01pxu^g;vO@XhI=w^9R>55T?j;t!250j`UQD(h-tFnMj z4$64Wrbuq~EfE}ianvY+=TA@1vmJ{m`YKKm+H-=!*G*F%dht3=#D`t{L#Z$|qqXFx zh;J40DdbD`=;%NttN0ze(t^1%+GNi*1~Lc;rUb*9w~NJfTOI3@-6cI z+>%6jgeuD4h?>lRj$4*Gpy0fmCMtZ(=?pB>zm4-%BUg2i3xVr<^iFK~@Jy|&zl^|r z^?2e?%-NRH+h&UHie-lRg`O+KLF8aw3fEGGk&Bj4D9LbE>}ebFPo2OvnKdRQ6Efty zVZBfYG~9}V(WpcPd0d6ni8PwDInhl@qoU?D#|MKb--Q6uRmh|xCQ(yLjtQC&+QQV? z=Y7XWvG=J{q)$>+&vY<)E8%R{dXm}(;DGkKmXtzDNhQo7@^DxNls&_CO#VCwae`FS zCpEQ@9&Nn94(Q3IodDGYgts3&ZCO@nQyxihxoOXKR=GGTCt19T&Z+XAGB4#cs64t} zh?+4qtpj?pXMYRmWxZlRO{vT6C1XOr+We3%aK>8}<7D8TG%XW*ePw0e9`?}2xbf=36KVxLOc>^- z0#eldm~(caRB7Zl zEyuc)oGnawv36rDT;N?2DTO*35i*fQCyF%Qv{!kT!9uHu*bzS|%*(|lQZZ@;;(YBF zsfMdV_u-R~qM$+#G1AFg4a=pqT=51XY!p@5`(uMa^#KaQ5iPR&Udss=Ckwc|<c>P&Vjp*mi&eyQ6!wjFb8I@65#ubrsP0%)aGUwha6$TjVyvVjZVDzr z{BChAIZ4$pS5K33@Gmi7XE52W4`PknkFM{g+ildnpA)zzi)-2Ts8WOEOccZFk(T`K zqVfv(K}dpBWFJ&8Jt5}HD8F;2yoT9O3_;Hql+g6CZE+z=D;uKFnIVmYB9!cEiJ3q- zZddYTa>`O72-Afk9yMw(ZGcA0LIFT-?I_ALl^8uT6lH?I)GHD96=Ke*l$*s2mtjmk)<3CG%gF`SI_FRM7yeDN2qoL(DWClgFNrvRcTT znw=SRvbyMCVipXmYfmPW!Fpg2C8VZ=VTMzk${IKVBVkD7U2O5p9A=j*Bg{uVB`1z- z0ku-0{l2$aV9QZY1@-wV(>Hqogu8)z!fiPkGK-SM16YlZ&St+#-AvSE=7;!*|vu>3Ym;1V9q$sh(ZF9dDxU9Vy8N;6no!?d)5(>zLR zCNWA796`efCPpK!A0>90)w$h$k;IArJ13_E}Bc`)IB+s zwn$6Pr*gvTQA)EdXL@lwJFRjF=pl$m!*t7Q&L^8dtvGdkR9#X3{eBjrF20z0luCnDgzhVL7!z6W2oAK735*>{PWlkMl{1 z8ZBIE97pNdy^Sr~W^j%>mc$9e&&m0QJZ_`#DM9oUP_}G$?g$qZdHXWkW}6%cI>JJB zeE_kcs@z+89>-Iyx|Am>lE5UsE|*PN7h|08QmBljQ;F2=g!f9Ik8g9L^FdpD ztHt^32|7W#lYu!$MX|K2Q-S#a+y1#;YhR!?)l=-^us_@t+9qXQ&f?^l?4ZI zm2i0POnF-$CMh;Ga-N`0RiXz}0_z)AO^;N`CKnGDi>*DRic7;4MDA40JM**Ij#q&$ z=UjC%H(p#lR~QA`B?F3N63C-An9}QV?YcwBkY|imDswRyVB#s~4*Qi8MHK2UOh0@t zCyL1OK^h7oU^}(&R%(Wx8F>&gBDyf+s|%Z;Td(6BcPxif9ba>i+v7YFAgwHFZQKda zlP!x5C`{i=wIoocW-fs4^ppw4+%O5;PZI7>m7sV;&t2qVq7i#0YG89&dU9eT5QQg) zO4U1_7jg0l#gir<9udT@1!u=<^6@tVDCgdRR2a7|Y?j$9-2Pi|y48~z; z4Mu!eW@wU1p$v%qnjA_DN2zEw<^6 z#|6qdnkCPyCnvImT}~xWWM$ldl$_q2o`(rkP7` z0r`Z(rnMJQ?Ll@%5feh)1mb5rOX8O@F&qCut8)HWGEH@%Fb{jy)<)TYGL-lVSfN}7 zG7~-H+FGuScPnCA+LTD)u&LO|6rtn=tn^-nk{OWW+8U5t#ix-Hy7Ynw8dcUaQZh#b zO40>HPnbFAIRQ%t+JapnbknDDwzd=b)2*!m$(bcggw`dNMKR9YFTwPnWmlq>E}$n8 z^U_!uQl2a>0!hb(I+Imu0l$3IY;HM}1i@$?V{Rx-Dx?|yHq4ytIT0BVOjv9tdvY-Q z4NJ1@^${(i0b&Qkj^cN+88jH|o?!%1*?46qX*kj~jMauUT2d53ev5oBKHM(BBEdtf znzM_m$Dbz2|AchCKAYuqVR?Ae0uhZDA+i1DxiF?g~kvWU3f@nd}aqsL7wbZbR3~H)&~lbq5sTm%#Zg% zYOf-d-b5$=#RyVL&L|~7=pXU_ke0#fs+K(4un;HEC`-_vMs%4XN)nT3_FPF0Fu9$b zsxEvq$^wZ-9wkqs={hd1K^aTv2qcyf)*Mn5(}9DYH|l=4KV$*&w>5Y!&{B4E3B*oW z_C)x=6njLMvh;0U^sB;$%B4)42gyUtFG5GnQ(Vv0P;y(FdZ+i4Emij%d+I$@jaO5) zMHTTi%}&G+Qaj-u7>h`$dSj$Dg;cmc-0YT)4N&Wn(IR-~im&k$dW({TyAXK-x z4T{yCf;`);5G17(gi+}`!k#Bhk_SoM`J7)d->ZGj*kdN=%Fn{y#E_Xv*l}&mnLOF8 z5TrGmD@U(k3O3g+CwaKxXmKdt{Grqp(ki!qP$>$f0+jVoj*DwhYP67YVG6)vrqB76 z(bKe^aHpJ_LGr;@g$J+=mDfBHm2cTPw*?1yK{c^;SV~w zFlEpq_~@L?od69;snMcYs9~bK5Kn|+Gjdg(c}{6DPP3{CNSd8iAexGzZh}g7%EndU zN$TJkm^teX$ALelnbrjQ`HLs2(pHB}Cs{%Gfvl1E(#LuJQJln17U6-8oahiLe`xZe zMiR!G{u^viw&P`Z8Mb8 zxxs#gC@CW*Xa~bmfXeQsr$pkxFY|d$mvAX05lPw2^!so)r!a9zRO-$7Q=^b4X1ra0 z3*_aF8goeyDGc|ZmRHvu5IvoO)W8Gf{U|egN6`3_$>ne1euX$?Dt7yoXcLYRuXFdZ46mZUkA@M-&pcuPhAWnczttMUi)l~V5q zjugbMefBX(JQB*lG+dB&$NU`xbUm(|5-)w?wZ*hVQ&Qi8g-whVufPdeoEw+|Cl%wL z;iik$_}5XUlFw(0djh6r*3*1U%z<;O8O=pr$Hb)AjXBIz?omHRAS}2Hy2Q2S*jh%>D*pr zli$hTs##{nw9HPYmXE+7MPPDL@*-$i8gc{;%F;AOjRY;>eAG0?<4mk&Xf3)yij-{66-7YhQ;pf{R#(-^*`CEXWnA(bqQW>E z`P>(Eb;}tftsEj^m%%x%uEB|=Nz8+bC{*fB-^{*cAyAEvA_YdT6v-q!_Usu2=&B;7 zBk0NMT7vGqHo@W=oXT(llw<*U0=g7tqKFc2T=au)(}5C1UMdnzmL^&QvS;bG^<82n|Jt620=5VJ|#cy$d<*{fyEl>Cya66n)>3S*QZpN!W$I!iO|f9y zVb794mse07nx(8xz3ybEN+~bObR$Cy6wyox5T-iW51f;pq8Xs$o@Iev4wzg8+JtQ9 zK)K$W>KU{#W&rlY!ZE{(Mbffwl-gjAo50lgwO@yIBbZ8`LgH&m(Zh5U) zl!HoYlbo2s*%WulX;0F0S=DtguUQMWaMh1#^ty&A8KvFbZbuZJi_cU9MoNK17~=Kd z-SVcBJv&jNuj0f>pIb$*;8bElr9dPNaq147+bPgU2l{2eODwPMSqL=Pvm`lU}y~ms99C!cE`i*|fd( zVBudB5mkblr_=U`-Cm#N_2Lvd*0iFj2dYuqVdrLxl+bOdEnzOnq+2S{7WQ(NA9>+b zj@P>`Cxy{5%p1#0Un?3WfV0Yd9`uyz(_oFLC?SM7t1tN{^Ys|5D}P(18ApK$l{1>5 z!|fCB?iVG9Vot1anl8&l16R?e1fS@QVBMe|yFHTU^EqoMQiI8ihJCc?5g_Ou+^B>zigq;OKx!~EPUcN>9P(y3n(3;BA93u< z*@29UIe;jwMlT<(0ueAQ_(Ganfvg06Ykm6VkbE@mzd{lJdi*EGNNNOl(H zvY2i?H4yMmo-0zk8EP%g)p*QXQ~?Y7V>LdWBoYm)b2J^1A_3Si-;_wvR@@9HcV|f` z&KorTZ1+bg+KL`d&$3DCEUzZXQD-j1*W~g0@r z@Q8~~n6OK9T))?lI_@OL3sMV1^~uY#MExmoq+slup^+TmM%&(v>T=Qi6;$*L=;m{) ziH4j_zQj+EqeV76@krO+phIJ7-c{7j677GK`QL4%=dP<1%hm>m8#6W|D z@M{hfUCg9@2s-7HmW=jTSgtXljCp9cFDJqg$^;)v;<_LOtDK0aTapsz>|WX?r^91` z%n_>`^j;);V2y$)E2@Ux&cNCi0z2EjZ2r@|5}iQ^3kB@P`mp6p`%s&uBBq?L@wnsl zA+MR1K?aK;d1XQlAr}M@)+~=x;!Jr=BP~W?2ta;R!=I-Z4U`LDl^1PgNI#VpGUtfd z2(~UfovML7ENc-s0u(JQ_2W-8FkU>lcZL{{3{tOmUT)BUzW{cyqTg}ab${(rb6wZa z0@I2ZoI$0ws^^X)=AY)qt`68CGnl7=&4q2nYtko+KfdsvPU*yq#VsW403kALMFcGr z8$ZJ{@ZW|<<*cvp9k%7%gKEj6iP6%Il$Gkr=Ya3HLuFqNBDq6Td6pT%WK^5ebQ2o% zz#NUEPAeWLx7kAdA$7zrlwY>g**Ame3F#@y8t;cgZNMCkCr%Z1;{LL~4vjm`MCLr4 z`uK^g+*p;nEj7$5e|D&BnZr4!&KaI_;k}c`c$Mf@DEo_aqqs=(Tk?PyN-ziH>C+q@ zb?2|7cCU=;@nM2}nLF&=$w27mTnx?em;-WIOd1L)UQy`{b>Ao=r%1|)CIPE9MJjr6 zbGP_nwH%1cVr5{8tB0DtBzK0qf`vfTg6eK(f|Yr>O`<$OD)|S${3$gql4WP0IcHm) z!xku4nwXz0vfQokPZjdl-wEVO%YV(Hu?o`zxN&fI=z-NxjtSq#KMRqDQs^bi>Mr*(O)#%EayKd!mZP0K>nJOjoUPcoUa4i_T8S&Y^j zRG&YB7$wwwlbNMbR=jlN)GhW9)1WBLc=lZIA2~pYzM!R#Es-bjBX{!TG8KA@MA|yX zJuhx15TvP#S_WVZl|GS73x0FTNp!Iyk1J*dv0h}k&A1L`rOt6PB#GqAIT|P`ylZlS z2(1*!#p1@HWrIRa6kRo(P+V_7TbQ?i7DKR=SxFc!j#JSmOEfweFju*@tx}|r6SICf zhZrsQREQ~92wK6kptj7i$HZV4HT|2(`m$$HO;8^J%JGeCi z>!_f13yb!V_>ujw1f;9|?#3looO+RF*1kj^RCnQOhJ0fd@8&r&>Znp51|{qu06fM`xQ-d=^8KKkE;@uu{XvbpkjiFfl%= zH&o`N{VXCp(csak4ohliY9*>!GAC;rh>*^qfIi`(S2Y??on=WSTn#3zTsjfyPI*_B zyryd_>Mb}~`RmU{OyXR%NJM+A(2_$u>5fNN7JFa1bn+rAEn8%jjkZuJ6rL&2^0NoT zi-DBOY*z=BTIHE7f*D+fNJ@Vm8P3dJhKwd`*R#1@OGPR)lf z`)u)Oz6H-FUm`Mv?i)_CNG$~};2|N>(R?y?Zf~t7vAF99S>R@;>c*di<~yNs2Z(k25hvnQ?{Vx zu0^P|(Mj1WPLcV@vMzC1s|T$3roe19c@LE3XS2&`SjB*U@iqR^A6N}{goC%Mv0B;O z8k!YSCP8dQao#o4#{aArE0Mj%@E)sHNO7sBfQIC)_NZH|nnTa(!-r7mc~r&NIc2pB zMBz#PqZkNoopqGSgVuix1A)-NioF|JmDHI^o>^7vQqb(eFa2VvW74J*$7$3yOWjJh zR~l5KvN8*sWGHOi+`v1lOG-%h8C0nf4F_&mGE){a>uA9zrWj|{=C*P;mrSFYF_}8h z*8Qve+4zz!BF}bIa<%hiNiKZpQk}}HGYw02p#fna zeK8=qbyUR_D^Z*)7KQcUiK4}9Fc|st$LPd0zeEC=7fTY@&Hz<-@fbv$)7r$#J*CB= z*x3+7>_-2v~{1N`XXl4_W9)=^x@`(tHjDfA!Ven$1aZN^7hv3NLRCG_1AEDR@Jav8F+JJ zxcKY=bKY%O*J`Ehv=lorL6!~rTwP)E2#B z^z|G3E4VJ{F_M`r_?>Q ziJp}0u&4Sc?)7T+Fg@BabDAH{rHKk2Lt%DM*^*JdGX053*GZ8>eLFbq+O_J|Q>fBv zOEN_YO#n13bu0`Q-{ZH}jKO=PuBP`Am?hiBgRVqt1jF2dV@jy5!`7dr@0qMZ!>!Y9 zhy0Q(=emm?1bf+#^8l7E3UZKvq%R&E#B34} z28+jyULFf!W$p9gzkKUr3WKnEKWnMv3M+k-6eIr$Uo&YrB<@#+s;pO=h{1a+Rrgzo z6dypyILE~OA%U}iHeB^4JT4-@7_MTg{TBz*H&Ein%9=Dz zoah91w8~->a(35g%8<}z`6IDeQ8*)2@|Z@!E~DV~gC;$26!6 z@Yb^s#p|ds5sXg_=v`5thS{=sTE&>hzmjnc#Y@KV;05pLaOsq@v~>TsHB1k_vPr>X zk31dzb(dE-ecoH)sOk`~qJ*rr8Z9g(N|SasnMB9x5T5O#bkY`*taqZn3a4HBo^YaX za(~yMAKN92z@j$X1b(yGmxS1`gp2g)i9?M9^zc;Xo}JT33{hO)}a5^}DXK@n25`WO_; z*~2)^v|(mR&zQKEqTY<$ccLctb2pG;6SQ%~Z?uJXM5tPTRdKjMyvh!bpW)T3Z95VC zM5fLGL*cviVnLR~k63COr`Z+r-aGZ|d2e(>{O0fBVFNu2?@kj@*`D#M#BT-JV*J`@ zj#dy}nP-c5?c_nUSNB3W*~5cISV4B3*b$6kjL))MU!ccg z4i`zBSak=JELp4q)&i>#quP<~EPXRMlJuE4=?dLU93IAWJ1vB~V+vO|k!w8hNaQ6P zt_bpnZ`FJVR}!>njm?+YBUz-t&Zz}f=1EX)tE7wfrwE?lCa>`DFk$!}LaB+_uP3W) z4+d9a?#3(h^uS=+i$~SMtJhARaZbz;%A?@J_~F3G=xAxv{H@b3?gVh;;YJogR!TG# z&?7gH`0?HmhcehST>2g*f__(~6~=x1YE8?K-8FjEK*lM8d0GSxLUtYr(_s&oxY9c^ zbiGRo9=tny|A)u#dXXNN4?0v4-p@b&M4c@JD-{b5V90FzK8Dr%b_BmHw{oRQ&nID) zBZf#Pfza*C+uE91j*#(;FnJ~yOL%9CD<73z;s4K*cQ+bgL|B|N`TP!E!d9>JP%;3$ zpNr7*<71$6G+IWCOWqwZpB&lQ$L@~#$>D#YeLRo*p1Frv|4_zaMw1ZO zB71-=i|69hm%YW;?_6nPzY|MKk%Zph=Q8V}gOU3P*7kFuJdDEfM#Y&7{6H4D=Sg&| z2NGMi#S?z)fb#D%l@=k;MKq||+Rg*~qvYUn52at`(Lp6EwOf8K;)$ifb#vYYQ$+k+ znU{oL-aF-4YP>o!L1xX}xLL|;+j0cI2hzXWAy;@~%4hZtCI4pS^I*5_`fxB*#t7rM zRHZVJzq-n;$_{?3?%!7h?z);yO`MoIm{$0qf1NjeE1tna+AisnQL^>X&@0qu_!GZ{ zrzZ82`CEJ;8PeTx2&+!abvXU$`8#_{6hdJN4MRq9FeD~c{zy7h0e3|)vkJWm^ri={ zgQQ&io>i^KDMi*I2Rbx=FdC0v!YH2q9A?yY7|AsJLN+O_-?tcpYyx8{C{#;T2`32Q z&B>%t!)(%*NGU^MA$-Z*UwG71&pt|7p?3M?LTQ^%mmoDU+`o@h=2HlmHmyX1)u%4@ zj9I=GDY)%3d{ehRm-%!tN*fw=0a6S;cleZRsr))JN_ApGahuWrqiOm}LI|?3_{cFX zPkA%@FjN;Q&Xr2VmfVbhEZiKcdvin51r zG3C$Z(rLW#3Hx|u#gersVWUzJ0=O;3!f!q6id-SSRIivRDClyzW_4eKNgNA^%_f7_ zr6wv-^LBb^GHRBsl4TpS>jV%s^$JuqI)x0Gd`jBHD`w%ga!!mF9+L-iOg5G^5Yel2 z2~>L7aJG4)GFRBV)n39jXSQwLLKBzgrE<_~H&^$jseoai5qmniI*1UR6m?G0U8;3SIu*SagqSU|?q0}Y=bphOLnx2Zz~0X4+4!H?LA zSq$Pxp2di>5fz!p|3uHT;;Fg2egB-rGxE=XE5A!w%VdKSKJd$_TgHp;I(V{0nbSz| zg3CTq^#r{hyQZ;1d7h3RQ1daR-cU~F@%jxoORZI+*!cbmqo?ODYaytgJwU8EDzUcfJ)|rkO{d| zQ7!%nnJ`fpGNwpd0|UjhGaulAW*(s7OK9-wa&z%5fmNEIMu&-W=mau%=B)%w!~tl~ z&>Eh=A#z|65isdlso2Qh%`rOvZ66UuiyZxc)!2t1x{(_Cj_Q+q{{b|5l^Tp=W(}r0 z15>3MYhZTxp-Jq_)QAQ#3@?T73_^R%UZf370zNpq_VH<6;mn$R_c0Y2^0HNGnFe<6~Dz!lth@d{USt$XW^wM z6(VtDskB;B6aL_O=xg6|0loQXTsW){kz6iBU{J-cCrmpWWl4)k;Yf&jD$%Me_uVvH zi3WZwx_1vbi=FK+cgvWtQu`foXNae;q7n~cPv%HibK!}}+dJ3t_$RUiQUv_nEBM38 zkLaTs)6y^+(<4}}m%Ayg?!JQ`6(ZDBgh)}d3R~&q+47h~#CecFNa}qLfK+5da^SXy0HhS|uiH9bp#z z1;41}p#ibTQ{j=dYo>uOX<=!j69<=Ggx9hQXgp|iR6X!R8-f^ap2<0orZ6Ml5w6l` zm8M70RwG*I$O@bkqm-W|+-l9%tR-XtObiFPbn>Koq08b4T1BtfAhmH9n_2RYe39@!zvOmY>3 z_x>o#|4?wE>{-xt$rYI_3n`xp*=i_r2#ry?DECp&q64I4sxM;lm5pI>wm^$w7DZJ` z_NXKu_CHgnsrSy%WH!ia#5npkSJZPnTw+7STr`fur$5Zrp;ufaC!3iaY=IAjRF2;A zWG^)*0x`e1>9M4->~{^0ws2Q^Q{rNAhAf|ndCH=ClXu0L^0NyaoT~Hf_4Jboh=S69 zQ>ab}j)lsekVU5G?No-7nXY&D@b#Frhb_eSh0Mq2@Jb1jjMU(a>x+<~ND`8qk3W7P z%!TTE<$z+3(sL! zy_DH^h9t;|RreLH6x&3kG-i+NFjUU}u6#`gk;b+c>@hy-MWp97D-9wISv$T$e++1{ zr0sJ=2MQR|N7&?O?mzCk5fblCm{zl7*U?zujG{uG%b}9R(QsPN9m*gn9aFHwlsu6a zXFqCicGV=f+d{g~#6nHp2V5qx_rA-lc|z=5IGS}@R)7-!rS$4k0$RaY=M=YQ1k6j1EI%lPk3^beH~LPBL4AK2xH^rc#$c2`@4| z$GO9q=wK>j_Pol%m}tkF7@#s6GbNnJbYIS^lg))SA=#X#DI;-9cd4wDtz^b5X}ZFo z*p_Pz8XbRz0Gh@mg$%9N#>S-IGSegMsLq%bXaXDVq^tldQHq}GMX8QT=PE^OKj~u= zl@^3*JQtW1sN_;9b8v^yd5JrV{!0}+#PB;<#X^5hqoQjwyQr+V6K#QkN{}*68?nr% zEi%m&<~mJj3ivEpe!RL;VN#NT?QFN>B(>|XrLJg{+QTDwrNddN3>Q=CVFmho+MJxr z8AXjplEzO5GVq8GlR*dYpfuy+Nrpu;nq`2w!oyJgGNLQp=IWC(1)O@)9Z9Hda}{2e zk<1Dh1C5w6w-zk1gX%@>RZoUSGPBLYsnkS{cGz~(vfI=3TU`hvx-+ra9Tum3~*$}GP8Fe zm1NO=lpPyZv}A`Aqyi?pM&i^xKXO(-y5kAiH3|>iD&ZMMNchk8uU@KV^1zQvchRd-m<5*^9C)zCWrr;+R558yQx#a*Naj_) znllC=oZ8=QkS8M+Xj{R<@v8icZ}65K8ABo&s|bdS#{U|Xf(~(N&WnnxmPDbtfCkCm zVM{s0Co-(GWgWOgt}N!`Ax(3l(mftpais+3C;GW;%M4($Eh|5X+OH9bx+sjEb+jxZ#W9SmP0gU*UL{*myQOOE%lK)FIH9)0yG z|I|Hfnv}mmiSz3GT~Pk2;>usvb|73dj>^+~Ni_(}zb;mw$VQzQ(Sg`ko@50YUrHpOY#p~0I3R8P&BbE6+JvUG%lNwuL{J-D-ypD~=S&U!wGy%5 zX47X6?CB7iJ2+y4GlGPw$t& zlAAJ2{rPR#vzNeR!;CaXrs(!H!}6rY^96yFQYO313MSR=`pC#ahhJvH#$T0_#+Q1_ zYxk>AEO-eL7j9wE1>A{)z-n zJ)u>wk4JsQ5Mk6oWIjbLlC8(AwU(=#(@OSzYyZy}F-LJjKZPX>)^*|b3Msxad0V~@^P z@3SYFu>nkIVSU+}mdfbKgVpKGf(+_IteMhM!HY`Ij%}fmps5Wq*9*Cm%rPDoDU<3) zD!kaaUM5^aq~{N#Mh z(4S9!`n%txY55lG0uAeJl(Of8Rmnxx9C_CjG5Cj~6Z10iP72Uq0!MIis63V-T#$2W z2_JPRyai3kkpdbhUunt82A2~_l1iFPy1dQ<6?E3_2UxYx<ou2|20C-co^H$RKnshwDp%2OIQt4#H+F$r)JE&uLSI5oia?MW#%6r!+gx8}Y3c3Yb zY55w1ook#eA$+EbJy`^3Z-8nOC%xno1T6AJ+=zeTg93p^HMz6;uQ7zXfk(@mTJu>F zf8xb~s!@HB!4!uS>P_s^QkEZQQTQZ^jWY*nDwI1s(y0~wRJ{6o1gG9KLb3rBPP_#` zNSzf&Va?v%mjWjSbfP)Gh%4Q#&@5#D8Kfh!CEdCXx*z3B{~1`dr9%}JxXGs@^!ABp z{bW)hU5fQz8~C!wJ*q)_xUFmy?}jlWn#@9lQe^A~O5*ZaHG=k@!I3R~E!VhYb7R4; zp>@icgT2?K-hAJDO%V?B21Dtxa3o{BWI1V1AYJ8miXHK$2AgnEeX{R^^ll8*kf4P6 zXl)w3IQ3R~vp$7i*m|NIr)_CbpavcA)oZr_57jG|Ke8}ci4rlK7?6U^QrPhL1>+PqMovE?Qp;O zC{*&V$rqJO5-=M#$O?>-FDf+Xyn$oNVjqtzZ?@I$bEdM{(GBreHeZr4Ipl;s9G>nZ zZhPp2-b%@sWS{z8$i(Op<5xALoo=P4vDhp`Ov9PvMl*!Nf? z2bFYY4Gu4fO~j9+J3R12p7{+=i3z7lm%nv6ZIwQ4#;3tpHhSo@3A!@7&!~KPe1lUq z!Mh<4-xiXOI?%X8`Z!wEk-l7G-$zQU+7rLo#l{yY;~vxoQiUuoq;Ybpt5SQMlB1s) zC5+`9jRaQcCbOTco`F$I7ouG!KHWL(ywq&N)yF4jNF6^}c_OsX3>xRo+#^C1t9m<) znJru3j3Hv=-96464CrWL_KGD{b$5ZRRD+CDR-gpVZZRPsH6H;^&g@v(NAG*~FyY^G zow^8JQfNA35|~%R(+y1x{#;_AWnf|5$%P#Q7}6 zbF5tO)#N%Uchx`6H=B8eg$Eh9n-@MFi}&HPtUL1f8M!oPcAoA{?GJDD_K>-iJOUZ! zox>_T_o(AUYK07CROTvp^+IpN7kPMrOLc!*s8kuEe(>aVTx!3)@vbLWr^um3DomFa z*QYZutoVnKhO9yLC-1?&g?R9Kl<4_)Vui%0EH)xFjhUs(TR(~rICba!U_G^3MRpM_ zI7s@&)@_ox>#-U?sXd0&GwOq0<79Nbz7CjGNu!amXjumDfgWlb#_Fl2kD57#zjNA6~V95xV$MhB}DgBL13n=8ve)Btgd+A?>IiHN5l zqHz(6)a`b+>9`==ix(Kqtn5Oz-1Ml{mSN`4{PfjoSJ=U#(*BDazF3ZDm^&tXBbH00 zg~G`$^??|Y)x5F%^RIHUO3XXvuC(A*AvL@<$`dj_+9PCmP~vI4gPIDd#gn?cbQM&} z_>8;Gtrtl{lULlE(A2XQ8n`rT= zw3;3VaOQ(EC{9YXpD)NTn*1Mg9SXiWl0ozwCX7-%#TjTPEG$+ z<|Ej3HS1Bbt^zAWYI^Wz{6TF{3l@$|3%#DMM<3)ANDFZ-^Sk34?`iwTUpdCwlgpBK zHDGhLT>{3K$ih0V5i*q)A4D(i^$0zxmRgwMjtAL6yctd5RgcCq_e5^4XX8y>J-|Ko zy!K5i*n(+bRPFt_l~V!~}kk5LU? z4Aa3BEN3__oNOeqB9#!(nD|$&WlKB_BY8v`S>D^{Rw<1O9I%GBZ01*e!@KShCLVR* z-f--uV<%};>i{>$2Er+;0vT;C@FEvc?tIjErU{qq$fsCmX5wkXZTNgN<(^J0v%)Tz zZzfNPIT-nimShV%Y`KQ8zSPRO2oj3%#W|m51;dl9*?Q<@9yXkFgggL1FP^P zj&Gp;b3Kp4KiJCU&#W>;8I+v(C$y2nK&6qSG5UU?w$$W5;1j6CV>?VHB^*6E z)vj(Y`V0|NGFrFu%^TbpTPMCy{N&is!EzW zSfP6?R0&tk?LXW_o9|EecvERjO30$&PYBh36vI^VWD7#LFZ65|=d<(unw4mNRW<(HB)-6Ot5K?!@`Ud4(}673F% zm1a?=utTPzHG#!JCq5a#Brk@VwbZcLbXJ=X)?WTx;)Ize;$XCs|AmfmxtO<?Cs;d^cQQu25)i)nazC&0_|H$lb02Pw;cg7aF0kO~3CwLGLK z+!m@(_eH{zo!AyZiozUQaQiNB>pdSbfZP0rqbwFd3_gjAJW}u^e=|)cJq$suDB)vR z^GFq5OraDWQ#vQJd|kL~%*hm=5wIkE@~zk`{$SkLG2B9lMt)4fY?TTYv?7cXrEVjx z?d>UV58}p_?hFj}!KnVGtA+h%1 zL@Ikk^0+j{C8$*#F$a6RG$cIp9Y{?0EO~lBP{(9qP_>1UD5HB;L5d#yr9YClz*27yCIU+x-N>&VE`s&kB(T%GD`}Qu+ zkcI9hDScTZLZVO(LMtSNyn;8;RcqSw`ztm*RlU8|+^knzD}A}}c=i3&JW z&?36jChMDd06)h#h_sJivJ?TbSbQcT(`$5bd*d{EfktxyTkqn{(PXNEQ`UlreqY7- z->7;8+^Q1qoVqTB^*5DEbUfG*gXjhC5{0md@mle!P#kL7AQx-kydh7$`v7v?XEHcl zG^<(=Om#qG@i`P9LU^&RVA~Q^AXkwn8r57UW_<`j)E8rExckVu84-{QkZ!SrA|0_z zVMai%E}>D8M~}QMOzZ7=9mlEL@Gh(1FB0Mobs<9K?;-mdY1~=5y951M97v3 zwyvu6*f&?`Qyn}NunCt{1^+Bll-&4-mz08Y72M~n$<9aXhEesZ(sPhaqk`STPhI-5 z5PtuiTtqK7X<6|{&s{Bc6ZKoy!JP=Ic(+>ts07ri*RG1bUGCL&@fZL^B9$fWpndDI zxEHtKa(!f8TZ?w%7OUda%{T!6j<_xLZ0yK`mBDCNDB0*~uy7QEpY`iq_w@?H-;ts~ zVxE@_g1J<*DX!`vm_Fayb&*ugX33FrzTtaQ*;thraQ3670kmC_%;oHCQ*tR9$uUC} zi~;ptpe*Xpg-cjrx2JP+UHmYD-D4QJoGk>GD3KiVMk6C~kI1*K#_)ryC{fjzZ3IQ8 zb@&`)pel;{FJy3s%Qvo<3ZAhlU8FdGSX6&m;tcEi8Ks;OygA;M3jM39jwo0b#WA05 znWS5aKJ9JNR%UWRNi3pi961(}YoSyYqH)v}mzGbeM6ZRpps8y%g__EWGJcc@nyx}= zDU-%RbTOwF^s_4d&c??^DN=@pt`>IPqf>N6deK&86zi&VOac}rtyC#j3nE5yA)F_3 z-wZBBJ8z;?Q|3U4p7%pL!GDF*%2vcnE3pWI=&i7-4MZyXhEn*l{oS;@!q>#U!(0{j z=hyU1J+hY|3+3p!qnA0g023T802}_T#R4l4W;8SeDm{OO%CKUMn29J8QN9bm_Xo4y@oo6-%Q5q@w%F|ZW z@B@V$u9$VCuCjMVF*+kum7nwQxOlrRP4QPvG!z7p>40KJ;6OOU&_gG5un}qszM^hj ze6EFV4q#*Tdp<~FS#L7SPzZn0G!8FmxI+it?LHuOb16D#H$18vk^#B0KwmWa1HTse z}Yk5l2xeO7r@PSlyk6uY)!%6=M2YoKt(o$T8KfnI+&Yqyy%U zC-FM=JgHL&*OS8@to^JYi$mcy#ba8i@2HBq_T)7`mMYhwkH?a++YI8pJE3_lT{m#W z*9BH3^RZ#RY(B^qLb%ArG!A*9Y2^ysFU=$&zmcT)8S=7p^<~A_z1x zcukF3GI6?Yt-}7k#-+M-hAb7F`78dYpuUu?sdx2b;DaTojt~pl3*o!lh<*a5<9sb-}VJm49;}S zWF?CI*=tEu&A1h6u?Vjr6%AeoAEIZ>%eia5A{DBO;cX{o-Ip+PrJ7$DLZf~NvR$X< zJJxg817+&t=ymUGcBdeSXPXdxRfNjnqu4q$b*&#f8$JrGeS?y#8=`xv1!(#Ny!pFa zuBm6GbEc^eE+fjFnQP%xr3)-~xUD1?tsPdf1Z{;-D8ypIdB<3GrV4^1LOM6jFvlE% zn0ZT4p{7-Gp!TWn-{(!RZB#fFwGt^{Z88a;G+zcVt2yv{?RTT2s z4yx}R`75pB_UJWov!_rdQA}>NRB6$kiBK%*GLO&R1r5oKI`up;U9o7`L?nc` zF-B$KfHrZ*cpsxu{OY=FTo|zuUjwX^y4X~)jObh;)-WRzI7f7A{5>(5rfR4>As2Kk zfkJhaQ{uVGkv|s(uXm=D`N^|G%3;)aw?nsK&sTHTCMX4i!f^cnK6PoA?zG>S%ZBY@ zREpnR+tm^u&8ckt0*h*3sQXn0J-N0_3e!T=-y)@SS_t3zq$+-xXyz3VzIgU9dE6B! zxtjp{W=gQuz%icqeDGFjR|R68AY$*5;TnG%i&zeuw$~LdP2NUjY-UgeN^Z;vABzwh z48q*!eYOJ#bYD$!#<4N`n9))7H2Gm(G*E*V8>PXr< zj{Zl2x6iYZozh!maa8>yxY=`^^qP{}d!B=Pts7)5&V{ z#0?XMvXnHjIPpWXJpG9~v}|v(Bclbibc{D6$gFDlJ)r;?zb5XnX-_fhgmvy%iL~?2ZVVrWZz9y$~B*$;=B>Qkxjb5wdLm1CVIt`0*Fx0qJ=4OZJu_N03pkAEuZcOvb#sgTt-Trgs>@GK-#-WlD@$4Y9^Vp<#pZv115eYJ19GXon#XL=Eho z5`i%}d}rNq7zG>|Z=0nLO3(CY))7f!9KKUq=x~7?8T$zb*h~#?+m3O;_}D=Nx`B0t zK%CalE>_kv-nKXw#>;aZ4oS9Fkq{ROO1P)>Q3F&?PE!Q$icK}D^H#b`Vg zu&pZ3(1(?=8_jac38N?&A3Ml}@xb3kfGrX{9sC58 z#O!dHL{NNca=wH*>M}fnm zy06PFJO`b|5#YgR^tk%iK_0Mee~JghNQCaR1PM?%C^o9b#>b8#;MpcSw46wCK?~CvV8$}0Z4;xXeFtdLkrrE9ppiG ze5&HXZ7j?;a-8;qA+KPto(s##ksm}tmA>5)aESyt4jX7vSQhbgYGH<8Qv(?Bprl*m zb=AjC#X{q+7X|TYAR!Iz=VnZ|{xSr*j}>iD{vhDS#}0}NueXkijFFLXz3isrmw&gE zk|$*x2()JWC;~0s2RYCkjw?l{^}n|v1Pr{}TEH;`=(wEAhmR-qRyE)#62rqPwgVeP zqUFPdl?m3fJjy%>i{Zr9slA>TzpA{#i_#v2ZmJX1Q!z%VyyB=4T~=VBGVbuhhDskt z!NUEZMsyny9lJD$L@R~Y@j)r=a6HuV;c%g=t&bh#0h0i~9)X4f*H!A29-Tv=tr-s3 zqbm^@?rz(D;drUhs!<*kqyFsdevxGmiAIpZK-fj~QZn>Y%51|jAWZfL4|0NiM~6PN z&JFKI;bh4b9Yx2>%D%7n$%5B$6fE2i^1*dNqxB3FDu(#bYQ%MXaGlIBGB+meem;N4 z@;jZBa|(SFffnzBLNtE1)%FcT2(%(}Sp$Trfy|PR?}=4TKm7v~wf}Il!Ba4kd1Mz?$nA5uwY* zLEa2jIuK|{IXKZ`eDJD?7QKV(K*8X_*iepvg7v|Jg2ef82NEqTOb78Y{NHaZM~5;T z2((-{h=B32gB<8S1+gDcXg;gYffjFLp6VC^Jg9I^m9+}TJ6H4a$Hr)yA$iu$$Watr zWv-T(M^R`oKZrp0S&E(zwUD&_z`*-L9xx&>uE>n0aWsQ1C}m^wj2cCbJfpTbZ2c?8 z>zJ}1b<1oJv06CgO&|e0(lprkU_0u6P?Csp2iX9;?ALL|xS05>SDE7LW9vy%Fksh< z#g=7xN-9sXy`IlIhybf)!w48Ws9XBhw6e*8x}h9Db`*i(I@bmyZK6`^^2W!mO3vW1eC$GF#NNUgA*!9SRVcDisGRbdk#{zb$JN--f_|N41A%r|;h+{^ zRZekWVBF3|;lfEZEiary!iw|A|=!J*1*QRhn!A;qZ{Q>Yyn`94T+ zBjpqBY2T`!k3W6PlkpCyM~9C>&YO2@lrP(Y`rL+#T@r*LNE#!QNngPoSKtqlo^Wzl zXpSb8?dL*HnP(w`q#Zswi|@v(9``xFA4)^i}xlvc*ldINzL?}H-5`-$feX!G+S5o$kn5P_$wxMh%Xq%L86 z>^cM-r7cs54>vjyi<}Xmkuyv38x0Ta4<1FrRo*gS8L18#AG@wP^x+)IIX)aj zq5arF9&lv+6aq$_YQPrJrYd&$&y=@#Thrr@4QVKwW?S{S_G1?!aI(Brb^XQ>Fg|ur zgb1h4iBMZ991@}SV@DBi6}Ajn=uM*8ru4E&w9ofsVXHezw}C*5_dyPDAo7$5nU&fR zAu>OB3<)k+dwg;$MuT-~cjCBi)50*1gXSxO7+sP8wz*yG?7cATl@_~nn9DHa}&70A?7_mym$BrW4s&uvT zFx0a#K6cf?5HgT+s(ciIt4_9X0@DdvsQ>M zM8Q?^GI(H}${6B;^}&OD=sw3=@xef%?coif(0=SF0A3G>Q;|J>P@N%$!-wM%nD2$({x9!kj6wD7E#fUE4)+M=N`kRiMei4ZTOo-BJA^Bf}_Fg|t^0aw|pCFRf@i}A7c7WqL0 z#_!VGmgpz~7v0ogEaGIj%RKTwBt(}D;(&y!+-1mvbw2EGjl}qU`VCP!jD+>UgZeOj zq25NqxcD@}2jgQ05g5NvF9cdq8n|_}@xhDMR`3a~l2_~2j-z1R`8vpl@jLa_?u|9> z)W{KM*x!sq$GxfW+@$rfqwssGUL_>q0Z;(p0cRwF*V32wGV}`T4^KERf8OamCU$ z+TXiPbnX#wBc12nu7R_AnLE?C`prH`(MNe?me;x#QBlAAG?lrrINBz#Avl0VvGf?< zGPjiXn834t*XaS?`1f>Mh6T*~jm5s%$MgB-R6G@YzKef9p$9yCKU#$k9AbU*_2AkUFD3GTlQgg;?>;`|R_e?k zgC=<)(x=xqUVqqcOx;xS&PGWSz(_p^!I2-m`r((kkDepXU!oaKUiV^~fd66gXVH$_+q|k5;Sd>qnS+vdQ zSg#NMOn8u==l#W|#~HQJJJkC;sVzZr2)J)HmGnwX2l!Wu{#C#~J)`FJ9`fX61e(Bt zAFuQ-oO}eY&DpJM81ZyXohLs&$_9gPS#x}9%;R7k`OhM=LA3$d;gcE3>!{qleZ8`( ztk#Bj^Ui%;CNdHCJ6{tclg$!Hz2Lqzv@E#D!vIrhHloyT=Mz)vY?khOV#sFjhX|1bj1EIz-PxQIt- z1l2a>^~u`@Wlx`!btiLv@r2rfb$q|~ARfVb>@p$a5du_B(Y`V`gLvqZpBu!_B)Aw4 zlBAX&TXYn;$Vm|M}c`J-YlPUqpbq{80{ZRIWa_v3;e; zct|<`nt*2pM!$Ce3qHqLb5gYBb3Y+2zZ3dhg$C0n9s6Hu2WE_STo$d25zL@!^RE1m zQ8-jhx^vj8qvhE|iK?81oPwPhfS#YX@V?AK(dO*HUa}yAZUC@k^U)oYh;l9H_Wgd| zMAM|Lgd`_KUnf`gMc*d24MPL7L2L}E3I}IkW;Jgg=90)A5NeR4!(L1G1t5QWmNJvs zhGB%@`ebsur-9}b-(IAX=v@6~x@3*RZ^@hhwJ|$nJ07fHcPx1VIhcZ_^11|t`(7v| zPG`d~;OtGuY0oJYbQn+l@;`GRs6b{FOuqMBsEO-AZ^`=xlGXqAFaP|n|MHhV{_@xV z^6&rp$8UdDZlu5bx4-=Lw?AiDmO$PfudnX2J@3;u6xWbUy+zA}3|4IVzPsVr82X3t z;d$kKe4ZsQ-bQilr>$LXOVS2S2=HiTQG($f+9w9i$HGhAxa&F4Iw{9z{j6%SWj$A> zdLJ8xY(A+Xyi?6RrqjfH9sU#TiB@TwBKA(BjJ5e)F;ZsVsK7GOgukaa=bqSe7joydcW^CQVd=-|BxGR(BvpWcSL00 z2v-cUfWdZx4-d{$r|7#Bva#=r`1yfn4ef;ceY#Nrhf_q>ycsP74;o-9@f~DRM-54# z!nFn^6}5Ibl53(QK==3K#hDmzQVMbc_IEEbDQ#2+VF2V9*v?JlTsl2W<*8T7N>twX z&D+!s@hn|PXgZ5X6!;72jGrGB_$_G0C0^e!VUe_*6BRhDj@Kg35XW)3Q6jpJPmZEC zppgg-Tcq$EZCTwg(?{hCyNIZd#km2R7Zu0F;$t~BEabk>Az(kBU|)<6Q61g^@Op3upo?nZN_&TC)$5pOgZ zYnrU``q*VWs4UNKuOFD=_XrGQCQJMs=g@dfb~J#Gf~uC)a@{*LNSpD7qt+NB)DyQ# z+Bm@*ZB~^$MS*YiWJ*6?WlsTxgVa~#zb{W!Q-OgUjSqZiT9G=u-(LkBwEe#H3qrJw z+pd0Mx}}jw(SG%>>GMocPJG_@k?;ks-X|CLd*)YzN~vsxmEq7M;Llw%8BI`{LDGL; z{lKF}Y5rHbck$0mk`g833!Er*H^dm#DRE*-ja8KNr^RXY11p?X{~A9|H$~%OGn-aF zqAzga^rU{#(UqD_t6#W+Nqk!U#NPoY-camRc5gMCrgxG%n6<(wssmG%Z{pS$mpr&S zUg*>9cMJmY9}bIW>iM4cAAbsUExzc+qc@rRGs}3>fWpO%k_qyD`%G?@QMdM>7Zj0a^8kfzkGwLjiqwq=Q&eCs~v^&lE5 zJhO>g8EmY6U~TbtHP%vUzZaXjt!V~FdMH)wVj}waqz3X~WPlFTGesLgcbLf{{LO!& zjeYa(t2R*xWa!R>87#MPpSthaJ25!|cw|aT0iU38wyTpRW%IW~)g|89w-7sDV6cVy ze8XNJa^wY9BDY2H!nEJVgf4uO;Ut{s5#@C3Us9;>8#kaUn3n`G;%ZujHLJGB;zXt& zFnN)&1gPNE$|BAYi?6m_av**@$rhLO@I!R+&?sYk-vXuw*f=;74(s6#k) zU+X=L(}2)5C|o3T^aDE@RE0;j0yTWv0Adbd3>;)yLTb<&YRz6C0_#>a^yr=$0gRJSr0 zoNP&4Yl*?&k@$AQsMJo+9p^HSennBOs1q7BvBHvU6xHU>2UBExfs1W)&wIt%x&XEM zh0(RXs7B+_=72nm?;k7}uD|FSBw5z($R;B>m2fgQ%?`*!dE`g`Br!CR1nu$%?<?CNsHEQ5n~lVRR?($YKRJE8fe9U(p1)hwuvuzk_xAH(M>r1nZ(ztU zP5FZ_70e15UHx-F(bm4zPlhk@$tu%gy*hn4Uk2a<0h9E#qc$X;bYh6+aoT&wr@~3hh+Z9}>s(Q)I^~>o0$1`LjNI*PREqAbz^9LS|F~ z@dOa>Zq0viB4fDdvnx8Ve-^&+I%IgytYbJbG6I{4CJ3DVe8T*%I=F!swA+}LOMenu z0?_(s-jQL>Dg5p7QMT`C%cnnHuCRH~%a;iwx14h{@(U=G+ZXF4coG)Ef92F4H4?Kd zx|CjPoSg_aK^`b35Ef4actHyi2L$`l;(|*nTlOoU?;h!0Ii4y+sR)m?PJ+dMDS9A% z%C|goGND_vp*22mmSow zV1+LaCTB6>*_*|m2$0o3;sZ?m<$bC$OI%3AjUzyuRfLz(B*x#p5TyVw{ai4VpLet% z^^f~N#Tax1pbY((qo5O>{)E}Eg_Etawl1#;$%k)aL~9w z;P?{<3EaKTprPwLqGeKe))Hu%CUTxI+t8y*s8LQB*1;250!@((DYv zrf4i5EI_?pGF;Ck1wv*r$E#q3;EhxZ^owMK(0bqIKFeC44Pi${7DAUCDy+wOX<@;n zW9;(wfPS$|Y!MbOvsQ`DnFXteC=#7-n3-}+FW=&W#Xv7NXf+oN?6DNru4uHhN=pMTM1a!8s6LAE1p+}5#iZ_wyLT*f1s!HtFB~N# z*Z)pWcDstILiuSbBoFqGSw0~#V&5+m7+CmwFptYV*-JIBn}$VvEcr6BxGz-|I!pj+ zIDWB2VOhbCmhmmW20hJ8j>f#~4;ygZ?uuZzGQeWtm%~(&r^kn@D!SRpq7tm#V%YRy zD2IYK{^HAB9DS5EKF%aP;UsXqR5EvQi=&l28<6*xHt?~yg$#ntg9RE2q>tQX;wwt| zy^Bd&1H5yi{2KY2(2mjcY6GDbD!QE%R^ML+4em^;=WvcSZm@J$X|xa;Y|&0!Pi~i^<@68%vH)PK*W1V=4Y02ag6=@DaBP1}3GFvFt&@^Lj zl<$7he3{DfaD`E8Q8=~6LJAuY*mZ*TP+4|j#I?VDGhSq(HbNYjAlqOM{Qcotb+B_F zLGfL8BQRx~YQ&@!>ws7|ItJ)d5ZIO!UVM5I*V7}qyDeBKJT2rPh`LoqYhl}X!zOCz zTFN6%h`zct{64G@m=2ee6fD*u93=@$;`k+*C}IfqR3=#t;GP=Tp6Y9}*Iw54CZy&-W=M`y+-@HdbosW!l+T#HBh6*-F zSp4ce2s4k5QqbdY33Zm^L#=G((sh!93!v-y&rCi9UT1rPhHO(W#A^)_M~T-hs3-9& zq1%?e@}~+M4ubdOM$W!=*wour-;#O-7DwUhmwF5Hmt=1nJn486zT(G@!be)WPd~Pj z3kbuNB_1x45E3$mz0G`Lf)`MVg`w;|1+>VyA9IKI!3LtE$uT?>@@>*xo)gRY)*6tt)vAPx8L z>&ZrZAYN$alZ7-SP+qPWGrJ5f{MKZv0HeA4^s5)--kVnM)wKE6&ic@ zdiT&6JJ)*@4ZW!2k*VGD$y;b3RfE@)kD{S0Y7`C0M%dRbhSP$oeh5a%r%XSP?G}m^%^WA z97M!|W)CC$#hN4}CZNIh@&*aVLc)2UgQ`u%yjPp38AOn$lV_|?sk$new}9D2sHF*I z_)u)ptuJb~Cvs}4+P%4uTx*fQP^F@p7w#WY1P>D~AL5B}bV%~Di%?4wEBZYaG;-sh zXAyE5B!t+u{jkSN35^FZzR@ZzZwT#SF-VA`Sm=J^?&?euGjMp&UCKB_ri|dQhx=i` zT{%35K(aW6;f8eQc#HTO_!>fZ5C!fncG^Z+B>;v>qq-uL6Xn69>%P6wcipsl5ognt z+0h7zU_%7-fzO6_INoXooG`&OsT`8TH6;QG*35M;cM3O~F<1=hVa9m6>8(?P9c%{a zag;gTje(pKiaE4JpB$qn0s20|8G3#%>cW4gxpiaCa-TJ$^f-!5cfMHGIoE`B*tsq_ z$lb3WrQ5W=qXapK4cBBlic|AO3GvQV=ebzCV+ZKU7H6G9johTiQGB}Bg-at`oplb! zf$L+0UA?K!I!iF?v(7U)j^fgNz_kpN^Qq=s6W`-QdC__c^`n48*Ktpn059s5yMXiJ zl}z^O@+*fUdox`ofvNwk57_O&%eLz30QK3f3a!Up+Lr?+8IZBV(|bq^-JL!fptG#n z$zsbX2{{P!$+Y#A*ByMUOV8vR%_;6fO|LLBvM>J?dn{m@BfNXaPzA_Wr{il{)z#@( znm(w^{h8@fN$RuH0hWG&9T6>h2kkZF!*bQ1LM}XY2B8meNUN5Yi}TUx!+>^EheYG8 z-@GLs`gzW8DV6QqoIVPC|9oSX_AO|J#a&-8c5?bKI_$3PD{nSN8_-C8MvYPUilK|s zhY_MevyV{CAGQw5i_^;R%y$a*ByQy3^kICMaoNYGQWi=c{R6c7xXedii}>WAE$t7H zr|2}u#d1Hk_{~F*o)3*^bwb6xGvzgrtE=825bj5z6^f*Gt83mz<%4&(JMyt2a{rq5 zW_A`)C@-4NNkDVf`#3he1TA4xx>2U7xR)T^-Gx2%;>(|3CYD^CU#?WkjOm!uV9Im=7)VLpxG;gw!mRD`b?&f*t0 z(NO>Ezc4d$_U?3f#m$VI$MJMbkvd zL1@4is9_pF3fZY)6Lo7(J8$az3A4U;~OFAw&PnbyBSxt&_2?+%536%o_ z`3MO={`fFhk|!WSqx8l^f_x4gNB+$x?*PovnGUft!1By-2!mfpJRTKv6X5XUY4E}l ztb;J~9C^n|*Dx~<4rv5)pUNTn;Q5Bgm6OC}U7%zAYCw6yUHyy-f6hp$1_@c44 zlNN*(#$GkF66YD@1VTs$Mr?@*`-P;}xSvBUnQoDY4~HF$^hvH0-WNo7O!M_BL^bI- z)atM#%)c;Tmmv%Nv9RzabEqt7aP>lY7^nc15%8w*2&*O8g0<$9CMThI@M zB#ik0{uN}VQ}0s6EDu9u&f;((aWx$6vDex7jS<(fe&-@TQvY7LtdfU29tLSn<|7*5 zfxP^#)q=wG1z&R^>3M_G<0|LE#<2OA>m~{B5F(r;Jq-#^0BhD_Mr6IH`CLeF<_$dh zscQ-zdyS)1sUZ>kg0PTTa#t0HU#==n0wId*h^!Mam#|+g>mROkILyq9$GEIp;GdLr z%G@sXjM9=wKOB*pVso9;qp_~S&ulKoNpD%nbEIdk!BzK}lZZt6VGD0&6Bm-6c+cfr zd8WG2-Z3}JHLp^AFR=C8(s31q*c;((k8FCzneb%{bZs^-WCHDGj~>r>49hIs5X@Cv!dZB;~m!Gpw--#36O)lDmTP zLK?GzKkQirL#hi75jI!zP7;<$&tWYD%%Yvpi(d58xmRH{n2$BkLO3)UvH(LaY!4AO zw+K%X_SJiC@3_%gma0PvJ49h!z{!zo_}ocSbI{4-?P|b>+(LBq`Nm4U+;8DID|BM(8vjKad<@h@8q-ZE3Q>{}KulB-y_YPf5otKn{?- zD0E&&_AghlJeq3tZAQp$HoDG{otcO6IUvlO1^NKli`LeKWanEQnre#72-(dd|4Fh_ zf%Yh>In&d(?Zw>Fg=A+l!I7YvqhLd1&r=sCiLGI`@uDV^H_HUlfMgf*O&5~*)m@4# zqm}~VA;RVnoRfs*5ekn2T4OOIB+i0xA&IB%%f=Ont?AbxV#hJtREE2tNy!OgPld=H zejP9#c|iC=vdiH(bkQ<=Lu9wcCr?THEwIo5y4hwNAiLSuyec6Ai|)y^O75-E;~@sb z8RsPT=jVbrH`l$i)CGOS+~n!(%j8~X=f-PE^d>B_=i9)>BIUA6T+EhJ%A5}xKYpCA zWijjh;IS=-v|9jkS$Dp`JO(hQSWf`_e0oYnCWYB~bOFpE))N4$^Y5UrWlzRL!m=pm zgyY>^BCa&ivf^X3E(Z5c(V784Pt0n0`!QN)r+JRTl#xB^X8}B>ei`6%>W5o#RD8^! zWK1M7z~|KOJ9+9nW*Rdl5;=T5B@#ELEj&46PGiRCnzMpabiKh^kE&%b$K*AGc}iY6 z1nH^S6e-pi(=(Xon9d6~9<{PktTDP~DLqG5F135Sng#Hfyk>yU$tzdOJ!)n7vN4g! zzU-Vxa5%xEU>3k*B9Q?;ClWk>=<#LNZ0VRt#A)2nDmxP`D9>;xommte5{aTLdQK#m z^>HYj3Gk3e6ab$S366+6l+FZrNF)k?Pgx1J+*~ymONNIiTr?<7QJ99LtI%QrJS4*f zz^7!GqJn4i#_U}UiG-|CD-i z#nMw=*`WWR@YwV}CqK{bdnB3uo5DXxe`6H#9P#Oi47Q#Nh3?Ok9CE#{CTDIi|Cm>`4BK-Q+Q*TRW-e*srHU z9qN^rsmIuF0ensncwX6|R_2oOm`LO;<#QtOb=)J~*s30*bq4qpg?TY)`~b}cz+=*! z0X`+eyj1I{xD-k^CJ2@cpAv~zn35ViLyR%YS0cvfY93%XM`A{;99maEJSMs(#OI`# zvZ2SXWg3qOg$eOFso=RmPi&bz@t9O(7k5q+UXG)~2yaf>#t3UBZRZHf>roybXI>N< zqj5edbdJV)a?atEO^C-dFGGAz-9CKzV91qBwf*Lq4o z-n=n79A^dy!ksl$e+P)H4_N)|Q}pI(uJO`I4f22_Z-IPDs5PZKtcEqngMwjE`J7VFp0@;%4L3&#Q)#vE_aNZTRfFG1^3;1*L{q$WJE*A}WEr=EzPYrF(`HNN7ioiKx zdHIeB7a$Lchz0UF5n;o@qmo6Ve+*=Err;dNlkR^n0P#50rH?=SdIEqf-zC79F9vx<#?xg+=-iGf2RaPYalN5%ODR@*;)(!py^_}K-v$-TnwmQ&1e4=pFCeq*vb^3iCIsfT z(>ZbYI8OG~AdlGu6XbJ(@pYW<70AWT&yYS|ZeqiO}9gW^yuX`R{8W)4jE- z4GKn<;B(^ebe!xJpm~RCkha#k);Zepbg?IZEI=NVU<>4P68v^t?X9UiC=M3L=LBP7 zSaP)FEs(QI9uy2~Q}Uc(Opb%S0y!VX7^JdQJ~>BaHvC+kE-#A@QrTLhKS$-S<5sVz zoIxH`KMUkj>c_LduJTC%@}OW?AfFP9@6CCu*KE^`$w<)>JS7?5yW=u1lCd!l+CQ?Q z&*nDfInj7H4)SioJSHUt%;#j|={&w$jHV66@#XB>nK=IYava(fam^RQHNfq1!&-WKhN0ePSZo~!le#DSYu9k)iRj==o$|NTFI`}6Xp%W+c2I#g!bv*mt&v)+lP0?3VMyrTiB&*fLeYj_j~^@VE*ra0p^Q(m#)7E$=Y@s`7&mdG<(xG2s1*PGumAq9fBg36-~Q`=`ad4O z{qKMHU%&n1zx~rc{qg_&*Z=;<|M>0C{QiIZ_rLz}pa1Ef{@*|T`rDt0su=j|w8=N5 z$s&}+T0f)lm-@6Zx_l5 z`(PatP%aAItU~Z6t#dK|LRur&9lKruY?aP7H8Ix`FQo9~n)5d=eTG=5qlp>z3pH_a z4gZ_4Z%Ri7_(JLUbe%^f9cGhYOB0J0M9Q8|n-12+Jo=aWa+`F`ZT0Ku%97Z4CmOeq z!5k6Y4DofM`=ZJ|oH$hwZ(4^8=5^MA-LUb=e!#Q@c7()Pb}uCH!!hE&0sE#DXMiu1 zVwS`_%4RvcP3g$a?n3Dx5b`)X3*Zsy$gp219WTdpKhk0CMr=xlb-DDcDW>>3-jXH( zGv`1zd`CHDdYSKdO^$i~4S)xvqk#QF>0p7(p^7H4x1^&0_(I$9b&U0Ii1Prki}Rq@ z5u5d~@dot3#sVwtKdu!(4&7PEJ@N>lMSQ2-E_7L{6-<@Ir}U zugs&KdA4`}_M#YiCB%-of0fU8mMtt{6@Aq@^De-=P_mznS%1K^W}&wvyO^}TP@Z3o zN&gLiM`R*TiC-uaGzT1Y8GB1<%cJLWoEJ(5yJH@;v-Ubhh@D}-kk}u`UI2n(!M-Wk z8Q=>g`|H>W*pTckuUM$!b<)8C+4wC>3g7mt*fx#BkH2okFnD-Z{W@y1O4cjumws{M z5T{LV0dL>lypZ@LC=S)!fWNDp+o)WpskAaY#heXPw&loX#f75uaPAm{TW@TA#6R;v z;2~BRM@28>!_&EVVB)c@5(e-W>ch*of?%FUEdwq|em;tKp|r5CHmtY-i2HY*xEm6Y z4D*GOF*$Y+pj$Dms`1wSPQk`pY+6)0TSu8bj%|brcw3bD5qtXhvO>zli{!)02$h)H zMo>SJgy=#^W>?A)&KBC#732!y>*QDqY{R+-48}FjO_?wbcwT4SNYY$qG7Z2-Xl~$e zA@Lc^adbc|;%|z#0r+)t&UTxp`cugHrm$pnyii7-j(r4#J5L0Th(;bbyig)A?H+Z^ z5N`@X2J=GxQ~q;wJ&FU5oBX#1kS~-3GBb~+!gFl zHrG|nJU+ZhS93b~LK5E{n+dp)4DpB*o4{Wu(BFq+N1+0KQ$9?HFBA~A+Z-xbc(a@uw#p%;c2{*g(7fLu&`5vV#Kpv72YnI?b z8Tp2l%K!E+|NO82@|QpU^4I?o*4cQcDk$y0{e`u)+`2|Ti}}NC8L_5Eual7*y?>Wd zt`4{Eb&vvvlm+OAFMr~?*i{{*=ZzCBoabw}jqjm-Ko04IIe4&hde#T2X$VhQ8 zbyG%)6|oB?uZgxi&u3CZKe68CACN93gd|2iq5U+yZ**d*T+m;&Yt#pFS+$3yaB+HO-e z^4RosX8OUXkH;C>hv&A5n@2A$BrazvTsoLrvzvC>ZuVYC=NGM9k3eLYhZN6lv|pBS zJ>FE%kAc4}8z#&bipfOL!vk|Ml(MOVdA{>P+4vBVdH}WN!M4eqM<*|&?KfN}9Io%1 z=WK@rJ41h+N1^TPD$bbDZ<~?~@^v!uBt3O0U>4>fGH1EIkjxZ44l3ZbG-p7sljbMl z;8H+y;BH$WvJ<>eAUJ~La)KtzL$Z;a-Z!p(Y60$kzj0p3&tTV8+9Em3`V8AOhn8q|FNN|!{ozpy zC1ZJ?pDF$L%?t`-qJqk>w!|j}lTwG*;@vT^GE>8AuVj;V1<`%hirdT?5jV zrspC3xbDxIG~Jbhmby$jo|FU5^>mDV9;%VfyjaN$Hz_i8Z!enHh3q~Hi9i*9-j6Vt zvM3qe<@G#cP~SKxSC}$A>DvStGSEzJvO1rIH<&kShqr*-0xR|G_v@ae*Lwi^iR}Aw zbPLvP0^3lZr|`{ja8@voN_^=i$VH?OW!uk&PrRwX<R1>N<*6P;o4B`MJM;h!T_M z`UzxT2%5rLS9I`xbgy|8aM}=LxlJ%Efr9;k1>_+4?wA3Pdwn4X$O(q@c0-X3oCUOd z?H~avy|%KDA@GjGuN>Lvr78(HsfdwC&A)b!aEBmc?_*STf)O8#tkaJzTs;=D(j)7+ zr9`+b@X~M2wA%~((~tX9n<-Qv*((axfEuYsR_#>|5HK@7aF({+(~}A05K*z*xb{7D zP8F>ClF=-{C0v~J><%g%0PeM*umE?I+1-0PJ>b$WUW|8<3!Vn9SKuvxD}seAeoMGe zC=7eM@nN6^xaDV@T1X#|IC);dzz2mEfv^9)f7ozD<+z~Fu`yVf64zKcA!(K}yu*K_tZR=jThNGK-vqgoRVM0dIcFR2-T6 zK9H-g`fRxW%vwe{ZnziDr^GQ47(40LFdU#?=`JpTT(6H%GGtriTJ&}$4)mtmm(t@) z1-V&ng&dh1iRqi?GiJFxi(ap9R`Kq}gDkLwQVp{Iv!>-N5e+Kn+nw4%T8p;;Vj9-MZ-yR>p z#*jp7zs4?@Lg2bTxqM49hu=!rMQaEv-%rGj!^wDqnMA^m%QcMmOjxb(mq-XqT%~+e$Zt21k51B9+f7?A4dk-M=qZ!zN{)yYe@!`85eGEAG?L2u!$Pd5Nq*@r5A>*QKh2TObazEVuEYlOG zGYbTlZwX=`A-Lnk{Ba9hfJH;KFsXb^dO~{{0w9|ih-pMM7tlH!L_=XA(s)mDP$D?f ziQI$W6-g#Wpfc+ZJaNOF>8^@}3|3(Ohz{{bAAaqOA;7ZNNCZqUSwg0)nh@r7uQ?d# zw2ffMgd&+fEUhW_R>l==u`hTb^zAV4MsSl#4Ma|iB~z+JnsCqW$U*#u6Wrt*TQAfWHGCbHWAY;_!%llc=p!Yxug>aPDuBi9PHnqC>bd4MQYC5Ee}P_f$))k_<8CgYTrlE z!aOQ-yq`?Slgc7u2cq7u1j z)x#F+7a|sPhY}$FGGoZ37n24cL!RifG0NT-H+b5}boXj&6`cM2hX2C)VY5P(7yR>{ zo8PvfC4Q%!1jV|JjJ6_b1)_=|$yQO7_Y#T5K&|x9WuQisMwN_+oq_}flITujp!Rq( zqecO3k@a(tD7j4s!!l8dp?0H$l$D98-&`Lj9Zh~v391e^$Wqo`VmH#R=|rTh#EOax z^AE%Y?ojRCZP>36q-29*dXc4*E=46&w$$3c1Nb!w$pz^3!kEg&$cSRt2`rxK>MiJn zREe1{Xifc0sd{h{R0y#a_lcjay!?k&7XbznjF{u4qkzK*nUcnsShx@0LLR6i#WXQ= zywcCRZ_hLVW5x>10 zuwoysirNanCiNE8%o6*^kW`wbv=X{n972RL*CI@#KF&RKYg;-i+j0OsqWyjJ$gPXyNX&bxrjJ1g^RbKVl!r^XgN)vw z_SHh(+Ro5GyQx5^{@Q``PsvLM!>T|*%s~x}GA!LHP+Zzau|QFDMr1ef+W0n%3p+fu zc=8V#AkZcl32Cs|$OFEQ0fruWP3q7FW~#psVNJA5 zm@J5(?K_7p8%(}f`38blqB_z?N&$>o_$!1&J{<%H@LP)OgemlT7SiMRwj$49q^ua> z^5BI^atA;DIoHn+Ps;8DXd3fiODTz#CgkyBIOThE?u6JxmslgsPv99V0Y#m7l%9en zRe(7eR$MLfRY&IxK9DHk{`kFogVQr~uWeSwWh-e2NgvI1713v{L9>)r&{rqlt#vOX z4YWcjA$^eRnLsgTz>|~$a0)qvkNbwDTr**I_8!6#28F2OrU{(r>-3L_KQgKLr`3KB zILtre;{YbC8y zUpo|ktq8vSY^Hbk2_JyiaF@RMlBo9lPP#tWExIM-Tz6SJ7n4V`2c58O=ChRszS!2&PZ0D6sr623F6|z-uNxwWCa74gT`9U!)D`W=XK% zj`=Dk$~3S?V2R7}BiWVF+BV?TsJuZ~O*h?Xi*B-V{gbsCuK!ivLr{)aP1?yX4qRXV zs2fK*QJq+!#*x-zh5~Q`&l(dUM)H$cHyQe^aa{jv{2nrGwGd>6VD2of>mPOFNVB!0 zlOs5;VLOInWZP+!9`{~#Kcgf;fdu6ybS!5Cnj=BHG_w2&T9U1b>ZirO&Rr_{o)q%4 z-A$rc{OAF7V~J(h(+MYp1hYw_TFOsdIM|N>%T2S3g@3Ap3f`4eKYaOI>_(V4VXZX7 zmHxPsVGT=n++5A426FKz;=WJtm?5y`s~PC+W`qY+v5 zDASj+cbkjGCZifTbt6S=F>E7R;nQ%M7$vEc%p`>(SgH6_6Mt#aG&t#dB*Td|v6Slb z(ToRoeDt2|g|tWr)gV*|vFLRa$$u}T;Y!M_5l_{f<6}Zz{KU{Bx(%SoOqg3-hwAx(?grV(?+cNW$ixEUk+~!~knn|xv z?pfrG?;-1ZQR<=}!|->)N7(X@v~~Cobsw3^Sz>Q(xG^k8MHlBp;VOg-LDtBwlNNOq~4I(K#4A4@8br?y$s3sQ4h+Eq<*VSPp1K$}*CJ7bD zBA)7%V>P1Qw7dj5{1dB7G!sacC>E?%^7vP}u#|7f8EJ*4wBKZ=^;JHJ?LVrvQbH5Y zR@9E-85Qw7UR19;=90R2=AX(DOpan;w7nVA3XBa!o7Kjv77;P7G)RnH3`XVH!VC2c zYB@m!Vi~=flOP&lQh@TtM8BE-iaVI1H`H@(Wg%SyGmLJqV4<~J!rK6t775v_AVi|y z&OD{8DHU>-77$O3Jv?$nlz(F2*xd0Wi{k+zEGrwXvC{wrHQ)lu=+N`|bq{cWUN2Ux zx{$QXSTs>*koE=zbQwQ*H?OZjw4GlQdlQAp3TckIhlNGByg3ZL{tkW!7dMJO~a3%^*_W-yf|^TI-= zH)zKJD@>{TJT6IK9h=&t7IhAc5rbgQxwG_<^)FB#5VpzH@wk)`m8yu0hDs@ZnZPFS4W zAoWEp%d7gLfm7Ny0i8U`5$D8$=Z1SK72|}cb<>)w(>6@fhuR4>67^OogGZZbeiNxN z6<12eBJ9_{d#g5y&xNWAtHou1r7xb3j$ei+YfQ!C)oWMnl1lHzD@oJuUhsec7TI4KqS8Aa0KbTVF zY}K#%+cL2imL^G!)R%x^B^d|Dvd#@h6USOoiGEjXbVzDTEng&qBfUZ$4MvV2nW)9g z;-;)>z7>6Cx{+*!p7arMCHmeEOcN_nm`$T&VQIjY3~T%%L+!9h&3I!sJu(M45S|Wg&QbDHiueue^ zN|>Sr>O*cxWoN4=so$E74Cv|X2h(x%#P?uB9?2O|B2H&egjvNoF!If?pRUVNHh|9t zx#n6!^BBgptZ3vEy3&r>N& z8)W7k49mK(7KKm^vZS!bPl~sxLyVHMxJc3mt_(*uECe^Ek4UMMQrMV=BtDlF+z&;Pz@m;ARn>P|s+yYAt+bH7RAv^|O?{knqt&yZA0RL1jXKKgzo@w6j z!#9#?6GLF28M-}yV|N2C*TRDpA%ItP13bA7v=~Av8HCoP@`NC>GtqjVM!lE~Lf^Dx@Yh>QV+S6||Ptzc#(ZNh-w{(Rpr{sVL17(*3~4uLA)1NL0Xq0Ez?3@Mn=P zqqxv=oJpk_XzhZ!?F}fRDf?W^wW@$3g%_e05JCh=l;`r|+BM2+=$Qt^X!s8ZvYz|H z`y&PX0Gn<^geH!098R~3G?}0PfY8vpb_9-W8tmhU$&J20pr{B_H5CoT<2TYWaAWR) zh7BcTmG+cE(Z(?jqPUQXun=6I-a-x-a?`(s0y@ZHSwE< zoX(z~dnsgPTt&c~QGa%N4Pn@uyRCWXz>s}5^(1IW5rwWbk>4v{LJw6=k7evl6wxG9 zny8Ulx&+pbVt;=HF)rkkP9|4rpeJC__9M=ofos{g0H>p-tj@07Mh{7{D8e7vW_&(; z)IPjgp~QB6Ec*vNYa|J;(Jy>9#ZGNGnrT(E6!MhXFeX+Y(kXfz(Q*;tVR9IAWm6ZQ zv&Bj7bFeXiUnEGS+;I20e}om2&A6chMu%3;FF_H=C@&NB5QRN*@;}oFKSz<2J|eEga{V&{krToL(nb{tCcl*8 zm^-dNnN$I$keIz@w2)s$plzob!A9WGaWA^N#q{@4^ms#&Ym59wrXNWA+=hmBVJDM1 zik@27Ow22{FWg0>5hX5Sf)~*#ejw4Pkxdn+xEH4C7SRT6WIuWe3&#tLfqS%Zfse>E z^^_V`6HX3wdAA`dXn&4mT zLW^Sf5$*vnNsUOqawR4>$jbIU3+rn| zr1ygu3N-eT)$nD9YIRBk^3YpFfXUu5LE9GQPW+4Ml)UJo-2nu<7f)*yq@aigq^dx& zL`<_dua<*A#;F2Q9-SnlvbK^^yr}9FDiO;BZ3`)mM4^H*U@hFZhZ%Ib(rHAgevlg? zUYMtOCDTZr6ncn#z^0p_)OU`c7{eY4Hd1L484iR}tUF+9sQ&E>YRyONSr^F}Hu8J5 z`85+j*tM2aLKtc`6dH7UH{D05jZIA12ub+~VqqdxcQZhLeP8ls-r#>B!6%bQQv5LS6StC90f6=~L$Qu~z08r3=15M~(i(82wLp-oi)#Gex4Yd> z1fqK2c!V>8V|3i02FtN16uhZLt|b-Up$FzLM>;68i6Deh4OKpfkl1}~68xBi8pJQE zzq*3d3aK}VpmyU;q*rksua7XQlN86hDlr|zQ1b)~70@nV4VBuBUrMRg4q_NYhT1&@ z#>U z%JU;hmc5T;WoyQ9#5@p(LU)Y>0AEtXNGcg+kk>gwe8Nf(DYS99E0BuGD+&RqBSjPn z3I-RBrk2zKHmYx+InR+)T%?Z9-UNcEfq2{2gzq5{Cek1g zCPqSj{KZA8ejQ1zn5fs5nAD;SL6r}SvgnY3B1>s(JW@E-COdPtiHiYn+&PsF8k9;m znEsgG3R!!Mh$K^*{J5sf=@%T4R2pCVlA2S-1vX4ZHjYV?N~Wv4o*Q{zjJY2Zm2 zn@MWD`vN(ba%f@zjFJjDjCCM~J9@bgOs@?y7vS$rQNHsSS450HpPsIY6Bl+BHL{(| zpAbje0nA!JnMN^HeWFl86hnHyHn4@nLR3aSIF(GKO3di5G}5o`!~u<)6g4S{%PmkL z+f++L8ggJXnD*0Hct$b=6ciK)dHF*$#Dd)NJ*`%1Oc{$uNtItmu2r9%;eRbMFXh%|t8*E{`@G zjX1qeA;jyfD*heK!!CwQMlo#7)?0e%z+fV5<_DlEL4ZzNxSfZ>Pmh>_AudffYxoZW zl}!|hwDIzA8Xr$HxZa>rnT(-h)ez_w6R$49@M}=?R;$EzTn3Q}rgd8t2T)}Gh1p($Jzv-b@*R@-kg9N+s?qR2(?<7XQ(PK@@31V{%bM5mm3C{#JdUyCDe!(a|i!82(~<4ikI{J~yqBZw)Yx=$aO!prJfGm}=- zlGVGRJPVH7=;1HfDJRfFWn~xr48&gi3iJSsaX_+Csyvi$a&#*Gg|S_l0#FFI!$C_^ z3nifP*|=ba{LqScv)ieJcvCNaXcP*jvjZ%7SpHCueH1REUX(D%nSOGSaS>4F=gBEa zkci`LGjkDwE`J}43?&yNlpHQOF(nwQiRn!Qm(U1)5SiVhP&skLm#S-yeT#>coN9=i?5knz3pHy> zoE0Y4;Uo_t3*2>F%3q;hR5MuX1UN=8L)MeaQ?ec$G^fm^dL@N}Eki@{NS%(;FY2GD z6XZ9f3Z8fUMC}P@&~O%7?bTV7eH8Iu)JoN@%eHiu1q7XVO&IEyT1nS+L$d2(l9jymz5#gCKORLts0tkb1a9bztff!`zd%cRgn^Uv#p|qMrohK zLu0y&sjATnU&72V-j}ck$3pYNpBd8p8#OWkGzWrOaFde3E=CmBu0rDtTGB!PXz5U% zoGH~Jsq#5LrAN~++!T1-P9G?Ic7}mON;G8J43TVj3Q{x@q==bOQ*p8JwIv-y5#s745|ZiEe>HfBt)l#o-Bm(EaNuVmz{|fvC?<~ff^f(|`i-Gc zV?Vse=|qvTrIU;Jd+6OtoeL`EFMlhT)~?so zjNvE1sA@9^&e1;&m{bUclNAhhhjKFdxGAKR0cfftGvp%pV80eJcIM?@Sdd^4jG%Kz zM3v=+G=usMjf#xlVoJqTR{J%*35~b3@HB$7=JpYUzlA#_{nc5!<~qUZb^=m3-xVMy zFitRFQ53Mzn4zpiJ!*+@OG}!rOvG~)Dk0-lj+j#F4f{COm0^OJFmF!cLl&M&rZ_6f z6L>2uRA_fJ!sfRyvY=Tr+_ygE4^Fkg)TwAxdKeH4YxFQ>UchSr3wlN{qdpr|aNX_U zf0B#_4DtBdw$&&jQx_W;Mula>g$P!|56G*3+*H!$2yVcTeF@B|wo0jR$FRA$)_;tZ0&o&uafNm-mFm5-uM=h%=0GG@JZi&Z5EcPk;H-7z!#b22g%0|{)X zH0f5~Tr4|?oeteGl`C>4VpSAMiyAwuJC7a}hJ6=N@h%t!ECWTTE#;G7_OZj>(q$#}+QUwD zXT~sy52?@`C|{_N)Nv0Lc0u#7_C#6K>bIFEqemBo&ZuVK!acS$ih%4vG>|E+!4;ezH|6>gVD;cU^r>jQVhbK zGx20IFxYg=CQCN#gi*r5R~CosWIFNQbgyugx?i_EZPJ*R`HQFkBb&NoLD=Wce6gLq zahi&U>QgATBvOYlI~d|4+0#cv$!=j{#X>KBs!yph`#j(qI3(tI zq$SqTxjJ%$nM!N#5ZK4*9%Y{VKJ7Bx52zpktQS8dl-!h8ZxIxkAh{AUyUByv5G}yj2N@^ z_tJ=#h9{wt9c9uIxnUM`uKL-og1b*->I5L@nyx_9-aZ7R)FElFO6+DiFj;sWN8Kjh zFCU(X*fao5cbNS&dFm{p!5u1@(D_)3z&mOPiYk#Zhrt%;%RT-~%I2AbVmXBMM&d9r z@wvon?A8;Zl4a;*8N9~9qg*oZ^b~1GRlc5VnaTVP$3L0x7@Bt`P z0~&}Vq$Y%hpm*2zo7ukDzS%K9r>OR-?#y!cvwbgH_kUgN;vTt`b$X@glfpr8+}dQ+ z6ZgGbsasDd<6bx?C!XILCEFflx|uH6aEfy7kTjq+9XuR6j|kQabs!98U4)&wFoa<* zmx4S8Q5vQ-r^%QOPYD`_zHl^;aR6z35Hfthx)`dSXPyHEi^#9*i;=UPV3sJf2vrKt z&>B#GpGXwuVKnRy*7iUh5lCBr5P;f2)8>6&E&_d)&7OBUEUbyL6)`IWOhX* zpd4QAxtuS023H)Ax948Gt^}Sfut=`e(~(=$ZWYX`c-)wf3xLH-Sp&A`o&bbI;;HZ) zp1&j@olCDyAp)*ZMQQ}D(rPmA?=o-sta#^3E??pwVM@my*%Vg_8}?AI{CVsGWr#>P?mc~G1?0A1aD@{g z%kmiHZEDP(hQzpo^jp#Z{}HrIE1*`gfqmI4pgbqri?n=XpJ0T$7`~&7dbNZsoVHe| zbQ^+%I|>0*EUVnTY}j2~Uq@jjP+XcGJnarLK*-cQeHIr#OX!ilsDeHmOCFc3;YtHp z$SfSq{kg2@Zo6J+4|z(77Unpvr6zy8L^mgw&@EEKfF(?r-^`XW*MPpWh+;}AkKFB2 zKU$4L6VYO1%4mVSS<;Z6wvK_}s>?vc?+ZMXWi7#jbl zX?ETP=Ej9*2|e3TvyRptnZK$>fA)dZOPpi=U1)vnYjSNBLn5hfEjN1f1r(a7?GBJ& zeuY3wGM)+Ct6;HyPzIU1fPxLICZ-dvY8$AG_fkAh|Da7OU1C&Yn79z&ZPwLa2Qe|C zB^H88QhYN{S}EsclsTNGP`d5!an&~z77mv1$}go2lqc(CbS6r}P0pSsOCl2)&QmB$ zeWq|*$mUF0wM6q}*91heoc)cEUIhQEklLwdPhR@Dr9xt&=1>o^Pz*Vr2xOvD$4O8G>v z+A_%lfpHXmA-N{B)z+P_v{FDPXF|0?U%Fcv8G{qe&xbk@Lr7V3Q*Wk&FsJX^;?^U1 z{99awemywor80+sIVBz1Kw{9Oba%cNhEp2^Yx`ap*gW79G8hp{LsPX6*>fV-rkMoT z9Wi+`Uq(6vF`7j(G}#j<%Wy=5&MBqOusvtr&{R!W;@LO~V;a1#36Xgbbv(}^N`hBc z$h;){Pxq9O2YJoq*%tz_O;ndfC3sL8tXCB*=j50YNy|ajR`hyK7C~n7P9-`>4X31# zVY4t`W8TV0{s%hPrAulLjuMI@I%zX#YVL~DP>1v=ab!O$Utur0B~oON44Sv=;%%*X z%7Lt7=Ik=pQVt40Rlb63ivfN%8ckXzp)O4`x@*25rX1Td69ba2Tttt}Qe;m9rH-@e z#_p&ry*%U=!*dHw-__(?B!m1LLqZu>BCXAoEt&v@!z`y26hRY1j*U^B7gR6uOk>B# zF^M=?Q@RY{O7WCc6rKC1+ewv(kEu!fMbpHEjmj!~gVK1V+rJ$jG*@l`rw>GRmW>OI zqV2=sugbWxP`@}KZo<$6b)%3@C!GLz6NOwtFBzTZp)QXJ9=@iFu{IYPv=Z2>V)Yhh z4u-x}p|b`;!1@LHM(zTP(CZ-tkCCT*xiYiL5tA3iVS@++^IoL%k%PJ_6P7TxK_bjE|&Cao=mqZ@8SktGD$UXrUG`zsa@|d$U%#kR28U${gF+IE( zT`56KVBv%VnW!hdTTgaT$uvB{JB00!orV~uU3kZOKDL@*vAAWk)(}I2_{C|((@`@p zEPWyAAWn@SP(qfE7|!9@nT@XGC#W;~3AhK2B6?BPD{|7Np0#mh%ufC{PtNNrEWG+r zITmVqg(}*4GD7f;uT;LZxRd8nUFk$i-pqsCbDdRb}?P{X)4bMb2k>Mk-U! z^(^WuIWYRybS6&{Tb{IUl0()wJyW#DP}Wc=iDe%pY~if;x{4B33QMsi+knbP`eKW* zS|(r#K-O4e7j{mPH^#tz?tRr|C|lJWT$QHaET{$G^_SKqsRbv~cgd>mzZ&jld~#Po zs^=wf%8a!tM4XseiFw1|1)f=UfJ|C=-p6*;c<!RvGNWagc1jvR5ZvoVCN@BA8nVEKrh47U(LVbIZ;aFiB${hJ$&FG@pxp zb7E-JZlGlyn7)$uq-NEU6f{h|#~G#~)v>UGWiUQ@i>SSb@j{=x3_!H3cHN@hEsdR| zP@elNl=sbKYe7bngx0*+KhsE)r2(>1=jHeCfRBP}z=3om9p{DAw-gzvQ|?w? zln&R_a+k6#S0Oz-s4+3mu__X>SK7$e=g3ooXKIr-Kr&BaT9{t$qB^|U zp2VwHdnOT1775K@ohY&#OQ8`&m|0|P^?Mp+HToe<8O>Mi{+dI&4s5J1am&TbhSt+R zV6h(aKaRp7)U|i$4_urV)Cn515O(F_Jf0^&AAlqsV0mC;(?;)5lI7BoXIoh85@RCa zj`;{~UWQ{jUA!PMkCCpBQz$c;tk^sy6fHpg(s%^so7YA_u>pvnAI zNOx1hBsdiQ4-`_0_)KCCR%)}-vY*)(9e!KnpI(NXGVcXk%WGVkXGjOkiDpC$OWpU+2F1vD2KLc=QjkpTgQUVmGpr?z$ z-{=S|kCEm|m%`$u*@wYAJqFOy9+Md03zZ+;u>()>4uR>X%l^a?ZLN+1gjJS?JEn}f zFTF5V^j#d&T->b~J`tC8Z`QhyZn^hBTw~rk3V%gfVO@C!Rp%k+m2bQhWS6?%3Dt#c zUc6b)yO+r;0{&IW%tf*di3k?ub_EzK}05<}-#R8e@t})is+xm!^k< zXqH3{_-eFGDP7LnRa=W}3$-%1;8%(nI=05;33`o|Cw!%pta>$TP})n`sMcPpKk&IL#uvdm$~E5)MaXeKR*rr1e&Y#dXkTE<=PI96XwPf{OJ7pXoSPwxlT<9Um?EYp5n z*)Vw##{d;ecgdM=f^;>ya_Tq4RiWM=(V4vR6rdoustj7sn@SPUGkN=b$YR#gQK5sK z`&jxCj<%#|n=ZyQCZ=3pHz90td2>ep2y5b;|GH z<*pBCQt4j5d?kM_@fW8no&xox-yaxAonY8*^FcE7acIzuzZK+Bn0vtJnGpX~h%7 zL9ThzjjaS7J0Ptb^BAt7h8ZV58Fua8YjXsJZ?6-#i`^#mEfD{s4+kl1eJ8JYISO3O z>Jn658I4YZoN>-I$br(iR! zQ)R4Q%=ZP_z7V9yRsv!<=?hQ3(3WB`=qOjbIgHMeUsIP_k|u)SY*oI?@qodyEIGUO z=ZRyMpH*)!nN9O9h&vzq2Z(!{b5O}=;xu<|c14w2Sszk`a~3x?u}obRjEPCc{4ETq zcEvvHY-P+9=Y~Ify)$eYsnz|Qey2@+{Wdmdsd3#2X)-8(Qf+}xpO3<{=8nj->3kzk z4FqCk>{?nT^3~iLQhdVzPiE+nb)mpkTe;qF7uVkas7C%?Q)FqWz zb>@409YHyZ>jzO>oQ#UYF`=Q;L3FON8c64w+SPZH8kGH0s=&^*FiH`X?<5CCCJY=n zxbmx#9<^r|oyD#&4jY_upi(QFJ@*e}l6)Q^ou`hMt(`V7xn=cP2M^qgLdZzf+Z=rA z1lMmD&Ja^2J?=prp2n7KX?rOJ)eE;Wk*{~+lc8GC#S=FRmEMgWVlK1KUH-WZ##V05kV&^lE77+$$bzByy+~Ly3bKz3 zHSd_qY)wI`{AlmJRH}T_uh@V^_4J*ZHz@1V_Waa9s`AQY<@zYb_x?$GJynaBu$#gK`!k^Eq>r6?j;ewo2`J@>bHf1WpN9(b8k0@4YW%#|uO+<23SacICcCLa?(w!QRI zd4Kkv4S2bUZ0NzpM3$L4)C!2y2P#c1Sddq)8mWeHg*Dittnoo2BhM4wKZL)^MHi0M z_=5j_L0aWyFGdBGKnj-4YMH~VaqM+W;Jf$a@kHW3L9y4*h{ipECNb-JFKM(~X+C{S zFTgW>JqML1QtX#9#mi&R{k!E3AkkaacqL9LGxi$~^_s+1X3>p;Xq)vrMd~?Iraa^N ziFeXP|qnK+=(R$j4zkQ6W@B7Qh2PFAKxIRv{}gr==c z`ckI22u#XZ+XMtcay3E7zCL{M4F$>sGeSt@YHiv{v7-VBlV7~vQxKpoqSe4N_^Hg6 z&BHiRm}eq;F0M4@I!6?Q$ZI~P(}kW{y3MR)hf+@@H^&o@RL&z1!u@G^f_;O$R7U$U zVldCi;n2rH9}Ropk3Q=F95*sn6C}AY2)DRtKI zroDYWbH;`#R-TDGGqMtytDV3yViTT2lyYDtgUZ)t<%d{bB6iKn`Y4-xj4O~LA<_H_ zVXfq&IOo90Z2E)O5OeTLn+QGWWMx3PmQ&zOeba!yVIWaTeo>E}r3L;!+X}$E)b8>m zF(svisYNonZ&7?Y6Wh5Q| zM|{D^a=0_>Yryz}WuAh2iJB(8m#3*SZ8j3YlN)vK}^Va&t??H19rax)A;?kO?Ogrx}Q=jJer zv|6mSl#-OM7MHZAuF1NXK>cQZm56s5jmY$@%f2kLA?zWU3pDT`qO!lxob6`{sw%3z zh@y-+%1z^?Swg2;k@k%`DXB~*o10=y=P#l0$490V8sG6Qi=}L(N&ZJzSj4=OnE8r# zEYVV%OC&f3QD&%mwhYHt5y~0PGvq?k}mu+6bk=!nK$+pPX zt`q}^mpmRBcUg-poXf}YvKIM77Zi3rl8IHG^6yIAnO{yOt3X;0`&cqBgt05wq4Jn~ zg3ulaOTQ4zS#P7bT#0hWwnA7si|ArDza|ct<{B1^T>6n~0oKypRLcKZT;@d%%2thn zcx9=&hyvhe2in$}9=JF~=>u&E1y~Wk1un2la9Z2432)H()@xfzOsN(t2b*9MTi)|6 zWq-N3fF+#X?Tc>lN}wnLz%c1_*&C8@O;9f0adfm+IPe9+{OLLOwyUp5a70oUTx*H? zuD;^nrSd)7*7{u*W+UP#k`^_mB|z;XAsDIl@u|Xvv}P_aA&aS-Ns)MHMbVoWI42*s zZSiI>3-2f7?`dO$5@RzzXPYzGA*tpZujM_E`T%@hSpT=JgPtp$aXn=Q{Xt5u^2n+mvD<-Tw!X5GOo;fIfBQb2#|dOcBf34u z2t5r*8!+`&JgYBs<+C{}1^`+R*PKgxJId6~q!3!yf`7Hvqn(y%YNK+gJSnj;Li3`S zMDt}EQehG>NgwTej3vSu^*(hR zbA(K|@G<&NQSKS0%{x0GlMr}!Xh}yGS0E{Z$%<&i8K*cz#=u{egn%l-N~a6CxleBp zi0p!_!m^8^$|;}8FRn!`eV5GtE)^}0NnZ5l4;ieg5|!F1S&37q$WoEfbENR%V5WRE zSa7n$kn*&>)LJ*vp>@r(`fkuHIi{GG=gWSAEerJgvaXln&4l6jHNq+nf%Tk2Q32pFDX-gf18-{Lu#nV<}C<|E%E;7k1lL^2;@ z!DdDa`Fd3&J-Y5v3efiZz%;*SVgSql-w{OjmpG*OrSMh~9lMD#9~w^92&Bf%gjf+s zo1y^RADk9PiaHm8hzVM)D!a@yPvn&j*^FK0wy?r0d$u`5 zA9Rpuiox_RP$npwQnj@zm2oegpREBatGKSq9}dCD&Xsu)Pl-!5$jcJWQ8puCrZw zdN)LinW8bkg#}TPsjh-FlgdMfMuEnn@TpnX{1y+#FIi@|qQ0 ziYR0;j+0$QI|t zOeRGz#ne_a?yRNgSg{QI3T6kDpJtxEnb+fzLLYP@*HgV2S%8}9j45=fk7%mUp4 z1@Fk)6^GK@dg9$$_ma>_e&+SgsKFpmPENNj+_t?$jg6Dz1~|GpG*B|jwj&dQYRO() zR{xvF%47f2yXTbS?0wgUAt{!xjFL6kF=y9wY}PuQn4w@nqMi&Cv?vR3 z4mnn)m#d1CR`m)G)0q;N4>w8+;`QQ_kS+jCJ;b3=m-*RZGZG^cqH4QQ2dT@L1}Mv4 zlh-fH3id=~UW$%&5J9UTrRXOu#; zv8{RJU(7J1aIa`6)Ni7lPq=`I?W&i{HyaQrJcd99`b+Ql6MDcC2{gg()T3=d4pXwt3c7~17K zy`53%U;;rtskL9cnFq$q6#Kwn$jnM?zfs4=pm}}9vKpOMWq+CT}8KkI>E+zGaUi3Il4cEc{%&DyRN0&1-=%bV#I~@s0`C7##4{zq0rGcNK0uesRIanW)SDR9rsWJw1tF3(AzE=F(9DWUol(4wDUl&kmdy@dbktKDc{d9@#Q*=-~qTtw7w zqwxNmGC{o2_uDkuZtef5>VHFw7mOx);AZKdF61Z-!TOf30t_jCLwuKS$*4OoD3Le1)*jPti@bV>oKt4q zzUC!V%in;19d+fM`Sbdv%u|$ynL1I|pM%@LI_mP)p!NDCioSgeL$x~x5&f)>=K@EF zSw~@s=Qj$M>xZr=lzB@s)~^GQo77_Ct~T6T8eu=X)0l6avfzG%Rcs_i8euFup{Zfo zn1}j>S00w9bn+`Ox+Sn@q5+0^Cfa@RsuGrWJBrQyyM>CCi%MV}jVCF-e@-XTx(cRg zwD9C*LlYW{*sQ9*M59-H>}6We+tYZI<7*o8C$Anf=kYU+`*lVtp5MP*FV)_)r?Rul z%N@5zwLZ(WbDicS=y8zxKI!9<@|-w%7VP6tN$*l_MWRU0;XLMv)LH#1Cl}FK?P2NB zDiU?YfeVAUudy(!tHK&zzwtqZ$fIaaQ>nE2vf+tk?W~FF!-KeXCTh>gJg2kJj}p>-lWy5^?&b)z#|Q-K8C=K`fOpnm4=g0&odDhpGCDms4G&VwZ{8xU;7%Y zcUM2#ncd&E5=9T&T={b$S1&mW$$plr*?xO7ROo`wR&rknIs^V{7wTi^ZWciRtV z4?fdx~_ov6EZcc>(1_;dM^5QYWE-&|#@yz23%`N;V>m%lnqBdB=bw%2NU zUL3q`EJQA#D-#IR@b|Q$L@*STGk#u_!Ay%ns1!gkT~}tGrDym<1Bm_=AQ(uhW&3%K zyxr#CGTmCAqdQIaI&%$oQ!AaPP(ATkeNGg5F&(~=!^~ynoI%$pq=&jF&AJqZWa(Kp z$jX%bg)TuT!Ll8zX@E^;128;U z2TJzI))xaGE8MD-WN)3|0>uWpw40_O77(FxH?{t?$e`ig4>*gAZtJRO1<~@D6-lgJ zo0@miRIFrE7U9f?BdG-sBy@l8sTz=1Q`W&5UFXYAQ}KNogtcv(wAP{h0*MT_@ou$w zc)o`2-AP@MsGc2Q*l<{p^f{vl@ES#24AI8Lv?}YIJzN`=5yT9>WV*NUQ0sv61B0tx z`EJicm25e^RVSnE^?s$j`d_d!SL>0~&VnQZ*XI2p6Fr_XaTR-XTA24|g?2c>z$$WE%d zajV6O5^y-lcUmO$DPs+j0y^xL*z+%QR8-H*re$239GdxaX)>_K{cPzf1q!}MW7;lY z+CHtDr5)Baja)U!N#9Evl;`=V!}wW9_nxAhzX?kXZO#>)4}1hWh$0vtlxWJ|kfcNm zw|r!JO#YZ)r_TatzsuihW;3N>mI%RDpjAEu123+lThj)_PCOb#ZN8q% zG~1MdkwLq@BSgH-M;1gOqqimC<1vLZs=z`fVNQt`vL*uH?7ya0N>OG~I?aGTGw(oI zmZO=G;pb4d($-$gx7gI8IHEeW+C*whp!eMyQp6dyFt7-*Zjb2VG{a;G_t3`a8zfFw z!n|=|kq5@5yZIc~bnm56+H9u;q#SwoT5b4PWku?j?Wtz01g*VoNhgmf2&*MH3a@?f zoDY#lWS%*p(&8CUEx0VZje41ck(q^u;VmPp>?7z9APLB?*B?&eIs*uvfE*<%G%R9VxzvhScJ^dCL!m+MF};i zf?~+uGki(?Hq6~iv!HCE23;D<@|w-8$Ha|O=mLMFf32COSls+xdU3FNT0YsMflv4M z_Y?{cVG4ByW0kE7du~icDkxb@SFXIRw=H7Q?56eJl69mu9RzQ9rv8JBzzL_TsGpt7 zoM-U11N-u8N1_vF_pr8q8Brk_ANu8do`@jIoZ!F;!H($=_oI83n5RF zx=kd)-Y;YkLb?G8lT{^KihK52MMg8jmd2?qyao&Ldwc*Krl(Gqu3?eFT|cGMi!#T7 z3g=>eS1HZ8dlmYdBGdf0(+UqC20>4BLsda$uikB(Txcp?eS z*4)K2BM+365%Nqnlvj(>;=YAnOd>Vh6Idea8h4tdL2IM&QbIjhikk(O;HLR|ULlVo zWO~oRG}6KT>^x75$g(XY3d7PjSJb3VaoB{1N0uQPd3Gc{fk3pd(Q^QR)*n?SHdRhu zoDRmKfvgS|3P1zVmHl0FHYTfto@1E3pT|Le925bI1?tj`MZB`5gJb8rm3%7;(|9d> zPGL*Ise=j=BoqWV8YskUjReL-1lD9y7$JOV6b7=hTEIXm`I(PoaD5`ah6REPY=gim z-HuiQHT}6DknN-38IZ>DP6xdy+lu3v!T-55jmFipQXZN!X{VG8=guc6 zd1l`}kjdJd%;-5^FpFSiAx>SwW(&*^c~*qhi^9}2CG*`ems^`earL%=HL41uvodE-?Ma8)v zCIO6cs6bFK9-abrM%dHQcpT-4Up+m%UeE0-Y5v&n-(E|!d>3B3@C4`J2}7XlHejU z4K*W(Q`CGZ6|ZxlsH zz>6#;Q^7z+rENEqDc8eNGS)tuq&XpAk%u`qk-FD2ANOAHPEwcSm&Yx3)O!p5u{ujz z$XFMp@$kXbK!PbAE_l^WPGvK^ z?Q;kTNXD@<;8g3ulj{=7c-{h33XYdb8J9`Em@zjz>e1z^j#JTkp?90+YNZG2lZLh-$#CUj3dP;`|`f?cCtayDc{6Kx8w2 zkb7}==Lb{E-3*N=rHj~lBl<3d0*Yr#(^F`LoWdNX&sGTgHA+6{Tf${qYn5%WrO0WZ zXwm4~PU2nqhC>f~J-n9UDz9;0+OPJ)2=hy|I z^&#vO#DeAb!@Bb=pOaw)G7I=pYf3;~zb9>x^aDQT*X(5l_<(<_^3^w!v^e)H5LK#f zk|QipUZeU?{aI6<14kFti%sb8>AGH|3ZnM5*0fiSGBJ_!GmG&~}e z$K^J$J&l~pysszb&uZAy7?%#}$~EFyP*C5D7^+Ss!%O4u1&LcyUwD{}8%i~)NTlRY zi-6!dNOn>_Fb?|5LA@`g?EN!+y_hPx8i`dD5&e3XMqdiFG!pS}xTUP?tcM+!-( z-ZV<+z}nJgke%dL2~`tq_9fO%^o~Md_dEwd)Xx+iI7p4kI$JXJN6DwP%sEj>Yp>vQzGr9Dv|EisV@ zoJjnNx5zT+86lO@Dz)jPS5E+B*Eh=|6y`!?%u~0u+8qmFh&>Av$uLv7*3JW4uQCV0 zzw#NRHs!fbQ8+3M9t@3^2v$(|#X__ZmbBMP<#n^lz~ipVt94A=-7#5tsIEcw)F;01-DPxPR`mDLERfTmtpwzD&k z&h*VItMCx`RVhRtuaoN}v2xiQzqd3>IrECh2Fy^XDCW{_2=OeVcG31eycr$|(ZekQT^ z7D5rAp_o!fhrWmUW(xPjN?Q-8J)B99A@e zk+>~aAe6_v&qLkTQv@dP7G}vSH+{2 z1+^XmuSBKkI)G(;ip1eC$U#hLN?Ksxe|ih**&8BMRuRiErPO*!Ep}qc0QGtZn-S>6 zC;DW&-z=LbOQjgNDCMYFWN%BqMqUbm*&G)?C}LxCnDb(ii^G?J87$ST_?g@Zg`;9& zFQiGWh1oI zP)K;Pq+g_PSV`+y$m}Kb&dd!jw>s*A-RLUO*|MchtHW2@Jy_E8??sy#(M(*_m`$*) zuPB`+nA>!7&qJ}peA`7@n5NvJpiy?jvBy{Z*-$p_KhdNh8oO2iW2c6U(}6_y)24xs z9}RX~ceL{rVj@u=bj|@@<%eIgH1ND8M)Szw|Mp-1kN@^x|I6S1%fJ4w|MuVh{`>J79VtKJ3HK%t2hyxjW8p{Is@9CY) zBv5;f`lHOh)OxfXoe{;anN+a*puXLc==Tjl==@A2)SDL))9)HoI6bl1rIv5TMXokg zGO-o#tM4JcWdMs;&S-vlj_6&mgR${46tz5O7rTjp=K(49YZ4SzOA5>ae%E-_Y@ui} ztr40+2{OVOiL1p)Gw@b=DkL(fK@4D{?3Bp8kO(Wa79inaTz`8`N8%SyQ{lu27w&B; zFXl68@fE)LM}4*A3nrLApvifcTz@6;Dn5llDqhFM3j}MV27NV8WUwZ!Ye6T^T>OgL zNF(aAGWLR+>V4Wu2@?0!ibqgf$pwoKh6Oe*5$YzW(%l1Ynw=5F$B;eAbM-$NQqu;J zNhkqcgGF{+{7RAmR2(_Rqe;CAZ*mb0a!FUhGFu#qF78Zf7B=+eCdQNa<{l8dud*;8 z5DfO`^j0{1ej~tUTkl>CYOYfjd1S_1gIPU%E}srE8Wd95r4SfxRclNEup}l&Yoj=m z2tqCuSf|N*#$r`Pld_~(aC{JlCB}DDQ~f3;_eUK=+hrIFk@%IKY_0%tg#lfUN+L&e_V!lsRjRQsUK%abMFviLPA?QM7%EbrQ zAsi*nkVzm_V8+TxM0$c2Qq?;heKH*hj4xcdT@rhk(3PJ{Vr3TwY?qE3r_p3p0?rAgYMOP9eW!c7Q~>E1y~U z>%d7MnR=AmfW#JIHB+B&NtTi9MxOF!yW_XP0(Q|0>op&r4eOV@N9^4Q@DBj7W1}`N zE!*_q5?I#LoJrdBg z0c;q~HD!RN-4`&wP}YC9+&Q;Z7)^mM#N?kbHZehE_to|T#{TlV(~1aI7+9NEI0z2d zeKpvAKxX6L>7$>aD?<>^R`kff>_}U`T1lx@$+l_H@^Xvl)mgXcAy*Y*PG<0Os~-#R zljdz-lAa<)?f-Z7ZB>gezZ(ZM5{OmsUw^myn^k7N{A#)8_x)o#3EY)-t%q7({Ajc; zMf5`oY3Oz&8~yp8%*7Qw&vxg5$dduPq5LXmJHkU>GX1ARs?v2l(bZCPuHpRQdhlnaO-WQ~x|%t6-LZ1RRY#hJ z+iypwm&IynU*f?xKq*v&V%%>Ulox(eY0@jnab-Xrp~Vi8rbA*eM%$I_zTYE*RX4gj_HN2>+kk-1y7omNr2GEFLyB;WD`2He6_Bv(>KdIdplUc@}>IJqq*tul(_@_B>5zy1FA|2Utun!+C@7H6XN z?@>(3>E-fW;=fX_;qZ_W^#|c}Zpds;TK^>dn0F6ZwDc^ZrAL1qJ=YeI=Hun7=1mzq zU$oOd+xm|D=FUg=RF>y#KNV$!9L+OevGuFnD}V8zDNmmiaiE7ik?CMo&RM_e%Ux1g zes!bck3#@<`JhWG4}bH|X{(x^n?Z!!Q+Z}V5wz3WVa(}QJH6eVO1D&=ezl|W^wavFYcfy2JWZ#rx{;6En;-MIKCw#d;=(SOdHmIm z%=-uJRlMyjJN@!BnQ9;d`_qRw+4jDv+XCqIOlSs3|4aY79i8Q;+kq*+RepjiwcxB@ z3u5R|+b>TyKxM*gDwI1Z+?B9h8`^J&!r9Sa7x6b?q*ZUBvK`~wx|u%hXJ^te^Z56Q z3#f0Fe?6SRZo^|pIQ+CZ5Q4CCASv`;{O&x;sQNIBaA2avurGs| zV7W+Hh}#Oauju|3VaLWBpMi;a$YAgK$l_O|lr7}Wzdbvw+Elj^)z>0f5 zG42C2saZao&@a#wLOYW7(zzVXmXQ$hatbFYzdM_$XgsTL(eQ+Kev!oP^eyn%6!2Qe zuZg@ltVtS&-4%NpS9RODht{IDSCWpTg>5g`ln+rfs%34R6#k%=xuV#5eRUYL;&k)v zRg6sTkV)MzG}Giq{MD*s+D3HW>ATZnV812Ar+nrzYS9H*hKe(tsZEB-nl>caF!d~v z2io*TYS1!loB~shcTbs(=~`Shbm#-sMs^@93(C!W=@Zoi);s_*#= zbY)Bbqo(zA>1fRCgxoj1y|uu;qf85kZoyElK}$p5reKc1${DSiSyd*|^?(LjT(Zm= zWICpFt0^v*_R=~10^Sc0r;al1xc-~z6b)lqsVZ!-C(V#gS}^##43F%lTtk`&Kue^x z2LxGvcbgW$DT3+H)&L*Mf9KzQSZf(XVvWs07-|ajaI!l zW}kyfu->XNBKaha+6p~GS0YAd`^7wIRt1b;7);%uCLPw=iJ1n&Q)y2=YFc)`>fT95 zRTgdSIzPiSYdtcIWL{M7qw#=yMKgSr4GUno41ayWeu(yF>_;Ytw0uz)C~o%0od`?E zx#|CGs>Ia|!bVp{MvTQnvBlJS%%12nLt=r4wlz|3j%K?2mxUNJ1|)MRI<2z=fP(A% zI}rx>6vsPcW0%c+7JQeK9R$(vP-B8RJyHU zo-#at*@BeUIKN%QY{xaU5ke~q%$27@{(!ijj^-apoapRTMJumylBol2B+}FntFLO0 zf19r^pFYX+18MI{q}2Rn8&X~)3w*qJS%#V0F;4c;+QAa|X23#OcC(N9cyEKu1UzZm z+lGYLzidd#+vy`MF>CgPWhCfCTpGc7ES$3?>#%(B>^dI!_O9`#5FCn<5P><$V z?RYnzDfiXQn16YszA(<4-f&{A?_tL`REearv;>YUX6Z@ma#(4~1K-|GLz4%+oYEAj z%0_yLsQE|9*0PspPn$^HA{v=U=G=bvu1&48M;`9A?SLIj-&n$q8SI&28_JBqWc4;Y zC&)BeY{k*14vf}{HG9~?9ZJFNO)}i!XSFKx2V1BX$$|d2+R*5;SdHZJrde(l??y8 z#4C|kCd|r#2fkfBYK}O=I486Vw=Wd1d#GrJ@UCTbk`NL-K2UelK6^a3!wZh&JQ z)-#SGNx>I@GyunuZ@rRy@4Jd#(zVcap|Nuui;vbU6V z2yH@|Y0}ivr{a(v9?AdX~chl&1Gs?M9)@1y=8v-hNR7_IHy^Q2ieFvGPD9}QA{ zB(2M^;HaHEzM88=usf7?9uMbqNBzLP4PoAP@F=wLKv@ro7O;2Y*<*U02f>ne$ZV~E z%<0z)ot10hq6o|p73~d&I@5-PYDn+-bV6hAMX<+Zr@=V`$FBpbUZb#T5r_ z>b^1RjK|(nwjr|?vlL051>SN-%DeD?3A*?ZLpfuj8np>#2t3=eK4)pWQ>S z*_ZR+nRj4puI88*MCFB-tw-MNsqE?JJ@mPE%=vJKzuwlV^OzorE%!D|Sw&3%uOq1W zgI%4P2>aeX{=E&QLe?I9HIntft`3I%eLDKhjUF$fr{x&;Z3V$U4`kg2zxi+?=M8yX zrU_1%M}D;fVTtUt*?^PHn2kQ;IERNF-nma#^0GVFwUm!=nxP zM-2@2IvZVG_iB%97kAMUQ_vqFyuC!rC%M0~~FufCD zpwK*jROBZ3Bg*nuRLu2rB=YYC&k{-{s5E#eaJpNoW6#TY=)vC1_t2`1kL*Oprv&eI zgzFMhR&EQY_s+_u(6mrmN@mS30{3K{J>9MS>+xb`#c5{g(HjI8d%AQt{{2frF7+F=bc`}T!5VM0r=bod-~ZK^4O6TQ9fV; zrR#5!nBh#^o?GSGU2mC2$z1)^br0oze5>?~!p~TrUZ2j$)Q*~72oG3rWOjZnDW#^w%%&CRW^WS44e|4($2yzx4_3-Z(oGtixB7(R8ClA!Hb$T0wM-j?h8*E|6 zBeYrQ@$q+>U)`@Zs)MY&sRGg=wSAjmk-3gJn*x;&pE!Fjb8qv>e(F~ZLwSoKQhTRN z<|n z58MuuL@2zE`a(h=^(|y{>DU9qE>hdHuten(fV{QD4vW&1Nm;~AjsJL3wlT9c1L zjLqhI80tvM+YnN&-I%ZvJu2HzndfNt5T7jT&=PaTK6mu=hCPAcu3hvi=w+5`e3>-P zH1sscue|2f8|^tY(ZJdt(|ng_ZnBuM6!#KXDC?!D4&?4ByO+W8@m_+z0KB;2@>ABK zyinJ&dgvT6x7?$kRn)SoEH^uaAb_-eIcCueeer+yH&&Us+X10htm*(zFxxz< zhMf~VtGb@cOrIVI>d{A=KzdeniM(qLPr}#Z0IDd{6q(YQi5|`f|iDKm^dVI>YIWDk1~R?dIdMHw_Sl-)wW|gNeW0vEM8C~W$02Mug}T?W9%~2`c_6HZB6mndPUW?p zs}TDpP=T!A{Vz9GoMF5pS@%#`2i zuTuCXOokS>mOpdJUK64Hy3p^;sNGRV7Bh;pMWu&&{o|((#;||TykbGNM&5Wx+m2Z$ z(rUoHrNn32)=%%7gK}I4(xxMKyP=0&J>NwlE7uMyw~eb5vyly#r**aCjr*rP-+9hy z%XFUe#=3n4G{X5Tn`aukS1Xcve77)VOyc(9Iji+S-C@=5zD?zi(Inuuu|0p$ozi+? z)=MH1W!ZYETlJfMyEJa)Z4F#zE#>-KJ=WoZ;=lBOu3zO5X2*QHJi_CO$Fp(|ytOSS zp7w3-`4}M{2jakUw!$rM26{w`?V$1|xVP6^U+tMdlQH)GEsu$h)KKX=-`A&_t{sFWxByyjro>z2LTBV}^v2LbesK{qL4hxXnl8NxM7BV#GuE@AfDE zXl(!&pPy;c$OST^hEKY%2xX|V4QZ$3VBKo(G`MeOM%}gMbAI`og*&3V%raWc+i~#j zS%wGgjJ1MJ&#ZgW+aK6J%6veeusKpSUJjy{eI$1GayNv2(+Y2~kfMnO^B=qQJ2^9( z&32a2YP$8z_P5Rbhs&My^JLoW_v{FNJoD2VGlAavSJtvEY~Te~<}Grt+Dz>gO&}dl zM^gm0f0ETp^Ex=**M1_Zf4PMy;M_M5p2aZPMQ%6ko~UcKoG38IF$;QYp-|y{oh@NN zVZ#0UmXp2L#*PagB4M~8Ze_yya@SnA7p?V!n;+WSn2xGX$(HqlFLLJcp25Pa+jrTS z^DwJFk4o*8%5;2BWIS&Nh9m7Ow;~>ANs0&#$htm{e<)Rdj%r80fBSuJ-weTg-`@}V zAFkgyN048YGq(d5AP2(7}L$m*Rtok`>S67unffY6{S>x8dPk0x$RyZ0^VMZo^H&M78Ztfzx)3yne51@zqyA} z?DG12{r#VElZloMGtnBr-7(_= zy6JRIYW#9}d!uxf(!Z7h)H$EKeZP59%OC!Ie`@@~7f3a5_#C0GOpO#3fqRA0+t=Gs zdjGJFsr6BNMfgh4YX9b_7o(%}9JJQ=IDrv&sdXjv`Oq%te4nGBf@h9)o^jQt; zuR3UJ<-qQnwOe=fj%aeBrezE3rpg$-@8q(>Arb zP+%lvm$v;=oDrQ2$kME`&=t|?#r?OMara9fzL(y*5n1Plg;~G!*IUEcI>M0Dm8~lWd;IIo}jo^aQ$YYc1LQ zsv99LfPr1Obo^tp%^V ze$OTsGB&EZ>P@Rz1zy}LLF%&8piwSB9N7C)`Q~*>yMWH!w5xJPI{FY;8L1hU4!5oM z7EE){t*`^j-(f^K^PVa%Snz{;NIfK+KUZ0JB%yq_e-vhYfvVBm*^5;5F!;~XHQcoA z(IX$}Ds1fPSzjV6!SZ95+Dg`cy!J{9w;t$P*tLZpt7@Hd)lbniGM5`&%j@-0c4Nd3x~sz5iiM!Gwg7U3A!7JZTsA1^ij6ByWdn z1{DU}JeP!aeA~)6FO-B%6MlVp$&as2ZT)Un5%PzpLxAz}gL6q}L%0+eDo-yd?P?|N zgg$HN1`qvMxYs?&qOSS}dUY-h$a5NMvSyGV_Ojdm!P+`00qJT&txo$7BXfFY)BNjj zPurj-^k8uNvQG&&cW(6f(-^NN9B&qdEb$vP6Le_veI9U?JY6`s9aZI7YlvqPRV7Jq zu!Ec1U1)s)p=KvjLK+ZbAfzjyMeXk2?uycV^3?Udm1n&i2I1?hmC1$huO@}lg!NYC zo{XMhmFE4CFs0MkZg%w!QjL{kapo_J=I!f!K{o5NIywJBqmqrhqyE~C)caKSESoC} zpU>zY!$H{5bF$bw1|yB%H)r2g;9h-mC90hN={N4b`@16jt`GIwbRqK3--in^dYZoZ zK*P}e!xrokd0u|Er|SGGg{LxP$L& zgoPW2V=p_RcUI(l8vjrhW?17{-F~fRBrozq>zMsqIRBT;()HdyR}Q&8#I@&gg5_I3 zG;-+|&YChiP7c}NkDtGO`sL*zrTa+X$fjVO;PoN8=l!|lU;7H$yhCtR`=DfZpfA@# z{r=M!j6#cHiSibIWX{EHFMs}-MbquY9_afsHyPQb+a3ZX3N6_e{8Q3bpHkDK_X#we zIIx#JfyN4W4j0&mKDM*IT8h|)uu_L{jXN*RpuC9-1 z=kz86g#m+5WXs+~0Y|yK@@0(kUwKP@PdSc=CUxu01$29ufBluSy zQXcae`f{bii~?E}^#{&TERYMwRO$Q6*;^H1Lt0u2Pt={br-jH^$MTRSpEfI)RP7(~ z9`|y~`ILDvbeG%cQbz_m*L2pu8t=^o7k^}7`U}))bckrThtw%FFY?`<{Qe2IK~RU$~yB%tV(@`aBg|bo8*NNQ{?rkSD*rbqSvygDjALjoUv$LDIT45 zd)eV3Z&LSdcnQnFuv{5V!Wvy9ncx4cfEtUwGb<;>yE2>EA`dI74^d!ghx8_WwzNH_^Di8nu`ZX9=QlU$#5uTo&2Zz{x*Q3-j64mPiVqGC zc~kp@euJL3eWAg18O6)#<`Lbkjfl0H5c>k<*uL9kO1Z0t1zEnTz0JF9>EwqZ zYq7(~zIEf#GikCH{q()$?Yiev=RVmiTuHbx~@kY#NAwq=(LTI=8R&q z{Cq&7&cOhAx>Iv9S}>pO&}ga!-rG?BOEgap*ryyZ#jj z)|gD)3sa?Zd)uuuB){)!EE5Zjh1i&faDl9kVBwoQ#3dG&ES%2&{t{RX0?>}U%Y%Pl z;2niF%I;LOl`Ep0ob38llZtm!TqKTC+?b+ON(KJjVqqcVvB{B3^GyG^Ixx}mPDXD@ z+{#WdH#O$``Ay!Oi;FnQ@5@8pGo{j$(OgZZh3v`Y+0QDWe0?#a<)4MX0#A%?uGIad7HhMZK* zfen6V?7thd;ZMi*(+xDgVv?FP*QM&3_Ju9$W3K3%mri-uoOLmFX2SC)ILYOYb=gfe z$+-U5<~J*l_d(gt>v#E|==|I1ApsLk59y?H-gc^O45F7#I?dMtU=acdT=4gAT2z=+ z3iyItvPUVMbPq7K%V>5F=%||KnZGc|77kP~lr<(npyAv#eqN!7E*9OhiX&%Yi>PHB zW&7+$r0>_bJD{V)l)X%83ol#UL?K6l-ge$8p|p2ho6*Veasbo)AE<% zz>M|CqV3G*FJFZ}i2kH?`-24h}RG927aBYLt{pl!EMLGXlRf#|BV{Pq{OC%*fksVZs6 z6@k<0CZHb~k>B?edbQLz)R=9dh_sfsU{(-j+Z+%G%31xwQveq4uT1t!U#eiU=B>YF z*$2n|M_^@G=ZEMU?)Omf*)nr0(AYQU9~#qRR~Q(Kixw*Pu`aJTI2voApyFkmMn!0d z0fbbM{IZF!DMi4n8b*ou;VBa5q zfH5}HQyI>(XlKh$TqVCanRn?M_HK6ciRlwJW&e$%r+wwNo0JXsJ6 z4Ow3s7+EAfstUpn0)>w(>-Rrv5A{*|=B=mBoq-GNjHeVwd*$Y(%9}-2HLGY>0Ze8` z*oZ*uL#`NjEeG$i@aM??^-B1cG$kv7bbfqmhCTh^nvjxwO7qs#>|Q{138ZTY7DbVB zQCT^rANrLP>E*`hj#we?cj+T(&-g><9+*DH^Ta_E^3@9m$3~`d@bs8Y5WcUS2yc?e zWDP=?tY}%WX{RrKVM@3vp-hF4XrE4h29^^3;eP8)MmIasg)muEDc<~D68sBTvphwk zlqblCeUCF;u&8$_l(r3+*r_3`PJ$PVjH&;lRR-*3{SNI(vWI&zPh;@6ya_9hBL5dImjK?kg$k9A~TTmw$|7^1WnDm0ZC zA#G;#k6ER|jOY^Ly~{Z%!87Mlpk8H@3s!JsOEPSbHmO2jT93I4247KYi6)<;&#YW$ zN(gvbwkm}Jmk{?CjO=Hg)efqoa6U=WN;61jfA8v-E^Oic_=E@|hgez2$%_~{Gpr$I zFYu6$5PXt_pNWa;LBWO7I0tC)ID4tDD4h3!abC|n+_R7|lF0n=4J%P6S}O#q8Z$X& zbs)@t2xW!@DkUUIN)H{2By}i{k&sxe{nsB*^8i(gnd(^h6#|DoqNC8^!d0Rzf5C9; zi$NN^kC2kkYF~VTg9%?`M1)e{QrlN4HVY+qmrIn+!FEjV(w7+NvBuDcX`G!i{w)<} zY0(mLakF{B{ zku&TpDda??k`DI-+_i3ri7xWhATJ3|Ff;b@WI^=e`Vfr#on>yT0cm*I1jxy9jI{>w z0TNlpft+@snh1u=!o4V@a#mp?a(^SXTnMbep^e3qB4U`1o?LE%XH6F9d9DD8S^iW& zLr6x7=m1uK{~Ouk#2{zTc+;wtK-*Nbm&k;v)L3 zES7s6+Knj(#A)6gCO?0su=9piShMrN!K7`dtcMR7_*JU#FcmFiFHq>corcditu$g( zA@yv~La6;11$?Lbryi4G4Zm}mYCR6*V!3&8+tBd`ny#Q<&G(OXRI5Q?uUJtnD zRjF`JsPOQ+NHiIjMC^xEO&*e%^ZMFec+w@M`RB|7^K2s>Z|==LDRKj zIF6fKUhM&1BaZqMq(~lQI;dIX+?ADKD{jZlTWzZFZD%1m9FVwYV(G8lv8x)0uQ2gS z7|hy{)1~}qbKaGp&ig~%-zpQ)d(zikp_u=uLM4 zYZ+14aS=|T8puaG8uq>#Q&};2`z5iGrRP4+Ar2+mMMSog1P^Wn9nlaJOAr^k^{eh( zd_VA}@}t1}KwseUU!eLzNsmHN)%r%U4B_ z!CRp>Fa+M{(&f)vQkp$*7Jacv6e%%>uB758{x8y%lu<0HJS`f*h!-eC6*v@ygtZM% zr0+spBMz5JbFL-Q`2Y{4+JnrZVN{ROa8Jj2ao4-yge zFRf-Fk&;ylQ^8Q+f)D8-p&Br;v!q=j_`TVgK4)B00&2Lq?}*phG4orBa%J?0*TJ(D zX@fqQ(I)cX#t&IiIKsdi<^Xn)Hwa8j>WrzJbg)P%Jp_XXQv$dUv$2$-kDU=R7Nn<{ zQZ-}v0Q>@lpt$ywH!Z0!e!#&)cGx9?;>bebA!mHSly-@rZj$<#E@kvTK1AcNaNoN_ zZaT&LG9ds;DY}x}=~tRX{fC8IkN?42B=H5br4=kGQ_VG|*)C(a4;3wnj&Spjm;zAWPhTAyI7<@&IaM z92FfF9eSehJB-hyR_O^A>=lX3j-V8sgmbAWe#DrDz)=$1iz!pEO9tyPYbWp0#>H7b zP@$shXnM#68;ys&@g*8}xu7aW)#=PvZfwgeldx03Ve#0V$fV zXzqh1Dp3U3)~xBDAoC)SBHKDtB8^(a;9cT|vjlyUkoQksm`pq+_i6)$k_x0WM>-`X zT3q!LdGKI09GRB=8#*@&c|v!Y0Eb8m*Lk2f>C+}KO7Od&O&0>Y$**%13_`UISwe?E zXfTytr0R*fbU6sD15Ew`;#cPVB|;X23jo(fj(3TZ@;pmsr+Z0P)vwikRf@nB<+bGb za`bfg$QBo&dZJASP3hrKN`O9Ar=pteoMroZsMl2q?-G|V>2k;XD&&_QHRMaWTW8d}+D(0hnuxFhHaz0DFg)465cEC3% z3X)F>yl@RFtJU1he4j0u`=HFyj7}=%WlF&{cbs!y)xP}li4n?6Mk|M+KiH7dY0ao>G@`s?0^_1QeP}S9eeUWqS z7uLqI{1r`m&QY>Q))~qzHChUCY9WUq_e zu4(!JfRBl)J07zKr)2Zbxfl;Z6z2GO(iD=)nG4|08G_Y&AkQ~tyTE>kD%NU!yTiQUC0J6(LFw?FMe@^1@kUW>R za3JXNm@rnboB5Hz_e~VuCDFs4dDvsyTIYR?u z%T}LAK$FN_0YLoHj!GD+>qw1IT~#4#ea^cy4tp*RhE!oO6*L17p{rOx-vC{tN12IW zfEEdR@PI+;7XpiiRhgrwLeb4O=WY9X^YpS((F#`swV*uTRi`6y!L&J#&o`dXD&c-`shIT zZHP%?fXJ*MRP!Tx8;Q4CNU9C6>-sf?2`jEFj8&CZFk-7meN#R&_x&uN2l9mcaz6(R z>1&auLi;eeqcRv(FEz7Ovx?Ng@A;S#M< zFUuOLyaj7-EE|eQ2U*5fl0r=};lJ`tno4SiS|I#1TM9lhp|&npc$b0Du?YqWHMJq& zSQ7a*I_AyT9Y!%zJMnJq?C%+vK(931cnWjblub0mpJr-5vEZj%eQ>R30yFo!!4^D& zlp%=(_&UoD3k#LCDPE$lOwzsJ28F<>&oe3rl~QocM;MDA4n#Xpnx?kEYBEUdf+v$i;|iY zbkxl!yhMG#zFq^xk1-|MkF&(B#?{8O%7x5|B|t1@wY}OseQG=m6&De0`{`r~`>-wT zYJwqC`k(0=#lB$+erG|;ELvJ1m~i2C^>$@g)v^C32d;g*k6|bg02F4w9F+@rQO?7} zLSST!jgeVv{O|HFbN;XAN)Q(+rtC~@k{Fe9*VCo%Iu<73cgyfgyWyRO|CxTw%n`(- zv~ZIYWUCC&!US_9qDjHq1df_y`WTdxqHIPwQ#|mN_3TAL;i;;6n#>m6c@oeplGC!q zLrLn}>=S1QFV`%^P-!6f6ouo>0bNBYZCuWt#niFm_$v>!ttI!77jR>*6a<}3mT|@z zl*FNlLXfL0dCX3oPq}&LJQHQ7H(rx~E+s315LsEs^zmKkrI+QGZxs=}i_lV-pn#eF zlw`HpE=iL|Lt^wYLVy=f`lg6VF9$w;?;vQ2f(ceRm3aDU`?94%XeE^=S*?@)(a1>7Xh%|D6o&LcvIR>$RR{1#DP{-hrake;<)@~YK z61WHYK>Qd@pjF?Xa4pNF)TBZZrW<@I^}h|MO%OWkVpGfM!pUR)*@QeDsYgdNoOBZ}9;FXAxNzY2eLS6PQidxi?e6=%w zVjGoB#VEDFR{T}eMN`^eJ%u;<4C6pu1C^7r?6U?zJ=GUdlS(IDS;yL`be2YeWaDG{ zcz$6RVlp8s+N_Vsf;HkT24bK-L?07B5X?P&8dLLD1XB{D3|n7J@WOz|ARWFREU)&& zzZ4x(#T9l5DH_z8cM+&et@0Z3vONETXBFU$3X0V`TR*;Bw75aP_fOBr~V zxU{8Cq>fG%R|!2o|Z)4qS{RW z-X?AojCFm=scX`^_O)bofj$Mlev*N#_F}V|cgg>bx_P_8A`Ie`K9IHqK!g%ZL?#5~ zth~$gBj#n8f6dVDsgo%1b!wPYHyf{-Pte&$n>{EM;q@^cee-CN&gp?@cKyj&Ppk69 zgEMZeBBl`d1GdiM#dNNftb6)`^c|OoroYRPar0^o9|~5I%{;4JXEFtWEP`A|%{F5l zm33+ca=z>ik>_oKc@v3A>=<33N-}yF4%N@EIsidG_x9!}q?uNd=wZcgvZq^{>>~bPm@}VAW>rA=Ew94z-6iSr`F8!!_ zIstU<1B|%ewrnzs8FO7I5C}lIYR$cHa+#pfbRe_5N;1v*X1}e-M|CVW@P5dtt4j`e zxOaNqEYr7X-{A|Of932U>M1fvg*3u!opJXB#z&?nMEHZuMH0xXN+Pg~gno>?;e1EW zKq;ZPKJZnPcGM~*MGa=vlB@uk?I|kBxmLawARnl+nF5L^YEEAZRJ44e)K5e(0t8Ox zBjl+lkFtf%c;a0eAC(5Qipg2(TV$MC9+N>%IMORIndV2Bz0_X8N%UER1IblM6?kHr z{UQ43_k?p$+{q48(6r87$WJ?XrFTTzK8bltiu4pv3t5EmA{T756|OP#&{s0o$1sHr`DWaI4un{r5tls#&BqiM0RqtlYbCTA|TBKbvxbkQr3s)CP+N3 zD1`Yk?${RONVSk4YaN@S8!zs_ibmV)Yb?n)^lvoinp3iALeEKwkBeY5y6kJ6vVZ#hn}i-PaAFl$wPgRfa_QaTx*-g4M+8K{mm>x!f$vfYR?& z1yK)OZN{g=*TwZOP&eFD*bxVTWE9dNpX4TMPqPJQ99m!W8PgzMh2wBr6=3` z&2mYEfJa`Gwk|MI13BJiA4wayh2FGyuOtghIQ>~XGMkwYBvbhXgCA2UuOrHmM3|KR zvKHz{_l4K0OCPE`GkzlwuycC68W|FzICOYlL)+uj`3CTU=;Z~=qML@9R7TK#APj2` zoVx&ZaH^U=J~VHHypis8qnND2-%YV)IF`PY9h%KAsDWjGqeL?=v?a;x^=Kt-P3K4c zwH%3XJSOLb`(Nj4QwQ$p$a%CI;?re)7C;io) z!OJW?fHn}PxzLyXkL4k6k|(tu1uZ@M1i&(K6=w>BVU?6@76LIz;Sf2dj;B-NBAn1Q zw=Pv}&CzHaky7~sn0Up$X`oX&GKx9-lt|npw1h`E7oNPHGGX!{)kYR$pU&QCUs8HM zOUmeJtxppEKrZ+l?V%)hi4NZ7ABby4Jmb|%6Sd~*G|SafRxq}9K7*V%u<`GXJ~u}3 z49>$;if0K{V4u zAubb$x9$}nuevWKE4dM^9|Zb({BY$V)GV2i%Vw?Q=nCgUc~AlC4!g6h4Lq9 zi&-v^N^GEA+(QKISGqSJQwKeN=3Y;ngh4FKX|XYisCfxW2yF|BC-GZM-UDs2Ia!^| zJXj0!Ql0@nOm&EBmq9Gf^Igdl=RMQbM`UW1gem<3@mO^`76-_yqbnu#b~WcC5Rr~L z1uoDpIMaWN;yEI93d*Qmd>v}(sGGN%I@Lx_y=Ps@BqTChXLR-#A!JYxr*@h9{gzXxzZRs)?X(iqV6`|uO>IhoVp_=2CcK=jR7zS42{%)W#AC7H?H zUHWeLs6t;H2Eh_>nzPx-<{fcyahwC|nMz?bxI{ogmB2Nd&=(ilY2LhT$r8(F;(FQK zZ$DvN8t>B9kUhDA(9J79@Gg!WY)=6-a{_4EWBf0iGyqvL!t%|xu`(wYh6(_Z!k3{45$i1xDJ1@Bub|{ zVQUtXr4gZtL$Y0VAC>KXwd=RKTzMkU(_A`x>$V<- zCt<`c266eSwiUl1Etl?XUdi+>43zANS&f#gY5L0`cX9Mi13q6K0xjVeGlL_N`A~oi9vv8q-a~857JEpT zGc=%vzZ|<%PWwX`v7_z|6v}QFL7MJ2&smaOIYjF0B1-xFhvE-jazI_DXf~0F@GC?j z94<#3RS8sufBDu6-HSvxsH+`i6CG369gc4gw%ifD*Y( z&28W~hAo6jfKh0zSzbq{F?v z7+aCmH*}K0XvhA&vU98SSi zK2y$})ssVurc&u5qGJNf&1l(|qkI*-tFjMjVw_9Fps96H;CHz<9ue()10aw91`jZ0 zo!e>Zo53F`BVHt*9+RgTFer=sI}>3G`=s^B=#{m&!1j=L$>T(y*>|8$b{%h-=t=FT z9eX;`6FsIyVI%I&F|b4FhvxIBY?>zOQ`8R%W~tw0o#%U-x>4tM7n21J3ar5LG2vAT ziKGGmmBEn}&$-t;{WrX1AWrd5TBFNxh&@y50ca;+`xI*8FAVJFo_A?x_$~f`1f`l> z-;52+R$M=kj~8~vh~7H&^rUH6l)y7ApuP5x_=j@yjl%*wH4%7|d2wFPqA6|L^G<_37J;d=8X9MdqSpY#RGB09Cy61EY6mhM$`MN`s0C6R1q{Sf=ckosOc zGwJH&$*848m{0>u5V*Fn6yDJO0`Ia)R6QlD)sj0_-hpT>9Ky?tv44cP?7@tt`4H#C z?a!R+VM|rHa(z}=P_-<4!v{qXCcXsO?Zuv0=eM)o*Q^Bt(lCc~c511WFFLuJ{=J>) zNzz8$H=SULm{~^ujqTiQrr|EJuvYN8VY0fsJJu1s-0Oyai3A!*oy`L@Ig2AWoe!~& z1%75-@9+}G>yOHOS*&?AZG4@v1d6Ce4mEp0?=nuIT~6>V=aDytnCOTibOzlruy{q^ zG@`CAYy<%IMl;JpiD#A>Sd!AT4A1Z~D1zjBvE~n=X$VX?kLA@luv8dKh9XyJ%~4pq z@FDiu`#jLRF4)X;Cle`L@h`d)S|+655GTTlw&d_xIF(UZ5ZN%#r@U9#O-Zu1Gc{2m z=Q4uvZoE>q5I>7&k3!&GC`rCjfda=)jk2L6)w`EOGwuH3m7ukTQ!1l~y$T-$juZ5h z4{^_-4WhBmusHM7^=i(e_p~aFpko~ldOq zkL@>z-=OzW-i6umdV=6KEh)AqV!@UDi)^A9g$LbZotVf(CSrpnEJ&41TZ5qsetkKl z_fmz7Uk#Yoh0>V-)w9^}hBja3l?0&6bkGt6KTwBHFz5wss0lf(O$b}3gFfWZ3Btgx z9P}>Bh@E_JgYFKpMuE<&?12hY096d15c>VLBHHc$ay@ zM4@*JULf6R73o_NG;( zm=excCE^F4j{f zQYqkNXLK5ghr&rsK?C-);2{#5rA^IJ|G!L$H{qznqb~k`$O|v0{l@L+xc^`WJ;*4Cac{F!Wn~QRsfaRANdM# z{-|;?u~tP`ux;N8GD;yuYKv&UX;r-FAkyrTJY&H6AIb%J^nb~D81~ZHERx>Z)t*?# zq3Kf%?u*7&KA>=9JOGDNc{v9s`k)kmc2dXUFwD_EczBko(%S|^dPof3|u=)$sD8yc0mlDs5520>tt+d z$8{#{uMb%xosPbFNRu_johM+Wr%zPxi1USYt>BvRmiA4J`C9X+#IUiw~f*wSeY5iCuXw_&?k@AneCyfrE#}Jb5 zvYM2R)ytU6m^z~(R>(0Unj!JAoCh>CIje-0HH8M(Nc?>gRhpjp*TpKqWJ|@I=}eDa zdo}FK=ug6{TmbR{i7+wL<+p`mV()rVNYfet01y@MsVxM3myPLXo1zgpECGB(d4$5$ zcayUtI@{ReCu&G$*Tubz3P}t}@pL(-NK%9W-PAkX5Dd@KhW0iWOKV^X=4X@yY6IKL`%=!-x4NF`pqgpY%{^s->Z=6U-Xak~NrHm5^wkNb z8GHHq<}v^JZ~yJ@fBWaZ{ipx=fBN>f|Mx%qKY#nr|NUS7B%YY##$@CugDL(qVeP*8IL?uYa7bsGOUMVwG zm>zI(w7A?+HIrFHaS^89es)3`ct+JBr4f?dl-3Dl$Bqo2Azenz-xo?xc&4yN+}S~~ zmr51;XgsO7UmYx@F=L!26=-3LkI%}6U9tg6RS=k35kaKXP*EcZJEf~Z&--+-NzZik zJE>@!lneyozd@r5m+GL?rt`N}BzAH8wT1BvEJ`JNj7aYL z1mI~Vs4yJw6`1-ul-)+L2^cwop|sqyJ52Q-iiOci*~TaE)AhF z0dH)Sr@8GbcBL^ofITo1CQ%(ZZBj>7&rvTx>xanF*)$3~7|R`5`eL+O8W#cJ)rJ}` zCK4i8Br_`!Z-o%TLLD=PVOEcN69g3d3fIT)y24^S=PV!97Oha>@xnV{1!f6MHA1N=e~tyGZNf)$I7zD;0eVIRY) zo6bkK$l~*jI@%7D4HZh_P#R3&!u=d(wDd?9#T6eHU^>p&LkSt_v z-f}t+7Q+nXk$KtVF*Bcno+OAcwpvX}Vx5vjSsbEc>Xs}YBFKz@lNv!0?xVKT6!V#&xC z;Qeiyg04ME;K6?-hv%lOT*xNzDn)Du$Qvl-N4Rmvs7j z53verG-6d}5m|Kd&!oGwoK>ubUL3C&0gFzdA|iTAm|}Qoy|dy(2GDFGV+!I6bj-Ce zj`h>;>Xy3MfU;v4B}ox3D9^B5%{8?|Fq*Aa&}N_{^%n7PR|IFQ+1t*0@w zJiyXj|F&yZ`5VN&hthpax_6`U1~QkJoD2$}7&%p7ihoO&T^NcXB46DxujM2by>@fiWt9*U)D%GMfXX#dIueP+8oXnwug&NH1!(v9Z zbfxPzUc5k>p+H9Khk3wu9}+Dr0`k*Vbp1sc=)>Vm_)OZmh?C<`_&D6e=eX{jQTn zY(Dz92m{L2vn~bSH`6c`kU`MV`LMDyPh{vg=Kb=QZXQ1 zknwheqbrFP zOE0_tf6E4{3(F?QqI22|a=}mi^t<|{VlyCYZ#x2%$+}RcQY-FWmW6XMb67U&r@i`+Q^z#kdxP;=P~oE72_S`!=(N>w-Fud?2b-i?515kAakU3plb_ zx+cq)hx0y#qoQ+P2fHTmvO3mi>?)UR=Aq_Ay3e(-_aSZZ!@!62)}t>`E`h^UHS?0J ziyCE$&%0_Sy!=C&7GUBLn(CZbUtX@481;qdr4Q-Cesm?}TA9{&a4tT7fL}`4&s23W zJtMvE2T&s}hB0%9$JT)>erYIT(_1?L6IwqETiiMa+9=K2QDPcEp9$+sNY}v8)&w6~ zJw#bmlFkeZlAtX>2bRc*zo@4IaN{J3W0TL-0>JwmOJmG4VLivVSdDCnn&eFCl;zCD z#G3gesxQk%rezML56&5!Lz-C*}QC|7fyYshF3FNyuN)>})x~yOv%~I3tJ@1oA9^kksQ? zixRaC>u^s0u&8#KP$+VEjR{BtkO)zfS7r#i3M46%W-1tg1*ARoaNehH6oGWT(cVn% zo9JAenNFj^wp>c#oigL{5Lan%k*eVkL+UAwD8?suRL8IY7e3R_kyv|B3hRa}l6Fa2 za7p33Y}HAUnQ)(wX+V~$X%4!RMj>#q8`}N|Wy=ic7ugnX3X&l_pJ5i)I5Hlc7fW%D zdX#uRM!qr&V5NoKv8Oh9YdUZRasZY>fbQuk$rKi;>Y*7JQDplNS;N9*XY9?ZFo*yq zu`3f;bNXD;5e-vJ(&@2i$AgZgt)rj{=?H+5m&1`b#}fqA%UbuPllomHW48xxI>E^r z<~#Rv0ZU&{m&WdL%z)hV`s&ZnqIj3QzMOs)iNJ zj%}Qk#3Pkdj(55h!%#>T0%{;>6y^08__oc3Z_L>FX$*~p-3eYF!+P%K=EyNZs2?aJ>d@kqw& ziVH0NkmbPZfg9`Tijilf4MV12xm+I4l%*{v=vi~GXQHqoMZE%&NXRN*GGmsh1&31Y zehsAF;S>ySVB$OJ^V%_kyr(`BQd2pVo@@Wp%qgtmHr((tc04_der*}y6-!e^qoSg# zP4?a??vN1)1|VfZ6;YgPTa|!jyEtC4a$}uct`m?_Qm*W zu;8=|H&f>4?tSY7Y79>@oIW90B!#tZ+DU{JC9`tdM;|Gv|e3k z9GZbvG!+qzP(!oNZv&taAZdirXusb~xrf`k#><0K?^6KXm3v1RN5SLhlllVss!HLI zo(}`6x*alB_#t*_Mm`UCWAq&+K|mMWh?64rpU*8ox4d&R__h zmYUjqc3o?R-9Q@+$4m}S*=T$Q%LWtpB;-9rZ)BlI#}m(W%XUoLV#lEO35~f+I5tu@ z18sZeyr9-rtix;SPvzY4`P}u$6n+wCjGAT?2{)EEYY`C3E&Ryp2&S?#AJ6zEZiWT$ zfSCbbq)@M&&{5qbEsGyZRuaOTtK678%PU~L44fd|(x6&)$O@uVA?464dQChV+VPCU zczI*0a%pXrOH75VG-R=EEYqhVMV*k7_+zjsPFYz?yPdAkY_BQoQYqu@(*~um^xRKt zT4Co?s^$V)9ssYG=wzlGBkOV9wkJUzCQKVbDqR?<^rgI4T7z0lWj`g*nrHAhdeRAI zA1P)zDd0ZQyQr+WbowW)tNk5I8_#W3BU$HEDI9dxpAqDj71G5STtVZMd?hiFdKW{! z#1Sd{m*LLRc9R%(y^Mlq&rQ|(4Uog5)nmv=QU=L<8V^@L^bGm<@^d*9R{EGyILM+} zq}W3VGK1ZsqVg75>p?W@a^UsVPAEjVuD(1*VGP<)9>bx-9YbMmIy<88n`62(IF`xK ziK=ZvVu@vBd3RB1x+=8_yG!q>3mC7cT}n?N6QW89Q?;)|-4si&H;eNJp2_WnMna-; zIjQ%lZ&9bk()PC8PFh2)MVK}{&OsNmOfj$&4Q(NS!XSVsoX=espCWGxfUq@d%mu+A zbQ}}u@oFtxpyt4z-|^%jtM|&%1Opj(SsFKL&=)QLiQIspHs(T z=p(S3Z+5ZsZTf^slkj9ipXh=8nBO~okO&l?4?9W3%%VK5FU!IknXLr1ZL7IYm0;=I z6O1ZHQ{ZZ5E#=Z?^on9wP7MOdo`|&*;2^cmlm&2{bI)yh%k@kyn@B4p*g%WLXY@?m zHsjO~NeUxb62*qve^TE96faXVbd^b@=MGz#DZMtN=s&>%g#ZhfB&8X#(pFUw)!U_) zAOI7WJ<_C`OZ%=sNN+M#tLlYgysRjR;f|TC=UsU9%sS>ChGi#UL(By!&{YY)!~uf! zA*M|?3yoO~zZ^VQhQ>(i8mcF+Ss5OcxCAaWrw%rrL2q_Qh^z^wJ|z3LaUV>Cxu25B zILT9ZWY9AZqvTV7@9;GrHM!D}LZ%qYOr^d+UH0NYD@9x}Lyfv}L4d*=DOhGM?)q&3 z>O?lj%tm08+${!ZW)avVCQ-? zcd3#}PC_h|_0C-z=HR?CV@oc0iL+TkK0bQ}Hl_nu$R@x|8 za3mihX}(Knh(N&ZP`CiRVk9Q6yhWDT2HKK)%f6nGWL#DopJBLc?WC0D_ap$i`OQKq znJ#f;*mMI95hKm4{m3Snr6|wWV%J+}CpELc#2y+bD^T=l+Nr{;#Y1WbF_CpwqDpOo zM^hjDSR_ovC$cwcl-4PUnQ#&6D5tIgtLTAe_E83EpSmzhlT_GK+n|uG10r)tFwJ*OGn(MKyeHi$E1V;X*15D$+%-o{1j>HK~p+aPcMf)-MO>O4pj= zcHdy?klN4Xp_W8ymx2w}AzkQr!iMo*<;5~tWE>?`0cLrr{_kTbMRj&tu%fg=mD`cf zw4lw&#AKNtvVN@a%%=PIHCaJd@)h4I0~^&YI9M1Jh%w|ofV3mJY#fXFal4R)_GOVK z!vmb7t!8v9tM3Y7hDpwaaEvpAclbhx^o0o%>XD~wnGHyvDAqlf!Ngg{9kq18vZ_@P zuB4WfiD-QL5S*XE)hntMKch=S+N7+xz-Jj;&LD`A8ENW>T9jjxI0y5|PgrKhoIN`k#%!uDCbg*LbW$j4N7y4_O3c#Um zVbwz+BFxQ}_A)L;G_1N4UO4b;_JZrAFj|G2_%e&5h$1ZH&jfe)*y+{~1~QTePhhV0 zPT=bAF@D*qozWj{BlWYp0w~*^*ozU&5FLoqwOPtVgsJV#c%j^Ipzz9|G*`AqGlCdf zSmn!swj1%9K=ckUqvC%k{)ecVuiovGWG`0wxs)V>71npi@P>61?-_2se}J)(3NM0&i8fK(E9`ULaNOn3I)B@0OrZhygn^Y_9xHcM8}xo*imVVB4jxeYDooK zAR!WDzqszoX@ z!pc;8J#_(TZu3gCeMPl0X0#n`7TJpKa@0bg0g&mfdYUTtL>-;SU00=|He*yDva4+z zOf?fZS(m7nWqvMv$21)r$6X7^noVdLW>w@s{BC+8$x6bCDtsx*5=I0OrJP z2p~cACJ~kY&C@Pm*Nd|uCmV(m;rY4wNQhXiR_(?{7n*xpiGshjpoyd7Rl`xxuF>6xp7$?tAa82~E(oq=n_DU82jB zB(7b4T5Nm3yKH7pxRUkN|$U?JG7>` zIh!f^yk((u14c;^WCiij*&tcJfn#RPGX9dip2Yn#I_HHZ=5j<3H~p8b%FR$dNb!HP zcROHQ3PLM@QJn~$1)y3U(71lrUS=QXxkL^=TigK)2mq*)Lu^&dTzcol7n&9%Huby< zP0Oop*`~gr^Z;K2&GYu<8JvA^9GwB#@b@96O=qeG+KzcfMun9;de(qF`oYfV)AR-7 zco5$P4~}^s_N|P*-trc1oU?C~OUXE|9qc1rCauWKO!CaxaVGU_x3wKaCw6@JC1x`5 z)#64ne41X<>~Z-F*MtI-DDssqb>LJ?3%$*(Y_oC)ns(Hre$4W_nwI&>ORN$xxIGVA zAQLHd>A=vGM$w$X1D8I{sbL?npxLjJp6J>|mIXi%6nht-2MZu_o2aY?ISr3TmwhxT zfmLz7DXtnST5!PwUNQA$b^r~TRx08a*w=P@y-0{&3ZA#A(qVQ^)kdq*pOEbvfTnEv zDQ{*(0xm5f;gSHarG~I4O1p_lo{|?!C_-#$Ugl(=a-M}_kHGpiSzc*ERu5IhM7S?U z=okaR{IJBx=0Gf&1q zrYT$^BTEI_s|g$+@tMvWx?&%8e6yOL3xwE-qD74Q#i}%>f(}K7MkMO0JikxgY;m}j z`7W*YLfBLP_Hc{P)6$9vita@C>QChhan6+!JO=;AX?%#9X#_k{leM;Lc$u9A+-t-r zufgfSb^un+dCeUUv@0!i<=d$+ElmvyyGAPv5A zL22q6?db_f*D`w-CewALU>2 z_$3FpYb0WC&Q1Gf1MO zlO+8sWEJ_+S2gj#a_h}>H=R!Eprklp(hW|e`39&>y z^K>$q4O5^{ryIQR6LXlUS#_PVEdn6eT;MoV#>^^ zJ{T=*=+XWv^8*cI-EF=hd$4hp_l9X?!hL&z`E90&;4X#l(0P$NAS7|^qA0eA$VW1w zfOF5267hYy4T*_*`tn__J>z@wEkWg{!d$I#6H(mQLk;afu$;T*t`_EMpU>1Ku-kt& z{okAT^qiES!he<#7}ij=S!HFJ3iwdyo;CUt@f-9j{l}SUg~=xBZ~6thRTO6tfYpGZG%RVpSZt5p+uEX^QyRSKp#^IJnsoEY1m=Z=-UP>~nQTw+=BqOXW4 z8EnR2Zk?DDuPebDoX^z|gA_47*tK;dns@)oTSBV@`KFwG{U@P z&T}V)7%a3;kCTQOjl|*XWPh9~KRhPh> z>fdo#iO-)% z7qXJ9!>UxlTFlT1?$TIYbz@HzI+#F_3GE6`s{p2quHce|B6OTg-X5iqD!~d)z3`}3 zidLLX62G*HR_PNB3K=rRmTtReBqdr8E(n4najo6Nu?SHTmSn(YCFw@dTfJo_d_%Yd zci~dR#Vm8YX=RgsI?->6r1sFav);2Q@euxqDlii%g-vGem<(SPHZL{UyRIthFV5LC zX7|FigrU0Wpl@QjsudKS`$QJ;S#IIk6O{Lj57%=g*oh=$g8lL$w`+< z`s`Bf`b>NQHJCM(jN$DeVHt2;4m|(eQm-SUalqOq{J!aue?eKUO5Ysgk*2h$Fe?{qOG z=_QiuPf;$VDt+WA8i>8c!ayx{#Y~q=&)`w53#M6vGZyLv>VK+t z=MfWm$Ys_6;oI`bY@a)TLGzxS{c|1;@Wv5YOv#6;Cb^wqLQF4@>UHA0?wG@??rkpf z=a|j6ITXbCH1`^ZhuCZuAQOhQ7FkoRRK|6)iaBKUy^DUR%or@f8&X)8g=W^e&7#C2 z3CbLq*o;9c!hP3UXaCFp7m}Gl3)WW@NZR? z1Hxph*+WO8fCCL3CC9RBV4Gw?Ao(GG?c6VEnu3)&iVh*5U+c>QGo^wLtkS5EnY@my zXQm{#4uXDkd2`YY=m(n8yg&$^^_YmbYb(n>zjIqTFixLVW)Yn=$%1tjTbYUqzb`9M z(NZgUfkFV8T`Kxnppk7$eacB{SHK1j%BWO*%xwyjHJ($*1wP`DbZ#*S27%JL3YW=S z1R%r-!l^*ZOFR`#g(WNkMH+5|QdZe?JlO}VfGwPh9sUqu(;Z*1m!2?!gL?_vA=+(} zL^4U1f+xsW_29_UQ7&knBmHA&k+RaBQH9-wgtfIwc>F zL*W-RmCX~@;{vwT7dwehLZ20~euMat!5Raoi)Alh+93cgtxkX2eakc^%>tYFME6A& zPpGnFK6`mJGh2}+0W_xee0yS5ijgLr8BT$WwBC7CWnm?A>$NoLe~5)?7CBeCVe66x z9GcIh14**mwlXnO_+lx(0Q9>oX59OO4C`UP6B0$B)EXGeR^bhMtKw%dGoBvR$pp%B!OU%E)D+r0eWd1t%wS?HY84-BtN1^1Z7^pa&!v3GHS(= zE@R--IK_zn{U875KmX(3|Lx!Z>wo>f|NOWA_CK?_Iv@VufB&!l_CJTQ07@iu=s>CZ z7Vv9ry!sf}%ql_YB<^$Ro;n(odh;Vcst(K_bxiFc{z7@O6kgxlLs5Tt%%!FDDFIIe zaiEV;Gl90!SBYV@Vf^idp3|jXkwWH!u3}9EAqo7CsQG)D8YXojfg?3uMq44VjT|y( zd5aYAb{_^~eabIe#j<7cgUahqL5uwNI)4J~aU{pQo9T(q|wM>K4R{ZLsZ z`)ek?df;5uvlVq}hGMU0dkk``T{Vi@Xjjc~ZhL5j{43U@YS)&ks$Hv&7ggEQHPx=$ z)Nra3Td{FkR`-}sQMHW+Ee1Jbh0=2Gs(}c$-B7wRJRtbUrgJU5y)mp6Grbhaha{iX zD<_6j05*x9y_H(Us{JVAI(g3J+d0xhH8C9{SYUEh*PT$@@Tw-1s`Tm5U>!LDk)D69 zZ*@wY&?F(5C+Qll;bLM)bzq6QO1y~eA)#eU=3B(g!>EyUPz&bFkdr76SX1mGr<~?r z5oGGlt>aZ*s|oB0>oggqT%q=s&4GVv3M72w^Hr_ltbOr5=YTEeE_$F1O(_s&5mVOA zH?h>pmyXKZZEVu}6~>7)TsfulMGD$>9ylB``DC^9Du~xUK-&xiA83;;a#V&Ur5+;u zI!Bt_K1Nv5hA8|^9eXa8m}FUnEGWQ{j;!*Pw8^9ojktQIZ00_B)6PY)X_tD!;h`5q zQ2eZ&ue}xECz?o!3d%O8t}M}&Nt4dtkW~ak{|Q9}St4x#z-{6H920Xn5~rE@YpyX6 zq9dhd8o(aHs-Xv4l}B5R^Hk{q9VBXHI4q}-1ceZ(HJP*@3BBwnU+Y7>%#6}|_A=2w8G!^tCH4z&>_7I&CC$mheaKcS+dL1N4kB{6nU|%|CT8Zr*ZI`Op zcm@Pz>=e^w{>y<&sex=d>LJLj&T>kd*j^e`fS-(nlz5sM&QMdXjtlbl5x$Z4(+F}L z5r&Qi5zmB5I*h6-FgTwV)ga-&L5VM@oQV-jekD%nTB=T5?;NmImqr|3Yt*Ghm8fKL)|e#1jlAnS87c95Dt785X+?KyWe zPG)&d-9TKqXErD=qp0zqy;L?;$ZxXCPL@+X3^sk@!>ud<$`N7+m>j5_QLceadm&4b z{U#r&`N_F+ypv%WGgBy2VOzp;-w`s_`;DSVE){$^I1!}|K=S&<@pxO=oBn7(3 z!`z!XF*Addj*h)T9nSv9v7Z^4(XlU5Iym-2{OdBBhrUZ4yDy|dwfXEE{z{kSnhI5K z@FW$w&A@5z_$Z>;(6V~?R&7eh_};^xad6||YiKq)_%_9GUkMd2u9%rkN>tM6fD&Cw z)TTzxl`sI9dX9WH+izQ#H>O0N5>f%lIfa7~j&aNqfF8y%r!1VuF-yE~4^lUCFoQA& z`oz+&W=3c9jhRtRg2v2fL2Pd8AiU$8e)cjB zZBY|1aezgyHIW)cUalf+ap@YcA3^Y}@l6rUVxw~wo>Exi{cRPYMx%RNy3&=gi~3V7 z)JWIT%yP3wBU2g^P-37f(+Vn}27_QDxn{Ej$Z&G~^=2#OHjwL9!aud1$*6*7*5}m7 z)i93zQkl^#&uN`*8`fPeaj~7V9CswqOtu6ao{-Kjh;kv(i-MUTUD*)uC?%d$xTw4a zsmD`l6e>K@zVmp>l8)SzO>o!5J&XjRB^&nB5f$LSz1md*GnJ+rY4enSgh12rSIkSs zVLJkA3n?E1uay4iqe*bmQ1mkcI#O8iO$uOI9}Z9-^9c5CvM{^5FPIl4MRQ0(^X#UD zz}GqfRn}3ImP4qHzM?hRU3(OwK5Mc|#$le1$5cb(I$!9=<1r1YxNAVc#5W90y*SIP z){&vvThQE^*qN8wfO%|Q?$-E#3bP)LQTs;LRi8C-t}^a`s#n-mL$cdcfx2$kl!l#+ zMpM^ekw^`1Wm>7#E=P$Rb#CcT?Cqv1)Uq!-4bT;gkE6Vv{22+oWLGwxq4I7dvPS#| zyc_*N9i0X&_WqzDr+0a0z-?9n8zpjME-P7w=JJ59kzt2Ma#@;tGgdK;c&P>KLYgpO z%&U3aWQy%zo(AG0Aa$v$2+}{ZB4e7qd9@{pofcC&;>uF<>;hxjP34y`=eWKUCwYrF zQ_APwZOrey&_TU4~6a8oE{$CH3$5Xxgz`S8u2Sd;N=&N~Ed z^KHI+f21x8e>Gg^uFLEVEXLrt?(u}W&G|fv=+B_vJN87U@fCX_4+9t}#wp_I$f{w; z6IA*sb%&MaXQ=2c;-)tYj0WWiR(|wqPl(%KwM#YjDPVYux=i$)*MzWkoe5#|4~nUW zF8B#`$6!$JKpmfK^PM?*+r=CCeg|!7Nn-c$OE}yj29XgZy z#LZIFk+`wM-wFVSGWCRUPgu{d>t(WbCl@NTZpgc|WeL_qDtqGUu1~XkSs)_?uR(wI zJ=xrpZG#+MKL@v_-$SFOmRv}J)f7fxvzW3yMnI9lkO(IwUNEAY-p+oUS&?MWJAt4U zJowp=G+{SyiSXj&c9$xoW??kV}7hC8)-$b&s(`j9@w zLNaiHh5Fd!S&GcI(pW_#050z~j{234N;>w8zI4JL3`7#$?U-mmL+@Bl2+@p#y^JD| zG`gkM?hDhZ%b@2lgZct}$0NE&6U_Gs%m~T_*Dy>)YnQFUML@T+Z{~l4X&F27lKMA`U?g6xA=2_b^ms6f{pM_JLJ!QTbeT+^9Ir&9(2_3>OP^dLdgS?JO4cMCBD>Y&T zjy@~EY(s3KexF3$yjP4&`VsZdn&INv+0*uFSr@JP#UC1`Xn5_JA0(Gqdgy4li;Qg4 z=h*VA|Lo_RpN3rPi1h{3$Zbx<(`vly0MK$^K^NOT!Lp1!9=7^oZJYJ z-tGh3b+s~(T0Q1=2x(C_tx^w(NMt1}`)Y^ahn$2tk(rGd0<~Oq8uQMcXCHA}!NE6X z!FARv2}SdDB>4UBkzuQT11MHR_qqOm|L-}Zr0y_NDG z;vlJ?+0VfX3ax^UN4hYw*#W|q{RJj0Sgg5xMz*yZsK)9%5c5^?7@RCa&kXP~8FiO= zjPp!92mQ01hlAt)avl3pc(WyO`t0Z7`^(o*fO?$)wZE7g(24xf{=%2bW@QppZi4>?>eC z`5kt(qwkLK%o39;wj~RUnSYd6r{v4^lGxL6f^|WQe^-NiU0#tyzl(#VS&j>R46+?R=#MUli1%jwN z@W!&|1E=U>)?fr}YIx3V3aww7S(i}(X_z;O-iSb2zlqgSzZulX0|&TVetG5~GDxIz ztIY9%WU4@#DnnfI6DxMA^xvm%x6c#fJMv1tI7SWs=7(uGJ zA%Gk~C#>}$VhyQ?Xcz=sUCe#z=JQgcd>WUfY0`y^Jhx+K&E)~^sv@LqKJAn`09EQ| z_6`SNY}Az%X>>1RAz8Nk8T~6u>dq}_PoIkRQ!uV3SK6tBK6a+wmP(#mdVLGoQk0;yL!%tx|A3D%A{!;HOsFeuH zvr--_=X9Gyt?v`{dj%F0RjZUh^D^+=b|0O(JsS=8sG!AH$@a3*AYtr>+`0r{VnA~O z9q^gAfMtloawA369ThIJz|8Q{OC%Ztx*CSTJ!Ga|`U=T_DkTRg3Wz3Omo>s9vVQDC z9L#FgbNezRM!X&#aRt&@fmpk(C2y5#0>HA(K^Oi#qfdGt3+XBdfVZaUN}sStuA8xT z0sF@!6d%s%8zt0|NNL`9eHxHiZk!rIxiX*}{Hc5%-ZPaxaF{nySJ?Pa?7|{UbB5mk zrGaO?_;W$F(hMw>=-OQu+!6#JeTEtY zT6AcMB+mkvz!&?wRgbQ+y-%PgoXh7Bd~(6I>t+FvyhaF9tw5q`DQTidpzK^eMLI;0 z$sMo5mRlvN{aC%ho`b1$4jxb}l`HYaTjK3CecY!m{CI&p&1w!q?~?NY-c(-)a+6&# zx~#C1`;2=iC7>(p%hkLHN|c}Sdkv(-qV|Ho5|~43_d*O4G&mS1H^Wvn1dz+mMnUPL ze5ppUx5ZPGG{Yo%`y%{RuN74}dsWxg(&@+rA95b0%@>Hnxuff`cegd)C+=eMpg5o? zm%9y<{?(M7L`jSm47-Zjndu~whu0Ka^txc!HD9_<-8^#`Jv&UZ^Z}^%<&LH5lqID{ z7b`u<*{NNYVY9V?Jlkp_!mztD?LKv>JDtWYV_YUI%VliHk;k-UN8r3yZe&|aeL0?k z`}eZEC8|is9~Uj&Cve&^I1>2sU5RIb=kYauWD^JoQF4>rW4q|Rt}{^Tw3IR$mZNKz z!pMiU3H}zO`CR+h+$D?c?p51ev~`<(+3#~MpJU)61naIflP^^DOPk2U;=EE&Nn4QA zeRH*y;5_Y!f*=O0deHk61{gloz#(!8!XnB9n4}oi@>oboU|5+BAGn}|yWOe2$(jH( zH6lom**4w-^?b zFO`&YJE;Ki%1-dxGUM@~|nqJ`kHSd@r@P%nis_ICkm?o-IWPAD9C$O5KHU@=?3qhe;fTKeBo8`rq2 z3$@aBriR(8n@VR{prO*xo|En};tS>w{PauyS3vP{C58W*R#HYLev1q#R>G8Y1Qt;u zwaKlswK)u47Pg`UQCK2HZWLSf(aYzTFuy> z(pa7wI>^@x346?nou66I63K7(55)py-)U+|>i8duVT7>PR1w&^y|$^`{Ue#dKw%ep zS3z9`Y((UbFCaR)8|k(x3ioHKICw;RsP!^nV7-Z^@(bJo-QC_qbDsL`ZtS6f2lvq2 zCvbWP@#qk<*#q>V5*Yx#noXGitH}C;n@XW_W#Q_pH@!+Mm4?T-SC#h~&4PJ#KxRV` zyoxJnA#Q@U^)c7eh~WGaYucNdT&%|6fvFvLnr;d)ygg}DGzS=_PO?(?L`XAxrV6UA z&1$vKTph&|m5Xe>*2w*#pw!IJL`27;ilj{sIMrn(1SQogi)ExeJT9+3o?~rCpG3SKGkWa;5JK>M)_27CyZj1fEoazFba_3Gl^N6?s(>gTFv|nVwZTSH&6i4~1l# zvzOQA&Vm{gQNLUls5vCa^<%NuO$GF-v#eqyk@l_BG!t_~_j%Ag5Ca4+OgyCfc0Z(2 z+pKUjO6eew!qdVrdB9$F&uJ7A>|`?R+)3{TNDNMUo*VXfMW(s>p{mwXxAYpFCKF-- zlKIHztFbja=1Y&C4@EE#@|p3Zo@=^f5Dx5`;R{eab&F8BG?1mKFwD~Ga894%dWptx zC6jN3`=#w({OyDiW`C&UF6_9r(=yo%eJx!psr^^2;TDAd%3Q)nlM{3MqVbh~$z)Q3 z+LkOqX~afkpGTGxmZ#hfV17IMiChlWC6$L1?2_uF4Yd-;Z{di`2-FV1pK}7WDMDpT zet-s(5Z1>i|KX`=6+OVb{D&yiv_7G5kkNQ{jh@^@i888fk=Y2>f@HvWl>T0!5dXEg zq@RoGEj*N0CbQ%tWEvG7Ej(QH^?Hbwvgw4vAyuAwtF!U`^)XOqp&QBd8D!*BOq`}lqlZYdFj!NLiWE?Ec{jJY!EAFU zU1s&`o1I!3J=JBFG2*S$vPvYJCf!iL%-Eb|Nba^GD(TM@v3C&3X8?W=E8koo%a;bb zdT-qea~+4^Z_#fPE04!~D5cjmHVf7UISuDhekFhaqH5BkoNBQ68>lX2n?Td2T$D%< zX-FZM1H@C|!`$nU&Xe>3>x=7>rB&Ro<1$RfOcQ%1CglUyi_*OsR@7H3?aHKqgZ#rc zb{YN3?lBxSnF5)B5lX)FHdmwUGtZVo{fKJ!dopiPn0st4#4(JY5M52V%qY~cIIwT} zvZ)qvT}DpMSs2xo=>iaCU4q4=C20$lLFGwl)yC0}I{fQoqYX#G!rG15<^3Brw z@@iQ;;D>c!1jS-SNX_7$T&DteBhAZWiah25%sABcm<>tq@SCB znx&zd23~7ed!M?gryp2%oF|R_(<|?u8PM{SRp44@7nk!;Gyg~DBi84BpDSdhGeZh@Lg8n&FIK^l3TcVlW zC8sfGQl}MV+EijIbeS4uhTVs1x{zzTTYD{7kCpFs@8VcA?OejD!&f6Rk)y8L34uL* z?lwtmUpg2=YsB+7D?MdkrX&Dv`o~qfqWrmJfS;n!Upl8S2=K~6fOEoo z@jm?nD-{ySXx0>IL{KM_1{SqECov(asas3pfN`x(b_4_5Rze%bCM?|8n4>p~LEmc6 zDSc0LSxBdIigrT`mlXLng{6V#Tnh&d_QjANO-RT3!7F>u6j-|Ej8;oJY|gk(U=qty z0tY)f77t(&MMkrp4P=p8eA={M2(42sJ*wBJxzSFc8xUk!YLQ~@9Yd2fL+2!Z9b?a< zD#WHjLeA!jI8+vkM6yCS5c%2IASbl5m z3o1(chSU25PH$ZnwR929QAv-p$W||jIZaZUc)^g4^|$5^!4Z9du{xdm6dLh97t+C$ zjwQX?6K@BAN*4?9OQ|V)IHsN=3w&V1>Pi`gP|&YlRS*YX$Yt=l?NzVJb8b_}Pfvst zWU}(mScFAFDJuz0QB&XT7&|%>Qw{prISC-q z++XM#>Z8z_NRRPq>z2At;q>~#K}?Sl3Bv&g{a0s-Sh~DlYu_&fc8YOvbOP3{@9}~) zg;Ur{A-qbT%+g4bZWj!(lEIoZ;Mrox?#0?8u}SZgU=`&_M=z&oY{6e`hDusr+FH&4X&cB8CIcBlZ>Ks z#WqWztQxBWBy(tUXQ)R;*r#G9h0qAw`t}c{;5LEtn+wO`tm7_nXie(b5ja~HI{{r) zXDnT39dmb1?Sg3~Q?p`8eRb!y_Mp3^U7!fBea^$d#vI*xz=CEqYc|T0U1iF-3c}WQ zUHiH;(mI#+L=d8M|`=2RFeoWTr9uMACxU8dlT6wchKn()Wym$`I-lnOyQk zZ89}BlbxtLLBC;m0>Ii5RtQ|5bG>#}(5zD}960!79c20{7(^8@VRt8^&rHm8{bonq z`i$!^u&HUUf0h*v)E#cKK3LXWJmC6Xqk|A+Czi!HDKs3qMb-eR&0_8Q!Z~fU9}Nt6 zT5)>2%sP{Dn{C~v9$u!cbuT>{c0Db4TqZEmU7ICx@QV*6^*rn)_LYF2erP~q42q&1 ztm;0c?&Y=G_qnHe^;|Xw)8fQ6IX*UZSE&9^Kp7Utk`dyz%*~$-@{mGia=TPJvWb1{ z4&PDE?KXK@qp#$;n?2o)Jei^1w0@EGDf2Wy1*|u6ciq#69x~hYPjGh2bsmxlf)5 z;hek?CiH3o;-m&;%RzxBvd3HmlA(F%SQnA4k;WKv(lNC_I;@+U5v~>l;>1(bec`pe z`#y2J%Q9%}kMa#K-<^a~F3N@CXLD2QgUeygu$6eHCB6{4kp00ci+PTsi z0PvxND1p&AfkVo`f?IN+Z-vD)BV0Rn(&dC=3I(xPc5(QH-#>>XKM6|tbWjBC69g2t z)vYnQx@E_$q4z%1+!=OGQ>Fwu$HEE2Q;jo7nVk^`F52^E33M4;$$pXI@E+@~p(ji5#qDoGy5{RGW#=AvDz4rtPql11B^h~%BBKZV1Z zi}C4Cy5Z8;)u6kZJz^z7J2!m2iSRZr?-4zVn-qMETfo9#vW9KRN=6mH%GnhG$Bofn zr1Lg~xt{IZv=4F9@g`9NynnLx9-3?oSyQ>QybQu1u&1F6rvgbO5bP?76KDFQWwW=* z%RM=#TR-&;-UkCscH3Z?~8pfL6)t2IT`#iSf8f-c0} ziLij}SG4Z%&WLfr(OfQRYxaEDhnP9x8fS{5r3)e1mI3lvo^qdcMwHK4M{d^iMLkIp zrDZ{RU&~_KlxsDIDvlvg8L)!W97Fb1P7n9xGRwWX;~uFGjpm7gW}-Pbgz?49T9i}P zftO(>t45`i+S8^COjxeDBO$3$K-*#>o7GPX;gnB9&mSYr_xjq&{>*UpmL)syU%K++ z%(CP*0c&is2MSDaaz?ksQ^WVfpO0SQ$&DYWe}XYYi|QP&h^Ml>O~UDLTW;gC+f3{k z4a{Ed&nTZ^ritC`Sx37LuKS>I>23nIX+oF^rj9BSXtXHz2Ak5T;yqkD@}ZKjlbTiZ z$F(IwTyAf3+lM|AFWYW2A#N`a2uIL1gI8*H>`VDZhHS+>;8!?c`Q*N2PAlFU^0HYZ zD-HUqK6JFLmzlf}M~@e)w9?z*wIjFbW8No;!XTT0iXU;M1vur9c`7!L^V4eC63&SiTrd8pQ zb1zqf?O(< z^GNz|dmJ+(R#0z@ z#HR>e4(T@k1jQGu=JA`QwCHLS0GY1*7c$ta5Zv92a&Sh4xH~p85YGc&Z!%kyvE(%%c90%`}fi>dumq>ug5t!r2F(;OJRk| zLHo;QNl;3QP10+bYiIQ+e0wEN$XY$)KxNPboY{&$1{#A)r!5h<_$k$!X0g3XNCsp* z75A1gG{jbqp51tXD)Y`uQSOX=szA92pj_VoCt8}P^lmEP0bbHu{2}}=Lni0)InsAD zP|w(v%6$s>>aH(@EZY^&bueFnS^0)72jiwaxGU=2GBDE;Ipg}UFSaPKkB}nMJlbel z2~`N0Dvw6VTmjM!|CEK9@ls)t{>r2UKh+axX#q|Ua<_nI=~M!~`#K2cIOpL=plm_2 z#`4o%Ep2yBU#u0Sx$*7NJGbjryf-X}Kq%uWsf(ebfH?K}K^q z0sEJlT%wQS4UA6biWWg9wu(jT>lOw+AuyI$zrNIi^-Y68;T8PMw^^5LnpMU45Cf+- z6{PUDil|q>^34?(Dp>4`Trk^*%X^*5CmY-^LN4-od>hAY{_)C_@UxdsZXivS+(EkN zDSkcpH2g`9Sq?^iN?yKva6g<&ynI`h#;8^qzfaus7KUCp4`Z_+gPE$^>>NI0-{Erv zKczD~QV;+9R0+j&&&@}=%v)?b-%#Isl5%7 zH#}9(eu0BW$8@+&{sZ(~Lv%O$+Y2#_I=3&zVq3GJ{*~RZv z7M|_RsbRItdlJ<=R{GRdBg+9#R{{2mb3`s-ym*bS6eVrFWf5uGR0y{8tPA8Ap$ zRNnb7AG*Zu3vn%?db)zz&bYSlwu(aczw?L|Y(JJ*v-z$uy1EAeh&;n#5{$2Yo|kGV zc%iNhh_9a(@>-&k)I%sEvF&@i(>T^Pjma7O6y~iTLIjpE;L;ZKc*2#tG5KkSdr3AQ z9D0FmPYC;$a7@ZI39ZG=1Ix0}!G*yh6#?hZ;^$&m5)o%S0NT;;H2qYKW66X6ruBE- zzbRoP)*0yn+BExHKJyUk6ZEAunOvVzWHOEY*H~xHW|9D=ceR(vEbcEW4wOAw1=)a> z5{uMn=nPX8F|hPZ#nnHxU^DZ)#bUS)RSSb8*-Dc`JoOp#X6fVYy2O94*=2T1ZJ!?JM$htl}WIqvJWW_ z0cw1Nb98q$m^{#z7EUXg7U-e5?&D7<`_hvA(%5?a(sDW4@L}6}ahr#ffz5Qh z&a31<_4-XIdUn4ELfjpnG4r{Yl5wH;<1zVy$jG@!NA&6(Qz*a1Nu9Ty}|#{9GK*aQ)8Z$?NYLw`cBe z2w;TE;4t-`;GRl75i1ZigIGo&#rM^wA5djBL&0VFYQ0-ARomd+#N1aG^fZBXRz_v6cjG5KHR|J5&7 zZM{tu<-L%$^1VvTrSXL5ETti_5;qRjG=8ntn~Kh!SE>o7d*wKqzf}~}p_u!tSL({yk!{ zUFHH)(wGPDUZko`0y@-OBZ^27{BuFe{%&$rWlG2s=1JS=&iK{4f~MX7l2H&6%Q7L@9~SJrc=IHz^r-(?@^*X{fg=X`6W=|YgG;J->SkIo1!vG zEnFX`#?i**yDlg2&?P&NvQqAJ%l5@~vyVhppicg%kk0#OI-_8m zq3PwD%{rsWriS6G@3ANS8WZ;T_Z4B&^va7rUZ=jcdlU@G9>2~Ctz{8q(x!F>RlTxA zBjZcu5XOk$s;6O(W_aje0NhE?(^4}#J)fVYB2 zPz#qYrKuUty%safND*glUg#ZaZnMaU5f+?nM;;s$!Otx_G@@kM^$I!T#~HdlNNfhE z#5x^{`}k^&1T&@>6sS+9ZW=vjaw%%v(p1Fcvn1VSQ?^oHVUrAi(g@dD9v+%95Ck!K zOXu?CI$a~$O5gGF?K`@p&O9^Uh+V_h4KXG5+z>Oq&Zvon?=JPQUimZSZl;*pZwo zQNzE6mfIYH^UlO>^hT23Rb6VYj|wXg>0!j4i5)$&_;}Hkn!rQBeDCP1H=>3=(+1`t z7Kh&c<22polY0ba(l_wQ9EIg23s@~MtHzE4w(Yf|)k{PCfw42|0V-X-T`Q(Gja>(hrDM0YCY8cvg^3hv1J7r=?UymZr{3v%+p#JF z){C)zp&@>Yxx8fYob)xE`yZs>Ha7%gS7HUp5!B>SL9U=(w!NBSfBdw%`(A&*4weV4 z-!7_BZtIeHEw<}`TibxgCv&^}yD zZ}(x5(gup3HGr?(!vA0kaf%8vdpHo69(LNa{8Zzmi;Vg`w4#+U&U%mNRW2D@ep3P1@_@Ibsy-`#TF~E{8X>2=<4H#{b)|~gf0M$0@F%YE7WL00yQsYs6P8H zh2|n>dB{MZZl}J9ue^l7uJcZcgSE?1CY)ighPG0mkY=%HBU@v9Aaru4&#km+UXIJy{)7_tBde@F4>P$T5rp+9`JKbOM|8F`^aUrZAzEE8o!FU}?w~ePYDP zQsQbr?s+vUgw2CZR8J?&Fz|Zhz=~Ic4nKYxkvn68X>(`Re|df4wbnJWfTh#%)aY9U z+PLR@?Lx^tOg{r~bI^lr^Z+gvyX=yk_mzh}pcRY+?Rm+zoa^PO%+dYlRJ z!oJOu+U5XgIc=~LKUXJdp1n+D=26Z~=Rl)O+#IRo*5)NEExw=7s3}^HMq)AoYe6*g+qVP<6nu}MwU1zcj zky$vF^?-c5npKSgo)Nj8mMHLB1mcnpq}H<#Wng4?s9d`lo#*G@$+Z&Bw~@x}S)K5) zlO4OYzh0+MRCR%ky=uV1^t3!DF&YQ9*9!~oGFv#vDrHTVncRXV>p?F*{h6??hsA=} z$$FhiD^Sm=?D^<|7o*D>4kRs%$=5#%k!#+Xas9#-D3EPG5Km+DE=T&aPCPl7@wDnb zuV*wSxn*t2aammX294t2a~cPQd`jeKS;O9rMr%<)^#do%LTzSUf3x>jHO#++^BUf+5L7MV9 zRLOj}>d{YYp#F}0?A)gr?WcUqb2?v|RgzyX*1agP9=3_u>DkzOE4Q|~nD{A)ojoi~ z!aWzWP-*d=?iu>|%;xNm>bhM`3FLw{_OB)s;98$j*byOe{k_8R<+UHaQ+g>VJc@FJ z0PR;7N2+G{?c$6j9(w-7;0!$MIKxmqC+`uM80;2Z4-D)CSdv?}csxcJh&}9(wRcp%o&RQi07Irq$5SD25 zgvQl{!dONwu3kVsrqi{#(p^+fM#i%$p65~or-6Nj(+|e9_jPGH^pDRZwRfOM?9z>G zU|@@P+t;;si+OtILAlowLR=)$67O?SeXw!=ZZg?7N$kWyX;gXRxwRSiXuJ32eB(z3 z7|&^38Ci(zoK&*?=O$-(H&;Wg`dFUR>2>N+Pb1YF;_5?9Rs$C$fjuA#mHQ~J zf4QuC9;xj9)u@Unt33Y5?r70plF&@-eZ3s08pfP;_Kchy-;F*$Q%WO}54gZelV5A< zSgCpNIS6rEvT$s7I^nSx^ylR$PV6`91l;Ik=diR9+JXO^%Kqi7EFG!rRrWhWTubuD zRIX`goXxkZLwvcO##*X#(=)Jgd^sr6b0RwnYM!~o(JP$VI~bXED^(p6*|}8DxgPBp zESb$2Y*^Vjt-zws&1>&c&1}P32c;aT)JFV7DT{EgWKw+#9xf+W;J;bJ=Tly$>F-b} z4_>X9{%5S55ZMWZWe%{<%U%R_Imxaz%v}9e^73c-RiSfrtI#_wbdjT&6KAn*T1HTB+<>kJtNNaiZ4(VfMzaFB=3)I@#>rzL(&Q7V^x&7I& zvvXcqT=DZnZ2c-W6gbt8OxdQoifx~jVo+@_IS32tk*vwJa>BRk9#gPQ_s;6UgK7?F zhHUgnq`rSQ(l}V4-l5u{S!W`iQn|WUD@)!mKx*jMqMy}&Su|wz%^97me>G34&NI@v z>YLrjCy{K9taoA-Rb1z$E#ng#G;(t_?Y4cMleu}fk;u+^N=lyQmX*dwlKQ)>JiV-$ zw*OD;&#IYm9UYN+n$+D+G_!NC<%+J6%G! zUuXxl)80O^GPPSRLU!|5j|Uok220jwxz>ZZ&LvA(TX{VIQi++^A4Qv`0$cv1zoUUN z_tgr8<;Q1HkWy{;dTKQrQVqu1++zqz)xE7Pes*da2eLw(sbZjYU0;q4a?8j?QhQdU zjpl@@iqY!B>cnaGG5|ah`aR1=gWn|>Z`W=gXi#~tY05PqP!9#3Khdf#I5|h9>PIsyTLJLn$;p*t2{>Y5#T%&L$8V4$Y#xGeV_u%!2xZ6^R0q>l}3t_{4X1 zgjTuj=CcnJ54(_fb-xhd(?wG2llZ@A1-1K_hnJ!-U$@k3O;M0=m@QB>JklXJ;SBhSe}R3FyHA$hK+WX=$7#; z_wYTpLWTRi{A(DvY;7&-zg9>Y6Eo0UUSsD8D(CxTrQ}jwbUWq(U!R%U@}PqR?~(=j zZG-8nAwvEjQ8mqG!K9GgSD$dQFr9qiqCmn9Ehb>)WO;F;B4zH5Z#7@>w2o56XAu6{ zmwAy&X8mP{Qs@)`*}{@WT)PU~VvrAaysUImrR+Az{n%;8Ua_y;fmxG$3fKxW#03U; zWMsKH{c@7+C1!ZZRyX%a#v!SN7U?jD#nS3C@rn;?Te*}VEH_Zrz2y2k%E!Ay%aev| z-HoAFjje{|Sy6s;oI`@~JS!_y_NhvAaU^p%FGEWwR1WE#I@)zAqZp@g(1XhI=3Joh zZtzeR%Afj^FM4RSOmeU3$IHzj4=U>!xY7yC@C_ttKi@M}K9&DV+G#ug1-K-yM@fw6 ze>Kx+n+EXWSUdBZGdlYdBZsGi_Rj)m7Ubm`q4OmNopzSje=Wr>XHwGQOkf!k`MVmS z!lOa_v-99gYCHKCpnktx1yt+0)ZAs@3j(`jV?4`qb`BYo+R-4iBOYO~^;vPgPwP;5 zy@f3|3{T>{=gJ9Ud`_eq>grISyko2UBzJoB4*`fy;ti|Y~#ptwfmkXV=8;whOBcqqFR zE0aM``%z{)*;ll#)09unYe-QFuyo1#2-s$w!K1+LIPjE2YvI@Igl`{6%#CMjsP`1x zD~udMMsC`JF4CAZ?{$yaCr+sXotd6KLBz_@VUF^k)Ow-=)GD_WjQq*2 z64$0@mH@P?FVvb~|Ev2J+Wud)Hy?KfJx2EKm2&+pvz+(H%yA!C*q)9VmFe*pP_HS&sCfNagx4s21Z+Z>R7hF z!A5@zUK1;MS*R-)!2y6*&{xOrH{`9Zqr7)^BL#tUCye;Lq^S0>I2tskZkBD&pP|qh zP2A(aJ{h`n*c63%^sv6LPg=qVu`8)vw|V>xeFOVAbwx>45*)L8x{fuBr_}Zx-e#b5 zdxB4nTW1Er`XW1uc;J(s@$5Wc5DtVjoUD{-}Ll z$x@1yXmPt`taU)(M*C9Wa?u>66};BTCXWsbods@LOIu=q`{o4- zIdOvn|J20YD+%Fc<@9P4`k2#<7M4@b)oTR_KV@JLc-TN}r8_+Bv3`0=w;33$>zsk3 z_8o{;+9YY7Mw+BX^`7)o@*oIDr*tId_v!mJLs-QmoqISE&{qh2Q$ANUPO17*gvQ#< zqU|%%4DQ6{9r12G^uWjCRmLe+^{Q7e=zm7_+;=oly>(FwE28U1!SL~8A!zJ~3uO6r z&e&ciJxr~a+plV4UVgr=m8*Os4;ucpJ_own{j_q{?r&b^qSSk$fWr4hLd)A>fC5tc z@ozrN{}auO|1gAOyMHZ2$=-!P%d-H(Ezv)C)HT_3Gs1*-EJROLu94~1##P8a3oq6m zGaQA^@mH~YBy{{|>wa@KDQRVCSX>UD(YR-alwI!`WAJ})uGe)?qsGMl1;DA%XL%1O zP$!H{L}AALPwhWL$MUN}W1ES0WG??4v0k2ZB&6Mw%CBCQQT5$Pi1vymZiLPMtYW*- zwvo(ZUF>u^XH#YQzAny3oBuA%EQSKxl72jXYO#E??60e8BNZw&TH%sRB@YzVI{khA3G=esf-D~C#IZr3DMzYJVx~T@xp`IQf z!|Ig>k;{Whx>&y0h8A};mV?zkxqHwx1LSUre~8FjKH_HkYzay6rc=v9_EZ@cmv%o* zBtAgo47}($S>EKBanEU57`NJH68s`fGUMwORhQ_ijH{w@O;AftZ@Vp*L3dz|}6smyZ1a{>J^ zvJPU|d*>Q!Q^f-T^{cBt0Cqmyd}Yw~pR0)OB8JB=4}bPDJGDzsg40KWAMJV;vvnL+ zX{pqYW}IKV8RF8-#+GMiwWshh*ObU6 zY40lp9Wd=7ix*f_B=IOhzs98R)B8yu>BHH}ZHYQ~yN*xgUteTY`Q1^d-|+FdH(+8~ z9(10*-ImZpqyOM%J%*!b?@11^m+Xt|oZnKv_`bZ`uhfHrYyUKS1gdBCTpMMlXqvs$ z=#96wl9!~hzi4QnP^l%5wwegLYn^wVqLTFOXGZ@t@9O<47>(kvzqM{cxm-9a_bZ<} zh}31)!kKa4GzfgxdE+JACLZ(W5Hq-mrRawVqa%F`c?}2H7l=OZD7-eJ2 zD3+tKjTQ^jf8n7YBWi|;j!bjSt2iK&!a3i9_-bNT;gqEV;d5#2>h?A`RA; z=?g=!=87~=5XiP{=03yHjdaeihf9dQsW=3^42GB9o+6Jn8PGJ=P|ebz*HYO5!xXHQ z3)R93X7ndcI;-v#XLLieZt09VlETZicS1f3Hb;hyT2@xA9c!7_WN_AQfl(kwEvq%s zBQ0}UI{hDJoG?g6d+lIV1*as#!m&w71P$-jE>X>Xa*>9MSOjxH-_)eD_C0=lPM+avHPAH6sNJU-&QnwvtoF1HKhs7PtF|WP zrrHS*uE=F-cAS&6Oyiry2mGMde@5uk)Psk)o2)mhMd!h0{?1PO!r)GMV<<0#(9*# z^c3?gMcO}n|}RQG;5i8KU$7x?p) zRmN4;7kQUA_nfo;yh~`dWk#`MAp=$JPGxI^btNDMAmUJRsU{GKg z@o*nU2xOlbvkfKZevD(hMaXnA$_RL;Nn@N>ai>@P>Z(cy=kW?ScU_SHE)$s(8g%4k zSQ_4Gs7vzEFdBn(5=Q8pzVwWgtRe7o=VeieU?tnP{%WKy!AGtb7IL}Y5RkQW?H3#R z=zF=Io-x%EL%7!93fN<;(LOLvA@>nhut!oQ#&-pYbS*>iFVGjfO9nbTB|8tlKAuu> zy4(3nnQu6C&Le%|L@ejLoOMS0OYot3WQUQ48ns=E&{uVN#y=n>C~|p9?eEkD?rfHa zG;rl+`YH05m`eE_>>L#^1F=<&`3JRY(8FD} zW!2!h_1_qkS5bpav=@8V8O=Qgy-E6dWaVm*L(a8o zNTk`qT{Y#n&a|g#z`d6`(?JRD12oNM3r0@OvEil8v?J>1JVs=4Fb_-6aowu(S(Dh; z?cjq|&%P(+%3L1Bffk1|8uec-mrpSM%qfr7z1EttAv71>=dLQ1)LQRMS#hE6`XHoB zOlOdA66!v;^u}JU216~Am+uCSNwO*ZlH`22sXI15CEhxNg^> z%@YJ*3^Fpmsqi;OckaTFy|lNfLB=^ra1FJ?;UR!GjlS(6qUy@81xC1(Oj_tNYuVip z6&Uo4OU*W)6E*P3UAO@i_k1eI&vibT4wyt07X|O7P<~3%QgVNfPZo?!gfBry)uuG_ z0Cu29%MT=f`EYG+b7xCF6~wukn?}{qfwF*L4VKD-*6%C>IY*CQA0&~@5C3;f7#LRS!7(1xTw!IloomV?@B$IO6!9zV1& zPnXQXCO!Om&s?#k=YDyJ;m6lXq#WvwUu#C6blmk`WtESi>DY^BPr66oY;VdL`&5z6 zUTj9? zIrA2O6~SD?^}1u>8t0xL(mmQ{of8A=c9t%0b;+jW3p>+Po^o(Pw(9AGoJ!w0aSyf~ycK8gCUL#hJ&WjW(WZm;oVGER9?eNb6%H_=;}qPldzO>Pi%;iIU z$8zBDupe#~;Zky$z%7g39ZR3~@z zp)9%%ptg+#Ba)XLX5(`TO}kH#v<5kE!Vbzov)Fm0Q8(2ZX=Qa+F`471EiBV)E9!6% zP4Aq4=Ma3QBhn`P%DCb2%Y$TkWumq|=yC-g8asLDxY>Eg>~x5e8(A;`>zyU?mzZdH&1$p%sCV-G+og^Qz%`p zupQo2Vtu;GUj>+SWcPBGszxuc!#6Z?HHjTQK77!1fz?TIDUSJPXk1d`!>7mSmnBZu z0~u|OGb|}V>dHcW6JT0hC;Aj9b17fRbPeEv@O7_b2YG1{b-B;uts>c*+d*s`$_hmn zD`_xvDO2SjRx%K&+FI6ZVR+=j>PgKJMXj&84Gk2tAauxR%_1sjWj~!xTnm)jOG$Mo zog5tarRO{^H6cz@kX9Gnpe{49x3)c}KO{4K8{!^^bSaEM;>>FpP3ss40<>uGuVqiA zfr$=Q3*iD2H&+|?$_5>}_X3r+N3rH*x3*%Su&+GH5v|9S=Ki}p%(VFH`K^X5ptid+?G&{!IK1c)ISZ>)QtKW zzO>!5ojKXePZpcz2AzV@pNr^tOilfC+614{CCWGaY&DA;>Zh4~!n%<-7DKrs!;~6{ z#L!JP>5%ZoLW5jL_^qyXJExB8q!@2kq|#=jpr-I%;=xh?Hvx6F%SlS#Ba zsGd6ocoR1SWJm>_%`Py6+7ne%l^!j~EDAFrPfwig3QefFij=xl%^T0DE)l(BJ?9%i zHpztgeeN?gfSPUlcI;MzkcCdBn9GK)cIp%Q9EM7mUVy)DQ z&;1CF`y0_=L%y|vlT0(1Y_KAY=g_Q(7gP6OoUS`3O}FKkex)?yazeXhzFF&j-?B`r zn4|Jhlrn;%vS_EZ`Of`YF+DF(Hyjf#)#p$;7f2}WWa+D?-}DMjXu`V(Fz7FVTKaH9 zicuwV2sa4xly$=)Egp{<21?OkwuyVVP1>~nwKA@dF$gBBc_dIpS)OZMdCovwR!HwT z*LIfQu`1@}Cr;sEG%IzzwrE3HSl4SE&|_rXCST}9Qb5)S>lH5he(#Fpw1;Jl#0q6h z2ZPU`5FN!womA!HpBf2tUS}dKPNHBJ6V445B{ynT&h?HZozeq=C1fbed#(kXu)zs9 zIP&jH@2p%&));tX%qLV1{xerGR5Cy9_R?*B9&m2-Z-_RK+qRC{Eq*0#sUp!wK>8t< z2*NXe67_ft;&$3=Z+ILo9P$KCLpE$mghd*;rtJ-4Zgup3F3V|M;ys&3hQV z&OeOjRHmBpAWK#}-!XmR2x}&Ci+yehI9I=o-Gr7wCzc;K+g19y*TTSUlzm9wa8Oo0 zR6+kdg@0za{Dgr;Ee~I-X>fg$`vyyjD$zz9H&Go7UE^%#qD@BmFg`ozr#QGh1BiF`+p*`Us?^s3hx;Hn-bWPz7U#hQunoCI__45Mi~G1Cpesx{aep zjT>;XtdA{PI{8;|PIDA6i$hqOIY6%uIyP8gem?vsCfce1TV)8ddrV4l8Qae}gp63S}wHsbb`#=?` zp{Vl`?}j|s+;)A=a7_8=4sC4mgmI(69AC+VQ+=ntsDlsraKgGFic{{a59-6Xmg3)| zZWcSQoQuVNLfs|Kg```k$~^PHj7WU)`x-%p#&T%meyRR+Ede#(9HMWSAIb%m^< zwxrpk3gv0t>$<120Da=aN0l2Q3z$JQa@RtXLS0`gNi#+zZ#ba_X0I~&uFgU3CcJxC z&HcM|Vc1&6(MET!a|K&?C7!$Asq@Eb_H)S`S$GuJ_vyh>!g=lya!6yAky=SUJ&MIw z{#_T(-0OQz+n{w%UaIeFJIm<`UEA77A*;{nTC?&kvZTG|WUZO_?xpJ0)y!Ux4onmA zJmxT;@6&KQ{)_coX?t7cvI_h4&c+e`D55k#JAn3ceJkYk1tg7eExhcHsfL^@d2dLh zO29c`qqZHxRztBKdSUodsRGL)YIgGeL2!hk4e>ff&!pxq6yuYgqwy6dLMr%n?t7_ zBw>Q96lXU+sGG)Elf~Baw`%fxL@I5}V(O8P>)2%qB+Ha~l)wD+AC?MArb{28XCdzK zgk|`B{B)Rp*Z!KP1dZ{>F7K4nTQkGlpHR2FTU6)q!pp1Wh26^Lf}Y2_{eD7Y|CRMY z<>@S6aU8seOP=zivgE96Ft{YB`e5kusV<%^#%TE8Zl6V{{9z4vdAFQ@uACpqe7+fD z4Qt!>tn#FFv)$!8V(ieIdBb;EIU(|p{m*#$kcxMCX_WI)NOQO@U|mR1+V!km__}Epn-K_Y~>^u5sFmK`=2QChq%S>z3!#{en za|-)KLywcn3}&@Z`A>5o#jsW`67_4=)cpFDtar45&6pm)&?#l(0oi6*bnsyN*~-1^ zq}i{0LGv!X(kXF+fInY1cZW0+=jWt7*SPZ+Iwx#roC@2XJJZYirY#XY9)=cM7|ND4T^bsT5q~{cc@R| zmN8j6TA96H)4i~-?0RaU$Yxnv9`wRS?&V2c9DChoWcuTreNU35C0{MmY%15~efjxs|Gg}{xfZI~oHGg4M*R1Y z(XKCXnfy>N?_eH*`cVfz<8uiJ)pG8R&H5}Y^I zsoE&4{}sR1G4k*`&z`jMHxd(!;2IlEC{2vbD6L+--{jUxvcrdU(r~0{_qD>ge7f+7 zloxjDOn=D!dnCELV&e3JEv}5)y;~T!eKnuGMbU?}&BB$5=Ns9ylc9fsFm7DvWy|^Z zOD@hj#nMJ1P2HI_S$^sTpP4>j-rSV^RsSyiDi&q?n`{w^}>CNTB zOBP^U@_AnFM<J|^rkv-$jhVWTozB5z=Uy+_W#C=y>J?ss&$^`w5w&Y{lsvYjKYP{ z?ic#H2A)qJw4#fy?qV~mn(>$Qnl?l>TQr0;O>;j$(yR-n zC#k&2F`J%Ku;|R5;X6JRj`lRkN8d0a)~B9(xd%j**Gz|~4c>J77-sV>~Y})+m6W37`Z2Lzqi=MmxCJE^S&PqOlI8<}0RjPC53uyP>s&@vu--2IzX60e=rb*@d9X}?F%Ll7^#fAxd= zgSg0|X}{4Uu>ZijU6;cTxwAi#ymNQ-QkmVAWLQ4{z2CS^zXDrK2mvjwSsNeJwj6tw=u#a#R}Qvvk`w=btu?10y%pEkLgeckSx` z`|aD$uZD4>(-va=v@B8EnYAPSt3D=MXujH|2h;rXLxJHkFTKPhQ*f2UK%q6%-wY$T z&p5@uVsDNq{E>@r|G3dIz~G;;qw@)gE|qg|x#Yo)hq~0pN&RsB0o2Vz?d2xG+@&x> zAii>->)xQRf$K_p#&7eRkf3t-zYO_)b@0DnsqPQ29QpmnbdN*_YjaV`3KSJlNZsAo zg8%&S&BEByh$ifm1Q&Z4*Ql;zg#m-sy7rXv` zH_MRK;cg0vl;(b96$xW&zX)$#mfj1ygtA7fR>eZu(y|Nb(dZOXw$ zkB*C8dE}yHt~P+_dU4grpG6p4^}zO8j?8|#u%SrEeJ)P7cx_aX8Tf6frn_Q9H_Fph zP!Hd2CDGLj-^Ma}7Wfl_Ca8a#UD228EbOkN>!NEra)UihWzQBrQv5zu&uZ6Fqqt^KnTZKZ zv*98XlqHDYH-4%CywLcDGO|IPGS1I z^ajWEGcozGd2x=-rlOW%mrsIfTiP)i95b4u!8sIFYX~`wbX(c5rER09kstZO_*}QC z9yDS%mK< zAc(zd)(UyT0}H2H{J@7^7E<B_G7abcaKpggxijl)w$jCq6 zO%X5!c0m~(qt1A?MBIN6Lip3>VOF}qZ#6{3^d!PTi98#};O1D=hHxo_FEaUgJxLuy2$fpYhy{oL;PAOFH-)tkE-_#G}NWUetf`$tF(8IrfFp$5axK)YW z!y$@qN(|Av?jT$kH#46jd9s|9JX=*rqFb*FJCP}``bY3t6{kCSdOF6V?2+AEtfU~5 zzExsGFq)JC3H<%#yxOYvogxn1*E+W^;^N+dI$4g66iIwbL|S-Qnp)V& zzbyMVu+x@Cn}J3l^%PN=^#xxT8Ahe~gA)|0+EDzy%0%eMw2O6c5|r#H;^xax$hK;@ z^6xtm`RDN(>4C0}uhr4_e0(S3=89+0D0?vQF;nF*VU~ivsH>Kj z14B_Px+I;}C%co?zhizM36Siio$DvuuC0}#GqGRU3M8tpTFz}eatguUbw>dPn|VU; zLg(t8i0A;?=FbVN8_t6Jh+2K5(hO7+=+lc+Z}Re8|vNUX^PF;8x9t2FW^ybZRBw5~QXsFblQUS%*>~VoAP( zE7I2_S!$Z|DipTHqLSJUQUiPxSEn*1QsA$C3gcY8T|WHvn<{^kcEF<8*~>BteZ8WA zUyqRYW6W@m_00$z52~euofG{HJa~h^nG$YzSkl3)>x_Sw)Rkj?gT$kgQkeOo?u1$D zJE;#PuEE0ZA_;<{=vWHJ7o~K1J&bIvS48fB28l3$_$~m?OSnB#XaRTzJczkl!rQqo z!RjW`)`}x>^bHg!KGq6_J&vNIJb-sB!+9P)=Dgy#%S`m96H}9I0G+K7H=3RChYidK zxyw2K{7Gq~uR>))-zvTxiITic!8b^rBAWmPek>^sx4`Uw(w236-DOays2+D6CXb_x#WT7n$-%~^c)syh0!67M$JS?bi>S$F=J9th0 zav44RTAB+^r#J@+Bb&Uk78BQ;1x(9ZkXhg_oWVAGAp|g|SPr*EKav3gJCJCPr0Wi4 z_F7{g$K@MJ9@LPpm!DAMR#^ilrWvUe(ZJ!?!%|7)%$WAJ6!Zm!*1i;RT*T{`!r|3M zTZ%sN{h+UAgj@(T1l)~VsVM;{$)xnH08;g`BM(O}SC`oPsizpYhdRBNm3ur^c?tAo zpX(ng$X`Rui+uKP7L^+1^O!)w9oR|C8w`K0O=?|gSZ+2o}q7o?jGTX4-S80bsi*+ER4fCI7Fxu_?0Rape7c^RYDEo2uRKKiK%g*I z<4|xp8RXyA-R04us{mKI=(hSB?KO|bE-Y-h zexyb?eZb~lHf{n6^BrZ)-4qVy*18|EO&yqmqt-?p(FtJaW(}r2ualS*fvNYiU)_;}!Z@*dTsecgh=HClGjkg+QpKQdeVOl_F?+ z`t>+3pr$%SweaWk33%9+#oM%aVM-uJ8A-pUg@S}h#67Z*{D27;5p7lm3?I5h95Ds^ zoZ`S0GL#Prt0uEgvPJ)?%Jcj0J{)Qfxk%ph){+;<hYpZnoB)o_fT{+z;rfr?^sRKQ7$x$<6Kf-6g8!*vO{$?49-09m%f23lpZBt&>=LIEC7o-?IT z)cl5t$pz}CB0BO=L=C6qp;>Z@SKiEKVHuM&l~!RwwGN#MzDi*lq;01G1~`$La}6xy zGcPAgyx^?BG!jVF(xjNISGLpGWrwN49s`<19s-<@J-ET0k>OUr03yANW-P)k83fKL zRRe00iWLDFNc=8yyl!Sl$~g}=Qpyj+q^P6=!WvWvXZU59MQ90*(r&URacgIeNlYLl z6P9`r5b#}|vmx<1ekfF%1#2T0^$9q8J8QI?$^VLt2$XV_L=ct0Rl!O+0<|fJqIgW3 zMJyDZZT=8}(`%qc0?RSWc!-$Zq-x{^USQj_A8T3$itSkVbIc~>kOZ3cT0AZ?_+3qt zHa}RRd|G?A{G%M*z(5xH4H*>+UXf8%Ki(i4Z}cZMcr<&pxOxUCu&!$6oeFF| zKLW{EoWwN<@|IHXKSCm9nyBH1g$xO6n)~4ZMAcaY{S+Z<^6^n2JdRBT}n|h7nJVFL=!F{O3+i z8ILh*;!Dw?Q7xGy!_^{ex+$?vi6AXGdsTb~Af-LCiP%9-sZLs}!Iuu4gDAv=0F9NP z+u(n#m8WN-o}V#n5KlNJbU1w$GpKqsmcXgV}gQO zW&DmYRJVPJKuPRiXjrNMaxkV0+8Iu(PXX6}?=n%U7*m_NK0)8C5Hm9HkUpl=q5=tU zfR#4-ure^w&IUj<43bt#{Xj~fPOMTGW2IQmPn6iNbQ|>)s^NWmgM-uN!y%$!DTT4> zpX{hEmhuwh%DApKO_CtmX`0zX7e7V`mD*|^W@!|el$L7GsWxe$htj;ujd_sjb9w>= z8JBC?BIrxr@Q^-*FAx^Hp)ntJUF2IXWec@7y_7xuD=ge)gsDRDyxVWQl=O%a)Tr)~wsws9TzRTk&p&QP^+zz!tikYO`igjlULV~HJwq(3w5%Y9Yz zc{)GAk12M;0A%#)_cef_!n`8A3`})|I`KZ2&8JqlOXjnGvotWouoKvIu!Aklhe~{2 zGnuP;utXwR+?py;yWNVWH5_0 z@GpH9$&E@n5}W`J^~nnyB%50i)v|WIdZscpk0Rcvv?5j!m=1n;EsYOIs+IskWv`WS z*G>a<-hJDcP$|e}!cKW#>>{-=KP#1NX+`%G^j%&g&E6}ipPNv{qn?FabIR0=h7U8yyIN?9NFX zz2Nb9v6em=kq{>3=H-3Gf5A+%$bd9&Z0KK+ta>T;61!Avs4PSgCsfmKxbKd@w}Nb- z$3#ZAMpVs9&j=HWZ?$1Wpv71bMC~L2ODjKC`m(=&6Q?Cxf3UF5xMY4EkRP0>RGoJ8 zT~Ban^&|-0Y|l}1PMaa1BvYK#pQqx&UI1oD82#K)2X7f%JQJ!^1Dql}j;Yo$>Td1r z7~*JReqHwQxfo%hg7J~7mpGh?OPlBEK$Vp5M^3*BV;Dr~pXkPza=`n_Eo&6~k5Yh4 zlD}u+WiL-EW;@pg0rgfH_{1}FSs>87f>?|j&@aUc3X>Zc+MoSFn1+RGFjP#8LX{wf zDhrOXAt8?*{Jd!A4f;Ur=N4vYagw2C4qJ4PZbMmn-U77rhnL?X@n43Y_xv>_R%jQz*P$F`I^-A#}qp?Fz}t)E<|+}hRSAp6->`-I7J)* zzAO|D%Iz~okt#ide*k6+ySiHk()g{xTX07PoD(NIn#_l<1V>Ccd~k;X_DF}+qe zOLxh@MAS)^va*S+dgNkyr*Qo{YUpjx)o^t58m|s2*vw9PxLF#`UB#)gc11&>9HS%T zXaoTQ8jk~f)O44L63MVW)HZ4GUJu`>Un_-Qtc`}r3QCcnpMjX%hA zgls#r&20{CUfeCX$E9#Ib+Z`@{rl<*Gp@2L4Ne+m#5Wr}yP??F$1Dpt!YmlCVI^)b zwih!vQUs|Hm1BRPU(NR97YoU%dvaF(P$7kcf z4z73$a4N|3xdsm0)3z+BS^PxRoHx*H!`a&|JoRh9&eDZfp~%5a0AnuWX(duRCvS{n z^dyNHrAA^IHliH-^(M8WKGkanX`BS{K`2d4hBX$m$CRVPgOWd2XTx zJ$m)-P>C2Z1Lbx@JHDD-#1V=@WuOuSvS;FTz)-8k z6tf>jCWO^l$JCmv8@#JFE8-%#k^q=WLqz*Na)P(X<~ajoXUk3|oeBqov+akL{(s`` zC0lY_Sr7DF)UK3xO=MhJ@;fDkL?T^>}~d& zp?{2C`7#_m#ezvXKeEt)tJTKH1SwazCFIggQnG+sQgLX*XdMfc_=hk}6T{dNp$=#{ zBi&&Zh=-DZv`eh5)>>OrqZNHc4P^#P0H;isff#BYl%{pb*+{HPZP{`oym|yus&bFF zJQGa_w^A82>0GBSBIH8T?EDKtt;RL|_@S_8z3bv2m&!2-H6`HLcpIH-O_!8^;XD$6 zW-7E+`wk;xTJlUFmMYqZWf^R)VXMF;$P<~Mwoc8UPV~Lt1>-swykLw1l$Oj?S45G% zzS%PWuE-Og$7!+8rP9{igxKg9P=1NNS+!z}(Nf`q3(%Mdu9`eWcNA3AzyP&X+CY^a zfUp-{;t6czNF=0UHCi8ZP@cbDvEV-^HfFfmOo{ffFYiOenBYh8wT4(@XLl^AW#sCj zUO|nS9K%7%Y*)CgSK>7CKB4Zk^e<_LNSdem&d#)YOxE>r|0+?O>VtPy2Og6oxjlbi zJWnZ@&K4J#dcExjiE`2S5M=8rt#6WvxKHfo$h%m%5}79tuVWwA#hBi_Bw9Inh{(Be z90MaOs=@3W6vOx|$1p*-+#8q^`?Og=uE9aoYTF(d%*Z}haKJ#W9*22S%0I~`vysNP zQxLD2H!Lm?JXHE8jw$8wcD?to_7ALKok9ldo7bRH6BTGWc1ekF>ffW8I3_`gRJSxTD)Rt;hNiXoI*azuWp3_&x717rTRF0f<&Azj-T_uLj zP?XlYmhaZrI8YzC9izI&?%lGDIPZ4kgCho|W<|bm503#Ye4$<#n|!Z@ClU|%PYQcV z#tD*#zB;DI`41Et&>bi=_SBtJ>+;J;I(&>wE6?e*P!#oZ-O#WA6B0Ruj*BSFO)oMB z6f$~+!Yu3&)C!;#In9d~5<6$1e|<8gD*a+wnU`cjRlAxd{kY8KDPihaP}1_4cZZXi z>KPN^sRj}S9Qy#aRG^S3)jj5~(jur_S0`hRe~8W(v^&&3Ru zF6&|#GUMXtF484qC!l0xqnoqlyo0+=-$IgJDD2<^81rqE)0F<@#>PBzU4>;N<)jow z(@9he$Qqhzv^u9Fz*uk52XiyArlhVD)9k)I_Bv(7bF{8tcX+Z?HMb60FQ!VxgCgp} zL)!t?DbDFA*2*YuSz1Lzgl^@6i!%#fsyzutW+AC|!ARnTtL*e<5-5KlS^DgOnKfMzJ%=)(NPj<# zQVoZ$m6G)$qsMnhs-XCY^zPaNI)8nYjD!ql<-^O>-ykz5Ax+AsokvuzUZqA)6{OK-D51<$`asN$0c@kRYlyXw!AU{|&up_4}~RY{YsPwb7# z-p0#9XSUt%uTlfcVi+Xt!ylZeI{j(Ast`y<^?v)w$X-rObM4_#Yg8#{P83kA*i%KF zRIvA-8ZOH<_D}pvjZ33>!>^8Xp8vEQ4a*}?Pezq_FS=8xbVEl%-T>j1(D{{R=9w;; zWcTrwRS$EnUQX<^OXII9qb5Q7pNa%I|LOykR}UJF%eIV0=KhzepQ-^ZlUZ)*xCL*2 zK^0No%bNdLrS_z@Bb{eWtq0aAb(x&4be?~AolH>r`yl-84%mtV3atA|W<|fMH>y-Y zSe{xI4-(zfc@T>d|E`i$yvsdFdqCRcb5O1FB59g*Bo*J02q*B;3~#A#K*jESd-|Lw zx7_v*64oy(VK%T%iojo@QNd>aso7x~ni-kEFHvviEP5iJGU;?SDzEEo3)tgU;d+ub zE-g{8nTAJxKk%t=v}aS}_mWFcwVl=KcbcBR+oCK!f6xPw^;df;UlYdZH7Glkj&k_0d==NRyAGz>arQplA1(e!Ehbn$<@1+_dEZ=grxuY z_Ft7em1qJr$*})lKmYSTz$`yQRkHr~Ip@R^JG7rtNKzykdHnw?neyI=fU1f0%mbU~ zBIsJRd(gVra^;HQH&0}q{&cfZC+|{udHUUD37yYWJA*?&%>~KSw;!qK6B7|CN2}L6 z@AB$-)M0k_;O#Nyf)9R(-PX)!;KBC-I}mx9!7PTAIe=$}bt3UU{{F9eIRFSCK`EC0 z^)0%(&dF)r>=h!PzFc*MD`e((M^uC@Yr~-k-G`cKpSW z#60Ej?T{HQht=Zk9{#iCu;*W17Eln6Sv|>HcQ!RM(8r6Y>ee?=8_Yz=_S5hXep%Pn zz9aZ=h0ap%>O?fpI=%$;wNX{N^SMjR*-34R%v?Qd&9Fj=O&B`boFz(?x0Ut*MN%4t zmE5^n^xD|H$PtG#C$(=of8c74j995KQP{Z`Vr{!g1p;LH!Yz~So04}ZzB*jeR2@wlfZKnC{q z2tvkLUc_W&uH)T*TA6kD-3q(t73}z9U*(XGM|Gq&N&y|ZzxM?Q2h85A`9BY!6v*`o zH^)g>YwCT9wRVeMr1n_|HH2dI7z=>uc>FTJ!OYccLAm+6UP`q+yO@W2sIQ!DLmibB zesTWY6Pedf8qQ0K*8YOiFRzNN*l7kEn-qs`=p2=*YYvp}od5Ld#6DC40~MKV5*|f% ze7D$~^2&fxo$+X4|M~sn8mX)`SFiK)c4m){T5@}Ot23a= zo`lBjsSG`f$veBcB{ENA$inZNXB}GY5bK#;qza3aDwf{6#yydlz1{_>7q8d*kn5c7 zF${3V%W|0o?yH1>m9!t#%O*-!$>?Z2*Rq*_myYbt@cuewz$W*Uy(XO1++4g~$FfN0 zlT#X{vp(!X)EC7wmnPl@*1LFK$Di#zE-DH;6DJycMc2h4Ez$+Nc25_CQ!AB(gw#DU z2UW%-twt!qnQL-zBOpX~Z7B|wPqW_>jM2!NxxTU<{@|Zq0B(v3Nd834;3@cNkA z`w7_7{K@v1qTKIOm`2VD7eSsa@&OA2b+g2~#mvy^!rN?3hG~E|ol|IcuCmbf7$D-p zMQggU$Gttrw8uxd$U;pt@WjPS8dGr;t3qvLXuqP5PJ()rhzd2=Gy*MKi?cnap5Xg@ zG$=obVZK769RfrchFVXNqEIa2MuD>vJ-@VR=z|PI=7x zGzz)b>`ZC`!0Vvkv^N8%MWvW{ai}3@MK%@mFVF}%uA{I$$H-234l9){(Cs<4q4@ND zBIn5Bld$sbK%&~XSrrsyYk9eKO9N(_twi-X=3eV_MoUvV3GdU$l`Vxf>Iz4Q#WOZW zf+thNEgr8Qo@~zOF$C(?%vZt+=z5P`YMtwS%B%&Llo7wgz0nsMJP1#3NefE&f_;NC z{E#oq(zzvDldDn=J>5z$O{86VLnp`1n+zCh%lh`9==JczKumTV6yhxI-uQ?XnL z+{|N$5jJ6D{>r2EIimg1Q%(~;Ybqr zCII`n+>($i%qpg%u#Uu(R~V@V)3_oq6{91;7)aS`SOe8Ib$o*`g&7?i&t#rBO z#$62p5{Xh)@#Irp(S{z=cgAm2i<(TG$ufZe1TWY`k>AS1e)+OVKsRw@lY^NBh{JsN zK3!9QY8cv$4rL@8G$=DZ#-uj*f`nICVjLU%+9Y4ox<|^g1)JB*@}vwlHp(*GV^wW- z@+69BDf8PbQx>_mCnwUZuF7tImwi*KjD1y}i9`}}0DnsbpYcpCYXn+PJ=buUz^vaj zug9`vL47X9_!M0pwL}+**=5nJL~{n9n42tuP(Gszq=F9pFY?Qx|lFB^KZtbjbcy){|>i?ipdA#l6pJncwK&bRMr*woX_a z%00`@_P*CAiEg2+S3O1B&CQ-!#$+D)1WwhCrB^)x;uT@b_bw_*&Vs6uFy+d_P>8NB z2vb;Y?{+4PiXMa+iM*ohV_K%{J+b&F%6g|IJ*$#4s##V=Rugb0ZSY#H%s%?JOuB!> zd}z{75;kS1F02wFs^xK}(3Ap@8p-Cawz8nn@>xo|smYnF>;#56a4UgSyXATaQMq>Y zVCL}^e=lvvx+L1ww#2V&z}4B%A+XigML{`S-a7O6tf4lE!GmXhtgK5oLiX}&YU$RR zm|v9;8^znQyLTf+yUHir8cbrDmN5UvG^TObm}PZ=@_6<+<}Uip!9FlcVks3>8*@dZ zKP)GLS#FvT7TZ3uRdU~_X%_tsasB0KpE$LJc_*59CMnLAD*I>Sau!+bT;9%Oa9%G6 zV46+0t;c~XW11Gu!}h7NS;bHcgO$oW1-Y~XCJfw+^ogp>#N=KSIjR1tN>AmKy)o95 z*lAV1yUFfA)w<`(mFo9YrPRD9Vdn#{YNe(lYupcfd$ki;HjZ_ivbyWvWY(Wq7r?~M zL6(-H9*x7zI!t!Cru|etmmk?lkqd(K3-iMA-V-lC2VLxg*niLiC!jvZrefQ<3H$wC;f8q(LFRxZE ze$v&H>#Jlmz-xHYSJ{Rd6yrz_H{SYZdCn8w4kWItQ|d1F>eQQaxos%PwQ4^gfSZ7+ zZ)W+h76xHdvbklIf$&SlzDtJ{NB49@zjm`g#!WF|N$vvAEjQH=t2AZNobs2VCA+m# zvdF6^JRfL$L6@XB_cSU89W=59GNE)UQ=H$TQ%iZ20Fo^I7M8nb^wLD|uYO6=pN6m+ zaSiqSFO_iU9V6g=WBcyAWU1TTlchCqkd@_J#U){y6=bMr0UIoXl2l4#AboqdbGCir zKNd6BJu23y7nB^>B|$&kmypW>6~A*=(MKX%dGX8xkG@KShWVvnYvcYV29lm*K){UM%aWT|6nX`HC|_Tr~0Q3n}=*qd^Zd%1)$r2Y4E|hT7sdl z1IjTU#Xj9b7x+@Gpk6mYI!R#)?_wpCnHlAAtD{!I&Q?emgVcp>NBxKpX2NNSUDONE zL3EInD>gZl*C^0G6;6GKS<`vvJKfR> zDX&4e4&AbMu)W)vS%Yp_xmv%RZs@LCRO&;7O^1I^x|Pel6fvEA3hGq|RdwC`#pW~K zxgn|RXu-I?ug>Xj<a|XT3uvz&^E-c>l&OX}D@XiMBNjN-`IC|zz?{+6Hm3(GU^z#l9 zSl~$RKrA2kAzjN=829#Mq-zjA5pXqYmZlw&s+9Z01w4rxmEI0fO{MiiECZZfA#L=} z?a;d*IV%#{o1K+y^v<>VF%oOR=w^Z53-o!;cU+s>2`Ujm$L;F2Vf@cNdz3mEd7&Q~ z;1Eyg`iJ;sQSHRFjiPwzo#Wa%727hC2f}iH?QSK6ijCb}oGcC9*!?EQTt2g8J4PMb z{F#Wc)3K**y}`uCV;9N{9vv#iyM2mf)3(FNvcV^VNVQY%luSThK71^Xjy}23HBjs7 z`cKg{EoYB(4N}LLHFoa88-m+vnMir|fXQ|DhU~27~ES-qO&s@{4Us}_<5WlHl^BdSko?ZFjfm|bcn;$w$;^>Iw(d7U}a+R4s z#Iq@$Xe4Y@F*m`L*N`1|N(LD6glB``iRd?u^J6V9GitJn@|!$Un_jXWm#%oEcMpor zJUe;fn&ynuDqdW%Y`KjD;yzmmDk$x1!t8oRCCwZCvL&h&G9rzSpFTS1V4gRJrEb#N z(!-~!GMkdV%d+X_j!_y%SFH6?PWYr~P0AigyY$8XlAaNerD$=~Cdztxh}9~`o_<`rdIarKe1!6Do2RyjVBW@_|G)0UfnP(U+S z(I}3C>uR9FK^WCk+MAsXNbk24Dz`1P*CqZpn=hJfvw`xVV&y`PeoUnnh!r!+a;?}><<@*wc=nU&G4YCMEYn-uk}NjHZn>$9kb{Y*F(U|BBQW{gAYBLGAR){py2LJMb^pGF?&l~nSM=sg zG8I@b#?gMLGR%f)%ErxHidjv<7(}iIT)LDqqt=UFwnOj|Q3wF%guCtC{&H<e&kSY?zOe{g zE}?giGXRACx$QmMk)O!|+DSqVat4@`8`i=uu=Ol-QAIJ3A?rkR!=;)uEF91Xy-z?XF>?gWHi-uM6ePPn(|%B6=W;H1b%^>_z+pt zcZpl>j8*IeAI-E!L#Rt`V6EW1m2eC;H&b}QE#NLFNb8mioK!q!)@NbAYurh&fspM; z-mLGiTuZtoJ7ett?~UqMJ62N`(*!Ut>;?Qf%e=kXS+|H=s$J*+*(d!QtCda_ei$2y zxqtaxx~3DtgDHexuv{nbXX5k&`macm;d59r|I<*CS9{7X^Z?JAa%S>O+?Vef3JE$Y z`boe)BZFBJcQ1p3-vS}>4PL<=hS{9kn3da%RiGF|b7cE@KQId*_#b5tG<{R5EHnWD zDjMVtY~zkt`5~&NP^-}nW|N+q%YT`GV+yq<>Un!pl9lxwPoZ(VZg65ew!2xG#5U7X z+Bw-!2YkXMeu%1IM{i?{(P=RgXrkXhe?ibT<;XO>8nKoUA=?0@4+eu$LF_Bkn-Alu z>WO5W1pC?6+{*beZZWy{bd53?3CfNN8=Ba!#w#yGq2N5=eYYh~k3^}Mvf^Oh=5d6O zmCexH!ax6qJP!Ut%u=^pAmx#&e$))#2-MueRq@dy#kv ze%P|H;>JH>F9Kwn#!aILUXqo7P*_f!MDfqzeevGT5o=Auk+{Y$pnPh|>j}9(WC#&9 z#lC%kT^!lft38-^R)TIdUc;*w?RvuNw|sHvnoYrlp-23lej4`JCMvIB=F6)E7-#~* zz${%g7SR;{OjmA6wZYMlm7Ry|Y56Y5v!eGt@c1b?r0okvBRAR0ERt846|Erww_M_P z4wl+HO|~-1EKrO7W!Y;x57q~r0SeR5j~GI%GA?~j(;$MEr!A$$gZ;Fha7w@=k~LC5 z4&`ZI=F_SfMAIC|*NdOSwpA&8F5dHd3y{jRi+ES(HGjMx_euQNeH>PskSu7j)VWPe zM&*y(GOR)IgjMTgiL@s^Yn&+<&iiM@wL$`l*X2rS7;~zdW}L~&=z*jdZMpKjIjvEv znm)d1D&(XK(S_q?BB({yD{e!Ke5&k7GKi*Lqq<7;u+}86cN%WPT zs!c4OSPKnwltqE{)o31B6e5c837+txZqZaw!PIq^kL}29S(2J;ij@ ziDEPSsq@k~`8V49>y-qq7TDB)rX`!vh~#EH>2CJzF&xc^C>PpPk+t-H1nDKJMK0&H@HW_Xfl17SH2*CN)q?18jU;>l$}Y9FhVb+rcnBA?7K3Omrjb% zbmJ_6Drj8sKe>!h6)45{!1I|2hDQVSLv>KBN?i7J@ss=a0Gz7XJele9B$XMBeX3Je zj7lDG!Q?^yUeKwfT8(}bhr)m>LA0Kf2-X^#xGB9-JlK3FE-YinnpSNF*d-0eHLj=rrxAUfobd7 zrGh-ut}(y}B8Q!}IKhg961_qdiT35sHVLZ8>}yibMDcjZNh(@ti%nvK1WfuaN{`L5 zzRxRrY!{Mc)>uO)8!33FMw5XGJF|#Z)Zgl}X9fd`c4Kjt;?`f2d8gfJq@U?%lLT*@ zcm1;or$!LT<@T%V-90u1d>h;2ZPkx9^24$$!I%W@(8yIViH_zJ&|o)Cdq+0eGVX{|J!c9}Js_sEe;cAogtT-MwCA=CHXX_U0Wpp7bF zPEmprKxSKh^GH~M$Q<9U2XKi_`2fST)+dw=99!5E_(0e-yA$c37X`jgmlEW}-t}au zYEIx;55y$fc!bIdA`Zrhs%lx+NAKAO?e$r$i6uNLxC=`v9|#lQNyG#U?A)_0l^;?o z6`u){MzuN}d38Y@3h;rJhGT5%_wTS~x>}^q2D7VBK@=fbXn4Po@_`!p#dIZQwKX5m zpDdO6dOTjC@8z7IAWR>qnP5yC30&98)o`Mgl;pnr;#o#0jQrBx$p;F;OxgMU;>nh6 zy=wsyKHZZwQI#Eu{XoVwBQDwazFZ~8zo%nRm&;)ZU=j1{X=~HymgYTB70zC+nd~Pm zT6R>Jvo2}VrGLGPxtL10W670s;ZFvHW`oCnfGN|0!br&#yqy$XO}||5Wjg=z9#@yD0Hp0l|8^aE^>@-LC{bb#lAkS9ER9O3x@9n*b4yLfFXae1Oy zBza29IMZvLIE4y*z_P69DuEN5^*RhY6m@NtAyfM@BKv(71t5MeY9onhmO~xGY*}%p z&JoYAS@g?Y51LTlFlt91Kk`f`E&ES>S-E(_??4Oa#iSD|tFK#J-zQ7)brLs^WVxM$ zI1RITplV9Dx~_Gpap!KHunnMFNp*in3&<=HS9cp9^FDpq9Js_b_1Xez1*O-2sQGs8 zRZ&{hj?i&Gs-_)zL%-IBG^Z3~Y<);=(-=I+tw8M|*G-A_S{x5Pv4BIgV8`(<4eSD| z)Ca3dpGHeTL;NwKEnq7_>O-qVc!fdPR+*lfsni;`>5&1h*gLCv3k=C2rj$>49A?^-%rI&77Ki zl{2cuP8Nz3MEcjqutq7nOqA=yt{@e(C)}n8z1%KHwz!xbNf$be*Qe~#-La-m>#=UecrBgdxx1T8{y0;{R9WAy&PC_n-m~a)PqA}Qc{mUtj1B_8BiWU zPz3On=B(A9HiZ_SsEE&<$Vp}WdvoJGJqt)?5|50G6AN)kG1x?s0M!?Bm9VZjqz8Z1 zk=I8cqA-F8g=M{Gni16|W<{{8;nINS#P`nOyF|&u?``5}5|g;=f~Co8ZAxpae@{G- zg=d-V%pLJ1j6b*4383HOjIjjLtli;a=ci@Wzl??G);^KOJX!L>7$b$_CdWX zII${1tUxY=bXN}f0u_D6Cqb9SpC*}*5T}da0xFSNrbvhWh%!g0z&fAOHN6+V(Isa- z3X&$UA^`(aUEj@Ocdb8YC(Yy|TsRwfxSL>)JRqZ2tw(D?G^|xn5S-X1xo;{}z{vMh z4btaMBF2yzq}EQjoi{6ySt&0iYJaLzIS?>FEHQ26WZHQcod7w4qKn*AZ5(KNfm3wk zo~ALTXMqFN+QQW~9h5ngJzRbEVtdm}%%=mD{l<5pP`DL6z9;0v=DZAcD=Ju-u05ijf1$i-#TP z5)_MWXtc9bV{fxO={}2kAvr;Dc06MF_QtNi*7=p_dcv=h<8l+SigQMCB+3;VAnO!u z*ms}Zte{36WnCIJ(C8R)sSC^=za@aKA{i_eL@ub0XspG~?@~ywCq~3}vx9ds6-YM# z0rwLG#9Q?u2q-*7oB+@ua8!dd`0w*EM;nfmNHvoR)`x~5-rB4h=T-_m) z0Lp?5o-B7swA|UiqA@-cK`G`!lY^`$d}9nHWZ>U`O1NGziR55_?0<-Hx_A@Du~a>U z3QlGjz;WbV8F8)eF@Cy1vBSD2G|DoA%Sl>_>A@Ao@Q)vEb^CXPQ;IaBap;VWpV~NRxTW6`HPb=wHBHk5ny;B)qFy zzCZEVBiAnNz5sWM{5ny135vVKLB37luQh#35e~RiB@UjJdK8}vNIS(=o+#`wwGDbJ zslUQbzfB?Z=#rFPK(ns__zzM19xU@_*NAscT!aG+4d_|&rT2X}^!!WSf3LW+b6eIJM3h*eU*S(N`BR?>gJ!9ga zgDYkK=T=4$@1h)i-Ryajg&9hjSecQ9*V*e=hPy`|s!m=lZ;(L=t);i71-4bbZg@ zl`&kbr;>}{g_eje!Es5z4T0jatMzkNE6ECha>k{!PwX-Ef}((<5blcev|N?{9xMNcpMSQ2X;{qjnQBX>^C#LjcIB>}L|tPw-$c{V zxUeDRZ9ZDAbI-@o!VIOOtn@3DpxlJ1oTmXKBhVHvAD*UxMp0EX6A9tIMueVU8>G}z z@@YzqU_;xs%UTY8y)2mV=cSmte>ag^EdfRvwpTM$-9+q8RCU3#CP429ISg;D+nkQ- zGg%YQJ&V|G*m%?hgCg13n4Ms2d}LNzz4ZF9-j!7?r-?oeQRyWc#}ALKl{el(1Nt}> zJZ&}9{!>Gc^{8HR7dF4GDPjM2gU3_}9aK}>p_Q&5ik<^=^ed|fJ~^1Tc_x=wu`lDx zwM}N@yBT>twI4!R|AXp{|l2;J6)s&0I^A^)|9y>Um;W*H0bj8qH$6RA)St z-=9hwAd*&;>CaL(w!d|+a&C8dMB_GI!wVOYI_E(*^#!N(Q@w+(sou}8cgK%TU>v7 z>(0l+YQTW;!)>+syB5V+O$7Ah>INZd%i^zJ?T(Arhcfc^LoF~l%&a;waIv=pVyPN^ zjf(lDcx5;!Xq+OFC&ldj+#7NlJl(zVq^o;=H1@N$jVssvtQ#IOEM+TmAU@sZpv#WU z+fq7hwe&311^fD5s^_6fTG4@K8R*Z*^|qNN8zUd~QoT)}y8k@~$4x9xmZe?2+BstR zQir|y&bP?|l)5LY7fc&RFP0;odjFkQ-!*3Re&go8eUsdC2*I-R)7qaH&FJH(jHpAW)By1d>tcqo!!;P`dR5SiRKZH#+mF#KUhV_CexVypyQb@30a?LJ&J6z` ziqBfdL0O)crQL|*J-bjynuKDtsnFxo(Ev@bJk* zo@tt&WF4qjT)55qyiMU8xQWR}jF}CLMiMfzl+SYOOIb-gu?RiyF69 z;TyW%AeY4%sHm94yT6U*#JcONrmkQHZ*y*1;JdxEtS02+%ne5f}gg?$El-9 zfxR5Fem|qZ1Dey5$J8Wgma`uRWkXVvN2*WYe$o;hL@C7AwAHsxz-+K<4ebFHKk&97s z?^vBgOfOD$E62?}vjB6gfqKhA@Sd!~$wgFh^bHGfc~EZ)=`^Dqy*=-2UN^J$2A+X+ z%JHjL>o}GvS_bymTy*0s#au-svnW-5`{Ox>qE}9^@;G+4IsVds5a&=S# z8-vy;W%;*hoTG7R>rq}x6=KsyBvy}cVq*jC`VbcZo|Z_I79H=_)+mfzv|eB?sl!oKCo|}x zdQG#;?=n%irS5XK?qg(Poc*qgzgv{{g47)i`khdbw@Ls##%-3vrthg7C3Lg~mT}#^+#UPI;3Y$pVc)>ie`HtnxZZX6Hik`j zd7`p+dz;QZdAD04`>ZQh(p4fmTjq+lEjD_a$Z03$MC9;tTX5AIkM8AesXTN}(&9gb z%F)n%s-&SjF)L}Ds2o|@wr)OoxmzlS<8n)Dq4LsYzMU*;MlJ=YqgHOV{rcT*X*@V7 zqX0*#G!CI*GtF;HYZiAc#Na14c=u|z6kc+1j9CFF3*B$C(f-*rvopNhw}0yKKY6)Z zDhEEcRi9(_Q318@mu{3kmlEQRk8a1aF|Qo;^}F4Y*q;@wa23lThtw7N5Fe+d{*%q= z-_0FY^);^F?Uu%#jg~)GlQUFJwpzgZvZ`_Zx;{e8l%u|Ww_6&Av)at+SkY;*-TO37 zaj|!NggLA<4wbp>-EL_-_~^UlKFf2)%3M3Z_i40C@O3`IY2CcrEsX;oH<=#`tlQN2 zyS^if%a>>z-fauRuHWsJ#)FUCPg>>Tk1|_I2jU;btm^ z68`>fcO?4iZ*z1yT%KXaX>mcYdw`p{yda%eovtDy@6$M4osv-RC>M|KR;_AQ&gy4q zSjn7a+h549jG^ej{&pw3f6*=|mMe1;;G9~qV4ao;f2h)^L_cBU003KgwL313&ryO7 z!>ss&)j6(1X-7pFmvdv`=|lnlbd1Y>1)JmD>0+a^O{Z0SuDkL#RBij~EQ;@MVr~VI z%q1VSn!p~G_QBx&EJf7b?uhbtW!P%}(Y`HOar*cOLHfy<9D59=VKzfFSls(ZMq;q?!DV-8M(mZ;8r!xnSHTQaA(%0Bp8r0{}UP71yJW`dqP;& z)+3Yd`h;>f)NT;>Cxmm$s2L_;)_NIEC3r<<#X8mYi}Ddxba;#^!A#|6>ALZk$Cn$geYZQG zW#f@sBxXw1TYFctXZJneQEoumKuJGDB=*N=U!b6VFU_BBoEN;bDNBMBx_<@9YD;nH6>CbF{{H3b&9v5s{=XuPrh zLC=KkR$d)+eaM#NGKH5pCsVAlCviEb^2El6dx>_%>m>3$q0J#;Lh$vA&x;ts`tJhJIPsb{d0S z-gOPox;*`TA~RF{vRFzkDx)knI*8l{m+!g9cGSfCZ?CXZrWDew=bJH!?RK+b>cBoT zZ5^ZB%vL0;1eQ7FST!J)Rw_7oHYw%7oVc_4-FWdWgj7WR5Xaz@Rt$-XXU7{0vLES^ zkyRy3akn@7C_Y$YlH-vqH)7?(_vO%v^%W~(OWzSIrn~Y;Rql~4pFU942a6VRJyK;J z;xmEqF9ZE6VMvA!4@Gik<0Dz*w2IdQS$%-$bS}7MnC3%5XaID@Y-l1J0V0TdWz3*l zE_bQU_kpfHKvYkxj#?`4?3rO>T)2Up2fDWLqW2}y-OnqQBa1dV%h3jqYeu?>qA~lz#z%$? zk)g5t%I!`P)rzY}e48+{owKo@Q4)v9aJxZ$;F$Tf=9eEhHbjOSfOz0oM!Y|wVtR`+ zklIMt5E+{7d{nXARQZHsLpYdRH+joISW8#mXIKUuS5!;%aWCR%CCtq+|jkac#+@tStYVrG8zdP zx_)M>!@&}8!VGJ6JL~uCbUiH(d>4*wA(NYOl!~`67r}g=F!O#Z@rKJe`k=RM*&U1q zJ6|KDM{77FBpWzs(5(&C`vJntQ?4l2(0yq9>f01>_AQowu!TeafyJ*OZr`T}NI%Se zpR8X{Br9YU)@%iQ7f&{O)|d77Qo$p`3U790vQeN&?D%Om6MTd;cMvW`9REr)(}-1} zX6$8d1<8Uf^D~9Jo(?H)cfuHP750V!v^~A0m?@^mt}P(!S0t()Lp+)MT@e zYJbd!Hz}*iAu-P6u$}zAX9Z$*PlicJ0geXd$u6ya_>KtaY!%MdfKr0kC3t|YEkI@7nkt` zoE~=G%PVGgB!c~Ptru2Q>{Lv~pGQE^-cW-z(Uf&Q&DY%j-t;46jo`=)|9K6Lyn!RS5sQt` zcgPlA*pSVt4X5)SVQl7tExUdndyk+mZI_|%NpNxkxA%m^LFblviw=HTAyPefZV|RO zB$ps)LT|mM7x|^Ie@~V_K1}rW`vgjAQdW14!LLelPnNanq6c({eI+QhmS)b{>Q2Z; z7)OS?`Ji_Vwg`3-QH+cAu3zmhMQh2kTN7=1-cI~Z9)H0XS<|X&oF%(8rO6~YV0ggJ zKT!E0J3^KwL199wgN59G)+J@x=13m(~pBgIsn9`h*{3cK!=@NjN%NT*k;F{zzgK=V5bx48cK^nHVHrw($# z`?r~9ch(9`t$PCQb_kW&zFC1AkEUI@K^rZH>;l29a{qS31TjA$rI)|%eH1`D0b;eQ z!M`Ks6th%Cd~zu7vdG<$6PGrM-Q~L-z|#95y#y+S{(p-aSFqd*+`y$8Ih7Z>jQV`| zFvQU19An&7m90C9w^^gGc2CTNH7y2zfr=-m@is+^<(cC!p8%HQeTVe@-$g0&*lX1n z0iNpe9%J$hk|8aa#p@1W7ft0&x&>k$oEcP%!k^dhPrE^EoJ*hG|CLf% zPoetXUjt^yb0A7}yj1ZmDpo(pV@wsnoT@dt^Hr`~4(|gbPIKiP!9k)cWHf1W)a9PB zZ{^i6Hesn7#*9B?ziUpPThz@hr;n1q$A!@hhB>tQ7?9EO4K-6YJJ!dTv?`L&KSd7u z^Y=0jiN!=nNlQndc@AezC5$^5=oQr>24P?%8S$`d7N{|w^(_43qNbsAOM30d%^gEZ zgjRMHVmvJCqNPZX0QUWsW6IwCc1$Y$f3Iud?@e7{^MYninEXOVO{{Xw8b;p^2m?>h;w;y(@% zC0ll_+jnEu$^U;ZuO=X-gzjC(4H&L7eMSdQ^qI}!)TX4hj?_6cqXtDOhV3aqoNV*!pUP8U{?;!>w=1Mr}QedO3 ztnxfqS+brhbf})1PaZy6876mG33Ic=y#s{m?O4dlbTk@%&TFW`x%#uXfA>@buy_(u z6|H~90ZpjPSQS?x20WlJov);ALWdopz2?-sX!r+c%)IX{AM@vjnBo_E7q)1Bu zPi@=kEC^-3!P7`;$$1(77eYKdM&PvW4&7Nl(Zp{ffw^B~BQUd$<<-3F_G;*=j_jU; z{AV`Y7k8LtDS3=2&gJIges&`hP``K$@F0KehyGkfssswU5 z+nX^I?d%WP+Fot1GN^uik-)(na<;1yYBYVRQ)~YAN(I4*cNGNI%+dGe;g1}`n|1W{ z=M>oLnSsu$9@F~-ioTYNjF@WEK}N*2RpbCx00G_$nPHM>+=K6w(!#`1|H`pwx=(wCcn<&w%FP5aZ zzF1G+qmYWbH~N}Gm1ug(ChLL07W(?f)MHwtZ>^V;)sT-u+DljLY3uVJBzxcxl-}hWWo!9LH@5`W6 zwL|Sz166^c637FJQw>W?FJ=5S?i)#54racaA($xP2wWN|x z{gh3JmsQo={86(F|I0mCdnozmWJy8l4l^T&4>eZ7dVq%}v<)&V$9M6VH8o5YdT&XG zv_f>Pc!H!<8O$@}C9;2rhZKTq{bw-i$&2;w-V-)6)7(9qo&mphOj&W}F=O7usjhQS zQEY`iw*?($^q;CdcC3^vwj8{u`3nRZkuLag{?Pf<7#1KxEt20WQdav)`cBD%2EJY+NKHrz_3wLSd(cDejJWVPGfzUuFbG*z`7SM3a_K z1wpr{CqEMS=U1YlMG>9OFOLK=p^7RLQE&?No|jN~`h#(%J-w=;ZF#fajxs0@RZ{1( zmy=svHP>a!oVZ%~ea$ll5tR$Q$tWNXsyEjI zKQJ)9#mRR%m@yxv0b$HfjnvB76c( zD%2#IQ+m?72sh94Nf=9UtfNoeBehYk(8aQ{lyXcy5+@W>W%X1|DY_b)QH%8=aBg#& zFmNP~1R5hP>qYb|YW^oTkdwz3D$Z;{WcOxLfxk{QU>QSjvLIK|%Nkj;GzKgFV#56R z_7lHoT&NKkyB=D9#ySGE)&~k@SqhcwA{uA5K%!!x{;f1FQI-Ny5l9>)q1rTr zG4+QtiR!?`J{(f&%U)LxN~Bj_ygr9Vl}H)8ms606@*MZJ?Oaq!|9jmR0zbo*?h`XJ7}9tNnSgbppp{Cbc?t8~8VWQp5}GpnnLaT{abX7wOJ$rWrf8MA zXL*cfqmL8`;PXAbdcuyt-!iHfJcScm5K_UIk~MKm)5%5JAv~l?kL>J`#3U{2dN|$FR|-^Jp_>_}C(vSEhG8l1 zAs^Sou-!8ECh+2C8q@3^X;hxkG`1r%ol%CXie%8IO8m0`jHg8zZNE1>Jz{R4- z5~T=wR~(>&Kh|}SPg`N0@l_TxWxquH!v1H}4TtW<2Mu&WGQE^x(k_%5)~B$+a&TRq zr1nCr4-q(n&z+ceNuW;c&OTuuu@Z zE}qjl@PR@`g?-$^nL-P$CIP0Ev=5v!C*P6hRZAv!c!|U^TwH*x@i?^v!*EI@lBa+Y zK`d0G)6pj;5=X2PI9=y@ir2(ZMkS~NF=`bGd{AWI4^g5ocj2RrR*wcokoGevWunm} zxK-BYGy<=@K;kT38+mA1!#~Os*{#V+)ZAMI3!tPiQ8@RI?Od?&nncL{osF$wHE{7I z3S|iQMs#3e&@FZYODI@OK!|$yX&VJoA{1c#ADOttA%~y_MbZ^Wiym?e*(c*xZ0$Ny zQp9~QSTDt+9=K*oQ>I`K1SlGpEs)ep$~;UK&x-#ZBFPH^GbVZ*RC^35h~bfK{LqrA z!A!@(7k!03&k_qYh7JOY50gt_W^!0I{-|~ixxgu>c*4Pdhrn5N?JT2@9DG4UWfDi< zzcp1EX%zz-QTRjobM-jyb1;+cUr!6OufCJ5T6-G03$mRD?V(hs+Ki?+givcz)ErmK zG|5-)li-eYbsiqW?5_8FMNCUpMrpy{v*}3zUL3f7TfoC4xY(gOY%~wj*DGRw$ z2~ekd4A>;V>j7H;#P=+eG#>dxYV@5FR{JN9%G`Tt)20*iNZ~oLAKSh4DNH9fq#DKP zB&aV>>3bBuw9dhwi^a7o`lL`Q5%M1vkomX}(FgjVfpQ?t-L$wib;DZ@3iAG}JA29b zk`@MBcD&n;3o8Ah0A^v99@R%^ed^c`*oNABBl#-(fo~|{@vRSnAeDI`U@Pkv7R-#2 zf&sgxg|%s>GqXxx3Ol=%sih7@R;eJDlOqCYdx%J1bA+W;^d@}}AVReCH5DBUQ6%K< zV~|Jwxq|+Pi1aD)6^9m_c#v#rTTRkOH}R5$PD^W}k%1ZMLYeBVo*>uys^8hu(^o~) zf_wT6I{lQu(a5|2xL~s;8aRgALQwr#g+k|?!GgS*m5@O?lUw4DGxz>&00w!_ysEq~&gvKhInQzLKLU9>_5hl>SQt+S( z%$^A9C4oAm1;kBCBdS;C<`n{E1ow%>$iwfywO%$J(!6H`4pQn6hf1(k0Dro3u(msl z^NDNdy8Z=tYmJTGXW(@6-AJEKrD|c6k*xqoDD(+V_%dNX+An=RAwHQ?U9==hLZmcZ z>Qnq{Cb}RM1bz8vFr~_r%LPOw(v`$lZ;yH?AeQWbSIbMNfGXz3=4-NXan%C${$3gM zWJ$FbNwa)1i;P;=-bTiI^45nbSms%i>BPOj<$)vq3Ibu965y~IcV$vzBn)gh_+C6y z4jjevg1np(<|S3k*jwxT_u{EE^?f}nG{Z9C;7B24l8{5xpAtjOY~rCw6sBh0L-={7 zkRYbwaFj=d2fkte&CsC`ut-5FbHFlxK#Pi0oy60jmX`RM`E*)d|I3(*AQjmPSY63- zYwk(ub@lZ1g8kS6;=CMRY8?ZEOB@Ik45ZIro>Guq<(MoO+XiR@x~TTEd(2iNUlUNB=ZX7M zpXf<6{x0gQQ@Kfgi?t+fcvz=a`G{)nJLDmh!D;F)fp!4SE^Y%5tH3-KOPXP9Ta!Ks zW=*5I$I$a~RBI$U#|epwK_iK-q)atb{DRy%XON`#Jl@OsWRA38vIyVLQBK9*iDZZI z*RtFE4&fZ+=C|cup@?sm*$-iwR)ob>DWfo#j9`sovJf`ar!G@L5OAEbILu4t?Ka^b))!KbDoQU>CwL5xc#CxeA_`|c?ZJ{# z8hJ8@Ah|FbP+ebw9Nr>9Ynn7wxHZurciL8X+@%J4~C^Wji_daUMiEgVm)<~Lw78DP8` zEIjeR!*gDOb4w0p_H^K*TsJ0RLwQwIWCVeQ8k$~h@ZsGcSWc2EFv?bfhRU~zHX0o- zv4h1fo&smO+}TFpEJqv&%uOL;i#Atb?{0ash|dm^2x*bw=t%<%z{}`;hemVYSoFgzF%Pw;h$3p1Kc+eXB?|`cFXdU zJg_~vPL&+Asmji;=498yQc=XjA&%R1nD~n_)T~PL2r#w)lJQ`x&KaWO=~SA{wsxGZhBTq94WkP zR!9aIeY*f4L;}((df3$xv&3gCW?+)6-ZV6~AZ4gg%@_JH>%GymRgiF3Y&$8U)a{~m zsA?Ub&$nmeQHwK!o2-exFZ~$vr*bjDu8O``m}tC)=z`K>u6ER;peFZTPB7F=mS`;3 zLkK{mN{m8FB?w!BW!{y^QH(ot@uG#F`HNtRBCA4%LXEWWzJ)KZT=y4AsqeWs_zMQ} z0uy|dLG||Z5fdyEOKm`AsX!_DDq&j5r1c8$F#6smfO>0_qR=`MpE{6{!_=;onnF6=U^DzoRFA%6pb}ylUp&WG#d7C;uJxNHSepnMIc~9!t zQPI?li%JcpD50#gKinaGBkZM=slzL2T z%;*fYDHJU%SB1b%8rz&$X6Ep=;9~U39%M9&5C#@LfeLlbP?}wz)7w!)0WZ)v1w);7 zmoTG>NYDkKYXa^|P`blQ<*(}GH(-)5e2C0|iz+ zw#}UbiLZp-;*bd&L0UUS6pK8P$aQBOu*napity!ujaj=gcDRWHN-|2M4(uQ0s5GO0 z@)GLZq=c$JvXOULXQTSyq-Z*>KK@s_Y_+C!*<|aO_)B|_L`)SP;v#YMWwGl0&DPpR~##og-yqcvofbXp7YyBsvpIJn6A~DLA zeHYSjrm&_xs%DBI_0>|aD8{Bcd?cQPG$|86NuH91YrY^ov|pz@1+GExP@d9JXhMic zui8_g?+mAKLm?+$Pe0Yt`f^l=0eK)1l6!QCioOSp>8a%_L939E#>F--)zMhCw=9zw zy}tK}BZ*os$DZdbGAXYn&)fRcpIP(_mBD78+4!QM+Ltr2HKSWp6bmd7uL@#87*p<; zP;fCqpdG0B$*9)5K=mdR#T8xv@)dPY1slCb30NGAAwz*K_niBpGTg60LnZA_LTJ6h z!Y?KY676SZuPl~YYI>WynKq&}x8WruYTAdKV95=@>-JYmbpnlIoO)YTY7}XiISmJ+ zC({))@}P|B=L~cS5UdZ?XiVjlJ<3G*ep;ngOAkb-etmuGv-Dss86KGllfAtj9&+Qd z{;c}k)~FI>mPKb3A3asQ)bKNb$Irw|i_FXh z`}@L%KkuS(%qN8)U-B?=hB0YCphw3-kS^;lubbOMB}bxHjSq0Dfke0?h1L?;+T)|( zRUVUA9yMC2dRl2JhHMf+PT*~k2!Fp$pGSR_K7XCaIZ=#^juNV`boA*9($sz13S}#8 zVo^1fI|@^I2nMCb<5$Eobgz*|qLa0tm=CU2Cv$v?SAHuy>VLh!KQDDp-wv_Kn`sv+ zqtUv|m*mZI#*iar&A4%H;0j)%3LF;?OriP@Vbg)!@|eKk(r?EXX+<+!{&#M~&JeJ8 zUth00Mpsv{Jk23~bUoQnIhpkn&jf}s*;kcjMkS@bnGS<`nTC?6x@Z(;s0d*|wsRj! zSO`q@n_~u-Ww)wfzNSy*N*h&%7W2g1tcxg1GhyML@i!Jq7Ly4pvB?Dr2OYg$xJtH0 zpt5hJ4;Cg970w@Hx?3#DQ&1(jWt!3sSG?OEW8b_YF)OQo*DOyvC+50DiOV|Z6el)j zPxvc=G{Oc3x}%JtyMVYD!JzWlT(spPq~dphnf^cgk4s6lNbi?P+u(c zxx0w4W=l4as4rHMC+0ts`U0R)O7*J1J9Oo;!$d&PNKE{SHgj?T27ZRbWbC&jp7c=M z7`+qG1h8LUtXK$zesP#gqUjGcY!OX7*DI^kWKP+<0XNoy-&c!=-QA~)+H}gmBXSc({r*)nrxT)?r2^QAO zr*iZfQF(izacCI+?t*PS8WY9)Z4`(HWMq}7^FOT@ZPgR;(yhTVSbZ@J%uW+Y)5H$ro9yLSgxEBfTvwJW+V&V)=?WymaIR+RfJF)1bj6 z`aD3x$EKX~7L7uP8IAkJVPRu~Z$k9KgevD^Yz7_6dEeRy-^h+j5jRV@l~aNY4%COj zY15k0t9;w||C)a3Xv~sTCaSBZpsGrd8dU)2oDZq_RXfspKD{)a92P^tPHLWU<%(P> z2o;McMe`a?OW_)`PUlnUS~eWexiie`ILd>ti2wGJS+4SSKt305cTeZ`kn+zhR7_W( zds3asI()^ebP|SHs@f-WpgUp>2m?(pnONC|c-b3j5oG z2Fd?bS0%pBNF}EUl{+5`Jqch{Y3UJ^WE!J+WjUDoxze@C>?{|lBZSE8BZ*`woi|U} zNl={fu1f7D_c95EHMySRRElbimz&_fXl}GyCzYcF_nn_$F7%JtZIv9v)*2)T3wTU! z08!@imLXlAxwkzhPv{#mB(ptfNGt6%R;H5=Y#^b{=xdb;60xpIf+?Z)}m$qqRA#oNV2DlRK3O_5350C zgk&P7V=R;08~1`VkXyFa`PGN_3>?3qWLtG{_!ufSl0ej>xPD#~QU#kOKR>+0HHj7E zalBcwom$uG6mfjcJ&oCk&s2jX$dA@#R75(_!;yUJOVgvgnYkqrn+tbUQpz1o`PFn^;h);ODTNJe6f2l0 zst+ndlJ!ZPQS4ZG(q>`D{2r;RYy{DqLJjuBqEMM2J1rP*tp>Oyr!E)Hu7+$KPie6A zQ*Ox=%lOa!q?W2X7NCj!No1%T7?Tq}T1$ybX}XcbMGE6YfvDAmaA>R3rM4_k+9+&= z9~DoP&%9SQ0w|FTjAT7P+CpJ4E3FpA_i>PU5Ra728D|0`vde`|N!XOiQCgGlq~Bin zs5o6-BPA6|Q>n~Q{Drih26{8my+26DsnR3+JRU?P8j*W7YFSPbg-x_^m(wUC;YyE0 zD;&UDZ?lmHbPx!h5RRv9b=l|ImZvCtY6cxuAwdlAhkSyiq6vO;WxRK_$K$je8S#r*WBw ziTWly+-0=zuyBtCu`Yt~%0fYh|FpLfI@gmQElnq)g@v{`>4MhhWdB1kWVv{9e~?Ce zeb7)aeZ`<^G_Sb+7<)|>eFd*0l&toyxQ*1~LwTAjS5$UxBUENwmft83+KL)B38;9t z=MeoGm%r~dRGrtHKL``AA?XPKsR2TyRm{KjU5MN%zg0&01u|2ZXK;f#DaXPp$4#2w z(x1tcNIfjI`|PNH#btn2ecAOpdOb)?5=kW{3O=E{KwgRK3FbxlOej}hHe=V!ZVgLh z&%4LSgQWI^y*()1xgx2~hcnt9)NJWNUTn>J57(K^(*7fW%WLHD+0%rJfo^AKM|r!j zk*(m#@KUZ-K7G!{@+c-X$ZxKOYI0opu&`17%Lb*1YRyGHwRUi0K*@^TES zj*r+T(;=K&B{SS)9le{9p?T~2&QG~no|Id~S)T1l&G3Ys%C7B6qUg`i88E~>oe}B| zxRrg56c7*xVQ|`c4Uh^(TFjDGeTqEE_^4WjDl!FGqOcP%Rtr=OJqt3>B+#iRle`oz zPe&1Wahu{dSxQyae3Y@)Z;46MYr@Kd#3E70I|N_RUhE)S@?RmY9f9QXuR$sMBM}a4 z4z;5?)#vt{j==BBE3PnO7Q~J8b?=ZgqvSm$%WVf=h(0q=P3B-=Ii=%3^!F<~`Va#( zoNd|qL7cMmI;>gVFza(3`bgY5VcGc{C@c)J9hY?8P|96xZfe-N`;2Pc7g?M8AYDL+b)TL`5j zx&NIRIb0{wBiD$8c`f&h@Z%!5(&>dND-(~rx_SE+#3B;Qxshz?uuSKH$m2m=PO1EW zw;!h^RBYDT6Su!I`OGqnxr_b-G-fpy(bxLe%J?sl*dLVw$%klk)RSnA-fTKqr4`y& zngdHf2kR~taR@uI30VWJBa#>QJ78RT1gF~o2dke<7A4Bx&x*0xh}?hGX9YdH zRONspp4pugT|2u&g=1bgY;VcPS6sp+mExgN!{=@oowM0dCS@oyu%6v|byrEyM5&=L zMT#Pu)Wgu{{v-e+TFBDRQZ|FHy>RCrwJ$%Jwx!oy}M51Tj@8Mrbj%c~!%6(oC&<>Ra6R zVRXdePDY>?4c45k?vTe3kF&$3f7Em8<+$1oS z(VTr{VjMBB9#M)9B2EK%=0M3L?ufdX`M(=ihCjfxOyfsJUn&TS7y~( zPb1X>@uE`AJql|PAYv%RtdYd9Col%l0XA;LaJk{T%1~NaTk@@|BFIxjGUr{=?6oMz zjk}X@m6Pu&%*>!L2Z;rHQ%M}elq$93_xj+>W(=}p@MK$KjFc8t*-5}Y-!$;CIbJ;i z8~8*8S+k+K^#U8GcK{xtT$QotA?1)>dB55`e$d4tc>H^IoH&&rPs$WzC#x`iVl&lZ z5Z`+m)pewfQAXu3^~!Zooi^o8jO2!yd*;ProVE{dBr$w+8mg{BIo))l7zZf798-n~ z13D?Pr`LR~ig|{$cM1w3V?dZBYRlwh!{kI0$#IRw>$_#BF`$E(5~jAiTLCyH5oT^v zq$tq6H0TbOmJt3Zc9ch%G}WpSk!K5ka~hz58ABnKjO_-B=Rd?6+)}vtXSwAlb)DJN zGzktOd9%_QXUwfv-WX6kW6TYi{IjFk`J>&T1*ADx9F!V6vNYTxVrAP2Ym^Q+7QPD}!Vy6-R>1*fHhh?R?6esi2n&WZR9^xnL)b zKN9P;59b)}>&S_eN>HB(=$2mi6eDA&ggRaWk}H+0W1Bw+fjJT%@@5VFCqCeK zQrXiO5bG=_Rb~0|go}Oau^c`RC~63Sbv;BrRJvEY(b(tobM_&S>&y!5&{*b?2MX1F zK)O;d6E;+CMLuY?>RZ8{H5QthrI`u(tQcDka0uNjfWxK-F>SB0RpcUa8`VaYuPA&J z()~!3s5Sz3s>Q&cq0iAyig7?2`!48W2st`Mh74d~VBLvPlf-y|(o70WtgrSLy`z!a z_pD-TKtEvKa3{ZAP>w~Zxys=|t7))YJ?(^B<8shcT|$!lbm_AwL29(slr#?1acK_Z znOF<`dAHb5!;<34bFyEG#R{Y;V3=cR*=07Hh|uI5L4#Iss}##$!*D5b$@rIte-H^+ zdQap-vDjH7R8w9(qEzd%m_*rM3ZTTn{1*y6cl*W1YPcYM|3g5Y;yYOog$>R$U;y5| zJVtJq{xQ?Zy1Xz)X@p8#yhdPRWyMmKkpZlTd@)OM*f?}-Y^oG=Y5Pqv-r?wrERgB_ z52Z@&G5tBU)nO>)dH6wqX0}Hzvgid>33EU4t)QNHxW8LRVwM^ND$Nu|_8JrS-~1|x z{YjaE%VR!3VqEAwi5F#JOw??V4Y#dT5(JU;CSlteI@n+;TYfWf&XFQEJ|2I1@UcIu zTDe4{lk*n|Z1>Q^cM3;g_T%ZWvB-ct?| z;v*Uz%D{>L%d7Q8Poz9_3f6Q|-@KTEy68OT+k0jH$S! z=b<(rmbIUX?-zmgA2#%X;*1KJpNbAYX`z!!O|AV%^6RPa2udIAr*42Ym4&rCIDEN% zsxl@^y_eI0#?07tG{S0zCjgf0xrZeU=dbJgKBF-*OyshYb^9r?L*{=;==PY#*>?%# zO((W=AaJCmj&5BO{gj8HZy+TFjE(4ngY6E1w>hYnJt?(~1V$ha=_)5rt2(Z#NzFN! zo@6JE4LDUEv_CxX-69Ha)995Z*7Tq;R-(w)e$>p{qnL93_hMR}Gl=_UfCuKPEq;bZ zRi!UmoAPeMYqSWmi0aOO>Lk^2Zmi8H@U@6PswW5k5elF;i;(9KnR6k1>4^j1MCtIf~d^+f6 z5w3LTIgOWsnhyuoHm`JepjRo(l@0f*I8ZnW>P-}PPvAhyZ4~!53$=G95za{9m!r57 zg{ z3yp(}-9&NsB#r`q8O7CF?AxlSmpLmGj}#UeJN(&Q6gQ#qEc3gaJ$SnXac}d{WXYEe z&LbahgSZowokr$CBPZ{JxVNcHclN7hwNN>@`sYF1iNq^?+ykY+VIB$BK=_Q&(bSuy zRfo97e|GaS@?5cf70;Up({)j;AXVVvV5XSK3(`u8Lbmg_c%dz(TF8Ye}Z zfx=SBe=z3N!K9M-QMH|r=m9zD#p2}(U ze!aLG2rqgVLEV+J)#2V|qMF%KXmgUVYH3CR+sbgyO--ROBES3nqYTGb?=ruY;ohba zHsZ_Xrij?U$A;v}=AFY*)DhGPjf2_R!?!_xJ@O->3WV@wi&ID(#i>n+40PA)*zQR@ z3HJs|83>0Q{0NCzTEAda$5+#eud&TQV%vK6R2wgy;-iXgc5A2tt-D3n!OyD2hrPLS zi;s+L<9^SX7z&3Yi9s#T8Dolz81MxGjp9wr4ZQc!MFr#o`L&cb+ZBR9i5&S5VA6jX zkA*s_Ah_oQ7H*BtX`@Jn%HY5uPqJ6}h;@qm7;!e^{MC{ps5?*FUT+%uXMR z^EKWxGql|%0`4?hv7uaCihiH z9|EUK#0~=U7UQew372JgJ%}o=B{tbnlZ0S#)n{%nx*O%8x;!aABgHw1kJ2%)Ly)L78Z65PXTyr2L<9rBK6X3GDwF$I`B4$keL$_2TlAsg~OYj z?tdDea!=uohO8CFRltT>j#=zBj4MFSvM{ikq7RU}7~=2*xX^A1z+v+txhkic4&cNr zX$)Y(uw{pIFY+#3fm{Xs!!^&d4!u4KJRahWXyGLsfAvSwVOmSw3;bgh?QY^sJUM?d|qi)NiGB2$j{ftf! zGE(4qw%}xjtkP*h5l6F1Cm_@o`JCAK3ZbHauQD{&^|{;zS7(&XSTlM33PYa@E-0Ew zh1@j+;@4K`j4WN%Pot8vP~c!_=q#JQU5%8x3#}?@>S^;2Cnu9IcwpCSW%6^mEeB@a zEkmhs`$iL*N}GA)fUUf8O+hwNR3^XAPFcew^*E7fKuuL$U}GZFPK_#Sx%HZR2P9+- zTUtM%Qur2-dDaXj1Zb5#(_c`3W(DNm=E*L#bD5Rg)0b^f;Xt;E@_uEZ`KC@Vpbp=) z7Es~a()#BlR#QfZ^hn8f_ESM2*28lD0q9sFJ3QUyH$T8h54=~*@v;chGk6HplzQ+$F8sy5Jlctwg9Z3*ocY}ovX>>3PR@=O=%MR{nB-*A~0;5&|h`1Ia5MKf_70-!93*3zR!Wo)MI&$^b@36W+}%nU=tC$w)w{yWl2T4tu_L?bk# zusxeab01wfe{~-dEL?yoE5nFikyY!dG8$=Zs$oEWvpk1sH3TET&&n&4Ay<4{S4d;9 zUk>l0Whn$?7BLgC{C~YC1JFNPHKdwcKn&1Vh?MjT^0^l>OE)Wx83)f*e)16mRaYdw zAgU%O7LAU1FDq~2u1H#=k(o54C5SEC9KK?6;Eh<7tf8RZxi+}UgC3X}7kk>Ul3HF7 zxz0xutrMejL<7aJD!Sy}@mzn?K#4dgNnzXT&sMbASH13u@8Ka6t_o|6DN}7urdS*+ zNkAtfxVDnyDz_#LGL`~LtK)>r!&L-hMq(ETY&3d9!Ya5a@qO%Jvcb#&iqd3V?Fwa~ zclUNh#$KcHUFRVLo5|`P1w1ArHlG1HM>^^Vovr2fIDXS1fdXw{*_=9n6H zEUt>RvZuHU#)#TQ7-9-S2uu_e>fSss#s{YoJ@RRXbx zB3GhpD)h|zmxEHc&1{)^tE&O(Q&JyrPL|NR$3xlfQv`~Amk8{IRCv^QsKERnrB8i- z6I0PHJCH1+ZU@M&s((XFbK~?HiDG4erSMseqeV9?BXudmoO^9&LZFOVl|;%#xa&oJ zjGAhP(K#k6n><^N{I()y26~CYSQ)t;V5Z6Yx@9zxxD6=^l9JKvL2su1UQS78Rw86G zwT*&NPI-qf>)X;C3jHa^&q}P>8UeIujh!%!3m0AAjXP6sHEwK#46Sn#S&|GjvZq;c z(M%RgT^1L4NXAnyxw!836<;Q%=5YJbApY8jt$aiB&O6u0GJZd^@AYT%7tj2D_@!WL z{!ld)iISF_Q@lPi&5`i7oJq?(2fw<$0>=`e>5iDr>)(->pd^c#^+2GaYR34)=~oiP zN3v>bG{8#hX225Jh#pE*XsyU+n5ZH#O*3|%U*ej6?XdkHH8&Tm#>(eEVM_@%MNG0m zk&ddf63^lE^B8WAsj0iC-8owsW~Jf2H&`v8LVx&>m@!#sO}v&jIB2a*bK;%Eyju4b zL0djht!-Ddvm-Ef#&s=$Lf~;C87)2&og|}Phd7gcpt?VJ@o`-s z(UYutR+VZX4_A-X1`*L-3~Z#Xow!2^1aFqAL^nUczv;N~L18`SrW-MyP86EgmXnz5Dpfm0J6+Nf6*kQ$)6w9H%)8$AWzM{9v-@e zR!mEB_G}6ft?KtQnG+Y-m!iv~q^1lrkSMLRt4r`e!<_O~P4`T{FCnuuN8zfu#O+S> zvh?T`GHpq`clzTd73(m(LCO)*1NO6eKW$0bxe6mlnSD~#nufc0wQfJXtTNyh-L=*wnW!4Iw zduGy?PG-fRl12VO5jL&j!UDXM)JfHS5Y1@|$98UliIty0X4Ni;zd{`6BT;F#6~$T| zgx?-RxPulAI@tsXlp=DZX1z=&4>pNZ6UiRBiB8c?(#ClE)NjJ$LTGwwdOg`<15c2T zb)PuDOyVm6pE?~`l#vbB^w4dk3{8EGq5*VEx=dolt$>jKnS)}b70%abbTaq6#Oi@W zXpW#aM67x^)jSNm^vANaN+M&Dw!TeB!GxSD<2fzj>e}KU0ye2o-_=VO)eC~S*6px_ zuBALwi#RXvQXBrB&JnGXjNRXvHHzd&i@WjQr}toZp|AMxcJph}Wg&}fL zcES`FOJGhS{U)y+jb3f1F^{ozlrJh7qa89$#M4|BIF%i*xfww9Ges)3fx znjB+PP~2sfEvD)iBh;kTGFSO}L@ya`VNZ<(cmFTVSb^5K6HX(C>vr1+ec;Spj zhxlxRO-YrLL)%`(0t*1k%V{L@sC#3y+g*h{xk5kyK*nvlh5c?0iHU+D@i%amAQnwn z^#4=};0JU;aDIJlj)v*X#O`Vt;SpeF;f)=4P-H3a)YHBbG%`kz9l#i@lYX~2AuBK> z|D!!9tOtDvGA(f1qT$1Ft$RzSIEmIDNMu;Ej9Nx-yK_+*wa2)=xKC%$U_?|&D~q>` z9UhGjMJ?j(bn#DMHW71#!ZQ=kkJT;e}vwiEtpm-ZV7} z2kyyK!jwyDQ>N3v9hL8t11s(2D64+m!OQpPoNs*Sxe4`@my=ZqK^1J;%dtE`xFv~5 zcykz^s+U(HD;(nN1-vQ%u%FwL+JVJQ3ZEL0p->_c)KaP5F6!j8nLNT*win|BsbpiM zf};92pcVHbJ{b9UUF%W51aiowX`*sFKPw;iqf#0WDIRR}Tp4(jV)+^XYOd=x5!d~$ zgCc^8AX3IuBH%f+E6RJwoCN{GY=oj-05;M|E!_bzcuJ8e27;vVJ(*r<&#^;UmYo&R z@&2RBg;#<&6E3Wq9zJ|RrBmqY1AH}7a!shHRA`z~D@!ZiO}Wzlr_ESv!>Q|u+p}&y zapy>+exnwMz{a0>RBee74-fJ^{dj27T7ZSBWK|)&6g2(K>*cJ}W|nA7z!lg7$bW*c zR%1>TGC4A-QqrjA{_L+&Qair;YWekEJaUst zeMTXhF;7iJsb!tM=|0P&OK_IQXjpxVIW zMKske{9Pvy8@?){MT`z%RCH>qD-VH7;lFj*lukDh)e0C0?1hn!X=}fF;TKHQK2I;9 zvaa>SgWdnKoe6=Rd2sTz&C`inF3qbS9slY`w&afTK0o4tg>IV zEry*T1##NNv_9pKNS)gzrMv%^oQMR@Vwyny1u<2rTq3Yzmq4h^DR!1d_(H5I6E|P) z)p7&ONaMgRmZ+JmJ@hlPk_Km$hTWQiWiER|naa%8?Dd7(_) zTe>&l<4_tGkSf24uvNhWAg^z6U0Dit!0$=%Qm7i3nEF&Evy#RqNokJ}Tf20n%)#h0 z*AFl1Tx&_9WOhQ~a2;MsfYOAF9Vu;YHbT)%b{u*nenFi)o_=3x+@wKkow!Q)m8t4i zA`N8%KqR-7WVL^lYjiy@cOBW03F3QAM1Ge!LD6O|S`Ap-sEi#=(HV!w^phh1vuwaZhi3UjwWu5;vSTHdb}?PPQ|lajqaole*nsY6HJ zN+-k6g*`7xMmE~CZPL6?AF}WP7ebo%!qOiJly~)0&rv7Mr799C7N{6Zr;-u!T*Z~n z<5p_kX%jK5rxQU?-qQwn&{!8ja(9Ng4GAGgL%r~EGs;`C+g?5U3*O&F;-*l1%Q#{?5o-qmR-D-I@{He zlgC2Y#S}`O0w^yRhHg;sFV0O>Qo)o~aU(M04K^LQ?oVjRRyzNgtvn<$7BCW}|C#$x zb%@x}O(Ok4dPz$3tzO!(ZWqb=1Xyc&nT{u(SK7)EDKRm^42K;nO{$9}$zG^jHNIZ@ zr5-bdI|Q@5Ts?TIrJQUU@{04Zv+CVxjK-jA}K=qwwx9TT4%Kv&Z76@674j$ zm319XL*b{fsf3sNFH=d`I2g$ixab0>E`JWFIct_P4j`b`A_&}F8p-6G!*g2opt8D2 z3q+wO_z!x#W?h6q6JI`Bmw4ifP$iH8sJt*_!>m>7LhMwZ*~3!WJMup5-HW3NZiD&) z3?g)w^`?Uf^tA5QNtE(Ww6J%5-YmU#o)>UJs9z_CSPI@SmNg4Bdl|inR|vX}i~d=Q zS5QX^SUi1~z_+9GM=bVAyyDEKFz{VO;|S7F%FTWHB#JLpuC8C}CeHK_HiNZAO;Au1 zJ2lF{qI{}(-!pF@58#eTm+)z_aCGIx=wD_~K%a#3oMU(F*1ac^`TNkmaz1} zbu3g23%Hc7U#(IX>q+bKN22fE`AKU7UM(GrMb>e#_pCcii(`-Df(p_PQELSvsno^$ z=^9D18Mul2D-ZF$iNQEamvGXJd>Hp9vmgY**#MY3#S@ICoysFE8y2y{B&HtypFWkI ztFs98NG5MAnhjmrKmJIr!MT!*s@-05~(NdP1VldQc=^+(16!mWgFg zBQ%Cn6mu`H9D8t=nyz~idPic0*wh`E;Z!RM7tMMR zMgPGoDOaz@LcdVB-d#~TnYD8FOg)l>EG9hK#sol~l^4?*2pp370lMSu1qZv{LkaXQ zPl+q0t$ zhLyfj$Yo^$=8m)Y3=0+UCi=INSB>8_3(dl?d`Wq-;G-AO2Lj7u922CgQf^Y?nj>Mo zcr;lO>m^_42~6FLwysxmlkdzl(4Qatt0lb(iZE8+zyWa>U#JPz6DlPf0A{Ymc@*P$ zTY%w#UaAYqLS}VAygf+E@^x{eC`KNm7$2=+IR$9x3V~Ef4-cVIM52=P=AWY{R%DaS zJl8zap_eYnV`a+JI_HosX*65%?r&Ib7RhmD#wDippf1&eO#eA}9;*R3^n@E=QI8nX9H>CPwXrN9-IPK!JuB*C~3I*y*lyby| zv;u0jzaXSRu}s<|K^AhyqRYGr|Dcy;nSn2fOVgytbWc>4G*;T%n-=JfjOBbEp>@<3bxejtUA|DOH?ohb zW7@2XsTYE}tbCdwGrzYhUm>x|mVT8gV363G_FYu2qkTeC@tO|g5m?v9NLiJmGuNHM zW_=3n<2qwIb=$U`zD4~cmC`|};<|Zp#Iwv{(7*J+l_(Tiv_Lk)u#&+S`f3rJoEy_; zuZ|S{^A&8TH6bva&gvkZzZ;@2TC8;NSpoaHex}~Yw1O|G?TWPzSuaTJ*9zEL-Ah{7 z8W7ri999FSu;a5tzF4Gq{$TKsO|JVQczyIg|`0xMu-~ZSD`TzdU z|NJliEdgXc{D1!Y|N1Zg?Z|PDH#>nH78(%Iz-ux1SNbcNk-sPJFrwwnE?N+*$OV!k zVa%4l_q@~ZilaGKd6_A!&oXFMPg^kO(31Bzs=U$Zd-4tg6Y`h^QB0Ii1j70i>5NQ0 z7U^SNOgONMUUNv_W2G*t^j<}s(Ykv@j;)Mc%!_ED3?Hml&&*j&%nRy|6bWGh*BB87 zzLj5!gSb9yvc=>sN%^Xr=;5kx|n<$^k+=Cd}JYew;nH7}0|6VVjNx3KNO9Sn& zpTK_#ONx<7uv)XwJ7KC(9l;de%o?&UO|-T!TMk&v!r>g$V;CIZkoa!p>Jr2lXEKLH zD)g*%f}MLOq1oQ!@0C?A2cmq=B#Jpm%;CrPniuji_Es?Q8--~h=}jmlD0!Sn9BijE zA_1bCEa)kqgmOlCpeGB~x%jO=U2#jK(+t!Lw56SQuYH5PE_oq`i~+>#A4n-TEB{2iFH;x`@W|TC30Npkp;yH&%|gri^IT_=NKlWl~^b) z5v11mER~PslG$JzOkxp)z%rZ_%Rq%y<; zMt!ymMh2YEiH9Jo4?VIcEuYg%<>L3MAa!U}RB* zp(A2wln;!9DJKuTjYYHMV26m;FuCRu{~vL8f+o3cWQlr3uRp0IT}cb- z{cqv@2LlPv>4d{0vieFTsUkC(G{A;q#|Gv(7C{9k*sVqb{rQ?UaIF?uWn6-bReEVH z8S|62nHUMcDi9tW%P~R}AKd7s1nAms2g3kfJY5iU_7&7*>Gi!10p-bDF29t-0ZmqH zw(xCOLXXx7OZXZirgM^9?mHP}gy($XAbg8_3`cn-L{kJRWSag^LnrFzf|#*64080a z5)D~&AWh|24<*fG?s_uPFfW%bgGUfi9bZDEY6D)0r{T4rXt_+oH_|K}TlE5qe5ji&!`UD8NCV~qYiqh5 z=n833VzNSImSWXLvhrpxC*Qh7@Jg?}6xsGzs@&`~XHzUW9F(!0Y)msX*SG(bbXUQO zVo1)m)l)XUP|rEWOWwG|v^*&5;#s>p?$jQt8zlsT zbWK`#aHfZoiIDKl>$*{XglCRJfq-=QRv8(fyG_3Z&V0LR3t|tFej>CF0ptCIyfnpy z<0MC&?0?%c0;fgw{+dS{^9+^Hu#VhGZjU`mDE-*c4I@qMD+oZYAhaLi)42L9*+CXY zGGU!eqFiQ08CQET*c#Ww{!``}w8}&vjD6l(Ih>mT!V)~4f&{vJCZ^dQazG6!>oyUg z+c|F9ad&PlU7Kl$%tBh$SJMX-A-?=>d=Kee`#~n1l(>t9Of22^8T-izJ@ksu=`V}b z#9M`iNFjr5j!6-LTukBp4TxCRV;-(o%#VvO@^u6G8SicL!c_BZ07z z4k07AEq8$VGI8#Hweo*)hX}3D?=Ve&Sp*JNaeiK-T;f)(vxEkZ(2^12(HB3-UmtTf zwS}@1*3;N!iVnEl4}S(kp9MVc(23^kf#4v;0x|2Wqr5@bx5Fc)e+V;}xrkm9 zE;lIm(mBer?Te=+Wg#9L9mvp)dJ?^aaMQglatv{z_?b}LU?@5+U3ShmhgU|C!rPQA ztoJ=@Sr8NXqR>$LLmz zjx-VZwxAaY;}WH`v6s#j_6*=o!rQXhy@dTS>E{0?kx=|v1Ve>~c8f(sRcowvzLJGH zDQ-r+@=?MwN_arD0N?UYm?+M_GEL?BZc2+IVE95o>D#k{9`;uxlh&xWit}tr23|b_ zI?njFyOYLs1X9#0{9$@3r-lQg#bO-M6g%TR+WsxDK?O7|!*2VSO{?Zd*HP~KI5dNY z&(h62J;$dGA01^TINvHBA97Q!t{yar+vHwO6~9)7L&RCcsqSqbMgQJGcHU%b70jdY zd^<#_;4MPLlpaB6U_BDSVJaaszy7wC9+)OHUv_Bw@@C#zOyd_tiT;?>@_#!#=+#@0 z6q9_0PawjQ!DsJI4e%*8znKJUM131q9B^n>HK}~3Gt`ykoWch`7j(a=Bms6S`(qzN zfKY~pUb3*owIER{LgwM+P*~6qGYL5bKo%3kS1Tg;#=-rKDDCvA6g_)q9Mj$~1QN1ORO13h!n^ zk>iky4miqNHGQio6o_9%zw-j4Mh>38xR%OP$aEA+@6wXgKh#oPXaS*T=XrTX)qzYM zDVbFgEqO({Lsg>WziIi74%Ex@P=BkxdjIk?4{cnYp2o6kC(TQgG>5)dCo32)9p^eo zQ(DXF^r8ayb9cNCWi8*ghj+H8cEY7D;=|}(_R1_1=$OMh8&*Q{Z$yH1bnR{MH9+{GT)Mz8MJvL;umRd_>c`5 z1>5kEf>`=M>tc$xueK#)l=lzS%FwnOasE|N&sTd@ zredBZRY{FBwfJ|`sJvB_mLjE^cT_wN5sw&1yyRIJKmjvTXRWm65i+5Sdny5!-5xhO z`b{xVyx#CMdAFpZ{C3jRI`X|Mo@iF4+yzn%V7=BE`BF4RfuP`8SH^3}bTbGp+qOnO z3h`bpuc&7!J;VWNkHgHi8Fa5PmP4oH1FgvK&FUm=tv`|t-sxDy- z)um!q*fisqhk#kzpl;1jjs-?ZQw3_AlM>2dhvgy8DQb?00*iD?#`mC<;6}A4$9%Q81JisX(4L5uw#rwG?e}v56||yoIkALzEo`RuynNok2gg@9owaxC)?mN zuN#*0K}n5io?%G?DXVg0t-MqAJEpAGKHe1GFa8Za3@=iSYg0_*`m>mq+UHGOPgPcZ zi*sZ(sDg#Vw0qY@UD`A?3Dgkmo8p{O4+Opnwd$B7e#l17;*zKYJh4*7u!c7JB$5)3dSfov-AI;UtRTCw+7}nT!beC3g z_>{BYS{ozU=ZL9i-BNIhN6}JDp_S*pgm=|l)^6l7J+$_6?~;a!CH{)%%R3io7V*#$ z01Yprtl*2X~XGF}=XId@z z=MrjW`1A&Aj4s7>2VF^teudyi)-DL`_LaAH%N5S0=RrusVaOUBD1I&5T>3RGg#1EF zEgo2C>1l*T#@l)Rn4xzAwWMIeSa+dyTSyu%FJIh=F_X=8Wqtc&k$yD8U2>bJST?9# zp$v8jTT(uERC%?K?ZD`wYI)jVEAx8>V5?4FZV&4uUjl@(rNyPz6H>LvUE{}4>W*QP zx*#5h_N=0l5!P4p9!M3wro5RF%DX8)=p+4t1Jo`maNB}+~hSmgsRG5Ni%B$^57{2$~MzUzXU8|4}1jl!pvs#0U_IjiK#9B)0Q zKO!Jdvbe!nz?5ghz|Y$XH1kk2@2e{ttJ`$+Wm~~0VOS>61>q~xt7e!Wk21)Z7B%UU ztr<^%EKHs2THjB4f%%0iol~W>0^RiR_^W{}b|PWzUaSo~-7ik8bx^Q7vhNRa0$C$LTgXlN}gK#C>?vVuh(yzBD^=B^l=78RhGJD*Q>r zdQfJZvV0l-t|F>By>7rj`(!vYbyvK>ZYhR@K25Sv(=lUWh8f|<@&Tsd6YHxzNH{fO z9WlSPg-Jr>D5*yDTfA9xJm2EBr{SSiuJka(++pCoqH|i~Qv&cK<11Q2*_;9TGEhBQ zArX$P8iRN@3qE3mP~3F^^Js*B?K@I_Y=OCDd1pQ!2bdXoMH!8P+Nq0tq{bu*S!pq8 zNThpFxRZ4qHdu~G!>I7+4>2{FM0rTU1U(1J(y!gZ;Lm~th_sOHjDq#O?mF>A#cYGk z(v^IPrd?jbyf5tq^XNI5#1l(PD;Ok$H*Q$_4~Uo9r)S$cVNAsHUWOaFH?3u@4Lyb5 zJ?XSWi=gg#UVy=Ogi1}Z+UH0c7UHi?6a$)W+nx}#lF;7EG0X?Y*lAVTlDhf1JrUg? zhg>|v@J+Y44c?v~670`bpn`^kzzl2W1NHtVaU3691GoDl$`)=Nah~6rO0Wo_q>-KZ zyYnvEOP%B54$m&G3b?aaH;c+uwQ&u_cJ?K7PNI1}8 zK9{5-LUQYvPfI~sJOK`DJgvxCXisp5aU(SH9|>NE2X&<(<=nU!&nMS%eXcO24g>)P zU*!6QD|CS?FB4clxX`GSG?HgPKLZFP;pg_`i!n38nm^PFq8=6Pp2MMZtu3$R}PX-=4Dti!bS-I znVVK$zbP$=GDfpG+nHd#&$U3==W?pZmox${!=uc-z9E4bTH2e1kZOKO^D{0lHhS~J z{OU2OcqfwwpLosIO&N#v+7T^GOHm~MIJoj9imj3hbhXNLM@lC0y>_wU(lXSiPY47# zHfOyTuboo5^r2@CrQDypf9i@s5^wE1}aokxeOM6;MAVM0H(GEWBHZP$uS$5hI_~ts#2IMpDalkLl zw5j4GhZJP=clAb0$our1+sH*f=PI`y&91cP^69}`sbrRToav2Ex{t@eK)jbO-*sU4 zLOd;e&v!S8hcdw66=r++P;M;AaJ&Y4MhQf=@vzsn+)+6Bfl6m+Dx6VU zTe%hw#jr1+y2$hG`RgYEop8D#N{5H^v=bD7 z-S&B-zEb579?`rQ?|lKG`sXX03rY7a+HRGtxZKjQ)o<`E%R@Kb{f!YvL zW`nMayEti7T-u3sg-JJe#RE1x{V_J28X99uITPccI)qzD>QW=(=i-%zls0zbo8b8= z-d&sb<@&a9XLbNAV&7Fh*k12n_HDJSHsvo3<>~>nrjVE0!YSr;th2 zOR>J24)oFbwpZc6ijeyA^-VdS>yxAy0ZI9t%RKz21P*H*TF4V~i53)(Yu^|xQ{tfaA&o($m zh}$_3E=C54mB=R{YCqFTzH&}#iArAth$&~Bgz;ULb^!qN6>68WkbWP=u$|Rr>9biR z{*NHEO2Wq=vU8}u+j|kU28^%R4vtvhr!TK}*`KFTBazkoAbD@*B0o}2-V*HvyDV` zG_2yFoOQ?nc|g7Yyd8sMLPfy%QMsGULPW&DG&hrR)hxDgEM?>8DPaCQz?0oflEFd) z6fX*OyCu*0XFH_PiEeM4loTw7T+~mybk#XPP3q=CIwa%Up1IWg4@pkmg-7X4g|(&2 z-yoDHz|pPKjdGtFWD$rQr21?%LIrN9LnT<9MmJa6s%gn(DSbzw>!(Dv=p}!AmBbG+ z5+|OWspx@GED#dAi2m}BpujfFU2d>6sIyl{nvx8?*~JQhW?TiNrZ26|jEe9o8GJ$( zkwnI(2Sq@h0^KU7-#5Z^NzVG{gmu}(QuIvE=wJrZ?Tg6ceQv5!Y%3C}`Kcr+p)s~JlMSTp(2giJys z5yt6;mu+b4e7Q+W147dW3ce`+>F+6`5D+nx7@Fc||KRC-P}`r7pccLs_AKDJSB!!Y ztIR0@Vj>2$?3XBQ(;g?yP!&3`Rv#ir+r+S7GtWuCd^lY>Zv0W7#|nB$E1P9MFmL-D z>(7PcbDo6^=ouKb%tVB4C|{XvX2gZ&OGMguFe^GcT4Hft;;WGPXmwV-!)@8wU;l)Q zBqO;2nZTj;Mb@7SNyQdI9wqtWRCz-AnwOvi>Ys%;6clvob3xK|o9A0iqP|-i5~yGy zj!vIy-XVE1_|7DuzUp2GDRVInntHzBk2WdMg#`1M$^UHIW5&I3UKsY&F?;H<`nt3MtsZ=R7+ath!=S23ufcI8znNo@0!9|AkG0`U@dP649%b zb!Q@WPNxNb_eeTzhFOy0^;%dvWjtI?!Ul(h>JSw%Z2zpkwWz6vE-9!}?=6P?0vRuL z-@iXPvhb%`I8RGdJL2|q=!CW?E6CSe_^hMGYYCAheiV33d0>tP`8h!gD6^dN?t3f~qne?JdcT9^x zK8J+$F$!;Ge#J|R9fjq={@QgQU5svWL_OyC{~;qW2sgYtWX@SEzk7Ma{OFY!T@ZDO zu>yRJ7HH|TIo)jl?NfuZcwtyCt1SP}NL_k57W~tBgT-(H9{EoK@$|JZ4Q5s`NvDsL z)&(5y<@N&0Qv`YVK;jhow*hb02dt)hE6LV@y!-X}E5A@smavEsV`)i2P~T=cN75J3 z&ChMPJ8epwOD2|2`Dk(on$U%F`HTkw7jzZs#mI14B`~6)ajJ^&QU4xLi-ras_&=U@ z-wM~YYrtY~GIuYhID{^hFj9HxY%ihZ-P7@DoK8vOvTH0-g70FETjaJ1HVO>|!-F(Q zq7G;@(oox#m~`^20L{@HQ^Hq$Gns*5TBxgrK^F;1f@|I{yT%SjlY30J2_G?8V)Oy# zQ=)f`wTrK~8HI}^7^x~vZl+!0K8>FoXAuHrZ)0*HlJl41pNo+oloU~1(<@Fu4KuQ# zz5{0T@gpoPt`tk-_m_e^k+8AsGv!8LoF}8dn$y}?DJ6(8HX-+8A*a1C#>1D6uO=pt zl?HU^y(^+}BN5zV7FA>Q`*UQ7X_aA)NuZiC{7^)x%(K6lMTGpb-Y7G1r7yj|nmxEw zRp%u0J63IsC~L?r%30mYsPPecRjPq+C25`X{^>PBe>*Z3_Xt;|A5Yd_y}hy*KhLU> zEa?E~$Nwm!0FhQ1FrCWQ(H9=`kH{#4d6x0yOmqH#sC(4FmE}3HooYs32-#0d$D}Tf z_8d8MRs#sTT(C3fr`46UOrLHu8l2Z^cw*Al6!LtPN3*Jk&-pZ8Ax~hDSQ{FQw(9Tp zaFaPLS#NrzMHV5ao>rYRhjBG}`BlQ**yR31C^1)@#wTKG2F{*5IR_o&cN?wr=v+f+ zgGIO=J#QLcPdW8_hQQ%?G}iVss$XYGHNJr3;`Ek-#gMTd=i@IH0h(nJ)cs0}Gzz+H z0{1w1yUU}xpR1t7D3tW|t7+krhLp|TH}_dF#a`Nx{5Am4jx-c$N-W^0oEd}OuHZ>w zb6!?|3je;FE(twI$3G#a@sDRQXDJ1XgmLY{Vc-OmhJEx1r_d<)p^-n3(P<%^rC}-o zY36G;i5F+!LarPQvDzLqI-YNgQla5P8H@SR?--MEqp$Fy8e1gKhorV-bXK`Ur)88G zzUxBf8xH9kq+#%ETY^33TVF}}v44$}7~g+dca!-orMBi{3UQb(pOl3y^1lVXtH*_d zOMy|=;Z{Ag-Q^z=Q|)BqGGD|juS~`G)(qQeRg(}tD{T2ApleuU)9t{&?I?#)y3Ck- z2ow8Q`=frUvdfJ^r;n|#N13<{RSn>#ei0z5i?@TVvxHXcyMuOD56k1o_>w*c-p7{P zfzi`^J2!BHpS>~6Z?GM+SUK652%}3OeyTetU8&KsXE}>ZCp+O-qVm zS&psL+5!J~kNYHub|dcdqi^C=cqumqI@1+bnuuzygklRxrwxGL)f(Fa+z~@&@vOK) z;-%PboJvjCN!LQ=0?rI1rE;J`U#c+$ zrT<>uLx`kYlx0&I#cpkJ8=a$Yw{SqVV7YtsVytU6Kvp|Ugp>vPwanXhBYL{W7a6M| zsA*+S4V|a)N0sP@*0`KnKWW#9!xCkU>c|c}>~^;#h%AkJMo>Z&>vnt8)^ae?6?6gZa+zJ zn9~QV-AvcA2N^SCry8Jg<=ZVz`Zz4vjgJZfCt{0bGF9<^C}i4Xp4D~6I+>PIfpXr; zcBTz_3~?P%R-8eKc^~L&I>*vDCf`bl^EfWNpMtY|(iFojp!){u2m=c#Cv`3FmOc*D z2l}I?S#Zu$#xsOOS<@vLjH`B!m8&yKViRT1Lnp4JLehIDe^@C1{ufYSHpu>J+^d=O zy7(zbE*wF=YJ@R3i^~HUIRJr3h+Z}^gus$svz8WY^*m;`kvgRQ*Kh_skr{RMt84tc ztd+M5?IO#NJVJd0l<#hmH(0+xBP>~D`n~-k!Px1 zYC?Fm$$eOd4O}_b1DAU_eSsm<5U(6iR>&RxLi~>BqitBJMgEZoNim!hRLbpSk4=40 zG4^~gL8hf!;3ZCeOQCzEh02aLNyGgi5m^pz({QsOK`>rU~#cl9giD#~d< zJk6;CtYAVJdhr{0@w=P+qE3MG+&}|)IbBEKPF9X{u^$UrTEQxK%}s`D*K?I6r$9O( z>tP{%*r{cyvMenjzb50yELPDn9Aeu4GS$x#PZ4ztW=jL6=T28A*ZL}81Fn3kegu_} zd>FAm=BI8aT-0-noHR8g=_p`(HElb&U-W6XEFQN znqrI4E7}S)3CPzieGtKKgp7KFyPUIxQ4@2#P8Cvb3;4vF>b%G|Q#vaAu{{cF&sP~< zpa|Rc{ds+*-P&r#Y*PT-i`91`n{Ohh8N4c6Vh?zL$VA&v9l}f2QuzM zx-4t_xrk9%bs0d7vhqGJjS+W3>g9A?nTb$?_aFVV(zO8o_Q+i%`~tM1y|&yArA)y*+oM|hZMnoZ z5*}TRC!#CLpeCtRC)0S@U);)mJUvgOF%rw1=8^8Ae;h)Vg{(PLX4pgdQ54Id6!yEC zQ9O~}Y{XM&LyAu$x_w53kCt2VU{Vt`kj@fKV(x=Fl-RSb&T;Zp z$Y3;6e6r_MY|_J|1>{p11>3BX3yhmiO9-K@*oM3K@eM5?LhaaOZXl_ADm_v@e>P%f zKov>jy$KyPq=rN&04W!Wl(^hu3A+Wljr^rS5;ke3Uyjg%=K zuz8GqA(>s;x3J1AfGYHSO$e6eFia@+7lqt{0^SHAqfRRG=jq!JNV!SnI$e@l%`~E~ zZ}LUR0x4Lxx^f!tg(r2rqsx0T%Y6qM-fssEyo%Xh4*_e$H7ze`3AtlGt}5%+)O}f{ ze#kcY!KUHXl(pb}p7-}|Qy6&mKNGNnY8MH(1gkjof{Xor<*qhyc$SUE1YkHzAJfWrEqa+iEA z|AwZA-rH$SD*J_yA0q)CH&ekNN^2Kn?wfbA*}c%I*}LvOZmgM0&C zkK;^=Al!HR(fy$XT~Uqpt(@tdgzcPSl^S02jiQ4c8dda*3q)M}R6c=F<*Kao$dcc~ zcn%Ha-;Y{Aw&2LEc^5DS1Jnwwb#)78EQJK??(FXi;kJ4o@@9$@=u{|K&e=;k8^Ya3 z2 za|oFg1K>@X?{2-z7tlK;`OodoxMv2WwE!5;NONL;x9Dgl-_<0uQKzPO<2|0ZJJ(p! zLFA-{mt>j;R!fb~0x2YWKE(Jd4iu356p!Z3xLffZe_txxEx8w+)ttm;s-`Uy_`Z?w zqN)FzBBIWA?l8m(veY1Q7OquU0!>v4m9Wxlj#=xcKVITRL}x|kgJ6N9Db6b)U@Cc7 z`F0PdKXW%`7&hVrm6A9pQ)2qVE0yaC$%F++08{MMYV*M@YS{qwa0XdEdo;}}fZ@F? z(9btDQfL1iO_jlXevRny_&=n80MpR&WD>7Om zz2R*lV##snTQY*Dg`sEr@%_RFJlwm52(03(y(?aG)n9#nZz;y&@P)!Gs(4Wi{#hSPF_S30-em&e>5RAxic7?{RpPOWQu@ulBOs3r6H3Qw}X2}r^; z`=$O_u^W_{W@xxe#~2VXNyw4J^&YT$I3|rYRw}UT`j{vAqRam83kKZy$*LlL-eDw6 z>yuP9jhArpv0El!Mq&^^cg&r#*m8&Il*6kXG9CxTVy7KEWxU7rVGwk1A2WBy75YoJ zx66c?UtHl~g(Ovnmr@o^9+^`;C2JuZfkH;hPpCYo zl=he3Tb?5wSb5R2QWN=@SbE_MU5XYmQ$Ne7Di5Qsf+WbIoUWmwnV-Ncs^v4Fc|E2Q z3`rVBSyIMkiQb2|M&m?e~)K1sKS4@H|O|h-V(Bn3&@zPMw_(FsBy}DcpGzV<#u;u z%$40Q&&d!OUdEsuJ*ij7}Y%{?I@fMKg)YSTFsh=q37p*$h1LfO9uP>)9ny#jq zQ!qO`O?ix*S!&4B;1EID2I4(bHAA@??#3_PHpA_&2ttjm$Y6^!#-NWxVNA$0!BN~O zzFuB|@3wG_O*-_}H=8JXN^gu?SZWCHd`_8e_yU~T zg|oQHQ^@Gp_-?6EL{&!_(-&0Z_4#fW8S^KGqsl_1%6JbVA`)8V=X}h!B2tP4cGF1H zFETR1B>7mMRtj4g5ID`TzS$+F>6-19n0--J0Rm$X3QDta%f?a<(FGVHM`KIp434n) z&Ca}hZ*76Tk$#ha+7}#((y+5HbP|u6b-U>h!d10#cLB0GrXrnD)Qf!9pe1oeoa+Ls zY(};Tt6XUT!KstJI%X3w_AQlwWM}8Lx5@Jt$SrFT2l(wBm?6jsimL8cOAJe#&Rew> zKWrKLsa_W?E&e9Gw=e`#gpX7sizcw|Jjjf1b_z6Jxd35LM-|&~;$(NF6#G|!11{@Q z7E^35r+wB0My)<2&IPMw%S;IQ>LK3>Sxm8>l`25`l9`GhW&i|-Kuy5IK1S9=-vJUx?@Up6zfHPyZ4FVK@wsv#IBf zJjKQ%GL(@xmj>J>@n+7HXCYN?4z#V~bXou~G!%ecnoDiO>*ezHLt*GK@BcI@ZUS>q zPi0%`qVWf*=&-AR`}gOZUPYwbnXkjXhEC+8PgErP&|H20osg4Z! zKD)_hpO*@nyeqBW*=vmAZsLW-%DjRo;ezW!X7Tp@r+VGO!JJuBaqO^|>ZsgCrYj6L z-MV#toCHS?L};#YQ==@;F~hRTe?r#~$% zY3=Z52}c2M^&tD%)U?9zyWHP$GThd}1TXSo@M)*68{nYX&b|A45HCYG{BO$0D#uL^ z?p@W-FHpf?>jEeDUiV{!?^9!wVgE#R}g5tnm{6I(Miu<_$FTV*xeRJzwDovvZnY#URiy#jhEV+_L^VG%`LJ}kSJ8BxYvAD$! zMyrg_w!d9EP*w{xHI=*NOCy=ADXV_+Tjywh!tMGP{64#tJ-B~u&sE#a&dCRb7ht9h z5B>ZS-N>_mC)|E7AySC zW%JNuN--&_yQ7ckYR$^@Iz^)hoXsbS0qWkX6W=j-QCAE-eHZ%37+==&7Pot-7 z5iDl$!kfUO>Gmx<85*Do?}VsH>rY(QtB!tlgEC5yCq0N+V9**GFKYS)qygl2oJ}T# zzz&Ue8k6;}w}c#@nXlKR*F+!Fjf}G$W&}R#39J(h(^OlI_!&=BkmPOB##bq~i-h~$ zG=cZo5a(MIs#RK&e7pb53B;R@b_jdlY3a)?x@{FWGkyWM!D!_{ewy+PQaQ`k+Jk7rnV4H+Y#c1eKxL0|zh(QzhVF<2uXIzx^8*>a1_~=qELf(19H?Cro@%m+oTi zn}2+d9O0IT_ppS@3nKU_^Lo8kDkC+gvi|kY`5te>Pk3(ybOeAl$6vzWY2n(DuyABq z&&D%oyL$j7qj>*1Q;cfUDypbDbXq#zy+QoVJq-Nu6{hI$sHGEkp2VJnBo)e>J7$ZR`GUz>CrLsC80{Gfef zER~*xm>r}>O1fyNjdqiKVHd{iQii&gfGC>6nJud2gB4_`jJ{tuG_^bkHKV6dh&A+i zs3rEMxEzxJe%^Eb9}9^ST)5RKKI)i&D{*D%7ts;gqJ1WNC|y=`AqV|ey@I!5Mq|}s z(sm;YmWg3Rx>~@9$z}9?WSGBU-k-~f0(-v96Ob33b^M~VWGr7;3^!S<%)rpbZ5A;Z zVYY-(|5Tk^Xnm5x2s)O=B&$Ks-JF;Vg<@>&)1YY|_wv1n2?5l1lPrLE%51X7G~(R6 z+f`{bs%XDKy&|T-f(mp2Vl}COc7B(N>ez#(QeD9Fq12IPPCih`Y8 z)tH)Ksf_I%@ofu1>$6h%QP`GBQcwAM`9pBRoz~75y05cKXgAB59SUwy2Ok$i-Ky<) z3C-{63pUZf(ms*$jcsbrz-Alq)LeJeaAqODh$ra}eRe@JxI^a%XjIOcsO+$8t)fNE zUL7P2mKnZsM3a8HH5JKQ6O4 zZP+4%4A@N`xA#J5p}z}FKbA6UmUiw^{pJ><$tPqX=EG3?bgufKOi{nL&3A~3s3_0> zWQ+r^@>`%*^1En4R7>m5)6(Ks|W$Z8FOzf10s0`@(xmGG%UA@cHTBKzFh^{hSV(l)$!E_p$?!g@9 zL3@{JK4Br})Weyc0AbL*p}%FDttVA0ZpsJt*Xp&(GN&dcsA?evxwY-Mn^{bc@{8#c zr0T6lJZk_6NawRft=DhEgdNZM&o)b`$7WTS)a*9grIo9Cs&I}{{m50MQOc8<6>gnT zB8i)fa8hzLRBOsRhlo+x@=e+P9Dk_%3DnB)oTI#)GRc{kf1$C4c^9td6tb!r(m;m9 zTV%Dki)&)0pWIRqpdq^my2ic{vpgyNap#ljpOBM}&pFifhf3dK z?@MKUMRyv~-*h0`_s0g?O+LBT_*7bv7IZb;rmShO;M=Gw&cq3{qnd8=i;Gl6TbSf5 zBF0ZfFGb243dp@`nXM_Ar;_{!ZFdUw3mLKVRtiHxA$Hpi16n)W<5x1Snsq*rQLxRY zx3jnbFZIDSib4$AXp&Zzlr`H?MMQ}!AFWHVr#6#_jCk9%rr+*4PR=s&Qb4-I2wL|? zs}Bw9W~;Wjs&t4tv}pCaFj+MIUdDnb_*s5f?_FmK##{VO#1-7R5fQ_sI+ZeGr7`wJ z3~I762T!TW(}F}bMks(UcAM>k7qg;%C8Ac}?OS{iu>djT4U}h(O{aXGtkEIicDNlZ zN?E6v%l*XTd?)0J);jJnam@>5#5-JgxVHv26Z$g}m@H91X~oz#GS;zGp zA1*Q)*8>Fv-;5_zl^=EW8*4;ee|V3FhzLryr{&*ArpobeiwK#v#+dAZ(Zp3B!^5K{ z;U(0TI{R-)xT5W*ON7K#l@VF4AQKn;)j~}MmTPe7%kAI!n;g`=go%t9@KsA--V*uW zxx-81ut82NQ#%^?XFDtg^#4f4kZn6MW{+<^!NJo*BF%(8ka2?I zZn16*MXEK%Z!2}VXT%6^MjR!5ckjc;(T-D$Bz zi3xzpd-kEKG_nf%nklgZl=gQlF~eRPcUS^O*zSB0DMRp8#6Z-vw_-W6x}v?>dsD2w z2KiG*ZJN6ODG66}^5kpYNLbVq*a7Uad7*py_ae$NXrfgJX?~UK_k*JTVLeogc%xQg z_%TA&8?@tX^w9>N#;M@$TaA=^=WTv2VlhR_bqvxVH`;9d&*7W5-ElVWMD!SkW%Wo*f{}pE zCoWB~=&9(JB9?<`OBp}GZeKZ6B=xhq(d;$ysthb+8B%rl>bS5{MfAoZP>8H1q~6|K zYJPKB2X;0mY52`*d2@DpVT_+ODbt>peF&(kd`X~@U57QgW!`Lih!an{r>Y1+#Wpq{V|LIewS`XhCG&)dVgS;74c{7Kv>4u-g>Z`$aYTSV4J9Et7wCa263C1VgcayL% zmAXkZf@JEW{j@{zu&sZ6BjZX{FJ;!^ajzXVTSMEiTvNC(adv{KV<%( zTq^JF6CF@bK7HeP{8_45^$2l$=aat3{L|^Q2p&^_wj6X3?}}A&5-wFBb-ShbG6YD^VbY-#ok?(fdysBPu-?WT z9!*+PFEW3ej}FGr$-f^UgT59*x|UO4T^-1s{x8KNa}oXBP-~o!nHC|h^$}JSCa_Ug z`QUMpabFNX2ILi`G+J^&hh+l=ssem&)~ohNTilLDOs1lewR@2=!OxYo_*QBbu8d4H zkq%Y&SGAQ1rH?`TZGUIKCykNm?y>srf&&8P&>UijBkO7(ebqb?AWPh{>^SJ_zrPSu zQu}x4URD3z>QCZOoFQ-GCpdF4ydF^m|lm zq^fDPE*L;)yLeTkp25ce8{Mn?Z;Q2m1nc;e@`^wH2fsTsAhF5xl_&Ev$=m3`aN4RK zVeom^BZ=&YI*9HXJCvBUnaYUiX0*4Q4A&K~4&NmLv*UVRS#p%ntZBkP+jfRk+AyE5 zb0P!o(*}MA+nT9(l|(RQ@~jrY!Lq|L$7+^fy&dkDs*=c5_vMcpmJB_e|7<1A=&7MZ z;mPw0F5HV9nO=C7@WAE8?W8Zd?CPLj8rzz-W|+_`1J$lTqgy@wA@ysC(TV3&_|?0p zK~NAKuaU60=+{hbxJKW~*)~d)_sS?IRlSE{S@HnGX5o=|dzO7$_&D6+C}RZEeV?z1 zz%}(6Z#?uQUs;Q>d5Ny#`4T6L!{pFg;3{U*)!NsYx>GaXBNxm&}G=W0mzmFUjcUO**6Jo8;QgyrVRgOMN)1yr9KP z+8 zqt6>$U!Cgr0;VVQu>;`5H|5n_8b4^#BjjN3&)718?wEQg0bvdB*f=2zN{qVd2LADNZ?U~$)wu5C2kjJo#f&G0Qi`6CYPNi*ObGP zZUF#W&l(TpfWk@h&aX&f4*?*%7jffAAmc9dAS$h=T{v{HN?}z^*{!Tsx+N6^)5{OT zL*W9D#ewiIY?a9YcnJ2z3G^HV+JOXxju7tMd$nvE7YWpgPy6b+tg#B_1IP)rojeF% zm^WzwOyN@^h{`GiTW8WLB{#m?=~@e6^;+b+J1dN38bvVk9IrKfUnuL6u^NF~GQC7W z-HZh7(f9Y7Z8Y6;K@*85JtlH=RPGans z@>QU76iYE>&B|$ z*tI~Q4jHJ3-dSMjvinOp!@n*yt5nFbJm8>OCjG0n>rX3es(wXL+Cd>w^sn$gSugoN z`xs6ZyTEX#9aa(V*h2enfV+$g@rEp=B^#ZS%Tg8ib1ssT5x!1rU|ukJQ+QD%(>)M@ z#Ohdf=CFjM&|du6{v^Gvx2v#mSYio|w?)ykf#0w%3n>)~yfUVY1@?_(nd;`av@I{{P#fM$y&;vuu~9KWe;+=!#`N|DU2&BRw?qA8h+!e z5IpL?l&}il{#**UzMZT& zU){jD(&oz!A+Qiu=9MiitL2>{(VwBLjDD@;oJevt`GTf7`IMwkJMHB}yWlM?W?2l> zP~LZ9{s~}C$rfsR@v*hwVHcDU@_Y!O-$9fty(flS4H#El8&adnaG%~sM9s`C{GH{G zd~JQsJ>?D(02Zx4w4X?F&WkuQU*(%x%-_7QDmnd3D@U`;gmK|g7!lNW`*%x;P{hd9vcYbEk>At<-a6Rwq>#wz-O#^cf~75DYjpHW-`3b| zweMdwMy>3TUm9A<(qfA`bzj;~;O}ZjrO+x8%v5=EJLsPDc^(&e$oSHlR;mFntilhg z0qPA45l?0HYRMc@eamNcv&*5zeK!#uBX$Nh4#Hzn*0T+%JjNx0?KnQmJ+T|j90R^( z&sIWWU|XFUt2wmHeQ}BDIrvypWsx^;hNI_R(}E+Yr#f1#ar8I9>uHU-#6p=|+1lc9 zbjyioasafzVb-TlEs=K98uj`-%XkKk`feGjvI{T8aqTNrPcsf7UkK$dHSBYpW8C;p zpxDWF6e8JO>4ah2ZAd3OFkdP6*{AN`BABs)0AsP^4aXhfQsq#Rl*so11<+OY5nzxVU>o~cp=v#g1!V18UkDbPo+-Y)dn^kNA9XdMW$AE|)uT3yNs%lc zbBQ1sU<{nQbvXBh%=_c|DgEfh7A}W<4MM6s^E52U^=Kb&rYAXw${Uk>aPn+f){OZ7K%upYbZ|zyZrl7HCx9fWAyHKEq8b4)VY9>|Jqd49p3;D~SDg+kQyZ2!qKJ$ zM?XtDrF5;Ds0eqPZtH3Q9O{plIn4GVEFM$`;|V_@H4p_+mTelN@Ej;PWIz6kk=7S` z%K_vuBny9OMpX-QGg|I9s*l1%vkSECF(b*be}Cfi!pR&pjx%k4X>5yFqMN>B)hgM1 z^9~0hiCY@Neti=ErUI8s79ON!MV{QOi0jTEC(LV0%5I?Uo*~9PJxBiI8tdEbWX5yQ zK2-G-lQv2JdCjkiLyY7@;2#s zXqxG-R{#+Y)YoV z2$_^zPuU5$Ywn^;sp>4SUdC86X@$qY$g)RJq6!(j2QVpjWNfmxF;yWmK!{S`r>aur ze7?yeh6G=Rk^)iWOHN0kQQoXZkQB+Yt@J2Bp2vT9)$)k!Oi*m&LQ#Q6%E~ip>`4E- z1sEyemY*iLoJr#s(uru#(w%x56QW(vwy!!I_OUgJ&%51 z#&d_X{57{OMcP*=_)`&=3DzM9*5v4;_hAP5WOMi3I*<2`4QL=L#Nc1w;#AEkB;B#_nYDr1uRy*@G!g{L`Qq(y>o3jsB`=`W8A(Eoq^mw(y-gngE95ludvn zQn;dAiG*2lkXWU`v$dDB7Yhf$`Nstw+*{TbP*0T%0i*1ZOqhkmU(RXZPj`VgSHBW% zvOc>~y{KYC28Hwe<|><`HV3TtKnuV4*x=e}IHO#pQt%oAl}**fGq@``CU|-94WpkD)O`)FKZiqy(zgRhI`f{jRgf4&%rG!4lLfZWcD_sH4oIu}53)D}Nf?%dL5d%scvaY^5PFf-RmwmchMaH5C@(}2xmeaM&?Qe0wd#&dF#(GWIr>v0x zWppWYV3|^?`7SS&`E}gX@otWscp5VPb=KXAgdUV6Kl7~V{_Am8JmY?JoSEh6pE?QO z!F98N@KXDRm~Z|*-=G&BZV)Jewc{pq5BJ5X*$zTUNp0OUCapP%u3VR9cn*nN4ho6r z4>mVL0m2mHP=jml&gcu_mKi=R8l*!}Yp@jx)p5&wR8I|*4H4kJ!Q<7n8ke^-)HQ5+ z7eEgyEdDBOeED#dT?NOUX7`6SWouMdj?pt=eRKAh6$p^J#C995D7=E;h^9%-OfT{X z7Nukqy023=>3B0fQ_7~SRIC>{&s4FBDYZ8l;mqRidilc1z|E{wgHi^^T3*d@XIpgD z)oq@bdaZck$)6ICbg)&n5}zY~;WS)?QlmanR}d$Z@8hyswbMd7od_V1Nv$=(pDVB( z2L!LTA8s6$R~=U#QTxebs7C;@YgY}^H@EFi13eekINc*RW86a7+B@n~ZShb4zHyGM z?aSQCf7TL)g(IL0OchozZT4#!yYQjNoDY^MX;cy2Y{CjUj!)g!)hO$;h~p)~+&O5T zo)Y=%n&~mmEW|*HOE4XH|uws>=k zmlaOj%4pJux{sFl_ok-B67wNOW?6jm<|Qt{Tk5ORC60>fh9h^%65hb5Yeq4^z1$&C zV@8fg#`eO&m$>oyC30Gc#So*trvDRuWKTpMeQ}2qLwqsCz5*A<63ul7A#c)&TP2LK z`U$SbJjZUam$+`E$~-*JC{iQS;7R>stj*L94@iso|_^r zI~it6G+7)TN7Dpqmljq_%uJPRC=2t1`(lZp>@d-A#c<9k{e4zb$OU_Y&Kq?lGd3Z}wry-2rG z_-|yy{;l%i;}#zj%+-A$)*K4Er&@^xpYD2?l;}Ucxrn8C?>z9<`kMu|!@U)t_5R-S zl==F559S|{Z@I~EyfvV6uo)J2V|rRp9`&+Z{%FAGjY7C-?pPHrmDjEqC7@8k+mV#YlHT zA<9IuR;x&o&ls`JOhF=8+VwfN_F|~wi*UK_wAvcf&CFs^3ZI^P`{#`hEKf>z5Gq($LV!s?~| zUSA`#`f{IaxzSN{yqb=0Mx!V=XAuseWXp8U)u?k6{mhm)&Y2M^d|LurZxv{FKDZA_ z%3s^77^L8<4KTBO{O92Vbo4g)PG^ygOrTbIH-)MoINl@d(&Y+Ahm?WYD&yh0&;mYs zQ=j9B7z92_?umfj*3x`=@A(cdF(NJNU6agOv{&mYSBl(KM20GL()uoDz~vVgn#pLs zHF}LZ&Qk{aX41S&d9-kZPz+4suwmSN0hj6g^%4hN!V%Ti7?qCSFRw;jGos*C)2%o( znv__|hjz6#4_wZPe?Iiz6?bb+QJp`^mN<0!b`p{P)GbFkxI6nG?MUf&c=$!(;(GXQ z>#C%q=M8uG_6|X1JcV#ZMRCXbfiN9D3ne}J6e^G@C2gZ2j#-CS3l;wA8Y=h-5u{#X zzGQ3zjs#x;V-6JoEEvcP-arS<(**d`pNaNO5x5v^OtgW%@8=TkU?tuK#iX8J%4Vt+ z*|}F-N`~0P{(L(^d8nCBER4P8>ltzXvw&IO)`ijaU8AQ)47@Mj3I(#c`s{qXGv9N_ z!|G%9peVj%MI2sk@b=Y)3+e1{`L5{vY9kUI?p)j`!l<&sp;b8&Evtl}URoNoXeit5 z-(fl&w^Y<3uaNg?mefb8Jui27|7xisQmnu_hkt=<698&vNUBpry4@tCG#TV1yV$f3 zwqdN5h_jjwnk2YaTNzdEz5R?gIH%y+AfVvlPet`#F(Lih%-M(oGCK8JLe}9Vbvj<-PVN2xXOAb=GSlM&7}in z#$NVRUX4FDD%NEzx0o_vav~>>@kZp&BH|q7wlJ(zB)GLma}lx9A}E7V#O0*Dq#a|QA#N@NPnMEA0QGyG#z7f$% zx^OmSE3D*yzQjS{lSvw%5y`$;p7KbbEBf~<#XY1>uH7OF-;z;%a^t`eH|H6NtfznUZzNu&LD4r}uc#pUNaJPR=I-)*`?+V}3=1}z=0@pPuD zR5~6)k`h;kLVZv^o~H!@QIPEhyUit@&RZ;mJi>m`r%A_#m%E7=uRdasanOgs*WAna z(|}QS>pgTYna3wJt8IGq0P z`8Mc#ys>>JuSwFO-Kr*2{>c)%0+%UM~r5Se%p&HTsfRkL`^mM3vckz zri9B+XQgl91mN!606lz)&DNk@>9%_bRkV-an$^N{*dHH+D6i?}{GfbEHbRP-Y061E zxF*dn;3??0a5qQkuzDNAkLDw6w-VW8N;Qv4J8k(G5nfE6K|Oz-3DvKS5^&K0KFb(# zRe?0A7JQvfCF1yqhJG$xG$J4}NEdFAF^x>2uk{LKpPvWqU8F>65jUn(QPvUe=qG-XbZ&Yv56&#r5T0Z!-NCk|Zr?f#KZhe3O2avqg4<2d39eM&w5l6f1Dd zAeFO9)h-*GYtQKy2nV6C$oZY!(SlJ_=f0tkYE8RXqIx$ylS6duor#y$xb*)agH=ch z_1y~TwO@q>VRm*IV&oW=d%nnN+ET#4 zi%6$qRWj6C>kmrh>1OLz>CJz=hcl`(w>|vNF8@YEsdd~uikY^|^jf6&ot3q9;D$6| zFRk6k$8dV*e!Q89VY;eTzTIS+b#u%9s6$nYlz6)gNhT(9%5Bd@DxKM1Cg3NhZykNl zLJBKjykqth|L(`7!``EP(pP;%#Hd&NGa;RhS9(r5j@VIz!1f=fnH-pI&Uc3}W>TJhpJ zg_Dfalw5|GfUwv~n}PvWTt{$=L5o~yeY-9vyR@5emQtN29o5ib782FV&j*=7c}HTR zDj$Nq5i+=N%O?5oWgq4oJycEaz6hZigThjMDSPWe00I&qEuYG!&wpGn>uvKm2=MC| zK-mRuTbLo8+LzJS4;7UcAq}Do#lU^X&^&B}2aTjSqiQ zQR_uU5m3LPQ^3 zkL}P_DgzH%94Id)=@sk@XB@X!pMofJSs(>;qX!}qX7sW=N2=&AYTr{$-(X5v)Xgy6 zSAhe@ezwL}2}7J^%w8-!-i^1>&X@iS1DNHfckg!i97nY$B+#RcQAV$+b3b$dp3g!a zWt`(0KNnJDdUuaeV7KDU+xGPN8jTd5NA)uamyL|0Q_bnC;Pz{5+x7Bp=QUG5(^ z#EhY`;9X_?Jt+<4FWlKC80k(;4#RB*|*4E$_2NBI`Fu2oKTY z6U&w71ab>FK2EGr>A&^T(3SkDDnBQri|k*=Byk!JgiLP8y>AzEG6Az?kw63OvQ8o+ z`YjUvjYmLj@Lo!cN~!IQ%ZvIo@}-abbgV^4kv{#IfUg+Y-Ol`=_IWg630s>kL$Ngd zb=wx1&2!Hd=?o5z6_E7z*@O@%BI~IaIlo$$@#fV|uM-fFluYAob~sc=l|AqD0Zfls zIJWwDttNhjl&bAXI=_(d;~~Z3bzF?rpY*HfQENF7aE*-g2^dWXNv|p*N6Eds+m}LS z0U4~AvX%CceHoYCDpSG3MP@}ya4GYEW7 z=AlPUXToz5NBp2Ln6J;Zk3cfIgiS=NN(C2FnZu0SKglTj5(=^!7FK9y<;i$VGG<1l zr7&5Vt8w1GNsu`HYu~Xlif0jLT~)Kvm#BILZE1aO@1}@oDoERU(0a=m?%r((9x2p* zCL^W}TF79ERIDuK*i=<#zat|1qJ1ohxsbDpIGba$(bqQ{1f+CGsdiEgO4w~Q98}vf zm0D#onzHlGU%NdWmW@fP5+o9J^s4-azfr?ClB8{)y&bbH9Onn|lm~M4+Kot^DM*yeR7O10RsFX-W1r-O;4-=<-UdWlm%w{wo z5OMYQknQzJKt>sDfr3jm(^Ox&S+*Y2=ajMkwh!sj8T)*hljjl7R38-XWk$7;FI1ag zVog@oMEhasS>Odjc&F{LZ2CGa5&{qlomTpTnivitm`E?H?y}ncpX@Z>LXlEC)h}A* z*!UhG=OX})Y(N*-{ZT0WjcoZ;UN+t&K@>=5TTGvWJIDOPKf*%Oge>O3-)5#x1-4G3 zX8S?rbwLA6k#uZ3ZYT%u#0?OK^}8CX%EG!5X)16ViH~@!Ht>hl;&WK6>=_?hXqe#= zy>2MUEEj=jn|HpuM(`Nd7o{a&WiU6r&2mm(B?i%V$K8}lALO)Zz) zoztF(nc3QLqRfHj@c*1|&x&u~?7@q!rK>ZXuV=I?+iG$Be0`q=h#UVt_!rGlh&!-4 z!)?eO8hdfZHJD0d^%bNk2_fx&><2)edJ*Yo`F<-*TqP`7qU7QxO#Fh3tMQasModIf zH84{^e+-3F1gkUo!!5=Ht>e!!2NzkK()}%__g9qn`_gexb~tTnsV0#f3%mxxxBB%Q z2Co9vOT3MzzaZisQ=Cew(-aM5@GVYo>F!iz2{tjI-l|sVr%9B@J7pqi4u$*_wjf;} z@JmmFUz}A0NA)q;%t8bo`u*E*hPF_|r+L3wPbpSL`mn{Q)E4UBh?t!N`j7k@E`{4J zLZTbWdTUkW;--CiNekK8CK`aA{Gvyxf;!%2WWQ^oPKF`?+vhp?8F& ztf}uKL(<*W_4Qszeg%RSIMSMgf}PDWD`d{&>gme#q@+^S`TSJKJ=*^&WC36J|a$)QAJm3RT6xd!bl2x&*Zk*Zmm;;c1w|5goUZFrZ zjizHp6Z*S>5VN)-W34sR;Sq+oOaTD-gGQV(%EeNw)fz8;SZbE|ALIGVb#k$E@kXwOlfi}>V;s^#B&i*_p*zW zX8W~r@0YBx0u7<|<)AjLk#=ugVhVt;o5WGla`$HaeHQ|*5nU7U1sCoLxSDdDZ_xTT zL=$4I6rGxv7`2O!X<{>2Y+CSKY4n?K5Qm4&M~&*l?d7Z)u{Nw2ZM7{AfYdLiV6|_D z<_31IP={L9nUPO%v$=>#z;1>Zb0=Ztn<|}#uVJe#_vG_v`Eqz#QNVZry&lSa)X+7l zBROA9Vbvn?7g!D>y(MHmX029~CdAhIr{NCo!qY-8fmB!qVZZRF%TF)NnkuO!O_smJ;Xm4ruaTSUPP=HIR;w&KGhx> z^h;jyjh1R}-4W2p9@b0^ zMo=?wU9@ZL+UNq_z1eAqBISn?ro9MxnNK3}ylKMSzeDPyZ9kk3T#5(l$h=F@@Lu8-pO}R4}8Y($VqYt)9jZsj4AvG-d|Y_DAE?or=M?e=-I=D8bm_=GiS(%03kWr7_&P{^X(j*X97e)VsnT!CO zF^1$nv@3Qy;(;>onJ#0WX`amy)v1=;j_TImGzo7GY7^f8k$*%$ew1if(<~;`e|>eR zQWyGz5)Qpnt@>6MJm7jzn-T)bI}(C7`bOOfgA7Ml9M0{lJx7dB1-v_`T?sci;{>h@ z=b6=@lkZ)s@TR@Pq5>W#fpS(->9FC!8d`Om)yLe1)}IGOpAp=+Lm$)o4GEbrOl>oZ zTt0I+cLxPBybG_Jmxxf`5%JTocpJ{nxR@dV0>smz61{_Zj<1oifjTWL*$9xqSpWVa zW~4s4fo{rZqkt#q30N&=yuMvQCeNV}Lk1(Y7<(w|CB*)klq<^koQwDB;n6Y`#uH`( zr4xD!avojICvowYBt#1?w3W|2=QgA@L6Z3}na;k-Q)RX)G=NNpQguLpiGsE5RVy3~ z8fWr3ne^1bVMGAIRvnkNzm!@tkxGs6l;!XgevPtbxGIa4Oh#{GxYSRcH8nW>6fp&F z&Hb_pJ+RvQ+Z`f?)gEzCN}hmE`DwTdU|UcuW$hOkNphT30}(l_H0fs0Sld7wsJ=U_ zJ+C9rT-f6{`kxq(H!)$iU2G^OGrfQYdU{w;B ztSd%oxQ7-KYSCAArJbtmDLgfmJ(??b%}T3vQ&~!V`D!m3)kj+VS2xF0snX}*DQdC% z<|v>q1Po0u-XcuyJSmOv@Q=1xGI1re4Gu9`WmQzAJ3Nfgsh&<#FHtg|q|Tguh62-b zSK!gTkkNhaORIow5noguv1$vdW1ck%ms55CG zMg(RFWR{Uav)QNhiHH=B`nq-&$gB&?emSZ3(Of1A$z{4ZkKPA!CW99Kbi#7CFQ#}6 zXJ(2#*4awOuP=6b8o!AWz@W;Jl(5ce+#eGloDcS9(?Gb@eP3#2?E-15 zv^pR?2HW9KJX%O-{$TJk?#Oiod}44RB2FI3*k29aYBQT91YlFaSAT^Im?g~Dm&!p& z#RQV#NzDW#riz7x%IPI*EaolNBFD3Zd|SSJh3^@hP7Br5cr|YTw2)NUPE~@~eYiK_ zca7Aiio!-2EoO#gU1bf1Mm;@OYNF8BeN1vi;nyi7E8Uk*4)81=3q8XGclH|WCnVCh zFQhI0eX!T(u25n6OA_XPR$h2|&WUJdShW3JKVVsD>sdx9e-e`ZBs0v}*R^-7Q1Y1S z3Y|1k-IVJw7G{9z>SbK{%^eCsbll&lo|2mD_AT;K3(PhPC>_LZrv)#YDWjv1VjRD| zFBeRcit%K|G)ot>vdAsb-jfkxEl_IMR3MBqtD<=x~@LR@NweOCrWx^!dN29aJ z*;yOCzD|axVMB03GxCt=qvEmvJFeK7WHD#w64Fne0bNKPZ2kKe5-xKKRh7{ab7e%z z+bF13()wOR%MHS?CEHNNF4MrHH+>aR0Y__JDg-Vb3(`{TpUb#hpmvEEvbtpEfCdm+ zPCwm7YU9GBWJ%vwHO6NNb6vNJ!X(Yhx;bsU{pW~yzLNEfr1?y_ukBR)m z!rN%z9&SwW0>C&DP7|w~HiX#{6)A;rRcDAg0HT~! zI_!h7OO4Vt+UB+h1{3nBImrFJVs2u|WK060aN(LHhpGJNfC`i4 zS?K@WxX*7aa}43q6WDu8d{zq`Y-LJ7QVMzAd7o78rakX29Oe0&j|{_BU3%4I`&T z3`AyG(t>&c0y*#KH^Ogl@O+Vaim+JX3AOj%jinR%IUstH4zc+9V4k1LNY$V5+h2U{ zd5{iEL{sQgU&N6GDxE0u_eEot^BO<{8vzCP&?5i*gJ!QzrqKgt^F< zcDC#uBRY+2Wb$-Q{7aEgjHEXq4^oZVcd2f0!AQxwhb!E0IH`c9auZ@VO`Vg!$ydo@ ziWV28y{e^`TvoW8e2H1qRl55XHKp&1OPrI%?4QgKb?T?}`>)9sWjSa>ycjrEwJSs5 z>?(^0+1q6=6T7v?2{O+|=z+5$iph8mR&^@mY?@WdPdO~u7cwQc@VlK2XZPt2wh8B? zdQo4E|0pj}(VJJwd=sBn-z>h;PbhTO4$W7{V5K1bGiu$AWICswTM0NRzcOP-<$Cw6 zFq7Gjd1B(p>1Q&hox-7739_x7ast01l(M8G1HfqlN@&fhG9NRRmvkTH6q9w2oN7}> zPt4G~Qiqfa&Mi-oFNc&W%AB2KU-+5b913)!H5t0eD!2L?$)e(cXk<>jwW0z*J~JYz z=X(XE$qG~6myAe1v;eo+gRgPC}f@|D{RJOdHELO8|dZG9cn5F*Iivn;7WQj5t1jh^I`)J~({IIba zX;m&-5zUWlDGwJn(_^0Mmuy%Dx_y<&51vK5TqUBSyn5& zxAS_Dqq=5MY!)`?rP>c39K)t_%~uq`EJl?Hj3TDBplnor?i$S-)T>M)p*Sqx5(#9# zlk3q|B*1g6`i}E`^70s@SC+caPI~UIC_l{FL)-!68doe6*uF`wVjg!3}#tmeP1M#ch^xAU{FR7PGwCcBRi&KDYUa8fR}@6_bACKjyTrtaQC&< zLbHXo&QKhVas2h=*0`0_**oG*a(Xz_7zZ=jElMsab z!@EgCxcv<2Trv(3R4SQ63UVsSJ*#Sm=&mh!r1Ylbnfr<=rZ2AW0_G%znd@>g_85%r z#zKTtImuYnE3YJq!Ubik++})NM8yb;5h4tAt-d7=2ZYtD1T#pzhp^TfX&4;HcayKtWrQ-lMY#C z$K6@&!MV(YJe#5p;!#GC0FYJ#jT0yurh777sk|c}f{v)ysIii}RJ7q!-RKlGz-(p= zL%5%`82>HDC^}GX(TeTo>Z>^sol6RJ)7ttbY8o}`Jnc9H3TXz;-XIyO={|vfNQ~ltElZj zZc!2+&KMoXiL`1sx}By*sUzsi=Hev1`6P)VBt+g+)sI5hpe?hWsqwXUr?q#H_==Uo znZgDFK&Dh*F05#|$&};8aE$1E161r z5>`$o#(vX_E1leSt60OuUCI)NyF_$^!>KO^tj8dA1*hhnJS5C^%lmF#?R2Zi;kuF{ zC>%<7IIK{AE|}FjOc-ikMAg8BSDmPitdJ5GrH{xo^_RRG{3t}HM2Jl)O zJ~W29zm($qUj8;rnRl=Irl+Iws2*kMPHA~e?XIfBrmkj) zB~*k6Q+2TDM&rAh;*y;O|pLMAlYNj;gOzfJVf`j@xT4BTG6M3Af-ELH=FN-l_CSk3jl@oW4qf92NqsLj%$46 zRYSR8^90u_WQ~tEFDJ;kO0b)6k)BKjsWh&F)sL%QCBsd8gotEZY1pVS$esJsI2FL7 zJZxJ`NzLLer^umDnvR7a>@-Q0o177t18DCCz^E7q=%%G!@M=mNNtnP>c}aUt99pKZ z;9hxDbI(~1aUPaB*}ja9`Pn8X$C`4l%%HtnBU|3!Rih5&llEEE>g}&R4rvSvVAVGK z01B=kD7Ovoa5z zH(D233i|m$ZOZ6~o-gr|I&wNG{du?aZC9`VF^@L*oK%PtXGdC3Fmdzz4M+pzR{gy@ zt4$e^($6wZU^Q#`d|ZN$qkXux+}IngsxeGyyMo?%jLG9b>FyaiGyRraaeR=3MQDX+ zs#P~WC>3d-e}6C))>`EqVf6>F${f>NS;|Ohg&SY)WaI*2lZ0gpX-2|%#hJ+=BgZmv zRjLSTKPeMu%1sAF^;|k2enxZ16IO-Qi-?Kr>JwVrMK`?zk;adZENya1K&W!3QzIXy zGPRa|`RN*M7Ev>S@U*x{#;VE>eYhO8M58<$s{QMU?!*>8_EC$)_g~!*OIH!r^G_cZxZw(we26A@`Zt#`5s? zRTzW;*h=ngvZ@fV3lVwUldRHsqfL&-xM{rikbTBK1J;X}KYxX z0UZ`z1XQ5KnWR5JdW8(xzQAlocs9QYnPw-uwpiEVjJRv~?Z`|_zXJELs;dh3B!+(ukY?gdms@EoU9 zu4*336h7+xr6K-D@^MfL`DXX2QX77)Mz0#DZeLB6KGvm_%vLk7FiFTEG27#qYJ`|# zseHdk_5gcR{^d>Zj4)ti!Z3L9Z=bku3;9IxYBp*kT1&e`SS#0-5 zgM8*ho+X@os3D=W^X02d^5Ev^YTq=pk)~<&(ukdw&UCKOX9qCfpX|9p8+bp(i+W6o z2!Ha;_aC+g1Xm^p!TB@RMm>-M&RR=t9QX4AT_|YU@=)0mCdeuhyV5D#BU? zSq=&*ZBnxx-iye{fwXuf_$qB;vGSDU(yfts56QuHi{kPw8H z9A(K4%2V02m?F1Vtlc(EDg0ds)6xOO3#f~y6{Q~(n`<^9W>NfVFF;C={Y(A@=(Tje z04Ds0#EApn_N914@Bf(9PgzA8G&5e4^)51}UbYQ@aba$^6!UAwBZ8=y@*}0$`-*DP zwHj;AHwcBAt_mvtG{c|Eil9ba{Wibf4L20e4EUB}9+0XOLb*Xv$n1i$lY$XzPNmZpdS zB*h75`I!cWCZJpd#Lf74YT<2|1xiP!^3PLSOKXX$V*f-$d9}CLz7jMmjr+(hH}MnpZ2X zFa$tYHU#|SlU`>i{Z-i!P^;R1xalri!{EFv8Y9jDs*6mIt>X4ht(0>U=)eZ7=Y=<2DF)OoFFH)^STs8q|e^8abwvY(>cL;Yq3pm>% zg#@4#;xioG8)~OF(;)oz-A<>fEG6($Rb?6kY5fz^bJ|l_Cjg|j?zdCueQ=Wu>ipUMglc4obH_bQS$rxQ$8HV$Hi2)qk zzeU67&oa)psA5zIQyw%eeMJ_iI$*$(8+pHCP5tTcY8=!BzzOE15b3B?vwEM&a8$C- zqvc)LN6xuNI_+=Smyy%kk}(bMc|FFG^({q6iJul2{J->G7;4y6N>pCX-Gq#~5F3e= zAV8K%xW(RJ-HwZn2u{LMdA<;mB|%J*nChteIhFij;czZDsRxlc(y#g!&oSVMmQLL{BHXN{2G9R@h?Eusx_8mfy)wx#ch14wB(n zNR|2ltb%N^{p00Y=$>EhZ{6>|0uF-k3L+qZI83$Fu8ju+{xR?#I2$ip{F%A5%& zBX!QA#{SJPzYh&V^}>A1k1jPFE>{<3nv?Z*bS`I#kq4g8(}1+3L+m$BHsF5qCR4H8 zFiJPCaRKDQUkHlTYD##6#*>WX7wb<~V$x>Km;!5xHocB>oLK53`fiVB(VgIOqDDQ+ zDBZ54&hm3fqpxAZQEO&~6dX@P;4ZY&r=hV6T3$|U!_29J%xnPI6t0Z|B))bYvmO~~ z(T!?4%_N8{5TlU%2*CRS+M%~smO0lQ!-686w57<-I`Bbb3Y2g;{Yyhmk^S!FPXEKP zy2y53Y5aXXue0nYfkrPo+N|glW%fYU3dNhIsUpw$ZhD5zJ=C9ib-;{_DqUdwMM%-#7`+TU{;NGEAfKuvz0xXnJm%*z zuJGL@8$l0CXmQxkT&D$kE+R9ciOrns^~C`trSiWnHC8!`(VG~X+%c7xa#WL>ZR()u z4+8}tX+&c5`#zR7EkeoE>YzP?)?_O*2$GhkdWm|EXq@s5=Z6Jpm&o0!%tgCot#kE} z^JKz6d6umrl-qOc%`vf(<(lb_=(slBguoL$MIX_KeNA2Ni@5+F$+F>vFcf^inJ5`* zOOKWE4$(U-O9)T%IL$M=P(G+|dLB#Ca);`)V50M=awaOil3^LZ$M$KDW2=s4UrY?x za}*)U1Pk01{Yfvi}MF-MRl{pLqewDZ~ym;=!HwjU;`!48T|nn)`Hn^Tl7 z=YRiZ8goSn)+^)yO4Bta&cIEy6S0X%XwS(GO1Cb5&Yx_4`Zq*ev652|0j$zG721yb z=_JVbZpXNH2B7}RQj)-NtsK2=VVcG2 zwW#dDeyLqV))%HHwGsJ~l9ronN>6KVz@grMU2JI#%V3p~?6!BsW$Y*`XCSg4FIUBR z^KQ>V;@=Jg+`P{89EiLr@f`x*y~?d@3swnBCA(CnYVQ_^ozKI{L0nEJfNs#(>2xwr z1PC-}*p^*NOaA+2`8EVD9!5b{(ixeb!wi6}kBzbJ`fNzle^(`jA`Iy%aQl>v8 z0}SfaXQ-H-)H9g|fH}PMx_qIlI;M7H1TM28mG6;lRSBtF0i4JI{4ZXpx!V9S_M6EM z>Br=BWL=;x2Pz~0arI9$PR!E;D2Ldd(*Q8skxk5n-rUqwwf-FuOVognGaGb>Ga)g> zuKIF!NNl*q4cvMIfOn-_^|MT_RnYzz>)b$;K}eSch*ko&BVA^GfTm0m)YCFTR#@ja zT`E+3^rn!@x|Wu|0i1(jP-_YtrR3W*>JICyxU7$p$)5uO;cj7)Dej%Eo>JGq6Bd=3 z^*R9sG>3f@5a3o+Ud2FmrzFLN`cifSb0?z&@Wf657yHI5)E1rmwzOlVb(`ro#dqat zY2jdX$L@drPG+{M6iik0P&*-#!uBR*F3m%4M0|O(Q&l6NJ_Fc6ie*)9eGJRa0He!N>-1EiZyojXK9N>QzS2$IRdTt4#|YzapXmM;?N+)ROOb9o>Ty*Tea!$QX|kH zXx-ByBDfDTVuxA6w?DyGOg22KNLCD zk{04$+-H3?KS(fOUV#Ib-s`NRWX^07&dJza(bYFXUe9VTa-=o*`4;EEapzO-T_Hwa zy&XIW%Rj>$-5c2joV77+5vX0T#HXsa|1 z-&^8jK-b~_bRN_6?BixzZ9)9>9A7}LNG{|i-W}_wM`6E909lc__m8W~&K~i2yxFUO z=Zn3V&**7F;&fwfdCP3e?Gtf77jKJ_lc46p)ER|^+LoK4Y}Njh2au(dwU`r@U(2=D zqkKI^dHkCFTgz5$IYFRVph?QpmURGE6W3tyV#`}bD0FY}ai7bmotGnmNicEc^L*nC zqT3X0bpWK|@nnP3No@y1((Ms(t|c8S^qL>IeXl-H^yp$f7VqVdHZLzVzeoF<%H>#Z z%|K{dh%?A^#B4%G`d8ET6Tg#Q`0R&qJ6xlts*8@Q+)0B)3DrtZt54Fg}=vdtOW1F>>57cujJZ495(% zYR1})iGQa+=QuLU$)jtfDtT&p zqO12;)(>P(l{dS^+RGsbkxg0v(=tWmOF8F%Sx&=xzb|KWmc3~L%4{*S&9L0X_ek^= zF*Tk+uDxA-R{n-I?#^oy6ezar2q|ae5ux(@S8tV?->n(u!uu>`?C$68ur_7PB;q6R znG_apoQ{-aMa;<`EwR6N(v0_K4!5NYwfcmf3ptsJ{&bHj%&d|clYq4C%CcituXP5q zq4ZuVSNDjAPOUr@%YB<%eko`E7N>B6>B_kOlA5Ijj()>x+lfJe$&jLjwOUxVWt7A%u8}66tSXnIT&BQF zl(x0GzZsZ-C)L2x-nYJ)A^{Ij%! z5|>Zw9Lj2(2bNFef!=L9oqQtwS;o2b5hIZOFDj3^8CXq0J7pS@LqIP|+l-o3;L4<+ zA6W<|VjyM`GNC|G2ns?wBVNlN;byfzq~0!Hr7jgpCFRVpWk%A|%C#>eShgjj7s%d@ zG`a=DRT;Aj!E5o7glT(o+0T=V4k%PR90WnMWjX1^=XcT)`u`JmXX%pUNOqw2!WDE@ zMrLGk9leA8_{bt3*blw?{tpIKKurgOnFU!nRa|#hhX4YRBS!|fuZ=7CT11idgNTQx zxxi#;?81bnpz|#e{l0@;jS3tkygo$Xu0S~n&p*}?fMHq>m+|llu+<6Q+6_uwkCn)19@&IeceyQ^;$Tk6HbDEOOpaP$Tp(zt< zmKD_lV4)g+qN+DHIZx4A; z+&!67_4jO})?A~$ln1OjA7bF7g(>jPys>tOXJOU7c2}o1vp?B>fYP zI&-hq8GxjJR#Y@u`;<0FI(YuoRkXyQEq^#o}SlOT(i zT7P&nCg8zc%*XdEAa7lLndt7gwn0Ej%*d5VnDUVgjGph5C{2ez;x8B6&0aP%IJPB2 zBTvtSx3%>Mcv{;g73x>-sDDuf=VkpKIYS{Xo2>j^w2N1gOj+i`OiSfQP>m--aVj zZG5g^f?6KmT~u$OxWU5ykBAor;+C~Zo@b9P4)R5k0PwV<*x!^7Xc2#w4`Y)CKQRi= z*2%YVpWGTvc=-_bBA7{YOKK_Br#Ppz@WIR+MMOYsi)&1(M3N&jNDGUKhN(aG176TY z6Lt8X!x^SpO7@Aj$yA&AC+59U2wO4l_c98i?~n0tit$Lu1@+skciCqq{6s|chvC-J zrHoOX*p`5_ClkdnXRBdQGmFYS%nCsV2oUkOILO6k-QoVHUok`eM23}!- zxfUucNoctE8soZs5LN?#Q4_|j!T2jY7G1!VhJb1 zq`6#ptQ;3Jbs{42E6B(z4XFly~$N<}tQNVMrUfAxzf$o?TEW6D)|B5e7xW%bQ>?an5ox+&G{ zt_es}kKiv7GA*8cw;ZRfK&`{G%Th{zKHSR9L2go>9_4-jnfY_IxOywMqfA?UG8XP; z@5A~lj2`-aH9HRi;Xy;jdBUQ4SM;geBFbOVyPIvUTgD4CCHg&eo?; zYr)9@=v#b*78n-S-ex{q+#n{7S(2^qS8E$^?y~9Sr^&puB08~&PA=C3-$5@vsFoA( zJQ&&8UtWmGkBN%ar*Ls}s+_^u;zlu1aT$lry{5UY1>P58N*du*{XQvx4_H-x`vDak z57U-fTi(^w0@zRigp-m~*&L&{P|8h8W+TKZf({1>4N|pHO!qpC>~dd-WCkF2LO_}g zOO<>`f99!u>svX~e{t(gcC_9sP`VWJ6lmsiH1im0a2%nN1!K2pwVVjOO!jw=D(iQW zkW(?JvL_BrVJ(o0gk zhod}%Bb-4jpQgvMo`%x_o^(RBrf2Ro}r@@$o&2J=6Ba(k!en9a&>O+8OOlll*(q952;%U+T)Z&++gt32II zrMGM5AxlUvy*~2nrD9>cm|&X{7JfH?{dT9m7x3+*dE0xjpe%OUa&+BPSN64p@%ht7 z99oqdXP>9}f{$&(Sxs%El8^)dB%!GMjWk zH?1jJj#Cj;0jWxl%hB3PHLyvWxb+{@cDf}Gmh~v26{Tw?xI80QUUt8W7y>#lGj9u| z!10L8DF8;J?G;9?z^1=Q$oFeIo1XHICE1$@q`ek&dXA4mf)aL1-YzwRubZ{0Dn7tv zX2+RrSLA~lk5n11SR04u--_m)Q+Y7_<|JR&HmNJdHoL_|65y&9rtGXk=c=%-sZaYP z$O@GBO3I>Uv$>Z9DxTu0`3=^XiDv;^u3g%5w8Z-1<9 zCR!p5Qg@qY-1ef6>V;$j5CY2K06C<_^>mn*!TslSIS#aZT zR+s|KUHEQmdz6tCGN3TE_vnoJow4vB+);kY@=60H|5}dnZyy*{da@>?U?@Rh!Vd7` zb#3D4mY959+Xw-8n73r~m!(?IWI2(gBJcHMe4Gt*z^gpny@-ALPnI@G$eE<9(TKo4 zbL|zZMpGrpfGQy~J`?U;r>!K+*6fXFAVuJUgV1HoYtM^wcbba%ed7EKt4zb5xg1V3)Dbvn$jEmEQR1NOQ;zo^4$GH9CB4x6AH@R5xL`Rk9bLGHNRvlX7l#B&pOp zjg_m2Ut>BU(1YdKr|4C@`L2uyz;n>l6mjq&2$Ve0+qB{A5Wkm@sa(2_+ybBMzb(w^ zH5U>VSrCy<78pp=U5?TDq--wKRUR!Vj{#5T2pFZQJbjAWYi(yzDv(G8jK4SOk4i@` z>gr?p&H?h|rLk>oH3xI9s>R2kn-YcKoeu{I<7eu6I(?*EyC)iUODSyKtRKjj&e7Wf zffpGKe2@&#%ZEa|4nR=Nainhxd3moj(A$OZnc6Q=JnMCX+W8lKq`b0ABn-(g)(Xz2 z%KFBjpDk_H)e!EbJ69dq4RB)843qG=965Wg?rGUa%0{pGNQ0(Q7O0`s)>8-r3I6|V4)dK*9#Rm*_R@rF!mfcvw_a*S|KTbFvVx-_y*6`t^Hyi*yAT0ZpyF`t6211eCy0j}#5$QuFu#C|5`{GpVA7BL0s($Z-L!jmDmmvI69 zb}dDj>P40xMId+-QQaKp+2RI;P1!s$JxR(uHrCkAWL*3edh0X2y`QF?<(0&Cc^9ud zVZ5ZYq+Cl=U4QZzFm?1@JB4=U{iGmBBQ52^16&!Tx z^n7ixp4U>wSZ5+g+pc!IPyC4D?WFs#n5w^+&$wxfROL`Y=W%VsUwR`zd6NOvC`h@z!C^-e~maG8@U zaM79L>KzX94H@NZ>g9gjtwkyMqpzi$_J32?dswF#D{s%RE;d3ktB5mwNY14G^klnM zg?wuJJuuCum-5u|KViF6EK6F!7Tf#1vyer^A6!ZO)A#47)OHL(G7V3rGJWGvtkQ#W z08p1A^1u<$Mc@>E#Q%e{kQ2!Ch)fVXsB4CQArGXVmFe{-CS;d0rY-%Titju|=|gF& z1nDsEnJehk94coxfeUkTH(J`?lF{u5GY8r@Q6U%48oku!&w;k%V@5 zysK?ADsL+Wm(snJYU>sYi_{>>GM)YAcIE(1);0(!8LP9G zC}1LjzM5(EF_~PdR-YSoV=G-B{$502&@VU(psfojQoGmJSzRp*e3p}SjZ*m1gfv7q zqoc+8iIrQm@5$nxq)hUB*e>!HW{~Bf!xTv2yV&#tF(q#9#XMM^1cCAIWoX4lLPdjx zkg8z(n!B2_%&b&;X0l>{=S$O_-eo;A$^^tUTSEfHOmxCI@~uIRpo)Xp!ln=XB=oaF7zWnZ9N&hHa_LJX8oa z@)gO}a-~gQOUWK(Pz172YfCfdpa8Q;F()Bo7plxPM&wxHeN+>RsB_7OwVH z#(;F329`>msM^x`Lrut(UIL)>UUJpFT$k~Yugj2-!HcN6kz+O6Kz5B$uR^9ErNr(o z6#k-KC5h#<_hd2xvpmen3WN~;=D;;2WFB8jR{u33BK#j5WhyEM5sl23H%$GQFwX_4 zhJnyv#5N3|@~mxa5p|+C^7V)rN{J~d|H;0*8Y^- zmW{r^G@<*^J^`EB@()r5y84uIYh50Msvi<|t0RfFa_$^#ei}S<1V@XSiW$4t)ZEp< zRb1Rf6dmp#x3A)9J4rU)`^*#-Qau>c_hr=Z^rg4J-#*DWiOAN_8D|+Dn|~<#Z!C@M zQmJ`Uj^j~z+n?ibt;8fL3lX;;uqhmtP7*tUV0{6AnkCWp50* zvFu!Z5?h$IOje9WlTL63o9y%5nspO$`&7N&T&eM zmAU>R1I`hUDdL<9S=J^7D!4U8hKG~HiJ)uHB|It&U%wQ-pFhpKv&;r5KV+HosAm+v zM0FYazIGoWu?Hb%{4JXCS7+`RPR@UZl?A&|(SW#NX?o~I383ilLPoHFa5va~wIG8} z41p43?B7jIQb`?}HV-#^P<^E(CqcyB1H7~Ez%FKxhmt9(+NN(%+eEE2id*ylR0)GN zQ%sIVBS~!jNa6hNlQ3TDUP4G?w5rq#Sr(32(l8d(oyyz8;=zQEt+bBQ6o#k+ zXZ)V8fqQVPUlGtMK)*n*L zw6+H!XPd)B33-Dn(KT*l5ywhZ>BwTohM;|$jH#qzEx-Wm+QH;t8Id&ZG)KhMmOs(m zteU!9?)pQv6ekY&V$0p`z@;^->L8x1>Rf7dag2ZBL6&` zqh@WSemAT3IZE%Uznaw_Xlt6{@3r;dA(KNxsq$*6)~xI}A}1po#D@wn*rfW?WMf<{ z+Ly_Le;kvK0#CP9sOj?c;uTmw=!XU%!sQ6+hf;RNDVeI7t6!%2ubm~me-d(5SCk7F z0F;M!YI%;bHYPDca9Eu!Wq29-m-ZPk~u5^=G`W) zgB=0UgT|(taxgrJ<9JDy6@w<_)>bD|ELL#J4hKhEe=04*-*D>U2lw@GE%5~zZ^`HY z0)A`#Gf+ePz53V0SjwbA+X0KjW{c%zn6M9`tW2=ESJ@d0(6G1=<{;xeYMBna7RF4k zAKqVpx&4%*V2?6N51n?nn4V>X;*-{Z9(oB`kl)FEm0G*RUEsy~lUOM2r&6Rj1%SX6 z8)T3L=j@fXl4EsGGw&M9BL>c!fc3}aIuV}XN$T|gc|tY{$RzplYrP-Q4d*WDasp<) zqyGi0x!_!+4g~&VofD8&dN@j`@=;|4xTk_X7@#vjX(x`rmZhV#w9{0br6OQDSCZ`K zvM&+nu0@j$Q(i+oJe&h)bvK723Jt}Q;OXiSU~MuBz637=@Izgs7 z?Omd(bSU)R<{-Xg%forPDeE#yxZK~$*~DTd_%y~dEygu#?C%u=B?}|UWiy%@Gc4i; zj7$b4^8mAmf)D&v+bf9XWUu=87Ao9GOmL~k=r?5!q%5UlffEig+8B{Y8DT4LUcq2Nc1n~A4Zz1VeFzUkzKptIXV+!4 z{|_=AF?xo>B%-7}tb2tkanv}JM23JtA5*88n!5?rs3rrdouy3Bi1lH>*qWA?djaXy zu%+cN=z*dZzHbc#5^Uv}6tCAJ*xPqxQmBGleE4`6eOXuewTFn=rJIDzH3X`$ZkgL^0Ye%wq-p3%Z$jBy5dpNVd{QX&A&R$FI`9i*C*36Qy_v`fjevy zoYkl%_(g6G8p*r|=C>XI#A>Jm%to^Xmq+``fk=`k(EyON7>&Y;r)ezB-%6BH@SPYy zc*3wRBLSB1iO1sg#&dLulHO;Or8{KmVls4=F|8;Oo>DyAbWGImlF{yDfiVEHaeaHM z7*xSc60MjAd$}Ar3!9#DbxwHUTG8%uPP^5PMD`l_92<|a*Qd>LAeUEGVH5pYF}GCb;fms%g9W& zge#dm!r6$iXI%x6;D(@IFt?FKMd#IzQUOH5<(M_(aa-oO-|17M8PRW*_mp*>`0<=1uolm zCF(@?YRb(2t_%4XPQCzF{n8efq1{w&SX}8lr)%X$84HmoPcV-HjALI5L>u}iOjfMe zU{^^D)w5Lptax1zEgGZmlJW3y$x*M}$UxA02N~!-Se@?{H{t*&wB%PwBW!F;Eqw2= zIH#1M0SfgblezVCp{1eV8NsoBl8>R}!GSn})LW$=(hY3Y3aE7MgoSt2#8i#@K3m-+ zD2Kp|IVh&O{u%jppf1S*H#5X-y_Rk^kc)TWaTDk*!`BQ&egJj{hz?MT>+0f~lnaZS z#1w~FKKIU%Zj5=T_%KPZP;Nz)6E=p;6Y7|_kZRiX^IT1A;mzEZy1Ir3T&}lQHw&6N zN>^A8h_xvy3QbW1OnOba3Y1F3g>qoRKqTHPpkq0%L@qpL4CV`J0l1E+7fh2v?6?kC z6s3`n*QUEmEg(5t-YjWGy~4y&SQ_=pmymM|IT*!1lD5f-{4-UC>)7P zH5{fGIgCTyFU1ArLzv9R{fZA>zMq(z2kP#a9}#NMCk9^T35dz^($kV6GIBF0JiVzyy^-f zqhm<}gW54Ts43d((uT84DV^xDZB~5>_I0z01u86`-N2L~Xyx?QkMcPSH0MVyq#RDN z6C(5Cj;StrvS51WEsyQS9ZypJxA(jA?ld`7m?;bU;{zd;rQGA7!?i@fViMcpTJm(b zmc!bRr@&cUhO5ew9@Lc@D`exCtUrc1M)v$#x)`Y>{R1iF_fy>Uqx1*wr96Ok^;s0L zukK`R?GXVp(d{piAV8TW{xiinz}fH_4gIO53uedMgAPVPiu; zw9XC2#GzypqOT)^bF1GGfJ}F2}8K%NNM1MbnlhsXP3Xr!AYfp<` zgaK5T#+I&JjT^b6y#d^0K8gU-$}IwyoIVmL))z49@A zTJ#A#Ayf-ZP+32du{`0EVtuB2U0anQJ-Cwtk|iTL96y&wBXL{BW^A>vlaLU7QCJQD zmMk@_1#j$gu>saR^pN0fyd)MAhc`rKC42z&$_8Nz}luQwG^@F&u8zK~=D4e(rU zk@}V@VlC43{vA`|9#xQ?t{kny>@2SS;Ky&%)GbbX9C9SF0Q^>)+Lvu4gQ$sUFTQAAkl<#084 zNufkKDWwsrgjOU%PGUn{xxoYTA;x|>WfnMMMHN!7m_8VF2NEi6)P~UjXtY9aL9m}B zfo#|V41l;siweXP$dz7Z0b^a7@=Z5~Pxt(7Kf*iE>#e>h7fewp?8XzW^PMEg&k~{*Z5FpSNSWvVy_f$37C|RYBfU4s)}$Srkq#CMyx|} zCh$Q{M?D-RG-_cP7{)*L=`@1badG@XxlXB2fXNII3^X_QNJ6w>PNJhru^lRyOpOn`nfazIp9w~BePx=~EUv1QZ;k~9Ch+py@in3a2V&L7B$I(&+hF%>EN;5R|ER|ylT0qBrvE6SpysXnkT z;9@H7d%Tv-V#KisBAs;+!E+m4)6yZ(WgPqBz?9`zNqgMURd3t*8podgyxNY{${Ldu{6 znw<7R{FHcCNAnS^i$vH*14L=g5_To{6Ji+7u$y#fdd=|KJ&e^&(_? zNQK6M7Yf~)>lKi2iE^k(O3QFIwb13|@5_GSdnF*&Pm}5_on|I2Z{TcNoE`)?52Mpc z@wu8iDVgd7pRBb~p02U)!o?-TE`jq@NpMhETF9o-8nrkwl67@&>)GH*!YKeP!Tab&sUd5VH}RKirX0?Mm*oS9YbwTyq*%g4%)gUYH?7lf#Zb2ppWn8c*G?PfMj z!`9l&S7P$?W>)3r$xV z@}+U2kWKkrUI_yz zh3Y^VTDG@+DLvn58cJi4d%J#`IJ5iHJcyZ$i2O%F+AaPqb1lN1qGNlt+M|rpfg#`V zR=(F{v={OM$Xke3Ax%q?sUT3D3UcrVAC!cE+>1Dt8KGl5L;y)cbE+z{Hu*ItkWP|% zl67tP@wCgnOa~!?NJ``=%^?nN3QHlyrT!AhSLazi1R?^>&_xJsl)>^rDjs@3vd7|I zJzIz-F<_~M=(p+3#f{f8rLX&TRUsvUgf&0~U#0S{jp5LV9H0TSYYtj}D%LH3qJCy= z6ozIvF$5F)6#S=FN=@!6+EZBU#G3*RLr-d9X6En3%8L&UYeY zW=&*U(Pm2eG>)xntCY>X**OSVA5VnT6E(JT%#?umvN#tpRK1amDqb2vA{0shSJP zs;*{dm(pe8(8XW?p43MS#vrAPz{#x~Oc*cPdS`xMdLEne4t(>ufxS3Q+9;iqIa-vr z7>z+rmWQMr*!3No3~acN=BDg%546atq=0ex#S&LeQnsJD+gRUF2Y$QjzI-v$OL#Bj!TO*; zEA8AR|L_Z{rX`lkiM64K1|s|!%#wP!}kuU9ow+BFQqhkAcMxl)Ty^4^!s?* zmusf#D*mRf*_yIC5xxooH}IH32#phH?jEMix&EOj3*W&{RY%N~lWy?ASl8h+XnEHAAU{Wf6f5O=Hft#u1e^A`n zp`^_773sabxKYTn?dl(DtVp%9uYhswazddGA=p7i1x6WTMsHY^4uR6M&f8UEe@TGqVc>{o8EA#;TxgKe<_YbCa z#z4uaX2`GU0<2`i26b)j4B$zoHmHxKEQ^C=fLyNhP#Bv;AVD!YvIZ#}EeF?W`Y@dA zU6&ITnyNRclN9Bxm&2$Xd_wNWECOynL6xL2g0%aTw!E~GiY_(amqqgnmX|t7DZfnd zn=!3gFibjJ!3@exwm&oxEsRb56eF&0gdOwS>CFcS0bTxZI}b-HY;qDZwIZXQFP|2d zBuA0+Y;oi5WMWf5q`Eg_KAN^qpW5UkquhPMaJ2}$_qwf3q1l72eGxP&*@CaC%exv-Q9WtMQ6TE1wBB**XNJctRO zx>jINigs}e{a%IN5J1vrcB=j~V|}bi?5-@vyYUCT4T~)k0^Q2ncGubW%SO77Jqr3- zN?!e5%7eXil7TR~q1A!3f->e(dJF5up5PbJp;c`&D3AFC6*45_AS9C}K*u0@pw!VE zgv4@+=41kGz)qb(K_Zl-H>rNV5RHdWk04WKgMDdHVILE=M}-Y{r0hQL7j^pP?E@HZ zC6{5Js!pi188x3aBo2jZ?RBJdzQnU3t{cv<;uRq)X)_CkQ4nTSv1?C}(HE4T^6rqcagDdIQ}Oo>WK=|}LW$XF^^u$z1it9X#m zeRIK5{u<)-Ou*}%S~EH+312!yurrU1(U{CBxDiltJjRIEv>E?Acn>+AR|#E96+&=u z^7*iN$(Mwsl=vPtYE{4|dTTZ}syCQbVP0^jDTYN$ruy2(X%n#DgB9}E&!)@Uw+PYc~yG()-UMWqO1xZt{VVE0AiWW-b zdhG2IXr+vx)VcO5n#^_Hx2Zl5akfosN60oW1(Y5oDD^i2=Tuv@x`9c;%>T*}E{T|& z*0fQ4d~I>$bKGPmH$wrS$Yp#ZCSNl(iGy7fiDs16=^=IzPu4cz8)e%muaE^uV|i0k zjzfHrIlruOE@i!m76}-*kXY{Z)QD1~huG@iFDxJv!BN^gv`D&azsL_rW;l7~bU&T1 zY!WbWa@#4rP0eVXN{AXvzoHu*DsR218z1q6Y>oys4OSQnCP3&@Ma*PMfkUdgnVY7l zCrg`zOxC3DRab{;uY^KTc)^)VZ9jb4ZC}TzxcY}gh>7nVclWGMa4$aK$qMwMF*}wD=yRDiB=5;SvQY zAP=3NGU0lX2HNxFEK!EQxj*%S365pnLdJy@FA?8(l)wyTNB|uc;1tBQINPW&|5pDi z9~<^^-LfvXQyhdmhvMa@d|e{xOy|pt$|H_*j_FSf9V^Q3X}?3bQ9ks&l=NxF$+a0W%gNL+%u~WUNB?vwD;m0mhb-Nwvf)TJ^_?rz8rY(5&kmZ*;G6vRjLn zGWLF<7%i!*Bv2U$_lD^&2IE}F#1e(dP_T>!kly{CK%ti(-ml z*Tl@d#NR8KODkIQaObOgk`qCl++FBt_qOTmEU9R_{uKy5ngJ1IoR;t{`oAjb8V{KU zC7tMCv<8FD9?q-V&S75NOOORVFj;xRBIVl`fpWQ=IKE(hZZo972OV8$s$M$KGbzvS zlnQLYMF=OV^?JAn+LbZ_0lH_nX5ucUl(nFkZ(Ax`#3p+pKD_>FQqM{klU zw5n-OVrJ~Bs5#A1$*j~rG>h4-P-e?eaAz;Q`vFo+(?3a4GZn6tUSDL^P2J0!jR7np0+ob2kF>rRIcA? zD}=GEaSBh@j}l{aFXSNwaxSE$Nm>bmS&}v#Juh9BTEmofnw)T;Ta}=cDtyJvp)s3Z zJQcF-7QT-S@E3d_%tS;kE=37ZhVv4&|knl?NJM6Y$Ha=lo8ZE9zDV~)PkxQWt zDn!?XL{mSY9zOpdq)O~Ckm)1aEk>SqIM^Q84Y0}6gQ;*TuQ5&fdSZIYTb9ZL*qWpv zJ1h9L?Qv-y3~a#PsIkAFI7g`%l9(kW9|=jXRgop{4L%@Y_?V zMMn4_=9MQulzuoYxvPw+7jJn#sYscVRDFuEXMGTsRU>vOQ@W&;Z`H&qpMK04%+HWn zolaLv2Ue0mu4jPzz;(&*s8LP2zx>ptb%#`HfeEfy*#5!#ND`&%Ifbz4qz_agq=buP zwZ;sPsU;-jD1>YbIx)&II zs7d}uFaPp96r2216d|-56*ftO6zGP@kfJNg2$_zllQQsAd{75Nbl8uTP6oamEf0k1 z$RJg1(bT!BrZbm+PlIa`pZ<9Hv10{<;=IazSbvo?9{T~q9_}SE)6!yvHn(wGygC;u zrcQ!gSzujq$q?U2nF1bl%(kt)IC8#QoQPFQt?{5#c71+^zvT(S9!}El4_skqLcrY# zdA7LmQc57f6grHhFQ{(S&C~5l4GF)S)I2+`ns(Xt*vtn=Faw{|^Jcb)_#I2xf}&z6 z;Y1ll7oZ_NEPG(AAO&@B4 z0rP;8M(Xh4wmz-ib^FJ)brH3ub5MzpU>?PD2iuC#WkWM$7M7_ym4_^yl=1frEv0Xq zQ3@mGy;=%HIPj-*=Agn2_i_95|dLEaG+mYMd8qS}n}XU399AUSs2IO97q#I+|A{OsQnb zfCaGc^h;HArZM&IdMq=R^8hd1iEmmrII(O?0tSUEQU*n2Fgj^?A>d(UPvT8qak?$W)LWB?O=VA-sn!Q+>2Z6a zB#(;fYN-BjDK@)D-A>Q&WO1XI7%RvS(W5L&BzmUuO;IyzB^mw9E6Oy;W!I5VeCZ?w zQ{^#7Q4lZLf`rrSn8LB+;zlWvc&U~Vs%4%}3#sNWH7Pkpc2?xY)_x*mMyaf%@k&)H z^UfYZaCQ4f7{=r_sB;FxMi~i*;!4Zwo?95dGyu8`LIerH9LV8=gLLKBgnSnROuqYd zx*g5S({X|dn$bP&Uj%dnLW_2X+h+0=|Mf1MbFY?XI`3Qu%noZeSKCVtPIdK5_oyrI z0hJ%D&gp#|Rcuh!7Zn>-m8LRZYADoHY@NO*i97rB-EDlV=Rs>sSneodNd|m^R(CB zAEeG`=Xq4WGlheBB^hNKkNg2t6_q`l<8~KsB}B755^SbRh+Azv#{!%vlD?zTz3tzL1x2totm+aP>c znN8-0dk2q|34c<+2$Uw|EBk&UUmmsL>!G*&$@aL)seJK}yuX;MFn#L|Kg}5T$G34C zkuNJ_>|6*mO>b{Kmk)22F@BHZ@)DUDbxyjap+g44HXw6O*ErDA7KvZqy8qfom=-pP(<%0+ z3P?hQF(UO)pe2T_h%F+Pw)=3gB3y#DQb=dWJNiy$9cP%|@S(71s=VEYbzhO%iT6UN zac#`Ge6g%!chfGB#GuXyRqu8CGdKBKMwN0XF2CEIYb}E35@wLE4NM_Pz0r$js5)jv zzHwc0Dm9B#jYN?zhQ0c+mxb+^JM1uHnifLG3Be3%>T1sW)W4GnM(GJzKf=eCQ8u(z z>hre6p>A?QyR+_xxC_}1F%$$B^S9li)-Q=@)4^fsNo}-d-{Bmw!i{VX=TXk_b1|9j zH&1e0oC3wPqu}5V*HMC(`VF@Td^wkrvMaGmcQtb)O6ni#_i>Q2?N>Uv(@groeUzfV zml9|hV+?)dZF#(!f<%5N;>YBtlRg>Jh|~x8+BGuKnA!;#+iCCt}cT+@&d)7 z*({Y|T#JAO2ecohtWat>A=UK2*}u>N$%-aK6~QbQK3dF^;n|!=+5T}|&`wvfz?`Fi ziqJ8~tfA%6*g1RS0M=q%q5AT~Zq9P|~xR6k*j= z{!B_cjR62cJwtk&`dcNvklKK8%2rAJ(A8Y&j3I8_qjUjM1yVW9V7DS5tg3h*Ge@Y* zCtR`0kaykV?b2Q)MAF#-PLvgvi`r0J`HT#(q%1&_cVbh~+%`%K0>If6sj50XJ#hS6 z5tr&ZU5b5esmtkW6aS0$CCXFb)^`6+L}^1^m24+<#0K=woQR0SOHpAo8}na!@z+3r z;9<#iNG`Uuxo24HzBU+|meEoGtlpq)X{np5Mc@Mr*uUeL!Etn}R_EIRj7(t?wt`?B*%s{ud!W&b;!CQ$>^{Oxt%YzS z@$A9#r`{xRfqQ3Gy+m5iFfmL23N(;2RG{tb;+_-{@+IqM$Vji8p#kT%QzDGZNN;@C zFZm(_3lS4Ov?lsH5ij=XL_%3s3YxMkLC1RIE(`HQzWsf^iil8-EJXsU7861B?T0|n z8Hqhq%hc_EUEH9ixpHz+YUNYp*K)Dx=y~0$yf+ZWh?b=E@q=?jnys88>zMlDKt^zi z>Dhz?+)`wc3V`DJ5xsHMbP|>NdKWKuE2T#2!?iGzFpGi78)LiO#VElEz zfzEumj)z!-$|#5}L$~nO?In6TMs{oo6$ZKse$G(o8l>jb-`?2is?nk-` zLf@a`CL|jtN@XM6pQM7-QS{B1b>J(bWtjS^sYGOGGg?4&i^bZGF`r58r{AA}KrjTS z-an+0S$vg300Ck>#$3>J#+E+jbv;#KbT8kgr#JG^xWlrdq!{JA#V7*Vm9&0D-H@U$ z_)oZzV!Y-v=xCk=abDa_6K~umD*SZ(l|=^@&Q>&G+u|T97b>~> z-rPn^Z4xPn(sUV28RJT^ZsoKeq2OFY)UZ*uH)2ZiDHE09feTmD;o0W3h9le`_TIAG z7!)y{tuD=3^4Lit@_Vhm9olzG;{y|hm2hD|IXOxMtobFDfG^!dl!vt{AE7E`uhe1t z^YRS}=H)3@4Nry`Jo(52qk6u!A|uB_165nJwc%drG}kG&R$rVOWK1?*7J&Hzvt7I9 zi)e&TaKccNK;}n6LV@?{iqIcvj@(MDK`su1+F9cdF6E`Nid_)n8FW!>>-Sd@CHN#` z7qNIZbvD9MkX}`s~)PWAgA1hd2s&wJ_Gh^-T4&Rjf-Wzke$tNSCRYsry~8 zOm!XY{DP43x7@nCz5~i#>PzDVWNPd;7Oq+$yZ^GZt5Y0hWYo6Zs-FiE1Da$g@e2j} zu8^t`@yT~gaBdcn8R;_0k}|gXj~MsXRPwU2UBdY@`%a1c`%bmmVpk$BF(6e^7P5$O zTqV7V_b2F=E2EnGGp}nDPw)z%r+Nr1C_;yz=u6WXJ>Nr|U7RT%C{0p*lQ8~$lVrf! zSEMzd{bUdPYnc|0h)*S{lZcXrObDl)2sSRVFHULWtB80fIvw^HXFj0S$=L9J8N$~; zB!w)|kJ98Znz|zqz7$dbaet0eWHp<_*e<_fOKrr7Oj$n<-S$k;btUl)02mN=MF(<14&q1-Bm5RrGIgr_@Cl zyPgg5Pw+Q7NXY;c*gh0H#^NX?^Ea-;yafJ?ODgraGmQg%WA5TMMZ5^r{uK;SlCScol)HIEUtrkM&O}2$kWcWs za(ox^u{08vjK35_OX)E0hm{QnIDCd--sCfWMVv3PN?m!~CMAw(O&5A5bNtLNcZAiNEV7a3*D#^9)8QvonTpv3%%CQ$mCWwJDa3jH&f(X@8Jr~5g$9m;u_>i~tOPI0vd?83mlb4SY8Ta59cR90i{J1o? z+HL;djqEKAEXb;m_RCxiRIL9^l5GoH{t78!qX&ic>pO~zi_f?i!Bg@r%@;Bi0CZ-i zgXhjB#bQgkPmtBxyXL{Nr3-AsXtI&th1)r9C zQ=}yxr>V@$v2%o_(w2Z2V*;CTO@`Z&pdN0Y2Xm*8JO_rsHk7|ojJz2^-+kg*uBLh7#cU)KI?=N3U z&i5feo`vKYu^hCO&2Tx}$gqI=MIl3wrWREGEiFpj-~Kg1KGs$XRL7INQrGn>neZ94 zYTNAecqfyMrJ}NYO-=Wj#`;>rM_O z^0|@oXZG;QZ-@5$G8C+mwS9*^tN3I*R648^tK7iDF-{WdBT@c=`J+u1ooqB6$Z7*7#>7GX{k)Xx`YDv6$vjW4jvF_Q46g{r`{^J?69zB@q~~2 zJ~i*DM`9=<)?dBhdP3n z&01ss)mi+)*jSS$1;>U@HYu-Kn_tNYBBb{YYWJ8>DbHG!@d@F)Wl&FL{FTf2T1Elk z{e5)IJ5s&S)zkZUcZ`>ABaJvsS9@0P`}-*Byq9r1#~Kd_e9TBi!=VR7108&+6qA`s zScStbx~iK-p<^OlS{z`z-N*Y6fjx?s@p~IcFHk&%fr{-iglXOV%QCFo$kcu)=t|<= z`b&pI*35)fDPuI?gC?dp;jp+7$6f6g?!WI>ucZ8eoR4Ehw$m&zQ6O}BkJC7-X1&wM z#ANhQ8%gt4%X7B2-Aj%eX4F`Ji7h_oRLs)mz)0I$MraucF!-D&H#SxIBcrsmNWb?DVl&zrUUUWXg0Kl|fz97M#}Vt~cT8r$BH zksO&>nmDXvd&jzQrS1z-*2Nj%fK;RBTbo;aC${b2$jjoy z;;D<*eLd?d(tvUC3BRTyZ7U0qRRw)ee=2kPE7K?7Vo_fW@>~(~a&f0(evN#T%oUjQ z134cFtf?|!Hvjj|^73Yur3+uqp<>GA`{nGjO=nN?uhqJ1ms6zr=6ROYrAs`mmL+|Y zGMwfC5FlJTA18rVYdm>&d_~^URr!x_+?4j@JAFi=?`1X+8=JtgvGBMgE++*kIBl`@ z`qgv`ej}p+4U1v{Gn6)oXZShe`Rw`9DVYKoF&wP}ZQp!81l%`-T?yM7^OIhZK-VT>hpwgntTPdlS zZ)Hpq>Lz|)X#)-;b#D%fk{^Uj8NOdJU^ug*wv$93mf55!)<)juLs&6i3ZX3;P$|5u zuW?WJ`Z_;OlG0EknPWEaXDT4JOUcr3OQNp$nRmo2#dx+xgp;P2#@71cshl!zFjTO6 z(Eqxe;@k&0*`~@Al(Wnj82Hm)$`%NM&NQ~p-3~P=CgJ_kc3w(~hv@QBO1aAPAV}Mh zxE>}eCM^c?=7pZ+Cu#ZY6wur%>;~{2WX#+U7M18Vsn|`%xq&s=3|3bq$o>dZJH#vY zwU}=}s&!RhanTPFwgONb{Rg&3O6FbgQ-!RHix+VgTcUsyk$HA*qH3k#m`Br>{rM&u1O6Qcz$ku~{RVCy&b1^xn zbYkJ_mygoCk%wEk)nb>sbhS98t=r;yJ;S|}8brOSB)rn1M6b8&eI}+aDW=g)$r&LY zK9KThzU9BCql9f#GRhST8F7`pwodq*nZaQf{eSgRT5cXrG#4R8_kem-?u1s(M4*iQ z*qlhl4l>9YzyK)J4`sRl74iE}4xh+qRiCRXC*Lgw;kL!q5|=OsH$t|}qKC+WEiX^$ zUxj@A&|3JMR-C^|NE}Z}p^$n|>c0*rd8PNdw``4BdpLqijaZaXo8#v)?n;Jo?n{Hb zs*>HxD3bZRGNn`-av=V%Ys86=(}(`K9#g_m4~~+p99>9V9CU-g*)j$$q|y^*<4TYr z_!Ak+(ndF#5@*8cjLj&8mf+-(PGqFasH_r$m3P1vk5Ss_{umDeVnvbTj=-EJB`4eN zOZzxV%_yE@>vo?(w73jX0qZV6otiF9^Lq%ABBk`!gHo-W94V40$5_{fXl6u&VV}zwP>4&{?gh+(!RyXLk=*@39wHD$a3TSL zP(sPxV$9*c%E*1=12S*U@5f=zK%k-Xit@+ZQpTQ|AR#G@sJrz8DIYQ2bRVw_;tAS$ zkg{%9D?Pv#oqSABJ18|+C9Gv9qVJ1g#?LPusPwfs+N9$w8v`Qt= z0{OpFSTW60U0o)d>=guwT`fb>B8l0(VZ}fx760m5g%FRiP<(CoJLWAEzzuPE5_CrnVprxEJFHRA}GI8OB~{hY?J5T4J^(JdkMqLCzTuYpglAc0}QICnaealo_r{Sf?ZtTZZAPUy_EfW7xHiUB?waqY|*{W z8b&tQo~~>4S`JEkW_zwqvqYwMV!8pD4%G`Uzr2^ioQIRVGClflO9Ybz$Ki8FnVxLh z>iA#ecY4ZMSF}(15B982H9mkm6P$YFl0@$sn;bQ)5x!R1x%}1)FHpOLjm_{HwI<67 zi+_KJLuN4vBf%;_OQ{9}(P!iqIn`BhEjWToOJ2*lon`SOMfVx5b~8`pR234vkKV@p z{;?d2F!N8IWX5;>Vmdv`lQigy12WZ2mZkKUY0p-7xSHp3I?TFb8I@R1l*dayH-wyk zK(>ATM5VXyFXwD(B_riMFigY2R8;o| zf?C(1O>K{4-8K%0axyVh=bl*)%MlXfU z#%!ptTt7`z>HTTGn%Yw-PY(0a3_V;=l#i%TC3-1+{MBhH&A1nISKG2as0{{94~Tek zFAWi_Cd$|91jsi#sqjO)C(MvpR<7cHp7l#$dotE9`8+vkS3OVH3tQ`fn#7y_G&&)a zH4J?HKm|beavoU9l&5GDED^ktx^9Qq2;u{K!P?~vB>g0xv8QRj)F(6F%_~wp3 zcm%k&en|zJ0#eu)6i#5eETo-$@G7&lEe+gaBAz2%^L>VHSd5g%0Wk`88{@2LPe2g{ z9wRGfG>e&01j_4V2tt|btL*y)0EKU~hu0u@Ee zft9D(GUynf?rUQrcvUOcoz%>u8qgGp3YwD4Jx<~;C$A_9B~73EI0kFb@%^W;ahMJ+2skbC8c_f}v`L7qL&b65hXa?MjK$kV`; zDHShuZi`wAy4_0&_>S~Q^pBxY>x_jJ-EV3ut%GbdH$st2Q#NF(K*Uvx{nd>)iy5ow z&myHbk+asYKsb8k@ISCf5JzYn^fy3so89;YHmGs z4w8fT=TS^SSnNznx5cR&cEtGdH0cL|XMZLpka#cVthCKk_~dwY}W0MWuZld_H@WOLUM){B>pt*BdqIyngGo@A9?B%OB6c>8X+g>J@3kW!t`4<+S^ ze2#)TSWk9-67+J<)=ZHe>Ic6v-_ffK&p~-FS2tSRx8$th+jI>+ zQ{DHwglZf$>D%Qk{YFr|8iQ*5PSB?e=KAnw9{r08!ziqqB7e#K1>L#6 z8n0wV8>@%}Q*)(>ycv+>aDj3&(v37KYqKHJJTeLSsgAdU$-Rcx%5z zLTGeBpGi9Fp{JDc!|mLs6;>gI^RW}qr&I6}YJLjnVc}A}WO>HewMwj8DMRH6#>-5K zZMcLFoe3#w(K4UJqn?`eDX9pUr$p`{@=Q}9(4FD{<)j^vI^PV22vGv2ZfZvI491qu zQ;IPkW$L+rc-|(xQ=N?vtO}ybcL2t!tpGl^qypJd`U}>z)q)?ib+)rt(b%bw2|`je zD`}8=iDNi+E+sC4nn;8BcYT#P1mSmLqL-d7<(p!LFAig%QmGZ$tCHm~6p^G!TKelK zWnS(9_Sq{wYM&tP+|@GXwJBz+LOvZ=R89yaEThuvLmI_!Ph81My*@4TFJq{P)E}mI zFDalo5q0EEH9q%Z&de9{)NlByoN_A^!#hY!nmt)oTSbEpDCi*P=u1=&Z1GrETa72Q zwB60Z;V4dYrC7|PGnpX#AZUy#x;8zlO*5+6YAqnE{rn)!069L`*;#Fu#N0g{77rsb z+o1hZ;@6n1X0a7mbnn~xIDR0e>wRy9-i*l3j`QJuUMj8{vO>gQfYodc=C&Sand`Ky zxFV@1L$vWifg`vLe?2>)Eg~;Owo{;$GMerzbKD4?H2jxJrVPWue(f$L-$74iW+5{b zye?+zA4CJX*324qx3q`jl++tC*P%TUVUjc*5#4Ww1>@IH z<8DE_v3ZO^nRl8G8O}{(i-=)XsIdUapw)e^l0J2knBT;;MQ$E9u`HzKerMw6`Z@CQ z_Zpk>sJ$>qdAYPI%L8;}Qe?kQi!v&xbzwu>YaOd{^8W|s--U=tS%ebJcL9y5l z@u!sYe2lIggQCtR#U!R_b>>ViQNF>SL9(}4;CoF4ydREnI>ouQc5et*dY@rN2+T$* zCu30FzZFSw`$&U>bw&4_w$?(NCH0TNMNCV)?y{zqFpz2V7oIxL8U$wO$zx(*&JX$4h)JX!@jCW9(TNv=0Dn z${FtE+zxbEPEK59JEyN2B+>9D=Jq8HHN>XTs#|=L3i*A<>W2M5%C{NmZEakE*fviX zZr(15YKNKs+6-v%mez90eP>h2+ewh_620PCH6MV>ouJgu@}(RV7q z@&xbtQ^1)7yY5)r>6A9IeOoVuB|vU+)QT1Xih7qb)RKP$(@4sPZs*y48SO9W6#B}( zF|g&2fgE%!#WT1g;dGN!=2Shv1=w7lzZ)1fQ*8&74U87J&zWYaaRCn6vkZ7MaV(vir zOoh^keEZ@=ANUhmt$0>B%#Qp9FU5}>U5lYHNId;498ARz+C8Z^1OY%Jze);x?MNYv z2gThy%ec6Ti2~#MwNgdOra(lS^*meLB_e`y`j_li-?G+wrZ53NtKe3%xM$v!4K80$ zH2IQe*$`3oRdCoBC*)u_MVlSPY)i}Yb9P|&E8~7OKr~7j#y1TQENnl_7;>Nn98os0 zKEI*Va=vMWhQ;yJ@NKrd$59w%aV0VuRi`|$UMc3(+ISjJ5lB4R+bbjw4fRj8>hgr= zYCBaZ`#Kc1Zf%v}y{ojFk=(59emV78C@)O6LI7Kn@^x)zI(xjDXHq65tOiTSlF{}b zNcmVsd;^9aq?Al?wxSC&pxoua)LMTA};Z65bG4rxr-wXLU7Rr;i+uG<6y>z4o z(AT4MxKUa3kdk#_AX{8!Wi20 z=VB_KCsJNQU+ zR!cC5G*S?p>RDEIxS%;s&?r^^@wR4Urz)`Bfn*RsdJYReRuj2KVWoBtKP`KK_FWIK z;j|?&G0CEOe{GWT$hgi(Gc@muS?!RlyC_TSl{ZD8!oO5ZEX@6B&U~#vOl2WlfudqN zwlm<;S&9-YAxCObK)+alFDPZFIuxC@)5LW8+f%`qSZkBgWDE&j5CJJuK9s_2l!T;% zEm3s8Zi7PRuSl80#EJNCLl-tqdP&CSQc}e(nsWnv4;A!RO6m4LAliTY{$}2*tavXs zGZUlQV4Cl5W||J}4|DUJb#dJ~9v~Xt&A3MOm8mOk90D>$oG0Is9?ap@%li+R3nAL) zB&kgEOsENzFm??FS)a6$w)+QXvdLI36YiB9sAp6g5AIH9#R(3JjF=PGwGp<{($ooG z_>$vpNwK`_*0(}F6(7t(Dx3|sBcu;E6#{egNdEQoGFq4wU-%X*nzzA)iNM*1$t!oO7N6%++jhHGW$i7IA0D{ za%~qM5P zYbuOu3h}js>OS7IIyVcms%>Gt%$G|G49XlltmN@=uW_Dt#O+WG*VdlM%>@!bAfStsLoI*N)GHyOS04g2GLf$ed9qteLh{E? zDWV%y9fT~^d2MZt5HVCksuP1Fe+$Ijsp{|{FF(jb%EQptZlYgzYgNdn*~sq+$rmQ2 z<{F_G-;px)2ZBrfQ~2!hA zQj52H@Fu5Zr=$ZXs!S~tcqhYyo8Crxrzv3PM9`h-=qr9#Us6F1udrhAI3+9=F6Q;( z&gJ|S=6L~6i&Cm|xtDS;o_)2k_nz|dYThF|dcWPxZe_o7l@h*BCBmD|-mWdplo+V^ zZ8ov!nZ8&49;cHcMd8zt;JO0Bc-_MAxVvg)+oz~ph9#vo8pX6sR+96n)p(P$_<$Y4 zrp9$^vT0)e4P8gv%eB2h$tpZa=OuKsN7hJrVG-pA|b5tf(fFnp>rB;Kw*tV{~R4HDS zy|axS0c@;o*%jxfegYQ9jFjqt+!C~eeUq0-a@2s357hOMrkoCP7IF9Hr$YK6ItlB~ zHEPJ1gq%Or5iG(Pt}oM`1TRe+z8CTB!1>j@4k8B29oOb0RUf!v3M84HNkqVXf0G8s zyd9&O8|_S3WifY?@pY>fHTAh-b|xpswEONt1e59|+uE8F*E7$i>8A+`Ewp$`M#t+r zV7fwuUY$o8$DeHAjhq|lwgiR}JEC02!8 ziks`=sHNb-{z9g0aq`A!9b|W0c=wWJaS*J&ue{hb>+67DWs}l25IY*vc?SSM?v z49;N1qL`Slg|i&->$JEFF@J`6Ug6WKoKFGtdkFT#i#Uyon|X^86_jL@V!N6hCVuNl zqEm04=l$w9@RZDoFXeTbomG^_kR*8kn!VJkjTjb(Rjm!RO&yp^u8)qy^`5H=QN<ZCzdY`7q=tb+GjC?%)+# zN5%RM=$ctT#j4MHN8Vz^^2`T0$cS(2YwI9SEwj_$UgQkSlAUhk<##lxN`f$B zTId@QqBeZotTL;2@gVcY_-!Td&6OO5WJUg^J}w2>Eva!QWCyaS0WJ~B-@@lpDTxX2 z$M4#+^_OdvYdn?tOj33vt6n0+&OSTFlSfQUb>ux`Nqa30b1%D@TJ`BLFTo;6;I~uQ z)T+1e<`r8kp5^0Ir&-ENlzl4Yx45SbF=fP#Us{xs<-6C|_h9UqtGrU#dz{F??iaJ+ z#P8k6`%|5QR&s~*FQorhSMdH?l$vLXsSCsH>3|@}G(}3T9(|RYom3X>r&0)qmF86? zEgkoy#x3Ky%tF)`U5%`!8N7;k4|~SRthZ!BYEQKKq_fvzqNMOrX*T4U%6ZL;bIT?% z$1hn!PhC36Je44&m;UeeA)$5|N|>AO_6J-n>a6K?_d3f6?^S8z+Q!3_g^M$D6(Lp+90SDoie;BJaX6_4SV~9&-E4qcF7Sh7p-G(pX!|V zSusUt(+iLXIphe$4IA`4mr^|d&>_MS`8$M3%1LM8)&403sCxMDND1Tmetj*bs)hT* zoK$vPn-HNri|hy#OCa&oEGug0_vv>x)5vsb30yRVR$;l$IWuYGxNFLs#AINYL5c08AS_<)tP9dliu2@vbMw>6WFmyn7l(vxDv&X=$Ue;?0#z{PPK##ffje9Y(LAA zHK4S>M`(m~kY{%uyvZbGTU+VtP%==Dt(>Lc!#3wBq`tV{Ntvf9F|6fg9NXej^%_2GzL@na%YJ1X=B5>C*RWrH z)Q-{|&kRQtSAzb$)3S|q`VUCgnFoa0<&*%&Di!q=t4a@5Mad zE@a4wlquX-XQNcw1uZPun!ij*`Gb^h?d~uyjE~6cRZ5t~%}x1iXcES1K27_D#Gw@i zN`o}JCsFn5*My`fhOV<;%gHa_%Q;z}D={sst!-;2IWdeowRQ0wZTuN3TWqybp$0Fu z?b3F^o37tWB|0lILLdCRB5U>6()-`1xJ=LlDnPAT_R zt=(XG{7&(mzUr+dr95?$a(vAL4E%C|q3-OZf+i&p=OU*1q71`vRom|86`pNr2W&Td z$DwV_Md5p5iQ(~H#b<(v+2BmnPgIG>;fGeWBI^34OxenatcGXXI+i1=OsiODQ)ld1bmF|<|$*m?myPC ztAf-OA6e{YO0vYk?%&3ps)ci1fz&_s$yX6ySGL1|X|K4$ZowGjzE!QLO$?VnI!|t9 z?ARY4NEnp)el)otA&dzTq#8Dl*A&+_h!{`PcS^y;mh{AxCN01 z{)D3xh$oFv^FH58_!CT?X)=9n?JoYz+_?7hRxP?mhkt*DGnSjY+<6tQzOkoom;m03wJ|>E#V>QvtGHliK^}t5{ZF}UR+@%Xa zIWYc2kOkJY=Ty{52!vB*jhI0%&jFU=WWlgNh6&wc5C25y^2`?Yu3pJR9;)y}bYuj3 zK0tKxcMq`j$Y6!0$_T&YLNMF?5b{1u>Ul7A=~v2*q#op2PJ>PO3ZusTKEYSvq*i3pw?kgwj+}+q1pqZwg|hn*`pXRbFacY4rizTcG)NW;m!sEX*b1x|FhJ z>D05}E$w3()>3+XP+Q{sf%UTuaUL66$L;2&2+e%D*81)IUQkuw_kzyHc_F6+6da>~ znXhZl#%Ly0EQ|FnFBiLsvzStNnHq=&$h`7;5#uQtB%Gff1|35EcDf?c5EMhO=c6Ck zAh+XQ%E<)D#blnmz0M$H-FQ3Gmbhem0grQPG8AYak7gN42HC(BhY!PCy zvx=uP7EY5wd5dhoK`F;Jx4^HU<6CwzVrsd`qY(b5f9Go{!)V{$Of_c1VWuOG11m$N z2)SXskCav+Pv9H=Yrs=r6Gf+(Qk{J^!S_m=hio3?9L2n#r7{fOAtbEoy=I^L?X-a_!q{E@^Q3dtp%8yR4{FnvD`|R3SlTz_`lZkKN8swx;lY^6$ur4xK*;M^08dPWOVW! zX*uT(wz1Xy2s3L*c7U-0f$L8FK*T4?;4KklrG!f`iLkkAS9B3t=lH}I2Q_u!0-m@d z@ny0@T}CR|J|xO(+F;m0=q_%A&0SYhcI;y{-8d1MpBD*XV?PAm2!e&36I`1zgd`U) zb^%Ld;*X`Er%G+t`c64sWXT62{(^(WdT0!omj=db)&pDPPQ=5Lo?h9S)GsM`O}w1P z2I?uEY}OhIka~M?kA8XQw&ulcJii(Th92lv>)18*mqKR1BeTOi2ZXGjq{5U1WepRO z$(gJ|()fdv8P{|*Xk+pT7Dk`~FEn;>L#1ND#Vp$@iS_;&<9nbTo8)(X zBB4s64O=_8(bZIcj9HMGW4}eh_pofu-3`t zet^U6&)QWir+8f2iG)rzL|#f7@xwE5MW+=tnJodg7Xw*S3td_#0PrH$=#pgJgj)bm!eb0i*nkaE70h8@XG zwrAzGmtvvIMJYpIZV$_8!Rp*&c>(d~Qa-+`8^iR8z8XNhsV~8vSu~9n<4d7M6O5>IgCmVZ281Z2NtjKeU&dVHUP~T~&mZ)}3;%Rr+89 zR_`Mr*KCfYgi<829A1rbm7)MGURnEcGAhu2=0B%lOBf&PhgtZN-Vm(;QQl^Nu6wY1?FhwmtG-nJ^e zT7@M7X|`j8?h`mGN=Rkzx`>ZMKj!+ROBo%h^os;6lh8y=3%8aA&_s;@258b%;gS=_ zcx78seYBmUC|e?rR$`0lmuNhl&_}_^Dtcb#kKwH+I5$JqEDqTMW+EEl$i6lSh!-jI zQY?K8M^4&V$V*+t|FiWhHzVDS@_QlSihDFSfq-#sw!d}U0MbeR+U*1mjZAaPesv?u zZuuOHEI3&Xlw}N`hDW8UaQBe2N!&uLGw1Oc3~)g^)akqRwf{hTJ)9)8x67FPHS6L( zc@iWPduYalM2Z3^T1biBt%|pT%YX$r!&t@XPJ-o9i(-Gj15n+rq?SW;Kw|FXVM?`H zx`K2?Xmt+hv3?^3dQU;*R1c81m4dY$9OOZBx{SG@;;Y=imY@l1crD}QW)U*t1SQ~Q zo0ObYM*5WZflH&_5^;s>ej={sPM1q5%M^Mp5k3@aZHx07hMViZQy?}SrJ$O3R05pl zE!d}Tm!m~z;)3$jR{c)yp)HlmGFt%)xa>m!frqo43{P7cDnR+IqNKhwBZ8n+i;+%j zEq3G5;_u%Rk+Lfg$X;~`4RvJFGfjux`R4}`KDYHwA|jAfXsVcVIT-rQf1HSDt%=Ofz;KEP3AeoOl>z{NB3aAr6u*`c^Ly_;4i!2fBcNu)Cu7jp!Rly;RHcwk z5P7YtVoKfOS2%h}|(%9D(w^;yDjUw`bY*G zkU%P=z~?k)m{PJ8#j6K|X{eMEjvjYqb$WjVmuMZVz@)8C?_5f?KPu~y<>3a}jU+hw zHMNGK?mw65D-~Z)xvQxnAd>*z7gDH{VbMH7>OLnS%ZFSsp_H~kwyEnY)0(`WQVyo) zS3*jM-Ye{(KJfiZ`K+%(i+E{i|4l||9RHNDaNXX@|9ok9eDC2>Zg!`*WqCN!hUPjR z3x@6LnjEjpKNReC8kn4L*d!em-(^Y;gv;L!^7TW!U_Hn*pl5J`qCAyW|ES-|6x5JI z`h6+UaxR(0cxsWDWmHF!qK#Db0jdCbU)za{)7o|qc`Kqy=C)OwNZYIFJDJfdn?&!gQVLE{BkY-aP%&G+ zv<7$J$t7)-iV!lDXFyW)-xo)XUWDA%rfy1pU?0|U*e%2k4zp{7xTbFw_B~p^edkjd zU8M)BvqQSNw)cgEYc0#Il^PJT9)%QKtHc%MGp4BjP49D*>VA?g=U!(qZ5O|_j?bOO zgP4a)$+BR;K>^pS?5X?~Ab1e*Vyl?eKp;RPfqXI1FFUn%A5*jN6A9%vV6YUK zz=+Lx+)3zMg&mlF@r3YXyN@R#f_;)9Dc+$tr9^#I#wVzAIK^#k;B)3>Zkl=~jWqU9N=7=vZBvlZB8@Mi$|$};$F)6 zDB*u8WYqy&i1@$Bh)m7{7=ls=Rm2o^<(GKP40gi*^Xl`3oWIi>1dxVlS_p^CrBt=g z+cKOS!Ws*)UglvU>zae~2h^GW1-fR z0a7UbO2ptgGEcAmnv^5fK?-bVa3ZBRBpr1)0vA&c#C#`FlxlF`36Tb3Wcv`jul=XI z9rqu#IZx32jf@gtPcm*P*H_az$|&N>C>k{`3~oJ03JaP6bf6Bfau6}UgmP?2jhsm&CM8+yS z-F~~7=g`=qf^}v`rtc?kjy>!v`?G48OPj(ZRBBqyhY7AtA4cS>ys_VG?nAqzKkWay zJ{-4d%|WJC`~E)O9pbPw>7C>ffqYzAv-|f#@`A~}8E&Q3rI#|rxV{P*UyFlK#)C9l zuPsMqznxgF2hi4*Mid*~(xvH6!2r+hdt4ghGvCKcCkY0m(8@tF6&G+~^&p?P*8NTK zd!ut=Snt*KN=m6%Js%lOmllL#bG|gJkDaZXvgU95ds+ZkJm>`!i3&t;i;=sMjFNj& zw%dYuRCvanaFf6spSPW3J~WlG41=`LmVkhMcJUPsGQTx7O;{GGk9Z&)uMe#qB)xdo ztmZGg$VMh#AsC@wlFoI4z^#b$UTw28&Lj+b=K9KOKxokSd_a#hZ_;0a( zMz*Kdc4s?YcWNtT0SU}VL@Iyd}ZJU%@Sz#R37ejS;hx+PE zT)*>Ya55gdnw+!kT9nf5UXXHD*FnwPzrM7pWnxKw4?QJlkaPWGR@ZA8GsjmQN&e{d zX06Kj1X*vcda+dkjuM^%N8*}tA-(FHTYK zjfN>GywO&-04QOv6nuI0=x*2W$lMZ_Bm5CURL z{4ky281?>c|V)A+G0di`Y7i83ukize@c{1=lQlOo}i>Tc{F&=eF(%I7XvVeK71{qc7 z_swEl>p_+dpOjJ>&zO02>j;37|3pYB;lMRBu9~$!S=uh-yji`OETz?ss_j;bt7Kf0 z+R{q_81h0Ni1>CYAeZB6X(E08A*e>k*Nx%p+IAV|gWT_<`s2P=x-80lgyT%r6nUw` zqCM*(q74>Kaa!4cqR-*@xVC@n>}nQ1eP}Q_3JCVCDkA;>jYmuFS-Bg}xD^MU!12#a z4zgx5t8FmY_gGc8&%KQAhzM6w(2SyD@~fdp{6(`;b?t^8#Q z>qrro)+@I(Y*mTQ7JcJmgTN%>yte%kWvD}%z!G2-1^b|YNeWxuWNg@H*#=&tNLDLz_55Ul`wfFWZm9C%L{rc z2%t3FahMi`QXQEf+7&_|wgJ-`w8!;tD;sFzYM8f;N?qF4BbZXxzEK{otJ>hLpFE~u zY>phrx?4o#KNy?2#_CeQQsCwgas7Q|s8rRP3dZC`kMDf+@5Hon@-2T!7nE!mcAz9J zy^+}sbO($oSaA=fzt-KNexV1?Kh@}7o}o7ngzU%-4y>>2u=iIwI+&VQ0iiZkW)1=w zkQYbSN#iuAEof;sHD-^{nw@w_pq?}xg!S)g==;)ChlABhAzh$%WJIZ^WI_}z*IxE2 zLyYOW+ppvU4Yqz2WxQ9c&1Im6Gd9#Hzubj9S=t*ys!ZElSi}M0I8Cm4_bdp!!k4Or8su8~s@d@5ce(`E)8m|va<4M$Zlr|;T z$+9OAU0MkdbiU3yNz>ip7{w>xaF&{qYS_Zv4tphDTXq{T$O^paYm=K%`((syC5CE!T471E_~qw*e*om$&>WaKh*m8%o8WsL}Gd!^)Aej%j? z>*u&O>FG*FaCBQ+b84^XayL2qXOw5NB3&H>`3JPCyz*tI)=(pO${F{VgmHmjfER8^uI5+`|yy}q}qkL^~Q$tig%+nxz;nbDaJ@C}?4<1Tk<3W;$! zWpUcAGWaUfJW7$+rm80&(jU=}63H%~p6)wlgWGwGER=AEZ=ytn(=QWy)2~@&`h`omS1?w+X4RzS&8U|iBthVf4#wqOB z)@E_;^1l6Ovbr|;spcW?g-jwtw`!W>I6lQU&DEX=Sw2+KLy{7R^>HSe@N`of#b;GEqTpFOaG9!7M7P!lwI!+zaJiFOrD8AHZ-S zyKUW0(rW^4*RHM)RtFHkv$Jd}E2|5c@8k!z)rENwbMqjPG8OOzycs>EM|JE80PwZ6 z2*CijViNVTq$C63!IyX$VZM|YlXQnDBTJfVqZCrV56hPi2}`S1%wH-GZm%7t82jN? z&Qe}1&i<$3&xwVSI9uBXQl{=FTbscyxx{uPFJ`aP0d{G{P0mN@BzGVFBIL>1c2t+q zbZ1AYn%VmreYYC_b@HXfqlD4!@8x`ymkRrIl!tfSueR${VSgayQs(MvaX(X7XF1&O z1`)rPl5My@%iYEn)0q4>YvCPmc7|}(#wv5u&M63VE42{iHlzs@rsMdSz9b zY7^?=RyK{It}V=Xx&za68<=pbU=aFA4%uE+~f z$gB+s+zVL>UC{W>`A0$uXYLR2T_F*qu%!qg<>b}i$bzKC3L%v;!5!^X8H0c_#>`2} zCG_V*)3ff5E5s#hO}l5a(yA-^4tiRj#O886g&;>MO=il!(#}DyHg_%6!(o%vc={py z_J)|3%@1c{DooN+CJ4wCSvRey%!eC!5OZ`MVSYE$S~V7RUZxmz_hA??=q?COv+b<0 z*J8SWe40U8Emu^oB@ZIU0MxB#B5~Re)^$TWMb8#w#1wDNjS?R{!luauwMBI37N`75g4L=T_L0JtwkfQ&-QO&f91;QISQ=rMFtxNd+ zgVL)`tyRf_>y)(83$#nEiK?lmak=e;yY$N%^3Bw83>sY zlo@ftA4#LCry!Xt#z-7-`AG;I`TN_!~=1|c1Rr1-;|*#U_{3q^z}kWnyn+2s}B^YGM?<# zBFagQ`nJaN9Ob;o7zbf#dRhJ~T#V4^4&}_3d+((@Lpgo3Qc!6N){Uzxb1&n|xQA+a zioQyK^n-l0uJ=O5)1Ep=b*u%-Wq?E}_4t8x<$msk#J5b$l_K0yq#|R8Lfh(4%DBhG z5F62^^ajdgYw=l5*s!EoUz5S(D2!>t9^(vpzDOUSpYxWCGxo3SVn%w=d>9sQC&pTT z8{4IP9R75$v6cj}N-w3dLk(X&&%kML$zh8%ZCl%*mkDE0SqX@E<`A+wl1i-0r%Q_V3seJ$FT(jhy>a1 zwmfuP(#d&>G$wb}Ud1`GS-1_GmT;rp_RMjMj=~d4vHP6qG(>zU>ErB6Lsq6Ebx)xZ zDJHapU}0OI9|o_#e@`!!R{>W_W6PQT?3!lZ?vHfyEJ>$f)S$OuamWkp*ZjKcX=)75 zq9~xo^`^^%>~1bF1PJX^Px%VJni=N^5`U%_uZt^L$5eN-LjuY8V1*_n7Lj^Tq9$js zth1`$9^A?-;KkBVidM!3=5?#1ovzB|8sXI*^>0wb*Sf}_LCN~WJ=@E47Au3$%fR>?BBOhm;vT?4G#DF z^A$lUle`gOfrC@;Qvma{?Gbpsxb;{{JFgeDNg)Z?VBxGj=h3nuM`D>)fmV|g^85~o zd<%5P;wdFFsM+>EkI3k6lOrmW)^=+JUUs?EP}N@H;>q76st4cBc*$s$#L5Dp=i3=WINrs(*%yCKAg<0kOpbP`Um_ zJ5MO%*6*Xb*U~FfbzGwok{^qLO7Ucqh0>c}p^)xi4EQn2z>0}Kj>aKQDu#SqRICp)}hQ^aq>nba}gx1)0$a;&l-nq_L05^5Z+fk-NjHiDTS zRDCK>j-O`q{xe)b+T!Bs6|L&nwJ@H+;$ma1+{C_=elxB+5E%5ho=n%&B;yzl@IPND$#6Oo9acixFP9uMtagf zp`m#nm{L91F*HAsC|U!R17-Bo)RDKFlbs~~$iwV4t2fnleu{k9oXja3ZQ1Xb&rtOD zxxIfJ20;r`&}e;MuLoO^N77*$^DSv@OpFM%VNi{eY}-+3@4^?(-d@aDWrchGKCD$3+QYTV#7jp*$bjn360gN(<6H51nJf%p4RdC(00yDXSX_%PW7fpsWhgOFOaf z_>B6nZ2p)DR3^zXKvLPWieDgb3qd?ib|o;wZ8;fQDlVoNtSF&kLGHlf1+PBUP*_&B zQHZ+vfHSLLh^cYfG+NAUD9<-?PvV(4jeQm_tHlpOI^6wDy!JaJejTvs>s=U{cY^La zJ)Gm2_h4Y)#2K&ExbJ%@eSgjRQ&!;>3P?9x+YW^iu(8naHItw4HG2@!i+IZDA?uSC zDud^}4o&ggUL9KH_<0~vH|^x`KLCN#CGd%vxty$&Q`*UD!tBI`0S!`}-8VDu zj~z!u=ScFXekY!SKxJu$7K|iKMD*okr;Pq|QS!m#qFNVLnwE9*nhHt1bpOpf?sE%( zn&Z)4D1?pW)n^ZfWw-*~Q%HP0+DYOMH`yqi>$33+MhQQlCD^iljd?KXFY2(Qk&L=z7Fiu&dYE(!h zQV0wLdO6veK>bJko?5{$V;#yVz*p`b;`l+p2DaPb;e9Nr_Vr3)mKDeoGE{BL#8c3H zno^EIs0K-t$LkG=Ec^nAt67GLiL)E)Q8xm3i%kE>ZdxnwpPnfEA?j8bdZAFduXzCr zB^U-*Kd_}T=M5$v6bedFbWQ}lQWz&MV}x|*7P%DEj?WaYdR`PaPpIP8g{*~zzd+z; z7~+LMB-E2x=+^wSb`rg_I`z}`Hpeq_%&j)u;bbHKqM$tJh|~hHY1wTT6$EjAMnjG2 z7gqiiS8)y4eu==ZLpFlHFf{K3-FIrZ5z>s#LR)GJ+1e=Nw_2#k_^vw)Txfz17A=9( zXOVSTeX&u73nHe_A`h)q1Xq$LGq<}qlci~3JL1xtFL~0U!I6oHlxUb{fnZTZ!7f>^ zt>WqS-|s-B^>4#a^>DW>)0#zZ$hNV6uQ3zu@}}n~R4U}DN08mDL9yrOXj>$jhp4r~O;o~XlJPmg5IjnjS1?3T*c?`#rD?sf$Bhob>GUuc9s%k)yiR;kZ~?UPy_-QlQAbq=Ht z$!mql8==^xa)nU6Wqf3efc|7g6sQjLjgkwuy?~isz8yM;Jzp!O^2;-ketYN$ zKhBoY_E9~hK?MkfE&?mwu{-GmCly)prDi9DzoW6)X;avytRPkTsDKS0h%12TnaEiu z4O#?saQhk{R8@|)eEB0^ks4h5XNgv_n1Lq{kp^xmj}?xr{E19u8l_lPN560_s4M)Z z*+xjLPAfm%2Xzz^wzQIO)uS!EM5w`Jt!x;`Uv1<=jo zH#&c^z(6|;{6!{vifl%PC|c&c>m-|4^f4v*iOe3v0*r$CROvURkzs0`RN4KtUpY=s z^A0m-Pjc9Q&3R`KTTA~dD*J`$^00pNbeBV@-V?8OUk1v>ib{CfBC8s`5Lr!&qnZ6V zSbt5uW_SJ){QPKXUn7j~GfY|W!kxTW+VBnYFoAXNZh#I3-BB-8T&@03rACz|?WT6% z<@MP)#`|Fmy>u+;HP^n8A^GBEd?!{)8fw&Z@~xb#@Av`j?tc{05b8mkg>?pVn8LhXb5*DvU&IezQw=r~8r4(U{%P2|&oa zWU6<@20kd^X+T-{lnXmq8-cdv4Ptf9x-sFN&YRP{MX1TnrrKn<>ReOqkx^XUdcDPp@bwfDRe**;}>;Du1GPya!NlYz4ap!e+%DD-nXG|&mK zQybFY3a4%(wGO9a(_Ub`#ZLZehIBj{*ifa+w%p!@C2f*=rQJ{_>TpG2(&wCIW~sUh z1-HqBn=Qz^$gMR%^>7|C8sv7MvI(;y^7Uu~FDEOMXCJy$=w@lR_49Z3B-TxCg$L8o ztcUAj2JY9vBfBgQZ~S!qKhh|CeV{R@rvM9*8EMQ?#Y7R++PtG< z@RrD%!@WbM0fT;BRqIvizbA8rv!B(kq99=zpRfHyT(Y1OoTA^4nko(nknmt2Qx{6R zFv~tp(9EARc^vgK#@&SCdn%W$gI6Q_1C{9w&(e-8g*hVkVA9$6#M>K4z3zK}r)wK8 ztFpMmK42KzOYlp!2@Yw5X3vFYn5; zMhZFG;iMH-&u9q>&hWCT3`ALWfamE|I7&BVd2imjgg{O-w0-II!Zyi#zY(ozrhb+* zw+hO=q}z+FNyFONTzfT|!T-z$ruzjWB%_yf^Jg-NJ&+tb)yzS$94CY>>H`V7P zMonnZS%$9a;X0jAA>AtgoFF;F(C6cg>1j&`CfPJH*yUopuu_8A9qm^2G1IC~;fTE!31!x#urP`|M|I*CRGO?2Q1^TZtcj`RK2v`T0@U9fd^{~oz# zCbc0O(zC{d@o*-YE*@nLG=>ZXon)5H@xL5`@dCGO@{@^tHbVLRp|-H$IG@=$k$HxC zxv)cOo2mUiKCts_fnffH_Es{3nP$(no-uv@mcwMlZj-ebS`#k10X4+dl7LxdTXAeP zheju}n8SmBDw*X<|Er;^=4|s?SjN0{9L7&7tmGdp9j%Hpe5YW#bW80qlSkj8(kqdF z&vu;5+1awuOuoZyP+4zF&MIhxughHl++8*Q5GpgD@GP$9Qf}g0!lMw7dyel{pCDs5XI zq1nQl%rpvVO6Lgp%Gg-T0>jAniENAv(4KA|QLS~@UF`o58dVCP`S`adxm zC$sr9nT~9_bsBuFl4NW_=_H!8yzl?B$fsn(`zOgpb6Uo%aX0=q_m?S(TLj~Q7Egr4u@$P5TcQN zyws{X%(QaTIqEBx$y%D(#{NWT;>ch?A!xWVWJ^_&vOxFt36(NEOYPHJ3Z{CFKo33g zO3SG-3Hu(U>G;)M*j`gOhQSo5ZzxsnCrOzJcV+vp^XjHwHOX97?v>{hU|6C!IQd!K zq(rbOrbxefi(3fXpNv`a4@^|{^UWNE#3y|g-YdV8@MeZcIhN&10Ff3<0rL1`Ot$bO z>*)3)caPpLY^}6@65T1QKAu&eqpyUTaLx7|O67c_)=RbeCqfh68V;kZ?x!ljFAype zUWo3SgeDmlxtp9(8)-VqYi4XlU0x7i`PwxXvn{K>uAq<4Lf#JeTH&rYH()4l)wMto zM%-nKE&bI7z8}3SWGx_sD^F$f`Jei}f+I-3tb3-8eiJ(H`VDBUAj712L- zORFYfHofGrqKobK2U1qUwx>l(7g|Rb!w4OCNt0g+C6+Z>P@N?wBS2+;#jBYinl<%D zQgs0S{^i8fNN|l0%)YFC~ zeCG_BDbdxSbvkQG62iCn6W|!llF1pOsk^<02x)$5m6lgMO)i(W-qb+yNKxq)%KJ_B zF|ZHf`s@eY4jhuXze!|Oy!sAo_V3Cg(AEwo0uVasBY;TP_muC>c1LBlyNVT$d8GfE zD8F7;8w(U;rH#g}G5>#mZWunbLKBXVp)k_x05BcxceTRW{Cs*O&xXq~$Py(h)vocxO^{U>73)3VFOv`{UAg@eL@i|~O|CNoCcxtN{G z0AL;-+ELG@Gf~K8PAYF|3N?$RieBF+%z2rOwkMD_R( z`IXU#Db#2Wc@Spw%c{>-;@!7I0xX`1JY2|eHof-PU)Jr`XvgeD7C#k)!wXZ@QoyKf z>}6CPTJjP-8W|~Ci0)?jvQ`6H-l_Ch6IBFEs8=_sPgiaVj>7#sskP5ZC)p*EamiL- zflbd+I1lL<6sxeM;6d5gujwsqY5of_(Y#l%JQI2)c2mqD?317v+l}1iP@RYgK zEIHhtljez5zT-V<6&4?UtsU(r2YCp@&0XF4$Jfi+0x!j!%fuR=Pgw8ADB#BIq-^;{ z81Ujf62q!UU|EX-zE{b;osxMrQC>t}Kq4fx>JbPUm@LVLe8B4}cu5(REJ~l6^2n)? zVdVT7`Aq+g-hvbms3n(EzEcK^gIuPv%X#kWBW!d-AEC~?y*i&HhymB}n2ne6IMBzhtwSaV)c;PV?7U(Z$zYuGq{=;)3S zLD{|4?y4csc|bGZfh`+iorFu9+Neuohl?z}9a)0%aSb@h<()MfNCK&Mm9Ob!!w}dL zfy#vEO|{SH4dz{h0OG1oc=UOCy@1afR@Dx&jrP0AGxukres1Hdz1Lzg+!QsDh9 z0#}IaETlgW2ogR{R>w@F4CWMI0qQU~d}hfZFtPQyj6Y63(JO}^jFK|5Gl7iqM{h1_ zQ%3g|gU&}g%E!P*shwwF)6CqreEkxMf(MC)wJSoL*wlSB+}sSxW{TemUPUtwV~RNa z1VJYaLRBu_9PKnTKV6k!yW^_bT1mDGu9p-G)LDdKlZkt)LE{zPq)_?;Ko)NbEs|tS zia32oJ-6e1JdFB+a1Acm)`@>l;VNaE6p=>&uOu;c*G3BupAXkiS5)0AFn3d-cS#(C z;gv$YKuJ9`e`);DbF+=h$ur;X7me!wNTUo{;Z+zD0JxHPbGB1Z=MM>PySdQ~bzD{x zc&=W-UD7BT-+v|?iEsCd780k(Z3wwuLpPO{%gNp#5Z>5ss#?>p<2Lv%IedhXj|yH0 zWXj)k`JXwAjQ%u-Vdd71Py8UNkNf7tDG_tH>3aK+Smnm<1MWw@q zs7@BuHFJNN_hA%Nkk6;yZ)lv(_R`H$G1&^jO^h^?+AgcVQZs$%6C%YU&-(Z#kwG1@ z`YO+OS5wFtUKwy&ocXrk><6$Rin$O8-NMAoBajoh=RPN4CC@~jecMqpZZYi(K-lbX z?ayQcPD(*iC5*qXG>%6@_X!x6&-^SAN}BU!$zW1nPS%)^cORgVMK7dvrtt@0M-bBw2)tY*>7b{cyk`Fdc7Bn17Q}TI@z2bX;co?#R%Dj6xKoSN0T#thf`$S zOVXJCHPZ#zgsxImd=NH*88in4cinH1)C#l0HO_vlBB>)A)2-P9Os&XjaxnS~0MzTR zXUo%HG#;m>gd=4;hQyR&_JS!Ob{c6TQ=#1Z4X=I+Oi1z1Z|UkmOo3Z{VpRn?II+oifzIfmvk6^ zX>6WxE9LXHPnliRd!Zl&iOCeyY<=PxvLccv5#RJqZ-X;h5c86@ceCKhQDN65IG628 zWz^*MGZ5x^MdYNHx>4_m6xgWRq$jGsNaSpq=@={hpjdN>cXZf8=2a4LNK;>f9?6Gz zUD%k0qXs>S1!NxZAxHr0yC1jGr=4Ixym}nX`T8Og(wc1uUgH(L*2=0kXojN=`!kAl zt)I~tK`7NPk7j~Aa6jJ^H)kv{ZxjFqq@CN5xoca50%uoQag>tu{EHMwhtSbuazmiD zUK*M%nmjKx!^iESUMa*wJWb9GKQ40mJ%u3Ig)$!Ndmbo+)}@fofhu_CWMUoximC+v zC}1ef34`}YK3~^q z@-R5nxjnd#S2CN?&kJc(_0qswJy99jf!8uJ2c3!XIGspEeH#Ei{wveqtp7P$uS9S(t__d~0@Ke($m}GI$R{a%+wZUy?IHvx}6anw^A1YYvRL zHt?NVITt*RvK24yK&h-|O0jMd1lGKDTXJnePP~4{;5R^VxdcDl`(YEJrel zTnxr9l1Ob8?06-W5V64rByJTS^)|T37(PHtZnq~#Suiz&h)T>&KmVFuiC`f8a zVw5Zo9DwW(oxYNoX9^8|r}I@x!>sMIQFFnwW1L#Y*k7rQ*h^}MZ6`A7T`vU`!8Nm2 z-3B*e7{uxUy`1(7%ozs}keDfbv%EOgcXKk$FkcoYtnJ$-6_$f+iQ7{c+<%@Bb_BhD zuFw5xRL9vh_Er=7`Dj$SPt*C;EDjrQ7Sj_8l1JHs>p!)z%vu>!6RW!uK={E%_a_!i z7f$V01y^O1ip&Q~!I6D7e)!JD)O18pxy1C8hLzR#PcB<)^vUSaB%iWL&q$d$NoNZ7cKRe^TxTZD{7*i^R{226P4Yfi)&~Uod(Q;UxN(kV z9+O6xL7_bTXg3t9?eJ_owSgACZKm)C3Dw}BuEnnt(F*^6Pod2U&lFA)I_eIMKSB{C zGj@DL9+)htPX>*DMF-180sm9x{9v#lojlJ3!rzCeZFUoV?(xn|ypcfNc>4ebJ%MUc z`mLK_=@x3}<|Z1`aa60uN}q=Y(G)Mvimo(l*3wHUDzksKCV}Y=87*0`UQP?XBn(-G zZXTk^I(edJxY*WeA zET}y8U&XlHTT>+{Ay$b*498cxRchhjVi3e@!adlSuZ#-Kd^Tsnmva2c#55}R=&CH_%8#Lq>Qy4GGbv=|&0gUNQKU~K^5A8cR>@KDCn|ZmMt7Lr_uwXi@`^F43XxtWjH@xM zvprF+PO?fdn2^z~VokQ|!S~bi)mIpRb15Vd6KMlG3guC_fQQNYF#4b|@|u}IdoO$d zuT45Nv!fL!+R5dJzuS0qe7>}~#N?S*`aoV?+_UePY0TD{bQCigDo;KAK?_I)Xw43q zo~ev<$P&;gMWj3ay0u@yDl&9y%cyY zBz8&{-8^Ip${+!ho;I6krU(ZSh)S?<;ba1KaWnb^XNpu4E2E0mN1MTowXto!i9P6x zQC1Nl#%(?{#!fVmB`qbF**C7)Q1#5pOC(qJU%Oas&-NX6_vZgrQ3TxxPTA9SeGa66%5C2r?z#b`sbTS!I4J%R+A80!*0wBoE#K!T#=~UY1WfuNEr^SAM zK&cp5MuDIi$cwzkl7OyiE+obV*i_+DB*0Dg!Y63Mmq|?Q3}nfH@~fp_+CoE;>0%^L zB91_o#ZFn9z$?>P^Bu+|W5xFRa^RGUsC8D%_=Usxq_4LUDR^O7v-4DGxBN^sjs4Wj z!SeqT6zxjlV0^$o{WBS82!3V)@gc{(Ie|Zrj_@_2Kpo`=k>x|#kt8VKN%d+T z3)(26*1_2MTUrpZqjSIv zzEbV!mB=2wrXqVPx2ZG%j<}xgSD_FbW?gK;;Y76`;N$LpK__010?Q_nL>J3N^w!m6 z@aekZ$90yRg+idQ-WI&dXvINgiC}|(V^J0-!O=F+3DYBs)o_ zy3b1C(z9_rEOSN<2A`~CcxHtYFG6y#1WdW8MDqfY+ zbn3SuZ5seQ7J?DKE7>o1TM_u{_ASCvxOt9pb+`+Zn!2AJUA| zA-{Cj33pT|6pm}%WY+C{HcDUq7z$qnY@ja#xC&V)iRogI4{_jXCCm()@c&M&_bJSR z$;a4y=AjHg2$}XpLA^AjooqC#6=8e1`48!9HZ}jK$ZS8Li=$gO$f=*xLNv_`0eEBq zUd{TEK%ttBMTwVF4Lbviq}N+YAj+a184Qah>|>)?R5|GAGQJ>hIZQT_R~|&-vH+O! z^Ny}TX81^b0IMQvIcV9bt${y-p; z0(2Fdy06;2=O==*Obp5T&RD!KuzW<_Kw2q$JAhMz^;^a36m=YCF!x6tEv@Gwt1_ z0fBYUl6EG(7zYKWfj&(pu6_(>#IVvVe3aoU_TyCtn)&ofG>|qrxL;S^eyk~=PQ-?=nB(P2*KMI zQ=Ve6KNEPk`j>M7a?eomu%v&LD2ztJ@iVA{zZXgUfkNgqz0>jme{nLW z$;XKAK8=jQGmRHX#YEsusX0*p{yIH(7;})lP8@j8dYU)1P7MzHNFoINkcI-Z2J)8@ zhKpbhlVrYY3vckA?HT|BzZy8Y5ZMexRmY6`g}=(JLoQr{wj8a%92^E8etP^-;&UsQ zoVcTYM+nK>;v}2hx_QP-7!tP6M<(K#j~7{;vh+OIaYJLv_xss2Vk9285_w)0Ht~*U zx)~@cj}(APT4eKOzHfAJwf&F#8vv^6|L>x=E2^Wd`IY^|<UMwyl zc-Muz5_$AI5Qi9iuC5d(3z5cQVf?D4GTY(t_t&qmTHWkqB})PghDsgY9|f1ZT-7dt zd!gLK#eqPOa4AgXx#Wu5*rpF|)%1|{A5xBshx}1gIs3f0#8HYL?yqW-L^auuwQ(d7 zCK$Lr<>Ff3F!c@LhT}&}_^7ufwd_#UqhPeC1%=aX?YD92XxhWye&VCd2#za05pdPp z=k^#zfhH(MA@StntEisYwZD+Mk}9OtO)dMpxvWh_NnO1j zuNR0>+Ljl6@=yzN_KD;0!5uc1SJUG2l;b(QUR#ng`w8R8C)QYcI$63-E+%IR0Zt0j z*`^9ct~W zEL3by1*`d zO%~FRH(B^-=U*wj2`np#uiqI$8}44^hsy^F)OW5_*uSQ6)uD2(aCkl3;Q3#P{LEjJ zUOy2kx@h0;Fp_Cl=;GW|^-24kiD1pcJqhpAAppMGR>qXSenA;oEf}xxO?cX>x>_LbNxZSk zhdm96QhvQ=Isoc0$n>2L!c)QHyXNNRWT(eatVs_s8;Y0Z@~4xHOuYHd6NQ?w3{u*g z00qnB|2`9!Ek=iw)}yH}q>-DIgXm{XMMrQ38vC%=&FR*DBje#&`w(cP6;G${VDdhd z%k>REQ%UbMW_BvC+IVxck;L(~(gW5DIE6?FV^ER`-&C_Dq#!9-o%;cet6b`0QlZ)G zTH0=DO?r3#_nofwig0O2e!=WVew6B zAhXBeGSA{TMj}UxFPS`uEQa;GEw!g~2KL*^NFcT5IZ~9Z*Hypt1(62$pH1srEtZFq zB~hDRQsBigASVGjoJZ|sgK4mk_?kZ{NWT#2J35P4V;qBe_i~(I7saYrS;TT968mqh z`QFxg3ZS2(mE*Au3P-0#O0v?zmnuiisM3wYcPn$GDOz#$LL~d54l5Ya5-B!4NK%*AKgNya<$AeYpJ>(qIS2RaWA+CTz}{kfTZje@4(AHM zU-U2t+HkI>hNYf8k_Tkdl_?y}ob*v%PqnQyY8!{i;;}+sHCbgZMLJXW6_LC>GjKMi zWzBt%6=55n-Al%!H60I@7S>d~FU={Xd0ua=GGu11&KM%bRAo`h(dx2u&QksBrm11E zpDCP0^f((EA58l&^n=4FBtB+ShuZ-}2_rh<&rN_sf+Xs?u4(c26e?LSV)40w`p10g z)$xB8jK8KWEoJ=N?Q2zE#5U)P$gwn;BX;coT{q37cLqRLxUoDlO8jb*xIZKDCD7-l z@Ie`eeV!`%M=y^i9zKaf6yCIMEO}^IsYUJSX~akk?u*q8ee^%JOv`-P1ihz=8U1|LMILiV{3nAtxI{_>gp>cT``@+I3F zm^g(G&t8Ah>QC&AO4mXgCy*+w2V!EK4H-ezmJo*VV{nNyE&|BS0@WW%fYP)ISj$M% zKTR{7sXhjWN;n(o1c!(6?rFoXitpQc3KRHqR33BZ5Uq z5)6^!s|1o-eddZirozQ~MK}cE+FMdfl*|~sD9#c(3S%~;Rsv74 zC3W?*R7sx@G$K3ICi98xu4`!3VvagM0%N70=mQ0$N?QUt$fA=qAsU1h zX9~saLRQ$r>Oo`^2*p+&f+%Ndw$eJQCbC);U?AlqxgsKu`MHJtjEU;*3Fl-gE9WMY z+O6Jk>BECCvk@5?cbZc_ZGGTr;8%=n;LX0_6f&<2r{6!~vlN$_YXBHli$FL9DS2=x z1^(2{ql=j_$sPrDU4C%_o#0T%U&y#hiw^RhuhcLrIrFSz{R)dBYl;lWqdrJ>L5B-O zhK!8#QFz8tF3Q-~Cs60(Hkym?V9|BN612JQ#Fb^sLMd|ShHfgR0Xee(zG~G&n~M|G z2-T$g5IWh#zS$H=t;n0%H?pb+o+C>Sd-r;>AuJnMB|NK9%EZ(z8Kxf6V1oVzX>OI zhj<;B{`3c}?ab|pxQTbu1$V6xU;_|o4Q({cUNrAjX9nUB|M} zg`BQw;SZ?&pm##eOx`EgalI|>9e>6M%`L_W4f)4chDz}cTq=^X=80L&qU3)9-&pGlvni;#^Z4*6ZSDly(E zL=G7x)6)WZgZx-^`=| z?wP&|56>Jgixj$%g(v9*vcYFmUIym4lgz>fNvG4<1Cv@NE} z3R_}2U`zJ!HF$Q;c(6*}XFZ&(o#&Lw_5Z-c z^ZHrXQ4MF?+cpf5^b?2^+%z+D=7D^D+0wKnq_Dfy5Xl^BPf4FBxr*12*mZ0#6%Ku_ z78D51rZup zLyoB)*W~lNOfaIeiq<9u-s&IKIR&nxePb%9S%1QqB8)xn19#T$zDaD)Yx*h~6pAb} z-I;-7-erAN_biWTaVL_-w)%~K>h#C53WSq<=*9#$I9!lJg~ zo@AbtMFS+&>kKtP_-WYeOYt!Idr#h=;ce&&L0+1C_%!_k}T zpAy9F#!)%m`!Ghk=WbcbYpzYeP9t;{^~Us&5t;>c#Iv&Hw0>taLT&FJ7JpY9R26<7 z#R!R`NCHOhU<^BUx}`YkgDKElXgu@5ybsz)Jf-)nGM-7wM+L(4Ol^tjkPg~9-woj* zx~d61H5e;|niehu4tR)WhR(!6coSL#4;YJt;fL?+1vrqEEtC2a6VEcAu8CH<*U{5c z^r2MPt;*S#(Py0Q(YCQzs1snH!ex7NoJuVg*0W9dV9$T%w66|w{a7z7-x<>trNbts zL!QwZE9Y3ZuJqYtqMfnNQR;=nA%fQRbC7rj;^|bc0yZRyQ^~NBI0p1up_Hoq zdW@+wx6MSm;}&uFndnz0j#=R$U{mh*)5&V0QRy4F#q2f~j-|)$F7$$BL5h?p;rPCk z>a^G-aLfviio==tv5c*`?j{KuNF3!l^CXSNDc)(g_jjd3gG8%#peqkYc|7sl5zlbd zMZBhT@wyf3k{Wh#SA{&P<{9U&aypa{TVlPZi&?(>tcz#H7#X`Hhtl8IpSC8LDPtUf z;UcPYZrHGq>4%y~LgM!cqbBJUiGKfRzwls0CSN>*p^r>IQ|ojo&VgKt1Y=p?^OSu<EQ01Y_U1u)c7>L)G6Xrr^T^aLK>It0co;L zboWP+x17Q|$SYSrpRIMP%>*_R2}(};omyd}%c(zvV&Pc#k^HrShq#xANq()e;$R;v{!ac^zxVl?dRcC)s5 zKi3dHF0!dz0=t~P9P9v#Cuz?!Jx|7THd%Yz(v5+0LA!O*h808~R%kZw$oXF$PgT4b453Upqt&X<=zj zDt}g=TOyUN6Np%)ClZpuzhi3dsr=g3q=9U~%PE8#IPjCP>C*avvAHMmMX5Ix(i>U} z5|5Yo!pIF0Urx3%Hxq%a3k$G5MM#^}EusE1%?Neob?l|G^uQ!j9>6T|$gPyZc=K|O z1}SwIInpep!*^uZwPSXU9oh(^TITsLdeOya_9)EbJCDteh6}SL1J8`9fIh@+<~!jN*kt>*3nR^W01l~dt6W4f&wwATtQ>lwh!ewWkBB?~;61|Cw%#+3#1K zD8ecg;QZfMtGvb*Ffn{?vKGcym@Uy?Tiad~`CL%MWIlwH`SuqMW$eDzn}eeb|PcrH>+Ix6^;5T@0tur@tHlX-%gLQ z3#1!D_xg0kdHN%iBC(=jKh-`v6lV{mFHzQSKyU*J4KTaNU zfCT5DEbG>2JnDHyA3qo)&0OOm|3BrlDA*y9>|Ads@{uldnrB)ww}nVuObOcHK+0zZ ziR=rLM-4DN)1d!TN}1jLUR&tOGPOEFft>7=NC-_Ik33pUtPQNs<(POngw#Y-v4ck- zmv)vek5swUdj3TvK68jZhA}Dio=*9MhV4(udVS>m2C8zlQx?mz>q_AuZ*_ImD4$}q%arqJij7kC z%GA&~Wv;o2!6Ba3LzPED_uQaBew9Z}0(x3L4Gkuw%gxWG?`Y3EB{UnQra53v;K(i1;Pe#H7im2E-wufrYPItGU_fm(x%&A-7};UTQWMcr{>$3) ztB5k8+ttOa%wD;{!-8I=vCOP>Ej;|c5vYo)j#8?%u@vY}=w`6RbW7&aK6Gk8a?|$Z2StL^4ZS`q56Y)0BR-q(*A~=dVgvK zO-6 z>!g<%d~9}9=pHvJ?xvX^WKSaEl`A~xD|U1sB~wGyww}k8JGFbir?33^lafrMH1dXf zvjL%gIg3F;o;b+FXUV?y45?Yym4MFV4L9!$hvjJ(@3?E~MnY0}tsfcgO?2Aa#7SN% zliTViV_un59$QEXe1m=Cisy`=z)Z76ND|)?>JSI>Db@;kL zv9{QNvHFHWx#U7lPaa+<%pSoekS9Z=rY+Ao2~0lzBYDZzUPx9^EK=|-aaN|j%f1&; z?7`GYTY4C)br@(6>l)g0A{z(d`Vu`|2~tKF0oVpvP_dgS;LVxJhS$; z5N#y~^N@5`6KqyI<)_3#62<;hCwN_uY>}6J3|ZEf_49o&(HaFnO^TsPIHJcq$VxOsA7AQtTXkN$r;3fnAtNB!7U^K;Pc*77V5>O z_V+mf6(Gl;!fDVr`B~^R$gVFarD>U%d_F%+H@^@9@Z*C%UoT7zr+p`HoK_9rlUic4 zklK@-l?UuRaN7`IaI}^uhMV-2I8(IXX648e4|u^zYW-!AY5$N^Jb$GylWx`z@v*Pp z`Gl8ReHQ-lqME_=8BFfm;xU18Ia@eM&#b=EVH1QmKRr2c;bbmLW2sIt`ijq4_*}^e zCtVm=*&C91nQi{gr<^qUy%5-mlX+qGA2N*C#w^KeoCKhyQ4m-h#I0|_{?W=7o~b$N zqAeflTS7d_nuQ|uJ3!|quG4ouus+44J^K<7RkJ=ho472+3g8n?HRVe=@Gl87{U>)K zbShG2sa(p6T_q=JO)&<4jd~U1+?Lr>Ygh({Cn38yOYqw89pYd9idz~! z^q0Hud?KtwW?^X=y( zq`Q-4IYd2~H`Lm)8&%&0fhx$B!+~mA0{X|$XQ%wLL7nI;3@iszRLMrp!obki80d5T z=C=tPuZe`W*f+WMHw;|%gTE5^BBA>P-e1(Mq<>4Gy|TL;d?v63W8X?>TV-+cnXM3& zF2~*dkAM50|Nd|P`Y-?bzyACG`S*YMPyekTFn;*I|Mh?Ur~h^aHbopc>vU4WZ`qGO zS9=ntuNf$d9c?J)CyV5I{@@3vUp^#y;Bitww+60~t3Xy9h}L#wI9H(oN#k>ehikdP`1=u+2O5gka~LkroIUwkg1CXxlO6_Pz>_g zmm1Liwck%)(=#*A*rps#Ck7+f4wt#KN@nqK^>D(^^1}-jFl5P2R z?42ydZ+Xl0Xu(QIr@c-bsGq8N*eOohPLSPZ)b3F&CwWcspSAu@r}?FxLG~}E5%FZ@ zdce?dD#6XQq3bMd2eS?C zscJTm`qycbcG@ba4?H}Anos=~(lA#Zm#xTb{jtWDU++csUCxL7s-?kS@_i-mifX)H%m$FT=r3v6@u_ecAH zL?B-bYDlE-w_My$iGc|Vdqa*-V6`gI3yHT!dnQrAT-hyGmD#^4@8vTrtS~|oYQtx< zbo-lFJW%kn%eXLcI#~-rDiiC`;!f_Y%~ekGohqlgXb^WUoCzRy@T*v?FxkJgj*V(U{|$3bn;El!=~boLqLJH=*EW@bMg2oHFfp?l0BnYbHT0>jxoVpF=N;{p^1h)`&T{LiJQmFu$ zDl1<~MXKFaDmTiED7MbG;Z>fZcIc264&us-HE@N&N8_uAleMX zentgbTDXo&(#UOi-xuWX-;_U=+r~d-nA`VHzuXIWs z{T(@C-Y>0Us|7$Cgi>Et2ZD4em(iIq024dJudF56%R00yET|;YXGq>yke)BK8OdX3 z!812&3Fb12f^sbbkO0G88N!b1DRPlo9F;JV>~!_MCLG`+Zer)Na_TCX2`#5nAvcXC zZMmLKZ8Nm=2Y7Qq z`y#8M`kBZJGi@h~jm1hab*ItETy z(|iVvZpNp4$-7H7cKQz$-4Z~3PbCp}=H%f^2wPh_@>6=3gzo^|8`zs55#t3AzHqRYx ztD?WQ2nHr|Q%`2x7HgCxT2tZD@V&8^w6~e0o)1H+-lOM(!d>z&9k4zaQ8!3 zGoq`oZZxRcaCcaE-u+9J<3EtXm2Z4^oS4{^ZCGx*!2_w?F)@tU?a;I?oGfwDAF1$_ z{X50az>#mpud7B&2Mr(-oeyNysOYn?IaiAm#rt6jp7YBCYyvZC)5?z`J9WfN2MT3o zzmZlWrHrh47Hah_K*5b1M`)l!@Bnm*wb4G2F!!(f8AuuCeJtcmtvCvV(Rt-6?Wz2E zX&lZEhhJ<_8l!c&iObSpk|vJfMTXo{{z`fV6@&C<*(O)-BtPc=c@lu6@03}d^FwKp z`M@vgKwVhWgzYtwD`(>dGzd!)lBFAY4>>w*vr<7!nI&lYtxA_Q{K^{0gUFMM`5U@E zjL4-@4B?1-EZ@=R%2J2OyxvPJ^V9P?g~p=Td(K}OZNn|{5NR57#c71&CN3n3S5Q?* zG~d9bW$m`Yn+Br8Z4?qSf^5L5Sk&;bekZOK-_zrgB>@wG`%36ATl~{Mn>nH~Od`c7 z7c6=73Lnm;iN$iGUY%c6rq+ITuQ)NhNS%D4c!>ZE{ z-)msDMn2Pcu&^GDT_9G0P!oF9X`p)=XC7Y088x~R?JT8~lax*LMNC;=t^lh}R7tIRsrDc0fcJ0xnW3|?;@8XVy8xT zF+0P-ZY+$iXgmV=013kCl2;@=Pq<59SuY6jZ<$fC(KDSFDHRYaM=8<=&*m5F>5MpN z5yO!%p-#Rpr1S?OsU(a>bfl3(EB4IB&&+6|{#8tKVP?jjWN8U$RG1pm!GZel~8yRZwBJh#>dKD zqUSqqnmVybg-#lF6Y{lL7Gb;;Oav@9VUp73HJP4|33c3OLTAM^mxw-V2=e#|%t?3gzwj~N;R;24*4bgBJ{(@62?V>1y}qS|Q#$-BA)J4I`Iyha z$8x%CuCaZT-C^XL?JuZ(629ctl8AD&AC!FwDXA6YAE`PGtY9^koz14)^#4aut{< zJ>u@ao(sGLi%Urg1SNRBsLqWN>Mt(!Gay@x)8T#o;( zM>o0llRS5BLt3knrTC!#pB{-ZQ~H0jq2)vRG1JPJbXQ2&ed}*iw`|p%EvSY9IR>yd zaj0OeG7m4)(4d(?t;p{7H%zF$06o@_M0E)r5}iKACP5&>C30hTE@JShCrq8>Sx6@( zJgE%QeVmQ{kt;TV$iW&*dNrHS0nI2plrKrTfHfjD*VAD5(MT*H10t^!k>9EC#-KWLo>65~_9Y2V(2&%nNOihg;94=P z1SAW`FMj@GCc3d_DrY9%6PdYp&3^2tIybE2MG-Zz99Tvnl0#9UW0<)Z2~_?@$w!cgl-QqMTEZbq)&h;rrHvT?gGE0j?QfH zPhQiiVQJPAN0!5}_Pv(EN0a#%_6-jZhnk_d!xo9x>t|AWgfj=!l0Yj8`?G}LI~rwN z3mKg_DC)p+5mpA>6xfOwVQ1>HoEb+irsn+X(Ryk0;9v=-`H*yAu)@IdG`cl0NZU+u zWt^05Rm}B!`a~md^ROPTSHyT^zBp|?Vai?o@S=q0y4Uid)O}lhC(UgK8&&mjGOLV) ze$|eBO{UmnA*u%(E0J*4y#G~J=aaAs#!KMnC&)o81Ny#jakizEM7D<^QaFSXki_;G zQlco6q}h*JJHYoOF1ygv2ITTVdo;7y}UJrHTA>=Hz9WUsSHwclh~U z$A>Z!UaLv`(#G3v>nnA1kFNc_kfxAG#5fHNw3JG)RZo#ugTTRfz+^byO{{!2g8Rd4 zC%T$YwFo#0!rKhVr`ZnwthDKJYq>dPCM-t zuD*nB^+TM#HVt(qJ+(Com1UM*K%T_x0^;L^kzo$_o%*Wq3f0_`lwNuZ}4R z>h>z4H}mlfZ0c98Rj4SmfG5qIaQ>ilD6e1tT3Yo&EP|V>!SMu(u3r8N0HSi#feguA z>WPGv<4eO+h@a_vkyn-S$bB$VwXHVl;IA_;7zqUz=OFo41Xh3cmcSM~CKddcJw!Dm z7wyt~mdF^s7Mr(fZqg+QeHjA`8#`i?e3r=F?g9PPED`>drCQfB2gZ&ahh!Gpkg+f78)-&h?6CVDGjYZ`u-nlY!D6eEt zsLdy6YKSUHBUO=DpoReakX%(ddjZduQp(;jV%cOX_-GwZhcg}j)&v>IUbRhK!nz0) z%aQU&6syV^cfeZ6kHspouS1`DcwS8C9HS=@OE(6L!^OaU+LwU*Vp`v)q163%h)gc? z81oFgEC&CqvgrIF3kRA1q|S(o3QTBzwXzp)a@6j0Y08Ti1*z}UlC^#}Ko5!8RRb1g zVgQAb<$nJhuU3S-k)sv9Cci}Fo{{CM$_lZ(lgByQkk(xiE+%gGVG#ylnHgDvi|w_k z+9doVTbz{k_kxR7BFa}ajLBg7QwBG8a>vLaKrdAG>YWN{wv#kNeb(>jW{VxaR>>5v zpJ_Z)GDp*w;+{E6l^RiOBQV{5vS7^2h;dh=pV_GHCbEHU0J}uwaK9Q3`FSR#AmTTsyqz*y-~+AVXjvN4cBB7gdt&nr?FS@ z)UFtvUm;QR`a)1ACW`0~;~eR;(Ya7hmhNuTUBs06VEl{0dDOrk8rBI{g@}R!1%)FN~5GZtKsq@n$%8tT|) zNl<{}c2T{W$ELv|Q-SoQZw-$1B&(j{3m3}_EL0*OB#bSGkUU72g{*WDAA!s5Xx*sJ zJQP_OX=7?!PFPrONeB#jwCt~xh13~;hdM_7*}r_-g{YfNhOHT0T! zI6pTfvIYIXb@JwGCd$iK7@Ahf6A;Ex{s#ZFN-SaKe7M}w|y$dznr`i_fL|niB z`Z3HpHBZn!{7S!9qxFs|uD76%2N<+7G6X$S^L&=fgQ{vLo4uUK%Gl8)L}&0gfQ;ep z`78a6ee4MTl&cFjrFS}Ad8uPgW@O$;W|2r9gU_&VL7S(kjDB58 z+ZkF*lL>+BgHvDAnO?C+O#`!x%nK7lC|RY??RJwbH@-VvuWVio$^$$97#S_gE+5G} zG;gw#lW;9n@5!M2QFN_33LaU!SMhPEuYnyta(TV%CctWWIo%4$k71*A-ogmE;FA) zD03S9h1?UUKr^>0QLUp@(33+F;unC*pOoE<=H=|`D)RaAnflY|ZhB)^|IUXFPZ+i1`l@HxZz#qfNl)#>CsG{&Fo`%vh)}%&XK!h6C`=RVSt#)vT+S~>h z8X0+c0E~Y~3qtV|JWdVAd?ig8ptpjEJ6Htb_)cY{L~1L{)GM+|?^M(W{iFS=m;FDX z);UGm4u_vMd|k6pvK+~G{^Q~bU;akn?aNOKiTyjDlBgp0%*5bLr-{+#Qiw7+F+}@) z5cat6JF5KE(As|WGDiF0*Sr!}EdZ675auM~x0xPG19Gv7Fx&Bm75TfEm9iISa0v5X z@twk}>8CJ>+2(#~R}xD-GwTq?oI)-NFiIsb+kP9osT)5%tk=yY!nN307?6J8SsaBt zcY8}@#xFZPR6I#^phmrH5Yg>i!3@(1-#kb}p@uDJ7FyT{ z{xXd&i=|CBGrC%W{zuWc3b4mVgeo7~(ej{WPqH8RSnvNGJ~n~ScWD${0#*g$dqyq+ zvR5Ksgf+{?fOl#wyJhV&0~-$#>vvx6>PG1ILQ)l+g+ksC`68^b zIUa=6+{Ld2OARG!M(UlT+DFixEw9g_`Ux8$;G3fQzB(S)p9oAb?+5`NIN9#1w8F=6 z*1I~sR22IIX;sEsNb3>kt&_WrpiP4P-UZ~A`+PLp_#_*WrA9;vKsZ# zeH>7C5!NDOIxLMUt)4MCBAud0ZxJb9OY_P6jLG*jnrwKc@pz)O(kR_%dZcBrMqyP} zvlvSUff`;dJ1rD)ej%c@F}5#pzoo^rFTkFt{L_AVrIl_=BkR)##p(=1-aQMj;A6Qg z@om~{vTdhcVXW72Tg`e+Bz|CXmhj@NkkuTPli9jcBONw!d_ke@Bww(xUeybUcX#zQ ziCY2dPZs|Z8jJ5}m(>^179aHMu4CCga?!?|?8V{?mLmI0-!iL;P_#EKu^^MC*7ZBt zz8GKFv|7)+RU#sHgQX?5-*k=~>yEuCX2RM8og-QJ(VSYj{Ina20<>4wzS)JO-Wwb( z;h96VnWk)_I9-S8T{`0dGy89~aUB%wnas-`+Ty#9AfVgTTVXx)$WZLx=N=2*zO;v0 zqGcjjYi+eSI)DYR9Ai2g^i2Jhf7FutOk~pNvus*b@e+b(2KZc6H*-K=HFf>i%ctxV^X9xXvd z{_H8Ppvk|_LAiD`ZdSZ&6N(q2%AZe1UM4PQbsX-AE_@K=Xy{!iZ7JujzV;u9E|CM|e*aUVs>WV3Wqn`f2F#()yd0h6y;@{ht= z5}5PFwv1Zv6LKM4v^s0*O|f0s;Gf4Q-NC*-E}OaU2y7>#OHEcwOWjWd-bUnU5Y>dL zqnm+Ii5ow35!J6rd^^l32{I=vmedEU%)}qogT8qd7E8E-jzs((0ITtqd;9(9nz0Ex)9Dr8)b2PTLVT;qAmbCq!re<}P)IDA4o3E+A zVSf16&(eQ&hJ_LyhNjTRVN(zD^YGo_-m@i0n5D7eZT7v0LGt3?=O1x<_WG~<)5aQy z=zynuKJ)J?pOY9IZ`mh$%cf#2N~-98ZMLdtV2|GRb1BVO3kIV9s12hlO{2VD$?Cf5 zM6^)I{uv#Cu2vO1L@P+#pU>FsKUf1TGJ58q`PGTS?8XzlDI^IihZy{Yhl8Kadc*^1 z41rb#GNWQ@mB8#39BfRML|b&ndsGdWZA>Z%d)_`V(ldoSGMWV*t1RkG4z@1O*;X0o z|A4|3?0<%B#mvZ{^lr~;DDKiZ1>z8Z8WXHC`sgMEe;Ixe0s0HATd@QTlB7&&BIPz@ z+kI9ixbtfKckV*T#&Y1F_35PnvpGW3A==7~s~eQfGAeN4xJ}*%+|vqX{RU{o7Qeo+`o#)zGSv9ZL=D z{8>25mlUt$#QjUn;}z*tMQ>kfNct%UW&U@6K2$TwvYp`&(i=M4PHr7@cXS@gbCuE? zIva@fhtVn0dv+J6wBFG9NAt5f+*2?rJGV`$+0)gy@5#--{gk>fBDa4 zLMzr)f*@8+V``ZM(jsKR9y@9XJr7u%UccOx^?RyCU=M|Af3vQj@)?cq@fbXkLFCe2 z$3bP{T`DTX^oO@Yx3VksnUP7ZPOF-|1Ub32E6LMKmu-eajbDp%Krm^7N*CKfWBi3* zM_^M(^ck>|-Cx)qhSQrnfFrdWQm z(d~;$vh^cdqp+fqI3BG|^#}nR&Q=yZf7Y>-F1Deo(RT>9DA(DOS(eWzcS-yc07pD) zA86(^pm79PT1*+XDKx*jfTPU#4-_s1Rr`C>p+{vzzc~{^pe4@4UEvp9B&+83EtR&s zsB~?r%6=)QGO|UIA(5CV%!Uf7u#$femaCMiP2^{5O{9gIrLzj7t)lsZG*KmE5#z9R z1BJ9gS1l)PFQzs&zB?oWhJ&JJ8vxj}nvR3UEsJ_%ZlJ0fA2Y&kFGC>atu#tfu(CC& ztDbroJDAtzOp=4VDOjbD9Wcb?Bq6*(9BCLE>|jj&pom4>839uh)-Q1t^+Wnls9WR~ z(A-if+FEURHO%{ssetCySj}H1J{rZwHKr6ftXrKDWl(;mvh7W>dPt3h?(cQ78#e`_F)H=8BZe#i?CWygObl)@%P*2Rb0-^*#7+akCT8SH6e zr}6(a+9+%YaPdF>?SKCJzy0gK{OkYv@BioD|K&gZH}03i{~!PMzyI}r{ipw?sy0x` zqou7K3S4TnE%YL9d484&Ay8at;lPia#2#^8UJ~Yh@=$^$h0QhInjA&Dz~tVV01m2j0v1jIi2WpQ7AP2!q4=d8Oh z@M=_5L>_%)ei&y)o1sl7XhRV)_9@88G@iYu<#pvP?~!@mMWlK{RFyyQc?Hg_s7rf6 zH5Pg8B9&|7L~KY)c$p^46$I)I?sPMa-Zz20f}@xo{0WI!e5ZT5#QCw@)#zkULXD~w znMr`}Y?7#9=2=*eD6a4k%E{IQ2`2z8d$Op;N%-tHNNVrffrz zw6L(rLLQ+f46V@RmO!c*0L}i*58OtHR-WlQVz|aZaTftZ4HYWJK08_j+gZ3n_Sy=U zax$ewrJf0# z6j7xC44y0@o8#SoBT+!j+)$&UUB}s?Hp~xcq-qlrHS)uP5=e0BV%qW@fVmZ7e0^5A zWVK!Hl#rSg%*J#oT8dhm6xzwSL19)NNe*F2QUM*eZSd4COq~aIVni3)p1PuhhDP%T zvxsnxZhYuQ4YOAZ?XEE0My)DB4dDR3p7@tSZgbHU75DJ7&zQti--0{V(VZ*-7u!fC z2*B=@z-x3S;Y3l{=#WPFESxJ@{=~+VwoNg(v$QG)ZY;(|bYnG^2{c2|*~QyF1Xmz9 zx))GeT0ZwUNtza%)bG`_~Rv%tWvq3ODQH4>aa| z6a>1&XhN0MA`z6FTKbB`lKY%oK4NkX*OpuD4$VKEDcfodn?qAllH)r`rE&0#g4&Bh z;*1!AM!FrWtlvqp#^gx$Q{C&|DH6e+v9ltD{e(lbxC+K+$9Q<{naB(fiwu}ahM{%F z9gc(h|BA@;|Ht(UqTJg)A6?|L)wz&(>(tWwl$TnZMK!UB>cGak00+yoAbUnZa#j?( zhc_2#_?AHM=z_o_X)J>JJFeeTJ4vtM8_?DoAt|SpIPl{8zopN>#e%*Af-A;`NfTMQ z4O-jD}__rYm_bW+RZGq@dND4o$oZ;rJgx zJrgMdtwFfIEG2ezLON?)doK!S3mi}y=cN=S_Z87!Uh#33)7U}5NnARlw6102uZ1y= z!ik8iTfgl=;k~Wl|0%AP){IBD{cb-{`R!Oy*4{0`xY^tU8@%CT?ii2^sS@tA7cdVh z@Aw#{RxTEW8-X)alx!;Tyf8x13!G{jLvcQmTJ0dBIH4U#<%3j1f8NUbPeD#0(Sjmp zD-V-a*k25pMc{}N;m;Ue^@Ef+M&sGw{N+G5 ziYn6nn{3fUJm>``NO*fH`%EB%lUG|nL6L0#QDeCKgi(xFYB%ZM5h!l^#k46sQ^}DJ z21oFfz5~)_XqL%nhtu~Y*snx_e#%$r5Fi(^xh6e&u#IK)fR5rGAH$vha=5~}J*fSG6N%=H8p zY5lebl^+XimKQ(6ag+b}!Lr_%oyN+nqKwK=t3xtBBw9~K7Z^o%(gO;p$?Ok~wySQAqC8PQ6Av8bmF1G5;x;G}=jrVJ{K zB;qILQRZ}@`c@&apm4M|VOOG`igk7CTt_`VLE-Yk*t3itC|pQ9GCf^9;L~?f#^U>H zn^zUlNf-oxd9>WmN}yCSMxkvM`nBvjk7L*?poIhZAEd?5phY@$n3~E&+ZuRbK?rYO z(*&1qu>m|hFI+>FYFvVej;32H%^R|cv$|2fBTmgLW}=Af1#dn>WRny*2vugmI*BDC zCeM}wf_}F>qax+PoKBi}C#Px464_`u;2*N2B(}7ODX3A+5a5w>og8F`Q=4LqL5(h= zdj0^{P>}qW->wF^KvaTEA^+d^gK+WWf_)=xOkWD&9Gx&SC9>)$;21d-ELX-OwQa=l z_Qr5vLsWDmu0WM`>iQp5xIFrj%Lv5i1LC|qFX8FF;%-WcO)Dv_KKTz2jTD)mHE@*A zAiRhRIT9P8Od~L_<&>r)M)^eFc*ArpWYTf)5s2{__J@Rm_4$1xI+a2}jt&Q(O}*s! zj>Oa-W5E2wALLPn!51t%!M7YEGcQ*a043n*w;VJ>d!1Zk+%>y0yZ8nDY{c~pIXa^YrE7kN}4FS z8l^PXP%9z~O&W^B*BQ|0g{@es`Yr-kQ+Xv_t0%ZnXaWeCoVMUR5wWGpETeb8bXet)`)r6uzZVDV3-JG1D_)xf~ zQmQ1P-M2?-Y*Oi_RGun0SN)1YrRJ=ZHbkh~CPo2p;o?uUt&$gqCutQmwN^E@5P;!l zIxNz5QH|dd_mYq#U5vNLv%$Hez)(seD#!V_TI_I19c=r=4Q7S?f`5~RDew`$t$dY< z`sU~*!70T%n?cF$Bsz(AM)Z!vVyFVHLSNlpCGY^DFoLhxcM{@^m5DjB!NNhAjONMA zKv9;OO_Uf}5w*N2+##AHU%FMmf=On6Pdh?+eBx&w9tp3Y0EznuO{%reJUkJaDx}$* zkdi}YL)*iw$;Q>BbpZQu7~8_E(r%E2cW~ax4F=}17)`(@&T+lc% zQN*oGNZZoxjdv{|1zHHZ3NXgpPdvOQF{VbBiW^~S+H+sT=_Yv&SURlJ{2*SlW@nM~ z&d!jpcvDV0#>Rh2)p>`Dq*7_oUwZzO2p-JoOyUQs2=!Q*(=n|GkZTL8NzpQ7b9fBt zfKnhgrboKX-;+hf41Md+3%+b7u}FhP6A7sW1n|*HBb8Pm=4Z=7-`+vg+4!lX2KIZ_ z#)*yZOKRg{+7mPujpc4iedjSy!hQ)Oa)E~04wvzzoRa=$0(q3P!lslR$BdW48$Ers z|HSbnR1gMvtl}Hi#-JWf;{{|Zzw3Dj9W1!71;Z$H&F-a^A{dq#jXF*a)7<$OtBTRv zv5kOa;Tey}tsZV9Q_56iY$Ows@tQx)P~tmO!Z7G+@6R}*h|1Fs$m9l|x%oimm)y)M z2`D5WEgi?@!rtNLCsk7_^RCcF4oR9yAD9J3n;m}TYzoriZ%rae$kRf!klFH~ARmF_ zQaT0hHzH+c>AcDaXj%Io#?Kz)BO;UiJZ2jQFaMt+^3?E;1s1xwMWidvoH_%frTqUR zoYZBu5LbTmw6STgkXXQP%kJ+A0)kzv#{`!eQ!%S2gRBmKoSmB@Ye0QgX?!WF!jp>2 zneF;_@+m+ta6#>gAMI;_ZG?BVi5mIV{VqRU$O~5f|AWe9g*d(NCpXjUWTq$sF)T-Y zV>ZdIE+In)(pv)#cf7oGO^brWNBF6`2Ky?WC++4x5)$Oi@s>rV86O%dyGn|+-*uDT z`2`~Zd^3r8X%s*hOx~k2F^f7;wEM}KR7f4TK>_pPh^x3JZnXyi$Ps+DU6t^h$<{(7 z926$B!0se+Hx%F@R|!^e9Z~f3->Kle!Xao_K$W1UN?^asNzx z>yckj1S)*We>61V{7zW-r)?ZSFtw^GPW*%NibIuV(hQ__TS*jNbB)2N?55L?Qtb`Q zRi7+$0Dm;3TzlVBHAqoZW~NQ5Tot@H-CsJgj7FI_t>5{EflC<2B8icKf>R`vn^&tX zhf3A6@z2YgjWl+$D312q%i||`NHM)PCDG@CYM%#s^iGvu*`3$grBBMr?`$`{Gt{d_ z;(2`mm}(Tz3IWhRg_e3a|Jjy@JbH_SZ}$>P`P#3>JyH5_Roe?-q7=S$N!i z6!1)ptNwk+!hPz15(|G1bekkJ{pgPdv`-tX7?}5_l9%Zr6Y>^OUl~x+u}vahze*cL z9eX6c`iOfgI+ED?AAi|L7;ss-z|+eo`i^@BPwCss6ja?*5HByjVpa7Pfa03#`jLh4 znh6%fY;l0*0-7rOirX}UEMVj7zjlF?Y016Q!-u>$=1irD3xO=Hnpix1tSD(~b@*r6 z1g=@3s>>l`{w1gOS4%lWl)$g_dN3eih++1n(|s*cr_;Pt@=n9o=JaDeR}MZ0JGvDn zEBx0w*H+y7i}9Q;Y2UjGLsm)t;oX1aohh&^EXi5|8!Jdd$yq1oek}wCqXX1r&N`W?4U>sF5MqIYkz?=T3(C(MfXA^*0` z3W$2ey}_?n_K6CGjm(~|k|Qva82w;2Z>SR*{Kr^L!R-pqAAEWvZ_g_f@}|lf+5CXK z-JFk@uN>Zia)+>gPPZu2m@0c5dNCm?P@-P>y4p4^Yx7Qw`OtGd+e|)RUlcGOVAUUA z$`WXO3bLn6b+dQXJRM&t8Q*TbN#!rCOV2>s5pnKPNPd+)@jjisSU7sU(!yw-z#<_e zsKvyOw3`yY=usg0&ANO~CSC=kqGv0<5cEJ%y!ieRZiN2p2{}|SU>bVmAcBFIhoBp6`v@q43(A-NX)a& zq7j)m&2?pJJ&ksa$~I9i$jm_d{7^X>)0~;^1~j%jy@{)g!qud<^IJq}v3n*`X=x;q z;)$oN9ufTLs(GTabv~;ur6oJ)$r+?+%>>+QjZQQ}V@hTShx1jfZ-P+^u)9j0+Xoa1 z_DoI`a*d+R6l%Fp!gmVILTT75nnY?XCqs2$nEpm!dVfkwqGs3Zyqq*r0Yu(7m`kp^~MgE&1d-zl9d=J54DDMK<>oknzPrpr9AK7vg&Ei`KRSjZ~8 zbWlibT{1OLlH19YYvrU3r?LC6Im{DE*VFZq-z}NoCR~I0DqcBz|B~y%M9&^FJ?9K0m4{&_9WTF{adtjUbT(m>NACN%w( zCYwZs47;k@~~KCE^^Nq(DH|OBS4QpxHSzd__%wfg!j3#fY!N9SuGUHqJ5K zy_?ihL?-b{-3Un0^oafBX{;M$+VmdHL>g$d(J&!kw^E4_wbsPGfT@Ul`wUQ=9OxYL zKl_0|s;bX&IvX4&^)A%O(?EG;2{r6$!-Gqxlaa6VLrq(3iZsZ2N}!-_CA6r~4kEK) zQuwRzp@*UQr!)r&Bb9}XEm%po**+Y7v{dw&&T)$7FozDo$MtQ2aKErjJBH}gDJlmJ zyLz@6oUy<$>5$OfU6j9a4k?KC`O3~pffH||35}+xMr}Ju`OKm=I_cwawuC937rLB{ zjv`s*-#(+A zoGtYy4uZjKeQD)v8W1y;CVG2~0 z(?F3NUc)fb~(M~yGn~B8YV2}{0bkFRtgPFef79kB&s)4OeA7u&UzRz`q+Io zvc+3TvZN=?-kc!45z5u;Z!m@4cBu#BP=4Cd1%~&<{S#C%IAWMeQrRM2T_y=klU7<^ zAj6nHBecNt4-BfB(!!vQx+ug{oL4)_wlfBEzO;@ z2**l0t}%NHAz8w{N}>r{h>T2{CHw2X`-i102%J2I$w7TIN#f$_+k8-o#aVutEi22{ zmy;bS@=Jehb^do0=AzPJBiSaYU8g&Q8Cj5eY}*?}=Y`9-hB$C>-RV}XAf~sag^M3$ z$k}x-q>0rm7sHm_WXK6?Ki-)oz7blkh@2A+!j)KD29+IbJ^GSW;iOELl?R2q%gI+7 zHSCyQ0fvdvJGj|sl(^Z@xZA@Q8dazkj$<;Zte`+SlQpVn2by;JYy$`-qdfw+lJdP6 zRG<&%XaGqQe;008pCruhn1+Xc+?g#I;J&C*u4f9ThW?nfn245MM_hzRaW zIZZiYLE(fSPjjZho__`=4mLi<;d88eJF)sLiEBh|BJtNT9LhT;EyK*Jpu6exw=_z$ zpV>HBn;)>3PpnOGKu|pHrp-89u%IIr{MK*S7rYSF5vCe*gb^nka)fW}jUtiSN2cg( zOK3g`pOb5V6oOCJNN{7pi*MO2vB5^M*I)}f9tf5ij@H^0AHBctWaKduS3&A}I+Zp- znOdmH3!g>P=P2nDlPV!taM2B%$wrmbEGG&2P!Dk*-~g<+wpd@VZ5C;d`P2^~TwWxQ zWTjPm2qsjakYMltodarYJWK@5q0*ps3yXDzhUEJC|)A^kNCJ; zVK-|dO9zfHs33FAuJYpPXIbrPbU2QC|9>m1Ya(m6w#L2abMpJ?uh&`imlo zt?LiP_3c-WI#Vz_ewn;I#5Ff_`AeFtZ+?0Nuyu;DeV?Xm$2qC*?$9aJk`(t}K{Rsa z{8SfX`_)ji)S8|Mef?CSbpBRLk)>c|Uh@k|wXH97bDN`o{=feGU&OTxlw2@twf^Z( z|MH&;6DsU@!?}r{hrF~pYifvm!STy7plybN^cQHyOy@I z0PHvDv{_*RdR*v)il2fji>QL@r>EdHN1EfMX54L5ZMRTYJZj4qZ2=wjP}13<~tdF#nk(V^aFTTc0#AQDmb_%~xR zO@g(*S)vPAKxwJ#YPW4fV};)~qB&RI&I4_Z=i+Yi4$^e4Lea^#Y4D_kxf=S1Z=_D5 za!|iff`{)ZQ#D$d%|j$ND62P4K@P|FA4HE{ww3ICLeKY{s?ys`Z9m!F12J#~e+Pe~LRzAc`)XCvT! zR4}Zmt2*<;Gmx&62j}HiCdS5%BwoK$xOn&V^FtqUQJrfmKDoQ+3u`+U(=X=Nt(?w$ z?@dH^AOD&{<*h$TPP=$jCY}Yv%C4)tx1Zk0X}_w%#DDC2JSDq5K{fp!-n3s$P^~p> z+UdW9UqywUb@BS0O5^lX`%R}0eI}?%uX};Cwvy9V>+7ir1BY{xm>%yOO(0qnv`T7X z{6QCAzEeni`RQ+vsBpcK)WaM4_lzLkllVgSuTgm1RAu6}pk`UXDu9`shU$O1^ZGBf zxe$K)(`O=I|4QNG>yN|8!^Jiw+4YSc3Ru;k+2=i8;YmQ{EeMll9hZm|40tx7@; zogDiG@AT|07)g{z3Z-^XL>-tGI2(YiN8>WH%qvSp60?W5`Zn|%m$wsAoH)_oc2Qc8 zvK&UM5V*03Loi~0%MW}5?A_42+{9NDn%jAf;4VB&1A&9daI&SZ7#xLsm3~;QN9JJl zox*{IQij=Yq{AXjYwDs#7ci{cROz%1$;OKG``?fVK;IYBWuMzjqJ~hN6Pcb6fwqm& z8Wr-&s(Pexx4@B=i35pxp(c|WbR3^GVHz^l?$DT+{h~Tr5NL@?#dp4!(mXx+*djGc zsg_vFFv@c|kR>&~D3DxGfroOMr-2c^NU7eqIeycfVy;+khh`FqK%En(d)X<4;HnAcb|nz1o*ahhl!-h5 z9#C(JeODR{nyNpletag82=9|xWJXA&*l(UMqRz>Mjv;^kO*3dm0>Rq7ZoVyek< zCXqI4umIHPe^6*D6lSNSfj6YP!~W{W$ivSFTxIpMl)@{r5eUGSMeS{=JiC`+uWV&g zj;d78#*~}6Dq>pMta(YpQJVQGiR4`0j-cL%Ut4l8Gw~yTA-3OQqA=M|2#`=4T3tY> zLa2YA!AQfmzOZ+A$STEDdB>E8)#6zxgre{*klC~c_ieEw7eAtKnMuuDUIelrDI z0|@nKy0f$YL0f>Av2R?W#;!R))d9%HppMJWdW!lPz!S-^$${ZAFO(mC&qEM7O?zt= zqdM!fK(Q*cvFxdB6y_}pt#7bGtv|(Z%(f;?m$N2jF$Hd^4Rd{3hhmjYbA*AGWf~Vu z8{`X#`^Gf0lsg3K(pTZtmZl@ieOF^@XhhxJ69Wvb%2IXJQ`n}bcBU_j2|dEV+@Ovw zwu|Crorpz|pU|Ec0zZ*bL%s`RI!kFDGfIDVo=eJbT|F9XRE^iVs656|R~F=~+@!!1 zxUGHk61dr<%`S_A($js2sVG(-B)pdICl9|x;tI8y{RMeU4=f()Mr%=xJ*P1dsSJj} zoryX|#p9yPjA_i3-y|x2Q<2J$DOIdY)X6IFHEI&8EMop09%iO>M-LNw8;S}R?S#$e zr|6kEP0cV`f#0GqGZtw%E=frbaLEF|j#)OB^IIHTwhLc`)Wn1%SoWRq-gfiJq|%k1 z@`AL#T>T`Y?9Z%*9E?__xI|Mx_*rDVNT#9aK-F4TZz%l4<(mUon9`X-mNdPSyrD#g zGb=~Sh*oivI)^gK^+KZUFE5tH*l?M-G*{8mC*4R)55zyqzA~tC5mFcX_wB-`a3X`G z?>h^gB1r)v^D=XZvH{}q)x_lXv~Y*j#^Yw!Ldn9=WmG_sX+OR*K;eJ)jxrGsAQh(m%0HO7SF;#iS@0Zt;$fcYz}t)OpUI=`6NaJ74}2jq=C@j8?0K;}`ttN81&}h%(!tnmHW-HREeNBnx6MFppU zM#|b5gT+@4zY#d<;cM!IRUC{&Gh>WJbyIf^+M~EH*G%{FuNayL{j;222+Shj>?=uK zy<>^^C%#F_o&fE}(r8JYwXn=N1+_qq0f6cag*Z?ekDZB%gp$8xN+CphQmV2pZYjHy z83jw;q2mHkpIIuo0jm^vkRWsJC(~4}oU7UqoXr{GSml?KGEU70Rqagi^EfOrdCjNXjY%-7z@%D+Y|ke&%mzf@#1P9?D7o zvX4YjhK0+Y2~2AtpD4c8rk#h+%E=%SfrQKarv$lBILfI#doKwv+08lv-{bZh9OAl> zhpq828Hby%3b#LrOame&9y7Gv@ zKLQq{0UQEi!%?{_1*c#LYIeMS#lmN&_z7mJtgRo8VVWb2Y=@Oh*6-qADf;aYYSf5oAjFi_B(wJ++`oDE+^GqUhQ?{t=`3yMcfGUS-z2Z`ATCcu;Q0K5;Rs7e&I&1jDzDsWub zb8#DBI&MDu>~X#pt}xb=-t4SJx;D!z?0^{SB=qDOyeCCjq^npvL$kk+L;k+$B=R zw(28gV`f$&vXs4p6N6r=xKc!g3Taj9xh;$v$V{#H%1Kn_oooUwcyDeNm3huJT@uE0 zY5+iF_*UxxvRci3Y@-@*yj9K!h8e^)Rj4e^wM-I_R0#BNYSusij2V(v-=(VuA1zJ4 zLW?SgX7Wwy$@*ny)p1Cylo?ZQ3zSp6()b;w{4d*EGm?a^d?VjHP?%MA+oBrO_@a$J z@bFbq6R7i1DWR&7@K?K%s=shq*#{y{G%~C<2CxeB1z>R)R#i@B#*^bcO&Iuy;g?uE z6%W`=M)k;%?eI0mA+u@D2taHs`C^|xGdZHJRT!rwY9cYyTX~aHw%0Y0+2H>9l)&KS zV8i8mnn%R{1{W7L^)tu8c&|`?_F$wiT?*PNvdS8S12`?_a#6Q54i^=4dVjwg`?o?-g)=i7c|`dkA1K9WsT~2$DjJHNsa`dh!U54ZzyDJ! zQQiS33929fNdJ4KGD(Q|sXU3I^i{q?0TlDJOF$enF>OOs-T+!P*>X`ck%O#CA@5|h zv+_8c`Wv;M6>@`>r$}%t`;lB$>n%LTB_Nk82t$**a`-i#0XG@NkS3rcHSv1?XF#4Z z-8ICyE7~km<4@9m(f-OeUfAewz@s12gR^+PL09HplTW5mrvI8<{)N7X z_&t4>uWU!AJoc*CHXBl=M2IbvERV1y(1vhmSTMPiaZv@{I?i*)H4t0*yR54=qxyHX zu;lMDC;o03R=?iNHcg2Y7J1W5lf+w2o8CPD8m%it!IEg4+hLz1Nrh*(L;(x)m!%r{ z%LxUb-t{kgy)}Qi%JH|XN}XG|B zW|-YO9o?5iS;!)}omlpADnXXU5*0)4D=uu!uWX*n@;!xN5ome-IN@}%p!D`-x$rG* z+nECFVAZuY2Pcyx)h@&NWDY&jH}UH~%pl59R-nsiJQB)M>vLGwKnP)~KRj)F1!5+8 zUjJG|`u?Yx*&KfDuR=&4*1~ekG}*Ocxp4p0Afvk<&NRLJi9*xuPrs)rrJHBmC;>?| zhq>C9WBl~P&uIE-9D57ZEVa?!Cn{{XT=)ehdcB>4b!AR1y(9`IQP1m_J`l%@Ixna^ z%wqmQ&a`y1lv6Yn16x6Uj$c*9E`M?^XkLG_B<(V|b4h})72A0I7q^odVfXt{RiSWv zsj$~tZGvCNX5rnlFmcV;8*#~`I~KSG!?Y+8EqhbH3M_` z7q>%az}pHknMl;=U?xprHE%QmYK!el+;noXb<17;;KZ}}D-~JFM+Tw`2QPnaf4t0M z@YTG)6p~ei`GXX%#FtkRFDkmPcPcDfk@V$GYb&a6h+VrbYUwR}{R3F|k8Sr*p7C7R zmC1GEN?3Qr-hF7xbb@78g#;+v5M^gu zZJvk&3BjL9@Spw*R49$pDL_XT|CTjkVPgI$7vQO0zxAi#9hDMeX1j!b7t=dHzFM2D zrW3a3UqEGsEdIQmwW@lrEawwNbqwqhG}iIA3q3`ihS+Q*2zXX*Kty_YQvXZcMeRFZ zQAk}@ILcHr5YL0)biwI-R}gRg!xs|IxHur6>I=|TQ_c*^iZwNkaq28)g3jV)D%Sui z&@s@1+Ol?w?JfZ&rIoonh$34Iwyp;+T!_Ona0=LK7ha>rra?UxPTSazM9tSz7*}Zu z^MZjW)5KYAiy}w0YPFhZvOE)PSK3n4cMO|6lJs)6DvPg|qwHVw@mJI<;}?t6Zl+1` zlraZQ0eHlJT`%s~1YtF2@_!TeE=#uT%9Y)}uz!#3e5`!%JE~VLS=nuQ0hOl#HPV3?Tg+N~=y#eKWxQYl4m!v1HX1!A}BWqew3bfl)*9C~t!= ziiG6EKnRT?{37LI3~dFQ7L(}PQ4a;X%4nco{HWxP5_5GIG1sw36a9zf2WY7$N=TRcJMm?vY31%f}9O9%|s&1!bWBzz^EDhj>PL`zV~6N9I8;U5+C_WH`1eqO}JMe}eF=^w_NYqHWQ>2N@D0~B* z2BfO*WQwYb5EzPITN64Q%Zh2hf@zo%^M$FS;WeO0!|RM9@X8@%#R`($e$$~kA*j9w z49ar1Q?K%@SO#Fs+$ha?ewwd%mtj3ltF~F}<6%uPcZ%B_iMe zKZphkftS#TiA9}zSk$5EdU&%6#5G{*fcn8CAmyXDPWXTDu1s(O$^{{KjUc~<*s-%n z5V)D^9MX&hIK!6q~Vupi&j*%0^ z3KVg$w);yQF1!O>j^AYZpA7P z@RO8kBZU6Xm>~80nJZSLq&+?+b9ONdt8AX=1r$wDw5CK06s7kDG!d?0jlGK}nImKe zNC0qO)8Syhc7jML_In`1Sr552RJR~>)IWsD<6-K62@S$I4YdQVC!S-(iBn%C$u2^p z{>yqqNoU0{2t&t)BL}~HAcJ6BbngKAsyRuE>ncF z2lT@VE1}d`=;WqB`$|AXP_1JU8aU}mtu~MVb~l7w>!CPcw1w1yAdjg{{1Z_T^97@@ zh)`9yPc0>|GB#L%BRI6_o3=+--&b7tyb5W#D4uSwzL&b%967ieUe^5Lz(f+G*PAzq|6t_iA@BpIa(5fI@hqs zAe_evgX)8v<%BvIi-`!Qv}b}I4z(X6N3RT$K55J>A&BIKHG{25CBiYSG~gE&DZ$k& zP-165Kl%ZM&ZWIrtR~PdSLPb3fp`9+x=PfBairQ1hU`W>@d|1v;4V<30vl}#<=QNL zNmH18#i4>i|Bjlr<`apMj4`Lw*d0*IT;~pg@VC&zmQd~D(>etWgSy^eNZ6U7A5-A0 zxzo9YMQPLamFvM?eGrAP=h8N$Ck8WUeX~(nSyL)KNZLp)ncyPu#U*hcSo(AtBl%0dg+^4HK z-ol#tFbJ_?4(uRlVzF!8s6C#O!we*~2F)Y`Io>TbQ3T^PY9cZiLpNvL^XPrj>%!I? zV=QdCXBrvoouSERp*G1L$vG<=G-t2wrx+8=d7hr@tE!}|jGh5iVQQ4zOSbr2dGMp; zfMn)G5x7&c)#vnR8S;J$>i{+eqF0KLEA&8#7Ez0M>Xi+DP%4(>>di%FBhzY`xSGx_ zEGm!o@?AD=xC1-Lx$mKEF`$RYMZRyorJ?T`R zV_>T(YtzpJsla*hF}3Row#|U)aSn?ei?uQ?*nIoYfD8mdE{c zh+ay{=29{^Eh}O~o8?lL@|@FSmjGg9ojqEpb6wgrLr%Si5S~IQR1N3>eMZ+A1E!aq zz1*X@H=;ID2sRlAb*Rt8r|Mf^CPD$lqW0jv7wBmYa#Bha)950f)58LW=)V9|q1cq_ zmq8Eh8{h$;1}Sxu7Tw^Fw!vKIj~|3P?l35GP0J5SCs{uHM^b6lag%DtBF-I;ffuD*4k90;A@t=IT~oxYF5*Vx z6{TGX5SoLeZcpDPIQZ5Zm3SYFB`G!TmSrsI3WD22U;8zDuUEPSIa**)a}FA+9hu7| z{ZoRXd`*_izfCnnL)i4hQpHrtM~zg$J6>3&@)%QDGYd)*FVfUG3h~T2O?EaijZKf@ zLj;fNzf#?y?U2{7$G4O-sbP(SW%J|b4K@*JtdQgyMM)^qe5B{fE{07=*Oay%LTOCm`U6W?J&|lZSO&qs9e90BI4l{!{8@L0|9+48dC(QSokx-Sc<%u?2RI9h+3HR zQgBRU>B~F7vg zDXNdA<+NTHt{ky;+KM2VAe5=ijgp9?QAW+|IImPud?nA9| z>(&YJsAVq14BEzX1FH_WV8t#VJY;*wIi+3T%>!RlpNv|f8#<=LP6*;}f*(`*M;+zH z=2iMhm&=Tjx$6XVPPSVGI+H4jAReSeX}VUtrUSu%5oVr*pXFcC6I=5{#PTaP!OsD< z>|Ej~Cm2-4UeB3BgX1@ug3gUz#Q>F<6H+HH5~!M*{aW&BOe zRD^4z2y?9@oOoQQwDna3bO0}x8slaOR#-qxU`eLN^`6@Vt+%g^_On;B;yb4lk+);| zh%V@nu}$)ZXT@}`Sh?#I)kkCBsrw-<;iQ&KuZ2fC0P$~D4iVHWAWdc3P6F+(#|mIf zS177aLLhl==7d^OcSkl$5W&4*5o>OE; z!#;Yba7vL%#H?E*zrgSlOspmm{2uAr-$Rm}jm5T35^zC!-2^^_ANdtK-HtH*fGN2) z)=09gIY5#t&IpPyqAL{nNd`R9Mr&=+r+BQ<--buXB5-Od51btY)@HiZwxy^=2~Wjy za^FR}06~B!RtU0_q+WbCKGl0ehoe=|0%Q;r_>8<*1hzy2+9b3@uxR)?LDSt7?p~== zajAeviRGwDpKDR)WCMCm@Tek@@QD7Q*6+hmdT6We38v8mU11twqy`M=*)hL28w1Xcuv!WgV(gOG{1zn;v~!&P)@KYhaFl3YP; zC|vv^-b`3D24Q6JBdA}rASC=NL{Vhr|4=3no<6-`b!6Sy(JqlhF2=@nVh=3+8#T6d zm7DG;a+MQiOOr-|FKLTbUmSxbJDcpE8~WyQDn99nHo?N^<)CTHk5h9K{Nf6qz>?D3 z2fzlAo+y%^EDCd%D1x7i zQh?>e;4#q{9fCFEpd!c$NnlUZ)&oF{Xq@J{>AER#5h^ejL$#QjcSZ8MNhw(xGN=TUOT|khA3x8CkDiiLoN&%KKN||;(zr$@ z0fw-!dRCoo$U2n@h^|2iq)6(vu;iWn)BHb(=Q)wsJw;i<3uqdqT?Sd*mevqNP!=ku zKJ{}HX;H*=iqsJZd?0OexulUl9+PBOQ~53+uxgyL8j6&RGT?f|%a(=}8?r!B?`)OE zu~UH^Lu8Jeo+VJ?c486_2GJ6r9!=vHpw+tAsi<9!=`_`JPsWb_E z(UT-;O7}XKRBj6De?&wPE_PiFHZGCTxyppci?EWAA?}kiPHM7{dOq* zRh)X7D6HlRQS=I^)zPfL&V!&OQZn3X`{XdhU9!!&s)(h&CJ3G#=OE;m8YDT+KRMA-&K zLf(Pxv!h}DUHk+?+-?W-$}W9Ru405H{K%N5W^*kQPh^exPu}3_Tgg*V7o1M@7poDO zBw+SmOBKhKz|$J({MGo-nk>rajY*^`j$PT%*m@5Kk3#p4Do|R!29}88e<3>ur(i9} z9$5lIIf_li-sovQk`T7(GeMXC@-kqaw1Uj&39=Fdf?alGzdK!$EI-+ptcd^OBh|*? zcwVRXnI*o#gv;5MPOXKfcue+?GYXS1p+~MsqEzx=#D}L?6xNXnZps#)AwSek7{(F! zpF4f^CB;_&4QatD7f4eF@ZYL8qdGCmv-T%fIwuQrazde>t$HY(?*Ng7L=2#wF$2*Y zAz7b=WDVrhg3d6dD`@O0jX2HACQ~HhZ{P<$heDX%CJu2ts9s!u=V-|b#COs3QG5c)PSU;XM-r`jFwa!JlBx6&9f!)m~NxtkMZL7HQ0fBz7>RGsuQ@vOW zFoMunU~YZpgg&rnM0c7=!gZp$%LEd5OkyzOp&%6d(Gn=FuZfg%*~d=nj~*uDuTiDm z#1t`zDG9oM#GY&i8IXuhP|zgSB(#xauamg6X@`|0pp*zS^@J?3=75KtlkF5zR>Uy^ zik8vMAE<10qMeOxwj&y8yHF%%7ci)6{y)yP)2MlCScnmU zL7MS66;z^jp?45fO@FV0`7zwr5w1D~PK>q>lBL!$&xW3p=trXgY$R&Ki2&88+0dHG zfKrat?gkC0Ew8wOKrV7@YMhCFvJ@KkRgtUHv#C78$|7G)FB*kF^2j;_IiNh8-z)Aq z42{tc7E;S3a3XwI7E^5j8dF#sQ%-{((jOx^lD{6Y@OZLaNCENE^wXX=Fl~8Rb6*ju z-61y0gZaDojdcR2xu3JpjuzT;!a%AdunFV`E`f#9HUFqeu{|K|K@korB8LS@UrrC@EC<(LB{w4>oLoJ4w^#H~DGi94sCFt9UGjMqE? zAuh_lP9gd+mQiCNmajV6AZlY`Ot4C--qEdb`fwGX`UJQHO2Gdzpicp*0D^k|Y-DM8u8^ln}k8lby(@oh+?>+LRC_W}=n6Mt~mld8e>VE@)}PWny$q^s=et zhKx?>~&AFRsd%;V1qLr1vE^#sbEW%&4sS_x`7&A z?sdn(z>5I9CM<=OdGNMRpC63Ig6SZ!7kEdKAq*oi_ikod4iYNx*Dx@|GQxr`s~~;K ziIH&z+R4y~ft68lLvtN8Hn2=pt&^Lg5<*E4Q>wR{sY;zIVQk7!pAm5&4Oz~Ai6&+R zjM@>B=O|$X0IlUvX^b^-FqKoZx5H1f=^g%n_9Tlcxfa%&4H903A3%2n{b8!^hVLVA zS_xm8lMxueg1%hh{21u~hei61_*E?*aZN>Q5@$4$8B*ft0o!6?kgaKW5sf-83+7{K zS6Fkh&q4e`m6HN(J{kE{t$2jXOer$eO(v*E>MQSX&^!Q>4EPWWDE3_k6XKp`ro}X` zIT~TsITMB6!V3WZp=j_h(}FMi)`RIv<>4SujR6lavy{2Ws5FBWdz_a_YkGENVq8r1 z{Ae^Fb_%yz=6;@Lu%{u6Fm_DXUQxYKi~(_WIdF+Gl9QHqa`iP(IUpe%>46G^bru+3 zatTc>qJ9Lb0_%QVH`vGA%EZcS?CTs&;rXeVIaR{=P-A8Wsje1AY+6Y3ZQ0ByhrAks zcFs1ct6@rUa2g9^=8QOGGc@s?##sz$tPIv2Q>wYPF^$egKiaXSaOMMpF87}!C4ANi zQjnZjm)(G-qj3>YT2OG73k-c7B=1v61DKi?-63SgJ8B12c$TKWPgKyaYCSvy7CbRD z#yUUQ$H)s>U|gkux+!v_I*v^3yCA`90wxo(@w> zK?CeJtlv}lAhO9tMxuJWtTjhS_&c#O&PF>Lvoz<1lv-_-qt=;V&}bRu`@q*fp9)gS zomiQMkyu9%AlidS-G5kdBAus-skgppv^1T#ar!A1MA1Fo)gKyGp!St7}oH2i%Y8gRf zuWfZ=R_(TKw3|Lby-lo+bJEU6fpA3Rv7uQJ>Fvio0%+|jUCOF!$TN#5_L8td;>_eU zjMR8AV@H&|s7S=g`es$FU$D^ZhN4%2ziDiaw~$8)359j7A z8~74c%xVP$&`tzdqHb4BOUSDh{(AQpDD=$eG<>87s|qfi4yu9_Q3h1fW?)>C@)JO2 znnruwCa82kN9ymKP}#YzHEBhtCT7PJ63<_OO(<)LD~ouVM56(72Kx9coQ7ul%;YqD z#7r^>s27se>q>I~Cp0=NDj-|C%@OXaLViUlw$H|=VNr}kUS0(m*Y8Ig$?7?{Eq%y9 zaw(iRA+mE>YqARHWi8ghN~-Iig%jAkK^TBxCHH5BOGtE07P@T(dWoI@0%YqJAhHoB z4GJiH$FlzrM1LFzxJLTf((1k>u2D)=We{i=V;$7lg-r8dl`g9Egn{)XX~)evX^QrT zaC=uph0*j)Fj0)-0dDGB8%)p(iR@k1nwV;Ma7^V@2JSH0Ftm-7((kgYqhaNVlpb!2 z`Oam`3A+Pl_Qp9$!xDsqX2taaS3=_-ZK}@JQ=rm*)(7Dq?(goDo5E~on6JU3{njGkkpf^45Ei@o2MVQp+B zy^awMsw#A^KuRYye-UU29;Vv-M0+~}#?@eBs?Y1PNwHyKU`+eeh}q%2=lAt#dG%avRS0q(rRGSVbz;?-p4&9YttZXu#f&s0nthXRqwJ z`-hA5(;%^e8RN{BjVDF)N!sKb^!og{h}N)PGG%9=LiZhId{Q|Tbyi4UM?cdnnpqg< zp96dIaIjak8r*Qfq9$}zDr#=xdecFsU+A$>J7qAkk!1RX3E zcJ66S2N`IY*qDZghU`uGc%Oyio~bqMfT*8(iVn^A^}!x%xO`2hF>imKIzb zQF=Fo@ir-8)3R;R8jP`bXgF5`dIh&Ql}?AvHXgpYpS0MbPhyQO1_QoKAsryJ>wo>{ zfBe^f{_CIr`tSeofBx&A|Mu@p@<~t z?pL6DeoM=b%;AKmqX*8w7S3CR)=dawa9$oDaRQrbI*&o=IPc(M_L_#=@pZ%_SH9)0LF_1PKOQ}COW$Gv|T6) z;oOc1Z6UPRu%-G;4KSwDwroF{k-i$d@Xs~aUY5a}I|zy9*|LP@J9#a3mxsrDTIAt$ z>R{)gDD)r8Y66^akJ*js91!soEdFD9TflSs1O90-TXU)x=mjoS7{JmURQlft~X3@PnkT=bG zoOp)AG|Nt&-%)x^x2teZdOq4?GmB!(bEGU#i(MjHjXR!fCyx=P9a2myP+#c^rz47) zr&u+aEM}NN^Jk76(Y+P7^1=5RL^q>jDAh#!NDp#~BEq+b4#OV_r^g_xzSl$=v%1(ymfBIel*oepD5 z2A(aqfZ(0k7h_%niXG(aezY_Rzq8K(#2|^!#nbS^pq!U2DCnI@a#ZVIvl1a~zUdm6 z4qSJm&#wttJ*V%p%K64I1xF*J0hm(>9tI7-yjOd(I6^ryH`%rvZkU`Z<+P z#|s0XTGl^y5nL^~=;Ezk2e$Q;!1KPJK4Z6pRo)0}ie|m`=$eB7Z#S_o&OgWIo|9({ z$+VPd=bz(*2kDUmg=0JMB6-(eKjGfVQ!7;N={^$v=4sZ$0Rcx(?29qb zH&vd)CVB_k$ZPRy=j=0xURrm#NZxdQpkbeZ{s!@xqX*N`HUhyQ?r>m+pw8QU4j$C| zuge|~#04z6)HXt~8tCS^d>X1TA8aGAfhi{_aIXa8aM?QmP_RHV6VtNr(gs{VnW2?+ zO*I}^&js{lRPFihht{N&M1V64%5cZvz>M0Ch%{?+2T`vr6N_pjvM+#oZCtYcpRWi<;)l!wl|S$4 zY`joFWRw3cnbD??!5sh4?<28HKka;pcGv#nSje+vbdauDTi2*$2_VVu{wI=h{g4XM z_9v~+);kP4m24|CDvuuu2J7?rj)JmPKghKI3?XUsG+g7dr5=a7=7$=y+^?F2w?vU_2p+cJ@F(|E>+Z0;J1FDjd#CP3Mk%7)QMPGOp}|20%HAGKs-*lW8B zCSAltr2UW%Zu~SvbNk!h)hfCB7 zj7;Sgq);-~i;9U#mL7%kR-VltM*y`SN{3pc&k!F>(K$^r1|Ne;x^Ynm~|+Gbx3?yZ-qNr?7PUS&))? z4r)v9m!7i2kVF5=D6s!D7? z6Lrk@sx74nG(%e$p{;R9w$vrBh-oo0A!F%mJ!uUVz4e53vohsNNrdCZme|QU^cjxX zePQg|3_BByOUZ@*FeSC8%IJSN=YiV~gAgL;kkwk9*T`a{-Aqc&5&FN6jZ;wKKLjOz zwCokz{BN^XHH?h^6vB?*SfdPhoz#z$9K_Qh84y{Vd6>z*jqU z&2O-yED_=#O0HFptMC6J|I%_Bo4Um`<^8BU1VAo^3R%lTLeJ*nBt86$_0%NgKuuY0 z5R%IOsOVPM=~R+evD=#AS0Q-cIYV%ZpX#*(7LLb2OR5h%PbAM>O~RPk3xY4y+k53t zf|hSEdE_N)2L5I`dFARNH{-rt)Y22Tt0KF7sFMAj z$cFI8Uw)pQJbrYM%=f=o(#fl%ATwE$%~GQfHnGNJE!O}}^|DW-K11zcSIaXRW0HH# zjga6xVSG|aV~xc3zj*3}x56>Y02JBG{Rqkbdx@Ow%~2tsN;E)x!=o?ypL%{d8%7*1 z<2TwPP9G*wuF>Le`8f

db1K&5wwlZ=NJ#HywY4cP<6^3jVT$=7(2}SbK#5U|DPa zKA+}2s!v$`$twcO4L8=*&$3}XA5l{oTSj?mfRQG`zZ|II6nMQ?n^t)cIW=D<-V*#R z6+Ey+WUMR=V;WIp^3(h!n)w192koc>f#!qj-~kuG7nj+C$1B zQY<3hPeD4P=5m*;Qu+mQ1nO@!=ioJv*}y9en3_s3L+lNB*NYrvQ7N$%Se6$jco>Bf z^6)wyUUZ1ccLhRh|JNI7dv=wmq%^M88EfF*)oY=6lT zL8yQ<5F(;|zg$cqk;vssUjfbmz3YseBH3X@O(YL3(SM=*%Fr_*KB1@1Oc2T#3f*9E z0I*_@%9J(>;Y+;RJi^ZJfB-}6dE!G4Yh^l5zr=zm1c*n3=u|G_y*cu%lmo*mf#p#K z9&ahAoaoq)5-&UAf+OQ|NF*P7oHV2nMDx4wP`KJE3u#?HnAhbAGb}chGQf`cQ1*pyPGrgg`h3mV+g!S=!%Tnw^&uZ4s zF*3FDnYG-N!%Qv>&&%_J@kmTEDB{;FGN9l>+aLACfAEBRmJIZP4D%Z}AxICTI^WpS zgfeJ8=BJA-Py3Jn>)}}P{hghF0FW{)3Xk*R-b`%Sh>FwXF&Q_u2sk>)zHH(tf}0!x zk&I(6m=hvZ{~`j+KYm_r8K@i6>24F{d3)z!Cd~t&p!vE5k_Hkeumf-U5F%s+&3^Nt z8z5@ldjg@K`hD#(hRk>nK162ooY+mw`m$Fc!=LD<#XzjO z;$&J{u7}3b8c5~;8q(2!fC&Kmc3XQM0`-aHOL|Ya zc`=kGWE71X6p8p#g2_Zzdc!)!d01ecpks#ocdu|2Mt+fFLP|VlovuY9LG1%Erm>96 z%7!TsscO13e!VWjk!E#~v1aPTrcJ7T)rzTzhR5Rw%RMteFZFsGs}Hef32RK4p;{*< zNx>fhd@(=fPS&3Wlx3KyrKexn&JqWZX?-WjpVL%-YP7nWx{W z4K{I831@dJdnf-Qhnkh~8gEjP%r|P4gy(U#JvT%=6}oh&9H*I-w&Hh~>4|ieXAzaT zY!bUudCzI;vEH#>y2REY5cVfgS%)oYaXWC9h}lUxwW+n{^4n@(;SCZ2b_xlDjP(@Aq7QLv!y{m!8Y_mc1D9e4r) zCPA;wJYbn!wNOjzp125ra(OiIgLWs^AJ(oo@^cKsA=VxR?CZzV$maPM^*7 zqy$4nL5lD?BoJpUt|;HaJtFm3R-(0?$nYS%uE&3AQWBg!KPG`u%9ge>MKVrwi+_@M zZ|eADVVx4qtie^Qqn6-V4lN2j^)0@jq|k(E=w>`|zlZ6HbM$hqFk3vI9(STloN@}I zOgL8FlGaAL2<_6HvLB8R!hQseDKX zpr{%mvBkm5-Fpx`{5B;YBpg?YVbNQVdGZLwW(G zk1`!y$1Mt}KaDAL*FndJ$6tADl`KG0Vu?h$$EYGT8$3E`8cXi+wqBd$WrvBRn(H88P$Kc8L_htj~nGz!mkO5 zZdJcDh)ekumNDs;@&&!?OC+tJ43rJ$PHY@^et;ZcqJSW%luj@kzoYfV)Q>0$P$tph z@g%EzM1Ie8&`FueYV9EP?mEY!JW51K8g8cFp`}Z$hnpcD;6G+3gvZ6}!cVpz3@t?IU&-Whu&wQ zkoGIVqK1_iprLKmLc^U5fK)8Gw9~>qe zBt1B2CSoCvz$FwScke+81vaatk~9o|Pe@2RAieua;R;dJ(=`Nn*rQESpH;_s4bm(t zuc*UH^e%#(90ou*Qi=nKR|oV4vovm!e9(-9W5f=!r#PM*P>`F_Hjvro=5WC;av(C@ z!%GrHb{18RkbaPIwnLk^s~$v8XYQFMfrL>2V6sK&82@h5D(?oYYYZk0wOzG}P2BdNzj3WsxAs*Rasi0mE`sPx4AJIK(&4~JeB#X2X65e5iNrjjS5htx zEh~~WRDt@|3aJZO@f|Ws3>v8j(F7J2XpO!@rUUAQ2#X&OBD{>q&uLQ0B_z~Kq7qC1 zegJc!4r8eaV=^E}jdx1uC6o!&3!030s zp;ct?gi~Qeb|SQ{o^LQxY!sl3DpiW|@G3kqK`bLK3rSIHCnPAwBlX$CgCG;_<64kF z;3N>5b5!nz#7$)g4AhPysCDy3Rzm1FA#=C4i3dcmLiTDTi!M{jB-L>Prp8%FyhvPf zdO0z;=?UXc6|9*bQGETW{USsrALzubtOE&%J7)Moms`0y z>K-bCV_zloVS|)payTRzNH`VZ#;XW}gaW&I(ivmASZJ9NR4$REdWv}j+7Ma z$!wa-pC+0cDlI7$AsXf2H*yPjQEEI~7p*w;IE26U^n|i1Bofy(RN@~sNP+Im;ic#gqO;&3FGfH-j8*jM6# zpa-@Bpiqe(&q-HyClZGu5BN#^zIT8Ukw_|)O5{>%fZ|BZK{R|}&%nN+=Rh-SBJVpC zj(QpR5@(}?r@#r!uD0ENCI;Z-kTAWUDZ50pQRyZA1XBWT70HJy! z@`t!x2tzc0a>kZz*6w7zy$+GnTIH6dBr543Q|D$)d{CZ>zax)7eL*hBx6?QTA%h6sAdxAHO>Ux$H>yGA+n>ko?AiOJ^6$H zOv+&LjGAX-M`uD1OqhorQd`e?H7YOY49H9Tuk<^vwgPeAbR}4eaop~%gq$CHM_Egd zW#KF&oEX-CyQ1I(-PT4B{e+U z6u}}qMa^sDg9xJ)pExqEYpG(%L%B1(bU#AyDTpI3LjE%C_eHn0T@Zz0B?FTO$+tLA z{g9eOp#hPm4k*-U&`9J+8bE^rC=d}OfkKkk;w*0ysnBYeQ8#V`_#7=9>cudDW=3w~ zkY>Xzid|SBT;I-1mAi5J(w_s%1@O@gwUnE!5#M z=q0Wd8UUozR2B4(oFa^LY$Y zimBNODnkm3;yI#JpiO6|G=ME7nWSodr8CYq4o)KBAW;`Lk<}vlk+?bh7h(|eugh9i_#GD*I zi&{V@1-uh*r1ag#p)BR=W{52WUHy1s+pxmawM+74vF!4w9u*GJF)BkhPLqg<-WQEb zSRuS!7Ed+Jbpd3+gj6}7*hlPCEF$-Ib{^;qc_CSgZxJ>rG24voPUyXG7OlU}QOZ#{ zc_7UcAB3_dZr~=;1zcq*^)~f~lF5;m0a+VGT8hV;hCWLwZMq3l-Ft?LQqmy@Qc=r!qH-|I|Dwy(4~wyQ>__6BBLxOEajNNAL2U z1aO=qQj}bCqoAYMl)?e|ld`d_xl{j17nd+fy=tT?I2WFnpHVyk6voo%R}o49W5Q7H zEpW%!FTjUrCHRA)RtjTiWYJ^?p{?5L7AX+IEAT}>nuoY4+w>*AB`bytgt(O7$fmOjA!2mzH10%GgeKoLql?;-mIF4x zq)CJmrHUR90(_T>$Xi8vx4Fb6-||#z0RyO`nd~~Hcmk4qD%nJBN_jIM0GD7|^=OA8 zql<(p$t3Kf)FOOk`jX0^q_s%1N?-5A80~c8M%Uv7!suC&-IA#`q}m@~m^ERWPDh!J z8YV2}=Mv*?aN5@1m3yfwOH!laN#>^<6omwtbXnz6PI!_~m0`xVsL@c85?Z)iDs?_M znAu64nv!%h$h6HU^Rv{y1lb}Q*asDp)>)!mf`voQ-qFw-IVilD(AgHi$n#Mwd?S3- zv_+;=HFnGq_6Zp&2iD%t2r8z$X z@Ge-(vWAiZPBhfrsET0N9MWLYGsG^_sp^&5pI9P2LQpxEtwVoEL!%5P*`#t-hL2TF z6Oa>G;d3OZuOf3kdFoD-d<$<#S&OqMpiAeVxC}ZLp(73=70-Kd#ZT42H1|!Rpjt8# zJW@>)R_b$TV*y;MI*QlDZ_!ERw`)T0=b?DKiQu||syt1GEQd)PR3^8Hkrd(5gN6}X zG+%IE)Ga98(FpY5?@*vl#J8pHEVgwfdc%bRT$#|>WTG-b$W?AOpuKSpZxYB%Mo=`) zTd4k~ZUe1hbf9Qr>04+q0_dX5&)wk4gRZM5R&s1`8#<9pgfaJy%6hOv$LA82xpzbp z7=yI=qTGg}6rdpUK;{h^~xQqn-atludNYly#fPRq`UIs+AGd|75`qE4u6oTob1lvfFhfw!nU zlIa8*OVxxL9c%rlJZ}k$D!7O_WDqX75yIcn@WTcR_)Q3v=~Nq>+8WRqboZ<1X6da6 zI+&U?Ytb!kaH5>v2~Qt7Tg)&2%uc%XYD(0RB);ko+XNNps71n ztHkgV&$)rVz@1>*(w8>;m=HM%qcWYlvBh<+Pco=%x0aP*Xet$1jWxQZbh(66i0eRt^uNOV<_zh9FD$cIT>Ds9v2qH zTMvRnV`~*W3Y4iS@a)L#jhK&Ud_rd9SN^D%2%Hp;CNO2mvV{TGiYEo|>YQzM zC^~}#J4E~qp(^z$!TV)2o?(B=REZ=tqkv`lC*xS;Tggb?7;%+heVScfkG7Mpp@2+ii0`$e}8JT%3(cXh~KP z;o8UChyf`-Pl(+k`mm>YWQEX$j8vv^)oPtAd8!j^;4fA=^ zi56A6!FeSS_1QEE7CpfY)aP1Ej}@KJxjUI4ly(of1(7>O7zs+p&`_V?T5xC_ z@2XA|J_bKRL{ni>6P@HbOvqF6qe(>xG*cA(1xKy+*;d~rFH_r&S$m>=+QG{{hRAfH zpqr1;;RMyj)6qWDBcr&dU?+Blp8$npB0!M%jmq7_)Zn+EQgfcf6BH0>6hlI$QrR{E zrMkXgb~bK4OXU<7wmX<0lN^9s<$zRQ0SFc{@rY`f5V@;&u#<^zA&!dO4Le*@A7W60 zN}z&2p<6d#Ch@H*3nY%D?xh@_c=<%$LclhWS<_7)y#~vdco~2&5>P6*R2&kGsi;6| zL-Q1*mzf``4}tqbBY~gnrJ!nrTjh@UxYrbJAW{JfPDpesix_GAi8xkWpqzl(XOfzk#6nnEZ9#lj@+SUij1jIJ z{lY?d97G*VXp}FPS*^ApWnt_q8ylX40vU*)s+~|q#o0 zin2x=uu$enbS+3`6Xj`d5cM>rn0TLJP?dI)1qc)gUfkE}JmE=bjj!mX1}~vdVHpk` ztY#Q{cu5pb2@n`G!kkmFT%XoXU*aLqBj!xV=n_~1bSA*h!b_@Z%F(cHTh01uR}%Al zW3}AMU*crhgwv$S#E6b1i@*NGGC^iu_xS&Net>FL`GE9iD}d643LVScg>`VkL^+TuU&$r zsWz3`dvO8Qa*3OO4b+~;rl48Hmw?M8h^Meaf{Y6=KUZvH)dmzZm5@-wBx0wb3sfUr z3}T|K(DW=Q+f$2w6*H$WH)AH(PJxQ0S51(|gfwd!C{kfIP^es!b7oQsGBX+=^-n2Zhrn^ug(?x0~);a0_WFRZ$u(R(kAkGxQDZ#E~hM zg01Kt(DTeYf(4;=QGdSwDjOuDIU&?y19d(a{X!iXXaJ#AYBWR*gn7(d2^nAfgEO?% zPT~b2_UMG6rt-r<=f3OZq||kXp#ko`%+TNiiLUZpj0aLmqoKHUYCJdzWS8`uS+mR= zE3j4y8lR%OfIp=V6^~4mhX>SLq~48n|HUy5s6E%3v6pbX&*=PdVmRJQY>2{6L#Uj=^YWgV;!^kP&h;8LQPsrTgtjl zr;^mt_$l{E{@Ma=g!?28X=a9c$RfO8`7H{dS5rDun3P^sd^B9%3KI@Jm=u>pD3&^a+_ zE+AOdtIkwJB+yGW+K4JtqfI30d5{f*4dVPjA`!*%US)xDX1(jZ;*})Uu<&4c6u%Yt zI?PdNZjy{85{p_A_n_#hsB4gVpdDR@a)*&qq|hGnB`M4Hhx)QousoogZHDTYfP)hU z-1@Ks;KcgWWEMMy=cIsuE*_YP^|?bPnbkyI-TY_^#fIY}APvS9@Et|vD4yiQS$I$- zV{u;v#s|-MxDY^Je97^EB|mT@dxuP_krOhvcrQ*@oTgTrYV&y<4x|TRK(){#{;IRH zbtW71v|4nr`Ch>QHnDh`NCLMtUV5-c10|^3A~Y(IBv;*7uVv;I>+#MNh=U>(bcGWYO|nt)=xo^GB-dV*6^;>)|mx1f4%$>R$V{minxpqE zXrw1@7NkH~mDy3vnw$Dk$;2pp2^X5@>u|V{)6wvtzTK7CJ5(;BD@vJ!!n%%@>`$p~ zkZTH*Itzee;kM#s{Xj^mH$phYjWXBZ&a#euMC4Yv)X)b3LXHWDZpp@| zfN9A@nWcQ%zEU|{Vx`{W0mc8IsUSRI>O}*Z22DWalBORh;!-*vvXUa8zsM-kDdlU1 z4ypufr{ULA%R8(D=sfWvwOVQrgGMHeR@xD?9Fr3PF(G6jj#8Tu=xBD-vaNGzN?Sk* z%~ezDN+E&ZLRbLB ztkg+d^RL5f`x0uwpLkk!ts+AGeMp9Y+tnj33sdrxP=A3ofDj{80Ac zL*>75@+6z-^ZD1QEvfdC{vg)N)gJ1h6FD{7G{&U`PUTN7541lFZ5+}TA1Vij%h??s zKA*m1WX8U?H4Xw4n~14V*)WTXMz$@F@DYp zA5=){50wII^QCNidY@WjrB;$Ika?7?B3c!hNk4mMyC|fUCi^w5(T4GwnVH&8fEm*= z;qnI&7H#@rIRrYD{DdoDBc{jig#HaaRQ^#=f2+1s^Efj(JrLQ_b0o5|fPT1&gNN(d z$Sl9YRpub6b74!o)MJPfV@gb1`9p$eFcCoJs8nfXNUp`$56c#PYL%7hzI!3E`B2Ui z{p)4GRl}hB9~$q=++-$jVp+L`9jrwahvbKfM)U!ad!~<e3gZXr`JbO(W(^^M@$&(f=W`r`sEq=8%fcZLP5qxWdHb)PW864^UT-d_8uC z)6RzjmK8{KU^x_YvL~NVSzVSYp+Qdnx}GO;`dXh8N#h^%lGZtqC2lddbD;DtCRCD_ zkpu%E!I2bzFLqm_!W#NyFcm~bBHqbd9#sU9K!P-OA1<#n0$8>|!v*mFw)U5tkt&uz zgo2){G8vpPGI{r7_md&BbnECd1EuAeJ|L#~cW9^pIb={2q{0rAeV$JG#A7-yu+y2q zdYfx>)>oF1FB+k#u8dgzRs5U|wi%s)6=RkHsGWMtVsdf!F-V{# zdt?+EG|7jX&>5?fs67&E01L@M5VOO$Esa=dC0jv*JPZghce3?d8?s*|wD4xZ0G)6%7H8eU0B&v(7&+fnMq!;LZ-53 z^*sn`NyoCW>9b%WvwdcgX0!Bxd0g$)1E%;YZqmsclj$-`dk1R|SQDwzhJs)l;VC=C z^fm$;8Ia#g%p~Ii@28cnq+UfeX>2jD1Q?T@BwW+0VjyDVl~@m4Z;zRM7EHKl7nVc4 z{(U_!vb6BWyfk;h;5lm}aF_&S8}h~(P%ytU8hfm?&y%3PN?=KY#zdOH8a-?;PNx7p zzY8Czmn#BWGmU+8+m|YZAl`Ttl^Fjqm2+0!BeK#zrb)_mRg&^TR!*nfjYwxexoTpv z-6Cxa7z?awmYXpp&&+AA<)aw(cM*T_6k{#5No znf-VbnILx;MAmswVlazju99h97JTpD%+Bf30+U+j!8T88JSg6LEVUN4G7VSQS%=Hu z++W2`BFZs4O=>MXCltt{R>$8!2GdU`WY%dL>lpHv>J*R5dl8jNFve6mGwZMwEcp{u z*69pMWsamQT7DffHO#s~<^>iMyD?#AT^^uzR8p-vlid>brvo6?)lIyn$*fgDfZ&wF zS=s6uoppUo3oo;H)|DX!;$9WBlVnUhic4+H1j4d>IAZp_o>OFb%+9kL`c+*sgX3v3HCuJPa%uH&^8Ss?s&-yvdBV;5!b;>sGjXryzmS)DLU@75 zx*K%Hfnqm|N^@w<(<^Zi39Ka1ABZex93X{FqD=TB>aul0`j%BD4m3DR|y7 znFbf3eNqf<4aCtH$7>Q!b?C-)y42Pv4?>0Qa1|s3gwLgn^W@I{E{0B5dmEw71qNR7 zeRsJqVQ38`BD(%9l3T%!^yKKPILh?(n4>PaV4JW-?0oy?WZ<*PIp~E^qsEys)x!*U zI^8*?A&we1-afXi7SWR^4D#vW9^i5$^RJ?mX2qCNXQ}Z4!iqnzIJm;u>%gvvTmca zj*8N!DkH8{vqer#=Qn%&Y={duWa42q={>T6r>+W}HRP}yZbE1O%3O3`$I$5t{)Wyo zE|`lcby%a+LWa0Biy2r+ky+|KW()J5W+_%~tfiajO{X)A9eBIUQww!V{c1*O6$N5z zw@=k^RuPZql@!k~Ce(TAY}lrwJqj$Rn-SW-w7-j`jGHY{dcuY}sxO_T8KHHSrnMGX zIxMc=?A_C{%fZKly6jp#0OUo91gp{lIsCM=5PIOqxblh$bG#KMlFek9{--Hr6VsT| zMtF@6OlanF^p7`T>e;pZO-!XfzC!95BYGIb8KHGqtkn3ekRr_r_CIfq*fKdLvyok` zI^Gb9tRTzhuwrhha2cJ4n8B)?nvl<*s;jwR8ec`IU=-Jq@1$5=CUnncWF8%9T`*-8 z_jYAnLkyx@L$PNR)4H$sB@uI za1E1jouf6z24G;hv_q;Q zP(v^N-7MAQ))J*PezDB1nBuZh=o+ClY~> zjG=W{09ZULL5-Vacq0Auc{+KeY)q${T=SM2o#t7$!%gX|on;9YTr^5l_yRiDDkwIL z!Q(cCp>?dpgx@v6t>YhNAUm?b?CYx-%4;-ZhBks*hwj+He7HIX;T_UkZkTb@QH=R^ zENx@{{$-R>fErWUh;E;_ zq72!L$#lu3F)NRd=5KjbDT`ZO_F+-SH7Cj&Yx`I*n{5-NRw>gvAFrt_u)%NQTU>A< zbcZr-VL|_Jclg;AjHlW8J6(6)P-!g4YG^3A{TYoJm34^^#%69-CDdIoUO?vzj?##2 z)ovg@$Y(R4952A8AJ6EtdVayUT1A{xqcmZjHA8H>nRu3lp$fLk9)N8(=gH}2l=eAV z*NTBI zHPair)Yi6xX>Ze*(8eI~9MQJ#iXGv@(-}(-l%8;sNr8c zlUgEx38e;ZWLafIdwuC}O7CzK4vi^oMYqB>g4T_Fx(4av0j~07)|gJmHWsXoee1#F zY(){CCzX-+F{zF4*5F3HuaWpr<23a=S5BkHv^qd+Pp#Q6C| z&iZ(4(dq>bM?I~im)j|?=G5TUT|k`B8#6t;>pM}@R($Jaid0hqk!r9xy)PJ?9&^+! zFF9F!sfGu#CcPW-u4^e9uV*NYMsy8#Nwa%!xG|Zv;O^`+!2oI06WeueQcGQ{q<}-I z+zYX?$h3HYeRaJQ<|wr`3W3Qv$_4*akIXyVWF_5LI~$?3U>6@BWL5znPX?Ezkz;Op zsEeS-m+Gil8^d~J-r*+8^2TH~LR*J_%JGheW9`lr-LzOiu>AN^9V)zS@4dSTy2H)u z8&gx+rjF-XewEp2NI42;SLkeVwB(HIA+Sm?o~LuVG_{dht1sX_#RSW`S^jm2O0O;? zV`hoydw&w`4l_Sz=!`~Y>$9=SFA-T6QFxmD8kL@!WnP+8@HAjgHE)smLp$VS7YYT59)SU8z?ME3f+)MRGsVzriR=xmOSqb}ItW`|6} zyyZ7Utn94{V^1~juyeXE)uq-EjCy`O2(7zGTOVP^|1IKQZ9+`L8$*b=x zQfp`9QT4&uCRBPWDRc8gFkEWyaP#`Q)R5YSn^|h>cHV;*elJO_?Kol2T8cBQ3Azc! z^K?$vr8ZJ)Fom3lS@)i)$_|-_z}@=eT7VfcTVp0aUe$PbXMfwI%;&*@o$U`>hzEz8 z2<-_o`-1T_H}&Mil5%#rX~@Ka&^0Ll}{h4aeoCB`8+3iaCM23cDBL*+dFwJ&~wOQ`A}CRoX9(zyuKNS^(Q;VeV8k*OW>g+@(xHmEG-$v< zCe(XT!3}rGqRdG-&n>KIg;_{yCBCuU;ooEyN)T)rqtnin^d+Kn*|SX{?T~Jj$$# zMgCAt+N)JA0M)aa8Ji!+(kmVA~f^upKlRIQ;In;s`IyszGbFT8U#wN1X zC#k0aB9#FjUCJG63&>?D{c>=kUhWDeSgG}zwROSBdfv#z%OZsL>9*8HYOSpPpobP@ z))ja*lXkqyQEF{dVUF8*s0<)fdHt!FGtyx-<29l;+QjDpiGCeCdjpP+B-qz0cn#83EGQPbGj?lW!851J>GK}+S{-N zFg|f9-q+)Os4N)uOM6r_UPLGFU#v*2AC5Q5ud?$P3AtpTJjs|5*lrKdkS zlhj%dIT7j2W_Hx2v(30^O?Q&8OlG}vsNdDR;W&A2a^g5$Y7J`^4>bl43{=veIXWaM zjzrXTr%xFSCj)NG*4}cQataFpf*(#p^g7&4hMH)wYCIEKBUFlPynxWPIte-F{va!_ z!m)BFD6Ozs`^LSAQx<&Fi?`aGfEYg<0-bYSzCM}C5(eevjD+Y3m&Trmlr+TnPD^d6x{@c@UD-Bb3IY^jeCJ+`tTTxMnI^hqpncfe^JbHGQZyxjcFHDi_K#s~2tV z`Qd7m;T1y^UoyGC`sPU44N)(?y=92j7N$A~F-xpt45wBoh&&OB+N*R?!*^&z>L%{f z1lD7|9~RbyoYg2k-gfUqL#@CzL2|AMebuPP$E$XGyz_?l)qG6k_}LyH+x1fq5xQVK ztJlVtEI{}uB?P~&SBWd1U(w1Y=4R(yu+p-zDe54IG*l`NC1#nZqxUkFWd`<6xW_|y zlRAmXt6>j6s7eKmmME6Q!tAT1DEb}GI5T*`%Lio?B13Ud5e+PccKQ7R@l&MyTM7TcXdIRM^0L?MGw)&m(*6=N+jKQ;7&Cfk(=nG zi))QM1j?A*xS{vTlB|im8uBpTmX&DBE}Q2$sZ91-1{R#Old*K>J||5kN*%g;Sx)4Q zw!+8tEvO>Wx(c7PxD%09hVHiFkK$?~!Q-9jONMmpi|dV|!N+s~s)?%s%d(qv&|ZmC zOjz4kz#AvUffy_f3-hAb^@F+I1!?V{&HF>w7-=H$0X>qF{%yIm-r?i*#it>y)}Z6z z(tNgh8)EU`V@_JrFn`ASeEmJ?cNB8E^VCGu0A=qPOX^^~QZOD--E``*N+`0u)La~-V|IR~t=hP(3dDy^NuJgrPW{f_4LWKbF2{Q>Q`8~gOoYYHAdEZ7au9oaZT-;)>|abiXJYmwG&Hz%^g7* z92f=x?j|yn#!+jE3_AVFI~4M|>C;R!5O%LVcd$8K8vA$kyqsQNVH$STBASd?Il2BZ zA8Tp&^PS|uag1e@`~@`5Fd;6ewnvXsh;Yxhu8FEe-x-zZNlgg}ox~ei2cWW*)XK4h zg^hLS$=~S3a%~XMWQxgd_3!F=8n5px6~{bL%t>GW`b|;~;i@N!83^JjWf{_N8t+(~ z?->xpMAfijkKBHB9Nup?0%-YYOBKJnQ>u90j#a%Qt3NY%goSc_J~}|KXI48T?&}nJ zCNZTiCztg+BdGx|xDJBP{oUSAUXqmrJ3O%5zYFWf<7b1ZhtyjQjtMjg71yamu;G$al4XR`9_n>NoT-kc`wa~JjATcYtSiZ^6Nr1Ud77mD@i4< z-agLuqR#*$^2o^=E?7ju`pjk3*wdz!@OV=1aA`FdM#h6Sc)Kp}^+2QTN@OXdF3>P& zjM#Tq7Trk|NXCj`}hAD9^OB-fi3?g z;NauyG6-UHx;_HStww~_6`>At+99ts(2U6X81~!&LhuaB#F1?LjDN6yIM>(>tnGA$ zwAFMP7NTG(%!|GZc>mCv#i0di$n2iY;-NA|F(%T7h^lE3yzk40Vjk1|luqTz;p!Zv zgg#>`n=HA2unY|GvU#;HT2w2%JUN^J1D^sTN|C3R#e*$XNA1( z_*DYkRElYJ}+oWPSV? zWiGhxYHhC`j0M*B8GIzPfL-Bx*&yQ|x-Pez8}3g_})bF&ERVdUtZT1DWQ2 zayi{R72UE|Q90dy=gh3ps2{&&`DR`9IXT;bNDC#fSjq`3A*a{hO{4E<=J(|WUJ5Gf z7!0$2{ctUr9v9}~mWPnrCgJBbbGj6+VWy?PxrBP@a0fE0WbXYp+iS~L_BG$nllgnO z%ayoUPga$=vP*|Ml38bMIis{MRm=FFrt^EcEp5b3swzSKwc{Nr{rLEO{E}GzGBQ+( zJtiC5lNrww`gXY&)KSmU1iyT^D$q0a+@JHX+~@aI@0QTznDv7ihF0bO55c>FdNY!5 zqtjJ{TKyAUOrJ8RvcEp{JVQS&w@VU3>pZD?>8$oE!{gPIn)fVejYSFD<8aRtI^DVD z9JN>o0C!@;<-^rvTK1N|W7!!xl`gm5>T@R&`X)_ZiG)0^)ypn%4h#9d`loBnkVUrJ z%aRr&Z?CI9&rIUWB|6C)X|=rn@E#H4bY;fp%IOYtdj6Kx(=xQzJzET-^>WEQIA;{? zZ-Lk3fAu#@9_X|bu5`RSNh@n;pXcXvOOq?73FxD|%xcoSKcDWWYw0|>F)KxUy{xte zkmHGZP|{AbOd4g}YzF{>{6~wjDihSdFHh3gT)%zjp*i~ab0dWRneHxfW}0gQd7VyC z`H3!rms5RxkKaIVkx?gQ+T_+oURHRSd3AAYHpyVvVUEcqjei7 zcc`3h^l?sFT=(a@O#b>9?q$x`aaGuE&Ii zP7~Yx##}uMI{bMuwITajwN_-Bf&6$Bp{h(R<*@S8GgCXdFSE4(9A6}~- z!q0pPbDM*vKvK=Yb=7{8C8w_<^5=3zI*6>(r0?>!qXj^JHU=9jLz{LYPj1UHvjU)g zUS6k*Ld?us1j?9wE*M)h%VzOz9l6m|C`ld~b8E9|Uf-CV1sjONsW1^mOhs;K1 z&17lGMEuJ23tOa;6)Y=M*0%nW#3l}BZj`d`6>eH*?Wf4>mHWD*nbRE%CbL#oeUt#e z6AcEzJG^XsN!?icoCRzk_pTTqPuofeaQVU(shqAT zFlN>PHLqgy8YrIwxa4kSzbwcvbBNckYmrK=$G#rP+A-eBzNnh^eN&n{y2kui_C<{t z9ha;)@%@ExcYrd#(;RB@c%*QtSkS*MixgN~P>M^(>}JXI5T;zNJWE_X0NWO8Slm~_m?0}I#@VjR zlbfD5y2Z)Q%Rp$+XtDG*#b2iprL!=k@Z_qj=hDSG-6C;18*RdB>BxIt;pTLg_+?0= zB_rwx9%ZEXPXEq&T=((k>oWd1xM(t&0WHpx{?Qu4>LQuvj!b&@`QztloX!m!8{N8; zx#8Lnot>>EvOE86(6>^5c%H_e%h+e}(WVrOSv4C;*{L5l`!YUOH<>Ul-EiU-kxOOfCU8r(!o!x6v$aH8VVcNU zx8*Tjfjd1dtfX-(Wu7_)-$$aZoUNtN@{cmxRyST4pM2Fs)W@5iRK1>mc-lahB=OR_ zHYJy|!7rP|jFj5HH5rNWZ>1Ln*1{cXELStF(eY|N@41#AuO4@gZ@C!cMY_i40;%y2 z-J&8x351+=D z8uMHpJE+=8LJe6XHJ5p&u6V^~Z#dEHLg0m0ZqmrTCB`Ujzv-q|Q4Ef;>%4zX$e%;Cg z+>(*_hi<7R+X+{w?4HfCt}c-WR(cv!h_tk;G(cZKlY4pq|#(OhqIo0oxFK}M_}1lvSfVBJn#a1 z-Y8|t+CScbP*3Cton(I8xNW0H&d;RcYtDqn#+K}lwQs(2w0GrnM>^dB9rK)R_QE-|5bwfeYx_SDXq6h6g=9c^L1#wJ{|Nhei2A zb$s1tAKP^#3Fyzy2BrFx%QG)JG8 z>(oK0B~hQn*_%x7lTy9oRg{{X?w4k{+cqlI`_>|rU$ZjFsHtOA%HQ}~#sTUCWy;!EMLxVq`+iaRuT?dA; z;%5K8EOqPG!frX2pUar&WaR5ukC)yHjNhv0l(tSiLPe+rd;6VPWT@oo^jnK^%SOBv z^|Sz<45W~1jgbN+Hi`IWhn7D%~$=pH{mE|;x!IJ1@bhcXgencaPM%1(D6^W?(J z?iPWuFWsZ_`t$ap(_9~&#R9VP+-;CUCJh~3nWt_83%)3~)A#K$RsZpS{Xc9X4MHtV z*_K0FShP)0_1LfzdUj{lgnOBH`CNPT-9l3wcXDzT=9U!(6Dm(GtPXOw5vty&7TGy{ z^WE6#`O}tE*$CAob9-`MmbGnVnx|_hpKH&cd+t<%Sv&GRL)GKKF0_`>O@^p?Us~km z^dWTTW-V0jW%kXokH;p`sC6F?~qe*y%A@f0Amel1&J;IB`5m6TiqJyGn&K4bpP#cZ=wcD9z0{oArkr@Z}c-?=BP(&Eqs+x zDmzzvRCc%nk(Qd2XPE22@3Y_byd$jC@mI`_B_<#F z=|qp?d)3;OL=RZEyE05)N$%{fZZYy}@on2WJ9^JZ6C?cAqp#ev?3a_?P2z6xar&^W zDWr8MwWs3R(ON!w;!TLC&zQ1nb5W-deT&48%Z2E06jrc!Q2V)fxC4=OGQy;0`i>KY!BvhkKOL5q|-VS~79H&h8#R5A0ny+kwWa zy2*mH^mJbn8kA)21w>9?MKwlx4OmtU&RMW`|3EH z6ePXyH2YzHE(nUti}1NM(U{l3sG!!vy})L8k2{;+0;-3aff6)~46$MEBZKAFq< z25`XY%<@R2@!&}3k2cxRTl#$iHHquGYrty)$_r?dNPq#- znkX=(KXkX=zJDHHY)Hrfr+!GEmkC-543sONl%=#7r0vg_Qy8Biguvx}0UXW))am04 z1$@6fz=%hn$73uHo@b;>#sBjA`LRmkC+krr9`eC1gNkq0N#q&6uLsTnx<7teCh9X> z2fP8|O~W_W;`!+(PU)B33oN`#B!2PUAsc{MnhrGd?R}NR$J=y6PCVSRI}V-g@r!HY z{&~zIB}V!o01Q20^FwJSoXNM5_}$29+|)HLRwVMgqrS5ws1I6WGcG=yi%26f1k8eB zT1kxf+4~>yi$>YEOoIezvh}oyODz`$pfeA>Y4mkI&CPJYbZ5jG03J-#*DrKB$94QUZ~%7tQ!p*!Q6w?@Q83 z<}u5Z8A_~(eE<6W!E%1Rf3Sa)C^e^l{8X~~`yl+J6ByDuB$Ds2E0n(-4nYr#1(EUj z-Rq=jxNlGp%D;oaO zL?ByC_CG(rtCC7AHk-Q8f3MUL$HjCOEFzeMM=9la!;K@R49?-$us#t1)SjDP(%JR^ z_2YvAz%Q2QgG7vXY)TzY@1L?Y?;SAT+h$jZykvvE@J#P)G+8Hdy1?=c?W(C{5%$j; z20<_E;2{zhdBKO*2(*au=T9z~I*sqG&0)vDhoU4bDRthGabn7_RM?0gD16iNtXbwO zUM|zfHBM#_ZbzqejM>C-9;udHz=u%vA8&sVh3WBdUY+9#X|?_HA8-2Bl3o2qz9#wc z8<((4E7{W99)p*qqwp0@B6+N@=hi5;C0FoP8y!x&2`r~aK=6l(0UoSq{o?dF5_rd1 z5QcxTQkVZw_HYo`Zsv=s%kR2keoVKNk4VLths-XM8a7$Cw#ni)QsK9TQpByjfYRv$ z#aAdbK8XAdPpQFGJSEy8xcOC42q*FR5j++Bc4^@jyr-~Kv1-zure zYZ_CDD~|H}&)MB@#D6YgJt* z)GiGVu+G!zVs8e5T1q#QDea0wH#{vilfVZr`2O`t4~w9pvPqZyOj$hpw4b3WK8fNz z=Y)HhO;T&#x_tZ2TmOvC-HbS$Y{lFt{r|zueClzlVbiO_(oOY9w8LP!@D?|7PUygl zpIn;Rqg$Z^Ir}6O+$kNL?+U5A?CwfxYVf!E(}&&(95!j3XA_Y)`OHi7)XyF*~(AK9Oju8)^xr_@cx`^_VgLyjJq{L;Unk zrIhLu)t}VD{Q7yXn+M$h{9QGUs*=F(P{aDe=Saa-2My}^y!xXQ4WlR8`_diWeN)(; zP-$s4HA%|erGb$fB=$4r*|8v~k5lEpSOBp8Q?kAI)m;oIAFStLl*A{-loZ|t(zd>& zQr;zjtX^mDywOoto&R#oDii((C95tH*im>x6i8XhbF7q*R8;@`i)VPLZGMwVvmNcb%CM=PP&@hh`241E@b+gpK>zu} z{~3!V|9OvEPiPgHKUDiU!H??g#SBuLW@R0PcKQL7d8VX>M`T|imEAAu?UbU+bRI>o zH_E^)LU~Ky<6BGh5zaNkFz;E{30sqMqcVqOe zuIk_Tz`9~--XFj8n$)I9l7q<56vMzh*t!eHmuaOUGjoYn3+k}7Lo1!lWFo2X9S(Sl z+W1F$celn`BxOSGsu1f;IjHRj-k8>d5a$hh>eTGo@Vi`aSK(=5Zl@9)f_*SdA&N&! zGA5I{B`F$+(Qm~5=MQE}b;~5dZsfputxGUP;jvw!@;^3A9FW)zqxAN8kg~qh%i1dn zw7EW1F=d4muUmhsuRI|)u8#d!sQd@f)bAIi{v0xV{(RE2VeXE9jY|9teZ{ChORdiL zN!Ce^KrI4l=Y+*c!9IBK8CvBbzCNhcUL*FCLhwh>1c$Lg`C~Mj=|9ke0O-V>u5*?O z|KC7s>L$^)t4{ZGk*y7-`BR-+TQf^EGA6!tD#Irt9K1H6`)CrAGmrDfBse1(Kw?$e zpw}Olxr!)EOt7}nO#_Kfy1KNoXeC5*sI2oMal#c6=zJ0ofK8YRa9j`_N(Kl3IzH%h zmZ^kK7A*?}fGsAVQ2TU|sSJgW#rGbeapJ?-#y06dCBb7v5VQpM3qw)Ywe%f$-k8jI zl_@batV}0{i1W1^)ei|+>5$Vbm;+xq6l%)W&|-_HNgNVe zJqAvR{+hl5otw}))7LP-wHuU!2(Hrke-}`Nasolzg?v??YSR2d=+n*ydp8M`#Pp%E z2Bkkggyz%^9#lQw6I|`w0LL|)g-I7I@Euo!Q=JgH&QU6R9iM-(*5Y-WRLd~Yz_u(q zQ~`TmucH}gv|K(rswiPZ+*n83*A!HEoiU*^cJ^&$2(yLcZEL$Hw`$O>xKm6bS`tN`HcU{C#L6f?9_L0!==tP}9 zU(I9=&QyeY{&yog{pKiRN@pxhPSXl|ijm@U$EarFOG6SYsn2k2i?%4fE(8Cl2FxP- zX@Nzj)0%67c)CnX8BxRxLhlv`1YoUztZ@os@OOi?Zab|Bcp|e|7rZXTd%OJ(bltbXj z3bpY+vm>wnu8Jzo#p+XZoN|Bay)T>9-<9ZpFE^Sfo6cl&pn|}sbFxI88Dq2kA(=|N zwXPXsH%@9_4J&=-0!pW}QN!NGlxNt!}Zan^AVsFlRSN zn+2&mY3B#(ljf)U+RJz$aP9>v(i$D?N#}BU^-H(vs&Fo`uyeY^hAKuqr8HOSUAi$d z>s*{d5jQRtCho32+l3XXQYGmdB1mEzoWD(~=)CC?K(1B|TZ9XmjF zAreG^>_Dw^n2aa0}+_yOqK>KR@>uGHsgkLZeGmo zLhaq9W$S_7nqU$)OgOd$o;prHI@@Wn!1HTw(iKup?%^Nre}QTG`K7kVd>_rnKR>r( zO%N3m+i{he^AjcQ8WPm=;grs+n4D7cvSCyNIF2x{ie0Ed??9F1I2XM1+jUI({`)O` zT$DVfcE;pvyh^V4H03$VQz~jsgOI<8RntP*J_VA9V=o`rAlwcTOh_NqW}uP4M4765 zXAe0zoKz@ly@0zluu0$S`=G(iIt=EB!%0y21MUX62OK0w(o!Vrd})z|>=GEWuptxr z$UtajBFfkjGE>)=Qu#}YA z1w+#U!!qHWzJsXzKy-|V!_QPP>wIX9m+VWJI5j7dtW%=&hi(tUy6_<%?w1-r%%nev zJf{$)bGF@xVhJfxfbLi9VEHV*r{rTuy&5N+7K8 z<-bUN`ui+a(ws94WEuhLdlcSbA{D763fZLteiVQo8=&;0riAVj`wx{+FImmY`i49t zN@15Pd?&W~<^RTKSfRkhu|g7)%7)c0i8q)Cx_QOeU>*=73;|`k$0yUe>1+%yXtfpi zMJz?y!7_9iI0~R?+8QEn&;L(+h75yWr<5!F91pMNCQIk8)~wAB&5Z>%YHaFPi-8Dr z@TfTtq6tXpmYg3ojeSXRB&rL%EjQg6sAi^x_C zPD5l-89N<2+ENapY zizwJ$^C}vr^^8HtN(z{cVZmlu_&u^c0#fWTD=nw|ojUf#^uCJ7`P_~%(lQSQ2h%w) zB$hKoTsl%oOFZzgK@BNemB5roM>}`5<|)}ya@p>LSX!bStMl^lEWw2_Lo(B+>P(q@ zG3)m+>3)qP(Js!b#wY$oxF56AnAZpMP+6*k*e9$b#N)uTWI25YF()#o5lmP>L|6F9 z#2Ek#4bqY5yv+EJeJ@c7;OU2vHv&*1Y3=!lGgGP|I@c;mJm17w#xIZ>{L+r)!3MG! zve0~6kf+6O+O5mz&J&G;v47l}hJ z$SlwgkP874rnz0_$Vk`t|Dh5F)SpZ`TQ{e2Il_ZV^12mXLK$9zm3G>B77I9oc7_HC zZi(#x>=QHQrIUWTaC3VVEBZ~$Mrd~(^p?OJa5WP9@y2phR{9p}>tDJHD@QL2B-`rQKep#Lh^@5PxuH?Jd1OQK3^uZdbs#v zTo8<7y$i1us91p)hb2J}BU|jJ2B`=zNa8l9k|A~;iRJIhKhX$FQ6U!u08o_&vT&wK zdzyKNm-AVx&1VLYOhGAyWJ4RAQ&k`c!eD4&2e3)#raX0lN?@CeQ)$XxD+*HGl{Ew4 zbBGfV`*)P1N91yZhhk2Lj~eqsD9-L)LRBiv2wG5s$sz0HKOkY+C~$$q2ZohRCVYr7 z4Z)Zrf+u6u+!^l|uuc0lv5)Hg*GtR6NAs2%ZPekgNR^k%>yyt51?fYzyX0b$xVCOL z{_4|~hsxQK3M+MYXv{#>s!Cqb(m zB^AX?sChV6W6$YqJY@;_&E--id=Wpf`)kI>TqVI-I)}M9yuy`e-F;;#ADPo7R_M`r z!&|;jCyPejlDbSj2+nhNbkyN4@Y5V7`>Yd1=6SUiF@(tN>>WDkC#~owFF;hibsAbp zt?;~cPaFp|HA0m1tL8dcSou=hrtc7XLqD;Smkp85PXBFhJCkN^6^*K2%#zeGo%+yQ z-FGG^E+48J*n64q=$lq*Bg9z5Y*+aiEUJ5!dbTre+q;dRU5DI^|5!II6;5Xxw>LjY z@w)YbJG`X3GbYmUe+_gkDWL=7awnM_g#dT|vz48LoaQ@O2fH6aF?Uql`f4{U1)a1p zjieY=MV4(4j9>st#8dK8R}N+MU<0O1-~l~3azQQ0NcBz#WfW{QZS}-Sep-Eq^{_=E zo+47UhY67_BUP2${-k)$xiWy`?4^PRw_6qg95|V{uE!g;f0Hb25u8OIZn_O@%*)U} zXMuPbr|Wotoz8}t#aJ6NPrkISmQ*lizGTayWio6>r@EMlpdJF5;i!>b4!*R@OX;fV zQ_ryzZJM}}jm}_EbG(SRLx09p0lh;1G{?$}BMNzPJui|`pm7t&F(L}kOHg!!c?U9) zjYR4TI5q7QY(yO-QZbf(c!Q*d;kj|^A1d9DR}eY#6h>ro-zkFev*oJtsdyglibAdK z>Sb)BrZ)C{V~WnFNftIe^{K~DVfPw`1oJWJpV4| zM-OS@NTey`gFVim}LF{sSK&^d}k?j0(3d;wblVQ^>ok+4Cv8F(_4EfNCVbKbV1Cmgf@@6 zcTTp!ukRr=R&)R-ncx|lvgR>L$qd(`Mi zvM;(PrFVEZg$SCI8t{aAamW`5S5>B=i#TVZ)q8lFFStnA84zz+Qfzi9A$P87&C*~P zC-nVD{w(MaVEFMJL7lfz zikDTQv}t*XNcxEyr@=>{kF@^dY;1C1ZHAy22rK8F^U?53^j5Q3HXzdXi+ZY9jaeaT zlhrWcHfI9_Is6&5(`wEJ(#J%`hpY;V|H)EsMc5JyJ}<7*iSS)q)9LEUE^Ye6ONx_> z38-z3V+7lJflMC31A)XIc63jD;;fWag&640i@I@?{U}?Gp$_K%>8sLGCoW;s3NxDe zs>dpg6tBaAy-0&z)^l9wX4cDgj_V~+0Hu#va%D1$DWx>P3MLR8Joy?Npg3Nka{$=S zS*g~14Sz}8=e9^YGW>;Yz%ODYFQ-ha;2SG-t1YG`5oAqAo{>o2bI3~w(yIaVf7Iau z+8Q@Q?-D}klmkTqH*(TlUGLrieVzgy8af%t-yu>Nx56ss00uJmr*_p9GLZ?Q2@T%y zGDeO9tq)C!xNBtB0|FevY~!d2EWrv7YjfqC4T&pA>$-z~5jIyfXhHO(pvT&(4A8u& z-$=SJMVT8X+pcfYOB@N}MXj3u`3)HCf?g6t=%p%_`4OnUrDyHQU6697@{nO3)95!F z?{Jb_=clFg-) z!c;4g3ig)&x$&`WDOH}59-{Ud5O%Th`MWG$wbu9s8F`+SM59a63KWp3I!q4Zs9L)s zB8gilb+GPEfdVgN1zS2ttB552W!{&`GKL_TJ40o{L)D-(0C+EAB@M#~kuI-}0n43X z!+<4AG$zqNA-Iva6+?0eKKUA9r6d3e!_}!Std28DibM*?d>&OR#sC?^y}(ALpn~br zjU{x@(l047GAq0%f*^YYYhOeo^_3+WDdYUe?lXRkE+rU4?4={20cXWS=Gu;=6Hgea zC_pc}5SuHuk6$rpAwle`h@2v>2cpW=r(>9u2`_Yk$Qtb{7a2@*p=WIEMXa1YZ_y-M z#!9_080Rn^T!VLhSG;8FL#jHuP*Cf96`5M5aa$`hh{n~40?7s2<9f+Dcnd zY2H#e-5}}ccVEO$iu+51TI2(oKC{7K^!cTdv8A=pr#vC=F%+{BJ$~K@)JaDsWV+Z| z%B6>h;FPv6gH%(Y#q(GB$QJ5Y zVso-^=SGnL@4T3G+2~EFdRtCN=zYO+5=ZRGCBKoanPsUPQnn-hYpK_K>#qrIQ`jo- zBP&ULq|)U$2=daFc2$LVT8)eezOHWGVJ9X36%*uOf5N_eym~C|+SEW>^a(Ppc*H#GZ&Q8N_e=J^d&0>g1YD?V0VnrbU?zSR(Pa+ zRoAzonK<7q0JcH7OT1S%BVGlke`l9HWL!(aWInC7uC+p$$hst6wm)?YN0m)mah-bQ z3I_6ycCv8pDxo2vj)JFHkSVQt92b|>S+j)dXHo$@Bwn>$`moU(aw{Cin9xmb#ZYV0 zvN|tQ*|b-Oo-;mEqwDlN{yMwy7$Pl%3~9x z?^q9$w+_;GtQY#V#YWFsT2Ky4L|QW%X)mm-y2xxFoRpqLW!;U|RB$#xbz7U>+N&H2 zkA_UhGh69AyAt`ST?~+CNTU(@~ZbV z$3)ih+U`TjS8c#mVTY#jYWPZ1A_-}&@wqYeHziUwXM_3b`Hmp+02hw0 zJ11{gSKf`B5LruWV_h=@&5R;FlsO-3<4Vsnc^tFRG!$ONMoipTA1!WGFMT&UY=cbH z)W$;Pizyeu9PEolRb19@nCVj0sKdlNlFFW|6%rfokt)mYwb7UO&PY5u5B-MuAib#l zDjL~aG^Wu7m6Y#8cAYK_j~pinvsIZCudmTqF9gjl$UnqVsxFmx)RDEiV=7%(dvmV1 zOF{zH9%*qGK=TVrBq_Tor7{QM$Ls27On8m6&!{EKz?|j)gy7 z2#A6Ix?9?8b7g)rbGjXWfPGe$OXAx=yJ@pr{@ zz=#$+2+WZJ!z$LdDGy3#voH*an|jHn4wf_jw=4ClJ2q#!M5$KDrs|}Tf?&X*>NI7f zm#77TP9LflC6qhtiTzso@n8Y@MY9vfXgY5>{jg>Y=%g_#(}x_3YjAwfw6cMk+J8`t8MI01btC?Er6+JV{IxCl*aW~q`rYMjUoR|%AV z#qt<@gC}iLNzQCP%Xu%TWD6V+@68o$J%i^J@^e-fFkxjRz$VP1^wG3TFHNeM3t>JX z6x+bxaz!sv$mx4%8;!c@y3eMUT7!*?b87!DbAOU0z0RcTp>t9Do_~ec?izR62-8J;Z+|-JDvH~d~9|G zkzyFu*8aMZ7QW(4gPd5^r>_``FK-I_?Pqsg6HWV!ykwowMh>kE*Rl*#pj|2?4UqUr zZAeu8#?`Sj1lvbp)b}jGMtOTGj5rM=+Xn`|6=dY_sAv0cfw5dx*x-Jfos?YhZZ#$<2nyRpV9VPQA}dVlo7z*gQprFC<=^xm9-y46fH3uM z8^LVn98x|tvQ9#26s|z#xxJwVf0-PZW*J`q)Fjb78zUAr zP#J)f%gV)+Os62=lRs?Vh}P;AV2*-Uk{Dndk~J?=xlZ{qiJjY%>v*YLph;}o=!|bt zQN((Xe+Xz;EU}Y6Tc=Bhn`Y4PE)hixA!@MzLOnb_jZz>TnR^vV<#_CA3HIK!%#DzW z{LTxBHg4?#P=~cH3zxQ$YAW#v?dp}K;h-B=b^(~E#6Im-7+uSd04UO^X!%^?Igmyx zCQVo7oPkscUcotU-%^e~X~cVKW0*knRMhm_2d3H`nQoi9rAW14#{a!%M@bXF8=3Ly zk1->|e`2&QWrJ8=Xu}lp=T*6xw7UCG7P0;rQHdyz7D6}**L@gdo`8$}I~gec{W3Sg zxz8JLML@U{_D(II$25X$(Ndq^tRS>FT6EhxBz#iLY5g?FAPl@7WPHmVK9}a(Hu%qwaGDx9R2ZShkFd$H? zYaKyRijAzypW8gWvJ!hYn1(ey9HG;AxRznQ4Q6v1($ZVN`0lW z!L~Emhf)oj+=rl+4JJVlv=_iRUg(116ZtX-Pd#2LqHmvW8_xJ9Z#yjQW*e631(1@+ z=&O{1(QrOB;TQuQbz76*2B0bn7=MPppmtI!y}tm`VaA|9+GfyrI-7k_KGDzI26WA# z#E%M`E~paY1{c6N94)1a)1s^P`9||97HBUIL;O7TuNPI&(kaVV!h7<#h~=q&5!dAn zrRmH8!+J)2TBOYHSED0wtDmL{P{{YAZ7}RtoSsS6flLWieVCfo$x3pxg2~#SWhaH{llbU_Xm4n`A$%asf1;Dc%@dvHXnrt1b1q)5}OU@-85QjWmft@D?5%uY+Fj_ zNt7w81565(YOgZyJsnPBj>*Vu*d;Euqi>=tu)L`VnN+ZR0hmKkx_}vOTaduSM3=cM zk}-Qo1DaLJU;#}Fp^$EPd*qQSc5N$!qoLVf@*vw!sp|D_qK#tOjC&5}nH+<$@=!inc-{tQ{WNgLn-a(6 zL-oltjPzm*0w3aZV1ByIj{@tY2xKgkRsPP!g4I9|f% ztwXe)8LBA`T|RH4uELC~ulz#*$5o(Sp0X}Usy9v2x1NnK$ZH%1qnfw($iqu8I9~lG zT-XAp_3Q!wQ?}qV6EdD-p!Sss$ppAWMAX*!w(Ex@82OIN=f$v(y+|GgB%YO}RQ^qQ zjq3N=tT&@m@%z%lN|#kyk*|1)Omy0MSiR?fPGsKt$bme9$7s5X!d?NH2V(~+h?Y21 z=_EBly;=45x)0rpdBzLCD8sCjLoG#u>})+W@;(V8%SC2_87)DwdKMA3R$NX!w4kx~ zcv`&*jpOM^ipE+u8{^f_c7WLW%I14ks&uM5nQI#r87bp&Hb*xhaAQZ4XD2{(?@5E& z&J!xaeMG3lDG9($)2f07 z@Bww+7*J5mY!(M&4=mQRjUY$Ngs6l5q(Wf$Ua?MWO>rP%rmeWz42lQR^Tx~OB#Z65 z?4ytkHXbk*t5EHeKlkX(b8K2!$|o6)_Pa55Y%UIUDvHC^kHh`g;wdPCX^;0WE0t(~ zjgqSVyR$fC#n{Mt(ZmcpUz9BE9Q3lJe%0#7brqcZF-q@~a>3#2<(@Kux?eU92=AK0 zO+f z1#ot7&QS2x{mgM6>6pF9d;Et?zhQv^5|(wo{n!7Xh+rFe+du_`?59X3yq*Tr#(j2U zO$+WChhwi-2Tna*q^#ml?B%?xi1a<`yjcK!{fFOWp!k>CAxzl6dk3G5(|K-e+}Wmx ziND(*_({TLUDr;Gu4Tox)M)_fG5YyWSen5=H7guOm~m&RQfDQUuL6{z!+k(iKWdUG zsf@OGt!wqv$kCtjN9-OczjdB)o~*0C`kl5?8PGf`GZs&nF;fh6%z6i^*4ufk4mMTA9@)fpP)fsQtUjcI){zgL{ zIvt{~nzjSyz+@xk0G*4Gx-D5Zz}&J??L`WtyRXWe<9DZRH#+$TQH`T8Ei!Wr!Zx0w zYLLr#PnVc7*LD=d=+NWT;c9O}Q8jv1gSICrk}(r~6}Vt8>TlsZcf7Tyzo0LoWS^JR zK;QfvJnDl-rZIvtk7^aFnB{0y8gPx1CI6 z^VrKLxv>>pu6`ww;QDdfo|y*BPSoeP8ZZw-D&n~dv;@%-Il0;o8W$>+u3w_5Euv5# zmv@~dO}1$d6oZ;*N=n<58StY7_V+Roe~?&>p&hZ#w`6`^!**|lG{w(ciHH5?|EK8z zDO^GdOCzvQ{?FQ3!yQelJxutid`pV+3eoZBcR`Y3i|g+mut7ebzhP!Y%;XeXQ3T{@ zr#`(`Oe9>fV4wmcan?KnKEo*{N=X}l?4YE73&(f3U*NZ7MgpyVJ|qj6bNzgUgk;`8 zMo9X{Gk(ejcm9zkaWFaHakCy4b}z8Oqe=tuL+9DhCmXo|+FoA8?xH9%|9;F=bg!C6 z+3z>fz+F%=RDyXcr@N;K*|fxYK;Jbj+Ukk$b-AZErdFCZa2C2RftZ0~wj_eWEu)v* z-N!+ttU|mo%~V-0LQca{JFrU^pPGce{ZZ>SowsHbx^sF80jw>tL8nUh0z#csvKB?V#w#p~Yuw z0x5{hlv>f)x1z#UDY#+Q?W#a2`k&HxF#8ZA99}y+BWb$-gv0 zU$~KDFNj+&9dS;g-olHIUdS3Cc~Q) zOwW@CKpXj`8qO0M&G&8$HM_I8CX2pxY zlD1sHEZQL2!J>XHq*FZ9K`^h_YTY$)*t3$&eS&NNjeQ zXeaMaubSgW>Q4tUrz8*poOZm$Ahtqn6CrYr|5w7vpptwK)HvCZs!CFwJITbTt4nhW*vU%e}83v_t*uF;hbHs{MFd$ZHI(k^N1GDRte~^ZJ z11yWA0|5go6*)^Zsq`Ujf>^yLhuXLvwxFTODQ5by0C*lob~DYQ(LgYwD#8(eD!_%6 z<51^Zj11TEl@E@LJyZ(#rST+!yB}VF52N@cgSTu_Mh^R%f|%I>WL)H?M0i=VUK6m?;2xBHL64I)3Yc07d5!sL-m?HpUpE*+-GDBUFbOb}I3^sW zvFsVcbV_oyaQtX^BX5#bqjh{Ss+q5EOO~%Yw2ujV{FAqZ*HB9mR$7xFbw-oGO<(X^%ae z;3Nt>Rbo)Bsd7Ork|-k2)3;5}iDYn$F1gy>7Ux=&B36k$^+Wm>-L0+W@?YM*^V9v{aL_uM(6*vo$gu}2#?LFri z3=uRS#4&@($-XHOC^DoEV!~K;SFbb*U16M8a9>ul4Ond)b`TwqEke>$8#*9kaV11l z8|3Yxx6|4H3vLFDO#!F(@07t>RXN9Q#e0FipKqpvgxo(yFQNUbsP#Sad5UAV#z9KR zdX_A96!lR|_Q(pI2+$%o4WPD4&>IUYb|QDLZ){GvGmYdFIyv!8P>>tOl+r%6NhZk5 z_K&|W!iZO~rH%XQCL)SAv_?QgC7T?{-9F!M3)@*dut8>3vZV!~>QS)}3IqSm2Rvz^ zKzQ~>y@+gGF{NQqw3v8BiyCi{>heQFVxUQR(PF(c+^acCCDJ}Ju@|SdiN@98viG2J zKN^oixg!KYmv$tG^H2`GKnT)>t{-;_J#yuPHOdDlSxAZJzI;+_uu&!9z_d3l%L=GH zNhwsE{PGx|Km38S5ein7jhx+*HZx=jm=I^Il+d%K5w%rvuujw~m_&er31=5prY*(V zl+!?B^$#pmCTBWaici5tR6ChPh!z&ZCyx#~O+r2mQGzgbR}!kQNSl#_Mw-$xqX40M z`>bn7YwSqwC>mQ3(rbjNoN1MYIRjfC^8c!i47tw$SN)5T0pinXa46Lnh!`S78Dn;< zdeseHMX?C4e)Lr2+PJWZ72O$-!OIigfu5w+otU@pNUMVY9> zY=`@Jb;z*=QngHJxxo1x(vQsZz^K__yvf=21?Bawas{ruh@fetZ=Z0BIgBZFNHS`u z4*PhF^y`wGOTs{+@;qH5vS6o|s&1vc=YS-TJwT)gP`!U>HIkF0w{q%dGaVo9MW{7f zHcIwBAMfsCTIi6v8@KnfT&q`Oo1q9s^SyWCZQB~^u;7CE0`E!PT* zi&9GI<|crHEQ{bUNgR96@@{hP*T__cu?!S_QGKzg&9&~6JSQg4xrexx)5J+g1Kji+3zI@FlhlSRZqv@tS>ux_Pks6>k+ujK;~Ly2 z5jC-F_mDm80fRi928~4^1HRjZGzFp!S{T6Uc+VB?88E5m;3CMZJ7iSDR3pu?1V~CY zW=2=|cUm;%Oc;AynPqLbl1V0bo2Nyr!ks~b!d8)N2TF%PgL{Z_t^x> zllJ+MgfIB8Gafm3_+E|1z(-d>fqOVGjtjqRLa~QiT$CZaXC*5GSjsJ2aO3I2=yS&6 zU_}Qab3kN^zze5aNhy2!-wWn_9?Z!Z){tb7*s6=52LrZJGNp;5gFXGuqOMc{&U4!2 z*y=u5au_G-0$6>uD_@8R&h zq%~>$=zZs@DN3!>KFk9%o-i%ZI4VXdTqToC_>HEPSbv4wB*;$B!TbHX6Sgs?;Uo?x ztFJ{_=DVju|1`ji2#Yq<1R?27>~eQe)sz&qV>K&#Dr zXoidI)^nKAWUQ@E-RVTT24Zq3v~MkOSi*D;)biNkmY0BPLy|^nN>F%bwAfOOPiaXS zX=ek+7IT`qu6(*KsMWg&r39GtaSk8TO?=}|Ky>zZ?z0}q^G2j|K&%2N1~^ekQo^Wm z>*Jub`6KxP8)u09cr8R{5lEsVl&GkJ=~=nI)DX=VN$dV8F4w)UTy!2uu!eK=CV? zEKlR=H}X3Qt^y~>@#rs$VnvX})LKDSlnS->2v7eRvZzYh%UR(dsIkH#?_VmTYY@{) zzsZHr;GN{mzhW-x69?fK4gU&YpVR>J*9k+y5B6=WwEw;*cP9xZWtMQ?sBxWG|O-Cu`f=@bTN>ZtQ;e zB)?_!4*S)4?2$f0YjvZAqSf>isYg&BCh+bwOL;k7oXjAa{yTwWF6D?s#mZE8MnHP! zO$k-slhV3>`m}vpp>uT3K6x|Bdj^xrMJ+zW;>Zfw!x;7&IXhZkglZ4?)u;JY6;T`j zllHz5!HR#U=lE{|^8(#LspJSwp;?=;QLqH>MH7anjtNs0@M7Vo*sxNqy{UZ1))6LK z!v6v0c!tNcBEM7ngnv}BzD61(K`jym)IC@d^{N{lqKQrayDv-247%KH)E~Qs9 zCFI4N4Ek?{@;+R{vv^F#Ib;)1=rnUM#}0orco8gppx@_4=$cOA7e226t}b2-eiayb z&6moe4?zK905Q|ZR0O7YGJ%}ANVa;Cu*@|9Cx+&a#E-&AvlxLgjz+ij9n%tcCGAazn+-nZQ<>f}@#_xmIz)4tLC=4@JO9K#L3k}+ej`ZEK#}&ZNtF4pzUD-lgeXHWO%cjovPG{>M zbjI{IYbF^pAn&2V_d^rKUB1R;=tlPmrq}7)-HD<+eCTP|kPLn0lY>F(u{4q55hi*#rT%<|{G@2g& znFf3?ULvwt4`V;nG;`r#CK@iH^Ks{XkhhQ{Rx87}j&T{#%u%3TY|MP=%@PFM0g>KI zL{Q^i=J7MEqZfLUTO_h%C#SmK-F6&&GO!-+a&((hY3~sjkJ1|oXo7zP6?D7XF&xU? zxXxqb2*)wMD7|H2Ocsw^Cm(Qz`tYf4)|)oNXMNK<=&!n`$Wql!*_-F-k3P0OJW79F zwIB~d&RBI&8oRDh^vXsQ@lB<9kTWXhZ8GRZG94*2LzAkZqBo|RjNw*^DvSG#n66UF zYM-#AGoW4!naIG?NF#VKM}*$4V60DMcTuaUs=bS~>S7YRibeG%hjJCxhDFChnGB&V zrZ@9S0*0Pqq%*%078!^}@dX&>kl*9HhUkdSV-3YR!D?c`TT`hWUY)BQvM~&zSR6PE z-Sigc>JcbDA~`6MnIgjKViyFhE*1oJY>VnzVu{XEJ)i*OJbsw6F@qloL_jIwW+h^= z$6eOANOG5-5+|VZ_&Tm)QQQoW5>g`G5`grvC&m+GVc5f(k8t6$MKY97*riYoD~(l4 zS4c=irAXKVrQB9#Hi;dD8l8(IBhT=Xp`;vQMghwCT&SDK`J9^e1oS237DfIP9Y%=cV&YpW zG6ZMy_!;(MEcoH|npsJXuI5hCVAxHg!`>ot9U&L6Biid_1vFR5bpj_lb+jE$5-Zjc z$3to$edc6fDB4?`HAAdFhG*0aA**Dsp2rx0)jl{y8QV$xWpk9s3ZjeYQ{fjohP=H- zuO*h=XdVaW?J}H^quMJ8?QrO;l2);~_B>SE9$gq=+_0*`TYOT5OhkH%x9u+sjWR`a zf-J?{w}IE;aBY8V8$|KyY}b|DljbRo#YKtDP7$S~Q^;#I4ic=MzH*jy3hOo^!X$fh zodeCniV2dGXoaonwX;yx( z1n#Xz;37kWSpEz>R`;CfQ4aTvOxGt!y{CX0AL?F^K8-K(>J!ALxS_(0tJZKnjbiq& z3ymTt#S=A+gI#qQ#*hj7Dbn96qxXY45|$$+nE>1hbQ}3OPGU%L(8odwpOgZe#~0>b z9~!Y7tE-L(^I25p6pgK_>QZ95*^?xB-s?0NBb8@JQnLLq_##>je{D>Wq9KUm1j3fY z&coW@t`Z`{(p9gc)#8ZcC#DHAB6pCa&$0k+G-kYQV)Kik-FcE^pU4bJ>RofK#xQb_ z9sXx^DKUCl;r+TQ50WPnB-u={csrMJu(6b^Z2D9kC@CGHjhE3RV{|9Pq&jBr$S~@{ zrLN$vCg3&BGo#$YXrW4HM6-LED!-JRO;DxYHuLkh4gx$K!LM1D7$p_AFQa}Qp8JgJ zqQQNN(SswTvUWX`Zm!0BB@A&@eBn@#>K1{JDlWHB02R5P$E_- zj3wa~nxKy*1F`C-2+)Ufuo;3Z){{^vYCw(va%H*Sh%$-$+~Z`Xc>=_F?lY8ETB|I| zDggQ^sfZp!NggG)TKLc~yCIJ0Ei9iIdebyY?0T>Yw~{GIf#E)WG-_;aq@mPDn14w- z%wy;~<(pKAlr*uRb&@_r62Z4w zkWG&gD|QAT326o~E}TY|?4ZrdHuD)O^t#GA`~uU9aAzn)kYasS6KxgeK#0ntTjnx# z{Cm!%T-4ye9yGD$Z3XfSiKO~e=+z)y_35g-2BQ)@xUBP3NaAmX3gsvXqSir1ICBaa z{@cd=JU~`Dv9B^4Y^crtOsYq$ZHi|1ND8sqDb9`{`2^03wh@yb^B}RxegY&(p3wOe zl&SZTzBWI{G;CMA`}7HI1`!~!+aJ_}90Lg1*9S;NpFc`&M)ba8K1d%RDgH`(6xW!( zNGCHcZpJsML@>=`0d1Agk28xRLQxqnIZWyYcvY* zNN|m|MY#4F$Dh{2DZiyUUT(AZDZ9LjvnM_(+{eXqihD}859ly!37eroP2MH7EZKtZ zYflW@ap}A|*1$qD=Zrg|IU-tdBK2sJE}8UQQ&4jk`Cfe5fxTphEJ2!D zr~DB;i3woHLi1kfBwelS(jag6&o@q=uqInNr}>3K_ANwP2+u% zj!>G2llrDb`)z;6y`jfbzU6LsR;A^3C}d$nEWq@Zr8Du3ReeZCFbs9ZEUeCv{3}mT zBr9WoIwaW9RElLfDI-Xdk>=S&lAYNLGZZL2Im|?eXOnzUEHfIwsEIop`e4YHMB$;3 zA!|%$yc4ki?x=-$4sR#x`Qw%k-WiQsMVkvFuMeM9k|0=v?8aLn7X`7S#>{%{P*U*`ym=PQP)B);lFBmDVJ zkviq8SVb@|C?@;ql~mp-3aWMei)q*cNl3SOGZ!`_GGk)5cVc)G+k@7;hB1};$+wkO ze2*WIV>64xQ)$_L9kb~zkTF4t5|`m1$rKlJH`ZMAA=1E%rAGrqV(uPvxiENl3qSj# zaufpT(Zdy6_4x$t{AwSj3fsv$WPP!}!8;}jZPK`h3TJJT6lT3IGj*v-CP;U9yhJLLTNpTR38@=LclW8TvsFNxB ztfDwE`Le$8Asbc{5T&Qyjpey6W5fMT`QgIV1C7k1!5gN;?x0WUa?fs3U0o^1u)Nf51RZq z=!9+Yzthc3BZ++#GwzMnsKg0WQq4j|*bbwzD))}xkYX0bZ(qh+wsLO5(XI+h0(N`} z3VkPw=+9nX=160?ISy=+W1Or9ikAS1~(dhY+bJ zRoOKv^D?IPkf^5xb52PsIY#HSy74rIv~NY$yc$9Bb93J2KwX8n{jK-wgIN1WBwRt~ zs8nZ-Bn;>LB3I{URpM8HxxXntoK8d>;l%%E9 z+esVh2S}2UM_HCg&YGgKLr5BS;@@sJxBK$;Wq=QZ17B1(J;;egH9%9rk1?4a>bE|$ zBBg3yN>+fCLOgzEpSNu?F3Vi>RV;6bh~ize&*V>1Gs~O6fNh$eM%{h! zMq8^w0aLMwyT3Xc3pS#>>|m3lR~HuFV*~tc9zJ6j0W6{NJd7+l+6$wBqesic*+#%Z zXA=|~_7waBFo~=7!DOt5L**ZyN%(|+VO$2-sm@{DMqobvk(+Dji-pWGkNtFA)@^x{ zMeLXI!Os&N#V5W#zMZbtz~J!@hlNyAa~kQR80iR{eg|YYf&H~`v=o~ogL#WUM&4rI zLJz#<9TAd9mdF(<|Lo0?2jV-dh&X(1vjT_6`Y88}hD(qIrXykaV6;3{xwbqyF%T=A z0hMXBFLqM|HQcwY89Dc+$(~9rmfqS9-|%X7{7{fW`KVPzXS3zBuz5l!fY95UNnF8! zNam1PG&eRO@xLsxiZ{<_6I^QBj=?@5)?|#GBH94_RYloJ$`{Rp#KDfhI}CuI2a&3* z0f+^Qh??s9<0kHtZxg_kIJH>)AEr~e3vL`eo>rf7_C4&rHeGY}XF`~!Fbsr z$$EouHcZ*D4={^^9q~W5G`WikhAS<56h%C36BC;hZDO?j!3(Gq$vyzlYkliDDtFH& zzXLcltSf;35{Im=8v*F8x9ViEGG-EmkrINrnUEf9y(%1Dgh4oI5YjER4@NR1Sbh}6 zz4#s;T$}-d^!XIq5wjMD`3-sc>ussn6S6Q9U>0`fpfWd zu7ysF8W#YgcVv66i!;R>JGbWkgD8%#Qol0Qs-A(6tnXeF23X`=j4V%HKowNVSHHkm z(`poyLJy1%XkAy*mkvgw`UAuYPYmK0g(ug?OGjVn9Nlvsr`!nNW` za(+P|foEdXKUTJ&KU0WpK(fN#W~|zaxG+ci{7NML^H2_F8&PsnJdL)5WjsoO(u)0e zFs33it@5pmqs*5L@}KgjkY}Ub=t8r0+bpi2d4>TwR@RxvDAM`+W8v%FoQ3B%`6BFV zwE1z1&sfBdy~j%E-;@i`HOFY+xY^2jWKnB3s<*95J|~CI`i$%r99gUi;}2(nswrH1 z_6lNHMtWr#-xuc-pntfq*%a#n`K68q_xEdAEa*JifEL~PaEGkIvFX}LR-XqFOSo^+ z6(ED~5e&RzYH1RY;XO(bam2^J!sLqzsVN{8137f+QTZHVGC-*`5gYey9z;PUzDx?C zoW>=&>_P0&TRpgo5R;9g{1HpVP!HBQj1-om5>Y1H5rtx8$zs8%Wv7TtbLE60aK@tm zy8yzG`D)qxCG3die%t0=7SFIT^e=|4**wGSDa1cMBm~DcqDYS&v4f*Vki!Pa6UvEm zvdxfQE^3)ua~?qAmwiet0NSw|CsX*W2RsPiE%3ry{5`#i#Mztw5r8ba?gO|WFrM2h zj!!JJmZK4E8euSiSW$blCjJ$f61M0A877Lh=``(Yq&`F<0rO~#5w50kY;p9Q0RYzz zK&%Lrf?dYR6LY+g{6pjf8e=Y)nPCs6X|dlimq2bRM?)kVrm4P#`FJ6UHd=F3K-+&4 z?|`Rap{wK#@uq=9eJlYFJKXJoV5dNw`noqpN-lsUBgLv{j03D4Y}Vv5b-}C{I~lqU zgcvRx@|rP8c;y#~Rchl0V45Wq$u)8%VI`Y+Nwo@=cs53C?Rzj>s9|9h+75~(QcD>1 z_s529LiCV9_zvw{jr+n%JeLF@d|^TUUL09zmZ7z8#=p>J^ts`3B!`df_O|uOmYI_b zz_Rd4vSqh6ZY;(eEdpOIEY&ky048OzeK1wTs*M6TCjCLm?S{=x)b7C@coEw&1Pn%k zE{?@hzrhxpXmUo6J4MdQ<}1Vex}lCbonJVk5bd%hKe^^CI>)oTyO9btM?1 zt;4SIDFM5};y0Ov|3Nq7#Sf? z>Ky(NTu5e>N^R| zz(%fX`Q%yU!KPmT4LPtm1U`v`4&cOwEv9&tMQ+16B+Uk#skd|k&hrShgyLR64M!HM zDWAMdS)Y!ys5m(A3z?l!U6IuWG?VgmSP~{7p8>^ZTPm8d?3;P zRwywC2UuhQR)Mk#M}@e5^(@tvcEcKGEI2l_wZ71Q^F`!1$a5^8+jNoYdpwhvEO7x* zBTKPsMuVw2SR9S4QrB2`(3n{>Bst$GLI2D0H_Tre#o{ z!Z0{ArT?df%m=rIYe=8Okwgl}Svj3rWazxgXA{&Y_*Os*VqedcYD^|!vloR+!ePpv z08oT215EDmDln#%&-M5q~7;?gQ3Mof7qI#Huq`b%ZoAX`-HB2KZT9lq0EtI(% zamN2zpv_g8b|7(zs^5#&clB`jGDW=QbDIvo;I)lJO9PtaF9w%y^JvbPftHWLc-mdC zRX?K;(-L}FFBlHaT|nnjp9 ziKk-ais3+XWy9FmOB@1MbXmw*Dx9Bhym*pJNPA24CL_3p-(D8rScv>UsNqYEz`)ch z7Gw}${%pDG$YNu-O0O^RX#Sl>0xNdtF}-8k)As@b-!>eQ^J7camvIqTvqLOA$$=?5 z8x5=rf|&7gcm^+IT#U>r)61}1F9I79$3ujxl+4K%VK{%Oit0qRXT z6~NgB$rW@`=UK>wBOQtNE>M=(W`_S zkWh9;$r01H(!34S7tx*j@5?xZ&pW^CGz&4`YXFjxn~fT#;EvIY6sO-ZGZ6Q-55d3( zm3hmaD@Sj18FBp2i_{kSc=_J*^|;?rVn|3@F&({~QmLeN2eelKrH2coC(0+7Eo;(i znmckAl#`s`q1Uimrs5&47>|WOpapng`=H_RoXREN;^_8@-pEzK@aEO$dAAh%V2GLx zM2O2uDhn9rP-CU7UB|CxA%C`%E2s|FvI`L8wgcBXC0Ov9P7meM^#WfZ&COc63MSKN zU6?9z6ZVdF7(J2hY)oogOFEha2uni})G)qtdFx7;TqEhQc?bTvfMm8b76uxJ$RSmn z;bIXG*1-wFaUCfrSqpEzMmq~2QC&&UIpTw+o*ym;V4Cvc2L($|?VP_rewlOj!kEfH z1_!E~z5r}x07)Sbled(*;vI&<+ZAdkP(dmZQKBN6qNez*HTV~y29e!|Nja!GTv8_h zO0MgV{w9D;n+`-Mu*HQXs0?Sarb-;Ihz9rx8;KTP+ITJB>7?5!u|SK)04Sw5dNHhs zhW>UN0g%pyw~CwhW#+JL?X1PM^_ihQ4IbuYCWv7(#~D`pK9i#2~Hp%DgXm^4@A z1G5l`gI6rxlgBK1tsB!_47=+WOJY}cqa7m8}j}c>Cf#fNZ;7{b6 z)lDo|nwARRVRyQ!9ARV*6ys+YrH-xQ(kf9o1g9LUBrPgDMJq)7BmjhV81JqOuB-WX2EeW_;ovy}> znrF7_JATiba%r^5d7y|r41f}PQ||tzd0~~A85`XNQ>tyUajkkOkMuYl4q?>PfcOL^ z8rNLlgD$CX-$WC9kYvq5He;>0sFu`ta;bkYsXY2~5nKzUE8gcIHkpHv)i zJlG6~_t{es@dflo)}k*Ml!@xYrAw~PRg;t>h9Hp4{|Qp@F8Vk6cv6{aG@>7u$g z%n=|B0I!Ly3hE~395=!RfYSinLjv2H1P8<>JX4=1Kq1bM*ZePz`HemG~sgMpNs?;nqO;pncAlAQyZ{?u5jqkZk0mE^u%* z;UQu;iE=~~RE|RUmKPv-ShWZO5|)Oo^LSyD=)k@%EVMovvpfUQNKOcAhTmLl1N)Zn zUG53644O*`UF0$RPz(d1Q1~aD&F5?ADovDDooxk?qq7H7N*nY^bo44D4d+yOq7x&5 z>dtryHFg*-RY9aC63g`xMBdi1PVS4y&L-FH4EP$7B+HT8_ziI-jS>eQda|o7BIQ{u z_U*DLmnkC(f~M%sOE_XS>ALH)RanxCVCH)Kn%F&rfeV&qO;X}wyW>@c7_WRDR9q%7 zyb>`!sKHR+Qm!&TUU zV*A(;2GXOYPT|$jDuLkn>qA;7-h$*x^2FEE5d(H64DciD!$xeEDNM>-xZ}mP9sTQu@*=WuSA@fLf|U^BvunOJcZ<@^$s)G24q&j z;L06iJxaO4Nd9gKPKR8k}NsUS>Es%pyuu8Dg;Opjn$`HVW+x` zynNK}P#g!Xcp8^DazK5y6-;s$v?@fClN1UCZdHrVF-`L^&uSn4bGV8{ zqJ$Oo!>%0RoA4#6FNhwq1f{9PbZ)>j_uGz!J`9Cz!g+jj`JKe_`am8T_B9E!=hh`3 zk+)5B0k0P@&9FwlFpZr}BHuQTE%5H@a5YGh17Lbh{F;wS6U0p~JMDB@A3z^Xo@F%S zpL$v)1x@eOD#gaPTz^@L!%L`*c3@|0PSYBbwg$9T0pY5jmu#gknzrLqXsO~MDH0&{ zqsFz1c%BDhnB1rs#%BS!^zfH`GSk*BR6sCl*fq#S7!-Z1c`Y!UvM(7_K0u0cizN41 z2om9OsZ6Sewf@0)O!BlTl^|_y^yoOOoP%h%wob@Q68o9Vl#Lr=*=MJ6lvgrY;Tje) zI|UF!(>d{8KT};Pf+F0%IxLKFUs0U6ZE2Z}^fKqYn#WWn1KtOwvT}_#SQzXUVep2R zF+j~V;^bHa#2^>ThBAN0H`Bb2$3H-X@`{)!*66xE(Awpffdr{ON^Bq-s_0byInrWZ z#8J{>N>1Q@@7FM^Y8`D>7bmfpkfbTwi{u%W{D9Jg`_%ziAaX8OI9p9>5+Fz=b(Jl5 zBKaJL-}Lda%`bUYou_=;{YB6+U3cPgS$dZz%Vq zB(Dg8comCeo)iKAGMtwt1g7o=v7#Cb>V+B#Q$$DdycGH`E=|GBJQ!%)K7|PwQaTn} z?!+{Nk5;i*H7J3|U>7^a<}93nVVJj2E)gpv)-LFA*70OD#ZvdA7NgxS>QtfGa#&`s zJmPJ!(5YhgD>a$c%*jKjBR1&s-)f7Q;}X8*EI20jIy3)-egPu>+60w}SdDR4@hxe% zZNTGQpt-_~c|5Jo^9~Rgv>v*T%#se4+c%z?j2n{dB-vFbP!nb^& z;IT|4nXfnlu~cYHFpD@Y z7$X{i1sq8vQ~Vo#LDJ8(N?%4+)?VIqy@W?3`}m9%vU)Tco@<;KK(3@NUV~5EvhY3a zT|O_uNQn#(Bzz+IM_SA5?3ztwP{Ilzsj0KcG2vT&3V|Qgb&BuV|2lw22u|wUn4ug_ zCOzydd8&9uD^k)|TthNbzFg>X+7Pow*glDQ2&yW#a9An#!6sg_jDQ`b!rFQ}&h-z* z{r5poE|JDxM!~YpL-2JNUa>BXzZakCM)?6Lzxxmm&q<-q60GX z010U@CMw7-4G%|5d3c1C7{8Ui=z)a9|M& zyXfsk|4~e`7=jgscl`>uLFllSdCE&)7Emh02C=;jn4;XF?>` z-2*}SMXr`iKqQnZ!(XwB1dAEA7{8<${;Lc!+m_acN7=>4igDV5HG;3=+V`Wl68iEn zCdzi!cfcO$i`f6e<@MnaZqbt^a3oBIy;`HkNBs~Ek;m#gxJH_Nm^`=>9Q%Vl6-T@w zM!Kr>zFL^^TP}G?y=X?NE6YyhedndwXE@Nl@J~3K&q)%xqwfMZC1>}p;z{d^cr*1e zd`;7rJ_vKls$pL208535!s)co@D`JjR%cjd@KCQIRtswoNGZu>r1nMM?BpFgndDibpFf617$<6@m33#R3yd?350aGwYq>DX z`f_7UPM1~eOP;}EAwN&GsF|6!7m4TZumHYr%KC6t)NhCDF^YXl*~{vG?OVP=NciLw z?~{+1p|a{|F(V`u#tcWX<1PxcAuuvTau2@PdY;mT!|NB$kL2u!#l-6sBeUv&iQjRB zm?o-o7celOGWn|w)G1Q4)O!Qjggtn1G(QA2(L5zkReb;Tiar_>{d zA)|y!kkqow_(|P#UOGv^AYT9lJ&1<$Ju2|zLV^F6nB#L zzYHSEaAwF%kH#8?2#}NjRFVGxk<b7dhjHX&5-S zOnJZN)v(0)mfKQri{TlK$&!69ymLy^(3}mo_wxRD2uSg`UfdX);Jlj}lG0=TVao!j zz7_GYet7%O^G-eUi=R+XMb_r^U;pFwnH3H;^KAf>NVv-MZP~uT%@K1z3pP>*jG*>$ zRgnBa>Cqq;Q;7zxsR+h?ML<;*c9fAmFJPq$pj&D-UZftcp}Pm`NCzmYMS~tLp3P*S zEo!svz;&Ba1j$GEQaDFigV+FjkwZYdXB0gXs*|Jz_Hl&BWjDgnR^nTVIHK*UB9e{K z7vbnb3bijA_)|$T*ln}@fE|F$B4pb+vBZ1K<3Es@A0A-bG4eilQInsgf$x_;ci}A@ z3j{cl>GSwde-b6&AA=J?`dg4-Rr;}vH*CIfOm7SDN-Q2 zkAOmWgzIJvH&ew~fynAdR*dJd`W&nSsJ@C6TX+>4-s$LOj3;Xt*>;)e^E8~HFSaY{ z5efxN0?RCe&DUxp4h+TikZ!s3!M=^O2E^c7kXU^mK8^QOy*8Icu%p-(=h}*5`^*dd z-*DKGhYq=B!;<2+^{xO&_|CasR#^)~`#Jq(@-13P|Apt1&jijpo zUN6cP%d6(;ltj&d9R+{ZLLEPlsS!`a)SLFuo1OS=|473`304!ShgK=Xx6k{xKxvF! zzbYb~`@6lvABl!M_Hlek{HwQFMnt2IY- zC2!E&+ei%HF%lx&0O>WWrih^k<8s^2%)lvx4Fl;D`R1DnC}B@CvnjVQ)t^5e11$PVpUMEx z*Tmam>mWSI$bOa$qac#vIFHIFZ|lRj*lmy#!tjTIgDuIlk~bnEs%PRI54MUUaLm6}ys&%{hmJX3fPWzIUV z)L#pj1&<)^smcRb%ydUWf7o)3z6_*~rHCO%`4HohSv*hi^ks0~=X`WUT(ojLjyZL# zpB}(jVJ?-e36?PqV=2Y7YNT#);4UpRYJvsv1R+`u3!C(l3xV#Si49gqd-)SN;ynlNrbx* z%1aKd5-CyrV<6!mPk>~*?BVja2}g4%qQ1gL2&j_4qSgvB*b?Ez~xq~(1l-iqW$ zj0EhnC5$0wCXhZ@2{zE~Dp`peG67_TGBOu-WJNC`G|^^HSSsFrX*j;eFX4_{7&MjX zBbGgixCp;t`QE8yfv*0*+dHv-^)%L#4T#f__9dfip2rhYAYP6>#Uj28cX;3vxVwo| zd}np80yIdtKA5+s7mDe+o+3VpWE>JJ2!t82qTGev2*grxk6@YrRk#>M5zgdggh)bmuMpvM%K6w?4H<&MjA$#? zG*-1lBt#Sul1$k53IhB27#UiD?mmTW@Oasb5Q#AY0!mID#4_P+zA~hVs<1gVYi(e* z=|zH{sNP=T!QoUc+xTKToS@)2Qf~Gdu>;Hv46pGjoPN0rfqadex>$@9|%`+c>`PBL8+v)bpG3@&wahKV^!ohxHXHQ$3qlLfi*PY)?GX0FU}L zcU10Wr1`NVPcKvFv8G}T$2pu%L?H3LnEl;W10X{MZLT$P%I-;MDM;UWw3$7)A0kmb z)Z|BqynMjk9hj0vhh7A+NGNfe7gz5kJ2q!xk?EL_9_lcrGEemvLsuzh?utm>qoD`m zD|yd{2K8eoB2c*3^e|cx*NPhrC=xz_aDw*fL!`c5lB>eEI5oLmV-80I7$;N${6^1C@Q@%V4(gF>#i<|L7?r3DHi`Gc2?8F(jgoDG1y(jxb|AN{Kap*8 zl|(}GB9ciJ0l;Zt{pPRkhegovNex6EVd(z=VwZ2!l1fc7YAhWEW_K*qC`4?O;0wwl zs)EL_i1|ZCE}%vpGBNZZ+t{pz-DKv)7m>i|45*yjff|)wpSXiSZ3Rk~jg{spjU@km zaD+$Rq>Ais3M;Xk(4KWEP27xE4ALqy*_g$vOgSnWCgg&ua&os3MAW`Z6lB@Z3oglv zC@qLotL8(fmAlB9djEEZLk&NgCrBfHL}3lWF!mC!hv;(*6jzJS(+K=nU$@fF}|&Ac8?zBG@DtI{Z2Lu2Bq9A22B7+&=VUn0H{lZ9?jGR zMPe3%?_hwF@u_>|h5;nX1zryTc@@Pf&%WFUZ}DC_xsqT#sYzj(po=()L2G*jN1z_j z{Aq)V%0|}FBp`c8Qz2_#P~jL2jd>CzzC1yKdadE6)y`P_*$oTH?!;p_$I^uqLaL2l zoQHRm=)AD@4=0HhibX-9W^YLj=VWniNd%U387*(R&T3Nx4p;QY+vM6 zPGtCk$R0A0IF?s&l&!hjXFD17sOXKpg39QU6z>qBnp=o1UacAJ==BiY^w7?rij z^V;cD0;F-k14Md%Cfa3UW--j&-aOA|!V?1M!lTJi;Vp(_x@beKu{L}GCqYwvIz=jaY$EV9IX-AV-z!JLU51QX27#H0NiYgpa=7Ep4K1JBL-^}XEj634@{bci zDo$t~YT)kxrf@?>LWEmbsuVd?Q(Dr2w?Ll8;!syC51$K=nXn5=so}{SMg?_-oPU?6 z{{8lU&Xj4E3SU@Ki01k>{KTswDKxKP(MFf1!XHFdYe?iX52rIr-lJ8Gm) zNXaq0XMrb;boi^jl+#c4xcq_dbYB96lp`NOaTP`1@+U)t1A((VFkqKzumuXp@~$G3 zGG|PkcSD{WZR)yJ)O9kfu-Om!uNh*W^50)ji&R~p(XilzF2=mq@=q>?CxNrf*ox<2k! z6U`s_BEW)Fwf9hwzI@CCnnENXj%17Uvr*sIgb_oQjtrs@HnA(}@5^AsmHJV)N$s%p zXWWgwCtaO2DfH5dAML?2^HIS+$)|j+6K@xN#(U!=h8qx=;Oo{%Z7nSq37Znl+ zfWHG^?jJZ|3VDUe%c1my&)5fh{{;j)oJfJC=$I02r13X@Ky*L>FG1Aj4{^Qpw6BXhx=bM`^mt zdB|wT9e5c4UJSOC`4mwF_MCA4riwx9wQ<+3mH>lKkT2J z%*c|l;6)EnLCVkoML>}9G1~SB48{-)J$Gc2t?dMv9xUP#Y;n-g+#uhMu?-G}pv1`K zb=Ey=mocXhP^$yx8sN#8OGzk((n(``JkjReKvX6$5FG<=g70rq?TWwKygDF{IL&8{ z`eP(lflL*Bp{1?-YEV@*{wg4GNQ7UbREiuokG`RzThM1D=-6IQ5f2fdak6B=SRh~V z49PPGJz=*J{_7|J!(9m*093Le)?;*tZU+eG>1?Qwi=0@{QISW*=+ES`ikNs6X}$?o z^`1EN9;@-Jz@QI%FE1@18gHABaHJLaeOpE};j)LS608A|r>8MTWOm@*G{~?4)e%0j z*C;nqMr}|XWT_`D{CyjLfyMsH+N$7TJ?9}C6^t>(aQKk;F)dn4I>WPhYYR!6Z|*=@ zo*ytMn2|7u{4BQaEL5xjeh^askV2(PdJ`@peGFeDn8+~9T>ng~SGf^_3iAq>^e^b> z)u->k7KfrKnEp#8-?0Vvc&)Z3^x*r;k!ByC~Z0wsW^==w!iMRFap_Gs-ajGDb-M^ zA0?d`1S;DSI z1O-Lp185dyW#=jGM#Vn~N!uDKLsRgY9FB^UQvJc>w6>y$ZeTPm5^#ZRQ9yaQ=L{od z2#fQWLT{DnMe4FexpOj*;c|OrU~Og1b6FUFk${u%9c8cKh{py&a*tFv0cW)@!Rel3Fqz|_BZF_ zwhWdW2=z4ydgzQ`C=R3Bb@`+k4tF$>cptn}Te?C=8deDoPeC2D}b;AZPCPXa2-V2fry|-TEv;Z@Fd+^u-PvQ&T!{V ztb%p_hE$5=V4D_)WH?7STTA#FE~7*e=MP4H-k%S4!UmizloZvGCHI|SOMD_ut_(Ds zORe-x(Z+D#9YY;O;V@J$mcbZCPnWb}5o2Hq6CDkCy1bt3Y8cI^wpBMw)%mj+zgo!L{l;k$a_uG zDsiI$9{Y0Bj;jYtWalVsA<`yn;SJ&drG(3A&`6f`NmM}7GPcP{oAb*xq-u!67fZovLcLa_`Y97==RP zi$7F_suu8E8HUKE!Q}o+hn`LsPc3GCN~@_+?G@1 zX=syB@}jEPEy>#RKyttVZCY&E6;TGWGV&I`wvNRQbpv`2| z9HnJ0dbS8;b+%@iOI;18?@0l@>P5NEMT*bny*w=HQ9hu9$BCn@>f)L}29gLAdI9!^ zlZeNVRmD6hSG!q0)~3)Pg_YJLg=@G;E?~QqXSZ$UT?A=ouXM>( z{PkjdOP{|w-fB_+>SCtJ&*rRZujtxA1uU>Eo^Hw!*_R7}%=e8Tj7C9PM7zTi9BodRZtQeV!ezlnL)l9Rt^D)l0ue} zptKQ6NnX-H#Qs}SK{mvZ#7|^stJAhNRMsT18D)M#1cT5<1z)T(ER4vCHilmxgV+PP*2Cj`P281djfUBDyfM?x0$eu49*+gAZaSJoE%9{zAn4>l293h!T&brv5h|Vk) z_;+fRA$3B93Vn4H5?KFBlCG<(KL()@|J~YTL(A_xfXJu5x5UWbA&J^pCEPBu{IuXC zm5;_R50ROr0DY52H*QMqkC6@2Kr$fv1esdWBru()Nr)-+Q#EL8gh~IEMDR+#^Ak zw(km83Q{m_!oKKvIz?2Sq*G=~V|;^0LPjr0?fd+%|FMW01O`&j{5%}xs)2~)X!#_8 z+NOBKlGQUXw1$7tq2p{?3p!kl+f#esbU=C>v@6uuni`WImh27C;} z%u}*$&6AnSM7DuA_lxE0)N`4(Fz1SLBf$MUuVq!YP1sp2rnvrDCWic9_+xm zDC2KfL!&gR<6?7wUL;EHDHZ7xCRBKx*o4u!OyqD9jNZLU0rg23hb^~bk6-UUC6dHz z_|!&t!;eyzDJ%gCUJcrqp_+ zH-!T_>1kMj)2KG1N2ocF`V_Y*O$73$0H)n4CDkHTaVsKIdk1TJAPWGZw)$30MWqev zRPR2;-k5(>{Hu@%9PwcTIPY9ddl&$Rd(a1N4~dGqgzz<4DxMXSxm8;GiEMIy34VOp~0t8$SqDvhQ!|9#j* z*psYn&Cm3|Pz>jF_Ln(_V>~jj%tcJG!#5~?l1`BoeJoaV+DJ;N@~2QJKWx&JBVtFBBnO#*Jvj6xYHHB-mM(=?rhw)kr1I$kfhw+4 zSP-Exj$Y<8DS!1c&<^368l*l6-)EGssc6*ezf@7AZWIyYa5Tv-?GZB)dddJc=wK2+ z+MD`JxQ9d~M`|GiXten0l)SmoKPEex+M>EA!W>5Fl9P?KfpZYrg!MjzJyDvB)GE9d zdJQFxvj>BiSW8Kt)n(cxc}IV`)CQlDRVaPncF?Eh@WY0@Czxz-Wz1ERiJRSUYI6)b?W- zar!`|5%?VAF>iN{HXHg~tD!L7IhO6CC`EWjffEWiz(35a&JrutInQCI5mT$Nh zz@Adi{*h>3su3cHUXSfbQ?!ZPm&u!pHHSb7L*~e{VRwoF_F=erK;SfVu3(R9YV>iF z3}(T*z%dfjkQSg|l&KNH8!G7t%*UYE3#gyW2TEfs#cX27gLRlRV(}qv%%xooi0ZK9AJb;rSw27lh?+XVj zk>2J@#`eoRaKqS{>c1v+?mE{9HnHYNU!xsVAx^_a8Td1;b_t)uX5C2FP=1BTh0 zW^b|{TVq_(Gfq)x9c_Tcb%JFxc{&N?uugr4d{H1RGryJK+5$5&VgpK~jK3}`PMr== zSi}2yL8HW)ww|=k)`w9O5LXmekiHm2C@9Su^%{m^7-G5f($g=>aD`x8rE(Y2#y`eg ziUw?kcH4HIPi)XcI;$vPpixaM4Ga!K{A^%Y+V1bMxtC2aj2~jbq|Ir!IRF7d3bZM> zwh4IFPoWSpQh@FjR^@Ungasn9=v}8gnug3j`oXC_32))eA8X&HTY=t|c?j>r0t<#> z7Ze(ROiu`XxwK-(-rhERR!?qC6krB0*AOy1fgRg6KwzoZB4R?{5}UHVbe$q_FM$v} zJ>bC|Qw1>fDK4}%*fxB}Y7E2KxOU1aUiMFxzBa}Rl)3J&G(Vkb`VWpocQ5PRQWzAs zgoYvOGN3Jj(FxP0C^INVu98aAW-Lu*3KJ^=jH2R5tSF_nIt|)BrPPScmgCWSavOdp$G?&>qJ{p85`O8Sohlr{s<9-U?>Xb3WEP9xH1GlP?V>i5SGFm`+FBOyKp6QyEAD5a4F{#4=x7dC-(dh8H0^m#gAGQX!wOg?YRZ#lwsBZOzdta%uqO65MV8$q<}aRn|P* z7CUx;^o2ugkPmW8*>PI+W4Vn;br*=fMU9L}NKn+Jl8eOI22n~y9&tYHQ!6*;l|Kf? zz*pP@Vs$j816cfaQ*Cr$^i?$o!-z*Me4fW6VW@$~=>eJeQ7g9Jaqz2_2AMRB7I+6j zUrj-IVYsQYMk*_8fS?!6*aM)Pi~&~RXd7|h4uBdcW$L=og0w~-FjDE~7)YCvYzk*< z%2bW!NAr1ovJncaoJUd`Ql4@^YkY?G+YTI7M~k9nBUHMLLSLA{1guBWihktOyd%uK zwSlDBgTa}6VFSR_RVsOT>`Eii)A_<1(+vi4ria0-5%p}b%xNo~-GNZ*7wCtIAo{6A z^UA^mL|@EwQMf?p%Lb^zUmvX$By=E@^z|p0@iL$2KtTe-y+)?nE)?p~f)d**C}{wg z>^4PubT@@Kh`mhfLS|N7Vbch+u+Al*P?GRFRH5eiqYEYc4Y^Hc?Qhh@59CaZLcc$r zMK-}MZJ*5s0i@A*nAfEsb{mNr-)DY}-IPdaq6r6pWVqx7oTwS-gaMzbPKVpnh`CE& zlxQ5dEV}m1jLcbDrGItQCt73DyHQ!%sOdo+h+#moxj24%EVn9~5o}zEIWo)2NMg#3 zVxr?n;&f$dGESw*a9F?HAlHmYF|{u$;I>|ofza87NIBcE48I4Y?=-lm4j&*#a;J;P zLatLCBONHk`wdhtEq#=$PRkvJN{;eUyD%w7iv=eVP^0(8RNJQ5NgA>W6VRvzYoBlZ zx!VYmE2QiDCk1`0(-Eg|ooWqKZo(OV*G)`0)T(ByFb7^$jn1a76m+KXdx8dSJe&qp zVmn7V519}!l0aSN%u-gOEvXAwm`eI&x8ba!Kb!r;bEn5%up?#XzRcnkd=DZ56k3f4lHcqT3R4IrEPGIdUiQNX;J17MC5 zR-FKHQ6;`StvOo3^^kUelo$}HH2YPtpezbMZTS$X9|)f=PcBeO;3ef-#rSmfwLKvH zW#MN9D8*6_^9$x!l1&{~SU%D`(>xmKiX945yb+3o>^daaGwo0!jYmRf7Z$~#wAf=j znrnVx1YsA%%#m_e7*Snkb$-7PB!|xs9S;oQq&>+q498{INi|U zZA9vAVTuJHHTW~V|DAd$8!vlWyo%YiV<_)7m}1*(Oy!-P0}hz%4ef)u51G zxlbJkn#U&PjD0xK`>yZ`OgUYilLiM0ubOGa!YdBEAH+ar?W4`rmZcXpFH5S+ z?EcLtI18l3E4rGb6hU@?Y#vSH8LkSl17uYP$>LfAQtBY5XV_8_#<=J6P`1w|zJ3*i zZBzZf=o~{3j?yA~5ZOMOH_GbRzy^r_qIrx;;!#~v7shPdX(v?fZ1e47u2-i+tGhb2 z=E5IeM&q9#)C}RSlQ}a$CD-znVHa6U=}v+;4At#IV%17!VnXq{N;kJDRU$mL94@>` z8@J|1FcGR7CAYdz=D4f0lg0uwVNn)+RYt%Dlp>{KDWr%qYN@8{%jts{)tGgG%yg#W zotQAVY#mMrwxuDpfHDpa@TNhY0XRpnzoALD4@%M0@7Va?I-P*&BPsd5)OfSu#9JL) zlYlbS=>p-SCds(LtRrC+(q*uwSQ`g=%t#}S@|9hbX6{t8Bt~gGMsow4V028l!95iQ zm>=THs+dvrU>C$pYueR18mQetr51yvoQTM>0~57bHOo@bvo!ns&%?%|Gq;>IIW$WA z#v4OAfO-O8OAfW5_RBRT&pKR>+c2=T3!kDk$D2YsaEjv0sSz>z-t#%G2hD9)$e=b7 zRMAw)k+$L#Hl)w4xm9BxnfUH!sdl9#m&1wCz*;el613qIPGlc(3RJo=_>9(?jyaP? z+TU59Xw7T9Bxsw56H4~GH5xQaqh|m}EJP*{CTx2D=0MQdM!lUDLZDNucGk6}oL+;c zh6-gP-{m*KP8X!pSUajE=!&3>Ob^e31A*Nw+Grp%2an_{%XKN_aqIDv8AQYCsN#1C z;eoVvmZ}Qi?P!`*7cAYC1n;hC(xSt0WEhk<>^6K;En4;(g)f^I60~NzL7EceEBfYp zUs!@TD)ude8qd};%DfIK-JF|2tqzcWfX6a#NQ}p6--|klQLo*YO53-81VW!NxTp*5 zVXLhBO0q|&Dg3QXXs=kzyw!x(L7`9lEF-ae2I;`4ga;YjL9$>Eor;OFke4|8B`moO zq9|E5+lAUtHUH=Hu{Mc%V9#~PG~-Y%pFKq(COi$GBq?o9D0iW??gvE8lWmFTiPVo% z-Ze9?Elnlc{9)`x08z5m^L=)tpGGOIJyhBzFK>Cd$a05Dz4h?Ov0FctYgv0Fgb})y%JD@JSM?Fnz&=WT?2w~U+OlKpXq!N_tn8vTLY761YCdWL^*%;6 zMZ`B)D9dLB_DE4NN=fX8K@0LQPJW&1*+KS#`2S&mA71IG9v_%{z(4^+|>eI+& z>B`+jpbg+e?95LUM;M%OnHKP-2HvXx%@Jp*)%^xn=IQE4(E2WSXhe4t*{d6tCl|0i8s& zPIyTfhwa;ULztgB8D4R?0pT@GyKK?Bz)hO#*B`z@vn5qPOcKT8DDskKeFPzA{9aE4F+XZWz-Fa{t4=6ikmaG zf5T$29sZKenZk=OozXhm$XL_P$7{NhZSvv?ji0kAn&{s%F1Jmpb#9cr$MZkT;bYj7 zrDcsJ^0Lt>Og=G6kE{M)hXzL;{Uf?@%!!wQ7YbcWium&>Z zZ#IWFTWy)#dd8i~a7x90v$eb=_}4&YlT~i(ngz^H3RzA_*PPx|OJLW6 z@V0o>syM`IpjOQqOecfcB6fjWC5FIeQ~wq-Wpng$deDz7?unhMb2X|G>j3H9D->H4teQGFkkYqhlg9;XMy2>y z&EWt&fwSPzgZOIB2AEC;Gmq&C_ez2QgSh}b9R7p30M7?=zvt-G=U1`;AT>kd>bDM% zK2Y^}$2sL1?V6W31VGPIsYD1seInzN@1!Wij)K{9G`_Q4v+to>V; zCBfqP(Fae0d?zS1Yk!ILx2o43MqgW+F~O&`P#nw5RC#l#w3>6ONSPm}(qz18sJ}hf zp$A_UrW*kI6xIA#2Q$1*X#NbMpWi^zx;fS1RcbRgiB#_@*@5~n3{IHC;tOGaT%Kks z6^VDZ4G(P!+oID2kA7QjqISjY*K$9TAU@A~Qz8t8Q!CauEC70%yl83#@w79JRI+O{ ze>5Cg(Sgw?nE$RBTESLUeN|6;^EwMiC`% zdoGO?tHf1DWn@aN@>&pBc#pSt4wOh+IP`=}O{6+Em7{}2$+_jL68rvuym=3&=GU&2 zH&L@l6~Fw;gt~bDQq%w5MXJ)n*sSOe!_4M{Dx*@5YyXT!U(fe`%|`=dj$drZ|`LsbsI_+>d(-;mpp zt)dS0^ZGuR70Lgw5I4^$@^$#^?b?G%xvmF`l!E$@FzY9c^!yDA#?b42p;c3fRMT-N3=iqwEhvrA+S ze)Rds@$WfuK8m?Bdo+>!et+Kfi$sSkT@bkPMHS7*RT-Bw*VuX z^!oaKHv5fa>WWewgbNnM_Zt+5Zv&{|x46nhq95}z_4Q}8Ff+udO{V*f7LD=_fQ zcBI2?Vsc5b`}XgRV#jHrYR1=YV{R>Q7IxJ9IJ+%Fg_Uo$OfzjZ!OXZ6Z4)|_oDsHUMNb#W}W@hOaW)!Y~sH;;lnyM*n=;kIJT+fWJxN`pDHBb$UQ;RXdeXK! z3F1o3n(69Y!UX{Wc|9;j5t;OceB+`d^Xtg~#sQ2P>3Kh>C|^GBC`qeG&u9UCU`SnM ze~%?dUVvQ{>0#>62u92pAI)mRD4{k&WMMjiYPd?W5-W5=qmc>$@TCBmW=ATJ<0^Xz zFi(#FAdx<@)~T&k7^#6Shl7`+lzh^y_I)y9hd^`eZ#Q%^umA7%!6Tp*PLu~#0Z+Q) zmQOU|?qB*d7~jB9@*A3U}SO&4C-GMIt9v5ZiRyGHuj4d9zNmt}fL zRWTXhZMR?K%?5<514oUKzqxN`J zIWze}ZolTE12iztY5%sc5qIxPwB4@14`WlHim61A$R+d0xxtb0f9{Z|A<4{c-0zcd zrVz5;KRvey5g}Cy?HU4AGR#-aHbM@VDf<8YU;n@V^MC!%|N5W**Z=W<|DXT$zy0r| z@dAtf|NrOz^}qe^m8sgqWBdBWE36{tO)QEnxCE!g-ktZAf5WjOdzjJJLO`@}>QWED zHV%KT&-ZmpW7K>h_WW!k>O4n!zoeEs;zouWZB1P&3ZqS=Qr&dbXd{9hlL6Nzk+!L; zm-=WEskd_(?-tlu92P|DbP)vI_anu>gG{UI?~XSLq=1&o8j*kJ9FZ>{|NAi-*QBx( zVNbK+`wtH43z|JtDpin}Yf;Xxjy57wsTa*dc95y`*}w*rF@RS@@|4zpV*_3wO2v&T zF#?Ew-M{ureWTl%Cr|p)>Q15(_qzy~6T|wEJ+4tyrp`tCqatzoM zq8iAE_*2S1kbT6I8QE(!fi~=Jy?Q#XBkTCW@D+tNglG#w5j%hLEe}}lqb$xY67`bq z8D~y3j^=RKw!({Rn1M>QgqT9eAxi2hZD09JoCsrDOERVTPE zL#LcOM0e~SH@FR?chBCeI-fS)tWo~Fc{(@xXj}d3F0fFm zJlmc?3*= zPdQcvlT*`=wx#O|% zR~$0iR=VET<`kZ}kidtm!U-Xp^5SX{qz1nhojD+zLbgi%G-n{)fAe-a+1m?*tQZBG z2yieqqpKS*o*RQ?ThXqdRp0q&Q(yyEN|z+5*gffgwP3HBgT#@pcevVhkCDtAGTQ{J zDWEi9##fjhseGhUWY*;Ll)=a$8d{et6SBhpbCh{vC*T$anIy@utkFvHQD!xGYO>#>eyNxzBCr za&@a#C=LpE#HnGK5S+^59_FScmZX9nlDo0!?pB*TWTK$$!rGBAEmK7$Po{^wg6_q) z@3c`p2}{{x(P>nUrv>ivxg`2Jp5GO$(zbZ@p~=Jx8pl0Qg$%2VbS0|PmspADS=^DF zb!7alO{Erz!6@7}OEOjRkXxh%gjz8wba4I?DqA4>1nhJoi)P4CnCICmcFX{7jqf7Q zd1JyfUFbCV>=Lf|rYyKj4OV0Y$pg+y9hwCPQm0F*$#Rus*1p1ACDfcK&~#6;GM9FS zX@;b3^1R`y8LiP6ufUB>%XI@rpBejxuKYRuLH*qYrmN&#cMS4MU^e{8jqCcnpHvZ3 zV27!2r+;`JmzR{xiTK;t%NZ$cWV^O#Ur{_iUB~LuE+AMh8;0Y&I+*lpX`6bA3ZZ5DG+fHs34BYtxC<>*&H`E<2yRgi?ZWzU8jM3{f%s$Jy}@Il=4PHmZoOE zT2H>CJh0rBI9~^tlGcX{2v&+%$0NNu^y>Zph4M9VIh~=z>zj=UG!g|;L`-HRQJEls z+V`4X8@U1r0FWY%Bq5=K127KTbaqjzEQz7SIiAhOwmw$zK4Qs@%aSnQe9Jjwh)3r6 z9?R8-SLsBhNHg%Hv@M6YjDxZ%T{p;H5|@Mwrp+DmTj#`UBZj5v$kAA@z>-bV^&gG( zvb84{*shWdxaC=bnx5T7usYQ%g>N;}GVf`z^y;j1eg20AXD;hy>CPJrv@z7{U1ceo z1ly+kItw&SuT-l~(rZJ$O16|}TgqT43aB%!rB6e^N&@$0wu+JWc`%1VXe^1j8U4te zkT!{qkrK?0CDxR7s#27`2m(a=Q$PpEXM5Ktqs;ZIgHL9o^G^9X92a)-iu+Aym5C=Vik z1mzOt;qPsX91B1q-v5X+5GEbWE{pHsxXUNc&hku2JQ@=*z=&b+WR4%nt@mp>ZTI;O zS9}#sxecP^yYtCJz4<=6&G(3&Y)>vbpe4U#!TVaW2V!aqZy!x;u_9PE0ThRgDP^%^ z_gwcC#VwA7LAG@xl9Ig>rhcl^L7sPX1m+x*LR;V*gl$X`lu1u z0#G74Tc!DP!8yjo4h)8tjb5Q4~JYXx^NS98qsK!nlCD1 z8@AfbH{mHnKOb)VBJj^k7A;K3K7DyA5ZqBlDTQwvvi zt?>lii}Ir+C*=&ZsNxfn`noKNAuz$gD4iqxHzW+qgX)bF*Ei>d@*%v9+A|U3>?J~A`cBE+lJHA z=GIWM`8bu;5S%w`L_1pP(Iyf`d?`Azz02!BF@V+8oHuaV7*Op}O0BjrscP{?@1c>b z^6G(D9RB(Kv8?fQ4aVF!oUm)P@}jLQg#|AfN5)c*{ZZ9T5Su3x686K$w(%%->5`-s z3O+E543B>lQte5e&U`I7FEd*A(5l+w&5DP4*^142Ugiii%k8TZQmWfVB7SgZ z-D2!g=Jr1iiYSO9KA)6UF3#gNgd&&QfvM^FPRtG+MZ=4z*#=N7N*0#HtM}uo_W&qT zd1EY)y=N-2!Kkdsk*h5-Z69qTGPR9Dkyy>h)Vzbt%&(E8S%Mo44CYxdGVO+`X$TV) zf_pHivbQyiWFCLk1im+N+JG;WqxhNr&4}3wJkQ7JlJr7ap{WDYEWQj3+a17Z0JxmZ z1vr0HBNzsi-j0k3i1QqU{Ey7i|1vdaAV_z}nJP-PXOezXS5%QI@~7ODh*!*$d0G0V zSo<`ksxz?>s@jtzR&U~>Ir?9wFkT>SG>X$~)?KF+8!5Lch7+1~+hgkIbcW^Z&SO#n zaxqlZK3sH(x79`kW;;~%nO7b3J)V&~QM4+-wnJ6nY$GU@U>l*Tc{juQWd?ZU=Pn7Z zx<855=ba9W&*NjWUl~0VOaDY%{EC~gjYX9@$@#c5!1NDOkoAKkPe1cLk6$V-&(JC` z-u^@DEPX^YtlW{83`g52+wi;Cw&83CNopFNw&N^*+{b0l+h}RY5~jik{(WAIgS&mG zYB{M+{zjPpw93mP|GL?scEl39XBaT&TX7N^iB_e46A$VWxan*qP!uywAWSOJ`j z0VvBSt@2?2xkYNwk*_C4K#Fmg2B1BceotadJKz(!)ehp!R~MnNMo7HN0P7}%q1)+> z2?FFygH27=658oPNL=1@iAv5~|EB|yL*RMJB*$WZumxhl zCa@4CO9vj*v9tOB0yE_1=_EAOz*N)G92)CJHJggYV0C|3g-m}7MtHKlY0jcd^TWyl z($^1Kj_ha@qhcf40Cvg=wI#O=p;_EzV18W8SIx7S6{oBj9Fgf*)aVR7@_^A7l7S9k zSA5ZlZ2cc2PvT03&U3+S}j zb}6Qvuij`#)nvrA30|Gz`3>HLl17259b$D)zwsW4qwU7lc4_x<8pa3acwgY`AXn`+ zPMey#-NtRHx^Y+1?0SGD8P#*1SjFGl*KAx#)l95Ss#gndI!yI5;n&CG4qDazSvWk9 zm|TC|YurZUzvwll7-ST~*+Z(*YRtm02xF(!cmqOj#N)3-(_Wp9d1KYsxsSyi>VH0J z+$PiwikC(#)XTK)Ft4Z&WKF7T1u1Qa_dRXK8))>N;|s-=cu$2Uptk(hI0m3Uds=eh*p0gG{8Ydg8JkGAj+ffKXcq5S>E8 zqZ(1sM&$;Wk|1ER>AX!x&B?%U-9@j{`vNL3Qy_T*Or2Fv5^!3!QdDv^)y54~YQ2!T z<7iIssA%1$*)8&)3nvp0nj~5^?1I-QG#lzN#dx{b3oa^5rtsAolLS44^!d~C&B(tm zA)~&M+(oZ`?#ZrwENv*4WL%K2`LY-wM!Jmj7-LutsF3exu22`Vx`9SSgB8?Tij*bI zAp+jX-pbadFC2-N|AO_8hLIQgzRpJ|I zaganX;tDQ@M$OPAc2tvTS+hj`3Y(o(hvas@VJX<0z+o`<1!7f7#$pm!>#oS@?hvaQ ziDR++B{k*j>K#R|_Ry-t;&v@%gH{_xt2A1t2@ef=m_*|+)w&|pmRY`If#9B^0QDjv zFiXnXNO?-aDfRiVnP+-|AYzbyz`o+x;aycJ4m+8oFu0X2rDmb(+m_H3;XM*vjubzG z#USV>wSNnVl3|K{iavv}UUgZ?)MUw3`Hcu-wM}x?j581~@UEon;Tct$X4^uVdni)n zred=X>zc5_Y5k!f>A+4_x)5#lS+}rb50(1#Z?n~EhcwlE@ilvcfo~YEs)gy=w9$0& z|HIpxWXrBA*|mL9S$bo8?yh#I2O3dSL=-}W-}^re07)zmfYF?OwIhA|p2JI{<=L_W zXM-CFT^g*?FfNC!>!FGG*+nr))iIbRLLLTwu6_r^vzDRd;=Rb4E;H*=D2?s0c+M6i~cQd2f4M@e{E?=o0lVG(y&c4qNGA9W=*B$8EV>fq>`qJ4K z@@hl$3kbXy*pbo1X>VSnSmEXg#3jfQ6) zj=>Btq5D)xMj0L#CdB)a5ED^`V;m8s>!l61PL$1^KgOQzzp2nL;+-eEu?Y9~?GI?o zCxf9Hqjim_eki(YiNv~O0MsZ(SZ zoSI~;DSaN`qtr#I9A-&9g<5P!=Db+O*j&-rQ=)ISiUMqWz6hB)^UT^OlKL0znL;ER zv-5z>Jc>gkHH9mC#YnETCok*;o24LR3obLrqRxWBB6Zj(q5%W~={zT}NeFvfjC+hO z507|^xVd>SV{n?n{;SP{8p;XlPss_JpsirA)InQxz3+uXJPv!8`kXxu_Ft@zT3jB| zAWKpjL9kEKRSZKM$!FW{g)eBo%zs$&Rm7DVSrBH67C6R z7BVIND95Afp#|o_8f=(8GgV-JFboEPw!=M_)|(r=QF>zN3MfS4wL8QN-fYOkuFYAY zVa`o1LgF(94ac`{GTFlj#>cX$N-D8Sd5^Bu(|8z81KrU`O^TJuB?cf%WL^P)#>bP@ z=7Q$}Zy)54T*=_{T!vQ|^0FvocO6wDs5pKxQxsG;9C1Zoom`_NJ#CR=? zL6?ytmg~x=c2C2wFi?rGo|aV!%8%_%D~*djYWE|b*OG@n;}@G5Sm%uUX&U?AzxQ%O zt5ZCP{GBd1On3th8kxX%Xk1TEB~7A&vCcVLK_l1V=-WLgG9A10JxV)v=jd%S_CV>3yhwg20Pgh+CVA_F@UZVkIzp zK`jv8KbL8taZg^3ie!%S_E$it_a)g-G=8Ca=J@`t&N!qm3FzSqaC-t5L9Zu;Z#IJQ zi&82LKF?=tjng5CcE@j-3#GxI+iv@h??|YQ?=wE039RQ?!*~1u-gzJIOXZK>(ZR0n z$Y^B+vOQ#>L^eza=X$?nG2z_b!biu(xGLEH@W;t3iAg=4N-I5aZ`b#UDd6?$1>e4O z(xll&K|erIc3y02D(;zAsH-Ot?Ld8c%E^8dJ)Yww@R4x#rAk6cpFD~B250-i1=Nc* zmgfG?mreQZPQ!Hgi4-90H~mtmJ3g^zZ>HX_R#*-m!!IV*6y za60<(eYqMmFNW0B_>v6IqzFMWl5{sdW?K9sArsjw%+t?4A2%5i2R$F_1G5Oq2pYK! ze{w%`6eP~V<7xTHx0}s0RK`k_!O(3OYD8Q!3YBP+8PzXFp_uqMo*a!{Omd@5r21W_ z(L*FHVy+>5BKc*$UmWAzodw=G?3 z?ZP;5?ulAoF6FB`p5eCOg&n0IWL9Iht~1+%VU=Q~4cMg1B?Tl=#QBoV?FoMS5ethsEyd3vkLD+<+5qb z_ho8iEf?NNx6f?_sC#wxYDi=E zV`)1hY;OShKc6hA(|2dn_5}8PViE<3O2aT^$miokzO>jH@%Ro(S*ESybhN>=ps-07 zDV*tExs>wTkn{kY-k5v!*3e%*0wJMqva&;h@G}Q*M2$sw&IirO``s%C#Rm?+D zlF%D=e4N1hkJBcqLs@s^+aCx?YXX_g$fIbweHZT7UN7#AvY7#0R8YD*1u|HhNj2L1 zn1zhtJn)epzBxOp`8!EC=JcX1ZT?gXS8*$I zbqDSzwa|rw(n}eB`4M?VkL#k-N?ldF3SZHA0rT;Llu5fhG~Lr@uR%l}yybz)g?uHl zLVJ!>d&Bovpzw7*XOcSogT}@{utxkVQJNO&e{+20MIYlt%2awtQmZc!%>KiV$jjoX z)Zw-g_XPhTzQubb7(VUerHS1uPMrO{Egi4F)3-a#Fa?b09 zGZ&u~P`f^_a{E~9Do6Du7PJs3ow4OEP1EuShiDutJe|x-pvX#4`SjJMM15&x&%mOB zeK{AmPZcUoA+h3sURkV;Mjl3|u~NuM6!lTI(DKhHFn79o{35MgJ2Iq5qwMeABp{Z{vK z3sB)lde7NN(aI&g_`i{)s@Mdm?fohx&CBH zl9Jxwv?j8tcP4MJ#R|26Lc+^PSbhv2b=Uu-B=b$K1bUhaSA^t5~d6C zc=)agvyd(q`{Lf#yW^_(0xWp0ijB+P3#xR3xGVd}=D(>^SGf2iRg{I695^U}uXsoU zXptkQ+d7L$O}}-b&_EWCre0I?b}JLpgLL#c>vZ#}%E}I1ERM5sN{;O?aHhkO`f>-k zHX4mY-Rdj*Zc5^vtG{WUU__!lr;9_@kocpWohze>4j;GBZNkU8^^8r;&_H4++P&)@ z8^z!N5c`v@ohuRhVXrtLQ5t$LJU^_`IRlOWsi^jL@Wd~!uynGx6TUfyv2nww^zrB>MH?KeDpsazAZ1SC&EuqNN<+I`XOQ|S5WE_y^_eK1vpc9BKe2J+nyVwEQzou7 zG6ZRuP8|9G8+7>nMGyC(jMfc*bPeWpyZw1!fQR@fbv19Ed+ZCfuGSyujw>Swv}fX( zY;1J6>(BwJt~N?t?Rrl^gVr|k(Y07WLr6rK;(!0g|M}1V`1gPN_y77||KET9+kg9? zK&>YE{lEYIU;piYPT5#UlmR_=;(5YGNhp6a^L*o~s}pulwQ(Vl%EkS~mto1~ap>fo zj*{lbG(`cc3jgBb9WXEM`t>0`hNgl$e9Xm~4wXc>Qs4M$DwqcMV?dx*D}KO6L%g&7LN0nYUIMh+Cd(eF72>!iC4ACldHs9$>EiwMUC6joll&q zWU;Q&A?*&BW)^si)H+WY-|LJ4#+)Q5jE)DHvT~u(?qIUn0)7L_ExGF^E%El8%7KXW zwwxBPW8c@~6OYTosKDypinulvmTW8}X^=V0V!Jv)tCV~4x02C~+ZVuD-zy&qB>Q_g+!^cWN5kG=Xcam2fuzau6X0}t>Zfm zaj~x93`Y7M2e_zZoOSN12AD{LWig8b44D&_A7P`g%pK|*Dx=hcegxcD8*DZ)^a0UOFUuU_zBFtO=ztB*9!kCmbM;!8?v!44Na9N z+(V@$>W#il)iFCq@q>fWu%`9a^^Vflc!GPF`6yMM_=F}sT~Ao2>R4#3&!YIlVPiga zJ@Y(!`Q?@$~;)5sL|mR6jFb-qH}1zsBPk?Ms^ZKTyEi`)_LMI zQr(@?=WMvQHt`uMX zO8%)4`WK$@dVC75$ml-VYeMKOa6)q0+NzR`o~2PzezZMAj^?#;eC}ybLa}KOTn-5= z6`W?azbu%Z4dCuvlW_7WpG0-nw}r%g+%=@JxQiNlbubwowxbM&L&2=aF(a^K8r^JN zI9tjtLSbjkL->VonOfAGjqhO6;P5&eGXje^3a>z?OzJvVfgV~IjY7*k6B+k^gjb;N zBrZ-Rbw=L8KPi7M>-7YL*m}d>|6^AM$rA42-qxQipS?uYpL5? z&~A;s>9^D{AVdDO4n2o!;{560-{Vo~)m`##soaNIO6AfW+z?6xmZy-|QNTToZFA}? zV4nMpVbSl+OwmG-(g8ZwHrL8HrurZi8!L;;|}ChNuzE!o<1?-Uo?{ zcWmyQ5O$_hd;&E(18)Hen*hu=rV@^_lbZ+pWG6RVj=JAm;HU%C$vb2L)tB83h;{6Y zevdo=C*SQazOitpHO%{;jAb-znIn;ROiWfk73kj_zQ5m|mbjlJPlC~PJYB5Cj(>Ys zuTjg7&Zgh#$e)j8#E#q1@iagzm80FJf*P0-ZA<9#$bzmlws1q3`-5Js)K@?WUDoq8 zjpOzWjK(eIo-tDzMOe%ii`Q;03N3>O)%80n9Pf42dp!!Tho~-Zj>X%%fpX2!5md_# zzBEJN{iPx5eb(6lQiRLh1!d4c;Q@YT)9}H1RJ=@jr<&<#Aws+z`0J9$tr?8f1KKUZ z%@EKGGkmB7KY^uwU{D(^R02t9%=Yj}YNW#aOE#wObQX-C79{+qTOl$u!OT(zU!$jI58xun$j%?}pQ&ElKWF$d4 zw_N`WQzvop{kT6a^dhO6#^D9;bch04*brC@1hc9Dj8fL5uz63{KGKW*U3p>j^?^ih z3Db}~>Bju%+7=2GVjyO;CtE6`uScGCpD?g7$L}?Xx3wJpI!?&obqfP4Pw|C}KHcHk z%jzol_)b9ypR0m81NfUN6iWJyNp8FER=u1cyM2=T=wI z-+|`#Azm1Vd}Ayub<2%|YyiEn7X$&|Y^GPsn3V} zPWnXYsMMUk7Z<-+lfeEE?7T`nReb%A0&WD{a}#Son!h~Cu>K%K7G}jFZhMSIYo!@s z;o626{G*8bLd%4h&xWO#VN^JqY^cm1$ML^_pYYNNB~Xpb!ohk#Xax?K5UAJV zvzu?|LvZ*Mdi5k;_9fMF1a!^m?ZYc|#lrL@YeHRLKI;Y{Sxz>@Qc(UPnIM^Ts%qN| z+n&IMeX^MUV204X{QlJ(4b){T>ixr>y;iBP~I@u6F zoJ}|<#Hj=n_pUYHcS!XjD1Q;ehhVAg}|eFcM8E&R-tg`;+lv8c64k?L4A- zf~Wu%vawGa3{r{ds-Dbob1T9gA%p&Llqee{a)M8#uIn25I#c6CC~;lI6H>a=MdLC6 zxej-9O{TiEsZiypEY7%UZtF*lGV&77CCt>WICTL=c91ZJYNy?{WSQi-UmVwD(aKAT zR4&!r6^G}Gl*(n#-zl%l0ZJA4uv}7bbHWuRt}mFi>W}ngi&a$Ta;*7}(Dpn$a5vUD zk*EWgLk}}fv^jo%l9OznGdQAj^#WS&a%eS}JyJRyXZsO)$pawDkYM(;&O9}Trp=w^AY;DF9)2G#|f@x@Yd!Sy;PZ8u;n=~hrA zp+Oe*2Gkfsg4zG@QUOT?_`OhVg4utDB=f(ziwaz>7pTk>uO#PM0deW;c{`nL{T+E9 zFL!Npudd!M)b%AxM(P^z1j=svS=Qv9$kKzm4NM?B76Q)>)bSwCDIC$ix&(RX@N3Vf z>uk$9UP+usorcLOYV}_nex>c`_J}aATMMPHJ<_RSzuioz)I7^o;aUs#^%b2^&NUj{ zPx=BT$WD2LlGtvY%6r0>9a+cf_^ zS3_;j&me|k!OX)AW|YLfA_@SK2WDkF>^??mOvhh;0%ippz5MooDyoE;sgdTSEDMap zbWfo@re3K;dE+;HZFb3tw-2eJOva^pp1j-shOY{IiMjVg?i#{hp>;i&%W*8K%BsFy zR~-$+Y9wQ|LUy7XC9~{M)^3CC@c8vY+owbrXA{dxWLJ~a<{Z0JtgbO9VMl0;!;w8+ z^a$cU?T?r^D>P+8LcO0mJd}Y!%XLf2eWM)K4waLJd|wTS=AlVC&ii{T`ML!^#(V?L14 z%SE!r^bMX;6S!WRzA|)SV~3#Zpp4;3H0H6fdedm89z^R;^Xf2%ow2ca(gxE$FOpEA zXOy5iq{2UJNL=q~Ufwpw&3^lp`gD4V^ugmM=EGae>AT)42KMtFO5LDxzu9zRp@Y}U z1WKs}TFo|WGOB)JDP#*P#<%Ti1_SyZn+49l)t1K>P>vkK@kS;u2b>|p3+(>?v2^`@atAs4X>|}=jG+qg;h*d2}@=u3Wq2a zv8#o*xgV~Nndq{zHandd7m-pYaZ(D^l9t3mDP*ZNnRzijSTosE>Sl-XH-3bs`n039 zb2*)O!$P2#^Ft@n2P~|W?ngJ$36wogaX=AeNR%b%ynrh%vOSXCbruXW(2l%bEXH0w zR5Sk&wlo}W3dyK``$Y={8nk;P9atUL8>*-;%G?f~gh?dwcZBqa8pcWNIYcFK(dP3c z(ntPU4~t3Bc^AT5OMFzk5~B3x@q0qr4Bsr!JN3jjTODy8l9$X0oatequtEFffLbC^ zZaSqc0EfhSr2S`Lzt1}f&YVOQ)2=2;HpuRLUVhLil-Hl1T<8!^(P*7S31j^}!B=vm zR4G({xG=GgW8+a5U8SQFeUArHhy5E4fM%nK`m!$?C?pR>2yolz25*{K@2Tpq4@DPRZ z<@t2FZf;5^Vd-LL>c*D~?>ppS-JAFwx-a!G&siK$M4fzLh&ua29ko#|b}fy3soO1= zOtqUBuhGzfbc%^8r+Y=b|Lb;PSBx~1J@^a7wtxE{3!b|UqUMNtpm#`pJ@D8=R|Mue=oyAG=ex8Y7G|jCI zJl^W1DyT~Vq8`u(6e+#g^#!6afK~4|gGo&TxTlCz?LQnEMz}w>4^{l~5V{zDHjK`i z#4WCefP6S%=^N@t=1`5sxrZCtmF$qS2wiVb9Ggc8JWE)f?{$6mEKseyezZ zN;%oFHV63F933bvC>-M;KX87Thm?i?9NL!`>L9B(y<6otZH*tE8q=OW8&m#qorn zK?7)*4JjT`NG(j+-N&Rzqq5CVA+`Ji)@4!b{kICGjP#bgr1$_M2X!;SIGD0A8=b+o zI$3@r2Jno|l#v;?YEbA;gBCUbLh5}zLgJI|4o97UhGbE`w6(NOX-^6A@EHQ9ZbE=U zUv=i>!P;S#uU?}p*B3j2nsu@Np`?}iMLX(6eD4^XBTUq0V3`7wRwMItzP*vZ!E{Y& zYsu5U=qkQ0$7lG{_wUAX+WK4C)^+>E?x`LiQpm~isseg{(HwqV0#p1Q8ViV=SQf6M zCSxd_D$bW|MXHXlW{V?jEL#b+KPeI%AJAZ?!%L|Sm{jSiyg;kAHxmPy=I$M3RLin` zC>!1Z6_M(~mEKl(BJ*`2Q9JJ&73Yc1o`@7rX9&$RQO#`BMdNa&Y5%ceR@ES)=QJK+ zqXZ$#k>)zK11Ivs+%l|A0x=uzMNItYgj(De3_V>&SK+L6$ES zj^Q{6>kTo?cvy^$M zbAhnOEDgZ4j-{D$vD9$(WWoTUa@o7{oQ47FZ$FDb)FqrINA06V%rEo5gQP^eoSmjf?B3_hFt1Tw7}uWR5}KxZpU{ zE*1cWcnn7)!m&C>m?-fLo2F*;>$v1@P2Qo9F0MnW7{kvLQ$#Xy2>7~wQ#dGr7o%9v zCxK)yjLUMX-~fSAk2r>Uf5MbxWu@=(xK=f zg;@o~WP*#Ibg=nQVIu<~zhh*kEXcM|`2dxR%!UwmB0 z${gUK#4Q_4dX4Y3L6>&o(L$h;DB=>-3}X#OBhm=S>G;BWIA%ij17CYZ`RjsjM%IxAC(MK@E`wJ zHT|Nf_;K5%6!9to;dyOpxHVa*sjFm3PWklMn)MWA>ksugW>!o_j9)9+%xCp}8Amwf z@{(5?#<6c)Y=|s2ub!&B&vntb-YvgoSs(%|cf3k5OW~WssneU%z7w{|^l6_ync?Oj zM&{zkUyMm4#9{;hpoS}lu=7J;>vlseT}cXsrSBV^QpeQbFIO$>(`$jOjbrDH;&H^*hXkip>Je#vyRRtY}&urh`OarC+38qS{@>H2Xi0p ztPufusqX^3T7kuSfRN1=EGX1$HX+QFhvX%--6W+-zzdD8(BHTKL(*n2gP#CA2s zfG6#CCt%N1$_&f+${tJjm=i-;-tKQ8|Qh=)cdQ{PA{*k<>2i>%f7xcfIW zuhWEzb9|8rC5i2EVMZv1RNN!8ZTUI1myNFvf&Li+U+Bx3s15z6lJ$v(ZSyte6Z&aX zm19&QA?i+&6)kDJX@~@^4qRG)ioFnqahfCNuZyMhM+IZP z!B{lw|@GN^EjGx?vUla0E9du-2h|)#d;LyPru6a{MUn z+mH)SFt8X2u{7mOpw?`T(AW7&^58E@Hh}dXwxb>PE#wI;>%d6`{Fq)XThj8Fx`JMc z%R)^4O6qI!MEhg<0myWL~i3X8_MX%3*Q|cE-7qX z1I}}M`xo;#s3}xx&WP3dre?#m%kjc@hrS}C>JrLyX`LjNcXLUUIK5xBiDPFFDju(X zkBMwtd+z_$j*XI1dO4x86TfRShM9%o!H}3X`dFu1+!i5o_#TK9yxHyV`EK$@)tk>X za07E}eAJQmW^-8EKX)F-dre)6V>$JG53Q^cP;H*V(P zjZ0o^&^^=F@rF81&Y~87^5mR5pmARCHlePpi1aHPH8^{{N;70%cVDI6&iEqlr`LSe zwDijw^|sdGAvY*V%^PchGg+YO{HbsjW z<+ibav(~G!d)6(vmsrQLj#`hpf3qpePPez=<*J>gGiCgQ9QMTt?Hkj&4_WCR(s<2$-h!#)w=RRZ5roh5G5O zGczVor1UpH86Tz}zBe)1H>inODi`9X547>s#`KX~zHkl?%<|Wsz0g-DFk3cX-wUW9 zhsNv^2hoKb3gbo^j_mh=OD0dYyAFU24hd9`0LX1lmQSX*KC-#1e-c=;QkRo91?bt@ zzhnBuBMeY605fUjKgp$WCoc%N`p&ET}=TDYxv z+4tAvL=c%6_dxe$lz$`k!NId>X|kfU~s#f7XYfE0o$kk@nj= z0O{`=Uy1)h{EI5?}h}noOZq3zvy6-PS)~P&M5x_exJ=MKY{#BB&_@R>%q?Sks-9cIp-KNtW|v z`t`oyU;xzAq^svI`ftWEC>MbDz_ddd6>Nnc0n>84)-yA{682@QhV7^!Tle&ps&V}n znB&M+MxXr!Vk;+by|igYVF|p&W^NHP)%FD`_@PIk8cSM8ta<(;EK}Bpy@9p^^a=RE zn(`1xu&B&PA=&T-g0*MhQoIn5h~Hp*eh5lW2QwOAulXt&3%TBd4KgCh3ITIWpdcu` zixrh@;}xwwu^Eo6d>@i#Biew`<<6PJUKK#(m_C6QKx`}=l}IqW%ME#M&DWRDHYCoA zS#|ilAOVg_Go>`DxQUrS$u*V|Pb40N#*ddc`7|~x%xH)5@dZ!tAQRWDtct?pc!I3A z(1txNq*6BOW9=QO&(vD@Bdk3L4B#c(w^v7Bv{20G9ExtwzapYyM053CqtiGN9kcl^ zQt|--6(`t-X>*$s0tUq)A?qq>U;|D@Fsp~W*Xi=F#=;)J*PeSzbH8pO6&NjzVWOoq zsBYm{O|nnlbAA#=xsXXi1}ZMmuOO2k(FHH7 zAcb;u*07n@pZkg_q)jx3 z%vn+QGs(Cq`;g&Slo2i`op0uS`8Tds26vF{jLcAW_tUD@M2Cfi!rq6HM~64mc-a65 z#+Zj%nWdR+O1OWuYDiQqRVGmW!fzJT(t$qDh8_@7kw>zFBMWL>66@2gzd;p(!~g`w zn1?!VF^3iE$Y@EL#iV2~Rxv$atf)a?0QzG5YT^?PZK(A)s4L4E)w*^b-=GRXVF3AJ z%tH0+9;{I3OJzOOr7cQ3KS33GUqDWC%1%d&sSn8`(5(Xi z7-JIEF7#oAs$1(FK}8||NmL;S^?@*s2x~n)uwKu*+$aZKZjU!p{sr4kv%Z} zFWw~7Ark8-x&oB>v!w$Pw#V}&z(PYJ``@Zog!mi{MB;pd!n#k_H5@;(l-4t?5{{2I zze3Hm3-!}qCsgBCbF7W-r1i0d;!A0CbpE_SA-Y3#Ui@Sza{GBEV29dFfGw2!PfhHj z#zsq1jH9B7P2uJ@&_Ylc#l+}QC|2Siw2;zhPMafiVet}}|!SkvB{i3S}(7E=CY8SQ=~jRdTg9v1&bWa4||i3RM| zZF~*veIj{oyl8WIMBy*G#OdzcftpQ^c|yvsYBrB3^hJ-preu>kG|G$}q>vI=tcytE zuSz!0DDXv>LJ6o2RBV*KtbK|)@Dog-H&%$}Hi zp-vr()0BY}iOqAVKkpW7T0EgHiPDGp6`T-kjG|pAkvWi28cV$f{6+3HJZUpNL4937 zs;hWS$tWl>0x*B_N^m@qCi?QdktS=GS2;p&gafOK(&NSeAJ{UO+fLK0m{OW>U-Dw3yn~ zLa2DhZTnD4Hkl2MxQcuH4U`Zxy1)rj8nfY%u$gBrJ3;lKm~BF_1c6wq^(V{gKqRzY z6W-6`ecUbl12jtP+%MSdfP{A9`j1s?fcHFabtGonkYnn4&82DZD}}{*^gor$Av^}2IzLK0$|RzdsLpG@NYeZRf$pWBl=30$_% zH|F@|!y++YQvdLo(R}}kv3K;)pm?fTlxLT~C(mJ$mQ&{7R{fR3b4+nCnf_p?kt4Y2 zTIwdL{|`yL-n?yR?)B9qav_ad7RwKyV#dQi4*cP>nbT&MiVC&;lEs-1yAs^Lz5l`C z4OQQq;sr(_&&y99re?y56!vyyLhZ#&YOXFqj-H7uhyw=sNxz6jh^ifMXwM(1;X zb2Rr2#-(RveERA&=Yxlxdj#r;H9DOnRCXT1B~$*kSJ(IHQ&(R`_p7DZ&h2<~YEeG^ zZ$6Hz)BZoX9S{H9zJ5#JK3bN%VjYyKA+NAUP1N0Epbq?J0)?s1C|m^ey}e<+mcD&k zMyD2X%?;y-Z^WBliNNp8&_a)U3QEJppk#6c!r+-)X(&{?-aa0ZcS~P~f0EafqT3Mq zYG`0|N%N79ugTE-7uZ*Cj(u9NIlD{JQn=@!)}uJOF+*W}|F0{0RICHUht^Vs`{TLqPIKKm9LM8pjZ zMlcx2bQG~$Y^!ZV+D;boI#McIMe8njWv?FL)+jNOS4^B~;k*DP@K;3Jl25SO{p3g} z$;ZoJgs=q`yoy)f*7*t6C`VnW!G*5@Bcb54%_a0g;v&H)mrOP{omV~Yv_bwTb$@P5 z1h92qcChKZ-u^JwwDq|`sQ#jtPuyO%2=aJ6_$wTi%PS|>*Ny7R`$LvO08X7T9F9I- z-aO4dW!jU-);)pW@@~JS@bXD3Zi#O8`ok0w(|g8LnP?f)mat~;Zpa>Fe}%#foy2i% zup(X;94@=mUH47OHEZK(D&Ovn^#fE&2r~j}OOTb0@0ab;%YtMk5#1M@e7l

PiL{cCm&Mt?X=SEy}qhtVwSl zuPxrUxB|WIn4AM_Y~F3b6%^2mbQDe`wW9IDrCp1+u@1Q13{ErvY|9QP<~k@xI#y>E zsP=j@WtLVzz%DzhT2W{)zfh?4nsN(6%08bjq!h%qxluhpUiA_O0NaWp?p>pN5!wUU z`)IW*_me{`1Wv+>Zw|=m;N@xnuMDFzlGDOP!Ibz7Xxp21hi7Y!P{^Ud`{$2JHVGd9 z4mmQp3BkX?q8)h-krH|pWU%Gz@nqxhT0)nOX(MYT}iK9dW1yj zX)cBOT89`@I^Z`%8GnW2cDvuaO5+g{#iSBW5RYl(dLV!^bNXO``Hd%gf@-!8TfabZ z!xDRm{}KAcEizb^0!~s6?Bmr2Ht6d&15&+IO0cmkk+si6i+=@0rP>&Vcp*!V_A~aG zRD~-*F)BPSqN0FA#`#R&V+8_Ms$JXidOS`VY-1_j z+)!QG^#I)p2RU+M*BSnvG_CR=RVuj=BQrBh?gS!umW2AwLc+a^Mcqu|IoZ<&=$2mX zK=IV>Q}FSdIL^1Bd7+ewDI;XKK|~=Bf6*9XoDcY|y8$4DYZ;7=d9y%)z zK4k_yhgdpLw8d#7+WKGU+%hmq>{Wy9pJx*~Cay+S=r04$$Sav;=M(9QNgTzE{;fBU zF(WVQos6(!_DwLyG3cIq3wfQ7B#(|a@(HDm1Dx!+SICoa+CgyJQ&(!`afIF7r)G;bM<_6mwmnqJfcolfqw+vW?$Zm zUVPi4(_Y>#@Q^@UxPjBK*%^?88@Cq?A24?+JAKu*rPH&czq)cEP z0OhCXf-D12KZ0)Kkg-=a{DQ8@N_prZC)lgBXLnf2~~12Q-YBU zDCZC;V#+#9E^P0h(PC!Q6mi}yoYA+)S8ZjS4d9^`O0d#h0R959jl~T&OPbi3OrP3< zK44qkznXCH9|dfqZ}V{mzGiG(#I#;}WP~gUm_}Zi1rsu1uLfqnfor?7XXP{~W&~zF zN|5|!pgR$$kU-mL=}1rq(jY1xw=)m-gpN<2u*wcZrleK$s<~jLC4mx*4nC7i9)}0^ zaIfAf-T?w7G~1xL23x-)4)(uOE&TLt!~Pyab0VV25~`_#xAHrpPcw(otd}7C8sEdC zTjlM^%otcq%+XhyTNuqAHaR%C^h?t1wI#F?qxg6Q6ki;>gV1Ii+}E1yw`>j3L}a3v z)-0!eII)$BhBY>AxbH#);Swm`ut%Vnhd#1?8p_^S*n3KCMOPp@HO1i-ggdC^p`5Vy zVqzRTaJJ09J=9|N8;K!~dx)2vKAlcHtNtl*xicb)(=W!X#onQ8cE6B1{qV#(!zW%p z!lzD*OTQR%fV$epluslN{-P8^T1?k+iXeW{AgKs!nvo8Y$4dP7nzx{e*Ev$g8{5BE&Aq)<(Mn7b z05LS*py-o0#46azyF#1C_@csl@bA&tf794#jB;qck3XWXoiBSHF|!ZmG;{z z>8fQy{1VwzG^w|vd8Z>AQJX)T#M{?pYB;tbm4nYE3Lh@aJQ!g-5#4n1iVcLTuFK%> z4+P&e(%|-~YEAe8KA+lQtjMjhx*VaXs|$nDOtpYF^-b`T_64!VHLB{rrfs9gr&1TS?}{Ki$Sq`;s$KSNu#L* z9)Lv}@=$1eD1h1kc5Kz$9AFgS%9vaVDiA`KZR0?Li_{FGYI+v?z zV4H(|_?0jZK_GVGn3lepGrefa7C2IsqF%#!`Q$0`3WpBzQ^b43WfTd(5zH$1uAiuL zBfz~&*4>884g2`_u0J`Dk>m($;4)()1&S|{cT!O&j`10&uSVpaKfP?Iz7tBrNJ5wS zp98on?|6c1aNr>(?tO*!K$jYfE^tOOz=9W{+obVTC8!I=G9B__s4Ll3>?dL6dr*l^ za-g5?8}_*;8e0+V5GZ*z$%L60-7voT21tN%tH zY=!l-u#*5-KWJn23=D#Fj40IQPNpN0AV`oJ$LIi--5YN5S=eAZ%pp34v$&T z5@^BZP z;}{cjn?r-QFVH!tf_hb6pNXo3&pd5WXS`r@_+!kXgTI32cyQb2ypfS)e2&a9^Yb{yCON*1spS-`1?~p4jj$#l0WP1R%jer4NbrzbXvK1 z4(i2+hk=inf{rUA?Vs1~ zC#3{j4v`jOkc)6*^+AjU`nP@lCTv^%gOS*mh0*!|XCmq7J$N|PwfHd+uAh4yr3*>^ zoR2cbvMdl7h9LklaNvI5lyFGkg`pa2Du2LQrvY4$XJFyB$Qws<0I9@_&bCR>@@jP$ zoTOByedb^eW9np%5Zi7lcy4_F$SyB^I6zxxHeMRnuT)sbxx1CJu)S{ICNx6gz+aE1fcL9pRpSmmfjqNs8Th2HWW>@ zB0VsN+h4dxjqDtsuj`PP1xqI>dSDLu)g0?`WQib-=J3P?JBjU7Kr@Nz$2~ZQ@t2bM zdI|tT$b`@|#glmvr}`46v1}2r!uU$q!u)RnHtt^UEKMDIErUb#vLl&w`XJS$ueJ5! zo&vz@^QJ}`%flB7iRw}&6yFanZ`c(++!&3v<2Xhu+9a>ju={>rM&>dLb7S zo`bXQ@zo{r39qC*ODKxNesg)13wfXklUQ&yDsy0(H+7Q=@rz8o+UHQu|4f&;Vnzqc zdfu=~N^$I{yC#_VQ;j4-v^`u{dp=)3u&e6o`&$GI4z>Z@-mDJ3mFW8y4w7v0v{@Bt zB4RQL6R88aew!oNt7EY_gHI(*`gG1XCaK&(b*2yw7@a1aC`AkjQnMC~>}o-Q*LJwt}h35^76&e5VX+iO=x)r>rbl0kcLwLM9ydz zGjD#upCO|f*QpNjXX+AEPUeU34(|s@H;BAlJC8Gvo`xf#YX#qwr$?YzhtH+d9-ihu z07Kwf9mONDFs61M(b{58`3l!gv7%k%@+fQl>fa|5Q%A; zx61;_@)9R5K~>;sC}as~>0TkV#D`7q*K2D_1QIrZajItdFGRrug5Pdt~4F7>p2HW5zP8!N|$qR-ujRs~*C0}C= zY3ooXK8yF_G_2$2FRmxFp5C^Z^7qIEw`n8;B1hFAgBUERb{$z6&A{(6gOeRjDA=aU z=M{w2OQZ_Ji@EAQTmr$9y_>8ST%V;G!y4h6@QvmX=aH|?nLavDIF9uv@0oE7f@$s7 zgK`Cz)bh}j4&j80G~8!40X#I)JPOtNu}nP(RIk3Ir}Q|eyLI$?)1RytPvXbGUwYvC7OIsgt$(#uUxcDey?J(Yo97y7VfWRrt##*2 zYZiMR+OwPI{A~H<#ocko()dKm?CQ2&C3CLT^2^ZH*mOg+{ZgvII&^E|5c3rmj-}6S z=>ZCByGg&UsN!J#Wk_JN|MDq_Cg=8FURR=sIf1Pr)^TzPM5_P^#JL?!^6FhO+Lur?(i23qyc@}&QtTBV-SsGsr8{s;1b$IU+tvaKNFiZ9%6SrS%!n|%Aa-Zwr4K_=GW^Yez zRE^(KG~$f$g`~i&31!b4m;{z4a6*n7U^6~u;22qd`q95Z*bhPD{`gNJda&;3frnEI01ByqVJ zBQE^Y-W=`gKTF{W|v4uVLs=%>eJP0)Clo!&UlzD(~zk-cI zZz$iFQps`_0wrFp;4O;B-=+8}2ql5i@AzpHAx)Rhx@oLivf|Sr0(3sp2#+-)z!i=jhZ_bM%FuuU+osY7^XRGPL;?b1AI+U zxERxR#Aqz_u@IcK0mtvR((3Th1AH2DQA#{zx1?s`A`LMDX(^wUR8=B(L3B)_7}Xzb zh`u-!d|FJ^>-R=!*>up*R84Bn=V#3F+M?dzad`fc4uO~HyE3Zud7x`!21;4xSEy@T zGVtbvqLJzHYEq+ODNb3~4Zfv-^_TZxuXNmq?!kSfS%MGeF)=NC^Y`Zo)PcxUI<)iC zgo%SHp~dOTQp|&R3#X$U;VkJv`kv9k_ulDicV-TISR`~GmdYkH*rJKNjuZsRqq09| z-%db#^wof;G~Mjov;uda5OtU0+$)WcY4z=kJ?+;ga9py;*3J($+a#GhnbT{RNxH6H zCQLro#j?*NFvoEd%0=p+oA2;XCJ3kqrx&Y=#M~UJU<5iwv;f~q#VI#l_hJwe(2r^I zv{1Se&^`a;y=-2V53j|ygz{6R6>2~`<(YeKA#3UF{SF&Y>L=$jCoKhc55hF%C$*s2 z$II{qc|ekaj+loS$hdhlYufQo$y=7yMrgks@yzoHT8!kV`9KVU^xe)UOwF4m{nOuV zXaZyM>Jlk=bE2;P9dH8S$^}cp=ToJgU@1=<@_N!K(=**;OeW$n-d)_?kv9I^8_&8; zL3I;rWX44Rs%xN&G5fH)L}=HG)tY{TbV1Mle2OG?(gTASQYUuuk)szacM~?m`S(1Z zAob)*9R90`t-HcmdvOd?8VweIABXa=xz?a--&xKY>d=RQFWlS3p5nt_2&sv<;w6R) zzVzwOr$)_-CDqej1>lu_W+YK26|jurFX8Cz5f064Q0#PSB;nyASej2vZD-DnBn?_8 z`6Xfcf`R8pf-reZ=FvU7{;_iI++Y|iW>RTL zZ#IlObKF7~%Aig7Z!YJeehKAE`%H0=$~Wy@$GRwd2NsTfTkdYqGUZ>MjR1Kc3*R?p zEx{qC)tEI$>wUid*(eY*A9l2X)?h}N0pP^|JTA;yk|~8f1N!PvXYG6G>+XzaGlu1$ z=nP$-!swXO%X6`qSvtdr89mg`Hw>ioGS7^*$_w_oyT=(aFZm($Fk8;irSn(rsGPJd z@ZFiNI6#}EF1dO=a_oE3N)f~N>+z_Qab_o_^@(dj>Q2nLs@;&b&i9eWevvIO?C4CV zO-Ngy)g*R)WybAaEE~-caq{PBmGb8#&_mhdMg@4N!wx;a*nZ_!B(RH2QeJIDU(z`V zEq{Vb@@A_2v^mkhWM0VKb1pk>u^hQbT^pEh4x7Gxyy=NpmMzwdxgd6&wug(SBo;uD*@(eNNTq2@ z%5ToU<{|?I@vEi)8=4r-hC+j4$_C5u)gp3=ze?dvE$;E1WJbQcUW!j&{gqK4+64Ay zJE@y{zkl@N=i6pA&azQ5HnyF6=P(u6x2KGQk0o97=?Az*a@xv7&T3N zRO@eVHkZ@EcanzU7b~B(H}-uXQ#?i!aFo&NcfIr3Ucyu+CWj~?`ud%uV-p9kVDXxo z|4CD$MNV($b6`p(P#c}V3=8O+;>~IDWao2m0dpdtnR|7Ryn7M0Wcf&8%#Y<(F{;)z9VQrhqdN zb70jgPc%Wm%E9E}wC|VeFGGY50B9-gQ*pYm1s|2s&(*!=W=n-ti9&gp2o&?T;HP?9 zt@~L*X4bh6Na6u})gK6|xr~D>oPkiKQgmDi%g5iBo+SY<0L1+ptwa8GKax0_aPgCB zoU4J@*E#dVKipns3(wDA5R1Y*Cgp%@=R5HTcWApv6a~~2Xg4iuo znAYUztRn(tWJ02yT!yJNI*#u9xdjo_kg1(jY3dZotcV&l_^DmFRD6;iekzdZVct<2 zJe)jqc$btcR;uVQFZ;bCwTk%A=jR^8PHPyLRZpFGnJKRDK$m&cp?nq+C6WIbd@4I% zK~S8IkSd7>(Np`9DpdB%74NtYyt^Q3Qybb5)f76`Nh@`f^kNAjA4sGSOoDPm446tthW|iqY_Jzcl#?vGU z>7LE>jfzO%8xSa?ZTDhAnpW!VQ)n?JSxk}CFRC%j0>&aU{p6W(nkCK0Mhf?L#5L8J z-umA+<(Q9w1Rm^@4Fyx{F})q!{AzRdsrAn%{WSXm@HiZJay2a$mGu~??z_7SUyY7* zzEd(zyC(i`Mn_28I4yFTi4Bd%&?!3hQ>nb?u5iuAZ)QiJk@q`IqX;TlaIYSd=2{|> z`V)W{2z(u%IT%Y=-8wo_j_EN_!jwzycZwao#6xR3ZPwfW-qIuus>SH`!Q7W#Y<)bb z1=4OQ{09NwA<_k)JP@LZFJwNn)Whn&Lg9djX`P7VV5s(ozd?M5LQZF$WurvL1H|`x zT9*<6cRq0-4w8z*$A6&l6KsB}&qyC%6o&1OEUBVe`6%g}#KEUJRgJNPGT8o90&`R& z(b=FJQ_ug5BAfn~l4?wN00IQ= zdBnor>|-I&`jdLi3Wo(+;jGrQr!M={8mWk-so$X5L*3ntX9(!#qlq4p^qWaIrlc;h5`E&x^LN=lI^l>z+%t7BAhkOH0$u7SMo>i0@xJZ5B%5- z=EHeYezl$EiSJs6x7dTE*USBI_Q3x(%Q7U-EfdBqC+C_@DxTscuICnlv?>2@WrITZ zCxZzujC**!q?uf1(1_S#=ZJNRF8bhjlnG{y(i9&nG$VLCp&tmQL>zgdOiMH~u}tdK z6>SObqIEO~yLnl>=MI{6tg1! zm8*f7>RtG~OlH1)m_TDMm4p!^R910y5k6YDhPv3Sc`rzjSh|3JXc|~uo8Qw`0&>X^ zb9Go!!0@0XrCoQ>+!M+eM8lr8#5V;(Shz2+M{$MYNbgyxRPc~olx=_`W-3?s_9O_u z+1VGGeufimqTParg#7^c(?JJbhfe9MOK-s)a2>Hu`YEGr*GMNCsidkqwIFU~J&iu?3B^IXq0e3Gn>g|mM|R1R`-fn=PsB6lwp|&J^M_0bMy2yY0p^5s z7Ei7v%0#o&vab2fM(oSZWwT3887jkT7nG z{|(&Pzx|K29~jCHF5Cc*wU50)*)bs7OJ%Eg+a;L_BE_G)SNezTn52 zeG2P#!t!n-CN3^Qj$0NWl=?Y$3a(M4C8pE^v*Ot^?-C&;5f{NVnZA5^B-Vo3pVtX5 zPkq2QJCP10i?S!s^iaP&*u)btEj&~?Edxolw106(1_Cdq`#;Tfj`hv9yP?-@B_)eN zU87k<)Sv}Fpcc}GxLBbzHQH-Ok*-3;l#r9rXYHtZ!QQAh9pgO&?tA}hJ1T~PzeU7!7^IYnj zxyA6KngqK<9rc79A#ozF4m}g@Q_Z_tlf1|n-Wr1tV*)g(wUN#3WR=0L|%L#pjdG&SN-`q(35X_&>inKOe45zj&{YsfM zl)Br0@r2eOo97wdL^6}r?2@Lfof&CKF15W<#8P`q7@V+VavbJ_WM=B5ACO~A>Eyg0 zwn*rhl)4>6Lod5LB|3hd7{LrcEaXsQ7fBtHsX2Kf$G;n2ygXfq1y?rZQaM^|&Z_s_ zM+9c+l=hG1iuROtoh&S!^sP@zXZOu&8+gCYlrI}i?EpOsZkt%-xb8h)r&FMjTumSn zdqJy&mVfJNf9+4f^AEF+1Jx%jXFc0t)%R=`wAJGVWZG`w5_FQzrsebnbuOmDtc;XQ zr@k2g()rC~UMMZPPL)qvK?&yu?bGJN>kHq289p0u4g^c`n+h``Ti`k$%IYW6aN9nI zBqQ-`kJENB@!Su2Xh(?rF*8uoi2Uj29IP{_=j~mVIZo1NQ`-@d8j;F}X4u(fjtEeUYlYwO7qb zX?_12{#noI>+z4QfZaF4ywrH!8|qb$e@0646n0I1Lg5v7TF-*6J2dtlP4Jk#v%cK2 z;M08lm4oRqHf6v4q*y5LK>d1)hAxpCWUmw&fjvAYCGg0a(B)41Z~aMQoBtGjZjiP) z`5_0Tw|?vH32iQZ$iUi$0W9tIRTP zrI?|NYU=ox=RNE0FHoFO+&K_<+}m4I3X_Rxh9wC7j6z8->Z!9ah2rvlGhV(O z(9AS3S(!YmCte6!?pqIOLZbw*xhyAP(w)F7ToR>k>P2f)J{D6Wc^e>YMuuc~)znLe z#H@(I#UD+*T-m*HK!%RcCz=S_SE8ZTA(^1)P?&A0sN(ZgAVfr`U*W16M@Xp-oQ-ER zc46Z@6VdO(cL?m*QiFW6KdGTocp3BhbQ{%E7A8|8@9La%?gZK z@*_c&kMg6I{FRNW^QJ}{flhCCNZvow+r6?ic*fEsO%!XlRo-Qrvf|`(@dg-FpQ!WBT-LvRu$4Ah2lX6HPWyivi5hz)Fc8W?pTU{l-Pj0 z+kWiZ&(bF&yLr&hs%(tCJ5{!gixzVps6mwq^^iz=Ok0Hd2T24K<~Vv{em8CbtUq}p zU2ENkE>rGly#MQVvHb@$kp3Q#5<3vTDV9>q_heO9Ke}wJ&}R7ON3L%+=UZO?{huu8 z-~L{nQI&#zmqv7NUG$*%Q+kFHm2c{}mj;3leyPfMXOt(|tu}>;TAUk8org`Ty<3k$ z%?j6cn4}DO#B=Mawc2PT))i9_e@gha`%t0i?RIg8W>ics_q{3}X^U?0X=dTR;@y|^ zb4^2LQoLe@lGo*5J&(Q36G+!r$>4 z;&4zpR6Z#>t-}(-kZmBHO~Ce>kp!Zv<7Y_ni|v(9hh{Lx=D2lDx<>XK(bt!8nJEb$ zALHzw8_W3W_XUBffBB-&z(@&&;rhkx7TYW9nwNT&;eMgWnK&r*;dUyh;~oaN$yxe> zYh^tGwSIAEZmmaOjg`e|^Aaa?K2yvA-h!)T>Hu@}p@Ws5lKIwPSAYy?-@Zd(U(ipE zRo=kyb0V0T3g!bo2k5IV9hr&gY2X3+!gr21h~VD!bzPv&jnWdz8YmsLt@bpqpaUrv z_I*PhRp6rq(){7;d&A}a5@9tC?|Ly`4_Z|sPs&L5s+;X0&#tF0)6ch4Oy5c z%5?FIFIxBSZkv6=a|k!U)1AO&CC>upX4o*-dPB9P^pwt&h1Qn3IX02FEE96q>oR5Ujrq8`CsqVdopJ`Oju=g@=Dts? z$m^DCRvOL37qM<{t|@)5dzpEX-GTs^#8dr6b+Kv0JaGcn4N1%scM;woxV_l{`JTLF zIK_$I{vH`TzVY`i_r!_+?pzvWPj8fvJG13nntge2_39nfq#<;n*#^3D>J!t#Bs36P zrZ=|D%2YJD<=^wgHi6RED={_)?-&ax+k$|&QJ@Fg?@0uj_DN#?4+r684@hx73OAw> zdg{@^{AQp)fj0<_*Xw}`nNgT~7{GTjium9YUO8kz`>do7OmqUJ@?ol(FZcQ&1KAB_{^& zC=SS{h@%N*dXAlEeA|UNW(6K!AnyZ*>jl}&1y+{}`xJu3`XJ=E+>t19w)ARGVDw&w ze$OjDVALw7|F22Bf)O$oQ_OZnB3~GLNn`s%kM_kRoH6l_gIr(@{$W|3^cC~hXReME zkPA&5_q!-`)88ASH(AJD9f^1%z}NSc>LvMi_7;~L0~jEOUY|^hrfOA4N*S5+W zJ31uK)|%MadEf7Jw3BY@+EP3Wy(3_bt2fzQ4Gh#hE`(2HR_y*f^7%{s?9Rsgh&b#p zhvujVS>@ybzGv3qdN4m8sPUb=bzSigj8N};lZ~SLTuU zH&$boXk*}rLbj(aXd&lofWb&EV&VgLljcS?u1%FvX z(2?TEXd?~G%)QTx*{B<)7N&@2?@=cKC?BcBF2cOH<}tE2ck8xvwwliF@H`F~XMVd` z%t$%*of7g1@0!W8eomgU4)~J9JNlAuOpWEd4*=6@ z?)B*7egnw?c>+E2KN{gVfK|;4GtURI6|32so*2X|GvZzhTfJcRABYI#5%x7mBHvf0 zMhRc9jIsSBfyZQeUR~W@XQ(5Z7j=C?y-g3*xv<+{3&dIHP8Ntw>4{WV?V9(}sjShW zF#B)(+XACgFBW`bR8V7Q>P4rP^u@9_mqFVl5$ab3_W?mRL28$ZSrQ=5aK)3EQLme+ zq^U{Cg-IoiR5$y&F>xKmRoWJtdzLuvO3Zy-o#J&}T~p4@R$Q7#>Iszfg>NF*KdR>9 zNxV9lKL)8q^yOx5kQ{ zhD_dW2~Nd31z~zVA$~L4DpihTDs5f06WU(6R^1RM_OhdPN?TFghPtpbur1z65X2285cZBQ@YPP*a8&;ib^2Z{b$h9-NB3 zw!^bH$?ueJJ<{rF|G~ZUu)clVN~VgW>RWblDu3(9z?CSNjOzZPXClRhUeY7-S9G>n zP>FYf$W6Q$MX6Ia*Bkd|*0FC1azovWN%tXptvyX0b>G9&9>ez%{aRT!yXW4MOcCTf zs3VFPzg0z1)N=&B(&;$H=)E@1bxFJPTVh>uRnpVMe8rRc;+Xq`-l1bHRW4QQO6FBh zth~t+OfGvuHK$J&QuAbsRn`#W$D5~p!8sZmPK2Vw_4Gwztz*P>Je>rRY~b1lI!heS z48@jA0<1qdFX{5FjyEM}?y_EDwVw>eA>3Z^>wvyV=Ej_>eeilFyt!20rA;90cqcPm zb$<6`NGj^)XbgL!D=L%SHQ;Ca zgNY~45zMr%uueMS%b0Ur^C_>kaj)a(q$h40*!CrAM9^28a4`h z3MdD43WaZLB4YyiKePg_011Z2HLWS>;{Gp2h8V9guu5iP zK8t)gB-Wb95MG*Lu5kA5e;h>*2iQ!-I#Q|>9?(P9CGY?0YtTlatBJ@?hr(A}Oc}&> z(%ME3cbT6Gsd3QMuohC?Ow4+?AFb1t`>!?=ZSd9c7Bf98v8dXJIdJ}vK5>RW0?ucu z-F|&oH)tfDNbj(tZ^C`-3#NHJXi*HjHV@s)x2M4O96-bW}uNFJ?1niccik=o%YF- zGAIW1%6PSOhn6h`+j9V%HScKtBU=j8fIX|Z(UTd*zB zB=U9-vEMdNDM%kYnrEy(VG5rFo=#lmZ_!u>gpHsVhdRMsLp%!=S9S|8ET=K2E=Y(; zJQ>1Re)4DllFg}kNU@F}u~B*oD^bP+14d^#G+aM>@?wtq`Fl|4*YkQ?$SY7zmk%Se ze~d2P|IC8jlt4(RqPtwAzP;EFVo@)DCA7l6(v=UCs@M6q3GXwM;4-}HEz;PIZzZC= zRWAnbX<%VY_|Ra=6sP+!WX6%A89Ul_40iV8dy0(LCu6^8gl+(W!T!ZMQGOR`A2a#k8pchc&*pj`gQDX z7*iK|OW?nf*c+5!hmHQ~i()mg3$8KSVu2L;hQ60OnRI}Mbqi_1OcMH}&(htf!3|<> zQEh6w#65+7^ki%WfVBq-$KmO4Lu7L#v>p!cY9KQ%m$&UcF$`eaaoI4yu-Ah&~ZWi_GU852+kr?xtX**u1uNXEW#p zvOHZ+wifW6Xbs5?56xkaz4Bnqye@UN@I)EKV(gFY(3J1a%RcCFaSnowcw&;;eD(-D z#J(?-&o)!%29(ohE&~an@WR{_hSu7EVh8bdO!N?Hxno#JH|y@Un8CUiUu)4nR@l!m zkrw2f#2f#-N|V44+kSEyIN~C!L4b{c3j8G2PW9)h0aYLPq!`|Df?v2nYOxN9viPOt zr99HZg4gH4WFL0M)QK4{pSh z4vY1hZDjp2vT0M5fPbud@E+vW32eLt}nO^`R&S947G2-+;)QNQb4i6Hg1Emw77}g1(U!l3krv`{=atGSrEu_$axw1DmS_R8yD|`i zogl4G#HT;J$`1B9+*KlV@&fM*vB9d4e;2l!HeNzRB8jzFJGr|2l&~2p2?(H*oQV9X z*2>4f$e~#Ur_jqRDuHdfac3WrOp8q3z)=|6ek{$U3u!U9N*7z+q)-{JWAJgj1|inH zCRF~7bU1s2rkU4mx)!IjWL1QOJo_(P)32h7B!;8x1JH*h?>2fs$QnE z_jWmC%TMadcFVl4R!V4T602-{V`2yj zJu&@L8`CwWq$*g=#g>xCE~2?n0%+H&dn=)vy@xP}0}BEx#p4$VBod z-xtmcr8pL68&glC($4TsM`qSA&Uv|wmE}ApX+`~ZbemQ>)5{+sGopZD!i;LJcEG>foy^j{8lrqrwl!7Rhl&Y_u!qKN<3pajcKqitq z`eH#ckK;qHlDnD~$}Bx9bC@T>M%!l#06LN(->X*8WX|^AD@de^61_@o`u80%LK(BK z(avl;)_O;_LjBLR5qTe)vmli&fP)~yG_hvhI0E%eg7aR4a4cqR^s<;*4G{8^VpLk4 zX0DerDhD}8C*Tu_MJhHyuQ``=LK2s+XyS%(fTr{+iBakQa}>=|iq#Qvf;)Tr9eeha zgyU5F0}yInb$D$(b&UENMVk~R;(7v82d86I-PlyTpFS!aoEmjDy)t$4o9xYl)2bg) zBCX!reMzVY1eNw+x?zO+In>I=vBfkIjSxD}vL#A89lTr+`Z@coyit`eK)q#os@QLe zDLGth$Xe3f`p-T$u)!?l`AJ0$Z7nSr2p_i3bfS1kf9v&8Z_zMzo^%VDI93@LY38heGs2#tA6EEOm{8t*3g zF+MVd=HwI?9c*hVnGCdLR`$rW3Mo^G)()qwn{L2WRyF-oo1G#4r0G$#5@Z;X{v~WH z-XlL~Ngc!0Q~vz`aeKU!*&3_hE-yhI{U`+{4bZYu+8^C~JR?UcvHFkkQKprR8OyZm zpJbRN%1yeO9+elZYv_kHW@g)1xRBnJ(l-N?^u#IXei#Pdk;nA#8*o%JG7MvsC&-st ztt++>XnWvE7}KEGbO}yqz({(#uE0uX>bC+5cCsP(GLb<6q>ySj%`^ZgV*t*(RMhp$ zej&1yR=j~>hLjNM&1a^6XR0B+xz>y;*r_H?CTETIN16DBp9UwK2P$3NtO*5lxJYeM za@3r`R1`Uhf5--be&|Xq%S$z(mp2P(hGWgBsI>xf(p$A&-XMPFX?|pkKT8LLxh{Yt z>AkD`=11KO@Eb`XhVC#GubO|GpLGQV*k;4hGI)qoT1;LPB-olwnrJ6!|HnAC)zGu* z{=fc3Ld75?qpJx_(|R~djSuejA;ae<3)`kuW06 zU_EockEO+wUS>#DvQ(O2FyDCe_Sl{jX&vg%2%dVKO&4> zr%cH&$L0r$A&aGLvaAAABMFjU`)ze%PdyWqS<>hXRBZi_+z}B%g z-&k}y25#K7xaj`-K~s7cRgjvlm0z1!t`_|eVc!TQXV9HYc4JuY1&200zf2WWHH4Qd zuhyk&S(g4iJ<}SCHV8@`os$WJk@0h^y2)&Q;Q=8^_cuyK7* zL5J5d4o#fP{5}m~@Rit^u_c8?iBveULT6E1=-+f`G3_I|^jZ0n1O<&*={a2*zia&i z{YtDMeL$9$ET7@Kj(kjuj0c`;v3?c+P#;(8zwj?@#P|j*~#)RsA~hS==rQS zSu3l~bA2Y-B^AH{9(LeoA+wd;+rK_25EVe~RI*g^u+mVR zOl|}?aSfZqH9tSFl6z%j&|E7tNO*H{kjXNS9lr!xf|<+Q+@n}*OA)NcGtEXJx}h@{ z-}wS;RloSB6LwO3rfQ3xyvcDXctq<9)S9>w>9F(9YMF;rbRPnIr=wXmat;YJk6PX$ zO5w3OYsq-Y!xjV>_xL(Y@o{Yy7E&S4v8v%hf?!vfe4SRtn5d`d4sL+CSvLREb3kCBv0w{aR-Cs+MPBqWA~Q*R#D1i0^Wc-VmX9GTBJU`p0Vo&`Y+{TJ5#&N?bt0Q zTdQM{`qdC=m=cV(5^>maX8u;x%`f=dH)s$rlp=ki5d%yc36j}nvi*Uu4I&cp@cmZb zSx97ij=QzCElh@FeB>}H_K{s;>@5Si89)?gVVFyI+siWi&AZNkGSrEMwOR{)6MI}H z5_k$Blq~_XSYh|95|wCGI$f2vR?yoxm4Hk*nbwYzY-h5QenWWd{A?oBVhyY*!GI|z z1~Ie7BNV_0n9Q~wW;?GxQINK-mti{4A7rzAWu`6h(hXz=1tkp&EX`tv%tkHQIwiQZ zI>8mO%JkUjUUbi99{_kqjH))6jrV~{{^RPcz`=||Ym*Hj+tVw4!BZ)+_JOl=iUhVQ4 zcNnFi{mi4VGz^=UZ-sau_VfYBaqR%x-tqvF5bXo8d}eoar}0lKt{7D!0uwZ{&=Toz z`VGHLA%sYQm8$GSOfAju@a5?meKag!_KE)@oMCDVIn3Y17Rw=;X&4;FniyomLye36 z6HB#mE}9pZlGxZCtQ>-eaPqAwXCx6rs;oH)C3MbMr>gZ4%fnS*8sEIyR!t<;vMb>a z7F@Bg_`vj6m^b^tUA_!!*?90ZkWF@nQYVUUrx4>*Qcs>!*)kH_N`PnKDV_0Lg+}aH zx+BU2Ljto~9747_BPvt$hgvf~lCO7?6B5qaKmxlG2>ntjfRAQ#t}nnKP}ewxyyu+4 zMjPn`vKoZX_#@9OkpPQt@D!{qtLP$}nUAZe(+%S?n1cDgMU{Uc|vbBf#58GYl zq6~g<87eq$a@+wCCDQQfFz>efN5r1#xuA1KGN4tQrZ28z33fPM&qQv8kdRD{T|VcR zV3F7)P?mTS0Dc8T#)mwOEGc=8OkfUmzB4%fI_O$1uzw?L0+i_WHcySEOooEl6gIpq z+9Dgqv}DyR45CIZy@RRkI${wGa=dim;{<8T-0v%Kr7iZ!d7gTpk zOAQWnkQ8j$+h9kN^<+8(77~XM=a_PBBogW1&!`{}8K}X5ON2SV;_%I|RhdTq6uu9e z!n_ai(Zo4MB&lWEvWP{j7GTb`v9ULB&oIL%&{BQMu-JG9y#E7NVi_gBudV8UNK_g~ z5WAL#tsPMJ84&Kd^CFl06xg>Q7jMihI6eBg^el_XtI<4F`%~O{K+;D zQ_g2sv7?~ zGId-vA58FjK)70N#croYW zdAik2NH=gwjlscV0`(X#0&p+UAyN$v0hYzpX5+AbSuU--{f0cNfmp0nd4J2PET6#L zspEi=7-WnQfuG_2rN2W>673;=BPy_1y$~q@4jK0sR9ZE08jcH<7ZN%vMiCzy0Amj0 zhuqZwLQ7TDYWBu?TPhzDV?4Z9Ll)TVW@JK@1}><*Ld za~f4#2`q^xDJ=0~q!;PcsBXYs@*#8&eG;qlWYq@qLXk!y0LnW_hpA?fj>Qxrw zU?=z(;9V(+7^j4-OX7$&7u&@bBB8Pv4js3Vn&cr@tAo2Cn+Z?d!AJ78IgKqJ?Q2pP zrxbBrLOCSY{Iiu>P*vvKv$W={YDgv$WG@Y|rH}`OmbXx>BVFccZJ2{`GWN&$=$4Ti zee97)7EkvD7inX?1@<_{0om%HawJL(Cjsn&W2TNsZ4p*bcd1x`oQ3$K@U=dcLQab7 zgWiLjcFsm65fnd+6m?b7V{B~lkJi;8y%^zGGAyK_y3^#bS95e#``t3Y_6;vo=J%kRnb~!%4zLHA7iQ zzX#t)ykzz!M{>}I;1ddCR4tAYYeR%cSpP-tkLEb^sj(rnw8#Xbcf%7V`ba(q-)Q$y z2c<@yv!fK?;OQ(gqPEmVI5uu>Ej%j`(=^HU6vSYIOGZX;kaoOvGd5_f^)(H3BCLl1 z7dt^*!@^XyCyb$FP41H!W>%kG99al<-NNh5){Lnn9HJh=7qdBkOo;s*wgGuGsS4pR zju7EZR9Y7xB~{!jC06{R;OKXjRTsNd5-1szGqEJ~oh6Rj@+zWF+9N8ew7C#WvJpyC ze4OlKt?*9VO&#D5RlsNOGAmRy&PhUvh`F(v8?QhbjHgIpG_D=t!a$&1SjLP>z2;SB zZKx|&7Z~lesYBsROo{QQ2y3R0X#7eC*Wl+VLQ@l{C_EA1SRsE-Vk4}4V`3Z%8I%?+ z4oE7=eJ-6kO)#+17z(D8A z0t5R7IUc95Me`#y8Z9aASRFg75HHCg>Q1n#R)_W$MN-^^4K0wXCvm0XNa+IqMtDz( zTf}v0cIe(%V;tll^5JqvlRyZ^NX^kkMtE4QlBJwOI2Gq4>CjwUl|*oI@!3=Ya9WH6 zWV>T5G$ukNMkb41ZFk7G_#UE?Xep5z)o^n~8TSLA0`#5o)`#{qfw_>Ft8Aez+Uh;y`ZJRlKnkwKY5$RUGOAhBjRS~^vf+M7ldeJX1@#QndG$7%O&{zp2K%UK95G?Wp&^DlxiJ-7bkVdzH&M~FrEfim(8~fv0 zz#;r2T7h)F7fvSgkU$Sj!yNNla^p6U&LQ*ba$eXh_>o5R4lvL}`+E z5pP15C6dHrn7u5eOI?E!oQ>o(1QN3&)L0oCt4h|Fi`ORp%oJcVt?APk8hVoagD>Wd z$Vr{}tzjY=IZ1+HaS*@dtP!0e&%-5BVI|vZYc~TLk!nm*GN-oYmDou2i_nJTA4MR@ zX(Jl~M|#!wcmRhpbEp(!gL6mEC=J{6wSnK7xgj87bb~=ns#a`lXFhJ$21O<0RDXd} zB%emuNi@veWE!d6prZIBd@I(h*2blJ^G(T^uNg6@C?e@POv9$)9P(Ki1KY7s%wkp^ zSG3WHB+R3POlgh(AVfkLNx2QY!FXzatyE9L z7$ZYdu8cR}C2gLIE-S+uYhs)`RVkr**x;fPX@gV91gXEZ!LunQl{Dv%K+t!mI9w9r z)#%_gsaC{o4iY{$t7>y-aucptScCr4S4~X2nXxAcqK$~Zjtu zWz==713)pZ8|HjrbI3j&yV^)9i4f6=4Wu%gf;?qOMdo0P)&Gg4w7tm*Ep7 z(i+W3B%gvhJNdpnhtegD6D#Xjh(MxM1v-Qnh$^uLAzoZq>DJEmQLPSN+gdCPlHioB z&{n9lh=qI#?ZQH&*lfwEFc)wc`=V5We?mc>N*3dq_@VT*pc41NLsNWPj3m(t5D3d75nC7s^y{MM%fW7NSV>le=?P{Eo@nV(P(pfC2(B=9=KvJ zuIUGw%CDe>&H(~z0ZEcsIBCTN%HfzqzE@RVJyFZCPj`??V~`b4EkHrpQe`QpSZE^_ zmRVBzad0@ZvIIO(h?HSRRbma%$Oal=zwLkI(+lJ?d@HCSU#8C2F+N`vb8J9kPU9x9 ziAZzb1a>$}TnYK15oE;{s>J5=tmj_!JCgMwW}|+$1q10h#Pd|vVJNyyYFgx#V3E2q z0?dSpSRVd`X*eQ!D8Z^|7?L@OtL3pbON9xfjK4@y%m2<4!c^;G(WfJSD4B8&cStnx z_^9e;coKyaeF$lo&7!BU)&i{m!Bmo&G=kS9ZY_offljMB@eMi~#BhQ-t&TAO zW6CT%3?yMTh>z?+5INM8Sz4y9Y(_d$xmq0?;H|ArmIwyotw3v41q%=D@1T#A(17W`^q<&hB@cpr3xMEg6`R9z%Ln+Eq@}c2VaJle zIgMg;P&&pfsJ$>t#Y|0RBY`@_W2-)5hhR?@)vS;d3DRK7>N!kMkxv^6MHUcv3~V6~ z=VLuQN&?pU%W}F{94xO5jU?+Fq!0r#r%<_QOAXX@2)MBmWtWPVWG%(2-85+U#|KE{ z-%8$Nb8@7k#cNP8qRfMBrl-l5+#HA58~jT;RBHYwNFkx)oIkpza~Dq>)pk2$<2q9aVCctCpx<63S-G4W~*+Y;h@ zGkt7>U;z@z(UD0ED=|2(I#Fm@0WP24kwsu7vXm|n4m0mI7O51{lcIx+dNCGGaFFHH zMm#7o+9(=dY5@Vs6fVZ*i|mS8lVeX+O!3U7M|50lNH#MJqeD!_gbj<)mcXYMUX2YQ z3|UcHlimy}t{p>8EKb#g|4M>QDTq24M$B?IzS$tGS7Zw@#S~&ZHLJ22+8&J*Dv@ByS$KHH z#q6`BZ361>SWPoo^!1YCU&0%68YC!bhAC)nuxrP4(Gq{sH&{e8Zb5TWMhok3V}z}# zBT)FbMmIKN+p>|K6xI|QWhf6hv|&VrIEP?>w2bJYlTUp!kVADSU{0~z)_Nn)Ln2XO zzC0YXTb_tJE|HWm3+ZBM&?#!jRYT5fsm-&JW)S1z3QBnv14>VXr&wK@jZh))jHMy2 zne$JDluas}m=%QSN#taafiF5tycfX^1(?RpP{1Il6(!^YvExS>*hXE8wX*+fql56; znqUikscekxvGr!EN8wEsoBnp_6FXxiGCrutfXS?P5R=jD$6;VtmG^$E^lLX#mSUe>5|PhxfQ z$qZ=%J;L-_&6vJvmIm9EpeGLPHtYB!JBn0!y;LQTfhS~%zPJ^{tukh=0-@D3e@`J! zP9&9C8|0JvB-R)n+awB4vhfp}cj2wb#rOcVs4i@bC&8$YSC!hROz%!gL0Q+P;cbcp z4i-Y2`eKL9T3GWx{{NXflO$J?BTe5W*IgwsAOZl-!5ft1vXWe|7Ipjnezj5E4Q8(H zU`q!n%w)U>JX6#8*THak?OIkwpD)&>xkJf(SjODQj&Wl9UdKNRT& zu0f~*K$#4gTgBkDe{)Y{XI_m&GBIo{*%2Lt5SBhigICB1#Q?)9bNQxEiO*pE;3hHC z!{uXN8EYadrt8>9+_lEaUIX966na{f?$enwgTBF_2No9av1g(BpM@< z3|*KMoeR`uBnBc=jYTAb098VfM~vKAS1=Ftjk_%X)}?~Wq|V24CIgK;Ga*mmEM|7B zYfJ;q#A5_wS;&wutz(ez;SWeD2b|o-0*VBMH)5+T6wqD4J9-6xYiYSl(9VvL=cJVo zG@_D-5%3C@A8^qcOYCssqh!hkpN?`;n8z-;AZ0otRfsYzMp*|?Q6RtIdosz!OfqqerGjgB1rGf&aeyk8>f{vKMR;@jPez#J zMEGbvL~jresyI}1ZS$d|ihd1#Cx2udKQ z7T@7&(wD#;({B~7FgxUNvjX-?;vfTqEvr?PolrzNOPvrM#G;}^M&vGQ zZoEtxrM089&`uvi9}A4bi_oTmY$UI%PB_wOVt@Dy*Ln+^s{m)xW@5wzvg0_ZLX9Q1 zSWGTB1uI0NL@vU+?JGf7FBvHc2_YEwBeqGOl77Pmb?T>-lA~v%IwHf+0N1#v132u% zdJwc?5#(2(c;X}eQ{7ZTEa=wk&{YyDEzv_Ix_Lkmsn#;EWmQJx#`qR$0R9G^tg$BH zR6P?@LU~RfsUIv#jvl@O&?dAb8h}W;&~-GrylMN=VrsaVadX4xR8*x)$*rz5@<{Ly zc(tWtt@RlQ2T%y5X5<&YRzjVGK4RjCe!$-2Y6zgYpbpjMP2lQx6t?ClJ_A@MQ*Q1`-+Ix(dR zh|<&lMfRgoQ$h~4N?z?L00YXEGat#LWoUM*DiewF6fjc7IJDB(s5Tdj48}*|(81(5 z7S$%Hqn|*LWyt4oYHw=PsHY8!{QU@1a`?!hH~}rFAm$*k5c0_8(I@)j@f6#mx-d^Jfcwb?ixP*J+ga3kJxfT(Kc zKwLzZlj7dUaPb_3)+t0xNxu{h%L5O!{SF)wN8YN9W@KzXCEn6G{4t53#&l??k&v#O zvYtvZs?99|lu5hd!+%`=%2_x&qgE+ABBD*jF}VsYu^|G{7CYgFSxA$ef#2jGfPJoF zEU!So$InvxN>yiheL9H*1F?Gq)6kn4VddIo@)dU!gj;>bQ0UAHa)_75Z!+GWKz^`#y3!29 zCf@Ewr(rY=9E5W!V)piv+?IxL0w1CR^|F}0@(pECT9>0Gkhg+M=7dS6Rjr{XBy>4E z?O6yErWMrG1i5A7phm?|HzFLoM_x2qvZYrPl15;ts1uPlaBTY=sH4M{d<^6ivb*Je zW?_WXVtV2#h?E4JJY^J+d<2!`EhlnN%4um4g$Fu9647R1u(%jU&q4%Ls}JaGK~S?2 z!dO+c_+(g))9ID)O1`A&yW5;^@}H=gV#60k)QKptrn=8EpVxzi0r~hY@{=XfR?U# za!6ZN=R%n;^=2y&j+3|?nclFG%#Gj+vnLcgX98GN`8{OJDh?K!G-ETSQ5YR@np(=S z#OYVKJvCne^GFd&Wk769#zx@c-)3v@YXNHt^k*SI^8*;d4EFL5+XkwD zO)WP96rWnaU2F~d>vJY3#80Rn0DDWQmZDgdn^Ho7J;lW&3bU;ta6r~h zz-xdZ3j+I)1`(xxs6JFQD1pG5FaXcT0@AalJu2SND4wD7$i-~X2mB#uhl&LUPeQ6- zlzW4<1Qqz7L?5Qh))r9w;bZJE^jHfj&TSF1c@AO>OP97h}TH(Xq%vc3BY-ZH2JQq@DW)M%Y3^l8#5s?tRk z+zQPQQUI29izfvIV0-Z_d;}Ll7?eoF(Gq#$6tx)u0dWlrSE3p{%M&4y?2Ym>#)XPu zzI{zo$}(!{0OX|a8jUHg(L}s2HGy?dSYh&r%!{I2wlqYwDh9w+(s&%~yE+z_FoI*yhm`&?+qTz>ppL%I?hq5$STmou8Q$y1OU>aFH(<|zmOLu}3(!?8Igl;&P zjiCV{AxMaioDj;dyoED0Xgpytu8Y_?TTMib5Qipbt{?op@UR3m#42QH5AP1?FxoI6d4P2!PFFY*he&bQ=jFq!hx4mxRV&zW5E2aaeR&7K4M7K zT&OMxhE9km6Q{71fcrpes@~)7(|21qW8+*dUL)zZJsLtUK+F??_*XRyX$YQb6FEvx zValFPp}>@*7k1Pe8B_(?6bp&86N!M^!aA`v6fbgvtOec0$|w=p=%A*4sklH5#NX5MQF9`wT10LGRsxT5u}aKyK2BSVxS)_r zh)n?%mz3JpLp5$>7mrjBx{>dzL4kOr3r|xHMa%*I5$7guAmI3=k~n^FeWKxf26PE6 zCGW!%psU$L_R)6moB8uEn;jP1#;vNH1p5<8c`q46 zIc>SSob5NW0~FfrowWE3qe@o;VG<&tA!8F)1*{5qG+K?7b@AH;&<2cYVOYJanq#CP z3Li)go{lD;rj(sz zNkZNa#C@P>!!v;ya5I}Wququ`P zH+)p0A&`yO4~nutfU1(Rz(w3IKQM@L(1a5?zdms;tDZ>97fGZDxVRk?v6SfPRX@sz z$YthZH8|U~lOAThF z&?E?;^DW~Q!#0S27eu;HN8k<68G#EKUp|_lF6b8tA3-%Ar|_DRwn~pG2XD4cijP8X zK)19RpA{>GMuUOK(m@x5Q*De6Xn-2xy6p zmnbeeW7y<;ILNXuB-@*`auVa}oTDIS)p-zR{9_>zWn*m|y_U2i!OC~p8w$`1o9gA1 zfQ&&9S$t%MIi@UO1S}FcDA#fTkKk}zY~iNzh7b_O$Rg1mS7=mS1VOcM92=3MM!3Qb{{N08Cp+&~2K$p1JlYL*7$DNJ8W z4^kLsNC)5J(g`FmN9ofuSWMOkzDEcfPd9XH5p$#JBGQHGsjEHHsG=aILk$@k&pSY) zYKu4s=!E`^xFHBiNzH9wY`4!z@Yp_eUl(uCXB){B;fHw?I zmISm@BUKuaQ(dnM#8rqBf=*@cM19zrDi7yV#3FExkWc)|UeTIlDB-G&M1fLkRwT5c zQE0GXQXYr$tAGl!O?8jUy;{?bdTIdqutsG>F&i816j+Ct@Pwe!02$#U(XbK@@;ad{ znTzUlA`8OSOHf^DYD}bZBehl&sS>LqhUtT3ONoIo&S1Pb;3FdTuYWl=m6NMq7fnhm*p{9nlhN(yt;+G!0pI3M)rQg$rFr}J33poX1 zsTQh4q0&P=b_Cji@|JFmYHDyA*rD+BGbDzlpY`_%+!tgZh%1BC$e;D2~Kg-TTy zEw+I>0IZ&kipw=P42-S_J`st6@}okybb-$ECu4I4wt+@m`J9c;+F*Xk8Pxs8=`$Az zbI=v4SH|!=;poaRJ0@SxWPWDxn_I4u6g4H$*o0u{n88O0{*Cd|XqI z*gN&dn%{>)!7}R6R2yo8G|bZI-2tTAGf@k)1hxWBsp_BOH*QFiNP^TcseJ_%V?!Q^ zE+DN@Oap_4tDckDTN}-JV+l1%r8FVah*+8VpkJmDh_M-OV6-7`jp^Iklj8CT)$uw6 z6MUFv`E+~0uof-iOQ^|VlH;~UdmZNFc`kDEh!z%}Ng=4rIi6P-S2}WiX__%$6l0i?va$9kxf;Omagi%pZ39oQ5QdfLiGU%a^i| z5SoO%5tw5p_~*vhAjHU`12u>HzJIc z)96=C(hwx{Li>4WbkE5Ynx=X^<7#wxBc55v`t4F~8JhgQhVs=z2Pmvblz*?yfh{2- zM=`3fHvw-7yjXcVpt0MaB?<}S^+1E#+?(hB_e5`)!4Q3;j9)8S)RchJCyO5vh>_f+ z{J2GuesDwrfTW6Si$MnXza*EG#NQR43QU^oB0ivN@*Cl&m}DYq+$H8vk6;d1=ytuq zMCF@cS@ep~=uU)_OpCx&L0klN-~rX(T!a`^HCaN8j>utE3W?(jH>YOCeEqNoA;g_& zR&hrokfA!~)j&t0YqtU(u5K%wF9r?vW|P`ec%ncIg(~Y!O{!<(sMJrQz+eUTht_b8 zw$?l??U-lUSQ1et~w(}(F5T{KQDSDn-)8sLr1MA89Hbny2@h~$D0))MJ6aP3=gg#t? zA8iMdk*^k7Y{dF({P)|z&NV&nJ z(yOk(h3aEamO#8lqTUf$wnrkl4$7b)pcIjLFU(82B@#nSfiNm6+ouYw);+}1B(J#kz&%t{(^(X7X3QNWBJNZ0fk5mRrx9%*q(*7O2%`1lJA9__J|_r zh2G1M`g83`<){l&TmY#+gJ?79Dl}@%!0@A~evA+HV=uv%a29f>qMIAT31Rg>J&=ZC zk$XdPP7whg7D$apqrlKO1{s~rW#rLptwaLn1RkXofu0iMqna`eQp7ZYvN{O`&C=cn zfzq06&$6y{_4L~?-T~sZUmM9~VXDKi431|(p@S1OEKGQ%I-eTevw%Ubntka4HUK5!1gwzC9c5W3Q{s<~LF!m{X{emh|^r8vJ z+U9~pE-S)L8A0aJ8_J^Oi7K%qMN++xf`(RvVQ6yyNohT$Ujv2r>mvzU5D4lZbX~Dg zBH2yBHhPGP;9YepxAZI-({mLJ%C8G+>PR$z45u#$LY6g=NLw$*LXp(4mY(gwkYFHF zGnmkP@A(1S)R}?1qE8C!K5-E{O$|@h2&o?xF^Cf4sRaPIPQKZL-qzUK>)Skp%|+^Z}v$5Jmn?@n22x!?-0tfUMVLR5>xep!D>nh=wsaC zEGxp!;%Kr)wJ-#U|0!-mgO?acwW9$il^*G2aj2PUfuybUs_hv({|8ObEtX7jlk(DBgYa*uNEw6>xW2eY95+|``LZ?z(nLgV!Xkew{1mfrBY;*+D zK}32EDyI7;+eqpNLrqSVegLO;RbewYwECf6I$M)f!XCm|YQG9qKf@jXCVbeP$a$nQK%%AM(lWd0MA}l+vFfe-hfcbIM7i^a><@k zRWrDkJoS}cyhZP{wvm1f`*iCi!s<{+=FicGI476I;oj)bS%5p!a|2|EbRkt5FqS`rs0a#$=oGqy+ZX8_?!t}F~tuZFFbBye?Fsi8h?V8H1ENR<$r^q3HlC>@jokCcf_ zsYgy6sq@E)1QeZf(h*6UuNEho;SiB2d54GO$_zmuPI{=MD-vUSG##h9jZ2TY1F0S{ z0!1UR$-F*`_9S~Rju9SOQ%a>HQF);|43EAruwGsjbRk{z^ikV|x*YKUEaKP%r!oFa zxLqX{vx3&Kidh!KF%#9}x{O99SP2(QEU1i-ToDB0VoFgi86RRHC7m?JhZk+Am3QSw zob^Er_2LX!5Du1VTMDYdnO;z-taG?-Qdt^d4;CJr3o&IhO~NmWtATK03QcR+_e$%A zVm~^~?m>B`fFTbjT3=kZ*0F|1ltQ0a^`BD&ZS#c2dXw2kEk zl@j&fcLW!-pg>&1T3P#%R;1APuCb`ZO$0=dke1|Y>yQf!a<)a(A7>{<@F1mjJmq}s zZ&9|Onsy0dF^}>ND5e(Ic7(z)&7&fg-Tq1YBn_c(&EWoq&6dbO9g@mXFwkUZC2#gN zC_L+ra;|$Euu%zzOoVEv0xeRx_0NK=7?qD$q%IUeZfJ zs+bemOk6@{Xi-pXDnH(BqD*vRPjN~zYm~2Q5X9#|lqNSB*2<2v#6Z@5j$w#*kl~CE z2egSyvI)=-n2K4{emheuOcFj-nhP2PXPg}xlL;j(5W~+Bg^|!@V@n{X$`RnFCMG&& zS`dVJ#sY-5QIbq7k>zTL5)Tk`vPj|}4Qq*oAWIV&r zA`y7p3;_bcGuEN*7jiSSKlzkC3Oa}Q5FZ{jw{|!ZTq@#NeM})+DN3*>L8i{ejU&!^ zF`5N?$p{gsc3Ua!gZKr09k9ek#tU4al#}iP0!h+5k87nU=v2K9)Q}{t9PdGEr71vGS?v1W}$B zwm$gv1(n|VXkQ(z)!0|^Csh=6Vr`G(V5$Lv%cu{@=_UPT=x-P58I?3+V@qjL(abB* zZKe`%mw`Eo5fEMgylQ^59f*GBc;GIZJvXvjW>S>oZ_)%m|IBs}I`O4~^tC{Q?xsU@ zs^7)NjpTrHSAh~Qf!G@MWM4$@O^N|xM&<-mNmRKY)Egiy3AK0fEl9;vR(OQ03b7)z zfe*qkjiGZBgu%qkl9&T3@b5VeqKO+@Y7><-J--cf#?LMMiKkPWPslZ8JM_X`mRo>I zVotJb0(xS5pNSC%(IQWbfKoL}s}VwBp5)*fD$7z!B1g%SfXWbh`=$edPW6@{dKg#JBfQQ{om!-kN*$~`09mLqTP;vZo;ngS#|SM0lp5E;r6nRY;X%_cA(6_0 zZVcHhkTyyF#`~_pAr@463#3=uY+nq2AJwSBNnE_TTL`d=@|vKwkq$vvuzmq4>%sx`tP-}xymEti`NJc-1 zWFZ^ReTYbMHf$L2s-Tq`{y+ifu4-nC9CHgvVp|>toJg<~5A(1W3o5-@0=3~$NO?I8 z)aIO8Iie68;tY~V-0;r&5bpS>T@_fGbY)O!@~IMw-31NRh^4B$ys_;C0 z4ibfZR=&>PP%Jm!;EH5+Falhl4X4K{vwZG?NN0B_xf%L_>DSmvDY6p~Q0OD|!t&CD zw227BctKsBm8xpWb`jwV8MX)tGfT6bQa7>{SZv>I@DJR@-`MhI zNFlPMT?7M~xy>!aSUi#?njf?~oEFullL>o9ys^2Slh8xe2d-(qP`)ZkzDTy}dg|XT z-A{eeMXDEvxU^M!&PY!qW`&Lh;2+!~^|xfqoX(tP=D4=Xa+EaV?v@pkAb4a z0zCQN_E5$0N{L$suw)eiFdqM2ic9o?Dkw(j)e%#MNQ&_xGNvj)yGEQ)BC4^4VjbII0wtzA=#%D~YWse}{*iEY_ zB`c;)o|+*ct_83x4f@sm0Pj+&4lkJjv<9b{bJOdldc`$!qiBU#qVRJ_XUn-ZJ1xy^ z;6*44XfuF{FNI1HO)>%6?zF2U8`<6fovFI3P#mF=V26ejv{0x;Db@;3MJLI%WR?hK zH};1#jO=V3W{G}q9NnwU#!CQsYAd)D^puFI&_ zhlp2BCf@C%t*(psZo^4+b&@9`mbCkzS9TCt9Ru(%9c0p_RFaYP7euNG#HSH2fp->x zwQL%rrmkP?Sr*u4d{l?}4!cZZl2xqkZI65$CqSjp!JbOeX|<55{9JaiH`@c&x4~ld zDfFL_a)BW6L0K);h>y2a52MxxJGD$H*9qgJWGQ4|N!`&7axTrLX7j4T71Cs}8fM6^ z@3!rhKqelE)#^PJmnn%M_y}z>J%n#~B=80R56Dac>tY`o+M+s{lJfvSKIOQE_Ii3n{g_M z?<1B6e~cCZAA%APGiA#I12~um5@M{Mq)U%Lg?*OSMPd3Ck^;i zd^BWFRF}9$^rn3fN^h{!fPhJ2i|HYk#Vlb8;#88v&8hUZ2TmbP(M7M91?`FV{74BFe#8-p zIaZKE=L=1Da576QK^mbt;1pn^S}R@PV+CcUX8mzZbmf$H! zD6*afLkN<=x>~a;^J>&rGi1v!aX@i?QVR}QA(>AQ5w>!XQr5lqYyhWR@T(?ZZUg<8&&+o5t~5elhb5H%4E z&=-ur<{Xfo7#&(^K8b$moe+`OA9@hrJb8#0SU!kQRvaCjf%rP{fv+NV-99 ze!`ELU=fKx=0tAH59xXuxFY_+v87|E36R8E;kr5}n$MK=A<))7)(@X#YLOe>2PZ<7 zLnxFbLdzO7=Ve8%JW-pB4>n3wYi>9`a-r^p1)1LX2x8LuM(GovRLSR=4HoK235T%F zSKEa}D)rd(`_Se?AVqqnTn2C^Ul^BVBhN%2w2qW&Nlw7jXJC`Xaix?`o+{;*o5ZaI zDYPuhpX3lovxUIKU>s;5o`Cv7!luwV$azI5)I$|sRtQPvC&>+QpW;SzQ_uWKVQUD4 z+MZjHsW^B+sJA|(nRqnZ8D#)+{B#Tu12vZs%czf~r6v~t5VZpuZ1hs=cR;H!&BQWJYeNKcvn(LSoxs_HTEM*kdzeJ>&?waVpIzUzA z14|&jEz)Y%M}6v4KHJ1aB2+^-m}|x{KuxkdU|tDp!2t=1HQ1KEof0rxlZn*^mJh2X z#gzr28|#D8sNW8xA6&kaGWZUN4Y?CID@iEITIl3Lz^H|OY(pPRi5g5WGQgXNX{HFg zfrvoDq6KdS87cUWpcLBUA8{~`i;e}e^hwYtN1zSfg~`i01yDe%p$4CjWkmM~p=!~m z9)*4?rZ241ST4{#n$9gyGHM*f9^g#LvvEOjhSGmBm)wndk};{i2MjLHpF%SNPd(tl zu?g?AJki)$!yia-OEXPu!E*U6%Av#*ZF&~TAnK=wSW|pRZlbccLCjKzhb{m+m)@jq z>eK1)4MgS)_aas}$U-Krl(-xFLHMWPucEfP|FW*HTi`RXLsAL&MkJ-y+G6E=40Og0 z2{E2~O;0Dm9A3l_ay5$-Pe80d_yUViwlb@Rm+#0#>wNuPG2=GWqh(WXWD#Bw0fQWt z-~(KrRE5&1N}MM`J1*3Eca- zNA`+ZF0pp6mc%4vLzo!tJJZV~iAsU}5Jwb_F6BX4FS2_g>8#PhDXlwfVbC?AUQ>5ZMwG(cj^kO@4-RY%4nJUVwJC9OOx~|#0SLP+TQ8>t> z)EXm`Fh{uq93u*&R-W4c2+j#*H8rF<11VH8jtfdD@hQ|3lnqW&&{@idQV0z8V7|7n z^bD;;r$tfLOgX_5sT#zMMY?Z+aNmpkD96Xrq;==K8b_|kD-m>L>j~snWg`h z5r6QD<3>n_69S?=DS&utXU{f>m|YU9jv3IqoKtyr_Hmv*NV_d?z(6VrfOC3+xS-U0 zlyXf%taM#{ID4w9$q+|`mz1Q5e?hK<>!^O7Ob}oWSv6U&1iI$@j>;V`tzlIAbZ|}p zm5CsL=YPX;D%D_DRFZRd8yl(QC}bxR0CP?>TFDMjgFnKb#NFdQSNK{o&Ut}wlNXx&V8c+o-wm>uc%(3l}NNCmy?2CT`2a6h7?Bt4- zZNsQer%^8eT6N!HHR^4vW+&d*ms-EqbmB+YMX~*)v}Uw@QsS{b zfnio{K#funN;aJ;2I=22ZTuraB6B9@-?kgG530YOXH^$ zW3Muw!WnU8R;SeW=olps#iHWu4lvGsg`Y-0z+-c*%f88&3aL32?L0qK?#Q~Fv2#)B zBtKoLAbz)_5OdYr)~iDdzy%Z_DFCzb(WQ=ZE%J29B4KDrp9|c_OTqMmbG!byX##9;Oon=Lz3EU~fs3^wAW%)=v z%@xcO03JBha@Ol!D3!S(=+e88vgNpkq?^i_=%SQojJOcX677b~DJNPr!ccMQIGK*70Vte4IGPpJ zEh}sk=E|zNb{dJ`dX9_frlbMD4A5%W?S{zQIYDH5kxF!b5$WuyR2KmFp;p6CV-asv zP{3L%;-upzIS}v={Fu;poEnhojz-*uSuO3tPi7g}5Lg6srWS2frA1lEG*!UYorL+P_T3nXM4cFRE}ud-e{nMHx_z)7byFf*R<1M#DicOqxsja` zYKsVN5R?drFJB6RF1uhjC5Fu8z$BCi9XEnUi4rK}bftlnhgm?mav%?&M=d!`SMOO^ z-u9K9X*{$y_>#9U88uK(c8>TAC~UyPQl^xhXtKTc`BGW1(UIQHxCu9%!Sm2-b(!`ww5paj2NpdxqT7X+Be0V_SJd@#6j!w zslP(C+3pE!sQm(Ac=@jTczd)XG{0sQk^Ox1eoCm!lxp zj5gPHf-Zvjg@y6V)2;96!i*GB^-psVw1hT>nccMB){^`o-icxUcQb~^FUz>rudwT* zGQEn>8pGP@=r~DV#AA{`f4D1zQf&hv11z0S?XiL_%6Ct3m zD{rq6nrzbs6gj{g2(Db%0<2HhQu!e6Mju2Vs$!$?SA}k6Hj2S^Esi7nP>u5$ZaK## zEuH%TA_c}UkVAQpV9Wi{uu@w6OiiCY1m$Oj4 z1B_J9;NWoVl;GMiweXl9@d3<`N(Khh&7rqYg5 z2A3XciG<4IoQ2RUO@aWC1Aj7@!#B}e8#j8%${b_^_k)@8YlIM>{g#L!rPLz`y@@GE z{lgRz5iR0SB9cB1l^!YaO<%;3Mk0WVKw_Kh!0eco5`Ah&n{X6H?t(N70a~2D^0W5@ zdfF#Ky;wxiu`6X4mV=f8d8ofDPTY)utZSrwDhjeL1I1#q#0c|mR2QvH;Tv~P%ekCf67wP4`P zVU)p|jiImm&U%mGTRQjtqPT|Uc}l~;#$m+A>=_%o;xH87*y(&+lHJ)R!lByhee!%)>7FYF2eaWXYk`deCB}cf~k3 z{|h2pn2G1;-8Pw+%&m9-2N=1DBIq3EW3GCC8oC$p&76(mttT%b{`7^DsDm-#=ZMCp zf|_~gJ_oaw?6te5_`Y`<6<3KAsrSnJtK7PaZuEW+SQ(8C)F{BH91Hix*|IeEIa9`r!T>=+k8CVYjG5n1$E{sMrUB zX8uEBPE$ih=E)i~I7M|B#CR3H*@yd&;RB6CC5m*D(M3k!7`3Gsu2m&bjT^1-w6TGt zvV)^hP8uGqnbN%^*vI%7JZ%fx$Y}gY0u8z?q;wg+?N3MdvC-%g4e$QPRC<9QYvLIy znIxL);wsk=k(=-^a1<-{|!(-D&KIa9E3I$uznC5purMj$)95-xOt@tw^;ON7f zv8nLdm?hPptB>>jkjh_itF3AFBpOWPhuW4L$vl_qYPNsp3p6ie3l`LXU9XPdCA8bZkdt zt2HEuOl>FHT0pc6jVx=j%cp-q)g`seGj4jH(wNG|g46Yc6D27+T8fa;o6059qROX( zQH6yRxnIOL>=W(SsEO&u#uUiV5KlumTh`RHR>wT~j&`=FmJeSx6Z88ZLRt>=21-nQ znGQz1$dqo%S}|DqLMe{&W&Al!By8muYk;Fu3?Wxs^TaAD*d&Zvbpxl0soB*>yr6P2sk)bU8aLvSivC`t z(AyjOLUb}`CDaSqa;cXjVzD}V1MqDhro=Ci-zk& z#pq~BPz#L>AIT=w+vWlSxewA#qBxD%syU4-B#t9f-Dmb2W3QgR+&6@WqbHB12z!i) z3K~aysf<_zeGIcko0GQkX7MLctm7=`4MAJg@;=Sx6}g(fJH7 zrgrh#6OT}qujJuy?etpK?`<})jjbt_k=*`gzg=w_J|tYqK%`cLwbB2gH#_sEc5Iv& z2tU)6+S9~O+Ac3m#nJpoEx@ebLNvVuAP6R$Uc}?uk?B@i^^*R{ExM z(*RR5;Y`}+{XMSKNbKVV2CKuJw5l>M9EIbewvY}&8bN>~gflw=tLo?E;-KkUsG;yVCP`=rCPs&csov~l zJuabmsD%q;>~y_-*7-pLi%;zT~v(n~L&c?8gX$|>oTNuDOY^H|iRjn}ZzC%veG zyVK)i2o|Ftbd^$TVJw*0&CbS{eD0cc^g%T7V_A?%>f1<0+QS0>h>1v<7)ryW#`TXr zyeky$&PCLDhCq?sUliG7@;9Eo4`t9n3!}cyDG!&CsLuoF^f*c3hJy)p-R326lnqE{ zVPahO-Y_ksg@R7|T8KzIq`{l$jCy{W18W)6ODjsOLPJyin4DFsi=61Kd`_H)>dBe& zaOUfCQp3=!5?m&Sxi5w;#YASfG_(jf!xj;B;a5X5Cegm@KPWZnkaDseSWBPijgEJ^ zajX>vHFNbjnqgpoR$*8mL`$8IMj>NAtlxq_ifgnSRSNZoBUi7Kgg$kRm|)$Raj|HI z>tXAd`p2y}6Yq4>((i?s&V0ozv!5B$|EDCf?ctI&m3aA#TyQtvbg4Z|YZ;;baNpc% zALR009)-6La%nG+PaM9G{>+te?G(L5&C>|Z60$*}MQw%1mfBa0yoV&!Gs2I0geLA2 znHN|DHFJ-l%ioy#;;dI*zY&;Utne45VNgDNbWt&MFH2B3(|N0-HXw2PK{+ zPr2gi6GRs38I3NrKf%Q1Q%ExkOV5eVEx0pDVxPLQJ@*KS4&@=_O7l=XK%)mT!m-Wz zS(zDrQI;-wpZ&-p*86@TD=*WF%*Aa4k@5@Y`ojPXW4^1V4CfYKSwe?F!BZ13b*on- zquCk>_C7<@cRe0L9yO4LdpL)popaU7zX)zj6y3wVWGWtd& zecPMn{1Rw~*AU~gm@F=+L{0PPW)Y>@kzEL#1$CP9@55A+2Ul?|;mt)sWg_6s@f*GT zgHmv6hfShtYy{P4@lE*^N1;k}qT2;HCzuE-vWVc;A*zqVSzTx+^Yte+YgC*1lEzK3 zuB?OYYx-o_;jCCQxQm2p5~n7P`J-iM-lquY*%1=AwK`J+_euDYxZhylWnpq=5l$A% zR9Z>=p@d(-aGT;?*-|U;v`N(>2d=_HWjStX=xbV#HuL-0CHl$(+fR~|I)6>lQ8{RA z*^Tg-t?`aODYS=&;~fh?oGWvB!0&Is-4um8a2M}eNrcZYtm$}5kNY5&zwkjZw@Amr z!eva{Vh+MLm8cf*#M&~n2c6+0Ma_juPW(oK+Z;%r2Phnd%{v`EftIp3wI+w((btDYKbO8{ms*SlI*FkvMf2M5Ar1DjlH7~ zFlKA?jLlpLcO2Z&=#NHG@I}nE3f-J2fGnqvaYC9ZTR{?;cbSuT1i4{vA8WekO=SNG zC0yj*R7i8u0NdI<3dUUp)mT4vixdc8KNH^U(PwTp*)ewf(7I|hbmpsnEmLo+^RC*wh`a#e#0S4>#xtyu7J zL1Z#Iu4;ycn+0)HviEgCrTvbT@mjk_T705MEw+Wc7@4XK&Uxv=xB(7lCb3t^yd>0% z*|A8~t9D*@Mso(8^6e`gkkfLvAaW6qLnEcdzRH+iSlU+yUuGSMtBHjFoa{d~irfcHFBv$g(k(m}k+Bch} zX}`QBZU5W$v;H$rm>NBC7-FDZ{D`!AV%j4sy`D72EA-Gq`O1psX(($i{dZ4Lrrxs! zWmWxjmv%T?g>IslYMpu>xDl2Mp!Q8Cj$^{~bM>ZpMj+W0|J``&8iNutEi=MQL@4P z#5@6`LMu;Dy`8D`*)(7u#QpoIqW4bB_^*Hb_doyf*Pnm=>+k>j&p-e88!)js_W$|o zUw`~<5sXO+TMMQ6<(!H4p_sJ>RA_7;i18`=J_WnQt5FIy$W^BZv{nbcKblUlNl=H0 z<)Ho!w3@$ig334n`>1(QKo8dAO!7(uB&EaGY{)Vsn@qs1qLdwtt)Q3V5qC5#B2Cxd zxB4c0d6tFm?oG`m23I#PW4!wwmNSCtQR;a4o#n7AO`Oq}D`HzE zN&@C6#0)koD(xL-MeeF!zuD=S!X3IOub4%`I<3%%$hhqZ$o|*S-M4~%rHT&ZDC*g9YW?)X!Fu-P; z*rBNciZWUPf+pk0SZkJh+j^T7F4@XHFGRGl(5TrjCDpf&Y+$*vNaykv79!A9MALL} zLTGRgi#}<*?8M&~Ew%blzwG41A{Lgwtf~!%_=&aawx1%K`YBk_g|4Sw+;E_lFV3yvmUFLELXp=kD(DIEniP)y#A#oNc_pz zex{$75Zb?$SdM>&vj<@s3l?E^Is)uOZMZxyb7q0F7Rc#Y1#mv529%@IVLem<^Vy-1Ll-Yg{U?MYb$>`6@PLtc?sKV=tbd){@_Mp*}2col3OvNX}F z2db^NnXGi4B1%>E^z(aJ)py@W0Np`|)-=b1z^XeNtChB6Z(@nOq|xubTd0)e(FHcc z9oykYLhSXXg>KDu!eNzlvQ0>thD~0{oqj>{W3C0sc)$6W!HPzHCm2;i;c{(5Z#yia zcR?5D-GoZXbZlZSCzhLW4q_rv?JKNlsMi-*qq7`Pw`|X84qBA#ass|NUR3vbrQe=? z`VhYf?oI2%A&|`5EHeA9<9Z&?D*8X*2NCvYvF!$%Z0;}@nnn*gL* z+OlTdM>6&KYWJ=~vU7(NCm;)-yCDuc&Nn^A5_kAO zNUPlqWF1{V!+?{;Qz?R{*lAqFmFa~RT5cXJYDypk>z?(-G{sG(FvuJ$`$P-#Z@e&A zzH&F5E#TIphD`d?6ERp zdFT=bgiT`1!tO|H1~oqIkw&7w&qdtdSptQL|e)>x3&jB``;Nv%__XQHm{X0goEF&8f0N1~lBJYGd0$%H~) z+cIutVb|6zD)OyCo(COyCP&Y4av5fpSlLyfk6OloN20d+LG zd`tp?`52Jl)?uQ%3b}g*vsOU7+(-gw>}a-0ng^rIvqL?{#hgAE+@N&NyH_l{?g*^c z@AC@%#^VF~q-QCyjQSMrj!@{yYjy$})55|x(DzuiUNPR=(Z|*~@J(quFLSG@*G`5F zxr3$=15oHm3u!Y4UlGW*O~PoRDV8wtEVF$KW06mVW^^jxA<8vfWuPAVomx;&ph6~A zOJxyFyP|l;g`f=4RAEORr%C7w`hLDytj!8_W>9(Zo8cUj17bR!_RE6KliKNHE)vKS ze+w7r7|6SOOaNE<5(BmCyxx3zg>}I{F9rs7b8|2G7uGwyr8{Svr)tEt@pa3tyy6=7 zfUz#TH|xZGu_mHOW!ijR)b0dTt7$j&XLZ)Zkp%=`dg4x0^<+ku=XqKSJ7ZT(q~a8^ zRdvoc?-69R2`jQau|NvzPNZ3G+}b3vFxFaucLz8S_R^QnNN6aA=%Edg*_afSy{Kz< z_FzP)^Zt%$o8-J=1bFpvdM2n&t&ay58cunYCR|*vc#Xg&fQ2o4Esb<#3}D z#~1bzS!PKu7X|!899J)jpb~{;^o6ZW?}|=<>J}E$DICO*LEeyOTvmRdLfX;Ag~gOR z$@Jm#ND$!YYYv7*lSgqDc4QM(-U+(&uIz)St9dLXagP5_?T;KoU~F0yv@(=L|I9qH z=AW#BxKA>{-W=FS>mc@)H4?pK#_1wSnX8-^NP#@akyeQ-&`oh5Vg(?ecUQj1>&k&9 z{2Fupt^5K8p3|j2?*cCnSWsi|OJWHAtBay5S!*#E=Q_5xfyqbBU|uEdwuaMtEUGMJ>G_VB2iOKCYbub6Dd4 zN2Lb&J9GB4J*3}M!Zl;a?p0WZDQo?aK9eL zG@Kq;bI-IFLWvlwEfb;UB^pW~W7iugX4^Kx!^dJ z^OOpUTVXZ(6#OzrfSm0=;M0;gSFcU*I7!x~>c#b}k~Lyx*~RM= zvL}B|VK~Y{Q1jU)7Q||hN5ZV@6yj><6nahb@qcFFAaNUs=HYzpGF4!Ai)hP7kzO)! zLGnq%yk;ty2lASqoUUIdk#cB+aYF=d1iOwnw*lQ>qpfcsYXu~n1t>>!ZLsJGE_t1> zbzW0I~b9G}x6|ry!kEe-d507Us z`Z~9k>DtMvTOzBbGd^%UTy?ulA1x3Iu5BFKh;5^y)R1ki7M0h$Bj5X4)OEV_NXs`vpgsOXUnj057yyYk(pQ$#UQUu{6KTweG=# z>txaW5Fv|G97F6zWE}_UuG6JOB~ugW;t&9*V@TGBtfK%{CMuj+)12c@)0DB>Xp1^V9=-_Y{_i^K`FLVqYtZN@9$Xc$2-WkFHj?M1n zA7Thfyu9}ej@WGU3&zoq%o;&ZMmnBzQz(kJgfCCfN5kG+$Gk~|ZM3Osq?0lX?J=@y z>iPN9CRv3NG+cG$=|DZ(h9LhMY>v}K_t-+;yzSup^qbMv`1pL%b6{kRQ1GVzjjWOF zP_YW|n9(%;X%~{(^e!N%>)9R8s?o7VGBhNKtPJFv0vuH|wXe$asm=?4!gJ7icBfXX zUA5{2rRwx;evrSPK|-#e}~;r#xU0_k2nrb_8QuKVK(ka8<8nn%0H21`k@tb z9Hhy)h&^xn5h~IylWMu{a%xkE6UK0V zHBAw#Vzp15ln~|(9Q^R;!)Dg(+mLWQBjvC`^;vk8g^xtt&nic9Uqn zu#=uZA~@)~vqYRq@u;`HI_)@p%!e)ffTvHVpmU-$d7kAUSMmj~%Eu%};26jt&nPU3 zQ~33{>KZ={K<-uVFz$HOrl=cd!MKf0IgUH-$ubbl*y8UF zRzdIqRqjdxE!ii85P_eQb-oxgAZ%Eo8u#>Hw2yR#EC}=bI&iYrY4xy@^Y0;R*$v{g zYk0EJl+P&6I#6PIkH4nNVAaxZC`s!r^L3)^&Pe`w6rLw382w~UKZnJWBE068`SAz7 zS&Qvb@BE}<+Q)05E*>6}U%~}~fld&Z#?Pw1ZZqpj9}W|Eb%>2NxYgK+^Vi=*TdgZ9 z_XpGPMnFMppC35<2Fg*O!62gkShb2MjL7w@(#rMme!rE@zdRnW)7j(kt1FaqeY|vg znr>*qVB_31jrSKxJ14kA{d$C-+@M8O&#O*>=Jm1DtsXgcy5Kh)Th9Z(=h(EdJ|v90 zE6&2e{O`qtF0Z!d2 z4;?N7xb^YKapY8v+$zJk_M=yCbv=4{_}GLFnwhCzdSYiMxcS^Hkob;EE-?LN#gYhc z$2@0DdrSKoimv2AKg-vN!vZs3wE_}|q&mGNeRZ!%a{8YRu>l^Fl7!WiuFtorDS(zn zf2uoQ-M7}Tb@v@VJf)Na^Q()S=P_#MSK~L&K7h9=tkwnhH@`YO#kXrR zPxba~ew75%`PJ3ovGV=l<6=V`{5FME+d<^!Y4hn1AKzrk28kHbGm8pPSm$ED7j8Uv+v4<}JXOfFc>ZEp zWi&cdbN>6Z7W35|A5e4ZXh8;m68Vk#3@Zf`{YEGaq#Y>+7QGgJ9msC9M(Fpc@Y~Oe zV~v3C@ZNedf*5`@KmS0UUy8rZKhl@b{S$1&fTa2P2i9bI{*ko`o`1PO_^A2OeU6Oz zlz@S=h@GERCU4SUoqym-r^g>S>e%rCao*&4b^JjTGd=zwNQxbw*6TL~%R2rbf}9?I z5TM46&ra4ih08krAbOu2UoCE(zp%1W?D$k3-{gEb{wQ;r9)FOS#g5OWrT3{WY1=Mq zogROX6vvLwUX%B!?g%lM9)AEx#E#Dp#rss3_2n**oJMXEwgDIvJpQr+Jm9zN!GaA^ zHog4;5EnW=yA$69PU$u)HaR`?0Pu_*8jXLW!Vb{j>G20(bL{xk9Nwp}V1YZtV0L`^ zp&TF)h6J_9?tKaiP~^~>mBIplIxr}l=Q6tUE@%pgr@h!AWz#%YKR+mN#e|35rtkB$ zqw3#Ocm~DA*zq+j7pZq!nqmb`y}B5vZ-RDq8}aR(r4hBU)3ePZuDR~?1OAULe02JO zs0B|?+xWG+A1L3^(+~7KcKXLX){wN9oPp&#disHpjh!A4Ca$)<GP!YND^bo?eGY^8Rqi4QY@#Jl_*j^M?P2)zLybL1Sqo*GP(XqQ{ z;4hxfy3-HRile8$So5@-yr`>#obKr92kB$%?qS|VT^%IUM^AsT>M0oU1Py2vD4pKxqHcC9xZl`PCtMQW2a{*`kK}rt#*!1Kfr5a zrzb7BrnN`Qouku_(DKmn*?MsTgX-1xaJ_SM{z0`Oc6<=Di+VdM;2bqOgJMza_%zmD zRNSK#&(ZB)t$yC<3pxQpIq5lE^4t+XQhvSs$QegbMQ2(Tr zbh&zaNx(pk52=8NAL&m_30M$xMTd2WfgL$az|{&U&tookr7SrxGUSITxL5+^Rkr1J z`XvDaKYIB57i*w5z>Q1Tlq6^n#T-8W#Ukhpgy0f7rSl)Gd=72U#VY8H(_g};bpC^- z&(Zm>mO(lHa#7z({*Tr^hvy%pZ6ON^w0;Sr;{J~oKZoZZB+aq&YsbKa{6*&avvL4i17@X~ej}CF@ z!biV&>Gbl^tNQPA4b0_ea=A7FY-J_?xpp+z9)T?X5rJm0 z&oT+z9xLy&d3mh-=a-Jf#=+GX{*LYGw(PHM+THBhJB~#!PAugdDa7~f>)U41vn_Qd zt1Js*m8g|BldX=TTvrEWGwZd3@)B*xosAC49<1d-VcfNY{st#* zMhC4ox`ANX%RiEWe7TsM^z#IM=?j}099a2f!DK939GyRlu56&~Q5c?@1=zZ2GnBTQ zA$(L!ekjBo9W`I|{HX1Mn=XdTCqp=~9B_2h?pCemX?3fc5K>c$p+nPw983J>hfc#M zi$kY!T}AAlw%RLr>ZMEYiQnkdO)658(D2kvDz;5XxA0Ye2FGMZhtB3rX29^);i0pA zvmde%-0)G?4`r?IxB9kiqq%Nw=ZmwYC^(MjiirdTjLTlGI*(kS6O!2#Akz1(0V07e8-4aq%9N5S3%$?$GV4`T(Hv2P{S&D$>C+{tgT^a z-~TKn zix?z!=6i6aWO8PNG*$11mZDuRuUcr2R9NYFb>wpR*{(OWTg|Vx+P&DFvgmaIuSZN; zi^6sy+o>Fo?3D?2z4CG$VX3!!DA%iEoND&ru;TMGI3Y5Z-AT~a$?nCVjc7hN7&19D z`ZhSuPD<)MHwr`Y{0X{rS@CKp)Z&EQL2Cfi0*>H8gM%NVyX_Lxn*O{xsVv@Q#iO2e z+1IrwesG-K>1&wWOiS#Z0qEbC;5Bc%J7^P#QL-I7^KWppV2ar+h_&>pEijiovd#(oSm8n2A2jENW$iKn) ziOG?V-gsx|F5fsWHohzI1Mu1OH4g1ZmGQIogZFkXD`WG5?G!sHX})hnSWHZw!7+)E zm^7nzaHNrd5Xe!vOc}O65 znD#p2QXO}mf*wT})m^9clr7x*h;CuJ^G@yC02gfCq~)Udl*=s_dM^2TcT2Mu!)x5h zM>8FbH8J_P1?L(@+E)$6A?>RMFPmxryX*K&cj>P?R@J~`s4&Cl|6r054<4&}6RX*BHPh5B>%9~O1FwTE_{H~_3*8Z@?cSp)r z)rFrdTiu>N?}TTLL><+IH}MaN#t+#0yWkmIOWLn7N^Gm+KG)8C=Vq@@7gcc>=BYas ztn$!u-`M4TeZFnbh&W+k>j z&p-e88>ZWC|9}4a*B^gd`|K8IG_(8adIf8Y*bzH5&zir>2U@zP*8+xD-7Lmsi}%Ys z-DO2=@ZIPVcb8s+jmDVJMYDPAIx17`T}zgB2d&E2vaaAkpVu2>I^}!a7}F`=)yA0L zug7&XrbbAk>hSKK^XbQ>=h%(Y3U^rtt2iGze3j-=-8^>qn}&}sn!R@OgUo4i^R~=7 z>|TChKR;^!<}w_%~T)#hG4 z`|oysEjBmxyNERGmo_^EkMzCr5HB_)trj=gpDTAdbFAkVuf3hTsqXLGvGB?^DOPX< zci-gATFn`ycfg!wA1;@>wzla`mwF6@$_F)b-k~7R_Hfwp%r!r2gQ+1we6r6zWPI|O ztBGv0u8r%X%dH8{*@ONB*WOGncTu+;9lv?g%gdbZ&!6Bf952vPw88$S(W#rkZ)}Q* z$8T^0&dXa5oVwlh*;6y~6bb^oP;=B#VQzH6End0YXrs-b7c^1#Tl-xPsiOUcf1fg3 zT6{i(t8w~InM6T4Gf##bUSo|*kVWh3@*a)l1#|t-`co8 z{gb7mo3566^TtOM8KFf#xDRJ{&qpP?-SgFk^~c9|a3jv{&<)Z(Djb)AcTOE#ijz;h z4?Sf3Y{RyP-A97b?DW-A>Eq)T+>hhsoI{TwsL`RD#Xg5eJpkTgc$60qu6GJSjn16K z`z#*yAa7b_8@`z2Z&#OFmeS2dx|xnTK@c-{G;Ut-fn3m_?so9V4S0RLn-N?htcTw{Q8^aK3DmFe0~I%=DfUrsTb~pozdmXuUwm4 zKfhWR5QLD=?IoJ9gJ;E947tjuubFvVU7IPaW%$^Ie+8H5 zyu5JvoO*4C?pdyNz@ymtzk{1~c2{0E`pnPVF8b6WxyR=%xLId=&}I(~9(34h6uVrO zIGo8F_fZs_9+=}fAypf%R#B-w1-I=?g?xb4PfVfIqK^H?ZvP%!x8o&7fAIi{pWk`s zeooEwJU($iXPjmO!H;4&EpR=Dig486%AMW)wh-y)t&R+QOemhgl{@*+?S6-5VSfI0 z)y)WnPW|-}+`8jWjU*2?%8it+1>B?1D|Tj{bX;Kn!|<=&^ifo#UGGU$gepa>sc3h- z)j}N-1evt2XX-?Y-RXC5!_HpiYFs%#X)|P_AU1Yr&V0rT){;Ox!L4F^uHoYG#VFc^ zyfF~Ub+UUkl%rA|YaH52@hF&_OG&-w7P-bm<2Sf~RD?e>?T#=USn73pluq#|w!hd(cTVI%(%<1~_I&Oum^R47C;ILpMirFqf@n zuSF=agW?d+c*MQgJC&p~W77JOV&`Y*`HXwqpC361Bdk?3Tlx?@eQ+PoPPUu3J7o8y z4OgA}_Yb+~ypv`aO;>2_sC%ro`lNgOhM$*|a8z-dUvpK*R^E#V#67rb!)et-)Z&d!+!4AneV~KAVjE=6ns%-1^3JJ^)@^Z#+X4@h$9|TKtDQ~gi$u#)qE4aMJ%L#{W0y;lx zla7%##BTaKxV&d89HT`|^V3)1IJXJs@pB6<@A3D{H4n1y`H`zzZ>fIlmVbiFd-9R@ z7F^BwREoMTqBZ*0;;7mT9XmY(>({ig<+Ag8ZaO$hoMVS(s_;U3i3OQ&-bYxa?=^drk~YH0Sfl z$ioLS7U?V8Px<>DT>3NB&brRxuyzh2_t@p%g6n_s`D?}*FICo9rB!BQNB#*e|JlmR zNX_OKUd5&9bnM8#!QDSEr3AZp5KFERN<%M#XAZ6b+DgVSNuS?y6^#Z7#Lj#VZULIz zb9@Y|UHMh3LjS`V@7V&CqjtPShu7^mDe)QS*__YOkhVFW%OUOkBe)9arNk&?8TB#D zCB8ZT);|~$`TJ*ZEs$4Jo!W#IK}cWg35q5&$@9Xt{Hq_)XJ?V~;HsdP_YWZlt3ORm z2Y^QG^1p*ygLaqSeBfM8+MSOaZtT#v;M$;k=!(6KEXDlv)qgg#6g+ZpZO}|gM%eNE z_)TCcQXM<~PjG|KUQFuf%>1OCm<*aeVu$_>ZV-BT=dv;N;^yb?%;AVlF#>49JL5#h z$sB<7cCY0Ku4n{YcTM267yK!gKDxsB{Z~b842#|QGq`Q&rO*hgC=Z#>&s?>$fg7PS zQ$s(63Jv8X>`a@$Tz96APagO<(TvcAjR#u_J3Di=rI07`P9a4t106I$%q1qD9uXUK zyToJ%g}J1o@tL!#qSp`q&DhxqaoGz#HyN&HHMOmfQ|#(*#O^0f-{fY1og9^$3e?1o z{PT0FS!jRZLh25N1kJ#V`aomnr$_v49<{*|^Gk2%Z^%dN)RYj<=;;2|x%7dxJ9K=0 zwVKx0>6w%{qog%jZ&3LBpw+Gnf%n*%pP#3Oz3Q1qvD3lRHw+)Z#XEd{6FX6x?%ZmXB^cJ-0DX*xr121;_xWV_Rs0?FOw7JMM!!pw9*!jPH zugrz%4(qhy{Ln4%YTf3sqtfPn$!#7*S!$3qY8#0i`F6Xqz9(?IolMtp)7ViNLpq~} zEdn3fg2OU#YTGJ%sJ>RMLCR#V`|mH?FF&Z_@e&)2UFqxR`~T?T zpET=!(>6dk_`wGAemUj`TX^m?50+24*{6Kp=+>;C@_E;%XyeM~*H750+;6L)Fi+Ok z^P5uS?dS3ROPi}E%FfaCK^DxGz5FqsBf{vTxIozYb+8R#yaDs^e0*}K+f#LoMi|C2 zf8CZ0`{EPeWBwQc=enPFa*Q)Byzqvw@5f#Ae9*x3@yJ_#lO%=+;C!tsUHIk@8#H&>iG(!@`TZ`{`}&yf&G6N zfb4BYgk$X9#lh5%A>4d7Vc$z6>j+^C7+?+9s(63=e5+EkGKyoukOb`|NFQ_iJa0Q# zWBap0yF6WARJHEf*o6&#QhU}#bI5yV>+L)nQ~%|*Rw5=;lYi=`Bze~KLTBvFW1O?~ z&kvrA3R;dY7Jhs^>G)x_C|7chEWDZ?c+H>kX=<9ts?vPF;KQCDzt0sqwqX}9P~$7J z7yihGBP@nr+|8qT^K3ZYD25pNMZ~|Mi;6gF9LaOo-7al7$*>1Izd!58eA=g&7`};L zeEK3?_jG+LvH|F)1qmGU^CwAASihi&zUBHc-;J&&3Ky&fZ&$6rwhdXM2+>L5?RGLk z^g@UOIUPtnDKV@7IZxIH(`R_E`~}l=&%YS9`aL>*l8r|X%g^yox0>}sPlpq6l#luS zvX3DM|1RG%sy?1PIEWj1{Lr{cbQ27KpL#Vk6m=*M=#Btw{-nR(x95nuUl-TA`=Ak2 z#QBS3%qf4&HTrmiePKl0#5NU{8|JireTjXapSWf!h2<+tCHtUy{`CZ=-w;*$yn0{g zY^Dm{b|3f|W*blGE^G)?*T*k71*ygz!Ni%W=4nQaOa^!#Z~yc7)U-;vZ>W+K)qIi# z{kKoX6(Ihb*gnZKpb%Xdx6j)*#_37wmVfsmRpf^Y53OCM9a%R}l_w8Dkh(Azd^b7z zM%SJ~{^{F!(8yQL_L^H<&jWJU%6(@`2xN+JUk|M9&lhX`d86P4*%p>v<=fBq%2#hF z{MD=p_e}giEc-BP0yktEe!lI|-(nn3e@7gdZZ z%u|;QRlPWJ;Xiia_-!J7H0}4vgWNe{oG94`qXx+3C$9)2hc{%vK86Bk5l#N&nQiT5 z#ywX~+bJA=j7On3(x*^6L{Ufk2BcDQ{B!5Ss9aZtdu2xaZxCW90=FOi7Rltn%+tE} z^#D~$XH)8*bq~GF$;_0Ao$i4=aLclq2vk)*VxRXY-!EI>BVvjr>68W2B(va@3Xgk$ ziB4VfP0@zm6#MZcEqD(Xe^$A+6I16GiXyTyuqh%91LbHl1KR%z4kj_tX?Y0?t}5d1 z?+ToD6naku;+Dj#cWJ)~w^4oMr9;O?bD($a&|gKyFM9X;G8FT4c@Ip`EW_Ze#cR5J5b%+b9Y+>n&wJQ~ zA6`@X-6!rxV`Ru5RWu#5!f!IaVSe*0DA zqRYo>s+tcHOPH?b#Nh#M1U3BZ9T@P}k|-Y7xc_|K)PhGq-Py`; z^7B{*(Jo6E-!u!G%1xKEY%(7_-<_gJ{W1}J&7u=ztbDa2;~Tl64);KR& zeS?q^ZmszOZvm2U2q0x-Hi{?J^7DbI`29v-#qs_zZM{9FlA^#W%lgU7$z;ZNchbMzEz2<3s54loR+V+?+X z2tf8(2Voxq(9UWPN|D&s5}aM7ZiylHviSK$wb0Hoyy>kT4OsN?O9E7JM*$Mard%c? zq*7xZjjne?65OS&r*aoAi!mg8s3yTY5ZSvZ!j~+>t~cJ~!utCklu>Rs?5w3MFRuD^ zXh97La&Xi@A@|1vyQ3=pn^?pI&LYp$pEo_CyeSxit3}@NK_+&?n|@8u3wH58_Pj6I*OSLg1YsY}1;%~+P=QD$jQ%$oJE-*mazC+%OA4`< z#19BJwG+~voMGx20njnw4Hb62m|ub?Elr4bT-bKZIZ6k@pZt$t8*-g*5y$z8V7-=4 zHqelSV&8ALO>DiPMMU>{-9fTpEiiB4-xr1#{`}WJ{`;T*`0LNV{`L3&{pX*5{Ef)Y zWcGjl`qv+SllV6Eqh$gSx>1?clNNW9CM*MuJ%|>-;xC5;W<9_@6J{cp2R{$@q{TR~ zo34%!2G-Ku_YMI?{#Wf)cV8 zs2;xEtS;#p#e6*jPRL9n!kfrLXBNTyhJWZEH6kJi&|aE*3_=8cgg_z)^`-)mFDc~s zK*&VH04P)vC~4@TNb;)s(OdH_3YX>4-oQ}5P$K;Ey#4B6I+je~FZBT4ZKf-Rn!=Ji zt#`Ol3;CwLLDf0qtiODM8f-{n2-b>_UyD$_NPrgZZ^J*Qe{^Q1i~nx=_f=!S*9Jz- zMTlqCzaJt~eGF3D^zS{%H1H_aYieIM>c?5gqQOFOb;QZWK!93glMXpjQKWXAa3Te& zjDqgAkTy^mxMxMn;w+pZpZCXDRofZ_qB5FFswY1kkN6M+^o zP^84Ua7B6o^(~I!YaN)aJs*Q2P4m?#>k=0K#n%45-kSBb5 z5WUqq(VODN{w`oAVk;MQRWhS_LsLCG_?Lnd4oAyE(>)FJEUk-^X7Yc13L}P1_uj_B zW!|u1;nofBR1e@}P2XKp62%(jChm>y)sKONVcjDJ4p|guxl6uxqnKFb>{x3?FU)fA z#!tg0r+H6uxtcogSA^thFEB;R7P{q36K+)Gwgb&{e(!x@~rg&f!Z=&&=+-jPud&S%O z-L2kzD??rC-6jUG4qMClDon-uhR`6~OE-hdI5c6KzZfq*&--g)W7Zgfflh_rVP_ahqED=k%peLe&r|0d4yTG?DW zJ%!E>V^0PYQoUOnPcootmY9rA{ovk!2_sI5e9_6P^&muJ@1z)M+qnl2#HEGlJ*M6& z+XrSyZf9b`vU#VdGpEXj)2vqSvH%+~pnAf1b?aWpzJV!RPSXY_^jaWgLBI@#F08+c zNj<8B=@O`k;xNir9CDzAe_=aXgU!!>(l$hgJhgmk-H6|x|6v#Vl8}z#r=QYf;An6k z^oe!d9GN|rDWp(1=Tvn7uL&HVtS4bhAbq}A*78Ng+60*#w(yF7qQ54|mr0~-HYc$$ z5p|lKWJc2N@cOLx5P%Ju6Hs}izmHk5%{A(q)>&O|m+F2t(i?@Mw6qnoG2h=r*(x}0 ztl=-*A5N5^EFHZC(sLT*#c!aI|3(@g%jTk1fycm0jfm(xD4z|EJ*VsvLtmeZOMRpXYtnb75y zycf4|Rph`#=M-&*WLebHU93ueG#t{V*DgE9vIMn#EYZhD``?gZ;gdT_d}Jd-vAG+U zjV=$Pc|$W~(`1rAZcR_jp;3_5#KI4oUzM~&Ab=1Z3Xn*zGWDmHW;y)=ZvW*bH0jH* zty;G2atK<9()lo|&@@jaA->wG_FT_p^peQYe(**z81#B8&^EHvCQVtIfje%gR%$0z zCsGh9y8MR;SsMqi%lQDOrtOA!3FPx#1S*G{vQ3)U@lD-KOv|drj9;}`Wp$R*$VwA6 zZ6GgaWdXQ_8DItJ-=Z6KY8GbLkd8Y&7{$}$slE3sYEMf7R{QQf;7xLMtB8u?Al zBcx*Fc^ELJ8km2AId(1@tw5)#)IK!!TyK3s9r7!Tjyt(i{IPNX+pO3fi^kyrko5W~ zSJiDfx9vp*?Wl`0X<04uk|%M|;*dK=4~?+X(1MDN3xmRn6^Ypzc3KD- z@T8fOnJ0Lhc*GT;L$tHdn2i;D6PM)ortyU*35IAOgGh<#GH|`bCFwk^bf8s~dCCp% zh_cNOL|<@1Tg4J@fI2kV1@HNG`PEYzw5)mg8CJp&S~$ye8V&wBk0K;mp+7NpxX)Jc z@+u_t!m}}@KsSJO+F}#*EFy+M4cBjSOpL&+&}Yw_5k-(Bg~G9ruHbR1Rd}sL>Lq_5 zb|?!zAo({;905JDOALR7OE{8+yg6qyWYX}iXRek7ZzxlqL$o<@<|BvKa?v%Rt&1>8 z(R_>6pUfvwlVh_UbHWtuB!V=2gPLz9Hz(B5-2itrBF=_345+CUGZ(b`fddGfd`nm> z-ybj(&mTIX3EVNrBz;LoNFm@pTVLdoOL6TrWtt}^QItNBoSBE?vlOu7fYCf=$KOO6 z!P}fPCzGQKf59|oHV79q0InGeE`-qv&j=Oj9R9|p6Q#mqa0&8!3OzP8V&g=t&!mQ|kA2e=DAslbIr*uI(Pbaw5_h21 zeR326rR3nyr4Q0EJ(FG_w5w?%X~)92_qLsj#zdeBv>|8If&hY)k$j#x1md@nz3w=~ zB#cN);iFa z&Z;CPm84I=02t1sQ9s%QEV~103ZVNQ8}Yr&>S^9;mR&If*btfle^4z;fYB)?L&&9m zFwFoo)fI2d1lbeO5P2jcSr(PRF9JrwKXia0%i_bY@@w5z**h!1N+B&IxWE!xZDHn% z%O;0XBt-OcAi98MOe2xAVA+x2WHFFwa#S)znjosFITHg4u{>_cg=DfOfiRYofygGi zPL1edx`g5t&6qeTq6)1P1dd>!mo*Z)72K5UyTbpUcLjr_5vb2}YSnX#cmmt~jR99k zn`k2^LQ}|uArKc-1@KiYs2o$}5*6?f%FHdSJ(&p*9Ehpo*A)~7X%ATs+a8bmAst8E zlQ5!LfG@ZrvcNVLHentngA}-Y+2}cw=)gLl-@+G#m%hn?`c!%o6J34bzwl91d`*sx>dGo=*#ZTw-RVPYFrRO zDwHtSuM|>q$!`KL@U4*;3VtY9MFT+b3{w%Thk;}L0{*>)sxxL0G0_AJ9?bv~A+ueJ z_P@$`QJN%4s_9l3U&5;{Y@loS#2mmRe2@K?IPmpFA7T+6M%u(J3F3K^nNS)K@>?{> zV7r0Xxzz;V$#4)c0muO4$r!Fx3YRD6XPqY+e@6nJEFvY(W-gcVA5ci+QxnyA@c=V78&b^7a zC7j{A7slJd_8Y7y9_#(7^5sh6gH1_;WmYP)#~-`lqL=N)-Uw>RQxgxf8KZqqBFG2v z12R-R-#2ocrUWUT3tmqNAs-smzAT`iJiprjH)GA1z1_aP99x_xX_XRtaU-$aa%X(U zsMti}y7r+#v&?B?aOQLVcsTmNO2r(nPiT3;=J&Bk3GJM!Uh4Wjq+yTQUT<~{j@H)o zM!v9_bKzrsd49dgv*6(~z8qNPX%6YEw9(P9;EPwC@io8X(JN!U=>k_^-WnrM)3V&3 z(z{gHiGe<_taHkqW6L@dMgB4(FW-@xf}jNSXV`8!P#WKiZ)_MgoStS$tjGE2p3WId zG<|qvPv?1(R=LAkV}^G;cQzZ1AzOIa+Pw>BiFH3B}Q#2ei@tU5K%^f*37QG(4In5E`#kuWj z8iOB@FW3(|Sn4*@`~9!zv#tmdg_EPl9_u1PyjNRJHH#{7Nv@YUPe1wb4GZW_vtzmH zsEX5TvIgf_kTsZ8dBy1Sl&z-j&h}zY1n+n+_F1yDE`2VDo-8^P*!c-;24F8t8ifMX zprj9g20laUa{)0XWU*(GKebN*1lG16K81Ey-r(RKB=|wc{Y2qaq>Je@r zkRlg=Tw3K^!JQdJ^g59I=g&~P5fstP27sJD#Y%oBDPpC*tk?|D@f1;L1p1@+qnU&3e=NTu80$<5iRnzi4L%ru{>Ht>08zl^DB6m`#=!sB3GX&6@WAg zpl%2j-qOZbLRX~wqClcEi`ZksGW9*6YESm?YL93VNa98^b6vmoH!i6oeP%Z?7o|PQ zddF7wk@hembIRN*FUFc*{ zp_i>t>^3#xsEsp?iG>mOYG1`w-mTjsoT&s-!7<4ZAe@Yvq@y8GdR>~DG(PwM?*R1~ zk05-vj##S&qJnBjpalfaSNMOGI6W>o^>Q_Ml)P~j*b-DdX2aTU)iCah_uMkmk`7PA*A0-(3v@nYO2 zlBkASmD8!WXtTRM0RhL`b5R;5DvskaVJn!zD;Z-zh!2X6J5#rqSrA%~5FShmi~egv z!=@z2yot887ySf7Zkny| z#N+&t0o29FZ|LD7XaIzV%v5nB#v;`+dHIuDAkKdegV-^!unyZ8Sb=JZf%BU>^dxhv z90K>@LSOD9^2O7&Uo}P4d`kVzL=omET$|Go8EMcU79HLDLvY&rQxwcz1yjj{4;&B8;Vh3~x{P!E0D4#X*H=6~3wY z1#vE2Zu%I>YzP&XLthvKFK-G0c?k%4$NW;2l+r>|kRRnFzgX)b4qWL9e}-cJmRW5cn6)iO0-_ zZbFr2bNYoF`V={6Kw)}spo=D>?o;Bt(sOikaZ1XGVHXq|ZyL5J+BMebq5yqc4cF~wS2-pVU!_H;4txseB_CCeZ z^w?YkeUlzRz`g~3+>8C1s$sM6J4KKXWyPspv4+zz-OR?zP@wW@I8#7ZFhjhA=g526 z6n9GUNa~iYl#ZTP?d7GHp96J?Yww^q?_iWb*}RN9NMY&Y-Ya6rPbmgnIA1?jGqUJd zg|1n!PgXri!w$Alqu5FAfC)!*NH`h2n}B8XyJBx;#$Wdpds4>zt%JtPlcbO!FG%r% zwrh~a%jy|POeN#bwBx>tqMPcF(F?cs?dQY3_>(l@*A_IvzGk+^;KK{hr{@kUCk~~; zC&|#$B~zH;NT%0k)xE;B#ysT)l{tu|3+ya6Cu-g0SLbNbyyl!HpOKG(RgX3HG&w?E zpj~_1D`pvQBE5DsvIP*ivV>3A*%jN)zqr=FByAz^^qo+RaW)&H~sTF2P;WWi&C5t{eYpW373Zm$qy3{ zHeQ5uk`ShO=Y)89^V_s64cD0XXrt1Gjsc)RzZaN-qP%{&*hxY_*5-t`K#ibxut>=* z%_^YHRLVv>)0h!~UDO7^yMb3TEPRqIiXRcOmYa$+fsmlat-WT>Vz-q_fbxE8&N)&D zvsPB158Ajt{vPEd0B?192x;AJJIs!d(fXg4*p-LCV%Y&G@IrgM4;oqP*J~-90`XVv zS9I9srR^3Lapw|I{Qg|zyh(7_McU0xDFQAD*`njbkLo$1z%FsBeH-FZMjvEeTdv|JE`mQPEA-D% zb5kWJ5L!FNsBkqo(Vm>qRRFm*-e?_FL%YJTqNWNL%H#5#UREk^HV3McR9lnaeokY@ z!rUB%_e;nx)$P@&15qrs z1MPHU?1G%`(}gm)mGWZwITZrW38|1jP=ad5Vl!isH;1&04VZ+Xs>pF%mnf`9bZLAb z7Q&DMkYZCVW$9RHV%zExYb(LLwNIFG2c~VWOAJO|B1WAe0XwG-CDq_nV%1X-I*@iU zYS{#JUm6f8^1TXr9Da{*NPWf^aZ=*co-`%KS-JhWIglr?f0WsIQ~zVrdpJo8Fy@>V zZwvfITF=#{`cVreGxZ7F$vL{TYGqEB<5BN8O4Q<&;&uODOHhZGGme{1Qbj~ErwUV8 z@x)=VL+us~QSTF?Uhsx%V#b?qPExW2;d}m!YXhS-LmSJ+FEU$C#zBBUs-2oGKG|JS z>Je%HxMJ8?)Vz>0zdvKN&}v*rov4qf+7(hMHP8&?w=SLJ4WE8o%E;ujz-qI)Zde8Ti&Iftv$pyEYIL7PJcC1lc6wQI4v^z#~9 zSO7DZFlU^Xt63gJN@i*^Y!n%7X*tOx*455w^5%^;kkKlpLHA3LC~e~!Y^^y-6=SJ$ zs+{Nz%Y^h?(F6?$tW}>q0QXAxUR;fO>o!}eP7+1C|C}f%exrRwTyon9c1Zk=uBkdp z(h42%d?Ghcixo93Gyv^Ub$h%UXlv@QMTZswiH<8k9G)^Hd58N4q)tA78*G&6?Y1C1^NgZY1XyO-Ttjw?;<@1n77h@?b{HEnq8NuwX2 z8!EtqRuya&jDq2J_wQSgx7a%~V`t_*{7WLK!;^V(#kzm%65s5J6DW?Ptw(+@6b@gx zV+>$#%wVU|e@}5dbwSL`KJCtjW&MBdq|keF*ayERKL>+K@5R`gB#m3(ki6tRh8=YD zxsf5$%f|O=W}%-jIs_2XBKy%`(M?K*@WIwlXZ7gbu*|l7-~;!g$>p<_z?(FQp3d#T z)>3P>{IGZaIGDqr_jv+i0j>mM^7WI>m(<-PXjpsf2paa^WaG|$wqOjv%?R4t(3-o$ zIjy}Bl$&G>+Yvii+bd@6^$fh(v%LrRt6+EO7^S2gJ3gCB-jB^=*?atQA3-E^~4bbU$;EkE0a#lz;4k$;|vgI zO0~Ji=bq#VD2dkDBzY%!%2*%YxOPHS-;*)z3fE_qX;+q?ebeOlB!IIba$vBNO|0%T zUH>26-i54fB$^4WbRrq{P_mom#`hXbZt`bX5AH17xQA#9i5}!~nOn8!`t@S0_uikI zB=H3oL~gg!%Xlu~H|0V3H-_PepuRop?5diZB-wX-PEr?Jr-jHy0pnuM6ntCtAH(^u zYr`U`3n{?w`%|3<2Co@$-66&$D+^R@v3m4xnT%vU=Z1JXMouqvhvfc%LEe*=rA2K> zyXv}%h{+bzhykkfv-2^peu$zg*BOsAUYH5+dQumK^%$BMV6KMeC%)dIV+a=XxK0{I zt^5#*`hqNo3?1gtb8n)?UfEz2dpE$@Jp)BpMnQ~LFEC`#p1noNu)T6?pnozOm}%2Y z8>QnM9l2P?aI>M|%n@%!nYUIfb4u$8)G}nCVRj_LyIf{xo5BMUG((+h#|t+sNf0w; z?}gPbtz6rGO*SL%bHhA{eHg-Z`*|tlR2?;Lms<_Y7U$B82izdH14Va%+^Qh1d;moM zCHE*$QaD%`5;w7a4l8y)CHU%gC#;@16p{Q_-ph?ij)4R)$-YB!NGTVR}k*3M@?F zNxH%u zV9WYpF!opV!5@1!4)}B7MD8%ihJs6$06MxdsI_kO{E@C4P_lmv9gF_=SOmjK{k(E5jIYJWsvf96Shu;<|zKn0qveb#~?9NJB7y# z8b;B*+0Lb3iwBB@c;}E%=72*VoQb;5OxX3*CY#-^@aSg|=VIl4Yov4>S`dmi7WL;~ z=~JD52nh=gp;ubMLhbxAlXG~>qy{($p zxV+hc4O_(KAe$m&VC{uCyr?4QFeQpS`1NL_%Z zeHnRm@&}ZxNvn{-TzR;%e+suK(VulmymocvB@R1O{Lc2~^3l-p68_aO+#+STMdwBB zyRWg_F<;Zi#@h2f;fhNE^X&d9+#)5HR9=7xHmc%wXH|(JWt+Sl0kpknYECRl_D|ss zC05^EQ~Hi6lj6Q5lpiofUvTtvOWF+=tQers{&?t$E*BuLghmBAi8CZVJU4d>CwcTc$|r2D6Ei<*~=yRdP#-6NZ)8?cK5CzuzW6^HflT$CU z4*b9(iw}NNUrsAs+CSR7-`*kIq9j94ryS|q)%QL|J11MH%x({zq1^*AK#vgr-`s%f zA9PB!BS?RaLX+*q_VLY|y>Ah6tplb18co?@h$YVyWxE$Xn=lUhyw$1qNZL7!djyTb z>O8iR7}?YH47uC54#`_CLo>?1Lu1g9 z5fzA44K7 ziE_m49*r3>^8X`3E?&-0&nSH_E2AW)4#r}$_LdY=bN_0S=J_puxh#R%QhbFpFiJWE z_*8vszuC@F>=KE-9`rk2xwhXLGu*z!b{?cfw%=cJSpd^gKe85`v4}felwDyU-;!41 z&Cg`?lz)3mq4{w!GWiFO>YsRdU2!P4i(DrqLy=dQ6W_R@#jJX0$rad5PM{V?W?}km zAs{bVe*cY+&IK>0(LlFa_b1&}PEiAiRloVV9HM>_^>WSJaA#}O=8XAefw*r5JpI-l zEnvx=6DrutbBu}8kMFs0bE|&rktOR1fjeYbp>>6Sv4f)uotXq9j=5>q-4_X5OBznD zF3IdrHL`ba;Q+m8ddm})1 zP0Vs<%QZ2hcl8p+ZJ7sR;o0qT_j6033N|$r-U$m@>3U=pvYY+3GS$@+9FeqgrOMLw zi&W(i#^SjfsI>L)C6anh(6;)JeT6%xX<6|97%k^UlO z!AA2QVf9KG==y=|nZh6CtEYsu%6qye7rUO!y$t)umSUz$j=8Z488R!WuCIqg84;c$uMNDnsjTW8yWu@w} z>uvnqg@kS&dLxDSKC*AD(G@!Yc3-0~4ZE!)JYmhOEf)GL5neB1+c*$@_pUA$eN^-D zU3JmgcPUQTMqcvq@*SP#XC3BZt9xR$!JpmF?b(gK1ekv$WBSpr=zbS)<#L@@8RKM+ zf}U;2rxfufWbjIO@?DdhELf~@LHE0eOJ(p)_sOgrc6Op2V|?o-(3=`zE2p1~az@Xe z&=Q>d3N2ljRsBIM53DlI@NHMrzYnck-f};p2`z@0 zuULYhJ6W$i{V>M?5!@F50Zr}Eh}6DG(<>sVouBjP)`O}NLZJ5GbRM@Hrx*VU`MpHR zHeMG6H0j?&0fHzPC^*q~Ki#`8flLfRYd%O2o$gb?5WPOjx`tvb1_-B_+o%i8?Q0{hUq zt;=-r-yk!qE^R35szOfE!!x5e5Ddq=?W@hxcPe?IZ6rNX!Pat7qHY1))E&}j+I`1On#TK!f1C9n zMD?w8bAR6M2fa11sds7A zc`FcbA&bTk!GDF57Fj6w1c+6@n#~PNG%6>1@?uTWeo3PuB;;1?# zNnCE*A1E}N6l(=T8dyOXa6dj-IyD)Od#p()HK3%EG0s>eSE2GJ7eutXa9+P>0%hN% z>~}jbrZRp0R(dbpMA;ml+PNLPYwHAZ}DxQegFTqDnn>#ZFcM<|iyi3ZcQ*g|SgAW?$cX=;JSQ?n+LYQN~SGMhF&zYfvp6-*@=)Z%iyK9G@aI20ah9KE>+r@ z-8PYRi8gyxV`l{19fyAjEEe=-f*GHal^a|?c9TBFNFdbTZN0vtHIlgoR(FW@1XVbD z8xle75S3;I%e#O7Nq~yCIS!lov@$5CSS6Xhzv;=Rj51$#PEqGAA!wO#614uA9@+Yr zFLS_78Q`c|Y`y9HW$)sbA`{8|C5`!2V@jb)i>X>>CI|l3)^vSA`i5neG%ze0Wm-{< zi$##yLrh!mD^8nEH^`JpCY(HEl#Uw&sFoSEkgGLTWdJHWE6fB5Z6E{NF_KCtF>~nG4Ng3VOcf=~yh`*-2dirUsijy+DMJr+8 ztyB8B0REm^GEVJ8uT|lRjWp08GT0nbb&Hr#3kNj{FX#QHRW6eK)oPtIr7@j&N+YRQ zI)B(jn=D(U=9Q=$tTKmsPL$fmR;x1nvpSKo>6A&8du3HCmb|+vrK2nrof1udE4AXc zb5r-k=h@D5YITFGTmgH^tF5iD&Gnb;e5LO?c`ZE5X=^O;>lW`)3!djd{`?juLN_uf zhi58xpnb_1amq3(IMbI51$Xl~MUL8?%l%R37K<9YW0l#lMS@<1ud(Sv9zW$%x~@<8 z)QO+dwpPQL=1PvADM)e3Xd4rfh7?NQO8M`?XT@(?efezm62m4=Wy|cZ;*-Cz6;q?u zi}|}8CkYNTNu3ha84CCl3HxRG$pnq)LAJ_cEJ{g_R@TnztPWCy)J1}~dn6Q6TukqJ2q)|7B z0QpNEiXIGM_g)fHo|4du12~Z?&j`02*0b08QgtJV)gK#ml z#ou){aSo}xIkl`i{7y_koUg?c5>zoj7C&U!V%2Pzb-9wf2$2GY`NLinOQI;Cb!~yv zzODB9O(dbi%6%2Wz?A29l8?(#5``EkRwstJd)xkR>AR@9^`uDAQ<=g8Tsm=6HG^(J zj^0BBxaQ)V1jhOS(y*UjqiGmX2zZw?(JB8$q@CsPhU5uQ=?4P+vbJvyf@mG+)}M2e zn5Siha!CkBo~;g0B~mb!LgPMFH%y>Tmw{F9sN!@J2Baq|DMM+6L4Ko3+HR!!I+~7z zkASI~#9&I>%|%DvlfD? zQcqTJYx^7snm7P4Nh0HVlw|=Sr$J2OyFB_Z_M;7>prRMQ+_jetM~UCWe>rW$aAJ}v z7Ez>r%qe|kzleJ+X<#sFDGPuKyb(1`-r^+o%-;?18`g=F@UNyK_DWD83)c@qlIpw} zy-cB(vO*qwYUY^`kJXA=vQKkfD9(XLxfbLSqdM9 z0MkfNX&z@j?suYaBO{q)&`^1U*svLsK^}6Kl#jl|s$ng>XB9_fPfR4HZpxDL%H9kq9FclF%#y)pLsa~{M!P@KUJ(@{@bOBq9U6lASZli?&B89 z(=6!{=>kLKDkL%ck-NeTm$MVyL|xOyL1)5mV;3VBQQTwK^}r&pJU8q=ac8S$W!I5S z4Y|jO{jDx4$)fa^9ZY+D)}|d&r8h}Nne+t)#ZJZ6_$R*aS3cZY#s!dn$gF_;1FE`s z2@207h>*kx3K{ifB0|&5uud3}>8u$=j%w`(xM4XzY?Gie3Nuo1m(ZAS#t_8=WVgsy z;z3fy;GH!L^c%&UxCs}w8CDTcy`(W&BWo5&S7+RU{=XX!_E4@U?vep0J`~>qPWxqO zNF4JnS=a5n686A*b!_w7d7!@t(&LsPe}QAjA#7T*?}$#!ysA|Y`e+rR+EgUtXm1hu zmg@g`S_Kg?-xlL;sF)JkIj=gRG`>mDGV;fs6>i4;P%EwUgi9mNqWXJ`0?_l_EKdH= z=$F$mTIBjPe1UE5h71hIehDgyQ34;`ekp0Gs2;m6&dxqvRQv|O zVB{N<(;+F#$|Y;rma?N%*QJlg8Ci`k$_N5s=~f~;f35jVjFS+WcOru7bBD>kh~L#W z+4aTXOi?a2{}kL)Ax=ST9zlC7eyY_2ULkrl@I0pSAQPu!7{(5Ah*JGVCOK&afOeel zDwQsVf|GJ>WE*wjq#+utJa+-N{}!*(O?qkoJE}xUa^Ki;nV`%nM4^P$Pd|hJg26s? zTj~o;H`21zp^S`3nIghQfd)Y8IYH|T#SQth*WjF{SFOsew#pt_fdQoL%Mg;TV5y-1 zWBIZ-Qz0r55(02SMzt4)$&~aL0F=ORns0q>{rHZ7_`Sq~Kg;pxQ;-#n2MvIr6OxLo zkHaw`{2{A2UFOf4hy1?QsZJhg7_m0}O+Dx6 zM^%Gema`wzWZj*zv6EP`5m+?mB_|h!LE-kS-*q?TI>Zs9I+Db4T)*fXXTVJ~ictg4 zB;w6U2cg+VI)&y8c>&C!uevo2s(1AK5TXp8e{Vn8lBtGwUVA0!lJ;6|YG^ z8n<$FbP70GfK5OTsS-FQX^aI=Uq$1z?wN!e!VGVjpY1Hg4PH_FD^%f%XgvED(q&eq z8cCNx*92h7S0wY0sMby457gz$xR+kJLO1&|kz|RM@aZd|QZB_iC+a0_L=Jd1ZYugz z*sWNH?^L|X4y-gJ9Vr%cQ=JG^1ehijs}vdKS&}T#-vJ_h!&)%L=T!9*FB}qPQ6aWY zS)~{C{z!$l+6gX7X+IA+e)^%<< z+kp}6%>`ZmDcPNFv3x{nmV$s_+yCQ@65$>)%cnD*@-Gfb9#Y(51sTrl5f&?JTG&&q z>-IuMaE+|=ub9gtEv-&((g&a?Pi1(I zrW>r%t#~ehU9`^40=m*d#eb(cr;eNL&_1Gfr{=(qsqzS~kOl@ZMJuDGkSB#qBMSD3 zS-wP;^x>SWKDyv%1g8wL>L-b58|9pHCQ3A@vVlqX56oboDP0zPo{&PT*~ICHF3*q# zfNAgFV|$^uc@PQqipBhakL-GmEzkDqVi$#xv&*$q*nH%y9d8B$yuvn!90m5Usggpl z62OC8vy3UN?y>8-X7M}&y1D>YhACv?o6_a)+p20KFQy&w(c1gYbPI3@K}yCOwzXoV zwYM41WN=uUeZc(&Rl}y}-WAJ`V0~+AUvbO#(6!}f2AAKNrGpbk8FW!!85=RBgp-}| zUwObRzMXBqK@^cX*Q{T#az!onh+^yo+~Pq|4-9rG1ndxn1g+BqP9E0WokQXl*iWMx z>ULj3Ez(baPF5#@dsOK_+WoS3s#x!uPib6j%MK6t+;Qu=c~1}QIa$3OjIB~Hke91L zmBItw)1Lr?fF>u;I52$_eK^@X#|Az$TQEiLnzh6#`bkhKhTkLWIY@vz~SOtbnR zm-!}ca*=|Or|A&MA1RW)qq>&49Qb0~a#slZu5nk{tE@Y(96&Hv>*{}8{9UJ7H>415 zbuNXyb(eU+z666ZD+QV|?#Y}KxY=ergmwR z5|H@OR}IGb3VG!kPg6_G-7v2P!oV{0hXPJ|!@eO}(^5M0=MQ`JXGwALyPORdFtsq~ zKH)J^bmpwV8{Z=8Qk)>PbS{h1G?Iwxd8HF5R0B~iuEtuqNwbhrN~Q$l zCQei4+KoM~TM}J!14-;k#u}|MA_t+svsTLHIpokfyHm;W>l;DbS`VWOY^sEds7Z{Q zX{}IZjWB1h=b?2>-^dm1k`yu;=|WYu34Kv~Y@%88#oxt?M`X!il4k>~*o3(XkpBiMCC20LsYuD`{-|EHFg;OgO~F?Er1VZVxUj9p+D2mZj>ahOqb3FKJVQDU=vC*_8n4K*Q3; z(Wh%T{zI5$I&b8j`zZJ&b1w`3lHo6*(L297%s|W%X1}8gJD%&Zj%mmojsEoGoE2^) z%MiS>Z__0~QWn-afQ(_)W27yMjR-0*AcK=^D8dZ1Ya0i(rbb2KcWuXIGY@JRX;&Wy z`_t3gmMd}HLmRmsYPQYZ4LQw?DmYLbh~6T)<$B6wVUFONmqcft-p z?x?KXkwuvT{X*9uikxje3_LG*)xiWI2o!f@70EI89Uv+<47DyJa*RTxW^z@Iu*a(# z!Z^fn`Xm}|o4^4a1rtSAJ8nsRz~4wIcfFzNKo~V;2o^J-k!5dno05P;oaKi{vu%GPiOMZ< za4ME9*xz9rvvei$P@9Wg;B4zB-pJvz;LxU)SuOH(VnRUu0rw$5sgzIsL#meQu`)a@ z6bC&~H@G&0cDld{Z`f#Ylx#z6ROC@G)-3^YcCIX@?Tu%i`kUZe-24}x->Ln z8}`d5uv}H`EzFC7WVU6GLJMEL9Q-@e_`Ve1#RxEtR?lE)(<`d>DY0HXeMi)F`>2vS zh=$*3dMQb$8ts1BJ5_I)PSkXt;T>7md8PICf{W&}ln>U(A}~xq9Ib-k zg=DEq&p$z^Vnx$b0G?7;IvAF`&MS^-pkQ5u-_O9O_xAY9UU}t2cBsk(dBUsI0M?3H z$Eq7tIjD29(Y12u#f!~?v{muDI=|?9_!KAL-@th<@oJyX9aT33P-J~hRhMOEAue0a zgCU@L{}jrg$CF_W;|RmGOv;4V?u*#wCkn7=MO6dz%a zJwY-i-nXy-$BkpwO=Mvkr!z<6Zz`2pAVkAdv~CESaw2#vahFnNKmsGbyvE$am51L>3v&63KRMxaSn)M(tLbodl&yX=&hv8^c7rH9d!WG~M9TwU&U$ zToQ~F`55<73z3dq`SiSM1V53!bl)XpV*d3xv=jiK?XG2!F9ab?T3H^(K0nH3YZm0#4s~i*Q4{d}Nj7!;w z4AzW7G#f=K`}s14-7jbgt;x{EdcD$Qh8&U+;KN8;=8zkUg-3~$shVtd*GOEqe94y1 zEngSd3bQpaRN$Z$rJXj76peCSsh=EqCx$))O_UA}(w^h;bz+M6{IDKh5<60GPEVJ8 zkS);wv;pEU%`PPQ)9q8~Ki!|rR(LeWLH$Yz{TVETj1%(YKNHB~iVgrhyf^bXi}ZFf zc*9U=Z91o}ht(`!z!=6a1sv6d(vIv_B+CFAVbCH+uQG^H`tkB?3N4dfrSFTO!0W`e z-{DyL1Fz7ezCodsUj+~hL?w(MYe)noQ@s-y%wKlKvp}V)xJJYoj|LSGX-COo5(p;{L3b_*JGpLE5ZqA$($8cpk@#ehsva_pu-zgPDHe&E0O0V zZl#+#H8P|D$lh^qBvaLmk-iXp6md;Vi z7?!pB*WjFbAZ$}2o)F>PIPkhNhI)+zuv06e8F5OgkO`h3G=zwquS`*=jR3K8U)$)G zHDl_K-*hTEww!ryl83zaoc*+1~WH&8&6$R_UI^I`a&g(HE8MT=5NFQQUK?dR9TisFdJaJ506{gjG6W zV*avrnk>%x{w9EUoHiW6lg1RDps^X-xMm#$Qsl1@HOzxMqMS9*Bvbv8V3~ZKc0frc z+nh$`Lg%pVjVO?Jc#B*zBbE1%C zUdnVeugqf4GV~^Y%(=&MhdWEh@G}M^yF93TCDekYx{+)bJD` zL3*&$L!(LXxQ7O(#r$l7Fe?_m6bp%X1!#y*UpW0xv3SyfU4Kz5QE2)hb#C!hHGM}> zyK?Ke3)xgVUlwoK55@~SW5W=t7K#jKp8`v3kK83sq1%!gK2B34f zE9RNfq{Tdt-cc5!p1@qf*L0jGQOvXP!2TlPN`vLscr`45cT^=R4cH(n=XP4Jf^4=- z2YpXfN7 zeOl~=m}x$5EKjtMf3-&4ZypOq3oRpoX&?~chAOyQ+MBZQ1Z|63=y-L5s__&ZY~$KCBn6XvbzVW>fQ&SHo%XUIGL4 z>lAlghm!wPJ&+X%n|LBrZ7Kk7RHY-zZ%h}FXtpiZ$)rGfj$tte!-Usug-mbYgFEpv z&?<8lS`)LBKT0v;MSm4Q3FR{*iD7xRW7G|zaQ2zcvnwTO(g(|{_M^tG?B6nWOFTuX3!d^$7g#_llX#uMQ$r|TX9Jf4n7~*j@HM)! zeeImCE^4P7j5?4k!v)D>!Y<%sb_Oxs$!HICOCPUK7l>rNn7_3s67TeRWicUk?~`@i zW2JTZoUD$jny(9(&SzyBDPIQsXLi&8D4s7~zU-Y_@xOw0au^TQq)=j(ok1c@mURUa zpGx6yV?m#cB$^cna54BoMUbU8T2Be-%k~yBHa9W8ljR8OvLgnAn`$UiJQXvjX%!cj zBY8*_pE$6DU9XRBzUno~{`r`S#;eph#Bqv|`Nbpij+Yt!mko>j^n}*4vbA)o`M>zL zi0@OPlw8gwu(ua~#wQRWMF)aVm%MqsBhhTFnltSPPA*ymrEninnq)Bw2oz zMb1D6-(;)B6V(x175!aRiRy|7|!!0_=Q!HM* zBkQ_l*Vi)08+*&XZ6}UlsN?3W6ncVFG6RRUf_1F^Rlhs%bEzcEAckJyM`X!}P7ilP zT@IQUT6%Emh5N-40nNgt>8JFHt(G*xz>PXa8($_Tq?26!J zUa_U4;9{qXIIU*WPdoA00l-D}@^Q)Yr|pQ~dmk}wCH@k2*yzW}>~u2Sph`2*IkS2v zyxaSYQGp^}5B!~~)J@k$lU7vDxaj6*Hla_2P(k3FuFhlalePb4?_}+@M~jyCINgzT zgI&Wb#rtw&8i3?^qSBx;j9P4&I7!gWSO|(3$61oz=n~xvxt374Wiy&;m_@k?#avU* zj;!k@!xs%qMlXe6TS_EZ1b7CtEviIJL5vd6ZIHb;svs4rdDRZ1ooez7%9px4!Dm1W zLFS%r-JojNAl*}?xRZ)$OZH^5<#)0vA=~J)*k}zB-l$?wveB@zOl~g$ZlYpocKo33 zM~Kars2WzhJIw-1rdIFs1Q|*r#VUz=bogK>%`ypVT=zBD++ zC4b3Wz`h0o*byZt5??Q9Lp$vZQ`NpzmDIjXtHW=_=fWzZJ<9#QzYYW;L8w4gqTIEv z{8X#Pt?V6DASEB3_%!>@s=t6X5FP;(z>|qTc36sx3D3oYs^!UOiqA4*LaP`qNL(N8 z$hvL=W46vsdy3X`X+HJW|FOtOqW_g7}F%0 z_9p1=F4%tESdg881a_fdI%2X9!KY=5P9+rCpqmhZuB#0!ANHKmETSdk59=@OIq))05vCCYff_F@QUjejF6t90U)Kmu4c zAs5+AAmm8E4p@=5?`$957ukI7g1~r!sjh zx|tdSg=TWGlhCbPVmTZR+Nt^ipJ~k|8V!)@c+%UYmtrSbxo#t&5(8{w>(5fYc5Atx zm_`1{X>-u{ms@00YFzEyt1-zIi7cJS9s;sBJ)0$M*=!(fR)UxfQ74Iah#IL{AJRA5 zsF(n=WT!)updqV~tb)tfLOberil8|WViQbwJaHJ%tNl(BXr%IM6b&n^or4aZ7OaMK z6X_PL%YvuC#cIR>&$z@pNu*MS1FjbN8~bSt*1;bim?c6hBKMR@Ms3RjHH+6ZYflVN$$5Irs*vyCG2ZS6Lz8-rb zXTg@id>YCS5I#x1NFUP$#aXvxhc&tf9guxQZtiMJS=|1OFZ}_CL z+E$%)EJe{Ik7to(9KIF=dKkrLG=#!s|D8H&i7ocvcpSLAS%R}CeAjKc*k_GDev!abJqNe_<|JcS=ek-dF2y*6LVOTLFba1w4Q6Vk+jMnO%-wx+)nteYZSC` z5K8pXE+)mzCTAo~Q;VEqPvdmj?KrUcxZkMK2Z?H>5)mH**qW|`)}$}Mlua!C9;tkxJGb|Ra&E&mK3noGb4*D%3=EU#n zNa;*WuI(QVhT3niZ`kwMyRIa~8m=;PTA_h2lMZH`N4_|NjLX5l3#B+%haI7Y14P54 zrqnfCkMw8fh;{?q>r^Gd9SCKYc5zPRuCj-e-zJBggoGCqEU=4PrfsA4jOj-jGia#A zcdGlb`XoTup2^PTL>`KwKVm>t7Y~a0Wa}btz9wTO#j4DV1)L&xeWvw7Q+%8tm=j|` zs+ykNIk889x;KvRDNO?Bb58ZnE1iIuoKw73$*wOmBBQ@GTS+rS9XGunIwg0GkU`z; zZ{q(Vf4Ywqq_B;)1xDO6ir4*DwNRX9#hw3h)Csp57Hed&IF-pWt}82bPl=N2v++W& zEa$6qB(;e2(f~R1FdU#YcZeE^Ur$u>;2Dc$lk2oa8VcJ&pAfs~#hax_CdJZZJYPY) zg}K3<VisjSo_ z3a22#T;_-tEAvpRJk#lKy{`Hhu|x`Dx3(6$jwrhB~^N-3RbvOR^$PV&nbzA zg=q}>npO>?_ZM4{4VY_;-#*w9h{+6Uhb^oSA-h&E9pl%V!M2_MR4yW~*>e0^O^` zMP4jjIy4O6q-xF}p4OWr6`P-!-Sb0kB!0QV4FRjTLvz$$|C%4 zijxV?*JlM)fVJh>ITC(G74I@C;`e-!x69{+WIW@X5<%B}8aJ8Y-($Uz`>U2NkCrt6 z)ThEcKRd%v4~fcT=oMCB3N$GdN09@Qi&d!|WVZ(+!Hcd);foOAVVX9_5Xu1cfOHv`42Rh=H2**}YikvQgj~ zM&MXa5^&3u-+Zt&$edn+r1q0Qo~e|Wb$vE0Cduv8O=}5 zXYr6CF7Jw&fTRYvaKP{p8Tb<2%%Ag4h(JHN{Pa`qw&tYQXTQXp8fd)`r$+gKtMgAQ zDq#;$ObI{cYt0K@$x^&d0d)B({7ZEU2>S#@SM7!#?JOn-XELq@T!1LM#qe?9{8B|L8@J$+c#syL<8I)ITMP^Tus zLFb}aX0ys#!1or(>Jm&(*L+4#>4VCh3t~@Sf>Gm?X;n5f-x>coC!oVU8JY68w~=v|*guj2C$X=xLhr^@_I@6F6)UK{~0dc8HK| zSk@z!qP+BPDT`(bEeNh*5V0-SMccBY>T5)e@{W!uC8(;Z8`)7vr=L*}dk%OSe1cFI z_}vh7pk>A_EUYhtFH3;pBXp%&qm?Fvz-d_jC7vY>I_24m9154fkDwVrUm@qtJ!3d< z3LTJsZT_$~E1wA$g(z)XjtI*`R3`V;N5xU&LmNBU6IaS=i+J}`+D__Lj zFo=SrI&bVs%2yNY%W;RQBc`QwU6P;Z*q>iAX;XpMWd#Fk4dwh2)2=NsS6H%SL!b(r z3vf{f&xVU#L4DaDII`k`WCS_YR$dTma~g1jB`ah+*#Bj-%(HO+}K zZkp|Znb4tT*wTwhan!4{?VRjn!d4&|%cFreA%1jkhq8*dAjQ2sca^rf9WMxuHyy7B446vh@|&K zX+ZTIfhN=LH;IwvV6*vDhDAK_Vbw~(7}6}it7c3jZK+q~rWs%-WaC>@jR3)ps$A2v z`Dx88@u-_$+&Zz&GpA6$qR;8Mie|mu3btb~u0l;TYdBKTPt5Jn#fQaVONV)k2>nN)d{6g2$I&pu?91m0KwkAM50|Nd|P z`1?Qp`CtF@-~axnf5|qU{NjK7-XZdmryE(jAl-3oAEUB+w8m0Tr6>1BB6np3=~Opv4A08ikWzwf%J7+wR^;w?%s&p z5p&Aq{U~-MkNsHQ$RV)e{`4e_3X5j8YxFWjp6S}zDofAf}q zmLC7`=|f@AOHHVfB(P!+yD9Z|L0HtBAWZ}|M}0q{~!PQumAVo z>31fzWDn;|>60iCnNldrp|1~>1y<LcuuJkJxOIv7DQ$jpF2Ch*t$r|lRJ3IS zH9A>JF96AWhi!nW0o%GNhyV!R3V;PKOb#WpNeyg1XW91mgNe+!)`bvqaGxc@$^3Jc)E0q=%Pk1dLD3r|Y)oKmYuq@^lAhJrg<5Qo8G)#g>TIZM zZz=v==bE;nbF#Xot50u>ev!$ZY24w5_eM9aT_=h>oD=d4`sxK znRmv4`=YmH0nTJGUBS??1ov5$R$aA%e4?4EH#8Sg^V4J+Z!$}J_BmbM{bZ7a^lmGd z_-~2_1;gy$f_=)c-GD!96E;<)En%}M`tuDdGOXu!R%GwX;-22`W`7~Dvy!Th7@y7> zYpZHPSK;mlkv9t9jbyLxdgsHSnBXtKCr_6T9?GR6m#jrB!!vRo)tu7ETYbjl@}If@ zu<^iQZ;8{Yp1}g4mbfGJyeX7O1A4}F)E=h$5MFrKSre=?R`*w}k13D5#>HQXBP z%C7t1bfvtH$s5L6y$cWzVUWu-cx#_Ag-Xej4IaVilh^FAuanI*^z&i>LLLBWGdW6i zWm8!^s1+e|2Jo1^VXuA<^5PlvTFVLf;?JfGAW@+fd^07ronVi^j)Ca|7mB9kKW!)z z+#458%(*&~3h?9aFi`wZR2kCR<8tVGy06Ul8L!v(p+c zO!oJB4Qs5Lf}dV2eA&=<+1sV&bcw2f>&YFRd-}NYJ%B;Fs11}{DYQ=Kedg_I$t3TR zv(XXT-Xe!g2Qm>zm+Tb3Jr&C;(S3{-$UhYKq0X@)63IrLuMz^QZJ8s}@jB+2ijo?2 zARxh7Epv57vN_ncIdIV1RwOU8Ovl+M*T&KnMqmut5){Gdm6Tg)FR;A$gg*z~Pgj$l zSxQ}nsl^B;bxa_x^cCaN31Q`es_s0je>3c&!-H6|pY>t8Y*9&1K#h!qQyB*qs<7z5 zO)hxMDJIBtja_|eXh4=?cT8ejq?9(B8=fdv)@+_DS3hf!1p( zpW;49;S-|byP{bVS}<0KoX6Wz?rF3q|ueB&*potLilZe&C6ZI*dN(e)c>_$M~PD0~Aorx(uLRUByL> zD8A?;CPCrUXCr0M>$bX8>ce(szQOy#{?!v-m%J>8KegnY|Ah-=?05PR=9TDWV+!wu z*2GmGh@M46TV$geTvM#%@Ian?@H}mHmr+AZc&ktC+VV}}R7CB5&WZbdz3RJS%QU>2 zr!&>6b_p1stmjkzOB)7ey)%KhmKzb59PsSZh7|Valr$zV&qN`eTZM7?^RDNd<4vqD zwj+x;vJX}}6d7uulQZ{S%h`{uN43jl0ebtX07{EnwqH?01p-EBL*G?pBLXAO)eX6e zC8QVZFgIGUYMhQ4)!LkG_}!O|y|MP7Sah3r5+qu zX|Qk*3NDF}@-^^xe1hpPAHHcE3kH7Uy16>oK;40hqD+)4)>!7knQgP@>ukE3RDw5! zrmPpZsm@m{?=uA4!g=ZaoGhK_mJW0c=rSyD9#_?nDveZzu9$kwrnyq`k?f5#$*oP4 z0_rvq6`(7Z__j=0_y?7j=30~?FC1zVE_u{g0QtkRT4T^Q!<#B9s6jZjwTahxr2+MV z|B~79V3|YJp`|&mNZtXH@#H%G8nUWc^Dh-AeCD$!ZZ2&jZ)x~iU6yLnX?JskR z2oHj%PW~A3bSn`zX14%9fM8A1=z63lAH^BD0mqK@qs{Q^Mu$#)`~t) z)>}ZK0IFaFtkir+_nfu#d}KX3(o&XXsHsBAQhSEQld z!eelbx-|I^n%af+PXtj$bxvNdXCPdq0nrD0EtD-pliV0wPS*ecnz7qsTIZ}ebtRST zQep(bZmp=9^oxxWc*dp7Z92uZCj{mrPx;rOI{7pSG%L>*R2{6HJ$J3SKYI(Al5tv= zL{3)VU=rDgsPmSv6F5oxRPK|Rf5%dCG3NyKb+MR{m<=qh@E?sn5?ZUxa{0m+mT?hHER(q&{q|FbCKuKZC)5+9egbD(mf?wa!FGhS2?!N?&PIcnNtFvq^cV*Y>C#M8c0Qkfk?jeG0Hl4S2j#8nJhG) zh9>!G=wn(Kl6Le!tzUb?@9Vky<>8{rq_;xS{OIKJi8uE$|NQl`qKVK3GWkMPwn^59 zB{id@h|2wajVOM5lBRc(I19!!B!M9TA$d{;Y~?VTFh0%3({VhcDOLJ&J$sQvaZqx8 zPKd3L;n$}ni6oA};%WW|<|9?X>gTcUf{m@0Xkmf#C2OcaYolqGIi+uKAb*|pNb4l! zmianhNqr-V5Yss)9hI5S`wU}D1QJkL@&ZC>ZxLFNLaxv%5Yq7#?+gnY$YCE}sS_sw z$-H?g`V9=pye0TMLyORi-RPrNvm`1ulwp@bVjA6JJq)5}Kapr#w#}w}g+8UBflT&^ zjIMl2&7IXxOCYh-a4Fn7J;3|Sdm&G5MiGI0P@>G&7JXbnj7x?xGavIM`go~<&UFO7 zcjo2j@iOplg8Fn@wNLBC^M%6n!p)~76wXT`+XNtGZn^q4xSGx64X}_HPij9eB__u#b_aZKV&mht6gwp3Q)k$d5A=HeWm?`7RNlTf{eVKeAN>a|%X~{9x zZAV6k(mKo}#gt}A-F!4Ri6TM+RrBxHh~J+l=BFi)QP#5RL|By`2U#e)lzyZ!uUZvR zMqB%mg~N@m+@~R!NqKP5*n4ylf`JL?R7{+h`(%hq?0*eqIc5eM<7%m~4wP4`LC=H{eeD%S5%$Vf~$HvN=}?cO?kO4jH14?ngcx(EgY_Bl>Y zJo^z<{3>{ec?+(s>aIu%kxDP-2acPT0Y_v@nON10o3{iU;R?XfU4z+W3z90|In%nf zvKBUO`oSuSV5igjGIR0+{4rz6n>oi;?9Zs)=4YFkUZ-ogjH(Yt90QP0WnPk|ExfUc zjk6cc^h5ebK46quQ?{*GJeGQXuoVV1l^+qKp|gqC_o6Ey>>$4H2-;0x_7C_h1ldhs zb}v?bu3ccTE0Snu6!obdGT~Vb2gIkPR}LqQL4Uw7v7&04giaBQJeF$ZB0#?iNY`HW z2n2^d4Wh=KloE|L+74HM8#?EPG5EO z1H_feyln*^jT&>s@zUUsdpZ z64(byRy~?39vKstu7)ZZa4u4%sS3YO%wj%dU>5tTAgDr?B3w+Q2zZJRs+iTZKnBXB z`5zIbp%t`40JBLAG+3;Hq6@D@pem1B-0G_LV#h9_RU{*%=&tnVL(j`8GiO)?s7jUc z1Nd8OBLv-Wfz%nw-$(*JYJp*sl+~8ji<{Et-2?mH=g^eK0ZmdvRgs~^Pk(4!5>FZ#$-Ab0R8qoicQR!+MFsj3+h#h1NLQVXAP$@XrTEDEG z#7rE05D%s`m`M?4ap9^_?OfoHfrACnvj9J}>e)qci8kS2uomJ1Zfho4VJ060r1Gy8 z@j3IzBsn>%d)Nq^?7673Yf|{0PNkHUzfq*foa88&?>VOwp$Md8%NnLFA|IwK#H<_uhuvajeK_}CuDWU@|h9p3)R(&6n zsNtaU@`5a8pqeuPh{wK{Oj{bsmuLSe-~5oK5mMSaVrdb(q3cWx$G*4T+T0GO=YuU2 z648+l42OsbV5+3^95-4@_#aP3D%$w&N9Uw`Bs{2>U)&CU;^pN zkI(tUz{fiY`2Fc|-_w=22{q8A>xY$OB3JdgEP&CffywA1!3>Kk{AK3>H`UaEEOA6S znUxb{gCFoJch?4OOn(Ja)1+7fbjA;K48(;zB1*b`PE@B=0_$k9kPXV02BT6cmYS-m zmdlSnVO45o%9dnSHmr}J-oiPPV78S{d+4~p#(>0jyxr}P>BZeoDwl6#(|gD-pQ1cdV33c`_T zBq9azTnIBZ^IC+{SSzRuVeN)nqWh!F`;Owqz-Y^UTtO z77ha0s+^vb3zqpoEU)o57Y3!K#Jjg(g&)kmW6Nl$7V+FrwIIHiC$Q3EI5PNL_gYCu zUy>EZD|6>9s*_0S>dPcuvZ~MMGb|BR;?M)ihik+T+AlQA*)0*~Q-hco^b-HzUxFuo z84HMX`!e~ieKMperIt@rO(rJAh9w9*!#AHRBtf}UWhWG1u;JY2y}OiG_E5mgByb9Tsr80^EFxMM|ISg zwf=q-2MeQ_SJEhX!S8xWvT><2pdnj=wj8@`Bf*|mtUd!Tgb&~w{CUC#lDi~n5nz2J zg_3ZRJYNRhAmkJ;cr{ArT$Tbx*^nDFjf&?zmkK0>lLi-PLL-u;+i7280+zVwO!U%i zndKSbc8Zq8C&7$aCmI^qVAju@G?{H0=u-!G_zYUZ7G`8t(3kH?mZ6>wZem*(RXC%H zoj1TrVC8O}ZU6)L?d>Y?o7hy^9 zP6N1Pn99l`tW+SRbsHmiUHk;=1EM8H|4hJOV#p>yr@E!grD@$$ ztVW9Lc?-H$kn&pqRkH94^f~VUr1E*EEg){^4G_pmpj27rj+qncSa4wme#w|IYR<%6 z*N}x6K^qsi^(M~@J)P6k38Cdmpx!vBaxftYG98>ii;7b0bPv;+7@F$mqVjysgpxJ3 z$DB?GtTu`#b|a9Nx9OM6r zPqMhg&oPa2G54O}aef2A>qttcG6R(WkRz=aP+LO^%h^tnU46SbWf!)?HKa9Z$`GEb zlufKopurMh{iA(UKRc*_d9dD;5QbiRLppec^Gb`k2&H_((m9;@>OeDM@zR2(V z?A8}A1YS0YFtL%*=m)vUd?xJWSpuKB@kyoyo#BonRq8*xtm=)1NI>wV#GIn6$3mWb zna>ajLa=7f{*Y10xCi3bX;+HL*~rQ&MnTF{o5o4aI8}5mcAvP;LCdRc!b`!No#E9= z4#DC8a=uKyI&=LwaThBOt(%|Oa_ou)B~!8VX~N(b<&1mg{)IUBcZQMJb#A$(a2#}& zkSVvNoo7yWioC1&vXdSa9>UR$4>PC}jKy)&{^rAMd{o%i#vmfeRQ-^u#AVddTe4fA z7$(My9}Iw#AnyqVAkrHmh1;0Q*Er3Z)=l8rR6kX8gbIauv`O{P%?1}o=DcibVU+g; z$>OB_Yyyt!EYcr$ZvD1Om7PlI(vs8$gDPqa0B1y!Yh@Qd;7%=zVJSGP=?!26aGZ73 zlC{2+cbyzK&pA0=sa&s;Rtq|i1kep|G0aNJYOx6vr0=u*pK(VxlI|K&MKYRNdn8Mf z9Oxjh89{3OrF1{drUO@%yGs{+Qn8V&XGJA-n6{wlv4L2o7zVYG#g7>VcA|E~HElO= zj2seM>|>JC;T*niB=CXvk_Qc#_d=fSXW2Q&T4ad1eHp|j{cP1!q;G3XpFWN4p7as| z(YF#Bn2ss8fR#yh?%y2gb{_LuW4^7cRMOgeYTqp)CW#bxQjmblCMCS4e@Oqjos z$n9$TbbApdpvLBFKGC>cnyNuW8H}IEzLt$hUZ)D8Ft8#$RZcq?{<)_v zLxdkSISACX0DueKZ``930&mmQu_gDKJ4 zHR@eXLPR~sN6it*Q_~Hm9LQQ%)F%jWvCB_v_vUMQZtQ(|R!(hxIz?H2{RRUB_2&#o z{}0taVy{ zJ`t}S_WmfAiPO$m))9ylrg`F+a2m(_Rdb|{xin6~hYI!YMX*Z?F&b_wdIbWc3#9^& zSWUHkmK##vcP1<+cS9Z}0q4YZYK2v=YC*5wcse5R{RwY*fAv}&c|f7eVnAWPqv8EC zFc6NCVNMn#mmdrnXk~#mfR%w2k?;>`N1T7Qo_GGW>nJscI$~faoqN=o?%DgY69L`P z*h4XRYF{*V4qS3aAdi)8qq(;ZQaxRIDE1OeWu07#!fh^DejF-sFL|}%rnk3qdBUr7bf1#du}VCcv(2)g zj8jzPAumzA@r!1m^k$q(AgEO7A^Ty|nAk4xt_@$r8W%IyGBJB4Di-9r^`|CRTwCH= z`BZT8G%K_a4>$|0Q8AG`QLl5-s=F>on()j#PV6F%r>iil(ZKOpWA~V0a3dV~AOH40 z|NYXyvCar#Ion?JEF&x$X@KVp zV2F}LruNOm8-*2!wNF|N{SMPqBXSRE`YziB+(?6=HnAEEQsd<-S@S!t*?U?1B`>Bw zL}E$uk{7nN1o*D@eG)25R5Bg8F%BwGLSXk#dKMeCTE3B-hEn%va$GgX}jpl zayL%a6Da!TmeerLN90Zg$0V7anxHn?MwT{;7Dz*`Y<5kDLwjERnGK?}xXz_~iD~JH zxnM^$yXhuLr#w0IMRn#-k02A+;bY;pW0_<=;2Sv_9fukR>VVR;=oLg#8Em@C?m6cu z@Hv5<#<3aIC8OpcjbUSpb4g8uQVEi>n&B)8k;7W)SuI`+QuR37W}*Oqp(*|Ici&>& z@cP_7ui=3N3%O?itF$W@X=$VkBp5#~BrMX-@@$caMgln-ZtLxxMB7M{VAOb$%8G!i zz2#|C%wP>X_fK1Zl=CsVk-ZCAz{KO?4{&v~1iH!zo)(ayw)8AA8uuvgiqgf|AVbX%^=;uQ|V^!^b;MDZS zfySH94>D1e8sRAc+_pSirzrzG=eDu49o!CkM$3V~Y}#~Hh0I0dm$@xi)(jP%l9ec* zW~FJ5u9k&OClmgPM3ey)qrRkJ*I*yejus+{B#@=&%H*;!epjpxeov6{8Qan=ksdOk zb_#{X{7eW?;OvmfWmVszZxn64;3B$4CC|%GBT(5j{pKouitKYG>x_Z&&n!9O;iT7! z5FyZ;sTj!?0I0J!7jSRvfozQc)=n(3DU6?fnrqyL#me$uRyWn`LHyX; z`(3*BKj@S$t-Ud#!brum@Je5zt~N%v$iM3N|*A>mOVPVldKi{hc~q&QnXPY26}!0UoJ#C&?rnLO4;Mx?R` zVG037Oj*tmBc6iOxF09sf7+7b-0fGv_4tXt{3 zESKrVK95g=5iL{+w=&Mm`!H@*$HhoQO61a?XEx;}T3XUk0Vq_2+wN{xC9Tg-Q)$D;_5kCGMn)eb4F< zvElL9!iFjfAkxp0uGhd`^%hlOA_DBuO{CX+!=X7G`E#m^*YK+3bmzS4rS8)YTcWy! zD4NHG3nQVV4xxdIa4(4}dzqbL)aXk@4b#iM(VR}pbvdb@TA`>hO*J5W{e;=iuCMC) z2_&hox@u9(TdJQzM-DUNf74s07(=%QySH%d*Q;FPTSvh6C(iiT%lM#$Z|tK)OsOSJ zR>8e8uQ%&e!u^piF(N4t9Ai@C>Ql#BO6knrmBBY%UdpC#<<^62Z zAx7XbdzBrk6G~dVT8`$rVlhhtE8lxDFq_abkOp_7uF%qny-(XAYwt+JN7)^jjh^M! zH@v!R{G%< zrUGhj-2Gn zsx_pU$0{ee`#tZpL>^y`A!9ni^-Ok^1WpC=dtrk&40I-C^Hu+)IKL{V#jj?!M5+JY z=j>9F`2@yZ)T(x7lQ?PPkf^oyg}9zr#~@A{~_JW&`r zSCl>?c+bk>&3gwwfu(1lxjw@_Ma)}XgN-I?UA}icCI}RGPGC1|7ciMMR&KLoB4esS zhx8C;Xf6w_C>6B-NbHD~oE3DO$z2j!&+5~wX+6^W)+X7?b%_J{lG(^j;Os*k^{QMG*8OIjom$6!Ond~PkC z2!R47k#1aYdS|xj-tw9oA~?L`qz_Aj`G59lJA4!L0M9VW@GgY2c{0rv)fW?)o@yD7 z!=6kM4cOMjr5}9Q5q?bl$efNL1yqgz5s^mNXF^@nmIHpISeahCLdYVl) zO?G-IZrb!DH0Q+h^7d&j#aobl&|I>240lNx$8o)F*l(dYY!2vLt#imoNfK4?d0oh| z-&OKhcMPlz#I2+1pm9R!MXD+v&@^|LGNhStud8I|NWMVUFjN(6tf6Y%Be?cUv~{;= zfd-{oBqs`3dl2I79m;-N!cE!JNi;BUa<>gNpvufDvm}CumYfL&*eH4v#~Ivyik=A< zR7V7;*{pXpY!a&?K36O38QTTk~#@Ni&f$ukVLyAICUR*(F;dLJ{LK@@$*-xVFxs)3*uOJ256H6DQ1_-cews?$l1@W(=t_m6xrF zopRoOnxVX~4)z+n#ASm1myLus1QUFj*mizNyU6B;SWDa(Ri-|m@4BzsrSOM1yX?3a z1Y9o^8o>t6N-^Yv0I>21Hz+i6p=Wb?P1~ILV+ho^b}3j9r|<>(R%!vOKt3XRoj`^u z^A_`KYMkT8#4A2{R0ru<2$a>Ds4EBDuHMw5jT;n-<&2TG*NEBboPI<=CVUvRi@y*E z&(z?kG7WxbMsIS^01s?yeoOh#A0nbzU^EC^x};}!#3zIOLT3%O=_Z~cDy5zPP(a;) zG%xWqaNx6Xnumqr)NTeQrUx2#2Yu{#(K~1%s!}NX)1uCmzAog9+Px0wu+_(2^`}o7osRIQEPfojeigw_v{rTs|_9gK-B%=aJj|%I)EdB_D;mCQ5yOUiD^}bAJ5tDEs_}LbBXJ$1(Z6YNiTEL zY7QBq=;q~*2$Dj`0bb_icaP+z$g#=i1oajIq$BK80IG!;ZB$+q86fU(s<_jk&yVCL zK}G@w1oc8!y-Y82(x1+xuCVv6L*Jd*eQNZsE?qMPDNUo!qiqxiA}Bq~@(@@==Im+) zXn*s_bHYX#La$pC3jkTuBpV z{s@N*DO$UAE&=wT91z4qQWP)!Cb(**Y1-!AjOAwkUnXPN))_5+R;2wE+J1>W8Bo!v zk&22Ti{ef?SNRzYlDU!R5ZCtyW#O|Lv*z|}6$xiC$6~__E>g6Prppn8V;ZrivwmjF zGVh-G^n83v;xjvy_JGXkXW!V7s8xMNIPbG_rDP*Uwq^uY*q3EX4~cP71Fh+04fSFO zT0^L^?5Tt;D>K+GT}%2CradR8#q)I8Mk4;AWCl9bs}-3|1mPE{l(sv$>{RUV2i-58 zE5Zz&l>qmprnLTnvJvsg|EOq+@RJ3i~M1DD0i^rz3)jl!ga&-MTsmV*j2=T^GR#iZE2%XWeS z3>eeX;u|twS=+fxnZ(&@H8ZT43N2k*FUqJo`hncRd^P;RtCT`m$+T~XZL_N}bT8TTT#68@%!Vu3nbj=eu}BD5q)*U}i@B3_r^7}sqOL^YhwT~W5Sq|t z&nQd^2=uMV169${_JLjiaVN8|>>E8cH5!`IDd{iP{fTbo3hf?E=}iM8s$lcJ{xJ{x zn|WNd-P|q@k9A40x|kxH>g{Ard(;pfQ8iG)xb?`khi z8i(rPAZnRi6;n8(=CSW}259adid#>Nt#rJ9tW-wjrdyq|XGTzx*0U&@F%QIjfcCN9|5Y zV8Ad>QpzAOA#R`2Nb$HPHli|?lM)sQRBDvpbRa(GTccbq>T%vVzug(g`Q=7cI+-DBl=VL?aw%AN>Y!uHcbckgl{+`c_h&%sX@5AEJrUolT7 zZCMUk;9;XJr@n@w`_x6q_MtcvmTZAzac z5c2s?E}Uu}=m~Yhwi0dVoBRPq@I}U2)RsYt5+R$|>;;t0SvQnkha;uhz4{0jU$0`i z=~qe9Nc^_6NEzNPQPLn0gRNkjy#2^Lm{fhgA}GJMy{zai5dz484sHFZ2>ShYpXBDi z4;sP+9r+y~k!8hM@)b2qS6DPC8?h?mP7_mS4W0;@KEDA?oi|k^8{PTP;{6>P2W{WE z>EZ1TjK_+@DUA5E6*jqDfU8;&B1W!391fl(7Qtn`k~r!xBIT~2l;%QYw0u`M1=@0OP_<~IkVjCa7TfN_au7h`Y7xo z4+9>8x~d`Np2F2?UngapCUk-(IV%5n~YVTx&jnc66U4Ly(if@lUeS9@?oOly$e2116+1S?IGxLmt=y z;NBpL>!%BZ#VnlZ4>7)AtYjY{878j06o`MA`)I_^1R}^%H#jUgA)v7n!8(~2t6#Iv$M!U{>0nnqgd5CRbayr#=< zZ~7hIG_YsAw5jDTj4UI@HPtZlT07d?Qlq^`T?c4)=byxyB=!(u!!4E)8wFucTU z87wGNG>hCCT9rk^DM9ce0_bC*OA6{r_8@SrG$~DoCLqH74B z^;uj^_8@0XQ|z@>1!&8xN8sLLN^;R>pb}=@fOv)FiP)q(iIxC&U9@x6^{9Ld1*~&D zii}yUCt)U1Y2AzK5mdNIEfZ?-ty>&^vABJm!9j zhCAD^l+UnX2D~W@RSQvriJupm!Rkf(X;M2*zHuTOzJsSQFs(CNTyA-s{Fd?KtDiVl zKH*wT2#>VK3M;E()xe!-F-$#>x~&vb#djy*$+}|*mCPV@ty+N+_6jiqRwZ)EJM(Q$hcO`^iAd*_l8Cr!9KFomVY!2oMiyam+Xfy22#fm%h1Jm^*M3_LH%qP_PLhhUZLW2L`Y~wR^o7hYrG$iAi@XlH`6p< zQd5mVm(3zYxe{2YK&B+32a$O`;dYjwr7nh)^&k+(0rFoNyZO zOjZRnHD65ea7~rQf=hCkf~&*kc!gUkj1_4>CSltNID`pHq;W=Fnu{2n%H3I^Mjg7y zLIQr-+2lE%PAFy)@`^~RNu-x6S<^Zb%YNXo<(ND>fPMO@dRcCT z5?f}8q_y%3&+ha%L~ur0*2TQ(4|bdZf!IdhjZ;7|iWUq=A~@UXbBm~4A*{4z1Jgy% zc?-lQAut|F1nBL?;$OBM(w$LK-&5rnl~Aa8u9Gc0&&)&ggm?O7ax2MnVZw=i5n{n) zhFnx+G^$04(#@sw94=wV6)t6#8WN5RxqD5&-3M*y~*36{MfG9irob zTp)Z3@V;Lz60zgyDHHdsLlRljvp2IwCCvdTeb%VUCwJ+HeT0eZ*z`RDkhBO;ZN;yq zLUGshh2BJEI`d9%l0#=V50YXY#LZkeGzoaAZ2cX4EXO{QzAn+qN3c@BVev-0K){!R zz!R+ttSI}0kDU>RJ@ONOIP??h(f0K?Hy&PRs0@Z_-4b|NsbZY3h+jkl&;=YztT5dc zM6QnS!P!I?t$HxKJAxi3D)QR_Reiye7HgM75yOB-<*F=~&NT=c zCmCzO!+|m9!<7k?48)Lu2N1>TiAe#w+3ha?{!*Na(*p_YEd_P1UY~5^XCe~FCpq>S z!3B#hLO(=kIYW_y5F~tR7xBdDrj?ptW8<@wOGY;!rLz>fm!Hdzn5?ZhjGOq{8qcmb5X+1m(+~YK)McHRdGDu4n62@(+-tts)nEp

}DEalRHK^E0ZS1#g6@S52deS>AZ;it*$vTQB3`Vg^@ zTW+o^nO60)0GkU}*zPB65$s-~rvJmEDg8Ifh>rBXCmOm@Pxq(O$=DqBUEfVFm>S)s z*dxr0S5mk6hbWR7!4S4BKSxojK6X*U=Har6oa*wVf7qI~%f2Um?27LJjesB0ohdmM zv>>Kh@3K=U7&47Mw9<-)$!8UK(hXL(zzMQ*uS4Y#DsY|pEHqw+BV) zs1?D$Su=v5q>(}VY#iKg-DsJF+-UwO+4E3Jo%6#RJ$gb`Iz><8)PAF6m@9%)R?8lW z7B|Z%GTNT(NTx6`3tBecMxD>=add8qk$ZWI8c#OxPj8t;@L~Q}J9IA4Ct*~kFmxfa z0fCp+2Ug;3M4sY?d3zR9O^cn*%VWU>2Pu2Im(*4aOLqqyNz5MHyn7)4A+R;R3Ko(25C2KHEpQf}#a-<-IqZ?O(_KO8 zM2;`6?yeT49q`oJ^|b6ZY)Fd?_vlSa3&lfR&+shG=GU`Bey4V2>MNtZ(f++xSDkAC{&`#LGTQT%=yI4hc zeY@C(k_UlCP0$;Omn-BcT&HgG>ZWAcIbna?9=TIM~2GU@nR7_w|x}@`IL52fN>U;b>wdWQgoT0>`ZIH;z zTNIfxJ~q8&>3e?`&B?AuJYO$Q+BDyb^VvtL;WU1dKGIGi6O@1Ui!RPA+dr zOA8Dm6MiqRd0J=6#Ni-Z?ZLZ`VeK6yQzF>8oKB7i5~rwH5x0eh?wi4M7YWXGhRGYwlYGvWs{!5;!UAnGEO!M#8xV(o~P9dNjwtap&&k5sB z&+SRiw-3?aJ)$JF8k~74@nS*{+{)}e!>J!rJ4NpGT%pQ^InMntF^9O_~(72P#KDB8B<6 zK+1Rm`#72fsb_3~uJGn(W9;{WCH1zE8R(so>K=sPeDZqRN7_L{Pzfk!uppUJ3md@> z+cEYHR~~51cz1CpYS28v0%u~rSy&W1VDjaC{CY>y_U67pDVrho4Mo>g1|WPcXI(by zWVeIlZS*>knz85T@iK0?N67BXw-_tsLihvuGors*=^M0+N@E>QREIwsBj2Ir5+DV%9a*$(PQLVjAcbAp#>n)nwhJfWQ*VBcJ zwVl(~#XjlT1uTezfr|kNXsUFbfLp^Z2~XeM z(oWbRDwkV7<8FxDS;XD-aD4t{=k!HMt2Q97s}>s-YMm(tQUYO;@Y%LMB#%qI#y%`c zoxP??^mdee+xxO}^3oKh|I*=VG0Z#C)5mwEZ<3SWr|!CNGUC^m7hF~OPDdTaPhHo0 zUpAo5WT)h>qOZTTZ3~uuK*?04O$P9+QxMoO?*@67icSZ;?mHiLPTk%arN>eaq`JG- z%(-?S6(Jl6N@Sb?c`0FbwvGu?Jjigio?5oigNI)8v0Tc3 z2XeU$SA5LQq?%Qk>F|R-#mbYif}(r5><8X<=gRuAxw+pZ-4qYvl}yi_Gq2CkKA%-P zGb>7A*&kpATOBEFkQk@{B&XFxC!Njh;9m;J(zSX{U?-iQf7vO0I(s-<%^lR8i@w%kb_8zD)O-A|oe}apLs0*1>e+ z(HoK;7{pBGpA*-yYk&Jk7WCy~<(%`J{|;nT&8&fiYh8Q8i1+&2A1B=+hXIU0MAoDm zo-TRRTB12b=gzdNbFY8?ohZLwJ32;7W>lwfDT}_-7@*x0d`e>#JEZ+zMve+^D3q_urOQ`US( z!%gMMxctDl;oj;}wWPr7pa4K{gTf8|R_jr@*QcU=dnxd|)3USNH{v|0!_>Cuf5 z5P7F~TFTkV*=S$z@s`m~*ZbaO$arVdmLc4xS#P_ClvuLtCLTlC6ATp`O||2A^Q&T( zJA=Yb84d$p)$D9hx0|Y3++aJ~!1IX>7?;_4qISQGW7Xdk$%B!e&qb~nVo{ZJ$DRop zw{&hT9zKh4V^U1huVj6diHB!kRrbdXl&2d3?^obt zewNtne$S`0=(#q>qV3QkzPbP6o(8FYjI49l53;i*0G{*yH9M4ai-6`+*xOBTmy&Cl zn^JPXXC;xt`;(5eM(m@F<&(RP8YznuU#|NloE>-x?Vz@9=2qiC>;f|d zK~po*(N|7-9|wWVZLbb%OQZyJsXfRhvk6Ctdmjf$C;Pz0^`wZaKe;ci@n=zpu2aX_ zjx25vlh*BgwJL+r7ICc5@;8DQDDg4`6$D_K>}c-<~rHCb6@& z;JNsX_bP9#h1kHNfpqA}g80VxSngnFDZ&m}!s_>J3`tniSQ^Zw%ZRSRiS}=e3MXg7 zTWls$_NUXFa^eas-2%P&&6~L`b?Cg{hYY5r<7=Q=)rhpF5tc2;2U?(De4MG7{^{D41Dy{7&gDP4r(fsuP?YqTlz!Jjm3*Bz8&!{yAH_Ou=U5W%dFPG z{;|6qzcSIJ@mJ&{@@(tXvIbAfgQ9|a4brSyuIfO)>Nlr?my0P(`4_vy8{TN}U)!UG zrPmjPU6(JewAOtz7!cF46-D2mMN~4UDby-3pT_!RMXk_5@RT8w=61Akl+69!S6s6i zwY`Di%bLT)_f~n-3m8f-m>L?^7lgL!e#`FKftvNS<%Vds7*3kYrVQx%vKqG$VF(m8 zOf6-5`xkQ7Yi(SBY*Zu91{0#Ad6>6IzhV{#=Hb~L=iyLPKi91X5O*MsFV@49^oC`> zROf6K$!u6QeVS;3m&;P@jyR5QdP7*&cCKbGyAwnmQs(i9` z@`!t+sWql?P(pk1NV?&BO;u9HD@#}B-a9l=q=;;JO_*o4-(IxkC0}W>kqIgGo)h@O zJh((-UeQ-FNkNj!&g3=ApNa5a``)N*q*iM!}-xtv}shzCg;iNg{rHzQQ*PS4yf8j zh$;}gtk&}Rr#dfioDEsdcDK!@XInN?Da_74Rdk|&M0Eb8#gaT~wSm73d^Q`w5O@;(6&?Ggq(nD>g z?KS(Qg+?y619Z&4I9<4P+Va&uQ8xDF)yqcJj%ioD8mp^{cY(l(Y0J?^D06Y&HTw1# z_=D&p4I>NLXJ3UqgbixyPZ`S@(F9sG^C9lcoXzwONx4vG ze#e*CWiIHNJs~k_iJ8_Qd98B@KE;bK446x&y*&0&G7Sx7^J@~b;g_k^MH1##z^C%) z-jpl$Bt>e4omp@SJP7(m)k3$pOEF}ReZ9WfCJ#wo-cm9Ei*sAg{F3kR&ovXH!P?Hp zrLjlUn7ihg0~>sD@JZRSvsmDy`t=F>R8CaOm$#J9%%)?Fee+wUNZ=v+q+z23uA>iB zBnVXq5p22VqTF4U$Ye19WGf-TELbPvNm*3^X-4;!be-mo)%KQ22%gd>O1xrQR2PN4 zCLXMN&o$_khk@5BALl&PljnS(r>_%F(5avx7a!#W&FQez! zwfdG(K%K!sK&cLvsim%GTyHlmz|J7g{EA{7iImj#?>7>>!^Ybml6&@$V%?yjYb_#JP$n;IG zG=Tt1mS?rI(kpz|2QfYS6{X4;$;hmCO7-JOdd#JaZw~B4$EAdL*3?f4ddstNV{D+C zDbL!bNL!7{$TwJPdA5w7Ki~A!{OFd!4-`t!=%de;Ty)t7{rmAmJ?0ci9tmH^DY*st zUvl+;*}^5$ck=#*+DzsB1zuU>JU)uvEzj1a^y%oe=6-qjOU92#j7)l`Q-2IukGUlz z8;RhSTM}m7Xt_IX1&)N{!220E+N#D@tE6Aq9y34Lnp!1NxfWyZ*#~OH?_G&0{s@{L z^U0Qvk@#)-1icNyH!Hz346As&+O>_V+43n-hgD|FlkrhT4(vZzEaFsQUi9%&_N3u| zR9Ehe-k6d(v)%ExpVHF!b2TCY)eNK8jw_ZKn%A9i@`!1SUD^^LUOn9YPE0Or7FbSD zJM`PYQPHe zV=vdComL-(IWOF3(5x3)X}di89Z>a`EE^n9wGHF`7^)ugDzkYPsLBnqA2v1RCfLKi zpAR~l8rzI6&aF}5^3~3!h{rHY-Lg%$;M|=#>iINVQ8(&wzxlKmJRFG9RWT65`(4glVjrV*dOy`I@(RKd_)ZtLyJ8m|r_lZqb^5rY0amfDhI_Axp#5 z6~WY<6k9R>ln2#Dpq%k)2;Qgy$|zKo*-`%Wp5=*V+@C5LJZ_X$bR62d58>xrleqp& z_aL{H_vM$P9ZQOvu7!o5#uX#@3FvX3hUaJ9npOz|L^QFb0BchU3h-CLp<1rb* z^Uq~&%O}mMz6H{tOtyNP?V$N74GX=`KYM86VglFG*G^`-P(9XSI@PWce4{u)KXTi9 zX5lBF`K~G_G(V@qhTqSRKOGBMIWUt^aH?=we~k)W7W&Kslub)I-T3$jo)eX}jMI3# zzd!F?w3FzGTY08j79^M3XvvnSy#oovzez-s@;d-nX`K> z9c!JC&&e7>TAdlY@M$}Ay^-+a>{_jvJC(r>ILUAyhqzd;^78Ij0M{*^aRTd3S^_kT zo03}_zgt+J3)C#_n!@^Ry0!dqms|U+&mV18f1%H{!}dokKXECxAuYeAU7Y(iUxj{0oS1!Zrs1u&da&y{ep?UjpAQ zuX({PF2Q(aGltOD*3CNOx$~U$3N1s8>KJ4oN(rF%S$uOyFsiS)A^WzEXsL(S6c>=?Al|~N zRi~~qW>|2dXiHw@TrJ*#?Q2*CHA4$&a~P9G4K~A>&!GRCeei5HN`os@ud~Oio`qdl zQfjC*iwo!J%mP-flcH2~t~*;&GSZP=V{PSW#;%VsJx$zx(U+UpaEbul2+>rOp62OC zG}4|mbFYJ*flL=xd$!rR>x9_Xc1{T6x?#%y&)d87TCXJ6f&b->%fjZHyi>ztPYh24 z4J_jpph1-iRtfDwqyKxaB=^b3-oaeC$l!PEZprr?<`*mDk&%({fU=;oYiMj0nojHu zMe$GxB2mp3XbCwRhk(_>dH5no8*UwV1`XXEA!+-{NQp!3ELK6h`fVX^1-?SE2+MT^ z!3Drj?;2X#;#n2>*1H7`d6kF?fDs}8wgn-+2!D#8Et2n14|pKNm=FASR0yIW6@1;K zOYyW&y>(mw=*Xa46p<^BzPxCB5NZnXxIFLpkcACpLk(&;OOdmCW+IStib@2W&gkt2 zNe(I*vJk>8%{M1DlP~Y?HN!90Rn@J5C}Ew4iKmT_|bop4{Z=? zTrk+Dc{H#ht&zMs1Y6jKCJ|p@@O(1A#(rIGQY`pZ(D(wCD{3 zNO6w}x#Y;EjJJ!hN@%%&kU#Es2w@ztu?|6`EM@O_1P$$RQAv&P3f@f-vDjNLsrc9{ zXn4R$@u6>kc&0w)iw97+QK6g$XC^MXTWN$5dqJrdN=tBcLWlTZ?(DsB0EG<~6bO{z zvWY8baQTmpYdI+79b<4!2nYjJ$*0hBA0@_Uxr~eCeh{HhXOHy-)`S33$WlOX6lEcD zlnBu@;%=3!K|h=z4q;>t`daUO-%1#-aK#SthLYw&;1GidRj4b%bO=~hIfHt!5r2nN zqY#LaF`+R|>oKz{0v`SlxDH{U@D6)U8O$A`bItJ1vtIk zu1xLQ{!Ldjepm!kzk_{5%__PLL9J|b2-ZMA@NS8+qL9?M>FDTijxx0X0{NvL(OBRG z>T9!Wpln+a%B=tj!#+?TjGfRi;T6BmvEUcw_7Cll5yHdWCcK*MA;zR-)*jbDopCBe z!@>(~aK$lkaM4c{qXm?VFQEF4|^gSaa9t=AoTh=T;OLLGAnkT*lde~L9>5MXRVuk1lo_27S z??%R61uut#d`yM*UF4X`HE4gKz@tSNK8Ey}^AiS-E|~g*2Pr(jA`1-~5oJ(0rOZQ`!C?13v+e z@c8rZv)2U=+NsnHV9BXaMFSqe-GSXmw)lX9cRyUa@N|uGz_rAK3RmQ=<82eSlkISe zgOh$hK)L~h6*rS@|4OnAxOlVRbjcA=f}2EWWr9q^4+Q8?gaR#eD1i@Nst!P*>2G*E z3^ha*c7$Fu&I;K#$0H*>S79}x-(bksw~gAFQ-L<2?N@+geu*nrFjdI4gT90s z5%~^<0w(5=7c$nm)wpY*s}Yn0$ra^I3bmsUH(aq$`>}V9IfI5ac=%J`f<)sv@dCRb z5_R<{{0Ff2OAU5seAfd7kZBFV^%(ESxHg3}1H5+VrxLDt1W>`NZ}VmnW|-aVRD$P= zA*cAip!nou!~S>(BF?lrw@PqdHaOXCWDR^OdP0QsJ~Xlp6ZmkuI)-Pxebxg9N+r;y zC4|k9AR+fPMp6)pMC&+8sr%+q4&=l7CKxy?5jBH`A&+S1i^*FDzM#;8;VF&Y*I~bV ztU-z3V4s?BWCS3rfV8z4=?|v{4^`72UWRra@y<7ekcI4#{Xj9TFL(_xL;7ThZeg-s znK&-kIoxESULk`lq`s*4BpixNbBdS>dbxjWwJADPZhaoO_Wr=qm8XEnELdNnN%=J$ z$L*)BikbwUH$P4GFi6s+W>(!kZL!l#nPB0g2Z380qW^1ld?A^i<$%qIdwnc z_Ye}6j8>kN89iRA+!*Z?+XCG_lUFcccuGh#V4PlvdI0Pc_2n1(6 z{S2Mz#f7+?`D%1ex1HFmG5J3@37&%ZaWR2$= zhhk83sPyTl7O4BCHY7vWL6r=`J2Q&N;!mmO7CBc?8TL+O6|Kq5S+yS@$vA!3u5(u; zu*%#IlT{9&SQcl&DufeIHXDE5@$DbOP-T_9Ag;`gW8aNj?hv1N56 zi6x%|{UA7XW%dt3N${fxw3=UJyF_~40BX^nkR22M-jXE)yk?KWOO(WcjG#AwTI>yP z1(-#0&Hw|vNI&haA9W$fLrzW;`6<$9Y`=kAq@K0|iPQ(;QI?gZ1n;|wH|>z}@cs!Q zF#I91=g=G+d0@yD#yfoshK4ml1!nZ0kCI?S*U@DF&yYeKrZyw!=W2`^y5Fu z7hpV_gZ5glRSFGY5n4t|LKGjP#mos=$pSY+!xTxN#mj#fABG81Iyl-aiGjmmfil6s zD-3rDox8$wHKvNE$n_bs%w2In#L{14;dLO)ki>+jB7Mepw)EWxgfU@t`6~b!veN{} z`0g=4?A<=~qS;x5Y@y_j?9U~A$Yz0jQLSvjOClLw$2khRk-fUNHx0))JG9%H1u+tW5f->4h&5YbG0WT)2SluUU!hutBql`Xw!+#8 zTl($;3WX!pv#J1O>~s?#GTCovl5nuXLmux+{xBMboj~P~kbGbD%v6(jQ+|~=&ZW~4n*$_@?3tciJ6;Y%{+E0$8kHhyJr_#KPizYi*w1+*N$TolDRJq zkeL5eoL+`7CP?SUv9%Sp{M`qHutZ(E3P9FYHzBe&?dPs z7>}jW;h9y5Lz&o2#W*(@0=C=2h%zX_)LZD1ELIGL4awY>`;chctX#k9kj@Q;_1#0- zg}!&h!6*P(nvs}PL1caS6eJXH)@@+v1b)1A9a$A(tOm^+3s3SW9`%37Ln9FuTPtEU zVLotX4l&6UwL7vy`0LQ2RIARq!q!_MO))NyD$QSH>(Qzk#JA?(p~?OCIcD0lb6YQ9 zyKNYIrO{8A7xRTKnURXEw;`GPavu_H^HZ3{Dx`{KG`@StFybyr;%PY`bE^}R&Jmd( zJ_U)kQ7&wK{}GozGIm89DGFPC$+<^En_`ip)z$+BAHU~9_Jl%RKm8V}mWj{uif7u|G3DubeIfrF({64SH>Z;LzoJ(VZbz(x!KYfZ@ z6MGI!UgSYs=>T4IBNq&4N=5{F9^&W^TmdjUh#Y3=3UCVVf*1MA@U6_r`e0v}jJ035 zq*A!BH5iBY{`3h(VF0Gas0c*o&Z9`sRgW2p(*9xMRNl^B?|QH^2OT;yg*y6V+9u=c z?2}Gqz+)QK0M9hhUxcMY86mG$cy|r`h#PLJr+B*aO?Lj*f@;nk*v+6NlnGSrOtw*( z48PARbcI#UE7Wl1BI#a z#N{m+)nm-SMc;kc!}bqdvd}r2#nwvhBp^C>o<%ZflN^vLS)9GcWmrCYw`S+|>xk2Q z_b_ouu;Mm6(-eOZmV9?)Uly*#u}NmY@U}r8M&>&e2HhmB$)KBGK4j2`DX34g$7FIX zfvTRpCaX+_-)B{r3sgl_vdU7mgsO7(n)~q-t1v2~4yy3oQG8$6kNrtjH6JL4DD>;7 zx-#|aOG`!bL1(&hbfz$U(Uq)+fbPCXQqQRnNt3iDku<-2N+gl5d{ZP7rke4vL7Du% z&nZlWuY)Q%W$0M~Rk0nWf|{yzAJWFcPNg?EptbTT<``T zMFO)*q^z`eA3>r^)*Q9wzsQ>N36UI~sofQ8E}*-uP}9HyO@)mxNoz6^=9dpy^J!pS z6J=V$RI}zbD3jm!IfXG?iZwU%EP<+7bK}FO_%v$oawxRFYR$(d-{mk!iG|2Mta${Y zTl0sJw9jh`foHTsf+4Y7uSgA9|Y$rZ~jV7hG&X6gzRmfIw) z$sm|tK4cM46{9#4iB$u8ws{Hx z@~86KgQE@gt_6ll+nj*tw)t5k>%i^|B}?E2U1iDqXefNcJW+)u35d>;hmo|8VGGA4 zTEbpFENTzpZJg4PVkU6BG5=E4*zpXg~4sr2X1cwp13lU}qECldKJ<<96gId^~i zJ9f&K+aFaT(O=Q%1ox@!M~{TMMwi~!d_B}WKN+B%Fszycj!FkO0lDC9J&R;wuKWi} zVwgov+F72A7wy;3x@>*0Bm&V{@-UM28EE0y#-yyD!%Ka^#r(9NPoFsVdOG^7JirqW z(|T6UJqF~q;SJU2b?GV$Z=$Ek@TNb1$nXv?mYR3Mi9~+w+{@@UId^;ekr_{7SjF}y zl}Pm0&b=gfrW)KQzkO0!&}fV-{ZUI*qcI=*=hFhp>nN8*`(^xZX!;1nAI9!q{`8yX z$qpS0mlSf80Wsy`i<;!gG9dSPLVb}FC`qJhDv{A|LU*8_J@gbRkyw%Fuc$=&^U@;y z$kBcBhvts0K_$|5Hj$tH{3-HBR%=zdP0RIA?)qdXcN*!O?9y#YKyxhc8AMJbp6t?9yi#8TK zi6>3~WGGl0AmhW*iu(a#-b}K6JEEd})ZPc@!w62tMxzp?U%T$LLD82nC_|=ExJp={AR=TkuQH@r8WXlR zLCM-7-uU zEPXHyd&|1KNbzWW_gSXsVEB<2Lj|V_sVjXe z<%)a1&{D?SmYDeTLqI@y_Xt1(NRph-@HH6~8=#BY4DKS`EyJr`|lpd040@X znsr8ZP(5)V&v>pQVbORXpUGkyCU~&l72yv-lIjrJZ?Zhb}lk>N|LJSHcSFdRN&M3Qq=@EP0udF?N0m+cUHblmU&)9N25E33GTfXa6 z@eT_I8UInc@$amD>>+j@2Bt^Jrk?>St$RygW;h%7?qb{dsIbJO@DHA*yf+-U=gIqF zWmJ>icqN}v=1ZZk|j;Sm^zZ%2kz89XZ3&*6H85Ndv?z5-&Sg*!td{&u2cJ9 z)ekV@q1poH?om2nr|TiVc$Ai4xNZI*-{j=&b917uPCR5vdSv<^IU`{pS|715ZGSAR zdger&=s475Y@vIIkQ9UMtm)9i>|&Ls0dirtZW>@DI1$xI2KWqIX^LA;$7Xc5jWQq4 z6;(gLGv`Q}N_}RY1Mk`b~FS`NKBXOy1u%=nHKS z5e@p;W^>bi_T@8Ha*@WOnu^v0$^7ymNOUk)VfdF|_%B_5<}eHOnLJeZyn)DCVnku! zBM9B7S5e$HBA3kF-HhLK@9KIQoxGy?GfH$(8yGlp%?Fl<4Jk-{(&oX)&vbhnw; z(MhGbRYzJ_ewlrFvaLt}0Gar;nSx~;jl2c*ixryt57J9k}b2ydEv;8T1m3tyAT zw-G&ZEMw3;^P}=(*`(|SrY8<&KvLe>FLTNI&{nLwV%K- zXN|{c#ANB|Gmu7BN1L3+ol&vbp_a>XFga#7e$28DzrFWfhlhjq_qq~D=@vF6Obn;p z4#U#7ok8T}k$2&eDW`3+$#ZHT_PkBD15?J11#i)5#;3AwXeh z=4cYwXX4XszJTzq%}2H{7*zA482_5AiH+zPn~zr?lBOEHD6q_=>;|SsOe8v43Xm)* zY(ivx_>8N#&|7d}^Ltc-WxgUrHgHaTnCm`l{`Anp98%bcP8Bxa1gG2lW^}i0{z^xc z7R*Dn?!~9?b@+KS_YaQYaZzDX1W_`EhQ=VLRTQ_G!Do5p27E0WIPG4K_Sz8uq01@S zg8lqFdj4+h^GX9{7Cim@Z3lSw_}%E>QpUX|!)^k4=JdswG?GJ{pS~7h*AYE&_Tt!K zMXm)PLjv0X86Q4!_5u*=ZyjYWgj2JL0;a^&qPA!4{C^rj-;T+wXrM{V_!$_{EQGCK zaBf-yfN2gem7L)c_CdbM$-6<>@K8Z6yHQn2dSv>a(R2)KsNaPO@{?k;k)QtlA-x{7 zC$iIt5Diac=My0UWAD9Nt}j~Oko@OE5A1Qv)HyqZ@aKKa%Bj5To}rB;dmk_CQy)U~ zS?l2ojnD(A{$p6_v5cuS_f2qU5?@!F28b7|u>kU}VeS^@)NqJxM#2X5jJfX62)E9- z!rqyr-9cr_<84;0(i@toaE+i$U3~@=y{x7i_pbkO+PM}a3EvK<^;`TLQY%>`)s%NbGfUe4dbvH@7gUXc1+q^=~fC9?Yxkgmxx6iol!^B*u(!OIH zHd-M51mN&LFEkE0Y)Q@ey=m(QTHjFGdK=UQyZ?GL6>%Nu#IwY#{X8vSnlG>ltMnlh zo)r}xFCgw=ab%3L`$}Tk8Mu;VE$`LM=x!g{bNfWsuk@4X( z2Q(jqmTZ1FSi3kjR=9v;*q)s5WJsr@G8u_Jtr0h9F(aeX11dw;_{6d|q;!=h%YjL^Wx1ZaPb5N!L z+{)5>=NoP6mtgbyhphZ6%$5!8 zNkA@G`8tx@rhRK4D!W4o6G--b)uU`^J@oUfsWkUPYtR}JeJ?B=x~KG~M3*_R+7UVziN;$=*ZcvxoOWdQhhEqY9=p z)ciD*HQ?J{B>nv}zSl-Crls$NIQ5VJB&CE0Q;1@!pKslRsmK{-dQ#r76OaqOR~^Y+ z-)j@*hGAQgDVN7Qk9Mf02A>&gEP{loe32)w)Uda#!XlcqGkBuSmH^(g*dUGhHw+#( z4QGH%w%;|}XpqRB%%Y7uA?!M$CyX`#DW$5Gf;9oMK77QCqtO`iev%pAb*gyb+TU8V z;OWlipIQ@tYu?dPgk;T6@RVk~9@c9+h2eC{htFjCd?(@&31=rUPJt#EB^fN|M=S=}JKA-}KU6#-E1#s*MsVXu(i&1;X)3|Q5nkIwMg?(DzRl`)A- z2lgLCj~n{TXPds-BJ)~j*oPoj)(7IA(^Q1BJrD2U>F1pp-3A~boFQnP!+P?>E?)b6>%o)UxvLsB7hf~B7{6+T5%s&j`d*zl)6=1b!Y z+z^o4R6t#FrcT6RLr)Qu#^8=U9cZWN6K)_UTGEYkEYULD*OLJ`&6l{5l-05}gd3iw zYQRgWfM8yO*S9+evZgQ70!`n)bvz&jdg(0$Dgn5n-U&iookX2RYVRc;)QLz^l*o2e zF z_{w2j(Po}`yIlV5dulBSzr9F=}<4qF9{F`-=1e;ZcRLWhG~tDCcdMSAL1 z!35)KAlfVBz@!2B%edM9{2YN0$vgySb{J4({bORbcMQSvm~StMJHe#dhBH)kRTNDF zEs2XZ?-W%Y8u`3i9ERZxiKAVht$!H~)he7~ic08U6gJjDo1%);oSTF*B(4?#dF6tK ziK#ES%P=2z^1>#(?|`TAtYH4}EK^+Vk0Jt3qp-1I0+B&GJr*q0ESv)KvW^dy(T=90zicf3_IapQ}nn{yti#^IDl>DqnYIv_D#x%-SVS;fr5cGAm;8J*syBa49k2wBuLL`VN&j1O) z75z^T>PjXmJ<`DhfyyE9OG2=JiEKyprZe$Q1xF9~X8=4Ed1ig4&LBi0>c@K`+f`*} zmf;b}2Jg2r3~o1=dx#H;6Y!H0AfI-JckxrXXSgKih(yQ;R-$1?;Rvk0Fh z77e-`VxEtN_)r4VdO~AkO;8u~+=NxC{AW~6Q+ebzK$e>B^5?K}o&O{!>bwcX?%XEIu<69Gor&&ONrZvn5axgz9Hw)JS|Ko>M zIC29V5C2K(FkxZ3U=&PLrBV1ic}1fj^_8$uHQ59ciK9)R%_MT0VBxr65^PMKCZWAW z*O?wgYN{5&MB-`@XjiVtpKt+$HNAXopZ8#%cY4n>O4)k}fU5NYeu7Zy`sax&>iQ_9 z?Bx)+ikD9R1p!_C1}X4hQ=r#oyAtCnC<3x7>GEmDQ>^kr3(xxbf7BE-!rX`()i9G?Nc+w2{{CM6riAz`OsZ|z#m+$GY8o~r+GnHUhT#l} zpIw+S_TsL@Xe{Bo z0p_tesqYj@?hSleqNMwgd`E?+Ll|>~xA<^H;S&%~EuWeb_fGiGs^yV4*H zsQ&F;ZqJ2Iz5>{wJWWA+XWLU)k(}xsz=Yyz7U0!4YS0n8yq=&J93TG#y_q(vjVDYA zKvn$x>j=SB-Raz-1pm;mlWO$_lS3LY9!)Zc}ucA zRTd3-T2&U-C&U#qC;i%UeTZy6dTqz(c;O(oFsbSsw#Gu`sn|$B6wYxQ71!`HB!0TS zNNwjV92dNJlRL?Uc2Iw*+nkB2!48~p$JHWWuNrMJ$U&LyhKG%xpQF64NZDmodSQ`x zNhzD|yfXqX)qE{<>|Q(vPheay0ttw#=A#tv9!KibL})%6qahVPJz`;h8A^PX086#;#ZxX!-SoJ zaWrR3bKvfjN2(b(hZU93!MZKYA-!{8k)HZh#?&NN1Fs!mRHZfyP(T)tD76gv5~dj}?e z+8iAd$5TEJI>if@0TY#K?arjm)Bjn~X#FO$5;^C#?hJ~jsY5-S;xvRTs@xa4)#!(cN1IEkeK_Y*(n$vkfqUd#E+u--ZNxbmS1TdS>%jXD{099Z z0rf!(i3jpES7}~HB40HC1%OiLZ+ZjL?2a5juIHaLL?0mAb+_;bUIB$bK_XdI=VH&3 z#@yH7t$jpCpdrb8gR@@{?Ww5Xq;mNW4S9~FlTup42?ZMWX&^sm{p-~&@qI0ropr=; zKl6R}IBd%a4HnUdUY~p*60Hs6NV|SSkcFN8 zjvEI6-_PtS{ZjNUZxZ-9?g-=%vlKfuKBWTMgpLG8H%t-AXBte{h5Nd!&Fn}(?2Qds zIp>E(g7V>FoG?@rFl|mpg3_whk$g|B)@E>IM1PH)!X^@18Ua)hi@UB(-bmwiE}U#> zY>h2__q9QrwvoWdYMr2zY8{3W`Y3k$tc`HSB`EgRRuww~^N3=%kJu=oRK+|U*NJ>j z#crRV@je z70UzwyzO;qnPOQ@qh(4|KVzA?_I8-Tvcjv25gPd_lvT}yNb?tpHOE9`+sx$5laX?5bH3y;)~3i=;!EQ`XgY#`l@d8iP^x;GS*FMfN6UnNyY*S?QgWLkVmlsNd~KmOgQ9d#rpQ9S0z_2 zgvV{Jcty&`SI?VW6$ULaqtT$50G_dJ$V~*TO)ahhU+gqX*~&F$kGl9TeS0&EGla6e zGx0rT@7lX!oZ-7*`D}!bSUx-;-;~fs8)#zkw1HaB3`^H8SVI$4bw@P!4n8%rAcZxw zU^UuB6UsAoacD2b-L)#*rn9l_dz$}+kXa~q&)vWGI@U$%_8oO-uhKn*C|gDo;6s*i zXs_Kp1$eGje}O*8(KSj32D_5B>&I^v>D#XtAi#I+|FXv5uowoMR5lykZ^qi+&1TJb5`DwW=KxqHY~6fDc(m z zTAso>nz&l6qs5|!tYdqIZ_unTXe>XL_tKFI)-lX*%YDZut>e_51AGcmwvHyihpZ#2 zvlQcT!b8h%uLcxth)-C@Ny{QO0ai^xvW_MwN9#CsQci;nMYoP7tm>9%)^Xw)#f5b= zaWz^;6U#H!ancf(%$7tKtfSdU#r9ur->fmpN--WLMAYFTF0%ql<*viZXHcn)h!XN<3{TU3+rgIsL?u_Se~(t zsLqv4$DYL#Z^X-XHSic3(&WzLyUfXQU~ZeoSv07@shZGYZ~?8|euTYj3j2LYk-?EhO5JDUpy9EV_v_aXFeu%y4A3q%@JH7&h8S z6U;L(TmKc%98@SlGRho;kv`<4mMOZZlnTa$}Ioe3{qhPj#a_hqT z%!khXaI1E1h&)2B4LQf6jXY&itBEw3^o)&M+w;W&ti4G8$Fjj>UNDjS?i7tZyS*`% zt)sV{NVLOfbwJJlHY)w0WoPgnvW_dyG0XMM=AU&konEj{0Y2eAq7lAgPAqs0mhlXd zqg`C3(Tb*?iDvN(RCPZzqqs_w6-`hLCh-i&Lk3Zru^4XrS%<%45S!>T27Ks|_%*=g zDT64@UNiy92GN4|ltGl{F`Dq~jjtL+6W}8TQJUCj!mAp9bck7yJPo2Wuh9mgU8T?T zthyhfL6oLAhQ|~K;}PC-ewp!*COVn`RpVj8d&+pUXSqX~OnAESumL_|Jla#-&)`*+ zB^nPClBe-#&t*RaA{!4ARCPZ@;{orLTro3OKIGhF#^Zg3l7dzH*8D=pqdl!1lv(&x z(-HE3zAWQYrh})qQ|_tvFdN?^mZN=~)$acfT}Kbo@1ZkUKX z?Z*9Kl(OA0F?rez`~&U&MyRR!mORzp2t{4_iG1|ynk)gnZ#SfQl@>nPZdmA^vK!I} zOADQCu4`cqlY5Pur1`>Ids!XMX$xIdQKG+LBJ#8w?X`1fICQ&VN@2~6io9trmjk9y zqki9Rgwpt5W;fcan6H|3NM7z;G4-=TInJ@Z1CG-gTWp+avk!j&m?S_f&DZ3#}%e2txcEiT^ zh~1EeW?JZ~iV`ioiOAD#NHa4{9J0S*VybS3WH&G^Nr{Vw_JjBRjnKC-w;S(Vz$fl0 zz}MW;GuTA~pK3QubkEog%#?3VR6jwd+YKAv19k)Gn%jY%psOlMv>PTOKfBSr+6(p1 zaL9JU#8ll5(QdR?<^xk`sGQl2ch0UF-w2(+f096+F&6FB_$Q!bV-X=eWg*(@?@u6I zun-B^puKgvo1|OS-w;4Wg-Lhh_Y+*FAYdlJ&0c7C>aSo zD69#7#+HBU|JlcyJ?eTTaAyzSZUM8m+kjdA9{Bzkvi5PAV1pG#Zo!35&DimCsG5Uy zVav}O5TA+9A$#GsAtNDglX22+<7^>O4%_Exg0zn^tZkn&-pH;OS|DJAZ2UQ?|MY^@ z+&bb3SZPacPH!E%P8+USX+d+gvq|zorA#h)&$6g}04G?qZJ24^$Lis|bxhjjx-pOO zp~s8^9mR<<<#%V{n^=r(IJ|R57SG(@plS0P>0EZA!S11x(rEMis1Plr%C z{^Mhu*#;p1V@10gQRPoVpU+B89Ky2gu_WsuxfP22I{pl*{zW@)WOms~1#LuS=7K&Y zc4#luT8I*aBN(f^_wVjcw&2=7M#@0$5d(s8fxYUu1=gF_MoQg7sHWxwjIiUuV&!tUr~9?w+J$S^s$V6ClQiEkIGvh} z2p;akHUhVsMmIHVZ#X112;oG|{hdccApJbG8U}z#kLoSbg%8q8`eUcgqO{mbVff|; zB_kpqA3>}ex^^w?@tDylP1sKB{MUgbSHKg<+T2RK5G0-aBvY>BH@6Sp#riwjQU{W* z)UH63j121*eF2Ddq4vbIDIr1YJx9l6KJB<-QUZn6EltN{Uf3Kl4X@@fA(Y69b?BJP zu!k!qC2nX1bT43fSf7SY2^yNMY+yK+X@FjK1N#5IjzW0jni5Y>vyF%+pE@OaXvPP0 zMwy`kPf(z<-8(RY);cJ&o1-hJ=GY;u#K(K@(X;mgsPgIe=-KND3Ql`Fr|f3!BC7qa zT?P@}t;}6I$Gaa2V7fz4nv~(Ixrx=Cgkcj|kp| zvjA-@aF`OlN+OQXEvT__wNfVD`UKTud%pcn^fV%2GwfWqA-E9!mkGW`mSNUy|AO?1 zfBWlizyEXjL6VhWMs;}n>1KSO#b|NI6>edu@_0=##dJHY4yPW_tS?<*DEBUln8<|Q z*wd$(prqTQDaH80aJrwL-O3!)2PxUfk8<<+C-cvboezI*iJT}w?Wy*=6c4D!t$Og zY!@xKL~bCOuQ5T_3|iVifcpMtug7hFjHpBD$p5dK`;bZNBusoYS?^8+Q58~ZyI0=uA; z8eCY^B>EtwG^d5bZy-O!#|42j9o?`bhvb8l(gckk5WbK{2;ay>9!NvcPpxP`P`h>+ z&?5u`x{5(aX!xKcKbWf^!a-0RA^C~+#X#N9n_fZ&0|8O`2*sgXNYVj5GNO>B>80Bw zOc!py27f4Kew)E|8nh%|wFaU*%yv7hNfWwov=%OeGby)^Z|6TMwLwb)VK}*w6UK)s z2q7n-a`yoz3|b-x3w;7{_lSc-3#d0Xq>iTK;H*WRZNYrf|?lAMDDc0 z3hR9DjwWymcB%floj~nQ^}gkaMO7@j3l+F~${803+F_38f^nJ_q|M{t%P##OrG6A1 zZtRJO1t1$Pcs~oTvwl&<=Ooi0@G4!6qF)^imqEfIRmqt>p&x(n2|!kml^!E?S=wp% z7U&E?RhIV84ZYG70&y5}jC8^KJ-868*Ju3cWP|UCSHNaTr-Ut(_7MwK*yT@TpdlU- z7BSI)l_~}g;e1aFiB&PN%LsJpoLj)ewMSsHgC6xSY6sfbWYZ#Z$w~IMW@jJ&U{{Jz zI&W&2_V4ys!->54Ab}Ilw5XjwWjvt_P@mshoPbO;&>n$=y)Ee}d2)&)F(sN0AL@HN zQPe$`z@~Iso>6~dS+i583}4~zOR#znsPAW*Qy6Ktj8ELkD)C<|`?&hvhB0(33YQ#~ zFP;9lIG!IUy9AX^+lhXk?1pxr40LvUBd9Ym&m^k})!8~CEINK1*Qpy(i7|W%7e&O~zAYswd4e^F|ArQ(tKvKwb)*pfc`To)q$H*f71rD=#wN13lPd$+!El;pdR^e+akY{y- z7VZ}uF-vdTfS8|pa)ge?`#|z7>8(J%zjVa0zF65wfx|2uZUbU|>WKukW`d4bMaQi` z9@P=JB8sk?EiD^?SVxd2M^K@laOAYl5IaY#Vrx$v6N^d~I${=Ww{gV$)DsD^Jq3=0 z3dL+bnsOC2KlMaHOMwcW;8p&rw`G3niG+^o_&`#e2MSNjQg=rrXtbl~yIC^drYGj7 zo=AH3npg0|EVpk(QmWWHpYSKPXViFUQL=4d2_q#EtKz>AiS?-`Pev(rW_Jr{g@T-T zv@U=D;BmK%xZdZ=%pO=0S3-;$<6`qt@z6{S|Fr>(@v(cmgMM4uBWnjiR=E_M(w5=C__$CYFcziKUeJtVMVA&JuWP z_S^8pLYq{USj@g1jeIe`^~AEYNAkknnoU2Nv6TAa+~@@zy9&pzyFVa{Oyn5en&&${kr_0 zfBpM!zn9u#Hcn}jF!NhaEOcJ@Czjw+3A{*cT0E&9+v9gZmdti9jT|t)^~8eIc}1GS z`+>xP^noYUw82d&H>pWYf>H~qf% z)&Yruk`JCb@HA8XqX>?BjfYuD8&m6_Myk^Xo>bFb4W(SCWsZUWO z)#(Gzy$mK6C#-8sO zs5b5-AWw0JW<}*dQc_$m^CTswJ;W2_VhSpsptNx!k^c}Uh8N3f&p8o})$IB4qMoFr zwWoLzGP0|O2Lsi{odo15?(F4vwL5SQ#F~PjYmAx8_7tOV=(RJ-!q>%_1th=XpHnYfZ!87B$ZsVDW=_x&1*vov5$;=GYnP#TtJ;k(z z1#2n5Hm;eVp5ofd-nw&8X6~TQH8XMVDXy(79gzZT7LcZe+hbo0SvZ7T&f;yM*V zgI#Y}@mmKm?3=@g2R-4TE53KU=WAV&!;f^DW5~iY(Ra)TY*n>$jMY8QqrT?bQcuKU#zFI}~di+65^zlT)8EhGTR1?G$2l$CD76u$~e^TG174 zA%|6!K@(MVM?@K%o8wXeiJ1(1K?co4+^1v^^CjvQBRWr~5UV?$WYC25lngE`I#tM^ z$+-xtDuX7f_^HEjjCV$XL1yCf1sODxj-Qf2%qO}FvAW|)22EH`$>7E!H-!wEoQtrk zGH9ZTpWc^2%x6*DB{M<%iVS|Z7<+>CLo$e_@QRw55UV?$$)E-6AsIxHHBqfX2J5iu zGH9Wy?ud34PZ+c#7zrz*{elRZ+2l`&VBdWI4@a?uu)5z#0!>s;N#MY4{G|kb`0+*J zd{qEVP}L0)1rU=01p!QH{1?Q|Ord{D>@eNn60YjrCSfzNJSA*2LADUK#G{C%Dq<#- z_^HD=ODmTPXFSy@ToAETF7T9G&C&%vfvIk2lB)#ZDPf|$_6lJ#091u3(O(5D8mWcV zixv`;sxPic(0<|v1O1c)t7fvIk2CP5LvQxdeY%XJ|^27tN*Mf$6NMG4xP^B#g1 zl8R6+NKh*6cu0cK##Zs_6PW6TCJ9Oa9+Du4gyO#&0ICv{=&u6SBxuImOTnQ?r8O5M zC>5+cB|)_DWMNPfnCgZm2}%H-lAvC?*rr;VE8K_!x}V|(CLsx;mB6%eBLaAe8$OkWD$eqSWFH_barw-x#YgarN=`6_3{xFUf_&+~W){CVM zC+tOdRsZ_f70t$S%M*7FAujsjWnBO$m~flOI~czQeuYxX@a=v5SYGUuF0h2#%4gDb zqkdbTdU6HHIwUZYkc7Rf1d8fxIsMob4Gdqa#sq@S!+;!&^{p$Gk@+5pGl24uV1>u= zfDhRvhs;+G5%XJDEHg_PDY5Lw!;c+%ZP{>)I$y#*Sl_y0p|7I}OQ5#$&Rz#|`mrmT zmHAX9nvhYN_w3p$v|Ge1pfNx8L=(n>w(39V*#IVQQ(EUo@qsJV9lK~J9)Jk5kfVhK zXWzPFq3I37N4$yc^HEUGIOs#Y*8@S1dG=Twn=DMCKn#CdvHP70br* z7YZz?7QB%e=>t!yH(JkMP;C|TH_~r?>WZXeaqt33h=b>MALSBge(Q>bhM-C;*G~tl zM&1?4$dZK%B;m4Bp{U z*7hjePEa_PvtGPeKhE&$^DE%#$F6AjjO{qBFA((k#LFS1FC6JcfmC}GF3|Y-l+Ec* zU%1lUOYt_dWkHK70J8b5E0#fuw^@xT8lhO9x+0m{<89bkv+TAJiutW87MkH-oEv6& zbt4w@TURWL6m3hL!5RUi4_v9FrCXSr z8>skvfkQ}NxYDgn;SEln6!uRa zcv6i~R!X*7aKfd$uk?W{)$rx&XL3w4g@kN-P0nZpOv4ca_^AY@Ar|%csH;YHHJ{-+!;bwzKyJF zLqrt>$x2^S85hF6UbpYs;oPM=*qd7#RDR&-F#c=b1JT|keOBJ3yeLvaA2xTo&tMJC>NI75~Vv#AinGBNA$Iaus5gTYcovVi3(hS>0S%V^~UUf__KVfh%dXa;W1EDPZU zW|;_G`L?l}WJDFTK2`6k?ApKHW7zwZ?yKct_`P)_5}o2rYA=%DsJtoRcya`Z41$kg zrWLBZ!Pb{)n(tK0r&I||UhP(Tz;nMJ_ySMLpkB z+*NL!A#~;2+#C-DIc5^&1;&|)rH?UgQ9`38#0#7=A-ZyIVZDiRd9<=GFEB18p+3ef z9FUD?76j6Qb%9w4mMe!=DFB+%G*!lgLm{QJKE@eZ#uo)H5R~Ak3@PEbas;Dg8igwm zVdiOGVUC%;`V^ngF1j^_aSHMZ%S@1-+?!A#EpQK!qdZ0TNCUmXJu^G@G45dk(p`{O zxMzZNMeZ@>R@L32CzwC7)RtFSWdkD(HfF@#C=ePd}b##0)LXCaknOYp{98*wR3p8IEYfW!}x7;@8IWzYAO`Qq%?} zg}NR?z%!~M0x-skLUJhhFvT4oLNdK*54t2{yNDIf7M}%0l_S)QcRz-Thaz+SSkFyO z{4pPxo&weJi$Mf+9Qgr5*|hGALE-Py!{1{FXoH?4Y=I*4Rh=_t|MbI9?-f-~;p%D2 zm4pkhtQ-iAD(r{V zsfbNba0sCwF}_qEtt=lyMN5kls>5c5@#cb!+s#7w`==00yi_z=>0PCZ1NEcT-I=)# zA6l7fkAa%$OJxKV*b-zW?|$;p!}$zW_|z;rc?uV#4Rp8P9ISFLu0#QrS;Y1jES}L2 z*#+9H3QLX(ABMcC{Pkp4#HTZGeR+L5xSxSVDtOIAsA>VIOFjeCNj z?q?3BuI=Yg&h*_A2p!@Ofdny#L+*eAK#j;z9SNt za^h~~Na~lbDv(rz<4JwT5-M}*>-XV0^$)AT)-!KD2U3q#RDqcB3QvvgoW@r#e3@m~kIMY_*t3frUJ#*0GpLrJh(iRyY;0Ks4&F-RDT~srlaR z38ZJOmm-iLe=1x@BBa z(%T_$%P_K|Zkc{K5%v>RNlT1m z;(s~l=>|Mb#h>?6_LM>169F?Q!*=xZur{IZiZ5TY3<}dQ$oXA>LMG;hhmV~ppGd;a zS_CC5ukdli{yO@_ec=l03?(o*H*)W9UH40Rlq$!v!w!z=`sPqjmYs%W7zzd!BKBHe zODZUMz4zo(P{TT7zaiY0euCC%N;J_|kElZU2XibIk1TpJ9;J;i!62A;fqs_a5}G+h zW?+HKvuD(?1`GqOvl5F692TPUva* zCi_S5Klk^QWAh_*?$}!%LNHM%I%LnxJr29IN1nod1f+9n>=xX?*9m`u6K*UO_3Jx$ zuXqLxsyV%ITy7&=mIWoGgDfL6ok-RU0rS;5bj3R0O~H^yNeL1B4!7O|-hN~x2qpAI zhtRW>t-dSSur33de&YYE^IJ*Z?!~L0LF$UwQ`nat%qma>*W|;$7`t)o5sP^BA*iHV zc{msB^oo}8^-sfupk6p!)<8E%T&GB2_-#L;1~UE}#g*J#MU(rXG9Xcq~5T13x7U~IRbx|dNJ(){tK)4J$83N65n)v|gl z;@<3TA+A5zeT6vqqU?~fh>tSp0YiC(M^4m+T%wj z6`sjO#lh~#q`vuojnr{sMNQVO{z&Sy?1q}!${?Qew%dPACJ_p`c;d9moaXZnNE(}?D>-PTVBi{YDbg9#2bAj(BXt_l) z{EnRD;Idu<~NlNO%}GCWF`*ijhK_H@A5FPQa!rM zNNmYT4q8;P#@*N>e3}G9R=N!d9Lo7-*a_U~r<`Oa7~wjfk*o{Gg#L~94iH?ti!+ar z+|9+AC&vxojI;C-CK!kw6=xnfrV%|U&OF%}-)6+*?(H%L8O%DvEXTG{6DRUChVdYDWvXv19v?EB*UW1`U`qc^k6eNb5CwuBiCy%ZC% z_8G4k%0BP!hj&B+8NYWl5Lcu9DJhXqUhThq`_I3h^liqXcT_N3=fbmVqB&^PnVS** z`kN=3T#TC(I{B0fkYLGXgjfww%9l+HG&bJys3AF!%!jE@J2L(x8YW-1v_jwWfg)Ak53{PhUQkJ z1)*KT@vRVSc-0!gNIkjZbAn*wa&bmwsr#BumDm!evlt=`FMYm!q*fZn7s6w#u8YL2pYt5w{#)HY!_8^u8!Nb!S z{=p@C+TCB6Ez}wgn5b*I7;zZ9FE_pghaqknj()xvdWkp;rPFa3damIZ(0=otTp89* z$6**)4aYcM4AK1XgFmu0$dz@nX*edH$P9k{-fe=vxDVEXJFPZae_!IIKqp z4aoeu7`=)bV!XZRK&K=YU}x#4-%SBhXL`$YH;3ae;!qjxs|P*7(lg(oi7b|DJ-= zC({NLcOOzms&0$=aK0o}3} z9!I_)ke9z5@9he{z6({F?++zrENG2E6r%ygQ7M{8sM4OwO0N*SZuB~b7ZUijxA)!R z*Dc!TVWTagq^rE2_NS1W#y0vvsi;27SXq z<@oL*78O$#@e|A~{>|{g#}jDiiKA^dDom9d<0$KP{NdU{-qYnEFs58 zaV38m!;Jk~R*v`yqj+!ZwadzVibw5Ic)Hzz_q!*q2+N22uNG7-Bgj!MgKz5Jy4fz@ zZ{>86@0lKkZQ6J+cqjjkrt z$F+cxoGjqyT|^gZRM--)&ytW#sN3`~6Y9HqxThToA=lFlhY^;gCCc|v&nZg_`Ws32 zwr?Y{M}w${Wc&S*U!zt>PG-tIlzpltU?`nv3sOz7Zt zT_dl^^jlW&=`{;Dp#}7XgYnx31O>-yNb@OkynN_d81&x5goHzSPadNZl5F;8WLuYz z&>~W&emESzKysTS!EK>N&BFy>^;<*&F?%BmWy7QEB3%w91YNExA_#3f&6BCV zeVU`qsg!Q;Hg|8yz}D^$V43&C6frqZ`?Hs>h#NYZ>Y^O)yPxsDqNdxrJVsmB?@>RQ zU<^8xatO*D4$|9ZE;8NwcnFit#f)pRi|z&D%RV-NmKguAwmY8W3AUtzNEw%s1j_Rp z=SkZgH%i6*TltKcsTU5zDA7lkf~bP9L2Qo`@nxQmF53v^Tu{bjJyhw4*5j&lOlbM3 zTaWA@JRZVg%Q16yY zKGAm@cbE%m8D+cCF-^O@r{w4=hzrjh6?`Y!F_V$V+;i%5GB;Er>7tMn@5t~E|8Dj8 z$kfg7Or(|j`mvE^PeAC57E$HdOt7SqjqmJGsMOj zuZale8r(VdJ~OIlPw8muj%qc1k0;Do(N*tTK*Dyn1@Dr%u+VDTjri9Ejr^t_;(a7> zw~P0+vt_|{Ur@+o>Wq`3YMi6dONWxS#b{Q4;V?{oQTlgV=nP_HK-5Uyhh@oK=hOM! zD9D+ez8i%`lj9rFm}cos!f;J`(PH&V1SU#v;~A33+^Y%j|NQxp?b{k=gy{AylZCby zpiCC-z5s%Y(7Ih3&XYMwR`yX~LvP&$rUS#2Jx_D(%rer=W;NJ6`2ou6{v4qRna{dH-PV5|7KGMsuiZ(4Em}i{%HZ zXq7KML2R=&*{6IDgj5)(S9Ob%zhoSl+FoOB@r6iC+G~~cwAc4ZM-sL!Cf{lqBz1o^ z18v6-jVGl;@uQ(Q20Y5*zG~xtszK?Pyi=8*jC?EkO_QKa8wKRZK zrLKf+Y#Fj{;jL_lQDbHA5f0Ht1(k*ea^IMplAIIk@YP7(6VK(S)Ax=Cr47COl~?k3 zntpV{P~#;ldV^kx@WgwuoU#%v{a`(4Uq-Q!W2Zs_K3x;y*g|pdL*;M8k-B zp9m0a;zv0t%?F8AB{5AC7ECg~?(YWg#mJCu-T9b6qLI95bA>*I#mXgZp*Z-;VbY;& zush7czToFZgRM(2 zf_Rkk4ybHL2Q~?ow%K^?yYN04J#Kl26TugEc+*A@eeSRv+l&NXi*2qwE`S&G@4dsp zM9Vk!?1Z^?W5Ioag!Ctavy zk#~01LR=P^Nqnt~$0x-}lHPm z{kh4>^|@5Pw;?M^$}F-7e(y0npIYYJ=Up_#b2Xtrw#(fEE>pNu8<8p8T^limK&nuv zVC`|VzLv%M6pCnvuhp|`Xh1J@_OS?#LUDcpO{d!JD>IswNsWE#6j$@gKjrvlD)~0{ z+T?1B^kgy&S^bobXfm!!#{kCN6z5C>PtT7`1LIv)G8N;f&7iLAY;YBfdZm-C4S#La zMQOxO+TiI5@o*bY9r-8>w?l)NFD+G)Sp=ukx@EW1xqW}P7j3MxMSN7k^s0LzA7IEe z2RWomI;kFLh~>NIWX9TMO?F|??jCr_LKqDh-ZnV15I1`;Z0IL16@pm;kep&mnLal; zxyMO6rCmnfOR1f*MRGi)lZ*aIXFR1Zh6B+#Udj`)$V|d;9%#*k!6>rUcDC0BHd`bo zQr2HN&^RXBE}9if@f{KvbD#_swE;m_c+-y3zbGP9vJT)aY>L*kGOb6 zO1Y^TnJ|lY^(`4+vNBj?{F>V zKCjw5stUouvNpt}vfaKLmzp3mL6ddXZYy*7o)qB)&*$rt}5G&?Y&ORo`%rzxfW-y$@5Jm-XF zJ9?E+ZQzteXttx3zE674i zcBDX-M)0hSp0dOv*|ijgKA|&6MYPcxp^G+f$|5wL6ISHrlj3+{q)?DX@TyIjvItJ1 zU>pXY1Se65NlO~RNJMf|HtPlDli=iA8ZL)KI-C&4=!xOde3G7o<2LD?Hg2jSCcDXf zp&}gA8GQ%KkgJP*Mw|EB=_#4@h*_1N+nu~3Grdidm0p`TWo>x6I5p^H67y?%8Tvll z)yvG);3s(IbKE|`(eV9tz$KFqE1XghmUt1@BxKSCQB@=aT6Uf%mYh(_HPJ{$%;l~- z8V{R#AH>p(1TQa`9E=n^e&qE2b9C0* zXH7WJbNsGT8ZBOvaKtUXEgYLRi^>v?WIhtZKesp?Fjmf?wA4-Vs=5(^$-)59sxoKg&H2rPy67jdI(YFohL3dR$+G}esKSd;7 z4ia-TsUEd?RCNhyiRowC9kb0ek|z|e+{`OXH^v4>FWKp9jvm^+du6uZSgv+k_>R@= ze~yFgeQ}UGrovEbL#iwZNv66f+?cHPRlB!nW2!8glif>IVV~NU$+A_RqlxvZ&8f0z z&d!$@4*#S%J5;VkY#^0j2hm%=U{a1thBLD;-hbu@QD;7=hW})tM!fiysD(Dm`L%U4W+W=BAz5IdmK-a z%X>U((Lfw;$$Hi^ojIPGzRRHQwQ_0=lH+VrU^ z#a1!@r{+b9FU9(Ut(djhQx%Fs_^>4ylbw85f-!;UMVmuaCpz^GI@#S|lw;c@Q6N@r z5S2w~<^jc2tWQcax97^6VA#`5n?O~e6d{a;czHaUt?UAAmqSK{+kw|&+TwwC)wChC z$S?kqg!5A@BArRb#hvZ7u~T)aXb5a2skjo@f*hl%x@WAV#h_(w@kN7%2J2qI7ARlC z*__Uei)V8;Y7?a_!H7O)%SjhS`RYm6P1+DCi{k8JcX~<6j<+k9q#(kxHZjVgG`r57 zKA~lDd-Dn!h+ecgQFWq|lY3&)TrNtuKzc=20zLiQ9leYyG#lmXqD4j@p}S{Y@+i`| z@JVy>DAMtwQHtK_eu*zlv8zP$-Eb@f8ZTJV@NXi}-_2RS0&bT#y3-~>S(L_`T_WN{ zBEpLrMj5M3yTXq4+W04n&UBxP9{DGo@oa0Ov-{I;|N4)=|MB1d{OAAp1oF@QK);Wc&8c$$}NbgB;J(>ro@pzye*+lwiV+fHx8U-2f z)+`tW-1mX#fB*Ym{`T*G{o}8H{~!PO+aJIEjsV8arT_dZ?6@e@BQ3iXWpJe76m>yb zFs|_gO_|6Rs_U`-tm1mKZ?PuRyo;JBG7~kdqEJsXeL)l%-i1wFkfz>fJf3MwC3QVk z8Y`|x4-!oVXIjb+GsCU(JX`}j&*-a+rrJ+0p6$s zEYipAs%EHB6hW>eB8xErfcaaZ8sim>y-8`ChyWV9HpvV6iecB5-6Ncz9nZZHF{6(L zF%F?2kU}CFl9Jo3y5c}@PwI+eQ&%AcHSS|X163N)Zo!!|b5jEy1@+R@-$q$+ZE8QG zthhCGiV;@qQJL?{8N5d^QzlAJk00o5Erg-2IM7I>x*{AMU!4hKXPh}RHMQnYq-SpG zouRC_G&QtPR$OWC32d{ppz~SXuk>X>^g)p^!!$-a2(ci$`>7;uR0Ty6H;k65TM3y& zdV5hxq{cS1Jym3J@vc z1)GYd7173E9HM{W5K>kg>CIpC^X7@aiHkI1o+k10H2aN~G>p^gg0zK#x*#pW5-kpL za)|ng3(igT6pAQfdJa3UUV|pxXdptO6Cz($J)Z^<~c1$SR?u;x;YDKQi*JfmU}_!G@-FuwVgy_Gc!Blfwhb?OEpko zPZRUzNA1AEVZg$Jnz3DGI-o*buxDPkW*G6X$dp>8kOn2x1<~%VuGFgFEEr5*Us1ha zEh~L8S1(wha}F_PqUBj%-hS;0b4qB`n7yL!4e=#3Lxu&}Wm;WuVvl(0f^=@Uydd+( z)CCuBrYwvpqDrql8cNqyT0F1d-!a3e(l}Dt7SF2{>1^cS*G>Z@)-z743!))^oiFNw zy|cvun~B8{P1rP2M@PhrNE>1EBCfa$&Tl#>262AVS+^I0?+nPaz z5Z#up+Ypx`IwVrrzvvZKr4k-0vzfgXh3xtcgG1}U!y&H-JDPg1i>$sRbqwSsks(EZ zFDh^}2VqN!hNDLd0d@kZOO6Y(?dl1H41K0OGJ7WKxQQn(3QO5#M|4+F5J>$4mB<;5 zX^1+i{GMq(g-j&cdew=PcQTAS@?LUej=G9_8QCk4ydt%}`cAIQ2+2#X)Ksdt5mqD4 zzicoNVj@e*L?X?=SteI^tA?Cz;Hq7tRM^{#1;S+BY&}yP*>AzXb8p-J zKB=AEVvmO~fRmYCdC7r3j0GE|L!CGZ<7=(wmWnLkE4VsXgR$o%ZJz>;`^NRcxPvp&n zS72uv=^L;r6M2UZ0%2k7b zCPw5)lvkvQR{DzUaZz89-I!$WbfpQN@{$lq0IS`?WVamC_Q>s1-OA1V#m~vuQ`yryx4dKs)78aXUy@!&;)&OdiDPcvHB_pqhYf0U-$t%*%j{1r$wlA-Ui6YLZ z-A^54rZQC&i+nI-hel>)wOOc;i)B7Yo`vsH=Z<)1oRKR+_${wU-79%TS}&#ApOtp> zlvku#Te3)U|6E;iLEQ`Utsq~DN3e8MfMhEB7YkDAOVS2Fs(LSIg3I<&^Z}O<{i5sY zEmJwsq91ulG>9Q4Ltb*BZ?*E0cvxlZQAHh%lnL-b%|S+WDf3%YS%+A%;8h2APEqo8 zM1@jaF!d#8rsVpPYX}`yBSSK9loUBHIlbK3Gj)tT!?uVl-!>L_5qr;dcyMFhs=g$> zK&eu+y=WbGJ7z-j@We>IJ_cqW!9IZjiz+q z82eMVZsDG#oD>_z>^UF1p{SFvM?E6Z1(Tf=!+?KNLcY@4M%9PeHa>Jxyx*gj3=6ge zT@Zj{uqRDGmzP9)O~!J~x9(qN{)MBQkg2cP;IP9CNIXYhFlISa z2BF4;m`qX4agC(8amdipkarV*mk~F!iuC17 zvl{(M-?(HN;cwJAqp!%09(hH2hm-|!qiz4yQvzi`%>7rXL}3WqN-^}00XVemOFYR? zC%}jlb$fs=66arD5e4;iDVI^xxmGfbIKS&OiW!k$HoZ5CMZrB9k25OuC7rYSL8Nn5 ze^`+@LZY8KAjV7lR57QvM|lkklZeyXuq38H6QLB{i(#ZarPQq)X`O(+BD>|uE7Hn? zkWHpso=~a8jGD}DWZi&@TIgHWZk~rFeMNR>lvm^#^Qzv=G!`gM2*tIDrWVLY z&g`5#9`1I`LsglB0R#A?Cgtji3yodLzTZL%i{vGdMNN#kyyQmf8Pp|51S<)5@?Bdj^OY(k7 z`ihJB}8FJh3MoQG%w$d8Z~hOWh&7) zmqaSX_ObnfrhCK^iJ{7+rzJu1iW~DPRd)BZ&PH7ky~D^p$}7_G@%oC)U6WVrnI_6B z(y`~F*Rmi?Nt8yF$AM1ekyo6V^vI|emN_odNT2&<8mSkg(iq|cb-zkpkye7Ms7HFk zkyoUp<$ETLbRc5%IXk`7N6-~dPVC&4*IZ}?os4~Rue9zr_eyIl>0R^ILmgSrLA^t4 zJi_1YZTSS@99|pE#?Tk-@nizUtKCIKe{DdgcIKqZOO7-tPG6F~KFLc?v>B4VByFTB zFNq=W%*JW%%h1nskeg1W_iYE4IC|TWsa$9TR9=!NYwAnVTtInAp8u&YNpl|bCFxd$B)Yz`Yl==K zbzDTOWACo=k~7Z+ z6%PuW;(-cR?FsK&-b>QlZ2XH#I19-i?D0`vktR*aE7A+3x*{5t5&f1|?3i7XSEQ{7 zdCruEA!(qcDxMH+mNSENU`x*{IJoplENhKMg9(@0~#@{084 zB(FHKd`)>p+E`y+(K*R*7&jWYl4+!FpS&WijSyEvN;1nHkyoVe2KtK59>9cN6y!Q9 z(>Sn9A$djTnGATrqd`xZMtWtCSEMKMTk&bhdSELgexn9D2D>!!RSeV&(Bq)jX373q7WydsVEsVkzPkgsnx^|a(irjbr1kXNLSE%J&q zR3WcO$6DwsdV2spee0HKq>*BI#nm|mF!jz=FT*tOsuy@#O2B7ALsp{LxaDap(l-`; zMHVZSS9C5X0c)r$CDTaL9`zMj1X66%g6v}&LlV;{2aGvqp;viHo?WFcN!`+JSARuy zP}Ig==~Oyb%xs1wtOc^=CDC(?+~?3MQ0vAzqA8IxbUY@~dJ<9G#}}TY33N>-v0~4H zUiylRi5{aFyx?aGQ#f#!-geS zmMfsSYgln(Mo3+;qh(X_ik)wWJhbs;)JYlx1+I{D(h&^q9EyG4`XI;j1*tD;nOytB42YJPronZ2c3%iNQ zs*R)~!W-58^hkCi+*X$yI@Wkg-AN=xlLQlaMcOc5UU6i;g}ma#m@O;fK)rmK$i-U` z@mxiMEHdoz<$WTKw8&fC$PtaX>xw9^IE0O=-DYL`0~sg0QH=$z$H3)FBwE4Mmy~yM zVMbD3ab@>Tc}03%QddM>C1JL#h!fluU)G>*j}R%t9+@KQuu+fU414xI5hvQCMBYex z+m`Lm{9?RO?GNvBqZ5f9&A!~m*j{XY%}A=enUSUKydoV0EYmnMX3L6*q!4FC#4ru# z!)B(z8X5M2%6ngKFEqBRa(n5$PsA{VvyNI;?FA1m^(9sN1A!zGsS}AZaUR>akL2*TLm)F$Gi!=`iRW!}JC_{umM=MZZl)3|xN zrklI_gMv(gS~foz^GDQ1-AGLNb7uDD?*8D=CU#s#?eG4ed!9Fu?(PqU5EAiG%@5-E z&Q=$54V?o5NEu{SSCpT91fi>m?D6JD#7FdgFw&4|wrYMb9nziI-q9ZvFuOC`JNnb( z8JaL#)fDuDKW{OWnjWEr;i;}?d7xLe)9`|+#CyAnAX)Q!Zv zLEivXm}%!M2t(spbcbvz$>+G(M#Y{aNoz*R`IJ+~OKKIFbi0Pcp5{ceh*eTBo;(`){`ie4a6qI=rN&P8R zelQ-y*`O^GDcErlerrA#VitM>h)}+)h^q}{Zaa`S5 z0*ok;1M<*__^9RwolMv>xoCc{qC2x`d`jNP&70Y1W=8G|DvjvN#Fz~;uatie9StYR zL?W8)>IMwm=xudTH0W$~hi>tuFs`dvB$OyA_BE6$O$T#p-#L+wYGmP%hAB=rwyiwI=^p5_7 z#0?^mvi%voqd#b2>l_e3Cvxu-F?9K^tG3GQ$vygmY&mvqQ0>n|qd&6!nYi)>aVxvz>qDO@n z7FNNc5;?xmiouoJXoKghh?r~ad`Cpk%lSkc@gNJ4t7(m@+Gv;VtcZBLa8^WgyJm_g z!*=ib96BmH%Q)})EZQFgO`Y$EV@Lb1%f|Zf6-Ey)$dZk-9&!u^8#ol4{XL>i+0NdiVVSYrIdy$vaqsp5aUpRT+n8L1bK3 z?a4b>gQNp*MV!2YH6tb@Iv+OE%2M29X4AGm>WW|t6Cc%B%(U%~ydr7ipPB?@XO>p_w|e zW3kYuD%Dmjw2h)pq<0r-aE2+O%5C07T3*pRQ)gUh@JBX3yo=0xVi^_R`=k~ z>K^=oJB6*UJ%^~A@oyrH)UsCa`60)8LQ1A}yyO(L(@2?05~qBuJ)+GHmb6p9$5Cz8Rbop0ok0wvV!A545OUH9rH5Ch0_aXZ}pQ z=d&t5qj%=d6w;IG+?Hwd9!WNh-XqCyDW=aWV!7Ki(lRZ1BWaboyrTC=vdO*W^Tb;| z%bFd$zPgO7=4YbOB%Mg_o;nklLo%pT`I#o?=amVMb0DI2*vK?`mwip{EuXQCEXiH= zerE3x8q@4OLSve}Gl?d|BAvx&rkO;tX3w-pT{S;gkQ~}Nk=_%;rrA4_2)QLJ;;tHt z#XFN|TD&ufCPc@bWqhH*B-#8Rfx(+d?@XeJw|thx$2*f~T4*Mbtl7vBB*sEDKP!zU z=|p;$ec^4_`+0?TXjbKC_0A-kR_{zAI6vOcE35lJ)`@p$R#~%oXA;46_I7nQTJ$cX zrkO;tX5+mWRMb3t)%j8>t9*{WwTzr2G# zGo}s`B4yUlOd=h&ckl-e8tdaK!}gx{g)UUi&nt6Bd;X}#0yk}T4G}Hcj0a;Pkvfsy z!JoPF4*uXN&07&W8vKzJ5q<#SjjA@hp|ZRp4gScmG29kXTsyX9BE2(z&|uE{MC@ti zkBpkSKeB4~wCYQ>KRtDSWFmP(WpyVJJj5rS5;=Hh{$QpZ3(U!=Y0n>7wRuBjnMm*P z@$*14e{|U1!J2uX!5VcV5zcm&@sYlL$uv^;M>ZBC&3jfY+DP3Wok;Is&5VLz=R4x) z9juv08mv*}2M;Vn#%0w;5}t1o%#0iuLZl4aJ6JRG2F?0L(rNGdk~~jYOtqMKLuHxD znFd$%C23}jzNC9u6>J(4be&3?38ODb%b@fn-GdkI4U1>@hQ;CG*x9b}hQ+F-TxceY ze0DFi2wY#1RxRmE(llFnN!|`vUy^3U>Pylz4t+`Y3g&rr&pDk}nsX`xckhjh+1)H# zN!4)P8&_V@J4s^RXp+PtUP_i1?G`34$(vK6MVU6Z0XJ`UEz#HH#j+~&l~+5;OLp7~ zoI7nd*M4ITmQ3b=SN?h=OkNUKQ4;Qzmz;2ks#7V85h6G&sY6~9HIMA_s6yXD)1o?b zc}e7#6UVLV@NX&;TCkbkqKUj#Z_(Tk(qN(~ULdz^WT9k{KPcwLyivk(jY{Ofcg|9T za_$$CqM%=b5MjxU6(H>|u+o}i&!k9S6Zyg++{yrw+ehT6sYnz(pqYocj6J#@93$`r;( z6UppmoXU#b=#g$lps$0tjW)nF9|OCn3hZ<3ZClfDAPDI)H03q@kn(xMkL3PLqcA1poNF(PKGhDb>65u zInYx_UXkXq$*5^aU8NCIuE;)y<6Sb6=+aNrW|3E9r+24CF3}@_MoH#L! zUmEmKY5_88UdH|)tuSa_Xd-AZ0Me2x?S&>v(Y(@bAo_|d@FJew^V&1FMW%6JuCKl# z3$)3o>8K)^M%w&eUy(WIGHQ&|CW@%)%tCKY@`~(EFQcX{@m6(jR$6nm!|=#xR`vKFTzrx0>^cDC?`QD5IwNzA|c> zG9<4^Tm8wX(ZjsHk1~xLyDNz+BHqcoXAw14WY<`kMj8f@SET)TWYqMTO{Q^RaW8pA zG^ne~ql}u?xXU!s%YwWj&BK;a&&=DCX+%FHaVOe5N%`<`5V&n&LW>z?Kc%cyC4b$vzW`}KnQ zdk|5(vCA~h%%_l7zFtr=1)oTX<(Q`ejWX(&Ny$NuY%Ferj8?FYg;8v+bVHZAeJa!@Hv`Sdi9yHJ!SUg|m_>2L*1h~4F+=YSd z6O?C0<{0IUSeOT2kT&|;`{OEf_Pp3ntmc>zs$(n{H#3Y^CdZjhq;pSHz@|M>Wg^jj zhn%_UPA;@tnM~yBoV|jlSstZSac^`qr@SIf(N=d7tqRzUR3s7=$LwaW6X{%=HxDmb znX+0*{kGLeIG6XnnhpIsz$BIz@mx|3)KJ+e z8Mgp8ToUXO1i|pTdvd#<;|wCs?tWNvM>2xJ_z!!MZ}HBMP>9vvn#O8lpk=HSICz@I zNfnqHF_ZXe1u_FS!F{ka4$Poy#Nr(!X`e3MK@vpVL88AJyID12xg9Xj4$w4WE_qvp z#;I%R{|Xgf=8uQORjeKoUj`3}KA46~6bv3451Bm@#q3#Vm0Kz^vWMc*9uiArJmgD; znuo;65gPKs4q*?OQ5>~Gl(H>)88wxOg2C;Px-BzO$U@bK*h1+MDFUVuvG~>_k`b*D zabCYiq@;#MES{(I?#je!2}eU;e>Lt#)`;jjctpyHX+(5JJR;du8WG(aH}~j$8qTG% zG&UR$tr4+e#3NQ~+=dApO(PaDYeXD+(=_w9BU_g~l-n~!irmb=7R_5)HbXMHE(hZ|`1Nn#Av zBUXDge_=_kB{C@%kaB%-UQB;!B5yJyJ&~CIl3N*U%ut>jYNbL2nCz)n5_-v0@?Y<``3mQn%h~?TIk;>FH zVhS&7mBru|DQO90-4-Yd`_&U`Bt0TM4H^;cK95)(VaV39YR+W+MXfx}@}yTDnqp0n z90ORUn%7v1rV%merGt@~2VBkUR45gT54LCOgTzs!98|nw&?-*=WtkcX zq&0MNj>R{7;Ve=sJ_|d7JYsdsD`QBCb#59*fis%d#S5$6L^rEn?1he(<~6SO)`&PS z)p|5*Rll!mQHt}DL}n>-u?d+4$`m@3tO;VVKz3ekt!cz&QJFN2;j>HDz9K3z0vp6) zN3Q=cabbfMJ!2%`vppmS@nzhn|8RP!79gzuwTOw)!0UBenY?f(u_h81ELfW_W3k; z=5}@QMo-ZbC`s#YKiGYs5vzLzQdUDjDs7vlo(K-oGP|Q8sS&G7HzMHG!Ii9;ELM>` zMM<9{R+o6hY8BbBUt81Ii}Q1-hafjZ)A&;SP$ObbxkscLi_49v%s7kcKx`1{Agvb9 zxVd7J@5LG&O(U)!w#?2}$o%9h#;Ivc)6O@drm@j$XydS{mIE3!BCa3SU)`xRQX}Hx zDvwAp5REvhLul`)HUVB7d9J@2S0vvymJ|mTMBHBNOr-?JOM4)rQJh9cRZ@Hh-)#eZ zSxOszeyK>E^BY)QV#|N~NMgH~%9NzThue`3DN&|JR-fgpPL}ssoh%O`ous{t6UPi| zM6{@^R$Ey0teL$qwXHACLhHg)iFMEV;w&t$wN$=5Pg^oPh-8#&#G5L}rI^1zOrUzi z;v7q)hm3L?{>fNn%3oNK%)$~ftn6KUuZw&KE#()^w)c=&@MXpPddXPxh{bXD_rh1v zUL0PKtr0QKpqZUX9y$9j>rdas?5QV6%kDeL<8LbchoeuTA(PdI5BHF$&h1e)tcUT4 z^gw74YFG|q9jDCXB*#gAcXh@4+hRz6i@83@2dl}q*K5jv_86rot}m6L#XN2k+#LOU zKUi+7sZ5gJmz{?4&5QRL<&7_;(I6rS)fHC%mo8dl!bm zwwa_%%EcA+_QTU;22YL--z+rvtu3A53|s0dZRzog{|%7xEK`C(VM?oo#t+r6CbBwF zGJY5m(llbCL?g1Blb6$6#ysB?=9bqx!(1qQW1sJFVHt)NNnQr*Au%~`ADwY$Zy8)~ z%bpweUh5C%Ey!9`-e{kFh6ele z5eW6#4)nma&KNHyOsw^rLNj2Gy^aGFn>Meaec|rdh|8F$+4K#cXt8OA&q*I{xicsE zCK@q?Vc&{PpX9pmZM1T}&}7p(V-2KIs`MFW2LxSmCx}?qBVX{0U8I1w{%kJV(?p{7 zwdPeeDejl*%W|CdabwI*a|au#G-4JOeEW?0 zvoqByRD8Li_PJdd^hnW98KYg?qok?i{vT@;WI*bs;_EE+-FbR(Ax^9ew6CmKJ{W28 zh{fJhOd*N_>bH@bb?jV}l}(*=!R^)Q=r(Gd5t#&?p`V@iB8F=_BaMw@qFXbtytgK` z*u-!foL=RvFe}yfAeHuhztscN*ULi*EVl<6s`fIbh>czdO(p7ceHjPNn9-M!+jX=9 zHLV&ME z=PE|Iegz$dRlW~)rD;UeYMw|mF*M{J*I0a%alWg$GtdImA3iZ+ry*lpMUpGU^5WHj zmdY!$a*Np$M9K_mDsRkRYRHB*zlMC!_SKLnk*a17S9)kF3?it7|HgekxXO z$v#mXj-@h}hk|w*^1^6_hP-jUg@)w8ZW@wjhiOQjCZ!=?Y(>S^lG?f{n0B?_tKxF1UJ!knJMY-LcqEE(#C$c!17b4Mo z(L_F2rC?7oyWl`5J&_oJxc_v?8;-we!X&Y@py?b$9W3i-0*U4Ajzd9wF(l~XcY!QU zLv2K|Uz+{y-Y7My5z#kuL5L)GumDTbh*K{7L82a#kHkzchqT5u+@|mJ4kq9F?N0ou zs25seUU|jCfG-zC@+XM&^4P;nR)PdwL*AXvQbT5<3;0o* zcOKqv^(K?U^UmIH(8Bg88;&3JL}DMR%t+Rx_DhnBBi&F|Lx6gRGdg=OjDyzF2^5NLsU?1JaJ@NX(AFRmI?0IgovZQuv4;mXb zvJv~g*fMAj76I$e=B;1$fGBVc4TgiFSVSrGl(Xwwne4ctny({nd@s#galEM;XpBITeZ7(}MBMoBb54 zyVzf1&ef&4mfBi+axB9~r)f|&RGF!4WVUF?6e9t9EM#_-(!;1BxoOKoVta$G0_f4` zaF|kvQkp_%=@Ch5=%ak9t95r*FG>14^3)l%5kz`$r}a%n!*r32(Z(|&g(+D+8jdaX zL}D41CGx>GTuo$34#6DKMDjR3DV5{FXF?N+1t0c?@24zOd>L38lBb7kE74r=MA%4a zXvkD{fe6`HQ|xJ?(lUG^cQUxxon>Y}6yKeUc&6x;rV*2k@+3neWg|2qCagUorN>@r zP-nn1Ik%R`j!AXP?CgRM5nn1uBVtju{%YK0;}NN;Oe3Pj;t}c6XnDk16ip-6wrd*E zOq1>KSqFqwcA7{m6q0`OjBNoA;w7_Alb5Givpnmc=&i9Q`C3kwA}DU7X-x6?_XDfXF#|il5iN}w=mIo) zM6#xAetM>M06ts43<(Mlq*Xuh=>SqAX0PTqyYpw`(B<)>0#d8c#!KwBj%=Q7(z@2` zoVhpf$XY5h-HkMmhP*IGB9+?8*el2k-L@%hrQ8V4(o*^0ck83<7hN3>xyUNlkhwc> zlp1p6LVoKE4Y^H>V#tgQ2F)g^%m#%N&X!V{6$+S{*Hoqpyp}!DLq9SzG?nRpuV&Aa zSG<@#c_wOa&-%St)bvedcgigrE|SsshLpxjAh8<5Lw4f$^*Hk-i#RY7Y7aB9V|sh; zOPNIL`rRa$&Lj#V`pVJ*4kU8ig&l&3SrS><63F7z>PDm+u6a}JlZ8g~$()hC5y{Z7 zh>;)Alpc}HevSC25&J6~?GZ_*X~c8_f9rBtyOq^KSYg)e)#eW9$JH^VE;HjYzCT>f zR}Ul(c#v_=K;m!|4cX9-koLf~Dd8^OR;e`%Q(AlAYMAoAtPC{_uwC};Zn&RHKVsE$ zn%2d0nyeanaG146#Bf-IR)m`J*_=bSh}dMRKRXGcZ?&coaZ;Q|q-dB%Ebhe$uZw%J zf{49XvUn*Q_i(m>%!=(LeiQ?=yy?aL#Gw(rFij(_Dbk2IkJfWLS*-7?y(6Paqj5G_ ze>YCQ)QH79cq2c>UDO+q0#^Ffev1neGnELPcx~#xXj55kCtQ`EeECfJ-XtUqkeWyw zyx6c5wP?o=M8Y1PFjH&;fvxiZSlm4P+kR(@hz6iehNH&+IlE7}7anVb53xAg;- zNsYxPIpfZL6KT0Uiz_GBHOq~(S#G3d8c{W8&`8q~IdSfmmq_eN(ei^;gc=c>Jv?Hy z+nL!2khjt_Vxgl(#ORzyq|}W?T$o?-h?I}lh{enBvStJ4e`p%9W6>j$Kc^AV!q@SD z4Ay{32^}WSzTM)Ry#|&1>60w((u_owrxF*Y67^T(+)uw+nk<}HpU?PVIk z8C!F3cQj2e>o;V$bvc;>EB`Hb(lP^QsSz_o?py!JlGD@_Ra*grZ8U31CPWTTgBKv2 zGpbJ#6Nw&?H93;rfHvXl8x;-by4d!-*3b*F&qBj3(fS}UHs=xP(&(?o+N|3e0coVmcYVDJa)jz? z$WRcwI!z>2l6xYtOj{F)r3{`(Tn=rCe7UPkMyXm>Bp1tM znpvtZPC8G3NX?uV*HmieU@@>K5-V*rk*Iq$k>f{!5KClg2CLaUu>MjL`OwAjCy8TH zG?Cb|<%t|*4`?E>3rrI^F-T>JO!lu@CMPCFG?6%HQX`hkv~c zK!GYrWj4-{p1d@b32eh#YpF~W5j}fdsW|{N1MA{y~HL;phHt4LZiGh>cevp##g?nx_kq;I6+D$1d z4;ZKmO(c%kuu{G-HlkUBJw)!_q=xO6-ErSi?hbN8V%E_;vVS1SdvMIzkT`I{Q+cDt zaDl~5CT`o2X4S^zMj~gbZOr1tV<34`j6TgPu;0?|uH>dN^WncCWqHcR#7*^D+_TXJ zUbF4_iicv8iAf{RAnf39e#xdXdia|`T4^R}1c&J%F)*ahGDXkT!k(@)I7=A{41d~1 zy4_SOhgY3(?jCBrsXK# zPPg&^Gh5M$W%K&IG^bR{=JmrkoMll;imC-Ekkx{e-K%6E*-IJsm)B-&9&2nZZL@22UlvYhI4hLIeEqm>IVKm|l+Z z>E*gO4e4NOYZkTQfiKtZ%Dz~*m7YpmW2`S_!*}gKj*{v9zLg&HK~vky=EKc2nne$m zuxl1o4_%LJR!?3314)4?f0p>Jc{$4JPq>u_m}tFw+05vGa$TIwh@gu#i(X9gA3&B1 z(p%hJ5pho}63)`g(VIcq-+J@5*^w)oCP9wm0Kj~E3Zekh%X?f)`1br+C2_8S=DU{7 zfzcUHW$^@{%^w^A{=hIj43cTKbCN%`itMmm5bLDDxU0qy+eD>dR7^gQKB(EBORrf2bGxj&GNjpPsb zd)Zq#*E1{#xUOZhV`Ywu0@CWN6J(QXt8i@sQ=Ik!s?==y#X#PD0MBf z0*-t(&GidY-&))+tZdSdSprx62xVy-Su;C$qq6B)N>qL=Z_JJ8dWWpuqEGjCC`XD1Um)t*Y+s(ip7td;VZiF5(az21z46hW!go0%{Owufd>rbFj9 zUt}IYk|60DlpXZ-hgsin*Lrz2J&^QdczN$=z8_#>-r&>e4 zIL*ZK=SB5?fH^3p?e*r1^R7H*rtE+qZF|(2NCPYWxBi!yI0WCDatU_9x9hE*rESLi=!EC%i2SZ%SXMpGaQSbE=cb;sIsb*1fjPU7N+&jJ)T97){zI$t?<0Iq+ ziCcEPz-MtASjO7Be6kb`Fg1&kWUQ9WEVBaH^i+<$m*LAe)b9U|Y?psIK0=<%QU7Fc zXR&5bHUt3A{jD50IKtn`y>RSXko>L8?q4+CKpOd zPMcj(#dMn5*6w?R@3%76eqdHckv*dyjTo_1v8`ED-wxZk9oEWwzfiw>23=UH?#V=# z!1Fwv?_hCi#o2Fk3H))Ux~tfV?TI24E6#rN{Ih5RWg~U&;naeZ(R}db`l7ds%6vS} zTYYy^&(a={BQNhsSHm6h?@%kRBk65X9f{_89!oe)Et`q+foysPJs9%wiu1umY~E1l zm}T^rDCwqZ7A4LHEYe)>IE2%4C|R-cFGpKjyDr%nLCV+*{ENfN^bU?}gd{80V@7cT zi#%ppyFfY*Fi{(8%%aZQ z%!|k5O(_SM807Vs6D=i=xp(vy^Jx4q0ipGLN<{Y)_9aX9)!bF5pguh$a{U03E~Y=s z>n4+13)0BcvT{MXanOgSGlOk_>mHM*LVL`Pv$j0ui!oV`$zxbOX6|}9k2uDy=}fB= zm1G@YqMzw8FDxVSm^b zumARi_3#=qGb*TB!((1pTH!Idnb%`BjPiTTC!y4Dqt0V?%#?Y|c$?MtXk`FXwXRzO zdnWz2PaNyyF?q$B#mw$9OmTS3tQarm(Vsz;@E&FKgxtb=U44;7Zz~P11eYkhl*2LE zm_S~X8ehwT-ZN>^Z!Pjpxn4e5Qk>1|K@&))JMTZgr#26is0V##c4~Z|sRx~j3)GAL zddi*IYxQzxHkjqk?3E{^`eDjc6&%W>6=`fSy7wNF3ydsgtYz%H_n2J7VKWrF>VVGE zPHPD!8YG_18x1@e54(R{9^oNT*B?NVCwp+1xT4fEyA|qT0Val7^l_F?qs|O}tO4^>;)p!YbRKZ+8N_7=p3aW33w@laDg&3x zLtv@6Tl>SD+<_fG*+f>-zk%hr{>hj)=UE@;#4-LFa{VaDaR5o8>6xAy zD2S*WU}9^8W_kjt^kmrM+_71R`*=tU&>TRPTkj#V{K>d@+OZa->%yd-K29E>d;m#S zmxsi4mHq}L#tjeK0fR8m=jpsLaH@~<#)>}=iERuAkmag46Pc*K*E2oC?DK73HE*8j z4NGhEac1Zq$h(KcWb*+es^WZwGP*J{i%bvC^ar~b4luD^MIYyb^EEvrW^fN6Ni_Wp zdeAENn4O2jTaV!CI7>$#XSyxGhCP5JQ~Lmtyg+}0^5LN4Jkwts5`RD^CWiEJzE~lC z07<5{hx{8<@nBV~pNv$~kRa)so{VkvwH(;0r8&gKNgk3_u|CX+RD3_jr{sJ zZ(L*NA#vu-0c3d~<-T#6%mITYT_Jzd8%87bac0;+@r!XMgjB7M8mnTh-t(jbnV#t> z6ob?BOn-1`g=YGL0}MPQRz@B`l4u?<2-h5WOfCl2hTNS=IytYe&~9W`1tahDc7kkb z4t1;~@Q~$oVs}UF?y1B&u>&!}N`j{8tREko3=Vehdos)G#P0I(!TE5k6Z7}{#m+|0 z^nu#l3+G5X+P6N^Odr@db^u8ZfrrE}ia*SWGfKRbkYcHFYbH76>K9{{7jdaK(#P4#i@LJRoWkUu%KG}+1ZK)(ky+zT=_`NJ6Pu~NmJepcG>4w@ zqOJr{>Q(W>s#rf688{E`ufOTNylb^3gal-2rgvP^=^=57*}-ArzSVN9uOqW^if_X)<$`qSRkoR%rj{I@X5$w ztI&I#K=M`(=)_6_&GcDbC$@)aR*UBR8&q+oBLSKIRxVVH*)bIh4pDkm(`I zi@Fk@AkjQHOicUhI^d_F-qb1JC-<_N=??}tHPd+%>j5NL?;a8j?E}bi$1=TfWX*Uo z(a_cw?32xXq2p7DWEtng0F_s`y1!tmXa1 z3akT25>0=aquweWY!&NUIZ$u<_ji;BD0bw%T6xqrvOV0$<_|N*Cg`{WOjN~Q-gyO) zzLpaw9D2y|0L7CcBoIx{p!GMX;)SaCfX?y?tPD6L(?c_T;e2KN<^5Mazc!F$6(5k9 z>`1XW(|=gGYB`iT`s$cRAj=)gtjMMez5jCTp3the$MLUzGBSXJOeFp3^^I(u8`=C7 zy0O02e>t`~9FU3iwO)|gRW9%Kjcj{-ZS@1(8y0nGrtifO)vCB*eXSRyr@W}EKjlST zfh@PW`h!JXn(3K^L`=6XTklw3>u-9Nm_t3e{`C5;v(8;-Ufg?mtHbU(qxV-c{Y6#m zKm9GQz{+aMYU@3a<)Rs*m~N#F^7WThv1a;6i%a#Bkw6N3yT0iIE3ghAsnx+lV%M3! zL0Mcx(c&RXhWgCxKw!ESq&X;MsgE-yL;1~DioioosvhwV+qy^>Ycf~%;e3C&7o?O7 zmEZI=$@cJ{KFPE6khq^tGyVN#&E+?TESYcOJ#;JWlaVcYDDNI~RYy{?eS#t>`ZN>o zDL>6C(?^P#zQ?$JL+YEJ(r+?nJmy|c_D!ee(4DQB)sX2m{DwUE@`tXF|MCYt%Y23^ z15Rd@K3!L&yzN&VoXMi;@+*`O5;5IcGZ}4BZOsIdtQr3bwd|j$miMf*tiG0s_W+st z3Z-PI+M0PE+&k*Y#HFiVAw3J_UBBu5rYA#xdZr9jGrgze|6ANWm5K6wLwW}FK@Nex z=_&orw|)6Sp3XNFhu@g`II|8I$UJ~77tMr_Kr{~+6mRwWFg=6DMe=@t+3Cs992yCl zet-G_B#Gw1moIuUJeiAvGa53n;{2xeqR&Rwj5d%aTE)6pIeWj$9fFBgv1br!cRf|> zUAUTFlbOCAlB4KA=VPR9hA_3|u}1k7ihTrR`qRu5_3vBhA=!4f3`#*LK5UjjX{@DB z*YZAov)UmTzjEy!ND@tLCZue&+L{>`8ru4;Oe~+6et@~i0k(H2neS>}HIO8lp6PeF zp*`+;Rh;PoDDPT(WTIHHZ8$Qj3oLCdN3oCcn^L1|v^3&;V|p^Ps_7fj%VtAW>~H#W zRfqG(lTlsYpRP|cQ7I73gD+35M>U!6X6mPGTI+qJDuV<`-}HW$%X{kXfK1Kw-bge( z)3b83oXkOCa!=;_L+f1&(u?UU&7n8l&)@QX07;^GaGHZ+GoH*@9*az$6vbxzlMx5F zTHZ&ldNI>Sy(%88inZDttKMbHj(0dsFYg(QQ_b{=#R>Wf%}oFLmZO6&FE36Qi;EMq zDqcx2R)6}!^p)n&Dz6h8X%+&})J#tlmYxjzy?cqPYyiP0= z3CgYad0{1i{_^W4Yev7nnebmP?-!=8{HK@KiOmaDu|LflD+%V0O% zJG_?q)7y{a{Q$CD6{lG!WPJM6){vX6zLH=z%r$v=f3T83bLc5A>PmXCTr?9xq8p^& z-{)^o#Sf}tZ_aeAB+yLnH+icEkmOh%e0irz0#9bDT&lH4ug^8jw>;N0vo^l^#YhMV zuBB$s`!}fKmsN32M&;AzyXez(&F&l+;2ioqV|)PDJtlX}Xv`$kNhKX%q7~~gFYH3{ zm|XwuF$;4 zGesZYs?(E+Tt6VQI+v3#$Gd(&W_3(5WO7VWYU6}cE~;Ag@_uLH{kI@_%vkXtoE|eX z8H;sNOE-PBEt?W2EP(glKG28pm=o(MJm$i7F^!pN|J0*!fQi1A$K;^7$4nJX^*y>8 zR&#nfAMBy=m>o+$JZ3sht94zf+vsukbk1zzDAvi>#Q46aGb>$+eZuSy#KKceXEr^M zvE(stv}`*?$`lEhNFm5IF= zObaY;fSo2puY$ZPJt9 z!zGB$1I+48$sx0PQ}Tu+pGF3*0@>*av6T_QJn{ zJdk++NgC8c=3ah(_))6^5r~(GC~LF^f&#%twH+J_r?4^&I8DD(fkYZjrFa} zA_TZWwx{{oV`BzL% z@|d_C+(V-I;mLe)FO4QMomy~*w3U=R2R*{l#ZJu*Zfm^r?kfXvyn_Psp3LfPjrnri z*64Y@sx!LD=T5Q@y*^60G{~mMOn-d!8=OJz6rHs!3M8?}Lssv;OeCq?icOCiy}!?G zgI=@qkf*y#^|3NUh+GX#>EafF<|&m7+y$%2Ii+die)F(np_x%8piflaO zr1?MHc2BhAlaU43a=+85~e2{$th}Auh8?rdsx5J!d zC+#$fafpIh-eJ^#JR#oN@ac@e(KjA5OIkqS4=~F+jQVescNk@R5YE!|-=2-p#eP<{ z@?wXPrt^v!8y)`DFzzvLoYLblQ(9B(3+EPLOTVY{!IexNGd%+3JbH1Jj;E6cQ+dpZ zCsgm{gR-WjDgRF z22EizRe)H|XGb2%yjI8A_*-2xn-*G3ym>ks7QcAR2aD1?W|q2xUhzC?3!v9&@o0v5J0hhC|aiGUctBM|s?7Mx>`RCGFKb%Cv7v4SPCMFj{?& zcJ)s=kKReaS^w?Hy8@52$d5FWen0Tq1RFc8_l>E^OdJHbZYu(MzP$W2C)Psfl*vxD z!>9Yx9Hf&x(~~iQJEX~6yfZx~qYT^G8&^TqBQ}uCj6-Wl03+4^L;L6E3^Qd`EdqJ|#uuzIr+*wyb!}43Dqo zQD&2u$K=;_QK(9PdluZ4$K<2r%N@8CYoVM+X^N=6N6CwqJ8mCz@TM@J+Gg0Edz45ukFH;N&(fRid1N!_7X0^G4}H7`jeHX4rJ~;= zPnXj}q8sNwy``%k9uE)tWbPZ>`23&7Elvx^kBmioo=+;PKz|-UlKS)?juwM;-gB7f z6(3+?cf@|F9n+tr48LCv&7q7i0nt1l6SGD(sFs;hlbjBZ*|F*I0F%3sHIKM;*wYzP z5iYyudzuNs2+^Ou8UHQu2V|m+y!}RZGqW6*u93%l$xhVAnG#>(kR~(ZTmjQ|2&4zB zlR0~9kxvweWJ%keDdM0v(_?1#Y#3V^r_7)xEMoXmH==~TXA&iF-WEB(J)rRM2bfqH zp`Z8Niw%m&)5-nA2bkp}QQrRI`+h(tY9`O47X#^5f%cSQ1KVv{Glz-s08eISdw#2s z14wd=4!#^ST%OG8p4adPW4@kBZ29yzD49~=xyMWkalY;ADe_E@^#xZ*+Y3Fjamz7N z0tJ|w?P*E|quU>60&2i^PbLobJAkADC=ZD#jwzeQGoc=buG*;}!NgXEt4Vhwaa5Ac zeaDnFm-r;bYHZ8+`(Ei@`qm%XeM{{uMJ%i+?I>#T9SS6ABri#KN)x|NQ>%}p+sj{# z%!s5{L%&1`Ad@5=U}7Ko0VcP2Yw^s3nctMY!f(UX8J^7QjgN1}YLhqUB|d{EK__X| z89x{pq!07K1!JB{?91I2zI!y1a)mF~ko`vnjlY$N?*o}$j(AeF4pGI|APw)26P28n z&0alh<9$00+t45W{z!MoKB#xwGZ5vy9&O8I$w9vDOS|t7qq~+98{n=k$27eo#U*fw ztR!WW<+lI6zFmh;$Ay*W9+O9iA7GaE8>Ao;`wcvu52hjhyempTGlP&E7%fXLmj8H2 z3`YCo%zm+Qkxxhk{FmHbsY9}In%?25U6_@5mZ0qRmnd1<%U1x?GCoEPWk(OlOyK-m z*LgB=%IpD|Se59>#PSzU=D?RjlbJ9t+@b?A>nlrEV#nolrXRT;v%G=!&0Is$A66qL zql2XoyN2HAq+nut&|}8@0v>tHdyqxzG22T%;gH6B)Ew4Mdd$vqVe?WuzQ^eR9z7lt ztq_ly6Qws((>XfHk_~i^-@vfn(z28x(0LoaoDNTCl10FGP3M)#fnYFb!#mCqzQtOB zMkUk3=`pi60R+@zW>*Lt=w_n2@K?tIp!lN}GzCx~O`cFLhBzQJaR$0dThFK?-M%(_ z{r^1Bz{Ei&w;Z%HqD6>F(p27%r0T7y98ApX=^KCF8Ex>b>OE%6 zn`+IJ@gSs`Je{!`;BI=%w^au(cJb4em9OX6(>X87@f=`cX3t|LNnFjN7Mm##PU(4O znI5^E`r9)opG;7X*>Enh$4tDgoJXk}F6YsUbEf^bzgWfKF*6?po=uM#$Z{T~hq{_a zN$QdrqQ5;oLFFNljDaH8!_%1p{~;Oi!nEkjB-B^Y%PPX86G6^i*cw#kb7g zGFLvvg>}=m=3;k5(c7U#9S4vkMq1O2IPavD@)_!4W=05ox~DVI5Rjy8@j5y? z2dOoW(!B(1_jC@-MEdjOsEwzShpt?<96P%d8Wqv%kDrMNfccr%T1rzkc#+SQK};5O z;p`?m9(rWP6g?d_ryoolL7};n^<|_+rUlKMT-GD<&d==PtrpSwtDm}@Q7+|Em-k*p z(s$MX4Q3{6eOnC&n7BCi022qq9AIK&`T-^mR`ZzLry31wp5wHc;baRNOAjU&LF()N z;=YdqI&tQq)yesG9JYNxC)Vf=*>IJ)!`R4VO_7;>N%VGj%!Mt_HY1l1HO`d#6D?8~ zDTx^xNZ>*5h7~fs%TUA2JSd7W+1nY&VplFyqA*#R4E`g^q)iB?Xp2~p{Y0VzokmRYvZZLnA81eH|;@}odWvb~QhN!8$ zvVG=Th&+{8-t4KwD3Yi0rVHt*#1>~yC5{L6RN@3|Pvt`~6i+24UObgJkIhqw6QDhn zSefOi%wXl}JB~RlPbE%3_GgKeNuJ6@#bcgItY+3!#t4RoLQ}~b;60Vt%kQbYsbRZ#KIPTmYD?btu{QBSfuW$#HqBNN^ETNRA!4(^;vQqsEuYd zT>awDa#8z)KFicWhK#T72~8yzDSIlhQq@z5W86KJSo-Rz%-)l4_IN6*$A`=)_425} z^I+MUy^x7KfvEeltlol}v&0$Eo=Tj^>g95flj5nwYBf(KR$F)~ahjs1G8++#?|8=o z22Ewg6y`Ty4~0IiZ7PvtDPFFQ8Qdn&PNRG;PEq56FxHI*5y4v?NoY#jGg z;zmJFB~FI%RB~H{Rlzab@@1tj_6_N&e5rKKbG&*>S2&Jax;&MGE~G!p zS)P>|I7i%5i8FxpStghjGQKXPrZUZfAnKmV>c;)qVi~|g;i<%lS^g~3$NJ44PbKbo z^HgF`$5V+Dqdb*Qc~)xj2v}>fPHc+xXNeP&{8?s{af5uhsoI}qD~}qa(GV`Ar}8P! zO07;8(o>16_q<$Ud%C9*SIT%Q2VF={B@U1ERN@GKPi4lLSL;h`^!HTa2snF|*||p- z(o*^SGA6qAECWetVoxOw5A|nRy@EV)jys7wm5su9{w#5Lrl<0u3+bukp$^jg&m>YR zF85U8vQB@NxZucBi5pKmm6O7Fp2}GrHP}^%U<`UHS9R3jNuMq}XPV0EM^1|7_=Q^^ zJe9az(NlR>*BU(6O-_oZ5~qmyvy5?2{ElDQK=cjisl?^z{w%Th$5V-8dOVd_{Nt${ z)lq}z!r~uKC64LwXNko>o=P0kqp3`7dG+l{pDsKUo=PnK(Pw$%m>y3h7XNrEaZHb= z5{rL4l{luyQ;Eeto=P0kG4!z@sFnx$MkqAvG~VRiDP;^m00}asl+io zo=PnK(Ns1Z)1#?O$58d#lM!UqZ%_Jk0n(o(j_L7diN!yjN*vSUsl?(RPbH4&@l;~* zkEasH^mr<<_{UR;V|qN5Sp4Iu#4$adN-X~IRN|N(PbC)rcq(yBkESvKOep@*R3`QW z4~3@^i+?G4!z@sFnx$MkqAvG~VRiDP;^m00}asl+ioo=PnK@l@iN9#16}|9C2KOpm7$ zi+?ngS!tf%R91;T*`EuLo=P0kqtEii;vY{Xj_L7KV)2is636s-DzW&-Q;B1GJe64d zy3h7XNrEaZHb=5{rL4l{luyQ;Eetn#zG=dNh>-i+?D@e>|1Aqsvo?#Xp|P z@*Q2zz~UcIW%-V-XJGMq&!u zb-rho@90YGzr5BU3!9)YKGdd&8qD$?UC+egAAgqR zJG!2<{#ILVt9(b-lcR(Ssn3!(z3V%^u=vMQS-zv|Sy=qzsVv{o^(-v@@l=-Y=z20W zxBT{$@9286qPP6^l<(+zvZ5D8C3udP@927BSBH$RAh@Tpd`H)_u=vMPnY&XRHOPSI z>Zm~=$w{$VJ?Zi4xdwr(jvDl==q=jps~GPgg^3nve0z9$roIz*pmTEnaL(#W$(Iz-c%h7-cHdTHF4 z1@?TuvBcf;Jxj6kZC~*aPiJ;t5~e=ShIi9{d)nLQ+?lDJ#0^fHtv%aJQpE@}r)PtsAjN)rL$}%%n9KPO%gXV*6 zdpd5Fsu$XgazN<7rSSel<9g8jw9&1;}j4hVG)6FR(!z$SW(5w`O8+rhmDo0Qy z2cQ|*LvN_G8>2~n6c4oTaxihrtQGupIpKtTPv^oZ)SAvK^S7fVzx)MF=XGJ+($jfk zg`TG~&7mOlp3b}=a63JnDORh#M^`#8>D%S&nHL!|z1Nh*66=~+3Feu!=5~g@gx(Xn zbv=M;&fhl{Oz4ll+bF;B_w$m~=;`dZYs{Z#f?_1~_C-pbqWs3+ysXdKj7fQ6r=K^) z+OPh0W&$PM&I3YIWJlhowHe!kZ>Q!`OOZEdk%NyPShc9HXPY-A0X(74k84{jm-Z%y zYR*3wc7Yvyd=xX84puom&r7A*2ZRosPp;)Y-O}`e9AIKkl>hkDDN`a<-=!Yk3OIj2 zXv1mU`b2xfIX@orsSmfM1qH)xo=c;X$$Y@2g|n;miN3t@>HxDo+_q9Aho-32cyC*r zu(6&^Mg>sh-k<1;889uPc|FN`@R;2A>oM0u3QuE>A7)oP=7qaZJ!XOqVBu-MCN2nB zw;nS~?y7yI@n9C+pJ&G*QafI1s$#QD7zY6P^GqQl@!cxBk@i61k=1o$rf404Bfn-3 zbYXni+VvwZCm2ndN0E5cpY}ZGRUfsD?^XVA&SX+SJ|F$6nfLXrHa#TP79T*CrxIqzc1HcE z&ll&oXoEX*Tu2#t|84Sycm46n8&e?26S@+o2Km${x*AS3@gLvfyno*#kC}N$@Cv6@LTDVSL(SbLzsOh6fIZcpbP z(olMlLTAVEtx`aP`QnH}|LuRJ+RizJ_b-M2#r09aysX|O_O{ZpiiZqS-@Yu2s8iDc7KWD=$Z^ku=j&LkREX zpKcfBU!^jS?vSRlVXMFnTS_u#wYPdVWRWK`dFC9~m#v^rGsTn0b$gl*PLK6u;>3dk zNP2~Kq{Yb*4<|T)B%XUY>NqFJlZnev56Hwf-IIx(aGp%=Qq^RJKVTspK$41cwE)Q= zznC2JkXYAwxze#sX5TrbFReN3J%8~H@?Va_|FxCy;xOLsI?{8P<0&_0QWhU+{^E~5 z%+y~3q-J@17Pyk$CLTDePG9qZ4WC}Y&5IbM$=t(SzIlE?=0m28ClgB=J=5n)x?RiW z#8MJ{gC^zzwK|#^lJU)RuZ|W@{nKP-h$4|`pNlM*1xU^E#85!P`G+$5O^8f;gOW}s z2T&JhWGM%kG9L5BCIFAw&=2yMd49`zl*B4LZJy5eB0Irj4s66dz(gOzW2R4|oJUb1 z)jWEBIHXN~`*Y!_M~|5zJTMkKW{U8tdGsXlU(TZ}UxJvv|MnE&!P{Zgdd^0EcwuA@W{rb_SB{g#$9nV?Iw7iNL))U^)h9G}8y>ajbRx46Ivkkuw!L zeA3Mex6+e|MvaF|k;1nT@4uX9{An_I{*70g(VCz<4lr?ov&KweSG6Dol7i6If!TYv z;56+G%91Sdi9953IcYW?*{@D%daL60E*7|z+cHu5C(UYhrs$ zIl#05s{VEif9T^J7^+wrb7JXX)8D>QM)ED5O}|77o0zpeUO4H;OA;@fKET8=(Eii0 z+C>K@J8xdrpPm67^lmi!?Qi-h;Ca*4L+|e;&swJ-QjRa@t!wViG|Ls>JO?TS_ z=9|4Xppdn1{a%90^M5Ktf1CCm_14DH)nIWcvuFZ#r4TMvl^(K-O~@~&ttM(d(iT?atk zg@Z3Vnb=wHAIp`^oZmXm##G*gDo$UZwa7fw_dMNLq&9W@V_aB<=jlx7CzA42;O6Pf zNj3ptZq+?Vg6EH!R^s_z&ripBvCQW$c zz5H>%l^vVXMye@E^?`hbXI6_Xaf z6KrO_CImq|=0Y<>W9D_ISJPuALyGcgpW?-}!rl&9F}{II-Db9u*dnd0C>rJy?_715YLvy!qoy?E(bqG?{-PlIk(br?@5d zM;6GzY2p+&e=j*mDNi%QSu>{e+eoxz1{2>Qdz`^+bl3f-D&kXp!$7xR6bo=ofj zl5@>7k~hT=pgHXT_JAg<1>bJ1r0e%!Z~OtFap2%(_a_<)1U}yG7te`K)Jy(EGkw0C z&`?SzY9rn`tu)DhUnTwVy9NkcVoztoJgKMiNnEY^+dK9ac{)>B1UJcJrgsGd^Z*kJ z7(8YyFyfK)+_Q`gv)Nic_h2)Sd7I_A?j$9EM;>$ABHuEAKj+{r{q=ii_^8|qF^CYIP7KvLk(CM32lrgW|*Gs!{_PJPw6 zxYysI*mLv->pS%D80G z!(YoZYys2#m!lnfz;m4b>rnl@Lag=yI4>&e8P#{)<*6};wL=oM%UpNt6^$6A53-%S>x&h4~cqiB+4 zQTt&hkiM8Lb%`YK)}Ct@8pm2GH6C$x=aE*9aJ$OamRv0ZJi^y6$H0qxVn5&y>Z`fe zp#tAE+ix5xtR?(y|$4 z47P%Y#3@q#!*SR7Rs>GTWp*j>+{;l$vE|!7m7J#&M^owJ3ng{hCa?0Tg49`Ns>Gy#(1^7zqmx%L)J%)qc!V& zf*19>7tN8B=(qatS13W6@+&m(&CtS`VrDRrJS0w$*1|ckjL1V`vyT4o6mgRnY5!_s zZ;3ZOGWdo>)6aU*%=3ZDEMlQ&~Nm z`AQic1v#xodVU!4(NVdbSf{J*>BN#3{aPklPtTCY%yE)B*57`iQ=ntp$p!xnbY{&; z?Nv{o^k%`A!>TKto*Q#`2biegHP`nxQ22C@iOsD#hL%xJq~P@<{3Hku2I2uGY9)W$ z8?X7+JZh+w>{IkKG>#7-Nyi^RQo7y?=YxxNG?~0s*1wpsLmKCt)=Bc7NA9=J2#}{Pa%N!U1N20N;E+z?|r4X`PfAQn@Ez@~N*8k0key z7*RQZBsJ&Hl6$jk3_e$#c<$e}my@ji+sor0JEH+t$iEr`i?{u?Oll0&oM+J(G_}F2 z&VkKI9y1mqe7nAw6DvOsAgfbEPsV0}aOx{GvEj#mI0p9p6`Gg|_E%_Pkj7u3)Qtg$ zytpr{v_8PZUK-7I-m~f{1@NYWmj>6xkuWNL#ZgWTxTy})z7pugpA+4Sg{)e;%9yuiytp6ugx*>ho=Vpf%^e zec~t$?-oRmK!Nzno@TVj%BRHZ%bvm{pwlb5g?s4rEn2MSJSN&+I+fKIE|KyEcLu+b zqVwO5TFFDMEh%5pc>sxu&MMFMhXu^qs>vfvVKjY--XHd9XhoOd^LU+fBkBFbV+ za@nBh3P4}>h8CT+65oc3PK$g)FH>L4G?ajy=EQGPTcnwGc_t; ze`p3JqyneuwQ)A^f$H>+aK{C!2beenL3-B_Y0@LJwvF-C-j&% z8ekrir>S~Oo~-FHJHBxTm^hfmV{(+=V`hOXShOCKS9E(!4p3^$EMp_<(_?0q9XK5x zGbxU09<7uFRO`CM9S;j-Kyhs>%};TCo?O` z;nmcqIXK&H9ht?8sy&$)w7A!9CpPiK%rnEeA_u7Nz`7!PkM4{Cp*dW72hRP*eGenP z!wk{d>P*KkV>`YbKGD4I6cvy=we!N^^^^;S1DVFz@6$Yhq`f zkXUwp07=@@Lt@LU7tDsmHQSVO7btzra49{V9i{!zbf#hlOggLMQ?x={_mEgJ>mjk^ zUTdQlm%V$)@@V3nflTNbXfYaSdwFr6Y;kKkx83=z-8G#lej<6->SLxg0IsE{Gu9V< zyFJgz(@H&^oGJ9@`IJXN?%A={(SLi!&zJK(vlfZ((mU8=-N~f!-@Y&kqRGsn_lWeD zy?p>l59S}0t*nKWd>OFF(z!TqazJOpYozJS>?~lB&Aevt{zVCQyFopen03~lo+LhS z{ovD4l57wppI%*z|CQyrw5ZlQ}T8VLPzzHF$Ei z4a}vTox)Sv@X9<)ib{ISh2dk1nGG=ISygZpLOS!+_ zbxme^)WB5m9BSAa;5FxicC36b_f9JEv8*u{OtfSDab^h{a9vt+yI_Gzsl0G@oXu>l zx%P|s0iSMdnqXp3R!dUH;J$T(LnfMtn#>eR(`kB4p6ZtW)A$-$Mvf5xf1F7Yfu8f1 zJ^f^WsgJXKV{6vr@sJ+Pp@D(UgVRJC{s0rLInN=S!FB*iMQQ%aCysSHz(j4VKb`y8 zJtXGW5561|!XC4{MZW#GMP8rg!a(%Fmt)uc0cQ2S#hfP2kM^gDFWbSFV{BVvUUAmp zWwT9hab2pT#v2m*aAiI?n79@4;5fOqK-x%IRJ+OeaxXoHE-cB~4wJIwt~6KxokLbo z#cRVTnx~Uj!20v#<*L?k%Svv_I(g}AIQM4^%l0R`dcMWevnT~=QMg|sZ}su@V93jJ z{fYbXO{QnjgTW+^*)z7|n@)Y4{VGnrv@7Mt!1RMJPoMbrmmgpb%0T$jOheH(nI1B3 z!8fG;@;&;d95bnsZ%qB^Zz~t~%&mYz>x0vLDLZz6IqA{xr@6|-JtOTv-2IoQyuKbY zbu{0yc|hk&`C!eVG3W(8fTT>L|ML0UFYMQ&et?!Q=lf9Vc0dkiAbpMsy6&eTPz20B^CZ9w1-D6@eub0oB zBDZS3_nVxeuD`uk4;^ebR|oqiE}N8q?bZglNNYc8%wHI-bC;@zS~QE%LXB2R7*A zT)jL}bFWD%-Z~ujst=m)%4pCZ`gKb+9(}syP#`HLYu~mMq>+YimsCkH=c;2=fkgK$ zZ=cefNjTD@p&69fR^%CYGBLE!>>WxVp!}-08-ud?IPcg=U?A$_yfJg_$?T*(Jco8u z$@iygGIQ6-+}5YrZgSl`nT@oEHjU#9qNSjf*>7`iME_4 zljEoP3}+<0828a8=Q}Ah=f4~$+I#yw&U(2Gdk@@hfKoM$*rP3F8P zSK>9&L?_sj`POTXWN$%`JehxkU%k+;-nv?8q}WL0SL-&!Cnff9oSx3i#0w9;vKpSw z1W(~@^K{1k09(P+nG6JdyXJdFo`3@JbiNloMgBYomT-GI2i{FjCzq*sIx~^E`W|KU zJk_LWI#VM{Iz&fg`-MKHwn6riBDhCZ%?FY^c2DMw*GPAEX7w|<8wZ$J*=fgbrR51r zY7XecGE9$|;4z4j=X+~Zu%X5CFXZj*%aME|8DQzVM(qup-=bp}n&D{Ep8x1@2bYgh$N=MzNG`O+G zMlD8)RlrR4kSU`3_7L(vD(7f$tB!|6yW2xzh~Gn^MRx#6{X`zJlP->GksL>t(92~8 z^M1>vrxIg+p2{?G7gNbSPhJ(hSUl!c=D>{znnBSV5LwU+8fbQTD)ah&^W0O3bAvpU zXh(Z<9bTpn|APq^h! z#E4>j+gDJJT5<)H7d(KZ5&#d0Ri_7#6!q|ssNfDDcewFW+%?C`b>_^Z7rK;|$~{4) z_`@@qB+k3&PnoAV#mh;Bo(zCKvI;$ zL*gXs14s&xd&u&UQ?X&Hi-smI=I|dr$c6Th7$!V`EH@3ZqY>U7J02-(AImw;jg0y% zqtx@8(&y~H%8kJrw@CUA$7*uz=g*tdshZA)#mWbe<$Arnm|(ERK|^cZ=746y?iPQR z<%K=7Vex>ca*?5>&oUJw)fQ&e zOPRYrZ+VT#e6gQaGbj#PwXnZ99Y$+RZk_j#n56l$oW$`w_2clC@4q|D#DwcHvCsYB z;}s!6trEIK?7u#Rz(AhgA(kv<0F_jI7XBC@;fj4C{i6+y;CBPyi>wzP5OHs-*)u@j2GgnaSG_O7~=DpBG?iGPBPM0*nV_R)^W1E1p+AtyXg;4hoq5Gx1aj@|l%MU?3hq(x-dK3}yZ1kY>=p1z{tH?VgPI1o^bDx6O`YdG5b3 zD#_BB>}ENgd$=zMr#{b?0f^P-nTZbdbY>cUIh_yIWBT(9WI3I@XwTD`ip+94lZY#q z&lFIW)5%MY^m*=j$7(vCtNtGC^2BmFxvtrt=Tm==p5(TwkSI#Kdd$Sss(JLr(*_>d;|wIRsNb^v zEgL(r-ucSeC>`=Hu2$4^u15M(pJ%cr!1e=3YT)UweU38kg+AS$=HQ)Xmg$+wO9HP` z2jhL|I1ex*@!vs)9V<}+KeE6O9*&m3OH6!>4lr>7)xo#pjCie(Goyui#XV-GRsfGQ z<{kkF8pLB>56Qg8yc^|mJ!ZQp7vnLLcP-~p+6Kyb)KQ1{Z%@r*o|~`W=YIW_4w(bz zN_xzs;DAS(%*pF8_t~g#U%yU9vWLXPQ3gv}I`8tFX3`v_>JI445)`;c`qMimqYmgy zVj_fm-6MTB*F;^Hx>d{g^m+rKDb;tN(RG8kWV7yjn=svYd!qf95)P0iIdL$Mn2M8T z@`fZG;vpNwR}LV_qVl+4zUFWQJ&8@*UL>LG8eTe0kUZ;Eu=Vdgz?L~@30L@AgU2sog# zdVpidoOGPFjxPBP91-Z1Ty|@~>nm-!7>5}P`F+uCu~INm$LX6su@c5cltLzYS=&=~ zdUGb;`F))F)7Ot2cF&=8(c&yENEuiP{-wX_IZTlE1I+9{`R0&Ub8FCX9?*#sU^Sf? z*Gk`R7ycyYiX$htC82In^0-8&70*CYn8serctYr|>o4aNw*KCP(r0c?0!{4E-pC>xCbS9iqElSzU3}k9aN}+fp`YV#;Av>k=^c_la z5I+0>l2Q=FmX=t!M9^3PqRHaO!#yyoN0Be zmiO$b1yjybc~KPFW?Hjc6HAFa&!0r6zIEIICWes?F!5#c7H3LE;oG&m$A$%Y_mJpk zXyMGv7Wi-viJL_{&qF2LbdQ-;RPgBsnAuedcSxUSf@t;Mj`d^y9eOc)=`GG|dL|xe zi?h5>tEXrXMah$ic^9oexCTIned4-MoKp*YM%cn7I)EgXz(Zm>V}FGUQt%>KuaYLm z^|c^H8<(r3naa6p)j8{f@K@#xgLHZ|x6swl;+cw8AX9UF;R;=^K2~*Y^zN=8W$X_V z7sYuKe&N1OThtlf60;0$W|0$yH2>>iS|(lK%eJ@u7*C& zt5J=theYq?01_V!k6E7#&f*%fIsGNdf}IG;SNzZm{Ed6l4luKl;G0gbl(?$V)0w{e z;@2&wNjk|sn3<(R_fng4Dc`0TuO|}&Kl)zs7JCnw%A9Y}Jb)z6`T&xo$X}o*y#?Q2 z?k`ZLcIMk^71D#xkQevNN(1Xd2m9`nvBG)kE0nw-=uQ9W9ZLnZbf%>jzT87*eAKrf z9YE3}FIp&8QTA+ic}=tMS)J8#LLJEvfw?LSRkrh z)_Y*_lvW>cFF}$#Br14)m;)n89ul+vx}x#^3!CDtv`^f6?8(eDsvOtX3#>6?6;oZ` z0VWoWdCWA0gS>mp%yfgd&0}VRO*xMqbg?|0$qT~k<}uUYR?ee=Zm_3w;){8JiO+_| z%;`hWERc9@e`L=L8ON5)K$5^8kXdeTKR>j$b&e>@s>plsr->2s zgVV%puqP9XW9=Z&{#^J9Ycf-M3BKSq_LRAutq^1&X27&!m!ef!Evm_}kM@Dh2#12XXYw>G&2;%^{wnd;nSP zwT?6lf(G$a;)CfSlX9zO5Bgd90%emeoTZ1vf-Db-9WNfTUKzcpj69WSCU{7k?X4lX z49!Dg3yp`w?7xS^9!U>bp1>Ld6Ih-~d?ODa$y@V~I2_AEPRi1I$VE{U4Vm~6m@pm^ zCuw>}448Vz^4_L2F_Hn}sl?tU4~dl?9ugaoJS5hsdq|APXvj48RNtP3kv&f(PFnJi z^{(kc*VI#qO=2DrgGL?_Ya%@)rUg7?c_UlGxa2-tDg#+<8q6O?p*)q?bmk$kL)$}Q zX4*sI{6G(hZ4(|6yU0BxX5>924!_rsnHK?>KM#q8zaA3vX&w?wi9ICN{d!33TJ(_E zV(1}p@Vke^LShez$@uHuPl*Z$uYoCPOK7IoVC>e$t&>2dy0E6{oS0ZSz(jx7W5x*p zll=e_)5jJwK@$wO9$=zb=rJ$s*gU|*zD19jC9m+d9blsN^q37t0v}*vP~2nk6p8~( z?9@HL#0nITnRht)@vGwO02ALhkC|Ot#kwx7{+PP(bPjZ}4lq+#Tg{_+QD?2EGtGk)VdG$St$v}Z}PiOLL z)%Pevrpj%GE2V6ZM)%*IG;u@CQ40o<( z^?P)4XNEt|h5_0GOzt(cIyt9VZZq5u<_G<^KdankxOKnxyi{qd7f)qBN0zvK-~0V{W!t`4dJ z@Q@Gnjd@5kK@TA7*@KG!yqtPgd9&_CVX$Exnboju($kqtIWay= zRKk?K*7O={#^<{4-+WoM9y3D=;PLS1IWf)UF&D<_{I@R*{aVbC9lDf8u-`s@*|I>& zPRi$YVCjMP-yWS@e2+32A4|79ogMqDJdYAiEdTZ`O>o~e-v^ey`tzLS0sj#*1Rr?& z?TIs>u9NO|0u5Lqq0jS5-Z0UEvfqnj{s0prfCrdZqH9N> z=G*Ze9ni@hd~}SlZIV2|(NX@}d61tS7`Brf)UUYTK>6)Bc);^0<9^`n(APa*4o`>X z`isT19un7FZ^Oqi=tU*(4-K-x3%EUb7EngKF-OHMwFnt>k|znPbLnO)l82^2$$#pk`nkH5|hq$`OCN_ zZi@4wxv(Dl024cu4=^!hc7TbszBbaIP9B`jt3@ewYSjW?KJYgmj_Dn%JYvm|Lu7ZL zBr=H(<^d)<8vffcn5N}DTgYfqsW#xVkBUlwti0bBmU|vRk}>BYvEloGL4&de+McD?&~@Fws< zKGwl$a&$_o_;{?qA+11O>>&1#_-GtJ()e||vtw@|BlE*EeW3GlfQiZ515BLA=hgAV zSdxx;W#=!tL|T9F%n>b~6YG<7C~2GUaM%5pEpcc&CueWICQZA-_o=Jhv{`kg4zRJz zo8g7?#tsWFNIXwU3sQPuh(%h-rRl96vpm7v8cufflGJeW_W@>o;HN$HfuF4Lqo9}e zG{Pc`@@hqw3T{wzUMr=J21H(y*)eFYFMG!Z1OMeQlHfEwnb&S$({R>A-PXtrSSoN*)sX()@?FYRBMtQ8aaC@W~1>xI+FgF@UHG_8%@c z_GDtelYZ78u3*+=rjZEVHeCt-Bv1jD^18L3_1>uE4p0Xlsn&C2aKz6xvj_7=qx)x* zWb@Z4Nv3NS=5Li-HZzeGkSIA;XUuC+$U?S=Z%7LIX~-KFEqTbyDEhXL423W6M?nh#eHC^#A9;a+JAeF6W*Y#Rj?NFYFxVSVOuTlqqzS z-tlzuCNz)9Rp$qo=x=${kNIM&g~!~rxW#tJPVtoA zBObQuzkQ(-Yca1(E2*{_u8d8in5w5UBO;4=lm&R$z~Sk9aO9E4?A1BlcKzP!oNh3a z)-2}{FU#=f$7)9AWQf+@s<;u#^rj-2SJ(J>4OcE%lhOY9VWQfQikI9`nXA zi5@f0d$nD+%bct4QR`Sc?Z5rSu0oHQaTdisY-a0Jk3nu%TR6+oe>=~U(wM2ItjU;D=Jge`~!&5i>w|6W7^q4Q!Zh6d%{x0Xyz+MSY=fw6ckGXIRfyV5= zUT!n&(%fnu?aB1j_oz3V8sN{9dt?qUS9NaU>OEVrYU8w-DvgW!{I`!(=vLFYD}$;r z7q$}XZ{OwU)jZnU7^?5ld*f~-|Lu46PUrM2HXLx^>EzM$9D!)hRLMgvT3+G_z^PE4NZs9TWB31Kf-sLrrR|Yqg+YIw5uYpWz zqPzw&+Oxa{GMKp5#LH4bEY~-S8pw=VF0X-%LN2d?Op_3HgKAky ze^j~6u%7Z7$ZI7PS^XZZgcYmrQLMUhn;}nJbq!>?!^&$QV|bU>K;FMJh!ykb{&6Fl zy+^?;uYpWjySxT6ixkRhAopoj+YEQK67?^79*y!E$OKr*YakP0DX)RNQ(RbWGX%4| z1~SVo%4;CA_Mp55a#wOx#~HFgqr3+4zIu5LWCH2sHIV7rnc@1R7xBRN(48bg~fy@k1oGYmBW_!zPAhVFB zyaw`)-(HmD>#cDzAY|rl-6H^6ss?2J%j|O?jLl zgLta@CQ|)bUITe|o?oZmqir&j-=ma3mfxdQUIQ6dro0C7POD{gJ;R+WSGmpbw(=Ut z1Z~P|An%tK#A%s-dwC7yz0Kt6d-O)+tMAb}%WELxzL(cP-s!Ndu4hP;w!8*1!TItU z$a`cwMRlBEwDKCrdpzYekf{d4t=am%kEr?Tdo%`4@AGt~kfk~nG?LUWt_w;Mw!8-N zo>zGdWH8HXAn(j(EsrzI1VqYt6z8z|J<7z&@;F0Ivpmj_Qlsj6h7{YB*FfHLmDfN9 zv%Cf}QJeA_$a`JoHIQj9F0X;ScL=ch9;K3_JkF4csB)WOz2!BKcSfg_=O)%DuYpX* zNO=w9y;gY*WG1SX*FdJFzPtu$d;sj zb)2Ck!C7uIB!N_&n`m)6s(US4B);5cNI;}I&XDQz<#Ql|SzZI#Vl-688B%IgJ_j;c znesW1Eqi9mZHD%g&w*@lwX5qHlGrVu1KHXrp92}p@*2q2l9DQpd$+dAYamlzS6%~| z^}^*fkXbKWUIUqHR9*v_0-o|3$c%6+uYn9^c@1RSrCZgucgAv*+YC<@BoycPQc_x8 z1KBe2w%le&bg4Qw5hBZLAX`r)teQtXgZ7GZd>MsUUIW>7xnlJ_>M1>d_b5m6@Biz+ z|MMUJ@{j-WpZ;U}$N&2u{-1yR*Z=Xa|N77W>%aUT|NNi-_?PQH{Num=uYdpNfBx5h z{lEYD@BjFhSPbZ4PWtP! zuqeWliMFAK#5CanBz2h`941C-JegRqVPvf46we^`v`sl=G% zpGFU5AMAN$@R%Qf#@>R8D*f^GLr&9MS6<-T0!eR>PQ1PKLr&XUKjidJTn=ug{`RCb zD2Qf7DUie>4_R&|q*|KH1WzRvfgC`R`Z$23QYsIL74ip=G?dXpmYYY}5nb)1j;q`} z3M83F{w&L1pp0Lokc_7iZ8)zmlV${mGKDcRiZGHRfCt@Lh9fBgFg&`Z65omgNU{t) zB({DXK+-k$kmyo+$aLd=hdQp75TmkR)2>3dau;w&%=!Y%kt+nYQHGvcLNkFAK)3g$ zK0ZU0NEvILG_S1Y{pS3m>AWUoaF+e_Olpb>|KI=H|M}nl+rRzu-~Ro7`x6R}Ed0@@ z|Kr~h^45@<_6A>W73a*5D!4|TN~~V@kPjtVwh`_`Gv%!CwAmY!5%pBxWgqoGk`(o! zzkJd&q_y09Qoa5y?f#-?Y%|EFr!&3$<#fLI6lu1<$=Q7$r-yv$4jn*}A?G2pK%x4> z)7x4OS?yKkN>V+vKg-M?{QmG;Ka?50SS^?-u+FD_J(T;(I^~{*G{DrSnF4D#O%K_r zcH-d6Gc51>G@CXOGV=$Ret?-lf!}oMngwL*_;ZpxeXH~@5%epwbY-! zvTDAVLxH44ikpM()3X^JxNZe0DQ_}7^u5g90IG91z|5qQZ-GC+OownaW~LPbre}L5 z=>Vqx_RIq)$4uu~J!Xo)fk!s1``l zN<8pefBAzYVqL4_UhV@gUf-j?e6J1t79%h1JvI8@n4ZjZW|TuxK;huaG1sJ>|Miy7 zCuu8b0yxe~%RA2w^5;3wHa?&;i^ji2NmmVJRs-qxo*UuJxy&>JI^X==VP<~~@ZHjx z_h>W@atH@I*<5fiF?#Aho#(u0iSJmUF{JmBEq??1)is?1{q-sR%M9M)c}bei zg`GGv;%n@W=SsZ`s1Tc3&zb<9&0+a|W#dN9>+8w%bY|iQTz4&>SE_yBY4>zyU_3l< zp3cm5qHnkInHoHjC0&vAWcd{lx&vcQ=(8mjglQ)L9A>7j(Scf}oGLHETvjn<&*f}27&9^H`>#@%E{y~i2n3UqsebR?OBbP#aCd~ zcr}*CAEn5G9Y9ZVlj(X3;>;-9s+Q=UrYWv8(y!xRvfq1dK#!M;j$3 zj$gX0MVA-@UCm4TTd|cWckstXabLeD27N1$_|5i6_ZlDoee{`TKLlLQTZ5*wmFg@q z`$>L&&o}@$Q+q>u$I%xDkQ4^vK;=Ao(fssu^7^9# zOk4rvF|%!=T-RmWZaI%qObG6~{`Pb%p`B>&(Ma)qwXVy?*>am9(-tTlHJVK!>}*sF z%&)jjWKDT-lRFO%=;S>kn$Czk$ov5$1pqxH4k`7J_z-(Y?7+5=D@o#F_M~-(@{gWM z+_B*y(ckcpIN{hs;*xR?i6gi?B-#lc5;vTANL$A+b!!L!ueuA#pj4hs50q9uh}`Ysh#k)whRpgTuylS2n)Djr5o;uE4iJs1r}? z!8u`-YzRUb_zblmo;bk=Xc>{)zD>3>h>Kzq)g=foNIp3aF^)6=G@Bt(lUmlX{oa{ri zCiw-PN?cT_#pwQ}jK7FFQ?mvCvw&)$Tlyu_uZQG8Qky-d&dd!9P;ibPlGf+Y1ZJSEJldrD6 zn%tq|za00Ydq}Pcwz3(66ZoUAWl~O%!`mLMxCiCzBlidtYCq~gcB<8FSAhAb7 zGYBmjtvgymXmHP)wP;!f)B@%Kovh#ORnIULvXV4p$_k3Fdb_c0U(4p5+M#dr@Bos! z1@)Vr#%Rg}dpWuXeR|X1zAsVnaW;%Ydn&8@(0T?Ok&e>_Qfug49xw=3&Uws`2}(|L zD1%w5mB+(fKK2!Qa8{PT>FH~O!}Nj_f;=!H#O6_K0{MEF^=M$)rck>=H55x1Zkp@JD_tBoti^woS}F^ zj>diZLhI0ziQxn-NSQ?gOh166c-#Rb)ogo6Y*^m!o@6<`K|1G>{l*mP@|ahBMm_T% z$piLu#svo9^q5b5O>pWNNqu-aJ4U-a=F9mzDe{@!Ml7;g?s;+akTyP^tQrI>)}Lm! z2Z3~2r4$Q^j9CBavr)*$lZkhIztBo|J`?NjJegR#tc{O7$UOr6)kNaS#6iUR3N0+Z z(^Mu{4AQQB%V%}Em7YxOdC#I5DVseD_u$(-=$rj;1ZoYC%v3C|9ZJBM;uL?@N~_zx z{Y(0I%lZ+e1Xt5;AnRH3M40;B7;G)*Pw$+&loJ4Zc2SX0OsF{9a*N0|$ih_aZ z9x^RS-wg5}j=^mY*(gbJ09mbw)0RSt*i-qGE2A6Rd_0xxXIN7^FA#pY$HX?{?Jp@y zduAa|&g)CV9bjU;n8)nsW_ZjOd31n@ZkxyC!Hfr(7^v`=6Yr77TsX4q022%AHD-*% z9V{xnM=NGm9>iiy>=^Uke&3XSIl#m$p2yt9B-Q7cHP7WddeAMfcG4~`2Qob*dchhp z8vu$8#LQr&{FtW_Tar8^j;HXDn8fptXn%Of>XC=pgNU72o=R++@{rXd53_I!6Hc1S zw|eAZsKj1VPbJoic}RTDJtU4i>^taf%=b4NqbZJZ0GihV)Ub_uyjc`V@1)1fP!4eZ zZE4${sYjUy8#E0jmf%TY3M2-6Y_;58%|O8}Tk;Z26ea1c2NLr*2aseWcu3qAy)#GZ zvS;lV#eBSMrl=3@y1zrMx*B>vLzHFI9Ew7MFZYnx%IKM%^<|;s%L(*M&l*v{^h{5w zPXzjlPJNsY7FZuZQn<@QV$HTc%#LAgFGwAuGhUE7daC+3qdTgvWk=`NQ;9`r{xDy3 zRlOj^y@J!!uh5Gwn>Rgpgv6E4aIfV+-$iqMV6fanqC0c|Ne`Qsqw&_iLIX4ES~e5d z1#$PX$@4h8Y$l!nbZV~8db4<9ZMmoNZ!n8_cazt}i9Q2^{2f~LX7Q>wi?c2jzFae% zCw%C`ynontcz~H*vEL@FEw9e%H=N99k28?;rh7=t*d9Pqa7N$C3}zq(d8YF?4*Lq- z7wS#@3f&hPoca~I%V%f2clqp$4Y@OYm5$||F9#jx<>*H3u3fg|RrekF`gDJX%4cWn zfPQh|(1s-Kp%qfYpoeD=kH0@)5Jro=a6Z*FZ877jYuYws`NNj!5fGKqX@|t0=@s&r zFM5_9b6}Ux0Val^J?6yhs>jSCBQWJOX8WP<;xR8AMd~qA#|f{7$4rK``X03h<6WLk z?sPf8Tx5WFOzw;Im|3$`&ZCJ-^*o)t%2s1OKOEHWF?ocw$4p$mnny|IkgeqDY*?P+ zF&|8nc+8HYu{>s0%a!wJU}(Y9IdRmO$6Q$3rZIOvWA%H~xir?($u73Xyvvt;yuD#a z$aoV zZCGF8dBm+*9+SuNdd$>lmGfv~Gq>q;?9 z_1Sr+s6TtdHq^}2iUgaIzj-AP22y{3dh>$GmYE)s)+g1tK&waHPY6wvvAoI{!*ZYI z{rzDdw~RNuNzYWrLElvGP|L9Yo;;lS023<(JmxC*Y2NJPuGUX)_Hk29zdn1+rfQ$& zz0zJ)Y>T~D+7v;H__Jq~a`79or-oJgG{G$QX)>Fs+^2c3OmZyeQM#O~d368EeVVum zaA*@=DkzQQq7}KS?$v#nNaT2yf-)TXdQBA-A1*pyC+(Ap3b-2r+M#H?$g9Q zF868PKPT7G<|U# zG$A2u8_;y7+NwGZnifcGS@d*XxE0l7M$uREs5fj>^>lVzBjzy&jveus4>taK%)~{? zc{GzaF4iG?L{+uT&@(2ZTGyq-usqH%E*wp!`JQcj)p5{wFSV@Z(dgJd;Lkp=Q|JH_ z2cCJ%2giPU%&7Tt9%a{i`8`?*0v79#jKC_l88UpNI(Pb}tEt>(cp7ep(Xy23`Q>qj zNK(1Y@bJ(#fA*L*)%WPhY`W@ulv48YI74!N@lb9v#Iz~58RnH1=wiK;%KUPh zVYXSGn@Fmw+-8_D=d170%+)OC(Jb%ldb2O1JU5ZC8RfZ&nDgZ}L$XI?GlYdE!5jYo z+Y)?&_g%au)}v-8RCx>9x(2qO$xj-{@(zl1)pt;240w45MT#ZLJ1AD(xa!-P)NXkP z#oCSf#Tqo2IHbT@Ve78%ph$gCc?ZS1>pLj2As9E+`|nxbL9r#i+M-WeLU{+py6ZbA zf?3`{5!<`GgJPwasM?}m8PZT~(XUqDL6Ll1c?ZQxUc1_&kMb<9Hd?K|gCdya)kdq; zcTlXX{;SR$W*>TawbAPJ9TY1Ix2rAsm3VTw&Cu&RC{`A3S4RPZSzc|F9)j{}qt)v> zC^8PdyxM5>`VNZB6)3MZ%Knh@YNL#kD6ck3EWNziD46BdM%h4&BZIX~n<9zoDBv3P z9TchAE3Y=nOv&nZu-u%d3roSzc|l<}9x^N*wU_rjaIHvxy|sVcCEPDXuXNDRKG{-S6*$j z61k|ZHi|+nuQm#1d9~3>V3BNw4DpR*h(vUz4d$5xX*xhniy&5>xIW`lN!;km?R%k4 z|CU#MhtBeepmiW$D;V~U@jg&l0~l}xh?bnlJf5! z5(uX;*bN#`j3hACZ0+(yFDakU=JYaAsSHv?w0dt3Qgw3iPQ&>6jt(( zIHUCdk`lVx8IkF6A>H#K>)jYsN6X^gG%V<63Lg(!O69be7nD}BGVAiX- zc!arnU(=WL&D;)5IV7nh{V~@My)1k3K$0VT07I6(MTXg~^n7ujy6HMMq z{I3^D8D2X)1x)htncf4y)bg3q8t~E&$gEc&$(9tGoXOl{y^8#r8C%k2@@w(HX3V|<=d2_f^)5*Oi z2Xt~a%i2qs@<|GGdwA-;-wpeLyezfy=*sS5D0hxBV2Zw{KYPd8v;$16zxJ5iV|0Lt zeY6LdgLtHE#dJPW^zQ%@rvcdGbnH3;l(0e*pJdbZbZkKeZH!l6?lp5D`rXRg{dQlol@9ODA!Hg&o->nn7 z+XKL+_1}}X(*GN8F=3I1n@l%$i%v4PbMzZ&}8;xh(SCpnSmsa z>wrx3U_F^w^`#YE2I-N*r7vc`S%FxE+*|eFqKqKuJh({HS-wgnbaKt8=X*AEfCBM+ zpO`eu~UtCjAU$ znl1W+miH+zArs!ynF{3UCpgvdbl+1vkpERVMemDqjBPtel1A9^=rK9EaDa&uA~a?O z8elJ-e?+B2`ym2=20cPe8RMW}b-JZ^dMUNgcLCSI- zb@UB9of)ZB&Lf^`dO#-*hW415F<#E22P3JT&WRo42blO8draQvb%2Ql_#Sg%gVg~h z)@NGGU51VpxO_K*iP^#fI?*@um>2H6IKaf|7#=gt_h8i?U}84gV`j2vv97y+4X3Yq zIy+8dCE z07-qXJ{EN6W|Dto2~CEFOa>2$^@JW0N5E^yjEDt2=OMBG(?jC?I1hSm);~i3u`Jj_Vou0I zX2(pesHYl>A_tbrY^L}yH?Ab@=<9}=7 zjB&A`dkM@psO`|mO5BM2H>Urh$@l}E%N{))@lm&5M%?g_WEXl!46}R4K|Ny!kd(0T zkWW2(Frw!LGppF(R_e#H|8P8=)X`2bk!%9bjS@|KNK*)k7-oapCl_gR?Ix@9>y+ z9^&u2d4PG5>vn*7*YhaR4?4T`VA68Bory1t`{3+4Op zBIr78duCBHzDJtQo?5o=vwJ$nLwB=H%l9N*h(}(5&Q6}|B}Xl$u7{lt8wbhkF;Yza zfnVj*bMD=@W*QNQQq+Otd&j~8E%CgU zeLw$_Ozyt4FWfUO$`R_LkBbz@Z7teAtfcSyG0Ip#utKb1^E{~I_1Anb1f~!E#4r55 zLU#7+&JdEB=uh71rhA@G)SUk46Vtfbn0;c*f^0U;_SD1z=6n)AU_`vxoOv zJoV9E+yJW`qbC7$_?**5lILCz@qKhn=blgkxBa!RMl3H<@t#heNA%hkb2b!DPiM#4 zAJ6wp$_J76bUqKI3O${?L)+6CtpxJv>CBdQx|>$jy}z5Dqw8lc(z}O+eP8&^M5UA8 zltq9r?SnYXKmwi9D&;rD8-Tf$jH7cTC-eP1wSc}4zDN3f&+H&npw{?&IRK{Z?sq=> zdwoTcwRmR6BCuV@zcP!7`fWYt!m0KeGf^dS+&yLr4nX8Ddo|aE*T`D)fu!56E$?-` z6kG9RW?Rv>!0RYo+Ac}S@AQIFbnAX7C2?EpbERMy&aMTiapqaGD5VjgKn@_OxJbJ( z=}sbn_hjOD4zE5sE<^E{16vI|W?o?sPLDZpSF^|DUGE-qFO~jQN?Mdwd8BHu{00uC z;N9uDXe9Jv9%&@*9tIL68=DO#>SJpp1{1rO4?bwhvB0AHSD9~Kqol{tl)rB28|CG| z5eQe;pzok;;oW7#swJyQ-?Z6KWxGbEN_<~>=^+FX&E%~3kT>+2*exurhU^)^aEP@P zTSDICb{t^hUD|qEU8U=NNQ)j|Voi+4T%6^xm-AX^HyqH3-G7=z3zvduiC-^Dr~R7u zAA0rdb9`sPAt@zIXQs1&J-@5&)GfLj2dFijEjvBG74mEOp0Z>LD%zd1Eo)avmR`;G z2Zt?qIwyMXp3cmi0~^%Sxh4je?DtG95C;6MeCBzlv)lY$%Tv5H?pOTJwyo_pP5PeN zRNf&0&>{MD&qbmTi&abMq@@UpjWgtPqFU0AWppQr#EdFb&t{g`Qc<$baiyHF<2}-ZuI!Kd)=N6nu$QR8+wpJsf%>AUNv3ji z?Q!KEQS!(xfKMYe4z#luK9IzBfArLG0FOLoivQs4*zc8Nd!AyT(^ftvf`IcIHH*d~ zQ_-djTYs>FT$35~2^`X|d-lwb2JvLF0p>9$WfAgaoNT7iEM$DybT-A+`uve!s82pI zb>y%5T=X?P=9_x8@6YKmW6}YOG-k$|6N@}1=ZQV$-N=-;UiP@Ldc{g-An6T$G?^{y z4ZkHxU(5vN>9XIp^`d2=6uxfS{7SDC-Oa?=rLG$5#JZmvmoUQ+sGy%1da zIAsz*V+k3Jxa)60#82;?MSn7aI%x)fFVr=aI6KfR@Fv~jv+nnVc zfh`GB@@D+mcX2Y9BU*<<)xj%wKxg>`g?!KQ2@1jF?0deq^5rr=fgU+q@0=c39QUX( z-waRy58h*5*a_+}_j-_TnfI6(Y6Gz#I}xnKoe0fM*hwUK~LjRV_14y#sJtQh457{XY;vuov*F)kuPY;RC zi-*KTkscCb=Ngh%5PC?Q2kjy8jr5S1D)NvR^Yf6{5#%AWvA9^djY%;dPi026`nR>|vw^Y8@^i79puiDMHzB+mc#khrJVLt;720c5#p@L&wVQ;EA(J>(+KTtiOW z+UX%LifejE98%;V8#yT+5~s#_$mDT~wfe*mho=&U9(hO{gyJDFC8QzK15wQ$?oIPl zW<5x;5b?eMPbJQO@sPOM+e1E7edi%@X|#vLl#PePaf=!<>o%%y&%&MpPbCh~_K;W! z?IE!u)^)}3+KvNE zj3*pmVv@yU4s4t{z{F7<9`ixx-~baNrXDkOmN78D3I`4_aeMdyCe9P_m>ISR;g17M z%n5nSIN0SpN?%{OuFD*R)Nho^Ql_t!+YEPxiB#L(_l0v1G~e$F+Y}BkF_cG*a zzK8AQJPMiB_vlW?arHgA({x*Yk2)slJ>NS{XYrT=S4$sYVsPmI6T=}MGwVjm?@?4; z`8~?jEWbxQoZ5fSOnolDM;Uxv&Z9TQeAW6heLm$pT9_czJlZn?t9g`W_;Q<}<$15> z(SDAqdDPMo2k+5A@V6(F4yU&*UVT3vaC(pVqQ&Gf7bZ~J7B>}5-(yPP@CTqT+F|T>uz2b9Cw3MOC<7L~t(u9a6xNYi92Y-3LeK5=W?fc9!bWl%P zL}y$DctUJzV^0-kJ!U595S>@&V)E)pj~RFF+p@JCgE1TOe3WD2l)wWzvwx$U&PCQ;B+aosIV6zI z14!~?JtXd)J%A+D=^=3g*a0L}_UammIdOBh$9!>^pMTi1A_QztZ6zieLgKFJe1AC4 z&SPFLdR*36cr%DA^7j>=-*E_~KH_qaDSv>8Tg&Y=iq%Of$+IZSH$Xf!nVG)^=G*}! zK0|U8eUI;2e{#&{`;)KwlMhr$n#@tX5hpti(LD52HgaALASq1eAv3b`Tf^B|gL`2l zY0dqAI<1+oO3wDFi9IBJO;6^71LF@cd7!KuOw!*B4T8`4>c=vDU!aOTW(Jytj#9Q~ znk-4YmQIfO>5Iwf2ro$qPXUKKnV8M>`XdV`fJ2^4j2`Q+nU;&{uep8~dFnRskzHDp zG`Oubv$6mQZsoz(oT!bhMp~KP4FLsD=Y^KS0VW20G~2Ts0j_%fte)VEmZWE0J1#4= z^6(BFV3s>WSwBh6kkv@*p8I5#FIymq=h|h<9u#s3^vRR{BA#2(%#=A$NS;azCmcXh zpR|X>fv*RUcqO$W?j29=F>w)ym-g%uf=j8R+H1s|`M&6O=zLQ4Schx(4+b;MWk9Fq z(S!GLs{;27@oZ8LnOfBEqaQ$0N>FY<>1$$v{M2tcmjGKOE5^Pi_Pkia2JXI6gW zpb|^x$PUwbI`70jzNORCncCL!@7b{!)6*G8qnu7|H1TvMSzk`)EWbz5@c+X-TJ`tn zO5bDk_q?w9d$cP9%jwJtsp|W_H};m(Im+LoxWV=JDD|E7-;-mV`aQbd|KT3RMy}@j zo$h{+Pa9E6w=4QF)|el65>GMPzC3J?$$;X20R@eG7T}`T4_8o!7=)SbG_}?3?zlsEYnl^LISTZ zQR>a9&B9~WuVu>atm=Az4M{r53TNNhw{PKWn(HeCz2BI_%6sA#BuNLDymxWu_LZL7 zMjhC**RG#-plpCyCM79OO!ANzOSR&er-;P!01_kpxe<;(y^&7RWF}Sxm&iln>cK9{ zbjIk(zkT0zn`}<23eFThz{L3_Hpj7BYDkg}=tPs-V?Ov|9$;dV(g7w`${t|8#G_1J zlGpvYuvVvQqx(t08$2AZy`6i|Ilb=ofqPzDOujXO(x1;;y&@q6p12}m`{0huT?_)s zPFwORH6R|{9&~W8qh(S?iIb|=0y-zUuaBlP0t!NJEt{ETPr!H&*(pZpA*(B@Mpooe zWW`gN-H6|p$U|aVo`*zNOGB=NsfrJtm~^bbuK=>A5?yu=iD6l-is!=OG*2e>v3p4D zBD0VwJf?h!hy25)Yxz`Wza)haJ(+3b{uXv^c)VPHtI51DxbGpcok(AxtXQPJ1y5%7 z%X~A)Lt=)^L#8agno4Zp)>J0n2yti+iIFKUMK@+iJelZKd&o)8q(6B>r&^Plc05pU z+8E9hGBnz)YVWAvY-H-~*n+7)X2&iFPbKzCdMeTR^HgFbv!`;<{jpBk+i~KDhpc~o zGKd~-q-Re$dB2~Z9hX;eiA=O2{^*p$I~LYbSTbY3!OLsYLT`*1V2~|`Pk}wE;RDQ8 z&!GorI{D9ulde4^_R<`DO-|fJ(A*u$j75+nomPG)-u2dO@HqoiC<%N3I+Csa)=Ku# z*j*+0%~xzfNAuHFLe8&NbYVNiUk@#Lt>uZL*jzN1IXgcYD`4z{_s?$oS<5W za6y%)5-l1JiSyPpWW$Yt9ugOfc*vXFK@Zu;F!qqR@o8HS#t}~N1MRpe8^fPFjd;~c zIGrT$Mrso_D>o@Nr#UnxR&`khWg9L;D*VZLp0z&tQ(cCWW&$k3IXF3viS{Q)Pu)Xe zaiBl>%mS3+M=eDe<)S$;xUIit%9_9l@{kxV_YB&Dc#9d7OdDuTeexG8Jq}KeRlA-{ zjPGj56m)?Y`I9eBMeJQiRMdq`ZG;vsRviHB_E3bWO}yUB%= zvj^W@n@oOM%Lu$;U6g4I;pta`!RDu**0CVcA3c4wV8&?C?41fC56HyF{NQtzyFe`y zG(p}ynMo%CrsmMVSIu)Meadi$4vs#{mE3sAx$tBrISqH+e@>q3p}GEGlhDD@M|Ida zTTbf*>A@}`&!LQagnM~_iSa1UqHLzD_5jnU3U~eB=ooX?0za{6!jt)8X};&s`)?U= zt*x-@cE9b9gR^6;wk|@6nMAkU*2=VXk#u@UT$n=xIztq#nIQYXYekVA0G2YHFtpduPpQPakIq^X*{E#wx=^AF5!D>iBF^)-e4{9 z4P)BEx<0A0*iE0B&EFC6H^IQv#x>K=_S9_X}_Bhq_^ zvwSbxMUaVdq(k)UK1PphhS4n79m&Ort5Omv2 zybgLgw7>PFaGAcR{hWJ%^|z+;N6*ti*T`PYC&3l46t~89qLh_mK&Nh$dnQ^T`sfq4 z!d+T}Oq@h&{g`K>&!OMp?3p8X%YV&D_fo%adtxZu%lz5NW;RohZ0e)GxY@@;vU8v@ zvl|?~rdCPwhYf89m}t>?%!`)=+3z_M@+1dNVDv8w8rMkb&=+Gg(*Xf`CWFF-Co2Z$Gl+jGy!a%zG zpc|5+ik{3>-4s24N#nztq{+N~m^!jw^U9tVkfZ}LW8ZvBrzZ2lkfJB^n&cRIGO;Gp zlbOv^AV`|b8(m^gW=eZOkTjX8?S+$jGSlc5I=&1MO=iF8XNUSA#jw^IiPb< z*u!H+lt6bLU=A|g4=^*B^jjf&%!XTd_0`PcX?TM@ccH*f$+nF0@q4#oi_Jr^DleU<}ADkbrd=myF8 z@~Lvlkl{aSx>8*H&GG|GOk8*dq4#q@CYHV*VAi_chox%Be9P*`A{8ibgFKbo z)Mjn1T@(3zfp#d(*>9;U&J8K`^?4|VzLPVhu+>!Jv~GVT_YU=HGI55YC-cQcp>}jg z;wISCrJ0_h0T4}nDU z{Qj7l%>E)~0R3~94G z8PaC`+nWh65xg%G;XrY$dMhqnnM9`@*U{ec&WJ!(cSgi4q@awBN4;1ZWG4yj`E%u$ zGE;9L5~o$ii|acz;|4sEv(SKN6<`0ewTRddBiUkT^2P z4kMnuVRl86+3=P0WbPN}`v&bdPvsJO=K{0*pAIvYD_l$cImbo8GOsq{>xYi72#+Td zU5f)Uai5(h6X!Y|kXc^C)Kj7f4Dw_?Xlm+wZx4e&-u1Q2q$qfQHPf^A7O2z#&7MpZ zV0tp2@)&8%SBjB(GGCNUoBrz0s*V))iBE=3RrTzMgJ;MKQv7Ma)EwfOmj`5ya(gDh z4!A-GWR?%5=@Zvh9*|jHFW<8^JA(4{rh8L6E3Tuzzc96IzMV=S{VNoORQ+V6H<4sB ze|N^=i*YmmHF0j8|C+I8;OLsn#r0PDYpzZ%ftUA%Pn$nF4w%p!8mUGv=1?H%rXP@5 z{<3B17~S*(GP4e`R>=)s-giJIjtH}|IpX_Q%TYQdsz2sc9`D(^X~E{Q>L@c_$(YgX zx$bhoOovFwsC>{9o~WMsvg|0kUgDcI10 z8_;f=KTr8m&Y6|y&J`Vl-y!iZhre`x_gs;?geNks>roZJQM5ByI4eNyJ$e=ke zvA3hGY>v#mB6WeM!iGXk=7q+QeKGbJ zQMl+Hviw#?Y0|Cq-x7@@-Sn8GZ}n4|=>XMFWgsc(t66?yMAJi}KdD)s?H;6ut;&qQ z57)<2iNk39x5TYTw(#}2aj=y?_(OVK*NtZ$5k#3F@7U|D<$L##poLhQTa3(v($f(iMd8fwmo6HD>q!L3&o=UV3J(cC7Z&IvE z3dvJhK87synq(b%DlsvCX_jY1Yqel?nV37Y2(NF%N_t*MS{~5w>djqvO<9&7f2sRoj}`ni(>_@>ZV8@&eGbYLdC-sVtv| zpCMdiXnHHAV@;_R%-*T4#eYmr*jd9UlRH4xJ(Za9_TLgaIy{x-5!kFpA|KULi3Pu2 zvDf#frVMgN?@HC%D6gfR14GaLMH}VaF&W=S9+eiOft9cNN)Gg>Je634av<#JtaviZ zr|Har&WfipbA-OHq-Obp`3rx49vl?l$wdE0f6S+R!Sc?nfk)+qy}oUFZzim^4>AG< zoE6VR21qDB!G+NUD+1U-Qiz%=)j134VX{m#&a~D&HSY zYVlu_d&Lhh6Eyplcl|Xl>@`a9gA6*yXCZS_ms@3|4AnMht1FAj>3bf~i2*5{y?8rr zdGT~|r?3B>gLQn2JyqF}SRC0O2XtaiQ8ygLq#?JuYrXVLsyjNMv%Ea&jXwlx$+IX4 zA;8pHDXU( znZDAlnBROk)*ce`wEo~&`RXC-ZP@ig8`hJF6`%)@WFmN$<8!VdFRUrm2T#Zp41@zn z>?gIBdqzxBHLbQ|7I!*p260=m{+c(I?rA$_rM5qGd?`3jW+T(c+A-_KM3d(aHWB-S zm)F^4+Zbg){lV+=OzXx0!g}DuN>w%_7rh;m_V#?QQfaSW*uJuu6YivDdiE)TZugM* zsObyDoz4f4_*&=}sF!C(lEomF`;(XZ<|~0sxIS8ndiivfY!xJy`)|orJz9zeR*iT& zX5c1P&7eQ5l$Rl%%#R{vWhrDmjkf`2e!GJtjhgm6e`K9AoDpv1R%I5{(0U$Fpn;oL)`ks16{!zbr|L)$c3@mm^lZp4l{4a@~8ptruW|xBi9}>J57uA$l@xSKw@i+zdbl!T|>_5?Iv%w0hdP&(tk`bYy0+;57o%Qu{^@Fr+NoV zsI1<>vLVZ(2IX@)LM3+fdiGRTWQNM>ip)S_MW#P^^%n6^iAA2C$_&CQwl>o61gS$$ zB@RfWS4VsDcFmeswip%UAjJeAdx zE<wCG zzvU`74bl@_&7PdQnmr4573*)gswbOfpE6E1^;F(8o8bVm+%#C#jT-ru)r}f~#6}JO zEph#Xhs55G1IY4(!m4g3+1tp=O@q{Lmn%0M66@LXme(4r`ZB~-Uxv8K%Mh=;X2ow$ zAgL7Ia{MZvD3?O(@-oCL#lgk5Cy>>qK_IK623hD=olpp5bwVMPtktGLAgfJ-D@8EH zwFZH#EmSzbGL{jheu`nibis8+=304QfsFOTMh>GU=A$K*kjUN}3}yB$c{}J?0+3`u#mU=1N!AH>SOv zcghdS*&Z(gFg=;bbuXRktu_(wwMdXOnJx3=KsfE!Z0Q&T**t)xkcU=DsSl@T_~2`% zY74GV)Qd7fS}Zz{cm2Y(3st;*HTGs*I=VhN`Y%gEW|YJ?gFMqOo}rp3ZyF zRnN6`vUxvrFZESVu@Q*7r!rmU)l6@{`kUSc-E`0NT=eSC*^*@X{+ycWZBZb}>$uFm zgOl44;BV`bOeD{tp20rfpHpkO`rfq0y=mIuO#L|t()Q?`MtU$*-e#m%f%XfV$uyxo zZ3kc_*-bw232qAb9bk5h{^;*{V^ZvZPAqOez{Kp(0VY;?w5=q$*Vfych{SyA{ zD~%o1XJ5G9WZUKHkxPqw`D;8<1pqwK59hdYk-ooYYt}^=e;8VrgSZd+OiD;h>t!e8 ziI|$s)XIT9uT8s=!N$NOjrsh_%aQ^~ddYsx1ScuSp`|me6J*y7Ycf37AW8C=JSyzp zgbQ_zcAF}QXCh?sZf0O5MQ5!Fc?Q<#d&u$>Tk^8gc@x;!R#A{}7jZJ%1t zEu6uiF=u@R-TXrZosCz`bSg*TekI1OJ`N=1u(!jk^zppPU!t_8;7g>x=2bolCoS4! zBKog+qrC4I)p4j@l#0=JeKy=5qlL3!1M~rz^>?V@9XcQrZBG3)JGPp7GP$D4lga&& z(g$7$Zk)1(|k)k zZwGYZ@^O1mkwbt6Rd&T z5w@;T|(PVB=JLy~rLjK6W{e*mCf6zS!#PF?rUJ#vDJi7dwUz{M{nAHjLVDfl)|2^O8 z1bOIO)d})cVE-^duFsyRUAfKhCZb$@kKU|^s@8RhhLpz{;&PS88Qy^#emvhF%o%#j z1k}rU^x}#vPv^p!i5heLu-w99?%{OBK0>UJa+@L6e7ViA8dj$I@7b|9!eeeHwwgyz zb$?k}6({zW`Ll0DUw!t4Yl1DEd(LikoFSN46yxcW8K|5`3#%XX*^@%4wi&Mb!u`RX z&Kn2Hd(4JS)CZVRpvCtnbMLEj6IbThR>v8xZQ4}dqdR0)-=q7*PBYK<#Z$ZTUWqEE z1QmZ+#I za4okPQXNumGxQX^SMw-CPOEbh*ND?q?Zal`PI;VRhi$6w(TE9F&ZDfKsJ6Yw9xhh= zb|foPUC)sDTIDs6sS?2M39aYzIm_b=e;BN$>3pv88pvyhDy#3&6St%K9zCtR1~SvJ z%WEL7XO!1KUQc!^l=Eno*FZ*jme)XDPx{HLb=@B(Bk8-j!}HZVnsK$O?@_Ffa+@Kg zujMww?Bz9(SJn`f+YB?)8OwPz?{b@AzU4KL*IeZ_kijgkfy{oN@*2opNnCC-WJwrJ z+R}PyZ)~XcVc%X}19`n!k5+w;>W2hn^m6%-pp98x1DWaAI8D*ZQu&aean%nA3MLN; z(q~_Hc@5;=U07~2tX^INc`Y8w;lC%3rtp|gc@5;XOAo5;x|K9SwXVx%ylR^v$<6W_ z$ot1bFD>8i-(6kJ6iC7tyV>+ig>lae zm4y45Kby2^AkqBxkobD|FPaw#OkMihuR&AC?zgsds)fw})Gd|@!%C^mF9wp;bU1isj@u`k}XPzk9Oj|@u`k}x9lsa&X{NDYkBlLq3`nOcT2{n+LKLw0?ltN^U3&B zXUyBq_*CDcSl;C}LzYZbN54}CSswk)4ukUOca(g2^t+`{qTFUk#)sw-dznuQYjHNV zCF4_WGwh5{^*zeVQEoFN<5O-kB;!+VGbH0vU1isH#;2S|F_^0Dx@3H+Gv+NBpK_bw z4QO$uZ^tXk;|$68R7byCGCt)tLoz0RZ}0zh&T0Z8P*=nx)Ell+bUn&CoNvu-azmSJsmk+up$}p8(LaD6!gR$O~6K0iee_so#Lyu8G1_hs^bj7ES~_-uT?$)AoCQ;CjjhxaCMxaXXSZy zoT10`u8uPVuzUhQzq47W`aQb$visWZo}|jlCjewQSNQ~h>~bid0MOG9Ty8V8U-<-p zNN4#3fIJ-K699VSEq6Aq*s~a<+-7J=YggZ+BqPghhMkzHw(E9~x;PfpcfhV%*ClvS zZZpI=EVmi9QCrQU{lHiAXe+yF9)tkT{ECOt576XY&ZT9FTAJ&R&80E;x44U26KASq7iAu;`Y07;LAhD>O_nmxRo%TtLV z$^%G>B6~=5+7BSfMmm5bGuA_5M)LrYULX&NG5#H|SEkIvITKGNme0n>m2{?Dp5jTC z&OnlA9#Bc%kf*ZT*37UedL=!TXlp(h_M=2|cQAp6p~<|k!a}n=ZcxbhT19pMNpU%U za4gaCkm#u%K$c&h3yn-Kmsq0Y5010iG?i)o3>jZ?dF6Jw8+l`~uqTuA!J5j{E5ONz z#>5iwOEWzk3}CtXuZf*i{^Z#i_5C%qe&b0y2awgqaK@#Q7Ytc9q> zKKQ26TA4FDltCGJDsM`z>Tj8HmvSo8P4@jQ{lSwA{D!>r^-1~$PVOHIo_%#`Wt6Hh zpwmNQWXsDD)(&X~C3gc%*RjXh7nWir4dX0?fv<(9GgJP`&ps2w|Gq?8$IXYHpcHS& z@41&2!s~14e1CX!&7wU*4eq7Kyt9nun?)Y8WidrHW@-hi#WQ;l=~eehC!-)Uz7%#ZZqw`^vDlVmkNO!0LOHAbxp8c#3$*HrC&B-HWQbhShbM4M6sSwrf_4 zQvT-q0p=pUr+`+z9g9oX{Rib1&-=1;CZ`Na#F|ShMf;$WwT-+RzJTvjpB$SYZfk)p z9{iM3D5GwVYXOa{88pkix4lLH_~Q?bCddIKg;P8vI)n$1)P3tA)7AQ|HV+`l`q=-a zl=Tc%`6jdJYyM)bX_T~d^iSH2=R$;6__1IffjdVTb~zWGh*qc*U$)KiI5#ttCMHT%FiOHU<+_B}XrX#kpi||YwJ<(;(Cf32E zsDwXzCUJ(XUpMGqTuB{1A!m}#$0lu3$3_l|)o~f4M=yr{o>xGN?e^=!#uj@q14#*5 z4_O{8j3ZqgEW9oZ7W#wZ(i{(ovjYzx>H2s`oThaESzOvNt_$bOcq(z!u!qFnr~}Aq zKP}^ws)G`Ntd77%w{5lk^`!Z4i36H6WNbq4({y1&ifO4(ByWkdWUegND93h7ruC3ybNCz7F@BO$ zI14*tzCgzvFn!WR_YA`EL>}@bp6dkV6}J-P$bZd&NzVh!l=pvMb?pNswg-ZwWpiLZ zi`E@uklOT~+Q`D-?~m!poTxnVvE5D24oP5;Cv%Y)HCv~dDot|vx9RAPo_rN>$d)^g zD>^RU>+7}DpL1TsA#cge^7O@(K6enL12VDL*?-MWp$YwDq@R{fF3aX4N0TaP{WFxE zY7jf}PsWSkY;VsbK}+}2UiBA85okervvZ~RroZ)%B{zR+aZi&7STp)b&o;I4Z;3PG zJ;!lI zKRSRc55BJQim=T3rSeCu-O`L)F6!mwTi5OzE`HC_k6SM4Sb^{55;q|qK$7+5A#w1Y z?Iqk>YDl};m*UP|zv7o7kk!{G;{hqr;18ayKi}8qw${O&X*GapXUV1#4jZPm#c^Mw zT4#no#PkC)Us6X_wWleDY++Ak*bZFRWQObT0v(WflOyfP%!sq^J9I$iAal!;nNj=Y zWa2QPgQMe&Gkx?H{a$_amJY>lOiv~%WB)Z@DZo9eHbb&K_6Vt7k`%_J4;$;32^C-W(Pg?fFKzLhps|T z=YvD3G@TDSM4rxsb-@kx!jwJd^uXD}r6AL;IFtLZzV{%#J0p=u`_n7ZRI{5$-E4@4>ml7RdV$H?@<{$Fy_CX4d zh)G(3zR^pdl=a~=vw71|Y0W-iFn| zp3Ky*&6As~YI!$H_Ll7h_?iq}f-+b8|S{?16*EgiTK@aZN_1_XFs_8c^*BlP+ z*)z}wv{uZ6<&CV$4~eA;{@{xO2%5@lvCMD2tQZf8J683NQ5 zg*2T7RNG`#$&=Os5>ov|vq+2l0-N$q4*;gTJ)LQHf(z>D9F43xPiJHlo?}nv#0lV@ z&X;qbG4++Uj|wH#j#i@+dU*YGY61lDQZ_{Hr#J=fH~>q@R*qk2QS9M3n7lyr028a-Jm%yMKYfoTcV&6ZMUe}C_CNUUn$F~5%XQttK}!DY3#X)O z%$4ehYF(FLK)KDZQjJ;7qm@ahNw}5THVIczj??of?om09xRcw{nZZ=$JZkCNsOC|} zzCnNXjA|+85pRw1bY{9a@W`sqH85%DA#rYlhg`%U4VipB*mNEeLku3Wx>~21P_S?TOJah9}kILX&!P=TEj!) zoW%o3Dl+hp7~%GiSgPY8F?OmU6Fsap4LH~6sm$2hZ-dZ7V!X#gVxhE$#7KgNe8{-= zkm#d&NX)EzNStG(A$e4ehr~Im9uoIic}VQl_mH?L%0p&>PO;ipn7Z>+;_O2YiAf<3 ziPM%OWSSN*-EaU|Y#M}03}kyMu>#LSVtJE?>|`1wuO*Auvnh9Ap}9xBA9VY=te2a2 ziV5<~z9NMOm^e_u)=Z^P5VPMNGs_U*?6zhqvk&khdCUu2R`l6h77Rj!=laS1id5xX zbeZh^%$$9SWXpz)T{}d5c?XcBkv$})lszQ22p>S!vj;Z^T}`&B%tZAt8Dy1wcHK~N z&0ot0i;;AP(#-rj((zs=#Y6;WRUf|p24z|FThuSyLM#U*WpE76Pw|jAXv`|ko=XDh zB~K+fFCG%t;(0N;J2^xiv*A!9kJ+>9_S^KbNwAa%MuAjg4jla9>C8YHFh90#H3d_% zKR+~S>=KzMPK=W44G?quunSj9QydO@iM>HLZuDcUUK%$JbGAlEASnUrA+a^-0Fr7Q zJS4^sJtS_DJ%A+kc!O^AtT+NiXAQd1adV@;mLn^;zUlM^-QawNHt5ES4xvB%!gQ@R z=$;>XZ`KIe?*=?Z9uh+!R&nl=`GTj3wN32zf``~TxizV`Nmmbhe42ibrqfOFJ9p{ zi|ot=1Y@l{MF>mNnR~IH;L!1RY+>y;A(1-e+Ic6 zUX&g*l@2f$g#!H1F~gzFh4~}H)9!McD=qt=l)M6&lN=8HHPanRI!UYeiKElKASGl$ zI!T}Xtq<0u?}vglUU$A|$ZLtuaxaihuR7nCED&$e@eUZx_1H8Z@jD{w3?*J%;w3&E z(LkqHAPd#8l%zME0mOC5p$$pu*q%I?nBTC$-e6+QhP~^-jPm@pz5M5VDa3E@ddS4^ zk2U8qBMcX?9bjg@dGY7G`u<#BQB=*LiysY-iObCnz9wpTtv;?rCXI%?f5agB4(+rK zx&@j;DNKVm_yCf`-G5EoU*hHH#@$pNvti|={+bQLNgnbdSI~MISq^~9t*!A9O!PDk zIE2w8Eu0x?6c&8xVt@2Z$Orv?fSKV--*jq8>R5m4wcIX0t|k-XQ+pzpv9@>enhct) ztR?2Z`R|{Su^Tu)gA9Not$-jt<%-y*F#-)w{ZhV+*`(@yEKYt@;d z>p-WLq-=DoClfnSZ*6%k%ob?OG`Es#t=WEMf&u7{1I+SJ()BA3B?Xd%Q)}bv$H@YF z+0%|mdd@>)8KzcqX_Ll_sp-5L84I38Su#+pldh}Wd$}(3Ui9O3T`#H+tKrjLK{*Xi zXLbvNvEWtG-LS&XpM7BX!(-yJVPDMauI>j29`*zHd)dlMlisa9!1Owx6Q2#O<{EZr z9gvBYN!sF0K$b417S3!f1#PUqW|o$cMWe4}Z`4n8@HO$(@JC1YMW=4BbUDHuvelAt zSu^Mf{1<)pfw6rpoMVt}Y^&Gbgwe>u^nO9QG4r{;;xsyPd}XQ~u*ggN#K^H`(ZuO5 zT976t8@)E3SQdWpHL<$Sn@KMw-Sp>tZ%RS<&-rqgS4&b_G2taTfTWO$zn2TE`!ty= zfdx<>n(OO-FliQ>H1_P-4oCKfzC>|}$j|a*^0*(%q6B#=@P0#?76B2cHv_k{6}y zw1QjYFswUc`4c+{ zeFM)U?)-W5*%!tUFFA~SuTLglOW*dz!$3V|^-hDF9CsRct0tiZvOw~8RX2F2;R`VR z*Tj8Px<;M)Mv_p<$PR;#X0N@WGvbK3Zd*|~r76`Rzl=62yeAuaLk zYUCCjVB%t(oljA>s9h5S7FHi;I|LcCUOwX!!fp3_zwc@d(h{mk;N(j@wQtaFT*rLy zIWz40n@(-gwJ17Zk=AtWM@1n17RAW~7TM5OR)XNy^hZa9d;m!dy5w}gH~uvWynWfz zu|WY(&7qWgmCJjQxFGM_S$68UWBA7l{6OFY$&8gqZWbQ$bG}B)kzVA)= zjOD2oq=YJRv@cJ?tB+*vfkXOhuB60)Of5(Yr`mhSj$s9TEf-dROt}puQiSVzbvSyb ziAa*{+4D6?C0P~)l9aKICiQGjA7q$0m5)gL|CC%EiZe*}_h zCbgPNzOh_5|4_lMIh4>b+)G{B*%PEG7x>gNgCrf$i6yAoFX#;i-gp+_0A(+oQA%)$ zwA0#q0%_Hky<=Ug{+u!9K$5f}+cOLjZqWfImdfg*rxc)^Ljzw8|6=kqe=qUjI(BY%jC>vR>WNjr(Y>B~u(#E-JtJ!2X6ny5xp+=n z+_RBUqiwH@00GtMxt@N+dQ5bM{n1lh@cm%w0C#`uvqb&HxTIId*~tYg(gOctT+%~w zae?Og`carhhkkmtSHRcw99n}OOn-D-M}I)(OTjs9f5gEg{b403kmO?On99hMR?r_F zGmEL02mf9rT{ER6P`qow6Dxf0MI9x{!i-$y@y zMBmLSrA*d9SJ-1>J)Y-!?|63oJ^O>w>CcWEzqOJdDFw*czT$}b=;I<&_5hOfoKB2p z4=%mJ2bhbj1>K#N!IktD9bjTYOIu1Kqx?Y69bjT!M~l+L%dYQb*1y0j>|eKZPL^Y4 z@*H92MO8WW@n(GVxBk$dGqMR}`iuEax4r~lu#P!`NfL=)<_3mvpfKj z6>R%C{4%_BV&l0m<)}GyaYLfV#5r8{&3G;>=GEHc$*iMd?GZ@2=?7#^6eL@)@bGdG z-AVP_zfgLw{)3u)+Q3E}w&uanxjO`=h5b4I(N!LiI$!gGJ*pV=2JJ^q2$R zb&r`{lc3@~X0{`i^C)9QfJa)z$A$+Mc}4fuH&Q(>Hd6VcXW94n!|ox`UB7H8VutzC z#XP{oYEgak^g)0i9YB%^uY=}Kx~_ptFYhZY2E~H3CVA@zWMW>!a|j=e14xR(>yytP zHXa{fVm!qjeP+*9u|kRzQJmu7rD|k2x?D?J*y`>>e`?W;u`c)bQ`e&C{7dGVov?V5X>~n9gh{ zA`4N|nS?OqTCG}oQ`-nE(n|ilUb4MBnTzsxp3EClmEVtkDic9Ifw3E&Y>GK ztp{H->BjG`so%`ZPNKW+IaHn_O2Um^O#d}AU6TaK#t<`Gf}#osbdGv~Zy5RUl9Uyr z<=^uU)ihc>({xRA=I<*1@^Uqet^;`cBp1f>sPns_Wqz@w(R%2 z>G|HUo?F|=nI=T<(E%oACH&btR$uE{$CY6dk-tydM$2c%48j4O|AVgU|AVgUsO$W@ znUxOY7wdO(U;(z5&$I%S%TiW4z}dYGmWe{3=l$6;>I*PE-?OqA?BoMXwCfJejT!aj6qh6ECee5E7>5+&YKiTOR-4wM)J29x#4c}Ap% zL~}uZ%ydVP=JaIZt@MyDIoVqY8U>$PTx^8$ke#Y_?0ox>iMqq;xP-qjj;xQK^)2AK zYNj`~KIE&OlcT5QPmYC|ULR$E1sKQv!ARv>Sn%bzddz{wv7JbkI4ag)+W~LET;v#N zwm(?;X8W~PqNv+9`(lwN6Ps5&haNPy^<96ke$=15x)3@1sV+ngBo-ojG2-G;YrZEF zfunykgEFudl$;i$i6z6H%BTEJP7Ki;@P{oVYamUmJ=gq6j2GS@&7Z8?1jED5Qcj8t z^MePN*qP{$&I6CMf%Ib8mnRb=`v;I@%N#&bUUb(AI2U7~1*^$S#R4czJE>)5m>+pp zULP%-WN5?C$ue`OONQivnVQ*elk0#^d@`&gWhBIo3|3l(d&&gpVjGCf*Gy`#noNwx zX@TF{OX296K^Ha_=_ljjZV-QTZnLl|>B`+l*_oZ`vEjyD}PyapSw+ThGa@@l3(xOvcPj|bNT z>bT+c)GOl$m9ZA22ct6{60LV_dOTQa?IAJV;}4F7L$>hrg5k z22cHJ`tS{F&~*Mgb1TW*KET9x-7{&Rj=%Knyn_i^#1ooX7*O(YfQfM*FQE&kwQ9`v z!=gTqndk>R9v(A~2l3si<<>C%;pyyH6zwqwI+-5x!A5`sOl%(Xm=mo!kNM&Y?=crv z0BFqgYEWjwV{)L^W8Uaud(4KJ4UgG*w5+v6ddKELPv^j*3jH4KK9y?ynE(*wHawlY zcfo(ps3khP<@@;6>*SH}B)yxOPHvpk-*enNI!x2qu*S{P*)ag7>6EA;n#epnHp>D+_(b5BY=;{^Y9?D-SZ%IDKC-tE6< z$Rt_PbPgIn0xgfZFhQ&_Gh3L_?UqGx5Qs%Ofsh^0 zq&_{F$aNh}o_9?X|C1C!Q|Y8|DG@Q|9H$aKjrd$z3wY7i;|_x=%#4hosvL_+IkvHz9}7+ z(ljbjQ?rN6kj!c_GYSNlq{)0PiUj$unYAOpAy4Mo2G*B&dNOAkVZJdnnVB^J4Dw{Y zowSlBGyUPfAW!DH$>q>wu0{{BCNuqmlryws_LNG)vvELX#sbvJW>39v^%aV%MMM4c z*GwU9^%Y81lUyxL<~_(8_DpX#jls}l#=*{SO7&*?u4$5vCNuSul;+I#jqk(T?>SSP30mGC{oQ?k-*g^;M%4qTJ^b5o zHLi!u8p`scbBy1A&vh5?)_#8J8z%S7e$RYO^4<=P9#Y{R9e}P$kpO-8bR!pw{94&R zS}dPwM#jOq$*Z{FWY%hBuG=@I9`ycUHaEA|gl0o#Let-L?l0~z(?bgas>!@^-@nO} z>76GXw3vVxB} z;i-J;*@N97S}9Ql<`>91c$>Z;9xd&Kn!%t%h&B&_P4S_=ShaLt-Va)kdw| zB<>y(2dqq~Gh1@(V8U;+Og$Irh#_@!07-AUC$nc%&$rgpV$?AveLyBAh4t6$gH+rB zB;Cn_lV=0xH-qHBiRViB2ccZh6#`DyddV*>^<`rY94{ zQ@`uI6>qP|9^{7GD?FJIPT-IoJrF{p;^}HyudVaoaDR<>inPZ}7^(d1JPUSTGxfmr zg~DV_knzjEZ;fo<%s^6-$Ww{^(w<7ZM4n3Q#Pw7*Dx>mL;$(MEfNIh$q`f1A9_hK}>K%UM-K4M#Z(y4`W;QnKs%1G-q zX-$9j6igD2^x0>I6jguEh&((({(HVWvP8@0!Xb&8N6)X3X{;UL6k^hSw`>n2iIUt~ z67&6sRu%?qdcA7G;P^hd{3j=n?>&)4u|q7Cc6Cht18&u}VQ(Z{kbYo-_M zVA0o8q`zj`gh_LHOzda&kT@^SGd(LD!_}{^shQre)aQUq99f~iX2abBUKcl9JLt*8 z;S&C9_LR33Gd+bAAV&ve;*LQ5HG8UuzEAF%-f=FbClfe9FW;4 z@S(rvi$$DXy}#J{;K{_+G5TH=7S72#sXduIB+NeQNimWnS&cM1uC>#l!#U7rOF~=b7_(lL>Mk{*Z?boAi99B6 zjMI6NHYhsMH}+KGXkJexPGI*` z;?P%5Wx9B)Ilih5&Nnp=#dgA*8e=%P{+0u$;c1Q!%sP1eHZbfNuBt?GHJ| z2!*PhdFuxjUM~+U+%AKobD`~_d9;3+3HN=~J?4&6d}I2?!*wr8g8Rn9bjo3swY3me zO4~p!*&dpV4yF)|jrycxolbrLN&b+BT%X>Ns-;Fhr%OjpJ`Fs1I4?Agl>AxfoWe53E%`C2Yr8GZ_fzx4-A{|C@1 zqjY=d776_UB;8F9i4{}_kff0{Wc*BEkBq4#+la$2?If#U#$5WAc7JkQGH^g9mX7U& zk9vwS@PjyH+l}vQVj$6Dz8QV-%_18>zONT|j1H}h7xGAp(n7EB0FvT!9lWqKefGU*|)ChGvQI9;D_ ziK{>C^BYJqi~Yf~&FuS5dMa@=NDeOC|e4q@vEN6OlWkd8xGyS=U=?9QxW$GM3lB>v|W&_aoi#hP6G1pDu zD1C`mHl2LmOD~)YBXOGTE0MTwGIhEs0d0DObQ-7quqnqLJ%$I>9$Hr|kYpHoNL)m7 zc}#5lKfuJLidx=Vs?fkdI-oOm{afHK8#rqh4x934Pp>-A>B%gQM`ao~nXsNp3?5}T zk$l!$!x)NH@EJEvuBvBxOTyt>I6awIcc>L-n;0k7{7DDR_rVXSq+*u?{!|wp?ln&I zF?GJObxb(OV#bh};ThiyIv{h9$*IexGB%WQ1KpMqw82dZ8uLNzVYk{O_lvt@J?6Z~ zj9prmUMxdPxL<0Jo`Mgsx0h8Rdk|cH^A%0e+4O#+^8DABsl3+SF$iFv;mi)93%_4} zM`mVd0FU&A&qe`q-E>#M-FJ8FH{*3zLFO)D1)@${_B3jMTJ~Qw9Ti}N$U@#bZYzaA z?0p|U9OiTYNhY_44BNj2$wOix)&XQadpfyUS}@ZxN4Iic2BnflGXEg#p3dxD0;bze zg)D8u__o#XnfOR#dPsaQJtWSd(b}k`Kjr&UYDiwdh*a3e4NhX4a#Lb~m)m9Uy^AN;cn@1U3Moxjhmg&y`ISNiGZ2oId>1aOSjr+F}(`1jMT2r(bk*tL2^)`2gEJB$odBgJY+Ur*hE2 zmnL&Oq>Mf0gL9WW=8Kk`$IP}^@GUiFriYOF@R%1Wd5@VYC$P3XX4D6$IgiPK3XjR7 z^*!c9ufSubsG^)lD}x2V;NnxKKsiBr~1i!xpK^^D$U?Guadp5TL+qFvCbB(_x=>U=pPu;=$K8tD~bQkN(Gl=!kCzd-MK+@OL zVzkGne)C+Xo!<1IL6St5{Jb+$w}4K4_NaG~_gH4`Si`ptuLDdBs2yOU_vSHE(p!Fy8oF->bf&K4 z`*}aW#7fKqOmqo7W=99^02BL-?XrqH6E(@vJfIWXFg@nLmZAepbP5kJv3F2E9RnMH zw7Zo-0Q+cPMS0eb*|P<}TJmIO+zDW6GXF3p%lZfFxygm|WTvM1n?VO(6AR-#nb@#$ zK;}!4L{H`-an~W~HD8iV>lm%ckuQDp?BoF-TUYRBJZrr%oBcUC+m}YtQNKhN>L0fZ zA20u&D^r8M&#u|NaQe2E&V{b4e=gIES^qWBMD$0;&KeJiMyHKPrx4=8dnxG*COX(s zHa8?ixovndm{G^ySID0nJLCPy*<+W*x9RD{@(LUI3MMLe{WUMFW%iKxWY`I^IXTAw zJcsZZ(t?ynJ-_*SE$yqmN6662ra2S`3&_+b&on%EE4{d9LpXRtUXW5aSbp^Chb=tE zhs}l*S|Z#S=G9jy#TwP>z2PflU6&jkqbXY6vvaIkjvB_I4^F=DTI!>xqy(7mAu$wf zy^KuA#t}#UbEeM?j;?iaUvw??*Gvq)S~fFjp459jjLBuSAX0cnf6RdycK0sdb0VXCJ_0gXsZ@&#B8}Ug)8ir>)=EN~!9`k)DKjbl^Jb>-`4y6nLbe#8q zxklDjskHQm(b4VH!eHX8tOGjBQ=*}h-66~O>xauP>}?Muy=|Jx3m+mI?aG8BtRB-6 zpPCAa`S_z_P+#khiznx9`%%5?2~tqZXTSRnGb0;7&-t?t9G7foF(nd<4IA5za%X?A zS>@VZm;;@u-T!`w{XKd!bq+AK3VAOw5_Lr7N}hz`3Ytk-9}KVN0i8I+UB^GN3*dkF zp19Q8znUv6WWHs|>*S0&A|A;qfR>>zbdL_`T-#Rvj3U~{<4)`tWM0#mrcu1__IqZx z6{Uo=Ub=s{>BgTuwheqwecyLfmiTVF zo!HE-KW8R!!Bc!dCN7`%m|2Ed{y8(8IN$3_ed^DdaWdtflb2y?GE?LRC-)rcXe@a$ zaj>d26XU><9C<2nE04}-WndO*cz^Pj3W>H7RL(&rY*N-hf6Yu}0@3u4xB*mu%z-0n zJkJMi3G*k%73BWpXme^R6YB*N$wMYq^R3!-Ui41(7M>vOz1+_vYug{49rhf<-SY?c zF>5)>1W@>z`s5Q$Z4Zf21%Gff-aVD|Pw&L1S0`HUiSwQO$?=`^Uf_$~faZDp%4%VM zafY4OMsK5-&$ddO>Ui-9@-Jn&2CE;86@Tsf!8jlj=Y-i_(RMG?#9H7}G)FDh2bidm z4lp^KV8cjh#luJ4V=gj2{MoOI{PY7%9zm|pe&O!V13Dklo(GtymON%+l6e`v;t2*9zr_UkwqSJ()ZNmD(T`T6U<}2ouZw(T&45UMNMbA_sLAw zbdH#`a5WDwv$x~>iSwA*K?i1?$80$A$76P^$Ml#3H)DEC-umP*(-Be5qZh|Zcskd= z3al>^>;My|uxZTXnafL%_tJ%G9%Z~cnGF8yS)T@PvB&J#J?SwA_H%p8w8E70C}DXp z>pY#AJXp@77w1-ZI@ct(SYysa8LD}d1$Pww^mN|w>@c~c+tpJ(NiWhhM(&02ks_fO_K&zJ$i!GE%CfJo z#6&mNlZh*!56Hwsf+v%UfTsSM*stcv#2o~=x{l{bOoWUtlh$U6dx}x%*|ha(!Ng}% ze@z}X;brsULE8FS^2`N&^cw>L{^&Q(oAhMje4+y~%ip)2wZ)Xtw(oFC?s2?|#~htf zn=(|FE#2iETbVn69a}b=A53J?0VZmA8&1t?Wt{yp^fh94t6M{9Ck(+%v<(OGu_uYA z|DFr0BkY>Ley^lYzTZrnkqPFcaH?$r3nqqvv?!%FAiw!C7c`lfEkh9oxr?x;CWg#- zd-6S?3H;%MlVi2CKRJe~4#=$DixLKvn{#_W1O%#V{;{WLoSb3p47RjDf#%e*c}>cj z*mu2M7*6w$xTwh=9E0Z?GTmgL-1Wh4OqF>mamts6#NhD(WVss7HUm(@o=Qx$dyZr9 z)KiJM=6`RV^8QvkT@#+0Fn~78gk%xFB^w!qyCK?^>1W)$nvqi+#mlf(}r0MiEpH5502~9 zYGdGo=D#I6=AOzyeYc)U3`Kb=F?w(SNjZ8CnJoj=qK+XrPbDU5HDsRgYPIoT(8N=T zllDAhLgU38&vZ2SmYzz?SJ{%wo(T3%O?~SiT36RNVgD%A-m`gevQI^v7W~Y?w^Y!h#OmEUMW)a1`?aB$?Qn>jR6+ zJ(V~{))fB#yN{_?nnPKfuHZ zrCN|49Ga}}`BNTe?+?b={lRe&kAW%z?9lJ?4X^hkt_NSAw*A z%oh{1OMlOW122{>2Yi0$`rjTC2OsDN+LJlSq>8QLd=lvczUw#r$vi8-^kia9!fgk~ zM1kD&v}rn%Mu(&8YxF$W4D3Zd*Bzcd|+V&6)x<~qMzF2wb@8*lf;-%?aIDmW`D#}=V+1Eb6oRkya z27sb-<$VXfPkZ)MveE;;^U;pZjNAu9#ABuj3m(ptSIGK`alJosyACiro!&n2BMs{m zmDiYe76g(sNzRY^!Xg-LHY9j~)ty!~1rztXZxw6Ae%uWUOziU!OdP^wVa;qfs)PO zFYVP9k(pGL$`?7k2m_U~-A3K6}bjNikWO zPwfR^`bfjm%7dWeNkJu8-=0YsRti?b0VY9ad6S}A)XMfEr8bJYc;ND3xv-N9Sw^vB#@%r}2zUrW9v zMk#f4Wk$h)*7Rheb!-j9nFeJt5M^0Rz9x_S)wV~r;D9>vc0y`?>Fl0P%sn5_IY^QY zFmasj0VdZR`0vT{A~Yr!+W51-JiW)$*)Uq;F?qU!$HZO)J7Z`>lFH2w-uGpzAIDr5 z1wpiZxT+hZLM1jxc?NM}uj_|np=oTtX8I8D-LPiTo8_ovAljoxB~gx8vnV%+YFBhn zCBri4Ewc7pATj)*S#+TdZ>xRBd&PhGwma>h{9snk>)nv#YuILqU@mfryma0vv4PKN zt=T-n82zwDcj}eMLe@&@4@IQ@=vZWO>7(xz7QiB{=o%IRX;hIv}Sc`6b_BVmF9PO)KX^Vvlq`eLM7QI4FNEY5<|2fkk1DO8o9qUpxi_)q~Z;`&4 zNsN<=t=Z0HK(?D@?9M%4k^Y=1)q>ACv_eiL43L>WyGz6yVKwB#Dqb`Fxu`DFGyUll zn)Dn>LJK&g1!-b9dfSkW>&c13z4Vyxg)h5idn~2==Ihz;>Npukz_f!2)4wzE?D}O- zYym_`XJFp-KUhi&EhYawSLQJQ-}U!gldik|o|*ejJhBy^XGJzB{yqES12V2+`o-t@}D}j!HB-*)y z?O(5kmdzVWknJ11ZY-elR5lVMPbJPJ^i*>0NnfEGW1XJNq;S8b$W9-PwAYs=tqk)3 zI<<07bq+w$Pa!)0?fF5#@ zZFK9P{^A+>w|y&9>4bT3>j(uC_uN@uHJA^5QER~lbCMxx3;pG|_-mBJAXo}slfZpWms zzO@yCi6)J01PCVYPLR=*VEzvpBvUcK>hyf?7e#%%rt4gUslR6yn}GjfXN#xwgNqww z7B8!?Fv{ug(LhyqH%;h^#8WFwc{Sl89e^%O ziKrz;OYZ1(e2PWxm|2{KUUebOqr%@WF5IS(3-b>Rq>555T^N_ zUE`pV4oG0j_T(=f4D`)#k#pt8+ zY=8quicNY*9MW|^!;ZrT{FUAuz&r@$*{i>~Bxh2B`7W~0+oSApl5}E;)+p@t- zIqK#2d|@xM|C*y**jK#?mmZaJVXrsg7MgGel9{c9-!IUCWMYuZiczMUR||U}De>T` z#LmV8$ZCHj(*Uc5J&@I!y{D1}1k-;@Y^m^&y*g^tf7r_EsT>qFI)J1Iv4<>o15%Jg zZh(#;^dFD8&0C^8)PCgxeQRO;H7{Hj=pnH?%A=%fS&KskT`g87ehTqp*8(aOxx|v~9Hreonx6-En`X4q< z+Q43KSRgqyojj7nV-EBMGVRK~8Sh2msPy<+(3L&NAfY>pt6sMVJ&Du55pNE(VJ*@& zNgZa#rf7ZkOyU7E)Be(W zdAWW$lJG_a;_2i)WF8ZD>mHmPhvsq`@RXMF#->Of3<7??5@mhLFw2Ji&ikU!x@&n9l`1zKj156Gq z*qfdrV2Yf2I(OCT_u2Dll;e^Hv~tDyv_>w$zquuj(2gx=+Pi)Rb}-w$LC?cwVjgpr z2lk&#;sv+O`oMuChsZ;g2lk(=&w)GSsl;ZS14w$=JY+_5ek+dyNO~+iWJ*1%sVuL) zN_>K3=AIi>bhT!4FK1mu%`*mKtEZU0aOf3#XkPaZR zh0S^x+3ri?X;~CIruq?@7uwjmA#h$iOHm*F#-x}Y3YMAe6gRYLZe{{4$fngFfu!iO zPOGOAl1{F#&|N(SFS$h=gQqp;OydMF$bZe2Dur*OSnEwr)N46vxP{l>pvFD5`7$b! zFcX~s7emh^$l`kP*F4u#?~+UM70=f!O3fh%lGdA<#0rphE7&tTzHC~1bTm2r$HYja zhs41^{$pk@Cy0^$m;<{&z23}nY>*>6wQ8n;04}<%@d+eVlWU$2>~rv{V_<2Q9uG4I zzQ3O7X?ljBhc=K>?*RD$e}&TH0fMBt{zM^tD|gTJgq{KO;OJPh?2nGMcV3VthPt*? zI6EQcAqeLIChiT^rT~GCV^R$B`>Cd@vs)-)OxL0x(lex>v>8{%jyyTZDj%L4RAW0>4U3<5( zA3B75MYpvlyfU{NSfnR`uLmca9MFkmjQH0bvgY0<7&7%tduc){5WL zLdlf1=5a7_eZ&D~>MG!I(--~Dtb%XM?K-$S)EcErq~STYiUTsW+HAOX+IrU^lXpbl zKWWI%>&4;xHi{a|EZq9$yWKGtOibrJRz6b^POht!rIZY!zv0Pz(SNg;sq~^yjaHu# zKC(Zw`n)rD3Ty@I7bW6}cG3YR7ED?llCD#7wLBz-d#%9Vnc@Wu@{rY4ojEmDl~~Jb zzw5=X#+_I@KzhOC5H8kBMDgp33TsMySM$hNiM%_0$0*WkfwB)*2r`lK1N&BSyu_C>v8qKKXXtw> zQ_NURWjc4uA|4>;y=s%E{ z@b(9awS~%=N04UFZ%o+{xgqJh4eD zB7~Vq2VS4fEj+lQYI}u}%tfB0kCdf{FLZoGuYFuNffK;AB@_3a@bFD${_MVH%GZEO zf7Q7rP7Bh+P_x~Yk?9T?9`)(Y7pJ3Yd4F*vkeyze?our5(1NtGfa6;>{S{ichd^H; zUYd8wUZH$VOeA_iTG)qT+hC(SVkLdE$O>m5tDWhDhUr!JRC0Zgt&xc)rg*b`)LUGB zh@a>y)bg+qrv99NsMWM4=N>ZzblR&PNaT=a5m&ES#rYp?=aOtW&s*8Kcmzi;it;#W z1{H3W?S`vSv#+iE`&zje`^)Z)vl9?N5XAF{%L#6m7SN7OfjWPD@C+<%{4cy0tOQm$0|HwWd@DR1_%oKI-X!Nad;r1FkDKxXX(53O3G`L1c z^FDCmj(0!?hP<@YZ=6@{$;_}&P|jU{&Ko;cz1TBDKJLI*q{6G`#MS}L`ovaHE%kZO zQ^T92i4RO~I_F(~zf81Af0o>;i~U`H4Ia0S&7HsO&->O+eKIrNl5&h%MwvH6yxRy> z^0oBPvX6~G(#yaeqU>xYGiQ(bx#9F;FY^rxki5)Orwh7i-&yB|g*aN~8(O5d!rYzo z9XI283GEzG(PU!Fl@3LpJ1*a}&w{s@0QBg+p`CANuyawsvz-nm4{L{MSt4vh5)xR1T-o+oMb=2Tc7KxG|68&rm8U zqA6biBpsAG?{v6-V`}A`*!H>rNmr$Z#3@w^kmO@)HOf>JI6w=KG|j;?Ua!(VXT3^0 zkoD)vtXFAg(mOp@yu{Ikv&&@@9>>zA*KKr9=?C+b+Q-gtKX{#MWq&w~uNlXr>cYpw z6sZ50xQ5<;OpKFS$V}>?JnaHx`;xrgscGGNH<0a1GAVC5KDOfS%I=nY|1T%TLt_1+ zmpG2P@{k$){LT0RB;6Gr68+W%$o}c655BqjgKzRWrPJfTCDyCz+R|%7PuRZ9<8M&V zNT))s4JU@_*Uyy^J#8zTp)zpH-(qX!7+w2C1={+}dnLUB4?mB2V7H7ewhQNIHf;g$ zmFWW@_66Q?ew04!aj`*_79goG&O>4Y&H`jRK73_51c=;IS+B_tmF@WOm0VRg`|`JR zt;lr_v`7AHVg>yIWZfZto$T+gsj1A45fV@|*IgJ{i%FO^if~;Qg->*%JCKB_U5~5( zqU5CmTId6V?KY2^5?wl!y2$PtJg(EzSuf_fQc&AImE)pQsWo%dN8nroi>SRLGwO3& zuEEVB+Qjje34JItfB~$g4Vh(@MLXCYNa~I9jAO7}PaC{$+{)z5(OsVuk(PnFk9}j= zycW>Ab+GJqOsvHBRQ6xfS*+TA0?o_`Z-2{->#0Lh4TcxbL1oShkd!#rorPD1o3&qR zNrlw4sGeBLrgXY~ynHaRv;awSvOVOi+u(`WFHhyux52oeL{phLe(lo}zT2ng;VmjU zNSfI)b5-MZd6 z$nv)OA@9F;c>;|6m{~{Cb}<9lb}=(8t!;w?NiL@Umi0$@B7|)lJbw5n_l(yo;4;jv zZG!_zRSmitYW#2n=&%9t#9N6@8!j5zxCA%a`?XarAcgm&nx1oB)@R+fkym;2`7=+Y zKWDlp>8Y=I&w2{Ddu>EKLH2gKbL@Ce>a5>5&=S8jzCgLhd)Bs zB&loPBg==tzUxyN4;F4q-LW(V`i5RNGf5Zd)LFVWmk5|zLL)iP@1uU&N~>{W{N5{P zrZNNTx)5;OC*|pM!Qz-WT|;a9#2Ad%q=Wk9DMwV1p#B>?rc@%GLFojThcPk}r{ z>u%q_dcq;&*C`^WspLsV+Q26dMv*Cf*x$PiTzLH;N(l;ucD*8PlVUX1e%xE#n@ju| zJsPb^`$fr0uSuE61ZGZ;8%&!#yWsmwaadp~%uYfXCMCw;$KZ;LsTw*`x&+eI?|hA^#!-YQs7 zqy*s%VkkK8aIo}UzWC|DRrcA_`&ZLLLxqF`Ri*6tfnL?6p zkuN~fGhLg^L=%8Y?IC1dC^&rfdWG#G5 zPv%KCuMQc`6RU>&%g+er*hVx0pp=(fT!}QhdJ)dt^D@iG?gjvXd8~?J;8A3u=vaawU3DooX#!H zl)=_NCl*<1*C^G`QIxL;oDW1LZvmJQpmUAxhjepj<34fXpm(t+uWqxsrI~;xd`>T- zj0EXp@;U%3_jHY*Gh=IjQxZuLNc}yZA3g_k`M|Sbj95SWlMkWeZY@Y4>1amN)M67DEeYua95|l~e`msZ9Ig_uaMt*^X;IJ63{v zD(k`VXUCV&WwU?Jj$_z#N=@ zPbStnYt6iGig9UUbmNLf4_RLe{oFWpLx0OueztY}E&TlUV*aGUoo2=zhGTwe2|Z{u z{|xCigywVN9%p-11``W0Y)?lpu_w&h;%t({k<9i=4<^rQk}gs(Q)ljkuItBH z*YyL3%;*!DxCCgCyfE@DacqsZZwKaCJm)y@>(H1dE_Slv_P7anRW4xS+6LwzDiR zWI0%xhNyOy<%OhYhBk7UxB&;qLt>UidkHD==*D{TE!!!PKw?V7f6Id^Cp;wf^e;e` zGrswj?Y74klG+|UU#a3}MSETF_1ZIWrgX+ra5dZTq!*KJzuP=hJqH#Oq+cLrZAe z`!|Et6^)0I}zsa;lF7ly(%!1T0Z?nL9Oy@W2_Ws@W_Oiy5py04) zEuej)2fF{5JC-^4kBLJzVgpq;H-+QGxrf9d8=i42@6e`W$Kj2yuj4*uIy%55UVtPw z&O_D%TwA7VhK#CdKk5Ol?Z6gIf6C)=fylkfm2yq^nmU`h9k^;i8_fg9aOv1YTm*U! zEMRhHp*}-reU3v`5Z7ZU+sQE$&3Y!klE&*ROMkLUy#Z%dCn9n=4-7p_WY?$|qKlHTHbrai- zYb&&cOBr?h_#{f)K0cWq+&(^cyCrIF>1(Jne%8J0)MdAA@ZD~S%D2SG#KQ5xG8tWV zw8fQyuepGU!ys*+Z>E%{EdBeM^qA>A0e!!6YMqCWP(EPh&k{1$nR^T$-Xlwr%kKme{rR5<649c~1 zAy0y~e3S26J!cb0atXD_H*90^kT^zX0kUp`6UT;!pQjSHV|hrdHNyR)hloIENO`9RgLg_OSU0#-mA`p>}iF9yW9&X zDbGG8mW}JATDEBPMT7xtZQ`;e8NQ~6#40A6vUt@9sLY?8?bzG1RA=fhFvej+G5di- z2K@;-`tN|uJ#D)PS$P36*P59QQi#8K$o@MZne(=7&$}GNqmSf)rCZ))o*U&s>}rlk z=b&hezt&E6;`H}Sr+Ad_%Sl-Hp6NgM#`I+3U|L&iwWr<}sI+;%K$7FG$AIh?)>?T1 zU0B9s*TB#H!cHT*ICSm+&Iwq1xR`d z=|gnmj13Qo19?5;*}e2_<2+=25XgSl2Z8Kqb*<|qjvMgb62~PkK+=uwA^YKuxSDnG z)W9RFzhj9ZLv=S1xm21cS$RnMMu|1YY)EzLjgf@=pdQ5Kmv@@QL zRE2@z^a}sx<-aYbb={Aol0iB3Q}swo6tJ!(lz29f=^=3lwSM?#d?7v8G?@pc`gNrE zh>O(zn#b0TZXQQ6Y~R}MKW2Le`nwgHl--~61B+BW=h#f?A@TZM&`b`OYD;|Z%SB@* zSqUe|^PbJ!fT=}vCcIfbLT3z89kT8fp9guxx_tULF#@aQlNfnhQlVL;FNtXFExITqpU%{##87tklEnXK0dfRR8u){HKTr~jm$dwW?cI)*#r)dp7H)GVDw)B*#r*HXwNvl z0u~_q60c{#QiVYV(?_C`?rk6P(O$w6Yl%yEyvVVUP)7>KBzMr8BAko207<&;pHtaa z9szu%8MJ)vKkIPHkag$n#!UsD@x}OIR%%tig z^x*J5&p0kpT!5qt!!wS~>jGq7iEvJ||CVPx@c5h*c=YK29>J_P>g8KvKHdub%px>+ zSH0Jsx_&eDg=#9bn{dX!0iCCPOrM!WOqiB+p2uqy{>)T_{HA$bq^yG!$y15Km5k|Fj~V&R&u7&teao8-x?M{>_(YeGiXZqy^W z=T?v8CMAnkg*EHx@r9R~mUv8XTRdqMFTVn^K#^X(p7DAl_uSDL_Ed7Onhi@Nv0uN? z_IioPnTx!xnDyZBxz~fkfo#7l0$IP%lHRV12jk8D_+W410%W`VAZ0P_{AnQR*7g2I zit5^qaOyqV7g~xW+KPFk@x1K9WV1AcakXL|XZ;zOTAR9fuKF|bNH)4H9^8cN#gnAc zH^R_9LO_X-^Q2aThA-_RMz1FGq%#5c6} z-!6QfE(i!m?AhTT=Y{JsJ!Jpkcl95BSO4L6^&fuO5JSqYwSAz2t*5o01ILSd%H&NT(N*45p@XtG}kNt^S(6HhfKMr!Wt6@{Ih)#Mkr!B;7t95@+WuK;p0$ zo05L_d4`U!B9R4|*PqkZR)0>XnVDQIFCfgL>X%vu3%&yQ6p*dYy!LuaOd!cjJZw>9(gJ;n!Nx?&ZalUC*GFY$R%6~nSQP8Cr(gJJkgor zjD({Yq>b%eXT3xyko9NKg<&|YnRy50H(yt}wwdwcNIu$2$h`)bp7Vp=l!wQ>@mhQ1 zKu+JsL!i1V=E|~a5W7vUj!h0TfjNG?&?)s?TXpwgPa=CFil*i193gBH^&J3Fa z`|huyd1BwNzK13{#tWbGLGMu0`QYqJPiL0hgQfGQ{TXy)YD@RvMui2|aT|>%Gp&!` z2E;;+G(N&1T7Ybae8w*Uv^L}Qg%=rf)K<(ul0CAmnd65+z6D6~w7nAHY#wXh^1z_1 zh=;7NlE`2yI*^{qLGGr9tnYn@QK!@6shku#^N>%wfplaV1h_`JpM4|@nIrf05Yi`d zt5+k8jjIvl^CFP-D{`xM42-SbF%YX!zaq177ZlSg5q1nLK++ZIA?r;DBTIbS9?Vv6 zLKqvC^60$4;F0?JnU*1lb@R6G?S`n4X*ccjlcB!t7r>550eyb1}8k7_m7;| zThp0r5O_&m=d)`HbD9!!hsJNQ9gL66nC6PJd2-D-T!5W4YJ>XX~kcY6&b zdrK~j*3S9EszdE|&NP~Wh_p+Sg);PX^}KIv>8#4<(m*=x9XvOD7A^38)t_&3!!}MY z_oVL0mDOi6^^BySTJFi*6P;S_`$>u1&3Z~14TRxtk2#TdjrkY7haQuMaYQfF?LM>R zD{}n`1-zL*hndNdpq~qvlXS^rUI&F%^b;n|5?${eGsRipfxTzK$>>g>^|#zTotd!( za`$x3NuerFXUg?~cTMNRrSOM6?^$t1cd_O@3&~LK_U?ERN(CF@A#tLQwMx&9)9*ZF zef?e@2WXGwQGa$EXX_cq?s9*E4h#j{n$82~Q}`2f@(xS;GRiu(_j`Ta!ukZAm>;%P zKua(>VsE!xreA*yg9{ocOl% zbf!Fm>PRe|TlP?ZDs59fte@?`@_J3@!4D#>pK1PJ=I!CkW_wC3Yvyya=Qp2@l4d?r zv8k`Z(iupKD|n^fc@%=C^DpKW`0sgQA&I8*#CF+*@0lhth}390(=~}k#Ga$Hl$7HD zPa1S6q2a&hk-!%)Z@=fUCG*lg?^y&*(FIK>FY#UYo)^A{ciU9*9N8`w?!GLjjCcm} zCLt|AQeH!gXkz!VrxI_YL&nXYieKWE~y`OTMVzL&o# z#!7`K_DsIX6p6`p&hmb8A+M)1bG%8Fv@WFpk&LIUC3&&~fV?GJOOlb>+y`NUKnbYP zlS|9}8g#dN$eZ$m3y|b4$h^*TCf6D=z7G2WB>5kn@!T5URC-8^BrZVGZK=QIJKFb~ z@de0oNky(T9N?|LWhPZZfX+kW9kc*RUV?Qz@@PZDZZFD#(GSl!-n|Qu^)o*3*&-{J zqw2UK$U|~Ll6|Yj(Zsia_P1^+wDOk<(+kgXO>BRCe0*@aWVL>ay1ChmKt(FMMzm-~$mOE33W zd3gU0&HG;z;^k&h-}7DZLN}bfj>ZqSAb3c;H1!QPvH>1c$)3!}oZi6p@gGR?5dFu* zHY^Rf{U}7C8Q*?XjAnP8JX!fc6^J^no3O`w$$s5#UNsYd1|M+&69@g;y7hcdo*-gx z%q)Q*hwhCfJ1du|4J*RdY@);KWN=IJ~zN8t7I;J#S> zJrCZesC6k0GF(O4BBybzuAV1WwCWo(DJ-ybT0kcndH*r5_M3eqj{_q2jANwJ-e#vxBl#%|Pxir9j z_?u|p`^DdwW1@`odA~8^=5Ne&64l1v7ntEvOPof z8Odva?etXQv}6rAfAqGF;yQ^>tY2P$#Mg^1JxtXl6`5xQon$_mNpIoTVyO>$pIq1H zA?YG|tdLURM4<&8-@gZHy#Jgxc7W`|mMcW(DW|oc){W1wLex;L_H*1wsaE@${wy$d zT23*aWajPZ3?%srTJ6&tPPquJ_W782l&lp=T{O|@)jngB$+7Wj|2!B;bzaEZ1@R*< z#GUvTl0yL=6N{eS9F@2|UOI6jrkwfmV)E7Lu8&}D7@^cs-?F9!g2*mN_mY`)hToW8 zM1L`k*wdNLif=l-*mo>~aaJjxGs}sAOm}O(kXQtx&t-NKhqKRYgci_#V3oN&>X{l0 z4jfvs%LkK=uPfo~X4V`5nfbGYB-hKI$pgax`fDB-m(^;N`OBb2 zGT@nWo+>iJ)aED^!f=AT(0Rs@i_eAitf~bvWvutb6};22W0Z&uz!X1&?{)+%?bpi6gi?W_H-sb&0Dc{rBX_ znx6Lzr>XOv0lIBlw>{VpuX*1SnQZg^mM9VL)`nzA3EB{A=l27%qt>fQdHCzFeLXO( zzpx)?+p7sAy)QlEIK$5~j_!h|5_^~zASuM_8ONelPbHc-P34J2t(r=%%JPutBYDPg zd5WhJ7Xf%kj3;=;v6k0E;>cvrIC^mlkQ6rbjN=eyIko@(?HASnXfo57mEU~bXZmAi zH3xVc3y^gioOUN*d_g`~6a9wz)!QnS4HSg+kbUo9pm(5U&T}d~4@UsNfuB2N8X$X*xdrr_P8(CWGeH=%NoO!q$V>%Po=i*!>w}cblddH% zq5Z*TZq56_vrlYzDq~;B4b!2y`${*&w|4sPIk45wV`heK{bXhU3Y<*;J)dlehwrK7 z{@}83{XOT8XNy=mlPsYZlK!4^=ViC{Y|ePLZC#ot4}{R)GtM38(jkY7q>MdldEvl& z(AZD9kgNy(90#?td&rZ*`yLX_r-vM*ogNZhOSu>~430*9;DLt?PPLt+K5 zhr}^<9ug;`dq^DZZ1FD3QG-BkW!E5(I4n_r%N^(8ddO^aESumR3-vseIDOGW z-ZTKmL*h6gTMd(|2XEa>o{0oaWpdt9H~E+gsF@|+Hk?jCCa*5C=P2vRNkE>=y&aQ?bA&O81v2ZlGX+pILCcewHsAIU%A6v2 z_AZdw4vBBsa{pEeeg#N9nP=T~KTdSr7s$j*L!a~$2U&VDc>$It^TLem0-5c|(Uw^o zbgO$Zxnf#>&GZu0k5C49hK{desmaWP4Q!nMns+;Ku^l%iEN>oZyV>y zOpO&tNPo=@(@P6v;wmvs=8n?>Jee6m021V^d}>rvSAz$mOI zGYh5KN9e?+l?5`}#dX_xV!X$bdDWAEXU4XGfELKaCQ5zM)7uV_SWo6?*LEk`gSFiY zWVUNiwli}g+Tn!ruE)yH8{<9xYtD9SQHJ1Pyk~*Tb_rz2#CVS<^Qot5vj>M#wF_io z2evjy55{{mnb)sffgf)ZEASV{Y*z|}OpNzzvhndo&_@N3H9s1c#kLZX!jq#tF%c#o=hG=uZ4bMyk~*TdOg<_cP6ZT zg-kt}S+v?dLQzhzaSLR&+w`{U!g!A-bF|Be-^3~jXn{;Dd(cN{V7$kZd1IHjuFkk7 zDyPTHh%-2s8Z$$#smf;o6WeY)W(KW6YRF^m7}EEcSw~-&(TR18c1F#XOdDkcJ!Y0F zgN^s!^TtP($ILSrE{+9EEJyN~4^CXrn0M9$wq=wtY*hK6b?M&mwc#<3zD>^6fi_u= zo!o9-bRQ9_vcCJ;sJ?3flIACQ$epqz3y_q4@Q^9$`*x2PAnA5{BfwJR7g^);x+Q3~ z0MqqmJ-QjqgwMIz6O^DN-EMMhYqsiOL}h<+t0);|6$;%%c3<8$PYi%)-mf1$2(@~~ zoudfV0%nTazE7rSJu%sDNUxo|?n@t{3-?2MMM~NUSodEO7ax0}56rSIVB#P@&H6|- zxUEP$_*g5_z?xvMNCW5Y`L8*tFvkl$6#(#bTfppJL>Y1quNQBT?vp;JR-_yEyLm;r zardHDq?>PG>v_$I%@kgdLMC`gn)SI;^@CTWS?}VU6Qdtqkuqwg{x$gq_KNgS%FQcM zE_JYST9G&|=@se0RUX>!{;LrGDxno(dSI+2r zoz4R@m|8oJ4gId%Q!3P#Iq?*d)aD~Cr(ig}gi@RX67pXY8x_2A9+(koIV zdqozj40NH+#f z7le+ZK0Ic|bc2=CtiMGC-(S-!Qie8zgtQ_}EbQ}&G_hjee@(uD^)-~l3*8wW^P#AZ zSI$HgKuQc{W35vM+!s?b4nM1O?~pe(GQzSmmX8Poo>@rExu2|DN^NL1rrQ>p;_)*@E@&c?1+}h^O=HpQB^+&(SgQ9BJO8 z@?huBd~bIbr~d_HWcwg8;s?*B$4txuc=wq1Mo}e?na5G&`qkgLfQjebV`fMgoOjy; zvTwhed_|9$=1GwIzR4`%zHzT`{!ev|wi9Q=+2fv>03@OXNIFHHaa_~pslFMi4WXJ=&8g>k{+@>l_V0!sU)7tlOp9F5(nFQiC@%_E;!!zEV4x6L~PKVW0K3IRT09j8cJXp8qsl;K`3y}4M!h?hEJ(bwIwg5>l z3VoeD*p=<6#0I+s$a+G7TgN?>I4f}hvYk*!c^SF?mdaFuwJ(Z5wi61e-Jv3U&v-ra zy#FxsY|nVg%BbDOGhWX;r*wrX)jZ=kwAM3T&phv`$PF1^(Jaq6PXF1rnw_6@i6c*g6Q=QnInH*Pp(QZvp=;uj#>35EU5mwsOqp2~XWdEYVftc}}_ zZReixdggiGG4t#h$Id*@cs=tRfzyk^Gmg6(JmdAubE4|>qVSAol1%%I*E7%ifthE` zcp5b#(l0MqOZ=#3p3_A{B}$(0gWP}5cs=vHADDUejN{T|&v-raoVA7YqVSC41PIS~ zJ@dTt3?|Pw?gR9U*E7%ifthE`c(%fav#N1B>zU`Br&)Q%cXI!=#M2R7|CX3}_Kf4U zWY2g#^Bj+rUKE~j9OC5}uV|bs_OHZC9DLcCMvz~blWIdsf^&#y8dDSz|dluZb zV{RAjG}fwq)iclgg_&o4#;>zoc$$5=^^4-d%(G{F)ZPCJ)5M<2%rg4+HasNebTwqA zkbv3nkeGm7fTTiw4~f}Q4|z}!+(Tk&(?eeEf|Y$>9@0~Jx2sDsqP`vr9=L>6GoIy< z?He+?BinA)jp;bg_)+(XvMr=--0pgdW!`4>_~l*ihupKnCnEiNJbQ`Pn-??BwC);Y zcVheWOw9M_Z<$rtZSiC6XLuQ#t`}91R zQ1Dc?_t)%uwo0{6&vVvYg9k(P{#yGY5oSND+h_N)EDAh@M61xjt#;CKfmcJJ|| zA=|FO@x$=4|CaSGq~nLNU{7VeWhkp#+O9!-jkarW{4mPuzh%7{=h!eLs;S&?xxI(P z_@#%$iPs(ygN+{YYDW!H7SN6wq#&a08XOz$9`xVxX-5q*p||ZC94TfEXU%76ic8v2 zgCm6-<)BXP$GU5fBt_db*s*ZeWP{`J>cGTe5>+J+bT(`D(a-X$NPY!wc-E)NV z_USpWP+#liQLm~$4y>y8RMt!2vmmdXP&kfyy?O**cMVP)Yo^6>VsW{LtXF~`Csu-c zD(hw2$BAXzp2~WS^>Jd2wWqRP5FOiAcMYz3_41Js=Iy)Zs+Src7nT}piC^`);N!x& zU{7Vei1)a#h}Tnzvz|O8R@{2XdUkEpr-$G~8thRha)_H~xskL{<_jrEs$DaDb}IpF;IZBjyK zYV{!%dEIuERmQd>==(ZSx^&&BOV?#7jYXn(o?gB*&Pj6mvr$=bADcukwd0mwbPUYY zXwi>5kG1d6VS^1OdnA2j7(DEXfTO+gS?5`FBm@s)1P&7P$@(TQ9SUjgC; zOsvE8m?u7m7BDe5zJQ6P5(}7EIGcm!bpFIz3A;#kzt2GjUR%)nyvgZapc4xbJZ5@9 zz}R`-FJ9HD?Pr=I$Si5hu@mq5^0@B}F||p~$}!;GugH3LJh$!VO!)v{T91CFd;mN~ zZIc@MsNH{ebG$+ChqkYeKM#7bjdDfO>+=Ejcg3;NrN+} zr-#I()&eA5>>d(}rWPRk;=!VPub2n6!oAT(cYsdpIr4O-SOHX1@AQ7IdXn(rB%wa% zV1;PezJPh*`_jG(vN(c#xdl2W`J5i};aHmH{lSZ4 zfldy5c{(#ssC|x}jGm}tPVzhL_slh%PQEUk!Ayj%j+ru(I_5>S0Sn)g19Vb9^F1+? z=IKn{zb>P!6{yQ-!*}Zf@A%4Gz`WZ&L)uAZ+h<5CFh=M+@9)U<_SxKzw$BjWGwZBQ z=iT-h-l@^#GuY>A`n7M0|6GTRqoz3tE4DPD*>*yim<2*_)Fx|`w>uM7zm;hLlFqw_ zMAv2kk~GOf4wCr-B)zk3xF$Wk_bd@s&T7686 zS9sR3p2#bF_QJ)rDt}H4fq2#@MwGmAay600%jU`UJp&VXT8TzBm6jzQwXBN=EBrj;=x;4RQt;hF zVg$)Ua@H~$p;8(9eUodX6O4O`XyE*e*eXZoQ%?r&nScUh`nx>U!GLM=Z0WqED{X6|Ece~um;%B1N$e~Chu?b7+f7pwLX-#8!H zC40x6Sw{{pYfopcO`ubgd0>3TL!#6dAjz-skSCq>1xRwa7a-|{=}+Z}`4NwKp_8aB zQieuRY|7JlW7x;jnK@~2Dm|TCD(LCVi;!+NtDjf)lC*ixrgO5K`g>;8Io(A1d%n}C z>%4Oo%hQ?l3U#?>6*BQ|J*A5~aJ}3!RJYE1dhLPt&Cb9$t_P<=>KPcvNFM#E;aiQ^rlsZ3raBq!%FRao{1bWPbsYf?pmo8>YWs1|AYu>v_e@ zaO#+`ue_i($K%AIvYyW58sT&528eOtsPEVT6<5iCVj@$Y^MMgh582-PlIgs-_r+6* zMW=s;Zz=(0wgg=m3!vd0ZVY`3W%Uca-WD)1LZ=VroyBl%|KlDQ1<*$6zHxN;0w$(m z{P&z#ob$->V@GDjlhSL?y&h#_XZut>xF~OdOthPJxyJEi4+glK+BMA3WJ+N^R_sr4=wk>&D&Z;8FLIeugT2r zEXccf^~}9NDj!XA+L;n6VBOOB#^orQVqb#6#CdC;&WsEq-sShqBC@Fbw+Zodrr8Nj zyZ@g33XtTj>lGl`5?`+XN%>g40wkDR0V2~`>8Qc=dtR5Gfp*F2eAXr)ivB>&6P z8Q+s`cP*ol8B}l^>C-+Y9V7oeGZl|`x7Kr;Ty?E^f9kbvS-HryZkEn8n2-t4GI|He zg13}E8|U-fcXVhyBn~sv#&h3M>Yhw|y?RI-{IS3}dNrO*Y@^eVM|NU5rM~qOR@SmFLM!`%C!% zC9l!vygl+XY~#pN|1mN8;k7-btf8Z7;ZnEXmifg4PxD_owcoQDQ!PbPP7opWr<@toIpV4nMf)zzBJ?2B&S=V`mF+xC>yw`KldBZ>c**mdd8 zc?uNjoMSVA=Nx-&HRtbepEBp~2D7rZzss@O+8(E)ZQ+ijE9;zNU;Tp2vA^1?=JCVD zDH<|eE_InFtJ>D~t)6K(Qkc-^yq;;ugo5@f^+=IzpYwXA;Yc36ea`c&s&k$wLR;JS zdZr=ikoqh2ND{ryc|FsR(!jojOABqA^P`?=IAS~M+J0cEWj>4w=VnY{-NJFjoxjiH zw%27|&opFlM&H7v#ih;pSzRh*tY;dI^d;0ePaRiV z=2tz_aPU+DZ{epOdKWn21nGTdB*3?Z@w<01xT{Tf9e7pop*vs-*kH3-_dH{ zn1{YNZf@v`C3L*=qzljcOd#N!cP;mc4P6;fYk5x|80gfzXTAwVYAo-8M8C#kVr2jI zp_MAdc#^-MRX$Ru%iYWU+BcGs?rOUBhX~aVgzK1ejy#>`P1n1p^GZ?d_j&i210RN- z_xQ6pC|~!{+mYy$e&VpL*G+MlDZm3dryNokgN!v5r{z6aH@Y{qj0Wd~JtpS|J?0zo z1zoaoA3RGzKZ?hRX?ss5u60@<6IU>KGC3x1A6(8W^>-rHH<_OGyzT*0E7D$X#CuX<(7u3Uit8`n=cxCiWr%nC0)8?~5X`&R%|L>L zyl&Yc%vu>O9mu7J2$)(dFV8)Tn6EP-_`^MPePeC8oD(D&PT=&zZc8Tsla+Z@L*LI+5=mm6Q^vnzB z#NspkH8VLTzxlF9v4YVw(~y!VYw{+ zRa1AaM{U zb=P3rb=M$I%DQ-PV3}6+`$v&y51E-WWhJ_CLZ7D+hZlKBoYUqZag3mc9Cg>=#vxdq zN}P4*A@MPl_DlJgy14pRzoKI>>D8w(M<#LRgMHnS9+QU-d(0iDj(E&$90G&nF}Y6a zHG(Q4Gfr&Z^K@QV7wGBC{R^*sPv?z;c08RiA$6Tkry=of<$lK}E_+>pBoXPjW(w}e zM_RzdVMx}@$DtvQ=6U4Fyc6C6U(RD5Sl5*QQW=muDoK$RAn6Rf_lhJF&$=fQ3)B}N zDGui$v7l=KlC<5+Cn0yZFEyE|MFA7%A#tw70we|EwB>kb%76P^p30NNvw1Sn<@987 zPSun7P)(C3lTEv|Zx{AWXexPpoLob4-PfPg(btQ>Q@PV4LreTZf6G&eIdl(+<=LKb z3}kyMFLL0#65*H`JEJ^fBCvKqbDrlfc5}!i8BK{mAHyhpYwUu-I$3}?)|sCDaqo$WyU#vA0Hj- zxZ`nzj;|xBV;%FC&H=!*ywA5Hu#FiH0eII1Es1c^_tdN(Sbd_ORhd1}zAyqwuRqUu znxnpj{(fwARnDwaD?cb_rc=X%QlHBij~LF7XFWZOaE7cc&a6=qx*eK-%?n#5-cRGC z{ss)cHEFk=$GlPO3z+p0JIM-Ry{4|yow0MI@^X#IH6JY8+kUqc{9FGDgih;iKU=-^ zD4_(pGG9xmbUqVt=*m3pc~21zr5rq+8Lb3X-X8aiS|#;7H0FWZfIRD2G~H(X81yXg ztS1Ny7l&s(-7;;~Qx6GeeS!51fr5)eAIuAVM6I0HL1}u=`jy8)oAsEvw$um44n6Aw z%PhUZr%+oXpEE^r@HstZe_`g8#ul>23v^r}O6miE9%VSkD0Lt_2yt4YwjosRuH%y1vQu ztZ&#g;-$W~8!}R(jtv=}^&P{V3#?}a#kYvG)Oqi!XZ<+aW-iN`ZgRdf>qo+A-(Sh%V(@jEe&=vhxgdELxiCplkQ>etmbb5}NDe`}JL`pDMRZ%obl$W!mCz#ka$RJq|we&`XuS<&}80N+_*p{9!yUr=SMZ>#GObU5?fyU*PM7PHJQn{){oG0 zl85Zc#KB$qYo_6aiVQ57*-Jp>Lv!OucMB+zegmh3imcoMCOWYmbK;2Y1x#FQvVe*ArN?}D4T-D(843Het2Kg&M{|L9 zoHea6k8EjgpQFsLt_RLj_w(}hb+vomH@x5$FmYh&0wy*HFJR)T3y-;DYuW-P)|@Y3 z*26UEf+3aHPRMa!n8veSpV^)jPS|DPSwH(X+*?~w_UVojS9f{VxhLLBJ@&ZGdgi;f z-Pz;97olf;;G`GpBBwiz0)AfVgLflaw{9uL#zf^x)2NFZFaov{`@fNvNfM{`zib+Ev8PGhO<<>)HmFQrWHOler+>%?zmvhv%cfZu?5zjwwX(#bUi|M9w$ZUJnLD;QZ{qh z_fYrdvP7a@;Fwr^-OQc+?BJO_1?_wN%u>#_)Gv(F__NOa@m}G%@Wr|x=g1-Y4kvlm z2Nu3~*0adDE%m#fh)5A;-^``Kv(0*jztp9kVHowZp4UsAb?mo)6;0K+oe#bSbzUcv zohgv!4^f&7+Ogv_bJxXw{di`F4FX(09A&4!X9g&d@${H!;;+kS>$g)~8@5w<-uEBX z-Y#HbQ{n<<`k%fp%>~R^kN#W-Hr;zV6YGtWQO!SPt0G-Tp3Xem>oPizdYI}u6PRs( z&-0=3AAKJs`$U+!EE?w@e4>Q2b>?%!^>seJ z4Y+lu?T5&miT6BrZODT;6Z<*y#3q&3Z=<(yw$1wZVa~*}K1n$}>l-d=(N_L#Spn_T ztZ!Ik;92KY^Pcq#`D(MC;Uf85U*~dxbzB7MbpzJzIIb}=4HcAg``HJ~{XUd`gw^cr?xY{=UK5%`#Hgs>daGmwk8Ne~pQa^FAjAuQO zuRiNI_(!vzee+=GJnISn)LFl9@Q-I517Du?j54gVK5+1lW_@5d$+I34UuXS3>t-&S zKtbVOlcgel_vB&9Hcfa>oSvn_viHQgJbwxEyaA8-^b6VVya(H%^E>;}L6zB3BU8#>g<1DT&qA;B1LwgmVB!+F1H$Cgw;9FPt*E#;a*fr}9CX77mF(7@`@pkj9qa$ls&oz|b zsx)tUrLJbcGIkH=*W83_xg^%EZ=PJ_zNUDvJ0%^&JC~d zM|;QL{X5W+^{i)bTK%k_?Hzv^B886ZDMJ;(#34mCwGm8C73K0X0jfA&TXQM`z9x7S&JaOUO$ow$WTV{X5#ooWA5%}&Q% z4rdSMO~GDUop)~=UYpkK&ZuS#qS~7{OXMgzshzrQ%lyUiY2Pxi2gI&FCvRNwtnV3C z)Mh;$2W{35EKBsP_e-BLX%+ohE%l>5rTX5^`jqNm4zfv_^|L;u`p%HIc8D&RSlp{w zzwpNN3ZLft`dLq4rG3^%eM)sEVqo)|cNX#-ZnJ*Zr&QnDjT09<>$5$jIxVRr<-leaDFl+RW|Q-P2b117Cw);SZd+u)unIO7$D? z>zla~CoXu_lPhXV{j5)^zV{3ZY+r7B41AmQt3IXr-ZMq2&iZIisScUgqUO)~c8fkDlJ)I8@6k4FOpUz8g zj?#IW&MXh48b|#-X(o0?JV@bz@22Dg5Wu72$6NKtd!TS~l>()a#*4tx-M{T$dz z=jr?hN*6LuoAS*Ibk+xXW|kC&l{}rvJJ!$9(|>CoPyelXB>EuZxp3W^5dS!p<-0&G^gKFJqc_mDWq z(?epdpNB+yp9*fV03~F!nRASoAL!y7=A#taH zhpguYv)_<{UY<%U1F%B@?!-<}*KKU>%=-%NUCsKnQ5fxILxm7ir$O$k|D1`YfLmy% zVBBZ=JKLXgV9$mpbKvV=H&|q6B2605k>kwEf4$SM3*$YwPL&28c3T{s9igQ0UOUrN z1OWvvqPHgP`*Z4EofOWI?eq_f#G*m$3z+Re(wQtj`oyq|maR_=3noqs)Az=6 zktX?P<%5HywI*G^o$ieV%&YAgXWlh=3;J_jDcy%F)3csR=BUb-jbFeV?bm8HJ5sHe z|C}lNsk6T0De|8);RLY9_OK@ePnzUE=fRVt!-nz}Qd~f%$bZh%*~2xgKWE~Rph^C7 zo@tqFAI!K5z`FmOv2h;Obn*!b2)wwJ>ER# zhKpA0A;&#hht+3MJK zJ4gD2p;**^&NKwnSwHa&tNJ zubGyG_7TcV05Wo(Ox%Owzvf;~4rXUB321@L`Yn_(5F{W^=5bKdwHEq;`!N^D#PuSY zOs>%JWWFUj<&*xFseD6vGA|5%=&u=HJHPp|aSLR&*8^ne2@X*9WTyERB&5IQzyZn& zWa5r5PbTIXJ(=keZXcl=bBzmRwpTyj_g!E8e7}3hz)#RZpBPK=UvpwaQj?j67kFRk z61NQ0prG;V-K#fSrmvF^o4}m}ojayU^d!g`j}s22eyYEX;SucDt+9ZKqaYVB`yDTt zPm76?99^YM?_0etqtx@(WyIq@yo}<3fT>%+#KQdrOst9bm`P{VWi+t!c7e`|o~;X* z{V}aG0onRFN>4ytM)%E^hqWOy%OTn}`7b7b*lEWz%XR63*Y>=w_Sr6Bfcq%cy z?jc8gN?1xy$-3z{V%ES?dVK-&A^%-}&P3wj0C_TR4EcF7F*NBR`|0&}3vB543L^Ti zInjypm=8AOEns5(l*LRxFGkK6Fwsd^z{H*L9y1M&;3h0!){7t#qQN2vPv@SF=I?VP zk9)|(A_!0Bfd#D#nCQxR%oEp~FJR&VI**xslW-Z?MA`hkt(f1cq?1~itI74JGKd(= zdU7L}IN!-WSZ6vm$mL$ZtS2`@XFa)*-H`R;sp44w7lMlkEijWi%*3!&GgtDf8lo%Q5Krd-vN8^Nq6H-d@pVlSgnPj1Y# z5K_R((|OmE8=sVWPY82<5?@wVHCD3vN8p#?JA8gQ-+CGrBDSmf*PqYQ(Ehqk9PB_?!l>N_q=GU|6+rZ3dx zKJmTjzh}x5>oQ8nrY@uT^!<=$f4|pPNWg#3>_(~IahYz{meISdxho`V_Iv9GjNk$bp+ zdC^nYW4?EKS=+NA6b{e=nHPDSTHUWvKS3APjC#)V!~y{=V4{EIF>fp}SisB@*Kg(Y zm=iZ|E?}aQuz-mHWRIB?RNc@$*t?=n=7X-bW<3#=`Z3BT9P$)Aomu7yB6|O>eAsu| zC}6&Bv%}ocgxI~sGezfA31XMx1`~U+^)q7}IAvo269-rRW zMAVOFYH-2(T%Z#j?*&Zsmi%>;o+aSjdNyP3nAouu5vj4Dm!|)m6B7~o6lMA%d`(a0 zgLBjuFmVOt0w&Hd(U_S^Plj#*6YI2eKS)Yz$YHRmbf?@A0u1(GW-knVO%I74h=;^} z9S>O_A)isWILkr5i|%cbfIQ}oe!TviJ9fP-keNa1-@bw;69?gF$OG+>=lsB-wF{Wo zJ8D<1&ih0s-mZoXCiaec-s35N;q-ULg&PjEDkW_I3h!CZlc>&m*5ZN_uUY5y?4I?! ziTbSLDblR-dUnrx=2O*K&)Su?)OkI-XFZ(}b=G-+x|aIH9Ydb=Oq!^({$LrZW<8TU z^P8_qBF*|cim%OjX0o--Tyii}Rk6T2PL9);TP7b-gvv@i9z1z-p7jkIEf!eE&9Itv zp2zN4kM~hm_`UwjN+%(upHBM>p7D<1BGT!Sd0ceX-)ERg70m;??!9)Nm~CFb#1!EI zW|r-K+xP`c?9B9-*G{^$fQf0x1x)UMiaBulnKVRQMoB}|&C*DTMO&8=Mr`K{QshUM zyO(>`aMoqSQvy7l?@Y3`jN;djj2>&0pN-orG-f7(0HJR$tU8?UzLoX|eX?%_=+uJG zz7=xoJm!HTRu(Y($;@}(N?k^|i|aB%=ScFA+Ug%y0@+k37vQQ zjgal#xE{#!&Z+DL%+Ypf!#hqF@^tPPsa(LkXdKQ0W<9m{{0>a*+0OQ0w!0GpiH!#~ zTo=r|-@lK$jnY29tU4^aA;HA(rwmXB5_fxe)-Rmq=`}t>rQpG(Sx>`SUFsM1M|jrL z%+O|iq{p|d@PkK6N#8S`(nHT|E%hW{>#S$3T>Y%ym_qQZW5C9r^`tuLtk3qu)nuY@ z;;Lu8KNjQ3#D%(<%M{nP!e`r1yWAjq|1j)n6+TV5bu+j9a%X;1J;8W-IuD$B4mxWr7Ff$vp3AF{+=VfljxlGj)XZb9CcPyg(Yu)^_XSM6 zHp7PUz*190n&dy{Ua!(hDv>kF887wOM=;d9G>&M0S{^?|3zf6jrM1oh_}_2k=;?ag36Je8Pd z_mDU^e*u!bcn^t>VGYT}03H&bSsrqyXoZJF2i`;0i<6G*nF$$R?c$zF9OCIA@A^G? zwDT|<5^GDaoZkWZ^dNStGPD3GX3Y=aO|T0oN4m|))z2wGJrko z*N%IO{pZZ8w>s+wo+AG_4|I_A=R9yEx&NH$@@wD1=_R74mj9fAEMG;rgGrP8=S-Jh z`xd_9a|7%Cb6&XpTWjZqTYLQH%oN-@>jO`b|D2hF3r0zQ&O7m+@7v9P&P?QjTiBC1 zC`$D@C@QRS@y3k>OrAwQ@@*8MBZnQ-Q-{;uT{!t*U*R+z_RBIHs+`+?a#YJRMizyB z6KVzj4!wqBbb2zgRQsFEQ_KA?MpVm{FnPjcZO=EIc3D$uuCWTh29*Lys$^$Ug-k4z z^3+X3y-sVNq*5M9~87H4@V1{A>Cj^w%BZ?PfspRu=AUz6HojCoflQQEzpTWx)(4x z%b{hI;Y^_R=}uRIf3FT)eD-L_a*O;+C3b^&D)Z#}HuN5{T($8sj#V3;O3X&cj8VwU zs0Fff&R2Rdam4=uo!Bb9fO$|lVgZxQod2He**G^OGTPA%*$z!;$`Ro%x}EI|q1?|d zA6&t_a64{>)VXIzR(fnW%<*>5qhRhhs>a_O`+=Ji{uR3yj!1G6zmq}@slBov_2Sh) zTT1=qMR#+QTIR{;?@m<=SyJcMznBMFXOD@=;sxHZf@J{{t=W`?zY+Y+mv z35-yF%9DBGXgd8hGfxbx=mI3gLKis4@vvS%xQS$eOdOBmza~CvJS2x}t&xA{{evEP z0X=jXdjVZ&IrZ1%;cN?#=q76c@rE@mpv>6GZ@$vI3j#uq)_+Z$1+)N3m-+(dO{?FTsD! z4AL%;iE|yjfN)&T0whI$Jmgk|b7Z+B?sMt|1>w*{0U-*3nTJ;J%yUO+gqMMGv}8pzypp84E>sZY>@ zldcxX#Gx(zYvOSK1;~CBvOQ8chcXX9IFt(l>W7{m3_W`R;nYFR`MZTNbbQ5S>kq<>DHjjx8>;mSbi_K%E;Em3u=6%C1y#+cs66xv0#`Xm| z(fL@wMbN)`HZn$9E3pucY; zPv?mfR_#TcrT6_CE*ZwME1Q*c^`uzzh%)N>YhJj@V*#?B6nipO2%fEIyfTV-&eZ&jhV=bV;Mf_SonW+m0U4P9?I0rrQkQmqY0vb5t%?k*F z&fNl&z zFOZ2NzWvw41uGsB*l$HyqR9Ip4`1NdbjS?&$Mm^4KUBJqnralIlQWNwqye z!NkP_UO>3_c!A7z=sBEY=-D4iEUEUKXHRb=@O7hW0VNk0*1jMY$ZUt6vz!@As%_dX zm>0b&7ckL*UBJZYnjZ6C-HD%Kmub5_(;qNB;4wK8=`j;429@`i=zJ{5=s_n*(|K%t z868Le9331*^1Kgn5WS3e(d4UZCfAhtXxKSp)3w3GERLr$xmCE0Je?PI9O{cWlZ5Lx z+(7qOU&JF`2v{ZU$|h_InEGpGJOc>bLt)x*m1Z3Ne6v_ zb99fjfNl&zdopiykM-BQce*YYAlpf?_=nhW=mms9=mi1c9&-ORvE$G~^0Po2_ZvG7 zy?`(X?FGbJG4hgv{9+j@b_ET#H(Jp9+hj>82=ifb=$jva?y zK>QBW2YqI7R$D;Wai|6KH$#K%ODK#-0$))IEud@+3u|AHUXLE!UEseab{u+0jB77& zjva?yKp2ExAoC{U;lCz!94D zd(Jab7Ho$WP`vE?rh9_+dgwU|iD@vdP6=)MMbU``OmtuuFduS|Jm$f@aW-wY9k>K@ zfliJ@dOC4$^a7pee0a>0w>oLwPws2-n7r=9V`6pW!uP!U=jg<{NT+M#e^8t+4;*Xg z_Zt&!Itjc_d=q)h2WPeIQ*Jm)9*6fc*a`TlT+aBN@2k^OdYV3`8jbyYa7DwknAeZP<{ERu+8j@3rd@y!s?ErC;05wN z!&SXc7MxRT#nYM6M&e!5Ij~VXPGd(itUYbZ zE%qDDl3ac}v;Gz9tv%+%w})JL96B?Mg}$d&`H8gvUYEGlORG{ezRvoC)x4febVBSB zn!Mk!@K$4vA4VFqc8*{6XMcN&@5@9Pwu8Q=K9{3C^J5u|bIQ?qP@;`dDdUc=mowSK7;7(evNKd_q zdpy{sqIL7BrwSAJp%bLvLnEmzP|gKRY&+I>#{I(`+}ajr+a_f{{B zn~N;0fxkDrf;}X@FZEHslPm*|#-7W>lIUt%fTS~I?~HW5P^!!yp#$suyt*GefLN=0 z-URRn*1CC23ekAoOjaj!e0keik#4+n@LJtZTtB35p_|udE?{C|jdtbk zfydHg#=b|aU%KgUOI{1+&Bx6<%xx6@o)^VubmHkwkpX;9Eu)#TYlzEfI_Fz9T9$iu zSyAxgPyAcCG;_xiApb#gWs;DrGR^a(cb2E~!ZIx{__0xd+tZmYVYr7qojFOQ^!7f= zDhvSA`by6)8wD)5hs(c$Ax!))kF)idd$REz^gkn@3TGJJkJ9hZmtz6 zcM%vR&v}+s0;cxA_PpWXGSaN`aFxwt@^sN02zQ85GYW_3{ky_UlxVA%U{81lhkk(Z6X7$(HxR+8Z(uRfC3ty8*U3uQybEz_#822q`Gk5IR zx}iDWcY1E&+Q#3!^vGjkHHa5`Mp?iy@*>KkJ;(VgP^C{h z$LJQw#D|tA6Z`M|%|6=&$j33U0NIoIp#9Ka^Wp9%kBQ^hv^hRgdktsEV{Z6%^O!r1 z&(>G_xnn!O_G-?gGb7ig{YZrc)dXmV?o5KC9HKgtD}oEtf6e$wpq+oND)kmVc^mfv zXyWlesn_`j1M(U(qg&{O?J+m(L-v?E)@6Fk120XFd14U6V_q1Y^q3rz_L%*~oeagm z#vM=R#JqvW%s3RV^BQyfa1XA>+;Aql$K>&O9y1{Zi1&KT6RUhZ=7m!e7cg;#g~v>A zrF|czB$ZN3i}iMosimOy#l)5y|3M_CI)d2CN7FVxnUGxZ>C86^xvodTZD4U2X>=8m}&kC`T( z_Bomf|J7y0a}qr712=GZOy1MwG1GQZmk}>s@pL{I0o0hOz_0rZnUqNZ5l?4a+O~|| z8iw{c$}FwA&yZs5dYs`INxPSQ#doS@T}BzOQ2Hwk#mJmbnT zI)53tTb5C#VPn08=l#Td)B+}^U_ItF+djkj%Y(BnqZ^k(dERFRuXgQHMmJ-fjixh0 zx!XR&`4&R8WfaJEoZ(DLs_iqJ89UPU84|I=YBewS^!?Ul#A}f~oi|qhdCZ9|Odd1g zy7qna)|Rzplw(BYCYtx8VcT(rGX-nyIK!C`b=_ykO!>OcuwOXM)ys&>p*-e|BfC8& z_ronK@f@ju4JqkW1Pb9UcYUFNe-%exR^(c5gCRSK_ z-g(8b#!Nu49R-ihqt<&mw|W#jb3^J;@R6dx_KWtN$J)-EXXs@;3ZB$4-XdP^DLg8B z;^T?=EPLX?tVh8|RtvOWw26h*qu}>1GyBUjdTZX>FWMyd(RZ@?nG&IT6g-XU^(c4- zS=FQ9?{KX4i}oFI+kVkz$Zb6eo>46IDEOT?aQj7jZ(BVI9*bO$f@i>QJqjModK5fU zCF@b}drPrM`98Y0QICS(+g*=>->Lbh(syl>w@lb;-$(ne9tBS!S3L?I%z6|&^P=lf z@YGAxqu}Xjt4G1_{lcCpt)Hp=rnrd5OMoLtosbtzSVt(Tt{`E;mWk%az$ibaX13g%RO1Sw$G65%ypmP%2JGSCD(n; zgGP}1@0lja_I;G8n)Nut*l?_-<~=SLWzIb&x7d5k12fScGuvv~=P27I>psI6IQ`S} ze&bv#kD12c`Z?-P0!ZIweG))+v19#({+q7E#Pb4o6l3PyGZ3hz3$>|j%~+7vYM-2cQJpNQCpT#Fza;}^LN(kE@r&sb|=C7 zCB+AZ-rn!?En2P1Xx8g4<}deA`5pH*gtvX0tfQ;fT?DgUcadJ>dfi1zmFsmEGh2Jx zK0}5#*6S|v>ZsRU%n`TIh_HQ*Mvi;?9Hr`_9%mSPz3yU;qh5Cr=d)gSF~?P}yGTbAu~zpK0}`Gb)O+KN$NgBW|Gu> zhIoqgI74QV)Z+}9NkTru^SA=LnU*H%@9>!1-{CQzr1ih^2p04CaXo{_%*a7_!+Ol@ z&4f6E$4mee;tU=$4GDD_HsV<`@kA$**rX7KN2F-i+c2jP`VS5LnfPZNGiwOGG4E3KZ-gGYg*L)`>eUrI>nL%@P%t3WVc7yYiv3-3y6JBYH{VkCA{+!w*8mj7SNN8Z{LvlA06XQ#%+B=zJHgPNgsS;Zl2Bz z4*AABEav`0FaAAZiue6D$a22lMq*BSW$so+dkV+FB6&J95)I_8MYN@p>09gzWDat; z7e43gi#@so7T&A;&PP+L=bpCBwv6_K)Y_OwB5HNao%}hkpGWp>)am>O%+i5o$@6~V zOKSlWov#H<^lKI{@%6TVnRHBBm(mDYKS!ylt6xW%L{dLT7d{ESj4ph@Enq$r>^`hR zyJvtxU60m6YDt@7GpzCMsKZX0!U89$PxMx)aq(k@N9)+h<%zh(xmgEjW7pY+P~kmz*kvwm!8tNb=eI!2dXT4G)6=AIPc zH<>y-c|?!EbZQChDg#l5id zUIk38?;~5+zRC1ovmTzwkOXqxy>4dZ8tA6}m}!6lJ<=aDONiR?d3WY~i+tf@W<_fq z6O)bpYu*&w)e)bh#^@6An5i}gMben*PkY7sby<4MEvsn0G3^;TbN_;k(^p2OjL>UU zzktsz%YwdH->iL)faqj;Ix~t8zNe1QWKt2C&ILL%Y~%ZT+S7ifS^+d(Yv+y^(Zbin z>M^hJ$4<_iW<5;{ARuo)&Wt~I!C`eNi<2pNtM86$!^5fXj+713%hi9+l;47kJe?V5O6T3$ zkZZ>-PcNga=>(&^z&lRs@#lTVDWM)SsXUUAKJW2u;Cp)gZnAh+9&DWcF0TYL=>d%?^X>f`b$i!ZLPbRM8@MLE45nLRa z%z;zh^wpmC0qBvZ66aOxjMkMdM&bfbH3CUdUZGS6^KP)!}~%rtF!WNAIh z9Jc)C>q6H;pXh3PNSy2D8As<`Q<(sFTZ__i4O*lVt=EG?-8|=bPx@EjgRcQC^9M)y zdCqYXm9|D10YNbz-FrKJcm?U3GM;8z-?PgD_1!*yQwEQ9l2+{bm}H5y!Vg{q;e*vzI1x#EbxPXZZR~9hQEG=N-AU}_pdF*u= zB_j?`EbSbR^rQ9Z#3;qW_eAf@V_xVhEnsp=N86AuFNBRh_hTP2 zc^OfR>ismT8X%4KC?bz}()ZNmDv>&+N;Kx51D;rZ z4Cu7_nF<(kX+51M_Ud@d3rGHV%&d~j_xg&cdCWUQ-rJbj77MPTr}M$thzpoFUP5Cg zP)AWukGbI#Hjl}@lOFTH0TUjRTdF)})+e^l(UVMO`y4%)2iiVIPh5h8q^dR~HM8U{ zc^PGrPFF_hc}t|SE2Cg$N^w_4!Q62osQjM6aWSeCcJK@gBI+^0w&H}@T_A%z>}G-y0*TbIG<>N%>Mm$@!$b{zh&<( z-ESWA-l*=)h3axHxyjj+nHU%xB3U3GI#d1yHc2+wyqM+T5Pu;1_G6;w>CJH-9dOva zh_Yt}t|BiY-Y(=V$dgPQ_=x%%PSp~;UbT%+)e>m@0wmcaS+$hFU%K=_leC0JoKC=$ zX``1;oRVOL{+8SWnf`NbKa#pWL?aD#a4@YVC00XGrS}D{o#ANl(ZXx7ADDObkn!fgq0yMUhR|y#PqEPU&yo3q-*hfu;vi|Qo&%Scc%zhM8(@??>o;bK^kKg-O5-*D#_a<~ zK8<_6+&JjWvyL?|Uh26u;9z>Gr^Em-7wAOe=?%!lx&^OFX?rBza|t+AnmFl9N9P7_ zwbbhQU@4i0#D{@*;vY2e3ttl#RC(61XhGi^&qHTj>w888lD=#EamPh$pP@TrJjw60 zE_X`4Uf!xsO`?*o_I+VmO$sE1lRP9|ZrZ}%8?H&v7Cx;O6rHn&D6@*`a`TY5KTHRX zlOw{+la@NyoomQ!7;dXOFNO6MY0s9X?^CItME8yrj@}yYSbgm2Ok--q`el*)SwD6X z`vPYDt#KcCX=sJ7udaQ58Sq6`&fAaF=YZ6;nL8e8HSh-h#8U1BOtkR+bDrg`HIX`Z z!Yr_kNoF}8B6OzF05oX<6T82>{opR31HZ6JV#dH@ z^3Gn(`Yi96i6(LTq(7Gv^BVpl$^^cAu1_ak+s=tWFAs^S68||LY`ypI!RMetBW zpD+4rJ}1Qh{IPuSt+DVm@z$`c&omH%zUz$6yO$g=b>Z#&;rbS>@G+e99JI=r=@qZ0 ze3}o9nK~l)oSyY8R-#K-tI~$k0X*wyjXfkslRPFGcwKipvwZ-ht_8GXFMxhvPTqj5 z&D_jxAzG? zg^n*1uSIlXrqy4VY4-w!_hP@$L)5I-_u)oD+?M7)=Y{T^b`fU=RKq3gwR4~W@wRhd z1IHJ5^-N~8eKNUoP;30n6@J>zrPd2H$zMe`8l?pZVO_ZHnw**P4tJ5qd@u{4 zF*A9PUK<{B!!mA<$qPL_=7IOH$2_s)YXK7<*dFu3m7X3mml0g<9`nXFGLJd2V8dhn z#Xv)8lQXsf+wv@(+brmd)41oPm8BWWW`UtkA6I0h8Yp z-`AlM^WnCVIhg2rEqu+3Y61M$#C*6Mef(_MzkulyO=p%RfYkj_KTj&28`>CW&^gfQ zJ%y}sfftPDJ!5p>MW{ve7bPHJ!*pzH*)~c|qw*~rNbFJa2Xo-GFkAf+I`OUHC4_xX zwhJV+<`_QKWZrl#y*bXrd`i6Ovwq(+x4~;tM&?6|%41G!{?Q_Ob1>hRunj1^Sxho> zHjEfd^l3buTnC{)XGT1MHTD+%!HPU>Iunx(YhSLHSI#_M0Mma>jQA}G9j&pJP{Imy zh-@BWi{IJyj^odfo21S0_G5Ew#h$B(0xDWNw~W07?cC%5)Ghxg(5qSBQVjqH(;oIM z1AW2k^kninE&nw!W#A>WXZYIp=hUocY!pby+mF4x_4`Rk5(oY+kckUY{nxx`y2JvR zX>I)$x;Gztd*@d~lw1jEQhW*Z%u4o!v{OF}LM53_E%t*~erfx`WhMH-o^fuZN*?oK zr$+Oh0X3jXT0~hp0H?^G%nVwDn@C@7X*dT9uU*81CCUHLUvr!^{?vPj>1T$whX0zl zmtM#Aw^(D4kp7yyiO;(VHx|nJqn=&}U|mZnGce#-`pYc?_xhMv+UZ&6Dk^C{r+ zc#FI~L@8GQ<@AvGoZp=LbGaXN9si%Uw^`LDS*|qiCC3`P5$@q0er7_{tUyo&x_|?jph;6mM+hNw@4aGo z!&cL|L1eXbYHuxxl0L)JN$sYK>EEKRjRWuBZXc&&=5(B{ zyRP}`)K%j@8_KT(i)_c>RJUw7rZ!FjrhkjB`f|zh!g5Jll+>;QqU1w%j3L_3+l7vS ze=*eo1E215U0YDdP_obS4@_mY&r{(fP)h!J@>FL3)3MatheT(?E(ACy79s|ixCYnl z&pOV@B|5ew-I&0A-T?0zzR_n7FtPTFt?h`40>@;++tPXSQcSnYugPVFOXQo|TA~C`k^Sil)v+D; z=~~+XpKf2w&OIP@2taE~$(#%5#2Ou&?OhQnh?=`>?`o<6Neals$pyYBX^k{|y3e8$ zhw0iDNLQE!65=+CPF^78W0w2t8fQ=bx*eA64fm1TiH+Xs(}O~+eu{d-9E5*~czUB9 zlI?v`cZDsS++h%qiN$li{PP%ZiM)2)?+ikw9flj}9b72BVx|p_C z)CXo9*D_;NDk`DEK_63-_u*;xF&75DY|Kls1z@|6d8*>;U6g#xrn^~?FaYFZ9$4S$s=C3sQTx@D;aP3XKHHh#76oLUr0D|8 zUTxQm^P)>+zwMfIRNdt`PA+VEctEY3)aRywk@4=NphtjE6+NvQN%4xyNZbv*vAM~>O=cxx1==3pFI#@1C*MTx` z-y_at2H%c#I(8UjXo@mvPg_3aa1h^ZT{p0s%s)>JVy~x@Cv5oV$-2(RT=?y_%xmX& z`Q4o8ZTT{KRN9w_g2CWq7XsXQqkW2dv{jRNm~Ic7C|NPOD;!@TJ*{hO{q+8{=Dd9&=WOlkiu0oP>r)Zi_B?fBjHU>3okt+5v zTX~JeEv;FuJK9P5$mWnTr0`h!km_!J_bwkZ&(oT1pq*gfN*?rOdsrHTLQyaOVNC_)DvR+)!G3>r|FZafi3S0vMc1ZLY_X|zC#zzEb$fRg#$+X zPami`Z4Rks1GJnkNU8t=HRqFwecd+G)h`XtkWVEJRK z@Z6W9smRp3_VCF>?QX}qRLD**u#b7yo9~*Y1M=>3=*BWKn?pCMcVFH$a{xZwzn2RK zGufZMFsScCVu-@Gx)v4+`($!T)HY%lrwLrlr6uB^<=jtS+N7=DyxOpmUCSp>Pd8?V ze9UrXygsOm{nH%PkNT1W43DL2dMFG_Joh0LhkX|#|17zV#>UhREx15-$W$Lrr}^c2 zdRIvHCUE_E^gYaug*5)hD`pCOKU#AMRaOkR^l;Jp_&Mkr`It9O9PpWR<7y1ezxO^~ zA$^=9?Gk!wdIbekd`v}+f$^?{o*&I?fd?+Y6qnw$osZckJsm#gh0S?B=D_`}KBjuA z%6W9-$b6qpUjAfbYE&;p%>zu;pcc#Lp`kj}JkreTM@PIFpZ>RN`6RqZKBfi_6u-vj zabcspPp3*$=-b`5<4{XPIp1%bTw=c+$Bm8M{&_Cm=INfNa;+5nvgwpCQBv4GPq~F; z(ff2ZTukrN*>RPJPv=!`*nRCms=i0(z}fNsc}^Vn<)0@Hxbx{;nyFO$b~IJg(7Wm0 z_oj!Fbh6~aab})P-KaxsIyIVHzbSo-TT^KXVA^zc+&W^*XS;ANnJu51BVHY9(8f2_ z8NhkkvUKB|CjUIwfp&;Z=fV{sHl14jRUA)M83_9CZZ_sr13sBx?rF;Qr24Gq-z}}w z4^2sUmrkEd9Qfsy^y)NmN10D1zQaD#wam3zANO-nnUa5pq~ojKVU5khci85UB9;10 z>HDTMM|m8mPn^5y7IyHAB%zAFnS4^|^-2D_TYW7|JX4=cG(UAK zobwcwxRB9@#ObKZ{_+dAP;_$_gSrT@*wOyLu%pxSTq47IoGZk`xKm$ljW0%ooPO# zf&lO4OaMty1s@X2@&ZV5h8}y=dwG?5D?dz3;QM6WI0eK$O?AM)owN^=i}GA&NKs>) zcl6v@kLlWw0q&~)*@VQgB0iNkQ`kREt{rqs4BCfh%Z|f5&f|kY3imh#N#2DIiAfFn zra#M8MaP@7>XWIVOz)6BnL19XhgUN7H?2E#9M!w{6oJ3UO0e&cqWabEuOO@6-{Zif zsQ=~4HiF)?wTCw0l%M9QM8Ugkx-Xk5p3wAgp9~FFpb)grAxS)N$krZ8jDbQ5$i(2T zPo`oh?@SNKM8#cEGg_hq9~1H+__^ zPSaCao^H_VOXBV`ePAV;&GdnZy8x2J-G{_Fm$TpmDDrqbp4vk4W{Q2=9c`ed#_Hn9I2FMH`%iqa?m(rF^O-X`#?n9pBUHE6Iew25~^da$529VXJ ztH!3#_3_!$>6P?v`D{-YL#;Ma<%Br!hG{csV&KS!T;=cNRKolH!)>0c2&Ep9uB0zU zH!61jQCmEqz-4;-U^v&NQ^jG#BA?9a74c7#W%Z?eDsVt|xZ`{pW zJiP%VT}mGkGrsm&9yn{thdj$o*QQ8^PV4Of@^ATx?bJ4dRCWYp29R_meMrnF+B}yM zhWq0~V(E?jsI`WQ-4~;dsU@31T~j#TrQL_bOBq0t@oMv&M=kr1SbpM*(REUS(ibE3 zCW`}a8qTM4Xq4|ercdYmRM#x(QqpnSvN`cm+Jf|Ks(U|7pUSh^yHM|Vx#_CSwh)T) zKO8Tm&mNpc=~H>p_3^3X5d=1wcc-`4zvXxN=(E-qjy|*LR5cv2$URO$(sBBbcqv^$ z>YwW2+D%uIikN&VJJnkGXNf`V0FwMk|HG??&Wb%abk?VGQrn|#b4Z4$gvr0<8iWH+ zuTQ6jB!G?W)2T@~K&LI64J*O|NV=4^Ahqi`tT*G;rxGVY`&5><+o&eF+H~y=FQxzC z<&BRTwLsU$r&1HE--XD(<$Y38+P~%XHOXpcpet$LAN5!1H*Z(cX3&MR7JMo@HKzJh zmQQPGO2(67_r-{(`q`&BZh9wuNW7FbgS4y}?zv6n{FIxn6T4!3Z6sx+PkXzQz8Kw& zG@MVT`kTw?tS?XPT%KwR(!!c?Tih2e?(wNCuNm)}yH{+wUZ3(-H9^ul>9Xhg;I0Ul zJ%Xg`<5PK3)YZP_m$qb7M~AiGo-~|K=ZW2(w${`JHDZy?b)KvmK+>hO1xfSAs_(gi zTkxLyR37AA*k{>r+lUW|mok7Pf6_n8MhRpe68mQTTi&tnz`y01vIrW^W)Sc1@F8)u zW&m0KPIeqVW{Z)G4u~50EWa>b=8NViFHgNx-7TiRc>*@i2VP2>K?66|`cz(2XysFh zb6e!d8*BziI>ubRGp%J^Cs*z&+mf@tpZ58lD-(-7ilpIxYx|S<%37!`?vfoA9piOEKjw?=;UG6=8zImNvhrE`H7<{eMnU7z8JMe z`pp-kj^(L7ogHT^_;g<7HRFRf7TDr`)nCdBFQqM;S9#6&xUgp27o&kQ7JM<{@>HAW zv%F?pyCR;`db8VoDlxNUi_vV=-o;P_hQ93W!+kNDHyx%gM#?M!oi>AR9DL$K;-w5A z$#}KJNCmIeCiaa3@$3&@s{4GG%m9-7Ngon3OE!DfQ5_gpbuSs`ZT3X(R&S7)mPN!co!O6@;_OX-TcdQGami^&6>{SU{%Cjlf~ zN*@w4OFnxV6zDhs$;*9hLAr2++-@i}p8yDvtH8o^=uVsvB8xKF37;c_~;Jk=JYRbDf$3^HY_ zd@Au$y5g>unChBwK~mX``{B3h5I~9oNNRWVA#u!{&z`fo_VL!5TBv=rZ~4uGf^BVd zAKDgL`&`@y4nDDYew0tN(&9T(?Y0$SJGz>mJImpnUwSNAyKj0 zw|w!SVEeIH_2sFWmP_xX%X2}}mGmLYCt5A_;lllK#b_O<*nKgQLs@OQuKMy+K~e(Q z=DA9@^qV(pD}byn8CaU@1pM)-EH4>Y4NC@WDs>~P+0(F&$EQ*;o?;sFU$oR+f(r|g5vfMP#e4BFiV9l`q;pJO!7k6m+RF-eSU7BHB&K?{y=6^W)r9NbN9mnce$6-^c zpo|VE@Ch7e0V2Hw^|(9=u09kGt44gCUQ`yT+gMo$IK9yH_)If6zs!fA| z`@;PX$6i(+vb?xPDf04!!YD7UQCo1iX`udPoqw%zTh*1}Yhu%nEkv_?a+PM2Q!ju| zhvlm@Sw0 zSspdG%L{pzCP9_6r@WAN@mf)zJ=pRRK$b@hlt?LOPx(MTZIvlE4es(OnWD1XG|>dO#UeHo&vc&kkVSy|=msV_rR5lpq; zqhf<z|L50V{_@K|{f~cW zzx>zV{pT-#{kPwK`}JS`>7Rf7_h0^U{M|2q{g1!>`j5Z;_OHMG?U%pk;rUcoQVFuU zlInph)^38VuB3V(iya?9awV0`@}s)@xqpu8Vh}-A7lS;I#VsU)tS$z5ATg}tv%ET= zEi!RIsZHfsozL#dC{PQQPi1vJTU2sB+b6R+B_}egQ*sYvaY{~*)hW3Lvi$jxDiTXy zqt-UdTXj~Ue>8cd*1CQmi?a$3WO3*~kkwg*2NItjo8`SaFsk;9>cFTVs{^ACWU=@2 z^raN%Odm*metec!x0v?NRUO-TAd6!=f~=11Jdowj&&9DFo8?!vd#W$5c26J3;!=1) zR(Hugkmb+M#d{EKmMaUO-@MufuB$)l-P6JDsZAxWV)Dop1OyrE`VzO+_T+w%OsFomejtkzr-H05w|*eec60CesxG${mDT0eg2YK|wp>2LaEjd&B_*rh zo>dQHR+n4r_EeW!3lbN7`WLdg+*(vtms>xO)p0k? zOeik5?t-jN`y5YNyH;NcvbyTv_>^ZA1X*nw9G~*6f*`9+gX2@4RS+a*6-<43Jn{N! zxvbuQt_xXRZv8-32d$4!b-A^utS+~HAgiMW3OrSt27<(#sV(Z&<<>gO@|4{1sG{Nv z`S7P2vOFbs9OWrF?W!v`4UXz^>wf4c%h^+1ZY?US%dH>Ca?{|bF1Hqy)#cWL#B%FH z1-n)~?{Um>9em7k9emu?c`2!l>d38%TI+SNdgY3BuvUuKw!Fw-{gk_B3XoMBnCDUM zo}Fj84nEIv_v~!NEid9YZd8!idYb6$#e*_LWiNNn&a1lU>o~7+_e`LV#< zPko52*N4bDhRAeZJ-<|&B+743^+W=#pDAzoP}g_44({bGA4e~5`4D8ed)B$-!h8>GsnJ|XTzqK02BL3zPgq?k?&aJ8GsI~yRf~=Q_&8v-UCeLlAAj|hy1JeS2Lg! zeS!dUkYWljv9lz=T;yr^m=mAP028yG0VXyE1el!+#Q+mKm;+2qS_PO`*X?889}2?; zm^fT4z*NevS})yLmK)G{k#!Sb;-ats6GO%UCRSDYnCnCNkpL4Lj|0p`-e!P_5x)R) zQ06eG=8Wu6-J1>4R^_`6K}*mZSuj*tHd4E=scc znCif&w!NEbBIQxO&5#M`#HO17vr~LFz{EA60VXDd15E6h2rw5_Klqr6h?MI(xgF)Y z?!lmzT%iE6x>BPx z#c1D!-KX*^>i+f)`H&}>vH>K$LIETNs(i>sK4t((=AjSSNwWu#6#VfaFY?<0NHV#6 z$U#xr0FnYKKI9}{D1an0#)rJCi#S`mDM;Z{iT*_ZS#BC=1blINP{Rt#O#^k=fnQ~x zrAh(7Y}GSwrLt68T>g%C719^K<6YIo?~wk7qwD9hrrT^h)`9pCjSN*Pu{10#RQ1~CN za`I{_RbyKXiO~)J!!gm|vuBihXBUp7=u>~~1#3^Y3COQHErp8!T^GLn@pp|?&Z|vX;FwuYwFdI3( z0p>-1P=JXISOF#)UI8YqX!9}GhwS$N6Z>ZZOnlt~Oq{|TV9GqM)*%bm#RPQXgpdG} zyItH8aK&`XZ3eARq?DEY?OLWsxq$!^XP^d{80HHwCuJN0OzhA1F?ob#fLY&4p$7eO zn?e1%-`#j#Osf~4#225p{^9AJS3kaRJ9$nr&aU73GyUwtae7vXiS z8!KlIFTykP-%2b~_{%>_Znw3m#9kbq%2}Nh)Ib|D4}B`NuJ7H;3Lq)?<3nn(Q#F;^ zc2f)~7Ym}Y_J^x%rkXvPX0S*;BqnvdcIqXHWSSNl{sD8mQ^NoIT}R zB)f`x%Gp!CMN$L6s1nCl8|7OhyXu9?m0S51NtK+DgX*7U`4-78NiV-WWo9Fjwhgo|v!mF*PfpoJV@x%6X&}s@1yg>KMQG z&r`xgaRgiDFAl@mnELc`9u0PeY&s{~b3P`H$ng1o?L5=T_|koZ*kkXUW#L!z zBHP~3gk7o!^fAwRn{b@fqM;X`6v%7?@n2OILnf&?EDs|S2YO!fPa zn3wkD4^Cgk0#E|@V{MVXE~2<+%oIasaYx2JbG3oRP#vX)a0<+-@cTzt>)2c zIN#oN&ZB`1<^H!19P;5~P8|E@V`}ndIgj+j74t|XUO17^{r2l~GzzNt zm?usN@-Y?jE9Q|D$fw$75az138LrQT(`Nni9JqtP$JA2#avsU7E5AnzoBr)@KeTV9 z_&rjsG0r>p=~OPFnn%ZpLoR(f8!im+G5f5x8Ls2HsDR3+QzHt?c_de+`W~r2pMw1U zx37Z|F*c?~{8QF7z{J_wKBfvls(EytIGDkw^O+@C8@o{O4+og}bZRVr^*uV}zL)c8 z9_2QJypHNPgC=<4dK8~Ws^_idQB&VfHIK9)nF<5!Z`Z_wa+{$woUQKDsVN`jJW|N2 zoJRwPXZYVfaG;ToIdRCGkEwiaIggaXujY|lu5z0}gO|!}hJK#qHiPO`s^bjWCxFYK zY*|uYYjtiyEpM~jX6R#7=O(VMlFaIR^wbuW-y;Ppi*pl~T5!v4hR2C5&P^y&jKf)N znU`@>ZZoLu3w3b^)qp zw33bEqt0g$QL%=antxL5c?z@q6;Uxu`71It5u^GQnQES{enqByh3Z#iYRpFUE21LJ z@>gW`RsM=hrBkXsPhpn7BJ(=RUlGkhEPq9&W-rhy;=amL=54j-IWJ9}E4IdDGvaC@ z|Jx@nPz^9wb+lR))VMXvr&Eikt9dk3vRP~~&vD>FH~ZTaV665$=TO^GwauWefpVK+ zXbwR+k1kv(0G$&*2Yv`uG;gQ3aVFoo@&Fubz=lgn9rH*ZaKgb0q$_b1L)O{cDAIge&}CB1r9%PZ;U{gl>LpXVyC zq@T}Zi)tRNqr8${DYWuRda2LyO8Ti9*z!1oYRSuOhQ%8wZ5^`ICs(cO)-122pPCO- zZZj;+NG-lcDwQa&q}TIaUP-Uolk!UXTQywOHpBgq30BS{)$119-uLG!ucTLxOL-;z z{gH=MY%{1NuDp`|{;cv!dYQE4mGrlw-qkjP`d7;<>9yFhypmp+n3Hqgqgw-Gs^bi| z3d5@73@UvtucW^ZIq=oG?vOK6t?T4%R@)5PI#OOqf1e7^SL?b{A79NQ4GFG}Gu&q@ zucX(-EU%RB(Zq!(s+CH<|CYIU698AMv0n~(uk zUP*tqR$fVew?8mNM1G!Ab91Xsnc@t7eUPRfqSWj1T7+JzX8=X-Lt@>9Um3JM+=u0# z=+eaPYMV(HzT9S7k68&R5$^>ulvVlV-P<+e~V(FSnUw*_GQ&!YsF$);Y^< zCJ|X~Gp%!#+e}XesXETGni`ynZKl=Ea+^st)%beYIz&q)s&g}{fi1V06#6c=ndHEi z+f3@+F1MMMA~)4>mi2@$s^6ooroQTXqqal-_+O8Y3yl+GWcIAB|OOxWuZ3cPT z6tc5z2GtXn+YG8FF1HzGEAJawswXbD8J=`x^*vHOae16!j`F^drF!CWn?WyJd7ME7 zapg9Hii65+1{GhF+YG8FuAW$+NP2nS$a+%n)%QsC#N{@_Ekn7uR$!?kq1dA>6Z)B;SxIE4vLW^yNufOsf9tM@TH zpql7d&M4Iv7uygIrJD6s&nV4ODp!3fF)lVEp3m0=lzK+p)y*UirK-m$XOzl}i^C71 zRCUJ1w!{}`bwkMmdj9E-5^2uA{>R^b{m0*a``2Ip_RC*>mqYDoqWri2OaJ^8Jo|rZ z`TqAm{Qdv@`~UUJfBoHm{_@v<`|Y=1|K*?l`PYBf|MLF@{2@g04f(kI7UB;@XWxiZ zSJy)PVJY-C;^UfIh(GLv{ziNpa|=-wXTR6V`i*$FH2z?Td?VT<{(eQrH=s?TMErNv z@HeDOqqYWsh}+V0{P6yM6KRY1Pvcd;A#M3Ne(+(xA#EW)ez3c~A$^9cec)ZpZHE7l z-}_TU{(k858`387hlaav#3iY<^u_VR8t89GU(kPe!M-7FseIn=cYX(uzi(rIQ|WR? z_5kP%AMy7+mOn#d`TOuw*Wx#kwgjC&>=FNlwB`K#p|A8C(wCqg%3%Hsj0>!_=LNB-)H($H z`+o-Vhd|jkq|NRh_I&>t z#A;(r)$8!m`u7H1G5Zz!X#v3ZN!kiSCE>-lyZ=yc`%R=PKwYhDwHm1Z(C_q3qkX$o zvknL8v%CL()bh_zc@dR1bI^nE5y?~b5r4m2=KCQ1@Y3}|ocbHnrBZ1h{p9VT4XD(Z z>T=9Q*U_hQGz#Gan40-h{q6I7jQUz0sp_npN2-znmFb`7t!diT->&-aavrH2tDHwq zIal?!KYK*WnRI;ABU?_X@`vSY(#BJAEPNR~RLNJ*DD_;|GfLiHJ)=~&42-fJ-{Yr& z;`vJ_NKz%XA^SwGfl2OzEJ$KeKqiKTeKM6ae!ubonLl)S{TZgCX6pJ3D>iZbw07y6 z%r>5gr-k~2T|tx*)Ss56eADXdyYv2`V*MNRD-Y^@zp5qR`}=SYRaJ+-U(@zYsUAd= zQ%|u-xw=|`;KX>XfM!lZi?U@m%;e64h1Vl~06x4<>% zj9;Y7<$V8Pg2A7WCXJbZyJRa8*|qhMB=Z54^b!Y<6c`C0>)C@Lwl7WSDWyxT@$XMu zU@TpzJ%bl%{Lsq%eTlwwq4)Ve&3*p{4Jf^T7~1^jK!2DX_6-_5b4!Kw@7(v*@=t3O zzX?q+DT3oaa~eV@FW^1G>MD8-;=_obkI7DgZQm>`GVr~*{`p~`&^PCOZ%zp`vPOIb z)sG*>=6zG@UwaMLEN8wjiTUo!q=^`GpaCQqO#viX^#LSB!2`&8_B3KoBAS!JpaH0S zMDUIiP|O?q&zwwUG8ygX<1xSC>jTUmCNO@hr390nPWw52mJfl;onT@V<8dV{^G=hw zkk9~BqqN9ya3AD;p*t5`rb{CNfYK%*_Re(t(Bbzjq-Ow%4JvkrL01+4Zs_wKcpv`^ z0eU}CpU!zwskEA)Y(h8W`uiV9_WP_?S3CJ2KB#sI&>i*9R11F4W3Vs2h9H4N`4|8C zXwKogm?oguZxMhVGDpiPJ+N{-pi~ovfKjRmnC3mz$R@HN)qLfuDcvYK)%I9KmhRJ9 zU8>*=K(+D)?oUN&7+TTKtO zwgaPr&p*&UyWDF!v|Iwj)UJFO?Ar&JXq*L@T;}%N3{UXYDNncQaMhm1&hT66gAOwJ z{KrJSQj}ix`SjC>nD1-v8YiP`|Mj~fwawk3wLidlpUfY&pZvEkx7psY>&_<=6F9+X zVxB(0yh-ByPybW}{V8^< z!k9P*$(E$q$({)y%hmhDE}Gyle;6?SeTM?3Pcq*F%pVrqeADT32&1S0WVzma)(O0u z+IBm2K$dG`t!5P& zZ>B;(C23<{C267t1UUmt?2+?L`1Qk%-*4IUj}wb_0!T_d1dzm_0Fr8`{bcC;{4k6C zn?VVvR{XwSq5$;xVLkkxqEz$U;T{E)s;mZ-X9CKFC68xoRRYZOhm~l5>P%aC3}mV^ z6xd{cdi^93QHeIl*K`bzN8={tboi)R+E*{5_XlhL{LZFZbHK&iw-?#(Y?6K=*Te5@ zx|NP7S9^EEY8AWQ|JFi0P*83+jv(nk14w%B0!Z>=eaP~bE-l@tXAdUy{3l6zi30rr zX#Zi`?Vov)Znb!T4)Hsi?v6Ftw#%u&8d**WCf%b1lOn3VR_cFXms9Yq16fK+v&fPeEm3nroX<|UYv_z5t7*jW0_rUVo9o`0S{ zEbaSKbYgX#I-evN9_Q~L79svOO5G-mrMXljp#dh9EBc)O0~1he&aZ!r z)h3u|kNb3L%-Os59ni@$dVC&Xb|IjXwX%Pn>N91#DV%^G(|l&nQcf^J#d@sdT$Nvj6NpeJM-X)RJf)?eEk0M{`5F`U!Wy062##yV z7<&x{qUd2l>%iLMGdS3j`)~td&lAhegWIKUXsY<@!yQkm-VGf5>1QH@iYJhqt2zWw z6S#NlRAVMsnD%3MUO4PH!6em^V3LiMVA9i)U~b@%T-$QvN;Lu-Obe}W* zXeYzkHvi80_8WbCdF{!ANm|OTC>AJ=Z+w)PXZfCUBBcQ+HUI~#FK@!piI#WaJeXvj z5C7xu4^>#-Fl!6b_(z|`!{_g5t05(X3>KijZ2)#)I z283eH!+)lm=J>&h`fjPRD0KIq#I?zL^&rDDoluG?be~V!Bmu8qf{6t#eh#TA8Y@y> zll=jzqDLT7iQc<*Bxu`(30j|5%6fyKCYY4*O)!a12_}`KXs@juk!$M6h9lKhUpvRq z53Q?smw)9rRGs8$s{XvE1bes@8b{YAFL2X>jEve!Nmrkzf3li4%qMFftOjer3HVd- zkFFs;K&v0_6)2KwUxTh8BqUgN&`Y3XQ$41Pc?CEv8-bFmmVn}B%LtU7fC!ZIwQm4v zAqE>3HuvX;L@KyZ6LVd`=TA(?CY0h(u!vF${3Vp0G$<(o#cL}2&{QZBLrTe+evSNp zvwt-=-u6^3IVxZPN3fSB8@Xzi+@dFNMz zio?C-*6HNE`y~_Td6C|(LIkUxG?0S8W}P>VD2`BZM?`|kMfwryA8;{jt4)hhi9RE-M&e=tJD0+0w5GeQw6 zzFZ0FiQ~W{R2&}=q3W4^f4Cx4btrE@)d+=p)P@Txk`vJChYfd2(``0zOON3OZZ#|| zPtKM5bR$%Zj76xO1DUoxaCclo8PSSOhCa+F(o^9J=-yr71S`s!x?CqU0^(8ZheEP$aFGXU)(CMsZX%I8$6ImYgXL1ByU57!wC) z*Mc+sn)6ewPjPKma;DhD8i8&wCR7cv;YMMz;~BSbtRR5a1;ji9P2oWy?HNP9p@Q%9iX zArDc?HHEG(^?*{y!=8yCP~4+q-zi~|H5m}9BsQsi|40vwgn_pt0o@=`$3b^LkbT7v z!IKQG{()1K6H2u%ubxq8r6-@?c8HWFg4BOLZb3*G_0{L}7Vt^#zPjw+Ki^kU2d+p> z2pv0=)Yu_W8YudHqzUuq4kd*(L&+`W{`x@iYa&MdnPMw^^7%MTHsL-x{Q>Ct*&tH# zqv_rA70QWAO%u!wmek1(v@iP_qYo-NVg9*6NoiUgcu@(ZSlblb(i4XXCzNvgNWguJ zN+h4JDLCco^u)Qx$(iE#zX)`PlESEDpro+zJFuiqoU4}{DTaC@&>cz&m-8f);#k4p zmNpzK6HuyAt@W0aCbfb-Nj|^64Cg#Gr?uWVZx}sH7=>jx!QF3IG2<&KO`?NWKOvOc zoc*^{BRxP&6F&7F5_N5`q#BO9NN#C;ZHsOx2F?>kVQowD`8xvV4R^97pT8q;u1S^P z?j@AsDD6N=VQEXEq__&jS5kdPG`{bM#&>Q%4n7~F@xd+aN^O_>JAFqqzGE~#`Fstx zsQ>&O(fGb28n5-S8@P|rcwb4Wo)_$sKuL9s#s@08^DL&|>hB2gYx)M9Y4Z6P;!kdA z{lYkfBe75@`FsrVC!c>)Nl!v4&L)pQcZk%E5dVcCeqTxP^3gy^UG+WDD!i@liGDyg zi0QQ>Z*XDWAh@OSOY7C?CC{|nKDip%e97l`igg6~L^DI{ohZHf^){b6ZZ>cq^9F&E z!s&yFlF~f-dNIXm{E0+i-XH?qA*Ps&NNy?awM;%A7e+>)r1^r+AN4)KPY!y6=F=^$ z*L<4nT(9}GISB5)ucWx+Ado1HZP;+6INCd+bb~q_xZ){I&#v=k z-5?QDo;vR{YJRBQGWh%r>vGPM*X0CfIyJYU+>Mw#$Uk7zSJP8*#kmG6iIO)^Ur9}D zH%Rz|yLThd^05UH)4t(>*7j)-)8v-&6yQKiv4)#fRezKHgi<~G^`Jah zIbalSG*3Q%;$s>p6r6>hU~Z_qo7lsU9H|E1)=O0VC|M=oag=OuOKLEjFbYShCQ1sYo(4*4 zVQSY0T{{{h7B)r%618|Wh0pwja|Hezi)W= zH2A6BG1ZhNo!OfU9Vn@Vd4oWoTsxH1j>d?EjS-1N?Z_J}%o`-PbVp;v+R+%XurVU} z{8evBDI8m`qy$>8qy$>8q}oTr&a0J_Kq=5=D=A^tD=D?D?vSVrA%1NV-62tpB+9>~ zvQFxI7zA41z12P#;!i#wXQ}#6lschzD5(u0eo;yym3%&i_y6^{?Y0!se{`Me9d=k2%NWLL*QJXJ0uDN=ZTndYk(?!y^-W9I^Ch9FmRrH zK8`6$G~b56c{?@)&IP)`k~%POo-k_FrwrA+Rh}{wCT(>NRP?zaaNf=hfpdXwkf>)Q zb@>CWCPPTW23P;Yzs!o>4qwPQA*}nqEN8l z-Z#%qjK(K~ZU~&W69eZ7^EVXSw{t_my+Bc-e4FpwP;lSQ4F&g2VP4QDf#O%F2S5Xn z(jdY5cduB1`%-;yroNJD7>!Q|-4Qr%7&uQPYC~?(8wSpk&)-lRuM0&Yl~8(<51A+wockv2=oSLKLOn^{ipQ}(|-iI zp|GK2INn!M9k(L}N~&w5(ED4OF#p;iQJPm#PwAkkD#_;$lqlak>l+63v_7fBHu-!U z)DwZyRFw#{ejs=28@2`rl(I&_-Bo_67!ok0Jgq zg5nSE{=njRUrEW`fv-;pJvW3pG)ZrRM713f)pkf!M~U*?y@3P%lUpjAxBN938@2{C zjpy5-Pd01~(Egzfj_Kg70f9on9li-B1$h%Cg(Gzm*~hd&0=i*oKojrbg^DQM5bBsa zs`w{X@dq~FJT^F{n#T<J4~z_W~uQgh-*0I`DbDwgKsPw1H*PRa zl+?YUtmD3^tRp$owZSpHcMR%Li6kig;O;MM4e*teS}g0e={hz@)WWnuAW>_>vSF3T zZ3uO&9fNw-j(&rM{RV-OS~~{ytQ~`TG)WI`R3fK4`VAKL8zf3f$(Z*SI#5!WHb@Aa z8w!P#gNCn9m@g;t{YWEFs%MKp$uUi?{*FOCYeT<*s-!4-=6}9G>qV+-l3uw;3AA3M z1WF?1%W3~$zk#n%1WKlqt@(sWnW%)&wnL)S7gMdIo>m($qZ8(HYk>Z!H>sw7HiY;E zTHg!YHJ%Tis6Q9s?-{#Y(5)jjbQmo>SK=n^5nXs)MJV zQ5peK&nOKj1Y0UOQ>;2pKym42VD_|LUxL!rY6aX+D7~ntDFP+c_hlHEkERBEgq5f^wv1B{VbtXLmR=sh){9VP=eaA#5qF6 z3D60uYG*e{)`bpMMC-!fQkNNK%Im;Q)Ga`rSUi6DS8L+qogC}Ly3_Y`sOV%wsB6OusAg%p zreBd#Pp3{*6acr5ubKlBw&Qs9w)A&hRBXaOk7c9s)G>9d+Ne^2UP3^!6&0smD73F05{e_*FV1X^FaaStq6OejS^(D#Gy!6OKLjXJQY;Pl^=iF*Jw zM%R8*uoO!ML-4qLTX^XSAlSo>TP#^uUrc8pbSJ?L* zGhq`O<;mC6Ga7vTz_5QnC|9c{p!AF;Ur+X9!h2lXlz?hT?7Nf(U(ZV+0yb$*<~yO$ z*V8i^d_9kj2)q$Q+UyqH>!PoOpv*7D-hkEq& z6fI1?zTC|b?|DOOaHQBs5qv%Ge@h50j~41ku_8J6dY%#&d_A`MC6bRTYl5%GgnmLO z7L7%q^o%B7U+(5eNUt5wD303=zJ5>vR>CGMZj3NeWIEw#z&xqmA_N={(nUX%zGmqR3|>So=*Ep-NL z;MO|H%1lmRVI!N}9o3G7?brGix93E*3szvB?a;}4FV}fvH_!1%iHXW}t^UED3pHUx zD%x)esaWF`koqKQKxO%)3KY|xz5r-kI7I>zQagp1qEqD@fPDc})=l~N=Q|d5lr`hR6R%VVn?J7Y(Me^KqF~M0|v6% zxcSs4wS6cmn4GHOm&B`p)Qj0gp1%9URU=yPMLMGF1kH41Qac*08|q=K}jc|xOg!EMejEO#hh3Iio5p`P~2#jfZk-H z1fXiegEuMx#gdH#^d!xnfTD$(fMRE70*cW;U-J!I7L{O9geJhmAZ3F2ln=Za5(y?5 zdKclnmdz-U)MC^}^cCIuxDObW^+nB+Ppm=romFj3drW}e2tf$?{peJw*R*o@h1rW-V|02o4knX(gCc%amYJSwMnG*{cMT`j`^Tdf!-)rg}w>ec<*c z)z)UOH^a0-8lL!sP^>$i!Ij?-!kD<0`w2&w(QuVo*2@znR}(_9aW%N0SO}9~k{Oy{ z((C!SdoJe}HCHE>Ni&VBZ86nsf`|r$-XD_t;7ISI-Wt1ir2lVB{|7hp#x_G=NN=3L z8WBoDntRm9!~EeD4fuqK>I9S66ky^U$^^4MwV;g~^*rJMC4PWJ zOFZfoK2|*^Orqkv0261PB$!y8V88TAB-itZQ{Dlc8=7s85t(8^<%nM7dI`nC!{jPmlmSaXanol6 zTA#Af9=~!|iF>X`Afz}eB)Ckt03b0Nv1BR&txqnkMdp~V@0F}84?A=X2!z;>pRnp5 zUQ4Bm;YBY6T5gT@4{oLMtvrF!a~FY-DBhY$v&$B;*6UE3&^6@9-7!ptnKLlTo z9qP|rGmSin6PTj`q4l8xjZvuA%&O$BS5AGyRl<(dg@n=zHGV)TzV->F_0?njob?a0 zI^lr#$tBfX=lAef1X`XAdIrRSSDUaN6|~=U&>Ifk4Jd8gqwHTNwJd@}C6u;$7pJxQ z>$GDyW^X(k(^vYfzH?86(sc@ws|{C!`h%Bxn~%ToR`8YFQA~*>l8=?R321!-S63Ds z?!B)|lm&;w|}nj6Eix*vFHA zYC6TciV9?Z*8Adpk}sYJ)P^FZ-myq2IMMpKPNI{{=io$@8-N$DOD~w7<8@FZKM?%u zBn2HPldDm4bwVlnxV}JLy*@#3;f&QFzHwb7rNPIee;+)f*R{bay>JacU_h$97Vc;w z`S%7Z;#y=y1lLJJd&>(;hPF&szoG*-Bl?oBY2Cp3K=QQ@4?aEu-5^inBzX#+JS}a5 z&kwHCz;gUV^09J00Yx7-0j(dL(- zBT)MMAi$wIe_+((Tbhral8*3{_&5LNx+OnHq$wcq4{zVR68}D39~=kbtElU9(o5<;CD%uZ?Dx-4&J_C{63~kjpMUeO59Xfy zH(&eMNKSoqa(xzAe2;(SJy6#nnR@5G{Xhwmf-(M^e<@%JSKs#`1WFPWTzyR!f+G!> ze>94227E%pJi)|fp8yndI*H_C*GHgD4$Yx`zfK7#Rs#k{iYB!GsUAWwnX)1009hg2)l z!7>Z{C&f7E^X&x8)v(Si(4`FrSNWH;EqY0OOy%6+L<1>RTR-qVxKI6j*zguQ2yVWb zbm|@QjtyFY!K2zWxTJxU_KPGcP$zxXza^@OgRc)nAA7zMfx4*#J_3F2%bVyg-8VBD zp$Hd%2E4xx3K$387o6#(-kTMhu*`6x{ovuDADlAKa&bV|RiO{J=Jq z1e9xd{QER+3Pc7se{gw-|L9E|{TkeS?fHcp<=^~yP%=BXr4y~)y|D=(@X79zLOj8JQgt<) zsW16A8@mB$eM`Dpf5#4rMji%>g2{?dGJ2*HlrW` zu|5>zNGQd&Z2vxKm>2LVct{tHK@Bd{;{I{_(OYQj2PcZ7RTI|ZwwU0KY7+@)lY~-q zAQDjQb5HK*O`;z-Ws4mMUrI5o?_Vb+O6YxxK*=`onLj?71^fP#_>bPu*TeH{-+WjOUB)KU~YdGa2>+>1adWEhD4iS5o`%NtDYpIC9?GfERoK};h`Zz{M+ zP#cylN2r*1Pf#@u8{ET?}%9u}o2R6Ci|6r2uZig2Iim94_P^=$&vaObbB|^)m@;;ap2DPIh59q^& zw$NcT9E82mh;3+n60gaN!Kd){Iih;h(7-!`L}c6T4;vt+`*Ynda4sbu|Ul>Q`Lcp z@#O>*P3i;`4eA7x(>6Z$+4K##-&8~WZvO;?V)JoAs79;-p}ys>RfaUdCV2c$Syb>y zC8)|T1FIrboL}`dipzZbHL4iwf4f9e9mp8|Oh9qhMPN{HV?sjdAmc9rrC?g{OmnwG zLMfU)0i$koDSY*JW52K;OF3^ervgH8jY5Kn-lRMjQ=8nVr2|5_tjMPm&C`TVs(=aZ z(v2%36Hs)d6S>FvO@V&8(T+|)afw2}e74Q~+q8JJs4e;WcCyX_%<52oKQ;Oo?2>aF zKBYJv#I7V2saTranolW8zFkNwN^vF0yj)7vI8*PGYbF*M=Jp*GCOPE^CS50Apqd7t zLh#Vn&w50uh{%6Qv=f?YT_R9YCkf~Vn_NTI$R_tg677TYb`tI{a`OV&Uv%*kOmdxr zk3Vn*sGm4%2ex1PUoS`qM?{3ubvl+z0?*RdC_rLVLMm?B4sO2kW?)GqA~nf832we} z1{>I4UNF+zfdwOh?Bi_BK%mrz2QTSq8UmJnE_g`sK)U01KN=#VgW8h@{*m0kDv1}0#CW$~os5X(l z>y>~|Z1qV9#avWCD2`W72%S{l6%dL=h`~MWHxD9s9v$;O-8<^Lx~AHQl;ZcV%bf)2 z_d{OVR6sVhf2a#P{q*M8fwb$azf{+Wm&&$OA57qreWb#~ke4g_!Yq$@2$O98uQ5vA zE!8w&N*(zps(>H7q(0}lSSZ1yKtl5En7A(XnIq#0D6Y>+2qgiH z2&KWLk2UOmJvuuHrI?L4{3oR04xwgOvtJF(=N?ds>4@Y^J8?hwdW;|hIZ9Fef^1l6#-L zBR3h&38gsBCD3_T!57?7?1%|;9uFPzedbFOr@(R!{QIj<()kIhwgyskFF1i~;60TG zXj)Mhj_V$NTi~Vm4je$BrPX1+K?3H6F$4XY8^#QDMU6H@cog5D2v2ecqy#o_i`TCQ zv})Wa#SbD>?6po%4_u@cp`zg*q282_Pf(xksCWA}LdDX)1XUHy5S9D-A3UW!8jo|b z{b_+>sy6_|NauJ&#QgpzDE%%0$*F3R5ooMy+N5ghqpY$wXU#US#>GoZd^+)I@dFKC?Y$OOHk$HxvK>f^~qJ-V+(c}1JO4WN&~y4m*9$IuGV_v_?`6NVHNfcpNF zK*{$V!RO=L9=}+04D`}3yIfA~A^0)}pTCIv!HcJ5a=?9Gqs)V%UI`{S=m{pJi~W$F zX4TPipAd?-$$m;y(gJpFK=GV}GHzxTF zOhc2J>ZJ*Xp$8{gUvH;x-*DqGUzl(nE&Sm9oEuEi`Q^C3iD#t zd_0c22{1QA-8i9>&{?lXG~p0<6ju*?Lr-dVb}H03=wme7eI7yrgjQcVG!xPc_WtdHH_ zxX&V?vp#muWeW+N^|AXKli&%RWG*L|r0Ij0gJP`k#s_ixg-yx+*K6#5xn|O|BoR{U zBC7@v4m9|7)s&ReSwDzlXpvbxkFdEp$gHe`(sjXA((VHIdX0CsU%G{%jN`U*-}8f# z?;n81*P}=4^GeO_q)Lz5&I3)YMF3{`HPr&8yYD+pN`>I5x+7m8*iq;Am5n$=t{PpFrD z3+Jq#Ha0c16|5$IX6t+gcfNZ!z6&}vXi(SX&9(DSw4p1KVA4yMd_0zB1a^2kNtYzN z$1T;tkv0<21d|L=KmDosO7zkvCyKd{1XMdo-)~dkEj64lnMf%v(Dh%@CU^P$>jSs0 zVXJIHD7jz>p}3DVAQU&UY5b_|)$*>xK$mvS?RjVZaryBVRb|12@()$*hd^myLG@9d z7?>J20Uw_bI_q5=4fzxsYK@3z1l~KQKNdvAbEKbx=c(i3)Ziu2xDB!(eaXK#nrSPO z3p=C}I_pDE7uJafujqySw!R5<9b}dzgyKBSfJ->HD8Z!6NN}K-ZwOv{4eX-(>0c#Y zK^S1tfd))!q?!{Yx(b+>5yo<`eJ?&T5pM} z#1Aadfbr-o2bkEVpJ0;Bm|&85mtay@+;4-_T1bkG`mT~N!CMGEe$dA!m=wTHz8y7v zU^if$o7QmK5Awj6V_=O8t;u?KmI5t0@R^S&rFSWzv{Pg}p%fKqLaAnRyfZ4H6bCdU zluA(RDaF31gi@sh>nX*(773%Uiz)eh)gsq_KE^Z>O0nN6IMaz)v4GO4)obNvs|a7D28a_%ahG92X`@_YLMhKBl608G027y%CzRq?-sDWNohbq($2s|Y zp1~h53RgL*blK13EF5|noT{`m>8XI$`@q&7pH_j=0j-*;1NPtXY4+W^7uFXhM<7}$aO@v}K*>*!Xyv7O0j&xmZcr~; znp5ur3l#5GAX@7_DUceRtF#N_JK($dA zEI8NRHr%aC1-IpQ>jCAvWt&7#HkuMi{`gy=-WaKWj>t0Km667!KQfwp)K2!BAGdt6 z=j0Lx=Xx9%xJ+pM1E!`gSqHBr*8gF1OX>yGc5<#K+QrGaHXOMYq4GKado}T;Za7K_ zB%4U#o+4_HKNr_zcDb#R10qG!I`a%9ox^ij3IX9KrX^9Xt%IoF%hW5M0Jzm~MT zmV+dy3+>kcb>RfHuaXf@vYzk&NLHW;6(87ex73M;cT1Az9)R*B@E9hb9Z6yn#@d3fFQ2pW(21N6SpT(x`R$1cFtI#4;SyWFz9Ky^i~H2~nEL79G-d#L z5%W)X%8Vq6`;h`lv2QM+R8z9wb-uj>NS}{RNBwo;eZdC>{`z5K7jLU9qb@mP#{=hPkigOABJ}nF&_=agi6%{Dc_Nh-+Dyc}Z zN&iSSb_1MT|9MjP7+ldLa-eOBaG@ep6sZKYV>3~NiW7GNmt1*ec%c(e&4B~u=Zn>a z7XOpSHQ%VKk^darex)Yh^AkcT(3@bALJ2T&sDC0)INLn|#X7)5o^H~o5$N-IZ=Qa@ zCtTJRV3tqsx=yXs1O1d-&_!=aAWz!*30z7*G0z*wlSYI9r3omP(fHQBc0ZPzCmLn~ zU++u)=+sRXV5-{Z{njV)gqe~A6sH3v^0d%_3eFVGJs(p+Gtf{8COsnwCh4a@lPa$d zA0NomJgHzL0p;Da!I@$+ejxd3@rN@_7=@vO;Onv9Gr+`XM1o1TDUl~^%uGNRh0FqZ zy3xgpKs#p5 zH;*lJfka{dT!2|VU{BwU1NIVm!e*=hlvmmW^2Ga6BG7u@K~6JhC|{n|NuGFuxgq?v zuqrf>Cvy z?}YkNswNil@e)ujG_r5LvTpS;C=I56M7uOlDoirTgOA7Fg#?pAWxn96jgf9sB2Vaw zCZJemAc8q zNde;5v0|L{C6Z@*M)^cZGJ|)w3_9n*9y$NP<~^n>r5qNw|dWZ32p! z*5EevN%PJUP#mcl@E+%BCYbb$B$o;Ex5A1);36Aut&yNgra1%Ny zDVlIe`>o!!UIL2VSaLtl77xB*7%f4=@$kE2ndVKh{6!k0tVi`LRUu zd6=}%rvsNC1d^|nHKOEANc}gjAL!@=Uw_o!Chfq1j}Pd?oLeBITK@u9G!W7Q%PRf% zURz-)Qk)3sBq0s>gw=|P;A4U;A(VtPFm`mA;B5*7N@30V_g+Jq0o3b3L9qjq%Qrj>toO6CM7iY{J)Nn)Q|P>pPRf9!*|>BR2F zNzzxV2+0Nw{usy=ae zMuJPKcs@MMeppjgOXXFi!bB;x)w2rJ;p3ANz3F96Bp?08z$}xQ51$`g{3o*YuJr?x zyyGIC;3?@FmNRRJc73=^h2LRbZldR`}O|r;A zLj{DM6fX+A9GUq*Xdw9-$*#|P%R2$C77fDk^{xzE(z}yo7o`!9oHL1wBiJT1eI53MW`4@ zOi;&3f)$}+9zH>xpB*oYTIs=Lk7&hgPl9^49WTp`jsFR)3&W`qDptn_s87c#I2jQt z_CiLe8suDV3ywpzGaFEEYA#PsK&IdZZk_73t3QEuP)aE|0Upnkpg#4&^(WA=WHzGp z-e6^n3o|PTtrsQ&5>)jwZQzz1q78RzVo5=A0<&-MU&q9uqzSD`hiu^1jT;TxHKrSC zpBEm1U#c=M_B8dbc}W3%J_Vebs#jgu`;WXZ*I~mBtjRw$V%ddN)RF25lS5dVA`FH` z06VmbfZ~}E>_hJR;}u+mN5@j#lCKSh3e@XuIHBSZB(&Z~y$v^x8#C?+tqT*x5voj> zchQParM$~g&kqg-w9_R@72!ks7-N>|7AQ9UB$Q6lS#Io2gic~qf=Mbnz{CJia-jHX z2dqDEzCi+d(k=Cm^uQQKf=PCJf=M26a-cZDE|8}K^?m}14pwla*rAhPQo1R@d|3OI z%1&61d#eL3Ns-o5dVW24~|<1e2`Z1e0vjfc4z>l7Qki=md0-5gi=qpcF%Z zsd;1XH#EVdfOT@9HyKX>sQS|2>l0AyCh?C{1<+vSCz$o7BR9Py2Z}qE6Hu(O3SN== zz7M59vF{^bJ&p@VFv)aGxTHtQ4NH8f16L5)} zQxZ@dQk{UJ+YlV7s*2wQKfoLmk4`WtvKgq+j`g1jmv*=fDkv;xld8VT-}(!yQ+(E6 z#|Go+QYGQL+y|`J^frCon;#Yk>4gOp!I72^lOE?)K1}+-qzGYhptxW-VLhgw0#N0N zKuCSoOE;I_`thlr=rGhPj%J>3JdKkKoj{&O+YomgSm+$EUNxET>M6k_lPtlc2w`%U zCK)9O>v5WLK&i&mmfz6%A@j*+)5NLI2_{7dlLN)MWdZBCBPpS@*PCRsyklUTv%F*A z!Q2qdn^=RLa0%Pb6VOElX>gk~q_$e&Pu!N1&`D;V-Q1})z*rg>aOuX0&vpxnD8&YB z|445fq?};Zn~pd3i6>mb`prP$-?)P&0bLY#4A_Ky;t6KG>3A^VC_g{~AF59FzQ z6xKs$c_>qu<@TsBDU=z=s46|7pXkXOc%{QllhZ+*0vSEZCnyg!GL+l6!lXcMaG;tc z`flhX2a09$3F~ndOd_O{!q~x)PLk08lV@xBcL@h5CkKk%@4my>&ZFLPZYNIW_1Scu z^x7qu<@Tt)9dou)v!-rV6+S5Zg!R`BN+(eout}lZcSV|D*4v{e_Ov8i!YNgODv|A| zBYQ0@@P$;O4?^m*so^A*1hd}EYuMA0a0#dKCZMw{abtO!sVut^Q!?_Zx_)<+0c=DLCPld2UGd1AN0E_c+!M3nk$8rZg;VAe+n2lliC zTvAyo+@;`x4sJ2`%{(<;0i^+(>ibXHsP8{%GIQ#0{lHfEg!O9!rOH^Bvwq?(4_};S zeNT)0S~4AjTR*WCK4AUCb&Uz7IL0+#6Sl1bNziEZl%mvEd`AWxcmQ-163 zPraFU*Y~ujkP6K_osAj8R}vg-+<^7B2EV-<&IxF*H}h^>;o#rUTVCk<$0wK+AxsW* zkn!Z#BR_iu;erO~okJm^> zAky^2pr`~71>d=YO;OlXxV1ilx*y-Epu}cngLminm-_X}5 zf{#0D0ybg)NrGAaEcefPSX*m9Xo^t1QKB(I^!0&|D$7*;)^}d?;j{keXy}NIo)g-S zi+CRpiUZgaE@_%~y^z-Tw5a@{+;kLXeR5enq2=jSVUp<>=w_9X)wBMr?`i4Jh`V6CrnDO2DknkSeNMAj%R(Vh*UGh-2&EcXcg(|zbI$DI@#(Ch{kS% z|J=3u_LJVw74ccGL7|{Yg3Hu4xFW4@Fvc}~R7dt|kovd2)whcDCo%9&Xu$dnts-4> zs&GPRYmDkNoKuj{FHOC{OiFKxe&w zqy3U#Te$Nia89__CYfu@4BvF+vHK zaQbKhid7ZC*AMb<63h*$mT{BM6cDb2<8k_^Kj5w}EUWO#ru(Yjgdj{h(tu4k z()6(}%$kz5A?B(AN{G28T*C4XUr5!~P;QM2v)slNX1R?kOe+8Ixpe6~%k}7`4elUM zzTj)5M!7Y9eXzpYzM#S+d(<}|t`C-K1cVN<$dU_+(Rklz&_YmVYFyudf=vj{2%` zVQzRr&x4*&pY?xW`l!5A&mO&aQfR<>?X=bBz11iMUyrUxf=Omx^6^;V9T2)<`sj7y z^wHqCJFyx&_4o5)Gl$=hfc&rq1nhOq>)N za7nd!?{o&5q+OH^Oh9q^XaZVa;e9o%@DA8?lj#_IyqY+H_dcQhL#AV(n|b+37L6~?VM9s5lY!sO$z!aHC+PapN4Wu6oo ze7#0pm0LPjeTDaRafNqqqP^bCyHq$`Za`c(DKud{W*dCLzv?TzRXba6I%)=EeYpKv z)E*abiKmYS287~S<+py|G5}wkcv5JBi5Y8OlMKx-FTeEzCxs^RRKE=18n_G~U=vRY z_5J#R3kCv0H%uSBc=~8?>(wt%e(UF1Z|3o&P@hYZ`g(=W(?^3$ur|$u7wVS|tB&kZ z6>lM(FFu+vXO$6xKt-rnRuZA&JiY{VVF)Th#pG>(IzHHf6`|rvhy?Y(4q5+ZX_h%X z(zafC=A%PgGaKt|>66gf zFlZQ|V(D*!ss>arD}1@?*oYTg0Clz26RH6o??y#JC@y^rP82)&6GE}7G$0fQl_i8? zcV8m;m!9Z%=0~Wwr!PXqy0rvV?NjjdN2s_BD?yz&93(=On_4deH?}z@v?>X?fm`ZA z2eq2ex^M_f3Ot^)+5lSdGxAUJ}?FbM*%<&e z1Uon?Dw+09c4>JYU4#Ub(hV9t;Yz{$@I_Gc=rE5!$tIkzkifQ%DTf4B!&S(FvEBKp zKpquAJ*J2yS_0MV%y&;N0oCHzcThJ%B0|eYB0QL6z6NySNCZ29D?%sb1?++Vf#M{! z0F-yh`A2$}k3>+3LHS682a_z}5qvxbg%d7eo+-HXTFY2|>u=W2w#vK9Ck=@87!yvo zgi$uTi(8apdr$B*)$e^%F+};Kfd`YGQ2&A|6;|$1iP8;uJE3mK+f7Xyp!B-$r3iIH z-fn7zW_{dNr~^H!C!pimW*TEaW>j*nCysH5P#4{-1XY4nf48psS@~1FP86%~`QNaU z;<W533Xj6IR8?@=b*ssqk6$4dyto5b#jA+0|4->&rj@j?Xb|ShZur4e_A8dHWvhhVty{cq|A4M zi5Jw)a|})62Mv|TQ+=PaZfLzBElm3QfK99XfgT!_LAu#zy~f-V>jO|UqXT(TAqi0G zvq^~q{pii&O)$%y(xC_vyr510?s-rGB?BTb%*R~xj3lUcr4a2kLaSn^^><5? z=QacrbgIuQ_x89XC!o9!Jc9}9wIl8ElsN#m?B`XO>B{adCvL=o^N>Fbc78;@A%C7`flVVA-e9LMr zrRdA;inZ_+@J~P$-?)-8Le-kC>JzvXPp(g@2^E(uBqyMW-k@9})C(1?Ew6e%FlLv~ z+GMoX%Rs~3oC&S{Bs(}l#o4(Dsx~jc-E!?AmAoEwvuwjnpeKbc0zz@Rj9sZ9LL0pT z0ijsxZl}~lsOD(CU#WmlR4EDT2gPgxLY1j||M-N^atByks&{||ipFYiqUZo8`e|S} zO@xYLL=)7hZ65D36`|r9-2_!l1R(zrDyC{9)D2#cHq>tLf`q!k3)0BC4PKB?H+Vt! zAyc*9Qqv-BtUt2V5?b31FX-qyydW(J+u#KqeTNrx zh|~>t>)PQ3Y5&*;FG%h+rN$F^o#+KcsMt#yp<=B`f~t%=I0F&ty}`;*;aYvo!F}k$ z*59pD8TWdd@M-U_=azy@)cPIBz$pa_5r$w|!F{S8mX5$5*>Gzx6j?8}XCzGW3j)lE z5y9Z|webosK>|B9a~M1$-94+I=~gQgT>|@9Ww_Dvl3=3Y=6^iJo8pSM<&+llU*wxmzMgeXx z|ND7vF#nZZ+hG28)mnn4YQecS-1%r%a%)%_HmpaWbOrpkUj;m5`397Bbg2^1FW2U+ zdNa7I9aDh`rJbJCgi%Tcz8mPiQk97YH|o(2ruLVOMxX&ENonx$=$|DYk6Jn)6pQx~ z%nj0nlc1BkgqfuX6h+jR`wQ0=1^P)_*x}YEpjfu)3)F=%q~JDbNh5rHKq$7tB$)N; zNxfiTnV)uPt)`t~7~LMGB2e4_*W4!k2b6ekk2-vYy^;}achd_LhrRmlURQb!;&Hy1 zj!8$FV3I0L1Pa>#17)I4Wqsb8{TRF?6Nd>zprlR`&>c4UAK26Ai`2wX&jI(d#aKBp{{1%~$si zfCeIUV=&ea8!K)`NvMGRkEFf}zkf^b`lzv{yi#H-`FI?0d%FEu`gSyUx;>TY)=*NC zePzGxYr1fFrsk=;sF!Mft7S@rJ*~f~p>U;8ldGVaM-U zMIMYTSE|Z`N5$4vQUG+S2_`+M$(i!3%LtXHs(j^^y!ZdQaXY=*VeBZ387d$91wa^X-7h6qg+G+iW5H)P&9uM zP<5xjzbAq28_z`Y4XBukI#2uU8y8p22B-sFiiB1%3-nZiIvZKQUrTzthe|;|rd6V6 zqN)lJB_)VJT}b0yXS$&8oUJ0dawHT<=OvSuLY*cu>tifLTqxY4YFDSEil;(PH648 z{5O%;3rFgHDRuK)FPzrus{tjyD8P__elhqh19Z7lzwbXVvB@^Dg-O8$-@=?4doD`e zzCO__V@Efw@|2`k5?beuZdw(3qkZMiXqoqpZrXY8=%$@(M>nl{N9fHCWI)4js5UP` z-O)|^)u>&5WACR$bpz^-ZraDmAV15$TPo3`4FHJ@G&ZsWTHB6pT2+(NOrhiixSTXX z<+wm_t`}yT5?Zev-L$v11cUdI(5h6!hPySf%p{?ecj+dmdJHybLN&etw~nvUKF`cv zhjv1|tL+F@iENMp+kBOcL8$?e>Ta#MWe-qAWB{v0ptu{s&bvRLWNf>~`e2d-JQvy$ zD}ibk+`Cu}w{}yY7a3W0afm?C#tM!UqwWFbh8J6_WjDOoLd6CUU#|*v!;8H>ZNrN# z)D17TT531E*h1a#VlRb8NmYIIb(nhP4`fJet8IO>!~nF_|Dz;5Vvi3;o9w#qrPm6b zm)m^>*Ksr|J+cd~1-fD9hEQ?mhMr#g$$A=L!4e9T)^TGfJ3(C=*14=>VGm0{s}fIi zxqSOVpp@26Ko1NJ*38h$ln^204VF{&ZT%V`?R-L-0^_u#Wy;APBYv%;6N%IFxELDL}h~dzdTl-$g zzk-8}U~iNHZRW74Z5q0(AH8LsY%fcgWCkUeWLUT>QkD!H3R)zXbglevmjZ-KmC#8S zHKCI#q!T(Rz8cVp-QWS8IaIZt|@6FTX>2XtcnRzN2{A_<+80ZQnk z$ag{~y&Vai)iH0~BNZ*Zzi|Pb80`qo6D{(DPO?T4I_d35=%lIN37zzI1aztq=3SNo zI{TQQ-N-j0M$vK13L>Fo&UJjqrJ=scg?bFIJ08_*Iu>Fr3)lWfI=PI@~6I(c@N z9k{mBWP^mh1N9gUZ! zCWO)hpAd?b;sK#J@GRi`Br7bTleBU|Cow6YQ=9DGt($<(o2;;ePSVN=on(b2bdpw1 z=p-vFp_8<7K&RRR-(@MF6L%OTbdnX8(7C~bUu1U-Cv?)=5u9fyTQQ-N-j0M$vK0e5ar$3C=S8++LMOc)37upsCUnx< zk?E z<$PacD<*W(+mW0n*@_9B^mh1kDq#$F)2H*o@gfPGWGg0g*2fvH57~+do%D7D=c!Rh z?{_nx6Nj}Vbds%@&`EDcLMPdZ37zzIBy^Ik7|@BMZvr~M7NFF|73IQ$%qMi##~FAP zd_pJLiUHqokWfIUNFR36Z&Z7St@ z>1zyDu^oc@iIVdqTQNCLdOHF-XMLRE!hxO%on$Kp=Q-=+43{?Oyvuw-C%qlPdE$uN zfXFr49BwI0{bHjv1nV(=QCUnx<5u7K^>`&;V zwaFCM=E(6Be~pwmj}Va7Slw zk1l#Uf_tPOOSOMAaJfl9=Y|Q3W5a~SA*Eb?p1Mfyn8|sPtr*DXsE;#@4HFi}h6#&f zlC2n==cKnI;QJ(7F`<**j)cw)afS^O7RQDOi(|ut#erM$0={eGR=Hlf$yN;L+%REr zY?!b(7QG$8JzDkk3}eyTkZq4a@zb z`JuNXpmW27MVTSxcHKP4Rt)%#d-am@BwI0|lirSi&J7b5=Y|Q38W&W5k8n$2a-L)> z27JeLq5+*7CM?QDsDF<(Ojw*7CM?cIwqn5dMsG*J_YD&k=Y|Q3vy-hDoG0!iOwN;R z#e`0JI|4d4Ojw*7CM?d2Y{lR_wT!ad{@gHOabEOxBzz}ZF*wf+6Bg%&35yB^)xSrB za#G28(%TX6T@L)a%m;K%>bVQ(+%N}nZkPi(H_U;YlirTxJU7G{Hq3#X8|FaHo8FG# zJa5WL1^4Kt7BjEdnIgs~;Igq#3!MyuNU&8jc|M)+@{_>Y! z{`Wup{r~*?|Mkm%{oQ~5^4EX+?YCe5<)8lf*MI-zFGBe1fBfy&fBfyYfBp4uzx-vj z8>N}*gwhM^rUFU_y?qI# zbHk0|kWoPC{n>D%)GJ;ur}v4`1E2e<>fAsn&shm5#e(yM`870i~TnJqe{eXUFHh9#aT(C6rDQslY-}#JHSNRV+~bpik*D<8uS0 z9G$VbuVMI9-s^M!`fz_)Kq)5L6Gq{LnB?>C`Wtn9R{f2-G?TPmP7j_=>2v?UHr;?x zM<=r<2zXov`sNAhiLu0M+0WFaB1IB_0JY;BD?d1+r;ncLAdYmYO$hACgjsT>;aC$| z7nTwS$GUK~WCF^~tA5OHXxayyYQU>;a3VUOwPB3HKi1I?$|oeCJWwL|{((ky!Yehh z{@=8nNtWd{3Yk$ThOc#D#KwHBd!yHYLdAVn29>)g73xX#B!2~vHUFB3Elp1}vSutHSeB4=ZrBYZ zWStw%A~mQxR=_CKyW#zoLJ$gx7+DYOIZ>!M@zS84VXt2&*JtJ}0ectRZQd89LyQ9c zp*g?KiRZ+Tr*)n=7uG%+P-O4oTV*h9!&^Hk0b=h))&s|o*VUTREsC}n&_x%a`TgOT za9YK=S~m}|tDmct8UvuNLah`1wE>M|d3UV!Z(7X$l9^ zDr@#Z#om2|is@$c!7gmNRv+x*neXO+Otfb{> z<_;E%+Z-(BdADCRZXDf?jeNM0HXZdH$AO#Kl(fn9fxA8Ls~D4yZaIavS4;f=P+L6B znjJUU9{vTYHD7E`Q7&*r1-s#C$Zc0Pgnh#~)xr>hN>;l?^`$^(Tu9mm@#Gp*dWtCx z;65~^0W8q0cBVaQMUtdI$pQ>0rVxd8=AaU%uFmMUC8HfVG>tUc=#K7WGkJ664$ z=f{3xQJr$yDOCcGrKBCnczmzgaZt)f>0o4>%e$}&HgU<0+dEk;P_2@7{W`*3`@&bV zlNJXOZ+|1siWm5ivK>&ac_p}gY!Ui&XmK=eS73X^%xsHpM_?bZ#z-jA8E16xTJ$*m|*@~a{S zb^dUxibJJ$mr=l?L1V@NCeRImjpx5tZ8cmdzwm8Qq>~jx=fbaUi5kDlY8(qkxXbO= zsRrRLJYiT|$7F*y)X<#FlWen@U#pcEl9=wX?A@@~6baD*GfKnXZXyC-~pg3A5-Y-g2?DRLH zrcVC-3>Zn5ez;#k)+Q|C-l%GefJm#lcy2La8|CX{%T1ofpP0i~<&2fui0i z$wvy{Zl?(1-#Fr035!8|q1XGMxUeySlp_FXHS{uNWZ+qa54dp{wef*rfeoT!b)FJ6 zvs2$`kkKlRc~Ay`Ez`-olSQCuTzc7cIm3B3;Nh%hEF zb}HIG#PyoRWuO34f03d;5>~-Z%se|-?C({u3&SD~7RR(XSfoS-Hm^dAw>IMh9h{h?{#K?fhIoJ%Bru#P64FIzN1ZZ{S+~#<*0k#D8e`7iQJ)@VG8~cqj$j*a{#%*8L+Fpgil1$!G_Qa}@SH zzNczh0|$c(%?=zkE1pT$ILWz+baYTL!x`sORx298sz2$jF(_vwylc9+;CdNG0XQ7} z7KW8At>jsYFl^dA2X3fFk+G7Qqo+$WU4i;k&w>VwAcj95UMNbeyfX~?+ zzd9;gmq5iKbNg053il5aotev9mv+NpJ=<0v$Z%))HrVXnc<$;K+i+HT-FIhHI)+Y# zab=t_+z6tOCd~>&w~PYtbu2=s_r{&gMy)s&@cEckyV|j`S~S;WKrlVIL$63Zo~}Qr-L9O^7qLd!h#rat)B3P$>~Jb-x*KzPBM(BSO{&6jVlcqb=YkXtTC>!|NYhLQ5Ztnou3>cwwFRXa*8Il zmugcAnAPvwfD)58N8vc=f#guX=SJhex(7iGg4%LwQ>p}~RstgB5-|{fB@m9tk5=mVm16 zu8XrLf^_EjO~$39y)ho`U~yQXVlm?)H(TEdy8Xgo$RTC~ew`dmoRBM`yklb5n2GX^ zg}vj-5EdrAL@Z{6aDk^4)M#NQO@Y$vWpmeN%>&)Fby?GmN>LL9N)+b#@5TINDt73^ z3boE`mjbmK1z_W(;2IH?)T&UC7a0Yd4O!nT`JgDbQUJCi8U^5<6SFWPE|3zbM%GC; ztWqnEn>NQai?u$#1!m^_f)8+_cASAse*;;C1#I{_-1d4FIic7F-@4(nRiG;hBoPykfw%jB0tEmLc%-#=TdDyiTq-SJEau+3@h3b97{qvLl$< zuas^VcFGvo6i^*3oH?wFb<)F2 z9V{FVY-G(?6}Sh4VO@#qy!%!KO78+=tvs5-9M{b2Y0xTGZz==G#<%xxWsYmct%AQ& zvf>;hg^K%f%yE4h$lvv0EntkGtvM31eljwdQic$h|2iIlQ9jw$aG|oRit9pjWv*ujTG~->&8HqF;~n* z8BiQIX*}z_sKVIX0vXH!C(F2&>?|f!p;sPasX*y9V2*3T`k(-Ximmv@VU0nr%tu4j zfw@cLKedLy(LtTw3P9P8<(w-UE}nnd%>FHq?Qq)`?h~xwJF<3$83< ztuxQecWX80b>1YaIRi5Ta^GbYZZL^RP=GR4?A=hP4OMhu*i=Qg1Zi2AD>QbskPaJy zl}Soq0>Z9VL%rKdE(_wK#;j7F3cugn0t=r5#s@4+Iw@JXG|iYmdLiEZm68>Q;TlmV zQ6U9Nw}1krx2rk=n8H(~vE@Exq5!Nybf|O)%z@o;a=AHL zJ3ce(A-w1no0XKTxR6bu;!+>uT=wluI1dwtjsldVric;E9}@b7Jv^T z!-UR@!WZVWX5I>zfcjXNc2pk=({2hCw}KcGSf95-$6euyOXUQxV9=oc!;GXlYs)sy ze2X_KYz|hcrr`*fgLVD2^S#Mx4%XF>cg%uM%sZNcl|^|#+r+`Tuxnj`Hbn3)Y};4o z3e&C*_4&YW##%3Eh*@Dt?@9Z0!vW&yN@#SW&tkLpxNyHuORUCrx{l4Ig z^TUA^#sV_s7s{Fp72-vi<_wIJ(vHRpjGM})jRo+2ow{ck*#h$J1PFV^;~aHQZSfQ(5L@O?(a*-;(v4V6Wn2rD~cSwn4?6U?%OBZa?gcUx zDnIazV;e7!0&nuy~_{k#%7eoYS6x?SOF#9Qn!GB62%h6n(71U z^bvNIG%+ba$%;F(g&WMPm~L%BF!Cm%aFepu?^}IRhKV@`Wdg`t1s8Z~M!{i;la=bW z?+HeBRujn{D;kI^-;dhUHA~bx7di%LEgpiE_ARr@hkIPt14i-D#94yZ4P_W4uc6_oM_eCpd$3~G-2a84T3N}khI!;-d^*TOTR(8Q_MkygP zm^)6{!s!)8+C7am4WDdJ-D|@q+w)p(_+) zT{}M6k=5J{x;?QD{5xI^}ma@8zPj+FXOX>FBDR$ssF`K4fdBmNA#SWI( zUon}K?a_3`1jA3Pi+s2d6~_c9Q87VdM8#GcB`T5`BPtFwSgC3&8&+BZ=*TME`@|=y zIb2y8OHT%|7HPXLtb)itTvl$X42jVt?Id71I3phB_rSc`Ufx8z1(ix6%B#5pigf@A zl$e16rFWPDCEBS#J3iFkDgQdylNWx+nb4Fij2p~+PPe$?>1X^+6kdGF!?(>h8iAUS!zfnQRXC!>`q42)=A9B)PRP^S1y^3 zsMOf7tx4&2!(JH$yCa8jusHTh!6u^IaLUGkLw}UCCw3z`SnNhqut_v_oU$||!Y30R z;cA#GI4;bt{3*WpwjVdIaVcLn0i}nMl64F^U*cm8TofpBt&x=M>fyW9k2NuIr$8|} zo#=I4RH6nVx-n9C_x*95JO@?$ek|)&zyF}jtwQZ^g0sU3PIiLERy*RGBfT9Bwur;G_ejnz=r9Z*Wv3eTG0CFK1c1yw!k!roEQLO(LS9zK?+yc`)$ z0%t&x!PSyMnwbFz-^)llGrAa5t6=j$1V${Z>*+~^FDC3DsMO~sVkI-X!$AWMmEt-| zuRQsr9*mzE(9od)ybqOL@ui{kiqRKkujx*Hzq*tLuwq=vii_QptXQ*RzSjPuTSmFU z%ms&IP`_srgQS?L;M&jnDG*iZ6{iUZS~&NlI^Iu#vDYO2;f67^aPHXYBxun*Fi0jW z>)0?5U8mcjMASiNMEyIDZ|MjT$H*`N3g(%kb>LiR5y_dE2@9l9$%elZ;iN;-(;jdZs(~-3^LwbvA_Z5_6P&#JL93a2@s2855>xK- z5a>6?BGj76t;E{%Q;Lzito7@lK^I2ywoAy$1E8XzvIcNglbC!mFQjbyR+UaEaqEH9cHCAeLxGoz(ki9~6e(iMRH)c-KI=WUxd*vnAzS z1KBZN=7SkJK(0{Su|Xvji0d$P;Ct@6^3DRiin^YlQi?=W;H(`3uA)>Xe29|IbwU(S zDwQ$CLhB!DkjyDKaB7f}HnR}HwuEML$HE)d7{P%NM`N(ZMK2h0xQ>Pm0qejiqsC<& ziR6LTj)fE-@r#!|D_MC0jo?`+Z2@x?XMlG-i_+QjJkb3zNBv`+4atmkb|f>_iOCG} zt#ISJF;*^Z`3p%@PgeGjfyY+DVndbDEB3-GQE^R(5f#VWsgHH>8u9vZy^v%YwO;ss z5o+av5hW__CO2L%FA=yqk{|Ciwl0)v}a#@lsx40pp}2p!`+GQr-lz>5-`{0GE&%wPF{Y5;a3B z-s23WKQrz6*g?@} zr3BvaS^vIFO5)E0D2s8SympkVKl(g5)CS@^-<ZSfb=$v9-X#VuV}4o(HU< z$thGWR5BXCC!>><-U$wsB1iR_s@N;GMJjtucP!XzZlbci{=@1=ftn0`gREEvshrjw zjts)qx47hH!p=BjTQ?TJ7~A3?x{?*6a!yvd4V0|76}NHXUc+Ud0ES8-=?S=))o29$gBQ;-(6e zxT^vs@~%LMwJ1?I{BJpmMG1N+Oc%!WG(yH(WBZ(x5DV|PYU9HFm3iA+}4A`u8n9KCDl_;^#bNVd~j@DxBWnl-j`3S0IgkNImQX+w-=VS-gj zN--KmR-Rhlcdwe_iSnu1Gb;Y`8!({XM?V7kee@%s6#WohHK^oO6e@PrpR;bS8HhuS zy7j;NQQ#V+y;2R8y!5mMc*$kg^CpnN(D3g?R#Ofurtp2?fq(mO`i(AU=?fm$beD-H$5oW1l$`mdth!v3CmUV=7XKMnn9tSEeGtv$E?z98uuE^;J%2> z8_nLh2vezG;Ji2mJ3|iM9j(#9#7Z%Rier+L3ep%0H<*Dve>fmQ=pdW*=mt}$8Eo}# z1xf{5W)r`|8ew_MX#HJx<`oK}KIfzug*%_h{C5QyQSnYxqT<8Wh`LiMN*Ms&21ZnD zWY6rkx&`ot(TqYBusHMCC^k$3E(4KE$HwqMpkCoe{LsX1#8c}g>sM0Dv3yi280mJjefT0l;S@t^Wm%xd{ z^{5Yd-OmeKq0L4356x+!)8)LrA8Qm1V1Kc&fxO?o=YkhD4;V?Y4O)SIUyFWT_--+6 z1LuvGfP+PcWh$tWjiHKkF=pY+iUPW`>K*py_|Zf27LIV>NFVbe;#Gjg4`yIiPS0Cp zTO6*@ald9B1XzIiR42WN|BB425ACsN^Mg8C6K9PmX|rAn3aOQ}sn5frhg?Bb-DWH= z*nyGu`r$@AquVQqBe-Ujw4CBm(ry@rchVx)P}1(n(ZBmHCGC!JT_x>-B``|bgn>v2 zPbjf?$}S%4q@;b=JbW@EZOZF9PFZ%0kgHMB{==Yw`mKAV$)1#8q)n{?8JL(6lSNiU zJk%*0H?mJ7ZJKOJ2}ZY^?oy|0;v(8nZwFprqwT zlY!l^?av8NV&A+%#Sz0w1GwkVTnCxxPfZRA zHXV5l*TFb253Ho+C1(zH;9Eh^m~r9O7$t31UUq!4hkwIE-zecB938Njwo40h-O-Gl z+?RvJaeDPjJTWhN-Tl4Os=hX{!Mc%kCRz>jur6yr ziN+{d6Ub?BF*7SF;dA{ti=xG5stm=u(ic_s1@pw}Zqr#hPu%%rZiRXML#(H+gX}&8 zL#T7_RCAFtP@wd#RiJboC{Vh;6==tY!U8d8s#zrUe#0o(1i2cRMmiCQ9GY5=bm&q4 zjCg!s1z>|6Lx3T^nu56sFVd0m-qOQ0-npgdK(U;1R}VVxCYU9B`Zd| zjRG)OAj)oLidoREjId$G@4irhk{1vKU3nLf+csWcU|d54x1Q$)kZn=eIuqdpRHK1^ z*nU?Jnazn^pTe*bGzDulUVsM!D%6YaZQ}>C$Dl(4m;+a`4kVh!2Jp=-HXO~A-@(xm zqVf;`b6ywjAyNw1D86eHfX_Drip?m-Sb2<{aRMpthFe?7iWy%e>-GHATi{LE6>fc0 zs2DLfhLtkxcLk{9I*7VERC;e41x&hJ6e!K|Rlh%zXWze-AXw=|p@*h8uIq=9S8-f} zN^x?9ib-^(0i2O7Y#>+m_vRWFJNo)?mpctMKl`9&o+YE5!LY=6<$gg0N@UnP2Xd~!0G@+ay#R?S$tCBSw z`(0LtN^a0NtaIzIf%C6n_3fQ)F2WPvnF=+tr{BMpVOZxu(IzD;zFviI$)dOKnLws> z!5L7JHjuWIpTPH5=jtYUVSK=eb-oU@<2{t+K|rufv@xZ_@U_gjx)K=s-UnRSN%D>= z&cKDEWEALQH*fx0fp#2$uq!YCa|EuV;|OG6AshiED~>EQ&+IE>#okT837#Egun7$&V}wxZSVYkVG1 zvMQxj^o2&N*jf6}hT4@F1z<$eh?>nw@2p_t9xjWDJ?7_jY-QXmJR`p4aKpL5V+lW) z&DA8Wu-K&H>48u;gMd=-O(_6lTISZ;7LFe`u=@{(mx@Nvgb6MR!PdXmo^t^7SbIoJ3Ti4@F&pntDNv+PasIwT zr92WAn8# z^|s?{Z5=FQ{|kP6%?bCtgJtj>LiM#eqIvs{(L5(>2g}G#*^aZ7O>zxB3+K2fyb&^iy<|cMM*_ukbM5t5Y34?v zYM*c0KDPVdxDJ5V*uaY()&yG*Vb;3?sTwm&7 zvHaM+zCGEsb6b zXsv?f0HA{9n396UFom&%Gi3}7cUkI%JLtz5LufcXZFLk-ssp9ZScZ zv^WgI!Qz5k2fI3=A9?Lzq}_b7BWwG}o;E$#(Xf!1roS(&DMIA%*O%)#OW z0|$$3@!PuMJBu;VE4%6GelWOqHu?gtQNx|3ZFE5>aj#zwZYmr=UZsZ2;DLPMUqZ2H z3?ofjP&gnKw;f~K_*T!)sY<(H{lC%e$WmlbLVaOTbbxg^cCAS@~|TgmZ(?$)vC)na0Z8y zm2w!yV`W4=UR^>1I7V36)`^pN9Bf9h00B=YUR?{>umndzi954z@Lk-;sH;XhaW0)h zrGiR>`s|kYUIU3K(oqn4U4Jjwx8fwF0i4YDe|({61@kzlL~S2s+X^Z`|f@A+t~kxcvjuZ zc~Wnnxe=3MLeE{Fc64N8Ho1b-DAeaAB*sGzaHWM90`Y>a{;HXoQHHRgIYm==u5h|- z#W&0DL3CaU7E{FLlV#yZhb62;3_3npj(o=_%Lsd7bLNvBm~T{{?7+mJg3VH|j!zbf z)bYtqoZP6CaAESw!D5z4!QPk-aPRsNU!6rZ1*YvEoaiVnqG9Kg$}xQvSNExfbwZsLLAEje@@l73X-? z=hj8m^tHVEg8F)o2bB(&`da7?%SS7so|LPq$CHD45$$rQL_O=1>mn;oRx)bE)kzAJ zZWskhEKb=fMmdxZSa@2?zBRRjIMdq5n#qO0j*VWojq-I0b*JtPrGbMi%Q%7UAcs|t zp+5Da#9NfC-wz9aL?sgtUSK<^PE3IkZF_!6jSA)WV^&caE573tY90kZFO0*&B5EV+ zKUA}oQ&eY)q8h9<`6q}=3v11C&ivI|u-kxQhR*mE9!~P;r+Tn<>^M}YI1yGED@Mu` z>P^OKUIRN0B`}7Ck5>gsL0AP!k0JG`u$t8np&k28jjYe0hj-6nWX)-%r>nSI4s6R% z8o=F2!mzlW!1&fIHvzRO)RST&Mgf@NQJ`d2hF>2TW>7}}i>vCZqt0JSBEbTbtp6}D zLa^Z{g7fZMgbh3-`yJHWgHI>fJE{>i_52N>^cplyFuO_N_bXH!F>9>##HuPKE50%n z>P4(YX#gvgl&m-iRH5QFVRL7tDjMw7oL8LKsT8oNj-!kx>9H$x)ykR4B_i8;)ywJM#n>4#Za)zz#m+vM1(9#UYp% zMp_K&-Ea|3%;qXdiC>Dk>5LG@r;CF{j_qIH1;1Yx)qFsC@I9RMFaj-o6scvK`r^p1$&y6gwIE7j%fiqMN7K;lN zY;q~zU%UzUUKBKN(k^DSb+0fN)<7s}R|i*09Z&~X3Ty{gx)P-(u4Ht(Hq3uGSROPd zJXqXfLvS)13g#0ec}s&SCFF_MaF?yztUzy-v#>0J~USJDpL-r--c07M^PzhvlQU_fYrTam~_J@%N*ej`jJ;z2mQ!Yx`yOS zdRnve?)xXnzNMe10X8*N4R_g|nyQ9VmNnTO(U1MOI_SrKtPc9IpV)t6Tus){bkL7H zNIK}peqo2NQbK5c$0@t74*HQ2!w&kf4=jaJx*fBFe(ZDapdb6h`c0*TOp@quj0?M6 zowOZQR(JNrbkL8?edwSc&osz}Pj+lL$liRiBkf2H^yAoZ6qu6sz)Eok%S$Hf^$B+t zVs_Avl%96bj|_(FpdZJDQxMcA%l74tQ+EG4=tr^+9np{D#_2^$w}bb?n&U7=2mQzz z&yMIvS_wPoM|uf6=trIo9m$ttb(EfFZ9qrqX<$1_PwxcWJLpG726xbpP^Av~aqbBv zAK6pWK|jvXQF@y0%8t_0z;=|L2DYR0^gdTd>1kj)N>A_W*HL;J*pAZE``S86PXpUg zdK!|@QFc9fnb9@1m>19np_F8G?>amYq=zrz|m`j@pmBPCJq> z56f?Gj2RQ&5&d}Pgm-+hyQTE>zFSI9@6l3vdXJXU(+oE6pdUH99rWX#Ev2XT!c8ZJ z@B6IgSVg>yB$YM>1mchchHZd zx;yB{I9p0j$JtVPI z>$uBSOX+Fe=N-|H`D-aXooSJ6c$dxe1U7uKWQsbXA9HIdJAr%DLtL5rSvqVoE_1R>@Mh_AM4jrdb+lj($g412mM%kOX=y_TS`w8 zuj-&5>u4!GT}Mml={j3VPuJN}db+Nb($nOhI_O9IVh8if+=~^A7rzyGYC_N2qN9pN9nj7dxU^_}rGw`CL^fa&? zrKf@IC_Np&qoedRupOnR*<9RFdK%b{($l2NI!aFi+fjNt!WSE&AA#*CJq>I}>1pEl z9i^v%?I=A>aYDz`(`PG0L-ZpP13OAj1KUx08rY7~)8x84N>2mZQF=PE2dyFb64;K? z)2zShC_N2qN9k!`J4#PSVk!;MkHB`6o~A~lqxAGC{b-1OWQci3>1kj)N>2mZQF@x} zKu76mU^_}rM}oo)(T~7(l%A%xsH5~WupOnRPbE}C^kZzRqx3Ye9i^w~&FCmS4Qxm0 z>Bwf&hPfYs?I=Bcwm@~zkE}~=NWMhcj?&W<26mL51{OnIaC=s0IphynqFuq9#Wv>R1_#Z z>XlNl=+B6{5xFv^%7f*Us0~i#!ZHyfX$C#LyMF~rPUVjxR!K!Fpy8@guoDXig$m}@ z5hvPb_Da5gE>Q|U_GfKr2P`ghcG6}s-S^TSzii^_fX(Wmci6glJrl{{gDFsY3@K3h zSOzq$qu=YafnKN3l}?uW`E(O1P^zO=pyUP>==bk{d?>nHl%(Ik1CFFS!TlLY7dbx# z+Rz1*L^>v-64WTiERKDrk0to!ktiFu|0P5{=uT0fbgUF85f%fAaeM{Z@u9Fr<*#V4 z$b^pr+w0Q$UN@^mZga{%URgel%%}y2H6J!pRYFEAbx50;G9axXtw%~(fwH8=v95%F z=_fL%6cpY!fr`DR#=)k70L{S2${9$3nha6H0UH>@7yfWy@wGA6RM(LLgsfri0IU4r z#JgL$f;82E6*y_LFqL#GK3RJD!Eq^2Dg;!Zbh;EMxfcc6@YY&5mPScRq)>r2ytT5s zAfmjHm*)bml8lvQn}BLS$z5H752a_QK~$_SHs2q)kox^tCGpqyQ?!71KQdMai^Ugp z#bzT0xm71?CIWnY2r@c}a%6uMoaN7j-7HE48*Z!=pDQathzM+TM{sWV=rppX`sCdP z#F;(0yi1{Gv|xj**qp0m#aC=9>&jQm8FOv;TziJeeXrOZI~R;%(~=5K>l#9@*n@W* z0yRO0cfE=e%iC}jC`AUg)2KB)>fb8>r$reBEJ~84n7?iT2NwGZSrf^EBVa(0xR?`= z=8_Ik=^jwOpCa1o_v7Qugc`DHiiB0LC(jfWcNVXhHk!?3Bp?INO_rMcvfN zlf1WKgk_HL9F(dKt~8{-J8dN`@8lF=;#8uL88}qD4a^5i$271vrP&*IxC?)nt}T$& z@T_cYf>WC|$GXY>Ll&lMmIE$n>gr2fKs~46GqES66aSAnP<5z!9oO0U4b6u2w~gA}YA7{itV6&rCIh z!=nBoR$a~V)@|F0Xj$Y8FFCZSLEc#A4*W--87FqUv_nBg#%kg{@$ z?kZ__bY4o@ED|CE6Q?ZoG{onXv>{wzU@1GU8(7|7hvH(2+-B+ zb=GyIGnkYxgl_+3<4^t4$qGN@9Y$DeJwL>o`5G7Hkp!pDUO@U_m$-7SiJBEJyPy)E zQ4V2k^jdPTn5H(cxg9&0QU)IrQ#$G=?EWQi@Xl!JS9w6O{-N#>v%rvuy%9Cz=H7q* zvwI+?&(4E%#JLJn|6`!FUEip?XJ6nfRY&)P+ZNXKEY+m5+Zp%qKiF7O2Yoq6kgT+D<2a6S44wf_b#u5@O zfO}C%d!H1Wb+FhpXWUBwMW7+W*sUKB_r+3){2HtHe(14pDeE%ivBAlY?yI&uw37l z;k0G8G_Sv=^tXO8kygn3Ch`fpk#;5HOcoYXDKf^OB2Q4L^llQG%?=29jyP0`&?(dm z2m}{y^oku-PF8$17+G->h?12ZqLLN8w?W0y0HuL}_o9-O@>NP!EbelsNRNyL&~GbQ z7ZOh;E3#yPn&BP!tB>!)tm4CXkCK%V%;sxtxI@9AQhL#$QmR6sa>J_mTDZ{O$x19E zdw1)UXyY0w1G^(RHkrWe0H#Cx$C|3VkYn`cT@O%Zt1f*qGZ^KWivjO&rQ3_EJnPSn zbzxzIFxspaf&hmBMR%w`=|)tbM2ZwB@nQu^AIh03R^BPt)G>7&tQ%K>n`F(pIn*gG zuX}V*jXU$Bzb9MwB&s3Cx@GDV+id-wO;1sWZ6y;3WmoDX#0cO)uVCj+-q68jlKQ)K zDcF$tj!(95*rk&et8N5rBL2u>94x+-6>J3l#b#Hm2(gwVbw_X|Do{GO z3bf%uyl|Ydk`xow<`7&s2H%<0pnQ)}0j{|=pp(LT3Y2Of6ewk96==)7_4KE`Ux&)9 zlA8p_A}0N%1_bx{8V1V&2!*;DJl2g#G+|l^KY$JVRlQclTX+)!eg*|#BpR=mhgrL9(p2uSymHdE0O`H9@(|QcLEGrgN)O(0hUxtlj zMy(Cu-A7dVSoPdwQ1MY<6o4Tj1xjJq+n_Fr!V1*whaCe?pt^Vj^4_8FwgJt)vG>!e zK))w$8D&GnP5703C@MC7D0ul(UG%Axtk|rtP%)S#97{%Aff8pC zG+>Kki7aoF#TY=UiQvLE-fBB25hc{ht)2>$Tz~?l>q>B|Jj+@>RoYU5_-It|{^e-FRknAMKu6Xp`!|JG)_daL-I>eZSNaNw=PY0WkPI05Dk zOwJr0u1Zv7tVXF6Xf)CG%&Q@5HTTty+t-z~Vo8emSPiW^Suuwt;6_yJwOaLnP)GpP z>l+J5;tjl@v4AWyjo#k;l~60M6EL17drH7x8BsI;27bRmy`C@prq#!vRd0afQVpksqO*28dg7OMrNg$qi*= z7iF>>EH0~2u<0`dBXF=dNJPPApes;U2aDqt73{yPGZv>IZGrH~6lgp%ead^nuRr45b=wLkxvm7g$|if{kHEIX zHp{3WwKMORqB4Sv_5GZ~Wjz2z;l%}h9GKq~MsVPyA8{*2RQg!T5ga%-UD?37qYc#K zg$M5w5ufYCwZ7(aWl1EQEhQ>NHkBVZF=Vc6;KIghm7n zc4+T`U)?9@;kbN2r-~c=)D7*H^)x>^HD z3Q(XFH&UP!;!_5IOj8*EvNvS_$TEyt8@gjMFNc~rm83+6j8aoI0`xRi! zYTM~z5o*nQ8$?y0R0XF%=~F4CB4<-()v$NsDFLI4Mevnt!zlre-i!4#K_!1}OaLn$ z6llk>!Y&?TR>{i4VKql!$A%m6c)QXd2%gm#>weJF%@}La$DmhXS33^5Q=kpUYR5O5 zxdeCIRjG`1(5F%dD|wCg3)_6F?7C|JB^sn8rO>ER>VY%<6e`wFJeOqkx;ilEF4UUx zG;o0m^!qUxS8CqiacR!#akZFLM`Sn)+9_&buB(H`%L{IG;G6(qSE(WS-UTLA`n?NG zb08cm<5yDh2&m=~JaI~ZIap^({yx81;sP2B01MTPsbaN&`cyXsL)E9krVVARI5*O$ zHLVrjTNTe>tKZg7H2hsslM%Tt?2&h{7`j)m2{OXxaHGApFetgsZSP?*zw825*zNao0|=k5-yzFuVC-Lzxw(vyHoVl z@yRj|zT=Y(-07rrI~Ik_6l^94glK>M$x@@$@yXKN+wsY=^02`%4z98`pKSatik~@H zoY3u$ZA&use?FaIiNGTvo7|HQ8{=M*5~2PT4qC2mQ!2`wse%O%WaRW27as zaA^H*W(Lp~_E#E;uX8PxGV#5u&lE7j&tkG?HiW=BL<|E*&PA4tq{1t2ln1BC_ zS}7`TU<BnK_k&Wx*-@&ovdy4@Ev#sk*n(0* ziYhuz+1*j9u|mlkawY4^^nr%E>`K_GPZeInv)d_rER9rWYQI^~8>b|-Ar@yYg%QjJUt=qS}#_t8-c2n z(Lq1%v!hgFC1BH#D+z2zsYc#89iX*)_aR;KKA(2tZ^bnPP&V|0{i z1U4`K2Hidx`VQERQjIlI`_OU9lF(=fSdGbPnmeK&*=5xc{g|<@hEtZB^p51qJh@aOjmGE8%`dfjUBgP|m>NolW z%Wvtba{o}jH?Rk`f!_wUgWo=|4g5B+9sKrzZQ!?o?clc$Yy-ayYzM!6U>o@D1KYrF z1KYuGAJ_(d8`uth`@lBv+rW14+XuFR-#)Mn{B}=!RRh0$U>o>tU_1Ej1KYrF1KYuG zAJ_(d`@lBv+rW14+XuFR-v;&{_-(lW^?_|DMGkC+?0z0zdte(%kssKGQslti4W-Br zY(pt>U`InK@&k*d$mT_osj%M{7e(56eIH(XU=wEiI=mLxjBo2WWvPk#{NcanX^L-Y zV+s2Y7f31C4aY+|*z5b^qG&cWtmBjIIDT3wVaMsq3iiO2Ar5wYA70BRONnU5Cp&TD zlTyNkQw<&L`F(aTy1ixx{doEUJ3iT+#_{iOhkb0{*ET;+{Qf?>7uYn)Hr!=}Y7MinM1#Yt;kW&|3AtHndg+HXSt`pX_RAt%|gFLu=Io+t6AS*i^-J zIL4F#b$qhX&{`EG%!byg2ezTLDzJ%Mc6_qc&{~xN;|T{g++~^dNc3Y%eOnkxDLbDS zcFr#l5C=SSfEzyB92m69!mqL#(gxMR$Y)Y?PuKXzJgRvB7gQcdM3LK%4H1+cD??wgM zV5yny5K-O+sOI@scPiXDVib_}@ON1iC`FwtU=)zn-Ud-|mX#4T zd4dK}xnt=`iC3Lq#>>Ft^?rU$6*e<#;DQl~9g~t!3X}}%Z&PVi0Ud)x!(RSjkf``t z|B!()s5o$I3%98%Hdj5IuBU&tjEZk!lXY1s>4jq;cvhwn|HE*wRaHV@v5_Qg76NwC zi=+O<@-+C7m)(z17k0yWDoO_#`wE7zWi)JE+>RwR`}R!g{r=ezSnLd~^NpZR%J3>w zEUq%BnVAUQOQGWEm&Xm&eB$=Iu@+yUV)2hc#pZK`$_{ZWUyM;~T0-9m;$~noXA2Ik zv8}PuJPL)1(_R(oN%2yJiVbB773)$ID#l?I>g@1ZgFEWP;Y!*J4%hQMulmA&s61Dw zbhebNT%l!TWzK0(c}S!}B~PgI+R)uIRwy5(!p3@I%uwnfP7W zaxmfnrI?(PHJ;{sSusJSWW934K9}{v8NW`}gKBDo4O|@=x>P!2Y+iY;8#8ncwxf+O z{;;EsFt8nMgpc>8M~%{Lc0zXCxTy#SCzGnK9POh2PBrNFjy9m=XzM5Unez;aRiN}z zFrW>NYtNdE&u_$l66;hypH6@RC7z)`Kd&y@qSMcd>mJbW@9lm2KKUO>G5K#kR7NVk z)0Qn|Cw1=^Hqe5*_7>bDbFDk%Jw|2#yzAH8g~vGQa&fSj_)@UhrT`a=gB|3#j=xz| z#hd#~=O~CPnr>2VH>kqE!Dh?byM-y(tcim6jDt;2YKOE*Q+2>{613iaw`CtLHsC1O zovKaLCyTG?_+$wpc6_po(FZoCl#t169j7eg$U9D12EKKCvV>zgKH1EC{)WT5Fb}9K zVPVS7!D4pJ!D1rJz-Hkx@ec=^IZWSMLT1?z$9K{uf88PN>YyK2qO=XC?AneF`jOG; z9rPnr=^gYV>Glr#ksa9-nNW6{`G*~+EP0TIyDWuW9rWW$B&p#pyN;uSeq>R22mQE? z(Lp~lEvbWkT#0{le6kb6O6rtlWM#)GJF|4C;nK+@%#OP(FX@g?c47EKeX{Frp&u7U zRg|>%-(S5|AUIeI);QR!g??npD4nv{buj`IJ3zu{P_gV+#jEavJxyKOjG@B2L80Pp zZcuSrwkTD<6J;gFtYk$eV^H~8P^fs3D^#Rj1{HUtD;wbGs*<(AzhuBH-r+*l6ARsp zUe6TJ0gW-T;&^)}E51dItT<;_$;yOF$%+v=gNhUWlm-rbhALSxa9~hR4D~2f49+Q3 ze9suvB#ImS0M7PNmc>aXqX8TY?quy?87GeSQL^GlPKVmTGEUA28XLfMnMwov?liJu zDY=q$VQfdpnmk1V%eXjwt7Pq98L1$SEU!TVBP%xS7#m1GamUyCt1bCl1DtC&dc`hg zrB{yV7+JCR!^ui4!;}i$+;Od7Z>;f66>vHHbl=z;>|il{Z)C;tX$4Ab+koPHQUyxk zcm+z&0tHH0KXnAgP655YZEM8{Y_>ttyWqU@aHzsQQ$OK4tk0_7GESFXTuQe*r+43k z4zT08J~HKA7>8G&^oUWQbi)`>++M0c>BK5fIswL1pE76QnGP1`uPE4Ofd;q%ac>VU z`xlfbs10d|pwih=vLbU49&2PnGI(u;deh@j*;e-BfNeS0lOD(pHpAfIB>XK3Enc)E zNlDT|3IochCw{Ug1yY8^@XN!;%BVPEIQ3n1*l|!!Zm&-f%T^q!U^6NhS@ZU8T?#c} zoetC%y<*H*X#h*@6e>=Hcc`dWak$1HzolfwYH5c`*+yHu5F@0tp*i*U0m6#3;xW9!0PE7k=b;>zU-0ES*V$Tc*0K?kEy>(u62#j8l zzle)FSr;Hh4|}d&g(tce^ZRjfn6iM2cRUFVq>qwbNa7Hrq5{tA5;kz*3lpk5_DXy5F$u@IfE!2_kLkg|k@FAgPb3<1uVk#_yic^PR}wgkWprld`s9VtQhgq0;5U|`3ue#%y6 z{*km#KA?CU){cRgebg_-S^ge01j= z;tifT`Sh+8oc>ub4k{2i>!5b{@YPdtxVYp{S=Y@W1LMBZF91jEsPnJfHshU*1$lg5fxLwA{w{GNe*TclOWf?5}sKnwJU*MFf3zNn6X!S%}%xV+sl~1qL-a` zEv@9fK&wL3iK}3h$I5dF-nI%hCIEMggT<|t4i+s|z-F2edMyWwi$luh6;sutp zzGK6K(ZPX7S12}n%DxXx?mG|qREqtFxq#5~@D;x`;WW^1(#sY9}j`9K-h)<;(^}KSb zJ#dtblJ>@xF%A}YyC~R!OIRE%ZcC{@?)QPQUSYF|a}q6Df)-_eZG?G?$eB}{mj}IP z1nu6r_|9ail1?G6@mGUTyl0OM57_mqzdh2QMPa$j6DnUd&op)*TzT5p>3rg6l(IAj zH$0BC;9v(omFkE07+4mN4TSY~LTD%6ICTpPDxF?YHM*ZXh(_dCleDDJiKv&1u=hg( z-~6Hyc96Ffg#L_i!PTHpamv2Z0A_=gtayt#)DFES978Oz{-{ei8``Tu#fhp$uRBN2 zjI3BFY3z09X?I3e-0iMp#dc`*wQvWdi1K9?JeIkOw^AA*DaCGR!I`>nV95>^Ys3_6 zoB`ckMz<%D4Kb-TwewirS|?lq{XQCVo{Ol4krY?CC{W^s3Y5690;Nofh(+Z~QAwjg z{fE7Ag2P`8J7*F&#d$$W16XV1Q0XpEsQ55&sB{P%Dm{`FYQxT%SQbt@bh6T$Q=vBO zoQVc_Bct&Hn4nY|z%E6HinZNF12{iW$=a}U=1ELZafy<(VdqR_ZP+>Upi*^-(m=z` znaGMmPo1nSETduPOf-OP6Gj7>x&ki^hf1$4huXn1{$Vk#@Ps#3>?jT3@F9iz_eOn- zlsZ(JqUlgOSVrE(i2;4CfrbX~R4HHuzS1j>%yXz6EaS#Od`ebq7jUQ@EaS%Z9wqBd zMdA*%gJs;$hgy&w*?gJs+}bw|lMDPy8gv0TTYwy=!UD13hxWLSAv#Md`W7Ku09 zTPay<;DlqN%&D<~Y}@GgT38UPWW~DZU)P{ZM#+i|CSf zP^bsB{3=u&JEl-EsHadd(```a@A<1YqM=Z6VVXiciD)R)ybT&OfW+9y${QXPYD)RP z*Fc;L&_X3E)+8v@*}yV#Zxe+Tvfe4m{r+nu5krApB`fZQQK*=RP^dV`%%J8K)9|%& z#eRRb?rb9b-V=trHL#5Ive0ARe63X4H+-!MSE`YAPGP zR)}W9*E+ELQEA|&@S8%#!1XWLR}p!-kZOQGV7C5MVf)@T4*1eB~7#ZAm1Ko4s` zvF$*CQm|ivl4nt%bgUF8aw1Xwv2ILynikZRGNAm%&uPZMO{eOHok-^$EYG(UkDA=u z=(7y$;@-CBaZMe&PPCt1x8&NSjWSmQeDZ#fgq9!rbU;w!2*@%h>q~L-zEy!faoRT`q(G^#QbgR2--#J? z2b+cT?^YKae{FLhDnkh=)UDVOKCzKsT3Mz?Db*EG^@KVHovq|LZx3T7y2w>%NylNo8Z(ZM*k z{KSS+7D7Q!Po>*`8MuB$?DubNrM?H3R5;pE34-vWPiwFZLnf^`0NTng!RA{{7cvs(&SZQZzH0u)0~pv1cV76cU?!LeaZWgGR%t+;M_ zi8)x@%6*(+I#nfbWBK1yhbnB+6%a--=k`p_?%l;WRPqMGW;1mSIK2WTuCZr6ZHs;bVyu`;lGD@bplqX{3BV10r8@oS3aJvhting}PC^PoZML zu|oaZ+4@F`6lxYfyxTz5v(^dsu_jsUzK=R?wzAW)-46r1C=ar7REpm4*;xe6AS-AE zEH2v|Nno4`cJhi)Bkkg@ePgr>vlZKO2#Z#G{Te0{C-~1z z<@FbMP^sBb9EIF9@Ns=s7FSRgkHHpBRk2UFf*+qaLRSNWo6A78?A6lsDZFC6}QLD$MP$~NK_?~JgBf)6! z*$Nd`@@gb#GY$kQ6l#wwx@ASIhdutrRWXDb7rbxMtdv6`_x1f?C zh@?cgOM^SSH|!`C$2N;?De|B+a1npmk9t8t>cuJa@EBjw%ijA=_qRgD${K}=zFVOp zF;u9No(2Xry^8t9Z+S$8n$;5TsKR$=7Y@A*6e{P>&Q(t$-gi{{u7mAd;(RTPYbj^2 z@QErja!D^x5xcBpjO zD%6H`yvI0jgO8Jyh=D;(jU5Cw94g&34i#e%^(fRhJCfc(rEr1L0FrKn+L81gC*I&r zR(c>P)Q+V0$heV?v(=IGPU8W^%+xJ=PI6jej(l!I+}&ZUAOSA;UV%wq>@LCsc zv{M>DuB9}9bW_QSd!7|4vKOU+)#0^n+@@eOaN|q_qk$XyPn4|KG^S)lU#Mg~=}oUt zu>eSE06TD$tk_iUP>E?N4d7TaB`Z$waH#Z-GaAUpYIwqA3&4BXnPwd1#JSQtX4%I2ZJdcvKqgZS3STiN-P48HT+TvYW;^njD z#W`DEoD*N1>TAu8c=^P5xk#jsxjHOsVS-1b=W}t>NEM@jEZ&41s=IPp3cY|)E4J|{ zP>Q>$Z#BqP6)GmV>-{E~qfVFhUM~ZF;$!e6c+Oq*2;}tw4qI5jj*E~UA6XU^t5Osy z7MPpUx?^rnq2i!mg^DLj?CO|1cC;Erxb>kiOlwB5KSGEwtE&lh~EyH3xm8q^>+eT@FT@2w)Z323( zt?mp`P(@F=L-dcYeUK8iqu%J8&MWc;!XZA+034z+gah*&;#rq27OGztCoDDbbS;{L zn=TH>peezgzVO=OoRF?#9LQcg6S0od6#3sL%P2sN}xu5rb@9qe^>mfv;=( z{mZ33I{VV*<+w^$A8W@AAtdW!AVR@u)v& z0*j;TGPS>Yd!G@OZ0q_7C8Qpdbi0+W+B6GdelBnDGMztvH)hl7kMIYTTMNNT7oPL_$QExVeuBqt{Ielv)zGKtS(rbZ|?sFbU7!eX>f35yX= zCoI-mDq(p(L49Y@nbn?j8jP?5-Hg)gz!--T7Nb&1*i1V)tJ|<9jra z#5J&ab7BXLTT^vEo`3ZP|DpZWkD%68)K%wHxOQB*Nk3t=k z{Zpve_H9se9YWklp(5E-s5rPup=Ns3yC+nr*z&7TabT=M{eI;AnXY%bVCpfbfD+46 zpv1HlD0;y%NG$Dy8BTV17SEV1=X^`9K#yUD5;F zreK{mswE=Wso9v}gQu!)CN*< zo^%A10xm3iH3tjFp$|cTPL95r- z33NoOPHa~)hxO_R0$mMb>(Bkd@^oQV8NveIT7hDIv2Ik?MsC$eimP!HC>3ugP^yqq zpbhztYy$zOswAcSN4>K$M=Bkg@BZJ2iakmSwBh=@ux4CI+Q8JZpB+Bb-(#+NQC-$OELNc#y=M6NyR3!)To|lVw`#^ByvzE;h{|7!iwg{BhqK0NOB1ckER)#HTicuY zR(F~_-cg0IrXUXP0As9KbKD?mN5tmth}hg4IYINKxC*9zsBYX+pgwP84l0haGo`SZmH7QFkar+FFVnPLcY@g{1G4^&2&wwk zjM{>uC9W6l6Z~6~RhIRp2bO_7c#vCN1p)p3+72jP+e%Vmt-`mYB=q~@m4MPc;6x>} zs?UNtGdTErE}W5YbXrB=;u$peImHYp*{XeMQg_Efy^7lbU* zm6XNP#}XPyn)Ul5ur-7(^Ya@nz?3h3PFK@s_Z+`*AkG<-KD{GDM z<9sp&+Hm`CxLemq${n%w+dqLmI8pVXt>>|Iu-`nXKvZ+5Zb($kr{b|};-cC*=wIHH z9a_EcQ6+2@w`nQ^z!{Ck0C47r0_|WF-;eIj`Nz@S>gRVb3fy{XB*jFC0wqRq)dxr( z+oXWCd8cn&4O7opL{>@!nefMk)i6o}Sh*thnVd&foq@M@ut&qodOzr8Elxq&LO;(j zA5Z`0dtgBftj@=p4G)VQm%uAo58QUQAA+*vYr%W9z8m8_(i#k?!m?5k0b$UU|6Yv( z91Y3qofTisbddJL$}&b>5@_qt=@a zt6}XY&KxkJ4!Q=Ns1&s{qIOgptG5W7 z6O}xx5|wOKiHfY%h>G!bC2B{6`N9aZV(k}p2phGAx4s*zxv$c6`#od3E((V$QE@4b z(JF52P@-bntr2z59iT+TifeTQ?jH#&G;m{ssL?>W4!*xyc=d%6b#HhH+^ORG-m%;b zh3vZX$CM0-wWG`;aUZ~$se9eGj@rnX%7-y2b zqvZb|{ZxZC_k7Ox8(}x7$uvNKNr*a9zV$Au0&Tde26r*6XubNa#z}Y8reJaJs?jSZ zF!ocxPK=2gCz!rFI0O!r5*S7Syz)m_*5oDUb#t9K)JSO+UqTMGAsjd_3I{4tado^g ztB#johML2%Qj$`t%_)`0g+j#vRO%%-aaEns>+1Mei$0dh;4OT#2n8gI4W#{VqGa{b z&bU~D{e{+)VUf2P74Yg9BPp>KB`LkIjbUZFE2XiG4V*trj5%0rloK`bneh7L)81YL z_3stX?_b0L#TW5bZxYC++3yWDpk%P(g2{~AhL>hg>7^+wAZ5~@lYvM|Wm3=mQ}nHw z$4liA=J!X~&yUrH&BDs6PP(-nDp4$>)eIy2UaP#5OBfZ;4XZ!gvb~y4m6&mti6I>a z;HCp0%I_m8dI0gQZYsZhZiup5;RU$H0w>aZ?4SE7(1Ib5Vyf(vIS7u|x24DPr@ z&%E9;;el>fC2dMD!4oQJQ+xu~mXj9wppy0>1n<{@k~T3n3TF$NkxAl!x^49`_w!uz zjurRpiIw9Dl)jc>Z;3jB4G2*)NEyDB0!7zt4B*;{Xo+f}^ExPwVKjjIwV!WUy=X7& zb5javNI#z!rk|ApFsrHJ4aw@l$x_0u4#Qe_$tEgSHLTELh~*i>N?{LNv7&L{yc@=o z1(d=#q82--WLLtqqy`B*wiA`YI7(D<*h*An#YR*d`sPHX)A|JZ%BK~FzA0G`I;~1n zszOkXr6c5YbI3`&jgusStHo%Q<5)`64i|8e3s5HjqeIH9;#%JyS>{`%X7U|W9aen8 zD^cmNI#KEUZbTgv$Wx*=Y*tM_7A12O3&Iqc(JD41DXn6Ax)PPhwG)-1&Pr4ahZt|& z5e>O98ltp{ee~uI7!A8svjVQ;9gwO~xC4Y)4UF8FJ8(3tEIr5HtNbnVZp>;lbfiU8 zV(d;-aslcD;M6ZAYr}-D)b|nzP@*9P@=XR)Zn{^ZhgZ?)|K)-=86E@2E!9z2V6^aX{GX}h1W-e~Qg0c{vSdb_=yHaWau65+U7aevggPyPP77kRhVw;=TT6X2Uf(DeVcn>JO z4kSYLYR)U11-_QDR~&ySTD&r&i%x-Aih1$CS|u!-R{d=4Sj=a>R(Kno0wL;6yyY(z zU-d3~F0Oa)V*EfBx5e4N`7F^napm5oS}x&VkL`QvnkFAI0nz0W)bF2J0VSU;dWWtf z8hEz=(T@^T$~V4mL(tPB?h6EOF{f$PDI2~0Wz z1{4E$>IiVRvoWkiJqStx#Dx?nx@$q((wH4t-YzU5Dz_miP@1V_tSXbx;rA=lhMlMx z0ZZP>XceP^rd8rPaeJrXK_^o|;Q}&X9ZbOJ6?g3z9@H@k{W@_Jy5T`5XWY!U!sM9w zR=8(Ffws6SBmss8or~@(#e**Fz%V@Mp{<|aSn2MIHGX^zUbq#<+%4BZJV2r1EO2oK zat#2#R-ovv1rNF|;sHif9Drv)v6e-Be;k14P#f5FnmQV+>c&&`yz8q`rVAe}h6g3g z1`ka0vC=UabNtu`rbY@JtKmU+N9Zc#5=1pTDAOuCzEwv+EGfhl6-j{M zLFvK+&!Qefc?tlmNe*Rt2BFsd)!o6bZ{*j?1hAq_p&lV(f1b@R(enf zwQg0JT>kydlExPBR_6Psu?2p=L#0bVSXFvZAcLhqDLJfM;J~c=9Ku>tCj(#W7CKmX zxtax;*ZPNYX(R0-=K4Hsi^Mf=44QjY7xn((;ZmUA)7D5zv{gy^y%&h2-+O_8k{3`v z|NAF)B>kSV-oKqH(9O?p$O%MJBmv^=V@^Q*{O==d`T3M-Rg!)mw1}km1~4CrT)+AG z2R(xoC{;x$P%7b3phzjihiWL_xU*^$2(bG36k1ZC9b^J2rI8ftOcZDbnK(Ph1WpcA zKfi-aV1ijm+Ce6;)Y3?ba}yP42bo9~?CYp9m7PG^`SfPCFtK*tn&1+7X$+r5r}m z)e)J%<{~9&M`WU*)B653bXo_rBQk;gh2le{$@Y6Pv0-PKlC*(LB+2vr9kt<*c=hue z$i#-rua%??k%=va`uV+|oh{#!iC{LIsI4I~vEk$f^YyX+Q-L;+310K4ByAuQDP#El z9mV@7&Ckc30}8Z(Omr;HOaW;_WFqPP2G_SYL?*VQgG@9`g1Iv@q2WXw9b^Kh%a{{& zbdZVk5`TY1A01?(VQFj@<8+V-+~8rp{@Fn$8n%K&rwug|TShm3Z>MKNnq$LFBj)Qj ztl_;=*wt`H;Tm4`^E=1{E{#``c94mygG^iw}6QX16-e!lF#+^Mz z)GQzW-u!o5gkzcyQYrmC^V$Dq`n_d2uTvQ7!4=pBwWDB^=Y5%vb({@X)zMMjml+Qb zpisXbi?NhlWg%Sb=FMD9$5dzq)ue3WJnEP0LZ2np*WGDtg1Eo%gy9x+zwD2aiY-%V zawKx?U~ze;j%{PK!eNLF=B1na>tHA25}>fBy7O7th#sI$M^ZVvF8xHU$XmVMD4h>b}ar< zCU9WB-gtqqVo{4B`n4Ulwun;8js8@29IU@ z;DMajjF}%{@F1-DS|<-Z5Uwy&<-iY!i~G!sZSvX%7WX13MttF{s%<@#q59lNF)R=b zCGNWDf%ueSm4&_NN>r#F8yMqXC_$=ZMgHPY=|)tjI9e*jQ}IDXE0_nC@b2|->+?(_ zG`ItWN|9Zm*?Df1fpVxsxRqY6ZFhSb(84z<%3k0NYoU2C#v1 zf3m+-_i|z7wYd@Jg~c5Xc9AQ{X!<(knhWFcO58Q62zTG=&-(SlL5@b+6-xk)tYGuH z0y^tp8+wmdMmPaKtaIdmlArxstyMg^Yvb6)s2_#3|9y?O97<{e%6?`g3ISGdh}}^M z9McE;n5Srhe}jV*lgy+fG<#>WCQ60shd`I)HcY9l*=gKpmGAU zGhm%K*+T?3awU@6Qm7a(5c>^QlGNZ`l&p&k%b;HA^n8DMDb%F98c@+-m8>TPxXi53 zmBj(z2NdkxP*$?CIRIoeLFp$71F*tt-T3m@eu*ts@7PSZ28%Va;;;jy*MYAjA!~wL z@UfI$2X<8bP1mn}t}!T`Y+OO+eSqUOip2s$BWj8?z87_3fuR!h&&c06ywK|Whg!h8 z7l;#R(CSW8bkciMet2K`R>&hwtBC_@8Y*4Wn?DMGq)aja+QyZ-pxx&B>Z4MT*3uD=NVCa!Odt)0^WeU}3Fbr^Yit0+ zBucHgQAOFn!nF!U*mcmYWo%%jBJT6Ma2-@qp+rs0{CiQqpRS%*DNa{c27uWpal0(c z`zukup9lOzpvkI~sNeUoMAU{pmY`xE%lT(`#S1ozbttH*aQ6h?;J|LjpHnLe9QsbB ziw<~ZP#(Mt%v&~Old_!-7N>72*aWxWN^r2VBTf)dqQ^?w19_Z+O`RDW2?vW;gM-DP zsS5VOxl9gr5~EkJye!wj{zFGn{XU<(D^f{2u=iQPCXyDl(ame*umlyGzW`)L<)BAD7{QWX-Dbhl}LIA{YY2x2PxQeYkmL8o}I-MVOP@b8E5dh zfn{?o?#5Em9yosA!CsWZRIps{?qJg(-SElI*+4(Cc5rW?AA!YypwexIXns#WvM3K{ zrYLC#PSSI*n9p>un0QmL3EOpivWc7Ml(cDE`aUfDEKh2nANRAAsNpWlOS*%8Y`;Y{ z1Ll)$8)i!#EG`gKuqnyv_+$x z=P79~EKgIgk8Av%ETyHjA^H&?zB=efMngA5KQeI|lfCMbrSz@ilci3v!!hR0={RNU zYKVT^+gcs;BfWPW^dmP}2mMGBLkIoHyvYvwk$!Y4)-tDT->-(`%e|)-wBeMcaj}Db z><7*eP`YjD5xMu49+7)*=@AKRM~}$8xAcevwxdTRu-GG_3@igEJ5E_%Bn@}jJ~K7> zdk(hGoQMY4_3NM?`_rS}AuSg283Q|hI6K(E;zA7to4&*b#+ZGF9rPpNst)>*Ikz43 z1p2Q9i^v%?I=CHquGw+OE#Q!(2rz_I_O7MF?S?i&Wtx|pdV+FdmX22b(Ego z*RP}WG_W0|r*~c?9np`A*IgTbo9zo7^dpJWj^s-+ksb6SJHI>VN8XSf^y3O;Y+#I6 zMvFGQ%dWGf^z^z~N>8t_<_5=j-7Tf3*WFTjdX1LS(`&Spo@Tjx2mOd4bkL6sF72Qn zsk!W+AJ=LrJxzso2mMH;Y)A4XrGXvEm()UaBww;}yMult+uafUh+piWANSExdYX`E z2mMIIs)K&yiQYj!?z5%z^uDn4R86PI^b?%4Xy$ZeOEOnThELUobUdg?oCWHJI#9~Z zf=~>KD&-y-MEyM(9Y>Z>f1f=KY)8U7upJ5SEOYEgcn7v4;r*0zHu&7Yb|kz<5^)Va zH?SQE@4$8>yt9C_BjFub+(IfMAmdDM>H8;NU^^1tne5t;@D6N8!aJ}X3GbvyIuhQ2 z?MQf!3>Ry7@&ⅆXTgm4E;Xh9N3P8cVIgb-s8;iZJ;0L=ty{nd~_td1B={F`PyhqxV8Y0et?MQeh=-!d=4s1ulJFp!I?{Q`2NXID~9SQGD z4eUsG2eu>OJyHYH5OEG{$E>Bmb|k#hOwy6?4s1ulJA0Em65fIBNO+HX??`wDwj<#k z*p7sEilI6Z-hu5%cxUlvN5VU>9SQG|nw^G8(}C?sc#kZ8?4Tc+Nzjn+jM_>UF>C2rIov@%B5p_WWz3FQOC$M#j^xY8WQGpM$P24Xf?%wUSxfn1 z9kZ4K+c9ftWT#FC{m4$84*HR)7ahr$*g;3~CF!yb`jO;u2mP2w$E>B)>U7Ln3T(%$ zrTE2;SxbTKn6(txj#*1%-W~h61KY8Wdt|2$(T}*eI<1*W^ulGPa90M#ecx7-`~a2` z)O8S03Ro#na*GPIgL))M)bg>8bb@`}j6c?qyjBBjD&iVSb=G-zP>*$GK6--^uC(5E zz%HU5;xHs!*YUyf&;ySsWW6(}EWzEsTov(k{eW@ zL^Bj9aSR1Yca{Ogkdy*#aDF^Tdc-*vgIp{5C2;@d_hV`8cFwCV>?7^xK9v_79Y#{3 z7DBBn?M>hRe0&}&Nr?yk&H1buYvQJv4e_x89#Fbe%HRJF6eLxkpTAljNk4zJJfNR5 zst5FQM)iP_|9gf-lnoWLJ>^3cQM0e(-TIxV#8jT6Tvq_y)k@aPSp^N0Ztp#s#Lf>fKt!am}VR zpaH_K1{5R}spuJQ+0dL5*pB>A65Jj6p}=B($aunMbOhMe6V|Ib*kp|1);7YX`Uz}S znO6pVf({gHCL4kd9BfC&&wO}B$I<1WxKhI1(eX1=u0{a|C2eZZfo>?+3}Wc`WT}4Y zIAzHgcbu}-(eabIvW||Q`OGkbPxhCtFS^_9$6eQTinRUMFDg`gCOubDRRud%%PY<9 znAE$55H>Bb@3(H9d_B!%aNpD~@_z^2wjB#BpNB-*1aO#;Q9v4fzW-F;XCSg6 z1Ka-8&!-5S0mc3?1xoP;1xl<)fzoqEfztJQ8`McYC3jE#q#jtey`93X9=LV(6gNv| zI7D-A9U>x9kcH922^DJi_Pea&-IcaXek2Mbh|7AH^$?c;FW9^`AuDzho3E9Da`3gx zHOQMrgd^Z0Hv@|Ac?C*lB{ET42FU>pP@>|ws+(#OM&HxG6Z?G4&p#+ys6grUsz511 zq(CWUdWq-N|ASs%Z!06~MS&3oN|%)ar5CmW?Ku6IgjC-jUjgP;%_zPG_lHf`=2K-n z#XGA|phN)`D24CT?VmY7-~WCbfovWZT#7EV%29W7sxl-GxT+Bqi-wd|vAV^GitE3P zt)^b&dt1G-67TZ^z>DjQQab{6+4K`p-tK=RX+~N$fD%(PM4hMonENlQgBlcowJqjT zrNI09PlfIKO45c)HM5=?J`@)AC`-+3-}f)2EEUJIn@=_As4CEgM^zGG-_ySf2S%%( z|9KZe<_h5CVI^rp4uE&I8cDxz7mQA^GD1n(@Su8zb-sHPC27NhDl5$*${S00LIc$V zV9Hv-qnh~ty*2o$>>c~wPu&~FlZ8@ofPnc@*&_1({S|0~pGp^Y!-x8-_jxmalcvci zRXG0YP;oQeJ*@dzGZo1zF};JGq782G)i@UMQfGNuJS*f#6+!WlcS!zBWXi#^Oni0-?O#VL8}*D|GTIwO7;VO|6i48^|_KsR{*Po z?Qqnqp#>>QCAHScPe4hj^-~p4VpK<+tL~XY0N-CcSA$Bv%4ii|K?;&gO7ViiWMxIsXH(o;pGRrl1t!3j`W#bk{`rNo+eRqbIbpaEsAIO)zfL0sb{ z9)Ou}@qK13p!8N#qUL4s^&4RS;aL0au7_9lG;ToH%J|k$Hh2bXm$(QwtXdZ4nhsQu zRj{ipHT*st7*J|maH4)+vl3Ao*hPZDWUS^0WZwGwaWz*~xFE=CE|=#Xc$Za#E%zN? zL*lURxHwiE*2Gsqs|u7u%;li%9<9Qs67*`vwF`y@>}d&mw<@DmoUg7xDRpC%iu-a6 z3)pcYt2tE1_xZ5c6e-nwsgwMl0;LO3ff89!pu{W{C_SzeXopM1UN|KwWdW4)YiL>6 z_v`!MdO(S(8l~dXT7eQxQJ_RA6)2HE1B$!HMHk?6Ny9B|E)<-dYkvRuz6^NJic)x0 zo1c#hByU3~Ch@6#6R-zHEDcY|E_X01<5jc&7Kpl%H4Et8iK>z{>uTOnm8|Gkovh@q zl&m;-NXeS*@C|y!ZZIY5K<648DQ52W%p8KVrM?!nZYd2ciUb;2PYis$9PV9+! zHYF==t5$m5$PXx4F}$E;-N_FqSuw_}WIf0aC|PlGGx!)htkG=7G3Gh(TF?ADgtQY0w~=l((P&{|&7ji4 z$;)$vv_YjhbSG`v=E)Z7=OLvyExsm=0}Z|=s4c$c9D9SWIY*pLgC9Q^=8cTqF5C~I z?DontgtSn%+o1A|F7C)H@uTlgSy1VX>vVgaCy!y+>d2fVH2GN*lpy> zFT>)NTNCxXvYHq;qtflfV5*XK{sSMc6Wl8$Ds*_4fL#aqai!aZ#Xm;3cQ#T16LqjS zv?AlU%f}%pAmRx|w`nq_%gn(Js$5q}*cRnMm9&|*4Ia$FW{u7}QBbf4M%9#VkALvD z_2k`spxr8IPpn*Xushuj4)&xv8wZQ)PaQ1s1OtH#D zV|07xE&cAn&c|~WsofnNbokqFCGfXOx9L9so*>?3nL|MJ2M(294#I_JWCDCHv5es! zcso97FPj!_LNl^PRIsdiu}B7{;+s_P#K}E_b*-jQ9)7rq(j8z&1 zH1s#$6Z@M*qrja(Y+wN90N|cs(b^VK@#!J1tcf-4PvENRttJi)75x|YyhsCkeHTGc zi5iQsvG>HfwEQ(zZzLF$D#C!11gmUIIXTUKom>Kn#I`f z(LtqGPO2LX`~@msPeJ`vIDV<*YR~|#DOGyCFx;XvfXRP@dJ}U|8o<#U4wae{)!D*# zu^6N>ez?C}$%?adlwPwCyy0wN`G?W~zTwr^VxGCg;Yy7aDb}E70pRzaYvWPH;xfpV z*HFo?FM|!=aK;F-2Y_T11#u&@Z{TySdeC8P|6s9aJ@zH}(>_4TO_zK* ztUG@kC0Sx%Ri=yavqQMrxI{{v?yEk(bWUXR^Ld;WKiV^A8Az8Yt4VVP#r90DJL6`F z9{kNstSTW>R=_O?XS0$z0YyJI+B!5%nr)WKpGn1W4{DR^85i$xC(78#9#eM+X^ zZ(awBTOAZ^mT+`@vJ{ARoU*Wc;B`s~1K+p~786tocD9sqW(+muzm>F)!)-VY3rmoN zw9mbZZ0YF^s$FG)#c+p{_Frn;a}KNGp7S4S=LK$97d`b39sc@G6jFYB*&uBc|Wtd9Zp z;$V3-(c|-#sm;@R=d7VNGC-o`U=NC*9W1W;aIlL)T?hLg3l8d%ux~uiEd*@eviqq) zz_!1M&o_;rc)MLVCT^IJa~K`3EOUThZ50!C-Y%z@fXO;XEv_wBum?_%I9S})2GH+YPDMx^5ve{Lct&dMtRi+kJg$uh0g;eMn&vE!5R-CV`ng%_?IEVrc?ov{9j zYoE()>c$UZE2%tjViSmT0fzmF3oN$16)JrQ?&`2PIP!Z|~^w27P;D!-JtV zou!!lsEch-@rx-`%HP*}pYG#7I;;(?97Y>dUW=wsF;%5d@p&24h9zT>0bVkuXho;P zpmNu;Lgm(+a#}HII@E=RRxG$FJuoO?uTVKbWjKJB{~WCtg&A706Iju@(A7}1qH}0a zIh&|ZvALd$Em$j~}F zyo`i~9d8S-AuFAQtc-7!m3xV&E)oVz{VK zQJbzKpw_|iIUr%a2Hz>EZ|TYqBnFBOwINIjtt_ge?ib4%q*Q7U}|) z3O=bB#oP2qfmu|r2W|*-u-GyyIGa6w@W!45Q_(D52bS+2=_{k6Srh^8mA$bb1j2*` zl{_wC!ZN)}4wpi0*vfL9SOYU`J#i%12v&Avf-X#1O*A%D3^R>pxd+)nhf0$XiUYW@NTFg)(+F0A zjCXydK&b$2^!1IKg^YuFW0)=S*w3Au@a-*qAtd0=sX|aKidNjIBKR6J@O`o=pkxN> z(wbX>6cCG?$o<1*rb+^^peb@9_pf8~M^H%ugci7exT8bymBY-kE0iOr=nK{}E%y)m z>z`ay(QUgo9Gh0CI2B_=fIGDnYKErYRkqMAsgFQ7pg_qC7=^uIl~kc-r1hPv!fne9 zE6U#(HMrp|QN@9Uu6sRn$$2o^^gtKtAwNrhnTI0vLa(PoR+n$aSt4k!u0kl5&}+|X#y*gM`$P_*J=T;sa$8B=)I zEk>~T!h;bkoPJTywWG^7c`*v!j4O~8>EL0B+H+iN%8ZG!(|zzjq>zE!rUB(5#P!I$ z?fV-r&Hhiq5x$lQGjgm7P(>y?)2l?QQ7$JgVGv*I#7QOdv`%csG&(z--r!>?wqi4) zv9M=u9=*Q;#aApmDZXChXDbdQJ@(E4Bd+MYoA)~K;<+HTXVKHMOAXj+L}1{x3}dx; zdz2BZbPodu%-7<=i!iW*Yb1tNbO;qFts^q)&T@KyTsI>ENwFFzyeu3~ zQmA~fQ&@t9ezxK(Hh7swu<$&x(XK1~)1Ui;3mszf20A*i?rfZa-*1$_!bu_{0cjnD zJeG>#!vSD{gXJj-F-UT!3JW2eVQnfchd;I^};HtIVxNndiIgWb8_{N33;?X8O zM5G#2KItxu!Huiqj7JoKrPq~zFN;7Hqkpcp?;HL1>c>j&W zKh}fF!+-gfB?)*?PvXF1*vqI`f-1j(hgQrDC{zsN%R^cZt-KS)d@VGFN?vm#k?^C>`TIV#A<%J%fHoq-1xcfyo?!Uy$04%FW(U%E3dtKoXw!vM^Vm^ZLt zVarG>rd-A*KGr0otv=TG&d~F*&>2#1;6JW62<^IKrNA&Yc?|H}gk^*E9pGPkb>ZIXv^RXrk6&mH5<@)dh&gz|!hXJ2A zXa9kcFJu(feiH-ANw?6N9v5P3HGX|iIq_PzS;tOQ=<@jALn`K7#S_S(OK=8_upYP% zMWNz)0mA?sCMjpLpKpa@A4atvc<|N412KaXWr!z$+wqKMIdI3ZVk=gkj2SpHQ1p33 zc>bugZ64N{`^4|0?pyUNP#(dFDc5?AJg~gX(C}d37B8V(#zvOVD3|OqgwLf=V_@Hf zz@aweMRNFw7?6LjrtwAu>zx5cxs1OnRd2D2QG^3~e2lbWd%DqsgD1A*fs{X1){MM= zEG4bD8LZry8-?P*ntS#f%h|&;of_zyZTnoC7x| zYhufULLCi$%N*#pm~VygyHNsj;Y^vK_49d}N3&r2q|z++^H*;s%T)BzI0YJ8p<=gy zc&=+F2AFi)!k$c%8eF&y!id1avV&pkiAq2u#`0Q0VH>wC^#QQiN(68WTA|{^vf==4 z#xhCwT<8J58gb2~CeT>M$(7bfe%h|r{)xN}Z@D-5&D8@O8B zmaD~WxzKGff`z-HRSM_kt;UZ)S0jQui^$&{7ej5jFvueoZe}h!KXU%&WeHobrTiAg zeU6HEXNA_@ezXB}wcUsN2I&dAoVCxYJ^G>SBVmu2CL0F9v=xFfSxWUJ8 z6>s*6DT0tnZj0jTpl@XufGhq*=_Q8`$;C3Het$$Nu22^EfC@0CC1o-&SW2<5e^t&k zY-z>=1}IW9rueR|OsXNy1+eu=pBA$%nRg(Ir9dBp^lAp{HG*t)CFjCC*Yl+K-7o+{ z7ey)#e5lOWiJQz6Y;w8q3LGphhf=T;Ls$okdRxJ!0tF9D2<^hC&?v)&BV`V?!N@L* z3Jq6r`0c27Wp2E_L!shitziHjQBj~&)iWk`VWmjPDt6=<24EITk&1)GhEyD-QJ_>J zQNRBpy{b@gwXIe5YG^&vlGK4pd{rFSNna~e z>`_;I&4B4UUquyiKk>MrXmHrm_zp6l_`1jrC{(O&J5$2>rUyD>jmqtpH$SjUHG$6P~!CYGKyVksDawA3}@P&Mk=s8@ndWKd7%Y zDZ6c6?7B#@6l!*;zuPVI3PNhb*SfHi(tNE{4It)L9KZu}3Ka*Ij0{{@GBDQg8l+tm z>ZGcP;sD;05RISlhv;o7c@6CQi&eCuS8Qm#@k)jHTB-9A2ZWb#vsWx^?7dT#OmP6c zV)eDKR$wwuH!e<996+yFaR77W3Kf?+DGqQ3y6zP}>+QgD3tH1yP1OQn3*r?%U*j!0 z7GLZ5VSC!+i57kBpf*^;BOePiq54|5@m%;WM^c&~SxN>t18rUbjzTF8WIw>WyqXgC zvEey12b*(P@6^_f?7^$##eBuFVF$D!6|;{If2w+5M~}!bAj?-EigTz962SZU&C|*v zR|w)118^g0=DdXrVD?dgA_vMR)?&4G^t06G!oxa-1DMiOGJwvTaR(9`!hjloxrPT~%2R-jifd(Zv=F$o?@ffyM-kY>0Wcfr?aG>7+m@J*+^< zxfFMLj+`8aPi08Ol(Sg6lT;h|Kt@^p$Hsrd0c@mJwBoL7k;=~~1%(1ev!==Ed%@x} z0wy;+arc&xfb<|hTF|_KiM#pLx5AcZW3VQ!aZnuKvr={2njNXXCUu#D8!$kj zHf&pY&Om}x8O3s8SBnW;FAQ9a1T<`0IWF9`q9~UN5WRiL zhtr&*VgLrNMgnjG*qGLzS(r@L&zK zXO8IrYZdHP*N1Z{Tf?VhC8gG3sD(%Yx$V)8O{5x(|`ZI*&zJS4Hi)lc902 z*z&Gmxk}(*@!YI~MHQ}K`7EY`#e9x}%>h5CYdBa85)~|8FLSUx*5T^04mVl{#e^Fh zR1NIlGfNJ3Qb9_=W(R(QK_AY=0dCTB^(?wFBxu$bmmuzX>_!Quf*1$*M1dk2e4 zRTXR+>KfeU9D1i5vZMB*SYN@;xQy=}ql3ksA_bcYRmUgGHjWO(c;R*`#e@rw@;ca9 z^ae>te`&`jyK#exVZ!`j(~g6kl>Sw)xkuRW$!0E6Hhi*Yi%P>Qo6mB^@8x#x*lMUg z+41*RZ!>rf7IW4LHp!2UPsS_T9JM!PKk5m_dEWHKL^)*g!ZJZ>G8CW=L^ga5Y>+pk z;?-L*dXcsmO57V#(SRudz*hF_Pp=hwS+5;WaG0lc?P=!wUddk1_;d#>GFLGnMZ5;P zc%9)w0~6BLPoL~D^Hl*GIPM+Od6aSQb&;O^^ZkqD-WNJ_qL!Cz5;?VwSX_vvh{fo} z5sMjSMeI$AMiG0X)EZ)MT$AgF&9b?7g`kMV_D(@;HcX}Z_%*Q)Dup19Se#0$b2h|c zE1n}3=aLk$IQy@N%~5QyjfU7HtieBU#OAWx_cFU-n$i)AXL=N8aT|^zHg=IdSlQ=D zf&HM&fg^UJ%VCJcZH9_iKDKPc;Mp<*FX4IDHLq*S_$Rrvidb~(9cLH19EJrr0IFEP zoy6JvS^r>Ze9v!uOG|AAH*L)g-a$~&JE(uL?RQg>*6|>t@GZPuxVk||*t2kms1>~B z1*eL)`!=YC=Ws{E+M#VvtIzkm4Jz7P^LBS`*;c%bEyv9}bqPye9bcJ3Mf+%Yn~7U| zWeWGk<-9^Cq$LMmnc!{IE%_dX2j|YKClv0)DS5%$bK)5Qg^Keg>g}G%e31q-ydB3u z$x6Y6pyDg5%k7AB+ab4O;%f1I6I{q-H@!25J8)vUTy5D>!a?J3)W2B*J(2`NE9U9y zMXYcDJIM^GJTPq7I=`$Tx9j&e!}}IO@8#K^EvO_2clmn-lrkO)lr*;i zja&b&3lu0h8w#}JL*X48C#s7)7zMkbHE^)FlR#{h-PU$tQn~JE1hpZj98`K+!ZBPa zjf0^z8f(J}u0hQn=(s&^+I1@r4Mq!MLZ&`07gSs!Q1{>hN+O_0pxO2LS3bc2h>%4JI$73fmlv5v<_0ON?aFlK#41kjUU3% zKG4J3hhS`m+#%9X&TE$GfPGQ015f!lSWJ`s?H{cwgXFZ}fjv=P8FdnC%~Rlnj-nO2 z0gOj9zu&REt$CA~HKb;z5WIt$-aSPsdsSo#NFAf1WZuW-aT=524A8_Uqi0v zSy!L!jZvp?Vs3m1#(>?KGJNNNBDJA;CH)oTZPZB(=;NflOF&rwf=ZTFkxKeS2*8yt z5Ku3M)Q!@Qj#PTBic~b*byw^9{b{*(v8pSU>xccfM!P;oltB$TSPVKGY{!~_q)Ks3 zfGNdftgMB%J6Z$9+oL5!xKc(3uR!rOEw~+Wo2v$(5*2Sxlv@#lUp%}kl;VjUlJ(m@ zDI07Q*b7oe@>}l)+;BDLLPE=%{#K~p@7@kqaXEl`TLW*kn~#P5wqh%;$u{0bNCoAh zXvI!^!&dCjP|vj?G`Pmy!PSZWwvm8bA!(3+XGzGrY7r8UgCSsGjReet_T?B-aownS zS6N~KTvZZ)iv<;}xEa;375DEb3BWzkhE%M_DXw-55njnZHt2wbYqJDflX(Ljpd5j< z69){fJGp{J1Tx}99LUEkX7jFvO~8s)TybXDdQvv;u9u^(h24aP)E4(@p?hV_z{1jo zk^t;@GHk_5m&Oe6-d;g!(oPMkwPPDfPQ2kZ6e9uGL9L&Lt=#Wa-x41Vpetl(#VrMj zt>_9FCBWxRwsb_4&CAWnS3zx1$rK9C-dV2{BP!OUZr8$Db_DitIZshG<#r2fgxTSD8Bij6dNgE)5_NUuk6cea3oSQ)OO z1E;u(n@SX^6mdIJDMP5#;9T@tl^V>D378nA1{V(WI%+!(dTbeQZ{ckghXQXE6Oz<} zXX{|`pof?e&CzbWypd%HRgIXrAgmh-xeaXYIK2BX^)aRgl?0)jf_f&SC|96BDVkBB z99nUmx}p`2=xs|pgp7AWg3ky6hl*p>AMN5E<6CH$RQ-SjMq;y*f+9LaEcU<| z&R#bW`(#zBO7{LyP^(bUM>ZU|+3Ebdpj6~RiaxYJ;1C{SvIXRIU3Xm@YzGeE9asH@ zZP}_1&fF|l6cZ}pS(Lgb7f?zTC{W5pDNqWQ6)2UF6eua!`XFvTKf45V8xvIOvo{Rj zV8)P&voYBTU)I{W0Zgi8f07hcML4k+(7_HYP}bKWCaPMLG|Il}Iuqg>gUc;G*h*`~ zdwx@a5?>YQ=cBEA)_>7xtD=-*BNKUNQ!lC4EQhL#Rpu~30u;3urgj8p`R1(xrG`)i z+VEJf+^YWkv1a59A{g`YdFxHR#*;ZNdRU57Ecz-^F`;EpvBYB-kinRDsWKi`vLoQO zJJbfhHD%cj2Jn^-5oBF|d)421R78F#C4W*Z>SJMX-bm|37Tb|ZNfpyJG>c>;X6Qq;`%9a}0z>1od{ z9&m;g2XJ4hC}f1z@7Xkbz^8kL_qBOCZ$1k?SDu z%GH2kbAtk<;N3jeEa3zJs3#itjEDoMsJ%uBl65hpVi$%XH6A2*LMGFi^Lg|FlrMBH z@`biTXsm&4PS3BYx>#9+46IeCc)vLN&FjRb(+e!j{S&Y&O91YN$BDt50{wm-B$QH0M^TDewye5CX~&1cySh$PXU9CqF>sHZ zqITc~9y1S;_=vivj6E3a8|6J$ZP&n^Uy4@jQ#KmwKRWB{y?#eJ>%omvvNhA1`0g2< zLui=A+mMA6WI-2%Ns3g8y%p&9QR0ykGz~xhB#+4aeB4N)K zVZ*C>uQ^{2A;+IiD>C8y;f4=G?YYI*eAg}xHdlJzVU0n|L!hT1%t26jc&Tg<&!>C_ zET}8kpz`-Jw30Fu#`{c}2W0CMb*>CDQngpXp4g`AV6j(O!SaQ5143iiOBptC$Gd9D z+_#|iB6+QE-3@0i@{FH!Rh0#Ic9p%ez|i_^iGD{ldXTTGDq0g8ywj@qim78oD{qi_ zI_AnkfaNJgY))~!GghHC95+bwA|5wTwBkuBftrRu%1bNMjVzZ!Z8$`bu29@#t7ygZ zQ3{pQFG(R3U+m15uJ7O0v-S#HZN&lH@1am}ZG=L_1v(Cu{0xJ-Vegtk-Kg&SxFJ<} z<(J5+Mt6l%x3?94#~&@Lj3n;W{tMzCHGJ3Vwhpxz{#iC>e+ zhlO#b$zWs_AC!QRRvy7L92i)BF)`7=*%%=LgR3ufCCDSF>i1(w$GAd#LeX#)=L1dX zl9nv6u8OTK;p^b=Rmc@CZ8zU)QDRVW6$5RhSg`%qFaRfw6e!s%!_|occM28H!w3c> z-3YCzD%mvgSha#(7`ZsulbVzr>`kt_d0Y!`*%pNKuCyXRxMeo!tRMOs<{rS>b}E|h;*3k~|B@t#C${1k0Bc2pAgJWV ziugEv>ZD{8>PAhE4wbSQhOaxOG!?A}ZPpXkEB$_yBN57b?YQ;Gyn-D!^C((zC%EG4 z_59Uq9j@*cto_EpzIGGFV!wKV2y#W4g+Yu?tgM(O=)DO6m>;83xbv>qL- z16@P)weV!SLd}7{_phZ;+0QV1y(yM6v?h>g;J}G4k)jpL{KApX&{hiv@Bo*h759xR zzQ)sfe+7zG-1sES*2&8_#M4TbHaNwi7Pn4xwG9JsBdX{~SOa}xBLM@ui5)8H!E#C~ zjvLJ^83`CzkQW))+_j@@ zju9;E(N-dGk?ZPEDUD$mz~^^_$r{*Ct{8w(p(q_c)AnFq4Xtw{5iqf4DqKLT5P`{e zsf7rn^ZENC#7ZM2DJ(G-ovlffbu$K*7mp~(!h(UK6{k$i82ifMSomJ%89aI7_mDuL zVxzi3&6$h_T2E30idO9YR;ako#G#TkRH(SmM4{qxU4@EE>N4Mi)r(TKv%onsc? zzpXSBHdyW`ZE)e0qjlrzJd=4#QXg0#;tgJCB6bU}8&i+Z38ZrFE#*y0yqKNXxzYYq z+~4Y^4z{I1Csu|gZcQi6H8;v^J6NpBJJ_3&kP4Pp**jR2TLpXVR6}>LcuG&fW;-8* zpAHtiE(eQuWese)?J2?KV51e@HJF0U7i;)rxfMWFL`7|GEJG&3!Q%Em1$*E|JqP<| zSl?`!gGJ{j?;3Wn*j%7s z(_;iKzJtYjrGn*H*TJ3??mJlAYA;}qUqXlPKUrXL?XseFOPlb!z8&i*-$05I$4y}8 zUuvi}KXl|^I{A#{nD+rC#aN%t3o063L+VM=rAXz20oB+%zdxIz-$iScZx06*H^3OK zqI*!U1wN!A1Ip>NpmJ-N;J|_N5(<=JawDt;87YyDt1O0Qcud#DpGN& zim_Tb7~c@x<~TC;FDPnH>=b`uo~k8GrW!1_B6eV%z23lZWD+8{#B~ft}do)RHXcPPuUo8}nE$wSWI!q6{5vR6)hvAL zXS>S<#sr%N`}wAN^uOD(;_Gpp?Z>pj1Lp zpk%HUD7A2@&!6>u?@0_pDjy0M`L9-0;EkJQ1g$rkYs1z|AV3{ak&4cxh_n8qCCH$n zYhf6``+5|qWLFfa6u~Rd23vJw8dFh9w#tB}!1uYXx^eizq(<-AU{-ECudSF$W<`Ng z8-)SICPVe5c*~~IDT`FKVgMDQm8rrtn}$@}0H#RAt}=&8s@kD8gaF*Usz|*t&1jy$ z_bXA4{pR%{id52pf~_fOfA3lc^daS~+sTni{lF&Io;xw*uN-$h!<6DX!OpSD;YIS| z)Ei${gaM_(z;@KD#L3$b3yc`-JcjwCVT*Cwacrnyk9z7V+oUKbJnOCeL7k)wgc#%@ zd>#)TCp$#qYo*)mb1yrjl7cZzUEc@Uq4aytEuiGNJv^_zE3UhW%2euV?Biq~ zL#Tig-2ubbq{JX6=1?1?HD@w_RAUE{yZK%Pj2~G-p#pNy1N3Tr>gqU>W`f`U@TdA* z$I+n#2Cir`b)h5sZt^+a{LH@t)>R(ldLp>5%F&$Ijj3SQMpnzgVmG3Ky;yBM-?aM4 zE_AbuHq2xrC@w`RWgQi%gX&JApnYWg5MF{qCCx43tqWh50)4*4n}RU{fNrKShZnkp zCeDbP)xZE$+lH%nKGJ-DT-~fb)kXG2{eF5>n+V}A^oR{tc@BLOu=hbR@vdM|T8$yh z2~qO29W0)d-&dWtscDmW+3&4vw$BZB3tk2l7cGl~-nnm-9Wg#^7A@1e74E>f<7}CT zkAq4Hy}udtqVsmro4t9|aH?ZUPA43Iomo8~D>d#Qr zCL4v4AgJAN4&Pa3__otGry<xOwLkd6^uQp=eyePP{Ir zV8dJR5fyB_15k?!_Qov-2KM^lb#n!~{YcR$*z6W-_+;0PM{5+d2NpvVEVuI+C4S|8 zS*-P2`PRYW5kCbxe>9NnV3VZ(0nb?=yZg2w48TjLLdZp_0@5x7xo-Y<9r_3lwK3>Ms%M z-4hRajCvzR=8K613KdI23UyJdqe4Z0S)pQL)u1lS*_*=iotPBffk}DXT+cS|;7Xb0 zU2hrA=C&Ec&k8k1j~i&kn+1wiTsdb@dDXQ-{nN{DCQ-eEZ~%p%oUD!7p45+2e+LgL zHA>Vu8&oWiE7XfTBZInOUPhtfIUj|(vuIVlt@F42#}$Zjtue6wp|-?3*f9V*%0-Jb z>0VT9RHzu*I#etI2o7XE9xUQ4SH#XAuaB;mn1YI-SG_+VsCY=$yxC)rPq1C)b78}N zy_YsDXc%G5T2oZ9hSpFExeXz&Ar_3cc?Iczhupu=uNk!jP?0Fe@5hdE!&a=WDbR+j z|M|(F{FGW6KBHyWyJDQo94bbehOfAgcK?-= z`(Z3j{wNk;qR@nJ*$n`%K(Qe0q96tJfseHE;ce!}SXAG^!u<%sCtSJt@vdDI18^^= z(OD}S65eU8@3P3p%4X_!RKr$$1W(4ZDghTB;x!*D6Ws6yjI>_pXg)2QX^S> z_rQd)H!f#Ye8nj$#R0qlroPssx25=+k%9NOrTB{D)!P<gPoj14NWAh!qw zu~<2+tC#JE^U4bJVcT1lQ2ll@D?It55I?Cc`9hBHL zam_2jpi;Wjp_1a>_lQWy46btnZ~4ERij-8UK~@-z_`hCF^t8|eI)}o z70}Hiz!e(;l!s!B6_~jGK#__SX@iROSOtozweDR^9HUp1k|$(9vHe+r(loXLrBFbD zQkGbOVyR>oiO222F{|Vw>Sg{tD*pQ*D_vwH1lwM>0{ez{1w=>jzBOzT&emh>`&6`I z!bQ}~GM0mG%i}E;5%N4!HhPk)Y zmg@B8w&jxud&_A24Y(AQ;&a>*V8we#$$*(#&qE(c>yeDrB`m1;cxQR<^?8hg41?ip zw*As`xazhs*WIXLPrTjOFqYY}MhGfunxFVy88#q=u*AEa*#BZ?57TH(YEjtSW8#{g zZPjy;Idh28Wmvl~T-rqD^jNr+;oODt;-hKerpk1`Q#otT>xHRY3cb_p3+4I30fDS60>Qj!4S669VOwSgH@8)ouD zDOp%WDQPPON(mkXN;W`&k~5@0sZB)$-dTB1ezsB83s1ls24LDyfl@ldfSw(%KU-Pe zBO>+v@fM{qs|(kg8?L7FbtQ>v_g&QkztIhA!TbgWHywXmDY za20cT=2cy|hhLC-VfoN-HI3B}SQt`ssRyJgPq~_7$VCc56`)6huD%Y^)rP4!WTQYE zJhcl?uPRE(Q!|cwro=&}jQzXto`GS&Nl6d`ii`0TXoFEr-Mm3j;i3%n^C?bMk~&EH zDM_6T_W$A|??O?}hM?-o3K}p}g3^XPDQCJKBZ{x?pP`gebw>PgFkFFB+l&J3@O|R_ zHhicK-G4O%R2SBl%!lH9szN1=YAPVvWb%EOdNoW^oQbEtx2ShVN#Vwlg82N&rhosT zc;k$sl=PG-RB?&jjB7u~z@eMTct6iMpm(k6h+Qq5Ma628s`o`bZM&#djc4UKa8_&) zAK5no%0=)XsAOElVU1J)|MpqGIadyrookV^8~aU65Z9*8adOh)3G0ekn=$Yn&fiI{ zD(u7@?MRgcbfQD0+|6IRQ<(**y%e#z08DB|d@j_9idHY@^n(J$F6Pg!yyut6mj zI8@5N82yq>4wNcX#PVXw`jAeVWm`U1#|o;@N}o%-gZabBMT5Fw7RsSg;H6ME@{AoS zeJv5pB~l};rD)BX!*^@&ms2VRGIReC3rti$cdQwj>sT|*4G<$LSl*skPe|r~^!Ekc zfRZj$l+xo;pyU-QP_nTKl+qarl-ySZN{`im=HlABVo{)^0~P4^ZP+shA|VH>D5Xri z0wv|AK*_8q(C<42a$ty(IEGTZGbZ{4=Ya_fLn?0kR-mZ+3@Q)dl+z3|NVmw{KJjUr6` z3O<*3S(DrG>xLkH0C;Rh4NlH5)R!sD#MeNp$uLY@(O~3i?o`iGPix}Z8qw=Aqh6o} zZOqHWiz13v+!d%kSI#27`$NLMq+fZ2Mzf$Z zR9}Ac=qvbIMqw>HrJ`g2*IFtWz>!bGfi$-OUkwMYjg*U#tZSpje}#%&ZpOp7@Lrd3 z-mh%bdG`f`fxWV)=p9rER>yIQnQ1EUTa10l-Zo&XaIw;j2cV8rO5~~c%BR&H3tTlY zNe>bWgqL}9Dbt|lQq%h@xD5wzE4h%YG-3g%#=hJKCG!<(Ho?8KRRx==4-;%8uPm=P zS7@GWI@EzyvA%KUQWw0f?N{&l&hl`Q0-;|L7LhL8_PXWDVl9#aA+nj(U}Ed4VEu3q zSaFs|OAPFW`RDzvE7>QI1)UykOQO7Lqm@y+DSu#aRCi6md zYM=Er@9JAT+pG=;DG-fQDaDerVMxX9K}9N_Eip(?Mb#C`8H&Cirj#^Q9Kdce#ewW!d$%*YSVo`4CS<-$hxV1*6R{<4R#ABJK_xXSx;}#1kcvx= z8If=%af$%jrJmfpH{42H zS1$pjyq*H3?1Om%=npAS`u+-(JZ+JQzqgBG4fCb2c%1{w81|sjhp;8i1D(|YFPstkv+M!gjIZaVYo|*!sw5S2a%kv79 z9=`%@h}Cv1JSj>k{86BkUQ(cx4OO6&T2Y{6`weJEn6l&2IYlXjDGHSG%Lm``wpRly*21n5I;eb~qDhMg5$oImP(>hdR=S z+CXW8GjTNBjJ*$R#}^`XV694lHaHX6I}JGxMQMXGabTs+P}*=YH;ZP;nGn^#ppxY? zIllvIimP5yybnC@Dsuh@Hny9p$B{Gl@9J;VTZHf2w*&QW7%<3CnSp`(xX7mvS+AVp z1qO)SQkljfms0c?#rvVq&!nhN)K{Xr2=fqdoB)r_ll@-lG(Pb@IL*gNhq9 zL?g_d8B%%#<#vUDQkl*yMZPl$5&QYtWF`#3*vPpwPit)SV9nDSXkf+8rZlmVFJvTZ z;42WFF!wkcJk0beeD7h7lej9J!GX&_O>6Kya954+1qO~EsE37@U5tx0@CM6aUe;uH zsNQIKX9*JMY|~#g7s;zJ+Y{TE#VbhT9=uoM5YL-bwo!w;TIlgYiw%MILZf9wASa%{ zb5pb)C|IY6UlyLdHLVbmZ1`S%Tu;~i zyPs*gtS;PQYV>OYW3UAZ6`Nwyh9MYxQDkUDE1l2qxRx-o>5T>E5712DkB4YH%bZYeLuu}9dX__T7&ZA8mYUGS6J6t4=Tmn_2IUlVsu>g3Lj8n z>rqeW1(qwXg4hiUMfE2;e#z&7(lTFb+bC09PG^Nw9C9s(oDV3eth#y)>Q2RydM@Wd z{ocR?6;B8%2|yR#JOLhOsk#{X{k&3U<%!f>!ocFz1NB@pj{9z23|nzltez+j1F)=7 zk2OYCnp5X}YG3uQwI`GZz6y=CN7;TE* zpX3M_R|QIg^9q#8rP~k>;6T^i(3-nJ?{C$Z>;ny!5vyEx>!9`Te#={sVc2@oyQ=3~ z#_zyWVO)y?lcV+0OK8pd&UX$N z0rQp{l2!Q|MIe zd$}?;vg?h!%6i*yQ2%4gbo~L0jk;!qSf#BCOqBv9S4DAkCl}C!Kx3zH%`gB@c_>iI zg)30ZED1@?gu~~qDxbGBKOcRn`l9{3|180N|NROTohrkClS%;!l-ijTXoLM9m{m}e zHrW4kUw)rjPxobm_K!_@mwv-jbbjj{a(SqH+*K5=<5NOb?J)JViIp%DRLx9{eEzj^ zG~%IK8~FNzpa@#uwV+`7J>Ld;+vP9d6v-Gvi_hO2`bArvU( zR_a?Q^W*VGtWs9EhuJUy@2eS59B5LY4Q1d98y6L&lm%Cy)U>BS8#3z`_EsoL$^I)) z%7GYAJV{a?>5NMGe#O@VN=b0_`zZk;Ky%Ojd++!De#O_wh zS-;-#p(vf8c-mn3aM8xn<1&s8`duxn;^2-j;a=nKK8=E!?4FQX#CqhjDD# zA`g5u+VyDIUlCHN6lNZ5`eET)8Rc?j-^jb0DVj{PaE6-fj0l|AVxee7rM=ZxagOc8 zeJjSoocIbv-ovaFn(6t0eA-Hb4`r46s;H-DZXMg z!^ptI%$wNn86m(uS?Y7~uC!?2YRJut#EsTUcN}~sTWbyxOvv8@!BbtG|H@2gS{My>R~8#G4ncicxZPP(II8b}pRj-M84a zs>;gv9SDJ90WM`0THv}Vjy3t`JLQ6RU)xC5y*(!MZDUxDW!1kHuce;#Z26v@ypYVP zf31K%g7d}!1&VB~o9+GAFn|(Js+NezFsKw78?NqDFjS!5huixPQ!amQcu@)NKb-6n z8at@p8}0pvvl8Z8EeeSgC>6^@x*>&4%4Zu=FRBy?pCzP{X;r9cMf_f`HrVU^hxXch zD!c%t)ap$kmT)ch4Xu}~*x_YJou z8&Vfmamo>3D5VIxHIDa1|Sl zOad(PjUZMgt90P4LvdVv><0>#@zxKlT#H?tv4Qlo%;(CD5BOXP6$d;_6wD2crd>My z;-p;^3nn_kA`&`rX^>(p>MTPlj(G`1_#aJ@0yQ_}AQBLBUVEC^Ld#pu(vaG)<{^|e zxB}cFX?{L7oGDOhzgD1>T~VN{M&KX zn-}*h=M&yt3X`(B@Y0hIs|!;$3beugU9-XdU6a0)5UXoaZCOmpC1F8;Y974xfU*}x}o)YnlQx%5XYco<)$HuIMtuVUyZXD+ZCqW-~-ZIKobxuqlFIxtq` z!-Gn(MaJsupDXonAXdo0j;(77^m|9($cqJ+O;JjYfGCI_S#tsp%b`+yA>LK$%+R|e zstjQO1;S!yz!6d#B;cSv8zWW+1y~9cn>V5#szxB?kkIm$Ts0~%t*Z^63K!C3ft}#M zB)*DLz_DY3Nugo``{UMCW#GVN9HP#av3AmeqAVO#a$FTEw(w-mNicR%4O!+jJ2Ya)U*O6L#05;TQi^y$*^SQDH&!$fDBXT2flf$>i2hO6!dcGH@(RRPK*~%ZvnD2c{~F0UWq5P&|Nv3z8nKQ~p+XNL+m@Jb3C*8&VYm zZ=Nd&nAE&sB!JtjjRasvoMHgBZy9qvIxOoz%WA$ArqvWzaT%@RDq2BP3mZ3CEQ2~R z4{kUx@$S2@Em@hGzj_OVvy`K*u~WPM-esL^Tnwe;U8tYmP-C74eJVvMZ%V^9|btzzcxm^c`vP&-25i3VHgz=c~9P0?;`WU<6< z-(zu0gpjPoh4!bvqZ$q@?2k3HV(LbLQsGW`ZR>he@|($4pwz#kem-??C`ua)_PQDj z_PWSmtDjHVuqRnqep0yJ+reo_}k0qW<|I~6h&)%ShX`ua7z z(+guD_46sgYMxYb3lIW554rkKFKjbZsDoTUF>jqtAc_JMDyD+AAu>#Nn&aP9fOxI< zuOS(D{~G$1c&oYj`FKW4fi|QT?vD0#p14szzrjkjpui(%hCsg&#+KpUd88?)c$>*H1g1xncz_4qNRZb-$Q z(+ZS)6w?KNPkN}P{&V9RKf{34Vftb9KR6HrRinnK+(v;tx!p1_$M4xjt#0ewh$OH|ht zYd|qiSN5v{O4>?M`hC-KD5dnTqLj)s>a7miGojS#ps+%mh{=Ezu~jqxoIhORCyMGh zW<%;)@s;m+)yK@wU)BS?s{qkl7F6;s>xGqol43O?u;GxQ`B)oX%-x1yLGsF=u*J>X zGmC7&6%^xJ**QciTSQoyv?C5EqrIWP3ay>q8sMt}r6Q1#E1X_dpcD&;pPz*N_dLyA z)6Xl`xjsgY!z)LhioP5&C zxNBM9L_#IBUv>?VqB0VY#l!FJ+FzeYu@B_TI>!+6aUhs7AaS4`2=2HNL~Pu9E>8fd zMqH1-`Q(qedNiCJI8z6O-!EkK*<<)FRK{OFcFNlt9dKYHlwknwTl-saQGKjA76(Cq zNwFQ1Qfwv&$O0>n0h0_n@U*4*T3BUJ;)=(D6kGAOlX?U<)x?Ay%wi;x*0bJYbLI{& z2$m3m*g;5!7*On7F$snwS%IyJR1yI5TJx5K2BdLG}o;IlJfeW&Q_@{ZT<3lxgY6Cqr^Ya^e zjL*@~V;oRw2vI+u!gUi>jSiP`bhwnG!=)S@F6BU%Qbd0P+kxvhz2c=(s=^5BphCC; zZ3unFc%IDHHacIb0hAhS)YtE@C%6*J_~-+hR*X!|4!>`9_XVQrSQ@^HJXJQM4cvTbomW@X_ zu^HH*lCD;$IA5wzJ7Nl6vZmU#CYo!Z19Nca`#62hhRXWnJY~JIK6$@_0c~(AC!R(! zYGsnPR-jZ+QF2O|UjvGl3>7HFRHjNXao4&y5P8m^QQ9~}!jLu!Xc#VJ7Z`R|5;%EHM)MJai{3iPo;9~V>>#uJKC z$|x&P^7|ENhvmcj3WCzCfCYtWG)h*B0;(dlK}}x`3n0&{WBloASO6JH8)Av8VF6?) zrB(_fQW?|zT=!iK3n26JDV8wR#A|ObDA(R#P_n1JL8I(sP#jYms>#}t6#aw{BahY83A^zSvm-H@cZ?hXZrYw%Pt{l=dE$3#@8RBs$m zQ>biMgc7(X>Og~vbxLzuAib~jvV?9KKb%z;dT?Z~3YcusRuojyuJuy=0}8rDlq$v# zd+HS`I;{?sTtS7}FjF|Pum(Ps(S%ut_q{0y==Y`|pyUgiCxD)S0;R`VSFQQ^l(JNm zexF?nrQcWT$L}V!YJNWE>!18X(G3_`+zKyMeEzLrUsot?c&AB&f&o-N|NEFVKc7^p zqO{>jWw+wz$%U~sB&-8U-Cu^M4GHT|`hD|DKq;~`KIN8$WnTw@nf-d4=5I@Y0eu{% z&q2RW1BX&F(&|g$Vl{`_p;L0T==)EF+gi=@&tlbgN=^8;ofH8p)P|YL5v2l8bs0Ye z7gdS&-?1%vtYWM%iyx?DX#%yap$R1GBuH61QYlhBN8MH3f0VQ~B9Kj(Ag)3Q?6?GQ zo6%=gXFV0h&sR0%wKk~My`fim>uPWVceE^uQgQ>;r@}nA@hx`DfEfnh9B@((^>=mrh_8ovu34@LrbP@F zjRV_uMLlpFxLC|M0tXfZM}4g>&cFQLEXu5H%~STk-@x}Cwt;PTrm!q zrVz~A8NTA+j-r)kYz?g$2zn0*jUG5Jk}RQMPwt5~3~1;JewGYZ0*fL*Bo>0__l~jYP^gEXm#EQ@kZa9V&e)^Zhr9 zS{11~CGQ++L-PI!TpPaCPB|9E0CZQ31pN8rZ^A0p42-PqYf!5van=0(^ZRzo(XqNO zppVeJeJS(vG0m(%8&Uz0sRl=7P{^u&KDBKqP>O;TC^gv`(AnWpPBQ-{Yn}cokSP-Y zj*d)N_5lK^=2KwEh)Rvk+K_{vJ)A*?5zM#-F*L!Ua*0^V1`m$GN?eQ z5~4uK_f-xho|;vpqL(I6=id#fH|NI`LNaOuZmLNF$5er;Hp$8qt$kOhr-}IrPm2Vk})ZK+`cZ$}7^x?jX_LvKOLh}$VtTHHxy)n~jh>cf7_RFZ4oHT7P zU^m`#aGb?OVGb5&8^s4plMH2s46!ry;RZR#`e6#?ghHH|l_Ke?tFHN*q-2EZnm;`3 zsW^ah(~4G%=8T%18)|R!5H_3`R1YCh0z3po?7}LEP_uKpsiI+s-LaypI2+jkH^#wY zGp6DJCW{@h=y5361Iy(`9UM68qfmFM7#oF{P5%&mDAb&ge)qf;>PZP6rDhM--j5P0 zHhInTB7w0L>8PNRn%(LSeNagX6e?Sqn2a)C@r;_t9L0qphfAU6-sSr{aHwPuL`7yM z4FU2hvWGz>O`uTGEfC{m^UOls_phaB#i4(twK7WppR1man**<&i^Xbl9F&JKuOK%X zq110=V4zntMTj(T@WJ?6gBMmA8NjX5#(PO^j=q+m74yf6uQye^4F{fx_FcOeS|?6x zD^#q`C=Q@@QM9tJDI{y2RH0NH!1g3Dt@zwP0#o2nNoyOsvuW3;sKWi5*{Q8g9 zR|9*H={75ivS*Px${Z}Nng8o#t-A5?ir|wuSiIh8#Cq}sD*P!>v|r|BZE3T6cRBaH-Vv8eKJ;LfdfBlNLL?2>j<>wT!wM)AJ48=ZNTop& zAzJAx02xrARF+YoBvuNPtboWpti55WbwJ4(Fuxyj1PYXll>#O2LV=P`tU&4YD^N<5 zD(!cn_#4A=;6$i-Rk`W_?uyZ>ajZZA3U}?m34T%BSqC;1iOmSPk%uxMoPYzj4H&j! zQd`MYhZ}r!xWNZ^e3T1j>o_R&DpK0(z(lzymaOAH94jMNn9&urf|Xu9@B)pro>}Pp z?zAgfSz*;{vFqes*l6@(YG~zT4%h+3SDZIid_Bm)P_!PDWKgtX#Z1wPr?M5TyerK} z79Js19N=APhE`nZq-e!Eyy|P^7VEptQnX$aWhz>6?~J0Aw_6$+xJeHfT6vv~;p@Py z;fhvV#;s_@nKnf$cjyTj$bQ3yx0Ozh1gUScF^U7|6sxa=b61L1tng-VMARK}KD^<3 zE!^wjsLg5O1|K%<)!@S_YIF9q!P^QdYFQ%**MaGGA-7qcNJX8Tuc*syX6GsUY^V)u zNxl?sSE4V_Ukdl;`f)u@x^C=xQ19VR_(fc(QyWx#WrnvYb~nV!PYJz4*WBZ3u#lgS_-RaSsGx=3-HqLk8{3Y3Ju?y%(NWAIW=zsww+Z20`q z{^8nNEFhSgj64Jw3Y0#7eFFJmYRjj>Sg79m5L&U8zOA~;`W)T_*Q%b953!iqRH(d3 zrXFZ#F$9M1=DjXbElOao&%1T=v9ONnNF_BO0@u(=o`s?n4R*aq_%#BZ9d)x=)`^1 zGdbJDwKql%=Ahhwl7s)4aefR(F`E?yj;uZMMa!_b8?rtiK{ zs-Z${*v%2XV&_(UH%Cx0tv?N4F{CxQf(xhmjK+$y1={sCZws@9+fz!Y3T(Pm;BgsZ z?}G|_=5yWHcwb+9^XxDsW2k6l??u>xbko4sG6I{^9DrIM7z|&r5l*~<8(*w3hIfYh zAmlI~3oG)90hB5*CN`;f2sez0y|L|H7{fG&Q$Vj!aoMcUE&DG<_Fb@qiOt>!a)^Y9 zeY&&2Yzf^GR5FG_yY4^i_7PSqon(|XHYRpYoezY-5WC@0EyLI+ar`c@<{50bdRx(o zyM9FGJlPsDh9UzOR8rdxl}i1J1L$TcT9em%mn?@$S^j#kv2P7skNd`5kB^8H{rBwr zB5_SxrVe|a)K2-gZLCUdj@5&sWoX5%g@>_RIRXpz(9|QcoQPPUILnJRlSr$}0jG&F zyk3XB`Gtwcki{pD>-Uz^F^}O{`~e2se6pMjAlIn=7#>hG;Po`Yv-<*I&0{#S(VE`a z^WQD1nUwrUdzr^@jGN4@c??Ic?E({o6+gHkzOD`eN)N2QU1=s)M4v0icIr~FZVYJZ z&cTs%JeV*Md>t3gXB!zv^EybD23efFja=P3nHLeu95*hMs2?PmN9r*kSVjWyE|JJU9T_$P zQk7hBImU1RZ~YkSa^oH(MJjp3id0;#WSpU_Bp?wGN)T&2hO2x)>5=B5FLY*98nmE^ z;m+JGB`4ERyWyP|MJ=b{94z(|DcGHzV#C{X@OFH%W2Z8zV!|4-c+hqupEFpSS))8 z$0JcaIp4zZNaH!#T}3Nzz^Rv$LMu5*jsv7+3TB(^l|j+EQy+*!rM#))Ku!}hNY;UG%e;cjVgaoR6?44i zZDlF`V(QM0QFBMvJ`ic$fKFc=JbbU{cjneXTf#?=rC6bj2}0z)wkx(@xwI*qStWz{zGC#g?5|+(}#b)b1~DEF-Lk~ z;#T-fvKI}_J?fQ|x$_Q$zcp+{Hq2z`!9m{d`hf17xVYtyPgQCYdx0}+BE@-UbH}?{ z{5!l*q&C$*au5ExD9f-}`3%(7731RlHR;4DCzMwfsepVb*qy~zWO=ecnT)xSuS||m zTvN~S1QZhyTl~nXbR9VAWN5{Kzdy&MOe=1@R-Y^VAPrh(#gf6hRn!jLX60b97u&&h zoVb4Oad#MoHE~6`V#30a9|wy)atbzkk|1bsu-MY*VDUPPg1zxvoP%vC<6d0GO;)fT z=Umyg3aJT)+i`|0y$pDUOa%Pb$x)f$?8zfV3bi5id7URITg6v2I1ZJJu0q8Eu0zGx z(a1oy^}mM;iq=VeT@Dp}TEhWckfUhDMcNLvq0v8uP>RA7t-OfLd@b}46|FeE?ocUG zaHy1%F{nu=LipiOF-t3CV04T+q<0=mONv(Nb60%bDLv^>$(47g9bU%3kWSHhG&C<< z+#;oD#pO#5wZqF8m^M2PIi3nXXOqIMO;Q_%?>YPV6InvEzH38u{xZ%q1757gmzT%9UL+$V~(!SC0wYZJTe67*pWlXGc zsIN7tsP0fZyo`y9zZI>xlGLGgEEM=oO>9Tk&xbW}_hFAWryJ7=6a-WH!(QM7h= z8N3=vy;!^z>`*(rjK!N)%-7<@1q!vp%UHbf+0eQ=av3?-(P6jv7>sDMye@2AJj}77 z`&{%83~t<)hDoOf6%$4E9-YAAGN-zZc~CL;porx=VdW!-hGvRzmYXRIvB&RwYqK(#gw{q8+feciv0U<1 z#OD4QC>f!;a>XZq^*XSwh;1lLg|oPwRA4C5h_GOY|`@d!GsuOY^KA4jfPaj`VCG+D9+*nJ>we;j&2pP7%(Yf z@iwc{vy)G@3z>b6|29~#i31phvwW7+ah8Xc4QErT?cgl$NixLpb#e2+GN(!!Q4qUu zrK}Qzm6iDL!3?nnWjP$NXeCA`$l`YTUgm*i z$9ls9yKr9HaW=-LfwOq)&=Je4A&eN{1p`IwjkoTMx#dL*j#ylQs))stE{@oVKD`iw z8#mZHVjH#{uHVhu4u$I4(q=#!vCi3`qC!-};`v)4vq{ULLR7@!k}E|lF6}iko4@(K zARM>z#t}NhSw7KdI2+|1Nq_Y?6tTH#0{vW3k#P*8|=KZ*bsX(%p@dhz%vPo z*oHRu5X)`uir9wE=_eo4k>uD8Y{nI9T-J7CLfye)tB`^nxsU#C#vLrCCl&0>@sI{; zXRal5z}}SoR!qpvuZ~Z)7IpO~YO^P(Ai#P!DzP|~&vlw5lSN*;m%#g;Jz zN=X?7N;WRVQhdUO;dp)@9 zpir^Z)}c1YYy2znFN6qe_+EuCbZqDh8r`zt+Y)Nv>8SeLW@S*H(yd0W(n9gQeN7t; zO&u7vo@57%cHOc;{QYAoX~o;LN?LJD#;_H4?I^jzyB7)-FYhVThCut+Fwi#Anw}hZ zu0~o@*H3Nn<9OiM|N64uP=&PS-~og#Mgn%cqu@}#544XR18pT&*w~@u3bVLI3+^YG zS0h(=ds0aNPWUR+hCn-aLP@hIxx(H=C0CfmRdR*%^G2?){aH!C-B8UuvIPjj0l|Po zSpaI}>cCsfMy}GR4aUXD72owWY)z5$-DDfNN`o?dEQNYD)UvX#i5z!DD{iS#sHj{W zDm^WQidjsBiVdj-^+d;2p<;t*8eSDz@P$)IrU|3KchiDO7Br zcBm8>XUMZ&(#ggjP%mcQA)Y4XvmGpMjZm<$Uf^##*oC#d`s(a;T&QCdwHFS{E7%*i z&pKEdp5TtH+%vynxIds3D@;QoBatI74Ho2(ZkJ~~NsSWxs%U!@7QokRk z?alAUvX%nv(0}nv8{R)&5K+IsMgQSadqXM?d??Ts{daWeKiukLem^h#OC(*7n z(;)wta8tj(MgOt0E|`i%UGw`#i~h@D`0xE6>>gLYzeWGyzDq+YjyoyP7X61ceMM@A z|Cj3s?~M>W5Hb@+d)MgLvYeqnz9_5DhTbL%(~6VwjeRjuu5~gZ@jP)}a5Au>D^D?Y{>7m-}`dzaQKC#rNlxN(!{Y|4W9u;rrus zgZlj)`ftZ^Btz;>EkX*kL;vOQb;I}HJM|R*gxC@X+9OUMk&x1{f9RP6{#Kiuj2yJx#MV;`Te-{OM$ld zf7lskNX=IB&yxzNDRjJlTzaN{e~13VZbN1N(z5dXr^4HyhN*luT;%`LzSr^lJMqFA;tIKKdU3Y*MHd@(V+h_d(`p!8}uI!G#UBNcz?t1-x}iI zXSn}eQ@h{ap#L(2-5~$iTd98k-?o*vVQHbNj=drOmvOd^?;i#DE>-6D=T$X;w&*|H z!=ZkEhyLpr6+aIg6*s^C?9hL>+eE$pvqS&kq`YA&F1k~{AE!4IsU7+cw|=YN-*8eO zmz+BEA5O%$-{0Z?;Tb+7RI?-hmqDur`-f}O%HVJI(~nH{>x3@j`!a&|B-{E z4f-#8Jl-{x`u;fop-}T!8)(I`3P&q#a8Rf%(+XMO0I${2O8XKODh>fS)Cv1G6lzOv z{fWKxj#k>=pir@8-J#M3GKbn?39u7f(b}=_|2%QwzoB*fXveEV?WkJ}>|0i}W-a&k zc57feu%b2RdmCuoJG_i+NoufL16T4YzGCyLL+$V~#@Ue*8Q2r5IDjYJ6)Lt`I@As? zBhFic2cNP?$J?46UdF)2K=rk9X0|~Sw)EQ#?6*@KxJHNFx+smMXuVs!jF#@O6bBpL z*2JxehOZNkw<=UTCg4yzyo|YZcp39=3EEqSkm3Ng2szXaFC&3`gWbwbyNU`m6_=bj)DACWjgE@R!rftt1GB@+ShK^+$QJPq zyVbJkDvh2UcI)c!G8Qh7Qj&!$>K$r}mw|hk46WC%!^^mE-I1fUBbSjfcZ1!!aEp-Q zz}DeqT)3P^(Ykkd8CT2Bn+tc|C=MJQxr_@}$tYU!GMq#0@G{a%-(a_{(cxuWqr=O% zCV3eN9jl9vlgR+KDo`5yQgSt0ECKElG1pJddqcrG?^XU@W9LwQZS{keW3b5P22Y*d z9G3z4+UBU!J9lhYeH_x_YshFF3GN|oz9+)!a3A>9xkAi-&3HZ z3JoY0z7;6h7X?a*G6hN>N{Q-)H!d7(OICjUM^=6piaX1bL1~#7CWoHD%`#fxKB72UVzpvN;MBYX%OL`V@ZZQ*bC@T$$vGdsS(3E zDTRv39EVB~j6%h{i$cXdFolX8TMm_as}w4BK`B(sJSkMn=Qz|3FJr@7HHy}ox_2FF zhnJCSrBE|6wC>nXqfqg(ghQo%2Zef&mtn&0YsWRv+Yn`l^h1&uC~{|(0l(Lc9J%)( zZ6KW38;5TcDA`#9Iw_r@Kq*tEKqi*$XR7ETL#SWGH3?&2D z|EFlhqLD(q$ZRPNpbzh8CC^2n;uS~5ftw`D(7NFrLx)P9o8iEQ+piR@I3l7@F^W+f zz`id>E5)1&6}!n42XZ3lJ=RdP;@vfeN_8{E0o*91XvKayg^KsQ6bG`btU(5_a;P|f z$EOqr7D<+(HG|U)eC^oMbf>czGFplQDa$u-;3i+&$iR+geGCWE{n^0RTwnpdDh}Wc z8pQ!T7voSV^`R1NpB{kW)=TA3VxwV3T$rkKh&t zF&9IC34#SD_Ujst;GFcj6scrl6sfqz*^r9)0Y@rDaf;NAWck@}@;OmFSuMp?%sCjY z;&o<6Dm|;sD3)=M|85#c(&s_$fP$Skb(-o&-4;wd^W><-t1${TQ4FMBjC^HKIn`Sv%Xa($rIeupCFN~Ezdy2`pO0B{Md_nM->i%R zMbl+ub<6FTcUpxWxPCicR&}sADC%JG?wf+mw#R(vH#u;yIDe^NvzFw0`<3B4%yKJg zb2kCrn1jVx76*HiLR7GE={r8z5urpeHvJ0C+#p09e$J72| z@yWIQcpZ7&oeL~7!SFVHcC@alKJb49m68YLeHsraxm^mB?2Q4%sdNQO&Wr->_)zE{ zJ5l92wNSBJ^70J^A*PlR(_;7}M>KFvOT9qzpt2uR&7K7{o(x$TgG!BCiUSuLT0twH zT>d*|RjW~5nX#j!_oi?!Y&;if)N8x>KCm%~H}0KPdgkWdNTFx;bl*2bjT!gFlj?a44GP?CaeH?Wwa-s&4Na|h`nPtMSa z8eD-=AvFF&T?S4Zr&oN<_+W!8v*)x54PqD-GqCrxp7PtdY^gvg;rBf0q7mN*-mx^K zV&ka-rO-oxl08(QahG^GBV$ zMyj%43>-qi0B(d(ptSTsarK}CuR=u+(=Y&2+zPbAs!W_8H>6_LK|KIGL}5t1$Oke~ zl^Z9a<*h6wNR3qi1)xa9MpJQ;CVPtT+K~zfFHGwGH8oW&)-@?XqNt5^0Y@Mk^~?4( z=hCPqb(Ien=7KBsor_0%{IKg<(K?<8;@kK2%rn6I+Rys4J(2>0C`*Boi8TUyY`Gip z&Q}MEzMFzgZiGIV2sD#$p`bufo4JmLusH2i9aZ|gTB`IYCM4z1@ySlS0jH=v zrK!2&mCe83_@)%a6}T+*ZE0URR!jTRv0B=fj%<&IPbQT3!t%-EMHYRTTpDd~6OWvh z0|qEsqif&ojbQ-xwHrs~;$CrMY%bh^p)}XcNgh z`nApL+<3Eq_+)3+p)^?Bb4R~k@pkW+rhJ|*X)nlLk6hlM#W3K10t zvKOa8UUO>jd(=Ewu-t|N0}E z4LQ{37rt2-#eqT5hN2aFOB^b7EGQ0O1zgdJ2jdkgwwEXlB**_QS&CLX?(R^@!YB^# z3J9YKvC3gMFmVvka3CXNU}F`ne@)+SI?JJwg;5;Xsiv-I#mNYTnogMa7ppjccLWrz z4Hw9-bZgLjjN$-x*C-C)9RY_*4F!q=xO-61Iy)@P#65wE12~MSIDjkt9BN0!Wa7qu zMeE&RVHWn785vl=j*3YdjvJ!mBuKz=D-P_>Uwv)47moB9$y!;R{7$RlK>A7EQ5CJ{ zQ_B9FuP3!@DGuO>l;QyH=69%MVH5|j15DA1Q&JAKqhhkMouENpFUn^r4&d~al7X9| z4MpqSVPUcxtw9rJr%r<=yte0Se60zujcW2n29nqZ8*5}BtJXUBiq~Nk2XF>WaRAo_ zJJgPf$%Xy3iq=8-EQLBdDkj&YXhYG8b9fGwER1>uX$Ef4S-9m|ao{2gqd0)=;Kxy4 zA93E3%8_Ei@4T_hJEGRBO;3C+U7)7MNl(_amF6zy^OfJMtb^r=)I5|TXU7jWS>E-X zH>t={qUQM6*ihoUueH}3)~)Yjl$@cc*1B7n13V%%b6 zQ5E=_g47+G9Sm1@Tw`h^VCU`eV#;9bi{d!N0^FCZQ1PmYLv4tSM!wef@|uxk&;nDu zf`cuALCuWCyT($W%v97Yx0!$yvpyB}illrf!*LW^K>zUM488w5r@U;vFaOtoD zMGyX0_q9`uq;!svtZ|UQ3J(0o<}-te^JYe{viSzofO!P*+(2BjXrlfKX3KGskpuxy ztD=n@nFH23SPVK9?1ehk!6rz4S6mJjH}C%S#Z=Yof2^DpD@DeQ3o-Yz{v2kO7J;ex z+e2AoLbjpN<29dbZa>mA4i?7*9W2gWDcBtcSwu{mjUprnb$b&~%9|=u2lZ1JQU@uS z$9t;2gB{PbC{)bu9e<;gMQWdp5>N(4VAl_4P!(*HL4(O%TgQ}CP@lN=lUl6B&B1BcpSw@%FQ89i`zbeXQR zqsug?^kS8~VkOn^bznE7k*tB~J%x%rmWHoc(bS*^Mn^B;8rTb{IDnmSO0qh7*49{5 zno^R5J69E7u@B7fb^fSAZ8(sGDWpgoD%HIWUsIBRdA%2B;{c{N{a;lXtEwNCQh z%qxiLZqTm_>l=!%IVSY}wG>~kj(BU~0$as_ob!I?fI}ru)9^LxCE;rsdA)WjnHUb_ zjz|MvFWfe)_?jM|cNtK8#d5de>m<9SP#3*e#aFzkr1*+$@rDC;?(DwHfJ3DhYxtTL zf(CiLJ2pcv?tD>v#m&%)uajPZk=GkH7%L8}4!e~RA&@M^SKJCL_!=Lh!ERl@j{Uts zr57vsdi}7~TJaV4%nEtU7MTXSb^Wj}L-7?yc@$rKD zH-@hnll$Hu$o2^GG>yDQxq#MIeC_DVxVDbIjG#8ytt?LH`iazIOCwTX5=-q0H9qIUpx9Tt~8~0@U^2al# zE2s@BP4bEFb=N0OrwjZ(oE9=?_^$EK)#KAv>sIQVigDQgt-v=BH;O-wq>mpZ6p<)N5L#2HI4)yyfgM6)qZp{bv`)Kw- z?eH?TUx$~m{W`piq#nS9HBP)D6zE(r#;r?xy zc~E>kDL8bf9bQJ7UOK)Oc0%W5(W-`r_iy6uM-k26zf^fZZ8=!1_bS*6&pkO1n*FRQnE;aQY=$1N8DSkoP?IQO0ppp50*aa zp;kEwse6N_8kmV!q+++4;cB|7-anNR08DNhQt_^6`5sTc|4I5^QA*LFVk+KzGo<1` zfC42|rG7td&oQJzvR zzpZ-GWt&%nXEiZ&HGIWA_6oEir@du&_xGOFys5Awbil+*y@shbxoal2Oc&MnOkG%i zQTc_;T|;E)U~yN1g1xc>_g%X>Se!opTTxI|+BdeP2$8*adR!)KyU}emq++9o0!0J+ zM4;twg+tPYRy>Vh#C891AyTkl|KWr|U2Q+R>p{Of`ltA{_6*8{hW(p!tio=byr@gT zp5Psbt)Jw&GjvL6(R#OXQ1P0HLdCwEeG{^^|A+<0HtNEax)zA+{&=EQ;W|2s=fNZo z#t2uc+>jcM_z4zp##y|tqhU{DtSqLS{{~#DQV^5apbXB;_P_f@!jIk0C>cO~lzW*4 zxRJ$(EN|~tEWndVP71O**a#l2l7fM2 zJ`@YE3aeOvW0Hzi3=<9NjD!6B>q-g^gh0`{ljc^a=yfYp9OwJngi^H!6SuS}V$+ZC zE(GQoOx|)~lwoe1HOSV&5W%ou@u-Pn0qz+#Qjn9if!-5Q3G^oR5H$b)w3+}&U zz*}#I(gio3UocXT&875eg*wdSJTX>D0T=x8pRIZucf&@hJNwUQmyVHw?5QHo3Mt4< zdCD1yhmdg#%E>ww;H02p0S==p7T``)MJw)UGN?RxrBHFts6y@V3Xa5ckSkEMb_DfD zt{{K!8Xoyr-`m+^!|52q*Zog>yxQ5V-c^#MJh9+d^%_E!_EC1rR6LFYPi&jgM6&&~ zPse<*B&9)S#q8B_;$GBQuS^^#nnY3eI!=sf>${qA*8r<&#&(@pt5)Xw>=>LrPR?`- zkMkHf!(%whnQq0|(J|h6q)q>D!=uw~^V!J-z0ET^QLKVzZE+5^{>z__Lr9g;BV0wnxcqa>xx9>{`^> z?uf+`5=sm(WLCu98x5lwV$;@4-^<8sTzYajgv_R13lGeMi#I1FMGzVxAX@7Q?;|TR zAq*G6efk6Gc`4M5JUNBBlY&vG=*ue9fm2R(8OZkhhJsppOejuL9KaR}gBtz${o6_e z-jJ3(H_S;Y4q$7yLYP~#JPPiwBefZZ~*?zpc=p<=hVa0t$ve*z8| z@8wJ?yWz?1lN79C0sFARCpvdLgJz`QDFDB}1H*zN8%+V#upkY+4GJb@1duJof|f*7 zVmachk^&rmS1iD#I!YIuzYfRn+(@idSCk1#NRqft*0OIx+tV~EWmt`VZr>P<;|Bj z4}s?<6bsUG*q{#QiLX{jL0nFFw2lS1wm?Y%ZZA<%z~dOkJ4{;?aMrM3;l44$g8vxD zP%OY>5{d=0Asd?v1Z82=Ls%DeTNxHy4VNsRbaY4I?^%%9pboE&9+Qksbo7{<7xtJa zDM&pL!dhVwE*{4)x*+L-26cEhoJYK4XeoQFbis`~u8kBVL}>61c^pIZ2c9=}n23^B zrodZ73x~_a*BZHq2B|28x|2y%s2C(E)X@+oj+n0Rjm-EhNU^}rl&y{RJm zs7VII6vEiCOrLhd@^E6dmmsl^(^Q;!OdgJ+WHUB0QuqVm5@B*sJCtFP=b#KXF+Ma- z9DOw};fa&q^_F5R7kos_F$Rvl8WzMNG{{yCy%S><3vl#Ru>gm?j1&wm_$U^1jJ}R! z`svl?dsfw9CNaP*Fp=k&IPYepU~+SXV8P^qkC6gCcCT2#%@u|PT<}pWzy@K%g2l}h zf(7eO&R+{Yh6U@OQkr4`H&+-IaKT5hfO9ayk6YYaVOYQgAH#yHCG^O^1O$r4C|+Ff zQ7q_axf~ZaR|qM{Ap~OVV~eY{_PVI^_;00q752vbmf5U5ZdBeTP|BSZ;;m4K^Oxp= z&!dF-o0K~>tA8W14N1NM(wxRW3}4CZG*YnP)^?!~)3bqURw%^GDidcF z3owDKSa3bR@N4HNgG0nw!-5?LXABFnqlAKRBLz980i0DV;O(SB7woKL6$@}@xne=b z5co_^l7jHP?##{uXJ`=s=-f4J`mOcP2m+8f!Rz6e6DW<#v--4m~bzF{Gap`@ziDis=TvDpcMo zAoM^O+hAd4N0<1Vm^3te%|5S&ueJDis`y$fccQ+xu^D`ZG@RlqmJ%QTw)$chE+SO4 zVkJ==^~#Nj4xe!0PB+7WBpw=M;A+vYSBrj4uPJyL#%^6)`i}Ogz5-6ikNRHPs8>o8 znOATvisD2wRI0ONw-l|ooY=XG`CG*1S?|sIuEFefQ7NXHbPk z2)OUwv7log&P+`Td?LjHK7%0gnk&6v@VtaUTt7ZJR9Dz)1&e6@xJ zdD0S2>13N}7DBv`QFqMhgY6%9hhQn5AGFt+7n!P@X-fzU9KSCm-A0-T&vvUNAu znH6OS+E8hj9WA(FK`tRg&|mAF;vwXYE*Wqm1?krT&MFq9bFF~|+|8|6fEL`a;K(e} z_bkXAZepxq!GRWBv0#vF8Fk2~JCrWSbrRsLVgYt-DHd=yw~>PEO9YWMEZ{K|!-A8$ zxfKgKR^??yImwn{0e5pN7Ie&eu7UHOh6NdUg-5#`^}5W;7ALT^qAn9u>QWGusgFUaZ>Ugl`Mp9tNNXunJoc(kF-B6T9k<%! z#8T$e(7O0m`%!{Op!kXxAQbALl$k=sGfoP%B~g%VKwx7efA??>`!|5A;1y|Nf={b8;ufqMHQN?B8pX(HG=>9tUP+ujxf1b=IR|YM$a)I z8Fh7QRqV)&%*cop5e4)*;=d^>Xq?8bsG!}OF`R|AlmiAeNMvtGD&RDBNd+|XE2#kK z)a#=~=$y+GE2yB}B4|Kp5=fnb`LJodQSzn|Evh%PLpfhBVHcpIA!8K?h5%Id?$lI3 z2a+l(7$_MNcELjFo01Apz(>Llk_vdqn4$t&d7-HwGh(cy0$wtvsDKk;l;d!{1=O^F zWXATEau%TB6cl%MflIpp{&B!@I8ZVs?1Gh&gEbXIG&8FMC1Z*T8taZFsel)vDQCe( zgRzPsY#R&0XevPY!MS}&Dxhu0Bo!3)0@qX!(TNoOlPNV)Fob=fse0u`K*%WIINWIi zK4lkRxCHTGq+PH_gigU`rdF%$0zRf(*#+nuN;IpS1!-k_OW6g9wm6k`L5e7!L;)?e zT45I;B1?=`2*-gb&)hf(wXvk1v|O2TR+Jr^SGrt^d1X5ITN0LD;F@MBvtJSxqkhl5 z4M|uq4oOH-5f)QB$Z@C%OB)zT!qWaKny?YY|FzJ-v?MGFy~yrTG+V(n3)r)j_7RqZ zrFVj+S$cdc!nPapHzZ*ZL&j}-7BY~8jd_1HdVEX5^7of=gP|bhdIQ7OVi7rI8?+le zz6H&KYR2N|ny~cvmV^z-E4CXwz7=8dUM82gq}hcY-;%I9qeE!I(&JkamR6@p!mjlA zR)j@`136ui32)oBCU${osO-5Yp`xwb`DLr22ILjn%JYiz&+vvUFmX2| z4e(f}B5S43a0!)q$P#Kmdc9$;dc1?gI9p6>3o$h9EFcYo3D+R2Jlv_A5UxkH`@ ziVBeTBjzQc(ou}cQBZg%BjqS4G*%?3AhW$Cq0*ePq*ywhS~?2ALJ!zml|JVb#iHJg z959Mv(e0RMKvOL3IV7n7jhD`ES_zdCu!S?0cOsM&i@Xd;R4XcI^f@P?ZuBuDD7I}( z1Dawf0b5c*M0e)aXm@7iC}^~&{=8x_mKPP^SD#yVRCaDnw`J|9E4>ooj!gw1Ix7Bi zer!!QP`#s4Z)>)+zN20rfViWw07Q45r}au(&Gd)aH0t$isIGzQ)9FARNT&;WT>{E< zyRg@n>2_3FraOIZcT_s~d-{aEqta~G^z)#@(lT8|1(;+;PAv(Qw~7;X>>4om8;Zpw zGvXXeD&XDvXPXvuSuwMLTr!Gc>5LW0Cje_JU~lpCq_SMwLc@E4VmI0xNmA@~eP0;t zt?l~0Fddclg;CDfjW_SW8*bb^+>M$+@LycBfMtG+}wdN3gG* z_j*;X+Wq=&?R^{2Uayj7(KV8svdT6{DpcSu(OyG{ zIDKZlj2$Ie*PmHD)-7ouG51YEE#2+Cv}pw_76kkN-({z-Sw#aVm{; zkA_Nf976nYf%itPLnR}#U_unRV>DP==BB6?ll_PjuL;YC=n5w{is#sZNvO=rCM_pcNYYZip(Jgi5pE5ZjyTj{DT_~orQs3fmG+Cx@CrHn%f zbz=vCgi1pZ66*C+G_ha7z$WLmBx_|?qJoN;Y=CVAjM{)+`KS#^1GK7ILQO0rsoYzM zmO4qY(zclrDjMdUzmpWye0|>v?5uo!--?b(!_txlDD_%GrH#@gR2t@!P$TM;(LI;F z>lIl+Jr6iv3w?D-vThNcW}(qIN!II|PQhXeZ8{~%O4~~)sEF{95TAs)u=M|Q!$jz{ zQvT|_LVhwowbn+3?XR3!Sadlh5x%?mO~cY{AcUn?46Pu-YN+fe5Ks~AXNRGNO2fzV zv2MsptGpD{h?X$D^ z0Prj<=Z7nY;kIDZ%=zm;*#--a?g&(N%_y?2;9V10g@g~fE3k*Bl9T|In|T`=Y!1lS zZ}8L4mhhB6FxfJ?CS1*R#1)_F;=X$?8U(@xKD!S6_PK&z$$nw`;LDOXm4#YkOt z>n>&fNXXpCrpImUw+*)=Ic|kiEl$O5nP+5tB~`msI=o#7d2f|YT@k_@2z0TRsDw%> zViGDPEl8-e6S{;-of!ocL#>DzNT~GimQd;IPC})903_7R4gv|4HuI5CD|_J!sNmwW zXQ+fq*>MtTMEy6)=-3q_$r@4rz2740zrn3wuSMbB+R+Dryg?PcE?}^oU)>Taebq^* zlxHTPQZH6Qy?#zLENh_+Q6yO_i~dp60$q)PL`AG>L5qVQHW;4M?bz1fZcZE6`BcIUu2; z6XW^Kt)a5JKtp97k%Y<{)6Pe=c66H}9+4z#ME%r`umiaZG+AksThS{|b_ns^edh^q z36{RPm1yBUFqBkKErybkr-3FcCA2HM3q3Xh>@-xi0iQ}LX*OZ_H95N_Y3UEYtNPZnhhch_`UR$9ETJnQNnP&KfFFiy@cNmfcTkx=Pb zAfYz4vlLX!WF*;C36*wemQXRv<@}75P-!;+36&l%eKlt-wnZdnFu{W*W`r4kd!zh7 zL9Zxw3kb?5&~M4@Ey)^jzM@%u!1OcSx9&h z4Ja17@TnE^ucNdSb`D6gQtwSeW#_B%>_lcN;w6{Xke6Iq=}S&g?Mho#XsV?RL?vNq zrM8C3&R9tWd?=*`OKC7Yv^eP-Cq6#1he4-NLn3@>qY*ykqCxsQ;P8$i%O_5jS5$z! zI`Lx_``W1|FB!s4bE=XGXkoRa0?J|4R6rYVDJn=e=5Z-1z{7+1oRSLAXM}87Nd>$h zM>q}#CS3|4UQ7mJnw3-#a@VFBa@Xb?V?rn@KyHTYEyWOW$N*?WAed$)74X)Pf+3); zgDF-qgk0J4OHx5&drR5{wB3qy9O3~=G^?nfpp@|Z4X&u5+?!sU#f+9sc!cBSK~x~5 zdoU1zJ(q<%T0*rS@j0dCifBERYDDX)R3lnX;g(?uWks(wqV-g&5v`{ZvJ%7!Bn?Eg zo=TOTg^H{oa0S>_qse4R)`-?qsfE0dz=I)%Ob2B7aDfwDLrFjVnwX)2N zf*R8CIuCTb-sUY9zRUF&7b^5=<^R014OHfAORE(zgfDNj?q8CXlG-KIh#Ym^d5(I% z%}n0W9O?XZsA!;9HUyy3;aifd)E|&g3u6{Zs1eK}%rs*W0!7xIroVmHfk*0ziadVZ3vdoMa2{~UR6;#@n zSUI@s!i-kg1$AM^mZk#KiCph#)Wr6dq=Ll!LQMsQX;#_=d;s5k0ud)SrA7-0#N0sO zynYun^lCUqRdzw6bB3f{(BN^N3#;q`^kycPqND?B4D!2fuw@UVkMFamWW3ZCc?12rKn(8SvX!( zK}6%hf-=|Zk3*ocIGm<}h<;mTq5Za$U4VJ4OtH#wh#gCAaOFl=X@pZ!0gv-bD#%Q; zk_rm7+IjD=thA${WC)lua=mw0HcXB^ces>Yz#DmKDxhs8lwE+S*UV~#U4W<=Q>7j&KAW56okmpB^dD!vx|C$mSeby*TRxp5y zxCas}%_&JrC?TQAg1MB;K~R(c@-?}~Bqh|40uS`2rNLxL3AB~2rUW{!TY|+Xgoq_W zh?ZEH;?cASN_8>Qc@;eguGUpY=mYu#jgk%S3 zk`a50r>7*vMlk1VPalw@Kv8UsV9wV{PeVnq1Bo=jm#;gsF6k&h8jV~tk_sX^rBzgA zkOM|J3V3%QNwKgla&#+-ZM0LGgt|w>iyDs?DMtZ17Z68YQbA>VOG0flojiXO;8D*s zpzPRoi4OFRurhw=%px@AG@cJlPt@82^i?z&UL z_`1$t2`l=#5GQ84%{vAdc*ralW6-AE?`1>NVzL*&`ka1*E$C0j_SkkWhnZZp9d8@5 z8|Fy?3s4yiS3;$OfHhR+9Z0CO6|RQLY*#=~~_X|Dq;2HMP9u;29t$Cl}KRtFuFTJQ9(?Wl|+GaowuDyNVuvT_ohpjJKv zRRLx1yLmqbT7~m{e&0%KwK30Il9k4Mr(FXmfL^x}==DA)L=7Nubky#pocWy6T7i>) zj;g4Y7OpFxwE3g-{gl}%*%h67DalIXQHokQiAOjCY3nTM`>FRPtraaw(PU+}fU;H~ zM_q5MlrJrPKN9xmqAF{JW-H{hQe+*Nf<12n=ov;t6*fS=F?xyg{Y(E_XE%$qRy6J) z$x2gxidt#sDG8KyP}IJkd2G^JZIon%9WoasTW^>ULiUxSR@(hn0%b2DX{~tYF`SXp zTBWQlN!G-;*NR#xH&g;;FCp#wS?pD^E1vCC>?*TcKv63%m=X3Wjf+WZMF;*$Yel)i zlB|4;u%K4j=2Y1LbVj-K{WMo3trZ01_3IKv^7H`ToM&+zR(qp~I;q zS!qKoMXi*wDS@(=ko5h$IA2+-H6k8XXjV^A>&8q#0_|&Y_7alTidS4HYXvGxfUGp* zq^OnFVa{{R!BeH|83`3LPS4dUq0;6I5-Kh3lu&6+go26@jKs7gRGJu*P-*pogi2e_ zN~kp1BB3UB5K5?Y%B_To2~O8rY^A~GdC~}CSG2fQN;)?hzfpv38}o-XVQIOfaK$wG z&QfmfMq9)xuNRaCkqs-!+5)0&jdsCO)(UDpH(25OQNqOXqrzGNmC~{1BRD8VzdqUq zP!@2WUn_vJYg<~YB_P_i+$bkel9lt1rXx5Im6?FDR`i`EeLq@Fo?EMAS9I37Br9z@ ztf=))2|RlgN}$&>vq6L7t!d_8n!SjVJc*>Wx)*3(tyVgYLs=`@9$ET+`p}f@inAJ( z`wD&K&d&fvt@KSSfd)j|P-b^>VM&pb9|t>6ff zTTqb|M=SJprU5~%y*54ol<^Lv@26yGX|3p-O-WW-zpbnlB}+@7>?NdqKVynYYjv*} zJhK2vR$B3+sFjkXB~bPflD?mkrKPo^L)|4=X{b?ADrKPo^V>+d^s_Yg})JnPFitNT@W~BB4?OmV`=KO%f`l3Q4Fm*xdK? zB)uKYtQfgjNjmrTNF*qt2>YjQLT3l8CM@laBq(;L?=0o!-udKuA>)8HX=Jq|S!u1O zqE_BZVcrP9mkaP*P&h)gs(4ul3Xm&SS}RJwQP!$_WcpjwmqWO6D_d< z0?s?{p)A-{WA7|wt#A(#YgOzjMbvsOxLK|@0dyCF;aqH2=y^g;D`~Bkh-h0{8TCez zl{TUkj;lmlyDFe`;FR?J^r0!)6=yZVLT268L~A`2wbD1S1R4=-L(dapt?EN4Y7&y zh7sNK(iYkRXhrSjG%jcz%)}INH!x<%GhWzXK&5U$njSl_V)`31U135nreW|2!HTpy z@7<@sj!!8SEIwLarGNmKWL2+bkHW zjGlMTSxg=Ud!Igi9_15^7N`M6yDxN>uW%IX3oS8}G(hY2wB@1{Jw;evwln`;#57Pw z0GB{n3aL(yCR_J)rM5Ni69JXUswjZ=29iM8qgFY!@uDLyd*y~f9D*F$5-Lx2EN%XV z*{BT&arqrV2;vkfMu2Dmxd|j$=_cq~Z}!&OXm(aZWw#cnF@mr()+?AS6hMqi0%bm- zat>^TT?ESec<P7QmkO7{mi7DwbL?oVH5B=5DAp+0cB_HG~c1z1v`!B zD5!~MCRXK!NtC9b?AJtlx+%7Wia>I2NwU&SpxgzCc3sd=S%5$~2Qo(Xo*#vR$!6Ny zQvt=i-g8Nnb0Dwm-jZw!6@f&piWTGt&Mt-^Q^g8?7CO3+J677SWo0h|VQZC@+7`ZL z*3&FJk|BU@%ym($pwQ96%Dn~NKG^~iDh-cFK4GQ(M>JSeMxLKq%EeV_QH*lD)WY&R zk_y^FnTtX;3a%E*Zz$4YZZoa75u`=dgq>T$J^(7)T}Zf3A2KKq4bcI5GLrK^S}{E4 z$X%@S2h*f}G?R(9P;O4tXyuK9aB?YUnlr+j`z33z`I&r`A8M2|(` znUK=L_JM>-Q$30^mlB;gs=-q7v64VZnX0xQZiWJSQ?O& zgr%K6B*oJ1hwCn!TyVh29o7WD9)*+iG^lx=6NcTzPsDjGfIStFp{`(7X78cbL%;R4BMeZ$hFmY;7z!;>W#8P6_23aC{tcov3jG|*1R16l-)0a zQ&?|w!igd(eZopwr8BDU&(X=?P~{`EBv_t5Q>+$z0=5e@Sg_5`UmO~2Nbs@Z%|$L+ zN!mn%j}mOA%}q5}Y7P=?Oxuzg)3&4*TIM1tA*O8!F7k*hPi-_1D=7h0+5uM9Zq%Vy zq-{4EGtpq_uDYLxZiXD~trYuI#<2!SejK;3~qeWx*p!TFiorSTf9li?A{j zYr=6m3n5BM*lUFQ(GoA)R(3+7Ne@X08T9c0-R8t{pOUoY-Xiewolr0qFF*+ew^;xz z=8i@z8Qhu(D+9xl#MGso&}eu@fQ9AWSRPn|jpzUhX(Kv-ZnuTDh>(_$k-U|({D4KvCB2s5Naz+8EGr&fq&QN(0kvaoxMCxqEgy(?R6<{M$XMl}J zogoPmkvaoxMCxqs6MV>dBU}`KjYyqg=2ArJ46qTYvpyjzAa=E*6-I#b2-t|!**?%+ zLE2z_FI?_7?KwrH&Hx*cIsTJ(wi*o%F4X_cZv)X|IDokW*of3w zF9c_ANyW;_7LhvJ3y6{d9wQ1115#&@HX?O~2?-IYGr&fq&MTSV#%uo0;I|?E zsk6NzG#+r5f$ANQI)k(ksWXhbps6#($wviSg!_TOWrX{IdEODp7gVqXw4&d81zUi} z*lsi@sq6&IACE}Bpz1G-An+FuR@xf(bCR?}K#IAS4=bFd_zYJwI-5aKR#$3|@Z3lGTWI zEqlW`9Z58 zqRc&lehb(L`YkT92>LBxBj~pYo?So$2(S_KTfj!pZ_|qIw*ha{HAm2I(^?`r*8nzx zew$WwKMi=7f&CKUet_N`5CKBmGJ<{!*a-S9`h-Q$Zvh)YzfI_Q5D@{|mI(SSq>Z58 zg2)*`zXfar{WgL45fS~syFVZSm9{;Cehb(L`Ym81=(nI!M9^;m8$rKC>*5IdEnp+) zw`nU8^jpA2&~E`7LBCDt5g(9%0&E2R7RC@kzXfar{T7sm2>LBxBj~pY$87-r1+WqH zTfj!pZ^1>6px**Ef_|I!ErNav*a-Sg0Sf-rsr{Wd|f5$;E)>jW$r(yev1yB5%k;M_%p)&$Tv#A#q(mC$Cwv*qURJo36>WSNU(UEk}Fbz-Kh^I!Q$yp z?lK9scPVKPg+R> zG-WDjpfC++sO(aZG(e9-1r-imz#hP(iR^)H(X$qd7$~`HB@IvxtFi|`AtBd+aAcw7 zJX3(6RrHoRx7Ybm(g?28lw1Fl=^a4d_=;AM);?E&1j^i4X;&4t0h*#!O7-b`d3LP| zOD*6hL{o3_Dy;_u5FFfPmyfM8h8;jC| zBvBE{IA1J9RN7-i616Z6k0L6q5|l(mi^l7Ns#{-sg*L{%a1SQpAuP;Nq0Sdl%T=#>{@3tM2lF(*^mt}Cs$ zRMfiC*t4Wo%IlRhK%WE}Dsza1IC({;o7@CKln|)Q9aOd}Er}Guq!=>Jf=<$6QC5+n z0Q$_3Y=AZv5~6M(YlWOGXu^2zw@8acOUnB5ZuTlf!7;HcWwkam**e#NA}VD=YNE2J zqq10-L`vRSiUKI%N3j7^1e3Lr_SMc@EJXpdI!#(D`p#4$7#jw3otuEPTj@hf(g01r zC~qP@u3p&!Jo_RXg0y-}`F{8;>u8S}C(w zSu4zzJU>_@tTp9n_*@13S>*Mj2Cb5SL= zQYwmK1ciD7k_IRhMLM)fNE>zx?qMDgYKG=*7XCZ214#*>B9H?HlU(PeZM5GXTA&HA zjm1aSHh&(X#D=+Bf{6i@MM#7I0mw7VjTPRN!B%D4{UV0ha@Ylzn_22qN{Xwqt31^O;qZ-%)bjT z7?HW!iUMeZK!K6aHjHWyP%C8dISlN5tV=R>cNrzfoziC{0~Cu+S2dZC9Zz8YDXA zVJH_YZ#<$Xw)aaWdq8jp(NmA0D&@PF<;;#3#SD<F{TNbdq zC7%QvLC}F_IYFoUBD1>P3k$#r1f7gL4BZNfv?;Ubz9em?$BYI`_pJuoSh0-+i$XqT zy~>gmTFNI$TdCKj!DfCi3Rc!=XD&%v1Wh8AtTh(lQKVgNG>fRg(j<}uyU^}`8f<2M zk_3wx?j$Iu!D2GU`HM+|r5(B?Sd1kl5g84ZGWR4{44#WvGECZvSh7S5(Ih2cGDpOc z@m|A{w3(6%G*}u#kzfnWS8A~Itt-Lets8KcEtPh)m!xepq^!Zxw#yo9W%;#Kwl@8E z*cRFeY`^!7oP3n*H(HZ3?}PP`)#PBDug=T+LN8uLRLZ-QMCAhmrndlYT;?H^B%sm` zFp5^GdoZ61#0H@0iusH5@=suNFlCbSRA?>dLDn=Iv^w zLoy{%7k0fUx7NPWidP91Bw;M_8ADWqrA+buIGMc(H&k~<2ut(q^W_5QW=$u2%$GQI zRQ661Y<8!dZp9FG+PZC?)eZ%0EWs!(7LCS8i$xt+Nw2)`@_bqWv&q?uL)ln#_^brV zXu?8TW#1{MTUsmn)|k(NWegExaRSA6!(cA*BvACqb03OjB^oXgHWo;CL;*!GEYRb~ zQ(h4j+}rb;Py%Hs+xh%5HY)}XpNlG?(%hG10<>|Ngi3>uk_ISESVFA<{sl(j62p>2 zr7fbB6B}Kd7#RTOJnOlFeoi!?oPsEvB(l!a%`oeX&Y}^{mP|XBNuVsxBWabsU6kFL zX>4CPT9BY6`$|J)SC*vL!d6StD<)frfMgYz!@i8U6(y*(9O8MN%el5K7wr~z$iXPcn zk_Kp-8b#E`JPgSQXz!c8@n*fDJ}~3lUS;~$2&(= z&X!821}Pg0L|$?ZDq%cuZbMKR4Nlpv^r*tO3r7pNw3UrT>yaf;mUWQME6RQqo>>VaG|9;#oY+8R8jxhA zlVpWcAaQ=Vgi14-^BXJO@YX)}TP09-vIwVO@Ag2fRXAA^?*}WKf=Chu+}S`4(JLkW zN_wSSBxPgKC$X}z7CMWnzdPM?)f1G2AR|Fckou&`}5mH(g2;$E1?Fwi4*3Xk~>S;t-PDkJi)JXMc7&? zs5JSioY?Ei$cV~$g+k5<4bUgCq=D;4JZ02yvI9%ltt*{Ap;+rmQ@YX)0LStA^J=Bj zn3NNH<=wP!^vrrKYh~{N;h~9POxH(n0Lmgbidr{XPo2aI8!&NMcm)Z+PfXE7twinf4}A_A9EOi3WuInz=(f z?`8A8Aj&z|-vsA7KtjzCXG^A;7p15+m4&H5gQX#24VJd8kYFpl4K!GqF_&Q5%HjhW zENxw&z~&pJP-?KK|2a2Z2^MWG$?2`Z(x|2eOUeHd>`KW48Y~#)0ZX>=eB|_flQ-IM zLAY=8wz4?1gi49O^S5~3Hnvz2DD#b^@28V^1gA5jF9dNq6$Q|lIT9!fX-MBsdxJ=8 zMboj00%$F)1j=p#AzGZ#5`vt8!kYudmGq4~e*~hah=?j^6`?|MzY4T()Pb@zjH1E0Yy|=TPW?T2+kuo zWX#1>_7#G9#0DhPfQB;}!6zcB5Yx(VT*&<*L^U(UX%kdQR!SrkY#`IpI^`07{R>4@8Y7mp%BOHCYelC7DGET*>iN+snLq^N zFIUR=Q)I2Q-HM>rN@;|esLW|m?!ijaFG{$rZtSV8yj+mjA`X`F$f$HCr?LfT)>JuK z!1^WjDy1?Soo}bX(#mB;2Q8psD#EzznW0!Lo`ht%6o0tU0a?m3qtQ03f)zCWexFB0 z_@XbySsYJLD^Qs`C>(@^=Zh5u(D%DwSmm~|-Kv}dcxJHtzO-6}u~LM~5Q!JIvm{j7 zJYCWNE!Ge+I%QdC&{f#5%gXL8;m88l=lYyxClIk`@$^#@pfsmB9~Z!MYPMU27kmN1 zg(yH;D_T~e*uX+V*^;dMf}Kz36r|sXGoTn2y|tB_V4=;N6j5muOSxas*OF*eLZ!3C zBvd;3NKoraZ*9c{){PZxDdxJ;w#kyLv>CCYR?2-B9t7x@%6!c3f=vc8%St^gX}8kC zRY}&$xE+#S@qRmh5hz=LI#|kX-RN{0Au>`n+RRCkmAY+$TDO%^w3RDs+gNBwu>rVk zWM3)o0nWvfP$L*_C|ixNS40PiUX_hS^Mn#8d%a4AMU#&bDs|hGvvsHA&m>gda0EMK z_9om{dI~708+*M98*9gjb@`RG)8wPTYv{R07IqiB78Ju0RHY2ApcOND5J<3T>AU5vI`{GOu0yklYxOs*I!%UB9YZn?g9*FAp2GE zhrn=(kQK1Rw&t&boY`6_*A^H~L;?MQH+yX%`9zFBK}A6S`rV2{nT@lJ8qAHJ~ zLZ@pgTL8~(BCBw^BAY?fs+?Daj$2nmrQAtr2hb4;0x7qEi*&t{RVd9<(JF0YB55_V zgGI>^l^UVd%E+^dR{2;41(kM-+}ivl!1+yrsFfbq5-3}L>HBHvzJyAtqlyCPGgAU( zFAU|jsvC=7Nm`||pcMtsXNz(KR$A|)xE7U?Tov~kMNLZywv6?>&ls}gAHPTTcHP;WF*E*L?*q4@XQv;>2# zH`!AowjnWdOg}-&S zSdyp_op>wAO+;4ZXjy6bvxG`3m6gMFr9OtVT8*V&m5oKms0c5ux-IP1-qSYiXTu$2 z2CKo+RIvn`D$Bb_u$i}zS9Dvb`zA??00}u`C0GpZB+nQH7Gq}F16hJy2C~re=FrxK zxiFHn+l{#!5-eQ9h$Y(t>Y*Daj|c}iP?=)q5AX(lGI<~=qGEO-xx*z?n%-3uKs!?l zjzI&}iKtZ(m5yqWv`QgIY;sTZq77ZXfkB;M`0`i(6jU(W0zY#yGt5{VJi-C$fghUb7PFPPsGC z(DZ8Y*Q|mX(RT|S5khtrea9&0K#pjU)p(06<#Z|BBNonqvM?V@u>#Q2$h{?LfYt#@ zsI;4vva>L(g}82#UNa+5NE)E&4GFctF#VI*;$nmNhJ+% z|6RCYc#kAyXCbgjP8Uh9AzpE%Ua=%AWzk4_rR5J2Djl|{Xn-?b6pL-hbDsOJ5-RtK z1=~VPZg#^cs2B}-t^sMaD4|-}S&h!Akx(g3S=s}1grVXOG)gI!Q0c7rc@3a93T^Q^ zzq5dfZ2#5!6{wV`D`|k1ZqBb3WToQ?Bw6WXL}|5X6TW%h1sb4C8c73{ov#uqoun{- zW}&Yet*%mJU1*u9Br9#XAn+)l0@~9_f?aPcN;DlTMk(CA>h~;IJWqk`s4VaziOR|$ z=Tq|#mHIA{0_db@4K-p1&|V&jX|0K+;rfv_7ktEG(d@aTR_eS-vZ5;b+#QfkfsOhu z8Z7PWq&Nf{zhvh(!Iqd6D9eTUKjaM~99i4-72E}!3`WZ6`k6JYjZQI@KpCe}0;M#M z>1ZCbdVQ;`4$4w6%6SFa7u0rkXA4@z$TqyuPeJjzncY=8XE-RR*O!_j?o3O~m16}% zE16matiU#Ps2MLr#1r-Mqj_dWCwR-~R z7BFAET##{K;SdQm;)zk{6GJ&z3ax!n9&Uv`T!hUEDptU@O6<6nBxT_+#bYTcA|6t% zA5;djqJzp5@3J68czy&((c4OUMBOV}XQMahxCqM~}-dSkbJRNLVZj?lf zl&1ho9byS~i5OXj=|?n>e@}Q#Zm?zDXqKplI;UZ2NvN`Kdy9wwb3kT0!W{63Vb_AB zgneiI2sKzb|3ZSr)flm4sDTJL!Ir$Rf=EdT7#2@bTM{hXS=i=TuuOxcV{0^6TGTGV zR_fAfu!RMTBv_P4M=V*(og#4cPQb);<}E5pSZ|b1roqzJtpvO9iNV4ZiBfqM=ar;I zJSyN|#4IlsmzSjFZ8d;vbMUs}sr!`nQ zZa{;j{TL+JLW|rr*c#z}tSIh`xXVH&l$SMRLOEdRb5B{a4HWqR_XBUp2=@aGq9fdo z4bMmt1(tNX&@hDryV9cE`S=sJu@&ZqLa81xEd`NP;9P+phvY zdRr4SE=5#&fk_*H5+fxOfR`BHAZ;5B+iTL|F?Ri1Y};wWMM>J7_EL~w;U$tK6DYD< zqRD3Xyg1kP6?D1cSxYuU$xLFI|?O9Sv*Dp zWid|)^m?Z-Ba2P^S4Gn62ZzA=X%t41lyL(D%1s_26VWv@3SbDeqeOOQ3wSuC2YlqIdmO8Z?XH+7~HUWBJshFd|r3ZVc4qew;cO0PhfzvIAQ>1u#VuUwD@G zR1}a{Xh@TlPPbTAL0ZiDVdud7e#Mv{qF2SXFySOX)FogGRLV1wzMnQ-?+=C9v!&9w zkg}`j^{U*2XemZEfIyVam6kS1i$!ljMXfY)BZ-Rbdig0>Xa>l_gWfl+$wCVMu(e7-ycvfm0Lu;6l!G{(^AnY4F^hEr6FuZR7wezL`}@B6j5nn zTM`u;>-+>zM5V28B~j4{_Ignx`jeq`b%a?_mY$$h6m_r%#{32VD0^c|qAu5)6;;)dJ1{Fz|@EDm#ESQIkN~jV0`Wjn3ngK(BX$ zOXtjczhwWQosqLjvi~iFFI;xY7nY>mH+BmMTML{< za;t#(R3mh3;# zl$fvs5{e)%zXTJl;Z`K2G!|h8BpM8tK$&A9Z7X!;gWAqg?b@~qDe)~?w z5`?XVUT4>zt(p2PlBDb*Bgrm;}oBM)O+>lCs#9Bq@trNRnQEt>E)nFhu%%wxyKM2aEOm zU{NHco%|$8*|j3sKf1S(@PcIj3#xk0^(sl*JMNvsO46iXxl2FTS&!yeR&)JpaIv)Mw{Cx22cX7m5shuq|<6& z8Q)IYR(nXh%DU5bm6Eg(WAG{;gC}e)90J6$gcB>#+A~Gcg{4F!N!b}7NqT+9po+K+ zxvr(pXDJcs^I4u%k(9nxq|*uwGsyPW>>mfq`HMx878zW!2PA2c!zD@(c0s1mO9hnr zEW*}`;96A9wU8ubXMm(r77UR)_@&=Jmd9; z3VL8;GoBI7guMy^2hpmq19%%A36xzc+WM!EEK6w-JD>&Z0Hj#1-vJR^3lJk&KwQ{X zl@9Hewp9%o3Q=o76P8+O6BglM;nM{qP?lv=b^xtrlR(+EqHU`d5)R{B3rX6BVI$`^ zmf{JtTR^24Kw0#1e!l{g`79DBdkD?%*LI`)PzjWU!<5gbgGD7!_7s*t*_M)Y%1!_Y zlsOiP{Wsj#I_0Of~DpzIcqw$(;^aY?5YN?NYp0UM283VU^{KU)xr6q?{yerQ>NNY5B|(VQbaQ@)r^)i(X5htVTfCua)vcB~W$?NT1Kn011>i z778eO=%2elicaY`ISG_qE1Lb&X$O-1NA$J8w1qW*aSqg5-3ZFNT7_$C+yed`mVgaVGKJ1v~5*bKvddR z>k_a7APKQ7VF#=hog!Tk*@Et2uW#=MP>E32xsE@aTERXBb@H)HRnV{TBWufRCQwcO6 zGLf)S0XmIvCg^x{Nv9Fc1no|tNSax@UI{e9naB~530jjTeSU;9ks~4#*SF`vA$@&& z9)MEHn6glmi7tUgL?%i^WP)}omOekinJ5vF2|Bb%`FvW6BY_5_IZ_QsbEF#KOwb81 zl1?L>i3nals67GE^BO?FOte9(vQTswt^^w4Owd|nNzw>sqD43pEg~|}0wNROwOwyf z88xGqKY7sO>H2pR+R!j_b2D0-T9_3vedzj0#w&h|2C9QP~YrXMja5%$d0N z?w{*Pj7@cY$Ak_V;G$(Zs8hI5azyzxp3wo@pZ28I*8lnexLAMMlvP^|{SisHey?Jj-1T>AxdmtyyyokV>T(NsPLzekCbjjCsFEuYRdQvE&}u}L zT#2ZXE3{#dw*C?20wtnc0EcS8p%PIpP$J3&3hznYU-7g4AKF@6uhkmCn*QtfjcHYIDr*FR1f?Bh`)lhTkx9c4EwWb? ztwvoaKpz22Ds==GU2fL@?CIEW9GXc=+iFs(ydVLfPpw~MS0KGom1JLW834mT7nE>eZ&ICZO zcP0QD;Y@51&cqhsOl%R(#1`R9Y!S{xK%3>|7C;~YXoNEnKpJM-x0th6KG{TwK zBb*7en!WlRh0l+0CiVztf{w3IUMB%SM^;KfJ2 zUs?Vf@jMAALdNGuoG5gHout!<6D5E;0i8xXPXeeD%PoL90Z?|LD61b(gbYa|o+l;Z zc@j{BjL(mFo&*#jBZ3t1JP9a5hNKbClYk;*NE#9A3@Ac|q!G?UKoRnC3n)ScXoNEX z($KlvrySA&MacO4i04T_5i%r=c%B3>1{Xy7FVAoTG~jvCV`!J}(;h|$01a>^x_=%Z zX+W&ApVHS$ij5io8sJQzusL9%Xc4mVHeVvLC&31TE$REGi;uEe(~?b0t(-Jt(2lo+KJ7 z3x`Rlv@%IUWi~6J(zv~b$}TSjmA4R)P-#q1LuFY836+j@(oh)_LPDkS1`U;Yn-VJR zBdDP=M?*rT<0vFlG*UfxiZoOfbdgXg%S1zEWi=8i^=w^;Uoa&;Z+ND@)@`8laJP36%~{(@-P43~&x2R*Md1k~EMayo`np$N^SBTUALK zpxr7o)CeyF%>_V$`TWh--@JMK{QBLm|M1Q8i%&3HYwJIJ|N7mFPb67sCA@^%Xs~de z#*Im*0bT}B1H6p&Mo0Y$dIf5Lm$61v@Bx$s9p))r0KJ~o0#J6rN|Lhowgk$qECrNC zbtO=C2}q#V=b+bHKn@z9?EI5HpB+>ZC_7OkQ1-x(Kv}#|0S(AOgL}k$Ye~}UDYB51 zd8?A7%&n9_S(HfvWsaHz%HlQ(Xg~$u8d1RqP?i{xK0m^lNDK@uvKvMF{)mGbX{Pg6x?)t7)iOxm zUn9=H8gc&Bkn@jH#gwIL5$9hEIseeB_4=)fc9j93%=K6HKN^i(|NSWDx&HgnzyMqE zEcB;+f57>Nx~qWir@=Jo`P&$Bc{-K^F;QLp0{z;Ms#Ar~@LMWn= zr0k$pV#%N>UZ1U8dHI1P>(1VP8Y;V1BvksWlu&777!8%3RuU>5)}^7cLr_AcExR>T z7O0m{X+gV!+S6+1&V`1`TowtHPVCiCS!_{4r8l95%0iYBDouiDsLa8XQ0ahO36%y| zHB{yfNT`{G12ohKFJqj%%9GD6RtUT7XiyLU8W42cBZ7|m!frxI zr|e;@fZ_>z{X#`VM^To3eROn>h>oJxJ;0(OqN6*W7y+vvkjC0q7H?EG|HfQ)2{eGg zw$m~WNz#CP+fIw|B}tk8CxNnXkOay+Dg~5|Fqc4CBt!y@a3*L5Ly|PYnb=uQK$0}V znb;$o30i8Ud_H|qN}v(WL<&f??zHGw`h524kw7DyiGcAF>mD$EV%=$$QPF9@_z6hL zB5IPP5za)w_z8S|gfl^-K9Wu&oQZ((6YEYJ11O(Q^B)puL}Y@FpHLcGt%-(_G+5d< zPJ>PC1khmV2y+QG(_oqgOS8cmY-V8^4VE&FCD=kkiW=<3jzbNWUNRai9rhr>)`dk^ zG+4?E&|t9@&I3#uEFBmw!GeEIf}t8L?NbY(uqP6 zEFY~Pkg+#Du|Pwmnnjd*vSTY`WpP|dR>~33P^p0_8rT@iUy>Ch0dmkvva-;VBZmU%MnO=r9Fu>RO)pp8pteAEXkT#{8d6N)cIC4Kp7pHtSks8q4GDF zqJc^uj1nqK>qr_vE4hI4l`;_}H)FlGlRvF_>ptG>-Ho(1yJI9+TJ|g{f%7pnSei1| zU}^3^gQYV(CD@&^QZ-mwR;9rvdV?wZcCV~VLy{Kht_UkjbheFhEGF8nM?D>6Q07l; zNUD(ydtc94N2XH$XkFU8e^hB8S%Pgh7BcC9npqt*s)PCD8shWpRhPiwoEDYlR1{Hp zn?XgZblg`DeM~EW-&_i6Vo#bhU#x;*cPxCY%(_Aa47(6D*qzyy2HTh&NU(g8q6S-- ze=NbSl(4PA4xF;{=KP=R&?p^EgQbmD71(@35b$~{L#;-H`+=_D5$*@huZZXeYD*%b9~pyYB9;uk zQh=4^jk1cReY;Txp#;0HEH$RV<_PyA^IWDRZQ^Yrg-a(V+J9M+HlxKvzzK$C`4Luz zr$dC56-oq`bXyljA<|&!&eS-W5klxh@51rEg~lg*od5DYqyA;Bw!L1h$Sl#IY~%M<5rTDb-(%Y5N3n_5#fH|z>RP}?pxt%C3IeEKu)s5(tzOnP5|r@ zkdy4N0XfMI8<3L(>>7}h?63hjNx*IaImr$ikdp-L9*~plumL&A4jYh@1Z)b(Np{$P zoFrg#Ku)s52IM3GTLN;D9X22**1o80t+XkHB<;4amVg>8?J1XNHmKs={Du-qaV;Mc*=&dwui+sXe?&0+tNvfe80wT{hN*RoS=eLVF3OT5QXME1D{wChWfDlr%_xEiaPD%Z9mWQzi>os95!z_n9u0iA0S;uHa$YXHle$}3h@aH9t-Sy=*DqENyb zz!L4S0W49#ZUHRO4jaG{1?(Qc678@7EYS`dz!C*)3SfzL*Z`I&U~>RVw8I9lL;+g@ zSfU*^fF%l8urwkL#!7uV=@_p8EKw+-1+YXrYye9X&3o|P3s|yx3t)*t+9iM`+F=7& zq8&DXB??$HQixcxHGm}wX}18DXon48i2@emqyqvKnC1`>sK7%fB2ZCN0813QO#v)X zz@k@2#FBx-7hz>3fF%kgp!_r-99T;LOBB+=dLxz$(ZGl$1F1FODGfG7MDzoV6lmN| z$m+CP082F8dIRr(B}2c*i0DUK0$8F@0xDVqVvML}jmVQU1ji$mYzttCLbqE0OBAqs z086yP2Czf{3)_uYvJ}v{2GZsbmT1c%EYXGuXaRRwL!KmJ$w~-I6g7+y?gwhYB9bpC zeu;2DK+6wsKR~gHV2J`Yf+gAsVFB*Pa>Kl+>#Yp15iC&zDI!>+fQ?{@E=V8;xF3Lx zV2J`Yf+Y%;Sp-WIun{a#@FVX5&ucr^B*1be!Tj4{x%HN!m(z;?8^IC!xt~V z{r36Yi%+jP&u?G8d-L|iCoewz=K1y0Pk!{PpZw^jfBW?7=g)ul`ps8wzWl?} zKmY#szyJ6R{>RT>e*5{$FP=Y!8}+X*e)!_wp5K1^>dkBX&Gq9O{`~y!@7})rwxj;& z{kz}YA@S2s-@f|t)$5nDxbi`|kPc{!jhlSO4&%&;Iu5$N$&UXTSc*)6ahK zlOH}UAFsFd{ujP{`TEuWjlXfn#!r6o=IgJYU%vzNi(mcvZ$Eqb(P!(v{>$s1{OI35 z`q|$-{qp(qk3W0+^7C&${^+BRe);^(+vjib%lE(j^z!u=PoEus@aDJp^P4Z;fBx?2 z=PzHs|Lx1q-@Sj^Mf=(7-@bYK^`HLM4?g?(&;ABr`^Pu@_lkOgkCxj<%l6&>3+Dub#hs z`s&rUScexse);Y5$I#6;FaF~{e)!@y?|=K-=ePgotLNY2lmGdTfBy4}Pv8^&<`3_l z|MB_tm+yY};uE|bSF}R<^G`qh?QidE`sY9X>fPH{Up(WN5Q%^H^6i&>xi|3q*8lk7 zB%u9g6x`H1-*%6-OaB)+LA=Bq&mOZminsj-cIThI|Igok_}~>&2Ky9}{ySKz=eMt3 ze)Xr{dj0Zid~5&V|L8mMo8P?s`SZJ%Uw!rJ^IyJs|K;yqV}1I*{0-Fn6Kv|Ye}{GN z8}y%VA0x?@(CQ{Fhkn@qqnxToCXmTNX9|og!stT$@Q2ICH~hPA|AO}yh}*}w z>+sq}&1 zB!YX4_bu+(Ep4cM>OaB}o*VvG6aj(Mx!&@nLU-ew5xOAR3RWd9ZP2Jv-XP$}kFM17 zHYsviOTSw1QmSyb@N~oe82HhZBJYzTgQbRjfyi=2e5$5phsV!YeTBD- z|BnrfylEGE@P}6lo+kxI(gg*K81cBGbuW4X-FFCHD3~KqF!yn3{jdPn0!0P|LwvWg zbe`Ll5|>Gdw~EsV4hW2JYnbuZH#NQ?CG=Xsxd-1j^{+r7OG0!HcLY8Wp(r$sy;STv zDK@6HU}hdR_KFJMau;#rM^|dPO^SS5p}UOj41P8Sm+be;WW_-Y!SRO0JX`Sh?;HI; z|L{t=m)ScIlp|Op8qW5H5C!jxzK4f?cB$C2w<6Ts8%^NO1w#UtU>AGrXP1gSdoT84 zZN$tll^#h^G^x5<-_Xx46?^t>yn8@h!;DG}2IIXSeZ6WE9x5nu zty?*o`l6XU-na=D4vx)hg`T}gMuqmC_NAL+_S%U#57xP>1m`tQ0(g@JhXJ0bXrqER zH4+Z^Gae%t&w)eo5U9F8!e?zl1fd9}f>N1_Wstlpy#?cVUS8{#q`AmM;Obt+~S)@%Kv zb@r0mw|&87(c=L~CL>nVWrXL}18b-gLl~~#Cg1(TE7iTtUUU!;BKO*`f(OWYmvQW8 zmx?`i(cz!I`=Z|w+PYM#*}Dvkk{;Vc>=F-9I1t^lUr^$UYFxxxy35*$+PL6wPa}D| zZ8%i=9FI#cvu*Y=`>yB;wsQj|6MGu*VDKI9c8IVnVz=-u&>8@Vj%%f!z0Ghyv~F66 z%OeDY09AyuyUkv1SbLD+a4vzegb^+I9(N!5*`*tI_I^X}#06tS(8352ckIY}2oMc6 zaQ`AQ(VJ1B0KU6nD=uX4N&Btq4W%mBawrc7X08#rJlXxkW|7n6qF)Do{USb?}xFUT`BfH zd&412+=qPidA8W%Xo3&1$9{IH*mF1Bcjm_aUq6)h*$c2{cy8V4DTrA0wjqdP4gBa* zMbBP;|M|RtINy1WTq@@5eV37m0g)dS;oFXr<9-(Oo!ld0NYLQbgrR=ddJ_Be?bij$ z$UF9=Gg`K-`=3K}3*z$d-;tAn>rj_V&#`^_vfGi0Uf_ViRYS)7?v<}_b$Z7mP>4W{ z#$&W^fZ%k}K6~4tt;;PT%8nd4c0uk38QLkK(g*Ecz}|%aeqaA7|m--e>np20S)<^aoQnTk6|)^oRdzk|T`# z_4BvCdp1Oyzkh!xkbw{K_SM&~-o5&_KmX4!-+^}YoA>YfAOHB`7oYy}=Rf+#7oXs{ zgP7xs&p!Rt&wl;0Pk#X-6DTsTUVriG^ZtA2AkaxleD;Bgvu3^@vK%27 z54kCjD4F>nC8$zXN)(LGOWBT)n}DFuc3B2VkHFYE!++tH@jQD4{trne&`$OJi!9j)Gu zHpPzm!XD)GcGStz^ZGP)w0b+*6+7w+`$5jl+Y$ISf}F;VHg89}Vn=;p4{~}t+7&zM z3wyxycC;&Y)ED-E>FsD&?5Hp70n^*juGmpu*aN1wquvQ@dVltXJz#n}0$)Fp>fcGMU41Lp4SsQ1C2*Qc?g-P;j}v;wBFqutvP!W06gv7_DF5h6?T zn0;Xn`t)|xtM;e$*%$VJ>Fo$nBLUOc(eCXC$sz&M*wOCo2oVDT)7a7O?WlL6n%AeX zqutw4R_v%R?1wc<-j1?jM}1)rnBI<1&LVufv7_Yes2BLo>(kg#@^%C=#XM$T*u%Gb zJIab3^@TlPdOJe0SCG@#QSx@wo7PP0voGvHPH#sD91EDnj*_>dqS#Si*n^zjj*!h2 zSro8apc9 zj=;AQFpV7*Z%0+JqrR{o*1dQ;>I0MJ^=a&=csl||ZXUBQ>_JX%M^&+-zOV;OZ%4=m z3vwDeD&CHIcgbme_Juvj>Fo%0zXGPQqvGwTDR$Hs_8_OXBXH9NIgK4vZ%4gl>AXIT z9aV2fsOS_hjU82QM@_M#zOWzkS-l;h5@cS^zOV;OZ%4fm-LyXY!X7Za9f6)DU>ZBB z-j2ZK5-^P&Rc}WiOADCBj;gaGP|v;x^Is3`0Dkr6^Z)t$?&){EC&cG3zj^xh^S95x zfBHYraAI4Z{{0Co-Cl({m}c#};;}Vv*okv4yKS|?5pM8n{OV}7!s=1Jg8tv zsHQ%CJ=$n`P;;M+nG(qR7S!7kYES2NYN-%lGkZxDW3prjGMI{ zW-p04issoBAP9bsXeZ<(FwQNgw@XW}7*(RROV6)B#|cGJYnPs2ku1StP*O**@C*w~ zycQ&N3=2=OK%*W7)Y|3Z?b32AMnB)$<>Kwqk}O6+tzCMS1vr+<=Ucm6yj@zF#i*p# zqCC$cS)RoxsI@3hv;h57`Fv|po@s&B5elfasMX(emTEEh`Ic${8nZi(zrQSDYnnpvJ<3Dp#CkZJ+?vgDS44rEM&mzv3)!W6*XwA?LWIyg^#x#we&Y$jx7I zmbozsY7Np;H}0c(zSEyQ+x(rAbNGDE-AI3!N) z_xSnVqAZ7F^z*Gnc@hVDdnuo9Eh_nEm}PMsBz@eQXlVPmH;>!=ac>%y1!^e;gS3pt z<#BI1oj&f(`P=AmZyqk=|3dfX`Y$h#!0iA1>-WETe){aI_g_AJjBeog!9Srl`w#z; zA9vh2!1P|L2w zXb5LfmR>muYAq^zi?aO6QBeHe!J@LaC`+&$1+^CC8J1}HC#-&7-J_&F0%Iwbqmo*S z@*K-#IhLcK)}lPg5*<{O&$kxkS(X@8pnzJ7@-)l)#Gwyf&*I;Ey|NE(av0v)LK;W zca&vYj!J4R%F``-uk}NYeiYPNl;>L}%eNc_wHD5Tn(25^E-`|2J+y+v8p<*20AqCD;LK2&=8JhjY8 z^r5s1g|1A>=Ua>N+)1=uR6wmodGaLsXDXo9qC9&t_i5$xI<*$%>62*AI1hTC*?HJf z%~=#itSF$?qC9~TEus`qYf+v-i4LF&sI@3hq0E*-Ic8Dlz+}wSb11XrP>zDyJF0n$ zvLwn;P-9VOD(1}8c9I$eH5P^L`5siTsNIq%(E`hZ3Kq3n5+y?P9#pX?OQKvoi4yH$ zg?(yClxP9xB~>iSk|@zs%!4WxWl5CiEbBpqchrtCY=?_)^(4w{NtA>8)RHLCug*zo zNtC0Y)}lQ95wk{=)wdS4c#E?1$5Bbm9fdxr{__=!>J-@z*9j)+c~HfoEd3FEF+Hea zQI`IQ?#3Qeu_)VN3bPqJsA5sJ#T0t@dr-xqI=S_@P%bi&E&XwDOW7t<7@y%Jwe-hP zP-{`1{)k4Yf<<+5>*4b~{V`km`q5I=Pd5g02$H9f_t9u0X7G>#=qoCHJJpD0S`r|05@%mOzf5hkpMW@!H zJpD0S`s1ji)}lOr5tD|$N75rVd)SI0pISwwA zB{`z|v^&Zy$#E3anw=*(W=qx>1+`}9$r_k%qjm+c8rhN@N4J!+sFF$!ue$~UXR zlm(S@=W<%t!T2CYbHEy@!svL#jwN@|G} z82{t$C`+su1vMe|)e|c)eO&l_+qi1=#0pH~Qb4Umd13`dCM%%UqI~Zv%wbbNtwnia zMYhC>(S@=W<%t!TP@_m{Ey@!sFdkF^wHD=x6_^OFfLe?4#0rcw7C5?v z3uQZ4t)5tc>4=J?_KxzzifoA$qmo*S^27=ZC08W17UhW**%B*8CAAjii51xrD@H-B zMR{UHw#152P-{`1Sb-^0icYOXd16Jj#EMZ#twnia1!gb_l3HTL>WLNE5-SEJwY{t` z&(&RgmRKIW`Fv|pzMU0D<|?4pqCBypd~ZLilcL7m5-V0utiT9IMN(@~ zo>);Vv0`+gtVMZZMX|(+1L!dzNZWbM^d`Z`Sn~+=vK;_FC`-%OJS_vWn}sc9X&LBq<|Q>gmF3GC`-#g zqcaC;X&IxRZ!8Lp&OB(xL5Aqb=Z%eU%q|y`pc&ufKKoc zCgd&?Rbt7KJT_1AC`ykj4EsJ_qnO$0mtC<>OY*=xU=OO;rzLry;h6_j?9-Aw(D2NI zD)wnf9vJ=ZKrP8*aMxRs$L2{M*h}BDK~LP;dk3?_k?%ejrnN3_dR>)#Dq3`EG_<6N{`li({97o8!LV| zmKJ|3JzDPx`_yvJ9(Pz15W0%tQXuW5fyg#Bs<4>a=G5m1GVHmpIkdLU){26!e zWPjADf5SeaLeqEgBPw(>(??Xuol>?~XYATcwpaP~zk5`OCQ~N*yyKoY?nj@8ddxnS_}w4eU+=Rf+#7oVUIelbz*M}XFEOd)Ud2+$h4^m(JCnNzTDBldG*k&-Jpw^=N^*&uC{*Dmv1Je zeDjfa|MXWs`}LiM?@Kq6Qo8xbyZ=?6i?7>EO5Nro?|!`17GJmd$h!-XDqFX?_`1z| zE#5qr!CdN#uiG5UyMOui&DUQ)&qO=y$hysURx7r%S})ETh<4bKb(`<3R%~arK~URS zZS$SgitVg63ToX`-&w8L&T6Be);;x|)r#$`HVO*w=-{6E&T7SWRvQJy?;SyXg`@4P zHVSHXGUgY$m$~h%HVSIpQ{P#w*v@LBpw>P0oz;r%tTqa2AAG*ETCttgMnUa^&v#ZU zwzJwGsO_w_`Oa#^c2*k&wHD<&s}?EuPM{^h^zAFVe`@w|OJ;qu?786GydZ_8F} zTQ-P4a>VtmaRl`dP1}}j6cp+>f_ihbZP`XatvUL(Y{j-^8wIuI=-aXt+m>w<)S9Dj z%T{b#woy=Pj=n8hv2EE#L9IFZwrs_=Wg7&wZP_;8maW*fY@?v~y~CFBZP|)#%QgyX zFF4*{O;*j@4xxx&D)t*fSruD`37!9Y2bFBdw5ioyUnW7 z!0kTw@CfRh%c?YROMM?4Kz#$Zsx)v*eIFb_UBjsQy$#$>xJ>uCheuG?`Jvhv-k~ep zDX6tQUp!N73$`)P``p8$q%J>KZ40(hP-}a>*tXghY@?vo_Iw<#+Bn`QsJ+d60Zp|n z*hWF^ZRT6BRojAX6x7~kz6D#g#kQlM#-cDL(Y^tz4dso38jIR}3%1&ubbW}sjDnim zZ1*kLY7h3zgBpw4eG9hQi!7!=Z3{MxN%T5}&gVgmMeV)?TV0^@c~E0fyKli(dwIk> zsIjQsw_vNit=2rKu_%m5bUL*qG=p2pme62Kq6h8w_g@S0MnSDb`C{8@Td<9ST8r{6 z*s5*8HVSGj%6BKKwguZLsI@5HG_BgEX@j7)X&S~P`h`*~$~H~gebcnsXQxfCzU@x5 z`|d>5b|)JBd}~p@X8vv{6uN zQNC$fwN2ATL9IpkrfJnSO&bNZ7Ug-4)$$w%L2dEN?kD3_%X1tBwRe=Cj8`qsaTL_v zQJ&{mEzfZj)LN7;eyNt{I0|Yl%JUqnpqA&jd!A!ehTh%h9)5V7?VjgYEzfaOQfpD3 z=U6SzaTL^Al;=5C%X1tBwHD=hj@9xUM?tMcd7fjnJjYQ`Yf+x(SS` zPru{({Qk1}3D(G?LEB%6xDTTE>n~n?{`~EWPY@or8K%QVJV~%&uFLTf@(HE~QT(s5 z@KJr5SJ8tg?hZ?vT^iJ>%`QEN;$Ellc|OF#M|EoA4F8pg;*VaYpZJM-$r3WgmiSRq z^}$VW?FSxL<@B{?B8Z-dkt`8oY=5HB_0jcsT$TP@9! zUjBB1OPPB}{=@FreQ|oV#p!+j@hD#IA^9VyD>taNIDHhT9mJ+tG1qQ6x3RjucxcFo^BM>T9mJ+tG1qQ5Y*Pw z?Y^F_+IqTCP-{`Xp03(@x=~PTQNARu+LE|YP-{`y-%++C?f`m>;XW#u|1z2vN6CO^ zaBt!F;dI#iiTkKvK05fLI>qKZ>eQXM#h$pMpytHg{E7RhU=|k2p1A*&DwrSV*y9|# zPgoy49q@a{Bgc7;#d?mTppSFxpi}QTJ~}ac&xw2V$7rHpn;90mb*lD&nvPGbS2g-xWeLSRn5onsBa{uQ2yLWG1KYc%=d+zmV2bM3sheEPF z6b6^OcgQ$iO0LgOvON?=LG6?FaeZ35d{jaSF3IEiJeaBPp^$73g+Vj5v!WiAP>u=q zxIX92w0Foj?9>0H>+`C6^AWW*OXAuDCEJ2w@aX6bHjeA;+0(WK!zifXbu7LGL$WOx zMnNA@+rvUVqPEr*vn?0~x0G$cu=o}X$+ln^1;y_j7s^|dZNV@KYAwpMd6Q-Hj)Gc? z@}s7bW%G`L+C0c3YHRnYW%C|%I+g8wR1hP`#QExvvZzN{)GuCq;v3W^+o1Mfgs0Wh z=HdD%i?ZjM?N2+ZQXBU5{b|#qf_VPn*1HcM+z;QMHrf8PgA4UvchuB_7<8Zd_aFwj zn9t*hIe&EY0K(zucsw!f758{z&TlDOFuFXRn08Cqg3-atxCampX6g$@)6f$$<#$i( z?Tc@oe)QG*uV1}>|Mk=I-`0P5@$?VR|NivjH*cSxK6}%LxIBOH^!Lv%-#-1|pMLV$ zM>h}<|K`OHUwrfS)z`1yz52J_i|C*K_~PZecW+-IMcV)P#}~i&^p`*X(LcWUWWD8H z68AySJv%aawR6NezlA^PaxaNHg1VxZYUhZJf|`?W_jAOmog+31YSwA@bHu8hBQ^?Z zGP1j$BUbGku~AUthwpxlShaJ+20`r{vE9!Rt9FjqC@5^?u=;+EShaJ+MnO$*ZTEA; zs+}V?3TpiD-OmxLc8=I6sI@3RN37a8VxyqeqWm1OYUhZJg5viM3+3mCRXay)6x3Rj zpCeZ79I;VQYf*lVShaJ+MnSDb`8i_M&Jh~~wR6OFKS!+EIbx%r)}s6zv1;dtje=T> z@^i$hog+31YAwo72dj2E*eIyAsOs*hW~YOVf?A8J?v849I@l;Ee(zvWemYpQ)4@hT ztws4}RLwS{8U?i$mr`wZI@lVni=zRY3jYXkPs{^&u!A2!D7M1*Tu+~cl z<|V~Hey}LdY;Bg=Ix4BPC_f#nS!U}fsI@51Y;CqMWE9j|lrIcvwlHK6)E0&$Ul`JC zVaO<`wJ2X0(k!!e6x3RjpAOdSbg)rSYf*kWShLf?MnSDb`RQQIP6rzWwHD)LN8pD9~&}fl*LvQNE!- zvke7CLGgPBi}HEHW*Z8Of?A964F#H=4mJvEEy_;^Yj!%=D5$k4KOL;uyx}0IrKX~H zh_fh5O&tZb7UiddHA_t$1+^CCsj1CUQ%6CqMftp8v((g4P-{`1n%Znbfl*LvQM-@z z*+#RYp!mImMfpav&E^e9L9IpkykWC>!%RqRdSOq9O5M^M+8ttp&|(pUEg>Z9ihXQEinMDm=8 zrf?=oU)`gmt{|x?oQcv`_XwJuf2wdMN?+Y0sE?j2oQcv`_Xz5v=L%<{^wm9rdW%vx z6Q!^20n~FQn!=eVeRYqZ-l7!FMCq%01oalBa3)G$-6N>CD1|doEN3El&O}o<6Q!^2 zQBrSF3TLA9)jfiGi&8ifrLXQ0)LWFonJ9gAkD%6~Fx;olmHzA0p}~u`FX`*ApZ@997tfv}{L?q@fAiJz)8Bpd^7WU`PyM(4;nzR?z$pIg{a0T- z|KaHe>ry`2m)kbM9jZunu6-AM&`5UN41gNT9R)R(n;ka;pvH1X zL5<~R$ISq!vD`sW%gxA+n*mT`xuc-QaGUBxf!FN#&WacW&qUOg`=S6F3gUb0Z_%FY}c{uxETQL!u|C!7?spo zl;dUqRIw=Av@<(y20#^yvfPa9xETOdEXp?R%#ND@P{pG9>K-<~<7NOB9BYf+AyfxAhusJ^-fNgX!>po&HH)jfjR_ZmR^7tdN$U)>|9 zeXjvju_)VhEIV!nKoyI!+>GqF830u*s;}Lpo&HH)jfjR_ZmPIi?U5Sv*Ts} zRJo)2>K-Na7G=2^gBI0S_Xz5}OUum|1+^CCxEUC6s#uh58ImzT;*9 zRI#YOx<^nO0RgCDQI?yL9XA7@ibdJBVcBsr0IFD2U)|&9dyBH%jKM8shdpG+&48qe zMfKG^O6o1jax+FHwHD>L8OzObGe$wJMLBK;KoyJXt9$r-$ISq!Vo`l{kD&gJvfPZ( z&$kxkxEYXCu_(*U$c~!sNX1N)opw^-sHv^y@XV&ZMt9$r-$ISq!a!2*m zJ%ai>%5pOXKi_gQvg2kzQpKYB>K-NaUZ3S=j7s|du=jSonjKk{?qAtTZa^x-ULWuJ z@Ez6Ybfbo<5=H`vgO0N7O;rjz(@LkI=o0_E$C{?SV?2<~`3@cFpu^^hM4RDwBi2|E zE8>YUeU1W~p_V3&x<+?wDZitf&FHq&9R)UHdUQ6UE9#B{n<3HUJL($U;pcY{;{a==F>5 zoui!1*pO!-(Zo^CW^Bl_kZ7{%b2dZaCPq9+G;x%(845R{XtL^aHe*Acg<6_8%Grz! zc@`2)R(;N9Y{;{i9-Yl-I?CCM4S5z4O&sNH#s)S+qKTuN&DfAoOefdqj-pugX#+J8^;I9)4DBH$qQ2@Qo1xF> z`$a3QWc>MZ?BF zSxow$MARIma1&olObIhlX(i8nx|5lh5@w>(N=8xa^{M({^7GA6JDCYpKMX{jnb^rp zObIhlX(i*&$Et5in2Aa&8AY*sJ|)aVrIn1LbX3AjR9eX>ioL!mVJ0fAWE90--;^*D zl~yu{l9`wiW}?zcMp4dD2{Tb?C8H=El`s>hGZQ8OO6sI-znl+47GFcXzlGK$hs z2{Tb?C8H=El`s>PRx*lWuWw42iApOOMY-xrn2Aa&8Aa)+gqf(cl2Me7N|=dCD;Y)U zsDzoQw31Pjj!Kw`N-G&f>8OO6IK5KaPG(|Cn2Aa&8CptaVoI2aN-G&f>8OO6sI-z% zl#WW6iApOOMd_%7nW(gqQIw8Kn2Aa&8Aa)+gqf(cl2Me7N|=dCD;Y)UsDzoQw31Pj zj!Kw`({u25G80q6OjKIQ&{8rJQ^HJCTFEF%MN=GHkM5UFC zqI6WkOjKIQC`v~q%tWP?jG}Z@!c0_J$tX%kCCo&nm5icvRKiT0*XRzSWG1GBnW(gq zQIxB`gqf(cl2Me7N|=dCD;Y)UsDzoQw31Pjj!Kw`)0v4Kc^2C3NcQ@!(H&b#MN=GHkM5UFCqI6WkOjKIQAWCLpN|=dCD;Y)UsDzoQw31Pjj!Kw` zN-G&f>8OO6sI-z%l#WW6iPM>h9eEbo>PsATjqcb|Ix1l%Dy?J`rK1vNqS8u6Q93GN zCMvCD6s4mQW}?zc22nB-Q^HJCTFEF%MN=GHkM5UFCqI6Wk zOq|Y4DBJ|c9G+*Pw5 z2F%2H5ix^J$xO@%GjU!-%qR*+%>gqZAjWEdDBOfU|9(eF)R>8#%)}fp6B6}RADM|c zU?wDL%*4(-i#cE>Bx=mWPG({bm{cNB9b=75=ys5^=| z6LY{!NYougW?~MQ389egC^8dsz)VQg9mSl9IbbFv>W*U0#2hda5_LzR28bw}#8I9z zai9jsGzZLtTI!Bs&cqxr6B2btk(rnSWPLJbi8{A7;uoQVT9KqQ*XQJyn#FlS;8m{)BusF`uxsYM-p{Mk(rnSWTnV17+LS(%=ia8T=z)VQg=P1+w(a%pDW(5aF$c_qMBP!S0ir%l=BR6Qhc7doho+}nTa`I zCM4>PV$Q@IFcT7WN1+CY`c!>>_jGcN?(phk&cqxr6Kbi?QOuc`17<>^K1Y$6m;+`) zqV6cv0GZ~1nUJVEia8T=z)VQg9fcYoYH8vq&zU%wGcgCugf0}iqsUCm0W%>{cNB9b z=75=ys5=TZK-8y+qpr~%9L1c8IbbH#Qg;+{Cgy;dkf=L~%)}fp6B2btF=t{9m2h4;--BHY$m;+`)7hiqV$DD~dU?wE$jv_NL2h4;--BHY$m;+`)qV6c>Ow0i@ zAyIb}b0+41nUJVEip<0uFcT7WN0FJB17<>^?kMI=%mFhYQFj!Xi8;ubkf=L~%)}hz zOz76PJBrN29OO($)Ez};Vh(a9B{cNCe4 zCCHhOs5^?x#1iC8NYougW?~6)CM4>PA~UfB%!EYUQOucG5@tf@#Y_N|T@q$O8&fU{3Ta8034KPpC@7>QVJ7q?F^Vd5 z#1FWagqhG{%0++?2<4OlQR7u@|mb!I}LBNSDi-!E$4Q3@TQsQUbVQJ<;;XaM<|*&%9)9i z%*2u~6O%I&3LRlf6Gu5Sq0kYECXRAuLZKrRO&sOSghEFsnmEdt35AYOG;x$O6AB%H zXu?cP&P*tDgrbR~oS9JQ2t^Y|IWwWq5sD^`a%SQrGqEJh#N^C`LPyxr#8J*nD0GCP ziKCpEQ0NFn6Gu5Sq0kYECXRAuLZKrRO&sOSghEFknlKZSGZP9Op=jbLXC@RnLea!g z&P*tDgrbR~oS9JQ2t|`spEDB*9ieFAC}$=VIzrLJQO-;#bcCXbqnw#g=m#X0 z&=HCzj&f!~p(8H3Cd|a-%*07%VojKd$(f0h%*2{76O%I&Cz**gVJ0SLCQdRFYr;%S z&P<$SCf0!c5H0Oel1OEe#x1DI#N^ z(oqRBQ7Iy$DCVd&VJ2p0CIrx6l3EjJqGCjzn<`bzQfop@RE~(LVwzeLY@&ihOcnFg zns5`9Bx0(VsMZ9Ws3;LrrLPilVs>&uqlKwzP0)$i(Fv*2SwW2sopaksuT*KR1fHlk z5$jiaE1@SUPh?ajKCveF#O#q13U;8k5`JR#%n7N|TM0lhJ3t{-dMhC)DpSPzmEKAa ziV77mReCF7C@NLNROzh*qNrFAQ>C{OilTBwOqJeBFp3HmF;#ji;V3FuWK<9Dl@Jw`F*2$WsaTU3iV7JqReCF7Dk^2fROziGh@xUf zOqJeBsEW!NF;#jiiK3{W5mTkNk}Qf!8ZlLRD+!~hs1Z}8w~{o9${I0MdMiOIDs045 z>8*sVsI-w$m2kzH1X5Joh^f+BNg_q%jhHIEmEaW>IAW^wR+33ki6f>;ZzZ7=6**$6 z^j4BeQJEvAN^d2x6csvRs`OTpOHrvKrb=%mkVVCgm@2)MBvVxG$f!!pVojncDtN?H z>8&K2qLN2UmEKCiDJpuzROziGouaZwOqJeB;wdV8#8m06B%h+vM@*I8N&+e>e#BJi ztt6qM@<&XS-b!$b3Lr66dMnAOs05NxmB7WCgj7@niK)_CNlHa!keDjHl^_=tLSm}) zR+3XuDI}&!ZzVw$6+>dG^j4BoQ8^^0N^d1m6%|Bcs`OTpRZ&SKrb=%m;6+7|m@2)M zq*YWF$*4;7Vol;IDvZQb>8&KMqS8oAmEKC=i;5#LReCE)tf)K^Q>C|($chRiF;#ji z$*ibE5>utOlF*8ZBr#QbD@m=WOcGP2w-N-SLP<=O-b!*SDwSkZC4{ji!4(xtVyg63 zl3Y=_B&JGlCD9cXOk%3^R+3#&$t0#qZzbUs6-{EQ^j4ByQQ0J>N^d3c6%|fms`OTp zUs35KrV4M}5*VZ6NlX>qx+OG5<&%u6#4&COj!^+6rV4M}5+0)xN=y~rx+OqHMU6jLIl6Re0-`AQ=@>Vyf`gEy=N{loC^gw{8iPQ86W^3UA$#B#X)^F;#ji!7?hS z#8m06gv+R;l0j7m-Oi=l5-y{nN=%jBO1O;5Dlt`hE8#LKti)95t%S>{v=URLw-PR+ z;z~@F-b%QP$}2HddMn{FDzL;<>8*szsKgRerMD6;qasU8mEKCYjLIw-Rmo-C5-y`c zOH7sCO1O+lEiqMkE8#L0a2bj@!P_O_G8V4}qVN=YE8#L0F9#x3dMn{FD!Ih^mEKCY zjK#w()K+>c;W8?_#M(-4C0xehB|+3ydMn{FD!pWEE4hqY!euNTaG|IldMn{F7Eid4 zD!r9(85Lk+JwR_IT*l%V7iufLm2er07Y30ky_Ikom0@B%KyM{n#^Ny-YAd~!a2bo| zTu7DPO1O;0i-Sm&-b%QP#gi`d(&m~l;W8F44xQxXMgs83b zR>Ea0o^~NsdMn{FD$K-sfZj^DjK%XV)K+>c;W8@D#M(-4C0xehi5F@sy_Iko6=-5@ zrMD6;WAV%jEnVoXgv(ew^g^oiR>Ea0UMWPXoVOA#WAWGvsnS~sm$7*6g;eRSgv+Q{ zlkpi~^2IITG8Rw1P+RG(gv(ew`a-JoR>EaevWfKoy_Ikoi-%vRt@KvHWh|b4p#?m> zm2er0$6rX5-b%QP#q%$uN^d1x#^M1OQl+;NE@SZo45`vv374^W1cp>OZzWvD;u#oH zrMD6;WAP9SsnS~sm$7&XhE(aTgv(ew21Ba!R>Ea0o`a#lPI@chG8PZQkSe{Ea2bmy zVMvwUO1O;0qcEgOZzWvD;#n9{rMD6;WAQKysnS~sm$7&nhE(aTgv(ew4nwN+R>Eae z+Q~R?F%aXHa2bmSVyLb3R>Ea0o`|8%9C|C^G8T`-kSe|PQ7+@}|Mh3TfA#kDH&3rV zfAz(?FaPoB!^3Z%UVruQhr(*{j1j>KD>YP>+e5Y|NQ-{U;Of~{_;=%;??K6R_k}QaaCL8-Yop!`p3Jk z)CM`?r!;jD|9PNsG$>8WKIm%d*6^U|9VbnTKIm%d8vdZ^uOw+&@2m3RvHNH6&zV6#uJ!F?VlRXDKI54AKg(>1!IDBa{ofZdjwn^fU|Elupio7wb} z9{_e+YJO6M1GLo7|GJ`PC{;M1=%w=?Icl6LH*H4#Po*O~{QUj9xBu(u;n&}P_uDsb zf76~Hr^N%OG-dlNp$`Omw6E9ZCuc~h+AJYef3~G+^F&kCBd4V554Tk9;qI!cqlbrE z31l`BQnk6FtLjhp#MG&qLyuimn=RA>{(P&gHeU>?<5Tl*3oI>{KD>MT6YDIkJ=;%` z3bFg!94F7JSDU=ekqCf50Es4Va|8k)4?v>!$anpWN8X=!iP{t26y>qAKkyQ@2fizc z2i~7|iQ4nt6~*(;x4EA=cSZTQn={o?d)m9A{x+ZZHun?fuBgAwap0`F%9qZ6^fv#A z?+hL|N%u(a? z`Q3-tzj=E2Ur+DfJ^c3d`>!6p`|$4D_B^SRLcD*N@_6$r23OxTR$QL)sFi`QC$%MO z{nb^)oX#r-H@{-gRh1ovCwpSho zKCx@G>^0O?)eu|1`phm>dk=M0{XH}>?eXSU47#eA+8OtF^D72jRd|bekDFgH=&E9J z$1b7{CO+n^@wM@*@4x=~>0chc`}XyhPw($|UwAO2ST=0cZoc1m&9sg8g(pKw)ps2A zn`|A>RfPwc4Y~QAV^Zi9>=mgd#} zcP@2t+XMqF&E(_BE2h3|E5H5f&6n5th_X~)ww3REKwq|%ZE5kct^BiBZw5cTY%ANb z>&v#XKJ%~`|1Yzx{PA=9d$yBTUuEc`v+w@w$ueX0lyTj2rf9IvsB6p5pIy4n*YhOc+J|Q|@t34zP<%7)7y3yC)~uwT2u;{YXMB4YrhO5jl!tlXg$euxk}LiuxAG z*@dEW`;eI;u9s=ddY*PU?NNutU5j+gh~h|9dc65vr>>~IIwq9&mFT5&?^immI^m|1M1xlcZ#v+$Rjp?{r+&$)`AFfC6Ye;vrHP|(#|c-QBpOV{ zyyArNzK=J*;ne;4?kHSvl4#;6TyVnuCW$7F!u=*(Z<6T895v3Hzj^=en{S>zv`qlP{ls@^vRwdx=QZf3sBWH+NO-Eh1HajY!pABVAQ{jY!qs zBT}`wyQ`{kw0`v$i7pggSiz4EeOJ|9Bx(zK<@;1h zgQB;bc<;7Ve>Xk@*r`%m6K^4EO=S_;uZg$7ysIoCRTFO^YE5MkshW7}8e;2Lddso* z=4c^mO=S_;*2G)a5L;X6EeGGbZH2c$zU#_*GH+e?8pgH)eV1zDEu!yW-=&(&TmO!I z=e*_cd$(UPZ-IVSTN7`Qeh2<8)x=xG-@(62HSretcL4BGy}I(=^#B2Q5b#n>yhQ>Y z2)rT|k~JX_crfr%O}qsLUS$#Sc5w*4`Ml!TL1huCnt1CP;_*Fzg9r6MGH)SjO=S_; z*2G(gT2om>swUpLhS++5^Om1IG)D_jYbuM#wkF=f;e*N|QZ?}wqSjOv5vqRt(Cq=t zTR4AEd`aRhoIj{6BHNnGTZmdySwyNP-ogol$|6!V@fMCCR2Gq{iMMbDp|XfnO}vFe z2$e;oYBF!(6hdVYshW5T#}F!uNY%t!*D2HZcELe};&zgG3sGw-i-@-RNkr4JIEheM zM5-pwl(nTz^u~FMQEQt=t#x|<-eT0+=22^1RSogjRz|ID9<|n0)$7w#=`D|1>#FMSOqJg9 zG?=cchS*f;El-1Ksv-?WWfAdYc^XVt72jLL_BT(1>8k4WX+1!1c^XVtRj*G|rMEl{ zrmG5X@qYT|_tU$o@D}f!w}wcoqDvRiI!S45lx~lFil|`g# z;w^9)DvL-}b^N_&Mz}eoexQJ)>z-6c`BHMZi-Fd!M@uoIfSQGAkRk_<%_ZDvt zDK#?jmfs#yztUR?mr)6)V-Jwa*b^=T_lHzTh~7%LjGJE|k}AEGa2Ypn87hm2C(E-4 zo6i8a43$NsYT_+$87hlN)nK2nvL@{rptlk(qrxUlmEQ6^!fwC9TL>gnc531+l)zJ2 zMD%OIWmMke*aPG;_Jqr*z)4f3w-PSn1};No5!nOk_`Bb)2qjcmM5-q97Pt(RMWkxt zEpQnsi%8YPTi`O3Qc2Zh-U64QvWQgGg5mDb0+*q(h)_+qj2pNNl|`g#um@kslcNjB zW$X!;QPGp8N^kjn(B?Y}T!zXbvIi1xfy+=?M5-p<0+*q(h*V9y1ujEn5viJZ3tWcE zB2qQ+7Pt(RMWkxtEpQpSBMjAq%cx7g_Po+t371i~en(Yu8M|K$ZMpzlhOP;-2ZFtf zy7y~srMLWQXt%BS-XfQ=``yr{D!2@lMPv^o-U64QvWQeoyag^pWf7^Gcne&HE(=pN z@fNrYl|_VV!e!L;Uwg9Xt%S>{`@f?qxs2Vfhz?KIcnj(!RQLa+^C_m)Hh-?w|EDiz zE!Vl!FbprDx-X%+6Avw3LUn&A3#POQ%}b+Oc)0Nrs@n|Jtt|8(qK&`nUrwzewnP7` z>MbWYTRL5H=%?R-74TrHTsrv;|E?;QPQ>nZzvACi1$M_f{wf$_OQ)`?AF-?KEO{yJL4~8l8r%hF0cf9SdwkF;JcE{`f zQcb)C>`qm0`3xl90(PgWw^Y5l@?LKNyHnL$s5*An9W8i^*xl~fT~`&}B6hbscGp#f zw^-qHckHgKsv#a-z#?qBV|QIu{hg_DJI%4XrYf*IRlVgi@G)xTU3m%?@T z6|Q?p7&gl(V%IEp9X@<=v8);Zwp1iA^pY@ar>@;TwW*A-&`ZLwEfKqYYSS1&A@!*p z3N=L?6e1@i(Zo@n-$G1CqP9Nlw$#48NC`>QmWN$Y`}BHA7{>e5388ME+R~7K(Btla zP*>DehU9}J`Y}h1i>;qOy?%dJRp1+n7bt<)dT84H7DSPipPX_u$=kE6bXtDv_%(>O ztUb+=<;RZSgJ{cQCxI6scE1QQ%8tGNAJ?6l{$%}Zeth`d!{Z;{QDpb#UyJ-$R5W1n zHt>%{ek)4!`ZW0QTe11%`nMuK6(4v1RP2h{{JP*vQKFa5-7U2*#RVUV61C%)ZcF`b zfbT?!+8#_-)ZYg9OqA%y-UdGr!+rBw-3v-}OEj5Z{VS0li4slbSAQ$89CeNE^QSjoND@sP<%L64x!vB$k9-~Vz5={%s0z1JG;!25y2H=Mtt_=Pag-l$ zs=f|enmFnj-La*9V4#*Jj=Dy76!m=bi6{w$!J2wKQ?mHM*my zPx2D|n4`v7b6P+Ap8(WvzkmPm-?fB!_(M&YfA*`NJsjVB^YF#DU%z?#^tWF;{QTYf zr$2i5!@v1&zxr%?oR&Yj;}FW9eXSe(;a3e^fB0K(=^r+8o`1jM^0}*z$Gs(ts%y2}(Q z?vu{p7Zux`;4V|DIAxQ$tWv^<2W;h4#lx>Ewp;5iTX|RUz!qe4$gY95)?zL@unF0f z)!&&cU50JQuB^Lk<#oja8BH|Uc83f>(kp|c55KV3mUWk{ys>!rjm5Ss zT*fPl2R0XuzuxQurh56_tH zb^x}JAfXkROefWLGwk%x63yp_gXl%>E zWxUaNpw?x#Z{adVO&@-xvE5p@jCUFjzth;2#ihoTml_XLyli#?ZZ)pF)p(%hWmgt+ z8Lu@SsCwCzh0A!a@j%_nt}I-}i;ah0Y-|r1T*k!d!*4dWW#KYjZ9M#HV_Oz3qF z^)I`93zso;`taK??bgC&y#8|d^_Q+J?!T;zoj&~jOIuc*HLe(W0p{>3mu*?NjKR}~ z-+*b$!ezVyb9kl8wk%x6J1~defoaRaWz3#F{1QxC7B1s0n8Rm+>~t0mP{*3zq?MnhrotU0Jvcn3H7H`S)*FT?0M7Zvi?0%Odupg2zpkE{oWYN**^^?&L@8M@5gDEZC1DVm~T-++@LioDus` z;o~L?_T!A$j}7S!E7=c~)J|UG*FcZ0CHrwk>__E~n=D**M(jrgkee)Ac1G++C6Jpe zTy{q6M@5jEEL?U*>_=sgn=D**M(jt0kee)Ac1G++rI4E}T^6w)6+>>abXl#x?`1#g zR^cG4;BtpF&WQb}Aaauh`*C{p@aDHeC6SvfT^6w)6-92cbXmlHR2I3((q$3*QDNjJ zOP59LN2QUQEL|3{9~DP#vUFL*epDX0$?i!jb zT^6w)b=%Nn>9UCZs8Di~rOP7rqf*IDmM)9fj~(pCjqJx6u^*L7Zmp%uBKD*19hxj% z7O@|7^U!4JvWWfIkz1`Sb4)rB`>~^-_>Jtx8L=NbDvIC8ew-2eu_L-#apvrVWcOo7 zcD3@%DVywmR6hCmB#`|$BlcrQdi9O$#~HC7l~8W2rOP7rV@H0qGR@hy+IqTsXK6=( zwL;Ay8?hfd60C1zKhB8#*il;iM)u>3*pD5x#cyOk&WQck5n_EK`*B9>$Bq>18`+OD zVn24UA2+feXT*N&$gx(oIUg{66yN{cg8fjqIc2rM8_4<|qteYO8@UWo);F>rXT*N& z*FcZ28nPc}#D453GJYfbaYpRNjx_5V*^e_~KX#NEzmfeoBlcrQo$(vlk27LFcCa5e zvL9!}e(YdBlyZ*eHex?2wS0WQ$bOs=`>`X_`bPHSjM$GIq1FmIM<+z=M+KK#Cve3W zu^&6ijo-+AoDuu6qu%(9?8h0gA3F+;-^hNP5&N;D;`oj1#~HC7JJ^pK*^e_~KX%j{ zSKc`vuxKtr(QyTyQ#P8*P<339xRj0NGL#)xCN5+n_MLT*P{vL9!} ze(b0`ek1#FM(jt$+*)h-T^6w)J8F;L$bOs=`%yu+)>`gmr3?QweCKZ z2K#XX`yttc{iuMKv9(}7B%5%I74TxR?lQ?nJNef@o2_-K>m@Hiuu^$!iVzP8u#C}x3i^9UCZsDKxfrOP7rqXJ$`mM)9fj|zA( zS-LD@KPuqGWa+Yq{iuMKQ5NjS{1~wx74TxRbXmlHRKSbL(q&QZM+Ll?EL|4mepJAV z$_-K>m@Hiuu^$!iVzP8ul>1QuFD6TuMeIifyqGLq7O@`{@G{DR z{g@vk_M-w`OqMQ-*pCW$F9UCZsDKxfrOQ6fevC25FLknB>STEj*yh8vZ}M-+zT;E# zAD5i?gX!_JWv-GF`yDkW)@!r!`B9z`U8_P-zJ>MNq@Sodu=){`UX}@R5w(- zrT&_Hsgq^TPV1tq%7oed+Zl1Ssz3BnCu`UdZ9b>ws0A^#>eIkcw`*JS*`_abvTVch zrB0R~w)CFUYa?=aq_91u>QjEy(iFAbssBuMvi@z_{Pp)AKD>MT@bM~>syx%KGV!>0 zCr<1{UG7l7Js*R$I&r}kACi3^b+scAwb#;wTwjR>uchVM$9;Z=CZzgGG??fYg!&@W zSE7DS)$3DS>%y%riTWv3Q&gin{(S!ylBl0iHAQ{%9BIB14JP{K8r`v_{vGtF%N)TY zh3j0n%_Y&`wY1FK&jbEKtjiz6}`(1l#oGPw%7|IPdS!TV-#vZ!5>(g~?Dy`O3xn<}VS-Pq|Ic~Ve zqPCisyQ)4rZn(xGRWox_6}MP6++vZcxw)&VC(HVk+l79KrK{?8-f)LSZ8bl4Regrs zaD_#xX6UY}PmvpLu*{EsgQcsgA+~D>8je=ecEt;MQu&Ih3hLDuCGYdrpazw z;Vs-=k!s>CTwd95c}1#;w{Ul5!`&6BCf>r;l?_){q-s-TvtMy@Wy8%CsV3gS#gz>g zSEQPF3-?ww+*_Hodl$?F*AS21!nGBt+H~3NS9lAzR-~GE3zt?lTw0N8;;n0l#~wgl zsZyoI#V4QZuPO}vE*D;qAXNHy^m?yGFLuOijNTZk&%5LGJG#9LmA zdD@UvIzRetm8J`>A+{%r^Oj#$>8iq8xT~VJCf-6!>4un6sV3gKhIs4&q?AfE@s<~4 zo;HM(N;UBoGDkzT|;cD^p@XE>8fgoO_kpAt0`So4Y8@hTa({R z>8iq8C`dc2jC8Ql#Jv=y)!G4+R13ixUAGyUFZ zRq*Wi44@XR`Ze%Y<<6Qayfyiilx|z$EmWdaTZ4J4QfIBL@YduPQo3!0w{WmO>!9j> z7gXk~wH0f^$*-ey+v;mVWz^z%_1h?2RV_`1wko2Qs)4sEaMo1mEkE4vw$=9u6;R8z z2J_Z=4Y9S=ff+pmiMOsHHdT7dFQPPi;2L66#k@87J(RAh&sz$oWxodBTjw>z)>h72 zeha1BR-d;NO^derC6ulzyoK}WdGhn=t}48R18S)z-nxc(>{pynOEs9cPMlCHmX`gR zcne3=VtS~WcnfFL3Z6k9965WiMMc6Ew+bkO}vG(YK75KHSrb>tCdAd)x=vk ztyUB*RTFRFxLQfHR87`|IImU^Emf0w3kTN9p@piSST~dm!-^az>RvOVz|%h#6G?Emae5A!Stg zvs6vIbq%pS1N4?(G-*Bq$QV`nEZXY#OuDL=w-7NpPkzm$tBN%txr`~{GEM}HDteYZ zkjz`i7v0HaObM59B3^VSmoX(=M#adEPZqfhrJe=f+z1y{>@52=@zyoO)>e8e;W8>i z)>P@Ogv+Q1SyQFA5-y_>WKEUxR>Eaefb6JBE@Mi#j1ydj0%!3IBwR+t$68ytCQP`D zN{=;F&RYqWae~WG+AMn@@fNrYh0Rhm@fNrYWzAAGnYX}YC~B6f$(j&chLUEXns6DF z8*9%1y_Iko6&pLMlFOJ9F5?83p_p0rKr(NE%h<_fObM59g3H*+WlRZ|ae~X($z@Cl zmr;qaHd^#n!evxotf|sl371iMv8GCIC0xb{E<^dUc(M{Mqtarnt@KvHWt`U#kE-M{ zri9C=tXNZ}w-PR+qGC;z^H#!ToZvDPEz8kLzPG?-C|Q=O$-D(FL&36CP3A3d8OoKV zYBFzu%TTN=Rg-xOT!vC*p_*_R=Y`(blSOYOT*e75Lz%K{YqFOCE<=&BR88hBa2ZOJ zrE0R50WL#{zNM-U64Q z=vb;I-U64Q*_av5{LWk?m? zB9}1-T!vKPEpi!iz-34k-XfPVdvrkSY(ulX&s$22vD7P*Ys zGX%OWfVaqH%pM}pR0WrzoLD{siMPOIC?=MwiMPOIC?%GviMPOIC?uAuiMPOIC?giC z0hggK6nKkV#_Ul7-Dd#aB9}3HmOxh(-XfPV2V91F0Nx^(F$Y|RRN*ah8MB9gHhTbE zhSFjA3?$wHm!WW2swUn7m!WJ}swUn7m!W7_swUn7m!V`>s0LhyzSH3?av5{LWk?m? zB9}1-T!vKPEpi!ike4A&@g}2CM%mJ67{SSF?TxXHXm;)|Ds=k+@NLW5u ziMPOIC_{y+iMLSlRT(N&O}vGQuLtuo=77skzrtH9zqbM|L#pr=xr{mBGNcM`k;|9^ zE<>vD7V|RZfXk37yv4kXIp8w13kYwK%b0__45`9fu3+g}2CM%mJ4nRd|be8FRp8NEO~&@g}2CMC<{M0 z-vXC$kjqdQexeF*k;|BaybSdKyhSc!4)QW|E(&jv%b0__45`9fJzF5@7VF$Y|R+6r$S*vnV~E<>vD7V|QefXk37yhScUsrX61V%{Q`p;-Jx72aZA z#u9KD>H&C*c^ON>WmF`}xR=4aj3wbRDiXz1v6rzVTt-Erm@4)%mW0cgt|2y6>}4zo zmoa%AjOieku_RnZMWR?+u_jbJ{{7EuMWPI<%24s$oF(BhDiXz1!DTF7yjAb`Pp9?% z5Q$={;4+pVFGH&CEoG>%2lP^VPTg;|6r?*VWbC%KFz$jkU4 z62(S~^Hz|T@k1nvsnS~smob6MP=*RdE8#LGa2Y4Lj3wbRCU6-ixr`;@GA3{t%1~hs z=%sf5^NM+kT*i`c85M~#J_F=37O(EmbOE@GlU&B)T9x3Z9k#er+&{vyNDFEZSbzBO&!`qq-f$OzvZDlM2PxkLbs*139c?dB&C-FDiG4fjIDuwF8EzSruA>A9UclJfW3&5s|t4Yl{0PNXOryw~c0X>2L2 z0w!Ahadmd1g?O5t{G zO5gpQ`bt6R{Ag*iQdn^8z?H(yPaTGV8mG#itCr@Qx4-Gv(!7BzQjKc+G1Km3QN1fZ z`FS$kfEF!4izMr#+1fLZti2tzjpXAgSs%}?tZ&FIfQzQx;i9n<#@>JVzJK|?*Y<`# zliJ?!XHqYmPa5cl#n|(UOG`JirC{6Z(Y|wnt<~5l%CC`R)~@B)v#1ttY-zCkt@YR_ zidkD>`^nGuuMtE!s82ukHS!aS>ROSFEyW60QTstleb&|jj(r-;+O;MdTk3Cm{rq6o zt~J>xidlPiTws{CeyUF$7kK%;$LKpM(Ct%O2MZ9QXyPbOa1b9v(T_Rmu4(h-`@S`2 zynNsP@{2$J>p#ENAjp4u`M$q*sZbE<^Lzc}`~GLI-n{+l&6iK#z50CB2kyt-YdU0O7M77j+YFbN?;!ekw;+y#9Ok%gC zzDi+ zW;&Gb0*$DjAAA!pNQnZBDAB}GfDyqWN;LQ;F5Gk+D0~y&97Svn6e6NPBC4gqF4Ka9 zD1eBMHwO{BEp*0{$Twjnyg)s!3fk}qRH1FA{asXOEg)#B7qSB zjEZ{;PDtx6$2j`@8g$OTJNo`Li15B+olxXrbi10;Z zFG@7|8btOYq8BBaI115=NM4j^;wU69B6v}viK7s_h}=bqCXPbxB4QU6b(lB`v5QDu zlxXrbh}1=dE=n|U6haq~xhT<(IcogG{MFar_wg%TSMpcGiFbqYwC$H%kIETAXWP*T~+S&#HQ+7uu`>GL|4_fU{Aaw=EdI;T~*&PQW<62g_Nqj zB)Y2b7Tyw4O}vG-#EI90R1*CR@-5!9q7|ptPG;328(X1+?%+X4`g=kil zQKo9*Ekv`bj51ZPAAPU45Y4JG%2Z9fg=kilQHH8Vvvx-d-eNTC;?b;w>Nu@^^X~h% zA4C>E{QB#6U;g96H*em*fA_w9#5hlga#h)7{x;gD&{#xxeB{ZR58yn%5_PiT&s%m zID0b6bxERJtBSIza-K_~T&s%msLCkUC5dvK5ap_}%W!NGkt}7Oq>U>@rnto@>6d5ap_}%TV>( z7F|`$bBuCbk|@^+QLZPWT$d!ubwZTu$tc$)iE^D#V)tZ}>ykvdDzVVL#VFS$iE^C~ z<$5y8bxERJCq%ib>@uIM#9N4RRoP{#Cf-7n>&YnBC5dv?r#?mt-dd9=*9lRsC$3G; zt6!ULIu=o`CoWD)HCYp0X}#lYhy!n_+V@$vt(dnM<+>(Ot`nkMPe!?lG`)XCr0SyR z0nA&gU!d;wfa)qj72aC?3UyZ%YeJUTUHuYuR~2hQT*=Zi5X@VuB7`2GxBO04x2>4B zfLg1Xn(cjbRc-G>j|9HAR=-Q#RW)x(6>GxPuVr;r&0A9Sb3FBc?JIUwZQhb9)`Y8H z%xbFo#Vo1PTYjIqt7_hoD!t`bv%0G0EvaJOTK#TTSJk{FRjdhDzf#>*HE&6k-ts%u zT~+gzRPnvF`lafwD!c_=T9pced24oFTCZDr%Yo@`Tj4F-&{A6yZ#glow$fXUOgG!= z$h1`HEoY{?s_+)0TvvytyQ=UOsA=_UuqLc3%Fk;T^#Hx)*mSq8@D{jf)xf-je%u4? zs=`|Ur=^SIy@~^ zddunQt}46*d|Evad~a11<47659sHCYonKz)^6_HV=03F>ZJ;VmH4 zsxO;(%cERXaF*V3hPvBUcnfHk+8TUsX~%9{YpbnX6FS?~Z7bGm^yam8ZZB4x8fS1}zZ#m)BZ7aORDA&~yudXWA zgyc9@=Qz5m@D@3a)j5u?D!fIGV|9+Bs|s(C<5->JXsSBLp-*sn%Q=p&D!c{IOO>`0 zZ#n3tw$fY9adg`XZvpjETN7_N>ZP{QTh4KG+X`=y<5->J=&Hh7yhV;Ru$!OO-PPoO-k%m z6=hT9_f}G3x2h0$bl`Tu_P@IRh@_we&~ z@1Gw2?A`aj{`%?R|N8p%+uuArTz~aH{`$`z{`Bkbzj^ca`)?k8_5IghKmE(YA8KRi zvsGaef7GURRKwJsiVd5`%Fwh8u4{e&NhnpK_QKt;cPvr+PUwo-`*y?Du|(|?yen$2 z+YLL%5|tI7_e+|hzH_``<5;5V^ZP|@A+urMSfaL$>9*ANwl-`VOH_S+e@pcre>TL1 zU1N#bDyG{~+u7Q%X{E zyMMkr3LC}}O&sML#vAsFC7L+O_lq}d7fUp8lvn=Ruv;wA#8KDi4i7&zizS*k>Kffq z)YmQ&O&oQN?kMU@7fmCHqrB?ZhMi)GCXVu*;td_~#8F=IYr{6N zL=#8(Ht~jCVu>b>@?GK$o5T`L9OV%k8}^7LnmFnj-EpA&Q(K~mqda0`!w#`T6G!<>#cag^^5Z`dA|XyPcp_`6|uSfYuee0O-m=CDK)M|qvE4ST~9 zO&sNW!yC4SC7L+OFaB=W8J1|`DBl_0urVyr#8H0ncf-E0L=#8(zVL=^Vbw-X9OV_h zHtY&ZG;x&Q?%S{_EYZYKez|YMp0Gp{NBPCy4O_wzO&sMHe>dz1OEhtm?+9<$5SD1- zD8Kl-VLw=+iKBc!c*AzEL=#8(#orCP!4gdz<-5TfHiK1)A#s#n{N1n@EYZYKe(`t1 zRz#F!KC7L+Ow}Ch80!uV; zl;7stun8>D#8G~kZ^K&yY0XnrHY2ZOWH5rZMb_k>F6vGbw}aqokSBy`PI7(H}52xIO-bR z;e~>WcM?q;YEZ~;=D$85G6CAS_R3^*ZXo5^;>pwX)s5fUIuL^GchI1 z#Och0DjwR+616m$qnw#g#Y2iFbCfd^s(47zWR7xXVka{(CCtR>%!Dc)vZaZmoS9I? zLx?8K#Och$PG(|Cn2FPwiJi>ElrR&gGZQ|`dUgqb*< znb^rpObIh_Iy148nNZ>5;MM2M#ExrqT1zCWK4&I&G80q6Oq|Y4>|`dUgqb*%*0M+VoI2a)0v5#%*2#1 z6Q?s1JDG_oVJ4J)Ykf*)VoI0^Mc=w8SA7XHaXK@xlbM(jW!Ng2 z!c3gbOzdPPri7VL>aDkwj!Kvbh2FX-zoQanLYcQFN@ik8mCU!CtQ^HJ~&P?oNCZ>d$IGvf;$xKwv?fnDg za}=40in+a8)R~E$%tWQ!-Y@EN6q$(%xxHW1=P1M&>yb*nqnw%8kzy>-WM|?cVusBw zgcxg6GTA-9h?r57b5z1iD6iH;$xKWMGoiRz7v&t4FcV6vby3by2{UmzGqIDIm=b0} zS+(9$&QS?7p{QCH<*F}XCX`g`qFnVQ%*5%;#7<_Sf^F~izB3a$nTg7^yd$P)Mx}6q$)BVJ1#zCU!Ctm1%o_pZXj{W}+f(?-q4tVka{(CCtR> z%*0M+VoI2a)0v5#%*2#16N;zx(dW)Y!c3gbOzdPP6xtZ9`JI{A$xJ9&FA?=Qip+$< zzYg^2_=2p-BJNDK1Y$6m;+`)qCQ8FnV17+LZUuL zA*gto17<>^?kMCGOZ5I#pG1AtM`mIUm{cNCe4IbbFv>W*U0M8($LKl<({ zG81#aOsJ*qC^8dsz)T2*bVreyn1h@NiP{`>keQf+oC%4#qsUCm0W%>{cNCe4Imnri zsLfFanTa`ICM4>PA~P`u%!EYUQDi16t@iGR-^?kMI=%mFhYQJ{cNB9bDvDcYHdgUm$b(cUlWj$+P4#nIj`>W*U0 zM5WQ*FY1mWGcgCugswliqnI->2h4;--BDyFDvI{*pYP1XL1vW(5aF$Xyl zy8GvjA~P`uITI3fN0FJBgPaM8`W!`OVh)%IiMpf6Ow0i@AyIb}nTa`ICM4>PV$Q@I zFcT7WN0FJB17<>^?kMI=%mFhYQFjz`Cgy;dkf=L~%)}fp6T0~7j$+Ql9553Sbw@F0 zVh)%IiMpehGcgCughbs@WG3byXF{UxC^8dskTW4scNCe4IbbFv>W(5aF$c_qMBPzj zCgy;dkf=L~%)}hzOi0unMP_0Sawc@^+Z{z_Vh)%IiMpf6Ow0i@AyIb}nTa`ICM4>P zV$Q@IFcT7WN0FIW0%k&@?kF-7OTbJ>)Ez};VhNZDiMpf6Oe_I2AyIb}nTaLHnUJVE zip<24FcUhA9xKvxF5A7 z%tWP#JU>z=nTaJ~CMrc_6s4nroC#@~qZB&A(N~|}`@LT&B4bOzOe{gpgj#BjQs@X; znlKZUA~Lp=j!Kw`N)Z`E$xJK>Gf^obqbMB}hf-BDyFmV}w86p^u|bX3Ajh+H$9 zl9^Z%W};F=#+K4i2{TbCBBLlBl`s>PA~K57Q3*3qDI%jN9hEQ>l_D~V(oqRBF*!4F zl9^b7oC&@8e2yYBu_VkyrHBkapUlLPFcXtA6AB%{t1n?DCTAv2G80R}OjL@<`19$g zgqf%mkx`V63UVeiMcH?hLPyxAS{K|s@i{Z0&=H6x%tWP#j6a`_N|=dC5gA0uOe_gA zQ7Iy$DCekznWz+zQIxB`gqf%mkx`V6N|=dC5gA2sKWa&siAoU}Md_%7nWz+zQIw8K zn2Aae8Aa)+gqf%mkx`V6N|=dC5gA44sDzoQ6p=xc%*2u~6O%I&3LU`?|$_;GojECit5|-Zc%3@6gomteY@T-YC97O9igb!1^0{kcNCe4C1EBiMPz)W z=%|F5s1%V=l#WW6iOHD>g^r+4gPaL{oB7TJnTaLHnUJWj`p8TyLC%Ck{X2@x#1iC8 zNYr;G$V@B=Gch?cq0kWyRN^RSCKNhC(Zo^COel1OqRGyL*XB^@2t|`spV#J4=mg^sYLdW+rt>T_m7p(7O4O8b6McNCe4C1EBiMPzvOk(pQ$ zW};F=Mo~H{VJ0d?WE7>N5@w=OL`G3MDq$unMPwAEqY`GKQba~kIx1l%Dn(=zR_zqY`Ffa%MuIBY2-C%*5o(ghEFknlKZUA~ODbIx1l%CTAuTI>MGFbCfd^ z3LT+nGDkTxq0kYECf`xcOel1OqRDrZGZQD7i6vnsDn(=%eKHeE!c0_($S6ujCCo&n zh>W6iRKiSDipVGmN397nQ7Iy$C>*sW%tWP#45DNv)`Xd;6p>LBj#?9DqEbXgQ8;Q% zn2E`m35AZhqt=9(s1%X0rI@4Egqf%mkx>+@zBOScDn(=zg`?JlnWz+zQ523^6K0}P zL`G3MDq$unMPwAEqY`GKQbe9b1<+uUS`%oZVnj@po=T{R$`LVDnkvC2DoDgs>8gaA zs3Z|nrL7WhqM}4hmA*>IiOLc&RT?Xao2W1mQ>C*KcB0ZmOqJG3;E9S8F;#jip(iR& zWK<C5w!z1S!@8q^M{SQ>C{OlA^Lj zOqJeBP>Ko{F;#jiVJRwI#8m061g5BX5mTkN5}Km&MNF06N^pt_7%^3PE6Jd!gb`Dv zw-TVDB1TM=-b#py$`~0{iBzl!Qc)ozrb=%mOhu)Pm@2)MKou1;Vyg63LRD1Gh^f+B z306@-Bc@7kC0s=%jhHIEm4Fo$HDaptRzg-()`+RnTM1fGVI!tWZzXI+rHzcLge%qr zuBf;XQ>C{Ox}x$%OqJeBA}K0x#8m06B$J{NM@*I8NP{Wtt6GAGDl36-bxUQ z3LP<3dMjZpDs{wE>8%8^sMrxxrMD8wqH;$@Rbm!vf>~7Xh^f+B31?BsBc@7kC7?w` zkC-aGm5>&dJz}c#RuWH9;UlI>Z(XPH_nx*_`iQC0TUUg^{i=r8>h==7b!8abuWI)| zq)KlkxJ3n!SP#%!32#veB%>;Ui!}+Us0b2MrMHrlipn4{ReCEyE-Hk?ROzjRxu_Hp zQ>C{O=%QjsOqJeBsEf)WF;#ji!7eI@#8m06guAFD5>utO67Zs;NKBR9O2~`KA{kYQ zUaSdvQDG#eN^d3XMWvCLD!rA!7Zpchs`OSuUsN86snS~seo=uWrb=%m{6!^_m@2)M z02mcXVyg63LSR%TiK)_C34&3fB&JGlB@9NTl8mZ^FxDivqGCx*mEKB{D=L@7ROziG zx}t(fOqJeBvMVZ?#8m061jMLl5>utO5)z}bNlcaAN>GdnCoxreD`7Dzoy1h(ty=

cV!dtfl$f$@CQ-!x~36W75C8i2* z-4Z0DLP|^(-nu1BMx~UPD!g?|pp1$sF;#f$mQWd$Q(~(0R)S?zP>HG1TM3s@NhO1- zzzk=7ZV8uBQ6;8IZzWttWtEsJy_Iko6;@)Z^j5-UR9cCt(pw3aQE?@vN^d1xM&*^5 zD!r9(85LM!s`OUEWmIB`snS~smr;==rb=%mTt;P8*szSiBsFROzjR%c$fM>j8Qz;W8F42%@&qTM3s@ z*(KIidMn{F7B2~+w$fV(mr>~@V_V5(+!8Kh@qi1NfZj^DjK!;hNR{47xQxXkE~H9t zC0xeh85dHew-PR6xrW$Ai{47OjLI-EReCGoGAhKxROzjR%cv9+Q>C{OE@Qcd*i`AQ zgv+QLlTnpi#x3D8mTQPjmEKCYjO7|)Q>C{OE@Qcd*i`AQgv(gGLWlxY=&gjySiD4t zROzjR%cwLH>j8Qz;W8F45~8-!TM3u3c$E;T(pw3av3QvfsnS~smr;o(W51HixFuZ1 z;-ME>5Ybx+m$7*2g;eRSgv(ew_Cl)kR>Ea0o_irxdMn{F7B3beReCGoGAh@^o&kC* z;W8F47oxV(TM3u3c)bv*(pw3av3U4}ROzjR%UC@9LJN5AWh7k2;_(+!rMD6;qtZ>r zXMh11w}i`BJOD#&rMD6;WAOwGsnS~sm$7&RhE(aTgv+Re6YE!cE8#LK;>1+xt%S>{ zj1yC(w-PR+LQYJT-b%QP#d9zewn1+tT*l%-7*eIT5-wx$>LF6)yp?bniEae+KKf5y_Iko6?bB) z^j5-UEM7%Kn>qAW!euO8MntOg)AP2- z|K0Cjz5ejw{TuziUjO|4t6%)`um18+|Kio>x(e$xk`?}JhYl*IW{CybJox6_S89#C z@l&Gs!1UiMQA;f7isJjyUnLT?#DcCUKQH<7EwP{}%3V=^k*KAXQ`HsK-;EEv&(RV! zcCssK$!~Hzf4-rUT~S9Tu_LOM8ade&b#f9ll2xHk8OzT&W>*xOHvSHg=%w@e!_)gW zufKlvc~{hu-xU6gKK1R;uBbZ-yP;}n;wbEfVlz~tiKDO?ioH;YCXT{hD7Hc+nm7tu zp{S88(Zo^L=nghTjbw=?j`F-;g+KF=N*v{RzY2ebsBeQdpHpmuqDHc6UM7yZMtA5_ zY=TPkV{_Cveg5j}?|;*t7j@~}|C=Xvhjb6m{-f8ZesW@zs@s^Es8Tf_cUARwL;o-o zRjOv>uBuOsOhuKdIk~Bd-66)JO4Y2~Rn=oavWRL#p>Rrm6VU{tAILO;$AT~(hR zPwWm!)!f`w_4)C{?vQSH+638E^$C*Ms8TgQcU9pn><&pa@fLQ6PV5dzHSw0GqblRb zmz`2gyoKGN6T3rFO}vHOAqJ#MHSrd9hnSEm)x=w#kg9(5rKeP{hv{B#c|@vIeWsLZ z;w{fem8wsby62pD%R^G7>Z?zwe#~3rwDxabh5v7T4&rEV;g_4A3|k_9-3Zi@oMR;V2MmJ+(A( z6ix!M)O)=7Qm@-mcNES6C3@-H>nNN9VxcF|#8Fu2VVx(@k2z|bH-FeK{l&k0{qF5& zfByEnr}rNo{z4n9Z@>T0{z&{`C+qo<5ew*_(7W$-T+RCQY*{;5qbPO{ci-#iifZ&m zQU5+t@o;lYSJWIM5RgCL=Af>q{%&lkui(^Db4*v%<{)8!XsPdYbVbcEq5vssj_Hcp z93%*kqUM;csLerQ04aLu{OIkjsLeq_04Zv7P*>Debs_*MYI9Ii)K_%^04Zv7P*>C) z#Z}$ztGceJJBq8i-B)#8QT^TED6Z;uU)6O*-BDcC?Y^q(in^n?s@r{4*A;a~aaFhb zs;(>Qj^e6r_f=h2)E&iD-R`TpuBbbTtGeA+bxl!U)d~B9qkL7@6?I2(Rk!=9t}E(} z!WQ1+?yI`4sQzwn6jyb-uj;y@?kKM6c3;(XMcq+c)$P8j>x#OgxT@QIRo4}DM{!lR z`>Jjb9anXq+zq+sY<%@9=(<#lr`#`)UbFqDmv^ftdh1RxMQw)biPjb2=Lb?(iYaO{ zTvycms2jx;wKZc`)cmLm#T2zQV^>szzdn=YII zsy*FO^~YPPw#m>{wZ~hk{(LK3^Ah^;Q5;lX#^Q@V|LZ^h=?$eD&|Hq5BI>d&>4g>x$Y7jhE10kjr4Y<_+{0PcdHDl%!8>kB3*)g*<%h zi}a^%6uq!1qxX4=ar0A*=4AZBri^{cQ;h!)*_1DS`}!a5z)&_PmsUOWbPH$;vaX!_T<7qP7FL@{H^7Gp??v?WwPPIu1YM>WbP9;L0U{c&@B)e2o_beQZ@cGx#}(NH618o| zuBdH0u7J}eY9HxcQFj#Bbcx!gV^`E21vLHfa5TLus=pii6npB2lj&VicNAg^)KdFM z?~1ykkXj&7_4)IbYgg1Ah0p?t+6tyC>W)HYfkZEzA2)}aqMli>BCTgMXpn4`uG_ussK_sus?cg(l7+IqH!ZUXunclS5$^{{+; zzAX}X6y+(Vzj2$Q{>IfkK(^GLkFKb_adi!lqV{}rMeU8NTYwa`=c6lXZ(Lmhq^La~ zT~YnrI8c7d^SJvPw<{{ckD_?v?*7K@irO1jHvsYT{f*ldwKuLV08-T6xLr|u~*UA{OXXbKa!HQN3tzz zZ+Xf3Ln&E%DBH63o|mk@=p}0}`nIgS=_Tv0ddb?WzAdYPw!Zb3y((MUk$zhiF5Brc zFMQLMh09R+My-upb`A8{2?t%~rEl7;h06}Q%xmAYW#O`eF7x6yUD<1(trO@nuYS{( zh06}Q%*)@jW#O`eF7x^~ZCSYNpv$}fPFof(JK!=@z-i0EWd~e_5;z4kHs-QxpvNZx zHE>jyHgefD&?XC)p$Ja9wQw0AX0_JmvTMTZbOKxkj9Icim-S>(2WNf+$Shf(%et~~ z8Bk`)CUY4o;i$E687kp4pIel|kt|$>QaEi{xC}tEDjz3v8H(YkwRD*m!)dqHUB+rS zYHi{&l*5@PV9k=f9;tiRx2T6BSn@uBIja)5yR6$^zWZf;E+da9S)a?gL*{dt^5xlDo6D}J zt>Ik{fm9#RWJrN*Hr8w7NR}o;4rEtWe>b`TNs#JVGg-F};4wr&O4Yu~x~i}kvLI(< zL3UN)Fcim;syVEy3WFgHQmWSg-R%Ugjx)15j$|W)c_5@@IgKF^vioqsV8}^OYt3NY zC4z@SsYp z6WX#c88QR6=sS}eCA_yTk9JiteB(Ly34w))j*F=0@4&DdkNkBzI6~$oxsJS z=P7ib1P@e@EM4Y_3T;^pv~>bq=9vm@S-1?unff+znImUcS}qpi&YZPd3zva9o0*r@ zd~UCSw!Y=YhjVA`)?zLLd8XE0?YsNA_0X)DwR0rvF6(vzTm}|GvhK2L3TnJ+u7Mu= z7W|oHeJ)dcEIa2ZIn`Q}_iyA$9trlj7SjA+ZkWnd%J+Q?;IMQ3Ie9mz&6^D;V;<%-dXwC=0M z>*z?9bD1+~U0FvYBuke$mDZMp%Rot}Z=+3o2h-GAZsI$c)^06a1~yHtwXKh~EL_Gr z<~P4%-j;>Sh<)55>;vU=W|q^LZxQx^dODKj_F{y6EZ0DfFGgY?w+Q=Ku7NgLx-7yz z7GNI}v5#AXeJs~NTWdL&McBu34YbM9WfAtVTmx;goXaBYW4Q*}WO*PRVIRvi&?d_j zV}yMy*FcZ5#6E5j_OSr_n23GcBJ5+i2HIN7xh%pymTRC*mM)91j|JGrbZ{<$ zXlpH97GWRDHP9wYmqpmeat*Y}(q$3$v0MXfvT)h<=tpJOimb5^y$0H3;j-;foqzua z6tItp*vA%O9}BRL>BL;NJw_`=MAuEkJ~m(<-M)p(h<$9pK6Tju71+m2>|?8s=ezsXL+$37 z*vAI!qxsxk18to^mjV0e%DT%$3i}@87GWRjHPF^t&Sk(px~+AWiLOFxfqisk;WA<$ zTZDbAz&->gu(iotwtB?ftTRr^s`Kxj(AR6A#~~y3vCZoI`(?p>XcwEURp$q?K9_0l zlCsI}$9fI4bpl=H+(&aiVZHbslcmcX{AkOP11- z33OS+eym_Wbj^xSf?jd=ziPZNs9MXpEMh-aFAXYLx-4Qp)@z_g^OF78BKBhi`!SRK z*dq301^Y3R{n#S*W4$0B>jb(iVn0@}A2ZpHEn+`bupg>;iRU(AKUT0GD)vX&=(`N; zhwAcCHgcIqPwBl#mw5$^?xb@Kv^@!Q8Q72J6bbfYCi_ttH21%1u7Ms~i#i%}rO*Vj z_%0*+v4Q=#mZhKGSyHkLT1%IK{kT?S4Oy@sGue+VVn38FgVxez5&NNh8OYLQ5&NNp z8OYLQ5&NNx8OYLQo;cKX8Q2fqti(GZVn38K}c~ky=ZaMeN6V4fNlSJz z){vt zM`gQMC(vb4=0|0_m@HiuWqwq)i^{vt$L$*Ev9)AB_K5wsf&Ey>e(VwZQQ_^4Bm@Hiuu^*N1 zVzP8u#C}x3i^agXM^hH;$3pgF2m8^L^;7AE?8grF zqbsYA0eceYGSB^JJ_tZR7NQ@!$9{BG^_#4%oXMR0=&JfQ{=(3Y-NBEpD&{eAANz#^ zJntoRRsE=JA@;F*e6ksgK>MkFF~0#lVlJPJ47!;Vr@* zy9a%ARrPnHx5#>+=1Er--XiL;d(1~u6{H8No~Rgs?I?Ct;Vpt5yN7&qRpBjWeC*D7 zbXDOkVjjCkd~{XeEhc=R@<~?}-Xi3I(kES2c#Dk3?u<)M|Rl#?#{>i*M-_cctw}^M_j(2ob;Vse~yVD(ARd|bV$L?@PR~6nO z+p#;_(N%@F80)b++R;^ow@7yEPIh!v;Vpt4yMrBFRsG%QEoOS`&UJKE;Vo8j*&XX> zsv^;2VWP+GR7Y18-eMh>-Jy=ID!j!qF1s@wT~&CCRa|yQI=ZUx*3R!OCpx;S@D^*h z><)BvRpBl29J})zT~&CCQ69VF99>oY-RLbAaM_*a=&Hh7tlzRb%+XXuj)xLna8Tte zM^_czBFeEl%F$JYw^+Pocao#43U3kQ*d65Ps={03I1cAHx~lLNF^hDHxF~8$*hNG(rZ!x~(aD=0$S}`rwR(R`hf}^VnZxP@)B7mb( zTCB0yC_Ey7qf%N-7TfVh1aMSJi^*c@Ivn7T#T)zE71Cm=*o{A&-{`8ky%g%=uh^q5 z*ZdeS(N%SOtt{AbIK9zTb$cn&g>BV)?Ri_Xc`c|CT855YS+C`Ac%#`^ z=&HKE6zIY(P|rViL08r1F6FsU^|JrH55YCY)~|GzgB#tp`rM^77qr#6jjpQCT?%ud zsyhDu9)P(>Z5&Q*blVDZF|gxsXrrqNbCKCNoZ0BA`rNe=**F~8XsRNuLpd%SEp`0e zqlF?ZE5kaD2-v7pmeB?*(sD$=#)hyC#kjB!)b-DO(0v&K*ieiMWFugsQdz7M=&uOa z*Z^#-1U8Nc*w_GUtOPcW2-w&V)}a^|_H8tOA*@3&E|k^F?fxeLVI3>OI*tg~*bvsS zGOXi>fQ?FJ86Pl)bsQ0}u_3HOF)r*|ciHu?PqPY@%3`gh%N*EfF20e~p%fQ1HsUoZ zlx1uzd5r_Sh87d8KEO0aUgL;(jSakpQe4;xk;#zNp%fR&MkWKVv69y~B3@%dR)0~i`62jjl-#pwk(#5#5NAcHoAQaZeu04aX7cpZ7s4oR)QOc zgBxvGe2tOZIGo&Q%fe+uHx5TP+Oqf_BfD`pyU~_~%Ls2A4sW!d1h|a!#^LlvyR~o` z@r}drjkYXYMtw87HC~L!>QIUcUW^WKbXyC8Ln$tlwXd?aEVev|a2$?sv}NHk zG8~699Bo;+j1b4+5Jy`UE+fTpL|Gl%HPGYCON`@)vO2a4)fr{UaU9NZv^xPVBgk<$ z$kBZ#Agf~~$#FQz(QYl~GNK%Zqa0mXupBG1Iu2(!+OlvNVUELLj1a~YYA z!+qa-Pl;VO1%&CsHEL=vc<8Z8Fl>PgE{n_tdy?y=7)2q*4eev$g ze|-Az@Y|=?Up;*J`rC)^zI^}m&kuhvJ$|;#55IeO{NrW6z53a!Z{NT9=FNvU|Mc|T ztIz-L_pe@m`0)PCufP9r{qy&)e(}q{`pZB4i&vk|j{@Y!*EI{KKC)nHXOSUM8*i3N zmFTrt`SD2M+Fk$T%0;3!+7mv)B`T-gE$ZLkER`xzU$*pG>R;e2lqym6`TZ@mx9Nn> zZ;7hU?-#Wd3yY*mRDFKGsJ%%ie0o2!L~657?L9i-!&{=)Q*`em{C#j4IK@QU1NnvZxYG9OYlz6F#;jnmEdHF(-U#OEhtm zr(&`oszehei_{5fI;wVqUWFb_Ee#}uX^X4_f zzs#G@-=i<{rmbc5K1y8vGH(uB953@GAE}pl^X~QCf8Kd>T0cB|@!{#|>xVDC{r>&K ze}8)Y{^1Yj$A>@r)z2P|Z@$t0_3JlppZ@lXho8TD|MW)>fA}~5?N^^okJIu;?T^su z=4CeZ8RCc66Uh969Y6WSC|TPi(T9lhjgs}%Nb5sXvcAAq0ai1BWPLr-mGvdQ3b0bv z*Z5soO#h(s)mmTWH)S2qSKs<3iDZ49-<8$hjk7iQe98JszblK6X8`(=^>=A?eRZ@E!LmzB`-PF3%nQ1w)YAtS4=TF;5gs-CLJ(q#_ow>!aIMp|F3O*$3Tj`n$%=9FGMkdciV@g;yKjBP zNN!)Pjpi~3_tjdu3{i{C=hn%6$?dkNj`GAH*ZlKYa4T;}AyWI30C-0yY*<}#4`YHc)^Ik~UaaxO#EVzaeQ z?n{;~1G(Ro)!&UTMv(jJglI1FGMj2G=Q5D{-PZbd8OeRMHd--y)S_C;6{C~;-S@4d z`;z5~5$Jxm6EK$n-Jgi=cV#uu;%FDpb6C4Xf7j8 z0G>dy(Tb5k0nmNPMlK^#0H$Cfy5H?vxC~T*WG|t+SBy9wS-}-ZHgXxj0u^BOEq9{( z-A;hZfbOfck;@$27X-r+2rYL8+EMh;Zo~rdN=dy_X*u2c9T1%Hj?8oM1HYE#}ogUBFeG_^p8HCei>2I=12 zkE*9S$f^J<%p0*ERZrDqF_)bY`%(2&O%^N0Gh#ogo~p^xWfA*P^;AukE{oWYs;6qQ zbXmlHR6SLbrOP7rqw1-eEL|3{A5~A)Wa+Yq{iu4XCQFw^>_^p89c9UWoDuu6gZ)qe zR+u+pKX$MmD!@wFWcOqDGMl<;MVCeF#}4*G1z6eIWW~6H{ZIi`$|k!XRZrEP1iCC@ zKX$MmD!|ItCc7WIr#5QH=(33YsCuf_33OS+e(YdBRDczo5V0RS*bfz8rEIeMv3qLc zqynszja&xyLj_nVtB>NlKcIH7A2+feXT*L~J=O6^Ap3Df>_^p8HCehWVn3>$s>#x2 z5&N-&{ZIi`3|Yi}>|j4sfR(b>Ueetw#%rL*P9XbnBDS%&VYMSHLIqga+Q?;KKU9E~ zvXRTcey9K|Wh0k?{ZIi`%0_b;LL*dwm9o)X2KGY*SSg$AF;+cQd%)$>eyPcA7{jV>=)!?vUFL*epEqKlcmcd_G1V8 zp~x6Kw-NhMB~`7pbXmlHR83WrrOP7rql&7UEL|3{A5~S=Wa%=*Ha6{mKnaD%V8|l& zqw1=TttI<$M(oE9_Cpup+1h9>y9U}?OP59LN0nAJS-LD@KdQE>$7E&Fis^lOknchlu^C602it z$$p#>`%yJkO_nZ;*pDi*YO-`$#C}wjRgYO-`$#C}x8Rg`%z_AO_nZ;*pI5aYO-`$#C}xaRgmr3@Tz3$#)yasxd1^Xe{ zgk!9L7n60DNjCZ}y9U~1-DQ%E_85`-aYOEhWRpF{3V5;B`dlX2WRI}|UQE_qCfQ_< zu>xL9)?FsqWRI}|UQE_qCfVe?tO8z4mM)9fj|zA(S-LD@KPup5kX0g#eV5IT5&KaA zFD6TuMeIifyqGLq7O@`{@M5w)m#GsXmm&8amWpU_a)^i2bO57n7ySBKG3|`>}!jP-~O9 z>;U_*f&Gwd_-K>m@Hiuu^$!iVzQjeKF)sJRX*UJsynOiM$EW~ z@>us1h8-DAU!ROSeq4PoV#Zd4M1A?z64hOUaj<6ukV@1a_@=0RABM2||;w;-CLTAn{Yk~4xwAL~xSy`z7-Mt2nT$6TVm$=7VDM)z5C z!RCWReJW{+YIH|YpGYL?%eAJc?e8s*K8;A!KZ%;6c7Jj~+^9qoNBOS9f=vgBCXVtw zhvm_iX%bBwKFK&-8F5#RI7Xa^{daXck`!b_yx;PtUh0= z)djDP1#xpon^S=tEr9NQbu8D{#q+B}+2XeFeyO_iu~&!6Tz<4tB}3-?i%xwSOvVc^ zV^GEt4JPA-0dts)U#iswjsjc^w)nqDwYup~*3VRW=c@90M~&B;r#USMb9yY!>)uz~ z?SHfPc0H0DXOiw;NtAAO0aBasl@Zx@(hknd;OGmYFlT|;!J^n*q#9~=6V=rc2gLmM zW8oaJ+@4jl-!RO@U^nkXpT8|Dd7P7)0s#)~I8O$c&2H^%FDrS>qM z5aT4#GFP`2s zA-qYV!NYjjuWnx{9>$I8I($p*SGO1Cn-So>(&}#U+@@*uZ8iP;#8IBwG_8Cy0=QSK z)E$M$rZd}h6-9lo0nnaA6GwSo6I*pjG;x%tHL+2bL=#8tSGT*R5Y;5n#8FP`u}POi z6GwSY(}b8Ni6(mu`_=7#J{<*6@A;PM-!^}#=5(*$eto3#oIM@XdCngX10N6j%fKgJ z)YKx*evM@P=SbGKPO7rHTb~C>vi^vWtUn^EvbtYQ)*ljTW9IKbooqk)|K6EiUFM(O zz5NesQ12Ti12;@`Bwv^08D6YhpY!A!CIdH2bRa(wwJpej8zwrApNQIHVE~hHUchA3 zem;;45E&8;9t#tI4Dc8d4IT>#%06t#(V zK>rnq220lo7zQW|i6)Lh00$Thi6)Lh{07oDB$_x100#IAi3Stxgy;<hqFB6GtI(1Bn~j?etlx<|sfHU@jz@I0|taATA{O zF-P5|&)@$3*T4AH-3vil{=MNgePYY_Hhmsn=Ix84?y+>6K0mvA{r1)Cmk;mnUd(zb z-=@#QZw|NVvv<^gqUrPY?(b`??j`->U)8iz;jb;+AgsRofBpFGn{OVT$~!OmvSx3~ z6ME#FTYSc|JNGBmC-+?>YH!OEI^;;y*7ikFZ;&&gKaNCgZC@3&wf%(dI1;tBeO1)9 zouLp|?I(1`k*M8wRZ;!j^UOS0_UkHRZ({o`r)Y3UFXN0vZ|;%3f*udnmEdv;Y{d-BhkcB`_=8o z)OT_v`Y}iKFJTXF9{zm)^zQNWwYHMKeD~ey{nP#1SMR?1s{CXdM=xYNqbJWednKg@ zwN%a9Qgw4n)y!R0HFHbV-`u5Y?yjop=6b#qQuPhxarRJ_PPM-lw>jnM;qmp3hgH4m z4!F%J_PTSMQppxNYp+Huh{2YM=doT$S!C^iRL%O}CA` zZhbY}zKhvJfBP;LIO;#|cd_4nc=P7rUr+D9y?^=eSbhx?b8j#1`gZQgIm5;CsY+{X zsoI;nRQ=Ums`jC~s%pzDsrvCXsqR8QJ|(NF_UI_cSK;xbFqHfU-Sj1GF5re9=f z+C{Ev+C|1CmZn|es-|6HTwrP11+Ho8l&Af6KjJP;+nlLt>hGQx(me3HBnN(V#?v%? zKSXufen_=W+YjM!-z7Qjs}r79r|*TF7sQQ~?s*;XG)VTS&hBKX%9QK{|OZ$8`4Lt0t_EJfuW~G6Lebrnl5cR{p0}uNy$zfle@ARLKolZ5D zN-8xs4Lt0two-|x*=gWm-z7QhJNaSX;Y>pzSxjXY-YERA?{KE0K6==`^9FU-(JYo@K>a{V;)4 zePtk3TNzYU?O`TWf0{|vo@P~5dzwj=-tzMVRaJNkJ)c!;;w^9atXknMw0y4C3U6Vp zJ)+}tRTbXCYFny_w|uod&UmSkss{eB3lOq1W5q4i{YM}57E*R*thuEccni&*H3IM! znmyO97J5BP72ZOx=c+2ag`^#gfGriOs_+)p-ck*`g+|XB0eZ_<-_=^-tt;lOtFOPS zs_reec^UnG)E7c?-RrNA`A>YA|o1wX;;|Ek8(B9RXhxva_>lO}ynN$y6)7md*i`8)KTcL10eA~QydndG_bs$^9@)}a zs)@J!K$%oIZ~2L`>Ih)o!lyIUx(gkhxBN(%YURA;XUdAT`k6AR(p!G0tg7noTRK3B z=c}J8tE$3VI98@{O}ypD$}|F;xBOgLwO0LI?=2iGQ^uuzlCG-4TR`Kbnt01kmW?_^ zimT;E%c`|vO~@?Yt7rLERpBkPan=azLPx#jU7R%n^p+?27Hjn+HL22DdvD*vwR(=P zROv0x@vYVhZ!yOAx_9!+>ZddH%m2H6MFOJQ720A9PsAN)e*p&aHh9BQ?01#nQE$)-tthjsw(EK zncniw%~e%+Yv%iwH*T(~!do-F<$as0s`@*-v$!Vow#`*l%v(rS)7SN6-r6s5Un`n6 zOEvM9_iP^7vstQ%xBMiMROu~m*<2l0cnfEdRBQ6SvQMjFwtS*r9_a2iRf z@D`3EX#|paYrn*HXVF{1c_h^eZ{a|ac#ve?+Ap!y%6Tg|k)>EgVTwt%C|pLrEF|cnhbJRBPfbKb15tIF=;UWKD?EKnoahscPU4uikJPXyIv~ ztDgocKC?X2Q6oTa`Dvi4D!j$hKvzEvR8@ty5bLN^{bb(qSjTZeuA@{FZ+WhxRJoVo z!H(4tfVYtBs9JZSqwiau?5J9~CiG~>VyzzSC{@l|p6ysw#hMW5Z5n~ZTi`Mlav4_- zZ>!ddd5c`eHQ_SQm|5e>HDSVKpf9sjId6Gi=IRJw-XfQQw#-#k%vyELD0d;WE&YS*r9_!eyW%vsAezOt=g*WR@!5w-PP`{g|c7c`M;E(2iNE z?k#b$$(qm!XsNolq?*iI&Ona~xD2T#^A@;_1zd(ylQki@j0IeVRCntiowvYcuoJUX zgEb)74iTT%_ygy_R8Rri)ugLw;Wn5F98l4|h2g)Yoeb#F;E_`ZcE%u=Pd5-tNh zn59Z@C0qttFpq4(JfQ`1ZQeo$W~us`P^y8q(12O0K5t1i@D}lELD0d;WE&8 zdAxwj&>4?l-a_AHsnS~smw~p+Ql+;NE(2YcrAlulT*d}2gH4w;u8Ft6Ww7V6R18*szK(A$~(pw3afmX{><(e?zGSF#Rs+_kHE(490rAlulTn73qOO@VAxD2#e zmMXoKa2e>bELD0d;WE%8*sz*u1;4ROzjR%RqBwsnS~smx12OQl+;NE@Rs- zare#W0xm;mUlVVE%ea8ckZLk-fy=mn%aCgFzU8g%#tXO%sV47R;4&`YGNhWU3BB2! zYUR9@a2eZviR~Vsw-PR6+b^-H(pw3avF(@GROzjR%ht`x4>mwz-34^@z#Ec`#TF<7v#iBHQCDmmvI4?q4v?i9{dI_t`x4>mwz-34^@fNs@3%Cra zCf@R9o8tvshEg^XZ|#@3e`bNpkZR&Ba2XeH8B$HW1uo+PE<>t`x4hxzcmbCo)x=xi zGA`gUq?&jOT*d`lhEx-8dCyIa0M~>Gm$8A%xPZ%0t%er;F>Vu zGPeB^_uc}RF`W}GV?$oX1zd(y6K{FvO{H>hO_*>QEfS?40dN_rHSyMdiA|Mz83~uM zAurC0s^}L@`x(OUYHo`GFRR zVybxGQgl_Ks!QCflFLwbRidh;iK)U{3a?63_4qVZ>=P=zDp7^Eke4wH3763#QLI+% z6Dq&zc&#lG#Z=)f1z07jy2PdmZz;hlQN>;cxeP^EC91l_Rx7=ga2YKU#Z>97gv)4= zD4nV@RQ#Exr0HY?+*`^}p=#i*7KviD(pw3a(IQby74z1Ra2Z!{8Ol)M2qfMDm$8z| z7!od{MWWaU&|3+Y(IQby74w#&RD(MUT*gW+V@SA+s|VMO%22`8O1O-xcU@LX6M8G* zGOqh2?#Go}#*lCsS8p7tTIsEX%V?1(Rx7=ga2Z!{87uNKrXk@nuHZ6OEamk(Z$i6}TYbGFl{x)k<$AT*lS=FRQT+y_IkoS8y3Cxr`y< zGFl``KLX@3hJ?##ktn80ZzWvD6?qvexr`yk;JjQwZzWvD6?qvexr`yvWef?I zaYbInN-kqaxQrHwVzqKjm~a^_62(;Mt%S?Cg3DORWef?I(IQc-R?b@qm(e0oOqJeB zxQr|EGFEaKL&9ZT!DX!EGKPf9xPr@A$z==)m(e0o`f(+fF(h2Z67Sa2YGPj3MDNuHZ6Oav4LyWn95!tmHC=gv+>s%UH=}3<;OfB2oJLm0ZS< za2YKU#Z>97gv)4=D5gqpC0xc8T*gW+V@SA+7KviDa!r_U8CP%_E4hpz;WDn^GL)f$ zH_n91Xpt!W2$0Jd5-#HkE@LH^F(h0@i$t+nId3Ig#uZ$KT6S|>lf4XZ8Ol(hYO)6p zE<;VbshYfRfy+?WZm1?)MvFwTt3_`mTtJpcz`nThiT!y;DC92qiCzqivafzybJ6_3U3<;OfB2oG~3wasSkZ>7S za2d)_!JU%{mG2k+!>RiT3E@KS145?xdo_QH#z-36)dBT->8Dqd@NY&>p zWvJlJ3b+iZ`n;tK6{;ThmQ;P-Qicjuk9$k1TAFnCt1?umns^IbhB8#BdYsEp#DsfG z87fpgK5t3Yy`>BlsvdvelB#=487fpgz9y8adrKKAPz|^Ysk*n6p+eQ;^OjWMEpi!S zz-34k-XfPV23&?z;Vp6*W58ud72aZA#u#uJ3a;>ZYa^F223&?z;Vp6*W58ud72YD3 zF$P?QRN*b=WsCurAys&bT*er18B&F}n3pjIT!vKPEpi!Sz-34k-XfPV23&?z;Vp6* zW58ud72aZA#u#uJ3Iu_-$YqQHmmyVni+LGiz-9apiPF#9%*z-9F5`zt6jSBA6>u3+ zg}0cOF$P?QRN*ah8Dqd@NEO~9moWxhhE(A#av5X5Wk?m?B9}1+T!vKPEpi!Sz-1`7 z0^VX?#u#uJQiZqB$7E8c-otxDKSZMRE+Cho&Zmhg<}K!BsOMv%3U4tlL*4EYRd|bB zhB}=ks_+)M4E0S)RN*ah8S284sKQ(1GSn?3QH8h2WvHV;po+W4O`{_)Fq-<{q+-M@YH?yIlrecc71+uOeaCG5W0TeA0+>_7IC4eIr#;8$3I5>&M- zTvhcetUw8>+7+&<`qNW^5>WLon4M~WExvg7@=p&>r$0X2zdF6V|Mv9$<>SL&PCpyY zpHJiIyVLpS)4G%|i(={Qfi_^Rpr9Ump6xfwC$EY`?Rhp}sUT5%oK;2baVBuvMo*&l zG%JewN@!x`hazUDz!VkDr$GSsBKniH+ognZu9}G1XXJHc~#Wz z^8t$lr8Mn#_K!iK?4OkmUG;x%#4Mb|==ljy2 zc%M45Ibda=*t1>ds7;;N8~|)eG;x#zo5HmD^FQXOe%}0Hg8a?DzIpfd^M8E%{^9ZI z^eauJZ$CWMXUoO6f+p+)DRjsjvzPVh*;3t0`{_cjk^b{U>h~9-DypmZJO^n_N>Ou6 zRn+F73EM#W`R16asQ#|6)Yn=PHOEv%Z4R2S38Wk+n}e#NHU~}E1CppYrYdT4(1a}@ ziJD`oqBaLjT-6EDPi`q&)lFR0t-h+OR%)xdiK{vR`az|>s++i~TYdYdSgCLSOkCBi zzN)K=x}&(N6P=&@eEs8{qqwRQoS%rgqqwRQo1cifqqwRQnxBZeqqwRQnV*QdqqwRQ zn4gHcqqwRQm!F8bqqwSDeb=XWpZcn9;;L@-O`oc$&rw{}t-j||6?I2(RVOAt7*k)> zOW<>7PDFlEsXL0Ry4KY6c~w`f)E&iDUF&IjT+|)KRh@ABkNo_8Rrkfy z{nrnt-+g%V=HXx8mltw6k!Jt6UeSF`IpAO4ADEw9$w}4xELDF^ld2iIs%nOos=ud6 z)#k{es-FRpsxLdGYRk^5s##j9zV4K&2LAb0sj8Z%rRtj>QZ-XoRds_sPm@yhm8Vp9 zp&#FXs;cH{srt*>u=*LGs;b#qs=ogrRhucRs^)9$DLIoSRhufSs_+)h07=!HT~&p* za0W=KiMRX=kVb&s@-sliT0NUps`Qqh0jjFPTi8L@2qfO}9dy-7Z+SLrwN`iwJLsx) z7dq-KKLey%=`G(uuht50A)9qr{R~i572d)bAgLza@@!UZ*mB)PCqOj&ZmFUX3*=G_ixJUhaZ{(JkK5D zh9!}%Rn@MpRDD$Z=mf z>Q`5)wkoNr+LKeNzABNbJvpnYwknaTKRKmptCFg!JvpW7s}ia1xAc!s&Z?^Z&aRd} zIVUBgC93x1RIR=$k*cjqsCoJ`)ZDv@g9EhNToSd~b1|Ivr97QBU3 ziBuDB`Km{d{t7d72d+CM71W~@>PjyrMG-l zQmqxqMOIGHR}tOz2NDBlgS%TChM$H zq6%;EWU@|aB&zThPbP~`PgLP8o=g_=ov6ZFJejPw$K$H4DM0Tno=jGQszepux?)YJ z);x(Syv38rdj2G;@D@)d%O{B{yv38r3iwY{F>mo?@|2uRZcPEYdq7|ETUVY;o`S@9T??PLt~{AM?Z;M+z8elWnXE1X9M{BK zIGL<20#r@Bg_Frwo=jF$NiqWNEp-t|10jMS?lLwqkRu=)P25Z9B6rjJecrsapT5=Cy-r~t*A!>;# zyv38rV$>2<%v<15Rchib=TY_6ioJ}fIs)(( zz*Jdl7dp5H-h2)!sP0m2erueu=GC zeBYW9E@J?fp)LY=W+hxkYYJes(pw3a(V7C7D%XSwm(iL6m@2)Ma2c&BfT?ocO1O;H z6u?yJt%S>HO#ymUav4*?WwfRMrph&8!etELGSo!?_iMss3{H#cyA!>Ya2c&BfQ;0Pq|Ti`O(MS!ZwyoJPgbrGOy^1cNwLtO-*ns6DdDS%xqdMn{F#G3n4 zn_R|}a2cX(p-OKhT!v^+sM1>rmob3LxRT455-wu^mvJSRF(q8auwUZ-9w3)7C0s^p z3Sg@AR>EZr;4;)jfG$Y91ujEf1fZI58LcURjR3usa2W%*40RD;t;t>nxD0g>plY%v z1ec*M0#w}>!bkTqz-6e509BLsEpQoEav4*?WwfRM{XIY~V@kM;))c^0>8*szXiWi3 zmEKCYjMfyuRN<{T;WAoN08@px=7h@_kQlEn0)A)B370V-FzGT2p}Mdq6Z6y_Ikotto)1(p&pS`=c{VYYJehn78JH%VKRTBoReCGoGDc5~mnyxLB*u@P7%x?NE8#Lm z=Q5;9ZzWvD=!x-CrMHsA_|_DlcLBMKIZ2FfO#w`m-bxbVTT=j2rMD6;qcsIEReCE) zjBiZ=dR1~6bHZh`rU0f&ZzWttYYJeh^j5-Uw59;2N^d1xMr#USs`OUEWwfRMrb=%m ziSex|fT?ocO1O;H6u?yJEzb(8eKTrJ0Zf(NO1O;H6u?yJEl&%p)@u8N;?p^Ad0bdk z)%FRcN^d1xMr#Vtj{v!hIpH!!PmEWs^j5-Uw59-7E4`I)8LcURsnS~sm(iL6m@2)M za2c&BfT_}33765D0+=ejm2erYDS)ZcTM3uZngaByEbprU0f&ZzWttYYJeh^j5-Uw59;2N^d1xMr#USs`OUEWwfRMrb=%m zTt;gOV5;<1!exw}3#+qAoVOA#qcsKSYbBR4CtOBr3Sg@AR>EbprU0f&ZzWttYYJeh z^j5-Uw59;2N^d1xMvFu-ReCGoGFl{xsnS~sm(e0oOqJeBxQrHwVyg63!ez8blwOrw z#++~&EfU34Id3IgMvFu-ReCGoGFl{xsnS~sm(e0oOqJeBxD52c(D_PwE6K}19}KC| zTS;CC{OE@N~qL+4gGZzWtti$v*bWnRXda2ca> z8LE}uO1O*`iDI?VTM3sjI+vkZ>8*szXptyZE4`I)87&gUROzjR%V?1(rb=%mc^NGd z#Z>97gv(H{lYcK@UdEho84AjARdN|~l9$mUQTh=emoX=K87&gUROziGFQY}Gm@2)M zHktn80ZzWuY5Ov(I@Ya%W87&gUYQ?;@ zBwR*|MCnz@Wh@Do(IQby6>GvJ$;)VwD5eT;EeV$~I+w9$sQ5SeCCSUs=SRN>$Ym@E zm!S_@P=&XaBrl^yqS&~?TT8-av`7?Fg}0W3%V?1(rb=%mTtEbpNR(ccT*i`c856h+WvIZh370W} z%NWRIED4v5W$YO$yjlVC)FM%=R(dPp zGSsZgX6}J`8Lhe3Q9i3hqFAl;R>EbpNR(ccT*i`c8Oluc5nx`%l5iQy_Jk_ut%S=^ z$1bSSTM3t;mR(Tgyp?bn>e&TVdMn{FS|p0y1N2tHWwb~XQ>C{OE~7=Fm@4P3gv-#$ zYK$wrm2ep?5~Z(|T*i`c8EDR{5Wk{9YO1O+^zr=PA&|3+YF?n8wYNfXlE~7=FSgrI{!ez8b6jPsa2b>5WoX-w-b%QP30%fNE@Mf!jLGvdR4cuea2XT0 zjDcLnl5iQ5=Vho?dMn{FS|mz;XR(jTl5iQ5=Vho?dMn{FCeO=|D!r9(87&gUMu6T* zxQrHw(yNloSQ0LyMWUE0y_Ikoljmhrh%b2{6iE4$nE(w>>B2ju5kjuCv zTtO1O*`iDIhsR>EbpNEB10w-PR+MWUE0y_Ikov-dI42WomN;WB3AWhg_1_dxLN zcm|iD3>B&d8EP#O#m1H1O1O*}c^S%3L9Gdw(IQd$TFGTx5-wu~m!S+5)*58dv`7@I zmEKCYj24Mvs`OUEWz66*l%c{A&?eGReqcskhB8#Bs)yQfRo{bGh6+^^Z+RaRAtm%y z!ez|hGL)f$T9dqt+54ENR(dPpGUgq<>F+FZ8JC31n89TzLxm%dcne&HGE}I#e6^?7- zEpQpiP@!t#EpQpiP@!t#EpQnl`pGE{K25-wu~m!S+5swVT6_c0N+$$2Z`GG=fY%1~jgiMPOIC_{y+iMPCuiAI3l zO1O*`iPGO$>|=6CxQyBRn5b6HTM3sjgUe8c3dS|zGG^~%qFU*#gv*%0Whg_1wFa5h zGq?<8s8BWWmiI9cyi9K;T*eG8Lm4WpHSw1BF;T7bR>Eb>;4+k%!DT2z1tXAf8S{?bSgrI{!ez|hGL)ghS`%-9%TR_2RTFQ4%TR_2 zRg?EEa2d)_p=#nSa2d)_p=vU3fy+>a3RM$tc^?xUji9#@E@K9lp$rw)n(PyT%TR_2 zR1+>^2A81>6{-q|Is7IME<+hAR871EE<+hAR871EE<+hAR871EE<+hAR871EE<+hA zR871EE<+hAR873Kqc{Cin_R{v;WAnzimB3D370X0%TR_2Mj+ubX5?ikLxrk|w~&{i z3>B&--ts;sI(S8IC0xb~E<+hAtTpi#xC~{eP&M%uxC~{eP&M%uxC~{eP&M%uxC~{e zP&L_u2bZA?6{;rl7Pt&$sJQBya2YeW3}vWLHSw1BG0{Omcxz3#jM@8`NEO~%6E0&0 zm!S+5jzHoqa2d)_p=#i*7Kze7wV9W(CR|2~L@`x(YfZR}7Kvi2@Yb4e87&gURN<{P z;WAnzimB3D3763#QB0NIO1O*`iPEVmLj`wM!ez8b6jP1_DgK4n77u1%UHl=C_{x;E10(ya2d)_p=vO1E#NYgp+ePQ-dfPdL>VejO}LB& zT!u1Ks2a>$EfS@_2gqft374^e%TNRZYYpDF7UX3pLxrlrytSZ@i4Mq8HJP`-W$17u zRf9F*0xm-b z3}vWLHSrd>3}vWLHSrd>3}vWLHSrd>3}vWLHSrd>3}vWLHSyLSiPFyn3%!+a87&gU zROzjR%UHl=C_@D!kZ>6bxC~{eP&M%uxC~{eP&M%uxC~{eP&M%uxC~{eP&M%uxC~{e zP&M%uxC~{eP&M%uxC~{eP&M%uxC~{eP&Jviz-1^y1*!>`v4G1^h6+`ac?(>IGE}IV zcne&HGE}IVcne&HGE}IVcne&HGE}IVcne&HGE}IVcne&HGE}IVcne&HGE}IVcnf(M z%21(d;w^9)%20u7!euPrGL)f0)x=xiGL)f0)x=xiGL)f0)x=xiGL)f0)x=xiGL)f0 z)x=xiGL)f0)x=xiGL)f0)x=xiGL)f0)x=xiGL)f0)x=xiGL)g>s$0TkEZ{Pfp+eQf zTi`O3p+eQfTi`O3p+eQfTi`O3p+eQfTi`O3p+eQbTP+f$e=i`Hu_atai$pP1cxy|z zj24Mvs_@p9a2YKU#Z=*~E#Wd+B#NohTM3uZB2i40-b%QP7KzfSDnkW#R>EbpNEB10 zw-PR+MWUE0y_IkoEfU34>8*szXptzUig{~GxQq+93}vYBYJF_p`j>zE?EAa7_uo9+ zy}0|;!>IUq0Ty{L{nJ>HUXqzkT=kbobfaw~w#CdHwYI&kyhKUi|a-clS?EkFUS{ z@U;Ku_jkYf?eBm6i(lQn(7{Py9Ex0F5jM>UQ2FNFEB(6~fuB;<)7A!zR`j+fRaHH0 zO_f%3jH9Zmr>&{diXN{~RnWz}k}*|!YyZaod?2H$3U3kP*gRgNstRur z6QP;4N=^QdNbwh;eM*_N1x`ZxQ3zJYJ)!3U3kP*gRgNstRurdJ*ld~Tf{gvkJqTG!dt{RHjme+s=`~uI5x*Ps;cnT#5JK~9930#ix|h|7)MnV z-Xg}a?cewhuQGsf%)~f0kJqTy3U3kP*u3pYQ56`6B3IxoZ+lWzg|~=tY#y&sRfV^R zacmy1QB{Svh;eKluTfQnw}^3Uj&W2~;Vohuo5yQZRpBjS9NYel|F8>yam>UxHg9`U ztrhbYF^W*_jjAfVMT}$fwkK6pc#9av=J6U;Rd|aS z$L1JERTbW1yvF7jM^zQxBF3>f#!*#;w}^3U-u9%big}9|$L4KMs;cl7F^W!g zEn*y-w>>GU0^?BR3cTfQPde3p1Mu%ZynnB)zkhiB_SNYRAHIAzu=xk#L+LCmK-cK- zLleY@(pjjgYjj){HYD+}d54s4uzqTz62!+$;$w5-qpAuUlK9xXLrPT@HYD+}d54s$ zDr`vNWAhFvRaMxK#K-0xQmU%3A&HO8JERmoyhY;U>K#(5s_+(x zkE?e`sj0TGmHzV*iI1xjA5~R&>xwnu)rpU)D!g^Yn(*qxM^zQxVuzHg6CYJocr&O%iU{P9}dTS{kv zYJzaANa9dB3sp7n$7_YRh;UpJgkwb#htgSCYvL^=aVVXIs)@Id#G!N+swUn7!l85) zswUn-5{J@RsG4{SNgPUNp=#nSBylL6g{q0Ski?;M7N{l&$BHBlrL#~q@fMOe79t$i z1mReb#G!N+*7`AT^&4tmylX7oA0O^tonGF5dwT!!@!>D0pAF~Fr}6aN>HPC`DetkJ zk?qE4xAW=?%6%+9$=6BLCOsy*Nz{B<6GgJyh~=b2&6ZVB{oV7VKVmg0QFCQg)MmU9 zi%E%^DXXHkm>jW|l&E>KDr)oHh^6Ft^`&H0)RvMXR+19kb$;yFQx)~u4hu<%YRr#| z`a%-xNQs&stCjjY8kUg~wW+QuYL1$)ij-*LD6Ar}h?HpJC}6`_LrOGp6fj^cAtjnP z3QI_=ASIeO3R!MgK%Q4$Ko+k)7LZs!N_5vb>ZtwdK0o>wFS?~9`D$#I)DKfBY{?bk2&(<^G zOhDBme%~5AJj2;SlmVy`y-k~cb4(9So5~8PziuiVt$%b30Iko9gVwd>(d2n~12}7m zer$d4arELmd0gHA%vz$sid)HO{_}lnNut4uTft~9>N`sk4OZOBMRQT#SdwV4;#Mr0 zi~7EjM1vK#Qqf%0x0TL|6V}CB${QFC0IVe%JUWz#W|e}kmS`{;D-z8`eNRcE!HQdn zXfEp8wGvGn{@n*r zkN^00r{U+rxc?u&{kzlu^XC5T*AK5wzkIlVeEs(8(|=I|^3T<@Y51@8X_Oh{`0$~X zO<*N$a`&cZ0=Yy3D=~o_pFJcRSZTp$4}A5IXkeuUUp?^AL!yC|7JT%;H;?n`-#lto zV){5fc}O&{(t=MO_~Ieaz)H*>#|ICIe#}Zgu`*i_J&q%*68+fZ)cf<_zoIB};OX7l z)5kxi99!P{p4z}YwRYqF%_a9w{9Xm&_r4ssr`B%V`zpfsdtj z;~p0E$I^h$vFCQ<9v78G`bxQGP996jz;{uunUlwoBJf?5Yv$y!qy&5y<(fHpEGYor zMg2?cc}X5i%D*>JK9-i`v84EW7v-8cc`PaY-bJ}){^(=rr@ZeC5e6Kj*O&$qy|VAU zQoe=yIr`e9r09DWrK9{9eO1&Qg;VtU`N2f5;Cru>j`BnF)k@t_I76>j+h7ArvG-mn z9py*ptChN=aDrZyer%$@O`m_wB|58(j9r=A^l4k*ZQXZ#PIj|%Ro~Wq$3@-jT-7hP z>GSZu`fd6&?<0mrlTz@We49RfOt~PvO`o3(%hROfGyCoB6O&T1R=&M`+IuqB%D3tB zHhn%lJifkvbN8b9{&9Qz>~@|I;ilC?u+6NlYyUS+pZ`(2wl^rDf5s#FO&bEqdiDk- z*qCxXdxH{=&zmRY3?kDdW|b^GXPzPwGJz5u^5L&qOW zH)hCYx*IdpA0+%gjTw6T?(~<3FTdQO_pe(ha2a@4M_%J?)LGu?IyEUY=y!*$KABS@ zRpV8q$^aq9>x!z5*Gbj+I@M|$s#R5cd6TM}MXE;9S5p({S0MQ z72aZ>nyVk8tg6CW>{D~~4;EEbcnilUr>h^Mtg6CWI7cbf#9Mxja$4A@=IRG2tF^*g z>{D~~lay6e%v(50sSz;LrKsvhDK!H0mY=1ps={0NZlPL}dCLz|s#eZhewwmcE4+o{ zl&UqExBNJzYURA;pDwDk!do~{IbHogWmOg4!ih?$Cf@QBm6J|STMUU*lX+{u#LxR= zQstU3=~J`rm)KM}ZzX+dR`jXS0cwswvL@UwvDL~oVbZ5&-7m4J(pw+xQ`3KI+IxMR zzIeL-`r&jw{nNwa)9aUlgvy{i}x0BI3CRJ7Sch9boDxUJAcTB3P+EZStcsm)rV^UQW-eSk3(K{wpRqgF$RHHOF z);lIuRpBjmOd7poQdJe+V#lP>J0=xXyG?O zAXQc2Ew(`#y$w=T72aYSBt6A~JImW3jcSyJr;E2iD%QGR;{MKJ8zlWZNv-e}+aQhJ z2B}&ryu~(1qqjk-s_O4-1UPSb8>Ff#yu~(1qqjk-s=`}rgQWQCO>XZ zVjCm{SSPCR7TX{x!8%a&Hb}ZV=`C-ARJ>aICGPJmwn0)DXHqM?#WqL^u})OsEw({Y ziglu@k+Knhwn;wp#JN zrC`ov1oWFsmEQ8~`sxV4TL`b$FYBqx77WNs=>Uad?nP1d8?g>JzT3N*pKRd##)1UYw!qrsbVjq(N)K5 zb#JNr8EZ|vhJpJD@C$wZ+ZAuwN`iw>07Ebc;6a4eM|3boVPrFt6D4O zEfPZQjO_7og||ouwTPy}s!j-L1n4a%go-2J30zX8x112Fs=`|&gj)Lc@e#nhMM9{> zZy#6HZ|c28La60$A6NA?;gy6?3*bJk3U84RY6;xORWWao5NZ+J$5r7i5<)G5`?xB+ zMM7wDLa2DZIw7RJ8+ywLp{lCCZ(T_UwHWThBj6$Hs+DU(CxoiC!doPSCMSfds`|U$ zTO@=gCxoi1@D>T7$qAvVD!fHPNR(eN$2uXT{X5QEP6$XD&{Q`LX#6hRaJP4gwW)KP*qib*L#bE(ByAKAT*j1e8N+^wtyX#~;WCE(5}PW$m2epYxQr{gj49zVhW!#-t@KvH zWeoczHdT5n;WCE(5}PXbG7>Ih*e|iE(pw3aG3=MvROzjR%NX`c+^dqym=Z2y*e|iE za^6a~jA6gTrb=%mT*k0pVpFBJ5-wu^mvJSRF(q8a050Q7E@Mi#jA6gTHUjik!etEm zB{o%hE8#MR{Suohy_Iko!+wcPmEKCYjA6gTy(+nkDd94P{Suohy_Iko!+wcPmEKCY zjA6gTrb=%mT*d${<4P_=;C!$i0GDwkmoX(=#;{*v8v%MN;WCE(5}PW$m2erueu+&L z-kK9GW7sdTslr=x!etEmCGJ(pWy}eeG3=MvRN<{T;WCE(5}PW#H78uguwP#CRBUaEbB`z3x>6^#WhV@|k?k?oPmWz2iy`J-?0qjMRmmEPJv+8c`M;E#{CkTD!r9(8RLG5dsT87bHZhe z&SmKA2j{JX%NRXvUaIs~!exy6CAJaZ`&PnbjLv1KR(dPpGDhbzq)KlkT*ipxmNU7G zIpH$K{Sw=_a!r_U86%Qg&g3%Ygv%KBOKi2$TM3sjdR~UkDsfGia2ca>8B(RU5-wwO zE<>vHR>EbB&SglI-b%QP(YXw%(pyPh#^_vzROzjR%V?1({hdWFV@|k?7Kvi2^j5-U zv`7?F<-C<}87&gUROzjR%V?1(y(+nkIpH!|B#NohTM3uZB2i40-b%QP7Kvi2^j5-U zv`7?FrMD6;qeY^aD!r9(87&gURJkThxQx-c44nm~w-PR+MWR@(^j5-Uv`7?FrMD6; zV{|S<=TEbpNEB10w-PR+MWUE0y_Iko3Lx^8Cb^6`;WAnzN?$AU zGUkNKXptzUN^d1xMvFu-ReCGoGIVqm<4SKOT!s$qL6zQ0xQrHwVk1CrC0s^}L@`x* zE8#L)B#NoRTT8-a2v5ei!dpwiWsJ^cD8m5r){<};EfS?40p?{a3763#QA`!yS`sd! zMWUE0ytO1;hCV;~)gqU%BwU6*yg(J+S`scpTh360x0Zy<&~_tK;jJa%GPHdIReCGo zGW6mKReCGoGFl``cV{U>#m_=43763#QA`!@TT8-av`7?FrMD6;qeY^aD!r9(856jS zfn3Ita2YKU#cHLu5-y`fqL?bZm2er;eu+($-b%QP$@4Na%=A{mWlZ2Q267oo!ez8b zlzs%rWvI2raV}%pFR`i8TM3tehEuxH=&gjyn80NWfecl?# zWuRwc?fX`XM6s(yZzWtti$pP1dMn{FCU6-8xeT?|NXFIYt$|#IT5BY#{=PMk%UBXF zV*-~kkjqeOjigrpc07>FKW{lm$4*VhO)f;nME#RNw|y_ ziDI?VTM3t;q!rXkZzWtti$t+nId3IgMvFu-RjvsWE@Rp+aj!})V@bG-X}`p#%6Ti{ zGFl{xsdC;*xQrHwVyavdCR|2~L@`zDWvI1A@N@x}F_6nx5-y`fqFAl;R>EbpNEB10 zw-PR+MWUE0y_IkoEfU34>8*szn80NWC{OE~7=Fm@2)Ma2b>5WoWyA^H#!TOrDn^ReCGoGA7T5WoT=I z`-BOXG3}SQzgo=8SQ0K{^1KYy$~9raWwb~XtCikLxQxm3GE^(Qm2er8=VeHh-b%QP z7KvgbKyM{nMvFu-ReCGoGA7T<&UWQcZt%S>HktqELkjq#SE@Se%3~d|o zeJkNICeO=|D!r9(8I$K_NR{47xQxm3GNejxC0xejc^Oirw-PR+MWWa}KyM{n#^iY! zs+HbKxQxm3GNejxC0xejc^Oirw-PR+MWXcMN-kqbxQrHwVyg63!evaJm!U0rdMn{F zCeO=|D!r9(856h+WvJl0VZvoh;4+kymI8>ZS@+c8*szXptzUN^d1x#tbfFB$shXxQrHwVzts+3763#QB0NIO1O*} zc^M=7m|PMrqeY@vt@KvHWz66*l%WC_BwWUfybNWiP&Jviz-5f&GA;?1(IQd$aV3{= zNw|y|c^S%3;Rq!27VAgiRm6Lxrk|x4>m6Lxrk=w^}4he`hf-V@7Kvi2@Yb4e87&gURN<{P;WAnz zim75vxF%dii$pP1dMn{FS|p08(pw3a(IQbgRb{B)&Puq97Kvi2^j5-Uv`7?FrMD6; zqeY^aD!r9(84I`!WvFmmgL!KKm!S+5ss{5`i$t*zptlk(qeY^aD!r9(84I`!WvE~T z5-wu_m!S+5ss{5`i$v*1fLz9!a2X4@3`JY8)?nURz-1^yg{r~4wSdb|h6+`ac?(>I zGE}IVcne&H4jNH4@fNrY9kHNlum`_@%Me^n)nG4U0hb}P8mbAG(IQdI1@um6Lxrk|x4>m6Lxrk|x4>m+yPT?tx4>m+ zqmZhJx4>m+i-f9)xAs;wc4yIB3763#QB0NIO1O*`iPEc*%UBaGqeY^aD!r9(84I`! zWvJk4C0xd`N1|A*^j5-UEa+pR3>DUzcne&HGE}IVcnf_@l%Yb^#9QcNq6`(PCf)*< zp$rwMCS1mXJ|@agp=z=w1ec)<6{-e%87&f}zhB8^tVv$R0xm-tDy%h`x6sE#87fpw z<}Gj;%21(d;w^9)%21(d;w^9)%21(d;w^9)6S<5v$;)VwD0XMjTM3uZB2i40-b(T^ zS|m!ZN-kqf@-h~18Ol(>)k^X*7H}ELP@!t#EpQpiP@!t#EpQpiP@!t#EpQpiP@!t# zEpQpiP@!t#EpQpiP@!rvZ-L8Dh6+>@E@J_gp$rwOCi51!3}vWLHJP`-Whg_1s>xmk zxC~{eP&M%uxC~{eP&M%uxC~{eP&M%uxC~{eP&M%uxC~{eP&M%uxC~{eP&M%uxC~{e zKsDhq7H}ELP@!t#EpQpiP@!t#EpQpiP@!t#EpQpiP@!t#EpQpiP@!t#EpQpiP@!t# zEpQpiP@!t#EpQpiP@!t#E#ze=Lxrk|x4>m6Lj|e{m$87$P=*Rs6K{dbP=*Rs6K{db zP=*Rs6K{dbP=*Rs6K{dbP=*Rs6K{dbP=*Rs6K{dbP=*Rs6K{dbP=*Rs6K^3eLm4Vm zO}qszLm4Wrx+Pr30xm-tDpXCp1ujDwDpXCp1ujDwDpXCp1ujDwDpXCp1ujDwDpU=; z)gn>)_gHcnTf$|uNEB0rx3+}KXptzU3U6%*m(e0oOcmbR5-y`fqL?bZm2ep?62(;M zt%S>Hktm(2GE{J9C0s^}L@`x*E8#L)B#NohTM3uZB2i40-b%QP3%CqrsBm0^dFui$ zLm4Vm{n)(qFaP%0_jhmazj?TOarf}%;m`L^?;cNIKiofl`R=>Z`=|T2uikz2)!k=z z-#)(n=JnI-KR>*`d-2cT-`zhwJ-+_(!_)qs-{1Y_x4-}OFMf6RLMOic&2K#8%}=Mb ztdhL}!n;@c$2AN;rK$({^Rr$0X2zdF6V|Mv9$<>SL&PCpyYpHJiIyVLpSOZlRl(MAlDui7o!dxpi{m~#zn|7<3x-U9Se=tbXCf%AQ znulS^m8Lxws+#({u1czk{T=I%vR(|p8!VG<3DgnnVenNIR)wpytOS95!lUj- zD-1WcW^FHJcjYH%Ny(bKN4AKTtlPUPYZIkp-Qbe-sj@0-4wtN3T(Uk}R%OlOl68|y z)+fxOtZ%PM)|b+fb(>dZb)lavDOsO3CF@47%Ifb-)~zmCpE;|t=5f_M zyJUU-RFHwspH*474127Sja=rNtjfysmsQE`^*ujFs@1|}*kzS$c|s%RHC3D(f4qlBLT$n7Awpmtm(>V;i~5w^~&#UFJvN%GJVU*lSg_k;{Cu zRn@{}Xc}Fv7B0gJpYlT7W&2%RxWW95PuY=h8Q=MeF7y3X$zm?!YhSfm%w^bc)gbs> zR+YtEh8ZeG&2x@E- zm!W;Ms-?^DE?BJ=F1upI$k)NDtgjgPLa11tUFhgshBv~IuY{7_Z>i(5?lQgSAtG_c@tQgy& zspEHoAB@u=&}Dc*tXAtT<13=_q>{Nz$Dn)=a5PS`k<0vSoFa=kmw7Mg;)IT7(vroB zv7MX>E*V^g({UOEbJ>2keR`QN`ROx>~KDk&`SP<~^m$vc6axa7a#r5IM|G$*Ed8%)3gL ztA)jIOitCB#mchq81jpi31}WG%fe(M7mI#St}F|e;iR0Zja=pt#!9oN%lxQZxmvgk zXXR9F3Qc zxmvgkN9R;+LMOPjKxD3bW6wT}|tKJD% zG2$GZWTO?MAEZ3`glS2=21tGr`Z&sam?sdrw!Z z1yaf8)2cR_%ltH*s-?@EsVr9um*F^_s&$uD$5xNi{+WRDbjlQu-phb}umQDX-DTBk z;WC`4lWgQNKT@Y|Saey0eV_-mWa+X9`#=+F$#TUQVISy1Em^uO!amT3TC$wWBJ2Zw zs3l96Mc4-#QA?Ja_!0JjPSld+Toz#;Xhkhq?tVnr2YOMfjT={t5%z&*)RLvkBJ2a* zs3l96Mc4=0QA?ICi?9#$qn0dP7GWP~NG(~qEW$p}ky^5JS%iI{CADPfvIzS?Pio1+ zW#~y=oq7F`on+xMG^H-fVlE^0fv(hLS-h7K`#@XjvMk=qh<%_hby*fGMq(dmOkI>k zXXawgBE&Upd*av!3mu0bHB=&*k)MZ($7>RwfqgdUmbZu#e z_SCv$bQw+oRAt>|>`$$ZG0BP%4XV{W6m!`n!amTUTC$kSE)n*D7S)o)Ty}}D5A>*( zEatLHdnbS1R4HCEU>|H!txJ}?m!V6ws>NJ(0rpX?)?Fr~*NzCP+T^_qeX3P0=Q3a) z)oOkBL(mqg1@=*uh0BP2pi_1AQ3LEl6alN%;2(d~cqX!%^wMSCtGZmR&t>}h!fKP< z4|JnWU*qrMBK*=?nB!j90V;Sj$bklMpm_SnS&qIOXkVQlBLU>{3y%9 zWkf$Nj((J7;WDxxmx%p9(`ubHrpqGsWA=1p$IAQl-nL$Yo$Z*tc5U+BEpb z?^_Q@R<(3l#D2_RKiIii)kZG!h-6humqqLcdRI%9E{oU?G_RH{=dy_XK=*3hU)cRX z_v)&7!G5rPwHo(DbD8HPt6I7&Vn5KpTC#Lm#D1WIwPZP$MeGM!SWA{Ji`WnJu$C<6 zvWWda6Kl!RWfA*wVvXf%fNnA ztM%OvcCuEr{#AOn@~6L?qLsC(rOUv6?C(7VS+F1MWvyzXxy(b8RV`f>u^%(o4|cOw zwb5MWvB|2IE{oWY8SID7fnt3du^(t?t!nAAi2XoEYpp&wmqqNy?9s`RrOP7rWA^N1 z$#O0O`%yHnhbK#xE(7~flm+`CWRG`338Q72NAYk`{?8gP{ zM^)DM7}?ocJ${p~(r9h1L7>aPepIW)dl}h}OT>Q6U_aR0T7wX+7{Pw9yR~F}E~^d# zc0b5|Tq5>k2K&MO)~Ysg8Q2d^GH_YMe#~G$*x_2$Mst}*DeG;Ib6LcG%$}tzS4Hx-4Qp zTDD6+wq!pp5&O}yT}+lM#)$nu$7^jY(Pa_)(Xw5vTCNx)_M>IHm@HR}5&O}yT}+lP zi`b8r?P9WYS;T&z?X@l$T^6w)=zA?$xD0)-tGjk!KiK$MlTgAj&WQYA=WEGEa~UE( z*!o(s(Ol*k%i3p!%T`2w6jzKMvMgD+Y(?ZpO%~m+B@36K`*rb7K>KUS!ewZGU6$3a z>Rm?m1O2bdvUo2e`+)}7Wm&wJk^NYs$Pcu@*4Sb$TO;-ZJ+QTrkKK>8{p_PFMl`{e zEatK`Vn5IYTe5Un#D1U+wq)tDi2XnxY{}AP5&MBg*pj8oBK8BFuqBJRY>n6tw8EAw z=CU<7AG>$?_R7Daxb9kyiYvMBNc{jeoVmx2A*_d-6s z<&K8flBLT$@}v5^Mdk-PV(YCkc`s|(F5RTVme`U__842Xi^;6kF9g zVYR;j7cLpt4|c`Yt97!+h_=|e6X>#t{Xk!AedeXhBK8A~u_a5FMeGMUV@sAUi`b8r z?$Y02WIxu3{b=znCd;`jVn15Gi^*~>i`b7A@M5xbS;T%UU_aO%TXt}l6<6clA6s_< z=dy_XK!a?_(q$3*fezWC9_TXUe(bxsg+~q8kBPY-E7*_XqyzSYJ+ifn=R5gTS>MT@ z$bPI~KZ>%*{a}}DRqJzERo0n&w#k;P&t+9ve=lR7Y{}YAe(^@|KH0jzxL|bjqpGUk z)ISkOeymP@R8<{fWS?wp=GxXrRaFrqvOw}^VIj(QYTL3*%H zwwe(n-U8^sKG{;WiK|*GyhYAqb4&)d7#9D)^3U4vNV{?k5stRv0z+-cWqpGUE>+dWw9Gf#7RaJP4 z2*>6KM@J8fB|kOk8M`U6zHr2ymcNc3BqoBEYdZ zz@Z`v``c)htuerE{O0^dRn_gqR@vj$e)Nya?W(HVYbL$1IlWO;b$iW(H?|1gK(A~a zlEY`^&Ebt=v1r%AUfCL0o4cy2?l1Prma44_tExVC%_KKACpW69`n&FFs5ln~lQ#!9 zs;X`-rMW=Wxs9r-&s_?0p{fS{`K`063UiU#*qqv^s={1^Ha3Sgs;V#-nT^evjjF28 zT{Dr5&5@0wDu@l`xbSKv-a?a>nPDAU1Z=camfi*o>)0Y-JfwMZm^ozsxoW^j8FITy`?2mnE>VMZiW&WieTN>DnS- zHns@ZxFD=!W}}uZ0ybJIi;XSbzP1S1XsIkF%N1e-Y+L|rD8_}COb@u{d7;f{pJo*< z05%lk0$B$(ii_|4I@=h~WD&2?LRorQ@){d>jpCCAyv9skV~co=7RqAP(q!N@s?}m5 zBd@W6*C@(@*HDTJZv>mkicLQ*`-Qeapvk~%RIAnBnJi7_yhinX3BbloU}JM&qdW*$ zDU#UOoY*MK!ez|r*c{m?%VH`cv#~j|Q65_?7MaztIkZuh#cGj#S~jOP%Cc}7v5n2K zjq2Ef+fa%NT;|+HwOV9#D8+@c_A*wMh0928Y))>JWwp5O%}aD+i?TXeD2vH*Dsy(D zTrFHicw=*TqkJd8Wu!N@D68Xwtd5!Z#^(4&c@W?-@*A7;8|6WO%Ls664scYf1;L>d z7udlGj3`S-6Z4$L0`6Sr&5{DUQu4j4`?PG%a+GD^GG=vb z4s(=c;WGAV*_`I6UNU5LD8&Vj8pk=x)xu@uIX34x%GJVU1UfbcI?C0;Wh6Q_Cpya2 z!evA{Hb*+jvY5-rbZpLalx5*ELLHk!9o4Y~)u9v@++a?1lx5*EW_4_ib@a0T@^7Dg zfA{wOn}@p>cgyAJG@f65d-}zj58u3g`{A3@@ZZM&d3XAUhwo0meE0Zp`rW&ie|mU& zcy;>whx^CVfBFCZ`|mzK57YI(-hFoW?c?ijUO&D5^TYeQ7ytbI-Tl+kJqnW|&zjsnZ1N)typ%cQ^}+^3E*6)Sa=NpVFK zO&qmf-F{5zCw^s28Q9oLs8ir!8Wr7xm9l=c|KDRZ;!jv#0`z za7(qd^Wm#+j#3;EMFU5*aG}0ZI;y?u9In*ns0GZD#x!x1GfNBNW+a+8$~z4yhKOUD zIBLJT{g~2G4lEUKsU1q|Md>K#m8zmPM=5{^Ki_ess;JFTiXWnAFh{NX)$M*hV5Rfb zVWn!N?kKQI5=|WCy@eD!#GfC`Q7uNO|M{GwoK!0Qd?%F@I>btMoul4&P)U(P6ipoE zJ%toFMA2l9a!5&WLljNsC`XhOHUv>8l&TlX9fd%d^VRvJs;K_1yQM%UNi=wmYOz7R zDCa0=ld6^4dz3M3Xtn zb7K@J#GjuyYL5r%e?I3ZhmeXt-x;I@2$FvOu5;8;P9P~th(AAZ)P8mQpHD|QepLPW zzUl*fq@SNSYKP4FO6e#^kE)gW90l;`e0A`sDyqNhDg|~V(PWPD4nYf`BZ(%C+OKY3 zDIMj=QT6A$qW~PK(qxWu-e>`CB+$)x04imN_{ii-E?esz0M z&QXpORYl!V0E*662a2kq`n#@D;6xHl9Oa#V7QjRjO&sMc(E^l6qKTvStK0v4uKFA# zDvqghL<=w?Rl4gOoufPwW&uPb(Zo@n2(thol4#;6Cx{jRL=sKrC}$=XG80$FhpHFK z9Ytp1nlKYB@Ta?_$V^-lW}@Z&^rGCENSKKh_tT4V)#unybxhq+WG1c&Gtt6+`bxRi zmoO78>!%mxdz1r1#h>rY#6o7`>M<}?QJeGwTQ3*5AGJSecI_jg$M9&EeE4psKSeEnu z8n(~3(-%+ouiw6Tc>iAi>*3+e>5D(U`|#$~!{h0TmyZvBDYLjB4esPUxss zddm@=Vy%woNR{65kf5q6yftx6=#WlT6>CCJIvUqxP3V-4Mu6{Ij_Fiug}1=z3>W8g zs;XEM0@RUeGH*GkGmId0q?&lkNgb)uTaM~fM*!XetD{;IZ#k=@TInr^b&9n*tRq!= z%W0jeD!c_;M)s>!^yU*dlC24qL7 ziMJft8AdQWQcb+&%#Kv)Er)ih;|gzq+EJ~Ex18Eht@M^-JH=WZ+mR~0<=jqH72X24 zqY>DJj(W?%9o0&2Ik{7<72ZM`&~R~dr>Y8Xf!&d6;;sD>_uc}$Bh|!P4(|*j=pCsh z-g0_Js`QrQJJoT8w-5xRS`%+MzoS~|EeCjtwK~8fReH+_o~kOm1%yW zmELlOr&=q#1&C+3IK)#`g||TQNHy`+eu;Z;0ppQs;;sD>n=1FC4?&SCz2!ttbp-Tx{nY}}qgpla$L|4n z3pprKO}ynfC>jBJ%b}j)2zU^RROv0JdaA1M7O)u_j!`0xn}Bm$4>X#sV&5BA3yU zG!Eado|7_6EZ{AOouOR>EZ{Ap@$Mw-PR60hck6%UBaGV*!^jk;_;UE<+(17y-^(374^e z%b3VztO=K)m<-fPZzWuYax$PwZzWvD0xn}Bm$4>X#^Mc}hKXFpns6BlxQvNh#+q;$ ziwCEuR(dPpG8S+d6S<5v;WCt#;r9T!j5Xmh7SB%62+&&zm$7*3CaH4XO1KOKW?%&9 zt%S=^Vg^*{t%S=^WQMDf%UBaGLzx*+<-C<}84AsSD(9_)%UJeH+`k)=%UBaGLx)zN z%Ds$)%TR6xRJoUta2X2DfGWL}a2ZO@fGWL}a2blufGWL}a2d+ZfGWL}a2X2Ea8+^{ z>qoha{uGpsJ$GDD#_IfrTu?aWw1D53$ZxF9Z&X#`LGl}` z^BYA~@Ea5Pjn(;$swzB4eq(ihqpAuIlHXXJ->9m>gXA|>=QpaV@F4k()%lI8Dm+Mj zV|9L`stOO1-&mdBsH$RqBfqgazfo1i{6>Cbb$+9&s=w>!H}V^+^BYA~@Ea5PjTX`I zygN}n(4sl0ZW+9u%h@6sgiEA8p(J4Ab*icg-9ma2`GRQ)Yhs=7^| ze^*h}cZj6wD{ZOjHa)ItPa>)MN?WSBO^>VElSrz*(w3@j)8nf4B$BGHw57V6Rpz#mt&Cy`YBEmo=;_~WYf zB$6t<xafP?AL!??0Z}|?9YNfY)hp1Sq?+{6q-trxysw%vN9U_fD;w|4HQmyos z?+{gMg|~2WXS(_hQB@V*!pR+}Cf@QLBE3Y>TfRe7trgzF$sN_2c*}Q)R4cvZJ4Dr5 z;VtYCsn*0>zC)y1=`G(OD%R>dL{g=1TR6Eh zA!@g(3UA@$j#LwG`3}*fT|>-UzC%>472d+mk7`Z4mQl+VU(=?@>id^r8`{^g$zEcN|} zkA4(Q=vzelTT)@E@8P^s<>Jw|h^neEA-0Gn#Pe2Fv3SH5kyLH*SXG4yu|*_RGhtN~ zi$`n`Np%1PLK}%EhA}@u{j}@rWZn8Ub58R#o9G z9PyEA;w^7?tPyZ;DVB3zF&}-t?w7cCEROg{)n3f1BLHvVh>uhgZ+Uv}#Q0vRCf@S+ zUa7jbq`Lp;!{Z8X;fRk^18*U~SGBsgq#CRVk>D#;_m)(Hc?%J~QuTRDs)4tV;VV^t z-;!$JErj?=mEQ6rJ~bC0#aF7nS+B_3z+0Oi@tH0-;v?0-Tbm#8k*aUjOEvJ;=0|*_ zN^kiQpKe_Hm-8>)z5LU|)9H^7_peSb@4r30-vf(JKO4@UPvhyk)A{Gqx|Cnp&!QCj zN1h0F+cY{is`1(H`z8A18@ohp^*i9JghcHjQWdp_i1QG0+?MQw5(@IgYN_WY=d>gx7C-ya|6hBF?%rAVy$ z(?g4O`{_)Fq-<{q+-M@YH?yIlL zlciEjRq*qZO&Q<5HdI`k-G`-3d#T!!U8=q|l&al`RaJYmOV!tgQnfp=s%p=6srtix zoPEErQ|+(Czpr7w{P6Vj?(KirQU*s-aU%6B@F=*UaUvB#;S&AWz4zJoclS?EkFWJ3 zAKu@+`2OxUzy1BMfAOok7YfJ6fmGy#OEh_!<2)*kqe?V+n&UVsPNPaRd79%iDh{Jc z)Lc}2NZ>Fk&Z0`xOjH#$6Ag$6m#BHDDrz1YkPv=u#}p4gcySUH2T>)u7kBh&j)SN; zhbqy;Q80iiFoqIM9OaCmGI6mybi}ZD^&K%(#3)4*N8t=A07L!!#8Ehc z3cgUHiKB1=6?maU6G!0yD(FJJ#_aRZ(VHLVPXQN7G;tJZi{i&hMPw ze|!J(;jz4Y8T9qPU%sgOjsNR|b|m_7+AZ_Rmwl=F>TF=v&?VT2l&Ws7=cSfv_01C1 zYL2efs=Lcn-O^IENwQPz$N#o`@lo_kqgl}|O?MOj^Zdi{ zkz@9xwyLDLhr434?}}A5-9Ge>Z;Dkl%|F}|n|)DP)ieWfOKkQvWlYMPI@h@5>7tg2}~;uhHKTVPd9^AS$ho@d_yt7@8$2(iq; z+1j%@p!HKR8J5`@mTH~mBO)wwaIW?|I>JJNWp;w4SSL@_`X2S{083TVd_;a_c7CO* zX+9#pGCRIf)ifXBH0^l~PSffdnU8RmR+{_X!;kyZ)jG{bWLIWqSE`!kBcdy_qbpTS z^AX9F*~yivrum5A%Ix4uQPaT{ax1fQD^*RKkBF_zj;&NR%}1nGW~WxFn&u-yE3-o@ zRZa5|nU&d@m8z!sh{($9$Vyeyd_-bpc4DQfX+9#bGCQzR)ifXB#O!$vPRyRi{lY%K zZsNSGG&S6ZpG$sT7N=#Uso_4ZX+FYPS!rsxk87Hba8g#98t&to<|7<`m8ORKxTg6C zhhNXLAAT*~OZ$cGt~>V`JRPm7X+FZiSJkQEKK|RyM>zH>O%3;PP4f{By-HKVeO%Lg zgd?xgOnl@=UXh6=&BR9zumN9_X5u5q*8s0cGx3r4vje&&&BRChg?+x~0j`}t4zB&w zHu8R9J5Bn?JJ}U|_{a~m;y9}`6Ce3;Rvc!PX5yp$!ak2DjC%>L#&q$iPXpHg2Gub_9rx_wIh z0oS;FN_~8N|K_fG6XApbNrc;{)Tf6-<9Yj(`o%x~;U9ndo4XgcPpQug+3i#6(N6)l zPpNZ9AI)Xqn@PpJoebo-S0 zS0CLzrFK5LeM&v(quZy{zxwF*DYf&_?NjPOAKgBs{?$jfPpO@cZl6*Q`sns4^{+nq z&+{qu7V6M{HXnHY?iT9MV}U!5^2unF^K{Fk>PQS_xcD)WTP9UDTW*ynWjH!~X7#zFw9?siqBJj?$v+k}7NaIIK2p9&@0q zZ9k?h)#JFDRP7joR6XoKs>gvfsT!~*RY%sOYBzNWc#^6eMUbjT9!T{#v?f)9sHN(u z2eZOD`kSR%tKpwg^_fDd#{p2)s!RL~0!|l1A4t`1>}svL#HQ-u2U0x_fvQ$rVpH|} z5UC!=K&5Jvg+_qh3IY(O&8Z!!(py0Uf>hxxgdk`H5^wnmOtsQmK@5Uwg||TOsMf?= z`z5w}fZhtC5L7F?g;m(BG}^$io(wu&5QiYu#9JN>Dph(b2t?2bz*~q!P_2o#JRDTD z(py0&!n8TbBUO4Uh((YpyoF!{jX>fp&j(el^i~j!pjzQA5Iw3j@s=lqs#ba{h(}PZ z@D>6RW4F8BR1lt%s zZQk}ns(jxH0u-bQZy`cKBapmrdE*b&%J;1xL_xK}TZmDZ&q0iWRN*ZIDM&T(miPXc zE{IZ)YT~W^68GLhn1WOjZ=nJC1#t>eO}yoC3K{{f34=g|X>$rls`OS6sUTIX2@$HG z5lH5({Sw>N;=C2aDyUYh2|)v?)@0s7U-1i~73Omgt)N=rE%X(aYT~W^68GbZcm=5@ z-r6s*sd7yi1T1I-uqH&rf@)2?wO?YZmEH(s+_lipasv2FHD=$LQ>_t6+|yc74sIt7c>INyyf8ws+IFr z5Wk>WF>iqyQmx6nGN@M0TR|v;YQ?;TScZAcF=TlR??w7b?=NaU-7Cc<}LOWAH1)4Rn@({7qhJ?$wg3DORWef?IaRryLlFLxz#^7p!%UH=}sB>eY z>fTz(WeAh|h-#19eDQZ*oc{3P%Lm~$AHM$VG@ky)Y4}Xd-?hh9@BThrfpe_HIR?i$ z+Ku!{?oqPt$(20E;5$mW9j6b_~vTlx5*E!X1Od9c5X#jC9A~bVpSd zc*jb-V{p8qEDM*B?--o#D9gfS1Uv=@Jj$|g83_+H|4i%v#A7AmF*xE;t`;sM<1skn zQI>_v2zd++d6Z@0GEyFcQyyhmxQv*`;Fw2Q7A_;_F*xT@l?CXr67(1x^eD^1Wh6ZY zCq2rta2YydsB@exGt07Y8Cj3PS&yH^x2N|nA0Pg58vfh-`FK8kr}c4taeQ9>x9=?mrk_{;+@hPKa3pBq=N8|! zlBhrXilTl|@UcbTh5VWnMg75tZ!HqtfARC8r6`KW9wHQ1|I|_)Q#|ziON%P?^?R{W zJo0?QN}|4cFN*Skhg-_OvlM?mzO&#niz?NaAHGod%!02h64jU=7saE_Ke9;FpLDe` z#YYx=W07d$D12kVCzkW-pIE9F${mF-ED}u|g)c1lz#>tN`SA7j9i6)N1_Z56z zk!a#5d|tuV6^Uxh5C438UBSl{i6)N1#}#~Ak!a#5d|Sb%6^VY#Q8sJdHj}3Hwwd%o zgMbhJx6Py%YI1nnOwu6SHk0;2@F{BlufldXjtZ@}%_Kc)ZktK_AmE_uZ8K?q-rhEo z_CfIFVDV9db3^NGGf6HBH#zU#RL?ZH;*`&qrp!ZRaN!c-SIvvPZhF4Q;lr1@o7so2sw%vNFJDr%efp{@yv0*SgMa#}s=`}5WiUtLmw>6f8Q(LHdwhHsL1zQ=JX7D*ImmfFUA)UDAirUyD4j-c6X?y+DgVG+;YFVc?EOi^o zru@gWTGnaeC=W;zKu^)cQ4Y`Q#1o=mXM2wFcr?ND6g_&;`Rl^eRlV{y|F7W*%t8{Bm7_2KAHXNr^)-_%e+#>42dh3Qne|vtBNTS zS1zS$j_#_uqqPRI`j_fMAIRtW|BtYJaGLSD#k1{nRBdHaPL|bQx1)Le0eP0FRbN-s zs}I1lM6LFkqRu<(keWZ=zJR)-`n&t}zwSFwG+AQ!@sw^mP&643J=IQk9VnU%h#qRE zn+^~K=G+?)opP4(DSEWcwF9CbHtCiFMQupxw!RNZIBHTxT;eDXw9^d-mNapc=h^9g z14R=@`9YHoq$!#>%G2z0w}GOGqdd$`HybFLILfo^bQDd|#8Dn)r&|pW^)sesKlLO# z-D#j`;wTTY(~Sm-CXVtPJKblX=tGYBiFxz!v;Uue{i`QmJbw1058*OxZ&G^v>_4w_ zaEVsQt;q=D@#wlmkA}h(+Ga!foQw;!D(OQb$iv?rifQ*%F0Ri?G?|kfczpcqXX__( z^5bX!*{0cN|8HNv`u*?k`Xrauxn_?E0Ef~c%^t^pe0)cIK};<84T;*4wJ8dI1NeqS zZOPgd)!=vk5jcU~kf<$LyP{e?okg)^T?2UIc0oie*bSA`maN^9>hI1a#gcUm&<&MT zt$P;5l64Kp4T;*ulwQ#BA!iN14T;)>qsLPyY7J987;RZ!wXe8puF~4Fy)EnOcI8U2wBDf)_VPa};kSJXeD2o~sSR3hr1Py`Ef zGb$1FPbls%tRBeK{rUb0#gpmPPo}$~w)~xVGOcS-$hW7$ zQFjzirdPiO*%ft1@nm}Slj*LgJBlaMx(tg4rdPiL*(|A_Oiw(SUi}7SSJdYy zo=mTP0kSLVj^fGm>h~YJqWZg&qj)mC`t`@Is5^=$)2p9McSYS%Jegko@?%%j9mSLB z)$cxbMcq+6nO^_HvErF$XYEb2haZzcjj>Cr^UCBw+TU5bft~&ZN4qa7m zQYDK~)z%$dRc}*8i&0fZy8lo*sh;b9*Eh-dr7ji!+pvAU-F)-*>GPK_?%ur7|GK+- zar4dhuim}*?(X%?H%B7k6<os&@HQvxe6+y>LGMpy{fG6D4&BE{W*wk zS=Gd6=kqy;vA#>ME-O6B=O9LZ4x(FD_vpswAVz-CZpG5T{5T~+ti z#^)eLe-5In>fYM;uEXf>I&@XtTN|Hs82wp?t}48RTW9m=x6Zn%@D{F}N%i`9Yrge^ zr)lGx4x_*6&@C&x#T35LpLA%d;zfszFFK6=qC-~|-r|D}qaQwXRpBk%JyUBPLf4L2 zM-!h%7hFD*s;w=%WreqJ`)nTl_E}dI-U5dvRa;wjRpBjwXi~McWmgs60*NNo#9L0H zO&iXjq=bX++VR*EY)O9=*Lj1SFQu6$A<@c8F88^#{J>w0V#wu&#Eo>TZ*fo}F;w`_=q}HOheA~EN1DLn4 zZ>+K=^OoOeQdzkt;v2`^vcg-~Ii5$~Iqs@r-onXJ*gKYLGH>~vcg*o&>J1Y?y6$m0*5`1&S7^|F>e9HmTEF@9Zh_$SCH6JO}uq9v8i(2 z@&LVN4FJX7z+$VciMPOFZw$~I9mejK72aZi-sk~(T~&CC0eYhc=yg@$Ee7a~9-!A% zg|`@>H+q0xR~6o3fZpf=3%FhFng0KKj%yu|>$(F63FstC~A z7@#+LfL>P>^A-d2Mi0>Is=`|g&>KBKud51gF+gwh0KKj%yu|>$(F63ls_+&A^hOWR z>#D+A4A2`rK(DI`Z!th`^Z>oCs{ZcmEe7a~9-!A%g||rfj!yVCRRQ>J1bjz-Nvf*~ zZ;|gEo$u|c!dt|9M}JGIs|s(C?-=)FO$feYBi}JO-_b2AyhXlaIu7lx{^In^sA(hL zF?nWGx2*6Mxs1s(qq?g4yR)~*WlWwK)m4SJ$Yo5P8P!uAz-4UYGN#*LO*nwd*vMr} zx2pJS`@nECvDGWSx2D_UM_;*@F@Ve1$Yo3kmoXeoY-Ppw)|7A=!_ma13U+ErxQyXw z;*;u5E@Mi#jNxcvQ^j7!lyDit(Zr?-=4nc}jNxcvQ^ohzlyDhJeuXNyj7o~Vy1yPx zY-Pn>Mn%P5uj<~~$z{}S(d$)x-rC7!ObM4U98GLBKyM{n#&9&TsnS~sm!bSuS0$G* zC0vFAV4+HHC0vFQV4+HHC0vH$9id8ZC0vHWV4zBGC0xdEH1W9)kjt17E<^V~p~`tH z;WCs516Az7PYIVX98GLBKyM{nMm>OOs`OUEW#}%bmz7+G?(_uffuo7fWhIv}C0s_m zerc-oR>EZ{3>Iajw-PQxX|PbGw-PR+p1!mi;JlS^83VYCom|G0a2W%*jGbJ@lyDjK z?xocLy_Iko$`nOw(OU_Zp-@p*C6_TJT!vCbp~`tH;W88}3RQY5;WCsf3RQY5;W88~ z3RQY5;WFyM%X7~nmoX(=hN4ALR?b@qm!WJ?sB+#)xQu%3(rSR-O1KQAi=wRbR>EZ{ zUer~|Whfvkn76=X?Bp`0gv(ICD9TE2C0vFQMxjb?C0vFgMxjb?C0vFwMxn}iE8#Ng z?aFh1C6_TJTt>ZJX{z*A!e!Lkm8ME>C0s_mU1_THR>Eb}+m&Zkav4*?Wz^f1rpkFM z;WFy&N>in`5-y|Ot~6D8E8#MfNbfEnmoX(=M!j8WWu>*c1m0X5i;tu95rKxh>O1O-AyV6wYt%S>{w<}GR-b%QPdb`q8>8*szsJAOkmEKCYjC#A$ zROzjR%c!?2&#L4ybT=Sy!O_H~%6Ti{GV1M0Q{}vsa2fS>rK!?e371iCSDGrlm2esL zcBQG(TM3s@Z&#Wsy_Iko^>(GH(pw3aQEyk8D!r9(8TEFhsnS~smr-w5o>j?ZObM4! zZ&#Wsy_Iko^>(GH(pw3aQEyk8D!r9(8TEFhsnS~smr-w5nkv1Oa2fS>rK!?e371iC zSDGrlm2esLcBQGpTgnm$=7OV%O%>kKz1&0V@|k?;b`J>4Uo&2 z6E0&on%Gp~tvTT`Dq6)<;jKC0GDdJ2JGqQG;W9>W89Vbb=7h^oKr!kS-kK9GV+5D6 zGcRLKxQr28#?HKqIpH!!=Q55A70)4=6E0(PF5}2hp=$8GH9D6eRm@v+!evw>%DoGu zN^d1xMn$5SD!rBDWmF`Jsbb#JtM}KBgcXTms+hO*E_I@6-cr5NTM3s@ktkMH&RYqW zQIRO7%6Ti{GDhbzH22Y4371ikDCe>=FGH8llh(3%OJ$|E5-y`6QLL==R>EaeB#Noh zTM3s@ktn80ZzWttMWUE0y_Iko6^UZ1^j5-UR3wV2(pw3aQIRO7N^d1xMn$5WRmo+{ z371ikD5lDJE8#LK62(;Mt%S>{NEB10w-PR+B2i40-b%QPibOG0dMn{FDiXz1>8*sz zs7Mr3rMD6;qasmEmEKCYjEY1tReCGoGAa_~tV%9pPPmMUL@`x*E8#Lm=Q8xoMsFot zMn$4nS?R5W%cw{cQ>C{OE~6q*OqJeBxQvQKF;#ji;W9?&GSpi1R>EaeB#M=l-b%QP z(YXwjmEKCYjEY1#mz7+`oNyTxiDIhsR>EbB&Shxlg5FBFjEY3DveH`#moYk*p|a9j z371ikC{|W_E8#LK62(;Mt%S>{NEB10w-PR+B2i40-b%QP@n~XGrMD6;qasnxs^l`} zgv%H`FGD+R^j5-UR3wU(mEKCYjM4KlR91Q`;W8=`#mY)=C0s^DqL?bZm2epqiDIhs zR>EbBM-!VWy_Iko6^UZ1^j5-UR3wV2(pw3aQIRNTRdN|~!exxkWoW;d-b%QP(epB- zN^d1xMn$4n4bWQ&moa)?hRRBBC0s^DqF7n!t%S>{NEB10w-PR+B2i40-b%QPibOG0 zdMn{F#-oW%mEKCYjEY1#tCGu@6E347QB0NIO1O-QL@`x*E8#LK62(;Mt%S>{NEB10 zw-PR+B2i40-b%QPibOG0dMn{FDiXz1>8*szs7Mr3rMD6;qasmEmEKCYjEY1#tCGu@ z6E347QB0NIO1O-QL@`x*E8#LK62(;Mt%S>{NEB10w-PR+B2i40-b%QPibOG0dMn{F zDiXz1>8*szs7Mr3g}0W3%cw{cQ-!ydgv+Q%l(Q{NEB10w-PR+B2iAN%208FVoA7+ibOG0dMnAxs7Mr3rMD6;qasmEmEKCYjEY1t zReCGoGAa_qROzjR%cw{cQ>C{OE~6q*OqJeBxQvQKF;#ji;W8=`#Z>97gv+Q%l(Q8*szs7Mr3rMD6;qasmEmEKCYjLGvd#G}z$370W>UWQcZt%S>{NEE99 zdMn{F^t!R_4=6(gqjth&OrDpa8lbllE@L{H*lK{@O1O;4^D;yaa^6a~jEY1#mz8-L zOTuML{*H;tN^d1xMn$4nS?R5W%a}YbLuIA65-wx%cTA*8ZzWttMWR>@&|3+YQIRO7 zN^d1xh8{Y07w{dECE+qA&&yD~(pw3aF?n9btPB;5E(w=0d0vK8Id3IgMn$5WTZ>%A zl5iOniDIhsR>EaWo|mB-ptlk(WAb-Qq)KlkTt-ErSPjry370W}%TR_2dzLOBT${|M zCy(7*e8*%-xQq#0hB8!8)`ZKLJTF5eIlYx|85N0gZY}0zED4t}fy+>a3Tr?We|>A& z9TU|6y_Iko6SxdzsIaWM+;eqVJugFLrMD6;qasnPwdk#c%cw{cQ>C{OE@L{-8&l<) zFyS&La2d)_L2D&k#^mpq%*s%qYH)vR0+*o-6{-dtd_|(1>y_`AED4t}fy+>a3d^d+ z_|-1(ybRSVy_IkolfPpkReCGoGAa_q>XqI~xQq#0hB8!GugSdS@0h3t=&gjym=5&D zYJlEKxQvQKIjfS(SQ0K{0+*o-71V3OWlZ2Ql%Yb^WZv?3OlD=MP&M%uxC~{eP&Jvi z{2ddOmEKCYjEY3DK0t3JTt-Erm@2)Ma2XYeVyg63!evb0GL)f$)=IdH=|FGJWhIxf zBwWVic^SH~M{gxu#&k5Xm6hH~xQyv&VpFBJ5-wx%cT7|R^j5-U=!s{PmEKCYjEY3D z8lbllE<;Z`qO9~*!e!`*JgCxJ374S<;-E@zC0xdIH1WA!$z?1FmoXhpY^wBD!evZH z6Pqf%m2eq)UIME0R>EaW{*H-m?$TQcmoXhpY&Ae{C0s^DqL?bZm2er;(Zr@oZzWvD zymI8lfPp!D?`O+!%My>#KmxRlhJTF6Kg|{vV zmoa%>hE(CLOTuO73Oi~5-nt}QMn$4ny~10Ugv+Q%6jOz_E(w=Wktn7LZ(R~DqasmE zmEKCYjEY1tReCGoGAa_~q^b-Rcq`#DDiXz1F>hTGE~6q*OqJeBxQvQKF;#ji;W8=` z#Z>97gv+Q%6jPIW`U`Lxp`H$ji_H0aWR&gv+Q%6srMxE8#M2L3De)I0di@QI+ zdGgtlA6`HI{qwia|8V!_$ru0nKF? zppWj#<+PpZW6Sc@clrm_OdnFUuM(+x50t9yrgc@V2TIj@pj2%)t*Poe)l&5yC{^1{ z>#EvUiB!D@O4WK`SJg&$sd^8Ts*UblRU6%<>OD}ZhtT_X<+`f&#V=JK-G|k8s=KN- zx=YnZcd1&6Usu&ecRl{$D<`SiDNt9{zDlG@Z~0DjR~6pEPPNLKc*}RHRaSb-ZxA-i z>O0j^rMLVBVOJI2!cMhnAo14G#P{Q{%1UqfPIb4e@D^U&R#^|BYrSY}0R4ey5@s{sY3*Vr(e5blwR(K0L)hcT;Z~0EO%F21mcdEN()!&_43omY~tjWCP zJJl*Hz2!UAr?Q^c4HwZ+|Dtb^o3CEKdin2nH{ZT{^ZoOeziqD|l(%DjQL7^Fi}S?^ z(8HP^T|r3I`l3{QoR_Ng#jdK2^IFh(UzDni^IcWzi&FJ*UaHm?yQ((MOV#_LRBfE^ zs#;%^s*m$hwZ3>#J@=Zg?w-EBrk7|d&Hh~-3E|%zd`G!Rl^eRlV{J-*9gwt`Wo^{)eU+GA>Y?}cMf>KNB%4XI+*r~v5eRc+RgDrSuefWBVU zW(^%YW7enu=$};ml&;kbZ!>}}aQKWM7U=pJL8>+~OVvkasXjC#d|(Fv=jc-Pfmy0H zFrVg`531U@EL9(urE24HSJj4Psrs-iRU4MOs^%N1x^JXvzB#F$d(F?6|MBGJ>sRky zes}ZF|K(=*xvoLz|M2Voa`R6wp1%C;-FG+tF%{qZox*oNS76ET_ib-0F3Q?o*Y9kb z>~{4ny<^4oQET5WzNM$zcNDdj?}}Q>>+&5%t>L?(*6_M}M^S6{uBf%UuHI49n!PLP z!zI?(x2vzQyP`f?Vu>x$L+Aa#-WB!15-V(p+6ucXs@A>#g3`4+)TuA9yP`In>ed}a zZ8SZJp8a|4N?5j+(*1AI`0HI+UxVJ2kGC#9>N?3e=t^-rjtF_w>7)XHS2)dGqY`-5+m$Hr#$bjW>U~ zx&8UN^hd+l&-)e4fezuv{ihD`@RW5s`*FXLIVftgYfrR-Htze7f;lLf46*(=hH^P5 z>ix3QEpIDk<6KhjmA9)O^>=^1bxNgju%zB6nQp)3CohFVtTK6nU zNBI$dvrZ3+<19)?`3Zkl)CPKmaq#E+IN$51e!#CR4vHp@I$HPq^XVu*-tYc=bCi-e zP*OkL?~1ykaJa8^aI$DQTKDwxakekf#8F4A##xkelppP%e*Ssd+;26!eW@#s|2Ax& zZ#OzSe*W^s-J3W1Uw3yeZoc{c)w>tp-Mzl~=9o^~6R7Sbnu!KISJk~m2u(F`2wmH=e2!8L&|3k7HUL7CD!t{iRJR7) zTYAU~BcV@IT~&As^OP>FCEoIRYS2SoENkK|pQxltZ~08stpRuoJ65WJ#9O{&rLxjn z0feTT@9-A(tW?%y-f{>{W#zmTKxitf&s*9{WFJW8Ek7DoS?Mj`wrchPKN^-Qz2*B> zT~&As8&|rznRx4H;`8{5ohzv(-turDWdqS$el*;z0eA~X!zydyEe{7$S?R4H97y>O z@D{>>RMx~>M-y9X(OW?{kje^gjr3L!4kT4y6Y3!^I5r3ek}BpcgahfSak3`#aG*gC zd9kdCw>%t3s+_lia3Ixy+;Z*%2nSLPBx}N>iA|Mj!XO+-c_se6rH8y&ugUk8hXbiz zxh4$4fmBv_YofP;a3HC|TL=eIYbEoRhXbhw=&c|eNM(h$5DugZ_ldVW97x$~^i~iK zq_Se(LO77hn#@}s4y3Yj-U=RVQd!|GgafIp$-L#^Kq@P}6+GIcEFjEV2nSMGlX>fC z;`8V-(_29}kje^g&78M_a3HB--kRyHARI`l@D{>>hD#6*Bvq^l5e_8PWZuG+3q9n8 zQQNOvG*@p&6QBD4uUuUG%0*Wd-r|*ui(k2Ds^ZFp9`a%hB=eSs0|}JiyyaIex@Cp8 zc;({aS1!7$@D{IJT>Q#KR~6pkm5YmCx#+6GTfA~{@hcZyRd|b6E-rrMqN|E|i&ri# ze&wR8s=qsXi&ri#e&wR83UBes#l^2&G*xlsLJxVtTYlxDtBQGxS1vAo<)W(!Z}G~- z#jjj+RpBjOxw!b1i>@lXb>Y0_S1!7$@D{IJT>Q#KR~6pkm5YmCx#+6GTfA~{@hcZy zRsG%BTZ9@f4mEaF;VnXq7l#^~s`)X48nni*~5VbJ>-Qx5QGCs72evoCJe%Xq^g=adu!wO zRuB#(Rd@?mITUcFiog1F$8U0|Ug<5r$@CoOQdPxYuL^Gg7nEw?E#QKxS9ohpxQu$2%W44LS`#h=!{7O25)y}GybkQY@0Z`He8R#wbg z;0C*8b#D}4!Y4(c@pdMn{F>Rm3YS9&YqG8S+dga=ixs`zV1 z!o}f1)d0Pfa2bn-14)(MO1O;0!-4cl1-+GU84I`!J>-R+iFDkQY^hc?%bb zR0BBQ!cC%PS;1xSDv>V0CEfy;!Mj9K)u48De+8Gp%S2K=e)N@V!UbFgZxcy1@fNrY zJ>-QxkZ>6bxC}kyMb%(UxcH+@gC6ptsuttd*DK~Nav5vFWh~$_c%?{JD-&-WO?)1; z$z`kwm$87$&_iCV*Th@kGW3uaRTFQ4%g{q!R871EE<+D_Q8n=vxC}ky1=WPhSioiI zAup;X-U64QhrFnocne&H9`d4UvL*zVp@+Pvns^Ibh92^wYO*E-m!XHesG4{ST!tR< zqH5wTa2a~Yi>isYz-8zmFRCWq0+*ra8mJ~*#sV%w4|!2F@fNrYJ>*5z#9QDp^pF=- z6K{db&_iBSO}qszLl1dTHSrd>3_avU)x=xiGW3uaRTFQ4%g{q!R871EE<+D_Q8n=v zxC}ky1=WPhSiogWV4^6>woESa1C_uaR5?Tb!& zf<`04{gO=W>fJ?I|JGfO+c_V-=padL$OqCDDJ9iL^!MBI8>_EUAn4jVpH{@SgJM@cU9HIrs_knRBb5k zs;Y@i)rVrK+ECn7_2W>DLp~Hs)rR7(D!hf`P^l)~@^}Q5mEQ8>&~91bEgXlctckad zCbrh1xBNJ?TUK}r$Dw-jBk`6WhicaFp;)SkxBNI%s`Qp0hjwcK-okOH%9?n~k3&^f zddrVPn`QOmP^r>eejM6Wg|~1Vsv1bVbu{t0zv4Jls>!_N$DyhL&Rc#Q+N}Y23&){) zqvjC0cHZ*iP?Z()*6zol-Lhid!f~j|nt02PL$xAOURmqJ``lk~9ICPg^H!aBn=00XyB~*k%L;GdI8Y{Q zQ`bvPhtQSYsuOQ3E4}5%q202&w{%2qpAaf*;H^6GK9yBR&hjG7tH0#N-c z3x-nglYL|zBkV^v2PNu;f}bR6e(H+){srtLQQN-gin^WPrpK&Oo2I&Ts@6R%s}T60 zI#r$Dk5DJkvp@f{x$#F#=eZclH1^q2DWq18qo04YYfIH;OR4%wRH`;xHdTFhQmQ^% zO4Yvdx~i(%`-YIJ&z4d(b9YtE+*0+Gs8r3}T~%|pRDHITs@eObdhRuk3Aa{D^$q*+ zPF+qob(A#W_WkM9&DYO=`~BPg8P)Cw(0U%mSK)dm(N+qFaXSGuY;u1M9#6{#Nfe7^?m zs@k|BRUcQRYU4^*)y5U6`nV!hb4*uNe`h_*zi{;er>(-fs{Vz$;s9Ez$7FeRz4|JA z#R0Tb6K{DifP%s4Ee{6h)&RVPU;vf%5W2bs;4K6LNHy`62Lq@E=q-PXu~`Ei3?Nl{ z%Yy;Bs_+(q0aOEtw~i)0y8yueQcb*dG_k4DTOJJ1tpRuo!2o*QHu2Wc#OJai7(l9t zw~i(@ReH;V0lGB+Zy^{!Wj%zh^_IWIs3d>RTOJJ1EUO0tNR{65V1TYF<}Hvgs)1zQ z0turhSZ%LQs)@IbCbmAndCN(dZVl+~OqJep5~iyPZy^{!Z#*a7^0yfEm;={@PQrA{ z3U478KxIwVg#N9mvT{x6-&RhPi*;U27 zg>OyOK;o^ViO(*;x29B+c?%@WieLb}J(jEqk0!RV`p&FW6K{cpSwX@`HJP_S!srQB zjD$|Ybo&72Es!uO>ml@0^VWH1;4c7W`;+umInd{d_p#@84o+MpX=9I9jwEg1Ic-~i z;C%@tK%YzLqmCr4X1bC->R1y>(uSO-q~AOB@kWyN4ce8ox!eaEN!mo-m9)XeXK_i| zNYjel~kMF4+uVg-_F6w>h0(kO?`loqzy3LQkr{ks47hxUb>oYANt2{ zn07VIKR8fTITHgN&3fNLI8K#j;vhdx#bK&66ASs#4^Mt(Kly3ar=R@r;Ai%OpRT5v zi03}DpZjz*%|$%+nS(>r+tCkEafEtXG0^wZRJWYwBOIVgGx3ohpyK#cn#nxmw@G>A zQvuM||90~cZj!2;iI4myDejR4T34N_?)vytB* z#r@IS3Vpu1-TnS3ZjVYcnUDPTDDI9*Gx3q%9mUO2X(m4Mo1?flD$Qg*@_VDWH7d=- zM}BJ*cSfa|_{i^!;>M^n6Ce4FQQQ}mX5u5iFN)iu(oB5hw?%PR^mg{UqRqL(?~3B4 zs5BEF`9U3y>7<$X$dBo8NGHw2M}A8bM|9FmeB^gTaX=@{#7BNWhvPYECO-1}p*WnA zX5u5i9g3qlX(m4MyP-IklV;*0zZr^qp|`Ui%Qb!E_d;qksrn3AWoWzkB){t{dR6L_%U3w zfBG>T4&hYJ#7BMzhivZK*^l75;8805f0u|&csK4@P=bIX(m4M3+Om>lV;*0KXk*9n>3U8$dBBR#4XLl zM@Pe++MU~Ve%#h<_oHD?n)Hz$wskelM>uM`o&Bh-tEq;)FDDM#q?!205880dCe36% za-18KMANi*@$(XjX4#F3gb6Ce5Ia$GH!X5u5i zT8@k5(oB5hIor5aF3rS8eytpr%B7k3$S;-SO1U%>9~}*QYIn>>6~6qFJ~|(ze)HPddsoz!NKB-bsEzGiQ5)MQJQOZb z8{E61_OZb{YKbO}axQ>z)Dle`h5OgIel1ZO-xIa?}qMa@x6qL%2P^M3u+6?I1u5?CD)=!&|daPe9tO&o=b*Te)?#{^C# zJx`mzdH3SQ-JfsX{P6VI-Rt%QIZSwHLKvBik-BPNBhO*(kIs-%wR#$akx|tus;g>4 zk5ql5LuIwGr>kmXk5qj+m#PguC)IQPkAE85wLaFXQ}>1+nZY$~{%LgjHy_5er0R31 z_CBoErD~S%s_O5otUim5n|~g4Rn7CN0pDnls+qp4YNj8V!6nt}d$a1*db3o$H%s;U z-Yiw?%~JK=EY;&jzaRFxHDJA2s@|KW`cQBFP|xxYC8;`PCsmtEn`QM+C8_%IRH`Y|r6e?@tt)q$0V-{u#sUF3<)?1#zr5b>@kipff0c3DV72ZMyS65X{Y&8IHA%m-{ z3U48UOZ6If3mIIh0nA&-;OdrDe`hs7Z+Qk+R~6pE=ij({23J?r=PhP%Ni~?akij)F zgG;J`w~)alRm@w+;Of?Z&s)skQdxs}3mIH0E4}64fX%Y{H=tDME&mAYs=BwB!KE5V zyyahkDl5I^pMl-7>hDh8Vg{G?+3Y*8tLolj2A5QWc?%g_dSjgPmVXI$%j)wMGq_aN z#9RI;sIt;q{w>%oE4&40TxCtX<!?sgq#^%Qcb)Ch+HvJSigF5 zP`6&;Er8@IYvL_{=qjyy?Zy^y% zs>zzr6QRZhNV-%LZ#j}KRjvsgO7GSH)`UoeQdtk7YuALH2&J-eP3T~Hv#buLOO@Vo zG`*{eH6h@1)j+Z)bU0mQ<(km(^ln+PCIq0avL@eK4ydcFToXE?-YqMKMCJxh71wj1^plLdUHJ#OEg8TmCkh%Ie;dYBFzu%UHl=NHy`66MW+WE<>ux zyag^}0hb}wW1zlvO$aVy0hb}wVBXq}CO*&H;4-8d?7?qG6Pv1gOR9mlwxfwn)x9Ov zVBXq}CN@>~mQ;f^;dV5!snS~sm$4m9Y^wBD!ewk8(>GrDHrj2%Wo(|*CsqI65~v?| zYeQI{z+H@4PUiPkMBCBCr+U5cZM55j%h(*vR}J{Qr5Z@Q1ujG2E^8q1mc#ifE4`I) z85_8a3%Cr`K;o^ViLJHht%S?iJi$*jKyM{n#&$IExvbzabh9Lwx3&YlF;#ji;W9RG z85eLFDr+!rZ64(}UchBYHJP`-Wn92zNHy^mxQq+945=pG@<2b;0KJuP85_8a3%CrG zHSyNb#MZOuEsynUj;|i;ry8KQ5-wu{mvI4?p$k@tx4>mw5bh_{WZnXoaRHYh)x=vz z6Q5fPT!vH=Z-L9WfXk3-;w^9)7jPL;O}qsz;{q;2s>zxVT*d`lhEx-8A?WV{E<< z6K{dbxPZ%$YBFzm7@%r^Yr=%f*uZ66z-6ec$-L!(fGR7!m2epwxQq+94BZb;<}D8e z953K9q?&jOT*d`lhEx-8fy=mn%aCf~Esq9N4bWQ&m$8A%xPZ%0Src!8%ea8ckZR&B z4+vBZ&|3+Yv4P9DfXh%>6K{D)pvp>bC0xdKH1YYn09?kTT!dhT0he(Bmm$@}Ti`M- z;4-9|c+0~A#|yX&sV3e6mvI4?A=Tu23tYwpT!vH=Z+T>(YJh9Pgv;2#Wn92zsI1AF z&|?EtR;~#XE@K0iaRHa1T#w{?%cBETR;~#XE@K0iaRHa1vL@aFmvI4?A=SiN;4&`Y zGNhV#%OeEG3%CraCf)*C{OE~6q*PO8dK z!8nj`85N0Qs`OUEWmF`JsnS~smr;=@rb=%mT*eMAL-DAr*I?eNNE9n8y_Mu;R3wV2 z(pw3aQIRO7N^d1xMn$5SD!r9(85N0Qs`OUEW$fTGl%aw?kZ>70xD2JFQZ-l;RwT-~ z2FPU$374^h%TP`#%Nnc+D-y-ZN^d1xMn$5SD!r9(89TTPWvH+Qf;C}9qF7n!t%S?i z!DT2c6=hAhjEY3DveH`#m$8G(P+Tg@8hmf<;4+k#O4Y<$;4&1LO4VR5V+WU^#8j## z-U64Q$W*E(^A@;_m0ZS%2}0M#*lCs6^UZ1^j5-U?BFt#p@ROJa2XYeVr8Yb5-y`6QB0NIO1O-QL@`y) zTM3u3gUeXSWef?IQIRNCR(dPpGAa_qR5@=YT*eMALm4XQSqYc1gUeXSWef?Iv4hK4 z$z==)m$8G(SjlA!374^h%UH=}3<;O9gUeXSWef?IQIRO;o<%NWNVtrOL@`ya2@@`( zB2i40-b%QP9bCprE<>T-*PrrMB#M=l-b%QP9bCprE@Mczj2&FYN-kqaxQvQKIoANW zj3MDNc5oRhxr`yEcM;4)Tn z8AHNlR3wU(mEKCYj2&FYN-kqaxQrcK#!4<@NVtrOL^;<0xr`yEcM;4)Tn8AHNlR3wU(m21L;%hB&xy# zOqF{X371ikD5lE2jD*XmNEB10w-PR62bZA?6?`2hT*eMALm4Vm4Y-VoM6nv6w-PR+ zB2i40-b(T^DiXz1F>j3tm$4%+Lm4VwuVcbx?8wVdh6+^^Zy_&387fpw_TZ71u`(}X zOt_34c^S%3VOg)=gI5@YhR<^!U|z-;a2Zn7@M)^>));UZQdJY1D!erYT!vKD#HI>w zjRBV-RUNaKD!mnO8B$dfn<~8(a2Zndc}p28=ve`mAyuEZl%Yb^>%Apa9bukoKp84j zz5aYls>0e#mEH=t4240sx0Ip6vR;3_B~|y9GE}H~{k$br_m(nLsCxa`u~gk#%21)| z^*o_e-CN2~foi~INY%Zi3>B(gzb2F_yhSc!47d!b!dv7r#vm_4s_+)Mj4|LcqzZ45 z%NT>a4240!Tg=NC11>|V@D}qj#(>L^D!fH5V+`^#qzZ2_FJlb245`9f!dv7r#vm_4s_+)Mj4{Z|kSe@IE@KSxG86^@Z;{IwgS-r> z!dv7r#(>L^D!fH5V+^#%NPSLL#pr=xr{O3GNcM`F)w2bxD2VnTjVmvfXk37 zyv4kXG2k+!3U86i7y~Xts_+)`GRA<*P{ahh#k`C$;4-8NZ!s@JFZEu%^CVSxi(H0Y zK222NE#_tDCCNk;-eO*c-q1@_;Vp6*dOa*rg}2CM=tZtX72YD3p?7E!Rd|bBhTfk@ zRN*ah8G0okPz9Hv3>B>411>`m6Yv(f45ck6Wreqxm!X{5L>1m*UWO836IFPNT!yj* z6IFPNc^OJodqDO4g8M%_{r$~9y?XKD)gSL(e|GZ^Uk|sR4_~$4bf0Hm>&*JZu|6{^ zB*wFTdwcih$rnF9`PHw#{^ggyc=Cnj8(-{5)<4oE zYn`SoYrRIY{*^9S>osjz>o$`0&veOJw`t2-zmcqer_TxsdZ=zcX%kyVQ!)I*Ud6DE z*8X)iiqHBmLeKFPQd`!Bamo6&nM!NJcw5%Samo6=nPhDoZ_C<1E?M6=ldKKoU0Gix zNtUkkRZ?5lhH}Z$mA*`B%fgjdC#e!5S9-9RN=sMzLaAL^xDqR+SrJ1Ix$;9Jo+GR( zEnVhIrFLoIGOU$UT3ai%W#KX`mLwaw%qiAcA4wP!e6`drEnJ4>l1dx7%-2gQEnVj8 zrEY0`!6aF_%oj{;S-1= z%RsZLw2{jkXPx!61Uop++Ab~TGVrV_Z8VoT(5ljME_0x@TUt*VlPq24L~C0Xa~Yz> zR0+`v)3e4@TCOmiX>FGlD@=rqskG4w)2UXKmMcuBTHB??iV<;RvvP+L^E%f$>$3@V zaIUpoTFhktTUFX5}DlJ{+pliFda2ZI~`QoH&TNZN}P*=%DbD3w5%_CS>$v)_^Pr0|_p=BxtSC|gR zwkr)QOr)0S*F`H#e@;%N3nQk7As5uvZ{m!SD2r&i9P8|zm6+X zCu-Zj4l7bbo$1#_D^kxoQ)#gxRp?PNS2|QHS@539n;0ut zV7MwqG`Bj3JCERSB^$ZeL0rkg#j6LToh$7F8)%D@xRQm7S0{1XvT*T^xpj3E_bhvE z;;-(WzJC7lx1Zg7J%9P%|9k&{WpQX%KMVF<9ont%qmLi3EKco87L)Mm)NWfAlkiUa zI=0)E#U#AbzRvBoW!=8wSp9=?b#S*W>vj~vM_ISyv4H3_nNO;smniFY?8^F5SKtO^ zeW}}&b$D0jgtVhScGs<2r*|bwJ9?^GTh^Dl3U6m6_)@o92|h_G4V$t)Np@x3Ws2;D zY>h(i9~5m@g1bx^sFXd*cfBlJ284H3#!@5;mx1Ax?1L^l56u6`1MtP6UmaZ2l@9%$ z=Z6o?W={P|macT_w<~-6-94x;S-R4(-?pqehRM>E&i%G!;YxtNYGQZgu{3N9q)z^- z66i`Nf7_*nD}nybtE0bdS-2AHuVmeo-AaHf0sl(YUD=g|D?$HC)?Im${gkeBTzH;< z3#%ADSDuRTAy+ytELpnJdEsso1EQG-(J0Z$M#yGq0nto^Xx0d#SsWQwC2+2M7^3-v zO*}id`-r9dN=(%wmQs~~*+xVD(MLmOSF zTKodJWO;7#@P(=m?FwQiYT^YcMSKS%-r`rt=ZP1jl<^(OVuzL&q!jY~knE@2zI(({ zWVgR*EM@Ur0d-&=jYW6n77rGXEH~k!J97)}%uT#Aw?=p77LOKCX|XxEMw^ohHYX=; zPAdHUui)YZckCwKv0I}%cFWN*&gY4|W2d0!L`eY*DlxS+U4S}hs+bNU9Qo!%LV(} z6R%ya(Y4D3*DfbsyIiAdm&@UOb1`<_^pe0|!^PMSpLk7kjjm}f{^W?7m@De&n&yIQ zniH>S>hXbxD(yq#KlZ~X?uW0@HO&RrG$&ru)bj%mmG(SP|Kp3hKRkW=>h;Zku%b6# zy?FKPcQ;?X`tHv+U;pEOoB!_17cXvp^Yr!GH=o^n^Zl#WZ*RW&;pwxx*Khv*3Y_%l zZRhUDyPqrWejc9~4WtHlKPPUouekf!l*Qf8iFZF&-2Lpzs`pqWa7~80pIuq~oypSb z*ktd@s`r>IKZbGlvnz`=7Vm!QX#?xEU0L8ty!*Lgll>%nHp71w%fnsKiFZZy7=rz} z-r4HnkD$yG?~1O`UC{-1MJL`B)pH0@X?;_E;->r>-4$JMS9IcC(KWg&y5O$p#Ji$v zbXRma8v1M>Zp!OPgrsh9S9IcCQN4)}$-P0a0|}8V_7`~f zQ!gY$vRGmA?&lia{akSObK>34HM;w`;O^(dyPs=x_jB>bQRazvKi9v?-OmM^>=W;P zuF>7k<>(k^v-9rf8r}U|aQAcK-A_HNkaS3FvQNDGsh1TZS-6sSKlQZ2L$aT8q5Jq@ zukE@2yFct7?|v%YbDr17yProT_@sIaJ&pYpf3`)}9(j~@yyACH~hBr4)NV ze+)l9Zr_mA`9B+e{8!mj_h<0tiTN8F@;8o!VPnuo{>H@o4LyiuBS=>k`xVUJ(2H1s z>;?H76Z1FpBvvGgy?W+v=uNChR+V+0q8O{8N3kMVd>JuTL$6{*ve>U+tj30=Rj(&p z{5d@JTcEldVl}$5{$(^XR%1h~MpxGND`v)OY*<=#WqrS5=F)1z(yA-#E}OZu+OV{0 z$|6={=F)0ItVUPXT{bgTV?(S)S5|*_a@ovSjqONJIIV%YvhK2(OREh_tCQ>}{Pdn5 z!_y9g5o;iBpk1O3v>6*{BR9~R;c0)3>HmTy`OGExh9&u_JAQyxxcGyL^UNjrR-a?{ zEB&r4MrX#cY=~p&%3^e89Lt6{maZ&DXU3~+h*#;#VsvJ_%7%EArtHzs=kbp5DjVWe zy0RFZ@vP#!Azq~`tG~0-f>+oOuhNyp=*)PP4e=^nSziOqj91wZuhNzE58s*bDjVWe zy0UN?<5f1qt8``IGRCWHh*#;#!exw0*$|h~m4(X~m$D%)r74TJ6s7okc)*6Zl&&mX z#<-LXaVcF{{oUDRj7!-Nm(rDm%lO&7;fhRG7B1rznGIKDy0UN?ugGk;BGZ+H%Xmd* z!xfpXEL_GbG8?YQbYexH^A&oS-|WwVfGC$dsh~78DaJfFnd>4e|L5n z-w@gWvv+0TGQ#N_;PkF6Tt+y31DxKKh06%1Z-CRgvTzyU^bK%&R~9ZKoW220@5;hu za&YLz^t;vWO$E$D&M@-(?X;emNT2WN{$5 zMI3oO7G<(HklZ4U{Bkt3$#QS{VUGMmn=0VKXL8{ixbUVOz=hA`!Z&c?U0Jw{T=)hq zyeo^jj9mBzF1#rVE?n<6!o1+ZyRvW@x$q5Kcvn_`ckW>1!Z&c?U0Jw{T=)hqyeo^j zj9mBzF1#xXmyrwKz=d~ZF_)1G-@t`;WigkL3*W$ncV*!+a^V}e@UAReMlO5<7v7Ww z7e12<-@t`;W#KY%;TyQ{uB`s<>@srU8@TYUEL=t|d;=HWm4(a5g>T@(yRvW@x$q5K zcvluKBNx7b3-8LpW#qy)aN%89xQtx*1}?lS3zv}#-@t`8WpS)E^H^)cu~t_WF5|J* z1}?lStG_$DjGXrd&buoMmyz?{zyIEL=v;dk5#;m4(a5dGFx7yRvW@ znV~&mhAv=+W->#2#0=GAPUj9rW@wL?p?b{8WU*r0BW9=`b23?cm+cWVRF65CEWXS3 zh#9KKnM@YnWqZU7)#FSii|?{MVutE*CX>Z?*&Z=N^*GZ>RJ%V zJz|FH%_Wlsj=e|BP`$Zive^CDBW9?$dy}QhB4%jCQ#=cqp*>=T>dhr9EnOBdL&e>j zEM4|6GxUM|gca<^LiS^i*pC(L$3pgFkJyj(Xy|h#kp0*r_G3L7+GOdni2Ydcw9Z2I zV~^O66;JCdWIy(Z{aC?%EM!0Si2YcPhPJxpTo$n(_2!bv(q$3*QEx7pEL|3{AM4T3 zCd;`jVn5cSp-q-^S;T&`GkZL)M(#D3HpN+!#>EMh-aJe9MM{n#V+ zqux-m(sC|~*pGTc$z=FA>Zz7p2T^6w)E3z>4h!WPf5&N-%{ZMc&Wi`ZIO;fC3KNOrxSq*W4 zEaoz@A3L%zd!N#kgKJGjmqqMH<=~nuT^6w)E3z$>l8U;G*pC(2mP$#btSUcfGR$RU zKlX_IsL<1M-ID#-Ble?0PfeCCi`b6}F*RAbEMh+@#METzvWWet5L1)oTo$n(6=G_# zbXmlHREVj`(q$3*QHhl%OP59LMbKN9;!>R+=p5vWWet#7dK; z%Odup5-3fUE{oWY6&Zqxti-?=u^*K{X{DvhBKD&aC{30wi`b7!pfp*!EMh+@EYf7@ zvWWetut<}o%Odup!XnSIWIy(Z{aC?%EM!0Si2YcR3Am8`*dz91#X~&{*^fP9KPoKJ z>Xt5x*pCW}G+DYVVm~VU(PZhei2bPWN0X(?BKD)gA5E4ni`b6}e>7RTEMh+@{P8SH z_G6FOj|zV@SNlon}=e91<;A4fx9UCZsDKxfrOP7rqXJ$` zmM)9fj|zA(S-LD@KPuqGWa+Yq{iuK!ljVvrVm~V2#boKSi2bO5m$NL`kL5OEKPuqG zWa+Yq{iuK!lcmcd_M-w`OqMQ-*pCW$F`DjeJ(B74*}oNiV^RcUci1xHrf5CfEOz*T^6w)74TxRbXmlHRKSbL(q$3* zQ2{R|OP59LM+Ll?EL|3{9~JOovUFL*epJAV$_-K>oMpj&EVmK+ zQ2{R|%egFKKPuqGWa+Yq{iuK!lcmcd_M-w`OqMQ-*pCW$F$D<{@-{E_{;xgiXBQg5<;tl67zHr;G7{JFN>YNKU*US@-6ym&FCii5Dd6 z-drH-mr5pvW7oa8K-N3tG)u=->m71pICkBe3uL`RP7KGcdvk%TUyz&_j$QZW z0$JZ!n6ODc*S)zw)-Om-49Bi}b3ZNn30*nkHK38n9u@fT)5Z9JD`zBojG#N_3VaA; zeYP4wcSzP}tJ6^Sfzk?GuQQVUt1eNN(gRoUlD8Szqj(WItgO zS2)|Li7&|P(iHDR*{K*G_;nS|c9sRVDcPjbDxA$^`5g*wvs+px$}Y(4QfYmK+?Dk) z=Yq^G$tGh?g|k^DaK#I5^HkbT*mD*{j852UnCtez^>)Kn!-TB{$v)_d4|K={TMZMo z8YG)E@q%k66R(-n?Stzp0TH7UBS!1?K_KhX%7m>3Rl#3t6^fqXx%;t>K3yPBS!1?K_H9S2U`tu-989pv4+G}gJdI@VXI-n zR)b_Cmtm`6!d8Q1lYw+W#OTC`(Yk$becc{=N~iI8V#H|OJ_uy-rN)TSx_uDH!e!Vx zP~Ao@I~v+5!8i2gx_uCo7B0hbMY73qWjXeU&ZWh2MY73qWx>mN6C+0J_CZhyzFe8G zTv2HwmmLjlmEhavl8s!3h|!4=qwB-Vl@HAhM?+g_`H6&UCZ|c~6Rv_Dw;#V4=gOl# zwZ-4q_T%CG)32MDI=kZL(W$3>umfY@W$NsTn@3$)47^O8tqUpFk2$z`G~wpaTo+OT zSq!|mc_i5f2i{NUVujOq6En7`(rm8(b%-sR7+X|nHrLA{wrFB((F$~}*>mt@)x_AM zO0x+{3;XcNs!Fr@Y1vQO#IPG5lBw${1ELM;z?eVkk8HH{o_>^|R>84~=`GG8~i_=ZX`ltJ;wC7>; zn^(_%clY+@+jno@zIu7{{oT{=Zk|2;;pWY=*LQ!s`Pp#$`83}A>E`z5+IxEP*^?h$ zKmYynx6l7@_vXnL|N7&Tr*GfBey;!5<3E3V@~dBe{mUXf@mnmEe8Vh4Q0-Y$MCvRhJj6h2`k znmEe8U2XZ7DOh&?$UDU6INHmy?^flz7zKbK##8F4U(7jEk zTSsvunmEc|9GdXpkVJ#YNUzFxN$Dt$oN3zhXx;PAr=vV@rYmZWnh-am8%)9SZt<6f zCOkAG(Zo^y!8GxMsa~JC+WY>&H1UI}-k!N$)E&hSCJ^+ehB{B17m=F(G7rPeSFc~a z{P#P3e!lts`ODw7zcA++58RAcy3ZG1x*z@gqo0^kwb61Ov38fLHEvhchRb=x;$5mX zUUpUWclVBwst=e_wE?rMYRxNEA2FqBBW73CMog*tkSSFgGEb`KUh|uGFJ9dJ`R2_J zPoLerZugaGKTyv5nwmt-*uA)U@ZGKB2Y$4#NYw`yK{Kv8`sP+w)q0@H>J#=n`rcMo z)q3D0WQJw69(Ync*Z)^{PhVf-(rI@PM85{@J~#+cA$y&w_qkFmnE#x?L6Ekr%x(R| z7oh4VN5{PXazAE|PHBC<6br`E%5y(0`&j!gzkB}d*j}9f57+*#zB_(7EZe^g+vnTO zH*cRlfBE9>%^Ur%ySo=R-+ce--HY$;Uf+CkY@A**HmOUU`y6(M<#!v!kDk)$ayE*~ z?-<2L-yH6$+9)nnxOwzX$(HI|`L$L9F!Si&l3i7J86T6XSMzdL6;|G1<VVemz_4G`;2Lam^a=^Ejz;-tq&vt}48R6FJpD;;rMn)#{br@*}x! zS$*D8vMqa7;w}HOSH03({$<}SE4;-o`_aGbyQ-MC_+>x(mwi_i-r|@2=wJ3-RsG$$ z5Ae%=^e_9aD&{SI*^mBZ-&FOJIbBPjxBO_Xs|s(8oVWaJuB!@fjr5iu&UIDcEkdTF zpU!nveNCu1TR7H_=enx!7S89iSC`CNem*xT%$8+M=B=ZN&n_TfI(lMhw+8fgrph&; z2bOkK;VnYnqvw@2Rh{`(z0zCGe0NphEh68er@Bj`qsNqXRpG6f zYeGk{o2pJ?>w+4+YTRsC7o zNujk^4|p_bR~6n`=q*ns?W)3C3)h4mOxjh2w-$QKb4k0Z@YX_ac`RvH72ZNB={$NW zX;&5AVp7QHp`=|^c#Asi7LEBwrO&O-3U86im;x?iuG^Vs zZ;{Io_M6lzyhScU-0$_ObvM(>3U5sbmr++UO%>jn5-y`|W|}I#w}k#CH2`ms%MkmU zsKQ(1G6er7s_+)M4AH-ds(WiEm!SadMAf~ulgm(kcA}~#KJ|f}T!!Ma6IJ)tPA)^~ z*?}s!jGbIYU7)>|bwSP+#*}awx)}>q>=RB2mob3L*vVx~ z374U}u_!COm2epYxQv~d`BTDW=yoj1ihaV#?@Bj&7PyR^T*j1e8H3-rn09g*Q^I8o zM-!jt0&*Es!etD8U3%KdWhj*^7zg~mv{bPNuTZW;72YD3p-iqo6Vz+C0xef5qVPOnlRxq25=cWxr`~{G6oOGQ&~B0C0xdEH1XM6C<4R>EZrM-!VWy_Iko!_mZNRdN}6$RU^ujwUu$dMn{Fbj=K^ z^j5-U3`Y}NS?R5W%NW3A?Bp`^h(l1XM-y9F>8*sz7>*`3RnA)pmoXeoY^wBD!etCc z6Pqf%m2eq@zZN^~EZrM-!hN zOD;oqS&}}0d5c_zZbu}l@D{lYQPGJiyhScUL~No8Z;{Io3mB+^%h<_fh=NK~F>jH} z5dV>=V%{Q`p)=}474sIk3`O%Ns+hOPWlRZ|F&s^N_7=Ge?Hnd$g}2CMXeTC7g}2CM z=xZ@ig}2CM==&p4g}2CMXoV1{g3H*+WoX1rRN*ah8B@Y#3?8Yh%o5I9370V-b7m)( zq5PPn2H-7n8M>XGsKQ(1GUkNKs0@~~W65RA371h3ET)R@tvTT`hNFp172jKP!evyf zkg4K(YfiX~iWM?da2a#LWmK$?sbWnyCtSwp;fw0?@YbAg85N0QWyP9MoXzzvs7Mr3 z#hP$VxQvQKF;(nkCimB3DNnS=pqL?bZm2epqiDIhsR>EbBo|mCMKyM{n#^`w&Ql+;NE@Sj0Myb+U z371ikDCc@5m!SxTz_Fgis2P>sO1KQA9-ikdsnS~sm!Z@{sM1>rm!Z@{sM1>rm!Z@{ zsM1>rm!Z@{sM1>rmr;=@*0boXgv+Q%6jPEaeB#NohTM3s@ zktn80ZzWttMWUE0y_Iko6^UZ1^j5-UjGmXF?;v_B;W9?&GNj6RE8#Lm=Q5;9ZzWtt zMWUSRm0ZT0a2ca>87eEim2epqiDG4?w-PR6bS^_>rMD6;qasnPtn^mGWsJ^csI2r> z!evw>ij|e#O1O;CxeV8R`S{R>EbB&Shv% zjNVGPjM2FasdC;*xQvQKIoB)mGUkNK7@f;dS?R5W%NU)@kSe{Ea2ca>8B(RU5-y`6 zQLJ9+t%S=Moy$;J>8*sz7@fEbBM-!i0i(JN> za2ey##HPx5E8#N6qlrzG-b%QP(YXxOE4`I)85N0QWu>97gv+Q%6jPimB3D371ikD5gqpC0s^DqL?bZm2epqiDIhsR>EaeB#NohTM3s@ zktkimB3D374VQ z4}E+kmr<`JUVBHnB2lcY^j5-UR3wV2!dvxT;`L=UE<UKMLX=4C7imr;=@=hk9g#*%Ou6^UZ1@K(K=cx??-B#NoRTlH+>^{Vg| zxr}-@@p@I`2}NPRTlH|_^{U1^9T_UlI_RbI>(65=62m}371ikC{|W_E8#LK62(-p zCR`FOqasmEmEKCYjEY1tReCGoGAa_qROzjR%cw|{vnsiaCE+qAa2d)_fnyUcV*;0< z3>B&dtZqf3SPjry371ikD5gqpC0s^DqL?bZm2epqiDIhsR>EaeB#NohTM3s@ktn80 zZzWttMWUE0y_Iko6^U|IC6}=zT*l;i8DbLYt%S>{NE9n8y_Iko6^UZ1^j5-UR3wV2 z(pw3aQIRO7N^d1xMn$5SD!r9(85N0Qs`OUEWmF`JsnS~smr;=@rb=%mTt-EroK?wX zED4t}fy+>a3TBvu%h0RL_RXyf6{;rl*3raP1N2tHWmF`JsnS~smr;=@rb=%mTt-Er zm@2)Ma2XYeVyg63!evw>imB3D371ikD5gqpC0s^DqMTL9Wh@DoQIRO7N^d1x#^iY! zvociRt%S>{NE9n8y_Ikoljmiqtn^mGWlWxzAys-S;W8=`#cF`wO1O-QL@`x*E8#LG z&&yB^&|3+YF@eiah6;LC!evw>%DD!}Wh@DoF@eiah6>9X+>NYA6e}yem2epoxC~{e zu&lw|$O&AAGE}G<+>M;TWhg_1s=>YEibSz`rMD6;V*-~kkjq#SE@J|hp$rw&K*D8A z;4+ky=!_l5iOlxQu~Z#*%Ou6SxdzsIUf-H6geRWvEa!@fNrYWvEa! z@s{Uh%*s%qYT_-=%aAI)m2epqiDEsA^H#!TR3wV2(pw3aQIRO7N^d1xMn$5WRmo*6 z370V)=#8mz-b%QP>1bk8rMD6;V>+7HROzjR%g`g&P^GsLE~6q*tgQ4_!evw>imB3D z371ikD5gqpC0s^DqL?bZm2epqiDIhsR>EaeB+6NpT*i`c85N0Qs`OUEWmF`JsnS~s zmr;=@rb=%mTt-Erm@2)Ma2XYeVyg63!evw>imB3DNnS=pqL?bZm2epqiDIho)+Ncy zs7Mr3g|{wAUPeWtoK?wXT#~$uibOG0cdfql9y4DC{|W@>yqSU=;9{I3U6JKybN8ff-1aqN%Ar(62)qO-b%O(f$u0Qy_Iko z6^U{xt1?u41%FBMGAa_qROzjR%cw{cQ^mY>Nw|!PL@`x*E6K~KNEB10w-PR+B2i40 z-b%QPibOG0dMn{FX5?ikLxnv{i}7oD7i|oh3zVS()r8BKk(Z$i6{-e%8TxSbvXaZV zBwWS}E<+hAENie&ID^Yjh6+`Ky^I-o8Ol(hYOt3vBQHZ4DpU>jGG^puC_{y+!Cpp1 zqMW_OcT6q`mofW0CMr6;^&pq=KmXTfKR$W+^!Im9zIbxcsph|EOu6~$^{bcves}Zj zyEorIfBD-dpFR2E_4D69fBXCocW<72@vlEVdHVM4>*wFTdwcxnk57K}>#u+L9e-RpCaG92X}!x~lrSbNiCyP#vE~ zxvr|OB9*$r8Zb9@RekqEsVh`9H=b0_y=J)md>U_l_2(C_UVi@1FW=m~etYwaSI>U; z^4;5Z$GKfR>_eQ9mE?AHrsSx?kMD#;4&!4_{ z@yCt>xR)`Tq9Vh9En!!aFQPgJJuBiE2fDuIv zFz$+~bx(B)mgIJImZU3c?iOCelA5`@qGoQ`X=fj5|UCBw+R~;+UoGa@0dR1@ImA3{f>i2q8 zZ_|~#(-rmmld9+X|K{z}-`?H)r4`<^>t8U7El~8Zowxq5dYa2IVSTjzrD`h_srrB_ zRU1&dseP@_eMpt64XIsKTlP!U$5g4>nA%mfb-z@7nIcsiRJ*F? zL8(o%Utne0I z*-=>&Z#gxjveH{l4K>T^)R0u^EvJS~s*4y3NoA2+Qes}Zi=?^z=p1r>NbfeO;JVY#bm zT?fbZ(zK4#)l{S1*C)ahq-o2Yo+iQ+cJDOOw8c(WQ-60Vr!RG+X~S_>)0R4jQIMuB zbh?^07$ZbMnukZ;55-+gTjn4_LE(rNq0rSdAML)xk>(+DbveyP%ukSLU?k)x40zT; zqJfhTpD^6|w}V6jD5>3o>wC=r`hFiMHkLa5{>S*1wsIP5Q z(!@@FLOvzX*`{DpRDD^kf%g!4Kk{}}Z8VpvkLOag-q%&N@qAtZUP;vk^scI{jHK$z zYN^_Y-c_}=kyL$1m#PivT~+tiiZNZPiMM=AS6O|9B-O-QKB!BT-ttksSpz<*OO@X8 zVZE#B-dZuPs|FHp`M9pK(px^TcgyPDS~0R~Rg-uN;MEH7N~(#s0A8&CucVrI3*glX z@JgzQw*X$P0I#H)cnjdw3h+v*iMIe=tpKm2n#@~xsAvUvCDml!0(i9oypn3-EnrkD zFe)v>4?A5uZ{eY$6&RIN6K~<6q7@jGR1RQ@5<}7FZ^2${a%1&Ra(lpB)RB zNvesr@KDhTnn|jOx1460SKv%iO}ynelT`V=<$*Ze*24D|fF_kS@s2+M7ItuJslIaYQiMv71yAZ{eY$ z6AkGT3MP*Ia zghvyfM{S@jQcb*tK%5n5i&T>}Ap&uPGNNZW+S098%v(TPmch}Mt}6Bkfwo9B@fHGc zL^HAm5^o_8M>r!@lQp5EEwhL=swUoYv_-1)mZL4r)M7&3ZkW*y@$u@<5!fD(0<~-ts`4t}48>a!u%g zI9*k&30Hc{197^l@Yc#Tp$Fo0RWWZN5J!j0$-H$m@wpFdoVPp>r(0GnO-z;E@<5!f zD%OM>z2$*8P1U1`t*rEx2jX;9;jN9{@<5!fD!he^HKAWQn0e(us>!_NR}Q2K zZ{f;8w+7%XFm<9Kl6lLSx|vrFq?&l^XyS9v0#_&1WZps`&I+!?sE@LH^F$P?Q zo}z-c$YqQHmmyVni(H11F|PiSmnytPE@xsMlNFvxD3^+dut1m5moWxhhH3!bB9}1+T!t8WpSL!08Dqd@NEO~9moWxhhE(A#av5X5 zWk?m?B9}1+T!vKPEpi!Sz-34k-XfPV23&?z;Vp6*W58ud72YD3F$P?QRN*ah8Dqd@ zNEO~9moWxhhVGKUTjVmvfXk37yhSc!47d!b!du9dS;m0NkSe@IE@KS145`9fNS0Z~ zfXk37yhSc!47d!b!dv7r#(>L^D!fH5V+^L^D!fH5V+^L^D!fH5V+^dTNi(JMSa2ZmCx5#CT0hb|Fc#B-d7;qUvD7P*Wu;4-8NZ;{Iw11>|V z@D{m@G2k+!3U6)TGRA<*kSe@IE~8>_t|Y6KJt7aDPS3XuTt)@qT(1gmk;@nZE<NEB1W zyfr0UMn$5SDtN*v;W8=`#Z)nGO$nD#ktn80ZzWttMWUE0y_Iko6^UZ1V0EX2%cw{c zQw2{rC0s^DqL?aJ-6`QRDiY!mav4*?WmF`}*<0i?^!!IsR$mkDim7tmO1O-QL@`y)TM3t;++%DE4a%a{@_ zqasmEmEKCYjEY1tReCGoGAa_qROzjR%cw{cQ>C{OE@J?fv6IWtn-EFQ!n{Q;LvKPP zs_+)M47~}FsKQ(1GV~@ypb9QyCzqi&Are)r3CU&XO^8GlYeI4vdJ`g1#hQ>@hTeoo zRIw%`m!UTy5>>1T$z@Clmob3L*vVx~370W|%h<_f=uL>E2H-7n8F~{UQH8h2WlRZ| zQIRO;k&s-5-h>Fs3NB+OmoX(=Mn$4nSvhYdT*d${V<(p}C0xb;E@LN`F(q6^MWR>@ zaNbI|i~(H6PA+3gxQvQKIhU1OhTeoodKSDzE<4RBe|q)e#j8Kwz5eXxAHLRmV8d5eynBKf>B1SQFtYpBt+ULJKYX$Q z6}%7?ERHOY^?iy9=cEG30$JavxDXaBk}Qz*or()*r9#PmTJ{q*@r;YDy3cMv#eDGt zlx7ppxY?=;?Uc2hsJ5&(v2L_e*0!SBvfjkH(oR_$8{4wp#JbZCSwBQM%buI~A79-4 z;py8~uW!E6(?!o;{`Tgp7kcjR=BroV{rTqWfBbLr-+lSw#m#S?zJB}Wvzu?efA#w9 z%{TRa^P9i#TYbSWrqzp=Rrw$1fxJ+Fk6V2KU#8^?W$oLxE$bh*TE9@%Hf5W#7Z7Gz zz);q9j@q)mOwbC3vTlZBOa0?@djVsnB@AWV3|(0_gVr#Vbu)Bj-3(g9K-MX~e%WomLB4$WS(M+2u%iGFiIJ zQL}C(AOlEC8J0G38A5<&gaFN(!)EQ$s-dkC=rX6x+OqDl88JXA?Sn2m&kg^{72XU6 zTvtE5E%bPr_48vj|M8(|#>a;4eo)qbU02q}5MBOoSv{W?mDa})-Tt7gk0IUC`WT|? zAC&bm`7fPNl4avZCBPOi3=tP$$GEt%6hN8;B!v0-fO$EzRQdxs%;~koh69!h4_N9} zWFYGu^1>6ATR&lGSAuuQ3y)ZC{fMP2i!+uB&sgeWFIyq%&eYQH;=TkN@ZvW`g zpBF>VW+uN5v8=lFN7-ngKKygqLD027%0>ee{X^aQC7^a`VISNAQfVKw&j*{#7kj$>$I|*@ z?|+jkk&CBm7bu4F*WF4(FrMyRP&RTU2y9)vplswyMC0k^1!W^wA{$RvFDU!qKHVoA zcpn$u$F|7d^ul`qIV)fuJV7-8@UYBlK6Sb zMlJ(MD}bJ|k;`!4F@aiAPl#LwmUaTQbUZ?pe0gEFM+`kGA=>R(u-hYup0bh4u-hYw zp0bh4z|#t&r)=ah0JRf#d(>o+%dp!sVYf%Jk;`y|A(Ebz@Sw}i3*EoQam(e%?>T)c z&v)J2PJ0k*x3C9DVrX2N)MTyE7x+MY3*&uB_VQTnWf`k*u4cE9+aI zGq-p)Z1Hqued}}P7SHAhFU=FO%hAwQ37B#=k9cXz`d<9ZEuPIYUfQy%EGsRhoDEw% z&AP=F&y188^#q@Cy0UN?w|F*e@pNT1>RBaV%Gt2R)0Nezcb4TA&xS3Yt}I-}Egn6^ zVe@WR7A`~7%e;BiOS^-?WypGwtWP=3(t=f<$trJPmAkTV8Cm7c(_XrjfMjiaRay5mBm~}Zc*=aBrZb^%uH@^1Gm^M zE#@)=!OVK8BPuOih9nrtMspdS=$R1(BiU#!Ll%rkS*#O03#MxaJkm4cksg&cn#+&| zGb0T~ve8_IIG7o6F!SbdFzrf!%kWN*WTUwZ$67OwwKg1UHSK_7t(nJKnHS<_&^H7+!EaoyEYi*ti)0S1!o>z=K*4jK4rY(!P zjK^A==fbpQ@mW+3Gi@A))TAN41v?~F-A3WBo>m5O9;W8d; z>Gh7pWjNLn)dQD#I!w0`aI7`+SgY99>nj1rS~HKeifs*K;W8d;Z5|NQt^~M@$66bX zwVJ~?jcU1K3zzX&t1fH=vTzxXwKhP^-MYn! zk;htfVdMJJ;#f-``s@kOiV??J`o^VfwEF?pSxY&}Mk_|J&RTO(Hd--)b=Ivsm(^QKJTUxk`cUSg@Z{~ae*16y%A6@Ka zlO^9}bx-%a24m2|j=L+pN?37sWoFRAj=L*eS^b@r7B1V5`}bE5HS5vPCJUGC$Nl?2 z7Ar;uE$mUy!g@T}WTnM#luhQc^=N2oGP*1ZT3C;#n@pB2dpKy} z0|Vm<_CxOpq7owZV+H%6JFt|ETn6?-_cSSc429S3pctEk3C{P zR$T8{$bRe*`>}%kSa`i>kJyhD*LxPSAA7`ptj7R)wgVpcQ6NY(mx29Q$bRe*`%(9} zth97l#D1)}-lHH#*dby+)}x`%r6v2ZN9@OXG_=WbE{oWY^=N351#YPKK9VuvXlRq= zTo$n(b&tzrIhRH3$BLY~h3v;3u^)Ah%Sy|+EMh;_qoGZfb6LcGtVcteEL|3{AM4T3 zCQFw^?8l1de)OCw%p0*EE7*^P?8hFlAM4T3=Sm>^p_e}rmmLjlvUFL*eym_W7P23E z#D1(`KNhkdd&GXMM?+gB&}9+(u^tU=vUFL*eym_W7P23D|0C%MU_TbJA9?^JlEqv` z_G6FOkN=OockQ+7IInd7$^!F60W9~P_c`@Va(AbV$QM{a0(1vB*dn(j!W1cxo3Y)- z`R`{`*@v9tfhfLfMCbtN^(7Z$W4Kr~$Ew@&j@rO}EMz~9i2c~Wek^1^j)?u(P&IN#BC~Sjc`H5&N;B^mHNnp=Us%*1~0EKlBbrBny|3{Wv1_V*~rKkp0k0AW>^E zmy!KABKBiLX4OLW#`G=A0hh77T`WAB;*^eV)KYBQswU#T! zi2dl{WG2hgkBI%~;bbPuxh!HodN`TMaxRP5j}7d{LiXc`*pICZw6&Hi#)$pczg+V%4fBiWC`p9ZSll7RhK$bRUNkfak((!7xU&?_O4 zELMzUKlDsUBny|3{m?rhkt|$B_CpVaM6z%h*^i?k0oR}8qojEu`*AcRAdrR2$bK9V z`_XIH&vqdDaiFBRb;-voWP9zp$#TVrlIE(c2HIq~VvJH*H?SWncE?UAccbR09xopQH8w(!UkZdxS_19FawZ1Qt zY%-VaZJ_BPO`*6R5cd|(m#vA2OXS-&q+YZI64cw|G* zudua=%XU1nv4Z_jYa^F|{aC?%NH%gA*pC(Lhh!s{f&EzTd@hr0|j6i{0e0wmx29Q!G4HgO6Icun#$Q_U_T@qxeV;b3id;?k;}k-tYAMR z8@UYZhZ12pWRc6jeym_W)Y`~pU_X=y!`4PF1N*Up{ZMNom$iYm4~#C0*pD9YVzP8u z#D4UEm$NL`4WQ8Q6~%?1y9{mx2AzGo_fzBKD&P zyqtf=k^7<6MlJ*Uv4Z^&LLIpb?8gfBL$Z;}ko&QM{g7aHxACiq+hTM-8xgU~^Tn6@I1^cnwMeIipc(E^m`?84r z=m9ThS+E~!ZR9erA1l}o$wn>%`>}%kkZj~KupcYf56MO@1N*Up{g7jAJVF<2HIr(7wzdc ziIQyOGHks^Y`rBLxeQzH5nFG`MlQqFTQ9Do6R`Czx~vWK*=5*z&sujU=Ec@~#MWD~ zk;}049@lB^$X6TkjEDZ^=e3!`6Gm)?2cX%dqtxvGta0;C3Mn-OG-5tqlpwH&T)?2NOT!yXph^@C|BbQ<8 zJ!0!E*~n$sdXLz8OEz*Dw%#MQ-ja=6hOPIAt+!+&mtpHYV(Ts0$Yt1ikJx%kHgXxZ z-Xpf&vmOmk?0~KJh^@C|BbQ<8J!0!E*~n$sdXLz8OEz*Dw%#MQ-ja=6hOPIAt+!+& zmmzXIvF|zDpMcGAF7IPWPE>@IXoMeB>vmKOaj4abwQKoTf#*c(qDTvX>f@K;j$~3C7 z`uRN%G0QYolxY-Y5z#p^qH{%=Mpafnzt&pr<4~q?lKlyXSn$3zV`5pyhO&-RGk#=< z1@A)^F5XbqQI&NUPblk{JMDj}5va<#izk$INH&=(1@C(&psYi(ADkDoSg(sdr< zFCOk+KY#hn&n~~4KmVWq^U2SieE<6Sch4W6|J%cxC!hVVzdX5re0=@<>$i{X|NYC8 zU;pNJzxw>kC;f47x9^C0k$FSCNb9?gpT3Lkv#}iy+86aARayUJMrMWf2+7kYQIQk_sQqSmVO16iL`C)A5b)|a}) zPC&iLgnALl`i8P9tG~0p#iZIJB(LuT)Qe207g1|{Ls@ODyKF+eh-CeTxhm@}n@}$@ z_Xx?L6WnDJ>O~~m+V}qVzS>&24D}+Cja-JT&T~Y(YOPr{y?(cX;oSOY0?n^TkD-xmGz${9T8C0f10YY{?nu*0?PVN zQ&AS{eH{@{)_o2o^&h5*m#RJDERa=aofbnAFI9WQSs)AR@=|rfrD}1=aH%@+Qng2%1+Ddk z=EO_Y4VS8?*8ZfwcfQn{i0Jgd%+tT_^t1aTQ`!PVXCk7rMTm~_Fa66QqSFI2uWv07 zor#D}56lc?@tqUV>4BL)Ec;UqF(&MZ6ZRHO*vfwPvEYQ=!=iuqU-x5Q4)D~8cxn%e z4rH+~C7#;Dq61khOo^xVu;?F_{V9hSsR$EN5wv+uHf(zLz=s&A2$D@UYztBmCZr-r zHd#h5NJW^CiXho!8NDDCVL~c`WRqp|f>eYFsR)uymeC7R5vBpxrv0IWAO0YJ%$0Z% zW8#Y#{h@?F7Oq4pf}X}~)7}p*`hT>wa3xX^B>TZ*k)P6)NKu%OqM&9(u0)E$gcJqI zMy|x>cH-u?Kdf;5SYUHIadX=rRtRJA4BJG8 zZHpMT1q|CnhHZ-&wgn8^M22mP7&ZmOV#s*07cp!LqJt+gY+J;zEp4FBClZVf?uoM3 z+o27#$#O9kF>DL&s3zP|&0BOwrGQv(E$*l!8!g7bq)oV^lI#Z;V?Q=Uf=QcjMN#QxW= zpJv4VkL1I*h!3B^hmYjLxBoMI_|3(di~n=G7`I@zkd`(VbGEvLw0t(-LR$1?D3zj3 z4AKCoLzOY4NlW#9>KAuY{i3;d@ z@&5VC7Y}dV=>K|nc+u*2-@bVE@cQ!A)7KAwtba>$yElG+u{;cTMSRc`!spgCKYsjM zn%lLpsbYNef^edW@j)h(+G;-+)wW`M5D6t!8=tDG|5yx2gc|gGaMA;^p!KV#u1K{_ z{_pO0s%IAOp=-Y^e>hxi#Z0_<5LC6T?yV6y zP{Zo)hF4YHTO(qiq?&lkUkx8dq(DhE@s@``N!9a=q?&lkt7D}~Z+UfWwO`>a6vwKq ziMPBqR&AxXyf(JjRxgc}D!t{Uu~k)g3zf0zfhKgVx4bY`ZKb!oFt*xOcnfv0gPsab z+6r%>ELN(Cx7rY&e_v4*E7inX{#5udq9|6XiMJg6mnyyGHLlgsg11oOs^gTRd@^at?Gd$bgj3X;#XVgEsuhzwiVt&62yS$rm8Bug&+v2 zCf;&{f8aA^Qcb+&4}?pV^OnC-R_y`(-T8L_{F~aEtO*^~R$H+j#v5hDwmPdVReH-= z?W(GV*m{88a#Xvj3U7hbR=+l(YrW;kVd?>T%Tt@HZH2cG+B|@KtE$3V0NVV{vz4H7s;fWtO-3kPpVuKI_p;L0jvoTou{@YYeG-XQ(NgRe~zr!R)395s+_m{ zHL|KI<}Gk;>VYP7?Y!l0k*Temw>&nl+E&b4NX;AY6j@aj-a=@eRFiqj8MlFqn^Y5T zd4`KrIdAzpWYr$f-<{_zM7XG}$-LzWE@~_1El+SMw$=GIsnS~>;8In^yoLN0^*}Oj zd3=l7%6ZGsRBi|mAYBF!({*h0QNi{ix_tX~kE9Wi0e=L3jxDFqA|A>dj zs;cl7?;lscf2^uv-r{BW>O@;r72X2SHUMa=s=`|cY>{f>Esp^h7y}^H#9JQMB2}&l zJ+7tN16UIxtwn83yyamnYAfe04{Is5)w5cpN^f~qOH~zXLX>-}2b$2eYeKK~R$I9y z^lI;FTj4Dfdk-k~uByUYsP&d=vL^IW?}4S>Qcb+ohWNaCJFq6)+B;6ykCuAMRN<}d zE}6I55SuF2gj*vyuWjoBE@LE@u_au_0xn}b;H@p;GL|;P)&p1*;;pXQ_ll>w^ku!?H_%ux4>mEuw1H%w>+<0ZKbyoE@Sby za;ef=374^e%b3VzAg#RmWx-qIG7wf?Rn^~}y+tkq+2d7Jc#B*HqQ{G>;4+vzJ|KC# zs_N&23?7$i;w^tvYnaGoAa}glRzJ(&6CG-6;w^unLv5wE{7J29TYXK)2RcN;2m38V zD-IK)6{Q;Nw-#_26S)jL&r$6G{oUDHRJq?uxD34LCROgY5-tOeX-k#f@oa$y3!Y1+4DkFP;v3@l>kGyw%W~^Y=2*!Ci7q$jE`42E#No!_Muem%%iFb50c-&(}zV>@Ed&j zP;IsOt*QzSlHb6?hgDU0ko*STJ*=w2gXA~x>|s?EXCCA?@akbz74sYU4Lo{SRfPwU zQKZU5o8PLc*q4#tz#BYORs8~-e=o>y;0d0ps{YPYd7kL}Mo|^~1|Q&2zb4-D_jd-q zzav%KmsQ&eZ;{`?^E*{lc#Hf7Uf-#z!dv7w@c2$u72YDhfwy<6s_+*14LrS5RfV_k z@{TImlX(mL1|Qy$YBFzu-{8ADQdP&lKTRw40Qe0)yCc;PdF#AxxYgW0dH(X*^QR9j zk>*x&uO4Wh-@B9D_Cxx&_1^ib8SXxv#>=n&{NmNiPk;IH&4XUZ{!%Y!zkK^xUV7dw z{t6)PB7C2FHv6}8!hhk$o@rnf3;lMT-RC2D)As;JF1JOY%cE#s=9Hr4P1P@+xe>VdLV z9G}sUs7*B0mTGiQqmT1HiP}6<6!r5z9{))+ag-nb@$^rkiKG1VkB5H}O&sM#Sv>ob zXyT|gy61uNqrbb&kN&Cy<&MJ1pF|T!c}3QQgFlHTj`D*)p8H8Oag?9?@fmuFCXVuQ zEIvXn(Zo@H>c>Mri6)Nn7wGu_y+jj7c`X)?{3MziKG0yZ^Ch(L=#8(F&EvoomX{#Jw3d<`TqXt!|U=wZkRwi4tUf? zIYIVMYCinvN=~Xa?J9o>q~q$OV^!7WU8#a}T%B~Rs@lXWRh*uzPCA}cZ~g!O{_MO1 z`;YAZTl$~<@}6V*KKzcVc8vO*-~XP+>3`$DKDqqq(*EZ^z5QBO886;`bNRW73H2ZR z%l(TNKfC>2{L3$X`{|v|QvSaDOLaHlUIJyMcZ*+3v|p`{{!mHO z&5v6NiP{>WD2iJN6qQQU)(BNm+s6*LlaQ#b5vrp4yVLOFNcBP42TgsQ0RV>N-=kEBGK&buvVRn#X`+(t;$)(BNm zpHFcaA<;J1UENZ56lzH&nm7t~5hx{A&%QIw9VrHP|ZI=cIwPojyVP&taiQHdswYNLDp=hIPMH(DGh z)QzHSR4q*$g|bmpjY>3els^(YplDR0iK9?7ikeZ0CXVt4f(Mk0-mQ2axVGl^=Ya=Q zj7l_d6wXm_j3Uv*Q8-4yDT+iBN43#Cef&5?k!a#5l#AjFMWVqR#T0K8i%K+b6hpjG zD=N{zQ8Q{q5#cS-z)^D>-Sa?UjzWTW?N@3>r6>Zt?-1Z!74~uZiyz2^3-mIc1tvIl!taR zvsy~KZD6a|~Q51TIu}o=CXQ;Odm1QIgi17VlqYpF zs9U0mqnrX8Q4cE7#8FOxF{WFhiK9HGn{?CHf&poo{%*5+wQXc=`6>{@LZ} z{r8tQ?MhIo< zvQ)j;Q>td2s;Y+3RDCv*s(GiXYC9&i)wfJiHS<(e_0wo=b>eH8`(^99dy=ZExkqhv z`$)A3U9D>NQQnf@K1tR5Q*EowNK*A}lT^(>RaFh~`+k+G@0+A*b5d2+R(VqO!#%0m zq*PS(jgwUAE#Em+RrPn)1N4?}ovNzlEwz>2^1V}4)x0HDddoLYRaNtrROu}b*Qu(S zx1>sM`Sz)*3U47?M+NMOw|xJkEHiq`H&E5K!dnQ}QCkyl`3_2LrMG+wb!zK*B7Oey z@%|4Fm)8%EukW8eK7aL6k41j>{T0-jB5rJ|Q$uJ+-*&ZsYheQQZI@JON8fi`Y+o6yxgfT<4qFR9v8S8S{AzZ8Q=Z}|qSs;VJAe_41ZNo}=d zWK|X3!WK-biMM zg}0E$qqZjAYD0YPSLE?XwKeZrZ?z#dRZewYk5lXcug6ip(pz4Tb5cD|puhUZ`T6Bn z_irBcGVX8hRloPo<0oIddVGBKoybf5LodI1`Qp!)KR$o__VSBw@4x%~!|OM7&~nie zJNTz_8uS96zCJ0;u3q7ze><0@UgA@h#YBjJ9}T}vgk@Rvy^TNJ>SaD%#UPkI;_fi#gC$P=~*xN zDa*oT2>MZLZ9*)|Vn#&Lk7R8|EX%@WDEyIZX1WzN&9wVccRU8d>>=0v?@=`tYo)lPuR z0M#!up!%vTR*b;vCEJ9qcA0ba%N@Xa$wn@7vR<-u8PNJ-CpcR#S-K2xeN`4N175FA zh+O7;y;@6`0kE&OR)2SP86Id-Ya^FAW3SfIWq|Cft;Jl1Cz_TSn0-|iE(2&U*=R0v z(q6Ara4rLCUu`YsGQjp~ZR9ei?bTYk47h!u>o4vTzvye6==mnKLD7EnKGEM9{Z-oyR{gLM2*|M6z%hsS^FLN3z(L0mN6|Ci}9< zNqqG!_GSG=pR2zFz0iZcrOO;FDXtjxL=R-?GAB#QvhK2hXvyMeNm?8>FM`&AYIbm^|@Xac*#J#WO2Nt+P6;T>xC$sIAyX5tDLj-DLwAlf@a6vMgLi$fQ5-6MSHB87Y&cx9{40 zncnMhI}kI`Wl}U`a2Yw1{=(1ood9ZNAT`pT_z7fvE*prAERKy-zXa#?^$;6YjEi$4 zWm&k4;7E`53_8K*vVr7C5BCgY;WDBli=!juPJqkEjx5fOlx5*E!Xt~rBV}2*jP%Ij z^hjA2E+am&I6hL91wS&7AL)<%T>m9F!LP*z=Q0OK%B{s*MuKERYZD9U>{W7A_-2B1kQ2EnG&7MAT0t3zv~25lIlq!et0{)sRK| zGLR&C(8RAZbOn{P7VO7>r=8SVb^i6{1^c1cf3{YgAIQRGWIuHL5y`@3c-={F$wV$| z1AX2*ko{O9_Cvv*E=%@fiP(?Hb6&Mw;^{}kekj}%tp)V2FDx1|xQy&afB)zD4-D+b zK=xya*bhZ~q7yimMeK)O>VYg>7O@|bXTIu7;OR%ie(0?pw3hp_i2ay6_f@UsTo$n( zlPAAwn-3y#iP(<`?8iX%V~N-gWF@M#bXmlHAT3d{JY$U5j|uF@K=y-yiEVoSI8rjT zfj<2>>tFmwz*$>7jR%PKb zvL6gmtjg-|>;vOm7O@|CzX!6M%Odt;0{bzL{a~D8wG-envL6gotjfY=WIq_GSe1p# z$bK+Xu__Cfk^Nw-Vo?_ChhEslPA6hNCQnw>xjk2m5&JQL{m^@fY;CkJ^K?bEmM)9f zj|uFDUdcjhBlctRghjQME5?ZZm^@=qcOqOdM(oD~_G2LX!I;JBcMF%1{b0~yRTeHI z`>{mq#{~9cAp60v#bRqcZBau;mqqNy1onf0iwgr6tF6`Fo#!&LAB}f`@zt~ zsw`HFWIq_YSe3F`n$8s$bK+}u__CfA&7Bd5MxyqE@P?)qZq5Q?lOik zseJ*1}qdK7pUCVwTqfxjE&KMceSZys_M)rd-jYV0o9}H?#CqynoWC)`gB^$X6 z?8iv6^k#%d?P zWn@1X+gO#wTt@bT!Hrc}xQy%vqZ^B|U_Th%s4pRM8Q2fTH%c~gnddj^OTg&|101WJ zpuao2jO+&^9ILW$8QBkpI96qS#W<4vV2oo`7IPWd4+c3_W#KZiAB=LW%ED!2Kh}u- zm=Pi}lKogC_G1S7F_QgQBle>w#hkxevL9>2e#~G$MzSAkl>5=MVyv}XF-Gi14~sEb zoH4Eu`!R$47|DLD5&JQN{TRu9tP%S$gZ)q<45rA4{g}aijLiL5Ble>Qyqt%O?8h4A ze#~G$MzSAk#D4UE7i%rf7}tpX=m9S#%egFKKYGB6${s3A3fm3TFaCCDEDLb7c^BqLzhLlA3fm3 zT1%HjxgR~?#bh~`MeIipcrjVJEMh-qupcAYk2T8unEfqHl_v4@Bg*~g0WarHAp5aK zxgRrfKSr`2Yn1!Z1757PoXeuzj~VR8NcLlm*pC_P$4K^Ljo6PK@M4`nmqocBJ>bP; z>9UCZ=m9S#OP59L#|-vkB>S;O?8glDVm$7cqJmjQz{#NN^(U0`KDp@C;65Bqy>WBcv*e zyESqmD>#v=tlwad%m`VL5mJ@aA(-_o9f^#Ps;vIbWZ}pS86j0!oJW!q*^m)ZmBo1^ zIgt$ybXH|?9!XAQ!xNoVS)50b6WNdvQkBK2KRJ;N86h><9tLy%63B^c$Ox&*!e!({ zHe`fUW#KY%A{#P7sn68JHa`TqAWNOrN>a#@77MT=UMuz z@9&=~H~f=dyn6Zj=ij`2egE}~hbz*-l|x`Z`%0T(Gwd#|4|w4_Z-00C&L?JyY|fRG zW!;q%GetJf6e-K9bFH;>rE?`^S$E~cOp(nqMar^pCApFf57#u7t1@J8B{M}f=Ss@0 zg)7OGY@R7nmW3c0q%Cc}G*^|w4N6NBrBH5G8AFL_M!imfs*_=Ho%fg9dPc~;y%Cc}G*^|w4N6NBr zBH5G8b4SXua3a~0&2vY}vT!2Vlg)ESs`7S`E+c!gIeSu;h0B;bvN?NFmW9ih zJF+=@QkI3w$ewJ@o|I+bGO{O|vnOR)xQy({=IlvX7A_-uvN?NFmW9j6o@~yZRAs@Q zOk__sXHUwqa2em6*_=Ho%fe-Rb7ph)q$~@UF?VEh_M|Kem+{S+&DoQ(EL_Iik!`y zSr#s1?#SlsNmUl?i4tirmpOYgk4%Cc}7b4PaPNy@Tt8F`Z3d6Kd$ zTt=Q`cb=py3zv~6*_|gT%fe;kNp|N+%Cc}7d6M0ElA>%6m^t6Bk|)`nCn?LqW#mbA z=Sj-4a2a`$-FcF-EL=vOWOtsVEDM)0cVzEE@4^7evTzxBlHGZdvaGvIi8TIuyZ77Q z>s#wCo5_>x&Xbf|>n@wglkCoulx5vzGkKETb4RMO?e9)5o5_>xo;y;Ob(hWLLw3&{ zDa*RcX7V9B_>h)3@bNqJ9x!8_05)<5A5xWdm(6^0W(OZqm35cRPoWEPLAA7`p^ne+Y zMNPmSu^&BP#$@TTi2djRGbRfPYmeBE9x!9Fs3P4X_M->PoMp*=>=FCX17=JXwc2~c ze)NDDlSNIy9&(F0~o7W=Y2Vn0^oj?82~_K5xH0W;QGx-4Qpdccgy z(q$3*(F0~omM)9fj~*~%vUFL*e)NEuvn<(LY#WfA+)17=K?E{oWY9x!9F zbXmlH^ne+YrOP7rqX*2GEQsPgVn2GojLFhv5&O{tW=xhYi`b7IFk`ZGS;T(yfEkme z%Odup2h5yh$$sn+`_ThtOqMQ-*pD7CW3qHv#D1)8piP!8i`b7IFk`ZGS;T(yfEkme z%Odup2h5l(T^6w)E8d(@A`LeF5&O{tW~{YzS;T(yfEkme%Odup2h5yh$$sn+`_Tht zOqMSDF#B;P;s2e5By0OHtQmAASP>lnRCe_3!!TL860As37OaR8Z16#X6{*VNw1lk4 z4pyWptG}~Opew{=G(`5amm^~kaOpeG1;9l zQCC-7)V>c>r8yljsj9-8BusWEOp2-iOcZ;AuhIdNsw$jGzGQd4q^hc~!TOcPbiAah z3SW{g*_|$_s_O5ot+b`XB~?|pl5ENDY)MrWrX*UjJ6cjzg||qS>`sZSNl_J8iNbE+Eyqf#s_+)6lHIA2sw%uisAPAjq^b&Uktx}oDXFUJ@6O&L zQnEWzQdNbwNR;eOlvGvWEdnLG10_{ec#AyA?mS6V72YCFvO7*vRfV@mlk85D6jcF} zDB=d*a+sv53U84m*_|b+s=`}DNp?p`s;cl7Ns`@3lB%ly?(8jsB!`0}RaJP49LeDv zNmUizB1UpJMp9LUw@8s3PLWhq;VnWWheIS)Rd|aG$>9u1O|@swoWB7gB!?p;RaJP4 z1j*q9NmUizB0zFDKvGqOx5$qi&W}`8^>@~*stpN_oo0=Rrl6H zZsc%oq^j!PT8NDtj*V1R-CGM&MGmJ%s;c_CleZQ^BZosHRaN)aLT2P}W~8bLZxIX&`PXkBAKpCq>@QD#{hQzY>hmw3e5QD3JZ+<=^)Sqim{e6^N)jfA6DCzvn3CZl zhXW>6RhW|5B8T%ORaKah(ISWAB}G*vi!4kQIh-!3s=}0nOAd!is;V$0b43nkORB0c zC1XVnM@y=z`n$8Ym@0BOSyENSgvU^k!@-iOD!fImCv=W{@1< zP)ZkzJ!|ItT{42?0ESXjg)^Bza)3f9s=}FsP!2#SMOBTS^#G4hz@QXW;Y`Ml96(Tt zs&FO=lmi4xQ5DW)_{aeOrKk#LGJE6zPf}EcGZ{T{04J%bf+kr=lN_K)imI6P2$LLu zNs6lQ7IQ}qup~uQc#9~>f!L9vD!j$ikpm=2Q5D`INOAxqDXPL-xhsXj*wJU^>^nliwMc#2uV>D2+2Z(9h|RTbVMLUK4lQdNbwh>#qPkW^LSEg~d` zBP3N-c#8siB#3`*Q>%? zKuDyjj=x?N-U31*RdxLJs_OrsiB#3`*Q>%? zKuDyjj=x?N-U31*)%M|E`Mvh28S7U+|5)!FA*p$*C(W3u->6A7@Kz6+IjQPjZ1;3h z4ZPKJW=z!!aHJY|tH;cksw4YS4ZPJ;W=z$~X{4HX3kb;yghZ-|x9~L03WP+eiMQGi zTMzhtOR9;t+7O$nm(oZz@m3pRQ>C{YAt`#R4Y8@xTaJ)aRej!Cfsm|sj*wJUecoDu zkVrN0RvY4T4*(&NYT~Un#HLDbIYLtG0U#tR5E8XD@fIGNS%Hv9HSty(V(S5V%Mp@l z55QYMNYvIQbnU#=hS=IlZ#fB4Z7aM55@fw|5~QjMZ-E4nYBF!NAwKs2ND!$e-fBZ^ zs+_l+1gZ9b{?1hCEhj;Wsvtp>K!f#wlOR=9UlS^ThN_9T+7Me0&|6M|RND$~fdtVv z(1fn_RvTh#E4}3;NVTo-7Dy1SI+8VE8{%_YL4rs%@m7OhfIZ-E3+Tbt0e-fBZ^ zZKb!I1gW+a-U11twRhsJHpJ()f&`Ij;;lBsrb=%)2~zC=cnc(m+M0L^p(2W#feV}j zDYg|Xhtg)Knyd-i5L>@;-g1_s+E#cAEQk749e=e85GbOk8TLSH-nHIpLu@@jZ#m0R z?E!cTEXR81EJsxp-U7=Z)x=wEh|fI$mP4w^nh@C_N}0iEIm=P)0sWn|mELleqo@j& zLm4w{YvQdo#MV}N%UOO79Jph(Ns)@G{?XiO8kZR&BM0>1YIi#A*TWyG~2k0$lIf|nNmP1J~@RqY2RaJNk zT!wleSrdZGSn+aEcU^cGX4 zw-PR+r?;3Yy_IkoJ-x+LId3IgMo(`sReCGoGJ1N8snS~sm(kN(OqJeBxQw3OVyf`g zkZ>72y~R}Fts&tu_BO<4RdN|a!e#XI7E^_{hJ?%L=`E%TZw(2T(bHQ@72X;WE~BTn zm@2$ABwR*MZ!uMPYe=|^p59`r@YaxU89lwlRN<{5;WB!9i>cCE3765+TTGSSO1O-k z-f~h^+>7rEhJ?%L=`E&8ZzWttPj4|*dMn{FdU}hg(pw3a(bHQ@mEKCYjGo?Ns`OUE zW%TqGQ>C{OE~BTnm@2)Ma2Y+l#Z>97gv;pZEv8CuC0xeQhWM;XE@MczjGo?Ns`OUE zW%TqGQ>C{OE~BTnm@2)Ma2Y+l#Z>97gv;pZEv8CuC0s^NZ!uMRE8#MFdW)&jTM3uZ z(_2iH-b%QPp59`r^j5-U9Bqits^l_;gv;pZEv8CuC0s^NZ!uMRE8#MFdW)&jTM3uZ zLs(3e-b%QP1JA!GwFRpTPw1$fKK2k6Yb(8#a2Y*>#Z>97gv;n5ET&3tC0s@iVKG&D z>w{dzxk7Kfd%TQy&%VEW{^IR-&tJa%?lSzB@n4@@{>Q_gE?>NQ{c!nhFNc44c4@VI zmrwrX7r*^fyzcP#^$NZo>~d}?S&zY454pQg!PkRbOqG6h)}yNGXOA0MkHJ}ws;Zys zZ%F+RU8oC{_xGknRj?i#S&zY4kE*JlJ#J(@24_90s(xp-A@xH&VCVW(RX^9?$a)OU zdQ?^YTz^CAhp0`fTdAu0o!Lg#V{q1^s;a*`yMV06;H*bg)$gM>q<*Le?9QyJ3U871 z7@YN}s=`}jJqBkzimG5eHnJXr=XO+8;VtBLs9){Qtf~rck@Xmy^{A@CTVy>3&+VwH z!do-vLT5dys_+(BkHJ}ws;d6(>@Bh$gR>r0Rd|c6$Kb3-RTbVM>oGX%QB{SvklV2i z&UzG8!Fp_DJqFM1sH(zS$n8*D6K}O4wr_yzOlLi+ZH2dx+o86$W$-(Ws;UZak@Xmy z^{A@CTVy>3XFaN_`nz+#lJyvz^{A@CTVy>3XFaN_@D^E*!C8;0D!hfqo@kj zVR-Y(#MT2mA92>B*aKiaHnJXr zvmRAdcnirqwJ z-<{h^)?;wiqpAvTA%jD0O}y2H*xJgoM`t~%ZH2dx!J)RQ#HLDbIqOkXg}0Ewp&m%Q)rQ#G3U7_hdQ{sAZ!v>obk?J)s=qt8 zm8{3;tVdN9-eLyF=&VOo72aY7$LOp_RTbW12FK{EM@dz23p%c{e#N=|=&VOo72aY7 z$LOp_RTbW12FK{EM^zQxVg|?PtVdN9-a6I`87GJ-P z&U#c;-CH}JaZy{ZpSS)Rvtn(*%aUQ56{+J2N;&XFaN_ z@D?*TMrS>$s_+(`aZwK>-fBZ^UlzUPtVgx2@D^TUSx09*s;WM3?abg9o%N`y>hI1y zK-Ob))}yKlZ!v>obk?J)3UA>x7WJz-{_0^}Th4k^+X`>tH5O%^Tz_}0I1qS?862at9@Vz$@6J6y zE@KS147C;B!fPz*fn-hChS=K5HDSPI{5599ROzjN%TT}s)`a9T#(>L^D!fH5V+^L^D&{S68Dqd@D7FILB9}1+T!vKPEpi!pY%Z9&+Yq0BUC3pO0hgh+!dv7r z#(>L^D!fH5V+^vD7P*Wu;4-8NZ;{Iw z11>|V@D{m@G2k+!3U86i7y~Xts_+)Mj4|LcqzZ45%NPSLL$MX`7P*Wu;4-8NZ;{Iw z11>|V@D{m@G2k+!3U86i7y~Xts_+)Mj4|LcqzZ45%NRe%Wt`dikGv!|{d}yyB&RmP znWQ>Kr#kdye4L_}Dx68GV|1#cstRY4>KL8ssH(!5cv)o~o$4s6g6dGJ3(ka{>Zq#f z@6KyKQXQjH9aU906ECZ%2h{QJPnfEza3-ma(W#EADx8UzRo2m|j;bo0NvdOXs-vn3 zZ;|R4o$9En!ds*|MyEQes_+(GR#CsIX@ABsH(zSq&g<2 zI!>zRx%98kum1YaFJ8U;^p`K+JiLCqe5uN`mv0}-g=os*fgy>4OpbzR=qgiaqkYap zOcZ2t6r`#OLlOm<90jSV_GA}pD-1a~3Q|?opqVPJt0zZ6s;Zdmh=NRxf>c%Ych*)I za&i=;stQ9A1(_TLsj9+|L_sD;L8_{5NJYW;58dP_NLAInr6?GxHlcSQL{-(jr6?Gx z+GJN%b#EyOhN|lLtJ?|`L{TtQRmWei>fTZm3{`EiEA{|T5JkaI)h4^Ds{ZceEk(gl zRULnQ54g7!1p`$_L8@(aZz&3fs%<8^_IpL_hoWGpsvouMRpBk7Ad{mY)gFMih=NRx zf>c%EEutWkqaa09pdgBZVZSEc!gDN&f}v{SEj-7fC>W|H-U14uC>W|H-okS%ih_Zv zqafAMg13l*Opbz_RL@Jk+wsXi{qi@ze)8F}-;Pgi$0xVrliTsh?f8U6G2`v{q;!08 zn@ewV>AN1lD))93al4ART}6zytBBiNTAE9L^^f!O%dhU=JU+a>{PtcK5&t}X^2Mvi z$5-E7e)~cPMwj2beDUYYAD=&dd-=t;_uu{g;q{v<((*dWeL6%F`)ynDWp>WDAN{;~ z_VDC09f|zq$^GNw>*rs;eSCQHp#`Sovp_p8speDaxSQ-HpA0DUEErxImZZQiZ5 zek>tbJC-QR`kCJyP~T;C)VD0_2NQZ`6MgHfZ&}t))CGW3)=vG(vVQC*0-Un#tFIm1W^F0Km)a0B~6ra~TL=$wn>%0xT??oe;SU46wLx%0?~&1S~L|vXRR`0gDW$ zY~(Uvz(T_*8@UV|u-I_QMlJ&gEI1sp4gy!dTadt_!zmlN3^1?oaLPt=8E9Vd;gpSB zhLAP^;*^bChLkoD;*^bC2B24nIAtT3;Y~g<;*^bChM+cK-jt18*0AmKz6?z7GCR{- zwF9Es^cp8x>rii57Ar)rv@m2BiP(7Jk?)4znpY29+)!ezj9)!Jk( z>m0ZBE#|VtdEH`bJIHOan9CLicFVFFXp@D@7AJPgvY5+|-lo1yT-LE{Yc1xo#hKl5 zYvD3LyUXIxZduk{CXyT9ty8;YS)a@FNGD|zmvuDz)VF%2ld{QN*4b>6#ay;{hFi50 zKsIbtxNM}$JlCx%i(t0_!EWk=$YprN zZ$Pq}WFwcgfwsQoT;|bkuJCfUek2zb*Qo|w=*;H})Za2a0SQ)|`vSKpyeh~jo8Vz@WmygM`G=A0$Kq*kWm&k4?8oA9Z)I7y zjO@qad2eM|%w=RhmWchBkocwtI5A`q`!ON%O)qd#HgXx*4?V$2*~n#JKlBDCWh0k? z{m>(vl#S*xupfGbld{oV2KGbGa8fp!%fNo<9Zt$da~aqVJ;X`bXf6Z$p_e!z8?he~ z*bhC$N!e&FL-^Z3_G5|Ij|u5-dW@5;ja&xyL$7gCHgXx*4?V|8*~n#JKlC0aWh0k? z{m_G)l#N^l_CqgnQZ{lK*bhC)N!iF{U_S=3A4|l3Okh9sC?{I$DR9-97wm^#<)myh zmx2Azvz(NTTn6?-?{ZQ$av9hUJ`EL^5gzo-*5&?bwyY>n8D zxec_*(q$3*F}Hy}$?DBc*dby+<~GnKOPBfUeZ}?d+y>fYF_*3Wd|z4CU8ZL{*$I)$ zz<%i6PRd3u!wY_TxRbJx%aGfqmpdt&%w;p!4?W#U*~n#h#7}Q`LN;PQX1wC3$2%#T z%w;pO+eWeKj~N+mBiWBNVn60K(AHYIEMh-qupcAYk2PXH zX0RV4*^f11KW4BWddU+XSj2wJc+*c$c~Ul-%fNo{ss$BdW#MzSAk#D2_RKlGv}Iw4{|X0RW6(vz~$Tn6?- zZ+cQTn#&sGa~?9XA8W*Z%wRwCswZ0;xeV-wp7o?`2e$05}Pj7p&wb6NqSjo6PF?1vut zq-?Y=1N)&@J}Dcy4D5%V`J`;*GO!;?UZQN|GO!h-&{WVr+@n5(>tX@)ze7V0mromj%#(S>Rs8K`_VK~$;vaQqnQK8wUYI&tjfwW zChJ`(S?kJv8(V3uJY%x{gC$x2!78>E$F&EJYbEPHSXEhh##-w?Sd#T0tg5UA+GPC) zOS1NZRqb0G*B&^om8}0@Ra>ipw$}O&*4it$PIX^ZS^b^K`VW?5{RgWmtARet;<#3_ zk;`ygd*HZMvXRShTzlZSRvZ{cycKSw1=bUj4G%Tem06 zZ%>xro-98Ay^9^TO>WU!$U8j1yh}Biw}8Cgo-F^r;K}mg?$c?!{QA!?UcLPEmoMKu z=yA9&Up@W9%eRm9v#dK5Kkg`g)Y7DV*YD0jYajU?a<6yPK1wyP&TYx3WMezJzb*Op z+ma7y*IM)j-cqEoeOb39-)+fvTk_qOdmW2ALrG{nO_OsmVCEUz8$ZeXn}55^hHCqRsD%9*$;9s9&}Mv)rQzq ziNSczMO76P3}P;{jI!(Ys;YbIzzZi*Z9-RWrv`*v9JeJO5-!xQ$+U!ki`$a#w&c4l z`EEBuJ9Tc8f8n+iWwQs$W~FMkrBzkGEj>^*D^>fgud4dd*@2>2 zsoEB#s;W^ttxXQp%u2Nhy_@f=s=kgoP%^ttUNT!%^>x&Nidm`J_gGcMItm4|Qnhtd zRTb+f)XPfM)=^beV2dc1m8u<`RaNzO=WhVjvQkaFg<{zQ#j;XOyoFlX1GTbJO}vFt z*#o7rQcb*tO4$RIvQljWbgj2gD0`q#cAdOXw)hR8PWC{ZtW*JsE$2Q9V^wuTPTh_P#i1O#9OG1Jy07f)x=vUjXh8r zE7inXsEj>O87tMqTPTb@P#7!K#9OF~Jx~`b)x=vUi#<>lE7inXsER#M6)V-mTPTV> zP!zjPUKCsO7HVP-)Wk|P@fJ#A50u18HSrcIVh>crN;UBo3Stiw#7Z^s7P8O}WT8tn z@fM=c4@99$HSrdb&<`Y`OEvKpg3u2Hp-VOK7IM%J+FH&RaJNkdFN71yyZ{b>$MVk%gOI* zTlIJ6@0H|t55d0r%X0EtZKb#Tq5EQ6J?mVm^p;~lRaJP47*J2ZzP<>9+;!H(pw&wQ*A4}g?RI| zr(R$EJK*W&YAfe0kISjH72aZ6&g^M9RaJP4VL7vh=4)k;~{Y*H`y| za~XPQj^0YR3}sfMt@KvHWhk;5s@!iST!s>>p~`tH;W89h4OQ;95-vk|)llWUm2eq~ zt9Dg#8FRvAD6JZ*Jj+P9424xgmHVxP%TQJ|RC$(>a2blKhAO?4a2ZOfhAO?4a2X1! zhAO?4a2d*}hAO?4a2blJhAO?4a2ZOehAO?4a2X1zc2#m2bHZgPqZ+F8R>EZ{q8h67 zR>EZ{p&F|6R>EZ{pc<<5R>EZ{pBk$4R>EZ{o*Jt3R>EZ{of@k2R>EZ{oEob1R>EZ{ zn;NS0R>EZ{n%Y&#Wy}eep=4^P(pw3apc;W9?&GW19?@3#^z zqbD_-da47uh!PdxeT=x-dYkaV{$G-s_@q0iG0hlWUcO!a2Y*;$3~0ZO1O+3x@fBOR>EcU(8ZJLKrUlRxQrgUXsYy9!evb0 zG8EZk4{Yf1M=i#G@I>!i^>vHJzC~ld>jC^W-J-E?(b%_W>{~SUEgHKPjs20i^zP^D zxYSFjdoqeG8@SAML{bMNg(dj}L~+tg8Ca=RibqaYVAJ z>PMdg5y{07$*QWhL}zaikz70+x2Ot4av&nPI3ih9)!$iLu}oVWk*uo1TSO!mPfDw* z!dpZn7e^$ks_+&O$;A=Lsw%uiL~?ONvZ@Mi5s_RRk*uo1TSO!mMrt#SzJ> zD!fHRa&biRq#dFC$mF&C%<&(aPmnZZ?@{gx_^;j~K<-*qM6Uwq!*|I=k@dAai zES9#cP*}V|;VgSz*L?Bt;>Dl8zkhkfK|ouDSwC@W*%0^BCQz%o%1Hpq7zUOxEMCUY z_u7?F#R8ah42#z>lx493W+B7kg$!j`EP+|cuy`dySr%(xmNG2<>TgvRwG0Dm85XZ) zD9dUMe*VB%%&>SdLs=F^WHrO$)eL1>7?I@+i?$ zT*lDJ#fuxtvTzwwCl{}7D9gfSjGbJ(yrC+K`i6nIlZ)3klx5*E22U(Ra2X>g7cX@v%fe;Mpj^Dxp)3oRF@$pQ zVu!LUT*eg2#j734vTzw=C>JkxD9gfStan(v-k~fDmobQP@q&l4EL_Gz@Wm@0%Cc}7 zqbL_Id8o>w=3!tK<>ECDWm&k4VU)TXNH+ecdKj2Sxp>t>xwUW^%N`aldnn7oWvqKx zyzZea3zxC*Ve!I;vMgN2%7?`(AIh?D8A~4)FMTM>!ey*|SiJV3EDM*h_+jzlhpMcn zQmzA2DHpGPD9gfSEPq(M{Glw1xs3G>i`PGtW#KXgQ!ZWrQI>_vSOKAQuH>f%B@hEk zAQbo%$--rkvSiKIS zEDM*h5JLCfK_~POQfn=$j8t_K$--qUg-{_!Bny}E-LlndA?5UbZilsmy)HZrJk1%+Ac1Ynp- zFJ&jF^RK?snGsc~_)^M7E^7mAeM^`1-n{xtXmu|pi(C0mrP$!e!(!MNTJn0FXHn z$Xo$r7F&zZ%8{X!D~QahEL=t;a|M!Fm4(a5WUgQ`tFmwzp-esP84Vd+Mk-S;Fh;U) z8L>>g3>?YAW#lsT_F5#XF*v)7VCD)ivpQsO8Ocn&B9^ok>6Ih#5Ivw2$@+?MWPGLG zj)`R9GU6e6HY1XS%ZP{Q#ehf_E@OhF!qOvIxQy(Fvce--xQy(FVv-|SxQy(FGDjm> zxQy(F;z1)>xQy(_8nGWes`UJuK=xye*pC@OmLu7ZHDW({SgEy^E5?ZZ=xL=U%N1k9 ze)PCfljVvrVn2FbsmY>xM>X2X2i6AqEKBxdjo6R54YbK}Uly?+J+jnfxnhjikDgg- zvON8W*pD7sYO>syMeIjUEj3y0%Odup$CjEbT^6w)J-5_k>9UCZ=)t8XOP59LM^7#_ zS-LD@KW5}wj$}X9i2axmY^ktQY)&KgV@9&2(oQKG&1HzTRNN_LqZK3A59OUwHd-+v z+){z3l#N!5NVintDP^M-BjPO;c}m%6#fW@MWu8JdVn1dCTq^XGve8_IgiDn_Q8rpJ zBH~i9r<9FWjL5iD?kQy>mm%a*!KajsTn6?-$)}W!T!xrSMW0eOav5?im3>Ot$Ylt+ zRQM@nBbOoRQt79Vjo6PFQJ0E8rEKIfWL+x%l(Lb_5O%2mRLVv!^8!d6rqN{)`!OT# zQW2U{B9&~E5 zaM>2IA3f>RWZ|+cVn2G+smao15&O}zPED3Bi`b7Ic6yRkIx4=~i2dkkrzT66c@$>x z4!y^nnk-!wu^&C})MV+hi2Yc=ekdW8eVfc>3)l}uq*6AS%X;Lgbpl-$u^$WA4~3+% zwaJRHhn`w%>9UCZSlU3FEL|3{A3baBEKBxdi`b7Iwq~+)S;T(yv^A5Z%Odup$E}$x zT^6w)3)qi|?8g?d9}C!ziR{M~u^&Bg%{qZDi`b7Ixn{C-S;T(y%r%px%Oduphpw3{ zT^6w)J$3CYOZH=n*pD8&X0miy#D4VLHIt>wBKD&PubC`e7O@{adCg=wmqqMHk6trb z&Seq%(X-b~mM)9fj~>2evUFL*e)RM;lcmcd_M^wInJirvu^&AH<}6G0V~g02r46*n z(q$3*(KBF7mM)9fkDdWzvUFL*ek{oSn8bP;>9UCZ=m9S#OP59LM-O;8%aZ-rBKD&PyqGLq7O@{a;KgL=vWWfY0WT&? zmqqMH4|p+I&Seq%(F0ygmM)9fj~?)1vUFL*e)NDBlcmcd_M->9m@Hiuu^&C)#boKS zi2djRFK1b@A6vwJ^ne$WrOP7rqX)d0EL|4me)NDBlcmd|+>ajcVzP8ul>5;GUQCuQ zi*i4Dz>CS!Wl`=&4|p+Ix-825=m9S#OP59LM-O;0S-LFB{pbNNXIZizTa^3J171v) zE{k$Mdccdx(q&QZM-O;0S-LFB{pbNNCQFw^xgR~?#boKSDEFfWyqGLq7Uh2QfESac z%c9(m9`ItabXmlH^ne$WrOTq+j~?)HmL>bKMY$h6;KgL=vMBeX2fUapT^6w)J>bP; z>9Q#IqX)d0EL|4me)NDBlcmd|+>ajcVzP8ul>5;GUQCuQi*i4Dz>CS!WfA+)171v) zE{oWY9`JIOCHt{OxgR~?#boKSi2djRFD6TuMY$h6;KgL=vMBeX2fUapT^8kj^ne$W zrOTq+j~?)1vUFLL`_ThlOqMQ-*pD9YVzO}A9QyqGLq7O@{a;KgL=vWWfY0WT+6CBpdC{2s9%J>bP;>9UCZ=m9S# zOP59LM-O;0S-LD@KYGB6$rOP7rqX)cL zYw5Cx{aC?%%w#|Ii2djRFVCS!WfA+)171v)E{oWYwGFh%(q$3*(F0yg zmM)9fj~?)HmL>bKN9;!rcrjVdWfA+)171v)E{oWY9`ItabXmlH^ne$W_-oHF{vtM-O;0 zS-LD@KYGB6$N`#?oQeU{vt$BNvKnYkZ(#D1*E{g|2iu}AF3irfz+ z!teu&T!!3_nYkZ(#D1*E{g|2iu}AF3irkNxxgUGPeyqs-n3?;rN9@On+>e>;#~!gC zD{?<(=6>uE`>`VTV`lEh9aqmqqNyirkNx zxgUGPeyqs-n3?;rN9@On+>e>LAA7`ptjPUPA`JRAVn0^oe#~S)_K5vhk^3<-_hbJs z`*D77_;;_qe)V|y;{NgR;q{*{-@bbBOiw|7egEd6{sQretdN;mA-nS;{dB!>YlWWhsHkIg8GhHcXbo}R`j5i%Q?6D845)lXfDs%}&T(Lfc* zNm12(svH`sdU94#6*eVsasW6fs=}q@O%CuTMOBz|phtIkc+k)1U%qsG4}I4e@Cyp!^xCCf)*QqWBr80yHW1E4;<` zWe#vAMOAooP@t2C9DeCsllxO8iVz?YopJe)ARhnW)-#DOLRDEAKN=wcmWH;x}J$pNXoir=*JC z{1FF#`mgx-Tzco{ep1DHN@1T#TkSVrHC6N$j{S;lwcmWH(pxz7E2_d_it?(8P?j}FDJE@-M(!Xv%fBokduU>xo%a?B+UO!&G z)QBtlIH?T6_cGpLC=FxRmEh-qdsMVUavZ|@8WD7 zp7c$A(pPKi(7p>(g&~y)nzR*$Bu=X}++>hG+rnCvD$=Buj0kUZs^{FJY%Y8xDV zSu~^{@>NyckUHk~h4|!Wd{tGS>~zXc)h6_Ad0JKV$xes-R1Lf}v>`ry13KfUYT_+F z-&3hGCcDY&!HPZLQNU8Ax4ayzs_Nd-0Y7`d7Lrv}{hjqIz2%QUS5@6xI^IWH{a~)D z>fX}nK2_UHbnW-*m0+q%r?>oIuG&_3iwAR)AIw!%;VmA_O@1&}RfV^BFgN+ZTv62z z=G3qBRzKFhcC`FpPO9{l7lBpV3UBdXZt@zis;d6(>@6P5OFHvGM4fjDCMcj!euPwIZ(<|m4(Y#%5$KUrz#7V zv6SaPDNj)rr92Aw#dnKRo~o?=?mU;Vl;=Qb5z)gNt7B1se{(-Cfsw`Z_yZi%p`BhoCjFL0k(ugbz@yw*Q(tzVS&dwo@|(`C5V zugdE0&MxD{{(+1Asw`Z_oBabf`&C)Ej92>yuJ)_4a2f9QRjlE6`&C)E443W^^#TR2eNP(?&>A0&i`RqJMiw1{f%*W z_WWt%6jej-{nm#3;~T^q<1jRHyf>w|0h}1!7>66Tf%kte@daRtxn& z7CSPaos!i;J&?6^k2=A>AIWN=9?04UBw7D}wmZO`ZGTqjTkOa{cS_cFWaT0A9hn}3 zuyba~+K#L&>pL<%20__o^7r1Xc7pH7^cVzXZAVsat?$V67zAZ~^;2xEFMpJQN0$Nd ztjcPjPcGAA5NvJaGE`sdF$l^=F7p+TI)N_33aHu%?lL_Ffz|@^tjfB}^cVzXBbPbo zsn|lg42z&@YvD4Gp4%Nr&#Ek32Gmosk;~dZpTAqMo|27R=CG&wmM#PAS?mO-Jta$* zbx7;#U$8dN)(LbOmO|Cm`dp^RAo$%za~UeJ^%w+X`!DSEodB1C_}uP5d{#RFa~W!} zB^%9UZJ^IXhGJ~VMsrykXp`k!=GEBMxvVXEO_p<+mt$9D+uxZiUFMPhWm(K+D9Bdd zMsrykXlpH9<`voH*1~1rgw@)}W#EMM7zAAAoN&3da2Yt^?an#jvMgK%PFS*$%i2Jn zhYXysWFwb>6V_u8?AvHAYXfbqrOTWXuJ$cBVLb-H)<*lXHqh2u&SlOCms<;$O>~)a z!ev>w44kmOgvezL2)9n4%bXJ~w-zn~C%oM`CtQ|=%fJasHgZ`T=yNB46P9e`GDQCC zF$jFO&Iy-00WJe4tky;=MsUJ<41%qVT-FBK`j#$pPPp0$ZJxGW2offJT&oEv+LgX?;{;Tqbve8_I$bS{R zP&RTIIAJ{oLD|S<;Dq%U1ZATYBRF9_20_{A^aGLqBFrcoxeSs2LTVuEoN(0+i2T>t zC1s=24@Ca!42ZIk%MkgmEjnc*mm%_Bk3mp2av383^%w+YBbR{_Ucm`(JqYUhgH}ZT z>oEwnHgXvv|MeIIWk2Y$Gx{>_kC*Z8+4q;vU%dV9`OCN8U55WM{_B&=|9JS*<%?IZ zA1?p!aR2)9$vAAEF3SJ^`+6y8ej8RK0)6Yqan%l^o%BbBEmNAWko^ThNez-2u* zDv*WCh#U`&9GCkRE+cZ>smh?Wn9GP94~`s{TZ_4j$ngMlwl-w_$%pfoK#XJnMpBi9 z%kUDwHUJ~3%ED#DNCsdeRav-<7)j5My827#Pd-@R(q+I%s;$L}kr>GUjHD{-E)zTB zzqbQ0lB%q`Of(8*lew%v`Ecr6-8@q^nalc<4;zyWI{#*Clew%v`CzTZ z7H>dQShcn8G996@waJR{07jyH7-f^WOvz9-mucY%Szsj9PH>lLrlo8XdVge9VRDa1vE^7mQ9x}xGOE#Lz+CZBu=Q3a<#l8hbvLV=C zt&LoUxVeoO$pDO`+FH1b7|8&Pq$&%S5hEFZkyK^jGGZhHFp{b)TtExH(Nik;{OQD2NbKq{q#jTYElc|Jx%^A9|5u{P`7+JM~aP`=`>P z&Y%>>1yOYy5tP9Zl&Y$4={6E5gA*uKRrnJ@by^xU&hg!JRaJ#O$)60)pHx-hPU0tn z<0n;Bn3MF$;PgpV72YI#GB|uvRrMp2jqJ(b>`74-=*dR(WblZ(s;d6(>@6hJ>B~~b zU;SkPJlPOXCsmvMs%?e0$ej$%om5rfEn+8wV<%Nrc#G7@;M7S~72YCrGB|WnRfV_6 zoD7~#S5<|#h@1=_O;=Tgw@91}o=jI%1#q$vI2jO3SGu`9z?*F3O@@Xc{Ghk4m`bPe z4fQg#L;Lq;pOqkEllwCJS#GKGmeHSjkg6{kq-qQEs;d6Z+Uk?OR6o>tAI?=)TW#~J zw)zp1RImSGlB)eMN!9nhQneGNY7f{ClT`hHX_@^Px2kGCOj7mpC8;){>y{Gg0sCRn zYp#BXD^+#;^{V#6Bvn7dm8zZLR(rsHn5625OHx(GU*A^qmQ?92Kfx`w)emr`N^f}` zU{zIr_ugAlrMLY2wyJ90k}AD5B;NAVTdC4pUIbWet9eVR^p+pqR#nYgQl+=rk>1r` zmRA7kNn?7;k8Z1Ng|~2WyUc!aTUCX(aBwTt#9MxDs~(`Yy!`Lf*7HRA^F^H3?^ON% z?DEV1dKrE`jO{=8&40c8_ZRmszj=6e`9kQ|^OxWJmHryHX}E&^>aoD@J+*G6K!*kg zUODz_PX#tr|N6H9VX^wJ_&EF3LxD}zzkZ$FCfi9Mpc@g;0a3BVw%W|HZX`elB*hk0 z?dzAS&n)VJ>t_~?mVNzF^_fMg*MI#|wV6e#{`E^$KRZ`{S)e~R(w_rTVr%^h_;Vxt zIUpqVz3SPiA2~g``}tNsK3X>4I4g7-bLbIloTaK?nfD%&D(285*f>ko=TIT2zCu5O zjk8p3eX6$lugG!)8)vEd9J*lRyd1&CS*kvVF4#Crwf($bxjxmev5yuu&QcB5r<)gR zD0kd{MWlNDuZViUenq6}zamn-{#Qh*_A4S){}qwy^}iyEevQ$u^j5HOmMXl3jkDSs z?EUm>jJDES!3?do!docQP+Nn&pMH(eR-d62ICK3Bt+v8jn4zVbc*|=v6qAqjDYM+) z|K|V5PJQzd4XM&w!3?b)fVVJ1s|ONq`3$YL(p$j{y=*>1OO@XG;0%49OW%C^@Zv@J zjA-qH^?qK{YQtTk)rPHO+s|fU#n}eSRDA}Ls=1`9YA#V*-6h-Lr4dzCbBR=a7bjJ7 zNmbQmpjD%5GrLrq(7So9s)}_i>mmlPi>RuaOVn1Mfz(!WNmbQmAgQ`bq-rxzQ58iI z8;c?a&tb2s+6<(&`sz+?wHc_Ys=qtCfF%)wmqb)m;Vo7~3|3n5Y--lw{UB=jecuZQWfQHJ0}%}`RY!p z>i8>rK&tQ->mNqHHLJE&e|Pp4Zq3xz>(_*8E4+nUGpSy`CX_1XE!>)Iqu-iUdjQ_T zt(jD>UlXdW?k#1j`kHX`TeE6g-CK%QrK&pq`Y+49wd2-IJ#hV+P(9$@+Hq?p)$7-U ze~n2!eXl!i&7_)ms|~TKVoj);@t|Lkow?)IOl?iP<+o<*j$1RSCf-8H!;V|CZS-5S z;`iEy*!mUwt4Gz4!__3 zOQq`0l&U$is%p-Zs_)jMYR;^xnlq*9yEUnrGmEOeTa&8KdQvrKR#o+P*01hNshTsZ zsv2Tb^^*{(nlr1aHtVSe{3JxG=FF<9&3aPxlaO`v-C9-EoGDdzrc|5IwJvBweC}85 z)})$vs|~TK(p$b;tM&lAh25Iknt01A*Owi;HK``v^4*$L=`G)_6??$z)}=~s`EISM z3U6VzrXEPV)rQ!<0eZ`;)~juWx3F8&<3ZP-#VZ{e-okE8s;zm~ddpwQ(t|v{qLk`~ zymg*SfAQk^cV9oe?oR_;zJH-cln;=#_%eI1J8%^(608aB*Y2ZJr&P_}QgwSv)uzs> zs@YqrK6Ogf>|IsW-@X3~rRr0sRL$N+Ra6=7tTG(E%CM@cugu!&_EuYM>a41oz10Ig zbxPIjT~#%EOV#Zy)h6`LGF4Txw^V)VRQa0OyQ*sTma0#kQZ;*5RpBkx7mi+ESXG6$ zSY9}Kd0|x*-ePs(=+%W)RsG%hdu4Iq=*5LaRn!*ltSub9wy>%SZ!w{I^wPqrD!j$Y z!qF=WtE%u83kydtEUc=+TdXS_y{@pT3U9HjaP+dmsw%w2s>0E$3ahH{7K;i;FDk66 z!dt8<9KEKns;a*`dy6H7qn8vGRZ&s6v!ZbHio&WYyfty&@|wV^D!j#-z|m_0tE%u8 zYXV2F39PEZTdWBjy(X}#3U9F{aP*qMsw%w2n!wR(0;{U<7Ha}WuL-QG!dt8f9K9y6 zs;a*`dy6%Jqt^r$RUK_qRGDx2w$ahXsw%t%v{9y?zbFmto8uB1+-CZP4-)k zHma@MZ#mjnY^$Sn=vr?%+NieD zTaGqX+X`<1ZB$T3;w?uT*Bxl1R1PtO;?&CRKI()xTM7h|jAxT(LC~3imliKe#N%(icM`* z$6wt8ZHTR{+;906TeYq57J*1yu~k*!EnKmw2b$2e^A-}KdBwKjimlpKcneo-QcdP9 zzhYZ=T(LRpBiH zk&^?FRaMMe1R^H~BCD#Hw+KW|4n$T};VlA@lLL`eRd|a)c)Wc5 z_VMx6%gcvS2Jfz7{uF#`KWhs}%=K^*v&|hJA0GvMLKXkw!%57ls+)QNiMjSn;!{5s z+v=uXkY6HIn=q?wbyF_@LZoUFW>wWqy#NT2s!f5Tdpw-omrx3xE)*Cf>rU9m zFj+60tPf1qwJ!^E^}@OOz+7Eag||3W9}a|^zO3_IQ_J`t!qi22%C8^_GrwOGgURk$!vsT5nixbtJdHPIOv-9IV}%ymqV486RER>MbQ- z)*LL}n!I?cD(jhttDZA*|4m-KRhE@etrL8sq_{U**py}c*Z07#L9({8Da-oO=3oKW zx-3!|9<9+10;`Qw)|QJ_Eypr9msfwcZM|q%s?6QxWh_)id->${@-z0l zO#82E&bOV<-~Zy+?JcUZ%FBj*M3az4p)l5EWaY4Tqn0$-p10~Sb7^v|Dj{)@BZif;_|!a zZ?*io^fUi|8$bBuwH&YCU%qIWT$j&Zz5L7N&o3VSc=_~?&%gif{>|IEA6bqjeJD;J z);lC<=$Ry2`gA+xlcoS+{d;|f2n}IvOgth&JG8QUBmWHsA$~;U%)%vVR*hpn~DC`bt8p1{@^EeGv z>nC-3o5RGEirl(A45QZ>{Fk;*()L)B7c9;;EV7GoK5HB@b+GWV^jTB^)_tL17j zmLXX~j|oO9^JooSw(<3cu#w6cDJaI$SaxC-2jcT_yEnuAG5Wt#Q})%JW9!$M`6K1Eol4CxzcghXXM zVa2M2%JfT)s)fpszoBXqmGz7jtClMB0FI&@ddP}lF_y^}8a0BeOtCCJPtcY42&;}h zRXZSqLrPL`pq^q z0`?dee>J7t2v8ZGO<5Md*;d9vWq3D5*l5PsI{MtUxY;Ibq_Wo0hNa5<<&<(GKxKG3 zMb$~lxDPy5BdOx%|o=iXB{TS%|&~9La#aKq~hqgZ= zEL2ACht_)$7Am9nLlfKx3zgCPp%Fd8LS^)R=*t*kp)z_uB(n$$mC^gLMBa}H-j9La zk0tVcOs%8O-voL;mdN`t!TT}L`>{mcj|tw7f!>cL@_tP4ehl<}ERpwPg7;&f_hX5? z9}~PE1HB(h1qC@5j_S z+8TkoACdQCg7;&f_hX5?A5-gStClmy$onzD`!Ue_u|(dF$wSMO1S&s|3E#}auzCU`#vdOw!P`!T`$G0^+5MBb07b+k1CRTgcL@_tP4ehl<}ERpwPg7;&f_hX5?9}~PE1HB(h{mckEwO^ z`BOvh#}auzCU`#vdOw!P`!T`$G0^+5MBb07b+k1C$Fj)#F~R#W(EG7O-jB&&Tv-Ns zKbFY*F~R#W(EG7Q-jAtuw6!h9vNiI4O#bMKjtDW9t&#U*g7;&f_hXH`9}~PE1HB(> z`WjBDimm|I617AjjK@5kIa+ORk;TO;qs+&bE@SeLDl z_hW7yZCIR_t&#U*ZXIn{sx0z;%&ntO*pc3kHS&JUt)mT#o%}WOe$1_-4GZtb8hJlv zPc>dfq#A2uNsWK?CA%5kkCEPwHS&JUt)s0GsItiWF~j>Y()+PS-jCTILs8pOWs&z| zhWBHn_hXH`A9L$yYg?);@_x*%qt94+Ki0_mF}IF3ELGMIhu*~m6pxB#ct1vZKi0_m zF~j>YBGp*?tdYv#{TS)}SR?Pp?2n@8Jq)TW@_x+levI^fC^RJb)U>X(UjkJYc|T@& zKSrb)YY#iw{g^$~SZzy{Mc$9Ob@aIr=>1qD@5c=9$4Kvo9^{I;3}YF+A8X|OnBn~x z>HSzE@5c=9$4KwT8hJlvPc@bWjw*}1A2YlkBfTGM$e$1_-&))=kKi0_mF~j>YPF$Bo-j5mH zkCEPwHS&JU$o&}U{a7RK#|-bsNbkoQc|YdX(bi=g%OdZ`+&bE@R9WQxm|I61mMV+9 zA9L&IGnU?uHS&J+fEUA3Ws&!z2fP@T>$1rE(F0x#OO-|5j~?)1SnhsA-j5#eVpxu4 zk@uqqycm|dACdQ?2fP@TDvP`yJ>bQ#R9WQx=m9T=rOG1jM-O;8W9j`^BkxBKcrh$h z7I{B8t2vdH_<16~YEl||l<9`IsVsx0z;^ne$`Qe~0%qX)bgmMV+9A2YlkBXd92 z$otU)UaVTGEb@NL@P3T+eyoxAV}|!*r1xWuydOQ_<=hDLeyoxAV}|!*r1xWuydOQ_ z#j2&sBJalx@5e~*#~OJ*dcccSOO-|5j~?)1SgI`Ye$4QGjP!o2k@uqqyjZnVS>*kg z;r-C_lWx*jBk#uy@5e~*#~OJ*dce!M5$OF`BkxBKcrh%;vdH_<16~YEl||l<8QzbP z-j6l%e)NDBtClK@ydOQ_#jsRacbx zrT0V6uq2y-@P3T+e&}6`2#ehhdOz0pdq2+4Wej&8PUGdXzr1|?>cii>dV89uwuu-yS9?;pVZb4MDk5y~+ zot^#gFUUIiiF=jm8$0{q9}rR1@YlD1@9P{mZx_|RAJtl2TL+>RL~WpV2Z2?pYm09P ziyCMPPYBD|=R>rpiMDXo&KHD5O|*rh_5(2sq9)qHNju*U7B$fp4%+#Au&9Z)aL&%x zgLR~4CxFFY7LM8Zc(AC6ws6YMw}VAZw1q=G-qAi@U^W|Vs6K&y${lF2ssEM|4 z!p?VtMNPDY1NH+4?4l;x!uk4v^L0@ZZQ*#Gj|PjHXbY$72Ts>@uAFEKhwFSYSk(7v z%cgw09-P1X_J_+aU;g<0i&sB>e;NK|{NK+mzrO$J^2zHr_m_XYfBxq3!8mN18r~iC z6#8xOlRnLCeRp)5{G_j!`{YbeSR1W`^%bSCuBg@u6|7AKh4tY|SeH~0>nDA}`tGQ( zuBj?kfA=`S64qCg!n&xcSep$B>$5>&T~$@AzMNLAuPB9eSyiz%A5^tIAKd!o-_vZU zinR%$us$Iawt*feSyimf2(=<}pR=$&YE`i|B@~t_^OL@+%34RCy9~FyRc)lQ*3pKg z%KW6STCLymRwGble$rRQst>GMs?1ON%2=ojx4hN1k;?p*w;F*e^OL@EwNM#ud2jvl z@AY!K2=MV`AJ{7TBr=SytjV&_j;B2 zNuR2v%KW6STrE_FlRi}&smyPAuLn;0gpE|@Cw;cGxFp_m{UXzP-P+0sG;{ukXua^)`5Vi^e+t zLTkEUzny+)`s7$GtbL(1*7lLp=g4REBwws*P0UCNj+^p|T$85mXD6VIHJvBb9l2 zi>igndZ@?M)heUoJZlpcD(j&h0TwEQkxY${sBHA~7F7$C^-zzXTBr!BV&wKkRs zOO^RNs9LShgM_8Z+)-A>n#zR5Sk^;5u5SeQlnG0f_4?ke+@s%Zq%u!$Q6o@gp59V!1gMOj&K~L! zGy-Of^mO)6j{pmm(bL&OJpwFLMo(uC^$4&~8D8$$dZ@?sSod`5go-M2PiOU);4k+G zOO?5&vy6qx=;`dC9zi2OW%P9RP>%qM86!QNJ=7z>LS^)H_E3)i3zgB+*+V@7EL28M zXAkuVuuvI2ojueez(Qs8boNk>>#^?X)PXHk=AO=~9Ng0>ELG;7&N3D%qo=cndIXIC zmC@7LLp=g4R7Ou{5A_JJP#Ha)J=7z>LS^)H_E3)i3zgB+*+V@7EL28MXAkuVuuvI2 zojug!daQdo%IN9rp&kJi zDx;^fhk689sEnS@9_kTbp)z_pd#Fc%h05sZ?4ce37Am8svxj^xMNdpfIf za8IYORGE7^%UGz4p3d1lon#fiM$`9dp}eyRJOPWw)nl3)6sum^nP?}=l@O}*Re&_+Y zs1aOc1HB)5k}blz$_9Er^h8jE^%cL@_zLED65t#>vsXKH5c^&sWX<|k0tVc^aLrxa>f{WKYE0eVX3mn`_VI` z3`>p@gm!_+SFe)QnB z^B0WXkHz!6%8lT=9|OG~i|2Wjv6wN^`>}YQR~ZYH(fhG@o>v(QmC^gLc%D}k3-8B3 z@5d5(KYDQ6`IkWN#}auzdT^UzsWQ*=DmMaDM(>B7wNF&mI@+qG%KYV?a#f@jS0`+d^gZek`8nRmH;lG0^+5MBa}H-j9La zk0tVc^x(Gh@0Q+=#q+$%jR2L=`=L0C{N}YQ zSGiiKjNXsM^SsJfsEpo^#q+$%Sg4HNkHz!6s#thG26{i1$onzD`!Ue_u|(dF9^7{R z-O~H9c%E0e5uh@9KNipPDr2ECdOsF_xu=YU%IN)AJkP6)h05stSUk_GjD^bR{a8HD ztBi%p=>1qc&#R1u%IN)AJkP6&h4*8i_hX5?9}~PE1HB(h{mcj~?7+ zSnhsA-jAtuv|%}x`O7`!E`!SG{aB*hkI8dClmo)^vdH@}!TT}L`>{mcj~?81Zd>Ml zERpwPg7;&f_hX5?A3eCus^uPI5@Fc3`ovxBtC?FzTeVbK8t2vdH@} zw~jU}RTgKjzlahNa3P??(@KF)URUc|T_4evHih zSR?PpjNFfrxgTrf{pbNN)(BKt{sekJ;aH+eUgn*2w$O1756Jsx0z;%bQ#oH0h;j~?)1SgI`Ye)NDB z!%}6D_oD~A7?vuFydQJx=rfkyk2Ugs%>I_!Hq!gCM&6Ge@M6_cWs&!z2fP@TDvP`y zJ>bQ#-2I5WA3fm3uvA&({pbNNhNa3P??(@KF)URUc|UrMc$9O zb@Ula@5dT>KW2Z+Z5!$RSR?O84|uU^sj|rX(F0x#OO-|5j~?)1SgI`Ye)NDB!%}6D z_oD~A7?vuFydOQ_#jsRabQvrOG1jM-O;0EL9eHKYGB6VX3mn`_Thl3`>*kg;r$rt{a7RK#|-bsNbiT<2v7DHk^3>y`=LjXBdj~D z`1aj~x9_S4vdI15+jqk16LB> z#NzF{O^GnREsVGC%2=FA^UW8$eOJapWz79h)J)K2c>7L`fUyj3-<7L{%9#6sx9`eW zsEoNEc>Au5b(Qh$yA5yOm9efezI`WbqB6XFwGM4p#7sF!4xJBNN9`IsV%oycyO;iT&$Hd%^E%JW!fETM4GsZ3Qe)NDB!(zrL z+eXv~P#L`+Tjc#%T1TI&rT0TeT~W0@mQ8%~WsAHYJ>bQvrOG1jM-O;0EXT6Q`?0|L zG12>>RdCX_t)s14s_gyVkMnz&UwryW{q4&h|6>19j&yK_v}xeeZ(sKK7sFD6aE4T| zKGG>K1|NAiL#kM4kj{_|sUTG>G)QO224_eW3k}j4vcVZr#rk|wc`FKGepnrL|CYd&JevX5@De-rh@3PiUbR1i1K3iOYr$*vCEJO zqP!SlBbC7!GSL~b!5LDm7Aj*Z$OdOf6$_Oy6=Z`mq>6>gm@dq>Jx=#aS~n|nvf zSd4b`j%@B7DPu9((L1uacchGk%9tCnxp$hA4lp6sm zqjzL;??@R7l`%JDbMHtQ3zac9WOMIG6^q=EiMb)0dq>JxsEoNGn|nvfSg4G-A)9+g z%2=q3xgnc-N6J{JjJYA3dq>JxsEoNGn|nvfSg4HNk~fQpQ4M zd^2Wq??@R7l`%JDbMHtQ3zgA3vblGpjD^bR9ogJFQpQ4M^p0%q9Vug>GUkSCo*Pod z!aJfw87xlSJ5t6%Wjpsr+&fanLS^)hZ0;Q?W1%v7M>hA4l(A45-;CMaJ95UJH!?nX z@#@~kP^M3FS!=R3?N zntv9yIoc29e6m6B$qw&HkqVL0da}cMQlvtobe`-;9Vt>FQ5sKngpQP`JzU1x6$;&v zIZ~uTptPOrh#Vo z&p!Y1cfb7YvyVsZMY;BrQbVjdCcwJ*X8KWf_oGy+MHY!tYFMqh=K5-pMWU1%V)fk% zu&zI))DWx253nvkrPL6s#t*QrK&8|G>wc7Sm$?L$QbVl1eL=O*ApI!2`%%i(`T(bt z8de*rtQn8a;-w#DcRxzGTBvNmS@`aLlqwckBuc4aBSb2LA4MrO#6~KEA4MrO#6~J> z#v|)8s>~fH<+g>&m_@R?*hpo_B2h{Wv60H~4vkW3h>gZFyhAh7 zak9JPq};Yp8679PJ5I`2sEm%2-5n=oEL29v$?lGmG8QVM<79WoNf`^3(Q&f71C@{_E1hejziXxqq7vbK)4YPl|p{3Jbe=8UDE zWRLtLE3!zGQo}}w)@7}uty=DWM1GRBb+lorvdB-e!cU@<8a6_tGQ2~hlp12A8Dr~c zYXqt+@{{z?8N*U#k)LG6J2XnEK_f(dlC^cTRZEpcev%bgBuc4awQBt9H&u{DqLdn9 zBbBv|J~smWBzxp1SzAXNmMV+|^QT{YHwVS?Er4 z(A$he4|Q=)W(%iw?Ekcptv|bE?aFo2%^LOpIcwB1{{HgC>u>&a|8W29<(Dsi{QkwO zAHTnR^}~;EF8_M}{LSTq@$T}gFMe?u{$>2%&n~~d|LO9{>o@oReEHztKmFpvyJ6b@ z`3hrITOgl)U`qGI&(?kT{UE*YyKM_(!*X}RefU)@eE3TDWVI%;G8Q}S^x^OB!!Kj8 zJ3$}*?mql77CY_q;qUIlFJrMgK_C9^KKwEkyA$-`@9x7dW7W~;9~gc3yZi9VSRcof z?uj3m`|!(HsEj`R-F^6FEL27x{_Z~fDi%I`rF*gwB9$S-QR$w<+8$uJTBwXZ{M~){ zWh_)iAO7w>{4y3QqYwXZAAT7NmC;6jxQ)Jyh05roKio%O#zJM>zdC&Xs*Huo=%hc~ zNngf7Wwg>CZly0`dsyfB3&siK;VaKF7GoLB^oP$F%UGz4Zu-OB^kpnmMmzoCi_bC^ zDx;tN@JVAC3zgAOf4HH(jCGYM-P1pehp#`&SXbFX&-~#Tj%BQ?Y@uiV@C?T?)>Wo- zPd0)Y|M5_-iiKx>p=bW^497CoRkqMGe|Uyt8S5%r=$St}!?BEYl`ZtlAD-b@#=6Rs z?ujmQ&wLr{DpR^Av2F4E?h(^67Am7>{&3HH84H!sGkIRs(KCOzXTFMs zXI}Z8kb`^X%UFzM^voarerFkrv5cPi!&4f|Sg4Gi`NQAuEMuWEdgc%J%$KoH89nod zd*;hnsEnTZ!#(q5EL29%{NbMYG8QVMXZ~={d>IRs(KCOzXTFMsXMUk){&3HH84H!s zGk>^ezKn&+=$Sv+46${V&LeKo+8H{BtRK^U(!#(q5EL6q}#=|}H zWh_+2493Gf^JOelM$i1=p7}BsDq{xY;hy<27Am7>{&3HH84H!sGk7Am7>{_qUOG8QVMXZ~={d>IRsF@y1N&wLdN z&-_Bq{NWjlWh_)i&-~#TjAblT#tg>8J@aKORK^U(!#(q5EL6q}#=|}HWh_+2493Gf z^JOelM$i1=p7}BsDx+uq@C?Q>7Am9n0e%??(^Yv__!HBJW2J+cd1JOc9Kh+Ffo0jAihC2&+%r_2*^CP+Z{s5LS&JU@?}# z`ys3*5&;%t8N46DY9bL}F=K@HLs&Kb)mZ&M^FasR5B=Y3A`xIQmcjcWtQ!AsW6yW% zzUt=FpEEwcdH%!y$@d)YKAc7cd`=&Y^@L9)_t~6i*)bxB2oQQEvo&9id6T)it1l#QSCQWrRwh+2Mc{HPMz&f<&dZ zd=gY_f!4*=uGE&#fvQw!3-(vFK%%YI#a1h{rRR$S6?lfU+7;T;>%|Eb+QR&2)#JtQ zq29*Qk4KHr(EDvHy^W=}vGg{U-p10~SelKcKQBN(`^(GMuRi?EtGD-W9xlJtQuWo3 z59JGw>z&_JUUdD;OmrI7ZF1ZGhr)8S&9TlC8*D#_Y756I6_Z=+K8R|Q+ZuK7%?Gsr z7LF4(A4)ASv^kcw04BE+_8y8^@;H=rwL zq$b+(>n7SWrM7V0q}HzfLW8K(7H*pqsje;EH)9JV+G>}ItX-)s+%+lI>e|w6Gt`Q! zCPk`iOP9?^O|;dz_}l`xXtGYYXi}^d+QK~(Q4?+X(+rDlnz02EZM8187NE9p%cRx< ze#u0&Qd>O>`P#3Gzsn#hwKdv?XYrfm&oYQgZQ+VZu?3(l+%VB^z&2&7wL)9CV6slQ zU{b6V+QR)3QQxPnE4EL@E8ZGgyVw5lXQ`A&@9J%E3wEpT>8W40+8fooT2%XtR;kw2 zs?|TEqFPs1sn*q^`e$?-+<#rAT33tepHWd8=$$aDRQrr7JkzHrqP}nc?fpST`VH7; zR8*g$h}u+hb*(l<5!FAVqS|M)+5+|&71ckZqS_RtNOkA6sQwuhRSkc23wT($sMMAl zudB7%6h%~O%YD~XDzru0_29PaDizwI>w0k4b(IQj(R4ky>AFgVw&=MY+;d%}LR++4 z4{o`xQlTw6t_OEqSEe0! z@?pfXwGfZTk$qXP^j?td&=wI-u1H0-Iisk)9uu`q5#FtFs#KdZE(?+!M78x;m1=WF zQGGoos;$SWRGTx3>gzF48|dm5usNfsz8(|R)?>w5J=H-}pEHVT>#-`;=8U5HdQ4Q? z)~Zr%JtnHJ$3(Tgjw;nAXrlUFhp4vKQKjnd&e}qv!-7PIDizv7po6H1wptgTYek-e zsEM{(7aNt@@;HZT3qV^)b5N}fbgi~p7hA2=mWMeMYxOLLg;@@&HPKe>I4 ztEnyDN36C0w1s^{)!IPUYRjKJRISvO?<1aSJ?|g4b-xN*hpoV zU}#-IY^1W*(dV|s3}c;qhEZ+=s0?{g!bU2?979VBHbSH_Ofs~#AU0B2n@C#Q`V3x; zU@EJ&Ev6Y-U9j3nWv!#FTB^*?E6>%QhpwA(kORuiICwJ--i(7ts@BxHFj>192b(wa z{8hdg2XDr~n{n`F9K`8`mR5F~v#kXR-`6&YJAYkpdLgPUflk!(l<$cQgS(HmdWONW zxo1i{C_cy6zKqTBTY*phOGWjC^a9V6s5Zr~QvK_^;GkDjo8ecfYUfk0EbvT;Y7_h_ z)#vvMJW~sjDyvlg1uZz}6}5rh?V?qwzJ^}lnG)63&{e8$ROztJ7EYqt61qzD6||02 zNNt;ZSGRyKptYGysx6?4wYq0&VMe7|AkkLq;`8qn2fd;u+G<^FR9`)dnrN$au~B{T zENY^yW{WebubuT|r+uBPy#;L{o>J5Xy7rgVy7*ix(kVqvwAH%UsMMB+Q&w95+Cny^ zYE87&y4Y%^wmh1$SgR*fE=;CWt?$#;6=Ufw59s0k&5P$RpM6~F6(u8hU*Gb8Zh1hr zJfIzKVk%+g`tRs^*CL-z-_iY+2ZT&Swd?hB6kVJ5If`DywYlFd4@g(h-#14&kEI_i zdb9b<*FV1c_VSxwU51Z_vHdST|JCLH9IwASO&^Et!*QF2D^An<66EpMulol+Ki!64 ze!BK0h*7=oMZJE0Dyq#-RjbcWw;`CHifZ#yQT+f_)a&P`qT2j)-7r5D^?iN+_wJ(k z{8Ut*pNe|@+E2CG{8Ut5`-vKSSNjs={2O3&`Vh=d*S-WXs_(0)*7wa%|6aScE;gzk zor?OtwckytU;p@U|MuC(e|`4Z=U@Krm%n|cB(IxN`(}atqHaq4Z=}>G_j>DFy-Jz4 zEgp>@K7=Ym_xkCRs5X5P)rU|~uOC81wINhgA42y#Pn;<&PervMR8${AMZJCq71f4N zji7Ep67~8aR8-sI5!Hn$>h(jYs5XR(>O-ig*AJnh+R{W+-{KMV`t8$g_rw`dU6`U? zKZJ^EL#U`ego^sUA@uzNv#74E6$i(nCff4E8P!T{dE!h_1+9x8Kl!3kTb?*mrMkAX zuCis6zCMYzJaI%>WMR=Qd^!lQ>8*%NSsj%yiZ%_N$RK_v!N@MEjd0akp+flBMKu)`scvJ}dX_5m3vyMey7>Hkhl^dc+6Y&rLWMA~i)t#Y zQuTLMD@Qo@uve+j7A)+VT_)OUU2L^-g!2n>)mot~7}!;7qAmBYZ^}}{XzUl{sQcTeu*nm0L1y`31Rc#RWN06K(kgIZ>%CzaUp_0cZ;s9x8{&3Memf?=vIW}9NRQv9+p{^hXLIzpiLaM$$K+}On@zMK z@X3{>HeR5u+cEinr)P6+$KQ-$~%YJRJB!2OZ%}^_&WKjrcLml{=N^ss!@81?}>|QtC}j+ev6{|sz%hd zIC!@kSEbsjMpTUPldoz{R9k=i@cbKPkbUs!>sQ~s_`{EHo`3!F{tEL@zpe8)+tkLq z|H{_I_u2Y+-P0Y>uj?4rx4VV);k$K91#9DX3li~P&Eh+4mEo zN#Nv1hdMW7ZwE(*s#OBD7VyoVRnd9pk3_Xr`%J17TYex|ZC7Xu2ZH)OC))Bmr)mLe%MS#r zwL)7s5LB&+wmjNO10S{J2ZGgFp)DK;s@6nXt&7jU0UQX5`aW%4F__*qRlsGH3}@Vf)x+&Q^1Izu5Bla~Wj^k~>f!D-mfptF-Bu5`vGg{U-p10)R6YaI z3mvvlo)5hAz04liSz6Rp&Yq`VWiKy?}gnIw>rZ(G6TcT21 z!QqLhrY%vat>ExPRMVEI)K+kKBC2UiRB9_YJQ3BjB`UQQ9G-}3+7gx83Jy<1g|={b zvdqEZiKx&P4o^f)wB`4%7G1Zr^HNb0ZQ-SFUAH9lecC#2@cx|7{nf8O{pvsZ1*CD^ zFCQu#L;X}9L$}>S8fB7jMamm&qg~%7fAVxhSd*l%E=gf+xGQ5#lft?tg|+dnj5SdT z>!K9a2D~!XR4J^hQn!0;#4BS>mcqI$g|#8Cj5S?uE20{OwK1=ZHDL*rB{=wSbxX#$C1c!@F>c8i@(bCj z=a!727O=Heo5dHFT5fOq@0E;kdqc|C56ZjrnN6jOw5Yy%C{k^SE~+mcMD-I?Lr&EAij$JKVV36H40 za`@ToeLd9{4$FZp>7UKs*HdkEE~E8k}mcZ zwxkbiNvqaGTiB95uq7>OqAhGmAJ~!>HPIHfqz`OKi<)Q)Tha%%q-AyXWqIv4fGz0* zThc$9y{}dQwxkbiNsH=>@?x#f7A8DDo4v2E723j*(|EcH=JQ?jOx6)@J*vmMU`}W4{qpP?;MUg{8`x z%kBCuYaMNkK$W#8D*`N3wozqAYt5^FVD4p9BT!{Wq_Wo0=SJA6vKGe?R11~uR9Snr zBEUjr$Xrp9Z=^DRn`B$@Hi@v2%34QT+frpmq_Wo0hNa3pcBQH^&s|X?P-Xr+Nf`^3 z;e8UdZKSf+(bfo1S>MmN{s-1N+OSYr-_QuKP}u>M4gN$)xox4c11cMu%Py!EDmyTi z4b5g3U@?}#N~yr?L}l8f@Gir~m9UA*v`YajRHiHGK_h6J0$8YQz}8i5|hnE^)0Mz!xomRja24)Si(|e*u$z;>nhu@iKS|j8KZVA(6&?=cCo6} zy2>_eV=0}#fv%k~YR>}IQe|$ftg6g6vbGHyS*kWtnVTzxrOMn~S*{i;!&a86ja24) zS*n&Q!(LYLm*AUO!eYj#FrDO=;JaDEQf1i9s#Xh?VLMB08>tL|^$OAQL)-!TS=DNx zGHht=L;p!#tujxjP}@>vo={Q!-L{TCO++_DRH)iWWu8&7ZOEt)HkmOVt)s14&KNzU zqTC1=%aBr`YNHur`_EgoRGH^#RjX|sZCI+z^R&uXs0?{pYJ^B-t)s14s?77W%GE+; z%&s4hU0)P0!t1w@DnodE6$_Oyy?#J?eHDutBjf7_#Mf7`P#N><2jtgRu}~QU?0XL2 z_0ta|*l$d*??He87Aj+e{eTGjVk02Keq)CHfDHR87Aj+i{eTerDi$hZiv55T`zjVQ zMg%_Yg9koVzX_iBxNS&$6gC>m5M;k0@=@6Lj%9ztimMcbhu5zzf4qPG?d6;2KV05^ z^XC4~mw)=%UG&rC?xSmR0XIKI*F6Vc=C3+VJ5S{Fn|}JZNkIxwjRFxs8a2>B&vV0MQxyW)2%AiKG?eG;Tvh9+E1xUwePj4zV;B+eo0lTeXd3I zNs*{(`0HE1zSg4p%0pC}6BTRqg@>pd)h0xuQd_?4 zs8XRVtU6R{qOI1&)&kU4|AtGXV0`c4%Z*~Y`f8(vVY1dlTdj+&R%*)^8>d>&L+Wo| ze1HG)#UK9oaQR*jsy|%5dHLe|ua$uO_QkjN^?Rd7n{quCqj`gOvIcnT&9EI18%t%=VZ9$y789lfLpFrtaY>+!8=-wU=x&bBiL6|Sf8N?YhTea z);^=c`e$?>aLcvY2sTF%*1w~|wjcPruXDLt`;cxMZ@CV*{V9z+k4VsfW?fFF3cWv7+|3?x-fgzVSvS0Mi*ueI}EUxG17(E(+;o2?n*E8 zUjkj2W8%UT7BfcNAJ#7+P?@k;m*E1ju)&N`Sf~s)h=mQtGGU=Ix-fg>VbEomG2#yK z-ZKvatgB4r`-icI9tK!f*^XPps#c93U|nU(M_{$VSf+oot8B+TVpXfgzrI?yF!csH zs|{w1YD!m`;&h0OROW}En$%!jHu@oGZHQF0t}@+*W3`dW{4%ksLH9v047pV{;4o&yb4^7+eywY3HAr4JNRl}b?^hGLUh(l9RU4}&}RER@U zQC)>aDuy~7nu_WotWjGRpT8J5G!-?`mLHmG;mUyy7R_R<&=wtaPo&nLC}CV>9esPsO-JW9A5BW~~L_%iQV99O26>QZa7PmN~+fS)@W+bY+fk zWfrN>7EPHWOqoS0v_((m2v6oC^*nQWGRE}wn)3addXTANkZdSXewt6yWc9LXnk4u1 zBt=yFxr^#UNi&cM^lm~`rP|M3RG+5FlGKg`ucq41T~uE$iQ3A$nrc6HrtAE08SlRR;quFuKYst>)sNp_hJP9V_p{5d?|-^{^7_sF<%`$f z{OSJT{@csH-amhH`JkUvY0~=7`%T()gHJlQrmj%$q`mmTcnEW6KPRx zky@qNB2`qM5sGSy)FKr(b9Ua$8U1EXm1>Jr)#{5>)oP2>D%BRLqWY*Msx4BhRCV#= zf?8Bxq>5@AKvk+OQbqL*pnddPIaR7{0Ey}wK%%xa^t%n9Dph}XZUNrO8U0R9l?rX~ zO3vt4a;j8li#KvczmZd=LR-9$Gx~*`A{F;>cHYMs{XR~W3T^Q^&gj>1s#Iu;w{i5k zW$?>tU2MNBYRfO8*%ynZwK^_wac+T!h- z(Qn^Wsn8ZL-;93wrbxxzo1J%WMo&PmQlTwgy&3)LO_d65@#f9wH*cy`Xp0wbMvp(Q zQlTxTpO1d;rb>mjcCzXrb>mjc;ROB*z+nC+Twki(eK+-sn8Zf&qu#*Q>8*%JJwrM zyM%G|$_STjc3!rb+8vDRsromawZ*$OlP8{6TL9YPRh!8J&#P2ui#Kg1&pWSDp)Fpt z!Rc0wif8(CGs+L#cRbTqr9xZ0W`k$?s#Iu;w`_2_Ri#2(ykvuC`l?iDi+5}$Pdcws zF>djS4NkYJRQ=saTYRQ(?=GTi72EUdjf#CjJkwXL)wRWE`c$hL{`y*7TYRQZR5kq7 zRNSuNGkv1AfAp0*Pcj9ex3Eu$XZnim>PE4Rr(3F34S#*Dt}Q;(C#o9$da7%S&-Cqh zrmxxpt}Q;(Cu%Tm;dE=`Gkv1!qjr4@__%ezC?={J{(3631*4d#iMDX5hR^hgnrO?7 zVro~8TW%C9{swSYhR^h=RyF+9?b^Ed{3V1@Ow>eMe!8U=z&_#RMzLxOKwB`1?RciI zN`M0BnJN|9;$4}^@5)rE&=!nhYS%y>h+fcV()z zLR-8mGx=SaDph}Xu9bIXCci6Fr9xZ0D>M0BnJN|9;$4}^@5)rEm=p4@%;a}vid5W{ zQLZR{S$5?@A7sW&Ret;CnnL+Xu6Z6&^p zo>6a9j$4T@qes*mmE%_8%jgO9M&-Db_%eDdu2DH|CBBTFifdH(GN#0r(L-_1RQfWe z#Fx=CagEBojKr7GBXNyNZ6&^po``EyYAf+&^gvvrQd@~HqvzoomD);t89ffysMJ>C z%jjviMy0kAUq%nZH7d20_%eDHu2HG2#Fx>daL-iwGN#0r(UWkEN^K>+j2?t*RB9{n zW%L|eqf%RmFQdoc8kO2gd>K6j*QnH1;>+kExJIS65?@Boz%?qhmH0Ax1g=r3t;Cnn z6L5`6Z6&^p9)NqM(w8wMzKouKYgB40@nsB1MO9ud)-Z`Lqo?0mt<+ZH%NXFxP+Bf) zZPV*(_c9QPs<2#Alf4WiqADww)MTF!fvAegB{kX0Kpv`+azRae83W=_6_iVAvImbe zRORH7n(VnXX`AJF9NevZC7{`7^9q5U?_SQ#uN6%wsnJtuowVmH+Yn* z)qno+cPlJa<_?cC)>I}ehd|E)Dr0RwUs$TlJsxN5d1(FWhv(nu`LPc^ef{dY7k~Ki z&GWBc-d}Nra`Y?DN}#1G-4xO_TKMeyllLu#7xM;pg_N;SC2b+I+d|4%s1gA}x&dl) z(kj-CA!-Dw(v2ZyEL4dIAysQDzB1OvK2=Lqx;3PXg(~R{ncW*w#zK`ehs;P3YGccP z{cg|l`DoFVZm z`(^p9JW>6FC93UE72CCS@mU49l_#oyuO4eXEA_wf7;kS`|Nb|hfA;L-+gsL(c65R2 z9pgZtn+Ldy>H-xt5a{MsQ&C-@q6Pxpd`2Ov3slrVpqpDwMfGXEsP7Z#FaG-M`NPAT z7gFW@+h-sD_1R~ifBCy#{`T3&y2b8RQ&D|BA*#NN*M9gmx0;ITgP*9u;J39dK7FDT zMQYPky}4}Hk7^&j4Vi?ux2$h(S^u|s%en>ceEs^T{&w}{?Zfj|-@g9tySMfHozZ{b zS~B?TP8l~%Deq=X{X_cX1o!8+B_7q-9-}Zd3TxB5GS=pI?KKKwZTKi-ZGtDPj~}Ym z#*Z`hJiqzf|D0c3e)s(CgI4ojJb&|W`M2?dPhLMfy#D_3#Y;8eoRCRvr60ADrdQaH&a-bK^1E<5Y}ZNtjnN^H5mx& zG7#2fP{rCpM_8Xn32XDHYL|I#masmN64oYCWh_*N;4EQnCRN5lWk}8vHd0yZ=*RD@ z8i6Wvi)Oi6s0`Uz%j_P_G8QUBc$Tn{%34RC8v!m&VI!5bjy5b+<~Gf8BS2-y&r-FK z%34QTwN#lKHLKNng4S|}1T9q?sjPLhRqN{&VI!6KZk?*-Sms{Maw9-x*sfEx(OA|x z+8TjlnY%U1)k0<1uv=!|uq$JsGVIt18>y^y^tlnRWhZPKW*#S?#X+Zav|%}x`JP?5 z5uh?`+Ns)TEc0Ev#ubTC0qO%HZJ?Hd2|JIF~z^IE9T=<}ca{%dyN|oaIKqSOy!Xs*T1n_i?IPs?2?y z)oT4kdto`2xskJs#aIR>ry3zzm${Ww)pA|t5nJVIF_yv0xyX%~OqM)kOVwicV{ubv zxmu_Urc6~EsjPMMc`Sn|Q`kslt)mSKm1%JuwJlTzQ>Lm-RMx}PtXil{lf9tYo~CA4 zs7xRB2n&_Ll&MBYRMzvR_mc#!ct{! z$}D4DWqh7djS#8K-)B^{RGFJH%hmc=#s?Y~JkVIiy2|)Mqp*?6++-=KQe|$kELZDe z8Q*ABwUNr)5TR zDMF19sjU6yt!=3?cSV$|h00)ySnyP184H!+*jU&|Wv!#njeuigVWY9Eb+lozlfQIp z_SJG|9c@^u49CVz%1<8}_M|n#V)tY57_MrUc@CFm1yq^8SzpHb?uXpBn11-9^<^wn zh9oZi5+aqgj<&X?%KX{-a_e0rjtTr0U{Hm7rk*KoB`!T`$q4YLX8+kvbX7aHg7*!T| zKc;5#Ib-SlSR(Jo1n-9e+}H?_%HaJ_f*Y~XSk^k)8i6W{ydM+1AIflJwUNr;{ZNP- zv60H){ZNVBJao4Og?8Uy&p^D{g~kW z(0xrdLZmWyKXhS}*hppYe(1&~vC&ut?}x5z5*w+^qq}sKi7Jb{A3dJUehE}r< zV~M;UlSg=|5va1r`!T`$G0^+5MBa}H-VX)4@dp--WuD@tMxe?f??+E+JBydzk0tVc z^r$w&LS<{@{g~kWP`I17?HYMMdRW`JT6#a$$onzD`=NL@RvV3F@O~)Yjo4@`YaMNk z0F|wg_oD~485U#N8hJl@@|t0xvNiI4^yD?eLS<{@{piVShQ(O6M&6H}yk=OcEb@Nz zqT1MH$ynBt*Q{EqEb@Nz*kg;r$r#44b+vIhF3&5LPW!7I{DB*3pKg$|CQ_4DZKC@5dT>KW2D8Mm)u)bFE}u zHn)yGHv+vMYvlcy;r$r#7@Mk1_84b)KSp{#*2w!YBllyZ_hXH`A2YlkBfTGMS?ne)Jv1+NZ zDEFfWycm`$i@YB_;Ki_1S(N)R!}~GP`>{sej~?)1)ly}V_hW|lV`T2f8hJl@z{|N> zdOs8s8MuIYz>8t2vMBdshWBHn_hXH6KYGB6Rm-s~@_x+levI^fD8DypTX;W4dOy}E z_oD~ASR+tnQSL_%crh%;vdH@}!~3BJYp~H8c|UrbQ#R9WQx z=m9T=rOG1jM-O;0EL9eHKW2D8MtVQi$onzF`!Uk{q3q%0dkgQ!NbiTjha)U@Kj{5f z-|zi6$C7^e`s>#Zmrs=PeE;Sz*F?kG>9tZ(U5!dbwOx|t`+M?s+pZ0#^U_#UpIC}& zLtd3?o?=m5i=x`8T9v9_!{d)zRF|Tt4fO7Wrb@LP5>Z`=qS`)Wm1-L#qPh_GzB_e& zt+qcRs*iS}+TEDG>0S8|*#5|Vhh0cvO^4MNMSK@hSf5i0YdS1r)dlCD0d^sUwY~l> zi%KIvU)Y5d*7Q}a)^{P*2o#v_LYA>m7)eVc3K$QlT*1KU1xy zuxhPP7_Oh~j2cY)4QB7S%s)r8m3>_BLMz5;4S|3}(a`^Ji$1+y`D#KD;zWG?jLS6_RRwJ0a%2?!4Mp6z$od=xfPnO{5;mJ>zad@Q#uREEt*RU4_yFP^DdF2sEEvHjW# zQ!n3p6qWNt-+Qc5F_K~HQB7de#3~gM!>uz>8|ai%J-nXOv zX07K%`|V+uUp#y9>f0CJv`4A5%LJEJ(^26!?k+7YU;WHYSQF&?9(MVE`$DVV7nIbv ziuOI@>gUGq3+{K=GuAIH`Z)TYv9SC&`kryQTIuIJ8O5Hls5DdiU{<_s_q* zeDnN=%iC|>-2eIVPs81Z(|GymGJdp_cO|vuX#>o^9CI-dMch-wWes;`tp z^#&|bt^GvxDV(U@enqMcFrxZS-=+)pDY6{+@t64eI_QT+o|q}umMRG++w>ffgt)%PJp_0N;2zCtQep)I_9 zB&to`iodMZ#g89;)kx~{HpbR z+By%VFJ3)7|I_{D{-=lgS8rdues%f!$M1j8bAvDMzk4VTqWkDK_B9RhpZPxfscrl2 zJvoSqYCm&PeFzcNe&$uG4I%p-&TK`sA*4#RpSh?$gotWC^D5Pb5K;YSE@}h48$_#A z` zsx1I*;dutt8fXizGpJT*3$HWOYQ^IWqC#7EoS{mEw(vHCS|HFCo@P+3&=#I%sMe~# zJ8SEpw)}Q}l?rX)VTN7N;n#n)rxwC+s+I3Dh#F`M&oba0RBFp_=2zR* zwZ%snRBNIwf0IGAQd@p6zgVkZ%NLc}@+TRpRM!??WKatv+VTe(R4cXRm-4H%>hJ9L zN^SX_{3_M8#pf7yJjYO_LR+|zFKVK#*2U)*z=eEK6K(lh3_IUq5VifIubdO&DF#t7 zC&W_>#dh`E_@Yu^=uXuN%N`@P20zxwbuuioCjdAR)c^*4Wd^<#Z&O{rtn8Ox5v@7h;Jk1}sx zy(hQUM77Qk)hFnpww8J~iKtSoGeq@Cgs3(_uTizoISW!$pG1giol&LQhfY+Vpo?mg zh$_`SbfWqsLR6ceSE>5D$4`=|K8X-j4S#KKX`utEf9Tf97r)h7?L((pebZJ{Tl`k3 z_Mux21k;IXlZYzSwRPZ4LQxy&N)_ngIcwJgi(gR#ZE2wcDz)W{-(m~+;#ciTZTaH2 zN_A}=Sp2F55^c3EKB?fiqqcnUTdh@pXH;s-7r#}iYwNh9wtVqhrMk9`J8H}G=&Dp` z3yWXnWF^}2#qV-p@hfU8?^t7r(_?kwkYO ziB7d9+VaJ(YNfV3h^|_z{_dj!v-K~qAi5>@2~-gnrI7|{X1*` zq9)pM8^E%|1|X`f){5_ zf3*dmE!Y6GvTUGhwbi=#Tq|qT z&*0;HG$;4tk6lz>l8737oR8+@HmWc8MGZdA$Ia&3y4c#)m-{!HuZ*Mb`#AsNug?_v z^5(_YKR&cuRDXT;+2>#W?w7xP_VKtL{=lW|sMOZY=KBw{`QC2-{WrS(cRLpHu}srJ z8_U`t{Pc#y?N~_uxARzbI~KYf3#kRDt=qBC?O5n`EOa{-x*ZGs1CNFN{nIZ#yt`XQ z{eOnbm-qiU)bG|!enEX7a6w&OB-{Gz2g^@RpZ3Xbs0-^Se!|+`XBlgA5@CIPEv#*R zma(?`DXi~)?u*}1FJo={Q&>Mx7uL2v%UIk0+y~rJ7uJ^8Wvm@82SZichWqNmMk@22tX(-3mh&!b zq%yy;E-Y2%H`dFI0F~j&x~h#-=6BXrEmh{5S=DO&(z>uznO|BjW7W}T@iH-Q@x;6` z7Aj+6-r|XQWh}-rCgv@8uA`-|6b5vEu0w6hvCI?m%GE+;Ow3z6G4G7M;xO-Kj8T~S z6{mU1LOB2AWj68A^=6E@8DnHLu-R+voLE^1{>!=LtRwmYMz3nqUzb(g7-SUXfWM?JsaX1Gsyxp2VA)m)(#cQ)#B(5ckYC3pObgvb{UJKJ6yUGHd2{yE~*izGTgdr zP4eV4W1sxmov=Jqz_q(77AnKNJ2iqG-BsJRb@bzhTh;RD4j1pL)k0;sd8caa=&oEX zREDc}yPRRk4-65!1Mc1l>syS~MzB4`eZU^0unlyz9Q@r>VL6uJ_Fc7Fs0`QdRBfa( zzkjD{sWRNZD^}|l@PwtxZ~?E1h01UPPmK_%tabERW!PyH)@&$MIrtqsH3DrYxPw=1 z1gLEHDdN835?&RHu?(Ay!bU3dYk2#BYk0!8`mR=)ClUz@m8~AfTkbNb43R{tHd0yZ z=<^Q@nMA@SGsf9NiPQ*C+3KN0#YUK0M_aWxAYVO|sEmcm5KE*+NK`hv0bPv%l__T` z_<_wHOe8E-=D|eeMu5tYOtfnsB&ycOvJufl!X_%4TSuRM2_v$JgiU6QvxgJyBf^P< zO;k2}I+3s#%T~9cSG&yPiG-!fJf5hGb(M|CCsHFMW7*vP^VVgUF|O`JFIVd`#*y*7 zt0xqdu|AfKh$z}u-%2cFU1cLOiiC|+);jv!wg@Q_Hd2|V6zwBYiiC|+<}pRWV)tWp zKYF=seJmT1Q>1F6v8;8pwJlZVK}FSSJ*h~Iz_H9N>18ZbhNvPnLNu1Ojua#;jf?Hbq#BWen@pCTN898RN*b-qq83%UuSQ zF|K!=B9*m{KL5Z*s?76xtJNZ~cVuAi>VdswEL6tC-gSyp);ii6fhzOJ-g322*~l5A zXZD`4XOrUJ*k%9SFaOt9KfHYL>R!9-AQ^$g%@wFm(oCkoa>fXi4+ zK6#&K_4_i2odSg4Hmc~-yAQ^rDNyw9`x zeV#HFD&u{g)$j9^u}~TB^Q?ZKr;LTlc%NtW`#e=F?(>Yi&$Ie{o-!6H<9(jh@AH(g zP#N#@tbU)TjD^a0pJ(;^JY_6Y#``?0-{&b~p)%g*S^Yjw84H#1KF{j+dCFL*jQ4p~ zzt2;~LS?+qv-*9WG8QW1eV*0t^Hj08&olBq&+7Mi%2=q3_jy*o&r`-iWxUU``hA`< z7AoU?p4IR3l(A45@AIsFpQnt4%6Ok=_4_Qk{LFVkv5VwvXRUl-Mo*qk*tx8WNsaOZUov$*2qRO!$vaF zMzTgWk{LFVkv5VwvXRUl->kOfc4cHEnPDRtX(L%98_C={+PaJ?i))pGYEvXRWNktn_0Es@G* zOvW{PSWP4XEXFe0NY=mZL!(uGkA{$A6xBHBxjbw{#B>mxT!@@?gMK+TDa<^fjvMsWa^ryQG3zcn=jikTb zZCI#GX6`@^{qb(YLSnwv!%}6Djif)|ZCI)- zvXS%`yiZs?`RyOZt*^wcHEZ=JybVj0MK+TDhPPp{asw}dR^e4RyOO-`7lK!T*VX3mnM$#YkHY`;Z*+`b=7dm5UBiSMwNq^ScuvA%O zBkAvY8`aWan{n#S!M-S~aEL9eHKYD1dVX3mn`_V&t4NH|p-j5#IYgo=0 zBkxBK?KLb_7I{B*lbp}mHs z$|CPa5A8K9RTg{pdj~?1< z)p9J0ydOQZ*RWJsU&G|RSP8Aa-W1AruOf?sP2=f zDb{Tgx96_a0zR`+yXvEMai)h1S=`ov1tCjH)Ik!o%~QGH$|s;rjR*J{%$1^D=( zlBm8B_gL#~EY;hwcWyttjiqV1`zHhz+FJo;D zu14^6g0QwusA6$zVdAZY&2KG~v3@sb!puR{+RUMhwW)&|!9Q=ps_`Eu%4Mv5--PwG zg0Qw$C}VB0AS_kpw-(A+s0_0Q%_bt1;nsp;QK2%wwNS1WD&wt%&2KG~u}~RrEo{CR zFJqxHtj5*0k;;5IuE<&L!g}~+wOZU-n0RYp^EpHr3zcCKp+<;QhVaV?D{^5Ym9>sO z?-^rBzVE&yFE;{IhBdjck;)K$Ibl&QY&4c3{BmOW~TD z15+$2t4+qT6}J`?i%P5-|LQqdPdT+}sWK10thR0IXv0!verutOb(JX=m5q>$Wj*E8 zs>O^^QKM1Yy2=!bifaAVLb(y3GTvI){nkPm3zhNK!tUXhWh_+2TMN72S}0?EESnjA zx%;h!Di*gEX5L!ZJ^Zqa^|5T`tp(jLPkvynqtCxvhF|JJZG?r&2CB?&EtDI<$FiB> zmwN}jyVF+2LS+oU-2K)<84H#1*23<$7Rp$tjNzBN-&!bRp)!VF?tW{bjD^Y=e!2Ut zg(|lF-T8ORTMOF4N`AKpznmFC3qZ!Mg$X9vZ<-amiy_3NK5Z(n?Se|h`x{MEOw zzx(cO{SZjm$u>&eabhw1#G=n*pFRW{aUJrG6N}j=7GlO z_w#FuhV|92ur^~TW9?g}YJK%9tj!q8So@X<>oW#nZS{M`T3`J9X5=65pMQJ#=J^ko zx8JAD zS{FZl^hBk$a8;*Bg|?8=suoDJ)w@ zt8RF3TYgDL7w)JnT+%7l3T+{uRkbGC@>hOUE476yI<;CoomEt73paEgspqkD z7#}WQJ>1{F)LYCyzPYqH=jDU(?((ZIesS5q|6c#w_FBaM`s(t@>o@oReEHztKmFpv z;cmFA&wciussH%9(i+qM{risVwxyrz-ZS+L>kS~RPpPU{`?{!F|GEh4BX<>RpBG_$ z=oZ#LFIB94UxfAVi?BX+SF!ei5!MH9`2+m}Q^ndBMp*yC2-`sKc2N5v-jl<(ehK!8 z(Qbne-@^JQrdq9y-@^JgMpz%et62NU2O&$Vr>K$mMX&tUc~wkE-Y1sA-sy! z-<`#aFFpgIn0V=~l zu4*Hd`ADukJ*o^Nd9_-o3`4o9ja24ixvHhgFqRjq^}$?Nstkj96|28H%YoNzcU-rv zVxh8?D#LZ#Di$iEX<1IML}f57&onK|h!bHkmeI7lBWk_c2v8YK%R8dht5}R>G%f4? zVAKdu8BNPNQHZb@%V=8Gv?jsAw5$+*_!-=^T%CR(YF#1x#71M8-*?if1Xbpy<#M%9 z8BNQ&MHsa$W{fl~>l$H%h017J-rclZZUm@|rsdsD%VjK7M$_`{rsXmgDx+z6chhni z3zgBdyt`?+iiK%eA^eboo0iL1ed*3)8BNQ(o0iL1jAb+}?`~QyW1%vdmUlNTm$6V8 zP0NRymdjYEjHczoP0M90R7TVC;ily>7Am7@`Eb*684H!sw0yW}xr~L%Xj(qpv|PmY zO#QPQXj(qpv|PqQWi%}xZdxv5p|S&G+2N+;G8QVMY58!|av2Mi(X@QHX}OGr%4k|X zI_TQnkDjT2`XwlY-@msnc+SKe5S-v1jUAwb=bQ+_YS7TUVJv_*rc-W87d` zRtP__`ovwmVYRh?l{ErpjE9?+tBue)+OSlao0iL1SD8Zi*$ByuaYNL)LimAo({j05 zSD8ZiiET@!tL1>Gb%pQ~tHuwoP#I0jhntqmjo@RMLiky2vM$>YwXP6;Vk4Eow5$+* zVk4CyYF#1x#H#VH?=qN{6~a%f8b827Wi%}xZd$JX5}Kjq{7s-~`RMketK|T1kwW;< z2<|N^SL-uIh42#_sjRuv&y7HD(c#{ra1C@_uZsqYcX$W90qV;QgR=bEkE)+O|*`y&v>$RRYu`S>*lL;QdetKc*j%_oHX(pR1+!gC@@E4-6`!_v47XA6x5atCqVTk@sVR_k%u8 z9Y969AMk$A$SG{3GDNK_grC0zHU9N-XeJ+PTdvC@??=znH!M{ac|SIIKNP}`Mu@y0 zTkB}6mMV+9A6x6_GnU?uBl3RqOnt+0CqMFjY@Tx~TP#%;c|UqGp;gO0#>o4z!TX^o zL;eyXmBIU=i$BChDuef9q4(p6ydOQ8(At(Ni@YB_nb5FQS>*lb$%KZb$|CPaPbNHL z>HRn&??+E2G%QsXc|UqGp<$`A$otWg2@Ok?Mc$7M-j9Xek0bJa^khP-mMV+9ADgG% z%7M?ZEb@NzWJ0T!DvP`yJ(US_vYt$6 zSRc!TO;pyC2@UIGnXrkuAGLWz7+xzOO<(GU2zk8hxbEKhO9PHS?lO?weWt(9T};t zb+lorvYv5q^`{2jj}_hzRU4@c-Va3?vTY-k!TYho`=M&1u?*gi72XeFqp_@Yv~?L( z7I{B;3n%dsr-e)MEQ!%}6D_oF8h8kQ=HydOQ8 z(6Cfl*lb$%KZb$|CPa4|p*wRTgbQ#R9Te!(F0x#OO-|5j~?)1SgI`Ye)NDB!%}6D_oD~A7?vuFydOQ_#jsRa(S>*lLTSuR(h4(`@0wa|n_hW_kL)d6t2Jgp;+z(-+Jw|vxR^)yN8|{9;`>`VT zL)d8d1Ky7n-Vb4;-4A#_R^)yN8|{9yjbQ#R9WQx=m9T=rOG1jM-O;0EL9eHKYGB6VL4-rydOQ_ z#jsRa`U|qAjB*+gJ*{-^SA0Sb7^vZ)53gEX~H!+oN~Cc=qDew=cfAfBWoX zMd!LX@%%d7FaG-M`NPAT7hnJQ(Ej$X&p!M7%isO-x6eM-VjJef_|dzcHwpA#czFHl z^8WYMuGuTtJfu*sxL_`Oz^GoD$!+da7ZvNo13vX4)#kFIVlI2Yre37lTvk-96A!r5 zi&UG-t_&z#4}Vp?Ek&Q+gW24pE-Ln5m`_-w+PqOztP>Ad)QePGCyI(am;(;=8r2Qz zqGFwR_>1brc6EQcsMv!!;7>2sYI`uEQd_X67pb;R6qVY7JH1GSwh&CXGMKPPg|?7O zC~E7V$IA~zDzpV_x~T74C%*qHtus^GgIO0i(?t#TU^f5ui%M<5m|koFXbYKysx{by z**ua^wNhKKrPpfpL_$%iEx6K)RA`HDq8>1%KT>ad1-HF|)&iataocyl?YnCy7xSsx zzWaFFcfaksm-gLXd^-+z<(IzYPqDpPz1ipU0=?>BXES~7@#GRoSeqCK>yvI_?clSF zwOO~YKI<0NPG|a@rc$jYT^at96xC+ZHOr-jS+}REB&5Z78x@S6Q`Ms0_PDsy0%YZy(9SQ^= zh05@@#W8rkK^Y5`;cW|HZCzHzLS=Z{LReE-6^pkm^y&%Q*2c0j7AnKr7OK|9vNHDn zVejpF^*XLA-M_Ly-z0!!@Lk_acX1Nr_{5S8+rVic2pW{M6BCk1fua%zM*jO5v)HY@ z#?zrV-+{jB=A8{}3{6(8v1Yxio*D(0;cg4bn#k8o$Z5*CCS2NWIrabA6;3vjO@ph zupg=xy^QRKa2jio-D=@7vL92zeyCb^nQlFS9l(BctJU9K-U+((gtFety0Y#v-FiY< zUom!N-DSG!riA^_*m^HJ$bL)-`ypBMGO{02!hT3rucWJa$$m@;`ypAljO@phupg3z z%gBCA3Hzb@JK!?1A5+49NER+5`!S6t^=_BdMB9|nWeNN7?h+G|WiK1+@B6DoFC+Ug zCG3Z)h0Dl(ObPoTS-6bs$CR)il7-92eoP7bAz8R==87?4KO_s6k^Ptw_Cwc#z-44V zriA^FEL=wRV@lYMcbAx4?J(123Hu>gtQcpyEMY$+3zw1om=g9wvTzyMk11h4Bny|3 z{g@K=L$Yug*^en$&b^TXd49nE_3#yyS@ecp<7R|8h7@iEen^C z{g|BnXv@N7WIrZnKiaZz8QG7?*^jO)*bm)$!m*9Me$+%?p9HcWld~V~YO!J@`!PBD z(UyhF$bL-DezaxbGO{0&vmb3)xQy(_l&~MVAO^jR?8lU_ACiU3$bL*(5)ww)hjNLh0Dl( zOkh8{V+)s&{g}XhbY3BAVe<40^ z+p=&Oa-vVKOAL9}elf|y|9I+qc5)+ff*N-`3KgJ~{ z7g@m|{$iXX_G1LRm@Ias=Op*zUBHXU;&<7M+>fpu+-3T-&q2^D?(R3(2zaq-=`!Sg zG^<7KhrYM5+7i0=ci9Mdv1;kEB=?8gXrF4l_mQzN9@N4crjV_vWWe-f&Dnie#{a3aRd8tlKq$?_G1LR*dVZ% zMeN52crjVJEMh-Kz>CS!WfA)^0$xm(E{oWY8`zJN?8h9jA0yz!s-?>!_TvWj<0Shr zN9@O~Ci+?}*^fD5KSscd$+DM4?8mJp+GN?wBKG43_Twb`F&7eW|F1}}A1B$5IbuI< zHPJQ*bXmlHjDQ!DrOP7rV+6dIEPGkRevE(@lcmcd_TvWj<0ShrN9@N4c)3aT#A6;2|VrQx@#U$=r`QVn1$RKTfhAbHsj(fERlb=(33Y7y&OP%U*`ukM7vQ zWn@2Q9DF#=vp7A{*N_G1LRm@K}2 zED`%L0$xlOUq65&JO$UQ8A)TO#&j1iY9mR*Xx;evE(@lcmcd_G1LR zJjn|Ez?b|bVn0T}i^<{};}WqSBjCkk@w;q^*pCtLVzP8ua_5Wo2OP59L z#|U__L7>Z$J72^N*w+tLOP59L#|U__YU#3w{TKl+CQFw^?8gXrxyq9LSR(dg1iY9m zT^8kj;M#ZvcF<)}?#Bptv1-}NqTG)W@M5xbS(N)R0$xm(E*nVqy&U5RcrjVJEXw^D z0WT&?mqocBBjCkk>9UCZ7y&OPOP59L#|U`2%98z9BKBhhyqGLq7O@|b=YELlrOP7r zV{-OGvUFLL`!NDuY!K+Oi2WD=FD6TuMeN52crjVJEMh-Kz>CS!WfA)^Is2h0qst=p zV+6cdwRBm;evE*Zt1Q`%C1O8Dz>CS!WfA)^Is2i&4!SI2KPG2CBuke??8gXru|c5A zBKBhhyqGLq2KJ+VPJMX4Yy`ZREL{fnqwvFyELM!n{aC<$bgRYhGO`~_#D0u`7aIh+ z4D83H+JFAfPyX`k)r;>QpMCc153j%a=JD;rpB`U){qWU`?;n2n>doW7Km6kM{L^`Q z`18a3%V}+2alAeE-8NmY?!W3boV2bJa37o)soDohsk%j_YN&BnRU`5=fKqjbN>vm0 zL}GMR?I)d7-Jnu61hT2>J8e>Re@fN%v%9MLI~xJFr&Q|;@=r_6uBv@CQLXMysn(-- zx2l;_s@?*nS}wm^)x0TH?|>UlSa(OjKAA|>ttr(Ky1Q1}V_OgGu}M_}f4?fcg)KIz zCf@R7ebq{D`3_rmT;VMou2!vyw|sw1wbEO@zt*hPx7VafZ~69GR~6nus=h`b@s=N~ zR;~1wZ?1J~g}1P`w&7fLR~6pEv1+N7(7oRBowfDA&YD!;=dEim{fEaFZ@zr}=Z7EO zzIgTZ!|Q+fmv-k|7Y`0t)za)+^Sb%7J-#=7uyw8r9&YtC%39-S%W9A>okLBHver4; zvi^9ht5Mb-@3yS>4z)GPTJLDf`U9@M=CZqQ9=B!v30GsItUcjvS#KZeY?QS}ye;ef zL#>Un)<4>^zBp5FqpU5?+Opn3)Z8d*9i%C{`lS)8vO_4FxNP-HBP0u#?Y?>3t`;uC zr4j4yo5yWgxD1y@NH%fV>X$}n5a=@BJZ@JDm*LWgb@$EVwye8MJq}NTZyvX0-DPTW zlucZ=) zRK+`l0E$%Y9nw|R-(6mK&yhVMRa*{sRn1#kWYAk4Jrx%jEVuByG-RI9(*q*|`~={r_e72e{R!o|-N zc2(gm9w}V>NMTnM-eQ{c;wK8bs_+)Wq!&L>*i`lNgbLWExBNU|R~6pkal*xq6LwYM zEhb4XewwhW3UBc+;o^r0yQ=!TtGAdVz4%$et}49680p225_VPLE$nUTOuq*HZpZrG zrgGrew|sB2TPwVUy-n3xLifI1YKpJ3g}qIwCVk8IHZ=nDmhWvgN5BseN|k-f_cpt# z@D}zqH3CWBswuW{W#96>&2FvwJ5y!f@)LwzRd@?~o9E(tn_X3S3wxVVO}tf8d>sMo zZAvv+6Z+n!A{MzO^u5jQ2*6v||52@pw|x6YwbEO@x7n=K_cohJ8yg17WjHF&?)6q_p6gkwYC?zgt@ZJy7u@uPH?#9KAR*IKdf zBh|!PHN~b1Z;jo6`$quY!e?658hC4LUt6v4*6Jq)dr#KbzBW~OYxO;!t}48R&$JqW zz*{2|+-ill#zw%svo#{YO_kpA4WI4^z+3oCd#?VOwyWxWO9|rk=~JqKw?-cLWdsx; zPSwC$BM#hD=`BAg*c}1)mg2)%YvL{cOsj-zddol4HfyaZwh^GW{4;G=)xD+caE?IY zEgTY5bU0Nt@OOI)X9REfOnYkcDN%KA-SC-Ks=>F687Bml8;%k1&$Qjy^1gM$XIj;o zcnjwPl^V`ktGqjZZ_WOhwnD?Hns^JR18+PXxcce9=D6Z;pd!Ors|Nn=5%64SjR3vn zX9K&nYKpJ#0Uiw$WRTRV|GKHNZ~4ic#A>Ms~-mJ zjsU#Hvw*9g1?;NATRaN5`cc59s;59}TIVV4s_+)?{}%5XJOh6H zw?=?#LO%xBtyO<_^%hS7u6_!zs|s)N^6%9T0d`fjMu6_Wpsp|KB>#`7f%g_IHRpBjO`@Q<{zpg60#aq8uKmFHLMc?A# zzts=_byf9uS8ws`-|A=ox~lNj!taEB^slQ5Z;{Jb6E0&0m!UXttlknXW3DN_jw`v0 zHQ_R5k9<$YBpm$4>X#z^uuReCGoGUl3MQ>C{OE@R|)n<~APa2YeW4CQ{qTM3sj zgUe9tH&v7GgnqC0snl<(Ccn49W!!M){M0$opmWz0+icNW370VvyiJwfO1O*>;C)pk zm$4>X#>nqBReCGoGG=fY%KOGMkZ>8ZpUc%%fAm(uWsLA{8v%MN;W9>cx2e)w370XV zyG@neO1O-X+-<7tTM3sjg1b!>-r5o_V+NO@pl^S&Ha~OT{JjM(<3=uHOSp`Y+I<}X zav58~Wz66*l=96HsDJdm`&%`|Rx7-^4<+YfHF{k=Sjj@Rm|)?jL~>*lnut z)|PM?Bd^<3;jPV2;`W}`5!Y?1^j5-Uj1!WkN^d1x#yBB)QPq)3Jg*6tF-}ODD*D#u z5zgIl^);cgy;*DEt#LxqYNfaQ_*}DAa2ZPWX05@ujB!HJYNfXlE@PaKG*x=bkI!{S zz`qkJ)|(>`tO-X*x7A8-C0xchA!(}gR>EbB6Ova|av58~WsDP&rb=%mT*d+}Ly6v) zEk8cjeFnU5DbSm$!FR$1T!!+zshW5TT!!MjshadHa2ZPTrfTqeYn+g@XMo;HxQuZ^ z(p2fKgv%HwBu$mxO1O-r(3`6&xr{C0G8Vt8ThZ9`R>Ea0ep9zp>8*szSp1^yit)yi zm2epgxD2IuQ#J9HU(>Bx>8*sz7?Ire4A5H%m$CRI-Kv$|O1O;0@935)y_IkoOHHwj z0KJuP84I`!<#*#5NVtr}FX-02^7K~1Wh}^OR(dyUP1b~nXjXVPRg=C2E<@SfR8729 zQ+#~}$YpE^mob94O_knCxQqo{hJw2}0?C>X>CDRQhHAoPEQQ|K2+&&zm$4Ljb5$jm zu_au_Qd4ZI^j5-UEJ$WnW;e$*@fL!a71>SI_j&6Ysqj;R;LEQc-^BzqXz}E45|q7qw)4h9zq=e3iXU z#=8vUFaG1(*RMYP^{XEq-@JYJjna}|{rI*$A^Or{|3vK=_&-s}lJ-xm|MS7L3#r<_ zP^$hfl&bv;yQ=oPMymb{OVys?o~q8oTwN?x?+;S7{?Jvm{vcIfdr8%P*K}2lEt0DD z2dUccny#w;?&&=yRqqc{wf@jm)fAhm_lIrv?{QsK>kq2c`-4<9@K2WPs@nTw)#X(7 zc9g2UKf0>!E#2`$)e`#Yt8`b@y`^hts2X@nXJTx&blCz`6L0zVIE^d4<>#cDBjD$x zq)Ko3_qeXAdrKi29D&4JeojiY(pw&9)veXNrDMaW)xXDeRoz=Uic8hRTYgSz)nPfR zCf=$kzPw#@^oFYSkG|Ji{yk2$(p#e!->nL7;d`7unk3%x?{TV?-tu!&&1b;B$4Qmm z!X;|0^?=UAV7BNjKPT0#RexvC0KMhk~v&dqu1OEtQgfdCw z`m-a|``0{DwP#1Q`m=Lx&Qo{C)t()x`g>Wb_rI4_tF3vIQ0MPusowuyma4s%rRwix zsn$RGzBi~;ZOtQ9e=ke*{xy$O?Y%5jU-L-y{`ay%-0b&+ROv0xxobWHHO1HGl|1$4 zJatzU-eS((<~(&*Rexu-(p%0`cU9r7mELlmx~mFrG3Rb`p1P|FZ;_|ooTu)p!duL_ z+nlHFs={03sW<1TyQ=UObM7|hshg_csVDN(oAcCNRd|a$_2xWvR~6o3&fVrbbyrn? zcl8!??l$MCyQ=UOdFsu1>aHrh#hkm%dFrkzyhWaRbDp}Z3U4vzZgZZxs|s&1=WcVJ z`l5PW_5F`TcrCf!zJB%ItI(d`brsrPUo@T`q)ll+wpiPQl3p8ituQ|P;cxe!yHfR6 zzf^5m)m62}Q>y;z-%kIz+f}v4Q>wnKl4=S4v{dP;+T*#c{JE=5$VAm1PpSH{O10Lr zb9b%wcuLimRZ_KORd)pJ)h|_FR!P;CRZUg@xhqv)R!LO@fAc?wEKVB<(;E319YejWUqs6TCoT-@AYbW`5t?0*VML%9Esu93?>i@iJML%?5*wpck5_bmyrTQ#72Vozy#JT^b3ZPvw==!v$EBMqACIw@Dt6`$7a5+@%mJEA3ps4@!xL${dUK;zIP6NyYi>|+&pMwd^P>xM_pYS zf*nmJZET*j(U!I6Th;pa0aa_?-rBPEfk3kUVOz5HfuJpGU*9C_U$!M{U*FoY_W4b+ zzFa&v|0&j%wclcr^>5pft(VYG-;3L__5n_xG06;g-bP#2zQ9S=ziz8q`vTXNwa?p< z^-pk;wHDHrwQq2erOUjBbY;DXNYLgX@M{j~`Jm+j8_ zx2uKA0Q;+2`_kQ%9T(p`Evi&4T(&#y-(DMvfX+AcC~OBfPYn+ z^s;gJja7?Ywmb2Et@iqD{#P$wef{#)zrNe({_e$Bq8)YE=&Lu6|Niic>C<(4`18Z_ zU#{(C(Y|^<&aTWP+v?tR4C&eo>;HUkRU}n&>8{Kqs_GT_)MC4;W>TqoD^#s!(ypp? zLaDk(rD~n9t7;aNsy9NZnnio6BLeB^DUzx?RI1hoyQ=y-Q}xBBRL!7WRqKMP)%__| zTWfYz&7M;ArKVKPo?TVzfl_sM?uWaxt7EM4Z;aI|INGUPpI z5F(e=L|@H|i#Q}3xy%zEGzeHh?0yqRdl29Ba?#_q8YgD`BoH9QwWvh<7Cyu| zGs&6{+p_3(IA|tW>vnBftSNEQOtQA7Y|FxBIBF)@$Yp-kOe;usJ3njIt=12lNtQ12 z!)9$+xD2PwGzgK)YND^*4#&+T8@a3|+GN@7{JdFv5a2Q#INNtWaMqTE%W&dMvXRSb zqOXI1BWIG0Tviipvg~Dk=Bzyka2XDrsoKb8ev5~GP|;<6>a1I>A3KvQUFOHm+OlvN z&YfuxBA3-f+mzv>)b0n*+SS5kIC-XGqh97$d1!3;eZ-HRwX228aP~}N5V@=-`Z~5a zd?wk*Wi`Om-JZY>g>yNdrgW%XEkM-tnkM-e)uiMr7 zW33AzSZ(rHZ#B_2wtTF|PW}^2c6qGd9~Y#L3En((B?PMV^VjV`(0~3~Ee>F7g_bmr z%>&2u;h!$^6WHx)y?N+X2o6HzvN~pOgFu)08SHMgHPI$Zmkpu2p9DXJt+A!c{1kS( zT5le@8G>W0!N32-h>c=h4MEw+W!Naz-4KxVjpFtoz-8PhK76CNEen@%qxkTR;QGEDDaa$HH<3{n}8^v8&Y!vH;2tEn*hP~TmejZzUjC7fA6t}B| z%eYZ|_(pMC7QKuc#fNVcw`I}GxKVugMsZsfF5^b=;Ty$mS-6ZF#fNVcw`JinZWJql zI(oq1GHw(fzERw+7B1sP@!=cAU0G}tD|8z!^Nr%RELM!%C_a3nxGf8paijR~jpDW} zT*i&!!#9fCvTzwUiVxo?Zp*@D+$cVLqqr>#mvI~Th_->p4G`DG61RbmXd8I*`vC-B zaK#vH18;sofMmI1jJAQ5s^lw1ZUZ0DHn4(vAj@7BZ3B;MAZ*IGVvM$dHxC=t*mA`f zZ3AzfHY!=J7^7|AttQ$AfxpY5ZQv0pdzIxj@DXhTZyq=*Xo$bdqHW+2Dr?o!Wzjb9 zNR>5Nx-8lT9IwC zc;Pni5p4sHgjpK|x-8lT9uc!9OP594z$0VUWa+YK8+e4wnk-!wZ3B;#S(By9qHW+2 zGkcZgHt-Q`1CN|plVvY^|2DAgAACGO^@m^o@z=lo;@M}y$vK7}4^VwPK=tteRqFuN z$CH@9{rDoei~xUCe0-67e35*7kv#iMzIgAoI70mWYx~C)$;TtzACGj0N4nSN58u9g z_010tznIsDum1Gn<*PO*b*>dh@bvRa*&qI6@Z9~Z`q&Bl;Bha>+V;VzfKU76B3T1Y z+OqcAkgWfZk*s}kY0KIt7s>i37s(oM(w4PNI?4KnP089Pm#(a1U6S=Bh-7Umye(_n z2a@$qE|S&YKkcx$Wo?sAvi`|MvKstA);8%R>z`aCYrsjnTHBpmr?{zVGb~k~;dODOs5`Fq8kMTQMy0BO zzdYs5TJ0^Wb6lB&N!rRs0crYgJzmPo3Jw`z)?8nkMqw;UyEKCd;!rb=%)Nz_%<-5GOF*ewo9e1so06)xDXH2Lu&ZiqN~+$bq-smR zt}48RC7_aZ^$vS_opx1i38-4VO-Z$cetJoFRjo}4#_}bgRIN>QRc#3>Z!|%S;GuZwidg}df9e;VlpKJXju7Ac)&vjYngYRLf+H);$_;W2)d#<~x_FPNV zpKGaF&*-Y!b1hZx8B(?9x~po>wN$-lNY$R}rmFW0srqv*RqGjDRZa1e2c_!IwN$NV zbXD!Sma6v*soHbhRkfZWRqq*6wVu&cwVokW|7mj~va+iRZ=q*MHStzW@pZP)Go+e$ ztESjg=`HUW-4TGd&@)tP;w|qP>XG!8_l#z(-ZP|1Z+Xw?s={0785)7aTmIQVwbEPO zGrG0HTR4EES`%;86x)+UZ~13~ZmsYZJ{z3KsqCu4Tlj1s)x=x=*+7@8(p&!7pj#`v zh0g}6HSv~bRH{~b%Rd`5YxU0tQl+>2vq4uC-on8njX>fp52#eF^p>AH>edQx;neheh-iAr2g=)?`iS=Z#b=z2)bPnzj0IBdKyt=*Nw^s#p^ubW$UbtO@VVe!l3OalS~ZiMKpuQmXWpA1~^T0KA2eN!6No%MTZ+R(i`17d313 zvqe&+xBP5TR~6nu!lXvvecrl$P5XGk@4Le!x{B9VKDsL2o}e<+2fqg@ugg|GA20aT z2>9Ds<7z9P=D61BsHeU!Rew86)qYiURqgF8RsY4lO&*=tRkgRXRQ*e{R7>cmFU?(5 zTlwh1RR2{WReL*kRqa=WRQ>HNRr^)ZRkgRXROu~`P3)?|TS!e*t@f*;sp_GLs@31l zQq{oUJzF)!*XI?PiBh$s=`}HOjNCjw>&UWwZdCsX_Ik7y zv|jpme|-4+Zy*2d#oO0!9)5WF_2a{rumAk;_Qx;pAwK-F1pV&z)slW8`!A9De;@pb zcdqrl;%R9oS^p^_Szj)7W$m|!WPQDK>S|D1*>q)X!6aG#F(O%CFm+{Z#dOX{$&jqC zn7Xp|b40TKb40TKbEGS)zq?Ku)+dtn-}+ry`$3{=`MJn1OBg4F8V{IXmLOUGMWSl` z7fG|)nrIsYe~n7kmndCX`%R*1=`#G@@5;hu_`$DgBbWJQ396PZ!!Q1BwQw1J@}IaY zq5UMlW%$i6*~n#nS%R=Tx(q-1yMv&=yFOs})vszJm-%H0s+KOp&;Dk${<~kYbQym4 zcV*!+ELJoKk<0wD1XW9y;g^56TDS~9{Z(z`GXL$bYT+_mme93>U-m9p^fF%d-W>$E z48Q)*1Hb;evgl<oC}ZAAAXd+U9G!p;Zb_rkkXaKQTl~P>2X6!Th?91 z8&Wj3NiV|b!GTe~TuGU?~8&XtlFI#vX z0XL+yW#KX&NI3jJLR(fZ(90W)H>79~l3up?4JqfsBMFBeN$6IKGYJdNBpiMwp)CuS z@le9yhZ5Sd-phDHipDnTWqw17#ui^c4nLOAuGV`QZ%8>0oMmfv-kNB8z_?=cg9+_w z;WC~~zzr#FS-1?x*)#}IFRO{Z4g$|6;D(fTwdiF$oPZlry0SQ(z#CFD2+@kskF=e< zAw{xLFT?o+rI~m@5N=3m4+44_4=CVp|ih0AzE0XL+yW#KZOQNRr; zZCSXChZJx_N?R5#<0%E)kkXcg%XmxyH>7lBaZZ6Zr07YATvibl*H;Y>D&U5ccD3kb zJgI;iQrfa`8ILO9hLpA}T*k8sxFMx23zzY*0&YlY%fe+mt$-U++OlvNk1ODYl(sBf z#`6k?pI2zh!euFC2b&p)CuS@$|ysrx)6?a2by;9DaPEEen_N z{KDZkq_kz>G9F+!`~X8+7B1rn20`A*_gfrcSa^g1H>9+yh0Az`;qWsIZCSXChZt}} zN>>)A7g) zkt|$B_5(Mhw4Vg@GO`~>#C~kfrk)Gg4*}oNAi!m0KSZe|vS2?JvL8aeBU!i%cYUIKO**H^TQsJu^(Gav{maTKF%XzKQ^!*3)zn&Vm~&p9}C%!BVs=`KlE`fWIv9G z{ZKj_#+ELN*bl{RL6$Cy*pChD$3phw1gqM#1K5v+?8k|NA6;3vjO@o5u^*e?3vn)F zKhB8#*uZ`)WIxV`{n)^MEGO8Hv(okN#vb;X=<7S-#Mh5AVn24UAIk~$<9wd1826fJ zs}?RhBlcsji8fid?2Oot9qh+)VpsZ%*pD68C@f?@&WQck!G5f~M&XRukG&@PGPa5< z_s?r*#D45G(I$&tc1G;SUK4GybeUhH&|Eg}U_Vx}AE#fV(3bTTqb}Is*hVg^iMBzY z%SL_oGE3vW43nkHBKBk4mtnGWS;T&f`!Y-xyV7UGevJDvuCio5PS2ujKM8Od*$)O7 z_c|{UjFqHGmqqNyxG%#7fi8>Kk8xjy$+DM4?8nF)HCehWVn0UcsL9f05&JPxM@^P4 zi`b75J8H6YS;T&f+)2$$l`&xM>H(QZmZ;R6JX<1_S${n^W)__gu>E zI|0FzE7=c)@+8%Q{a~801|j+SG15nE%ILC){TT71CQFxjHf48gYobk-F7t58wyb|+ zT*-cjY>cMNzkaM_KSYQ{vi`elCHoJR|mF8vds)POj7(CKWiN}^kG&?^WVvFD*pHD)YO-80M(oFq%*vJQ$LX1s zT{|GOawYq5M(oE3CcO><*^e_~KXg^DPZ`;dGh#nRG^tffmqqNy$R;&ex-4QpMmVX- z(q$3*vDZYKEL|3{A0wXBWa+Yq{n%@wO_nZ;*pD6Ql`Gi~U6_!xNU$F(*$-vKN3!T; zWIq&>9m&FFWIvQUoXCRxSeam{AlFD1-x$e$C`u!eMK2@!q3nQ27A_f$zsJw_Cv>tB3Y~$$$sc~MkEWDk^K~S!I3xCB1iW0U zCHrwk?8gXrF#L?@6PJyE7n8MK zR7^8 zT^6w)BjDvK>+FXHA!0v9z>CS!WfA)^0$xm(E{oWY5%6NNbXmlHjDQ!DrOP7rV+6dI zEPGkRevE(@lVvZ9*pCtLVzTUI5&JO$UQCuQi`b75@M5xbS;T&ffS0SRvmbI<#D0u` z7n7ySBKBhhyqGLq7O@{A;KgL=vWWc{0WT&?mqqNy2zW7Bx-4QpM!<{7(q$3*F#=vp zmM)9fj}h=+DC#MqfW_qD_`Ai`b75 z@M5xbS;T&ffESac%Odt;1iY9mT^6w)BjCkk>9UCZ7y&OPOP59L#|U^aS-LD@KSscd z$CS!WfA)^0$xm(E{oWY5%6NNbXmlHjDQ!DrOP7rV+6dIEL|3{A0yz!Wa+Yq{TKl+ zCQFw^?8gXrF#x3f_2b)TpFI2i&CBmzzJ2*`k3T&7?4SPf?8V!+ zZ(e@+XBXTM|W|9mhyN2>NvO4VNdrD_jl zSJkLLsoFDHsZ;n_l2q-9ELHpJ-BmTPR;ubyZ`BlAt@M^-5#3t7Zz&Xqhavo^Xnpti_Tf*DFTQ^G>c#gDKYaD( z@!ubQ@opvf=ZEQ+Yk%oCasi$m_HD;;ab@q=YqY%o;icb*1u#{gYN^^(cU3hYrs`8I zRa>HTRc)#@0zTD>3G$Oa%@MGvma0#+RP8m|t<_$m+wQxCi&Sli(p9zBs8oH4BGq~l ze|n8}RqZt@Rez02)s`q-ReOy})nB7hwby7<)o%!ps=r31YRmtws{Zc!yyAiYsV3g? zGvcb1-oid%?|H2$wp!^eY!fzB;Vs+_pscLKTQ$X2E4_tH!e*`TmhTbDTi7FPs=`~o zMOdndw|s|iQ*MB@QmH21^26a$rMIv_*c$=A7eK1?7WN05s_+)B1<(k*&s*14`uo>k zzJB}gD}5MweDfaOMV;ry_W-Q=u?KKWsDBjvwrxlC@`C zvi6LZY`uhjdMCGK?IAxE!OLo`fwX1qDVMBukgC?6^0utC5XstOUb6O>w`Hw|NYVvlpTq>*C)ZhA(gB(k+!To>8jQi<0WfPdRx|3hj?|Wg%lt!^ZCQ7jB6#64|B}>}b(blEm$He=MxyTJxm5%&WfPZ; zL|v1m%luJ(9I&rDW|{>B{;WS+e%5l&rmx+p@Oq zk*qx{C2McwwyZrXlC@{0WbIjL%i0@Rvi7W$ti6%jvbOG#ti6#X>u=wk%xc#~s%*PCa==u#MOEbHQ*t?FO>!I#uJIr$`2 zf8wQTtGBMIwH2xQ120u;D_vE4-lghYMXL6^cU7&aNYx*AsajL%s@l^oRqrY5;$N(~ zs`ju;)mw^GOX#Pkva4#(x^Pinw@KBW^{%Ql6sh{MO{&&Vx~jHnldAU>o4Z6tUW!FwKsFg`qR^t^@YAz{qM zd26Dt)%qPbB^$Y{Cfa1_GUS|erwlIhJ8r7l$Yr?WMn9Ua4W(owm(@huAkbxi7Mp{B zJ8pKr> zShDq`-Y*N6ImKAA?y_#RaG7I_B^$ZSIYwRKL6?DJY?`+w`uf~D$XM07%et}}ER&_n zkaN-;TikK8uXGu5PP)~?Wh;M|A?Ktk3zw~Q8FEg#g8-K?=j4W*ldddW=6BraNkGm? zR~9bwJ8nwWTvkh*#xkMi`TBhM6*r~oCTkXpD{gf85f+SyIqAy6WPZg>Rcj_|jzLYc zjR8I8DJNZ3J=~^Bi+RXNR}~KP`)xD=o^jGug~9xKn^M)l-`^N&lCML+h?5&4PP$J4 z4CdF{RJHY9xx0@Mh>fawrc4xM4U9Mt%){S{v<=hNmo{X zXR@>yB2K!p@Yqg|A>yPf3zO|^V~9BE%ED!Sy^Wp(M4WVG;W9>?+z@fnm4(X=eqKbx zNmmvwW5me~5hq<)xQr1eH$!{xY5N&K4p`ixaodg#Pv41_=vJKnomuq zTP(WjY+zHY~5wL_=vK;VyqR}hh8;Rt-DMYA5pg60#DV}Q{0htm+9go%KD12 zDeDx2F2Y1Fn?NyiW!+`E_=wfI%bH_b6Mb=+E zIp3{82(XWmh0BP2Oab;$vTzx(k14=DN)|4gxnc~kkCKJUh2s;Va;>Se$_bny}12?6#|)xu>nSBwGnQL=Cuv5yJZNAnE^>_ZnHVGsiBqpF3= zh{vsxQy7x1ni?L3zrf5n1FpWWr2O@;v-I3)XRW<=;9;FMlJ*P zp^J|w8?6{Ux9ZfzN0g0Lj5X2MH5joEg(fHK1W&F~wRBm4eaL0F-bNQ6VGsiBqh#SS zVjok0eUvO*M(kq>u#b|3%ZPnUz&@HT1NNbdk2toG%Yc38;v>pNE~|;YKDR4f7GNJ5 zTVNl$_=wd;E~|;QYWej8*hhEDuwo?kF$LI14FY-@v5zUhK1voYBla-`*hk62WyC%v z$3D8>6Tp4w;v+l>0r#P5!F}lBBg#fDtBJloVB|g~=RUfF0PsT>AFFsvYovwU_VM0y=_^GMWn@35fc+?0xQy(_6tEwX1^c0kkKnR^{U}+u zjO@o0upcE0my!LL0`{Y1;WDxxQ^0D#;0Lnq zGGzOeZ1TJ8Rug^sU50GGlGWe`)w;`&?I&5VAJr>9{Jy=_L|e7^#)xdct{uRBAlt91 zO?ug_Ci+?}*$-s^qqGSBuq zk?mKqk;{;_ii>A9KWh zjBFRHmMg}H{TSIUS6Q+jbHsj(3+YUjUq2%DV`RISEWdt4?8ms0&SdGbi2WGZE+$Kt z1(6^6$OZP}B>OQ3ksl?C-(_S!<{~BlhD4_CxWRthVfW?^%)?*pHL!#~iUABj3dafxRqZKSscd$%6fuBlcqiyqGLq z7O@{A;KgL=vWWe-f&Dnie#{a3F#=w!TDlDEM}2l}ylTLH=s+)?Td*I^rUUjvCm1Q~ z`(<5Od}Ad0F@yc+%Hm5t*^e3QM^hH;hX`*Df`4P|%3{Ba?8ofvNAp1d`f(Edm>vD- zs^V7}$&cB|kFKgl>gol8AB%$@T~&NvB=@m6_t90w=S5;4i(?;MReW6}^|5&3M^{yU zcO6$kABzWmbXDOlG9S3Aq^F9jN_6)H%!R8;x~lLNi4R;=(pANeF#;dBs-&w5Z;|)F zRV7_jc#F6Pt}5xO!ds+0a8*fH)x0GNh)Ex~tE4My<|OWx;^iWbsREaoVFRYbGmMtPvMa`sm8iWlZ|OttDMqx{S03t}W@x>hH{Dq&;wNNmrIG zBkh5UOPaC{duYm-^szYY(UqmknDntY?a`H`%b4`BIPKAurOTM~u{iC~m8Hu_dn`_S zbYCVebUdvs;#GSVK4Cw+8f=`zwDizj__W%YOFGSVK4(;i(}x{S2P;z=J(S%*F3 zGA4a2PJ47^=`tpLEKYlLW$7}~9*ZY^bY(jJS`9$i_wjI_t%NgrKVx{S2P;z=J} zS-On0$KpvJU0J$}w8!GKM^{#VXD%b{u{iC~m8Hv=^szYY(UkR|54ns^knCVl9xyX&|6t}I=~q>sgEkEW~#eaK}@`dA{`V{+P~bos+9!aYW& zi;pgUnMJ(E2z7B?{xoyoL%wW$404t#WFX*7m?EDn5hWoa}5ABzJYU0E89 zVINBbd`u2}=ousNu{iP3EtgIs@v%7Z(UkSDkE)hmK%DsK%Ceu4_*k6y=*qI6k@#4g z_~^>&@5~QO`&gX#=*qI6k@#4g_~^>gW=#87ocQR<(q<$+7AHQsva}hA4_z#NZ9H9B z_A?S6ixVGRS-OnG$Ku3CQ`UhGxs1fe5)mIG*2NxNA|FeHe2iQd*JVEg^C4e$8jmv{ zH4f}&5%e*VUA$g4w21ncYO-CI9~&d=V{+_6<3R3XiMWpu?qc;4{8%FJV{-7L>g8Ac zDD`7<@}qS5SwBKQM!t)W1G`$pevE(@*X8;#fiEr*KWcpGH^)Dk z%X6ncN|ttu@Q;!4;=@3@f&XZ}cAWoEy#zp(2mqNJ04ZJWp+)H*lc#@_F6{;cq&p7m zZe&1~hyfWvFE($4K$a)~WF)<~F74(NNb}gzhQxL3Cryb#2xjUoIudgDAN+(&bu`M2OBFM!H-~k_lOz32Bcn{YENe zjc$P%kuUa~kqcR)YhZ*BW4S{zWR32D8KEy;FZ{Mf7r~6w7uSW~*61df5&Po0=x-~o zf~ikuAAUcK+!xnHe_NxwU`FuERaYIuA-r`s_g*k}B)_;W`rC>`knT9ZZ#P0B>u}ip z^}=sAQX;EUBF*>N2!HW$z;beROr)&~zum}*tj>wFb@g`jdg(U@McTT0ySgs@=A=kl z7yV600Dzum}+tj>zGb%*HPWt^ej_%rIyTbQ#d`8aZe(?Cq^-;TMsQ?xaHKuH>~ADT zRwqZgxPRy?f{8cVQJHA_j=I#{V{jPF-9LrK;8msGJ{ zY}RUalB%s1OVxj!HC4?_`{rxKQuW_vO;xj!RBfeLs{YHYscJ@&s(lA3)#|KwKLchX zsan@6RSo>zs?HKi)p}N`YT)lzwI!ldtz(s{2L66kTOdl+`czA+o z^<6Lh?!{Msdim<{fA-Vq({;PIovt4EyU+fqZ&7Cqnu(gSO}CDHUVpfiYVg3TDMQtp z$-6Fo?@Lcj8LHk)q#8W%YRXXc2VSZ{Gf`89sz2~j4VsCXGE}{pNHuui)s&&?54==^ zW}>DHRc|Iz4Hjx@%24%YqHg19+E3=xD))U$RW)U(`a(^rfw$C@O;zVT;jQ;B)UGd* zFSG*x&C9R*3-8r$FxwSm=l|W^xyJG8{cs;&3t+u;1_jws*1A|*7Or-#QT&5*jcr-j z+PTJ(HCuOO9cZVjcr*N+p)%~){Nbjg|j`ys$|XCZCO~`Q>;qXtlgG{w>`y5 zvJN%2WnpfI8cWv9-IjHCE65IZaHz2@3zs?6Sk*=@bEt7wkR7YF-r24eE_0@_s*POc zP@}4)%baQKR_iHNl12O6ooQ^#!e!1h)*wVK^Bc@mEgI4^mwAens-?@EX>3;umpRi|)kZFJs8Q9@WzIBq ztMwEs$@sA?T!Y|FxBeuG)bMlN%TQD1QAGKU!3)xu@Y zFjlpZ%ba0UwRD*yjO}XSGA9_T+Q?;|Vx?;7G6xvD)%p!)lBLU>Uu?_5WgcTygAlpQ zZ!lA}beYqO?P}pNhZpM`p?!0?%3eQY{OZLIkNvM0+I+Cj4a&9ho^<$z)b+pmv!8l2 zvX`$I3bvxG{Tb=9d|%TJ|!Jw`o_aiMA=D z%RJtuE$d4(C0t?3Jl>`)3zvDkjmFmFZQ8PMnaA6dY~-?<=eyiLhQE~|+)S@trI zw`mUoR*W8RQ`JVj%=2w_C0y}IhY#-lknGT;}mMs@CIe+OlvNw}Fpn8+gMuuoABDfO))4yIQ!6+rUS(4ZPJv zUmq}T10T^g@P=(*C0ub3BA0o*&8~zi%0|7+FEf%XT^4NvZ+@APWZBE2ZQ#u>GmHPQAY@ON3X4ZPKU|5cXTz(=$Vyw!fc$dRU?p7P0rO~^u6g}3qg@GC zl#O~BwtdRV8vVE0gJYQH^0niSG*NvBbQ+tSm{=j zja-IpV5M78HgZ`_v`raZ7HtD>*alX*6|0R_j5X0#EnOCE18*K{qbGqbi?)F`Yy&IZ z3WE@B18=q8e;ovF10V0-2Dbf!k3{t!e*MQ^|MrV#pY5{;C+IfuARB{`OaWpkYKmT$VvIH`sRHU>gTn8a*5v zY|4u8MceKhY;9TpA*ZMa%Gx$|Th>39C@F%n_UXSZ>r2d;8*IC8u(f6Vqoi^oSgmca zwPpRIZ02AgQUNY;PI&D>xUz7)y&r~ldSj}Thr z8*J^d^&fIGH`sRHU~9|5W!zxXet9$qa2Yq)w4E8r!e!iG(~d|a3zzx*5t=gJU~7*p zT*eJHeWpyR#Rl8V4L1E6k7VI8Zm{jX!PXrFY_QFKe?*OK?LcT*t@dUGD_Bd|47zXW?flp86|7Ke@fO?W?flZm`T=GW+iJYv#zWy z%u3d_i%YhYe#%+u%G$!LWbOA)$=dIquBYb!F)? zUzwGx{r>67(q+CfE7`9* zo4Cx$r;?@19DV8z0$t|lQ&pR|%*m&!mM(MjsadU)PbEv2c>+dPmM(MjsRki&nUhad zEqj@xPu*(uch-3weX44cUgqReRm)!H=u@{^y37+WRIQ^=U0L=rN1sYIaha1(8U#_^`Bc@?WuAc1tk%h=lBLT$0i!F+6{9C$)F31)Mkk-D zTCNy90i#dMk(jy{#_`&NwhDev*c8>KUT@~|Dp9ly98kkVK=Ayxl% zGvoM;*!aoqgjDHrW$B1iTbD~qkIJZeZE4xor5`;jqjb%WU0u)0sBxenJuIWG%hjc) zWmLV^_u9I&q{n5Hu356JD>qo@^Sq4Gwa(Ypr71lyL%JTA(blCaJu#zn&6RCkHb0Nd zDBZ|!y!Y$onHi;9@1vi(-?iTBYvd2#zxe9$%_k4Xci;W`?;if!!!MV4fB0?vujjv1 zBFn>X?s&I&-iDri58SAl%&X&IcH`YrPl`QDp14uE=GCsQCvH@|^eQ4Zns0cI+$ddk zPh@U%b?H?P-KcReueQg5UiH+C(lxKPb?H@)-OvqDh~4Op1HI}&!li3oz1Dku_WwaG z^pl76`5!-dn4bUL?>>2`C;tC={PSP^-Q&N!`0?Afe|^WZ?WwE}29{5&X?h2wy=u43e`@BQZUpjZ~_;wR+@atX$PUiBL!G!7n2+^!dW zb@FK9(oOuPWELNX$wPZex871e_0@L0@Z036J*DftvHLv0ZDoHBJH9pBUN1i2j6j#5UifYD=$@)K@|#EZ)Hu*@<6nOF zb5^tM`uJ?WfrdmPx`95k+aBfoi)kDgyAjY~J` zZ%!JQE`IxMjv9BzfkewhqGfZUrL9Z95oy^RX=&@yZ)93FXIk32^c$g;&7qdIF8xNT zWgA~Q?(Um4+vW>mEt_L4?Rx1qaxI&4Ep1);jbO{>U`tz<>q(L=o0BbFU7{@$(U#58 zmbNZ_zfELYM%v5$>prKB^?o4SvN_z+u9toz-7@lCf_mvU;w>ZaCD5hc$hU0Hx3tHB zek0(rIpEUPrQb-njLer{9OyS9E+h0M(52tVxQx`7`*jJqOoUuU>`S0azmakoxi5h( z`x`Nr5&RP9(r@HkHs@Tr&ly3NiJ;5opi5hqek19!IqA~YrQe9UY>v9Lb?G;3u*-;l33TZ<(k>(a<$hh_E)#K=5dahD(r@HlMgmNrOTQ6#84)mnF8xO0Wn{nv zy6kU6UN%Qwy3ent{ix5AdD)zKY3tH&gkCm>UfR0!8>yF(0~3rd{YLC%bL^#EFa1XD zWhBAeUoXLziQvnKf(dl#He6pyQ+BW^U0wQ(Y|0KcrK?N7kuTXJzGNX^GLbLYJ(jKO zH_v6$dy;&~?pIy6b=lv@m+XGobyIgGUow#|**#OKtxLa=FWLRV>$WcaM!sZ^_>z@; z$#i1>ZIAepm3+x`V!wMInFaTLw-=j+@Al+N_J}XhzLM+C=9qGk}sLbm+a$BbGP5fm&|@Sl*Zxxe94u){QMu6R|*jL;jOX*e)rL244ajb-N5md_LMc0-l&&sKN+@Lql+x9u zNeQLwfKo2H*Gc)q>#x3feEaa_k8j_;e)aID#}{8eeD&h{haW1{;o%pz=bz5g!=D9) zuXoH*J!U?Z*l6D!Y*D}LOcA-3nOw{6TuWCLZFMHrvOCt&mDPazAh4@C)zX#4A{NPc zGNVH+U0L*0BaXvM@QXDNC0TWnpq&Q&X&gL2{n#;1J8@op5cl z|M=#`H;=C#-W|Pq_}#a9HQmuri*K@CLgEEEd)L!1@4Z%5%VZKS2->TEoUd>%i-@1q zr7KCiAZf2%FKtQU1yOr#UHX#53$pgwx-=$S*;SAnTgHpo(*$x_|JL3Z^hCN6;d<1XTx-5*+&V@?4AwN zm8E0J%4bzk*EHe|9**zPkE33b=&PY~f_iUK1EL}!aX7_BEt}ILT1Cvgk%&(oXFB;WMp>F zhG`B05t*5Y%;R#pk^jevjeE<>e814YIFh8_1U?O!*x3Tmk+1+A66exL-wL1gtG&}>HZt( zWsb*)<8_=$hR~mxd;UqYH5pT|ziBA)Fl$PIKOBw(WT! zgtG&}>FTm`62jR5;dFKNcU~_)rvk$1>e8cxaCSgAU0pU$LO44hoUShYMhIsIgwxff z-w5ICfN;9H^cx|Z9S}}emwqFJvjf6u>Jq}43E}L3aJstm8zGz>5KdQ@ej|jl1H$R* z>hH{Ngm891I9*-(jS$WO2&bz{zY)SY0O53X={G_+2OylTF8xLb2X`Z0*9Je=Hwod) zgm4Z(INf^bH$pfEAe^2q?kCWiju6fP2&bz{zY)SY0O53X={G_+2OylTuKv#aMhNEs zgwxff-w5FxfN;9H^cx|Z0}xJE7k*O;(Dn8zK`(%Cy1MY&LI~#ogwxeUe_IIQ9Ds1T zy6~G)fH)4xdU8biT%R+g08v*n@boje`Q90kKCX+hIUErf6mKsa4p_-!GCa{$8W>e6rIX^x1e8Ie9VzT|0+@nrqDEguW?{(7;aE&tmwqD`b0FlUI}Y?4!I%RfFI`>wjbzM$ zke9A5{YEtAK*&p1mwqD~b0FlUt4qHTjyVwW($%HkNXHxqdFkrXZ^UB`guFC$$;T`V zc{!Yq>H31m%R=Pk@C%IEy7U`EUXBQP8IeA=ejxI4_!UO&dg(VJFNfb@)Yhfnh`byK zdFeh6^c#_vBSKzAq>qg+k(VPvUPh#k>*DT*BSKzAq>t-zJ^6m*<>%Iuq*WHuDu>f5 z-RFV0%0gV_a9pLWOTUp*{&*@#XI~2Ugm;^c#tl!-XKVo$gLdCt+aLVeR3hVayYos z)}`M_t{hITv~}q>qAQ1^D{Wo+jqJ+d>`Gggej~hcIK0x(XyzQjUm88IeBLhsdNH5tA|^eO#CQ zEn-qeq>t<3Q10=5CgtbWB{kcwixBD~;!8%PkLi*xIU>GfMEbZcLUE6XFBy?OuFLgg z#FvanAJ^r2GU7`{q>t-zKOo{uMx>AHaz7yAOGc!R>mv01i1?Bb>EpWeTf~=)NFUdw z-y*(bMEbZc{TA^hBhtro$(I}vUos+nT$g@}_>vLnwpkv^_VzeRk>i1cw?`Yqy1Mx>AH!f$89myAds*M;BCh%XtDKBh~) z9|3%{KaUos+nTo-;jBfexr`nWFqc1C>3 zi1cw?`0b4Nk`d|Sy71c>@g*bD$93tqh%XtDKCVl@MSRJK^ttLP1<3h_GvZ4|q>t;; zZxLTIB7IyJ{q2nSk`d|Sy7U`DUV86`5$WT)^czB6y1MxNrW7E~n|?vx&8>_`AFr2w zi};ce>EpWeTf~=)NFUdw-y*(bMEbZc{TA^hBhtro$(NiFUos+nT$g?uUk2{wOGc!R z>(Xx#Uos+nT$g@}_>vLnwp={&AW zzeRk>Nat}~`Yqy1MzW6Sk}o+UzGOt}xGwz`@g*Z$$93tqh%ecBiO@>E>9>e48QC|cOTOfc_>vKRwp z0XVKpzeRk>NWgJj`Yqy1Mg)%Q(r*!8GBR*nmwt=*k`aRAy7XJbmy8q~(6ZxLTIf^b}yev9~$k%Z&A^jpN2j3^w}rQagHWMtvEF8vnqB_j;S zb?LW=FBxe#u1mi~e94Hzab5Z?;!8#zj_HywIU~MgB;2?z{TA^hBjLt%>9>e483{M8 zOTR^Y$w;_yUHUEJOGa9a>(Xx#Uoz5aT$g@}_>z%U9>e48EG}HOTR^Y$w;elUH9AVdBm5Dv>MlSze!g+p!e@@)@++D_!8-g z7!P#8E3e2ek#6nm-o5`uzGMYoB3%*Vfi8IE75OF76~TJ9?ntZg@pZpRS2Gaka=#n- zCDKjyyGL4$*Xw?hu88rVUd^`ay5FR$83=T7K43+D$?bW>myEO;ua|y{_>z%UbJbPA zjd2R9H}Ts@t8rcLZ_-WtHqvTb*ZZ4v6TgkL8rSvpq;w;{@e-j8`6beg{KiX!Ht;3V zjr_*^k`4JK(vAGaON2IDA|&0&Z@ffkLw<>_b$f4S<wpX*I4(zeRk>NUL#O_P2;H8EG}H>+4C4Z{)X{ zZP#Ugi};d}R^z(tZxLTI(rR3n>&b{OIcm0Dm;Ei`OGa9a>4Gm&f?L$zYPMaM{Vn24 zMp}*Q(r*!8GSX^Xmwt=*l95*9y7XJbmyEO;*QMVgzGS4;xGwz`@g*az#&zkph%Xsw zHLgp)MSRIft8rcWE#gZ?T8-&~FS$LB_>z%UwpX*I4(zeRk>NUL#O`Yqy1Mp}*Q(r*!8GSX^Xmwt=*l95*9y7XJbmyEO; z(*<90dmiy6Bdx}D>9>e48EG}HOTR^Y$w;elUHUEJOGa9a>(Xx#Uoz5aT$g@}_>z%U z{(ZxLTI(rQc>e97&3#Fvb;8rP-YBEDp# z)wnMG7V#xV&9>{(ZxLTI(rR3nev9~$kyhin^jpN2jIMl?-y*(bq}8}C{TA^hBdx}D>9>e48EG}HOTR^Y$w;elUHUEJOGa9a z>4Go0Dfl+=Tg|rX(r*!8GSX^Xmwt=*lA~tZb?LW=FBxeyu1mi~e91_wab5Z?;!8$a zjqB2H5nnRWYFw9oi};eGX4`e?w}>w}YPMaMev9~$qh{N5!I#{gM|{aqv+cU{Tf~=) zv>Ml?-y*)`AYY<@8|;fje96K4aTIVv-Dv-Gw1UHXlDi8gW~UHXlDi8dM{UGBe;FVP3pNSFPMe2G3B z1-c`x#^w$8z%UbJbPAjlX|y5nnRWYFron?H2JRBdx}D(cf+nUoz5aTo?WA7V#w~`4R=( zaC{@bkuOoe4Rs^GkuOoe4Rs^GkuOoe4Rs^GkuOoe4Rj;E!||BG;wgBEIA#U!s5;j6=kioJA8^z2r-75npnWFHyh^>rK{^ zXVFAnFZ~wrB`5Ps6mY|OqxB^3$5FrybtAv=ejEkdP&e{h&9;v({TA^hXVFBiOTR^Y z$yu}Qy7XJbmyEO;*QMVgzT_;L$aKk<+#9>e4Icv6Emwt=*lCx&pb?LW= zFFAQXjskAri-<2dc|VQ!|`+jZ%; zh%Y&7woR9O$t~hb&Z3E2mwt=*lCx&pb?LW=FF9+rU6+1~_>z!|`+jZ%;h%Y(Gmnh%{;~ViMXU(?NOTOe5@g--` zM6OG}MSRIwv+cU{Tf~=~+v}E#gbgnr+vm-y*)`ESku5>9>e4Ig2JTUGgQjh%Y(Gmnh%{&soHmoHg5CFZ~wr zC1=gH>(Xx#Uvlz(90lBP93sEfYMl?-y*)`tl4&5`Yqy1&YEr4rQagH zCS+&A{E~dC!_{ua|y{_>z-+i2`m|Z`9vv zw!L2ZE#gbgnr+vm-y*(bq}8}C{TA^hXVFBiOTR^Y$w|IM0XLYph%Y(Gmnh(dy3u|B z`4R=(P&e8SAYY<@8|p@WtJ$`BJLtEFFFDDVDByeu;G9HwD~q9D@EPUHDA_H`LV(-1|P0F8ro| z8|nuAO}g-#0&bw2@FmiP-xP2|-C#W_UHXlD$&}=mNSA&iUos_piFD~V@+DJ}Um{)l z?MA;Pe2L&w`i*?al;oF4mwqE(G9~#X(xuCDNteZuDEimq?d> zBVRHle2H}FH}WM@!k0*wej{HpCHW=NrQas@w}dZ|F8xNnWJ>Z&1ZC52C$f#`&+`7NSA&iUos_p ziFE0=nd`}fFOe?&Hq&njUm{)lZDxN<_!1pfpx?-sObK5iUHXlD$&}=myi2Pwzs>Yp z!k0*wew*pHgfEdU{WjBY311>z`faA)623&b^c(q-Dd9_`OTR7jTf&z}mwsF5w}dZ| zF8#L9ZwX(bLp<~w`I0H&OQcJ`kuRB&{E~NRHRiX4eoOcg>C$ft{g&`0(xu-P`Yqv0 zq)We%FPRd)M7s1F`I0H&OQcJ`t@K;Mmq?d>Tj{riFOe?&M!sZ9@=J8Mjea9vG9~#X z(xu;4elJP*l6Pq}=C_r8OZXD$(r+vMmhdIgrQcTiE#XU~OTVq`ZwX%_UHXlD$&~OV z(xu zCDNteHu^2$OQcJ`ZS-5hmq?d>BVRHle2H}FH}WM@!k0*wej{HpCHW=NrQde?E#XU~ zOTUpXnUeex9fqdgcIz`faD*629bJT8;T_r{5C3M7s3bPQN95iFD~V@+DKk zmq?d>BVRHl`6be&-^iCtNq&iR={NEvQ<7gIUHXlD$&~OV(xu9+&x$vNRmq)We% zFPW4466w-!CV|G;KskN&kE3yi1-pM(5Q>= zC3D1=s1Z>Y>&ZFEFL{?%bA7L$@g+C%B`5ik zIpRxhvp>l9PPN9PuSL@+Atm;rMDrf4?utmnh(dx{=?= zmnh(dx{=?QU!s5;>PCJeU!s5;>PCJeU!s5;=tg|WjeLm$Zm1jijeLm$Zm6qY(7|)2 z*|zmB`I0%}OK#*#PVyyl#FyO2mnh(d;}H3ce2D^Xs2ll>e2D^Xs2ll>`6UXtp>E_i z@+Atmp>E_i@+Atmfo{Z?+{l+G;D)-9-^iCJ;D)-9-^iCJ;D);T1%1Dd$(NkuOXi3# zxsfkXzzyq-{6@Y+0XNi*{6@Y+0XNi*{8luPy(h_+%n@I5BVVF`8`c~7jeLm$ZlD|S zB{%XV3b>(egue2D^Xs2ll>e2D^X zs2ll>e2D^Xs2lmMX50KmzGRO0k{kIF1>CUS$ZzCJ6mSFGh%dR3FHyh^btAu#FHyh^ zb))`9zT_ldGDm#LjeLm$Zdh;RH}WM4xS?+3H}WM4xS?+3H}WM4xS?+3x1x#6Z{$nn zh%dR3FHyh^>y7+IzC-~x(2e+#8~G9i+)y|28~Kuxe90W~B{%XV3bB446_8`K-|B_plI>!sf! zzGS4;Ty(`BVLiD-e91_wab5JcCE`m)T8-z%UhWl95*9y7XI=Uoz5aT$g@}_>u{HiN=?Hi}FiGT8-69zGR8`l95*9y7XJbmyEO; z*QMVgzGMPlB5s#{i};cWe2H}Fw9;7q zWTe&D_>wPKqWqGPR^z(#Tf~=4;7fEKgMN$nk_mi?bm_M!zhnYmB3=3|$}gF~mq?d> zi}FiGT8+;e{TAhyOyEmYFZ~wfmrUSGq)Wd=e8~j9M7s1_lwUH^YHWPTmn>0!$w;el zUHUD`FPXrX=$sP$7V#w$_!8;TZ&7~91inPN^jnl)GSX^%eCf9+zhtD7Uh>r;7g=SzeRk>NUQO2px>hWl95(py5viih%cGIm*|`w{TA^h6ZjJ8(r;0I z$ppScy7XI=UowF&kuLof<(Ew0OQcJ`MfoKot;U}R`Yqy1Mp}*Q(r;0I$ppSc<3PVf ze8~j9M7s1_lwUH^YHS?Hmn>0!$ppSc=TGUkh%cGImq?d>i}Fh*@Fmiv-=h4I34Dok z>9;7qWTe&jywPt_e#uCyab5Z?;!8$ajqB2HQGUq;zC`0ozeRk>NUQOB>9;7qWTe%Y zF8Pur;!7s*B|4W)zeV{a6ZjJ8(r;0I$ppScy7XI=Uoz5ae0=G*_ve@V^M8KwmuIhD zeE0b5vuFSC_~Okc57YC%``srGx9yLgJpALE7vDU-dicZl-@bhH`0SHs-@keJ-OINx z|LyUIXP^DkU!J{q`}WPtFMoVn|MxG?zWD9$KmVKGJo{|cIX_`YUJ#9n;1eBC|L*nI zszHVSoUVgl8bBHqU`kil4~9#ZMg^GC)#b(=!ITwXN>^7{gpV(bx&ln;>Iy?LU4khq zz?818wrO1#MqL4>bajPAxGs#k0!-=ZYMa(|Vbm4DCq3N}bK|-&>IyKWt4qJ}Vx1LW zN>`VDBbc%x_@t{#zwu(76<|tNmwqFdvI0!$>e6q#SZ4*8($$6Ew6pIZ%?dE3s|&wr zr;)l2UUqfiH|^9=*TKuKF8ro1$JBKYtf`CO69u8rZva!ey6~I6FtA<+Q@XnFn||?7 z*FmtZF8rnyBXu22>FUC7YMjson9|jS-xNhfT?d`Jy7U{tloen~SC@Vxn6d&)>FUyN z1XEUkDP3LqjbO?OFr}$WFy%%tWd)eh)urDErmO%{y1MimgHKj~DP3Lqjlm}?z?7~o z{l?&v6<|tNmwqFdvI0!$>e6onQ&xZ}U0wQ(!6z%gl&&uQ#^93`U`kh)ej}K&0!(S@ z5=^-fOj!Y@bam-B2A`||Q@XnJ8-q_)fGJ&F`i;RSE5MYlF8xL@Wd)eh)urDUe6j*e z>FUyN1XEUkDP3Lqjlm}?z?7~o{YEfl1(?#+rQZmqtN>G*x&%{h1XEUkDP3LqjbO?O zFr}+YzcKh^1(?#+rQZmqtN>HGy7U{tloen~SC@Vxn6d&)>FUyN1XEUkDP3Lqjlm}? zz?7~o{YEfl1(?#+rQZmqtN>G*x&%{h1XEUkDP3LqjbO?OFr}+YzcKh^1(?#+rQZmq ztN>HGy7U{tloepgMfdvQ`15~UUOjyN;)l17ZytX4;?3K?`uydaH?QCP^`}$+qw!3d zMR7X#(FdC4Qq0eMG@g-`qEt9o>FUy?q*+$bEL~lilr+l9o>FUy?OiNiovvhT7Qqn9dXqK)nO-h<&1m6oA)QU_+vpNc+xom9k%t%^M zQZ2peBurP9RwW3tItbI1rBlhltj@u7WocAmFsoxQO<7VfH&QUGQ!rgw{oQp>Ln%CX zZ94?hm8DCWv9dY?)0L%38L_fD0@IbHM@hh}PQY|!xo#x@vpN9NmF2RP{LAY6OIMaI zBmS~F{?e7D%SgYhPQP?z=`zAEtHUo%S+XxTvM;N%FI`#vowjKM0agD+iKx{Tb*>fB3LmM&wg%Iet5MfShwui_!zzJB%IHv9aSQ@_vZhDtT_ z%e?C(jPGFSjxU+{=}7UVw)d}zC9A)4+5extx9im;Ij`*g%0cT!1jxq8$nU^oP5t;AG9e&dm zR$+b~>z9*8>%U(Kt1v&0^~*_E|M^N-h531`UrxgMuUFdVY%ZnV=&9zLH{X8oRrlEX z!(^=zoCk2r@G5U<(asCuEn)=OPi~^jvoiVrHX5})Hc^wE*h`jQ^mD=YMbjz z7jgZjDy}VE+FZY@itB3^y*RPEYMbke7jgZzDy}VF+FZY{YU>^3?SNT2Z-z zU%qI(c4KXi*VixNB5w!G((ZVfH&&hhJtGAa4iE(k_>Iqgi^uEbVfcH=3mf%+f9wc~d8ztr3?4W@(q}j|+Sb3&SJaUuytqSh^IADG|qRO)> zxN|P^7FC{A!JTtCzrieRUca;8&bgf5qRO)>xHB%z(gS8`cf8CS&C;W0wC`UgH0QUC zm1pY2!*vF;v^!qRZ|cM&H_98$(m}KIfLYocFDuW~iO2DNG;jae4<*%#=NAz}3LUlk zkJR5emm!6Y+T~(WRFNJI9(2?$mm#H&dO$~g;Nqlw^YY90Z}tA}xBv3;%YS|I&+lJ; z_2%1e|N6&o|M|@yzkUCM{tuqpyu9ofQe{1$vObLI<8NY@4SV=4D&gZXoTR4%jy?Ru zWx%1bcE`(rQ)NA%vNpL?SyjTv;}A`#*uzi9fdPlg+8r+zuqxr>c#{Xl4SV=$yv!<8 z*6w(jRjRB9RMsw+S*6N)KxOT6nK!De2UONBmlG;g)&nYQmx~8RmGI$ufXdqCGH+B_ z52&n7E>%{Q@Nv9R-q^9G5LT%CdE@4xI=Qwblq zP+7a@jd`QWdO&6Ea+x=(tOr!qE|+ftL$1Em zVBY+P-0ngizvPO`y!kJ=Z7%0G{FE!rC(0W;)>OjBTts_r^ z;lJj#xy&1W&J|Z@;Q9N`JlnQT#qYV|&MWrm^&~siRKmyOs})ATW!~_MuEwh~@H`hk z>1uCp=FNZ7?VdOMrYkP<=D+E-xy&1W)YWl_@`hh^HD2b;f7NY|m+MLVtgFrKk{=*8 z{I09<@&%3muG=0j^M)UGHQp$1_+@ud2_JIdzwEZh%lQpI?P|PH-tgP5#>*Ep{@ZSM zy!dffT;|Px+--C51B6QWczmPvWyQXa}^G4b9aM`rYW!@;X9Ffqn zQD{*KAFi`VXxZ4YrV>7Kqxp>;YbxO*H(F0pXi*6txjF;SuTxo-rV>7KqxlVc_$?~o zBR5)4Vh=xYIlo0h%Z5Gt#KrU583`>L_V5!I>&Y_`S~l$Ar_MY4z=7|+&G6k5(mXsKd6=OS-sB(zj9o^z46GZI>= z7|*%L+ZhQhRgC9c<}DIhsu<6?%v&V1R59KoS6zC@MI^LTF`jdow@7HIVm#+EZ;{Ya z#dywT-l9GHsu<6?nBPuRrS;x>RxzG)nYU;UzbeLaF7p-%E&Dv%&Sl;{F0?%U_WZx7 zOI5!*|L{fY+V;=P+Tg{Pajy#=n^a|QuPN%swNHAI;`(EgxPF<7J5T8MuLav&e{2%h zFLQBi8Q13eW0SaknTu=7xGoouP2&1xF0L)(+FXBZ64x(tacvpb=K5okxPF<7YsD$0l)oS`k-g;Q8wp-vPYxI{2_`&y3(XO(b3qPkZIDb zH0jRBq}yrItu*OQbToFy>vzCqWk=%~NpaQ4>DQUx0hJ5819q>6dA6O)yhT!6HF7%F z?|_;i?GD%;FY`vR?To~>YUH%>QfxcX(b&Bne8sV>6x+^7Y^z32AFr=CbbM{a(LKHt z+g6HgCpsFN$AMzoO0n&X#I|bW^yAG@)wZR1jGJ0r2J8abWoD-Nx6=auzm$NRYA_(V<6P=A5if?mJ8&Ln0_KeWQa)P88cY4WV z7t6d-j61#Kv5V#ONH6YmFRqLA=YwUX7I(T9*TpidwBk;;;<{LW8dr@dv+7b@7t5)U zPTc8ETo>!l;uOCyfeCVGU{(f@G6>SFbGmNE))NwvvRMV^l3wCFxuceG3y zb-1M3M5ATOXu~DdCc-jhl;M(U6JeP$x^PLgiLgu=Rk)xx_y7LHWXf$xS%RW>M7C0We7Eoy6zl5xv`d`I-08|(o6AH}nL`aqo6Cuh%G~M7 z+#~n#O#Iz%zt&pg-OGRZO#r1oRxV{kAE_EM$(e(Lr{Nz_Z`T0MnW9t8Nr{iyb^^3n# zx9`8a{EwLY{qO$x2mP|~#0`rMDw~CL!?G)`e!*%i|GCfaN(YtILi4uR;c}XzgL=Ay z+8!_GIXb8;7wV3e6CE8?whMK+oayMGp6;Nwj{_H!bWqtZ)EqAzR2B^BM-E?6cDa6s zUwDTX*Y5D$0hf8hkE!Bnjt#iX8-7d`cmB)2e>K!SzW6b9 zS@C14xKZBb*|zHeKc}#dD~d3cDaMv z<|1z!OVuuSP}^MOZDXn0RitOvlU1Sjn756kYL`2x-SM(iZDXn0{W zwarD|Hg4B@xr5r~B5!Kl!}aSbSeuKysdbOsWIcIM1yk!DxjF++uTu}IU~1hXH(5_s zg`Qo%RKYG+!P>`{d7}z;xeC_hQUz1%9*;xv{B}?U+o*zFu7b74%e+wqyIcipbD1}8 z*L%4N*5)#A>_@v?1#5GeH}<1lu7b6>oZqN|U9N()xt!mqf?ckHwYi+%sDfRtg0;EK z8#~S}SHZems$d&cu*+4jHW%y3jVjpXDp;G#ys_i#auux2W!~6vcDV}H<}z>WIJ;a0 zYjc@5cAQ=H)8f%o{DP3l^7-TjTeZW1elBH`#G^ zLE~z2>2YoJxGs2HT`u#+jda&@`P8&$3gDp!}wywT;l;Bs}j`a8cK zxSoW})#Y-2qs?`}=IU~pH|ks$bgnL!d85yD!RP97nKueu7lf`Rmqypdjn`hguGj^O^aJstVW!@-tUD&Ux%VpkZbzRNF7G&N zbD1{^TbB!4Z7%c1jnUW!~tQT#;XLVDqYFqhE4)$60&4%p3iZ z%RA26T;`2_$rbq}2RqI-`X!floOQ=bzhq;_*%kRE2Mj`;H#Z2iX^_sq^Y6Lnmu&P) zuE;MrU=V7&@Jp`9FR4a5n}_I^T#;XL%(LxW&To-la^PeAWusqmMSjVFkM+gn`^m^J zsYW|H4)jZ|$S*nO*>)~I5V#`0q#Es<%lDI!Us8>B&Sl;rzoZ)NoD09?iu{slv~w== z7WpOBXy;u19uWB@)oABj=I!Ht$)gGUor?X#m+Lpb`N@x8{_*9@Z9QLpKL4-RFV}N_ z`DxohedPvv`XJvw)7FRnT3vs*$2KkP6@6pk`n50aTqS=0Zm7$J>mjaR`{LTW`8LywJRHURfWb8VmNKdlO@ zK!3PQ=QZ2G`jdjNzH$*(d43-24+_HK=Kb+cu0H<3lMaHfTZF~E8y`|N4+0*`g~hEK z-%)k3`n!i&Rao4)@flSYiyQan-K6J7ICvu0H&OF&em{$Mk1bP%2XbMPl%aE6pA0c& zcpmSC_w#PjZ{EHC>z{q|?%nU+{oqHVzqn*)(d!CP?ajANg2PWV?C*`Ny_HyZM!G%gF3X6 zc8@JnhH_F(LjL_~FAnqNwvU!`8D4jOz&_yUSX3*QEXo9VSQyJ?DH!l zVf~&htgnoOeST&1y2I-gmMMeR+q)9b@F*-(2CcV=Wy)an>L4U3!^XuLEmH=mw>es- z3{LOs38%M-Wy+xR3Y(-1M(^tiqgU7@W%E4SJpn?muu00$%BayYW$<~M$CfFB&a2TT zDTB?c(K2PQc|VNy&rGxb`u5GQU%r0x`tm`lEHI*mCJV#2zRQUp9X4 ze&Kuf4rS`U}J zuzt3M4c5W6xt3%7o+|9~D;JH{@2MKCuUv$E{+=qVuUv%nd#bR{uUv%nd#bR$a#?PC z=ia++@zbZUzH$-v`FpBH>noRK<5%uCzH)DlmMP;$?l(SiZ(^A;e&c@Q8}}xbDdQ*Z zH$HK1VQWtCDosX_l{=%wYpX<@bOs)Lr z=yQAYJhu4a=)+a|7mqD6^|?Lzt3@@>SRa0FkFE5 zLI2oO*ynlnPhb4Q&wuf=zxnAG^K!!b09F3u3GwqhTZ@h032~qAeSEQjC&bV5Y|RD1 zdzgKG!)?d*^E^8j8+bzeyi3Ep!055lR z+LW5l+QE&bHkf|Av1m_fVn4RD_zMq5wZF7u@q+iR?Zf+cV*0*O_SU-i zPj33EmOvJw>uC( zgyjof2q4QH2q3~TWe`Aw{aDKW%=7H$dG`Cy-IkrLs-NdsEr~zRv-2R#`|pzqm?lKt z0Y1;O`tIQKJUb7<=Xq8Kfveg7AI`J?)0b60e*4dF{`l?tAM~}Sl5lNJ2{}_!zO8_J zUyo@i0mnh&E*6z;XLh;JGZ&e=u1*+~(qCvFu$OUsp8STrPy+XfC%qnr$xUK}ee7>I?+e1DC?EG{v>0aC^LXVXQ6M zd3>Y1v37Nbr>XJUBWHKK{9#60v~#>s-e^E*i*|COyv?(1_cPY6-d?-fJ`T(qYgcct zU2SujH`cD+Ex7V(=xt!lv zyLx-=YM0B}RsDL0TzKtjo6Gr)ztP-YyV~Y5Z|HSdZm(T!bD1~RuHIg|+U7EEtX;kR zXPP#bdE;){w^zHgxy&27U6$LsUD{mc4dpK4M)Mn$2-z~YeqD)ZkC%Bvy^F>h&2Q*; zk<-DvdF^UDd(BIm%lVD9tGCw%4< zy>_+DW!~67aC_})o6EehfZ+Dp)i#%TV*|nMwX0n&D+ts=g8A4h2-;lcjobR(-a*jj zGH)m6H!mS*bD1}`5Zqq7+U7EEtRc9)hM>)5-ngyr?L7o-F7w9E9B=>3vCU=P_?_eJ z-#NCq%o{&+y!}JRHkWzhmyWl8>Dc9>>Q$W?%$tAe*yb{CsCr#)|JJe1W#0I)#iO`7 z0|A$L!zYj8>I?*2<_+IGimNm5G`BW!w&x*y^eC?GcmbDr!?wQS>I?*2<_(`cimNja zaG5uJ_b9H;K)_|*@ZsZl^$#DLd8#mZ?%cDbN%->aihG^^gOVwueed(sCphyJ;jakM%VMew!Y#&e>0*^V#NPjREXq5Nw(;FpLS<&A#H z0l!4tC~x#j4)`VFMtMX3myUz~-YssFw|TbxyfJT)Us9VmJD2lY|CxVBfq3Jads}(lU@VXy`Rx9IpCM*I7E4)Uvj`N z5jV;k{gMNIiMUbT=$9PuOT>-lw|TbxyfJT)Us9VmJC}Kj{F2(l*}2SH3F{F2(l*}2SH|Ew8@=IzHXXi3+kzZ1qI6Ieli~N#{e#rs9MCUD<-{_Yd*w$CvXnvb#+m8eD7WpN$ ziL-N=x5zK4O`M&}yhVOVZQ^WP_$5OH*2(;aZG^N#0`nI6CAEpOkC%Ci{F2(l*}2SH zCR=|BEO_+)18aFEsKOsp53w(l1#ezoeSeor}C_U(IBlI?uLq zk+&uCOR78FxyaiR`6X4J?p)+;iTsjkPj@cnwds}}rg8AJzf&dZ&Sl;rzoc5!oy)vM zeo57+JC}Kj{F0k~$w|LtiTsi(QupyPZ;@Ye(=Soa9IvxvJ$chFQPCW@kzZ1EHhvtK zx5zK4-ZBQP~{1$$IjpUvknfSt7sWreC7EIgU43Pgbdo zpEu5LkzZ2nan5Dlyj86E`)1Y0IhT2h{F0k~$w|LtiTskAe#uF{WQqKen|_H(=Wsnl ze#y;hF}2Q-8|96Di8kjZH_99R67|lJn>@eW^h-|qCED^gndj-3sCka#O@0rk9y!Ye z`b)+V`6X2(=UnD3@=L0%#<`r|BERIGHj#5VzeRq@jZNkj?K6q<7WpOBR%7Euf5})P zzogn~oXfmLeo3{}IG1^g{F0k~iT0Z0@s09EzeJl&k{jiXe#uF{L_2XM_XqkVC;Cft zJw)qCmdk6uNgRjBFR8W~zaE&k$S=94O=Mj9C2Ew4jxYQYZ8^!~5Y2BanAe_@>r+dSLOW!@scq}pnn%e+N?Nww8DmwAi)l4`4QF7p=oCDm5r zT;?tEORBBLxy)PSmsDGgbD6iuFS+O0b}sW4`6bm><6Pz~@=NY{wv9`_MAeK*-sqQ{ z^h>mIjkx$d;6#7P&<=YMm-8F?OT>+y-`HQG9iA{BM}A4Q)%ba1-Xg!G+G?E3yhVOV zwbeM6d5ip#YO8TB^A`Cf)mGzN<}LC|s;$Pj^h=h=FR8W~=W>3F{E}*`aW3b#$Sx2V6Q+G?E3yhVOVwbeM6 zd5ip#n|{ejzeIiN$$UY-kDcPqM#6AEZZIt|#f2=)>EH z%jY-tm*|7Yh|9dOzeFEsMO@~M{U!P^>3ObBHg?WB*@SgM9&vTH?fPYZ ziGSXahW&zB_ruC5tn(RUow*Z5^YzkL%P6`{U^L8$7>hyv!T+ z#}PN0-{_ZI^h-wKmuS4q8~u`z_$A^pZ`dD4$01rzvcE(HH&{O;eu*9?nK$|+Bk3;@ zmwBUKGLrrhahW&zB_r`m#AV*-myEJq8A*SMxXc^I^*lJ%e7dFmKo&N8FFTFL~Uf_HTdni@$sM z*_(fP`MckKt^KFpz5M;}{`iM)e)})&t@AV#Mig7>Xec^qAO4ATqy6Mw*WVS~*c5{; zb;Q+43%HCZw$u^Vro{Gm8BuJhqZPhQiES<;iY;}-wTQO4T!Kd(h+<0}acxR$kCzd}mOA2EM7vyWsiRIDOtr40w7JY1D^G?iDQzyNL{^>*S5n$s z<_%lw==er?qmrUd92{R)QrhEX-ms;Po~Wa|QAtrJ4#%rA@O&<)q^J{z+$eAJY}@^p zO3H90rG0#vH!3N^m6R@*N{TvhcpPj>Y;&16Y^kH`A)4Q&faJ%QuQXjrX^)qA!ck;8%G*5KetelXS5n&JW!_kMGF(Y%bD1}6 zsiQZg(Ry;8Z9fkD3Bi?=_IQ~$Dk;O2ls1=nqmnXQNojMLH!3N^m6SG@d83jtTuJG2 zsia&~QidxjZ7%0GDk;O2ls1=nqmnXQNojMLH*Be+TtxHRJlmEFZmF}nlF}Y8^F}3Q zbtR?EW!|WytgfWAxy&1tl+~4#HkWy$lCrvz(&jR6R8m$~QkvW*Y`b>jHCWOXH_ z%|+hSi9>F(o~(kK$Lm*}IOOUKJpH^`1vk#cPYA0kDc$2hB}JV$9Iwv6^W&wGqD~xg zll5d3-1u?8dUEy3llE~y-qeZ1@h0=zLM26=IN-XH(jG7JrcNAkljpaEN{Tvh$kiP$ zxE`1{Dk-ZgDedEc`AwZT9B-62DkqD~xgqr6c`Q6~<$ zIs?IRVBV;ttgfVVuLmkAHFbH!3OW#347D->9VA zR8m$~QrhQ@d83lDx{}i7GH+B;)*^kcMz*=k8n^m6SG@ zd83lDx{}i7GH+B;R##HmT;`2R%IZo=o6EdWNm*S*x3Dk-ZgDP1m=l$%P*>PkwR z%e>JqStGxs3T`ZK^h?&rFInc*1T7WpO1JloFY^V`S$l1G*3m%sb^ z-`>7|`KLd=fB(DRzWnRkH@|-Q`pxfO{_yp?xBvd~SIg^<*75QmFRx#Yy)75L?zpJ5 zOQPSzUr)cN=9A_p-6CQAniAIU;lkQIyo>c)xUjxt64sVXU94YG!uk~@tgV>3Sihiz z^$Y6t^b4ws_3KGkzn+Ahr0>@?U98`}WeWT20AcNQKo{$GZ(;rIo3J|i&yUt`-opCJ z0AcNAKzFo$?-tgdO@!6ae|oe~m4s!=Tvck0cAn>lJBzSPnVU*oEK>$iNe3ZG8MbE9 zXqhtil)9s3%AhH|o~|i%u}m2(C1EG&*_1(2(k`z|nfK;&N6VDKQPOCWltEF_Xqhrs zl)9s3%3vsIv`NY!C~34znRn(qjP}pWvmcvamoNMCt4db=GFlc~M#~;tM#B2dTJLiG zG7|Rro3*fh842q*Yhjo;p*pI;IQ>o;p*eMuzj^EYc@eMuy&->ijwen}*(->il8CDF3GR;n%lax_zQ~esTNy_N9Ehkgv zZd>;tFlA8Nbjp&HaWk(4W}7A|F?H<{_X8=U;goUefjPejw z!zZ6(#YI%r4@<5`wadkfsD4;-J*!dV8n4ZYZ7u?P;~7R=4{Y~1U|v)|ERKUe#I(n&v+c*h zBdf2eEwXJc^M>`Oxbt8B{dLynGH+ObitBmn9$)4SD^PJQZ|(6iZ&-qgYkBK(xdv4~ zEUyR4Tbs+gVG*kFMtS2ZRQ<3VZs&ZHy2P{Xs zTuyFSkE(jZ!d6XFo$+#VGH(3PV)YL#+Fa(1A6l&bp+)<8VBYwl#p)kg zbh-S{Lglc$9&B=Jb2+*3LyOfvv}oSW=E=5L@H>muzq9CKnKpiAvHE8g?W4e@BtNs* z{4%6@nhFt2U?fkm6k zr11lb%|Ebca~U;$V6piJ7HzI)O;-nAl59o#{-LeS^{k1Dmn55aezv)uHF5EhWb@9? zHrK-@E?$ys{((i8iw`WsW!k*+v(5FmiHmjQ=6lMvxt=$1@zA#U2NrFv=S^JZtyVTq zUuXEhLR_pPH~+w*Jzme7xOhpj`JS?EF7w6@EH>}_Y;&16eqgcr2NrEE^TrP>Ht+nb zlze(Fu7=l#xmYEj%$s+9Hm3`GUm+~x=9Qn_;o|!WaTzzS{A_a>H-2BSdF5xD%ee9T zip{^TXmfpf({W(j{QHXTWroU6aTz!NzM{=#-1vRP=HFMexr`gXuh{(iiZ+*V%c0bQ$-uQjR=HFMe zj|20@?<+R{zM{*;_Z2!0%$t8-(dII5{JvuI%Fi~JdE@sLn}1)?<}z>mzGCz5E81M< zjo(*n{(VK8%e?XXip{^TXmgo2eqXWq_Z4j}=Qn;|vHABEZ7%c1?<+R{zM{=#-uQjR z=HFLzxlrNNEy}z>h1d1oc>P@kueSV!3qLlv@LewR1{q#loq-R(!M2YB^9CDUT%Cb{ z%e+B{SA%i#n_CsU`tjv@5-{mrIbV@cT@m((SMyF(h z6W`>*DN!LU^AhHHiK{QUt=vo@sS>q&P?+T&&3=#*@cQ&MfMc6{lSZ0?k_$IHCYDcRg9 z>2l$e==d^k@S2;sfY>Z9-Y%VplEm2A*Tx?JXsTFDk^CDqny*8{bZEz(M=t<|~AoA-Bib1~1hbD1~SO4?kV z2j?`+}ZLL0DYRT?uN&7f(JxRA@cekX;t+rMlFY>m#T+-$;Z?sExw@cbw=8byE9_c03 z*6POr^V=TjCDqpIT;?s(ORBBaxmZu`kzP`5t&dz4yt>x6*O_|uy?wQ{I+uBi^pa|8 zbuRRhJDy0pRBf4A1~&&J2k52T2k52T6h%0Us7$Y&Sl;rzeIg{JPuq> zMt(`PwfcCOx5zK4wpQmdZ;@Y8ZLQ8_-Xg!G+FG5{yT~tX7^A`Cf)llQdfq9Gk zl9hgmN^S6582Ke?*W>YJ-Xgz*m3cb8%v9qJ+JrsTQ$_!eUg3&>+`x?zAvF)!v4H2m-8F_l0EWEs-eb@ z1M?R7CDl;lT;?tEORA#Axy)PSmsCfMbD6iuFR79m=Q3}RUs5GC&Sl;rzhs?f+qm>g z_Q)?;=h=2H=eNi&sgfG!a(;{ak}9cjF6Xz%FIiDrG8WdB?2%tmB{e=?<}LC|s-(ub z%v5^si@Y6?Us6Ri&PCpi$SI^*nUarb&e7wvX{F3f?;g_i22IGZa z(&b`3Ip~)h@JqT}JiiV4B?tVHE|+2jGj`XvYak|vja$)I0yz%S`?;g<~h zB}e3!R9lT*zw}Fv$SKL+G=dP z^h=J&FR8W~=W>3F{E}*`aW3b#$SDXN931O zTaAsEe#sH}CEGmP&Sl;rzhs+d+qukJx5zK4wi@R$Z;@ZJVN;wj=$9N(f5|q_wvCs5$r1IJR9lU6 znYXCFq}pnn%e+N?$;SQ?72F_ikzcZ5TO6G?<}LC|s;$P41LwEMFR8W~=Q3}RUs7!~ z&Sl;rzogn~oXfmLe#u6^Ls>mwi+KV^A`Cf)mGzN<}LC|s;$Pk%v*x3_LrRSOS;FGd1HUc3BRPr zt+pCFZ#U+*)BTd>aj3Q$=OS;X`z39z-rqSFc{?M&q}pnni@cqYUs7!~&Sl;rzogn~ zoXfmLeo3{}JaScVgS<6NvK&&V&Swi@SRemf(-WM_Yg3T}9O z^$Y0J^L(|{_;{JO$SU+{iDfwi-VU%v6e_5Us7!~&Sl;rzogn~oXfmLeo3{}IG1^g{F0shB`Ub#^$_Kaeu)Zh$W8o` zeV%PU4$NERm+bRwJC}Jwe@X9mvYq`UEBi~%$S;&2RH;`*C32BEO{CYMjfwxnI)sUaPIfxy)PSm+bRwJC}Kj z{F0r1i3)CT-Xg!G+G=dP^h?gjFWK2&qJkTaH+es~&$I30W!@scWS?i-xy)PSm+b5> zQNaz5LzK69wtc+JTjZBiTa9y>x5zKqr%mKs<}LC|s;$Pk%v3F{F0r1i3)Cb9HP9@FHyk_xl!J@KaL7+$c^$gZ6ZIuoZlk9 zq}pnn%e+N?Nww8DmwAi)lAV5u3T|+GBfn&)U!sB=a-+P_FHyk_xzYSazeEK$|)*`zhs|nHO^(;BEMvxHj#6Yw+ntr^LK`66FC=o zyWB77zBi&@qJkSgZ2f$lDe9CDm5rT;?tEORBBLxy)PSmsDHL zBUc4C$XlJMXP<|vt;V^S->%3nskR#DVt%_Kzogn~oQwJGiu{s;eu)Zhczl!j?U-lV z$IHA$eo3{}I2ZHV75OCx{Sp=2@HiyzOAhXjqk&b(Di3)DWjq*mnL@T?@zvQ4_qJkTaH_F>Q+df|AE%HmMt;V^`TjZBiTa9y> zx5zK4wi@SheuG~!@A9Aa_^YkPxy&2jgPjedy=Zpe-1w|Tbx_%d&iUs7!~&Sl;rzvQ4_qJkS7 zhsZBE=$EMAhFsn8o?rK|zeEK$72J>;J-^W}QNazlQQqj6sNja&Xnvz#qJkT8 zli%N}t;TXezvPPgOAh)aD!9RTBfsRJU!sB=a-;c;eu)Zh$c^&G{c%)qLvEBe`Xws3 zAvek!`%6@CLvEBe`Xws3Avek!{Sp=2kQ?QVeu)Zh$c^$wzeEK$6fVB2HeOm zIp~+D;D+2NZ}dx4a6@jCH~J+ixFI*n8~qX$+>jgPjedy=Zpe-DM!!S_H{?cnqhF$e z8*-z((JxWK4Y^U?=$EMAhTJG`(jgPjedy=Zpe-DM!!S_H{?cnqhF$e8*-z((JxWK4Y^U?=$EMAhTJG` z^h>r2dAlRO&cUTi3)DWP1chq{Sp=2kejS0Px>W0{gOM{ALpcBqJkTaH_99P zOH^<}ZnB;{*6hG* zUvknfQNazz8|96Di3)DWjq*mnL7WpOTJloD?-Xg!` zq+g=tFikT{gONKOHTHesNjajgPjedy=Zpe-DM!!S_H{?e18~aOC za6@jCH~J+ixB)lvOHTSFD!3sx${YQXoqow3?T>TPFWKpr+);nYNxx*LUvfwL6fVBhU1O$M!!S_H{?cnqhGSqFS(=sl9PUk3T`mo$S%RwRyh+}wt;V_j zzC_$4Z`D@gT;?tEOD_5)D!AeC^}NkgfBN^Ki++g;Zpe-DM!!S_H{?cnV}FSXZpe-D z#{Lo&+<+VTCDm5r*8}qw`6U2mdV zmN)n%>uc0sa?vkQ!41b7<&A#H0l!4!jq*mnL72J>;<&A#H0l!4oLzFlA zB`Ub#c%!`0FHyk_xRGCS(JxWK4Y|?t8~qX$+>jgPjef}izhr%l{E~})$pODa+$eAK zOH^>f;}GSIeu)Zh$c^$wzeEK$-xM!)2MUm|XlH~J+9{1S1aywNW? z;FpMNc`K{GbDimI+jA`Z5^9o5sQOd81#Vf*W$9ywNXF!40`l-sqPc z^h=h=FS+QK9P~?;$S=9*mmKsFIghL6fVBhQ}ew8~qX$ z+<+VTCHFkPew}fCo5n$Ke08>sOTT29#zDZ<*>*1Hx5zKK>6e`JOP0tlx#^dj^h=g# zf1I0s$w|Ltna08M$CrMI3T}9vS>C$$2l^!^{gNf}ORBBLuLtHW@=I>|B`UbVaftkq zn|{ejzhsI0lAC_XNxx)?{F0k~$w|LtiTsjktFiM&zhs%lL2&)*?&@65Z__ww4>6a{# zUvkqgIq8=y?w54$lk`hY`Xx)`m)!JAPWmNF#_a?>wS z!40poC~x#jPWmNF+nxtK_OyA)7RVwWg)!X=ZhubCH)5e!2luJe=m)w*~)NaG!+RKveaCNTj-axlx zL~hAVx8$T-GTbfc4wqS@S~3!~M1>p@W&JQ-MNffB9@5DtlgN{Mk1Dot6S6Kc-3r!thrdyJ-o=8ifxFU zq&M&1zWe6Qw_kkKTkmPOy07|h@jLf$ucSL%WKF#`9B%NMtMS~BAp*dVy zC91XIaD#bG!$sCqYeTNhYu(}M@BAn*YsscK-&NE&msxYEq&r+hO{F$C3f@`L#WHDB zN=C9Jj*bGOMx|s-$>8~Gj7g(WGNxnj0ozS5jgpH-$(WA82X6D|QYg77l#FCU9MyYZ zT2rG9F9wTRceqR%eUdQ^gAYfcdvxiOsL+PP4OWmk44Bp~`XnRqNyKH==#z}3uS8si zjXuekhQWv9+dXZ}8g-J9)Rkzs3>$Tlk?17ia$ciOGNxeg;V^VBGwLK4b&@d!gMiDl zQ70KwF!;djy+&4v4C6+fWF*_+d{<6mGZ1x>k!*(}F5^a>WI!jGXYrE{#Nsk;)JaC7 zlZeZ>Q70MDNxI`@-l&s|L?_XBnK$YrBhg93W!|WhjJjf&{q&aW0 zuH>RlG7_Cc<7M7hS27Zv%dB ziB2Le^G2OyBsz(>%o}x*k?17iGH=vLhU+BVd7e7SMV(|MI*G>1`HecsNOTf$nK$Yr zBhg7z!om5CI>~@e(!B3bCsCgb)=^V1c$nY1T;`2B$w+h(9S7!(I>|_M5^;6wyvg7qF-vG@iK2TO7wGA#AV)Sl;~Bt zahvxY)|FgTO7u$5xZU%{yiqC9tB;7w`HfDA9`OQhmDAYuz`7DGWg{;0MyW(ocEn}g zD3$1z7jZei-FQE#=tNwuCvUu;TqCQb%4z((;iv93vP!C)=8>yD8-EU1>yG>E`|2vE zaW1ryHK{An!9(8EXT$M&-g@_kDyQ-B!Yf&mx)PlfJin>WhU1O$MzKVFHsnTmn`hgP z1H_Vb7Fawzzg0PnbD6iuEU9uD=Q3|@mNeH7RZinv=FQcTHW%}o`fPCCBDZ9rTcSQ2 za+CROVO@#(Y{>Pz_2$ima*6tE$c^SV+9m3a!s?n%}6GsLuvm*GuL__vy#(g?5SRY=}*klMC$<)!C3cFW9H2H@21B)JxV# zFIlLU+|)}}*GrmO#X`O0re3l}ddWh)o5s%@r?*HiscstQa(avO zlIo^$E~mFhFIlLUsLlq*H_}TM>LoYzk~Pvxs+-1+1ND+M(o3qF#<^ThMtaFYy+n03 zJigI#l6uKay<~O0q?w$TT^pfhP zaW3-~=_S=oV_fPbtLr80>w)td^^z5ONps$$UUE|}StGqLsePAvbz_qh6vq8*p7O>0ZCoOK$2VYowP{H;v_u zddV8;B@6YEn|jF_=_L#GlAC(T8tEkq^^%)<$r|Y;3-uD!+3TJl3@Ry&Tcnp%H;r+rm#mRqvQRHkoej=gq?c4T zjgOb>$w)7$ZW`xuev9;yg?fqVYXM^i3(n}Whm8i~!+$e9pd#+%3{es+`91M!jT< z^pa|)F)sCz4SGrQIg5J9O}%7`^pb^*B{%hwEz(P>oyLy?=C>`cidUEsDlIG9;RZ-(y<}K1o2J{jgU*^qgOSWZTzwgI^d5iRtf!%O4Ugj;*ORA&B$IHA$dda|UI2teW=6Xr@K8f9MBw;dd zkzO*Omx#-}d38zqI@8_NjxY6+4c#SEHu+cXZIzdt}P(Q#njTrX*#H~+m`T;?rmFR7{;I}Y?q zHg7L!k5_kB=Q3}RUs7E)&gJ~(eo4(rjl97xk)+MMMSe+j)%bXsx5zK4t{UeuZ(d*0 zJ#X+!bR3ws$S|SZp^T>OSZ@^sj3?1 zGHq^`bcf5yjdIBr$tBfPa*4jQVAvwLq?&4cybN0; zmsC@Ya~ZZsE~%y(=Q3=OTvAOn&SlynxulwEj7zy>i{z4Os&Ovk7Re>mRO4JuZjoFv zAeZQi9_B6TE*X$Z#AV)GE@|F&;Fbu>xJA_^RaE1LmvM{Sk}9fkF5?!tB~?`8T*fVO zORA{Gxr|%nmQ+!Vap{(9?v`{f2QDS4mTaz;bg`V=XqIe|SyDAMeiRtC$SkRv8s{=> zQE^Gt)Hs)Ei;7FCrpCEUTU1<9H8sv<+E855`;eh(YMjfoxmnU(JisiO%{F*L8<{0l zQ)A<$S+YfD$$(j+&nY>%MP^CW)cANgxkYA4)zmnbd5g@Fs;O}<^M>M*<{J%|B|5&$ z8;VQ1T)vs4S+YgNB~?@7$ANi^%#y09aW3-)v!t106qn3q8{{oAORA>E#!Itgi_DS% zvqYa6GjEYuQZ+R`Ugj+_ORA>Exy)N+mQ+oRbD6iOxTI=ooXfmbpgyExyaid znI-y#6z_gnT(Y}a(!4+DmmqSHw>>gTs;0(|1M;?`xTJUgt(qF=B5!+SmQ+oRbD1}o zCEfAr@0`oL!7S-=@mqkJZG4@&*A?*LC3u&M`EB8TI6KUeE*I}h78aN6FiW~z{m%M$ zd>3wrv%@TDa%q+ghFqP2fUEametelXm?hou zdQs49w!wH|mUOxLJ0CCe=4MIr7v7a-iJEOV-no)~I&U;f7MdkH%#!YLVBTn!>@Z8Z zT;`2t$quum$)#DMW*Z(~|1zM@Z8ZT;`3%B|FTLE|+;@amfy|q|0UAXqN0S zOS)YBo#l;Y$quum%jNt=vt)-^(&ch~V{^$4v!u&q-q>8SM`p=Nvt*%JvcoKCju*`( zsySocV3u^b%p03ac9OPa?4%_XY;W8NT_ zbh*qM<&qt8NtesKabuhva!HrVyscbMLN4iYnKy2XvqLWFa`kt9Juq*OOS)X8SLoVrZnKy2XvqLWFa=D(QT(UzhX>uu-sM-eWNta8y_Z`|Ls~5E|uLtIh zddcp3Nt?^O(J$HImvoN<^Ty_q9ezoZi{=v5#WHX3OS)XnZ)`5v;g@u|oZr}7vcoUw zayh@Txnz(0lIp3kT(G%hhhNeiul~-toZsM=bh*qM{gNGiNtesK(J$E}zhp&oiQf0{ z_W<}M-SIMSY%ba1mo&L(F41_IH~1x8F7rmeWQSkU}U zOH^%x;{d;;J6`6Ee#svBB`casR5#DxyWy8~$IHC2xnzf5(&aL5^hOm-M*RQ)B0ie#rs9q|0UAxG~NF zzog4$-q>7nM1D#2)cA40{C2=E>5i9q7xRke-Jn@8lA zR8Ng_F~1#=U$S9ioK@8}9Iwv6)9=r!r^d$%pX;a<*|Wd?xf8|977C91X|H_96}#?kR* z-Xgzb!^Sw`GH;PzQav@63;HETKjGmgf~ zyhVP=HqW+?m-AcXmu&P)2K|yF@=G@CjI*lR2G?2Smu&NF+i{>@azuW~hMjRVUgpjH zlIDB44LjqA%e+N?$wt3K)iyl7(fr2p5_Q{<8_jR?Z2NiR{1*8o+dSLOW!@scq^fG1 z%e+N?$u`fnb2-07e#wTNaaOh4;JihC$u?~w8!!EmBl1hOdA6O)yhVP=#_|%i+weF< z>q+`0YPTUb${YO>wcC&z<&A!c+HJ^KjGtR1d8=SYuFWIm&j=0QQ6aXl zU$U{kLKZO=RPxUvfl#$;SSYLBHgP z{E}*`@$oWmkzcaSv+Z2wE%Hk?`Xws3;dzVlhMjS=O*iMa$SopDwb+>om$=zz=hB>j>j@=G@C zjHB@~Z;@ZJvA;wGH#`o}{6@cI&@VY6zhuMCI64l@TjZBiTaD$7e#sH}CDm5rT;?tE zOE&C`qvL?QosnO%O`FKai@cqYU$V`!ZCv^#XXKY`*cnIPb7DPtMt;eLopHoP-p&cydi3&-{P2NvdTa6zF<_$aJ^wyKrR^wdeE%HmMt;V^`TjZBiTa9y>x5zK4 zwi@HoFF7N>WT#)U(l0q9zhtLhq7U71okjg6JN*)Uh)r&?p4{n|=tE0#qrA~C(T8>9 zMtP%Oq7R73O@0rkwi>_An77C;skR#DGH;PzQf)QPW!@scWT#&uArZ$n@=L0%#>Pv( z6e_5Us7!~&Sl;rzogn~ zoXfmLeo3{}IG1^g`b&2DB`f`sGwLs?wi+KV^A`Cf)mGzN<}LC|s;$Pk%vXXKac^h;LyC1>Q9?DR`k`Xy)NmsDGgoj3X=XVhO(Z8gs2dNT4$s;$Pk zoZlk9q}pnn%lR$xORBBLxy)PSmsDGgbD6iuFWKprtn^FH$S&d9Uq}pnn%lR$pFWKprtn^FH$S6fhZOU|gjq}pn1y!1=X$S>LHm#p+l&d4v>>6fhZOU|gjq}poyI52OKU$WCLQNa!F z>ycklZ8bh#<}LC|_Ib9Q%e+N?Nww8D7kRrPzogn~oQu3&kzcaYFInlAT#;W=Z8bJt z`XyK7msDGgb1}bNkzZ16HO|HSc13x5zK4wi@R$Z;@Y8Z8eWv72NoJ@{0VDYO8TB{E{p3ORBBLxy)PS zmsDGgbD6iuFR8W~=Q3~6{y5cE<6P!#8V65%uhmxLT;?tEORBBLxy)PSmmKqKJC}Kj z{E}*`aW3-~`6UPYOH^=!yhVP=LBC|9Uvfo$$w9wlqhE4Ge#t?WNpgZ(8cxFI*1-{_ZY^h>VDFFEL!Z1hX6$S*nQmu&P)uE;Mr=$CBtORmT-IoMya z(J#3ozvN(li3)CbJw$n%XWQlr?vHate#tS*1T7WpLy`%6@CgX0_d zB?tWy72J>;&2Q{4+31&CkzaDqFHyk_$E!2&{QC#?m#E-|+-QDde~Aii$c^SV`Xws3 zAvem~w2AEc<^DKVqJkS-50PJTu)jnFH{?cnV}FSXZpe-D#{F?ra6@ji zo@9TC3U0`a^2YuW72JRu`6UPYOH^<}ZnU1HU!sB=a-;c;`{Qi%ORmT-Ip~+D;D+Ok z<~RB!D!3sxn%~%8va!G9iu{s;eu)ZhINm64(qJkT8qrA~C+31(tkzaDKzeEK$9B=e~lKmwrxFI*n8~aOCa6@jAw`!}g z>x}#3+>u{WZ8gqC-tNdRskR#DVt%_Lzogn~oQu5OkzZ16HO^(;BEO{CYMjfwMSe-O z)jV=laD(eC@=L0%#<|Q}6fVB2FD@tOU`+=eZ0(DZEOH^>f@h0oZlYWT` zZpcmMx08N}3U0_v=C_l6i3)DWjpjG@m#E-|+$eAKOH^<}Zj?9rB`UZfH+g=mwi>&B zxj)Vw`6Va)5*6HFypdmW(l1fL4Y|pB@}ys)f*W$9ywNY&>6hG*Uvknf+3A72J>;<&A!c3U0uS{E}*`@#}%}TjZBiTa9t) zm)uc*$w|LN1vfknQQqj6sNja&Xnvz#qJkT8qxp?~i3)DWjq*mnLjgPjedy=Zpe-DM!!S_H{eEo$w|LN z1vlhI&u{cgRB%IXlsEb%D!3sx${YO>72J>;<&A!c3U0`?yv@OXy8id1UZQ>*Vl8f6 ztj@KqN@$ndQF}>s)i{@Fi|mr>s&OvU7TG1$RpVSwo7xIq1Dm$GYMkq76E{j5?Gn}7 z*ySK@ls4KWs<$CGN*nDG)!UF8rHyup>TSriwAF9lpN?B~)!2E1U83V_acgs#x7%ko zag*7tx@vs9o;Pum*{!;2oa=cLH<{h4tH!y^TV$71SB-O-x5zH3u9`=#>TPhHMRrMb z)i{@VbGxKE5IWbd&bD)zx5zH3t{UeuZ;@Sc(JoQF4Ucb>H`*ntw;|W^)|)n~s>Tlk z;}*#!RaN6$#?9rD?r?Q)bu7~sxg{6f5|!KF=tgeIMYlxdHsmI=+eNoTFdv)e_t zMCCT*CbQc`w?ySOo?>o-=vbW2ojL$2qo z%f-{1%5BK?ymh(yJHH;7H|&km<#K+5TcY#kdFyhyo`hSny}~W&a&@--I52PMF6nZ0 zwv7w7MB|;LH}BuR`{vEJUwl>1a-Hi;XWO~V8@fxnh=<-r$z#I7E4)TcUCs90#~1-SIMS za7(t=$St|(mK<(oKiOOxrjpjGHB`UWeH_98`k^^qZ_8N7UTy#qgxFzCR z-n#cQx+MqP5^@HEc zjUR_4vP&*@mmKIWQRjb@H`*l!?UE(3OD@_aD!1Wrh~_uiB?s-2CE6S3qFthL8;&>0 zTQ$|#a{%p)&dsaW3=bc1iQSXEoJ07r%EeuuHn*#rqPK z+weGe-kMz6B`UWe*XOq`7kN{;4Y@wQb-DUGKfcTx^pY+Yc~iL!$Ls6KE*E)Ixed7R zOS)X-P31P^`ux`A>TKKbrC+jOZ=5byXWO~V8}`QOa! zB@6tLE|+2jGj`Xvkek}j8dqhGSXFX?ibH~J+D_Qq*)>6fV72G=k4#_4i7 zztJyQrg8B6{egao%56B_C~x#jPWmOwG!BCCGH>)t7WgII$Veq(pZNxx)?{F0k~$w|LtiTskAd*ht+OBVPg&HFF?l9PVP0>7lo<@`p!WPxAO z<#K+bU$Ve2>2f*0(Jxuxmo&NbOHTSF3;dEUm+MLTCCfApo}V|_U7~Uuq+`03;dEUm-8F_k_CQAm&^4e{gMTKNtesK(JxuBH%^z!ywNXN;Fol{ z%p3iZWf}+1U%&KAPWmOwG!6nT^G3g9nZ`lD)$y`*6#bF~d*d{ZFZ~jg+aSmAOS)X< zjeg1Eeo6N|IQ^27e#rvAq&r^bjef}jzog4$-sqPs@JqT}=8b;I0>7loW!~tQEZ7^T z$)#U%(l1%ymvp(z8~u`H8VAqkjed#BZIFv;90Xj>Z}dx+X&eMx=8b;I0>7ktd^x|- zFIlE>5R8|3qhGR2;~?NNZ}dwR_$A%rz`W5fS==w_-p}Zlob*c;_$AHp(l0sbmn`s0 zx?JXse#wINk}g+&XY(8Vk_CQAm&?4-FInK1bh*qM{gMH{q|0UA=$8!mC0#D_M!#gh zFX?ibH~J-G8VAqkn0|@sZT$W_+%K8`k;c#S)JxQEL#!<)TUa%6=(iucdTEyow@bQM zhKGZOGLbcz(R>Em5%zxxSK|qi%-OCy(J^@N_2dg zHhLu^@k-Rjftl^1S2E@Jm8HraSF7rmOWF%gRxSZYSm5jtI5tn(RS27Z>L|o>LUdc$j5^n3C0#D_Mz3VRD`|4+m0a{n z2E39k7msc#w!!r~O@rriL9ax`HsnTmqgSG08*-z((JQ&=l?-?#-Q&x=(JLA7O6KSr z_epvs7rl}JucXUm-sqJKcqLsf^G2^^z$@u;^>=n(r&luIl{C5ZN-laO171m&%e>Jm z8SqNFT&^eSl?-?#T`t#?^hyT2k}g;I@$<%)CGbkRT;`2l$$(eV<#K+bS2Ez0bh*qM zy^;a1q|0UA=#>n3C0(xm&dwXXk^!%z$)#6v(JLA7O1fO;jb6!sSJLG&Z}dtAypk@L zd81b{;FWZ_%p1Lu0k5RXW!~tO40t77F7rmOWWX!wa+x=JB?Debm&?4-D;e-gx?KI8 z<&9p+fLGGw(kr>>l?-?#T`u!RuVlb0>2jGjdL;v1NtesK(JLA7O1fO;jb6!sSJLG& zZ}dtAypk@Ld81b{;FWZ_%p1Lu0k5RXW!~tO40t77uKv#QMz3VRD`|4+m0a{n2E39k zmwBUCGT@bTxy&2Ak^!%z%Vpl^l?-?#T`u!RuVlb0>2jGjdL;v1NtesK(JLA7O1fO; zjb6!sSJLG&Z}dtAypk?ge`k54S2Ez0G`aLjE_x*cUP+hBywNKe@JhN|=8ay-fLGGx zGH>)s2E39kmwBUCvcfCra+x=JB`ds=E|+2jGjdL=8ok}j8dqgS%JS5lil zG~OFgEV(F_th34D;eB6kywy@;Ii^{%x>?d3Z?)7o7w;!mS4-Ml=IzG&$rWx%_c$d zQ#W|Hc$*gkOG|FbC2J&?EZh|5rd+Z@E@|F;DVN-oOIFAwT`t2$xny;@q<%_nT)mV_ zZptOA%O!0t!$!GejpUMra>-4(WQAPPJ-&<^<&qV0Ns~*t*LWB~?-5 zTrMW-3iz;i=pJ7#CMlP!kz7(0H9lT0CL_6|Dr%g|#bhLxR7H(*xtNUPlB%e2E*FzY zX^E;%v>tFS7n4b8iMY%g<&qV0NpqfOX~|8wWQAPPynZQ{+>}dJ$R%Aa=QqkFE98$!SRJ$(j717H_9a|yc$qiKB`f5T zE|+uu-sMUt&&0m&uxy&2ok`;1Em&?3SE?FU$bh*qM<&xFqlA4_x&qMQU zTiz&_tS*&n?F7rmYWQAPPdkV~4!ft%voluK5~C0#D_M!95#T+-z-Z&pI@lr0iDVMB} zOS)XnZ)Gl=qm-8Ft676mkahW&DCE6`2;&MGnxkSG&M_kXF?go%cwy3(KT52B7 zo4EKrK)WYI;;PA};gha!K>!`2o8`T;|Q~k~Wulqh7MPUee{lFVT3JH~1yZ>lc2BxXc^;k}j8d zqhGSYFX?ibH~J-8pebk7_75^{75RW)`!u)Ji0U(y^eHpS8LW!~VIbh-LFA20J3`6X3V<6N#M zBfq4oYMjfwMSe+D)i{@VgJ04;zRVl_lFj{+riVA?*|zc0FWDl$WMESqy&d6tGV)6X zHpLN_^PBr6-QxhiL|o2q?w7Q={(e$i=FQ7X+Fa(1e#sX3B~?}9*8}qw`6X3V<6Pzq zeo1rv3%^9imwAi)lB%k)@zO8Z;FomA%e>Jq*&@HBs%m_^%vaoXfnqU(#Jy!!ObCW!~H`>8`8i+4k`= zZ;@Y8RW-(?U$RAhNmbQ2m+MLRCCwbqv+Z2w4Sq?N%k?Dvk}dK}s;b7v%e=W?(!Czw zm*`go&To-lQdKoRUgj$e+;6dH zZjP2IgOjb%CMm;`S)*mjuw-tImMO!ES))x-1|eIcWy-K%{xI4o;qS_W8?5Sie~d>z9$R&)=+t^~*?D zzgY|W{AHxiWxe!YSig*feSS$KtlzAK^(B$8&)=+t^_#V@z9bU%`J1({ezO+VZ`Q&- zza$dYZ`Q*4l1Tf4yMy&1qFM-lWECqcQwF79*ynH7!ZKxe;u1DV**wn=6QSBim@+(Y zH4g$)2A^M}O;R?`vyYZ3!{b(Ow6OVg5STJNZ8fn>8DxGPgd}D2Jo`al%HZ-hN6VB! z<=1GFl+E+(qh-oq@;67zltJXz-1f1Q{h9goBhRtd|9FhO&L`&C6Z^3(JETT!j2g^b zC$?h~7BiPha&+*Xd(6=0=E&3zrBR~|X08)PqehENsUjyBErdp4F>|RQC&409JA6hR zgka`6(UqmqV&=M`Gqx`NbDrnNOzp54wL@+&bDfYGHCn6>Z^(?z(PHM>;WBEp!OV3+ zWn6ZsjKU@RL-k}`OV8ZA=>kFhseXpF)#WzZO#Sf&gXqYgrn zGL&R#v`iT!#^z|5GB}LdFFHvX_FvOznKCGh&CxPtFc>x3BxMj7mmLD5updjA&9lFM z^Yz&MNdi`=4`^!(;uZbnP`csOM#obl&*aqUWKbNx|6 zTz}LM*Dj?t*Pk`S^*gq>wk~RO{gy4RKWvC=x9msmW?LWWynq2HnO~cG`nh>M{JXbW2Ym9{7uU~?xPETL z^>Z`td>yWz8*%;Ii0kL3%k^_3uAdum{oM4p`hLS!R^s}6Dz2?so5xq*0g&qxs<^gn zZFBuzsPX!}P+Xf)+g!gFitG16as6J{J-&V~6xZ*CuZMs4)*i3l3&r(&p}2l8?2gy( zh5rwGZ`i9ll3v&Sm5cr)13k`Rkt~w)O_G(sP{tP216Xhn1g+7v)X=zRaMiLM2>I{X z^^Dy2>;<>(^KJx45cHP;1~^z*d8zQhId7c*PlI_ImXMPmfdBY2%jxY1(FN|$2^M*G@9fv4y>umdR zVBY+du{~bq4eyL^)884}T+D9+FOA|x^Ba1V-v-_q#f|cY*G6%fH-Bwx9|z_Q>)tfp zC~sKzrt$K5($~Fp$BT7u;xcc(?yb$m^Q0C=;`zbXy|uZ_8`iz)_(pkKXWR0Ib#LNE z&y(wHJD1OszV5Ak9GEw(dwZL{?yb$`{DyUJ;zoH}XWNbg*1d@vJx{K)?OeXU`MS6E zap3%hb#EGPG{0ffZY^JB-hAC#cf45lCNA^l>)zU2<_(*6>o`PtTW8zP8|OD)_tqXS z^M+n!`P=J>?B(Yu^eXH4@_EwNy|u^7ykXs&#vA1g>)y1Sne&^kduxxEdBeIljW?R# zuQXp(r%l}ywTd7Ztb?Y%p0}c z>Dq3a%lVDo?sRXr&1K#w?oJnX+g#3XGMs;_(y4&V*extiP-QDeSDer1w zB=Y9+Zkx-z(cYbI@3y(j8};4k`fi)cyrEb5ZMwhP<}z;-c&7`zZ7%Z$_3~}HdfDbO zZ*VWgjpjGVm#V+u{O0myd%VmW>`RR|n%|&bYP_7^T)*s&7yhNV%$xg{Z7%Z$0aM2z z`aJ*!rpC+P1KhxDkC%Caf~oOF?{9E0HD12Ixr5mrFY^Wo^KH6>+2%5DurS4q@&*m_ zZ9u~mS7+e$=W48b6PNFA?qRl%1LrsNDr>ya`x{J5jhA_I6SF&Bta}re?{BVRwz-_& z;3DWaMDK5K5j0-DzrjUleg}t*DK7H{7op2#-rypB>ulTmFFmG@XG~Ot0=v96j=v5Y1XW;ew&N|zE9GExnRqp0(oo(lGe)C@C zHkb1odX;q?qWNu|Z67c4c6qOId%VmWdX?WU?^SMdnK$|+SLBx*^h*Z)k}L8{j&-)} z_|h-ABERIorroMN!}H`7`6Va)l0m=Ziu@88<~$C_TS@6J=U9q4xyV~t=>eB{qhC^5 zdcbAg=$Dk29&njA`XyK7mq;`BAT*DoS*{UQ?AKLT{Qei4c57m>LBQqtx6OaDmyR)x5y4s7J@v=PVsto3pxDpR$DYDeM22i<_mbm_aA}&rgA5gkn zoNYd!XuSS_(&hS7uEy(6xmqc^NI%Zny{|1g4*rxYu0Q39yRP%sx&BtUz2Pg4xH@6-UPbH`X_N#nE_m27>YWTcyV9Uvb3M8F-nimvnm}5Z7M_#Pt_~-gUO) zD~`B)f=N~hZF))Pc#$_PAdij%^M z@fAm0<}LY(BQEl`VU>`MLzFjs#nE{AG?RSA(Rh(JO+;oDY1MZ!zwP*nqw#Wn`{}PZ z|5C-$I@|9)$mliNSLJEEQQojhNLh9`X<}FzzBrfxYRYE$xQQojhNXM6XOI8VKyv!R`32kSxN=RJHZyQz# zi5tytSS6&(mw8K832D5X->^zZ`MgT1SFpC7P0md4BH$z+v~#*6344XcDS-spJ}tAsRO&Tq*oA&r-L!z!We zOjZer%lQqfgv5>JH>?uUbiw&8StX?LGH=)&OXH35w$8TY7^{TDjh-j5N=V0nc}rFa ziNd^Lm5|08OI8W#I52NmC8Y62dBZ9pjhA^#RtasYZ$~b$ zN=W04^0v;lBnN9a}RzqT}kNtXzp{axPA{1*Pn5_T)zjX z@x-5T#r1nYm+Q~C;`*E`?jn8u#@prkoGY&11H|r`AR9t_j6xZ(o-SPT8KwO`5#r1o@JMQ~T{pqj&^3P(Frg)}i6pqw%}Z{PdR;VVP3+a)-(~-=CE(mLbK5 zR$(oqT`V%n@2tXFM!Q%3kXSPN(qi*Kw4zp)By z`RrnSiWZjf^iQl^EYis@tQxJQvy0W=y-yiGunL=`4BuCE5I7h5_toxbkurW>)t;_N z%J6md;MY}Qla%4(s<500{o`u)ATVY4wyM!4DZ{5#jh54(e_Cyh7GG9{44+kX5IC3lXVva#F_&%ls;aGsler8ZRW({ZaQa8p?r1re z;hU;Po1_e%RF4gxRE1pwe046v7gb^TwCP_|y9a@D89u0Lw8>nC@2MIsQ|8}Oo1?|& zRAD)n`RCLwmMO#6R2_sQW%!t?(K2QJF||8drVQUwkJG=UcCnnx@F`W;WG=&()I+~f z+b^5KCMm;*RAD)n`G?f*LEv15@2DDWGMC{qsz%GX%s-1OIus!N2|Wzy0_B?yFzwiTmf}2J0aBeM;*B?9Fz~ zGhh4=`SWsvKdia%rvV*Xzfb+V+~5yN{JJ&$_{`nC!2D@IZ%O{l{qu5zpO+i_W^JOa z4}RX-(Y(M`Ma#Qq7hPcfX4~9D?N7A7g?=yk`h&Vo+F!KaxS`>jb|SM!^EYg0SkM1o zyf2IEUvtIvrv`B?jcu;SQCyFsxb|?~=K4FZxc+o5uDt_yxvbLRriS9$wAbeP^SQ?B zZ^7c)^Ld-=ufgK_1G>2O8rh5Xv^!Qz@>eQrwmA zA7_&`*FQMDZLHEcy-KIeW!_k&b9$A|d+z(k^q-e%|5EQwSPAw2`cmzm_wD-cFHb-3 z+x3T+NL`~oq3Rm73AKL4`Qk*a{nmU!71t+Jacx3vbA3V;*C$kQZ9;v|{eSv~v_sX> zHw^qEPpDe!P=5K~QPmO`|46D@O)gX|as6dkpK|P};r+q;mqY`oTH^XsgSht8(B}G6 zgSh_GAg(<%w7LG&Ag(_(h-*&`ZLU8xi0e-c2UV@^dGn_Ras8=5TzhJGKi>Bj{XZ`i z{;T=+;rGA$uOB~s{F@Jd{eLbA?04UP_@Dpk!yo;JKmCheNZonsZ(66VVEoBrdr%5J zb}xl4f8mQ65Z9kP#Pu7Kxa;Ws_@vb4`i)6k&#bt1V`_8##w4z1R$RL=mCVvO4k(2d z*E1`wWwy=rCw*}}v*KE2>o(BfL&+T&&3Pzo)s<*my_ zDYW)nWZwLPa+}M%p}1vM}d=@ zf5z%^@fk};mtphISZyxDhR;|!4i>gHSLfP~1H^a zX{#NmKfkhchs&^GQOu|fs9(o2YgiK_tY>Xq$&Gsh+Mu;rGhW;dUlY^5#+Ws%iP3m1 zYu%&Es9{Nruokr*R$ECU!B`O^td9SyCrvv^6N|SteaK9(oY$}(Mx(W$HP4wglICzR zuW6~v`{A~^I@5N4#L5=!*k(3xo6D$SX^Xf%udRf9ITPAQ+QzG^15c3>IHTj>^P0HK znlEl?9|zBxxcEq-Pf*c#J#6CQIr8x3E#2{AeT%r5*A8Fb(&l>H#AV!kflHg~c@r1U zk%zBvX>&bq;xcdbWb^r>S@ZhE8W(Xnv-ujA_IN#S;^HI8;fq|_T;>fOLgVmNE^RLJ zhGj0|uKD5h2d-?mO#jzq?Or`e5FIg)T$;NE6Gr`9hcGH&pE-O)lf+ zD_z=L#tlndba;JwYaZTpviCG3sw2uShh7~Uw@4B*HzCB>ci^j{m`I49Jc(LY1 zT;|Q!ytKK@8y3CjIC$Qg(-2m@XuQmuuX<^ZmwCgo7j1kSJx-!RNaJPR%9nZldSKqL z@I~W|@`jZ!dVFWz>g)0Am1 zVD*c}Yj1CDF7t-vFXBddTW8zH%e?vem-cv>H!Oe|Dm+N;lc*5Vd1KzZLa04n<_$|= zG~Ot0SOYWOum(olXnup2A};4Q_fp!&fq8?MqVYy~gO{T5GH>psbjJ%XMO@Br?xnQ3 z%p1HE9fv4ys1VY4nK$=R+T&&3;H8YiD}>ryoo%~6z)KM~`dk91WW3QSIpCBu=LHozW>d z+$m{uIls{#l(dfn^G2!UaH*utW!`9&9B!4gxy&22k|WYe2DFm#hSgEy zh_sRctwdbrEz(K`HX0X~&y$f>GO$0AxcoUF(njpBc=`7WZc(N2 zVtzy2YJ0rQ8+ubUUY&tpyv!T*5)`Ml$IHA?FF|u^n~S`$I(48rwarD|*qth_&OmT{ zkvEp7imNjaaFI8*r;4jH@H&@z3F}kE)fsrlU8Dc<&-2`(YOp_5+$eAB{Jx*xSfDDd z&cM6z_MUgNODef|oWo)p&h=Yuj_cxTO*4?;qKcip5Hr0VGs@h!6Z}dx0r`qOn zexqN4KGimtd81!~EvnjF=8b*{8dbYo`X#JX)p_&0HLo-JCG1ocH_98fs2bd&O5A9E zqhG>SRdGFU%^YKkDvg(Ui~JI9Q6(R_?zK(T6@%e>JqIU~P>TU2Sh z_`Ms|s_pSIZ}dyBMOBwezl7zgI=-H_=5Q9aEmIP zH$G2BehIgz5|?>{U(&pv(J$c^RRayH?c>Y&jeZF#R@+?WjeZHXsA_XLztJy2?@61> zywNW~?@5LHmuM?!+bX-Xg!G8fu)&yhVNq+jj@scL&;cyYnX6cg1DiBEMu`XWNbg z{SvhAw#Uo)jeZH*ce`BrC2Zf-@r~v;`Xy}N6*rpS=$Ej4SKMfRqhG@IU2&u5N%|#h z-yLY*ZJ#$jPtq?z`)-@d=Slh{Xy0vf`Tj<~1ns+RF7w9Pk~69;*-=|EHu@!JR9mvs zFWKmqoRMErB{g>6pD49ei^<6JyX&d4vRvKr^&{cYASW3P`FdD8+z9tYj=UcOIO zS&fgEd2_#{`MZCW)i{@Vi~N!*t8pWpOG2+ijUiN!p=$@65D)%bXsx2V3P%4(d; zyt!Y}y-(6Fkr;&I5cwqs{Sy7~Pp-~DaQ)(WQa?nJyMAGLId7~l(GNM~MtP%Oq7T;O zChu=mR%6!#{gN5^B~@1AT;?tEORB8Kxy&24*Df}K*M>9`b&;w z6WMs_m&~ZYMuFiUoz;I z%*ZdPwi-JQ^h;*cUvgmY-ZAKx%&5Pl+G>2foZlk9zogn~e7ww?`z77y z-}QISW!@scq}pnn%lQp{N%MY2zeGi}xUWb3B?q?f)$NzhlTm+3wbj^hpkFeh{*r2| zaW3b#sJ}#e1L1n0UoxZql4`5*@iK3bUvkhdQLhNEhvfHwYOC?_GH;PzQf)QPW!@sc zMB8lhyfJT)Us7!~K3?W6>MzlDJQy$ik{S6W2mKPQW5<6Pz~>MyCb8s{=^QGdxnzeEK$$Xn!>9P~?6a6@i1ztJxl>@U&g;mP-3 z`Xz(?B{T9%s;$P)8}kgX4GGDESt!=oZql5PV+sM{Us{6 z!F3k-B?tWy72J>;Jx|gv8T3nL8s{Q!m-{94m9E2O-sqQH?w7Q=%p3iZ%l(ozm%qQ!FS+2CbdN8; zm(VY{;Ft8c)mCHYjho|K?w2%=L$%d77kRtfFKKgi-*YbVc13>A zFR8W~=i+(ta=)bMDO6jHbD6iuFR8W~=Q3}RUs7!~&Sl=B?QyED#<|Q}x5zK4wi@R$Z;@Y8Z8gTFUvfo$Nww8D zmwAi!$2sYj?DR{nXn&k)tMTzNZ;@Y8Z8gqi-Xg!G+G?E3yhVOVwbeM6d5ip#YO8TB z^A`Cf)mGzN<}LC|s;$Pk%v6cuQUs7!~&Sl;rzogn~oXh9QdQ*ATpRBeT z=Q3}RUvjd)Was`kSLByeTaAyGd5ip#YO8TB^X7g@_ql|A$S2 zcUN1D9|z_w>MyCb8s{=^kzZ16HO}Sy7WpOBR^wdeE%HmMt;V^`TjZBiTa9t)mt2uw zQf)QPW!@scq}pnn%e+N?Nww8DmwAi&OHTSFJN=R?+8?LdYJ9xRTeLq;wbeM6d5ip# zlYWT`ZgAg;{E}*`@$oWmkzZ16HO^(;BERIMU!sB=9EZp+IoH{?@p6BhEAmTD?vJx` zf1E4wOU`w+eZ0(DZEOH^>f;~ULy>umdYnYYLIoV&Lf*W#^^*AT@ z$5FuzxykR{C;bu?+>jgPjedy=Zpcmil4`55T+lDMBERIMU$WCLxgx)$+G>2f%vx5zK4wwm``72F`lb*5f@ zo~*VS=VE@lBfq5DYMhJt?T-ACYO8TB=C?cYOD6ZnQNaz5Z}L1j*V*>*GH;PzGS}I5 zF7p=oCDm5rT;?tEORBBLxy)PSm&|pxoy)vMe#vBii3)CTJw$%VWPgbYZpcmE-{v~o zb{y!J+>u{0*@T?^zhtt%om$`hbh|-3R+i zZulkZF8^hZe=eKIuV2n@@JrUw?r`z`rh*$BhsZCfwi+8R`%CV~FPY0GaxU{0`6ZM6 zB`Ub#aftFpzeEK$J9P~@>$S;}nOH^>f;~V9T z{UrzcOYX=oncN>o1veaTG{13w92MM<8_jR*FHyk_xRGB{Z8d(KF>jGyGTC3Ef*X!^ zeTjSddkOnXRB%IX^!~>Eaa3?aZu0xvWPgbYZpe-1H~J+ixFI*n8~aOCa6@i1zp=kW z1vlhId81#Vf*W$9ye*r^a&aGP2^nWE%Hky{gQ)z$sPG6lYYrTzvPbml4`55 z<3PXUj{K5pt8pWpNUeu)ZhaGgc{C6j)M3U0`a^0v;l9|z_w@=GTD5*6HVyiwlh zm#E+d+{iDP^h;E5LvG@iO!_4%xFI*1-{_a9;D+32exqNaf*W$9`Hg;w3U0`a<~RB! zD!3sxn&0S`sNja&C~xd9QNazl(fmfgL@PXkUvfu&NwwA3@nwI>9r-1b{Us{6;cPv(Pv(BIq8=? zkzaDrFHyk_#~bC1eu)Zh$c^$wzeEK$ z72J>;<&A#HNx$TY`b#eQB`5uoC+aV`=$EMA2FD@tOD_5)D!3sx${YO>72J>;<&A#H zNx$TY`b(;<#-6L`mpqYQQf)QPW!@sc<6Pz~@=L0%#<|Q}f;<&FI%D!3sx%G)~Ietem?$S72J^Pd28Nx=$EMA2HeOmx#^dv;D+4f{q3e-GU1o(Z&82AO}}KqFA+D&8~u_A zzeL<9Z}dx4aKqyp<&A#HgkPfZMtP%OqJkTaH_99Rk_o>=|B@_K6;zoI+UozpBh#TdNeu)ZhczmP0(JxWK z4Y^U?=$EMAhTJG`^h;E5LvEBe`Xws3Avek!{Sp=2fE)QG)mCHAlLzw_`6V~~5*6HV zywUR{{gMg4WPgkH$GPd3sNja#qZ}dwh{F41G@=I>|B`UbVaftd$Zu%t?eu>5#<&A#HgkK_VG{4a= znea=*jq*mnWWp~IH_99Rk_o>=+$eAKOH^>f>%sH3M&I}jL%&1?H{?cnqhF$e8*-z( z(JxWK4Y-kCa?>wS!40|5^CbNe72J>;<&A!c3U0`a@+djeg0bU$RAhNwwAZ^?>

6fVBhU1O$M!!S_H{>RHtF{_DZ}dwx_e+|2 ztF{{FB5zydmsDGgbCI_#@=Km|ww;UT$u06rs;$Pkc%IxMzogn~oXfmLeo3{}yyvRm z2G^PUCGG1$PczQN^W+x!CDm5rT;?tEORBBLxy)PSmpt@KRB*%NYx7%kK7QzzsNja& z z72J>;<&A!c3U0uKU($Pzeb`^3f*W#^_qT_Bi3)DWjq*mnNOH^=!T=@Pt-TMRm5*6H#8|96Di3)DWjpjG{B`UZ9H}XrWt;X_3zhsO2l81hY z3T`;w=y{TU$wj|pi~N#@e#u3@WLw5TaQ*6R+wrAevPFK$L%-yrU$RAh$wR+H1vflz z(fmfgLp6cve zOSZ@_dFYp1^h>tLFL~&fT=Yw}$S-;5mt6Eqw#YAe=$EMA2DwM6(J$FnqeU=YexIaYvPFK$L%-yrU$QOZAQ-QnX6(LBzhqm+LBQ47b}qk9M*SrZ z{gR7*$>x4Z_q~PvB^UjY4Svb`dh+Gp(I5IH7yXhg@=G52B`UZ<-j;Fj`gx;Ya?vl@ zqW+RYNG^FOm#E#wPup<0q&r;BZFEaUhBzjiESieiH6Gu$%j!(#1e6twFf`EjYKRF7Y~wZwn5hFQS8SL;N8QEtf|(aH*s_TtrQ!HpJRHTNlfuQ7IWoWr>ag zqei7<_?9@`;WBA7O2%>wf=DoGG)l&D3_f$4!=+H7MjM_qOIr7aL!m^CHso5=y2EAC z=#z|P7<@ho?cwUbZ&9O9GL~Twa2YlFBqQ-j_BZ+@Dzw4jP5Mg2W!UJGjAa;nJ`UZ} z#;j2%8HrA!;WBL0Nk*cRh|921CmBmH_xu@f5i9qqfRmsokZhh-l&s|L?;oKd81A;>WY2&Ig&cbO`T*UI*Cd{m^bPqBhg93W!|Wh zjHIqaT;`2B$w+h(ahW&jBqPyD#AV*7lZ-?s5tn(RPBIdmL|o>LI>|_M5^Ler4 zNyKH|sFRFDCsBC{zLDJ2Nk*cRh|9cDCmF7jbmt-JBsX=Eu>^zH=OOAO>a)S)*($II zxXc@Ml9A{nI=;*sb&`?jB;qn})Jet?41(jpyiq3^&`Fx}CUugVI>|_M5*-KTjXKFl zbP|^yF%lVBu$w+h(9S7!(I>|_M5^Ler4NyKH|sFMuWNxJt*>LfRHl9A{n8ZYNJ>Ler4NyKH|sFRFDCs7#*^G2OyKqqP5 zcc_!7&jz`GPSWM_d6GKGNOTe%2j-1B$w+h(ahW&jBqPyD#AV*7lZ-?s5tn(RPBIdm zL|o2qtScFbP9iSzMxA6NI*GW<8+DQaon+1WjrVTqBsX=Ek?15U_u%|Son$0BiMY%g zb&`?jB;qn}tScGNNt*Wu>LfRHl9A{n8ZYxkon$0BiMY%gb&`?jB;qn})JaC7lZeZ_ zQ70L$lXT}})|K4!Nrw9*T`q-^n?lL(x{@}Rd81G=lDZO=hA?jwN`?z1?eQ{i6iP-S zlxV!1-&j|oUuu)*Uv7tU((3o0e*v+?IB zefo&FoZsk_=oK&ERymFR>_n$TkFpV$d3*3YsVO_+GH(yw-*n51xXjyw?~-+2H!EJJ_q=!K<9cxzI}Xq^?8<5A&P)Y&c%eTkrl* zumdRVBTCTY0hs|PUBqWEiy|snkDM9 z!Etc2q&;3dPpZ#`++=>+SXZJx8*+Vq>&-(O-4gZLkekeJ8|zBcXG5;%tvg=KZ|bul zH=5sQm#EK%+$e9fOCH)K`zo+__Z_i$-(g*e`fNDfXntc|iTZ5FjpjGjm8j1KT-Qt1 zMfc^`?u~Yd>THOO;zqmVp%d5iRt>ZWln^A_nP)lK7E<}K1os+-2S%v+?FR5y)rsh8}om$a`3&TrI9cIYL| zd6Rm{L%n2=^pcHw$wR$lkMxp_ddWk*WRLWc>ZbAY#=J#($ws|IbvDRxq?c4TjgOak zi}aG}rg1Lw=6Xr@`lVj-P%qgdy`;KnY`oM<_DC<;sF$eD2Ino(OE&5y5A~8g(o3qF z#*YK%w@5FkZW`xueuG}pyzfviQJoEsZ}k4gwi4CZkQ=?fQ7?I@m+X;VQr$Fue3`dM zFR5-C=W>3F^pfhPF)sCzJ<>}y>LseP!Fh}HlIo`M@$&Ozq?c4TjdPi|NH3{w8s{=^ zkzP{WG|pw-BE6)#X`IWvMS96bz2u=@vO_Ov-gl^%sLlr0S)`X#H;o?$<}K1os+-2R z)JyhAFWIP zP~%)YPaer`ID1vpIG1^g^pXL+M8}tTTf)J+pQU^Ev#O}^@iK2qI0(4m=yi}aF# z-Eedqn72qT8PH3_W!@saWMDTOahW&Y4X1mbgkB;ElX;7(O9u23ahW%-E@}RbKA@L~ z%e5@R z$J9%XsJ*0`YMjfwxn9yfZ~l9?jsx=+wU-R|C6bewx5zIU@JqyH-Xg!Gx@zqB(l0sO zFR59nkvI4y8ZYw}`6bm=C+#0&v#(JVP4vt+<5(Qp~I$SkRv8b7)WTV$40O^tJzw#Y20ni}UaZIM}0 zH8sv<+F+LS7BW;#jdPhcH%qz?4=_tsvkiV>h|H3zsj>0WEIA^xq-tuM%eX~m$$(j+ zWtyDaBD17wYJ9xRTV$40O^tJzx5zB1ni}UaZzwKlekp-jqT|cFMa3mmQ{&@h-XgQ4 zYHFOzyumDK<`~5#tJwy5i_DU$sj>0WEIA^xWWX%ZGGpc~GE1ta#>dONMP^CW)Hs)U zi_DU$sc|mz7MUegQ{!Cb&CQbTmueK3=)5s+ky%nTH9lVEEiy~0rpCF<8_bes-cVe! znr)D`$SkRv8XGUok^^Q*cf5R@q*-!A#U)i!$eI6_->^jgOak zi;7FCrpCFExyaiYnI%t!H8p;Gk+(B4ORA>Exy&2PlJ0o*cg|(rV3u^b_$@%qHa>5jbp?F> z2;Svle%rVo&Iz-m%fw_nY&1(wm?d2<@}_1Ro;Np3 zx?JQ<%{Jt^Ioajvd)WKySIsu$x;fe9dQs47wgDGrNtdg?^YJooZk9BE;oWJLsM&_& zU2obi=Z$8`MziFES<*cY%p1*;6J|-5%e>JnIboJGxim}EY{TR0W=WUJywNNJnIboJ`xy&1jOHP<2U9SGl@6X>ayh@zEIDD8 zbh*qM&5|=ROLm$i8_kjvW=V6rXfD||HkX_*OS)Xfq8>m(&aL5luJ&?C0#D_#*J}K$R%Aa^Ty_q6LLwH%jZdMjB`RR zX>zeK&aP@3-7aZg56m0&lGF8)HkWy$Uvk1P=^h8>jef}qzof}UbBXF= znK$?)T`uQ0Zj5unFX?hQzp=UGgkRF-GH=`%=ZyT4>Z!3@aATYkeo1${`a9=xeuH1q z9ezo7yv!Rn#yR1aG`ZLqN8hKIH~1x8F7w9b zk`sPOm&?4-FFE0tbh*qMn@djkC0#D(H*Sn`Mt;dozeLqGxX$30bjQoQ(JwjSmvp(z z8~u_Keo2?h`HdUnobXG!T;`1%5i9q zb2KZAN}c_0+uQs@lfqp&9ul)l=hK%x^RDORA^Fxp;q@kzZ0hHO_@! zGV6)#)!+RO`X#Ei;qgtLCl73lqv{nrPfj$KG_T)vw*5HZd2*t;q|3$prfM4=2i@^r ze%`5`8XqtGk{S6W$2!~2W!@scX1&$GiUJFXxSZiK=bLjq=9k5>?xft1}RcmwBUKG9$m_z{WVcs%<#lC~w#pM_lGD z@=Ffvj3X}d7WpLyn@a}$k{S6W2b)U<{gN5^B?orK*$4fS8TlpEQ)Blt`Xw{+OAh)a zs<-%AecjHC0$yhVOV_0;%zW8Naa><3PV;Mt;eGopCf?K2N$|()=!WU}qe0Ilo1I$w9wF)iyl7 z(fr2p5_Q{<8_jR)Z2Ng*-Xg!`SZCY0%v3F{E}nYM8>6G zG9$m_ST>P!`8*ln!q1j&-(uyv$qVmmKs<)NaG^MtP%OqIMf{qrA~C zQM(Pf(fqc~wjW>SE%Hl_b+(<$yhVP=vCg)0nYYL2$5@=K1@RpVUdE%Hka z?2NOk-Uio0xzYO@{SwvNkQ?P~oozq9%vBF7p=o zCDm5rT;?tEOAhvzsNe?YE%Hl_WfR$W>6gsNFFCL?&aQ$RjyL*VLcc@>H{|M$_xg8& zb+-LDFmI7xa?meP!41b7f@kV)DXWPfiyhVP=vCg)0nYYLZ8gqi-Xg!G+G?E3yhVOVwbi`ms^G@&zgOg!R9lU6 znYYLwC#$W-j|1}-`6bm> z<6PzqJLB}8Q>(4Uxy)PSmz?xVcJ7RGMSe-O)!2CHmt2uwa<6Pz~@=L0%#<|Q})L(MaFWKprTv2~X zwbl4|nYYLZ5Y&(~Ei~N#m zt8p&!c1M0mwbeKmdAlROHFf*W$9ys^JT1vli% z7!Qsw*1xIX2HeOmskR!w&X~8zFPZEwQNazzyUd!`uQQ!(8!!7y?#M5h>@QKl4ab|T zH=XP+QNazlQQp{JqJkT8qxp?~i3)DWjq=9+5*6H#8|97tB`UZfH_99POH^@PXkUvfu&$z*?t3T}8DqP(%cL72J>;zBll>(sxZ!xCywNW? z=$G7)UozQWa@QKl4aXbhjr}DmxFI*n8~aOCa6@jCH~J+ixFI*n+p>vl ze&hZ)cjT8$`Xws3;drCGvA^VCf5{X1C6oOnD!B3SK9OHC>6aYzOPORx5zKK*k7W88y??ee!JLTqJkT8lliUMYWz4bZ;@Yet+VZ1<}LC|s;$Pk%vRLco+LiRB%IXGQVB)OH^<}ZZyBKzeEK$ z6bi_UvhDOoRfaZ6Zs_<{Sp=2@Hj+yqhF$e8*-z((JxWK4Y^U?=$EMA zhTJG`^h;E5LvHf^cCE8*xu9S2M1IM|{c%)qgYiaw$wj|J1vlhIdE@>#D!3sxn&0S` zsNja&Xnvz#qJkT8qrA~CQNazlQQqj6sNja&C~x#jRB%IXlsEb%D!3sx${YO>72JRu z`6U72J>; z<&A!c3U0`a@XP=xzX%KyF~RisM#nxy)N+msD4cbD6iu zF1cx!sNROhH_99B64l#~YkBKUn^jfghkG6+PbqQ-4d1CkQ>cz>@HEc4Y|?mMz=)eHsD5XNj242j?rCmyhU!wO}9klHXLu1 zH@YP%w;?ym8{HC>+mIXOjc$p`ZOD!CMz=)eHsnTmqg$eK8*-z((JfKA4Y^U?=$5G5 zhTJG`bW2oj18(G&+;mG+ZbNSJ_Et?bmSeaj$6K^F&P}&Ov`*P^>=Yr+ zK2O3eIo{xwbh$d)K3?Vxd*gJuI@`vDTcYtU(&w(AE>~yUxy&27OS)XXy}>Qfcs*}j zuI{crUe0gW8>h*oTQcF6XuMJ0=$5G526@BYINkB;@BBD0Z`d2B%Vpl+mgqS6{MO|% zZ*WVFH@GETF7pPrMBHe8qgyiJmWaDX_&IOuF5kGX(=C~BOT>-lH@YPgZi%>_x9)hE zH@GF@F4D`#fo{o!TOzLKtvO!0B`UW;-lDy6Zn`BCZi&VlJx|gtnQ%+Q^}KbD1M>#A zrDa7#4aC~tI2CfpKnqrA~AQMnC|LzFkV zB@=Fm#vA30Zi&imI9`9AY+k=~OH^({Zj?8=B`UWeH_98`5|!J4>uyQC6*T4xx+N2C z$?+DsB{$uY3AaStXnvzxGU1kp8|95|$%I=XZj?8=B`UY!d5iK!w`9UC(Ric0(JfKA z4aXbhjc$p`ZOD!CMz=)eHsnTmqg$eK8*n4H@JybOT@Ljb?;|%OD5bBaihFZE}4)^#EtUC?h=*T@H&g~#_kf8+mIXOjol>^ z-6c8>QQp{HqH-G_?-to5H@izFx=YmgA3aafE}67Tw#Y8IX_rjeC0o>8QcX4XTur-V zi}uF3X_u(nhUYEGTQ$}Ac=3C{7TG1$RO4LaZHw%ZYN~NA^0q~GNj23t7xUW|*(J|9 z+s^SJ0Uq2-zPV>OPcrfYN~n9Rk;nWGuS1)?>p60<6L~7+}tjy|H_x2tE;KT zx%mBUgI&@cukNnSW!_+yG`X}(RBprL>+@Tei{ArOZbPomZ(Xkb&W{802EC-q)zge~ znK#!~yUxy&2(#_4kPG~-<6 z4SVBsxy&2=k_~&~G`aLkRBprb7Uhk8iOOxrjq*mnMCCT*`txM>I52PYOEz?ubh*qM z{gMrSNtesK(J$HHmvp(z8~u_Ed*gJu%p3iZ4c#SOF7rmeWJ7mJm&?4-FWHuH@b343 zCYOGR%58A{VsD%-m-8F_l5H6W!FcuGxBD6Wl5H6W0hf8BU$QOZAmB1@^h-AQCEer8 zywNY&&|T8yGH>)tHuxo7F7rmeWW(M#T`u!Rzhr}7(&aL5^h>tLFR7*)yMF1HY>{8` zu)9R%Hpua6vv~dbWp|0nZOD!C#_o~}-6h8s`6Um#OD_5)TjZBK>umdZ{8`&@WNB z4RR6rB@eqxRBl6Vls9&lT=Yw}$S--=U2@Sc*&@H>VRy+zzhr}7(!74@mt6EqHuxo7 zF6TG;B^&&bE|>Eg{gMrSNtes{jef}nzof~fUvkke+2EISxqP0aU$Vh3>2mdVc3-Do zvcWIua``+-zhr}7(&h4bl77hszog6M{6@cIgJ06+@_CYe$p*iq%Vpl^mu&D$x?JXs ze#r*Eq|0UA=$CBEIC%Z}jDE>Qzhr}7(i|`S5|!Iv9$LmhFkb!lEpPNoHtdbl9WV1n zzhqm+K`>tCjeg1Ieo6PcC;gI(e#r*Eq)t2KMa4JHE}k1HBRz+wi=3+PYk(jb6!E zO%}m;l^;tny^@i5B|5&$8@-Z|cqQU8Z}dt=;+2TY*^OSwNW2npnKybRBk@YaW!~tO zjKnJumwBUCG7_&uZ8CV0yy=w;cqQvn3C0#D_Mz3VR zD`|4sTXNGY8SqNFT)eue*amrnSJLG&Z}dtAdP}-o&TsTe2E39kSAS>oCcTmYucXUm z-moXmG2oS~hvCM3l3vM8uVlb0>2jGjdL;v1NtesK(JLA7O1fPAot-y&B?DeblS{AU zrdKlHm2|nx8@-YNucXUm-sqJK^p2jGjdL;v1NtesK z(JLA7O1fO;jb6!sSJLG&Z}dtAypk@Ld81b{;FWZ_%p1Lu0k5RX)!$j(=#>n3B~329 zlAB)1fLGGxGH>)s2E39kmwBUCGT@bTxy&2Ak^!%z%Vpl^l?-?#T`u!RuVlb0>2jGj zdL;v1NtesK(JLA7O1fO;jb6!sSJLI`?<{ZhN(Q`=CYN5xO|N9YE9r8XH+m%lUP+hB zywNKe@JhN|=8ay-fLGGxGH>)sc6cRSF7rmOWQSMM7BP~ zsqy20pSyQ=OWNaQ-YA#sE|)Ydg^j%>Dz@?OzdP&_9k<5!$!e*2e;ib7L+&Dd{=K`) zMc!0wL$2<4@3=Z{t??pnDz+hakzOCKt{XoNuuJx&x8&Gpm#El=+xvWRK*MjdICDxny6u z!MlsMc`>lG!=O>rK|B|GGj=FOLK$wRqhhg{O-GHjGfc9%=)r{u=fOS$Bs zT(Y}d(&jR3luPzVF4-uTJd{gz$R*w5%eYZ4*&&xSxs*#D$|bwYCEepox#Xc-vb$W; z=5lhQT(U=UNmbO?!vp1#J(5eRqQ<$L+#(7&2F6TGOB|GGjE|+2mdVmN&{JJLHmP-dI|qRvR2&$R*wJa(<&+vO_NEj+c3(T(Uzh>5i9qqg=8>F6nZa zH_9bD?#;Nt?_0jdIBjxuls3Zi@3zF4-ZMbh*qM<&qt8NtesKQ7+jbmvp(z8|9K6a!K<# zqg?V(F40S>kEqN%H?2t>E$AO#TJd{gz$R%Aa^G3O3hg{O-GH;YicE}}NF7rmY zWQSbRy&gEfQ7+jbmvp(z8|9K6a!L0%FmIGgcE}~&@iK3eOLoX5&GAw$c_^3ckW0E; zK2K6E*&&y7x%xYsFDRGnkW0E;=8ba64!NYuW!@;4?2t>E*8?}jc_^3ckW0GbW!@;4 z?2t>kT;`2($qu=s%Vpjum+X*Bx?JXsa>)+4qM!7`0+#0ucJyb=FT@RE?w40}Kd*`hxYMhJrH|^eN-0pbw zch1H4N$pY>aXG&|_&%v!s3I=&M!7`0MMYdbPf{+?@5>R_^QOB2zE2)ebxF0GjEVf#AV)=ZV+%i zZ{jj<*c7KbUeBAj%vJqIU>KLs%q^1OTXlZ{F17waW3=beo6N_gI}VjN9N7_lBVoAP+lS~^A`Cf zRaIlhfquyWzodCTLwSkD%lQp{Ns|k|L|o?0{gUo^gI^*p^X7g@_q?IJL|o2q@JqVK zfqA1}a=p(&g&!e7wwCZp@8~l>)@nzoVmmKbwG(Ehr&bE!0e#sH}B~?}9T;?tEORB2I zxt!nJFX6aYvOSZp@8~l>y{S1DI zzH%~eC@<-9nK$|+2g*yD=M8>|#>@FF@=L0!#*Z)a=6*@{xf*_n#>>39U($W9UT53K z%e+N?NmbPtmww3+`6X3V<6J&Z!Y}Dw4}6}aUvj`N>2mozNx$TX{F17w@#Da}xnI(~ z9^jYgR|U>*kzZ0(H9lVEE%HmMs>Zp@TjZBiRgH6*x5zK4sv74qZ}3Z+_sMm(jZ44e zi2RbOs&Ov!2EU}4i*>f0%lR$xORB2Ixt!l3zoe>aoXfnyFKHeJY>J~_+nBeX_DlZv z|Lg02`s({{|MSPMe)-j}{`~m_*mhaWzE`tTRue){2$e)Zj_Prv*0uYNJU`ueNi zfBNn}fA_<8|K;O9eD%x!?VrB-_J8c$OJ=Oa2=$n@J*>|Tm?K=AY_mB6NhSK^I(G%B? znz%kcifg}@x4C{Pi|g~FxOzhQ{Ci`YtNYu#NQ>+9qwZt&dwHAd&!gh{{3x#dUf$;V z{P?!xdyBYhrv34E%r@8G|HSqAQCyvYfa~+4xIRCMyJncz$Lr6d;`;n3uKj-Z{y5;) z_T7hXe)#zD(|6zh?T2sv?%V(L!#_u=9j0T)PPO`}9zXJ&{!;#aFh3n8as8x->nG(n z{iVFk^^+p5pA>O}lcMqZNfFmiiny(l@^60kkAMB!k01V*kKca!`onnpH-Dl3J%9c6 zhx6^%FPs&=%4@r8yTxfV3e&qwZw39!PXRlYis)bIw@z{W*4gFyty5gTb&Bh^&Mwz) zo#OhfQ(V7wcDa7*6xVN^$LX)~B|>zLuirYw^;@U7e(UUx*KeH?Uzk#Vm2Z!iDdkd; z(_iJ=T&9$-@~6Mbx4BFyU*%7KmG5$~R7A&@dGlBKHrF3j#AV+6Rldz--ndlc^jG;d zmwDq-k<(x0+g#?2OGQq9m2Y#IH!c-9{Z+orW#0HIfBLI@o6Ed$smSTC@@+2j#-$>s zzsk3{%o~@Aoc=1``8Jn%<5H2+mx{Ex%o~@AoW4|~ z&1K%WROIxfB5f}7#-$>sFBNHXnKv#KIen=}o6Ed$smSR|McQ2EjY~yNUnQmZ7%c1r6SXpinO`R8<&bqUn7d1DXh^ra$gF7w8vBGZ?Ow7JY1mx@eZD$?dM zZ(J%eeW^&Bi@a$qk>4k0{W$pfQ&R7~QwxLM-zT+}h+Lh4m%kI#!XW43E6c1O&0ilc z@}}*sIbNNC*T>7HBHHenT%Cb{i@a&SYjTtMtriCP@x}Z$eW^(II>R=%ht?8tygCEH zaX{X*mI&M$;mg+pmx^f1YjSl4g7GqMTq-hssYv_yVt&)6*Boz@H!c+!Tq-hssYrXg z%o~@AOkXO}<*vW8>z7MKrY{v~bD1|T6`8(Nq|L?rrnN*oZ+gOb{W@D;t^GJKZ@yHd zJznOGOGTzH6=`!ZzYSKAPG2h0<}zP#2o-0ZL4eEl%8$D01v+dUdpC_R% zbjQoQL0vc|)P*jWd4swjuI_lRKRVn3rGZ2iId4swjZuI`f zr6O8O#N(hd@cMYy*|zJ9OGTzH73t=9oo(kbZ@yHd&1K$LMLK<{NSn*Nv5Iv1Qjs>7 zdE-)%=}Sf0T;`2d%7m5D%mu9!ZF`OD3|2~)%e>J_nXpp2T;`2d%7m5D6gsNFFBS?aMt;e$&bD)z zx5zI!*4cJ0^A`Cf2mKOld(HC}<&A!cw!J1d${YO>ZF@~_^gM|wQWa1!Z;@Yeth4Rs z4SBmFzvMs_sm6=EU6EgMESt#2OTXlb{E}Lu=3M0Miu{sVqvl-X?TY-8TBGJ%ukRtueQC$^$__b=Q`WYW!}7swE2DKTxZ+4%vnuHOH$n@bY(eb(! zPWmO<_8Q~$D$@4#z`W5fxgx*hWEH8lz2Y1VXNC?r(be;6>0Z6qhGSKiu8*7k`r6qYP`%_Z5Z2Ng* z-Xg!`WEJU7zvPPil9N@W+V&dPL*$p7*y{Gsw%6q9j`w>@yXy0pc zqxp?hq}uqJ+$e9XBGt~<6fq?Lm&3nFQqR(Pp-4=<7M6=zvRSLw<@Y;-Xg!` zq+h~n3>}B)d2*d?I}Y?qSdG#9UHV*S+qukJZEOSJPf^5#{f-RCpVDFFEO#Xy4@Em<^LW`j*yiGQI_;26uFZpOE`K**&&lN;N}J2) zPWGH!?xD1~eC}k=$>knOo6Gk+dMKBBDDS!d!|QzBZ!fgKp7d3;lQzz;`zr7M`~N~K zU$x)Zb<8L$Uc*| z(k9oQPus_Vxumahxv%n`>(}{z`S{y^EDZ`vM?T>B}a%|+g{%^11%siw=N+M?}#$n~jkO*CJ= z|5j1X`y6Y#6moqk>~fJeZI40jBK`PjzkM8#H+AcfYoBV`T;xsNI^fpF=GVuIylK;I za+CROa+h6gx=n5}zfGzw+H{-TC~vGzQMV4cQQoMwXwz+Sqr6dV(WcwvMtP&!qV8dG zqr6dVQHL$LQQoMwr~{PTC~s6-)JX`gt1aCeQ*Aj|opQU{(&lo0quO%2+S2B7exurQ zyV}y`>TKJ6oodVN)hTT*=QpY?w^yfhxl~&Ysx7xyr?k0vp46t>yw0M$QEk!MJ94AE zQEk!M8giq&QEky00&rbzX&+zCZ>&za>t*!id6R03Hr?iUqxp?$i<~-gqxp?$i(E2t zqxp?$i<}N}qxp?$i(CeBqxo%}ZM*MKZMj`->0W27PC2Ny+(ml%I-}ZhusY>-wWU2? zK2KuT7p*x3R;S#qwzRp- z8`YNE)s{Awd868LyV}y`GH+B{ZdY5{T;`2x%k64Qo6EdWZMnTVrOTz-a!_r#eQTaJ zmwBVwa{JaiZ7%ahwdMA$dD>j&jcUv7)hTT*^G3DhcD1F=W!|_o&+TeUo6EdWZMj`- zX>*x3R;S#qwzRp-8@J}UU2SP|nKy3DbGzEo<+3_O-8y)lbhV|;W!_kwa=Y5n<}z3n(j1E|nE^>yWE6@cQ?4R;NfkCs$`6;4*JiR&FRO-Q&Q# zQCYd6taQ1|8xP=)**NO%U}Lp!s--t>yWE65OA3{ z`Xx`~mrVL4>elh`K3<*DK5xt${gNm0OXk|%+j2p_Gc;sBn zZ%^cxR8fv|k+&!EOR6ZxxyaiS`6X49<6PwJiTsi(%5g68_C$V373DY=zXv>#Us6Rm z&Sl;rzod$C-gDKhgB(YGNfqTd7rzHQUY*jsKU7hUbD1}wp{iB^Rqx)U89V z-k^i)0rT5QzvS`il*5P=gywNW?>6bi_Us6Rmc3-Do@)<#ek_Li1Nnj6m{#68|96D ziMn;jjpjG{CF<58H_99R5_Ri<8~G&{t5Z(;B~Rp+T=YxSt;6x^i`DD%1^tqfe#zt2 zDc$=d{gRV@$>Uq|w7Hz$=$AZRo${XROH2OyQo;GkQo)NJiaL0B9z2)pY39pb^Ffph6;h}W7_>OtfLwVq#bh&))q=)jr zL+NsLwryUahw{KfdB=T!oqzM2Paps5*B`$5yWjoeZ~x}wr>{T!Yc1;h@K+zkzdpbI zaQ+|L{Dn;C56?Ev=a02JU4MnuwUXr{JZ`kKxlAsNmdA~j zHkZkz(ek*_(&jR6G+G`vTH0LZjYiAkMoX7VqeX2#$eSB2Z7%ahqvdgXnEXdX>*x38ZD0- zEp0CIMx*6%qovEG(Q?vgdE97ebD1|9Esq;5Z7%ahqvdgXnEXdX>*x38ZD0-EnO~+7Pa|c zep_`LpWn#aT;`2N%d@tJ3AoG~jh4ramiBm=HySOE8!c@v^G2iPaigWpW!`ACJZ`kK zxy&1lmdA~jHkWy$(ek*_(&jR6G+G`vTH0LZjYiAkMoX7VqvfR0^0?8`<}zc_F~8rTd-++=>cxf#%j#uRaryj4Gr zkJs}iZj!g^$8oOz0wJ!>KyZASH#DYb*Q6wG)sN%j^H#VkB7%k#Pd0S`OatxzI+$e7}S|*GZaihG^Xi=pO&s&r?Hm0ajhukP{G+HK% z7MXxi-q@HjVYG-F<&8$mgwY~yls6hJ6Gn@;QQl~@Oc*WVMtS3AKodrbxKZ9{v`iQ+ z;zoI+(K2DQh#TdNM$3fJB5ss78Z8q>i?~tVXtYciEiz=IywPZxFj~Zo@-x#?62x{1S1aym2$2 z3BN=uDx$n`GoT5-MBFHE+ze>KFA+D&8#e=*@Jqyv^2W`8Cj1g{qr7o5pb5W3+$eAK zOD6mhaihF(GoT5-MBFHE+ze>KFA+D&8#e=*@Jqyv^2W`8Cj1huG>Y=J&bGaG!!Hpx z%G)~I#)V%ZZj`rmww=rGC6QlJ{W#9$_sPgFseT;i^7~}umsCHFbNM_O`6bnl<6QSA zb>5=9aWkL^zeL<9Z|iLPc=^2~@=K~8$GL7kYXx4Ew{^Ci%ijYczvSj-Kofq6#vA30 zn*mMuCE`Z&+dA8J9N?FT8_jQQOquXY#Es@R`Xv*7iMY}H#>SKhzeL<9Z|iLP@#Xi) z$S9>BERHbXWO~VTjZDA+`LD7|KNQ-@=NY@wr#xdOSD2a%G)~I z&gJ|T`6bnl<6O>fkzZ2%IL_t#7WpOBkK6dJgUvjfCWzsL%BEO{i zas2oqZ(HP-R6mY$k+&`KOR68oxyaiV`6bnl<6Puzi~N%6$8j$67WpOBkKM3p)iZ{(Le^h+-KC0pc|JoHOcsl)Lm z?{5$N5>@Jun>tLFR6YUKfZjPjQo;^eu*k|a2z7PptLFR9)eyB_G5Y>{75y*JKf-Xg!GdT*S|`7QEG9{MFJxWRQ6`6bm>px5zK4wi@R$Z;@Y8Z8gTFU$RAhNww8Dm(P=tUs7!~&Sl;rzogn~oXfmL zeo3{}IG1^g{E}*`aW3-~`6bm><6Pz~@=L0%#<|Q}{75Z8bJt`XyWBmsDGgbD6iuFR8W~=Q3}RUs7!~&Sl;rzogn~oXfmLeo3{} zIG1^g{E}*`aW3-~`6bm><6PuzM1D!N)i@V<8 z62C-T_*^Qu@$Wk$@k_*oKdFKna)b9baq<49f*W#! z?~~%{*Pr+2O$9gP2ETW!l>>RZ*;+KfaywNWiiC-cv^G3g9 zBz}pw%p3iZk@zLzGH>)tM&g%<%e>Jq8HryaF7rmeWF&rxS~-|E_Lq#rFASX zahW&zB_r`m#AV*-myE(qAGj^G3g9Bz}pw z%p3blM&g%<%e=9_WF&rxxXc^L{UsyuOT=Z~*k3XdzeHT-jef~U{1S1QH~J+b z@k_*I-mpK8cIwm_cy(QexXc^&#}QX&;B_wd$GNdTj<`Al0hf8h{y5_53RK#5tnl!_SDgFh~~s~w(WYro;u=2b0YWD zQ7I07`$?P>HO4S+*i%R2jpjt|siRUHjyKBNI@^AHnYYAA(Q#njxTnsZI4R^#{cC#4#0>^kF~I(y`#RKtyP z@f-ObIVsg}<6PuzkDQchxN$D>wnt7%HQYECzme-P=cnf5_s>Y*{O&h@|M70$jmv*rTs@imj)vfaL15Fo;oT^NRSeqBSSj1FaI>g$v*u>IgQI!s{_NLgy>hJuN zF{Hi`PZx`4P!;KLv^FPpv6vFoqeHBY{>xVaEf&@20P7Y@ceI!g)uKb}B7OVA$4}pV z``fR6*~MZ$REZ9;Ny@0Os6&U?BxN*MRG~v`k}?V`YS1AzNg4eW73dI~q>TEC`g4f2 zN6+S!Kzl{?Im9L@qr9T_9AcA{(Opq_4zTX7bPobkMs;O(b>$uQ{p|WDAHV(d-S>a{ z^#@g0j`mb~Xah~Zf$n%4JftMQ4|(s)wz!z|cDxOWYjJFIG3)Jk8x+^_*ydu|+wnH| zf3tUXJC+>hm3@^$&5aDS1m<64X5W$0z#~W`1yL9YFpNQqEQtj-n?|$RKOp?>v*YU~ zdG>;ujI*x{`P@lBdpnewyCO5riWSPWLXPJ0YjDBWpmME|!?}76E+@VPUxUiEN)G2@ z=3DSJs9fvha4x34g(s{ENq*mRcKMwDqn`6;chmWYXLs`lzxth)+?IX&KM(&g{K#(; zp)OgaSY&(TYw{d;eI(Q+s}ytXksr>*BYzU=S|X^c6j7ItkgQT1uRZdk<0aH3s}ytX zksr>*BQL8IbM28I&c!1ys}ytXksr>*BQL8IbM28I&cyY503$tuO`8}*G)*GZ^riJ-2DP?xMy9B(wg5$cjvin-DJMyN|xDdt9fBh)3U z6mz4#5$ZY#buAIpRf;Hoe%ZGO>MBK)Kg$q zS*4g8^^Jg*tWwO4`bI!YRw?F2eIuYHs}ysSzLg@%-lGU;tr4JAiYU)T-_{7wDn*p% zqHk*iXq6($bJ4do0<=mI<+<$J`vI+I-`>A?dV2l%=QmFe-`qd{_WqMkfB*4^zrBC1 zH9|^*WR=46;FQ(iI(R9fF2*Z+4*TYq)o`x!81`p3A-^hf*n5e_cJ7 zeM=6d+Ge0uy1tm-)<_yOLmH%9_RU$V(fbBzkaF3#4&hwAPB23nq+IqbIh0D*SASjo zzOirhzx>*DjTzD)jhB5(4yDp~^)_SUC2+My(x4f{m8?AMTOfzBEF;)QJ%}bMbe;BM0qaz7D~VZ;>>p6j7ebzD3fYQbc(!`xfyfrHJxe_ATN|N)ctbJ>l;^T~VZxLToiYU)z-y*)G6j7E-zGRK~l2Sx@F8dboC8db+T=p%J29+YpbJ@3u zFDXTo=dy2+G^i9&p3A>DAh6_%{Q zTtHaTaj|c(WR2#sZ-lT`Sh7ZQ**8L1D=b-~x%zk3H$qq|ELo$u>>DAh6%f{FF8f9Z zYlS6iG?#rNgthv<=+XBQKv>dSagoFKMGxn)Z-lT`|5zQ)W#0&4t-ddMG#3z7*Qfz5 z@O{z4x$GMutkw5L59hLPgs@iM7d@QIz7fJ&eP8rt?%!OL`A~BHKmG30|M%Iu|8T`O zD!{F-Uh{jRpQJB;h#y<mmNLv4l21>l*>8sWZxXz z8thwn)cn3-jb(FiYd9BulX?w*9~|5o&PCs(USn?3xALf6UI(eyn49#iJZhech5yaL zt;_3h`8WF~jA$SHqRrd*pYPJJ`LHmhZq9x6zqvoXl2R%)k7ZjO`x=c!S!G}2&9SnM z#-ghep|8!MuhCdkb)sTRIN#-;fYDgIy-q~FL~kXrEGmhw&55tk(XyumzP5Th`5t^5 zjm5M$k@wo1_Zp4GtT++(+8p;9j3w?MVG@FYO7r9b>^nX_J_ zqh-se*wRa1GFrBbimlB_uhG%6Wdyx82fapP*)noon{!^Hv1}PJugx*9(O9;O7NN~4 zuhCexj1r;EA+Nz$ID{l^;#}s8*G23VGwjVddZoJ&D7@Be@J6*b3V(51eq^VCWz#9qs7O|lDrUU z*5hdL?Xn~2^XxXy&z7So`u3x?Q>#K*SE51;B>cv&ktd4uSfv_I?8@J$C)~R ztGhqlO{@OXr~N&?nhqsBS_U5Se<;uyAyg)2a z0V)@Nh&M;IhjaPTOcmhfsP=HKzwl_h_*1+&s(qPzd87XL<-^0vyN|zq^XlpD!vITL z;11M4@W*=t+pR{7EE@FzThr+d6g_$Qfq40|#*f`-xC1p_HXUsD=y=(5x&t?`-J`i| zI^BUA*zVC>Hk}8;ZeY7db6HTb-5c2M(OiDi@<7-PZ1-p`3rct32DW=Nmj$Iea0A;t zm>7%*y;jzpmI60M%d~Ccc5}PvqsoznIi4) z84rZrB5ZZRfw21FfIq23*y@4K0+E3*3PkFW+P%Y_&|0K3?`M!d4f!12tauEy7k8xC52TzD3yT0(YQt`6e4-s|(zL z`bCU=i?G!N?m*?TZxOb-z#XVu_ASCz7q|nJ%f3a}>OyRFBDT6k*y;jzpvKF-McC@n z@3!@g*yy`NOQ{4;VR z2tWPo*MInR?H}K61mSZn^Y91r8$tM7YqiM_<^@JrOZkKOjUcRRt2Ou^z6A6abL0mi z{9rCHkuU7Y59SMgFjp+!*OMR27yMwZSiBe92*Um({2da6AOB{#`{hHofZYA^>z8l7 zdKLW2y7rea`$NJFB+WOF4E`Fr_Lnfv#naw=1IchMzfNiXZN7nII2T{1QbRkZ(R>5R za4x=1rG{p1U!VAad+7h|r?)vI7-YEJ@IgPH@6 zqt_S2qjLEg?8M`6E?$GBhURs!xn(#PeVfTVHfJ7(bI~`cp)p>E9*1+$H>shS+o#p5 zpI=~)dKF~f9D5udFZ)LBu~pLb&w15`ZzjX zu#d`R-<*9M&Sl>SKQ@OShjZCCzRWd$nY+xr{G9ER?ME-ZdAR%Co0l&i{!^;0@wKs) zuYU4KqeTAdcR7e3SsPpV?kA5lbE9(hN5du;ZXapBePnpNEGPGmG~YimoXc`@14;AO zzu{b#lRHS7?;sh?&q;q-($1 zejV7i2qj&KlFB2^@#^(IxDM?0D5lULVThC?RB9wF`N;(rIZ4pYk z5+$99lC}sXU5S#;L`hqOl9un*t}jv27NMl&yY*boZxKpbzFW`b{1&04<-7G<&TkP) zTE1J)W#1x{w0yUo%f3Y@Y58tFmwk&+(v>LbOq8@mC~5g_ZM;NDTZEF9@78lUzeOmi zP94De15wfzp`_)z_3^TA5lULVThC?RA_HpqZatTMi%`F$i^a4!2s7-f%OlycYl^~L7)4ucnajSpf@}CXV1ARY z7WXZJQM82&<0Xu;*9fouy-<5Un9IIJFpBm(Fcw(hTL=6H10WW#1ycq)fD)%f3Z?NvUW(7waXvD@sT28~GB!=e%#x{6@ZHAz!jb zd`a18{W`F35noa;x#zNP5nob1TF+(QBEDoJU$T%d*(1KBlz28?@+Eu3mu&rRdoKGH z@g=3i^IY~V;!8@2=eg`##Fvy3&vV(gh%YIVo#%3Xi};c<*?BJe7V#xzvh!T_E#gbc zWaqi;Tf~=?n9g#^m+TQ=QeryK<@Z~}mu%!q7V;%~#Fvzq&d1BXMSMw#={%Qxi};cf z(|IoY7V#w|rt@6(E#gZ`Oy{}mTcj#0F`ehKZxLToVmi-d-y*)G#B`QRzGRP7WhJKb zT=p&EOE&T)3;B{gQk8AwOXRY{`&pza+sK#5Wyf57L0`YFLB2#TJLX33lRRNpE<5Jx z4I>yY*Gs4>+atcD#B~0gv2PJyvQbqgmmRJ{#Fvzq&c;i=WRLigjeLn*b{ubCk-U1n zgnWrycFaw9u8pcPx$Kym@LU^JWpdduH|iTzWpdduH|iTzWpdduH|iTzWpdduS1VT6 zKMz!u$z_M!h%ecwDwE5OxygQ<64P1V$d~L9U$S+Y$aC4Zh%YHIo#(P|5nr;AFOkcR z*Ei}LPuP{qj=53as4A1oj=53as4A1oj=53as4A1oj=53as4A1o4!IFuvQbqgmmPDX zzL77H%Z|ATuUuj}>jn9eJ>p9?s>&9s%Jzsa*{CX$%Z}F}>KpkIx$Kx5^^JUqTz1Tj z`bNG)E<5H%ed~AIp9l6W;!8?Q=eg+H5%DD(9b|IZ`E@uVzNEx-HeT{2N5q$GbdW9N zOOA*y+2|l!$d?=uUsA?7zYge|&b0{Mcgi^Dx#-&w@g-%P^IY`pi1?B+&Ur5Sc0_zh z8Rt9~eLEt)q>OW(%f3Z?Ng3xnmwk))k}}R+=1NkB9!Gph8Rt9~?~_Nwmy~hNbMZcT zM0`o9Z9JEKi};dK+juVf7V#yew((r{Es~v-+QxI)w}>xk{cd|M`xfyfjeLo0ICy>| zzNC>aSt&a?BEF>5Hg+AzmmCpa(#V&rw(wT)k2_ATN|N^Rr0>|4Z_l-kB~Ilo1GNh4pf zk}o+TzNGcLZQ~_hazuPdsck%$^IOE1l-kB~*|&%8K+~oVM zY&Cuz*tdu;DO-)_vTqSzQnnh;W#1ycq--^w%f3Z?Nh4pfk}o+TzNBn5HeT{2N5q$u zt;TcNw}>w(TaD+kZxLTowi?f6-y*)GY&D+CzD0aV*=jtOeT(>#vekGl`xfyfWvlUA z_ATN|%2wmK>|4Z_H2O8K+~oIw#-s2gxM6Pcdv_yWBEb!FqrQG~8(fTC$l9hbP5&26R`4S0k zINqplp;Hbi1?DS z)p#!Z7WqrcR^z$sTjVck8K@ka9-`4S0km>bP+JPJ>O8|Fsy8~G9m zZkQYOjeLm&H_VOtM!rOX8|FrRBVQuH4RfQukuQ8K+^BElOC-2qZqzsO zB@)~)H|iVt5(#dY8}+TzMAi%XOU{TdY2-^Jxbg9x5noca8XGV9k~88<%2wmK=-V0b zC1tDeT=eaX_>!{KcrN;OMtn)xYCIQxJ0rfNY&D*XzMTYdFDYA%=b~?C z#Fvz<#&a>hoe^JBwi?f6-y*)GY&Dm;65OE25noca8qa0lBEF<-HJ;19MSMxwYCM;H zi};eV)p#!Z7V#xztMOd+E#gbcR^z$sTf~=?t;TcNw}>w(TaD+kZxLTowi?f6-y*)G zY&DikzT}MflAU~s1UKk$#Fvz<#>dOPMSMxwYCM;Hi};eAe2D}%ybj6x!{K_;}g3h%YHyjpdRrIU~MgCto7L z4X;D;{kGFzBEb!Flkc~()%bN_-y*(bCto7L4aXbxjeLm&H_VOtMt{jhf5{o~C1tDe z>&w1He97KvBF|;tBEDqrciVH>w}>w(TaD$CFF7N=WbdaTc`o}F@g-%e@m%&T;!E~^ zw>_7Ai};eA=i^9lgI+{@$_JRe7b8(fEo zFWGrMjs!Q%O@8m*$(KlQ!`x(jawlIR@RhmI{6@Y+f*a;W^Bd2{k>G~8$@=6@zC?l> z=0@`y`4S0km>czte2D}%%uUuOck(3?+%Pv;pDbIA^_YCg8Sy1M`4S0kFy6>tvXd{7 z;D)(T-^iCpaKqfFZ{$lPxM6P8H}WMC+%Pxl8~G9mZkQYOjeLm&H_VOtM!rOX8|FrR z>$V!}1^JRQ;!Da_^vVwf*a;WeWSl*qrc>g_>!Iel8ye7 zGvZ6iR%7>#e90M|kF%36k>G~cH|iVt5(#dY8}*HRi3B&yjrvBuM1mXUM)Mo_l8t=H z8Sy1M{Us9IV7w7uvXd{7;D)(T-^iD2|DBEb#sThur5B@)~)H|iVt5(#dY8}*HRi3B&ujrfwC{t^jpm>Ye+kuTZE zmz>f0I6L{0jeN-&`Ac^4B^&vYGxC@0H;NNe`O}^jCR^z$;KB?T~eX?vdp6h*6Zqm21 z)p)MYZ^}*Px3blEuFr4EP3E_<)p#!Z7V#xztMOd+E#gbcR&$xF|J~?u#Fvz<#&dnW zM8cb-Z)L0TTwgCyZqm21)p#!Z7V#wq&&QGAhSxXh8_&m);D)(T-*`Tb1UJl$`bK|= z1UJl$`bK|=1UJZy_>zPE5(#dYo6K)Vr-|%2179LxQ!>9D+8p_9-kin?ctmI=l}HW{fnok*N=aG^VI+AxA&iX`umSR{O$eo zMQ`4ELi}E{qmlEZ3^$(3jz&yM8E!n69gUcjGTeABI~p-5M<&t~L2Imo0)io@Kfqy29Cbzny$CgmWLA}J2X``(WJ$k|N?nG{KJm>bQB zWKtx>VQw@h_Pg!ZmwkIblXCgD>Z6AjuODCi_1Rt1>+(9Az?KvOL)!p{%>(9Az?KvOL_2*pU_2*o<_U?C?d-MtFBVy|yu_a{`bE7v#8iAyYVy?Ax@C34h#Fms%%(a#d z=Xy&wDWjNcEgjDFmMYgR>1ZyAEh(coUTf)auD4X<^_FV9*3#izZ>e&KlnIDWjMh^^L@q zlu^u$`bJ_)$|&YWeIv0YWfXIxzLD6HGK#rT-$-mp8O7YFZzQ&)jACxoHyVMYj6!Zi zY?c4XdJJMqD@D=#Mq*3KD2_Mk8;LC`qnI1@jl@<1v8C$}^^L@qlu;aS)Hf1aQbsX1 z>KlnIDWjMh^^L@qlu^u$`bJ_)$|&YWeWMXb$|&SU#MVJ#tAW_k3To6h5?c+#mU5%M zk=T+liq|3P8;Pw3VoT$V`bHy=lu;aS)Hf1aQbsX1>KlnIDWjMh^^L@qlu^u$`bJ_) z$|&YWeIv0YWfXEFV(TEWC1n(IqrQ>YY9O}si$&Bo5?c+#mU5%Mk=SY=wv-$7jl@<1 zv8CLoZzQ%Fh%MzteIv0YWfY%>sBa{;q>N&2)Hf1a4aAnNL)14CTMfjPei=&$l7qxn z1F@ytsBc)+6wt}{Nnh0*{f@<|rgAyI`Ksn{uI{$ISA*Enb%^>#Vyj_QQ@K&!u&Sx+ z!1>KrHAk-li7hFk&4YRn6gC-EGgs{5D0z)Mc=0P6I++7@_%^!@ZyVScOSic^Kkdcqkam1`Ea*BzPkI<-Sms?@zwC}QCpd# zd_-vK1lFt1J3sk*lyceB6HT4KdX46?sVAEX)@w9Zf0z9_;7xP_>ouCI_n^yM$)@}- z>;%?pG*|CIo{O1r0_!!Ji{I@??FCZ zHWe>F9H2`-_*T(Vx0P4T`(eIvIe*%WjA%WrhN z>>FG{V(X&5^}B6M|S>KnN&$)=ba^^M$?WK+zI`bKU` zvMJ_9^Bc(&$)=DCGG+9>aegD2G8J)ib&pA=NH)ds`pV|$c-c3SDHB{mqq*!G$&?8$ zq0wCSjbzFMGG#EAWQt@{yuMN2`rWqqf@I1BGG%nUoZm>MOdwN6b2-0}OqoEYjOKEF zBbhRROc~8(-$%jSqWXjZ8h3m&lGDWf}JZCto zYH++HQzV;WZqzrDDUwYwH|iV7l$~VC1eeh0b>RF)GGzjpGMdZ2kxZFDri|vYZzNMD zkSU|NoZm>MOmGQ}=CW@jQznopqq*!G$&?8$p}|~|DUwa$`R%O2^*tt;BH0vkqrQ<$ zk!*^&QQt_W>?BjB&ME}gfqf&HGJ#APy>ILr$&?8$q0wCSjbzFMGG#QEeIuDNflL|A zW#34qOdwN6bJ;hNDHF()!CaClJIRy@WXfnRzu!ovOr2G@{`n=DBH0xB*6lJuF2CPM zrc5AHMy~_=MlxjrnKGKozL89sK&Fi5vTr0)CXgwkx$GOslnG?YXfFFkGGzjpGMdZ2 zkxZFDrVQqiOxa1MOdwN6bJ;hNDHF()(Oj;Vz$MfskSU|N>>KvmDL0zm`rWp5Bb-&$ zW{@eP<7MASrpzEyMswLWk|{IDl+j%FjbzFUGG#QEeIuDNgG?FCW#34q%pg;Sa%GCq zzq99oWXcROWi*$4JMlg_gG?FCW#3NBZ*#(z=sK`(aB@C>MRx?s?|w4qW@bqg?b&vMJ{34qTs0zC^Mq z=IRavx#*i@Q_KzCCuL$n-z1x2Zty<&)*N;DcSo`*<_7cITXU4>;`g^X;Y*Z@zDYKP z@#3ti!M|s82}w4^++clD<7MB-m&^%YqFnZke94^fCCX*r$d}9sUm_C|=C^}<$vj7W zBVQuf6z^NqH=b1`*%Wi5zL77HY>K&2-*{HlLB3>8_!8YW_KkeWobV;e<@`pzWKQ@J z<+5+&OXh?xQ7-#NzGP1L66LaQb>>K%#IpIs>^I+e|m&`b;YVi7!FOeFD&so$ro>g^_FPRg*MAre| zZ&KrMywUu|v#JjAC3C`;XuRwj`I0%|OO(sLkuRAOzC^j~8~Kts;Y*auzL77P6TU>b z>>K%#IpIrWXl38Xm(1OTas50*zC>yqJinbd2y!{UkuRCM3nR#7-^iED-Gve4a(*LU zGADeA?i>3?zGP1L66LaQmwh8&GADeAJS^-R`I0%|OWt~J>^UP} zGItlo^}Qfpa*!{Xy9*=8W#7n`%n4ue)^p?6fqhH(66LaQ zmwh8&GADeAa``?$$PNzvN5igfDsPx$#_nza@N$a@jZXC3C`;D3^UBUot0riE`OD@+C{c zmnfHgBVV#4e2H?|H}WM*!j~wQeIsA8Bz%c-**EefOTw2Zmwh8&vP67Id2Xy1*#Fv!k#&hxe+Y<35<+<@(tWPcxUs9eM&&B)X67ePFx$#{5-n~S8NqKHA zbEU@db*?4iOUiTOx!_Bd#9z|NR^z$gOBS3}rT4j?_Sq;GeUspZ*Fk^ruKsSB$d{bt zOO{R?1i5&hJjs_ViN8cA9ASPt$(JmhI0(jz`RycMvUK7g$i@72(qFPfe91(<>K%#CGnRimwh8&vP67I*=p?XI{A_%;!7s-B`5ik zCE`ma@+Bwvk|p9x%2s37fqcml@g)=al9PPN67eNvtMT!IpIjooWFlX3k}p{zzNBn5 zK3=|0Mtn)xYCM7Bww;be91(<|4Z_l&!{dIlo1G$wa>7 zBww;be91(<7Bww;bd`a1A?0FzxvP67I z*=jtOeT(>#vekGl`xfyfWvlUA_ATN|%2wmK>|4Z_l&!{dIlo1G$wa>7Bww;be91(< zwlFDYA%<&rO1 zBfg|;HJ*#Utr1^Rwi?gHddV8`C1tDeT=Z>?_>!{KcrN<3Mtn)xYCIQxTO+=tY&D*X zzO4~oQnnh;Mc>wlFDYA%=dy1RUsARj&t=~tzNBn57r7F7fG=4izNBn5p3A;Pd`a1A zJePfo_>!{KcrN>voR8DWR^z$sTf~=?t;TcNw}>w(TaD+kZxLTI_q*-6>|4Z_%>8bA zF8dboB{TSvF1T^tXpQ)i8GMOE9_(Ahm(1Wxl*_(Fe8~*HM7iu+#FxzAOO(sLMSMxw zYV3I+U$RDg$qc?k<7M9>zGMbpqFnYZ;!Da_Die8~)diE`Puh%cGJmnfHgi};eV)%f-0{1)*gWvlUA_ATN| z%2wmK>|4Z_l&!{d*|&%viXi3B0+Tf~=? zt;Wa8zD0aV*=jtOeT(>#8GMPZ1N#>7C1tDe@v?6bUsARj&t=~tzNBn5p3A;Pd`a1A zJePfo_>!{KcrN=E@g-%ev0U;cYs8n#@Rvvs!oEd(N!edOPMSMxwYCM;Hi};eV)p#!Z7V#xztMOd+E#gbcR^z$sTf~=?t;TcNw}>w(TaD$C zFIgkLWCmX%K?wU6@g-%e@$s^65noca8qa0lBEF<-HJ;19MSMxwYCM;Hi};eV)p#!Z z7V#xztMOd+E#gbcR^z$sTf~=?t;TcNw}>w(TaD$CFIgkLq--^w%f3Z?N!e;Vmwk)) zlCsr!F8dboB{Tdb5~Z+j5noca8XqtF7V#xztMOd+E#gbcR^z$sTf~=?t;TcNw}>w( zTaD+kZxLTowi?SNU$RDgN!e;Vmwk))lCsr!F8dboC1tDeT=p&EOJ?vT5~Z+j5noca z8XqtF7V#xztMOd+E#gbcR^z$sTf~=?t;TcNw}>w(TaD+kZxLTowi?SNU$RDgN!e;V zmwk))lCsr!F8dboC1tDeT=p&EOUhQ`x$IlSmz1r>bJ@3uFDYA%=dy1RUsARj&t=~t zzNBn5o{PS15noca8qY=Fwumn&TaD$CFWDl#WQM;)f)Mm=i};eV)%bYPw=LpJ%2wmK z=-U?YC1tDeT=Z>=_>!{KcrN<3MSMxwYCIQx+akWCY&D*XzHJd-Qnnh;W#1ycq--^w z%f3Z?N!e;Hb0xU(-_f^-FDYA%=dy1RUsARj&t=~tzNBn5p3A;Pd`a1AJePfo_>!{K zcrN=E@g-%e@m%&T;!Da_7fUPOFJ*=lUO!{KcrN=E@g-%e@m%&T;!Da_#vekGl`xfyfWvlUA_ATN| z%2wmK>|4Z_l&!{d*|&%#vekGl`xfyfWvlUA_ATN|%2s2!!{KcrN=E@g+;Y z+n&q5MSRHue~GRy`xfyf3;ZQbf*U+%5nr;9FOlGexykbJ@3uFDYA%=dy1R zUsARj%Ozj3MSRHue@Tu+wk|x0oo`;ApS>P{G zF8dboB@6r|%4OdozGT7qILc+;BEDoHUn0Q`uW!^hoR6dNvTqSzQnng<&gd`MBEF<- zHJ;19MSMxwYCM;Hi};eV)p#!Z7V#xztFc`2C0oRol&!{d*|&%!jbC5(E#gbc zR^z$sTf~=?t>!XUf*V|ih%YHyjpwp&5noca8qa0lBEF<-HJ;19MSRJM^KqI4H@v=4 z-}>G5@v?6bUsARj&t=~tzGS7pM1mV$hp2D#mq>7f+=wq($(KlQ!`x(kTj?*6;D))$ z{I=3xBEb!Fllg6>zeIu?<|gyoN`Hw2H_VOZH=K_nfe`x^@g-%ev0l($(jvZOrN2ai z8(xQKe#7}Vx(@7H#Fwl%A4j?DTf~>FohI_@%f3Z?N!e;FmwZW!_>z_W5(#c_-y*(b zrN2ai8|FrRqrXIg8|FrR>v!9)FZ&kpB`eOyX%gIUywUq)zuP`u_ATN|)_%7=mwk)) zlC{%Bp3A;Pe94OQaddszw}>xUaXwCy;0E_C;!9TgOC-2qZZyA8K z+^BElOC-2qZuCCc@3uW>JRhe;d`a1AJePfo_>#5LM4rpOMSRJM^Ktb2vTqSzvUZxt z$IHG&e94OQahe1-cpf6YWTn4Ef*a;Wed~AIuEWZ{MSRIhzC?l>jyLLCzuP`u_ATN| zR`Mkh+;F_n{MPTbkC%Om_>#5LM4rpOMSRIhzC?l>T!)A+S;?13aKqf_`;B~w1UJl$ zzTe1~NN~g4sBh#;B)DO2G{2EAk>G~8QQydyNN~g4XnyN7kv+fUOIpO2l&!{d*|&%< zS-Y*qbJ@3uFIhWHG~8(fro$wmoN!eT(>#wbMkN%f3Z?$=Ycm&t=~t zzGUq*k>|2+5nr;BFOlE|_buW}R`Mkh+%Pxl8~G9mZkQYOjeLm&H_VOtM!rOX8|FrR zBVQuH4RfQu^}B7)8TpbH@g-}gi9DBmi};eY(?p)jzD0b=+G!%sW#1ycWbL*Z%OzjZ zBEDqpG?C}BZxLUz;(VMY!400Xh%Z^mmq>8K+^BElOC-2qZqzsOB@)~)H|krz+kW3T zzeRk>O1?yb8;&>n{jJ|^A20g0M|{ajzC?l>AMYOVC2OaNY`o-4_J}W8=`WGshU1Oq zw|=*Myy)8=@g-}gi98p5+atcDY&D*XzU>iTQnnh;Mc?*_FDYA%=b~?W#Fvz<#&glP zJ@S{7t;TcNw}>w(TaD+kZxLTowwlXa32xAfh%YHyjpwp&5noca8qa0lBEF<-HJ;19 zMSRIdzC?l>Uf*PX+sKzlaKqeWek)szUkCOr;!8I2B@*0lyvh8wkuQ<|cf}M!rOX8|FrRBVQuH4RRyCWFuc9!3}exzIB?&{+^L9*(1JW zBVQuH4aXbxjeLm&H_VOtM!rOX8|FrRBVQuH4RfQukuQok%5{ax6%h%ed5mq>8K@kV_kUn0Q`awEQEBVQuH4RfQu zkuQczte2D}%%#Hd+zC?l> z=0@`y`4S0km>czte2D}%$c^}tjeLm&H_VOtM!rOX8|FrRBVQuH4RfQukuQG~ojrvBuM1mXSMtsRe zzC?l>=0<%ZUn0Q`bECeIFOlGexl!N9mq>8K+^BElOC-2qZqzsOB@)~)H|iVt5(#dY z8}*HRi3B&yjpjGczte2D}%%#Hd+zGNX^vPb@s zjeLm&Hym%&H}WMC+%Pxl8~G9mZkQYOjeLm&H_VOtM!rOX8|FrRBVQuH4RfQukuQ

-gn5C>=9qGkuQd;BEb!Fqxp?|i3B&yP5M^08vFZjqHjmUmz1r>bJ4dW;!Da_Qi(fK&? z9y6DHi}(_Gd6~<;Md#zlYl>X*B}a5Vj(mvBW#6LnapWaqF8dapk0TEibJ@4(d>r|K zn9IIJ{t|gQn9IIJ{t|fun9IIJ=i_MKHFMdw$X}xU(adGvBEF=NFOlE|f6pR+iT1l; zyyQ!ch%YHyjs2Y@UvfnL672`zc-gn;e4IwUWF=p6MCao)@+A`7@V-U!8~G9mZkQX* zZ{$lPxM6Pc{np5rNN~g4KpkI32vAh z^^JVVO1|WX_>xAxWF=p6ME;USzGNj|azy@;venr9M!w{T&c|uwOC-3#eT)1hjeLm& zH_VOtM!rOX8|FrRBVQuH4RfQukuQG~8QQydyNN~g4 zsBh#;R`MlB#FsSkB`f)oBl4Ft@+B+zk|W|v8u^lye8~~{OB(r-m3+w&`Af=HWAhvN zk|R1Fr;#s_;0DiGbUscaUn0Q`bECeIFOlGexl!N9mq>8K+^BElOC-2qZZyAvXU=3BEF=NFImZ#9MSnWjeLm& zH+UYR^Klya5(#dY8}*HRi3B&yjrvBuM1mXUMtvh+BEb!FqrQuoq$d|0-OOD82(#V&rKpkI32vAh^^JUq1UH_0Mtn&lUn0Q`a}&O#kuO=vmz(RK z$(Nkb`8bVy$x6QDjQk~ye2D}%yuQi%WZ7!$?*sXgGvZ6iR^z$o+ZpjCWvlUA^zDrJ zlD*$;&qd$Ph%YHyjpwp&5noca8qa0lBEF<-HJ7;(+~7Hj_>!{KcrMmU&WJB5TaD-9 z`|XVQlCsr!F8dboB|G^N32u0Ollg5YUn0Q`bCdaPCto7L4Re$EZ6{wM!3}eh`E4g( zBEb!EBfexOUn0Q`bCdaPCto7L4RaHIawlIR!3}eh^~s%li3B&yP58;3e2D}%%#G$Z z@+A`7FgNNO`4S0km>czte2D}%%#Hd+zC?l>=0<%ZUn0Q`awEQECto7L4RfQukuQ

L)16&B^&vYGddq%FJ9h1uUY@=FCOln>+k=!_b;BFUO)c%&C|m-_s_q*|K!u(fBfNZ@1JXvBKeYy ze90N{B|G_&jeN=3iG%CMOTJ_yUvhThAjkzjDZve%-{^dtoqWkgzT}MjB|G_&jeN-& zosYAVFWJbKoDpBLlP}rGmz)t_vXd{_$d{ZEU$WC*vXL)2BfexOU$T)eIU~MgCto7L z4W8dl99-WE@+BMjk~2CVXD44G!41b7&2QvOHu5EBbUw~bzGNd`az^Ll?Bq)}@+D`) zm+a(AHu5EB#Fy;kOE&T)XT+E6!G`$wt29jQEnBe91<>84Sb1mqu&F_mu%omlpB4& zkuTZ6mnb*-{f&Id2EIhO$@^s4YV5v&FHvsNx1--}&-K13H|g8a@3!aq?{CUYet$d2 zmu#p19-!Q$Z%4n|K3?`M;!BQxw>{T?e-q%7^sQ_)m$?$$;O|4kmz1r>bN%;jjW_9A z*=ju3fA3aq(zmkJc&>lHDL3jH`4S0kczvV3kuQKpkI32vAh z^^JUq1UJl$`bNG)f*a;WeIs8Y!3}exzL77H;D)(T-^iCpaKqfFZ{$lPxM6P8H}WMC z+%Pxl8~G9mZjc-CC1tCz_Z{#h0;QwAkuQKpkI32u-Z@g)cO5(#dY z8}*HRNdsS^jR{fT$d@$mCCZKZM!uwhFHvsPH}WM7e2H?SzL76!;7gPn^^JUq1UGyh zqP~$Yk>G~8QQydyNN~g4sBh#;B)CCt#Frf8OC-2qZqzsOB@KLuHta-wBVW?Mmnb*t z8~r5>e2H?SzL76!;7gPn^^JT<17D)tsBiR_NN~gFA?h3X5(#dY8}*HRi3B&yjrvBu zq=7Hd#<1k~fP;LA1UDFO#Frf8OB(nRjW_BW`H}{{M7dGl$d@$mCCZKZM!rOX8(!b2 zZ{$lPxM6P8H~LE?xM6P8H~LE?xM6P8H}WMC+%Pxl8~G9mZjc-CB?tKu32vAh&2QvO z8u$`z@QnIKzNCRKQEt>X@+A#?iE^X9kuT9s1YX~$Z{$lF_!5mb>KpkI32r#vsBiR_ zNN~g4sBiR_NN~g4sBh#;B)CCt#Frf8OC-2qZqzsOB@)~)H|iVtk_Ns+8>*wekuPcB zOOzY+jeJQ1U!vToZ{$lF_!8wteIs8Y!42KpkI32vAh^^N`#32r=h ziujU){t^jpm>czte2D}%%#Hd+zNC>anIgXAAYanRmrM~~a*!`+t;Vk}`xc##Q??q z<|glxC;1WyZkU_APoCsUB)DO2@;-TzFOlGexl!N9mq>8K+^BElOC-2qZqzsOB@)~) zH+i2t$(KlQgWQNOImwquaKqf>eext#vekGl`xg02%2s2! zw(TaD+kZxLTowi?f6-y(lW*=jtOeT)1hWvlUA_AT<4 zl&!{d*|&%!{KcrNF+h%YHyjpwp&k-wyD zHJ;19MgEeq)p#!Z7WqrcR^z$sTjVb(TaD+kZ;`*GY&D+CzD0b=Nxnpa8_XAxzocw6 zHeT{2Q^c2)t;TcNw}>w(TaD+kZxLTowi?f6-y(lW*=jtOeT(>#vekGl`xg02%2wmK z>|5k7DO-)_vTu>Uq--^w%f3Z?N!e;Vmwk);C1tCzT=FGToTaAyG zeT(>#vekGl`xfyfC;1WyZt!<9;!Da_`CczDJgZWLl=$iyL$W8bX z<)UvA+%Pxzy<55L8~KvC69?D6mnfHgBVRIi;vmRn-^iEDoj3?`**Eefb0-e2&m~`S zkT01#aS-IPZ{$nnP8>K%#xf2ILF8fBlWbVX4kjuW2FPRg*M91Kz@bmB?tMEIpIq*UiOWA$(-;d%4Of^FPRg*M7iu6`I0%|OO(sLkuRAOzC^j~8~Kts z@s}u!y6TU>b>>K?h zbHbM>mwltZWKQ@J<+5+|m&^%YqFnZke94^fCCX*r$d}9sU!q+0jsB83;Y*auzR_PY zCwz&hefEw1k~!f^l*_)+Uot0riE`OD@+EV^mnfHgqrYTM_!8x^Z}gYU316aI_KkeW zobV;eW#7n`%n4tjT=tE8$(;C0l*_)6FPRg*M7iu6{Uvk4muNQ&`$m7sobV;eW#8y8 znG?Q5x$GPLC3C`;D3^VszhqAM66LaQ^q0&DU!q+0jsB83;Y*auzL77P6TU>b>>K?h zbHbM>mwltZWKQ@J<+5+|m&^%Y^43;k>z?$N%n4tjT=tFrk~!f^l*_)+Uot0riE`OD z`b*}7FHtW0Mt{ki@FmJ+-^iED316aI_KkeWobV;eW#8y8nG?Q5x$GPLC3C`;D3^Vs zzhqAM64^;OztLYZCwz%=**E%2=7cX%F8fA*$(-;d%4Of^FPRg*M7iu6{Uvk4mnfHg zqrYTM_!8x^Z{$nngfCGp`$oQGPWTe#vTyX4%n4tjT=tFrk~!f^v@4i>BVRHne2H?| zH~LHFgfCGp`$oQGPR_?sF8fBlWKPb4lKzq<;!7s-B@*2D@3Bk7mrUeKjuXFk zFA-l-wi>?<_`Q3H_>!{KcrJeLULwAvY&D*X-@BKHFDYBiWv&D_xNi|(GLbKl;D)*S zi+A-?^!2M}ciJ=DmJh|x-aotl*Vm6cztc#8Zu%#Ef;;wkduFgNNOkJphOhq+PTh^NSp!`!HE z#8c$QVQ$nn;wkduFgNNO@f7)SkQ?DC6Y&)JahMy;Z^TpN$6;>NH{vPs<1jbs8}StR zahMzRjd+UuILwXuMm$A+9Og!SBc38Z4s+kzx7+LJ53kSsHRAR<`pNzCNrzdmt`RLg z-CjrEex}`CN8eos_U-mM`nGSk*U@*^fzx9|OHa4g(YJlOy^g-S4tg1~<*eK5=-a;i zH-8<~XU`AIqx#Kx`%v3-u2>!=Z7tm+Uz4NHN7B|>x@B(k`AFJYx<}+jwDm;VTDnK( zMxT$Qt)+WpZuI#`+FH6t=0=~7q^+fUWN!5NNZMMuN9IPKkEE@odt`3(`AFJYx<}@| z_w(_`mPbijOZUj!sBfgLrF&#<)Hl-B(mi_a8qwAhX=~{onH%+uw6%1P%#Hd++FH6t z=0<%ZZGDoqUL)FiB5i$=wq7IJy4;QSoL|_h z#Ve2uy!Oz^^3$NJXoFmR2>Ny4r$OH;6y)kd&~y1|kQ{8S<79m*)OEnC=NfGcn;{-nExiM^wHingE z+H={rXk%DurahN^i#CRpX4-Svw`gNnX{J4weT&4yrJ43z_AL?*muA{?Ilo2X;nGZd zF8daVhf6c{}!rF3q&(vTxDGu+mI> zF8da33@gpF=dy2+c(^pvp3A;P;^ERvdoKGHiHA!w?YZn*Bpxo!wCA#K(Z;aSOnWZ- z7HteG&9vomW7ryP3@gpF=dy2+c(^pvp3A;P;^ERvdoKGHiHA!w?YZn*Bpxo!wCA#K zk$AW?)1J$|MLWAnGwr$TTeP#QG}E5TzC}B`N;B=b>{}!rF3q&%a%a~XiHA!w?YZn* zgwmE~+H={rXlGYxrahN^i^RjFnf6@vEfNoxX4-Svw@5r(nrY8v-y-pFX{J4weT&4y zrJ43z_AT1kRhntfW#6KmU8R|}T<+{zBk^!)rahN^i^RjFnf6@vEfNoxX4-Svx4zfs z`gJ+%?2_S_eTz`q(oFk!*|$hMT$*XmW#1z4aA~GJmwk)G!=;(_T=p&6*;Sfp&t=~t z@o;ITEtfmH)<`^DnrY8v-y-pFX{J4weT&4yrJ43z_AL?*muA{?*|$hMT$*XmW#1z4 zaA~GJmwk)G!=;(_T=p#z50_@zbJ@2DMJdg+=dy2+c(^pvmP-_Njl{#Hnf6@vEkaRB zGwr$TTO=MX&9vvTZ;^PoG}E5TzD45U(oB0U`xc3ZOEc}c>{}!rF3q&(vTu=ixHQwA zi@t3U3R{|K&qd$1NIYDcY0D)FyG7#R(oB0U`nE;l;nGZdF8a1bC~Rq_Jr{l3A{4eX z)1HgIZ4nAvnrY8P-?j*aEzPv&qHkM-!j@**bJ4dgLSaiY?YZn*gu<3)+H={r_oJ{s zg7%kY`Z8B$YDdJkh%YJ4wCA#K5noc8Y0qWfBEF#g?x$3)VRJ8U$T%d znaG!H5nr;9FPX@fY!P3wkT03YmuwMVvXC#C$d_ypU$T%dk(rwJE#bKqh=;qGnz>Qm zARbmO`xfyfrJ1%~P&~Xve8~dwu*S>2MSRK9@3xJXe90E^B@4vE`$X~Z7V#wu#KX$v z{1)*grJ45Y!1*oWOBRTSHD1nd5nr-EJgi*yE#gZ`Gws)beT(>#(oB0U`xfyfrJ43z z&TkQ4QkrScW#1ycWWmAKyUf)1dlvB}3&g|9<@;pBmn;wuE0=wX_>u(&TPv4+i};cS z;$h{oZxLTonrV9;C?4J-zN9qMp3A;Pe8~dwu&x997V#yenfCFrZxLUzKs>DRvTqSz zvfyCrU1nsh%Z@S4puJv7V#wu%)!cK-y*(bfjL;JX7(-OOBR@e zmCL?Gd`Wqt?RlU%c#HUw1?FIlmwk))k_F~q<#K+D_>u*xHs!K!5nr;v9IRaSE#gZS zn1hwezD0aVd7}M!VBaFXWPv$Y<7M9>zGQ(pc%R6ZY!P3wz#Obx_ATN|7MO#T%lR$h zOBR@emCL?Gd`Wqt?Rg+yvPFD}9QOF`ra5?v_>u+YU|k3HE#gZSn1hwezD0b=0#%!G z*|&%|4Z_EHDQvmwk))k_F~q<+5)PU$Vd) ztX$4-5nr;v9IRZvOa_;q04BEDpSYE9!s-&(|%EKsc}7kz6HU$Q{8wol|sTEv$uP^~E! zeQOb4vOu+_T=cC)e8~dUnsU*%7V#w|*0bk~sw(v5n`lZxLUz(qAGMAFprXFInj?k&BPH$?x4O`4S0kn4A3Gy^=4H;D))0O0;Y> ze&5))h%YHyjpwp&5nr;BFOlE|*CFCdR`Mkh+%Pv$iLT^JX7VL1;!9TYB{TVw7V#xz ztFik=zNAHb$x6ONf*W4nsBh#;B)DO2)Hm`a65KF1>KhKWmOzMoi};e2e2D}%7;nUv ztmI21xM6Oh?p?{3NN~g4sBh#;B)DO2qRL)zu=Os%4Re$IZ!7r{32vAh&2QvOB)DO2 z)HfV#t?R(PMSRJMgRPazzD0b=ii53{%f3Z?$=Ycm`#Z^lty{#GtmI21xWRpk_>z@; zi3B&yjrvBuM1mXUMtvh+BEb!FqrQG~8QQvT|^)A5;bECfDU~A>FZxLUzk}r|q zhU1OqHymuO@v?6bU$T-fk>Cd7jrfw4e2D}%%#G$Z@+A`7FgNNO`4S0km>czte2D}% z%#HengROT7ZkQYOjeLm&H_VOthLfo^UiK~GOIGqF65MdSQQydyNN|JPh%Z^mmq>8K z+~g>Tm3)Z=H_VOtM!rOX8|FrR!%={{1UJl$`bNG)f*a;WeIs8Y!3}exzL77H;D)(T z-^iCpaKqf_`;B~w1UJl$`i7IK^*pd|5nr;BFOlE|KpkI32vAh^^JUq1UJl$`bNG)f*a;WeIs8Y!3}aFzGNj|BEb!FqrQG~8(fmff zM1mXUMtvh+BEb!FqrQG~8@9o=<9VK;nlI6a)J>}x@FMvD9)y4N*JpKi62f6xVXSw{GDu6r4)gL?0#p7Q9 zcaW<;cAksJzX0waSAXn07mt4d+}G#gb4n-7W4bATJIHl>Sh<*P3g8ZM^~cVy1E!k- zxPx5wjh|Bma0j{U8$YKC;0|)xH-1hPz#ZhWZ~UApfIG-#-}pII0C$kfzVUOa0PY}{ zedFg;0o>Q;;&ZB<{G2L)JIH0<_&HSocaY1z@pGyG?jVJ_`|mcEn;>5_B#6OPv0Ie$kqMZ>*(7925+yU-(81f^<%>7zFy1u z`4_G3PgvboEN&gn=*`p9*RP)4olwsRr z+1F_IsWun#Ib~m?-KP_N9ng5$*XY*)Z7$?^+1F_IsWulPm%k3we#F218S*1m*$KZ6 zw3ELM)PBSum!FUPb)fbm2D$uv7OEeqa$oxOiP zX?Y2M4sXBCzFQWIWNLC{;m`N&*V%W=OYB=DQ;?;}R?*%osax?laqra)7X0p4K7FtK?XRXETfM{H zE4?n=V8OSqjhr4Mx3AQ#cz$oMqwijqz^30|!S7zn^%w8@9^YWWx0KNB*V%X1fveBA zUuXYE{W|-{FCQLWKD+zuSD!t*`{eQI_2bKjyFa{sc=5%vyY=za-JkBJUu=*1rS_wT z7q1^*{q^pnuU|j>>{kzedGY4u(?5*=YP;fBuU&^ebFYn_#EZXYnh(GF`iqDA=lXZw z-oJR#(Ej}9ssHV}T-ICZT-Bk^%+*3fkn5kp8ZYK~{jL<{`aG{(EIT#)>NR>Dd=*}~ zScTu=Tpi8z_iE*06@G_vbu`!i?(91B+3(v9=jv##FFPq0n{akGS4VUGS1;va6V49j z>S(Ti1}hiu)jOQ4W4U#L^Tn^s%0=IHI9Eq=ec4I5=-UqG>S!+e#$Ua5I9Eq=_3!*T zpl>^ztE0K>8-MlEX{N#7hdRO8$IHIKxjH&t^i798qi=Aoj^?6oI`o;jJ?X{M!|TTv zFYlk%iK9RLcfC$ztOq6!?`+|%lVDY)g5R0j^=WHqjPn~nZBdBe4nIq zb;p^$gSm9B>dgauA z-{@T3;anZfW#8yr-EpSxXfFFk=jx6#eMfWIH#%2$oasB7%f8XMy5mgW!CX35b?7sn zhp2CKuIkWd=0<&kBxu*6&&-Yb21$@|**Bc&J9>Tj{YFX9j^F)9bJ;ik?!V(q-_cz5 zjgp`pXZnujvTwvt<%>$*f9YJ+q0e|8aHj9*c-c4p?!V(q-@#l+g7j9(zTr&Y(Oj%g z>d>JMX9lZ|h8+T>z*p)q+%f4|}_KscIqq*!GcV+Lu zP)BpwH)5!J|0VeP?@c;a0Uox{O&KzihToyIyhcnsLEyE zfT51&;`aba8hCx9zTtO&jhB7HuI$nAvTu|G?bww)n#;aX60~Di_Gm8q#^3#SI9Eq= z**8jpcAV)un#=b|N`iJ^sH3^;8!^-!XZjB2LK3vg8HVQ10y8~Ktw;!8H{s@CoYtd|@SU$XH`Umg1F_w9)Ik~+cJt^@g!BjQUop6RPYpE=(C z1YG@lH_!ByWP!Q*ix=dwZ{$mkh%c!Voc;QuZ%4$J)Cta>i}%SR;!ElTXV1m^wxo*>l;qh%c!VoIRI)i};c{!TB;*k_9}!5noa#ID0PphBJM~{{Gep z&YsJ@;Y{DrT=Y$n1zv~b`>l~Lkz|3ndc(N-??WSBBFO@Cll781!P&1b`xfyfjeLnD z3mmWRKyV%KJ}JopawEQ^^%I=^ImH}WMq^qIL)-^iD&Pd)vGHepqK1e9ro+(#79HU0=)#H+$RL>wB}e zeRmyvUKoAO{JTfHnD8EUv$uVBef>Rb?E21q*OK-4W^X%hx{RAHQ zW~8;?>j$uz(OmvHBsOz9TkE^~mi#%q=`!BEKHm;Ac&jnMQN=m~3$Guyv$fv!?PhPg z+1nmpeewOg32bI?e!JP*mRWL)U)=0%zFK*+w|)0o~^-+yXVX)H@!CU^A8mF==J62-|cnuoz0J{&$rjn+w17ugzRNrB(a)_V881PXj`K8IyczoPPe^!Dp)&11K-wcb8wx3jgryADpt zjrDEr%)kHIiN4*=)_Qk+L4l86U#C*_Ydxsc@NBKy`^WA5rdZ)?{XK~ z?QGBQ-ou<49{am>JKOW!&%W4&roZ2yhHvj5xA%|xi*=R1)3ZH4etiA<>(?LuW_`T- z_{BGJ4B!3k#p|b^{qI+w3&GZZd8w80yH8)e{Li~TK0bYU_scI|eD#-y*WX+ru5T17 zt`sUBkx;QwsJK$7cr5fITff_$i>cy>go>@-ZO_F|Cr2by zZ2fL~E=Zmu5-K(d6;}!sk2UHWg^DYMipLuDjY7qhLd9c^`bMGRN}=MhMt!4Daivi4 zh=hu*-)(;$*tbZi*!tbJTnZJBNT}HQ-S%AeEfOlWez!fBeT#&Ot>10WW#1y9Vxv%T zrBLzMqP|h6xKgNiY*F7RR9q=kJUX0l@l*TYJVc@5N}=Kr2^Cwv+kW4$^l(H%#fF0v zrNw36BB5gIciYBGq2dt<6>J7O17!GUF8f9@{D_2#jY7qhLd7Ez zDz<*N{rX}l_UI=)U*8J~6;}!s4;-X8czr2UTq#sMBB5gIciXQ6`xXfm8&DkSqS?1d zsMtV;?<<9hM{}#MY!oW4L~#zFIHS)4`$iP!h=hubLdBIr#Um0bHVPG2 z3Kfq?sMv6>x9%HIoC7G%;Ps_Yaivi4h=hu*-)-v~g^EWcRBZijdoKGH2^Cwv+m=hA z;t>fITff_$%f3ZI#n$h(=kk3LWccXwz`jwactk?QMxo+Lq2dt<63^}Fr4TrY`)iml&m&*l6E(ZS&J(C@bAvTu=4vGu!cxfCiMkx;SqyY0E` zTO?F$5FP9*MF&SDRBZij`*`{N76}y_g^DYG$~u733_cG)X>=XfH=s15x$GN72S+4S zY!oW46e=F?7b;$gR6cq5_q*RdeldDv>a6n->M9^-W(Leu5^GJ`i2VAlC zeD~OX#eYD`M`LY1QLIfTJyw5Uf>?XJ6>Cp-kJaCo>tlU&La}Cd>aqQQ_SF}`7bg^J z&vuXXZ>7O&>uVE=wW*}X`qIQ`tZwuVe>xOvGf9ut#Sbom%_NGoiA1qjm>32%*tp5n?nJE%QSi zdTcb8`5J`I9N-%xmLNt)i#J9;(xHzwdSmnz2#uC+j97pe9WCZEUw`PMjoui2{ekB> z^w>VWtLHLbeo!o1hSi6`i{Psdisf8}#fQ;Y%w>L!wx4v z^qKLe1gl!+=nu+eOa1(ZRTHwxA)uzJHRCLtOe(0&z(a}^)gl=T)sWuUg zrQ+a+U3%6_14vKp&&~Jq;ApD;o!u==gE;kJG!^ffC;EvqA4XGAPd734D`52;O~sq$ z$#(iqpV3rIfxgd2WA)P>MpM08IP0OOzOP%iKO~*t?|+_de@L|F!zzFKLxOMC+aHp# zKP12VMX>d_(Fd&G=*z$EzN@3hMlI_%+G5!< z-_$WYTC~jfbZE4`r(-x4E%PlMJvM5YZ|P8{xKiLdI)+D!mMvV5^9>!tv1r-Cl>*<- zF&gXpIdl=>+WI9IIF0%LmMNbM#vlwaj;OXteke5eAWz*Ee%07H<%{@8uZ22xysa z<YNZ{H1L-wn5w%ul~lRp=qY zOT=v@^R|+C`$IDLhvdaK592EkIMa65$x~QD$C0-EbMdE_3UH*YV)6cd;6&TeSbu-V zfwq0I*S?bbL5U-y?QeG%FWNZIw#W9M?|(-aj`jC<9B12O?frc?*1wY15Agne;56IO zi{M|$ILx+>*1nR5N9*tJILlVCILmf)wEq4srwE=~9A!HitABU-B=||TeYEzKJbV#+ zEeZ$O_E=ks8jkg^WSnE$V{I*JI2JAQV{ChD)G|NDR?8UpNGkFHLu?hxmi1FjgIKhTE53)X_>SH(toY&tTir5W@g0su%edmp18fId*8ksMwu~#j zhp+e!j}|TCitphozQeI-8CQIHdhO^%K+Cw|OP9}JELMD>^65`P54yT#Sn-9)r^iMu zbCZwOAlWis@g2QoSn-9&r;j$8%dq0Ry2eMbzT!JPTC|KSzO?v^J_-7Fmo4LpFC{*s zv1l1reChBRjYZ42;!B0kXe?UB6<->B24k_}3xQ965_-_pEpvg-4u4ONjar5kU+8;! zY&4f)#TWLT9vijH?LE2(_+5qap3z%|mT|@R@D<7^9tW4Ljpt?a^}^?Tl;K83$=kkBwU9(jHv| zuCPWsCpog?Tmw_hnAim8?Ao0rAM)BS+p~*VQ1XRopE&Z4F0LX z&NwJ~`bFqLSHCg3qDL2jEsJ)>!O){vwk+Bi*RV4Vex802qBlnO^JuheS+p|_dLG5H zWzo(!*m(qTa4w5>#zD@bSgz#1e`nk!(J+1Ra~&u8$$!55`qj^W{py>C*H3r9{rdBN zdG+RL_*aGYffL2sfgkiF9Ja>y|MHVRDk#-H5tZtNSE?;{j;7idqEh|cRjIbxIhHzo zU_U7+)hAV@THQxe?H2{5dfSz1--n~A_Je{_z3fW07uV5L{ktEQAC&4ds#2}%qp9|D zf>OQeZ7EXc`#+AEJ} z>bKagE4$^t)s2qTyLEoRZuw7jqp9Al6Tj58#eb@GG6hn#^1NBi(l5M>?e@^OpZcr&M;!f1?|`0{#=7QaNw= zPjsWH`geA>*e(BsZZs9$!j_D-_z!fWspuAdpHu4l=B?W+-}k(krh86Hw^zQ~E8p#v z@Ak@fd*!>m^4(tfZm)cQcdvZE`orBXUp{{IXB|xT&EppjcYpr+KklC1{CSuhmc+>w zE|YeR+2`W6YrW(0W2ruLe`=Ml=h{1M&$Y#vo@+0)!@2gws9d+O^j!O79L}|G#-3{* zjXk%&&42&VIGk%=jXl>s8+)!T$qeV(cVo}Bx8I&?AC7~$yRUfmTw9jux%TNeoNMbc zJ=Z=Sd#){d4(Hm+OwYB?$DV6TGsC&|{n&Hu1G4AZ!sl?VeL?nI_RW_*hjZCCU;NZ~ z{Y`i{7k%4&`LpLHecSup{^9$4(*95O%@;t2$BVvgz69FGoAhn>HPAj@_RSYTN5|`{ zpgos;^JUQCT=Z@8h0uN-qQ3RJ?e~p+s}WxNcXIc&(0(1*H(v}Lz7FWy=F6eF4*qUD zoQu9~z98Cjllg7$ciXP7FNyZtsBgX|s_W~EqCGd6-}ZjJe7v0Bd|7n(`eJ_Dd||YY zH=5skWwc)h_RZguN5|`Hqdk}Nn=g(I=dy3UJld~AG{5z`?e~p+^S9;U@v?8eM5^)n z66tU*`{s+JJvZuGzuR^ld>2E{jr!K_w&!ww^KA^n*MWWWeGGlP(fro$wvU(d8`L%Z zsr%{gfN~UhF8k&?8Ah*z?_^NlTwc?!Lo~nnR)(I-`OWt-43C$6bA3%8Z}dLtn;H6e z`9A5p8HUHpzWH_rjTZu&(dU7E^Zg7xH|m=kY;+xbLqpGv<~JTny!noXo*VUzhZ1kT zrJ?6W^P6vJ=+}XL^F0lt&x7x2=((KVd{e`4F6TG**!1fV&2PS|p^umIn{R6v9xvxN z-`Ak=!elep3m!_m`NoEx8_jRNu|e0tcQ*9gsBeDePtWE2=35(vudl9`%@@A6p^rD} z8xJMkd~-w3jr!)t{`Bj>zWMHk(d*#58+tDL=Gz;FbJ;gP`KMopsBgZ%p^uk+^9>He z<7MA`hl9rJI~;~{IluW9hn^etjfWC%zQ>{GMt$==4!XX+$)V>)^P6vS=(+rU^IZYML$=;LMIe5=Fo zc-c4K>!9)aUWega_RTjt^xUX#Jd}9zbAWno)Hgo|NY~d70_wR@-+a46&t>0yzr*nL zW#4?mLmzL{H{bBk$IHI?j)&3l`i_U5%f9)Rhv8iI&G$U?>k#$L_dN9RvTwfWVR*dk zo9}wiczxHya4!4i+a7vu)Hgp6NY}ylJ@nkDZ#YJYpr0d{^1NGdfZ#rIc++=>!{~2?=Z~6!Ni+43=Qztt4czu3TZqm0p)5&waZ^}*Pw{oF+ zuJ=v3$^2I5I(e?oZ@N%P-|A#1&t=~tzNCz(m${NLUn&4MjW_9Ao$lnh>|4Z_)cH=H z%f3Z?NqJE{*XK7~hp2DlOB(nRbdM&#Fvx|)pOam zh%YG{s^x+&(ThOTH}WOTHJO?>BfjM5ciYFyzD0aV2~j#GNO7e`xfyfr9|~y z&TkQ4QchIQW#1ycq@<{x%f3Z?Nm)@nmwk))lG37jF8dboCFMo6T<|4&L5})HzC>I8 z@%|9;B?tKuZOvwG^8Hq7RKE`FTf~=?8`X2!w}>w(IjZNfZxLToc2v)0-y*)G^r)W8 zzD0aV`B6QWeT(>#5~O-A`xfyfWk|JL@Fn_ijQU2tq=7F{ZuCCc@3xPZeT(>#lB9Yr z`xfyfWl8m1_ATN|N|Wlj>|4Z_lqc15*|&%m}q%WLV{RqxBN< zB~q+1H~M~ak!HUR>|4Z_lrq(y2lg%EOO8$xc`o}F@g*fq^<4HX;!6(lCGxD|zD0b= zLB2$yRpv&0BVQuZDs!X0xldEi8Tb+{xJG>=Un18k#~byHe2HYM%#Hfi@3uW>;7fEJ zqTd6^mq@qD@kZ;DF4gS!jeU#wlG3O8bzt8jzNGxAmJ7Z_3-HnVB>9pCzC^iE-^iE9 zxr+N1@g=2D_3Oa*$%rpG$d@$mCAtn#-^iCpyUObj^{wA+zYd(=BEIAxUn21;#~byH zd`Saeq91yq-{1P(_UpjDMSRK8@3!TFFVT3TzL76!;7gPn^^JT<17D)tXnrGK(!iG} zH=5tbmo)Gt%8mNg@3!AJ_ATN|WaDKn`xfyflCv?FeT(=K8F`tD`K=tj*YgDAOB(zo z#}x4;vhrfQbJ@3uFDYA%=dy1RUviQ!*~yno5noca8XqtF7V#xztMOd+ zE#gZ~@+A`7@HtD~C(Bmj<7M9>zC`X`|NAS!4aOVsC9?M-mwd?-@g-%evFkv-WQzEb zv)^scW#1ycw(TaD+kZxLT| z_Pg!5>|4Z_l&!{d*|&%ZxLT|(qFQ} zU!vzB`hKIoWQV^*xykxu*=qbcux}AxQnnh;<@^@$C1tDeT+VM1UsARj&t=~tzT~98 zWG7!TMSRIgzC=gEw}=`YdAYrMYE{6@Y+B4p%7d`a1A{5r625npnWFOi6o<4t}KIO#8u zAd$Jr?*V12vFkv-WQzPHC;1Wyq&VKFZ{$lP%3*FazmYGI5QMqW{6@Y+;sfR;zjv3d z#_t>Z7V#w~`4VlA#dssWq--@lUiK~GOHT47JNc3+;!95QCED1*>k##ge92C}L`v&m z|K>@)WG7#ut*uEe`I4P{iI9jW7r(y=yyEqZ`bNG)zy@=pzL784$(Kx#zvLuevXd{F zBEF<-HP$!yOSCa8+24KAU$T=gnIgXABww|5k7DO-)_vTqSzQnnh;<@^@;OHT47JNc3+;!Da_p;F_iujVU)p#!Z7V#w~`I4P{$rSM=WvlV=vTqSz zQnnh;W#1ycq--^w%f3Z?N!e;V7w?nv|7Y**dNoU~~gG<-7CA$SA+$ zCSP)rFBuVEa+5F7Jte+=7!hAmX*D(u%r6-cUviT#QJy{Pjnv+d6r{g&`0($#Fc zF8bR@_!8-AwjXu%|ATQz_!6mTwp|y$-$ufhNEiFv$_-$>f#0Ny^`y?9Q#bM(`4XMq zrEcUm=9lO^A$23a@qQegL!xfvH}WMqXF%P^Z_F90_wT;>hd;fa|MOqJ_}jnx`>+1f-+b}2bsJ#Gw^w8pZo2&L@moLbZu_hy8bSduFuV;%kQFk{aq+spBw4gZ|iow{w~~JvDTNaeLHUJ`nyoN z{w|cReamX=`nyoN{w|cRy$jpA{w|cRzYC>n@4`pj$7lbmpKss3eD&s!?{&Z9FW$U+ z|D&(IdH3$ScR&8gXg~C?JAka$6+qVO=|I+FF<*YvOw#p9k*-gQbc0Eeu1|_|eNv=a)ZQUVpNV zmw(aAY3xr-5^fQAU2%(m4%c~?lkGqGVtQ3Zye%Rm>rGCw-sGCHzNVC{_c+Pgdvv}` zI@S7XRI>gWm8`u+yR!Zkm8`!-)dlP=+LiT}sAT;mD%q*@A*if52>uRzU9tZrS$l_e ztEF49{U%v+Ygd+L#qOJA&8%HndKH^*k~Ob3WwH0BvGuj2WD}QR>rJwB8LkfKJqg%( zlPq0^lif{Ox(pWwXb=*YVc$*F(q-6pYgS8_;o1N#wdUkM>oV-Ry{_1GlWgKLY`RI7 zJrS1%GzWn$!=9U}O%B>`z52JB{dfB8$G$EMeO;)J4AE;@=@Yc#CQ|`n zK||C%m6Sz8JaG`9S1rx~Xb@mkfxl9E@-?{6Lm!V%>56MiH3)%Kbx9>fT!x>@IxdN2XY%1ugFu(zm$Ir&T!vUlRZExo59J5*KK9u^|JC3B zrFK~U@#QbS{aRnB-@SbG-JibIcZT^fzuj546)?p13K(M3PlLx7-~1PU@`Jc!{Q;7! z|8Cjz(;$)c2S~F1nwG3RK;3HnHN7c#$99q>Yp?09tUo}K^%a$5?E&h_`tKIW`U50c zjsAyqKv&jZ(~|YyEt0j@bW;{z2PEsSY028}maeSk`QcR}S$|DS))qruS$|DS*1rx& z)?U+HS^b??>#u3aCN9I*0aZ(v`PYGNwQ!m8c3=npI?$D+%kXtz+x_c6SC%fr*8#~+ zr5~2XU0J#eUk4rOWVjK!cFD z3||LSEnVhc2fEdwmo4}@uo_A<}Z=nevV86q`QZQ`;y&-NN0beSh=G^?HS?6P#32WoU>>9WCI=6M=jS^b?? zOP6_^Mpu?DLz>1`pH-fIz!0XP2aGQBFpX}tbQ!WVRBhriT-CBIxT;06v%qIvhR&nt)_f4W+{{UuA61#f>9XMM zuWIQsy#0mUKL1rtvUC~V{@>HQ&rca$hPS_D6PMxb|H`+&WD}QR^F*?AnQxxV|Hdaj zq-t#GGHjlx+QenpJW;iDnQxvnt0lF)VDm)PCcO-sC#sgc%r{TE)#~r8mtpfn)h4|R znYI}ETyDLkVk=ov!+V0A-myz1uo!V~7lG;{m z8tmZIc2}0a%Mg?Fy3gR8r&l#dNqSw7k|fz=#fXq3$#TW$AxYgqpv#bv^s3vslR==% z5RoL=kNqxt{0073Z{O&A?Rfo*Uwrwp9KZVV<>&9-{Pyj)g6)6z&9`scyWsj&=yR=o zG=HNmn@5J!w%R9GZ_@Rj2h#P0i*#+W+q#;*hj*%UeYT}*E0?yePq%b^=^{|rrn{}{ z^DSNf9WGs)@3yYLR<%*-8~4(+#YcH~)r)kefqwWx)YkPEt91QGf^=>9($@7i zt8{(+B3;eE)Ag>143VzCTBU0Xm}b2zB15DLzX_j@>ZRWh8KQa|-nf5r) zZ@^@4qwfZ{#vzym;KEF znzk-}zi|&$;~VuiY@(`O`pq{{+x6o28+TDvZ`9wgjjDRt-{$t(^S=YIk1AdEH{VBX zj|2M~Hd6J$H0p2INmaXGfAgKxcD?Lx*h*EsQGeq>H14HJH(F0(Ggae2zxifrcO0;r zDqZ$B-%V}nvcF+FRpSu#H|(dXUiLTNPi@!B{)P=zeVLE^h8ScfPUDa;A*jAM;{pQ=MZC&;^?5k=VqW*@B zRn^P><{PW+dfDHwv#NTd{)Vkp)yw|oTdR-tK7Kg=f!yn7yg1FMj$<@s6!Ry-@MwAmFL3izkN(Ppa3RoVG6B)QotNuDz)rbsuNq z-@e%Y`gnc$!*~Du_TAgxy!^xedim9x-zlN)KmYpWNB{NDfAJH2b$tDCdyasWnDyS~+Ya*m{nRlIJBqOPst+q!tm>82>^+FP!zi&eaCilVMPtM%=!F%EoI zZ#=6SU;EYE*2S}`o1$2+KdW=JJN4pO)lE^<^=GxKi?^I^ilVN)<=W$bRfTSfg063E z*IKqS4w~)9cb9I8qONA(!>@z3F8zkh?Xmjic3YQz!|t|p-EVX4(isQ(4cpt&HNUm% zrQfi>EnV|lR~H-Hx)#BEgLKVrZC&~eJKWNZ{Dv)V)l0wm7I(W|`VD*BsyFf*E&@`$ z^qX&TcYQo(+x&)I?y-J!m;2-3?NDchEbal4tS#c3Z!=s2wA{D`NV4X(t}M-lTYw~M zW@`^F&33Z6;TE9g%VAEnP1;Gb;TE8-F3onbx#1R|uCD&h>!sN|8N55bNCwyAz~<)3 z;I$#sc=_TMAnDRaMHoCxhq&qA8 z;Nk8wMy~|O6Q1lX*Hlc(lx6!-wXq{|LEz!M-m;Cj_P%iqwoj0I7(nVj}9OY^2YPKJIAzk{-QJ%K0 zX4`e?w_4de`|ce;c~mdfkz0NIeO}l7CS80a*&O9*kAwF%-H}JXIm*-4rQd+^jLlJ= zwl4h!lt;Smx9O5k_u?^U+nxuYJkmA4HM`K9Y?r0ooaAYKLmeP_G;Oq-lRRx*+6^R+ zhQZrgb9h1Ws9xI5NuGAS-rl53yE)0zeat}eNSAhVlBcapyMg2xo0B|kUD^#fIMR*U z8%Q24f7srfZRYDeUQ9{nJ?Oi@ID+I?24y;H}V^plJQEWWCK&uTt9#*kuE=%cuqol9QgB%Ov&a!32j~ajZDer z{8LvKOo_&Uev6orfvg1S(r?Z`wdxgrzNy?={GVZn=>VCUHXko z$>wvl^TbF(#RBMC zRWEnLC)(xu;km2`F4--wmq!ujs=J7?SGjaUgToNw#WZ^TM) z;e1<{ej`?b3+LOq^c%4fTsYs=1y(X%iIr>-R>Gth>C$hW6w|Jk{f%4+l49Dr>~Bbl z8Ayt0>vBCwumnjlZC(0}WC@aD+Pd@`(Gn!Zv~}q>q9sU*Y3tH&L`#qq)7GWm$d(`} zrm4%Mn8Bo&fuxwWF8dql5+ud6b?G-G#i(A*z|-H)m=vRNKz~D0OuJtCjd%%?V%oa& z8}Sm{sMOYl-SMjlvk~i@Z5vefrX zgh?@)x2V72wvEB080kiSLsE=%>9>e4;e8v@<$5yWOL*aibm_N0%#{t-0=9qGk}pw`7=FJ+e920_M9D_fjr@koIA*8~b))_^XWQqE>&b{O zStm{8y7XJbm#lNPU6+1~_>xMfFz@;$wIyaS8}xLrQgVx z;7*RNF8LB($}#qcFIneo`}opt5noaXHLgp)MSMvm)VMDF7V#yOP~*DvTf~=CLXGRv zZxLTo2{oomzGRR1l1iv?UHUEJOV&Btt_xmykNA>GsBv8!H{Bz?WF=p+kT2OIzN8Xr zyk7b(;!7%`#&zkph%c#(8rP-YBEFQ?1(Mt>e6rIOZF(XWJPSrSjd;`QEbUdzGNX^vPXPLh1A&dK)z&;_>u~#ab5b& zZzAgU`8nIJOTR_IB^6TRy71fK!6of_={NEvhbNb`b@}^^e93|6lBO>ZU83XD=x;|9 zU9!&Ew(%uja(Hw}dmOl)BwuoPc1csWVrslz{C+z;yriwm^(6U{!_!OJx|(0F7k)b; zzNCU`To-;jqWF>us&QTVEs8Ixq#D;ne>(Xx#Us7Q;u1mi;U($V_kuMRrg6AxXFR8E^tC#U5hw~-vdePss z5y^Vz4$ISiV|A7A<{;!8I2C4+p)f&7x*dZ)r_yk7bZ zd`VXq-zW7$0OK3wmsD7d*Gs=e`6U}}A{v8y$r0t3Y;(4)Uh*YJlwVS5HLgp)fiLOK z8~Ypik|WA5*~pg+=9e7cOPckPFB!})IU>HK(rSEs+210*q|$0!mwt=*k_|Tz>G`GK zBEF>3YP??hE#gZy=9diSmmE=k$wt0pkS{rE<@9tPVt&aWUvfnGB^z!c8iRbv5#^Uu zT8+&c^GlA1FR8Q|*JXc;_>zr$iS9H&zi_^!yZ$9#qRevY>W%mOx@69_j|2S%zNGm+ zBVVGJU(_4%B^&t?rG!#9pf$}g$38k;xrB}bHBQfW1= z%k^Z$msDDf>(Xx#Us7o`u1mi~d`YF%xGwz`@g*Dil0m-Yi1?C9tMPj2w}>y<$d~AR z6MPZnmu$>0(RmB%Mt&n-BCede(eJl8+cv)BOOA*ysk9o`rQagHq|$0!mwt=#ODe6# zb?LV#zhom{qJ4hOTh!mkmkj2Y91&kqX*E6$^jpN2Y;(3vmwd?)<(F*aOB8T}@s0SB zN~`gD>9;7qq|$0!m)}dG{E|wmab5Z?;!7&6#&zkph%c$M8rP-YBEF>3YFw9oi};dC zt8rbfCnLV3(rR3nev9~$4VU7KLB8aO_>xMiv3i+bazuPdrPa7D{TA^hl~&`r^jpN2 zY~)K6aD(?w#FuQ$FHyh^brXKF(rSDh=(mV3sk9o`rQagHq|$0!mwt=*l1i&_UHUEJ zODe6#bjg<-5nr-Rn#gt8-y*(bo3rh@^jpN2Y~)K6aD(SJ;!8I2C4+p)5%DFJR^#J9 zzeRjWrPa7D{TA^hl~&`r^jpN2R9cPe!fz+|lDVt%>GP(QR^z(x+v$8seWmN@ay?1D zF)#C-{<{Zl%@Oyxr(;r}HJvaj3K!*M;9s z=S$kU`a0&i@Y@;jC6!j=y71c>@g3YFw9oi};dCt8rcWE#gZmt;Tf8mz)t_QfW1=OTR^YNu|}eF8zk< zaeDhLl~&`r^qXIg)Aa@Ul9hbPiTiPy_40lk1>E308Sy2RR^#J9zeRjWrPa7D{TA^h zl~&`r^jpN2R9cPe(r*!8QfW1&OTOfc_>xMiab5Z?;!7&6#&zkph%c$M8rP-YBEF>3 zYFwB7E#gZmt;Tifw}>yPv>Ml?-y*)G(rR3nev9~$N~>{Q`Yqy1Dy_zK>9>e4sk9o? zC0}wzd`YF%xGwz`@g+O?l9hbPS-(`C-Jjpdmnh%{{UYK^cIKBT;D)*hKe;o%L;*L{ zO}BEF>3YFw9oi};eA`6UXtfiEJyWM_WK%KLH7h%c$M8XpJxE#gZm zt;TiP-y*)G(rR3nev9~$N~>{Q`Yqy1Dy_zJ$(NiFUs7o`u1mi~`6WB~l9hbP8QqUl zX*FIi{TA^hJM&9c=9ioiU$Qg5L;*MOam1HYT8)nb{TA^hl~&`r^jnl)QfW1=OTR^Y zNu|}eF8vnqB|G^N1>9iXBEDoNU!s5;>Lxtb&is;<`6Xw>m+W)4ZG4$uaz=c~&ioPu z+;AMC^(6C46mUb`XgxV++sA=^i};d#(nPLHzeRjWrPa7D{TA^hl~&`r^jpN2R9cPc zk}o+UzGR;?k?YcL5nr-1zeE8yc+MieWas@j3b>(ea{g^6U!s5;>PCJeU!s5;>PCK> zv+eUnzeRk>K4;r?>9>e4sk9o`rQagHq|$0!mwt=*l1i&FUGgPo#Fy;kOB8T}=ON-t zcJd_(xS?*sEAQk>6mUb`$ZzCJ6mUb`$ZvDDectG|h%c$M8rP-YBEF>3YFw9oi};dC zt8rcU?E+uY+;5pQk?X>5m-8jv??#g*GF|c|m-8iUUG_KfC71IhZC&ss3b^s-_X1zi z9bc{|$(LNRRYFrn7yPPj+>$1P`ew-`fODe6#>xJL0h%c$M z8rP-YBEF>3YFw9oi};dCt9jH_zzv??nyF{MuUA@)>!QD15nobiHLgp)MSMx6)wnMD z+ZFL82k*yGzzxSY>2H-*Pc13*2!TWI(aKmv(&f`>Cjn_-RMSRII zXWMn@w}>w}m|voR8;nE5msDDf)yw>nE8!Tb^h+;AL{_2famL;*L{ zjr>NwL;*L{O@6-}%rDuPUvfo!Nu|~JywPtFUvlt%oQ?S+pbH$MSRJ@{F06NC0E3k9Lz6KzzxSY z@*D5RQNRs#^~QVpTz;k1`1sOq5npmJzeE8ys26<6{3`xwj=$1syk7bZe90W`jxK(` zDd2|n&R;4|uP2#bvN6BpiujU)e2D^XSa0&Z(e zALdDBy;=(Ry;yMCJ?Lk8?$QNu|}eF8vnqC6!iVy5vi)h%Y&qU!s5; zjBmu39Fr#Udg-@_FF7VnL&Z$2l)~O+)y{_ zZ_F=Izzuby{zkq;0XNi*`WyKY1>8_K>TkRsM*%m~jr_*^5(V5)H|lT9FWH!1az%Ve zrPY|w}m|voR8;nE5 zmmK6v6mUb`$ZzCJ6mUb`$ZzCJ6mUb`$ZzCJ6mUb`sK1dfQNRs#BfpU^QNRs#BfpU^ zQNRs#Bfm|W$b50qZxLT|@O~Tx+@RiwFFANWjsk9|8+|V!U!s5;>PCJeU!s5;>PCJe zU!s5;>PCJeU!s5;>PCJeU!s5;>PCK>G?6{O7yTCTB?s@vQNRuBjr=y#YP??f?T+}8 zgM5hsZoJ+*;!7&6#_A8_K^4p||d>r7n8+^(9uYCIZ zZ>80^F8p>!d`YF%xGwy5M|?@8)wnMFc1L_krPa7D{B}otNu|}eF8vnqC6!j=y7XJb zmsDEKqpkvO@cc%6Nu|}eF8vnqC6!j=y7XJbmsDDf>(Xx#UviQ!QNRtyH|cNZoNcd{ zev9~$N~>{Q`Yqy1Dy_zK>9;7qq|$0!mwt=*l1i&_UHUEJOHT473b?`Z5b-7FoNcR@ ze90a0B`5h31>CUSq`#fyOB8TJ-DEv^k}pxf4Rs^GkuOoe4Rw?CWTn;kywPtFUvkdb zc3t`{;!95QB?`E~I7EEONxnn@H`LV|@9BN%N~^JPAYXDve91|^WG7#8M|{aSXWQ$g z-y*)`BwwO{8;)<}H}WM4xS?+3H}WM4xS?+3H}WM4xS?+Hz2uy;?ej*zMSRIgzC-~x zs26<6{2I~t9WZGkua|xUU((gpY@06mk~_*TImwqO;D+On{C+#hmnh(dx>0{4U!s5; z>PCJeU!s5;>PCJeU!s5;>PCJeU!s5;>PCJeU!s5;>L%YyDy_z!U-~WLOHSU8qktRK z8}TJ4@5fQV4Rw?6lPCES1>8_K@*DXQ1>8_K@*DY*o%iG15npnWFHyh^>y7+IzC-~x z)Q$W`zC-~x)Q$W`zC-~x)Q$Yc`*9R-1Ko%(Ip=Jfk2m@);!95QB?`D0{4U!s5;>PCJeU!s5;>PCJeU!s5;>PCJeU!s5;>PCJe zU!s5;=tg|WIn!#)Z{$nvh%c$M8q+0Taz}j0Nxnn@Hynq^Z{$l9a6{e5Z{$l9a6{e5 zZ{$l9a6{e5Z{$l9a6{e5Z{$l9a6{e5Z{$l9a6{e5Z{$l9a0A_lFR8Q|_XYb~#Fw1p zOB8U!dZYeEzGNp~a!2_kC;5_{e90ZNwL;*L{jr>Nw zL;*L{jr>NwL;*L{jr>NwL;*L@jrfw2e2D^Xs2hEsBwwO{8|p@WBVV$UFS(=ql9PPN zPQK)h?#DUFmnh(d;}H3ce2D^Xs2ll>e2D^Xs2ll>e2D^Xs2ll>e2D^Xs2ll>e2D^X zOjq||ye8l6$(JbLhPsj8m|wDkFHyab-^iEj;7g<%ttZKsDByT$g@}_>xMiab5Z?;!7^_B?`FV_`2Vw zt3SOzbdfJnzzuaHzs=e9aiHHKzNFG>T$g@}_>ybRw(HVw5nobiHLgp)MSRIczC-~x zn74>8xyY9&;D)+Mf2*__8wcuZ!>a*;1lzzyq-`WyKY1>8{A{Wez<4Zo2uQNRs# zBfl}fL;*L{jrtq;5(V5)*ZW)Zy+gi40XNVEU((gp-}!S!zeV{a7xPOLaKn0&_2fmq zE_i@+Atmp>E_i@+Atmp>E_i z@+Atmp|1O_`Q9O4qJSIdMtsRdzC-~x)J=ZBRa%Wbzu-&O*N88<$d@SKhV@4MjeN-g zzC`s#ej{I^fE(5u`Hg&u0&b`q`Hg&u0&b`q`Hg(Z0lq}z8~KfV$pOAZx{=?QU!s5; zj6=kiT;xj>a6{e5Z{$l3@FnYOlwWd@FFC-MNH_8u`H};CiF6~skuN#Gmq<7A8~Kt0 ze2H`;zmYFdzzv^=$ZzCJ6mUb`$ZzCJ6mUb`$ZzCJ6mSFGh%dRwmnh(dx{=?=mnh(d zy3u-)e2D^Xs2ll>e2D^Xs2ll>e8~a6WPOe9$GOOtDBy|3b>(e(ew-zIVJ^m(U?e8~a6MD<2~BVVF`8;-C0t@-_de2D^Xs2ll>e2D^Xs2ll>e8~a6 zWPOeJl8b!F0lq}K(Rz}6$pOAZx{=?=mmJ_rq#N}&@+AlO66u=XYWJ|=H}WM1_!8+x zej{IUfG?4*`K|kYAYY<@8$7?!{Wur-5(V5)H}V_#k^_8+#v$?>`I3Wt$rAA;7x|Kd ze902!mt5pa4)P^S#Ft#;OAhiSOT?F49Uvkgcc3u2_TOz)s(rR26>&YeJ zODe7AQC9&sc+Q+JX+IBI&A2YslS{;xR9cPe;(N&w@g8_KSx?^N zOB8TJ-DEv^lP^)g4Rw?C8_KSx?^NOB8TJ-DEv^lP^)g4Rs^GkuOoe4Rs^G zkuOoe4Rs^GkuOoe4Rs^GkuOoe4RpbmG}k4}FHyh^btAu#FHyh^btAu#FFDDVED>LF zGrvRuH>@}E8~G9i+)y|28~G9i+)y|28~G9i+)y|28~G9i+)y|28~G9i+)y|28~G9i z+(0+tOK$Qd3b>(e#GY+~iA6@+C{em)zt_PVyy7#FyOUOB8U!=OOYN z`4R=(P}ls{eLs*dQNRs#qy9#|L;*L{jr>Nw0!$xXgQ0XGm^^JfE&)6 z`K|jMhJ1+vZm1jijeN;TzGRuiK`;*ZK6#QaSt7pVCSP)rFIghKJOqkS|##aq#@}OTI(_ zH}Kme4gy{52Poi%x{=?=mz?BFmWVI8$(NkuOO}W)xtU*bk}p{zzT_rfa*{7uBEIA% zUviQ!S)4EFzSo&waw5NEUBH*jUvr<{N59FJoa9TEh%dRxmnh%{&+jA-p7#a$5(V5) zH}V_#l9PPNGKqtrUiLTgB}>GY+~i9XaD#D(_>!A^$w|IsiTIM6e91|^WQq8an|#Sh zzGQK}WG-4ew%~G-c*){;NmG_|$w|6o0bMfJmW^^rmnhzbPebH3(j_P9lErVwnZN#9 z^|HH>E?FYFq_S$P%abk{PM372jUP)0my8H5xe1q?giD6QCEap0*ER}dOGd<&++<5m zvL(aWl5V;58qt!Gpd||AP*9Bz13r}uM@w4eN><;YT^3#&30Wdt?fbYcI@@rvq+723 z&SkNX90^#Wa@p8!e3%>wSR!3|?M7o830NXsy_z1!LCH4$iX62Rd-MM7yKmn7?u(yw zhZkN`unlFW(hst|^`6SrD#pvjzT0rFq+2e$rd%7AI~R^mmrJZfxi-|b&m_%qNtGzp zhO$9lQrhFzTv$z^Hk7qJx2`OmMxy}HWktZ3+eK<;y(SP5pMxJCO_u+h>PUE_?TEde^mtG@JGLpO!>C$ZENrvBt)15YY zjX23ja1xbEvk@m5NnD9^X*S{{V*&;r%+_@UagvKT$(Vpapo>N1MVw?zz~F;!?=!N( zUT8PsBx3>wA9UN}K)Vqq8Oe1x--pwf-H4M6;3RVvKly`Ly0jZ{l9618BVF2!ILQD` z(yf<%BTh0BoJ94~Z^TJPf|E#>ej`pY>WO`N9Z8(zB2F^u6T|bm^c!)Kk>DiXhtt^e z%eaz};3U$e--wfpB(6ldTuBlq83|4zUHXl2B_qK}q)WdMCm9J&B3=58ILSzG66w-! z#7RbilSr3-BTh0BoJ3(H_(pOOCmBgxiFD~V;v{1N2G92);v^Swk}&~;K$m_aPBLbI zMW9Q+5hoc5PV#*?jlFk>lZ*r>`97S+bcvIU1SgR${YIQ*04HhoP2waMagveXB&wHw zBTh0BoJ1if^c!)Kk>DiKrQe8?j0qS#|NIgsxrmdD2^a*r^c!)Kk>Dg62l|aT$w+XL z@55=_7yML`;3U#zeM0qy&S^}J;tIOYS#7RbilV}|1H{v8?0tV0fm^jHroMa?8$@k$j<~QOb zBf&|&52rC*;v^%%Nu~9H9 z@_jgs=@KUy2~Hwi`i(frNN^JA(r?5`hT|mNe$2R%i#*A2o}{ZwpyVP@G8`yr>(Xxo zN=6b_qR~920Mgo+mUaltzlxU|mc|S0&q!zN`c!VZ z&G!!DN-iQL`Xp$&&3-|oM0qy;KGUaC$gE){|=4 zkuLpqqrd5u7wOV(H+H&Zok*8{BUQ3SR7r)?_`IRNtr1mH;WUrB%Co`qTW_#uzgJf{ zjq3s{S(CUD4IcWN@@!bI`>pqWsBjvu7hK7j#Fc1L@cT`9Hmo=D8^IFg*-$s~+njA5 z2l_3!4oBkvzuk;0StGKf!fCu-tS46|OPc+7VO)vwY%spbbvPOa^f%?%P}loguMaI` zOO$6r-K4)Qj4M%|4Rzgb-FngAlxIWTsK1deQJxKTBfpU@xk;C-Gr;2EcUJSg!?+UV z*|6TIzY#A{o(*-Q{>Hcx<=H^j@sjz_eR{ilAzh+48_Fij$%S-@;%ulJ*^Ox>H}R4+ z!b=w7B{%Vs)$x)hR zauY9EBfMlGUUCyJStGn;AzpG5FIgQg>AoMBR-!l?K4;$En)AlnaBkuyYlN3nHjVj> zc*z>!C6!I%y7XIwmn_6f6la6+jqs9%c*#w?WR38W%BHb#AYQUYc*#P%L~%A8hiExT zyhL#})Qy&t#7l1CC9C5lUB3}8QJf9yjr>NuL~%CMjh2&4D^Z*cb))4Z(@GR)1KkKO zscag5e(AReFIkvYqBtAYYwOAO^T7T_ykrGl(tQ6CFS&`AtPx(a5HGojm#h(9QrR>% zZ^TR12rsE@8rP-YBD`cFUZOY~J`a)Km{y`V8|p@WBVKY7FIgQg={~auY9EBfMlGUUCyJStGopvT1xA*xw?&q_SyTm!C_3mo(oy#7h)s zgXb4`Nmo~Y=k?NW5nfW+G_Fg(MR-YN)3`4CTZETXHjV4DzeRXSWz(20@sc&dODdbj zb@_QR!b=w7B{%VsHNs04;w3lnk~P9hDx1c~fqskdlFFuWUHUD;ODdbjb?LVVFR5%A z*QMWpmo(oG#7h)sgZEB^msB>5*Gs=ecu8f`m@e^>HNs04;w6f+;W$Lw0mMsg;w7u& zCEfJ{@sgW($r|A$l}+R0OTR^U$-=x6#o2Itqu+1DOB82A-Do|@+i(XG~YYKOK##NTZETXI*r$h?ta2* zMR-Z2)3`4DwmDwXd_Pn?jqAd1TZETXJdNwZZ(D?yR6dRC!f#uImsCED>(Xx#UQz)y zu1mi~cu57+Jm?BG!}pRc!b>Wl#&yx(wg@k&gc{eS-#oRXx$jgFHLgp)MR-X?)VMDF zHi3hOZRy_otRiY$mwubTL7?lu-)5=}`bC774B#cwrQagFq%vxJ9O$N1z)Pe{ zzfI!cd0zl8kuLoPyrk)4;3d+f-=g%A3aT+*5HH!H^pZ-dab5b&@sjquY4^u<>9;7o zWPmRboJ_xYdP%!p-w%*3{TA^hl~rToK)z&izNETR!*AeAR4@G&@g)O%iFE0=h%c$E z8XpJxE#gZmtHyQdw}>yPuo~B8e~b8%3afEl`px;09?n%+H7-lLIbPD0b$C+9KHV14 zB^6a;<&rMhoG$5>tDovF%jOorC6!d;x-?rY7oKIdE2+kHX*P#Tx-T=pC7L#xEy^yb zq#Cc6W{cpGN~&>Pnk|A$DyhbGX|@P1siYd$rQ0I7q>^e(mvG4z!6lVccO(E%jdEs8Fwpc*fic8j7*DyYVFX}2i4 zq=IT(mv)QTk_xJEUD_>TODd?wbjg-%9$nIX9JrJuTCzD>(v@X%BU!RVWJ$%;_$bh9 z5m{0(HLgpuMPy0E)VMC)7Lg?tQ{%dHTNGSUF*UABw;{NscaWiCYFw9YbF!qncmP>4 zlWp+DC?ZQLrpD?eS+YfBNyXH-E}L6KmQ+lQ>$15;WJ$%;xGwz`ktG#Vf=i@JzeQxp09hhk`Yj4BshApn9_Y6yxTIogT$g@} zf=eo<#&zMhJt9jgrp9&Qw>=_DDyGJCNtWypSyC}Iu8aP*M`TIG)VMDEwnt=1#niYi z{I*AAiFQcwF_pn3yOSl&_k(uCs0+XC5m}<03hKgdJIIpW`?q3he0<@zJt9jgrp9&Y zH;^UWdi8g%OTU3E>FQ!HK*=`VH}`r1K70i4>Y~3byboswS<=FUyNBujRXC0$+m zjbzCVvZSd?vP8)?9A76(y1Mim$&wvpNmrMCBU!S8Ea~dfZzM~0kR@GR`i;RQJIIo* zuKv#a#^jP6WJy<-{f%VF4zi@HOTUpU*+G_cb?G;fC3{4ctRzbok|jIHl4iXmOBRwP zJIIo*F8#*jk{x78SC@Wca>)*|q^nE6F}Y+1S<=;|-Wp}q@yKm zUHXk|$qu%pI}Y?4*^=Gal6JlH8{hdD#^c&!kt}gvXxMT-h z($%Hkm|U_0F6rvhZ%i)P0he@jxt?Tl$qu-rsf*;2RnazhPdZ%EeeaMiQM3(pH3QH8 zenWDJ>gDe@&?Vh*px>BWvV$(^>e6paF4;ksbanN2<~Lr9vx6?_>e6qdOLnJA+Rp?1 zM!aNqyriv5zmYH5!IyN$fqr9h$qv4xsf&wo6c~gSC{>b$t64Z zlCCcO#^jPc;!7&0#(cr#k{x_Ww_g37>$1OrFX`&iZ{$mM@FiVc`i;pYd&HNlNG{R$ z9_|N#FX`4xzwu(69ehbs7Z>BGUiuAuNmrMCBVV$EFX`&iZ@d_12Vc_FrQdil&JMn$ ztIPhzi*fddFImZ#DB1?=2k<4`dg(XvB|G?%t}gvXzGMeq($!^uV{*w3zND*5zcIOF z2Vc_E#l<+QqHQ>Dnt|uneYhA$x?E2>U(#JakS|fR4eQkm1ohHyyclN(U(y|4`i;pY zd&HMiPL1_9@+CX?l5V~98~Ktw;!9Q}m#m7m!MuSl>DEiXkuTZ7mvnXMH}WMr_>!hB z`I3cv$qv4xtIPgIzGMeq($!^uV{*w3zND*5zcIOF2Vc_FrQeuba)2-C>gw;zZ@d`i z0AJG8rQgVx9N!(J z{l<%N4)7&iUHXj|;~WuRQaLp~4%qKLz?XFErQdil&Jpn?l~d#OVm*08d`achJnAai z#{19_@gRI zFIZ0=NG@qUzjL;I9I&1|kX+K$MSoMY4aY%myr`wZP%sWBEDoJ zU!rImj6=kiY)mduv<-DN1Ht&BzYX#wN5q$GOfFHh4eOmx*3*6?U!rIm>PCKJa*3jC zsH+u5P%r&PzT}Abk_{K*tctc_y^-H=F^+WUw}>y9>e4*_d21$d?=uU$Wt5 zoOO^dIU>Gf!_7F-Wq*tKlFF&E_Zj(;BjQUo@+FG4!E+YzB^z$W(Kyg=5nr<5W*q6V zzeRk>HfP(%mwt=*lFF%ZUHUEJOE&T)gM7&m@g*B>##t3@gXbaQOSU=NHV))Vj)*VW za5IkTrQe({X?~a6a5Ii{+210*WFudqXd8}i)ZZ9hqHG)LM*R&p<7gb{w}>yPq#A!7 z=(mV3+2(A!F8vnqCEJ{B*JXc;_>v7bNwMCmrvjr>NwMCmrvP4)ve+>E2~rQagHWW&uk(xu-b zzGR!T?awd$7V#w;ZpK-aZiDfS_>ygA)mXjcOOA*y*>E$C>ZRWzzGTDAIMSuxBEDoJ zU!r&$j&J0*Iom$I^jpN2R921a(r*!8Qeic&OTR^YNu|}eF8vnqB^&cg6mWxii};dl z(nMA-`H~~zOE%n$vnt?*^+w-I$d@SKhPql|JpY|w&bE&O{TA^h8~G9i+_2urZ_F8kKGRT)45nobiHU2!%ZxLToX*I4( zzeRk>hMRF#1>E@fo)KTNO`6E-h2PGIFWDwdWV+-_&WJDBa5Ik1bHZ%wnm#FtcB zjqB2H5nobiHLgp)MSMx6)jaAd;0Eu9h%c$M8rP-YBEF>3YFw9oi};dCt8rcWE#gad z@+Atm;rJ%~Z6{x%KvL=^-zO`r#>atvi};dCt8rcWEy^#cv>Ml?-y*)G(rR3nev9~$ zN~PCL!%{V$hMBQXRpwepmIiugA{E|wmab5Z?;!7&6#&zkph%ed6mk7ke_(pt5rPWxy zT$g@}_>xMiab5Z?;!7&6#&zkph%c$M8rP-YBEF>3YFw9o z179MptnnSD(rR3nev9~$N~>{Q`Yqy1Dy_zJ$(NiFUs7o`uFLgg#FtcBjqB2H5nobi zHLgp)MSMx6)wnMG7Uh@h(Xx#Us7o` zu1mi~e92C}WF=p6Mtn)7)mXjcOU{Tdsk9o`rQagHq|$0!mwt=*l1i&_UHUD`FWJeL ztmI2h+>X=xZeM9NUN8L?<(E`ijqB2H5nobiHLgp)MSMx6)wnMG7V#xJ`I41<$r{Q`Yp;Ysk9o`<$5yWODe6#b?LW= zFR8Q|*QMVgzNFG>T$g@}_>xMiab5Z?;!Ae&B`f)oGvZ4st;XslUveV9r1}0OU$T-f zIiviNN~`gD+210*q|$0!mwt=#OLp=lEBTT$;!7&6#_OfuBEF>3YFw9oi};eAe2D^X z@ckj;ODe6#>!sf!zGNp~vXU=3Bfg~4YOG%JC1;dhQfW1=%k^Z$msDDf>(Xx#Us7o` zu1mk+ew^lehkS_wZup!<-zS-0vNFHqjQEmDtMPH5-y*)G(rR3nev9~$N~>{Q`Yqy1 zcJd`F`I0l@OLp=lEBTT$$}ic;m#pMV&WJCmv>F><@+D`KUs7o`u1mi~`6ZQByPv>Mli->!%+sk9o`h2O4-FR8Q|(+d`YF%xGwtJ74apNR^z(x+ZFL8l~&`r@Y@yfC6!j=y71c-@gl~&`r^jpN2R9cPe(r*!8 zQfW1=OTR^YNu|}eF8vnWk5g$iu1mi~`6ZQB2lGod@+DWqmsDDfjW6>{u81!=ct4H;ZaBUP&vh`rWMh8G74anp^Gg(P z!+ImXF~39sH`I;%#{3cm+)y|2+njBG9_Y7-FR8Q|*QMVgzT{wji2`mg4iR5+Fuz0r zH`Gne;~dN{QNRs#lk=tr^Gg(PL*2-4%r8;E4RxdbM!rM=H`I;%#{3cm+)y|2+oXx? z`Q`mMSHzbb%r8;E4eE{fl7smr3b>)JPS`)cE+Jo{fE(&glI__XxP$p68~Kte;!6(Z zmu$>0xgx&gV19`LZa5B+-(e)Zdt2 zqJSIdMtsS^{1OG+P&e`$`4R=(P&e`$`I3!%$rbS>2lPCJeU!s5;>PCK> zG?6{OydUR^_>zP9B?`D8kKqJSIfMt&n-qJSIfMt&n-qJSIfM(auDmnh(d zx{=?QU$Qa3*Dv@9q}cVR^z(#Tf~=CTFs-b z0&eh}MSMx6)wnM91MY|~sk9o`rQagHq|$0!mwt=*l9Tx*3b^6;CjISXeu)BZsGIb+ zllS8&;D)-%dh(pJ?c+PCJeU$T=gxg);hE_i@+Atmp>E_i@+Atmp>E_i@+Atmp>E_i@+Atmp>E_i@+Atmp>E_i@+Atm zp>EXQ$d~NoOYVp-ImwqO;0E(XrzT~b*!u1mK?=_Qp_9>e3sjM2;rQagDq_S!rbro-e=PaU2 zDyznI={KiKDg&YO{A#vcmwt=rlFF)aUHUDeOD@tSinrnTMt&n*qIetXn%{bDv!ZHz z7-+XByyPNWqI4UUYj*3Ft9PrHOSeUA$wjtA;Wj8YVoNTvB?`BpZqnT@vLy<)p>ERM zF0v&Gx1ny*-7c~v3b&zd)ZNIIDBOm+k=w|YDBOm+=C*FvBwM0z8|p^gjckd+ZK!K@ zYu8J^fi2lyBetZHYRt!AOQf5uCNHuj3b(;HMA;=5*%F1@P&e`$*%F1@P&e`$*%F1@ zP&e`$*%F1@P&e`$*%F1@P&e`$*%F1@P&e`$*%F1@P&e`$*%F1@KsRDbF0v&Gx1nz2 zH?k!Px1ny--^i9I+=jZ5-^i96U`w{w=x&^gY{>z(M7r*`IVz3SFWHg9N;Z(Uvd zdQ-R!$JhPV)z#nGdmU_v>UF<$bv4_rOTQtzq^ryR2DW5-1zXb9)ogpc^c(KR>FR2> zO&4s5>YYj-vP-(Unr+vm-;iC>)#a}@uqCS3`&(C6Z&$CE{S9~HG9LuzmY9bxDCg_`&)M$=r^z>+bh_Tt}guswnVy7e1=3Bn;UME{}fGv@3)ZfUK9AHbN>wfFjOTU3Fk?vG_dK}1>9AHbN>;0`+FWC}> z+u-?)?#8*umKXA*#y4V1F0v&D*plrv zVoNTvB?s6N=|+AdTXKLck#6KSvLy<);rK>=BU_?y8|p@WBU_?y8|r$0Yd*hZOB8NH z-N9LuzmY9bxDDqm@*CNb18j-vjr>NoMBz59H}V_V5{27PH}V_V5{27PH}V_V z5{279H)2aJvLy%DlI=ChF1g5-9AHbN8~KfF$pN-Rx{=?QU2=dek*@iz`#vLEa)2$7 zZsa$@B?sUV=|+BIc8S7m_?$(4V|IzcZKxahjoBp!vP(1$k>8kIqHr6pcZukdi`gXy zvP+ctAN_tKU2>2vSt7dRB3*KjE?J`Nl1i$v?;4~_mgsJri*$*?Z8&d<-zurb>&1F< ziRh9_s&QTTZHefTN~&>P_-%>kl1i#^UG%plqD$^M+pbH$MRdtMZ$ffi{C-=UE@{5k zE2-vDSK&5z&On#+zVB30jqBq3T0%KmwvW?Ywk!`(PtUHXlD$%4Can!4mm6mG+L zi~L5uMBz5njr>NwMBz5n_4QALdDBOm+k>ALdoa9TENgM>@OTUpXS-_Wc$CrL1U$WqCoUShYM!sah-8fxc`i*?a zGSe)A@ulC$mn`5*y7kg;LF zGrQzOcFDFxe96u1l9PPN67ePXoNZf2A-hC(?M3TJW|y4gOO}W)xtU#ZBD+NOMt);< z$w|IsiTIM6*(E2kOH^;v-^iDo!KV0Ot#zGR8`lAGBjC;5^Ed`a`YPQK(MU$THN>FTn-kuO=mmvnX6-^iCN;7hu? z>~G{t7VsraUGgO-`H}^ENmrNOOURcj;7hu?`a65ClP_7omvnXc`;C0b0=}fH%k?Dr zk_CK8SC{>be8~d7q^ryIB>9pBd`VZAej{J9fG_Fl(r@HT7VsrqUHXlD$ufz9=ik5N zOB8N{J~WAgK$m_aU$RW%Akfu#ncv8lEVvt|Ilkme6mG+Di257(l9PPN;(ST>J2?50 zlYGenzN9-2^c(q-1$;?YmwqE(vVbq?>e6rIOBV1YU0wQ(e91D2gXf=L@+Bwvk_CK8 zvtIHg3b(=YJBfp!Uj6sYZ{$msNgM>a>~G{tmPs50y6kV{OBV1Y-SK6ABVV$BFX`&i zZ{$lB@FiVc`i*?a0=}fHOTUpXS)4EFzR$>)oa9Ru@FmT9$(NkuOBV1YU0wD!@+Aw> zOS-!HJM$a)k_G7{U0wQ(e8~d7q^nE6kuMqGOS-!B8~Ks}zND*5zmYE);7hu?^c(q- z0luWGOTUpX8P1o?k1~yIbmApSxAAr{CUEfK_1ltFB8QS{?CE88$#A-)D@(I6x@0(9 z(v{U5c(vFI7+_0UbEZ+yf8TYnmK@HObjzjHZftcAM@zc0blQ!b?%`xf@fDwZ#54+U znu2Zch=DB8Kkw6zu5{tF>lHiQBOyzq3#TdAhV{-0Kb)B9J`Gq&D%gg)X0=|&++InR zDAFa1WYWF%aP zbm=#8B_rWVq|5F`u4E)!iFD~VawQ|-N~BA_kt-PqS0Y{djakGjb&ZTuE1#ej`^hz?ICmMdLk5uH+(D zGQgE|b?G;9B?DYZSC@VxS2DnrbanN2HgDug2Dp-@F1eD6T*&}e($%Hk$dwFmC0$+m zjae6rIN(Q)+t}gvXu4I5K>FUyNXIwD$dwFmC0$+mjae6rIN(Q)+t}gvXu4I5K>FUyN z^c&%l)!~vRrLZu!M8P)x{dWajqH$|HXO&X(I1UQ7q3%@ru;1O)h2IoxLtVY`9&|Ns zt$N`%1=~<}Dm`DXo*N$r&?Re^UCltC zi~goy8|qHyeweqWkLNy}&l_N_6?{oo7ya!fU$TNPY5IbE$xXgwO>#^0oY8OOOIGJg zruja-eX;OboSS&b>Uc?4mTn_mvN~PTlqFnp6E0aJxMU$*auY6DCvNcY@HQU?hL+rf zOV$W3S$HYVO}JzQT+)2`5-zz3m#lzGy1FzQ;gZ$ilG;jcJiUZVZo(z2!zFE9nvHPD z8o?zC;gXwh$qKlnJHE6V;gS__NmG}hB{$)c)!~xv_!2I;374!6m$Y@++z6Mf^O}?g zA9u%r&5dx$iqMj-uKv!N8{v{Qf=eo*#&x-vjNp=mm*U)nOV$W3S$HYVO}J#OC*Z^4 zp*y}@OcE|xBevAy}!6g+@v#cmwqE$vH~vY z>axEPE?EJWG<6A=DAk7J>p$MQy7*Y4R2%C0da|p_{zkZD1zghArQZmbtbj|py81iw zG2xOGa7oi|3@uTr4aOI6Nw;2noV*E_tbj|p_0n&IOIE-o-FoRa!X+!@}U2$!sYOS-!B8{v`_a7kB}ej{A60xoGj54;rTCS0-tF6q`wzY#830he@j z={Le9E8vo@F8xNhWCdK()urDEm#lzGn)61uFVm=<@I9oO=$r3J+-UL{zkY&=aWshJHGTA;S!z0jCAQY!X-L~ z8R^n*giCa*bfina5iZf~xu)Bjw~DB-=YepEZu2zV-n>;rjqBojiEb@4-EO`5JJ-ec zN!?Nx>9W7w_&%vys3KkZjc|!>i;8sVH^L>_UygL$Z+aWx`{WiymsCp4!@NlsaLE=$ zmsCuR>jExO8g?`e?l;v7xJ0SSi7wz0>Eiq3HgSWe_p>Uf#>atvo47%s>wZ(c^cyb4 zX}%wjT_Rojt?;d9_lE}H66vzP0WN92cMx78U3{P1BDiD#E}7Xj{@rtn;F1BjM7s2w z!zInb^8<8=bm=#zOWL~h8}X9O@sh4C_!8Aizkx4lKEL2gq)WenFX`&iZ{$lh@FiVc z?{BJ?ev9~$imI{q4*8NT;!7&3#&zj8=S$kp1N$5KlFj*&ChR#7UZPbg{TA^h6;)&7 zK)z%HU($S^A-qKOvcG{ZY3hP6kuLq_d`WlSz?VpuesjL0J8uXtkuLii_>%58&~M~R zHt;1~UHRRg2lhAcC0$)#Pih?KH}EB0UHXlD$p*fptLwkt^lOcN17FhB_1|yOWq$)- z($!^uBVV#bd`U&s*z>^fk_~)GvtC?^qj8|$z?XD&^>~9fYQc*Ro zOTR^YNk!GTF8v0+q&vR!8~KvW`I07wH|A_xz2r-_h%c$A8rP-YBEF=eYFwB7&H0k< zIDjwF*BtgY4=-u!`u9oc(r+GK($=Nl$d_ypUs6#uKECu@#Ftc5jqB2H;7gk8U+^Uw zU-~WLODd|y>Lp*YfiLOSOTUpX*&@EAqH4Te`Yqy1DyqhH={N8t&G#Aj5`E>Q-@uo2 zb?G(Xz|mvq}{_f3h-+ue@%RjvN`t7@yU;IuVk=J(&c|K@+b{o@xu`|tny#hdr< z-+l8Be|kUv=f8gOw}1EdU;U@Q`Qm3f?v7uPuR643U$!qvr?uT8JwytLFVV0%quGj3?E?`^NyR3BG_0qLnz_zZt{#A#T zFmL`VvaRc@TIss$Rj+0s7+-h2blvsRoxb^DH>q8(cUkGW>!oYEfRDP5F8bwnU;p;) z`xjZ{{deEK{L|Yvzj^uk%^zO=`1QND|NQc2%j-|p@$xS(uRk686XwECQ5EN}4i%?q z{P2&SPeQ|6^NF!%6~9C!Yo6`O(z5s=Dp|8^SC)>&IS0v_W4p36ERH$6p7>;zy`tXS;t|mTtvwP|2EGyVcUHIN~5#Giz6tUd0Iq$(mQ2viJe2 z@1S%Uet`C#ggMXVGW`BjwTa8-Ji9C#BYu81tEJ0ux*BSl+Y?!@y;j@0m~q{nNL`!prmhGYf9`dA zB6V%~($>YBRktTn*WRpcUA$U#dm?ph0n^sSyH&R*QrF(CZCxy3bbBInojh#o;_a&2 z6RA5}>ko^Kwk}?;LQ|=0uh+IN-mgMascY}owl4gp+Y_mq_^mk8$M=J7Po!?-H;{+A z)`@;|@~}G&h_#X~{pRFhTNi%Q{fQih$ZsGIRWJSKMf52YLV4arv0rQe)9Y>xx|2J%q#Mt%c%sCwDooILE-3-VC9^qZ51ZC&;^ zkcS$FsK4RbG}TMLIeFNwm;DXNRlYvor5mj$=WM$!`IE`Go17De<6>>16SlTZKdF3!}) zf&C48MqOR@H|`l7*fZ+t(r?@|Ib#>`C?in4}GivH`yGLj$eBs+YUB7X^M`$W_H3QH8o}aUAe&dGE;Tt~f zdg(Xr_#D3D)7GWmxaD*BmQP!ke&e3c;d?%9UHXliK8J7mv~}q>?)n_Q>(kby-?;5_ z__j}5mww~E&*A$%U0rVc2u+1AeB-CB%l^ilpTl>4+Pd@`lC543-}-6m(r?`RIehP@ ztxLag^XKr*pSCXj#@(O8cYoTt^c%N-4&VN1>(X!B|2cgBr>#rBaRcb^4WPCz{l*=j z!*_tXy4(WNEsF4)ZvnM+={JyvuZNR|ZC&~e$yU8q8+x60KNVZbFnt@<^={F=>Nmnxv=+bXUwvw)9 z;CWpnTWNghHzyCf;|uaox?E2>dDzya-;ivjaftjjXWRUSWGm@Lew(xHy8J%r$yV)g zpx=;e^?G=+Ra=++4arv0)eHpB8U2Q2E9pjlo3m}>i)1V5Mt+;K?YjJ4;>lLs@kO%L zt8P(5fAeIkwl4b{lC3ljnt|u%ZO*oj1HYGevQ@iY`VGlesyFi6oNcccemgzcs$DPr zhGeVP)03^*y7U|Qk~88(X!JOHNO=YU|Q(|yI z7Dd$ialYh{z5IN}Vdp3Bm7lynpKPe8%Btx^0%A0 z-_ofF)sC+J1edNaQKUNu>xZRJTi1JvF2nPm1k$xnUTs}}+@X4{@$Z0ShXeiC%Ych0u!`cDGs zY6hMkUu@}U9OyUS(rMRAzhO&fIekl~txLaQOGmnq->{{lOCsqv-_mKrQdu@r(G}ohAkb{8~F`eI;xj`^DUijz1Y%`uKxsAy^-JMY@6S(r6b+QZ`jgN zz4V)J>9ogze#2!Y%jsJ>ZC&~eTRPH>{5EIX#ur;U(vAAtoNd=-fAcM!_BgP=VM|B# zM*R(2I*aZuvQHe+jr@i!9qH09lp}H(XYtaftke%Stp3^qX(# zwCkncF03an-_mL8(r?((SuWqwY3tH&*wT@18M`%&5sOs>&2Fibm=!gGThdM-;^@QaftkeEgjWMzxk2jcD?YM z?k+;TzNORFh2M0hoVt~AX@KdUnzu)}GaJydm4M&DmZ{)W*+dgmfn;#i& z*Gs?Q$nbIjp_*^w#`+fw)v|%1l5XU;Iomc4I5I5V$ZvDDU6=jMj|{iRmwv;MVbvS; zH*i!MU;53D40r2ASgdr}-~7mMTbKO}M}{>HQGX*}vXL*j{K#;-UiyuE$rbS>bwJ#o zGk!0L_>yDJw&{{Dxgx%#4v4!hf4@b1NgWV(UHUEJOX`5Q>$1N^d`TS;cU}4|;!Em) zxa-ny5noaV#9f#DE#gb+fVk`O_glo5)B$nVWq*tKk~$#ny7XJbmmK6vHu5D`#Fx|o zajTbn$rbS>bwJ#8>9>e4sRQD!OTR^YNgWV(UHUEJOX`5Q>(Xx#UviKy*~ph%5noaV z#JyhnE#gb+fVk_@ZxLTo2gF^Me)~9I@`#>(_4Dmpp{IX*Kd*v$^X~nRzWV0fyYJrp z_$Q+cpK52_o1#!M|HyJFXz=mJ@8g{sx|il7cg;xG7opPirYK!ogtm2k5h`6bsdVi} zUt8A~q0)7eO4k;lU0rMq^(M_*gl7opPirYK!ogtm44 zN1t@vq|&t?eQjM|gi6;`|GdLzHh*|vJIi6Gs` zZ`ec-DowxnCPI50=r?R4sNTqL*hEmh^qX%YbnC??f^_LO-$ZEZ(r?&A&^SbX!zP02 zrQduLp< z5i|~5Px>Z8dmQLDY$9C4Hxb&p^cyx2q#OASn+Q4rL%;bZLc3ngw#^%IM^$h1`)$s) z>+<)TZz6Q-#U_HrfqwH%gtjh!zhM(W;}HFR!C$h$iO?Pg`VEIvRd3|CIoswp98#5T z)ZcJORpUUv`6fbl9Oi6$z3gwkiO|+%e?#u5#v$r&IHam^;Cj+G5!&@~J&8lAVnn0$ z!sgtNLAlCBEQYq_UD&= z^G$?yz4RLnsjA+{Z#bl?qr~iQen_=lFZ&w~sjA+nzu}Oo>g9UU52<$R#UWMc(rgIHam^Ncx)sw5W^zrl7&7UiLQ}Qq@_T#BU37M>W3aZ>t|t zZOP`H%Aa_*J6X7AgRrS(u zen_=jFAk|nmwxj@s%>5P?ZzQhjYH%&98y)i^qU`2ZPyFG-8iJG{i4WkbG9GfJ2wug zN;m0m3;B|pe90Q|B@6kIn|#SyBl_&V|AKpM74<^DMSRJEL#oondUB2Ul7)Q9O}=D} z_>u*OR8=qi7V#wu?zNRJ){|?*mn?I(?fE5NvPOK#fmO0!0{L*g`U!sso>e6o!U!w3p=#np4Bfdl-Y1HL< zGU7`V21Q-=w}>xM_z!jIw}>xMxCeE)o{absg$+=b{Vn24bXc3Z>~9fYqC>RQ<$5yW zOLVA@y7XJbm*`Lwb?LW=FInbn+xvlh$r|w`3;B|pe90Q|B@6kIn|z7Vy_4UCIHam5 zKKd=T#sY{zkq;smGBn`x_3aUTegcEaXdW@+E7;mn=A> zsz^=tw}>xU$d}yYOV)@lS#U^I^|HT3e91z-G;gITilP_5#zC_vd7zgqt zNT*39@g>Rvqb~bf z#Fr?Wh`RJ!#Fr?8g}VIx7V#y@uz)W4k~QK>7V;%G`I0r_OO`p?_C6zDqSWKWZ{$mE z@+E7;mn`H~G{tlzJTLvcHipQR;D|%l?LYZIvyl8F-q17<0Dm{Y$Zt1Gb1S8Q@E#i~WEt;!DPy?T2}jF1}AH^*9*^@Fmj4dUA{Sk^#O% zy6A6P#Fq@*Yb#x>CzW~}jf4A5y6A6P#Fq@*Yb#x>C%1?%8Q@E#i}j>ZkE3z${-)p& z`Yqy12KW-`(r*!8GQgKemwt=*k^#O%y7XJbmkjVF(xu-bzGQ$ekuLof@gT$g@}_>xMiab5Peh%c$M8rP-YBEDpRFVS;G zzeRjWrPX-7^jpN24DclijA4I^_>uv>M7s1_#FtcBjg15IOO$$?ydS`qs9yRl;!7&6 z#_OfuBEDpRFHybpTf~=CT8-CBzeRjWrPa7D{TA^h1AK|bfqskll1i)bdg-@_FB#xV zbmbcT7V#wme2H}Fw}>yPv>F=+@+C?=PW%SGMD@~d5nobiHC`|M7V#wme2MC%-y*)G z(rUb3`Yqy1Dy_zK>9>e48OSfuIM8nqUs7o`UN8L?@g)Nx=(>uKev9~$f&3Eb(r*!8 zQfW0d4&+O=h%c$M8rP-YBEDpRFVQ&AZxLToX*FIi{TA^hl~&`r^jpN24Dcly2l_4I zODe6#>!sf!zGQ$eQN8qA#Fq^4CAy-Mev9~$N~^JPAYZaYe8~V`qI&uJE#gZmt;Xx6 z-y*(bfG<(K^jpN2R9cPKOTR^YNu|}eF8vnqB?Ekk#({o|_>xMi@p|dEh%c$M8rP-Y zBEDpRFVWSt^jpN24Dcn=Wq*tKl1i(waUfr^MSRJav+cU{Tf~=CT8-<{ZxLTIz?W!z z>9>e4sk9oemwt=*l1i&_UHUEJO9uE7jRXA_@g3ZxLTIz?Z0A`Yqy1Dy_!rrQagHWPmSG zz4TkemsDDf*9*Vx5nnREm#AL&ZIAepF=yNAC10{fd`YF%xGwy*M|{aZeu=JT$9i&) z_>xMi@p|F6J>p9$t;TiXw>{!ZDy_zK;kP~FODe6#b>X)?;!7&6#&zMhJ>p9$t;Tif zw}>yPv>Ml?-y*)G(rO-c6>#G@$a}<>R9cPe(r*!8QfW1=OTR^YNu|}eF8vnqC6!j= zy7XJbmsDDf>(Xx#Us7o`u1mi~d`YF%xGwz`@g*zy5(V7g`HlFJN~`gD>9>e4S&?6& zYi#JZh%Z^mmn`H<_J}X3v>F=+@+Eu3m#pMV7V;%~#FtcBjn_-RMSMx6)wnMG7V#yO zR^z(#Tf~=CT8-<{ZxLUzBELk>FZ~wrC6!j=_0n$T$lYV;!9TKm+1N|`Yqy1R^*pRmwt=*l1i)baiHHKzNFG>T$g@} z_>xMiab5Z?;!9TKmuP(Hw}>yPv>L0Ie90d1C6!j=y7XJbmsDDf>(Xx@=Sv9(FPe>eZH*PrTu z_RHV&J+u3r%bt7*RlRt(=qRSwdn8{%rHgmVf-j-k5&!7B#h(4| zzW(jo_b>nS_RVizzJBwEmp^{}?(ILn{MqvQlXblO%ggxb*!BOs{`5NACQ#~(8(uMM zZUUXJHxtZCKY7cbWZmzQbq`3^{N9vBIG1GI0+KZgbY=B-4^Nb2-2sv{2XtlK0FreB zNY)I{mG#~#S%3Z|YrVBA>yN)={qa{Kg0uS(YYs${LNc4g@@v{lI_E<;yUwRD+x)n>Jb%mHIWXC+mM%jcm#R%%23%6r(q)cIcB`e!kjAx~PD^%W=`z5Ql1*F&R#I7+beXe~ z-D>GFppvTgV=jB5&n`dR`~9^-x*i|;1z6p(J66~Gr&dOn$%3krY%nn^E(KGVHYR3w zsIFTrCPtxNwz5*SADftuU-_;iR4g)-=|$OKkx}_vKDK!M?M~D+2LXXi8e1$fb_eRZ zvRGs&(2Ii*EHWyb%Lf6AjNNg%ZnaosD9#JjI!)J=#p`cDSktmQOxKmg>u&)|C)vbh zKpuXb>)w>E{Q#){^~oQ^(sgr6 z*IS@;&75sr?}5^FcS_fK;G^#2r2O*xj|>0sr}yu_`}Y6wjp6$K6T|$r@WkTh#2q!t z`t`w7$de7`!vpgl^!*bNB9is7l&pb2N0C&E7oA`)$_6jG6L5zH0WZ4S;g0Sg;6*3Y3)MQ?(UtXg zmLjVCouzEDU^#K(l_goa%wJjEYW9Wrs@%4cH|L`OJUw-?wewDv_`Kv#@dH0)tqpqI#ynv6julkN} zE2-DhKh{3}tp4~_U0GiPOZIbr{md-PFPER0g&G99%!7ZLE<^5*#+EMo|FXaS z+v%-eAFnTe`0k(IzI*$dmw)(QFTZ;8J8hQ#=U>14=)eB?FMjfRZ?8XYe`C-E1=y&# z0aq%D**7ZYXTVRQ2GVteVYxw9O4oNPy1Lj9yn$Cr*SFofy4VrCanq@E{R8M6mBu(A ziBjX>TY}Q{p4ipZ6aCl}dDE$Mttr;I!%n^aZAkTcSCp=G#kMZmB5yjCuD8YRIG``` zrc*_J+lshduV&lF*O$c7o$r(%P7Jhl={GR5(w+bE=XL2fK(o?yzjeo#egictUGrOe z9OyS-v(h!cb#;+Mx$ve_>6+i#y7U{q#Y#8w8&{#c=~TLr-;hM9aqtEy-N%pFwzjV3+Ft4>n;QVy=1UUSoG$nO#opWW+>#{6 znSbS?W+MSD;?1v!%-%_&AQ2)(LL@K(gjv)yi(*0DO`^J}nE^5XeJs3&eUClR<@ICe zg%-8z242|pibzY3%zTbH2wK(aW?TQSarN>z`rtUa*Uxc3H;W1<>gck$;eC&Et+};z z={CerO4r=h)}`GLLn&ReTU(cY!;i0}8~F`CzTP-r^wbQPPLnOwVwsp1Bu1lwR{A62~R>OEx z%_lOewRPQVx;mVhmacoPcgNZB(*)@{G%ekAVZG}$jyILAQ`6ElueH~~%_d#{ae{Qs zY+YUaIzhVVYZ!0Z)^)o{7kv%mP20NeH|f%E_38?yMBf@Eno{7j))E`FyVUD^%5Q|Ri_Zup^sw$0v=)J>?f4zwG7sUTfH zNOtS>_NH~9-SAU|rrp+N+wB3rRnR!QsJ*S-HeLK!LAsIM@M{GfQ`p|{YlZGQ_)${2 zw40|-c5gdtw|yOGH&37J>LPto_0n&iKH1h~dqeu9_RUU{ZC(0pXM6MX$+j;2wzIu? z`ea*|e#3NAjblvSNpiZW_Koe$(*~^P z27{L7uwO{Kd|Wbf;;zagkgy3ykslDbqc z{e~a;G}jlu@{un6hN!NtF8zkAF0Di4H-vSmUiuATUEO-=H~i2?^+tX}T$k$Qc@lA5 z-FkVRL|&K10!QabFeN*un@V?8__i;=lt`ET4NOUQ9q2bQC75p7?elB5?L0}Q3!+CSCe1VoEsORJuG*I#beKU;2$q$>~fZRYDDQWAn zzmX|9ohfPS(r+M}bv^j|lIDF9Oo`Tk&u%k!i&CGGX)d6H1c z=}<{qm#-&Dm7GqMv~}6vh?QWvXN5%b7GWivZYo{&w+JiYbW`cF zzeQLHr<+Qbegjt0^f9m!>C$hYoV&X0Z^TMYU?p8$`i)r039O{6OTQ5-If0dQb?G-^ zC75p7^&7AfedgoyTZENxx~X*Ow+JiYbW`clZ;q98*8yCKbm=$eO4_@t;^@PhklFj5>7YO zzTrHn(7WKh2B(|uoNl^fx@mhI;J1x<$ra%xoNlUm@%*OTyJ#KYw~cs-e(9d*5--_^ zmsF7J%loKR{nx)AbGoV40sT#>Hc`Fs+eW;kf?Qwf?VU?F-Bk6`ZxLR?>88@9-y*z( z(@mvIzj*>?^S2zFZn|^2>3&6c38$M%7w=0j-LzdV`rAgl1k+8s_lLFHulIFMH`O{s zej{J9kuSNxmo%?m@+BMjk_&uESC@VxUvhyj>FT1t>F1>A^WaOG_Z>uG>N=y}z?XD& zah}}Bmt5dWy1F<|Zsbca-L$$#7EvM!uvbZU(ya8~Ku&xEbi`{$xHTUsAcEFS^b98Tpcpe90B@ zC7ShxddZhu5nrO5Q0nqL8Sy2W_C;MjzeRk>LB3=oUvfo!$w9tkBVTewe2E5raUJ;l z7V#wq`I3!%$rbS>2ZChxjeN-!@g)cOl8t=H74ap<+HLbO`I0N*OAhiSnz(@bZ^V}z zPhH*dUhX^1bIICmTLh%Y(TZu>gWZxLTo z2{o?E_mdG{QVBJ#%kyN!msCQH>+<<6;!8N@Py5F6WW<+n&fmTodFZmKq{OhhS&y(a!u81$Ggc`4x=gBCx zq!Maem+wm=zN8XrT$g@}_>yDow(HVw5nsZ&f4j2saW0AYlFF#@dfDG1zJ!ziR4@G& z@g)^f%wotlS{hq5!Y^; zF8Pvy=#plCLv)FLJ`KN(D7xfWyY2PDZ^NTY+UvmcB>9rz*(FWgimCB>;kV)8C2d{y zH}WOJ(@WaA+F!31ej97p=G*7K3aW8k_-%Y7=gA7Hab5Z?;!7&2#&zkph%c$Anpa)r zH2C>p)K0zodz{Luab5Z?;!7&5#&zkph%c$I8rMaC8xdb}k}uH@w79_Wgl;i9SS9H{nZ8@+Eo^PF?d`ci+gD=mi>elkeRX zR^$6dzeRjWh1Iw&{RY0IcaA#Am+a(A2KbV$F1`oofQI!2U((gZd2%OTGNSyFlYEJc z%zBgW0hLx``$oQGfG_E;1J08>`H}&?q^V23WM_WK0AJG8#d&gPe#waVl1i)b^`+mU z{F0M=$phbjg>DD8HoAYFw9oi}FiO=9lc` zOGcDmax%YUCtot6{E|wm@pWK-i};e0e2D^Xa6gOkODe6#>!sg3zodKqU4Q4g>~B$i z$+>phb?LV#zvLueq99tVZ^W0J58M;!rm_Pm(WD{s(oV^CbBa3YV5v4zGOuCB`5h3ar>+{@*DF@#QRb=@*DY*oqWlN_>xMi z@%5$OBEF>3YFw9oi};dr?Y8UEZxLToX*I6P{uc2il~&`r>~9fYax%X}0XMkLqWqGR ze2D^Xs2laSwcEB1yPv>Ml?-=h4I zlYGg}{E`vzB`5h31>E2|i};dCtMPT9-y*)`T)S<$phbjg>Dh%Y%8P2{@tTf~=~#4YU;q8)xo9HS zh2N(0CH0oBqf5V$FPYAlv~}q>@+H&xlD00-lguxf;7hve%l<~bWP&g0=~h~e?Hlt; zrt>Aub*Qu&*M;Av^CfLv_BZC2%!n_kv>LA$ewz_rQfW1=OTR^YNu|}eF8vnqC6!k5 zs;ht-zpu}TFR8Q|*F}Gu5nobiHLi>PHY2{I(rR26{cT2k$wj{8AYU>Uaq#y0-%6|T zdg-@_FR8Q|*F}Gu5nobiHLgp)MSMx6)wnMG7V#yOR^z(#Tf~=CT8-(FFPRZvQfW1= zOTR^YNu|}eF8zk_IKA)37x@we+~B?w<(FLKOB8TJ-N9>e4 zsk9o`rQagHq|$0!mwt=*l1i&_UHUEJODe6#bjg>@h%c$M8rP-YkYCdD#oBGxrQagH zzl!$w9tkMtn)7)%ZHlZxLToX*I4(zeRjWrPa7D{TA^hl~&`r^jpN2 zR9cPe(r*!8QfW1&OTJ`Ad`YF%xGwz`@gurC6!j=_0n(7mo$0LN~>{Q`Yqy1Dy_zK>9>e4sk9o`rQagHxMi@pYizBEF>3YD|}W$&C1ti}@uAxZye^ z-@7ZV#_OfuqWqFdt8rcWEy^#cv>Ml?-y*)G(rR3nev9~$i}P_5aKn8|c&>|li2`n@ zoA6wfR^#hHzeRjWrPa7D{TA^h7x@we++ZCdzT_fbqJSIfMt&n-qJSIfCOp@*Xd+u* z=9kQfFS*EaD(e1;!Ccz+g300OJ>BER9cPe(r*!8QfW1=%l;PeB^UXUgM7)1_>zl! zi2`o8Z_)cn@+Atmp>EXQ)^7Xy(r*!8a&bP60&Y-m#Ft!ax4mBaE#gZq@+AtmVZH0k z;oI*Y$d@SKhPqLIBVVF`8|p^=jeLm$Zm7GyaKF6{yf7ER>3@Y@Z(r1>74e2D^XeBW;8OS{~m+QiB zcf^-eT8-<%Z+FC(R9cPe(r*!8QfW1=OTR^YNu|}i>MGy{*Kh6AyZ7}yPv>Mk%f4d{TWRNdWzzx?o>2G80w%1F)MSMx6)wnMG7V#xx?Y8UEZxLTI z)^58l{TA^hl~&`r^jpN24Ca?8;0D)2#FtcBjn&Kik~`u{2J=f4aKn0&{x-;$DBy;= z$$4^+FHyh^btAu#FHyh^b(80}v3A?{jed*xl1i&_UHUEJO9t~x6mWxei1?DRXd;!6heOHSsO+!0?g$d@SKhU**ojeLm$Zm1jijeLm$Zm1jiZSA)2 z8~qmXC6!j=y7XJbmkj2YDByLCMegj{!o?^bv@mE@n>(X!FOV-`3qf5V$ zFS#SWq|$1vUe3q4BfexXzeE8y*tdu;sk9oemwt=*lEL{n3bALdDBy;=QGZ*z z?dw3lMSRI%eu)BZSa0OFwcB1V{TA^hl~&`r^jpN24DuxkxWPI^e92&bi2`n@o4hX> z%r8;E4Rxdb#{80#`6YM6mkj2YDBy1TC-Y10h%Xt;FFBcC zaz}hgrPbJdlKCZf#FtcBjqB2H5nnRMmnh%{ev9%;Dy_!rWq*tEOUBx5*JXc;_>!@9 z+jZIBBEF>3YD|}W$sO?}gM5hsZm@4F(c(e^!!G?L;*L{ zjrtq;5(V5)H|lR|xBYsc-y*(bFuz0rH>@{0PcpycWPZsV@g-x?M7|F6Tf~=CT8-(F zFS#SWWRNdWzzx55r+)y|28~G9i+(0+tO9uH81>8_qZ>-+$7vxJ6a6?_)@d91#wq3vEOYSJY zWRNd8$(P(we#szTqJSH&L)72Mmnh(dx{=?=mnh(dx{=>jT8-};{TA^hgM5hsZdh;R zH}WM4xN+Sl;!6hk5(V5)H}V_#l9PPN{Q`0a`Kl1i&_UHI*Z_>xMiab5Z? z;!7&6#&zkph%c$Mnpa%~+~7Kk_>xMiab5Z?;!7&6#&zkph%c$M8rP-YBEDpjFHyh^ z*Ei{JlYEH+Zm65|w@Rz=b)erOzNFG>T$g@}_>xMiab5Z?;!7&6#&zkph%c$M8q+0T z@eTr`pE(r*!8QfW1=OTR_=C6j!K0&Z~qM)@U^e2D^Xs2ll>e2D^Xs2ll>e2D^X zsGB^$&9&RUZ}eNlmrU{{3b;YN5nnRNmnh(dy2*KRk}pxf4Rw>}w@JR_B46@Ee90tV zqJSILo17;n`4R=(P}k3sYgHQON%AEMxS?+3H}WM4xS?+3w?z|~FLwGZ;!7s^5(V6_ z-sJghaz4(r({JEQy8DLrlM1*&z2Hl_y4r19U-BhS#FxxP6S*$?Tf~=4@+Atm;W|Wq zV}6MOZm1jijeLm$Zm1jijeLm$Zm1jijeLm$Zm1jeH}WM4xS?+3H}WM4xPflOmsDDf zU%&KQ#FtF+B?`DALd zDBy;=k>ALdDBy;=k>ALdDBy;=k>5BUM*%m~jr_J~BD?=y^jpN2R9cPe(r*!8GMQhZ zfE%tu0{4U!s5;>PG#Ie2D^Xs2ll>e91+=xJ!L;*L{jrtq;5(V5)H|lT9FHyh^b))`9 zzT_fb@eBwuooFL@Sm@cwfw`4R=(a2+DQkuOoe4Rs^GkuOoe4Rs^GkuSN(mpoB^ z$s}KLfiKZKjE`vFwA# z$1 zej{I^fE(&Yej{I^fE(&Y{f&Hy0&b}5erw)$$d@SK2D;!&y1M#1^Bee*<0Hy1xyhF( z;D+@^ej{Hpz?Z1r$ZzCJ6mY|OBfpU^QNRs#BfpU^QNRs#BfpU^QNRs#BfpU^QNRs# zBfpU^QNRs#-EYnN4*3!V+(0+tOYSud$@~VsM05P2^W>U_WV+x>q#OB-e91t5iF6~s zkuOoe4c9mF8~G9i+)y|28~G9i+)y|28~G9i+)y|28~Ks}zC`;L`Hg&u0&ZAu%x~aJj*lq6 zPCJeU!s5;>PCKJ zeu)BZs2ll>e2D^Xs2ll>e2D^Xpd0Zel~!YZ17C7{MENC^R%5#0OQak5jeLm$ZnzGS z-^iCJ;D)-9-^iCJ;D)-9-^iCJ;D)-9-^iCJ;D);Hw^e=PJq-C01>8_K@*DXQ1>8_K z@*DXQ1>8V4;!AGkmkjVF$4A7M+~i9J_!8+xej{Hpz?Voj@*DY*0lq}K=C?|X>|AHs zZM*M)FOhEKH}WL|e2H`;zmYFdzzwf6_uJaV#yXHMQNRs#BfpU^QNRs#BfpU^QNRs! zBfjJ&U!s5;>PGKN$d@SKhPsj8$d?T8CC5jUUviT#8Q@E#Ykq6yKiuR?2KW-`Mt&n- zGQgKe*ZkJKKaej`zzz2;@*DY*0lq}_Mt&n-GQgKeH}V_#5(V7&I&2YNax=d~0XNi* z{6@ZHkT2OHzT_rfGRT)~5npnXFB#-Zwumpe$(JbLhU=U7t%wna#FtcBjq9SnZ4qDckS`ez`r8)qB@g+M@z8G(U-GPJNWKpATf~=CTFtAj0&Z}f zIbYJg9&~qgT|B>S5nobiHLi>2w=LpJDy_zK>9>e4dB~S2;D+mK{jJ%LAMzy%xS?*+ z-yZTM3b>(e(%&BPB?`EqZqnZ#@+Atmfv)o<-RpPlwqFnQTf~<<B={?6j%r8;E4Rw?A0i#T|j z8_K z@*DY*Nxo!T#KHUb9r7iUe90E^B@g)$1>A5QBEOL@QNRs!BfjKW`)lXPgMN$nl81cB zBww;c^Kl;XC6j!~7V#wy`I1S#WQ+KchkVH-U$RB>aUSv|lYGe*@g)!W5(V7wIy1j@ z?+@fl6mUb`sK1dfQNRs#BfpU^QNRs!BfjKee#szZw$s}L0MSRIazGRXw*`oP45BZWwzGRE$<2>X`6mY}q%>34U4@16Wk}uh!{E~-! z$s}L0Me}hU@+Fge$rkY?5A#bV`I0T-OCIKzO!6h0^CjK;B>9p_zGRE$<2>X`6mWy< zY!L_VpQFf^DBy;=cAo5BzvN3M`I2oB2k+NQzC-~xtT*x-`I1S#WQ*qGJmgCz`I2oV zS_JE$-L`Wd`I0T-OCItilYGe*@g)!Wl1aW~i};d(ebe<$%qJSIfMt&n- zqJSIdMtsRbzGRXw*%omStgr5_c0G_U*%omS=xVoJm)`>-zT_caGRc>0&X=r@4jo(2 zZp2GA$4i>Bq)R60k_~jp>UE8BNtYaN!C`(lMTMy7U`yl0CsmehQ~CUl1qR6P)Cya2nU; zNpb-O@B587$xWPOPjC{|OTQ5(*%O>Zy7U`yl0Csmq)WdMC)pF6M7s1Fagsg3Nu*1^ z5hvLboJ3(Hct>&*C)pF6M7s1Fagu!j2Jc_L#7UHAgH!4P3<6yqCyA5n3or4jC-FJwS>9DB>hHagsg3NmMWU8*!37!AYb`zY!e6q-N%jOMQRof*Mx10%a1!a#Z^TLV1SgR${YIQ*PjC|H(r?5` z_5>%9F8dpCl0Csmq)WdMC)pF6M7s1FagrT4$$E*@cDZ@agsg3 zNu*1^5hvLfVDRGO?mEzK#7XuQVDX~cygv{pxrvkP2~P4;IE|ejh?DFIPV!SYjp-66 z*%O>Zy7U|4O7;XNkuLp4oMd;Lq}z`fS8|gl*_|ip>Jliq36$&(l(co}Hv%R53b1&& zew)4^P;wI}*&Qfp*Gs=Ku4GSu5`~vUuvUuV1FY~qVGqMF8dpa61^%n-R6CV zaV0mA61@^M-R|{3zY!_XtB**R{f$hC9`OR*3a7FA8JQ9tWg}hsjZleNcBHF)@OtsS zM7O+1mwsbhiL4Xp(r=_nj)*GRNR=qh#?R|VM3q!H&FlIq&xX40x1KL5oW^y5l^jW2 zi53rjQ=Sd$b-(rQ4;4=1^@1xolDHCW3f`9}&xZ9zej`|-JR9mpep~&@*MWXZ#^Gok z;J1fyB}YV-R5*>-3$o;JvZUFMH^!AH&j#z8#Fc0r(BG72L*2-4WJ{E1L*1mmZHy~X zo(*-~Z_WDy;S%N9P&evtq)U`%L*2-4q)Q&sCC3V|csWlt?>meuQJxL!jrtqoN|a|q z-Kf72FHxQibR92Q7v0w%yEoD$inF0?a-7^qmpr6P4yQ}Hw+E(`Jj6?m2rt=)mpsHv z4#!KHSj9%XqKl}+QiY;O@> zvJo#)oDJ4D!b>*dB@gkEBf?86o5t3Gc*zmrC6!I%x;#!sc*#b*L~%A;-{?3=yyPKX zayVYn^&9aL#o4glsJ{^}QJf8RqyEOU62;k2H#$x-tweD)(2ekt%BJz_jDCyolFFtr zUE(E&<0b9uf&Gnm$pO5i**A%oJj6?m2rt=)mpsHvjtDQ=h?hLXOO6OHscahGH~KBY zODdbjb?LVVFR5%A*QMVgyri;eT$g@xyrg^m5-(Al4SXEoC6!HM^%5^RBD`cHUZOY~ z)*HPpAztzjFF7K-q_Syz9oXL@yri;eT$is)fR{AyJH$&AXT$Z4`Ww?q6lX)-sJ{^} zd5D)B5ni$pFHxKg>W%P{jd;mJyyS@RlFFvB>w$R55#c2p@sfvl$r0ftl}+RI@;n*g zC6!I%y7XIwmsB>5>(Xx#UQ*dKu1mi~cu8f`xGwz`;U$$#w$R55#c43P2;-sTZETvoQCrdFF7K-q_SzeUij^d@RACrab5WB zjPR05r!igPB`5Hb=6#2F$wR#4jPR05r}28x-_8gx**Fd7AzpGucuA$xc)jRvr{g8f z`$NUkxGwtJ8Q~=rPvg4q+Zo{{l~3ck=x=9)msCED>(Xx#UQz)yu1mi~cu57+yyyxx zLw`H#i`%>XtrBWn7ya#w@RCZXab5Z?nT8_BVKYw=_M6Z#)1ab5b&<4d~N8Tb;d z1N&PPUs7Q;UN8L?@g)^jl^Cdl;tFmfbmUeTzq$}(2q>z1fw}>vOs2VGmbjj&- zNw-|RigsC=ErLrbsm66_wmL4neW(UpqUEL894_ga0&t0RX|@P1siYcT2bwK{ODd_x zb!oN;E~%s%*QMDaxTKP5T$gT(;F3zJFsquQ*+#<51VrpEMev8PGim7p3`Yj?$DyGJD={E$I zG~bkfEYZHvZ&7eb#ngDc^jk!hR7{QQ(r+M3nmz_uvXX7!w}>pMm>R2>WXTzkB|FFx z{mhtti^!6SsquR0w}>pMm>Som-y*W4VrpEMev8PGim7p3`pwCb?we`^muTPUw}>pM zm>RE_ev8PGim7p3`VC}B({GrAvyyG#w}>pMm>R2>WXXx(l5V{`PLeD+qu`Q?squR0 zHz!NF=Le7_iVL9MBC@1nYP??hEh0-Qrp9&Yw}>pMm>Som-y*W4VrpEMev8PGim7p3 z`0a|wl8UKuUHI*a$dZbwFcVeIw&A`xS<=-7S)ybc>iRDOy1IHF_Imv)*@n9Q%eSts2L-KU z8|Z>8>FVn5yk7dv$&%(5-h*U`l5JS;deVN|ZzM}Lk|h_&lI}XtZzM}DkR@GR`i*4C z1+t{6OR_}CHe6pPxw^Xa8_ALjWJy<-ej{0Ofh_6j(r*kdxj>e5b?G+-ms}uAy1M#1 z^Bc*M3uH-Gm;H@o$px~ctIPgIvg86;($%Hkm|Sv2WXVCYWFuK}fh=j(i{z4HV{*v_ zvZSj^zcIPw0$I}4rQb-FTp&xjy7U{9OD>QlU0wQ($t9PQCEY%R!8qDC_BTgM+Pd@` z*^&!vNp~ISH?k#{vnB0%={F{qTn?8s-^*1_jor_fTyg;}X|4m|5=GmfzX2}k>e6q7 zOD@1AU0wQ(gK;jvC0$+m?cjM5a7kB}e&b-A3vfwSSAXZ%1N{cLq^nE65iYp^mvnXM zHzt={fJ?f%^cx4`T!2fux;#%3F1Y}gGXRF zegj?7T?hJ&$t4%)lCCcO#^jODH^ib6xf~@FiVc`i*?a1-_)KOTUpXxgx&gKyr!R_waiF_>ykD z^cx4`T;NNZx)_Y3dg(XtC0$+mjmae!_>!(J{YJjz0$axEvx#WuY zl7oDSqHS<~0AJFrmwqE(a)B@D>e6rIOD^ywU0wD!4#v5_mvnXMHx9%7JMjMdUkt{PF8iDFCEfD_`4UCjuwLyzP%r()!8jNAlJ5G_Z%i(^BEIAxU!rIm ztONLxZoTvy`I0N*OAaKL9E!GKz1o3b-{?0cmt5dWy6Zr{kuSNxmo#;eT%vWL-@uo2 zb=lvTTylXg>FTn-aWKvWzND*5zcIPw0$gw<8Jjua01AIwWmwqE( zGQgK~b=lvTTr$9ybam-B4#pYaOS-!B8!J(<}IhkCdXdCE8d`ach_&U&U5npnWFHy7&>(vef>wx~I zXdCJ#=gE`FB|G_&5%DD_lS>qB!+O`1^|s&0mnhnXx{=?QT%u?j>S_mqdg(XvB_rZX zP7KC56m7$LBfnuVj&$j_h%Y%Y8ArPGTf~=~n2dAmz-+$xgmxM10AK$vB6iZE!tAe95_X+tz`6$%y!p6O(aNFVBiLz~|8}+xf+rDq~Tf~=CQjP1&OyN7ots7V#w~CgVt#ev9~$bM3ZYXY^admz;|xGF|c| zBjQWWl~v=qJWob^$%)B0hvIE;Jw$xTiOD$9rQagHCUS$Zwd8bL`|xM#Ps?T8*y*{TA^hCnn>l zUivNKOHNG2kuLof@g*nu5(V5~-y*)`Tr`obFZq%Y@g*noOB8U!dLzHB-S&Fvw}>w} z*KWHm{TA^hC;1Wu+;ANtzmYH5$(M|XFR8Q|UkCaP`6cTu($|x8&qWitF8vnqB_}51 zXk0n{7V#w~`4R=(VBaFXxpv!i;kOy_CFi1vTo-X)e@gyPw3=641>E@k zcSd|krPa7D{TA^hl~&`r^jpN2R9cPe(r*!8a*;1lzzx?o>2DYL5(Sb{H+erteDT8-<{ZxLToX*I4(zeRjWrPY`&`I3prINf!?`^kfR$&B(# zF7hS%p*ya#h%dRwmmK6vW|UuYkuT8?I9YGxH}WO=VI6fNzpdT&>w$iY_>xMiab5Z? z$}g$38rP-YBEF>3YFw9oi};d@e2G9j>|4Z_R9cPIOTJ`Ad`YF%xGwz`@gzT8-<{ZxLToX*I4(zeRjWrPa7D{RX~dy*2pydzebAab5Z?;!7&6 z#&zkph%c$M8q+0TG9$jE(rR3n=gEjKsk9o`rQagHq|$0!mwt=*l1i&_UHUD`FS*E< z9OO%8lwVS5HC`|M7V#yOR^z(#Tf~=CT8-<{ZxLToX*I4(zeRk>MZV-9Uos=Uq|$1v zUh*X~;!7&6#&zkph%dRwmmK6vX2h3NT8-CBzeV{a7x|Kde96RgoaS=?`I3Wt$&B(# zDy_!Xfqskll1i&_UHUEJODe6#b?LW=FS*E<9OO%8#Ft#;OAh9j%!n_!$d?@COJ>BE zR9cO#FZq%g@gUv%rBV{Us7o`z7F(T#FtcBjqB2H5nobiHLgp)MSRIczT_ZZGNb&Gi+ssJzGPxP zPWL*)_wIvy$&C1tN~^K;C0{b5{E|wmab5Z?$}hRdmnh%{ev9~$N~`gD+210*%wn$#FtcBjqAd1cf^-mxMiab5JcJK{?! zt;TiH-|mPnsk9o`h2QRoFR8Q|*M;Bih%c$M8rOy2?uaj`v>Mli-|mPnsk9o`rQagH zq|$0!mwt=*l1i(2)m6Za-zV>gFR8Q|*TwgMJK{?!t;Tifw}>yPv>Ml?-y*)G(rR3n zev9VgR9cPe(r;0INu|}eF8vnqC6!j=y7XJbmsDDf>(Xx#Us7o`u1mi~e92&bi2`om zw}>yPv>L0Ie90a0C4+p)NxtNc_>w`s#f=5(V6_-pFrjw|#x-w}>wp z%r8;E4eL$vf-0@X>!sf!zGN`JL;*LbH{weM^Gifw_O9t~x6mUab{UYl9`!D$t1>8_K`Tg5qe#uF`#f=5(V6F9U{LmzeE8y)Q$Yc{1OG+P&e}1 zqKT{zaX!u+@g;-#B?`D#f=5(V6_ z-pFs{OHT47cf^+r=9iqzFS#SWWRNdWzzxPCJeU!s5; z>PCKBG?CpWIUnba_>w`sYWH7%(0XM$BPsEoD@+Bwvk|*Lz zDy_!$jeN-y@g;-#B?`FVIz)bBeu)BZsGIn$(rSDi;I}8@ODe6#b>X)s;!7&6#&yx( zo`^50v>Mk%e|sXnq|$0!7te1`#FtcBjqB2H5nobiHLtn~xWRQ6@gMl?-y*)G(rR3nev9~$$@~%p+;Dx9{x+FkqJSIfCjG6_YJ45&w}>y9YqwpOev9~$ z$@w@6xWPI^e92t9?e)@c5nnRNmnh(d^(N=Zxo9G*mwd?+@gBwwO{8`c~7jeN;PzT}DclDX1qY#qp#JP}_q$(JbLhU*adjeLm$Zm1jijeLm$ zZm1jijeLm$Zm1jijeLm$Zm65QFPWT=qktReMtsR6U!s5;>L%acCixNt+)y|28~G9i z+)y{kd!6J<6mUb`sK1dfQNRs#BfpU^QNRs#BfpU^QNRs#BfpU^QNRs#BfpU^QNRs# zBfpU^QNRs!BfeykFHyh^btAu#FHyh^btAu#FHyh^btAu#FHyh^btAu#FHyh^btAu# zFHyh^btAu#FHyh^btAu#FHyh^btAu#FHyh^btAu#FHyh^bR)i`(rWA+MZV;T@=GT9 z5(V6_-pFs{OB8TJ-N0{4U!s5;>PCJeU!s5;>PCJeU!s5;>PCJeU!s5;>PCJeU!s5;>PCJeUviNzc_O}~ z(rV0a^6mWxei1?C9tFd~?mpl<)GRc=H;D+@^ej{I^fE(&Yej{I^fE(&Y zej{I^fE(&Yej{I^fE(&Yej{I^fE(&Yej{I^fE(yWe90tVqJSIfM$d2LOB8TJ-Kf8j zFS*E&j}ceHG}oD7~bz zYFw9Yi|CTds&QSqEuu>*tHyQRZAvTn2!1tFSv9WfZj)~0Hqs@Ex3SAXx{=#B9Y^st z)QwJ)q)QZUL*1ymkuFiZ4Ry_J_3iuXcB`x!+qcKQYS-LG^OK!3y3b(=PMr_GVwnX7J)J?kEO}0egHq=eJ+fBAa;WpGwy4y{* zMBz5njk+7z5{27PH*y=<5{27P*WA|anq*59ZbRLuyD_^&;WpHbx*ORNh1)ALcDBOm+k>ALcDBOm+k>ALcDBOm+k>ALcDBOm+k>ALc zDBOm+k>ALcDBOm+k>ALcDBOm+k>ALcDBK3R5nFPTEm61)b(5#JN~$p*gDp8fqU@5J zY>C2cSa0MvvLyp-iRz8~Mz%!ZHmukEw(dfW(=XW)h1*cq{npjR)0@I=sOx^~>gwg$Q-F9924cR4KU7jbwmYg48OS-z+ZLgPp!)%jf9fi2NGM1CV%GQgHd z*ZW(yUiuAeiFCccb#>`CuqEdQ*pjX;{RXx~x>0{4TQb0wNOx8E*>CGE-?*=nEg4`- zq#N}&vLyp-iFDm>-FoRauqD!6N^h?N*^&XaM7rMJn)Q+`QMe6!9L>hL$(9VTC92o` z)~%O*16v|p_ghz&egj)_enf1^&Fm6|+hBbow&W&TGQgIo-pFrcO9t2y=|+AdTQb0w zNH_8u*%F1@aD5}cku4cuOH^;k#>k*(D0M@p`w2F1eXqGLT)O%>U^5jdaN%U9v@V z$xXUskS^Jx?2<~VvA#*VWQ%6wR8o!WqQ7m?Y@AA}ab3JG*&@26l4@KRe%m6tq>^e} z7k=9!x}=h7To?Uqi|CSP?Y8UEZxLPctlf59Jil#Dmo)F|l~nVpt8g3KA3&F^Zuj-` zZza{ZF5XXWPM6fb($Ur3)phaxZ3A7>tygzf*QMV;mo#-rmnhtZ>+AiktBd!O3b&!I z_qVRD{?6Bdegj_8)y4Y~h1;-R?{8gQ_)Xz9&;?)8)rH>_ZbMz~Z(UvOwyiJuk`1$Q zy1ICNQ@9Q5_48y`mwqE(vSBt(SC@VxU$S8~PE(hBiNbBT4w2u;mnhtZx{=?=mnhtZ zx_+MQt^@r>zGOpoNmrMCBVV$CFX`&iZ{$lh@FiVc`i*?ahS@k>UHXlD$%gEbt}gvX zzGOpoNmrMCBVV#D;^5_bKvS1|iNbAg{bDvwSC{>be95+mgP>mh`*!~&U$S8~PPbnA zjeN98=WVaT{6j+Y!P4bFuPzaS zaVGha4SY%S{!6}Ok}ui7mvnX6-^iD2;7hu?>~G{tHt;1~UG_KfB^&sXrY`xCNxozQ zU((g(d6Im|2EL@LtG~1RI{A_fd`VZA=SlJ<8~Bp0F3*$XOE&N&U0wD!@+BMilCCb# zljKV_@FiVc`i*?a2EL@LOTUpX*}#`{b?G^Ht;3QddZh4+y?z^ z5eGrN`uELmfblN zkuTX6aS-UzZ{$n1MH~dW^c(q-4SY#=ec9j0mu%omy1Mim`H~HMNmrMCBVV$CFX`&i zZ{$lh=S#ZxGx8;qe8~pBq**Wdl1aW~17FhB<$02P$%gcjuCD&h{6@ZHLwZS9mwqE( zvVkw@>e6rIOLp)jU0wQ(e8~>Jq^nE6kuTZ7mvnXMH}WMr_>!(J{YJiIcfLg1-1$7u z@Diolc)QpgFKNjtkwZx}cJ(s5WOurxD@(I6x@32_q${gE@M`gHatB+|+B2;1UB_qW`?FU%JwT)9w#^ z>E08vM7nUAf^Asus_@M>_R_^kQo%OV4Nj8h2gwoz+fY|K@P56_Em5!yb^Ro{s&8Bm zYqwurpe6lGN_Nb|>FUyLuPRvA?B7S*am(}xDwS%zmY51 z!Id=clgur-$(8KjO1irA8@ZAlTuE1#ej``1gDdIk(r@HSc5o$KUHXk&$qufht4qI; zE7`%7bam-BawR*slBO=XlABz~4z8rDi$^yF+rV#&GX<335QFUyN>e6rIN_KE1 zU0wQ(T*(fuq^nE6kt^B3m2`FKH*zIAxRS0e{YI{22UpV7rQgVv?BGhey7U{lk{w)0 zSC@VxSF(dE>FVn5%x~mMc5o$4U2-Kixsn}RNmrMCBUiG6E9vUeZ{$jLa3x(``i)%4 z4z8rDOTUpT*};``b?G;9B|Es1t}gvXu4D&S($%Hk$d&BiO1irA8@ZAlTuE0~e`kIp zSF(dEY3h^c%U79b8FQmwqExvV$w>>e6rIN_KE1U0wQ(T*(2hq^nE6 zkt;dCm2`FKH*zHhxRS0e{YI|j09Vr0rQgVv9L|;0@Q22GBZ4J2!IHzllBRB@)R>P+ zmK;u&v~}q>q9uo;C2d{$?ZMaX18hle-zufX*8!iq4`)l-_0n&IOAd!idR(7Ufao{U zB?ssdty|;$WTn)+u7iSY{Jru4x}>WMzbV*;y1L`N{l2DHGTbE`dTyjKk$ws*3AzX3*F6pi> z?MArd09?}4C0z0lE;$@7>8>x~l811~;c!V?m(7iE$q~UN6;WeNh;Ydf!6g+@+&!e!6g+@+&!OxTLGA>&A8IH^3!bUG_J^ zB?sV==JiXs}zjl5V~1 zZ-h$@z$M*!={Le92jG%!z4RO5k^^u_SC@VxTyg*|Y3dR#QK}91&0m&ub?G<4B?sV= zt}gvXxa0s_($%Hk2$viVmsEFdJP)niHop-rIUFu&>$1NQE;#^~G=0ILI1k~H18_-K zmwqE$asV#r>e6q7OAf##U0wQ(aLECOL1eX{9x*Oz`HT%zA$M!NJH;S&9>G18^q2$yJTcce?d5iZe`Thr}b z4;4{k*8|}aP4hI}-o8~tjqBoliKZ5sZns|jo$KQLq^8tGy6kTc-cM=@RisP55iSwO z5b5$fNw`Gcmm^*Go9+gHOHRNg-Rr^qCS80FIHTy2im7?I9;6GnL}}R3I=J7Yi|+wS zRZesPmq-`yOU@N%@$y}|xxRo)q)Wdo+#t|(ze$&V!%&=Vz3w;Z(r<-tz59J=2V5du z_BX&K&HE0*OQehUlV=2%>zjMab5b&`I7ea!2U+QdlCG{lzpZo|^keWPU0wD!hL@ZXUs6#uc0Dk> z!)!{?6;A-y*)GqH0{1=gEjKsi+#)rQagHq@rqEmwp3Z(p_Kr zjeN=Jd`XkT+t+Sez2r;Ih%c$A8rP-YBEF=eYFwB7&H0kr1~yd`U&sxGwz$zNC5n1z)1|rQagHq@rr9Uh*X;_>ykD z^c(q-GvZ4ss>bW3-y*)GqH0{1egj|9yq|$D(OXXX4dEqSUHXlD$r;f*|-1g z)4%)euk?EOhfn|E@BZO;-~aZ%ee;WN{{DyWfAjs1-~W&Ae)r8U|LZ?~^X-p6{_y?( z`42y?|ND>M{HH(v&wuu>|MZ(*>bIPj_o%5vUW(rJ*{6wmA@J2#(bDy!t#sY`(zQ>4 zZC!tLBVD(?banIn{3)fatF3$4YU#T56{BsR0^7RYYNhMem#%#ZZ0ox9HTB6qO-Og$ zM1KE?rmgEoTj{#>rK=qXblv*Wb?Zxandkj_z12$BtuI~s6xdw{9BrlR)|ak!;Qe~n zZrgQ+qpfr!zpdSNUHZ+Bw(WJG-+)f5-pFq_+G>62H$U38>!sg-PU~AhmTu&?wcD;szxmO&y$s$TldkGAdgrQd)~tKP_OK&MqN{pLs8ZoN3#N|%1~qitK4egitKb%^}7cH6H9 zo+llhZr4k{0iD)3lIT1MbXx1n^Q5EG?Rt5h1UjvHBfqWPw)F)%E#1g(YqwpOesgrX zy$l_rjycdj!t*$UAyh;K)*RU-PWbwfKF>2BEJEh);iE{j!w7hrQeXt zr!hT|-+)f5Uib~UeC>MaH=xt1H}c!sZMzC$hGPPcX8H|Fwb9dyTge;w9tzxtTDeA12lhOv)Y2l~y?>GnFnZx7IEjdhFs26S5W z(r=DVx9g?ffKIF4$ZtTWHQk(kb9B00FZ~8|TJ=VLTf1%78PI9zM*R)wwAO)sb9B19 z4nU`+%l_u*bX%8x13ImBi2R0VKGjRVIXd00mwp2}t#OBu-!S)4_0n&SPPgl&-+)f5 z-pFr2r?&^_v~-j6B%}GH%k!k8)9rPj-+)f5-pFr2r&TZg=IC^{UZB&`rQaN#ZtK!- zK&Q11k>4=)QT5Vqj!w7hrQb03QDZ)2cV}8|FT0ed#wxr@Qq6ot7^B=IC@=mwv7w$Zx7IE=|+BAyKU=$Xg=vi z=gGC(uFK~)pwnwrzRqiGK&Q11^c&FWt}dV7$d?=uU$T)edB~R_ny-7Et=;zZrQagH zWLvxKy7>NvXufv6^c(q-D@ycF1ku0$hi`xQ>ra3A_uu~NyC2#Z(Z_|)tRD)j zvtQ0|Pzg%+)UvN*Kr+;&J zEk=;p7nm{Wx~HYYN!G6> z$-aNjR<(Z5maN~iCHwx>Bw4?jB_6$@=>`$-aNjmaN~iCF}QW$-aNj{2{drOWVQT(V2)U6)~G z&4)gd;eK0hHr|${%kWxU)g~^(TX9uOm-$=q?%L92cqy)G6PMwgxT>Yg{GIqqwXbdV z-+cG&5BibVFFuX?Za=VoRCM`k%j20>KTfv$XI(yDePWd^ww8xp>Dtz|b#VvfsaLvo z2W{(Ob9wBQu5E5t7w6s&o_nQh=iauiE(6~;+(dEkZR_GLx`D`6y>=IE>*BD&qpx)B zu+rAWeRKnn{c-u(x2=mC>4w9vbnQmk*2Q^c1CcG=$ZsIBKQ<8A(*2^}UT-5mzoPu5 z28jJH_KH%Q^8Kg3{PDZ*)*b%SU;gd4fAiy~zxwvqzy240{N3Mt`wzeV@n5!Y_!>6m z7vQ$zz^u1wb^-QY^Germ_|o+gvvlnOZ0q_BU%KARrE53*wyxjsrR!&A>DmpytBXUk zbiJKR*KYW2UBBT=*KhdJ)ed|<*|l~3hA&-zIF+v5@Y}k6!UBA@UoMlKr6H94TqnOTPgr(RYo= zZ$wIVOna1WMTL6*kvcGv`NqZf5oW%!i03xrKe)GtZZoP~wQCuUhhsbY?EZGrR zqIHP;#>f)IHL~8wZ)>-Ged#xkENQPV`x_!l^d&s%ZzMsKV1#w>$dY!w^czu-;V4L3 zmwqD)GMoiz>(Xz8L59O1ZC(0}G{|roq^nCDL${AG+<_3}K4 z$P#^Ejn0#dEZGrRBHifuZSA&QXNWA3Zsa#cmWVI+`_A;plCIwvS)v3Z>PCKByY1_M z=eOyRCCz%TwcD->zfGU^*w$r#d*HX}(;nNp^cx~ebUh?~yVh>|I>2w!r#-gorQZ-) zBJd#b+qHJv>&5fi^vIHSz3`h7jBx#WWJy~W=Sd|PQ8#%%d9B@kT?Zu?Q8)41wRYQe z={KMD*j)!kmMFo9^=b#+{!Vsb+T*4KBkCs4ZxH4K0-QZG?uHSm4>z9IbgG)iWe(RO4UkcIH4i#y1}hix_;}GuHSm48$4Rf`tbg8OP4PFmVAnpF8zj2v8p%n+uCifmwrn=#j0NV z4WD9FZ{)YN+g>mImVAm;z4RMC#ZJY=zuz*YOTXb$taKy4;Zy89@hMiik>BtsR=V_C z@+ns9K)>Nrtm=*YhEK7omwxkK_xFxavp&4rb%sx|syFf*KEBtsR`t?v$){M=OTXb$?7WjtvC^gA@F`Zhk>BtsR+u~cTk^NZ`WrsQ zs$TZD>z3gxJ z6gw3cpY$PoidDTlPbQyYRWJR9PqC^u^4r>NyZ_=-taPLPhUpPga}w>5P`Z)d)^2;f z^jq>NcGib?*QMY5m-$`4;Zv;EfqwI!=C^g}H++iK`bK`kr&!fXzxj{z+x60K_!K+u zBtsR`t?v$*0&k z@F`Zh>~G1ZSn1Ml_!O&ki2R06v8tDTOFqS_UiuB6VpZ=K{r38*`sXC4Kl!Ua`Sbtu z%`Z0v?RX1Qevesd_1~}lidVT)?kLIniBYoVsIIIZ7$xh5lB~TDY047a(@!bvd@EV& zUtL-K-OFu7)%tN!vSz2Qte+Mo>u!>)off;YZYIh4VNtSXrmn1?6(#GvOVKsZbeW$JyRvi{4v5Vpr=KGx)}UpPA#TU|82Qy^sz?m) zdWwSZt|wjVdR<)*v_D5o{B#D=I=Cl)j+pq>|9}1ZV_W+=^X?Z%OnmK_-VZb26Y6&2 z2~~rpf<9kl`0I&}52%t2PSXX3yDU!Acs}jj-3J~|wFrJ+QMGnoY0Bd1RI)ft-~M#k zmDS(*BH%QQhtsYsPSbog)glCao{y$l1iz<9HaJZe67GwDKCeM$?;m@M2zObWrZvYb zk@fdLVw`cB))=!y*6$|^A@|2MO)*PkaheuEPTAlzJ;(>27-^^(TY<|82DdH4L_^62 z&#c9QyDVI$31;uFZK2>Ui)U61FiT|d%&MeuZdu^6`GIFv1&u@2(cs>#rZ{k41iH-0 z;I1rOCUTtBe#vF8FTwr*0Z!Y2H@_QGs`S8Mwe-F?Nf(x9N|kiY@@-vse#4tz>6+); zx_)HWI-s>)-del5?5!Jn>*c+*t*dM8_0rt%=2z=rwr}gAyKZ>%D_!$_TNlRH;A_9; zFK@4HT{vF@eqDEXe{JjXL7G3p8Qx&qy70d4`m8td8-IkO!F1G({Kg;QXkZw1Bfqi9 zYLF9kt;sgm_vDXoGzf>f)@9qe^c#PKGrY~Vb?G<$2xoYoZR^r+Y_uc#5zfg@yRp*_ z@3ifD={L*`)@P2@U4Q?2xUCDn?d-K9`Vr2_xxqVsgfo0@aJydgx1B%289q0-t&9G) zV{Wk4H}V^QgtPNUIK$@#ckAVkaCZI(XZYOUwl4g(^G7(t=LWZR;kTVX!Wlj{xUGx+ zwqtIvzSG(BV_O$~+c7s-x{=@3Zoi&OcFYZyZqnaQ&JEr%H(0t!e>>N1d%f&$J~z0% zzVsXB2CLr4Z}(g>H57;y8etW-QcV*UB4Gf*U$RW)egMd%cbl0Lh1Th|06o3;EE_3Z*!uJ_LKN`B!cUGJUJ_1-DnR`2{nT=YK=O#Rn?`pqvjxE=?vd|+yg5&oYa z=C}Qw!@L3mV3-edHT~o=G0YA=OD|?%nA7>JrV$mEWeNKXc>Q@gYZh?p;l~*45hU;9X6+-qoaQU9GK)2K9l5JLx73N?}>pH$2=)_lphc zwG01yOx^Aehu6H2mx}l`&9jL48hLWxuN+ayuP+eU&lytoVN!Jb4)y12v z4}Ph+oQ0_OaGiZ~Lv0`YQd0q1FHgtadfiac^%I}g!41{bbwf$lPkhpKL-ll(hGj;T zuAlg%>nFahuAlg%>nA?xCVo>I7VCxIDnRS)eLEPJ_Q5YT6`&R9(r^4ybKy%(cYWzM zeyOPdt)O1`ZR3}k3eXC4;Ws_-*^|(A;Y&?-9pJZ(UurIVsp;y%ZyUeVT=-Jc)a93& zjbCame5vW`!fzYD)Li&d)76FFHh!tO@TI1!i~hFpOU;EZHCTPN z(5RdAH;pFt``N}XH5b0rbnB(x_@$=C8NcsieyQ0u_BVW~>DEiX@k`BxFEveFeyQ2` zrKTntzrPOrQnT?(O^q}Tbm=$DuHI^e6q>fRwK8c<BuzO!d-l_(Jwl@9T@>KfsqP-STKsd{*1| zS?#5mFMlPFE=`KyNa;oC&VK zj_m5vqzI1GIz%Q#aHQ&`Nf8{`t(PW6aHRg7$fO94RJ}AQf+Jt*{R5ly=E>^j$?Cpv zvRdcDuYMu851g!|>lcx9{bbeE^@~WlezKCTUqoG9KUqoFFCyv6#xEzquCD&>Lw z{}Lr#zlgfJ{^mfsei138d0jT2pE$a@e$$q&zd4Yub|BF8oA$loWF=j{X?N?@Zrl3e zWF_6D^!_^dOy+GO}ksKcH8Uqo3?bd1Mk<1la=bF-*B>O)(iGXy7U`PR$X2C z4JRwDL*zHGN2-^8!^x^!Fa3s-)g7@%8Wlpn;gBTV$Zt3#-TGo^Z``FD`3;98>G~l_ zx@$$>_8Zc*rAxozkks8b`VEI9)f@Q@ha}ZYzu}P7tQYCp(xu;UNb2g+Z#X1r9U{LW zU0e0iZ#X1%>!sgtNK&YO)ZdVit6uue z0~6cz(r-viypfpL)@6S~WTJGV{)Tkzo0*Byjr@jmZRxVVd1zvL9eAEZYNG0m&Xb5~ zQ@uP-dQ4llUc|IXmwrpqwKWoq&u>WA);dJbZ$NWZFQ4BMG*|WN?rP_Cpt-6ydVT|% zt9tqTmY}(+mwp49tKl+{-+<=c{K1KIBflYIMY{A`g63)+=r^FbsyFf*&|K9^zkM0a z{qjpqjkMEg#;!B`?o#ze?@REzOV!K%26DG~J_ETcUHT2=ZdaFn1G%epi2R1%U8-LA zE&AQ1_Kki6xqJUJzq|ZruLqtdLGDU7@*6T%Zf2}VckR^M=SgI&NEheH0dlu{J@7mU za#!^x=SgO)s9yB90dluj@3}Z_^D)R>)tmIU6XdSyh2Nr#6^*>4-$3rF-o$UrSW&(7 z8_3=6`qFP8cQuSG>2K%S?bm%{#)@Y)dhz_mj1>*j zOWv29Yqz~#yf29|R#Y$j269*RMt(!a%FT=w>8_o6+ixIurAxno-0fZu^c%=s)f@Q@ z&(r*!8qT$@Em;Ei`OHNF0SH1LG#FuC|H|ix{G9td@ z1i5?f~9fYqT$?JU-~WLOEjFDy7U{!-RAw5e92C}WJG+4B5_bJ`I4IF9b6AQPm(Vg5npnW zFWJeL)I9H?UiyuE$%y!plYGfezNF@Pzh5u;lAV0Xi1-o>=jQc5zeRk>Nxoz!Uos-T z9pN@g*nulAU}>&GUZ0 zUh*Y7`I4HJ7UzmYGgdES98 z{f6kbdqjMRCZOTIL%yVjrUmuVZ{$mAYFePn^CbC_8k_dMF8LB=13C{rBEF=8{_MU^ zzGOsvNd^76F3*z@Us6GTuFL1Qh%c$2Ki5TntJ!J6zR_>wOKNyppi94zFRAHifiC@q zWVm}qd`aa1+WL|&srhL^z4ROTk{Y1)wr=GBdcE-5jQEnu0d!rQCuhW$R1To)!f!K~ z;d56GpzFeKGvZ4s2hertw}>yP96;B_`^g#cC6xpCs;lTgzyHpNFR2_r*9AX0Bfg|^ z09_Z~17^gRR1To);{D`|_>#&2bY1!_;!7$A&~@oIB*XRI%T*4b>(Xx#Us5@Mu1mim z8LnF|&XWg{;qDpnC6xo{_0n(244=Dl08N*C$&C1t$^mp;`Yqy1DhJSY>9>e4sT@Gp zrQagHr5w%_xmyV5=95%{u}Wnl>_MOOTR^Y$wj{8AYU>g zzNB&hypp64)P^4;!7$A(Cek&BEF<@09}`Ui};d@e2Jn1 zas5Vo$wj_I(Sg*B{6@ayAYU>gzNB&heSPV-h%c!eK-cAYGU7`r2hertw}>yf)^3|F z`H~s&C6xo{y6kTeUviNzImnmHh%c!eK(Cj6i};d@e91w+WJdWVl>_MY(r*!8QaOOG z%l;PeC6xo{y7XJbmsAd*>(Xx#Us7o`u1mi~d`YF%m@fH}8Sy2RR^z(#Ta;f?X*I6P z{uc2il~&`r^jnl)QfW1=%l;PSmsDDf>(Xx#Us7o`u1mi~d`YF%xGwz`@g9>e4sk9o`rQf3blF9*eUHUEJODe6#b?LV# zzogP?T$g@}_>xMiab5Z?;!7&6#&zkph%c!~Ki8$-qWqFdt8rcWE#gZq@+AlPk{R(O z73pX7k}sJNUs7o`u1mi~d`U(6xi0+{<(E`ijqB2H5npnVFFBZBG9$jE(rUb3`Yp;Y zsk9o`rQagH1! z5npnVFFDAU%qYL4(rUb3`Yp;Ysk9o`Wq*tEODe6#b?LV#zvN3ZxLToX*I4(zeRjWjYoD}_P2;Hsk9o`h2L&W9&El}XMV{+zU0Q_ z!LBafPm(XWqx_PK`6UPWk~`u{F6NgUrPa7D`r94xC6!j= zy71c_@gIB}#}6zQY2k?_8 zCJ)~F#cZStUReP*T;IrVYqxEEnO~w`Rweb4FHyh^>y7+IzC-~x)J?v3S6Yp)1N|29 zC6!j=y7XJbmkjbHC;5^);!7&6#_OfuBEDoSn#gp?m)sFwQfW1=%l;PeC6!j=y7XJb zmyEUBuFL)w@g;+N$w|IM(awpF$(NkuOYSJYq|$199q6}+FR8Q|*QMVgzGPtXpn{ax z-y*)G(rUb3`Yqy1Dy_zJ$(QKAAi5sd-3ZxLToX*I4(zeRk>V1CKT`8fJ%LUR2wzvN_oiO}On zm;H@=$sO?}gZU*V^GoiCFR8Q|+c)NyXs}VV4(xB3Ja}s`Orp#D5(V7g+!ygBgY$6| za6{ebJjwhL1>8_qC;IoFH<@3efE(&+2LfIEKH%hh90kcny7>K@0&Y-m#FtcBja|Rw zOB6U5)yw|I{1OGhMY?=`V}6N(v?5*ljrk>a#Fq@_mnh(d`xc!inO|};zeIr*$vQB< zL;*LfH}V_vOHSsO=!eZwz4RONOY}p_NSA(Ne#ss2C6!iVej{I^A9h6b(r@HT?uaiL z%r8;E4X%fXFR8Q|Uk9EiBfg~4YFw9oi};dCt8rcSw}>yPv>Ml?-y*)G(rR3n{Vn24 zDy_zK`TQ2~C6!j=y6kTeUs7o`rc1s=FA@{KkuOoe4SW&tC6!j=_0n$jSbP&evtoR4!dzvPbil1i)b^`+k;zNFG>T$g@}_>xMiab5Z? z;!7&6#&pS-+!0?=X*I4(zeRjWrPa7D{TA^hl~&`r^jpN2R9cPe(r*!8QfW1=OTR^Y zNu|}eF8f==msDDf>(Xx#Us7o`t_#0C5nobiHLeT4JrQ40X*H%xzT}Dcl1i&_UHI*Z z_>w`sL;*K`UwX)s;!7&6#&zkph%c$M8rP-YBEF>3YF>2}aD(eN;!7&6#&zkph%c$M8rP-YBEF>3 zYFw9oi}Fh*`4R=(aD9{WWTn-3z4TkemsDDf>(Xx#Us7o`u1mi~d`YF%xGwz`@geeIsA; zMENC?e2D^XSa0(DR%ta}FZ~wrC6n`U6mY|OllPO8e2D^Xpd0ZebJ0Y;4)j~ZmsDDf z>5?ybBEF>3YFw9oi};es`8d~3zeRk>BwwO{8}3`=H}WM4xS?*;-^iCJ;D)-9-8kKqJSIfMt&n-qJSIfMt0{4 zU!s5;=tg|WBwwO{8|p@W<9r+i+)y|28~G9i+)y|2+oFl=K1sghiTIMq`8W!=VZD*x z$d@SKhPsj8$d@SKhPsj8$d@SKhPsj8$d@SKhPsj8I3Gs=H_(mvlF9iv3b>(ey7+IzC-~x)Q$W` zzC-~x)Q$W`zC-~x)Q$Yc`8W!=fo{Z?%(dHoJe+-1>8_K>Tk?1QNRs#BfpU^QNRs#Bfl-0$o7r-B~QecOy-v;;D+@^ zej{I^fE(&Yej{I^fE(&Yej{I^fE(&Yeq(-#0&b`q^|!U#em&4{5nobiHLgp)MSRI* zeu)BZunrMlGC3bd0XNi*{I+N!TL;d^c_O}~(rR3nev9~$$@~%p+;ANtzpdT&dg-@_ zFR8Q|*QMVgzNFG>T$g@}_>#GH+jZS9>e4sk9o`rQagHq|$0!mwt=*l1i&_UHUEJ zOYXJXu1mi~e929|L;*Lr9wNTvCSRg}8|o(g?IvHMfE(&2{p}`SqJSIfM*WTXB?`Eq zZsa%eB?`EqZq(m6A4dT<)Q$QZ`H}&?M3`>W-^iB?@Fl`@lk;Sy)tKKl`Yqy1G?y4Y z24A9jlk?=w`8WgfaikmhjeLm$Zg4$Be929|L;*L{jr>NwL;*L{jr>NwL;*L{jr>Nw zL;*L{jr_KD+pgc8{Vn24Zt^7xxIw)UUviT#QNRs#ljpZetFd(eUn1N-@*DY*0lq}K zk>ALdDByUoya#NH_8u`4R=(a2+DQkuOoe4Rj;Eq|$1v4}mYy&!{55 zkuMqGOQak5jeLm$ZnzGS-^iB?@Fl7@@*DY*f&3EbMt&n-GQgKeH}V_#k^#O%x{=?= zmnh(d`xg0)e8~V`qIx60kuMqGOY}3q==qI&$v}RIbR)l!FHyh^);G#8sk9oqKY%Y$ zy^-I@mkjVF(vAE^zGQ$ek#6KS@+AX&iF6~skuMqGOQak5jeLm$Zg@RJej{Hpz?Z1r z$ZzCJ6mWxjBfjJ&U!s5;>PCJeU!s5;>PG#Ie2D^Xs2ll>e2D^Xs2ll>e2D^Xs2ll> ze2D^Xs2ll>e2D^Xs2ll>e2D^Xs2ll>e8~V`qMwaNej{I^fE&~s@g<5s#QPo0$I;Kx zBfpU^QNRuBjr>NwWPmSGy^-I@mkjVF(vAGKcH8>#O}|Ba$xXgQ0XJOV$ZzCJ6mUb` z$Zv}#@^zr!BEIBayY0Gsev9~$n|z4^ZhRfKh%dRxmnh(dx{=?=mnh(dx{=?=mnh(d zx{=?=mnh(dx{=?=mnh(dx=DW%Hi7Hxf#0@>FR8Q|yM7<|ZHxGlN~>{Q_-%{$l1i&_ zUHEN__>xMiab5Z?;!7&6#&zkph%eD&s$UNZxWRQ6@g+KrQxMid0htu+_2un zZ*Lia6{dszdhtj6mUb`q`y7nOB8TJ-NPCJeU!s5; z>PCJeU!s5;>PCJeU!s5;>PCJeU!s5;>PCJeU!s5;>PCJeU!s5;>PCJeU!s5;>PCJe zU!s5;>PCJeU!s5;=tg|WL%u`-H`I;%#{7~=zGRE|l81cBBww;ce91$;WRfr0qWqGF ze2D^XxW19!$d@SKhPsj8$d@SKhPsj8$d@SKhPsj8$d@SKhPsj8$d^p=C0oRoJmgCh zaD#fI`8W^xl1aW~i{|4z0(R`eTe90tVvPJW8 z9`Yp$xZ(8>`Hg(ZBww;ce91$;WRfr07IEzZw$s}L0MSRIazC-~xydEOI zkuRC#OSVNEyzdM0CG-Dd?`(T4Nv`AkR~qdv5-?nMRb|%8d|R4^Ojt__Bw-5{1f#jz z5(k={C5FAEjD`NYqt1+WZ#-b{9g9 zBEIAxU$T)enIgXAAYY<@8`c|rzcIgLBVRH_e91w+WFucPMSRIYzGNd`GDUpJLB3=o zUou5}$w9tE0XKYZk>ALdDBy;=k>ALdY~)L(h%Y(Fmu%!qrid>&$d_#7OQxtl&OyFp zBVRH_{c#TRB^&vYDe8}NkT2QDmrPN9Nu|};x`cem6!phB$d@SK2Ji1l99%zNkS|fd z4Rs^GkuTZEmrPNAoP&JHM!sZ<_>xMi@#n_*E#gZK@+Atm!T3ge$w9tkBVRH_`6UPW zl8t=H6!9eo`I3!%$rSM=2l8z4 zkuOoe4RxdMH}WML`I0%}OAhiS3b^rl=P1AAAYY<@8|p^uN%AEd`I0&6k8_YOQNRuB zjm`temnh(dy21XW@DlJP3b>(eFuzGxyV3T$PQGML_!8;rX}d1`HYa?Eba~!=z;E-* ze97Pc%d7A1-#vc)bpQJPi~ru<-F@-+hv%pFcYpKv{`oJyc=P`KH}C)QC-eQQ``^ER z^YxqOH-CKk!~N^O`|ken`T6~u-+udi{?G63fAPy-eewBU-@jh8{+X~rR=_AG)Q z73umvQo8<+ly2~&B3-@G7Y{|cK8b5DB)9}2UA@w->pv>eeeuxa-}s?CbdUfK3rK*6 z>TPlDN>I9*cP{>s()E)`=>{j0($y>Cy8cTf-Qbrcswq(#306-BAKv{gPgc+{8CX z^#*g9>h(8By8Z@9H+X}j>u->B{SA_C@CHfO-yrGw8zkKq-yr?czVx%%!IDVV=Q8OA zbD0igd@hr&uN|cutR1C`pZSG9^VJ>Y`uB`K^9z6Gt2;`di=X+0Kl3^~zW!TS<3PWG zCDGR2i$C)}`aaNaU`eDK`3)?|w16d%Zsa$xB+{kdlB^PqFZ~9VMD<2~152WM>9>YJaWoF}8(0!;c}IQ& zOEN8BNu(S34J?UtIlsNkl3cDhe*Mjt|Mc{Hrxo|}H}CF#_w@MH-ItHQzx%_N@1Op3 z_n)SRpDgp;Ki@rk)`!<151ezfdUFqGHDn$*2lkt<^rfIbdvPk0tWPW?kgR`KNY)H6D(mmRWc~fum12AUM`iu>m#i=EBzr17>J#qG?y3D7T(Q4^3(2A-yaT#DmRZEwh_}bOKU|kRZEvS#5Gtg z7%s`uWzKM2$lm7Ji-WQUHTT00%Wa;WG<|cWeVb?dZJxbSXWQ`;)_eVzONx&n+b+>eZeJN|KyUc zp1==Z8<)D{YuEi>Phu3yIBc$ILxzoRe)>x_RjSDk#a*ncU*02<3L_D+q; z`YR<_f2AaAuhgI{0&FDfZ=lJyr#vi3ra%KG~xS%04-Ywy#jtbf8w z*0;(fd;KT8Zba!h`yluyyx8ySmll%sA8%FbKi-l(|J~Pp!b{eFyT#r3fs|zJw|jJK z{ij>9bXl4H>T2mS!bTNka{VCCWn_&i$>eHTqDErT44c*1CN9IVuf~=x3yyt-C(&g% z_Eois%g*O)cEGW(WD}Q>CKZQ!WKQLupEnOBI`+h*mOcuw!y0?+IjEs?p01kpJ zkS@%7InVwZ;K*78>PPM3pQy#9zwE6gcQT}_qFvYDcIn!ja=DmzdBT>izwWBnCl%@1 z>praO@4Iw;R*|l~@0Yrl59K3=@)CeDT>+p>3%*My-Rt)kMV-g5pF9@q|4zErPubwL zUad}l%&+baR*RdvlBLW1=I*Gh{_bMZ zk}O?zUgf;{O~Acf$x(wHL^~e&JAr)TL(q(>YceGl%43~B_x1CCV&SjVL z>t8)RzJGPsAAa-dZhrXL-@Ll}Y}xvMd-~_=H|!o3Y=AvX*Z_N2u>p2|0Df{~O}hRS zC0)0ubZsK656cl<_o#GzCX}vubXZrf$;E3gT{o$8Z7LkpZP);luDevaHWv=-x=p3) zHkGc~bXeEdmeO^fO4nw?VO=+>bbUIMt{HV$*XKj&x>MD*%eE|rb=|7c^$AhBX4PR` z-?Vtpb!3|nrE4?durB&Vni{HAXJ_r;9OLDif1O&hD!rQdvaaC987J*e@e-+X&; zSQmbqu|KGBi2R0pYt>7?`3B)|z3`i^BlCTT{Dv(;)l0ush2KwM!}Y>%x{i!`eUETh zmwv-0q1x|7e#4!_hZ(zs(vAFvJBiZe{DwP;WAkytokZ!C$h$RXD6mzhSRX;}H1`n}w>Ee)G-3;d<#eUJ~Ke^U?Q# ze#3U*gBm7ZE^&wJ<@|>ILg_|+!=1#3nfFB0FgdE1^BXUUs9|!V%bOxIZ;Gg4a-_@o zjaNm~Fgeo2dUEDn5j9MXbm=!<7E#0GNEhqLnYTsMFgent-*{a_4U;2X`i=KR)G#^H zrQdjAL=BT8U9Km2V?+&;BVGE9S4Pw@Inm{vk(qZ!)G#^HrQeWmtv0)n-;i(pFeBeu zx{=?IZ!KM}C(%EBaK1pkwRAbZA>VpbmwrROwb~6wenY^0iG1t9dU+3O<~=AiOiuj9i%>H!LaAYLq|5n@gti(cN4lKf zcoj+wlOtWuZ@deohRKmG{YFT8bx3=3-N)NdGjBtwVRBS2=Qm!5Qp4m(mww}YC^bxu zbUDBALX;XNC%U{5HS2iMagYnVd2jp8zm-{77Y!BEXnw;Xx$5P5(htc;>%}R# zbm=!gB_GzM-*8N>aftkeb8^*7zxg@&aJ}>!4$4(;T-TVzO}|7n%}@us$TjHEahOm zU@4``^8m1vqqpGp+3%_jlWCZwvVnHB63lv7TJWm(-=C;C+DK7Ti92s9Qyj^7$d}Z$q(B$z$%TB08YU;> zOTJ_wU!sP|kuLnUkS|fgd2PAK%QU4P7@x_r$1Ojq9-d(5M{ ze9ZhzSKpbJbT1#r|NPz4)7!f*zWMgu^WEpy^RJ4a)&I@K1L+ga_jiYbtdyhVUO4sMlQC*)urR(2^(mj=a;O0hkeg2fLe;-O$Pax3s`BS>SA0u5~uMXCW z^F8VMdR4N1-Y}|5zu|mOx{=?Iz@&QVH=OT{)~mm>-yNLqsouzM$U0QL^c&9iM(d^D zaK5L<7Wob5d%6%zzu|muv|joR=XW%z{%tO^nzu|muv|jz4*UR}0=X;~NoZoQ1r=Oh{7cwv3O6*f50^F7rY&2PB+s(LxU;e2nfUYzeq zmwvYYr7wT)rQC?_t2#4Q-E~+m6Wc1;tcEh zE7=wtfl1e1$zffe0;KD&q;${0|9%P>*7a9Xx;_O+*IvnCU7rG^>#wAAZ3-CFU2(-) zy8cQ^S5M&TaahsfRk}U}NY|EJ!}a3K^97E;q-#sAVO^gBRIe|& z+U`eS!@Bevj=-dw_^mF~Uyg(B;M-ofbQ8bTg?iVe-~0${cpTujh9fZ5oA|9R)O)@3 zn_saWtrtgNt>Fkv^+tX>pSIUazxff^aJ}$b!x5P3jr?{#ZLimtT+)sFhAY+@U;53D zz=p>Ge$yR%_`;9ChIKK&HC(Z7yI-*$*2VnRaK&1>$^5qBigjzaVlCasZ@6MDUHZ+h zSdWgw`Lyjl!xd}Q8~F`atW_`l=2xtT>!sgt#ai`7emkGGj|2VYSFDHY#r)QA#k%c& z#d=tme!~@O=|=P0`Lt~uaK&1>(fo!;#@2AfTDpTu=HH>*4XmdQ$D*@q6Z1 ztVeZm#ai`pJ?U4hhjlr>;fl4!H(F1gPut%It|$G9^>DrP8?IQZ-e`V1pSIV_`OU9b z57$e-;fi(J{fhOlF8zip*3ymqhMs(_;fl3%Bfp(b+r}4Htfd>xZ|KUWdg(X6Vm&&( zKrp0Bzd3?2tV_QE!O%EFe!~@O)l0ush1Y&}*M)k2Zk*p7!5AI~`V9z1+a19e)}`No zU`RKb-*CmcX#tGibw@CU>*ab92!`s7{C58T+j9egA>GJtxMHnwpx+$97##;77}BNR z9KjgYrQd*HXdEKH0l`qY^qV6X!}W501A?J?qxlU8hU(?~<_N}cz4RLpjJ7+1F|5n^ z4G4yGqxlUTCtCx8A>GJtKrp1s^`s*h!{fm9BoGYMt0!>%J|Ykd)l0uQf-zbz5De+^ z`^^!IVO_2#fnaDHqVKo!Y1{84u2@Sq@*5gYY8>b{M=*xRfqnym(RN2LhIQ#TAQ;k( z{00O=Ka<>_bOd9#Ue0eoFjQ|ezX8Eey`0}1!5FO<2!?d&H%BmrbveHQ!O%EF^BWKh z)yw(K5scw_={F!4syFf*5De8zzd3?2Trd5GE7omy1Y=m2eglFb-NtS8`4Ogr+4w2t*#ai{!Z+^vkxL*2= ze8~~O#Hi!f!{!m(+!N*M;AXh%c!N^{$Kcta25M0`nI zsCQkQcOMa7QWxqkb#({d_a~2tFJXI6wHl@0BEE$EJ*A8J4gEa_e<$lgy^jO^7V#x@ zq26`rw}>yP3-zu`zeRjWU8r|m`Yqy1>O#Hi(r*!8!Y-d@OIy6Z5nsYKpVFn@BEE!u zKDCWVzeRjWU8uM5C0}wxd`VrXcU}4|;!Em6z3b9%5noal>Rp$9i};edQ180*Tf~>J z+o#?K`Yqy1Hu5E6(&>w2zhpy%zv`vmBEDohpSF)L{TA^h8~Kt>z62dVN9POjC2aZG zj)*VW$d`2TB}c@UY$r`*<4eBei1?C?d`Tx?azuQ|c0O&dmwt=*l8t;xM})tgTk`$3 zolo2ArQagHWFueF5#isCh%edBr|tF9ZxLUzolo0z$(I}vU$T)e>Eug}h%ed5mvr(a zN5q$G-8VWzG6`#T|2}XuGcq}rRyKv(mgBu9_AX>)zh~30gDpp>Inq8 zz9><>{t+NuJ%Q_Wu_%$Qe*{QZPax2x-|*Wi-N5W1ar`v{R>Z)ACYQyV^E_S}vHQ zMrGYl+KhHXN!AQCD(ildtbbHX*8DUo>voc?+exx!r$Jd>ko>%KAD*gWz70ta)ivR?pe1bt_5Mrmj(0pSe`6&s`XiKt^Q zy3Ch|gKq*lPfC_9^A+N#EM0~LqQ*9H88@vCtPk~dlemm~RtJ`cA3nx@SY})d!sYCG zehK{i-SgA?ub;kpBTL@>`gf22@O<|_mf(|M24CDCz!xi>z<&M)mw@w0lV5mLy7>K5 zxfUp!o|{{pIB`~nInjOz8D!2STfSP7f<6F6M2{{~7ID-8jKQN6y@ zkS=}%1r$cQzSfW~)*8+E;?Z#cUo2hx3<@Yr>IGjcUHlF<=ZlBy_2q_i@k1z}Fshe+ z17EE7Eb<%pV%1B(IbS?H4)h!NVkN{zenShV{s6vMx{=?&7fY9ZbG~?Z9OyUj#i}>* z8~9??OTRf^JX$aKV(HRv&KD2s>S^120lrw{V5|FKUHT1tv2-K9olo2A<^1M+@o>GI z-@q3u;n8qA{GNd?mM;C~eDUx&&~M<2H4c&A&Zlkf z1NdU;+A4pvUhu^l2l~zV;$dC-4Scccjr@idPO6vloAbrP_0n(Pi&bwlzoCVb>gD|A zeDQF-^c(nMC5lIW179qBg?@9sc(`7!C&3r1-e^4uzF75gJ?VV$aJ}>!_+r%?`3-!r z>ZRYDFCMKIe6e)7o^-x=SeNq~_+pJiG{1o_R=u3xoG-qt_wr-)6I;O#pRMzF{GB$< zH2Gcr%ud`}6c2Mb-JBl#^mcIVA-gP|j&PVn77s_;&OSMchDl`cTR5Tph|>So^xK&{GP(>W&!R07mw|>86oJ*fwnCF?vACab?yPDPmw|;-wfL6q ze(XH>d&^Vj38&7g_9d5H&agjydVK%p-9Ns%TNR}`e6p%-U4OJneD#%N+k7Qin93*T zQtA3HsC50=O4pw4u&zH`>H11iy7q8~b^SL~y8d*fYb(i7U92Rf>p!B>wZ}WGtJmwo z>C*MJigazQGOX*173uoVsB~?yGOX*X73uo#sB~?$a;bZJ&((V9_MZRZ{`ENy|H0n# zU+w?ve_io=&YSZKcDA(98T~$DXR9sP*^+Mb`-q(_>GJo{ceXBn7hY~=q4|fukJ#B# zz0vO@cD7V6e;<8kYq(ziK4ND}^}hJ~_@m>Xr)~2DcDD4pYoBw&_4@am#=%#b(zTW5 zrS6~oJ^$5u&3nEvF;8nc`=}P-p3JM;S?A?=X;DYr+KNMH_3$d$XPVx{oj3n*)h?=UepY_2$OJJaO6>2PEc=>S7%$PMf+fu46CX z^H1!6-C#(OEN>p)YKk9u-n##Y?|>T&sl}0Q_uI>_{`PMEtiQVJ|9e`0 zqNBt+{Yv-a^L1(C`v%*2gZ=Vnqcg$z@C4^N1RPnHAT0?tYKZeSt2oQsU}_fwI9~S&%J&EsB7PU!@Afv5Lp9V5Z33{;K2KE zK5ZXge*b~69@WJ;Mh9Wt4iMI(y8QkFVJ%(z{u>@&`VEA&bZwt*SeJeSVJ%(TryJD; zVXdHL?ze!j9voi~*3zZlKv<9J(r+NFH4c&AnBc4?zVt=pHxSku2l@?!_2@XzZy>DO z0m6Dzmwp3bEnPiZx2tjqb0yujf*1H-!X8@ZUnxtLL1axtA;%;8+jurB>ZUf^&pW>}Yg zBNuZx7c;C&zmbbMoQoOOrQeX?ti;x6emkGGtsju!EL}Z;>*q}-ICmsCOE;R|nBd%z z;4Ix}emkGGjRO*#r5mj$nc&>fAzZr2db0Y#d%eD%l&*g9u6}OS58icsJt^H}zoh!X zyRPq-NHM(H>-u@QbQ8Z-KX})5?o+yn->M(H>pJ%--N&cZDRUZ7J z%CIihlPhnkJortOVO`8`D^GqO{Hn^ZF4mJP@2WibU6oPY^Y84rF$m|uFRKjeVm-;Q zL?y{b^BbdZRz~44EOBg~p!&i4IM8o?UuAe4u%2XCVt?=pE5o|<8`E$YmN+^N^c%0N zFf4IYmww}&6^12_>e6q#w8F5&QC<3tw^kUIIH-$jE6T6o{N~qIM&Abn(Mp%|8^RJt z>*f50utdGT(fo$6MAb{bAuMsUUiytev=0cP9o41Z7)1L}XXRJVn@n(Ck>IQ-rD#3L z1m_hA&eDz6lT2`4k>D)dXg$dU=M@Rg(v8-Wg)S-O$m&Zlkb2k_3) zjr>NwWCdR$-NvDdJ_>vt7e#&R#_glo5R6lsH zm-8DE{08SCB>1Ub?w3S-$xgmxWrCj~yAmItPus=;e2F5kBEPXi_zJ${jO>c)<$4l) z$r;%d>2f^@zC^mw{6@ZH1z#fFXn&G?$qK$iy3zc0K5c&==(mV3sebUTOTQt(Z_sb# zOIGkDiad(uxASRxz1%N}_>vt7e#&p;{$#|L>`3sFF83!RzNGrW+ckD5c16 z$@eZ_f>UiRz8!H}WMb_!8+xe&apo6?}8Nur+i|bzeRk>em-p*U+^WWH}V_#k`;W3bR)kZ!B6AB z@3)9A*?IG11z)0iBflZRPxW#=8Sy3i`LzAH!EaNcEE3nJq*U7 z`oVj>SWngs^Ppb+y1Fj>rr^V^jpN2R6qDjUA2(+`E82$lIjQV zy7+!m_+d1@*e_8FdDffwt@^=xz1W{r{9#fr`4Y8|XT8b%R{h|;UivNKOR68d>(Xx? zf;xD9p_}9GH?@%GI7EIUU!oTB(5(uuJr7VL9o9>~MSO`m=|Go!iBb@w_YCI&Y9Y^Y zi2TMjOKKrc-NPCJ$pSHcf&fZ| z@8dwfMSRJDKvazb{TA^h2fHn)g*?W=6H!Nhci16ZE##>i`3;$<>Qh3$c_!*`y`103 zmrNdtI;@NDH?@%GI7EIUU!oTB)Q$W`zCT$g@}_>$v%+OA8#MSRIYzGNd`GDUpJLB3=oUou5}Nu|~JIM8nqUs7o`u1mi~ zd`YF%xGwz`@g(Xx#Us7o`u1mi~d`YF%xGwz`@gLCM>&b{OImnl6 zxMiab5Z?;!7&6#&zkph%c$M8rP-YBEF>3YD|}W$rSM=l~&`r zTu(-PNu|}eF4vP0Us7o`uFLgg#FtcBjqB2H5nobiHLlC~E#gZmt;Tifw}>yPv>Ml? z-y*)G(rR26ew!n{q|$0!7k--~zNFG>OqYDg9PuTUR^z(x+Z^#Fl~&`r@Y@{mC6!j= zy71eafE_D@f!+L}BH|gTMTLCxJ4fZFci}N=H+)y{zpOh~4 zOB8TJ-C%!GsVDH80&b`q>`zJ;epA2=b%XN&>B4UcxS?*aKPg@KO#wI54bB6k3%@Dg z2D)_udnI2YUHDA_H`LV=xRz^^F8xNnWKQ@J>C$iHOXeiMM7s1F`I0%wFOe?&M!sZD z@=KH=LcftOnG?Q5y7U|Qk~!f^q)We%FPXi2#TZW@UHXmfE9QhRkuLp4zGP1L66w-! zZ zN)e&o$d}AXeu;GHH}WNO!k0*wej{HpCwz%?={M$=%n4s2UHXmrC3C`;NSA&iUot0r ziFD~V@+EV^mq?d>V}8k;@Fmiv-^iEDNq&h^IXJ(OFPW4466w-!HH|Cej311>z`i*?aobV;mrQeueGADeAbm=$dm&^%YB3=58`6YA0mncPq zej{HpCwz%?={NEvv-2gj`uSuZCh5{|=#SIqgfEdU{f7QH(vAGa{F0sdC3C`;s9yRF z{c-x7@Fmiv-^iED311>z`i*?aobV;mrQgVx%n4s2UHXlD$(-;dO68#6$d}9sUm{)l zjrk>W!k0*wenWp8y=Qs?*YC?QzeE8y*zZgD64lG~B=bw=gfEdU{l@%~IpIsBOTUpX znG?Q5y7U|Qk~!f^q)We%FPUHFORTT>@7{d<>Tdt~>${)-OpPF?rvLWK^S^!8_1}K; zyEk9{lNv&5m%V?ko2J7JA^U<4;y&?%SREoSU)aHkXTb-tbaB9<4v~?r52$o;z@iS3 zk*@!MNf!q!-9Lyg$Kmop{mZJ>UKG?ysKS&42N;r+;|-_U-dujz5(h z+bVs32BqttdD7Jr2y}fK zl&&AsN!O>r!S@&2D$@07P`bYC9M$z{P`Z9hw=x!XRM)3L>C$i5RvFc$->|KsdLzGK zTSeUn={IbvjMhuPVOvG@Mt;M#it6=WZRtjS!?uca={Ibv42}b~RisP5VOwQXmwv;x zipC-G8@5$cFa3sXmC<_XH*Bk@ElD)LVOvG@(r?&S8LgLo!?ud*jr@jfmCjgL>7Et- zfCr4$OTS@TMY@sSu&ttc={Ibv4AzTn73tD%*j5?U<@|Tj0w#sO| z`nwCw%Z`f8*y^-Irtg9S8+bW~=ay^M{6}88TzTdE|qVCK5e#5rPXubS?!?ud*J(aHZ8@5$c zFa3sXmC<_n{f28hsyA9sA{JKl(r>u7GgvRK?MRpFNnG0*)#Z8;v9KD4Xg!HoSk=q< z4cB%?>*f50SlIOe*LFsA={K|;mTu%X#KLyQ!b&%q-w+EcU4Fme+Ro@Wa6O4wSk)WN zZ-|9ey`0~0ZD+7v#KKCKe#5n$QC-e&h=tWSMDrVBVO1~ZH(c8ptyh0%^BZDeRc|!E zAr@BkVt!*R>}b988`=)5onquS#KLyQ!b&&t8)9Ll3%@ZIc61!*H^joK-pFr=g;l-q z8)IR|>SZjfbm2F~!j9_FZ@9Ljad^>hm%H*meR_QV=G{NOy3-HsJiHIzI)10yg6oxS z^WW*qQ-N3C-9J7*zkl=FZ=aw3aR2(d`(OO>S6_Vo*Y~d%>H4}zy8hls_Z*?`*G0p+ z{@zH}*G1B`_hwkv*G1Cx_eQ$5E*jOv@3eINy^*f%YY*%Cdm~+67fILNn_*pF7fIKD zr=@G_qG4SH4}zy7oJLseAdJ|JS?!^7hT|U)_BsKv~H8o$>>g>GNfJ7=Gt< zWQk|3-WfP*#v1tCIr#KhPBp@~{5S4c1NRwg;89&X>m6%g>Dsd%MaS71VaFO+y7sJx zb@8m#JA>nE&w5zb*T8MZ8o19`1CNfc&&ksDJs#=$oII-QdpvE&Z>w~DP9D|8Z|jcV zR_WSr>+tyEw{^#Ft90$Rby$~v!*8o}?YDJQm%pt$ep{t$zpcZ%^c#L#r5pJTYhb+( z{@W_u$ZzMx;*AF~2R*)%E(~ab5cD<*VzLYouR)^W{H1J>UKA>G7+(FCTw@_lGavKmF-$ z`p@kr^TXXg-#vV$Uex2uC9SROHSMa?r}KW^sr_Lof6kSkUM(%SKrLB3_3i=vqq4q$ zl`I~5_k8|QS^tfdES`BkFVtQ?2)?9|EFO8UN$dO1q|s`9MI%}K!gdemAC>h5O`mvo zy8GSfQCa_em8^d&_Fi<-)q~(auafmoMakOF>u9yUnvpDiUAteL9+W+w^M&~(OPBe* z=}}qzoy*c?erUdpv!n)y8C_U(Q4^3UYG8EU3yR!x25~U+tS@{OJB%d&aglG z=G))CeG>fo`2N-1{P45C(SP>eyt?ZTzZsrb+X5z}O<+QrPE{|T$k_LbbXE0*i=^wG zmu|40lCGOxx<0i^*GxZLue)Bl?t1Ck+&Zl5wwJC?uC0R!8Tua3IJobn>$9tL&-dp0 z`D(acH-4MIgh)5oFHpVieChi9DqVB_aJ_DQ>G}jKU7KKsb=~{Y^%+*W!G1woz=TNG zr&#Gme&bb}2~3D|Bfo(OQN8pVn2^Eumsf3+>}(5q)f@Q@Oo-~G-@t^7)=R&E3DIdo zAdzZR3mmaOp<#8<>!$WM{l*$$ofSxF4=$XX-}t+xfJ89JroL_QO># z*OS-}*Z4;3N$!U$*_q=I`HlPG6ZXT~n(T*b9OySNA<~Wf#{KXK`{B}!{01hZP1p~Y zZsa%ahb!6HpPMc}CF^SLhfmlKSG~#n))?hFfeDdr;-5+Pm8Z>yg~41UKpM!724ne|3~W0b3s zov9o7jZv;jc7|^K%dg$n(Ef<8AC&A&-DG~#_a$_39MM)kju?J!*e{uJ9wFVxZ;W!C zaUdbx$Zw2topB-|-NB# z^!I^Lu1a>MZsa!{PBbMuQ#bM(qg<8jOx?(DjB-`7Gj$`sG0IiR&eVtM{X-x%epWM_^;H)M`9B|B3$@*DXQB|B3$T2GQM zQL;02qxp?|iISbE8~KeR z)Q$W`zC_orsT=u?e2K1KQ#bLOdZJ>zPQGM|_!9Mgq%P*SE#gbmg7dU z_-%{$67?*iF8vnqCF;#WU92a!h%ZqO3fI;3YrJO>U!p(^>e6o~ad7p0hEBdj*RNS` z;x}C&XT9{>NgP~XFZmK(zh=G3{HCjXte1X^_!3=SqAvaBS6v6sH`N({y7Zghbsg4) z-*o*N<6BDCo|AR*CAxl1-DEvk*P1W)J#`bBy2<=j_nKXoev9~$y4dWx^jpN2)Xiqs zrQagHq^>r*F8vnqC3Uyib?LW=FR9DTu1mi~d`aDIc3t`{;!Em!v+L4t5nodGn_ZWF zi}(_C)WYu$`I0T-OVp8wy7XJbm(&$!8wc_wTf~1 zTf~=ibVh0m`4VNeCF?WtB@6kI4Lxnf&I>#Fl7)Q9hMqQqy5vh1@+Diumvr(a3;B{Q z;!COzmcI}58+zJ|jsyKhzGRE|lInxy^>TiT_>$^_<+}7+#Fuoo3SP*UY!P45(bJ|a z51ik~mu%>1GpI|xWFcR&MSMvoU!r(Zdpg9OyUlC0oRobhZj!$d_ypU((UjM(;2E7V#yWe91z-WQ+Kcj-EE+Ke?Wa_>xY( zWFcR&p{LF0`#`^uFWJ!3W>A-W$wIzli}Fi4`I3cv$rk08s23poM!sZ=@=Mh7jJo`O zi}(`tcA_rlw}>xM4;$*zZxLToX*D))k}ugJzNFG>T$g@}_>xMiab510MENC^R^z(- zev9~$N~>{Q?w3UQC6!j=x}4vl{E|wmab2z_qx_Oet8rcWEy^#cv>Ml?-y*)G(rR3n zev9%;Dy_zJ$(L+Veo3X(xGw$na(>BWO4b+ueYyMT;~$>x{^r}aZ=e3p-TzpI!?E-& z;y-@c)bod-U)^(>`eC#9{G|MJ?4;mI`|*>mKMd*mX7Q-5Z(eD$&^L>v>zl=+y1scO zU4IzTJ(aE>2OWK1JY?zmkDqk)1Oi=OY)IFC{G{uLGlS!R%`55pkDqk?aAs83H?O4Y zKYr46*k@GN7aP*`A3y0jd@!o3zw_tjKYr5H6S)4lVe?A$(r?(j8m*Up!{sQgaw5Os za+EgF={Ia%jn+%QVe?A$o=R8y4Vzc0mwv`W#ST8oOq)WeH^J-L=^BXp=G!D`H zhRrM0%lQqPSEKdn?`(d<=9TJ=<~M9!sb0=+*t{C8m-8Douk=+M&2QMe(xEHoH*8*w z*30<~n^&s$RJwY8!{(Lh<@|=ttI>KnzhU!A^+xj>Hm_7K{f5n}!FsWIC0)*M*t{Cm z<@|=tD~&@mzhU!A^>Tj0=GADuoZoOcO1nDI{D#dd)yw$}n^&Xta(=_+mFkV=H-zsB za^U=i&8yLRIltj@lT#nK>MDrUiN2y-U zZ`iyVtyh0%^BXQlsorRQ!{sQ|%lQqPSEKcEe#7M`?V?8W8!kr)(&7Au&8yLRIltj@ zlY4VR--FXuOe?~c~X`3;w&bP5p7Z@3(#dO5%0a@1(OoZoOcO7%wb8!kr)isSr- z@ZHgRIltj@l-Kv7k=aAsIhu^IZC>i-*`D{RG0G`!gny{9>e4;pHfe3%}nYzJ!;fq|5m&;!8UD5?+oH-5AYpxE!T=>9>e4 z>EugzIZE~F7w_utSYD1&yxY(WFcR|%Ta^B59iai-yQNLTf~>} za+Jn_ev9}LUXIf51^pKBCA=IZUHUEJOL#d-x}4u4zNC{cS;&|0a@64aK)!^RqeLl3 ze#7M`jRXA_@g=+*C0+V0;!8ThccshuE#gafIZC>m-y*(*m!qUhzeRirFGpz}rQagH zgqNeFOTR^Y2`@)Umwt=*l8*3Q>2iLH_>xY(gqNd4??-+kU&6~#(v7~~a5+ljK)*$N ziEw1hL*z@gh%XV&NnQFa;!A{=QI~#;_!8kc&?R5O%Ta^B>*Pz+{Turw5nrO?R@O_u zMSO{lf2d2pMSO|2&#BArw}>y%HX(I6zeRkBwppl4zeRirFGuM+hVxs*m+*3wbm_N< zFX81V>C$fzU&6~#`tIWV7V#y#93@@)E#gZ$`I3cv$rkY?)ymtx1IU+b5ns~Dmn`H< zwumpOR^DDO{TA^h)yms->9>e4saD>uOTR^YNk{mu-ZT0w;!CQPx7SO*MSMv|_^$RN z=(mV3saD=rFZq%!;!8ThcU3Rvw}>yPR^DDO=eLM2saD>u%lR$hORAN(>(Xx#UsA2S zU6+1~_>yYn?Yi_^#FtbnZ`Xz2c7*Q^uFnv@tM?3k+atcDlP^*CZ(sNA5ns{~zN>H~ z%x`=9p5t-QTn_-#k{?r6RIej{J9M|?@O^7eY^H-ztw){E~qb^nInBEFyYn?Yi_^#FtbnZ`Y;YBEFz@; ziMoIDeMtDp70sPhFXy+2FImZ#sQWkSjrfuk&7F0wL%&6QNwxB}_kn!L9`PkBnmemr z`Yqy1R`Ml{e90d1B`f)ohUU)tU`qBUS2TClIM8nqUsA2S{khR^5nocRyj_=mi};di z`Tf~=C zT8-;+ev9~$N~>{Q`Yp;Ysk9o`rQagHq|$0!mwt=*l1i&_UHUEJODe6#b?LW=FR8Q| z(HCU$RGh zNu|}eF8vnqB`f)oM!sZ^@=GeM#_OfuBEDoLU!v~c@NvYKR9cPKOTR^YNwxBJUHUEJ zODe6#bveI9e94ONUHO83i};e2`6Z2f$sX|~l~!ZpK)z&;_>z_RC5?Q^9`PlWR^#<@ zev9~$YUS;^^jpN2R9cPe(r*!8vXU=pz@;Nn?J=9`PlWR^#>3 zZxLUzk}qlGOZF(gWF=qH$d~L9Us7o`HV(`$*(1KBT6w!J{TA^hl~&`r^jpN2tmI1? z^Go)KFR8Q|ub1;%#FtbnZ`Y;YBEF>3YFwA|Tf~>F=hJpw`Yqy1R_2$e`#07l5nobi zHC8YAl0D)}R`Ml{e90d1C6!j=_0n$F=hJpw`Yqy1 zDy_zK>9>e4S;?0)@+Eu3msDDf*Gs=ee920_q>(S#Bfey1en}%=vPXPLrPbItkT2OI zzGP*7Nn?J=9`PlWR^#<@ev9~$YUS;^^jpN2R9cPe(r*!8vZA@O?s?E}5nobiHC`{~ zwxMiv2h?@azuQ|%KQ>_|MvO#i1?C9tMPgTo>m7N0eVuX*I4(zeRjWrPa7D{TA^hl~&`r^jpN2R9cPe z(r*!8QfW1=OTR^YNu|}eF8vnemsDDf>(Xx#Us7o`u1mi~e91<>q?0c>BEDo}eu)BZ z;Nyrdsk9m!2l6FH#FuR3OVs_F^(OgTl~&{R(r*!8vXL)Q_ixsl+<&XI8n2gri};f5 zeA=!{zeRjWrPa7D{TA^h8}m!l{Tt&O@g*DcOVs_Fy842?nscnQ8XE`ZmmCpavN69z z0XM8S$y3;vU!n#L)Q$Yc{1OG+Q#awcw)1KG_|k6?Us7o`u1mi~d`YF%xGwz`@g>#D z+jZ%;h%ebrn#gtOw}>yPR^FydzT}Abl1i&_UCwV2U$Qa3L_scieUZjy&rt-O64=(mV3sk9o`rQagHq*{5qF8vnq zC6!iVy5viah%c#D-mXi(MSRJI=FZBmpx+|Cq|$1%2>+OA8# zMSMxM@^)SNE#gb6mAC8CZxLTot-M{Aev9~$jrk=CxPjjyzNA`td%g5q#FuQ$FHyh^ z>rL+CR4Z?5?xwBEF>3YFw9oi};di$90lA^H}V_#5(V5)H}V_%<0#;Uy3zbbzC-~x(2e+#N~`hrfqskll1i&FUGgPI z#FuR3OB8U!aY*iWZ_F>zeNE~{ej{I^fE(&Y`;+XCqktRgMt(b=wm&!eE#gZy_Qz4c z4eO2kM!rM=H`I;%#{M`8xG`M?S|t4gHu5D3xS?(|zmYFdzzuby`HlG{3b>(e(euvzg1d|>$=~ho6K*OR^z(vH|ZvRtF#)|b-zhB z@mrT$g@}_>xMiab5Z?;!7&6#&zkp zh%c$M8rSvtO~F5r-_ED)y7XJbm+Z_hS&?6&dLzFvzeE8ye9t1kF~39sH_(mvlAZY_ z3b>(eGQaKQOB8TJ-DG~-$(JbLhPui8R%tc%o`Ek}A0obFCtsp~8`c}mZ_F=Izzua@ z^xNP6%d7A1-#vc)bpQJP*I&MW`qQhs>ES2KeD}9^pXq!4?x){AKY#P?)!i|vd-vz_ zdfdOd|NZ+nU%z>N^T($@+`s<2@9rO;pWnav?YGb8|NQR$7r*?~7oY$2{cDAR;yX>e ztIuOP=yYG5tFlk_$&#+`i%8dfC0+N`sIFEm7tdX~?kgRj`nqvc*Uz=3>%Nk%`)X8I zPu1$hcbatFSEIVVFCw1UeI;G@)u^tXw%6AJ55b@831ad2Nr z*L^jr>+_g&eIAppuNy~o^|XB)=r`O07}cfU@SUc5BfsH0P2&K+DOk=psL^`qH+-iF zScv?F?=qzk__+yfXL2l@@)X{tB!8@|(2FZ|YU4`8g``Fz^;{^C1L z^(KCs&!_FW@SB3=g7<7bpSJ75Zwi)+bm=$rG1WLEew)vy?e)@c_)Z&rZuA@amsRyB7{EWi#%>*ewTu@x>C$h&4n}pk`~Y^Kafti|>_GL>Z-})Rt(Sg7+Z5Fs`3=~C>ZRX+9gNmX zzX3bYc0e@00XxuVJLfmVT8!4q`3=~C>W$_%UG8H4)y}WFZQYimAIBk@9&gLh z4}QBXM?Z|iZ8`dJ9B#|eI!(JRM?by~x8>;VboTY6Wj#M1Z>O^#)*rXi*^lFpoEA-> zXm6*pKmX+~?oYqnPG>)i!|inT<2Ycu=5{)J5>UE4b32_KfWvO5vmchTXgZ+NWS$n? zPG>)Et3;)k1O0Y8o&Dgq+v)7bak!n%*7pAGboRsha66s- zI1bV0_5Z8W+1q7>+jiK8Z3-UG-nPR&`1N*K;o~?&$FsM~3Lm~#Z-?qd4J#2^l^y!aJZ}0x<>GA!myQW4k&!YgCthLmZNHlY3?J`Lyl*MI4fJlau)waY$;{ zNWYy8m@e8N4UPlikfck$q21P~F8zjfTN;Ptq;Ni;wvR9UhIU({_0n$>{f2g1qq_9l zM8Bck)~GK1hIU)(uaey3oY8Je?K?TYEy>boKA*NdH?-SQy^-J0ZcFuYep@2Hq1~2r z>9?~1)AfEsyDjO`Z%gv&Kcn52bUDAF-PYiHc0O%?ZuA@4ZH?;EZ!`Udc3Y#m^xI6o zq21P~F8wxhenY#hQC-e&Xt$+)Mv>pnr)|$|;d&D7wnppa{DyX0syFi6`Lw-W`VH;2 z2J1baw(HVwXty=0%lQrMwlogW{DyX0YI97#oeh|-|J^yCwvPk-hIU({<3PVH^c&i3 zjq1{G3;l+6Tcf)48`^ED&sXHP^J&}oHu??iwnpov-_UML^+tX>pSIUazoFgMV7=$l zc3t`n?Y2gB={L07(l|tZ16i&1-}GCQdo?5XO1ku0lzTNJXh6F3Ta zXXIX~4LaA8QSQ}@paJR9Z&A>|jNB{fay=R4UdxmPoCucS-AML`2Ij*_Iy z^<iupSHheoZq6{s~JH9+XHj2T9kV=<0whGoZq6O zq#3za(xu;`+^ZSwwxmnHMY&fqa<8OIzeTxMGstS`(r+*4Uj5iP4r1J;OTR@i?(_My z?fqqpdy8V+XSCZ=z4TiY6fmDp+v}y@q8Ru2eA=eV821*%xX);}wLLJ#y+vg7jCNbn zrQf0$_ZjWBq)Wd=G43;B+@(vuMP&4hpaAL8Z&8fxkkQhG-+B}jupq`=y7XHV zu+fwxmnHMSRJEc3aY=-y*(bLAx#K(r*!8vY_3T zbUD98e93}#TiZmwq(^+of_7WdrQagHWFcQNkuT{HU$T%dnaG#)h%Z^lmrUeKdc>D3 z=hL>|2l6F7;!76tCDTN|MSRI}K5eg;ev9~$<$T(%OTR^Y$#Onz*QMVgzGNX^GLbLo z5nr;9FPX@f^oTE6$d^pyOM1kYEaXcj@+CduOBV7a6Zw)J@g)oS5_PzzTu z$u!e%5nr;LPut#K@+CduOP2F#yDt3}@g>Xov|X2ei};e|eA=cxU$d^nD*OL)nvXC#C7Op2FzGOL{wvPk-7V#wu`I3ozNssuFg?!1h zaDI#UlI48bJ`VI-#Fs4R({^3@E#ga-^J$wd`H~*-B@6kIiF`?q_>$#(+FmdH7V#wu z`I4#8ZxLUzkT01U{TA^h%lWi@9O$=*FImW!Oyo;?#Fs4OOD6IqJ>p9i@+A}bk{@g>zo&viM!MSMwh(Q{q;E#gZS@+E4#2Omd#i5iS!ej{JfBfg}% z==nI%ZxLToUG!X+ev9~$>Z0emTu(-PNp;b4UHUEJOBV7a6Zw)J@g>zo&*~*#(j&fP zAzw0)FX<6qQeE`CUivNKOBV7a6Zw)J@g>zo&+Fy<7V#wu`I3ozNssuF>Z0fM(r*!8 zvXC#C$d~kpFR3niUN8L?@g)oSl8JmtkNA>>e91(D3a znaG!{5ns~CmrUeK)`%}@!ExAxWF}v-Mtn&lUow*~StGur(rSDh z@cp(%d`YF%xGv_mHR4Mut;Tin{kBGYNu|}eF4mK4#FsSkB{TVwHR4Mut;XslU$RDg zNu|}eF7`{-h%c$M8rP-YBEF>3YFrolC2Pc&R9cPe;`?ol_>xMiab5Z?;!7&6#&zkp zh%c$M8rP-YBEF=NFHyh^=Ano$Y2-_0@+E7;msDDfjRX0THR4Me`4R=(a2%5R-Hm+7 zOul4|_>xAxWF}v-Mtn)7)%f_*ZxLV8$d@SKhU2Rf(5v$lDy_!rrQagHq>(R~nP0L- zd`Tl;GBdwqjrfvAzGNm}vPOJKBVVF`8$7p&FKOgUX6Bcy5ns~Cm(1i#)`%}@xAxWF}v-Mtn&lUow*~StGtgDWiV=HZ#9u zjrfvEtMTW?`7Pp08u^l$e90Q|C6!j=_0n$rv5jrk=CxS_6yy6e|x%r8;E4Rw>epvL?X1>8_K zT2C^+L;*L{)s3iN9KcU1;0C%8U(%RgqJSIf>K8Al7yP6GZm65&b2a9dDBy;=BF2My z!A~mShPu)B8}myPa6?@Ytk>5|zC-~x)Q$W`zC-~x)Q$Yc{1OG+P&e`$^Gg(PL*2-4 z%r8;E4Rj;Eq%prl0XNi*{6@Y+0XNi*{Kote1>8_K@*DXQ1>8_K@*DF@6mUb`$ZzCJ z6mUb`$ZyOqQNRs#BfpU^QNRs#Bfl}fL;*L{jr>NwL;*L@jrfwr{1OG+P&e`$`4R=( zP&e`$`4R=(P&e`$`I4D@iF&Xn^APzG1>CUS7yb74|Dqf8?;gK?x_^ED>o4Cw{pr=+ z^zf5qzWdv|&-$yopMLxN{LQ;pcel=BulsiEEcUM*wUXCgG`4-VuLnP;3gEta88+c_ zO1gOc3*f$97oSto#dK2uccAOr7t+OaQvi3Ms~@|I&tU0dx+#D=(ACp+T}(Fxa0j~n zIi-3r-4wtb==yau>0-JmfIHCj&#Cp`=TrgQfvy%8Hop9vDu6rCrQi5DRRDLO>v19) z2l_3-^+jWI9O$l&3fs#2-lzRIi-5(w+Po4jm>)Lx9D?f!snFg zrQaf4UoyoZ+}FRq_?)_R7W?@xKXkC;=TrgQ*N-ngr!>Cw+snBAZ8`d@FFy1) zo^X3q-v+d6w7WlHcVD`+YqYyRVRv8CF22UGR6K;=67hhwyMz{aEEKhbnChYEO zd}-I{_UMG&ed%&~jBbxk*xi>dr^o2_s4fR$y16Y!KQ=a{-=f>26Vl1GOu%mAZ8`eU z$G7F^$Ht~-KaA27Wtd6v{9wcg75AhpP%2q`R%vQ=a_wW|BGLKKX2Za zqaPYpV|QQ6F#0XJJvw1`U%LGKi*AqVav*+x|D7*K^`8B(J*o(={<+SP#=GC@av}e{ zoFAjxr@CB7UCxiu?NePYq%PN^(dmFL7gCq&(dhQ6E*C*DsQ#(~>4(d|=RF649LdNjIys>_AcrQf34r@CB7 zUHUD$eX7fa)P>*bK4S3P=r`Uzt^0_9F8#*ar*$7O(B<|hZ=cqE#6XvRpo(jOTY2&oc>A>OBmQ~a%k8k=ynlN9N=uHn-#*>_;*A!+Z=dekn|C^>oj&Vt-VLuj6cXW2 zrt4G8&Wm-;R^IsY6}`Ojmaab;>H06BbOSCyy8dLO>%WA$z8icgNY|f?bbaL^-GEDw zuKyA$b;@_bq^l1F75?O z*H<3W4R*r%fqTKy^_7Qo0}e>K@S7TO!EedEVClkdYB)sQ$ZyD<*ErB`$-Q9J3%{v> z1nN!h1xuHH!@b~DLDSKDM!(@+uyiB8A$PuS$eovNuwo>l`3?7i zl~Tz0Ex8x0dg(XZ3s$|6-*7Kj^>Thoa_3bq=QrF7R=v^uhI_%Pmwrp`1uGPbenalO z>W$_%+zVE{oZph%dDYAL4Y~8GH=5sYFIe@`Z^^x2)l0wOUa;a-BER8Yus}rmEx8x0 zdg(XZ3s$|6-*7Kj_0n(2yW%z{d%>!geoO8JD=dzF!@XeD8~F{n^Cy^! zbyRXMSoP9xxEHK?BflYcUiH#%$-Q9JOTXb>uwsWIzu{hR-*7Kjy3u+Px%1NH_giu= zSmVI&H{1(Wz0rCS_kvX~*OSS;V1*rWJ&Ak4syF(6!@XeD%k^Y(FIe?*J&D|T)f=rR zaW7c)ay^;c3s${cPl6m$Y*w^i0&+<8^7}0zhg2`W-#`wj-pFqthx!I`NV?Jd29RC4 zoZpgr!5Rn7ZvfdTj0yThoKz7wjzX4=dy^-Glva9O={g&j;t6usIW%yckX`lCZ!d%FKXy(A@<+Oy-xBgiN{z#X8OLFHm4)hzyAJrTA4fldoFa4I}&i4c4k94`7OvoSU zay^OMd5uG~o&@=$dg-@>{87F18*=AWZ{#i+nnUi>$%ZyAb(VESegpZVdV~2*y7U{! zAL#~ulP=ejB4V2`I0%|OQZ|G z?c_`5gfEdU{I-)XQP6ba3-Tp9`4R<9N4oIaPQGML_!5l+{YJh-LDNya^c(pS1x-h~ z^c(pS1x-h~^c(q-IpIsxl!ksIU!tJtq+aqRJNc41;Y(C6{YJh-LDNya^c(pS1x-h~ znBR8tB?_93bm=$pB?_93bm=$pB?_93bm=$pB?_93bm=$pB?_93bm=$pB?_8Objg?O zM!rNr(~&OyM!rNr(~&OyM!rNr(}^zmlAV0XobV-Tjz+(cFHz8RR4@HT zzGP1L64gt;kuOoubW|_>M!rNr(~&OyM!sZD_!5l+{YJh-LDNya^c(pS1x-h~^c(pS z1x-h~^c(pSU8+rV$(QWpOB6I6>C$iHOB6I6>C$iHOB6I6>C$iHOB6I6>C$iHOB6I6 z>C$iHOB6I6>C$iHOB6I6>C$iHOB6I6>C$iHOB6I6>C$iHOB6Jn=#nql$(JZ-I?|=z z$d@Q+I?|=z$d@Q+I?|=z$d@P}AkwAZ$d@Q+I?|=z$d@Q+I?|=z$d@Q+I?|=z$d@Q+ zI?|=z$d@Q+I?|=z$d@Q+I?*LxvXd`S&~&6rzmYFd&~&6rzmYFd&~&6rzmYFd&~&6r zzmYFd&~&6rzmYFd&~&6rzmYFd&~&6rzmYFd&~&6rzmYGQ6TU=ElIb_{C3C`;s7bP( zww;TRFPRg*M7s1F`I0%|OQcJ`kuRAOzC^n88~Kts;Y*}TzmYGQ6TU>c^c(q-IpIsB zOTUpXnG?Q5y7U|Qk~!f^q)We%FPRg*M7s1F`I0%|OVm7^ej{HpCwz%?={NEvbHbNM zmwqE(GADeAbm=$pC3C`;NSA&iU$UIU!L@vebm=$pB}>AWNSA&iU$P{8iFD~V@+C{c zmq?d>BVV#4e2H}FH}WM*#FtFuOLp=lOT?E<GYOyo;;@+C{emrUeKcJd`l z#FtFuOLp=lOT?E<%rDu=mn;!qGLbJi$d@b;Uow#|ImnkR5nobiHJ9r%1>E?3$R*-S zDy_zK!E-GUUs7o`t_yy0iTILAt8rcM%1gwTR9cPef}dO>zNFG>To?BPmWVH@v>Mk1 zKeK)X*I43esYQUl8N~x3b=vaBEDo|eu)BZsGIDU zOyo-r@+C{emrUeK6mY|Oll_uPtMTVXzeRjWrPa7D{TA^hl~&`r^jpN2C{xwHyASdu zOT?E<%r8;E4W3)XmrTqrQNRs#ll_uPtFiGVU$R7e$;AAUgM7&n@g)=a5(V6F9FqOX zN~`g4px+|CWMY2FLB3>(_>xMi@p|dEh%cF#UviKySt7oq(rUb3&TkQ4GLbJi$d@b; zUs7o`RxkOICE`ma=9e7gOO}W)sk9oem-Ac1mrUeK4)P^S#FtcBjn_-RMSRJ`{E~xw z$rAA;l~&{R(r*!8GBLm8AYZaXd`YF%c)j#n#FtFuOAhiSOT?E{T8-69zGR8`l8N~x z2lzhFCG32(MxBp7q}AB_K)xhu#3^0uPqGoG z>W#kN$d|AYr*xzBB=bwy`AE9a_Z#y|*!f7h$$2+BAL%{g{1)*g?0h6$`Yqy1Dy_!f zGx{y!OD5)*uo34PHRAk`R%7*&FNqp)N*Ct=?0lqp6TYO~ZxLU@Mw|*@;rCm_ zm#`7%8E}K&^@uNFBTngZev9}LHsX{n{TA^hY{V&D`Yqy1*oafQ^jpN2uo0&MLO8!g ze96T8l7oE767eOKR%5;(U$R7e2|FKY9O$=*FJb2+>C$fzUow#|VI$6UiTDzBE>gYp zTf~>JbCGoEw}>xc=OXFSZxLU@&PCFt-y*(*or}(Z8~jd2e91(EqtMe9lOB?tMECE`oixk&FB{TA^h z>|AsP-1s;|os0C`cpgB$BdlUiyuENz}PWy8M14 zUlMgLQi=%uM!qEKTqIraTnG7*sB@8Y!E+ttOQOz2(gn|TkS~ck7fBa9mjZ6^{ziOB zrPcWRi}~$GIv2g1f2MlfZwm6D-y*)G(rPa1l`hWTTEv%BT8-=Cyt_qwNu|}eF4mJR z;!7&6#&xltY!P2lX*I5k`K?8KNu|}eF4mJR;!7&6#&t2jwTLgNv>Ml?-y*)G(rR3n zev9~$N~T$g@}@=GeM#&zkph%c$M8rP-Y zqWqFdt8rcWE#gZmt;Tifw}>yPv>Ml?-y*)G(rR3nev9~$N~xMiab5Z?;!7&6#&zkpD8HoAYFw9oi};dCt8rcWE#gZmt;Tifw}>yP zv>Ml?-y*)G(rR3nev9~$N~T$g@}_>xMi zab5Z?;!7&6#&zkph%c$M8rP-YBEF>3YFw9oi};dCt8rcWE#gZmt;Tifw}>yPv>MYT zU(zDJq|$0!mwt=*l1i&_UHUEJODe6#b?LW=FR8Q|*QMVgzNFG>T$g@}_>xMiab5Z? z;!7&6#&zkph%c$M8rP-YBEF>3YFw9oi};dCt1(^jB`xAhDy_zK>9;7qq|$0!mwt=# zODe6#b?LW=FR8Q|*QMVgzNFG>T$g@}_>xMiab5Z?;!7&6#&zkph%c$M8rP-YBEF>3 zYFw9oi};dCt1(^Xm$WFqq|$0!mwt=#ODe6#b?LW=FR8Q|*QMVgzNFG>T$g@}_>xMi zab5Z?;!7&6#&zkph%c$M8rP-YBEF>3YFw9oi};dCt8rcWE#gZmt;Tf8m$Zm4sk9o` zrQagHq|$0!mwt=*l1i&_UHUEJODe6#b?LW=FR8Q|*QMVgzNFG>T$g@}_>xMiab5Z? z;!7&6#&zkph%c$M8rP-YBEF>3YD|}WNsIWBN~>{Q`Yp;Ysk9o`rQf3bl1i&_UHUD` zFR8Q|*QMVgzNFG>T$g@}@=GeM#&zkph%c$M8rP-YBEF>3YFrn7>rsA5rPa7D{MMuV zl1i&FUGgP8$}g$38rOy2dX!&MX*I43zx61;q|$0!7k=weeo3X(xGwzGqx_Oet8rcU ztw;GKl~&`r@LP}aODe6#b>X)j<(E`ijqB2H5nobiHLgp)MfoL_R&%MVfE(vwdc>Dh zT8-<{ZxLToX*I4(zeRjWrPa7D{TA^hl~&`r^jpN2R9cPe(r*!8QfW1=OTR^YNu|}e zF8vnqC6!j=y7XJbmsDDf>(Xx#Us7o`rc1u0M|?@8)wnMG7V#yOR^z(#Tf~=CT8-<{ zZxLToX*I4(zeRjWrPa7D{TA^hl~&`r^jpN2R9cPe(r*!8vYb!bb?LW=FIkXZvMS&P z^H9W>R9cPIOTMH>e940Rl2rjWtT)LoSxMi@o}KvBEF>3YFw9oi};cS`6a6YZs3cE zFImo~ZS^w0q(^*7rPa7D{TA^h%lWijmwt=*l1i&_UHUEJOBVFU(Q~8UBEF>3YP??h zE#gZmt;Tifw}>yPv>Ml?-y*(bIiI%c(r*!8QfW1&OTMH>e93Y?ZP(@e7V#yOR^z(# zTf~9>e4S(Xx#Us7o`u1mi~d`YF%xGwz` z@g>Xov|X2ei};dCt1(^jB|YLx7UY*GAcTI4_>$#(+FmdH7V#yOR^z(#Tf~u+vaTLHpzeRk>az1UZmwt=*l1i&_ zUHUEJODe6#b?LW=FR8Q|*QMVgzGOL{w(HVw5nr;LPuq0Km-L7)S&(0{D&Pj+g%Mw} zoKM^9rQagHWI=x%)l0uce940TIMSuxBEDoneu;GHw}>xU&>u&-^jpN2R9cNcH~KB& zODe6#b?LW=FImtZN8>=hMSRJE{x}Nq;C@NOmsDDfjRX7R^oTE6kYA#D>9>e4Sn&~Fi6QfW1=3%@B@An1=% zX*I43zpW8pQfW1&OTJ`{_>u+vaTE}O`Ax0EqjBK;#{3esNRD*5o@9Q>8u2BSR^#If zzpW8pQfW1=3%{wQT`&#}`6Xw-jjv18x+~K4{1WNHZ)#B#>GJ%I`6X+_msDDfk1zce z@g(Xx#Us7o`u8a9?jrfvEt8rb-Z`wIX-iPyPyDt3}@g{Q`Yqy1Dy_zJ$(O7VUs7o` zu1mi~d`YF%xGwz`@gatvi};du zK5f^f-y*)GkuOoe4aPU(OB(qS1>8_qJ62csact<1BX@Cri};d8zC-~xtT$OtHu5D3 zxS?*co^0ex6mUb`XnrGKqJSIfCi#=?q>1ePo$0rTFR8Q|*QMVgzNC>aQNRtyAzDwO zKaSpC`Yqy1+DQ}nIM8nqU((2zDBuR;5b-6Ae2D^Xs2lkW{c%CUS==%-*aa1q;7V#zRq>1ePUFf%nFKOtHqk8GLh%ag6OB8T} z@s0SBhWu(j(r*!8(#V%6 z;D+@^emiL*^F^cIBEF=dKaR$Mev9~$c0O&dmwt=*l19En0XG=mh%ag9)3$oam#h(A z(#V%6;D+@^ej{I^fE(&Y^Bel(tO~fHZsa%eB?`EqZnT~xU!s5;>PCJeU!s5;>PGvM zCr#w<8T}UVCGDh%T$g@}_>y+gM6OG}MSMv^f1FhTHyGcDFKH)DWc9K?&KmJ04gGOc zFZ~wrC5?QE0&X}Ck>ALdDBy;=k>ALdDBy;=k>Adz?az&Vi};duK5f^f-y*)Golo0! z>9>e4Y2-^3aD(xU_>xAxL;*L{jnPGV$`4R=(P&e`$`4R=( zP&e`$`4R=(P&e`$`4R=(P&b<2PMXMk!TvaF#Fw;_CURZ+E#gZW`4R=(U>qX8q>(RC zzzuaHzo9?Qs(>5nMt&n-qJSIfMt&n-qJSIfMt&n-qJSIfMt&n-qJSIfMt&n-qJSIf zMt(bKBJ&0NX)y;!7I(LvM!rM=H`I;% zhWTo-=ZBEF>3YFrn7+akWC(rR26 z>&Y$RODe6#b?LW=FR8Q|*QMVgzNFG>E_D@f17AdZNu|}eF8vnqC6!j=y7XJbmsDDf z>(Xx#U((5!DBy#yDt3}@g@Cy+OA8#MSMvoU!s5;_$}f~ zI{6X>+)y`JPgYuuj|2S{@g<#ni2`m|Z*tz<$(JbL2D%Yn(#e-7;D)*hU((5!DBy;= z$@g0)U!s5;>L%;SPQF9|H`GnO-#Ymc1>8_K`F`uPCKJeu)BZ zsGEGhb@C+&xS?+3H}WM4xPflOmvr(a3b>(e(e(e(e z(e(e(e(e(e#@+Atmp>E_i@+Atmp>E_i@+Atmp>E_i z@+Atmp>E_i@+Atmp>E_i@+Atmp>E_i@+Atmp>E_i@+Atmp>E_i@+Atmp>E_i@+Atm zfo{Z?bn+z%xS?+3H}WM4xS?+3H}WM4xS?+3H}WM4xS?+3H}WM4xS?+3H}WM4xS?+3 zH}WM4xS?+3H}WM4xS?+3H}WM4xS?+3H}WM4xPflOmvr(a3b>(e(e(e(e(e(e(e(e(e z+)y|28~G9i z+)y|28~G9i+)y|28~G9i+)y|28~G9i+)y|1Tcy?5c^3JSJ>p9$t;TiXw>{!ZDy_zK z;kP~FODe6#b>X)?;!7&6#&zkph%c$M8rP-YBEF>3YA$sZaD(?O;!7&6#&zkph%c$M z8rP-YBEF>3YFw9oi};dCt8rb-Z+nzqqW%$nKCgfqKDT6kQ?5UC>9>e4QQkUr>9>e4 zsk9m&U-~WLODe6#b?LW=FH!y|#({jv9`Pm0>!U9H7V#y@XQM9t7V#y@i=r<57V#x3 z`4R=(z!wo;qP!B;OTR_=C6!iV@7YAZMSO|wU9(>LEy^#^y;bVcZxLUj`;XM6-=h9F zx<3Y8@+EteU$T-fQNRt}vy(WuI&VdsHtVI|qW(DIlc`I;Mg4JB@+Atm;W#AUZ!7r{ z1>8_Kn%~HmDBy;=$@kkzzC-~x)J?wMR`MkZxPflOm#pMV6mUb``{Kn zO1?w^H>@}E8~G9i+)y|9ep|_xDBy;=(f1qql19E{kMc`a@+AtmVZD*x$d@SKhPsj8 z$d@SKhPsj8$d@$oC40n|tmI1?`I0@#FImZ#H1Z{T)E{RhU!s5;jBnH*XC+_K$d~L< ze#uI{L;*LfH}V_#5(V5)H=5tbmnh(dx{=?=mnh(dx{=?=mnh(dx{=?=mo)Mvd&HNl z`{N5m3)Z;Zdh;RH}WM4xS?+3 zH}WM4xS?+3H}WM4xS?+3H}WM4xS?+3H}WNoe90d1B`f)oM!sZ^@=I3oC5?Q^9_5#; z8_K@*DXQ1>8_K z@*DXQ1>8_K@*DXQ1>8V4;!9TYB?`EqZuI>|zNC>a*`xkAEBTT}zGRR3W{OMFHyh^$2Xea$d@SKhPu)GM!rM=H`I;%M!rM=H`I;%M!uwxFWIB~l9hZ(BVV#d ze920_q>(S#qx_PUd`Tl;vPb=KR`Ml{e90d5$63jjH1Z{T)E}qPYHS~ze90d5$63jj zDBuR~Z`2=WC10X|8|p@WBVVF`8|p@WBVW?Um+Vn~$x6PYkuNzSzGNj|(#V$_QGUrv zzNC>aIimcMm3&DfUvfnKaaQsrjeN-w<(E`ijromy$r0t3R9cPe!f!{!msDDf>%wnG z#FtcBjqAd1N5q$G=hJpwtS66%FR8Q|*Ts7Bi1?C9t8rbdCy$6PskE9)T?O3u@7WRY zC6!j=y4Wu{BEF>3YFroR0Y}7_R9cPeVm*08e96ZA5(V6Fe3SL$M!rM=H`Gn$w~c&> z0&b|A%x@d{5(V5)H~D_sm|voR8|X%S$;SK=1>8_K`F`8Tmnh(dx(PqIkuOoe4Rw?K z$&Gx80&b|AoWE`4OB8TJ-Q@diBVVF`8|p@WBVVF`8|p@WJ82^O-63CcM109czC-~x ztT*x-`4R=(KsVw`Hu5D3xS?+3H}WM4xS?+3H}WM4xS?+3H}WM4xS?+3H}WM4xS?+3 zH}WM4xS?+3H}WM4xS?+3H}WM4xS?(|zmYFdzzuaHzmYFdzzuXGzGNd`qJSIfMt&n- zqJSIfMt&n-(#e+`Cvk8!&$W>+>Eug}lQ;-;^|bAGoqWl05(n4ok}v7xOOA*y*~phD z;D*mF@*DY*PQK)b`r~ZmOFH?IBkGT{kuT}wOOA*y*~pi4@+C*amu%!qI{A_#;!8I2 zC7pc95%DD(`I1h)Eug}h%ed5mvr(aN5q$Ga^c(q-<0K9OT|I5D zm+Q%>Kh8$Jq?0c>BEDoJU((5!91&l#kuT}wOOA*y*~pi4@+C*amu%!qI{A_#;!8I2 zC7pc95%DD(`I1h)lH()}0$t8;9hM zJBfqqeL=pYlP@_=;vmqa-^iC75nr;AFX`Y*1ROj>_3GEv*1zCOq#Nx|k}v7tOQaj^ zPm(X`;7g<%eZP?}>EKJG8|_arzodgNk!~`-Ra%WbH{_Q{H<{n|^J%-T`%Suu-}duq zyRM%HNH_7@PQIic{{1H1NwL;*L{jr>NwL;*L{jr>NwL;*L{jr>NwL;*L{jr>NwL;*L{jr>NwL;*L{ zjr>NwL;*L{jr>NwL;*L{jr>NwL;*L@jrfwCe2D^Xs2ll>e2D^Xs2ll>e2D^Xs2ll> ze8~#FM8J6DH|Ccp;D+@^ej{I^fE(&Yej{I^fE(&Yej{I^fE(&Yej{I^fE(&Yej{J9 zf-e#1AAP@(FHyh^>W%o4N~^K&7VssiH}V_#5(V6_-pFs{OIGkDsyFf*`H~fUiF6~s zkuO=nmq<7A8~G9i+;Ds&zcIf=0XNi*{6@Y+0XNi*{6@Y+0XNW%_>!G`i2`n@8_jRz zOIGkDy08=ZjeN-pzC^l_-Zsa%Smnh(d??dD_ z=9ehohPsj8m|voR8|p@WBVV$DFVV%YXnrGKqJSIJ8}TJO`H~fUiRz8~M!sYPUn1Se zZ{$l>@FmiX{6@ZH1z#fF$ZzCJR`4a#jr>NwL;*K^A0oezFHyh^btAu#FHyh^btAu# zFHyh^bR)i`(rRqo2fjoXF{Am7e2D^XSa0Mv@+Atmp>E_i@+B+y5{*OTH}WMb_!8+x zej{J9f-jM7MBVVF`8$P$lZ{$l9a6{e5 zZ{$l9a6{e5Z_F=IzzuaHzmYFdz>Vup5nobiH8#JIFPS2~WG7#ufE(5u`Hg&u0&b`q z`Hg(ZO1@-@_>xMivGFBeGDUnzrPa7D{5C~=Nu|}eF8nq{d`YF%xGwxQMSMx6)wnMF zHbs0%rPa7D{TA^hl~&`rnBS&|FR8SeOI>j_@I}OzR9cPe(r*!8QfW1=i}SZB;!7&6 z#&vNXFhzVxrPa7D{TB7dsk9o`rQc5C;A+nC|FU;>y>=YuvHmL?%#97u!kV6M-T5OY z2^`smWgrHE;DDC4ZNf5TP*marBmezW_om5J4@B`@m0Yg7C|EA`?w;zmr|0SFkyhin z^jma4&Pc0qUHUD$A7`Z1xGwz`@g*az#&zkp=zg4&e2D^X;J4_0oRfTs0&b|A)VGs- zi2`n@o2(~K@+Atmp>DFCJjs_R;D)-%dh#S+qJSIfMt&n-qJSIfChN(Qe2D^XsGF=O zPx2)SxPflOmz?BF6mUb`L%;SlYGfezGRB-#~EogHt&!xnWFn~PVyxR zxM4p;ej{J9lP{S%ad3MbB446_8@4y{8~Ku*e96>_gP^^dU47i>w@w@cx|&^Gmwt=* zl9PPNPQGO7#6i$rjkdLye908uk8_eQ*~ynoQGUruzGNp~GDUpJNxoz!Uou7cB`5ik zoqWj@<(Hh~OB8Sezjfl^_UD0o$xgmxitMYTUou5}$w|IM z0XOhl#Fvb;8gDQC7V#w`t;Tifw}>wpX*I4(zeRk>NUL#O`Yp;Y8EG}HOTR_=B_plI zb?LV#zhtDwpX*I4(zeV{aBdx}D>9;7qWTe%&F8vnemyEO;*QMVgzGS4; zxGwz`@g*az#&pS-Oi_NxNxnn@H>ht>e#uCy@%GYh5nnRWYFwA~E#gZ?T8-<{ZxLTI z(rR3nev9%;Mp}*Q(r*!8GSX^Xmwt=#OGa9a>(Xx#Uoz5aT$g@}@=Hcqjp>pvnIgVq zq}8}C{TA^hBdx}D>9>e48EG}HOTR^Y$w;elUHUD`FBxeyu1mi~`6VN*#&zkpD8FQ+ z)wnMG7Uh?Wv>Mli-&(|%jI)w}dZ|F1`mS;0C@(_!8-AH~PB03b>(e@V#5Q`ugL#^jpH0 zNLOEfT$g@J_!6a_z;6n;VLt@l-=qt_Dd2{>!S?{^!fy(=p>FW~O}g-#0&b`qe1DTJ z{HA~#=q7xLbm2Dz+)y|8{w7`ejeJQ<_!8;TZ{$l_Ck}4?J|tcGjeJS##6h4-zmYF# zojAB%mwd@VzNB^HAkd}X$d|NE90a=b8~Ku!+>fJc<>)u^C9M+&L3`;p@+B?dOVnQa zjeJS##6i$r`i*=^>%>8zOTUpXX$fDVexTpTm$Za0kuLp4zNB^H;P!qXUviKyX$fDV z>kH{O@+GYk2SI!3H}WMd;Y-wB`i=P|E#XU~OTRI{q$PZbbm=$pB`x7gq)We%FKG#1 zB3=58d`V0A66w-!BVW=IzC>v%Tu+iOX$fBC$iHOIpI0 zNSA(Neo0IC66w-!%r9vPUm{)ljrk=l;Y*}TzmYF#311>z`i*=^OZXD$(r?T!X$fB< zUHXmrB`x7glukmwF~6iGe2H}FH|CeLgfEdU{l@%~mhdIgrQeue(h|Nzy7U|KOIpI0 zNSA(Neo0IC66w-!BVW=IzC^n88}mzA!k0*weq(+~OZXC{lhAL>FKG#1 zB3=58`6VskOQcJ`F~6iGe2H}FH|CeLgfEdU{l@%~mhdIgrQeue(h|Nzy7U|Ql9uo# z(xuz`i*=^OZXD$(r?T!X$fB< zUHXmrB`x7gl=eZtF~6iGe2H}FH|CeLgfEdU{l@%~mhdIgrQeue(h|Nzy7U|KOIpI0 zNSA(Neo0IC66w-!V}40X_!8;TZ_F=g311>z`i=P|E#XU)dP2W3zoaF6 ziFD~V=9jdDFOe?&#{80&@Fmiv-5Bfey$)!27*-j6d!e91_wab0}xo+G|wB446_ z8~@HbM|{adzT_ZZGDm#LNUQOF!1wMs;!8$ajqBoj_Z;yhBdz9IR{=NZ--s_6X*I43 zzGP1FOO*BizbW8`?bVET^LM9_R^#mjUouC0$wa8i7C;^-Tdc)YXg^=%T(U;0C%8Uoz5a{CS|?lKc{-ilDwJ;D+th2n79r`lf&z z>S_c6UHXlD$sF+|6Z1id($(JbLhPsj8m|voR8|p@WV}6MOZm1jijeLm$ zZm1jijrk=CxPflOmrUeK6mUabt>}a2fqo-jGDm#L#QYKk+_1fo-^iDoNwL;*L{jr>NwL;*L{jr_*^5(V5)H}V_#5(V5)H}V_#5(V5qH{wes@+Atm zp>E_i@+Bwvk~!i_Ch{dG`I0%}OGa9a)p_zIbHtZSMl?-y*(bq}7-%`I0%}OD6Iq z3b?`i5b-4=t;XBS_qT{InaGzY;D+su>KpkI1>8_Ks&C{=6mUb`57xK;`0wX`d-m$Z zpC6xn`t0BS`1ttM^M}uW_WARNU%Y(t`sG)T55IZ+_~Ogw56jC}55IkwK3QMBdj9Z} z#}}_(zWT$%PriQr_=BH4{{F?cU%mO^v**wL^7`eUU%q+ypO4=>`}E)c_Uy$QN&N2H zH~l~V_UsqG{Pkx){?})p&ijIW+FhS*yuBOtY5VHu>o3(r{qFm8eViLx}=A8}uv{hYykCiUw9UXzO^>0C$i9r`0Ef6kHS_R8S<3_)6pH{)Li7xhO)erO=&H)zt0sFMlrQdK4u&PVHai3NztEeCJ?_aMc zXYSLg@<+O;Z!`C4<-kane&ar^dOXsl-?&e!VA)8Q^^Ne6rAr`>T5u&S%yncuiiyW<>SRhNF_KJAWu z+Nv)7#(i1^%SO)w{l-$3AUQ7yGoD zW#~8T(^hry{x-$3AUUmww|pz#aRvRbBdx`?NdG0Ty+!Ppj%nzu_EU zRhNF_KJAWkfK^@kjpqP&oCB=t>UZWho&(%*4zQ}r`o?pBJI(=Cb?G;r15~hV;y0WF z)T)W^Z#V~7Z7==CbASq#joM4U@f_febAZ+M(r-KmxZ@mPQ5WX`)xY!`&H+|+={KGO z+;I-Ds!PA|9N>;~fK^@n&iux6fIH3sR(0t&o&(%*4zQ|AzwsQPf@PEE7v}(VO$Ggi zbAZ+M(r-KmxZ@mPRhNF_Ilvv~0IRz68_xmmI0snN#W_IrFa3sdfK^@kjpqP&oCB=t z(r-KmxZ@mPRad_=zwsR4j&p!jUHXmZ0C$`Ntm@KlJO{Yr9AH(K>q(vi+;I-Ds!PA| z9N>;~fK^@kjpqP&oCB=t(r-KmxZ@mPQ5WX`cYOlK{x8k}R(0t&o&(%*4zQ|AzwsR4 zj&p!jUH#7d#&du>&H+|+={KGO+;I-Ds!PA|9H4?_llq2pfZBaxeZx7xYJ2H7o&(%* z4zQ|AzwsR4j&p!jUHXmZ0C$`NEb5XknaP*z5nr<69H7RH`;!r0vf><|bou=);!9SX z1C%bmzeRk>igSR{#eRu`WfNcE9H4aZ{Y}BLkuK{S`H~~zOIDl%)NU`nza0@@vf><| zbn(4g!Lm_5&~M~R6f7I)Zsbd5@+AtEjdWSx$d@QsHqvE%BVVFm*+^IOlhrr!B?^{} zbXniXmmCpavLR<$&l&v|@g*Dil7)Q95%DD(a;Ehagnq+0z*@c7$d@eSOB5^{jT`*7 zkS{rK4zSo>@+AxTk|W|vHu5D4`H~~zOE%<8Yur%Z4%}m2?Faa6AzyMte91<>WFcR2 zM10AHoN4s~{TA^h8_oghD<0O92XdyX{fqVFLcZjP_>v7d(`qm4Tf~=aI0q0&*3M10AHbAZz2dNSfmHk<>L zF8vnqB^&NB*Vk?OE#gZyoCB0D>s!Q^Y&ZufUHa|Ae986sfX}~p{rF$cAEwKX=BCpC zpJ?~-;V0j|dGoc-1e`i`x&Bx|b@g)qcWhDhGKiM&mdjw>&@6_sOtKAk94umFk_#gs_XAP(xu<9&rsF% zb(nPNH|#T1b?Gk`Rtv{}pAG=tIAM1XP8FQ`O~k zNNi>XHdEE5--yl3z-Fqt^c%668Q4r!mwqEQqwnO2-x!~L5}TQU%@o@UY(|IFx!eaf zQ`M#4h|SEvW~#dM8?l)g*i2QIej_$B1DmPp(r?6O^qo9;9vGi}5}TQU%~abwP;+Q8;V=&izkjx-AKRPx5Elw;DKc%>@N3+CJM5`E-nYZv_CxY@ zVB&3Z=Y2cu7h^ek-wu1*5B&Ol-wu27+kHFisUPm!VQ>54z8yARS8Lm0pZ$D(`03-T zH;=C$e){!S-~Rd4?a{F7cyqg2bFULVZLb?XZTC05k1j%`>uY)G`dWV7u$Hgt`nMeE zI!Yp4|Fm7z^}Xd)?1Ld}(sh)is_T2p()GP6>2{?T8pW3{zIyiQ0DLR`>wC-6b#zO* zZl-E`eQ#O1Uc991d&@;#AoSApy(;PYyK`07zvW2R(Jkrv-f~sfzvW2R(JkrvVzH{L z-(CBy0ilC$frLa%u*p0qzHDA*ynGaKeWrwe)as}6MfYF=f}U6@uzhH#lD=N*w^Sb8|iw9kuFNi z42r$<*-pA%Vx)^lKDy0Dy8g&Z7bQlqXlBu3dy$eTT|DwLQWC4W{>V!gkNk|3#Hy}8 z^3p|#Q7l^24_;!Vi${J&N@BIWUSgz+CEbja#Hy|@>7vBDr;NI$A);HkZYH#E>;NA;yZ|Q0TZXdTk+TIWJTY`J9Qy*>D<$5x~y`{_ghVNVI z2Y-bsKEHjmy}evdCb+lSOTPj4UL)LFy7U{qZ%H@uTOV!f2jJe)jr`U}+jZ%;1ou`y z&~L!K)!xW&z`YmZ-qMZy*5Q8d2l_3+z1OLaw(HVw$@eYk(r>`M)en*1`e=K5>9+*; zR(t6;;NEM5drOyo1MV%|$ZvhLtsj7UOE>acA8psA-xAzg{Xo9~_f~r&zXA7NhC$f>{=W5L9CKxQfpqD&B)veo^c&I()DMy0`e^&}K))sF1!^z-hV+6pN-vNu z{f6`c=|+C*qiy{FTwA)4-}-2~F8!9I7pNcTH>4M+y^-ILUa&B|K)R9Nkdi1}`YlN> z(3e%#H>4M+y&8er*S|=*p_DiDl0=1WZ zLwbSQ8~F_>iOY%ff~SxEK|j!MNH2K$=pX3PZ%8kYZsIql7pNbwUlOGk=nE*zj1(JwUN&k*@nqx~Ol8MT>OZZ_>s0H^rhQxq=*UiyuQ#{$Hos!P8S@mPR(6m^MsT!?rqKs>6tUfkR?>e6pWNn97CBvy6lH>4y=S0iw{FTj_q7xEMQz?Z1KtZzt3thSeaBVV#ad`SaeqV{q<8Sy0zw{S|A^)2E{l+A>CLB3>(_>$H~ z`|7=0?PYz7_>$H~+jUvrBEF>c(RN+dw}>xkeY8y%w{WftZs9CGzkRe_m+Q%hFKK$H~+jY5~jQElUzGS_SFIghKq=7GyF8vnqC9RLP_XF3H5ns~4m#Dq;Tf~<% z+`=hc`Yqy18u$|F(r*!8()wsy|B^3RBEF>c(RN+>E#gaBA8psA-y*)GfiGDvxP^0F zBEF=7FOe?mTf~<%@Fmiv-#*NjTqC$Y5rX^j)gPWeY{yZ@ZpUW$^)P7v+)s9lYen8K zw?;Ae_z8@$8Sc8U`?yvl&_#KjxIMc1_Gr1iD6bQ@N5{1yL3>eNwSVsYyLq^4xxKLa z#O=||w@1smu=~XA(aqB=%DS+-_RrZ58iAmHQC=r*kB)0aZq^-};r9G;dvshY66oUf zapLyqxK5@ZGxKIgR{Sh5xs|`sM%q{O$iypHmt>HLMqUNt-AiYRmU+ zQQ}jBbm1kvj7Pfg(uH2qB0kcEmoD^@ihraFFJ0&*6_H36Ub@grtAA>!dLI`utrvP} z^`PXkF1&Q1msbDOP}YT)F7%R~yr6$)d}>fXV5zGAPo#_5b>XLm)lZX_`vJApA=LufO=y z5RNePgRkOWRt;%-QF7yr*sH&RjwF0oui(S<`UsW~BOVwUZyQ(?9s%nOps;yPK zs@2!3s(DMQ^p?B5sOsMprAlx4$?>YHe)rz7Ql+>2qheLnyd_n7%RebrRn1#crMLWp zVpY|=B~^OMKPOgI&0A8XxBO#bRTbXyPliCs1EmLC<@ik;r_&xqBw z!dw0kvA5MK>6PkrA$|F!zAja(rEXUO<8kah0qZ7RpMb|s)J$I*0ral>)KS@b?tGf z>iS&Vb!{^4y0*|M>uR*$&&FNXrsJ+_OP#W=&BtBWCgiSbi=DEr&B$HXrsS?`%bl{W z&B9hUaGd~??L`}-=}9qFlzd^PtQ;NaG#$0 z<8Yszdm^X$fvcg~^!)kDKmX;cm%o4c_~pZ|e)g+}_Q~ajr8ICoHG%L)y0&yG>vHJ?Tu(7W_D!a&%cT==J?YxgsjSPj z6L3B0S}iQ=vK9i@ldi3u%DP-T0oRkRt)0rcTsr~Rldi3us=C1Sjsv)!bnR88tjkvw z;Cj-vSCz6Z{RUi5x{=?2>!}}D3mw-hx0ilH9F*d>BEJFGQ+xTUGQK{%+Zrghmwp4T zr}jpE1Fm-*h=Y=DxL&!vtZ%^e)ZVDR0oPM|xi#RpUb(%jZ@~2wcNf(+;CjaaTu-`@-+=2$ zm+yLx>y`U~^$l@QYHw8E`e@tp3tUgSk>7ypsUPS!$MvfH09;SHTu(Z#SJq{HLmZU) zA*yePgHn50-#iYg++Nl<#6c;pF{*EfgHn50-#iYg++Nl<#6hXOk>3ypbsUI;l5SMr z5C)Iu67^NjLHv;-I8Uzj+)~ zxgY2^#6hXOk>3yprS{Tq9tTxzFXEu2OTT#>R9TmP!|lK7hsbY;gHn6xH;;oVx0imy z?Z1lmjr@i) zm38U2o$qfR2UXV9XxsY*;-D0#ZSQYoUDh|mK}pyB*8i1C|I%-WgOaZMt*T4E9jtF2 z2UYF|`VDbVYH#E>#6cZ;5wPHSks;o=DAr4CIb-(rMQFtB@ z2c`DXZ+_mX++O+(XEYQCZ}qLLOTXcahIHL;)qbGga7IJAk>3ypbsRXOA>GJteY9=f z!5IzddVMSU*a2;QtaCzpm9G1(rYi)W?SMpSTiRIscIzX?k8`F9>G>3825%DSj;CsD!K zQNgk<{B{x*oE;S`>!QA$L>FQohGv9jC={M8!PM5Z{$mG-B?+dej{Ik>&D8u z^c(pSTsKzMrQgVx;JUH0F8xNnWOlx!tV_R!}vBVU5+#;UsHOL*Ow{#zq( zwO>+vA0l7E>&B$35eRhYH}WO8Zmir7^c(q-+4+*PF8xNn1lNs~b?G>FQ(X!JOK{y-_4y@V!t2IPTsKzMrQgVx%+8mTb?GMQ);JUH0F8xNnWRCa}UN?4}b6Zmil~ z@+G`(?8J3rWnI=c@+EV`m+-nV^#ji1;JUGLds*Mem&_4g!t2J=Uib~yja8ptWPnN+ ze#3QRWnKD>d5?x&Mqt$!ohEW!`Yqy1M(~*H(r*!8GJ?lkmwt=*k`X-Sy7XJbmyF;s*QMVgzGNhi zxi0+%zNGeEIFiR)mwp3ZQq}ePCTx&?i};d}Jm&4C-y*)G;kq&5h^%j(Us9bX`)FHx z$(P`|v9d1f8~KvO^GnLQtZ(E?aNSsS-T_~t{-xi*mlWqoTsJ0N`pxr8%I#%+BVU5+ z#>%?>{-*ZQZ=PRL)}`Obmn@!NQr7kLq}ofrd45S*m-UT&39cKfKEKE>5&p~i2EL>? zpCP|Qx~y-WUs7%_{YJiI@%)miF8C6)mwt=*5?(hZUHUEJOL*OwbXng#zogs`^c(q- zCE`nX-I&_T`Zk>Ko&za9XSi-my7b%l%Wv1E-^iEXy0LQqvc8coSv^d;7ody7U|PlBzE28~KvO^GnM8K)*4+WQq8a zkyhjVK)-o@Nx8kOZ{$lB&o3$K(r@HT7SAs!>(X!JOBT;Bsn%oUm*^M@>l^rz;`*$Q zwv8M4lEw2&s_g||qV}@Bd45S*mwqE(vP68zNUQOFV10}Dl95*9x?E3seo46>xSk|m zvVbos&O692(YUd`d45UN7k#v?AIO(1o?lYdrQgVxES_Id)@6MoU$R7eN$aES{lNVa z&o8OA7kr71lhJRUUsBek-^iCN5nnRWYP=ulw}>wpX*I4(zj=O1xgY2^@+AxSlA_;` zU!rlN-;iHY)urFamn_IHsp`^iH}WM5_>!tF{YJiIL4HY57kr71S<-LF zFRAM4clP{}FIghKWTe%&F8vnqB_plIb?LW=FBxeyuFLgg#Fvb;8rP-YkY7?I zWTe%&F8vnemyEO;*QMVgzJzzos(;}(-K}Ns^Tp>3e2H}7H{3B>UH|scwtgUAf;(o* zy7U|Q65KIc)}`Obm*9@svM&8bz65v77IjBjjrTA7hC61q+t@xMQ}g%l#7aCAed@tP8*Kj@c7;%of+xBdzB8IpZC(($xrD z@kX_E)JUswUF?_Oj@fd1;WyqftM+OHZf`I75(V7&`R+C1OGa9a_XFzN8s(Rav>Mk% zeOn{GWTe%&F6x`^)V2Pt)uEAAMp})vmwd^J{E}*WQQs!! zm#h(AGSX_iz4TkemyEO;*Ts5rjrfw0R^z(#Tf~=)v>Ml?-y*(bq}8}C{RY0I_&oH{ zc3t`nd`VRo^=%?wvVt$E>e6q_FImBtRCQV3$d|0(ORBo`8~Kve@5iaup+4F+ZsbeW zh%XswHLgp)`TaQ6_L47|$d|0(ONw=#e91(vF7J+X={NEvx?(uerQgVx=tkm5mwqE(vPOK#NUJfwkuO;z zzGS4;xGw8k#Fvb;8rNlgi};d}R^z&?ZxLTI(rR3n^)2E{Mp}*Qay>cTtZwB%Mp}*Q za=&EEG`H*0Z{$l>zaOVMpCP|QF>v6y)`%||X*Jdl);GT&r}}=} zf9LI`-@um?+uO&%b?G!tF>l^u!6?{omm-UVLB`f%nsxIpr`H~fU zNmZAABVV$DFRALXzL76kBfey$)!1`JzGRK~l95*9y7XJbmyEO;*QMVgzGS4;xGwz` z@g*az#&ucWz?T%)XSg5doS0v-f-kA+(r@HT)`%||X*J#ttZxxtGSX^Hmwd?@@g*az z#&ucWBEDp#)wnMAOCr8xq}8}C{RY0IIPZ`znaG!{;7h8ytZ(E?R`4ZNUDh||m#pAR zs=BOi%r9BNmsEA>H}WMb_>!tF>l^u!6?{omm-UT&$qK%ts>}LDzGMYoQq|@A8~KtI zd`VT8-vh{(tl&$Ey5vhH@+B+ylBzEKM!sYPUsBbj-ALpEyU$TNPsp`^i%r9BNmsEA>H|CeD;7h8y^c(q-4SY#emwqE( zvf+N5sxIpr`I0TVA7`Z1*mFj{WJ7*Qao$0G$*F)F_r-?%lBzE28~KtA_v6%bM_P^d z1N^q(ew?bV#@BW6{!~HllUyQUG z*TwtWhWl}RV%e$rkY?BdzAT9~5xI_G-qvnFASVHLi>Lwnco& zNUL#O`Yqy1Mp}*Q(r*!8GSX^Xmwt=*l95*9y7(TjfiEdOXZe6rIOE&N&RbBdxe8~pBq^e85kuTZ6msEA>H}WML_>!tF*OTN+Ht;1? zUDh}9B^&sXsxJLTzGMSmQq*OBNn?J=2EL@KOTRI{WQ+Kckyc|qW`4;Q@g++iZP(>` zGU7{?KH9F!^<>1CjIzTuN#p%ETf~=)v>NXRt|ueDWTe%&F8vnqB_plIb?LW= zFBxeyu1mi~e91_wFvBB_zND&4zmYH5z?W2YS>KpnvVkut>N3AX z0XOg)_>!uwe&_wm_c!n*Rb8$pc|Xn;@g*az#@kE3MSRK9N85Gjw}>wpX*I4(zeRk> z!u*m(zGRE|l95(p?PY$+7V#xZA8ps=`&-19EX*%azzuu>zNGm4k}qlGOE&N&RbBdx ze90E^B_plI`9>e4S^8+ZF8vnqB_plIby?pczGT7uIA}Tn@+BMilBzEKM!sZ=_>z%UW6v4$OSXtFS^8+Z zF8vnqB@6iy1>9ghi};d-`6UXtp{_>Y>U&}FJ(hfl0&b|Q6@8$~^(6U{4SY$pz4ROT zk_~)GRhNDvU$TQQsp`^i=9ow(rUaPu%6r_zGS4;T}2G6haCF-_6fBog-vrqNd{O#F`H*a3Q{N1;29>00^ z>EE9H;+Mbv?8pE5>{DHp)(6{Vv7Fo;FR99+y3M3Z_Rbr;pVh0fFx$+_adwAGin7cu znVDU(J6lqf)uZTrORG6rQk6wzn|U+N9+4#@r^cI$H@7_^OGZwO>*CFAkI0gdQ{%dH zT11wNoEp<5S+avHDb6^&8As7JaIljl)yIKWn^@Q!EUC)UY7^FxyK^N)Sz;y1wP7dN zGO{X5t4*|;QzcbdT5V!cbEu>$tKaz(MyEwg$=V0nb?LN-DH#bhu1lvyOv%bSaTIEU zhXG7U(P?B#6lz1=K2o=yL0`#~DAb0!R@I7Uuh%}>*1u#*_J}DN2{o=uvqenFNT_jL zx-DW#MnaA2(ryt`G7@TBmwp3NQhd&OLXGRvZ(vHQx_D<(s12SoFeO!8ytB<@N_H?M zRb4J3$&~D1N~*dnZDdMzFeO!8`i)G<4yL52OQvKdQ?i38sp{%?_MDL^*(0W8B-FSr z{T4ALBcaB1={ILeie-~X$;>Npc1KF8vUD47#MzxFsmju91WI-XN~*H-8hMi4d6KFu ztwx+=cbuduOQ(@0*+G*O9YLBzaWEOWbLEv?PX<)Xp*&$w&{{4*+G-kb|Y8PBs0@WcF-hMUD}N_$qt&N zs!P9-CfPxg6m?0H%%n;7h$b1?G(K)zNk%lu$fj{!RXIgzNt5iLNvgW6Z=^}~h$b1?H1_;5tz-vHQmjLLv|X2e15HxZWqo5>$qt&Ns>}LD znq&t}Qq^UBBTce{CaLPuZ%ixML6cN<={Kg8>=8{evT5vjU|Pu@(Ig|A#&x-#jA)XP zP2;+(Z=gwvJ|;~vlP1|glT>x-H_{|KXp*Wf{YIK(k7$ySP2>H``WDe7Bb&x_Nt5iL zNs7K;TFFeBWCu-B)urEf8_o`zq^isMMw(;?O;Xe)O)`@v*^yRKe9lOd%%n+nq?J^4 z`TjRx+9y$o`)0l?Ep zDb9xdpcTf|^H9~L-w2f)4wY1W%(N24*|5DDf!o_ltYjfpa(G%v@05a#8CJ3oD>)LZ zWF*trQ%0=hNU)L-OyjaNn`0%_PC#u_lnutrsgkNJt;V2|!=aL@ES*NC|r2Na)2o*R!ruUEX*l6z?4*VS=pFVazsqYNTu<9 zU}cM#lC7uGxGv2GrldIYk||l3Q*wYQsp`^hWJ(S&B~@MejZDcAF(o6F#`>2`$q_Ln zBbCN=xsr^Sl95W|x~yywQ!-L%T$d}!h$$JVG_K2)B$$%o^Uz1zb?G-SB~@MeZKmIx zDXFeV2$d{^N{*rQeqOJ(mwqEvayV5|ZZG{ttmJU4r21yTdvF$VC5Lk*WnHc$36>lV zmXvk*=0>vQh{%$ykApqGBukEnEZO?s<+}76$dcl7)<@fQ={JxiRbBdxWXS=tq^ir+ zB*~H^B1=XpjrRlJ+#<4MBUz##8?5_4mK4`JBuf-zL)~aS*+<*@fn>=6vZUHx`i*4C z0kWj1OR_{kHtYw@c(<>s`)GSV&~G41iqCH!ZP%sWK$cW>={MekbAT+V>e6q#2j>7; zQq^UBBUy5QEUD_UzL6|BqMVYgkG72)$&v$PN%i@q-$<4mAWN#c^c%^N17t~2mt={8 zY~VMLB~@Mh&ij{si^!6ZO5?ip8_1I4b4Id6K{o6Mjlk8sQ`M#4NR}KRORBo`8_ALb zWJy(*ej{0OL}bZGrLl1%S#m^V$;O-#1=(QSK$cXWU;2$?$pNyYsLOkB6lBBpM)i$3 zB?_{ku73$AJ`W^I6l6nP&3L!_qK~#e5A<6^mTY~rU6;F)AWN$KK)*4kC6HrO*IU9jAu8Y!k0xGHM(r$!GPCzA9UHDBIHa_W`5mYh)X|DT0 z88+1IGs3M~v?Gwlb+MGx<=UoO?Faa6B~+qIZcVrN{4%CwWlYHlsHCc^zsvi9e)F7? z;#T!es6-hy95-J|7W=m&MBZNd4Nyt7A5h&^LM11ll4^V5x0P4m=yH|ld7$42m7IV| zs_jL6TM3n%9#m3(9j$QloFGf8?PYmmTFDuaB|FnfR;HDlPL>p>oj%y!4XkbsmQ-cwHr{`8 zI#)7YH9o$vGm>e%xm-*-S5nrc+sKtDd+~a)Q`Tj1BUf^cGWqUhsH{u3kt;c!D=F*J zZRAQ$=Ss@DbQ`&n)47teF5O11i6y6V zC1qVMCdrkY&XtsP={IsEr*kD`UHWZdb#tzytV_RK)C1qXuZDo0LuB5C>zw!Q?)47teF8xNX(X!JN>1lWs=DM# z6lsIEH|I*qy7U_pOHSuX%DVI$6H89#O3J$Q8@ZCx6HCgv^c%U7)47teF8xNX#0BVeU8rQ`+oD*D0u^*UNvNEycbgrbjsZ6j$kv8mK z&3IQIH;etyN89^>yOR-FGV*C$m-{77mX!N}esi=$2^Nl)ly&JhXG^+n@6mVrCDo4% zOe|R)F6p`&fk2n_&Eb-+s~PV~xBC3DzByddbu|KkF6*1aC0$n|aHU&&en&oyJ!cM= zbY0DOfv*02*EPR&UH4n9e~&)eu4{hlx*CD2_EvRS-~9fYuB#Ea(yjI{{pN`!(v9Gf zkx%3OVEZLq*Zo%Q2h=wSUC)zU*Zo%2h2J)ZOS-Q6t=hlvn<8!4UiVv77k*Qu4Ry_L zz40I41|RV>*Tc3sThhD1>{gZ4U*)oNTZEPzeXL!VZbM#4@o6AhqCgw=Zsa!Rm28fd zsCy%{WTex0KhSLvT5|NkHeE+cdV3?c@eZ8L(UPtkxvh`3x0h~<(2|3BB?`2`^AMpW z2hkD*+ECZ*R$T2IL`ybDOM3r$bt}#~eYCxQ>9+_iIr?b3F8vmvB_o~2bq$?VKL9N$ z&JTUGU6+0XT2k#_`pwaj-d^`xRhQMx(UPv~eyjEa{pM^**Y)aF)n#>awxsJ?bt|sc z53(hjvn5^E{Z{N>vL&0dC0*D3R_q6|C0nE4BDUlpTcTJS%sUZVGBRq+7tWTbAHbGW z`s9U$P~eUxd?jBfBxQWOKNr>-x)Ev48t$`*TLSIb2em&KO#vR2w`G zW5Mvw7S-iLA8l_h%bUX`WnKEs;S%+)!zJZ@px+!W>ALQ>>bSAIIb70pqw>~A+xpkx zlCJB1EBd03gX?lR>2OK4fBWxTm#=RQmy~t6oOHOP_k;Vb+7I-b!zEqUU*D>_*eux` zE|IRoCFOpg-yAOKy8VfL@8jb0%g_>~+F*WgxTNZ1hL$MRhPv*zYX8!24wv+PaKBai zfqrwir0crhin@eLHit{PuGP2RDTPfKW|k<_hTUuBttv~mIa<UTCdI9bwV zBeV6Pc3l=XCrhdiFYm(HoGej$oh&KqvbZ@}(sg|?S$)V@+?*`wx_zW>o*epMTmL#) z(sd)V_0e`+?v*%MQte-oC7Y8ay}f3(vaZI#+e^1OSyI-e-JC4x?KQhqiv<%)6lsIm z!O4=cF8$_YiQ4OANm-Z0&B>Ck+nw$=~ny7Zfq zC0#f2TOV!j2l~y)lIpmTEZLka>FssD73VW1mTXRzbX}`%RlhN@WOK5l>$=~HCk>wc?_8~x^FN!NA1Rdwk%Cri3+q*Zn z>AKN+l6T=K(#HFDipY|YPh;~h$&v|VN%eW4-$<5B5m_<;mxbFV=Sr%w>MWPVVsZjjQtRB2P~*Dz5HJBNsp`^f z#7d?JD;Wtj-d>t5!b(O$jq74(a*D8$kx+B3t56$E4iQ!|5^7u*J0(+um5hWM*Tt8B zDatGv2{o=uw|Qns(H4v>QKk*M*Vd9%S-5TYYjDKy04piFf>_D!i6vb(DQzdQ5=Gju z8?3Zdy8$anCE7qXqDn?QjXw-D8>o_M_oA}xq)MiUDmh7&?4(L2P$jiWe3B|rq7C~u zSxKIxN_J8uQ$&@Fcp4iwQY8}tON#wKs$?fsGJz_o>S86idtiy|7EvW5p2quub^}#X ze11Daf+5!i8k;>M3szq8tVsAB@?KU>bPMk zxsxiHBC2G>(|CJX-6E=F#M8Jg7n7h$iv2*UWG7WJfhwu$Vlk;i8$J(K-ikXKBcI0m zfqny3Qha{XXhkVqDUL`Lxh!#d>U&nv63mmN={-WJF$`}!b(OyjklMJ z$p|YM`82LezeQNd$ft2#`YpmrMm~+}^5qR!N%8q5R_K42Oc7Rc@-Cd6SjiM&B_pB6`hi%<6k#PNu@Z&aVBU$al95p3 z?WNx$tYjqAxGwz`VI?D>#&zj8U?s)+)<@fQS>J$_RCVb$VkJ|Am5hWMZ!i58VI?D> z#&n65Oc7Qx5^7wR>q*Znsn%oOg|ibYnIf!YB-D6&>9+_g83{G6OTQ&p$w{naCss0f zWJz)Nfj8mo#7ZW|N~){AKGxm~bQ`#mqT9%o?4DSns_9%wwHvsYBvvvxR#KH^Z6j4O zMO4YjdvJDAB~wI|jC2|sHBu!LsFLEEgjC7yc_n?+lCN$foyOZsuSHbJNT+dK*0zW$ z8R;~x%i0F2q}actN_J8u6R47^E^8a9k}0A}Mmml618WR$#pi)k$xfe6qdN~VY^8R<0Mzw}!~m5g*6(hk=`^m(`Ua|`_&o3?oSjt36j3E7 zsS*X+_&axtsFIOR-S;c3pmZ^UH7)R}p|EU6=KZ zU`Y$WlCI18#=MdifF)g*uWx=Cj`|@0OS&%J-xO$r=L}#;^*Mvz4(63KfF;%E0e(}U z4cn^`xRKWG{ebo4!Mu{@U`f>%BufsGCCvj%O7nx-+eiD_ZwjIT%^ez?M{X={H7}G_WOAUHXk|NekE#J!gz8Imni@ zfGz2|^qb#@qq+&Uq}mVk8`+Wuwxs%;(Qjl+8rYJmF6$fFk`}Nfy?^O9vLy{{NwI(X zXq%7yKAb*oQGM&9?Yew_3)m9%LmzF|<$5w;OS&%o#>kQuuq9oW^^I&v16xvj&iZJ3 zKX5%6uqC~{^c&fd7O*8D5`hlq>2UANL_>y9K`)J$z z>-XWPZU%fwZ!hZ`Q%f57l4^Td-^iD=fG_ForQgVxw16+^y7U`UOB(o+;`2+s%lbyXq&Z(w)g@nYkS}S@m*}zl=qYqH zm!TyGLra?DB~@9vjdV$Kx}@9-bQ|fC=5$F}mu@3n(wr_S>(Xt^ENM=clyzC%NS8FH zOUk-*8|jkfbV*s4ZewOibGoFgOSdtzq&Z!3t@|JU{rqpwUcLD9(74tug^Z66|&&Z%dz{{ z+V#ZO+OenbvDu^R`tu@Pd;93ReSUj)lBBHb&&z?YwOv<^4Rrl^k*<;LUANB|x3|}y z7wOv9+ODe+2z32fk4;iXXzT--gPwsfiC=pueH+kueIabOu=vXTC4WbZ~nEmKXesY+RZ=K_U4-1 z%FU(S{9|p`HM^B{X*d5^+jY%uWnJ3MKh}0#v)i@qeR_WR>dTj3^wOh#x=+t<`@x=< zYWcfQ&ri!1z%=*i`Io%O`1wEVblZoKUWJ8IS6lKV%PcbjO}Z^_!i{NN_#eRE^% z)q+IVYM*{n$ENH3)8KvY`KqekKMj62X>#9tej;x8Dfv!rye%hpa^tC- z+{ulxD!*@Td?&DX-`sebM(=yiPn&{wupO+9Ik=L z`=Rc?m(}~B?)$01_dMjC-1zQQ`JLPt()5m>t z<9=El?Gz?aoKxp5~q zzVGdX&&!?MczTRG2PnBEzeVYaM zz32Ph^Bt^H1-6@_`@O$bP3~ab{|K!6$>WRHFJJxP`NMV`vAKfv)cvNZ0oaq^l7Kbe&g|uE!`#*AL?r`?rtwmEEQ5XQidGl@ByL+mvOTQiT+Zp+-kG8eCeCZ z;!lrn9{%|F;>(9GUi{_Zn=f8J{@24lOqU$8<)eYTRU%~n-epR6S7la*v`vZ~7ZTqRkbtERPA zi}!O%RhBN>=(3|Ly_>44vUC|%25N2MGAs-xE(|1_xU7$}Jz!WDNH%d|3k~)CqK%uL`QN`kl9yF7rh}RhBNpnm~PRe*N|9AO5J7>*_Ku{;)68;w5ES zS9{pUNzbppd=xPEJzEvh^`~9B{OMWw9k&%1Q}d6%wLm9nls z@Y40NB3*mn%er1yr0Y+-bgizGb^Vc-t{0YN-RzMs>w0C8u0QkA?T`7p%5trH{m}pX z^@~3}zIyolFE766kNsErAC#Z=%i5RLSF_q>o_&-r`x1<@bbXYi>!U2)V3einqbyw? zW$6Z^EL|UE>G~*N_U^Oq9*qxgP)gTFS-L*T(*58lf3L1DATIOb%XI150^<7V`CeUL zr%Tt@>C&|oL|NBoRq6VyD&1gKRsZ^|DqWvdrTf8I_1Z=M3#DV4`?})FOw)w-PgTcY zP^9aFB3&O8=>~%$T^|(b`k+WR7!>LHph(vTMY~z2};)|LFopQpmco_l&(*L+6xFKLFxJ=C|#cfr5j9w z(xu-{p9G~F`K^z(`S^t2woBx7#A^fU6VK-pFr#v|X2e^L&)5-}-2~F8$UbzxB~} zUHYwk&~N|iFD3o`=ejZ6XPCIp&@J%M{j6#3yGo|Jq8O~3Kb%!vF1}Vgoa^SrpsI_9 zb6TthjZQh;jFe7#X!%M z!4CRwF9uazF1}V2gLU&_P}Sw)Yeg|w`{%mv?%!*Z{*%~{=MU@UH_sp1$`D$p}9Ibi3(xu<}fXw=@wZ+M|m zd+9g4&{W&&YewnPZ+M}p>e6p`p}Fvdrm9Q7;e|%JNqyrB&86XmM!J#T@IoV9`VB8M z#eTpGjdbZZywFs2>9>jX4KFlRUHWaJ-&$1P`e>VvC)T$X`K^z(>(Xy?|I6RMI9L0D zew*mGIjV1cw5`3(-_b7H9M!iz+OEs`Hb;KzqwTs}PtK9w`e?f@{WeGI$v)byOTW$0 zda{qU>(Xy?RNwk&yDt4UM}F(0?Yi{a9Qmz}w(HVwOXRmc+OA8#4dnP{ANSEV-I;#t zT*U43LmzF|rQbRi5$MuyGyT@Nh(MQqo9VaCMcl62N89^>ep@2Hk%DQYU^Y-N#d)0+ zOd|!efr6>((r=_-Hc&8CUHXj_%mxaks!P9-g4sa9RCVb$QZO4Rn5r)QMha#F1yj|f z-$=o1pkS)H^cyLd4HQgK7i{6Bfi1jjU<<3dtZ!for5n|^KH4@vfGw16RNwk&yDsY+ z*urW*&~IQ1FB{mxsxJKowotm!dJ=p7mxeum=|=UfkGAzM_WY$A)we#{uFLwC?D=1o zKH9F!`j+hZUl#27tAAPFl0ARv(r?)FSN}$S>!a=c!1ZLZ=dbqCZ`ku!d!zMaA8l_h z*OMRK^Z)RNPqmkR!&$7$=4Y|SuFOZju}PQp4TrI$8~Lq|w)F!}V@WsiTOV!LrQiHG zR=FSOH=M^(d!zLv4rE;#4rEC;T2J=T_I}{|o1e(4_Cp_S*QMY5NLE>we#4n8^+V*h zKHA=1`ppkzmD@|d;Z)XT^HW)6UHT2jvZNdN4d=2hjR&?jKbKW*Fa3stS!%CF;P&?{ zoXk>tS>OC*R<*r2nk8Mh^(27#O9L=3-N9W27n6K)xz5$q5 zKScEnz`WW^zX6ypwim#>bXng3%vW{kHvseMhsbXL=G9*M4ZwW0z4RM^`O6MqzN$;V z0hpI=#4c_VxOA z1~7lwBfexMUow*~*(1JW1u%b^0nDqt$$D}HFfU!KC-;aiS;?2o+e#MwY|csEM10AVUkT;hV$TREnVhc z!iufMhcL;~W&Rxy~Y~nI}0h26U=3l_7oj{lI(97;0z^-Jk>+DZ|^Xq?9 zu+ASI{_)ipDs`_PKKuIHS8pCZ@A-A*%Bt)O$zP51WolkjE~{freO~!!WtFTK70LSJ zE?FxoRat-BCF?~+vi7)FW&LrNtUvC`w6LO5mG#G6vR+gqYma+X){DwzBGELGUf#Q? zD(gi>vi`WMwO#3*Ijge%xJwrMb0g>Fc3EG#N!E*sT5C(UVr#KMcOmcSAMq>HU3ufzapwKl0`#FZEzE!o6nq?H&TE!o6n9ZmDTrOO;vs`f2ih5%`W z=qK-G9Zd7q^1aMarK{F{?;H3(fBo$@x{{*&_N^(-`%PO6-f!Buu$A`sB=gbNZ|Qo+ zN!OR!iXOI(E9-jCN!NQ$y0+FX>-q$x$b0VKI8<5I^%+XK{!Xj*_Q8F(4k+vT6eV3> zZcEpusIsolQPTCdTIt$KpsI^WO1l19D_xtU%DTSdmaeb3rE9ZPS=V1|rRz&>>Dn|^ z)}`M7RZ2JV8=y+Hmwxk!s@z`s4N#?S|A_q7NBe39)C)fS=1^t1z4RNPO0_rg8`JJ* zK$X&s{068}{XoAtR9Wo@K$X&^-yEte>(Xz4D%B5>-}-3#^FY5jR9S8>{RXH~?T!4_ zN88&=zd2M{ZZG`?s8S*Lk>3DSYUhi7bEvZ1UiuACrP>?$4N#@p%lhU}Wx2hqZ-6S* z-l)C-s#JUFH-{>#?FCdRUDh{;D$Ba`8=y+{LsZ`YRjR#QPdZdtZZG`?s8Xrg(Rz|8 z#EPl5w{z)6egjmgSYr6?aHz7}5A++LO0_rg8=y+H7k)b&sw}scegjmg_9lKCnbS7^ z0;-g5vYs57)2<7@9S&6%`(Z@1xi0G4;ZS8+m-P)$rTQVMZzH13+l%^kI8<3~FY6ni zN~PE*ej5>O*X>oR8+`0gWx2iZn^N7VoA_-+w0V2!H-{?A?Sc;j)egjmg7;x0L z!=cJ*djVBSmwt1ovaE~xwg9TsbC%S%kvZ+-hWd6mR9S8>>YHM!F>Vf3mUZDbrMgi! z@*7i#6;n-Jjlj+O8Y803`WK;Hx{V_88&ilEgmy_cd4C%bZQfq`%|pAY9>h~^U$ucF8zkkF5P+(`3<36 zx_^v*^U$txds*Ka>zjvmm31}R_MA1=HxKP9>$1Kz`prYTs=5g6QvcF#9@3Pry+&)hNZ&Q1@o^-se++M6F7w~OrZ?v97XqVbczd7JmZZG`?!fiU7a4YL#e{uoh zCf%sMA+$^P{n2mExRu*WzX5Vnd!zcs0}2Z$H|a*}Nnmd32l~x1w`xBiv`f0IZ_c@u zby?p4x~U(c`UcWX?PYy)(yiQH);FMTy3H!tFWLHN+q@3eO}bHi1MDUqi}lT6w{kzQ zzJYdAd!zLva5uG=_04g&a(h|dz`Lovk>3EkslD`@18>##f_RfI{pQ45S(knT@}_=> z{D#mjwU>T#=B?ab`VG*VZh4FR)<@g?2I@_^k>7Y?VFC6g-Kf6t$if2dO}dfa0KVzo zS^CYvxAM5rZy?{)-pFr2-_&0E%|pAY?FIWLUHZ-0x3Vt%#)~=*hu_M&Tu+iOIU>Gf zBVV$RFF7Ks!Q^jEFXyAIO&+5nr+)v`g)!-y*(bM6`K( z`TiF1B^&vYg?z~o@g*ao&D%@AMSRJKXmee@zeRk>h-hGfLui-o6X*L|#FuR3OBV7aN5q$mh&JyB`Yqy1Hu5D4`H~~z zOGZSSx0im4_>vLP=DPG-#FvbSHrJ)!BEDoqw7D+#OCr8x>!asJqde0=fc!xu09^6*VR{Q2+?)8$8V8zBp8nMJ*<*z>;3yr^Qwp0_s6K8m7B z*0yOlB$Ch_d)>llD^(RWQ{)SSN^#zk;{ehCKZ@?90{ryC;{ybfF>~|Ms{c)14 zKTeYM*OQ{G@4j7T>~>4m-%g6Mz8N4{pS&gOFDFG=-+Pm+uazY0dv8Tqe>IV;Pu-IB zSCg77cDg0&Zzhs;a-t|pmtmt@vcAz>l%>nC&n?-+WxShW#x}QP6PIC^TYXEHVVAqu z33M4Yxi335xr?%N8TPm(o45>H-2H^VeHxZ*;xZ)g^b`J+OhN%PVCpeDg-}3cq^s`ppkMd-?kH*ROy0qjp1G#kYD*(*EwLl49dL zzOWYxD{c&yE(hAb)t7ZSpW<7++G`_S*5!oC3$}LuR)4K~Jt!Xun3_JRFM9fU1z(U& z+;G5wyIxK|IyU{d0%W=0fCG0`S+AgzF7q}M>Tu)j-tLDL*jo3tWNpN&t@Qy{Yu($D zy}g3=qY7-Tdt0)%S5V1%1yyT(ohsSeE2w0>f=brcsgk|Df=brcsgm_|s$_4kppw-% zU%#JB+-JanyW*3819xhzuT!TL+YB|A@f6F%U4|9A3`JSGjGGKAHW`YtbQ$*;R_rkp zW$7{=VOg=oP?O~jgW}pS)nJFAC`*^|0LzLEhN3K8hEQ-lV2R6+2|np~7&{?x8Bee1 z6bxjsyHM-|)-oPmS+TkBUiP}aYSHuZ;qyPf`2Cyb4?lbT@;@IR{^iTB9$%MNJQE`- zl~07fj}euL#Y{3| zg(h9A*JWKyB{NoN(zSwJ)y2+|f~7E*U}veUi^+srOKPu`?6NLq6YecZ*JhKlE{Zlc zm!xacNm&mp#p@`xny&i+D~|u^Hp`-G z6YSMRCpi3}Ulum#)7UN;i1urRzmTy8h5h_k%^| zdQg7;`o*6fUp@SGyFC2m>;HOu{rKg>@BZJzZ(e+*4^IE*w+}z~x1av%N0)QC{II+* zY|16EF`7f~vB3(@UC$J~!+QeVh#X{=@_9R_fXq9y_@t?q+q-zuZI6U{! z1#+8+J)OXwr0ZKFy|*j6?g5RPdqBG8fw99}(RB|<*F7Lz^FUeGJs@58fOO3R<^ILQ ze*$}IV{_{Lf~eeHO#CNyA*E{*e_5A)!#1RJ&2MF0`VIS#(sjR8pELRm*pqb4Z{_yV zZ`g^HuKBI1%dN;0*pqb4Z)IKj4SSK&jr_*V$P=59(vAGa-N+NWkbo5A1PV0TUC~B!+xY>&23d#nhpDrk~OoHJC|m| zhNN`OY*k(ENS@e{l&+brtV^?DOH#UKwz4jZ8}=lnYi29!YJ9Kv=ud1)O4rTS|Euuy za#!-iu4Ge)hMBFZ%i@M@N$Hx|#tH69ds*C&sUux;TUnQOL#B>&&2D8~`VE;n(vAGq zN86qUWa>ya@*7^LrV}qz(vAFv7b@v;G3hT<#pw+1Qr_>AXw&GH! zkF}4Q?~yk}Xk5Fk+FY6qfjW{kvsGp3HRS0?*1guBRQ7E zh3W;ov?)9zcorHiD3mUphAf?$gBva=l&*h`Y74S-s=DqqJsrMVCtdeiRoA^HUEi&f zZhr!9^;*LPh0^uiap{`ZiXLvbpisJwk4V?dR@Ft8j&yyaP`c)}vaZ`rx~OXk&q(^W z|NB>Sq;yf(7G&uZp9fq}C|&vuSvpl+uWZt#-;kwK)%DUQUHZ+x{+7p$egmJ^7U%QI zy7U|PJn2S$!`I)YYlVy+kgof!yX51wxb@Mt=L}zerE7jGmJ59RRdZ=K94ja`7v~D3 zOS}2U-{RhE>x1pxK)dt8$SN3y-|5Xl#bde6qB(oz3L^$l15svlV25T#RXFY6nkblQR_ovJSVMy5pB z8Hq2zlxVw$^$ko(wY~HknG$7ZMD3;D$doJ*Q_{ecs2}LJh$(4^(vdFx=1fU-y@Pw? zq)Wd!Q&QHY-^i3K5mV9-rK9%JZ-~+vBCwretxZq^zsa_Hm=%oGB^m z(r;u+mWU~7U`o`#^jpM~G%zL7rQe(>Dfa{YMyOV%Nz?gwY^O$8N$aES?PYz7u#(nC+jZ%;2rFqg>!yC-`x~&5VjTij zB3=3oSV>iv>q%lI3$T)^F8xNVWC2!E)urEvl`OzYs=D+Wv63aiN*b^dedgnSNraV< z)0Zy&7GWji^rcI`IaX4g&%l*Pmwt1uq^!&OMz92&ep#3MCAg}otqzuyb?G;fC99Jq zWnKD>Xvqq+r05HvCHkC<_qR1dOB&D;>0*C!b+n}153FxwOIBw~in=r4615k8TOBSb z>$1L)E?J!}DeG!{t-cX2StGn;2413mKz&;yykrJmB3;zCHNs0~;3d+4$4jd9f_%wDzGMYoQfx2zl8JoD zIBtHsFUXfD49DL$SMVj(_R?=iu52s#lH$D6N89Fg@+B+ylBzEKhV06=f-kA+(r@HT zR`4ZNUHXlD$qK%ts!P9-FImBtRCVb$@+B+ylA$ZhvBLUjLFWQ5phuH3GNmk}sLam#h(AGWXH8=Yf358u2AF`4YtovL7_# z1^qz3;i{&#MtsTKX(I0j`VD+ZaXuqoqC1_@4-sE7U2_>#Ggwv8M4k~QK>X7VMvqlo>W6~^uTOTI*Rn^0FPj6j$54Oca_HR4NV zT-Bs;V||PGl9_zTM80H=_>vh{HL1PyTf~>l$ShIV2>llEB{TUF#k%2ni1?BjS2d}< z^jpN2%zd=YZ{$nXh%cGRmrUeK)`%~e$(KyzOV)@l83{Gs53FwyUosMET$g@}_>z%O zxe&^#xzeRir6O{Fw(Qgr7!U$#Q(r*!8G7@UMALzG; zFBu6nrc1trA5mMv2@Y@#gB_pK9b>X)y;!8$Ijp>pv*&@DVCSNjSoG-?oS^896ns3%_ji`Yqy1 zMpBLI(r*!8GNNj(b(PcL?{8bgmyE0$*F}BXBEDpV)wnL|+ZOR9Bdo@C>9=vh|JHrl zg?xz)Xt957f3o=9e}vU|d+E0*zGQ^exGwz`#g~k*8rP-YBEDpV)wnMG7V#w`tj2Ze zH|I-={KE*VFp+-O}+<=uo@pX`Yqy1Mp%vO(r@5PYVXG*tj2ZeH}EA@U3~9Wz76^pd`VRo zd`Tl;vVkwD>SDj7kuTZ6msEA>H}WML_>!tF_DdT1k_~)GQI~v4BVV$CFRAKcf3lG; z*&@DVq}AB-OTJ`__>zTuNn?J=7V#wu`I5%`k}cv(Mp}*c1N|29B@6kIM!sZ=_>z%U zW9=nhvW=C~&FeGrC5?Q^7Uh?Wv>IsypxvXC!n6>3>$1K@e91z-MDfh1L*Pq_^BMUP1<_JhGv3WS!9u=7ah}xeExg$m^pmuwMVGSX_iyxU$d@$oC0oRoEaXeXm9xDG zKRMEBtbfUuY!P3wkS`G@$o59>Z{$nFSy4Cg8}myV^GmjfFIoC%d;ijJ5nnRWYFw9o zi};d}R^z(#Tf~s!Q^jIs!Q^EPb?Hmwt=*l7;yt3b?`Z8}TIzuEo*z8T}UVB_plI`+z%UBdx}D;kVuSlCm!MOPF7>M|{ah ztMT^2Z+pa-jI8V4;!8$ajrRln7V#x3^Gg(P!}ccM14denwU^i9>=9ow(rR3nev9~$ zkyhin^jpN2tmI1+aKrvh_DfdsB?`EqZu0&%(rUaP=(mV3S^H?aF8vnqB_plIb?LW= zFIjm%jskAbzY$+D(rT=|ssDBy;=QGH{6 zi2`n@t2gM|*L~zm6mUb`Xg%3S+n)#eE#ga7@+C9*l0C{V8EG}vUh*Y-bU)5Wt8rcW zExI3PWqyeQZZK{UUoz5ayuI{W#FwnhFHyh^+Z*|fe926{WRLF0S;?0u;D+su{Kou} znfWDq#FwnhFPWKNvPXQ$NUQPZf%ProOIGqF3b;Z4MtsRizGNm}vPXQ$NUO1aAYZaa z`6Vm!OB8U!e&{=rH`h(_B?`EqZsa%eB?`EqZdBjMmnh(dx{=?=mnh(dx>0@O{WuD^ zfo{Z?jI(Xx#Uoz5a zOqYDg9`Pk3t;Tifw}>xU$(PK`FWDo$Waa%h3b?`Z8}TJ8`4R=(P&e`$`4R=(P&e`$ z`4R=(P&cY?ydP)g{WyEXmyEO;f6nN)h%XswHLgp)MSRIft1(^jC40n|tmI1+aD#D+ z_>z@;i2`n@8`U@RB?`EqZnT~xU!s5;>PCL+qwV8HzeRk>NUL#O`Yqy1);`*<%la1a zC2OaNTo-;jz?T%iZ;~%jz>SaF;e1K)obcLdB5N=ClEe9uvaV)V*M;8>=S#}Enq6HN zemlUIRQs3fN%AEJ_>!9LNUQPo!f%K3CB=RiX*I43za7q(ly$kDBwunwe91_w@%F-R zN5q$mv>Ml?-y*(bq}8}C{TA^hBdz9IR{=Nh@ffLF_X$Q?jqB2H5nnRWYFw9oi};d} zR^z&;Z%4$JY|JlFzzzF1sc#$a$5Fryb(8hvNUQOFKz%zRzGS4;xGwz`<(G`K8rP-Y zBEDqf{WuD^LH|a4$wt0J0XNj`Gx^Pa1=Z?ImAwM10BCu%29)Uvflz$<}EiZ!hax#FuQHCURZ+E#gZy=9ehohT|6b zt&g_1mwt=*l95*9y7XJbmyEO;*QMVgzGS4;xGwz$zNF9cALsZ-T8-<{Z{SP%>{ijG z-^iC75nnRWYOKA?FF7K3h$r14-8}myP zaKrXS>q+t@3b>(evOl>ozhq&4$r14-8~G9i+_1e-eIsA8kS{qRzGNd`qJSH=H(F1U zFImW!91&kK(rWzqWqphIl95*9y7XJbmu%!q6mWz7jrfv{e2D^Xs2ll>`6Ubak|W|v zHu5D3xM6#v_c!t-3b>(e(e^!`S^L;*L{jr>NwL;*L{jp`fu5(V5qH{wf1 zT8;UQ_v0K9U$Qa3L;*K!Z?s>+{E~(FB}c@UjIzr$i2`oe-e^5ZzC-~x)Q$W`zC-~x)Q$W`zC-~x)Q$W`zC-~x z)Q$W`zC-~x)Q##}r-}SIqu(OFWa~7M>(Xx#U$Qa3L;*MGhlnrP$d@SKhPu&ul6=WR zzT}AVOE&T)3b%;@g*Di5(V5)H_3b5$d@SKhPu&ulK0~%;D)-9-*`Wc0&b`q)wfO)*>gs|ze91_wab5Z?;!8$a zjqB2H5nnRWYOZw^aD(SJ;!8$ajqB2H5nnRWYFw9oi};d}R^z&;Z)e1p?Bq)naKrvh z>f27fL;*L{P3qf7tMPuI-y*(bq}8}C{TA^hBdx}D>9>e48EG}HOTR^Y$w;d)UGgPo zbU)5czC-~xcpjqsl95*9?WNx$zGNp~qJSH=H(5{ae#zcP+jZ%;h%ed6mnh%{{SfgbJNXg?+)y`JPwwPP6mUb`WIef) zFHyh^b(8hvPQF9|H`I;%M!rM=H`I;%M!rM=H`I;%)@dSpetAF68Sy1M@5fQV4cnW% zzwNvqM*%m`1z*yi=E8eGr-{5D=r`~sRb7p?>5?xwBfezsG?DAlZxLUz^L`u!+^~Nm zzcIf=0XNi*{Kote1>8_K@*DXQ1>8_K@*DF@6mUb`sJ@XeQNRs#BfpU^QNRs!BfexO zU!s5;>L&XoJMYI)zzuby`bNHFC0}wz`6WB~l9hbP8ReJk9^>9oSl4$0&e)6MSf#`i2`n*8}TK3A8qdk`Yqy1cJd_( zxM6!EzmYFl$(Ni_e#uV0L;*K!Z&csNm#pMV&gg!ekyc~lM!w|i#KFzyFLv@J3bk)i2`n@8`U@RB?`EqZsa%eB?`EKZp4@DeYAbt=(mV3*~yoz2ZjeLm$Zup!WG7#;k}o+UzGNp~vXU=3qx_Pc ze2D^X*bmYB8~G9i+)y|28~G9i+)y|28~G9i+)y|28~G9i+)y|28~G9i+(0+tOLp=l z3b>(e^!`S^L;*L{jnRumFfPgZfqcmdzC^l_-^iD&;7g<% z`Hg(Z3cf_T(f0uIB?`D<|3>d`GOB8TJ-N=|+AdU!s5; z_Cw@1@+Atmp>E_i@+Atmp>E_i@+Atmp>E_i@+Atmp>9;)$d@SK2D%Yna*!`kzzubi z_qU_phGaelUou}JzT_ZZvLU}jx{=?=mnh(d{Sf($e2D^Xs2ll>e2D^Xs2ll>e2D^X zs2ll>e8~pBMB^6ujeLm$ZrI+)Z{$l9a0A_lFFDAUDBy;=k>ALdDBy;=QGFv{qJSIf zMt&n-qJSIfMt&n-vVkv|FA-ld(rRoz179ND$ZyOqQNRuRA@UpZOB8TJ-NB$?qWqGPR%7i2U!s19{6@Y+0XJ-Kz*UFHyh^+Z*|fe2D^Xs2ll>e2D^Xs2ll>e2D^Xs2ll>e8~pBME4da-vbWv zB?`Dfdn3N&AYZb9FHw7=`bNHF179ND$ZzCJHt;3Vjr>NwWCLF!-N-6yz4e8C81f|wxS?+3H}WML_!9L)PG8H@+BMi z65T%@`Hg(Z2EIhPk>ALdY~V|zYknK4k(K96qiyvVe2H`;zmYFdzzxSO@*DXQ1>8{A z{nkgZ&=2HG6mUb`$ZzCJ6mUb`$ZzCJ6mSFGh%Y(Fmu%om=1Y`ca*!|Cz?Voj@*DY* z4Sb1oBfpU^*}#`b*Zfw@BR!a3vVkv=Zsa%eB^&q>>6+iF^8@)31>EpCi~L5uL;*L{ zjr>NwL;*L{jr>NwWFucPMSRIYzC-~x-rgzVOAhiS8~Ktc;!6(lB^&vYDdI~G@+BMj zk}0|$=OACAfE)I2;e-V(QjuTZP$h0rid>&`)Io^{5C~=$=OHSb>X)u z;!Dmx+OCWGHbs2NNUL#O`Yqy1Mq16at^#iGoH<`oejYTtx-Rx7r-&~ZX*I5k{gNr- zOGa9a>(Xx#UviQ!QNRuR*Xmob9-rh(6mUb`q`sZxOB8TJ-K4&qXM|_b${ieJfVPQ<3!|l&uq~) z42dRT3J?LqgHo$#7S!D&iY3beq5tk3&!zjkds)T%yc-^P;1Sut!LGQGxij+3T)86Z z8~Kupe94IR$0=Kl&oBEH@g)!W5(#cN4^iL9mq>7f+=wrE*75auVBezsaUSv|7x|JA z?T_=2FS*E8K^UT(_?)8Cu zi3B&yjn+5vB^UXU5$%stwi@dN`H~UwC1tDeT=p&EOUhPbx#UYm#Fvz<#&h}mE#gZa z@+A`7;CzVo$9c$?NN~ekTi?3RHOQA-KpkI32vAh^^JUq1UJl$`bNG)f*a&U zd`a1Aycg_Sf{UsOqk^#PCt#;q$ zH6HRM7x|L0h=cd9>*Px$xZ!yg^^JUq1UJl$`bNG)f*a;WeIs8Y!3}aFzT_caBEb!F zqvs{$OD^&yBjQUQ@+BAfk`eJG5BZXde93UWWG$kdTIgWgWrujlaJ-}$OSZ)9I4#VdKLR z!X-0;OCG`{vfFUD_A;P5TpeqhU9u%JVoM&fB^TL}>1;`Nxa=Cyl8LQxTCZ><h;hGa*Zq%U^B}R<`M6Nq4yVJ0C8pHWRQ!!v$D!J*-*+mME89 zd$6$01T0amE~T&YAhQj+R<~l`|NO&GKYsta?|##rUUW@j8^*4rKgRa%_cUDH#rSaX zoMbvz(j6|kCa(>L8$2eFoCRHz*M_-v8`&H#sS;^z7#pl>8ZNpftqpVSF0wmZ{hc2) zb}iWyN5e(eWVOL?9V+P#7gdwghOu@J*^On>h?LA^OB~Gtt45?``j$A|;j(EYN@lVn zj)u#sktmsqG5EYPG>1!|=k+r8irD3Q^ICxcb3J6tx6Jjq;yK`>nX_pNH= zNhW+H&6@`DBsY1IneZgCr?6|}NoL|JQ7+3yo@6e<;B$VvhmBn$PBIgmM8jp-h?C3& zC;2L;vD1M#$y|WJ=QMO%L7e0!PBIr@5ai+}@+M9)7hv$2+k1>G*$eANoMa~3;e3_T z`22EZTY$mmc-!;Km5n&b1WvM!;x~U_YP_r)agv#AhofB9jX22!PSPDO`$n8(COC=4 z%f1mOnF&s!TrO_JNoJj~Z{PM3C%K7}%zDJ|elGh)oMa|A$yYgz^@6&RncyT}%>WB zf|DqheIrgX7hv%IdO=-@d^Y%1xB!D7mwh8nG83Fc^T56lCz%OO@>Ndb$BlhUa1!OR zZ^TKa<0RetYT_g}agv$nN;F=sZ^TJvf|DqheIrgX6P!d64z6#+NhWZT=5>cSiF`Kb z#R3dodeP10`bL~&F2LX=cm23;{2n4sauX++iLONR%f1mOnF&s!T&{1_mCOVuQ7-#N zoMa|AiE_EV5hs}mPNH1)jX23na1!ORZ^TI^aFXVEMx5j(PBIgmMDi4_Z^TLF0u0{o z1#yy_ILTaqL6FP!jX23%0*ja2=JkO%$xWPOCOFAgIgPDv#7SnND^V`{Mx10OIEixE zH{v8S!AX?Mz7Z#xj+1oPW9mw7@+8xFl5Q@6lAA!ubfBc2%f1mPnM+{ta{e~24+Ki& zv%$LQKuLSN>>G6@GXYAz%4w_@1WNR#Hkt>nZzM|e{wT_2-$<0`QMu(duRGM0+(b(B zNYHY-=L7pjq(qNCqFkfCFUT!9jhzqFmFQMB%4Odk+)rxBj&gMze7xwJE_qQd z`}W}Zq^c9;@_v$3$re#1gH(xpHh$gNBC4e1G_Uh3pAB=pZ@pfWoW^s3m28QwM3aZU z$!Ejydf$52hmzCyc)^uyiLOKk1;5|qv*CE7z7Z^u&xW~C-`0BN^T56(+u>*)(6@)W zk}V=jN>1bB1zEB=S<+mO2X!U#*?Sl{HcVQ$nnvL*7_FgID>26ZL!*)Z4p z*1SFtE|JfMxzYMYxBvq}()~ z%enzC>CS^LPoB%ZMR>^|Uh)tx*?^aH$E%}l<0W3QMR>^|Uh)tx*&@7T5HER%muwMU zGKiNv#7j2EOS;zw+DfFeLEj?0q}()q+_=0&cuBcwJeSK`gqM_?#&g-X2rn7LOQf^G z{6=`mAYSqiFWDlzq}((%55!Bh2rn7LOQf^mJVdvX#7m^JVQzFgNxbACUa~n}((N1Z z66tI>-e`RzULu_hbEDfy;w94AFgLoLBwiw&4RRyAq}()q{<3coUQ%uv%Ozg2IbPB} zAGp2|FWG>XG}leyB@gkEEy7F6P2=;xzD0ORxoJF?Ki?v}WDqZr&W7h%)HmWK(%CRK z>Kkn((%CRK>KpMA>1>eecuDvC^|Uh)tx*&@7T5HER%muwMUGKiNv z#7njaFB!y3q_g4tMtvh*BApF$qrTBrBApF$qxFq=iF7u|jqs9k(|9k~w+JsOH;v^I zFWDlzWDqZTh?i^;UNVT6Jj6>j$4k2R55!9z;w4*zmki=15Al*M!b=8yCDPgOJd659 zyyPKXvPF1FxoP}7W8WgYq}()~i@xmX)V$;hHpA=gz23OJ`#EG8YCISBlY4}h zl%d9R**CYAG~XANqQ-Oaykw8?k_o&-^UJ<1;Na!8bnkjriW(m;`?i3CAXoo=&t=~t zykr6|(LAtk5nfV`8XqtF7U3lmc!|c#zByjfy-orz5roOUMe33XyhOR|o2yH@y#QXK zT=os_lJ$1r+dRPpUZPy~&D|y4@d7VVF8dbAOD6CV<+5+UOPW0fUZPy~EwY!CsK$Ch zykw8;C1tAdT=vcJlJ;@)_uZNY_ARoPl&Z$YOTJ`}_>u{}M9?$)7V#zJs`2r%Z_bz0 zs?_Kk_!5nmeT(>#a@F{F*|&%vTv?0>7HlcOEeGcTf~=?tj5R7^)2E{N><~! z?3?o?J)EmtH6F{lIbPC@b$C+9K3BJhE-6)w4VQGu?sQ3axOz0^u`F8zmrTGVng*7w zZWrFZsRmr4T$at@l5QygmnfHIi{O$n)%g6fY!O^irW(&>*&?{4Of{a%vPE!7nQAlU#kC91JpvL(B-CEe3O zKh!;zZF97w8_UIwWXT?pC8eqH;j(NISyGxB&t=&nvSflR(Pw#VTO=+iO^uJ2ZHvSu zrK#~;whiKv-iHjOsqtL4&B>DP%>&4iWwyZ++DKedni?A~$&x)HOG;DYxvX0xE}0-p z^qD3Xw}>n$O^uJ2eT&GF($sh^`v!4I^N9w?63qkq260I@mro{1mh6$Zq%<`?5A0h+ zmXxN(bJ;hLCCwf~T(ZnI=vzdVl%~eUOR{8-$dU=NM4uV6ZxLBini?N3`xcQUrK#~; z_AMeyN>k&x>{~>Zl%~dW**6!Lbe~j%EYWe}`WA^xN>k(GW#1q!XdmT0`}8_1Go z->?ska@n_tEGbQm%>&7j9b`#&yu6(xS+YlDNoi_)yzHBkCEfc6kR{Ruux}ArQkohc zFZ&jeC8eqHT=p#zmz1W)bJ@3uEGbQm=dy1RSyGxB&qd#kh%6~hjpw3oM?{vCrp9tf zmK+gTQkoji#rk$cWXZ%{IMQ99Z%0Iyl%~eVi@qHZS)wC&4^ZKASLCi(p zj)*KNO^we3`gVXU>0N*I@RZ|4-;RhZDNT)!mwf|S(jBk<&U4u}kR{z*ybF-o#_v;) zIs-l*f_HPVz76h&bAT-A=HhwDpt$4!S<=lFC;K|TgB#);AWNFLBufU#k^^K(Hy3@A z*@nl>$&zj^e!t0V!(1noySeC_%r?w*Qn{NelEIG~`v$V4o2$R`T=vb$lI9!Ujbw?; zHkb#HCEf9|ZzM|&kR{z*_Kjr80kWi<%f68;IY5>)b4ixSY{U6=lB=7`zL6|BK$diK z**B6U2gs6cF8fBZVxXf8P-vScG!GDwyjAWNF#g}G!KG?yG8OS-x28_gvL$dYa@`$n?l09n$_W#4En zIY5?lbJ;g;jB_|y(p`tJF^-NK*EdH?+PUl-*^&cnNp~LDH?k#%vnB2EvTrn(91fQ> zpUah}#;#|COAf##&3PbPBDD?HH^3#`T=tD{$pN^eo6Ej&W1ItUNjH~$+ju_-xTKrQ zzHwum18_+>D@6Ilz}RbJx+f z%I}`26yD3HXxkc=dOl%k>R> zNjH~$BVTfWFX`s8Z#0)25nr;AFB#-Z4)7)2@v?6;mmJ_rnz=BS==l`aH}EChT=tE8 z$pOBko6EkDFFC-MbaUA^noADwCEZ-EZ`>H?i1?E7)L7rhmmJ_ry5nWv$d?@8OS-x2 z8~Kt0d`UN#>l@7_2l$e1F8fAv$pOBknG18tCbbRj`@olUbJ;hVOAhBty7v#{OQg2p zcy$EczfXm^MDxJkZ{SP1^T585FF7K%5;**EefN5q$GFqdpn+u*o? zFX@h#eWSVL0AJG0W#7n`9Nl@7_2l$e1F4s41 zjB|i5>E^O;+!*HsU((Ih-&x4baUA^noG`zFDXxr&jZ%C6MRW`yzCn{ z#yKOtq&zh~Ui^MLBfg|OHLtl++xR+kMtn(mYCIR~+ZpjC<*D&p@LXramz1Z*bHQ_+ zbw~CtXS0(pk=lmyt1I5y_h&mc#?kgKcs_Z;T+%#$*U|QQ!2RS2b4fQB>zmXzoCjU; zf_XsSq_#nB#Fvz(#^-^3i};eAe2LUH9IuW*Fb`PYq_$zMjzEx$^=*>8uFF7N=WXHxho76TOZ`3zzjH6ukE#gad z?2Mya_ATN|cI=F^P4XpY#Fy+emq=}c`HlFJ9XsP_yjy<*U|P|_ATN|cJd{Ye90N{B|CP; z*`&6?`4I6X`#Rb-59CYEh%ec(Gmgf~zBymgd@i?BULv&(=OJ3($d^cM!`!HEl$XeD z!`x_nTSwcE8~YaVC1tAdT=p&EOZIiNJ(qop_>z6mM4rp_E#gad?2NNb@+D`)m+Xrs zvhk8HIU~Mg$Idt!FZ&kpB|GIMvfJSNjrfwCe2MHf%#Hd+zC?B#=0<(P&N!N1_ATN| zcI=F!T=p&EOLpvxqg?ha;!E~*wEg^L-y*(bUo?^Bk}o+UzGPpn8qekZWW<;3*coS& z-UjDc#Fy;rX#05Cw}>y<$(KlP!|_IaqrXIY8|FrR!_GLGU-m8HOLpvxqg?ha;!Da_ zz6mL^fXXC1=E!?DUsR@+D`)mz1r>$IHG&e94ZTakT9<*SCl- z*~ynkaKqyk^$k1YXuMqCBEF<-H9o)W8~i2B>m>OS32rzK(ep|AOC-2KZp4@D^p{9* z!(6=qegC??Xd;_m@+D`)m+a(AB)H*tqxS*W8E2d1OU{Td+37El;D+N}XV%;A1IU+5 z@+D`)m+aUXNAtkGMSMxwYW#d)-y*)GY&D+CzD0b=zK*u%qHkBkm+Xrs@?7-oiujU! z9c{}cUvfo!$&Q_I^gSo~c13*2PJf96H{OdY;!AeyjHB_QZ&$>Zl&!|+7wg*<@g-%e z@m%!niujVU)p#!Yc13(i*=jr&eY+yQq--^w%f3Z?N!e;Vmwk))lCssj=1Opb^Ecv4 z%2wmK>|4Z_l&!{d*|&%|4Z_ zl&!{d**ENr)4NYCTaD+kZxLTowi?f6-y*)GY&DikzT}GhB?ouL*~ph%k-y~N&N%we z9p_oZmmK6vHu5D`bJ@4ZUviKy*~ph% zk-wyDH9lVUE#gbcR^z$sTf~=?t;TcNw}>w(TaD+kZxLT|kT2QDms}BFQnnf!FZq%y z;!Da_w(TaD+k zZxLTowi?SNUvfqMlCsr!F7GEJzNBn5p3C(u@|TpY#&g-Xh%Y(Fmq>7f-^Y=^bJ@3uFDYA%=dy1RUsARj&t=~te@WSDJeTWR#Fvz<#&g-Xh%YHyjpwp& zk-wyDHJ;19MSMxwYCM;Hi~J=A`I3!%$rbS>Wvj9Ak}tU;f5}0M=dy1RUsARj&qd$vh%YHyjpw3o zcf^+*!{KcrMnrJK{^qR^z!?-|mPnDO-)_qHlM^mz1r> zbJ4du;!Da_#ll~G3ZqT=gFDYA%jhB4M9q}b)tMOd+E#gZ~ z@+CX@k~`u{PVyx?`I37P2XAxGC;1WyZg|`hp6euEBEb!F6Tal6zhtMsn1Hym&BJKpwf65KF1THn^uw)2ziR}F4{y2BUmz?yM?DUu15npoBUn0Q`<{{!s%2wm^z`jL%$w|IMf*X!E z>KpwfJNc43;!DnTv~3=^Kh7QTB`5tQ65MbeqQ22zBEb!FqrTB!BEb!FqrP!}90_ii z8?A5jmq>8K+-QBHzeIu?n1H_VOhC&`ycaKqfFZ}gY!w(Tg_{(1UER(BEF<-HJ;19MSMxwYCM;Hi};eV)p#!Z7V#w){Us9IaDJ2f$&3CH z32vC1tZx_h$C2QMxyk+HwT`yWFZ&kpCD%IIp3A;Pe95(rw&${M5npnVFOlE|^BeIc z7yTs?+%Pv;-!A$~B)DO2vc6s9OC-2qZnVCUFOlGexl!N9mq>8K+^BElOC-2qZqzsO zB@)~)H@Tm@xIc~rH^`0nlCsrU-^iCd5npnVFOlGe<4u0Qm956cOTOfZ_>znJ<4ADB z@kV_kUn0Q`bECeIFOlGexl!N9mq>8K+^BElOC-2qZqzsOB@)~)H|iVt5(#dQ8}TI< z_s5aohPlb}l8bza1UJl$`bNG)f*a;W>l^tJ32vAh^^JUq1UJl$`bNG)f*a;WeIs8Y z!3}exzL77H;D)(T-^iCpaKqfFZ{$lPxIu2jmt5paB)DO2)Hm`a65KF1>KpkI32vAh z^^JUq1UJl$`bNG)f*a;WeIs8Y!3}exzL77H;D)(T-^iCpaKqfFZ{$lPxM6P8H}WMC z+#omNOUhPb_h;lwp2%NvkuQG~8QQydyNN~g4XniAJBEb!FqrQG~8QQydyNN~g4sBh#;B)DO2)Hm`a z65KF1>KpkI32u-Z@g*1c$C2QMxl!N9mq>8K+^BElOC-2qZqzsOB@)~)H|iVt5(#dY z8}*HRi3B&yjrvBuM1mXUMtvh+BEb!FqrQG~8QQydyNN|JPh%dRwmq>8K+^BEl zOC-2qZqzsOB@)~)H|iVt5(#dY8}*HRi3B&ywZ5&ve_Q{15igP7hOt(+Zmf>A{kkAs z@w z=@RK}m>ac?bcysf%#GScxQ=5A&t=~tx};n+p3A;PbV<2tUUQ|l!Fd+ZCFQE|T=vcB zl5!w)&R-pE&t=~tx};n+p3A;PbjeM+M0y*}Z`3!^CDPk4*ZS65HcM6G)4;k#@{&^3 zcrNSaa7lN#y0&^O+ZM4UH`x-&Z7{nLTXK^vk=%y4$?A5KEs@-YxykBwlP!_lhPlb= zc9SiU+=jW)>PEIiavSDGZ6jMExearzZQWIqY>DJH%#BtzvL%w+FgIG=$d*WMgWQNM zDN~L07;MS@5wRs@sW54RfQuku8zj2DuSia+58Q+=jWyueUPQSl_^w>>ttI zI5*i6$!$2^sBdITPOv2!Z`3!kC6e24yxzBU6>8l5k}Z+khPmFiZZ3YkNp8bj?^`!l zf9K}|`-Z)7y16>qp3A<$UDD0v{Uq3u{R3=CH&;j7$IHH9Z=7zfj<)53Ezx*a(&wJl z-CP}Q&t>1>F6rj-*BjUpjo16u&DGV_$IHH9Z=7Z>*%HZZ&eTQ`?|16#6xfGz3fvTtBZlpC#YWJ^x4CCXhR{OsGh$~Ug- zWJ^x4CCZJ~H?k!s*b?P>-@4;v-@ukAcO|_&4`fSDuqDd%^{qKxvL%w+pcm2JI5*jn z6Ksjb>wW8vmwf|UqFnD=HAFr)HkvvlG|Xs5nFPT zEs@-Yxl!N9mYiTq_K#?9oSSUP3ARMJQQydxoM20oYklip&&ZaXU`v!6^^I`J3AjYL zQQzn;k=%yoL)16AOHQ~;G~TFhbeEiPmnb*t8{H+6+xR?;h%PBpjs2d7yF||asBff8 zB)8#sqx(tHC6e1PH|iVdl9P1Fi1x<0NtZ}&!|^74D^rafH_{~|qD#tDr%UR;^6mTTGSzr4-oFjdCEfAr>gu`d8|ac|F6k1E`e2L^XJZ@3n$d^cN!(6|g?2cD| z=kv?HE#lziIc+zWeIs8ous2ROmwh8&GQgK~bJ;iYB?Ej(HhLnC=qEZFrtVeWSZXavSDGeWSbNg1ba};zfO(5KN=P&z4zGOsv$wPO^1$T+Y z8?A5TOD^&yBjQUQx=SRtK`$b{jkuMpGIC%g1KzGSSzGOsv$wPO^MZRQ2e96PT zaW3*D1AIyI{3Ty=n%CtotamvnRa`;C0b0AJG00kuMq88>c&7_KkeW0AJG0W#7n` z4Dco0T=tE8$pBx{&1K)nmyAUmynp_ZFS*El^u!v512p zmwh8&GQgKKj~n@ti+srdU((Ix`bNHFEaD)T2lkD8$pBx{9WVPvzGQ$e>E^O;8`I3u#$pBx{954Bji+srdU((HG-^iB?*h{*(`aA0z`H}&?q?^mWkuMqGOS-vS z-^iCt@Fm?`_KkeW1Ygq4W#7n`OxR1hx$GPHlDUY3_pcA+OQg5)=LFOFlJy^HyhbNp zBD)P^ZFy_O%E%#8jh(%uOQzE$-B^~5>XPYjNjFx<)<=tHlM`%7>s-(*=)do|co#68 zE$I%IReSI%U^-gTjb+mwyy>1!mK0y{%~MRXfTl@ogHsG-iT-)tK6RCgrrjTS(>)Wi zM7dbmB(~vr*9hNyVy|4>NlI+PT&r4d#oRwgmPl;F+~7`9xhR{&Hq7-q$u;`M`LO<7 zudR^ShPiep**tx@DUQ50jMV}7JZ#-ql-ASE5|5Zsba4!j&kOeIr*g z6Rt$L>>Ig~nQ$e_W#7n^%!DhE^#ym5H@T7tu4Jtpja7(TiNrSO+cH_a-(zwm65BA> zR=4h56uFX{T*+J}iufOCVeIr*g!IgA#**9_}6I@9*mwh8wGQpK} zbJ;g?B@>Ig~39h7@tG~0pkt>VeIr*g!IgA#**9_}6I@9*SAS=HBUduPl{9n7mE7b?Cb*JrF8fBVWP&T{ z=CW_(N+!6HZZ7*qu4IBM>E^O;Vx$dycRCEZ;1jaYK(jaIl5#YTjDoMc*X0VeU$Lf4n+x zd>%lTY>BsIAEZkpw&8en#e09eq)Q~WVXlrqkc+-aY{Og~fgl%slh}s2tGS=Yt=Z%C z{?CsaV6F{(NjDek+e5x&17FhY1^JSPe94x0OLU&GZ{$lh=Sx=kzP$_$Zj18}FWDR~ z>Bh2cq)RrZOPaBSOCG`{TLhO3!X*#kl5ODzFDGyFWZwlLcYX<%JcLU&hfCVIT-*qkY-^j8mmYWLfr}gAk}ZNuN>O8r z8{v{If=fzK7j<)3zF4-cuWN=fQhj7VOXTaypL-)AxW|DBp7QrQho8ml# zOST9u8H7t7!X;Y-mz1K$j~j0$BepX=5l=_T(SW!>E^O;giAKSCEZ-EZ-h%Wz$MLG!X*#k zk_~W4Hx~~lWwpVNA;2ZwT&{0~OE$nI-CXvKaLER^q?@b1v%V27*#MU``$lPrtTvcm zz$M-Ba(yFQvH>pXj+cEST(SW!>5i9uBV4ipF6rj7Z-h%Wz$MLG!X>iW@VNQIl5Q^h zMz~}HT++>D-w2m%fJ?f$>>J^d&Eb+-og2T0*3q`U5iZ#rE@|g-eIs150WN9wf}7$z zgiAKSCEZ;1jc~~ZxTKrQz7a0j0GD)g**C%^8{m@Wc}BS8AzZRKT+%%sxGBy|F8fBfWCL8%&1K&Rmu!Gby1DEd;gSt-N%wr<`bM~916pX=5l=_T(SW!>E`P1Y`q{{vH>pX z=CW^uOE$nI-CXvKaLER^q| zuKrytE^O;>K!!Zm$1+Q!dvx@Fm?`u5aW^_J}VjRgIkw z*_|(Ga(JbxvGI~G*(1JWuA}X_>|4Z_l&Z#axxP7H(wztJC3>2}_09Q`cCJ64 zR4)7Gd`UZ(eIsA8M|?@CYJ7g#w}>w(RgLGeZ{SOs_rKsvG{5Xy#Fvz+#>Pv&WCvf; z9WU26@+Eu3mz1i;$IHG&d`YQlJePd~U(&pufiKZhPWBD*l5Q^hM!sZ^_>xl9_&jiZ zi};dK)p#!Z=6p%_z8ZXq=9hhQzNC9!y^gkzmwk))l2X-JF8Pu@;!8?ZE`l&l6=V?@g=3I@$s^6&X;u02k<3&tHAXw;!8?ZL0)R!}q`c;k(~__g8=S+yC&x&tLxb zhwuOWm*0N>_h0_uw?F;xpT7JzFBYG0DAo^=VpWp2M~h$BiuEI;Sbsy>9IfB* zE7mWFiq-7DKU#mDrC7fnDps@qeyonOp9y|B)YfkPdbBwSe)pl#`qfae{&ut(>lZ_P z?By?O6uT~~@1D2oINK!Px3yw5`|roHW%zVMu}RC;arV)&W&X>0O?0EY_+hQNWy}1B zbvM?pgNkL#{C9OXmMz22YRzrZvUQw&ZrL*Ys&39LTZWG|w9#SGGW@32+_Gi(P2C(V zTZW(18g0_Db)0Q(@rzoqNz2x8_E@fE_(AqATAV(3yVJCPhxRl zIbie9+y=|{wSG^%o=yjN3&jQ(mJ3_OXcBN?d4OAdo~61M{G}VYYaM4FEtYS6zMsr3 zmhS_wg*FCU*XegpFt8Tdb{@;OKHg7aabY=tT4=OM%RpLav}_qji{>H2@_hib&}fsE zfwRzP*)nhzz0m@*P%M`32be`OmMsHip-D(u28oA8%a#GMXpWXG17o56ER&XDe;ADx z%eTJS*8tyb84Mod0AZogCM^SCp;)eE04zS|_P?^u{?hN+@#{C%*ZO4g_3}6H5#2cO zkn?j)|IAf&!#8we;2Ec4gBh$3CT+C%gif)+b*jFX^jKV{4m{y(P6Dn|0}nVg+Tc1> zUrYLEah*Ewe6u%NJl@nH!*%Mwr{Oz>63u#)PaYa&C%jIHSq1+ zIPh$<8H>AtflucY8(gRAJ4u@aJlRxi(z11&Jr>ug0}nQvlYpNY1K-VQw81@heI)6l z#Xa|d$C|y-;;T8S&e$?M)ojM%o?E}N?PGIILU7MrUr72S;E~yZZ|0h#)z#Ev*)n`G z*NkP$@Wq@Kq2O+yK9BU#;%?x;2XmjJeO+JwyC1&)>Bm3(@4xzT-go<#>IcjCF;GUm zmb5Y!jP}i^O3L*%D%abnTwC+nxn4)*`l6>?t7ALYS3Tu=AC+sXUN;woRIV3Nx%MNt zo$HNMt~XM-*2s3QFMP`NN-EbDzILv6Qn}tquA4RMU>0F`Dd)J<9)r1{Q1AyfBf=SKmYK&Hg9b}ek@`n6EGel1k4T?^Z}el1k4UkjCM*TQCQ z+0$RnQRVuzP`P$3Z0Gv5P`Q3BRIXhM+qr%%RIXnOm220+*WA}m{i~n8{|`U>;mcqB z{rA89;ioTu`8)lvZ?{O;mH+EL_`31~uPa|i@ykDUmFxdH<@&!)xxe_Y`)6};rRNJv z<=U0LJzl?>XuN(k`M?{?cCKGdlsJ%y`qf0a!PP{$el=09Urm(zi&vA^7HMVr!!JDY|L|L_!*TpfALiK<#j;0e!W(%U#~B1@A`Vj-#%`By;iPYuaz5IuQgu3USIlt(w=cBH@IFa z*RR*g_3O2AgX^_&{d%ojzg{ahxLzxleFMy;++Vz2|8wU9XfBPHeRGuA3$K^ianmfRm*=Q`S+%f30$)t(3T4fjXao!lR3yzCp8F6Bmj z!~KznM)obaKhk*FH{2g-yiwn9f28sH{gHB`zJcpfF8k(OSND8aN88RbfL$7Iw7#vQ z?YUgvoa}0kmwkhfSL2P=w{^6AyzHB^UG4F*Z-Be5+u^QuF8c<$OSw_sfOiS?W#1g{ zYLAzFgOFF_jrz8ZwjDPJd6gUW4IfNt9@sbkV5&P0>uCFUxxV=aQ|(;#4MJYcL$toF zqwVA6`sN=@wa3f8;e)B`_7A4ox$GNQ0_8^clYj}ts`Gx*VS@H}c|Qr7K;w<>C-K3Q z#>@Lj#|hfwW#7OPXuMJ1Amr6}**6CYy5j{=pj`INiGp@6`v#;y^APoI9c}9yguKd) z*0*)EJ(ug7Lj~=5VBbI$T(?sN?Od*Jc$2BzXnn(*Og(Mo`sQyk+vDZ>hBuiSZ?wLx zqix3xZ!(n|^$l+_H4p5Yzsc;*13s8iF8k(hGTXWA8{TAU9-_XjqwVv{_08X8w#Uo9 z;Z5dsJ6_PvW#8~7Q@PRlwvM*V1KwmRH|iVSWa=#h`{r*l+w;J_LCCA|MtxgH+vkD5 z-(1Ms9WNeLYaZCQhdXK8VzJB}Fm;3j> z|DXQs%U^%_wH~~D`HS`cef(N`0(|+`?biq&rSg6`=6c)i_ey$;ADm0d^>azNel96D zxORV(%G<~5=aO>O=1=;fcaAF8f17B$el96Dcov{sKbMs2&jOSioJ-2}YqxU!TvBdu zucTbRb}QHKl|IgdbWpBeyOrzDx|REj*Y4NXH2?H5@h^Pj^nZU-{P6~Z{UN&Cu6y!; z;hegH4-XWJQ%YYg+hh2TEBNq0u{fhPe0ZQ(JEPXLeiKDeEKaBmA08;yPN;4y&Zi9@ z9(-KEhX)!hPNxkY9w^pMr|xL|PC({1|D~%~yA$Zf`VU>j`i+2MHT$0zt!}K}2PhWT z?h9ha=9z#?xAqXmdF!t!o1?{BN{yB+^S6}USpD7Wf}lNwIa<4LcVpQyyra}1OIn6k zl$r!wwl9B0*&QughBuTVRqPFAHWy|n#QlqsSq-HGMO=`4knZKKSiG5vW|KEcrwH>HmRL8_cRiEY9 zMYVU!rd&VX%Jr+Na_xAxbN#ZaTtDE-4Q`1wUO(c>_3Nr~?TB~BiwmoA{g5j+xFsHX zyKh%k<@%LXxprl3kJm4)%Jo}f<=UmSo$Gfn%Jplja_tVLo$D7@<@zo0IQ`<<&h@LS za{ZQAxvQOjyt=k?**9EXl^gX9_=onJXW#t#+8!_ah6}958}$wNhsMjk`4zT1UR+|8 z%f9&~ww=qq0sqiEM12DutMRgL3H~wkb|2RV;2#=q)HmQC8ZY~n;2#<<`v&|&A6!O# z1O722RJJ=%L*wQ8MzPPC;2+9m-++H;9-_Vh|Ij?JZwdaP@v?8gKlCMX)VFoCUw-k83H(F3 zQQv@nD3^Up@DI%c`v&|&8p_71OB1$>Il4leE|NU@v?6T{xS4+AH4wnq47q2TSwda2K+<0(eo1EADRa~FG=tZ z%>$p80RNDD#U4g?e;==-?eoCrB?l^ToF@b+5H|pCu+BOe(Wv|@m zeiEukmtyOJ3P)yj=OrbJ4RX1@K~A9YChJ?ND15wF-%1x7jF;;h z_G6YHC|Tc1Md9Pc`gZw#%*}PPR1~kdvRC;1WEo?Fc|hMbs)0)x8|0#I8{NR=j16+p zw~cb(%jLk``K29rqaFBiJ8(M}>)S>>@a1~ob}st1(GPsNAGn>1^=+dd_;Nw;Ywqj2 z=Pu$k`<~5@0}qkqZt$BBxf|@FxK_3XHHBx$iuG%vV(lKJ8|#Niv3?7pSi2;4WBmvz z)~|?)wL6e*tX~in>o*`Di5p&r%(@iYt^xk>{b+Zze*2+aDgAP&SiAk`#`@Jz zv3~cVSi9Tr#`?ujvHs&)v3B#(jrD7xV*TDjvG&`#8H-29ie=0E(Q!9cfA_M2DV8ns zC&%4bwhZ45Y7&x`;kmI!%a-|bouqh8dL`9CzLIMCG`L1;;LNlr*eH2{QA@E^VDqT z`ZB0oFQ{^D8EofzLzV06;MbpK!Fau*%Jqd%xmMBkczq=tv;->GI@-?lrBJzEQsvrG z*v|EqD%aOSGd#YT!=WOTdXum9n%Jtpfe+`D8}$ue z&MBAcn}0dio!|8!%jbdXn}0gj&Sl^5?VPqNT~~xZ{xoanvTyi!PPxhbA^$ng+<#K()haTN|VBh$mN13sMdEosdKlCUw zc96^UjURd(_|T&}59}L1^f>ULM>m&!>EGyIPjrIHLR9eCY9VKD<6S{{Q{;zZw6Z^Vk2=!~4HJKfe6^ z-~Fc_e){3xfBAR+d2M*3y`cYxzy9(k|Mp-0<)7*S4_=lk*B)54b8*3Y@U~RBT5?{-yJn>^4|rWV9=tA9 zuKj?n$Ag_*++aL-U#eXD0bRFqom^b-9=tGBu8zRxJhXFh!F%w=RJnG+YtI92Fdn=z zowb)|FkakXJa}iST>Amto(J4uJa}oUTfdD%bkf&Sl^5rHyiXerfaIOB;R3 zy>2P~_`s^$V}5D#;7c3jTHn^m+_;?aLz@R5+9=lQ){SM`@STlft!>>{mJOfTDAvl> zo?Mmy8#@WlyY#w}OGs~6uQnqd`7dKc|m1||IcS)V`a&g0FHp;cOwR2fFd}gCut6Mvl zeZyxq%8mNQ&ukuiW~1DwZ~V;W!DlwgjrzvVY#w}Oqg?A-^KwSG=Kk|Ztvg(n4QP*It!&*`b`77{DAv2S&g4di`H9T~vPZdVgl{kK z{KVz~*`r+RT6Y?BsO{1Vut%|0wO;Jx2R0A59>rSIy0Ki?fb}RgDB2{|^WgIu#ahvt z>)IsM^F00*M!8AT<~q`T(EKTtG&t6@_IOz}P(8}EstMgk zgL0jsQ*P3=xsJByIz^{k>sosrylfh;Q*_F;vUPJo^(fb$3M<#z*3R|1Dc7G0E7$7Q z&eiet`E|-bxl!NN(e_;S&8eRDc)f3$2llO=Tfciv*Hb=@*QuVlJJr)3FZ%|nN4Zho z*3q{41=XY6sBi0NdoKItR8RAvh~E})+I0jNjQ z>vda$|Mo43*i2Td%Ub0eApVVFK^xPvTlHSWKD~fHyE)szpR@>J>9wi>e1~4 zmp6xc+PSP7pdQUbRJV1s?feDQqugkDgS}Prz`8lq)13!EJ<4U@9O`N3a(M&Pqj~VY zHE&DS(f0Xe-`w8X9xwX_s7K@VzIDgTz5(i)yF)$g@p5?s)T7+!b`o-I-Db0IZf|Xm zmwf}&qwz+4gC1Ms}NKYs?abJ;h1eXrc8Z(vI12bmJ>*7^Fgr9EEujZ8`TJcD`Q{Un(Z z?baEMmwh8sQa;c3#|x%J^UJQ279Y=xxP75($3}jMy8~Ep27UG zZ)8f!=NaU(Z)8f!=NaVkaS54{-IY3H(Uq)K+DO4_;X8?ln|c?QRg>l?8W?bey}7+8s3ldx|QRw6kk zo@)>*(Qcj5c-c2%C3}RGNY2Ue@_rIn$-1j*JWmByqWR_TH@CNT&okItmCL>XE9s7x zeIr(~11ss~vTwvn%IEohFJN!g>p1>?i?EUjtVFqdJ{e&p6Ih9I*|!KQp)^LhT;Cik z>7HlcN|ej{N#{!1x$GOk5=dj(xm@1}mXy!){qqd=R?P$Y25C%tyzCp%5=dj(x$GO! z5=dj(xm@3fmOvWQ&gJ?>wgl3cW-g^MlhPRNcA_Kj_W2+=C)NwnC6LCn$IJDNcnPF2 z?OgVacnPF2?OgT^(irXflDvPDoRjm*zD0P6* zq%qy&M!ba57>!p);QjM#9c>>k?k6FQX^$6ulLgB@W}LPE_UCw;-*RX-ZH$+A38XRY z@v?8kOCXJDkC%OeG)D6f^^JJRfHX$AQQydy=xbaaH}6~TeqCE?^SI%D64IFNaU)+s zX^iGUN8s~3Yv*Ep8{|t4@FmUb&N|xGH}WNr#?;lgaXlknGRT)e8q>~Y-^iCh8q>~Y z-^iCh8q>~Y-^iCh8q?0@`bNG4(wJ^8`4UQFv}>IAt$Chdci^dQ%+TYAFVXJWIDa9H z(Ric2K^mj+;(5st@g>?{o8#sB7V#z9qKT}>0WopmkjbHkjAug**EefkjAug z**EefkjAug**Eefkj8X#$(K+XGmnTb*%nP?=L7i?NMqXLW#7n`KpNA|<@!dx1k#vx zF8fBl1k#x9brQP+&q2Nf(wO#mxxSGvfi$L_%f68>fi$L_%f68>fi$L_%f68>fi$L@ zOTL8Cn0Z8eiS+&G8~KtW;!EW3XD)xgMSO__{>1B;rdX@y9%nFFD{WY5s0mN87IJJpRn(@3)9A zk;tF9yq}Etk}}lzJg{#OUs8q|&t=~tXGs}qJePgLHV@7747&sC^Bg`eac4=l$Jpp$ z4)P^O#Fvzz#^!;1$q_kA%24CEc>i`pd`TH#GSql3*SCl-DMO9tvTqSzQi>YSW#1ycq#QM#%f3Z?Nl9uv zmwk))l9JSTF8dboB_*k`T=FGH#Fvz$#&g*>XiJ*wJo%DAzT}Abl9JT;c-gmzFDXfl z=dy1RUs949&t=~tzN92Ip3A;Pd`U@aJePfo#3d!E@m%!nba6@dzJz?qAYXF2xul)T z=OyGzPN++oy@0wzpHHK2XQVDEOO4Gh`I6JsCGC0O?>F)#r@KpYgZ;`&FWHp|P`^mGO_`W}0^i3ZwavqZR-6gB>@v?8umo(q|m#oHf z*|&%Tq+~Uo%f3Z?Ny%zFmwk)$B_*rzT=p%}mz1o=a>=0Zz`ns>(#^&CrUz)8hva>C z$!dJO>>K!!?s)M&V3IF6BY(+GzC<@@n1{$;veREO$(Njwzocw6HoxRc&d6V~(_bRN z4d+2e;BDThY&AY!_AT<4l&!{dxxRrfX`W}~OD6e}GvZ5j@+Fge$rUWT(GGdS;9_@|TpY z#>dO`E%KM_^p{Ax$?>i$?%ThI*3q`{k}o+Uf5}dNi9Bi?Z?wLxqwV8m-y(m>PQFB5 z9FEud$>#b-zC>OT=IRK%f85BI$kV~x=zfxX$)vyJjQEnBe95H0bJ@3uFDYA%=dy1RUsARj&*l0S@g-%e@m$_d zMtn)xYCM;Hi};eV)p#!Z7V#xJHpQ8fe90N{CHp$sHeUKm&WJB5TaD+kZxLTowi?f6 z-y*)GY&D+CzD0b=PJf96H(1{yzNBn5K3?`M;!Da_cCMK;JI#CF@tgx4$>t$(KlQ*TU;)RFaC1tDeT&!# zvekGl`xfyfWvlUA_ATN|%2wmK>|4Z_l&!{d*|&%Uq--^w%f3Z?N!e;V zmwk))lCsr!F8dboB?tMEjeN-!@g-%evGI~Gxgx%#Y&D+CzD4`vl&!{d*|&%!{K zcrN?qd`b8Imwd@af5{c`C1tDe@v?6bUsARj&t=~tzNBn5mP@|miuT7TTaD+kZxLTo zwi?f6-=h6-%2wmK>|4Z_l&!{d*|*4FQnnh;W#1xyN!e;Vmwk);C1tDeT&`~sUsARj z&t=~tzNBn5p3A;Pd`a1AESG%A74aoytMOd+E%KKf^p{9*gY_cvmmK6vB)DO2!j~N6 zOC-2qZo-$8t;Xk!{KcrN=E@g-%e@m%&T;!6(l zB@*0Vej~o*AYUTE4RaHo>mXku!3}d0p6lTLI1=12H|iVxB@)~)H|iVr$Jw|)&K2<` zWvj9CjQitU5noca8qa0lBEF<-HJ;19MSRJ@{c$9?!EuZDlCss#V;ybJW#1ycG~8(ffdPw0$19zD0b=!ToV0 zxZ!wp1m5Op5AKg6!3}aFzU1KkI1=12SBA7;ym;R&!3}eh?*ooS6WMX&{y0~}mmKt$ zNN~gPM(Z2-5(#dY8?A5TOC-2qZqzsOB@)~)H|iVr$C2QMxzYXPI@*3dux}AxQnnh; zMc;1lCB5%24)P@u-1t1)&X;tb8!ej1#!J5BcD|&Y%f68>xt%X*=W=}`Uvh&l>CP|L zH}WMn_>x|3*=l@#(YM?AlIA>=t;TcFx7+!WcCP+io{PTS5noca8qY=F?uaibTaD+k zZxLTowi?f6-y*)GY&EaB65OE2b)?>XzFxK(&&B=Z9q}b)tMOc{Z+FC(l&!{dvA*3A zUvhGP90_hXzsdSmwi+KV`xg02%2wmK>|4Z_oZKHrf*a05az9zN8XqtF7V#zLI@+Gg zzD0b=$^CI8xWPO`e95_vwvCtjNbV<3`b#9ZVQ$nn z?vEqE4Re$G$+Fe>{IYKmUvjRa?YZn*#Fw1hA4h^4%tOSNob;DSaKqf>_gmR&Y#zv$ z+!0@LE}F=5xxPhw$w`07PJhWA@g?Uv+CEDx_JGuD%CczDJ*DsZ~ z?8K+~|IC9c@2u>|4Z_oZKHrf*XuC;!95YOC-2qZqzsWOC-2qZt_0hq`yRh z8|Eg@Cr|oIcJ7aJM|{aie~AP)9ByxSZR;`j$GIcEKpwfJN+eh#Fw1pOLp=lcf^;Jt;Xh;e90Z{ zk5jf9&t>1D{c%qEOC-4Aaf|v!zC?l>=0<&6N89It>s!Q^oa<G~8{=8(hr189j{t^jpm>czte2D}%%#Hd+zC?l>=0<%Z zUn0Q`bECeIFOlGexl!N9mq>8K+^BElOC-2qZqzsOB@)~)H|iVxB@*0t?i2APC;1Wy zZkQYOjeLm&H_VOt#{F?5xM6P8w`Hrb`v>wRPsEp;izf11^z8v(vReJ^>si@qJQsa? zBEF<-HJ*#UJrQ40wi?ex-=2ssDO-)_qHj;cmz1r>bJ@3uFDYA%=dy1RUsAT3*IWs1 z(2IyKDO-)_vTqSzQnnh;#rpO{d`a1AJePfo_>zl!i3B&C-(-Ee=r57rhPlc5cCDlB z^T57Ed`a1AJePfo{3T_p@m%&T;!Da_mt5pa zB)DO2azA;IFOlGexyk+HMZQFW8|FrRBVQuH4RfQut)uPd1N#>7B^UV;32r#vuB5gJK490FS*EG~8QQx>fjs!Q%jrvBuM1mXUMtvh+BEb!FqxFq^i3B&y zjrvBuM1mXUMtvh+BEb!FqxFq^i3B&ujrfv_e2D}%%#Hd+zC?l>=0<%ZUn0Q`bECeI zFOlGexl!N9mmK6vo`^5G$d^cP!|_IaBVQuH4RfQukuQ!q;D)(T-{>!q;D)(T-^iCpaKqfFZ{$lPxM6P8H}WMC+%Pxl+oFl=_uI+7 zMSRIczC?l>j5p#-F7hQ3+%Pxl8~Kuhe905}OUhPb^Gm+uiT1}STaD+kZ;`*`B3~lG z4d*xN8~G9mZkQYOjeLm&H_VOtM!rOX8|FrRBVQuH4RfRQjeN;LzT}Dcl8bza1UDFO zv_H;8zC?l>=0@uq`I3Wt$rJfYF7hP@`I0BvALk-pBEb#kA?h3X5(#dY8}*HRi3B&y zjrvBuJMWLHl9o3Gv(ClU?LX4)7()jn+5vB?tHt zbJ@3uFS+S2k>CdN5b-59`4S0km>czte2D}% z%#Hd+zC?l>=0<%ZUn0Q`bG>itZlcjQ@+A`7FgNNO`4S0km>czte2D}%%=NxCuRG*R zB)CB?_>yj}{?7UazGVA|_Q$!&mq>8K@h10^H~Eqie2K;z^^JUq1UDRS)Hm`a65KF1 z>KpkI32vAh^^JUq1UJl$`bNG)f*a;WeOpJ{&fm$tMSMxwYCM;Hi};e8e2D}%n1^V8 zoSS@!1UJl$`bNG)f*a;WeIs9Tf-l)VB7ezEzC?l>jyLKX`4S0km>czte2D}%%#Hd+ zzT^a7qWO*bM!w_(U!q)J-j5p#-%2s3RCis%=Bl4HrKpkI32u-Z@g+C;5(#dY8{JQmFOlGexl!Nf zFOlGexl!NfFFD~a**=^vDQjfsJk!y(>lyeG%1-;!AGwB`5e2X@+Bwu66HpH zBVTfYFHvr^zL76E!IvmE>Kplz6MTtst#94y1NjmOZqSQG9K6j{+~iA6@Ff~=)HnJ| zPVgnljrvBuhX+MbL1$r14-WvlUA z+)s{(FDYA%=i+{HM0`ovYF=|Cxbf@caK5B{KIrP|xwxMk5noca8qdZ1w-NCrWvlUA zybl-=U-FPIk>G~&YwKIh_P6i*9`Yp;+%Pv;-yZTM65KF1S>GP=B@)~)H(B4xR^!Kw zeRIB~d;W5N90_hP-iR-G$d^cP!`$S4@*!U$!3}eh`^krVi3B&yP3|Wj@+A`7FgLlM ze8`tbaKqfFZ{$lPxM6P8H}WMC+%Pxl8~G9mZkQYOjeLm&H^>EF()%6z&|f0K4Re#< zZx8tr32vAh^^JVVMZRQ2e91$;j@SCuy)PkOBEb!FqrQL+7AYXEkFBywCc>jDLUviNz84+LdkT1E& zmyC!ndFU^>$d`k>Cco5nu9U$P#`bZVi4ZMW;hONQem%~;YU7wM7#x@2{) zF{qD#tE4;vqr5H6V!T=Ebu zxd@j`hfBJ{)v>l&AX_pcwxmooo{M*H)7g^laM?AYB{M-wB;G#b zWQo)^j19V`T>Vb>*+ti;lO^5Z>hC-j3)@V<5)D_cSv{9kOTZH4vTF|(wwZt>%GIUm zb-Xg$;IP%L*!MsG@Y9dq|L(irbf*_xlh}r_E9sB1z56{4SJzb^F1zMjNq4yDn!Gj~ z?z(Y&d$`0(+9w>ew_ zB{zYRxe$ZT*zN^~K#7btJQ=KN-Qlun@)(coL15 zT_aC26JLpPSvK+{a}frg^UytP>>6>BncyTEF3U!oWF|O?a#=RwBy#})>(UoYttQ&EX37ljd z#c%!~RxayCoMa|AiE>#t;v^F|Nq4;L8*!4k0E6JTv2VmlW`dJw9@sbHB(u)gx9=l~ zlgMX-%X&Rxct00E+T^oguJx_k3*sd5*)TWi8*!4GILSoIYXncyVKW#5RC z%mgPx>>F{CncyVKW#5RC%mgPyi66NxKlDZPTsZFjs)Ro*MO7yxb z%4Oe3l;}~pIbS0WRtZ(w!aJ=5P-u0p6G(KK%C0n8^(LurQH~DNh-l%T` zOXRa*Zq&DRw0$1fHwR0a>v73xJePfo$dZ!NcrN?qWJ!CxI&VCeeRH&=os0ENJ{ugj zh%FgpOXRa*ZnC}&>PqCZVXpVBw{8yVO60R)ZnVCUE|JfMxl!Lpmpr6Pwk5E5`Tf?s z?od}EpAE+wt#8Cjs57H&l*)TS_ogAb~q_bh}I$_^l z-e@a%h?i^;UNVT6Jj6>j$4i=6#UNht5HHyxykrnBd5D*65neKAE0NBI$Ia{3yzCG! zkQQc@Od1x!yBD|#BG`0*8FWG>XbmxJ~8}X7Y!b=A6l81Q72E3#@UL9?l2jV4L zgqIB3N*>}RTZESk;w2C9k}bkZ2Jw=Ic**8?N%#6dTZwcw=tW{H*~(4h$BlhUY$eLY z&o}98INoS^qpjp2Ub01a$sk@Loejnt;U$B3$wRzki|~?i)7Wt%Ub01aNx5k}m$#D< zUQ%uv&*kl8gqM_?#&dZ)>3B)EZ^TQav*Gy=t#8Cjq_bgew7wB9d5D*65nfVm8lPX@ zPDXf1xoJF?eT(pta?@BY@siE)lJ@z)^^JJR2E3%XZW1qfh?i^;UQ%uvp9l6W!b{3c z>Kcs=5>d7iF7uc z-)McKtwcH-=0<%ZUh)tx*&@88+%!JF>|2DFl$*wL*|!KUDL0Mf5--^zykrnBkN4Ub01a$)K-9Ivbv6(fUTb)Y;lN%Q(pdK%9~-}VSEDLswnVtv~qyrldzo{PTi5nfV$8qa0lBD|yoHJ;19MR-XG zYF=^$o8kT2UN6qyeg8Js(e_;2Pwo+3QidAO#r@>&){^FH|5DU=F8dbYB@=jw=9hh2 z`=h-5ezO!cK3?{10S7^@uBV>MzD0P+#BMm62lg$(OXfP-K3?`M!b>K0!_j!zH^)o5 z*GcS#BM6gyi|~>OyhOR|o2yH@y#QXKT=os_k_DT5nl^u!J>pBsRpaAj-<&V0RjJW8@Fjw@*|&%U!r;7`WER+N>=0JW#1ycq+~Uo%f2~Z(!;sRRpYU&o8u+jScfNt>~nRC z=#o;^*l`s?-hpR`?9?P;taLEK*qG@2+>UQDnn`*!%%4OLcF6ov6aEWqRwg@gM zQ;p9r%ND^UWvcO9mMwCZl&QvZS+)o+DN~K-vTYGuG69$9OBU8Gf=edcCCcT^WCWK? zxJ#7FzD00JnQCl)=`PtLxTH)qp3A;DT++PkfGyE9ux^pMq(n77T-Gg8mz1c+b6K~D zEh$lr=dx}QTT-GL&t=^rwxmQgmP@u|cebQ^I`CGKXvywqNjH{@8_AMAB1=kBfwt+0^eaKLn8qa0hoGj_yJb)}& zW*dLgvPWb|X=-e|Bun;)EGbQm=W=n2#3d7Ci9XZh;ueu5rK$1pvTqStQkojiW#1yQ zq%<|2%f3Ne(tJ_^vPARCzD44a($x5P*|&%+DNT*%vTqfzC~oogt$cW%f2~T(tT15 zafx!-w}>n$O^we3`xcQUrK#~;_6=l7vv1f3NAtkGMPx~7YHYkDOLmYY-SP5vl4Qvq zktL<6@$s^6PL_1x13|F&BM1BC@13H9imM+X1qqcm37FQ;rvXJ0h|~Pl=ez zzJV<1j#q!@^T57=Ea~RrU4YCsexG{O8SwcKyqk;lZE!!F17t}z7tc!u#U%&Gl5Vcv zv%b#n;D$H{$dYC*$&x{`bJ;hNB?rioZZ7*qvg80+(#>VxC@wibmUMI3H z$dYcZ{?7VFvg80+(#_@iMzZ7pS<=nr`bM(k09n$_W#4EnIU=%TBUv&?mK-2Un&XAJ zWE(V>93V@&x$GOwB?rioZZ7*qvg80+(#>VxXf8QGmUMI3H=0WhCri5P5H`lqapU^t zXh}PleIr|PfGz3H1N%m{S%jBv>TxTHA`giEBh!TJWc zq?^mW5iU6ZmvnR4H*Sn`050j~vTrn(9Dqx@x$GOwB?sV=Zm#~$&jA47#K{ zUiOXVk^^)}HVxxG~NFx}=+{zq7t^W1ItYNjH~$BVBShUD7@u*f-)O zhvOyfT=tE8$pOBkI}hv|H^w=@mo#&+F^+Vx>>K!!ZZ6k1noADwCEZ;1jpmXAd`UN# zeWSVLi1?E7)L1XLG0p+Lq&r^yo#%3W17Fh3W#7n`9N>D@6Ilz}RbFndwo=>rF;7hu>>>JG`2l$e1F8fBlVx$d?@8OS-vS-?%Z(0luW0%f4}AoCADG zGZ!1VxXf8P-zGNd` zBDD?X7ko)~yzCqKk|W|vHkeB`sckr39f9C{VBcsiIlz~6=Yf4AUvhviY39OQqIqE7 zz?XD$xxUd{a)2-C=CW@zmmJ_ry1DEdH^w=@mvnR4H*Sn`f-mXj>hJ7+k{jck;7hu> z>>K%#6MRWGm+KqNB`5fjZZ7*qbIA$5q?^mWabuhld`U02JT-RQ$d{bpOS-x28#l%| z!IyM%**9*Cb4Gkgd1`zf@V@&5U(y{f`^JrN&WJB5PmPZk>)RReCFQAk&6V25*P%1w zOUhH@xme%Mh%YHmjpyR`+ZpjC<*D&p@LXp-(Rug1|4zO{Y8%dPazD9aW1LND8|EhW zljW)Lc>rH>!d%kq1# z^3>RMhkVHy@g+O?5~*!){ziPsPQGN4FF7N=WXH}pnqT%U;!Da?_>u7r}*SCl-*~yno@+D`)m+aUXXOr3n=UK#;?CWUTJdiIrBfezE&Nvz`?#Fvz*#&g-Xh%ec(Gmg#& z_ATN|_C*uz4cZ9i`8Tf~=?s>XBK zw}>y<7focjz4cZ67b!w}>y<$(KlP!|_Ia z!_GLG2lg%EOUhN_^T57Ed`Zb_JePfo_>!{KcrN=E@g+O`B@*1=xJ7))zGxyFFZq%) z;!AeyjI&8_!|_JXOURcKk^((fqP+5noca z8lMODE#gad?2M!FvTqSzvM-v*$IHG&e92C}M1mU}w}>y<7fod2C0}wze92CKi3B$s zZ`8MSw0*qnTf~>_>u7r}`xfyfJNXg`Za5E7-^iCt@+GJHOS->f=`WGshU1OyCl^iR z^UJ|4Z_?CWTI zF8X#we969OBF{zNu81$$7focj!%+*|9T@a{#Fvz<#&glPE8|4Z_l&$79SArYA{$3GZQnnh;W#1ycq--^w%f3Z?N!e;Vmwk))l7oDS1UH=DWPLlx zmq~|_H~IZmwi-Xr*tdu;DO-)_vTqSzQnnh;W#1ycs!Q^l&!{d*|&%l^tJ{gB1^8}TJ&tMT!&ZxLTowi?SNUvfo!N!e;Vm-mwqUsARj&t=~tzNBn5p3A;P z{*toQcrN=E`AZJ+B^&vYEAp3=t;Wa8zD0aV*=jtOeT(>#vekGl`xfyfWvlUA_ATN| z4)P@%`I0N*OUhPb<0W5mMSMxwYCM;Hi};eV)p#!Z7V#xztMOd+E%KKfbJ@3uFFDAUY~)L>h%Y(Fmu&QxToGSV zwi=rU@+DWqmz1r>bJ@3uFDYA%=dy2+zocw6p3D2mh%YHyjpwp&5noca8qa0lBEF<- zHJ;19MSMxwYCM;Hi};d*e91<>h%YHyjgOaoi};eV)p#!Z7V#wq`4S0k@cS*|OUhQ`<7M9> zzT_ZZvXL*jBEF<-H8x)IC0FDxDO-)_@_sVnOUhQ`x$IlSmz1r>bJ;iSkJG&FkS~$o zhUZ!Ie3E?0M!w{V{3T_p@p)k1BEF<-HJ;19MSMxwYCM;Hi};d*e91<>zr$$rbS>Wvj9IC0}wy{*toQcrN=E`AZJ+B@*1AZxLTowi+KV*SCl- zIo8qkT=p&EOUhQ`x#-&+@g-%e@m%!nj`)&;e91<>wi?f6 z-y*)GY&D+CzD0aV*=k;MCAjhH!{K zcrN=E?T=Ho8qa0l7IE-4_gc0Z&t=~tzNBn5p3A;Pd`a1AJePfo_>!{KcrN=E@g*ny zB@*1AZxLT|k}r|qhPer^T(%mU2l6F%#Fw1pOLp=lcf^;Jt;Wa8zAfV5{a%nSk>G~& z8}*HRi3B&yP56?N{*s;kk~`u{%2wm^%f3Z?$w_~S1UHz6h%Y(Gm+a(A?uair=`Y#I zm)sFwQnnhKU;0b#h%Y(mFOlGe^SgdwzUvDrTaAyGeT(>#ll~G3ZaChkZ|i9Lc-gmz zFFDuI_FS%S;7fYH=gU^(x$IlSmz?yMNN|JsjrfwX)!2B+m)sFwa?)QS!41b7t#9;~ zNN~g4czt{t^jpm>aEc~Dk*XA^}Uwwpg=SN1H$MW)TL4@%Va|eJ8h-YRUD!E?`On>cJA>s>70A0 zE?VdK4y0GZGb7emGj^;eM$m5&U$Qg5L;*LbH{wfn=9ehohPp}sef<4PzGNj|az=c~ z&is;!G`i2`m|Z?v9deu)BZ zs2lY+=9ehohPsj8$d@SKhPsj822EtoFYm`WBfey3eu)BZSZ~zd$d|0-OU{Td*_mIm zGQZ@E_>!G`i2`mg4iR6nGrwddUvfr#$CUS$ZyOqQNRs#Bfl}fL;*L{jr>Nw zL;*L{jr>NwL;*L{jnMk%f4d^Sq|$0!7ya#u z_>xMiab5Z?;!7&6#&zkph%c$MntNRZ+~7Hj_>xMiab0{5xFWu!(rR3nev9~$N~>{Q z`Yqy14(69A;D+Oy^tXfgB?`EqZqnZ>t;WZJev9~$gZJYo;D+@k>&auxw%1F)MSRII zX4`e?w}>w}$d@SK2ICO%B?tKu1>8_K`Tlk=zeE8y)J^)^LB2!*H`I;#8}myPa6{e5 zZ{$l9a6{e5Z{$l9a6{eX_gkga*z-%i2l)~O+;AKszwv$?1>8_K@*DXQ1>8_K@*DXQ z1>8_K@*DXQ1>8_K>Tk?1QNRs!BfjJyU!s5;>L%a258jWXfE(&Yej{I^fE(&Y{f&Hy z0&b`q^*8b*3b>(ePCJeU!s5;>PCJeU!s5; z=tg|WLB2!*H`I;%M!rM=H`I;%M!rM=H`I;%M!rM=H`I;%M!rM=H`I;%M!rM=H`I;# z8~G9i+)y|28~G9i+)y|28~G9i+)y|28~G9i+(0+tOOBCNW9umLC0E3k9OO$BaKm~d zzmYFdzzuaHzmYFdzzuaHzmYFdzzuaHzmYFdzzuaHzmYFdzzuaHzmYFdzzuaHzmYFd zzzuaHzmYFdzzuXGzT_ZZqJSIfM*WR^i2`n@8~KfVi2`n@8~KfVi2`n@8~KfVi2`n@ z8~KfVi2`n@8~KfVi2`n@8~KfVi2`n@8~KfVi2`n@8~KfV$wt29iujU)e2D^XP;bPS z9OO$Ba6{e5Z{$l9a6{e5Z{$l9a6{e5Z{$l9a6{e5Z{$l9a6{e5Z{$l9a6{e5Z{$l9 za6{e5Z{$l9a6{e5Z{$l9a0A_lFFDAUDBy;=QGX*}qJSIfMt&n-vXL*jBEF>3YHVFi zzT}Gdl7oDS0&X}C=C|>(_;CF1LA*ryHk38Hb!9czJ_>YOlwMLQ^TRpYwuHt9xgBVD3+8+#n28@Y{iiQ;Xj8+A9*C5pG9Zq(gK zmnhzby5_d}_WfbIRaTA78|V^^ui34wOTS(2H|Zwbt+HyoUiX`HlkQeoHLmM^lWx-8 zDyznI>9>e3sjM2;rQagDq_S%6bro-e=PaU2DyznI={KiKDg&YO{A#vcmwt=rlFF)a zUHUDeOHR@yinrnTMt&n*qIetXn%{bDv!ZHz7-+W$E~%&**QMP&yrf&M-mNZ6w?%Bp zNw!4cHW=NAEjh`SDBOm+Nq0NRmMGkYx=D9C$(AVGhPp|2JIR(P+=jYQcOzS(a2x7I zZX;Wwa2x8H+qzwoY>C2cs2g=RW|t`3hPqLABU_?y8|X%CNhQ^okC9!n-XgZ-BwM0z z8`c~7jcmydwnX(tej{75gDsJ6{( zZ^$m`>T*2^wq(75E$QlNw!L2Z4R_;obv4_j3${e{4yAXQR9#)ow(HVw$S&#X^4A;K z64mSdt*fiItJh1v;clF!F4+==+rSsN8>g#Fzkw~$I7EIUTe5>Kk#6KSvLy<);W&7I z>y88c2DW6qfi3Ck(r;i(q#N}&vL!p%66uZ#-}!C4e6puOV(S&mQ+%Wy??=$NH_8u*%F1@V0@#yaZa)&JJ=G{8~KfF$qu$ex{=?=mMGkY z;}H3cY>C2cs2ll>Y>C2csO$Z$`TUYCQMe6tBfpU?*};}*-Xgz|Em61)>UFlHZp>`- z3$i6U*pl@Yu_Y(jk{xV`bff-8wqyreBHhSuWJ`9iCDM)jMz%!ZHk`M}Z)8h$uqCQD z@*CL_h1;;+$Zupz6mCP^$Zupz6mCP^$Zupz6mA3Eh%GtEmh50l)?1Waa*{3C!Inrj z@*CNb9c+noBfl}bWCvR!UGrP_eMYuq2U{ZD$Zv#8cEBaljr_*!5{29FIg9+p>=K3B zP&e`$vrBelmuMU!zm3_pb>9iUO%YvENj0vE{gNr7OHR@y3b*m`og%vABwezTE}5e2 zl1i$vaUfkXMR(&=QjP1PzfIBIIF(f6x>!$65nWPAHLeT4O%YvENj0tuzfBQcQb{$g zi~cr6bjdYl+jZ%;h%ULtY`ZS~=5$H(ySDh{;Wn(-`&(BRep9#&bitQ&b>TOK+fdi{OS-z6Z5vO)KrQgVxOt>4TsY|{@;WnJN$ZzCJ6mCP^$ZzCJ6mCOZUr%<&fqo-j zG9kO9t4qI;FPXrXbam-B@+A}alCCcOM!sai-8fxc`i*?a1iqxJOTUpXnZTEHb?Gg#FzmYGQMw&(N{L*jaOD6Co-FoRa@+DKP(BFN3YwD6O zImnkx$S y?1DWEyD}kB=|2OB8Oy=Qr{jvr7(Sm#kC7mt4#)Imnkx5npnR*|v2Q zvP*Q=UbLQMcF94$WQzEbi`gX#x52zce96V^l7oE76!9e&vr7(SmuP&W{zks!AYU>? ze96V^5{27vd?UY+FFDAUOc7slkuN#OmrNtg;_>$bvr7*0B~!$gT+A*x$d^puOPcRV z@+AlPk_miCSC{>be8~j9q^ryRM!sYMU((fOeo1~Z{$lR@FiVc{(d80GJ!AY>axF)FPXrXbalC&BwsRtFX`&i zZ{$lR@FiVc`i*?a1iqxJOTUpXnFew2`1_Z9$w9tk8pJ`MOTUpXnFetX=xV&oZ{$lR z+>O&5U-Bgf`H~5INmrMCBVRH(U(($NCtq@qFPXrXbnB(x$d^puOS-!B8~Kt6d`VZA zej{HpfiLOm(r@HTra>G${``_JImnkx;7gkIk}pxX4c3!`I0)+1f8YE@zGNE2L7>b2 zM!sYk#6h4-zmYGQz?XE#m;H@=$ppTnt4qI;FPXrXbam-B@+A}alCCcOM!sZnzNGs; zBVTfmFPXrXH0vc_a*!{Xz?XD&+26>QOh_;3>gw;zZ{$lRq?dGc={NEv6Zn#@F8xNn zWCmZ-)urEXH;(SOkM>K*mnhxF-;*==l5V~98~KtMd`VZAej{HpJ6|$3K^vdZ8D64v z8xDiDx0b9DIh0gmPcO4eW~WQKvNRi`OJ;{ly0V%BuNHfgGuV>WoM{yF-*;Vn3z(fP z>6S~YUHB9*J6h6}rPD5a>7Jb|DZb)^kC;XQolU_uc*H=K=%4rDM_0OV+Ihpy9tk&z8>y2cIf^Dc9{Bn~n%%)%)>iSA@RNr_W#=q;{ z6$-YYuB{}Sk1sF9QLYVTZ6Vo}h1pJWC3C`+XmsH=#oC};e6rIN@j2+U0wQ(T*(Zsq^nE6 zkt>)*?`y08E8C*$M zSAS=HlU&IRuB59=zmY4M!Ig}+MdLk5uH+e6rIN@j2+U0wQ(T*(Zsq^qmH zvw0&|GJ`8=>XIut$(79DO1irA8@ZAhxg}j)`i)%446dZBOTUpTnZcEGb?G;9B{R5^ zt}gvXu4D#R($!^uBUdtmE9vUeZ{$j5a3x(``i)%446dZBtG_e9kt>^c%U7 z8C*$MmwqExGJ`AW>e6rIN@j2+U0wa1`Hfu346dZ9ORnT3S2BYu>FUyN^c%U78C*$MSAS=IBUdtm zD{1PID>=!P%-~A8y7U{lk{Mh{SC@VxS2BYu>FUyNQ_*TNcnIU0wK1!8X*@3_Se3rBZ6VUeF~=l3TJ?N{#D+E?JV? zl64|oqF@`2gWh;|2H}WNm^CiQ4A8tbvuf@5Dmn@E#bY(RQ zHfy9y7N<*^vV==6!X--tmrR69F2W_tzzyym-sZ!=(2|RA$r8aO6EDTN2$w8?OJt(X z(?Gc7B3!ZnF6rvhY=lb|hfC^Ha^vYGTyhaESsX5D>(Xq5OO^;OnFyC$gi98{CEf9* z-3XT~fJ>UXgi9{MC5yu)-SH({auF_B94=|=vbhm1S;jRfcRucp1DhM+k|lymDx$_- zlY~o_2rj9J8rS7wGJ;DcUW#)OE?FYDWa6bb7vYkno`83Yhwi-L$J<4?WQpLCiI?JB zgiDqPE}00IT!c%O2rj9J8haiHmn;!nQV}(-%f%$%l4jo=v+cTEOadgu_1T`nd8 zmvnX6-w2m1fJ>UsFX57laLEF=q^ryRMz~}FT+-F0-w2m1fJ?f%>~Dli7QiJY)&fGhPu9axEPE?EGVbanN2)-MQ`EPzY8 zy7U|2k_B){SC@VxT(STzX+96U6z3vbvH&jW)=R$;E?EGVbam-B!X*pflCCcOMz~}F zT+-F0-w2m1fJ>V5M!4i6T(STz>FUyNgi98{C0$*Om-&rw$pW~fIljCU=OSFP050k3 z>fhz{V!uSE_H944tIPgIxJ2iZO}9I~^c&$4ox_ZD={Le9I)@qQ(r<)IbgOivOTQ5= z(e1gW+ncwFsIljPaEWg7G~M33RYZ;JV!uSU7MgCiUj3cxVt-P%)J3}NZ-h&93ss~` zzY#7G#}Mh#Z;UR{_vJ{}{ie48;F1+^N%whhzeyKx$r?qMR7}m?^B`ToB}&7N#=-q2 zUBD$uRZesPmq-`;lk14Hc=&r(1=aXC&~F1b2z1?Vs+WGlr8v#!0of(e#rJ@<@U2I` z56yr}q|5#WxTN{sL3oLDu|K&+aLJ7D5_L)XErLsCz$Mb9-yAL}mwb3XY6e{*UHZ-G zlD01WM!aNoyrioOzC`uXZ{SOs&oB5A>C$iDOS-!B8~KtId`VZ=`e-y*)GqH65D zL%w8<_>zjMab5b&`I7eY!2U+QWOcrz346{6FVU)$ev9~$imI`3AYZbAFKNEd5MH8s z+26pIGbe90Q|B^6a; z&jb0A6?{pv-Z9&*OTU3H>FVn5T$g@}_>zjMab5Peh%c$A8rP-YBEF=eYFw9o17Fe| zU;2%F$?AMblf$d18mpIl$r|w`6;XE5m#h(AQc*Ro%inL{OPW3& zv+cU{8~Bp0F4vRfOV)@lsi+#Smwt1;r29O8FVR;8t|ueDq@rrPUivNKODd|yb?LW= zFR7>+*QMVgzNDgRT$g?WU($R}j@dR{@+E7;msC`Z>(X!FOPanIv+cU{Tf~=CRE_Jh zzeRjWMb)@2{RY0IIS#lKM_=3MxA*fU|MDNt|MKkhi!WY2`}o)zjCXy?OcXPyc1Q{a~4&{`@q3v^{(N?5j7gzIgTa)xW*``q{_-{Fi4h-oAbF z>R-QkJO1xqp8fJyzxm{czj*fXqO&I66eeAqXprx;p(*H##RvDKCF{@Vq&-y28vVy*HP2qH_X6El>feT&gFu%7 zHI%G>8g9zcW#|NwORH1449#+O-u(XQ)3089_VP`;qu#1t-i_H!E!JA!?eO<#ef0fcOO>uqv2^`KDqWl6 zwyw{ybbXGcYj4uFu1~Ub{Z)E9{8f6ddp{kY{Cs`&^y%A|FWvZZUU%C@erNTloUO6l5)q^;{OOX>QO zM7s8}yw|;-l)t*-`P2Eu7eD*))9;=>T9@PLSL1)(KAPt3=@)Io=;OIR*jg9+gT1c) z?z*q(JLaaM7VnHGU4O8p8$8&m*B@-@`h&f${`P9u>x%^G`s+)&wn%8}`YJ&*9-jTx z`RKMTp8Xs7=+*h?wl1Fi8~Nzf`RKMTp8Xs7=+*h?dtH0>|N8q&zoy=P`TD&-!)_nV z{oi4?4IeRXIx}xC68%_wd{Hl1-&2(=n~{IR7!O#Z7mW{Ach-`uTUOOtFY3y&72$-e zWX-W%SvRbzb;Ig~^Z0T@W9xpEtov26qrk_0HA>d)dRx${B&*SXT-MzxS?^SmwNBL? zTQ{p@y-`Wl8dX=;y((GnQi);|cWvT~Ef3fARwZ3CQCru0mFjgDN!NN+Ti0zQU2j&> zH5=XQ{wGh$S$Tys^ApKR#{lPz7JZ0Y)BOZUB#{hj0MFHPzCOY^Lj_3k%Md*1x5DP3QiNO!c%Z+}a* zb^W!e+o*kUB3*lJwsn1VB3*xPO4n8=ZC!tHO4ok`NY`GRZCziVNSA)|^+{J3n}gD& z-+Y16)}`ODLeV%xe!~()_0n&?L}}MczhRA{dLzGKk)nF(H(#W*>!shYN;x;*A#Cf? zZ&;>CH}V_SDZ2fge)DxoyI%SY3l-HH`EAU$^*8JiN;m3n*e29C&~Ls?*c}J#6H1r; z&G!l0y6kUA(9<|X{cX&)k1zY1?-aJ{Wq-p~;aOWqkM|+KY#LwoH{UC4*Gs=)vrzR$ ze#36zNt{i(QGdgBp>)~be7mqc4)hyezX8QKLAABVm;DV`n{=b~Bnano0@o(p$Zr7Kq|5&1U|V|} z*xx|5soto+joG&60ce|aBfo)d(>Ty?&bD>O0dSji={JYl+Pds-AVf3{k>7x~sb2am zAw~9GnqH&<# zK!~W`$Ztr{J11<8Nmn!Q_<9GMW74JHlFhNR@)CV~`TH%|9Fs2l8#c!@4w`{r9N6D* zJ>$81f?oH%GiKYz0qe=#6ZG1;^cxcNRBz%wolC+M}ufqp}R zp6X5frX(oVi~hEIf?l&;CG=1ie%n1kudU1ehU*zM4oQEjyhNWj^tas;^xE~(Z%EKP zcTdo3>(XyX(35Vmo~*pY`*BdjqVI$6b!PI>eNPdZ{yZpRk-CZB^wEI2^jn=Je!O1z zZAOBg#y9dC67dHvaqO3nb`CH}V^9Xw*2+ zZ=Rsn9tZjjH#DBRC+M|x={F?kNjLHv67s^jy|ym>h6Fw7Mt;K$jpvL6J?Tb%1N16g`pu!&_BhaQw*1OIGqFide+DI^s)K5U?6w_P2;H zsk}sg9{Bq$;!7$o(RJy!h%Z^mmndQp;~ViMD=1ivFZ~wrB{~F*=Zt*G9`PlWmuTZl zzGRR1lFCbTUG}$#FImZ#C}NTG7Of}AmndS9x|)H9_rX{4B{TVwJ>p9$FVV-Bev9~$ z%1d-z`Yqy1Rvbk;6|so%^`mIr{zkq;5sTD~_9t-|?VQP%>=9p5d5Jc@IE{Ah5nr;B zFHyuI$07ONz2ZEY#({o|_>z@;$xOavkNA?6e926{WRLig%1iWlqu(OFWF=psh(*p@ z^!tr`$xOave}B}+cW}^^m+0d_zeRk>O1?x9ix`K9FImZ#%;ZbHza0@@ zvW?mHae&{Bh%ed3Y`ZS}c0_#1HfGy(>9>e4*~VX_0n$zr$$wI#5i1?C?e91z-0-YGv1;9QHTe?es-4JHYwNPVkuO28T3eU>jrk==R%`2WJxRU<(Q0j7`i*=EvenwU z^c(pSgsZi6aXx_QYA4dw+PdIN6maAFsfbr=>vBEG{E{Q$OBk@G;2iob;!BvYCSCr1 zi};dCtFiYl^GgtK+#O$Jtf^kECnLV3(rUb3_P2;HVal57Wq*tK62`2Zj5t0Kv(_G8 z`i*=EGLGB2^c(X_5VY3TrQgVxAmzBLOTL6L#~NR~@gC+&Dy_zzGx8{>J>0 zBjQWy?gg)xev9~$N~>{Q`Yqy1Dy_zK>9;7qWFud~u;UY9$L)Ee-^iCB?YON=zmYFF zqWlu(9iI#Nk|W|v7xMivFDe3NpzKr(p0#f zBwz9!SIK+_Us7o`UN8L?@g;Ttn(2}+IU>HKE?{$Aet(Pjl1i&_U9Kmi{F1tY&2{Ml?-=h4IN~>{Q`Yp;Ysk9o`rQagHq^@CeUG}#qzogP?T$lYV;!7&6#&zkp zh%ed5mn`H(Xx#U$Twac3t@GjQEmDt8rcU?Tq-6N~0 zS(smPMtsS}{1OG+_zd`YF%xGwy5 zMtn)7)wnMFc1C69rPa7D){{zz4)zHu zt;Tifw}>yPv>Ml?-y*)G(rR3nev9~$N~>{Q`Yqy1Dy_zK>9>e4*~ynE;D*nccB~%W zH`>XUDBuRV5nobiH9ijXTf~=CT8-(FFVRW;XdJL#qJSHYL*zH|B`f(7oeYfX#s1_< zzCR(tM7s1F`4WBkjdZa;xsor@my$@Aej{I^FC~dC`I41xMiv2h?@az=bfrPa7D*OL)nvNOMAC0}wz`6ZQBvNOMAC0}wz`6ZQB8_K>Tk?1QNRs!Bfg~4YWz8)-y*(bXMTwSZdh-$p5*;F3b>(ew4TI8ey0L%s2i;( znO~xS8|p^uN%AEMxS?+3H|Ccp;D)-9-*Az(#+QDJ_>xMivF8^zX`ebMoV*{HU!s5; zj6=ki?94Awzzuby-*4ngR_2$SQGQ9K)!6uwFFB+9lAZY_3b^4oM1Es_i2`n@8~Kg- zB?`EqZsa%Sm#pMV1O_F~@0e|$H~KB&ODe6#b=lvd`*C*iB?`E~_(u69`=E)uUivNK zODe6#bjg>T5nobiHLlD47V#xJ^Gg(P!|{#$#{3cm+)y|28}mz6=9lQjp7?_KB?`D< zy^-I>Z2P>?ZxLToX*I4(zeRk>&ioPu++Z9czGP>9$;$kaGvZ5j@+B+zk~88yP zv>Ml?-y*)G(rR26e!C*RWas@j3b^s{y&}G3AG2-sk}tU;zGNp~qJSIL8~uJGU!s5; z>PG!-%(jmM{B}irNu|}eF4mJ*#FtcBjqAd1SHzc8T8-<%Z&$>ZR9cPe!f#i^msDDf z>(Xx#Us7o`u1mi~d`YF%-0Ldf2G4KAmsDDf>(Xx#Us7o`u1mi~d`YF%xGwz`@g)cI zOB8U!@lDo~2lGo5a6{dszg1d|j|2S{@grMJwrPX-7^jpN2R9cPe(r*!8a*!`kzzxSC@*DF@6mUb` z$ZyOqQNRs#lkWkQR^#JKzeRjWrPa7D{TA^hl~&`r^jpN2R9cPck}tU;zNFG>T$g@} z_>zP9B?`E~^APbR2lGo5a6{eX_gkga_&CsS5npmJzeE8ytT*x-^Gg(PL*2-4%r8;E z4Rw?60hLzc<4eCqd`YF%xGwz`@gMl?-y*)`;QcrXxWT+dd`YF% zc)j#n#Frf8OB8U!dZYfv{1OG+P&e}1m~9^i`Yqy1Dy_zK>9>e4ImnkN;0EIm@g)cE z$5Fryb(8OJl~!ZpK)&RP_>xMiab5Z?;!7&6#&zkph%c$M8rP-YBEF>3YFw9oi}Fh< zt;Tifw}>yPv>Ml?-=h0*Dy_zK>9;7qq|$0!mwt=*l1i&_UHUEJOAhiS3b=ufqx*3V z@+Atmp>Fj1jeLm$Zm65=Pafn;Hu5FcAPycrFLIDCQNRuBjrtq;5(V5)H|lTXOB8TJ z-Do{IZbP!?mwd?;@g9>e4sk9o` zrQf3bl7oDS0&eh}MfoKM`4R=(P&e`$`4R=(P&e`$`4R=(P&e`$@5kAgUvfo!Nu|~J z^FY5vd`YF%xGwz`@g)cE$5Fry#y8?i4&INWfE(&Y{f&Hy0&b`q^*8b*3b>(e)ZfUL zDBy;=k>ALdDBy;=k>ALdDBy;=k>7Yfjsk9|8|{~nFHyh^bR)jxAYY<@8|p^C-^iCJ z;D);T1^xIsihPLzZm1jiZO}ya-XULdMSRIYzC-~xtT*x-`4R=(P&e`$`4R=(P&e`$ z`4R=(P&e}1pox6m=(mV3sk9o`b-xKONzR*AT8-MlSzezXoTcy>w zuKP{8Nq?)f8rP-YBEF>3YFw9oi};dCtGU-zzzv?Wh%c$M8rP-YBEF>3YFw9oi};dC zt8rcWE#gZ~@+Atm;rK>=BVVF`8|p@W8_K@*DY*9ej!AE%F=rk{x`B zbR)l!FWJGDNH^+lydP&re#v!<_>xMiF~1?dM7mLbV}8jFzC^l_-PG#I`6UXtfo{Z?oMX0q z-src8FFDDVDByALdDByPCJeU!s5;>PCJeU!s5;>PCJeU!s5;>PCL!{WuD^aos86OHSsODBy;=k>ALd?Bq+P zh%Y(Gmnh(d^+tXpU$T=gnWFn~PVyxRxM97C--JzI{Xo8CiujUBtFhnn7yLFwd`YF% zxGwxQMSO|2`#BEq+Z6F7+TNuu{TA^hl~&{9K)*$NiGHSfy$ZO&a~AO>TIN%iev9~$ zN~^ga2L;@)-lV^&EwWzvE#gZq@+AtmVZBLzyU3R);D)+Mf4j(+DBy;=Nq@V@mnh(d zx=DY#$d@SK2D%Yna*;1lzzubi{&tZsQNRs#llA09zC-~x)J^)^MZQDW%o4i+qU!Zm1jew?PxxIFK)yBEIAzUvjMUTf~=K&b{O zxyY9&;D+NH^*7#+qktRgMt&n-qJSIfMt&n-qJSIfMt&n-qJSIfM*WR^i2`n*8}TI< z`4R=(P&e`$`4R=(P&evtlQ^c2C!Xl8b!F zLB3>)_>zl!$w9tkiujUBtFiGVUou5}$wj_I0XH1q$ZzCJ6mUb`$ZzCJ6mUb`$ZzCJ z6mUb`$ZzCJ6mSFGh%dRwmnh(dx>0{4U!s5;>PG#Ie91w+WQzEbi+ssJzGRB{l1i&F zzmYGQ266CkuEa&YL;*J(-^g#|OB8TJ-NSaZ z9Oai>i4ua=FZ&w>%@+EV`mt5pa4)P^)azBpn67VGoxZ%77 z{Y|=B&GDZzdU>W;)|EhK7RJ;S1&$$ z`R4i4`NbDM`|;E7o<3Taj_v6e&z?W~>dmV!UcG(wZ!f=o_VGXe<=Kn3 zZ{NK7*KgjA|NEC`zx>s2KKbD?v}1UOVagcNxH#WNxJ?lN!Onx=>}^h={l<(XgJpjDvwSdbeG@2e*o#}Rp?j-{;&(6VQR$bzmlgHwz294k8>TFtsY)n*To#Yi zg6&*YYmZd7T0Bt;c5@|bPgGYH57dIqT%A?12dXQJ=V`%Su4ISOi?=V|yn6BZvyZ#7 zdU@PGrVF-mC9BbYTvqQ6m-U@o$=XVwTP&zTOvL0wsY2dz5uVn0eHYtLp^);qmq{n3={Q2O@K?8^F+DOrC9N!FgsuB<z!V*-svT4oxUrpdA?gfNY*>OWNkg&mDS(5tp7rjY~nJ& z?W&e8bGW@*EnKFfF0g~&&DoWu%g_N<-NhH!0S#cC&;TSm3VhUM0NW)?m-+j@I|y_c zUjM2#aT&07RZEu*(D~s(0M#y8x@>UHkIT|!fZ8<(iOa@3o6EqoOEz&Ckai6MUFJx8 z^GN{FE?K(FiT186T?U|i)eU^fl(CnAXP4|K@KKimXJ04a?2=7-8EAINvX>3M`Qd5- zvrCpP^UFA!QwEk@vUHheC3a=$GN9}l+r(uc*;OrjnI|Q7tHp|O0?58@4zhP;*~`GO zOEy_C0%Kn%VC<4jTn36=vRpBGN@8~qxMBpvu4)sPfnis*beS{k&1!+LOO`J4h{Uce zSBxOoH3&&B1Hi6oxnlHy#BR0vJL_fO*HvxO%Yd(|TJ|!>*SpoyWuVvB+W&s|eG7Pf zodB;(HgOr)b;;6Y&aU4L!u>DsPrv{C0Gj;v{pW{|^|Sf=&kq`e?>|3`LGXo~HuSB< zjFm^@+u`@0AC{Z$H?)SRvGt!z-+z91_VM=r$!(k@`ux@Fm+kL7(+s9bJH_6brWH)n05Lw;o22WT4AON&N!Jb4 z)pbKj*9|3IH&j>G4JBPS)U<(V>gu|or0a%~uI)3_#(Zad-B8+!_fJ#ObwhRQbwf$l ze*;O^4b|0kLrK>SC0#dESJw?CT{o0;-B3N<1w5*BeX~KjwsGE^w*@?^bm2GkYI^~6 z>!shoqpIG-Z~P9ddf_*G2X2o8{e}<06FvmDb?G;J36^f+w*`4;6F&t@H}Ttoyff+2 zZ~iT~Jr3|2KL)Gb#BU4o&Qve`=3j%m_2P4|bm=$$9NgCR-972jZ~i^FtqZ^LgRsUo z@*DEbR4@JJUxeHB!f$Fsw(wBg!+6uYTPQW(JIFgzz3gxPO}Jez`kRDVZ{#<871l># z`mL67kB%pyM1Ko(r^A@xUEaS;mfebA?k0)J5#+_ zPvX;XyI!m(Cwv=Ly~%oV!N+0MOTYQY;dZ^~Z~QtuZT@w*txLb*^RRRyzaj5Tv;_U; z--p}v(r@@cta>BA;R~_qrQiGuakpN4B9<=w=AVe$y7U{q5o;VGzaj5T_0n(tk+@wi z{f4i^syFf*^3GH*{pO#E+x60K_)a|GJ8@f=e#3`i=|+CTmtwUG`pv%-x9g?f@Tpk! zMt;M$V%1B(`M2V3z4%xxUHZ*G7PocjH+(JDI7EKK=VH}Mzxn6lcD?i)z89Ii_@N_|5&RS?{_~gHK&a|WJPjQ7JG)3;{CWR zwhXnS$!hfydRUe_7~0UJtlmM7%fbNK&!nswpgFe4YaiR0l-1}zUM<>7^sp>?jkYo=YrUphEnUW~i_5nzy0UZ`cP=j9x#-H$ zW!$)^=!!)MZF$9~+n$Ti>zhR!f(0!{YJ{i#yrB(`VloJ}`asK!07p zxahP6-cws}#8$sB@Sd7*#CF<(Bes&o2u?U+D_K3ikIwgkBevQA#A;v*j@YVNyr(7{ zu~oIfYGA<;TUCqq)aLhZ-aSU|=Sijo@raVedukhjc@K{*(h((#_tfUMZ+5H2dul>B zqQ*8@4J^n;RJB+QY@UtStrqX83DJnt=2vfaW$7{`BT6<{4J-&o)V?*=+?xj@cB{o| zU_vgUsHL#7KrN^tqYG49lrY1Cg!#~)z7Z7Humc7ggv%3fEzQ6t_WDiU$muEAVXS<&_ z>``9Q#d~k&N2T4@XKh_f$;<`X?hCZGF5Y}IS7^Jh(C&5rlPBd?$G-1e@_iu0&wlkw zWfN%}e4C;h2=P}`aJvZ-{3|aw^56d3%Rm3ak6-@J7vFsT_8;3DJxb{EUUpL`s;#+| z&}F^sei!Qf%NptWl2N+e%%p2e#H)P6YA`?f;y9~_cPUN z{j6E<3hGR{-q56L4Xv%~9ZkBvZj`Qdw6?ClK&9&~O}f_7+PeM%m9DQGZ@b5jv~~Rj zDqU}C(j9&5+g{n$h2Ip43cn@PnVvKFO`)jNP5icE$M&XBRO%*vQ=W^hoTN*?CDhqX z!5Gw~-xBIfx|;3#9;Q%Kjzi=(?AmG^=(mJAQ@!w;LQz?7XY~N}e=r`ZK?T!O}AV`;f!w-b`KB$G&&eoLq`>0&)OgF4eVMC(aplc-+yw}d)Vy;x7qpw4c4LY+yMegkzT-Do|D zc#_);>P)(k-$0#7m+Q%dI@37d_uCBWO!Y?VNl<61m+Q%dI=ii)&ZJAfCDfU8xt;`d zrg4bYlc3I2FZ)|UovB{-H&AD)H|lSo&Qve^TSA?wUiuBx*=-*=-H-o%Lr}?W26ZOg z$Zw#|q)Wdg)S1SCegk!;dLzGqI#a#$TSA@P6heyiB&ajh8?7gq%07cSlWycUP-hwk z`YoZ(G!FC|s58|Y`3<*hs$Tl-{nXia?Dr|3hx5kYZ=THFUGLzQ&D+dq_T8h|+q&E@ z!7ZD&-Lu)-y7U{ZRWtAZgdj-)|sDZo3mCZC&~e z2#Iu~-)~?@ZZjAX=|=qx5Q%iz-y9<8jsqwX>2f{k6iHi`egj6LaftdGI1<&%{^lG> zyI%G;fF!Cn>Te)PR4@CRlO*kW+24SY+;&Gv+Pd@`SQ6<*>q)>Qw;3>rbR)mvmQCq$ zzr<;h_BgP=0Vh$tnt{jP>)=ULFa72`Nw;1ACDP@7i325VUG_H+B^rmQzX2&xz3gv} zl(g$*e*;r;+np(C>(Xz4N~9b8enV{0ZANU7bR)mvmQCsM_Zwo1nth%(wJFyM-*IqL zTUVEULu`@8A@UnpNaIVtC8Hw$jiej( zH{R4XBh~13B&kLk2l@@EM$(P^M!sYwUvflzNo82sypb&YYHODe<4bWJ9G{kSr$To>!fIwKb7ay?1DMf^f$#`aU7EV zRvA`aFZ~wrC6!_2y7XI;Y9#g&>q*64aU7EVR`(fsy;x5kNve_R#d>lfUvkt6@=?B| zZZz_G>9_auCHFw=|8^PIfBW*AuV20XLmRmiIOIRob(gJAwLZPtPxbnM_dx_fx<1v? z^{JMwO?6w>U#-&hsg|xSW!kzv)zbA>t3DNv#o@P8-PZM`jC6gfrE5!>wyytF*ImK> zYL%}2bZG1P)|hnt)hb>4sovJrY~MZd()CxXbZu*_t?RE=>H4cxy7p@A>S8Ney8ddF zu6_Dx>(X!7ik5EVH-vSoUi!_qqTBV-Z`g`fy^-H=Td3-#-+U{&T`&EHt!SYck>7Zj z@x)fNbR)mq4O`KwH}czTS{qc1wwxXvKThY>u{D!S)>C$h$ z72O^O`VCvrsyFi6m~ERkY(+~q>TlSJ);Q2_z7^da2W&-4m%rb9E4r<#+4gau-+U{& ztxLaQD_Y|l`3+mq8VC5TBG(`H1-7E4i{Eb*xgO}UzhNs{=xpRS9Ce&dY(+~qT2GGI zw&wvy9iaZ`BrpW7k<026|HfI{Dz~Bsu%l{ zi*H4@>xJJgY(?wnLb5-ptS3Ha^qX%*x9g?faMV%tMt;LlN1f!ydUEljj_rEsHym|T zy-9ylemce%M;)ab`EAVhecx18rF}|~u4drzeu1No8ejU&k2-e87e^hXi}mEewC! z`VB`NRd3`s9CcK^Tu=H@$8Nni>L^|M&5t^^b+MjQY$bf`M;+U`>~A>gsPT>Z8;&|^ z9N6FdsAIcc_BR}L)KRynzu~B(>ScfPqmJ!*={Fp8RK1bkaMW>xSK@i_qmJ!*={Fp8 zRK1bkaMV%t(rWI!c#*^P`S!UHT129W@Tg{-i>=@czY7N9jg>!%;_#1O4Vl z9oyqTzu~Cky!cVawl4b{jyg&=>TfvesN^Di@7B%F$$AGz9i>aZ`BBIAIM8o6>Zoyu z{Dz~Bs+WHAqmJEranw<|^qU`bZ0pi*9u6#iH)!-sdJ)7nO9_W?tn{XS5*#@2sCYHV#$+ZR=O!rm+{CC@ZH)ZzQ&%)c`7}I@(?sp_5 zR06;2`nH^O?Pp6{*OyVM*OyV!wQae!t}mmc>&vLy;TY4s?)TI2v)}%&u;2f~rsG4a z&$d(4TCp*+0%Xw_ar>co=hyceMY8zLw}NAlY|y^y{Oq0orWF{AWbJ2Sw_1F4SV6H! z*1kG4WeKsYfLJ6OEE4PRtPg^}+$0;cuR1&Hvi@$9ti9X1gW#_=O_{&iBx|p>uB^Y= zB{Jv-aE~rCYLr%j(Fi%fe;)RQ>pqP$yO__<1Gl0<2wYa@ zWxZOu%(0c8%j&qS%VLqJ&(z5vpqJ@@EuLG4R_?03U+nzfe|-7!^QTX~{O0xBryo9^ z%de}h{bRGv+xh08E(^6M@_yCz{DnXN*7eOn>H0G%U3(_my8ci~ z*I)h8wTH5;>+gQ)`ct`Wz8T-v^_RbN{jrp;J(g`x(Su`c9m5 z?e*W*)oj~yhRt~C+WWt)>&qznb?wFc1D#b&&8={MhuZ|l-;*o;@Xk>9WxuX^b> z-;8h9OTXc;r|OOThRt}@OTYPMe7j!y4Tn9q%{SxQy7U_kdrCL*+n8kH}cz< zZP)enmUJV(joEfx`ppk}cE=ZoJ+;|QzxiR$wl4jK!=4(4$Zt68se0)*KkV7Amwv-x zPt_aw4Tn8dFa73+J=^utZ#e9!*ICrxaM)9KMzO#7Vb6BG^c%i3souzMIP9r<={G;@ z*{+v!wO${yZSP+k_S|rVWqaP(-*DJdx>0|_Vb6`gDe@KkV7Am%rbT zJE&!q#8;RJ~kJ z`ZjsDUhI=gmwxko@_XI;jhjz?zC8WY%hzx9-SD5j{QR3QUI&{u>)0{1mo|3NHePl& zUWp$>JGK=kz&2iXr{6lsL%-q#m~^pe!OQNt^`gn}vOCqAJoLQmPWQy)q2K)k*!^UG zN3-Q+chW_Z+5H4qTNh1+m)&U`k|x8;?o=-x`rS`}b?e0mFzKSn?0y2Qt&1kZ%kDG| zNt5Aacd8dnX7>|d?RwE+{C&1de^czlqX&fTIjsO0A zf8%Y~(tYobsQYI7qn9tVJItxBtlY zlMnaW%A9arc(fu?-+jex>%yZqe8yG1=Fzq;Hac$jjw@aBXj>Nx!5cp0O4k;GZC!Zu zhA+9&HIFuRD|5o;4WDwQs~LEB-YRp#b>Y#9NDXx1(Hl|-RIhooJr3~bjcd?~NDb;m zPrTv6WqsdD{8pJ0KECvuf6r}?1N^3#3j3g|dK14@=EQxyim9M(;gd8a6OLP|UT<#QdSRRi$1U|i)Qr=vSJUR>K;x8EzQv91b?+zk9$EO&(@$T%o`avh zC+^Q2D-3(gc3o9||M)hSGA9m|jui%VlYN;J_h;(so4+1Zue~1H^`af?I$hRluZOlS z+Oe+FrLMgm+PZi>=sI2M+UudKOO9m+$D;AIcHGw0Y~Mfix=xq%`dej;_J`enj@foy zf2*ioYsc++@mATvu}Ih7D&2bVR?&637>9^sQ6@FVfqsiP7G+XH7aYr8G1l*vCGGL0 z-@vg*H}V_q&(v3R`YqyElu6BTpx+{nMVZvp^`EF3hsbXTE!Q~EZxP3$OlsCkzeOC2 zGO4NSTS6L#$ZzCWc5p2FE#g>C94giL(r*#RqD*Rx12`7d8}&DGEV@n?@12NaQ6@F( zrQafsTl#&be%5ijrtqz&)jsKE_EZn zkz?7xvFy5-C|OV9{!Gy7+Ijz!n$QaAD&ITl@~OWnwC(yy3ma{mXjRI z4vuBNd1!fe-G|U}(S7{=7I7>mIhGw~r&Vv{H*zexPM6~w{eDAexyFHhi#Qf#QsaFF zjz!}T`HdXQ4vs~-k>7BDTH`>!MI6gXjz!n$a^51pA+%ie(r*#RqD*Se8~as zc5o~r8>0S3jz!n$VtgZxMVZtX2XHK^H}V@f7G0;ydZYCuIhGw9i|UR1hS2g&*Xgp} z$Zun|ZJmnyGgWWY-^OgaF8$_5KD+$_q2(F}_^o2BAK!mKXt{LZw~Db2bh)0y=Ry%b zk>7CaQ%#jt514J&OYb9KR`n*{KM^piZ%XjKvQCnB;FxV62l@?PJjZA^zDeT(yGQ8>515U(57lH3;dy7rvk>wf>7>!kJf&-pK(eLTkD{~yo!-;aoz{_FaK`S$eZr>Xsl7ZT=6 zBt_!*5@}nU?$Vp3(GhEHe%BEdiQ~I}lC@t)U0E~^-Y_FsYaCr!^bG~}*!okl);GGc zXdAp=MzYp6nzFcFMq}$;L$cO2y0ZE^pE5U-WUXm*WzjQuxr}73XLM!JGI+O)WUXa% zWi`(}2>wfC!__ifS-4DrJ$S$h{`wXL>&p7?5G6#>Wqz!nD@&K*UKtHS;xZg6P_=ZK zA1dfpOPBFX0dAFP%Hl|Ys-?^PNI_Rte`gOEe)4N<6PMu^zpC|>nPd}}jd}KJePJfq z#AW!suWIQs|GnQGTe=MQ$!xe!=1$gEk^iQMsGsTx#PcVmUu^Aey4KOl`|(<^iKzfa z`zT(>+6RANN*DjK1)G@C9sihb-ydyVyg(LgVoKNAbXym1kOiBV(zQ28TNjOb!6v43 ztx>mi@eWzAi78#{)J@$TH!rRW&OAuhT6J3&Z;|ElUM*dFi?nsotQVYlkgmN(+PZj; zEI9KZU3-tTb-EO1$ll0rICraheSIw5$Zun|tzImUr5pJT=Wf>(D`e>={jE+} zd%eCymTu%X+`OoI={G-j+w~h4$txDgsyFf*K8&ee`ps9#?Rx1qER$7lB)`>~H>ItXnTWj7gV%^ABTfUHT0-FKQejzv1RZ)yw|oAI94C zvcKVwoI>8C{)R(xs+aw(K50Dq`)$V|xpl=MIn^8a4L2`Jm+MK~yf|j@!@py71`0mL zAvx6>^*7wSsCwDoaPwlbUL2B>F8$_*nqq=<|L^u3azv zhC_0yH}V?}$*ErY%@4_S>%}2C>C$h0NUp6*zu}Oa#v$?>4#}xp`ppl?wd=)x$%?RN z)f=rRaY#<}ay{vXq$Q( z*B%G1Cviwl^+xMS9FkML^qYr0ck9I=Iq7me>4)Unx?E4TftCr+V4nJnXq$ zFZ&w~$?3kFXg!HTa;lg8%@4`7>!sgtNKW-ee#0R-y(Zb;{E%F`UiLQ}l2g4=f5Ra; z)yw|ohvd5T;*gwl={FC1ZtJqY;gFohA?j~9B&T}W-#qNOT`&6^4#}zBsK4Qmoa$wN z^Fwm&dfDG_NKO}2Mf)W-r+Op5;gFo_rQiIJ zT(@2vl9Mj|=7;3ky7U_k$!Q!Szu}Oa>ZRZOkX*Z7`VEKVRBz-r9FkML^qU`&Yu8J^ zA?#V0TI4qZ&HC<$-&p{f$7-UnuR)+$-&d#`ttW9vPRn(!Cjm5f>*acqKr`+{?9Lm3 zX6-j{9HQ?5I3%ZW;Cd23b8{SUNKU%+8-V7nF8xNJ8TTT#$Cv9#@+G(!v8_wLkuSl` zh;3c2C&`!KYQ(m#-mbQPM!p1hBer!lzpe|v;c~>bF8xNn1h*qLb$LDFx{@!!^@wd< z_BZk+xF4~t%inM0OK?GATbF(#UxFJF+q(1{`4SPA0e8ha5;br5{f0Xd+x5b4yd-fj zmr=d&n<94oy?#Y}$uVf6d%r1Sm%7P%@*rQLh+XO?`y~hY5=HD%H|cK&`4UC!Qa4#o z9^^|Du}j_2(H{NobdWDm#4dG{_2famL=n5tjrfv-e2F4NwL=n5xjr>NwM7OX}H}V@XY~40R-NDx$-pFs{OBD1^-Q@S%LB3=oUvfo!$uVdm z>zm|Du81!=$d_#7ORk77Imnl6w}$d_#7ORk77IS|6Edg-@_ zFFDAU==KFXzY$+@kT2QDms}BFa*!|4X)V?p`Hg&u&Zkf}>Tl#rbdrR+@9l4XwB&F1 zYJ7hX-{)bhzCOIqwjta}2YxXR-yg((`Sr7pbyYm}t(xPDaHs!_gZO9r_>|)NecM5+ z5nq<+ZaZI=wfH5#0uCD&ho-=IoNjLGEP6<&Lep86#`<}D=cKPEkzxmhC zU;gbV=6w6{ub)57+i#ygZMWaH-zq{Nee`se06!v?fqP#~Z83bf87+idCPFUCjEr=B z^i;2p-l`0{NY~$1()G8MbnR``9tVG0N!Q<2f@$n+)z-yVj z<&EajwYODU*WXss^|zID?QPZ8^|zID{cR;(dt0@2{cR;(e_Kh{-d0^*LN2_~T)L6p zkOZxIeRUw+$Zv#Pc%!*=BflXDTJ_Rz4!N|)mwqGUvN`0^)}`MFx$s8w;p)bFl90

r7{Kv7W@Q z-*&z98-D$&-e^6EU%#ps>q-3jZPv?QztY9;H~ji->-w)>>B4XL_1o6v?>9m&`1RY? zrQZm-RIJ9s?=xj&@HwO39CB&bOTQ6v**!$1tqZ@+3{lw~a%t>i@h)C$h6Ty(W?q)WdMa?#bokuLp4$VFERC%S}O zW>i@ho;Ui9Au76BII5R^V~C2b7LIi3H-@O}9-`762ZpH33{lb5!b!cjXvt`?4T={NEvx>`8WrQaB$qN{}?UHXlDiLMrobm=$pC40n|tPD|^ z$(QJA;iO*jB{M@*bhU7#OTUpX(bd9{F8#(36C$iHOZJE_QAP&VedJ37uSfOL zZ{$mKwQ!_MzmYH5Jw&D3j~SvelP}TL!co2S8~GAlEgb2xzmYG|)xwD``I4C-D!YfM zbjO!`$xOavkN6U0WZ?NFU!tppqj8|$$d~A9;YgQ$BVV$6h)R2W={NEvx>`7@mwqE( zqN{}?UG_KfC40n|DBA|l1NoBOLsZ)1OTUpX+5J|?t}gkKnIS5B#FyyoKgWT;-y*(b zC0{a=FWDo$WaVL$nS99}@g>U0;5guWcg1QvzR$%=dS>z^ho7!!KM(X9`H~~zOIGqF zGx?IkPgk_-rQgVx91&llj10^h`I3s&czE8FkwIPXC5NA`XpVz2GN=o`9e%o^t;_yK zzNBI`f^lGfBVSUn8i6kT#t@Z?)d+Oi-^iC#tVW;sxmmCpavW?mHdg-@_FWJUyn=bj1BjQUoUedFWFF7KxM2n%)j`z_*2Hs+Ts)zjCXy?OcXPt$*0 ze=y&k{`_?NNaxbpaal^@^me02Yk&N;PE*5w_p@^RCjMXwjAVWHLbCq!OIGXa$7Q|Q zNY)>I$!dB1xU8@3BdpP{KRLsTDlAy^7`eLxD27@s+KPE^Pb&m=`w7` zt6Giz;|~~JhTV9{CN4vwxjv54Wq#PRI|y_c_Tp7-;xcT-t6I9u^UUw6z3;F;dHSc% zUw!rb>7&~+=_z=+4qb@;Lv_l2TfOm$yAyP#9Ay8(-tMO^$nbVOZoITzVCh=BZtH3+ z?pG%#=uGKazi#XLt3>spVb2Mjsd4a*J#M_@I9SJS*Xu76>7r%N37x5Wy=O}oZxi8I z_qK1>>#q~hk7(L+LT9R8f1gMfU3*UGOzC>tmM&f>b3$iI*WW18Mc!sg7XG+)lcUzZ!1Dz>dTPC-4={L}s(oOo?L^|_C`j>PQzfGhw zb>pQ!zrwMC_wR)4Yu!|e{AY>*5A~y@zi`smQTvDM zYAH0d`k?x*zzTtAY)IhqxpdLc>Vs;a>jsl98d`l&4RqaL(nUk752}A(_kN;&^zv_a zko;!<@Bh6$4>}cw#wQNL3?r`IjM$q8>0+U&l|FUNh;3agG&g=`zx*?MTNg$YhrxQy zh;3aMapPz9%RjTXb`T6qn zqZePleERh_pMU=H|9SeqmiEK0H;PY&_Rp~DXJ*tW>BBFbm3s&?_YjyF)z$UM(8e5I zlFW?i>iT3z*C#_C^#_m!InO zm!EWf)!)^n-?%7YW>i;~e&eEqnNeL``i+YcW=3^&={GJ)m>Jd7#bQHW1bnffd5iou zX4{@$EHZRX&vC;Jfm_F&!Z(#bm<4eC`u_1UN@*9{w)l0wmVxv6{^cxl% zs@H#IcgKN#!(v0aL+RaFnXWGVhRi7GY6b#b`VCB(()!Zf$3AdL+N3^f$3Ad_|eVGsBXRV8#1F*Z{#;HeX5s!1Jl>67fhdYxt;{m*VW~E z5}8pN2fgtgpEodls+au@OkcNN_BUik33iM68<;-T%l-zYuUjws8<;-T8}+v_+x9*~ zW|VYCg%A5}%(m;&Z(#bm<3PV5GfMSFenV!I?un+~!1Oii#hql*rQg8xb#>`CWJYNm zBER8IGSy4Jf$8hkOTQsAN)Tw|w=vuPoY8M!`nvVfZ(#aVZ{#;*M(N&g?w5e+>()!Z zAu~$#M(asX391*H%FK*v)(a{@y7U{Ugsv{vlcW-u8P(OL-$*4eGpehrzq99;R01=j zy1MimsRU+5b#>`CQVGnA>gv*Oq!O4J)zxKxBbC6+sID&kMk;}sQC(g3H&O}AjB4tF zN)Vhwzky2V>e6qd5_V7tU0wQ(R01=jy1M#1^BbuIW=3^&={Hgd%#7;l(r=^^m>Jd8 zrQb*;Ff*#FOTUpyU}jWTmwqFaz|5$wF8xL-ftgV~U1mlJqJiI-8P(OL-$*4eGpegg zzmZB{W>i;Ke`kI}W|R)oXa*kseX-$AvH>aCM?f8>N!F9wU{JhXtS6Zn)g1@;jhRuZ zH(5_^gF(5kmzh!09Th(M`%QQpb@BU+nNi(wfZv!IrFu03kJrmXDa?$Lu4W+6h2NMN zC0)%xpbNh-GfKLefj}32V`h|eBflXtN>CO3Ry@(e&lxhKq)Wf~$&}{z0A@xFND1!; zWJWcgUt~s&V@uSH{D#aZ>C$h0IHf%f^czp7Ff*z-4r8|My~E=v%#7;l(r-MU!px|y zF8#&>D$I=P>gw-&9I#))%&4v|){_hQ5@tqqbguw;kuPCpR9Bb%jeH3+ zqq@56Z{$mu8P(OL-^iCRGpeaezJ!@kI*c3jH}WM5`4VPEb?c?y$d@oPs;jHNGry59 zIU>Gj~4={NEvI@y%0OGZMN%^Ud=W=3`E zrQgVxFf*#DOTL7eQ97g^`Hg%DGoz#%ttZKsFf&TJ(Rz}62{WUl8?7gi8Ktv^^jpN2 zFf&TJ^jpN2Ff&T;3$7<4zJ!@k(&c(G;!BtrC0(v3Bff;0QPRct0A@xt{YJionNbRF zi2R1kDAkMaZ_JG9*314zzJ!@kU0wa1y(h_+91&l_%qWcm{TA^h%#4yQ{TA^h%#2bW zrQagHgqcy&rQagHgqcy&rQeVl)qNh=-^iC75nsa0DAmjT$%rpuW|Va4w}>xcW|VZn za~%<1A{-fhBVWSIsOG#OGfMT+ZxLT2yo~kIZxLT2JO{euOPCqe9S5!_$(I}vU&72N zt%vEih%aGglyuqOBEE!~QPQQ~BECf1d7L-;E#ga<8KrvZw}>xcW|VZfUlQ>pT845Q z=(mV3VP=%-rQagHgqcw~BgXy~@g>ZRk}msO#FuPiwryQPzT}Abl8t=HLcZic>P7Rt zL%w7oUvflz$%Z@0G`{p3QZKsoay?1D9>e4*^qi6UG_JmUUbJne`kIpUvePzqN_{4kuN!sdePOT-^iDoNWJLl(r@HT zPNZIRb?G z?j)10W+2do-&Wj7CfzYpkAC;x$(O9SlT5mL;|03#+lo8Mq#OB-e96kt(=*~rcBY=L zOg%j#zGTOpWXfJZe>)?-WFNEb&l%Q}XT+E6NYC#sT{!r>CDbxs{!K$x6QD^!U@ZF7``S z@+GI|pSE?;-&XP^rw5?6b?G-Ipq`$9+SbK-awT7KdIV})7wgHDe97qQoKb$s&KT5{e97rCsO@^$-^iDoo`c%eC10X|8|T{2h%c$M8tWJ2OU@|2 zq|$0!m;DWQl8sf$hjV8tt;TiP-y*)G(rR26`;%wHmsDDf>tcWMjQEmDt1(^jB`5AA z>y9t|M!w{X_>xMi@p|z+;KZF|-FoRa@+BwkBx~xDFIkyiaz=bfrPcU2@b_E9msDDf z>(Xx#Us7o`u1mi~d`YF%xGwz`@gpvIU~NL(rR26-viEwFWJXz zyDt3}@g+O%BvTY3*OO6xNu||zz3guhU$T=gS;?22QGQ9K)p))1Ta;f?X*I4(zeRjW zrPa7D{TA^hl~&`r^jpN2?94A&$(NiFUs7o`RxkOIGvZ5j=9jGGOU{Tdsk9oemwt=* zlAZY_N`J(9GU7`rt;XwRe~b8%9e0w6Bc$IVzNFG>yk7b($}g$38rP-YBEF>3YFw9o zi};eAe920_2kk>e2K16h;+GMLcT=T zC`7va{YJh-*C<4~Tu+iOIU~MgCttFXFVQs$NxkGt6jP1<7V#xJ`I41ZRYv zmz)t_vg1}2@$Bqx5nobiHRfaTC1=E!R9cPevcE-q$v$S=bjg>T5nobiHLlCwZxLTo zX*I6P-)|9LQfW1=%k^Z$msDDf>(Xx#Us7o`uFLgg#FtcBjq7qf8Sy2RR^z(#Tf~=C zT8-;sJ$XfZNu|}eF8p>ye94YmRdg-|-`}o?FR8Q|tCxJq74apNR^z(x+ZFL8l~&`r z@Y@yfC6!j=y71c-@g(Xx#Us7o`_qqzW@%7FX@g5?zGBEF>3 zYFw9ot1rfn@+Fm4yPv>Ml? z-y*)G(rR3nev9~$N~>{Q_P2;Hsk9o`Wq*tKl1i&_UHUEJODe6#b?LW=FR8Q|*QMVg zzNFG>T$g@}_>xMiF5?zO zWqeI;u+nN=mwt=*l1i&_UHUEJODe6#b?LW=FFBZBB5(!1i1?C&e2G3xQ#bh@aPWQ{ z1>8_K`Tll{+4k|J-y*)`;QcrXxIw)UUs7o`UN8L?@gMl?-y*)G z(rR3nev9~$N~>{Q`Yqy14)P@mxZ(4VeD6MZKaK)!s2ll>e2D^Xs2ll>`6UXtp>FcM z`(S>F0&bui@g9>e4Imnmj9z>2q3VQ!Xl7si- zDBy;=314yyn#jh1e90B@B?s@vQNRuBjr_*^5(V5)H{rPs@+Atmp>D#L9OO$Ba6{e5 zZ{$l9a6{e5Z)3Lod7$4SzT_ZZqJSIL8}+wA6M4P#Tf~=CT8-<{ZxLToX*H%xzT}Gd zl4HKgiCmX{i};dCt8rcWE#gZmt;Tifw}>yPv>Ml?-y*)G z(rR3nev9~$N~>{Q_nQJO5`MDMYFyX-Cf%sNkuTZ6mq<5SPmbBPdcl`SH|lR=wq4i# zCf%sNjoEfx_nUN+{#I!t;TiTZ_-WrTcy>wuKP{8$?vyHt8rcTn{<=@ zR%tb^OTR^YNu|}eF8vnqC6!ilud9Ez^?3!;Bz~*38rSvyCf&qul~&`r^jpN2R9cPe z(r*!8QfW1=OTR^YNu|}eF8vnqC6!j=y7XJbmsDDf>(Xx#Us7o`u1mi~d`YF%xGwz` z@g_;zOym|Hd56_=;KkoeO`LnOyy!ztR+gJbg^6O_G|MOp-y?Fcf&8vU? z=I!{ue|h%HU;XBjAO7Om#|k+IkG?MWy|5zhu)gAcFdsp>zJ8Ie&#!dtecIOb^^0_U zex+;cm$t62U!?2vD_vW^bajz;C|#dl>Dv0Gt?TElr0eff>Dv0Gt?R$frR(og>Dv0G zt*hC-d(Nfn?^Eg8`sH5t{yG2jvo|mQ{rS_UfBf>B&wu~&&GV;^l&t#nyQlf1?fKL8 zKc@W$dfz_@GTp8pDomsA1b#`>K~y|h7rrEp-yt7%0>30m7f;rOFNsZEd`Xlpo~#RB z61%#1viK!&y>L>!tBWU#UlOHjPgeE8#`xk(qQ(JF)`c&L-FkiJN4nmr*9%_~ySjRh z+&e)>5^M!4UH>K8)%Bg$b;FlL>H5mJtBW`JhLh^jwKsWt-tZ>ha8g~m_9k!Z;!Q5} zgyU;(@~$qvBx-!=H=I;&jxW9>N*8bP3n$gPy7U{qBx-ykzu`-w>ZRXsQoUO*{e~}z z>xD0gU0wQZqu=l)v8zkJ;Y*_Gjr@i$i3%9N%IU&M^=`fN8@?o}-pFrbw(Wg}lj_oq z{Dv=y8VC9fC)JzdfG>&CrQdK;y{k*V;iS68A@bXpZ69Cy4PO$w_0n(nlDJ;@lGxRy z-|!_-x>0|_m&8?9W#GMzFNxiH+28ObQT0as4PO#fFV~Yesot%Ze#4hU)f@Q@UlLU> z{f3k3&3f@AQM&XSPO5ix={KBI*EmFe!;PRb;wl4j~n-KUVvHARt+4kqm*ONN&8u<-h z5?6jnly0=1#Fs?r`g&5jQGdgiMCp2elWw%0#Fs?r`tLXCCjE_H5~b_?O}e%d*L=?S zB~iNG-=u3hacy1tjW;3iOJeW&<(EX&>-|mj>Wz1osNdD4-*^+k4PO$wy7U`wLb%~e zVpkWx-}ohQ^c%h;cI!od+j$eh4PO$Qy0{5J_0n(n zlGxQnf74YN9N)-qxCue^`p&oJEm=?UOQLk?H+)I#jsyIrt1>VS^`?1uLc6OAzwNvU z;f61XU0wPOUlKQdN$l#2Lg!s31c2H+)HK);nhVeqExg zGFWfa-*8f0_0n%Rsot#@{Y_V8u-?dTIH|6B={KBI@77Dd@ud0;wA(If6{L_sovFP zf8$LEH=I=O>e6pB{f3k3U0wWs+h_U>C)K;U^xMq-hLh@DUHWb2@3;E){BYkKvu*ER zo>af#q~A=!-qoewcoV`6C)Jy}xCvp^*M0O0oK)}X(r-Me ze#1%it}gwy&~G@Y-qoew7Wxe*)w{a%+d{wLqfQ_2rQagHfQ?w}$(QJ=4A!d|c>MV#U!tors2ll>e2K2gpl;+hoK)BN(r*!8Qukii^UIqMZV_Kn z_g=Uz{TA^hb?=4i(r*!8Qukh%F8Gq|7V#x@?}h8qZxLTo_g=Uz{TA^hb?=4i(r*!8 zQukiCF8vnqC3WwG>(Xx#UsCs8xGwz`@g;Tdh3m4vMSMx!d*QnDTf~>ty%(-azeRk> zNxnn}SMZ+1N%iJBiYHHWRR(pV{zkrJ2Vb(?BEICrN%d7%Ww73;zmYG|RT9>e4IR{PTy7XJbmz-m^T^D|va8kYb{E{!xRT(~SQ^c2?PCJeU!torsH+(W>gDe@@+DKmm(;x%_B@a;nIgWV?!9nb^tUPE zOX}VW*M;9EoK){Uzjg10>%wnS#Fx~)7p_acMSMx!d*QnDTf~>ty%+box+(+DFHWj= z#~1sPx+;UZiQnqp3$K@ci};ed_ri72-=>H!xyYC3stk@p(%-Hz+g>mIhLh^ec_Uw< zt1?(`^1Zw6z3_VJw}>yf#%#MT{TA^h*O+bBrQagH5?y*a8kWHZ}c1ak}2X# zu0a!dz4RMSs(0%}f74YNc+Mie5?y*BEF>Vy>MOjw}>yf#%#MT z{TA^h*Pw}9mwt=*l8bzauFBx^5czG)w%1F)MSMx!d*QnDTf~?AzwEtVk0r-_ZTVFS z#MrWR#k(se_$8nx*=Q3}RUvivh+qukJ*1T7WpLy{Ss}Jf!{;qmmKHW zw(-(0nIgaBIM23onYYL8W<@^@;CC7QToy)vM ze#t?M}EmczeHPQ zkejRrR9lT52l^#b)L&9=9P~@HRR)iPo}jP4uG25s=$A}Ue@V5~_;Fy~BEO{CYMjfwMSe-O)i{@V zi~N#mt8p&!)*`>8+G?DOytT+LskR#9(l2RIe@V5~I2X@vE$T0+wi@T+ezHaVCDm5r zT;#1Keu-K+v_9or+)uW|FAQ1=D!3sxxStdk?L{Ut5&OT=Z~*k95TzhtSl8vFgyFKJ1CiMY%g`%7Bl zmx#;xjr}Dp@k_+z{Ko#0miQ&&a(-ifNlW|^ahW&vm$bw$5tn(RU(yo4L|o>Leo0IG z5^@R7F zUm`B^#{QC)_$A^pZ|pB=iC-cv^G3gj?>^p}XsywNXdNq>pB%p3iZmiQ&&GH>)tv{h2_JVd`_r(e<%zeM9@-mpK; z(h|Q!T;`2_NlW|^ahW&vm$bw$5tn&me@RRH5^iJX^CI*zOBaYtFb?hj&GE=^K3hp&u@ueqVY0s^h;Xe zmx#-}(JyI9e~Gxv8~u`&_$A^pZ|pB=iC-cv^G3gUm`B^M!%#b z`{RhqywNXdNq>pBoZsk|w4}d8T;`2_NlW|^ahW&lkF&JIFAvYc?U>gac1>#?{D z>N{~_?Y3iZv|OdpXX3=_=wCfrF4E{Labk7!ugBsVsE@>n)zQBmi%a0aC7SM^0FNG9 zTmkioI7aI$G^1Et0QH49u_x)L0^U(9Q^xg~?&~w7Sf-52Gu@YGMzKs8S7*Af&WvK2 zGA_<^Uz{1la&1N*hx3#rDdWYbSbp@_GG$zs z>Ao&Aie<{UEYp2i<^p>;yZ*GV_!s*h{xCe1YST3QzB^|3S-RL|$j6@A#KjN1!yXma zrjb!DcfaefN5!>Y_%K(;_42o<-Ky=kD6aj)hq?HTci5xi+HZWAi>ah@_q)yQ(P1ur zL?| zPkx!WV5!CgJJm~%7Az+&SRP!k?9qbd#05(=CUCqK(VFak`Nhh_1=Oy@ZN>pP4xl!J@V5!Cga-+O)!BUM0O9xCoWj3F@fADZ(Oic zV*T(DGQ0=d!r#sy0?CXgHDjSH4)OdvPP8y76qm_Tkczj47*jS1jJ3zk)XVAlsO zSoUbaa^ixe8WT9)C~sV_RAU0UQQr7U^S~?3rTZ(*(dR6_(me1=Q`{(Te5HBdm8Q5+ z-uOYh8WVVYqrCBhcr_-F8|Cd>p0?jFUTNw$M0w)}@dsXMF5O>gj{Y9bv+d*M{N}GT zhq*f2#^nd`J^3JBwF)}h&Sl<`58}nu*>*1Hx8#F(adozx%lYlB;J!39@ehU0#6 zcFk&->v!858}mT-imbXI$6U9@!~RX$%YF$ zzCOR{%W&q+g{$G?z`W78n%%e>=KB1m@iK3&Tn%%5eiN5@bLVQ5d;XpMekone(FgGj z)|JM~yhR_xSN(yHmw8JzTv)39z`4wudsoB9*Vnss9GEv3uZFpPKPfKr=H}HfmwBUK zGDm(%)gRdLrC%~feo2F0qA%H*x9EfT2ERmH<}LC|8vGJ*Ilo08#8>@+A7ADz`XIjQ z51h-qMIXdh{eg3tx9EfTsy}cp^A`CfRe#`I=B=c!tLII85U(%8Ilo1IN!1_NcpA2^qJi#~|2`UB@OZ!dokf2rVp`SB0A9zI#yGOpuxd>N$Au<*}a{BiYMGyY|} zwY~tm{MYKEF@FoW_|xhr77wfXXpC5USRKXUSyg+55^L{bN3pnd)>fgw)=lkCQ|>4h zch1@=l-QGWH5NC{6CYIdjFDjRoI3G2b@Aua(Sv};)QOL&i$A80V)2wZ@hNrjr_@30 zd7do}d`Q*j?!mF;GphCoei@{XZxbw2#xH{we?lESwoDlxP#1qd z9mO(bd_G2uaf z0d(t0V~w~TCvkn!64xfJu@@-fdY;7fS!?Tw04lBrN?f0|#63^QPt(@$cs)@o1yFHq z-Wuk5q{Q_bVsR}}!(7jlxPC({uFgPk96VIw`VFzTIs?~pA%KeOcZlNJ+%*!)B7lm^`3(Z7xY7Iu0d%DRDsGfF2%zF}eoGo_bR0Op zK>*cwqr5=?)p(h=L;%(P;mjKZP>na5-ync$yv&<_(|$P*UEYrV%ab~LbPM{;_m6j< zzkPms`_1Fs{PvyhOs7wlx9^7UL>E=m*cD(=r0j8V)eDO2uiWDL%qXrWRoq}^6xWj~ zuFs6CUQtBj^`wgHGo!dcQZ-(m8J7)ejkrNl#r2s{Tu-XF!OSSGCska(6BRc|s@^`S^XBg?FK2{T zKit20*2Vvi-##b=-X?*6r&^0C*1xXhcsv>fH0e|K@mD6Zd$>NrGs z<7-R38^AmisWocm;CMN|`FqRZ5`7Kgw)XYIH z=eJ0$Q8Nd*%v+?^sF{OY<}Ffdv@ioM)S9){a;|-YzGz{FT;?rOYqT&!F7p zjhFLVvT~>Ka(=_goyHsG4b?5nhLt;UqvtoQ+=^INiVr}1)r!^+({ zB`bI0GHM!D|g~XdBe(`xXfF!a;M|KykX@|c}rIAmIEty z;&Og_dFAe7_mik@5tn)MHtNy$a;R<*m-Aax-J)g=Tz632vQANTi<&ve<@^>^x2Tx| zTvWGcyiwjz-J;fZ-cLr=Eo$cAc$v4Ty5&H1i^j|Q$*8*JKy{0_%v)65a-h0JT;}a8 z^SJe_#*GH+*@N5JL$hUymm&Z7AZ)h!w?=C>;I2*%62p}J+QGLL}EyrH^9+$e9T zZqaTA$Xk_p1mk7iP~D>OM$d1kZqay=w<`0vcD$>aIdFYIb&JNUGZ1ijKY1W;EvatN zcy+ezy*>SsD)R`&%e>JqsWOj%%lVCdNtJm7T;`2_NlW|^9be>ar(aTK9>I9=esZT@ z(h|Q!<3-+f`Xw##OT@+f+=4)jZQ`XyE75pa>WoqkD6{E}789GUm`B^M!%%WJgz^!^hSd81!aWgY>Sd81!aWgY>Sd81!aWgY>Sd81!aWgY>Sd81!aWggda z>6h&EOIqTWtPk`{cKRh%<`ImS^Bet=D)R`q%p3iZD)R`q%p3iZD)R`q%p0}_TC2<> z;4*LYORCHx;4*KhZqayk1_CbghOL3b)fou5%p0}_5?5#7dM^Ev9a{s5t1}RAIlp0R zAaQjD0xt80t%1bV83?${8@2`#S7#vLGH=)#NKF{J!w9&{8@2`#S7#vLGH>)tT2kGz zKF}}Ou{Ds!8|96D$&Rgo#EtSszhuYOK;lMuqhGRPYanr>ywNY&u{DsmQQqj6?DR`o z;+L!s^hzeHT-jebc>z6=+ad81#_62C-T&TsTfTH=?8%lVCd zNlW|^aXG)yFKLNivOdr++3ArH^h;Xemx#-}(JyILeo0IG5^{1S1QH~J+l@k_*I-sqRK#4lMN=$GvDOIqTWh|9duFKLNiA};erzoaF8 ziMY%g{gRgWCE_w~^h;Xemx#-}VYl)tTH=?8%e?LIOIqTW zh|9duFKLNivOdr++3A5*SD(J$HQm-M8+M8|=7qhHdK{t|JSH~J;jzI*k1M0M%%_`;v8`rUww zydCsQdeUE_;4%lVCdNl*Gq#O3@( zzoaMqCF0_KQUy0W4mtzZ&ll`3Ip~-4q`yS19Gu_im-NUlskR#X{n9V#Nq>pPi|4n4 zeo0UIOT@+f)tdeUDaF7rmeq$m9);xcdaOM22@A};erzobWgNwwA3 z?~Hy)kNlEqt8p&xCnLXPqF-{*FX@qAGO@oz1vj|vM1D!N)%bDX{1*8o6Z=b4aKrKH z3Hti$B>PKLa071SmrU$0QNazldV&td%e>Jq>5*SD(JxWK4aci1UNBzHZ}dxgf@#>0q{dnn@sNja&==qI)i3)DW)fF!oFXuPJqiFO_k7w;#z^S~PIJfOA@-cQmm ziFO_k7w;#z^MJ-1<&A#HLBAy0c|hZ3-sqP^I}eD37TjPSiu@ApJRmOTx5zKy z&I97|elqe)s;$QEQ|XuV$S>i}0~#;yCnLXvI}eD5*T;od;Ar!uKVSUs7!~K3?8WMt%u*9?*E1x5zK4wi+KV^A`Cf)mGzN<}LC|s;$Pk ze141kl8JuFLBFI&eo3{}_;{JO$S;}bmmKsHsNjZNJwXS@m-mzOOXkQgndp}s^h@T*FR8W~%LV@=L0%#<`f^=EyIpwi@R$Z^`~RYL(&p684wO zQGZFb)m)5MMIOvsVHZ8grt{p1|^CDm5rT-;C2kzZ16HO^(;lKpYk zYO8TB^A`Cf)mGzN<}LC|s;$Pk%v<6Pz~ z@=L0%#<=uL=EyIpwi@R$Z;@Y8Z8gqi-Xg!G+G?E3yhVOVwbeM6d5ip#YO8TB^A`Cf z)mGzN<}LC|s;$Pk%v;o7Qf)QPW!@scq}pnn%e+PXCDm4AT>2$*x2V6Q+G?E3yhZ&b)mGzN z<}KMyCb8s{=^kzZ16HO^(;BEO{C zYMjfwMSe-O)i{@Vi~N#mt8pWpOBR^wdeE%HmMt;V^`TjZBiTa9y>x5zK4wi@R$ zZ;@Y8Z8gTFUouC2Nww8DmwAi)l4`4QF7p=oCDm5rT;?tEORBBLxy)PSmsDGgbD6iO zzogn~oXfmL{Uy~_<6Pz~@=L0%#<|Gb68R<7R^wdcZHf9zs;$Pj^h=hgzogn~oQu3I zkzZ16HO@uemdG!uwi@RmZ%gEtR9lU6k+&uCORBBLxyaiR`6bm><6PuziTsjkt8p&! zwnTnOwbeM6d5ip#YO8TB^A`Cf)mC%KRl$w>TubDaR9lU6nYYLx5zK4wi@R$Z;@Y8Z8gqi-Xg!GV}BeKyD)E& zUs7!~K3?W6@=L0%#<|Q}R9lUYmwAi)l4`3lF8z`v@=L0%#<`r|BEO{CYMjfwMSe-O z)i{^)TjZBiTa9y>x5zK4wi@R$Z;@Y8Z8gqi-Xg!G+G?E3yhVOVwbeM6d5ip#j{XuA z@-T0aUs7!~HeUKAOXQby^p~tExWRQN@=H4Q#}Su#i~N#~{t|JSx5zK)=r0kMd5ip# zj{XvHnYYL*WFAV_fx5zK4wi@ShevAB) zYO8TB^A`Cf)mGzN<}LC|I`+p=0SogM`6bm>W8$IHA$e#v~EZRav?kzX>?FHyk_jzi>^ z%-A1CzX#?m@=Ip=B`Ub#c$53d8T;d?AcT2~{F0e|i3)Bw-sFCAreC6h8*-!h4g2Hh zI52OKUoz7#QNazz8|4lA<7m9hTjZC_*dIq+<}LC|X8I*6xWRFV{E`{_<7m9hTjZC_ z*dJ$A!41b7 zreC6h8;&=5Uoz7#QNazl(fmfgLo2}E6?;xRB%IXG{4a=QNazlQQojW&Z>eN za-+Oqe;jd{x5zJJ zH~kV7+>jeRzhQqIjTd>_BEMwD{y5?yZ(HP-%-A1iRl$uPhb{6;=F=v!-x>XqE%Hld z?2n`IB5zydm&~V4x5zK4wi@R$Z;@Y8Z8eu%72F_ikzZ16HO|HSwnctPwbeM6d5ip#YO8TB z^A`Cf3;hxm-0=7&_mj(cwtc+JTjZBiTa9y>x5zJ9&a>@Y<}LC|mh)^omwAi)lI1+x z&Sl;rzht3bqJkUz9wNVFpjgP?QE;D-&tqgBEMvzU!sB=jyIa$=$EMA2HeOm zS?HIj;D+32exqNaf*W$9ywNXF!40`l-sqR8;D+2NZ}dx4a6@jCH~J+ixFI*n8~qX$ z+>jgPjedy=Zpe-1H~J+ixFI*n8~qX$+<+VTB@6u$72J>;<&A!c3U0`a@jgPjedy=Zpe-DM!!S_H{?e18~qX$+>jgPjedy=ZorNFl7)VW3U0`a@jgPjedy= zZpe-DM!!S_H{eEoNwwA3JWs!5i~36z`Xws3;drCG(JxWK4Y^U?=$EMAhTJG`^h;E5 zLvEBe`Xws3Avek!{Sp=2kQ?QVeu)Zh$c^$wzeEK$~*U1BU+atfE+G?DOyzP-+ zQf)QPMc($vFR8W~=OS-=`6bm><6Pz~ z@=L0%#<|Q}BbRxL`b*SHMlSOf^_QsEiCpF_ z>Mv105V@S+qW%)~X^_jjMf>BZH-KE`E%HnB-8H$)Thw2o?@P&L-Xgz5-_eoFyhZ&b z`pyen`Xzg`Kh8?OL?lLf@kV*0U!sB=a-+P_FPZ6=>`{NoO21^LU$RGj$x6RureCs0{Us~?5*6Iw z_(uIDEBz7`+>jg1Z}dx4a6@i1ztJyI!40`l-sqR8;D+32exqNaf*W$9ywNXF!40`l z-sqR8;D+32exqNaf*WunzhtFfqJkT8qvtpJB`UZfH@cssU!sB=a-+P_FPZ6=?9u)> zEBz7`+;F^6-sqR8;D+2NZ}dx4a6@jCH~J+ixFI*n8~qX$+>jgPjef~Yzhsa6l4`55 z=R*1=d*qj_^h;E5gX0kGkF(M*ndz78(f&9q{gRn}$sX;Gv(hh7!3~c?lsEb%D!3sx z${YO>72J>;<&A#HOuuB0_QzT2m(27__Go{cm43-gzvPJgl9hhROuyua`b(;<#&S%* zxbfe^5%rg>^h;*?B}dd>veGY^>6aW)e@V5~`0+*Fj>s>mwi@RmZ%5>p zR9lU6F~1#=Us7!~&c*z8M1D!N)i@XTlSky2R9lU6aX)!Peo3{}Tyj-#gIq*@Nww8D zmwAi)l4`4QE}q|x$SB`UZfH_99R5*6H# z8|96D$wI&6i2Ra`{Ur9)Gxh^Zfku_K)8`KYn-r`iJ|^fB(g2pZ@OtwLS`_U$W3I zIZops;OgpXd81!)oW{ZRT>2#o{gUG}4g#+3W_-NN+i4sGT;0t$mwAi!$JywYEc8o` z(>MsmtF!In<^5#jmu&P)7WySeB@6wMBkC{N=$9LGmn`&4j>s?B=$9lyu$BibKlqhF$e8~lEw{c$$> zB@6wMBibKlqhF$e8;&=c-{_Yt^h=Itf1Hhe$wI&6i1x?X=$9fue#t_=S>P zIM6Rq!42|u8V3QF_mlKXj%a_Jjef~OzvPJa$JywYEc8o`$S>KrKh8qGwmxWOBVViN3=gqwbj@>Pru|i zje}sk%p3iZBl1f&`Xvkfk|Xj4Du=zR(Ok_CQ=xJllst;Wt9`b)%3=C}Pk+s^g*P241J`+2sV z>+eg%P2NxL=h=3yuLp>myf4|$v+Z1eUm_7F$=iOOZRav?kzZ16HJ4l!+}M4I#+&4= z+G?EZ>)qled8@V>=lc4axJllst;V_j{3dRcH~J+ixZ&}Q@72J>;<&A!c3U0`a@72J>; z<&A!c3U0`a@@QKl4Y^U?*k7W88*-z((JxWK4Y^U?*k7`uzeFFvMDI)Jm#E+dcz68|96D$qK(j+$eAKOH^>f-$Rr)`Xws3 zAvek!{Sp=2kQ?QVeu)Zhz>WNpoqmZ5Zpe-1H~J+j{1Sc07Uhk8i3)Bw-Y9SEFInN2 zXuMJ0=$EYUOT>-xM!!S_H#`ne-sqR8;D+2NZ}dx4a6@jCH~J+ixFI*n8~u_Meu+Mq zjOI7`B`f?AaihG^FInN2h#TdNe#r{IMBFHE^h;LwCE`YTqhGSZFA+D&8~qX)*Z7@9 ze#uV1L6c8AUs7!~&c*x5De_CIt;V^S-=@efskR#DB5zaVmsDGgbCI_x@=L0%#<|Gb6!|69 zR^wdeE%HmMt;V^`TjZBiTg@d`UJY^_`6bm><6JzyO_5(xZ8grt`r8!wCDm5rT;?tE zORBBLxy)O%KTfsPIG1@ljf1Pb!GnH@-skZ5kj!rf{SrM7lbg(M)mG!jfq9Gkl4`4Q zF7p=ck8`lUL7G zIJkb^q+hbpFPTo`AmHliYV#2Nk}2{_4*De<{gNr_FFEL!Z1hW}sK4Z(U$W6JnWFxZ zgMP_IzhsL1l7oK9M!#f=`b(;<#(oddO~E$T0+wi@ShevAB)YO8TB=eMZ8eu)Zh$c^5Y&@WNJ4Y|?#68a@7xFI*XpQK;1 z(Jz@Izogn~?DtE*WQzQfYO8TB^A`Cf)mGzN<}KnT zzobQeNww8D7xP<-{E}*`aW3-KBEO{CYMhI_wZt!xJs^9}xyV~f{1S0>H{)F7ttEbm zxVoEhF7nnAzeHTVpFEJamiQ&&ay{T+-V(n=T&=eHabVsOzeHTE{#nYY9*5m!$S&Sl;bzeHR;Jvf(nOZ*bGo*-{3xZ&{)*5AZM-c)cyZt(mjF7l>= z8*+o^H*t|S72J>;Jim#Hys6*@+{7;t7kN{`4Y|Sdo4Cvy{gRgWCE_w~^h?@l99;W6 zFD~;&zoebULBM6+=$Ew9IJllmzhtLh(oW+b;4*LYOWJ811YG8gen~rxgMiDt(JyJI zaS(8sH~J+l@k`X&!@SWiX{T`zjF)+%U(!zFAmB1@^h;Xem*_Y!Z}dxA;+KfaywNXd ziC>~^206dcFKMT7aQ*S6U!sB=Tz^mFAmB1@^h;Xem*_Y!Z}dxA;+KfaywNXdiC-cv z^G3g)tTH=?8%e>JqX^CGVF7rmeq$Pfd+Ekb~`Xw##OT^{; z#{QC)_$A^pZ}dxA;+Kfays^KeC4Pyx%p3blTH=?8%e=9_q$PfdxXc^H#62C-T=8gR&E%8glW!~6d(h|Q!T;`4a zB`xtw#AV*tU(yo4L|o>L{Ut5&OT=Z~=$Ev_FA{1S1QH};pb z#4pj;EX*7Il9u=-;xcdSFKLNiA};gB{*spXCE_w~>@R7FUm`B^#{QC)_$A^pZ|pB= ziC-cv^G3giJX^CGVF7w9zl9u=-`pS!WV}D6Y{1S1QH};pb z#4iz-d81#_lKpYSW!~tQv}AuAahW&zB`xtw#AV*-m$an6L|o>Leo0IEOT=Z~=$Evl zzeHT-jebc>{1S1QH~J+l@k`Xo!Mw4*q$PfdxXc^-OIqTWh|9dOzoaF8iMY%g`%7Bl zmx#-}vA?7xeu=ou8~aOI;+KfaywNXdiC-cv^G3gL{Utr|OT=Z~xIa#h{E}*`v2}FrkJBT+WTIc9f*W5C z=#gJiZ8bh#tatawFR8W~=VHCPM}A4Q)i@XH-97S4s;$PkSnuwUUs7!~ms}Ox;JihC zNww8D7k){P{E}*`aW4Fl9{DBJR^wdwB|Y*>Ci*2RxZ&~D74PbGvWb3)3U0{N6))go zepA5>xw_&7T+DAOxFJ_pynu`OO$9gLMt;dezeEK$6fVBhTJG`>@QKl4Y^U?*k7W88*-z(vA;wG zH{?cnV}FSXZorNFl8Jta3U0`a^2YuW72J>;<&FI%D!3sx${YQXgMLYm{E~@&$w9xQ zM}EmfzvQ4_(j&iQqF%Z|pBo!40`l-sqR8;D+2NZ}dx4a071SmsDGg-S5yZ z>5*SD(JxWK4aXbhjef~NzobWgNwwA3aiCw)Bfq5DYMjgYE%HmMt;V^W-y*-H+G?E3 zyhVOVwbeM6d5ip#YO8TB^A`Cf)mGzN<}LC|s;$PkoZlk9q}pnXOTVN?e#u0?LCi*1@{gNK}B@_J;72NPRME8^QOH^<}?u+x=|NTE+{c!*8&7U9d zU*CWE)zjmDy}Fwoe%;&MzutYKb*H=EeEsM8Pqh$z|LXoPPjCPH_WA99 zK7M!q`oI5h|K|Dm>FpoCe?I^35BHz{{)^8({oVcRt~NS8|8YH`N9zd_*Aot|C-i7N zp}tPG-#^zAdbFNUUne`4d5zW+Cax#wgJzufXgy)#dV)S^CO5ht<$8iXXeKv${^NRr zK4>O4dj8{jf<9;_H_9v56ZAndxi98bX?-zoTu;yk&E!V+qg+qW2hHS0_oG}-&g#0ZB5!lFo={&WI~RGIqxFRPI@!6*TeO}~Une`4d3$+1 z;bZq7m$x6=w)Ri;{mvD)AJk*j&*wkW9_g_Y^;q@uksDnOsmC7FV|%2>R@t7N9_q0@ z(qkv;vFhi;aftNTiF&O1`N)kfhty-$&qr=_Iiwz|em-)O%i%;lR{ebBMzaptQ12@uRC+e~4=OZ_|{h%JJem-)e+Yjoo>gOXj z${Y1q_4AP%<&Ao*`uWI>@gOXj${Y1q_4AP%<&ApmK|QuddhA3!_MjfyBRzJa9(z!a z?U5ckQIAzWACK>gdAqzF{mtWlK7MoekB@JjUfs>hw2a?+RF4c2n!ZesL8ZR!@bF!0Ph|9c1O)CvM`H0KBMNKOWCXBeuThz4DV8V#YyhTkb)vM#b z2j(qmTB%+g=Q3|m(@OQ~IG1^gOqlA`aW3-~HLX;yj&W(i%u&-y_3Aj6d5fA>s#nLk z%v)r_RIiS6nYYM!n{Q$O!eycc$v4zgsEN~=Q3}R2~)i~&Sl;r z6Q+7~oXfmLCQS9}IG1^gOqlA`aW3-~nK0F><6Pz~GGVG$$GOZ~WWrRhj&W(i%#jIG zy*kci-XasGdUc%3yhSEV_3Aj6d5cV#>eX>B^AeX>B^Ax2S2QdUc%3yhTe%)vM!N<}GSksa_r9aw%z!npUb;$GOZ~ z)U;B)I?iR@qNSwj)p0KK7A+-Jua0w>w`eJ;dUc%3yhTkb)vM!N<}EU#t5?Ul%v)qe zSFet9nYYM{u3jDIGH;O?UA;QSr5Qa(W_0!HIG1^gnpUb;$GOZ~)U;B)I?iR@qNbJV z)p0KK7B#I@ua0w>x2S2QdUc%3yhTkb)vM!N<}GSksa_rDB5zA%Mpv(nbCI_tYFepY z9ploBUZSRz>eX>B^0q`xE7hyxT;y$unpUb;$GOPc5;d(NuBqi_GZi)p0KK_OcoMkuN=}SLc$eDjru{mdG!u zULEH$Z;@Y8y*kci-Xg!GdUc%3yhVOV_3Aj6d5ip#>eX>B^A`Cfoqma`c=&rr{F3U` z@$oWmkzZ21I?iR@BEO`1b)3t*MSe-AU!p1=9N)+<>GVrf#Y1kQ0(SZ(6aA7U@=H4X zl8JuF68R;ae#u0?WQqKePQOG|JUqTHs(>H6{-SARo7l9nM1Dy}(~7vvTjZB?G_8os zyhVOVN7IV9%vWoABEO`gX+>PlZ;@Zp(X=8i=eNi&>1bLJ zm-AcXmvl6(h|9c1eo05uinyHLBEO`gX+>P-E%HmMSI6cdHmxj?UsAm~&Sl;rzodF~ zj7z^{iTsjIzeH6$xc)|dNykn;+r*}oCGtx;cJdLId5ip#j-7nOW!@scqiBq>x5zK4ULEIhevAB)j-7mT9GJJrFX`CHXHyjqauN9@9Zf6Z zGH;Pz($TacF6Xz%FX?Dn5tn(3{F08Q6>*uj$S>(=S`n9di~N%6)v@0%KUH2Lzog?+ zWsR44i~N%6)$#E%Z;@Y8y*kci-Xg!G<5T5LRXoUBG)K6)3@x%TjZB?e5x!i^A`Cf9iJ+T%lR$xOFBMP7MFR8{F07O zmBnS=BELkPUH%=FzGdfmi{6*uQ)P{pd5ip#j!%`vW!@scq~lX%ahbQsFX{MHSzP8V z@=H2CRo*80B}?R&bbP8TF7p=oB^{qCi_5%4eo4ot%HlF_kzdmBsj|4tTjZB?e5x!i z^A`Cf9nE{6a{#U((UM zrwT>pE%HmMXVJ&YyhVOV^(;DREIy^A`Cf9nE_>zRX+Xmvl7miOal2eo063 zp190g}~ZH@erj^;gak+(JSOFEkOwuyep8u=w1&3ob^Z)@b2bTsdYi@dFo zU((UMCob}~Mt({4ELz^!ythVv$&8(RG+yLwjr@}NJlj5ARG(xs+!TC1J=kdsh&mWGH;PzQay{#W!@scqV_fx2V6Q+G?E3yhVOVwbeM6d5ip#YO8TB^A`Cf)mGzN<}K?FHyk_xRGBn(=SoM4Y^6R+f2Vi1vlg-)owHW5*6H# zoA_Ka{Sp=2kegH~&h$%Ea6@iVr8v_sQNazl(fmfgL#&DhCjQ^5_mkzX>OHj!O-xRcKs`6V-U^4U~y!|_IWqhF$e8*-z((JxWK4Y^U? z=$EMAhTJG`^h;E5LvEC}^K9Gip)+rhUs7!~&Sl;rzhpjbBIh!1kzX>OHj#6gx5zJ< z>6fVB2InpEOJ@2dD!3sx${YO>72J>;<&A!c3U0`a@c!^h;E5LvEBe`Xws30XOnXX8I*6 zxFI*n8~qX$+>jgPjedy=Zpe-DM!!S_H{?cnqhF$e8*-z((JxWK4Y^U?=$EMAhTJG` z^h;E5LvEBe`Xws3Avem~X%pFeOuuA}{F3>!iJZ&4MSjVQogFt7+~7Dwe#uO~Lk-b-+cf4{O!9}cZWI?mQVHIKEB=9gvYV<;Nw^c;MbpbJdTOW`7zS{Cp?ac z%lR>S9FxtB>-Wa_F?t-6%?&Oe$4USXjxY1d$FUN?11|H*$FUN?11{%BK8}?Dem(a* z+cxj+c>PfVc)<1L>-C`SUjlf*)ypm)FYiYq-Cs60xy)On`%lpQbsUhl62ODwz`RlS zF9AH@GH=xVO8^hJ%o}z862Jp4^G4mj1n_{%yixZr0sLyNY;OF{sQZ@y9&njA>i#8w z2VCauK;B9K54gJo4FA0Mte_}p+kZucMWe`mM*j}ONI zdHY}F{^RoX$F{BgQ~B0cy#9dQxE{0{t550r%NFcLadCR8PbuK?_K`xDUsHd5d;uQ#lfT zXS5ruPwD#W1MEgEOLBgT+Ot%S#PQLd5mguHxdlqX*-N>(?D|aoyR_ zYBYL$eV!K=uU$8^8jW&&nPbzoYJT1}v>J_a{k5LB&~7%g8jW&&nL}J$cQ&*djdFdN zLtJP#8(NLVxV1;x#WJ0^$lHciqfxFebBK$)ZD=(bJ_anK!l?skb6JzRVkU%~HQa#Kruk zZPj=jqP%g}EN!bsZj?9fnx$>k$c^&GU9+^U8o5#4xNDZSRU{bcQt zW_e?)(S}x|!CbJ_NZYDmyx28sl*_!a)o8=6S)*L$jjcu-cFh{)GH+}(+OTWZD3|ja zTa7mCnl;E}tC6-<<9Unn##SS3t43~=H?|sSTQzc{ys_0t+p3Wp<&CXI+Exu*v>J_` zH_mTtHQLZ>G|FY(*lM(4*Q`-4^Tt-A4ZCKIa+x=_8g1A$Yn02pvDIk9u33Xzwi;<$ zHU1u=ys_0t+p3Wp<&C>$XlT(laEo;T)=twtMKjYhf5 z8(WPw?3y*oW!~6ov|-n*Q7-ewR-+BOW{q;0H?|sW*fndA%T^<8tH$3$lsC2-XoiVb`odE?bSXtr~KHR-;ia-cM>oiVb`otF6TF{`)}AaYn02pvDIk9u33Xze1@y9{h2rHnl;L0-q>oiVcma}i}e6) ztA-q7*Q`;l{?78ob^i_P{-a#xji2FeXf+z;GH?70cf+n(qg>{VpW$xUHEWd1yzw*K z4ZCKIa+x=-`)}AaYn02pvDIk9u33Xzwi@ZHeEfc~Yt|^2d1I^5hR<+Exy&0squsD; z)+kqhXL;jiv>QI79py4_{ET+PXSAbS=8d1xZupFLl*_#FGujQUMx$Kjji0e>*fndE z%e?V3+6}Enqg>{VpV4k;H5%m7FOdd>yhVP=Lcc`Ys*xMrPjc5RZL3DE&cOBSkob&t z)3$2l>I?*2=8b;I9{D8;cg@naYChgQ@=F%(nx$>k$c@(D@EOadZPmydDm|M!?1Wq`s;rH<{mRk2F8N%vkz>WNp zm41n~RU=ndyz8%%+%-$vs*xMzjk{)PTQzc{ym8koZL3D^i}#b4-v_Wg_Ey)0-)ZgF zeDQlyz0AOO3%9ziAL~ebUeH$+_?_PBx;}i*gYQ@de`k2lpyP{qq4sOO{`ZUb4B}#5 zxYcF6KX13Xt{;zs--nI;es6VM@2`^$yL0O+G34!5m+|)b?SG!Xwg3L|=YkWonOj}P zKYeH;rZ&@|&5Xr$!e(HqUBGQ}hc+|H^~X|iahrT=um5nH0BvUQ_}=O=-nYVGGcf(m zc)Jg6X7u>_Yans)SbA%(|M2^THZyvB{k5w;CdX@_TYLSF$Jbv24IbZHUB>(C12zLw zxd7)kXfvb7m-8F7nOl4Phu<%>nZe_W&A@ct@Y+@D~=ePyB)2)uWzff@Am*_TyLwh?=OcaH5j}c-d1Nn+?Mn0GfNF_dy9X#{XnU~ z;P33Lu&}pbEH&sTH5ldkN7lN1ri_VFgHf)36eBL=u-onE?RL~Q)%joJcJ%hK0_`P~ zA`D(%ZhMQrpLfp+44W5jA1l1y?B}*R`{6hsZ@1Oi_w(*;b@s>Oki4$BtJ32lGZyV9^De3+8I_&*xK|Y?}UWdJZ zEr^cK(cjtab=duDeL!+soqc~jyM3(i;W+4K(;ioEA1l0nOk>BVO8uf$R9&C^_;P;x z|95rvv;Q{V{nI<`y!PkEuivVX?(WM!z4^E2yZ^Iazk%n{@a63CfWrA@P73G6^>^3e z`s65XP%tB|KP!mq&kD<&6wZt5Ca1XmC7-xK!Hl>b*5v_T&Walp%!uogqqx2{D{fFQ zBd)&-6W5D7#C@?~=4CZOT)!C=*T3Ww*TZ^_{udv5mWG>AaXqZ!`m^~c*Vl@~b#q!= zoq>yjjZvMdJFGe4||b-Ni*qT;>foqoZ8r4PVYKGrpW1aihGQXWO~VTT(c$-!Joq!g-B1%G-IieZ0(DQaHaf+>9;{D4f@Lqr72lR$S%{ zYqNvDGi)?3F7t-9*-@_k&W|timK4tG_%d%OoL}aoa9&*I4TbaKMtQ@Rv&#c+M#YWt zcAjlJzW8!h-1AIbS;(v7z`UVwUfd{e=h^o0GHgFvH18*q!g(DB<_(4O8gFzziNbk}mwCgNuY-BRm#^Y-e#4iq zqg>_A3hBa9TWV6UPqb?{jm51fBBz(`GHVezu<`LH`Leg`_to_ukXHk^Ow8tzIuB6ue-n7f8E>NU+*41*|%l* zBBM)+4{ll>{9>Tu2pimaWPkZmznyzOT-?+M>(>Hd?OHI3^-F=Uekl;vE(L>F>;)jK zUkQY@E5RsMf9D6mF9gEcgzuLHu`bzl^$^X#Mb%Yd+U85qU-RY0TltH5;l zJ^-UwzX%BH7Xe{U(oavRqgcNNObd1a5Z0~%qgbX4n*a!#qzroiXtYe3?*TA6TBZzJ z0BE#H%CG}~M$43)o$yzmGHd`KEK_z?!e5VN%FzF>gOH>Q_5T_zQ`VA{q5WT2rp(*_ z2Y(4D{}+}i>nG{jl%e}yC9-~JI~_eq8LIz<r;%d{^J++`X9frKE*tAtV;@e{f}Q*pJIgdAHT3K{rErfaIj!iQdpm2 zguVVoPNVfHMp(a*6ZZNkMk{(u8Qw4mo1_fwB^oVL<}Vlqe_+@GTUe&d-!F_}nKCR$ z>L4U3!?&UuEmP*}k)xw!%CH>yfc>vWu}m3OBZW;;hQ-JSwR-zI8SH*NI$D2R5|%0R zwa8H{Q-%^>9fTxhSc%kV{YFmMmr`~)&&sBGclX(w@8r|m{qvir=fD5#?bFk@Prv$g z8-9M(UY35IwRyAOO6<*V*y}#~7aw57^~J;F;`+H3*Ut4YS3lv48y9i?k}9s!Cb#H#-KFsyYsrvj$v+Z2wtw(t~&$e@!w;tu~JloD?-g=a`^K3hp zd7E_xuFu7Jww=qo)$8J`^LCzX<95z(bCkF9Y&)0p+Z^TXJloD?-sUK8=h=2H^EO9$ zJI}UrnYTI0+j+K~%e>7|-p;e_T;^?#@^+qW=Q3||l(+M2JC}Jo-;7+JxASZ}mw7v1 zjRaigZD!uicOwCpd7GKH^W{juW!`4y?R+~DaGAH6c{^W^T+hXOux+22H-8T{djEhI zVd64x{vvFc%e>)D*k0ata2%L7yb2RH${XH=={PWNiKVYS?U^^c4BMN(3>!Ya%p2Z@ zi5uk&ufw(-ufxQR@`m?e;xcdkK5Y0nFmHGvrtwC3!y7S;mwEFyVx!~5D=~4IH-9BI z%w^v2PE5xkn%~Z|ZSw_QiisQL4R6JC9GEwMD>i%_m^Zu@+goDk?~<@_9PnOD+$e8& zF}Ce^F(z)5H(2`OGH?E7Z20&xZ+JDP@kV*WyD^QIdGmK;qvM68FD~F*D)^u=Y~5=&oPzAu5Luj3HCFTr;08ZYO!#M0MzIlsZu*Lb7(?L6CdpSojy z>krZUlJjgk7w=2@xnt4w&#~v(HtvD_Ku|L(`Pct~+a(+9Iw|=U@0hf8hcI_H(lDFwR z+kSkRH#DG~zq(&uKc3FB?Of(!mc$qg>!AHk?o^3yGxS#Cqf)8_%w*xY`jzg5U^KAQgaX;DJ z1|J?T@^(N6-@EJJ!(8O;fDbNilsEb%2mO*B`6Uzml7oIpuYdWq>xC1P@a>>q(j&iQ zI?uNK9_W|!$S;}bm*~3?U!U)hUoyc8*KuIpBEMuh&$b^2&To-lGM#7Jxy)PSmrM}D zbsRXqMSjTyGhAHGZ;@XzK@H#ZbqIbBkzX>w4HuX9laXIC(J#^WAslaVKRMAa(FY>r zM)Mo}lA|$ikzX>=FVQC=9B*_#Nx$T1%vjGyGSM$N=$G`!FPZ3<9G!WK{E~@&iM|x!@s09EzvSr5TjZBa^h=J;yhVP=M8D+d z%vmrV3aj?TPAe#u0?zht6ca?mf~hS7uXOX!yz^h@-mMUo4AZM7ZrOZ2Hl#AV*-m-NUl;fB!~ zFY^}pB@;fl5|??4{E~@&2`kC>9{D8`{gQ)zNss)J3Ey1lI52OKUoz1zIp~-4$S;}b zmmKs5*T;4WqY%ehGKz8@%q&FFEL!^vExn&;qIP zGH;Pz!b);+Ilo1Ii8_Grd!S#!9r^~3FZ~kk(6{%DBfmt|fB5~+th{u7?Z;@Z378r7Q zKN0h>QElIr2-| zdA2Wp58^U!kzdl_mx#-}MSe+xUm`B%w>k1l+IhD9IADI8Bfq4)mtYmo)e#;xccMU((>0h|9c1eo2F0A};e5`6Ug0 ziMY&L0h|9c1eo2F0A};e5`6Ug0iMY&L0h|9c1eo2F0A};e5`6Ug0iMY&L z^_QqNwmwTT15E1gnmi1 z%c!{iep1JQd5ip#2ERmH<}LC|s;$P4FY^}pB@KRw3Qd@|$S-N=FAMv>VOT=Z~BEN*YjEc*=MSe-O)!6TW{Uvkcmo)e# z8ZYw}`6bm>VBR9Xgu9IH z5A;i-T}IU^75ylLaQz*lbYOU{BD|DH@c*F{|B zjed!?u8X+tmuS40-?VpK#N~Q7{gNf}ORBBLeh>6Zw0m7J-fF9HF7l>*pCc}x-{_ZU z|GJ3F=QsA3Xal>5%k}Pqd5ip#YOC?%%e+N?Nww8na#e7HyhVOVwbeKm^V<^nCDm5r zT;?tEORBBLxtQOyja~A4pkJbb8y?>%Z}dx4a6@jCH~J+ixFI*n8~qX$+>jgPjedy= zZorNFl4`5*-vjd&`6Zox$wa?oiTsjktFiIYFIghLq}pnn%e+N?Nww8DmwAi)l4`4Q zF7p=oCDm5rT;?tEORBBLxy)PSmsDGgbD6iuFR8W~=Q3}RUs7!~&Sl;rzogn~j7z^{ ziTsj|{t|5)#rZArOFH^X#AV(hzoetTL|o=A@=H4UOT=Z~BEO`gzeHT-E%Hk``b)%R z-Xg!GqrXI4<}LC|I{Hh*W!@scq|+}^!42lk$S>*iOD6gyOXQby`Xws3;dqnhw@$xg zqF=JS?3Y|_p7+21%NPHk&GY{K?jPQLr8>f=yU)J;{@wH4m*-~i!`tW0Rib%uxsv4W zKcg9sCFj5S7uyeo^`{bH{Z}+=U+v4g+fl4bxWf96NLYIbFpBkWC}rgPGl{VF4qz1P zuK8FafQLMiK5Z15Q!rB{vQLMiJ5Y{i)!rBALAQsOf!us`ESbH8B#ro%5 z!usV}SbH29#ro5~uzs}`)}BU2vHH8ql<{FiSbG>5#Uf>V7Ln?cqztON4gyo=k0PU^ zWyq0uHO!*hp5%ar+Z$LMI8GCX$7i$8XZVwo~LbqJfJ z3=bVMA3B6R2YBsVhG!08IhXk}$LK-eTn43GqfO>A80{J@Q|3nd;AkPV3(L98h4xV_ z=Q8;0Ita;J2Ay4_<#UT#rlt5Sf66FSC>65jbi=BFRb6l344-$`ZKE(*@H*&(-6f=lLX`!%8nM>uPSpA*-ZsC+` zv`NaKlxwt1nO7E$j+QBdQLfP@DT7e1(K2N&l#h;uWTo%ysh7 z(K2PQ$u-&}Whg7uXqhsX$wx=al))v}Xp@v-D@=`+DRY(lVzig@>}UUNey2Cx-#zOk z_dmaRdj9**-ab8j`}C_{x8ZqpruL_j7$3_#C)%I58uUfv#r26*T#J0Yi~7Y0TU?)6 z#r4dKYcuOG*F!I^Pp#rw=r6gKC*{M<&r5eb(6Z)&2P6clWPY~6RAGGvRY&yo_o+GvOc}lq5%wJ5bu*~2Oc_295jIH~z7NrUNlcl4 zA2NDunKFDHqR}QPL;I*k%ar-oA%mmE$05QpW&Ux-kx9IzaZgTqTBp> zPA#|R*K~f>OZ&HXU;gRMzdgUY`|Z=)|9rgrr?0VdZul@G$7EE7a`rF&h<<`qL z)gPJu%3{8J`Jpc{$+ZXcVJ_Z-b?B|r=6dTe7q6Q;{8n*w8UNc0g<&qTKKZ0gkJVgS~Pd=HhLbzQp8luy@YGTuj>f z5|dne9X8Bm-k`bak;~pX4|DNCOkZMRyzaRUbD1}Yt{ShscOK?4Z!lfOjq-*M?d0HL zeP?skb$GnY8(de7H_97iSB;l>bJ=xty!g;gT)ceV+;$!2GH=jbbsVC+;X^x(mw9vF zb$GnY8-!QA>yPq=5A8Hw=FN@Q;qfwWP+m3OC~t6HwJ|#udNy}nFUMVM{tH-BT zcl)3J{7=8V``5cq=Dywi{`_ALpXg)GyWb7pd#GXGe@oh`#;@J;>?;|UV|w}CLtMXh zi|fB7af55Oxc*xb*YB0IsvrE8#Pw^pxc*xbH@H_4*MCd05PW4`+~Bt)u3x*w_1}`X z!L?glzgH61uifGX_e$dWwOd@jR}%NdYxm`E|9?_se*5@uZ@&NL`B%fgdEMpszfl`g z`@c~;k_G=pasA&YuKydweevJ;a+Y*8#|p{9`AIw12lvGr=O=xT<@YPvxjy3hHATn4 zuPHhX$^2AzBbWED3+E^8Tpx|suPGX@UsJS`TyRZ!e>dXe^=pc_!8Ju(zotwJ=cgl@ zpXzSJ#>@HXczJ&M=KX~|O8N*yWe=Ybf zL&qV?+j+Kqyv&<_m@zzFpTqS#^Eq7Ojq-+#2E=9F{L_r#@%kJtF7xK!W(;$gH+-Bi zY3KUnx`T}dCVilV>#u*EF+5)84I2$;yiwk;(SXLwyd@hANXg;+hA%-h-e`Wqryv?H z=QsZpWc2u+XWR0IZ$UKPXns4-wsV;`{}^O=yqw?gHHdZ|jpn!WZ2NebH~$=Dc)ZLT zz6a5Gqr9DG+s2CzLc|U3nf3c+-ta|;xKZBDv+d($-u#o0(c_D6LZ$`ZglN1`-p;e_ z<7M9bqmbe8GH>`QMB|O}hK&Yv9GEx%EM$1R%p1N7(T==P-YAbRl*hGmeKHTx9$#pW zA8wBi9|z`*`uO4c_%N4wqd$JQKR(Q5-YAf3=lbOM(r{a7kZb4qh|9cDA=l3J5tn(R zL$00cBQEDRN^aV@KH@TOw8*t{eZ=MbMvYuM*GF8=Z}i*__sB@cn2$s-rvEB8{JRh9jv&_Tk;N8$ANjn zJ6Mf3${XInYP`IkeEA*h$KLOpXWMdtFAg={C~xQ4b}sKHlP?aXQ8I7%;!xv_@`jBD zbbOh&m%ljt=<((JwtL>1cCJsZ57=lxh? z-_En`Twf0mH_F?2ww>#F6F0e^)CTh8`urwtk~eMaO|Iun+~j^z8|;$n?04#?YzUQdlT${UJ3^>H=x=Ea_)^aOu-d0q5>NrGs!$t!d zFZ1Tzp2Oos-d6aJ?IH3XceHzIyv&=odk&A6d4vC`@kV(=zo)*o_xnk4qr9QuQ(WdP z@*nr}Y+ufAEBr@|H_99R#})pgxY7KEj!zv2<}LCc_w#J~ap3&sC7+|ev-9tq%e;BZ z=P;Lfga6pHbA2*joM+p|%e+PYqjrP^7yhHh8|4j6pQ@o?-Xi}|JJ4~w%v&To-lvePeFQT(an5ZzCr`BUTN{1*8oJN=Rseo52L^+_(yvu*Pm{1S1a zyrKM41w(va68R-N{gM@aiN+h{?L6Cd9N?FTo4haC>6fhVOT>-xM!#f*Um|WaztJyQ z;g^UT&2RKeR`@02MtP%OvZ8EM+-QC~&$j;_IKM@H$xgpyMcruA&h<%-&$Dgggcz68|96D$qK(j+$eAKOIB2liW}vPe#r{IMBFHE^h;Khj*1)Q4XvYUV&nZ} zm643CE`YTV?W^v zzeL<9Z!9QW;g^UT<&A#H3cp0$C~vGNT;Z398|951g)96LaijT-B}yy&5^h9$H7WpMR{gM@aiN+h{jef}rzocpB`Xq1kOIG+L z;zoI+U$Vk45jV;k{gM@aiMUbT=$EYUOT>-xM!#f*Um|XlH~J+j{1S1aywNXN(P%Ah zlsEb%EBq31qxp?~$qK(j+$eA7*|zI1{SxgGndFUr$x6RO+eAiOooyR0{SxgH8F6*C zos0DVZ4?=CIlmovKdGG}Bd*T2j~9N4wu%h62mO-u!23z<6&Z1Lwtc*KKdH?kBd*T2 zb1}bZx5$XAv+Z2GpVW4d5tn(xma$Dc*GF8PZ67bz-&FJzagn!;eu;LBjJU|#M!#f= z{E~xy$%buXb$pY&9p~A;JiZ(K64m)9$ANyyM!!V8=n)rr+vu05@+#sYZyWs*?Hd_! zk++S0i8hXmxX9Z^zhsL1l7oK9M!!T`M@Hji-sqQT=lY1tywNYw=8+K>^V>$hM7u{u zT;`2_iONnAF8z{?eu?&vjJV7j{Sxh5A90yC^lLTkAQ^F)H}q?X8|4k#$Z9_Wyr0z0 z_0f1SzisH(YHCW0xXc^<5;Y4&T;`2_i5h?+F7t-|5*>#qZ}dx4w`bpVh#TdNeu?V# z$c^$wzht9dqRP|c_|h*?-5$pq<&A!c>h{Qu@Ruk}2{_s;$Pj z^h>75FR8W~=kob2@=L0%#<_fci~N#mt8pWpOBR^wdeE%HmMt;V^0evAB)YO8TB z^A`Cf)mGzN<}LC|s;$Pk%vz`X#E0O|ED3OH{Xq>qF$1R9lT52l^#yV2Q@d z`Hg;wnmi&d?dONMSe-O)i{@Vi~N#q+g=Kpoq)+N%|!!Mv1t5exqNaqK1ge`$_sG`p`Y% z@_v$ji9SG%xV)cae~CUYjJUj?q+g;Bv?4C^c3^(f2P4;Wb+UD~?Ycw1L}GlzW!?_V zZxVnbF7tL^ev{}JahbOR_mdL3A};erzoaF8iOw7Ic3^&!SP_jEc~ilSKVN7eGU6g{ zD!3sx$eWG>@}`0ta)Z2yi@d4ehTJG`^h;E5LvEBe_Lr#OhTJG`=h?ozKJ4^MTH=?y zZ>w=G^OpD};v#Peo0IG5{(!0+fKivC4Pyx%p3iZ zmiQ&&GH>)tTH=?8%e>JqX^CGVF7rmeq$PfdxXc^)tTGC%4F7rmeq$PfdxXc^{1S1QH~J+l@k_*I-sqRK#4iz- zd81#_62C+*S(rEaCGBOuD#AY{kjcro~MQzKiQfj{b60-@&^y=;`+%J z*B{o!4Ib9T^^+~GKdg(ZxLv!cw77n<#r21EaTT|p=U$$ae|Y!Rw_iU#-TmYDZ=Sxs z`?9w7yyA4=8-2}v{!E}x^mSl=ei$!zPOG@aubJZdJ1=o{U<0mSGsX31aB+2D1Fl~) z#r0=!RSGCYKhM299lv>e^Yr%JzrVWsV%qmV{9*V^NFDPZgj{L=K}?(5E_H9CQ-A+j zZ)1MAfAjqO^!AV6KRGQ zFK3wRzZ@M0|K*5lznn|%<(c@OcKW>jYBhB(olRIelaUr&t;F@Kl|Fd#tChIH)k<8y zT8ZmdD{+IXmALqEPFOk<_rx`Q3rW8|97F{}YzZ#EtUC>VK`I^EgC#WA(pQ(#cKoHgoArE9vAWd7D}Nua$Ii zlf2EW{?|%6xk=t;R{v`yo!lgEGpql#k`8XNbT-XgI@3xzxk=vUbD{KdNkfZB{c60ppVX(JJibxhxOCRAbar-qC)XV=oi!|-iTh&SE+0z1{PwH=cznLobK3K_ z@9zHe_~z@ouipIS?z^v^9{=m^@AhB!cK6r2hfnrx8GmwA&4FJO7kCP~*|C#<{&Ii$ z9$GC2#Nyl^eyttF;?ys^)K)LT-)XcVLWS@f@-6 zI(xXHFpAZA_R-=pd$^%6iuIQx)55Fl;aAyFEH1JOFS3XG38Prt(=5Ek9)67-#WH2Q z#2$W$9mO(byuu!Sg&oB*WxT*1{(5l`%j@gH>+9jy*HNtg&VIMNydHje9mO(b5EJyY zW_L5ASf&hKg0OZoGm2%(pe5)T(4N&tu}m4P1Yu9oo9D-;w{O0=e?5w2${-~OYflcN zSf&h4g0L^mWta2p{~Is=W_m69PLww(_VXEh$uXaQclm2?{QYPnj>|JL%*78#nj6OJ zKcHbQenE}DAZ^6)(s(aV%1`gc*L@$pz0s<<|I(z1`8~7R?CqC!`9k>RcUa>3Pfc8Z zMitk7YQtQ=qKoVIP2$=+q5p@ycWc=tIj=4MN>Nwd;5KhYW=3Y}&TRL=*s_gfXhYK% zWxKpvSO-%sb<>#s?|a5mmew~1Dy`?87#-EqZ=S@pShl$y zOL0Ax+BLzh>us*bQe1yV71v_f<}z>i<{@sBH+=JumdU*NH;<3w{dgJqi|@Yqmv4Xd zAD=qE`kP;95Q)Xi>ZW$z-X9ZPUl?vO;pwX?F##aX#S5)s$V$~G5g z?jZl8Csr3beUc z1$Iax;@T?kk^3=4fA~$r_WJFsi2jR+*NLYCISp7z)P(i%ioZ^T&%THdmXXENfm8{L zY!}PK;`UBhOKca*z~b&sSPN_y%e>;|PJ2~YUb|Sv758?+F4B8X2RdX-E1nL7wX}9e z%dq0P9AGL7i(9p;Zg$>H8AN3X+;}p&TvYDPEmHlbTb-@hdi)-Tq= z`jfS=?_aEi^;;rg{bH>ey7w>E!ZKypR!P_-Wq6IH?sTTiUt@i^p#1n-ERB{a!&@wk zHc1)xRN_l4VUv_`OC`R;5;jR0USVl&nKFNc)tp;ysKhr|8f}s??x(~TSi&YLW8Dqk zUkRI}jJqlE^_3Q(BxT%8iEpoj{jrpNTwnj|-~H|X{MApt`EOtS)`S1we*K$&lYrfR zBP2l@SEn5{cse{jZ|e;G>|?9AxIFEs!PD{aiR*H4ecE{!aN#bX%f)TL&f9f5M>)SClv259n6WKdW81ALz~l^Trzj z^S<_+Jq#EtTX z?^^n?44!i@|E|@&p7FOlJAcb_`EPmJT;`3x<+=Q~JY6n-%d_*hJeU8Lr_E*F_*b;7%T;KRx9`#;DT;`3x%cI__h|9e3w>-Dk;5EB5(S!7jo=1cx^87 zrXPEeo8)cMFV~N~$W8J#`CA_S*o)jKZ#2yHV=r=}yz#d@`mqk?{Yfc zeIAkO*x?HSp`mqYoDy{sB=?i`%Pku(q!MwX^^G-n z^2u?Y!7Ay_1M>#0MB`ngx33TIO0+&P zpq7Xm-Sc7-Ka27Yp z8*A_m)ZmF5J->0A#RJ|FP>|2nK$|+cjT8$`XvYbk~{KCCN0y0e#ssA zC6k)zLBHgV{E|t}^q^mIM}EnqXnN2uxg)=1(lkBjm#FZW((mrVL42mO*e@=GR#(}RA=9r-1b z#_2)7m-mzOOYX=one|`z0UM)BpGd<&XWeWBkcD|D(+54H=a$ zG58}Hna%!CrIn)L#_=7-&UYBek7Tx!uQ2!{8I9H-sd}U38w~zNTUcLlnpoW6@h95C z`U6!Hi}Rnq&=%I;Uo^2e{rLlJ$>{$2qKQ@dK0Zb8_u0bw+lwX^4^#Ykwy^#%)x_di zioebl)}N)CSUgJc$JxRrDdU?9{x)0Kb?y7~rm#0!zPQ-=;^M-KizXJ&Q9IvTTzGHM z#4=@kZE@kXMH9=E9e8VT;jKjz%ak2>X>sADMH9=E9e8JP;hjYj%arkz#f4WEO)OK! zHx?J(STwOr*@+hx+6Z2x-xr79v(A3$O#IoO|J|Se^O9gyTTE289{zN-!eCbTo zBz);iT$Au)7nVQpQ_72_v?oQDFP(`iWw2OUYe8+k^YOM*`}MdC@uf3y%`FU;=G#uFp$7wG|yI6m1Bdou+5!POg zcCr52=C#43{GmPc)9pnU>-T-a`hB0Ui}btqD_yK#Plff@Hp1G|RTt};iLm|-Ls)w` z+Qi}$gs^T=3TvMrx>%+R5~Z-3{kP{94y8uRl=&x!?r8OQAD*s+Wy<^$L>J4H!JvGd z{t2RsWy&B>3Y(-1{^U!$X4zwqu=WX}J6fg;`lPUn^lr*vPinMGnSX-lj+QBdJgLzp zDZ?iSjg~3%PY}(~LY)-W?^-n4BxNusg=Nb86GV5k`a4S*K0#=-$yx?)QlsTs=AR(C zqh-qQ3F3A7Cx|YVYZ*R42%Dq~(&THyCkSEJ0N+g+oJnDsGXDh8odl)~%A`h{qzuNS zM$44BG1(mLI?i_9LYUNOla#IF>{zDEeaY@<^>>ctTIRZB7t6H_wxqVKPVN{XOX`sE zj?rbw?r51ZxRO6?u>E!%ph~`2$tmm_;JYbF-)>+2v+s}Gj|b%sZ$$8AOT@41%eGzU*3;2vU+L)Ws-pH`C6zVc7dm|~ zw@2eH)^8_-^$VS_c019<`h`wdzn%EAxZMAt z+aCN1NL)W5#kKp}Hdi-GK3?45qGh(t#T_nNW?yKT{mAX#_WX8#h?jmu@Ww&nYdV_3 z+8pZr6<@Ele8qp!6c+aVYmuQuvxKF@=TYGYVhR{kSRohpsK_b*xt_O9Ah0vPiDk<8nvRwEO)OJ}Uo>k?v{wP$xn;`unvR9}&CxPtd`-u`{2rFC=~$Pq zN%*m~?BhE7pYYB{#XLT9YNGQOoJXw=pHB9Vi~f&apv3j56W8CNh-(l2T`uke#PuhC zac%C}T%BnjVkE9V`ipBf0&T8eqr~+)0da$yKouYPMM_-12^7~ZQtk2jRZ3j{WOtnY z$*#@yn*nkCG9~WH`tN-Qh?D;3U;XU+Z?&cSum0OtKl{JF`RDJy`nzv_@rytDvv2?T zo8SE6`~T9ur_`D5*SKx)sb;#g-21nR>lZn3-CofKTy~Lbb3Lo#dRE2N(fj>#_~TjC zcs;A)dRD~^vZ}=6E!|-4-t^kN?mWN~(|A3r8gGzQjn}g(u4h%;AgkhfR>k$KiW_8A zT+gbwo>hJRu}>21`Sq-d>sb}|N3;5e&NFQ4xDCi+;_3*zfBv#|Z@?B4H_97-u|A-S zi5umOKUp8}#l(&B24PI|>uaO9!P=-5*4IXHnKw7ay5|{`F>#qUSH{|0<_*r6<{`=( zYxf4EF?|<}^2XY|0c%X$C~wflwgGKS+$e9X-5c=6#EtTXdr^&->zj*X?el@_8}3Cl z-Y9Rl7u9%~x8z<_cb?1}?nO1;Xnn(5DUFwTOYTKAUgiz=q8e|MH@uh9c)7kM_o5mv z*EigYYH!deZ+J5$eI0Mfrwe4=^B1qC#O3{@8)R)R?taGH?ENs?BBI@Onz~5akUTna0b!`TME%c$qi6pwf7wys>s~;0={bnrMB4Nv3(= z{iK^@?Rnty8{ScAywUmwmrTDGVcz^DReQY58{SfByiwj*yEpKfO5A9D!+R>t1M}wZ zsk-w3pG;idPr6Um=JNRsAKWw#(eoROGL4tdZ*G*e$IIt8C}sL7Wt2BKWg0K@=1y6A zyv!SG_o|5P{pUB|d%VmWYxkzt?zOqRpJeS`6|ucP53JoAtlgVlyVo5r zYxf3g_omnGwYkh2Yxkzt?zOpG-&nghy>_q7W!_l3H@$YR&E@?hYxkzt?zOqh8@F|w zzO7@M%lDJq)^Yl_j%_aU#%&#^Z|m6RGH=}0ar(B7T`sqE9NgA%`nHa3F7GF~t>g4< z9ot;yjoUg--`26sW!|{0v;LLj%_aU z#%&!h-`26sW!|{0)0MI^0sqZ$IG{M zY;%#fo!dHIYootl9+0=4+d5urqrZTQyzT73yQ+}?_kJ7w1K(RtTJk$B`O7W&?)-9F z$DNw|<(hn(i@fdh;G19{aIC9oo&DW-}>X{ zlDK|t5!c_v9!GNTEUsT$#Pw^7xWT(vasAq&9XI`5thhP?!94i2MO=S3ByMnR(RlsZ zBCdb?5I4BCi0juDas6GaxH` z_N7AYPyh1kFBNLPodmzIeyLDfZOAIv_unv`{syplso@JiwY3wg+5fZ%bg_O9qtW_3 zj9Txss=bf(TNq*e7DiaRh3Ssg?_h-WJDC5m6>9$(GVj0(EiLwb`e?D&ZPBL#(z}6{ zAE+t*@Zc`4pFiT-`P1h52_&wcK;qg7)aLpbB(9%9;@TPXk^Awc=P$nd=3l=3)mMK% zUtj&}um7KKzx(!|zWRs%cj>0T{?%9i%in+XNB{eO{hR;k^&GFhbUHRl0uLksNlTSINkCk?F>Q1G##CItF%{QtOzTy^XK$;lqN&GSHp}Tt**A0%LbcpgmrH5Y%}6 zK~UUvq5s`WkT%yJ1h)s0fVh^oHkWzBQ-QdixAkA?oDa+!Bmr?PZ|(6iZ;%AUwY+t? zlms3~0^(ZU+Fa%hl7P5T-tenjoe#{LO9JijGH;LsG~Ot0+?(%#Bp?aZB!O;@DG5A~ z1jMzxt&_QN`mTfh;Z|XL;0Oq7aqD84HYftZTH3l;h7E>*uokxV}YXO~%n9U!h{tvd}m)IMB1 zw;e7A^ss|&zymixqqU@Uv0T`o1_)~lTNlfq!3+@Ag4RsLSV!6?7wg*LWY;Cb-ScDNbP9puv_Bj- zasBI^xR$l{Jb2i|W!T&d=yG8Oh>LaYa5JFI^|*+Y{{JzGcH<`>PM;@W*=bGcXt+p&z>sv`Js*=Y`U9c#-j#Pzs!=YerU@r1bR40!wUfZ~bqLh*#Sp10H6XJ4t z^Wup%mw7|+gyzBX)}06D4aF1sA#{|tb+r9FW8S=YqCF4H8;U11-t{kk|2$*fP&^@S zls6Pl=&^velU_X0o(JX)#S2PiVYR-cUTD@iK2-JkcF5iYLTn-n@9C&1K$DJfV4r@`mCGjhA`z z;)(WnnKu+qs5m29-%vcE@p66h;)(WnnKwEm2b_}T^$bplUia|v4Nggy%lk<>B?p|6 zE|+eC!<~}$c$qgkC5JmD zT`ruG@uE|5xKq;RGH-NB4tGl0T&{0)N)C5Q+Fa(1PRS8DCF&L6`M|tIPKkO2$mROx zPDy(nm^Vr#hf5`GF7rmK2jGjY9;vbT=)FNkLUDxi=W@1 zm2}6;yiqH`kLTLsW!|Wj;Ky@qF7rmM1V5hZa-o%IetAC`X(jaZ#bw@HD`}6H>l?ii zc=~NF*EfnK@bueUu5T!wP%&Th{I(<_yZ+KFIo&L2kC*Ek)shoxNi%OyOU8?8$r-67 zV_8Ht4^&IEA6xQ1b!kM-#pmv-B6#~ft$GE>Mc%X{TQFYr3XqGuoo<&j&jgW$+}v6{`0){4JDU(i}Vuh8%i$o7U?D0 zHLuHYd5iRtoqEak!t>kddP(!Q5j*vgje5x$=_Nb$68&J-e%Crq*Gt;t z#rn2UFFB!?^w#5@ddWt;sld4pfl>6fSxmgChCc>n$k8=L5S z;QAK%B|A1Y5tr**Q9 z?AX{uPQ9?AX{u^T51Ce#uV1WW&ZLD#X_n@BJKO zV-t;+d4pflyq;lW6LFch$S=`us#uTdm(&KV!94K!jebe(z#4G5zR@qiCVSocK5Vi# zv?Ua-XOUl`9aTBMT;C$UWT#)kP4)&h+3U^&Ha5{bFmI7x!cF$X<@y%+CE8V$^UJ(N ze#uV1gq!SX0}9YK%+2bX-Xg!GDr%g|yhVOVb<{YQd5ip# zDyeZU^A`CfRZ`i@eRqFR79m z=OS-2@=L0u#<=uLX5^Rb^h-ASB{T9%s-?!qi}h_reo58TI2Y^N^zM@8c~&(w&PCp4 z{gMg4r1yMLWi@`DF>mlox?K1rgMP_`U()5```e&jGU1nWx%mDz=$B0R zC0#D_M!#gjFX?jOmkjzP6MjjPOTT2$FPZR5x?K1rgMP`3{E}*`vGbRH$&C6-s;$Pk zT;C$Uq}pnn%e+N?Nww8Dm+M>PmsDGgap{-L$S=|MW&V6T=$FjMFFEL!4EiNA@=L0% z#^-_STjZBiTa9zMzD0h?LBC|sFPV{FQf)OpUaoKMmvrxc>6fUp9P4J}mmKsD`%7lzmsDGgkC%Ci z{E~xyiGH7lTtt4!LBC|sFPV{FQf)Oh5A;iBm2mKQH zTRd*j^Ben1x5zI!*3mXD{gN5^CDm5r zT&{1CUvjX&WY8~}kzZ16H9lV6Pey*p!Tu5z+~E9;{E}*`@$oWmkzZ16HO^(;BEO{C zYMjfwMSe-O)i{@Vi~N#mt8pWpOBR%2ZHB{T9%s;$Pk%vyhVOVZT0S4<}LC|s;$Pk z%v4#W!@scq}pnn%e+N?Nww8D7kRtjm#nWkpa1=4wbeKmdAr;%skd|;F7GGl zmt5|bw7JY1{gTW5k~Wv`OW0p>!7u5~FW;9u$lC?Kq{pqc8ar;>9OrVsq&W}OR^wdc z?Q*}Q&E@*W?QyQiFR8W~A20HDMSe-O)i{@Vi~N#mt8pWpOBR`Zdof*Zdtxgx)$ z+G?DO_3euMl4`4QF4ngz@=L0%#<|Q}6fVB2J1yVsl2@ovA<+zf5{d3B`5n!RB*%bM(Z2> z5*6H#o4lW_wi-Wf%$xfq-TPnqB`Ub#c$5B;YOC?_GH;Pza?&qR!41Y6^_Nszjg6On z$rbI7Q*AZQ<^5!|KhDYhaa3@_c}RTaYOC?_a(#>Zl9T-iVBR9Xq}pnn%e+N?Nww8DmwAi)l9T-;t#9;8RB%IXw7$_V+3A;DQGZFb)%f|q zyhVOVwbeM6d5ip#bJ;}B<@y%+CDm4AT>2$fo32ljl0xem*d7kzaChe;gIuV7!rEaxR<5$IHA$e#y!H5*6HV zyvgqaPWmM(xFI+C9<6PwJhF`MI=FfW|)mGzNZ}dxU_$A%><^3f6k{f$Dns;$Pk$lD$HCDm5rT;?tEORBBLxy)PSmsDHLN3IHP{Q7&>k$U(2dbQO!7wg*{ z`6bm><6PWN-jQEYZ8grt`gTWt$>jbxD!AeNChObe{x~YQAvd|7thO4T2j(sEORBBL zxy)PSm&|pvoy)vMe#vBii3)BozmZ=u>6fVBhTL@}e>-pVOH^<}ZgM|4>6fVBhTP=& zZPG7M!40{|{p6%yqJkT8qr9=dLjbx2lvOh zBfn&>-H?2|%vs#cPR9lU6nYYLTMUs7!~&Sl;rzhu%cQNa!7A@WNm`%6@CLvD0G z$^H@*+>jgHPtq?@!40|5{UrNK4)&MakzX?Dm#E-|4y^?#M5xwi@R$Z;@Y8Z8gqi-Xg!G+G>nTzvPbmlF9xO72M#sMSjVoU!sB= za-+P_FHyk_xzY0*{Sp=2kQ?QVeu)Zh$c@%F`Xws3Avek!`%6@CLvG?vR$Gmqzsy_Y zmsDGgbD6iuFPZEwQNa!7A@WP++6~FZJDIo0FPZd94*Df`6fVBhTQ0Wl75K_Zpe++H~J+ixFI)M-{_a9;D+2NZ}dx4a6@jCH~J+ixFI)M z-{_a9;D+2NZ}dx4a071SmrVL4D!3sx>7ShROH^<}Zj?9rB`UZfH_99Rl7oK99r-1b zeu)ZhINm64^h;E5LvEBe`Xws3Avem~YOAsJ;%43=zhrWM92MMfyiwlP(f08oZ%^cx z%+*%oT;%PE{E|t(LHK`tV{q}pnn%e+N?Nww8D7x$A-o2BZ`D@g^T51Ceo3{}IG1^g{E}*`aW3-~`6U&J+117yS|y+;F^6-sqR8;D+2NZ_6g~d0^fmzogn~oXfmLe#y0LBIh!1 z@JrU&+;|RHN87o~8~lf@kZ+#{gRV@$rJe{7yS|y+;F^6-sqR8;D+2N zZ}dx4a6@jCH~J+ixFI*n8~4Xi!40^PUvja(Lx{gNm0OD_5)D!AeN zMtP%OqJkT8qrA~CQNazlQQqj6sNja&C~x#jRB%IXlsEb%D!2hR@=GrIB`UZfH(KB5 zm#E-|+~|D?{gRV@$rJULT=Yv+aKrIN>l^(N72J>;<&A!c3U0`a@x5zK4wwjMz72M!Fi~N#mt8uQsFWFy_Us7!~&Sl;rzogn~oXfmLe#uS0LSk+s*zG72J@UtZz5{5*6H#8?A5jOH^<}uIH`y-SnnkqJkT8 zqrA~CQNazl(fUTeWNyqG{F3H%hy5igxWRbgmvp)MJIfpVlKmC=B{%&N72I&V$^GO_ zzhuHM(Ric0(Jz_sOT>-xM!!S_H=KtkZ}dx4a6@jCH~J+ixFI*n8~qX$+>jgPZ5?ep ze+Tmx`6bm><6Pz~@=I>|B`UbVJVbuU&HZsya6@jCx7Ai-^ML-6{T2BoH~kV7+;F^6 z-sqR8;D+2NZ}dx4a6@jCH~J+ixFI*n8~u_AzeL9^${YO>72I&V(eoSq5*6Hl8~G(S z`%6@CLvHfE72J>;<&A!c3U0`a z@6c9SCE`Zw8~u_AzeL<9Z|pCb@Jqyv z@gw${YO>72NQAi1J3iLK%UiWZcFr>$ZCj7wmxvqX zjeg05Um|XlH~J+ixZ!d0yse|ymim@>X9DJLehm2ERnyC~x#jCj1g{EpOfH z1N{;e+#nax{x~=N5*6H#8|96D$%J2`d5H2xzhu%c*&@H>reC6h8=r?Q@=I>|C6j*1 z7WpMN{gO$)WQ+Wgn|{fpU$RC0B{%&N72I%sle|@1jjfyXOE&jQnt7|X8s{Q!TjZBi zTa9y(w=MEZo^`aHi~Gqf@=L0%#<{qk+#pebkAS*m#E+d^APzZ5B(Aq+>o2xPd@ZZRB%IXazFXd zFHyk_xyk+HL%&1?H{?d^8~qX$+>jgPjedy=Zpe-DM!!S_H{?cnqhF$e8*-ET$%lT4 z3U0uKU($Pyeb`^3f*W#^=eLJ`i3)DWjq*mnjgPjedy=Zpe-D#{QCPFmI7xQf)Q1ZqhH=BERIJ zU!sB=%tO>)^3X52=$CAfU-Hl|x#*W{QGdxpzeEK$oCnKW_r8RFi3)DWjq*mn72J?(dFx&u=$EMA zhTLdf@kaNP+#lznU$RAh$wR;7 zqF=HtbOTR<~H#}~Zx9)ow`Xws3Avek!{Sp=2 zkQ?QVeu)Zhz>WNphknULzhsO2l81iDMZaWozodJeq+fE;FWDl$WB`UZfH_99R5*6H#8|96Di3)DOjr@{_ zeu)Zh$c^5Y&@Z{@mu$;82+ju`ZCj7&mu!(=^3X52=$CBnmvpb|>@T_Kmu&D$*3;bQ zzoS3&OD_5)TjZBK^h;E5!}B4^8~u`te#y3sgZIw|`Xv|rk}dK}9{MFJxWPO`e#t|> zXP=xt6x|^xqmUzrN8f*&@57x@!EeA#KC$lI~&S z%M!{ZBa%xV$|V=&lHqbmceq^J=$4GgEqUmcTy#r@yCvP>GHX;z2DZj&eZo;8hl*YPRu9*{EBw-xV8mrx#gMu??|{^gC?teow>Ib=8N9@7%+^lJ0Pk zHTBwXxa-F8?cq`@QLhcT_Sn`OF0B&P+7KJ8YwD6g)>LaluB~g`;p*@FpfPKSRHES` zYihN@a9t|t4i`~VsSUCA%+|#+X;ex^Qdy!|VAQCTj3pU-I(NInWzuMrjATa~4VO`) zQ8Jce@b+*il&H~$2hEb!z2HzNQKJpH7PaQ=(kD@&4Y8KA_Hgyzx2Vx48R#o%-ZaoB zQK1dSoA@OAi#~}8ZOFB(wda9hqfauHVetN0#;j2%8HrA!X<*o>lZ-?s5tm`3PBN11 za8#axd&rwQ$ykEHr|In;HtHldb&|0JgHPPvYh;a=3mbKkk!*+aLphDbjXKFl>Pmhn zr*SUh2AyPGGC%u3EH0Ne>Ler4NyKH`sFMunB;D~cZ`4UfqLXO6%o}x*k?17iGH=vL zMxC*5-$zm>QJ)Pill6+>eJ&o_)MrDk<*l1z)|IHwhTLd*qfT;DCmBmH_;h_}kC%6n z)JaC7lc)Ixmbchz~%Zzon$P*AmH+Lk~+yq>Pmhnr}6WF>sz9eh|9cD zCmD%OA};eron$0+CE_w~)JX<(lIFTeo#duYG7_Cc<7M8clZ-?s`JtS~&IjrwBhg8I zD5r5Q^R@(o_j5s={POWF(MiN*-l&rd z*GanTJav+rI>|_M5{;MllhjE@qLYZryiq3^iB6)D6RvO6Nd|P1=5>cUiTZ4?zO4d_ z59e=}%k_;q$ykEH2kv^fZ#)lCC%LJUj3pQZT;`2B$w+jPAIfPgZ`4V~5)6XzGH=vL zMxv8wyjLI>~@e(mc&`<6HABqPyD#AV*7lZ-?s5tn(R zPBIdmL|o>LI>~UIq`Mw-JDi(7$#9>f%cW3qQz#iOl(f0b8->6GYJHsUgG5AG+mWJg@)?ZNv=UGgF>*S7~> zx)q&>%e*~U-}cBV*=Uuh&j#mNWR+Ao&ByaWeKzEJ-g>#HavJACE7_B}5=|b~H}%q-^`XjXe7x{V_N1<4uW}ma;(Nfp3M}4UFE)xL>a*cIM0s25tB;p?OSZ$&JRon+ zi+PL8k}9Y1@iK32mNf4lHrAD>&j$0G)Rkx+u)e9!hTJG`bW7A{LvFIZZLBL%pAEU5 zx90VMa*6tE$c@%F+9m3Ry6laXGsQ7=)Q4d*wyoupp!P%qhCFX`ru zdWq_6INoS|V_S*pY{-rB#RlIo^$F7p=YCDl#iT&{1CUQ*pO#-(1eM|#Odz2u=@vPXK!M!n>rUb07e z$ws~8p+j9q`GN*yv$pqmsB^6ajBQ=kzTSQsp$B3*_yH z^pa|)F)sCz1A0mGxpPvczXEz(P>pvJk(Tcnp%LCpuQWHY=k zIqHks@7|X*zrR&OjdQWS9g$vA4K>ci`^m#wOWNbr)z!JoTcno^)Rt&|nYTzUsfrpO zFY~s9gHP|dy7RF9&biE6q?ZinC7K83Ez(P>qsGU}yhVD+fL@~UGH|nYU#eyq^o` zCE_w~&`WyvB~?`8^UJ&~;~*HX>s%Ty^A@$2R8x(Qmw9u&qdONMP^CW)Hs)Ui_DU$sc|mz7MUegQ{!Cb&CQbTn`#u7 z=(sU&ky%nTH9lVEEiy~0rpCF<8_bes-cVe!nr)D`$SkRv8XGUok^^Q*cf7ovq*-!A z#U)i!$eInI!{eiMY&LR9sRuH9il_TU1<9H8sv<-lF1?s;O}< z^A;7CR85U@k+(B4ORA>ExyaiYnI%)Xcta88&dT`u02Y%DH0VU~2c zFiSRWh;za$X>w_nY&1(wm?d2<@}_1R9yd2jx?JQ<%{Juvm+mfC@54TxziPH2*UiZ; z7kN{&4Y)8%x?KI8kC%CKv!wZjw`yvPOS9yJS<)RZ^G37egjv$%GH*0XPM9TKF7rmS z6X>a+x=pB`3_1E|+;@amfj@q|4Rc zc`leYm?d2<*EgCaC(M#AmwBUEa>6X>a+x=pC1+%o>@-U@nk6U9lID16mTWXjPM9TK zF7rmS0#pPWUC=@#^oK%k>R@NtesK(JwjSmvp(z8~u_q@=JC!m*{;DzX!lC>5i9qV{^#~ zzof}UbBV^w^$mVWm&?4-FFE0tbh*qMH^w>Pmvp(z8#l%|;g@u|T;I4c&Kdb7)l*}6 zqhE5uFX@h#d81!)!Y}D^nK$|+C;XBwm+KpwOHTMDT`u#+=8_YBNt27_l3mp{xbK5s z(&aL5Y%V$7FX`St&@WN74ach^@ZlF<-SIMS+!*JCU()3=Z)`3(Bfq42YAkQ`OHTMD z-SIMS^h?gjFWJ#tva8w##|?f-cf8CSn@djkC0#D_M!)2QU()2#FWKmqobXG!T;`3< zB`5rnE|=>Yn@djkC0#D_#^#a}eo2?hys^1t!Y}D^^>>yxZj3YGmvp(z8~u_Azog6M z`o`vx3BRPvW!~6aGU1nWxy&0k#+mR-dfe)%vExR+WWq1$a+x=7j5Fbvbh*qMH^!Nf zUs63aJ`ecbJ>i#h$IHBNW1JcJCDl{oHn77C;Io8qk@p65O z{E~xy$)H~{BfsRp&N#cOZE!wBe#xm(0j7Ij}R%u67$7x5zI! zmQ7^irC%~5zvRHqI2teW7WpLycE%Bxd5ip#gMNwXZ8*PC-qz9f`DNZBzofcqoXfmL ze#wEIaWucoTjZBiTaAyGd5ip#gZ(8cxWRFY{E}nYL^fXfB{T9%4)&L*;D+Ok-j~oX zQNazlx}$&py#{v1*;Q~uZnVD9FHyk_xl!KOUoz;I%*ZdPwi-Vln77C;IhIZ2T;?tE zOO9m|IhT2h{E~zHB`UbVaf|$tW7$MDUiu|7@=Ff(m#E-|x5zI!urrS40eQP3zvNgpk&hR7 zyCT2jST>Py>6cuQUvgk)9Q~dXdAlON>k^A`CfC;gJ0e#sT}mz?xV^n+960z2b0&tLi_JN=R?>MyCb8lPY0E%HmMt;V^` zTjZBiTa9y>x5zK4wi@R$Z;@Ye(l3#Shw~xwORBBL#!J8Ciu{slt8pWpOBR^wc* zZ;@Y8Z8gqi-lG1JlYWU_u=BV@>l=5*(TiGg6MwSWYJ47;H~1y;I2-R_s;$Pk%v<6Pz~@=L0%#<|Q}6ctlf5}O|WT#(p zMSe-O)%bXsx2V6Q+G?E3yhZ&b)mGzN<}LC|s;$Pk%v6aYrFS#SXWYRBD!41c|-srsBUs7!~cHHQf+>u{0>6fVBhU1O$#{Lo&+>o1m@1E>0 zQNazlGFXH8#qV(r_Ltm|UozQWqJkTYH}Xp+{gQ)z$sPG6ll>(J{gONKORBBL&R_PI z+>u{0*@QKl4ad98nzyg(>@PXkUvfu&NwwA3Jg~pyj{K6z{t^}3a2}$( zvA;wGH{?cnqhF$e8*-z(vA;wGH{?cnTSwcE8}k@T?^zhtt%Lu{0>6aYzOYX=o znd~n)=$G7)UozQWqJkS9w(sxFI)M-`HPru)pMv{E|t(L| zUvjX&yM}Em;<&FE}sNja&=zfy@B`UZfH_99POAhvz+>u{0*; zt#9lvIp~+%kzX?Dm#E-|@QKl4Y^U?*k7W88*-z(Et|-$liVNY zj{K5IzeEK$9B-62_Lm&&FL@%rWU{|R1vft4C-O@s`%4b`B~Rp+O!k)?>@RsDzhtt% zLfWfM7jgPjedy=Zpe-D zM!!S_H{>SIZx{U%72JRu`6U72J>;<&A!c3U0`a@jgPjedy=Zpe-DM!!S_H{?cnqhF$e z8*-z((JxWK4Y^U?=$EMAhTJG`^h;E5LvEBe`Xwj*k|**@F8U=ZxWRZMzvQA{qJkT8 zqr7o{92MM<8|96Di3)DWjq*mnLtc1R?d>n^k|$~}sjeF5GHsDvQe8F9W!j?llIp5)uBT0H z1+U~SBJC2@+t^_fH%c4r64l#~8>NkQiRx|0jnYQDMD;f0Mros6qIw&0Ep7Gf`}1+D zt{OWZV3+8)S=`!O=I!y-P26O4tF9U!ujftNWOb{q8s~c6#7$PW>Z)-r^A_19)m7tM z<}I>Is;lNBSM@eH&my~|x@w%uyt!Rc9SEKCS4Z2q%v)raR9B62nYYL;xoMZE-iGrV z<&AcU>TSriy!DpNs;cp6VB8|P?rY&+yZn`BZx502Dx8$Z< zqH-H@lhy5}TcUCsa+B5Vrdy(N8*-D??WS9zavO4^)s1e6%5BJv(nhyLG6+PbSI z-4d1CkQ=RT>@HEc4Y?M#_IQ~$be9~j$St|qU7~Uuj5l&is;S1V4{%E~-Y9SEE>XD+ z#~bC1ZpnmOqVYy~qg$eK8;&>18{Lu#w?yNO@)DaiOOxrO`hIvx+N2C$?=Nz#<}U1sN9C*jq*mfWWp`cc%!`0Etzmj z#Pz(bt5DMU$`Y2ujj4H)zNk?^M>w{E|=>Y z+>+x3x1`I}(f08&Z|E-Ra&@$g3%5k$U8GN4L0ztnwsV;`xFuaKpWfh>XuO`cE>~Aq zA1~K8?2Xgp(k)TB4RV3Kak^aQ4Q`3%A<7%w5|!I+-QBHTQcF6h`UDkDR1j4-?*;REtzmj#EsTBx+N2CiMXD(?s%CuxFzB) z(%bVuw`9UC5!ctZ=6LCrsN4p*i1x;*rW(8Mz%9{uJ#XFda(#naBChAH%Vpl+mK?9h zExGBIsN4qg8+Di5bW0}O5{);?8{Lu#w?y11Z*)s0+!Ar4ywNRDxeezx${XDhmD`XT z<&AEM%5BK?^{sjS(k)TB4Y^U?=$1^lB|2_V-sqO7+y>)yx1^p58tVn!k_oructvi> zO}AviEfF`$8{Lu#w?y11Z*)s0+!Ar4ywNRDxebq7lsCF16K;vd8|95|iOOv_-Y9Q$ zOH^({Zj?8=B`UWeH_98`5|!J48@VMn-4d1CkQ?1k(k+>AOO98xH_lDBWWp^GH_98` zk_op&T+3VcdPcWo!YvUu${Xd93AsevC~xd8QMnDzhbV9CE>XD+xl!KOT{6*KqIrn& z#_kf8+xU35$S%2QmrU9vTV$8qv`Z%Kk}c{kxoMY7+9g}mT~bXo_IyFRWQ+F3xoMZE z+=j<3$y+tm_;_(YxkYwKHPtv5dD|kpq?&4+i@a@-T~bXo&c*t+MRv)vj<$1|x5zGe z)=o&y#rn3nUDCX+S5wVLuF7q2p205Zz2B*(8t3Buh=< z-sqQX%Q$#{y!1;{Zo}gi<&A!c%5BJv@H{{bX}~>6fV7hTJG`>@HEc4Y=@2 zy5nWu=$CBpOS)X@K8{{JLOCI_q7yXiL83*sL^YlwD z`XyWBmptq)QMnD~A@WNec9&fAOE&l=&Feb-l8b)H2EU}s<@!dyWP@MQ<#K(aU$Vh3 z>2kTg(J$HHmo&NbOD_5)8~l2mqL zgnr2ezog6M`bNKGgJ06+@_v$j$p*iq%Vpl^mu&D$x?JXse#r*Eq|0UA=$CBEIC%fM zPQT=$U$QOZAmB1@^h>s790Xj=m*tIq$%eggn)6G)!B^&&bE|+_3DM~iop18zy{m}wUD-*+y)1q^pfy2EAE9=s|Uu9kGMOxlAtlf%uD@+&@jifI;* zG!@(66oXl!f8OU$U2&1L`-LyvBQZWe)`2s_iVtOq>63GwW#%0%;QC~ zM8!7b>Il3)UiOx#*oIuclU$>3oDb{Y^)VGHwjtNUp6%~Y_rM71{LuJiTN+1uqZZR{->@JhN|rj5NNBk@W!zf2pwl96~N z$BSOcO|N9ET~a>GZ}aLvuSCT*JZ_%0E|+PeS29+UMKE6F$5KqMWMEI6?s%CudL<+A zN_5PD|*BwmTQ%p1Luk$5HIGH>)sM&gx-%e>Jm8Hrc&LraaFXY@)2 zdP~;X+*pO^m8jSTd0R~u@8^PEiHdE=^}IE&lk`e%dL?5uS$r68m&?4-D;e-gx?JXs zUde!0(&aL5^hyT2k}j8dqgOKEm2|nx8@-YNucXUm-sqJKcqL6Py^@<=$v|&Omy1U? z726;e%QSfZ{H0f-VjFU!ywNLBu?@LV-nb{uO|N9YE9uTJ^M*ZfjsdS^jlOZ6q*rp& zD;e-gx?JXsUde!0(&aL5^hyT2k}g+&XX_BXk^!%z$)#6v(<>S9O1fO;jb6!sSJLJ3 zev)3vfLGGx@_v$D$$(eV-&x-1l?-?#O)kBXn_kI)SJLG&Z}dtA zypk@Ld81b{;FWZ_%p1Lu0k5RXW!~tO40t77F7rmOWWX!wa+x=JB?Debm&?4-D;e-g zx?JXsUde!0(&g&!EN}Em2E39cmtM(DuVlb0>2jGjdL;v1NtesK(JLA7O1fO;jb6!s zSJLG&Z}dubcqLsf^G2^^hgZ_&GH>)sc6cRSF7rmOWQSMMhRBS`;B7OSa-Q^;0Dz+h4SG*5g&0A}{ z$eW67$X%rO$E)+k=K*%fp7fR+8|@Mm+i<+P;=Mm!+9fKsAy-Er;397-wjozXAmCzs zQ?U)XE4iPJTQkSYqVnU0_meyPk}enP+e5!(hhNgn1^tqTe#xHnmgqcV-sqR??w73a zeg5;s#%*yP>Lt7DC0#7jM!RHpyQGPwT=GyZ*(14Rqg?V(F4>oE@Zscbo(wE4c_^3c zkzBH|wB(^&vO_LuUVK?v@=z|>A(wQy3>)Q=-Q|+{l-xLbDVIEyOLmt_+FXW>a>*Xa zB^%|EhjPgdxuiS4j2q>W9db#N%hHmEa>?#;Nq2rJmpqh9c9%=qTrO^uOZK%*%7+|x z=YfkG<&r&;ORA#A7B|WzdnA`sMU8WLGa1Px8#l#yD3|P!T(WUfoQHDBUT46kn}_ak zBe|q1YV3TVT(U=UNmbN1mp7BirZ}o3Vcsa0 z>`7^fxH@lqyu6u&T+&?USz7W?F4-ZMG|ykkC2F<7O*Q0_E|=>Y<&qt8NtesKQ7+jb zmvp&Y-zb;tkV~3e$|Y*G;r#l;TbGNMC2F-H*Y790T&{1FOLoX5T`u!Rxnzf2(&g&! zEN?6=*&&xS^TyH=wc22QA(wQ=i?#;Nv+O}=b?49eY{-X zTrO#I`TRz?WQSbR%mp{ac_^3ckW0E;=8ba64!NYuW!@;4?2t>kT;`2($qu=sd7e=& zc_^3cE|+xA2X2bro8ml_OLoX5T`u!Rxnzf2(&aL5luLHVC0#D_M!95% zT+%%sxV}*?*&&y7xy&2ok{xnMcOIBG$|XDGlJ0n!H_9bDF6nYLUzRt@ zB|GGj=KOL~oQHDB4!NYu)xXQfi~C8n0oeQ0E|=>YLW!@;4=y#YAmwBUH zqTgXgT;`2(iFTEaxXc^n676zp+}?4kiW)l~D3@qAPviEETUFFJ7te3nwa~cT@#^oK zi}#b-r7q%feS7e+Tf0z2T;`2($q~sV)luW~fcGW(z8sC$^QNl--cKG;bxF0F5| zkV}rJx}<7qoC~=`uZW|0@VsffkW196oNytRh>Q0n$I=bn{+?AuH9il_+tLjJuIEkT zW!|tUPV@SJ?h8OZ02rd5nK$?)T`u!RzvO^l z(&hU4rtvawkzZ0(HFn*hUvfl#NmbQ2mw9u)q#g{gNZ{O9nQ@(c2N`E%HkSHpLN_ z>zn%}-FbjtA}-fAFE43x{r#l4%$t{&w7JY1{gNZ{ORB2I&j;o$@=L0!#<|QJ{F3JV zFZ>eCFY^}pB~?{pupn%6VZpzpM+o1Js)^KNx$TPU()6Bev*F45&0!mRpax(yt!Y}Js;qg z=&J(Px5zK4su~|J^A`CfRaN6$<}LC|s;b7h%vs>ur_Teat>#5h#v9IoJuCKD< zdg{fsuYhf?r~aiME#bKNQ)HX#ceUbr>NQ>+fna_;_2PQ!#a+4i-Pfe{czu->*HbU9 zeUAaDuYUT?zkR`pmp8J6ZO>j3ig8T*3jc8| z%JYwA6j%7yjw}4@@+*9s%VQ0LP~7NP;|j0w@>u&7zCB(ZYZ!zY?~fkqKQzBE2sK{6 z!i%f4y?<`v3NJ3Nt$u~?&ciy|cCCUzsPRVE)^)U<%WJC}gzfS2+6sg4b-6*<=JMJK zgHYV)+PaRm%>xWVao4@s+t;dfw4KXqs~d#vdEm7b2BF3qU0bp3*-Jt(u4ir#cE<~Y zP+aEC4Z=3p-x!F?ytzTx<}zXnwX}6=~{9Q-e&tI%> z+U+RfGH);lHQp$1>uB3}VGxQNt#9jSI~VJlb~}pZf$JL#LX9_B-zGLbdr2tv9Ba3u zV7zl3ZJ!6^P1_wsT;>h+RGNn*ZxdUeX&#U_?RON7mwAIh_|kqy5tn&GJ(ajg-X=Cb zdr6hT`B3kS-d*1&Ha`;=>)Y)HVe@)6vH6*}%v-%neSf^jn?9j(9-_R#Ak=u7H#Z2o z^MHCPahW$a2-{rbO|Skq4^iG=5Nf>4n;V4f@gi>$iZNa{2-{rbO+qobQQlw>z9bZr zo2+jW2BEmjTm8%5&IJrYahW$a2;1|^yul!RX}_c7IthbN<7M95AncA82BEmjn;V2} zF7pP1Q1cMwZTp5G=Ksx%M0pLBz;I}d265|?>%gRsrT^V`91KX>%)XY$+6!EZlz z^zCP^qwU9yd5gaNOf*z!e!0Fy-+m?J2}Wc2N4qM=HH8}k-@`hN{=?24S1a^$iB0xY7Eyj<(GM3_@|E`^j~*oy)wrLD-%Lu5W0l z(s-lwZ5?eNFZ1RGVRyVR2qo4sZ*CB_xy&03Ld`?;ei8@95ZVvn^%&1K$T5Q-b+Z5?epf6-7SZgfAnj<$2TzPUlzo(JX) z2BF3qJ-?x$>UE%@O5Ess01QHL`TXVvVRs(TP$e$&<_2M#%euB3N&@Z_ozhu%ckx-2HC6Qk;*U|Rza(#>Zl1aZr zLNUi1<&A!cgko}|^^JbXLBHgV{E|t(yG@AxsJ9UH|8z!OC}nsUI+b>JMv2= z{gQ)z$sPG6lYYs8hN_qLJ4)Ugt)p%8OTXlf{E|t(2#^{Ss|?6mgNalYWV|Jc_u;+eyDfTOLJRJindv zOPC`Xx`~ zmt6EqPWmO<@+dlP%p3g@ZFv-NaX)#|FL@%rnmQNpEPa?&q( zBERI~Z;Ma*B~Rp+T=Yv$`Xx`~mt6EqPX4x7TOLL8%e>Jq(UwOMmwBUK@Ngp2#n$Uy?f)-vhMeQ8d5I8~qY(d6aPJmz?xVp2#n$Uy}Pg;Qizi z`6bsn+RnxM$tUtl>X+osgdBYB98gG<0`Xwj*5^Z^uj2Angy-xZiPvnboY(>F^+bNj#r~3$e#sO0B^UjYlYYq)`6UMyzImz?xVwB=DU5A;h;`Xx`~msDGg<&A#H6Zs_<{gRXY zB~Rp+R9lUYm+M>PmsDGgap{*lkzaDrFFEO#Jds~gZ8bh#KEFkN$wj~9q+jwxeo3{} z_;}%SJ&|8hZ8gs2^IPPXR9lU6`TQ37B^UjYlYYq)`6bm><6K|gHf?znG6IM;nHaihG^FPZR5#EtUC{*np5 zMBFHE>uCEtFmI7xQf)QPW!@scuB5g0KY`sC~x#jCj1g{qrA~Cnea=*jq*mnWWp~IH(KB5 zm#E-|xro*``Xv*7$@Yr;l4`5*^MUJIs#cP-1JK({1S~f${YQX3BN?#C~x#jCj1g{qrA~Cnea=*jq*mnWWq1m z)C88SL+me^@Jqyv);Ibk6Ml)fQQqj6O!y_@MtP%OGU1nq8|97tB@=#$xY7DXzhuHM z5jV;k{gMg4MBFHE^h+lE5^-x#{Lo&++f{|{F0mfB`UZfH_99Rk_o?L zlR=kUAJ|_q;g^UT<&FI%D!Ac1M0sO>i3)DWjq*mnL!~f61mNujKs24rnhG++e(sUvkqgQNazlQQqj6O!y_5hbV9K zOD6mhaihGkzhuHM5jV;k{gMg4MBFHE^h+lE5^-xM!#gDzeL<9Z}dwh z{F3bz`6V~~k_o>=+-QBHUozpBh#TdNe#wMiB5ss7`Xv*7iMUbT*3q`>B>WO_qrA~C znea=*jq*mnWWp~IH_99Rk_o>=+$eAKOD6mhaihG^FPZR5HWjcZ>l^)&3BN?#C~x#j zCj1g{qrA~Cnea=*jq*mnWWp~IH_99POD6mhaihG^FPZR5#EtSszhuHM5jV;k{Sp=2 z;C?6aORBBLu4nK|G~Ot0^h;E5gYiaw$<6)}72J>;<&FI%D!3sx${YQX3BP1}MSe-O z)!1=Ee~GwJ-sqR8;D+-M<&FI%D!3sx${YJjRB%IXlsER5sNja&Xnmt!qJkT8qr9=d zWMY4uO&`*e^^Jas3T}M7`oI}+b+qmLrC*{CE)iEp+qwAOtrx%%S4Z2qcweFyT@jb} zlk`jUf+yfsTaAwwdDDYS#MRMuF7l=uw1}&t?Ofzd3sJ<6Pz~@=L0%#<|Q}{75 zZ8gqi-Xg!G+G?E3yhVOVwbeM6d5ip#YO8TB^A`Cf)mGzN<}LC|s;$Pk%v zx2V6Q+G?E3yhZ&b)mGzN<}Kx5zK4wi@R$Z;@Y8Z8gqi-Xg!`px2V6Q+G?E3yhZ&b5B(Aq z+~B$%^_NszjgOaki~38dt;V^`Thw3j&@WNJjnBh~{E}*`@$n*WBl1hCt;V?YOGf0E zJnSz~!42mj@k<`|m#E-|+{7=bwi=%YyH@Ke^7kiJ8HryaF7w9zl9Bi&;xcdSFByqnA};gB{*saSCE{Xz zyV+kd62C-T<_-JfY$NeY#O3-%zhoqSiMY%g`%6aRmx#-}vA<*_eu=ou8~aN};+IIu zX5QFeG7`T;T;`4aB_r`m#AV*tUosNEL|o>L{UsyuOT=Z~*k3XdzeHT-jr}Df@k_*I z-sqQ%#4iz-d1HUcNc<9UnK$;AjKnVymw97<$w>SX{aAr{V}Hp={1S1QH};o|#4iz- zd1HUcNc<9UnK$;AjKnVymw97<$w>SXahW&vmyEL{UsyuOT=Z~ z*k3XdzeHT-jr}Df@k{h09_EexB_r`m#AV*tUosNEL|o>L{UsyuOT=Z~*k3XdzeHT- zjr}Df@k_*I-q>F<62C-T=8b;INc<9UnK$;AjKnVymw97<$w>SXahW&vmyEF<62C-T=8gR&Bk@bbW!~6dG7`T;T;`4aB_r`m#AV*tUosNEL|o>L ze#uDu5^L ze#uDsOT=Z~=$DM7zeHT-jef~U{1S1QH};o|#4iz-d81!462C-T=8gR&Bk@bbW!~6d zG7`T;T;`4aB_r`m^kZn|jr}Df@k_*I-q>F<62C-T=8gR&Bk@bbW!~6dG7`T;T;`4a zB_r`m#AV*tUosNEL|o>Le#uDu5^Jq*^~YfahW&vm+X;Wq7Ui#&imkd_a6Br`d~;dzIX4DU!o5q zTKU!r+n-sqR?kzcaWFHyk_ z=RsGzV1Ai5`Xzhhmu&P)RB*%b>WcUNc^!4ivPXW2 zbPQa7>6h%0U$W6JQNa!7H}Xq1`Xws3Ay-ErIBv`v{gOTMOE&r?D!AczqrA~CQNazl zy5a@%!1axO$sYM78~qX$+;F^6-sqR8;D%h?VZ1*N^h;E5LvFOb(JxWK4Y|?!M!!S_ zH{eEo$wt3K1vlhId81#Vf*W#mhY=h%-cQmm*(1MXqhF$e8;&>18~qX$+>jfsZ}dx4 za6@jCH~J+ixFI*n8~qX$+>jgPjedy=Zpe-DM!!S_H{eEo$wt3K1vlhId81#Vf*W$9 zywNXF!40|5`bNJ*1vlhId81#Vf*W$9ywNXF!40`l-sqR8;D+2NZ}dx4a6@jCH~J+i zxFI*n8~qX$+<+VTB^&(`72J>;<&A!c3U0`a@jgPjedy=ZorNFl8t_e3U0`a@jgP zjedy=Zpe-DM!!S_H{eEo$wt3K1vlhId81#Vf*W$9ywNXF!40`l-sqP+^h@^0FWKmq zJoHQU$S>LGmpt@K_Q)^U=$EMAhVvWcjedy=Zpe-DM!!S_H{?cnqhF$e8*n4PWTRiA zf*W$9ywNXF!40`l-sqR8;D+2NZ}dx4a6@jizR@pH!40|5`bNJ*1vlhI>l^(N72J>; z<&A!c3U0`a@<6PwJi2Ra4zeEK$oZlpG zgMNt$ZorNFl4`5*d0^fmzogn~K5*q9F>jGyQf)QPW!@scq}pnn%e+N?Nww8DmwAi) zl4`4QF4ngr@=L0%#<|Q}f>eJlKpYS)z#Ix%vt2$Vg>yc@g*zx66w-!QGUsa{1WNX zZxLUzf-jLS{TAhytl&$eOTR_=B`fkvq)Wd=d`YF%*z-%iWRLigN~>{Q`Yqy1Dy_zK z>9>e4sk9o`rQf3bl1i&FUGgP+#FtcBjqB2HQGQ9K)wnMG7Uh>zT8-<{ZxLToX*I4( zzeV{al~&`r^jnl)QfW1=%l;PSmsDDf>(Xygeo3X(xGwz`@g9>e4sk9o`rQf3bl1i&_UHUD`FR8Q|*QMX0{E|wmab5Z?$}g$38rP-Y zqWqFdt8rcWEy^#cv>Ml?-y*)G(rR3nev9%;Dy_zJ$(QU=eo3X(xGwz`<(E`ijqB2H zQGQ9K)wnMG7Uh>zT8-<{Z&7|prPa7D{TAhyR9cPe(r;0INu|}eF8vnemsDDf>(Xx# zUs7o`u1mi~`6ZQBW4h!^_9(xk(rR3nev9%;Dy_zK>9;7qq|$0!mwt=#ODe6#b?LV# zzogP?T$g@}@=GeM#&zkpD8HoAYFw9oi}FhyPv>Ml?-=h4IN~(Xygeo3X(m@fH}J<2bsv>Ml?-=h4IN~>{Q`Yqy1 zDy_zK>9>e4sk9o`rQagHq|$0!mwt=#ODe6#b?LV#zogP?T$g@}@=GeM#&zkph%c$M z8rP-YqWqFdt1(^jC3}=#QfW1=OTR_=C6!j=y7XI=Us7o`u1mi~`6ZQBVyMMn&+60wKQs@B!|Mxp7?@6~QN6U4FPDn6e}Iq^rvh zcLY-gz?818um~Rq7Ok;GS65hs z>%yo5!6!Z4in(!J7FNqYa$Wds08HuX3PW;T_-z18>FUyN1XBirPrADF8^M$T zFr}+Yzwu(70WhVj3%}_Lynlcn08_fU@SDEmQrAJSt}gthWE|=`2-ekw-;|6)T?fIM zy0}RoDP3LqjbO?En9|jy z-xz!{0H$`VDWAMoUn9|jy-xz!{0H$RoDNS7jpD0j{egl}&)urDUd@=y0bam-B2A>RoDP3Lqjlm}aU`kh)eq->- z0GQI%rQaBQG61G@b?G;PDFa|iSC@Wc@W}v}($%Hk7<@7SrgU}bHwK>!fGJH~1fOU* zNxuP1>FUyN3_ckEQ@XnJ8-q^Lo{NmM{w?FvnZ@$o`uKveYit2p%`8Qwv$ICx_`Sv$2fAyPJU;p~` zo8SF;drSE|a5v$(V+nQMv4ql)eRxaxJg|h4u0LYZmC2vY3X`rsV$$_30_n=+fv!Jd z()BF@>B{7Ru0LYZ^(_MF%H)BrKVs7LErRooB~*9b{FN?U-y)E%W+157U+L$LC6shE z1A(r;(xvNLa?+juN)dQx^#U@PP&?bK-XXC()BGl>1qa^*ToV_y7U{CP|fE7 z*>TdP->`)0>e6pmLTMZ#zacwL_0n%xLUrq<->`%_?^r^0b?G-Op`;u64cT$$jwO_I zBflX#PP+6PmQdYspx>~BQoWJikR7Lb={GE)n)PA{C0+UrOQ^0c`x}-}8i%OAAv;d> zvcF*o)vZ^5_wXr8y7U{CP+eX64NIu=jwMuAmwrQboOC0J5IXnZwcEgUG_I*$7vj*{)X&0)l0u6Z0~s>J5IXnZwcEgUG_I*$7vj*{)X&0 z)l0u6Y_IC2-;f=5-V?T0y7U{e8LVCtdn2VS6~F}9Q@v4t zLw20%Wq(W9-t$0qoOJ28gzc3s`x~<3G!9XJLw20%Wq(W9Ue(L~hU_@i8~uJmcAVTdHo&D+GZ^(|5F8f=;_G%p1-;f=r zdZYe^>^Rj+za?z%c_2GZy6kTW+bdo6H)O|Y9HRb)>^RlS{+6)4s+au@*>UGRVSA-Z zzacwLx>0{acHFsx?UioiH)O|2m;Ehado>R1Z^({Qy-|NdcAV;Ee@ocj^FVf-bm_PE zv%T-X3rV`{Z^(|*I7Iyo*>S3u{SAn2^Y;+4(7&9ZN1c$_1Cv#eYvE}-1!aV`(;8`*5BTe_1$jCPNk=1eX*p^+2Bu4-+b#< zt9iEP7JF~1*49d0S$}n_TDr`)-nz2BQj#oP<~wgqS!}#XmM-&+x2~-I&c~K6^L@9j zEM10eH%(dMvN_LQEnVijZry6>GHkjnr*FD-W$7~Pxk+{^J?k=Tx#`*?y3DuSy4BKU z*l|;}iOaCzrfTUj-*9`V_K);gUBmeH+i%|6Zf|P0?LK=e`s3koy3td*@&5VFC0YG9 zxU73hvd?!e$-1Xht#>ZTKJO{Xx~C-To|5eIolCOrDam^0x+R{Htb0nb-nk_Eyr(4V zo$E$VN!EULJUpfEUlmK%JtbNH)gjsEJtbN1T#|K9N%r~mp=7;tN!B};WS?Ij-irA! zJ75c2vWd&EgRN@mGT*^&P8l|^B}GF>|Wna z-@We2(q-7ZmTclO>|NhB>|IMXaT&I*B}g8gP*+q^{d~1^|sGg-8SZuFF5{rJCfs{(#2bKK`yy; zZNBT!&~&_ z$3Jg7@4a6xyjqXs_@{L7Ze4KvQ{!Oo*7i7H3A5n%=j}+2f2v-*T^Ahxl z7rz+}9^$gr|Lz2Q*b@&jr=xe+ujd2 z{;Bbe{Dxd|jRXCb9RIxSbGE%+`Yk#BDP8n81=n+YqyENw?-g7R-Q@VE>P3H3a6NUS z{x)aZ#uvvwZ%1(X!dbgFra{D!j&s+WHAZ>Q~gxt_$w)7#-6Pusfm8@`@OH|lRVyKqx*J)SfF zeA=#;e#7@u)f@S3&bIj&A5f(m`3+|mG!FEee?jez13sZjmwxllJ#Ag=mngWN^A`Pn z;|CuF*Hbt08^8D{xSqOEf8!?~1=mB@KclwCmww|npQ72H-!I`u9|hO5-l)IvtB-=~ zsT=u?pM4ZuPu<9G{O+URdg?~~4QCf_3a+Pa^!trpeiU3!-NPCLU*#(UQ z{pR0(y1wAY9|hN=UjO*h)}`P0^`~g|=lzDW3pWMVv);&W{Qjfhdg?}g;|CxG*Hbt0 z8_q6h9OyUy0@R&1egaZ(J?oA9hO-N*mwv<9h34-IoL!JE{f4s(U0uz#txIrr;Z`*J z^Up8NE~sAm4QCg+_0n%RyKpO-J*bzz-*9$8x{=>-cHySrdOT-1yU-m6t|xJJLG?y{ z!`TJZOTXdlLbG0+U63yQhO-M@U9Kl_c0uD1^*5YdP`&gU&MtK8rQdLNLG?!KNt|6! zz4RN-E_Caq-*9%}Ry6zbe#6;?n}X}%3!Gi(*2~{-IJ=;FqyC1o3#ym>4QCg+^=h{5 z{fn~;syA9s;_QOzrQdLNp;<4^E=ZUC4QCg+y4)|p*#(V5w4TJ-1=Y*-B+f2$>($%U z=M8>4lX&sl&U^0_T<^X(lX!9IvcHipIU~MgCtsrcdDa{GjeLpn=cya@H{N@{k}o+U zzNEtB?Rg+yaz=bfg~_`v{B}lsNrlO~F8bRU@g)@|@4E2Y8Sy0*ChxlRTf~=Cn7r%K zZxLToVe*f<%Ad#c8}TI-ChxlR8}7aDz0WF4-gW6W+xA5OAYlK2PV zNa^|_RJv|b>3UO~|Er_xKl-HWCY7!?#jdWKRJ#77PrAMcebB|Ed}Aqu--Q$Y`489j zr0C3x|Kd>aq`#4u;indQJ3i9&$zC|w(hYv$OV=k`x<1*`^~r9%F{JC0EnS~%>H1`M zb$zm>>ys^ApX{bCcCe-Ezc{3;8F==W;vzuZR@&0_H?nktU-;7XH?nkn1*HES{Nj+V zX8WOoNY__D($x$ECvNkjQ8Ww_?j|b z5O=4{TeudSzC)oi?6w~6%F<q%MC2Ci~#37rQPuoU_!f#(bqd`}}H~ z)9d|s&E|LS-;dX9{?|CrZ^=IRqTk(o&baH6?1M`ee*1XM<{#z_8#CISO#0h~bC!$l z(X;Pl(zSJ6cefYkET!ukGt%{qndUC%{P!Q<>mRS#{IBPMe*1XM=6CCohRRWJR9JEEF?!#T^3*KGdb_uGPVmYTO{J&ALc8egs_ zlXI5Zx5RoW%z{bCz?b znByDuH=MJSF2CX>=Pae7Uk}zdanAC)?b+vlU(DHdU9KmSbC#-?>q&0Jf4pY%55K#8 zFTU$HZpJU%jQ@De=6{W^?Z!6f0=^vOSYj*3((rq|VDOqz{SC(eOflA4m+1i6kv*AFc zbj@sCT^y*?=+bO{pt7w?v*AFc>NT^qb=ll-pi;VKwzjV3*P0LxR7%&)Hvd=S>BWIc zjW5mS2P*6HLPwX)4F@XM%`by$>$17wK&5oeZEaoJ4F@WvYj$hv(r-9WDc#6#xC}}; zw7xMS-N7^{f3i0YehFd|K7pL9_8ZG zZw`>O>!sfSkf>hkZOu(dN{B%jKr z{7AcAwm0x2$_brM?9;Cu@FS|1?ald-cD=M4_z~4>cI)bbA5p#Zo9A@5b$vA{UHZ*) zy4$++8*;ie4$*QFIo+z4?ald-cD?i)_z~sC+7Gw3F54UU5$Q&L13#i=HvQ)ONV{J8 z4g84ejr<0FMD@~d&X2U~rQg7hsNTqL;73$1{pS2gw_flg(xu-#r@O67zaghv;}H36 z&bIY=@FUXo{-!!Q{cX;+>$1OjPIr48=r`naE2lZ~8*;k!^OJsaexzM5{RVzS^+tX} zPPgi%-#n+gT`&EHoNm<{`3*VUs+WG7l)>|T9{h-O>98Nht$Nwt za5HPuZ^-GEF8${GNcVX_%87Kjp2VTfZoT~ZMy6!Psm`u0{YIu_2UF73<=1fUjm;H@Q$sRE!iectB z&~MI^wCiPmBU7?FQ_|L@-^i5g&Xlxu={GVZd&HC|h8g2aret@fq+KulMy6zUrlhM2 zrbO5BvA;P}($=Nl$dv5Pl(cpAezNr$nUdX^lD01WMy6zsm=eV>vtIfwVoFvpC7L(( zH)l%P<3PU=D%l+>Y3tH&q)K+DO4_>g8?ll-!b(=;bn9~lKL;~(}5#c4wCy_4JlOw`QwmI96>t6*U+4*AKr>7ZsH@?lY92!sg_mmr^{t4qFw`6QY*z46|SLtB@ABVRJWmo)u` zd*Jmv&~M;Ny1M9Z3;B`(zNGoyAz!lK9(dgc>HV#%OTUpX8Q@F0y6kV{O9uFot}go< z`H}&?q^nE6kuO0$NfWK!kWaEQpG5QK{jFIq`I3cv$pBx{)urFamyC!n+2(B9d!2mA zi1?C?dg!v@8H#h2U&b{O*~phHxCdVM2S@#F&bGaG$d`q5R{M0|-tp*g<%{TA^h8~GCElju2%{D#DEjRXA_@g*Dil7)Q9i1?C?e91z- zWJG)kZ_&{>u)jro32)I+*a-Vu#Fy|E9qID-Tf~>}79HubzeRk>hI`pQA!e4~7M<>Uea^P)(r*!8 zQVBJtOTJ`8d`TtLxGwz`@gnF8PuX@g9;7hWFud) zkS`e#Us548UN8L?@g)^f`4}4pf`z7Q{jwrfh!~HipmJPoh9$nI|m*3yWmmHp5($uY(8hakdmmD5m z($?ko0P-b=rxGwz`@gta25czj8dQ>d^S z*F}FjqWF@1&bI5Kza0@@vg7`nRbVlnv*i0*h1Gby^jpN2R9KDc(r?a}bl+#>O9aGV z93sACCto5^fx5<*wClz9ZheTP?)+l>^!tJFCHg=_UH{(Q<0^LYCE8e~Zu0$YXMTw` z{HU9J52&yjd(Oz091&l#&#)TTrQg7pbjMe-?Yi_E_>!(J_9wNF!uWzO>FQ!VsTU7* zr_$5UFYdotSMntX_>ykD^c(q-Bg!wSv>KZ?=9e7cOPckPFHyh^$2aoZoNcd{ev9~$ zoqWkkzT}Abl1i)bdg-@_FWJeLtmI3Mh%c$M8n2gri};eA`6Vm)k|W|vcJd`F`H~~z zODe6##({jv5#^Wc!G`iQ<`2FZhz?dy;&Kf@rC$H{SDohMw08}&ExCCU|{ZnT~xU$T-fIU>HK(rSEs>9>e4*~yoz zvuW;;cG{gn5hjk{x&ANSA(#_>xMiv2h?@azuQ|PQFC^EXN`G z{YJh-yd-razcIf={1$a1zcIgLC0}wxd`YF%_`K0?5nobiHLlD47Uh>zT8-<{ZxLTo zX*H%xzT}Abl6}%du1mi~e96xIl9l--N5q#@T8-CBzeRk>&ioPu+`tzRUs7o`UN8L? z@gHK(rR3n`;!r0QfW1=OTR^Y$C@I5nr-1zeE8y)Q$QZ^GjA~pqVmwt=*lAZY_ z3b?`Z8}TJO`I41<$r14-l~&{9K)*$NNu|}eF8f==msDDf>(Xx#Us7o`t_#1N;7jJO zf)D4US6Yqh!f&VZCACY}(dG95@+GJ9C2d`-d`YF%xGwtJ8Sy2RR^z(pZ)e1pR9cPe zVm)~}U()>UUuiY2OTR^YNu|}eF8vnqC6!j=y7XI=Us7o`u1mi~d`YF%xGwz`@gMl?-=gbr#++@}rQdKpPVak5rPa7D{pQ!>bbUd-L;*K=pGEm4l~&{R z(r;0INu|}eF8vnqC4+p)#{7~q;!7&6#_OfuBEF>3YFw9oi};dCt1(^jB`5Mrn$Iu! zl8t=H8Sy29_v38jOU{Tdsk9m&2l_4IODe6#b?GOqYDg8Sy2RR^z(tZxLToX*I6P{#L(K zp5@Oft;Tifw}>wp%rDt^Kh7EPC4>1T3b;YvjQEm4zC-~x)YS^(X|AHuYJ7a@w}>yP zv>Ml?-y*)G(rR3nev9%;Dy_zJ$(Nkb{Wybs$wt29jQEnl{F04)$rzT8-<{Z&7|prPa7D{TA^hl~&`r^jpN2R9cPe(r*!8QfW1=OTR^Y z$sk{%fEzq#5nobiHC8YAk~88<#++@}Wq*tKl1i&_UHUD`FR8Q|*QMX0{E|VwL;*LP zx8(cVAYY<@8|p^=ZO*oj1N|29C4=|lDBuS5MtsR&eu)BZsGIPUW6rjX1No9O;!6hk z5(V6_-sC*aAYY<@8|o(KamJi&9|!s^;!7&6#&zkph%XtFCURZ+E#gZmt;Tifw}>wp zlO}Rq`Yqy12JgpFzzv>(Xx#Uov<PCKJeu)BZs2llhrq!4)m|t>6e90hRqJSIL8}&ExB?`Eq zZsa%eB?`EqZsa%KkE4Ja>PCL!{WuD^p>E{2Iotj`&~Fi6GA2#ry71c_d`WZvm-!_M zxbbngJ73cMJ~U|}tCxJq-T9KXF8xNn{Q`0XC?C6!j=y7XJbmsDDf>(Xx# zUs7o`kGcxDfsbpZo?S;(T8-=C_uD<Pc8~aygZJYo;D+Oy z^tXfe<0#;Ux=DYlv>G1=`Yqy1Dy_zK>9>e4Ip%D;F8vnqC6!j=y7XJbmsDDf>5?zG zM|?@8)wnMG7V#yOR^z(#Tf~8kKqJSIfMtF=+ z=9kyPv>LCM{Vn244)P@mxM96fe(e^8M`~U!s5;>L&Y>2l8_K@*DXQ1>8_~erbC8djR8_KT2GQM zQNRs#qxB^D5(V5)H}V_#5(V5)H}V_#5(V5)H}V_#5(V5)H|lTXOB8TJ-N8_K z@*DXQ1>8_K@*DXQ1>8_K@*DXQ1>8_K@*DXQ1>Csq74anp`4R=(P&e`$`4R=(P&e}1 zOslbV3Hg#M;!6(RkE4Ja)*JP=NfUX!@Y@BxWd183-v6z%8rOy2u81$Gv>Mli->!%+ zsk9o`h2O4-FR8Q|*M;A%h%c$M8rP-YBEF>3YFw9oi};dCt9jH_zzv??h%c$M8rMaC zyCS}%(rR3nev9~$N~>{Q`Yqy1PVyxRxZ(IF{p}=QqJSIfCjG6_YJ42%w}>yPv>Ml? z-y*)G(rR3nev9~$N~>{Q`Yqy1Dy_zJ$(LLaUvlz(90lCqd5HLulldhIxS?*+-%j!+ z3b>(evYtH2mnh(dx{=?=mnh(dx{=?=mnh(dy2*O-BwwO{8|o(O$&-AE0&bui@g*nu z5(V5)H(5`f`$KLOB8TJ-NCUS$ZzCJ6mUb`$ZzCJ6mUb`$ZzCJ z6mUb`$ZzCJ6mSFGh%Y(Gmnh(dx{=?=mnh(dx{=?=mnh(dx{=?=mnh(dx{=?=mnh(d zx>0{4U!s5;>PCJeU!s5;>PCJeUoyy-T+#hFl~!ZFTgaDO(fv3l`4R=(U>qX88_K@*DY*LB8aQ?#HRL8uJ_Zk}JwDImwqO;Ks&5_hH-u9`Ph!GQgKeH}V_#k^#O% zx>0{4Uoya#NH_8u`H}&?M7mLbBVRI*Un1S4zg1d|J!iNdN4kmMDy_zK-EY!O{8ni- zuIuYb=_c#RN~>{QUr$OmSx;74jqB2H5nobiHLmOZZM#K$Nu||1>MGy{?}vylsk9o` z_5P-M6TekjjqCb)Qo4!XDy_zKeLX4N$ZzCJ6mY}wb-&Gj<-^~H?&M1pa6{e5Z*#VN z9O$=*FR8Q|*QMVgzNFG>T$g@}_>xMiab5Z?;!E!HHYC#pU$WgIzT{56L;*K=9wNTv zPQF9|H`I;%M!rM=H`I;%M!rM=H`H~%&DBK1Z{$l9a6{e5Z{$l9a6{dwzmYFdzzuc1 zzct@GiYrc2pZ2R*-zeRk> zoqUM`ZcuN;msDDf)eF94yG49SrPa7D`&-19R9cPevcE-q$(?+O0&Y0Ik>ALdDBy;= zk>ALdDBy;=k>ALd9N55r+)y|28~G9i+)y|28~G9i+)y|28~G9i+)y|28~G9i+)y|28~G9i+(0+t zOYY=L6mUb`sK1dfIlz}}wNwL;*K^9^7xU`o=yC`4R=(P&e`$`4R=(P&e`$`4R=(KsVw`?&M1pa6{e5Z{$l3 z@Fm-A5(iJ`m)yyh9Ne;7g<%`Hg(Z0lq}Kk>ALd zDByNw%Jezmnh%{ew)O> z^Y2OWB?tHt)f@SZ`6UPV66r>MBVTfmFIghK3Y94hJa04GZU($Xa^mcV!>`yKc zUs7o`u8aMWCE`met;Th+U$R7e$wj_I0XH09>u=3|e336vzzubi{&tZsQNRs#lm1p| zH9o%dTf~=KydOsaH>lV7lJ4_6XWQ$g-y*)`B446_8`hhwCol3P3b>(evYx!imnh(d zy2*O-B446_8|o(O$%}l60&b`q`Hg&u0&b`q`Hg&u0&b`q`Hg&u0&b|AtS2w>B?`EK zF8Gq(@7Rm^B?`EqZu0x>B446_8|p@WBVTfoFIghK_>zl!i2`mo4w2u; zmnh(dx{=?=mnh(dx{=?=mnh(dx{=?=mnh(dx{=?=mnh%{x)EP;kuN#Pmn;!qa?RV2 ztZ$MpSt7pV;{7-$?#J1dh%dRAUvlDp9O*{=jeN;TzGSJD$oDzZ-E|515(V7wd5HW* zzT_ldvP|OO>HU&QtMTW7ev9~$i+qU!Za5B+-^iCJ;0C%8Uvka)^>JW-i}Fh@@+Atm zVZBj*BVTfoFIgsW5IhfhyV^LAFIghKA7n z%x~TI1NjmK+)y{_Z{$l9a6{e5Z{$l(@+C{emt4#*ImwqS5npnVFFDDVEYbZq7x|Kt ze902=B^UXUlYGe%-H&sTFFDDVER#5R-WTLcPVyzoBn|>y>`yA-2G8##4gy`hUG05F zzGRuiL7=O*tLxHllQ;-;u|Ii|FIghK z_>zl!$w|IsiTIL>e91|^WQq8ai+ssRzGR8`l8bza0&d{9NgO=?JdiIr$(JnA{Wur- zl9PPNG7~L=dg(XvB}>GYR9cO_AIO(1lQ;LFkuN#Pmn;!qa*;1N$(Jn7 zmvr~nnO|~}FIm8s%x?GL@8}o#l9PPN67eM$`4R=(z;BZ{c>Z}HUviQ!St7pVB42Wn zFIghK0C zI$P2$mtG@UvL{R-GU%j{9Q@Ple zRIm+o?K?oXTzE~nHk1vvNfdShuPN7ty0eviKMc)sNtGzphO$9lQ@QY(Vr{5vyCmIm z^>>e6Q>qPRgCA|*Mbx-1z2;C!w_I3Fp*ASjnUbz7okpZ&O(IJ)3bY!LlGP(iy5-Vo zBuduF7`%IQyACE%qDUK#u34>FE`bsy+ECV<)-9Jni4tw7YgX%)OQ(@1Stnue{OFP= zQJ@XWjjTqVM1eNYO?VQe^w4YMN!BEh#GOS2ItSreQ@ zy6kJjN!AG%JpY&xC%F?RStno+=wcChCr+|Xz~G&3ZyQ-*FSHwRl63+G?{vFw2jV2k zv!N{_yAdZ*o(*(?lgwHC;15iV1MNnfWKD1q>C$e*Nmk$_-FoRa;v{Q=lc-+$jX24g z;3U$e--wf}^~8R^-s?VR#7XYNN!Hq8cwU!&BTlj=ILUY6G`2EhT*;c?B+}J;+I8u- z2^c)@W8x&rvw`0doJ94~Z;UHh6P!f4^c!)KHMtH)y7U`yk~P6eq)WdMCs`AmM7s1F zagsH`Nfe&K-)+Q6)&wV!F8xNFWSxM)^Up7F66M+O`HlJ;agsZ6l63+GLA}@|xf3T@ z6P!fjOTQ5(SreQ@y7U`yk~P6eq)WdMCs~1$H2WrTk~?vdHNi<#Fa1WGWKD1qg|g6Z z#7Wi!C;2X%#`*ej`q@0w>XP+4h$F(r?5`)&wV!F8xNF zWObaR+m9Jna%Wu0>O4tTmq5v#K*{PrNn4kGBT%v?aU}{3q2CCUtPYg4>!sfal&lF* zqI%ii7+0b%waM>7#+BSjl<0F;q)We%DA88A={Daxj4QblDbbdo={EZX<4W#~E78_R zq|5$BrbIvS0^JIyvEMC>E74Lm(xu-Bm8fM$y7U{N620;wUHa|9?>AW|(xu->m244J zQsFc{Z}`-`MN~&@b&&GcTZ1o0vcE7s9XGXz-C|9Y>D!0sGIb+g>fayv!Sm0ty?epoAPX^ z8}&ERCCam*Zsa%8B^T+EZ3b98?5{W9JB%w)o(=1b`Wx{Q<=Id->TkqLlxG87$4llz z_ut;Sv5JLw$wj)UA>;H zy%8_jBD`cFUUCsH*?^aH>(y*qy~Inl2rpTPmt4e4wg@j-h?iW%OST9vS%{Zh#7j2E zOSd86MVyri;eT$k-F!b>Wf#&y}=BD|!sXcc*#P%L~%BF&LX^IAzq?58|p^ON#Z3J@siE)lCIx~mnhDL^+x@T zc!}a{s2lY+;w2aHk}bkZDx1ciGx{yUODdbjb?LVVFR5%A(Wf#&zj8$4k1;FYyw^+2Fks;U$$#WAzd**&@7TAzpG3FWDlzq_SzeUiP;LFIk9} zT*OPZ2rsE@8n2gr176a6?+`ChoDH9csJ}6-5*Gs=ecu8f`m@e^> zEy7C{;w6f+;W$K}1BjPg#7j2EOSTkqL z6lX)-==U3M!%>_Kb))@B;w6f+aos(_OBUiK7x9uk!b=tgmR!V3cHkw=_YU!ri+IT% z;U$$$WA6vzC3}RIR6338!f$(omsC29>%wol<0Z}aL&ej$F8sDfcuB?6xGwy*M|er) z)3`4DwnunL<{TAUR6;R{4=x=+3msCK_gRWpRe1F>`yrdFpTo?UqkMNR8sBvAa zC->wwoUI~iT$g@}@RAjHiN=?HoA;wU{oSb|YP??hZ2|{@uHL7vOTR^U$qKwg<3PVf zc*zR9M7s1_gqN(i4M)24o8u+j_att^5rj#z8CDNtekXuPGc*!26msC)V>(XzN zI0(kUzjtdK=r_kpy3ZN-66w-!QF_S=zC>^`{pRT9>e4S;3b`mwt=lODe0z$ANzH_>%6tfiF?L>~B$gNrlyTz4TkemsD7d z>(Xz|m-KM1%Bpc$+RgEjuB_gzCQG_xkLZ$$s&QSq&FPYEx%#Q@vTSY(XoyTvACj zu1mK?a7iWAm@eUxJ%URrsm66_w+Jq&q#D7i$dZbwv2h?-vPWb|#niYi zn_EPdR7{QQvbjZM$qKSW$3N+}h%Bj?8n2gri^!6Ssc~KU4Z$VNof42G8VC9{aZ0LKECkVh{zJ{y0BjQ4P;5TUj3cdOTU3E>FVNJfRb&z zZ;pBb-fe<+bgqe|)Q$($%Hkm|QZPEa~e6q#7-s-3>FUyN8`qP7 zOS-!B8!yHgfJ?f%`a6Ff=r_P6U0wQ(aLE8%($%Hkm|QXdmvnXMHzt=1z$IN>t|tkX z48SE#UBV@bw!wPR;garqhjfXeZKxalenWD}rf3`LY6hPFeL=cJ(Kgg|Qn@?6^cye6 z8K6tLy81iw8!yHgpi8>C^c(4t;dDv+d7$5jmkh^C+Pd@``H}&?q&p7u8!hB zF2+$@Ed2()q^ryR#*1+V_>!(J`x`ID8Q@F0y6kU*ev9~$%BeA5kS`hFOS<*y?_8Jt z4SY#gmwqE(GQgK~b?G-ImyC!n*>EwA_Ivm}0DMWeUiyuE$pBx{)WyX(s+WEPU((g3 z-b7vqeGFR7dw^Beh+0luVLFa1WoWPmT} z>e6rIO9uFot}go%#?d&izkx65jsyM1)U{q^qmHv;M~9k^_86SC@VxUvhvi>FTn-F}dUbU((g3-&N=Kx>Q)2*Bun>X?$2l$e%F8#)faSre$U0wQ(7vmfeUs5?WJ`U(_2l$e1z4RL| z#yKLsq;hJ!Ui7yk;!7&0=22JCHr_Xnh%c#}8rMaCJ0iZMa%x-`zu%6CFR7dw*9FgY z)Qarc@BTaa5=Gl^eD%hAdcUu7YP??TPaa4vX+FPmwp|zN$pgtHU0w7yMcZ&3^u`Ou z0e(}o4Rj;EWS_I`<3PVfe92C}MA0^^S2GZd1NxhyZK$gm2z1fkR`MlB#Fy+$E>W}% z>zz;5(|#jgqG%iHMt;M^IGdtvsH+(W>ZRYvmmCpavg2YL)l0uce94ZBaimMXMSRK5 zvtr<7_MWk|W|vDyPQYJLF4_h%ed6mnhnX;~V*ne920_ zeCfA{FWH$~qG%hAL$Y78<7OPyOTR^YN#)e|^FY5ve92C}WF=p6M10AP zn{hTp+hBYnzGR=XZR0?`Te7$ zQML_rqy9E$+vkmbi};d#&bI5)ZxLUz&)Ife`Yqy1_DK`DF8f==m+ZJ1XH&Wj<}Kn& z_DK_2z2r-dh%ec3Gmh$|-y*(bXLyOyZ8#2*-^iCJ-G;i6-^iCJ-G;i6-^iCJ-G;hR zey<$(JbJhV@2%o3riXOTR^YNoCczF8vnqB^6fVy7XJbmsDDf z>(Xx#U$Qg5L;*LLw}>y!G`i2`m=Z^W1E zlP0q9C0}wxe92C}L;*LfH}V^9#@SZ#B}c@U?94Awzzyq-`WyKY1>8_K@*8f((Kyg= z5nobiHU2!%ZxLToX*I4(zeRk>j+=2b4)EI<@g+NM#*r@kc1C>3j+=3G?h^YYXT+E6 zxEV*f@Y@;jCHtIhn>X?$XT+E6bGBUTo-;jBfg~4YFrn7 zJ0rfN(rR26emf(+q|$0!mwt=*l1i&_UHUEJODe7AQC9&s{{B59zNFG>T$g@}_>xMi zab2t@&xkLnv>Ml?-y*(bkS|fd4aYa>Z)483*Gs=ed`YF%xGwz`@g zl;AFj#-^iEfU>$Xn?*U`Zwm%Q_Tf~=CT8-<{ZxLToX*I4(zeRjWrPa7D z{TA^hgM5kZK*PL6d`YF%SiR&+&WJCmv>Ml?-y*)G(rR3n{VmEbsk9o`rQagHq|$0! zmwt=*l1i&_UHUD`FR8Q|*QMXUmrRQA!}~CmR^z(#Tf~=CT8-<{ZxLToX*H%xzT}Mf zl1i&_U9Kl1zNFG>T$g@}_>xMiab5Z?$}g$38rP-YqWqFUzGNd`az^5?xwBfg~4YFw9oi};dCt8rcWE#gZC z`I3!%$rBEF>3YFwB7E#gZmt;TiP-y*)G(rR3nev9~$ zLB3=oUvfr#Nu||Tz2r+yAYZbPFF7N=q|$1v zUh*YplwVS5HLlC`WW<+LT8-=S_glo5R9cPe(r;0INu|}eF8f==msDDf>(Xx#Us7o` zu1mi~`6ZQBL0Ie90N*mkjbH8~Ktm;!6hk zl8t=H8ReH$T8)nb{TAhy4DuxkxWRip;!7&6#_OfuBEDqI*>+v}E#gZmt;TiXw|m5w zR9cPe!f*G8FB#-ZHu5F+h%c$M8mpIl$vxsrDy_zK(ckV7Us7o`u8aP5kNA>Gt8rcU z?H=(Zl~&`r@Y_A&ODe6#b>X*r#FtcBjqAd1_lPg4v>Ml?-y*)G(rR3nev9~$N~?L) zRltqEC+`toQfW1=i~Y%a#FtcBjqB2H5nobiHLgp)MSMx6)wnMG7Tu3iX*I4(zeRjW zrPa7D{TA^hl~&`r^jpN2R9cPe(r*!8QfW1=OTR^Y$-(>*1>C@I5nobiHC8YAl6%CL zR9cPe(r*!8a*!|C$(P(CzT_ZZvXd{lPvYR|^Fs&u5(V6F-V(m#AYY<@8|o(KO%LXm z?94B@M|?@8)%f#3zeRk>!Tb^h++Z9czT_ZZvXd{lM|{b_{F0q~$vxsrDy_!Gm-!|4 zh%Y&qU!s5;j_=$-eKs%XV19`LZm1jijrk=CxS?+3H|Ccp;D)-9-ALd zDBy;=k>ALdDBy;=k>8kKqJSIfMt);{i2`n*8}TIv^Gg(PL*2-4KcZP%sWBEIBceu)BZFuoCAa*!`kzzuaLsr~ft7Uq}i1eL<^4GKh%Y&qU!s5;)*JOV z@+CX@l6%CL9Lz7-nO|~`_>xMivGFBea*z0ugZU*2xWV{Fe96K55(V5)H}V_vOB8TJ z-N(e1eP%lmQe5npnUFHyh^>y7-z{F0sdC0E3k9Lz6Kz>U{?MSRIYzGNp~az%W} z!Tge)e90B@B?t3M6mY|Fi2TO<5(V5)H}PAg)!6gP`*E&_FR8Q|*M;A%h%c$M8rMaC zyCS}%(rR26e!C*Rq|$0!7r)=Gh%c$M8rP-YBEF>3Y94hJaD(S8;!7&6#&xltydu7& z(rR3nev9~$N~>{Q`Yqy1PUe>=;D+OytS3+Amnh(dx=DYlv>G1=`Yqy1&Nz-+i2`mo4w2u;mnh(dx{=?= zmnh(dx{=?=mnh(dx{=?=mnh(dy2E_i z@+Atmp>EXQ$d@SKhPqLIBVVF`8|p@WBVVF`8|p@WBVVF`8|p@WBVVF`8|p@WBVVF` z8|p@WBVVF`8|X%S$w|IM0XNi5zIUJGOB8TJ-NNN1ALdDBy;=k>ALdDBy;=k>ALdDBuRV5nobiH9l|bZxLToX*H%xzT}GXOHT473b^4o zM1CV*qJSIfM*WR^i2`n@8}&ExB?`EqZq(n%mnh(dx{=?=mnh(dx{=?=mnh(dx{=?= zmkjbHSHzc8T8;aHev9~$lldhIxWPC?d`YF%SiR&+u81!=$(JbLhV@2%BVVF`8|p@W zBVVF`8|p@WBVVF`8|p@WBVVF`8|p@WBVVF`8|p@WBVVF`8|X%S$w|IM0XNi*e!r0~ zQNRs#qxB^D5(V5)H|lTXOB8TJ-NwOSeVoC6!g)x3X$n*WD)F$Ze!c6mMgXgLEUe zkuFiZ4Rs^8kuFiZ4Rs^8kuFiZ4Ry_J_3it^cB`x!n>WxU8eg+pTbF*jyt_#^>28%( zfN%Bpc)_nUN+?p9efu1mi~bV+5^xGwz`(Iu5t^QfzM8$4$bT~b*!u1mi; zT~Zkco#$7x?Yi_^M3+=njqB2H5nXa8U7~m!j&I~Q(j|(wp|1I@*ETDv#)pA+i{O%q zs&QS~&Eb-6xq7#{EZr8dC3mtV3b(=NMr_HQY>C2csGD@RJJ}M2+fX;@Zg;XJ3b&zd z(%tT4OB8NH-Ke{fEm61)btAWtEm61)bC2cs2ll>Y>C2cs2ll>Y>C2c zs2ll>Y>C2cs2ll>Y>C2cs2ll>Y>C2cs2ll>Y>C2cpc}Czcd{i4x1nzG>+MdqMBz5n zjr>No%pU`tf* zRC;%|yQ{0&c3t*2WS4Yx`RfgAiRyK~b#?W2^?KRga5qj7M=y1Mim*b?bR{f%tN0k%ZCv%+_N zn{WBXd!1~_0k%ZC(Rz|>$pN-Ry6(4bz4RN{66sE*r^kWWB?q!gr0afb)=RcT;WqGF zbT>{V)tKMFmZ)CuZ{2$7H?Sqrb-#6W={K+?`z>NiDyhcDf&DFFODd_xbitOW-pFrc zOB8N{=OM~2siYdOm%rblyK(MhOB8OydLzG)Em61)btAu#Em61)b$vbAe16H6DBOm+ zk>ALc9AHcIoJD>kTcU6q)az_X{VHhm3uc!b$S&D$5nFO6TXKLck#6KSW|tgbOQak1 zH?k!M*b?bR{f%si!fiNjk>ALc9AHaSZ{#z(M7rj;?)!{v$pN-R zx{==qmmGjgq#OB-*(D0M;d2)GjoBp%x1nz2H)fX{$S%=1M1Es-iNbBX-X)?-?#wPZ zkX@q8|LFG{>5_wV$r8~echV&ax8XQMej{CSkS7X=#ts(KD_>|q#DXA*btAtqyW~W6 ziSERU{Ko8(lYGe%@g>)sZF}z^yF_>GMe9jsmz?BFmWVI8m|b!ryF~T+eo508%q}^} zmn;!qaxuH)M0Sbljrtq;l9PPN67eM$`4WZOz!wo;axuF^;WpHb{Ko8(lYGe%@g*0t zOHT47OT?F4yc_2vU$THNX+FQ?OHT473;2?*F8dq#k_CK8SC{>be8~d7q^ryRM!sYL zU((biUviQ!S-_Wcb-A7-U$THN>FVn5?7dFDWC35&)#ZAUe8~d7q^ryIB>9pBd`VZA z{S9~H=x)}izwvGyh1=kL2EL?QFa1WoWC35&)urE%U7~T&3_QO+BVTfoFIgsW@VqYh zl9PPNGKqsgmwqE(vP|M2(A7Mc-^iCNxErTAZ{$l9Zo}s+T2GQMImwqS&X;ue!O54L zF)#3;2?*F8xNnWC35&)urFamn`5*y1MLdt}gvXzGQX2WNykdKBE&aQM!${i**7A?_R$xStW8Psm7jO(j}|YC0$vXjnO5m z!zEo=&4E{oy^Oa>ZCLND@ZE`-?$dykq=IdzYgX%Z%>72P zM8P)H)eJmeFLO&2Y(rgNNzUpU^EUsx9$lee8|vChvibP(QXJ*lP}UZbU0ImzPOfB4 zxDw48+@@F?l#ASwrYo3RqF5X1&gb>r)7#ah+n8Ijf-C9j(rx5Q)`Tn3_|k3UO4fuc z*>B`Z?&M0=c}vQ}_%`1T`BawY3bvIy#xf6T??O4fuc(fHDD)*?`y08E6k2XZAVxRS0e{YI{21y?c`!;SYO zxsp4%k`-J@SC@VxSF(aD>FUyNC0$+poy{A$k`-J@QFUyNC0$+iH*zH_xRS0e{YI{2 z1y|D5rQgVvtl&zzy81iw8@ZAdTuD=xT*;kW$qKHdt4qI;D_Oynbam-BawRLclCCcO zMy_N9SJKs`-^i7$;7Yo>^c%U76e6rIN>*?sU0wQ(T*(Tqq^qmH zGry55S;3Vwb;*_7$(5|&O1irA8@ZAdTuE1#ej``1f-C9j(r@HSR^*m+b?G;9B`dg+ zt}gvXu4DyQ($%Hk$d#<%O1irA8@ZAdTuE1#ej``1f-C9j>hH{NB~4v&C3kWq zE4Y%bF8xNXWCd5!)urFam8{@Oy1MimxsnxJNmrMCBUiG5E9vUeZ{$i=a3x(``i)%4 z3a+H9OTUpTS;3Wbb?G;9B`dg+uCD&h{6?;11y|D4C0BAMSF(aD>FUyNC0$+m zja@MmfQ)JYz~$*bt|RDd`z-rbF!qZOTQ5<*&Hot>(Xx*zIJb5OM3IR zkS$TLjqj&!&X%<6rQZmbYz~(+DTRf(B?`7dy`W1pZjJrPN~w8#9u#at-Kq5Mdv{kC zep9dwb@j%3(ABuL>V@AFY(w3t^nAT~ZhRa-muyLH$-a;-QLqi`)f?~mdP$ck*oL~A zfj}32Q?LznH3NYz`kR7ns5_neZr++co)neO8(^*td`VXq{p})OvVkvY`htAPMZRQ9 za!d4_(Qo8SHs?#G`99o+7G8^U5ii*sFX_tCZKO*!r%Rf$gi9{MC0hiSEQCug!X?|p z4IUoe=EK0yl8bQ37QrP8FU7eCmu!GbnlE3%B^Tk64RA?Umu4eevN>E*pOPC-FX57l zaLMLyNn4j@BV4jYaLGcrwlL zTbIp^aLE?IB^6O)O^9&G7QrPIQRBL7ZV_Bk5jC#M#bgAREW8xwB3!aXa7jhfSiOWx zwt52IEgrhhFBg-9OST9usfZe{my5{=E~$tb*X3d|f=eo*#&x-vjNp=rsBv8`CIOc; z`{tZ&*X3doa7kBJ&yDNSZ-7g>y6kU+OE$nI&F7bJiBfH_s0Lip)n$JpT(SW!>FUyN zgiAKSC0$+iH^LpX>e6q7OE$nI zU0wa1`HgVN2Dqf@H-?rd)du4WxTISzHYYE_B^%(9ZoTvy;gSt-Nw;45jc~~ZxTLE~ zzY#9k0GBj%3706UbU}(ujxMTxd($%Hk2$yVtOS-!B8{v`-a7kB}ej{A60WN7i zXM{^G!X=x-CEe$Nm*QN6OE$nI&2iwRI2YlP4RA?UmwqE$vH>pX>e6q7OE$nIU0wQ( zaLER^r29OuzY#9k0GD)i={Le98{m@eIM8o|OE$nI-FoRa!X+Evl4iYxOD@7C8{m?z zF8dqdk_~W4S66>${ep1G2DqfFOTQ5=*#MVxb?G<4B^%(9=JUWyaW29o8{m>|z4RO5 zk_~W4SC@VxT(SW!>FUyNgiAKSC0$+mjc~~ZxTHC6gi9{MB^%(9t}gvXxMTxd($&>? zncoPPY=BFe0T zzY#9cxyDGBej{9>Tcsmi`i*djZn-tx-t$lqHTFCZF41kCrrVphil}j2?3d`)LeuTm ztG{zy>`&^Jx=5G(jc|!>p^9|rH^L>lEh^IGdXjL7zAs0*?l-*+us^v+(Iu5q^DuAH z1zfU6(IpjA(u_7*L6=CEesj8{txLZVFWDV0>FR$)H3%*3U^c(n+t}gvX zzGMeq($%Hk$d~L9Us6#u_WmVbvPXPLMb)@2{pNg0`*~o0BVV#RU($p^nRZ71_ zd`U&s*f@|c*}<1I-)9IfQN8SM;7gji;7g=Szd2vhoj33$(xu;=FX_(PoNXUp_BZe) z-EpAb$d~NkOS-!9yVuM92EL@L>+4C4FZ~9-q^nE6kuTZ7mvnXg_nUsL(Qn{Oy1M@R zZKm6xAA>LH>axEvykw8~l8UOa=YioRJNS}jy|@%d<3PWGFX`&)@4R06E#gZms>XG> zo{adCimGv4`Yqy1DyqhH={N8t-SMU0$d~NSmoz!NbzjMab5Z?;!7&3 z#&y}>oG(X!F zOPcFn@Ff~w`Yqy1DyqinC10|GFX`4xzmYH5Bfg}fYP??hE#gZms>XHcH}ECR_Zj#S z?Q+s@2rudC(r@HT_J}X3s2U#!_P2;Hsi+#)rQe({>8`86muP(HH|I;b>*_h%UN8L? z@g)^iW4h!^_J}X3s2bPhdJ=p|)5mkRU6+0XU((g(dXjv}9`Pj=Rpa&2Z_bx=p9k?x@e}3}!KmYHa{l(vX@?#y=pI`1D z{#zAT?R(v~!@uR$PW=ZNN$L7pNxJ?lNmsiu@4kJsb^TeAu0KoCowM=%H;T5dzq_UD z&ysZQ+fq|k-y}G`{wzsXGw^i1+S{hCKTFcp3UEw`-;zv*MY?PW=Kc7bP~-}-X@I1c*QPu;|C z_2u4m>9<Z@7m- z_0n(tEw^1S{HBlnsJE1!eje~GSM}0w{w=p%Fa3sZxwpf=<+gRv-*hVt$070?zUAtZ z75(Pla@+ONZ}^t0aftjj|9yKu;9IVAqyC0(xf%!h&A;V##{pRZ(xu=0TW(ty{Y@YH z`8-7Z4Os!Imwxkax$Sz<-&SM=+z$Vi+t#Ju@GV!mQGdg?+}nz8xzdgNhO7YT(r^AP zw>=K@8@}bL-pFtGmaBT%-~3x{w_be9l`j3}-*Vf!>~F{l&^Sc>4Hr?UUi!_y<+kf( zf5Sx-x5K~Xwsq+@e9M(?w4Ov(fRF*MC;eM)yI%G;e9Kk6k>BQQTfe}!TvBEm-*UU-fQu+JzVw@a%Wdo8_nYpeLBH^Cxoutg4Hr>pd?UZj+4k|J-~3x{yI%SY z7g1}4Lso!L8v4z@<+kgk-|#J0^+tZ1vu*Q+tN`goew(xHy7ZfW z%k7Q>zU69s={NtD+t#Ju@GV#45bc-D+4gbZdeXn;w(F(ekQJbMqxIyRZLgQ>N&lAH zu9tqpx7^#|-*Vf!Tu(Xz? z3XpEp-;fociv`)={9A6jUiuAL0jf9h8@}bLUi!_y<+kgk-|#J0^+tX}R)FfI-~3x{ zw_be9l`j3}-*Vf!^c%7QG!Bv9=4_kakQE@^sK3qGc3t*2|CZYx2l@?J0k^}y<+gR% z-|#J0x>0|dvu)#mtN`goe#5t1T@XsY`M2EmIM8p%3Q)a~-;focdg(X+mfNit-*Tl( zzxlV^wl4jKtN@KejIc%kKf670@0Bt|yTdpn5d}&wnqRv+ecr_nT)0bn8V{fG+x_-#jazt;_W!vH~;? znt|uXVa~RX1Ao7HRzSO6`VCnDsyFIybGE%+^taQq0^0S`Z^#O`ot_oY)}`Obmz)t_ zvXd{-y)?dmc1C>3K4;s;mwd??@g+MhqR>$u`0b4Nl0m*i_tJ12Gy_ljVvsM!%15nnRqY`ZS~=2-#VddZjQUK);XBQQ z`#8{Vo)yp@2lO}HOT&7T{x;@pd%g5qRroAlGRT+cUK-TNK+T>&w5t+8-qM6z7}XbLIPC z26N0W95$BR^FDpgyDQ5_3dfg(wc1aVt}LG@?s%WRAI-RMJ9YSWYC$(2Zlx8p>$+I}4&P2~>tb#fZl@04 zPHpRAau;r=4&P4g>T)}E;dbiq?bNoe9s?g=EPsb@r?z$R7G1cVI($2|t&7*_g6LHp z*|gVaTNm%qh1;paw^Q4?c#$sLP946T+SbLJbm4aD@a@#LE?%VzqE~Ojw^JW=A73MX z{mmD0_nVi$`TeUmzk2!nx39i<{igpq8T_iIKz_c=thZNw*N0yx0}0%>jbGJHd{xuq z)>-lMtC|A&S+6~o?RxQ8Dv%$#_^S3$@8fiQ_Otz)m(O1P?yaWe7q8yD{lRBnzIpTQ zn?L{I+MX0;VmWfIBP!lu_8nWy55?#Z-FuG0N!Q;&()G!fZZO%>^>>hT{U^9|?e|h| zQl#teAnE#KOZUB#jY;|P<@2|%U(bg7^7(IG{rc_8FJFE2)$_**Rg*s`s>vUey*4c0 z{UT`pxBB}_y8iQBx^p4%Zd;%`=l=dupr~(`NmsKM==%Fhy1rhJ?yT_ndVRehUEeN~ zu4W+6_4R^ueY;G$nt`Wv>sIWCzAjyOwKgmRU3wMU)2cV|YTb(M^}?&QVfn}Fee~3K zo#xY*``2Ip^d~R>`0}HDJ70c2|G(Qjto!nJ?f2cS!r>okx-I+!IPeLu_3TU6=Uloz z=jyS+oa^YXzn`V+b1q%E?vIb*``^#f^*NWWzn`TW%(-;^{VZLdbLj@}XX*O;S-Spy zmhOAs&wp|p{2eP@f5+-5ts~RT=K*oy()D+&bl>}qeSG#m{&btC?DfL@_|xqV<6yRY zT&n-6$9(=!x7XgspKgEu$&Z)Y|1Uq?KDN-$fBMUx{`|W+|JXwRFb@BJw9t=V83zy6 zY#+ZeF1L?g8Px!{k6#(*AmGQ($FGc9a)12FSc70&OY=8dV@sL`X> z=U2LOroP{yZR={bAAYt<*LQxUYxZpG`p&O(-JjC6o!_>u?*dBKcLAkqyMSF?&^FTb zT|nvDE?`@ienTUaZsfN)+dgmfoAWm9dg(U+H>x-C8$yCLzVw?DH|=`qHy}3(T8aFI zgQePJrQe*nY1d1?0lHDWk>Ah{RWJSK{jgmx{RZqt^+tXJccXggH|K7;_2Lt_blKnh zU};;Ie#0kljYHJm@CjV?vcLJk(ssS-N~@Xy0}hr-m;DVSR9Bb%4J4GtA?j~)wrzYtLPmG8%U^bz4RMMsI@qd=huBWSgMb5^czU1ZoTYp zAfZ%m)ZgZ8+xX(EvUDTA;j6O7f$K^Cs@#45;;XWB={NtX+}7oK5?_@y4$*oNUzJra z{pMel+x60K_^PaWBfo*%QN8e6u^i9)0$-J-i{EdXe^qXe1Ao7P+))tTblB6s-*B*0 zAHmVz6q+9C(r+MlRBz-r94uA6@S9GO1@$gCSSnrkZS&yr=Dg|qCEhzAcQg)(-xeG! zRlV@r<_AmL_0n%RSgLvxzb!aes(R@+KUmtXm;DU~OV`a0mbP`_w+jbLrJML|!NF49 zKS00v!P0iU@Y{96@3+klmbP`Vp1crTu5pO`hJ&RV2l~x}%e(dBV5xMmp4>dRysfL* zeq29X2rkz+Xa=5s|1JnFSH1ZCws~-QyI!m(F9esbn;$G~>%wmr4wgzc`Te%w5^CL_ zf%W9(!R76Gv7WpTT&{YP{WygLpEE|)I*n+KP-b=#m$!A<-w<3b z-Kf7IxLo(uu)le5dAnZrHw2ff-ef(w;1X)p%k`uOmv`$$aJh8Z-#oayt&8>Kh2V0H zL$sd6CDf{ye)Hh+cD?i)g3DEJc{mEs{w(IiuTLGQV{?1wuT(0|; z*xzbIpVwu7LvXpqA?j}kE?2$mZysFUejeE0a0#{Qjrtpc%T+J^=E3FNdgpB0^MK%T z)f@S3{`;;=zj<(ZyI%Tj<9gDA%iFs28-mLf=pOlP&bE&O{pP{t?RweY5L~W$qyC0V zsFw@D<WgZF_#nmuwMVvLLuzEM11*B^rdpWxP*m!_N}Q zCN9IT5)A@f=D$k1gFu(@Hl@>llyqh3GW;gFoz=CUHSe5fdlK-IM6!v?@QdW84GO#y z{1-`g5a=@eAW^l6%kXTh#z5m>z zWPP@m9Utr^`}}N6*59d;_1Tu}^Y2v2`fN+q->H&)ezuni{eF1lCF`>-S$XZrHYi!m zfy??kRkHTuvpHq_R=?w0y=0$%r>a_Cxo8l4H)Im5XHkovKeJ_RF(72>wo$ ztgl=oJC&Y$`Keler!G6b(@QpS89&qS_)IU^#AS1y?E%AAddVg(<45`(AL%61}y(}Q<`fF9XKH<`}32*EAj7!(wt7G>ahPJN1Sf%SzE?s-Ewsrl@s=x`K zbLrZgw{?91BVGSdC|!HCwsrm8DqUZ}NY~!2ZCzi&NY|Gz(zTasR~IK(r0Z{2>Dt@1 zt*hC7cm+t;U$4@&*K1qX->=f8-~0qiTbF*r2^Q5G`3)ynR4@JJCs^9`(r-AyGIl?~ z($=NlaDqj;k>BQQ+w*`EEYgkqh7&AG+M?h51WS7y=r^2TQN5AhaDqkk(rUHT0tSTqi{o@wjSZ#cms-NAl0Y5Il+Pd@` zPOwNf@*7UD=+rp-o1b85*USEf6D+DX>Tfu~qI%ii`~*w4UYuZ&F8$^wSlYVmZ#coC zaftdG0-;nd`W)?ocImY4ze)Day$9f-stp3AqUcdh8<+E>p|IOQ%zX*Py77+E=5EpDo53Oti zBW*xrh8QaQF)rQY1-Q+R4_+@`fO=C!_2LD%0FhC>$qP`o*sxx_0PEtLcRPxY6aD@j z_EA8Tj{|;C*UdM9E*2aM5SdY-RDmvDfC~^A=_W704Ty~HPQnXN6Bj)XcmXazWK?hR z0xTfP<_(C9WFx;Jf<@y%zd0h)ea^UnwQvJ#L>pKIMEN-21vsJ&EZt`Vzi|U=L>pL& znxZcK7Hwc{bGB_9xPdjI4Xgs9To()c5p7@<5aqh`TeN{yK$PoZfj^=Rtc@F3VyMuE zq7AHV&bHS}zeO8ZN}QrD`&+buwawY~dg-@l14}pCP?!BJ+Q8B!6V#>Oq75uvG67v~ zVAZ`8&-XWOU@hFh8qo%pE}3Ax^joxnwawYK=YbnoBig{)xPi5B18YPZSQ|I67H(jT zXaj4*EhJ;%2G)o+ur@@nNSA(#Hn28sV2NJ9`z+ePQXW5_2l_4Az~W_8gO^ch`H*a2 z@iHpuvcE+eSlgU!^947skZ9grM{xs-mr-dPqV*&~GNq*2WDi zUPh&Qqu+0Hwte2{w`c=v;|3NlqtY_fK7n_ihdJ9`FZ~v6U~SyM;$>8-H}V^ZuEEQw zq#ONy;|3Nl_Kg9Se+Q8z)9@6D{^8FiFj~h3i{cL;r%U8d9{ql?7fA!Vt z|9JTyTbtS&JI<8~W=9h^oZD_bl>0nI{P<9=0JrskC!ue;Ah)HPJd``mm5vqY zwsez+a-WR8*Na8h;p}#Me6i?S0dK3`qzUYxw>1uUC=aK%yY*7a_ z@*jN>b2z`<)kxOlUiu9bx9Uxrz&>$(dwzj&OE>ZxIBtyt{T6MS@7y%kxj~L^vT43^(|q0Nw`kLR zpR?`bOTR^%<~ujdSDY)=UQn{=+HtN_^M*y&;pa-b&+nXV8wYNhAAYX1t&2_bm7C^A zv}wL`(|qNo`4MfJ>#{|T0~TFJv}vx3?5In>MVsb3H_caWnjg`o`OZ!Am7C^Av}wMR z`dmqU9?_=x&Q0@`o90KfX})vQd?odHM4RS2H_caWnjg`o`95dcd`#-|h&IiO@pWCU zC!2b=lvdP4i-WU62>!shKP4gYO z1yV}R!@+B7f5*T#XH=0`+*7US!>^joxPu0yWq^Q1oOT>=dX>YxOTXbfv~;8WNgRkC zy2ikthdL-5)JwnNM6~LS_9t;9TJ@s8)lu1}>(#+m_zk(`syA6r4&;`rUij_wL($EB zu7TWg>7u`#ek!`H%l?Mka*adsJwT^dIllCppNnqSOTQtve4KtTx~&Vp=^6w0!cRuG zb+KQfYYeEX83>+V_)XUsP&e`0n6v%({?#=G)J?tz4CIy%U1LDq$ZyCkmoEM0x#it? zo3riXK)-ozd0Q8L(=`ShhsbX;rQYkM-#oXxT`&BmYYb4Y=a#p1={Mw-i!n_4n;;yF z19Hoy8~F{nwO{G+?`4 z_BUh$iWQFhhTQVOa6susej{JPbU^7w{f&GH;{m0s8F=0o$Sv16u)jro$v{A$bm=z_ z2<$!&1nPN+{6@ZHBVTexhcX2u;yp>e^iQ_=OMSMve!L>e5zT}Mfk~)Ixy7XJbm(&ql*QMVgzNC)ex-NgeMSMve!F64( zCnLV3j^Mg3*OL)nQb%xIm;Ei`OX>)&>(Xx#Us6YKU6;S#BEF=K;JPmT7V#x@1lM%Q zmz)t_GRT)~9>e489bD!Q@iLF5nobA zaJ^poE#gardvkp0w}>wh)=FLaE#gb+2(FI<{TA^hgNHJ8Y8Ues@g;+YGIeT~y3u|K z`4XMlrEc{5jfXOIYL~jv?>F)#I<-sPXg$e8nL4#g-RSol4`u4qE_I{*5+2IjcqsFX z_!2G0;WzRnXT+D(5nS^dQ^n4RFR3HArc1u$jQEl|g6q2UTf~>t5nR`$-y*(b@KB~s z?czC$_>w`sM5lJC8~KfgGIeT~x{=>_C{w3)sT=u?e2Gr&QaAej#zUDpwF}*dFZn<0 zon5ab$9Z1=%E4SEz=%Fw{mnbd3KGMXWS9bCBnW~rbz%+74}lum1_b~2JY6#)_q(7W zYcKdBf%lCe0|#r0-Tid+?q2m&UxHh&GtO^nQD$F)Te$Q~cIB6>T$DM}FWJ?i%)SJ- zj+c2;i!xU(%ADz!?8-0cOK|IWnYWKG%KQ-{_Yd z$}d^zm(27_j#{}tINptZ$xOfGP=3iqzhtIgawxxKqhB)9FFBN7vR!ApUT4VLq5P7K ze#wm9{q<0O$#$LXI$q{Y`6U~g_t%Af$)Ws`?K<1H<6Y>N9M?|icYhz+uCraanBR`e zI1pUCFIni99FzI|w$U$H=$9PVPU-iLmww4YzvNJU$wt3qdB*&9D8FR8&UQU-%-dxg zh~t3YZ_6|1H|3XX*V(S)W!{uuvR!ApaOsyE$}idImn`&4jy^+tzx~bVd_litpmxs4&|3@^h*}{C5Q4$Hu@zC{gOlZCEInj>-E6ADZga9&Tr*1Z^|#(*k7{H zFF90y$;SSYg?`DQ`b#$Umn`&44&|3@^h*}{C5P%S+1OvQ&@VZZU$W6JS=e84D8Hn) z)s*Xu{UwL;OL|*P<>GzGq5P8GR#UmmoAOI~TTSIMZ^|#}Z8eq4`AzvHy{)ElIln2t zq_@=+F8z{2`6a!rrgHIq@=$(BZ>yrLR#UmmoAOIG_LrpK2Io!rCB3btjF*1Nq5P8GR#Umm zoAOI~TTSIMZ^|#}Z8eq4yeYq=x7AcG^QQcg-d0n&%$xE{dRtB9GH=Q++31&~;0D*P z@=G?Bey8AuT+=_f(Jx8C4Y_7L&PKl^1vliX_mlKXQgB1AdS61nBn3C*s`-t6NeXVr zRr4GDk`&yKtL8WQB`LTe*L?5Z=$EA6hFtZ2l72}FZopN3$;Q&}6x@)j^2Yv>6x@)j z^2Yv>6x@)j^2XBd6x@)j@opCM!zHl zH{`0k(Jx8C4YV}DZiw*)!cGZaD(ei z`6a!rrgE7#<(Krfn#yI~lwZ=@YATm`Q+~-#za#}WJicar>uoi4yv&>OOLqDt+0LBf zHP4ef{gP}~Os;vJ+}U4}?OwrEe#uV1Bn3C*n&-)#en|>$$TiQCJN=TCe#xo)lAV6Z zO26b(e#y@MlI&v3b79AD*^^tPHhUgk~tB|H6+m43;o{F0r1Nj3`NaWKE%dRt974)jY-<(KUAOR_-& z$E)(j{*sk`$*KI3-d0nO1Lrs8m-M!p%H{l~{F2^QQ@PBW@=JPKP31Cg$}j0{HI>V} zDZiw*)f6uMl2iF5y{)ElnK$K^?CdW|kqdI6{F0r1Ns3X(Re7UdlI_aLRr4GBOHyz{ zu6bXwv%e$-H{`14N%|!zxFJ_PPqM!x1vlU-zofU-)a#ddQ+`Qrt0`RiC8zRBdRtB9 zGH=Q+>1{QY%e*PSWT#(}f*YPUl{fk&EB%sF^_T4QOHy#d@v6LWf1DKDkgM{>{c%!o zL$1mj_s2=W4YopCM!zHlH{`14N%|!zxFJ{N zjebcAZpc-6qhFGO8*)|N=$EYYOHSpN?DR`k`X#68FWKprq{kh{LG_pH^h?sWPOi!u z{gU+klB@DYza)LBUFG;}-xhik;OHyz{uF4zzk`&yKtMW#_Bn3C*s=U!JNx==c z$}idJm!#l^Ts6PZFG;}-xoUo+Uy^n0UFInlAoT|TMr(d$tFF93z$xgpyrC)NY z{*s-3NeXUwd{y4)m!#l^T$Q)0t)@Iz(=R!dU$S$5oD|%Y@utusPxN=MKkjWcb-Xoi z;i|k{XS;CWmxQbGM!zHlH#`n1Zy=?nzwLG-g;Y2<<`7~Yx36HYAUzRZ{eExt+&-wF7u}RlHOKRxy+mLOL|+)EjRz& zxXzSc(%Wh(mw8iuNpGvET;@&rCB3bta+x>fm-M!p%4ObEf62lAk`&zVys5m=FG;}- zxhik;OHyz{uF4zzk`&y4tNfDQR#VR#^QQVsdRtB5!Y@f-lbPRoTTSIMZ^|#}Z8eq4 zyeYrrpkI=L8=f~cztJz*;Fsk1esq5OU;mayyszJU_44Y|S3iGw^X=QO|MB(HXV3Hc z_ka8A|NZ%g|MBYetKWb7_N%w=-v0B;A6|X>KmYjZ&AWHszWs;q-d+FiA7B0I*MIlR z&;I7sr*pP)%gld!?4I%Lm3PzS*{gri{pPp%=W~zvF>a1b<<@I6-16)-%*C_UGoHP| zE!XBSH+P~kUOan+Tb{j!xp?+^W_MiQt?q|s+hK0*M0LFN+RS*%wK>Sm)^p_6xggwf zZ4PsDw(EH7To7)V3x>Hl+m&1Af^f@RFwDhoooDV%*mtYD`@CiAIgYo^1^H%U@|LaV z$YtK@v)Ax(K;9-idu6;PZ`pdTj(1{rTx7o6-+aU4McyXvO&FO^agn!)-EoomKE|#0 z?07|9PPp~b3Af&=N4fRV zS!Ud-!>yOjD7RiZ;nv59aO5OsnD~RK* zx9V`~t$LJOZ`B!Zy;X->Z`GsRdaDk%-m1gBNZ;4j_0pK1zJ6Kr8E$=S54SwF4|AC} z)O=>Soyi+(J~LkC4Y%si3pd1K9I+Gm(I+^R>%o4>ow+k#tl#%uDnU1z&; znK#_32gi$L7iTm6|ldY$2Ca=6S}U4}8tMc!ERnd5u?m*1T?{7lYxnYUW=IXqtE zjWwTHhN|+0Wf&PR^HzT*50965!_VZ5SLF@MFc#K)hHK`x4a+dX<@{EECJ!G6<_$lS zGhQ{n;b(Hj%e>W}$)n@NGK_GUx4H~tn9ICj8AgtS${T7vGhXJcF2fieFY|_F7+IdJ z@`jqvjF)+<%P@w=%e-M3M#ii1hGiIOE93lDYd(j^%lQqzhN0h#>@Gw)_jhR z7t1ihW!~yCjA1UGCzr;&)nypNT;>hi$maN}ykQ&J90%sDF2fieFZ0&wPyf^wsJvkt z*^HNY>p!0Fp69WRY})qfXP1mu#3?t)Jc|*--+AW#4x(s7@yv!SFJ~LjGH!Q=*c$v4ljqK=nu?!ScZ|~pz?-g7#S|}R%k!!nGFmwBr- zpTpy2-mnZK<5hXXGK{poGHQ<@01+hA})|d=FsF=W^6-WQV!T z8N1RB zF7t+E7~!hCVHrjqADFkgjqLDvIlo~UM#ii1hGiHTFXy+qjqK=nu?!jiKhGiHTFY|VZ`C`0$p2RYY<*3UrhR+-GhGiJx<_SZLmwCf7 zjBr)nunc3#cblT2g{$T_EW-$w^IKhpF?@VEzhN0h#;fKxEW^lnnYX$OV|2V&h7m6F zR=1HI<}zgHeUxJ#?VJ`DVzvNVY32Q!ceDS{IRDKC-KC>$dz6YGjFJaARxR~Eg<(IJLGhEDX zr}9f!^BFFlCr{;IKwS3^G3Ol>BFr*cET-_!7#Ue z91gcm2H}>6uVHR|xe#uh48koh^M<*|Tf>i?a8=%}vwfT6h95iWlv8deV)CTw?4w}rM2PlGH>{?lkuv&am{(dkDYK;-tc25$ANjPKXyis z1Agp;%e>VeJHuS&4L^2r98}(}f4}4cKX$_XXx?ro+ppgIdl1<%?Yk9_qQiru?5i*L^+F z?YYhzNp3yYqg@gfiZ1gg;!HqvORSlsS^)HIvYR6($*Pedx=0%_P*<6P5FZ6(-@DhrWaN z*36MS4k~ZFw{Ca?knyU#VTDPKFY|_b>&^9Wd#`$bpZeuD-+le=>E|gG__~?9)%BLB zo)xAPcjTMV{741Nfpsa@%!;#uJMt)(DaCt(?YX`;7`>}tT}s-KnbP{+V3^C4;=Mt} zt5S+}DH$(QTHhOtju-1v!mW>r8Lvv|b+*fOhIJ|7s+3|~O2*4sv44@h`|gT$Dd94u zbzREv@nznyE+qv4^$BP&7g(2)@iK39UCQuynK!IU$#~VQh;=Dx4QJl!x|HGZGH+Oy zlJTm%VO>hb%e>WfDWl`Xx|DF4x4JH6n9ICjT}qCF${W_DWW3B^; zDsNbqlJPQcbzREnc(E=eT;{E=OBv=eZ&;U-f`nx8`h@Gwu1gsmFV>}m%e>WfDZ^aOZ&;U-r%2S5%X5pr3@cm<_+soGG3K8ZV$3y zT}rrWe#5$y90%sDu1gs`4p^5GF6XzpE@ha@`3>t*avW6Nur4LzW!~z#l;QC*Z&;TS zb42A0y{8#3e!r!Y*39$V9%RG1l#Ey9joX84SeFv+^`_|V_gvf_WW&0Ya8=&8J;;W2 zDdC#D^;Jma`3&n)!Zq(F`zoZ$Mc$^`dwP5Q-oBOpzLx#(w*T=zhQAPJ^=Pi*n}0tZ zSiO&A{Z0Ar>Tl0~@~dIEb>0rQ{&$62=Ivo_y^n-jf0u?^?jyt8`nxpTdLIe5{4O2l z*851f^>=C3A(i{cFt`3L4Y%G$!Y%iaVQzg7l=_VNH8R|C9~tK6Y?tc{?_I+!_mNxf zpS{kv;~2iob8zbA7%RM9j@k87T#n(^%Q4(~Ifg4P$8hWA7;e2B!xfifxb<=jw_c7h zEyd*+ZoM4Ct(RlC;&KePUXC#>>*W}(xE#Z+mt(l~F*4kbUXDNV`Elm7Hep%|w@hod zm-&x!bGC2dlkwJ{ZQ+(_ZIGL`W^(K8KU{J9&rO4Q!*a`TP2SSh%<&>``Q3K=IC6U& zZf_%>fAhsZy}Wz+-OHQbK7H}#_fLQL;@g*hd7A!W`B{5@`q!sv{MOQ+CvHwn7Fgrb zpQ{Xf<=`hL&@8*ESN@VGkn$lrf_b^}N3r$74;B~xTvgyvY>xWvLC7j-j<#I)qu6@c zXSBHN=PCjZV&MS?i>rRF9`GnOe^(CzCYiZvz@ylD&1bZ@=I3ewk7DZ-6D+2fxk|vJ z*gC@miy3CF4)7?pPB6hTWmN$l#WH0yfahuek7AiJ3cz!Jj{p8w($6(9MGKyu&U^xa`9^^)` zOc^A{EaxfDaidtK467W2y-0uVy1kuUfA}$a-1B2JTOQX_JL9GIve%d1x3l}lpPrU% zc}#AdM#2?OPpQ7EPfzKPtyg%s;^`^e9OTq)Tb}NQ$ID#e<#@O%mv}jzjPfKt8$6A2;nl9<}E@hG?`1hMaXzRn#>XJ-^!9}KQvX7w>9FFQUmCw@GuISBRK1dGS-{Khxf zddmzJkKb85XR!5-87v;Zvj)px>y0p_Ao!7+dI5vYc`jE1AHUNsV6gQzn9<@#ZpsA= zw%!GUtxqRwx&;IlkKe&EW#;jF<}#y+kKbt)Fr#J4`1qY-0fS}A`1qY(0fS}A`1qY# z0fS}A`1qaMhQTsrSYeb^btYw8U^HQYQLrXu*Lg1C#rmRPP0F~uXu|TMU`@)7b*H35mY+OG} z;O>}fv7bt6jChBw>sH1dg>q(ji^aN?tb8mdf0)a&k98~Ima{+1Cc(|CW1u zqQ3uW`*`FR=OI5O>UqecZk_BNkNjU;+oi8L4rRW(y&gaQSo!bx$bWqhdHwYH@4or& z%iq3a-{4R35+e7b_R0GCY5m{R_Om?oKBatdJwMA@t>HUT%z&Ekd||FnQTY;FuB`sN z`ja0_!o`)98&G*p54R+Il#7)z8E?JAhg*KF40AIT+{|;~)}JfkmItX}ZhevpxBgxU zw_I7n-1;aLZvDX$Zh4d%=H_hI<4}LGEGJgVTu)X5*8^6{WW4n!OSt7>YIwZ$X==%4 z@3_veQf73#bw&*rFKV-mp?8<5hXXN|}t8dBaMX(ec(FFX1w8SSd5gW!|t-W;wA^ zW|YgkVWmvC887EItdtoYFXuO`lv(n#?)FFh=yisbG8r%PhLtj-<7M8k zQYPaqZwrRU%e-NwOt>m<{AjrHqv2UU8V-+_dBaMXj92B29}QQ2G(77^!_o2bqv6Vr zhG+d~ILu|<_|fpJ9}S1OoZtA-@T?yVhq=rfKN_A`DKnT0tdzOFD&xLhKN=2?mwDsI zz_We~9Og1_{1|xFkAcHnK2P#v;8{Ng4s)3|z8N^{$G}l8KL)P+7@i3Qpqf-1_mEu9}0i`&vr0VlzcJRm<_(9qj<}z zI@|R))ZcG84mkt&ABXE~S8jb@60XV{go+#o=B)}9qt`D=jl-?)OR~d{`TcgF)HvMw zJQ;4zfH=O)8=Z>h>QoFL2j-1Z#dDP^hPliet%~PrRSa{PH)<8nRjU}~UVm4vUwReK z)vFlhGH(Si@Dn-{_ZY@Jqr~zu)MWu!%KX_4|!}37c5MRe8J4c0F&L-;`f+poul- zjd@dk$#I?SI$q9i$}c(4#G3IkZ^|z@=$EjGH9M24yj^Fz90&L%;i|l$iFIKUYq%uE&9SQ+~-ozl2S!8LxVtyv}wVFY~7S zl7oH;n^?26?)8N8{TkBI`RzK}b-eujru>ovO{@!>STkOgH#D(^%lDJYFFEL!Z177m zUNyg=i8bTp`$^@O9P~@r#G3J{ywNXV6KlBYdGb2j2iFIKUYq%rQI@=|0@Jq52yPDtVm#~R7T$ML2 zHfIxSxGHa4Y|bXuaMkl97n^VJOTtxoaj`j@Si@C$<6`p- zeo440Z(MB7Cf0D({D#W9CB=XBy*-;)2j8EevMyXaPqK-1l$*0%?ho`!*u*-@&DpM8 z%x`RB9p&b1S1x|Pv59q*%lDJ?OW4FZ#$^-hve7SL6YD6Kzu)MWu!(h)%jZe@C0U{` zeh;Mzjpq&XTh{0+F6TG;C0V4excvP_zhqK=N!rlraoFjXWSPDiFY>n2FUdN6#YNtB zR^?@(zTzTpJN=R@95!6~B|H6+skU_t{+>VSm+Y+Tn3P|VC5gNq@P2Yqe#uF{WT#&; zDZeDGXdEx+w|+$LeP43YFWKprWWBz+9+)@!C6n??&g*R7&OlC0QQ<7M9Hmt@Jl z;xcdaOR_fBaIdpnj|0AUPs%SjQQWcY^h>hYvKlY*#^#P}wye0A-*#4aOv*1g>6h&6 z?np&~8ZYLzoqoxr{F3uJ+vR$oUot7b`6VX`Ji^8M z$*C52jEV}DZiw*)f6uMl1cd` zy{)ElnK$K^^tPJHW!{uu(%Wh(mw8iuNpGvET;@&rCB3bta+x>fmz?xVcJ!B|j8*-9 zqhGS4za(7sev*F4j{cIgysF=C^h6c8(FX?SH_4smr zQ+~-wzhp;$N$QVP-sqR?=r0LZ<&A#Hj{cHxRo>{A?DR_}<(KrfnsVOgmrTkpIq8?| z=r74}Q12({m+a^-30LKfe#uV1BzvHl9Mdn^(O;7Bs`-t6$xgo{d!VWD@_PXNlI($| zxO_i}{*r4CG{xonN%WV5tMW#_WJiC=wFjCSFW;BYFPW5I(%WiEj?rI|@v6MhFUcM# z@E??4a?&r!9w_9hywNYo9w_9hywNYo9w_9hywNYo9w?RDRDVfttEtxme!n%m<|lHOKRx%mCoRDVfttEpW4eru+`B&{5|yH+mp)=Ym%xVgJl zF7nn)e@VFf{zku~8NVc4et%V_(4BrsxX9Z`%9YfOWwEDR4(&o{E~2)H~J;b_$A>oZ}dx= z@k_#G-sqP!JqX~r)JmwBUK z(u`jcF7rmeq#3^?T;`2_Ni%*)xXc^FP<_-JfWV|JB{psf?_hAZ`d81#_j9(Hi^G3g<8NVc4 z=8b+yGk!_9oZsk|G~<_q%lVCdNi%*)xXc^oZ`dCv`~Ir=jebcAZg4*{eo4m5ywNXd#xDt% zd81#_j9(Hi^G3g<8NVc4=8b+y`?z0nyYuNUzWMGSzI=K5uP<-18)SR_#oy-tuD{7< zkk7vv-~Dms>@{Kb$~H#gX>pl3drg?VuI-%epT)yPnkLL%;pX_>`*aX4(iB;`T=my> zPKt}!Yr^c6ZEJEr6XQjiCd^*p=6)u)NYjMbE8Ls`!9|)T%wFM&r^TE%q$#pA&YPLN z!o}=0VfM;+#na+4bM~4rdxfj=#@TDa>=mxc8)vTxvsbt(Z=Ag*%wFNDym9u5ERE~I z%w9Qf%o}E}?4+#n#@Q>fG{>v*#@Q>fG`T8ooV_ATlPi9m<@hphup@JPRo-YvMwaGy zRo-YvMwTX5<&Ab^WNC6$-e^ZgmL^x_jqO{JrNLEpB`M^PUiWH?OTzh$yIr~T-e*UkCCOxRe8I*)+!fy%XUucIPiHAySrW6IVmpZ zH?(hsYx1_xj*KkL<7@J^(2k5OO|Hq?LOXJT9eHi%B#!SwJ92^@d2Q#UxcvPFJ962K z9l0#DBPZCA;hMZHv?C)+DsQwSBTMr*sJzjRj4VyA z${X#-$kODhywQ$~EKRP;8|}!*(&VbV(TwKGXh%ktCRgQ+c4TB}a#h}F zM@E(=SLKa%WMpY_Ro-YvMwSNG*pbUZJ2J8~xhik8BO^@P5C8hL&fz=za-l^ znd_H+Nn~jp2j!P6^h+X3ldJMZza+9Wxhik;OCn2?tMW#_B(gNQDsS{lB1@C2@F>6h%vFUhi)I^LOn$!^-Wa-AV>GyRfX?e3P% zGdW)7P3`Ws(l43mm+Yo}Ygy@+%=AmLos+p9=$Fj&OR}Al;v#P|{gQ0wq`1i2OuuAT zen~d*;Pt?~nf9%mH|C9gNw#xR$ANjHUy|*d6qk9UUy|*d6qk9UUy|*d43~b%Our=C zIVmpYx0!xPwsTTk%x^ROl5FRsxXc^FSyYc4(=XYT zUy{YR6gs(OLo(~6)y8ezhpPM!#e??OWk8Z}dxc z<(I7VOJ@2dyJ_Fbcsak(FWF7|R=CU?{gU0ZZ-vXe(J$Fe`&PKj8~u{qv~NXI!26P! zeo3}-GWT`*B{Th!Z0Dr7%p3iZZ0Dr7%p3iZZ0Dr7%p3iZZ0Dr7e4eCVlI@%nmwBUK zlI@%nmwBUKvYYm;T))g4{gQ0wq{hp<(J#q%PKHarWTsz|?VJ>s^Bet=UG)(^_TRvn!=@DvYYm;_iZ(m%e;NOee1R*>+^5E_@|e5PrrM4 z^V_E{-u(XQ4_|!y@-I)*Uo1as&rkpQ^!&-z*5SIWb;j%YysodG!`A-7_J?|;>mK&g zos2Wy&Ien+h6P)${!whb_=Bw=S#Rtoj)mQO1*xMQQ=P96k`}IG*e%i9L)$mlBKCgNMU1pkcdo|_8`i;Y_ zchGR_xn1_UPvtPTp4@QjEi~M6a)-I~9vW^vyWy65=qQ(_+)Pt$ulrOEb8{Ws+(k3q zdKb-j%d^Tbx86p>tq&{VmfPqsw?3_eTkoUcmZz0l?&CV2a=aeb`KwQ_Fp^Sj?dF)`Q})kI>%42W^DT$-}-bI zE`EbG)8-g1o*@oAL#(YnLku4WJVP9Kh6uO(3LEC)8REdbHQe$HG0bJ&@C*^I${U{{ z4m?AItMW$M{=mI8T$MN4_6MFJ!c}>rZGYeyB3zX>+V%%*`}`IYZ`UKIGHW@^+o=%B|1r;hMZnwCxYH zIfiTUHqo{}(B>Gf$=k#>#{+GS;hMZnwCxYHIfiTUmbbM$ZA+AVd)23ayp7dOiz?R23uk}h{Z>M<>W_zNV&In z*HLW#?)Ii~@*}`(J_6)TFR}G^bq+$w=;&zi2zv4(z-&GO z$&UcD`3Nx4&OiAPAUdwO5|}c61enc7fQj9YCqDv2#xmrHXi}_hi?4HY{cbS$pgQ5hLAZQS ztsf4Cxtsv`KcX#DHMn#dCx zf4F5593C(835`G8lFwl-0}72lACgKyhq+8BH2!d}Tgdm*>oAv(o6z{fEfe7|mop(W z{&36l<}jCegT^1O${RKQ6B>WG<%x52ywvzlX#C-pN6uj`^9GGS+%g*ubNSE-jXzwK zH){MRH2!c^-l*}P(D<|dMdghe{|SvhT$ML!{3kU2a8=%@@t@H6!&P~s#(zTN4_D=l z8vhB6KU|eJYWycO{%}>^sPUiB_`_9sV@>1^SQB|d;}2KmjT-+6jXzwKH`YX+(D=hud85XELgNot<&8Cw zCp7+WRoP2>rUKU|eJ)3V zn#gcf-l*}P(D<{CSmlj1ktb>*!&P}>P2>rUKU|eJ); zQe5d9Q{MmknBq#LnzF1T<5hX1xN=fliS1^7&$A}-q_{FGaV5J<;te6im05`^*=3Sk zel}3zN_LqfmtW_UxRPBa!KJt|D{&>eOp?p@lS*94E|cU|DKPy7DsQZbJSncsN?ge< zlN>Mero@$r;>t;JWme+KL~-S$xH2noWumxpQe2spxRPBad3=$#zA@$f_eqK?C&iV% zF{R)#ZxmPh#*~7~yir`~8&e7{^G0!HQQ}H=nZ$X+Hl*nbG0&6PWs+Rvt#3?u_i@NB zljP!SUEi2eaPu@%zEn|M=^IlDF6TFjD}7^1!DZgC4QcvV%=2V+ndEW6{I-~y$Sl;W zc}tBbzP~M1KN)@vyg zmwBrm%J6uZH;O1r6;Xz{%o|OVrJ5+iT;`1`%2HL7VJ`DV7o~4ZdH?l${rflbMe2*0 zw<@EIju$pcxSZdrjWWz--l(H2RYw`-GH+azx>O%!n9ICTNLi|oGR$S(XryFqi}-z< zT_$lo&@Wk(Uy@xW$>sc}{F3Z4NiOF%<(FiaNpd;ADZeDUOp?pIDZeDUOp?pIDZeDU zOp?p_P5C9+Ws+RZZ^|#pE|cVPep7x)c9|rX^PBQZvdbj6^h>hiu*orMB2)9uyeYpV zyG(Mt%$xE{vdbj7%$xE{vdbj7%$xE{vdbj7%$xE{vdbj7%$xE{vdbj7%$xE{vdbj7 z%$xE{vdbj7%$xE{vdbj6^h?q_Z1M)bWPPSzk|tEeW!~tQr14R4nK$|+ePhb|pC{p$ znsS)vf%Zz zY*04r<7N+ln%8WmQ}db@<($ELk7Kwsui@6bhMO}exHYfg*1V>jS-fw_cxzt6t$7Vs zJdcK3^O{YC>id>(MP9?L&!gei`7vCP*KliI!>#jUxFWCN*1U#W=f`k!2JXKe@I4{i zn%8i11_Za}HQbulaB~I(mwChYgm6{f@I4{pW!}v9gzV+PykQ}1TFX`5@I4{pMc&l+ zgp8MY!}o-YSLN+G+c)nSvWXY+roJa+yv!TECuF=TZ}^^&@gi^PdqVbLsn4U~B5&$@ zLb%Ku7Q*H@n7lPCgw1#{zp3vD887EId{4-D&HUD|5H{n*{HDGqWW1c;PUh|7-xGf9 z`Q!HSBMqbTXZgi_$Kwa|*o}H@HnUK-L+G*L@^)zS*nNT?8!k?d(qqHr>46@b%{SEJ z2lUvDdThArb_hK-T-*+o9-HI9+adJWj91+bp~q&txE(4zHd}u2b_hK-<5iCz&|@=R zK7JTIHsj^v2lUvCSLF?QY{tvH89g@R<>LqR*lZr79zUSRX1ur^Dm^yi<>LqR*o;@@ z4SMWGJvLnRxDP!xTt4m_JvPUIkNePLGhX$$4?Q;H#p8$4W3$B`A3vbSX1wO{V}c%= z@#67A>9H9vA3vbSX1wO{V}c%=@p67MdThqa`3-t(UI(c84SH;Tw)5w;(PJ}SKJG)0 z&3IMbpvPvs%$w0;GhXHmdThq4@&-LN<7M8A9-G$z%p3IBjQ68?yL}w}@4tI_`SSJC z=fC*;_0zB3rgG)Wm#5!+n@;i9Ps`h{^MY*pWPO`gV;{OupML($w=e(c7cc+k&39kE z`_JRgsc8}^KmW3qAC5zkQeFpKSI1BG=4ET6dK|*VJf9=3xOJWn7x$g~;8xsv-w7A< ze15PfZk^}D#eIjnTaO;!dfy2b^E`LA9_7|~K6^0YzQf(EN4fRB6E2>sxx4i!w?0>g zi~A0Dw;tuz`%bucuIBF6W87#x$QxfXaChrbF7w9M4BXv%l*_#FH3N6I9_8lmZeBa( z_#$uI-FlSEyzw;yceftpGH-m%z}>A!xyT!Lx6Yu@j94?5W>7kT6E z*5TIQv7=n%E%ke4xk|Woo*(2wTg=|CnBVe9Z;k`B#c(md<6Q==H$7L0imbO)78K*}lD>r9%(bFSNzc z@iK4F7BgOzx9e=z@iK3f5(n;nKx*Q*~Coc4ccNT%p0`D(eW~G zsKv^7RokLR$=%d4sk%%Ej|!8ufTRsQC@rV#bT#Z~1|2=1pje;WBT~ z7DtZ*^M+ciY?fEw(~fePH`HQRu`*uuJPBT*iVu zVMpJCV;M`{YVmmz%UDLo%e-+J3-*K^9xwC8Wh~eec9cuMgnPo~ww^O^|2$8>gnMO% ztKOHO7AxnC?@N?lvSJy_r2*l6s`5)#EMo~5?@JCWV;Q{8u#6>Kd=EIVpW7&xd81#F zEuGc%!1;}S$$|acM#sy%(Jwi$jAfL|ywNW?P>VIj-RPHORa?Ez4(#VP%H{kg;jpH@*+eW`6tJ=sl z^V^2K*>c`6za7di+31&KRU5~fGjRWTqhFF$ZQv@uWTRh_Rc+*&_az(lXUkVS=1ut} z8~u{BhB^!2V%XpbL<(F*qOVX0Z@tXG~+jX`}j!}!1pT{b1^h?r`$MLGX zVVAZXU*=8uB^&*cwB&KTDsR`>uE&>oQ+~;YjoNY?m^aj74bE?<#md)h=1ut}8~u`n ze#xQyk`1+3887qpalhnteZbFO{`uw0r}z8TE$g(7EB|cDjDU_qrkXOd5*Lr)Y|6|z zueYd6ocL*_tnrb6O_|}=M}ko<9tqf#8E(Br4RZNNz^2S_>n&=Oi$`!aWrkaCQKMWu zg0m?z+&q-sOf93_obB6N37ay*t+%LAE^bk5%DnCYYP@&^f94}W?g5I6NAPDp5~!xk zz44LYnU4gjDKlI=f_nq(+F7rm^bb)d@%4OcDoGwsKN4d-! zmD2^v=^&TN=`)qn1+ zi`j{FZ>X9|@don-<#cqsoZqONE>KQKxt!mqoGwsKN4d-!mD5F4O*K?arGNyVEEg!J zqvK`XsGKfPPDi=S81nJY7fQ|o<#g~kP&s{OrP%`Ibd<}yQ8`_poQ`stH!7zKl+#fz^G4;g zmt5VSH!7#kR8F&3nR#D==JXUx;rH7L<#hBoFmF^&v$u~LFY`v_G<$a_F7rm^bcJ#{ zb{x`Jg}hNYU7?(gayh?IIbETgj&hkdDyJ)y(@`$-M&)#cayrUo-l&|eP)m? zRrw`ptm1LN`;t}pB{P-NiOT7!{F0f<=|tspRes4#<#eKQ+DoqPzaFTZPV`Gw<(JG< zPAB>$E0oj0ywNY2=$EX05zr6H=_r?ZqhGQ@IUVIPZ}dx6RGJNP>6c9OOIGEVq_GNl zqjI_`zhtIgGSM$tp`4B$2h491{gM@xW}{rpZxj8J70T%-7xUXhzhs4SI?CnzM!#f* zayrW8{6@cIRes4#<#eK7vMRr1W~JFgzhqT@NgAt=3;HFi@=MZKMK0$z<(JH?G@Iy` ztjaG*V-?4X_mivgOVU_HF1`n>$}gF*6KjfV@xEkLen}duFkbp4tMW@`R+>%pOIGEV zq_K+Qh2p&`zhq{m*+jo&Renhtt2kb~FIkmeGGiy!6b>_Q$}dS{6~~M3Z>#c4X6(e8 z@iK49FG*t+$IHAaza))S=$faL0vC?c+en}dua6Qm3S(RThV=J>1d^2y#FPT|sHqkFxm0yy^Djo;s zP5C7={gR1($*TO4nSRMczhqT@$;?W#iGInd{F1(L-K}pw(Jxt*Uoz7#ndq0S$}i~~ z*VXZIep7x)-?*-FIln2tq;FhTxy+mLOZvujmCN}}`6Yehy2@qVlwZ;}uB%+mZ^|#} z8`l*s{gPGrB{Q}%%f_qSE~C4J+%I$q{Y`6Yeh zy2@qVlwZ;}uB%+;P5C8#Ufzq<(Kr0>k5~C$*TO4 zzHwdUGH=Q+=^NKoF7u}RlD=_W@OJ?HlI(Sd^QQcgG*)4}^h;Ldm-LP6%JHRN(o3%H z|1NT!?aF1|lwXp@Dsq`O<(JI#OD1law<^D6re8AAFIkmeGPBZbqF=Hqzhq{m*+jo& zRenhtt9ag!w_b8}|8+*cWTIcPDZgZ1{Q)_uodp zWK(`gZ>uR>`X!t4OL|*P<>L2SFS!!OmwBUKvMIl$x7F0~a(+{ONpGvET+VOGFX?SH zmCN}}`6a!rrgE7#<(Krfn#yI~lwZ=@YATm`Q+`QrtEpW4e%q8^(%WhZmww5n{F2^Q zQ@PBW@=JPKP37`=Qu!slt)_CBH|3Y~wwlUi-jrX`+iEJ8c~gE#Z>y2%O@=JPKP31Cg$}j0{HI>V}DZiw*)l@F? zru>rLR#UmmoAOI~TTSIMZ^|#}Z8eq4yeYq=x7AcG^QQcg-d0n&%$xE{dRtB9GH=Q+ z>1{QIOTT1Oeo1eusa)nw`6a!rrgE7#<(Krfn#yI~lwZ=@YATm`Q+`QrtEpV(P5C9g zt)_CBH|3Y~wwlUi-jrX`+iEJ8c~gE#Z>y6dKEFX?SHmCL*-zofU- zR4((T{F2^QQ@PBW@=JPKP31Cg$}j0{HI>V}DZgZ4e@O~%@cu#hCB3btj+c2;eo1eu zsa)nw`6a!rrgE7#<(Krfn!=@DvMIl$x7AcG^QQcggrL zR#UmmoAOI~TTSIMZ^|#}Z8eq4yeYq=x7AcG^QQcg-d0n&%$xE{dRtB9GH=Q+>1{QI zOTT1Oeo1eusa)nw`6a!rrgE7#<(Dki*{)pXP5C9gt)_CBH|3Y~wwlUi-jrX`+iEJ8 zc~gE#Z>yM!YSHI>V} zDZiw*)l@F?_Hn=Db}NU^zxej$UtT{=&p(^n)89XRl3DTT=ij}1_s!R@pUx?@hM%?V z9N*tzf?u_r?C;4QapJqxblvT4{(Hm4_1}$~yT8{&pCK35e>ZLfw|;-lcyaxA<3@1n z_vh{8_1}#f!L8q)!^QRAjT^zO-^0Si_1}#f!L9R6xVZl3k6-_<|M=?7yLaEd{fF<~ zz5LBf!V*6+{ZV!r9djo>nG z^sBmYBe={P`+K@^Be={P{i<%<2rlzRzp5KIg3G+ouUeE}HNmgiPWJa?k2rJxg2fUOmLYu)=~EbWP;1Q@pW!rKqk1%8|$e1 z0y4p6-dIQ77mx`q^Ts;rS-sAkuv{>&Mfmetz0RGkm-qGc5FYpY0c1Ov0nKxw@OxPVIT)ur)cENPHB<1>jJdVDoOx4r zLCOhu{W5RLE|@Ntq~?NoQ+C00xg>@AcpQCyojo2$^8xhncJ%Q$`gk0D_4e!EzWw4) z$00Y&KmRN5$3FUEv%bgU=wJQ%!(%z8$H(L7`=5VGcAX%*=COt{gpytJ`w5Q;kH^u+ z9rw>{1Pp_@=04QEt(Vc$Cg70rz z4_Wa2ad>>4{cs$xR^cHFez@;EzRtdXo%{GY`{6j``}qCy(BpO3W9@9WxOV(Jf2^JT zaGzCc$0zJfkk=o4eXZ7xr+OYgcOS3A-ajWi*3N!74tV|iSUdZt*Gp=Ce5{@A?*mdj zkNeJJ?dBr}|5BG0$@j32VE%xZ{c>C_{KVR3x|NODfW_&z+ba%YJy*#=*-XDj@V#yE3;jviq{i0Dm z?mz7Ghn;@A8bnnwPuJ4evgq#7-SPgu^XTq)e;gj&9UqPZe_lVjJ05n}r+xp(k>fx) z{b7fFc)X*nqIL$E9#wMh-&#GoJ3br-=IvpJeR!;4-mW$WVZqSGd{oJOIKEsA^62jP zU|Z#dm$=RzRdT(l{r|TrxyRR8zOH#JmVAF7c-Ubdj)VDH^!Pgar=2SvUuWO%;KBLv zv9rSa=dj1l3LlOGo<|>FXCGf@UyZ-EVpqfC>+JhjJ-*I; zd{`9o_&WRHYkijEh}S@T+<$zXeSiObe4YJp9RA<>I{TY%U*7ySdy9Vg-OJOj-e&j3 zFJGRPw_j(^(dm=*?bpM5e61&zk*ujvEL(u3YA= zsk~ihyK7hZ`awbT;^?7dArVb((${RMJTz7oA z3s>dsI@@);%$pI}*ApUp#>>22+Y;V?-mvRWxXhc`gfiph{Dw^^b9`0aAhKt?oZrkQ zlo>DQH*7+=O=ewXxXc?ip$u2$4VzG|J4E(yRo$!nm-E|ITq(Gm-%wM! zO-4k|@nzn2{(dvN_JqslN$lE_@v6LCXS*C<)P#kr@`jqybw^EUxaxTlHKpP5dGb_w zyUun!4$PaW30qIpgk`+U+o|$)o$Wea=FRNdlkqZd*tI9;P2~-{_T)HVerwO__uF;0 z>v2Hd`aUlA-yg2CUAQOSm-OOF!DZecqHpao4g{C;+ll$DUB-dna(+9Jw{{r^_j0%A z>ulHKi@deVI1pUEFTt)oIldxq887ojzoZ$zBwXf=en~TaNw}Qf=$AC(mxRl_(JyJn zF9{cUJLs1*oZxiP?`mxRl_P0X9|OTuN| zCj5SD#xDt%d7GFw9ZoAFD+W!`4y&G;qZGH)~UX8e+HnK$|+&G;qZGH(m>X8e+HnK$|+&G;qZ zGH>)tn(<4vXZj__!n_&3BwXfgVcv{i5-#&bzoZ$zBwXf=en~TaNw~}#{gP(JqX~r)JmwDUxJZb!raG5vyCC&IH z;WBUZOPcXZ!e!p*mo&4DZn(@F{gP(*SROTkU;vze7& z(%Wh(7w=1E<(Krfn##reHY>lRx7AcG-cQcTFX?SHm5b-eS@|Wst)_DEJUJ`Bq_@>n zF1`oM$}j0{HI>WxP5C9gt)_74m(0p9>1{QYi|+xm@=GTAB`5uoS@|Us{gRV@$*la6 ziGImRzhqW^$wa>-1vj|wD8FQ)UvknfnU!BM(Jwjam(0p9ndq0C^h;*tmrV3aPWmOY z@=GTAB`5uoS@|Us{gRV@$*la6iGImRzhqW^$wa^8q+c>Czht6ca?&rEm0vQ^FFEO# z%*rpB=$D-IOJ?PlO!P}m`X#gSOD6gyC;gIH`6Uzml9PVPto)LRe#uF{WLAF3M8D*u zUotDdWTIbk(l42nUoz1zIq8?o$}gGdmz?xVX62Vm^h-|qCA0ENCi*2O{gPSvB@_LU zlYYsp{E~@&$w|LtR({DuzvQG}GAqAiqF-{-FPW8JGSM$N>6gsPFPZ3Czl0lct|$GH zS@|Wst)`Bbzu%N!(%Wh(m+woIU((xZDwpp|lwZ=@YAToSOO#(S(Jwjam(0p9ndq0K z;0C|Dm0vQ^FFEO#sGSGix7C#6OTT1Re#u0?Czht6c zl7bst56Ul@=$D-IOJ?Pl^tPIEeCe0W$}gGdmz?xVX62XkwwgL#=1ut}y{)ElnK$K^ z^tPJHW!{uuGSM$N>6gsPFX?SHb-c`*@=GTAB`5uoS@|Us{gM>iAaBYqndq0C^h;*t zmrV3aPWmOY@=JPKO*wD$OJ?Pla3jsD;D*On&2RKeQgB0VjD!2vD#w9-$)fy{iGImRzhqH>pq_@>nF7mc0zofU-R4($iD8Hn))l@F#H?@&wT3X<9o%Bl<<(Krf znmS(0Z;SFvdRxs6H$@)!{kAB-q_@>nF6OsI`6a!rrgGtzEXptGZ8eq4yeYq=x7AcG z^QQcg-d0n&%$xE{dRtB9GH=Q+>1{QY%e*PSq_@>nF6TGpm-M!p%4Ob^U((xZ3YUJ# zqWqHHR#UmmoAOI~TTSIMZ^|#}Z8eq4yeYq=!7oWs3iGD?lHOKR$IHAazofU-R4((T z{F2^QQ@PBW@=F^0lB?jRKL0MtFKO^gu7VqKjj!C`m!!yp^PBQZdRt97zVu5L<(D-0 zB^fXCru>rLR#V5zyeYq=!7s^pnK$K^H25XqGH=Q+>1{RjI52O@FKO^gGG69Q`6Ug0 zNx00L@=F^0l5m+f<(D-0B`NY?-jrX`;FpBU`AzvH4Sq?u%$xE{8vK%QnK$K^H25Xq zGH=Q+Y4A(JW!{uu(%WiE-sqPs$}ef~OEO;OP5C7aeo45@oAOH<{E~2)H|3W!_$4Xw zVBVBp(%_eb%e*PSq`@x1{QY%e*PSq`@yqkq7gp{E`O0BwXfA`6a!rrW^1{QY%e*PSq_@>nF7u}RlHOKRxqO~feo1eusa)nw`6a!rrgE7# z<(D-0C0D@>e!nTdq_@?S@zO6@lwZ=@YATm`Q~f2qt)_B0zbU_@x7AcG^QQcg-d0n& z%$xE{dRtB9GHnF7u}RlHOKRxy+mLOL|*P<{{;m^tPHhUgk~tCB3btaOsyU$}j0{HI>V}DZiw_FG=wT z^QQcg2EQa+=1ut}y{)Dm2j)%rCB3bta+x>PU((xZDwlav{UyDvrgE7#<(Krfn#x7q zR^^xUwwlUC-d5$8H25Vc^1$!6Rrw{ot)`5Ze#xr*lHOKRxyak9{F2^QQ@P07s{E4P zR#Umi+p7GM-d0n&$lI#?lHOKRxyak9{F2^QQ@P07s`^WMTTSIMZ^|#}Z8eq4yeYq= zx7FNoQ*cw~<5l@3y{)ElF~6V}DZiw*)l@F?ru>rLR#UmmoAOI~TTSIMZ^|#}Z8e2UzhqT@NpGvET;@&r zCB3bta+x>fm-M!p%4Ob^U((xZDwlave#wmfk}U-{xKAp-q_@@7@iK49FX?SHmCL*- zzofU-R4((T{F2^QQ@PBW>M!YSHHAyRWL192jQ)}>1vj`JlwZ=@YU+5IH|3Y~wwlUi z-jrX`+iEJ8c~gE#Z>yV}DZiw*)l@F?ru>rLR#UmmoAOI~TTSIMZ^|#}Z8eq4yeYq= zx7AcG^QQcg-d0n&%$xE{dRtB9GH=Q+>1{QY%e*PSq_@=+F8z{K`6a!rrgE7#<(Krf zn#yI~lwZ=@YATm`Q+`QrtEpV(P5C9gt)_CBH|3Y~wwlUi-jrX`+iEJ8c~gE#Z>yV} zDZiw*)l@F?ru>rLR#UmmoAOI~TTSIMZ^|#}Z8eq4yeYq=x7AcG^QQcg-d0n%^h;Ld zm(1udN%08tru>o_`{RVmyeYqAMt@1T%$xE{X6%m>F7u}RlHOKR&l~fm{E`{_<7B+d zoAOI~TTLA=^QQcg-d0n&%$xE{dRtB9GH=Q+nbBXerQindHI!d6qrW6v=1ut}GyRej z+;F^E@q71r{~7z^WW3Cq@=JPKO*wDuFIkmeGGl+7jF)*+eo1euspDndlwUGqf1He$ zc~gE#Z>y=}W!{uu(%Wh(mw8iuNpGtuT>2%e@=Ip)muxAxK`xYEGSe?f!40`8Z}dx2 za6@i(Ou0YD*dHgyf%BX4OJ?kk6E5?n{F2^QQ?Cc+P5C7=`b#oi=1ut}y{)E>7kNu# zfjVz>f1HdLdCLk^#jX2MZ7H~^*I8EDDQ@jA2^V?GiXz3W`{RU*yk(__;@16f!bRR< zhzo9St0~t5_s7XrkBVFO$H{n+x0r;ATlb?17kP{6rnq%Ks&J9Fm`#dX`%A)Q-jrX` z+iL20W8Rcs(%Wioxhc3o-jrX`+iEJ8c~gE#Z>yZ^|!O*k6)@8;)1yjebcAZpc;h8}`S^ zabVt*U$S6-oN$>p<(Dk%FG;}-j)U?`7WS8<;D%iDJh`yHBn3C*n&-)den|>$$TiQC z3;Rn_a6_(no?Ng$PVO?yoAOI~TTQv|u)kzee#yfAk`&zVIHrLR#UmmoAOJR%O= zqB>sYP5C7Y{gM>i;CfJg$wI#*1vliXywNX7!40`8Z}dx2a6_)j8}`T9QgB1A${YQX z6x@)jo+q!fU9Pj8c~gGLLcb&hHyp2eo@9SX3U0tve#vs#MD;i@Z^|!Ous_b0f*X!k z&2RKeQgB1A${YQX6x@)j@@P{dO+5~~@=F%%kF%xVhFq05?2i*J z^0q6#WVvjja^C2d?8-0cZ8epPyzR;_>1{QYi@fd1FX?SHm5aRX$}j0{HI<9J?aD9d zZ8eq4yeYq=x7AcG^QQcg-d1zVO~DOvq5P8GR#UmmoAOI~TTSIMZ^|#}Z8epP`E6Hz z$$Fjb%4Ob^U$W9KNx==zo0;EwTTLA=^QQcg-d0n&%$xE{*6VCnF7u}Rl9hf*3T|+G zm0z;bFG;}-x#oFtrC*YQ8*$$Ti>JR{A9=xFJ{NjebcA zZpc-6qhFGO8*)|N=$EA6hFq05?vIm#8*)|N=$EA6hFq05`Xwp2Ay?&%`{ShGhFq05 z`Xwp20ay7YEB%rb+>opCM!zHlH{`0k(Jx8C4Y?|B^h;83L$1mj{gM>ikgM`Wza#}W zUFG;}-xhik;OHyz{uF4zzk`&yKtMW#_Bn3C%D!*i{Aq~L~Jl{fk&DYzk5<&Azx3U0_%d81#Ff*W#G z-sqR4;09dfm#p+lQgB1A${YQX6x@)j@opCM!zHlH{`0k(Jx8C4Y?|B^h;83L$1o()mBs9m#oa2@=I3wB`LVUc$HtW(l1HD z4Y?|B^h;83L$1mj{gM>ikgM`Wza#}WUFG;}-xhik;OHyz{uF4zxOHyz{uF4zz zk`&yKtMW#_Bn3C%D!*iUFG;}-xhik;OHyz{uF4zzk`&yK ztMW#_Bn3C*s=U!JNx==dDsS{lQgB1A${YQX6x@)j@{A zq~L~Jl{fk&DYzk5<&Azx3U0_%d81#Ff*W#G-sqR4;D%h4H~J+hxFJ{NjebcAZpc-6 zqhFGO8*)|N=$EA6rg9JEm#p+lX8I+E@=I3wB{Th!L-{2u{gM>i@HnWv(Jx8C4Y?|B z^h;83L$1kNZ>uT4FW6slD8Hn))l@F>b|}B3x7AcG@^&b{q_@>nF7kFLzofU-R4((T z{F2^QQ@NPm4&|5hwwhaR3T|+nDZiw*)l@F?ru>rLR#UmmoAOI~TTSIMZ^|#(=$9qPen|>$a2%9hve7R|!40|Q zd9t_Fl;c3ZfN^+SuwLebQ3xP|&>Mz;om!#l^Ts6PZFG;}-x#suVM!zHl zH{_b%ZyWuR6x@KT{F04+NeXVrRr4GDk`&yKYu=Y^^h;83L$3M#w$U$H=$9O7f1Hhe zNeXT_UiJHpen|>$$W`+j{gM>ikgM`Wzht3ba;W`rHu@zC{gOlNkF(J)S?HG>$}idI zmn`&44z)kdM!#gCUvjAZaW?uT3;mKq?T@q3FIni99BO}@jef~OzvNK+<81Ux7WyTJ z+8<}5Uy_0wMz;omn`&44z)kdM!#gCUvjAZaW?uT3;mKq^_Oh)OBVVihw3lc=$EA626}iB`LTeSLKa<$wI&6 zQ2iwv{gQ=#$)Ws`jef~OzvNK;B^&*cg?`DQ`b&CSO}RhNFFDlyI2-+v6x`r?xQv6l z_tn_wm!#l^T$MNaB`LTeSLKa{Aq~L~JHNVj>S?HG>$}idI zmn`&44%J_>(Jxu(mmF$;oQ;0TLciot`{Qi%OBVVi$7LMcpEvp?DY(J)a2W^pbLp2X z^h*x4Kh8$KBn3AdugV+!k`&yKtMW#_WT9VjsQqy^`Xvkfl2iF58~u`ne#xo)l8t`J zLcioxe#u6^WT9Vjs{L^``Xvkfl2i4UZ1hV~a8s|dQ}vhhwwf}}(=R!dU((xZDi?V> zm0!}^YAP3bJC$FuUuU~=F~6P4FX?SHm5c8Ir}9gBTTSKSd%&sulHOKx%T2)zt~2GA z^tPJH#qYOM`6a!rrgHH-c`Co8x7AcG^QQcgoqkCQZg_mn^W;vyBn3C*n)z*~Uy_0w za?Sj<(=SQE4Y}rda;IOCf*Wv^U((xZ>h-|9ss56k{Us^5;dssWx1D}T3U0_X?@M<2 zB`LTe*E~<|^h;83L#}zA-07F3;D%h4H~J+hxFJ{Njr}DlxFJ{NjebcAZpc-6qhFGO z8*r6hvePd~!40|Qd-qPiBn3C*s=U!JNx==dDsS{lR`!>i$}idJm!#l^<5hX1Uy_0w za#h~wm!#l^T$MNaB`LTeSLKa<$x6TERQu!X^h;LyC8zRBcKRhN{gU%C4(|Rvztb;S z>6e_BaUi%k+hsncUvgf?f#BwBS1#u_<(KUAOIG?N=Vct+KVJGJEB%u5G7bb6{$vVn zkc-PW5Zs*YdVHBT<(KUAOIG?Nr}9g7`XwvU$W9KIh9|s(=S=+mz>Hk+3A<8^h-|Vm+bUQQgDO3DZgZ=U$W9KIh9|s z(=S=+mz>Hk+3A<8^h-|Vm+bUQR{ABU@=JF5B`f`sQ~4!3{gRb_$*KI3oqowmzvNVY z$xgpyrC)L?zhtLhveGX(m0z;cFG;}-@}~TfoqowmzvNW=6fhZOU}zU5L`Y_(l0sH{y01Rk`&w^$7+9^oqowmzvNVY$xgpyrC)L?zhtLh zveGX(m0z;cFInlAoXRiR*6e_!FWKprtn^FH%Q(0{7xYV3`X%RO z90)G+M!)2|j03^t?>G7-r`jK9r(d$tFF7ycK#Vtc*K(hvUvetHWT#)U(l0rcU$WCL zS?QOY$}idJm#p+lPUV;E^h;LyC8zRBcKRhN{gPApB|H6+m43;o{F0r1NeXT-4_(H= z{ns!3l9hhRsrJX&>6fhZOHSpN?DR`k_$3hzvV(&-4!OIQ9K$aOSG}L4U$Vk430J+J zq+hbaF9}yYPtq@0;g^J~o+s&-tnf?1HS=3{Aq~L~Jl{fk&DYzk5 z<&Azx3U0_%d81#Ff*Wv^UvjX&Bn3C*s=U!JNx==dW_~;9m!#l^T$MNaB`LTeSLKa< zNeXVrRe7Udl7bs@Ro>{Aq~L~Jl{fk&DYzk5<&Azx3U0_%d81#Ff*Wv^UvkhdNx==d zDsS{lQgB1A${YQX6x@)j@opCM!zHl zH{`0k(Jx8C4Y?|B^h;831FrH*4*Df2xFJ{NjebcAZpc-6V}D5sZpc-6V}Hqp{*nme zDsS{lQgFlZs=U!JNx==dDsSvBNx==dDsSvB+0b8-ifUEqH zgMLX0Zpc-6qhGSYFUi6Ll{fk&8~l=RRo>{AZ179MRe7Udl7br^UzIodB`LTeSLKa< zNeXVrRe7Udl7bs@Ro>{Aq~L~Jl{fk&DYyYw`6a!rru?3VUy_A2DsS{lQgFlZs=U!J zNx==dDsS{lQgB1A${YQX6x@)j@opC zM!zHlH{dG2q_@?SyumNYf-{vj`Xwp2;doWv=$EA6hFq05`Xwp2Ay?&%{Usaxk{n-^ zH~J+T{E~20-q>G~f*T$Ol{fk&DYzk5<&Azx3U0_%d81#l!7s^zN%cK|en|>$Fka=C z9P~>z_$3*y${YQX4Sq?uDsS{lHuxpss=U!J+2EIitMW#_Bn3A-Zz^x>FG;}-xhik$ zFG;}-xhik;OHyz{uF4zxOHyzHuJTI``Xwp2Ay>_B^h-AQC0Y2a@S?UOv*1g=$EA6hQ~qWjef~SzhqK=NpGvE#{s|JCgqp( zwwlVt{5C1Sq_@>nF7h@hzofU-R4(#1DZiw*)l@F>HYvZPx7AcG^QQcg-d0n&nBOMl zm-M!pTW-7>6x@)j@m0xnwFG;}-x#suVNxvioH{`0k(J$HQmrQDZoRfaZPQPSQ z{Us;;lAV6Zr1r-->6h&EOD45H&Pl%{1vflzDsS{lQgB1A${YQXoqoxr`b&CSO_|^5 zmrTkpIq8?A;0DJ*^_QIVOLqDtlj<)y>6h&EOD5G{a?&r^>6c8(FX?SH<-E}^nN)vC zZ>ynF7u}POL|*Pqnfx7AcG z^QQVsdRtB9GH=Q+>1{QY%e*PSq_@=+F8z{8^_QIVOHy!yys7?@-d0n`%e<-nlHOKR zxy+mLOL|*PM!YSHI>V}ss57QR#UmmoAOI~TTSIM zZ^|#}Z8e2UzhqK=NpGvET;@&rB`5uo6x<-k$}j0{HFdnqoAOI~TTSIMZ>qnfx7AcG z^QQVsdRtB9GHnF7u}POL|*Py)|6k;+iD7zeo0e)$w|K?1vhmbYO24ax7F0~B5zIkCB3bt za*?-Y{F2xMv1Kb4d27Zm2{&JVDi?Wc#xDssUw@R7?FA0}oZ|pB=#xDt%d81#_j9(Hi z^G3g<8NVc4=8gR&&G;qZGH>iJX~r+fY8K{={Uy!#CGXp6%KIJmmo(#-gv-3KzoZ$z zBwXf={Uy!#CE+q}>@R7?FA0}oZ|pB=#xDt% zd1HS`Gk!_hNtieGmo(#-yl<;1d1HS`Gk!_9%p3bln(<4*W!~6d(u`jcF7w9zl4ksp zaG5vumo(#-gv-3qFKNav372_ee@QcbNw~}#{gP(H#j9-#f!OR=`OPcXZ!e!prU($?U5-#(`{*q?=l5m+f z_Lnr{mxRl_vA<+Ceo45@8~aOU5wkefT6;9`DD!40^| zFPZ3G|nBP)xLvEfh?&s1k zNx==dDsSvBNx==dIRj$6%p3iZS@|Us`%6-A!||%TvA-k*H{dG2WTIb^f*W#G-q>G~ zf*W#G-q>G~f*W#G-sqQ{^h;*tmrV3aPWmOY@=GTAB`LV!aZq`qUy_0wa#h~wm!#l^ zTs6P3zvQG}GAqBNx7Cz+o_@)!{F2^QQ@PBW@=JPKP2tinnU!BM(Jx8C4bGeLOD6gy zC;gIH`6a!rrXB~*Z^|#}Z8eq4yeYqAqF<7N8y;VkH~J+hxFJ{NjebcAZpc;h8~u_L z+<>e6lHOKR&l~fm{E~@&NeXT_UNyhbFG;}-xoUo+Uy_0wa@F%B{gM>ikgJ|2>6fJ7 zhFmqj(Jx8C4Y?o9+yDBv*MEHV^_#C=UVZxNmw&zdU-I6*H;(H{_x&mj&p!@8Y5KjJ zgTVlj?V03GoEVmn1ar?pKv}d!gdzosO5$^Hzx(|?yJ~l>wf3&=>LMvJjt7-^I?d|+ zw%(uh?5oMQXCH6RZzkWJ-Q0fp?ZwT__06xI&A&ML;=|3w`-|I)zn*{m;@|$?|NF(+ z?d{FQn@_j;fB)|nzx)07-@f?m7ypJr4oTQ0S$a2^&btepWVE<{`=(P#oP0V z{^j=5oAaStvZUR`=f&w8bz8CqFzn8qcqR{SiQenCg!j5F(R8_;yaDfZdVURXnjPrkxxw%Cd2!zB^t|5d;+VnjWw*`Iq~F)+ zdA--^`N8jHxBYvap4WSI$j{I(7iX7W{M+F7vfKW>PS5MTPR|d1FT3sE>-4-7A< z_r|<9>l@@P-khhQ*AN<}ZZ>K@tLSB6Ed!xMhytvkPjJ(CXIO`kb&F94j zk2lKOX_Pmg7a#oIAa5Zr&N}$K_~7>jd4u@fnp(YgjJ(CXIDPw3-h5ts@OXo~LHr)a zJ4)U{UYzkpdGoy9L&qEXE_rX1H=h?D{N5mMAuq0d8)M&Qq3@FM2K%<~yxxPy8|+)i zi!)xI7a#oIAa5ZruJ?|yZ?n*M2|q-%Z@%wx@OY!V`MkKsJ4)X4`_>MHytv*w#=gx0 zuQ%%u<<0k94qbngU1`?&F956 z-cj-v^5Tp)%A3!N4;^pFi}T(nZ@%wx@Oz`Y`MkK+VU)auyg1{H^5*+42ah+(o6n1D zyrbkT^j$LEC~rP5K6t!Q-hAIBo7{*LSCHlMtSpnmxIR}<;~~C zHQrJ37V_eZH_DsOiw_=elsDgZ$#{KUeDHgty!pJi-aAU(LS7vHt|)K5?{e^XqrCaN zxW+q5-a=lS@kV*`eV0SW8}j13H_DsuyBz%9C~rP5u5}nCZ=vs!@kV*`eV2pB8|BUS zU243eU?{e^X zqrCaPOO1DwyoJ6?#vA3$_gxMhZ|J+^y;0tL-{s)CF70q=KC%Ok2lJj@4IBYzVCAId!xMhzDvD#l)Qz$OL$PDy!pP% z!Q+kc=KC%+-cj-v`Ysu7lsDgZIdr_C?~?aMdGmdjgWntF&G%hu9Y)Dp=(}XRQQmyt z<>2u~dGmdj8t*813w@W2H_DsuyBs{;C~v;+lJWY!%fauB^5*+4_1;nP7WyvX2afXQ z`z{BMH_DsuyVQ6`$y?~VWV}({eBb5J@kV?J#P6Z5Hws@ei}(_V-{X5n$y?~VWF4Zs zjl!4ALf<9tjrF%t_>x)ZyX3t=-oWCFz*Wpb-zD!2_3q^;e90{IUBYi2>Tkx)Z zyX3t=-j<{AC9}|X$$LY+dpQbUG7Ei|yf?_(aumKKvADZ>VZ@g#ec$CkIZiC@{=Gro zmcH+D@O#m&{=Gro0LP6uzlp`&zc)fiN)Q&H_F>6d`V()_wSAJ=KC&(o?nkI(fS7awj6~o znR|SR-W%m@6uxBc`!4m~C~s-z$Kvqj9$%vOMtK{BFPVE@Z@o9l+bDd=-1lATy;0sq z;Y;QoU&4DMzGOKHUo!W+-g$=vr{>b+6kM&U~mi@RUnC~u?iC5gq|zc5{tWkZ#op?%x~bZ4|yFvAFy9MtK{BFG(!!{=HG&M&U~mi@Ses zl($j%lEmWf-y7v^6uu;}xcm1;c^icr_eOaeg)d1g?*6?|-bUd|5{tWkZ#op?%x~bZ4|yF zvAFy9MtK{BFG(!!{=HG&M&U~mi@Sesl($j%lEmWf-y7v^6uu;}xV!g8e93YYz9g}@ z`}an98-*`PEbjijQQk)3OA?E_e{YnxQTUR?;_lxYr_eOaeg)d1g?*6?| z-bUd|5{tWkZ#op?%x~bZ4|yFvAFy9MtK{BFG(!!?!6ITvK)mkNi6REy;0sq z;Y$*WyMJ$#w^8_##NzJX8|7^jz9g}@`}an98-*`PEbjijQQk)3OA?E_e{YnxQTUR? z;_lxYr_eOaeg)d1g?*6?|-bUd|5{tWgZ^V}@N8w8ni@Sesl($j%lEmWf z-y7v^6uu;}xcm1;c^icVq_>#op?%x~bZ4|yFvAFy9MtK{B zFG(!!{=HG&M&U~Wr3`udh%X70GDGWn9$%vOMtK{>Uy@kd{W?T>8-*`PEbjijQQk)3 zOA?E_e{Ybt)hK*PVsZEH4f3`cg)d2LHSWC;U$Pp7FG*}Q{=GroR-^DGiLJ)JH^|#+ z6uu;})%f=Yd0UObmn60t|K4EVR-^DGiLJ)JH^|#+6uu;})%f=Yd0UObmn60t|K1>P zt5Nup#8%_q8|7^jz9g~L`1eM68-*`PY&G`15Zrhi-f9%SB(c@__eOaeg)d2LHU7O( z-bUd|5?hUbZ#op?%x~bZ4|yFvAFy9MtK{BFG*}Q{=HG&M&U~mTaABjl($j% zlEmWf-y7v^6uu;}xcm1;c^ick#E_6uxBPdA)gW#Fwl_;Y$)*ja!GvU$Pp7FG(!!{=Lz@ zjl!2Cwi^H5C~u?iB@54AqV)f ziLJ(uH_F>6e91z)?cW>aZ4|y_;d#AThlnp(jl!2Cwi-9y$X~J=g)donUT=*z%G)S> zNn)$<Dc^icq%k-ua$3SYAD_r`0yQQk)3 zOA=d+A8(YmQTURD=P%KCqr8p6mn60tKi(*Bqwpn(t;WAM%G)S>$->_ouXTv>HVR*o z*lPTEqr8p6mn{6f@fvTGw^8_#g}*nR_eOllY81XCvDLVBi2Nn1QTURDzc*gvjq)}M zUy|5r{CK0hjl!2KJb#JC8|7^jz9g~L`0+-08-*`PY&HJ9QQk)3OBVj#c&$T}w^8_# z#8%_S8|7^jzGUI=jn{aiyp6(_Ed0Ikyf@-YR-^DGiLJ)1L*y@6jl!2K{JrrSZ#m{Z@k7E)f3(sGo@kV(Y#b1)xYW#Skyp6(_B(@s=-Y9RQ@Ffe+U!rx0@-_-z zlGtkec!RvHN8w8rp1(xn4f3`gg)don{u16B@g>|8G^S4G`AhWPP=ABjXViN`fA=i% zm(bxo>bDxAiD|Nn)$< z?+x;{9)&MSY&HJ9QQk)3OA=d+e{YnxQTUR?R%71_63^GA*Q4+yiLJ)JH_F>6d`V)f z@$U`xZ9NKKlGtkedxL#jkHVKMBYz15H*tMoNISajzl{7P5ZuJ~_VRQ6@Bi=<0sZ;A9QB4Jb^e=gNQt0GANlcSfBmqcf zmb4oAPLfq*5lQ%wts#v@4uo_Cc_fkmWM>Gi$$5~TAhsmvCt@SGBI+e%A(kW%AdGn5O+5+1&%RnxL*-L!C8IW3*mj>V%Q&ZEWUdn_OoTpqs18tR&k8LOykp>>7x zjD@5^#>4kmOI;7Ft9*6suCB<{b+)>CR@cOm+2`SVtg5axow0Z`R*y^;58q`0$>#9z zUDj~MB9eXJ;d`tj5jYRuV<|-|BnqH8a}tG!=srZvp|&wvS-KPT>h|oX^T~Ab@3a3% zN9yMK_U!iJT4!(ioZsTnfAjD+w>M{3A20L&{)`Xx&nXK=8ix)=z`iWMK4&azOxy0C zHE#eyxTMWvy4l5euHjShBsdSrW_fyP|pV^+S;KAeH zXuIS>pYq+1RJQMab^XI%&Tl90&d=UXemMIu`S`=l`QIl0GMheI%qM@JOrNjf{F(cf z+tN2cvDTE=SKIaZGmZh%Tf^$MU9XrTVy}U0w#)63n{u}-!RC~M`)vDsCCa<)mi#fX z&ve1xZfi?8+pGy`*J~Q&=t1OGEnc^s5^TUEi4TWg$B~>qXM?9}AfX)G?QFAKJ6tb6 zKW-tty}sHrO%fq-qAcXzjpo-^+YOq2yIF&q((z}oe?f|k6(TF3>M+Vuj&GoWU~{f{j$rKjeK!i>tc5Vv6k%sU!MK&7ls9uR(ZnW zjvcp|2nhst#OUe#q3)hfH!#a|Dn!Yed3kpA6Wjcf`*1I=ewus< zW7ade{$|Z~8$JGbdTg^J(?6R%M@&wopFzK}YtPt`1`dsdPqI7Q)6?DJ$?+We+ZEMc*s`6D z4K|G*^kdd;vXSd0cJEZt87lj91F;SFUPB)wSAefT_)pL1W;xrE!Zf4)ES3xT!w%4y zuyaw8_^m+2V{4m#Nc(G;cwpV~c8hyAD|R;{ChdVvLx{42wP2{z&2+VFoE|*c75RG{ z1?NyH;A&4qXTQ1ncz$y``7Msn)u)=5#bPb#Tk}S9=VI+Sft`&S=w$mhwW2mFA65N-`Gu>Ua3z(wM!yr3Xs^~dZ(Kjytkkqq_i9}58f&n= z_lvgw!1l!i>TmEr->5{43{>H4U1LC+}Hk*YxlJuXf@c}@q z6CY4V`EtX38znEh{CD0oupFE!TunVuID|6|Qc` zClGcnNmg}}>~v|X%?C@TIjx+K5EN@+vv1*@j;S2qIE{*LA#Bs>7IR0FnC3vDga41k zgM@(4yPH9wi^t4Bqm|6fpYwa$TB<1ogwTzr0%CPUh3MA0{s@KfS-W`t*J> z`&R|lzdrx_U5~UyH#?r5HgGljum- zQl>ubLdQmz`BUFWJD!gzhx>odZ>}fr&TigLKHgq`sN{V34Wfw^^|>~Umk#PKn&{nx zPMfx8?c;~DAI@(ozrZvOq-pz)+7Vi?h+;d}XtUg|$=0H+F|_@z(SW5OXPR~F zJl0(4))L15sW_~Xj3V(x=hOld*!;tr`qEx%bMgnaU%S`xUUv))iZjldJJC;)PxZ~F zHFhRky;MU7pN*pNKCs!F)oQg_DL+9-n|x%QlGEpya&m++=F`=zIU)1s_!YQ*3i2r2 z%+H@Kq^7;tCXW~JLss)immTtW)wTU=mKyy*phX14y%k)JrGhi7Ny=Rc zIA*EToV9nMiY%2m`;3Tm!wLi&UIcvWs$=sRrRGzPG;t+d$k6gD4_x~!{%u8erkhjv zDX`!qi&tB86Dv(4E7=Z;BV85q!$-aI4-N|H& z2mR{9<;B(cpI#+r|5uHF4@98Hc^>69sf+OOWoW3gpl-Fj2g4M~O9`r1yVLDI1EtCYDi`q@Uq<|NXw~oO(|m&7^Tg ziN`Tj)?+#tjZ=#WV;U*V2T~(kUS$p`TB%9ot7UcclHAqfuO$0u)@?k@o^VRdkweFu z!znM!?BjiDJ&t)Ej4&(@8%n6nvYq*RP!zXxo5l*;44Tk@i-xan0PSj?mTi#GZ(#Dp9z>#PV=4GoR4sj#qZNQb`(6V<#bn z79S~~96bF3xN~roBom1ZbryZLEU7XFQDSsvFr7;8KXIyM0`%Yl9hKV?#;C)%^&}|O zQhcmjnSH#gCKwj;D)z6z1k}me4*md4zzjL*^YkB5?E07D>~KuB(^Cs`!^i71de2g- z+j;0xR_z-!BWKoURUMd3z0vI`&M(jZdUkt#Gx@1;%}A@B zUA?{j@yEKtBBZD4u-*cF;jXXRAwB%#otEDJ<9ikl z?&+?`-&cKCmwG!+oANZR3JK@fe&xS!&i-tEI2>Fm5uGtef$XFkm^XUOFz@$U*1#(T&`DAhsH98-cm)7%9P!ZM^E##ofl z12tD4oLL#;-3fl(r%&%{n)VN>NA4=fx*jZr`nvOZ9$NM`$Nk}VpVSGJvQzr6PU&k& zyFWA&B_@G(ZgnF-(7S12n<2V+h#7YyB_GAne~5m(}ztR(wXxtipM4!EMqZLG=x zD_t8t6zIg~Uk{=L*E_FR)CzmYSL9#IDC|%|zZS2O8Oy)hlhb&-6y9*mFd=T9#T}4I zNV4oi#k;6{RCPG^p&kLYQ=Gx$4){=!N%)-~<12N(#=r^?=XEdwqgJyJdqF#FdvJ6%^p{H=NP~>ps}_+?PsFeXvcO3i5zjN50+$Vhgp;k z?P$v)Z*kTRAX$1cgCg_rE7BiK)Uwy?Ws;d4sQN%t<-SATDgF81=k=(yDo{SRaxiQa zLqt2}{lZl&@!ph64}MU*5knWaYT|2JUfP2v{!c|*z}NOcsQNN3VjyY9JUr8qrJ@;H zX^5oSsreF>H&6qbe~BWu%eFV92WueGlDvEgHfFH~#RlEiQB(_d{@K*L*x($dlRwar za`D62WzXr<@85$YsQWwr{BO^Hyd~Cb`XWA>zK92$e5WOw4(G|QFX-pfLc~}Q@!wxA z;S0*HQ9Iiq0ND0}*){dO=M@+Mkx0YZjZObj5skfBzaDAEQ962D#YXK_BR%1#5afdw zq@qVygQzW9B{Ecz?8yNcwAP#+@Ll*I#)3TPf9%Fk8aIYv`9;u>r+fz&(m!jM_AZ?H>)PS zv*%zv=|^3z>Fn6h4GQR!3L10qDRVgm-nCX?h|3fCYdS(`%@o{3e_Lz{@2Zy2Tq}+o z_5M~Iv5|ynj@=VTo|J0F>nAl3* zm+{1EyL{BR;KQa)+VydFMM|-0cekb{ zbLQ`;(fRYesAJ>ZI2be))ZJW;2cw(u8+nyaR>&;%8}OsFceIgHGUo>)C(%CTrQQqE zo-=(AiBSL0)CsT8Y}2AMAV&cD4N7)PF;#@+tQ584Qw)%Je)!)2iVG1*SO>p}C@1-V z4s;q4$`(m2v;Nt|M<^Cp7ML-8o-~NSDKwogLDON=a9&PfdL?JJ**Fr0&c4(&;ln9m z(`CGih9+W=i6Ifwykow0Xo0xb+c1sG2NhNJHioa#`4+Qubhn-JYGs)q$zXY z=#XDgKh=rkbg%gg01vEbh6zBonB{cDkuGStz+);SB5lhfD3gL_H7lNBY5`$((L<~# zoT8iAEm2Be_pecBQI3s($~AHtV|;E=9Cvxy3~QTPug~T<>0-Y25Y@+WM}x-s-4p)x zReVJMmxuLq_RTawf1B};J(OLwM21d#g_f;2@vL|yE3;8^X3_^epaoGS?$+$YS% z+b8DHe3TCuyod0+$`;^WuS+)#df(uv91km6X)GF+;;Fk%)kC9x&Pd-m7(q#KKF)DW zg6CmM)&1DNK7t=H+2$>?b$oNq@8(8Txorkx(nYeHhj*-~8vG*R75u!E+W>BosDzgn zPlx71+7o%;6D|ViJi1dd)$~gnjd)<^cvcgq4F^%5#?3(k$ zt2*f38Fm-*Kax6WPnzVD{PPq)m(VopRF877)U7{ErhU~GHcf!}thpxJ>_aRCnBBilsBCJ)~Ov`hA#hwp(eoq^W`)xiZS zuzvy_B;4iUrW|U(1TQ>XmNS*|&FKm9YcDV0VZ5DuleO>BkF_-b?G|WQXzy2mNK9E8A(}6?Vl{6hXwOTgsxiObVqc@ELH>yD>7*C zhELUa;^j@ci!T|LYtEm@5H~c+^FJN-7j#Y~>;S7+}h|9O3RdHuKZo0G{` z-xI3MUdDv%fSEL;Y|r9UX1iNfKo!{85R)7`9aZm{Qqhc|+j4$U)9DQ2FJgB(`}m8P zP8ZS*oX(Wogm@pxlhC6F!#biV&2UONl`EDOIBw8@3mY(n16f_@Dpz2a|t8HZX8Y z4l3ryRA+{@;J&8wNOnfIinm7fAAKfWcJUv5CciA(Z-^A`YhxZ&_V3^JKbGv@zuAAR znH+8L51N-pnu%d)7$_{Y0#OfsuU3o@Y9usTaPiy$)QI6*sK;OMe7^m8^8Gh|Sbq89 z@^bRs+0E_85R(}Yk>S9ChFlb|{&icu-x@%vC03>K) zpiqmD_j&rHI0z=Vp)b%CC~cA*v43b!-*83@+7czbDoO30>O*b0M=7w*i2qY4u%j*g zqijlN#s3*L#c*T{l$57xRSaXsKl)65F_zwNZ`{|OJf@{LG#|f+>2%iq7cre*R(ju1 zp4`{&JW}Lhh*0ipCXcEGIuGF&FddaUv(JBD(|Me8rlReUGkF9DQ)T5m%KLOM3kCzt zEzQr90F+G-6o7%VyBobJG7Y?7LlyEoonz6}26d3&XX!tLL({+1f~?ezRqw<2 z4&u)Y2!TrS3H4+ifB-Z#>Kavg!+E%^6(HAqrZU@p)c3qYefzRJ(*(#3ZFI}(BUE_+ zavRbBey6=p*pS%lLlT+gJsNH@U}!aL8!*qnZ^CZDdbpq*PD- zy;7bkN4`<{wG=y;ff+R34c?#Y8}a>25iJG@l2nK~pOrE*`$8<)&kB zP8S|GP4MtNx~6EiK?1($5Z|m6%_KC4~x`F0l|5#woOR=>m>K%F#hm z`k-7g!FjHOoYo$^Suq)D&H*K$6n-2%n?9VKoQb1mbByjQ(SS)8p$Gh}CkN|oa(D75 z@6U04+NZ2DqrZStW|(Y#3A5=e@u1l}j?5Uon|~6SF|0X*_T_17X2ZZUXf{t;of+Dl zU%+I3Q62yeWVWq?w&saTP3I{Ln$6Renj@Wn$1ya9cIcnP&=^jmL5J*Vi;ST_`X$V! zOB?(WX49o72F<1i%2mgGDFi*(_fZWsL3k~7NnbT^b_g$%&@tpm`w?DGS|=O!rC~b~ zh5sq#G7L4-FJLmiB-3wrng;F6$n zHm5fZq~U+!ThmoG25rp~pUp2S{-@w`RQ&(6#pXyK;E5l!Bjf+4JsZR4HAo3O z>4Rp7!v;;}iEm9;>mM|mL9Ib2b#8zF`f2hUHYh&$>IsMvmIJ)L=bj|6RzZ~ymYaCHVyMY99WEGRP9p z9Gv_-e2?{Bvfd=fPav&4S+PDV)@Q}~09ZeP)skm^0u$1SZVdoOhLE%%xEIgntFNAM z3GH-}T?8Xt$WtOe%>Tje$B!5|62_I{<{!yd_+(vUT3YZAcOtZwE%_eldc*v496sI+ z^6_-LUY@Rmw_kV6Yx0KjG+I=BA8LJ(aC?P{TyIyP7Asa5piI8fwvAxR)4HTkO2yfcy5pmlu<7&pzIs-z08`$sgulzP!G@y?#GQccV;x ze|7oug@7kTm*)1Rzd$?Z5eQdrkiFN zHYn({4AUv@FC1%VdUOzfsc3+^)TUdw1J|4GvMK_Qog6&EDj3ePRtnGmetUlPu@l0{ z&F<=x2RoRCYOGHeOwvh>8<$Z$eO`;57=ZLvz~ir#%smK(1#sRmN?$S@Z+OJ7-O8Z=1zn!-kwj|W&3b>c3WKkt;Jy> zdLq5}aj}L7Iv4zHHtAwRAnA*vPk5*4*VEg{eERmotC?mB4=_3jq*2g7%K9E7;Q`N*w)9+iTog0MT zhZ?ke$JTJ-RUW%c#@otz;30;L2B%M@<$HBQ?kvdAoi#(Q97`yA))TUa zx6mHtr{!PQPVWja=uR)rGp8kZGweyPGh=wVMmsb6XIv9wZo;OiWqL{!IVCWGbvUVL zKE~hOo^t&u;>|r^d|Fb~GaK}}nY7Lv;Y?ETNQq1Vl&2ilx!mejObpf6e_ozl{e=Em ztlqyTa9wWrua^X>lQxQ;eEItI%V)S+t3oH~5VBiSqBjB|a+hoRpk}&e^@KDxDhVVF zmS;gUH=Q#nf)WV)iR)He7{10D5eABIwWf%qq{6J0TbTQE=%9=i&KSYWj+oe3FhaB} zTrbbhC%?V8`b+DBlHs~~TXFwt8}k7ARcx_#S~{Ojy|P-RcC|a#Wg14w;GHZZqmAAL zM%BThsGB)hv@U(V7+49Y@vjYqBi=7ER@QeH9 zwNyKtyMEUT@ECSDo2}HzB~wC%fTimVPWhknX+1DlzdX(1F?ScY_y6g0ADbSGl*nJ? zAvibdBhvD>iyz)idK|6bX+Wudil!h9Lb$%=dW~gLWyLC@nBzCMN$V9#T}Muuz^rNt zFB+-Iww4u_kAR|q>bYXMNX_KwjgT6~P^2jMweT6A(*T}SNCg4ZXoZP&g6}9v&os;CO)+pnosMAdbY#k2g zlpGfkpIG+Sn5IQN7U|!*yn0(TbjImff6_2&4c)s!Ov)o9y-SPf&Yr;cz3%`SGOR}k zTFE5lsvg6TT%u;Pu^W$z9qf$=Imo7 z>I%nS39;g%QkKA;7P7P`yDa7Ckj5k%+Z4AXCObz5*?>8M8&i{`(_O-&e0N^C_V66M z8M2g+LVZ1&nxmA*w7r9Fz{q5o!)$xAoH_Jz=I^e~0e2*!M0WNsWg$EFU`hhjBpf

8MrW zo%f~|I!p80i}&Z3N|a6B>jLbYkNN4%&?pa}?h5O4bPH&h?A znJAEbiN$r7SX2!wAEWv9K-#6rw$Ld4Ovj}f*|ZzkvzgH`U2`!RH{hJkxp#)_M7mcj zZD+5Ks(M=3-Y>BA;$RW;6I`S=cJrBnrBQyW>WcEBI;K@xh5G~`;afDHziOUt%P-S|nIw@|W9%Rq*B4X#X=wv(Nqf?QQ=Kxs(- zQ6yh4b^8*3m(mitdocaOucgqBH=q;1k0|0?b_G)*P4c{T*}!DJiQ425&m32QlB6WL z6JicwWAdncSjv_JPbJBSH*__byMDbDiRAzvyKll}0k$(@n=Ktx+hNu@L>MsuU}7o z(*UKCuk+^m?~~h4Z<^TB;3OB6l{h0j;O(fMAXz-%?NSn{#jd3q7TRv|`rXaNkGDUo zA)o?clQ{vCM<|Jb6y_Jpq?KYnh<%o13)LOoTm`M78@7?1+W=2&sx~TSLPod5Tyj>c z$zJd;Tw%@a)8G?{o$&0)3{1&PAjTNrQ@}%wRiw&I(qf9fKn}L5k+qv+c&EPms<<=s zA7cugVgKFv->A>Mtr&J3P`8@W0AbDRJ5y|7p#)eY_5n8s(B_tm3-D7ufoc$?Lxjt5 z0w|fj#HIGDB{e(XaH|gFAY5xcrY|q9-dU{F?ha2YgFY{-sHAPkA zu`<76m{0Gdb=Li5CF9EiJ@6huq6fs4&A{O#qkzYMy2Ab(kp%KcrN?K0UR!%S(gb`2arf?9haBsz>mog8!5Kt_T>G z80nL`q>8-k3b+D_-+6uniX@1ar)zZdlF_8xdF3-e5-X72>YG7rr?OrAsL&wH<`md| z3lbw=$^4E&g9-+pXSkZb?toxBq}ZzupKe-M*nB$q`n!{W9s5;=i!HW=V=>0FM$jDO z0`bPE3qzQUJO8oYv!*tYCp0u+Vmv;6&3nv1@E-zz(KpGQra;wK@NHd5No@;vm?mo~ zHD63spO+sO$4+~)x5(0)BQ%6o!`<+FjGEEaiW)^w(3=SFiw|(!2Cio%4Sr~VTCa#D z>>Xi$svg(!$T1cU^1%jzgxr*n?GOw^cPX>d`hEDec@W2ehRbtRIcm~hdTK{bA(%-M zkW@3dHxDv1f`T8O$9o5m+1&?U1LY)qg#?k{2RFVFwi;rm`;(Wd`1YO0P%kyb6+_o_ zK-02%h3lDR=6{QR6gNqf%JpF^@S~sf(;9dW?GHF8N zT*XTeYCq$q3&79VBwr0#(>=_%$ok(mIs_k2;dq;!YCu#oTo>#**=PL824zGPM@Wq) zvm~=*G9HHX>A>-<1aqhnJV%-h0oiWAq9`pY-BNr=1WR|&5`}})Ph%%-gyl!IjpRBR z?n+=g(Zuxb@osX@pnEYE;N+=_B%cL1mfDa=%9DKn+r*n%+hG`Iw}AbsPa+Wz7fQBVlt+$i&XQSbwlAUB$vC(%#THK zsfjl0t$j#n|NAUSY;QmTd%PUb8GWq|xK!V6{@Eu|J1iiU374BAo7tMGKL@D~WT__P z-GmNZsZjx0*3ReyL^s8@@w-e>9YSr*jWD~=(W{$PMdrF4}Fg0(L{ zd_1ku*>C3n$C*6*i76Zr-|NvFnZB%qJ&ilPAUeaSb-%U|cNt;_9T5;%6a(`=37-hLQHQ58{6XT5$}7GD#0Y?!NIGaI zE|^p*&Sm8z#G>#m2l|^(UiI|4cNnqca`s}x3?b1yVZ@kDTF!gOTNqv;*MXMo^#S*1 z$qmgAb4d$;Z?gS08XtLG2yEc;0g6ZNx66?M^*MHrqkS5r(^#beN=*ngkSR&2QAXEn zj}9a>52C+HC2+HP3;9hhA0JFwZKd!EJnmWR^T(+Vn} z%kv*^D<=+mXpIhpv9&zzp%YlHdSB&i z-v)HK+5aL?Z5kv}=(%rbgTSulhV+FA`1@#$_SloV;s#=u5%RoaZV08uPA3Aw z$TD)wc`ZFw)JOT@qeX*;qbNm#;4h&#nWd6Qj0p3wyx(%^0W1xzIeFa=9Mhd7m3oq9 zX#h~UUnYiukM!V}&?@b07?xD&EzkTtiS065gEPV!_m>uG*9O5H0I&5@3H_O!9SZ3IV zh8}K{7I?_nQ7y+Qtn|a=!+m&eU1&CRZl&N#TDnn;uKiJ6&WFCqk2V*tANV~A4J;Q>I;IYzdZ=OT&P+f>mgjNG zo5UZQJe8%c1h_P=I7HMt!Pp;X?QtNS9%>z3Byu7D~17aA_vtZ?G3Nd#annqqObp;JJhGThVM{kV@K@J=j=6vs0o}J zjX6sZd$PN@RrKx9KuUE~*|{#lG@L~{1>sr^%^|}Wra&V9$GxL2c5q2X&xkc}N6`a} zE;&JUiXJii4^_IAtP*cd6T1h`&+r<(IX@Tu{{7k9HZy-A?Y!ku%{S^%X^+ zkLnr8Dya8xEfV7Pyh+33+q;dFiPEqodZQeSYf?LmMIVkwH$?cMzNWcw^8e7g`nylJ z`Rb5)830B(xp%NjrJ{4#i0ZP7Je^j5JuxFnIAXm^2v8cCH267a#2TQWbG$m=TDN(G zNgl(9P!ovsG6tXP>G@VqPkKsE&F|)tRG;7H~rv7v?gu09+Z)1@mY|GoG2c3Jv zxs!#vRgg5|Fz#UC{uQhfZL3(iJw51OE`HV5hi+TWX*x@1(X|XiJkk*O*gk2MlEB@`q*5v%14dSw zO>;U&fDXrasT)NC&jCtHf$| zkJNOLTOJbqIo(ACaYY|8GcmyJ1ufHrzOJ3ZI0S~}X+&X|w~) zOHIk3r?EuWTIK~ju$N8qk`2Qw<=21Tz~X&1`O|s|qxYwe?=H_jew=)JEg|{x>ucDs#*Y2cAVouQEC`eqtnfvc^Ud=60L+B$F|Y$fr=+Z z_kwSuOy;+zEln4d<|!T6Sx#u0n%i5#YPz(SBqr3`2U`#i*P5oLzI`Ef-~RewlVB13 z*=AxTH3|l6=F+4_Nk63X|?pcDM=-Zc} zYAWC=EA1%yy26sKK+Xqj?EIei`7_K()hyM6Z;#EA0P2bzbv ziSM>m{I9-#HKB>&catyYoi%q~)}_~25W0t{A@g8C=pW?n55=2WF&WUJ(6q9hK{?Bvj}(G+V&K7p`kU&}ma8(8L@OZ!kbsm8 z*Gz4V#xew0U%meR8*Xd)Y4Xk057)Yp=-YG)$t%%rMyDvayTlNhly#HHd}#)`tgQbg zA6$Ht*d+@y4?i9W<`sS2OgrV#xE&hySmg(3#YwO^63rxm=;t`ytP;sym)J2ZS?!IB zClfBbD<`qhvcMKO%%*aQ4Ib&B+A(*l)g`{At1o z+Dv}0f5RkhR+Hbx$t|AK5zlRYoOr?in!7HWadXx5nxjFUl@Rq5_z1@Z!mhNqoWfZh zKC&&Tccq-fRFJysla_QSxsM` z0LK+Iqb3G`_{*=)e?0qid3y*RhZun8T%ZH>~tKIY23AhHN-?De7LfObYwy!cbre`(@rU)C$8*m?q7a; zadUHh^Q&hKh}38e(NQ7NP#SOp4tGILn`!7MLVrNd2ucH}4E+OLptasmJ4)Hq|t3DQqGn};J2KY>xcGMjp%X;Z&|gbXVH=b2vb z8%>Sm8G5fmtMuzjR3LyVmWw-)F>#!A^E{QK_x~olnM^|D)$uU#`qA8$LD&y(@vk9#9L)b}wyKvU)%XH^^eD={LM;NZEkps&oz?HbOAc3U&07>2-cEeozn+%wal zrp!v7Sg~ilmY}W<_+_s-*dDKBU^irQv;g6YH7kJ8!YM&CbxS)uV{90Q;S{H#u>y!} z+A>{2OD6%Aj`LuI%lIk#fzjCExNC8M52h}GvZ56hqzu?B%@G@7v}NmyfyuxZqLCSj zZR?AbWMw0irRItf1N{NxAeX!)TnX9=-*%0f)HMYxxR%;|2qktR+ID|Tm{mEW=tJIs z7(?#PJDN$kt`i(y{eXU7wfN13X>PhU%B3MI8-7ZQiKX=&JF%L|yoZT(&dPBUGyd|5 z6ta9w9Ig#?`AhV(E^|scb4kgE1IA4i{0|IQMz55=d2MpujZO-a1IUZy!J%l=k#H{b z+Tg|vH5n7TNWCXFx<296yR#o}C$G7AzSoD2IuqwnQIOMyRM>T5{AVeQ^&h3UGP=*T zso~e9smV>*KQ%*4b|{jo?a~x*JAidgIsv%!A(4OTx8f7-$71uQGGPOE2|v<=r4R{7 zhY&d;vu$A7Fy6YzbYVgPLrKH5phCqsxvx$+ zH%5o+PIZe@D1ca%;&{;?}Q&NE0 zI3?~=kc6D1We-}u?&SHilA>{fN?oj`^XJb0#x85;FzgP=_gJ+5`JZTOc#EHhZjpD+ zD*2QiXLVhj2++Wq7Ixlhl4s|wHd#EKNem5X20Sd|+ZhhCA--yyREh~#U}Q+FiIoEe zTPY}J$|ZG}dCoj`9B*u;hLXbnX4h&nlEGS0!sYe}YEkkK?2IZCG71W7n;oBl6SA4F zr$WUt$L5-XR4FOzozY!V zDV|m3pN2=gcushzZL*@`!YM{UPmoIM0$$_U7{;`r*@^-2E=kQ(S`lROB~%2vDd&{L zZ9@#j1#ZleIFR_YCU12OLaaf>Kj&p+X$a16?TB<0@8T_{_z88w7o|%c{4PDysnSGWh ziYzh?hteJ5BbWK|QB;#c2r%Ie&Jvh3T{~U5d^Cl+CXtr>5SJ=UVTDhk8U14T z)rJb+qlJn%!MIc0y-n&@u8!P1XyV&kC@Cy*TU;PO($zRxCA(T*lS)IW8ofMza=XmR zjaN5OfQiB>Z%Hl^#aedsI{j_f)Qy)t@KGOe zzI{R!cZToz&uS*crRI|G@G6(~IFwK&p3PoeVOIJQs{F=Nc2rrrJf-1|s*8^v&Xc1| z#nl_iosyAGk)BJ&wV6~x6>&#W*nvRBcsGV-ZvT;NFtxfZvh?IWlTScqPxrmyAmSD@ zMPL`cH(H&1Dt-eU{J3(q@5PYY9Z;v0)GFsQgcFi5A5P#hB)jH5MUg6kuzyT^Qp+6s z`eDk55Z&PK;-^AI0QYAyTDE|gAQWxXVc6{qBJ;!b-_CEqRlNCG$*b$D$$$Q-?abxQ z&_iY5hdZ+*|EOnRXV}S9>Glcarn?i*k8Q>((G^3sxiiopS+X=f^)oAv5k3hDcykIy zO~tfwW^s^kWm%7vZp<+=?dlxIpV`lD6HAj=NoLsDb;*qV`?$~YBZg%3a3SSma+iqk zQy7yusTCq~a_}^VHpxW$8D374yLW$Db8aM-Asav@K>yb`H?1q%n+-5zeocY2jyxg7 zP$Ex0TQ0zY3xuLN8?URxKHAfGCWSF8ibwc#B{}v@M%wC z+?-Ny74HG>u;9bTovqsaEJDSp6^c0`rxDLdMnnLM?^(cS~1{5%dQr+vExqWQ8fqw(Wl5}GHiyov4~)Mbv`>pIe^O!LD7P|LEEMv99*!Ngw`%8d|l}TkJ5aY!{rNgI-B6p5R6a6G85FjHEjWBR@X3Ua4?kP(2x*<;;Yhg$u zpVXF_JTKdfFOnlVV0cZD#pQWT7Ta(^jt=OYf3@Aro9bn-aoB2x=3FjNGSRLb%4&1{V!h5kpOkv$E3Gc_PEN&duzhJjZkugAymH+9)$^ z=0#$&(Ia#u}1}9mZSEMr?;56zp?S1@K0z)!_Y|A(J{| zVM78le!`8%6_r?Xqp(;55iy2RlKm;bJ_gQeT6I)SSivr`f+>S$2_D*8$f(mGz(acr zUHH`YdH5cU-vpgJe2>OqIg@zHJbaH1Lo)t6e2-=@CdkA0Fmqr*m~7iS^wss%j~73E zx;cAudET_gy#91^a}L3p=_PUrfANKq?1$40ANw?yrLaF+3XOaUfiyws>^TT+5K&uk z#LVd^kS%4|Rm{TamT%8D(=EO61kC}Z0ED-6=TuI?xT@NLSTJRsPOQ63Y*W`Tij8xc zC-?RBCr!(`=<^leR9Y8e;eVkpUuZw-w7Pm^R|57EW9gY0R#1n0EviqDfVHWittuyq zf~u}XRCf>YjU-<1K~}N#y8s(#Y5*S<8-rZc{oI|E#g^x(?R=o`>*$#|peg-~ut)?! z3UFvcU?V_}suLuo4c#ZyIr){dhAe|^1}wt> z)JT&$8rn>v;k?{ULLAL;N76!clb|!Jm_!q9+gWfjWo_InC`%2S1@UFG6&ygeByEM8 zg-I?E5O-VgR~V$5LpH#jWYI;W`H<)(bY61^=tQ&7EJK>P+m-LvRbZAAVf^fqXMN)?CRksJ z%I?q<2eBJzO-Y9oczrfA^dSgm1x!rH2uhb#NnLR#AS|yxUD7LelA4w1#-bMoMeyg@ z`WZ4kImI(QeSwvWn-@+YHnPdcS@Ghg2^~6n4hho2CnRcX?hU1VBTRY?6@Oee`q9+- z(iS(}DFi5BX4-i--%P%`y!gNb0SsXVCcI@adx7-FIni%qwRIBM*>gq$LQ)847K7wV zI(s@YMq^|Bhyy?-0QcZfqr3QLnvQ906G^di=MgO=A`NS<;GhjHcfEjvNg^gdzB&e} z<9FdK)87eLJ)E8W>+;!rO2xKz@u^b)QcC(Iw?P2P!w%7wS?(>WvzE3kZIt?5xK)jI zERe-Cv+CeD6V*jaLVb10<4m~~wLO+9FeoyzP;tm?WHB=$Grne5fOvM;*<a}ZEcT(yU8MFv_~CM+06&om%IT*j+2A&+bA#0CU2N0~{Et6<_xnG;YX2o3z0c&| zsdbhcCrF5+2^w59CXCpvnOSoHaoje9vN1@&>|R zq7N!c9)|``7xN=08Lzg_H>53+wpOJyw)8!8YTj^n{_&meerXc_FM4%i7!?7I2Jf5+ zGNy4tG}p&z(}`Z0kM{r@bx+{6+qS08)~D_Hl`KuhXcY_!pGp0ZZV=Tc%`e2#$!#Z1 z-l@N)C@$f?Fp@_#hy@vt@%dr;Nd~lHmXn$ltmW+P4?s^ zjC(;0o@e*%e=jCqoy#y!zPi5r^!}>%>=nKSs~QjAU{7|~oYY&7)HMH421$$9XNt+` z*hz^AYVzHu%gghhCx2)d>YM`nJaGqDP_zk2rgU8rd745;w0Ra(7^zUs9Sk;xZ&t~+ zZdS`lqb8b!-Qb-9BNmTUE$5;ySyvs&8MI9VRb(r&V_WW#Rd}6SVN^sd+VJvI(c3v) zY^@Px_hO<|#Z9UJu#6<1+8Dh9QE|g`lIB6;knA7UMQzO{YBB_*R&l>1^>Q`$`(iVy zFdtK`;vpkSb1o>xlNE#tv=s7?5e4f(GK+`rkvxKWgop2;DY(mrM;fZlmdc@idBO3% zZ4bqZj~~z9zq$OmFI^hs7a{}_v)*_pF;L2M(=}pG#*~6vUnr{H0dj_%`7&41SSGC} z_Gb-DgI#7uZO}vVBTw%2&H35elgZ1=Pv?{0UEJQlm^4{(<;I^TAQoGmWhc!f1At6I zw?gHbvP;@MQZd9Tq^c>xsxP}y!W6a1+(I^^{g*(pE+h@f7qaByK~YMocJ8^uQ`c>f zUsP{p`ZKB)Tbw7}!aW5F+O)>NM6i&+H%P^pNWqY{wt1iiX9_J336hteZf~!zlqjM9 z@df@w>B&%e0k1os6EiHVuC%({VMvWlgUvNWa$>zY}OXQ(j0_fLrVp_ z5%@N;`7A4msK(?lSB@8jIJS*;MV(@@i0a#Ajug0csA4Lgv!Uw+K)2|=@zPhL8j&Of zYAvK43_1I390Efp8@CVr(d{4UuGI@xG47wHN8pdUOdBghATv#VjTMJ~ivckq^o&Np z8BD2m?4F3fl0qYqLqT0IQd0b>WD;k`sZ;fi%p-ZQCfcJmqv($7B2Ztg?c{$#8vQg(-E!&S2veoPpiA~ax6*+4a36e+~AZ2te5AKS{Dy{YHl|6`kiiAZY7f;{JD*~5BfmwHW7G0nJ)Q_A z$Rc(bnj@=ejZvBTO{j3)n1^Ca2=6h&=Y zodHZ9J@Sdor|Jy129Z@dw$1<==f#lJ#(f85-9kDpvAQ;?`gVgs$Z@q#0T# zt*Jo)Qos*qhjBsp8MA*~)+SDH=owW*4r|AJuy{;Ys|*wXi-Iu*Mu917?6dCSl3io4 zI72D0;14kQa!3d?sOwixsGXu*K%5FAgw1{QZh|)HW++(4POx<{nv4}hW*mSYkgaWKDjERS20XcQCnKHx^ zkU;ECn<#kw`sFj^aYnNI=HkcOpTFYT${s`&=a~5kQ^Y}Cu+LgP%sZ!ppcDTW?>qTU zo{&5FPM*>puctU4vH>X;VZE@vry^VA{fZ2E)$rld)P{lp>KV%hYty2{Ddjs43eYoP9Lg4 zClUiq9VxPYSxgpj+^0AKYuLAPQa*fR1!@NHX#=LfO&5|s$T=e*(vYKQR_$w z+xu=vR^~bnYWS5@$jZYF6@R8D>-sNREPw8=ZT`(<;=@8{Lx&M=^I@8949 ze7tyjK5fPZZyOY@^KUWdn(fZtP5+V{ z*zl(*xfADx`GLQm92p5h;ry8igWoZYrR*rgbxNWU%&N4`Hg|p;E_gowIKczy?W3{~ z&H=_aj0G_U9xI_R$#qBlLw>Dp z9EI;lqKZukvYw4==li7S<(2QpHH{?k#0ZViaj~Z#Bxc%C3Z+OCA5&RzxLXK843DyE zpTpL4FMWbL0xIjKvr-r#4of&!*vtC4s@{%37?6NwgfQeF70>wA*%WiDOeyt{WWxjp zq^ZJ8`v}1fF|XpeQ&UPELKKElvIrQ8IM{_nA_qg9D3j(sWKc>u|eYgiOWCD|~d zLjv{R3QlJA%)w`s+RsY5^<1lcPW^O^uw*pQI-{iK7VgkAitQfCSm9$WY5CtWLlW_ff(NFhSxy z`?ob4oFiUU4#?i~NB-(MAMp~jrAlraT39aHJ@Ib!-a33D6Wu+WYmZgjPq*6?)MyYV zht^szYNMU5M`z_TScjGWOOulNJ3XQPVuiv@aD0362`W*B0&*J3;h+&F(F~*W5)KTb zLJ(OI$l6F}aWu+^R;>99RTUWWDkVACU66qC+B7q(%T5UEYL$ zWSnCHk^Hm!75|fnP{FV6?gmK+!Cd{85>&mL zX_#VjNw&E6EuJ3FHA`e105}YM=zJZQ z9G7xaap?u1K_QTkn;B?`p;R5E5FR*>8Uh9r5D^G9EIfS?gJDn|9S}Wzhm1fuAD<%a z(Cd%|r|aI;_y7^?&G=EA$P?-nL6gd7hk{or15}$}_$(!^!k^aQWh5Q|DF8z!F$u&= zHiJ*Aujmo~LgA|ATA9#)W-8L2CZF#HD#gNK~>byAUpk_s85_S#vT!kW)m zraM&H7W5!tYMM$yU$%pv4>LTNYcKHLjGs(CXgr)Y@Lj-x6+08GK;K8LiTZ}J(YTkp zJR5eTy9*i38Pg0E+z7`-DK!rQ{n@z7ji_n;f7vImAO34U2>|z zH~8>E08&hla7+#PuY}ZbLXdLZYe-N??!fFs3}Adt!&7=d2&`O_{sRX}=s}OIxF!>? zYKkO%Vgm(OYy&9h4beO4Y0eXfU@faoaV-j~ltajsCVDL*84-){{ym8eV!*sb%&uVA zI&__0m<-ah;<81-MZt1{T?Iy$KS^9ESGz6#@CNa8;(0;%Wps>7kSW z>Y!34U{ljMvwuBPVylp(ro4kAAT~6rMv^6Wp_>jYK37xV;dTbD*N?v=OOG9A53Q$L(MUKR{- zI1rv!C(b*@DG;UMgKww{Lxe5ei5tZm%2wH{4Dc{z%G{L)^bbgm!e<(s|I<1&!b*{H zO_*VnW)9?&-Ru(~Fi}}skGKLs{e&v@5kF8>(4EfP=jsDc{|eA(A?cGBfZo6%Ro}0; zA8Gr7!ItW%x*3rO;6xa3>G+C@$SGR#W{|5jeSS2E3GJO7?q(BPU=r9R;r-2)by@Ty ztH6&ZVyHPfUe)>xO(z@bkx51ag4W2}H(bOD&6nC#f;y4n_1Z8|L4(nP~Kf|18C{VaKYu0vKl!eh_iioj)vPx>Zcq zJBaU?+&0@Kk^nh?O$OTpN`}t!F0;CK16KE9vB8}eE8)V|tc0+J)00UNAJuQMwxOSH zBL??EyDL#A%idnGj2}fqGL6xSew2(+27)F!I4RUOMsP#i(yB=uA$Smg9ww%V>Q&=% zlLH*V?hJpcOsL$$YLR+!cM zPW;-QKe|9umJV&yrG6WP=M*PRUA_X%b&?~{d!FP0Wggd->NpL&WDV0LfLdBLZ~A%? zjnZ>vCZV#iq)~#|=U+V(f0qjB;Zg}T3j$FP*{ww4xGxW)u7NzI5y+unweP*uQIUgK zZR{&`s23v7thdx*dOHAX(Ca`i1TE`OzVXlt0eKB{B|P*((96m_a6EjEZcUPSJbaJ7 zAudjQsn&Q1_w9{!!hL7ve!ZL>)~Eq`BIh2?z_*NHTrqdg#lne3{% zK}o!;(yufphur^Zf(%E&@T7}L!zTug>|Q5#4&OkOeyB*0TH=K=D!xl|SnjTV(nUt^ zhediTPADnAFh|lv#b4I^MVf7?2V@faWSc?#w)F3U*0n!J(>d!UuuuY4Hn}#n(Bz%6 z)HXHt_c)paP7i|yjackfNhwZaXvH9vRJxwDw8==(UqK&nc6__&ON~HzCVi}>j9ov2)qw^Zh3RLIB?488tIb)nl zaqM7JD6lI0^NKFn(Zo_CVjD>KD2AKE)_EAishG3QlGJ0p$N-y$DmBRFDIAdf3X{1%_BF5IE~>f|7Sg%}D)cad+95~aAtwWnj_v0mCqvB_|AdD;3}syk9Xx!G-X$=ajx@2Xo9x;iBF!NaB+czOvEe{WXH$fUNJXN~#zv;2X-Tos zBRZOfI-BYIugbv5mFpY&M&@>h)Ur|wsSN2kTEAyjM30^10JDfLSq(Q1e+%w zb@j(HMaWDVf=Q~v>`x+*W`!9@%E}3%Oo^lf@Oatg_%CnhIX{B>DW5*S8UR-E#%B}Os~l!>D|Jv z9uwtnsB#fWs7Q$6HWib1IzuQAfH5%5 z*!}AKEX`}L1fpPokvAj|NUP1;?cvcJB7@p3=ag1_(&UT>Pp}elROjcI+@-6USUuNh z8iE}mlsU_SC~{uS>Fj(Wo9-6&sjRF^h*6Cqxd6*gXu@wvts_EoLXnZ+|4Ysof|W?2 zQJN@DRJeqOKP0jP7zOrfhW}LCD|=@GMU_5T<2nJ^6yA)hXKWoA*lfn*aU8N!K&k+k zFm$*S$ZY@-ld+Xnvv$nQ*2dLa7R4gY#tZo$AJ~5_-3tR=ZzReq?OQM*Of#>JEP&HAn|Ev_pra&R1rgw;bL4Qz4{}+nQd-|6AP0H&`vdYb~@8gVn#U} zcu>(Tc5 zodd}vlv)P=2qzcL&n*tHot?pv1g~tE4)p}siow`Bfh~}ThACT@Dof3H25fDEy9MJ=-cZwUc8|H+lc0dHnb5Y(L99)4b#$-Eu)Qr3_MH)!}rJx0S)Hid*~@$J3-$R58q>ZxrUyH z@8K|GfO+J*w|TekzWxrDmg(f*Xa7+~9(3asXwS3~tOiQfHV~KRImtDFv6?jS+flGu zLrM^Y3;b{5F%{m0F0c0b-4+UDXfiL}(j9vL!@?MdOyS?!%i8y1(vFe}~y#p&xb-SHI4!h6=R3F;qN(q(ju%jlHP}!GT+9d)WXjF_r zL0`LxDQRt1t9M*oNZ&iIyKN(`wVL7czy|7u&dBu+>u#F}#)Dq8`lxyrtFvAYGb(bZ z1i`x_@7Jn#RGkHSpi$A!jst$&S{ZJ^-cjB0V5!gwSNBnB%Wwhq4(m<_i&6u5ysRC9 zDeT)qL-yA@syi;0(!gTiZ7g(C3F_2VpN%HVogIkYf!%GnNNJMS&*K_);;Abh9Mv6{ zi`WxZkovHC7i)lyzvHlQvUH1A-bMMiM#=XMY=Dx#(=I~%qg-kpmmgK{p&y{*@3veN zGx5TD6j$$J4N&rT8y58x?sVSCqF=4vVLiB(r*WHHeBQ&9Og3k$Zx;>wT(5?>+j4PD zp>A@@0~@wnhM}%^Sa&<}wB)H)Q?)+5i`6;y4>T%p7rGzsxKTa0k|&SG#dAlFs;1;^ z^qe@S;uSMFyft4Wk#a)qlV{Ge;92slc-A}{o-NPm31Kb|-va|gGKPomf#?;|f}AlA z-=pXO#TgIZqaY5Vgop1@#i3Zn!}my8B1JaK~|58opZL6;T}-=pOTBK#A&1$g)#FdVD^58or$rl@*CS3S>+XU?1h*$BFh0rL;*o=>O97rU`lV3_b_SpX5&fJU|yN+Nye*fZPDZ zyRB|wL(?=dO2;guqU?cX`P`Akw&SQ zeL<>~A}jRPSAQcLJ)Q)0PHk1+a`lKhx%jl4|Y@2OR-o zg&TiJ=qyd@-w^8^NEKz)Ot(iN<)wtT|A;e*ruE4@VYA|ANpO7qjlYAqfr`gYp*4uA z!~~#D$MjEIH?dbnCJu-;p<@{Q4s?&2dGX7hjGBW+28ElN)u;d#6l4@P))b#{F!;>< zDP^2mHb$I%WH(yvlQvD*%!VRGmPM<^|4(*mNfCwrPEeIRsm>i3L|W~)BwcUkKYH|C z>KuvTyA+SwXPX!PNFqbwKMtI}v5b9=Zj7G0tkRsONH?6QNs3Hq&@Lohdeucm-*F6c z2eI^BbM}n7xjN(U6HZ?6@S!tft8 zI4Ad)n1-4X0eS-d0!#(DKW;Zkm?@@dZV*ak0(=~tLb4LDb7J3kQ>#V{?_WWA`|b6o ztJ_JcC&uJ13;fh4*12iL#Co`VaTjnBV3*;pC9s?8WNz7;f`Ijef<;A$-lZ|dX^23iKGun_U13Js`?){Itp0DBl@ z@EUrNx!0~yE#S04I<;m^PFX&WT}oiM6^N?u{v0bY2NU_C`?zc#UpG2dh@Uhi9;Rqj zfluKFNwG+4nt z1awaKT_zXM-))IE$J8CcyRH_Ee_4SoNuKZvsbh+7R`8Ri;>0;?ud_;=7|CD*At4MX zokhbCIGVow^O$Y$z_e9Z)lo6p*!CHUw$vUJob!RagVA=56ee?(NDh*db>~2h9Q-Lo zC%9$Q6DNJrQT^rwuDxqjUA?lTG%1+lKgN#w{ChpSbV zkcmxEJER(9ZVk{Cm_V4`QOdH&3lxsxRt%3tMxZZ$P}43ojj8%3&Z$~D2YAllAo3*l zsxkUu0gN7kdwLyVSzGL3-SeOD%8ilZM#B z{oS(a7S}W;ey@qH8#km^VRmlFfan?(?Jd~-TQxNut$?f0R>)2yrb=Vi&>W4S7SLW0 ze9-1o+neu+0|#Cetb5_$EC3Zox`j@Qg*XSKv%I7gpI~B_=rz1Q(v7On()Y(-mdJnB zP1zmV%Sc>t22=IVv#B@Hi(aKJFvwdut>y$82jt@B=K3a`!*9<%-f|K6cV{=ZUuG_- z?=H`7&nLgXy8LaO4&${sTnI+wYhoEA4$uuquEq&dCWbCxTrhpzL_oF0C!^F?PdQ zAsa19doE~tatgFW&|#I;DEAl<9Rmmlgi5WVp?8mG{Q=adN&tDHN2}2|K3s~BG&ya8 zp>$d;U`{H^yL7_FYlmxgkEj?lAGd>}4RAY=hlUR_L&qo^CI@uUc-lQ%@riFlZ?iiKf4@cfk^nFO#w-R}Xm^8=8-}+BrpssxD7Z2eqj- zqDi+>!s!cDZf^IDf(Z``9Z;PQqdHEW=pBij@85>NXf3J+azT`d&~Z%7*bqb_DO=PK zVJsIMkar`=vC}y!Pvxm`PKVl%pe0G@>F`($t1ztT#jqCw)1#qd=2dKk*||}sA(8H{ zwxZT0jntD;QOPaOYjkk*fEfsGD5M3F-VaPEc$}DlX#5y1mcS*Xv_l?HtTtxXI#1?6 zNL0x{ux#G3Ilb>pQ6(PQQ9d4uhg2lZJD2Tzal@SVIm2vp!u&@_T}(ZY1BoA1?v2nn zta#IC2d;u?{@LqItJ<3Xr4`tuzi^sj?vPRr7$gNl#Z{M2E zampd8GZTLxiDrg|uyDL}^Tzn0$|C3zy61PPBqmzPuc%#%j%d4g#sxFHhQrM_a$qkuCKJ#UtIQ?FEjfa}*f=F#-Je24SGM&rUIGR3 zroaJ6*RGOvF}EG>w2S^{Gz>1gAQEP)I-lg|IOwza&Qx+OfI*r!XqVPO0Tz;X&ICe) z+(GCL212FpTpYanw&dK=0Psje4MZ7<64lmx+KRG2oOX_#mooftGN-3qgcLd}Z(UJ@ z+*4isTqhIB12aU>Ppc|isD0;B^-z+Vq|X4;cG(x<&hqTWn>{x1aPcHH+uosik~9p2 zFCwOp$s<$SUPV;VFam)Y4RZ(YMF*7r1bf90cPXL>X~V+tRoQ+=&Y5U~?WIMe>B*fX z)j_2Imm__ZffZTYtU{R-kfb!h?k=J@LArcJaMVrE5Go!SvAROSJ=aNan-hLRL>mBX z*t1HVM5P&6(x|Ag1YI|@K#;=@<|EZfpk$#`BI+B0y0WO;gmfvQBjwAck{dPqRisjm zs*(hkM5o1n^vF0cAy@O}4L1dG618%1T2}9BrD)H8)C05OG9q&7`2Eyhz~4%;srbT` z-d;uo%7M=yHle?=;(QrO#o?3k5rLo-IRWchUnz>joZl=bykhiJQy-PEmF5KCZ8>ah zY72d3AVG}th8>Ls(>gks6O|@Tq(?&~XVQQ4*#J@kPv_YcCcFnn^nl4A6dtD#7yuDA zkn4K%2D(?=?eeH81zAgxhKF z7cL6<6`2v}3%R&Qcc#dzAzh-1clxJEjwC`hl%q)8jAw6|46E#`9ReyPe{6#U&Kfjg zJTw{5w@KEXhb99Q0;-pXCIeJBSElpuJ+=_;6&}9FjpBeHdH5dqe3}e-_#Qk4IJ+lc z5P0~W?bhhMqovxLU2i zXtF?gQZikEwG$p44mINfk@L=K%Tg=%U(XW9j?ynis;e^MhY7^wCt0~~Mt=s3Zn4|} za&?O6b%yzfvD3N&)T~WqtG7OzP!sAKLdD?}F#N7J?}i&9Fn^u5bj zC9;t$8}!yRbMKi{=j`mzAcuHIiY;ia0djkwi|F{C`wXONZTqTO-*U46Qsal}QV`vg ziNC#nUR_?M?-Cj>1#s=L34Xi{X{rAVv5zOPj{gP-L-mhVY>)#YB;mMKt6VlLd%^I~9rGmgJaW^a8KldU2j>U!26x#rQ%z4hbOcW~#SW zbpxd=8~~xG_+F!sYjcCnN$o&07^e&=o!Y$e-0($*U9VG~IiWuM)->fq|5@$G(bHB_ zc$Fj9T?qnVQIjKMtLoaJb8U8l1XoSviUWV{)L<7U!l2_v&D{K-_ME#yA&5r~tOaUL zR`kF$IxlALG}w=D(xjW?QOkghaMEDmaVL!ml`84gO(87-eI(%k?xrjPf&wx=Yd6xs zQUgMW;35bq!_l=?sB>fL4(E<~y>g$1Uu^=fVpp*9VWYS?u+(u|rE^NnEkJ`VT~xbl zDv^P3qw8PBL3b6<1*uaHage$-;PB$6Dx)C`38H0Ctz8&a3Qwu*>I%Ct9*#v8|Gzq$ z^4N9vgK+Hjt7}7TxcAt3)eGLRTx|RhedyIdsv7u@Hg&sGZpz9skii9+ysG|f>9Qkc zCM63Qu{A|5kjC^W0N~(QSG6+UBiG_``~}w)kF{Es(l>SNVIGF5krPjemm2_v?TaDy zPhQV{g5-sPVMd#jQdtlj zrW>{z712U3V7COXE!rfknnBB0+QMpZu+tBmsIsWxk0VZS=^Ti|ES|>nwQ;A>+@gUg z=REA!5uFz?_#%x$c5nyz+PnJA} zN{86>xlW$EKyR)P!8uoOP(dSU3MmU6%&P{RSBhX2(4|YQ2)x*EZb?YRw~DjGZjwvp z7Eh?zfJd=xO-G0t-Lto}Qz+k8ZnY}+=yNFf=0=TdjtP-8j6NTU$>*u`T&`ijGEug$ zJB1*n#Jm%vMmf84*%RN2YciPM?jAc*3$5npHNTx_vD=oqzZbML65Df}DhIE6LTe(W zE3N3wA@@O{rZ3pwG7TIJG8AIrGu*o(P{}=k&dC zGJ<2+oJ4{T=#3RKVq%R@k-FSXc)#8+{KC&?+CUnBwx_1ewF4>FS`8riUv(oWvn0D= zTwlmA@)UOmw0g5&6tstk=AEo171$Bg%8udMOL6oG8>Ak2E=`92Fjej6+a_XafmwA4 zO#-zA2ZYpF(usUbHv+WG0D?R1P8KcC>_C9hIUqJeNtZZ189Zbe!KTUirJT+~mXV|b zeeOKUGV(pzn}{xW_#UYZOc{?Nii0;0)zgpmE`k}DW`qzpFQvuyE&^OGsce6@K~hfs zYJC?xggvyK#q=mj()V_~`WdJABAmRV^)%3b$#9C6jAF(q!Dd zJSc%?^GLoyq7PrC`M~|tY`Gs^UF!2vg=p7_`3$uy(j*r0aA?&+h1IeDjojfg31ME(jl~J5F_Cg z;hHrw0i9@cNTZvH0aAA%-CYY)tu#!X@hsY-$QfR|AnjB_huL;}F;e=ma5IvELx0gy zYYNGEq0n@B71bmng4$7}xlKgLw8wGeleZ5hV0VQQHQ2@*2Afa*02s?DY);1Z7|PE$ zzk#xby*3xNP&sGKkUR&cXfML}2oGc|XN|fU0BrGcZTCf`0W*QPXuDC(; z&OHACJl)nV=wN)4bYePe~1D}{)FG%jL)VR`c%McP+;M-jP+o-81OCUhp) zb$r>HI>BWB|LmOyn3l!4hDAj=3Be%Ph$v!I5RkIKvb!)!v0zs;(iDLOB_be#phU$O z3u+K^#1?C8XiTgju%M`k@o22EMS~h+iHg`2jS|m$zwk3H6G zg_|9~V6DunE)!KYh0IB!_Vl9TDZXNnv)-(_adnvWdA1kL@55+dK9u{JEQ)Pg?CuV< z?X%hCiFVE%s@jGLs+aA3vXzY_RCw#RdZvPZp_*$;Sga{vp0ys^P32Qg_8wGwahbI% zH;cm9ido%*7Hc5i(CztV$8+!x-lXaeVQgB`wq%>9?Cv>x$oVs;*+PBA^we z_`Vu@v|AXfzq0#k;wY=m{WpxX?Wnr!`kT`07_1Ik-LrEctoyXVw)e|LV*u}7ZF9R# zz1f#CMx|aA)DUY&GheWVnrm&3GkcwFI2^ZN*!oxA)~#ys0JpbWIvTs)*LMF}gQLyH zk3Y7rl(S?C_hs6HzNCWnM*+n>O?-7}XcUm0Q(L!yt2hd<sJXx(u)eTscTt^F@fXccnNRJHe* zb>dk;ier`TQR)}O-lJ{Ne(Wh5EI{p0CKcc_&uIM*FKREb+0{ngHoIc4dTE`0LrVg! zH;@9KzT4u{7PZ%@Dt4?yy|u&tk@EuVXX*c0-(cw%?|jOJD64)r zZ8q;{N5a~psO}ll?Yg#4*C-W5F1K@+d)Z$_M|(-LKRb`v7Tei@F80^m{(9J-oz-kF zklbO%3zaQ;us@4uLmT^`YkwBc#sT)l+x{$`$!A@CN88C@e-_V%dA)2h%Z4%bXYs6y zw#UBxSv=dwZ_j`Gvv_uvbT9k9Xj3!xXYp*^JpF@>B<#=P*{2X2quQUvvj?+%j`;LjN55$gEb|0cPAa$)W}8(``?IJwccxEP8_2 z46+|5Yp$>ngzXZu;e0n=AW^Dh#kCT4x%L8CS67?VE-9>U zbFM!$DB6(Z@7-2ESP^OM&YVbRXfs$=dl})`WS6aX$z~k0!+=YFM5$fkyOrwMh{BxlNVZkbzaN zd>?19TY9tjryp2q&s=-Pn2ffF&prv-z={K&vdxD4aBM^q9#V+w?m8@PPx`3~sZXtsri*7i3A6K3k)BAQYEQ)(fjUDEFpQJaYG2 zlI!&<4Udg%YCQfIpL#uP-qv2c?ZIG+(6XVCIW|+P_#B1?U#9HrCoW5{eXzDthz{N> zlex91+WE?rq7Yl5=FdD^~ z?X#XH|H_t~3cTvO0j-trh1+IL?Ql>VCit0p^&Z{k%DQE>&lEfi?ZbfGQE%V;?9-rq z*RUp5vOZcHv@bN)5ScQuk(w2wN7{vD&jNZ8tB-cQv3)zWg^&3cjqE(&Rob=G-A;e- zISO+Rim^zsUWx3>QQZ=m{b*$qHg?jq4bH4#*aU#TxRlbW_=VBuN8+1rp%&W+-O6My zDYn_zdPVkm=1;fU0ZMvt+_&VLug$wKP_mQ7tkbbG8g0po&oX1DRVup^!UApT+KZC~ z*%-IZPwfbgvXY}n>sM^bjR|FIG;y6?(N!4nE2AlBF0rHSZ0DAZAIv9(?jkz}c-1SO zttw|vt35MqlFp{;)8f0L_G9A$1|eoQr-}MW7QVT?o}PAqTq%(_DYEutTpxqf?)c_C z+ef|8TvZ9}ItYXPheo6gmhas!3 zU!4xzW~t4UMcuq9#v`ma%!7*hd3$XrT`7y6$_Q>#XF3wsx-1_));^Ni^PW}75)(_M z=4E)Q+o06?W}foaB~c-)q2@=()(h(DWzBzRP0&~I*Lzyoj;8F4ZGR5eo)>GwLz}0e z2J%vqo>lgmkrkwNY_Tdw#+Geo&v;AJdQq0p*kW{be)hGzn{7(6&m>mG{YA{SUiaic zL;DnB9_XfPFl@ACGrksV->B`IB;%aVD3)tedkUvDD=Kqwp|S^XcEIndzMK8m#`pO_ z{q}-ORVW_c6Jjsk_GGt1gzQU1cAP59u{6^7{G(qR`+aj~4zh!P>&+ZAw0*tXc08qQ zoef|9Z2@EjJw9*FcF9b)?d-@)8{gZyByQjK0g^A!w*9L12(XnB_7nTwz%NSHN9M)S z`D1aoo4;x@QD|+#UcWRTwC7IN$Z97-K0~NaIe_eIdZ3jUNTu1{&lpJAh^;DweafVr zjq_LO4aPrP77fAdwWH1}jE$(e`qQFhQ?zc++H&ER7Jo?FOEWVdKI`M7V&A%G!@2kh zQ~PM(K0npaRUe6bO${#}N%CQkSD3uz(Z>|M!epo1a!H{I_UX^OPa8lW{zc3KQ; z{%z3D#9h6SFqbUWc`x-%@HTO2Ia{OjC^e9_={%bnu)1ff(kvzWz^PN@ct5ZZ zd+E0&CN_~^yYuZq*Cp>Svw_R!ov8b|9^^&Wx6t;A2hcp&ZFpysYPL4WHj7&SmT6aS z#PT^F<8|kW`O;SJF<2g7kjxpiQ*`zU)kSYZMK#%$yq0?8@w#PmC$<#Hrupq74JEQy zTn1>|7P8sdxnZ-s0 zi*fxGGNZl1Ib!I|r^1a^d2x0c#=ifKe|MO3Rb;26>7+mjw zVya2)fpRt~{?w^)KHaN8^_~I^O^tK+5npKNhpi_rTyIF*%kNLHJrnj|XP(dYz1ZZ6 zeXsQa2%{H!Evvmg!EPKX)x`8Y!%VbgVE!^-LA5&h6TI*}!}<|2$yR-^9zg~Be5X;? zRf7Ra9U=KrQzx2Dhx^Byq#;mxCZ*_e2KQn!XKaPEuQhSJjE8KzR{Jd@>p5yiCb6UN z=i8UNr{=4COSg$Odk;uoH+=a{(Zj$#`C7Xzv&H%9QS#PSJ4E^7FX?oLKE+_mRqU(V zS2W(V4vUq4g?mk?oAG33rupnY>xC(&&C{8%cG8Ybdt|F`Sumr@`eg>3Uq?ZUFD~XqKRf(kzTI}+9SAL>$M)SWPiiHLwYo( zg5!wO-nVScfBY}bM>I6zv>sammKt%EzH`9}pwtVQ_!~lTq2k`3qIfn%VqPwaW>2tE zWh&}wd{dUq@mhPd!|K>k?dcTtG#j~f-rMPnX z`njSYc7NMg&4#?z8JGerfQfV2rAo%PM>{{YaFZqXr&|_9U$CqanwRV=kIgY!)3o>Y z9@(Za)}&>Mt?C%;tL!UngGTL*m8Pz@t$g_mX9-axo6)p`pbDS4Yd^}d#7;%}GTo)U z;Ms~gCQfb39cNA1u^F}z(-uJ4xRMVtwpFk&3t_d0OAojS(RO9nBbVjItnaZ0GP|a1 zAmUL=D#&^L)+5^_un*p>ceaDIH438}i7!ExqkZwTWf)msk{#{)`5x{xxv%=|uJ-GX z6(YMph!2yz3>AGP$z~n0qkX^d@VU+#UOcR)UgNWe?y60>l-{UN^lt8BRW=WqmW5u- z$1g=+!Lw(&RVP)_&;1yv+lhQNQ%ClJtbuD5^f0&8KRo3)FF?&Odqd9-`u#Ew^P>LU zCR*w}?`(Boz2{w=7b*T}cf4PJ8lvc1Yy2o_>-g>6h+o_Lp{;ZDQkGr;#oArzm{v2C z`rKM~0+Y9F+*j21GZ|GU$oh6)d09Jw$;LXC(X7G@X8h`(uQu`FSJ7Ah?0wwUAge5^ zGJ{#SJ+aog-Yi4xB8w*(?31xim(?w*&pp;t$PV7J=crXOTLW5QT`y|bIG}cp!9Jr~ zn7v?Gmu6eK?51jaV>Yb|vkbPXTBZ6N&+o5m1zu4n5{Fx>KEaor1zc*lwcp6`;~U&1 zL!WG)xozT!n?-F(FRodz3-@fjxXl`K7N+eS_4=3v*;*zGD*7qQXG%7$!jsL`0GS~E z80XNxG{b<9n&7j`PHc};t!UYCyIO7R8MDeCgRqW4gnkjeJT)O!!LBR~+zt{|v=bY&w*+jNo2_o<7YKK;YTH~3p> zb{=oNZ>gWMjKLNx*#{gO7u)2gedkQWU)#uU!|twj^{h?Z*z2cXbZnDS_O8KaYVYr< znYK^D2D-Ko$7aoJC$G(IHc&TfrzWZ7)*spJCH5by=WXGf5C8M&R~tNMeMi0Nk_JBZ z*Q!@BgEGjs|ANPDG-V-Fi$al(zQq_l;kSwU;Z9-r}|6Hooh z_b}O8ux+R4XrKJ-&-VS;ggNI~+hR!jvwc4{#cj)_?9bxa`>`E?XMYyYJ_FeY3;VNp zwuX?ye(dv`{aHNwVruI~?a$)bw;}tkV73-ERW*1Ne1qGEiuR+j2g=49`My;XjeSs3(+-DXsVGY9}giov*#7+7_yO z%EP{+t8icFuzPl`eQ~u)_6hY*v-YDJtp|z!d7ogPqD&aQi!eYgi~+O5g+KeGMq6y~ zwJf79Q6xT;72d8m1eOZeV3BGkZqi6%6;8U(D;Y-#)zitmS2v8)F6vfBJCR})8c|s-2Vg@&O z!GcZp#81>k`t-;iL$;b+Wm)z673x?^0qQg)yWYp^g^kE1jti;fnym%LK# zsOY?4f2@^y8rf0;dsnfEY&#pnr)pH`Y6m%~pIe3Vf^90?KUfw$F74pKdb-)MLnN_PT1@uV!z9GkN5%))Fc!kz%O<%&Hd-eVSegX|RG&!~Im-}=W_)a|rw+Kb$> zXQ>UTeXD6v7>hRQ3D&^*cO^Or`^Z+?N%;I_(fB9pBy7G-iha4G;Oo_{dgF*M{rXgY zB*Aw8j+?Smo@}s(V;dYCW#{3$&x97}t6eY*@S6(Z=VyLgVY|WbzZN<9H+9p%J^7!odV~<^l^)Oi25h zTl;XcGf`3t{PdI5SE+-sr&GP&zvKg<{t;X@*Hfyl7EfDvO|{x$>uKz`P-Z`3|5?<* zWY6yGu-?yTcXggl^>vS*!t!!G)5L(?zy`wvz-G68Lq5jJ?Q*MH;Yi2B5{RC9%kNMH7&CHOzbtr`@n{z$d2P(<;zUIp3$Mb3)m_I zT~bA7;Fl4k(V-2=ER6R$TL9V3Hm@hDeiMwjL(46joXFZvcKUAoWZ%H4{rNPjeN1eNT_Se<^ zy4hcu{dKp$9`@JM{_MCV8yVThcRO~ei~034&$Dk}4wcc4y{j?q^|M2{UCe@tju^F9 zN2JV74z;tX{q5EU#Mv36b~I|q7Ep9pBW=mLg>+=Iz0t)-2~~$Bur}kA&C1zoR+a4w z9o1;%vuiMH_R=;~*-N9%TQi#DEL)opvHxc)7;Me~n`}1M#&vec4u=j~8?`VNYS>`d z;@BZ-HU=$KI-3+tXZG8N2U3cMi53Q{an+`M@vu*z_DWT5dqJ|vtn9Ggy2V?SvqbB* z1zRyvw<*|a*}6{`+cfI6IPZe(>gkf3OBe{)qr*BpmK*t4yyzXtlq5^5v^Jq@U4U(E z%Pyni=oZQMA3n@DZ}9daA6K;%1+rtQ-mAPV#x{G4O72G*)PJkuOdMNsW#5x*?~UtP zTyTG_;;3$$yRg|KPFTKEu7-Zg04&@m>4~5FQ8Q`?|E$hk}amN4O7;|+q;8xIi*$1 z&z^R76_=1M&2q4{KelVewz9C4JXf)HJoLp%Xtl`JKG_0Mo0u^#`UAj@@3ksvx4F{0 z*(1b6&Y!ZX1P^IYZ6u-z0=#wi&Z>UdRmEMhi8jB?crh1 zD_fLeA3^Px#djK5Axf%Pbhx(HlA?#9&(hnMb6d#7)oFH#Lw0ZnUtzywOSIj`_WouM zHro?!J)GA+tEP4eqlsffG%J!n`8e614}KgAVDm8E4z17NA!_3zChKijT(W>gCl}kZ zofcdqq3wtCNgei*a!Q~*UM%ITrrLMrhDy1rB3egb?aiKZRy53~L(T7P@b6|eKW;|^ z*#{guca9?$ytgU7xWW8Us*vUws|dRA#fLQc!-3%&&tc2m28`BgarB#|Q<$L2&h@R^ z5?84|HIEkEUc)g!EJi50;!@bGfmu|zzV`fg7cU>N#gF=ymHpbjO4_$4GbJls?TDss z=~kt3`qoBMKP||lv)5;9%>D%|8@A-<|BjwKW?IKKas7*(Y_}?fqx;N{dABxV zxmhdBPlI;@@?9LZP# z?U`nSLVNSIWAj;GY6WEfnXM`{{TKmzZ{wdNn0K>Xg|-*k`&s+4c`dA8~)M@T8rj(PY$iL1-rKL zz{+erh7Dr;U*rFa15O%$VF`@=Z}yeg-d5${0sHwaR--0PZ*%0h>M?DADN{#{X?v_$ zeB|gc6UMZyw9VO0N4BjTHlyu?iPdAEE(aca;IVDmwE5TZjrtATbB$|S>>a*4I6 zJA?zTZtnc(iV$vS*V_5#TZQn4!`eIF_DrA9y?M_Re&zgrDgJ^F_jD$m@6H(NO!`|q zSM5x`8~yEYXYBdGmQ$Uv^VFHgIAi~n_Z;g?x&HCOafvD8l4hF*l^1T@XONc{zITrw zd3oW@w;ST+g|EDOn3orByUsygUU1qdZ?OCc%g?a<52K^(L`T^#9f>1- z6(8M|4)p<6J%Lq!VAU&F^$k`%grygCOyz~;2Uz}rI zzUs4dCtURbRy~1Le_+)sSoIBl;@xrKC;hi_|A+}6e#yA--rHMyy&Y3AE-a{S=X}Fm zhlWRH$96Py=R?Ex8M~#eDZXt~xC1zLlrbr+0N&vCo#y_cyB!d+oYK5u=f8 zhGjD>n_<}u%VtMeoxp{&jfR^RAbiXHA$8PHXpy^F@zN2pwC$<~*izJK_1SjtomqXzKM=Oub!k{m5|aIp1;n zm(Cg)ZaTe*bM?_9!xj@`xjs2=WLS5vSl&}Fur^o`{V?FqBSYvD{j+SnQQ_nJ(0p`wviu#ldESyyVS{P!JLkSqe9EHuu;Rmt534UCeKFw;)lby{;){uY);*&_ zk8N9c9r)wS(c$thbTVjC_bF~EpNYK@=_dl*;-vwI}(%5`L}mTZEgQwbV+S+ z>@i(Z+njQAm(*rYKC??|%Z(OyNp1YsE4!q&|GRy=ras}`1zl5Lu}P`_*h`kaq$ElYJnoZAV@PFQxrvJ;k_uJtTa7NAx-#-+xvK*oHOYkvQbF=cC+Cj_2>7VVPnWbKR;+*Nd5oo zzX|ENFzup{o)^QWh4dV`sCV#Z4e5)?S9!t83szpR@`9BYth`|51?T0u_K-fQFI})f zpVY_ZK2&^cQ+!zQVa11~Y0l)Uwoka2@P^vm?5ldGzVyxm`=mZr{vjPP=_o#|_^{dq z@x_Fz&m>$-c=wqdLjN<${JAeC&i-d~2nz;v^}hX}8#;uGI&^mKzpO)edCN}D`&M-f zm+ltFr4<)<4C8Nz#qsC0b2^2a58B4#mu<3L7_u;qMen?7yYTYl$o+bB z4u}0b^8eo6IkavP)wUBktv#&K`e30=beGjK zc#AnzVdAUfoY$OJ74B{}-uYeQL#rk@|Kk@`VU3ZKoDUgW6^@uR+4JtTf?YRiO+374UzjTE1B6dzW6Sn=T(?>r>cb1`|9+dH`0!q6MXrZ%!x zx3Q`1+;Z!f)TS;yU`%RjbJrY`+TgO=t5e&Ybar)Wvj^F`x!UsH$5*E|zWuq?sqLS5 zS9R(W9&a)x^&8^cPFQxrvJ;k_uR zQXhWSxQVH6zw#dwQ=fnP*h%SG@cp+ZrDw#PnMb5&N1JAo(=%n>Ig`_~rssx7re{#A zSx2U4Q=`|8OwX+KdQVBuviFXflAduZFPM^^eVbi9#h;JZET$~7AC~>F?1yDPEc;>E z56ga7_QSFtmi@5ohh;x3`(fD+V>5k1&Xi@JUrtH=M&IdEQh)MFn3DRLm)<-w^*@Kr zIWqN2o!T7feHZD7NndHgN)uL^u+oH;CcN20le~}3ne+$Dn3VeAr&>-*{qr4{Oicau zfXyeS{=Ct-6H-5a-*+aYwk#%nr3oudSZR8kLYlDBgw@utO-#7zIpJc$^Ex9Yj&#YH z_<5g`+bkx&;`nbfzm1=EMCt=8!{pRA<{HV*{8sT{#fKFiK6%$6q4A{G{Fx%g&JF%L zB(yj+hMzrhXqf$AK*FC&z%i-a{)8B9&x!>?G zaMqj71CARW?mh1<=PTz752xPrw)4ur{l9!}(a=7U(qu>*tEaLX*Qu}cy#N?k382SoYFq>4-V)N9%&i*PY-tw zd%hBXJA41`VY_*eUwg4E>^La$CnuGKcV3G&OzBk?T27BV?UQa{`HCGpuS=G83(Y4* zMz1|y*xtj%d0AkU1y)&Ll?7H=V3h?{Szwg~R#{+`1y)&Ll?7H=V3h?{S>T4+h%~CJ zm&!}Hm~`M$^;va{_+sL#uOM7Zc>iODg|esq>TOm`c=H9r!YEW+FJuKX}@+s$Q zUL6)XY_T+j&l>QwGx3{^c*dD@+8+9>^Qf(dg#`!v-TA}YhK5;NKj*yN&O^iQ4@AD= z&LQFDf&cLEkv)clU(Stu)8&K1Cf65pZW}DyVA-Z{Y*Tz}gJl~m+hExS%QjfH!Lkkh zWT(nxo0#yue^-(0|6aR_RIU>*@0H5CphK_ZhrRw-p8PXmQhD;*rQOPtKksf@9^~gH zYm_Jd6E0ndFTF@dnu>GVVA%%CHdwa7vJIAPuxx{68!X!tj%|vMZSenHyi+)~{}rya znDA@f-YNWZ(B&S!{?MJnh9~{X`RRvu4uhV)%=wTX?Gk=JGV(Rg?-JJDF!GS81H;K5 zU+Qt1th;Lp-}UTWQ~XCa-Yunb$(-F%`b|FAE#>>lZo4Pj#JO#-Y=dPREZaPO!8Ta7 z!LkjOZLn;EWt+z@*apj2v|lmd(wA^C;cCl-iwRe`2p1EsI!w5j@P^vp;Wmf7L8sf@ z=VIblU)n3oZFWc0qHnKo)gzH#_)B?cJnc>oUpBZr?E7xy5s&u_<-7dB!x!(_GfbHj z`LerugcXNHUKo0WXDcILbZhr8T|NDHj?S1V%MmMX^>F&q)-NqC;=C+ylR{Zwl?7H=V3h?{Szwg~R#{+` z1y)&Ll?7H=V3h?{Szwg~Ui-}LL)+PNy)0tF&)Z;!u=Mg6e#3e8Tzw((KU?+<`|Wv- z$8UT}-*ELakz3mHdBIuddic?O`-K-qo#*_~&-#TWyPxm8^p<|1_rMFBpMJ1kcyOOz zI`8pVzi{b@3!T@!t6#YBu#23Jx};xdKJjAbxnuf;bw^)P#JQcY?1W_}EIVP@3Cm7c zcEYj~mYuNdgk>izJ7Ma^_cx7Y5fje1@x~8g*%`ledM5gW@!KYkMPD&~`{|3(hm7BD z+%PiZx7Q~`KQn$C^iI@*apNUdN9Nfr9mRRRu=0hKFRXlF9dG2spAu0DkLV&ZRl(%z|_hzZ|w=e@%_LtrbBC;}H*kb9!}X(dJR- z4Q$QHjE5tC|D4gG`+<*nc>9*4!;hCle)IHEVf=fM+t_-ZB`YJJI&EZV|JTUN-aa_o zcv9r$M;#n4XcGCIbq)^uR>$<$yJ|!jd{MOFG2D8 z!m<;Vov`eLWhX2M>A##5P8t>4_@L%T zgt3ic+h1$?5#hGGB42yo5#hCKVqfu8)5&4%)v*s*+;ehxX@2ZmS`VBYu6QW+t4H;p z9L{(x_C;@QH8~u!W~~3!Zygb)ekb;&;@mb^w!yLumTj!a{?g;0aAAkAq}heegdg-)Wa78F{~`}3ot=JpaZ3M^{V#DQ-(%j7j6Ls7ztqFA zbCV|{WBw#?|Uwd)86nv z*2&J{Ki@jpKl#M1Q@IFNd5JGSkdFLA`tlq3%AeRHKVzr-kNwgm*Gr71(hin(u(X4v z9W3o&X$MO?SlYqTPT^>$_-F@9JDBwGAuR1+X$MO?SlYqT4wiPXw1cG`EbU-v2TMCx z+QHHemUaq9JHL=lzCqp zxUX+Y=aUJ2Q~GCZ);Hxl=;AuadgHnCiZ^1#Sp4`!7L~Z>UI3m@n=Esak_3eanN2Gdq z*kvP9{UluNj`(VKpIAC-ccia&N4{!z*rRrbooaX3uXabd)b7r{e0U0<-(z@+f9V6m zQaV$P7?#psXNzGe-~W4dXtL+`*AGp0?(~bH$^PM|4o&4ETAb8Lg99W3o&X{T_tJ84I_w1cG`EbU-v z2TMCx+QHHemUghTgQXoT?ORRT9<@8{RJ+4|wL8kCcK1J59hJg6^g1fV-{9e? zDV~vE|g1Z}`WQWKYMNrX)KTojoPl|L|#3Qn?6MyCc5Z9qFjuk-pj;`KsMv zkJ=q}s@-9~+Fh=f7)_-eEbU-v2TMCx+QIl-?M~VeF704xr*O49X{U714wiPXw1cG` zEbU-v2TMCx+QHHemUghTgQXoT?OnG45UU^gBQ8;pBVnP0u=G&xwnli@!BHTl9I} z8STz#_kuI!dSO~*%C2yHqWJhq>EJ`9k8j%-^2O(}2Q6eL+R1*jQ@IFNd5JGSkdFN0 z=@ba+1sQ=`vc7Z)=FW9Meg#Bt?luPZ7XT8E111LUY1Es^5LFqG=P`hJ{A$u5m z$WF#8vY)Yv%0;-!OMLl(bmSjTU;UNkD}Q2-{EVIQKlV$PTrV-2N;_EE!O{+vcCfUA zr5!BoU}*LKsus-J|b-V$H+nRHaoJ^ezvBVV-(>`{BcPPHTKSNoz|YInTbDx7y- z#phjE>F|!M^m%tyyW^c&_VBJPJ9#&k{k)s2T!gE<#FrmPNB;5j3+;}4m^20X$MO?SlYqT4wiPXw1cG`EbU-vr*O49X-BxUgQXoT?OtQ9bwc3+;}4)h@6{ z?FBp4j<8?ti*l*mF_)`w=6DsKxnHHjoUqbou2}7kIb_+xT(sJC+PzVTR(Pq~`3jZE1Uj!zUHUnw1YsPyrz^2O(}2Q6eL+R1*jQ@IFNd5JGSkdFLA z`tlq3%AeRHKVzr-kNwgm*Gr71(hin(u(X4v9W3o&X$MO?SlYqTPT`bY@$m^P?O`1tmxLn7nz>*q&CySrNN?{U!X z^3x-u-P<46hWDFbXL}XeX`7{yNvCK315)~7wQI6hH)e5G{oq0+~<$`_x@9<-C4Xeay8PURw8C12AD}Q2- z{EVIQKlV$PTrV-2N;_EE!O{+vcCfUAr5!BoU}*AHvcOmUb|9 zq6IANU}*)# z+`gCBZOUFgFfu-wH#Rc9syQbzK3wrcWPCfu_GqcSoOM!Uw7dGX$Y^)c&`OVkc8~oz zGT}e$Q{~~rU+dSA(QcFVdwV$P?>I3s`QE%FGWNW=MxXdwvvbX^k+J{CJtI@D;e#Vn zc7>yz;^Ql&gAbKHzE!^XT=t-y>_j`+k9H~-;VLijf0` zy5xF^(Nx;O(hin(u(X4v9gNSh4VHGWw1cIc!YRAr;}clg!O{+vcCfUAu@fy|X$MO? zSlYqT4wiPXw1cG`EbU-v2TMCx+9@3E6d&ziX$MO?SlYqT4wiPXw1acK;3ZdW>vfp2 zUvoobe6q;{k?~cBe@DiLBjfY6mPbarP4?^PanNqX9g)#)r?O5d z{G2Ny6MxG3+j%(YoOX0%(x3l$Wb*ytHk~~V_KZ3-GIkz$US#Zl;dhZK*8@u;Q+9>p z6UE0@N(Ub*eSE8Y@wx0lJK2eLvLEeKF2Yq_;>!=DBma=T{6@a=C-%tC*eU;GzjVp< z5~HcKgQXoT?O)3G;8hknXW!E`0%N#BIDa#Rz$|67A73dQe5myC zt@6d^vIp&CC)&w=v{ShVS9ysqKah_6L;CU?`O2TzBR^xO{Ez+8CD%)grqT|UcCfUA zr5!BoU}*mb+O=PE{S-d^$jHS1(Q}bW=kQ%xr1a0f zGBWwD`+j8X8BpHR<6!5H4vCEYfBIQu%5}r+$dp~-_(bvXmD0h7N*~`UUwkfm&`x%u zo$NBv8%FTatm{E0pCGj_`V*e_jjy~JoL?OiF)F@!{gBk@4-e ze~OIH57=_8*cPlE9e!G5wA<~2$Y^)LxV1eF;jcaw8Lj_sm&P7WI?r4mne@N&y>&dC ze5W568GC+rab)bg`+>;V-|Mx=l&kIgktw^v@rmN&E2V=El|H^zzW7}Bpq=bQJK2wR zDi`4@FY)CE(vg2iUw$KB`4fBOXY7>!v0u96dWq3g+QHHemUghTgQXoT?O?RPW?0(6 z(oW%&UGeb=EbU-v2TMCx+QHHemUghTgQXoT?OCO4Bv8%FTatm{E0pCGj_`V*e_jjy~JoL?Oj&_QV zcCfUAr5!BoU}*oP2*b z_;F|K>GHS8*tuWT6CRHJJ&ua(Wjrl1Wmh;pQG9%*bnv0l$G6HCpUWP!lbvWM`_WG2 zB3$JqzWhKs@(=0DZ{#a~Vvqcco$^2SOP5?PF`7y{SlYqT4wiPXw1cG`EbU-v2TMDJ zQ+CD2C$O}Gr5!BoU}*8s-QvC9NM<$)>`xbgQ=`TLH#+iK2+h&n7_O!S* zGIo}KXR(K)-9|e`_A(BROxYEVPZS?tDII*M^zp6o#pkjI?PMp~$$qp`xd>Nzi7!8p zj{HOV@*DZepV%WmW2gL&{n91ZON^$Joj9|Hs} z`H_8(5A!eot#jWGkGDJN<~zStF*B?=Fz#bIcErrk{kwO2xNN{4<%>Pa7goNo@`aTz ztbAeR3oBn(`NGN_QP${TF~Ch+NQGX-*d}U#`ka7GL^mh zfFCBGob|)4lCO4Hf9vGK%1yROzMa{%UGlkXz#ip`4ayf*zOeFzl`pJ(VdV=eUs(CV z$`{V_70Vvh<|&TW>G9jmHvF;A36SQaACGe;uSGXT#)ekqk+JQ%Ifr^2Y(D-Ehd5J~ zhaMa2Oc@`4V2m?mpEEzMW5k}i`Km1B3oBn(`NGN)nOn83w%M*`w3GGJ2@>X`}61Hs@{jh#@=kU%Wkq`LUcA?in(N~w9)hV3vhsZ0> z>KG1a6#ZN(eezZMu+oQ>KCJX%r4K88Sn0!Gwf*uZzWO@rPhPjxzOX^<3s(Dr)xKc0 zFIephR{Mh0zF@U4SbYnueh*f^2dm$M)$hUT_h9vVu=+h%{T{4-PyBhFJNcQbI;)m+ z{#)n4=4ZF&=f37=x9Tin?EG(?_p9?`u^~T)R_99-{@*&onQ_SKv*7GrOB;LZtU1PY z-{iC4R==Y~y}m8)XshS4qF&#YxvbT5{!y=Q%bfq}Z=+GKZ_BsQ)oVziUf-5AB&*lj zMZLZ)YwcFANsfAbTh=76-n$X?`nK%dSiQ$B>h*2e!mtIZm+7ae{S@6RdNbV4dRx>l`Oo=QzPS#|hRs zP72pqKsv{XaGm1>>l`Oo=QzPS#|hRsPO#2#f^~ixtn=<*op%T8ygOLu-N8EV4%T^h zFz46l%p#q4N4U3hP`@Sm%PmIu{hy zxuCGl1y#7(7x8t5mCgkvj?M*zbuK8Zb3tL93kvI8P*~@J!a5fe*14dt&IN^aE-0*X zL1CQ>3hP`@Sm%PmIu}&oYF}T~nXbCCgYxQ(W&EJCm+_CzWX5kgs~Lal3}^hTvz_t3 z&V1JS$&^LsC&PrVKKnY>6Zw<+BR^BGytDJOnRypZ!J1E|RL%uqz9D8(DId2MCG(&v0m<;%I9vWN3LWv9-Wrz|>W9wuDnCBFPXI`R+c%Wvc> ze`1gPjGgj7_DdI@%hHSIwZeIhD?ZP6rNeVy=`$WszKj!O590^f$#_Hd>pl+3MY!}L zzWhKs@(=0DZ{#a~Vvqcco$^2SOBc!|y?9evqAv zH)Ox=Ogl!g>Jd#X3xdvp!StS+}WlSkI~S zS?8&IS^p_}SVt;5Sw|}SSx2h7nFv>Ti7!8pj{HOV@*DZepV%WmW2gL&{nCYUNiWu6 zDxCG1iqE=DrNepvrO$c*<;(g{*~2Bv8%FTatm{E0pC zGj_`V*e_j5-494T$?p@?{fyo&3imU@|BX8k$v3}?Ppp1sn{v``__g=EEGO?eBs88B_dIU!*CCPJtZ9U(g@FY zpI=T1WgCrh?mK--=+~>-`IRsw^r#%`{L-68hVz>p>U`LoBSYVLbA~jjkEiCzt`UR%707@lb_wj`S!7sLhB}xzyJ26 zaM;hc_V76~j|eYMj@+i%y&!aA4tIwTz1 zKJw5T$A$ry9_`_4bsHP*STf!DmRrY!EoV=2zVv`G;V&(Ya-O^97~4ZS#d+E7)!~Rq zlbt7>T^-gKIm!8;=c$&H!o9~ud+xYoVt90Zv~$4b6GQh4qy3G}oe+*{7t1w% z+7V&nTcSOcVRCrxyu&@6Q#S3E^4fP!*A%~5lddV9vrg%f(x1M5my~a_>pCZUdK}O> z*?D+%uaxGon^h&BKRB`~m9fQ~s#Nwh=T#-2ylX69{o@x^$%luGtxCSV^@ml-=QlrC znY6fgTxHT|ulFjFb{|ZwNSglOjb2IXsuQ}VI^2C`hg7%sKf})9Db$&RZs?HeQvYQg zQXSj3s$;5q6&H6*b+UEyPN}Y5JEv2s!)2Rnm+JPNS8bQ-e7_!@Q(O4o+dHQ=^4kGj zQro%X)-I_{?cT0yYHQf6Hon!mol-mf=Q$ly`yJo2V`|sqUha_Ed-Ll%q<)~0l~?`4 z#;pS$w@Y>Airf2y8&Cew_t6}(Q3xO3|FLtk;UR=RYj|C{_lyu0RIKSdXkG~G z?zOh_>%R$Mi;3$vPrE3Dn@(@yJZxGB$DZ>Y=ZkuWu;hfM&etB&Cu}h7eNTVE27SVl zJy%_O6ppAY}8D4xR^3YaRf11ANah|xKDztmzCFeKS>mB;+ z{EG9?qk4ypcYDqGqg%^TI?LAT8d`UZcAkHGm+;PjX#f7d=n_6GkL4PBOqXz3i&)+% zM|TNpJn)gHbMl#8!b3k@;oN9(m+;2uX!EaEb_t_qN1K1QZ`aVVb%K zbm|uNyerx{>AG%V;M&ptJ<7_$<8Q@s&FI!M{G|U@?w^x3?j82pbqnVWmsN!o`)ujl z_?oJ)tb2^pYQL(m?MtyQz2x=E&~#|*KlhkX8O}U8_Md%MR)h;j$A0_iX%(UGvdA^B z_X>}168qIt$Mg!Dz8=Frc(y!jKQ8jGMwW+1X2*1vFYg%^RLAt+Kc#1Q@9miH?5lc* z%QtQ1w%vJPpU`957S5XwADwjk;D*sji%}a@Cyi#DQJu8=py`;TY45pXlGaCTF*a#; zLG#h6p3GY^D%GFs$Bs(%cK)j)Qyp7z{m4}Jmd+ZP>SXoNBU4@d1~F-I%2HEq4C8>OikYs#D$A)1FPLGktnj zr@C~=mJ?H3IAGlP3V%2(*7Lc$jIw=pJyZCV^ZTXv3qIV_nRLE8W2iIfZ}D6lYmx6pe~Zst?D@f# z@i~s2r_PMeXzai8o_LQo<@(19@gD6xUfn%~pZes$6u<1lol-i#9WfxK-(`z_Dc{a} z?U3wwbcOZL1v`JfRS2^GwrBdJauKfb5?_8G9r=g!&h^ulC##|39^-Pkk?Gs-J|_Pr~XaJ>Nn< z39Fxk)lb6eCt>xIu=+_@{Uoe@5>`J6tDl6`Pr~XaVfB-+`bk**B&>cCRzC@=pM=#< z!s;hs^^>srNm%_PtbP(!KMAX!gw;>N>L+16D`7ozNDdnG5SV3+p)x>p2VSIScDK3+p)x>p2VSodwoA3#@k*Snn*b-dQ|O;hhE6I}5CL z7Fh2ru-;izxJGI}5CL7Fh2r zu-;i-)hub!? z$B^*LxskQkm3*}i*KK%vr|{1~mwSBe!zKLbhj+F$D3^KoAwSwB{C;HQYo6aFti566 zAyWs2lRv)H<213m5fr}b*}JCrk8ZqMO6QU}yM+x;`c;ho!EPyE%?XpQ=7eF*3Bxb^ zr93pAcBlV#+2Hc9@4JylJl->u@A3x^U%Y3}FlAEY%kJtCRvZ?2VdxQ_t&Dupt=+?n zXX0<~+_8HYFeLKOr^>?JzrDlL8E{-#_}}MmcYfdA*EU?a#QCt5-NN)nkz3jPF4|Tfel}S@Xl#y!M&fhqklldbs9_3D;aP{Lhws!+v|7<8d0F(l=cFOyrg}Kf2(o zb3Od%zWu@rqt0{w=w~*Ey8HRgOK<5HdJnw7`RNDyg$MWfrSl$-^$VAdxX^jsyZVJ2 z54*_us7v~V<`XZD@onBxw&_~{_UKyxtZxA@bC{bv7Hwb-^QSLH+nB?=al^>WVZJ^g z+Rq&3pm$=~nZvx~>d5+bLz?<_1MAxjJiq1M;rp9L`w74CgIGr5cX}q4opfZ+zyG>- zvS;iL`y_k1F4!m8v$*%Z$)11Tvv0EJH^T-cKj=FSHazo#F=6(>e{o;wn-1anrUP$a z?|?HNj^{*u|D4gG`+<*n{PrzJhaWGA{O0MS!ua$<$yJ|!jd{I1~O5g0TLEq_MeW!z)7QWNL`c4NAYJNl* z+bHU_*7PI7ZFfb!_P!&+Yu7}5pK3ZejJ-Pgd2!Fl;idV}|E&j34p%%B>)28KCx-#UP@4v9V|HAtI3+wx@!ufux_7d{tN5-FRbssu)hDo`u+=ReFd!b6|mMnjM?`U+UnmWbuYk3_0@nHpSnDfbt*?N! zz5>?z3RvqaV6Cr!wZ1~((o5?r2-o@wSnDfbt*?N!z5>?z3RvqaV69(*wSEcK`XyNF zmtd`5g0+4L*7_xw^+>8$TE9fN)-Sz81yUxKxM3D){0SnHQytzS~O^wRnz!nJ-0*7_w_>z81yUxKxM z3D){0n01e=hk>;|5Z3xYSnC5}tq+8?J`mRWKv?SoVXY5@wLVbcYG1^cUZlhN6XK9Q z>r!CyWxWcFJ*;Dav6J;JF!rAgi9~ttKO0h>tTpP`mBe6$(Qvou+|5{S|12&eITs$w=m`9PE{B` zaMvn~f4GAc#&6us3j6w4yR#L>&)nq-u+JLzlF8_7S{S(SnF?Lt-pn}{ub8yTUhIF z6|VAX{Vn07Bma2%1;3H6{E0pCGj_`V*e_k^H`qTyn)D|M*ZOwC>3@_C{gTqBzv6CU z;?R%D9{NM+MZYKewZ5JBgi9~tOE1!qUY>qIFY=XM*dx8LQ+i>)^rBqcO-x?&Ckm&Z zQGEIzr9;1@^y#m-o0#9ykI5eTH`)2$y3d{Gvh?D4ExmY-OJAPv(u?Q5^kO_9y%;A* zFUAkji}8l^(*6&S9ysqKah_6ihZntcek0+l?;VcsU-Bn<$BU{Q zFnVzZE{tB>jSHg}cjm(A#a+5Edg-24bkY5-=*6A9#36k3eYH_9`4he5XY`W)(M!6Z z7yI||A$oBas{7pZ;*L}py|_CSMlbGEh0%+5Wf1J z)2NsHiC*$EdddIjC0)>q^D*!tdU1!Q``q;6ZcP}yxN{RmFYe-m(Th7eVf0#kKW3b# z`l|28t&9y6Ap7^y1Dz;t;<2KE9}z{E1%jGkVGY=p|jyi}Ta)A$oDwoBQ1K;tn_% zy|^0=MlbG+gVBq-q z^9k`GdT~dX``q;6?l2g=xKj*9FYX$H(Th9CVD#c{G8nyd?-jb}J}mU&jx*vAzWV;J zsF(bSUh*?~$^YmjUC@j3Kk*@YEwwwp+~=kjcTU0R#a&b|dab@UDvm33?-lRM-1&un zcwhdi?~USoUGhRN?j(X4Z*W%;j9%Pf1fv&s8^N?M?mU8NU)+TR)4p`i4(&+y@6f)u zQ;9f)ufA_6wlDdU_9Z{lzT|(}mvo_haeg&EM6cEN)Wq+<+%betm`CD{A(;6k-KRr4 z(mgx0FYXv34&h(*JvE#UFTH;DKXJVQ?W=k~WZKuMS45_Lt+h>Dhd}#!_U_2EukxRs z@9EIKs`rj-5@<(lI>t2#w67)2;+h1)4|*#y@mt*=*T9g@PQQ$66-b|R+Ods%Ilmpo zp7*B5bxr=>@nmG`+rL`GwNKQ;2eye!{Zu&hc9TMU>a)^e9#82rzo&fBOZK3b>_ivY zk6tPl;VLijf0`x@dnTe$f6(SoSZ7S>)`SbJ$wTBee9#U9)NMY?Eg|&wi z)*ez=dq`pJA%(Sv6xJS6SbIoe?IDG=hZNQxQdoOPVeKJ>wTBee9#U9)NMY?Eg|&wi z)*ez=dq`pJA%(Sv6xJS6SbIoe?IDG=hZNQxQdoOPVeKJ>wTIN>6!wt9+CvI!4=JoY zq_FnT!P=JxYd;;V{dBPQ)4|$L2Wvkato?Mb_S3=IPX}v19jyIyu=dlz+D`{-KOL<7 zbg=f*!P-v;Yd;;V{dBPQ)4|$L2Wvkato?Mb_S3=IPX}v19jyIyu=dlz+D`{-KOL<7 zbg=eL!rG?^Yo8{peVVZLX~Np432UDwtbLlW_G!Y}n+a=gCak@gu=ZoZLtDlDn6UO^ z!rG7NaSHn}VeRLFwQmU4ej-@=j9~3Qg0(LR)_x^e`M76vT{{r<*my6Ksq(pMxL49$k)TklQI*BJTw1SX1Y}5dX3+5vqfh#9q8JPUi<^+ zkAC~Ng&&^Z(s}OS!8O;t)5LlFmKWD_-{tKZ;{Rm#KiBXF6UM*6#N{_IX^<97+LRF{ zPYbV5xW%tjd`rifbS!;m(zicn^0a@eis@WjV|h4}r{&>Ho|cC*d1m1iS^UZ@oysiz z$}Hc?%$};u&Z^9Q*RD`5!c|`4*A&WCmHDSC^Behk9P*^hg>qG9{;$k*smS%BjC1ba ze4)w+lRssI$)7U9w=EF#ZiDE_uMDK^`!^%=Ox_O*_w<{P+C+7FDx)RV{$4f3cN^zdHMs zg_nNZ+WE{i$JTsseskv?+sv!E^WHU_PuTLWHTGA@?<{PQ{hPDJU1Yy;wlo%5S`~$~ z7xBORXZaKEKDIoGUqd+Y$pa=G@_3!uU6sxcmkt4f23Vn>=9h%)%?O z_?1~Ym09|gS-zE-Jyn^VRhj+n<7m$ogsZ&7uO!^^tjhdTmHCZ)Jq}@JPgP9kvPymf zlSZbC*Nd$_neX+0vWXi%(Wr9#F-twX@e?OhKJ~9yCr-Wd&dOsKv~U|OPSqAiZSB0# z;!i5!ZAaWvv3%`!o#$QFweq^>|L#m0ZI}Pax&N}OD)}QmVf-6RTz&(S25G^hjcqV_ zTKGbRTl^Zuw{)CIXXMM5IbXWYpDUjlcAN9hFTJ61@$AQ)f4s{tDzAM173UcTjI6xy zhaWf}x4|Zrca2_S5ovDo&;=EipELPq;S00)HCZ|}S^70uzBQRWHJP0?d*9Z_^S!p_ zt(tYV{HK>|_YNy-cG><1&Ml8=w8+@~09zbq;@EF1v6J6sKCH=nTa)>`CexxO)2JrX zZegye@n_b7mKVNPK|Q(aSM3)5?6v!x=N*5^!j>0K^*VFcujVcMZj;#_-et^_7H4-4 zpLhJ`HD|Bvm=kJ-{{4E7^ONr_ zS=c!&sh|!&d*5RF?L!NR^Y8UNKFcg0NmZOW@6D|;Ttew%Er%zRjxMdm~MZPK(dt1}gu7WUgzH!3q7Eq ziFY5E_Y(eK!uU6sxcmkt4bp;1oBUw%P z$&-2rlV@JWESz^P#rJodLOTBL1CwW#FFMK|-npDfBeUPfPca>T=Tdq79gT3}Xa4z8 z@5|ZP!^T~4Y}0!A+^=N3#8|@YuCnxPe3F=aecY&U#xQ7`g?pUBZ++|+c>^E+5g(hg zF;5yFwqCx0r666zuW3oyAXn%j0C_C9mYe<9|QK;}f@K^I9yjKW7VDWdBBet+Kd_>^IJq#v)70+0ssSTAqa05T9`JfQe5YN{2jP z(&rB*j67iC@*9{mNDC%y@_-BFQg~$+zcNdwGE3j{;I|g$dBFG}v(xh+9G{T~j4!kD z65q>id6JGZ>12NMJoqhP{98=tMeKAY4e}tIv~#^o)2eOSo$2{+wD@@EZAWys@%a?z zd6(U2@8sNn+188f&)LGLW6lz>%13@Me#JHze~=%HpU4l!fBY~1;aBp22`3Mj_~ZeT4tc<&&mT+}{{|D6-@v4y zJV={72++`}y{ew3ZA9dRt}D*l)M@MTtB_dDVEGV_n? zL^$d52jffffQid*VC+;Lq@B-GW%F07=M~LY%=vxO<`q}BuUMbIE$u7U3#R|19p+4X zB%FSRc3S9TS3l#-C+a8h3BJKcu=+3HA>Pp-+U>Pr~XaVfB-+`bn6y z^YKYGZdpB^wDH?FaXe{S`q-HFDcT$3OnVPngvODJ-@mdr)C2vNv5n6sGfzw$y(|5v z=H#&_dvDVFi#?nmW^T<`}I#=pVDCkQPkZ)GJu)RTR!T5XEP% z5+)tiaKNO`JSI$@_HWMQ$@&w*$IP+S}g%NIjfzQ9e%!BaDuw{j%Zi4;o6byKKZzJ=nrt|D{Hpe9{mt^&3S)caH|kY6b<*adM|&Q`_y*rmPMvkUVqa44bC3GT@aY>| z+55t^M~HXd{fr)elvBoUFtWWPKP~RPVwv6>e)>i6c1ON9_I%wWrX3+Sw9c8Oo*;hP zWuNR_yy46Y;ht;Ys}H#m-ozX-Q&dyHSsq$#| zkUwmoEZQzcHrg(ZwhyE2;%Gbj;Cjd-TiHCU+A^%#2)pgb*e4t-ozdR#^~9giUg?ka z&P02~(cYP8uQ=K}jP{D7y~Aj)INCdm_KKsuIxqj?1M4aOh5o6FPJGIUyoCM#a{S{| z9?vNBRzK#UD#zDe~k~!?kO^2U&*;bOdWd7ygm&CDMT~k%tYneEe)CwijOF>a==p_o=CQ#O z`;jT-ztHt?B`@9RtYzZZA@a06>J?|bojm20{R_xcHoKfQcJkDfHmE#p4({qzJ!!MJ zlJERh+03!Mv>BaZeE6LHipojI-gC!tk&_NP`w>^%G;`}(ON)0p@+HGdS9*x}IsFd| z|G4Il!p?`Dv)O8&9P-C;l<^zKBFix_I?!d^{7X4?M!EJRQD?}@X5>SU7(JoC$1&)S zzbG&D#&7+i=L5qyMogWdOH7?nhtBsLUzJZ)^1Vt=5BSe1tlJNfW!r>9@(?^pFkj5>QFcAcFO)6RayI@?9L+l#!IIxGL6e}p`B z(l(enX>-xDVjo|?)LF%)_m{+XgXX29$DI7A;h8VFerB=tHxnPU^vT2hZ-2+=Z8x1c z{MycM8-DJFwN!q~GjAWRckS*fU-ucm93J|nN2>gW=gt{jzwz@_zSv`)IeNvzKQ%<> zo?qK!^po9|Q~3!;zhdL@^i0$ z7xF#Ik&p5zmxq3pqd)ZYtS9X0Bab~%Z=Z7N4f|D&{b8rdu`}AMa@rg1QaSAkpQs$4 zgdbFnAFA@HFO3c@dg!PVJ-tf4SJm6A^!F+|`;|TYs$Koc{(j|$e$`&}rSx0B@(=R% zGv)Rt`c)o&Ly!I6ui{9(qx4(9ihHk$Z@=m%v`g~gw_eqkrmFrE^V!*Tg9p>P0dvpY zp731deCDJu^Ihiou-6J;=DW;oVdlI1!IbeE%zT$)V6PRx=w|r9UMp}p^I^*~H;2)~ z{24}n{E4ZP`8MU$$-Et=PUh_}_A_sX$@5jY)(TQyYXvZMR{FJ8KsjZVJ)i&YZUF zGsQ<7`u5?TCp}qw?31n@eq!@Simx&*@tc@BqYg23Mjc}6j5@^BS(Q&!^1Vt=uhQSE>g`wd^ea32 zmHo=G*)Gc6UgYfu^oXgm@>`#_WxKFPOr4egdsSSf{*w5<@AQ?`2Y&YQZ_lj$i`CQz z{`2M^&b6ENk<3|dIcNCWtyYxGF7qxLer)|;59x0Y8Q(Dc;6Z;F(%*Kx;w!`N-SIHV zY_sxrhWv&Mviyb&viwG$M3y>`p-$>RhB~PO8S2DVWUw7uk->IsMF!hxGcx#qHY0-% zXfrbSfIfi?zJ!rstiZ@HRzlBIrDv+rGi5ztPp`74SJ~6EJ<%@7WV;ic7r8^P|*-FRT8H9`|STxIbghF#93)46`3%&k#M> zQ;jd$C7EoOWN244PVtXq@MSel`}9%j!k6?>>cW@wQR>2%^!4nA#A{UArFcmOUsm~t zxJw3KGKS^n@MV?9=s%LdmsK8%b)*j{XVTwTb0C+pp21oK%z6fE6fo-WtsS)X6#vGStbM4@{k`1;H_< z&Z)|^7L@W@3xcV$(%-M@?N|2nD?3^9kcv6Z^8z49CNs+>A$v+b$; zueBh`sdM&vgX^EGA2in+v*YW*HNNV2!K}w}UM7FRjBmzfuG7x0lZQ{pY2-$HLarlE z!Oo2^`5521oZM)6awF{A2$PS=jj(egOg^sszrZ?q9WQi}m-(-{Z!&v7YZ1Ml^?$kV z+2j5f_b9nvNj!ZYwv_9BuI_i0d#~NS(O$L3<8Ry#)7>*w{dvE&hs`iHErfkCo&I~Z z>u=mYGqKtB7vFYmd;s^=bg__+e4m;)R(=!zt@~~6@4hzoEUsNwZ|9q59+*Ab>p_U*Ym;6T`>;45yot1vwzo4A5${wwwQtowc7~NI7wC?Tl$`87K zK{>Wpe$%=)<+PPH!_-;%U-vI4$7glCXd~}^avSp?|)|r5^b( z^%FbSOYCe9u@mDP>OkJHD|%+%&4s^b-_14qZm!vPbIrb+i(IfUo{L!+&-FZT&mzsf zn``#nTo0aib8$V-IIXVjXXjkulSOgPHG8eDYyJo2wK}n5{>4~h{$pldl=Cvpmtf`@ z)jUpfAIh1R@CWCdOPq5qan8AB=gToiWA28p!asl0d^w(9*1JG?{@Ty~@=mJi-JuWI zyG(gLI_#c(H&;Gq&9l{&|Fu3j`);n;cXRPh407r0drM~D&Bc3C=nL^~mJ#ns$$p`= zVmR^#<;oq=UuNIU6+ZDhXNrGj-_3;|cpv|R{hj~O*OeD(kKa#3->=@iHv8_o@QvT; zgrEFQC)hrN@nw}y7RtNt>UhCEuhl$zj$8E4akKB{(mP`xH1B$49_M)$W4-X~ySd8T z>irMkw<@~1^8$0Xg|UY3xp~Rmi!ao7bFK8pb(+f$y|Rh@ETiiVSyz1gGOr(f_xJ0G zuh{~7Jdq-_5K6;0`SL5e@;C0bQzyUQhj$jE=kq)4UgSgnHGAzTrryJbZxmzC zerxU{#?Ir;+gFVJn>=GbG3|2szdvEBlRx98)jB=L-nMk7f9oah8oJ(Z?eW#2?K$)p z!=deb+v+Kr zIb@z?oFpT2T4@$jMxhVNSTh2obT@}c2)sjZuNub3j-Pk*pmv)eMq zHm~3B%fqYQ_=e`zosVhu|KiVw8@y?+=JczNZvOT7B}PB|=HAVXs~+9_dcPG%|9sv) z&F9WPs(Ha@*BBjk-M-C|uRf|7&uK=_j+n0WoTHkL-u2Sa$3MGoGv4W_=9Zgx9sTnK z`!rjH{8#55F#7o|dp9o$Jumw5;iDJsvsbfa=>O#l=Z)SJ^?oDj-SoRBkKX_N-I|Yt zJqH|k`e^?j?A)9YcJA@(Ge_4Q{_5rxTOQY}I5=lCjCP$J?RwJSywQ=--hHCI%iMbY zXqQKB-JBYJIDDB4M)uDNSDrVr-}-MjXJmhFx#O85`+4t=o!a?-=EV1Pak=^hM|JVq zdzFJmj^hP;?V(sZzFAjGEV8ba7-d~8vCFzzVw$mTiFNjYmOhYuqor?TT`hek`%=qz z$v*aHoc*w^@jf$cDJLc8_$7Y;Kgw3}>y#xQe2yZ4t) z8D>ssPg?$zVSoFFjeI^mZrg{5886Sd>YgFxjF&HO{6jJ0<$zCoUd(uT*i$YLGhX`J zA1-FRtp4bY#Eh4x-F)>7dKfQUAHa;4D4%k9$oF96Lys6epwAVUHMl!cMWy zr`tZHj~?ugc8PU9&2sviSesRy_DMz z$lE{YvER^de^Rggj6L>0b~-NDU&jk}zC{MkHV)xzqd40r&Nhm(jpA&hINLabp3=s{ zJ_2VOr(BLt;B2Ef+bGU9inER4Y@;~a*hf#cQS8`Jo_$jC*(b%>C&k$(#n~st*(b%> zCuP6;B>J;Ys=bsGJIb?9inC9Ovrme%Pl~foinC8DF4-r=v@2s*@_C7!@;q^mdX@j_ z53t7_>~RNs+`%4qu*V%-wNd9O`mM_|c9N%`TMzvo_PB#R?qH8Q*y9fNxPz~RNs+`%4qu*V(jap&@ko#YvJlzZI49(S1b{t{H5q2CUKgpjeCytiSd?h`Z$GSKo<2b^OBkVZBjw9?i z!j2>CIKqx2>^Q=XBkVZBjw9?i!j7ZMiKFE+e|B-C+;M~*N7!+M9Y+}Z<2tGhZq%;x z_7&6Kxb70;hqxXSC{dh9p!+n>~HKVy&muXtr#?j0{;$9#%5UVh!aE%U6^ zH)=+wowrZ>nV3%<_~kW5JAZ5M_R^S7ef_N~jy|-{UhRf4pW5~PON^%Xc|*H?%%^%k z{Q2Yl3@#qVO$NXZ4_NsqB zu37$_XAIX~Y1{TQPoLM^{@qiCC#|t{d)yu|uYC9^!(&f>ar=O|D7Uy+xktx^7;=E24 z=XJ7}>*QBHa_jb}m^1z|u9IK9__pnaF_+x)+vkt2xn+lTqnKkpIj)lzKkC)(RWWzI zWa^yJdv4pg{r=_0HuL}c%+dKj-mSeYe0$rQPaho;K7UF0{P1s_Ji2+`z1lxqb#!y~ z=JQ5(-m-W5qKMI)nDd@_{yyznB6fdx=>en1esT?&)XEE7Q*QyDOeDOgr1fzIw_q?QGZC<&0t4+1~d03x{cEd+7=7FzsxYIPA;A zw6p!d4}LyOJKINocnRCtu5{RnwzGZ3&1=}scA2#r+u0t!;uf}3IWzOjpK;9H7^ljy z+2@seb1Wz)=NM70&atB$o?}Y6J;$2P5jh5RF37Q|bA66kmFHNNe2#JH$+0i}nG;lR z<_g)9IYf45Zjt?&bJRwcS2;(y*Ltd)qg?HJtDK|UZab@-qjQAYRplI&+YeRFkskZ4 z$~mgney(y(IY(q%oO7bTsa=_8+O_W3)p@4<`gR96&$RQucDVCQd(W2hoM+mdqR(fZ zY5(<2r;jqvwAH9B#w(TQ`7 zPMm9WV)7w5abjpV2)1%J1`>TXVsw>o<3zg}<4;8=Xy8W8>zI-w9_2YLm zk9*}^(zEPN?{1o}-zL6!qxUp}W4=~++oPN1zWW*RVIMxWnc3|!@s>->Yj!#Rbn(Q_ z>HegAx<8Sh?%&+$3GVby_b2sE_b2vD_a}Bv_b2vG_b2U|?oZk~-JkejxHf(Ftx$bB#3*gC!u$JTL=IJWK&5y#g3B;we* z|3n;H_p69w>;4vTY~2qdj;;G=#Ibe1jX1XM&k@Jg{XF8>y8ln?RD82saZh>mht#8f zlKRzuvR?J8v`76d?NmQZ`_(_QUFx^lUiIhngZg>;NBuwjHqBZ~%Q~#`MsS=D8m>zz zXYG&cRXENE4cDP4RGRTw>-Q(*LSeG5}B=OD?4 zJzNjN*vUBy#(u7!VcNwx4yL^>#}AgrKh}fatRH{6Ui@r(@W1UOF1FwCqL0*am^E4QKg?P!=LMKGT+SCTYr9;>!szGx758Ua)?`_ajr%h# zYqG4z#{HR=HCfhUJ_h(w})36>J^M;oDG_1#Rp65Od>#=cvrsX~j>#=cvrsX~j>#=cvrsX~j z>#=cvrsX~j>#=cvrsX~j>#=cvre#f*_1L&S)3PSZdTiXEX<3tHJvQ#ow5-Xp9vk;( zTGnJ)kB$2?Eo-u@$Kszl7Wj?xvi-?*K8&9^kHh$%^E*sjIPb&6i|YZHIC7mpzhdpF z>(8(xtui%%d=)- zJ*-(+KWnnCm$h2k!y2ybj5U|O?T>c#t9JF>&yjckM~}w^`aNE#*W(C#Jif5g;|}{h z9%+}yDeZMRey}|Lu^#+p{rJ=M;%D1~|7|C0Nw(kdB98ZBwU=`IfIRH>!fr3@_QGy2 z?DoQLFYNZhZf};Wy(zEu!fr3@_QGy2?DoQLFYNZhbsH%szLqEMFnZ_@F#72yF!j=Z zVC>;yfFXqIAR{?@fG!G4w&bWuAKRm<(UUs5A!kWXCCN! znZMZ{=7F}8`JU~MeATs!a`#*0-Jj9pevW?kf9mzPz#fkm?DRNd9_#T%yFBh_ugmd+ z=L9qT1Ya}ge5UfAM8cE9< z1nUp6M$)nd!TLk2k+iHqu>KHhBrR(YtUtsWNy{1p>kqL;(y|7@`a`Udw5*k|{t#;< zEo&vLKg1eI%UTKR53xqlvR1Z<9$9z9Hr5_lcf>Z<9$9z9 zHr5_lcf>Z<9$9z9Hr5_lca&|h_Q<*;wz2lex+Au+_Q<*;wz2lex+Au+_Q<*;wz2jY zv1r^UW4w2E-ka&$IcA$G=QLH$X{wylR5_=qa!ym_oTkb-Tq8T@G>qBIMNO4+nkwfs zRnBRuoYPb}r>SyIQ{|k-{g5_RIY;t2mZc}hxb)}PSG}1NWKZS_*_k;+_GfNUyE5mf zy)LhEj{IXiRnCz=U2m0h?( zv8=_CXIPJAEmmutu^!7>EP00YSk_|6Gpxt57E7LCJ(jgt@(k;-ti_UNSdV2bmOR6H zEVg;f!qr%AsxjVFW520#LR006rph5*Own289LZ-clAg>_(x16Y^=3|!J(=rdXXZfk z6HD12`aK^(zvn6F_xuI@p4Xt?^Bwei9)y0+j~IiRH_<0u*S$IVs^^vTRnIr+tDc9_ zS3N(auX^4}U-f*JzUp}{ebw_{+UI#OeYGo(zS_xG^J2z$r=NLip7+TKojuHR^Ss|M z|8)+Dd?`!F=%N|AcCo=zKk0SdMng6m!k^PCxf7zqR{zT@#>``QYBJ*GN zD6&71`7e7E*`LV#mpzJ{znK5BN0FSv{Fgn7>`!F=%N|AcCo=zKk0SdMng6m!k^PCx zf7zqR{zT@#>``QYBJ*GND6&71`7e7E*`LV#mpzK?Ph|ef9!2&iGXG_dBKs4W|FTCB z-&WWEO*JoQs`)}w%_Ev>e$iC(j?h!)U+DC_4EB5tuI4qAYkrsVn)kt6|I@EvuK(#* zFxUU|E12tl`W0Nwzp&r)GTP<&n#vhRme2Wu^yEB3`g4AvdUM_(dvZQPyF5>k{W-5u zyK-Km_PV^92gyIyQ_Y*?PuE+`v*dr459OZ6!Nf7=JDr~?CyqJaQ5Y-gQ{e}9f@_0vNCqIN!k2v*9QhSHu8n&i*oA#C_F^|oJFo+$eb@ohZtQ^Z2X?^t2|Hl?haE6}E$!{fdH1E| zdvNLzr+#tPD^7dFX{R{t@1rN)`MO$(quP~mRJ$^cYFEZl?aDZ+T^UE&lW~-t8AsWl zaa6l9j$OIhn{gjzyR`Qap2V@MS2B}0c6O?K6304T>Yo`e_0No#`e(*V{WIgG{+aPo zzsh*2zh%7CKQmtHpBb;NJmS^KhtE4b;z_)^dR0D&S7)cnC-Iu*e9$tNK__!5<}xsI z3+6sBb1&vZFmns$N-%RZ=1?$m3+7gmkM#`ZTrhJB=3;QpU%PVZvpn^|=%GFs{nQ8Z zFaIz3_#HWzQa(p>tRg>0bFZRjj^<=V{~XQLO1*P5hb#8P zz02@Nu`}*nhM$W4b2Jw$?V7`NT#Fs_J^WhyP~?k$ik{-PqQCgF)LZ;q>?!^)c9ysl z`%An^yGk7AXpZReNgU^Bj%YoTIL^@=(e+N^81h{lV|;aSoa6bu+C{nBi@g0XiDS`k zzfIy;?6IFGaV+*bE_EF7Un!sN<3Gn8{}nycecIuEg8xdraZk33SKO=Z;x*mJPwt14 zc$ISZTjbrJ(c^xOe)oU=^|;{o;^$&#iPv-=eI+hk|7_@=*>A<^2QmFC+9giEiE~_t z)6Ye|_+OlH5$Cw;%EOLMKH4QlPuML+f3!zTz0s~BU-E!B`;{2`qg~?6C->s6e@1!N zZ^igE{3A}kiPN9r^s_kqFV47#@oQ;UH}1Ofu&HR9?rC_By_kcun^w@haoa{bUlaGVa{3Ch_XVSJXA#&v7RvjwN2* zI92&1Ueo>vE+amT;*C%+?yJa(4xqI|-6MdcAMts5XS zVU4>iSA0`m{WJBbKcs&3&#YJdC+$)HOgq&-(|(;7vR&$*+1^s_afe^spYdz)ThZ@v z$G;wT{9gQD?DRN7Up4MBj>;!p`6P}yZ+3bnanyM>-stR-Tx=?()D3CUa+&otJv@Hm3^|Mu57P3`?EOxBhLOW z&T%15Ka254952qeh;!U^<3#*yTr7sTu*kn zCCW=2OL-Z0MZW9LlF5E9PJfEi&*B^}MZSz9F@7!W>c(AH9`<$e#XsHnReAOkG4)3K zi+t%<;_Po?`bGFxJc(l&cP^jAv5dR$ujD6j?8b%4Cvoh?k;*4=?8aSJ?)K(5?evs5 zcH>&*lQ?#HK;@G-c6mePbsTB0NxU=<%6Jufik~$PB0ore60hn0e=K=s^MjLp>9&=H{AIDP0Z!oeP1ET|7 zFuJJ&&U#xoZ4_T}OWxBIu|Yp=Xayz=1uruoAq;%|TF!scyHyI36mHu3-B z_`L}^aU9pg@#4_egkEvBT^u&F{698Or)8+q$5N+tQm5;sW5v~*{ce(ca=S?Fne0r+X}PSl|8R8 zdthS?+T1sX{n|T=OxVxfV#$R4>^T;P{Y_;*d$Ls?_BWONO=W*m+0Pzm$%p;yjTVRf z?3osa{p_U{hyCoa7Ki=py%y)*X8An#GmCRSvpDxNi*rA-IQKKVoc+d@XFszz_a}>U z-?Dg;uV&9LK7UQF6Uud6$)AhP`GxBe_5X4{73XD;1I2k=AO&{zXUB{4v&%U@Qy(()FY1Fse@lHZ{gL`$ z&d<~bbAF~iIP|r)Kk8{2&n|a+k+&bvL;pYq{ak;*)XVh&j6Ga`z}Q)?!^?UL*BO-4 zt}_2s-e_GO^>p%FPgzgY)9H_Tx_aaH&Yq~JvylH`cD1yTcu`;F2XXpGoPHChKgH>1ar$3Oyr>VI8LzIK`Y6x%iZkxw z> zzvWfpC67LB^pibK(!Jee-49KfA#KlN#i>)A*W2=cUen5N_>Vmz9Glm@;=CRf=XJ6; zub;(vT`eY_5m#}{Be)J1$NYlpb8%j`i{lwJJ!46|d7ZEFy#6mTWnLi8d4xFU7vh|E zh;u$7&UuPB=P%-%*NAhzBhGn{IOj)Vo~4WaEzbFrIOkbKrp&*@IWH6Ed`*7Nxq~?8 z4&sIJEF{lgQa8Sh{`R1F?v*}BjIlXc{)w@yeyM&^o|#p7J_B30JOe9^e8PNHOn-Eq zp+C|u(L;ZvU&4{Em=BAIGyRhC$ZzVGaO6Ga)zTUHQ1eyF)3+*5pNnJM^a=4 zN!zFU6Q6V(zUpL#)v@A<&%3%t$V~cwXOGI$PI1~V&VE(+AM|WB{h$5z*#GfwAJ?q; zq8-F%FL7+M&I)B6d)>v4YM!^`n^k_}ZHG0ZYYrC2zfJtVIDT(JP8`QIalAP6HKA9` zp5mxaoaX}ZWDR7xKUo`@?oZZCru&n%l(sX&U8P|1uCDc z`9xjaT2RPzYedui$=Xr(?78AKSwGS9+B_$&@_g=FoX>rWxkioWzFp39-Xne%0To~Oilo)YJIN}T5@ah|8dd7cvIc}kq;DRG{s#Ce_)=Xpw;=P7ZX zr;1FsPB`7Ce>v{-FZT!fm-`9*%l(J`<$lG#?r;3=e#mj|pXhVHr5^WZxa9fzdHF^A z+4H;}R;(k>aGmD-!*!Z?at)?@#dVtURbHn>ZddNgYdPh;yv9>L%xgd8uDtf{{L|;y z^qV-ZZ^e^q3N8FBU{arQBB_C0a-Npbd7arR+xjyv(>8ccbEwQ-eCuG!-LOIaIN z`Q#ced{WlNRX({UobFGq6_wvu8<$LuS@GnWQ+blLag|T5QRALzSsPdR$UBix9eLp3Jf0%)R2w$wj8SZkMlg{Y3xC+%B2S`Qkhmi1QpF&U1%&GQa4~ zH7d_@kT}mx;yh=G^IRs*bDTKOed0VPile`At`tW<iyj9Q~Gat~mO$p1Yxq zxu&65UG{vIdkSSQXt~$W?Gcrp$-Rczy>_vtET6FUA8X2D{1USKm3;UD@X7^~d_yK>=kKv4qIOElomwOFGo_hw!bI*r+32@}4 zZjTN3h`9GadE~LbYL6E2D)%7Do*D8rdgxz_XE?@hr$6fH>W$w!d*V3yq2xoK?#*y4 z_tv;)15;k^4JmJQen5}U7wG4nkn1h?hKfDq-q8K;?cw<;_OYCD%W``6D*I_FZr8f& z@lDD!=JY%7!%@HWGiAid&zj+PKZAzf{Y)-?_cLqwJ>T6yySit48Fzl}p7EIP-qAR9 zIpZYX0fIj}J^0=F@r&!lU$zIo+fMvz`_u1g7v=viJPS;Wct$MzSlSiWe{L_=h4usY zitHb*Bkeb?FYQmRI~^~sN9}*EQymwsUmY*5^IXn#p5=L_$a;7-%=)>9<$8IR%=Uzx zepiy7NwfVtBUZIbN~5Zk~=F_IXTniFu4;M`Yq=&nEp)egc*0 z8F%DP$;Z2)IA^(>+-Z4oCyX9)r{qIFxf7;dawm*E5X+}X7& za;Mu%?u79Jxf8}eqS9{V3VS<|2`*iY{4+7)Be?Pcu3_<=DE;~&O4jNixs zF!3Tc!1$S*0TVB-G2t9vMLyz1?r}Le$@1hX7(L`L82wzM!PLt&8jL;B55?FS{ZLH2 zB5#O^m&<9d|@A+8+FDJMq8m&+(rd_7!awL?4C6PLv5h}r#yoz8$p!cyCPxq# znB0-qCz_|{bqnLe*Pksp$mQfF%agOLhg@d;_iX#gwcMlP^F$r1K5xx@Y^r#LRv^=C^Cayhxl^5iV*A(vS{ zInMQx`)m(6(RPOYeuqX|U4POpUw^j9+Yjimf6#BgQLp`pJ@zwp+W*+^xX>=gi}t!4 zKUg0BSPy=)e*Ecr@w4s0|F)C3I9}EDr}o-8UW{S;fw67>Fy`$ya)JFxj@q^{@kM-a;>&Kt27eCt`{BJv}>(3_Iqd9wCi<(uQ z*PrBb&ENC-v%wFHQOfZTV;9D6jA}x^5iNQJ>)RShkkM!Oughhn0S#3 zVa2OlXUhJ({&c(g$k1NP;|J@(Kh}@mTrd8#J^0yn;(u}{I*H5Q^V@cL{po(#Vguug zv1>mtreXZUScmZ&IRGYJf0^{2|oNtP#9Sr0i3MnAa?re1O$ zj6LK+n0S#RVeHTAPqoYC#LM!;%X)~H^%F1GOT26k@v@!7i`+?FIljbM&oCv{;zIdhdgFO9X+IqlQG^O1IsXB2+bS?9FRe50NjZ0~vY zdF}eo)-!|cEyrKb-h9%>B+tM6KgaSraxlknJd8f{!qh{36*rZPIFA*lPI1;HP8-B& zn>cM2XIsSCMspK(Sf&a4#BppBb&Er16LpKDt|sah^DqC8&HRoW%yAr_ZE2!zG4({< zHMfcM2Q>SA`osKE{H?}(Fgob*bv)C)!M|}Ty@qfHykM^Z^ z949{RasS%(Kg&LfIqmD#epkEC+m8^(zx=;Aes4og9LKeByg2lsR~+@Q2dU;3ohc*E zW5uacoOOxQ265UZPMgKq7IC)G++atxx1nwrd#M|y9n=leKI(>PH+94KgSuh-MBOm{ zqiz_#Qg_8oB_qyb#i>)Ab&1mkaoQ$Mo5lE;y3vo19aHvBcs>X(%y**J`!rzoi(DJ` zXeQk4D~`PlH5ZxUs|n}#DIS#Xp`|VPj&AjVxXxs+AIx=T$Clw8vwnvy@1FI$ZFwi{ z|K`1;)a7|4?D-4qc@6CO4(xdl?D-Mwc@ymU6zq8x?DRw&_xqXK>b=eSPKw_}f9m8t&-eSCnkqN)uKNe{J1prFzgt*s$+53ko2zlkI!V_b zs(#W|{im(^Rm(W#dX>5ur(6%ij8m?MVa6%f!!YCY@9`~+Vo&!jT-v4eAIh1-aGeP= zhvE7YW)8!3Da;&(>s6RJ4A-$Ra~Q5~VdgMg_rg{FQF~op;f4bf(A7ZE0 zf6(vzNq^!0Ss$Rkz`W;~cR$0t|CxRV^ImA)6%F&gX!@yS{=#qBGY*ia|I_zjzM(+h zhx2=*;{4vInEr1Y@_VBy&+mNC{O>3X^Z9m)^8Wue#WN#12aZl zFMR~#j%>kP2h86=yH(bp{ywS!aOpCu0=$Is@!=2H5KiFynfH?C&ktumVjGwJP$7xF&t8uD!7d#>E~RBeD-H?_GfYSXT_BMoa5B(QhDYd z$!Go%XZ{gq{t;*X5oi7pXa14>RsPX^y&R`r=Nw`)^7c>WAC;ru{>=QN^2|Tt%s=Y4 z*w0!7YfTY5t%bnc-|WBtqs^n9Rmy+=@N=8Po_~d8p1b)4&6c0OOnmEl7d20~`Vuk! z^8e`JcjRD><9HZ-=!L0=x@)H1r$6_~=J)ZQEco$=9yYdNtIEUnHrgPLHnq_< zakRCKHjDX}|3?qMBL{OF$HVADFHD`(S2Oim2KKSAb;7O-whgdtgKabHw!rCg*Q+*D zo^erm#!H-W6lZ+J#Mx~p&h`m$wy%h@eMp=uKa0~g$-q7qwoce}!L|XmZLn>I-4;0g z+*E#6+|$o0Pd|&(&*Jp6IQ=Y6Ka11P;`FmP`_cl8J(hueENq>y>w;|qY};Vl47)9` zb28U~eDj2FpYYuizInp8Px$T$-#p>lCw%vWZ=Ue&6TW-GH&6KX3Ew^8ndBV3(`0fecJmK3XeD{QJp78AxzI(zqPx$r; z-#y`*Cw%*a@1F3@6TW@IcTf1{3Ew{9yC;0}gm0hl-4nif!naTO?g`&K;oB#C_k?er z@a+@6d%`zQ`1T3kJ>i=teEWp&p76~RzJ0=XPwXGgiDu5}f6wQq$lugWjAp-0bKl>l z!9QM?gJb-5eH(VXU_b8$`*}Cm&%42X-VOHiZm^$sgZ;c495GUT*f9J3-2481uKTck z#W?zVKIzb2s#63;&jOL{A%|P-G-wouOfqXlV?*{VCK)xNwcLVumAm0w;yMcT& zkZ%X_-9Ww>$hQOeZXn+bP znA7*=!nWJu8*_YLj_=IzjXAzA$9LxV#vI?5<2!SFV~+33@trxoF~|4i_|6>PnB)6$ zd}oet%-OcO&*xas7=!)HGVEuTVL!7B`EAQc1l)v+sxms&1 znIFWNH^iAw#F=NrnSaEYm&BQ`#F@v$j3>rYuIGqzJx5Ic$#Z(kx4iS5-tsN)Jg2vJ zNB_xldds)G^PJxDE$=+1w|vVx&*?4S^3HR5%eTDqoZj*+?>wise9Jq}=`G*#&U1Rp zx4iS5-tsN)Jg2t@$G5!moZj*+?>wise9Jq}=`G*#&U1Rpx4iS5-tsN)Jg2vO%RA5M zE#LCab9&3Syz`vi@-1)sjeg~L!HyT~c)^Yr?0CVB7wmY!ju-5B!LEzAENb75%zW5Z z`B2|@&3veDykKm__5A}`L%!m5MYvx0J<2Cc4zVVv*P~UjXe5h}{WN~%g8}*%E+m_ddf7f?|P&YnV)V_Tjd7JlYs$WIkUZlPqOzy;Q zj7Kx$)N#!5t2n}WZffB?XNmJ%CeCx5IM03JJSU3tnn(PPdPhput9yC*ZkBkjg5I5# z?^l`AitoZcS*(j zgpasq_~@5k9QMTfW`A|&*2?``9Ajg{aSOHT4urv z-m}a1wCMV6QGQq0q>YRAJLf0&L+g8>^11RmeS_RXKZY0O_y14q?B0Fkev;n{nC6{w z`5ghhQ!c+Rpm)mUcL%z6F6r2X@jkTL&Izmkk4k>1S?_D2TsbhuuX0Ns+f*?M)|et* z_u?+TlApXAs{5XT%F{pM$vdXH?=q-7-xnvIysIkSZ&|+Ypz_JPt)kETmG3p3-0xeo z->DV;CyzyYyLSeP7v=X^<#<<&ChxpbAK?6|^2s~0^bHQaVWINLJGJ!9j)nRT-idF! z^Md=o-tU=xKK#>FZ{?Dv;gl$=`ukm=dsyN>}D$e(g>Y6Y) z-rc9`L*CsQHtX7wW5tuU=-MyaShKD}x^ns^eniiNyZ4mJKa=uqpQ_|1?^ca>CU@^# zozpA|@4{tGpj^`~+V7-I-$sAvd>-7z>s~yqXJ5F7$33Qc&%Ey^R^@Hzv5dHu@qIw# zeSZ*M82A3D%X{p3hJfb{ux(-N=g&6&nSauT82fs5W1&9FkiL}-f9HGXouBLY2J8MS z@r50W+D@4Mgnv?|V|;oa$96j7cO8RF-UDsnyf-S&d#2*NmnzPCtm3@)D$aYd;=ETY z#&+z>IO>@hIG<-xc|PYN&gWmm`CN=RpO+CwKfKRpaH!{AZEvV6Z4l=(JL1$MPW|Gn zSDf~U(@t^PFJ^rBS)252gFhGcJ?q-Hbxdm;>bBz>`c16cG|8;JEbz^>`nzxUCxZ^Y zTNb|Mn`I08yKLAhJH0;vo4s!V_I?J~`y62Je}KI&0(Q=XolD{SXuEtxd+|jjFHSw; z)Gy9@#c7W??G&f|;%t{VeM`UkyMA{s+t|{^V8&6$j&<6mxYu?fkMFQKkL}uGzh(KK z=|nfbaqPnW)*fx5u8gB{AMD%(JEy_Ub+B_F?A!=DXTr{-=kqA1PmmuLxF3PMpA*butw((&W2gRf?_=|R zy5hSq?q$$-usi#+7#sf1&x&?!&*w=s*77-1aXx=4&gW9a`Mjz)pJNs0^R41+i&FUYUid)~lpf!!9^ZGqhu*lmH`7T9fp-4@twf!!9^ZGqhu*lmH`7T9fp zmwV^sjoY&I{uefG$_Q|$8p3>M?S3T#X#y;F~nG+iO_E)za+t}x; z-gI>1SS<0gqZ-F(?j}b!j@@w|Kc;a^f49TD#<70NquzrC=i%ymZ@cYd zb3e3G;Z;w(c<$883qR_mm(G3bOA7DzxXU|!&5c)dG7mfOAbmg=u~ zSK$wzdv5RTe=5BD72lm2Jgki0;2Cqs3@sDKj(lwB99gHit_yZuu`1w!&XyHRQIez}rjw<}jz30up{Y{16yYq4LH+f~@Jy$w* z{zaP?Ug_+k=ijnn;nzRnsQJBT6kc=N_sm~;wZgx7@8R>WUS&b9+XA~Su-gK=EwI}H zyDhNW0=q4++XA~Su-gK=EwI}HyDhNW0!Lfsx-C&Y*KG{>xo&&tnQNbf{<-#5)H~Nc z414CsUm)<~l~v-noul_+hSN8vdE4s~JU%5-+y_R^!_>#Q}@BN);j8ERT@Q>Ry z$KOky`QTdPQ{Pz1|7*`@j&I(z@SE0Nd;In73$J*~+T-6nzwn)JS!aCJ`h~xF`#R%O zRx13)7pyzpBCnCwI%M7Pn}2k)^1}z;yYBd#pI?w`n_=4w+h*7{!?qc=&9H5TZ8L0} zVcQJbX4p2vwi(9ewXZ9=VyAyEd3)`DCg3;S5u$HE+Y;D?UVc%=Nlk1UM*vHKOq zhM89_$n~+-$+57Hg*obm`&jtiZFgJTu3E-i*X3M+JY36|>m2Av*ia1-(MW96aCf+ zTc;VFmO&@XvF@K7yVtPvLykS|YZKn!?!w6IvciI6f%c+@F;eSvUFd|Z(~M5bpc4+i zb=N8}PP=QE7{A@MO^oaAnkUA4cP$iopu0wj{Lo!HMc(MHsUn|r*IJQhx@)k=Ki#!i zW7Xy!%I4=);EfMGIfv+**JU;NXN1WdWz9xzD{=nBNaXm2bHB4M5 z418@9*AD|<^Tc(*fzkn0k#dWZGde9Y#U(P0NVyQ^1#67$~cb< zd=8DAKk&H~JF7e_u8)O%EbL=pj`g{ca-Tzy_qi1toYTzpvDV44u#bh2_qmdCpF^q3 z=T>Z}&Qs$0SnK3i*vG;g>+=`oK8I45&#l|^0~%3Z4Wvv<8xLWFZjO3mt{B>cK(F#tDjp2`TBh4oQ6NmwG8a@3o>>{t=DE_owN0tZLEK`UdxSj z(bj9cv0mDG?Kjp@TdxVn`fBU7;#hZWy@nj?v8~sZW4*5RnzOlX3+%SQZVT+Tz-|ld zw!m%+?6$ye3+%SQZVT+Tz-|ldw!m%+9BYzewR-YafBU5*l~m%N7!+M9Y@%4gdInh;|I&*AJ}n(9Y@%4gdIoNafBU5*l~m%N7!+M z9Y@%4gdIoNafBU5*l~m%N0$>v%M(Y~afBU5*l~m%N7!+M9Y;9YHTJlR^0DI^@?*z6 z^o-pfLjTzPBx zK#%={e*2Aj?N98npRv>a$9~79j+eQPW5!qVu;U0jj1b{t{H5vGmA5q2D5#}RfMVaE}69AU>1b{t{H5q2D1?s4ZhQtmjy zjw9?i!j2>CIKqx29PJu3PblkkQ9d~EiG@Rcu=>h{L(kwDPc0n!2QOQzaMU|^-A0AO zp25SOTR7|-{P-n>$&(-5sW5r+hCL_ccONj3zx;^8=z0H%h0)*taAE4*^1Q;>v+t#a zvGdJW6~_KmhlOd^Ye$92GcJ$#cJdMTPEYiQPJi^1uHNWBojuX72DXztY5U2OZWrZl zFY@*Sdh8$c+i%ose`1gQjGgvB_B$?hyv%hRGrp3C9Y@%4gdIoNafBU5*l~m%N7!+6 zIexG_{(&7w*l~m%N7!+M9Y@%4gdIoNafBU5*l~m%N7!+M9Y@%4gdIoNadbIxv^;Ty z9Y@%4gdIoNafBU5*l~oTU1N{CC?7k%AwPE9L(ka#A@q;kPomzj`%l<2cE2L;xxbMo z-4Dr=RsS5j-y-k+j2@3W^n2V2e9xK#%={e*2Aj?N98npRv>a$9~79j+eQPW5!qV zu;U0jj1b{t{H5q2D5#}RfMVaE}6 z9AU>1b{t{H5q2D5$I;~;ca9_Fjw9?i!j2>CIKqx2>^Q>FuEF*nDEEeKz<-Md7e#@Z@U?hn<7PzgU<&Isfa0$&)|+@ud8*cTMEK z_|S4s3O$!BTNwSXm{XW~cX@hY>^Wwg!q|D-hJ~@ew@G2z^|qR|DHgp0xesNw^Q=XBkVZBjw9?ix*R`P9{<3OBkVZBjw9?i!j2>CIKqx2>^Q=X zBkVZBjw9?i!j2>CIKqx2>^QodI9i@K!j2>CIKqx2>^Q=XBkVZB(XO$_U6hX<-;f_W z?xAPw{t)`d?k7?2*!?H$8M|MR_uSvelkSJ)$*O;j-EWb1e@2hT9r``)sMq5Tdpz#2 z)8h{NJ-%p{#~pdb(kABkC8~vxVhrDMy$&o&N9AU>1 zb{t{H5q2EmXxCuh<;&jSC?8z3LgA1f?DWLKp=a=#RSJjx!4az$j(P_t<#PdH&tQ|e zd2F2Tp7f%^h{9$ulmG_;&IU_fAjrhfaU=ldj(AKb<|%uLic0JZbyMlWrH~ZZGoo z1A6Qq^xJRLYky*o{fwRVKlVE=b-c`V95cR>haE@QafBU5*l~m%M>zVM?1vpk*l~0@ zey}|LfgMNKafBU5*l~m%N7!+M9Y@%4gdIoNafBU5*l~m%N7!+M9Y@%4bUAUfJaL2_ zN7!+M9Y@%4gdIoNafG8?V~@KiA3MGwKX%+h&)EGT^pD+7qTaFlPuMedzasCszmX^1 z56P2N{~WvDBJci;9*;Zpd)!g4#~t=~++nB39rk;C(JqfW@{G$PzMXu;z0(u@q0=Az zq^mdjPiGH#&vue0Z9jR^?V{Z6Mc#fukNtyw`;B_-PwcUuvD5y?e#fPbm${B(##i#N z;|M#Bu;U0jj1b{t{H5q2D5#}RfM zVaE}69AU>1b{t{H(d8a@jw9ucBkVZBjw9?i!j2>CIKpvXZ(QB)6Z?K&Rjzx2Sw61r z1BzW<$uFR%lGi;%%U9(K=<&Tp+g96SwoL4`_^bBEBJce(v2Uc?8yS0S?sM;M>_7Qm z@0p}7?+=N+K=--#7@2S89{$)9vdBJb;Qg-h|ATN(d%f=$pL?H=_y5x_@BfFr{~z}L zf7tu~VekKkz5gHf{(qRdydRAI=6zrEH}40dZ+M>={muKYV*k?rxM$e8m%3)po8|h} z`4*oz-@?wfu=6eKeCzUseBPX$Uxd%&{QF>;U(Bw(#UO^>Tdqz9Hkw_Y)akzR$?`S_JOv&F+85@#T0iz8tTZZ!T*4 zAI7u$#LD^0`_LF)-k-+!^1e03m-n-Aedv8|TpxP>8|4dmpV+|hih26L`^RGb-tFg% zd40FfGtSH1{?BMvw=Xo>)$JFJc6Iwm!~Sl6X|$``cS^b2i@g1S9{UIV_8axupV;Gl zec0)Jeb`^^>-&FlKkfbPulD|J<`jOG0rs;Du%Bgs{VW6QXBl8W%K-aX2H4LszpD%#@d;#p|3t&HA0Q>m@*v}Whe!c+q^98VSf6en^Jg@Y>ea0%* z3jW7u$B^;bg`Ww+PCxet`?){Z&;7xE?hp2Jf3TnXgZ&y&J_o)q@;q_CeSh5bA!?B_{gKTit#c~aQVlfu~MHA6qwMmf&_-q*91 z^tb=*Gj!DDwNRc_ysu|1|1a-LdBESZvpAP^?022fUcc)M_Pfqtzv~S4yUt+0>kN)_diUNrzh91Wzh4fH^K9d1{o?%l z4}VwQy`I}z;NDGjzee|WxF6)406QnZXvVu+NXM&yTRrkFd{=u+NXM&yTRrkFd{=u+NXM z&yTRrkFd{=u+NXM&yTRrkFd{=u+NXM&yTRrkFd{=u+NXM&yTRrkFd{=u+NXM&yTRr zkFd{=u+NXM&yTRrkFd{=u+NXM&yTRrkFd{=u+NXM&yTRrkFd{=u+NV$eS>!qz&=01 zf64RUzMq1;@29}C_piHsEZT>FPna)ze+%$`UCcMxpCH?E zzZT5=l>H1a^H%mbz|3da{{S=3WnTo${MY+im>1iA=F9A_K!$R+7kT>uJ?tB?e)f&P z)XTmR7<<@uy7yCxw=!ac-^uta*_APXJd_M(w)}vf6>ru8R_C<7d z{v-GKu&*`SHM<`&;>CIt_fzmm^dH?%ff--kFU>geeon?0`&yBqd|~g0biC-F?01!I z(QnxY3)7$39}CmZ**6O_zSvI-GcMR?3o~B4Uz%}b`x#$VyR?7a^7aFIxZh;`_8awb zzk_n@VIQ)N4LjL~3}Zk0jbX+Y`;cMAm&+MnmS=of597=FeLsa`8DF-C@nt(1Uyc|1 z=-e*K-CpGF2lUuK=(pdf*Z#yF`x!g!f9!W$IDhe+RJLpO`I?9kw;#}B|DfM~qh9WJAdfvf*QR5`PM&Lnv7hJHV8$2EwZZgH zm(y=8Pk*)^`nmPf|6MQR!uBv;Y$xN$@nU?rU6i}MI^QjX=MY(+&vuPjpNFGedhQ#J zcIkO=INGJ>#NlX{o*##!U3#t@4m3I2m3i9-4p5KS*=RDUB)BkziA7)(e9sro}<@Y%-zWls7&u`uWMnO*Sk2@?-HagzdH_l{7yOezTS6=PQN#mx>(z% zE_8a0g1T7Sx6Ry}fW03Wjx~@m@5zK?ZA9-Lhhxn|?;eL^Ek*AhhhvRJ?;eL^?M3e% zhht4f?;eL^tw!%2hhq&#?;eL^ZAb4OhhxoW%zHuMSPRm-$6@aWhGXqZ@3@9zO-b*# zhGVTs@3@9z4NC90hGT6?@3@9z%}VdMhGQ*D@3@9zjZ5#ihGXqZ@3@9zO-%2&hGVTv z@3@9z4NdR3hGT6_@3@9z%}wvPhGQ*G@3@A&9~dSsUNiK5V9LE881{Z(*!zKD?+1px z9~kz2VA%VCVc*w)eP07!l;6qk`!Z>N7i-@eqTKg8VBhb6eZK?t{SMgoJ7C}MfPKFM z_Wcgn_d8(U?|^;31NQw6*!MeN-|v9y_x$@?1C&2d-|z5!2Xy+r1MK?_uH;3EB;=kuDy_opl&$@Ev;jg>euI(a7#JPsg3(PKFm*Wn(X*)Eq)Rr0+`Pp{J7tLp7l_Vg+{dzJnD zs$Ko6z5U7$=ow-gbyj|(UX@cPZAOMVEC2VZxJ=dYdgD`{JX-JAQxv;h+b4;Cckwr8 zesk*b;`hJumBWwy>Jj2MKJ~-H4Y#~wi2OlYePPHSOc}qy$Z`yf4s^ljrj0OlM){P> zL%wJE&?81q=oh0u{>0Q7zx9ir4-cabF?B{AV(N@K#MD`pPgU~0N>8uS->d5FRrd5N zJNuRWie0vga<>=xVYaJZ`KMp`jd~?RowPaI)vNs9tKu?M$BQ<;_l8ww+(wxCX(LSi zv=OF$+6YrW^}*Cn8)53FjWG4oM%b}~Gj=mBrw+?g2aF!-fYHw%Oc}qy$WjN44(foh zpE}@dm&=Kr<>jl?BOk)Fsj8RQ*&f9L8GJ(>F#Uo$ik>GcrY^7iKKdw>`nO*8DgC22>0blycH+}i{?p@sGIQqdR~Db}kUfU? zocdVt^H)7@_^Hn?CO-73UmM0>kK>|j6u*f>b`-~mL&qp|O{MM;|MFkdPq};?bs|5c z9C_-1(L)_D`uT$?<2M*tj)BpEE*Ra^0rOu~K2^#0Dm}eQf3K>yU)j^I?Ce+e_e(8m z7v*j*^7aFI#8GFz@>@UZ)$x?^8@iAUJH_az;xcuAvHRhNo~$^&?Aq_lT(;xm#ZTVx z)x)WS9wpv-*|UZxeEO~)vF<c2$B0A6D0EFBAG$}_1xJ6Oe8%O} z0V7WxFnXv1Mn8WrW&8#s%P}xIr~^hfb->hFl}}ajy-H87(%-AlD?9s@{qk|K z=P8uCy~y_{k2?F6fBKc*s8=$Sg+2YE=d2#b!04#rqJHtTKV7AMK-cAzfQc_&;G5)AM%v(8;mT+!0131jBad$sWZxFTpsd6%ZDB@dj9#gv&3gE`Gwv$ zb{dQ4oq1`mJ^sJM|FY$Yy>ssRiTE8m{Bv*mpY9PKvceO4pV@V>5jt1D>9nb+PfYz) z`Aj80tn>^k{llu>VP(&-vU9l2c&_TbVED`7l284y+O^eMe;97L>666EzkTshu>1gr zj2M|XwuhY@TlsKU`F2?Od|1U|SjA{q#crmKY4HEp2bQ1y^%VW&Gap%F=J20?QGDJz z&zM<$`mO3SpZUmnGmm=2@hV?$_pgV{Rw_U5ovRE_{=*+P;n=T^emC=&jjmC@TK&%7 zhx{^l$PZ*?sZhu9uxEnS(doCyqU2iaz<((L07;KVzF2Wd7qzx6ds5 z=vPSQ2aoz_9DCt4$Q-i!p~F|*dWmEXTKd|VbqCi@(TBhD#Ws$;X$G19_|o3P%l`QX zl38iJ17==u!D2JW%zeVA;@EYE$Q-ovro&4fyV#JruDtt#YrcQLoFOtR?{s+_yPITI zTJP?eN@kPIZ#%5Wyy%2D_Fa;>^6oWfs=B70|H2C;v)pb|waipy^VEA*`h;XYJN2$O zwySHZYI`jc$96XNDj)W$x_VXHdsQr^Dx2fj&WF7!j#E|J zJ~LItB986)Mz4xv$aj5ds_Fy1s?RKN4PRZ`&(67G?!!E6QJZts*M8MC;q0|~TpM#8 zy(nL+6FcT*oD-Rwn3=P{%qN(ez|3Ws zQ=Z3S{{k|V%`TUW{K0;<1^}j@nzLsnS89bv!9(Ot(2rhWW} z4F6&m_QCiBoiM(lE|~UFAB|1scU2AQ;avRGh-e!BF2RmoPSj^^aCHuwT;%3Stmxu zbEOArO&)uyd6VZaagKgq?j2P2$2H7ke)Pbthu`8}= zpTFET&2~pF+lSxq)2*7`D~=cUj@+y{f4Q5)Pv2m}<_p&@(IB(??yEHX!Ibe^(er=U zdk?6simUBk5fv0s5fl|c5wXPz3Y$q}0cjm*wty?d4{4fR^pMe?6HDEa4 z0>h0DFg_D|k&O2Vk5Bl0;@2nflu4Xr5`TGWi?LcS^NGE{ulZ!W2b<5*c!bSoY5cA$4aaexkVY7vQJN{JrY^m_?7WB*SeR1QQF<0%ftA4=P_^jet>bM3B z2V7vd@d0MN61z{v`-I2igYm{+CVtB#o-&EEOybx6;#%{G-Gj|1b&`V5#}g%2>jioOJfpC2$bJ_9qBYrt^e104GyIQGL} zS3eBn)ephMp76^DcC*O`m|P}t$_I9GM(*H<`wPrEQnz4gpLzyU`_ws@df*3)jnBZ0 z8WQ@3%v_E+H1{sL3`iC^|bj7R&6G1M|Xz{aihs(7mX746h*98W!i zseOEaseOLH*!T?0SbTutzy~<)FL2yn!LFFXc=-Smd%~~%g`Hd`@o0ZxCpY*2le4&9 zZPz{_-|6!9n(v(xkImm~ca3oSZw|}buKj`Vl={8%2hLtQ=h_zgb;|hxW8*V0W4Q(l z2V7vd@d3tXV)w~-pYZsEzfAm=Njzl|XPLy`uwLd9yXI>?882);;Sn~U@R!79K1+VU z*!T?0SgrxX0T&oX+#0QvM@&m@kXJE#14H%B-gIwYRJAV?p)(aakCOld%?93_gtM$T84w5*vUf7LW z>jjSM747%{lS}dgh6f+uxL#mvdt1fq2alT;Z>}}UCf@Jt+!5~BX`X4^@xsR(Gt>I;Okr$% zR`K+)zJ0$i9B^TW8y{f)B=#a1Z|7G7kDXr){66t(wbl@iPvZ1R{NA+M#`rOx*mbXK zJ{j+^n@@Oz%_scA<`cid*!ZmC>0{^D{laj-g&l5ufbGn@KCx%Xc=8i@$eS>8O8k;% z*~vi?C+ia9Hx1b)=Pbh?8XJs$L}P=|mFP<_nih=>Mu*yuF!~gYjUC-;*9fC$jVr^B z&c#Q?Q)%pI#|N14_yEI$4>0`vfU)rzIBIM#9QXi7jSV(ke|=(?#t!49vBAWi@JnN3 zH=8szm>eW=$_I9Gmdp!#oG;@YW5{KaALbxC{QNKm8$Q5{P4cgMBJ6Ne^I&{Z^I+DK zng_GatT&kTr{=-b1@!@@UZ{C6b!68FQ(wlV_+#BwJXOtuvEu{Gczi@2e1PHS2aF9L zV8(I{7!J6=vF5?H&s6ilu9^?yRr6qCPxw{y*v+Pz2gjP%wU!%vfXP{0FLIg8mp$U* z_#{8@%ML$3jKP-VSv^YEh8_im8(-X`vCmjPFf~JMfMadM`#90}KaT zV7T!C#%E$*cE4;niF=v+#JvnA|CYPIxnIUkF3BV72<8VIa|`CWWS`QP;{Nr?zFyWR zEm!~QKFK=qC+=}Dd!IcHreCth!R%x9GdS*XaNOfy#&Qi9j@U=o$vQG?LX^&E#CW5BY%&%H^$EW9ruc0?)$ix26I2iy&^c?cZ0F<893f|gW-S+9Phiq z)J$um%Je4Y&E`6oYMp7rt>n6X>~j?a_9aN`e*e|!Wx&uQa$Jx|8Y zv(SYYZ8xq z=vvEV62EfSsO19p*#$Mu(}!%gn0cxu9@wz%J7`x~s7u#;nA1&8?xhxrPJ`C9Dv$N36}`3i^m3Wxa$$93dd zV#EiS*zo}l^A%>U1(O#I{#9Of16TK6zs^#CUJgrEA1e&vHPqU)FpYVh_6b^MLOs!Gpj0tt< zz@ZL>Lmdi-Ius6dD2z{Pg=_K2{sP;0>QFe;p)fuZzp7EjhdPXLiVJ&Mhc++OXS5R& z7@x!%d6)y(=B2rT@yVRQ#6vE?#7U08#82+P|EfOO@4V~WersIjSAJ#R4E)3c7yCco z{G@Q}CDZ+WYpmn2cX@V<-@5ZI!l#~ooVOogvw8bW*v5LhM%XwC;}SOR!h8s`UWq+R z#%BqSOZZ*l*J5pm$0c#PB!2C$FfZ&ym>1)P@ky*HTE|-J$&DLT$gXE?=wB{ zy?0aBnjrfhPpfxBo}VK8$)r2oJwwkEK4a2ccTx9?gxB5mHdijXSh)KWH@QZwFBQII z#~a-@PhZL&*S=tnCq0dxAUpkoenj0a>%ITGz4u>H4|`1SoKbH>ejMo^*g4Cnx7MqS z^S^(!dq%yDtDodg?6YS^z4@Ng{lxS3$*8wCR=B{o_|xxoZSP&r@>jmpE2H*qxb8yV z|Kz*Hv-$VKe2X!CGU{;Gr!MlxjoUY)4v(35vA=xrJ>p+|@EBj)>jClK{LBRZ#hH(Y zf4d{6_%7cp?}%-S4UY2d=RGF=FF%;-r>?bQ}O@UZckq>YUzmoZtr z&V|*V_^lobTUYVhIv2LC;CKeyh{MdZ_s6saBWbw>mAX zpNb#5)us5YP7A9`@mrl1)@Q}f80)j*2V0*NKRAg$vz{w{>`DBY^pVPf0o3bCGlrT{<9?iS(5)OsUMf*KTGPzCHc>i{AWr1u&-kMu&-kM zxTOBsSFwIvQvd9$SU>EmSU)bQf0xw1OX}Yx``0D)?~?uNlKOW^{kvrUx@7;lWdGV3 z+|YkqvVZM7ZsRR?1uj1lKyGucSHZN^Shz{ zxTJr&q<^}kf4Zc%yQF`*q|dvgf4Zc9x}^WRr2o65|2yh9Xcd?Af7yd>aY_GoN&nZF zpl5`Go)HduhWLwcHpw2e4e=M@oRU509O0mIh`$Ku7x5S2{38A$oL}T${OmLOLO8$3 zzxdf_^o4MK5q}ZRFY+&b_8EN*e)buC4Sx0+eL0+8@e)bvXBK+(#&PDjyXPoO*{VWf!_}OQi z>s9@%1h4qnXPk@hv(Gr!tNK|*=Q{lCGtPDR*=Ohy_}OQi>s9@IeO%{Ik!J`a%DQpM93pKl)AlLBENg zeU|KB^qca}K1=p5`c3%{`c3@ovt<9GKgExqWdEX{RX^k@*}v###ZR7+{fqt-Kl?1{ zKj>%i2mP%0*=I@rL_aHj@|5&X^t0k8Pf7nl|HuA`{*V0={U7_MPx?RlKlV@VQ)2%| z|HuA`{*V2W`M;e-N+(7wS38H9Phy2An%p_%|&dE54XMN_gYb zTl%&q4-nq(`I_g4wZq0|V8(I{7!J6=aL3xfr`c5x*loNpX#Ej2mzKoA~fX9bEA_HlpN2mbOh-VGXVqxr(am`?-NcReQ|A!!D1`Y z*dix9%qzrS{LFuqkFi-iKE`8nkzcsMaLyZXr{&?Q=+`BfImR*e{okKC!EoBOvJ*q( z40dsb7>u)FzAl-It_gEY{W@X}Igvf(3G>yMFfZ|hoQNO0veF||96^nm)oM#C9-eO>i2Gs>n^YGHMhAx zZ*ZmX_AB1(Zr=9S!guw#(SBd0!qk=3m(|bDJ>g$C$8*Y`LsIYHh5+m|LJ1`Wq*3_1N;M5RPRSd zt$0@I*ClqBjCTo-OZZ*lH%sENef0A_wYg->(dJ^`GwCaAb8*Ze%pH52qkS)>VeaI` z#eHY|!ZzQ`{0iHAGmA&q=1ZKyHeccww)rwIVVkdUHpE6AqMiK2@#IaIye0fT@mnPE zXurpGOy=m5xoh43Rdv;P`_37@S`HuS_ssH)8ou|`@&1j@yJghy{p(Ei=k)BEQNx?I zJ>PG!Tknh-e&>@5{r125y{>)fp)>vQO%KSZ=NtQ6>bo9MFP=MQjqs0jyH7lm=8yBk zEr|w8;R#n&+hHF=+w#)^Y=T9 z_Sby5nRpI(ZGXSVb*&vS_t|Eg->BWT;vD*NKY#PK>pS9Xa_j{E-LM_S`Tes4edk}) z#Ch;p+xp9zW#a6&&+&f08}|_B2m5yQ&m2$_=hB-`@r_&b7U%lyyZaZ$?JUmP&1d*^ zrXM8Erfco#n;deGI3M4*g>SLoP;vg|tG#{WzaA;h(|_CAfBN8&;v9QjZ*O_gc*~Q& zci{2jUw*@OzVCzq;=ilS{@!w=Yb|Gf_h(O+ubW=);9Hf)>)Mv>-YhJ4y4G^(Z=5z* zeml3`%icyYt{7&0wWWV_)CgVsmv&zkmQ!78Irdfu;mhkRMR6u&)bf_TOcS>9W%h~H|bur&~m zt%;vEZnCaD`pm}O>PDPaN5$UHOs#Tz%SzsANIX_kh1Im;u^KO|hIFmfRAKckzgF*s z)wg_Ey%$zP;<1`4tk%VEwO?4RS99F0cVWF=ob)8Cb#Yql7uNU1iQW3XIKfuy;XC7$DMS}(KnK>XNyeqY7bbH+xQoekp0p50W%dDd~8Wp*}*6Z`A)syII$ zzI8V8-Lu8H)#A&u8Ivv&=d?xJWwVElR&0m1}|!yUQcSnCHsPXt~lBENo}}fU$Ez^wX+^@u-`-Z8FpVsm(+|) z_6WT|bD=kEbXjlZ?Wk?HcF7)bFAeCc*si;92YQ6&MbAj~h-+t!~{U^)Uwqy2m@Y3t>0~h@b?xcS@ zxae5l!l(^l0I*GrJ-lKq|dvg&zp8>=$|g>^DgQ0E;)Bx z(&t@r2D#)6a!H?e$$8|G^GG@&oSQB=k7N(pOgLyWmz+nk2c0GybQ*CM;e3=mXg1<3 z!dXe2MK~)pCg?ZfEW)`-oJBY{$)`B!m-LQsZjw)N(iiD{aMBCu9pT(0pW>wd(c|Ex z=W!l{bCZ0Elb**J5YA23-NVV=qQ}8W&!fMGbJN+mDIPmFsR0i^d&tgB@z}XZ4ft?w zIy*PTY3C;E?%`xl*tscAJ2#!3o8q){)7iNxPCGZ9otxscbJN+mDNZ{#ot>NFv~$zh zxhYONH=UiE;x?}Nq-Qhotw_iO>x?}DLqlu#`5$B@!PrS?A#Q; zotx4YRh_I%PmnJ=H=XrB`Lc5}LvvL1vl=}?e(l_J)(_>^&dm({QPolldV*rGbCZ6k zYwg_3&>~fhwQ}euVq>3KuTVU8ZqggYW9MduMyYDAwL@1CC;QKOqj>Dxq*lbwUPQZ8 zb+|sgQPCjum#=f*3SmpMXm8c={ut(8?#KRs%d*PQoiY~-2dlX$r9@wL3FMP2_ z(TMP~N70CyqiII&k>KPW4UGsVdzAYnII(lT1Sc4c2q$}#dnY)t+qo$oJ2wmNqu|GG z=cah<+$^}Kf*-q`o8q){v*4ZzPV9DWiqp=`!p==`+PPWSxhYONHw!yA#cAheVdthe z?c6Nv+!Uvsn}wa5;#_W(ZiStj;V`-b{NQ^^;aD%lG@sZXEO26|H0q9>F3L{ljSG*z-Md{Up@&L_oY=ao-t z25qSr(3VMkdONq|%g!;hrRI*dv@=ZevNO#m^@+Ar3}{O`&%|lxn@{$Fx3f(=cGh{~ zAXmg?XPd6Iv(Dp>{NNuS)Dk}JY*P;Htn=_vOZb6{`hh#?pB^si2kxYQa^E3Nats%> z1b5Ouxz`XU`Ahmd_Zs3PPf4HW{wVf&?mNUuZjwIF{ZZ`mJ~@xLKZ<>xd$)KVaqkw- zBkqr4pXWXXT{00 zj=y=%Lk$0a&l8gPeG;=z<^ukkXVJ;C6vgmQe0D^h|I26HG5;2GocrHAH%_koCq9Gv z`B@qKKiB!s&%k-!MecYm#PcpN&x?581?D*t&%3}pU*dTenCDJB?*j8Y3Vtwuz~SA2 z=9oO|*0c2ZoWB}fJ;wvbwE)NGc;NUP4;-K4f#Y*LaD0vjrmm70gyVDXK68Q%%-UbB*tDlANpmg#0Tu zuI11F%-nyjhkw@EC395IB=-NiTK##SCi_><&*A)U?mP7^c>cTnoz9h97Wig^zrq_}+fF78{>cJQE780mA_o z7;b!k`IFeYCF8S%CrkLV#BY|wlO=IxN&Kp9{FqN?cK!RW=F{2u47>S+N7#JAU*RL4 zz^^biKC5^pWLyJ=11>P!_yF@KvDYW#i-d=~MSk)r%v_UriX_e=iC_7P@1Bx(ZM>_> zurGU8`0x3yFno7RYs7cT_}&-m6}~$r%y-cEo*4G<-7&jQUG|+*z7t0t*k62C4jjJg zCmg=(Cmg=(CrmE+E?&$h-_Zky@A?Uof4)zMJ$~2k@r%8^Bd*@XgL$9K{sPDS1&;6H z!MsoAy)~Hk$-K`7^FEpP;$Yq<^Zpym`()n5gPB)i*Sq*IUhm?;y!%f0^s>q;p9#O-#bd{o#6$jLoO&0}7`WrS!uiz=J7)|16U^B{Uj=iv&~JsS^Gn!l>d)9Y zTj<+h&*<}kN9PC_pNU_cJJ=bU#L4*;<8N56aDLS@9-qVn z#wW2x9_AoionONEWX{;h0l5It+ z7{Au*!sfI1Ju!d6hkIn;u6-}`AFls^@bzt``SRDRJM6UTP_S*GvFVMTd^&5J3(O%WP=^YQ( zyJ4@4ll|=Zce^hZO%mSo>^t4?#Z!ehe`u~7-u`^y`?tNtHEMDZdo80**lS5|VQG;Y74^mMUV{0(PJTZX%UUzn{9Y$NV1BQY-}wYHmTSOp zzy*f8@B3S3^Q~4l_+q$k*>wAiT3!6z7{BkCT{3F*5qs9&eZ0%4)dRnr?EkdM&Kb4Z zaorhy%CMVst=sAhKYZogGwOD`CFlEg@jUd<6u)%ha*lZRK5vkJ@U+H`cv@U{s$bfFWk)>g zeQ}om@w8PP@w~9laR1;p?HqI2^okz-h+1<;JSWZ>TmL$#PeAHqx^<_b`sBmueb2~_3a{_z1};9d-gp~JPThN zQ+zvXoOpIR>XiDYXHODO-)nzWzv10e#dBKAVfClIcb<5z>ovN*<5wfZbL!KJx;^&z zh2nYRuVd@4S+U}&E&oZkOPf|aC)K{}mN&0>_M7uvw{x!=Jh?yYSdk#k0Z1?`HYw z6Lsx++x{{8&FsPA9CF#m*`A$_(6txswVYdJiz&MH{Em-gb2l9>{`da!d3N;%$BJjz zD~;WNzl;{oRUN;}4&UHp@qDqUiTic;eZ{k6NK4nc{~5Y=_~KRFIYY*YbNW_4Wv|Zb zE1ty**LADiI8;2t+ppnv*yl*`YUJ^PBM^U`hHawqQ~9{#?6;6b|f;YIfU+IjX=aUQ+J z7H;I*PCWd*@Y#Oid8lVM_p2*+77u?D2m6<}n!mfdc=-E;U5^sa8Y|X0;$ROF*TFCJ z6c2wB2mOJ#$O}B=i8$yL#MNkV?`n?rH+g}FJP`*ygt*8HJmiUWf`@e@7x0i9;-I$> z7wZHM>qcJSAy2FmJgghF0uQxAF1VK5ux4INR_i27hW^+FxP zNnNvMaI%KfF+9{YbpsD|L`}m(jla@-hOS-9e(#K0;aX~k`i7r+XaB&%eq#S{E&GX@ zhLaj+|1h5Y)U?a?;@so5;f|VylN#Uo{I25p;|un^OWR9a%ih{=tC~0`JUzj&e;Chx z8hp$y;;j8?vU?%xq46JlHr;V1GGEhF?u+jGX#6i8KVNp@G<_vZoTjgYiOuwtFn z5oZApal(mT(^|w?z(brCTLBNTSv&=)Z3;$e^2z7P-l!s=f<)W2OX9`>Tuxp=5^yIwr(Kf7K$>^Zw$JnS>OUOen4 zn~!+dLw3D**f%yG@vv`fKH_1o*nGspp0N3d$L2?Ui${I?<`Lqd-Yvi434L2U)VSqW zJk+w~S3K0Lt+#lnQ_HV-s8d^S@ldC>-r}J)ZN0@qJ=%JUhk8WQvtHa^+j@(KdPLu| zUf9w1tQQ!4&w2@)zGuC_NjwEwpY_6?#8V{k6iGZq5>Jujr%2){lKd1_e=$ErlAj{U zPm!#bPx4bF>*bU6^2vJnWW9V+Ki=vuu9r{h$0zmUllt*V{rIGweNsO@sb`T zC-v-;{pFK-_R0S8$^P=m{_?|r-d{f1?>^aIKH2X++3!Bt?>^b@KIuO`+3!B-KR)R{ zKIuQ+>M!;mpY$C6uYLwj-{hGOe{+8dPM)7Ed;ViN`FDN(6W5Ei<4;(-W$&K;FWx*& z8RN8hl`(#sSDDPKjPqrD%mX|zKk&!A;Wy@!cw(MyUOwjE=H(mKg)=9t7yDxFYUkxU zO@66(c-P#Y+j_e2DtFiW3B4u?Z*c!o|K8f8gnP7TTds80DZ&RGl9flTeTZ+EsY#YrB-~1{@~*$lB|dzdiOe;YIzv@jJafO8BGVF2DSF6NMX}H_&gi z`8478=PfFl?LR}9T=ibi`8BN$ z5w=|A=N{c%*m9MBc6SG1%T?ZG@=C&%t9{ z%ctckKmNGWge_NY=Id1rSgzdB=T)^~xpHGRpQbUEtL)_cX9%Zt74n8X3waX`c@qwK z6ApP34tWy}c@qwK6ApP34tZm~S;(7k$eVD;8#R_$jgdDGwi+XE!XaIP_KF&{u`6KhRf&LthmR zeU(0$g}y2r`sy9gZhgst8E^ecIP}#VJN(w)ghO8y4t-TP^i|=|S1Y?s()wz&(^uno z`l@i~tHPnL3WvTb9Qvwo=&On|^i|=|SL3|st3J$&zA7C0Y8mE5Ulk60RXFrj;m}uw zLtm}zHm|r|={knKsx=LLRXFrj;m}uwLthmReN{O0RpHQAg+pIet%klT9Qvwo=&SS! zYM#F8Le0}xg+pHz4t+HbHBVm^4t-TP^i|=|SA|1g6%Kt>IP_KF&{u`YRjYM3C_Art zm;W*UbGGhX>k04p(LwI^nQIBRTK8(#c(o?NYk&2K>p1sQ&v^UW*?$Y$=edm&w(D}c zUfB3@<1H9(e)R7dfP*~)hw%;^c!UGLaPTV};>j5w;uH??3x|0{dx5_&UjD$ui$5^) zz#o|T;SbEb@dqX!_ydzC{DH}z{d=Ar61(Ob#(V66M>y~c2fxB0o|5t8kL$tY4}aiv zy};;uj9{iuMA3VZ8i- zi5Guh=7B#j^TQvQdE*aEKJW)7Pxu3qKh`d>YrbK;#~yfu1HW+aD;(k}8BhMW9!&o5 z2Ts>3!S?&o4QuB@P8hG>f5taB$4)BdVtc7q`Bj#c}4Qr==M>Whnj(3a+ zJi>urIQSJNmyBb4vUV|k*^{-y9@mcX zXk+3DcFi}8_hDY}2q$Z&{PEw63GtL+Uc@P!texJK;EyrPG4xCqdJcQjgmsXY83S^g7u?4-^i)ksjibp6P;}p5wxJ2M#>KfnPZI6%O&_j8A%Ij9>OJFX7O0 z;`rDzEuMy+sd?ZJ&d}3@lb%VOv1by0?3v60q#DzaF@!~J=m-quSKm382H~zrn1Ak!hgg-F(>)Wk!hs5ra@xp;eIPjN@A%FaL z#iMwHL!83o4}XkF*9-jqi-(uze*cK<@3cI;T(q128~n(5>$>LkhsZuXyUfkLx3};+ zEnjtg2k#{O@cPa3^03W??eE+SOF!WHZ>6iCj<~|$TNBI30Uv+iu zx(jc7Me}^4&o&pfzjOOvFqZ*!Xhe6}EcOdNC&0T{2!c@CXO~oH4<# zaEM1Z#3>x&7Y_4^c8@=Jh>Q5Z#EZYcU*ZqU{O|{6-uMHP5B!126aK*L1J*0C`((Uu z;1Le|C1c1R|6TDY9^nwDF!{qDW0E>7lKL!?x-F7=E|NMgsK-!;MY1o7u)nCiBH2gA z)3CpyoqCJog#(Xp;HR#lU*QmsaEMbl#4jA?)qv^O)^mzv9gC#L7D?|dlAc^7y}F>M zhF)4Ey}d|!evzC7#?x>{L_0k*ju#F*!hxUO82t)|c!Wco!XbWP=0)%3+N8%aFU|?(YjS2A! zhj}$%_Po`t)-m)?>X!Z)>w*3$9Qvnl(#NP<`lswk-=hxcpQ^pkKZWU^rbVw0^&I(Cq1V~dQp+|s3PfI1wAJ8mLlnOMd+FIlOpMj z#?#O{67^lXBo+-?{;&cA+{IIIeW$$H5 z_IP-HC>)+2s&D*nzL$ype_79$KL5Ax`Se`tpJ?M{n&0w}oGJg7nm?`=y)odwKciVk zopJv!Y0LkYv`0AC=-bQQi`jcP^6>BeUMy(-EV&opxzMubUAA_~JxKQN^1O@Q$n(s2 zu7Tq{EI8iVg2TPG#>abM?C~BM9PYLC>@?hK3!5K38(~bayJWm@;1Le|dL|tF3Ws=v zW8a1+#4mg3`NE+e#__txVSK#z0f&1rjfv+P_IM8k4)LF~P5Jh(|cwiwVbm&iHtiMQp#%Q}W&x`$gx@C?|JntubFVnqKa3Z}tBN8ur^M z#n^J_x|a#J+i^ts$%oeq-?!UYegl{lni4_*d2NneSbMNsl?mb2^ zJaoice)h}(@>O?Oy}$C>5#ro>+{^a=B|lW0Uo@TPr|*BZc-nrxyFYgSX^LUTHJ|cZ zcHLK;&EL7rpYrA@;_3L#u72`sQxwBTYyZ|?F!>nqJaKh*-)-6?`MvkKnf`NS5NKeXJ0W|z8<}BTYuUi=ZN$1n>Y6hW}GITB|Y2w$?G4hYtMP^o$QD| zPFFl8$X*5#Z*ivN-}zjvPw9IM!DjxNse`GH@%ZH^cv{=3$=&7C!Hl;X6xyEykD&n|J> zv=|}&->>^Sx5|k_74t>sHqRSBF<95m^PjpuKQmPPTlBlmUH9&3ivP<-tL3ilEM4o} zhwiQo&JzE*jjnQ2&pA%<5Bu#Z`L~;%rfWAI{*HUA&B@}Q;4X2$Jn3-7KY94ddH-8Z z(6xT{UtF`s$B2K_6)WT)FCL)rgWumVe|yrQil^0T&$+Lf_Y;4+9hbUZoA%TA(^uFb z-(k1Diszjd9(DC2_Y?npyDf1`rtGir5B#uQe)Ek7D4rE3_R06J?IO-SfA_vS@zA|B z{=pBo$`?P{Tk$OJ*DK#H>n_frpKO-D{@h-Q=fU^)&L^%=C!X6j-#9<}(_Iw9$)6pY z*MHMdoImZcN8arAuHyOXp*Hy?eVk%=XzIYcdEF-BeEQPv`PIjC66Z%(lxzi-^Z{K)8?hc-(7;L}h^b}%y zZNZ4VcJMgyU%crd`P|XBDhAuTIsJv$-d=TZKI?{&;(u-UjQsd5-=0qlws&*-4zcZd z(nPZ0lOH%`fKTkX~P#9(_jr%#ce zbw*Fm$G^Rzga6fG6Z0pRducu~*xt?QU*xBC(`os_k&PYvFJC@3KmEz4=M%%Dzn`4n z)uWMv^Dmu8*UL{yKxR?Qf6I-`%;GkKcD@PRLijXPo$NIdgbE;nhzv`0bp@?Yt5H*lA<) zIrBz4_&>VnjQr{Gi!%7_Y{~765&vV;M&>(wGt9x?eU(A^0n=Z};J33Sw=+ik4?i`H~e@%E`~bEl;)uI^Mx==S*(rjW}n$GbDdyX5*avy!z_V z`DSyEbnx3bliPVC&LRG+eD^_(a&l$oOm63mc(Ub>&zrUCApZ3`oSL_NWvTqynUmYu zBcAmxJvLwcsP^K2de1@m2~)q8-?w`mn%}Z@7hSuDKRR!Jb35^8hxE?}tg~2tpIW7F z{_&nW=-Tb3AD;JW+$JYiuU~j@e&Rig6oWhEfV@rj?R9Od?GMgJOj#!@0ok$1Ge5=*UrCt&wRTZn&sr` z_}_QQ?^}AHV({fI_WRo#>)N@i?38zyv{Fv4cAwcf|Kx=I6ocuL-1LdAeeG8p83n1;zs!-#Xai#N$l7s;>b6KDEFoTi;} z(@x?vEtH!Ul3&v~&UB7AO@rm8!Nh5rDmP6fzowU*=_T=-7RpTviJ#h}MyVOoKhE@z z_)Y)hrhmjwZBnDujOia|`bYexe{$15;-@yLQEJBYk2C!verl5%WgSib*#BStP;pX^ z)TQ=Or7IMJ=^tnMN1W6nb;;TVjiDH*N9vOG3K~OxsX=OyH3}L-euI{fuW(N%UqL^J zAG_V(i9cut@ng4pJ@K0^DohvY+MpTai!pW&C|{z7oIbD{uNr zF$7JhYfWDjrmw_r`pTQWQVc;W>RQuRh3PBto4)dAsZ~997rmwu|E5*PW&RI?!n!fU;uf%Wq%A3AY z44mPd<&)0O4C=0$MjWc z`bwOpuS(NbipTU-Y5Gb$rmsrVSBk;(RcZQ4oTjfz(^uj#eN~#iQVgcAO4C>3G<{W? zz7nVDtJ3t9VlaJGn!Xah>8sN8mH5%TXkXUF^i^s4O8lm;O4C>3NAse6Sr^k+rRgj2 zo4zVdUx^>hi}qz*Okb6zuf&heMeni}rmsrVS2`#E<4h`?4;kuS(NbIx9_I zm8P%6kLE@DvM#2tO4C<5E77^=UDm?%RcZQ4{HCu;(^opb(7EVc*245vY5Ge1rmsrV zS31AA@8SN3Jea;JO<#%M^i^s4N`AQqqEC?r(^sYGEAgAYDotN02JVOGS>(a=RcZQ4 z{HCu;(^ratdn5W6IWc`zn!Xah>8sN8Raau*-iW?NPE22wrmw_r`l>X2)s+~yH=@Up z6Vq3v=_~P@zA8;$btMMwjp%pe$MjWc`pUy^`l>X2)s+~yH=^H>AJbQ*=_?Pv>8sN8 zRaas#eN~#i@^G5IDotN?#jokB()5)$O<$F!uL?L#UzMh>y5iULRcZQ4oTjfz(^mzY zrmsrVS6%UI`l>X2C4SRarRl2ze(vMBpC@M1SEcDI55MWF()3jUKlkq3!xOXVtJ3t9 zhu`#7Y5J;wpL=)i;fde$RcZRl!_U1t_waCJ%RN2!_VAd#DotOB z-}F^!`bvIHUzMh>bgk*D()5-1O<$F!ujJSCRcZQ4*P6a6O<$GF%k))g`bsgFzA8;$ z=~~lQrRl4Zd6~W{OweWhznUzMh>O6F+# zsx*D27))Q4rmu9Z>8sN8RmmJpUzMh>6oYB1(lnJgIR}?LS8sT}o%6i<-~GAzvfr`4 z>p$vu?8EmX_|D6+?;_dveZu!m_->0&zR#lXm+<`=?8*08Jo)?I{w@-IGJek`S;zQ& zAASENd=E%Cd_O3Dzh>F@l77(lt^TFoOA6^%@6Ug2Eh zd!5U^Z)^EazB?AbC#zaYzB~56`hDAF`%C-xKW2Z$^`eJ-(sEFF=yvn8@1D5-jPkmf zvxR^6%Yg5Wsw>nL@W&O1BhWZ}D?GBt# z{&iSe;YBabDBm5sqHz5Gli+vR|JUWEV%h)K<)8omb@^A-^IsP{<2RposP@b6u3Vu! z>!+T=8(;Ii@3Z2r+Ee!qdBh*qa$n(_4ro#C{p``&J1dRZsyz6iUc&uWXkLE1Q9tdk zo4(tze1DBY%MWbteEweNa^@8Wm$Ph7bv)-4|MdL>v>!({Z(442<^jS}-fC6OIdG8n z;5+lTE7yKvf8iJZ@EgCV)uHmc+6iy_GnP9^{10B(x*R>~BynE3`i=hib^{gjDhGVv zci-wv#WQZ-^~$B4PgM+m{q$CU+(jqL*V-$7>JM%;RQ%s>cZdJW7K6ok?eX3G%f}6n zukH6=;@6mduJ~`gVZMLz#&g9v_4A$m)vuo{UzfN2+TYV{l=vUs@E*VXd!xlU^ZUL0 zrN!CuHTBSzmzN6%K+9wN(uO^=^&JX7=^tazTUYtX2 zJlHR;jg#Ls8$DJ$HFcOck9xbG&wn*hzD6DLOwntQVK# z6;2x9zaBhQoC6xYR$MZ5vaWsX$2W^jSD2>pV=j89XnXZ^jTv0DcKtpasF=GgZ0Ei@ z>r}-yr+-IR^dG7iej4}-S8P98@!vk{Qg{2f!!&;3b=$eUHXN^*7him}8$0tDUEA}E z9o!oICdqHFHaEEM+n*|)`*-Z-wtI4lVz_qIo83DPpDoT+Z+_A>`crRlwmi_enFFUO zwl-bnxRdrBDgFUlz2sgz@{npRhTP#sEF2^LTKhNMz@v^9|1oa4eDBkC7SC;S?{e?0 zH(tKR?eV_re8CCwb#D8W@`n$$-(j%x;@1z&cQ;-$LB84@@u_?D_S5C-7r$RMf3JQ& zan^VK$}PCyZ25Y3t5*3J4{s;_Qx>d|Ki2n9app6>bK@Efm#-IAZIgfZbvN<<(4ken z!w>z%+2Y(E-3jlEkgt!%w9ikub!YJ({y^(|^D~bX|LFrZ%g?y2hd5t-aLatZ)!WF| zbEDVK54hw6@!KBE;~s21r&E4#ZDaY`Vy_MIPP?5fe%n)d+*5CF=<@rQ-$K4@Z{~4t zzW0Z^{Johgiof@wo%35a-Bx~WFXwSDe>Z%OeA^$XS% zXPX~;o!@c!ZSuR;y@T?>?`|y4$4@^s|7C3z zaURs>r2OMY=E?7__neuxtZ!EF9CTE^;?_rqKfm#;{CE3%kCym+!r;8!fz8Ep&7CLa zod*pP|KV#7&#zzcK9AphXAI0A?X;1uy>aNT^6i_RA^s278=b#&=N~=V}JaKG3d*??y{qxB0hvaYldK+E)`6^@cPdbkl|J0Ah<=@PB%+qhX zEFG2K^riiq#1`8F-6rG*^&Kbvtv?u-zjm(E_{A*;<@WzzZqFLEzHU<9Wc~#4-_T)F zK6lmb8gCj(V_2gtwx5!Z++~vZAG~BrKK9&QHQuz9#;```Z8IOLp?`)9iEdi}zf?!Fkg){qyMqj(1#Zx=drp z!(U$?oqxGf69@m?uTRLI+2||>kLfjyArJnU@%b&AH*@%U@s6|dt#%qA&KFxu&O2SO zy2F>9ExDaB;@@-nx%s*C$BJ{ONmKKaI<#>3va=<(Ge-P}TstP8Q$JChPi{CpKk%uw z9KP&q$?c30|F54IpU+%zs`%|}$?c30=eei%%)jXOx_m9|G%5df>~!(l*^=8CBhELU zJRo0dmc3)LxjeaWa(+wyeCs)?Pa(Wrp-oN(&`K;mV=H!2$y9eiYow{;PuB?aU^fInp?cPK4?wht1 z{~eQu=6n9oBqvwa&vN=2*Y3D_|9sZcjl^#~ET@+dPw11)Ij`l{kFJ>yKzh|~I6PG2LQ&|?*k>7U&6k2phLRXnCu za?>i}3B6P?m@aari^OUACpY~gp3qkngXt@0`bwOpopRGo;tYLNF_8f9Hf|2We>;y3-1oBk0$wMmV#E~bB+=^yc%{>e@Mh@aY|Mp+lrKhE@z_^C~5 zl(jJZ<4pg^m+2p8`bYfKCN;{snEr95f8@*bk2C!verl5%WnE1FIMYA!W%?&G{Uc85 zlzL@dO#e93Kk{q(Co}ycPU@6;WnE1FIMYA!Yx*ZM{Uc89x#(Zy#I%qzEhN9Dg)-AZ z;$#f{i=3D)a;A%_xh!}oGhHN3#?ZgWiD@Kf8cBXlBW0$M#K{~vrmwu|EAgAY@}{rEZ~Drcz7oIbD{uNr{HCwG=_~P@zVfE8#A*7E)RhqsMkLfFK`bxe`UwPA4@@4v}G<_u= z(^uZ~m3*1L@}{rk%k))g`bwOpue|9i`LaGx(wkUo(^sYGD{-2>@}{rk%lbe`Z(^-Y zUzMh>#A*7jNddiM2L;RhqsMzwP~!e#H8kzA8;$$(QM?()5-1!#$2TO<$F! zujI@0RcZQ4{NbKOoTjfz(^v8p?tR2#`l>X2C4SRarRgjA4fjgoF@058sN8 zmCg~DotO>uj#AO^p!YGUzMh>#A*7fG<_w%rmsrV zSK>5%RhqsMr|GNG^p*UYzA8;$RXhhBRhqsMzv-*e^p(yp(^sYGEAg1VDotOB-}F^! z`by`f>8sN8m98~?RhqsMzv-*e^p(y{(^sYGD_v{)sx*Bie$!W_=_{R~rmsrVSGv~p zRcZQ4{HCu;(^on}O<$F!uXL^HtJ3t9_)TAxrmr;K`crx1uXpP}-I~5CO<#%M^i^s4 zO5=G(wdBVGI#9Q!uS(Nb;x~O&n!eI_o?S79x;1@On!eH)o?~IBZcSg6rmqTo@l0!% z{>OBn7n!~)O8sN8 zRmogTUzMh>O8jz1$kT`l>X2C4TM^>1D(d`l{kFeN~#i5Y|M+de`28+?3@@#5Ia+;;zEk zfisGZojMEi|N1!Qn0CUC-MgaahikF%8JMwL1BL@GFx<=$j8C&?(Qe~~8P9jHvBP8h z4h+Bj2;cvEc(dxlHoU z+R08X)AhQsI846r-|yW0-8Cm2Iv>2&z`nBgoY}hA@0?!3cm49xV#MAx;Twxrijn(m zCfu!VHE%z{X7l!$zN>6wy}}i;$5wUl zM*Vui&t6b;yK#Ig;lqb_%?|&rned>8CuVQ&Y+U@&A8P53emsdeR%dfgo zKSy`@L;Y(@FH-&V$sVg8yTvWCU%j+ZG3(30vLD^0d-3tCb!DG2XPx4gOJ7xul_$0? z#%{5t#$3I0OmX&tUi0BR`_uJ{ylcJ2Oy2x_yY`B1)aR5rmleHE99GYmfjw6*-a2xW z#(a4019t6`^BHsYr@t=RE_qgCI@R8-e|yNg-Kgi@6W_LLzprP^z@Fz72VC8>fM?&& zFRp*N`TF&Yx#PX}?b`hd#&oJ3TP!(fJ&n1&>67z^ou3zsS^KjW?Apm1v+w6E(=lDw z{`xl>bK~q=&3>iE+}^ZTed4Rz(i5N5m~&1%G9A+`iMiX!WB#f!yHC8*u5Iv@C3DY` zF?MZ3%vqAdEb(R6Hq1Rs)*?${wrd-5m?i6&C3ClH8`dIAYM@(^L%X(NO|ztCx+QC2 z*EZBfmaLXhiNeyI4&Dj0LvimRYvHnx;zfv8T=)+~YJ?QG>KH}d_x3hNKqj5%X zpAs?mDPZm`xUT_oU&DP0m^pEu0_GltA22pP12dLuz~TNY-b?CC#EwtyCBXRPJ|&Ll z-UAE|_atEWxlaM(llv4fKDkc;G(H{k zU**C4HjGa&@i*iuV)!BsbBWg$d=_Fboz`%z@ib`E290O)5>Cc9 zv3vEWoN;*L5;pFJIL#+^+b2&s?D&Y|@d1VhA7J?T0b}DcFk|rnh664z-1q>8c}07c zjL#At`CvSAO8m+Pb{i`nU~-ehFCW;+WinsJ$2`E}A`d>mq zc8NVp#%BqSd@!ClC4S`tyN#6(Fu6(Mmk;dZGMO*qV;)-E8$K$YHu3?6 z!{V16?sUDt%#S~e;cwz1J}^0f6HKn~1!jKu1Cv)`1CtN@fyop8z~qm=`9ogu0mhCG zFyrw7h6f*D`1t{2<1;X0xdseJ^Z_?Mu=6LeYwfTRW5PoYBfr*;F=iv@vfEhl7~|C1 zF~+zZfAfc2Ci7L^v6IUrKUyd3@bd#Em-qlPmTSPo8GXQ=KC?=mWi5NgXu0C~-@n^4 z#%24fs^|Zd{gtj4nEuH=OfmZrJAHc z`@rzf6Tz`hf@7Zq$36*;eG&|Js!tN#vP@3~y_e|Qe+xay{RKLcdl2?pg*$WKAuSs2 zO(M>cG2BnZYwe!vAKyh=bV{q2v}tX9Q}f$UvTsbj(#;h@w@KL>(oZAbgBGC%p8BS z%R05UpSeWwKlU*R__|9^O_!mQDZmX|fG zQN%H3<``oJ$C$w}W^jxd9AgH@n87h-aEw{@5HmQ&4305_)0p3Uf8&PrjhH+iaC(Q@ zy=PZ7(Cy0(wWE)#@cL(LQoD4Y3g7a*% zlT#}E+ch_>wdz^nSzB&e8`z}6_iwXlZRi6tmFGnpY+Bo3bcM%$)v?y9dxd8ehF7TY z>nC=s-Tl~al;;%3n3-dY860B<$C$w}W^jxd9AgH@n87h-aEuuoV+O~VH9mV+R1xYdH(B~O=~+G zUg5=;HLdkMrou0^U8Q!-(G}k4`c-P}4y{r<)^>V z`kvIcS*`Pe3SV+fv)U%(D?Ix7X0=uJtnkxcHmi+TvBI;LTdme<;niB}6vsHpLyQv~ z;{?Yz!7)y7j1wH=1jjhRF-~xd6CC3N|9zZuw!63?PB8iW^owS-7vH-`cf)poqD z!adG!R{QM83Llp@t2OIT;ib>5T08jD3pKve;j7k;d$7Vcy|hYg)Nd<%T+dZ%7hPQ8 zyX%|QI?bqXlg*ko*dM&INyB*77an3xaf}Unj13%P1IO6FF*b0F4IE?B_z)X7#s-eD zfz#M#tg^W7rWsYwjF`NAz1}BvSI)modFZ&$$926vs_?)YKC0`q+2yi7yxB)}Lr$o0 zt5-j)TkrQ3zU=-F>puJTXZs_&T+uN8gvk|#XU=04hX0b4uhba)?&T^>JlQcC#IZyFNjJ?N#CbgdyoTuDg)V67DtqUsL{?w+m4f<7h@oi0OXKhsB zfiE|$o&VMhjX&YjrnM&5R`}%4o7P4hQQ;$BZ(6&tO@;m4O>6C6ov!hthc~TFzqZ2L zY}2%M?1|GAPl{ta7?NrK&$fOn&B` z@x8JSX_2vqXT%-CZ*) zd{Vpj>lTfw@b``1t7~>jg%`Z}Zry_8Dm-<;qPi`EJ-gwZy7r?h`{BQ~d|p%GA8vW8 zuF<2xZuy^QG2r(BTbE0^jS=o)>-Frg3g2Ywc+$cOv%cA?V-<6XW6aDk#te=zgJaC# z7&AD=4305_W6a$>?pEBxXP-_%{uvBIk^ z|83obZz_F0@s@Avo>^God$;|r?wtu0-gx?VbqDQHVYlGBy0;otc>cog>JD5`X}@!> z{H|{7ITgNikMHX0x>dNxBj48T{6nSjKG@{jx^4bg;g|b=Q#bmO3iloPb=~k&DxII= zI2Yy~=K_v%0mr$3<6OXTF5oy9aGVP`&IKIj0*-S5$GL#xT)=TI;B+q3Nz~yHvo5S% zynkm+)J(j8rJP=4=Ij*i8J~IN5A0c7aaY9 zqhE0JtMQ57bYDcweB<01A2IecwurIE8fJXN*wcE57<=p$jE}hAdDqnrd-n0VKff@y z*7)HHzx(vu+80YJyw&}4Ya_P5USm4kGPl<9s0vS*GPl-qa)o;zJ-7D3O%<;1WY^wT z;jNdOTf60{3fCT)Q@iH*3SV}9g)e#T<+{JejK{wC;5p&}FSpSg@q>T$@of18zrJ9$ z;sO8e(%Fg=+;s44#SdQYh}oJKxJU2VHRcQ6fA86~c?VS(`ybm?nDN<1*J=zrH{4TU z_)os1!ub8uSrsOp2m4i+I9KacVd8JSSB05lw3CN8p8P}}@)r5YXY@;+V?5+P#>u+G z_*t(wum6v|_kg~uDEIzJf}{Zn5SkRF2Lgm9B)>D~fPi!qq>l0&V`U{D%|61=W{BODM*i{nKpK%)|rk|T_o0$GLcTCK4!NhS+ z=6c%k19o8igMApkabFmJ(jOQ<(@z-x(|?#a@?0=+FmdGGFmdF5FmdD_YUduho_oO9;T|yd`G1%;{tf0@?g3+id%)P{ z9x(S*JAKjh^ig)`yX^B!x-ZYF{@?@k6W^%+iX-<@9AVn!2dIC!hZ)JR=` zKZ%R_PrUS8iX+dfIKqk}tT@7oBdj>WiX*Hz!gIz^@m0KtyW#~aUa;Z?D_*eT1uI^# z;sq;SYFFJUUbHJ-u;K+PUa;Z?D_*eT1uI^#;sq;Su;K+PUa;Z?D_*eT1uI@K+DmoE zoLzN?R#V-f;Z%2MJJlVUPj!bDRNbKw6&JLl>JBZUx|@?#cW4*Y9dmir9dmir9U4e= zhc;5(p_x>7Xerel8cX?!_EO%`u6*Wtw#SvB<;W^`|_$prH zlHvs`Ua;Z?D_*eT1uI^#;sq;SYFFJUUbHJ-u;K+PUa;Z?D_*eT1uI^#;sq;Su;K+P zUa;Z?D_*eT1uI@~j~ym<>TdpRCU)v>hi^{o)ZNxAPwdp)HN7Tw>TcA`37xuoVfutl z-R*eHgihVVQ+ETOxu8>b2R?W~CqIw6=Yme&(yn~wdgVEGl>gXQU2tF33;j_Y(NEPE{a4-b zjB3XZx*q??4t|q;{HgomXY~jFtDnS0bw|8ZcZwr5qBz2eBdj>WiX*Hz!ipoTIKp$r zQFW(ykxPmfta!nS7p!=}iWjVS!HO5Gc&S}=r+Cq>c)^Mnta!nS7p!=}iWjVS!HO5G zc)^Mnta!nS7p!=}iWjVS!FxSEzEgJxK0LltcQ@ZQzEgM8rjGB_UH=ouck1rxUB-9n zZlg8Fck1ruPtWPp-Mx38)2X{8_KBrT6bG>nPr|$NRXLssu z?X%DB)ZN*KoZYFrQ@($8r|urx>g-N_KDX)FoxG)8`ONjobL=Spv9G$|zN#1cqdKCW zsxSJly5kwujvsVA{*fL0Cj0nP_r=fZ5B^s_iHquvc&Y9bM|`U|!ipoTIKqk}tT@7o zBdj>WbH-71r+AS|iWjVS!HO5Gc)^Mnta!nS7p!=xU3I5;(XM#GiWjVS!HO5Gc)^Mn zta!nS7p!=}iWjVS!HO5Gc)^Mnta!oqY&Wh`caMF0T&M1q*kD|z?iL(4u2Xl1^c>fz zyYT!Oow}QH?HQfATjJ<5I(4_|CTDc&?)do<6URAOb@%M!r+4b^?TM#%>TdUaPw&*- z1C7%=b$8A}r+4b^ukW4Ksk^tIKCM%C>ppN=CqKXWo6|aZOS|%!>y_u&QT}6Jb-{gA zFZ4%sL_bwu^j~$yGpZdw=z9DkJNQlZ@u%*KpVc4yuYM92)gAFt-6@XvR&j(CM_6%$ z6-QWcgcV0vafIiLqv}raB9{~|Sn+}tFIe${6)#xvf)y`V@lw0$PVu5$@q!gESn+}t zFIe${6)#xvf)y`V@q!gESn+}tFIe${6)#xvf(JczQm5|Ledwf4-5qo5Nu9bo?6Q+O zb@#gyPU_U%ML#^LQ+K`BIH^;2$9!^Pr|!%>moy?Sb5;y5R(?$+P_#7^C9v($;5 zy1VQ3v7NdbT#fD2-3Mom?bO{)2aoO4-8RFj`&t_ zgcV0vafB5|SaF0EM_6%$=ZvH3PVpj_6faouf)y`V@q!gESn+}tFIe$XyXsEyqFwQV z6)#xvf)y`V@q!gESn+}tFIe${6)#xvf)y`V@q!gESn+~S`|fd_x;uaC<2rRWvvpjj z?w(xnxK7;-o#(ht-F1KN*iPMzn09QZ?q0BcQ;N&G8z0-LyDjETOdRKA)!i>28`G(~ z>nDuq)ZM`0V>)$rX4jZb-F<(-F`c@L?~d-&-Sxj8-Ko2e?;G98&w1`1-N{?pmCszS zJjagmAN#5c?yGvCKdK}8srsV-sym)h?f600;~&|WiX*Hz!ipoTIKqk}JZBsgU&V`DQoLZr3s$^f#S2!vV8shoykNyk?W#M) zi+05eR=i-v3s$^f#S2!vV8shoykNx(R=i-v3s$^f#S2!vV8zSZCmqqLyV>U-(W$!= zesV;o?hf7Rh)&(D*Y}7{-QC+hyi<1*cRsvRcPGpq)v3FwCywgW-A;=pCXREm>aO>c zk)665G-PC_?iPOZuuk2*e#l{+x;tvQ!#Z`>dhyUs-K~1vp`E&`&OWr0pO2n=XeV!J zS3YyS@*F$Lf9$I+xUcGk{-}=Vr|OITtL}J4wc`g}kAGwbzsWxS)P3=@`h)+~PvWAw zBVMYznK_R5R&j(CM_6%$6-QWcgcV0vafIiLqv}raB9{~|Sn+}tFIe${6)#xvf)y`V z@lw0$PVu5$@q!gESn+}tFIe${6)#xvf)y`V@q!gESn+}tFIe${6)%{$eEm;pkInYK zwlh7pe~fnal)?BJ<{Fr5)|q&tU|(7}+(OZF7}h@6TdPJG{=Y z#7itXveh1y_`@X+Yppaj@$0J}+WPLS#OHnYkk;iP+1%u`ga5{U*&nW<|6If0!u%~Z zVQg|Qn0wI&m_E$ePukai<`i$I&n46UQ!l&B|8~3GCbxE6KJCNV;jxQbGe5i1+n0NF zLhIs{Q-AiJabBz6gv68gIlJ}7cN6bEU|i?ErF|It+*kHt*@tBxmVH?EVeGHg|6=dY zu}59~H+?Sca}C#XO?myowx1P0Z2a!kt%L1+8ocWv*R&S=LE;ZTy{6UwJBi;ubz1A; zVTnIm;@Z{+$0VLL#Xk3MCq8ZE>8)e?rvCK2czWxm0}?+n&vmUuUrzk=uWR6p|!}3lf4$seXY^jv61+MLmRC@_e}Ekji2jk?X=4z--oR0sWDv->v~w% zV}Jb58?9S+p6+&*Jvp?_`bOgU4r#Uy`{-J4zhIMA>-SeDKIijRYtpuf4?KVU)}pUX z^J{kPzd`GfLlPgp+Xk)6|9XwL-+b~0t?O(*2=`j*lnq*o{pD)s$-8gRTHuhYz0c|c zeN!J`^#N8NVD$l3A7J$XRv%#X0ahPi^?|+(Tzp__r772Y-?rO-U~AGPiQl|!VC$0$ z632yBZmoCb_1v~w%mwu+beBSaJG1rv#$qm}(>}T12&xh-@{xtJ4zvi)S z-)Oxu|5WE27XL==6N@IDlyNicAi()^SrXd^U6NYtNZf2>JQJWe)7EP zfBC%f1J5h}!15a`f5P%JEdRrb3#@p-iX*J}!iqbre1MfFu<{31Uct&YxXeSvjvUtW z!tw(w|G@GaEPulCGc5nZiVLiG!HOfS_`-@itbBl#C$RDdR$jr%H+Yxr2DTR6<8rUH zeZN1jHSf<8Z+XbT*2FsT78eX`?f+`x^&TGB8ZzG%e*MV)E4Q9pEpgu;tlZjqv&2_T zTe%wfdDS1DSN-I9 z)&KH&R>keAIV`sB^^^X0qpRL}x@1biC z?)2y2VS_vU-2ULfo&N7~19PMqfT#q-|v{lq-)`)elVc~_Y?G0%I- z8`t>tJnw)<6Z5?1)QNfC$hv!v4d0zFu zd|vs1=aqk8`3;soVfh)B|6#=iR=i-v5mtO*#T`~Yz{(R?`2#DjVC5TJ=AmLouIhPV z`2m)HVEGM}KVkV9mj7YJ1y;OZ#SvC~VZ|L*KETQoSos4huVCdHyvS$kwU%Ee&F7by zXGrU-yC?3k^pMsSrzh_Its$)=Z%+L75kp$vdM@#5)sWUJpC!Iyo}sPpFP>_4k6}Yw zPp_Kz`0IzZ?jMr)fPP)AM?>Q8@7L97KkCk|&h<+!*67%ozDJ{D|DDN=&V8T#eWTN# zXXXl>e%6bHPXF)udhq8Wj(Wy9nde=7o>Uh+?=OCz^b61X(6q!nZ;z7`^SpZwPt5ba z_3gww?~faadETQ3C+2w%AC#EqRXfkC>v>+;;dy1B=hc0AUiF9PRX=%N^}l>x`GMz^ ze_;6ymOo+n8J7QH#RXQpV8szud||~MRzASW6Il5JE3aVX8(ik0Vn?p(d13hhmVaRR z4VFJ)`5Bh~VZ{YjykNx?>)Drb9VSv=j>pevx7PR^^Z6&$vIHP>&x@4DPDi?`Bt4rCN4UU4C_2HtnE) z&XB|0m$T(C{o%|xj4wH(4%2_msKfYD?L4op#}BfDe`FuO>Av_<{lS;&C%#nw@ui-N zcy`^wMsNB*au)GE(H|I6U#VjJNQTT@tf|8Kh+=ntbXEu^`E%txrmpZmv;Gq>*XKp$Zyz} zKe?~`On>Bm`l-0k|Nrg#thBbN_0RvmJ%?QL-`!`(oJ5YtJgI zJ*%+xtisx}3Tw|QtUar+_N>C%v#NITSl5%^u=cFN+OrC4&nm1vtFZR0!rHS6<8$f| z)}B>ZdsboXS%tM{71o|rSbJ7s?OBEYC-xX~U#<1QTI++gw;$Htepq|^VeRdQwYMME z-hNnn`(f?vSG(e+z5TRnZ$GTP{jm1-!`j;qYi~cSz5THE_QTrS4{L8ftiAoP_V&YC z>w~qoAJ*P}SbO_nt@Wv$aYxrP9>H4cgSFNNYpoB~S|6;nK3Hpgu-5uut@Xh=0|o00 z6s$8)u+BiiIs*mk3>2(0P_WKGsa^5X87SIy1`5_0C|GBpV4Z=2bp{I787Nq1pkSSW zf^`N8))^>RXP{uM^}#v=1?vnHtTRxs*80@0cxkPVcCGcnTI++g)(2~?57t^AthGK^ zYkjcR`e2_aG)>%%w~q{2Wzbl)>S3L!hdJBM`~%jRdRS-b;Zwf+4g~j)*81>?*7{(r z^}$-}gSFNNYpoB~S|6;nK3Hpgu)cc))_0G<`tA`}-#r5ByGLMs_Xw=-9)b1UBWhQD z>AOd0*LRP=`tA`}-#r5ByGLMs_Xw=-9)b1UBe1@E1lD(t!20eHSl>MYYpoB~caOmO z?h#nuJpya3PwlENt@Y8awLVyDeX!R0V6FARTI++g)(2~?57t^AtnX-o^&L&HzM~1& zcQnEJjwV>&(FE%|nqYlLliC$8eMb}R`i>@8-_Zo?JDOm9M-!~?XoBfKdJN{dG(XgL zG|{f_XoB?}O|ZVB2}Z|gzKV`fKlL3=T%+%3g0$~h=eU}}~ef8eaciGXd@3MpGzv9JnDPH<6JFd}p*}?iQJ6PXk2Wzbl)_2*# z`YtVcHZguH|oN$A;p9ZN-aw zs-3>*dip3k^j-FOCf%23Re$h-`iXDUe|)CrBKP&Yw95}%FaKaie#5@}Nt^u4wemkU z6c=oh6Fjd!m#rzm^o5*|AIJ%qzLOI$&qPkZJS#Z?;{$R6#y8{yjL*n*7++EYYNs}I zJv9SkhgyQMPmRIcm)e8r4>bwnOKKRV|I{$dbE%!@)%Ey6cJPnv<2T(GU#dU&QvJl2 z>Oa2Ja}h5+FYWRJ*ULZHk>9W{e{x^>nf}QC^phIqS?E7wZs)na{LX*>PF>!S_ym9Q zj)d_u??@Q`^Nxgx3-3snc=3)=JMSJ{&pQdm4(}=$`@F+o;>EiSCSJVrVB*C)5++{k z>nqQ={ZE|fqYvf2$N$?|NUo><+GEKYY{~q)t`V1K^!{&W0QnpJ78tDGjDz)?ajo?>4`v2nZ+3~mKZ;$l`!{g#~C z|Es@qSN`sjejg2+`h7H5zmEp%_t9YeJ{qjwM}zhIXs~`C4c70Y!R7CxmA^T~@3!c7 z&G?NNeou<)`OTXD>EBADKm4{A{V9JBOTXi9+`dzhd$^xs$l&_ z70hq${HuRIi~E+p-BbR)kACBcYxEmWuzuqS)^9w)`i&=8zwrd?H=bbq#uKdHc!KpC zPq2RD3D$2s!TOCSSikWEm%s5;{%%qE+eZ4WC9cx{A$*4a{6XHH?AMTK=n71r5RSZ7*copptE1{T)Y zSXgIfVV$Lgb;cI{BAzMcxpcM>*4aQi+C25=hB%tSZB&$oi&4X1`XEPG+1ZWV4Y=y zb;b?W**92c;$WSXgLQ@u*4a8(XYOE~#e;Q557yZ|SZDg+FX9xSZA_eoz;SMh6~o&E?8&2V4Venzldkw zcrJdsoZm)-UwUhSmVOVhUTDFVeh=}KZ5M3m_YgVrQbswF@8WxzlT`<_PTyEo%@!*rT&Wz7j3=t+w_~c_uaQhtIy?$zq!dGt)V9; z?mc7S)~=%x@4M2%tpyKC{OCCYT0hP0Q+o|)jm+0~S>N`^c22TB@Az1{zRRAaSI_bO z?EBj@zP@4NY4+?Z{VefJ^T}=ZCoX>rzWlxT?GIYMb!+~8&!O)x-`aie^gEtQ9K1qn z{8ovtdwGRczk!KA-F(H?9UrCN>)h_56L(da$$}EUgDi>%r1`u(Td5t*3Uhp05AT{%$zeONYYxeQ;PBAC|_4rSV~Dd{`PE zmd1yr@nLCvzy9y|U3jjSu7{=TVd;8Ux*nFUho$Rb>3UeY9+s|$rR!nodRV$1mad1T z>tT(_u*PawV>qm_9oCo+>ssss<-!9jf*(%6WOsd3Y|(g<#E*V9lLi&8c9`wP4M`V9m{7&Dmhhuo=aK-mIi^PO<-vjSXu^_#(|}MU}+*)S_zhh zf~BosX)ah=43-tpL^<0<5(K zSZfZj)*@i7QNUWefVHLpYpny;8VIbl5m;*`u+~ywt+A;6i}F2nTC?K0wEhNb{R-Cl z6|D6uSnF4?)~{f#U%^_xg0+6-*XQ*sn0qbp)y3G-X$pMPh9 z|1I|4+&wY(eQZo(`g7-%iRtIz&nKq;KU^Z+m*<+ab7G!%4d^`C_yCeYxHI z|Eo_E-)a6oXXvqRXEXEvWA>fr*uUKTKjQYp`dol^eNF-Ea|&3WQ^5M10@mjgus)}N z^*IHs&naMiP66w43Rs_0!1`3vvwAC}&SrT1a!eOP)QmfnY@_q{#qeOP)QmfnY@_vfJ>cB6!~Bh|v3EFMzR)&}71#ci^ZmE}tg+W#7dhL18}`4Q?cW=AowNO2!~Wjc z>^0188~b*j2KR$=dl#IqZ@}4(bGGlC@9UiV>uasH|Ok6=j>yACGdVlPB&Oh0I-|FEvu5^CyjCHCphgZ&5Z})zCnJ4ac?!Wlq?O)yY zptJHHo63J!`45wi^r>iX7uUO;+~)@E*}ikWuXFB?bMB{e?!R+>F6W%XYH!%{>iUK~ zud~@{*z-D@{f0fSv)#ALp4Zv>(`C==Y|rRpSAG^ByI{tW;u&f0%FoF4{AtJ7bZqZ@}^oob7vizOQrck8|#)bMC)$ zF_!XN8cTUDjio%7#!{Y3V=4F5SW161meNm+rSxB8DbJ;`RPFw}`T8n97j~Spedl~% z=iDFX+)wA+f9IT&mBlgS9B|IL;hb~EIp>nI=gY&l8pIV*P9RP12I4p!`nc5+GA zH(j@bH1;09uu5%Kb>>`o%3@!m+>uYv*a)9)aN|^tLt>F zjSsYXPjjAs(fiKx=bw>>#j^zCMt-i6V>yPbwedT8@7OgRF0YAm*zEYK%>V!BUZp?H zey2_g=3YMDQm6mXy^3qppGI*#EIYaV|9CIIKKEI6@Rhfh<5=#GuHo6|yvF*|@tgI( z!}6j2R`z*Dae2+(^k45Up7Fmk))jsZ<#YWr#^=&kImi6j{~7O>!iS;E=YP~Yv52Gm zRuPMT#(O+Ji`y^arF@`Wj6eTd^W-8%e`B-AjacMHEZ*I*cz4JAuJryC?{4V=Z!cmL zOZ!D`aQ#1IUR}hC=d$|R#`{p@27Y5MUE#xGzVx4(dlxa1eYaDNZ`G0Fd(-pmrbo`{I$+V)L;TU?2K?LM&xL<`b(sLK{?P;BuhT|2FSpGN z;g03bbLPMNZ?56rxen&<_&;G-9kU;0-~JnQU;B6Kcj}M* zT~t5KUR3|>K5@#08!ykja(e~m>m!`)IA{CL`M%D%KhC+I&UPRA?`&%%leu4hE}mD{ z;|J&LALr~hXP%Gy<^JGjXZ*qaXg7Pr#rt2zYu;tw_1GQq&V^l*4u0SH_+_r?8an1f z=RZ7se^(g%sq>idm#!n%n5#()mh8JwW2K*Vb6)3z!Hoxw=p8LoS_mO@6tNZfr>JNXXeqvAk z=ROL>Qp|1w_x$~k*k$y0ayFs%8^v<5l((xASdVP_jy?SmFpYi8ye?Y zP7Ye4TXXc%H#RP?ocz|gFNP=IT|Quc{Y(ECM!d38!2Vi?%?f|Ga+QGnAI*9zG}c%x zVE@5c?}T%9862>G-!6X+hpfD2!2a*oeLoBvy;i{f(!0+N>kL~vVE?|y9trae6-ttsONLx$Tdd0{iC*=8CLq~7`H$1(-*=6 zM;z<+_gmnl(0lRY-2UvFZVuo1`~tWC^?730{;r8`zrD<@Vb-n}yZvE*{&o2AEx&a8 zx9@dlnD>FnZvVI+-5s_*a*EqO;g7!wC&bI#{?Sk06T(ST-9EOt2mZk}_rO2c<{tP5 z+uQ^HV4Hj3A8d0E{DW=ofq$^gJ@5~{!AID~H~0wq_y!-PG3V%jkJ6YkI^d%;=8OsW zD2+MC27H8le1ng$Pi%=X_K7Vq#y+w27+e2|EiuMEu_eaXC$_}c^T%RKjImE_i81!c zO>z|bh=i~Na2{zT=E<$o;lKNk5Pi~Ns8 z{>LK!W0C){$p5JPH`}qO-&oXdEb2EF^&5-&jYa*&qJE?5*L)L;@h2AJPb|itSd2fh z7=L0h{={PZi5h<_wy_vLV=;clV*HH7_!*1wGZy1#EXL2M@zZiM7UO>`#{XE1|FIbV zV=?~6V*Ia*@xRviZ?zSvhcy1Y@0`Y;51rHa^Qm(hf99&WK8-)!oYVNz-8qdvJ)Ehp z-2V#uR$KJH!oJlO{jacZwMG9c>|1To{|ft7TlBy3@#mPi=zoQMt1bFpVL$snV&7^D z|3~awZQ=ijeXA|}AF*$>h5sY=t+w!g#J<%Q{*TzV+QR=4`#FEyzSS1_>$bYwQwMG8BeXA|<-|bs%k^gSr zYK#1L`&L`zzuULkBLCffu3xv0ZSH}8u+2U254O1n{=qi)z(3gL9{2~_+ynn$n|t7& zJpQ3^hi6!uI}h`>?&g+&*mYFSpN}*4|$=_F;Q})!2va{pI#y zdw;q8{Qgz{dH<^aynoey-oNTU?_c%bYb^Jl_pkczHJ1I){6YR_{viK{!vD-4f8 z+HX*3Sky1`Pq)vzof^YF@AhK+VgBs>=iOe6Kg^%K|Ge9a@rU`d_n&vW#vkS;)L0%r zng4tLeQxsa<0tcf?>}>sV*F(O@BL?PQjDL>|Godrt*9~VGq)S! zD?Q)1asA4f|MI`No`2^$n7`xiVeDZS=04mnx3|@9*H^mU>{PO2_AA-9|5m!M{d=YU z*xyC<)9gj{-|iFnJe7Op_BNcaui$LQIoo&6_jS(wanAjWMgN^`?Q1gk%k4a`bM}LC z_K)o2H)o!Y`{n-NM`!%O{be}v&Rh&;-@X@YS-&xD~<$8M8YR5L5xBT72u36(Y za31#9xm}xH^(|-Ce|~c1hGFNed;9v&sN05yo!1-deC`^9!lqZ<<^1*i7Y!GF?K5Zl zZ^Qn#uN~RHH|#oR`@4qyed4WqH_Waxd1Cidd!=^nqwBek>~J61=fAoy|E~VA}0^+zeG4BKHWu5K0Lm6SZ|xn8eD(C+RKEW?)g#|`T4sUeZxf~wrudX=X`fy z*zmx&y2#bZ>-7t-jM=7voz{>wLf^AL=z7KScGmj~g*g0s4Q%$h@YBZj`<>}FXH6Xv zW;eSxwz7PF>ygF7((mlj!2Z;`<_e>xpY8TfpYZkY@Z-Z9*x&2Z9^sOG&U5=0tS~Tq z>%l`C*gx_Iy~6Jfo#^)O-)?4OawEF^E!JKmjM!+j+yC&_^M(1Yo#ghfdibTr+yifQ z`$NAnAZ+)>6>k5%(XTfidHW8x-{-Gi4XeI$o!h@TyxZtA;y$;JZSH|jzPiVgXALii7he4 zKKV#qVxRGcn!!G?CC1n%H_1`#bIm9lbFoiulB3wCo$(j@Obv_*SY^~^`Cae?%e;j`fvWPeuq8QvO)}SIU30U8#O8|10Ic z*{)Q-mj9LV-)vW^U-M0+@yGJNQvRFmO7&~Li5h>*c2xbEZ=%K@vmI5x=9{ST$6^~b zW}5A&`ZeD~jXxIKsPWT$6E*%=Y@^0c^G($FW3i1IKP@+-#&GjZ)c9kujT%2KH>1XO zi*3~SX}K9S&RcAw#!t)5s4?GaE0UMgm&G<}{IuMR8vm`f{2J=Zax-fDx7zY{;%m7X zHU3*|c{}x$``^aC3VL#`O+t2>5u%GkC?Pvd2 z*w6Xn_H+Kb{p^3YpYzA<=lpm3Ie*-K&VRR`^T+My{CE4ge%*e~AGe?L-|gr6b^AI0 z-F~iLx1aOh?dSS+`+59v`#JyJey(4)pU0nw|8xCD{FBF@i2rl_M*NeFZ8844eQJvuqyKsQbo*9YjQ?(*Yp5~&lgEFzPdhb+fAaY6_Gzca z@K1jKy8S%*5gq5gY~W&bmO zQ2%-V%KywC)PLT;@;~zj?|+{Ec>d(~ul&#a!TX=*Kk`5G2e+T+Kk`5G2e+T+KW;zI z-`swlKe+uo|8e_y{^t3g=Ra;g&)+=%^Zdu{=lPrJm-(mL&+{L*pXYC?U*?}~KhNLX zex852{XBnj`@9>eu{{1TM|Asn{^s_1H&SDH{9*pA`epv9@rU`d>X-Sa#vkU-ZlAdc zHAZ}SH&SEN7w>jz4ExMYs4?=BcRMwf$4}<}Zl8BMHI~Ou=KpS=xfL~rectWVSROx_ z|GRzWR@4~wnVV2!*k^7I$38r>HCX%p8hZ!VdE$>c{(* zG>Bhc=(2X9*V=`SYn$GbzH1k{uU+WDcA*p7g??-oy0T5}WW7ndbST%OqtTVvK}S0m zdY1d5qtTW02OaHP=wkXWy=-<|M=!_qxxIq(_0HLjbGGlC?;DH$IOl#QPW^YzI$G`M zXkD-M1o_9?v)`PvKh+=n?414Yoa5qL#%oFYSR0?({+9OJE3V^g`&-(#_g>Z6*1FsA z>gAnnt-HPT7E3$ZT6A?@zr~$xt+?vG!otqBzoqIoHLc;;{+4R`t7$FH_P5yjR%czV zD%O8|oh+{l`8ru%FYU z>t$S1tb<{n`?*d2tNRw~Y5sTWC-(CC70<=G+$3z~cGeqpeFHAm_xwI)-`n$jopXPj zb3X%roBQvapG)mphm;?@-R!UqDEq9-IrCrLmw)HF+)u5GDlXptGG716JbC5yp<&q9 zd$7Nyz3IMdhFdoJsLMWoXF<*@2!Z+DTC8?Cl%c>T_oyU59(@3m&wW!W)){naln z5k7tS4_)NvFE(E}3?Dg?y)o@?$3?;>mptA@uHJO{GU4hU?8iQt_FrZ$7{;veaF=~X zQ*CqWSHo&s?#7;(_AW;+7nZyyy3K3$?;kF&?(eeCKB{AH84&I|?cdl-Q>`-hlHu(Y zf93X1e7s-S=11GIucq4U(*fc3-dDN(eOH_}T;FFa_SjTcPMkl)t0%ktqbBwb`%Qn( z?azF;ci4K;X6(JGzPGUP7Qb-&D|YJ>hMoVa+yCUWxx;z=&UgFo-Psxc3^Pj=A6MW1D;6pIb-IY8-mk zoo*l7+ynnyKl$2RxCKllb8 zVISMv1OMO~eB}POcoJ9aW1D;6AAEz4uup7>G4}BdKEgh+CC1ptH~0wq#FiLipZp@v zu#a!>5%!5KF~&Z5NB&`-*b-yxlY``<`^RESjImEXl9$-0PN^B}6I)`8eR7i=#Xi?C z=3<}RBuBANJL50*$xU(;`?NC_=l)mfKe#_2f3LCJf3LCZf3LCJf3LCZf3Gp@TmDqaAM1Zx{Wt%6jnRM0 zAFr|O|4RP1{P7yg{;%YJ%O9^X>|6d<%762JCI4Igc#UD-^1o94TmDqaAItwr`EU7C zDSs^gE9Jl0j;deFpGx^-`Clpj&307%TK-qcf3qD`zn1@%^51M%s$cU>)c9lhUn&31 zcBT5Y+KL)~%yy;vwc3grf6R8J`nB4M8h%{Ul!Y_@zZiMYW%m_@@vQ+tF5T<-)hU-$sen&sPW%w%iGDH-2V#umYY%Iztxss zL;mFcx3O=vvfpNRkS`04iZ_!Eoq z)9vT+Cl=$U+qc?c{CE3#{Biqv{B-+PTa5p1-)f8T)9qVrG5#n2^x2B>)9qVrG5))K zYKt1n?=QwrKD+1r#rW^`xrQ3U|5jU`qx7G4Y7GBdZF!E;f7+=r{FC3mZa-O{f!R_bykNnU4!R_bykNnU4!R_bykK51lH~F9WgWJ#ZAGe?9 zZ*D)&f82hazq$Q9|8e_y{-*k6{+Y)gpZ_TTnZK!inSXly=J}iIm-(mHZ=S!Yewlx| zectWV82OXuZ*HG=BQ=)CALh?)pLZiQhX3>Y+3n}~r`yl-XSZ*$WzO&Rc{fsHdHiAi z?Dm-(Qe)&N?{;bo`^*jP{iX4T`Lo++ZfNf>x6j;)8q4Dk^Jll8=l^b>xgj-%eTyyg zf49%vkQyWZEw;@6-9B?eYK;81crxdAo0gAg79aDoPVsR*YZD*anIBOnJR|v>&u&!t zj05L5s(i*F!ugDYb3WtXoXCYQQz=T#T(FwGZn5QJ~+pj?|ue{@Kp9H={lGUGF;E-i-F8 z%|AKY-i&r}2B%$|&1n~BcG{d_%4d1n#TlP=arVdT_?anRC*cfJJ}cDDXQsTJe&w@8 zwCl`KyEu!49nMVo^~KpG?#r1eZ!gX|(NE4yc{^v7^4TJui!)P`Sr^Lf4LDyP;B3b^ z+jq|Qb-o2RFYNQ$6%AV-ZqHck?Qr1Rmo;oXxjp5W+2O+< zuN|#_fka zp9@dzHQMbTJ^c@1z%@s^{b$d3Djd}RNVor&MV<(A&p$HI|2KDiG|YY1L2m!HckcF5~NS@{=k|G{-;g#Ps4L-s?zQIRn+#VC~Q5v^L2Yi&q?V|%eO5^sC0UxDtdt|^z*vB{c2>ZmA7-OH< z5@YNWTVjlTVoQv%Pi%=X_K7Vq#y+tn#@Hve#2EYJCOL|Ia+4gzKDkMbVxQb3N3lW#3Fy9^2hQ&7Wp5G{EtQc$0Gk@k^iyC|5)UIRQ{Xo zSk!MU>Nghk8;kmlMg7L2eq&L;QT1!SiN*L6i}5EG<4-KcpID4Pu^4}1G5$o2KNj0q zjGwU>KVva|#$x=8#rPSE@iP|VXVmyAB*unYW%m_ z@^@Jpf4bK;FIk@ax7u@|M~2d+M@q_ z#!79`e?C{Gw&*{frBYk;pU+Hrf6;$FC*}P`|M_f`_ZR)=^G)7g_&;LbY775I>|1T& z|A>97E&Ly`Z?%R0BlfMf@PEX<)fWDb*tgok{}KB+f84&+7Ww1$t+vP?w{NvY{Ob#a^`G~z`p^4U{pbBF|1*D(|Cv9?|I8ocf94PJKl2CqpZSCQ&-_9DXa3;! z^ZZBo!~942!~DnXGd36b!~DnXGd36b!~DnX=lPG@&+|98pXYCGKhNLXexAR1|MUFK z?dSQM_dn0y+|J^^#O^Wf8`M>*zxk)j8 zGXHn~FgGd2Pv-ybAInYji^hNSi^hNSi^hNSi^hNSi^hNSi^hNSi^hNSi;w@Mp8Zl| z`uB}U+y19DCgTa37TsEM*4O{E^()=$*7+xN*2-Y5mBCsogY%j|g!5W~v)0OJ*IF5z z^Pz&3Cq;XsxIVyIi-5CzZ_oF2&i!%D{dCU0YVx;Qi-5D1_javC(5|%zIIjt~9j!&s zuC)kQYY}i>bMXFaEuv`m=grs0!j7}nB52oI1gy0PSZfim)*|3CUh=2qOhbN#<$qXl zffX-UafB6LSaFAo+-vB*x!s>XU;pLz;h3+KxA-LcKfuL!XnyXj6?fQT`ZuiWX_p;X z_Ti!~6i4z_ada-~LUAPj6-VcyE{MCY(PcY)uaVm+>Vo_F8Xeczzxx^;ob%kTFY1El z;(Lvj=bGG3UFiB)*l{lEg6Hz@Q{tMUF4RxIzNia*uTjnQ%3E0ZobCAcKEcX=Sakts zKf8U^5$!oH-hXO=yDT1Fe_ga| zj~SfX+r{-2ob5Pg`_B2k&bdF%xu220&HZ=g>@0ira=Y&dg!5iIZ#O%>SC96*H&6HV zJ%O}ae|+yCth2YU_5{M*hcmQAyFYKfzCnAo<804`edl~%=iDD>?Fr;>wI>iR<0Ymx zbq%b)g=G`gyusV?4Ru9JWLG9QJ8<{IymQ~ zkD00|+RJ#U7OY+SFgYL1K2n{VuJV2TvpLlQ*W~+pd%mx8zOT>IR0~|6@2mDNnk|hanAOg^L?Fjf1Gna8JE<5 zXZ9NBag28M0DHS)&GpIwSh)c!XJF+LtQ>=L&U^pK$vlp!opDUpHwrt>*}ikWuXFB? zbM9y0Z&eF$880!ps%v2VEi9X`?ggt4aDGN=u+wL_sOxIVs70FX1y=L9?vUyInoGQ} zvGb0*&)1yt#HP-N?=Wxk^0ha2o_#~#=4V@M<-EwceVdPdW!uD$_G!*q=6lY2|GZE0 z&1ZIYK4W3j%?$KQIvdAYuQny+1vc(J{EH`l#1 zU31#=y_%bx`m$fsJg`^uovv4%|G0dw<|jMNa(?NRp3TQsddKDN!crbqMi!Rt7`GEa}@4rer+FM6eWbJOoP(>2d_Z?3l2`p$QM)V+D|f!}oA zw9%v4HEJX0-skpc{%GBAIe#)}?&c*QZsNT0x;>lYm;Sc%ksHq2yn5gd)Ad*NZ64lj zPv`3w=-YhdvEk{OL;5uDzvuwx)5rB_-m=9A=XJO1)|~WCy5<|-o~t>}%zeE5l5c+= zdft<`Iq0+Sa7fp5TlLd$*uZ`Ln#)Ff5?+D9&Q{``h_!i7^VcE0P*55mSbUE%!d2eZR_TVL(G+=}mq`<|cX zJa(%;hnq)S=lpr|k71jbu9mFO;^=5#2wB(etmyf zYU=IIZ=Q5tICb^J=kIZE81a?FcWrr3*zxO$U)$|BVVffopSkAU;obw2ovVi55ze#! z%^3Bkdv6bKyp(wVEp87h+>`qDo%wDLOFVdwU-NnY+rzzY-|M{H4!4J=d*1K-#OJq% zUAIqtKH{yr!{vj2>+L)T&x3uQkLQGWZk`{;ANU2{{NWj)=fr26f3w+*VZ#Z(cb;(d zufpusQ_hQ=aDCW*(v!|Zeso#qnu-89{I@13p)A8wTT{L64fSl`xy>0AHZt_W)#m-@f) zD_4Y@XU_EYo0h*Oth(H*&g3ci%Jt+gc?^@+k1cTaiK z`Q+^{43n06!+EO>E(oveHp}_gRn8CJ{@``z8x}e*Z2EZO*OoXpd^|hxGVz>n;^cJw z2E)$`8{Uv?K5^;K!?^X|^1qF<$A#;V|Y zX6)o~;j8Dr=e)z9v%*=cf9T9O#CXKBFg`I(!HipsUohht;~G4y-|^x3b?0(EWs5Ok z|C>H>JNxt;9ro(^vGea2Iwrij+DFcN_xMSed1<=WE-%=395?a!FKPdM63-6gD?R~?u@c!XF1oK|%ZSNyxgzY1wtc%2y{|W}mgf@19Ql-MB{hbcJ-UTlO0qwm3a;k5Q|K@e8C_gwIwB z^IVkp&Hk&0hj&W-{IuU1VYerHd!Ly{FrVOAm|rl@fSGqN|A3i~FfW0Buxr2Y{praM z>t50~tbbOrv+o*&-R4i& zym`mZ8=s9#Jgwh5jczX|9yIFBM)$8II}=`bt#RWMQG_r~T&B)(zBu*PjyBz|Ot?Hf0Kn)u^$zuoxi zf$3hu@77NsCbi`(j5m%(XJ^%Pdjk#A(aYP582e|JNZ!FXpb!OrlM!(-R;PS*f zEq_PX(N*H!i;e2~#VYAIHqfdL5Fu*K*GdeQ5o}m#lWg(CY^!o^t(BGuB!;@e>nf%(!!K;){R!!HiwEOMJpj zi?w@Qkoexu)@MP@ zNU&+63XKGtHmcA_uxX2_1e-Rh&`7XpqY8}#n>MP@NU-HMP@Nc^p7qY8}#n>MP@NU&+63XKGtHmcA_uxX2_1e-Rh&`7XpqliX=O&dit5^UNiqLELDQB-pf3L?gkbjUpNewy`K` zEV3~wYK*e6D{AbrF)eCLGi?;nNc^p7qliX=O&dit5^UNiqLELDQB-pf3 zL?gkbjUpNeHf}<8^!6SkzmtC5sd_!Hi~E@*tAhZBf+MPA{q%cZ4}W+ zu)S-d-Zl0Pih2jxyD943Wbdq~ca~|Rh(_XXO&dit5^UNiqLELDQB-pf3 zL?gkbjUpNeHf}<8$~n{Y}zQIk(^&VGNO@S(?$`E1e-RBXe8LQQA8ub zri~&R3AVXJ)Lg>m7*TT!n|nmfJ#0=AH77A`6wyfht!bl(MuJTnMKls@+9;xtVADns zjRc!EifAO*v{6JO!KRHO8VNRS6wyeqX`_fnf=wGmG!ksuD58;I(?$`E1e-RBXe8LQ zQA8ubri~&R3AVXn)LhZ#kWq6;n_EWBEp5&jHRm*K6wyfht!bl(MuJTnMKls@+9;xt zVADnsjRc!EifAO*v{6JO!KRHO8VNRS6wyeqX`_fnf=wGmG!ksuD58;I(?$`E1e-RB zXe8LQQA8ubri~&R2{tVdr3FkQL}>)m4pG{{G)0uAFl`jkNc^p7qliX=O&dit5^UNi zqLELDQB-pf3L?gkbjUpNeHf}<8$~n{Y}zQIkzmtC5sd_! zHi~E@*tAhZBf+MPA{q&{=ZMmJ_IweIM7uqAlr}VfL}^CTMiGs~HKvUs8VNRS6wyeq zX`_fnf=wGmG!ksuD58;I(?$`E1e-RBXe8LQQA8ubri~&R2{vsM(MYgqqliX=O&dit z5^UNiqLELDQB-rvaO3PdRMrnM@>nQDS`5v_LDQ zB-pf3L?gkbjUpNeHf}<8$~n{Y}zQIkzmtC5sd_!Hi~E@*tAhZBf+MP zA{q%cZ4}W+uxX=+MuJTnMKls@<4~=&8XKQ#t>M_XRcmd>#a+kzmtCH5v&v zZB(O?VADo58VNRSRHKn#(?&HK2{vt1qmf|KMl~7a+ zkzmtCH5v&vZB(O?VADo58VNRSRHKn#(?&HK2{vt1qmf|KMl~7>n? zd1bA&cbjk4T9Y?zRHKpjThm508VNRSRHKn#(?&HK2{vt1qmf|KMl~7a+kzmtC zH5v&vZB(O?VADo58VNRSRHKn#(?&HK2{vt1qmf|KMl~7a+kzmtCH5v&vZB*;C z64M7Y8i{t(4K*4GHa$_JkzmtCH5v&vZB(O?VADo58VNRSRHKn#(?&HK2{vt1qmf|K zMl~7a+kzmtCH5v&vZB(O?VADo58VNRSRHKn#(?&HK2{vt1k1>q|n>MP^NU&+6 z8jS?!XK~KY=$xOu;+pIeXVXTteSYL@+Nee&agAxC8jS>-HmcD`uxX zn>MP^NU&+68jS>-HmcD`uxXpA1e-Rh(MYgqqZ*9_n>MP^NU&+6 z8jS?!Ty@Sl?3{DkIp@5yX`>pA#NV1Ws?kWWX`>pA1e-Rh(MYgqqZ*9_n>MP^NU&+6 z8jS>-HmcD`uxXpA1e-Rh(MYgqqZ*9_n>MP^NU&+68jS>-HmcD` za2|`C^BCov$1dkQra7B7s?kXNt!bkgjRc!Es?kWWX`>pA1e-Rh(MYgqqZ*9_n>MP^ zNU&+68jS>-HmcD`uxXMP^Nc^p7qZ*9_n>MP^NU&+6h(>}<8$~n{Y}zQIk>JZl zd=k+}uxX=+MuJTnMKls@+9;xtVADnsjRc!EiuU=DvuUG}<8$~n{ zY}zQIkzmtC5sd_!Hi~E@*tAhZBf+MPA{q%cZ4}W+uxX=+MuJTnMKls@+9;xt;H(9l zvqo^v+QB(%3TM+s5sk#(nl_4PB-pf3L?gkbjUpNeHf}<8$~n{Y}zQI zkzmtC5sd_!Hi~E@*tAhZBf+MPA{q%cZ4}W+uxX=+MuJTnMKls@+9;xt;H>qWvj%j| z+R!;`MrYGT5sk#(nl_4PB-pf3L?gkbjUpNeHf}<8$~n{Y}zQIkzmtC z5sd_!Hi~E@*tAhZBf+MPA{q%cZ4}W+uxX=+MuJTnMKls@+9;xt;H>4Hv&MJM+TS^^ z2{@ZJifAPM*0fPXBf+MPA{q%cZ4}W+uxX=+MuJTnMKls@+9;xtVADnsjRc!EifAO* zv{6JO!KRHO8VNRS6wyeqX`_fnf=wGmG!ksuD58;I(?$`E1n0Gy8qRAt&UtOeIj{LR zn>LDQB(67Y6wyeqX`_fnf=wGmG!ksuD58;I(?$`E1e-RBXe8LQQA8ubri~&R2{vsM z(MYgqqliX=O&dit5^UNiqLELDQB-pf3L?gj@EzUWw(K+X}JLkNn=WN<2 zqLKJp(?$`E1e-RBXe8LQQMAvGoJ|`=G!pHmjUpNeHf}<8$~n{Y}zQI zkzmtC5sd_!Hi~E@*tAhZBf+MPA{q%cZ4}W+uxX=+MuPKNt8-q1bI?R?)S}W?9O@Z-8rwxJDWDL&k^T$ zHf`h@2|K2ZTqD7zja(zarj1-9!KRH|Bf+MPTqD7zja(zarj1-9!KRH|Bf+MPTqD7z zja(zarj1-9!KRH|Bf+MPTqD7zja(za`Lh!5fBp=`Ie)g|oIi7MHf_{KBk{MUjoN4= z*tAg_jRc!EYNL^0(?)GH5^UP2jYfh^8_hr?!KRI7ppjtHMnlm^uxX>AXe8LQ(NHuJ zY}%*`jRc!E>Ov#Irj5GLNU&+6E;JHs+NcYS1n1AfobzX7&iS)5=lq#kYPY?0Xe9oY zy>)0Ln7wsqB$&N*Xe5}ub!a4*y><5aku!Vi&`7kiw+@X2v$qb71hcmejRdo|4vhq} zw+@X2v$qb71hcmejRdo|4vhq}w+@X2qvO#?aQ+O`Ie#|loIf*lW^WxDiR;;0hem?g zTZcx1*;|K3g4tV#MuOQ}hem?gTZcx1*;|K3g4tV#MuOQ}hem?gTZcx1*;|K3g4tV# zMuOQ}hem?gTZcx1*;|K3g7atD&iONL=lt2XGwVHQB(7&~9U2K{Zyg#5W^WxD31)8{ z8VP1^9U2K{Zyg#5W^WxD31)8{8VP1^9U2K{Zyg#5W^bK+e&o#FIy4gPri}s`31)8{ z8VP1^9U2K{Zyg#5&U+P{S)XH_j`qB_!8z}FaAt2E8i{MzTZcx1*;|K3g4tV#MuOQ} zhem?gTZcx1*;|K3g4tV#MuOQ}hem?gTZcx1*;|K3a<;v7Xe5}ub!a4*y>)0Ln7wsq zB$&N*Xe2oAMRCr1RGjnP73aLC#o4q`KqK+D?5#s1!R)O=Bf;#gLnFcLtwSTh?5#s1 z!R)O=Bf;#gLnFcLtwSTh?5#s1!R)O=Bf;#gLnFcLtwSTh?5#s1!R)O=Bf;#gLnFa? zuaR@!gXEm|COPLlOU~@ALnHCG?5#s1!R)O=Bf+MP0vZWsZyg#5W^WxD31)8{8VP1^ z9U2K{Zyg#5W^WxD31)8{8VP1^9U2K{Zyg#5W^WxD31)8{8VP1^9U2MFd&!*h9y4b? zS3x6jP2Q8{%-%XQ67B4*LnFcLtwSTh?5#s1!R)O=Bf;#gLnFcLtwSTh?5#s1!R)O= zBf;#gLnFcLtwSTh?5#s1!R)O=Bf;#gLnFcLtwSTh?5#s1!F&#eMuPc#42=ZyxfvP> z=JPZ(63pH@G!o3-Iy4f@-a0fA%-%XQ63pH@G!o3-Iy4f@-a0fA%-%XQ63pH@G!o3- zIy4f@-a0fA%-%XQ63pH@G!o3-Iy4f@-a0fA%-%XQ63pkEXe5}=Kha1qpNpcAU_LKJ zBf+MP0vZWsZyg#5W^WxD31)8{8VP1^9U2K{Zyg#5W^WxD31)8{8VP1^9U2K{Zyg#5 zW^WxD31)8{8VP1^9U2K{Zyg#5W^WxD31)8{8VTleY%~(g=i6u`n9se@NHCv=qmf|t z)}fJL(?$V}1hcmejRdo|4vhq}w+@X2v$qb71hcmejRdo|4vhq}w+@X2v$qb71hcme zjRdo|4vhq}w+@X2v$qb71hcmejRdo|4vhq}PXUbtvws1N1hcOJjpWy)J>kymtwSTx z&fYpS63pH@G?KU5-a0fA%-%XQ63pH@G!o3-Iy4f@-a0fA%-%XQ63pH@G!o3-Iy4f@ z-a0fA%-%XQ63pH@G!o3-Iy4f@-a0fA%svz}63qS-G!o3d6*Lmeeik$m%-%XQ63pH@ zG!o3-Iy4f@-a0fA%-%XQ63pH@G!o3-Iy4f@-a0fA%-%XQ63pH@G!o3-Iy4f@-a0fA z%-%XQ63pH@G!o3-Iy4f@-a0fA%swMD63qT1G!o3dBs3DtekC*#%-%XQ63pH@G!o3- zIy4f@-a0fA%-%XQ63pH@G!o3-Iy4f@-a0fA%-%XQ63pH@G!o3-Iy4f@-a0fA%-%XQ z63pH@G!o3-Iy4f@-a0fAoX^@gv%d_DL_7P=&`2=*(a=aRd+X3hFnjCJNHBZr&`2(EFrd+X3hFnjCJNHBZr&`2(EFrd+X3hFnjCJNHBZr&`2(EFrd+X3hFnjCJ zNHBZr&`2(EGWeirBajL!Ml8(hO#C(aVX#o6AfINMw43_I5pXM3ySY;RSZ?X8Nl zy;X6x*X*P-+StkM-iP8Ww(JD1$@ZP|eVucEoQt#A>VK2J{i1$HL9R#q=6hZ9=edns zkKUf^(K*+nbFN3{T#wGV9-VVNI_G+H&h_Y=>(M#aqjRoD=Uk7@xgMQ!Jv!%lbS`qT zQRHf)$l*q=M{>B4>(M#aqjRoD=Uk7@xgMQ!JyKtdT#wGV9%s;=>(M#aqjRpuHrM2O zbk6nYoa@m!*Q0YWw&)qXy%>uc#Tdm}1?K@P?v>92I_L9%&iOo`b3PB4IGqP{&gTK0 z^LapLTdUwapmRPC=$y|3I_L9%&iOo`b3PB~oX-O~=ktKh#k<4zYv*^0@8izz8sFcY z-$ATZa30YAHlGJ{&gTK0^Laq$d>+s_p9gf#=K-Dbc|hlU9?&_T2aNbOp9gf#=K-Db zc|hlU9?&_T2XxNo0iBDvL8F*6G>W-IqnKkfY^{Rxfd04nJfL$v59plF13KsPfX?|m zpmRPC=$y|3I_L9%&iOoGx+a|m{QuZ{)2M5%vRs!|5JUtNL_t6T*n@~jzM3yh1W}}K z42YqZEg%U9f`Wp8h(Q$DXrwnl0@5Qwns?O~=?PsRArKOhAZbt(lvXx~vgduR>%r%| z<1kKsoIS?LHx6SkzAN*sRjbxoRkP;2=X2i$>j#AO1H$?N;ncdip1bG=q&>B+(Z};0 zwlU$-#)?ZDLoWIO*&tRE284+!fAgr`;!KOj7{iueIx{eZB3Kv+K@tRE284+!fA zg!Kc$`T=46fN&ezFKx`fw7J02<_L>^KwhgK5Y`U}>j#AO1H$?NVf}!xen411Agmt{ z)(;5l2ZZ$l!ukPW{eZB3K)B7_mNutb+FWmGbHGJEAg|RA2o3k%%F2A%n{-Pg{*Xjp^^#j8C z0b%`suzo;TKOn3h5Y`U}>j#AO1H$?NVf}!xen411Agmt{ZraPzG?}GoHA~ZQ7X5&{ zRzD!D9}w0L2&dN7_1r~2Anp1AVf}!xen411Agmt{)(;5l2ZZ$l!ukPW{eW=O)|RHZ zElrDCnnt(i2jsQ-0b%`suzo;TKOn3h5Y`U}>j#AO1H$?NVf}!xen411Agmt{o?1ox zfUtf*xM`yM91eKOn3hkmJ-32sdqfj*amH(%!W6rD^Poen7U-4+!fAg!Kb%_p|i_ z!ukPW{eZB3Kv+K@tRE284+!fAg!Kc$`T=46fN*MEUC&+G+Q-t?M3%Nzva~gnML!_> z(GLjg2ZZ$l!ukPW{eZB3Kv+K@tRE284+!fAg!Kc$`T=46fN*MEQ}dehP(L8t*0z?m z=C!o7u%)e$Etwm+p1bG=WIw5OP0cG~zpWn-)(;5l2ZZ$l!ukPW{eZB3Kv+K@tRE28 z4+!fAg!Kc$`T^m#cDb}Q&84k%E^Q5T(GSRL^#j8C0b%`suzo;TKOn3h5Y`U}>j#AO z1H$?NVf}!xen2?2uCC`U`T=Rz4+yul>3qic0cme**-KmFUNSdwJ$KO$$oBdHVf}!x zen411Agmt{)(;5l2ZZ$l!ukPW{eZB3Kv+K@tRE284+uwBb3HfbaCA4?GdD`jYtGNi zjZ*U()(;5l2ZZ$l!ukPW{eZB3Kv+K@tRE284+!fAg!Kc$`T=46fUtf*SU(`F9}sS} zCF!H$2c*5#qNGoYACPwafUtf*SU(`F9}w0L2j#AO1H$?N;Z{4eL@#$eH}|Ia0okV2AT9aj#AO19BhK4+!fAg!Kc$`T=46 zfUtf*SU=#Fw|+oaKOn3h5Y`U}>j&i6T5VXy81Vzr-fGE~R%5oL*46dgML!_>)DH;j z2ZZ$l!ukPW{eZB3Kv+K@tRE284+!fAg!Kc$`T=46fUtf*xYhn;3>iNl?X6aDX*Gn4 zen7U-4+!fAgj4J4dhVhhaJ$c~9}w0L2j#8e zZD-~P@dMJHbxzlFmsTUX=m%sQ{eZB3Kv+K@tRE284+!fAg!Kc$`T=46fUtf*SU(`F z9}w0L2R-2tUe*A#6w_5I{)p##+JvV+pw$Tp=>j#AO z1H$?NVf}!xen411Agmt{)(;5l2ZZ$l!ukPW{eZB3Kv+K@+-mQm;lvL}d#lx7S`GiA zACPV4dhY6a?xG)%cKv{`en411Agmt{)(;5l2ZZ$l!ukPW{eZB3Kv+K@tRE284+!fA zgq!Cg+FksB+ikXfKv+K@tRE2854dgL`T=46fUtf*SU(`F9}w0L2Q*N`~K3{o0p3ELDzGc8@ZmF^`rO!*^hoe zSU(`F9}w0L2j#AO1H#SwmaLTc0cp>?!S&p% zAH@&II!kI@UC+(>QT%|k>j#AO1H$?NVf}!xen8fP^aH~B0T0etT|XeK9}w0LxG&r2 z2ZS>>ay@s^4@kRyK-kX$`x#+B`;vY7oxu75Vf}!xen411Agmv7%UeGntRE284+y8$ zH8rn!U;Tiven411Agmt{)(;5l2ZZ$l!kHUoKA-)24#S??u;)Ci9}w0L2j#AO1H#RFUiTo{ zy*F*Q`EL(<){o)`q+LHCtRE284+!fAgj4I9n%8_+`T=46fUtf*SU(`F9}w0L2F$V0|19nUT>j#AO1H$?NVf}!xen411Agmt{)(;5l2ZZ$l!ukPW z{eZB3Kv+K@tRE284+uL}gdIb|jxAxwoUndCSU(`F9}w0L2j#AO1H$?NVf}!xa{<^n0_@xYc1{872ZZ$l!ukPW{eZB3Kv+K@tRE28 z4+!fAg!Kc$`T=46fUtf*SU(`F9}w0L2s_tj#AO1H$?NVf}!xen411Agmt{)(;5l2ZZ$l!ukPW z{eZB3Kv=C6R)dArW??m3SU(`F9}w0L2j#AO z1H$?NVf}!xen40)9adw9)!tz>c{p>U)V${W*AEEm2ZZ$l!ukPW{eZB3Kv+K@tRE28 z4+!fAg!Kc$`T=46fUtf*SU(`_S_$kL3hden?3xR#9}w0L2j#AO1H$?NVf}!xen411AnaNg>>3&D+8OMc+O~b`2ZZ$l!ukPW{eZB3 zKv+K@tRE284+!fAg!Kc$`T=46fUtf*SU(`F9}w0L2xo4T8oQjIu7Sd?jl!;(!ukPW z{eZB3Kv+K@tRE284+!fAg!Kc$`T=46fUtf*SU(`F9}w0L2)b9 zu8G6?0b%`suzo;TKOn3h5Y`U}>j#AO1H$?NVf}!xen411Agmt{)(;5l2ZZ$l!qzIl z)-b@j#AO18#Zi2ZZ$l!ukPW z{eZB3K#t8?6xbRS*xD7?nig0;Ap6k|2j#AO z1H$?NVf}!xen411AZ)D>Yz-1@Z4zwF609E()(;5l2ZZ$l!ukPW{eZB3Kv+K@tRE28 z4+!fAg!Kc$`T=46fUtf*SU(_aEg5W$89e6>BQj#AO1H$?NVf}!xen411Agmt{)(;5l2ZXH^g!B3GIrABj#9b1%<5Whtto}) z`ceFVuzo;TKOn3h5Y`U}>j#AO1H$?NVf}!xen411Agmt{)(;5l2ZZ$l!ukPWYkgsB zfMIKcVQYqA{eZB3Kv+K@tRE284+!fAg!Kc$`T=46fUtf*SU(`F9}w0L2j#AO18&>5en411Agmt{)(;5l2ZZ$l!ukPW{eZB3 zKv+K@tRE284+!fAgss(wt>K5Q?T4-ThxG%(`T=46fUtf*SU(`F9}w0L2j#AO1H$?NVf}!xen411Agmt{)(;5l2ZZ$l!p+0AG!NJR|2)n4{Lb|4|6hBaX7gB) zoqwP_UrcWi=cK+=_~Pz^Yu6yz|CzJR^NQ^M%-O>FpxY8% zL#5C8Kk|IE1GS%Q_lS*tF1|zkT(EvFSU(r6p9|K{1?%U6^>e}cxnTWV+im_2Jl{=k zSN4BE-N)M)W}_dC?@&J)tRD^5j|S^UgY~1q`q5zhXs~`XSU(!99}U)z2J1(I^`pW1 z(O~^(a2s1z?nK&Crt}@ZGs5~AVf~D7(~c@vD($I5 zPOcPuao3TWhIT+bpYcG|Ih)3NKs{gbK-J;f8pHwhe9QxNov5vm9Z=8rJW$s$+Zygh zKXTUck}rL+em?1ey3XEe3=XL0s~)IzAgu;wqaU2>OFuZQ9~{;X4(kVp^@GFu!D0R2 zuzqk@KRB!(9M%sG>j#JRgTwm4Vg2B6t4&JQcRedMKKJC7XPf2XUZ>P*v^M(L`Rw}H zVg2l|es)+tJFK4_*3S;>XNUE(!}{4_{p_%Qc33|iHD(T~q(*N+eD$A|Uf!}{@I{rIqcd{{p|tRElNj}Pm|hxOyb`tf1?_^^I_SU*18 zYCHS0dXp29=RRbc<>FrF*=k&q4}ZWsU-&?+LvA(L8}kr2SIt9!%|n3ALqPvA4*@n0 z0X7c-HV*+d4*@n00X7d|%l|JuANfG7lW!h@jd>1yZ{|6`<~hLTIl$&Qz~(u?<~hLT zIl$&Qz~(u?<~hLTIl$&Qz~(u?<~hLTIl#@k(Vz949I!msDcdX;cOOUdux!ku;Io@Y z0h>nwn@0hgM*%0RFB*O3Zst+I=25`rQNZR=z~)iF=25`rQNZR=z~)iF=25`SThyOb zot(NncP!g17k8gg^H^=n)8Mn4rvaO%0h^}*o2LPrrvaO%0h^}*o2LPrrvaO%0h^}* zo2LPrrvaO%0h^}*H}6}Xl~B*xPL5)pi-iY{u}dTI9JV+fz6ZIwr}%f zVDn^P^JHN2WMK1TVDn^P^JHN2WMK1TVDn^P^JHN2WMK1T;Fi76pEaKx?*k@>p=D6y z`6m0L(PxZj9?tfA*yiED=HbBR;lSqMz~e>OKJY-w327NA(b)DU^EAJgc|NdtKCpQ{uz5bPc|NdtKCpQ{uz5bP zc|NdtKCpQ{uz5bPc|NdtKCpQ{aLcZ#=h~;8XEs{5%rhI~)lB=vF~_E5_~iLA$s5o{h2Y#z~WwlR+gHjfB4 zj|eu82yWR*dDhGUnX}X~rpTI&MxXD>JSEuk5H?QRPJx8%+ zNTz;1d0c#6^SEI1xM1_RVDq?O^SEI1xM1_RVDq?O^SEI1xM1_RVDq?O^SEI1xM1_R zVCRy1`GCs#R1@Gcssq640I+#tuz6yzd1A16Vz7B)uz6yzd1A16Vz7B)uz6yzd1A16 zVz7B)uz6yzTFqWQpmJ!{*|wj3KKnNseeNmdp~2>%!RDdC=Apsnp~2>%!RDdC=Apsn zp~2>%!RDdC=Apsnp~2>%!RDdCYN31ifXYc$$L2GtW5ep$usSwuo*QhQ8*H8%Y@Qoz zo*QhQ8*H8%Y@Qozo*QhQ8*H8%Y@Qozo*V31!(Kk1a=cwL;xoEV1iMZIn@0zmM+cin z2b)I+n@0zmM+cin2b)I+n@0zmM+cin2b)I+n@0zmM+du>x0es7oO#z|`HZf^!mh)@ z=IO!a>A~jd!RG0~=IO!a>A~jd!RG0~=IO!a>A~jd!RG0~&)DYa!RG0~u9fdkf8O|j zdJckh4tz%Q0Ace0`5w#zgv|ql%>#tZ1BA^3gv|ql%>#tZ1BA^3gv|ql%>#tZ1BA^3 z>^qeDWV)=~L!NTTA!sbcB=1IclNy6qy z!sbcB=1IclNy6qy!sbcB=1IclNy6qy!sbcB=1IcVD(~e3>N#B2ne!Q~Gl#7+ht0!; z&BKJv!-UPlgw4Z*&BKJv!-UPlgw4Z*&BKJv!-UPlgw4Z*&BKKC0_^1j>N#=xIQWcN zBl3B08}mGAH_sC`&l5J!6E@EiHqR3_&l5J!6E@EiHqR3_&l5J!6E@EiHqR3_&lA>b zvzHI3=NRgf;xn2@3Y$j?n@0+pM+%!q3Y$j?n@0+pM+%!q3Y$j?n@0+pM+%!q3Y$j? zn@0+pM+)m@+sg;kb2jxM@)^xjh0Rli%~OTVQ-#e_h0Rli%~OTVQ-#e_h0Rli%~OTV zQ-#e_h0Rli%~OTVQ-$@4?&SmOIk5VC`Hbel!sfxk=E1_|!7>jr4;D5L7B&wSHV+my z4;D5L7B&xd%iBCy*gRO+JXqK~SlB#Rj!iH2UOu3nQ>>4k&uE@4--CI!uz9wydA6{5 zwy=4&uz9wydA6{5wy=4&uz9wydA6{5wy=4&uz9wydA6`w2YdN|dXBa^6?{hXcwzH+ zVe@!l^LSzNcwzH+Ve@!l^LSzNcwzH+Ve@!l^LSzNcwzH+Ve@!l^LSyiME3Fl^_+Jz zVfc*Zz`*9fz~%|V<_W{*3B%?I!{!OY<_W{*3B%?I!{!OY<_W{*3B%?I!{!OY<_W`Q z_3Y);&yRQmrmmR!`4MkG*xVl2+#cB69@yL-*xVl2+#cB69@yL-*xVl2+#cB69@yL- z*xVl2+#b07MtPp*h(;fc)SM;QoF&*iWY|1p*gRy|JY?8BWY|1p*gRy|JY?8BWY|1p z*gRy|JY?8BWY|1p*etBQyqJrX_QhN**jy~wTrAjJEZAHu*jy~wTrAjJEZAHu*jy~w zTrAjJEZAHu*jy~wTr9Z#MtL6Sh(@2^%N#Sj<0c2%GB& zo9hUh>j<0c2%GB&o9hUh>j<0c2%GB&o9hUh>j<0c2)Ey8F^4nlsh{7mj%Z_^HtptV z!?)VzX~X7e!{%wj=4r#`X~X7e!{%wj=4r#`X~X7e!{%wj=4r#`X~Slv?&Z|a??j`| z?`3W(Y;G!SZYpeUDr{~lY;G!SZYpeUDr|1*cAIT(Dm?4HcJi$E9K)>p+R3xt!?W&d zC(n8h&$_RjJnKC?>%MmKtoLyHjq*I%ooMv4J@xZD(dfhGfy3s3!{&j*=7GcJfy3s3 z!{&igb7&qoY#uml9yn|sIBXs`Y#uml9yn|sIBXX2UQYe|PBi*__E}fClk9`Axx}!! z#IU)Nyd>neAWeGqQH5zo(wMnBuhsE9@%Hb)ws_47N?=+i#y=XavfhiCo#PBi-Pte@YB zMjxK_^E=V#!?S*VCmMZt*3a)mqYuye`JHI=;aNYw6OBGR>*sf((T8XK{7y9b@T{NT ziAEou_47N?=)<#qekU4z*sSlp98Gk`y5-c*?<8AfZlC)3on(uIXWjBnvPHtPZh0r! zBJinK*h#iXc-AfNBwHjr>y~$tEfSt}%R9*y3D3Iaon(uIXWjBnvPHtPZh0r!BH>xL zypwE^@T^T|mUogZ5;p4_o^|Fs(dcJ;>gRW&(T8XK{7y9b@T{NT ziAEou_47N?=)<#qekU4zc-GJFM57PS`uUw`^x;`QzY~o9qCEe_aVh(6&xq--jZb`JewgELytydP({Y}{{@XKm`fHOLFtT0t z-*|ITo=@bwmHoG881>gCM`Gl2X8(;h7v*_REfaOqo(a`oyHO+E$^IK}F3R(>)E@KN zO?$>xf9=p zRNs0=UgOP0d0w7tRUC7Bre1$-a>@3kzsvDA-dvRD54H@tO?yURf9?>_2FKrcb5Wj;nQ>G4=jH5j_@|&*dL-StkwVRd~v^387wtBuT^L$(LjH0}k^-g;^=VWcuUt4v0Y;VmT z$8b@ehnsnJ`p_J6duDE~wKe^3+FKsW(m2=qnm#ng{Oz7E9NopfC4Iu0J~aDmuT2j2 zntn6;X}p>J)mqP7`*zQ3jt*zvm_BVyADaEQ*CrQzO~0A_H{M*7=U>m`stl0y$!q%1 z?7zJ>Ir(e)&FsJN=At}L+**3}*`7JxUz_J9>`%X${WsoRl;^YStziG{8SeeH8$Chn zzwu_CkNeXP=6&aRx95_)>tlcV&Ahg8#vA+7ho*gAXZzDXhMR}I zbH*gKO@D2!@BQgF^V-H4kL^z%n)W%C+n@e1+&tHvGiIx8`fJNKnsM4P`>J?I8MDp4 zYQN*RjLr5tep~co@?MS87uGhL_S*6hZ?b>457+jzyM2vazvW}~c+y_`gncje)BJ|@ zd1?3avVXrT*za&J*LSk_wVURTtKVzQ@%Vd%7k_Kmb6_vmZ@Txj8Gr6iznT3suJes{ z&(-ZVhkV!m^r3A3-(2Tp+WTuOhlK6DUf9O#g?6ts*lTbv*EO~GwHbe|={IvcjWdQ^ z(+{TIz5=!n*~`@@q`kkka*EjA{)%nvuV}Zwg6#wMa`kC@Ut76VY;S+dHukr)+uy?W z;d{CIIov<2|-wJKurlIXv3=T%2=qq@T_Hoh!l4 z(Rgj+ny=CBTo2Azrd^N4HK${r&h_AVy^r*pIsV2q-=y8SD(oC~FV~zj?ftd&92T~B zzRWfm>!lCP`#RT#orCY?np5w6Z9SKV?K4(QADUyxST%iU_MdTX`q1#~!=oqc<wxEXIokcGxHOHuudU~H@!I*jeQRw_y@htQ8dwcyFPA2h z_S`FXGT#W#b8V;HuZwfPj$XumGEYh$n(t?x%R6m6P@H>uZPQ2ncAkmmicA+&Ac{qO}X?y+SL-_wq{X!V~weH($CKQ^w*YtSYy9$ zY0I-ei+)J^?5m;;vVS$hy`1r6ZIiKLy>@en`M<+nd6ls|>XhZmhrVy$d5^j>{6n|B z{qm}FFApE~%I7REy!|(pY;)YLHp`#g=#y~%&3~sof6sQ|ye_W~XMfpmIPa79Ywf#j z`%T#W!0sRRePNFW_BhwP*5ikdxa!lcKi{v~cjs}ybNkIaK6vhDGvBZFznSj`=im8$ zaQ>d{JkB+*4`+Y#{W$)-&k^f9fS&ztwD@4@{n*~b0Dd7pgFw0k_T$2roT_o?6I zw)Z%7bE~&Jnr-Aww#oN;tG9dsp6$!rrZd~S4g7zzpR{k94K*=NR@f z=i59^w%>C+dyjeJ@zj3uUd44h*`{-C(_hOr{|}#w?fZ8a_PW@#?|;*N7tV{EuQ|^4 zJ8~Z7d`)}%-8t_(A2yypIZx((uCnI+!tK1O?K!q~9@hS8_kH1ZKG$*PJg?)2=XLRN zuZy(jdZ#_d<#mzImFuwf&-t4DUELNHM}nJxvC$i?U%M6 z*!{!#{=6>gcxd-Hb6wQ&!=4+Pw72u*|8l;04zQnoKIFUi+Sz>d4WFftI{w3dx$lT; zd}gcY!}Y!^7?T0 zm;HwGzIi{}H`PA3Uu*lhpSAWg_rKQu=f7*c@BI5($1`8I)^X1Lt#$nKeb!gJ@U{o# zy=>ov-F^+bAK3lFzAx5WE^&<@1*_lZ#{S%_H)mG|LP_`K5qZocfr?v ziF|M^Lu=GKCkUd*zIBW1G|6N_Z`{Zub0Dj=Sym-Oc&#@4nm4 zhuwCb?6&h~H|M+O)vnjqI^TEK>kDq@XSUDvMSI>S=Y6(s=Xu^Y*B9;Wy2x?n`l3DO zwddhH9v!L6=fiG0Pj=h+vzzn6^J=%9Z~R`KhiR|#Gu!9- z;@H~xoc-teqP?B}Ii6f!9RGY>t}nPhe*o`27F@O)if56}H= z=6>OMZ-4oGziMBqJ?~T7=Y48Fd7s*U{;l`T-|Kktx;oD6uZ}{Q+u z+Bfq!YWo}?Jol6LgXjL&`F?Qz&3}75^SEyf=XLY_;OuX{AIG2fSs(k{WBgovk72hT zZ9lO4hkakzcQ7tzHp-pN7(ZRzW)vWb@`p2J{PWQ zA=}*b@I%JypYUPYJrB3reEw)Hvk@A)3# zx{ks*mK;;KuBmX2J)a?*>ub&p4r=Y2wms~AVE4af8{Zf9cwmncuIn+|`?+YZYcuWn zO!GCg*L9k9zcm%vCq#& zd-|tb%dLHB+r#b$cK;*W_`a~m1ACmX#}E6tU_USH_W=9-!1MRoo)h!E{61;-dxq^- z;e4jLj^2I9N7tXb-mxd-IA3?KkFJkB{JAHFzw6kKu7|((Kj7nU^0D=6SGvh=+F$dP zkFDol`~L7N|Lu%*T>k0s?XP*}y6+o*1%GYl%=Okcd;xsBhn%?{_cJeoul}qv*WbMU zOW;Rb<`e5(KJ!}mZGU<8dYLm$fM2xl-1W@2zYYH3%_r9%c+7j?$KU!>>o;EWe)uQe zd*1r=hn)hy{rfLi_y77?@S(3if4%=lJ__IBmgld(aN4Qxad*0Kz569E&F^^rAs4Ry zb<=Oqex++)xZd)WUxe>-&IRjFzUnjZo1cEcddDYy3Vz(>FI<1)PTOSc6e+GWd=Ppd1g7s%V@C)!4o_4|d+jlwyKIShzwSMR~?gc;SD(9`Q zI_#eC=bm}q`pQe(1OBBe{KNX@qqpq`J^9@Ad!M)ESAO~I^=o(DzV?6Yd}6)e;fJ#Q zcRc6J^|IH#FMPkRoUuOo-VcD^eexOWExzx8@O@u=#`?DNw*0e?Ib%KQtq-F8x32lI z^>)AWaQJ!uc>4OOH#`PD`e{e9Iqv$m#2GkKIrE%l_!}_2E}I3BK8fKf3za;#M z?>>9I%@1z*geRW8KJpfqp#7;IIeUHjL;s7{KIZ9XuFpSj``YjSjd-_@H z;YV-z@XLODz5kDF`FH=|W9wyJyxr%e{@3a26>hWT&?IKG92e`Kkx(Vzy8~0 z;TPZN{pf-gm3(i_pB$MbuIY!U-X{!8aKEueEwBVUO#lN>%(Wh?d0|D z_q`$fdmle}eezqjyz_;V*N0!}Mzmk~yWYEg>OosR>ss$y|Mzls$ zbMUeMa_V}6Q*I7l;eH=pUvQ5@;4hu`;q_A2x;1>{gHK%_^$$DnZQgat`kK%GBK*O- zeQ15cTYmw*>RBIJzxP?Uh2QsUA6S3&v3G?3=}RA2UvaH1-{>hHT)*_3U#9(#OPsR) z*2nJvKje|8toy(6OYkqA^}h8pkJ@hk*w$NAN(y<>g$9k+b$p>JDX`p7L`c!RgC zzx%{3-{s41U9bFSTfW6R-nt%o?3O?Nqkq4C<&U@feD<;X*Q=hleXo;lxvtBrw#ReO zf9|d?IsMKY|KI-OiR&%zeK+`Wmp*ZQ$3gdmFFfpo^}P@H75INW|M>M<_qY%I%_|+h zKH;~24Zh1s$E`ne!u{c+Uwhno+wXiZe9tqFTYvRe9tuD9=Z{}+@uv@i|K)DSujhYm z%ddXW@#|IY^l;k$=C_YupY`f3Kj?NRthZkuN&C}pbK-iF=RFEO`k}k)FWl@g@OA!Z zvp)LnzYYK4Th{gDJ3bzMkHzw7>s^{p&%WcnbW!pW0pTbLJnxXMARN{pWL@4qx%5oAuS7 z{6qLJo^t$pmmmFO_|iXg!g|>EZ}~=VIbnU?XP-g)qYgQ7y~iuJ{JgiFxE^zdE#LC8 z$E{DkV9Q^9%5m!#FS~v16)t)F`uS^ZdEffx^>4m&yUnv7`giLMe|~#BPrB@z);B+A zdp!64A8%Zr@%ioX>^t%G>pT8n%a^?5>(E<%YXgiSFYziZu?$uyvZxpC*5^>4FB^Vk6CvP+aBAG zpZxOmK1Xej`BPtd*?Q=6kL0r-@r9SJZ@u7|@Mo|0()EuIeHQ$+XCA#Cf5D%^XWaPc zb@yq{hJXL6N3Spb@#nzL{+XlKeINOs@NXP^^!h88eJ=d++Z?@K`{%ZN@Ewm{AN?C! ze(vcAqh5X#{2z~b+4|V)JP*FY175z~``4ZipMAe$*84p31@Kdk zICeekZ(a!B?JLKwU%%>$;SZm7?0V!;FM_Z2ieuLYUwg~Hb-iQPADYi-%>C}lPdaw} zr$=r1*6%oWJ?i|I(Ej;?-<&E+x%NN+vYXl9Al0Zp8L*wg!7(x?{JPK#}v*n=2*k|toh90e5QQ1 z@R9Sg<}-)$-Q+t8=R3=H7tVK??=+n6INxWQroLk|XYdPn_IR|qthI4M_91Z83&AA)Sxtw!4 zoO3+qdN}8Pu7Pl_iCi1uTr0U|!nuZWEroM!6^mo z^V0W)(}$%m3#V^O9~Vxan!YuhzA$}aIDKUL%5eJT^wHt;sp(t8>1)&HhSLY9FAk?~ zP9GgkAD_NHoW4ALdN_T2`ucG03As0fbFaufBb<9k?j_;eTXK&H=bn>$PdN9Y+>^q& zN9A4>&b=%5uyF2axwnOLugg6zoO@vIh2h*AbB_$?o|$`RIQP=rQ^UE(=3X1ly*KyZ zaPG;uH-~et&OJMvdwA~U;oRGEj}PabpL>5eV}Xnb!WkoEtPsxFA!CSe#uOP_gfrI2 zm?NAqNX8=Jj7>5|31`fbu}e5(nT%<|8T(`m6wVkbW2tb)J{bdrGbYN|D4ela#$@4) zp)!^VXKa-*Rybp>jJ?7ci)Bm}&R8#FzHr8F8N-D$rpwqaoUvral;Mm4GZqYIY?v`( zIAhX`O~V;WW=t7oj5)`e;fy^q1`TISnz3m(W7~{z!x_V7EE~?)He=i{W8pa_4rh#< zv2r+L=ZvAl8B=F$9nM%gWA1Rq;2DdDGd9l{J)ALn#_r*a&RijLhH&N(nM;H-x5ykLoHtnbU?dht6C&oVhP^;K`X2XKtMK%*D@|bMkQJ(3wkzGq=thJDfRp=HB7V z#WN=lXHK8FeK>RX%;CeC(`RlUjs_4dARKKV8bLUkL9~N#w1j91;b;ue8p6>YqCteC zNkp3nN2`ct5srotEh8LlBN|6Inn$#caI}zUBH?Hx(MrP6PNJcNqp3t&2}f&*<`Rwu z6D=kjZ6+E`IGRngn{c$8Xgc9&Jkff>(SD)I+9BnBYQ#hJa zw5M>isAy8*XjIXv!qKjxVTGf0Me_j@A{;D;y0hT39&RTQs{m z)WXr&qP2yiy+wlyN85|W7mijJ%`O}bFIrwW+F>-ra5TSYf8l6>(FDWMAfrWwqa8*= z3`bLpwiu4q7|k&p4Ki9}I9g^j&2Ti!XqVw=nb9=E(LSSrhNFo_8x2P*jb<8-h8it3 z9BnlkYdD%~wAb))Q;Urz8;(XBtu`F(HX3d?nr^h+aJ1fNzTs%V(SpO#hNBUOqZvm# z4o6FlrYzs0cy4oWZ8KkcaJ_c!b6@RqzSq8buXzmn>KNv+?W<#($GoqOd486C^;za; z+*hA*e)fI!+2?n%ufCJ{UG1yyYJP|N>N}j@?Y{bM=WnsEevA2=?yKK){ucY{x0t`t zzWR;kxv|u_F@Mv2^_$M$dSCt4^BmY$=fFHS_SLyD&%LG2y?HJzbuP_wY^if>p4&^E z+w+`U>YSYC>Qd+GyhfI~M&`M_)VV#+`K8YJc`Yn;EzE0VscU3jYfD{g^O{=fnwr{ec)1k;OrZh>KkXDxm2Gy`_iTQ z(%Hu@)yK}hcd5R2_Q^~2$+NFss;{1X_)>lN?Aw>>+h?D@RG&ZZ1xwuv<~?Gmd&InV zEOqag_mrjXDf1q*)IDh4%a*#A&3n*N_n>)iTI$|3?}o7&Qi%V}qr}26K!tYK$?*5~IcvbBr-+j4{U~qsAn2tTJk>GRH8Z#xQei zGiq!z$2_CPJaa5GYAiIzNTbF`bL=!~>@>$zqsCNotTk$^HOFA1#$a=7Hfn4($84j< zY;!C(YAiR$c%#O6bL=;2>^H}RqsD}DtT<|{ILDBq#*lMtIcjV<$DE_aoO3KXYAia( zsH4WHbL={5>^jG^qsFvztUGF~JIBDI#=vuIJZfw_$IPR~%yTR~qA#bfo@4J(WA8bJ zA2o)bWA9O8?>QzPH71{Pfl+gTIffrKhM!~mQDgf#<{#0Qv;R347&RA|bB$4RjX8H1 zHFubEicxclIhPqVmzi^rQFD+vHyJfInRB91bD}wy88w%gbDU9goH_RyHTRiwqEU0A zIky@$x0-XPQFEv{w;DCKnsc#HbFn!`8#PCpbGK1*w>hU9HK&_%y-{<$IR_jy2b^=m zQFFsNXB;(WoO8)hbICc!95u(BbI(z8&p9U@H7A{O)lqZRIforJhn;iVQFGfl=N&cY zopa$)bKyBh9yLdvbLUZW=Q*byHK(3)?NM{>IR_s#2cL8EQFHS-XCF0ZpL6+9bNM;P zA2r9HbN^9u|EUR#(gdbfFiI55OjM6Tq<}gZgm|DarEn;dQqco7I zU5wH$rlv7U)0kSvD6L~^Afq&psj-aGSf*w&N;8>S$|x;mYB-}boT=qco+d9gWhCrlvGXQ<@soC=F_AQ=_!0 zsacKEtfrPVO3RuW*C>r^YG0$Yuc?WR(!{1#HcBg-8rmogZE95bC#rq(w~>zf+jC=GCGgQK*;sTq#a45yYjN=uv?<0y@BYLBC| z$Eit<(j=!=IZCUX8s;bsb84HTw9Tn`j?z4*7CK4`of_#VjdW_KqqNhhwT{wSr)E1! zvpw>t7mdfn@+j?h>dK?E<*5~q(u${s zJfbhBpPc(1rCraqQJVAIc9a%9k8zX+KKDIJyPoekO4FXlGD_>7$2dv@pPzMF7sL$wH7n4p;2oz^V%AI`3(t)=cNUZq!=pya$e2W1aWL zQERXBo;hkwcHT=zt<}zZ?5H)|dG8&ywma|1qt<-qy?WGI@VtkQS|gtK_EBrc^PWFy zO?i$5My)l^F~X=d=s9*6wKhG+6rlM8ns40$3COh*5{aL)SCMoi;Y_ApJS*|YxHw$HEQjCj=4sy>Cds)sI~q% z)*DqzFvo7AY6Iq&ZdA>{97~R>RhVPIQ8fm0Y&fd+V2(*g)jZ6xRl!yMa=s-2i)*ikhSb8I`Rc4Cf&N7Y))G4iMyj5&55Rhu!#)T3%P=2&}F zEyo;#kE-#QWAjn9A9Kt;swQNP6^Y3 z_kuZR8dZ}s=Tf6;b>n zeU7TFoto&Vn%k+Bj;h6-8tSMT-KnjPs@!_OEsl|@y%Q*+8Mmwqocxtz!YJ;by zJE~@QYQ3XsiKhlUqA%yQQyU&tdptGcQ8md^OCD9LEZ-vAyUoGvwXpl#mv-L^_84G~ z4fdE}KMU+NMzH6`lH>O`rQP2e_8fpcH(<{_ zUhBC8dyc`L+py;(?70eijliDUu;)DNwE%mKz+P*x*A(ov277J7UbC>*GVC=Dd+o#a z39x+yY###Kx4`x}uzeA19|hZY!S-peeI0Bc2-`Qp_L;DKDQq7L+xNou$*_GjY#$EW zx5M`Nu=fJkdj#yg1NNQ*dk@-fv%QzW-h*K8O|bVw*n1i5Jr4HX2YXM1z30N-Lt*c& z@YI!aPlvr1!``D|#|9(kzxQ<5dp+zJ0CsG^YaL_I?pOkLi~&0)fgP*Bj$vTOHn3wJ z*s&1o7zuXl1UsgJ9c#gk!C=Q`uwypZu^j9e4|ePaJ0^r3E5eQ;VaJxRV@}wyDC`&& zcI*l}riC5r!j6Gq$HuT@X4tVb?ARN23=cc@h8>f`&IMq{@UUZh*fBrsTmW{i0Xuhq zom0ThWnkwZuyYgGIT7q!26m1EJNJQ|6T!}{VCPV>Lwz?g=|5g`KOy&S7Eawy<+v*tsz592s`*3_GWWoomC+!C~j-uyc0U zxjgI~A9n5!s|mnr1+W?dtmXi#UBGG%uv!GH1_G;Hz-k(>S_iBK0;{pWY9_E+3ao|$ ztG&Q#GO$_@tcC-t?Z9e2uv!qTrUa`U!D>pd8WgNH1*=)XYFXRuw;C6$_64hn!D?l& z8XBy&2CKQjYH_d{9jtZ-tLedNeXtrJtTqU%8NzCbuo@$*_6Vyw#SZ zf?XSeT{D7RV}f0)f?Z>RU3-FE^MYNgf?dOcUE6|P^MYMdgIyzoT|0wavx8l0gI$Az zUHgMwvx8mBgI(i;UHgMwLxf!`gk3{~U2}w8i-cXHgk8IYUDJeJ>x5kcg`T~mf#YldBehFzP6U9*N=%Z6R! zhF$xHT@#00D~DZMhh3wGU0a7;bBA5)hh3wGUAu=}(}!K_hpi=mtqp*!8Gx--fUPlr ztv!IPd4R1|fURMGt!;p4L5Gf~^^Ytqp^%8H24cgRMP-tx1EeRfDZzgRO0Yt$Bm3 zg@dh;gRPx|t*L{pwS%p}gRRYjt=WUE<%6y9gRT98tqFv!6@;xJgsm-vtvQ6PMTD(U zgsokKt!adfgsqK)t)+ym$%L(?gsriJt?h)Z$%L)dgstI(t?h)Z9fhq0g{={V ztxbikDTS>yg{^UgtxbikS%s}-g{^Ugt(AqXiG{6|g{`fHt+|D*#f7cWg{|F%t?7lW z^@XhghOG^Ttr>=`C5EjrhOIq@tx1NbuAExs;?ywLHmPlft$Bu{RYzY&o88t(!`4p2 z)>OmRTEo%Eqc7*R)@H-jY{S-a!`67i)_%j*gu~X5!`7n1){w*2mc!Px!`7n1)~LhQ zuEW-}!`95h*1*Ho#>3X+!`9Nn*4V?=_QTfX!`AA<*6_pD_QQGvV7&ma9syWS0j$>m z)`I}+O@Q?*zAJr1zm2Ut%8tXBfoLjmipfc0F!Su2aaoO3{r2CR1j*3$v&^?>z& zz)Csf>KvcY=XV7+g!o;X;q9IS^9)>{Ybxr6oM!Fu#yy?d~pK3K0GtOpR*GYIQFg!K%< zdI@1YjIiEAI5i{Dm-9XARfP30ZnxihBw;;|uwF=54<@X464p}*>*a*?V8VJcVLh9$ zUQSp~D6IDr))NZrA%*pp!g@|&y{NDrRaoyTtfv*$>k8|Eh4se5dS+q0w6GpqSnn;Y zCl}VM3+v&9_4dMgeqp`9upVJp?=Y;V7}jeH>p_O~Cc}D`VZF?-9%oqZGptt{)^iQ( zm4@|D!+N)2J=d^aY*>#roZ7nR%Q+`gyBB>qtk)aX0}kswhxLrZddXou>~LxWqc3Nl zdeULN>aZSmST8)R=N;Ay59^(W_0+?9?O{Fmu-<%F&pxb|AJ*d!>-~q#1c1#7fXxtq z%@%;o9DvOtfXyg?%`Sk=G=R-IfXzUF%|?LDOn}W&fX!Hd&0c`bWPr_TfKy`|eL262 z*$%Lo53m^#uvruEk=u+2IJLdem$M%;D`2xGU^6ISvnk-z6h~jqYg4lveK~B#1#I>O zoSNw9%h|@P3^+B;(U;Sn+Un@b;nYN@HaeVI>FCSh)KEuX4yU#{`f@lm+R>N8sl|@I z98Qh)kyBp|r=~mlayYf#(U-%i0gt{MPHlMf<#1}oqc4Y3OCEhWoEr1!%i+|XM_&%7 zCO!IcIJN50m&2)HkG>pEZF}_PaBAM8FNaeLAALET8u{qU;ndDYUk<0HKKgPvwf51M z!>PfKz8p?%e)Q#VYWAZqhf~WReL0*O|LDu%)c!|b4#yJ^eK~9v4IB?a^yRe2TM&IY z9M3`YWwzgD-N5lKL|;yOJP^^B!|^UeUk=C95PdluFGcj_a6Ayvm&5T!L|+caGZB3` z94|%m<#46*J_iC0mmB@ zeL3y%3`JiK$4eA_IUJ8s^yP58N70wV@gzlG4$n2^aRIUEmG^yP3oThW)p@qR^L4#%?MPClba~6F$94}h*<#0T3(U-&Vu0>xC z$I}*lIUFxt^yP3oaM72;X0O5V%tc>Ld%Sefm&5VoMPClbdl!8<98X^K<**rXaJ+rd zm(w24U-ad0ynxY{!|@14Uk=AR7=1Y$Phs@saJ+`mm&5TOMqducn;3mL9M59(<#4== z(U-&VI7VL%$NLz4IUG-9^yP58lF^sL@lZxz4$m5x$8GSkJ@qk8O4#yiBeK{P@X!PZ9yrj{W!||9#Uk=B68htq&uWIz= za6GTkm&5U@Mqduc!y0{=_H8yJ^+@r&Mqf_*tXWDf2HV6V8+|$L@y`EJh;)9!}0z`Uk>Bho!;GWyu8tu!|@PDUk=Cn8+|z(PjK|*aJ<6Nm&5T8M_&%d ziyVD99M5s|<#4>n(U;kNn~e#_(;R&{?eRKCUk=9u9ep_*Z*=tKa6Hq|m&5T=M_&%d zV;y}t9Pf4X<#0UN(U-&VYDZrV$HN_cIUH|y^yP3o-_e)D@q$NR4#y)NeK{QOc=Y9P zJmt}s!||F&Uk=BE9(_3+Z+i6Qa6IeLm&5V0M_&%d;~srE9PfMd<#0Ul(U-&V%12)g z$3q`|IUH|&^yP3o_tBTb@#sfi4#(>seK{PDe)Q#Vy!+9Y!^sSYz8sF%Kl*Yw8356j z!^sASz8p?wK=kEsG6|wDhm$c7eL0-$f#}QOWFACc4kxQ1`f@lK2GN(p$xevA98Tsz z^yP4}5TY-KlaUa8Ih^c-=*!_`FhpMtCu<@4ayS_b(U-%?Y>2)bPL@OTm&3`Nh`t<77De>sa55^QFNc#|5q&vqW-_(M z$-0QXoc5_DCl`ZS<;S1&*JQ%aXG-ke_--#A|Mi)}HsO8OI%<6OnP-=a z=aKAwdH-X_XMXKY@ceho|Ayz^$J`E{uUqEp;kmzM?iWs8^?bi--&A|vr?$`g)PC|l zwg3EE@0-8Z@#J-NoY`L;f8Hn09`bXgeerW;d)WO9KUek-`@XQp1ACls-Y4HzUORKs zkIDBK_Vd>E`5s`uA2{!m@6q?o_X*GA$@dKBb#($xHEB zUT~$K9*3Uy2k@PK;`-ys4`1PT-RpbC)ein5oPYD*dEfj!+lBMGygr=$WxwJ4UU@&; zH`PA3-_-VVKbzXm-2bNbKmT3pedpiTI-dEuwT^S{Z>{5>?=yd|r(HkqW&0-V_OSbb z-9PO6uG!w>fjv%mzE6%H&ht3(etxce-r7Fj1MK$$`@O;We0jgTHlI81=W*uyhv)wC zyTFyxKA$5n%yQ4O81j6KdLGB94ED5F?s~Yg*29&r9favEx1PsQ-y7TbeZqdvu-`vi8T;8!dq&3a*%^GUJPX2SPw*@bpGm>9 zIDA$G&*JbI7Cei?XIt(w8ELO)Wbi(V0W%&&a6bq`f^OW8_&J`5xQnh39eQ z_-a3VkJ)B^F22X`d|&?C>=REdV@Yiqosr86A@4_#A&bjMd9{*49%kJ`t^>H6!oIig2iD#^T{vFrL zxOcqw>K|Eu=rra><2P?`%KF^vGZz~VeD%re8$bI1wz>PO-oF0jb(mj|TitM7A9N_1 z!1%)(yk$M=-Dof4gRgnr`U7Vi#rD@c>Dcv?Pen%>Z+hU1*K5D?m9*dZMSrp0`7hr9 zKjJZevMygZ4u1OQp0a-JwEgfKulK0+-+uO;@K@e*-}MvU_dfX1pZJCKl*3t<8P|UJ zPp`MwVSR1<@>73sJ@5BF&NeT(>1Efi{N&l&*Iw?`X^P_*T z`L}nR58wI@2W`%~)`jqoe(hPir=Gp#dtY)rc;BTzP5YzI`saO@{qt@6nOD5W@}%iW z%lGz;Kfqu9@RyeVJmnntX%GFL@gu)+7JRKgyy1B45g&t} zbki}O`H!c~{{Iu>CDyf1_>t_P2xmP2svP+JwDkVXtM_YaI64hwT$!`wG}T1h#L1?Q>xJBG^6( zw(o-N(_s5L*gg=pZ-nhLVf#|fG5c89z8AJnhV834pWA$7w0X*C^Ow=)HKWaUMwmPIx3lb>Z@e(sk@TNryfftpE@m>eCoGk@~P{R z$*0~+CZ9SmnSAQQWb&ySlgX!^OeUW?Gnstq&t&qcOOwf`UQH&SIyRYn>f2=Use6;j zryfowpE^02eCp?9@~Nwjrni&Hrw&ghpZYwReCqaO@=-57&%LJqlgZ~g0-1d3|77yH zEk(w~xsE_4pX&=`@=@15_utkd$mDaqgG@fxFUaI`U4u+M*Hg&ka~*_CKG#Rc zekW zkxV|5m*D=ZDbKR3nKG#pleh#mP|g^Ps!wSU6o8e*IP$h zhb5EGbzU<0T(>2Y&-Gj~`CLaPlh5^EGWlE=CX>(gXfpX+M<$cc^<^^oTz4ju&-G|B z`CQi~lh5^QGWlHBCX+8dtK1jb`Z$?;7c&Sr0%apLGIc@>xGXCZBZ$Wb#>WKqjAc2xRhEpFk#`bqi$jS%~tCZBZ?Wb#=rK_;Jd6lC&QUqL3Hbr)pvS&u;`pLH5!@>#z@CZF{lWb#=z zLMGpl+j@`D>Ojckv;KrkKI=xvS*Vt8*ihFaGMZx4Jtr`Qpb;d#j@(lP~`5w70rD zGWo3Q8?8={OuqQTvwf=@B$F?G^0c=)Kr;E_Z%=!x8zhr2e)Y7sIzuw~;%`rTt79aS zFMjy6w>m~L`Qocjd#i^elP^B}w72?6GWp`$PkXDkB$F>b|FpOIOfvbB3y}6!&q*d< zas<-e>OaZkOYT70TfHcme90+Dd#f)clP|djX>awYWb!2kA?>Yxl}x_mCZxU9yOPP5 zoQ1Tv`dBjglFN|xR!>VNUveDM-s*43TOum`Tm-bc%P9|USN7CNv#>wPMUP;

=VbCF_axi2dUZ1Sl9Q75R^Lu0UvgE_-s<7WhClgXF7m~7MP{K@1?zD(MiFMv$Gq&d_S&+$>oS?KfUj~_c$pcDz z^NEnjM}E+3Z@v#Q`I60-?VC@8Oupn3rM>w|$mC0&QQDhtg-pKWAEmwdR>v-xm$mC1TRN9+A zh)llZQl-85iOA&BXGA7n@~yH>^CgkVmprVrHy;z3e96yBd-FY!$(OvXv^Sp=nS9CT zN_+EFk;#`lue3KG7MXm>|4MuFbCJoH+_AJbKi6nJFEaU(UzTl}FN{pSy=$mC1@TH2d$j!eGfwWYoJ?8xLx z9$ea+FON*VwRNAoR` z$(OvmY}0&>Wb!4OFYU?X(-%o5pMJ@3`6#nZp83M|&3Bo7=9w?FH=kyXA0=b0~T-~6*VH}cFE+M91T=Te^eLVNS)=G@LRUubWB-khs><_qo3Uz~G0 z&wQc1`Gs>WIHp1wEFe4)Mh+0$3&nJ=_A|9krOJoAP2=9kaCAkTcEz4_~N@5nP> zXm5V}+=KGW7us76K<+_#<_qo3*PnZ0p7}z1%K^weF3)_Sz2yevo|tF8(BAS2au3Zj zUubW+1Z48nJ-y`^dvxVw^JSZsBatyu^kv#x?nK5^(U)m&ITaa$MPH^p zx^lAlIJWIGU*PD<$>vLY%g4yrFZwd=El(q3#puhlxBQKaEu$~f-tsy!7LC44d&~F8 z*fshx?a`H!&6i_nIUyMXM_;DB<%(p?9DSMgmP3-Ucl2f2TmDJL-qDw7Z+Rw}3q)V0 zz2%=|Y#)7@_Li5Dxj^*g?e^PezQECylg*doZ+R@4%S2zMz2&!LZW4W&_UOvV=F4lN zD<_*T-11>E_ldqtd&`r_+$#Dq?a`H!&6n4I%frcBFZ%L! zKig-%z|obH&6oYRyq(M?qc79m@_91%jJ`~J%k#-xHTp8`E&nHT+vv-*x4fXtg`+Ri z-tvVqcaFYHd&?urTs!(Q?Jd73bMxrSw70yY%;lpm)86utGWU-3H zebJX`Z~1A_2BR<2-tyL>B}QMSz2&n-dyKwJd&_f+RvCSn_Llz^Z8Q2Z?JX}ZT4?lT z+M_Ecn=jX3bme68g`+Dcn=jn*?xM9uU#30&!qQ-)D<_*T+qb;CXt~jsX>a*>(SD;Z z)82CVq7_G9roH9wvG3BZTV5aAmKNRe1KD?J*DVi_V=1k>JI|JVUVyz`zTLETD~H`ZLJ-&JVwriT5D+ejhs8RHqr7PIoE0} zqvb<#Zr0jI%ai0>uC*OuPNtm#Bw<~wXTnOOshzD#?| z)y$ev^kv#xK4;ddqA%0l@;S5i6n&ZYmKU0}s_4tKxBSnnZAD+Ez2${wO)dH|?JZw4 zYiH4yX>WO_S!;{FOnb{O&Dvk|W!lrHrf<#p({fPhgKLei<)+fd*BWBWS*4G!HN@!3 zwdUAzT(d?QeVO-axvyE%jJ`~J%ZbezX!K>;Tdr)@OrtN;-g0QO#u|N@_Lf_lHQDIP zwC7%0Yqc%^mV0ll?Y6vJ?$xyx-12p~x7XTnbmdx8ZaKYKgJ!Id@3!UoX3aYKGRM<$ zfV0LOeVO)_8=N)q=*zUXoMFa3wYJ{!jkC7S7%1=C@`@RY)mnecH)d>AYxgY=nXy={ z^|u^m#%@&`(DIfUOIEEy%V%b6ShWW&FPgEW-pSN3L|^7Jwp{4cJValnz2#1)Mk4w$ z?JajYwHDErX>a+}sm+MKOnb|_PAvyx?tE7*ADgjx)qb=*ZN~CdE7J0}8T(glNz3bI zu28ioE#I5DMb)mfJaFbBRqGO6xoTiqt~hg=s+nmyeaoT<63-8cJ2a8Bx91n6HV+LY?d^F7spUg+Nqclz+M_kFdK+M{La zolI?Q^kv$kiRzt9EpGH>+M}WBolNa+^kv$kx$2!vt#9;Y+N06xolI?T^kv%H^Hx$z z9DSMgXu#2e^ZoeDm-r=9lZ0IiyYB^i46w%rd(5z(1@<$- zes$wDbj=`SW zu;(P~xe9xYz@FQ%=REAS0DFzVUTd(|6zsJIdu_sAv#{4P>@^O1?Zfs7uzdw=9|GIA z!1g(?eGzOQ1>1MQ_Gz$v9c&*6+c(1YnXr8+Y#$5T_rmtcuzfXb9}e5M!}j^G_X5~^ z1nj*7_MQU!%$Myp|NZ>3x(Ctjy$SZ72zxJsy~n}c`(W>hu=iZpdnoL^751JEdoPB) zN5hT{)|~(CIc}+2uIIa6$9qYo5fnmqSuw!PpJwFj$Ikg@6jU2WXz#{k~NoM8|NT!dmbgaa%ygJ%wlolC;bG2!;S(bO&1b4Y8h z$~Mkn;r2Y!)GgO@PSKT9YnAWEIWp|r8Fo$$JJ*JtgTv0vVdw0yb9vY~KJ45dRuh2L z3Scz^xIJgKvtY!kMrNC-9u-Xf( zCIhPl!D=|L+77Jd1FHqWYD%!$5v-;Jx91L{E2s7`pI6NaR?FIMzty;4pZNl-iNWpp z$f;Yd=O&l7#x`nhaC`o8>Xz%d%%$D2jhY_Zp6{Hx<$CUOX@hK|W(c?EN2hMNo-1A2 zBipD+!tMFgsavk+R+qNPHfo-5bmggq!fK?j&wPQ~^R-jAT+it)t(9%mVBz+>@6;{V zbGl2*Wg9hK*k``LYRhnYK6vVu>$%~nTc$QTzqOh(+p9&xYT#SmYS*xuHmueStAWF6 z>9CqPtd z9I$I2uxlc)YbCI2D6nfQuxl=`Yca5EG_Y$ouxmQ7Ydx@QK(K2=uxm!JYfP|fRj_MJ zuxn4SYhJKxRj_MVuxneeYhJKxYOrf$uxn?qYj&_}ZLn)_uxo#?Yj&_}d9Z7Iuxo#? zYlyIGg|KUguxpO6Ymu;Pl(1`;uxpyIYn`xbps;JBuxqBUYpJkntgvgZuxqlgYqhXz zxUg%xuxq}sYr(K<#IS3}uxrY&Yt680(6DRMaCGHl^QC`qEgN=?8+Pp*c1;|1tsHi3 z9d?Z#c5NMY%^h~FA9jr%cI_T^O&@lxANH9qu(biOH3P7<3a~W>u(b!UH4m`03a~W{ zu(b`aH4m`06Rg9a4Haxn6l|>&Y>gIdZ53?I6>O~+ zY>gId?G|iJ7i_H;Y|R*KZ5V9L7;KFhZ0#9rO&V;i8f*<4Y;7BC%^Pej9BhpoZ0#Iu zO&x5l9c&FAY;7KF%^qwmA8d^uZ0#RxO(1NoAZ!gGY;7TI%^_?pB5aK!Z0#a!O(Sfr zBWw*MY;7cLEhTJCCTuMwY>g#sZ6|C^CTy)HYz-%DZ6|E)C~Pe#Y>g;vZ7OU{DQvAN zY>g{yZ7OWdDr_w)Y>g{ytt@O!ENrbTY;7%U%`I##E^Li1Z0#;=O)qS%FKi7kY;7=X z%`j{&F>H-7Z0#{@O)_k)a&eydQro1q8TOek@Z4vf`2x@P+D$G-?wi(5!`4*8^O$$1 zz6@J~4bRWGJN0GQnr(P~C%aQ$hOP02=Xba}^<~(aaCrU}yHj6=two3DZ?QY|W!Tzs zc%B=ZsV~FUqQmpI-ktg~Z0$Nc&yC%wFT>W%!}DC)Onn))HXinwFR-=ru+MyfedY`7 zGhbk9^k)wU0>F9%;CXFsroIg8HGt=}yqWqktTzFk*ZyYe%dlPsc=i>W zsV~ENAK=-yY^J^p>y?0g<_oO10`{3N@a)s_%okXX2JACmU_BkM&wPRPfWSWU1=ceH z&pvsRT#THPdQ4!S`2y=nfqmu+tcL~mnJ=)O7uaXMzJk3;e&?d(&|3 zlCnw@0R=^EWl}^$ARz&n5gN`Ljzw2HP;e3Ac9D>;!vg&BttTYwvadg0uCMbde{0`=iqns$-x;}m;v`>tPQ`;pZXY_y*B({zqmkR^PICL=2|MSD zuzmN0*WOrht0`+=Kgri#T5+zC+hU6)zjPeHbNQdw9jyMsA-( z$=9A=@wk!OhjFjJ&-o&3pGV>Kn?muv(YFt#ymq%`&T;cVb zcdqkgVa}D8t(EZljjZ_f=-cO4^7Wfq@$Qk^M_BUp8(i`6k=v(O^7Wft@$`|~2U+s< z8(;DFk=tik@^vPlc>T!j<1G0)Lr{Ewe63lLCVvB+`jOVud^fNbwF-kc*)lp)LiGw!uF{bUT0Ry zCxO0w@FiboT*^Oz+&=q~uQM^_t3Ylaf63Pwn(|v9cT51u*O{C0VIX%50m;`Ho$_ZO zcgz9F*O{L3Z6J4y0?F4Ipz?DdcT5Ax*O{U6c_4QT1j*MKqw;?scgzII*O{d9g&=o~ z1nLH(6$952Q%m-n|h!9?9w#ui1{yJ-&2s_4wuyei$JLikAbG`^W=Zmm&z6d+# zi?DOP2s`JCuyei$JLiiq&&0FQPM(!#20Q1Auyei$)0a7`cg`2do%2Q5IbVdG^F`P> zUxc0WMc6rCgq`z6*g0Q>o%2Q5IbVdG^F`P>Uxc0WMc6rCgq`z6*g0Q>o%2Q5IbVdG z^F`P>UxXcVM%X!Dgq`z6c-;Y!^F`P(ZT9;6oG-%8`6BF`FT&3GBJ7+m!p`|3?3^#c z&iNwjoG-%8`69gT)X4cF?3^#c&iNwjoG-%8`6BF`FT&3GBFvh~+RB`9&KF_ld=Yle z7h&go5q8cOVds1iUU!a@Zv&jp`6BF`FT&3GBJ7+m!p`|3?3^#c&iNwjoG-%bE|r`w z!p`|3?3^#c&iNwDw={RPd}I06(oW}m5$2oBw;8!}z6h^7VsgF+JLiiq-+aFP=sV|& zuyei$JLiiq=gRARS=c#Wgq`z6*g0Q>o%2Q5IbVdG^F`P>Uxc0WMc6rCgq`z6*g0Q> zo%2Q5IbVdG^F?^s5|Hyn*g0Q>o%2Q5IbVdG^F`P>Uxc0WMc6Ucgq`z6*g0Q>o%2Q5 zG2eup^F`P>Uxc0WMR?g@kn=^@IbVdG^F`P(=!Bi~Mc6rCgq`z6*g0Q>o%2Q5IbVdG z^F`P>Uxc0WMc6rCgq`z6*g0Q>IalVl3iHZ2Uxc0WMc6rCgq`z6c-h{N^F`P>Uxc0W zMc6rCgq`z6*g0Q>o%2O_*$7R3%h4X^d=Yle7h&go5q8d(y?h^=QT9mucH}oCJp87N z%@V&g`OS&kIbVbw`%(Ii=>28jx8z7Z)<*IQ?FxD3iDf> z-{i<0>r&V;ErlKHa<9LSjVbJynZk~xDeM@V!j8Qu?3kRwj@2pb7@oqMVQ`i~dmQsq z*s(x`9V1lOu|tI&Q&iZoMui=NRG2du&SKzSwtwV&5q2z7;bkjG&KF_FJ{9Kdhch6` zI##MMXGNSDA$M$5Va}E~V?yp&tiqf{aVCY_v0H^XyW$KBxnsZzJC>}lW55bKHmvZn z?Ih=muw%&zFI!D=z6d+^tnjk!BT!kjg7=7_#y^9pm8$(bf{$MO~CER!=$qsSdYSeP?Z z&Qg&(=CCkluAIFhcZ_0T&S*KSMedl!!j5$;%vmpIzUXiU%vmtlF_UF`%$YH9F_1gP zvTT(r=gUFm7CES#BL|g>QIIER3i@00 zE5{1_-7qLoSc-3%g!n zw@29R6n6WCo%1E~Lurk z+RWe4<5{T3xlw38IbZTz~;#f{ld=q5;-|vqMzJ1 z=^x46Z^G`+v?sZB(*KfsT!iVvn_l(?^Dejk%K1;9_~60S?|(hvAHUoEcVGRB*ATwx zWzXGx;1gFA{={|9-@W#?E+xGF9qa!$%C5hUr6;_~ja6QF@r}iMh|a16n zqCPPFxAHfgQF1-6^*7|^5jMZD>z#X^b7_yT+bQh!3;*zW|7Cl`lYdWT7v6mme`sSY z;jzxn7#-se?LMi~SUksdhWU{9&DB9pGwQQEYYX~WThc$$alZ-keAGu-_p`A3UzmQPK6H+b^(V)%=E>6el)1F4 zvck!!ggm)>z{%+YUb%;q>j#`1K;YyC0O-C! zMquYuk~}$&kS7-sc$Fikl5~M}sNG=qn{?ct!tQ5b_rI{mMeTpqh0o77WjyTO=Zrgk^Y>^R-~X0p zj(>jbdxg(?(38irEZ2^rO?_bcgZjXWkA4(hYr?fW=V$V8Egj};=KQQV zKWom}%AP3ZXX%sY_7Fd0`p0%+!nP9=E}av_3oU(}m*5Kx zzirioZL211dp7WiVvUymw7r~oY%eEldpY6KiLIULvJIZFZS#a}vnPDIIHko&ZeDEv z(AW8mW0ub1(RmNP<>*wsv*M=0b1L>};UoN2m;BmY@Bgw`sa@}S#shraX>-L^rTqu^ z#v@<-mRPJj@2wr*m3~OmkiCyK>d`ploiXq~p_RK2$66fPab7{K3twe7TVTuWbh zo-_Y#Qz}l|lnSr;d|;gu#egk+&La~WR=K9}?Wf;t*DBmPwuzP8HnGCCxjnA07!Sk+ z;CV}5F&l^rfV|7vUROM}*A=$CuCVQOh1VLmBc=dtE}n}O!?rmqZY^iPiDx@2&Mjxg zX~QV_Y2)9P4(HH`d8^#x#4O-hDn@SCb)wk0UAE%laz>tbxyp-9yaVd0_`1rw?%34b z24Yt4EWgO{c&n^(xf3gadMh@sa=#N>0eR`4D3-77*eR>HDa2L)+wNVsWA>K5a@P}c zfqF|{x$Di-Iwy+vTXk`lk~qM#;sbM+lDNUGqxdnzbfEngCsuIRTQP*W7upd6g6FN6 z!?R)$b1#$_#j|1;&yGJ_cs74wVz%!Rv;BWnyyD{I4sA!g37)0m8_$Y+JS!gZtT@TD z+S5EIiih0wR-EKn@sp>0Nz}H|A%6ZY@$*j?OS$xC#aN!DKZ~bzP85f^IV(Q1@&P&* zz^r)Avvn#~^Q;)ovtm29KKToF$zM?Vkv;xaaHK&ixaQA>#aE6v*LSW zlY-Bq+EeksXVp8aJ+otg7oN>u_|panWb#oG2E0>CcLhJ}Y)Q_Ew3henh9@ zrO%3^J}bU@>ytZ4@p0(S(pRj?ggMC(P_E|C8yA2mBmV0wn{PtOK z-Lat~pQzrQ(kJIs3OD>;H3H`YJms7X7Rk^|NBvcN1H_#|=fOMg~8{8@4GXYsU-;^q?Dh`KIL%>1smV(DWKJBWp}_-Do5#~xO(laN=v z*u#<|R{9->zwm7S!o*cld?lX6u^{wZ7bk9ian6e8kL_^c{LhO2KPxZ5ta`B>P9A~g zIZD?h@lyb0ZgiDy?QTq6WC`K6LSo*VaRkY5D@>4Wt<*k^N&tg`di}~ruTTz^|@>$Hvb1^Ib#jLy- zv+`xk%A+wm7e?VD{8iVdC3i;GTRAmm<=U8)gJV{1j#)W7X65pj#Y4VeazE=kb-LUf zr9UfY$1MF>Jgsx0ydKTz7-CuvD-X!5{2=&&U8I~Kr9UfI$gCV9vvP|Z(QynkwdZl4 z%qKD{&q(W^DE~;8t=uBBa*oW(MKUW#$*kNZ-G;=4(>Rv?iE^4WXXP=OmEUAm-ji;_ zDEVpgp_I;aTs!q=9~T&+i;@XE>-qKd0t8%pHzHPRd3~mnT~lVdFhbnogC!q2lDg$ zOF3dnAHP`QE{do0@rw;l>zpXROmmV`i1mo?SLLIbj{PWk=aDHq9e+|fg-7Wmb|pHA zX({Yjm%=B>J5!waIulD%^^&8>d1~-=CO^95#gDHuu{0$oN0am5G|!3h+H}2+`6a9FS)3JypFa1&S z#3B}F@f^`PNsgrAB#uRLC(X*KL>!CcT528T?&J3}{d~IoO3hh$mx!g2d`z?QG|kdE zQEsNvC!R-gHqFZAL_Ck=c$$t=tu_}Xriji~80*5HmYhvpZ{>0#K1y;tO~>EX9H^X7 zle~`36*V1yTRO#aqMT5rPaK!zikg)}ia0LGE!8^8T}j+e#{G2pq?)txOc6^a`KM;( zrJAL4qFhv^Pn;W_X)<<|yNY-=$!T>&r}9-13nzK3X63hP{ls|J^OpXRyjNY;ao{yB zmFsGfU(`9Uh|@DTN2bl>FXapxTs()^zN8)#VuY!lkdX zcFxlo-_qB)IOpTYyR75qi>GpOO~>b#y!20$!>h|yey&-0yNJD%d|s2BvCi{FY$x53 z(4WPlI}`3jXn*OSC@)xZRxU8&MI}ertlVMUhU7I+y``^wx!m8-o+^8y{9>g~?5pG* zo0X4@*jLF@);h}f%e@!%o-Q|8b5_o>S^BeboXyfnZV2(8F0WbXPv@9GpBP}eF9egj znEO9)=PxTf$)C*qB|3$Z3qx&ijtpV$X1SwX`pVVJ9W9s~&fL+0PnYkk>vhf!^ogma zJ7#e4%*v-mOtsWIt39)LbdSw_Hf=avKDE*(_FM9-&C)0KTk^8C&WUodHD~2$o8--Q z?zUMu-H1`A9NVq)8%n1{ps8*>ci5X#dAcba=j5hFFD|d&nH_7`oB13TY;Sf zZ7cocd6B%!I(LlPQ+eWu?U(#e^FIv>!EajBel6Z<3VkdRl7yji*Px(ydAr(Sbb9=%!l^`>(k zsXe7nT#NtLe0;5QlH7cyKPzY7tXzJxcv|N~dHtHR^8L-q12`)`;4GaJAY0x zx5^%2PUnnM ze-`J7@-24R%B46f$KtHqi?ebv&dSx;Z5SoL$T=LV?5wvWomqJyXXT5Wl}B<`e#u#RC%X+7D<5TZRu0NpxhZGmtn4<7 zlAku0W$T%~?FNbWW5{v-D@>*_@Ss zb5>r?iH{L}N9>&nM}8}w-EwepcPhTkN%CV>KFvG}Wzz=X;%S}a6;)mC6JhtEu%A~v zB~KqpUO755UMhQ%yqwMHxgk!^0pa4wT$Q|Xch1V`nK>+-;>>%5e3X9Xw&Z?aRJQVa z=AD(i@`2_Zm)!6EM*kO2)(zwrIj?AQRxZ(5IYzS{s@~GidZ>C!KWmrdUf)!<@{nfj zmE3ExaOr2A7tiVPnReOARhn;#I4ig5temI$rW|iWzH6$t^ph7@^3&x=_4iJkl^1nZ zzSMkkrBnLD-&XOLesUR0-a04AwOabqdjr*5xmmL}ki2w~i&^!0Pa^C+jBx2^FC?DQ z&)!DzE_;$3ucbe|Hxp0ggw5Ve^3q98YUIgPEqqb)!xm@u$*RlyOySBin|-O|m6taA zSjju*Y~dsP-VdXneBZ(+$t~+Wzv}XD0pZF;JBug3FT{V6ytK{f-!kH_Jhu5QBYEj0 zAG+!~T~6E5&+k6*lzx7TN$%fk!j<=S`nROy{>^w?Kfha%pEiGPm#y5m`Hd{j%B4H~ zn_BY9y_?_8s;lJ5FE4rV4F3j~yz0$weDPNv-kcRk?lT18uB+tZboqQsCubVssocIf z(>PvN&Q*|)($86k`rZ{yvF3CP+ki9%I9^e%V&VXr^|6% z`Z;?Pf9dBeQSytLAG!2%b}Am9c?wsa<<`l$E;>2y6~3ssm3;=Qx_l-qT)CKY-Ya?W z=X_Z5%JrPHYvi4~Ip^Neue!!X&C6W+Ija|^&)9`4zjN#4jzDcYT~248=ZmLuJ?D-< z^2!aJ`v`HKBp-Bh`tC!Vl|MRnACk9@?_4CWT++FtIj*03BILQF5iXwA$=#E9D&KVO zswDRvmay-ngnh3B&b^p$>5r4-vu@7HVLdCi_4FOw@iycxPxY4mkzCkaw(?(-w*;RV zarzEXxb$<6DgM&W-J;}OwsK_W&QzS0Q+rmf?cAA4r+9L2EB?|yQEqPE!-})=anH)r zojYRbl>RtLUhmd9NsjN*&t19dt(@Sw`{ z>*C}kFV5J3s4m-42;06wxbmLI9z*hKPi#ey%P(j7 z(n!ZP9>?*xs5#9`KejRAtQ_dEb&=fmFyPqa2%jz=dg;fuM?9q;TOG+SYA*HCk6n{^ zY*Qp$IoXfsRKE3DdDvr@rLwkP0>>^(xb$NybzFy>Im(^0%EksvoR!0!+&hCDJm}a4 zOxSi=;w*V=y(BN5*oH}7^~OF;oVH;TuDtNEd6T^BvhAEWOMetkZ17aJa>tYNXOR1c z=d#V7aC4S?l>R85*axbtZ3~4f?|f_*C9gd7u~C$~>#_|b^4KB@+eT5i_+!&3d6kV# zCUSBR4RR5IZNn*C`lIBd^oMOb#os!%5tZCFqQbT*J+2?yROGQK6)v9E8Mbj1k8NCq zZ4)b8blX8y5g~ouCQ%-g`2bFvFR0m@x*>uWo?HnY&&FO+aU|v4q4cC z$ilX57VdgWK1)CL%;?YJkNvac)t=aCi{EzI(rNy}!#3g4w@tXPZNi0ZLoQtUu|-E7 z8*<^|X`Nx4cJbJzUD!78!c|x7?ZsL8vv^u(*d|{*w#gT^4Zm>J6+Z&;m;NlCBRcj$ zkiLBrgzd8++;x?lJWa|?wfbrlPkbd**1i?O_PG$YFNUyvG=%NDA>4J9e3bquo>Bbq z(SRpDBjU7=iLiZ7gzaM@+;x?Fl>R85_`ImBePo2~J0onL8sX+F`6&JP&Y&M(9+kB( zkFb4$gzYONY#*XMzWg&858kIX&w2XtoKkn_9+v#51Me*6<;=S zmj1MFn&e&9K5^o)Pn@uQ=!8o@zIfs({rJ{N-ev9gCm#F#3ES^a*nWS)_WKjIFQIU8 z#?KLX`~-!ICw_&JSH1B=l-$0M;8FMpf48A@icVf$_i7f<}Yk;k`MxOn1=EqT@3W#eNme*2ya+b3PP+7N$sah5*&arW7gcUk+q zi^sn6!uF9DF8%oFi>LI-2a0cu0Aa@p5Oxd!VaFB_E}q03K+f-~v3}ooa7SZd<1#oga{W;;)+OK^(GF9V&I^Y*f_$D$)mE4$s_ETJi?CQBV784BZNFLe1wbVh>l|r zNyo8?gdMX;xa%spd~wLpxauNrH9j`NrIXl7;&IF+VaH+;c8n%r$9EDgp2T!QE?*q- zK7xy96#sBcC+Re&V@8SJF{6YXlS;Vs6VFOKrJvYSl6P6hyb_ONX9+t-mT>7OPM3H} zKe4kUKT`I;9t?6xGQN%pChS;Y!j2&(?AT($#gn*X$mNSe4oh(HkUyRK49OjHOt?86 z(+v4^Y&2oVRTD0Ka=YU{Bc9SvY&6MR$1&L?cT6^6$8bBYpIC6n6T?locv@#Trkr>j zQ%=}1=!C1T#Ih4-=_fXwiN|sOgdO)! z*m3`a9rsVzu>^&SGjR@)Cr+Sn@g%OGj`6_B4-tch-Hj>T*m=VaLD}uJ$CBrZ`JK zu`wlgOiq<`Oip3P

%cPvO!}98u(n;VE1^M|2#6R634LD(sl0!d+L%< z5-U|@9a~k{F;|5hi&fY$T7@0ERk-Ua`6zw)`jC5-HWYtiv`SuO6Ju8Vjy)^vn6$#B zpLn+7DgEJCwUT#P$GjDfW8Mlormk@5Cr+<;N`Dkj>m>HCcpMX0*s+3z9Ya{yv4w@J z4T(#Pe3ZU?eU`nEu@wCoxOl;Ke6=1;~4nD#nU>8;V&M1gO-nwuw(cOS6$>B-Yt7vah85! z`%C`2_r23@*#rwa2Z8YOFL8$*xrgZ==O8$)pF9Z2N9m8^X`SR&5YNAR*Ej9RPYl0v zF$g-eS`px;I-?{mYoX51mxhI63lR~)kN6AO&kK$>a z$h3#1W5k;s`s3j&SKG7ms*K ze-=;c4Cnn3kMsTre{7%kN7#9Pgq`)6PTkfAfsR zlRQw8SG~y_C3*3XFX@o{;?(7wR>Esc50_t)aOo%CmUv2E`N_@GI^;__B*!`Y&dDXb z<|KK+gsU#*cI3>-!_3LzX&v$<9g=4qe&-YuUhm*x-qYqRIr)+f{ciHEg-1EwU6wWB zkX-NdvvaEnuQlOt`7a3XOtOpQY7zb4_*=i3oE zYku_k7KEpD_-1X(he|x_8?@zHw!T^0@`E~F7vIgu`DR6*Z&`R+XRdGSwtT3>v%am{ z@^KPg-_|YP?v*cTTRu^euW$6W{Fj8gu9EXDjy~V$@bK*pKi~A!%l_dM=h|az*^{h2 z#NbehIrO* z`7OWY*KhVM=K#%Fa(=T%pWpJ~A-__}&UJ>cEnhGA$;Y%UUoYWx=CCb)E#cDV+#_<% z9HLJ?rtq{5`Ixrlb0wa2#&7I9|(~kZu zp4K527csfSv(Dl1xe{LI@WkX2Ug!V#XbG=#cw%x1ud{u8u7tbZl9TT#`kd#7hjae$ z&#ISufwYHv3Vgl9UzmJPskbq)%}(jBdzN|67rjYk*S*QS$^G_t-OJ1y-)E24y~%vU zGxm7h zia2h<>rM*4GU3wa{wwlX`s8~GPwSBHi8yrPS$A#tmJ>hkSNQ}SZb&;DXa`HVzpS!~F9MM^Kl*A2$hkQ?S`J@T2J57Aj zgo~4V)yTQij6QJ(!_zwCd%`D8JnQb2IEljR?iHUj;dS>qbLYG6aEX&BdDm6)QTp8B zhKIY|@N?&zdbxu>#kuaF=kiGt|GLY@CvD$`JA6GpX~Lz?{dnZuSx0{qPwSBHiMW>H z!53}$myleyJ@<|h3wgLF02`?K1 zeA0xwu99O*5PfV6!h`KW__0Yyy~H=g-waOjG2!baylgOtb1J-SHt-D-E`9PbMNU4Z z=wr(fp4K5gE52UhS#e&8(<;2|Oz;gmUKhEXBA=x{i>GzS_k^#Pc$TdTab|^=O$)wZ z$Lqp2CUR_AqK~ahcv^=Tx^wwxiD%jK;JYQf>~QAt=@MS{Kg7}%UUoRd(iL8|J@|$R zcfBPi-&6Fl=Lrw_p2Cm)PwK@kDDA;c37;|X7bf3R>TOI+;#2y|&T9Vs&%at_m)+F- z=g-^YWtTN?|7)+3eA!LSXP>*r%Z_W_@lW@7*HfE>zmyH=dX{u}4su6!#c-f@k!zNt%*uO=NO zSvHDu`L@A>ts}l|!po)+-!|dm#5OW=Y#O6azNhfC&Rn*a__m2>*)A66JEB#bNRLjFB@Zg+k}e;JLkwp>0@IYo>BbRB&XgkJC}_#zHQ>ir)~MF z2`?LLeA|w7&vBgZB@`s8~G zPwQaQPW}e*EE{!v)r6N#JN{|M>zXAe-&6Flbq`PLj4%B9ADzo5O*~Iuc=@&oFB^XR z(~j4L4S(db^k?z34!Jev@+A|`vh&BsOnCVb;Cm*#?ELXb6JEJB@KqCDz5{dll?ivf zCC4uy`s9-e4}JvUC!bX6#qS{P!4Cr8Ht`oGpH%8?Og^bo`pb`FKIpHXqq55{WB%1O z_IUYy%#S_(*^)26jQPhm-s9ybG9PjIJzl;ZbNRe|O1&k=k0bizlL`-hAK@pTRO-b~ zB<;b6RP@q_|yq6pBMb-gi9a)n#l2ai9Y$H!qYnBpTT!dJj(}%yfVVe zX9qvJ<8|Tt6FELR(I=l&cv@#HpCf$d#It;e$crPqe2(y=J6;#LpCTupRP^yh3eORp zzxjF7io{_elK9cZ_^U z!ppa7E}uH#2hkQ!m$EPgycG`*CZW zz>FLH4rVSePGH8(`lICdNJbyu$?zP}VSX`h77xCknm1tPGIJMPoSMs)Yko1$XhZR| z4*8oj@8RLSVcvsz7kT%vBUwawLwZE{w_8sPFox%QyeGfeBo7ne& z*^9AHI#!qVVwP)vWPRBb7b|6nGJY81%_r#`P zU(ddry7;ZYKK@u6h;b1)u_>Z2Upn)&j($(@y8<45m+-p+%x@rmw;ZdB7#)!lTO<1N zr85t)M<&0WD9i6Tey4%?oyYGqFuxu7T?a1xQF3CHL|?vZ<~gFn?@@kdE}p^fRDNfI z`R&VZU2t*gx3A^;J!*aZPBl;Kkk?7Sli}faHoud>{C4NJ`mwt7+ud^gp0>VzXY+e| z>9-Dfo%A~&9?l8)oe$=Gf^z|I)unR<%XJ=LeVr3(!Zx+oLlc&U)bIoXPkI zf48A@24_^9JyDjkE6$$4oN00P1m>)ZvnMcTV4OXHIalL63tXH!SF>DaRMywom3efg zWqzG?xn7-txjoH8{wbZ)Q5WZYoYR3hJLIhJSbKDKXt~bwtgmxE&ij^r>yUp+=Zx@h zPRThVn6ppLI>A+!&OR;Ixu*4XuE}{N{9TswRL)7^;hdFoQZVPQoU4LMU+1!x>pa!^ zI%hS{5gmNmmT#Nt#n)~5$O&_1%o#E5>AFfjN?*Ql<{{SEsj{3ybG{4@=hK`ogE_b6 zd>PDnHs{M=&d52Z1{V);+ae#OKZ=J~YT+mURO;=rI*(6`IL_%gXQwXC{yFPE)&}Cy zMNW*k=#zhHnx}PiKfpZ!Jlr#IPXOjlgL{QzbrEMTa$?*?e{e5h9^(5=?m{Tb{S5am zVD4?WcL8%3#61nT^yQ0Y`6zv235Ms04);sCH(K+GdnfLV7U$qDi@Pgu*Hv=eFIivr zPUg{lSITlf#=RFj+?#Rl1?Db}ySHO?=`POlS^By+Gf(S~?@9M|@NnYm(k-8oxdci`sH9kuy&ckOz0r|tGM4|%C{?@nFZ z+jH*@#uk9P|6}cuEr8{^=eNG@?YX~S`mIA=D%lOdgWUmk17K_!uuA|}U9wZKTy_f9 zmz@Ik2k>`U>?5#yfCsw?>>j|_Two^wE`8Z(ST6er>&tG!JV$h}@4#+@da?V!ZUc;s z33egiuB+t4@{K+*e#0|LM|LRKqrih53U)2v*DO01>`}njzhI97#-;|l7I5(pKRNPI z`lEP8@e}KKy5253vERWi2Y&2&u*(5sD}-&(u{MyGDso~qN1qtZ;b|RWO;7BK;E`R@ zvMT~(1BKnvvAT#^9r-AIVo-;NSlkoaDavBcg`E}{J1^|Cz}Svq*99(p@<2sCN}rhC z;W?s%JsNgqi-(xxvNHo?`-WW_xH!r26gjcSqfZ{F@U#wjpkyZp4|aCg$$_!m!&dKD zUBqCIoY?8nCl6G3T8BJPvh#xnJ3;LHz}P2Z7kI2L@<2sS?Dy!C2P!%+`cxLg>s&`gURDz>MT#da0jQ!qBI*q(y1b;b4+j14Tdr(o=Av1bK$y(K5kfAq;$6&~^egr9s> zsh50JX%9ILPVr;Ui=8fYVdsmTE*RTkY=w`thx`kXlM^BOyWQXcE<2vr;MF3 z7~5xTosZQ;{)ouQ=@5PLRfVT@$X6vhX?U=+#!ecH?KZaB$Lg9TCnrVp$yXJgBRbfF zW9Pki$X7M7^9Ey+j$JsoILYe~IXN|=KZ>Vy$Q6PQn|QE)$9^47?BcOs2V*af{W=&M zeC*)CU02D;R~7wHJmeM$|EPLLl_h7&#Eu_+`~a}y2jg3SFTt@kke?;;QTn5JT8Er3 z_^^owKL-2|;KXMFzlCFUjgph|CHkXy$cZ!YwV*8i9QbvB@e9GP1B|~2ejwn|CqGo= zyRHxel_smmxEso z7+)X!aE{eQE~Ln3>66RjD^RYD4S0-dj`F^$NS*1LUq(*!2qgS%ix-{f0d46fT}Tm*iD% z`hhky&+r(jE{~D0=ZSE&Cv!vmrJu2uyvuryiN|wH*z;Vt^fR}`Q~H^!l6P6ZBjWKp zBJ6icxb*X0i>LJSu1Q{HvnELHcU;(O!g2kqEy%Mb2z#v%_8PTgEWAbudyNwIIw@TG zSsRgOO%pDj*2$VI9-%w$HbA_u7`R1?|vo94cp6p{KuX?lZmE8MqaDEF&UiEfet&`soD(l|` z!v0+#?B4~#{#_vK-x|WzhWxHUp5GC|#gpG1l2^U?og#Vj`!^Kw{1y}T?>OPo&u=&J z_&1ku@w85UGm6K*0fqfLRJiKOZ%=WSett_z-evt8Ry_U;iet9E6Lfb#i7R z9-n~-`+P>Y>dM)RI7>fgDUx?tpY4dpXFG%W>9ZYSpX~_yj7Ye6at4JwXF7xuk? zuyf<6`c6tbzN-@Uos@9t=Uz-arJuVh$*XMc)Fk&E znXvEFj_c=c4teg>gnid0>^nY{^&OwE@A!m$&nR5_xm!e@J3-;%X&w0<5yz7`<2y=W z-=7LsUAY?-XX)pzQ}QnByI1k}?p4@#ufo2274{vjaPj1h7=YbLTGXyL;g-YnuV_*p@)p zHUq+?AKL@*lzwapB=54ec@U3nA%ty%Azb>goe)py#}-2JE^E6E@z~x&*mfYowhs}u z-H5PlKZJ`jb}7hX*CAXyu>+C3>W$rq*eV1_6727RwmVRupB=54e8556f$%Jh)CS3ZnXR& zjO`rq*t`iBPi*j1);4&;_!2D}JYm}b3fpE69NRzP(vL0QaUJ;*5tpAigKrRV`N6ht z6t22ryC|O0k1e9)UDmdd;<0U{ux%rSZ5t_U8%yEhi47<6*is4?Pi!wGuX?+ze1MjX zsQ7IoDr}ol;c7$dTE$uVu{D*v%El&Ea@)!Z+y3^rer#)z$0kBR$!%K>j;*`oRd3hTIiS=-MG+pb>N_V&WI z!xy$Ky>PW5cKgUWv+~<7*&!m$grX zc(vNS2cuGIM5|VdW`*euMJ{rRI=@2gc_?3vK^yBLxd6kV%isbe&5w=gt zasBwVAdgRquzgj8?IWYI_K^{`kBqQ=YJ^KazB$O_QzKkFts|cs@@z3@?BgSB|0Ch5 zE51eIEdBTjN#14cyCfd_E(zOrN!Y$id%X9z5-y(jSRs$ElW_6GH%juVx68)oOZ@iX z61LBmuzkM7Q}XzHN&dLK@7Sm4*auB=`=ANi5AL{reBY4AXHB?xT8I2u_yUQ?K6JwN z;}fpB;=3o#(vL5m5erf_k_uM>IvB87`5ew30|z45!0+J<{PBmCyxJ50T=Cn7SJ*zh!uBH;?s`iepI>z13oKkZ z)L?b{rDnsw=Ta z#98`@B_es3bqo{nIEIO^W1a|?eqyJHr}PsGMe;7|I4$CFoEBlnX%Tju7GcL}5q3No z;o?kO8sv%VB3wL)10#9Wo47HOJB|&Q+*_RWNM7}JU9CfYF3z4*)^T-&9al%#adm_p zS4Y^fdW5^)k|z!iI*HFCT>OdWBYCwa@rA_i7(~L3K_u)rNWxuj$rG~(oy0N{E}h{R zO5$-0C1J;L5-$D3ZW2%FCl-_BUDh$6#N!xH!j2gwT>A2PTIaLkDgDHflH9SagdN*T z*s-mI9otISv8{w1BTKk=5`znQVqpmvPhw|DUiEfa`3$XdcJVvLm$2iE30E5uTTGm# zpIBj%cUi|M6OUt*2|K2laOo#Dns`b-vCbqvQg$D!O+1dhChXX2!j8Qr>=)P46K+n&phGTSsCDlm?3i`JrB8k??u5kSn03O%b4156^rYh$dcuz5 zCtRF~-G@9e_k@e5b;!?!FOzs215ns;2!*Sz#2yr9=_i(;c_9H&v(aTm33TAVaL@Jc3e$i$JG>etWM#sx8#Y#iH>}#)}6F) z@h6_AB~oI*;|OG^b<=~@+vDIre(JwxntN0J4Wtt{lv~io|w17 zj)g1SWgVMWJdW`z?AW}*j?F9V7{9{BlNiFt6U$e)coO?p@~XGX%7neF-O{0?-)WXG|nAMV3*~Huyzhh_%JLa}<>66=w*xlkO{lwyyymcG{Tyn<% z7k13>JI=hY?&b+YW;R_dM;_4$$TzcW+NgR90tKP)D zm)vpq!Q}QLCcorWZ`aj2!+8Nz)_DPhofkmZc>#o-7eLs#286rbk|&P|2}T>QyL zAbGVX`4PnL916nDp&;x$4#Hh;$&+&do#bK=E}h{V5aMwT2w~@;5H9`Xo)AyzCzpie zUDi1)#N!+m!p@^1T>A3aTK3uEDgETaki5#uH*48>OYR&T!p_-oTtB%#kSAw{uyc6` zcUk8a5s!0=2s^ikuyczDJ4cCd@gxTd^5h~BE}rBrk-X~dvhvMZcKqUZjum0&c@eHQ zjFKlOi};!p8mPBc9Svt{KVucO3C8md%jl#H&~~K*Ifd zv-FSr-Yk8^$uLi1ukG8g;>@kP5MkoatveWD;?k|V6Jg@jtveXuy0;p2uap>T=qS#d z^%Z~4Jc>(ae#N(Qy@?$pe&VE(+n#YJ-YPlo!Ng%*XKlj7NnK}l!etk6#Ll7Qisx#5 z#alIx;;@=u@myVRVqb`#IN#)2rVYgZCI>T^xZvxzpD^*l$?=T5?CugP1Nkhu;(S|Q z@xRTZxZvhjd~w$s-)-3{lh=aWpVURZi?t^ZCJzQVN0E~sgB+sZvg?koH}d#s3zz;Z zo>}~}>YeS6LtZ9w(NPz9naEKGzU%q#ndGhmlb4B{cHr_G8pRVILv&{8&*GWIKdau9 zJ*>KfT~^p-gLVWb7obdNcPX&*-@->^Us#xh?EDFWm87Do#t@5p*(Fg^MS1Tk@*+Nc=9p%c{%o zxUk=SVXq0o9Z#&{fMpFqC-1Uw@#Ni?yz0%`C4R4U!d?S~y*3IHo0I!v`m^IzR-DPK zvFK#26E2>tjgnWrS;NKeHC))=0%5QD!u}S36~_qsQE=%iW)k+J$k+a1hY!`lqcD4k z9ll=Zti8m}dAQh1?3{5ujMS}{l9FU)Uk#R`Fc{nl2z67c%Xt~e&((&4v! zLIe@#03}zZDPmtC165F8ais3lH(=!au5B{2G+&g?1LkA7La`((+#z zi959X5k}$>Eq{lRI7Q1JVI+Rhii0!~*Qj{#n~0paNzo^sQh1276n^3_rC$8$M&fT2 z#t&{dHVA%j!|^?cvoRds13$Ro_#VXN7>@6OAKY+!kLJN&FLL66M4vbz;URuV_=zi$ zdhsh)o=*C+Fn-g+KJWNn5Bsg-Kd#)LOCSI1VZU|!&4>Ng@xLDA5JjhW@Mn)4Kk?|} z{~jLv#KVujeCi$MIiQ_|@kyus@>Ms#{JzaEY<|k7{lexKE}qn@y4)V&;z|4A&vOZT ze0RtT6AOj;fIQoUgo`Kdm*iD1u_al5BriO@Mj^-kob^Q5>xr<}6Jf6> z!d_2=izn+0@~l6?#gp|)@~W4Z#;oU(7oJ}8kz-fM`Yi1AS=j5du-9i{ug}88lXV+; z)^p+F$@(vO)jRynlDsf>L3{_1=Nl*NZ<%oE12-~p3)!Q7fD_?`zY~vFC^@}kg)exDqHgG zog{zOh0hKCe(igO&wJ35$FnXxb0UAlIgc72 ze$SnS*S}-^zwr9|SbD;%9OZ=gDfg59QKM_|ksr zdC=uAb+(@i`OeRUzOZ?Qp9_9r*DLJy2)mua)I)z!_Cc3_%-QrK*v}h%^&@ikkL1)t zKe}G}Q+Tz9einBBtDV%7_V;)N-{sa{xytRw5gdJRc);NYQ$O{B(;jfz38tSY56*Le zJ&uv9AFR(fN}hg0zW5nO$vuw3>3?)qIgJb0-eVfUx7`&roiuXcJ|gl~G;8=QLYu73aPjeq*Y2M?GJ zU;T^M7(afu`)k}k@QEvqn_l)@;n)7wrN$?&d%iIL^8e`bcl5xNqdXWsc)^Sp^;v!x z`O@E_zj(IrEdDM0>))Ar*WYK_v&zl1bMeizf7P?b>oM1&F3S(W*5AP95jMZD>z(Mh zJ;H9M@T!OQ3-f+cANqdY=&L^Ss6Md!O*%Xu^&#iEsSiwlP#>6nqCRksS1@y@JmUynwXB2#t|L&o8%cs`(N$M zI3mw@)%gC~d$)hz^-jufO39wSK<& zb(h=y;tOsh{D0rz61$r|`X<7!ebEOF&VAj@gunf~^A9d{zgq}j|3<%maNa|2C4A2Z z|JK0+9(W-9t3UO|gGb(P2tV)XZ#a16PuzOk@g0}kz)$>e*R6p z{5|cVT-pg=+D|>}T|Udtg?#7dLSNWC!sZuty~EE%dxYIiVd|m3&{^}~Z2A%G=Z!x7 zAng7TcE1U)dg;%!hkh2OT-r%JX@8H`r+aQ({Z-c+|KqzZJb3t;dk0Uv{`lReeCU9= zcZW;gV0_#2{^o$WclZZ49M8DfhYy&05BcnyjQ{Oh|Nelv_uyZ=*?7{W|KZ>(*4(?t zxwjavx#lHy%)PfwWx6(i8$Z?J6|%+ecj8%`H`z$ZCvVpuN3DSUw`#+-a}s_ z&MRH&(&K{1pD)hm{L-bzcRcs);=IvYK6BjpC*CQ}^KWsP@sammAkJ5Q@Ur90zx`fu zp7ZygGhTkHzYyn@zvc7B-LLxral!{L&ki5FJUe{w^6c=z%d^7=FV7AiygWO6@Y0_= zH_s0z&&~7i*M}GFc>ewR@RA+Rzh56-w&VHt>%%K|JU^T~H_s0z;{+%3i1`F3^N9HbC-aE;1Sj)|`2;8Pi1`F3^N9Hb zC-aE;1SjhW?*N=&)<-zOtdDSlSs&p9vp&KJW_^Sc%=+kd9#%UKtDT3{&ckZwVYTzH z+PS5jt3S8u&#n4%tNz@oKey`7t@?9If39)gYTUOP_pQc#t8w3I+_xI{E#toC=T`G` ztNFRr{M>4OZZ$u*nx9+d=i;079?g1>X1zzV-lJLX(X97q<~>@^J?nj+^}f$~-)Ft= zv)=bv@B7UAzQ$+Px-@HDnzb&?T9;<6OS9IcnRRK+qgm_cto3u&`Z;U;oV9+=T0dvj z&o$pC^L78e-%xn}zTZfA|GwWuc>liNOnCpk-$Ho*zTZliIq!BJ!nx)) z2CX+$HQ(vaP3?T!wdv0d&NbiZ z&kfEs-|5c{&NbiZPjPzO#kuA?<1WrM-x+stuKCWmi*wC)#$B9izBBIPT=SiA7pLc^ zIM;k&U&i|`PM(|R-;euic;Ch8bxE9z z590(U#pJ*rZi1`F3 z^N9HbC-aE;1SflM<~{uhUhBL#!E2otr}pQMzKJ-&Yn>M-c&+o|WS_Ry`Lt8>9!`Ic z(oVidX(!*Kv{Uom?bN(?JNX`^KlyH^KQ-^&pPKjXPrjS!PrjS!PrjS!PrjSt^!Hty z{=Tc7taCN)eBZ^%I#=V)_g$R+zKhfQ5OI1RB2Mo^^z7b;h|~KJwbT0$ae5yjPQDw= zd-{{_M!iSum+~I5U&?#Lektz}`=z``?3ePsv#-nh&b}`1JNvr4@9gXHzO%2(`_8^D z?>qZCaq=Bz-qTLL!?iB4{}dWKEY64g+Aj>&d45ye_*97q2C1uU;5PXSC9WQ;dAc%`0KlP|AR39^8b|O@92RkM|m)O@Pes_`YhifU;1107tajO;-BGP|IXCA z{yx*5Rc@x8i*Kg=tDg0{>{4e?m*pGS`oiX!$jvY8dWGE{VYgFw)kFJ*IoqT@KNrs% zefmMz{Uhvt6XyA-kFq>B^|_t&zuLL@7#HCluW!8Vb2N7E{fFN?_?lmTuJHAL>vs;e zo1ZOww^#q^!2|x|Il^as=lc&XdH3fDKjNMrKluLZ?9a5Xa^7Wjmw(wF-}{PJ+}+@v zd;Hq>U3HzS?=j~OIbQ|m+!dVjSa8m1!8yML=Uf+@^Iovey>&Li+~7Rga?ZVlbDnIT zf4jd}{pSAP(I*}k;U2F~_uTl%pFC@vb@_Ykn0sIU4bL90`{H}=n0r@y<#WaZu6myx zbMH29eeSr&;dkwrdzU!xta0|2{HGmr?_SS1dt7ky`|g-~Z@>0A;}1W4-`#htx%c@$ z^|Rv!FL;|cAN!%78~6LAw~OaR`IntJXy^A`{UPJq?tXi5 zzU^)g9lyK#7I8lGryf4O=!@?l&a2%05#!1~cSmtP>zzM5zUb|D66bea?os1z7kryI z@A3nW8h`XNcNQmn@X}8B;H91L!Am>ggO_%~2QTe}4_?{{AH1}a=jQqM>%%n%&%a+E z&KNxZeto$1;Q9CK!*vGFzh58D96bMieK>RQ{BSZpj1!!U590(U;{+$;!#KgoJYqh<$vk2{!O1*gKEcU6Vm`siJYqh<$vk2{!O1*gKEcU)!aD#b znDr4(FzX|nVAe-C!K{yPf>|Ho1hYQ6om;hYt9EYH&aK+HRXew8=azP^{@kiRx9ZQW z`g5!P+^Rpf>d!6xxyF6gxX&8*S>rxy+-HsZtZ|kN(yVo9*19xnU7A^!);yZEe$HAyXRV*J*3Vh%=dAT}X8m0AeKKG7@B4Fw_wW1J z!u$9A9O3=@{ygFR`~H04{rkSh%z3wSgLBPy+PT5G<~!}&;9T>ac5Zr)&O3{CZg8&o zPCGX^*LajyAJe~NR>cluMDYrfN;;#~8c{uJk$@ARiQ*LggO_%~2QTe}4_?{{AH1{^K6q)T-*<8H z+&uq&+|S^B7bnln^Y6#~I=t`VyjzDH@N z<~{B7cQgITcQgITcQgITcQgITcQgITcQgITcT?^3_g$Qk|9V ztV`@avo5j!%(}$>GwTxjPpwPr7nt{OvR|n6lYMg5Pxi@KKiMZ|{bZk<^^<+FI4}R0 z*A3SBhhOnV<8Dv=)$z-({%;%jL+^XVc>0SkHNp3J&GW|PAM>@spY_nEjH^82A;Rn5 zvHo9p{T)5wRgUt)i*L7hg{f!N7x@-B^+ca~!b3gb=ik)J-_st-rJeAl{nWF5)12++ zLca5Jp+Edw@Cch<*!2p#J;H9MF!j)1@XQB4SUSYRK*yAYdaTNAAMy`1azxzRQ z_m8mqP1yY@?0y!eKd8^oML(+jm$~fwv`1pxzw>by%$vRG7c@W5x$d9LH{bPY8uuT& z<(uYZF8kfWe|pQ8%tyZMDZ=aDx&B{x{e3Py;Z<&~^1_R6TfD-I*Qzh_UF6gged-Ah z^@N{)Q!jr{dnlK7!k6|_&-0#sn=|}e$hDqWe~;!M5B&wtU2gq~ zGw4UKpEvsSgRuKY*!?EF>ZL!0S9|DZVam~uZa?Fq_V;-GS zUSYRK*zFXi9{LNObuM`Z{RsB+MxTBVrXKnc9rv5?s+ay0=I^K4v+sY&sVD94@ya-2 z1Aoiyz4KQ-u*pZ`qks6G`Oz2cj3N`uNdnzj8kHH-AF%-+93c=a>BPQ-!bcYv;^&{Kzi| zzwA4nIj{DH=L_HX89zO5_cJdRzW?_Sh|E6~cU*^Uy-roKPiYG9xa^9o13xDI?l7H#x4T!^TstC_jSnn(eXU1>dW9mE*iCJZXH@x4v9DuesdMkI&s+Abg)^K4)C- zrHb7;zWg_SY5eW2pDy{s9`e%h1>e5+*SOs)Uo#%~C6AN*jSqS4_Tg@{p`Z-6Jht2u=`NheJkuf7xq{P zdyMw-{n!b6Ooj8kpq-url6!6ld(H@ZE(v>%3487ddrk^_t_ph&3wv%0d(I2{T@dy= zBJ6iZ_`~~mO4#q3u-`#pznj8-XNCPP3;P`x_Pa0aH9^>Gg|OEUVXrO1UUP)K772Te z68739>@`i;Yn`yyKw+;va6l?7K8bQ z@a+Nn8zJm(hp@jX!v59>^R45XM_GTHg!3)7T;F1_zj5Kww-~v|5QxZ*?!f)qTDE$+%x%zty>K#}7@o?vc0DyXLU` z{J56~r(SUC1*cwc>IJ7>aO?-bsTZ7jOU~L7ePQzqf<4_@WsXUB7?zxF)%**%8eXp!?9E&9UdnaIsA z?0SXW9$~jr*zFhY@d~c-#ZDmOE}Z^Ep8f=}_tr@fRz7jaU53kjL)~9Dg)${M5j1=K#C? z!mIzz!e7gB{EUR{7bd)TOKfb)zc$Ja0V zTD#06oIXS+eY@v5<*S%>4&-jX@EW^oQJ>|9v;&;6Hjnxgy!h3p;8m~c17|LQJtx(+ z#i#m^uXLa zSpH3i<@a=0{!oYbIoVI@u>7YEsn>p0$m4H?KK^3twc&|>7X0{&NnZY3v~;#f{le=#!Cx%$_{XImBzOM^yWfP} zpJ@;MEbRUl_P7Z5c)j&@x7Pc;zd0@&@>8vd`f{(rjX#+g5S z%kkn@U1G=Fd(to5e4Oze|9HUM`?ELRWc<#zf9!y{_k@SuX#CaHK61d^yTW5{Fz#`W zzdc~?-QlCx9~WHzuMe1ecX`kC#y>vq!h>~pzy0+!ZZvN6qmK~hXMERJjFkiI0J?o5d{x3gh2j^|Cd9CrmNB!p=oPTlEYmN_I z@&P+IzwY5*KHhq}UlHeRK76%t;eB2u&Y$|etB#L8^5x>Z)dR0Ge){?^73V*_>WjvG zZ~S6$-uW(99zXK57mD+--+iU=4Uaijod5psK5yLW;Dh2k|23Bz|L4R1Qk-A&=+7Rn zeEs{x`RrF;X8g+QmrdSk=T&e1S>x5We3v*c{D(`A8{g<1;{5D0FFkJkrt`%KAH4J@ zeDLz@@WIQo!v`;%@WIQo!v`K)Vy~)HSgU{&3m^~^WN<|OgmS9YTmm)x9ZQW`g5!P+^Rpf z>QBvk+PTJE^B&GM-?tj~t;T(;ao=j(w;J~?G^Z9nd}6lQ*|`7X@- zT=QL+`MKu1F!OWGcVXt|n(xBQCAV{fbG?_e^AOJUUeeA(IM;hgI}hPp?!n_!MtaT_-@pD#C|F75&NaQN9>pK z9qatyzlJm^1idL%lpp0F7G@0y1eh~>+-&{uM;Qx8sqiT$TI`3~2*#Qsy9>=&5#aIX2zJ~`_r`{b;j?31&8vQN(X$v!#jC;McrpX^CE zo8z~J&jy8kW+?2lL}8yX3j6F)*k_W$oW*iB2WQTT!8t1iKmN^oKeZLRW;^fhd%XN% zw+o)R_jgMwZa`12>cSDYWa z%`?Z1Kl&bVKK{wi7=QcM?-u6=U-9(u#+N9r&fycD_q6e4XTD3E_y6vnAD@4xcZl=a zANkqwo^if7-+H?zkH^3H%t1R}{h=p~^X`7;pq+R9<|mB{o_U=?J1_gFpB!KIa>c7T z{FBH2_i?YMoH5kSd;Y|Df(jjzA% zoyGZt|KpM4O*i{CalZBZM~shN`c8vqztpvVXng)t?jX)9UiD$)D(8QTIL~_hL&k01 zdwX%h2QTe}4_?{{AH1{^K6v4T4_?{{AH1{^K6q&-&&~70$#e7k`!)7DgXiC`vDY3v z|9*`;{+$;!#Kgo_%KdzGCqtGoQx0S1SjLe zIKjz0Vm`siJYqh<$vk2{!O1*gKEcU6Vm`siJYqh<$vk2{!O5D;HwI2H-xxT-d}H7Q z^NoQM%r^#3Fy9zB!F*%f&aK+1dGB^=-n*Te_ipD_?cA!JTiUt$bF2Q`sz0~t&#n4% ztNz@oKezPf8u#`4<wTZ~zR$exYkX#{OS9Ic zS?kiQb!pbRG;3X&S(ny4nzeq;T0dv4pR?A_S?lMl^>b$ZT=QLbto!$UkC~rqzDv&h zT=QL+`MKu1@cw;2OL+gjKS!83?{*RsgZWN7iL=3cr=7&aV7}8%;%uM-a^^jpVCFrXVCFrX;I+<+6TH^>w3F{q+R67Q?c{rucJe(+JNX`^oqUhdPQFL! zPrjS!PrjS!PrjS!PrjS!PrjS!PrjS!PrjSt^!Hty{=SQob*{#p@4Glz=W5*fzKhe} zcX4_jB2Mo^#OZyA+Ub3WIK2;1JG~DPr}rV^r6)O*B!Nt}E)>OEq=Bu>5? z^&YWb5+~m`=Dpu{_H}9}-?w_-+1II^eBbJQXJ4mw@_ozu&Ud)hCH9|Lm)L)1U1I;4 zb&36F)+P3zS(n&s6 zFR z=+v{9zU(*BSH&-R`WAWm9GtNLyZzGlGYV%+tv_g=c?R`?7ysaS!0X>Zec<)?L4Dv= zZcraMa}P}aQD4dRyw)Gc%_D4nVb?3X>Y+Wts~*}Z?Dh-yc*P!``G9X6K5}6DvT3aC z<0fq1H(~q43ENjr7#}!%_TaH^o$#vntW}>d&x)No&(+v=t&-c`RoM2-!m*8~Y;5Df zv5lAflYVM**%ixP7CCiNAJ}r)2-%i?7LRajZ4_&u zaci1x+--2{odrF};4m-@4uiYP;DbAjySux0@5sX4-L=sf+z0377rU}1&wG#c-}BDB z_nmtO*6P(Cv7;g)^NWbgs@+vp)Ud#kP#knVx?>*JL zJNMKu*Ur6}jE#Fj`QB6LIr*mV2}K^_o=na|Jv);8kHBDy$J35Se=DTh;%>0D0u1Dys?S0a&+M#4oU|pNQ#XH#cp=X0x?!?15 z-SUOD`eCeV7WzsT$FLmnI`_N5Hhi$$89QSYi&QZ&)^!a#Dt4*Hz;c}%kn6fuf3N-z zSl2k@y2gQZjRWf%2i7$XtZSU*PK^UQwQK?F8aL#)|Ap_%K~4iZb{Oj#hg{b1DiY|H#NVy-oY<&Q|E(IQ=9|HO`ShZ-LV|Gsq;il%- zm-V5m^BK7bThM3QPX0T6faQoq*Ng5U&`0dLzR*w9cL13TIqng2dke5*hvmA@K<@ap zft`35J8?30;%DrPi?K6a#?Cx2cIJn%GjBc}-~IKBoq1;L%s*p?7se_#_d%$WQxTgR+eTk1%^Ts|PclsF1 z)jT7I^!#(rg^tq?S+08s)*an9fOX#h)_nt5_YGj(H-L5DVEMPb0q-sKJyy>A@H{&6 z#`6fQ`v$P?8^F460PDU1Z1SbC(_3)g8TTd49psujV9gz{<_=hM$MSDIpVv6eoijf? zkIuaDJOXR(fHil(nmb_49k9vQjs&y$8q{hzV=Tq-@r>NrxzGgkIU*<}pB%Ab}CEr%bi4?o%t{Am05 zt^MM29S@Gval)RCAAZ!@meCm(2;YY`B@}+T|z&~vhJNg20#|~r1z6Ck_ zW1PTFJdB+<8N)y37dp1a{(Nx#kga%_Fep(a~offi;i7&b+Z5XFeHg9-*Uo1lBwP zEAF}OfLlE{Dyt74&tn(E_efDAfdzS%0-IGXRAt<}`8;`K$56)Vw^aXUtUi}YkFh#V zs^b|ed!+0#24BjbmJ2P1AFU5R+7A3^`}nQ>;&UAjj?;0%o{k@WPFpto2=8duPi}_@X&viUF4)X|o z_|frytFKf%C*SJpTYaHE{vNy<#pCOfz)rtn9o;9Lc(_jjt2nt&0_#2rtj5KC(vXv(FM*wY z%UJhG$Q{2d*L{+Y_4RX>JMlBteG)p(cv-G_gk1MY$3E5<)^X;OvF?-X%juKAx=;G- z_|`Q;{*5o+ddhS7@5fhF-iP@3s-)JtL=Io2)H*npah3uF)%tjnar5SB)w=0tL0|n= zd6Jf~`ka&=V|5&f;iVWWdukt2iLtM~s%p7f$9;16(faVC?ZA(=kKfuaKG*T!I2|YK z>G(0v*oQddf}DUIea4O*#*TgIj0=7lJMl1f;$#dz${%BATw0FtYJJQDV`qLCJM+dE ze(-h>t~FpsPKG{XU2Bj#_9d|6m$CXk;$f_74LZ8kfOV}oa;`OCXCAa2%#XG&F^|x} zZ_FdG^SO?bYYlRT7nYlR>HR-+^!YWgKEDRm=hwi_`Je@?&#!^?`8BXUzXsOl*T5Jf z&U+pCx9cQoPW1UT=0u-g1MBl^V10fKY;xytDj@$>Yra}gbMbFgYYDC-5AEA$*!QYF zLRXf`?c&e{$wRO7_Q~_MP9FN9rw>mrm^}1BHy=*mmppV=XCL;v8W1|Koe$d-5W2R7 z4;NY(5Sp@)59gf}5E@j+hck=~2)+5!U-*yNLpTQLtefJ)ICkw=ABN48BYYUXvJdiM z#1Ol$4iW z{Vu)~%ek%_BCJdtNB7anlHqu`9l1fFN{m`wQ_DYSAH~aHdlY^p{%Z*k?pd& z_EV+G>iWHYIg1<5(Un=;IO~te;>O=)a29u5kZZo6ula%<%@^!zzTj8$g?Kbyh*R^0 z_%&a;f0oZ37^-_Fuz)a$d#1+dCt3$R6Il05VBIr; zbOkmwJfpyPheWzyv>z)a$dnT~%nZUYdvcA(ZfpyOW);$wg_e@~jGl6x_ z)EGTe>!4=>>z)a$dnT~%nZUYd0_&a$ta~P~?wPFbtb@S1e*)|N39S1ku;9?bs7I}jdIZ+}6Il08VBJ4~b^ip`{S#RCPhj0Yfpz}`*8LM$ z_fKHmKY?}s1lIi%Socq0-9LeK|I~8Sqt-_~0_*+>totXh?w`QAe*)|N39S1ku;4I>`zNsOpTN3*YPsf1_fN=m{{+_k6Il08VBJ4~b^ip` z{S#RCPhj0Yfpz}`*8LM$_fKHmKY?}s1lIi%Socq0-9NQl^QHSI;4I>`zNsO zpTN3*0_*+>{NK43GWWOIFJjPpFyQ~{exmae^{4X_Sm!6O&QD;SpTIglfpvZY>-+@P z`3bD^Q_H`t@2TAU#GL5-1lIWptn(AtLDYwmzGcfguEV9gz{ z=1$AM^_G9Wx0rl^%WvmFsoZrO^P$&qV7-n5>vbGhuj9aa9oKTbul}z%4}uTPm&T}t zZ+kG`eo1qOInmq!YwmzGcfguEE!S(h<__}ztUZ{?m$}YrjL(7f`HRMo>+=g>eSQI~ z&o6-W`339$CtZ`#elZW)FR=E@^X6O&0@l}pfd7^A8k|4sYfw4{j7!Vemvfy880Ucc zI?{jVwKDA&F=)TQ|JCQ4`kWVYqGQllpATv|;?d{h(9!4P!1{a~Sf7sr>+^A7eLfDX z&&PrF`8cpX9|tyL(|!?y_RDkSTssBUemPF(+9|O13#|PDYrnwSFR=CtZ2Hw0vFW`o zbTo#%+1+XUJ*NNDqV}SxQ>0(?p9Szw_E=f>_zA|_!UoG`cLOcRBg55uDa({%tbR-N zf5z%_sq`4D<47IPSlJ_GmodIiQU0`CXgU07efZIK;78lXZ|xVK>v(XSjuZBD{O|*R z&bS~aXI#){?AVdcxL}{LMrHIKlWM_~BD@xYo#U^Oo0(U6m&&sg&axno}fV|*AVu;vli ziIe4;N60mgz?w%#pLqn^NzQzAs#8&h$DGW#c`HjcXmOG8oPC*Plc2a3^wn>v{?Ax_PD+olI*!!w zjFml7b{V6-ls_#OS`I&2AAYnQ_|f+9Tl>Z5IvyOSth}mJM+WXnK#Dpga6}L6%XcF$BFr83_m)4 z%@=yCBj>dYeh?qzjvdC1eG78OFJmVj#_)rAfsPYDW6hT%XTE@)dC+#4FULOf1?uA0pcjljC(|kd$`2u$2Wau;2d_nHmm%zvij1yS%1?o0c*a1 zHDAEae6mf=7v#?TbDWwlpB-O)nHXGa9)UHFz?w%R9|W-D*8A>dK(LxAwO5Y-iH8# zFYFH-`M3R~niIVb!JO!Q2(aFV0PB4Su&ys)U0=YuzJMLxxfkjBf?U@Zu&ys)U0=Yu zzJPUoIr49PQq763FU*OqFJN6?z`DMGf5{wQW@(??t}%bC_>?$_JW?&tF5I-d$Qvt} zyc&|ie)smir^UM@vPgy?yUvc+A#txIkapr=JM?2U@0g{rWQ8~>ZNF_XX!GRvq|X2B z;Zv(n^YO{q=8U!_M9ng(7*AQc%ab=_8pZ(^{KE^U^vQ2zJM1lJ`Sj}yDGfWqu_KE9 z8pHbjXi9sK?I-%2ift7ROKCSO($w=^n>beEiYe_mt=B{}E#q(XikH$3uYJ&4sDqy+ zjtATIvgV_XXFiEW=kz|1ldQ= zUZp-SXNv1HgX~yqUsKbyT}1Wwt)!o~;V+uQSssK6vbzHhqFoj)1CXsi`*QP7))pOWy$Csy;sQb2d z1=^AGV#kVKRR3@yHroc4YEF`%Kb7kev~F`~-fqaC7IZ;n%plhNeCY)>g>szsD;Qw%xmw^;J?{HFBNikPxS zSW?;b>??28*|B9%mXxw%s_qe$y2p`S1JlU6;affR%fyp!dZ&`lXOtG91rx{)9+i(3 zr-+L=6UoM{bI7UNuJW!u$Tm=N^fnUA9rBxu-;zng_** zD?6#1{Yq51G)IVDdnt~;zxDoyUqnEmgLFJ|GAo7k!n5f2Bh|5~>ReDiG%ip}wdH4nDlZEeZ8W9FpR;~w)FA1EE$x{&S=COnml9C@Ac6Q4bqttg@6l?F>iFD=HL-Z(SJZq|`NfT=B zC%+@ftdkUtq7~mmZM?zOjW$KRugmPD2N9_)a8a^pQszSCn>BK5V(H|Yb!|>U>ExRw zm&TV)zKPL0;_7@8@m~4sd=t+S#n$;Ib_Bcm=GmDwhR(N;y_KWseDiMZ8%5_EElT@| zoP48BdEb$fZ*-vUYjX09X6$@UPQJ&{0yXt%!FL#=Kutw%&w(*osHqJH zv!SLe)YQgvSujQmHMR9aCXCTSO)brt5o5GaQ+tY~M@?C%sqAIaqNXg=RE>J6QBwjn z6*@L0YD%D{=B*1tO$pT0CE}VAsHxBU0#H)|HC1O!GSrj@JZ9P9+v|hJb`NU0Jnno~ z-Q{s^w4YrbJEr`}D zxjb%M*2Cp-{Q7P#kBtv?b$Pt`sk6)D-r!CykCQWXaCw}Pubs=|j9P769!CyuAH5=*jSgQ31m&ZLFhr2xP8#K)2aofzHE{{hS z4RLw=vTU%+~>s{>pf*Y54_@_710Uzf++(|&V#?AvU<9-~axd!EbV z;em5q9zDb6xI8YLINRm%*6LX#z`)Zn+i;Hd93Q0;PQAYbiB*s_=V$K9=pp8dW=@ksr4?8doHeX zdCY%pt;^%AKi0TBUXH%T<*{-S^}ZJ0IxY$Zu5x+Yl6s}fV|d;bE|2TVEq8g`_R}(# z$7eN`x;zeRw8Z7{L$AdykE=&5a(OH_exb|bl_?8c9!I>J@AB9&$sRpMnIzk8mq$C# zE|SMwiEyt zJoZd*(B<(_)&nk&b3*pJJc`hLE{{h`?R9zVy=;%mW22pS^%!OJ^LJbx*Iv8r@|fz@ zEtkikPa<6&_r;EMc`Oom)8#Qusv9nk^DwQkF zgVAig&#``tX6t=Uy(>{|z0aB4B&x0VIkE3XvGqQuT&pOy-seob{l(=m?89f5#~Cp` zyF4C^{mJFANz#ulj~BlC;PN=U*n5}9Or_qrJcgHh>+;xa^`9<}OK!!}W3+m-kB2eh z{K%^GJTAtF^CN3;*SHuX&W}XIyEqsl&X2^!VR0}>hf4U ze^QsnG2SFDk5P*zad|AUBeBcl?sADSM&7S(Kbr_+o5Cu($CsM&9RC?-L(mxOw61t+y@7fWsBf9dB_KYl@Zp$L z|7}ux*1%w^$DgffO^0N5qen@sm%SEI^SjCH!i{2CK>_N$Xte_DT>GDi?A~Woac_X# zDAO^qYhH9&EHJsfukt!RXN=t>rkf9iFT~V2FB|_HOXs}IaVnP1d3s$Tw$6Dvzb&@T zd74w$U*|k!-|XhR_xHSUbk0Y#S{6s=yr*r-xH{*>ovCqk&Wj_-;^~|h1IESEIWP7_ zi?4IuYTrA)&UtIzpPUbTP2k+G33Sd|Uv?+ZId28F|KRrLUu%8TYmjxg$|t=BS@kM@ z)@zV>5&A{1L84BQC_3jwy09oZ=f&#SQFYFH+6|4Wb3WwZhp0N|y-zzv(>YJA9!AqS zPd~Pfu5+HE--)hsp32vXp>tk7KORHpyv$IE>l!&P>m2gaIWGqV#^jvGxqq7E5A+yi zpC}LY8YEA>eW=$U+2qwDy#~>{`;YY+M0D(lUW2IIj;DGJqDJJdLEamip6fLz;`;m- zdJXd29r04HLE=LHS9%Q+i~GFRYmi9L`HfzK#Ee>h>NUvvqs&{q23eI#aDQeVz1DlZ z23hegzSnDzIuE_5$7l^+amnTJ;)2UAkFDoiae0h7;i}8yuI|_LUP4r9bzSczM9Ze` zUcz&~{!P7?2)SE6Qm;YY$N6sQHHfZfyRFwCT9xUJUV|tg_^w`qXnvG?dJU4#p5D`I zko@@pud~eKt~z^Jl;KZ%H?t6vC}S(srH<4d0f8Ytjpt{ z)6cm))}6%rCFb$qmTtG37G@pFm2 zE{~0i^1hdOJW+VR%VUN!`&}L_TCB$?r!QXO^7v%-QkTd6)0eqCCLg`r zo33+<+2<2skeU1`_5Jmw78;PSZj!v>efm=8C) zJhr~e=P%6T`5T*E9<%?p#pSVN(@A=a*1XD-T^?VTp5pR2ti)88$25hexjbGEp6>G4 zF5V26$04z1>b<=uM$}m@kI|mYa(Rq%ezwcwhof^`9uFRz>++a?`#hJ&ZHwo-JjS2A zz~!;iSUwMB9#bIp8Vo5p&KR{igrx;)0p+uY?bd)AgNkF^uDc6q#X zsg29yYrCDxW9CinwJ%SmrJYCL%X{?t|`>h<#AxT-Y$>RANO&2 zEPS-D%j2h=d|ilnd~|t$%j5Sw2D&`1w?p+9Wt$1bT^^GUD(UhV((4D8$Ci!CxIEs^ zSLD7oJQoaX&m(dSw=0eo@GA+g~~ zYsOO!M2J?ICNlP4u~2jNF*_LFd|FMk?RA`SjHro3z8M!7zl}f9lWEmu z#`xa5P}Dy{qJ3;cM{Yh5#|Lc}cQ=%w%O|^vW^q@F?@Cmp!p*0P=U>K)CRByG#NH(8 z{Mbr_rK?WqTOShB$7K_%y4R*MX|9OCg$F(RcGRbv+wY4je_Uldzx(g@mO2>8_}Geb z5gh}4xMSRW9=dXw<&kCYcsdk4!FYI~Lc;uR=yA^bo@Z~iQo>9rtOYBJir{kVsq(Xg zRz+)oxZZjNO={<7)xSJf1T`J{PmYdr|YVexl8&=c0Y9*3@ZhJcf9#%^c%&W;oYaxJq`fLmw;4q_a&)C0hmVPYmlu;w-Dya4TclcNQ=-znsrHwp zVs4*P6mY07CG;C7+9bM7-4+d?$Rw>rg|g47PQyVoBvD@B_x=M_OfiH~zrOFuKQOBN z<@iv_oS~K{dFtqL;lSZk=w^zDquZj%T=_@Ru#6ME6&pv9@o$cz2bW{fr&4dJLfB}! zpRzP%7LVw0fw6Qc#sF$^<0^f)G>+yynnm$C9HxGKC(zy-Tc~HcEz~#7B-+{Y7%k2> zhoWqoOlg0T%p( zPN~{VRDZCLI>z*q%YPmxa&%oxKb8DM&EKsQSKck5P3<33_Fa2L-G0lc%Z|%5r`lC9 zGs+73)N&tXs`Fe-9k7y0%v?hsPDQo)e_lnE7fhneVgA;V-fO7%s*be(P(rKT>$S8m zZ6TW4KbiHS!+LtK@R_&b+(1j--#|V0xAe{q46^(iZK5{ER}}f~W(v#y;%3^@f260! z=j2vkm8}%MJG$7~KdDu0Z#d1fONh*!6Ig=_d#PN~ej?hY453k z%Z#5j`Vv74E-~(sIftjy_0xnkSy&J=7vP<34c@ z{6mlZ#@D~jmzn?no$Djk%8nNbc(GQRcthf>%Y>=|$fiGp7|GoiO`Gnl79@tcevu&!erz7zv*3L( z;YChw*&o_zT zoovRjdruYpqMTtIKA^QoIZYj}{ypoIR%EsxGmbA8c#>p!&KRFX6ps{RHdc!OHgnR% z#yot>Pn8?UoqxCd{2He}Z1eFxef|P(*eqW@%&L`^ipKHfN#9>uQ|W=e{7KM!Djitl z%d1V7H&J)BH%4A`5=ZG&b6*~wIdh%PSm!;E7ftt&-u`+%1bET@XLKV@9j^NfbDvVV zBYp&Vs&)6NPS{V3zvRC}71xC^UOaIx9ayrGalNK1>C3^rjMp{^qwV!BF;04`Dg_<7 z&v<)sKU%Q-DdV7YHNCZWJ!2g9)76m5aUU{Hv+{!H;=1dkp2fPjUQ&-JxZtihG_GuT zuGF)=SNv{>jeQG6{4{Tx_tk|fEYJLV5Un3_j^(3z2T-*OM_4|$Wn+5uZXe5=J*-Qa zlWt`>m6||_&#!0sfq*geG21Mbr-@iYSvF2(`ILy|R5QE>%cGUrNBgICVtJCOJ7{dm z{49U(xj>sfe8+Nc>{I0T__zmgehR)#_un4$AkJbFuTsrJ3s_#e$z9rzeh$k|9K23N zGMxy4e*E#j)1cgkLZF}WhVSp#Ah#a<&hr8Jf{eqj0XT9+tw^|UN6bn`Mz+8#`>lVtK)>fgKq%PSo|McXF+ z!183fj*#`J70btmAEE^zO;~>7k3H1y;V_mby1tEU|G_Mu)-r-BL`-4%&Gs8fuZ^1B{JTrpj*LMvf#NnHt zR)jcw^V5WuKR?CtFT2XqkN1zT{Q1jL>Kx`W%Q0?@6Z#l;tjHTI4;vkY;&i&i@^+iv zc`=W$k9oyBLSOObJ>KU&%R^89=skY=Cd=3kBa^+K~Ibyl;DO3)yT+O{uIlyu? z_d;>Ta>b!goUvSSDDZ#S$LIJz?BjDB4>|1Ncwfv-1pGk`|L_Mn{HwWQImV&piscvw z#(S#m&|>(Fe;V%(k0Szy_~iS;M~V8geHhQKT)0`|s*KgM$;CxEka5km3&rc<(-{{Y zK1Q5)sIH$V{omTR5d(Wl#xKSd6zR|HXT0X;*PhKgk1)OhjCT(;wkm$4eJ z*O+IoG5?5@b<}tfKVvmsjEk`vFMTZsmKKQ4xiL3KLGQSymp#an2`yK83v8dpcx1`n zy-N!W=A4&}6I$k=`Q?g4;Mm_n<4}R^fh-?cvK6hm-M|ZZ z&%~eAu_HXly|lfCk@~X|mU~kl_0BIB9s&7pp`)nImzON>6?cet)$QwE$a^O4N1e~a zCfI4Pd~3w>dlo_NO9ht&DfmF2zS#xU)8I-eQA@&?Nbdkw#)++)P)G3*FqT*B}x zjCl}7oWhtlk1;M`%&o_m2Vu;=$Cx*z@6N5#apzyv)Jf_b9#$;>51mBE@51P(?qS7J zJ(wqc>s6J4+lLj~6|h;PZxe?qDEaqQ4vImYM|z`;4=XmS{Z+0t-?7g`x8wc-$L9I% zpg6y#iomg9RX2;JHD-&F1H+1~k2)1~C$ukMduUj(el23MynolQVtbDa^Q=*F9E)7d zx8a>AeC+>;liz#I^86jwc*`t&z^e4N|r|@TF{XO#v(akbAWpK7gSQAHc8!AHcAWA7IGv88CEl3@~iK2QX~I2QbEK z$UTO>Fzg7!zA*d>BOYPIDUA4;FJC-s7;TJ~L_dfG{mMCH%iMCrLNIr%^;_c(u4?vctp&HxKbTvho-Gp>)~T#X+%pUQ`?A>``%w_)(5^PDkqwL-ath=-58 zlJ(&hVE9@S_S`dbS}6;h;NShZ#Thre5{n)jDZ=>k;h|KvX?Dglr|qF6=K>g?=< zjsb=Z?E|*q19G+RUu4LIp)U+O!muw4zm^e?dWV}Er)9)%!4LjnE{*X*UqG&W!VY8Q z(=z7GQhxb($ncrZ&K|_c7&Z)Egvpm$H?3DY%kuuk#CQfiA}^#T~rr^hq!f$_|8JOdvX&oW1hz{)4T7edS7L+ir_FzmnwFzn+8 z7&3eY3|;sDh7I@tM*Q#r3?2=+F!cF3;*K3**vC5r_*f;wv+Q*|mJui3A;5CXnK3SY zw*YKHZp;Jh2*@#)#=P;n3m}IKpXqpv`R8{aK#sZm#uxMcKawwSXXWb8Ynh3WE080n zz&kK<4fz0!97HYxBR7#Nz{pwT6)=AY{ha?E9g-NMTD!pGh7hea5#iHJ(?`sHE#^ML;J z$WG6=!fvADi4rpQ20kP8BXF#eN%a|Hr7P7jjFkU(PR6hSTad%H$=A19`=3>7CSN9x2EX6xPUSgj z;@`RMz}>X#19`nOF?fU=y#e(LjGlqI2F92$HemD^)I2bH5BdWzdJ<|L7`+NL53Fo+ z{{&V(xqoUod}w|60EQj-0ET`107Hh)fT0T?z_0-yz=$6{fOY?L8wmztA*cfQa+)!)s!`%I0oX9C7P4f`Bm?5(i>0mi-#doN(@_pmnt#vToOBVgjQsO&M>V7An;bVkd}w|60EQj-0ET`107Hh)fT0T? zz_0;Zz_5+?2?B#hLoN(`Vc6mK*h3#8dLCfM z(stkj7;}jqV94OZXD5}V;$#dPDt^YW{f#f?{eL81;11vMp$^7J^Wlz5-h|Zf_u*BY z7Kb#8@53p&WD0@KFIB^eK_~BqnT!`6&LkdHpT#)S=x3e|`+Rs^foUG-z&><_{5FH} z(hZG8&=Vi-(5147Qp2b7I+KTWU>`c0#!q3JQ*&(;WfD(g{9xK_;n!$7;~B??u@3A* z=XLH$Z2xWl6QX~N$&70q*eCX!@ZnEUY}SE&=(OE6n(fp%6w|67FplxYeD6d`F@f>m zes@?0_MtPk#7MR|erPi5O1Dvr8-GY>^_d^WxIoLetONVdx!HRF+xa0!K5NjV!HjF1 z&1!8QFpP1$vT0Zc_MwyYUJthOXkjty!pGi>e;e+xQbp^>IA_B`tONVdxtFX7+i8=# zmNj^JYsPmU|7az8+KF+x)@4`+_Mw9xU>tYpMqS1!1~sto136^Sfqm$}2QcD-EnwJ& z4`BF&4vvKm#sG|QBUWIAz?d7%5isTqIye?O-~brBVXlEO z_uv2+oInT1LI)fJBQL-uFt`QBz~CG@I2Jm{AzkOTF=AF@VT`dr2X>&N z=87@qO3evl%!!&S#+WPUz&>;o7mUG$nsdgObHxQ?Z~-0IhmPV}0)uPCDa*mB;+iqI zh7RmQN97V@g3!ON^0A(1A_ps9a@?Tva*A7&)nOl`(P^I=;4`bA*s#(UUS@pvhbqpQYhmP{W z7&WSFF-9FLAB<7Q(1CsEs4*}`jjC7~qmI=W7^9A%1N+cXbHo@ms^)?*>R8PYW7IKp zU>`b)1IDOPHP?($$BF~SsAK5BK6Dhvj8UVCOU9^U#W7>lF?3)bIx2@4qefM(Fh(7# z9Ab<*h7RmQN98DE)Tqiu#;9YJql{6<(1CsEs2X65wM^wYW7M�mi6f=)gX7R82BQ zjjCE=j5=0z%NTVG9oUDCfg@C{vK)16VAg?s)Un}<44YoVm)D4yjIodrGZ|xH9oR=5 z8*@d*oRBeBtb_Pb#|9T<%sClcunz2_jt#D*!6_MBvkvT|j*VQBM$Skhmskh(QO8EE zN+Tzwk*ll&`>1217Nn8$(x?U2fqm4mQESquDQVOi>%czh*r;V`)T}gWnRQ?vwvApP zjh-NlUcoxBkJyb~B#oXUjb6k$u#dShdYv?SnlySH>%czd-sq*$=$X>!rK|({;MVBX z(&)+3=+&$P`^X(*Es#dfm&RJaIbu!%ZG57J{X_6!&c z%TdSBfqje@Jx_9oWQtqK5*53uDg%E?AB_h7N2(2R#}XTpN2TaLqcX zW9Yypbg%{hBbSUl8*+)|sAK5BCUmgI03%n8Jt1_Q`9W_UcQODSeK#n@b9t9Y63>_Q`9mN4-)G_ut zkfV;V2LeVNLkGt~M{&#;b&S0f(800LQ8~mIb&S0l z=c-=lzz%fGb7Ab2AxG^R=fV-VW`(~=!}&6M9Il}O)PuQ5W7IWxw^*BG_jm>XCjzM1K(Ib-Hnn{rdx=C5r-Y2&VGeC&kFh3J)M2HTulCD%XX`Q5hDS$^=(8Z@k~ zPk(cv3SZ5CvtCAQ8PC2dCbcPEjfw25{oV-b{Bjc8ywYO}*CX;A_1LWbM3z5}bBMkl zIf3=-P1ya_S~hFH$Hd|6YkAf<@?+(Zd~By!{_@AzVQe$X@3H=&|5V&Kg5@=nCYF;j zj9~qZbK`%tFPVL8UcT<^>*)3T^6cSWeC(Y{`DIw+zHGCxc!FZyJh8a-GZoaM5||T}UsC0nz+9=k`-i=U%1f53 zJe4Y6SzqNZ_G!FNz`2FFCo%Uhs;=0VsxztTgpXBqBUSydO;u04M*?5iBdL00xvD>@ z>X7wSU4C_cg*_XN#eNJu0^?GBLaO=?;XcrLhE#na1mjYD;ve>e=oea!exdchwpTRw zmgpCphiY8t7dRGiqF=x!;>VhY*szyFzknR$MZbVP=HYAmUaYS;7W+E%3(Xh$1&+o1 zqhG)#ctO8_KK6C!7m$NT^b6>N->>cAu~)#c*yEvJz!&lm{Q}1#uh1`G6ZwX{2=uYX zL%)C=`H6l3edO)e&PTBC!LiuypI?k>$D&@)FJKdOgnj{i?DxwA97&m!58q?&Jz(Ijzzo}55|S@AwC?7 zco8>jVjLJh^f4b8C*&A6#t(hW$JfqzG4D7QJb)+o0&kdi919-62W)~L@CtqK4E`Vo zpWqex;Q4Fk@5m<{i~K^rfG^}D@(ITxzmR9JiM&I;LLd2yyo4NiihPAW^7m`kB2Xtd z7IlMu0bi&y)CrD7-JpJ86ZM3C0e#dZ>J4(#AL=fo9GjUeuyCtG4#KBjmU^o7~>K~oWh7-81o>E@d{%ezIwgOn15mLC5-tO z1~0mZlZag32O>T|}(Lv`F&uMZpj%`*C-W%M`8 z=zEsYKP{tAT1Nl;>a}j8Z(By6w~W4R8U5Tc)&)ltsgD}=v%UG8!W1Y2(^_RaB0be)|FxG3!SjWHmeG2*oj>Y+hvEQ(a z{exxfD=cGw0=eFYKws}qzWUve>TA5eLY&4v3ULbLmFgdeUm)L9|FDdG7sktS)ju!~ ztgrfqW$e>1pKKrJ>uUZP<9x-~A7cLbSk*tk3)@uv!!q`h;F0C3e}G@sSN#Lu;3>e%mZZT7mx#^UqBz&xYmSz#rp7%>rOZp@v45vzA!$-hhq^h;)YF(1LKE2 z<^$t|9OK6Lp^y16t~;R*vp(h(*Pw7Lcu;+weStU3JB|ep-~%?n4|s(>cm{uvgHP}Z zeei5tgTng4`p6etkHWFYFXMa}>k%J|{6e0=Ch`vX3Vq}+@)C07De@J*kiW+DD6E^T zk2=7$DIANsF|Gq(o#kUuH>e-jL_MJnp^v&my+MxpLmk2w>e9G2^$&kXfqsEw(GSe) z7{>Jq>?_zN`he}a$(z$MlhtsM| z4dWJmcf{c5Lzs)yAGV4Tzf@-2de|ZH>R?>PjZYgw6zI8J1Plx>fa9=aq{C~U89X@dFI{y#Pl#ctH2R8;CkG@|X`p&)2|IvHx z$!8zq`s=wFreD*h8jHR^`k#Id0FHHhk;bsCu`?FezTu1Y|4;W~8!;<=cPy?iWuLLW zm)scF|Cjs3`Fk{eBPJ4jtgTiq5AEA>2ttb`@a3pU;CE-yyt`c z6~7+K|9#)`uRS;Hub7Q_!(NN`7?2syXZx3)CuZ!6T>BV{c|P^e?(NO<1@oD->Dq3g zSm_UhcTYTA)XT7nHWexzekO9#zx1ryS}6v5r!PAY9(wqOcrrS=x8RJD;enGQ#ec-F zImZ9UIi~rH+^_jH$NsN8NB3*zS>`kL|EIkF8t<|CJH4a)f9pFtz~le+_pRVPfPaVg z=BV=^{+kY!tN&}?fAn{FkJaDdePn-!_sabp-VgY9c+cbC;eDNfe}ng~{vF<*`@iLV z$L4#VKP65gk5mh^3pXt<^2SOguZEY4I+JERrF}uCwEHNZe})q@6g}4*gio zJ7#GtSs_kJ+izP8+C2F^spme}!>3lE>CvO&85#DLq))weJRiOqsqP_O{(*H0r3v+n z>H3WE&fE7qU#y#qFZL-QzBE0;xMI-`qRywSj5A*IeMbqK_>OW~lfg88c1pWJaD-Tr zzckIxn9@Eu=7{KD?SuEq@?iU?GMB{Vhn2iT@&(&FB5sN_{@#!ub_LlZA|u7*`FlKl zDh1gc&s-HrPvsD;Pp7c!bvPv!|Jgz0tewJc6=$ayy<>{FcPr4oGhl_N(QlnN*Co*Y zb?sOYdUdae{E*!4Mh!&ivu8!VfywPBDT2i1mDk1FSjp|;yXJc0=eQ*bPYJO5teak> zSg#vmV#WablhXF?B%Gyp-_MME}og0bmxm&JK)o9T@b6O|1 zD^H1}{8h7fm%dA6=Lm_U<`sYUrW%~cPBr~9?I~K62E|Tfzg}^S#@YSIe_TR)^nIdD zLuQjVWkUOS=|%KBWDAX1nZRCNeK;kobBGG%Phj6p@FPvQbb*?M$G2Ohi$!(Q+@zns zk8fuf)74u)=`H&0cszUifZ8E3&R-*{8_y1JzTVTJ_!&wV8Q0!5BfYpkeK(D65!c=y z)swMp#Cyw2x$!>AJaRxd&&fiWHd`2XS zxzU?0xxX!TT@wwuHIFE}Ft(i|(Jis0d?(LM=!MZ!Ej*y9=UH)yiT` zXe@i{$U`Dtl;NW6{+M>uo?ArP&kIHD8Zqr!CuWP?t4N%T^t0Es?Jp|yJti8r^0Nng zDJtguc3JFs9K+s!{|`^6+>s({j~MoWiP=5-W=D!#v0~UkgT6$ZI(|hAoeh=aN~;?*MfMF(68=TT%Xy13q?_a2dFr#Q zwe31ps*-}5-S{Nizg6$xh|+*Q{qa$%m#@*=`s&%dA3n(LJJ->1YX$91`9aQ#Kb3+` z@1Umn-plf&(3qL8eXzcQrvQ50f!c$~Eectmzwq7z% zEQ}aTr*1r#7q5nkaxY6$^e4|`{Dw!w!$%*zecwKnVcFDs-SbrSuJ(T_cdWiC8jji+ zk|O&Px%*zEC=hkGXXE#eWsL_{MOd61Vot?JQcgW3_LS@(0%|>!<4f)oH9JocP1-$> zSJk`ek``SjDvtg`9{n;_Ok1{B44?bEEck0f@p#=?k!!_$+3{A8$T|JGSiJR~tkPt@ z=X$nV;@Qc&vijhSMLLYUA8yqNRxw(R^e0afpOKtzvqTNbZXgYxa$ zD7pvUlKaMtqKb28h}wlCWx}XSY2>RO;&tVla&^valp>;__@V9%dA!yMirx02r%Ute z(lh%CZ7CJgbGp|xxnxWvZH}MO`*6lpxv@kfU0Zw4`(gDJ*=o~ey4=g66XBO-m-ELc zPyBv#aPK9VC!?hMp4s&7+C|xT%p%(MZZqxwa6x8RF`SBKJ4E^8UXbOF{YXQ-7ifII zdD-_-EJ~8-CjFH8oSb{IySG8|TQs=TSs80g#gI7B z%Va?p#gGY=M8-^qWL`QXDz6$QiWWF1pKRSCs&8E=rd2&4&jrm9r#q6U)n>me8-IZ4 zT=ke3+hd`*&%{&Kw=WjMQ3{P=de{4-)Y?Hv{-`UGy5 zX`*kW=V7%(rEJ?|)l2&+fAz#d=C`Gt=R75h80#rgLdtTrZ_wma6~d>emuFv9HTbsQ zEN|DIUb*PRbs9Z1kn#+Rkj+w^qiSV-q21%dWxUe+s8-yuGhF`v;1WT?`|EC*etQ-5igU?6O48M(XL#+J~ zIZocBqM0|y>dnh|$`8CmCkn5ZX;Q!SoO*DCYL{3i&#o^eK1`0F5>?j9R9gp$*XkMl z{o1UN6H zxcN85=eVmwR-9Nak3NhP5si0xI^0_(<3znCu9eCzTEAE-A8kJ+mW^pI&U{)T$MxPR zK4zFA-X>Whx5QZ~*1uaT9_Cl?@BV3=*xzNZs91WDl(`y-7GY<_+bRp?iB-X(;?V1& z&Myn(Ptg~824uY@e(f<|{#fT|k@hogh=G&m$)ov3cn^i27cCaem6ft3pp}abh{J2< z$k{Wi(`>&@BF*;MvY!}59UiE4@ainti@eW`!j$#QiANw1#FqJcvu$%|(fQFGc%T^3H1y*>@6Vt*c_4;v=P-@>X; z`570ewmn|QxhO`Rt|%TI9xVGkI3(KD93~!I8YH*A-Xc15SSV8eIZ)!)0kZp$P?50oWf4@ZpG=bOv8PRNqzLNqo6MgguP4K*NRcGGx4hl= zMZ|(AS4HB;o^r*DQ{HJ&Pl{uIc9*Xf=c9T_w~Jc|yU8;-yHUyDWkMF~Dn0F{Q{PKr zqU3L#W%k`0XiwSNBJ)}I zaFCdGP_2XMtIDWJ=ZWgghEVgm>KQAI!^M}bWhqyWO7e4*BVtaXD3o|~1=;q|Me$@y zP4Ck+GP6_W`UjuS_U?G>pnS~A}KMq+J?vtrm|k4)Gt zr3mSAU8IT~B7a!C$n!GuE%DMSEF0##S46D1AsTisD07S-=B;+=yl5~vzl{4!d^&sX zfXKKauiSU-XS!Q@lNfs_w+y&HlG+uXDelC~CHHq-LhWny5~m91ln=Jrw5fPu5m6<( zJQMW3qtBFdY0)eSsF_L@NVS+A^xjNjVz6BM(+Ens{~!(9 zkV5t?UzM)*yg()PCzo}H_|u~oH>k?pWO8J!zTPt_Z&CL2NoDip`9eHN)w|PvPAok` zR(aZOJVVjiCzP9urxgXPJw$`z%i7JFi8)=@P}&u7W#()X#JZZ3sLmh$GRw?W;(E*0 zbSiOd8M=L!2=!*7z-%$)`6Z{t{Ciuy=ZnXX>jqvEWxpF1(WFx}+1>A!$lAY!=k=N> za!iezBFWR};)gk(=xnWvqG8gC;{5)1G(Y&TXdQK!XcX-Y)hoDFw9T?m4D0@a>aLw5 z2L9<4F>XAeeR6;({N|__m+T>}E%UwjlsKn>XqgBPI7QXd zPN$^bjTWgU9izkpH&CPKbwtw(hbV2={nY)BB%)~4{WS5xIg0jSf~TR_O<{#^(6tNu zwl-L~ot~;1>{oQUw^^X1#V@bZ>gNHJuu3@XX?l)oo~lQAdTpY-YxdE~mSd>%j&+o9 z*m^qKb~(K-wpzWHdMbrv+d&%%R=*#u*J-^9I>K(aLDc=28p44TJ(k5#nmCs#L#7O9+nO(+G zYX3nZb>amSL%la;;-R_XgLepxsxq8fXABp~3YMdRBL~ywQ-{UaYf-32i~f}O_(f6o zT^;Y^M?Gl9@SCDZqIn^u?{%W8uOmgz4BI@J=C!74xvq&sTeFJTQJT=s1gC|}&`yl5 zTbGhP*eT8poh-hK`ZL9uyi$}1SS8j)sZ0-^P5MuJ2l}`7eSdr3_rLPKZ~RRIu8rVt zjL)T^&D5k4iU1 z)VuhA@da-`p|0&PR@Zh!(O+X&-ycnB53>D4pHs1|!eJ@xhDDlszH1Z5YFsg;J*V}W zh^A%ytzPj`+TpbidJA>%v&8XWyI$6O)bY$G(P(_I{Uo3dU7Ge#Y^)Y+mnt=%(k?qI z@&p9ih4SsBag)8`&V?ZR=-I2(=jBXseP)myYwc@ly0(kR-XO^ClEzQ^FU=uNr4O<< zMu{)|K5z5fzMI0XRUwIdx^P5Di zZu#1D<$a*t>UMm2YRPzNwJXq$oEKAeys(k_j|jBO$9_-G%bcc{RRZn2!){UOu}^4h zV4(de_W@e9D7p-~k=!oYb2-I{nLsvJn%wSsVHg#(lFKaZliPKMl%_tjf@QMw$?dX_ zV~|}uwd{UA!2WUFP%pm!%`i5=23Ppr@MVesJL%DLo*7S)$%C_#*<;sK7pwaE%P47+ z+0#nQ7PoT0qJm4*b)jg7#H=^Rse1mT_Q7mVMa)!-XpC1~3;HdV^?80%idr;@T_Y^1 z)%ENvZ;2g=?Vv0vt&XX>N9-<_*zOvb#=0B6)wBI{)9;VFy9NjvAOs08XZJw@K|+FCkb%KMAh-k=+%-UgOCY!e z2|j1{aB$b)Ixr9*1a}GY>u+_}zCF*q&u^{!to1&x-1&pWho*P!?ylX{)pcs`&L$f4 zPZ_!KkEBkfQaMGDk5fjjSTfd!-+z}}OTm2Z4pUGy(cZdiiBguNq-1DJiJdhk{*9rd=GsjJ^r%#F8WA% zJhko)`bc{05cwDSNP3JqeH(owJx;p$C;CWwEOPf2`bc^Vssj&MkKZ-Ci9V7Z!?xex zKFauK{y-mTKCZcZ9et$vnB&?t^pWP{$otXgBhAM>Nutq5nvZ2OUqv5jK7Nqn3i?R% zasG!<=p)U?1*I>0dYo1BlBdVzjV^k6yx8=Dr^oK?&U<>iG3cD9$LW*KdU`B1?Tn|# zJ+n`HdhGe`l&8n`9Zqo{MY6#sJw0w3b;8qQzVW|%dYmxhxTnX%>yCMPEWiDzr^f<& zj(B=pdg!pH$K_FnJU#yM{Gg}DweJsjdb}3@fTzd4srGw%yjyUer^lZ|_Ii4B%J1>? zc)0RzPmkftc6oa2nr;{OQKl=j)6-+*Cp$bn7Ws6$r^hK3w|ROz*)-_su}X)no*qB$ z66xu2bua1ZaqVc=)8n%F0Z)&cmq&PdyuE6Rr^mrtHhX$}dVG_o$HmbbJw1MQYlEl9 zlXus9dK_A3y{E_TG9Ld zzj}Jylyjx0$1TNIczRr0eYvN{t#y}qdVJV$si((LVM{zc{@rh}r^i*}7I}KCK6#<1 z$BWYzczPW3>K9Ls1Ka+>eU!Pw=X-iQICP$;N8hNQJv}b`X|AWoYpdpXdTbzPdwLYx zXL)*z+&k0LWAOY8Pmh})P51P;=k+vCk1yX%_4GI~=~PdT@$ydb^thqaPo5s@_C zc&+?oPmhxqPV)3PBIP9RqbQhnqNm3bg@5q$_}M2DJUy-u<2^mzZaB`YI=HH z`2Clj9v2P&!qelj71caF&NyGi)8ocFl|4OXfBKoH$7)F{dU`DGFYoE`$56kg$3x#b zo*p0c4Ds|>LzMOO_-WcQ+(#Mi|J2jtu`f${dR*P0xTnWKor`&Te7m5ir^o1EVNZ|i z_80Q>xc+njPmi1b&gbcIX_3619(R??-&PmgkGN>7gywk7xUnBr+tPmd4NB=PjP zEn6Z_kJ}3-@btL5W;{=i8wbYm^tdS3TbKQuZpB}@?C0!j`pjiNXV&&dF8evnL=WpZT2}Yww-g|c0J~qLMe(f$Rw<)61qCcDy zD{H%PyLJy;ynV^Jv97B7XVRT2t~kwy9D|-2uQ&%fXK;{XFk;zhC)ly6gB*iCY4$p~ z4^D89V{kP7I_LA7%N*nwv>89cIqL=;FF%$f1Gj*61DrpxmWEHCh`7zyE!eatyA|^#x`=K2JFYzyJOy@OIu|$}u?RR&+-X4^WQ5n$|>*G3b^& z(&;fEgmMg04L|Dq)%_3y-iL>tthfN~6qlse%~ zUMzjcF(^^#vfDY^tPtcFba@r+?t0lgfE&Eug&h_`U_m-7`z@i&yA`YaFJs$Ffi1u()}>y7z`iqnfvVYdCD=U)cHx^ z*~6=pWAN7%e;~u2Xv#5|8s~h->z0=&#~}CYL%ys_j#G|7oB73@yHA3YV{ol=59dLV z<& zWe#!-empnBnLSj+!&Q#KoKroW_jQj`j=`|P#htaET%sIDB17Eq2sv&TQXr8kVE z9D}``H@kD%)Sw)L->M#T3zmvcIROc! zIR;}ZBy)Do+)p_M=U>!u!Ygj19E02Q#yD<^Ih13tBy_QJEBOG*F=%sKIteTKT;v#3 zX?)a4_&Pd(9D`SJFFJBu)&O!0x~O>Lj@_w!$T2AMeY8{K!^=M87{sf4(K-CIjDsA5 z%omP2Szh;ZkYkW(Xrz;Qz-$LO2D0Q5=j4zL4&@lk9_#Fkzn^jp@)WP{Jb!V9attag zOyT^ri{VNsN0P&)6Dz=6+CQI5f}k8`+xr`Sz71{r>A zkj40=yo>5eYZiE<1k+}Q3`*;|lu3`QhB;nw?ns}DH_sfu29 zSI?Lqf*gZ~Pov#>o0|iUUL$h z|IvpWgZpK#I4{qobC6@u{@!UP`_r!-n-_8nl4dRy zs9xj(^VDyY$T29pxnxA{r&lP)U}*Y*zG3~(QjWp)o=KgI z2lrEsK_aJ)lWE9C$}u=qV~q1^#T?2pXq#!V6F+hQ&kmdiwPM zatzAdy5KxKoFjl7gI@Kcop-}h_>g1JX;8GYXT(JxatvN{yy&>a%Q(m}Xq51n^S*jN z2RR07WTaEB_-qF`24njzaaLB`pmaJ?M&BFjZ2x^9nXd!Nt|vUGYO9$}w1d{df26^`H+q27!#1-Fg|9h9JkF z^22ENR`*5$&+2XF*`HPDj zgV$N+yV;IJxX3XGd^61bD&t|wF=+F?lACkxdCDJroaU5c@VwU^C+FczlwboTmYwWFjzM(w zD^8nK=^W%3q)Bte2@m<&L5{)qEB87(PmFhvW6*2gI_HNB%N*nwg!h=~tV|VjkYmu& z>FpGLcZ_lj;%+M8%zJl{atyx7aKblvWi;g&j7#_=q(b&+$}uQ=>XSgDY8NQSVC1{I zfy@PuP>#W(Ugh0IAui<@^bZ~4*66j6atv~{P;)SJ6y+GqdAP~VdhJWfG5GQ30k_oQ z1e9a&uJk!~ZK94o)DS#Y#zUnMipM|BFEsypda1Kadx@LF=$q#ojYpmNy;%8mNmEA z{Ox7RG1yXdb>KyoYm{SPYvP$%`RJe6b6zW6a`*^Ispatv}mS99=> zSq^dxeA|~eE#qu(kYiB&vvJN(^Y>AX!Rr+boD`eRP>#X5kW@~dnO7*s;As6ZzIiI= z3ONP~%OBiwW>ggA7&MPw5NI{=6y+FnoRiJX&}TR07%coC%+30K4docLt1-!K@zFHO zG02{9rQ2a{XUZ{%`~7w|MT3th$6&eq-JLjmyAL@ACEs6in@(93f*gZ(ccR_l#p(x; zV=!sKRd;v0cLC%WBuaVSO}n_NiyVW8r4G3h6OV9_WAN$XEpD>#UtHuERA@cljWapI zMUFxKt;5{pw+>N`!4KOjyEg}&ryPSR1{Ke=cl$h$T7Hax3}}^Iyg=pA)&B5x@gE~r-}H)+GmmeGVQ(AzPIv4(-Lda<$G+1Y`%ZW4JKeGGbjQBa z9s5pq>^t4D?{vq$(;fRxckDae|L%9X@x5;BN%<@uFrUQ(=CgRHT%E=9@BHrB|83j; zo$m!N$(2B0Ouiob)K{lzV&ZhY68Vl_Pek1Pbjv{4ws^#U$4TR!PygIO{RFw%y3-$D zAx<7|mOFUUF5(aNOLupkg~YeJoOdHD_a$yo@R3_{P=4aO`Qyso9p}>f&UH&Bl2coj zih#_YrzMvAmh2CJb5~6$%WrU8@QY>d+y`$*5_kChjyv`BO5(f|PPo-->hI3Y9kao$ zli?%5Jl z>+CuD z7H81YwK)41*Ro8T?K-8}C#O37e;F@Z{hgZlV()P=+F+f5`%lmKw$8?-bHj08oCAz& z!8q^Nu4A2t8{<52>-<~^#}c zo77I|9}M|mTnomvb{*@iUf2`r3(f$?S-BWDJUd`q3$|t2Y}ZlG7S+eIrk*WgJZp9v z)Ep!EW)9MQ%{&#>{H4B_`ABkX=4;K_!O}Vl81{r@qQ0s}_hLq0Y&rkPsLyrOd?&_y zSAU3M1JpIdXoDITl8-rPog*x*^Mx@tsV{2Gh#?=0Yr(kIu4A1w40}R-!5QXCe{?U{ z3NWq(<64$!vt38&fa+krE8P&o4%lt5&M%hMImOaCzgSx58WZEbSkrJV7;C0o$2!Yc zT4x+f>+EAl|d)Iv?4!&P^tUeE1r; z77Sm;u4A2*>{@3iyVlvt#JCoI3a(|DHlse*Q8tShzKpVE#PDV8HdyB`yVg0&u66#h zYn{tX4EgW@aV;4Bon6N|i`li#Xm*t!NzWL3Mlh}g<64$!vt38|lvD>krt&F?;bYou zu+Ddmu+DLgu+Ddmu+M!4D=dFlSiUqd+K=bj@^xd>vHWmh`R4-j3Vp#G zwS3?hGA&;^Mjgw47M5QfqYbblkPn+-?MH;QPZ8E0hZuc0%uO=8Hj_Bb)>So<1b?RR3d0rnm8Vau&}m$2es0&51%7qy0i(HE=(xE73S?K)Qc zO;~X`fprM?qBZ}2#ouDcwB@5dj3M+0&4Eb2Yt@vb& zI_la8%zgL>R=gDTBhVMD)mBV0hDmz2p z;94FxyN=SSi@w0`vto=GL%J9A2*$NWr^L`TTR!k4iGxY^?1dMxuaV;3v+I7@iqrPDMS96eL!cT|KjeB8kf^jX_mT9wH$BF?8 zD>fLT4cKEqK5UD!ITC9D_9a$K4|YakzQA^Y(FQQC1>;(~j_7FztS{6CFs?;=aIIZOtxePy ztp94wBAHnKu}8(dupWVNty!BqnUI5WvwnGXu+Ky})_?3j!C3$8HmG%$I>F?rDKwb^RBd+95Aj0<666p ziV4uQSpU`BBbiwL)x4s6Va*5QS}?9%UqXs6AN!mEEVlU`+-?4j9*hajjiP#RTYD ztpE6(3A)Dmuhwt67uItyt_9mNZMN&+cP7-w`j6k4z*zt7HmEh2~56Q&(Z#@IVkb|||(nSom#vJh( zYBSb?| z*NpllPicmnK+679AM&?+rWyC0)kQPf6L*ScwDZ(z&1iq6pl0;z;4aOx!kc*IXSz1^ z>OX4O%#(8`e{)ZMkMqsF`=UD1x&KNzo1+&u4pz@+%1<;3hL+UaJ!PX{voAD% z+^k`6(zlww+R-4GWRm87pQ~|}nuq>bKltZe&BcDJAMBkcobFZT=laxN+!y5+e$eHp z-+rfN$l3fvGvrsx-Jh<-eYaQDjP^Wjr+JlX=i>pI(f-8aO}Xmho=KYfG-~p{$_q91 z>fgH8)RR->mu8;)6i##RzE?J@aW?Han=aIAXW=hHz4m|DBGl^_%DKO&&*K0&JU)=m zyf$NBkG{K0<*rrtS>Hy zzPLX01!jGLSzln*7nt=0W_^KKUsP`N1!jFwxzQJx^#x{qfmvT*))$!d1!jGLSzlZZ zeQ|y03(Wcgv%bKrFEHy1%=!YezNp;N7tg`037*rugZ%`v{RFf91hf4Fv;73K{RFf9 z1hf4Fv;73K{p51kPp%L931<5VX8Q?d`w3?I31<5VX8Q?7A7MYiY(K$lKf!E2!E8Ul zY(K$lKf!E2!E8UlY(Kdi_LJ+weuCM4g4uq8*?xlAeuCM4g4uq8(XUIR22|KN>R7po zuhd){qgR-)^R6$VsWzQ`CX{PapOr#(k^(su}HR(Ni

T8Dl>Pa=@zJ(9;rTS=3p=p}Y z&eL5qqx~%!Yev7mudVsr%_d%Xqbkk3`l%*1_v94b66(ocxTS@6-(N?!^xE?@cbM1C zQ-i|1_IIBb=JgBZ++Wn^aey2iAIRr%!+m)?(HkiDi1GDbHtUEC4jv2OPYrS~o z*|vb$wt(5TfZ4Wy*|vb$wt(5TfZ4Wy*|u;wYzx4%@=@VOzj#Tfl5vz-(KoF&tQJe!TkJ#d0v2dzJS>Vg4s5LdERk3`o;Cp zFEGzvFwbi+&v!7}0WjMKFxw3<>kG{N1@kz7d3?Y;ZeSiyFpo2sZ6KI!BbfEY<*+AQ zANB;ydI$6K0Osce%+C*)pDQpwZ(v(r;PCJDe%$7spEM307^urz-)R^eJVkR|sr;7B zng=bfA53{mb0t|X*!)AiA3yoJZZK_o%}G1g4QAY+`O{2wgIN>kJ^1sNdhJ6@0Oe(V z)#a$~ywMCf<*V!cHRL~;pc(hAv|lsY)8eIOwDWlO0kp42`$v_~jDDRC(R|}j6R-Sv z>SkX3#1)m_V&q(?7wXB+RI!D3-;r@zdhMw_v8C6}d^cKp?Qb1VuYKqj%DKO&&*K0& zJU)=mkG{K0<*rrtS>O@3(Wcgv%bKrFEHy1%=!YezQC+6FzXA<`U11Qz^pGWhrYNz z^aW;pfmvT*))$!d1!jGLSzlmVUtsuSW&AI^`3UB9AI$a>%=Qz^_7lwZ6U_D#%=Qz^ z_7lwZlgnX0xjyVCnC&N+?I)P+Cz$OgnC&N+?I#$0gf9(d`w3?I31<5VX8Q?d`w3?I z31<5VX8Q?d`^n|7pIjgI6U_D#%=Qz^_7lwZ6U_D#%=QzEekDFSu)^&Ezn6=fsZnt9 zcFoCl)DKRXsrl~Yy1{CVHUBzY?a|&1p!zGLYX-mlQFF1uUj@&m)BLXAm%-zs`cs`` z7it85dK6Cl@!}ffOXFTB-@3IQm81UPLYg6`@7%tg{98FSqF&ePm-@Sqn(kN zG^737?tf2p(68#znj7C}>Xp}WLcRK(I=1xWtZLiJlfNcwn;_q}@PM{ndzuby=e4s| zo^QPN7is*B*DsWFe^H;u0djbJAfLw#_vP_Kdw87DP9A@>pY>wv3mk9uK-&M>oY!d- zZ1{sNFP)@8a9w-N&tIzbsIcbma?}YPJEQmMsfX4IzU->GRjHc6(`xO&{(4louYw7C zYks=)%iy>_^*+5~uP>>;sDtu7d(GZl)vw`bhMaJx=3beNi2w zFEHy1%=!YezQC+6FzXA<`U11QxE%W8`p_4c^#x{qfmvT*))$!d1!jGLZGC}ZGeg>+ z^6V#=?I)P+Cz$OgnC&N+?I)P+Cz$OgnC&N+?I)MResX=-PcYk0FyzCIf!Th7*?xlA zeuCM4g3(9VPcYk0FxyWs+fS-*>?fG*Cz$OgnC&N+?I)P+Czr#1a(&oOFxyWs+fOjt zPcYk0FxyWs+fS-*`jv3cd#}G>9tSXw517Xd%;O2>aR&4H1?F`P%=+ST^o#4GUtrcd zn4bqQKPO;*e!%=(f%$m@^D_zN{(^ZNz&t)w->f@e9#1fjGnm&eFt2N1))$xKIpq3y z4#BKYb95CA=Fxx0F+b%HMG%(vbFl;7l zAeh%OFxyNnhi&2duq|M=yHsS@4!4(U>-v-k1d$T9L(z-nAbZn>yFFuOmclZlVE-Z!2E20`I!Opvjpb#4$SKv z*wz;q>)py>IzEPV0nGCh%<~t_^P1|LbpgzF0L=CQ%MW;+aK`wV8g4Q6`|=5-v*>o}O#1ulpEp|%xAC)EmucGJ8kW38ZbP4lX|HOYU*+(&uFBid%7 z{^Ro6W4(2REGI;k1$U+_pX`gQAX&28&9^~%p=Ywp!A zx;NC5)1i9HAj>~7EzG-bmBp>R_Kf?kwb#xmH(Gn`UzMtj*DsWFe^H;u0djbJAfLw# z_vP_Kdw87DP9A@>pY>wv3p`<4p9(FqYFk=oU!Mxa6Kbw?yiWxg^_Fbxi!*&H^w_BR z@WnnAo{iI-|5~349famgH~UoRckK<;?|iFIh0P;ka;C$Lf`2~L<*N%e45mxjm+BxF zB9+j*CZt}lPe09f64VWTyH|77o1~MDguN^EjtRG#w_FAoAr8}CpN7kY-L>-i; z+#ODJP`}{E{fQw5xhtpx`M3VmjQgG|J%Gy5p3iz|Mmx(b)QtAG4{FA^UEim<(kD&5 z@?TFj^XelPg5|8(*}{|G`FTt4zUdx@dF_e6yp`9^6*YVr2mV&)f}z*^~68=k{EF6$4M+m!8}2Yt|2r z%F>r)zHMGVSRq$mnhUSG)DI>t*q7$Qmjmhtj}+}obK&X8`oTBqH+{^7r9agV_AjGl zj-6dUc+;n47CKQkc&DkB`N7S)!Kg4Tv)tRd!JX~3%+OTzf|ojJnftTV3r^~$Wo9d) z^7MLZndM8@3wH0TWk!yx6WqH>%N)6|PH^`+Ei*%~PH@5&Epxz$I>A#?%d8PyC-@+! zWkx=&6O6x0%RCXMZg9dLEi>QH+QHe$`%&MM&aE9Bkh&lBy|}C${5yR=>U*UVwS%=Y z_oKeQQ@Imv)_&CYzhBl4-c-4Wumg(|)d^ntpdXEA&#kqBBYJ6>3og_O7VV>Dc70PT zSRq`??31x}aP$Bz^Ou6PgT)4Enf)u&4mKI0W!9=yJGfz}mN}T`O4rmX>*bL9O67e`=Z08*2s2-PSUrkEj^YUs`6z%e8`umEC~7s*qFL4LnOV z{hDC|tA=TY4g4!yGi+eFiJGDJUzTY`-@n>%nHbMBrTddijOYH6{YfUq z^TQJTNhZegd9nT^6XQ8o*+a;L-Zw4MGNJdA^R-Oqy}=wU6MBy`Q_F@2C1|nV9b#dTW`mOPkfYz;>zQb}bWj z>BSZ;6Lx9SIxQ1+smN+A6L#s-Wm+ce(%?l}ChX^`8(JppXW}R=6ZW&nX)P1>bM8?s z6ZZ4M0WA~ubM`JR6ZSJ=o0bVXzw3dP34VV|%LK>0qGf`=KBr}ZhbtcmeFqmgqGf`8 z>Rx!3p4MpUwR3Wnrd~ViR%q(AbDh)FYiFafO}%#BE7{a*XYt}qy>|MNsT@%=p0nRK z3-Wk=^`x0Mp2h!a=8fmn>&?9Jym6tKH=aXItKS68cwSo_>gm1NyiiZ?EhmI}dQUkx z)YE(0-l3k}*MA!tWW65?3-$C~{G*oM^XX)4={=v>-?i|b&%f`s@Se{}S6g_`XZhnQ zZ`nMb+4i>Zp3k}6!n}EO^6M~f9(`Ue%$rA-3Wa&|C{?yFZywD}6z0vNQLkHi^XSv? zR^EKC-LjQ8-wRc2<<0j@AGPx4dsCH5#`8TiUMp|DZ+sf&&G#GST6=bBOYYX5UAq0Q zm1mctZ?y94QpCwto?W^uTX}XV+3HrFUD~>-wP!yI&1mh}Pua7zXFmrwY3Fhvmm!*A=d*X#jAuTgzGm3u$CWkX znMXT$JwiKqJwiKqJwiKqJwiKqJwiKqJwiKqJ;HeMx{2}Rbra*s>n6sN*G-HkubUW8 zUNX?moSgmU&1_Me+l!5{UyvJ_Lne^*k8gtVt)zqo&7q@clPTr z-`TIjd}qH7^PT-V%y;(dFyGm)gI!|(6LyLHPuL~)KVg^H|Abv){}XnJ{ZH5>_CH}i z*-wW3WIq}9ll^4aPxg~xKiN-){bWBG_LKc&*k|lhMlU;Cj`uHM-q(P6zXRrd5SaHz zVBR-@c|Qf_eHNJaUtErT3fIRz1P&3xG-Cvw7$1wrO=U4%lV+dfx zG_dyvbIbwEu?R57D8L-M0CP-(%dz+8`q=w}IW_|3m597_Rnj0McG z7cj?U!06Y1OyXKH?Z) zjvIhEo<_r6lm@n)D zLnij-@Yx`fePGCB9~d&(2Zl`cfgzK9V8~=&9WvQhhfMa>A(MS|$Yfs~GO;&@&jy+7 zt3xL5DIk;g6p+b#3drO=1!VG`0y23|0hzp~fK1-|Kql{fAd~k#kjZ-=$mG2bWb)nz zGI{R4XOx~kGChyT8llN$l$$K=&@*WK`c`pf>yqAPb-b+Fz?q(^Fk)?c_EYcypYLzUdZIVIb`zQ95Q)t4w<|+hfLm^ zLniOdA(Qv!+)nsx+)nsx+)nsx+)nsx+)nsx+)nsx+)nsxJf85`cs${=@p!^#V^Hpt|d3}kXl1~NG&1DPC?flQ9cKqkjzAd_PEDka`76+Lei-Sy#8A2w<3?Y+ahLFiIL&)TqA!KsQ5HdMt2$>w)giMZY zLMF#HA(La9kjb%4$mG~2WO8g1GO^YmCJ&il#N;6pjF>!Rf)SI4OfX{dkO|JOV)Bp) zMob-x4y}w}edgEg_SAOUPs&7&6%hhD`Q>A(MSz$YdWFGT8@) zO!k2xlYMo_WM3UJ*;j{5_SGS?t?|_%lYMo_WM3UJc~1eEyr+On-cvv(?h|eIS$fK9I?KAIRiA8f5Yw4KjI;2ARA^gG}C| zK_>6fAd~lKkjZ;V$mG2wWb$4TGI=ivnY@>TOx{aEChsL7llQ!k$$MVNYaIkpLz9NUCUj%`9F$2K98 zW1Eo4u}#Q?eg1#p9Ygf-AK#jps0|N7VKwy3k2+Z#Rf%!ckFuw-`=J$ZW{2maO$G*1} z<-G@lG2!=sXsrH!-rI`(9!`|^JqL^xf6oET-*W)-_Z-0dJqIv<&w_wB zW8ZK6*WPc9{Z7$;ukRG${ak#*f#2H&^ZUGDe$N-o@Bf1Nyfq9Px<~Jz##{2h8sQf%*L)Fuykh=J$!fvG1$?``%ZLeOK;cNoC@9R@J(*TDQ81~7kz0nFcF0P}Yk z!2BHsFn@=E%VWPg^sjw)h;yf7bKU#WbNgRC*FE-odcS+$`N6mT_`4rq{_Y2uzxx5^ z?|y*!yB}Qs@BE$~f7gq@0fKKv@i#!g{0$H=e**-}-v9ygH$cGr4G=JY0|d<90O9i3 zZ+ZP|-|}L8@w$fZ4f47M=5-Cs>l&EXH88JhU|!e2ysm+HT?6yF#^qSoxIVrw1m^Dx zf%*GFVE(=kn7=Os=I;xE`TIg(^y`1>_YY&wl{i+8zx@tfa~u-P-+l-4x8K41?RPML z`<=`GBhQtnks@9s&Sbsv(+N2=U7W~|R%~>@Njp51WBw{3zz-@!%Ni+$5pOHMPX<3( zMy&pp>fglb|51-vU5D$5l{{C;^+OKsqwYtH`*1n#!}W0=mV^7SeEiM##s71Aa2>Z3 z^0@uD56-tY{X)5G`i1(^^b2x`jeKHrUt-f9V$)7y)BZ@v>6$KnK8zz6_rW-VaUYB$ z827tK7BfOR#w!h*^&) zXFY;hk6_bIs&CpKiE`E>*z}jm%{Wkf)+6e$9>J_fFzXS_dIYl`!Lj-p_TNfhE7I2? z`vu*7``1^p!RRzJznsyPrPFXCae-2w$`$F46Sr%ZOCH*mP@um0TdIE(tN(XZJz{m8 ztF9+j@?0gC81qZrkINk{$9=dy?!$6$AC`~5`M&snZV#^Gc0wMvANRriOutZ0^UKsH zHgbrKd};cH`x2Y>5Sw-q<31QK)Q3IBID$=oxjx2$*o+Uc88>3w2mi*ksy!HIZYRc{ z8291!v%X+gO*yS=xDVQgawCV>$QLL#_a!#%A;x_$E~sPLPt5u<<)kmL83&d_`ZDrK zUtlwyREPCN*BX6+Szln*msL*d8tV(?tS_*UFTr>&&`&Vy3vAj+<*YB1v%bKrFH@iN z1!jGLSzll?o+Oj?Mc3-_r#7>`v>ZLZY=*8`k6_j#nDuBq4-VMeSAbcMVAdm;^$2D? zf?1EIJa*oxF=0JoOjwU#GyebEyyJBZdSpKY%zg-%{SYwwAz=1H!0d;B*$)A;9|DHH z;2)UsSbtKD3Hu=!6ZS*E?1zBa4*~Q10`vR=^ZWuEy~o-~z5f2E+R2Zyc97drz{iYtCG(m2cxC%?0uVeHm`(`lTj4 z^wo}jO!ZIS$>6;2^NjdthmW1S9bXd9ANQFvVd7ij<<*)vgMQWR{PBYh&aJb${ku2y zbhh10LGAa4^>(g&uKPaiMStgpKQom-95BbpaV95mt=n52YdjrmoP{<1!qSU)@n@N1S-TC^0<#W#Xj!#)&o0t`iTPF-f$XuJzdK)-;iNuzoha-!N0` zT=t&oB&fVpT)q{b`o3@L265Q0$7gZQouWasF0YjTkf_m8k58XRCq<{OujtyfgD;7> zhi?)$2|Xv`=F)9zx!`w^sn<~||F+3dk?6@m;)lf!ix%JPB_8tYK9RG=4&n}Pwu=+n zwi4$nvQ=cgvxT@snFw)a`g-CtFE@$<&T8WOPuGjX>6Q~8EU;ee8NZ15tD)<~+T-(y zXPnv~K07y?ID3{YV$6w2#FZCr6Sr$mAg&O1mpI;S9P!-Ed&CFPV~D>Ud_auNs<~*F zBjTf%qp3Ws=I{Lj|wcK%)}ng6psnt#rf&Oc@FG^&#_GK0Tp^YO%Qi)QvGNHdf;qI*{V z<~(hQUyM!fzx+WB;t9W|@W**tk@#XTsei)=KXIRUN&K7qA;e$4P2kUe>QmwsQE~j) zca+_K$WF{*L~;(J|gi~fg`6Hh;IOQgIP zpE$btEfHGvp^Inur~H44v@$?^Kh+)ayR(dV;!k(Q`TcW~P}u`%?IimK{Od zu2^cnQ|&wA=6f>xCoHW%-1wth{=Z)*B5qNkfd5jmPXlOk@@~XFW>v=lqt3PTHHdqz z%IRyAC7Xl_afy{5Klz z(BJu3N8=uSMO_ZzYMv%$o3Ji=?|J zKK{-nt{!qnRQ~xPahZF!#N4NG1=_!<`YjPMDhYAdVYkH4Hfe}oFZol<8A=54 z0XHY{#3Ogb$4BxL-z)e?H1-!I?$z|U$Tg-UagCDiMC}kC@y@3S{plb0i9?De@o)dO z9&y}Usr_-&bRga~GXtJsVm!m@*(S!bt)6*eJo9QU5MwT+o~F6-)Fl2UPv%nj?oRJS z75^OK$PzC^om;br_ka0B#2Yc4xa`Gy;{Jy}631(EOPnq>k@$7S>*Dgtam2O1x+HR~ z8$&#%)frLt?r7rAHXRo)tLySXLk@`#7LBFy6@~YS&O3FR6Q0~9@}`(fB9{od;JZ> z@oQ}oox&rCyUmCYtF{D*_tXfAo@@3IpDKAk6svZKI9nTKSO301ytcwA;XJ%e+^y7k z*lJy_Y_+oCemoDb;mWoX!?r7%PYj!%rGPGfeEB!g_VC|yZRb1-#EP6Rh|4ygBf@=8 zi4%98Db63ePrUlwR58BLE#lXMe-zo5UL(G8W1=`d;u7(rI^)EhBIk(boE<6JCOAzz zT|F1;GoB>Q)wQok-01}I%^qDv^=q2vPirqWKRZR`vRiXe__Xftx%`#I4~;HU`RpT( zxHIVr@rB2w#eiG74NXHzh*^_wQhEL-AB$17{~~_yvWO@o9uoJ>R7BkR>N)X|u|-9p zcJGMWv@0P}&Q3_}+oBv!tnqkKhTuSl$X zMW6B&iIuMyP`)Cu@)ZNhS0q-xVnF$d#L8E6m9I#wd_`CJip0uSbd|42tb9dR`HIv| zD6Uy)e(ic6^WIvD3z~Btb9eOd_`jA zD@x@n5-VR(DqoRU`HE8cip0uSl*(5mR=%QCz9O;m6{YeOiIuM?m9I#wd_}2zMPlVE zO64mOD_>D6Uy)e(ic6^WIvD3z~BzKZe{rScVt zm9Hq3uSl$XMX7v6V&yAJzY%p@<10ogUy)e( zijm4!Bv!s+r1BMsm9H47d_`jAD@H0`ky!bPk;+#jR=#4S@)e1duNbL(MPlVEMk-&C zSow-l`HIBKSCq6^WIvD3z~Btb9eOd_`jAD@x@nO5-a^D6Uy)e(ic6^WIvD3z~Btb9eOd_`jA zE5cUm^1+v2!y}Ea2-{Aqd_~xNV&yAJ6^WIvD3z~B ztb9eOd_`jAD@x@n5-VR(DqoRU`HE8cip0uSl*(5mR=%QCz9O;m6{YeOiIuM?m9I#w zd_}2zMPlVEO64mOD_>D6Uy;T{`HE8cip0uSl*(5mR=%QCz9O;m73IhbYaEPoon!}P zz0WjvufIYzEgVOnJnQ?N@}*2nd}G}X`BS^3#3#4>B3E?QHo5v_R}Q>Tj>^+_kC3nK z=sIyfo+*DQt>w%)GfRG1>kZv2{L6s+pwVjL`Hz2*;VHC@O+0*|ypnDvmEXB@Nc!Gx zAzRnMzg+zNBo&oUIka5-IlCBf*>6{h;oa*K-~4KgICo#$+q6?Rh{WrAQTe(d0kL9F zZ{nR_NpWzX-V4v#xI?u6vOSfz+ObDGKCk!JA1^&97AF6Y%JbejBJ$0+L2bxd@t6oy zni+yI$zSle@SU5m1>8ID3Nd$cw43v3_DFw%?V^nT9PyKtk>d52=Umiz)-FP1O%_eO zecgI7Y*`$M^6`xpin`ISsXR-OpT)b6rV*dbyhMzXbBRNX{wgkwyF~nRsiorC);+}W zrmqvldTk@FRd(Sw~;nH|}n6YwJm>-)-ey zu_xpY;*O2>iTLqf5%=u1SN!QDqIS;tW0&}BT?*pi4Y!Lm3sVy}`dNyEG8OT)FE)$P z*WS~$%hjH7%qY$M!?%h%cOTK1EdF}CNOfP=um3VcPMD-^`=wNs>f+4-ogd+FWj1e~>uM zl6vy}xGTi(YSxtVPCg-y-?N%LxJ~pA4#&rEw!P&E+6xw`?_fuasSH0-4@N;5bvzm#9ec!9r5!nMcl8K>H5i9 zybj!Jq~$cP6CG&SG@R;uSTZt@KlgCrHlxM`dOjaXd~C~}wEv#oiSkH!7zO6J}`)p?} z5fVo~CtGS279Tb7Q+ZU)vSLgt{k#p1S6(DfraAoG=VHXEvQ%gIm$gKNm&J(3tgIt4 zCoDibV_0o5Wmy*DpAOa#r;nr{UU#L6u;z%c=8mxDl(6QSNSQ;=yGd7?iKPAZ(OjEw z>Kjoa!7k!iX?lsnJ+={lJvUtR$*1=?89NUVnNu&P^6;OBi{}rg5%;<=OiUO(in#uS zA!5;uHpCs9^bz-GR3z?}w2QE8j<9TzuxymDY?ruxG=%Kfm>1oJ7+ivE-PUgXMcH(D z$p${CJzS*N)}DCK!;xZ(Z$5Fc0%OFE_K%5c)E_HCUu1S+D}FdRO1$Y`l(=-x;o^i- ziMT`Fequ_4`ot5GbrzNl7nW@omdzK|S|D~!)a&W3kQU`t064$>GiBjsdERdju=(bL;Wi8Iv z7E4#_I$2Uzw%0_lBz_i>({5@B@uRX?kl7;mk?h`3t+Jfh{b62!lz%qLoI_7nI0 zq=1Ne^9Aw!f`x>;s}6Ce{)NPzRgH;3x1Dar5ECcQWO6azE)${Iu6|Uy|M3iL)k(i1GWo^&5JO-_z~i-1|Q2M%Q)? z-4OV5Pe0<#_5TcfmwK3%-z1ZJxrc7s;Q1f9kDKfEluP`X`{i5BvgLPfp=`R&#D~M( zw)uw8wYg_Za96DFLA-6{RJVD^H^gNY&vvb`a;-6Rt+92jF?Vact4G)7dvVu&8TvJG zxmPaC5hWs%_psAPg>8Uw4PP@a#(4qUm)XpIdHS)IgKOaw)RD+{8jQu z*`=`df!}A|Cx_KsN%QEhpBKtqzw9L5+~614;q_VKM`PE>980s&wYl~!k!flbBz|6a ziJbWDC&cpU3YjU>OtKFJGj3PEzpo%3Req0{m}xt4y#D(|(^v6Grj!4O_~U*N;#|v) zinfbu6IZQ!REUH6ce->s%M7~w=K0=L>~N>czoCjakO0(;tBp`qW6QG#LH7G6EEBTMeTezcDe9% z-%5OY-AZwA&@|#LiPwsZlSdQBdA&iDJTQ*<^SA*qEd5Cbb1h!~H6rc4zlhHcT`ivf z`Hr|myEUTy>BItcJ`G(bGR)L#O`-dn#N+UkRNiHV6tBza{n{_fw~H;K<5GFUg1g1r zrw>TZXP@mA1CwqhKJnv0vGJ+?P4Ly!CF0q5y^d6?xk$XK7(sP{{eBZm3N>_b-;z}} z$}wZ|5SKc#Nsj(H7jdgptK_jOZGEWI>clEJan+Z^-Lo8!jhE!7I^7%Wmt!OH5{LBP zCVM?=Oza!ET^7yIg!pF9y>jul+U74wdr;mU;HUC6%MZ(&wbBt++;Bt=&;JLlL85=8tQa z%BX{tiOY9cF3XqHdxYuB)^Z%fuksT(j^S6od2t-WZ^beEh+~)>2EU0*E-Q#3n9HY~s?yCN52E;?l$>E={cR6F5fg z2b&nRU*$7!jGEZwF!)Ve+Cd*pT$F>o_X_I3_aWCw-|cnO%8+K#HHz46PG47acN=`mnJrGX<`$X zCN^E=_FW(!?e%O>E-Q#3n9HY~s?yCN52E;?l$>E=_FW(!?e%O>E-Q#3n9H zY~s?yCN52E;?l$>E=_FW(!?e%?Z-SaacN=`mnJrGX=22s&2Qy?R*8Rw9HNUO< zk?(4LTleF)b(6#3H~Fq4$K<;bn|xPdlkZAw@?D8dzN==P?@Da)U8yf7-<8tjd{<(V?@Da)U5QP;E3wIUB{uo4#L8DhzN;?R`L4t!-<8+Z=t^#~TzsX^Me+b4ti`e8az*j`Rt808kWj&DB{uo4#3tXB*yOtsn|xPdlkZAw@?D8dzALfG zcO^FYuEZwamDuFF5}SNiYNzrQk?%@u@?D8dzALfGcO^FYuEZwal^8y`@)e1#chkrx z|Nq!K^Jt&y@Bf=JOXdbN36Tbx+;d*<25Ay$l+c7w(SS-L$`D1L$V@WNT(kRrzpnY3 zhft&vC6r3Z*yOjL`*ohy>wVYf-O{(#@8b`D+_fI-wf5QjdC%~ApR>oOcU6w+U6rGHSLLYQRXM76RgUUim7{uB<*43O|98~8 z*88QW{?6VQ zIoFPkkJ_xc*>KK`G4W~Duh&?2)%-9BO4L+dv2Sqj5l7~~kFx%Y5lR=>dZ zJ4bCQ^y(MfedZa;_cs_2C+V_&GtP&zwz{TV@8c zKdr6y-}avpyfDJ?HND3LUraBnx+dU2Q=dV521X+uQAeS57 zch~yh>u0*^c>5QY1@$*+T~PSrYs-Unpi%0M5LV0HwkKWmZ^3EYcXpw?vx`UX>_T~G$M;8}ytCtb zrBL44@qJS$@9g*PMDOfEd1sdqy|WADon1!s&MuU9b{Ww-yHMWQ zWkm1nLV0JG5xuhu<(*wd^v*7ncXk=kJG)Tc+0BdI*@g1XZeH|0?nKtf>KfbVon0vJ z>}p2u>_T~GS2KEN7anL>IxTu<7s@-kwCJ5(DDUjjqIY(oyt7M--r0rn&Mqx_XBWyl zyR_(?T`2GD(xP{Ep}e!>`%UaCzW2mFty8-Y-YBSfSKn1yLKSW7AuHqu|lcE3Zh!9 zP-?M)s1_@fTC5KSW7AuHqu|lcE3Zh!9P-?M)s1_@fTC5T^P=#R{Ujolt7A(xO_dP-?N#qFSs_YO&IyTC7lNvC^VitWavP(xO_d zP-?N#qFSs_YO&IyTC7lNvC^VitWavP(xO_dP-?N#qFSu5e)s>dekqh%EY>xJQj3)q z)jNe!ikw6N-b8+s1_@fTCAE;EmkPCST&z%KSW7AqdrVuezR6_0AM zLaD`yN3~d?)MCY>TC7lNvEorJRw%Vt@u(Inlv=EKRErf#Eml0L#R{bsi}i}QMp(y) zYlroXxTaY5h-)n#)nbKGixrP*u|lcEibu6rq10lKSW7AqdrVuezR6_0AMLaD`K{U_!e)`em&V!bHlDAti;?utjXSfSKn z#iLrRP-?N_Q7u*|wOH|}7Aurmtawz56-q5uJgUVCr4}n5)nbKGixrP*u|lcEibu6r zq10lPi#eQiwwT*le~USvb-DO0h)1KSW7AqdrVuezR6_0AMLaD`yN3~d?)MCY>TC7lNvEtruBI{f5 zTgkc?{D#K6_PbK=Evt=O8$WmIC(51IEsxt5sw$7|wLCufOI_m=Hfo*~U;je`9Ut0Z zOuW*wT7Mgk&M`W^wc$t|Z~Fa`c*eOKlz-1y6fd-Hn{vSl%Y(rS7brKrb7gS!sT_K5 zIr-Rx;PYI+>iD4sV}jTFB$R*1nh+cgW+=ZqaYXRy3tHC~u3bMWIBnf99k2TRq#)zt zca(3fFePaJMPKE$*Uk(Ud@@=&J;#jT`u%n1;ePnVqlv(7sG0#DvpF7&z5Y5K-@kKq z(4b;v9Y1gJtl;*XTF(;>J3KC^exKG_hie`fAKYTss?E8TrUbid_E#=)+MM9^oqd!G zG?^a!UcImK50j<@Wlwyy}DetDbn zh(gPQCUd@3E>j{a*j@V<<@2vw9Mrf(YvaRRzs?WVxA{%S_w`H!z3*(Noc3lssIkiB zC#y7A7_9irJ+C!hw7W)^z3jZypicSH1l;IMz?tb@2+l-_&QN zJ}cJ6#~eAL$NlLev*PFP)SAq&OVncj=le$D;q@hVvxl{4mzi%A3if zTe~SAdMrKOqUBoU;!mc>Z^~MuJmB>?@$%O?n^#_#gLi*;=G9&|es1AZ4xw!LPjd)f zPV&@RDmlmg&9zji_HDGT?Jw)WPGs$yZ{zzsRXedpcdhhhsee!?ly%W_QC$MHD zV!sYKfpsORdLKo{LZ3lW)h(y;f2y9jZ1`{1Ge@c%6RgjZXh@M_Bws4e$xe4nRk&dY}XX3e>`pHKB9l>5o3Mk~a<<^QE8p?58?CnT;B z*7M`sW<5X7`J|qZ-g%zpt+SxL*3_l)e`;NT=4sIfTkoU(>AC>#cllI*RJj(SdQrWP z`oHu?_3lgm+nS4nx8?%(RH)pIW=2d0O-;*X!b+uHEpS<4*Nz zmg^#_UDxX(s$Ew;(O%779^=2Qi%EFvV(?6jH3jM)YYM#Q=#=YdQu#l%zDD!3=qH~h zzxCn2u)YR8PuHo*{i+_9Q{U5Z{g$Kk#kxh1cI0&mhP5f5f^5Jk^@PRQ^w`CDc4EzMX;n8UE9?gp%LT zHfsp%!tv`gX=Uk2NkW;)ZCQ6|0CA?mA9@C zxh%cDkjqNt|I~U<&C~vC>pi{weCj)caz7d6!1dgY`mQLS=ywLa^PIJ>`Yyw}7UI!4 zukR-O{qJ2z8Q!%(d*o^Tp2jEC|JGZhkrwsE{mXSaf46UKWUuRwqJFl2xnAk-_M46D zbsbjJhxRYmZT;Oov5~#5M~nK${^j~Luje_}-zEO4zpJ+f;e^)lc|Ah84l(gpeOV)W zU7r~BApOhrjDNRJsps>A)}Nk8e^GBAvLC6gtM&F(%Jmvvk6*4gN&Hp6ckh^<(7F|` z*D=@KB>t*TyLV2W(E1&(=QGzICH|_vx_3>T&^jis_chmHCH|@}x;H0qZowM8l(EnCf~fB0Xnzw>&GbG=&v>)pJbTe0cX) zC&e0A@BZzi_*RQ|e|S=?z4h;%PKIyp`1fr7z1II~&98U=d{Xq-_wLU#qI={2X%Cr` z?OO?cuNePXenvik?Vbe&eM0wwISbIVpNEp@+%U zqs|G@!vuXu!01Eb_ayQAocQC}dzf%rjDykJ#J9=b|AaOe2cs{FZ}yE1ZK{3f_xbVr z@L(Kq(fdJ<6!jH^=@N*we`zrLOM}s08h*g&Q|7OjWBWG$q*u1@6Mo>IJ-5N^xeaE| zZ7_RogR>vIRQvp&?4N&2XHI*G{*U9A%nEXSc#(3C&U1oW>z%HA@$?UZ)wN40H~oER zP_9&Y<*uI(3C^fgQMvQMp+VQs`Kj{W@L*1}D|CEPzfr+=X*HA!bQlv{(dTOAMMozD z%`07_d^G>mVD=$r^ZMcG0rX(bryel$q|yohu%Ul2{e$TroZbKbMH`MUwBdh*PyUZ! zXh`+HV;{nX`w+~124oU`WAy#QCt|U`BAERZ!R)UHW`9L6`YXaG7(E_+|9`jNWA?t0 z^a(#;_KgIyZzPy~Bf;n!2|r-;pY(nDJuQ73jKdziE`6K7+xOD%z3KaeANXhgOfdUr zg4sV4jQ*MM14a)|-{(K+=b61nDE-4Hm_0(l>=6oPk5Djsgo4o{6h6V|JL>!Q`;_`N z7>7Ojm-;q-FH^rKs&5Y)Y>R%UumPiQ>d{x$XT0?3IbrXai~e>$)$F}k=@Y$J!R*Bf zW-nGSda+_#F#5Rqe*Av0z757HW*iyZ?*U~*}vyP8;pbTofqFG z`?p|dgK;pv5#!rr|Bei8Fb>A|Wqcd|do;cc#$k`|)c7|3zVdBS?JIvj`2VA?KUG}c zr{Ble?=y^X=tO^GjDyjC*tf~vqnI`r2cvhfZhF>NpoM&D!KCVOvW+F%@vp2@yV z_P)xr!8jQGmVKM-J(+2PaWHx{`!?D8InxH?VDx$RZL;@*rVYly=n?JPWbY$Q8;pa| zU)s0v`%(Kg7>7OjRQopmvG#3J9c%wM`p3xM|Ng%9_nW^@{QozVPG7^H`(M`ow``+1 z@u2lQ{a@~Ra!$O$IUg!7skSseX)jBR}z-zWUQhJLthD*w;` z8*1RTskHeT{B3;={&!Y6Zp;Osd-KQH%Bp1J(zroa14IQt6w+kdfuPknv&$-w}%b3h0WsO`t7j9?0bhNZJXT& z_OR((S9|^^z8g9sXTjfB(4n=YOi>=${+@dF7vz z{`u@*3;s3b??Zq8XWv)chrVWipZNcme{S@M57Fb*0HoFb%VRKeNcWo|6pPsZW{P;Ft*jycM z$-q4G%Y;PmYn?5s^I-G2Nq*py_V3l*qP#|IuKMbj+K=l$H|XBg@yjpSVDI-otItsn zEYNXmi*eY4VP9fFj`-=n$$4Hl9-J1}yi?+<+h!;E^zC7TZDF%N*HQJ;u3c7;JGXwz zBhglPPg-8xSA%yh4sJ*VL=Jcu;0~VdYi#E(n&3 zPsDvveEM;V-MmvZ9C=__F!JC=ey~s&=RiVuV}1Pw zO5(+wOM=~YqmDl_AuCvVt$yz#@x=YhlKwB>&#F!H)Mv9giQvj%&VP$;bAz1E&)4z# z^=AbKt<#XJU%E2lf-h}1Ut`s~YgTZ&Y>V+tUFQa^#3%S;@#*XQyvOG{KD5S|BtO1? z*kJ#_#%KS!@XvqW=aAVu^gIdkEJ!*JQ=M=AIqaYR{%^P zp6c4EzM=>26%#k*oEMZXJwUlqsRhc||6tgFVbgwJIX!mc3XctrH2Y5Ne|l?NQ1e-< z{B8P#VC8G?E6>R{H7NCNH{~3^&QL#$<@;Q`uABP5Zpw_nRC!nV=PJ{J0!`DE!yyxc z)kA(%uHIstYJeVSxI4Xv>gm^WR$%LPRj%;lwBY8=9hIBam>eWl>UVGwJs%k#tZiOf z$KMXeCjBq?zv%O;iMJ?ss5>^WH$JLdX4<&m*!EYH>(rPOR2kP*`OfLnR0Fn!hMswP zssBzNCX%#4r*8v>jla(i?-{TAs%va%(5v(U4<0<4OMRwYv?kd3qkd~Caqif) zL9iErftqp>ePb!ZowI-O=v77SKE0+hmUUhnY`gBo}Ht3{=@0UA%YtO=<@Zz_1 zyhXF6!TTFKDt}dQRdCj0O_b|@wk9ZYahmd!achGkkC#=>^Vr(p$?0F|F`Ch8RnYF| zDavav$VxhwcJD2q+6H_#KiE_+r*h9Zvz4I-3>$EEo3=wvQ~R6eO%1-CexdTE=TBCK zJ^1H&xpdo$*G^0FS!O~pofE#_IXM`AAYaC+U9$hHObuFnR3hWT?eaU7F*$g8c>aua zpP!SsU)~4Z_HfCJ3ZI>mcp!apuxWMvj61i=J?gP3!5^JVW_%;Da!j2ZoVF!@#x&uN z{+JT{*t2BD`@&C5nH+4~nm?nva2*-1+N)$nC*j&M?rYxgTpiV4;@hdgRU;ZGciAvY z8UG6yHelFbTmFyDUk>zt`E|tPq-`(k_=x(c6V4C7um{6Gefl=JCN*;Q2bKmkJ~PUl zVa?!L34>+l6twl*I-Nn|U`5!1s|87gbsxByF3`2KKP2(El6tdDivolD35(-v$hu z@k`sM!T+K=;=#&SpHm(Yxl>=|^a@-;0d1aCZhkMgcNrUYAld_uWc-x*1<5SKo0|EZPJ8JiL8 zyXryZ8{19|%HMgd^4!W3gH@LoR(@$_^07OX{{!9s{a;)WEPZI3a-XV>;U5eeaCV!A zI~7-LZ|+L2%DX{qA9+)E{wW_yJE78}L(NgKfdsc6z(w z%FlnZO!Z(K8hk%Rx;p>gd^Rrt!v+i+F#P*A`OdmT_1s=)R$0<#~Oul#*@^!mAatTQ{v_t{HqRL=GC z6lM4a!v+kSgFVNo%`J6D>Nw^cjAyrjJ#1zkcuVb%_8pzHE&TX4VA#A`V7A(C_|M9u zZQ;ka0mJ5x1N+qeh8wbywuK+x1`L~$0}2PwT=~aY!Ty)@d-RDm{o}!}rhtwQAGaWw z(=Dg+eU+9Z`A01J>C`({0Pe7UageWKLFIe@oF7~}q=@q4XU8=bY!J)ex5buyru;g+t1*BD0hH`1{J=Cx}J=IF8`#*TvsGMt}EQ z^3P}gTJWzUe}DSN$lnkC{`dbcf4}+v`WhVYX4H5c}d&Ck8cBp%{y1= zcYYItKN*;`E&TX4VAvep>*j%+)dnPO3qQUM7&fnNHG0jKcy?~mw(#TIfMGMf^%ZJ= z>$@3A+rp1;1BT6e&7Gc&bA~5v3qQUM7&b@ZZVve-ePPnJ@Z;NnVe?=Ww|~w$wkT;^ z`0;JPu(|sNcMd#z&-kQm;m5ZD!^S^n{B6O$4fwClE8pIa z2mf61&%;>tdoyr8_ZvGkKDzRK%GGPnREB;qY{0PD(aSx*|7Yr$__md`)IQc`oZ8Tj zZx0)63ma?;#oLwAf#isf$$8~B0EeIvK1 z{pCxi#jA9-%C*{!Px9m2!v@>J2HS$MZI1TcYC_Mqc5FO$@yE)spC`pVuZ@4beX?%*POsHTetdh_U|ZN=TQIhLzu$7zumcK1*;0HFNTHd4fql>MKfBQqd$5eT| z6Unos%9Z)g=70CO`=2}ur+Pm1@3Bwh-Z<4gt$#0Cb#0%-)5RBuw_RE$MwZ`?*pl?# ziFVE1c#Ek$6E8GgqBhTO@0Muv^HSyFP2NnDJ$t$GOF^eZkrgYI^Pc-^;<6vsC||zm z#l*1ZK2jc;-ab*d*2hWg#{x4Jn6bc&1!gQTV}Th9yroV1#E0WQ4t>V|ShiW)#H&Aj zsv0J*eJ(NLo^8sR)7vIqobi?N&H~RTI{vgv`If~U5?6lzopPxquO;@p^UUYRT`Xcz!gU=PqZ9%f%09itWG>U;6ml{1J@_+ zh*eN7v29agdQZn6RQoj1;WfwKw)!IRM`_1H+V4mde86o>MqI`MGZvV!z>EcEEHGn% z84LVi+bitA0=snolkvaYdRlcGj@Y65uy2j(w&_`4C~y7!3Y+`AEz0vByTazYY?Jct zR+rmq#n&sZKkG7Ev(akhfv;4vODnEWP9Ij)c6ldD`ITN5+m0jMxw^ekCHwpf?i^lQ z<|51UoD7}R1EwA@^?<1dOg&)g0aFi{dcf2JrXKK%EzYzf8Rha`r&bKl*hMb3G&I~y}%Ul|A-j+Ew z7>OO-J$b7RQ)R_4r*^RUdN zA?IhAV?)l{GWUj@&*j_*G3R6dkbR$E`UKM_m_EVu36^6TV$Sp#{$;KUIj_nb7;?Uq zxiRECEOTba`B~=Dkn^_8u_5PknR{gojhpA?+z9bo0RLpfWh^jbff)H$*^n0mm}1EwCZ%wxuzGnFwebDiP5 zdfi7C8qT*eHyX~vGG`jj&oY-9&f7A_8qVi3_ZrUgGS3+N7T|v;`?0``1!gQTV}Th< z?W0&=#sa7Mzqrq{@BdWi3Fimcli{Cpl+Un{`8LG-43>E~#JmmWb?P&=r9GJTVE=lQ zc{Rj5jB%N74d!RCzYl2-|Fj3w9!z_%f8CKWo@&0jdDrZq`hAb+u_Hr6<7uOUYc6o( zXXft{tncx#+H8Ejb1<;aL&~50`gl;{rY6d>&Z`?dJEoEHgO#rhZd%q*dB@Dk!8x-U zD8CdtHz?8ZK4pm!++XvaB=+Ni85hjBV8#VAE|_t_j01w3&n%?-nT-82XIJ^4 z@z42H&sPst3f}!RukyQ>Uljyj=26bbcWY4QjNHoonmioLcrmB)#qYipoKqo(^1aW# z9hAK0Pdzv4EF2OvS^c|mX4d3jXEDcJ3e6AZ7IwU_%=+NZL^4As^?<1dOg&)g0aFi{ zdcf2JrXDc$fT;&u>Gcv}Ztv zjIZuICTw}6nvPd&G%mbh?`6t;-x?nl`|}FrJ*Q0wU%lW;Ko~C?B{?Xy4Fic`U7MQWXj0I*aFk^uk3(Q#HHsa`5yz>nQ`*B1?ZG^DU~~I>Vdop` z>M`9qU{E---A&3ouY7xGpgoxOVA_N6oAt(B^VAO+i!{P|E%aZJ-qx&cYZd%XIfZst~+msj-4D<@8Hho{_ji(v&y;iyyTf)=Uu496 zy79U&@9F(?|9=o}2*-WqIRD$5!bwZ|>-fa9Pr|H41C)1!o5ND;1}abOxjB5`t3k@Y zRM;GrJ2+UmU7=6H1ILCWF*Gn1n6bc&1!gQTV}Th9%vfN|&$y0!#{Y%ig4TK5wT9n_ zCOsYFx1)MXcWvS~b&Wzo5MDLPEy{~;Qlb)V~X;`ZcW44O{XazEYT*c`O0)< z&gXtyXk%P3(Ws^HO0qr`7nQyXpO#<7Y4JZuYEj z^IN{_x|!O~x;gEdtGk*$-#gAost((*G9eu;#J^``F*l&yrW?V4if*BXgxM0Qw zGcK5M!5LR|Hy!ef*W*QohP*l7GS#NL-=>OF-ZDpDb-!6NuI*u_Jm!AmE*{#$y!PNE z)%@F*9;W=mla)t)*Td{*adx5 zKNnKj%hQ}@#q$HO~-V{t2*Cl-ud3~ z?Qh&={=D05dvl|EOp&jW85$T1%vfN?0y7qvvA~Q4W-RcQ*1sRWZzSvg_08e%hUlDm zrQ<4!)6@O%3XrFU@(%bu+t6xHSpS$iCr7XNChSwp@uAIMhYuBW=kS7& zUxmYdcIWmTSAP{|t(&g@b{jVnpL+BR385O1?H+! zgO#7lRmNO#*fIBm?+3By2TVU;`T^4qn0~#;>^X#^F^FFI(fc`Gj}JyS#dt&ll{10#sxDjm~p|33uas}B#`^^ z8QLUgm0*5Ma#;!H%_PT_U_MQ9UkT>fBqx?&{!Maa3FhS_UzcFMPVzztFQ=!BxQqp6 zEHGn%84Ju<1oLC^?2usIOr9MQ%%{n-LxOoWd3H!J|0d54 z3FhVG*&)Gvo!n<8kki9{Bm1$yj0I*aFk^uk3(Qzx#sbTqo5YG59b8fkg+ZI z3C777Pj!rVy~Caid;j{9{8$|MG>l8$EP*^5*uR!(4?naA(;iHFaH{iD@@5I-*$xh=HDb& zmSA2^a%c(W>*RSb!FzQw;xZPPvA~Q4W-Kscff)H$*^n0mm}1C|_xo_jt+o8+t#%#TSfE5W>(p5@_4^`uvjp;Wu$O#V z0(m^J($j82@kcdClP?Y~#;9(CdN>pA9CBv@=f| zuK)Y8_$Yg09>;B#jkd)$yXX2k%g5OIuR9(+XRN*bn0v;r*?XLA_@Lv*ZX0jc^mWhs zH|`j3H_dR*_1o^AVCz};EPvhL2{wI>%fr7qcY^(RyvxsT9zVgZ95g^RknulK8<^U_ z)CQ(DFtvfH4NPrdY6DXnnA*V91~v;Hw7IX|tIt+sj2Eca(Ej+xZXGW)q=9{;&Ns?s z=iFy&T=BK?%aiW0=VZE?*fu@xvT46>*YPhOzSDmGljC24y7tZ?&gR2vb?ok=u2%Wh zTDRF!Ih@bBJ#Mixhr3wu({HxTR=B$5pSIp)&uHfAmhU-S%XVq7U;UGPonYz&Qzw`@ z!PE(+PB3+XsS`|{VCn=@Czv|HYo4EIPkYkkw8=OR$1Iv?^EG}~&w-1!PqdfZ)LXgT z+KKk=s=bs;^qOcNJz4KEd<}rcW?^g6R`na_3lU zrgYQmg$$i_(#G1`_I1@*FSj3K@4LhCRf9&`iYvP4c<;%h?DCe5Pn$K;zEI6^iR@gW;~*>V%y_ywza+gpl`P@Dei-nEcUqKJzHQny zwnVS2!vlNy8I_d_+-YpDRu?C+YKvll z84Ju?=Ld&=~%Cg;=2s|vqk&&qmU`QyRw+QaSKJMrBU z``Wvo?xf>&&l_l;Yx9P3pHGL{#pB(alWMM}9_XYVF!g|`2TVO+>H$*^n0mm}1EwA@ z=SH8ge~uJ>$QC~2Y5NyM4jK%JIsL?d`koR=(uQ2Danuo0V(U zu5W8~3zQr8y2a+1c!hGR>y)vefw91h1!gQTV}Th9%vj(xl}pFU7w@U_4;lYg)^nv} zwT`&o^kU;n$D04*e(Td#mX2-u-Q5E`_HpUhn?>Ax0>-Z_@9rO9KdO>@eu1B*7r1wb z@V_^|J6Fljz*u0$0y7qvu{e%cv_~v3V}ZNPEg9>aHABbA_`h-uDj6%Z%st~TZBa7z zX@+|zSmeTzv0Z~_>;CVxrbKL1Gxt8RS*sGUa%Z^rjQNfhkChta_`27N$0|fMY(-`m+lIVcEXG_J8G0BO%(!621v4&~alwoWW?V4ig5zb1$Ex&o_e*5_zbl6nk2Sv6 z{YKZis6=eS^^UtvE)g5p(DD8&O2%Fv<~ZlnlCkbZ-0%3K=a-7jAL;nCuBBoZHF3Y` zH*PHzTYaVb9VbHrV}Th9%vfN?0y7qvvA~Q4#(C1G`+ zx&7E!Wt=ldi;h1&KK?xSj0yX*s<>xToHJ<`xo1_xdZf@~wI@RZY!C~~SYXBiGZx1Y zi}r{GW-Rb4w-$(fdd$_3knw-j8(ScDUoE$vca{rRdN zHg^ZEt|Pqokh$-uyIw|KdeGeQj^k~&9x%m!b=OzU*M2cQYdLPYald)Hjk^X1)ZK69 zbadC|*+2bk?(gWX*_QTaQ@x#gcfV!!&*rhFE*CN2^Pf$*``o+xvDNmQx9YpR#E!Az zv$3nkC~)g9X5i~CM?r>uY6ep?n3}=V45nrMxDz^Di_r7?}Yo%fp%TGOi9pOCp?ctO5VA_LuEs%LVUe>8p?94(V z)lb#DrDDZ4xcY>A@shC*UL2<5i#{wVxsoBu82@sVd*=@O)^+;pIQ%p(?rIJZ3%?Q2 z2Ilq7SkS;&V8#M77RM2b_J{>$EHGn{`8$|dq;zcHiXN(=_b;Vl>t1*4&vn=q_Sly8 zVA_Le59XYV|Lcf7Blh$S-PM2dMnz*CdN>Xa7m2NG?U>gu?71!ca9c391#??4w*~vZ zL1c{c`t=#Ho*TT@j6e9bzW*Y_=JF@knpTs()cnTLmTS!ecYmh*dEd3Ba^B6#qkdRx zs_xpLyzQBFrbE$n%0HaF-c%gAO8J7_>rJPzZf*N#>pn71)^h8Mr>)&!7Ibp!iwA$c z(d=pyt)1V$N!QasL)D0(lX}3^1EwA@^?<1dOg&)g0aFi{dcf2JF8b|Cb5--&dhE#1 z)~wP>v$NPOdOmEbwZbfKf2(r&+RM%TUETfj+UmOFy1=v=;O-#{-L$~mw&f=Exn=fzbN%)km5eo>gU~QcII73KxWe9V%~hAXIvFzdXYYyM znfIH!^TwFU*_&LeS5eyUk(4Drr{>IcBV$^2UJ3Gy9qg*blL9egPs3zCx_1%eGT@AihzG2ljW?V7%8|Pp9+!p@1EtuPa zxhayB=w(>VZz`0aFk7xkwL~dcf2JrXDc$fT;&eJz(kqQxBNG1<=;zwS;-Qe|6QIby24I z@nv^>`I`Sz4G&U za>XWJ?fA#`Ib*GJJ07z)N9?p`oc-ulIbw@CIzP>JA2S0(=fA_*$IOvQE-o4WJ2iu; z8BEP!Y6ep?n3}=V45nrU zTXV*EuTt>xTru9mT-7&MjQ2MG$&)+Ad!7eh%N^srP|rVe$9RwQd#5}x_81{U1LJ}j z7tFX|#sxDjm~p|33uas}o+%iYjB(_qs0}$QYDO-L{|jZGLIhXfuWIryLalwoWW?V4if*BXgxM0QwU;o9~v4an~d5MhUyZq5}Vs*E~G#UM|*m-Ra6x z2b7Clyypz%0z=BhE-F|;xyD=NV#OI73Km^#7K38qf)I~z*IdS2q5Q^*+4Xj?MYXY>uK z|H6DFWAA?9o@=`IE)naux|WU~C|V-+-c#<`XH?JPvFGPGK6qO3Slx8TbvhS|-EnU+ z`~Jc752k-G{e$TrO#k4n0}q-fn-oz!WQ;$y{h-MV3+ecxdk&eFfjjOke>!Bgws7~E zd(#h_V4XW>w!U}76nHg{+JE)-QM3FdcaKW;eS+x|OrK!-1k)$@+zStyt{orO`JasQ zws)}uru~JFYupxvelf4LZmzts%ziVdX*1>5%+IE1k*3NIcmBx)Z68&BfA2nX?}ra7 zU;pYpQ)W~XJpFdFy`Vk!?!Fp4$DL@?(FLj8(bgD`kJ~Vk~H5EHGn%84JuCEv6s%q#rQ- zfawQJKVbR+^PU8HK6vf4*pB*-X{@^YPKzai#xCyAys@grT$$y{`9c? zvB8V)P@esDf!LJaZ&hAbr%>!@$(xm9YYN9ooag!*eAeXj*rio#>G)Z{6ph)?G3N?s zpdM(W9x(N&{zwm)dcf2JrXDc$fT;&eJz(kqQxDj`uPAaPN32qD_x!T*`5dtg54h)= zqCJk8_tv=QoiEn?VTNAeo{K+P^_wYBDX0Fw{(M58@K2v$`UKM_m_EVu38qgl?*V+q z{^UIg#>p7xoR4ub#`&9taWcjy??|`IPm*D?uh?|U{A8t)(=GFpwf3Z2<|kk2oo<<* zyrFQqWqz{yW7912lYhKF)iOVM)8r|Z`N^lJOt#EVb{Rg&GCz5s$He3P56RF;Jz(kq zQxBMWz|;e#9x(NQsRv9wVCn&%6aP^4_>BE?;rQXU<5MoD+I83mw$6(#pZ4U4VRqQ1 zE(hB$KGe>B!{yV`ei~xmZsBsat7{LjH)pMNdEEtrZM?h7@#bzm*p`0(6CF>#aR&;0Hy{oHGruBye-lIrUo!IfFD>i!N!)m=RPv_!!6q; z+R4@3{nGizCfN(399M&~Q*6_1rS-R|UA3vU$_0)etuoCPEadLBh80S;w|?mE!CqgP zZa>&pOzj_hbh`aEm%C4!vue7X|E;?pcqZ=*TXd$o2goWq!w!DV-2=4UJ>9->wYvux z*K4|spW*HS$k0!nVCn=@Czv|H)Cs0eFm-~d6HJ|8>I73Km^#4^=No8qRdI6&8T)ff zmjSl*rS4v(TlE2Ucmwyp>?}IKUj4rN9}kotV5@!N{`XrR9$=p;;O=z~tQ}x)DDUod zCp|IHewD}V!}Zk$*&S2dz8zS6u>GK@+vnF6A7aOrEvfsw+C@X{u{DlOtzq`@^6nTN zYWjhFDLP(c=%-FFb%LoAOr2or)bU6sm^#7K38qdkb%LoAOr79V*D2=^>{~MIIoJ6N zo3icGZP4Qfz3xi3Nw=$SI;@l zjoatBuNrC39N~@y_c?6H*p~KS+Jkv6`HXFgl^kSOU+}B`FK?|LWal*dS-IgQgKeif z_b792fjt?1xGk95g1IeNYN8Bko_&TNsXaEViz0~o!+LM2wKl8+mwGdUT5;$hLnpO?sSQkRU}^(X z8<^U_)CQ(DFtvfH4NPrdsmC*3owG8=rN-E>7FueL4Qr&OCfTrdT56RIYpSJ&*|64H zYMTvfu%+hNur^z2p$%)crAFGYmRoA44QsrmrrNOfTWZ1$Yr>`G(0Fy@%Dzr8b%LoA zOr2or1XCxNI>FQlrcN+*f~gZsonWayG^m~S8OL2}p$+S+rAFGY?pkW64ePO`rrNMh zTWYNh>$jy=(4fW}e#r1opJ4g~(ZGRCC_+pykSYO@XNz@=u}us&RBxee>arN-N^o?L3b4eQLMCfu<8Txu^3YSgiR z$bKv^V}Th9%vfN?0y7qvvA|M$X;35WGvZ2Zvtb>z)I1y3S4%ClVcoUVNE_B;OYO8_ zown3e8`f`2UAJLfx70Zs)PBQ18F3j4%vfN?0y7qvvA~Q4W-M^3@%50QGu8Z` zYQE+5h;7Nx<6rM&*l<4d8TS75B6ZOQ_0<@cdTE2YYp~Q&8`NWirM}vrP8;n1hSCrG z(+`+_!1M#AA29uZ{rd;0qc*6!Ml7kXHmJu2`*Sbtu`TVvv4Qh|UQYUOslMI&nVS`#_uzwvf7UD7%SZanf7MQWX zj0I*aFk^uk3(Qzx|93>{s}1VCp-1Yj4eG$bQjcv=9}bo}ZG*aTu+(oG)RTjyuG^r_ z94z(T2KDD)sRK8tO9xARxIw)-Sn9?N>e#{l98NvZMm=Ea0aFi{dcf2JrXDc$fT;&e zJz(kqQxCYtH`dI1$Nev4j6c*m(_Hqh%g0`G?tHUn`C~e7bT~NQG_CFOu`9n_V9FMI z#Lbfj7MiQCa=F=qr!O|w%za45yI;1%d^FVYne~>Mb-Nr_d@ReH_8({eX47S+Wq;@A z-P@O&>ieDl=gwGR>*+z;&mtFylM8TrnB@mO8=I38qdkb%MW-bb_f9Or2or1XCxN zI>FQlrcQ8;Aa1_g=IWx!*q`>i40HDgcki*as#iS*T3lE z_H*Ca=FH#TRDQeQY*YIW_j`2Jlv(DTy`6RZ($2F?;kBKVmvx(E(k6FQ{y1}%x&6Y| zm1kcx+dP@?Rpp1~%{H4$zpVUJ`#I+3M>-@i^iwC8I>FQlrcQ8&NGF&&!PE(+PB3+X zsS`|{VCn>)yM3!!*kqjQBxC%AL0iqlC&ue|^NY8dmMteJ=YIE7le@mFweGTEi@ER| zS8HAN&}MVZ62}{JY&Jt~c6Hayj(%(w40D`!_a<}gO2@H}Hkysg98Z|P!Hnqdc*VSr z%;B_%v(}r&Go8WZ6epKoru-mN>>c6gy_`KqgJZog@MF)T59U=a=k7yCT5vwzxLMg@84Ty zx`yv5&p%V@T8H#i9$Is``J{lWrKv^o>T7n z#9A}s2Y2sr;N8`x=wWw%weaXl)3R+Vwef!w84Gb43(Qzx#sV`In6bc&1!gQTV}W_k zfd8dlm4uo5kb7shFK33yHO2ie{H@XRB)Z?gwzLP+9!z`iJ7>;4zV3sJ@wX4oKHl52 z$!D{U_xyZk!_4EoKrj4y#_=AZkCdEoym#nZPfb7GQ*`D}>BoDGemE-qcn{JKdZcTg zQp6%dKjVTK7tFX|#sxDjm~p|33uavK6Pu@*q9Z5kF(pI8!co&q(*f@HWx>#Crr=xd z_hrDMX{PKe?ziu*;^}78i|#k^6Vd-v7x%mQXXWYUqj8c45kF)0OgDq}j8R^-WQJLL zo8$3wW}3e1N9*`EvPSLfj*jOnn{8ft&~d5FbIi0yk{Oz*4NPrdY6DXnnA*V92BtPJ zwSlP(Ol@Fl19zB|Vdg$QTK5|n|L=~aakIL))BN&h3G-ba#~tK6T(-~gL!W1wHP5^K z5X_rzF2Bg_tIh2fnEZ#58L{XSOrNSD@(HF-Fnxk=9lz8xSmo9Pkug5%#w>H0b?b&k zPs=iWmrm1TQTnGW^YQ0yozc1S8?p9RxBjT!7g^?#GBefY!=71Y^u@E3Uo4zuf-19> zyER>E+83Ln9Djd_>A%HsvGI$|rVegx)YGFDnU{WY{8aCSrbNwoYJb*q3y$~8CHp$T z)Cs0eFm-~d6HJ|8>I73Km^#7K38qdkb%J?}e8zF-zV#V4{9iCm#<)MXkTK442|PPv zo;kOjJIDGjpKHoK=a|=pZx8>p2h$!*doZtYY<3LTQimW`E>K2LT)XUKmX7k z+tMCPdob<6r+3V-J;;c4Z~D(>(ADn#r1!#~%q^ceJ}`HmDSofJpLza+AI*b9 z9rt|o2lL%b$KN&j-V`0=_~u%BO~1O1PY=H{t3GmmE~)peX<5bb(vEvf+r~~q-mSY$ z`8MwUXa7S|bN=`+J>Sww>^Af2x_hBYM|YXiE^+rluNT{GsupzjLS$b*nEJug52k)F z^@FJ&O#NW$2U9rhYK>gQ*`p`QH6z*GF#cFd4_?wwAw`@_Aj(yy4RaOxG5U zJ3V&LH2cNzp|nG0-RSpp|4iC{$gJ+rN4evhhfSMSeU%^j{;BFB#)IZ`xzN7~u9v)~r3I$zZpycFKA9 z(+sx{ix&RQe7nc(+q3q3XEtBw_}J%r%>(vb-6utMes7L7b6ot;59aEcj(Zo{XD$yM z|4{ZP^W_uC>}vp1gN{cUz|;Vy1~4^%sR2w4U}^yKTmmn7|7TNqo;$}HZTZQp=;xR^ zeS4gHvu`5e6>YrW<3 zwLHUGK6lHrt>yE$Jo8#Ur^~aj<@38dBU?V#%d@lP^S(S&Tjl}eS=%x{AkW~Ic>{Si zx6CIZPmbo>_Wm)FjB*$f$i<8`!WsXjAVwSl($(32=^dyI7nd_6>nq>}9 za&DHnLCM8g<_slAXPHZs+?{2PQJ#M-@{qbeBi8>V(g~(cFm-~d6HJ|8>I73Km^#7K z38qdkb%LoAEV%`X+>X!CEIAg-{Ey^bEb~H=ld;SfNgl~Ek0d!9%lwk$b}aKwlJl|5 zM@cToGEXHrBFp@hG_2D#;63FPEhZ|MUr_ zPcVIg=@U$!;8e#q)m)lNL#p44RP&qUD=cy&*e8<5u*jK!CBI>jO94yX!y?B5mVAgs z?gcD)5{sM+Sn?+pxf(Ff0iW?dG8UMzz>EcEEHGn%84Ju<;8e#~@=F%^E@+UvlSLj3 zEcqyl{1{mBR2F$Nu;i~S@@ZhnYgy#kz>@E>$iIOl4`z{<153WnB3}oVyqQHF51eW~ zp&n?a9x(NQsRv9wVCn%=514wu)B~m-aH@G&@<7<4{6Kn3ElMMaT45nrtrokCfD4_8n;ZY#gnyfnOvhM zYvMAwc2CyIWpYiQtf9-~T0dD^m&rANvX&jbfH$-Yi7b%LoAOr2or1XCxNI>FQl zrcN+*f~gZsonTq_WW6<6${3e5Q%uaz1`RCh#WJxr4J_-(GO=b2EbGfMv6c-i>&`N<#tkg% z(d5=Fm$Ix=%fy;EjPpGAS@lP;z>EcEEHGn%84Ju*)|n*2h__ zvjfYzIg9moU|CORu`UnH>%wRFrynr=fawQJKj2jJzpOjU#5y?mm-T3wSRV(Lb!wSd zHwTvWYnfP22bOhhnOJ8Bmi2C#SbqnWb#R$jmj~`JG;b!>>w#t6Tqf4>fn_~iCf4_X zd0*r+bW#tPdcf2JrXDc$fT;&eJz(kqQxBMWz`O_W8QN0apQQS|OZ7V?JwT4H&mzOW z^q4xnrc8QI9baoEJ*kebL6crp$JeGw53A#A)}*)9@wIHy^Xm8-H|d3SeC?a`$U43z zPI_k@Un?hlFmyc~G?4MXQxBMWz|;e#9x(NQsRv9wVCn%=514wu(zC*%ZZ3i^U|xz@_t@=SXtiBOK&U7`+4bkWqCg@y|66r=cPxM<^8<$ z?6SO{mwq_M*F}<{hjGD-3uas}}`eTR`$G- z9#fXRu%!2tWsfZBNoCnPOL|pV_SBLdR+hcCq_>r24=(9>W!alcdSO}i?2;Z?mc6{B zca~+3FX`W6(FY9L$k0rkVCn=@Czv|H)Cs0eFm-~d6HJ|8>I73Km^#6&pV?;78_H*B zmL5%({iCFJlVx8i>FH$IZ%TSSS@xll9#EG3siZfQW#2048D-heN_t6I_PLTCQ`nEPcZ)`jvsDpO{4-GcbP>eTE*! z1v4&~alwoWW?V4if*BXgxM2Rq`3w!xx6PvG8(8|eS@ePfOP@E39&un^Q$E8Fw*_-s zFt-KEw_Gjzev>gS-=4Po=Cyp2+VWf2@~vviZ)D3itS!HtE#J1b{HC^i^V;%T+wv`J z%WrVYH?l3i%`M-DwfKHFG?V?fV8&IQQCu+Nf*BXgxM0QwGcH)Z+nd1mk$r{+`DSsV zck~Tq`Id2l-&U4y94GkAW%>4Tg5P46Zz3o7jb`~)a)RG(mTxF0_)TZ|wsL~sdX{f4 zC-@C$`4)46--ecN<{tk>AsO1J2TVO+>H$*^n0mm}1EwA@^?<1dOg(D9yP(B4lzqnj zk#8ScerH*}iER1(W%*XJ<#(Co8_Jg7YnE>-TYkq`zPX&>_nqZi%n5$?S-y{)z_+2{ zpNzPS1!gQTV}Th9%vfN?0y7p^z8!4weRH1?SH4kh`3-dWcDd!Z(dC=wmfuX5Z=G9y zOI^N!ZuyOM`8K-cx7X#{&Hsp9PvdCok>>wb2X39By37gN5N^2L-drhGBwi|zhsuRG22th($ja?iczc1O8? zsQf;3ySv2PM?REdP^4opZUiV^)?Vf9|`?AG$|FzdW+G5(3 zXW2tJV#*Oyj+k=9|Ma^W@_aw9d#+W!-DmA}|FxLDF3&25{9^Kp^L+xWzooCvv-1B_ z|HkvB{IK#{Jn$?Rw>)sjb5nzi`!DS7fQ)-F?CyY!`!ekAfGl^9M#lXb%Fn$Uc6UI= zeH^Nb*yFHlP#)DKrY1rS9*L58-^hV(JxBub6tp)GMZ5G4+b6S1f-L z8y`kT?un3Zxj#a_<*5M`#$V$j*NRi?9Psi`$6n3kBoam?2eC&`$X*S zkBoapEM9%4yGT?%ta_uC$y2R8arY^C?y3cgaMV?i!-Bpos7lz$ok#R?c z-EEO^cZS`0k#VPn-Gz~H*M{AZk#PsdU9GETx~D^B!m5k%#gs3md@<#VDPK(aV!PA9 z>rRS1t1i0(!gFth-3{Tn&%*Ax@Z57@cS(5ezp#5TJojSQ-4mYsGVD$Y&pjG;SB2+( z4ZFj_bMJ=TZQ;3(!|uHB+|yxqVR-KEusbq5_j=gf0corY%YJMYW3w2W#n>#yW-&I0 z{N*->Jmofvv004GVr&*;vlyGj|Kw*h{jd7|)AM5YJ7l^KLiz39hfMcGi1qybcYQMX zWdr%e^euT-Id<CO)2QM&H(AiwVT5UU*B{UN6B%Cl^sE-`h9sY^^8=eieNmoOCVwmDZ^itrIR86`RSxgOJS)HLt@XKm z@`06Zd(l06>1~g?XOF$@UH9z0w>|BiJ^8lR-LqHU_P~4g@Y~*a&)$C9Gw<2+Z+q!I zX8~-Fz2}U8?Y;M$9k4z5o-+luSKo8iz|J6e&LG%+W1l;x5IAqY82iQ8FUEc`_KUG! zjQwKl7h}H|`^DHV#(pvOi?Ls9d!c=9|9oJj+un809(&u|Toz5TYA-m~Z5_Sk#Q0@&Vr&lv&RlkYh@V0-mFX9{c&zvrxh?Hl(xkD%WV zoVQbqonq`1W2YE9#n>svPBC_hu~UqlV(b)Sr`YzQd+o8$vuw6K@Sc76wm06hKi~Gu zd-m+nf?OcH8T!8J>_vyUAaqB$i2y7p_&z&_0EPJp)j16LJ z5MzTF8^qWk#s)Dqg!FP7#Q)?6+qdtv&tE>V{rq10|MQyWS>=#lOn&h{J$L`~d;TY% z{8Rs9XOY5sk?MkFo1J+~Yf5$&GOab)8OgK;WoIYT+LWECOlwwl)-tVS*%{2V#${(S z)7qDv;Ywo$ST<0vn0m$3E2dsC^@^!iOub_272DY^uQQT)R(tKNqURi?oniExue7s` zo^zLW=FxK=)6PPA&S}~iNzeIBJ3Hw)*J)=eJ?A~`tfl81sGY&|oDa3LnVxf_c6Q9` zY^m&lWhb_Yu}zF^Vr&y*n;6@~*e1p{F}8`ZO^j_~JByd}f|YJ({XAz9?F^vjtfHL_ z^qgU|GlQP9jdqsMbLP>`7<$e^+Sx zvzd0T(C5x?2F}|l#!fMIim_9Sonq`1W2YE9#n>svPBC_hu~Tg4BE8P8=2^PiSya#Y zRy(8WIrnPkVLj(z?M$oZoUEO7^_-uzvyfhAY*h}d@+nhHnPSQmQ>K_Q#XOrT6IMFE z0j0xA|EK56&R2S!$5ehhcju|bRtVr&p&gV^G%I>q(Pv;1H& zbse#PE!M6hCa}feb;Js`*u0Jy!WOgF5nI?|`8r|_TZ~`Vx;z%K#r}1~D7Kiuj@ZQ( zE7%d!*kTAfVjWv-VMh#Pi|^_bCt0?^vKc$Y*eS+NF?NcvQ;eNr>=a|C7(2z-DaKAQ zc8V>QtW#XyJj-T_sq2XSYq546F@Y@xuOn8l#pZRy5Vn}Tj@ZH$%hwTe*kTboVi8;H zUzcJOHy-MUU2L&}9Wjk9hOi^nvBeg4#6Y%qwoY-9Wg9G;u~UqlV(b)Srx-iM*eS+N zF?NRZay!M?DaKAQc82`_(2w!F$bMM)^S@_{59}0MSm_ow*eT|)*y0I0#Ud8x`y&2U zW%9RT{#MN2iuqe{zCW?}y-u-zRlddbb&3frws^lzv4X{UpYyjWhrbo`w_^TQ%-@Rh zzc-6l>=fTv5N!wj1f{qbhxk1ky2_Zl=kq!)*+^J}l0 z5qQ9abzv;0{7P?f@T(zR`B&B|OXXBs8Cm6DIhfCYf?E+oxD1gKWF@^RPTxVtn%2i=Yo~V&Q=3fCi`!? zYh`Me(rK^q;|G<4e^fqxQ@!|8_TXpPiT`Cky5#kO^E!&rQH+jabQGhb7#+pvC`Lyy zI*QSebm>Tb=_pn?@|zeP#pozTM=?5z(NTcze#p*?fATi$JTu(^c$p;N9p2)tDkn8o9q>S=dW38 zo~$hLenZE)bGtVS=^ZD(=qg;^JaF@FFS(=7h_N~st)Jw2G&?k;U;F9HuF0H|z_ZSr z>bn1aOyK^9O>-TG#QRD%+&9e~*ZGu`zHiCdDSwsa@eUM~b486yL%PbZ{QQ-HRd1Vn zW2`6H)AO1eL%Qs2aoR0`W&eT(T>`6J{a%W^{I*dk{i?l(r~Dq<8?D^oD0S-H>_UrGkf2`}D+NE^btNi#u<=`KckKa@;{**oVS$5)o*^e%H zyqn#M-#Aqi*J2Bdc(N2tZq^s@ZmrulKCq_Fl+KJIljCNwQ6Qi9N?Zjv& zMmsUuiP27sc4D*>qn#M-NSAixmv&;b6Qi9N?Zjv&MmsUuiSv5B`q$x$8QghN;9F-dE$M#q%Ypr*`6U}RP7Pe6->j0;R?i5$ zsCThstA@qEZ+tkTZi5 zlimyIvZqbi(!jEFdC3QXWq*z?d=%}TLz&};jaV*ddbHZP@JN~gWbj~`SH{t4xm`%U%YPuYW? zWhefZ{pga{3znvNMn|QiqZl2<=qN@2qd%5%MVi^cL~1G?jDZ zRdG%c%0J`#RPW)-;@xVpr|Ft_@0IMFa`DEHNA@4qF3wHVu3p0 zQ@!|8_TXpPiT`Cky5#kOr6byj(N2tZVzd*Zofz%JXeUNHG1`$X?Z_|f#Aqi*JF)7O zZ^dXQMmsUuiP27sc4D*>qn#M-#Aqi*J2Bdc(N2tZq)R*UOFJ>ziP27sc4D*>qn#M- z#Cg3sK3Cff8L)pCo2_|gN7v$(0|K8nuBmIV{Xv0u{dzxFyyCFHCm(;98+J@Qm$Bx~ zf@^+zJkve%tm9n!B`1YEmyK!dn$(G7$P?SNb;G`iG2z$ldy;G1;Hr>E=}#XO$A`+l z!w&a^bd_`Ci!mO%%CE8_?y*t5r`;OwE0H}%U-EFsFFWh@i{A%jf2EHHhIF-SNxQfw z?Zdk(r}Wob{ZUH(1Lv(PrJUt;mX}igq%reKsrTm}d@1&fJ$-5^cCM;6u@w7XXgQ&j zb}60qDnEWuIrvBA<2TidKV=VomYw)t_M=N)FIbwQofz%JXeUOykiT3zG1`gIPKqn#M-#Aqi*J2Bdc^Lp8s)92=Qo_U0gy*={_86Xn=6IjnQP9Ua9gUpk6a zuXGfnqgZxIN3raej$*Y-I*R27($P`r=qN@AAUH&{65=C`Lyy zI*QRzjE-V-6x+Mc=f;_y@r;cDJmVZ28+gV)HfHdQi)<|6bK^|UILgK{%-IMe6GnLanp^to}SXS}C+83)Rq+&I(c#+g1h&h)u)W=gj)K+11pgH(=<8B+N+ zmPqy57$ezZW0hp5ja8EUHdaaPQabHbe*BC`LyyI*QRzjE-V-6r&^QxiM$ZQR(O?Mn|#g)pH?6M=?5z z(NS#k)?#j5rHuKz&2!6`*W3KJjQPIJi_2ICu=#RXZe68}bpxA^m$9B;^YJp)8EigY z#`=TOS(i|L)+=m2UdB2`DF5$ul`_^nWDn~hvXgZZn~#^Vexi2e)>Vq6+dQ{Oew+Um zDaYo;MasANaxu5AQp6scj~B7i=Ho@|xA}OHb}60qDnEX(`FIikg!2DhS1IC8*@K^D zC;qqjcoALldco3BZC4&K+KJIljCNwQ6U*naO^kM8v=gHp>AAI(pqqg}{fuALa|#PYec6Qi9N?ZjwDdTuQxXs2|v6QiA2zZq#K zMmsUuiP0|PFMrm=HsVssRvqZl1S{&F3~=qN@sw0s&aQP%zUSIATgrD{dzMT2{;Ty;z6;y4U&{Alt*`POS?jcXU)DM;-<`Ei ztFvqnhhvY{)v;6S>e#P!b=swL+N=EdLFM2dm5<+4FaDH0_*r)1f7y>N zdA(rih<0MM6Qfqn#M-#Aqi*J2Bdc(N2tZr1NbZ?UasoVzd*Zofz%JXeUNHab7RmKj3)oY+r#x zU)yis(B1YSIDQYdKf&=kv3(1U-;eEQaQv=pUxefLX8R%>zeC#>;rM+jo!_nU^Lth~ z{LWQAzkk)sb0K?pUSucFk?iOBQoDHWY+pf2xBUhwzwJXv<=Fm&RKD$7NcGx&hGdWJ zi%53bzKCSM?Tbk5QabHbe*Bkr6${zeIJMq8lN0+=_urx(GG1`gIPK1ZcLJ2Bdc(N2tZVzd*Zofz%JXeUNHG1`gIPKsxkEdpqn#M-#Aqi*J2Bdc(N3J#Ye3;Och!WI;rrMAyT0yT`784JKVNsHU&Zfk z+bx*o7Ia<{^4!q#4LAMf_zkY@9&fs)n?4WebDn?G^;sSF+I?MRwmYKXHz9pN%h_)4 zJ{tm$JZH8WQ|G6YzUzqi-A(!H)QJ1>RL&d6{T1@4{JPu4eS@lZ-nmadK zWoPBaF%GBfpEoG7+I2%&qaEpLJNc!Z812MpCq_Fl+KJIljCNwQ6Qi9N?Zjv&MmsUuiP27sc4D*> zqaEqej{MS2jCNwQ6Qi9N?Zjv&Mmup{ufoNzxZQfhZ(g6YeAR7wH1gv+m$_x{M4tU^ znfv2__${pQ^F`Oi?!nPm@%Pr=oqpz^z_%{&?uBgz2Ohdl=9YaNx$EVb8#Lq5klyZ& z%pLf|V}X_a?%hLD{)f&R8d&ALvS+-9QRUb9G_vabw#TrLNA_GC%q;@`)Jj#Aqi*J2Bdc(N2tZVzd*Zofz%JXeUNHG1`gIPKC%q; z(oT$aVzd*Zofz%JXeUNHabB;jW`5w#+`V1+-9GiyGWSQ@$Q|!q?)>YK`?meiRqSzc z$n$B%74DB-agU{cc7>b#)~O-=@V!5Bm%7sfcj)_(EBo+_!0yeD+`$9S3cT&|kK9dX zpOexj?s#6xzt@uU1FM{F*T=n@D*wQ>9Yeb6{iqn#M-#Aqi*J2Bdc(N2tZVzd*Zofz%JXh*uVBfqp0 zqn#M-#Aqi*J2Bdc(N3J#YkrlHPO)zEzPRYsQSPflBG0?vDcAqm$VY$mwCi@k3n9bH@dKp!*oN?tvKJ=72k&b=QACKBVt@&~xsKJ7R3Hxz9Z3PT6@m&C!45m$zIJf3f8`05 zUfwRH(_ZDr4=M-$sC@jUdhw_1!O!!}PW&(X(Iu}JEKSi)jCNwQ6Qi9N?Zjv&M!S%| zTstw^kuL4XFQ16fPK8Pa8E!w)0N{@?39 z71CATqCF#DKVrv}K5+jXQ~o>O+98#5%GEoh^4ILJL#lW5hYgcGkBn`Y?A-OihROcJ zdNfS!QabHbe*Bkr6${zeIJMq8lN0+=_uyjN_G1`gIPK)!F5CEuPo zKeBv2{{ENavtZBBho{GPnY4R!zj(e++NCo}mcHbt_>Pm-{TIh~oXRO15zqIj{Celc z_nqq9@M~n*bM>9^-6uOA{wT8SzrI0y_o-bin?+XJNtaK^FJDoPd`S87E%nOh*dy(* zQ`%v_w4+^0r@hLLA5;$hQTg~y_2N(2gP&z5{+IpelGh8Crf4TdJ2Bdc(N2tZVzd)W z3)w72J2BdkuC|k3J`tmx812MpCq_Fl+KJIljCNwQ6Qi9N?Zjv&MmsUuiP27sc4D+6 zUD}Z!KcJn`(N2tZVzd*Zofz%JdA-D4zUZ2syPdYVBR)I!dtP;4Wcg~34kaeH?UEbUIL(IcgQ^<8A;A2UDhg;qK54!u9* zQTffz=owh`R{S}#?CI8}S4fw3qd$l&?RwUZ`>55fbDKt1+ew#C$S+?}j(kY@@-6ks z=h!3duv6M$zqF%WN~gWbj~`SH{!#h(P4(hW*@K^DC;pfH=#tk9mZoaE@`&XV{jC`7 z#Aqi*J2Bdc(N2tZVzeV&Z708cB1Stg+KJIljCNwQ6Qi9N?Zjv&MmsUuiP27sc4D*> zqn#M-#Arvlv?IT?6Qi9N?Zjv&MmsUuiP27+*GqieOJ!l*UTydPi7cNS{dGJ;CtoeT zDhqk!!?Igm3oPI6{p+m2^7(^nW(SsbZijh+rCsyB3j<5LbPm_jn~sda zxyP>v9LnGSlfbHX$mIB4L-yQPjNdh6XI&S+Ysmh`_F5bAt6ghvi>$VjE}xKJzM>rY zkn-i*z02#B&#_0^VW+gierZR$lumn zqn#M-#Aqi*J2Bdc(T;R!M}BE1MmsUuiP27sc4D*>qn$Xf*UO*$qA=z_o-3`gk+n0Zr>>vH+cd1=Ur@hLLA5;$h3FVhRcd8eE${zeIJMq8l zN0+=_urx(GG1`gIPK1ZcLJ2Bdc(N2tZVzd*Zofz%J zXeUNHG1`gIPKsxkEdpqn#M-#Aqi*J2Bdc(N3J#OUyV^ZD%|qpD@mm zuNeQxhm4ElTgFTBIpZj4!T3trG47IfjK`GDI8FH(zo{I?bt<3np6X>BD0>(m%1*|O zvY+v!+Qm3iZ6{qmA-{Y@Ir1Up%eT}kpJR`-z)oq0{nCzhDV_EzKYma-_($dAH`R+j zWe1ZcLJ2Bdc(N2tZ zVzd*Zofz%JXeUNHG1`gIPK{dviP27sc4D*>qn$Xf*ZnnX z6FUV$&)Bwby^qF_pE}YTgyucL>s8blRd;7qj&#P0|?ZJ+L zr?;wGIPk3a9c|*%bql*(b!p81QQg9ilP?ea`?qxq>>sXR=_hu*Hl!>6PP1-Ey2mh#i{HA*G zr|iMcvJ?Ny{-jGzFSL`UXeUNHG1`gIPKqg_ZZ*G`OfVzd*Zofz%JXeUNHG1`Uv<=TnSj&x~9erYF0J2BdY{N>t- z(N2tZVzd+I^|EhyKKI?+^L^I7X?nif+P6;6_gwo1>iN!V-$p&(f9;#8=ew|dd-Z%T zwr{VV@5uJ;)#tvOd%im>Ki{KOPVT$8&wV%dx$ova_ubs*zMK2pcXOZnZl2QZn`X*y z-#Sw{_6;cyY32S3YB z{BPf0lP-C^U}>6X`vx8ID;*uh=qN@A7#{!9PkzN3qJ6j$+j- z9mTRoI*MhdbQH^e=_ppaq@!4VARQf*j*en<6r-aU9mVJM(H%yRF$Ecd?4a__s0_lwHUz3;Nz`!379@3P$cF3Y{|vfTSFrCVQ=@>?I3%CSB( zm2Z7os@M9uWRLZk$xeH(CHt+ypz8 z?eaQ`?cEXbhxBqC#pozTM=?5z(NTz59YcLw@`HNJp{k zk&a?}_XSty;cebXKF^{mdri}T8twCkXJ8W$#V?JVQRvGgYTg%Frzu1~s z#=OSX#4_ePwkDP_4^lewBjsn_q;i-~seI;Hs+akf>|tIeJDIP^e&%s%7xOz?Q%dQ! z)|B$w8dNIB)}~VVwq}*;wY98dkFAL%J8exY*>7uNsa;B^y~>XtR1W@8`S?xs;!oLw zpJgZhm;LCH*9*?;C`LyyI*QRzjE-V-6r-aU9mVJ!G94(NTb1S- z$sXI&p6s+e?a6-I)1KO;blR)@_(A31AC-^aR4@LNJ@{F6;(y!Io^;9U1?P1X+ur_= zUyP1obQGhb7#+oSrXbiUMn^F^iqVnu+}VWSAEm1t=_pqD(ow8>rK4E(NJp{kl#XKA zFCE2dqjVI@52T}`($P_jj$(8aqoWud#pozTN78d=6M~LPM@KO_iqTPwj$(8aqodf? zSbXj~f@i(j)|x!)*tQ1cS>Lv`DbKpMty%fpcLdKmxvg<|*3WHC%(Jd;Yhph49l__m zBlz5R1fTnk;91XCy}9oQKKC8L=e{HO+;;?@`;L&(ZLKNgw>79#j;&3l@@>s3)oW{6 z$sSwdN_N_sShC;N#8SJIPJ5LfKd2o16UzVlJ3{iO?7`2n6aU+qSkfi07o68oY-@ud zzZf0G=qN@F6j%M=?5z(NT)|=iVrM`+=UnV8iRb)_oh9*{i?OpL zK6eht=gt9n&ey1%+&LhhI|t-*=YV|f9FWhQ1M<0ZKt6X4D5cvOjg;TcZlrSTOh+o; z&U&PJ?F>k=$Ig-@JMAnNQii$7%#ewLm1-_DXGUGjRt zc^$=erY7VUqoWud#pozTM=?5z(NT#ezfix#yhHsJ^AYu9%v03AF@I4%$-GAWB=a5hlg#gw&iqdKnct}# z=65Qe`JL)zekXgF-^otqce0=Po!Z6xPW=q&>VL?ueu;9_Us1mLG3r(ShCS*hu~Ypd z_N$+yT}r3D%8wsZ4*pU3_)YcVPuYW?WhefZ{pga{3(o5(Mn^F^iqTPwj$(8aqoWud z#pozTN79+!p`+5#QH+jabQGhb7#+pvC`LyyI*QRzjE-V-6r-aU9mVJCGn{F?EV z=HraJG#_W2sdUDf%Fj4cqgeGa&O}G0qoWud#dg-o=g!}G&Ux9{ zD9`yXJ2T}u7iMR;Jm9hHubVssRvqZl2<=qN@Q8d# z?=sGLssG{pm-;2ng{i;dyqNki&XK8q<9wO=J(PW6-6 zuYQttDV_EzKYma-_($dAH`R+jWefK= zzj0nn{^T5){LJ|>>BYG->BV_8>BTuUrE`8w`8n67ayaj%@;L{mdO05_dpI{IJ2_7$ zy*Ov5cID3BrF8j${PGXw$ZwP{e^Rgfj6Ko|JEa%)OE21`blR)@_(A31AC-^aR4@LN zJ@{F6;(zIdE_uD+ypCe|LHWh#C`LyyI*QRzjE-V-6r-aU9ZAof#S8vXIy#EcQH+ja zbQGhb7#+pvD3%|juNWQ0=qN@AACbK}V&dqZl2<=qN@DrG-${M0Vu_*o3YGSV%! zVHx=?=3yD-SS-Xc%C{JaWz=i26U(s2Vk(wlr(!8%zhWuVE~V36<;M>y2mh#i{HA*G zr|iMcvJ?Nyessy}1?P1XqoWud#poFFm+L4-M=?5z(NT(n11M}baWJ>qZl2< z=qN@lReY9#;;CihaXV15Zyv->)XP2M(dPw)ByJY<;zZUrGs=H<_uFV3U zJ8{>H`P6UCnq({Qdo`rj>Cz-S?TmPSoVzcr&Qz~#pk6Wcim6vjy<+MWQ?HnM#ndaN zUNP;>bGbbQ`Jp^Lu+r^s(^+yWvp`#{t^#c|8w#}DY%Aasv$=q;tStq6Xl*RuTWfm( zpQ}E!pkCQSy<+MWQ?HnM#ndaNUNQBGsaH(B;(Wa@e$d(xd00o%|JfKjoOx84wLXlj zx;|<#Dx}MX)s>zJEZa^!^7+8BdD=7azD2dg#tb1{ZQQC&JnyNtA6$KINS8hTwO-ny zdd1W$rd~1iim6vjy<+MWQ?HnM#n#@8_U7A8dU>AUlk&e!Yi?F%Mq8||j5eAL8ZY6K z44;_I8NRZ%Wcbk9nBiMJJNO(MWS7|->Xi-DE2dsC^@`0WpN(ZKto0Pv}GBEBY4s zkUmGgr7x1t>7%3teU~(%Pm^}EMViva+ppN(KXYEA(6?XKe+R!+hsZ}wY~)v0h}^oY zv48rE9Ydb>Pw(QZow`Hdw&ynSJ8#i2@KNvX<~LolUEr-NH1%Ddsvr2A&zt&sFVqeE z>Ic<)z4o!p>wo#Z`191pA$|C*Yl_v*-7WB_y=N8gU9fZD(tTzZo1L?3;5|maRlIU! zlfb9lwXk^M(3rpR#kf{ocuuKQO!RrcD*O^SDim8{?#CI{WtF^uIu|< zcs7?`cWd#fvF`_N)amBp-QUN1C&w?ksrd96G5&2f`R3y7FMk^HtgYIm*zNmx*W?Lr zbS)nIO}uOJ_@1{GyY!Cb^m*de;&GQnerD3G#TqRm@3Ux7y8GkJN&SnrT=qsN^NN=q zDBjlL&A?q&_b#^oA)a}!)A9adqaEG~>35WLFV>tF?~|>x^WDY$zm50F9erg zeVU85YwGRy6Y`&ba|{1?)o5qyiU<1Ar{mf7!3Q1aFKrmlzpwbSg|G0)@{oV#B`y4x z`^WodzwCT~Z(b+f*ZEGv{rwT`<5~O1?`rO6?-9@7Pa3(8@A*)?>-MgP_x9bMiT1B< zzo+kVTeP8F&C#V>AGB}KWnqtJORxO3dDOA}^QFhEkM|W0?mM=$_J3N0^mP?qD80MM z!GYggIJR^`n?nOnUG;ovvD4v!cR&8Q(mIzN8F=3+V@j8nmIl7@fn!U%zE~mfp7+)* z-D|7=gmzuux>4!2OJWS+C0jNv9ehzt?|x15(pR3{9P+Ggdq`=sMO%cwEnHDrI=bOj zfouJ^b!qE6V*dT-ep7O8&B(8B_fE-wihoAGZPTcv!S>Zd{^?&dF6r1`g(WZFzGXuUS@ z@RE)TV_n&t@g-|(NA6jDX32~if7@{O5i#aut1qUNuy?(~#L*>(HHqiiwy!d%#-c>blN7Si0|h@%-JR@AfNg`QW*+{F!}9@4Dgq!1p!iRqC5`2wY=b zkJ2_nV!huDzNfVMo6(+;8aP1F5WZR?@oNAw8ybACg+Nw!%C;za$G29 z_?@*iz6x5@++4eGTKO||)V*~I>)XfQWaZ!L6!!Q&K2x1K*DX}qK0Z?qzg@TR_3Zde z)!eOKVa>YuOwGQcUSYdy<1@9@uzH1)OXKs~dq%y&&4t)M{Mmi$RBxT*w@m3nF5NQa zU;5~lshkH^Y?;chcEDDt-a`g&mFyX~b%kW-`S(;v_CN5S3aMQ+f8C<6XPwVNd*^rA zqVV3iF}8NCew*DRZ^wIVKUw^j8_^>EHr`$EhpW10{EdD3;BW4&JK}Gz*WV zKD=c0FD@&Mzu{SDY;;$aR1N7@e!tPJxT134^^-QalEoDRuXyBFSM~1rdv4}7xHgBy z-^R|n{o;Cci{~Z#*Z$evx?AKcs{iEfx%RT~w@bGB(G9z_Q{a2t53W|tO9Nln<9kNuM1a%za2g3 zH&+-R@3lX92b>X*Pt_!^TJzE$0m!J21zrogp@h9ID(hqvFLSf;<@$BcsohlSY zbiE~{HypH8;lwJp2JW);R)z70M*i;BEeqFHi2UsOEeaKHi228K-l8z8TP&y3mz&+= zrLp``_f#ybIrWlIPP+{i3&oQ79CaO0sj&6^@wt28{>p_DPCYH;xqf7o!V_=AyIiMz zR<$tU&(lFrka%|u}{p%JUTNwZL=UR0Ok6aV~cJu>v3SC}_ z{7c0;g?5u7U%jMJVc#WjEOGQF7NhU{_#1oc;vEa^Rz@yawPWG4sj)9@b$X-1)*r{; zmnwt=e-->J~F zS{#!c)OV*sojvP^^zj$%R2XqU9K$@Yo5dd7K8|hvDr;D%arD+9&*@{gFMNG-d`J8_ z&hCuaGWOdC&u>t;;m6;?v)Q9+gTh`b;vLh^Tvxwv&6jbUaLHfw3e8T6V~H7uzvX7v zd^(i*!c%kIxw||SxbwktU4@;V3|!^sIj(l~QGw6>bdEdx#}R=)*gVH|STQ{COKs=6 z3l=;PxZ^>K-5y88SgAX&Ug2Kv_HlSxn$fN0#%PcU*@lvCK2RUF>>Pj(kw>HLl*w?xFm-*@tfCweeZFc;O0n+dh#O zeDsmq=9tLqKL6PLG(PfcpMBy^ygoih;})%STX&0Ru6sPW%Kg6lwovBmGgiAMH+BvD z+GnfXe0OKymrh#aRvmbE;CCKa?bd)} z9uoV>U$%L}9X2DrL;LLirh9ip#iIU%NcOuTkgOg zWBE62JJ0PnB=*TCH!Hds7hD_a+OXxTZmS8gz1Q42-L<+X`tzWYGPi1Fj78>mdDWf% zbmSHFUU5ep8u^Z$XSg{ddWCX6J7K!J_miH1yAGb_w*TY)zz&!)N)cZ+&WYdXzcT{-G_!7J0;vIbG#w!^*i7xW3` zbX+~t9d~r!z$-Vs?ykJMU*KDpzTsY|`C#A z&w}S!uxG^cjMy{fd8X`H^E_+z40@hHdp14KraiNsXV#u&&$DdLxaS$S{>Rh*Sij`y zm#k0l^a<8ic=`(KLp*(m^(~&h#rhmipJRQIr!TTT%F{<#-{tAMtWWdwY1Y?y`a0_a zJ$<0{=brxD`gu=3Z+)q!FP%5%9Zw%?eXpnQwLaO?CtF|b>8q^|_w?b`w|n|_>+?N* zzP$@P?*e;Ac-|5A?(n=j?49Cyr`Ws3^RBUXoaY^9?YWRIklJQo7AeQhuAWq;hO7lghU_PO8`DKFJ=N6D2!su9WPzIaF$w zja4$nDmI467{l1uCSz=4W1fsLkBx;g#zHnmvPUhBk!TPhWsK!)jF&OSv$0>s*w4m<8Dl~lD`t!pZ48+)hP1I| z#@N!voEc+I8|!9_b!`lsF$T7=YsT2s#|F?X=} zPR4x4=0To$kj*tba}Aq=WXwTqZjv!Ku{le|oW>qs=8fb4iY0<;T-7sIwK=S34r_B;&)nALyq-C) z&96Q4Ynyj_=G``T_RO7aPVJdf+g#f-*S0yhXAW+2bI;t|=JKAoyv^}Fb9|fod*=SO zCXlfvU~2^#YX!%CS#;cR*!cT@iqBj)GK_Ps9`a}LlH*4Op7Y-C#d^m)8Th8Hw(~7E#qyv0vxz^X ze&jzN*v~I$9mhzmJ0IbzjCd^M?|)iLe@T-;fm^jd!`J*YjIweAZQ|cfX>hz>dVl0s59#B(ZXM@A z6W;CT_qiqB8S%{5{rrZ`6GHiaEbr$VUl`{sdynYn?>RrtQ(iv2pPz6^oGa}yp|Ah# z?l_04v}Ir4d~z&v$n*XDehF2+$ zFg2wAbdBA^{?*HYmtXs5+7~f%+GoWXgQ9I~ANjP{e|)sAV*GF!+?rXp7 zsB*1qeC@wl7kTZ;U-|FL@57oib)E0{MEotSJ#L-nfA8l# z7R!9|(I5O?uS6by=8yi1cOxJ4)JDH#Sp40dcKjxP=Ja9VZ{6#g{J66C8}45FSO4jR zp&@({|lfSNWwCBYiH~NKLqn#U%w6nBh z;_tKjCBOJiKgD*Pcm2=4*A| znLV=Zm;RM@@tOVcf-n8R%i}X!X~mbm@pbW;o!xDnzqvy!XJ7N-mCc?CHg8kf8%Qni~PXd-} zyCc%GPsZ+uOwXFq*;k|d?6*-l?88y{?9WlX?Awt&?B|i4?DLWR?Eg`_*cW7XET(k3 zdoktzy~>(Yj@{Lm%C|clQ@wV#W3tEYd`x!Q9g)d?yCX8SOX;*%`SF9w!9OY=zo}mQ zDSPm3v*Q$G`hs&Cl$U zl+W2GDQ2Ifn0=CB_DPD_CrSGM^nTZW&jm!i{%<%Jz!@C{zbB@0@e@`u%h6Ue5*R%JsZ(-dxWY=g^4@qw$?|ULr z{3Y4Ld3o8%IeOX8`FgdBbN70_NZ0d4em!55qvwnMP|p|V?)7|OkDf2=)boY?#065j zlumnq|Udr4x@=OgvsO z@p#3=;|=-$jjJ5S^TgwoPl(4W{y&YYOx$w)Epf}m#4Q&Sw_Hrzaxrns#l$Ta6SrJU z+;TB-%Srz?{(Pepw_H9UZn>DaIH9(97Zg zq*lWTD&(*3y>ccQ@f*5Xd2`*xMicv$%vC#xLB&nlmBwd!TOEqjRT zC_9PwDEo;6sox>-A#FUI(ruia^4s`1m1E=TRKAV3Q@u70PxjdOJlQE-uwQ!R#`CGY z%AXt0C;zB?{HA*Gr|iMcvJ?Nyesod0a`9f$z25Qz@kZny;*iL1#3zwIiCZE+6VF8c zC(em<;d_wu;vA*YiI<}M#8FW>#8*-I#9dLn#AA^?#A%V8#BY&axp*)C&)&D5`~FoR z{*wGaTqgO4cun#fah&8&;ycOD#C?+gi3cTJh!Z8f?5uZ~k0_nEQp!)fDV5Xe@3>e6 z;!~+!zE8;>;#tW~;#^6uTwJU|E-qF|*YB46`aM&Qe&>|0-#_*0`NAGOFW9N)3;Xqa z(JrOaUggIRDhL0leEg<*@u%#;&$1K$>-j<#`~KyAs}=V<+4nD(iy!E6@dF)k?d)4mx~|ha`6LQE`FfP#Se73_<=4LKhWjk z2fAGRK$nXj=r}iR-;e%IpFAw(x9?4<9QzKH%D3-Rsb2eTmF%&&bIDGNJD2RYxO1sp zN~gWbj~`SH{!#h(P4(hW*@K_$`&aV6>_-=yFT31*Z7z3To8!JPn=d==5wrQS<9;!l zFFWoXv-z^)J~EpxJMJm7`Lg5wGMg{E+H(z$S``TRYzBZS;ug&G|Yje5#+Fb6w zHkZ4v&E@WEOX)TbP5Etpn#!^Jwo>_a4_B(!?&nJO*gap#PP^wT*>CrJrFJQu_9{Pq zP&xQV<>NQii$7%#ewLm1-{#9n7yF*#a&h2YE)KjS4!M0#al|LL?a}}Gl0A06NwU-KH%a!}{U)hhN~gWbj~`SH{!#h(P4(hW z*@K^DC;qqlO_DCQPtWD{A3FBA*}gu<{x{q2=hzo#`v4vL-9D&O`8rh0APV6w;d6DB)tpJB4!_8+EpDV_EzKYma-_($dAH`R+jWe)^s@bjrR2B$hozKb`wvSg-{OOnQm@4gE5#m*CsvA`7JsZ1 z`z`)hDS9a#y_6rlR1SKneDqSi=p}p5OLn4{>_;!P3%x9UR|)AB*QKkl-P~cs^-p?1WI4tnV#~}W^$eyDwc{s4_tlKZ{1DE}kK92jY)vhJ&;y&#U@2;HE zUvKqCk^BeFTUVr<<#m=9DSy(Kc}42|`3GObp0TG-En?@YY7>jt|3b?NMcSow+N=Ed zLFM2dm5<+4FaDH0_*r)1f7y>N+TVNdgc!3+apZdZ6{IFlMP4v~8ZyxqH^p7!2j(o1a@A&wVkf%ZG z0e(TF=&OPA2l(cdVmy;6%?A3Fg^xp?M=u-b7mr^RxO3NmzU|>L-iXrY%!)CElz)1Q z7}G%ITzS>Ef0uv8_kmUK;mcwS1liMcO^i<>JEvT{G31f`hqc=jSncXHJaXCH52W-i`eO4BEzoBFOx!s$E^p2BX^c5~| z9=Lh8m;BLZvqT9dfVI^&-=@sp4Z$M(q(6h(_+6W`xi9m z64KSKelJB{e%q*&e%0Q?Q~r`#kEe33KIXAh{`~g`rF!>WH89!p!8HStomKnw_t-zy z^-t|mI_*_{{Gf91kIKhysuzFC9{emj@xSax7whL;?)~NHC+)r9=s)d!;pkWGJ>uwZ z?fv5DhwZ)N=%4L<}@n?fvEG=ao+Xul&3hR1WV8mCt)b_40m^J-l~hC+{PB zf4SWI%jMo*Dc#-+rR2BwMJeUjd!&@|?fp_pz4qQI#U6Vfm13v8r%JKk-e0A(OX;*% z`SF9w!9OY=zo}mQDSPmZJipc-x?F$g zc;2mlbMyn&?>YJh>knP7KXkeN(B=9=m+KE5{gUd<^@lFkAG%zB=yLs`%k_sT-TIl7 z-};|aj`d5aeCw}Lz1EK|fwM*%=SNZXS%E3RO{J;CdpLeNQii$7%#ewLm1-`-zImyMT>a(7g(AKuZft7cmUu5idRZu_UB z4WqYy&b2r!+IjA*7hK`31|iS$4^MVw+s1Nk{&KRr@6cHOoLVotCvJ-M-cadfS8Gc3 zkbn9DJIDN0&A{hhJlTDbupI6^%KUs*Sg18g~yGb;I3{N=R|)!`jYGZT#QwC z;3X5?9wQcnaq=-WCb_P);+X%g{*&B3U&J|4%XO37UX|i}XU}?*-MOcK6!LGVJ=t}B zF^=bVEPE>1aBzz!+?G4W^hpOl;rc9I5%O2CyB`}o8s`WrUwgup^@-&#Jbt)qH7CwH zj{JVOd+>^A&tqjH+_d|momW3S(v93N+TUyBDA)G(*sk5iKIyt$6We>qNg z^<6m3P4DzW;M(yfV`t&@}P|A7}pUF3*Pat`?_g?uIde z@BFCfzaA8M&FnJ2@UqBVUwqZixIA*}v9tX-3*s67hBv*I&d*-c|8-yYh$S(e;g@!eT=wXje#r9ap|0MS&i1#~j(mHKIliRXw2=PP19SYCy{85~`I9+* z-|eOZ-q~W^Ec!j3uW#`E9RL2ulS2BKiF5qm*%JegK6Z}Z-^W-44{bjq**2=*q!c&c zsnL_tx&A5NPfF+g`(86S#R0ge-peUIz;2(toZ<#N^xl*dPoU#RQ&XIQ2Y;EC;ty2l zGRY6LXG7o5cRq5GpLa&I=c;8BeXVC=JcRnoru&H(MSo78JI&v5e&o+zo$7b!7J2OS zDSq%fkr%xAvR~9D>h$AL>1=&Lltj_V{ga=&Xsp z(Oogd!fPWY`f7b+?1k4yPqeerF($*1w`TZ8H^sW9z50sZ`Ig94TmR%Azc*^V=D8pJ zgB@a9o@@T2?|W+W`OuGl@H?Fq+q-<)5B`!%qefTyAN+y0yd3P=;rk!_+1;X!L)-o6 zr+16`Ub)1|ye{g#a{cPnv-ej;?*2fv zZ0Y`eLjEu6R?E(QF7nCGRn5+78Oto$R5P1@ZA`zceXXo(zsSG(ZL{l-iCnf_ovhj5 zSmv=S>SqfNj&af|_Nt#X?HJ3sc-Q*b%x7Z$Enlja^{E;8#}@Undq>8N8o`NQjE9nOs0|EK!d;(KHHSCthD=P-xejn;K-Z zo5c0E+G87JqxT#b(vP$lL5crb!8)Wy_?4Qz?{`pW~<-hEw2Lr2|mcPdG_wQam zyR6QmA$^}p^|Nc+4hdYjtX{Tibd2*b>#2H*NuJV2-5z5pD1YtuV*CV^vwihvLLS*X zs9yXXiZ7}jpB>eEWYhS&l|2oc#ox2+AG=HZoy&f{ttJN*o zI8i%o8(HzAMt6$8XT_EJ;)(d1SG=hYUyaX#;!ste8=sMDZ&>N~{w}WNUViB+UwKU- z*#Fk$tNkfGjtV^Y<~4rK+mX+@?^A!{>ygiS_%lDcW8?)7t@VG5j(@x5ouB)YhsQEs zKjjPm(21p?oZBi{T#Fe;25vv>OaIyThX;P3@;ZO(=0gMT+jgBl`G@o!IhWSMspjtF@k+w*;Y{G!O?=Dz2jn-=qo?eUI3{Nh;e&sQw+FV2d# zE$z9`e>6X?!_@j}zCYx$<3l;Wo;}kaJ@e?m%cmKyJ~nXm<6iS^mdEw&i++F2cOKd* zq~Eagb$?#n)`8zxFw1}9+61or;TwLZS|gPB8+HR36*Pr8;^pCvgz`4F_N#w@I zTMV>b@o$&5oaf)VHI~_F&-s3B?Gr*dbDC!UyE|hWd)`y@4-Ppnq<6gXRli~XeFLw4 zf2O~@e9Uw2)XcZ+uw6)3JhX>bM}FdwqCfAA?L+#>PnP*_|7sX`(85>!#$G!Hp19Mi ze$nYW1%7|%D}L!2I|u&Zm{~_07JFpT#lZ zTO$_wRhz1Y^dH`R+fNu=G4M^#Eb>2p7{_vF*I4YEE{$WkF;y4)cixR-xtpF?{`uN*Ogs7QFZ>th#2D1uw^--T zS{T=OcVGXNKjeTIgL?U&>;1Tz)q{1esI4yNBF7L zdcSp_I7jF|?rZ<(Wt+p8(Bktr;`3PC9!K0Bi|6Br=VS4O9Px!L=8q%hkHrFV!~(Jy zK`zAzI{7O{?4VjTzIMbEvRFfoSVI5Ei@oEBy<;(X95Hz;R*xfAkHzqD z#PG4$K91Nv7W2mu^T%QVIbs1>j37shAd4O3h#h3Hj~ua&Ebfpa?vTYJa>OIDI7N;) zMHauv5x>ad8ad(`S-c}hyd#T)XX)#2K^sg(J?G%{v@%#%w;~h%;vMsZ^KEvmEm*o7XtzH8$UI%y(=aS&n&@&A%M;FPoP+=4CctbIjLl9_N_H+5FBizdK`7OV{(9_)Y5j z700=4JAD`Wma=VHxlZ%q_pEmPPHvJE%qMGpi3j$6eGmmRa@W^W1lT z#k$<<=er7rt`FsG(dKY>=Ds_GKC|j6&OO|D@4!8tEO7^H8{dgn9dM-k_Levm=hp=OwZ;Xm#>TFJ zziE5E>)htPz*jH2z}@v{zrfS?>F8c+9eL!u_HOeneM9=xN$0ygd-n z;l8`hb1iS{71D=Zah|*9(w>1kj6ct1r^VROCvAAhebxA>kY3@F!LI$|k^Ps0+$R-c zEV8j{A91x>MQ*=hpgZP*$U_znaLd|8ZnB`iJE2zO;Y%KNJG~Igx&D?RZoxEjqL3*{_)`vrIGtT?xNyURFN z@#;9Adb95fZscBZezatlajtrU2Sfh4507&fH;nVCTNaITr|%Q@OEg_Q&h2|#oO3-p zYn-dxAt$oh92~o!m)1G#ZY#+6&IQ1EKTl2{M$B%YzT^ae1VPo7L^CI7Q>$C2x zlcMfzk9^Lx*${cqha=n@W25fvc6r?0bY1+7eK~HhJN^3Z!Or)e7~nSDa(CbbH6C&e z=X43YZo7WYZFzm*ZQtwdj_!DQ;8WW6a(i#rG4Qny_jFxuI3w_rPxf@Dj*nyME4ue` zFVs0Yq|fWr)AgJd=M=*?^mGqj8s{2EpWDmLJ|xaT+6?dIIy8xMhbFJ~a-Z)M=MFne z>g7h*5mT+P*jlJ(E!5UXJ!_=4cIsI>wKY}Gn(EJuhkDjpZ4K6^HP}T%J!`YJX6sqA zwY6N&TCT0}de(St?boyRYiq)uHDOyT_N*1#8nR~%+1BMe>vFbU=UK0_bv(~Ho~x#DC=vi;Hbx6-Tq^(bS)+cS< z(z9-9>#M0=TX#)kbzA>TV`f_yO=D?WFHK`?TSrY}Z(CnYV{%(}O=ERik4+TT2llK3+xoC)ec0BGJ?qA{zU^7xwsmjMy0@(}d)Aq4{n@krZ0pjV zb!l6#_N-UiI<{vW+t#-|>)W>O?OFG>^>EL6xUG|W*2!)C+_Qde>*}6$bz5)uthd|x zyk~vh*6ls(_BOwE%&%?U?U;AleB3b~w|Tl_o^JDZ$Nb&q^^SSH&G#MieOm``tOMBk zfMb2Y)(sr%2DYBySWmEZ2FE&stv@){A8g*?n0MHG#4#VSIfY|RVRH?~T*KxdjycHx z$KIPq{aCf{!^u<{WT+^Vv50VUdn(u7m%2^)+#zHZl0v1y5M>^VN`o>}N;D8Es{6A) zQX!EBic)BvqcWu7@gB$C_i^=k-?iR<-u15aTi@sV{CBLq_O-8bpL_3f@AKT}K2PW- zM!E@f79*VnI*yT!1Kr0+_km7iq!U3GGt$MNqZ!%!p+gzzP|&T6bSvmwMmiUCF(X|J zI+~G=2Hnj_cY{u6q|-syGt%{-lP3RyuA1CCKxa(s|Ij6qdjaT}$$bHI&*UBfI%#sh z09`e?cYqF?+($sSP3|e6^CtHf(1nwG4d~8Bx-)cYBb^$$wvnz49o$FA5!KWqXmK-uyq*OI$#4avVp)hVq_a(9tzn^U`sKwrNH)LWP5>4#>gfE z+mVs&2sR}nn-Xj|Mm8MSc8qL0u=yC-d|(SQvIW6LWMm_P?Z_myqmN!UvMIsVWMpfC z4a&#{1>2O7Z3;FkBbya$Sw^-j*uIQxU$BW8*~DNgGqRPzhGt|#gKf>owg#IU&IZ8- z1zVhvEeVUu*n+KiDj3D z4cW?u4BN7mZ5cLaE1NTH(KgE#ZDpfoec7(rj%?bnfm_+YVH>xyjl-61Wiy8@J$a|b za@p8fU$%F)Bbz*Fmi?bt_X7N{Z1|){wtdnsn?LE#x(l$nBVc{q9k3nUDc}ym>J9>T z6IOQosrd@5$=+# z?vilFWOc^`J=94Lg?{R!pF(eS(p#a=I_a~}bDi{D=)X?-FZ5z3y%_qklfDc++DVUw ze(j`RL+^IdyP=Oe>EqDTo%D3*?@szV&f!kyaGcMb&gVE|JDss{_I5gZ<4o>!CdXOb z>8y@3ywe#TXMU$MKXd^nT>v_Qla2u0!AW<3PT{0eK-X~6HK2ny=^)TeoOBcDEKWKL zbQvdI2KtecegwS<_YpyFg6`v_`#>jh(utreIq6E!p`3Im=vGd;74$eKJr4SvlYR#s z%}Gat?&hSsL8o)l>7eU5>3YxsopeCxj7~ZubV(;&5_+zao(uigN&kiJ>7;u?Cw0o;AC@vEyBqb z0egs(Jp^_VCp!sj8csG1*gBkS9k78o*+5_$ak7oTX5wTsfi1LgQHYM1aoNP_7 zK{?r=V4HHXO~Gd6WV3=T%gL4n8<&%f3wcG;r#%&PdE^yM|FP&!uRDLZ?ymIuf?#Vx zUeWZ}6G!-RfCikykX`Yx+=+kykW*Q?Y=N!!)f}Kud=|l)kNQ zuq{kkwIF?cqhOo5V(ruE@!NvkqwQs{q$_?D1UZAo|S8}5#Wp7de*AnZZZ>wl}U zGhO*mu;)BCeP_Ds=W~7eXVK2|>F)&l&oh^NnBMqWunV1V&yMu7Z-jg2MbZ1|WxF5o z^>6O^PP)XY0Y6&ph4ihzz2M8I-Y_r8>F~|Xi_*`Vmwox)JswZLa(uw$D=ba_{n$&s zeAc~Br#Ds(c)`-;>70?_KDU3zmFZe9t?_j>k6WE?us7W2GEcG2Fw9@vV?+2aa}D4A za;Q@RIf%E<4c{_1@$P=1P3A0~RXY5Oxr{f>379#Kixl29GxzcO!aL|g@E$IBzlO7{iZ^8H{mwJp` zy#?j&Tjnux^%iXC_LRrS)mu=eSZEWudJDS2rp9qcuHJ%@Uj&R?y#-6k1Uiwcx8Ok8 zfJwv9k>h-QMhth zd4$Kv)mw1%+B-Z(uHJ&Gw~z7|xq1ugJUhl?%8uJ|>@)6Pf&1u4Imjawv1Wlv|nOsGQ6EmvTdM9x7)v=Yw)LbDk)tGv|+T zJ#$_u2Q=rKazk?-DrYq3r*cVi-YUm5=d*H8bDk?FHF8)ND2Fw2Tc?%V8u_x*%9oA& z*JwomPHr&*HCQ_an-zT|uL*Ad{J`VYSl6yMj z2}R!9PlUWhMtO^n7s)6u67nS(=`!+H06EUV9Mp$ZKz6etGR#%sa2WjQQxb$1zX6_CDsX*Ph6{ z_S!3%?_PT-_S~l0bFmjk+KaJAN7|#YcSqX0v8PAc)3Mh_+Us!!h;#&KQx-7&v=GI(y(u66s8Wvr4413eGT*&M-LJL^|8xe3i71b62Eu z7tTnL&PX^rMLIj-Ocm)&g|k+qvlh-^kF5kAKc~Z%xsin`c?eY2n^+w$J%_a^45N4(HOs+rryh&awJGg}2O{d#7v;Z=5+NE1ea5<~dh;{IbD+ z%Q<{|&pJAWmXS~Mm!&U7?y9lEn3`hkN zej5FKMh%Y_)%z$KIVRw8dv-*trw3eR&bv{*4fx7YTch5y!{ZYW>TUW8W8!qy7PHlIN-B;pqk6m=GZGXu! zkH0^$s$KK=3Xi+4tjaiS9v`h!%^rVw#^bWXtJ%gUZSuJ1jA}k+Apc9uxNXF&b7jYu zJm$B1Ccfe^+hjZ_*5SVzB0o1VX_!_LHgRCmc3r3S9+T!}m%rvQ`?7m)!0aRDi7#j0 zg;6J?I`}rDZ_#E(ZQ@@U{R=c?L<4Bch&Iri5zXjJMtwmaGwLJpQ{~XJX9xH0L}q)X=+R#MC{xriiJNa;*_lSLGTc zrVh)sNle|AYnGTgFV`|LWRAaICWb6>ltsjl363&>7_!1qRuDsmILZ)W$QDQ0LJXPX zD07G*iyUPUF=UjZj3S2Ya+F=fkZF!GjTo}dQPvSd-a5)#V#r}fIZOh zWhpUatfP!2hU|5ey~L2ojxyQTf3LcutR{vGca-78kok@>pBQ^VntK5;_J}n12x7>M zH01^{)_a=kofvW;O*ude`H-f3AcovXQ*IDLo}?*Hh#_avlrzMTKWWMzV(73Dby#BP zm=SeMV(6X`bx&gGq!D#eV(6+7byZ^Mun~1wV(7LJbz5TSyb*O?V(7vVbzx%Y$Psm9 zV(3Q^^&?{FI}!CAV(38;^&n#CM-lZSV(3i~^(JEIQxWwkV(45EbuMD)Voj-w5%c^; z-H;gap(%AnVxF(4yAku;MV*eA=P~Mf#5|`_2PEeCjk+N*&vn!piFw|mE=kODAazV) zo)4*e67$?hos^g~P)8=_`IfpfG0&gWZHaj=VxD8EBNOv{OWm26=U(d6 z#5@mE*CysUnL0Qz&+Ymb&)BpNu$*Ua>hi=qlT*hh=2@M(KQYhnvuf>mGzy_aMZ&2O-uy z2(j)#h;uk4??Va5Mtef5bGXuf>mGzy_aMZ& z2O-uy2(j)#h;uk4??Va5Mtef5bGXuf>mGzy z_aMZ&2O-uy2(j)#h;{ctth*0l-F*=2?t@r&AH=%*AlBUnv3!<@<+DUApCykAeU^yj zvqUVPC1UwO5zBvxSpG}I@?RpB{}QqMmx$%RL@fU$V)-u-%YTVj{!7I2Um}+O60!W3 zh~>XTEdM29`7aU6e~DQBOT_YDB9{LWvHX{a<-bHM|0QDiFA>XsiCF$i#PVMvmj4p5 z{FjL3zeFtmC1Uw65zBvxSpG}I@?RpB{}QqMmx$%RL@fU$V)-u-%YTVj{!7I2Um}+O z60!W3h~>XTEdM29`7aU6e~DQBOT_YDB9{LWvHX{a<-bHM|0QDiFA>XsiCF$i#PVPA z<%RxB#PVMvmj4p5{FjL3zeFtmC1Uw65zBvxSpG}I@?RpB{}QqMmx$%RL@fU$;+qP6 z5sBp|Ni07}V);oD%TJP6ev-uUlO&d(B(eM?iRC9rEI&zN`AHJXPm;LVr-(b)Cp$boz{Hw>04?f-A z_)XB)uKByXt&<;gI{H4*2a^AyPn7gB`Yh20lI8Seq7Ni7eVph6Nlf1-`alxXCyG9h z#PpS-4tsOSSpOy4T{Kob8ozF6|FvMq`vG|cK(B&oCG;UdYm(?2efv{|ab@yWk( zXC9x>@IbMm32oiS6isNJ{_mnmUrzb`ID1~%FFXxz4L{Dl-}Oh2OHVsy9(?^DR24(I$2YV0@F`-F4;`PUsW-`neb{U;teYV7g>9=Bcir`hz{Adgp${M)>L z+f5#iJnNYG{n=YQzOHR?d*j?te{)paj(I=Szr0*=+wt&?zD||x#q7~TgFUV>rkI`a zTKM*ZGm6>eZEy4CjUFv(x866za;^ zG~g$HIL;QoCDdOs@HqS0xX{kE-yAb@qR{@LF~#j??XU6eT(Q5nO*akt$jAjHY_Ul} zf0;h1q;1vyN?+&Zg(ui~ujhNb=8F^UioaTW{7&j5d$fE@kL}wh+j8dyePnm9Q|*Np zLttD`#-(R{5cV%1lywiR8@;;UAf(F4BF}*tC?N=@o`_iQiHP-{h*)ozi1oIJSZ|An^|pvuZ;Ocawuo47i-`5Mh*)oni1oIJSZ|An z^|pvuZ;Ocawuo47i-`5Mh*)oni1oIJSZ|An^|pvuZ;Ocawuo47i-`5Mh*)oni1oIJ zSZ|An^|pvuZ;Ocawuo47i-`5Mh*)oni1oIJSZ|An^|pvuZ;Ocawuo47i-`5Mh*)on zi1oIJSZ|An^|pvuZ;Ocawuo47i-`5Mh*)oni1oIJSZ|An^|pvuZ;Ocawuo47i-`5M zh*)oni1oIJSZ|An^_GxWZyt$ZH}G#BiS_1@SZ^MQ_2!XSZyt&D=8+h74FBel81@bS z=8;%$9*OnlkyvjYiS_1@SnnKtdEq-pV!d-D);mXHy>leiJ4a%@b0pR~M`FEmB-T4e zV!d-D);mXHy>leiJ4a%@b0pR~N8(MHkIcH8!XEL&wL4Ay!oB125+9fvJ45+-&%bXn z--o^9`a9k=MVg1bW6Gdy=J}s)_OkBa{aa1xBVk`#fAlRgV8}pUe#LW}%~K=89^DA< znqR&*?A=%6E~5VZ*ZMmDI%l2v_RX*djXbo@^lK6J>$kpp)l@1I>|H+|TyL7>hQ0gH zsjr)Vy%g+Ych!Hxytg3W3T-!-cfJm|)-@YV@drZvN&PmN0kc9o_qTb|bpGdwQrqi z-t2CV_Z(So28^EO@vt4Qo2O5?$K##@H<3Z&C9uI81 z$rP>psK+N9+-S<2w8-PGpKml5{kp*85AlY&=g0Fs?$ziWQ|sbqJU(aN$7X%6Wgg!? z_ha+Spr<_UU;AS-V8GKJ7rp-@Q?z}kKl%M#rux~>`tnMLcbb2_5%BiocAEJum;3T- zkA7fYT^MkQZ+4iA-U`^hx7}>t6!6pQ-ZzV91-u#gGLBqQh&R4#dcF|a?D*3=W4!#;hgr&wmqiUxZ$3* z36JhIf9$&5;|(46nQFI&x%cW9`^;M=jP-N*pP9WmVGg`I{WH@nFU*ZGi#{{cR)#r) zdFwQ9F;AT43FeQ}{K33(npc=_PV)`(&}klGemc!h%v+~&R&xVXZl>HLO9WH3(VZBr708oMZ^rtkassT6S8?SmRD>9Bbcc?L#Iw z$ppv>Cs_d*;v_>LTbyJIWR8=}fh=;8MUYWWG77TGNp?ZjImtT6Kqnap+2|x2Av2w1 zCS<9TEQO49lChAzPO=v=*-0j2UOCMxjIY!9V%(j^9rM9yK46|W%@fQYr}=|<S%`wcxZCHg9~_X^mj*IISJ5DW^4s zwdSu09oNAD{?j*w@+nr=P^rnpTCg@Wc=~K|NGSai4e`Tb9K`+ZlFN408k-i2!E+ah- z`dvo)9rV78^gif=8R>)26Eo5iq1$Gp+d}7c(s`j*I_Z_rH#5>Vp@(LqheAKiNI!+% znvvcLeKsR~7J6<*dM@p)HusJx{9AJxZvPHl?;A9_w-N4Ci0DFQvv(TOZJA;#*0rm$c`vdF} zPId{{E1c{VuwyvcF<{?tvTwka;$%yKjm62v0y~M5odot1C;JKPDo%D4*jt?JEwIBl z*7O$>G_`hj@65bQ`9*~DO9%E%@L zyHiFsG1#LrvWdY?m61&h_N$C+Vz6svWD|qEDI>|F8QBA2C(OuB2>W41_CweeGqNkf-k6cS5q3z3 z`Q!aQ4*O(A_DR?+GqPL4Mv;+?0``H7>;teHWMnshJs~4|0_+SK*%@Ge$jJTxyF^BI z3D_$#vRA;4k&zt(_Kl3}8?bw1WcPqQBqMtW>?9f4Nnn%7$R-23N=9}S*jqBPx4;gQ zksSv1nT+f+u-jy0w}Cw;BYO_~avlA0sdvDi*3qAq7=E^nezwH$zjgG#C5B(FqhBsD z{B<4ub&27}>*&Wz4F6t7|6XGF06Y2s6T>&y(KnbFKFK}?DKUJN9p8o!!%>!itWje4B>Nbo#PC)2u}O*H!|Y?062rII$1){`&$EwlN(|rZwEhL3?KFM1 zSq|UnG<~Ou;ZvQaPc<=ot<&_iCWa4onm*XX@Xb!sH=7tf+iCi26T_D~ON9sR3`;TP@b7flR*X-9u)V)#)z`cV_ZzuM8inizi9j(*p~@W*!a$0mlKwxgdm zv0{@FE2b#1Vu}(grYNyuiV`cPD6wLS5-X-Cv0{o6E2b#1Vu}(grYNyuiV`cPD6wLS z665W#k0~n5H^szw|LbFl660O4k10yb*qeMWOstrqD(CxR)#tloVz$Hg$i#{%O01Zo z#EL0OteB!I=lf{Y=eucQ#S|qb{d~JE%s1V{{4d{M6O(?v%O)oMe6LNcn4&7@`)<|e zyKiE)!}s9CiYZF0n4-koJNTZRn0t!Wrecb+oO=P^rxSCJ;JbBV#S|sxp2BzT#EL0O zteB$2iYZF07`eoX>r1S-zQl^_ORTuQ#ER=nthm0!itFp^7smDVb+(7NzQl^_ORTuQ z#ER=nthm0!it9_PSiZ!H-%E@)*FJtPvEugV#O6FR$Osn#T6%3TybK>6(?3)abm?4Cstf> zV#O6FM&3imJbJ|Ej`-3sUmG#<9y;c6BSzjs$NX-@$b0CR_l+2N4;}Nt5hL%RW1cu- z`a&IVZ53dFWK1`RRz+4)fL#vwh~XBj$gZ=Z={4F#jDf>119! zV$#oidBp4&^XL&HZ(vf6e1b`REt2|dVT=tL*-8z%H4?_ts} zmaD(4FFvpx@rUh;Z~U+LNqWR*(kcFvevJ$Bmub9KBmbAmnHNm;nJ-N3FprqpXMQpL zmwCrT&%MY;COVm?O!PB2kVcvOSI95D;7K|1gD3ToH#}(v`NWg~*SN4>%sa3CGQYX_z`WCPyLsC7Cq#@ z=;XMFevX&=#d7tR^~DFaBmS^`@s0l#KS_`HOghDX(ywtr-g(D(MC=#x&O7EeC*FMZ zV~%;}iJN`5*fAeEG4jqk=1C_;-g(FT>BPu8@0eGe7Il8I&A>a64@ssq3&!kiQC;b|i=Rf_;4gY$ipOYP4 zJ?JW*dWXlS&OhY#P7L^xL5E$f=6Cw?hiV*gl`kLV@!$U9ZJ^rrM?{4z3F&>|? z?02{Sig6zQ{Q2+hncCrw@3q6fyEZ3>ds~)&_jACkzvQiOx65|kn;q_a*?ygl;Vzi} zEq*Xy(lc&&xGyH1Pkb0K>7QIC+$pnPU26th{?A{N@~-Fnn$*AG%3qRpwm)(pY5&Nf z{mFkv4cVX2)3x0Ggw7GWeop9r;*Fn^ez9ErWqt91?T9~YUwq?##ZS^BK9f%IpY&^7 zY~Pn%^$8Dn-hP_*iaYXfz;n(iaLiLr*|OoM0>}LI#8sB19rM}~|Iykx=DQ~zw#B)p zPo3%U>!=6Yw??J99(m?uedNg46>(UnjUNq*Vr2LD;Ym@qGcdSX;x%#X% zN&6E=zL@;?gd;B`^nCfq3kjV?d%lp+U%&MWNxxXG{<6OKz;?tRwlBW%zv3t95uZt? z_)q#ZE}Vywhn$~UcbvCckDSk1r<~_nznuS)hg=t0?_4jE16)Uv4_sf88!VSRVSULN zwj=rD+b@(${IBE{>5&{Gosw^)UviKAl04-6R5|CZ>T^D;9nN#L&-pKT$aNulxL!mj z*OBPw`cl7GuKu#V_`r6=AK!kVJmi1HPtqeklTPuU^lM!1x39WEEB1JqU%%>l_wwHX z|M1s(7kwA@i!+g{Wy`>@U)(bJb+>j%*e_DG-f%UKeC5C0xaE({{Dmw?&6BU zH+W0l23Py8{l0u*mkn-7+21^7dDR7nllo;({=;Lo^Lq2}_K@wDJM%cdcKF}TU5j{3 zdS2}n?oCK%$tp#CIqBd0P{8chEd>Gp(qmmx-gsOlsei(1m$b9;NIGeMN9T0%-)=h! z5_)on7C6y))x`w~{o`vEB>iH!`pf#_1KSaQ*uMD2|B9caM|>uo;y>xvxNu+A{>A-T za+3SFNDlM7A^FVngXA{P6_V#XZ)pEwx%MyC*Z#$Jw12UE?O*(_ z_Ak<-{fl&J|04a`zt}JBU)--%&V5|WKz@qz7#KWtxoR-O#aVzVW}}C+QKNNvHTv`ZX@culvw-s&R$q$zzZ0 zbbqD-?lpRsbL#`XJN1z(KB29z^Lg=)-Jet1dF-D2*sXrEy~h{T-tGFC4j%Wsd$%k2 zsH4Z`joq&C16O%`+OFO1w$5P=uzcm&VGgkV`P;iE?Tov*r^jqR=gTl3_}}kp_V(qZ zXK$T89+S>mKLkwrzwOi4m$P3p?h3fyCm$r`OON{?seeb#j-;JxBeo~)x7_)D^4~3; z-glyB>B09BIyb?GNA&-;T_p5iy(DyE9VPT*eI@;3 zx%$ic;se_ef7rhG#{Y_+q(^)vo#H>%S28X*M;Yy3IA0mbNu0Zka`l(>#Rs+{ z{;+-VjsF!tNsstUI>mp|uW@0&vd;5H=SK2D=SlKM=S=cV=TGu8>pX9CUM2r^j^()M ze9Q6DxtHZS53|0`$s8}8pMCrPoac?s+oVV5aMG#sImb)qcJ?dlJfD=452{c8s2%c6 z?USEb=lO&l@?UgvTtq*|OZ{TG`pf#_1IJ7J@$LU}o=^Bmdc`p?3cz1=c}X~=dPqa&SObCIHx7;uo;y>xvxUgT6hwQJ`9r>X3Nd9P@a=f&D z$xp3o@>%Ph{FfZycu78Ryd)1np!(#G+TnPqeezTPC7(qP`7b&-E~1~~rGBwo{bhaef$fMtY+roif5lJIBR-Q( z@t^c-T-dLy`!B0|7V<&&FXWHzWym+(*N~sO$046}zeE1(-iPC&`yh^2659&pS@&O7 z_eyLh>;B7T-GAAv`!Aby|7El8ziih1m(9BWO3KLx)hB<{4*90`$xr>4d=@?Azv$$+ zh<=Wj`o(hfm-WR5wj=(qeesR|6+cOj_)I#*e~y>Nh2xcV|7CU0!tv7m3&%_MG8`}6 z*KoXak3&A|euv|wdmoOM?t?g9>;Ad_vbsNFecdauotFRHe_7o_@xQvCB0ajdBAvR= z;`-7(7yFfU|CN-J52{c8s2%c6?USGSFZnEb$bZqvaS{C-FZGM%>M!ey4{S&LVf*46 z|0{ly9`TuUivJuhjSKFHOxFFE(LD?9l}y(Cm(jfp?!S!gYj8hhbdQ63E2H}z+xXp&$2ONxxXG{<6OKz;?tRwlBW%zv3t9 z5ub7YmGB?;U&**YuQXZuvXNc}J=92FgMMnH$3bs3((jaj#)y|HplY(Y*lfL5%JTa6e*nkAQm>psO~-KUtW`xKLPpOTd0o+7D_`-`L<+-oH59I(20AKgnrzoB>iH!`pf#_1KSaQ*uMD2|B9caM|>uo;y>NXK5t}yhJD`1E)6@pk-ZxBd6Q+IH(B<1BfB^3^Crta zZ?f$3Cd)o=vh4FF%RXVYN%zft@^QANKR)zp$$(^uXSp&T<|kA^6!HGp^vFfTQ1Ax561fP6JtB_A7lIS zE8~CVZ$^6LhekR-{m1{%$Zw7Pl0O^#_mXn>^(FP;@0YX#Kft7Y_y;Ech2LO85Bv!e zI^k!S&=3E^q+cvoe_3CAU_0Uu+ZW&XU-6Ulh|i=`{3rby7x?K#8ZY?oMJk71U!?l* z_lwjH`~V}h5C6bO|ApURBzoXa7>Q2!8AhTX{)ay1Hph$Q8ZXw@c(EOg7u(l(@xK}` z(xdSrof_gJMaT+s`lX@*i`?8-(XYG1AoG%q7#0G zO+`Qa51VHBA2wBgSzml$JK_)97vK0_@ssq3&!kiQC;b|iUQ5fkS@+lXHto;eJ=--L z+Q8#(&(w5hRA}UJ)$cEK>FfXHaoZOEa&s>=q5hrL)f*9FzpT5ex$Ch#-F3+KL)${mv!@X|=y<$>y~F zd+-;R7CldOcrh(H_m*0j7X44>tw^h1ELVS7UwmLY;t$&w-}qnglk|wsq*MGS{Tdhg z!8TqI;#bp;bi&^O)4#O%chC7dU;3TS9JtD3`lF5?^1R3NQ{8{~MUUyfdgZ>CJf>gk z@fCw_75!a*o4U@I(+^f}09pS1{1981^>?2X;%l*;dzy#%TE6{yAx1I(+jG_Xz8%tY zc|nL{OgeWp{m_?_{vPKAKP&d@>EQv>?^osY2UdOh39B9Y537Cp74I+nFa3>05B-ou zC;gK}KmC@~FP5vntS>&W9r4GvU&uH9SNtSB;xp+K|4F~brF)-y+-W|S?u z^>;jevC4h!vr_}FKKt=Lcgu_rm+X?IGhDAZ!4K_>*7v(Dl>)CGcg=9QVl7gwAt%Oik!dwVImri{x&O;NBr^a7xIn&6+cOj_)I#* zf6}jU*}8ABJ67#{FI!%{{7IK72>8O;Pr0t+>-h3stDkj6udC;Ay>ZXEW*r-PyzPfo zZbF?V9^dr&^RC*)rXIi6=|wmGk4rtC@vk+m*R0ka@1MBFH6Ix6I$2(~X^@$$f5NVC zN6B`sKRMh@v;C6G2KaCJ-^<6|6^_!NSleBZgrH>@-zxBaG$$#taeITLd!yE5U=sa=SjD-HD%#5U8ELVS7UwmLY z;t$&w-}qnglk|wsq*MGS{Tdg@d6Tt&8OcfP3r6x2`-PEQ#Xe#rZ$G=!8p&boJ4W&u z`ruzm53{}n$; zkN8YF#eeKy$+$pnm@Ii{wC*5hjMgLMkI_1XTryg}kXI&49vZE8$TuT70J&!*A0Q7+ zmOM0B^3Y_-Lz5*BjpP#ln@?XfY zgdWJZgigr4gnr1wq+cvoe_3CAU_0WEZ~q^8nDCSIh|i=`{D(YD#)aqJtn)@w?Q1+w zYQN(-Q~My#pV}XJF3mb`G}V5}bFB7Ro_n?b^4zO^ndREASzr4&&%N5;ef$5MH=61^ zKzejeAe}lt@Z76&1^bnC-iTDr^S|m-FHk$w7t}uWh^+HQBzmZKh)(JwqMv$-`o(hf zm-WR5>M7!nZ~ve3MkIcc9`TuUivQG8G%k?yCTssPl9SjMjN~Ww3nRITeZ)xKVt+A` z!`OF>59^FJED9$P4H8zaM_ij9(gJ|2NL`HDi^z;OlU1&--?jIln|Wlb=_9wdvYnx39my%xW|6*>L7O zyWp{ehQPxJnY-Qz?7M5%Z=t!aO2GAME-=U5F7M0Zvh&T- zN&(L)JI^dCUCx)kTW_xUY(*K5pB*&Ed|vD{j}LB}Z7!`6;*_@PJ=@%P;>n@B%4}2b z!xKIJvh-}zUwWp1J z^9=v(kZ)F-iA_Q~8%sZL=G_+Bzoo?Urt}LZ`8sR2AV2DNr+D1G?`rei@qx~=(m z_6PbG;;mup$3nmQ)>&yv74l?gz2{7wYT;j9Dy=a6_5@t@*t4eEC1?6JTkUzqEYAtJ z(PM|*_PN3L{>m0dT&K0cZ{Msx;+`o8{`}+1{O&$q5q$plH2U4$IeV6Gr}ufkyLcSd zD(3LjKOS+%4}RF=ag&a?!2@S{{OqrX-PVy0d3^X1__{9%dj0ro4!LW8d%%}>yZNA- za(%#;5BSYhDG~7UPQSXZ-wXDEQ^)`6jtzR$*B@Kv8+SpeK=XM=zjnpz&iCb)l>5fL ze8mEff4%w}_rP@vJudO_H?GRyMILV$_pKY!Gqh8;?RRcKoyUCnsnPdt%XZg_{(X-hUFo?2Papl0`~HQ1hcEisbzczh!I$>CvYi5+vHpN-wL7%aY1J=oZj*qo z!rSMuO9Fp>s&v5Z9TfUCw*h~Nz8olg>#_00Z(Xl>f#+W~|JHpvJB&q-T?gFeM?yPqJp7A0|K)%Y zf8JeJI5!ZN-aYk8m@|l1?;39pa~N^#U7c^jd_#PDH=$`6&mY9ScT2tqa~1LM-QFW% zJ|j-PTQM`N5ya1T2R{n35pnfh%^g8DBHq4x_q`w+Z=1KxNj4%cK$3R}@%f!(BjWZu z$wtKUcan{W^Y0`Z5&z#wHX<*8lWau304LdqJOWO#@#uhUPO=es2b^Rh@*pHMAU}dr z94F*2aEhUXyarA&l#uVhDTWgAAUMTqLVg6N7)r>S;1u5p`4pVuJ|WM7Qw$~KWpK;N zggpZJ8r;`i!rKAlad1~{4SGHDM7Z1re|b5HTo3Mb`Y=Lwf&{BFTd%QJ+Ai8!A^)6@~-4()|Vr; zylXch_82ke-Nv^AMl5=F>-vBZquxEyD`3Q~cYi(+zC}!X*LHqr6S3~yy=@}j4r1WD z2VT0wW5mXHUmUo|W5mpN!;Ura7%}!;iw!{^N9=ufU6)WFG5MWYaj~z1SpBZWwtx}C z-z{Ae>L9kiyQpvY7h?XqXI~5SAQyn!{nn-aTjVTox&2#sj9dn;*}7&PBX@vnw(l~J zkyF53zAM;Ek!!#WoZZrwBL{)&Rxa2Ckek4LYA*NXB|m!IRW9AeW8^Y$UychHIS$M`<7xZ!K7dyG63Zo}_2Jw|>C_jtYYJx1ONcV&w@9z$*$$!*9( zBY6lpX(T5hKaJ!k zXtY0K-!$4cv7Z|4r`TtW_F3$|M*A=JWutu=`?b-24S8-P&mrfHNeD@F#tJ#AY!KYA*E{FU&OsJXN?OO@o>x?-2+Da z9J9G&czcexI_3eK;dpjJJRhF}niz3@lKVcy;qkefS&sNTKBu#<^ZpAy*E2EV`S={r z#EA3bb3+p&{*SriN2cHC*5sSub`(w2)M~oU%_skbOM(i51r1py*Bc_dMS|`weST|-^nYF$g zF>uVRT>&FDj@dEtC0~x1Ip&T70V9@VNig)Oj;1JDtOEK6g5wdvM(Dj^jJ?MZ=Iv{jLC!GLXqdQ{e%~6as=CwI#Q&>mLck>bC2-hj|;CwwVtRuuyvx=q0yg8Lm z3+sjXbQF6HG1;tQvN8Y8TTxg?i0x)~_6_S7G2d*hDq)Qy)|^#*Iby|~LyS197;%U- zXB9gRvF5B|$|2UAm5(CJ6@!lT6`PLjC}tgE+}R2zJ?{I3Sb0{l?+`1`DkdIcKm)|0+fw=~3)H(y5q!q<_*WGklvYR}4Vb zf8x9cd^y|MP%Y@Kh%spAY@X)J5qr?SGd5tvIka0F2aNcKw$99{z7Ap)+Mb;PMhrvy zbhCgF+tAMG7BFHS+OZ1*Ml3{o*C}`TZxJKWu6sOS#7?v|d)@8J5o^)jd}%003`RS0 zTEK|SXy3XiV8m>+M}G)yA~v1<=vep`@#XAQc>yEtob9|c)JHrzyQ6-;aBQBqrGdAoOh=XT3G!1hM@$t-6N5h;%+&q(iZ@`GBXUhH&WIp2T zndx}}57_>zxo2>g+q19u)vO&C<~-u{na<lQZ;r-*?3KGuQMB`wrs%naWp% z`HXmg=I-`kpF*5Kb5GAOw~=o>&3x-zN677-W^Q+4xr4an0f7qnb(;4?unW2czxlzK2&aS`r=W6C(lgnmtNB^ z@L@-n&gp__VT_u8-ZDM--{Ji8=gi#nj?LlxbNUa}(qj*W^H1M_rPE!e2HY|CNWl#g z0!F^tg1uh{3}5Sla?_shG$3DX!L19z*#`M)3pzg)&O*pnTQL5~rM?dG)fSYyZ<)u) zS6i^5TR2}KUu{8|Vxdjst1akuSHQ?uTTt?gfRV4ZU`d%kC-T)694H$wX&5?koNp8P zY76wn5cz5gN|YMv%aO0P;Ks)SM!wpDCuR@x<;YiCQ0Lp>9wT3E!PdzmJVw6Sf}_{o z;W6^n7F4}`l*hGW6_-+BVTQLeZfeNC!R4S zJ@&-VKJwM356%q#{dwk?bk2Z45AxNfdrc2?B42I#reXmv9sW@Iwz`viJ5yFINMGM5 ztl2BpKAj%F?OtEr_Oe&fmA(oxs_(Ha>8^br_T|6T*qN?;Xr9NGWxZ`KFQoI<5TI$W@(Iu4?44 zPAi8sa$BdB+Zs8q(<=&dULzNFdURnfY~;vJD@QhRXQ!1r8#%Sp%BhW<$Z6$7My}-a zgu-0Ooaf5R%=xcz;apX2WzJ#cT;|+XE@sYoZp7#|iqVbO-A1vy5!2f! zrZ-|Z8^v%&Y-gj`&WOWo6o(n{nT_Hzm#%cVQQT(4b2f_Sj5yCmah?(X*(m-q;zAq6 zg+?4{qd3xkO~246zBJ-a8^xVQJZhtO)QEj;6#E)6u_MLAM*QkX@v9NnI#OI~#Je_% zca1pMMsctaAKNHCHsWR*#mz=MZKHVFi2EHW?l)p_M~cOb7~PRAjM0tQ-H~E9Vyl~Vt_}A0gl+XPc=XsYu7&Iysu2{=DQ zIzQlC5$Rlk^G2le2F@Xo&LKFTL^_|~+!E>Bf-_R2GZM~Di5$Q=C(=0w=buRDADoLK zor`c@igaGWIV#dQ3g@dx=PR7MBAvT%_DkBwnK06s5a+i@=Qo_|BAx4S-ivhJ!#Ob0 zIS}W=NasVG8zY??ah{BHp2Ybx()km6bfi5Rduyb<6?<-^Jr{d%q`eq>bfi5Rdv~P0 z8+&@BJso>}q`e;Jfk@{8oD(9Q6L5Zrbbi3OBGS16vOUrn2J$@8*#q)C(wPMEJknVO z@;uTR2J$@8*#`1F(wPVHJknWc+nF_ud?)txIL{2fJ>2<@y05kw_jtGqUbXN7Gx^?d zM?7a#J+q-!i1qhw#ro#r9wFA>Hv=1(dS!#Z<+^Jcnj-asKkCPSH8e#Z+~w~tW;V(( z{VIm|eyxk=m}qf`(bRoNLo?^ZuYDcPE78OGc5+_GAQ@kz)cbw`WJRdV0WB=DZu_ z+kmeewKeKJJA7N~i8rGG3#<8WqYE}fb-D!m|ILT~hz`D3#h1VGVJTC-M3#u^s@E+(wl3ha&gvHTsdJ&PQ{|*?@dJwj{u=*UU8%k= zf8o!r@$!WMF9mK_t$`&y`Y*BmORWDA>%YYMFR}hhtp5`0zr^}4arS@32bS+{*e(8f zcOy?{HqNed{E+VP>F?$GI@vh8e#@v^d}`0ezRt>2xA^1j0Y48OM$N*vn{V$H4_Fv* z=ZCt*2Yv|nu~psT9krVHZ@+x6TRh{6fZP1mEw0)-;6vrR$7l2ixMY*=@!gjOy!5K> zakX+yJU>Mb`z3maMGvv)Ar?KvqK8=Y5Q`pS(L*eHh(!-^Ha+4M%WGcWGk);iF!!=? zcAd`ad&Ikz)bV`C#@Y4noY*t|yw0qMumw6N`Rg(N8S;iA6uL=qJvmUt_^?ty#*DY@A)^@4W8ufn4MHmW@w* z8#1AU_2tVCcZ*x^2z4e^=^ppG&v;&`4*#V(#MyP!Cd)Vc)hB+sVi=cfoLy({C%xl$ zcb)71n~k&UAF0h?bI-IoXa)a*X-FFyvFmv`?Ik9j5FThHzjuYLYp&nwYSK8Su|(N8S;iA6uL=qDEa z#G;>A^b?DIV$n}5`iVt9vFIlj{lwYyKfbF^ys&RA-_K64mRMX>ow)KhEjSBeU z*ZRaI%LP1kRiF5d=WF;n`{wtFkLw%o-;?^p6{-Y0V^E)X>yOoaoon0niRWz#xNE~c z@vUzJoGSlM`MJOMPU^4zw0F|ZI~#f@?KfD}JNfVMM|&sqRG-;9p>x(fy%YLRp4L0* z7t7!KAoP*-N4GrB)5dlhuMC*&uP=SRFXw-wYXT-c)t3ZJI&c0kVAB8S!GPJXxBeY4 z`>S&DLG{TWwL`wCeezTPC7(qP`7b&-E}~!K#kHS}RfpyJmRM~P>tDp8fmpN=i)Lc= zg;;$gR^N%m6Jqg-SUe;aZ;8coVvPl{#)w#Br*h6o)#scf)*K+#+#uGRA=X?X)*K_& z+#}YUB-UId)*L3*+$PqXC)QdZ)*2z!+9B4OBG!0u4IX!Ke*D&}E&O~N)+9fkl^^hT z7v{%5>~8MMAE}lfH@+?4Ps-%SOUnjq{!YbpU(NG%x__05TZ|6)$G1}P(Nw^%tw_ah z)(iN>2U79E>H#ks`cL`juK(08ZU1SfZmoaXzqd>(`S14QQVBid4z@|?Josaqg#Llw zw@LcN@_#pO>FH$srXScehkR4}TySRTU9@Db5UAv^Q zefhdnJgQY|JNc`|_SnEwyt7Sfdr9?N+u`O^{CvCC_PbuWcJlC4T<)sYcJ<6$d-GV( z->tR%abvFi^6pf8Df&|UV6J`T;Z(c@c+lBR>>G^+dHBrcHK&hQHR!cQs*YN z)4EhVr+I6;b3hY&-nLZya)Z{k`j94e?sGdEohCM26?53p zMzyk?`sCPA$LGffRe@n%)_qDR0cg(TJf0>H=m27RF>z-q8{~#3)uhH7( z4a~6*ZcN3)nu2d*bL<;yQ*n>{*7n=^Xy>U^T)zwItk1C}=cnSCJzLwYpl9xkRJ;Uy z{^0CJcHpE`JiZ6oY~RQ(yCW61MEz&(Ze*w5mWs=O=VxtfWLw^tijTVjV_LkiJz+p9 zE`NDzyQy(wdnv}~_#FAsg zl5fP4d&H85#FCT5lApwqtHhGG#2T;cdCPS@rD`g!`EH(Fct&IUMzvJ@%a%NQ+gpw7 zZIDq-*X7xd#y7GP>ZaoFp2@S{W6oD-oQfMgl4rjv-N-&4rQ%!0<=OrFa_rugm`j85 z>|<+l?CcJy`1Gst?4p@D_VwPWIQOzVJ8MLaJ%4a2{vjvNUUF@Yojy7hk3B!n7VVm2 zm)(o`RwK_Yz?`qVFcq(^nPy|;bpN%zgV#2G6)J%>&bTk!@doj;m_+5^@rc{31>6bj){Paflg$nuc z@wv@y)u@r(Q6oP-ZbEb0;L1j}LEZd#&#TStf?kbmGpygnC0f|3y&Kt`x%qL`W-aV} zT^re>SmTF>wXmbwHL@Ea2WHG`VYB7roZE8k+o;oFXbZb!P_E6xw_oJ8u-$LSwJRFt z$I;)-?WUo*_GkR-(8lI=)#O}T`Mmu2p@*8=SLfy0Ugze=m-cIJ&vUu9<{A0%=jS!I zKYo#GYn+%LpYUUzJ)u++JM@oK{O>h+c2&J5_ILER+g*9~x%?(}&CXQ(cb`1_W}hZ@ z{-#vixfS>@xQYE7@}X~To~;i#Id^F)zOiy|VaCD4&vwWAOYyPw4rO z+fUZbvuCtuVsE(~vgP7DyS8Q%JEa@Ot4*FAa4gpry&@HFzdFzEc|X@4x)kFwG|%pM zG}qpA5%!?zdDs(j?Z^hHc)_E2wnF_}Te}YA*zsR=e0b0&dSF2S@DW;@3HKCf%zKXUE-3p>V>f2nKh)^B1j zsnjt(wP-zC2m8gBB|FAL&!}fl1`q%BYlpb%1@-Ki!<*PocXx<~HVfqwH*|##ZI4pKD}Qzf8|YNjsxXYh=~Fc_+u}zwNOu zM9-B&a;)gQrALkx{r$1-)GwB+zpO7lupRM-?Tc^xulPxN#Anhe{*!)<3;VUGRVr?G zXJg;rr(2}rdZQbAKJ1QD@!AQEJ%9Q%NyV>EZ|wOtzIG}uHM_Cr=i?Poe`#aS=gUf_ z;ul|P?8ocJU)#iIZ*A@i{N}#Ke!RZgi1NdseA>!3@!*qkef>RiQGRZ&Z|ANl zZQ}8ba((-?hPH`IwZPd2^Q85)ZQ{C}ay>nRy0nRh^vU&f{(ME7cr4~P=i520QUB&# zKVBEKY!iQTORgU;m6H#uPyVPK@=fiNpZYKPEPBX)(aCWU{Twg#i{x&O;NBm*? z;v4@fev%&XnRJT(950Ov$E)1+UE&?zpC9_$ze~LO$MZcO+V}1fN57u$`LpAyE^+HW z&-Z*g)VfPNqhxK*&k7f#{u#ABpV!pt5?^wDZO{KcWxK?WHLdN(>xI8M$5*tk?Z>Oz z*PY`>`-k#l?{toTyCc-^@CwRjgm(T~(m5{icxZp#L!ILpFVyz`brUDe>9 zbA0rj+MdpSH+7DSeN@}iKl6Ij-&5O<*P{NN;~V$Y_T!~;@WKz@qz7#KWtxoJ=;<8PwQcM!ey4{S&LVf*J4 z@{Ru$KS_`HOghDXj+e%TXEW_(#D7d|6W=*6-|K_fSarPo{12VCk~8e%__bZ)B}JS0 zaTlh%9sY8ccvF#Pex9^g*CjT8#eV+0`ev87;cu~@SBpOA5`X`7?C0C)uTXzy?C0U0 zBVFQnW9;W=}3-hNiKYka}N*w5#t7j=z4x+|1F(za_nWk{%h*|jLYI|v&JQRe)|3KKWM-BPd$(6{LHZ{zPw{RVo#o*pTZo+KUQ>%=Y5jr z=kuE{;9R{k&#$}YnT~PsZFzp(Ro~Jv&aBV#>!QeR)L)(F*WEQgb&ShCmgm>qOGP@x z&)%Eo*IoZJJH^LFl81C4#M+!rNN!zmbF6rW5#ug zGv&j7d)(hCo>x53bIF2Eai^n~c{LjUD@5j|W-qLb@O^mE;*Uo2ODSzml$JK_)97vK0_@ssq3&!kiQ z=epClaO^ZcIbJ$%|0n1{|B3rP$4lol;=32Oi}PP@<>#j`$8pRP?c%{}Tlx8%|8%?f z%T=xXx_k5acJZ!dt^B%M`f9uQf%&ccx|{rNyZGjNTlw|!_2=#4ukUQ-*Ijg^T|90; zE5Gi(JGp(ly<;oC?((X)kH^_izTo2aalP81ew%hEFCW@@v|s!9tRkWPBE#Fq5A1L0 z|GRf``}pR4Ej>M%2iwQz?`Y}iykvg+xYCxEe%+n0xPAQKhL*lxe?Q(ne&O|&e%+~@ z^I7#d&(#j+zuNcfqVT_5FQSL*NOW?2iGHp-^^4`|FYAjBY)AZI`{En_D}It5@tJgr z|6F$(7ml6gC&x?YI<7mN_o(md97w%V=R=+!bZ(@4(|MBi2c0u%f6)1p_6MCyS+4Uc z>+2lLc67dF`#SgXzd8?-9-Wg(r_Rr$U+3yf^_Z`Hi%udDU%uM+?EKFV% znVX6)dobna{JV=%@k{rl{94F|9sb#gDZfT8Sd)tT-=6Yo^MsA4KOp7T=Ad1v_?6Bn zzcyd}F%@^rOZl~VBkls8yfEe0<|f!GJ5>zjRqN-+MT&*`+nS?%e;eOUjc&M)*xe?q z{TuS*{%^JM|Lu2YetcO$8&A(=cjd=_u4v=w%sha*h9zzM+Pr5L>Ob1X_iOx|{P?bg zZT#9)Ip@6Ub1kSHt`W8G*G}Poxu!%9*P7_$8WjCpo9Y+K)nC>ZAJ~rg!}i5D{#X1Y zJ>oOz6#uz4H7?oX_}_c0aBuZrd-ean_G->C-JuZ621xv0J7=!tn*E<*=hQg<_b%-J z+g%v%XtI6kWWSyG_+{ZFuUb1#$cH?e%AiRB|rEFWoN`A8GXN19kZ(!}zSCYFyhv3#V7Cd@YD|-$eZXwvWqao^|9iPb~j@;%vWty-i@b-X;+1Z3400 zCJ^gw0_f5ol-$bnUO~iWNM6CBs#CqRE{GaYG$3Ffi z`8WQj`Rgh^ESF3s);>k7eTrE76tVUxV(nAJ+NX%M zPZ4XMBGx`dtbK}D`xLSEDPrwY#M-BbwNDXipCZ;iMJzc?tUZNTGMQL1nOHKJSTdPd zGMQL1nOHKJSTdPdGMQL1nOHKJSTdPdGMQNWAhF~#vE(zcx~kz-YyaAO%t)+IuYv)6tUh$5$nwqvEEV<>x~t0_5Vfh>?U4$ac0rk z6XT<$Ya`y_#hG8KPK-Z!yOzf2iz77fIr zfmk#Uiw0uRK%7m(PY+M?G?4y=d!{9{T~=dyLUWPprYC*5>9OfaA79!rJ?VR=e@{<% z@>ivM5?;Ml|DJ@0r#HFB^OiJZW6{8J(LgL3h(!ajXdo61#G-*%G!SRgaQp0u@y&yc zAB)3tCdNPi5pe&76XR#a(=fwD@p+T9QeYPn?C5?(`FczYE8%X-E&syiZt-9Xl|31C% z+cW(CbzNQ8=lWUax4!H5TWj6>zSp|%)i4pxDRkVbWg@K6q?Pr5{ke&7?MBC4FHVHl zy?B4ut$pOFiSVf# z%)4x+jW8ZS7nUAaI$`OD)h<}=g%t-_@qraLSn-4v zXISxvl^0m~g8e+IPhuAn6L|OZ(`-z9CO$oGZDQ^8+uW*->9?P~-q_mdx8p`Rrr%}^ za!kLyXP{&H?Nj-V>9;3Nb44xD^055C@(-(CSbAXTgry%=yI{2!Rvci(2Ugr*#S^CQWi>h}-B*{+bxhwo zx>o~hr|<2l+t4z7uVj~F`d+GW5MChB&70?Rmp7eQ(7M$Mn4_UpS`k{g84@-z&YvF@0}AImdoqQhVu# zzFp4BvamVQ|6g4JGFaex&cSaE|DPgrq=6@OTHft4?qIfOjI@0%PQ z-ogFG7{@?ahmB%hWu>8ZS7nUAaI$`OD)h<}=g%t-_@qraLSn-4v zXIT3ETwq_nyD*&>pWC-6vg48RIcV>5TmQGmuVYLfZdtt=^R(xQ^4OTp1#TiC_>U%dYJzu{l+|b8yn`4T? zsY~75HRRx;aN*&O-``glc013_b$#~~hR5IS=0JGuvur4#LU&O%ER&l%Rj7oVd)X0Q)SQ(t6i|#3o8yVditMY-hDLO!}QOL zH&3_R(e%$bS37>w^v@GEHM90Hrthup;kd~3$*CVSwRSkKony*ew!mFa`P(XiV|?De z(9Oft^;0Luiiz@t9|VeRCo)1d4$SA8zaGG*TVuzC7#`&My`&%Cag)=pjRXYG%J zawI*!&7I0)mme5y_=i<5j5hR$(Wx@%ht)1v?S&Nw7(G)OhqgR%yLqL%ha#Te_Hay` zFWcUi z9=rU&@(-(CSbD_hR2lTcY8R~b!iocoHtrE%;&%DXj)`ZTjKY=k7bm z(S!H6dlR_hWOvU(nZwt(dl~+A($S9bS=!Cr?@(7__Wn31N7D1#+^M{BjUQP4Vbu#u zj~JaQgML`;g4JGFae%qjn6rLud9Ep|mpSH|GVU42TvHyu*)i9Y8|pabnsVIY_V#bN zrkvZ^G1rvxW)Cp_xu#6+;+Sj7Co9jlcCIP?&UVZ-rBU)cYv-D>x}{^TDOJpOY4F1} zC8M)r#gLpz|8H}x^4R4EmVa3F!qNjvCoKK2+6Ak)ug zpZyz{IQ%p3n}`Erisv5izstR+o)w_ke+KgJ@~lJ8ozSo6QLvs$w)J=UuR# zgTZ<}2J5*QtmkR4p0mMv{s!y09IWScu%6?=dcFt$SI-YAqi59czw&ck{~7zg^19C< zjq}5iueke{#BurIR}&qNIWRx$G1&1(-z375a~!YyJQ1G%sk_Jd?!82K-vGyRmnXvd zU%UIATNft6y4O1HkxYckUw8LAQ|BeZSDNnUS>L$lHk6rgnPdL;ocZn<4nEI5-7$4- zo93S9prLka$7pM{)jiKa^C8bVrY(c+bxa%I>F@aY28C&Enp2oAQ~koi^xv-OUYPc| zsb68buK9xt(;9vnQkd4(`jNu4=1z|mrrUDJsKQWfgw=M+C?@=^Vueq|kh&CGG$`h1 zQ!db~9MKl#jy950)>04tDIV6EG|+O}z435mmg8@KiHEzE-Dd6IRZN6ydN{6mcp`kU zg5y(;H?f_5t1YvtULve;tK;d-65-cpIqqlHDITcrc=QEkjjy`nMP2vX@4I1t`JT7$ z_j6G0e*ec5@2@u)zF$vtOd_pw`?y3}f1}3}>2_hi`S{zdPRh5>cZ{EFb~wiWL+$Rc zWvF-WSjXsT`LSbkwy$)jErb4&MviIMGntNQuk6G@<%y5{5I6ZJo~oBPOAqmvPVyrC z$`|);J}Y$}=jZQl7k2eq%Bw%)NBtcC z>i^WMae*F<7j$YIp?A#UvvP-B zxr3EESh<6hJ6O4cl{;9ugOxj2xr3EESh<6hJ6O4cl{;9ugOxj2xszSvPPxOb+`-Bn ztlYuM9jx5J${noS!O9)1+`-BntlYuM9jx5J${noS!O9ooZsa&~@00DWLGO+)3WqNl zVCVDPCyT=xL;lpu?);Ol#g{QddK6>`u0xNg0atAASuyO}0cd&8?D|fJR z2P=25atAASuyO}0cd&8?D|fK+rE!-S9JgbHGV9tn=5N2M0 z?qKB(R_0?qKB(R_0?qKB(R_-bfXrB6@UUB$&ek}U(E6r0~%^u*V3S!Z#zG(hs$TiqHmODrHV6(!?`PB(WlmDrRroC zhs`#aGCyRcdbBJKN9>D5#~hlSsu~oBr=JjywmL35b&MGc-6Qenpjz3f3(XjLxLZ8B z{KRY<^RrC98e;4njs5F!ar51{>{NAAzD8+0`lazx$M|XaaXk9qk6EePjQ_>EP5Do< zQV~<{u~ie%1LtR@rWidBo|=f>IWjBtz0omosx^_nMR4)^U^KMB*j~m`Rwa3Kgl>v#UVs-MZiRj>_%~MyJGCfS0 zIXg2`Yt7$&WB&Gl8JVd}<8z+z`Tf0_si>)I(xr)La8YI|Wi%{klZZ||DKmA0(blkO zBKpaJnW-PL%(y--5xss}Myk1KOVz#c=+F-{QrjcN;V0|k(Q&V5r2gYf)2;>a=wYvB zq;gD5&Uqqk-fPK7%{IK_{&=*;;*3-;!w+5^H)p?Rq|P_7ni$5T=e?hi>T6;({ls{5 z(&miR$HsrOLOgoozKm3L9) z)2{I+_qAi>W%IW`#T`$qUL2mi%5j^+io@JPZnkB<-BT0>O&r(zvM4Obx!KN#KFcT9 z3;BfQ6P8cd_qp?;qVT4N+;wxF;b~Rfb@Q$EMd7Zoj$4`aoEU#T&7#`Kx@y}+H^IZ=* zK6#RPCi8;hO(P1!0W%!GnrHTwJn6XOfWq*?I~-T(Sr}$!Ixe`x>?>H~o{Vy!Gh9aNoo3{{5CC z3d4A1$CD}-hCk=K`1>rM)Fq#=e8Tbx`#w*(wjjLfh5lAgYjZz1cdFyDXBC9qM>u}+ z^n!5n^^O&;sHri(3q)7R{w?dJHS zf${L+H65+J*ZuME$m<-p9U2d(9pJdyWAX5sX&r2t+os0DqJfUzPsYP9J2;-dG9Hd> z)4{ggXX&S1(ho~NEd8+b!_p5+KP>&Q^uy8*OFu0Au=K;e{)5JvIjZmVwvC^UE)M^) z)$u)#nt89s4c5Nt;o`9Edyd0`;&5|#qqR@JuQQCl2O zA6^_jc9Y9{Khwr_KRQO|gGHBE{XRyLcGkS)?w3RJ{O7uN9Y6SDL3s3W?q2(}B?V#ayB!ys4_W{Gz2jQj3c?#6bocMK z>@EmzZ{hBL>mFDb&iK~x&O^;J`FZZ1SMv-yr2&=(SQ=nyfTaPJ23Q(kX@I2xmIm0@ zpm`g+KkxbMm(g{K^8P&Uv&xVo|5_I9P!vA2z{P4>r=oDlcP@q}U1|39Wjen8hN7^; zeJ=j>?kWmSK2upF7*^9nE(jidy&h*(Y)8mDB z`0PISJEV!>Z3%ZxY-Qe|Xk2#Pe0gF#+*#zVp%cf&!;J^H-xU}BH6DJ`*IoC0mQV67 zpRjzw@(KGs?=@>8ACB&4=c~Fy%%1=693OjkBD}vyBt4k*7BBJ@8GV6LbxOx7in)%@k+Z~Uoo*&M>+0FSCtLBG){lf8amGi^xSN5@Wm8*~+ z?s&D2olAX|9&}0%EIqLFz|sRt4=g>f^uW>s`+BPNi-*Teb-(vE_lSp!D&1{$zIAat z{Ex1V&pFFn--kP1YTm=Tc825kYR1ETNypzGX8O$Yj;HU5g>&PMA2jb_<+XME^V(S0 z;A>acfVW~{-6F^5E{TQr9_{#z(pWhC5!Vk}%#DTPDms2~b}a00hg&c6S^8<0^uy8* zOFu0Au=K;y4@*BR{jl`I(ho~NEdB6r^|w3hDjVDCrd)jE6PWId0J|9`^o=``dw6#KTA1IX=n!4&3~BSKB{*Cg$j;UD6LrKP>&Q z^uy8*OFu0Au=K;y4@*BR{jl`I(hvJO)lZl+Wf!Y2`E%MdGfysW=I$5jyb=$~UFWXp zqvn}+m!5Xl`j3{H-?v}6Yutzr;^Bn$j<5M59#)?3u5pX^#lw3paNPLVM7a5TcfI@h zv_zO#;8^n*dZYoC23Q(kX@I2xmIhcFU}=D*0hR_>8i<=emug<3jO?&)_pb{+Ydlh3 zjDLTAQ@^5&?6B;VA9`XueCU87w!gi)tlI?FRtx1Hj6Z;j@u z15S0!vzPT{TyyDu`;W()=RalT@3=lI?Wg#qth9ghNCPYl`22BdzSZ;N8_iSSPjOtW zK~`$dB*$~_&Pr8(+Hr>^S*d%+IezG%>{RCwjt51uQ=b<(zWbW&RKEutcN>(QYInQi z>+-TwZ{E1y-l6;c@{Kz=#?S2Y9OM7&&@uI%aE4>_+~3SGIwzQYDa022PoM0Vc0Jk9 zahp!&js78*7!!c&R3UMGl&FeTOZllbz z1?U!LQh2fi~W7JfI#af@Uu92RxFa$zj| z;6TR%%{$!(y_ILLedXSbg%>`a7p;F~c1oNvCoApq%T!jXv+?{YRF)=iG*ncrq_H+6hKDi#jiVV;MZ9JMuV+4ihsbROM35mlUF ze=dFZi>y@5>hbWUazmmcYnb_}N<5tRbAGhGiRY7tn){I-^P?-x7^zv_yzjp=Kl@IXl(J z{6=awEI;}|*X&gOJ4XKJcOujDanjbA+KRfk}Y0I+H^P{VO&Pr{W9}7P%mv7FE z$x7X5z5}r8jYM?P!mQLdla~#TCZaFR%SwG|+SPVYBAp}J)vA7GD#w&rQ;>)rS~WBE zj)}tsuOySEAaQln-(G6y-U1jnzz~rUEbs4GezKew|*X2hecVwg% z?K6M7EkAnpLm8=O%L<2LSwDf*Phj;ESp5W6KY`UxVD%Gty4i=;Yvv$#?^8BT=}WT1 z>i_=ueQ$7f>O>Qt54+_>8=C&G{A=?Y__)02j^5d+8VAI~Iq&91&&{i$|lYBt}m zxHvaj^T&)-Lo+U(>zx~|XVzaj9c|ukiseRUjn7CeHRB>WIX4=;HzReQX=BBAa-)N9 z$Vg59Ar@Bp+0<+L$rC$F-)@u_U3zUsDsMw9e6@34bo4D5saobfYvQ0^&ruqi%&TJh z^Ka){zi;^SkL><@C6=FzjG}Pk^==-1$gG3hJ>Kz+=b3feHIDBv&xj7G<>u}C%`>99 zy&d+v-tT`C+9*86P?%T>O67vn-FL2c6ObOAjnPu=K#v14|DqJ+Sn^zMe{V7lfZYakuRQ z-xU^wc~3bWKeixTKiBcdDFx=8T*m|F7KE=h7-Y+TV1C2geYYFSKFcR{$tNtIuzbS4 z&rZ(|34iGC*4oz39uls6$MLxfhlI`BxV5$puMIJW06Jdw#*lDMEBB1+k(EQjaGASz z^I1NrOFm)wgyj?VeZIXd5svKO{8!v=zKQXgt9RE|iSWoWJ@@~I`L@Yor}IJcOzH9q z9B(`*KWz7zyEpV%KB-GSVflpR6ZU=j^W@>?+bIWK;c`*qMDq=n%8my&HT$36clmlF zOoU5bc08_QBE0+QyY1ZTvwTvQe8Tbx%O~vn%rWEisRP{{a-SK$mCkcq-teJA9WOKQ z#=g7K@uqe~;WLN3-x9Ib=6Ub=jz2uZ%n$cDKGnR#+wA!=`w8Y76ssJ!s9Y3IG}k`n ztJ!-C!^8GE)_ob;e3mxs(gsT#EN!r~!O{jx8!T4^L5`=KS`aom!|`8^D+p`8f0xbC)ba&k*u`I z3%a^zV&}a*B>Zu>+jFk|PpqT?mIhcFU}=D*0hR_>8enOFr2&=(SQ?0fKL&@E&3lxQ z9ro@1c=1{DB<02U_s3MO8MC+5ba6OhOCpSHbv$;x`Igrd7pu$PG4F$1?P54?Q6d~) z-o^Q?ml9#qhaKNMHW4m3z~$wjnE75!7st)}B*NJbI@UNsk2Jv2080Zb4X`x8(f~^X zEDf+Uz|sIq199;C{2sF=^5GP>PwZ>MwK_W1^_0I=d06FPm4{Ux|Niw?b3SEchkZM1 zbEC4{yaYGC_W}Fc2Ch^dsF_l z?9|}Pio<#p^P&e`ot+9UGW%hU%!_Vsm7O~69J8)^yy0rusYlGdnuay=qBFnDN#=-03IgMf=>Dl`1lOX3jC3%F0Up)$Dr-Oqt%hnx~eSJwo+rHnY!KV zN2*}j(qdd@YIvjKFw4aMrf!+3H%>MCjtqZneybm0_BgFG{Nb18IhASqHKzQ-rREt( ztKzWo33<`d(HW`w=b82WWAmaF&2RN~9gD+c<-F*!J{hSomlua`9gr8jrDsO!!yaaD z_BXlFQ+s5jR^DLtT7Q}wJhUqwg&ayNt_? zzG&_RswT|du)A`j(-&l3jBCbS_U(=tkF8cXW}J3z=5o#Woix!gV=!+u-JXMd8m)9IH=iu2Vc! z9=poJDvy7^534^=Mt0b@YusV?`;5;jgMWW)USG91oNvZB_I-xC{$@_br^>@B534+^ zIb7FS|GEsn(9b+$dBR<<>($Ci6;5>g)@#j8yBu?!YVw@p_SN>=zh9i0F5maI%(Nd} z*A73m$gWMSHgh%1Gw^p!zlC`=KHXd^VV;>^Z02W}XX$sFy{|CO*tebSm}l=-cW}(J z`k3k4l;K%D-wKAY-#1`?`KJau#?P@s9OJ+65y#Z~vgzCWEqXdkaE#8=OdPQDtiG{{ z1FSf}JnNR7XW%N&vvK+1nYsM)EM4{Tj9q$o_AZ?~lb3#;)vI0D)n3Xg4){@g@UOU0 zui}Xw#TlK7Kl+syKVRZM_c{O9`1=KR7bj=2^jUU1AcqW3F~xptH{YetmknsSO+XN0-d zj9=lHYt~WkJLcMyW!AYU!!?U<^~2bknY93z@|T*mGx>R~l4JZwj&)4E*P3+)%Alv5 zSqFj9`Kej6fYJZ4S=WGR7kejQ=6uIdKA^%)cR4>;W>ERkAom`uwpKF%d zg!D)SRsXm4mi)Q){lB~R{lB$8$6xRMci#u{N9>>EnS*~O5zHLU^Mv0rXD3lUt4}_<_INmJc|&V&cdt2Xps(Z0hs47ZPH?=>ytA-=O#@rz z(+TEpr#K$>LOi_kLC2h(bZgA=TT2J3Y z%y|lBI;)%S+)96!%87Klu%Dmn+DrL{J00WaO!NIQ;(-4fr#q(J)fF0BJ9?_Nb&Sr2 zw>w7vsJ}Xa%i(UAcpmJ6O4c zl{;9ugOxj2xr3EESh<6hJ6O4cl{;9ugOxj2xr3EEShYs>uYS(%RU+4zmK ztev`k>E{>?!)iH3Tc>rcY#B74WzMm}KW%yYVaK#_OTsa2mz|iXJh74=VkrN_R`n8d z=^=O0N$#Yd+^JpIQ!&>@%8&cnF@9dT{A{Ze|DVisOuZKz)YjV3Q*^FlbdI~zG5RY# z>X>$Y|F~n?D?4#edEz5K#7+K*r|Kon(nI{Ele|bjxuadmqgc69-iZmU+`-BntlYuM z9jx5J${noS!O9)1+`-BntlYuM9jx5J${noS!OETNv|Z(i39Q_~${noS!O9)1+`-Bn ztlYuM9jx5J${noS!O9)1+`-BntlYuM9pmE4v&}ggW#ewFS?f{1J@0(;ZJDxh*UqdZ zsh{84r6}G1?>FmN8W$(sT$CO!hYT`*TQ=?%4=GBIFV4%;xI1p*e*3#G?=L?qwck&- z75n|)_}>0{hkd+X&+yOp>pW}oe*O2EbwjlayZSBV)t~XBevW_jf9ln^K##@?IyH{a zukl5@H124x?8HIkiI4mcH~A-?s+TxR5Al~y@*@4p7kTtqxx=p9!O9)1+`-BntlYuM z9jx5J${noS!O9)1+`-BntlYuM9jx5J${noS$*ysy++kPlVC4>0?qKB(R_0?qKB(R_c4DIP#7cgMq5KnD)l1B!hg?V}xs!f! zr*>hF<+(Oe{+eBm@pD&~GpuI(Pn_YHdaG1yVeRPYaE@bi_PoO}`rjGun0A$ncT9U_ zCk`r4eB_6?$v^Q_y~J61h`)4_7wIQ=v`cvuD|gB}F@cpkSh<6hJ6O4cl{;9ugOxj2 zxr3EESh<6hJ6O4cl{;9ugOxj2xs#o?t2{A*l{;9ugOxj2xr3EESh<6hJ6O4cl{;9u zgOxj2xr3EESh<6hJ6O5XxYNBJWpsbU-|D^zpSr)JF5PFLLHA#1)BPQqb$>@&bbm)1 zb$>_OWhW*oPpssJ7|K7fRlUSqddQu0k~`@qcWM`Q-5*h2_f7cG{S^LnpGCd8|3Z)M z%h0L&HT3H~j&|w(j`qq<98{k8$PaOof8wcniL>+&f9WJI(ogPmuCdR`o$^jhVC4>0 z?qKB(R_0?qKB(R_6|q zFl$e|s|&M+#k;yNYgoLi3$upBJIJ#0uCB`St}cup-qnTi&%3%X_42MRj2_8wVdB8Mx-jwKU0s;C@vbgRJb70aCeFO83zIM2 z)rH9y@9M(ji+6Qp=UrWu=UrVGKfJ38+&f9WJI(oeqBF6?SAg0GSO3?$`Fe+4;|06M5v=hAYuv%)SMSb~cfC`u@k<$vYn9i#`S{U0`}o(p z{M4&={L!O#|25Cx2mSh10PWH@1jOp|8VmYc?D7e#E?631X@mcqquhM^N6k^XrYLvh zSMwOG`3=^*2WvirHBZ8tKVfNxHQ&OThhAvFd%7^P(-h0B(u;cjpmKQZ0 z8h-qyTZ{Lv*Sh}dzE#)puj|Cp<>xeyrTz5i6ifU6X>crE?>WP5z6T5cp6@(UUf=eF z{cnE$t9~;Xo%(($tnZq_f8@7<@y{61cYtBO+l>A9d}EpN`i?8?f4lYfd_$hU^}iGQ z&-z~O@A=L=n*DG5`rrQjBfs}fz4{h0?0=*9_k5?FztuO8VSRfU*0+~oeR~O#VSRfU*7pqIf7EwesY~Bxg!Rov`1gDlm-7BMA@yBK?D{SxtnX67 z`Yt7`?^440E+wq*Qo{N!C9LmK!ul>H{CmDFO!@!p`;*xJRlf&|Huewe8>H~R!?#ua z?{oTl$=K_nbusq9XuXWRFJz9@L zr`GAvuk}0HrFA{pD?4#edEz5K#7+K*r|Kon(nI{Ele|d3zXwTs#%LquweLuK#;|M8 z7_2>Gu=b3>+A{{DU;FxKm-ZcL&lqL2XAIV!F<5)XVC@-$wPy_0o-tT^#$fFklU@6E zD6joI+A~HO?HPl$XAIV!F<5)XVC@-$X_xjL(O&I4(w;HOXwMj|J!7!;jKSJ725Zk4 ztUY5eYkAsF#TwtA`^1{swO8%qV(nG?yI6bGzAx5Zl^34hDqpO<%Ff!W%Cq(=KdimV zKWneQcb}N{;gB!w&ta`r`*v8v)qWoQYo8DGYX1*4&<0X>S8|?QMXyw*l7P23UI=VC`*y zwYLG*-UgU6+&R-6*17Gl&TWTvZab`V+u@a;yK~!No!buU+;&*!w!=EN9oD(+u+D9V zb#6PXbK7B^+Yam8c39`O!#cMe*17Gl&TSWSZoA5GZab`V+hLvC4(r@@Sm(CGI=3Cx zx$UsdZHN7H+iAPba3?05?M@kD#hLFgG2|?GnAmbgJWR|vJ02z%oGA~JBhH$K$(`Cl zPSr+zKaDcK=evlM|IfY=hy5S*Eluju_v>JN*AD(Y-<+hp|J^)&yAQj*-3RO2eXzdW z2kYB?u)f^~>)U;>zTF4w+kLRU-3R}k?{-pN-+Y7hEjakU`;Auq*8lFDzEg)?->HN3 zojUlR^^HgWo0I>@Zz=2jQ`!#m{we%>z7tM)eQz25?|uuEzxBUEsP7+Q*Y^)$eg6>F z_YdvgF8c3(gV8?=n6pa%Ja^lyS^Nv1yX~Kut~2iG13Kd#)*1J(&bWtl#yzYv?qQvA z4|C@G1NGfmEjr^KyUw_Wb;docGwxxXaS!W^dst`O!#d+0)*1J(&bXJIGwxNseZFIz zagSYR+`~HK9@ZK6u+F%Lb;docGwxy9ThhpVqfBSqW7iq?u+F%Lb;docGwxxXaS!W^ zd-&j=;$f{x?z_ru_r}AOS&qN`B_8ftcAIVEcjmk9YkD}Yd3Yjxv4Z1Mj!%TGrn_9M zs+R~W-0FCGvqbpyS&sWf&G(AS@-_N`L^!ItvoGqp-+tc>`^)#deZQZBa`*c`rg(q7 zfjMhTdZJ?zX`S20CDQsEJ)TIn3%l|~dF2Z~*X(e)!~a9=-1lRtckfuo=xO<}V|2E! z z!&>`>we}5b?HktGH>|a9SbM_7(x5#6*tG`$)*b*@djMeV0f4m!0M;G=SbG3q{q}(M z9dcOTA&2!Ha@hY4xqf?K*L?)6-yyJmhrs$B0_%4O{6F~)v+h~&qi?yx`j$KFf6HC> zEZFreYs>$H^9ZO{_bjmPSzvu9AJ%vBVgEb%x@WLpDUqz7VNrb zfpyOU>z)PHJqxVw(!=^LJ*@B2!}=~gtnbpp`Yye-pYZp8GoSLhXMuJ83;ai(6J-6D z-Lt^DXMuIL5v;R~VE=3*-LqiVS|_ZvPFQDv!a4&K_Rj#-S|@g`b;4TfgtgWQYpoO3 zS|_ZvPFQQ5u+}x8w|3F{nHSm&t1{yC~z>%^|}^l{f~=SadjM-tXKlCaK^ zgmsQ2taBt`og)eB97$N`NWwZt64p7Au+EW$wblu1O&`{pKCH7@VV%ti>ugq7XS2dO zn-$jCtgy~zh5fTxwWg2Vf457|tFh~OHT>thc#Ulz)AMQ@&$9O@VLh*g^}HI^^J-Yn zt6@E_hV{G}*7Isu&#PfQuZGFjpYJUHd%d%)Z>o?-)?1ZdeN%*Fx%DYDaVRi5=1`Qe>Y`R83!)yq4o(!;x}(#gB7 z($BlDY8UqZSHA6_{S3rV`x#*EXMnYz0oHy7So;}Z?Pq|sp8?i>23Y$UVC`pswVwgj zeg;_k8DQ;afVH0i)_w+9`x#*EXOLa_(tZZ)+Rp%MKLf1&46ybyz}n9MYd-_5{S2`7 zGr-!<0Bb)3to;nI_A|iR&j4#b1FZcFu=Wed&VC`4*SqBSVSf&G{IhQdre5~*!02J0 z4~$Os|G?;HUl2^Y*e?XrUfGF*$`c>?A#UDRtl>e9Yh_#Shf&Z-{ny!%ZL7l&=%a~u{FoAV8CwA!?9mh##+3v1sjJh6Il zc=jrHj$WI?io@JP+!=Y_?kNg`CXTglmh##+3rEd7{Lq2{wytUB48bMe-D3HqE6qNN zOvl&XV7^0gUw><_cb7SvW34;yZ|ZplTCFL|OUZ1u6LYwm1wCP;qSIen|l`GXxD zYu_yOzSZ9B-x%x8fNOP5Q8=TzI~y(|S`KEmbk$3hh z51(>tJe+vUrMA5_O+WAQNGHobUl$LrIMDGIz2o81ftOhOw(HH<*>thxZ~Df=1>GEf zG%y}Myr!eI_qsnG9(kSPwnO9Lv;!Phdn_JaGp&OybK6w&{kMUR-%rNFFFQEa-gvZW zZ#=BM@o>e?#o=jpxbh==7l(VNJAP!KIg{vMSJ%C{=G>_Mj(3|gt&ZB_c>3_-@Ufem z=6>d^igiCa*4}vh!+iH1*1III&SrvjHWRF~nP8pG1nX=jnDbfwJLg96w|bWZ*1III z-X($cE(z?PJ*0O@uuLRb6C9vL0 zf^}{VtaEc>1BFru>n| zx@!S`8s6&||DD!2);cVH(6jF*ca1>jk>ebr|AD!VX;+`cj%ly##6jhWkNgm~g{Qdk z#8dSWXXzpS(n(&VU+b`F(>g4yby!&Iu&~x)VXec$T8D+T4hw4?7S=i}taVse>#(ra zVPUPq!di!gwGInw9TwI)EUa}{*;yA;dDhEdt;51vhlRBc3u_$~);cV#by!&Iu&~x) zVXec$T8D+T4hw4?7S=i}taVse>#(raVPUPq!di!gwGInw9TwI)EUa}{SnIH`)?s1R zD_MtywGInw9TwI)EUa}{SnIH`)?s0-!@^pJg|!YVyYi)VSnOJdg|!X~YaJHWIxMVp zSXk?@FzsR;7S=i}taVse>#(raVPUPq!di!gwGInw9TwI)EUa}{SnIGbcE|XcRNI~Ti~ln(a!kDg?{KVjSmK~{SXk?@ zu-0K=t;51vhlPnxl~K+oag%@Isd|aC^bmjPBrno`W3@z>x%(X3-jSy!!l!O<+}W(x zcTTmn_6F?}VZUF_w){+|MEJt#j)!$ggl)UEvG&(5Gw00axo1aRFHVHlz383`U4L#O zT)WXd^J&#G5!PtpxMRaaXl?=Q-_|#0I*%&v_$qUs_}bX0wa@r89`@_(_^T!H@bTu3 zKbjH`FKg-e+(+W!fNLFByfYq7ecAE*SDW+Y>o}i%+Q-8~ra8WIbS&)O?@a6e`!TWb zt38f;KOPHv#oXUM`%Em{TEUgidnp#ac9-LqOJd>F^^QMU9t)q&aBUg!Q7k;~R>yt6 zjD<@dbG+rJSh%C?IasW6Jj{O1*%z4eXx=DtT&rn39CDfC22u0=NF~SU+&%p?s}ub_ zZf#dF}87!CIfbd0vA@*Si3#A%Lc%aWarX=7;{=byGe zG1)OOd7##*Rzq(Ss{vQ`^a+=;jpfb-_A16Nd`Oq z`J_a+Vus_Q;}T)H15UK%*B@%mQoq{qrR5S~oi`n4{}>OiJGYK4Q~HhhCeI4TN1Ep( zg`MhJduzjc);Yf9+jtmWSI^o{*=@cVzSZ#)2blAkd)Bx1LFSoE_M48^?>676D%0G) zMNzsfIc?3HSytv~b6&arw(xTE+_lVS&+bL(x(1l%z0&ZsVQKrpl#%9puP92l>v9brf4A!cl<9V!>l^&-!oyvk!ROSaj;U)yAJ@l- zRqFfw-2ape8`~ZxZW(W$Zn>k0+nlQ%ziHxj!lq`{KE}jkbq~iyCRS5FXlm_nUOUH> zxom+OJN#{xz%f2=U+DTgb^X-IG1}VCavIQ_*EQ4nq%D1`G`CC}-~G@rZLj)VmbJs3 z2DxvmQs&X~&q)96-XmIA#^>f`j;X6=-3|knncK-H)Gach|+M=9vUD=%-qb)JpX+U#nw^p_c zahPb?Hwn(YZLt7J?@%CnN{uFwT!>bKFVG1@L6ZMW9qv6W_L{_4!Tw{ zrn-Ea$BdowYui~nV`_32 z$Bea4R-SL|jKO|qJ7#P)N}gx!jM>#K9W$1zEIilR8RHq99W!@HGxLM&%o{4td?G*0 zGxE>;qk5T_q=)%RI+@3$pZQJgV%}4GnGY2Q=1Ike`BQOYUL~Guww#`R{{`0jFR-`tlfB(hjf7ClT|2GYKABQr3i}jukW%Qm7 ztoL+ay{7}~Jsnu@>A-qV2iAK!@NeJK(R)eK!~Q^NfTaPJ23Q(kX@I2xmInB@8uacA zdVEHYuTxAJwS{+ZV7*TS>wO|v?-Rj#p9t3bM6li`g7rQT?7vUsv#*o3=sh55P}}w1 zkThVI23Q(kX@LJO4Q1~)p;PZV{g(CK6L!7#1na#gm@&nBPq5y5g7w}LtoNQ^z4rwB z?>+e}J+ws{U}=D*0hR_>8enOFr2+nXG-!-VCw*z&$OD77Pn&t>Am!7N*T`BycAU!HS3;>}oIN6$kt%KKNJMs8{hskK&9@#UK63i=Qts-?vomVC4>0?qKB( zR_*N1Kf6y)rTsrJa=vBiZL?y5}oIN6$kt%KKNJMs8{hskK&9@#UK63i=QtsIaTgp<<8p6 zatAASuyO}0cd&8?D|fJRCp&Fdd13-9cQF2mA*|fN${noSS$kRTVC4>0?qKE4+RJhW zD|fJR2P=25atAASuyQ9mxl?&^2P=25atAASuyO}0ch+8(JJ`>cnCqQ#2P=2h{^z)} z<5#&OCdwVG+{yk&kGnsApL9%Lp&u&!~iu5q^fKlt|v*EPnS#uu#dW$k~? zjp?~gbGXJA@zMB#bzOsXU4#EO=SIdCKL7j;>8__5U&KV?3)c98HNIf|{+Ioa{0({i zhtq=3cV1pPKJjSKY{e_VH_6LOPiQ?VcxLDHVEMqyOJ8j{I=Fb>j9}=VE~PF0V|4J{ z;+a9~tGkr;$s7~he)Fv0?P-^lo>pT_(4_V3p#Eo_OQSE14hFWG6O25%b7}JHQNih* z<_62Jy|nb>@}q(o_sn|xC+H6>G%8F^h`9^2cM;{F?O}!F~DY?9KYNt^_a^v)% z_N|wfKGuG8@b0%Wf=1tWDGe%)32vJ^GkEBVE~T%w9ut(mc2;o0l*>vdo;)VFuf^;j z_EG23Z|98;YPOgYG(N0z>Bm2f3ZfUx4Q6${w6xPW6J(?e!hsk-ZZn1pfmCKTyuO4lA;x{iPcQ%+|c~+0%$yv{?u)J({ujJ~i zwU)oV=Y-@Dmv6HC`dg2ebY8gC^5rd?*Z1rZuYBP72|WLSS8w3y2|S&Fr$6x86?p9p zyf_42d;%|Sffvufi*w|cIxhZw-`gD-G0gFb0pCXItatpEQQIT4%enlv{%&(5a@m14 z&XbQ`l^oisyo>p_?<8Bz`Z0&t9-4eV`A+sG%ayPAFnQ;K6_)4DT$4Po&J@cp&;K|X zxh!t^*z4CP8&=A4L zK6U-#w4PwWLfU2PYFn@%t-r0oG2tWMAIt<#hQaMK7lPEZQ+O z?Z4`<$?1A)4Vjdbp1Geqla$UylP0G1&)E8Ox?SC$dpg}-?1}^B6(9U4ZunO`saJ7E zkK&I`r4c;y4nPvH3vym|vqPvGeclrN({P`*sN0_6+47l*)$PoR96b_L3p zX;+|pnRW%rmuXkvpcZsy5!c{6{e{g`<^?cdC|>3YpPoYrIJ=d?~UZ>RN}c|JIF_0zUpW}Z*C z7rWv>dBq1miW~kFPwG{i(WCgIQ+YwZ>4yO^H1h`i(6SkK^h3+^ThpH{)1OU0w@g1b z{ogYE-;4{(X1vo6UHM59>4%of#+PNrml=0yyXlAN@}?hJ#*gWTmho@;p=Ihd{m_*+ zdQ3mGj84-JEu-Je814b}f7$r5buqrwUhIkk z0d>H{ zhB{zkM(ki>NlaxY)-dJi6EJ?r4UB(s22(G&gwbQJ4VKYKpTLfO`UFh7WG9v?Pb}q! zSjs=KRK3JfdWfZT5=-ePmTDJ$U+u-NI8a{k!H?pGf5nq}6=(D){^(R*(C_6d>DiNB z`K0G3>G@B3^(H+%Nl$0e)1UO(mGs)1^x}~8;*<2^mh|G8^x~ZK;-B>LlJxSGwwpYr z%bWbB{g}L`{hR)fuGjRFv>wxc(mGAQO6%v^qIU6HK<&k@I8a{k!H?pGf5nq}6=(D) z{^(R*(C^KMNpIXGz44gz#%a{sujwOcJ*JPOb@F>p`b{56x6AaAbbGNY4wP4X@T0ilU-6_~#Th+{KRT5c^wU=U zGtX6$`&N8tuiYzOs+L@Re`kBW?)yxYIx=?pym0rl{osS|q+Z0e+Z1U7XB z#*bxFXJGtWHg!_3Wo-N#?%0y}-5J^|DB=@T%0pFRQ8_vsTbeV;x7)A!XU%C2A5PTx24 zhGp!G4V7oi!1!S-!T4v4!PLvxgVDp7gwe@Zh0)I#hRd$YmKp0RPv4gx`o8?r_f;=_ zUwY{K(n;T!{<7zCS# zU2&ki;)5T>4gZQK^(xNjQT)-Vyr7?FDCEw}QFVES0&{P~GZdJ6Bc7qa+#B%>1?Jv} zXDBfDMm$4-xi{h&3e3F`&ro3Qjd(T$b8o~mBiVVD1XG@8UNC-m_5|afXHqcr@~jF* z56`e*bn?s#MnBKIVCG)W-qI_d|8 za=duvcyZ40;-BN?rKSHo`RB`L1r^Qn)*o7v@}1T5O&z z`|SU%|NQy18=nuZe|d1}eTNSZK5qX)@O<|^rFD-O9<;p6+0VIYM9?n!LNNTRn@XqF zA0AA&c}CEr=L4l5&mEg=(c+aLG~D?3@yUTXuLLLVxW6>3`uOB&i5WrfHusf&Gws)9 zPOAMP{9`U8+=Z=0V(z9rX zD8O`^dvo+Mz}S7Cjh@*Z8L)nI>CmHRCC{xo-*T*sYrj3Z6s8PJ8Q+gz*Vv4GkyoaVE`93Q zUzhj&k6*eka!#o$^Wib`t;Io8Gi8V z&A>IPzcRYCwEyN`jhAiLERS4f^4l(RYchW8^2m*b zUv9HCxg&3RWU%2wFWs8->m9djQKaYfkCZkq-jZBfe`%zDuY%HVcK%vV?eU8u4NRE| zUA80-`e8}rbW>($$(CQ`#gBs@pG6a0E_RoEmOQ;IkJr@QklZ$OU*!7vqf7fu`TSR7 ze^#3cL3~kO=^52FCcoKHA$YT1qO|*a8qPU9d6v&|wD#ht^M&4mo&Z^67UD4EC%UQhM~9U;nM&ua+1+#6REY`R@E}HWwYn zZcNtf^SGv5w*MCoYYp;Jda%XaM>0j>LWbV1PSbpuCjmZuN{bYI4PoF1! zJ$|nJe*X99{Cmc`9}{1{pGSWV`CEDaTV=kS<>sGq_iqTUspICK?ayuqPAlWB@6HZp zm6d^?KHiP-O^462%ov9g&$)j7aTzmCVc$>Hgqz21uQuyfKF3ve^B8vg=x=?WKV-SN z=Qr0Msl5N++NJV;kN>}= zd7WtsbJTmLE&cnsd8y&{O~Dx#x%ukpM>hsD7Jg~RX5GpggS}t9XZfRRHU<9g{rvV9SyNgEPz=`*O*K;H=6A1_znB^z-r? zgT~iZ2o{<-cILSogJI7d82l6;Qu^0|4Z&wSD+I5Z`FYw~8-mN*RtR!UnGwhQeSZ9U z{rqC<*zi`xw67#=hV=FQLX4#Z2F@Iy(_$V>H0{j@?^GqF<%{t-Jo;}AaAMyM|JpU1| zUZXXwC*tX(4(T`h^efaaYga(sW$g;kRMsy1Sf)%by?n zR*CuFvaywzf3s}LmYBb>YXo%CpzgAE1!yX37k(^LCvCt^owN<6PTCApC$WI3lNiC&N$gQm~rjdbG-67o}Y;4-`2t38k?;HHf3!c zu<>E*fQ@hJcp5f!Vz=`rcB9EM<&D;e{FpXa#y|gK$3`8_Pjg!bj1PRl_@)ln><6sp z+2>J5S^0UMAL3^1#LcU>#M4va=`8W|muMbVz8K@CPRiT4i&&Ba?8K5fU{fdcTE@n| zVOPFjeBcXKzF_66%x?2lR^H|dM!V}uq$6MF(Y5jkIR?r#6jh$116Tl z4aPtJ!`S#Yn6lIXWz4MBA(8Or=R|zc12DdbDZtNrd^SXj+$xNv@6nW+hLKic16y9$o<|k?TVas?A6w8 z+7-FB%YBwjyCS__a^umoD`#ACn6;aB<>Z|(!ZPdHo_(HIexB#2#PeU`)m!4}De-ic zc=~^pFWUH2+gUbuJ`)G*$|I~i!pbA8Ji^K&tUSWXBdk2a%43<`=CQ22%_B_Q$RkWV z$s{$|I~i!pbA8Ji^K&tUQ+4Z63?Y z+dRU=hdjc>&8yeu5j$}vk1+8kk1%;zFttg}kzdS?ls~s;XQce0$#&E#OsG^p5v$R)a_vb@w-Vd4ID{|J^7q`G?yRN+>ul`cf5^meL z7i}o%`$yt^w)~q;hYL}LlJDnbz_u?asE$=*Z!Mxyu<1Mee;)i)JzH)%& zsf&&-+4ba`^YHWjh=wISb`G=r<0IK6*H*4?x%+voN**q^cMfG*-*$G%wr#Jsgjavl zx+FE|h8*~ecOoSRo%D+3L(geiGH&aamdj18S#s^Ihes&WBzADgiI>*1eA~t~^IF}X zY59%;Pt3b`aMbb@^IFe4X-^x=E8e(gZsS#s%eQ;5<)~lIwDt~}?Q(id&#=7hyQg#Z zM(bMMbnN<^pK4UL{OFcLA{F1NpZ2i9R;LunC1nGnX2yPA8t2S}Aj8*-RThp{lKDqL-a-tgk(~ z*wS`5qqqJ1k=okDy_0R8!pj~QQdg_cZLV!WTQ7UtT@AG=Nh@rncVx8(FKVd;?AT>% z^e&5iNT*KPv?Awi@cSTNZ>{g52gDzjch_Q8y(Ny>)k({^!d-(+xz2610x3K+Xj|xA zORMJPra@b~{pGcvUpi^fb~Rl|jeT_1pl#K(KrL{zy9R9q_U6^HbkC?k+la$?v>qw4 zY0$QOtgkk>mY)V~i?`;}c<-Vbv<1c$)a z!h&{)VA2*|q*&0Ne$7eSzMqyvKMHJ1+6qoswzu2e?pEAdXN<|_JCL;94Idb@Z^Rh# z8+_q>%!Ny##06eu(o;OO^bD;~PVaco(pfR6oBn)G57O2%WQ^XrNL$i&YTtN$b>4=g z?efxz`tH^>Nt^qX>AK6qs-$g0?g+i3e>KuJDbG%Q`ITQuo8Ov!`mE;-NL%r@r}arY znv=Hozs2hNZ?-2rN4h!l8qHe~4~j^|g9bJsb`Q(MeM{9Ro?G5r1K(++Eq-Elem1rk zX-n7Li>Fwam$V&tossAB@F8u>vSs3TZ)72Ddp~61MdoK9ZTGtS@=eQrB5i|;6yPU! zWFc)!pOoaQmwJ=7$i5Z0&#r9b_h#0H-2Nm3v0%-3XuK!!Nw+pUvd$-(7hxeC`8wk& z&C}3j&G}4^V>D0aR%yty7Trzr^l+(P`LJ%QX`bHut14%w7tlP7dRvtrNjskAY5gMg zc)xz3G*7b}Z_GE>97XeVW2N@I&Ef$xPaoas#p_&eNq)Qa8^yI_#fdkR3*{-gc@lq0 zGlmz5jG;B8QPdcIC`(cEW3O55nZ17F=2ojL=IN?Gy75qtkTRI3zpZPX4^?Naxr_)1P^G}66bj;J`tGe=G)BSYJ(}hL* zb3JEc9qU7mQ=|BYyQ7GQcN)Pj7Ry{;m|g%#%JAUK_!m3`DAqAdz;iFZRt0?X}ho|m%jH+f6_MmOnQBL=P~5B{Ny_^!*5#r z<>zTJPkqKx`P5IB_CEKs*mxLP_H$f+(l)$zx1j0SyOFjz1;T?iO*4I&acf?5d(hBr zjY!+u_Sb@{cWFS{9yz<)-uAJy)r|_W`BiLA+Ae3SWAnY$fwb9bcd?zH7ed-XUyZY6 zxICCNc$8aa>(+b#@yjtgZTtK8C3YQh)OOS_gm{YAbz8g7O-b7a-#fOS$J8cmPHS%2 z`p+m&+E%B(ZaY?@3~8Hs|CX)K;o_vNxp%znM)9H)w-u+Hw8Kk^lQ#d-o?5ocWk_4y z+ZnWJwd|zrOsJ36%%c+dT|Kq1b}HINT&;a+t&(?1;<68!=2oyEap~MuwClo)v~|_W zY3-(^C2c?5EvtF;t`vEjh_l5Skw7E%JhUkXc;>K>)Jnhv$ zyYD*@nnPYTKWrOhx_Yua@c@w5G7zS$$Gd#7qgvc+JJH>_sX;Ma$oxZ8;aI{5jQB>nQ} z*~BNkZtC5)>?V#Md_e!R=|zh_FVTliPb9wIua_P$_Y<+lRxiC&e^-unN>v;f10P`1 zXIc0Fn?8f!18n-V!3Ws%X(Jydn?7yvrVo^xK5g&;HhtRQ18n-V!3Ws%iGGy@n?5!8 z0GmEF_yC(eZSVm$ecIpyZ2Gjp2l3}6HuwOWK5g&;HhtRQ18n*Xf)6la2_Im@5Kge4||E5iIivmU#rrJQ6$d z2$p#S%RGW*9>Jzh$|G3j5iIivmU#rrJc4B&!7`6vnMbh9BUt7UEb|DKc?8Qmf@L0w z9eD)HJc4B&!7`6v#1cNhGLK-HN3hHzSmqHd^9YuC1j{^vkw=_0;H<_YD!Yh2cbU#` z7XRuk>@$Mt>}6%WpM*zLBypR^?jqaCBgB6_O62B$iOn)@{(tli&a~xb9b&T$Zni~i zwym2!h|M#Vl}foyvDcJ#G^Kq_@oQ@Rs)s2$nWCR5{UWYYW}&Iox+ftS_cg$ddl?+; zxR*ifxR*ifxR*ifxR)WUcIaLPvEyC_vEyC_G5Txzkmb0SA?L3$~^YV#mDhhCT8u+d&_|@QJ>G;S+rZ!zW?^hEK!@ zjF=&g;7aWtL@DLCM@m(|I~f16eXjWBiXO}( zvOyb)etPeTJ|dR?8HfM>7>6=n7?b#qBX|GT-0iY@Mg78^um3CW;^BVHn>=pjdTHIS z0n7U}V0pg=EbrHV<^3A4yk7&B_iMoNehpaOuK~;ZHL@J{R-`@dvw-FO8nC=y1D5w| z!18_#Sl+Jz%lkE8JZo^j#!*i9YaI4;zXoi!L-%XIX8Ux%25kDJ`!!%w58bZ; z^QGR6Qdzl=^PhWC<|LMR#C(={1j{^vWgfvYkFxxK;+_=lAtI;d{Ytv;2F5);+=By$ zIPM{Wt{pZlcN{al$x#6;#1Eb|CP9x+ysQ^$7$h;g?SV+-Y&6BsLC z%n6JYFy;h&fN^&gKERk0@Bzl%T=)QE>|+jqaW@xZLY8ApNPCP4FxtVG0Hb}32{8O( zOn{*WV*(7F$UPYPF($z1mn_HKTxpLvA=|;6knQ7cuJnt$xl#}A=1QGdlcau(aoI17 zec4}>%Q(PZ#s}@lxS@R+PxzH_h8`Jz=)~McU!Y&j7Z`a&A614u%4HtGGLK-HN3hHz zSmqHd^9YuC1j{^vWgcZY;sb^~;s%y^1j{^vWgfvYk6@Wcu*@S^<`FFO2$p#S%RGW* z9>Fq?V3|j-%p+Ll5iIj4%aKR0%p+Ll5iIivmU#rrJc4B&!O)LqDst-h{vI**P$4d&hSL!Px8JyMkc(T|rrnJ)*S7-Vuy; zu%`s0ebX;7{F-_!d&hSLVFR7m%YvaFds(ofU&Po0V(*J`>>Xq~*aOP;u?LiXu?LiT zum_Ynu?NIn7VTh9C;NrH9`=H=T*d+RGCpWW#trSuc*3uYGxW&#Lnrn?XcPL?e1VZi z^igHlqg>_@Eb|DKc?8Qmf@L1TGLK-~eMi5*GLK-HM_G>efMJigfn^@SGLK-HM=Fq?V3|j-%p+Ll5iIj4%aKR0%p+Ll5iIivmU#rr zJc4B&!O)MnjhvcmHhl*JY_8c1a~o{Vb^2}w*j%&edm3PK&8F{cfXy|VzP|xB*KGPO z2iRP*8RjvY)Av1OIo3F7kF^hscCaRb(LUBnF#KW-1w#+kRxorb`$_sf z3ChtgS#Ca~zS^5>^VfFFwfSrN=CkgrU-KErq#pCx$fQnuZv<;G+Bcu2U;AY~W54zn zefMJigfn^@SGLK-HN3hHzSmqH7{mOSsD32(Yc?8Qm zf@L1TGLK-HN3hHzSmqHd^9YuCl;y}HSmqHd^9YuC1j{^vp$GE_Eb|D4er1ou%>PaK zHS@+yJ7TjQ!=3?oH^&7t+a)%~3p4!@o8yR?IxKs~w>M#L>Sf9v58pf_8*~1BEjPz6 zGy6m3X5PNGW9IE^`{w-n>erlqU-g*t@2gI8{(aSN&ah@13_cuGBp zv($F$0!k1`ItI17JC3z|fB|1D0b3EXNF3jv25VGhjJpz;euh<(L7>F$0!k1}w*n zEJrTDa?F6`m;uW%1D0b3EXNF3ju|lYEBh9v>}Qy=&tb~`hbj9artFu@cC3A-`TS+d z{)#F4F8W?8#;5rlN4eam!JhVh=5rkF5ThMszX!imZa&AM$Fg^PuN7^Y&vEFN`$_am z?lZrZoBI~@i|U&DnXm1b`<$=soBN-ye$9Q+S3Tx_>8nn2AN5tgx$mOywL*jZUMm>o zG7hkp@j*K>ZfIY|6Mki!p-09aI%Qs|My-)Pp?@7&@^B0z*IcKw!uEPmFa&+GG8Z?Ou*{<@M|{ArN8G?Nk6@Wcu*@SEdXN{e z%p+Ll5iIivmU#rrJc4B&!7`6vnMbh9BUt7UEb|DKd6ebIBUt7UEb|DKc?8Qmf@L1T zGLK;BhY#cwzY*XYj4=ftV8jwWz=$P$fH5}V1B@{XA7G4S_y8l8@Bw!GE+EF7Kul#h zVlC~F12Eb_Zop_CIRnElatVeWFq?V3|i*j`)CKkGO$l9>Fq?V3|j-%p+Ll5iIiv zmU#rrJc4B&!7`6vnMbh9BUt7UEb|DKc?8Qm%5vlpEb|DKc?8Qmf@L1TGLK-HNAQ2i zqfqiIl)MXNJP2i+2xa^TWnAG*pT?o7lh$aAf3sio>;aqoqGysUSH?3vQ&DdAi=J&@ zvtRVg1DpM#XCc_^mr&*rJyTI`_6z4la^8I{H}m+_-pudUcFeqgZQmRZU;UcncJ2Gx)U&a%DWt^c$#veLmUZ7u@cf`n} zIVQhhIqwh$v;!M6@6|oa~tKRPs{;gGbfk>#AdEA2Z+raVh#|S zV@F_aqpq2A%mHF^EYPzD<>uI-XA&6Yrlzm*ng3V{+SDofu|Ek{{3t#(X z&h@YTMY)Uv>}7n=j*J`Hm+^#O8E5E`@rO>C7wA{>1x6mxN0niZa+yc4%p+Ll5iIiv zmU#rrJc4B&!7`6vnMYZUJc415Jc7{<@(7lB1j{^vWgfvYk6@Wcu*@S^<`FFO2$p#S z%RGW*9>Fq?V3|j-%p+LlQI;c*V3|j-%p+Ll5iIivmU#rrJc6NL`TJu3`Fm|$>*fXUarnJu#zf94?6rD`b&y;>K zrN2yx15@I|l(;b^o+^uq*LJar=Zo?wdsmB0Rd%!d%k4Zg+Zr)-^lmofaV`G2-WoA# z+HUqXqy>M`VvQ)(&%=%wj!#MaKK8B?`Upu%qtmqp3tfI!`<5PAipK+|BH1 zN8SE4Q>%5EQkN-pnNpW2bydww(aaRhOwr5~&EN2=G4rV}qwXDI*>ZIu-n8>7n>f^) zxU%0Pwmc?GgXU+ulbQeLRyz2a-)nZK!0#OVXNwo?(8v-3ymr(BR<__M;=T#znOP8w{OOSIhxvC>F@IU!Ln1j{7qV%(`l^`wduOsq(dMe?Ywt`pez&iP z5q-SL=4z%#Vw&BXZ1Nv{C^p{rBAYGc9*S1m!ZghN*wx9R%GfXsYeI%5$--VNOoK1y zV@V?7St}hjYcjnSzpQPg!^Y$HSE6%3D;+k|OTH4GIe+J{iL3cSWWRZc!{*9|=b~B9 zLmV~*`aBmd{Ywa1XZk!4)5??(uxXd~ff#e9xPVRM()(g$_EBUr{n~lKj*cXoA@k0Q zEG0*h&6MotMb7*y$flK-F6t*QC!0>!VnmC1%gN?`uNbj&%099=c6*ViR%;*G?Af$P z6un`P&BX?b#N@`8$tFkP{-R#`%VhKW&3>ZUoJ(XgtA0O``f5Dc^cdqWvP_RBn_{*6 zMS^=g*=&E5SDc@fL^g}xtmVxsCXr3}fweqw=L@n~-DWNCTj({};NNl|zy6ABurH}t z`xV)sTxmyB+R>DDG(`_n^e{yaQ~Je}elewAOoRgqZOo4C-{hvM3A zVfaoY&t^{+b7r;D!DrXM5Nk+5E-m{7J-Zwyxzf54|E@S+z+%rCd|&nbHnZ+GmPi zrs!dcPNwK*O23%WU#7%?De+-S+?WziHO@?V_WftiVC{u|c+a5z-ILYk-x;x28f8@5 z68X*FI8gugf%1V!=ANnWbCsqU~^~eWr+cejmXaC-)dPK&2FV{Vhm}#kcGY5!*2i7 z)TrPQ$#R)@pzHZJGot%Pvb-+a*!b!_j1*Jnee<_kHoxD>{MUsT5wqv93^sStJU>2x zm-DsQwfGC(_l_Ht->vYDHyLDciGEI^RSJvK*j&Y}@m7D`kGPA6wf0kgdl#N9uGO@7 zP@&o4uEXZb0e2Cc->SP~sEeqy&f-_=Kk**Umf!l9Uh&@pEshC!##Q|T?`~r!iZ?fc zhs9#j7wz4|xb)xV#v{*852o9AhR?SI|SIREDy@wA0tiS}S4PpfcY z|ERNSJA#e#7w3s|B8L4|zmbtKaDkW~wU@=2f2Tf8!wB(Ek7l1=H#S(6g<@}tXjUS* ziLw6OLJ=@$53A_h%*fFzQjF?h-j!e8%=md$q=;|2hyKocrp1xp#Oj6lcX{yl-#wQ^ zib9k2u#f`H46mV);^@mgtVgz{#+3AtV$srQRv>#5qjSfF;*ZgLnN!Ke#`2*N;^^!c z7SW@Tk=$&7ICN5HyUo8rzb)l_5tUD{bhU$x;q$^p?+Akx`rOb+?KxL8?YEDujcaIx z<(MPJR4=9D+wv2-r{hi!PT9b<3je|rf3?c>Y=80-u~zw#4>x(Uf@R3YLyQ+*ffm<3 zG*84gD^KkN`%D$EPg^&_fIZp)|JQcZ_Ej6`fj#u7HmXk52AW|H&8m&s7u819rrM}| zd|J0Gwb|gxJTanSMba}a+tly&SG6fo->Q3H^Z0LKqQ*_NQGKa4YHZhBPbLkmT|!xC z{({6)qldA=H?8sq^$N3%Yx-}Prp;*Lb4yv)17EMJ|Y#0~s^W_#!CBmK3P z`m#v{tv>#_B0uZU)1Q2;-5bD8zsOAdCO$8#68@I#hY#{&@kP8zL!*ZkwNpK<@pE0P zWLs1C7b;J^e28|ixTVu$Sx+rp!;(~<-Mf=^I=(1z`|B;WxmN>;cm5u%O%BRST)bdy zZOYYi)R%oVHfv?4y(C`PY=ahX!;@^LH(#q|nUICJs&ACGszz>Nc5JD(>v{ljua670 z7qnCcvXCEP( z>EVxUXSTm2&O2_ZZRlJpFBROPY;~_brt*&E4G^pVunXw_PY{^>Luz4&AAg#YrjcF`r9VytBp~{<@=;mp&ci zdDO;Y6qDD5pYrAnt+*9PNalMR=BM(@A#eDif_aFa)cMFKUCT;*^7XyXeCC2Gd9}5sqm^(ptS!-!%w=V(FX*cg7 z-#&E%mCs)j%hRl}G^|~GgFD}|#!Tb!7kQ<^31kz|<|N;|`Z@8IHh=J<&#f^NQfwcs z=jg9|Hi5Cut82LW>=-`v4YhMLcRi8E!J%g~(Qmhv#~DRh3xCIW8q6vHxsrtzQpZC3(;>vcH;ciT8Z@=G7@ho*IF2!9>mQuwh^Mr zQyX*!)oCLVGoB^x^|`g!1?oi5L@oxLUGgC(YbS|ogM9$vumxax`7R&SeL0esJu^!C?>Yph@D=o zWUt0{B<|R1C2KW*9PyZ;D_GS9OK7~snC-ZBs{RW!%xJ!nWlndYEO_$ql`L0|P}1g9 zG>V;bXcH`)P4bDNx-I6dW6j*(>9Eg!T(FqSXUTqG)M~b7Ml0fVM_02MzyD5chNW1; zw#E(F3;SV9*09PAYg0S(2CZd#O3Ws0!DgG)v>wF8GOlIEzf>Z=TyG6KUe}vA?(Awd z+24xKzInUYX$P-r`#WoW#nP~A|27uwW@+2;=oGuL_>~U7u}@BjOp7e;KV^|<_Ge=% zkEnK9JUV7^z64$LEoQAzJ$4=vOB}o*b&M$Gu<24^yEt;hVSjIl_&M5|FPo-M5~+(= z(fKTm-~zn*>mk74v7mDd8e-< z4(uN)9ys`Uwb{b&^l2*ZzI28tSNIljrIOP{*38!WaO=o4;gMv`uYKvKisRcYJ?U>x z7TnR73}<(UR}Nk?b&VKVcaL`-oj4r@;i70C`hU$Ol+d!+B} zZC=E_;P|^jH($nzWxu}QXJR6Zz8z!5>C(?R_MGF}-V@h9C-EXjEk2tqiElV*aY*0` z?tIqbH*rZk*Zc@0)7DtwUMHFFh>kFB_{56&`(N;lCKqfQE1o_~;>!+37?a|@ZS$7_ zwZ-oVbB!fEFNo70CyP=SXBvfV`^ApxtA+E}FvIigT5&GH5V1?97?Vz!aZ7bxyst3H z=-8#H*t71o*uHjxG31(;sB;q9lz=+%>q#A6+q|1UR1$rlrh6ZQRB*u^*zcy_#zX4Y{n@be>)HF&(y{Y`bv zxNXID-}6{@px+C=&-}Yf>juZN<;AVob~ZJ{R!ioawnP{&gJYSht$ctLTiC43V#OT1 z?q(8yYQ`}7?md>Lc`|pK7-3Y5j%5Kkl6kw$=G%eqFt;P1_tga2LoPjwHxu+K~S z4TAk}OOgkhh>jFvszcR`8#`QbswJlgF!KTztxwi?QdKdMS5b7#K)+0Rh$3m-+=0GRjtY^(u3cvs?}$Va=T&^EZ2!JDVwPO*S3VKio|u?tJ@}o_=8}nqPg2zSJ9^ z%1Yd@l`H?~Zq4O>+0*h(ZLBpaG?zDT@wyP%%$%8*zj!z-4I5+V&_91@?-;X(}S^mqqnusEVT0m&(XnJ#~#eP$dB(yAe&r0PjdItFNn)@ z`GY5pvG$OeOYP&T2K9`nZCOhX&WluSs?ERa97#RbimVw=`Tf{_s;+8&_rmIL9p^+n zzWrnB`*HhuJ$C6G;`W_&{nt_FiFdwTqxai!khoyh2>np@?ZiHVXXs-FtRP-HcCub% z(-h*IE5_*?iZmlmv3soE^<_R{k9-q!Rhzn|sq2ZV`QLSpq@HCRcdQ}xDzp}@hFfb9 z&b8*RwDweG{2PiPKNY3O!S)VOXY))w-EO>W+&d#xRqFSI3w|t zdaXsnOdiCA^R^LFD?GJfJU4CIMr{9ZhPY3LHs74BspoGAK5r?umkQSts!r8LJ);YA z*zbtegj!d%QP0Yz*1kv@BHU^TwXSNTp0n+*W7)r-ol>ZERU7q;?ujFwlb5CwYF*Vv z9Rq6o)w(}=wx*urT{qA45c38tqgcN@%V@rg?Y5j%d{DeJ$}6>B$u8K=lm#C>w~~1k z9!>Ul%S5q+RC6glZe5pub55wXndWE?vI*9rm`6s9c*LibtYP*}#OXV&WC!1kBlZhj z@sG|J)w4?V4D)g>>lv5h;q-4bt2XNS=O~B0=st+4byXYn9Ch!jOB9o%H5M?nu3G*R zxAsEQ|C+$my6PFM%If*2-BEW(g>a^}quQurK+U6C_eak>)$`S8^Q;wPpl;-9wsrn& z%2(8kb!^vz9>j-Jt!4h9m5EnXU&B_;^CnJlZ1q1nr&Z5><6KwM_^dW-9aHsmSl^Pg z?b)}Qz2FCEtiJoQnw2j(W-m0y%v-}U46jFZzw}xA-Sgzb3*PCl?{-8m)t7qate)}u zI_wXmJk8X)s*QR+>|g#I>GV3ijj4528})42t&g?Fh7A0jsdZHw^;~*iZ_9qi>|IQ) ztJWqg+NkH`YaI5C_8$^zUDZZCW6!wC((}_xU8r?c8})oXbhTxl@z>Kr zt*e&TC~C!_`{NTrJ@Z%FQOniXsxegC`R_V=SKkp#|JB;F?KR&Q7_Zk+9vjt}Es9k< zL!1~jLp0lPi+F#T>7q;IL*in8P7`H9t^LxvpQefwm0wbMx;vBq$KOF{CoP@v-9v?{ zzr#N3_pec9qKJEB{RY?5P7vX{?~}IiTgQpVIW80D9x_%WRQ;WJTDLKxRQEl^;kUkh z-=V&12y{G`59e(!R1K<)`kvz1Fl*dyyfRd%byXYn9Y@fHvo@?VIn#_0YF*VveLqs@ z;AyfS^klJ6>#8>DyOn|tJy$2L5o%r4Mtv{y+%b;9d0E9$!# z_1(eu-Vvzp5&q8m9k(u3=^aqriH}6DX55DNL2S}vk+IT#Et|>HU&M*)KkwIE%=Z^Y zpEz+P^M2ZY&Z_=ERIFH;BQLX`B#1_Z42t>u_=n6Z_M zs;6bW+9LJLxyFtc7sZoVlSS~fnTAu!gCf*szU#^wW(*v=PMl3GMAFnL#*EanM7C^a z#HxmqjO!6y#O-c3MJ@BaPv*n|qE3@|k!SRHV@kkz-st#a(dhj+V|e;tzP#!aasJde z%rso<91zRPM~Lf5(~Ws6cZr}ktHq?IVaB$a>%{OH+eK!# zX-4Xii$(iVhM2!}iZRo3hUn{kRJabBY*ddME!v$qD<+yT92wA7T-C0Ki@!}YqVrW0 zvBz(Trd!STS)cNVIOqG~dd3OHw9`)F?74U`aQS#6bAvzluriOtl4j$L-z&}Hn|3`G zuL_Pg7T2lD@5UsGMrp?zb9?U9+ulnjvW;F~bbfeS*suGEaYg4Fm+s#XRY#T;_0r8V zyt`Zxy9&FB(eD=+uZ!LjdDm7F-Gal7QTH#4pbww;n(h%skLLHp172P1@DDdWmbxTT zRDH`Q^o}qB8^wyLrE7}Dx8@o>%3KmV-o4_}S49{;kM4<|#?}&_9?vy+>x)8t->1e| z9S`ap`B%ONRNwa%zxGI!%R1gjTryGX5Ed&^J|Axsx$4e3{`r^it~b%R(x(bL+2yFn zS9Y?o*e#R|_uVPpg-nswzTTM4&NA6&*B}a?X^Jf_!-yUJ>&s7t5?#wmT zmAK5hto~UPNj=|4ioVI%xv3tZko3?DtmX#Ce{HX*sH=vO%0DEasjJ2bPT zNT@K+aJzbyO?s17v>mX(@E?7Ly*!sz1h!sa)IEEL`S3uIux6goBjGyxJMUgIWwX|? zq)HE1gxy-Zd}AN7^<}L!t;WLymLp)l=4!5cem&z@#VY$Xtc@w3#Ie9m);f7=>|=Jg zjkSI{jeW%Y-d5o+P5YjyAF+d9bQ^ek>c>o7!@sv?s_Sa?ES9!$nf8bRtKZRj8)ou^ zbr#=9w}(Y}TQ(0&{yTk9pB?HuFZF$v`kw1w`F>V?_o}{ERo|KZ=(|q!J*N7OQhooZ zzFSn^8>(mT>bbgl-u^%RuI<0;U6}fwOMQo>zMoRxJ^d@+`}~u4H0t{o_1((<3FnsT znWTDF`LBHUp}yDnKjHm_`i|gVc_y!(x2tD{>Up4gPWZ1pr&Z5j)$>*L>{LA$RnM~2 zb1L=x>hGLG{*&`Y^$b%z>-*k0o_emLo|&j;DSzio?4O)psb^E_xs!UPq@EXj@4P}i ze^Ae7)Uy}$Ttz)IQO`rv-;C<-LG^dyKRIXkpZM*s{;pSlv#Y$Fy?%`M`qF8SCmGtUzL*0CcyyJjD8o3+zf zk5uc4JKtQx{CsDLU(CA2&I%TAq#Lnsnlmi(fkMQ!E8S#H2d;70+|D1*9(5{8oMUVv z<1KgDQ2uL$C#-J$!CGmPub6ww(JidF)y|W^)ZgQ|mmJap%ssPf(|F!tjx3qd}Ze_ zBem_ZXu7z%0QXvSS(J;kc>IFP%zdn7bGYjsFFs@ZQwVld+ zrgQCA2lsV9ue~pHl*-GQ>|EGlzvnKj((jgi>kjw%@iS55zSrM_xh#UDu>lq1s$<^rf?Dul7-`tJeepH*B^Q`#K=oj_fv8UREI^sXX)bqV@tJ;Je z;uN1*rv3NEylRs*##8<`9Qymr`S9I&q1w!G#4~lz zZ|&9jrP`=tqeU$zJLb`d7Z0>?<{e(#Q|@kZSx5Of&p6)8EKhHiKQLLn%Y3PetG(!^ zQO3xU&MY9_)xO%~@-82=x8>dJlT2QpDOp?5&CQ>I=pEby$)Xa?j!t zr=Dqhd@VhPb|q>#Dq5VX!$VEgdCY$Z)ooHaC)?UYC;s)#B=%3*RQvn6g5|g8;D>yU zLr^HU($BwVP>(fSP$a%ZBmP6 zi#ro9d*UR5&vqa_f8a6ic)LCE3C~OXu7h*Fyr|uB*!XUKtd&_})%_#ZiFGJ$wHewd zHS5vK@)dtOGyC3J@x3+hdu!MC#?1HDito+w@6FBc&8hFrg^l(NR(z5#YUv)VCvKDH zu$FLh9dYVoyS1{#))E))uvSa^a24?%Z6dW?*;f*$@SCYszPgmSg~vqgWcfwJrI(G; zqPs63_UJN5yD?xcajq4=Y0jZDzm_MipZ3*$K!(Z0XeaW_cw)4_(P=C({C?>_nizVP zd5s{3&PFMR5kr6WWN^hqO%US^E4Z zCUt(Um4!+DHCuQw*{|`by_xJU%4Hm2FXMxDWZclcj3@lcI75$&KXl5xK!1oMUp^@= z@iX_Wd`-E2pRaf1>t@N9{9REiUpH$zi_-~KzUG|v6t}Zk`RW^zR=7Fxb@csDV!9(= z0Zp=qA&z|Y@8l(xIP$eAi?=v5+R7KoH#_nL`_hhlp`DhFe4+giN50^9j3ZyrYD$f>tQ~} z_bwLCa}!0{x!E(B>wmM~p7P{eZuW^L4_*A4zue_&?`HDh#-DlbYOeN&=JUn-v$IgY zoAJH1U3~_<>FL7ad}bN9Yvj>gLo6P)Be$)4KSt$Ew&k|9cCcHmJbEd|w=6=MC4BQd zQv2)YusPfX^I3D`(IDd93v;oq zpL-LJ`jmyWkLX5xx_BDa=0QhdW0*55Dk%H zj>M&0KYY`sIv&()d$msny>FY$JM$m9I-lXKBHH- zTYbOXJdq#1Z^dN6cxS;ESh3oyr4f5RSuyPFnN_II_aEIGXpWe~W&OYhHLzke-Y>mS zbGO`~?Mv+{wvP|nvbf%pjUz6VY)>7Wad{k@b)VZnlQJwE<9PaOSqw(3MeifU#KB#Mg8Xt8%x#Xz(G_J}waVuMP2PnS3KAQWP=2Bh?d&1u+IunaWqk*``^=Rc^P6C7 zI}^*ARdr=!4vjU!Gv8;gB3)QHvuFYv`!?|5n-*=CT70v5f{VLn> zin!3g>TmY)$3?kjRvap~{q{ZSo6?`P9Xlh87eDP`i?chiCp{yKf!X#j^}Xs-Z>u~Y z*B%jB!m?kPb&pW(RU0?Q_*`-&TBu`H9mDFFSLebWM;;R{L^I=0 zA9&L76!iVoh=IvGJ}d=k7_%pdI}J`@Z8r7ukB<2T=cRpP)ljPRtsG+p4y zUVpSWPpm8RYLdd9+Klrb=f7yqqf^*ZntY<+J58;t#P*x-ys6)RQ}vJiGljiWndaP# zp?1~e7S7FxUzxJ=sy z{EvYauc=&{pBwo}OHnw5eZimx{Jl9}VRPV*>U_!b4^&>rr#fH%lU3fszY4cMc&F{{ z?Mbn!wI(G)-5eY3eEdZhsylH}MeZ}~4cX+KQJvo^YT4Y}TAII4?@Tt=YggcEQ`*s#b~L4(Z|1`H#*#ALxMIVV@y3;L^26U=R{NriC9aGyp^QDD^zm=S zO11wxeNpE4-&)5o#vEgSgB@dr*fGX9#+4)QRPGp)RPGojRPGqVRPGpKLK){&?iim` zjyZ151uA!pZGrLZ7;i$E3smkHpTv&wER=7>fAcMCC8sQGwv!#-aLu{w%QtI+TCU{i zyX%9JYprG)7ix2J(YxB0pPh+AF22*kXIuPdzhv#_TNbBWkf=pFS@xA)#eGv(ZBt>c zw6D&QZ_5A9cvIpal>YL$?<{ST$0YDm2Q5A^`x#H$#o`L~*ZhRL#RYSJ;A&m9P4&Ce zN-l)@+f)55Da+@#N%-cusXoh;XUaFlkc?88XTatsPKn%11hCU@7FYeKN$-+w-<9}>eZ3}|GO8NGlNowk=<%GTIu6B5CO z{~670UubNkE4`2<6pm&smo+iEUs}k9?%l)M4{2(&s2R!nhU{T~v}k6moE^!W9N+dF ze864ZQ+@O8R;7>Md|y=k?x>naHSbDJe|V3fYU|`Ua|rp(g&lL8Ih>jKNxSJdbLhG0 zl{U-qozFEsFEsV+;(KFH{avR1zWXQN_Eh>SesoV5G-MO&x_yLEt!Fr^S#C3%`?ROA zG4EWKa?fTepVK;=b!vOgHX}0-Wuqa>iW;qrAoN|6M-L!LmHY>zwVSX){kL zM?11S`8zD_rLQ$r&)K$REN3K`_Dc$%v(?R9&Uog~02}y~<+Dwe_EQ~x|G(N%^{D+t zxzDOiVx4m`lU&OunPPHo^CnT=EMIGCi`uYBbTWCVsjchUO=6PCXa_cTbNuh}0%l!l z@8M`C-fTam$^W%|ly_D9LW67*ekG%Qu(X$qHl@w~n@;IhwlCXJ=YskT-hVPL{>ho1 zI(Ov!!g-@)tn>TwN3hM^CK*3Zogl#bA6vZB!F%5>5MbDV@4C(*&S~0%VGma8s%>6& z*zY#$f?*F<>#A+4zEllrUA0ZM?)UtvZH{uY^rxOMfq|h1Jl4Sp=D9u?{ROuyVD;V8 zv;o5&tkzZAZ0oSUZ`K9F9<0_?+hlc@lCQg_4H))dwXWJ`1&95<)3X^E_F%QH+NRxM ze{Rck2CmwDl5x=F@+P0@Imw7fGn*Lw1$T7lKWMfIM*CpZm#U$Q!+vS<0tSXXSgotJ zImHp%m8K0C_F%QH+U7)u{b5rB81`VbuG;3h+tVnX$4whB?7?bXwawKI`^RR?!LSFb zb=5Z2v7wF`wXWLcm*tB|PvvnlDgKBva)J2En5*$rW2MGH?W3w+)u#GYb*kf29ee7y zQpb$?y=Zk$rJgsc{d!~e5#x$E`Y6YkI`-85s$=ha?Wi{DxK(}qE5B#1?iJPVei!?5 z2TKyo44+C1*y?9H+3^9*j6Z@RScA{z-*S52)F}Hhg1!2EH>=dPsnMh4LN>719(Hb9 z6Qf9ug{)AeXqNYGW24;G2sWU?UN+zSzPEU>fE5ppVaGc*GH$pmV7o?}{|@17uyG?{ z9y|0qXWd%|8%4K-vzf01Ynmn4xEnf`P0q28T}W(byl6S+o9~m)KDLuhC}-|zi$$=< z5h5rgWj6b`VwJUON3z9$hqbMuUCkP(gWJ9=uQ~S%Cmx*s7cDIE46*CG0L?kXg~O(J z?o3+EhS`Xd{a@P>t`xM`bH8ookRamwgT~qpo~lS(poN=l&7vyA=HFL{>T%dAchBjr zZ)|GW2NxfwZ<%Ga^DNZ?on7`O`_s+e=v#I;6K_0}i9cU)iu7Cx&&S(6n@#+7)-Swc z+PuVVYEs$>A{t&sywKb9&H% zFLo-gSF)z9-Odukk6%UEK9=((evtK+?L&^V#Pi})Xzr)tNkjd!xwK{5w-6uqE2h=< zYHw-lz_jBn-cY|f`MB|qAulO+uMatKw-XI?Xny`BNxwYWipfc@n|k*xyQw^W@B#hL zrWY;#yhI;5J(2i+zg~L4+)u53uRe1|MM4 zrwu;9rcYbE=>u%~w8011^l5_+u<6qVA7Ilb`c)Qe`qbb9Z2HvT18n-V!3Ws%X@d{2 z>C*-u#GjYg-~(*>w8011^l5_+u<0`hKEQ}2e1H*4_y8l8@Bv0F;RB3Vn*Ab1Ea3y? zh$Vc05li?0BbLw3n}7f3VYIg5cPE~rQBC4wd0ct#m5qt7PjTg%b9>_GI2XRGWEbKZ z>67)mEOuo_f~8I{be1@7^~Ko!v%a-pZ}OY&Qx<*Rh9Si7 zz1;QfoyQQDpL{1~_)Uwy{5&n@sn1v{pZe+2-sgT68xKRv2HzP(<+WE;2`b}cwOOz0 zxS+B#I#GG{pB4qBZP%Ij;>TQ;skj@pj;g;4nv zuj{rAlUotjs&U)aWnV*Lw)D1b&_gSaN1NQV?fTQo@0VdQw)&Zxlg;ze;p7Y2;Oj^I zLIdhT19XC=PB3&n&sCaymEM;|+n{O0E8@L0*Iea^A58Mqnt7PtCNszU>ZygbQ_(i! zYVAvFmAp$5mwm`Iw}J(UOXsel`K9+EuC%SZmMKjp;@meht<$7b#P`nqqP>5bjW{H2 zpvD996Z20w$QQK1*N^&z2GoTH=mblhVCekP`-+afv@Tau8#v(_agirYw3hFz^4-65 z(3&^8MCIcK^wL^J9wh#2RX?p=*kB^MI6IX*<|RB{Y)qXoUScRRWg&+64x z8+W)q@xzvFwQG-N5WBx_u7$VSMZ6%sA^Czf`1(=5(15zo0G(i|6AYbSPLGd4e=8s9 zq=hu8Mx60@U#(d{>|T`Hjt$dX#%KZ?5IAjyv0BrvtB9ZNAET|?^^SN_ znK4?1oZdFrX!ZeG|7&@PAHMIQ9oSfi*rj@V?bth=>{k})q$Q7PUKaLen|IcV9$rK? z6ZbdOss?Q)UhmRg`fcWF`?pn;Mx5P2KI%yeKxNB&$ zT<5mh!^|GU$!qIr8-uL!CvjD^{ux}Uyh=HyMK!!nbuT7W)7Bk5Kzz@yKKVkd;Oj^I zLIdhT19XC=PB3(iiqAzF4)pNXF02Y94r&yr#u-D8HWP{2sydExzSw%((OeRkHcbxJva_*Yv_Tgoz4J8L$$+ZrtB zNad-A-4B|=+7UnXt!VpPs3mc5jY;GS+TiO){XzrkLIZSyrA{z(Zm8Iqd_9j(+?(U~ zzQh}Us}nOk!0J~9wlHSj2y@PuV>S4~`IrlrLWv8!%A}`wYV~nwg>rhwgI3=w26fZ3 zJ?Tw0UAv6br*yE|@0D$w{$i4&U$4fS-)Ob^d!RkjnPJ7@`h{!c3)Ouo_ zf~8I{bo!R6Puk{|_u;2Qt#KQfHV1Ea{}(EsUL+g$8dsP&&OIwnO0>q|i$)%NeWEo! zH?qh2nGkCXS9U+9_lapj_Tlxf>nnIG;{79@>ich6XI`VZRX!*p6%QI{*}I2j z;;?}>*!&%PRX-SY(HFE2mhFSl{-U@{q$g`|QJ!X|7jfrt8utpwM*MP5HSV*^;+t6; za{H4ER4!OE9vbgSeA2BAkF4{F)|{}Aj{L&>yToOaT5_-H=ZG%{H{sJh93t+vydEFi zD~`BE(`vj%dN*q4@-&TnK^uJis9$J6U1)$#u+#~L&OyJ7CcoDjw&LgZ4B&954n|xgTvO==2!9+ATE2OD!-JkIB_~&ju>^p zum?+fFzg#;PNKf#{Hqdg7wSrNUuLPvPpwZ&Trz#VANJcdxCqtN?M3;Cf!03r+8uvB zyGcGOFMrpE|LJM%C+FP^*mQuyyR#gSKIWz>PzJ{OJ(F4k6Zk7Xeu5XnxD$sZgb|F-o zzQ|78AdB-iI@OqeukWytxv(`V%=hKYYM=6FATOA)0N-;stKG*t4=>o-k1v?)WuM+S zGw&Jc%Zny@+0&j#%@HR@8TlE^YZ#Dz3h{oyYuqZ{P>!TUiMCV zQt%3W1Gv`!FZ;umt~}zgKYz`$+E+Yu`dV-d|P!t-rOr%Ym_Q8U(nx|IQ{%|eC$Mj z8XI3axbZyBC8>Nsk578|Tt9wgepY+-_nCS4_yW}C^rSreQ@tYmukK#s2VkZ@kK458d=d-@2k8FEludeO(48KJP#go?Ih~J*4(${d4J(RCl}?ljC|3 zo}#w9{bJqEI5rjcV}K=hV|R6hPM-Mx51b9JjGd&;M9D^Z9l%b z!F6`c&yyc}6u`q~o?x}&UHI#MzC7^P#VnyvI=(N|;>SiBs*7^e&3@XCbdIUz$@`xy zO7@2zf6~EdQ}WpS7!Jg9O}e(Plt`!m~T{bsQM{`As& z)@_L^-?k_}>4}SU<~ODVaHB*l3#;Ht{l$2O9%w_qi1YZ9&i;?xc++|T{O#)TtnWxy zp1Dsx;515IQrGT_!oWeN`JofXm@t1yc>^-&qrL}+l7yMn~&emlF8o9B^MVX zeR(VY^!Cc}X?U&`d5L##b?52Q1`_u>?8JNBC`J7Zp7}}FCKjjiWs^SX?@LtV%X9u@ zf3Vw`7tQ3yYgh5K2XsuyJNx_b(Jh_r4SiGc8?6I)6Srq0>GM}?fZ*I_?i z)i0h6Yv;-LPbx|r@BCTE7(m~V$H3ow`JwFVSdMdP`E0Me+!nZs{kF-2&$^JG?+9AX zyaqe-VMB`XWpV9U5%Ebc`LqQ0$e7u_*&M?YYZoNmSHg+cG1q}Z*)rN2xTfPrNBL6U zA8t+0SB&%{ev&x_pOHH++0}vmOk_*?H73Ue#JYmabeA2~$06sOxLl)B1m2Zj7 zOY?DTRd?QXOdxT4bAE+)%1<$j-0#fCF7o65i?O$ks_Oav|3zBq6a)k*MI|N9>`N)l zy};!HQli-1-HoEyt=O#?h{By?2X+Srp{Sr>C%&xT%)Y<(TD(4My}rx;o@>^exqITw ze%yWboTFvBN8(kgEzZ_(5{HCtkX*f^C9Y@pEZ0xiJ!{6kA%}XCrfA;JO>`~mEg8JJ ziI_LSS+rbi7MM3lL!1-mBz{?D8kiQUB|ezsqSEo|;tLjU;pNF8O+?drH}TFYlR!yk z6VcMo1;?R$mAcqts*`wVopE4?S8UH8=q4`OXcYKrWfL*Fy_-0At6|`wBTYoNZjPeW zWzE1(19aFo=^VwHc#S}p3>|S`BHQKf>m*0De^W;`k8KS1N}NX+ zh*MJAiqi0WiHED27&&KmD zTVwV&%mUZMHy72|K5QsA3$*XAC%V4y6<1dp1&%!bi_YD}{Kb6DzykpqqNa~C&e8Q- z8seW_uHv_A8iDnZO~w5M&Zq}?Yls~koJF;TuO$!bG{pL=PGZ%PddZD`nxc)5oA}=F zwIsH%iFl>b3(H+6{i0u|I*LNxUdbv09kJ7GClM~JmkjT&DQ1m#5hvGmmt0F!7eDGc zihuMp1Gmi9747@DiMrQbOS0B95gW&c)32u@ODw;z;y+`>jeT@u_E^&?3a=e`u!?R@ zWA6uG%o8_Oq>bC`DM`Tc>Ya0_j;;*#ruM_B{6HM)i)SL~AH6Q918dsRqs7^%=lePS zD~|m)aqq@)>9sd{BHIks-%GzO$w0Qb(Xf`5E|nwOi1xX3ZeJO)&9JC3)aJGn*`{Cn z47&Pb60(i0t|z^s$UwH)X6ZuT?(KtYbLXfXE%`PA*=FJmLyTi{w)wxY<-du63&*9% zHofk5rSz;6*{0!be;PSKhHTSDkW-P!kZtZ;B+;|yq{uc7W&@~ls0`UAdAFR7Tp~k$ z*x!2`H8GN*FFrmzg%-9?#Qo4__o zuzc#pcC?>%BC?IG!+e^e$iy}ux~-?Z|0E*Y$g+KDP(dQH&G@ckAcGPW!4EG|prQ>K%ra9YOUOtZY z%Ik`{(%FgL?-h@BW;)EG*{2eaZM4Dz=?pj3GnBMF9`w3-D%Mw+xKV2Z1?oUwUm9~T z0qrmPltW|I$dPRl{s{C_x*XXi=>?&epC%yN+&w0tVVMeKo6Llc)F8AAUb}ikJ36L| z0`Fyytd3|KXB%!?Z%rBc);meVsKrq!{_fqD-DuU}IMh=XMpEBjQncUu$WUsjmw;M7 zErgyAR?XKF=TUTY?|5XJmPA=~V^ z5JxwXIP~=wf~L~)LK*4 z3+G50T@#06n4dj^$}cI9ZQ@$_(54wOWSjg&iPY$19NKd%?n*#=xPRyN zaNBslxR%$c`c-d`Mj!Q;A*WsRP66^t+q7xSTdGF zA9rdN+8h0Qr`@e+>SHOgO^R|5&A%l@wz;u?Ak`Z#L!Pl*$L?|8c+@wSh0%FzjyT(R z1^1$c>Pe{GXL;j1^1kzV>|qgyY?JY3GTpsjifrTJnoZ|Fi$k{gJRpKzxtWA)<2c!q zPWzLBJX2WPj+SpuK>hJ-Ak}bV?JzzG-Z6z9XV-GBGf165w--rKmqqlYy$(pRPKT=Q zbj1f%`Oc}S)V@;!mY?nsO!rAru)pb<9q3-u1k_)ALumBm6s)tpygeOtU5ae;dP4@) z+LVCfw)09LwPkb1*+$JYjZUm%bIRCeX?q#H77&l?idIa15umiK6waFPv>=e(g;=7qH)D zJoEZqHf_P~S*|Ctdv@;ymDcE+Npt>*N49CdH-x^@W_vPYo1LFisO*Ro8K!$gH@a_{ z4E3q633U0q1k?xJg6Pq-1Y{ele}ZUER~e4O!x4$p^n?`IW`9vvdi7^Kvd!d8A@tgf zcx0PCV?*h6QHpGHy09Njp;BZUk7502ryXqHV{9|+P#|6QS%GYGaE~|rkP?S%bJ}(q zohXS%wmCc`j9Rg^#M#DdeNXBq#3Rq_o)$)}ce1`PwyB&HPpwuZV;z@bciJaRhHNup zz$mJ=N``Esy=xqmUSQ{b7~7nqu5_a<^B0V5?rlq^3*Jj{jutLUrJ`#b^32uPSX$aj zhI+y5WICG7FJ~Kly);^QQ;G~TCOd=fyc>^f^Q2oSwP~J$_LC+K1d;F$mda+LxLC z`5gIgo_Eh*El0L_HLNMge3*!A6I$_Bc=0m<*=B*8AsL}BN49z8q({sv6OnD``nSTa z-wDVzHH8M`x_&b9!&vWT=u{}U?@mEoJpHop zht=ot$z_LiNgkUE9@}~JErfJ+%S5*MrFK9VuG=5m91*fq(DzXw+rSDhvQ15aY~$0` zlf<`EAlt~hdXc*AY^}1m&8uIX$t3#>v~9tfM6%d31=;4HaVPS6bq{QF?4sU8X`YOG zQRKz@f|o@y@_^5|`$CmP2I|PEiG(JrayI%kJtegI#Q228ZPu2!kO6Cw(EbNWgiJ0> z!TL`;!-$$h#Wwx#d67x6>G)d}p+|)ly%LdaE?cxCb2}v>+eoU~k}K+o$TrynU5V2m z72E7{_9354Q}Eh1%R`B4e-+yZ#y*7G#`jNd+jCKY3^1VSbHVPg9Bp8y3dxC9Dm~_x z74g`nKs$#ve<9>;P>p%dv#rUpq$F(L_d&sdAcZSv08kwHII^VrPRm6-HMLbl22 zR3Th7OGLjvt?VBmpdkU-ruMoq$xlx~UtfOks&GM(j5_qlU4dWA8Gv8A(j^h?9KY_n zFy@B>%R8O*BV2Q~`Jd)&!!>W8vkh-Qyh#%B$vB6ng5#c^=$n++)(eO4C8M6W=BD7b zPmVe-SB)Gtl4JcS+MG;uQt95~tchVx7u*leT|OtAIH+Qq^KUv57j-$Z&FvHVq^h+X z?HLqrO|*X`Alp1XZ;1AA|IY2fMxS1LVYM)2n2J^OO793~rpu9A+!v{n z-V;^&=v{jfBT=zjx7Y|G+nbF(eSm#WQvNFm>(3b=AV%c13S=9v2lc{0 zcK`CYjo}#sayv?ndg44=;_R7-zIe-*2BDbknVfS5KlH^l!28bU(c6+S1B=@X-+EnG z@Kla$vv2EfVMhl!vQ0*EOY$sJ#WwP$0%>@bj64&2GK4rkm!ocC>O$Uuiaq8mxh7nm z(FOb7_r*D3(40in_vU;OUObYcU(Rd$N9Y?U$MS+5+NAQRs$BZhkv#2^jD4@}5JYM> z%Tb?y*P7JNPR47Cng^2=L*&Rd>B}@o=rh$i`L5$a7PGnIZ1c)goBaCD=9ICG;c`>* zGFp!7q%Pl<__H;@<2Da1%!qn*60*&Uhd>sw`Q>q&=ba5ncXsxa-;dG5HOT{Ze{mgq zp*0D&lH(X=Mq81W-4c;)zEpe>ntf!y%i}iPehHTBp5;18qDI6?Dn0v_I(f8Gj%;%| zqcz#uR*r1*$VZnbS>Jhl=8>ry`N3@Cdi`)iGT?!#d~2RFIe%J?Y!f-diOgxL8Y}M# zeez<39NETlNmKG*l^oe7sDEp+YL*2Y~N#S zqt?!a^tq~Hn*$qsiN`{=N3pm~Xz&%mKUR)x)9t7&Y11kZxrNyMBkW=K3+I`1U1Opj z!}`MX)=jpg`dJdzIrt1nX}2U~o1du_!bYoPWSjUM_l0@<95Z8^O7m!v*plsCjBUQm zYepspspja$Qf*?WCRfF6_M4NI)+*h6Pczbv%`a!0+t%8o#{fApjLQuTvU!di*~VhL z19{vr8O!ab2a?E{iO4qjM?VS2`pS`Q`hC$L0-I|dx6#ZpBwDcwWScC9S3(e*BObRI zp=kZDyszU*RqW-6dgXuSfHn5fjoIUat%_SVep^O*99OZ5Z?TdzZqu}z>KW6_-jB($ zCVt2*oAsZNG5tMIM`gYzeeS7rrGYw(%kahW_QUj`aemt0a20hHf^0L~_%V@;QpFZFHdGSL zYSlBTy!xM{=Ak>XjhXFFvgL{DnbgrMKS@SgPh=Z+V-1*h&KqspAn1bkdk}KdEDkv&q^}*gg5FV9=foeo%`nucIw_^GWCHwvW@$P zuViny2bSw-tHCZ0PptpWK?4e&sh&x>8vP=#U4!tqPWU_~O|G+R*)yrK*zZK^hC8wi zY-u2Q_uP?f`XziLqu;2WN!8x`MNU?G;I%bT>Tu(=>X}sQ^S{tGzJGGt^zQqjZylWQ zgghFovUz9z3v#802ih}#)O%7_sLFNRGyVw)`>1-Ryu9Kw*<9#{?ZEgK4Y7z zTOY~A`|eo2$>ke4a^4Tw=7+S3q`Uc`-}mr%PWG94BHQd*^_oNv5YX4}v#TI?i~~@w zwPoMrW!G{B;MeYp@j*K$etAa1O;pdMB3}PN&DrLEnzIepynW6#y!{`7AF|5vswy(2 zX%sTdrKT0+*YN<POpNKC=;zduazu@^RvN7EQb>6}EWbreCKC4rBIXU&q z9pg659{wf+b3Bo4#+|PtiCtCC$a2=dCqk?zvdxFR^=J?G@7x}48}Ap_I>Wut&dDEY z$5Sr*YzH#a~s~08SXLYyGs46ertp=$^{^;MWb{j$$ z17BpD7ZFcM!u^iOHfxtWCCB=CBG2dq)RW)sJW!W(WO?ZsKIn_H%bt-X+Nx(#XM6m? zdE|ZP^O$BTAln>Hs~{~edn4P-dG?&lm3koCytny4u6lZ4+{S8i6WGe0Ir3*xt2NYN z*JF3o8Ed|h`<+-jEN-JMRFL>ef_<-wEGJnXd{DosswTp5)pMmoKcACG_WXj!c7*mX z$)1<)cy08wFJ$^65A5%F-==W$y*uhppQi7u?Movoo#Q(knSGHHUlQB!M!w3 zWSiT=>&f-QUbu&>4X-7R?Ed2S=9;R{#Am2#3^i=ulad2I$TowcpOI~^ypd{PP)-*7Cm|nKAhMfQ6j%@R1=Vx-y-V51g@vWDHjP^#J310Yu>`wATEtykK zrdGP6u1Wk#n!IpFw#g{{Le9+e#BsQPyN-Y-^_8pOJUe2l}?b*0-wlUiAm1t|Ko=K&J{2`wE1Y{e(&*db)tp~DA z``C{pFwh6NMW+9pv}?nB3gelJfv?F~Hnv<#Lp~DcY!9q6V450?JL89J6O>Rz2A}mu zwz<`=&XJbWOY-EX2eQrgo^Q#T*Pf^!4Shvc z5A#B{+5NGWq+VA&dzz|IOPc(4N45#}`Ap2Fdm!7K|Dy&*uYHhhB41V$-HTqxHn&Y{ zNmYs`vdyH)^(3mjFS3og{ZnH2)g9U9;MUKiagO(qng*`~*LFHjnOraa%qRpANV zH)<%)xACm-f_3sT%JXf0y_Uedx%Vm0x2ZkT89M4dqCDT`mR&q_S@4MRe4E&B8UL9d z{x^B-E45xyo^P{txfj@7c|&==&Dy=5P&Toe@_d`RP#+k1=o#htHdn8D!{CZHl;_(V z-R%jx_f%7!Z{zFX15Mj~p*-KFqudiNvhVKkXJp$)dqZBRI`E!VquRooax7_F#Vj3U@xBJl|%{ zE&}&oKcGC{=2Zj%+rkHw=i3ZiL%@2-eahoD4bl+!_WM5CmTwXPA9Lk)!fB1il*es0yz&R@ z$TBRS+%^z?4OG=H%L;*e>mJ~>bxHzl9M#Z%{c&C}>gPks*=BP?0K|2EM0vi=(!Bw& z^}!>`^KI%)S$Veyl;_*LHwVyId>`$M9v=)Zdpw{#-$rT#XdAbg+qU5Md&(JL_CQZ~ zxBeym?$J?R@N`=x>XdfAu%h5S+G#w@6AbmrQAeuzL(r#>*#4p}p3uKT1?6mG=;#O4 z^^dSTSuFrQ+kT=v-)2gRC-lj!qnty2S$RR&gr}6}+pIX?1HShfDEIZd2Y5o;hA*hq z*xKgT@^XG{eR&<)c|p$$JT8=Bd1OloYToAmG-m*=dHcLyy#0pi50vNI6n6K7@#l5X zH!YX>!O;HSDECtUBKJE>g)?&D}Ue^Uf<*iTa6!3 zo^Rv70-$U2XO!pLl<4|Eer_f9u^afpmf&j2^KE9N`=CACzjJ%IZMYjH%R$d6&$mg+^M<3lt56SI(Gi-hY>vL$ zb%{S{$9|{{QrdnRG zu)Ykn?E}DhKPcyx@{OL5J>@m(tG7I1(9l;{ zXMC&|Xy?DcaxG79NG^Gd<%c5u;b+->?C;HtAkc48j@qlaKeRu4AM3Q<8U(%6YbnpS zskrF{7d#*1xQ#gF4-+e2P|h~#uNSsxH>*VJPUyyBoLV4U~ifKnU zY*|KmzRm1Sf$)8JHRW-e+HfCOw!Q}Ukb`wz(4=`eYL}+|;8azKW7tQBjqT%l%AZNa z)Uvhu>=oq<)6>rjO4&Wj^$B**re)Ql{!G0fv`snX`8K4^4}QOWPWdyb(w^S1|KLl? zV>JcCyuhz}HR@I}AFyKi@x1)ZR`$Cq9#fugLwIHVZ(fW^03%JXgXS9`&7 zr*g{K#{Z2Ud>v9wdA`l9Lw@kc;|=BcHdBvzLX6=X%JXf4PI-b?8@BH;w&{J*AL>7s zQJ!zp^#Z{2tnZY^ZA?da!p}(+l;_*%)%(IhT1WXaDK8T*2tW6fa-OMN=mXPdR-j%` z;|q%|%CJt})<8IF@rm+$n>}oe{gQp5Jl`gh?Za2n?^7PP8Pc{Blw>l0!PutjQg3*) z{RPg^v<}`d+58FR`8HOW9ie^vbJTZNdPC30FDQ@O^kMhrg4!C&^KDL+u{F@Aobr5| z;1WNGd&T?(D}Uw`1Tn*3Q~pe9G~4Gd->aegnN$bnvu^dRraW$=72^XRM!sXYESiC_ zvpr$1TRG)%o9vf<|2ofgIxHSpLN?;R&vrHT(T&-|W=#=ZyY*2bMD1IMI;=@LG;Xuy z`Honw);a~$?X6MQ`XxfwsZW&r8P?tNi7?fC3+kR-)8Tt{4r-l~z5ZqA-<(rxe2(nl zKcgtmB|b52AY2-jN_j5v%&|S-r7ckYOsZj97jV&Ug=}L~oCxcaHIQwr2g{+-c%PE9 z&ARMVu>7)A$=RmM*evM0YP6EGjqk$#@cEdtlCzCo@6mYfjI#tkch>j}+TWa6Tcx3m zY~wOO4wH3Fk!^BM%b`iqXC-HwOSj}OR`QRMv(1_9a!_|SMYhR3D~C_;MakJF;IbTQ z%^i>*Uc60&6vIDCZjZ%$Ic%N~Ncn!aIX)F)!U%H9=|Np!k8WGkrvE6Q!0Hd49jM8b zgHPFJC1;+L?&)A%FQGh_ILjp!_DoAhKYJ^(Cln=>C^_4_Se^nu7E&c=n+wq?P`|fC z$=SwlUJCe^LW&iS~I)&RswDc8AQao0Obweif!eJHxSP=e5B8urkB}_oCCE z5}{>h2jqcfpA+E#$y0L9xxT48gj;zc4?Jj_3>7t(l$>p@=Ow{Lm%V8J@s+8Nu_7Pq z&q~dJv+s*hXKhJ=U2Xi){`?&&00+(}IooWFPll>}=aignc338Z*0GC9&NdVFCV}(I zBTCLT_H`-nL47mY>9{Z*>SCnX2oS4-b}kwyhlQq3@V96j}gzXR5kOUVVZC7$udAKkQc5iS+-~IWV z0&dJ}jk=Sy0)EJBQGcA92t`KvXwS*%a`@)i6t&h^IlK#fr{qksN-Ytd^*^ZOKK;G2 z3(TbxmE7kRwCe{gVrMBir}cl^3;O#URB~<^e5MPmxzir^tCh=>pzVV=^g->GXF=63 zYvdEZ#6-C6zFEncB)GZNSp8TTZ?4egGht;j>P)~(K=%s%O?L50a8U7UgQgZeD@SCBr1lE9?Yc|JIb>?9G-%%EvGQ)m=7Fy*6<}Oyj$Bb#F9(y;X2=x= zkL8eH`3-H}D#}6G?GN^4%RD*kntloOrBz9g-MUuE*<(*O``wi{m7HVuvw5ty*Fn|_ zWAi@!n>sa{c0*D=L=N-D-d6Jd7MChuw7C|tXcoJ#hje|W)Yy1IGHYcbyz1dZ`8ZT0 zDWDB$N$>nPAer4I5eE3`AglCcZN4-sP;w^G?3@bw9k(bslQc<4hkHLSqdw2hCce~n zMPE7UpaOQDZjWQKa7hyM8fb+2+$PqJK{FM543opijcQmvV**T&-ArRg1dXS z<9hh9Dh+BAZlW&!qJX1gw_%;yyJ?_(NduW=^dLF3d!UJ9zJ~S7=JGuyX=@NzH(dd5 zziHz-(O~u)eY%5lF>^wdRaocu{X~%5Rw_9Q#rH^oJ=#Zc zJr})5fzlNZQQrm4*a5=PnrjGlM6SLvS z&YQ}cIoBi|-YURLOOu}3ab8l#`c)j)1lKdnl0&EZ<~WZ!Y&->LZEE@Xkfb9UlR??e z$W9t#6krm6OUb$DLX`p{^_w6U^_nAxs?j>gKhId3%PxOXau(`$Uk+0%uAq+Zngpg> zt|>Vewem@V-;clIT=YCHhojY6$VGPSw_f|-QgSXj^Hc#Ex_6YEi#AdPyziz(V|N+^ zda^oqhicQdd-VhRFnwmRE`3qhJn%VNt3M0Ml$)t;;N?sOeChR838h+rJDVj!*2{Vv z&nTBfkl!{&zUp&`-6M;Qk*|FA%fa~LYvtxHO#>%bC&Gr0bvU+pUWt%;Ne>z6*i<>( zpzoEOqfUR6!{@~hQMVHmVD@sClCxI#pQ$i5#1=VfOHLvzPIf?!a{ZbJ@iSH_IY)i_ zmI*Vycu|Kz`hn%MlVSLvUrNqYzRToLa99oZs3vUuD;jE*oT;{?Btrl8zfjLz&er*- zSIT?0)B{%rvNiMmlag~$t9x=#ORzvLdjFa2KYO<-IU|MqPJ;pucY=8}9kW3h=#RQ* zlN7M=jYi%7Xgs)d8;1J%*H}1~zW}urnrA(&b<0$N%QMIj_V0H9wPnIIR`o z+>)<94Dw6d20D@ug0kDCeS7R9;@a49SzoLk2A>h+&z#{cGQ`<%=)!ecT&bY*bsT^!*t znS)E?KytP>;oM?iErl}|dl1eoVvrPyZp9HElOgOZ_z!7s!nx(0ofI}|gb~gL2TkP= z*S|aAbZ?2n#BIJZ>xk-_~VGYRLGpkNuC?J|pSZrR*j2A;_a z3Fnp*X$df9?n<;ReozuTkIW;STV8yKhj+6#W1E9BG9c$gXTtr$SQ|MMKI=?4tNdiT z=lGSVhxSZ@p>GAW(|lVJ_^z5vIJcw^m%;_Bd02j8aU8T6z7Xrz^-6&6D`%m$8X|)$ zHNN;;#le3JHU!5zZ~4d!_IrehT5-5;j>1!BMjb=N9)BGN@F~!)p&e zh=-AZvkCY0Czi_4Hf}SwjlPT~oD-r~$HRb*srb7S+sk17ieac_pJQQ7j~KKwXmUJw z%o>kc=`V#O!$@rZdsqVW8Z?@4o|$hTgma^?LQT0=a*wL80(#bb#j`=q2_J= zPjk-UnzzsU#oI4m8AUkT)W3*_iETR&9*4=w>JG=)8GEix-ZM^~nu>a+qYO;D_rUt6 z!=!N0csS~7Ut-~51K=3uG5_9Em_s=KOu8lmyUbpM^UuY$QpkKc4Eq?)>eprVAv`AI zWF|#>_)=Z%B${Ls z&PDlYQn)u^FzVX(vGCHcJ>hW)`^7zA{DMw|v(U9^ayUFR9d%i~6lTvGi~1mI|M;3k z*x%<>3E&!#i{*!E;$WEFCc^o!*VJ_ARU{=mCNs22JecN^)=&)ZwcuZ#VMH$GB&OvScT88t;`_AWad{_wKF`4uJiICnsh47fn*uFBz z`Y@dEn2huHSh(D4F5&#st7{yrU$lU5{#mj=9ztJFLVdZ96gFK6CY)ia8BfM*NU-l; zPAg!yogDRg&p2@2l!A4vyUE~5uPiK|v_J|A&QHK{F;WTx+RexQ4(b>W^w47;xt&JgI{D7V zg59&r4y2=Q`GT!6tMLTc!&?gZwcQAh z$&47n?nnJp!g<5aO9nZ*eNe|(N};&NB-HD&q>vFmk#P1fjhBM)gkCrfS#6{+Xkr@S zF`4OF>~~$q6V4v}eWb9#bR6OA5$7s}J0Ic+kI6`T#X)YH1j1u7N7Ca!QGoU(GfIO9kI9TwCPKfAQG~~2wrELV5lJGP6UqCp;$exP2U$U&VEg)& zp73>OQ`9SB+rqTRx~OxWIY4NM8S2aJ9Kdgr9cr5c&i}IWZ{A(g_}wyXb+mx9&6*am z5MikSoNcj#0kv%n*e8k4xw zYXfJSTb7O>tJDI{Hjm~w!miHhz}d#I$Q7pb(gw~p(l(Bee_ahY+nh9R2VOn3fU`|; zts`8~R|CEu_WIxhXWlje&NkOidBesKHPk19I)G;n)w_W5Ub6O2nqm2OR|jxnxhb4& zY(*b9m!^Sj-rE-f?evU*v(2R?#vC}?xJw-1_n+3-X83$pFu$S(oD<&Kw1X#?)qu0jO51kO-L56-lY<=L z=cgvX8SGw~2e_N)17{oQ4|@pOW`gA&ckChfjycx9*3SXv+Zmyr&FozFqzV33-(6mC zR$>60ZMxpFhn$!Cz}Y6~u|1Gbec)`<>l2&zsYbxrraim1>nAh3_K&v%Oc`$koNb&~ zIk%15%xx1FGzHE8S8dzED3({j?H@7H87gaZQEz_i0E_dRqMe5u+CYw;9_k~W4$z~0 zQ*2+U=>`+@ngeH>Eu$S^d3${Zt&KN#Xh#U>j3^6w1KnDrKXN(4`0vR z9&Q`&7uWJ?O|-Kr)d{+$Xai@Pb6$?HYKIQ$Cj(oA(W`_-+~9;|0;0cV@vSJ=8@ zxlmlEv~3N=>>Y`mZAvEug2i?<;A~T{t{rTZXrh+=c7jKXnxnQ#aDd|rEU>?K*E@iE zj476nt+j{frmcaqP1okGFyLcT;A|s{X#+=$)q%53fk7MC(^nff+jzS;LX%U?P#5Jn z!0_f8z}cp9tP34QmRILHtcRr5}1Jr=CjqjB9uwc3daJG5s-0)48gxNv5s4a6AaDN!}6VW4shauDfUY=$;)w#hJaggeVL@qX;I%?W1f>!BX+=>Xe~>EamXzIK3(*VKWt z&C%N~AokG!&NCx_IKxbK&vKp3?%7FE%pRt9esF@2kIjLz&2K*k$cWYg&Nh91Il_`_ z8o=3RM9CC)E{f-sk~mn`$)&SRG&toNfA* z*u%C+HQ;PBt7QkMyW9*o+qmUAfPte1aJJc);sTq`Hv`T#Pv$#-=`-eEn3g?g4R_gl zYTc5iaF>BjC&VT>klwlO^81P03Hz}Y4$+yU-xHpTL= z&uq`xst%lOu9>=m`(#bvZ1a;kLGoN};B0fvi232_roh?8c0e0&dfyy4+f4U&fX450 z8#OfyS>o}o*Z=u$x5hrYF?%F!ZjaZF)wP7_(E@56KW%8-X8nOcEFU9#L@G5TsGs>> zA-^sLqwceqroT@@U-18WPaUtreLAnBt}jEjS*gk1 z=ej!r*(UNCdvEKOAY_|Pp)B{wmOW!;Y;&#r8majtLAIHgd5XMsibS?qzimG`RU<>T zxiMrPS(BZHY_mPLfYiD7LAF`hb?<+^3+`{;S*LkSf^3tr`7{~gAVId7y6^(IY7>NP zv*Dabrk4aF+h`acCo}9N$Tn7+FOY3|LC7|i-$df$CP9Aq@bx+wIy4Z+!O7(WX=)LS zY!iFAikzPugxsQ2TtRf^OHe!XxP3o0{q9GRIOf%SWYA3)97=6{+q0N1>I&NjUL!}=2BldywV$nv7j z=$qcw*OS~t32J@MTcr6Om0n?fhK$`Ci1oh*A18)2!KfE^FD80-BshkT7T+VL55tjd zM(;g9`o9iDwz2MZj2y2F#y$oQEhaYJLC7|1W{PMJ_wU>uZX53x*Gktww6mn^NwQ2m z2zjR3^cV@QQR$njmBjscXJnfj`wtPvnSsbNHD$-i;izEL;|`RN4=&;8yOYA+k**R6 zvI;f3Np>=uIp>@*IZbx93`K3)@d#NI7K?p1yt$7+lPD}NX}6!4e(Zw&J!wDz>0>HE zwkiB_ksPy>AlpcXUL*wuLC7-&??rNVObF^?*-RV*@bP2LePjZ%g)DJ+5k8%8+(MTfCJAirINNOL zc9IM_#paZ;OqHrGlx(>hgltoGPDw`HjYPJY6uzGX+Xo@rG$=)~|F>!n zNpL+yR!np>SLT94#U{x(6cLl=e75oHt95Vbl}PkZCSKsITr2NnVRisQZ*0CZ8%p zk!{}T7Lly?fjACkiO0yg6B1;bj!RAx+aaOIHct-~kvD#!$Tkr=M~EHU&pF#Hcwb7K z+DnjavTu}d1jl7l9=EIZf!9J#4jJ9KJ8I7@ zA*6AeS_jgwynITL(2nIR@EDO$Izw<{IS^c{85|3Uk5;vFKBQgAxv<_?Znxw~N#l3S z{>?jS8^1F)Eq@rYjo8kZR6Om2Y*Xs+K}br^K(;Y{d{S6ZoQ!NU!*zjBcuaw8v)tWN zI69m?KW1^86UO<)b#C2|ZQ9M=Skmule^uP3tBKO8^=M?9r^`qG=X+oO=KZwAR}{!L zJ)aOkXJitxO>esa!sT)WvdwiPZQ&ftrQmU!%hsmC_t8nnHeL1&5Tp+j$Tm0YbcB+h z$;b~IG!_fp+4EG+c==T}!ei4+WSb6u&I-qDSWYvG+X!hVge}ko^}w$i1O=j&Oo+-c2H8YtUtCHlWnBj(=-M5qA|&f1r7BS ziYy^?G$7ivw;Bt6Sk&d`P;Gki`6@3V*QaDlS{Ug zcR}6$V!7Y5PU-ktSvO0BLkHNkjBVDJfAZfqB?Z}LBQy`#YoCH_^EKT)z{@rj*~WZ- z3%`Id8F+1)wr@#qon-W()-Kb9o%a;j{?HG>LhZsN)VV1%z_LNb;ZMI#74}a}M%!w? z4iAVLm5lB5mCO~EY9}MZDCVvV=xLsUfBO6XG$`bZ@D{H*xEb^?HPF?QGgN!>LIIKg>FAox;puLz~qOi=+oW0*%e#N?}vUz z{iCk3vTtwPmp)H;S0X%3MfPZ+<5Il+Z5J#b`Fp!?;cO4|L8Y-zg;oK{Sf`-hEMe5( z3}liuBYjFbu<_*amQewp{e_iD$RwI|#R0Y&$-r|9&H}O_mG7?59O~!d}A^EVonl4LB8?guGFCwk)9Cv}9bL`;QL~2)(O7)><7MEc_B# zegMm*i8$ge6n9ni*P(h^z=87$WKm@sf1#*v67XD_!Dbf&{Km2O-Lr9M8M0FN5tIx( zm&Un#mhgtP$yud#ZLqLEB@LNmb=Lf14@m}cNbfOjB{$x&d@mMznQ=BWz?tQXa3;~| zv`%PS-v!4cwqm>RCWJlrWlS=?zMHV9hPBD+?06F)JTF#YxiZdK5O*eHd9qdafS-%g zaXp;O(=F-D@)dZj>FJ=M0ShjrW1SNvW+kR4704u4|M3#y*{#6H|-x&q2v8$zKLNHs;oO!HvxeD+7lThbcJPvrXCJF196&(%m-`WLPNb7^A zzpqs)uG@Y-Zhrks(QK$HSGT4xisJ9BLZ5VQUK4T(R$}CoMHCx^<3A~UWomvz)j}tarWqUQt zrD@p%gnJuPkexQ#trpIWNJcJt{9f{QXXe@vVHL}>;adEr zDfF#KMx7fM9gwMHYlFpn7L890_|DcRpU119CtSU(KrY&oMueekKjAT-VfJGKRwk8nxG)r1{p1p-n$w|mpAA9x^dg&zr&!us=`7U6WO%jf6#^Tz5 z^V&(sNFVphh4~*?e;GTS?(rw!Ae#%WhkxG?ps$vWb=poTEABoi89C|^ohz)-OhJxn zKY6iGajYwH)P%lsOWrm~1D;D`H{gKqgY5~NsqQVd66)A`=JE4po1BFeY;Ev((VxJ_ z0b`CUP=^{?2~y`I;JGxWBcBD_s8k>qbqLoI438xt7unw&BQ$xRjyl8Hrlj#Z-UA1! zm?W`q_J6+by|I69%q=dbRZP|O`a|W&F)A+FSS_KA+Z@y^0Xb*L;~Z)#SH*TdjbB7> zELO#uUb$_dT>~Sr&c*OzdSz9ds=ngFzuravH}9@*{BHU8O9vnq4IDI`c6INDTy*Wk zEV|t(5xMC8hB@>|*BIm?%?Ek3>8o($qCKrv)1J-|$VEB!hv}vV(a1%PJ5JEWEEj=4 z&+=-xPIC&=kc<8q`3&D7&pG7(z90T?-aoI9L?9OheOgI3=tLnGNiCMrQ~!h^7oDtM zPhEY&k&8NyTSw~*qL7Ow>MW&&O~a9kz8+$AZp0vaWV+{3N&j&4vyix!>S!pCi?(&1 zL(e>rBMUt`H-|PoB1NrzF_#vz`kafd$FHSYl1MD~PbsDu*AtP8a#H8elTO{S&73{6 z=(6;1wF|~QAZmkP3jekw!O1GLw^m7L@wI* zPchwpRE}-7n0lQSK8V46>6m>U?etI;t9jQdkH%)kB5zpgpP@P%RPXaQe>Io3D-1&} ziYVJf3&SGN{?&62)3WQ4SU-~}X_M}%_)q$c{q)Es)qD7%OAgJeVb?M)vTwVW*53<5 zF1k8n5A{%nAs21;-A&g{R>geoZ{R|@ry&B_qg&x}s&yv}IcinM4RjOBJK-@9OV9b# z+c6gPfszGyEidQSMw&#Tos$PGr~6sFg_m2;J%pOaeEz3-%!g~6tUPP{Se_ z?r957%%gvHsbW3@XC9;%Ov8~+MoZSyd{&>^b8W~L`uKeqa>yIMe6)whJ-9vGHf}%a zf^f96t>qe;tR0T56|iJI)jk}C+Gzep3V*_oyPS0P(Nq?@aSAY z`KtO^#YOb+tSDr&7RE~`|8L9LZ0ztQv_LH!xhqn+o?e|DhI*yRHu}C*B*rLSMJ}iH zr@~R|X&u6O6K=kSc0A7Jl*N2Ln{31};l5ADb{kz=9HwF$#YQ@LYy|R*LGL2k z@_QJ@e3~?@r{l`QaS!RNSWUgz{l)LiwWT}ggGFIDhTH2lQ|QUYfj!Uauyz@}bv^>) zJfk|Tpvml>V99Xc6KBnOq^BMl)AT3xS#h8z4eJ;Ju z))If7HLvY9ny;;j=X9U9oQf69r!YQgb2lHymg_-w+vtsP5y&bV2NcofKcbOUOolC_ zy(?mnRrIa%=Z17Ohc-4m1^WR+*so*0L5IP8gw{dCEy_ z?ybt(Ni}8X@*91>hJPc5```c9_ilI{&KSIo`*%RLshwjj-hAeXY-7;hQq)=Fglu!_ ztBL5UWrJ+9(aKbOT5gVPQ}V-HbYE$NY*XF8wYYDiF|y4V_qO8ILUUxB4R3tJ?HgJk z+pHZH@}J*=`I~RnSoX0%w&}6lTrAbLLbmy6VJ42#HAA*Jcg0eiKi3S|MoX|1Q;e*T zZM;p*#ECX$$Tn+>EJf*J8{~(ue@w&^UsSmz#TPBa9b=u5Z9co2ivPqqA-9CQG7-%$ z*`bcuX(I0bYKCKb?Sh54SZRdi6D~N3S)EwE1OZ&e&O5qBH2YZ=?@4zm+uoQ#oeUVpF^ugZ*( zZ4BdVMduP#u8!q&d$H9?)i-+de>#cBSUKNsy(ikEZG8Xaw)xGsM&D{a(^UMq%K~kl z)7xB}v`}S#fswVisFyX`|8bG2sJGV`^%w^m@%_Y>Xxnr!6*HT$`iyNf-CByN3S%sP zD%gta7PmyU(eyJF$K+U|-=F-@Oq6ahMYg#qZy^rrZil{p>md_S?TZcS!!;&&EoT6J zt!aTJ+WGUWnP|Sv2t{JzilNg?P%GM7i>5DI;TWD=VIpqaXM{19-I@;K zkIrVuHcw|;ir;6MU>{pJT8oY!Op$HO>)1MH_Hh5s?ctjDi|bP(&C$+oNfu%^S2N_9 zxjQYzLBXb|;b{x;(LYAWHcN`^#7+0jkY{phEyU`#CaCLsSc$6-yQ5Dpo@*iAu(d^o z=~-nWu4-$6`uQnyQCen<`sA*b;__cc*!SQKF5;L?Mp)ij<|vkXnWKL zvA%6877VpQw)s_ODjHgwAL97GLBkwz( z$IhB|$TmZcnTSg*ERk&rY|X`veNB*U`ej**eKr_j?8qjlwOCkeggmpY$Vt4~#~Ags zFE*l$KWm4vjp8V~FREK%-`}!%`7x*k>Y6MwF+%_U5i(OOAv3%(u3-S13V=Qkz z)JFWa!wCDEQsF2{b{eDZ*WO0V-)n?*Iy*aw4?meB+XU8`iwpW1icWlI} z*~Z8=d5djC^0y9RoS#z_csKNFkUVdY{qxiZ{3uK$8*=FL4D)w>?maC)p4_kX` zX2>=d?^%k=Z&)GQ#Gf}6OW7Q8wt25<^RI8W?T29jcMW{t&4cZYFSvKXyI`L&sd%B7%fidw;j(|RhNZ} zlIyGRjMdhLaIsW>7M`(6aE}*<51)o-tjsSZiv=-L@Ql^oPT6AC`cZhss_w~P{MH+1 zs{i}lx4-#5-7lLpc*d&v?QpS8>y3EEYIRPyc;fd`JYzMgIzo)eT8?L|%oj(9k2-F| zGgdoT9eKxPc*aWWUWAxEWe1*P8uBSzY&U%cp3SLAju5ZqAH_3PVaKAy$bup~Kh;7v zTC}^h2lbbQ5#olKEAYI}2v+}6_6#h4-&-z@WY5Ss+jLzQEv9w5gl#_ioG6}^&A~HP zEv#kY59J&@V|Dd3duMjm96V#yM^7gHb74B3u{zr`k$rz{D%#eeMXGqlbq1cXT6;<^ zian=bo2}n<7b92fz%vnFzl4jMSMI=bNw#0Z#XnD{qF$nxDo#4PAMI?N9w|OOJrB=V zjo2L{cBy0UjAq>1yI;IG@x*kjuQ@tVd_(4-u4*e2&)zG<-`YAXO577S7tdH3u8I|# z7R|*oR{Dxq(Q)=XJYyxf9wUx=s5)b{YO+jhA36iCC9CCPVwLKQ)rfI2w2iY3w=F4a zi|UNe2KHUK<7@DDN1O>4PyYXBzJ8}iiGliC&`yW7;bL>A`KT8@jTW;Lwqg65PK1l& z*Db&^R^cwu;=zscu-x!OjJS5fHp26eHCdbD`E_{yNG(5H^uD(Q&scr*jufZp?!hxh z<%1(cS;S7%vzkTVwa7N?+K(;Qqn*1~hl@YUW?`LvgX2(hw)vmtY{NBgpR)~bzf-5J zcup#GZ@B1Fd>YTl?E4xgzTdkGb*vB}W-ecYI;b>UJi2H()?Ye1LJSREhM!!uTWX@uBQz7YHPsc)3HNx2lyScQC!Kzq1<=k{>h zc)z&TDP4(nR@g;|4-=Q+xvH7hBE+h_i&3A-ixfX!%E2>M>Yro9K#vu8uBuP(2vIn& z2=%yUk>bST=kN^C*=6iq{wsIlnW-UW5n^!eYSdQM;i6^PeAJP%qebg((^cc(p%4%E zor&cwnkIxdp^-Xxj>hQd9ab|~Qc&_T`{RnZpaUN>Z z_fcZM==G{IK`X<>DVDQQPxgqzc|^8h^XQPi8_!s6O^gtmoLY-#tg;K(zEPKlXRNfA zMu~kxX5ksDJ-YE?;ouo~uIjr&F0TJ)9_kA@F=Bhl+F@*yk{ux)e!36)zWqalc>QWV z>a5&wvFrM^Sm)P)a4})pN-V$MHbSf{%EfYO8zV;io`L-xKQ}?_V5T~6rB)X$cD_0T z>zH0m5C>?j#xqvxAHzk%-}7+XPR))HwJxs2Ggb@P+?_OGbIRDpesH8%t(%AIWXY!} zG3D`MJYzL)N~Aa;cP5^(sws;XhkRO!XRMN5M2Ia{t-?KIMH4ojt>>ebRx=xv3vmpe z21SX>obvIE)#!!c;s%R#c$R9=PPX^5dzQ1!7&f+3`mIK-TN5t&M$gAHRv)fKi;GXK zz%y1|VOb*6iau6Wx87(=83<^jhXOnXf#t0BOi=2~*CTD5q zEIAuQ&PW0b1`}+O!C)}oJU!cc$NoN5`F{7_x87UjTjjdHn*W@hXS#d(^jWlLk6o-I z+t!{!-?94UT!6f^W(s}BD&MjISu<)GeaGsZs`EEGETivO)tp#Iwtk`Np6YE@O>H2T z79U67vC3YkiOf0ed-{%5?&lhq zSI~E?0#qC;H=07v7KHt17-@HE_M^otiI=!QUZo zY9Au|J*XIq?^yM41S3 z^5e@Ge8+0kr6Ad;NI1RsrsAAHndZjy7<|Vnd`F1vpQ|ptN9El7KzY3Kma6oe+oz2T zj;vV~f2&ixYioJ7NVypBn8KlQehU3N@;|Bh-#$J~@4XptHcWPUxuPn1n?IdxBHT(XVcdlSDUMAmq|ncjO-Wl)H$gLkLw&gs8vO^6)Q@&dj0CgXx|`TN?( z^xm7yecH*XKgH2|Zz6Jr%Zf8nxnMIsyqj#cX<7{Wgch+Oa>Al%G59-VTk)ackLi6f z=Q_2MU9YU5-?d+`K1?3SxP;z&le$E(OndbJy<6r~<4{>P`*xZ?KwaBn#|7d$Yr^Fp zwBis`*3!I2g!q{m(aRDRSK35PHu=nZ__-V z^6lJg^llly%0Y77l&Bwx?=F}O36+H%i8WqzW9z+tD&7`Xwfb) z;OI^*<)rmr#De9+Kp9f83B8}B)~rA|y46_X8EJ#$JNKKt`0Ojw<50Qi#vXdlO!b;A z<)x+}^e&nJH9suFSlZ){snqYK^l2N5?^qpG`3XJ9XY3aY{opJ;Ez-GoU7)O;HH_Y+ zGi7$5oY=BIarW3id8Yq5daus-UxVf67wglzbegI2bxsZ^PJSs+=6bQh7k}$gX?j<= ze(b0i{M*xnbS>qE*QM!QE}7K(@0Y~RB%U@2+OE)kKZ;gz>iQ!zzG{D{{CRvz7yj<0 zR@<)f#md_;_>NV>0>Lu6%)=P`o7BK$!7@d=aC)y!xH`XELM9Vetq~+^ZO9ypznd-8 zAV~I@8ADvQcT0*R_Kr9vUI>iAzeyEa)>0-6%NvXDSiQ;=BttTckHvSa2IdNqjlbSU z@6XwvHdIE9J5BG*8GJBI{&;o~@tN%E_glgm#Gtpyv%jT$z3lB??7hT;P`S9lC$Zo| z(}HCE>G|lrE4k9E9Ny+n;{(47ls<9uX#Di`Aelb#IK4CH)fZuM#mPCuzqnNn_diK< zCWVH{y@e~p;yYF+_Xo;t_9F7zx@^Hxy*i2BY2#9{Yd^a;y?3SJwm{iqjwwW9J3Re&-evuT2%KK3kYi@2)BKFi7q_ z8A5&-ta7`;-4e0*j#dBbfpXBX+4Sz3?%RT7-+j^a?i$~DLDDC~pE3A5NVv?}Oyk4~t^a+sw$NekY`8Of0@*)uCfc`L(PZgTF&Anl4nn**rNG|0Z>`c92|} zEi1ieCa-^x+#NNU-anJER**~;(TVu>(mgWl=aAXQ7b_}q4Sr{B?60kVI) zz4T7MT-R#IO5Y#Q@ASJZ&#=6fkV{u@ccC8cxY|HY z`)Rui{YZaAs6nsR&60~{ERmppqRct-nyn7JL)m&2Lh|l4;-HAr4FHFNajq`g5!2*$+u?RMc_fB01``KHGn;;|cR(zO`JwXGa((&_Yb%F~ap)0~GREMnMXMsEX# zee4VN>rIPsp|?5yw7OjUe!B}jOva%tWch=;iFY-vC3~0KPh6mzzwEs3FwKukCuFld zr-(DYb;!U!cajg6wpX7CB{LjH`LoCW~(FfRdCUJ1*cu9CJRn*(R&5$Rn_Fjj7MGg{`d&n zl6h;MCVs7c58-ldw+p?EyS`J_>vEkqTThGPh`l3@jR)+ecK~);SxdgFv5($YeBr3S z{Iu8)^uFSq&m3}?-%Wa7@fVvdS@wFO3xC6$VWN=jx1S@vrgHCgJ!MDrHV@-!$y6zJ z(cZ_msw0P|w28-^bIKiU_R*X`m%luC;UJAaA1h>``DbZ7*9nJwACN%%U07Mj;pxv3 z-&f<0&nD2EYR!Z^IQ#&;8*uV7Av0|{M}9l1G^Chyklx*wVS$jJ1s|vP6+aKPU3^nsT5?{%QF>qT)@_!&cjExnkYCQJ9QZAcIKQ$V zQ1BG_@JuR8794KVJNNd_amtb(-7fStsqXsA(dx{C_p37-RQv$(?-~7NJ$D?vulRzp z^L5lAdN1GLKp{te*yqCE4+jtTm%q0?O1yZJC3p8YNBlwUeNOyYdS7uq#k*D=AwOij zV9C+T_PfyAtoQeq4UWXo`-)?f{i?okE_{F7Qs@23IO#%fvo~usxnzl?_vw9`x|+y|4IaysC{sZWsQ≻#mJXheD z3!mG(nqQpwwaF6UBx6bnZcVUvUw2HW$n} z;6iWn^ns8A>&4OgiXW&NUjA-8jjt*!jB}@xZ%6#swdx_Z5e2 zQThCd%Z1*i@e6eyjEST772j1pOs4*Cf2Ji?>hJQ{d(U5SfR_a1w*99ETHsYpv)HM> zTSVOUaVq=s)5nOfK6)b6f5d7`s{c)BJBy^chFIB<$`-M*?NVzH_str$${2ST^DV=U zW!Sfjb(L1H9%1MdhJIn}3*#=&zA#^U_9c`ZVyuZhU>s{=Z(yv6J%h0(d;!Lq@DUhm z!gpY`ucF4d%a{-UupRh~?Mq`_Y3PCfX%1`{`fc7Q3PX=DbP7YiF!m*k{R+bm z!tjqU{3Z-P+Z8HAlh4N_v&GC0ZHPOkydd7@%tqWX;f`o>aDs)nj8-q=&R0Iz1s*)$ zsc2irmf#JS9*Pg;O55NAo#KV4FqnAm;2%Vj(Tj<9&fF;q+}umtP>dKd@lvA&8N7bVqANE^CtUF-j`yTy0+W8P4-u6e4V=XyYDyIsTDV= z(@yl<8tNYCchSx;t-aXOzk+*o-%GZfG||HNqQOt>6PG%Od*f_T!!BcEzO!B(7am=@;9#Z-k9&W8cNuAK%8(wNYOzulXPu#iiLLRMtAAj0#gdx*?#_ou6@6ud2ydwBWzqdBJjMO znA@gnSKMA`51IEPUHj9JBKEO*&*<7rWm*(B))mc4xarz0`xe;;Zr`J8H+L**4_o`3 zuEl&~U1983q%ZXoT|21B7j~&sFX`IC+gcPi))mHnh2dur-{}=yi}}X7!q~4c{49)^ zn(GQ}mxJL*R}tVs=G-%i);i_M1<=c#tmc81O;uGMajeI{lLaY+6ZcG({L ziLc+EW@mUbgt+Z@1?=!l?TJsOxhz+v>Oh!`po@*OFs_nYGTWkB}r`oPhJiPSUUfXYe4w}DkM0b00|D42=`VF+#zf*mn+RNv8 zzO@|%^Ak_a9cA}AP=xpg-wAfPU0)HuiJNTCI97qU=7DLpLpq4JzMf&%Yg(IlPlssr z#;+#C`(8)e>wH3qdvA}nn?2Y2IyHNy9a^F%jh9+G-TrCLK;k#Ar`V}~*FLPiXrf(f z+9(eKS;F zn>lqed(iwynm@B|Jv&XF2;$LKtJzPx_a|O8#Lr%EK>K;g2p{`k+jca*EK>!0?BrnL z26fBXEv7Xjeo?-hef1BW1FP-wcE>ZmG(PoeC3{lM^28T<`r4i6mmqeAIqiGNwQmaz zsbhz2%SYqAXEwIWozSr;-Z#X)-C4)z!Nqp=&Jqh~PR#G~?R_3DJb9dbCFLv{->t^) zcsRcrhqe<%C%U1n`MzM{nhnd@`3|=u_A6PzKH9iDalQRMcGm0zh@*e;vyYsQAU-&w zy4|AKC_SfdeY?!sF~s+qHn-ok97{ayNw__w%sAo^?>gI^3TghPRA2jHc|E6Y`3Sp1 zSAFf!HlyufOCxFivIFDndhdr34_!XVKA5jR@q?RF?V{pq;zO-x*xxK~OFSb}v^_04 zh`7)_#qApq|9&OfKGdo@@wX3V+Ih}bA%2~2hJ7Y|S>op7rrLQMe@PtUGs#vj8YBL# z_Beaog*?RTE{(Du^~puNCgU*s#Niyod;jchf1cpsGo9?rZawG8i7-2Vi@Y?awzHYt zZFC{x*F)>s3yKscuH&j^7f4Z#xJwQ772&&8iMLksu{%Z9AkKcP{9oere=@KBtqBv{ z|5G*L-!nMT{lDo9CbVrq=dt*fC_AxOW8&`XqU?z&>l1G)9c3RcSc`a1jWPC`6;9$6 zPe<7WHaLjK4jyS|2-RnNZLi_B-*F!rPj`E;y)=C#;!H35*{*UGiPN6$X;<;roNjhk zdwoScXM4X6_L8)fY0mSht?iTBw9T`hhT7wDS~OliXOP{gU^QZ&qs`Rwsn*uXr-}V; zf!2I{Xd^rM0lk-dOB&iAf7g3#|9wNdW!_M__QLW;cJ7a@iH{9#V*8EkK>RX)bNk@n zF2q}-g6vDjbWNT*HPl|)vL}s~{Jf1_BYSV+FH(23i~Xv(WSMUEhC7e|b$@}w8d z89lMTT`Q-)wq~y(cFsQ9W~ax)?eMgEt;csq+9N);r}-a0A8jWN(AvK4IL5v|t|g7{ zsUBq`UfI+1b0c0ot2ZXzx<1POtxA33!eUSqreoOZ-t-E3;N+1rWOH?f7?qh2@S zT2n*p*I)G@zIZI$9vsk%xJlo3cG`KpiSKvpY`;s@hZz0gzh_~h`+wV6K);8xV4jQl zOLTnq_w8f1=%nMGt@=RwL`R(uF+U8oKi#17WcQ12?4|*ob)L+RwClHOPaM;1w7vXY zE8?8rj=b5o>v)Yao zp6AMsjcPltdbr@LOV%;Zb8DZ41w^+$^>gUR4>?4K1^T%uu0lr9_P%~@bq`N2N~hM( zeU<7yv95TYf1__t6O&{0b8(T}D@2Yk{k&W@~sGk7~IZld}&GfTX`?lA_=H>bs zHp}4dB3qPxK8kPLPPF~Y-W;HHK<69GJiP2+95+C?ph!Zy} z5?8%YMGVd@h^IzX6kDIwA+B+|ocJ+UGvXWX%Zgmp!oB0ob9MI4|1+>RG3?aYJeU~v zeeRAR#=7m=j3$PjU1Ot&p)>4?em;f%PwVUFR_u$%>ns`QogX>qTd$pYp;2D@e&Z&1 z*WF%lieNpjGfWq(vtgx~Uj5I;Mtk?Q`gOE-zZhpfU_Sc?cGz#Q&;G=^>}Tj<|3fFo z1^UN)qMuJ6ZkQrQdN{+labiv46!ODkHNM`%C*z{Uc+Z@piYIw^)yw&!>sR{ucbVc& z9zLk%RBxjGol|{wu}`t^@Ev8dooCKH#jQM?My-qdL7n9M0YfMBgP|Y$0%Kp;FBtoU zAHeVf`~!x6;5RV*hWr7upTY1m@`uL}7oLxJfnf*v1BQL%4;bqrf56a#`~gEJ@&pY1 z$R9B04;XpH^O0|C2YJZ$k)OOS@|N`=pIIl)1?%T?0sA-?ykCs7A26T&13TYYG`NR6nc>R0!Cr}P>ZTY|b?3?j2&<@#lVH#Q8q@`LxxG zQQ~bq{mgh|^+<7jf_|2q_QP=T-1Ch2^PnNZzN?=-9S8ag{{&rcr=IO4LR0i1n~RTi z6KR_0@yjPWiq6OM^J!!C?~{>3^k<|pDokYU+m+^z{5DvmIo6SQSDF^$`dt0_WM`|X zxcokh#?O>)EJVIw;&YE0icr-{pr(x<*--TRQGagv#mj~wmPk6>xDBm7XKF4_OD(!?+u>jW|9xi687=d3ZzdgUC*X^fbS4_neG?-_UhPn~fyrvIM7|NGD2M*r_csqaR+e|UMx z%5;ANaoa*it%vdJi8GwoZTXg8M_i`kI_uM)R}&v;yT~e#XBBbUqBE>o*Ow88ryg&e zuC|!C^74_^-tO~>Q+FL=-5NBTxWLMRR`O9ZyyH*QvkEj|{-Dn$62s1-vtx;2e`B&S z#8~&^fJkEKS)OYIF?0r{8%_-Uc|s$Iu`eF?J$}zSe`>*3UOT&MCKqhK`;jz)*R9v_ zQ^9(cJqJeS~ojm?l-@P0AQe!zV85A3ktV4wYob=l9*!~Ta(jtlhH z*}KHMubQ(p2ab!gnwQXgr~V0RM}+qO+dhY^ol_Ul{CvgS*2J$D68D`GV||u$0r9}w zyR3Q3=Mldtw!<3!*<9jE!?$_k_2r|jmh*bFcf4?encn&9E>0(go${ln5yO6}HdBeQ zZt8wIzR=U{;A9$y&LJV1p?_dS&4?F|*XnrFJAe1GJ6=1>hCT4wAAabGcirNF&n?zd zG|g`o>s)d0jaPr?-fzA8>i6NTcfS~CKVUxl2X@$Ru+RR)y6k7@VgExX#|8QkujJE* z(D}kRnBxWJc!4=yV2&4<;|1n;fjM4aju)8Y#pCb;&xe1&94|1(3(WBXbG*PDFEGao z%<%$qyuchUFvknb@d9(az#K0y#|zBy0&~209P#4$h!>dS1?G5xIbL9n7ntJ({(HRs zJ!_-Au|s|4*nv5AV2&M_V+ZEgfjM?O{y%lrU>`a8@45Tmb?(rI6zTaNeF&KQ5HR;4 zVD3Y}+=qa<4*_!@0_Hvh%zX%$`w$+-{hjCIz7OU;1k8O1nEMbg_aR{JL%`gJfVmF= za~}fcJ_O8t2$=g2F!v!~?nA)bhk&^c0dpV1g=U$0N?Pdxqq@poD5X`cT7%a9!QFi-zK zpmQ#Jsi*(nlq0u&C{p+T7~kya|1rO^r~ikYR-XPJ_Ir8yf2=#&)Bi(H5l{aQombN8 z{vZ06wAB4S_Qm5{eU3_=-}=^W$#zB#Str?kj)99LuNzi%hGab(^Ng3Q^Xl=DlJ&2j zK1A}q4xAh)dA}HEKVUxl2X@$Ru+RR)y6k7@VgExX#|8RRd-{LuE2XFZpF8BH%19bn7`Cohbf7p3GO85V;f2_6c|FQ1zzPkU1o)Vt^A3Cdg`hV#6 z@$~=L7mu%A80Vc|sm%$mod!{dy!LzhxxMQiSRdonbL7=7ug?089bWxor*HG_YuKM# zz5B&D`vLRWKd{4ogMIcV)@46K5BncFIWEwTc%irCc!4=yV2&4<;|1n;fjM4aju)8Y z1?G5xIbJ-Dc=3G13(WBXbG*PDFEGao%<%$qyuchUFvknb@d9(az#K0y#|zBy0&~2; z94|1(i^mZ!o{xBeIbL9n7ntJ(=6HcQUf{pS>)*4c?oI#8&KmBU$jN`t-T$t0hdu)#&oKVpaa!?6Q%?7$p5Fvkweu>*7Lc>I5&hcx5$)O|#} zDfEfGAzL#s|69$^f*Od)`wr9igG05&?D2<)?@p{H$|N2jo^;kBs$AYjyhv6NlZM&E zXM0r=6K=*5-+5nNjLEu}_}IvD;>$|Ai1YkeR-6pn?j1imd5d@cp{E;(VJAoQ24dJR zFku}r){RYELkvBK)~zOn&Rq|`BZmIA>osFvJl^p_uy=m1&aJ$5`Y&tmwSTH*7w@_; zJ-Z9m6Xoh9SZDu|eZBgpuJ7mFm+x2oz5B&D`vLRWKd{4ogMIcV)@46K5BncFIWEwT zH4rcO5^I3rORNEgMyvsbcB}!0FR=y~zQh_}_!4W-eC1250fx`uJ1~3+pYk|-&GQih zFzg^UVAw~@z*rZtr1?q@asmvU$O$m?BPYPv7mp)%cs_i|cHm344`1@S@FnYkFIgvi z$@<|--WPJ8_lt4%1Lm`TV2Aw%`|MAw%YKF)_CIuTT%ce5NP&fYZOC>`Obtvy+}P)g zsJ`cS2gd97JS8qvxlddt?zk9w;1uz~{zt_pg}*0W)$OpdGnQB!I4Fu|tgPoxJRpi) z-RlQCz9;vKAJ;5i1HL!|t44l(Q~`^2!X)+NTeN{^ne^eCOg(5duG z*nxhvFJjNWh*Q73;GLh|zU;O0Y1lQd{n*_%yz6e?f6J>UXSW3Gi`M#dd7@W;-nO@e zdVc`ztN*gw-u+^n{eb!GAJ}2P!9M#F>$0Drhy4$o92e+UxnX0E$a$3;#5fBoH;7Sh zRBjL>=T&YHBj;6a5F_VRZs_?c=T&YHBj;6a5F_W+StjNAB^u z$Vt|NTxFfeVb<@-d9sh3S7(73odiLqav4?nOS)F`$Ozwx^8C+mTqSttC@`VkiuC$jIU^TasoY929afV!R- zwL#e>M$J&`5u=tU9mJ?HN*^(5kJ3%-xqlI(R;hh@$JPG5^OawSVMqCk81|JPiLtKo zFER8ezY{~JiU%?Dt2hy3Up$Ul#q&|C*bZtH+efY9by2HW4{8YY`#fj`gzp72d>fI_uRLvqrtx~m#7&SoECSueo zRhx)Wt5j_wMy*n{k{Gp0)h1%pDpi|^QL9vKB1WxJXWKij&b)WNss+TbqiO^(?5o;A zjCEB_A%-4RYlxv!)gWT%SG9>4@1-%u{fzkz!;ZtS?=aSN7x05I}HCjjJWt2=L$rC*DuYZx;{yFg?X``XY;)~} zMy!E*9JFH%F!qEsz}PF+0K*4Z0}S6_4KRGk_e%KExYyXmJ;*lhO}25*vWtg_>$+tmuv^VWc%^M!jP80QQ3NHES9?vY@eFWe)+IA6F&f^oiZj|6+p7ctJ4 z%0utC%0usbm50QzqwYeepQ*ljkFE*$(oV z?IX{5UF1LO!MR|aI4`W;&;EfO_8aW8Kd~3aswL$rg7&Sxrju^E>`HmPhM)^+9SNAXFJ7Ux-BCPK%5mz)E%1)(DYs|IH(N_f@b%Ucg9Q{a1eH_n-WZuz$~16!#W8#<_Z>Z${kb<^)%^<^jYnBWAeH&eXp_ z{By}wt~UPlX#7N-y{;p*yAT(Mz8&-B!A`_&;;zRI9MYb6`CZ|f_?;e4+2f91>aAfk zerx0|zf!q^iT#d^@hdqkh&XvB+qY?e)^oIasTfCNJs!Pfv!iZNJ#I~y;22y>+b_SW zx?@nJ)^>CK6UXDN{$yuJ;~S2IPXzIgm49%2I8lwb>*~FZMLqPsmXF-*sIsB}jpy51 z%nDjrns{isT-N9S{X5HPtE908c1TI%M^Xu^^}S@opC**IUiVEwJh$Oj)~K85h$sA5 z*s2keo%mF#!d6Iz#dJ>pxZTovFy#R8?h4H;d&)iHzIW?do6D6YZt2s(iuJEb+$mXz zm9KIDarZq)3)WUr>+Fz zH$^I2m)Bk)zUr)I4Qo}I=9li5(aK+=1o8a)d99gOJ|`Yiw4~*Ztxvo=Wr8DHJAdM+ zE;k*slT{&J`RQ%PknZJ(>$iU9=z3XmLZ+0~#?x(S{9vJQ$MgKU<}ZIU+tJb8oW?8f zjdh$F*O|Ea7t8z#F4J@BjEnUvaXFC2Uq{{byI)Ap4>Li*G-(5G}l{Q^t;uWR)yP9upLVV&- zJ@szmmc;%)m2&l3toPeIM{@NJdF_XR+Y((X!?d0zL#6A}Ma60U7Yp;rV%LihH}J_S zv!2xaOGJA4<0$RhcH5H6&F?DGoIeMBa4i^=j`-S&s9O}1A2DTYa z@38GLV!K>C<2CV<@C`E5&xhV0n?L&!nPz)8;+mN!OZ>NAy^|JW_}{>oi)+BJ0b5|$ z#u{LJ24ajmjQI}3j%C=VHE^vOqcy;4F0BDpHfRm7vW+#q1FJPLPVel+xY9(7`AVzB zcGMn-VITit9Aj8R+wq|_z_0;ZVA#eQVD+3))EIYR4bOa+VF!Mrarn(xR~mYxp;H?A zCHe%|9pNocbTneCmI|=r_>+fYFDb z{{f>vLH`3*dZ_;aqn|b_++@q?iUT&G%I(){OASH!d@#P|C5c6~Yf199rD zxm-R2QcBqIsWCVfYk<|7zE}gS*7U;~V6~ZHl z7hM#z)7pS;_bB_+L7UUPNPB(MdK)a?eeA%#k~dEW}T7`#Esc{tuKDQ zFYd=^4V|Xm6HS(;5U~Hc%{_5+Z3+>pxJ&PQ;_=oLqKD!;BkqZ^-8YGD+ef%ZW|}P` zU+fTF6t~K=Q1}hg<8^z^5$X19ra80P%n@It*e1r->)}p2d9JwCaI@Idwuie&=GkJ% z`E4S+W|;fw#JM8+#7;5J8RouQe!*XCnsypEH;dW7^mK3hVzyXT|A07^(8Ap$=S-2O z&VJGKQVaKu^3kH?scjE7l?~5cZsiF zw{(kC3&p_L-C}xJOZSnQ3q^`fdqlqPL)@!NEEFSs_ll_N!S0u?1tPz1j3|{M*nR7d z`NG*KR_qB6atCIZFMNl)#Q0-@?%BW273cO#(K#^Coqy*Xk^ZGEGG_>M`;46}+UMCP zy54Q!KHO%OXnc5^D5dt>dBI#UdB;xTWAzt^1Bx3v!rW67*J`*&lvH!>ZdfE9XWlO! zs(sb(9W7p6aSPwaE!>+9&JrzG+oEydK=-$w&JllnD@EQRf$o+K=8B2kT_WYfKzFeL z>YdxYV#UQlLGG%N^F_HSG2-&)!S1%b7Km?7?G=d^gWZ`bFBA{U>=mt+hq$|6UMM1B z_J|I{TDrp+*3)-u+ub6^em z=j|PJev{BD$S3WbwiZfyoPv1!+4tW|2Mwoeog5+nn0s!-UeWJ2ODt3DD1BP=JKSE(QvBW8 zL*mw3OY~HB;>w;D%{EjN-zc9KY7!^%SM?DsR!6u?zBwaGT&pZ@&WUi>S#(BJdEqOL zwvTZCeDAav^z&$Ix|;uZP=Z+e>Ce^##m$Rc7t20m6Jr!V47enkMGdjK&5dwp-j*O< z_vvi~u8eRux|SeLsvp>sMIzlZ{1Zf#vcs$w>P(fs5-++{+eqWS)ozLL>u(V6UwobN z6Y~oMU-?U}nrH2wApAjI?eg+@<{jC*4O@$|7H%Gx!pHx ztoXPn!fjXECF06NiRXPI+-2795`FTI5yN~V+~USAk^R9aF;2xd$Fp5x{kOgp_w0F2 zi5Vr@Qrxq5IUuSYsv>#@M7TeM{vdWo`-qOyBi#Fjo)$08R-hah*8Gep)?lRuE_B8O6ZkM@igpZ6bXtx$11aV`EYF>UzkQ0tKz_qiG` z{I?CY;uL39bAI~={x{=g=DfK_vu^wo|Cnbgsk75}*f9G2j)k`pMe^JOhDAH8!N?af)QPk_&fjCQ?%I$q^h_8N`Anp!sMI7>VJl#)`54fLB7&6S7w0)#| zrLu1w=wsEIH`0CUhs1wWf6SWJYD6asb*BGki9+t`WZeiI;r>q5w-nDhS2#*4i^ zJ+1W5Biuo`|}`$$Dbus(Gzhqs&@l&QB`0&9h+INwU@% z_47YlOU*iLu4|s(q|U54$F%d8ns3y9bG~^mFz*-U`7-N9QfJV-cAt9ATA^|~bBn*` z`B62F{C}4wQ5;hIGAh!&y-#`HHwf=&gTLKmW;n z*}T7-=gvIu2Y(o9U5<}*e^Mh+2;ZTW|Bgs^9y>vVT^wRG0S4*FU{y{eRsT z;4An9zAExc?|pIVn__Y;z4xOFuZ!vTw$hx`+v3H{Li31QCM1ZZ3ty7XPARU71!-TB z&I+SdeO~i|bY3ZOO{5J=pgE$?4e|Y@cs=LIby0M9Jk6;&`?{F%`UK568FN!S8F_-{ zysdmw=Tl@rKRbkS+AaR5*Kx_TAhh>A6ECNNqyQ`rxNtNvR>{s)~KH~oBsJHIb-Vi zC+GUV>t4U;y8+g$8@6zR6cCWthf`dfACN4nEH z6GY(#y{si_e&0_M#nTi$tVN2i-b)ZQbN94Lsrd`rC5S9fzqaP9@lj_I#OOQStT~En z?Me`f26neTQ*+{d62!VEU98D!JYs~p_H{Sw(Z)#kx=+-#sk&HW)p)_S3F1<_PS#+> z@A4&xWve<{mYS0)JYJOO)!TZhbWSOdARg`NW!+UgFH?dT*|vifuI4}59xq})>1CZ( z;~hT4i?3Suw6-aJ|0rIpZr9$brRHSq5-%#3{MuUIBhr1WTf7)ntebVed!&18-gsfg z+RP2}Y$kPIFk@}z_CGlbn6v#}B%K#C$INll&ObRX=6SsNMH?$r<>y>=j-EVfWtDsq z>Hb!oFEdxo`R2MwU2E!0>MWR_IhdaVB=y{Fes*E9`D|`JQ=8A)>Tgq=YbJkCzt@=0 zS#fv^=MmqJ#F^uQoN4l=@W*(u4*V_!Mj^d>H}xv_V=R#-#t{4ym2ymoGuujjSDZbTjL zx)<}*_Ub8+vzC)}4jxj|$@;ffuj$@$G6MERs(8>OXevXS7 zFXl{53p!2aIAWaR2kHZfnBxfMID$EjV2&f0 z;|R{QZ;toewRk?)8{Zmv=X>LRy5a(FJ`66m(3>YS(k=4lPlRicH?J;<#ol~dKXtJ; z4=1l%?9ES%bKYV;=QHf^xr2Q^cUYIt9rWm-=#B$(?YnCm2%>m-=#B#$FrJRj!{ z%ykmXbrQ^V63lfH%ykmXbrQ^V63lfH%ykmXbrQ^V63lfH%ykmXbrQ^V63lgy#}O}{ zk8=m+Itk`F3FbNp<~j-HItk`F2{z-!jQ?*k-|sNSaRhT5!5l|0#}UkN1aln097iz6 zk;f57o{u82_Pu;{S6T!5l|0#}UkN1aln097iz65zKJ} za~ydbapd`kBbeg|<~V{mj$n=>nBxfMID)xmBBop?!CWW7TqnU?C&64N!CWW7TqnU? zC&64Nd7RH3*GY_Xodk281aqAPbDacpodk281aqAPbDacpodk281aqAPbDacpodk28 z1aqAPbDiXIK6hLvG0t@o%ykmXbrQ^V63lfH%yklM#*5jEBbeg|<~V{mj$n=>nBxfM zID$EjV2&f0nBxfMID$EjV2&f0;|S(Bf;o<0jw6`k2P!AfX=VAc<2{b1Iw=WG37)(>X=VAc@GS9MmHp?Tuos?IS5G>2sLbyit9faYXr z?CZRmNAvxmzG{Ad8ecNS*I6}%=JgYNo%e_Kqwz0#`8tcf>Pvjx&)50=aLpB7RCPYe zq}gY_X6Oe)KbZA{SwHR3qaV!r!K@$5`oXLp%=*EsAI$o}tRKw!!K@z){bdSi|5R>S z&e?OO=1iN)Ie+r_b6D2$&YwMgj-F87S;OQ1Old1Pn|tEYVrB(zye8zU=-oRQ_OTY* z2eW-J+Xu6Kn&Yt#hW*p&`;h;U!^!7sPOkE#c0uj`EGqvGF4x>$or@dUb?kaoDebKN zjphgQN;?aj(_Ab~8DiK6!#Z%RfDr*C@vqduX8HT$g641a>5 zAI$o}tRKw!!K@$5`oXLp%=*EsAI$poe61hM`oXLp%=*F5KW9P&?WO;%D$YK$HUHeS zigW!Q&0)t?oqVQwS>4LcrOx3rztwpk=cwhHZ};$VmjCP<8qb>3$2nq}=9ZT$Id5hg zLE};1S8|SCuKD!5O3vY>zoqd5iz+!!@6lX)PbKFJ$4DBV@vxFJ%`VMV%lkM_6pW;C zpDCK59}N9q)(>X=v`3GAFzW}ielY6?vwkq^2eW=K>j$%bFzW}ielYaE%rZ*rSGlo$ zzTQhW<^SH9HMdlG^=!J{??;tyS3lSMUgcr$o!UR6r&M#!X{)(bUd^x%hJ7${5B9-q zAI$c_Y#+?_!LUCzla5`bAB3~sG9BOWA;S5CzvgF|h4bXEIv=hsvYh=rc@mz-a<=#6 zPp(-GZ(iL=r5X0Yun%VYV73ot`(U?o`fTKJvu$e^O`G^dX-M z){nZ195eHcnfHY`*w?UU+J|EX_&e+D)j8kH&zWTGOrPLdXy$9dxVAxnt~2Pbe#omC z{neW{I7^O{ z)kjaQLx0u!fgVSHwYrq9jp(l)dTJ)_cVP0rV(166elY6?vwkq^2eW=K>j$%bFzW}i zem!672eW=K>j$%bF!Y}ann33i{nf1|n$cfX^Vf|2a6lo==&$O$9Z&PoUtK(*8U59W znVQjGU2d)!{ngq`n$cffJTZ>0MSm4CMl<@WGX9#;Up4w;EX_fGHFKY4^jBLaYDP~8 zhJG;ggIPbA_0t|b`oXLp%=*EsAI$o}tRKw!!K@$5`oXLp%=*F5-#l9T0sULQlbX@L zZSnXM{o7WLpV7ay^7tS9;g6oUpnv0dq4(gugJBFs?Q0Pg1#Oo^g%~@{sxOG2(b(j_K#5 zYKZBpvFB#cxj=uF@=wj^udWuJN#p3R-a9m-zuH${Gy1ET2Aa`d#aGvi{%T+;&FHUk zWYCQMYRheHAN^tf&6?3)omKx%ftrv0YCuKJ=&wrtGM&cJU;VUBGw#b^_!A8MVAc<2 z{b1G)X8mB+4`%&f)(>X=VAikaYyDu>4`%&f)(?jMR7WS#UU2VwaY{4#s~NX6qd#o@ zRx|pmNrfiUeDqg;G}Da!s>LMD=&#-$*NpzEM20CeAN|!I%`~IG8a7`u`m2?j$%bFzW}ielY6?vwkq^2eW=K z>j$%bF!YzrHjVa$+{kuD?*;wa^NE_#zwNBA8U5RrnKYw+dwxUv2mRZ)ZJN;&f?*#F z`(U;YX8T~a4`%ydwhxB=Zzt;5q0edSi7)!MLY}yze=F$82lQ_PJ$Zuu@UbU<(7$nB zp?BgKfngtOv3)Sx2eW-J+ow4m`(W5N^TDhY=D9QT#PoksXV&!L-}Q5U$a_J)G4sB- zKOFK_`w%@|d}|#q^ms|d&h!bc#UA-uFs?{tEdAMt_C81f#z~ zzJk$TA&X=VAc<2{b1G)X8mB+4`%&f z)(?h$)GX*n|3=THiqXHJ9$_5)8|oAo{Tu2R82usY8W{Z>#|ym&?;Q;LSc~n0**=)< zgV{dK@z@8$K0W)XwUEQ8J6IR}8|obx{Tu2O82uaS7a08;>KYjR8|obxJs}wO!LScz z`(U;YX8T~a4`%yd*f;%&dV#gjkh!Sofbg-yN|jBCyMlVt80XPo1LJY@cR zj5uDHWBNI%8e;lt!@}mYFKAi&N;A$!6VZakac&m&(Twwyf3jwrvnQYl0NB!tkUo-X!hCjj3 z4`%&f)(>X=VAc<2{b1G)X8mB+4`%&(zSa+B{b1G)X8mC3|9(sz+6%>Gx@Oe-ecLtT zJ`nm?Gwu&N{p!+u+&AVe(v15_oecG89QT=76E)-h^E^|18pnNU-XhJoU(GBYK;yWN z-QBJk_qWxR8_+oJd-=C&#{DoMPeU3j$%bFzW}ielY6? zvwkq^2eW=K>j$%bF!aAK&`9f7xp91!-V5qnRC>**f2k+y{h}^D&8`{sGHQ$V59;Xm zVVZHK!LSd8eK2wl_Q7l)%=W=-AI$c_u)ipsjvZ=A>xDYLsB?FGHKYC|Jkt4qx;WmG zC#aW0Jo$q<%6Ww|%`pPQKGtIUV73ot`(UBGP4 zM-4%a@m@^kePIsvHT|*nA!>809XjVxcaw^p=@VRwJ@U0+T)Saf6Ura-SDPwoMt_y+ zabp@se-#^}8U0n2rJB)S)mW$*{nhWAG^4*deN{91s|mTaP4rj6y*1j$%b+M`E5nDv8MKbZA{SwEQdgIPbA^@CYInDv8MKN$LB@@xN~e|tSmGy1pw zzi3APHb`hcqklW?@jv>*Tb{U}f8%(e_u##QVIOO;eK6Yxvwbkzr#T+`VAu~y8$|v` z4o{t<8U5SYeA@r$-x@8|jQ*`lRvkO^Z)b;TM*p_qjArzNVAu!4KA7!;**=)zsHPF`f(I37E){OpY*XVCC5jibN1(?B!s%V78u4EX=VAc<2{b1G)X8mB+ujgz1VAc<2{b1G)hW>)%+RX= zVAc<2{b1wY#+?_!E7JQ_Q9~9Iirpp`kV`kb$rpkg;<)=zXf^n0sY(iojNz@^FvSm z(C2%eyh889F#^Lr)?)i$whw0eV75IF2Tzv}&N z5sjn2s&_{-`m1plHKV_pa$Ym~tFAXSqrW=$Of&kcvRSlE^jC8&&FBv=^wEs|YS0GF z=&vsPtQq~)=Vh0W2J}~L25H9q4h;QZ=m)cYFzW}ielY6?vwkq^2eW=K>j$%bJzwhw zvwkq^2eW=K^k1*Kg7y*>?&Iv3NAry9KF-50meY8e#+9A94r$)Ay|OcQlIGK&RB>7j zHNUM@#TlMf^YGqPoUaZoqiaiyQZ;sj<`LhhIlh_~wyWYy@n$K_sZ*wk^N>sPgZq`8 z0pm1}n4%dv!O#h2onY1pW}RTx31*#O)(K{vVAcs{onY1pW}RT@ELK_jDmJdHGgmjw zJ<64HwwbB9-tuzJt6MdTyycy1j%faId3k4*IL-6Fs^F}5TJwxu6`c3?X?`y%I{U2E zoPU2s=Zq-L9jdCoM^X$8U}yld1~6*?vj#A00J8=#YXGwbFlzuqL(X(McF67WO*Nyh zYcX3h`ns7HHKVV~pGoHf`nnc1G^4NE-%~SsMKJ7xVIR!)!E7JQ_Q7l)%=W>sZ^q@% zpY>WZ>XdaZTC2IhX1y+I*WWdm{=~Jg$=8DETB9x{m8<62H_z9dMmmnweyijx+g0=H z**d1s^Y{3gIge|hfv*MQS~D(5)gsfk`_Joog+9&yqh|DJS&Hg&hd!;U(2PFqZGdL< zX)haUMxU0ere^eMn@ej(pVlm+X7p)4-_iEbXKvi08GTxMPt8Q1wyBaHN1xXDS6yS# zrxo(lUfkco*e@9R!K@$5`oXLp%=*EsAI$o}tRKw!!K`1;*ZRS%AI$o}tRD>h)sD@h z`iA>v>C>9gr=5(~j6QSzJI(0Rjuf6x^Uj$%bFzW}ielY6?L;u&=^*tTA(Iigq1$|)Y$(qpzJ`K=}KCnY(&FBM5 z-_rg;AGm+JX7rX|*ayQtnC*kvKA7!;**=)JB`NCr)9jY8GTyA3!2fVH9MyneOl=on$f4tQ{O3uX7p(lq-+ImH)8;?aj6N-~^bE3tKCS3L&A2~;p&tzWVAc<2{b1G)X8mB+4`%&f)(>X= zVAikaYyDu>4`%&f)(?jMPeSIX=VAcE#IdM+F=&x{o!04|~7r^MRaNfY^udp{T?#p2K6Ab-e)(>X= zVAc<2{b1G)X8mB+4`%&f*01Ml{b1G)X8mB+4~BlK-AX_1cc_op3;HY6P1>XCuTW3H z=&w*`!RW7W{{W-ELR|)X=VAc<2{b1s zPxVXLNB>53O)>g6)FZ5m{ta~sjQ$Pv3yl5{bq$REjq?h<6UPV)`&f(ZgV{cq?St7q z&GFa=!@ijhX00&KotY=5|C2hirVszFANxX%@m@^kePIsvMfFrMdOXxwjHAa(Dt4w% za4q)8*Me~^z8mP1Mg6{j%6G8(Z3tp~H_&9BgYOuEu_rL*m<%8A9O85RXg;(QP>lIt ze2)?gUH=bvcmMx?J>UNyIoOg&#-g%~q@p6J)cetq!Wb6G9Hb}*Ip{zVqtVeiE`%)| z8KW_CxUuCRHgoVX2V?kP*a60}j3nEd@ALe4yeu&E@XEk@%%axeg zEha7|E+#JKSZ5W}T~utmV{Kvg&9SkM)xqo4f6MA_wfdg1?p$NfSa-3pXRJHg*fZAM zZR{EAPB-?9b=Mnv#<~NJJ!9Ps$DXn7jAPGOcgeA5tUKn|GuGX6>>1m*-FU3htY2xy zX~t>BX~t>BX~t>BX~t>BX~t>BX~s0KH&6Xmz}Uyt81owf*fZ8|3t-P!zd3+CWBnEZ z_Kfu#1=uszZx>+CSifn2J!AdW!Bl_e@i!2#XRO~wz@D*wGXZbt{;t@GGtmu$_i4t94^9nW9vv)J9q%5mlHV=A{l#LBVzn`8ae-Ug5LSG-<) zcdpg9mva{z+vB;TjqUy1-NyEW?sQ}CLf!So_K@y?V|zrS_R*^9dCjqOq00mt^P?uKJ~T6em!z3zH*O-$_;6BiQ~6BiSUS#CF;@9uPK*Iv|J zZ)^|j4mh@VbvGQ_)4DT0)>-YP*ISFk)NV0xF>x_*F~>TqnC=E*`$McP>~7$atK*I# zwzt9REZH-+I@lda_3huV`q({6Y`^D@B(~pkcM{tZVxPt8t#<9@+{wlEa_;J4dpUP_ zvAvwTyQ!Ryt(Xmz(*eS0l; zuCcwAyV%%X%N=cOujTGGw%2l}8{2ES>y7QT+yTe-TJDBpdo6dyvAveN>MhUdwM3V0$gUU4ZSi{H6i6*YaBjQ~jOC-$20jT7DY=+iUsF z1Z=P6w-m6w)_P-x=CO}!nsJ(OnsJ(OnsJ(OnsJ(^`jcjyW}If6W=yj?gV>%B>kD?T z5Zmv$Gl=c?+$F^JgxF`X`ndX7eRmkK=PdTwC3{{}2fI6|jy)mvS?um)<+yV9F_qgB zV&&M~%(4DzPl(6*D_$?YJJ;&lYq^V!?X}#|#`aq7Zex2bce=5?mb>2AUdtVDY_H{R zIJVbvXMC!^VZ2L@?X}!7$M#z8o@0A0cha%F)_Q%US-;YZ(~Q%M(~Q%M(~Q%M(>&Fm zG~+bmG~+a5nwL3Wdg0Ese%Wiei;eBI+|kDNTJCO-eP8Xh-08;lTJCydd##_Y?to)^ zEqBAQy_P%U*j~$Ba%`{Vjybm1a`znDYq^t-?X@-@pZa2~(u~uL(~Q%M?GI_jX~t>B zX~t>BX~t>BX~t>BG_N;*-RagZdpUQ#vAvu-;MiWy-EeF#=gv5`ms@YHiK*RU;$q@r z;$mVk%k9SV-JNdj+RM4?jqT;!0mt@o?uKJ~Id{g#I;*|hdTWuG+ASt7CN3r}=2&MH zli%2$5Niw5z2xdxo3OnNR%gkcxz)keO7-mtvHI9riS75Sq1b-UT8!-pvCm@larLqK z>&5r(SR8vfea7~3a)IsT#X*2>*Y#J?G_Uk6BiQ~bF8z9=~;s939+`Yzo}q*!tw7bt2%hS z`qo7C?X|3x*j~#TitV+mt=L}6-?Xs3mbDn$YgwbQy_U5b+iO|VvAveH9@}eq24H(F z&jxI-<(Yx)wHmh@k5!uWJ&FmG~+bmG~+a5 znwL3Wdg0EsewjD!Vq^2k9c^r$xw}2~eYMweryHA>?s{YM)g5qb9=jWk&2M+cv3c(< zIkq0SV~(v8?w(`o$LXs(#n>F(czo)Mu}U*eGfp#3GqyjZ8K)Vi8K)Vi8K)Vi8K)Vi z8IPLRnZNFI>zC)JyWZGy)g5r`dFyUC_8fMn8+(?nH`m0}ZZUB&aWQc*v6$s{}>bE`A*>Tag`_JrYRg{E9a1sv<=idB_Hyo=VtYAvQL(+;dVLpDTgAl1#KpwL#A23{Wv;Nhx7xLr zb0-(u%ekwI?d9Cz#rAUU_KtN{d%5*;C8lsiwcNSJ_FC>@V|y)kw6VRGyW7}a%bjj)ujQ^cw%2k89NTNT8;cI zt$?wQt1;#`1hBo9-xk33T7Gi?+iUqP0&K74Hwv)5mftSG_F8_^0NZQ%t%Irl&f{+& zV0$gUjeza7{AL2S*YaBm*j{VBF+=m%$2HA3%{a|C%{a|C%{a|C%~SnJGfp#3Gfp$6 z*_}abPl)veyH|+q_uLu8_IvIUVtYdDvsisxeXPDajM#G)`|OfEFRFvxom9u35c@24 zcd~L^x%-&P?Fq4R>~7{*f3+vXWBnDc7vG(0_3gFX#m4qp?r39sEqAxEy_P%O*j~$B zZ)~sS4mh^gayJ~?Yq>K%)!#7QCCBz!?wDhHEqBkcy_P%a*j{VBKGLjTX~t>BX~t>B zX~t>BX~t=u>Q9<+nsJ(Onla7GoG-m_=UTt)wcN$V_FC>}V|y)kx5vJ(_FC?AV|y)k zy|KNPJK)$}%iVBnujS4-w%2l(9NTNTV~*{$+&#zkTJEG{d##Pfr@k1gG~+bmG~+a5 z`$L*>nsJ(OnsJ(OnsJ(OnsJ)(sCk|F>rS_R*~_`>jqT;!0mt@o?uKJ~Id{6Tz1(_p zO-$_;6BiQ~6BiSUS#CF;@9tb{*Iv$DZ)`8;4mh@#b2l8@%egZ?)>-Z4)?16j)NV0x zF>x_*F~>TqnC|ppdqS)&eCO4D$t73E{ZQOpLUpkFhS;4!cL}k(gzgw(_iC}vV)b$L zvHI?8VtYvJv)KJg?2e?nli1x!cPgOW9$AecK6o3VC+t= z`@+~=UH6EwJG|}}V|RPk%cpi}t6f~XxOQ>v;@ZWvi)$Ba*IifKy=;20yRO(?6sv>R ztM9J2`tDG>1CHITb~hZmbM4MJb{E@Sa_o+_JLcHkZFkSHJKgT2V|TsXRmbjtyTgv% z4R^O4yEDGtn5T{YwBfYjwBfYjwBfYjwBfYjwBfX2+SZ%zesh3+f2a0a1lXRdqjxw{+iAU$A?H*uK%7 zL2TdXE+MwJ#6FAF$JNK`yTgb*ud&ZA*>k5l*xgBW>@Bg+Vs|Gi$CbN}sodTYE646; zj`df2OFY(J@p|#yxmMqv&0TD4&*qLcwr6v98{4zF(~a%f-1WxxZ0>+#dp38&u|1nR z<5T?&<6UxW&*qLfwr6wq9NV+GlaB4#*6Sn9`juv!W}If6W}If6W}If6=BfUq8K)Vi z8K)W3yv+I13wN&d%bv|$Y;4cwjyASub9Z~}`)beTPB*q^bJrW&v$+F~?b+N7$M$UQ zjAMH?cge9mn>*&%p3U8JY|rLSI<{xqczo)Mu}U*eGfp#3Gq%s98K)Vi8K)Vi8K)Vi z8K)Vi8Pjae;*IC8JKg$aPw1{UwkLE49NQDR8;

-5JOBgzL>UF|}1pTufX{Tudxx zx!riayVI>*dqQ`;u|44v*8H+3bT?eNJ)t|}W1ZEWaJ{uiOzjpE7ZVo~7jvw$is^13 zwztIE!tMqxxjOC`V(-wfI!pF$r#jdjN%id&vHI9OO6it$<+lj1y_Vl7!1h{xy8zp3`Aq|CujRK6 zrusXNzkz`5wfr^$w%78T3D{oCZz*7Vt@XwX&0`RVf}=PVXy$(|S0!N#aM z_Jr7Hv9+UeT)DZb+@26C$K&@jaaMamJl0?Fdhv}paqP8>MQpESjADB&V;9?N8PnKa z%UH+uTIK+@*D^P-y_PvM)!#7QCCBz!<`}luGWW2(mN|*-wbtt+&H9yQoMxP6oMxP6 zoMxP6oaU+iq#36frx~Xi)4a_2(u?ss$*N!WTE?P2+G`o3*j~%n9s9o8Yq`^n?X`?` zY_DYwV0$fd1KVqvGuU3sT*CHR<`}luGWW2(mhWuXUTfp=sV~MV%{a|C%{a~2{*Y#z zW}If6W}If6W}If6W}IeB^Lq2woo@ZIm-EcS_Hv$u*j~;v65Gppc4B+E_2!zG+ASt7 zCN3r}CKj{YZam-Z6|`$FXAgnxfWu*z-toO?Xzyy1h_P3_+1Y3B`hxq8y`moGnWxcV=48|ysz)#nY5`NHlaA9dMz!>ez( z=P$5-+q%Bs`hx2Vt}nR0;QE5=3$8D?zTokFW<0Hjy!JUAN}C;;hB3sZ{+9v=jp@8Hh<2@N8NP#aP0S< zHS(EvI%9ajKR#pRT^@MG@bDXs{smrY#%acB#%acB#%acB#%acB#%acB#%acB#`oX# z!r}ky{oGOW=XbbpIP277NB;JmFB~p<@9`u5>?aotfBA{$kG%P(FBrak)eA;`!X+0B zXB|A{_Qb<47&d>+l=EG-zF;`${K<<8{^9)LPwzQ-^xpH%pS_Eh8gLqL8gLqL8gLqL z8gLqL8t}OvzF_#bJ3n>Qzw2s$_-~gzZR8zqbK&r`M^4^-a+?c>Pi;GS`pTVFzcF>o z$!oc~@yExE_2XqsTufX{TufX{yc{#lM{7&Gtb>>1zZ|L`FYDlRs|utrg`> zozMN!1;YdX;Rze?|D16CaL^YH8Tl@ooIm`@n;=a-XH4&*DCd`z-FW z_~_L;uIBp%Z+hK4macuu>*g``=51a#kG+qq-qSWFH~+Is=CQiX>6gr7_<=`XGLP+t z9kQywHs-(g@Jr^o5bI+aa2jwLa2jwLa2jwLa2jwLuyz|`=RA7#n|o_x?~ubUnaAW0 zPrPIvtJl8jl6efj;;&Y`Hn!tsOk7M{Ok7M{O#HMxYhG{)i7>F>L?chmCy3 z*RB|j`NqRXzU%j|7#{Y+-x~RCtG_j@J~x;D^6rPs^}qX&$Brz{>U7h{;-9qX<9~sd z?c&Y(ZQ_@%F0K0NF>({uB`K7ILcz`4`& zbcgp{J{Nrrc$(%jWeVUh2W=!Rf*2!Rf*2!Rf*2!Rf*2!OQvE8e$!b zmvwOSRGnCP;}ien4wnvZe9SbS4?X#H!&a9}Yj1UYwmP^vc$t$}`EpH*l`nmK)XLMH zemp$~cf9WM;ji8?Ju6>*=PQO!UGS7~d|v(ND~3P)<0p>1-drxGz7!J|6BiQ~6ED}F zE6-oems6&BdgSk2F`WIiUz{WKH+Pnw#eEj{S^W0T?KSV`U%12S7lzjM^S`_LzR`aE zuUGF2+Ry*zxvSqHUE9z9&adn<@8`GrqkZQ6{2n`RnD_G^{PPX-e*UYgubl1YZ+!DG z@8>^%+kNN#{3TD`cizw6>~;Ij`}v1{WZ!u|f9T)uJMZV?WnXZ8!Sw~#7hGR(eZlnw z*B4x0aDBn`1=kl`UvPcF^#%X;2Ufqcwzi-Dt=)E;_w&d7>HX*Z{8sn9|Gc07ecb)h1 ze|XKV^M3x{H@V-upO2TCahh?Oahh?Oahh?Oahh?Oahh?Oahh?O@xA_S|KYFy=g@IJ z?s<;`hHGvyJzLLz$N|G%J3L`5-|Ddk439tJNh6=~&;y1~y!P;s@3h?k!yX?xV&t!X zZ~x&Ve>?4y&w1Vc!^u}1HI^T-*Z#x%_kQ}wyM1i+`xh5Z>%(t7bid((S3GkpkC%FI zdT@GhdT@GhdT@GhdT@GhdPZKobNtrc)APlBy087u^qs}``A?oQJzsp!|H5BP&llhS zA8_gPeDPl3qUW}_HSI}S zThx!~>9e@c;y#O;FFw0mW8-BVyj%y$v(LuMI{3Lq?K!;s)&H`OI(NHn&*6*zIq{7z z*lT#$Ex$FEKkCPO4Uhcjw@1GGSq~b{x%YQRe)ne{G~8#KYe)XTJ@+1-dck!gKjZ0p z57#~IMNlY8I_;AW*nOAbri&;3$eVT^ zUiS8hciU>`;r7p(_$?RRclh(ao<6(H7WWh}I``=;IbND-U8vf4>`;2_(>fPNtKK-DPy))eIHGBR7FZ+V)3$8D?zTokFkFH+1>u_RwH{i`0PxIT&>E6;cAZ)8_~?S_4@zp34B%bP~7j?Y#HR|os8 z!sfzFmz+4yksqIQ;yib5zt4&DoVxk7&!6YoUC)00JO>|m=jYFJ^QzaJFwfav+x&!i zE?@MrBX~t>BX~t>BX~t>BX~t>BX~uqAwROyI zuC~7UE!NgOztP%y=(k&2C;k3v>*uzgJ#JoC<7IqYd|Z57d|dpo&RTrzw^dum{N`%w zo8Mw>-SZo*t%rWQwRO_(ueN>~^Q|HAGCnRoEBoLww>8J_ z=(ZMB$7id9tAq1PoLKpCyv53!?|3ti@W}Z)`^CpUb^b2D^-rHVf5(5&8Bd$P z`~P%{qvm%4N51Z;`CY+3$8D?zTokFn{nvBncLo3Q z;^)rq5N>t-bLMvohdt{#^LM&(f1FZzmI?7+{5SZ=_l@U`278S-&-6$f3N?-*PlFp-+$2OpFF<@_~n#tT-y7U#-^1tk3Gq@7P7h8GP7h8GP7h8GP7h8GP7ihms_*0OM)f`2ovFUR zyGzygdUve)zVDt??*ZJY?EOHzjE{?ti;s(si$B&`i;tJ%zqxF^ikEfpa=qH+wnxn0 z!QXw@Q|9mH!Zt5%c?pyMOt}`Mt!` z-}=<~eMR-fss0#qtv;?kKJMFR&CmUh?R56Mhk4+!XU}_^fBLht=RMCafA{QpFSO;> z=gfPgKREcDdGGYxXPh(dsowI^bLPF)yH~%n*Z2Adt+?;?2fpN-dC&IiN1rqAf>@^MC%D)8_927rx}Q`8&eL_c?9;?(n!xPMg0| z{PX8doxf{*^-oTnzk@vUyi@1zCP%&a)cHHhV^2JF{w@kFnuO3 zPG_ZXXQgmwrEq7ZaA&1(XQgmwrEq7ZaA&1(XQgmwrEq7Z@Uk!QQZr67PBTt3PBTt3 zPBTt3PBTt3PBTt3PBUKSyfc3K(iuP889&?^KinBV+!;UI89&?^KinBV+!;UI89&?^ zKinBV+!;T--khy3`c+?WeZlnw*B4x0aDBn`1=kl`UvPcF^##`#Twic~!JV_xugNcii9H zaet#<^76B|&*DCdJ4@iRoh87XCBU5}z?~()oljWuGA1r2E+#G}E++0w#gfJEOoj4T z`BH!9Qj~Wt1$Qn5cP<5YE(Lck1$Qn5cP<5YE(ND^$+V>hrw6A8rw6A8rw6A8rw6A8 zrw4b|g`QY>XIgM)T5xAtmUVo#I=DKxb2xF&+0NmJQ=KKN-x)dF89Ce;IougJoc<** zW8z}sV&Y=rV&dhP>CEBS?%KIW+?hk%nM2%}L)@7|+?hk%nL}Jomb}z}(=h5>(}2@} z(}2@}(}2@}(}44xhR(L(&bHysw&BjU;m)?<&bHysw&BjU;m)?<&bHysw&BjU;q}(5 zG}E7EoMxP6oMxP6oMxP6oMxP6oMxP6oMyaShdV#1FP)#nou9;=pRC;Z$?7{li90`u z*IP?#mxkKKwTo*P*KXz7t-f|~?c&Y}(9qd{B`@pX&LODN*@Go7>nuO3PG@^?XM1pG zdvIraaA$jPXM1pGdvIraaA$jPXM1pGdvIra@Uk!QQZr67PBTt3PBTt3PBTt3PBTt3 zPBTt3PBZST2>qQE!JQSsoh@1N^0T5- z{0y!>UiPbVP0Bmhgge)SJJ*Ce*MvLQgge)SJJ*Ce*M#filIc$mP7h8GP7h8GP7h8G zP7h8GPS40|=Z@&<92D*x6z&|{;QE5= z3$8D?zTokFth}=gxU&tovkl8SK3g4J9o%`0*xyo@ zEKYTB=RMTvjK`9fbvD+}`5E;)KZ83zgFBytJ3oV$?Z(UaxcIpExcFn8wevZ+__#AI z+UnfPl9zRstWIa8aA&1(XQgmwrEq7ZaA&1(XQgmwrEq7ZaA&1(XQgmwrEq7ZaA&1( zJ}!CL7hGR(eZlnw*B4x0aDBn`1=kl`UvPcF^##`#Twic~!OOANnLz#OOd#$|Anr^c z?o1%=Od#$|Anr^c?o1%=Od#$|Anr^cUT^%Qnf^56G~+bmG~+bmG~+bmG~+bmG~+bm zG~>=+(ck$o-1#xw`7zx2G2Hnv+#0pyWqe$GTzp)7Tzp)7+<6A^JI}D>WgXmE2z5Fm zvE*f)EGS748fb?hF;~3>EGS748fb?hF;~3>EGS748fb?hF;~3>EGS6<+o+ zUiJmo7hGR(eZlnw*B4x0aDBn`1=kl`UvPcF^##`#Twic!V3w?poqHlGW+# z4esm>?(EI7j?Y#HR|lsDcisti-U)Z!33uLUth09B39qNK`1BMX7atcN7k{j?79ZDN zZFSxWcisti-U)Z!33uKJuQ#WPudU+a;^X4u;^X4u4xU+V+vv#<% zcDS>4xU+V+vv#<%cDS>4xU+V+vv#<%c6hyUQeX6|zTokF4R;Q0th06w4Y!sqc^MxU9~U1N9~XbDvlbtB z9z*=jU@UoA2Y22>oz8eHd0A)qS#>(|gFEwsJM)7(^MgC{gFEwsJM)7(^MgC{gFEws zJM)7(^MgC{gFEwsH}0c*8Oy%l`hx2Vt}nR0;QE5=3$8D?zTokF!J?yM2+tP$?45$>!JUTTY%8gLqL8gLqL8gLqL z8gLqL8t^hFo&BS&vwyg=f4H-MxU+w_vwyg=f4H-MxU+w_vwyg=f4H-Mc)j_UX8O~N z(~Q%M(~Q%M(~Q%M(~Q%M(~Q%M(~Nie{MqC0cm4GCJFI>me&V-We(&Lw4^8~3UGF`- z;LQ{N#V58OzIf)uXFq5A;flj2-g@iphhN@x;;(<@Uc)K>bJiI1Q*XJ~aN$QMe$x5( z8oqPh#3!6~uVLTE{=EFr+x)!#N5A{~<7dU$(Gp{-s~o@1*JDlGRt9k2oK3KH_}D z`H1ro=OfNXoR5{uPxa*u=OfNXoR2skaX#XF#QBKx5$7Y$N1Ts1A8|h7e8l;P^RaS1 zR-cbJA8|h7e8l;P^AXek%{RPg9OuX0@xbARKb-jPuRmZo^Cc7SzuN)BiI13gr%&xa z>~Y(PfA+lnhfn;~$>V2VvF-lDWlx^?G5@&VaOMp!9Lx8A+kV4UXHERM3-=p-=Pna} z=ZyV^Uw+d`V;$u??K!dfzw)^kjOF5d_xTfx|GW2?Si8eNpE%Z`=RWV6n9i#&o|yj6 zoink1RsO-#4xH;>`kx2Rao+X#2hZ`p@#hbo+kM2X51RFy^N@pPotM7wpjrQBuRdt* z*A15+H1}6|c~HOnh*RFgFQ3{i&-9dkI`f78rC*qj`nY8EmFFYQN1Ts1A8|h7e8l;P z^AYD`<$SC@A8|h7e8l;P^AYDG&PSY&I3IC7;(WyUi1QKWBhE*hk2oJI=VSHxi1QKW zBhE*hk2oLk(nsq_{#s}9-TKpbur4)DtXGX6>saH;`qp@}PB!nXlg&HpWb;mW^G^Nd zojA=q@tb$rZQjw-yrZ-EMSt^7zbd!RRNwkj9P3i?tyi^c9ZQe(EuG`@Yi-@IPS!8$ zWc^iM9@H;C;*>Y>%cpkBGd<;>&U{&}lls+M+nAeo`N->h#QBKx5$7Y$N1Ts1A8|fb z-n`34<@t#75$7Y$N1Ts1A8|h7e8l;P^AYDG&PSY&I3IC7;(V;Ud6$pM^AYDG&PSY& zI3F?n&wl+=#%G81Rxf6`eK>sRI0nd)1Aiep_W{SB z59*g6amt(c9)t!!<*gAH~{U^4*{pf%HXpCvy zyXD6xwoX3j!ilYu?|IzM%RhSepVxoTwXYvPE6y7~FtPa0ef7lJ{mh9I)AP4anwZYp zJ#u3DfAwJ#>sRI0nd)1Aiep_WzV)hhtz+r2zNOQ;mwxMH{jyHhU*+XN{qiGDc@w{U zYPUSoQ~v497y6feVLs~PlGRt9k2oK3KH_}D`H1ro=OfNXoR5{uPxa*u=OfNXoR2sk zaX#XF#QBKx5$7Y$N1Ts1A8|h7e8l;P^RaS1R-cbJA8|h7e8l;P^AXd3^cP+;j&tkD zai5vkI`h73Cbs^({i=zrOLsVHV(Zmco-(m@?7;g?Y<+v*O|KqfS|>m8w-Z|@f8&CQ zt&=Z4^ylU0Zu|54H~aUC$Ips$%=;%6f47S#*6zj6pO~I=pExm{pMS)}^nd*!6YE#y z)|u*Ce~M#WD!%oqcCBOSvA(6#I+=d!Wc{*E)?el2LH+V0PI(i*d}_Bm(^LNG%oqBX zeqlc9>K31QPI3IC7;(WyUi1QIIeYBqBuXQHhtv`(i>r&&yde!)` zjy0~VZ;dzWWaH2}+4!_hHg1(Sp4D%hi_`cQzj>kE<_kT|BRZR3^f&MHt8(j1^{qd} zu`U(gdR4pDvGiEq(rKMczjd;HStskS^75d5`4OkQiC;doTb}7D|8(Zda-Gz#=Gw;G zyvs*k=OfNXoR2skaX#XF#QBKxvGV3!J}S>goR2skaX#XF#QBKx5$7Y$N1Ts1A8|h7 ze8l;P^AYD`<;}Z%RGyDGA8|h7e8l;P>F>R?^`!UJ)|uX8TYq}LZC&cUxAm&`;nuO< zlUv_zav;D`#Xa2-p{MwdwX&EJA(NA9YMSO9f6+yjzDLBFQC7_Bj{J< z)|u*Ce~M#WD!%oqcCBOSvA(6#I+=d!Wc{*E)?el2LH+V0PI(i*d}_Bm(^LNG%oqBX ze)YEleOz*XN61HB=OfNXoR2skaX#XF#QBKxvGV?okdMmq5$7Y$N1Ts1A8|h7e8l;P z^AYDG&PSY&I3IC7;(WyUSb2X($VcV*i1QKWBhE*hkC=XQ+rPhKJu&C8b;jJr)*o{l zTbImjY`rqKv31Pc#@07;8(a6xZET&?2DVOWqjGIjUmI8)ZD8^Jhn4w%SY2&kF|>ij z)&|yQ<+N0v#^TUke0{22eNB%Xq*HFvFK6{jF6*!I@}PeC5vRO~Up|$UXLZZJ82KXh z(l5+M?Jrq<<@t#75$7Y$N1Ts1A8|h7e8l-!xi+e=4V;fSA8|h7e8l;P^AYDG&PSY& zI3IC7;(WyUi1QKWBhJUlwNZU-;C#gSi1QKWBhE)m|7MqLF^*5`$!}aVv32I1CroVp zx$=OCtxHe6`NY<%>)&yQ@w3*kk3VK&>)X4oz5Q5j-TT5R6I&-wzum;v$=xsAe5|AV zu$?DXfB%o&ZY&q)PRC3v{+qX&Si8^q@@8WldJem4VmiNb&cyWJ^sMPGjoR2skaX#XF#QBKx5$7Y$$I9iW`tpYJ5$7Y$N1Ts1A8|h7e8l;P^AYDG&PSY& zI3IC7;(WyUSUDf7&qth(I3IC7;(WyUh?hQEPx99~lke7_#)EaKabmq{{8+~tSJt=2 zn{~2rXq{|)S|=N~${Ww>H_pXr{EOeb7}w{uc}Gw4h|cC0{mnc5s@ytLed|y2&bm~5 z>s9Sq$I@ecOQ&@*{np9)Wu2_Q%FBcL``KUY}aX#XF#QBKx5$7Y$N1Ts1A8|h7e8l;P^AYDG z&PSY&l{fG5QF%V%e8l;P^AYDGroX=j=~sUz(%=4mBoF;vNq+i!lf3nJDEaK~Q}W#3 zt>nMIXYs4QbMdRce<|hYetA6pT{wgmI>X#pJ%A5G*Q@iDvp7Kv;zHIDQf3wraCHMEc zeB^aL;(WyUi1QKWBhE*hk2oJI@9%f{s5~EWKH_}D`H1ro=OfNXoR2skaX#XF#QBKx z5$7Y$N1Tt9_xHPeRGyDGA8|h7e8l;P>Gw?aJ!ssktoBCO^W8HTd+vLtV*3HlRBWH% znTqWnJX5iKg=Z?ZKk-b(_9xoF_9xn?TpQKb1{OyfSbYCsW&R&lR~uLiZD6srfwfsV zE!C&7IJ6gEpK4cM(<2Azl$-S1pVTk8tiQ_3gZkx1obo1q`BYY()h+*Gh@~%LFa5%N z)c%sySDueJA8|h7e8l;P^AYDG&PSY&m20E=+Q9jU^AYDG&PSY&I3IC7;(WyUi1QKW zBhE*hk2oK3KH_|=TpQKb2F^#Ek2oK3KH_}DOCPN#`D>lYck55%!MfBqv0gQPtYg|R zHmq;jz}CISp>?wHX`O7`DsMci-#8bi@h^V!Lc7fudYVUcHoxd^-sxB6)|u*Ce~M#W zD*m`$t<87qSbD5)>9p>p-#S^ptdsRud3jL3{D@QD#4n%PEzk6ne>(GJxlZa=b8Ta8 z-sK~&^AYDG&PSY&I3IC7;(WyUSb6g1L&PSY&I3IC7;(WyUi1QKWBhE*hk2oK3 zKH_}D`H1te^5$JWD$hrpk2oK3KH_}D^lPK%g0`_Sr41~X+Q7!3Hn2IN4Q$M60~^cQ zz{a>Xu(2<9*qo5l%H_KHJiy}c28+)#tX*DWdU%ZKG$t_p#soGeDmN#pFPFtJCyH-Q z)UG*^9&;j{=0y69@%m*R)L-T0LH+V0PI(i*d}_Bm(^LNG%oqBXeqlc9>K31QPI3IC7;(WyUi1QKC-?=0G>O7MEc1}qiI=>`8ookY}&O6Cx=b+@d^HKcj z+!Vh$PsOj!St;-QmHM5_5~uT8;&+ZqyPfZ%r*mI)b{>rW&WY()<@#HFc_@zj6kpzI zS3c7t&*|h>`uSDA_*H+Emk0IBk2vK`{PL;Y@=QgoR2skaX#XF#Ppy3mj93J_hiC=o`gNHl6 zbmCKPdhoEvJtqG0OAi{J{hn>d&%WW>)fwOiOnlnG2M>36(>7!I)n^?%ym#}7ANtON zhbvB4{pQZ9tsi{w;IZA)Z+GF?u5zqgeXPDXSRC=O_}azVr3cePC#I8rOuv3%{aR`` z`D@?akRGfK4NE=c=Sknb_b=p1x%%=Jt5eLApSIoHR;)g*t;%V@UML^Kf3$9W-l&!lg2mR*H_0w4&wY$_`uGBAw;*?wQ z%ei**f}T90GwmL65SM52jhxqEt_8iyA%B>I8x2|GwthZQv>oC@? z^% z!`k&+!}NHrVLJ1L{^j`0U;WK@d1ySyPvb=18b9*cxRU3_8^83+ILR-}Fa4@qzp(oH zg~ib?EWUnW?dlh%N53$g`i1GQU+u4yTmP%?xlkO>i{g8Z)UM}CdOUa1>3Nj?o?qg7 ze$`*)C6}Un|JL!cv>HEeZ=(<*GF6*aec(~5!XjtA8~!G zyfIuKmDfjHA8~!e^%2)cTpw|J4{T4;T(ehcuGzyh*X(VYYxX?NHG83S+9NgB+Ea;d zPt{yg-dt0^xh76?O?+dc0DzA^YKH~a_>m#m@xISXviJOnU6F2XCmulYmF4esAow#}DJ8|>Qcj9#V zPTain9oPO}TfX}?@02(1)NkI2)4UVEd8ggx9X-uEI-7U&H}CW-A2;T__HLjt;5%_+ z!*^o+HBP)^Xe@d6&=~VhqOs>)MPt%C4E^<4?=~94${XA2H|E7@E{NY8(Qb2xp5_#t zJ=f^(d8dz+%R}|$r#SLfeEFY>%cpkBGd<;> z&U~T2=R*B5e)Kor<)QH)KaCT4Yy8M(<4T?zZ}Q(b%rEiz)wosOcvio0E>7cLeEsrS z?dlh%r+GwY^NW6C!2sUvIa@Uxya zvbOGU(^1oBSI^dG{^8R{*48&4{mhZ&aN9c{GnYTR&r?Wc}Lbp%cq(<#JwqUKEE%#phk^@-#iX zPN%V*eq+9VDX+ikmj`jmkND+HyXBLf@=Ry>r$1koe#QPhuO;WB@_fYki1QKWBhE)` z%+QbX5$9v&@=$&G!TE^u5$7Y$N1Ts1A8|h7e8l;P^AYDG&PSY&I3IC7;(V-}kJT>^ z`KUY}aX#XF#QBKx5$o6E-!uKY_WJwgO{Rb6P9Ao=ZescQ%VU2y{@Zr)_NEt2|1O?< z-sz?r#&UT+>D$x4oyV{3?>_yTdi>h#AvYW60>6H9v+3WLSAN##Hkszms{YN+p8h?0 zaUQ?j^zYP*zv(5vG}h7XhrjyEBh&NVZ%+TNJ)J+h^0s3+{ny-ivyt`d8Ng2W0 z;$q_3!fC*1!)eC#1=q*Q^}YIXg3A>yhq&D0a*p!?=Mm03oToUiabo~CHgIDGH)BUg_nNeJAY%RdE9>R*7q6NXMgV{6N~w= zeeOG!YwH91?>sUMC!V&;$h2*D2=0VC_<>U;lOe!>^`nCpM< z{JlmN=fEBJ9$EbBFW+Zm?Y{M!8%Cz*_1_vsrt`ahyzj{R_?ElvH?n>ma^S=~t(@1@ zHwKDhY!u&^sa<0!J;r1@jmh*Ill4n^{Z+p_h*N&VFK^l{pY)VxI?F%(`LgsY&Qm_- zwfZ<8aX#XF#QBKx5gV)Y<9x*VSh+k@Uw&{t;(WyUi1QKWBhE*hk2oK3KH_}D`H1ro z=OfNXoR2skE9YbN%R@dY&qth(I3IC7;(Ww@i{^Q6zj}OT`7N3c{O`nP-tfX4(Bl|6yt53XUWWPnT!;K#q*>BOD_fH=k*>BNoxa%iI_S-V|J^NE5`~8_e z+48e<`F59oey)G#+kI(daXxm?S4JM=@A8i$YxlM9`o_rgoc8{I8kx>5H%$MYEd8&! z_rH$i`t`3boY-#%Rqi)us_(aYisLtYito35c35lIZ~mmmZvmzA>eX*{rQdG{)i34s zSN-xJPWc(*ujNg<<&&QBOlSG0KVO!9#eA#|?z6ax44|+yuf*c^A6`J&THHlz>N*un8A%DY)q!pm`s0TQk}+X^?6qu-r>ePZZ6>F z2yX7+<`iD~g-`nSi^gY!I@@gi;*ov!8>dYy=Di;LyJNYwwt3h~MyBBl=e%@eeLUl5 zr%az+_3^sjdfCYO^41+*KC(Xk=4PkP<=_2}iRI*vKY7|%F3#uv;PjEj-|;bLjI7;T zT|Y5BFFWbXv7F8~esN;@&)DMk$8!C8{B{%bv~pfo-xw&4u~B?urgn{`^ca)rG$zw; zOx7>u^;iA!AWr!azr1O;e9}{%=`8>B=gZQsn5WgjeHIrJ*A`9#P8&`$t}nPgR<7^W zmlIsBa5==~7MF9J7dVe_-r+pOd5s$bxUqp7Gq|yY8)Mj*On+mta^6*+cet^Q8}qoi zfSV(@xr3WicU)XUJQhogwde=L~u4xijRg^Uj2~{yQt) zb3u8}3-x=Bh|}|BjKB8W(QeNpdU{UL+4GD3o@@Hm^Uj(1%AFOjzBBg4arVCW&gA#J zb5=h+&hV$x+5Yr9^IyM|*I)I^gE-}9jNd+C)o%Hur##bH{^`$`rC%{mtAqP2E+*DT zZQ(TFwBa=4`hx3Yz|=KhqcxEOhfB7ZLR0} z*gCI|t^fMib3u8}3-x=Bh|}{${GL17?Ri8`&nY^4e$n4^O}~2H@w9SYSKk;YjTYjTzin!i_Q9*u#y< z%6r~5hLtzAabq4g7jSa~H+OJz3NQWg_sE`i{ubN1>Tk5IxBhn9I_z({t79o%PeF>!6-G~l%1G~@b$>tp3T@5+hta)rnEEAMc*#pN951)F<_K=?;N}!w`sExz&pYP> zT34MLXuWlwpmo?egVtx~4|?7?m(Y6dyh7`|a}2Hj&NuX2P~P)G{hlM@^n4lPuRZUy z+w+K?o>O%8{Gz|-ntt`Xb3UMQ=LV|pJV9}sGbq0E2R-kcOGuCN3h8u?A^pxb)Gy`r zSN-xJPWc(*uRZUyTR!P2&vcf5`txP!SIpDu;696siE9g|0jCY88P^wFA1m*9S5B0d zD_jn7xy9ui=LOCqoOd`+abDxb0B&sH#td#O;l>zl?BT{_)BUg_nNeo_FfBuKH~2t(dLD+G>5Kp>>AmUmtreDDQcpe$NqcdcKI? zb4R;9kLc++MQ6`1`g^YFSI;}1R?h3{8w15LHi~b|)UL6V9%C$>#$@`9$@-HHPk-MXhT}hc*jWCdmu@jU=6=63@+Q09ak%WBPaOGM zpSa_2kMo{9@_P^7a=8DYM~wWAKiYEmwPU99W1D<+%i)Lbn$C><*Y~%a&r>P?%@<8) z!_?pABhz^>aW?(ZbnZ+1t*$(2ZuiRDOn>j7=X?J({f&dpPaQM;U4#B#eZ=&44gI>| zwG;p412&(_&v@$X=K2r2Y_mDet^fVDL-FtV+qa$D{p~MoI_vqJlQ*4p-g>`HXZ@Ss zchk9F%ImNC7RXB_?34&U2;B-_4Hnh+D?n7?e&_3#RSKYXw{ndZ`^NkzYcYWlB8&}$=znd#>pQe8MH*wn6 zjq%s^nc8h1NKgAiI@>qW-+ofR+GpPBzkfKFKmP7Noa^uO+y6Po`TT2sFvtJNkFVR% zKJz8dzi!s^_${xSb)Nj?|Csf^@o)ZP?w9iVtA2S9r~HiZ*Y=s(EuZw1XFAJ2{rR%= zD_;7D^AYDG&PSY&I3IC7;(WyUi1V@X_MG{sJRfmB;(WyUi1QKWBhE*hk2oK3KH_}D z`H1ro=OfNXoR5{a=gddt`H1ro=OfNXoR2skv41DBdAIq?ww}L7T>Jg4=kFJr9J{onogUFSHDdiGuC`2Td*yUyS5 z-uQpFn)ST$PqvzM{`z@a&HDE^b*s5w%A0rUH}Ax0-i`6s=ACw%cl0#x=xpB6-@IG; z6)%0n`H1ro=OfNXoR2skaX#XF#Q9ix^DZBi=OfNXoR2skaX#XF#QBKx5$7Y$N1Ts1 zA8|h7e8l;P^Re>gT|O$$N1Ts1A8|h7e8l;P^{el9`rG#idFcCv{Pev;-ugZwpM6h} z=f1zlf8T5P)%P8K&EJDo<$XU=zwb@r^nFVFzGrE-?_c!vy^PMjuhHN4IQ{DTo&HuX z57n2S;>cU^<+FC>IX&{9PJX4IU-e6Q{Z+p_h*N&VFK^l{pY)VxI?F%(`LgsYUiygh z5$7Y$N1Ts1A8|h7e8l;P^Re>2>*b^Je8l;P^AYDG&PSY&I3IC7;(WyUi1QKWBhE*h zk2oK3K33j$y?j)jk2oK3KH_}D`H1rodyY5nJm2%zb3fnh2O1Cd35^r`hsKY6MdQkT zqw!{c(m1p~X?!Yg+^XMr7N>D8e&b)e%?o;(FLXAK=x=`MSM$#Ey>id}>e~+#$3CI> z_7AmdUy&aBjda?dq~HFeekrfN>X!#`%8&TvO}pijp7Km*`KLc$mVU)cA8|h7e8l;P z^AYDG&PSY&I3IC7R^GhJN9Fm5^AYDG&PSY&I3IC7;(WyUi1QKWBhE*hk2oK3KH_|= zym^<8%JUKDBhE*hk2oK3K4Ry+-M_Q0I0x>Y7j{0}{V(j?xO-vPd2;u~uyf|_kzwc0 z-7mx4+rrMVyT^o`V|P!ja`(2X@7@*`$9*>}zI$+3yY9zfdfc1Cbh=N6>37c#>zDg? z*g5dZoe!_RbK}Kvp1k3jnE53Zzt~{rQU+Lsm`uSDAl-FPN%Y!)ONBr`p z-SSCKd8V`c)1NO(zv88jSRT~J`H1ro=OfNXoR2skaX#XFtXv+dFF!aRaX#XF#QBKx z5$7Y$N1Ts1A8|h7e8l;P^AYDG&PSY&mGiOse8l;P^AYDG&PSY&I3KZoxwqB0b#DvH zgZp1te%uSg^5(u6mQVM{uspk8hWX{b66TkCOqgHpsa5XYR`uQ6!s58^hQ)Ue4r|x_ zI82XwbC^!|=`g?Cv%~u3{vFoe%H^T@@>3jnE53Zzt~{rQU+Lsm`uSDAl-FPN%Y!)O zNBr`p-SSCKd8V`c)1NO(zv88jSRT~J`H1ro=OfNXoR2skaX#XFtXv+dFF!aRaX#XF z#QBKx5$7Y$N1Ts1A8|h7e8l;P^AYDG&PSY&mGiOse8l;P^AYDG&PSY&I3KaQ3EpQK zpYAMpZ-(7v@IDQ@U*Dw#qmB9 zkMURUGqHBP&&2e2pNZ-8J`>aLeJ0i~?=!JGCY8H;Qhj$)isPL~Ypy!z!qobn@ndDCwBq^CU7S^nwIm!)6v(np++I3IC7 z;(WyUi1QKWBhE*hkCn?q_2mcWBhE*hk2oK3KH_}D`H1ro=OfNXoR2skaX#XF#QBKx zv2s3EpN}{naX#XF#QBKx5$7XzH=*a9I}5F=?lQFAy5rC~?CwMBvpW$z@7$GWJ$Hwq zb>5we*8lE08I#I;UZ~%5M4X;4WBj$}j&^$<(bIE^&YoZN_gvGjo_Fq;RPOFc_1#G+ zj=L(wcZa3tox3gRapxtS?#QISyJ`BRy#A_R9>gg>WBm3BYj@&&mY(uVXZfc;UzUEw zOCNDQ;(WyUi1QKWBhE*hk2oK3K33lIE+3WWBhE*hk2oK3KH_}D`H1ro=OfNXoR2sk zaX#XF#QBKxvGSgG`KUY}aXw=0nin`9aX#XF#QN3qPJdfh<)QUfep-j+t@T+xTes!8 z^<4g2=lRw8-(9EXUC#^kdya_H^G^JpJKF7eL{HBtI(vT6-*ZjBdfw@8K{`6*6! z#AuVx+Lh<@$bUNdmHzIgHSg-L`sG2K@*{qE({A~sr##bH{^`$`rC;&VN1Ts1A8|h7 ze8l;P^AYDG&PSY&mG`{MN9Fm5^AYDG&PSY&I3IC7;(WyUi1QKWBhE*hk2oK3KH_|= zyysm$D$hrpk2oK3KH_}D`H0<3=y~VPLhGu#46V2BIJ6GC`_S{wors=y?n<#97o-pWtwu)MWC%V+DhJhz_9 zf9pKITK~K2)V%9?p?=R1aeBUpzvE-3?{wPjc}GvrDLQ+8(cg1Tzk1&3Z{_k(efcSl zycJ(QYgeArBme2-SNgk~*1W5~>X!#`%8&TvO}pijp7Km*`KLc$mVU)cA8|h7e8l;P z^AYDG&PSY&I3IC7R^Ib2AC>1L&PSY&I3IC7;(WyUi1QKWBhE*hk2oK3KH_}D`H1te z@}773s5~EWKH_}D`H1ro=OcDEq34}D3$3f}GPK^ho?rC$T+^?fckY-}?(RwT-AO5q zyDG(Zho$G8yDjN)=Ovx)$fUo!Y5JwS{;FRd#3?^x{I%zucFQL{<(ba%Pk+8F{fd`9 z;(WyUi1QKWBhE*hk2oK3KH_|=yysm$D$hrpk2oK3KH_}D`H1ro=OfNXoR2skaX#XF z#QBKx5$9v&J@4{Sc|PKN#QBKx5$7Y$N335x@AS8IRUTSz<)?L6-ddmKvvpgZThHac zb)H|X|J`+J-u1jtzvqZJJzvD{xue~lNA&cZqO<20{XN(8tLL5mRxS_Km!IOuTk++y zcI7!e@}EwArN6sr&Aa-met8h5{D@!Pv|B#uDbIA4fBN%f=~uk;5$7Y$N1Ts1A8|h7 ze8l;P^AYD`6fp-P^+5+rr)3!rj}#-P^+5+rr)3!rj{%>#yD0 z!rj}d+`X;pySIhAw}rd6HP&Cdw}rd6g}b+fySIgxe#J{4aXyaa@0;#X;(WyUi1QKW zBhJUM{+f?CA1mi$_4$bN5$EGrf6Ygnk2oK3K91#UKH_}D`H1ro=OfNXoR2sk$NFnN z;(V-}kJaZR&PSY&WBoNBaX#XF#QBJwJ8hroJZk$H=TzJ0IKSHd$GO(_Mb5jn&vXv9 zeU$UD?XSAGWz2MM3oCD*rhfZ3aoX37@z?g5+HD_5Py0hU+c(nRep0{MXF88sxpS)3 zcYd`v&b1cbdDr%t&cUX~`Pg)JZ%bdgw}q9r&s4uWh*N&X_-p%2?Uqk^$}^qipZGN z@7()nT)7X@cieDk_B}!#`hFoleeaOBzK_Uf z-&5qd?=SM-_ZoineW!a{+Em{6BlY{TU^6B;M>4~-xD zipG`wM&qq}Tk_YvEv&qGr+(vEoW{BMjeqSnFX(B$(AhkqzxkzK%{$Nc%02h1Z$D5R z`-I}#Kh&;$MSAQv(%HQ&ed*p7R^Gf*zdVRje#9?t+AW{-lxI52KmGZ#^ebNai1QKW zBhE*hk2oK3KH_}D`H1te^5$JWD$hrpk2oK3KH_}D`H1ro=OfNXoR2skaX#XF#QBKx z5$9v&&AWV5o{u;maX#XF#QBKx5&Ji${Ttu@{kxyu{!dot>VJ`!b?|f+efsy!ol#fc z-zA(~$Npa7EIRgg3}?}?zi&8;j{V)kS#<30AeDf^ zetGwZ`Q_as*00L_-LLxo9#|ZICoI0dAJ(qFE2hWa8`J6Ukm=uS_4nucjq zmvUOUTvwk5SRCG9@p*=|%S%j;F@fncCNTZR1lF(0<+A#6Ssb}6zFgL>T&71Z(C6}U^GlnR(^7pJi$iX%&BU*+XN{qiGDc@w{UDl5A&e^6Z5Nb{jI({6i0rFFK@LgpXrh3bjpAF`BK05RezP22ldO3IOR?J@~PeO zOi%fzGhdc|nbVb<>(#dg6vx_7d}~JST1(PnjY+4qC;ir>`em)Ezsk#l`sGKQ@+N-y z)NXmEr~K2IFZAb^epPNgslIilIM$!yTbF9rT9qDaRXVLz>9U;v46+tFP&igLKMG z`sJ*C$z}ajULMphKjLVEHu1}+vhu8M`4=N!#Qy)-y7Tz$uKE7=t$9d8P$48Zs))#R zXCC$~i6kP1h^aD3NDwke1Zj$rfy{SAh|Jn5F;i-&DW!@ul@O(sP}*ar<{>0M=X&mS zy{02qeboXx!v=%_DTQSzTd|G+y7JFebwB@ zI9q&pu&{{aYX7v~I?4Jsr1oHlNntJi9LDf5aDGH?NO-{2r2fGKq^7O&(%{{gn?4JGLEw7!&bT5DQp9j0g|F3fgyZ29e^8dD< zwaNeX|AX&eF#lWQJoh7mjlbrC!H#>u3kI9dSqBa_&+8vE*!;h?_h9E$yZf{L?%T$3 zKR3SnyyLp}n~!_HdAj$Tzk9#)@_co^+FJ+xTOZ@JZpLpt9k+EhpVr?zyDsM6^>QE9 z?*6R5`?hi1&yDXs@3`*&=Ht0&o}RDf@A>MyJYSu!_SQlF*2g%loAFyu$8DX>r}a0_ zu8aA1y_{F=?$7$WZyU$`-1zSEj_dw!KAwx_>3M1Xo}t(8Nc;( z+}7EAT7UEGx|o08quhsmk8*$ZJ<5IC_bB&s-=o~;eUEbg_dUvU(f26NSKp&NUwx1A zeDys_d*7qSd?X83Ut&ee9H{-XSj@vq$PwQ`Tf-8au8%)YyFN#m46O;l>^YL6XPtQy9_Z)Rzp0CbVd+VTo>tmeO&G@aSx$)iS9oPNed^{J;)AQ2&Jx86F=d1J8-a6>t`WUBmGk)vo zxUIAKwEpJVbus_0m-DLK{aJtaZR5C~8{d82aozvT$8*s{n%%}A?&#sI4_df4F?7h+b+54pXw)af;bMK$-^WIC{|GlqzE_#pk zeD!|o`Rcvb^VR#X_TH2A@BP_0y;mE*_ie}RJ=}bHKR3_b+s(iCdFNHT`?LP;+s1J} zH@^G4joMPU~j;*3)rYXY*45o<%@Toj@oXsS!aHHmtCfBzi#jWFWO~# z(Cr^Sx3Bq^T~=crcjI=`k@wnaZr|ptZKf;VzU9o@Z@JC1#hStEzO!aJ`dwSh?T>u_ zn(00d8hq8oYo-Uhe)GBgn%AwFUb5ccQ{K8}+W3{@SWo@8HPdx>7<{*TZnNk==JWOE zZZl2W4?gho+f4txod4x}Z9DC=Jg=vHdfVwP%k%y2zy989rwtxEc;8E>>6U8euo zaqx~m+IiaQr(^u9Ubyr0s{3xen&-Ap9qYEoeb!FvzkTp4&RRR2c(<|6H!tS)>Q@c^ z-D1w`-(g&rr!LNA|MLbvdvT86de>Oz{dSzDdwqAT?a9aQI^E_e7tF_U%uV(i?BBg^ z8f?7pJz%ioeCIc>nfp8b+pZpLUT2>_*nAt)dVlYXSC4a9T!*VaKG?aw>gK`L;5pOz zb02H->Qe?=v-PhYY%RZjmodIIzUvbQTl@FFda!G<{&GI9)ytRjbPeCJoWE;(((=4q z^9`5h>s~nZ(dW){a9=<01?$F~7thdtZZ_CGb>VkLANSghR}OX$zW(UJ?#%;s8tk6^ z*M>jrx!_WiB&d#H<+H>@YUDPedx*Gy?!t~*>?ZI^yHcA4W=h+K0A&@PtG}WFg@9J|H1U+ zpO*8aCl@Z~PftF(JTH2(+46kp$;Ur`={yH|a{sqnGUmL{lf!>Bn4Y|S&FDiFg@AefrIJE zuD=`O)05}i8wb;q!|pQHnV$S`pTYEGvoi}~A>-fD zllS~)tS3ELcgh>)V;#2rn(3G~4c_?UTTkEo*x;LY*?QXhn!)Sdx7Ffr*5C^ty4Ccz z|1|i&uh??>^1BA_a-S`ygU=hh_Z3@A8$NsRbGO)HdeF9mKlHiHr_G-=_?NF)GkxPR zgV+9I&GaAJ4?g99ZKi!r8|(9uv$mZ+@ehN){mpHsTm5SAo)6z{I$(#(=lNgs^zEjb zUNZP4f3e;4^G^(Z$jcXf?r_E2=cJ>zn|9uJ@J)McH+|@g!Pneop)H>n{QmcBJALw} zgKz)XZKr2!H0HDJKem}ZzVEnaXwJdQ`^4Yvdv89j9nJZ|cSj$ZbHeg|qd8wVX0+3s z*X}%+=4`&fV48E?kH>YVInTObFwHsZ^Mh&5Y1a>?IeUL&FwHsoH-l-;BQ_ah(wuwV zajb)Re*AgkylBq;yA7r}8?Qf@=A3u^=udO@f6ZW;v*qIl)0~UnH2QDyj)zbG=evW~ z?Ya4Mztf&RuQSd0{&|CG&du)~Omm*}!@)G?DLWrJ_oq2uxMVQRxyyQo&FwU&F=@^d zH$Gx+_YQOZdk&wO=G=RS!8GTo?|bIlPIGR%>0p|3=gXckx6_#=a%!QIcwfG&V}aOv^-y$v&p5;n~z0vzVYZIXZ8+rvs>PInUT|tTWB|i?avQoL{du zt_#iC<+X!p&UNn_>r8WQ{Xb)EY0g{Tc))xt?=UyMez13#YhF0mJIo2Y4E7Fl-2Xgn z?(ZGum*))j4)ei{2YZKUOz$u+T<^)_To&&z+nzYsJIp(OGT1xJ^I!OsxsP|4PyBAM zcbJcy{nWYLJIpig^=C7Chq>zV!QNs1=)U8)-eEp+_F(TYZ}{P0?=ZjFdCcEC%mvHy z@(%O4<@tJtdCNJEo5!ao-}>5qGkZ=C*?%xSx%RV~E%a5J^Ej{`5+XvH=-7XqTPqw>kFg^Lu2M5!W+kSsAJ$d`qV@!JTlsi0W zHP5&F>sU8>a_xzO>B$jy8%$3gbJ>cK< zCl3!2J$cc&gXzgD-!qt=eC>OK>B%>C*lV5}Jvr#2!Sv+fJMKNV)04)eCturW-*GMr zJ=yqOkDi&Hym8yX^yI(Zv(Ma4PtJSrV0!Ypiyt+&)03a9KbW4JfBHBUJ=yclgXziZ zE*|rtC-2>HFg^LR?~nP@laDRWi=LdiJYRb9mW!S+AB&zG^{8xdx@T${KWBZ>B%i08ca|AW&Qo`^u)i%^u)NBo;V(+C+0EtS?G!R;rTb*a!h(+ z-L?B|>fA6ran6{YSPM)~tP!Rs)(+DXYl`WKwZ`52Or)06pkwf>7|&Ap|ap19{QJ#jB$dg30%^u)c3>4|$9(-ZePrYD|( z(SP&Fvw`V}X9m*~&l095o-s^MJlohj=WiAZrYD|T?exU+jOmHz9McoeKc**i0n?ND zo>(wFaj$5nC%66788grCCsz;l?_O}@VB_8IrooPL|NEag_jmk5_8V+oFFk#*`8KBY zzTd0Qp8I=0nGPK6TuIr8_$~iSep|s9Bj>gyWe1I`H(vgw#GModK}Bz?|;T% z*W|a$`M6eREa&MO9<-dlYrAfFUat91m*?wVIQ6=9^BmmQ-+J@8W6q2FebfIL?4CM) z>(R%(cJ1+l-Gj%yW3YSkonIg9p8exHpEr-=UVg#D2D`_<`iQ~q{SQ8RuxH|9j~eV* zxp}9-o}n*4V6bQF*8gXW@0r{D?&qxLdD^?j`gmS{@|D4!<3C-0th49)y^k8~x&O)O zgXzKD|8+2(`07F9-?~R$bkkT{_s-Q%dewX^dh*|o8%$3Q+;uQLdDs01)021J^vbzE zJ$e3T2YWwx!m9_ha|aV`rzIqzeG>B(b$JD8q4eAmX9m-gJ(u&OC&w@6Pfyk^&x@YixIABa^5}hDG0%aX zeCN26$D9|>=^Gz5n4TQ;?a_yx{O(PI>B+%I4W=je-*GTK`Ox}<>B)ir^YVF2dh(Nh zA52f~dF^2DCwKk)V0!X}uMMUrzxvf+dh###8Dr9uH{5Qywu^c0bL3bndh*q2Fg>~Q z&V%X6eLg?>)03~BH<+G$_%Va&$xl8q`qPs?yZ=~EdUC<5{(PQ4JvsC>gXzg}?;lK0 zKKrA=^yFW5J!$SwPxiiiFg-bS{lA#o=}BYKlh54mFXwi8a{KqaY-W10Zl}TY;3YjSFdh*)ky+lv8d;4goCnx;p zV0v=H9Z#9(Ku>nqbTB>n>$QXF$;B;lX8%$3ge*eMrq%r4jw(B1|_xFDC z){_R)lL!8MFg^L^i=RLDp(oql>bRNd$yVzI(~~c6bo|^-PqzE3!Sv+hO~!HQ$yVzI z)0015&Xb-TyPQ8gx#RM@=*b?-^Q9-7ocEl0e0p-=H=aAQzx&reX)rx`{ZqfcPs(1Z`usls_+xv`?Wg|Hx?O*t)j`w$I7)any3c##iGBJFePK*nHH4!se+~6gGb~q_Fc+TMF~Z)XpbUe?FPU;ge~6KADco zC)0fRWSS?RO!Mb!>b$gfzWTQg#%XuEl%vw61u=HGR3UTP9`UTWE3{nf<5 z#!)K=8($3_?6_*{VDnLP2b-rFF4+9lcEQ!Msa-9b`m1GwjiUw-Hon?G*m2bi!serv z5H?RWhOqNedk8x(HHon6Si9?6f7iWn+z*ZKKIypbpXTE}Y@Y7J=3gxv$I{;U>fbsT zr}Z&@>*lzvr}?zb=Gpq2f7gXS!Cq;{;#;sM7xOdNtBd&@?BT`y4;wFPYGA$ydwwy$ zguTF+kHQ{d%wJ*8DXwNg?e^H#-yURa9D9?o@i%?qX)`;nz0BIp#~x>Fp7uUt^S37& zJ1={sG2cb)d>8fSyJ#G~i^k`>=(yE}Fb>~E^W?i|{?(Y!M|WxXX|hNT^D|>t`{Fy?fhN!=lg0Lez3;p6YIGAW6g)Jtaul}ur zak^f{U#;8XxUHx8w9e+)`kQ~(#d&qT_|R(SL#sa@TI2AcH9j9&$1S(HIrE`4Pd>Ef zUygKrw0FMxw+_Z>eT?6_Id1D|KCQEPw*Kbdb>T7Udhs6B&XZJsUZuw2VQPHdrjE<= z)O>iMnkSD`^XHvXGuL@(?|k)d9gNfUGX84a7RPNp&8KxX&(`1kyDrYF>&1IiJ5N&m zd6gQ6hpF*-n>sGfQ}f}4YM$#YJW|b{cdGN!-udd^IvA(*F@EdjxUHx8w9e+)`kQ~( zg~zDt#d}mcPg4DPl^TbKsquN6Ixf#s^WlYRo;*^`pLeSB(%$*%-#Qql^)Y_y=D4k= z`LxdF+4`G**Ts2ty?Bpm=SiwRuTtaiFf~4JQ^)0bYCgPB&67u}`SVV7UfMff{aXj) zv_8gf-5j^|G@sVlJX?SB@4DFEwATesneX{>0J{In<%r7xh|2+p%K?bX0f@^1IQPHd z?vtE&xEz4B%K=z_IRJ4v0C710=l;tafVdohxEz4E9DsBC;=F!&;rQEH4nXbY0L0}0 z#N`0Qa&X~t$Ki6v)h>rs{pI+= z#*zCA&*Lw0kzvP`D-4^D9Ael!S?)M}${mNb%VCA}Zyk)&`pn}m*UfQTPxEP=&9n74|E`PQcwH~KgKC#k zsQz*dHI5uajW0J**GtZ#<|CI;^E_ygtE%~zbIiGD?|SLqIvA(*na5wQo8z{g=F>Wx zXX|hNT^Hxo^^!ZNb~%OWFV|4x$U)TjauapE*Bon`&F(g$1PVCE>{&UR~5FN>9BQ9pUYLHkL!}2m#eDw z^uJtH+KtoS3*+~9q+C_{l&cDts|uH^3Oldy+RJf-%W;IuafHipgv)V+%W;IgN2Q0}uX^shclA7aAL}{w zp4Rj0{VhH8Uf1*PeJ>sG9+*COKYYvGubZ`9dwQsUI%AylXC8m4hmM*ctur}?zb=Gpq2f7iu#fUcMC1GW2ZP=DVO z8prpI#`pc9>*c#d^YOi+dHRmg{C(f(ytH?|`nL|oX?^DLm)Fa2TTk<8oz1iLH~+4S z^Xhu}K2W>w2KDznp>cd?Xnfxvx?a9ZG#}q9ny2p=&ENNp&P#jetAFcYoYrR^e|fze zxAioi*4aE;fAjCU_|De#^8KxL-{tD>dtKxBj@S6U?{&R=_iH}BA2v_l51YU5hn<)9 z&R74|!8onYJpS@}Id1D|KCQEPw*Kbdb#Y!@FW=v4_g$|3zSlL5?|6;x`(D?}cfaQ2 zdtmeQov``)e%N_w?|k)d9gNfZ%;PVwm*cjc=F>WxXX|hNT^HZ6|M35Q`uv;D_w6h1 zeCW)+dq4LTgMANw&u)j!?Y@)0d9P>8?ECp4r;p!*zN_E$mcz%tU3{N^&PC%lvhVX> z-|sndyYKUx-1E6JYd`3Q=dJqx+xg?SvvD52#j$g{@xS&r<9D>)-l0SRe;#{v<#M2LX&yVN#gcpD5GPdIIQ;|(Jwa_FN@o36fSx4C_z zyPr1g@W*@1eBPH%oqoCdBWFJ4f>Wn`H`;UNuRQM5>6QxyUwr#hrE`2hpU3&H&!0Sf=1U{~a>H9ro?iZcM!e=Z zXP-R%%P&Vv=kUe)y!&%I&HYc@bySvursDF{bZcucE_GE?Q@&4 z4&Qj^8PnrF^{shL?)cp^rZXQh*6r^1J#*S@V4j z>r2m^t~>cxGrxD?6Z?bD{dVS^7W`Lt|AToBd%Wb#>89;(HS+_GICJ{hBX2YFZU6J> z)48u6&&&M|efspCb%=Ex>$9#7D&C%08etgXHzfU@PdgL3%{BQg7qo$WW zbez{4pZu)p0}tG4{Cox5w;9jHosT$ldg2$io!j?6`_Spb?_V?X2S0o0wBd(G z|CitAu<2tz8ZpfS|MIZu%ELyi^Tj_sY`WWhM-23W zoe!OUc;tAF-uu+2Pv^Y!G4nimOaAds|8QoWlLwzP?oVEnYwtepPac&u-?{DFhj-;q zzjynYd0Mu;^N4ZtrQB(k_2zcohCjOd&?}yYH{3Yl?|c-u{nzpA@K>ZWJQCmh*?1m# zC!Vw3cpiBw9`fb!Jn~xXy7zbu0TW z`J#^edMt# zJ-^-Wj#=qE?@`x|C#m)4RqDF%Fm=6no4SrXPhDSLsIEKjOZNs(O!o|*P4^_9Q1=xN zP4^pbP4^+sP4_1+PWLU3PWQ8MTJxP>vDNBYJmw)=t8n|77RYz5VQG?Yz3@|LgpnSI@%FuiSa{jNEF${Vluuc{{J3scR2g z`0AE_%YOUOH7h-T?3y(z{e1r0w_fS$y&t~yN^h_J;9?)|QiuP3|E*T~{I**be(|Ml z|KUd#dx4gE{>pV*u5|u{Ki_ht|Ia#U%hlh7C!fFN>hHxxS8ciaJM#ToZ?*dS!n@hu zFaFE^uJL8|w~1e~zgc{o{Vh9Sqn)R1mVe{;KKtAEgTL5y^|x}(yW`>>XYH zZGG&c94j%;`Cf6wwU1co{{!#)h}GYPCx2n>>hIdSKELDY z@7;?Zx={4x-;uvqoNs?$KDqFH_IKweXYIWDd-SwF-evW7>fV37%j)mf_M7jz`n&eA zzu$HB_wI&;ZN9&Qzkc(y`ulkOo!74ZZeD!w+ST9FKe%M=>hJ8MKCyQ7_xItixOCd? zxP9ioLBG1|rPCXqxc|&gKJk+2-WQMepI86G#nX50Io_SVx9`Q%uYWP#dCuJL;_2JB z8SfbTA9C?@%_igB7jB^69io#(X~VyUV82KRxF8 znyW6G{`GIh{6F#1%cf^;I?n6yi{n1*7h`=k{n6#qKfHUa$!qU<#dOWN<9FqU_q$?x z``;co&+VC)UNODsPJg!Iuip1jGaveoS4GqSd-ny@0}06 z@3Lvf^TuzGTiWBl8sI$6?!G$fAJ1Lgt6P3&!OMGZ)7!6G-IG^uyl!=`p8v3Qt9$tK zcQ|+2?%&2efAjI@OnZKDtlNgSK4*IWu8*GA@k1>_2(mvsTakz1E$zdiLM^ zxwBT!{(So``5g3^^AP| zv9DbH4La^luU!2N`sb@pTm22X{Jhgve}gVK__WpEpu4O&ZS^;3r@NiD`WtlfV!uYe zHGcNvQ&)e3j{3=|tG_{q-*W2eZ_q36aoXx{&sHVE?|yae zN(a{e+_@`#IN;)QSGsY+A?L32WQ+TryV99+|LvTW{;dD83#Pw4bG(P||C85F|FpyJ z=HH~d-RHvT_V>Bfd=Ff+_3NjvJbe5{e&H4uO%MC~JJ0Rw?s)O^o73(#^Pev?bC2h3 zH1ijCxn#QJ!4I7I%Cj$-?(*XCyW`9^U$XG`ZntWG+S|sr0{#E>H{*FX&VxSigt?FL zkGb?|Gdu3CM;|(~`JDUnp||FF*zJctoB!=zIke7s-Sgm~y`MevHLLa;4n2R>f4_ZR zy&C7uk2!BO{yB?1O&#}d7SC7ndDPl-SMxk!kprappZ`VskH&dv?|k)d9gNfZ7{7IM z+}6{4T4(cY{msAYBDU1^+Iq1cv-Z1u?n$fu54zm9V3 z&o&zzyqf3N-hJ?D{(t?ggIDLJz4O(->t&qQ$M~(A<95Bwr|V^&T`%+RdO5GI*Ztq| z*j4);Puq9Z|KXeNvl{1yE%#oH|K^wMxjOFk8$EJ0pH1$$$7-H0e9`W!`M>88yRXhm zd)G_e7aud+4VC2uFI*vSk!1g`}AE8`qo3Hc)eZrn65bfzH>V- z{Rh_Hc;@>b_n_&nZyNlLiyky>u+1iO`!{cR(Dc0b4gS=&e>!ddz%k}|Z(PLpUOM=D zfAZkzaUUQ2gTH(5bmO-N@A>G5{J(tr?Geah|NGwi{Q33y|L!Ab&h`;B{saGgkJWKs zdh8=t^Lg1Vk6g|3-(R}tYW{!ogGJ83<$0a5*Iujh{qX5~t=8dD@7Zhi*qe{|m2an5 zT+6ppEZ*hYDHaFw?G%fT`F4uM&3rq>;%UB}VsSR#POiKc3!oMYt>)8t8v7^8ee>@tmeO&G@aSvmq^!?lYW*Izujam1M$U;Me_ zic2>i@#^L&j@|slw>vL!@6K0y>!5$@W1QB__^qeow$A3$`kQCh#r(To&Z~BDt(8Nc;(+}7EAT7UEGx|o00 zYw>q$)&9*Zwq5nV-PYT##`*Ep+pNa_r=u4+5SGu^Q#RgaHJ^LmxMnra+rNFyYW}Y~ zcg^a&-f`-h)%j{~9rSN~jMKUqzx8z7*4cbofAj3Rn19#HdDVW($=j{^KjX*St;RX= zsoSr{f8+bMUmf>ux7}eipU3aD!)l&~y=aHk{J-#;9aiV{;mdYdov-$;m;PNZ6`wrn77xo>(x39U+;yZ+IVtC#Mzxc+5 zecSLo4cmw4I~%q?(RVy-&!cZ~*j`BA=&=2azTIK_9DUQn_CNa8hwY2>4G`NeX)hw4 z^D!*;BF_C6-v;bO#P(gi0$XK7ZKa%YcC?U z|5xrl>>A4Hhg}D`{;=yK2OxIcrr!h@5iRy(3Q@c5ljG zhpm$wbl80-Hyw6A%2|iqr*he0_pcmx*nKTuA2yCWesllDb&x9$J6AdMur-id4_g~K z_pmjSiw|2%Ir^|Qmb(vIdpZ5EYa-X*=)c*V0}#80asy)5R?a}|n#(1K-3#&}VtZ^` zH}|`ogxcLxauv?~7x$VRhS)tQw;{GqR?b80o|Ov`yO-ri#P-|DorvB0aw=lagj|c* zvmys0_6*6*h&@|!He%15+51HcbDxEt$Qg*~iM)T9p2!`C z>4}_jn4ZW}hv|v@b(jvwL5Jyy+;o_p$XSQ!iClJ=p2%^B>4|)O*f{d|&HWd8B3B-! zCvxavdLp+TrYCalVR|ALAEqaA^kI4;cORxFa{6ISN$W;W=LKf$|4p`2*z@#PSNtH;CmMlsj(jzsMaYryQ13PM$hUbMCpwUx#VMmWv#8nC8e$ zhiQ(Sb(rSJWrt~w9Cw)J$k&IBBah$Qf1x>YjGTw~rbW&}xe&2jh;k%iITCMr$zZt?Q~u%H4-)j+}m&=E(JjX^tF#nC8e0IQLm-j+}v*=E(bpX^z}+ znC8eShiMKU0;V~92$)vzAz+%rhk$7g9|ER1d{X+<{9CVnT$W4doiJWzqp2%f~=XmmogXxKU zecFv9kKf#Xp(k?XVR|Bm9;PR9>tT8#=N_gfa`9n$B1a#lCvx{;dLpMErYCa!jsBa> zIRG&|ksA=x6FCDhJ&{Wg(-V0Sv3Ho(%{z>ogxbBs$W=J^U%bP}VTirM$Zd$d!^nAv zy~D_bh`qzek%+y+$eoD2!^o+Ky~D`0h`qze!HB)X$jyko!^qi)y~D`ehv~^d7wt7O zJ(25AJ3WyD5YrR60kPPuoPn60$oq%siQI9Rp2#VO>4`jbn4ZXAhv|SEbeNvVO^4}; zoOPI<$YqD=i5z#Bp2*jSjU$iW+<&1ba^+!qB8MKPCvxjydLri@rYCaoVR|A*AEqaA z_hEV>ryr&#a{Z0|Yv&w*n4ZWDi0O%(fta4iC5Y*Xyoi{dv~Ki7PD1VUM6SZQ|3XjX zFvRpkZbM8@3Pvl6%^hEANOi$!g#Pme2MNCiRV8rx9ZbnQ`52Oo(-Z59jbq*C{tG>EZkV1pXG~A51*Rv~2-6d5hv|tm#q`8lV|wBm zV0z-(jQ*R=IRG&|aV;@Dk?#r96W1Qo6ZxJnJ!#$OiF-&pJ#lZ%{TF)Tp2PISy@=_F zd{3C3xOXuGN|Ipwf>N1i(D-ju%%TPHc_u=`GKI_!Rw zvktpY<+8)>Upelu`&zy}Y#e#~=KhQ8AXgrCu5##MYaq8Cwl;F^VQVHAAGVfq^kHi( zcOSO)a{6J{M6SQlfAOxh$N`95L%9L5Yb$3UcFpAy#O?)o5wZKab#uSVNvPdDwQjl2 z?ln0KwYvx9HpKKq&O_{;l?xHOmv36+NW|`Oxf8K_Urt5rnUHG{dsgIN#GWC!8L?+e z&PME+le-Vo6FL1bJ(24V(-S!WF+DkOkwb6pv(OVc12H|3_Ycz(x#KWBky8%S6M5<| zJ(0f-(*Zf?Fg=l*4$~7k>o7f$%MQ~MIqon$k*^OMM;^bq|3XjX%ERKTJ>L`WyWhzquAU05Lt08xYeIIRi00kxLNM6L}Fa zJ!#$OiJXMm>B-vVI{Tg{hoN?QBDW!?CvqNQdLkDhrYCYFVtOKXBBm#DDq?yf*CM7T zaxh|gA~z$ZCvrAodLnlprYCaxVR|ChAEqaA0AhL~H{jf7p(k<%VtOL)AEqaA$64}_vn4ZY>H~O!ga{yv`A~ztWCvpa2dLow~ zrYG_uVtUfL(GxidwbK*13g`X{J(0r@(-XN3F+Gv<5YrR65HUTGBN5XRxf3xxky8=V z6S)>KJ&}VE(-XNFF+Gv95z`a?YD`b~t1&&{ug3I*zZ%mM{_45ULQnXsF+JfK#`J{0 z8q*X0YD`Zyx$gNh(-Zz`?R0>@8q*X0YD`b~t1&&{ug3I*zZ%mM`TDSN3KF3lY;3ITA5F zkvkF76FC(zJ&|h>(-S!uF+Gu+5z~{mE^;YO7jwtO+;K5?T+AI8bH~NpaWQvX%pDhV z$Hm-h7Za?%m>@3Zj*GeDV(z$@J1*vqi@D=G5;%_p&Le^INZ>pYIFAI*BZ2cs;5-sI zk3{Waxb+vq#d#!f9toUB0_Tyyc_eTi30%w_i^YriVljHLU@UeoMvTSu#g4I9fAir1 zXr8Jn zr*$)a>*=_yv-!0C=GpZ!fA0s5<-N{(1NMF>rjNZJde6Y#550e2?}y$?u=hjnE7&`y zzn$2a{-$Ez0Ot4L1$$TY_e{HYMSth8cSV2yuy;j&7qNFme=o6jMSn-JcSV0+v3Es( zcSrvb-^bn+{hh|%75yH--WB~_$KDl>T)d-T?~2}Cuy;l82iUu!_lCLu;$6}E1op1z zJp+4J6yL|*6}^{W?~2}6uy;l8G1$AJ_Z#e8(R&Z}uIPOTdsp z6Vu1W6Vu0zBc_iXUrZl+Kjag@<}1FB=ks{)2IBkJ+KBICYbL&r zt)=)rw#MT7*xHNlW7kA{fAk;mee4>F?_<|id>^~!|G9|o;Teiz@z z?kVy8x&Pu`6W_<~LGgX;T~T}=yJyAsv3ps3AG^oJ_py6ld>?xz#P_jhMSLH7hQ#-= zXG?q^d*+&_XPqZRyXTcB1bdEoLa^tXCj@)$c|zts3q9Zo!E}NT1iMH0K(Kp9Odosp z#q=>f5!1)?L`)yk6ES^EPsH>wJ>e6;^hA6g8&iBA(-ZN1Oi#r3F+CCA$Mi&eAJY@@ zeN0cp_c1*Y-^cVsd>_*j@%_<%#P=~h5#Pu3M0_996Y+gaPsH~zJrUo>^hA6g(-ZOi zx&J~>#P=~h5#Pu3M0_996Y+gaPsH~zJrUo>^hA6g(-ZN1Oi#r3F+CCA$ModS7x8^e zPnst^;R(@BPk2HwJ>dz#^n@n_(-WSMxz9pRctS8e;RC_+gbxJMlY1`W_1Lp7UXSUC zcs-^k;`NxGh}UC!B3_T_2@e3KCt~;5m}2*so`~IJdLnj@>514qrYB1_*s@qJ8l)bbnsM|>aC9PxcjbHw*C%@NaC9PxcjbHw*C%@N1<>JIxW_$Ho-jpa1PbbHw*C%@N_*s@qJ8l#P>1H5#Pt& zVZ`^bcNp<~>>WmYf9}6{hY{b$-eJV|v3D5pee4}Zd>?y<5#Pt&VZ`^bcNp<~>>WmY zAA5%p-^boz#P_jx81a4V9j1ADhv5m)?j43F1bc_!3BlfBctWsu7@m;1&*B}1Cj@(k z;RC_mVfa9>cNj5!?AaI7$Mi%@AJY>teN0cp^f5gV)5r9LPXN;s@qKJe@qJ8B#P=~h z5#Pu3M0_996Y+gaPsH~zJrUo>^hA6g(-ZN1Oi#r3NB_*j@qJ8B#P{d^3q29v$Mi&eAJY@@eN0cp_c1*Y-^cVsd>_*j@qJ8B#P=~h z5#Pu3M0_996Y+gaPnst^;R(@BPk2HwJ>dz#^n@n_(-WSMxz9pRctS8e;RC_+gbxJM z6UV@wef=;!5!1)?#JHHAI3A`a=7H&n`C)o8ukV75Y2D|4yU-KohUtlO#`MHmV0vPW zFg>w$n4VZuOi!#erYEierYEk==s)87n4Y+nn4XBaVtV4*V|wB~#`MJfjp>Pd2-6ey z*4%%gC-XhGXs0LcMeX!Nd>_*j_b#RiRTv66VEfIC!TXmPdxu~pM{>#1x!!e6PTX3S1>&h)5ne}rjPwQF@0=2 zF@5YfV*1$e#q_ax@d;q_72n76c`V}l*mV%!$IexJA6o>n5 z@qKLV#rLsmBECQRkN7@z4aN7dYb(BwU32k$>|PMx$L?$Kee8Z0-^cDL@%_2~;$9Qq z$L>M#eN0cp_py6cd>^})Z(79nv3p#6AG`O(_pxU}d>?yO#P_jhNPHiAw#4_bXRdjA z)_Fp-dtP}$u;-X31be=DLa^taCuHuk&;y{^s#4OOdrz|F?~!= z#Pl&e5!1)?L`)yk6Fvb-$dg3n4XC5V|pUKkLii{KBgz)`52G0rYGY2bN_{&i0@;1 zBEFC5iTFOIC*u252G0rYGY2n4XC5V|pUKkLk&Ii}*gKC(VB)i1bMeiUCqz3v;RC_+gbxJM6ES`4*%#Bt^h8V_(-Sd$Oi#r0 zF+CB}$Ml3x0MirkeQZqeeN0cp_c1*Y-^cVsd>_wRyNK^&dLq7$>52G0rYGY2n4XC5 zV|pUKKl+dOKBgz)`dz#^n@n_(-WSMxz9pRctS8e;RC_+gbxJM6ES`4*%#Bt^h8V_(-Sd$Oi#r0F+CB} z$Mj^A>ju*k@qO*a6yKl!?Ltq)_c1*Y-^cVsd>_*j@qJ8B#P=~h5#Pu3M0_996Y+ga zPsH~}{}JEE^hA6g(-ZN1Oi#r3F+CCA$Mi&eAJY@@eN0cp_vii#JrUo>^hA6g(-ZN1 zOi#r3F+CCA$Mi&eAJY@@eN0cp_c1*Y-^cVsd>_*j@qJ8BnkPNs3DHhZctS8e;R(U? zgeL^k6P}Q{&q7alLNGny1Htr!4+PT_o&mms@&HtKuf6}jUt18%&m$)fE+-EzCl4+s z4=yK9?Q-(eUrruu965P#`G0Wvd2so8aQS&~d7N;$dT_aVaJhPLxq5K9dT_aVaJhPL zxq5K9dT_aVaJhPLxq5JUrEqzraCxP0d8Kf9rEqzraCxP0d8M#_EB_BJuM{q?)ZG8+ zBd-)LuM{q?6fUn6F0T|WuM{q?6fUn6F0T|WuM{q?6fUn6F0T}R-ZHNgK4Zs`R|=O` z3YS+3msbjxR|;>s%qxYO5leSN{<^ zFLfcYICAac%k>v`ZXEIG#uumVxZ>B%M_jvkii0tLML$M~(Aj}H>u>&D7w4reWaq2?Ahr(b5@PG4ULm$_>KJ0{slFk$&gvdw*GoM_?0Tt_h+VHm zY=70Ru44VwTg1juhY=fJeMaoK>NaBYQO^;Zr#g?=^-}*4J1=!1vGc9nI@I6#G>&y^ zeCye9t#k9S{>{^MY5uNP=cT>#)xUKxPU~a**3EHSPxEP=&9n74|E^1QA)QzC2k|R^ zIqDMP>J{SZ7~<+1;_4pa>LKFlB;x8P)~+r|{nZ!4#!*KG8-LR$o;I`Ns#B)jeAF+S z|LtO)>Y8EmS1$%v7ZS_&UVC*UwO3yfS9cOuj}lj>63ai|JmsZt{?)tGr#hJRR|l~JSo?S2V z?|L~eb($QD=dX5N!20tDHV*G#tLML$M~(A zj}H>u>&D7v8?E7jIwfJahHurE44>yT<3e>$p65&4*X7dGhcz|LP|?FYTSL z{;h*?S|8)LZjRe}nosL&o~^(6cU_!U*Nd02b{@z2^FB5XPh{isVs=~}%I3pc**tkM zn}78#otO5`SO3<*IIWNITQ|pTJO$h`LgMN| z;_5=q{cjj`A#rsfYgZSt{^~;F>O$h`LeBk{bs=$eA#rsfadjc*_CFeRA#rsfadjba zbs=$eA#rsfadjbabs^{e%es)bx{$T23t4}4A#rsfadjc*{>!?MxVn(Ix{$cKkhr># zxVn(Ix{$cKkhr>#xVn(Ix{$cKkhr>#xVn(FtHV-%^;vLrA#rsfadjbabs=$eA#rsf zadjbabs=$eA#rsfv3g|c$l&Ti;_5=;>O$h`LgMN|)~=3B{dZl|$Hdiz#MOnwj;oFg zt}Z05E+nolB(^_6-5*?CNL*b=TwO@4-e2RZ1E}tgcJ%?(wVD6zvMwY(XjvB$R~NGO zu2*#-wHrsB9XyY}sQZH*xAm+pr1t7U;_5ZRi9LgMN|V&~Q0uj)c-uP!96E+n>Y z>8O$&YT}WJANbJ1&`&C^? z?bU_E)~CN;)rHhvT}WJANL*b=TwO?9UC7!y-|9kYuP!96E+nolBsQP^epMGzdvzgk zbs=$eA#rsfadjbabs=$eA#rsfadjbabs=$eA#3k?RTolwbs=$eA#rsfadjbabs=$e zA#rsfadjbabs=$eAu(O*eyA>__Ub~;|8`OLw)c(dLTaxrB-Y;bsxD;XbU#-YQoG}J z|5q1Mdvzgkbs@3$sPxeL)kha~jkSC4QiltBAL}{wo|YbZe@hR&*QJNv_tI_ef$2l_ z6OE}oJ=DLyU&cuf=kb?%=(y>j`J`j!sjitZ&0oDU?7Y%L?^m^Z@2bD|vBvS9*7)Av z9=bfP_qyieeXn_X4{ZL`yL4Rbov;3_gK=7)dHm(y5yx#k&8KxX&(`1kyDomGbiMq3 zson3I`un}pIDQ8;zTZb(FTb0bkKa?xbG^mytma?+MCYZw^VPp~Fiz_;kH1_u$89~$ zr*$^Z*5CZQF3zj#<@ZbNe%I9B@14f+JE-yfKI(e;-PC;io@$r!1v$MSuk_UaO9uU;Xpjv=nTA+GKrt{x(;P9m;; zV(p!;{;h*?TAz9R<@Ivh*3*1iXY*|R&A;nXT}a2OUL>xLB(A#e{Xy*eVg0LDsJ%Ld zxcY{;x`*?>UDiXy)k(zFPprM`RlP;+#_4*^<1eq5<95Bwr|V^&T`%+RdQ}(Fn7+T& zUL8s8)tAK8oy66n#MP<9)vv_WwZzrCti9`1eN64u&BXKg%j@O1T`%+LdYNbIZ~k2` z-?7z&G>-4v>JMVyz11bezK5$tLML$M~(Aj}H>u>&Dm+CV*uWCf% zYBl0&HR5VD;%YVGYBl0&HR5VD;_I&(wHk4?8gaE6akUz8wHk4?8gaE6akUz8wHk4? z8gaE6akUz8wHk4?8gaE6akUz8wHk4?8gaE6akUz8wHk4?8gcb8akV&cwK#FLIB~T& zakV&cwK#FLIB~T&aWxikH5TVSi+vF4PvL4T;%Y3;ecnB4EaK`m;_5Bp>Mi2xE#m4e z;_5Bp>Mi2xE#m4e;_5Bp>Mi2xE#m4e;_5Bp>Mi2xE#m4e;_5Bp>Mi2xE#m4e;_5Bp z>Mi2xE#m4e;_5Bp>Mi2xE#m4e;_5Bp>Mi2xE#m4e;%aW<>VD$te&XtW;_80l6LuMO zKXG+Gadkg&bw6=+KXG+GakV~iwLWpRK5_LKarGH-^%-&X8FBR)=ROOsk@|p`*GSz! zT&+f2twvm}MqI5%T&+f2twvm}MqI5%T&+f2twvm}MqI5%T&+f2twvm}M$EUPZXm8! zBd%5>u2v(iRwJ%fBd%5>u2v(iRwJ%fBfjghRwJ%fBd%5>u2v(iRwFiNH4}05J#qCt zarHfM^*wR*J#qCtaWy@0H9axkSjXZ;Q=d^gFPi#{m={fb#`)haylCn(VqP@$88I)K znvd9+t$DQ?wO6YVSE~_Ms}WbL5m&1bSE~_Ms}WbL5m&1bSE~_Ms}WbL5m&1bSE~_M zs}WbL5m&1bSE~_Ms}Wy*4|yK)bzwWk!mbro=7zoF;C>xi@Ly= zCsK{Yxz9$U#v-0Q){FYWn9owJJzTv-T)jp7qh-BCT)jnHy+vHTMO?i_T)jnHy+vHT zMO?i_eC8#i-XgBvBCg&duHGW9-XgBvBCg&duHGW9-XgBvBCg&duHGW9-XgBvBCg&d zzF}E!5&wEwZxL5-5m#>!S8owlZxL5d6Ib^WSN9WF_Y+t56JPzoQTG#9_Y+t56Ib^W zSN9WF_Y+t56Ib^WSN9WFQx8{j4OepwS91+la}6J`tht7(xrVE`hO4=TtM7)Z>xZl5 zhpXj>tL2BQ<%g@~hpXj>tL2BQ<%g@~hpXj>tL2BQ<%g@~hpXj>tL2BQ<%g@~hpXj> ztL2BQ<%g@~hpXj>tL2A3w5;WatL2BQ<%g@~hpXj>tL2BQ<%g@~hpXj>tL2BQ<%g@~ zhpXj>tL2BQ<%g@~hpVrLtFMQvuZOFzhpVrLtFMQvuZOFzhpVrLtFKqPdTsSruMJmU z4_99gS6>fTUk_Jb4_99gS6>fTUk_Jb4_99gS6>fTUk_Jb4_99gS6>fTU$1uc+Ul=f z8?L?{uD%|wz8g#E*z8uD%|wz8SCUDtWTV8TzkH8oNpZG8^`&^alUb! zZye_v$N9!_zHyvy9OoOy`NnbncASSC=OM>=$Z;NWoQE9eA;)>haUOD=$Z;NWoQE9eA;)>haUOD=$Z;NWoQE8@HzBqU0=EwWw+{lh4+6IjqIUZr>Te$eZXX10?*ne{1Ma;P_g;#7 zFU7r=;@(Sf@1?l+Qrvqf?!6TEUW$7+#=WEB-cfPysJM4j+&e1n9ToSEihD=Jy`$pZ zQE~66xOY_CJ1XuS759#cdq>5+qvGCCaqp_l}BtN5#FP;@(kl@2I$U zRNOl%?j05Pj*5Fn#r>|q{Z_*LR>J*O!u?j7`z(Je;eIROejnj}AK`u<;eKD^eqZB$ zU*mpX<9=V`eqZB$U*mpX<9=V`eqZB$U*mpX<9=V`eqZB$U*o!+o#AeXqlP zufu(>!+o#AeXqlPufu(>!+o#AeXqlPufu&;#C^NNeY?YbyTg6E!+pEMeY?YbyTg6E z!+pEMeY?YbyTg6E!+pEMeY?YbyTg6E!+pEMeY?YbyTg6E!+pEMeY?YbyTg6E!+pEM zeVfI7@5O!Z#eMI^eecD6@16TBzxU!|3b>d8E~bEsDd1uXxR?Sirhtnn;9?56m;x@Q zfQu>MVhXs}2QI#Vi!b2f3%K|KF1~<^FW}+}xcCAtzJQA_;NlCo_yR7zfQv8S;tRO= z0xrIQi!b2f3%K|KF1~<^FW}+}xcCAtzJQA_;NlCo_yR7zfQv8S;tRO=!rZ>d&EIuU;)%F;A}*eYiznjZiMV(oE}n>s zC*tCXxOgHio`{Pl;$pbC*di{rh>I=aVvD%gA}+Rwi!I_}i@4Y^E=G)t5#wUSxEL`m zMvRLQ<6^|P7%?tJjEfQDV#K%@F)l`oixK1e2{?ZO&YytuC*b@EIDZ1ppMdix;QR?V ze?slz`}G(1$N3X*{sf#q0q0M^`4e#d1e`ws=TE@-6L9_noIe5QPr&&TaQ+0GKLO`Y zsGUEd{`?6ze*(^*fb%Ed{0TUJ0?wa+otOQd*!kL5h^>SDhS>Vphls74{fXFm+P8?U zv;BNUiN!p z=UcmVsK51T9P8Hj*0bYU=jP*jHBZ;8`M2NGv9#OoiS=(CjMMrUzjbrm*3*1iXY*|R z&A;o?ei`GpUk0~d2De`Zw_gUgUk0~d2De{k?!VkGgWE4tyZtitw_gUgUk0~dX70b- zFN51JgWE5I+b=V>FZavf_RHY*%i#9Q;P%Vl_RHY*%i#9Q%>9@9WpMjtYPVme{`Sk@ z_RHY*%gp_k`(<$ZWpMjtaQkI&`(<$ZWpMjtaQkI&`(<$ZWpMjtaQkI&`(<$ZWoqZI zt3N*^Zodp}zYK1_3~s*+Zodp}zYK1_3~s*+Zodp}zYONn=HJ8Zm%;6q!R?p9?U%vr zm#LkBOx zv;8vK+b@H)cfHy#(>VN)xcxG?{W7@yGPwORxcxG?{W7@yGPwOR*nS7TO5A=K+=(cXR;+{&{E)c)GPwORxcxG?{W7@yGPwORxcxG? z{W7@yGPwOR*mbcV0k>bKcKa{tZ(jp$zYK1_3~s*+Zodp}zYK1_3~s*+Zodp}zYMlM z_RHY*%i#9Q;P%Vl_RHY*%i#9Q)ZY2FUq*ZTWpMjtaQkJj`PeUm+b@ILFN51JgWE5I z+b@ILFN51JgWE5I+b@ILFN51JgWE4td)KS|GTPfOgWE5I+b@ILFN51JgWE5I+b@IL zFN51JgWE5I>5~02xcxG?{W6#yc3-t$Mtl2ZaQkKIZ+|W}j{P#Y{W92b?U%vrm%;6q z!R?p9?We}=r^fB4#_gxZ?We}=r^fB4#_gxZ?We}=r>?#0)qZO2?We}=r^fB4#_gxZ z?We}=r^fB4#_gxZ?We}=r^fB4#_gxZ?We}=r^fB4#_gxBz2~d_)Y{umjoVL++fR+# zPmSA8joVL++uwxS--O%WgxlYQ+uwxS--O%WgxlYQ+uwxS-&A{lzuMoVz5PwN{Y|+2 zO}PC{xcyDI{Y|+2O}PC{xcyDI{Y|+2O}PC{xcyDI{Y|+2O}PC{wfFa{{Y~22--O%W zgxlYQ+uwxS--O%Wgv&31%P)b;FM-Q1fy*y}%P)b;FM;h>N(by?>V7M~gg)APzVuIL z$}iFQn?7-9RQV;emtSH&)?$B?`~$fB61e;lxcm~h{1UkQ61e;lxcm~h{1UkQ61e;l zxcm~ecfRG9&|ZECTz&~$ehFND30!^&Tz(1Mel*;EG~9kP+_MR{Od!KJV+G_m8ei__;G~9kP+%V{}?X+7%u-9F8>%V{}?X+SnWMu`uF#%{A2o*e+-v@43~cln`eK& z%0H&P{A0NMW4QcdxcpEH8ZoZjclKc;{A$8h<_ zaQVk@`NwekJ#qUzar-@S`#o{{J#qUzar-^7_3!Uj`#rU{-xF)^`D(vsQTb@SjySMy}*!OUG9kK7^@;zeT&*g!{zN^a*iG81! zHxm0kFP|j#eO{i)+U1|Dzr2*#IPz6u*BpNW0n zuHAR<`uiTyn4udF3I;dB|}da-4@8=S9c)$#H&ioSz&&=fh`D+fTdAYnY#0dwz19pB(2W z$N9-|esY|j9Ooy;`N?s9a-5$W=O@Sc$#H&ioSz)$C&&58aei`~pB(2W$N9-|esY|j z9Ooy;`N?s9a-5$W=O@Sc$#H&i+};7)o(0^V1>Bwm+@1y8o(0^V1>Bwm+@1y8o&}tb z9p_`m`PgwjcASqL=VQnD*l|8~oR1ynW3Qbry8e9ZI3GLC$By%{<9zHmA3M&+j`OkO zeC#+MJI=?B^ReT6>^L7g&c}}PvEzK~wev;SpN}2qW5@Z}aXxmOj~(Y@$NAWCK6ads z9p_`m`PgwjcASqL=VQnD*l|8~oR7Wsu2(*G?fKYoK6ads9p_`m`PgwjcASqL=VQnD z*l|8~oR1ynW5@Z}aXxmOj~(Y@uf6M)k6n8{cASqL=VQnD*l|8~oR1w>!`*lHYPiQA zU;olwus(4^L7g&c}}PvEzK~I3GLC$By%{<9zHmA3M&+9`mu|eC#+MJI=?B^Rd^? z$6kLvcASqL=VQnD*l|8~oR1ynW5@Z}aXxmOj~(Y@$NAWCK6ads9p_`m`PgwjcASqL z=VQnD*l|8~oR1ynW5@Z}aXxmOj~(Y@$NAWCK6ads9p_`m`PgwjcASqL=VQnD*l|8~ zoR1ynW5@Z}aXxmOj~(Y@$NAWCK6ads9p_`m`PgwjcASqL=VQnD*ylb=A3M&+j`OkO zeC#+MJI=?B^ReT6>^L7g&c}}PvEzK~I3GLC$By%{<9zHmA3M&+j`OkOeC#+MJI=?B z^ReT6>^L7g&c}`~KXU9D$NAWCK6ads9p_`m`PgwjcASqL=VQnD*l|8~oR1ynW5@Z} z=RQjxJI=?B^ReT6>^L7g&c}}PvEzK~I3GLC$By%{<9zHmA3M&+j`OkOeC#+MJI=?B z^ReT6>^L7g&c}}PvEzK~I3GLC$By%{<9zHmA3M&+j`OkOeC#+MJI=?B^ReT6?D($B z927VoJI=?B^ReT6>^L7g&c}}PvEzK~I3GLC$By%{<9zHmA3M&+j`OkOeC#+MJI=?B z^Rdr;mOgfzj~(Y@$NAWCK6ads9p_`m`PgwjcASqL=VQnD*l|8~oR1ynW5@Z}aXxmO zj~(Y@#~=Lcq0@#R-fI4vo{wF7K6ads9p_`m`PgwjcASqL=VQnD*l|8~oR1ynW5@Z} z@n&lenLc^*ljnKnW7nRK9p_`m`PgwjcASqL=VQnD*l|8~oR1ynW5@Z}aX$9Bed%Mz z`PgwjcASqL=VQnD*ylb=A3M&+j`OkOeC#+MJI=?B^ReT6>^L7g&c}}PvEzK~I3GLC z$By%{<9zHmA3M&+j`OkOeC#+MJI=?B^ReT6>^L7g&c}}PvEzK~I3GLC$By%{<9zHm zA3M&+j`OkOeC#+MJI=?B^ReT6>^L7g_I*;GJ?y)sd~VqHOnKh0@0{|#Vc$RHg~Ps! z$`^-yFO^3Q=VQnD*l|Ag+WFY)&&Q69Bd;AczI=Dsapl3o<|98IHcxr;u=&fUhn<%^ zd)Rl&+I`Qgzwexl%(7-tsCDpwx0ah*gErR<9zHmA3M&+UOOLn z{rSVOarnlu@%hQI)d>- zfAe%*ntwia$I{Nnj`inb$Hr-WjNiIBZtH12t+RQy{^s9x$;WQYeC#+MJI=?B^ReT6 z>^L7g&c{CYU;5Z_KK9!A*z3>7j`OkOeC%`orH>uwW5@Z}aX$9Bed%Mz`PgwjcASqL z=VQnD*l|8~oR59(zx1)=eC)OJvDcrE9p_`m`Pk?FOCLMV$By%{<9zHmA3M&+j`OkO zeC#+MJI=?B^ReT6>^L7g&c|N6xMBVIUT{8koR1ynW5@Z}aXxmOj~(Y@$NAWCK6ads z9rI7}vEzK~I3GLC$By%{<9zJ3iyPKo{1oS7$NAW?j>|L0@J z`PgwjcASqL=VQnD*l|8~oR1ynW3RpIm5*J!am0CXK6ads9p_`m`PgwjcI-cSv;99G zJI=?B`H=b8aXxmOj~(Y@$NAWCK6adsz4oqGK6dT-*l|8~oR1xw4<9?u$By%{WB;l9 z;Q#s9aXxmOj~(Y@$NAWCK6ads9p_`m`Pggcqo_Y01^L7g&c}}Pv19+K z`{4ii*l|8~Y<>9HaXxmOj~(Y@$NAWCK6adsy>>o|`twoXeC#+MJI=?B&4-U2=VQnD z*l|8~oR1ynW5@Z}aXxmOj~(Y@$NAWCK6adsz4oqGK6dT-*l|8~oR1ynW5@Z}aXxmO zj~(Y@$NAWCK6Xr(_}FnicASqL=VQnD*l|Ag+Phx*cfInl>ywWiJ1!qP&c}}PvEzK~ zI3GLC$By%{<9zHmA3M&+j`OkOeC#+MJI=>md)F%;yY_tSI3GLC$By%{<9zHmA3M&+ zj`OkOeC#+MJI=?B^ReT6>^L7g&c}}PvDe=9%EzufA3M&+j`OkOeC#+MJI=?B^ReT6 z>^L7g&c}}PvEzK~I3GLC$By%{<9zJ3_xCFwyY_tSI3GLC$By%{<9zHmA3M&+j`OkO zeC#+MJI=?B^ReT6>^L7g&c}}PvDe<;uYBy<^ReT6>^L7g&c}}PvEzK~I3GLC$By%{ z<9zHmA3M&+j`Oi&KIe3R|GE1uAG^L7g&c}}PvEzK~*!u6fe2;Zqy5I7#>!ZErOaI>I^RchSU-;N@K6ads9p_`m z`PgwjcASqL=VQnD*l|8~oR1ynW5@Z}aXxmOkG=NJHy^w9eC#+MJI=?B^ReT6>^L7g z&c}}Viuu@aK6ads9p_`m`PgwjcFgD8^OcWXdp>roz2{5+p09lD`s8EB`PgwjcASqL zn?D~r&c}}PvEzK~I3GLC$By%{<9zHmA3M&+j`OkC-t(1@U3)%uoR1ynW5@Z}aXxmO zj~(Y@$Ih3J9p_`m`PgwjcASqL=VQm#zvn9-yY_tSSbNWx{yks$*!9WBj`OkOeC#+M zJ2rnlcASqL=VQnD*l|8~oR1ynW5@Z}aXxmOj~(Y@uf69hAG`K^>^L7g&c}}PvEzK~ zI3GLC$By%{<9zHmA3M&+j`OkOeC#+MJI=?B^Rd_7^OcWXdp>rYj~(Y@$NAWCK6ads z9p_`m`PgwjcASqL=VQnD*l|8~oR1ynW5@Z}Yw!8W$F4meJI=?B^ReT6>^L7g&c}}P zvEzK~I3GLC$By%{<9zHmA3M&+j`OkOeC)ONeC1=;Zk)bv^L7g_8ps# z9s9n`FO7Zo=A*{Ghx1os-^ux|vG3>n*w}Y66Z zL;dPEuB-mUNBxYa`X7Idi_WoAr_Qm%I>!#{96PLY?6A(U!#c+f>l{0*bL_CrvBNsY z4(l8{taI$J&auNf#}4ZpJFIi;u+Fi=I>!#{96PLY?6A(U!#c+f>l{0*bL_CrvBNsY z4(l8{taI$J&auNf#}4ZpJFIi;u+Fi=I>!#{96PLY?6A(U!#c+f>l{0*bL_CrvBNsY z4(l8{taI$J&auNf#}4ZpJFIi;u+Fi=I>!#{96PLY?6A(U!#c+f>l{0*bL_CrvBNsY z4(lAd$~hOUc+RoII>!#{96PLY?6A(U!#c+f>l{0*bL_CrvBNsY4(l8{taI$J&auNf z#}4ZpJFIi;u+FiooO98N=Nvn%bL_CrvBNsY4(l8{taI$J&auNf#}4ZpJFIi;u+Fi= zI>!#{96PLY?6A(U!#c+f>m0kvHC{T$PPxvp!#c+f>l{0*bL_CrvBNsY4(l8{taI$J z&auNf#}4ZpJFIi;u+Fi=I>!#{96PLY>?+rI=^Q)dI>!#{96PLY?6A(U!#c+f>l{0* zGwQTYOgU%Tb#`4$%+`|6gx~02ZCLAtT0zSlX%Sz^(I9y9jghW=UZddDua57Z)+nf3 z!^M;w&?tC0#qqQC8U=NhI<9yk7Cd>-ar1GpU~i65Q9UyX$AYAaj$6GN1oL8!e=QIM zsVy8gAD0}AZtnPw%MF7M>pA|rf5YI_QjY7LY7lI_=X8ad2nL@X7I9kt z&@GQ+&dg37GbAeKEN$199CIEvWv%0m;W^pQPC4fM?B~ftqj=8MHlO2|^R}udWnY~j z+ZyLqw|cE$Qhmphjwc3RtaWW^x;8NwTG{dDR}zDfbDifG(-MQdH#i=(BrzC1!FhJr zofuTl=Q!cUTEU39?z)E_uNBM=9C!MA?O;*d|Nc*F2Yur0`uVOp!M65e zBLBad)i&mw>GJ1CN9DDq*9|7W@3_YAb%WM_JKj?-DX5bCY!q`-@1)?~G{=j^Bn7*+ zI)3$qq~MJ_&qXoE1|^N_yI>Ej>9Y3?PcF?kgo5MW|)d-Hq=Pl<|7gTa{DR21S#p?W%i)j)5cd@R-=l_xL zzl-%iZ&x1FtsIo9=eYEY%E9_Pj=#!YCFpe0&BNl)RSC{~?|68ws=qE}=wtdkt=Y@~N`;GIzo#Oq;e@kk4 zyq`HQye!`ToFne{nfte#FFsJDm75P?K3P1oZN%i0-nZZ7%ENqe?i+3DCuw)Pe@i~OyxuYS`DD~G$K;dW^0$o2$tTy2b4)%Nb)9QF`Q+0n zj>#vTR^1-OlTRj|XdW^7UxgJC-OjZjlkGDclTQ{;xHGDUeDY&_-jYwcv~zQqe6r&+H_yo@`CB+9pM15; z{af?r1#d@_EjtA~8@*ORW#$tPPH zxPB&|tSj#NlYFu--f!fSFXH`4K6$dC>re7Y%1IYbKKXNkWAe%UQ)W8nFrRGt`qhZZ zC#4q8a^>ND`p7BAVCvPruOg{Pf2gl@-Ho0a;^^i~As_dA2Qt(#C z#v_n0#{QcE{wCLS5XyC7-OkI6bP9eDcm%$K;dPC)1*G@=3Wb9FtF$?RQK* z>3GpG`J_{6_ixE3Gut{QpQs-4$&k*@fqb&Dq+{~Q-u=#pe6nhWWAaJuc8-Eui5 zpCo?f>L;H}80VOLQoEgF^2x_>AM(lcxF`AKv$#L`q;kAn zR8BtGw#hO1WXvVUEe)37#0h63_c%L4u?3jEq{kV%EpVV9A zn0zwh3CHAe`J{5XWAaIxuN;$4TJ3a9KFM{+G5MtC1;^x* zYm2)&$tQcW#rrn&9R0ZKEAmOfMvloRhjTe5pWM6C#gk78PH{{=`ST9Pe$>-{adL%)TGr24VII`8Ei%Psq15mGjL_@qCMe zsfTZLF!l584(7Ui(}VHhTOW)k-vD9!`8EjCE|s${s(AKGRS)~9s-OK;U6*}b`LG`= zPxfi$&;G62#lEiEOS$@ic=ZqUsNbkx{mFIJ&-keS@zl8B&)E#Mi!&Q)FK07g`hl|< zF#W^X448i7Yz9n!ayA2|pE;WWGhUp{fEh2&X26UWXB$+`nFqyl76PUo&Pc%2&)Er> z>vE<7#)q>OFrJ*vfEh2&X26V>%4x6S=?B$A|EPZYP1mJAIdT0Kh&dsqki=#*Hu5`qyEQJ(4yG^ZQS1hP>SxSguFF`$_%J76Jed%xOcB!1cR6KpD zdgx2lPhaY~^rd|0OL@|l@~1D=F6O@4OS$@ic=ZqUsNbkx{mFIJ&-keS@zl8BukqrV zD#u0fII14pRX=Ugb!n@7=mUAuH}a>?)Gqo`?WJ7(K)m{gdem>!ul}S={YhkDd+)UW=eO#Mu( z`ky*9F4WClzvdx({hFWb^~20t_WEJwGkg6o^PIhYnEB6MKg@l>UO&wJ#a=(m{l#8C z%>Bh)xyso?S3G;`F!iwK4pTpS@i5nAj~>Q{y?Yo>_WEJ&FZTLj?k|-yKNZisRXxmS z)z3WFb(#P2;l7Y3_lx|wkJK*iFSVC)^#k$hAL>!RQNQ{#y07E?jF0*sPmK%yxn8;6 z+Er$X`B3Z))g6 z#;f+Lc_OB~LsiGbH~uttR8BqlA9qas3ky5ux;?+o6~*AwVUc4ze;Vf)|H~sBGhQmE zy^5zFR1f{5`sp`am;RIw{VY%VU;d1X+QoROy_BmTh*$qmkNS=J)t_8f{fv+LA5V>o zKVIC^D(7BTJUKx1kQ-D#IYZYam&k`4BTsUV{K-jb7r9F9rCj|$y!wZF)NjC7pa$?kLu)pnY6_*_t8(|9dm!h z+GmuvDV`C(<>xWczonjP?>eUb^HUsi-TV7H#-~k3$9T?YhR=DrbHwo_VW! zn9r)8d9Ld+|K-DdAy4iX`EwtsUEE)4FXie7;?+OYqkf})^(WU=KjWkR$5Z2i|D)fy zZ$!+Iemfj9ch+ro%$!=j$T4#*-}8={gXs@CW^OjA;g~tQ?()k~pEH*~`@}JGyv#($ z%>AMFWR$;9A|w8q6YiS{^*p}OG4&@-bZQxZtnx zVjilT`Kfs3t?FSutA6IWuFL$F5BG&UxxeJk{iSwsf2qBcs~?D0|4@(mjr!G}Tvz>! zkNO`^jSK!7FWRMY=BMJBx2lKvtooVfx-RoyKHL}bUs~I}h>t{zEwo60-oKd7dS76k>pg<`ulEb?3%z%6zvz90`$+F8++TWspOBj8y?@azl`}sT&%9MV%xBflJlA!Z|MKC!kSF(x{JD?RF77Y2 zmvZ$3@#-JyQNK~Y`jhLbpYc)uDKM{%ZC>nqOg!pvLF?!wGx&hEm@bI$I< z%zw`A!rT{}-G#YdIJ*mTA8~dU=KkXBtI9bOt9Z`J!qmeVTA2DdTMKht&fLQIa26NF z^WCYAxxYBOOF8$K%9)>vXWptF=CkT&p6j~IfBA4<$dmg;{@h1u7x$OiOS$@ic=ZqU zsNbkx{mFIJ&-keS@zl8Bukm6Ys+{?$c;>C@VLq#V=DDuR{Fe{+g*>@ms9Uxtz)^rw7%v3(z=)XOY33EwN55p>u2iGx|;g6-sZYmhvTF5Ii6a# zs*6t!*k^^=PiOxXWFoKz?5DFA2(zEg9wE$rI(vsO`|0d2!tAHB?+CM>&R!Fg!L?5DHG46~m; zY1C^GKU6m{sQQ@WKVM1=erWAD_D5o{r>^5s9cu+Go^|IRhQCld_;7>cpN`cIGX3Sa zS(Q3L$D}z?oiiV-6I>YXc=)h7!MP6|R~Qk-WS<+w41J&H6&B1^b$ z{-NWwD{BWI{q8v19kqjpi#VT2duj!nTDdbJ%=ZW4=RoND!c||5>Zh$ce|9nS!ISax zB=pVBKCYZTd%1yQ`m*Zvj_KpCPQMb>L*GBP*D+)A!q<)&t7msPW(=GE;Fz&};-X{5 zyio~PCv)M(9IhXtInv9ui#gb?v18^@@jQ;1Uz2yac;;QZmmD)6tKa3AdHTv5F22ND zRf2zhc08$B)u3E$*H`PeR}K2S;kfvwn!&O69bal#Gid%ryg%2}2y=+z>9^Df{`;}x zBXg?<-z|6CuxRz*fys`W&#e{|?C$vSYSn_fi$5Cm6*;HGtGyy7=lsyJrz;Qd<(}U; zCg)su@bRdeoU`VTV{*=4_qcyc&Ka=LF*&F4^}VBba?Yi;j>$PYhC3$bJU7`fXLzQJ zcTCR7lj4}1^HJcKoKy5KS3fz2-wfowAm@|}e@hT1=bT^Rn4H7!1X51U;r9b!at^;M z2$OU8y+N3q^VOP%BPQo$KKW3@@9FucOKKo!)PR=@PbO6Nw-DV*e(oYP^AYYRCiYemQ8oSd_rCpqV_>m8GGvc2Fu z$vN-lc1+I6Ion;AoKvBpV{*>+xFPC3gtYn7!R0d z0^Yk1C#Y%=q-L>0%hS9sM0Mo+)oRW}KHDa?JP_$T>Nxhj}rel4It}{zi_O zN9$TTW`4bYyJP0vrTUJUkKdJc%skEfkE@^gTlIzs=K1W37b2!_&ZIl0tvBa!ZKMxY z-|m>cIrF?@`s{`;9n+WlJG*~Ne?N6$TvR9H@bvSJ8QZK|+&A+mpKNo?xDD9nnDH!m z!7<}ps+9Y;jDMFlj+qy#hdCZ}at_R?v=WY)Yp?HfKFqUSKB@D%WAaH_i2+eL`J~1q z$K;a&ryY||`UcL8e3E0ZWAaIpS&qpkB_{WX>LH(W`r+}2xlebscgz~5=@&hta`MU8 zR*uOh&AxU2mVC0UuVeDbr6P{WCymp)NB@?5^2Bn-inoC;SFAOg`basbTU7zgZ2FPxvisn0&%-Tt_isKIwb9N;ppM2f1Eq z5plVx?*|)8J3cV){ougr+oSTIHoPBfZSDBkz3&IFo@ySIZ_Kf4 z|LCURU=_z-yt*mqlh5&!yEg@+uXS83&t@yn*=)1LPaC}1>Z!bNv(?{i$7Z{3rqi3v zCujB#%=4ogKQRAwML)21QQj#_%gCAddi@|x37|(j= z9pk^aK=|Je4f~LGy;RaM?NvGbpm_R6_0VsspZ?T!>1X-S|MFy9^aByU%b9t6i>U37IjQ}RZc%Bp8ioi^qcCZKXqODSw8f?JQ)}HbKlV}#_@l##!=%= z|G*kYSmOw59AS+ktZ{@jj*K=$)C&_%6VSE#FHms>f!kUQ$NognCtR9g7M)w1>?!{3&x-4 z8ce%*-odn2<@AH%=^xcYzo~xuQ`e=R<)b`FoywE2@}$bilQ8k*Ntk+gzQEMaa|h}cuv81^8AAF=eY*cE}nNV?NvGbpm_R6_0VsspZ?T!>1X-S|MFy9u!JX0E$ce=M_?78E&M*Pvxma*}L9RGJ=%UIS&8%O2y_qL2Z zva3d(>BJ?pvdO> zHIBq+9AS+ktZ{@jjE*AJs#@sebxX*QKB3L;uT@ago2q zi*fv4tZ^hp;|OaUVT~iKafCIFu*MPAIKmo7SmOw59AS+ktZ{@jj^bf3Ygf)(^#u3&y!Wu_d;|OaUVT~iKafCIFu*MPAIKmo7SmOx)dmQz=qg>BB z;`O|v9zE}eA5k7iO;i=~r{(7#_Ek9d>K9MKu6Zx|~QM)MD^MZIiN2o{77wXq@hwJKj zgpZz6cqw*=g%nNc=aD2o0dBKPCZ;8sYpp)gJ^4weJ2Y0^V_?BxI1P`Y;e!KaCAfc_}E8`XfwQnmQ zeJl1^&U~AdGc0FV&aj+eIm2>>)l!Hv@#w`{aH z*z~63t(O)Vm)o$&Vu}x4WdHWwV3F0?CHo?~)+>7!nnUB&3nMq2eU>xja)#v$%Ndq4 zEN58Gu$*Bz!*Yh@49gk5nzMh86XV}IY6~%%8?fIlpZyr!kHq_P$!9;N`tetT-UX{i zV>d3(?BLEt?)<==$+Lr#w>iFT!0ce>A6286T+3$%H@xGxz^U2cf9Kipx*BtW#ZNh| zKQM#$y)(yRj{P;q{_WDlxmM?bo^$P5J!Z@`hY#ML8@bUxKFgVMIm2>>x1Q^Wk(@MXu8|9bPS z7GHIZW9nI#)FdkJSYbghYK7xB&dm>gE!Z?F-@I;q@MSN@!=9QS%v$U?z1sX>;10)` z!)HX|zNXQA?Xx`bmnSSwSe`1!Q}KAh@`U9H%M+F-EKk_?Jhf?NSugmdBXC9<*9N!6)#WS3-sIna`t012Z;CE;2Cfn~H3==itXTY`5nl<$7)sujeWC=sA0Q;C6fd&R!hG$Dhk- z$F|$^`qT0|>^a_}&klROH+pA>tyO%MC;cf;Se~#vRgS0P@r30G%M+F-EKgXTu>W0(Eg>5uQSI_K8fW!Ku9b(cA$9o%W_7N6xzTjUJO8J06FXIRd#oMAb`a)#v$ z%Ndq4d^KnCfPe4!thNxNc>??G^4X8ky-B=3uYC4n+N7o1^I}N7bbDTW|N9<$UQAiB z$DS8&J-Nr87Z)1svFAnhf_v<;fuJ+CR(^MZKgVd~NI!e@EX zpYnv|3Ck0fCoE4`p0GS&dBXBkxtO|qefDEIm4CqU$Yuq0>bid69%9T%u zS3aR0z_y1+RyHD@UJK zNPHwnN^*Q|$s<9Bqwd`>wc4Y>*f$(+-uP&+e1zk^cRm)J8Q{3&p~tNJp(naq{E0K& zt)8_#dszJ?zwTkzy{24G%OO6?leWkcmM1JvSe{XQ+!K~3EKgXTusmUTM)96!{?`31 zZyX-m-^P98^8Pj-hHmU{^MrEEAL5las7HAt@qCKS!)=pOY<^xTlw$LC;M9ILpA)n7 zvw1#hU|-7{KFbq-dBXC9<*9Pz4S7;7PgtI?JYjjl@{HoI;>jHI?**UbPmKIwe?Iu^ z$7r4q@85Sm`!P#4gug8p|4zGacvE}d$=so-z3((_+0@>5DA)TA@p|8(9=-33&(qA_ zcg_uLX74+jersm$J1zR(X74-WuiR$uI}KiJZtpuj%ai_;CoE4`o+{V-jyx%sCoE4` zp0GS&c}DS`XSaj*+xt#JN=Nf=|4&D2*MYQ7*4`x-J6S&@Jlr{>f8OqF{r17x&eor^ z3O``|-0|iItp6$3_gLcfo%38+kG{wHEKmI93Ck0fCoIn>KJE!qC*upt6P70|PnGL? ztnYbf;@$RM^H2S|gHO}kH`r;r+6C2ralEZlyWsl3eQRy>UEAQ`FvtJ2XdA45-SJ)P z+604^Ii7oS8!LZc=3N%QEB{?qPxje&TK#it-)Yx<|A#y5UB+j5(iVBb@`U9H%QK3P zd&2UBgK>qgl=3G3`^7Y8}SMzmp_9UOc9KjoL31k7>W- z*=5CJ+6Otavv^Eaekh-i{g{5NJ$N6e} zshIY0e(h5#rhS~_cb1B2A7^@%QZeo0e48_apZ%qz#f;ci(*Eu2r6sM-*Iz7Y*NP1- zX$}e9OGa+^`z&Y5kN`OzZHf z?-Yq?9sbJRjPeuzWW?t#Rn+RaCMat4r*|l7*WKB>Xyik``7BS$3wj^m@q!RU$e7kn0w>vY=D~8sW7@Addrk3}_G^5WC;sw;*k zok?_D?%RT~9_emB>x<0=V>?qE|GK9^63(flFazaM?}V`jHXviJID<|f(u^-tH#Q6|9bd$gvuvFM>V(i`g)U_ z+j~9b$|uAtpHPqT$?u=vX7BZ5AGyum>)-#inZ4K7>Jh#h#`DSV>EUl7$M=74Z4v%< zY<&OMXL;f;PgtI?JXNlIB2UWY3Ck0fCoE4`o>9E#S>*2;_Wi9_&l=``%f9N?uDKnm zTYGmM4DY>oUhOrwn)T1Po5Fql_`dnZAFEn_9^PEl`nl|ys@DIME6)?J@uD7mfAd+M z_{$TPCoE4`o>6?<6P70|PgtI?JXNmmZ@#DIKlioo>9ZfBIY7MM7N7kX%@gAN`_5-S z=E)~d+I#(`cTUj-L+sEv8>XhwccFlI$ z_A!6Rf7&_c^+}`(nmM8x5gyjj#6P70|PgtI?JYjjl z@`U9H`<{gkAF=Op<+mKMIq=}BBQ`f0E;(Xz=G@XFHkSr&IAU|`(Va(Z?%jOuh|S6G zOB}Vi+O_Rbo5Ov_9ksbVZtGE-^EY01%3OD6jcknN64 z_8s7sKAG%0K(X^s1p|IK9I0ZwhmWZwZE-j>O}1MJxq#>dZdX8$geeFvai-vNl% zcL3_qcL1N|Nq@={mM1JvSe~#vVR^#xgyjj#Q|0;&;Cog~xyHT&)aZOoOy3VX+6)0nAKseznwY*H9@%uo@d+y%=g7uH;`d@}N<3zknNm%3>ACQefHUtf!=4c3_cm?eYW+$lY!o6`#ya#(EDuC>oDi6z27CLpSAbC zv|{J%eXwk|bM~J2_nYVJ{c-2HjPfTN{9*CypZ>$@nX~>6tH0fEf7o@K6#UcPAAOc5 z{_=$73Ck0fCoE4`p0GS&dBXC9IFrALU88JYjjl@`U9H%M-quC-=L5U-&G4V&o6|^TB67M)QPt{~q+&kJ*09Xv-&~ ze;j4`-0+(gSWlq=5=uRKFN$}{z+Otd`nT$eCDo@ZVwGtu%) zr|`eSt?yJDW=^m?bGXd}%QHU96MuQa@`UB7a^)F$QZ7$ep0GS&dBXC9ujWY}@b4F& z;&?#2`_06Z)bxReWV(WRI>l6>-huWeW$&6pXE$j0AWmdLJiV@8i^?_i>-)iN8Ey zdBXC9;@~d|AJrjc@IF{cPN?DUxFIVceYXjADGA zd|9c#&7a}#^|yP$XL-`M@`U9H%TwieDqerTBTvfZ3Ck0fCoIn>-t*k~Y?{sgVxOhi zy}anUQFf1ibo(f~_jisQWjUeano*W3avdCHIpoW0Mq6%qztCvQIkB5ZTQ2&u!f4A; zyGo6=+?6xWXv=9u&Wy5q!Dl(s7CFOmhUE;)8J06FXIRd#oMAb`a)#v$`_84`O||D* ztb3|GU%tEYv^{rnKL4~mk49#G+MZLfr-s{eZSv7!_FVg+-7qVkvt_8o=WjgJ>S^)W z5Uc;tLqqJkS8@-r=bF#*jM^CYgyk8vEA9!)Gm4LU!t#XW3Ck0fCoE6+YM$Kh{ypNe z{E5+gfc>`k?8oRHB;KDtKKn7r?GmEzqQrl8Yl3|*y}Mq5eMc=@C&9k2Qm%YLyz&Y4 zD4*2so)FVHx4a|6`1m=uOmh?LdvCeT3HBX$;E@FTKKw(r8|<8$&+?={< zPvl9tJYjjl@`U9H%MV_y z%9C<=!tzwPo~OQN%WOB=_w9DS7qIW!gTF6e-?yLLP{6)#KRmO5ecw)asz6NVW8Y|7 zAg1%N^{Zr*|B@pk{?p_6t)6eT<+u7TuE=lK&Gc%1JKN^7JZXzOVR^#xgyjj#6P70| zPgtI?JYjjlSMy}P`S*g)@+U@f0QTGBvmc{-jd*{~`0U3V?)r7|x$r;vNPO3!Une)4 z;m#`G@X6Q7nR7Z`-gsy7kmuZ)=l(zMOkS49ag%kslAA4T5dGUd3%^NznX-Qu^_-fQ)ADYwt+uXb*qUHA7{`y(Iv z)@QYaah$vVd};)lJ-I>+L(Jn@$&EKgXTD%bY`c~UM(BD3_FVhqrc`_0 zQLg78@mgz4>(PIv+IquhdD5Tq zgyjj#Q{`H3$dht;!t#XW3Ck0fC+vG>+cMJD8+&$-jOn+Y8vZykrr&`2=#P;x{Wes# zENL>e`kPuaTqkBv{+`h3C6r)+(mH1H`~pMTjV zqkMRkjQIO=Wz^ICGj|wDq~q@}w>Dgyjj#6P70|PgtI?JYjjl@`U9H z`<^=n4zTB1=f?)vxF730z~;l+`v=%OphXZWh zzH?-N&FAddp0s&Bpwg4}T=Q9;_{$TPCoE5u>$xUR%H;{m6P_3Mgyjj#6TX@!_qBg7 z_$+^7GzVb6Ek64(y4Q&J=Zw#OOvUt6`+JkwKd0K?o8&*6YJYFiBwRCSy+pazd&FxU zNIhB~*4UC7)4H+4n_+x>-|dlbeWG>dt-ZswO8k8IncGwC?@gWy*FsuX`z%lTQ=YIq zVR@=t>uPyYE>BpVusmUT!t#WD&r4wr)Vg|d?;++NYZ2zyc)N;M2y<`z?`tYvH^lm( z&FR4z{j+zl_1n?U2U~wW@!??W=U~%d>wn7izC*m;gF1xu=zO@(^2A@BusmUT!t#XW z2~#KI3(FIhCoE5u>wLKHS*+YJ`@66fNyB3LeZM#F8Wz)D_QJ=9#q|4rB^k(_0R=I=_8%xLqsh>EY(^=;Yz{H)1}^ znRdw;mNP78SkADVVL8KchUE;)8J06FXV`bveZl?iJNxX%s4c|%^TcPxa4pRr;>DEf z-lW{;y!S4*b0$f-m)m~&^iRUyGL7FCZAXW{aT>obdf&dx_T|^*Ulu5DeEQ254V5Y&XD*lPue0+Se~#vVR^#xgyjj#6P70|PgtI? z@7eqK`e=Nahn=%-2y{lVT%iqi*68+98|)0y>E9zht1ZN+EwDdNeD-5Be~9<*N1y$el>A%mzIZs;YV-5P z{#$L{UV3Y*&F99ax7s{ET<0^J{~Mn9%r%)8Cv2e;j3^*k_Po7I2)2ixqr znNDo8`@&~=(x38#yws7~Vj zKKVDxS#ybazu$cJV>I80_wQey{g@>)o7g%(7}&(t`6t^pv336E)tlHle@{XaTj&3C z{#IM(UwiacTj#&@&8@c1FZTJZw$A_c(_3wwPr24J#A`i6JzCHBEKmAhp0GS&dBXC9 zHo8Q(Pa zP(Q~HEo>TlZHwc_-ftSKU&%RK{Hkee@Epgp4>XN6FXr~|&ivRk)-wKkMDPFHG{$}( zZS+~~qFn8Q)h<}=g4Hfq?Sj=VSnYz9G{HqXBf z`&s+Zk4|*=1)e_3lX7{&@`UB7ay%7}CoE4`p0GS&dBXC9e}j7PpNOJTm66kR^6_9Hd77zhUT+8=_`4{@`U9H%M+F- zEKgXTusmUT!t#WD&vmU6ZT?s9lxV-zGxd=~`wgErdL-I!`?TzyXutV0u4|(G7SN0B z6YV#GRyIkr-wwL3YNGw7Q2qjm_FF^a&)2lyAbMs`P5W)4_3LWdZx-dBUelhNKFgW5 z$QhP1EN58Gu$*Bz!*Yh@49gjoGc0G=cOI9ysy)|A9IRsZ^_TBfvHShaSE^VZSU0?i z<%a_gSFybD;~iBjpY#u^Sf065D~yjn*S@Gx#qtv6S|<~)bu#s6o$Rwb@s}qoPgtI? zJYjjl@`U9H%M+HT%C%1RJ#}Ajzx$p(`!Sji#QSaW*^kkjA>O|qefDGetgdPMdKc%{ zw0*tNuhg`Cz4qb!)cH)xwXa9K_VuVo`+ARUt!evujSh$L@qN9-YZ7f=@1D|$wy*a_ z(?r|XOX!(s`+7dhlfIQFEKgXTD%ZZAJSmqaEKgXTusmUT!oKILm+IR7d*c#Gc3vf0 zEXmHR6zGy<=T%-Enq=oy4!x9Q=T+)0PO|eVMK&bad6k4ulI*<7&M%Veyh_#WNp@bP z*tR4)ud;4)lATv+v??hY)2Lk@%b9XH!*Yh@49gjoGc0FV&aj+eIm2>>RuA6wdmhH>?EKmI93Ck0fCoE4`p0GS&dBXC9yu9p-eh}ixBPXJ?ZK5xC}(?f*{hecJ-gg(%Gq9C zmy~k0-&gXb4DPokBWB>K1BjtK-60dbT^=RF` zymtkA{_buU#>dy~hig@^=k?|rD%f+p@9FaPe9!zvd0VUaEKmI93Ck0fr^>Z%mnY@& zgyjj#6P70|PuTYy68?6s_UrTHFKhnqoeqDSH~zhPR`@%;`i{M5Wf|*-?bFL-^iNtD z>$isol(GIi(KC#XuTM6HzX_~wER<_~LcG=|yTf|4KJi(e_{$TPCoE4`p0GS&>ePO{ zJSmqaEKikded2rSUf_QBJ$?3LGzW_F2 zeUfQT1zVr^EKmAYp0GS&d8%CN6M0fDPgtI?JYjjl@`QcQ@!^_Tf4}qBJyp#A_95Y# zJl?Ly!}Yn^`@p&?)(>@eR>|m}pQ>2D&HuBC^=FZ5s#-s{2;T+N|CH-|An`gMSUs#q z=L3C~C;sw;Se~#vVR@=t=L3DuUb8FNIwTlZ$tD&v%^vDd z$MZw;zwb*}7O(XMq@vx??W zre;N3llUxW+9hXL&aj+eIm2>>6?+nRjAQ^~ege|Ai= zt>F*6nrv(PGHa7<&A)hOvb_tub0*o|5uQ#6?A@VEt-x}N&vK@3=GA&+^1yp0GS&dBXC9^)`vmPYozbN9SP_P+De(~azXXW0E2 z<(2AW#Ah#%QBQ%tVpe~H{V}_4ldUn!Ek4VWw#XBfCoE4`p0GS&dBXC9Z{g`(ju5a%pU0DJJ)imWWLxJSTAXa_|H;oK+k3%HVb0fi6`$pazdT`i!tzwP z-fQGZxjbQc!t#XW3Ck1qJzojG|LDEukEKcW4Y}I*B>T2p`iUg_=KM;VB>NV9Z`~yO zMt!+-l6|`_c72k4)4nNdl6~ub1MmQQ?^C;cf;Se~#vVR^#xgyjj#6P70|PgtI??^!tSla@~= zlz7teN#+VqT0Th(|7Jw*>69y<5U+efJ<2DgFAlJL()`c>%O~x_zfaM3gPO00f2$Jz zp76ud11z5m4F48J`NU^=;xA8Fp0GSsu6!a-%H;{m6P70|PgtI??|EWNAIm4tyxzzB ztEKj_cIA4YkF~c*tdI3WtX!Xr{>j(J`t6%*`dEKH@YfU8&sEMnVf|0JzLOBI?3Ck0fCoE4`p0GS&dBXC9 z6Z#ZNh2*6R7R zUssszAYQJB1@sVQo`*l9c6MuQa@`UB7a^(|wQZ7$ep0GS&dBXCH;yuqYtE<}Y z*R8D=?j^T%zdf~mWBB(KDUP$&t8TwvSLV&?_WN};^VP85ubcL0jX=NuP-t-t`~A8L z-`B9;ulxIK4g3ANUKeWE@7LY*a}E3bx~U)4u-~s+HMT}Hra1d7XUgRa%Ndq4EN58G zu$*Bz!*Yh@49gjoGki5?=AnO&_^h@Nqqzb5?ef`=(LG4KKbL&=W2T%f8t8q$YmH*| z_bK%{6tlliIp3|A{e24MTAvfI^*QxueZF#T(LjGcczaS&`@4*%Hy5$L*EriCyhq~e z^A*bq+uwKmr+8ue`xKw$Nq@={mM1Jvm1})2Ps-&9%M+F-EKgXTu7V7c-+~@fJCFTFbb+_>*l$PQTqUplrgX1WdF^+n`_{{6yypFU7V}A%h4r_$ zcdxzP>TFsj!LIfBGYRI9`bC2MZIsV)rY&-YN+t$_f>*cofcI6JaZ5^I1CAY25 zuRNRE*6saY&TZ@YpXY?}@qLHF^K#qzpK|Rx5U+g)>e0S~&+?>iCELj`%x=U8}^=9Om%*S2^sR(Puf+E;++;hUE;)8J06F zXIRd#oMAb`a)#v$`_5IyWQ)d~dAoj4Hk%Jk`ed_tazn3dHh(DBydqxfJ?hbVuiUHI zGUn&oVSN1k@%LTXY(D4zBb&|hM+;@Q`Tupp?DqcXvpn&aCoE4`o+{URPo9*^6P71@ zCGH8!6P71@HBb7@zejwQKQWpQu-_J+{TSVY#QXEdXFsMz_}|#lclG_NGTC>q@sq;; zhF5(3@Ob#&^U`;}L2WYGcd*%YGTC>q1*J3Dcd!}>ne02*yV=9|_<5lh!vA)dzC%*3 z=K}G1E>Mr23qH$}{*)&yPgtI?JYjjl@`U9H%M+HT%Jp3EJ$v@bV&AK$rDn0ScIRKt zVrTHqt;k~M{l43t#m@WfJDJ7K`&G%8)z15!tdYU7yR%wM(*arS-(k8A!=u6aeg*2&bPb#iLX>>2a(Og5XhtHOMu`8;V=m|NoWJeZWt=Krq8 zv)OlSpXG_aJYjjl@>IFj$?~LJp0GUO1#wSUp0GUOt9f$2`}c^?@+U_Aus=6^_G2_> zi1+VDpZ%Eo!!?8Q$!|~Rw*H*mFIFd=Z}sqkytbdU>eIZo&sE~ryte-}E?+(?PfyHe@t51@ zvwBYV&u8^-8=udv`{C>PEQk0kPue0+Se~#vVR^#xgyjj#6P70|PgtI??>Xi~g5`}X z7ZPkw_L0mt*k0|x@VCeH-+C*2?G3iKd;gUL+w*shj{;f^x2PjxA(>5OV_!-VZUeBh2$bb9p6^y zLh{hPjvsAwK6zSY_qXk>+WwV%PcO$6+Wwh*<21)}Zu=v7)0>W8PC93tv+7xkIbP*= z`?p^PXROZO9y@Kxja)#v$%Ndq4EN58Gu$*Bz!*Yh@49gkz zo!fl8FInGd*WA7@S?_WGxx6=7?{}k)>`m6b59M076R&kU^=RFGL+|~``c8Ya{()qz z+lN*>n5=!DNr{J&buR9PJAX(%*Uo+0?4NQtS^GXd%M*Wj!t#XWsdBB`IFryRYWS{qElvKFgmN%>meNi_d~~J~7E6oiH~+VWzb~!d{Qn>+ zEvDc6zq>{Fd(`pY{QtXST1>zBU*n0in11uW`!gBkd0)(kf9>^*dR|$PQU93tGOn9> zYlhEzJJMqMZxamuCXA2&Hw*H88~(<1{I^YfR$FMV+5)RBu-XEvEwI`Gt1YnF0;?^s z+5)RBu-XEvEwI`G|GO=kOO$Jl5wCY2>e0Io^=prS>*{Zv@X^{EPp!%E*S$cySi|Gs zGku7I-1J@}2g>CD%K?@HEC*N)upD5`f9`8BJqiEu;o^YxB>ZdI;(+xe+_KT)fb}H2 z_0l5aavK&|O!1+M?BCuSEV4SgWM5?0dS%Z-bC4(gKFgVMIm2>>UR$N2xYX3BzSKaPJ}a`b{|pAJq9`;9!Qa`HS(JkJ`KdU)2r9V;w|_6OlN z&drbZ4dKn}=12R9@UW-mNBfL$dbRn{{v#|moPCxjo;6&5U|JaL`PfKTlPkY4fVa$?(5<8vfogF|Ah3 zuz5H=bw1{_=$73Ck0f zCoE5x`tgM23Ck0fr^@kEygVDdv%}Uc?GJo!>lUB=m{(h*+qxxT?QUDQ`0U519{OZX z={=TvD|XvsIl0;Edn{MCPv2uXd|$3~%k2~Erd!Ux>;80m7Bospw`ar$sp>KBjWMJ1L&;V=(n-9e#Y^c3Yp%UcBAb z?P=lf32Qz7Y55(t&hOD@hpqp0Z{q2*JSmqaEKgXTD#ugtc*638PE9;!d3(fd z$1I;8YJJS|Jmt#&#A}^HJ$hbj{N<=UN3y?j)SfS8h8?x%&i36P70|PnBz(BTvfZ3Ck0fCoE4`p0Mw!{$vghsh4j4-~YbH+BIdx9&7JgPwugP zxX@@%M*oC!K>b$w{P)(MwT^vn{k%JT9%-FPxt_Dc>-pu+AD`ukzdT`i!t#XW3Ck0v zPCaMkNx3{>d8%B`S>My2+b6!-Z)>gPSN7W)Y+>yKwl?dNa=_MXgH|4}wOrwI2W-7J ztL{PLVCX@MX};m0{oCAs9<(~MRz76c`mEz2bMWsepXE%u&GO0TZ8};$@!5~b-@3o$lWWTLw0z>TA2VuTU&|+*%0FQF#AiRo z|F?(7_P6=Dae056w?jAfxA{!D@(JP(OAXI?rn|GNy-uwB=a^1s&rue$T3{O>rxV>_Lk|9uDenI})q{~iQ9 z?0{49zXt(tv*?tFAAj0_$p7xg0nyIGg9b+X+q^L_`c2QHl-0>t)CsE-Rwt~^Jinw9 zRwt}ZSe>vsVRh#DiOyYT>>c+zCw}^mxZg=R%~|zOzqsF7H0{v1-$^;mu^sAJHvFiV zrycgkQ89n}r26QX*WJ11=$P-7ozO4lfwbxT@Y$99;yLYgjgN`vv`1}wOw2Qh`<#}1 zpMR>2I;5;l;_8Ie39A!UXP#fu39A!UC#+6boyL7mo9cY}v;E_~=FZ2f;=U&3G{^c= z=RbNJn(v2#uX^*4e4iBj;?alX`={XD-#s|rSC!}YJ~-cR1t0k6LHRx`c-FQDMf{j+ z4vhRaw>&V~sXOz4Xn$6>1EOEGF~*eDNnD+df;?I$?Ff>V(w^s}ojdo}cKn zo{aaS^Qz)Fsol3Kj-RSNRdHMq_x^=^?_X%gz3i}_hjGVE4|-2D*G;<_k;WY z&@x~DOitT6ttweR0Mn+vT;8EozK)vshTU4_>#N~ivTp!-e@fiz2Kin$)Q0Ai)k$2P zusUIN!s>+839A!UC#+6boyNUxq&mw6Y?IfPaqZu%SzdGUQ%-ZNKl$6wYo4#MhhM&} zdA{}@e*Kc>`8t32`=QPAb^h?z2Q<&u`NLOtY@V<4hu_(_h9`ZyP2`Mwahv$RGw<3a z+MGROo9L_ZoNYpbI?vsVRgc(&Z{48R>`^!#YzrT$^V3ngLjCXiiz3#MKF_6IQ2j z??=>0T%E8wVRgdlgw+YBI;X7LB=;g8<0B1okMedBPIFSO{#%oLeJuaCU*{(Ix>@+Z z1DfRPY2gvWn&j(j;eTJ&Bwv3EZ~sV>d|fVl?T0n-@BXOCuh)F5XlI>@t)l%8`fe5d zrpHgp>SQeHgw+YF6ILgzPFS6=I$?Ff>V(w^r#d}u8Sj7hZIrKxh5u;ZC|@fJFWk>4o3Du3^5` z7yf2e!+Z@ey#E~y^R>b7{KV^&)y!Db467MdGpuG<&9ItbHN$F#)eNf{Rx_Mxesi0> ze51*4UE=vh%4tsee`g=Fcib&c3j_KN%W$tUd<_w`SIzh~UI15D?X@-=L2e^4k@dXxH@5V!s;~c z^+cV-)d{N;Rwt}ZSedjBH?}3(nzXp%W)(V$?*YL&T^T{u_kK=anGuy}U-0H#Y<2Wbob0qS8j+FYF zvO3YPPFS6=I$?F@`6ZpOI$?Ff>V(y4+~-KC&Zj+839A!UC#+6bop7r2 z`2D|#=Tv8&xip?rrJUwif9l+J{*rjdecaq7@$P%KJD0>e@l|&%iFf5AA72vh&`(~t zB;KuWyJ|_ibANB^&*NQu|ARk|cl5)id>-%ar!4q9-s%5sqc7rJzd9LX%4#OAW?0Rz znqf7=YKGMes~J`^tY%ovu$tjivvsDP^B!3mW7&80(ir0@J1>i|k34-@)a3V@mPM`Z zePvnH@bqQNqPG3(ERULhw&n8h;+lrb!=tn6FAwkT`QNhe)bkO|DXW>dnqf7=YKGMe zs~J`^tY%ovu$o~t!)k_8&C4FI70*N34__yqhoqe5{Ac4o;ySa-sMT?uNjc529sKIj zZ=L*mYjEG5>*U{IgHLL`PX2v1xM%Hk^6$LCOXmF<*OQIU{xhyKUAM1^U-s1>ah=)! zUw_1PX5gSd;yUv{w?E=Kqc-Z0vO0;Y6ILgzPFS6=I$?Ff>V(w^s}oiyoa!9EWKCRW z_RaQR`&=vKG{^c=w|$OY9mnLjeOAY@dd%*t;~3tu*XlU7uRLgV9P<|pTpj1a-cwe` zIkNh})p72O|7vxdQ`4KTiF0kvv1{TS-1){eac-)UF{Z3$;%bJ~467MdGpuG<&9Itb zHN$F#)eNf{PBmL+>iO_?wct^`+;2+hzOfeeT!vl3MXRtX-@io zAADg=%mZhCv?k_<>tyGe&s&Ile?-3bN3`So^P_QVVqV&A|17^WU+uN|nwZD_{_5(O z-}bv`bV(y4-1{SS5?3dzPFS6=I$?FfsZQ(3@!$6CWfe!fQ9L`k z?($_78{A*;`G+s7Xp+5qAZK{fWfebmE%=*nmR1b>pm-j&^Sq@M3x^jxa^}(s_Ue*9 zY0}b)TgMi>-l(M&$E+#VYVJ33X$5 zHN$F#)eNf{Rx_+-Sk17SVKu{QhEvVyF@N)^E8{+{?+q*C{;vFkm2ux!-E>vl54JjS zRoo~3HfL4bKQ3HV6F+m;pCbRUF+W8+H$3)Jw13DCKSjUk`IWLd(XUQeov=D#b;9a| z)d{N;Rwt}ZSevsVRgc(PV32eJ@Ly4 zaXtCbRb~GOaqUCs)p{j_XN!ETybw#`4Re33<)o!>^r?djW5DQKxI@zkxp(l{Usvaz z!nBFk@T^(Y`7r>`y`(xnHsC`uo%{wF_n83sKD$Vd^FgC7jCEoiZ@VzokG1*u!dO@K zeWQzFz1dGkUKH!luDQ(7FT5t6iQT{Qig+fLa+;$r)c?hk{uyf<2G7a%o0R78_xZ+0Td#?=7WE&?@=J60q1hfT=kUax!;|kEUTuskWpxr)C#+6b zov=D#b;9a|)d{N;R;O|2@TpGgN!^}#;flC--sGw);+}fjqppa1?avxs5%=J`zj1lo zvk$!J^0;T8QCSmT{_ACtKj-1gqMiBYTo&zbzV~I(uje3|Q&uN&b;9a|)d{N;Rwt}Z zSe>vsVRgdlgj1d8JvAb(4+|$%$MqrQG^fdr6XJMo@x<6To>NY9YzJSOzEBabA3O$hi@}Vg5Oh zzvUk1L_57-7#-~|I(~HYt2V}!vO0;Y6IN$lhmuZMoq2vqC#+6bov=D#b;9a|Q=Qh6 zx;49FSX>XQCJc+~V(w^tJ63-&3A8(I*F?jRwt}ZSem6leb#Ff&$!B4Hi~Cl4R>o) z>Do5h)RzhU8^trO)q}G9((mJT+1eO?ABp?>NWQ<1YNHM*tCP4oVRgdlgw+YF6ILgz zPFS6=I*t4LnCh%`{g$z|t^AO(yyoPmoaR`6>U_wG2JsAh)O!u$8Th2f8^km46Rv3x z&%n#hYLNe}6aMe52RF$7)(PCBV@>?q4QukB|9Z=4=dBmFjP}>uw`KIJHZ-TKPU7l> z)d{N;Rwt}ZSe>vsVRgdlgw+YBI;|(;eW7Pr94CkFQWnQgtDVZ?xFYWHM!we#+VS}8 zHX!?6Txm^a{qb3TX$@PgS!HpYw|S;4j{lKM%Hq86TtjEd>LjjCSe>vsjeFftCvkPc z>V(w^s}oiyoa(%3+GpjiVOw$C$K|6h*e$b%6$fMcDql@UBh##MKF_6ILgzPFS6Jexh@6|2Lv0 zFyA;LXKl7_)}JwscNet=g;CFY_gENp-r~78qW=BQ zc_VyLn|gc}p$6h=fYku20ainvU(x`p0agRNwgzg#c!~2pD42Y{69v-_$8%njtbM*` z1=BCzvx3pX_pD%a@;$3OKdT|%vw|5H-?M@{mAxPF2mby+n~$RXPOCnO ze$#U*<WoWEU;sN9ZQ~{jAi1_V`IKi zC;JAP^Np0#ocFh>j`_yVYsSTVBjq&5cBuLLZ;#La1{1v7m*exl!36*3r}6pUV1nzc zSDpV2Cisrcs`J0W1RtJ#|Bb(y0zcO(`(9S|H<;jmXWumY_ss>j>{y-u4JP8RXUyMV zf}ihDo&OCcxIx?M{BJP9>ZB$qt2vLCG{b6!)eNf{Rx_+-Sk17SVKu{QhSdzGnh)8t zs5$yS-FNM{BM4iOd39A!UC#+6bop7r2rZY#! zb>rjqXUBCTV(w^s}oiytWH>+aH{i+?C*_wzxn&qqvHCXa++iPsdK+m&WPjxi+*Rs@&9o4cSXJL zBku7}zQ;f9c>FJzaz-5gH{FuumyZ7{v%g{LT8l@PWPi`JbYEY$&Y5xitBrA`tWM(U zgw+YF)40dKI*F?jRwt}ZSe>vs;Z&#fq;7+jj0*jaZ!kK>^-(*f6=&0w#Q?vZiefJa7M@RjMd*4mI_uZar`B+NlCag|aov=D#b;9a|)d|x+ zI$?Ff>V(y4-1}~I68~Q|7VlGJ;umDsSmP--ZF6qy8R`4ssMs@-a+=frgRyxIzMMS$ zyx9Aba+;I!%x}iVUY;#ij*Y!My|Ou#^LgUl2a)f65bby$)MftIO7DaE&dKsi?}AUt zuK(T#^&FD@7L?ZB|G3ZC*vsSC)0)8Qgw+YF6IQ2j?}OAyT%E8wVRgdlgw+YBI@6l> z?tX6m_b;gVoCD9z|1Ji6+o|W~e=h@`a?!c@-_d|Cz5U$$?`yz|UN|@Z8yxWL?`n9( zCg(-YFMmHT{_h8U&WkqRIr+TktNWPqLPP3x%4%jTYKGMes~J`^tY%ovu$o~t!)k`r z467MVHG3{lhv`E`$MI0vJG+LIj+18XvTI9eFIfAHM#ph=(DG3=$6I!ecpQHI(x^B- zPy6?%IBqNEjf&%$xcB?y`y3!Wzfx8w`qc@m6ILgzPFS5VZTdc4oy64%tJApe(^H)X zkDVK9OP>Gs?h5ySq@3mq`TDUuhdM7l?4ej&l5(2UYRsdtwxs?M_r}_il+&E_|Mpw| z@e0>FwQ2NttXtTp`Qx#kVS2O2W1U0&%^r{S58M3uSgeaU=AFl4y~Lb3kHtEQR-+$_ z^%V_ve=OErtX}uASdVeqGmpkP4Run_l+{dJ&9ItbHN$F#)eNf{Rx_+-Sk17SVKu|4 zX6uY!-Rs>OYi6!~F8dyD>AX02V)mWh(s?mtpL=5M&7)i1Q{i=(~)^F=LPwm7wK`8vO3YPPFS6=I$?Ff>V(w^s}oiytWM*e7pczlnD2S} z+*mXA^M`X|E!l?+ABZ((EslC1)}HwFxn~q z<-utG$Mz3Jzv=mvvN{=yI$?Ff>V(w^s}oiytWH>+usUIN!l}+n#=aKUhg#pg7}tlC z)10d8dvwlQX5aN(Tpv+838y;SY&gH-#Rz8LLq{_Km< zZ+g6?tWN5qPFS6=I$?Ff>V(w^s}oiytWH>+aH=!)Wm5h56-`zY&tpfloL}+YNd>1h zPuc%VoBm%o{lA_^T>oD<@wqr|+ckSGj^`yG%#Y*z_Z#NN@!xy!{5UV@*Ykz;J&)+u z^K0#6$zx0nXj22M23QTS8elcRYJk-MryBa5&@2C24~%z%&wIxGPReP{)8AC(e`kSw zSj}s*&*anp`^m^&m5(+kp1nUbwO3{5Y%eSARNT?4a{TcHKlyyG$`7*ruEhI)-K+BJ zUkgw7*{G`Wh0hDV^zT)bb-pUN_W@Ovm;YJt^r2Oi^E(#*_rgo6Dvv+C;Nx$rs=RT2 z!KXZ3RoSCMp<&JIRh6S|D0t>4Rh4@;E#4RW_+?dPpV%ir2^^96I zeW_>E@cZX`#{Cg-=Yixq4@}R;l+}s;ijq!Pov=D#b;9a|)d{N;Rwt}Z-y_Q}eM@}pF*R78elcRYJk-M zs{vL6oNBOEjCahTgW~vE*>6xBSFQRFisOyA`pNfqigrA1H}5nk>acTzEWdOvSN$?D z>ek|&fl<#l<_?TH>jgSfRwr?F!s>+8X&jyAqZ3vqtWH>+usUIN!l};mxZOJQ)a(Bl zy$8haLW8~o;`ic?K?CA<juQ{&iRiGh~J~<-X9RZQ{#Rc5Wio~Hyaqg zYxh+SjNiLM`wxuY!8gVZjNiwjt{oV^n_aRx`+J(6FDW}N#_PCX#|1ks*m1#*3wB(v z)Ffp!6IU~=W?0Rznqf7=YKGMes~J`^ ztY%ovaH@IE)t%z``Iq~5jQM2BX->*F-_eHtCZErc-0B36ILgzPFS6= zI$?Ff>V(w^s}oLjdOUNT-}=*zalL)ziH>m{o^x%-xIRC6UdOm@e{w>{xSr#S*ZC0@ z9pn1{za6vu((l^KT{_0^1##ymV(w^s}okIapxzg z&ay#W<9+4z|Jym^`@9{_dDMpF41;c<-EYnqxcU@3D3FSg%s2vU{voX>e@! zSg&&ZIo)Hu%A(7=$9k1r?&u!tRhm5BJ=Uv~J=ZL6!8Q56 z_U;z#tpE3J(SC=rZqcvW(44Y5iK`PJS*zkJGq9pb(7?u)bh(tG)?>vWCx)Q7j|8t<=f zt?C-@wLJ&XnX)>Gs}oiytWM*;msclob;9a|)d{N;Rwtb5ynTGTn4c`!dE1zuq@3o| zez|STPey0oZsl1nZKj;&r2luT8SUbFJLB4RaUFhkX1lmP6Zg7JzVmt7@j8F+kaltX zfBTRuzcim;ykoogy?ADecJVthYmAf4-W?x1 zyiL4c-sbWeKK;R(oRM$U{NE#2)UN)HN$F#)eNf{Rx_+- zSk17SVKu{QhSdzGnmwMmo@}~ht2ln1TAqFPxb$A&y6hXszAw1_{+4kZzIt`bn&UI` z&g1rkGg`*+{N11|zcfF2GW&)z_uBMD-1!Ol&QDU`Q&uPX)d{N;Rwt}ZSe-C!q7zmp ztWH>+#+{#}I&0m~F6JkfWb-c9)25u}bpEPi%ufc->=5&ll+zsBp;o^f-Z8GX`;5-! zily~Yr)Kj;*G(PsXves2@4T>MT+eCK>-^0>cZ}3zUzq8 zMom&yCvkPc>V(w^s}oiytWH>+usUIN8h0I0st=8JwSBCc{qmg}zVe~=ku&|u_VIu3KD&Li zd4Iq5(bs`{whs;JWV|V>nYfx^HN$F#)eNf{Rx_+-Sk17SVKu{QhEvVfnRz@}apx!GJ3pZvkJ}@DZ(DObH*6Qjd8=;OZ(r$e@9ud-_M2EbFRmKh zF3uOvL3F09PU7l>)d{Q9xbqWr5?3dzPPlVPC#+6bop7qN<&G6`J-I7;&g}Ihn?a&gx^;(C&Dnqxco(&+o1QJ;bJvuER_x?P+-C%2ws59k$jK5}5Ms6TD$%YQHF z6@K-&D$6geOFT7uPoclWy`GTo^+avdA!T(ES0}7aSe>vsVRgdlgw+YF6IQ2juP3R_ zUJEMYdNOuwd0bCYPIIh3b-sM-J>vf2vGw+d`;O)9!I!^VOK$ z{OFqw?R!i4SuPN_ILfbGWt~;V@z3{#MKF_6ILgzPFS6=I$?Ff>V(w^ zs}oLjT2Jb>!Rh63FFgB{^0-HyenNTNJAZ#-dE8Uqb!vIsYu|EKdEA3fy0AR%%|E%m zJnq?BK3pF6@^>sOk9+(_ek_lB|1o71@l3$;4$Ud6nYfx^HN$F#)eNf{Rx_+-Sk17S zVKu{QhEvT8vZZ(K6RiE}u5rJUa+=dRtF7x*uFalNc)yc!nv?$D-P%^f{B3UMikR0e z?phJ^J>t#-$@hMTcAPi9UaKPJlRtl59`nrFFO|pqbI~2;F)y8dL3zwq)kYmsRwr?F z!s>+8Y25oAbrM%6tWH>+usUIN!l}+DPUsQ$J3lw-9``#br#UGG2(8vUln zPs-|Kyy}G239A!UC#+6bov=D#b;9a|)d{CMJ#M+4{B&3Mcvj!(lJ4;gzr|_YCWU-lBWFBWSvL_jq^Edj0P4PT{0Kc8+%qb${PE-a#~8w|l&s7_(9L zcxRD%owAx4i<)6I!)k`r467MdGpuG<&9ItbHN$F#Q_YR*pBdMa!{!f<>q*My@PEIX zKQyi2Y4{z1h$>FH%l(QeJP^>2Z91deP}|+`e(^>2W--dj9k{ z&a1vVJ&ynT>JN|eqUnyqBYs-n;gNsosNvC0^;N^8{eJfikABlSq^wTHu1;8;usUIN z!s>+839A!UC#+6bop7pCFE}sGpFK3LpPj}IjqBNx_~Lc@ zt#yXR_57G$PK)b&$5p4r^`E%+`{aASpZc4!I?=CASe>vsVRgdlgw+YF6ILgzPUGJ1 zr#d~hsoT`8&kX&w+npKX>YDAb^7#gFfA7fm_l|a~TZ=Vk)YNm)8ByoMvi(p#Z`omX zwl}Ku9OknzXM|s#J7`W>oy64%s}okIaewdBNnD+V#9B6IY!Y^XGYY z4vhJ8%4yDt*_sFUsr|6>w73sSInA*heA)N9fpLHF_KbmX-|??(&58FT#Jx`;-}_D4 z@xJDfc?08qXU6+ke(8Dm#B3df_eZxi8Wi_UzwA0F?x)m79a2^&adpD#gw<)>`%QHc zS0}7aSe>vsVRgc(&KY+Mjr+%!j~f#Ak13}))}K0G)?jGNjgQ=EXv~>UIeci$rGFSc zH0Ib{E*=_l?LPYsPZe5?Nsjk*2#+3$$^yN5nIH0}j9dUR;q zBd9a4Lup*Fnqf7=YKGOE=a)3YYKGMes~J`^tY%ovu$tjivvsDPZ}k}x_iJl94~hG@ zI$I2h`^3+G931zFSG+nn?i1VHIXLbUpPW<^A96xXe(ya7M>|Kf8XWDPx8dOE*K-h^ zDXWvXI$?Ff>V(w^s}oiytWH>+usUIN!l}+N54DW%dJUS^xPrg;M^4IV&YF{&#&_FV zKCpd!w=Lx~$9C}Lx`P_W_pJWizHxlds`l26<9k-by`GTo^@Mi3p7dGVxWez!JkYyI ze9vm^vrXcAR(1E=j47*=xH@5V!s;~c^+cV-)d{N;Rwt}ZSek{9)`)y^H_}<;%)m`Fycdfta65qSK;y+#Ddw1$&j47*` zxSC-#!)k`r467MdGpuG<&9ItbHN$F#Q_a?ydOo#jyZDaW;kUJo@5@c@)Hc35_vfA4 z#`ox+YPM~Br*6|r+Qj$kj$P9_;!RI$9r>4i-74C7{`6MS{;?ajihex@(V4P3iK`P< zC#+6boq2vqC#+6bov=D#b;9b*^Anwyt=y`@=OklaE{lCVDW^H>HftRFdftC^gV@)T za+;I=-~L^i#=f3i`ZkSyJ-?pVH1_onciu?8^G4cn-gy74tt#BVwomu1Vqe3UXPU%* zhn2f#*Ot<}@xFT+$NmVlQHPY(NnD+Gda+NZ z_ph~ckH|?m%}Kfbka`sd+}2PI6m>q z|d#Z@Z1-UE!R~H;#9R z_x`+5yjy(vy^Z3X^VZbBn=s;(n93^F#8TAJUHV!#3B~iTlkzAIkDe_nRx;tP}T}TmDoh z?l(_vR5$K7)yB9|Rwr?F!s>+8Y25jtI*F?jRwt}ZSe>vs;Z&#fq;Aiz+9dQhY*a7C z)nk`>G2XxTtrvBuGrV3+eX{e*x{bK9UexoO8?yY;`^UyN)rV(w^s}oiytWKEr(Fv;)Rwt}ZHqzgWd9Dop=s5H#`1)4tD9>>|7|#XDTkO6VJiaMh#O|CvkPc>V(y4-1&?; ziK`P~Bsv-m?#?6?K@oQ>~i%WXFJY z>rz%L>iI<7EWfnQ>f-Egidlc+{+^QW?`eAcq^wT#s}oiytWH>+usUJdL?^6HSe>vs zjr)6=>P(OAtH!PuYwdo$a=loCx9Yz2V!hwHudWyC{XSZ{Uaa@)xY_!#-fwA_8m>Ha z{m7|0WBvHQZD*_>ZMM2={pf4bf7TBT={c3Mni-dxVKu{QhSdzK8CEl_W?0Rznqf7= zYKBwI=j>EJt|t$Dze!wAQciO&{H`pnC;y(kSzJ$2PIH!YD~s#NKeFqv*OQdfob>bY}23y3twtxIt7VqGWUzvUTxAga?#w{+3cXn-GDT{Y` zOCBhTcYOV>E{k`62aGCZFD#tC_f(VKu{QhSdzK8CEl_W?0Rznqf7= zYKBwI)|u7v{AM>&113 za-YYhoaT%ezPQ}?JD*)pJD$g;oaWdL$Mb{xd{plIZQb8LEO%ZvVabQ(zTYA4Jdk|n z+qC1naf=}zm-{^S^B$j+JKsL1{io%=-?_BwqH@>8ZE?V7<*N=U{x*=>s6)!?B(6?a zov=EMJKt6(adpD#gw+YF6IN%QpXeNZ%m(p1_K6{Da*xPKInA;D)OmWN_2T*S!hfw7 z&!zjd&+h$8>n+>fw0=Ctp1$D*71onBt#jpd8^rVQ#?NjL&&l6=WrKKrPFx?!*I%`v zIc0ScS0}7aSe>vs^Zb%dSe>vsVRgdlH17O7)oDGc+u?7nE^l&9aW3rDXm$BH9~OM_ z?!T5__4ndC75g6iOZnl03vPGt&*gu+s^A;;`l)>0oPw|HzAAX*?N>(5*Bw{H|9z$6 z$7u71QZLKaq)dIjtt1vN`zsdiHH+839A!UC#+6bov=D#bsG2gG}W2t?&Da zza@I@eOZ2KuhWgQtE0B{XVlbu!1*;^=oflYRs(T0z-oZi0ILC31FQyE4RERlb9-E%)2?&vvh_^xO4^_RhX@UixWoWEU;sN9SiJOV8;SG7TB@Cjsj#;l#=rTNnJtWfLn8{do60XVI+e|K45j^>-{i`I8Q0G@6wG*yQwQ^@kL^%5+ozuPOP$q2 z{nd#t>esKUr*{hP)@FSqu8*)j!ukm7Bdm|GKEnD4>m#g>us*{22wS8P&f4lq`BYx)% z?Q$mn<<14u&ciRX&EvE`c}T(Z+q7xH==tP>ZSx#-zMQ?E=3GX9zo`W?t`QRoX1vC! zgZb3QcBq@}Q&0P)&g#K0b>f%$@yl@$?>)X4Bl&HY6-+zjN3_p%(*B?a3Z~z8Yj?=w z=xMNL!RTx|vS9RIeObYbYy9;EGhXA=!F=jtJJikgsi*x?XZ28jb>fTqIqw)3KK>Q! zqrOugSRY}1g!K{DM_3I3T|tdFoh z!ukm7Bdm|GKEnD4>m#g>us*{22{m78BJOcZzQ;4|c%0L|$3OjgUZBVG1)ZKp==c0$ zT%LD~*En@BpZeGib+diyX}{E2J=9;F_@aLO!pFa2eI!R8VSUVxfs&7~KEnD4>m#g> zus*{22m#g>us*{22Mhx)4%ztoRkj*Iw&>SB!KpRl}O z+8Nb%=Ug-G-|}F=^jo%m_dJfC1NSNzoyVV5F!~o>UNGZ&VrIdN*En@BpZeGib+diy zX}{E2J=9;F_@aK!HO7UHf5rN!@6-p@M_3m#g>us*{22b=gdUZ`ZXExj~+HcZj zzv%btJ@*SeyB)q?=$v)zexZNC@%zQNh#zwBUio=M{>YCDrkxf2_s-+A|Khs^({KNZ zeeyVZuAWgaI=_0gVDz84s$j;|c-`K4KI1h`9n7abwnN=)pL*Iabyg4cS0}!xU%&A2 zuUH?+(MMPxVSR-45!OdoA7Ooj^%2%bSRY}1g!K{DM_3m#g> zus*{22SNXM$Hnn^+DXU7ar^pd$Hnp7ddzWg zoUfR1Tpa)ZoO4{97YDp>T%30uzdbI_yPfLwkMr)xF8$-Y8+~|9yn0ms$Upv?{?Sgu zNBT$mPrcqh`n~vz{-Nj7RsBO}&p-Ny{=w@WALAnKaZA3(Gwpbs)4s<){d!)Y$MXf9 zo=52S{9;_5cZ}CKbugd$*ba5Ged=ky)LA{$U!C}(e*MD7zhZqPM;~E*g!K{DM_3cvwEn%I`KvQoNJ5=AODK=QQxT#tdFoh!ukm7Bdm|GKEnD4>m#g>us*{2 z2zG7 zdj#JjF#q&D0`pSeBQRg}Jp%Js-y<-;^*sXfUf&}yAND;0^JL#6Fn{(v0`qF)%(u;F z9&S6#&uyQ1yZthsR}c3E>g2va{oEHgF5*6iC*SAuwBvJo+V^=r{ra3AJwE?Or|$*O z@B0GA<$DCiYn(cmPkn5My4gPUv|sA19_p`7d{MuC;p1PiK9Zx4us*{22m#g>#(j^VkHqy6)<;+$VSR-45!OdoA7Ooj^%2%b zSRY}1g!K{DM_3=>Ige-0 zNtNGaeFKoZC{ifq3o@#*ScG@E!SIYd~tL9eaaoSv(-Sg58 zef2-DU^KMrQ83ziFDl+Ep?U1^f*DKeAA9Eim)f>Gv0%pj!b|_ZUp3ROW1(NzeqsBC z?H9IR*nVOAh3ywk$9vbdlk@QsPdTl_|KqDCN8Jv+a&nBN=k&=j#@{ZS9Alq%-sGss z7egmUtv)z*a@4TN{*$A&oq9};n*TpNrGC+Azp(wn_6yrDY`?Jm!uAW>FKoZ~UN`HP z^M&}@?D0cf=Kpfc^M7g6bAi4*N6_H8gEr48G<&Ww7SBP(=()+*J!exr_Ul;a7q(y6 zeqsBC?H9IR*nVOAh3%Iyrv0Xzo`W*~cXsxC$$2UFzs^^=FLoZw{j&30?xUUea)0f7 znEP($$=r`Sf95{jc{TU%&bPU*H_rXO`8)@(9i9)^KFDQMJ?)n|tB3ll z6JOM?UwHjjtdHdABdm|GKEnD4>m#g>us*{22IRaX1vC!gZb3QcBq@}Q&0P)&g!B5>ckiI>lf><{)+XH9DRiK5!OdoA7Ooj^%2%b zSRY}1g!K{DM_3JWM;huZL-$_xLdV z@_rvi5AXe9bg~`*MnCHWV8+Gz0hsX`rw-;*AKRgBwog6nmpZG5`l}OP)bCmyeEcic zM}5afSRY}1g!K{DM_3I3T|tdFoh z!ukm7Bdm|GKEnD4>m#g>us*{22BJ-@hr_q^l2-Z=OB=JOoDc6dHu`#d+WU!EtZhvy9Ht`aQoGm**YhHBKGOr#`kr-E5zF+Anoh5A|0k zzNlZn@bRx$AIZ^2SReCapyVU0kFY+%`UvYItdFoh!ukm7Bdm|GKEnD4>m#g>us$01 zywgYG`UvYItdFoh!ukm7Bdm|GKEnD4>m#g>us*{22;aW|cbuTdatoMLv zhjlVA?X!LcreD_8!02JU4UA6K;lSu;eGbgHShoW+UgOlkeClI6)Xny(r~OiA^-zCx z;+OjI%W)BBy$Ai0&w3A-c339^(?08GVEScU4U8Vv+ra2#9S)3s*5|;Ci*-9N<26nl z%%?uKL)~njdfG2_RuA=8C%&kkbB%G~<6p5p>O1v;^%2%bSRY}1g!K{DM_3m#g>us*{2 z2(RrU?;SX1hPct1t^-e=LT_h0Doz6_n-uc6=jIL77u9pg1l z9n7abwnN=)pL*Iabyg4cS0}!xpL30I;p1PiKI%L5f%OsAM_3KO?E545)y2hoE7d(+ZSwKuzkVy1=|;FU)%@2)n-!VyiJ={aR0D*+k&~jn%BNy z?z^7tTrl@z-*hjS`?Q~X7R>$I^#>Hpecky-7tH{$^t4MR@(SHj@|D(?r%(#A9P%!ts# z`UvYItdFoh!ukm7Bdm|cse}2{2i8YeA7Ooj^%2%bSRY}1g!K{DM_3$Ho9$Ci`=!q6!7p{Yu|BkK-RRePqQ^R;)B2-dUsAv1)JK>)kPqu4tdFoh!ukm7Bdm|GKEnEF zoI03KePDfr^%2%bSRY}1g!K{DM_3m#g>Fyk70`l0!;%6Jbyr(o(Z|LTIN&%4hTOx+r6cvzlKJ*)pwFm=B7;ezpN zezU{#9Q?ZZ;)3yO#s6yJJ%=8V=aAq0qk?H?r(S)d{S$61n0{YhUNCw#-QmdM|7JRy zpHMLRr=MRi<2q+@!Hm~9bugd$*ba5Ged=ky)LA|FrB3`(KYlqb;*OVm>p(l!hxV-- z{aR1-SZ8!vfAs51>X)4Q2m#g>#;Jq()Cbl_SRY~frOvQE!ukm7Bdm|G zKEnD4>m#g>us*{22tzRZ|ZFn-8Kug4t~A;Qo+Pqm+zX# z$*(=9VEk%awp$*j{XK^jOurAzD;Pb?*C{XlZ>Ff%$@yl@$cf90V2imbdv~S($*LtGII-}G2qhDWAzvR?MSRY}1 zg!K{DM_3W@xXA7Ooj_0c$WFrWIs`UvYItdFoh!sx^oSRY}1g!K{DM_32Jw$G1Y#(T$o1yhH{uNF*wI{Z;E zbsJRKAFtA{Bp7GCu(f|2F1v9Q!=M~I&jZ+8nsgLbYH`}M4_Dh}B zgJ0^zFZJV><09^O$+r%)V|{4fy3w!oM2~ewr}am_zNCK1sgJNe!ukm7Bdm`wbw&@Y zkFY+%`UvZzaq3_`^?~&f)<;+$VSR-45!OdoA7Ooj^%2%bSRY}1g!K{DM_3nejGhR4{dz(yd_XbN$H$Q@0OpEtq=l^Gm_h z`OL$%&fCGSDNhuPUjw(>CXeISqt_Npyv`=gBmaxh1=G%NiwdUwb`>r19QwU-TEXaf z^RFCOHO@+^%2%bSRY}1g!K{DM_3m#g>us*{22B^)6MdH>iO8Q1ykoQo+ucu zebWkNyvC`6`P9dDsGIFmPy40L>cKB{;+OjI%W)BRyyRO4+Oa;gZ{6tEdZNcVqtp7M zUtdzcU)E#5=wY1(j84{X!02ba2h6xw?*Z4_x@E*W z-Pa=W8})7x?R@`T^JstUbpfs}vfcwmKkGf<)Gs;p5!OdoA7Ooj^%2%bSRY}1g!K{D zN8{ANe0+rU5!OdoA7Ooj^%2%bSRY}1g!K{DM_3}u( z`z-&`*B;5^wDZKwM{}nAEsuOGXZl_CYr*IleD33U9G%lXEExU6{`N#3XFR>y7d&j{ zRuP}kX{*RTcR`bA=fJ^DqW#aBG>Lw1dB1V!x$KU{p|iy$jVsi@b9Lhw7jef+zIC7- z>qGn2jee~sdaN@#tv~wpCG|^AeT4N9)<;+$VSR-45!Oc-U(gThBdm|cse}3W2m#g>us*{2XdEBSw+{M9TpwY5g!K{DM_39Zp`EO)%g8_ z(Z6Pk*?F9Cz1p^5#%r89m`{Cdhq~E5^|W8=tRDPQCw{3PzZ@5F$4kC-pdIT&`__$q zttWb{Gdit5`t>FCOHO@+^%15%v;*rStdFoh!ukl~3;JPwg!R!lbugd$!1@U5Bdm|G zKEnD4>m#g>us*{22m#g>us*{22m#g>us*{22m#g>us*{2 z2s5r%wk_t0jCXdAf~iCG$bzZQt#21h-C7)3%qOYm|9&l)Iv@T(F}I}tS@2!Sv}NWo%p4G{Bm5x9WVLTfp)A9?OQkc zwVvp)&giuM=+~FjFFExQ)<;+$VSR-45!OdoA7Ooj^%2%bI3T|tdFoh!ukm7 zBdm|GKEnD4>m#g>us*{22Q*tiVCvbV{cCxgI*<6gVEnpa?(2CRzmA^vM$Y)P=JbUT zzvj?4b0+`rPH*K*JL7*ZnD#$-S@2!Sv~lrPW)0oemO4Uj+cDvKs(ll_N^QJT2J&?XLMSB^y^FN zmz??tQwQ>4eT4N9)<;+$VSR-45!OdoAB|H7^QjN4kFY+%`UvYItdFoh!ukm7Bdm|G zKEnD4>m#g>us*{22{H% z_Nk}+QfKwxmpbuF{rKg$h&x{Ltpn{?AKJHW^lLrQW1Z1y{n4*4sb6yHBTOC0hxHNG zN0@rjFRYKSKEnD4>m#g>#;Jq()Cbl_SRY}1g!K_dC%(Y?29eZSnEC`TZ;7{r$^=sl#dO)ym`4=lmTD zrfyG;ESP$>f39Ha+_zQjJRiSKn^G`-?fYxN_;u}|_3|9z-+oXq`3v@0KabPSC-)Xi z`y18UAdl1UsO;~Sa-WT!hi)hsozK5oF#5ZHUohip`E$XH*En@BpZeGib+diyX}{E2 zJ@}r3jFocajsBdm|GKEnD4>m#g> zus*{22R>+gf%OsAM_3(tv z<0Gt(us*{22B9iB(oKF_J_m*-dN;W?N(c@Cz2o`X3q;*OVm>p(l!hxV--{aR1-SZ8!vfAs51 z>X)4Q2m#g>us*{22^% zx43(oiXHz}aK91FD;{W3@QtloR2m#g>dA#H!tdFoh!ukm7Bdm|GKEnE#=a+nh z_0c#!nvajLKEnE#=a+nh^%2%bSRY}2$N9ahKI4G=_nqr1%0@r7l z`2*K&n0W=)bC~%F*Lj%v3D*sn`3b)Z#<@x@q8kA8hg{gUt4;-K&mrVix8`UvYItdFoh!ukm7Bdm|GJ{qSE=2IV7 zA7Ooj^%2%bSRY}1g!K{DM_3m$s#*l+G}%RXh8IIYfnDH8?4(3xI+o5i@Pd)9I zI;#i2)QMl}$1lf4-0_lc9cah;(7tt}U+ak;>x@q8kA8hg{gP83Vd_9WtdFoh!ukm7 zBdm|GKEnD4>!We%U_SMM^%2%bSRY}1g!K{DM_3m#g>us*_!i~Z&vx9n?%sRR3+Vd}#^XqdXOKN_ZR>+gu^sAW`_$8Zsk3_UOP%m#g>us#~64(3xISRY}1g!K{DM_3m#g>us*{22m#g>us*{22$Ho9$Ci`=!q6 z!7p{Yu|BkK-RRePqQ^R;)B2-dUsAv1)JK>)kPlNI+JW^E)<;+$ zVSR-45!OdoAB|H7^QjN4kFY+%`UvYItdFoh!ukm7Bdm|GKEnD4>m#g>us*{22^JwgWnVK)9oX*-Qy=z0!_N)VcKWkH%!0m2ZzzaK5-bG>>r2mi+$xV<6^%# z%y^Ac2lJ_q?NB${r=Ippoz;V1>clVgm#g>us*{22-TlO`>)PeoZF!f;{ zG)&#t9}QDa_D#donf=r-ez89n#xM5m!uZ9$Y~$=xHlKaUFzv9v8>W5seZ%z2esCB) z>=TF4$^LN|zt~p}GcNXp(l! zhxV--{aR1-SZ8!vfAs51>X)4Q2vZ00VSR-45!OdoA7Ooj^%2%bSRaj32lJ^9tdFoh z!ukm7Bdm|GKEnD4>m#g>us*{22WZyJQo!L(f;}`pLVf

E{tF7%QntFW%Jpm z4ATz#yJ6aApE69p><5R@!#;5so$Mcn@r!-sFymssIm~#CQwQ^@kL^%5+ozuPOP$q& zU+Tm!_2ZZ0BJOy}w+^&peQ4jh(XaJHk99_;^+&(Hq<+b%k1%y0AJ#`$A7Ooj^%2%b zSRY}1g!R!lbugd$!1@U5Bdm|GKEnD4>m#g>us*{22^^1Keaf)=lwtQN!|qdt-KPw@PZ@Tf zvT^n)o6kOF*nP^d`;=k#DZ}nlhTW$OyH6QT{gP83VSR-45!OdoA7Ooj^%2%bSRY}1 zG>(tv<0Gt(us*{22!WdeG#?*feT4N9 z)<;+$VSR-45oR3@`_1u`^*QWohFQ16erK5VJnVypS?9z4Xqfds?3;#J7sP&QnDs*J z&xKiE#J*ja^+oJAH_kp~^Vz2i(+>O1VcKWEIZVIoH;2)~esdU|>^Fze&wg{5ak1YV zW_^xv*6oOe<7o;B63#pU!Me1jLk>eunc*(a8v}1i}-@4JS^+b<# zMyK^hzrLh?$*GU9KEnD4>m#g>us*{22dF31m^!ns^Z(d;^ROMOE^xaH(I9%tYlw(MdWEE()N|iLM4AT; zDw+@(Q&gUKkSNkT$}8SVlR|}*>V1_a6-|^OniWEYx8b|a`?}Bd_|;M`uf5iF?S0+Xy7pQy{^GnRjK4TP2;(o#huY40N&9o26h=<_DaqbmnzP4ir`(q#FU^nGsPshd1>Vv=36Mv~c{&HTlJ74;1 z2jplU01ozYYKqrZOH(O>e8euS|D{bBtG>ql5W!uk=`kFb7(^&_kwZO0Dw z$3C!rg!Ln=A7T9n>ql5W!uk=`kFb7(^&_kwVf_f}M_50?`VrQTw&O?p<40IO!uk=` zkFb7(^&_kw;oS3c{=Vb6TL1FAt>1YL_j=&@-0OtrcCR0v=e@4@UEuY`?*gwweiwLs z((ZLjf3Iicc%38P>z{GGFVM&P1wFlw(BJ!ud3oRQTx~ng+xF)ql5W!uk=`kFb7(^&_kwVf_f}M_50? z`VrQTwtL^{N80rxtRG?h2ql5W!uk=`kFb7(^&_kwZO0Dw$3C!rg!Ln=A7T9n z>ql5W!uk=`kFb7(^&_kwVf_f}M_50?`VrQTw&O?p<40IO!uk=`kFb7(^&_kw;oQ8E z^X6W+oKuFe1LvJ#?87-|7`t&k8pfWSn})G7=c!@*#ra$qe{pUX#$TMvww-gz_UD{3 zj2zB)!^r2{H_W)42ZzyzbK)?1a(*1fUz{t4nHT5HVdiT)cCbJ8Q4V%fKK686?5sZc zOFi+I`r|L>MZ5E*zji>5_CdaOV_fZtKH3>QwLkjnmmU2j@90MuJJ282kFb7(^&_kw zVf_f}M_50?`q6gmV1Mib>ql5W!uk=`kFb7(^&_kwVf_f}M_50?`VrQTuzrN~Bdi}` z{b)OWv_F1?^&_kwVf_f}M_50?`Vr2}D>-lOb;~(r7&~y@8OA=GgNCsi=agaW$+>A5 zJ9C~I#$TMzh4B~Xc47R*xoq1xr)+=DDZ|L&d^e1I&V9p-%Xx4ZeK;o$qbKK-Vf@9p za+rB>-W+DWwqpnTV;|*UH|1kb$HmU-gTK@hf2lwIa$dAMU;1kYZ4&yJ*mBY-7^X4$~wH-UyANwc=yD1-gIxcorAN-}B z_)Goqm-C|C`O;rIAV>QkU%N4`_Cz1;jGo#b{q@U^{*rg}Ba9vB59>!*Kf?ME){n4$ zg!Ln=A7TAyJ9e-?_JQ>ytRG?h2ql5W!uk=`kFb8U z9Y5M1Kf?ME){n4$g!Ln=A7T9n^S;RQcf3dPoEPtxJpaXeC(niPKFafAyr=RU8Sk$= zU&ebd&z01 zozYYKqrZOH(O>e8euVWStRG?h2ql5W!uk=`kFb7(^&_kwVf|>k=kN3*?fMbckFb7(^&_kwVf_euW;u8L z=g*tNo;Qa*rwn^e8TOnqd}jWtzzW!Q7dwsTI|{+v^Wk;8d&*mKIc{`qst zu;-Lv&nd${h^X9PUlwr>)!=6)yJ*NzNP8s%`GVD3!T>tzzW!Q7dwsTI| z{+v^WJ*NzNPC3^ql5W z=KAOT2t9&^=KAlvPyespr|yZ^)_o9mAB5cpVfR7UeGqmZgxv>W z_d(cw&~~2(+y`lQAB5cpVfR7UeGqmZgxv>W_d(cw5OyDg-3MX!LD+o|b{~Y@2VwU? z*nQCUzw&v;-wurB?*-W33$VWzV1F;b{$7Cny#V`r0rvL-?C%BJ{oO==e^2>)fj<6T zfc?Dy`+EWQ_X6zi1=!yUu)h~ze=orPUV#0*0Q-9Z_V)tp?*-W33$VWzZ2zl&_f_2a zek|v&zsvivbvxq-Ie-0K;s`tAt?7FBcZs+9Js9i1-#@S~_+141h2KlCkN6!0`-|UK zuYxqUf#-=)9k zufLF^zmTuL7*~IxkN!eW{e}Mei+SlUo)2y3`OyA6A1a6EL*?^)=(s!|st?bH>dEt= z`up7%^P=7Blm6NPIob#L+Kq9wC;Dh-^wj?7uV0wg&hMPl=lQ?Gcg~(E;M(vU0qi*f z*mDH1=LlfW5x|}!fIUY5dyWA19D(gS&x0htAM^DGv5DshV9yc2o+E%+=Xai)OP@FX zF6ZWUo-a=Q^>;a6yfY6&>aV{`9)_LyYEpmwUGmlJ%+h1+YiIt$)L(y>{D(X9 z#HRlGyX1-Wdmi5B_}vKadHkM)_dkAT!h0dVKjD3m-=**#$?sKozvOo;ymvAl#QP|} zd!gO<7ybQC204B|gM7cMVO+nrK_9=vK~KNWL4Uv7;dhGP^AJz5op_4!pP@-gc+Cn5k?>GM;JZ1A7S+8euP

wP7)L)#}z$Vz4 z^BOSrxBeaevMwI};=G3b`m5{85s%hiJL_+z{^DGl{^DGl{<2Oe{<3~3{^DGl{`#xy zZxWBzUz{_AS!XzZ3bX!jE)`~7;=C%%dc`?bn01WvtuX7M^?6zMtlP_a$T?a1(7v-y zak>s`Pu4^2%zCK(Sr7FK>ml(?Y{+^@94%+_#9zeMVEjeg4aQ%@<6!(noDRlc#P4AI zMO+WYFU0#`+f`V+^5nHTX*nEBd{ z9qf;Nl*2xveD)W|Wj$0M)5_CdaOV_fZtKH3>QwLkjn z7oMZ^m+@%EH69HckA{s$!^Wdwo4Qcv>T6xjYq@AqhaIGu<>Zv zcr?tsh)2WBm;6pJb|CK)jD5%l1!FhzM8VjT{82D=Ca)BX{mD}V<1g|T!T5{(RJN0^ z$^PVPf{{a>D;W9Yzk(T;crlDV*I{`PkEO zv9tPMfAz#)>W{yi7wyiM{@MXK+6VdCjd8Un`esefqhZ#6 z@_)kY3*-@n*)Pa13bT)pcNAuSAs;EszC)f;nEi{qmoWPm`7mMjFY=w*PX15(lm8P& z4tY~yx6-H0;vcl+3zE(K5FDH3iVb*`!*%$23exV%p5#_VLI4=8+ z`mi6VC;OE8vwt}++MO@`wF7dr5AwAe<7!Xz(az|p{n1~)FfZcK&X+vNFm@o{GK_u5 z!wh3L@-xHOlf2C^b|#-QjK9ba4C62I2E+J^ywJ9jC)xhwNrsU_erXu_v^!T#!rU(_FeIWO9sFa5Ox zaj~H!`PGj_AquP?>&sa z$fFM9FY>Fy_>27cwv$iZ{^XN~kwYGS82RMqhZ&c6F^oRs^M}!sJpVBMBL6?kyr>HR zGhf@WgZ;6OaWN>}AAdP7+MO@`wF7dr5AwAe<7!Xz(az|p{n1~) zFfZcK&X>9yFm|Bs28?~E>j7go>V3f2lR6+UcBVcEjK8Qi0pl;~P{8<$IwQ7Icfh>mv}LZKGZ#d(X&iaKLy5L)JcJv7xhzM=4(54us`-u4t7&M_HLc0i8yLB4ilTjWd8dQULp5-*0) zhx$-3dQvwE#$VKvf|=L4jVUu<+p&ZFv5#`FoAR-z<6>v^!T#!rU(_FeIWO9sFa5Ox za*B8VeCUaO&GgTXA{Pr)Zc`$Gj%y({6(Ed7=Ka!5yoHC_q3gQm-eUL zC5#;Egu=+Dekjbi#EW6{q24Hrp41_Q@fY<;Vdh2MQkePLjvefeeUyXUl#e|f7dxvD z_E%5*qW<{HdC~5C>8~A-qkWLC-56JUqK|e)PwkKX`h|HJ|6;zzS+Ilg7wltP2D=%r z!Jfu(u(RDP#EW6{A&v~AC-G$% z{fRrn%**%}^R*p2*dO~S2fHaBdpa(5Rv+xIp7=%mbL(M#UbH)3`fCT|XdmQjH^$YT z=%by{Q~RU8eyKO1YAy!NS?PNwHvNAwG3eac>ZFfsJeqdn(Xe?8V9!Uxo{xq-9}Rmx z8uom2uK&*S@BdfNzw@4l`w`pn{s+IqycgnnfO%iUbprDqiR%aE{Swy|%zG!UH`sVI zY&;q^9&J0#x5$KPT~M{YBgp<~facD9rO4aZ;G) zI^w4=&wIq9VV(ntN5ecHn!lIlM)UgeJV`v7KD6)5W1Qxf)1Ev}YG#{vxgl<1gZ^F#aMA3*#5!eK7taZfiU7P5Tq) zg^|-fiATf8CoT*#F7aX*eTXB&Tvx=GVe}{N3^Om{n=tdW9Xr?``zVL!aOLxS?zpUn z>ce`dp4?yR&;8}RXm`H!*AB?hKFHT@jH^A-M?0gZ_D6sH!gG}V;`z#Up1bVN^O$mY zPE$V5Z;s1zo%$G$##Y9oVdK%ZJ743`v?E9RAYZ#NuJ%M9?TntZvcrM!Ea`ipq9{<01`{<1zh z{vsZ&zy9j_=ES4*7jaLR=VaocFwf7#NnxI=iJ!teZxdIAc@8Ju3iCWq92Vwzp7<=x z^E`1|+llAepExg!9OAz)@`($>j7z*2MjztHFnSVShFQ;vJHxCS#G_%Jhi&IM+5S8~ zD~IQ5<@3DlxU7fj!+NNm_)Goqm-C|C`O;rIAV>QkU%N4`_Cz1;jGo#b{q+m;A|CC0 ziF?A>fp{p4eTb97*p2upj6I2~!q}O3D~!L0!@~HB_$-`@za;T!+llAepExg!9OAz) z@`($>j7z*2MjztHFnSVShVd71XP9}d+n6%*wH-UyANwc=yD1-gIxcorAMCH5_(lEk z7x8GurQP|`UppX2`ygMtF|PJRAMK2u+8_P(3-cl#?R<%Q!q|a$D2#oGlfu}I_$iD% ziL1icnRqLVzlg)a_>1@~jK7H6+D<&z{=|7<ZO0Dw$3DuzZpz1=j*Feu2m7lheo=q?<-BNjzVz1)$k9H?*KUlfJ<&%y zqo?*qfBnL|h(|kL;+`;eARY>1AL67ib|ZcYV^89$Fm@*13ga*0urU52J`3Y7;WN>}AAdP7+MO@`wF7dr5AwAe<7!Xz(az|p{n1~)FfZd@%-1*zb};^eeT>Us zH{&(f(>M-xHok+ujQij(<3YLgFp1k@L)wjh(cicda*Q`2-#8TG8lOTR<5uWtJPZAe zb1^UDU(DBb>|lTFqa5s}eC+AC*jatBzk1>q_0O$``FYXqeCe+pkfVK&uiY3|d!mna zMo;aJ{`!R&G_hvha~O|?iBsEd%$j!N(XjF8Tzmd}G;BN?HXaQdkA{s$!^Wd?{qyl? z*nI4^laJm0q_97Yb;Ka70t z3z%`aUtsj%K7!Gc`wK>Y?mL)&+>iXv`ybnRFJyn-7b(YhH2sZ7!^Wdwkr+kA~5c z^U*N+b3PhoUYw7HS$}M2U9vyxm2z0el+XI+xU75X!+NNmtdr```suuAcfR!34#?3y z$k%R+t3A<2JEN!eM}Pgoyf`22e2GWH*nxU#F!rI&8jRhjzXoGZ>axMunR;z7{-XXD zjK7G_!uX50t?k5f?N6K+Mh@{`82QA7Va6q&HjF;hp@Y$r`gAbWN>}AAdP7+MO@`wF7dr5AwAe<7!Xz(az|p{n1~)FfZcK z&X;&Jj2);u31c7XQNq}bI+ZZ?q<$rgovCXH<1gwY!uX5$ER4U1+uBY%*Z#zLVdN11 zg^^EO7-n4ZX~XD4y-pZCspARbFY0^3x$7{g`w25&+p&ZFv5#`FoAR-z<6>v^!T#!r zU(_FeIWO9sFa5OxapH9N5lB*^CTW^JMn1yQ&$&84)us(LA0p>oBR03^QNbv4j1wk8-e^^0BAmVrTWi{_2Te)E|F2FWQ|i{j~#fv=8#N z8{=wE^wG}fsr}Jkzc4T2o6eUw8jKx?uff=dxEqY!h{wU$lQA2WgeXzfJ z;xF~bU!0F-EZR9A4bz|V(J*qf5AwAe<7!Xz(az|p{n1~)7>`D#@o3n1G;BN?HXaQd zkA{s$!^Wdw=l12~d^F7ZZ#(;f{n;;+!#<*X_7}%x-%%g- zBlTpTQh)X@=S92orN4GSj`l&mc4J)ai9XsHJ+(jj>lfxlJlgpZkA|@W=W}7~!?|4; zyK$Zu#-5z>g|Rc|e_{N^xnLN75ub(e7jawLiRap%I4_JG;=eHRi3`Jw%lTy(eK^+) zqbKK`Vf@88Xqb6%J{o4ewqpnTV;|*UH|1kb$HmU-gZ`s)|wMLgR1 z68D6$1MyH8`w%CEu^aJI7<&>|g|Rd7Rv3Q~hlTMM@mUyu5x2FSc&`14^TNm>{tF|Y zxG>DP#EW6{A&v~AC-G$%e-U?vnHTYBnEBd{9qf;Nl!M)rk3Ah1JF5@&S5N$+{`kvz z(e8ZduN{!1eUPu+7*~6uk9I~+?T`NYg?SN=cD}?tVeCLW6vjTpNnz|p{1nEX#8qMJ zOuQAwU&LWy{6%~g#$Uv3Z6}^A2WgeXzfJ;urPDU(Snm=SzR>fE?|EeC@`#+7o@WGkR)& z^w%%Ui+Hs2CGM#mh=;=1hd3#W-H4yU*ps*_jGc+M!uX3gER4U1&%*eNxUKEPbL~%@ z7e)^8Ul{qsg<-}eUJRoTaby^O5nqP!7jb8pc@d9>nXm2G!T#7sIoM74*wb;bv-)6v z^~5jgkH4H3?ar6}+5tJ*2l?8KakVG2PA=S$oZ#ty_oVeCVk6vl4E zPhspyTouO7#9LwfMI08!U&Lo&{6*Z>cH+7AC(a8ahxjjyeB#0|;}S21(T6xPjGn}o zVf;nh8D?I@qhaQ2J9e-?_E8RYQ$F@|Tlfx_{EPV-XTc7}U$BpH8SG~K3ws*>!p_FO@RxBP{AD~Sw;m>OTWm^(f_d7DI;f2VcT5${O`Za zjC>~LiZ6Vb`Jr07TzkFizRbMaJLMIHUuGVdp7ODq)@BC3m-404*JfILo^t&Wt22G7 zHOu|&?T@brUibcr%*l^6&9%??b46x-`;;GTxiYil=fiUCeFv<}?E6B>*F3v2bNVeQ z*VwW$GyUq6A2@1NaOT=o(Wk?_Rq?l#epwYV%l~tAjP>Sut3!v1)s}?~Pc2y<`VT#N zdCcq6P0M1ww?DHi?C{i8%fdd}S}!ZLTOw0?9=P?>jCMZat53uJAFcc}{6f3_qQ8FJ zuk*mrZOzz$(LR61!03PN{DC2dcKu6#$3>3%wAeZz^n7dLfYATX>H}h4gYWDg^KDU~ zf7oH<;C^ABT^jTXpRT&*lHga~z9chca_ZAYEiTOz7N)%A@k=vZzD#{r-1M@{*hf-+ zW&UNE8N*ZVck<<#p9ZB|XZ7XL-u=oR(SO}fJwnd&y?TcHIv@0mao;}mys+E(4KE0t zpS-JU%;k!TU1N@`N1h*Zue#UyVUs7Pofo!3rZ)V&;JmPH{U6T_n_s&6-0%hM`jr0q z^xem|hi90?bqduPx-yV84Iw|R&zh~R-vpweZ`{Hde z->x@p3pQsr6yE0o6B#&J91>kU9HUEUZ3)SS{pJywMhB9@78B}E>G9DqZX{sEE$mU;7RKoa|ROxN4OiR&}-d#8Np{0X7wKA%kp|Nimggz)c$ zTPB2mY1hB>*T2ZozpZYc5dOXK!lZxRzyGQ?A^dy(>ha;2e9ld=-rn=TO|cHwSXIjN4;&kP7Iq&S ze|z(!u_1Hh(y=jChce?rhZ|om2^%gxWK`(?>*|p)ue0tS8S|}j&d9LCp|wVaeXjYo zq||PSOzk;&a!J^E<}D>*|1)kZ3BS%et?1EW9r3UiQQ(*JWcbyW+a6 zd)c^~uFJZY-TK&dS@*KlZ(f&mFPpNilsD~lef0VDpV!CVF7I@G$o%-S>tn3KVb_Na zmrcArbnEijkgU%JzfByPbzh#?XK2>_I@@t*)_uHoqoG;%_r`k+&3cWUx^YO>=K*AD z!!O?+lJ#1>^0gsZui?ysAz7a{XxE1H*M>J9R2=#=US1q}PWrAm`s}y4IR3WnFU28~ zcE_T>Iv_{gnlCIa)%l5}fBt^CbbN8lu}z=inEOvB6o*avd^(#bh=f*mA zsSMasSfpwMT!iz1`dOitBCI z8NK3q+uXHRTyOQe^@{6_cCR=3d%Yn?efDYEE3UVrswVyO*IT<^d&c#4;Kx1Vdi!8z z&$!+$o6s}vg;@)GW{2K*Z0;HOv`mlemP0Z*KH#_>*-lf6ay+PGk8FopDOc^%BRk}w zwEy&8J+iG1P5J5JJ+l8=cucPUO%L?QcJH6^4Rd>B7dA=x^<_P>cl_BZ*Jt?udSokn zlkyw2duHGKGUaEoJ+t3#P5F#&J+sT}rGNWDanJ0C?kS&lf6r{QSt&P9<~65kss645 zm8+D_aq7ArG50eT^$43Zd$dQ`s%UJFu;C^BdW3CzpVuR7{%fZm;foQ8ee}_~g?+=G zH%#dpV>K=A8)NNtLEjjwX0~sPm2J>B#_CX|Z;bWfE`4LH3x2&a#%i+V%D7Hw_j;qh z*Bf$NhX%G3kSsBvDbP1gUj{npY?fu)lL1gKF@#fNdK(Q^IP8NpY?gZ z-Mao+pXZ;cJRs}ye61q}MEjLp21Nf`hYScgC3g=9`CXqG5aV{OQz_QB%6%%ubHY7u zR*L6`F)jCw=ZdON?H$h>2REr4&mp~MCg+9ozaRS@T_t$-%T=P!>zRGxZ_jvspOD$E zUO|lY_6-H0L-9KWpWTvNAV+za0~tr+)0 z_oFMuy)g0Eig7Q{u0HfvALOV{@tzgqUYPb%g}4`HF0Byv!mTqa#J!NYwL;trORuO9 z_vy@!%g4RYt9QBJyNk=kbJy0p%Ej~8mS@VvbJ{11%f<8C=j+SGb6t}v<>T3Jee+Vz zo>4yfv>Q}D{Yf)_Rad+s>W{nX8p}|?wv~T?*58094=Kp{+wi6?1zCSHu5DQmwt8(!mGJMiM^+9Vcw*&Pi#lIcIo7D`$jY&H zT|BLFtZ6gfs2pqE0Y6lZHE>*&D$%~YMV09P`AXte-)oPq6#gBvf2Hv6Q@d6Q{~}ZW9=Bqz@bBA8_X__$@cv%mU)uFA z{q=8^k4vJ@kPl1ZZ(n+^BxIIdR1#y2d8s6Hxc`}?zrSavl!VTeZ!3wp^thoU=Ggqo zl9)T=`iyi@K}kG2eO9X^`}E%FbI77YO0vg4nm(VrT3C|3^o*3x=vb1yyK2h+JFg@= ze?$75gZ$suq|CUsqmTXnmFTG)^jALfa$M%?vmACPyJz~$hJB8|H{~OijtHObc3A1W z-rv7;zK!-MwZq-pMudGPeLo`X_RNYAVNYc0(`(-z5%yp3deT3C&o*2*BK$?WKBd1t zee&S3*(LoN=AI9mwi=tgc38?aPa2!8_(;mjFC3d~{cXx$^&Ok7)230b|AOnsX4gHF z^8dz+&9-ZPNUpuj#If1-3sOGguCdw4NxXu0+7<5^n|*#$o)5h-#(iSm=xFaYe{}R8 z`0D78GxyEWA^+zON5{B}*NhH*mTejxdfr#=#?XIswHsqzj5V`q`fjIUqQl)Y)AvR6 zSwAgh{Wm+qOV@Vevi%BDo$o(>T(-`XRJRj4j>{g`BIQn} zjLRPSPO9g?F5|L)_D%VQ?&Gqz9guQ^E5~KeSdqT_;+wkTo=TZ-?LN3QT`4oKUmi-C`Pz;h?2mnvgWZ&m zJslT2s}J^9PyC|(`0I#$j?C#s`&W}&=9vDw9iB3BHokR4t{wURy)tFSJ-c?w=u_kK z7P&s?S>ef)(f{rVDKoF9My1SrZO0Dw$3DuzZpz1=j*Feu2m7lheo=q?<-BMgS(46? z{uggd8976`9F@}<`O{{n%(w;R3v=!0b4vS^(X;#2DWm_AJ5pv|FHTCC`Pz;h?2mnv zgWZ&mJslT2s}J^9PyC|(_={L8>l^LFDq;E)!-SDTY!gO4F;AFriG{-GLyQzgPhzJq z`gcuYsxb2+)(SIU+p&ZFv5#`FoAR-z<6>v^!T#!rU(_FeIWO9YEi*3ti8;f_Ar=iI zpBOdFxWuku^dY7VqbIR$82yQX!_14=ILv%)#}4+#KFYyv%Ez9Li=EX6`>Q8@QU8`# zjEZ>;>^&;xTesh+utWX9qryI&hK&lloik=s*z=FuM}?hNPfq?e@2>}+8Wnzd{l!t? zuZ?e(wmVy5& z6ThfG{&HTlyZ+PPeE~V{7sz)XVO;kY^l{%oPxmAAcb{Tj?qAH;cI;q(?4um)rhM$_ zxY${Ju)liZ7xf=FU`cT{l4q(pA~&} zK*}T6epd9)@#z{u`}O}z*BSb^>YFlhp7}0aSNH9+qUfsuDSz2&WzqF}qE1n+s+=IHZnlTGor?`D1q znLl2>F~(Z?#D>seKyrp!yG^WKE~EZS{#`EPyt+0{-Zkat+wkG?8SOA}_uVqu2RYg; z`@n7)?OEg1-7?zw(|32vXn)%E3;p%iruTQxYPTk1DrD8I)vOZ#*?qV#XC|3|6J;s4t`#ya53 z-9v{zM^_3x&rg2mdQHBuWv{IEtX4hw9i6{US|z`!wdX&(RLW}43Ii%-wI?#Q=fJxv zWwqyb4<-Hc*KLjD_q+C_U3=1Bdw!6-?^2(+*Hno1wtXu^|9yK`2syMXpZ<=EFVv^O zgB42kd@kvqzb`f=@5G$fem^Jg$MW;Nta`<;!}d#S#XVbZ)?vZDCe(=Q@PSin#P#r6 z;~H_Dls%wETtBp{C;inEIqKPIO^vudXLYO@*KP5u$@|0n^<1(2{&AgmTDpH+|HGcE zm+?BBd~tI2BY!Wyw0Dv(pd`I#&w4aD&-{JLW1A-52xiiI^Uq|jUUgl{FV#LcGdCY| z+546TnQNX-+b`UHP_);&@}TH{`?vK&&Kv#fhx`k7uOH*i9NRo>_59IIGX*~{+XGS(i*T8L` zHqX2^HRb{0U`mTBAwtFioU*zcD7Z&u4>+rT^N&ozHI4X&k>EB1I z_loQA*JFCcbvSCv6|tVYb5Wn*4?FeA>fi0n`egNQg?;;E_3xKI_0Hfc6> z_s;6y`J+qQ`&?YwzvFSeL(bXtdx!k%ckdnJ-Zs5&*y{GGeY5)aoFn^Y_3!0p_08(v z9|!c!>fh!!_s#0xasTR@)xW);O=41c|6cM^->m+v|KGk@{d+?a^U}Y4U+tUKzkAH- zo7KMuU0f9J&F)`Z7`&)jCf-3E+b|RFe`Yqz#CxGNEi&=Gh<4v2(cgFP$nm|?`(-lm zKI)fmi{d?1*|&@0{nhH}Me%-b;*CY|ey{A}W8%H*ix;;Fo^?&Dco#bUwpQ_uboh)` z@$Pi$`>o=g>gLU@;$7=S)sKmHux}rGOtkOc?U?AF8F5U=X+HUwkiX~LV`AK2suzZ> zetxnr-XS-=r7+$tA9!V9ymP+))WUcdefCj>@s9fU0}JEbb*+60;MR9KqE6Bt>+jdblYsS+}E^HlZ%NY;1j>?O(BKshq06W<&llE3z?evu~P&t$I&7G<3VAd6Tf`uV*z0|DG_k zN%;4Q`))xrGztIK+~u(FZ^yESg@0++zx3C?Wgco2`dsjB z!_fKrPa8&`tKMrEf7|Yzh9Q%7uO<4scOXaI&i=h&sm|3J#a!yQY!q`m{_I9E_q&HS z3Y*kBym8nqGw#rM4*Y!Jq49jUy33*QEc*M=hsLw$)*6S#v*@E+8^^Qg*B_ViUC%X+ zJ`?Y19Dn=NHH|~&vt1jr@$R>=VXV(t4rmbZ&^mXNa{t+-eFlG6 z`nTt7DwTO=rGsOv=MOqKboi*GUf6B#{pyGQFKw(B^LpUDdNJR}o~;*lSbR^tQu`!w zwA;ml>V-Ym^-B8Z<0+r$fj*9!`xC07f{i%>G zjCHB%g@v(RJ$P+ltYfS1D2(;(=;?*A?$w-E80%rd>xHpSE_tUg*3ZL|X8_mLT5lD` zdOPQp!dQn3dbJ4M`p!B$^xr=9@VJ*p-G6x8%V*wmc-+ghdoR=9dl@<2%a<=YJnrSz zYm)x?=fD=bw1|88tOHxbz5GbK7I81P`2C2m;m9+NjCFGQ(MQJm`TYJz#`=86_Li|e zxBaALtk0j!Y#Hlw?+K;tHG7x#-`cTd$SMENmLdPpf|fDve#zXuf5#>3q&%l{i?|M( zo!=t%>pL%P5&QTfJzK>7-l<26*!RbEYZ1=_x1HG{o)eyJ+ajJH&N-|_JXh>jwM9H{ z+_LrXcn-N?+2QegGI!45@!YbxO!K&ZpSY)K@YE-p#xu{b*PF((Q2#HR#xv6G<(tK` z)7nPO;+g7{lbXe|){6s5+xNVywEtnxHw!s+KWrBA|Mz3F829UwnuOgBSk)x%-*;b3 z_OkrC^hC0+xn9k=zDeA_D=%&m_b+n1e+Ooo#Qpo*5lR32{rgU`hx)A=?cTri_x^qP zyLJ(4hV9?=;4+b+J}8*@v$_^z+}qwV5*zsp~47vBMHf4^OPA2?}cyZCPKr?1<^ z_k_EB*(U7#c=G(_b(=}%;&;O9PfMN;^EQ7wc~;cs%L>|t&HvciCTxyOZGOjxZNlcY z-fj~%{~>uU)rPcdbNXxZU8=VWeI_J2>#yo7+J($%@3xDvo}AMzbXf9G(m%hits34g zbbjfgb}^Se$F_?(PI>b6_&(~*OJ0v}lN!~2J-%65yL@4M%k=w03*#H7j=dLV{6_km z;}*s@Q3LBOjBlkzS5ErpueS!fFN|-i+U>hI#=WKZy^PNT;R@A2E!vCdapd3CJ+KhM89_K|7#T^;*K;oz%dA9?rG()R0{l=eS&uTnWZ z)(;N(<3Ai6<34=V(9rGomxsju+iUHR*!$+~mVB$9e@FLu!{i(O{5!GtjvpF(==6(* z#@>od_uQ(ZhQ?le^Z2BH{N}#Ymk)~eueuJ3{?8}h zxGINs<F$^eNQRxIi|GF?$?z5ZS|g|GVedH zbgb`AF4bZ97oQcmH@(09li-IZd{N|@nb~7ak$cBaXRRr6PwCfhO_6&I?XH>hcg;kO zYv!u2R~NaS?_GU$k!$8PjaC)8_gzwFWs!U0s&Xre+$%Rdu%gKCzSea6pvdpjx?TH0 zk>7po`}zk(eh)U|xFykl;CD-k{C=$MoTWv6SGMfY4~zWX?8j$5D)KwDfp33Y@A{VShVJ+A*w75)+TZ|?`H#Xa)Lf@*PnHe6dRuG>!Ks>k(QRIhqm=hcp_9@jte zy)Q;~s~-2uwq8m9{JM9@mDS_^qTO|m{;qppB;Tfb&la6t5IVovrXc#9adbiaZT%w) zLMH8wMSt&EurmC@z z4EeNb>@TC|RgL}Y;`^$`{#9^w)!4rtIjw5!U#*&ywtv5SY5zCA-7n;P_||?QfBQ50 z#ke(p8ksTnci@Y~5r0`Sx+G#owcad=*vDggjEvaFe@++~v5zGqMn>%8yxAio_OaKh zkrDfNcb8ES`*^wfsEB=J4;~eYxLFqBA!LN{-wYEMUMV`w^jd){%!ei|A=SpQgcAWv&KD?oWIVm$?qOI zFydK%RvH>M%=RdbSkfnd4vQGmo;MAP*wcuz!y+b?z54oyRZaZzx`<(Yar$-9{?Ni} zqyK)#T^n*bzBx4HukJoH#$B15UG-krwEw-qcaI$(cKdgq@nPE)=Z+7X&pT~=_+sFh zXq~eaL-r{dBtEzPPTC=Nt1 zr3dX2>qDEeyTm%PcEO)vw>_`gkp9|mL~?%Ld*p=kx5d3M{Df_BFI>=iTigr#wcQr?!d<6si+kb5 zp4;MH=rC?u+zZ=gZ;N|j#5ddGUYJ;Sd)y08T(~{%g`@tpJ?@2v2Y(y>t-fY$__syp zbDTOu8sDKX0DC?$3DI` z>8S@>t=*zIfKlb=4?9--W zyLh)y^MB2Qm)7Z!@tJwb1s&o&!?hzj#CwLLCw7SU47B^qMt`5>kmEDnrnlQ?eD)iA zY5RE3@bVAG$9sk&dLAF|88$6%7w;JsY%Pj+3zJSP48CDQhyVaZul&mOK!&Zl}NvF>rlM*qhb9vgB77Zrv4mD7r1+;Imr4O{i@ z)jV`QPZ?2 zPIzFyn(=P=wcBgPyXC`Ps2T5;@Bgf{ecd0W{VUboKjiF^*+1kj@3Mc4yYPi-VXOb1 zSUui{|IxU5yeHqdXZ3i0-fKg(c(2~z<7)A~{he2;#e4W4W>ky!^P8tui}&^|CRK~~ z`JW`eYdquj-Q;TV{{N)u)gmrXr&j&g*Un#3H}>4?k{FYF$~WWc#U5AqbP~hL?{ViP z@htbalYXohdtAc`^<$4izI)sqht`ihZuge;V~;yJi9fo>(e55cfA_ebl50tQPO4oy zbY5PmcJ#TVTN%IkMZrvb>lt8Jx%JydyJ3w zEalPP*NHyE->MUTJL$ z{NucM4qRDsemn<0zWw}o4lKC1Ydi-cUmL!O<=hS#s znSAi6(SE^wr$qmy`<)VUDo#2%(qI1~NB@31cyai5 z()6T%{{AgV;tu-vjfU@qe|z?QFZ^4wYDw5|?yVnX{AT#)ZXad*X88BUA7%Vz_{a?( zX8dOOuo)j_{AT#(J|AZMW_b5QO8N4ymqwopA6XiId(Rb1L+0comd040m0ubO%6 zc#hhT{GM|EJ@NEu@tkn@fN8N`*BLb}_VMCz(_(+8-TjyT?!U-!|2?nKw0M4aWXsfe zu6Sk6)Og;w?&_)W9J0LW)ObF5_2tR&9M$aG2ZP7$Jtc06gd-G4KC%+UwA0`eD&)?@wZR5m>e>v^_m=G^}Kg-=A2>5 zZ+<%N1>}2=v^jQ0+&fKAnGyHYt!K@MdyRJ2XZpML{+V1$>hnUKsiE`hWv0eG{>O%g zwV_4K%x7yb5F zaD#b|MW5Q&J{Es_cIL5=d11xJVyyd@JsLXP-k?+Vq3-FqxtfP|%07E(gIqlEreiu~ z2lYEB$LF8jDSPhN`Z@m3wVkpT&8?T?e?QtO`)T=la zIxl7Pukc&S%&TERdVYub+KwIUkA0Mb-IR|#9Tz*R5B672{G$FX7hafs>y`Ap?MrW6 zm|gjw^xW>DpIw;!*W&bS?;k&3n7#4a^!)PWH80BEQa$ApI$V@3e_48Fx&3t)WiMTt zo=1Ln_C?w1JyWi=>7wk#2d8{a^KRMWs-%2J|8CK~=BaMczt=b2LQaqUyNCRaCv=Z- zpY78<^cgj#d+538p6;RlwUfHXyl8*nrS`dNhW@JSnXm2G!T#7sIoM74*wb;bv-)6v^~5jgkH5UX zX!ri2zxNk%yuXm|{l&Q6U+Clgg`VDD=$xO>d$)UylD6Oq`%iKa=f0A?{&_&UjOLheSx0d zFX-=m#Js$}n6K^F!T#7sIoM74*wb;bv-)6v^~5jg-~85>bM=%sAKl>2mvi-q;FS-* zoU2m=e>3mpT>T<=^k*;U>KeiG%Pz>(JAzL?d_k@b61?KF1-W`k@H-DK$kkJVuli^~ zuAUNHYwuU0eb3`xiT-yFc_rlh^U+sA{w43d662QH_)6%rXT?`T&;R`6)zE*={;$To zXs3P@@Y=t=!682zb#1v4+|U%|}RcI;q(?4um) zrhM$_xY${Ju)liZ7xl+qd)<+)+qBO=FlG9$oRzNa$XV1mW#m7&Azl9&_pr$+qt8#t zdsuWv&s9xQM*qH5Qf6MGc1xN0+KwIUkA0Mb-IR|#9Tz*R5B672{G$H&%X!g$ez|lH zqW{qYQ%26I%Th-E^+%?A5aWJ-W6J2$a8b(WdGyx&K9%S{y=v$1*By0IX1=y#2m50m zio97%h&pB+KbJ%?BusP3RbDqQIJcrGB4x95FHs?8P&T|-<{QiQ? zc@CTN95&~j@4Vx1iHYYZ0PHfnm*swXVVRK@`=ER20*A1H=8#X^S zY<_Im{MfMhv2*=vrTMX8^JBy2$A-<14VxbuHa|9Oer(wM*s%GrVe^f{=0b?Cd1}Twq3iKGnsaCCd1A1Ig{ZoPZZ~3 zJ+L{GVRI(K=1hjoI}Mv38#X^SY<_I`(R_Yv*!Ed3!76HHm5FZPF>iXy0AHQVRP!j=G2AFsSBG^7dEFZY))O+ zoVu|2fnnytcY3h-bz$@C!sge7&94iaUl%sNE^K~X*!;S%`E_CQ6~pFIhRvl6n@brs zm$L0%hvrhI-CWABxs+jZDZ}PchRvl6n@bt?tPSkh7TB{buxDFf&$hsxZGk=80(-Uv z_G}C6*%sKdEwE=>V9&O|o^63W+X8!52=<%{>^T?Mb1tywTwu?+z@Bq~J?8>@&IR_I zi|wvCo^zqyb4;-3m0-^+!Jb!wJ+B0NUJ3TR66|>;*z-!T=apd3E5V*uf<3PUdmat; z+#KxLG}yCguxHa?&!*W<{KEdkFJRB6!JbWnJ(~u5HVyV{8tmD$T%Y{eG}yC#u;PN8hX{M#5ca$w?0G}j^MnZlkkg*|5qd(IU0oGI)%Q`mE+u;)x+&zZuW zGle~83VY5J_M9o~IaAnkrm*LBVb7exo;ig*a|(Or6!y$1j7*=UJ#$LCXHH?yoZ9Za z?3q*AJyQ&Ob{O{TFznf3+g+bMJ50N0hhfhS!=4?6Jv$70b{O{TFznfI*mLW!=fq*p ziNl@~hdn25yZ5i>#A)}OIP5ubxLN+3IP5ub*mL5r=fq*piNl_?hdnb6duAN=%sA|s zao98CuxG|$&y2&K8HYVH4tr)C_RKi!nQ_>h0I+BOVbA`;o6`d} zcL!|l4%plsu(>;6b9cbz?tsnR0h_x6Hg|{Z`q$hYw3{miHcty|o)*|VEwFi7VDq%V z=4pY=(*m2P1vXC$Y@Qa_JT0(!T43|Ez~*Uz&2pH|7TBCEusK^` zbGE?dY=O<$0-Li1u945#0-Li1HYX2EE*;;2n0tqIbML_B-m$;$H_W|5ySaB@bML_B z-hs`%1DksXwq^lr%>vk(1+X;>U~3lS`sZsFz}75)tyutDvjDbcf$i>J)-0gidJ3@h z3t;OPz}7E-tzQ6Jzrc3)HR~79Zv6t-`USA{3t;OPz}7E-tzQ6J0|K^I1#GPf*jg2^ zwJKn1RlwG&fUQ*lTdM-LRt0RW3fNi|u(c{+YgNGJyMxWk2b=p2HuoKD?z>$7eC|8g z+;_0K?_hJ^!REe$&3y-(`_6XP8FSy!ZtgqST!OH9@L==c!REoU-Dd;y;L&a#JlH&V z@SpiSc(8f!VDsR?=E2ML$>%wQ&1VRk&k#1BA#6TF*nEbt`3zz68N%i>gw1CNo6it7 zpCN2ML)e-Hur&){YZk!PEP$<909&&Fwq^lr%>sCNzGeYz%>vk(1+X;>VCyNs)-Qmq zUjSRb0JeSsZ2bb*`USA{3t;OPz}7E-tzQ6Jzrc3a8S59&ZVd?7S{1OhDqw3>z}BjO ztyKYAs{*!G1#GPf*jg2^wJKn1RlwG&fUQ*lo0}9iZz^n_QrJADuz5;h^OVBoDTU2b z3Y(`CHcu&Ro>JI6rLcKQVe^#2<|&2EQwp2+6*gxnY|c{HoTaciOLP76IZI)4mcr&N zh0R$Co3qq**BNt`(r!*#*xa+Qxo2T>&)V+VV(wYm%{>d7dlokLENt#s*xa+Z{`uUq z@RV26?~&lQ{@W@0j}IE;o~xTI?v&l!F6ELHow8TIdQh(Ylub$hPAUJq=ZV>hU)ImH zKXJ&3*$*bBJg(D;*%4=?e8-h1X16p+nK<<+2d4b-bEWO8J}vG4^0rbrS5@mA@@qCv zzAws;`|a_aL!V>M>KuAbzOZxXzo>iqJreVxy}_n~b9&PMgyM!dM$W=r8|4`JlZK?s zxGh$tj6PQ!p1!L=&lmfpjQ$<&N||~6FePQ?YddzZKlV`$c2hp~bX@GLKGr=qgq@W%LY^@60sUKl~>N~*Js(`Ik z0W&UjB4BG(z}BjOtyKYAs{*!G1#GPf*jg2^wJKn1RlwG&fUQ*lTdM-LRt0RW3fTG} zuysl7LtPTsx+Ji5Nnq=ez}6*!txE!1mjt#h32coFm|XGX=!VH5PwsA*-16k~hRHck zu5XxJ^yC1C$x%;kaG2cnCJ$Z#%j1?N82p<&aBX`Q+GlTypQL z4>|eOlU)7kZ;cGbqMaPwF#XBh4I_t~-Z1jX^$jyFIly7`AvZXTp5zRN(Vtx6F!LhE zILv%)#}4+#KFYyv%Ez9Li=EX6`>Q8@QU7+`FUozF#aLHfdQq%D?_YUQtV;(CyC~MH zO}8ce^Xu5XPh1r1+sSWU6zgY`?=On=^T4CxmAyWiI>ks{1myqLng?!gB#&vx|AJ;wf zbUj3W*GcB(`pJB4#}4+#KFYyv%Ez9Li=EX6`>Q8@QGfi!cUk(YZL^f=UpK#wA!lmc z^x8xI+tbtQlW|+NO&NXu*pS|j==s#ll+pjd@hLN}>xZYzd~L@L_QyWT!EVaOo{o#1 z)d%~lCw@_X{N=o8KmD}!xjE8*@QRd?v#DE$Ts!jL`Xpt>?Up$q*N#5-+?FzWezQ1b z^uKCL%FL_At{rpznXm2G!T#7sIoM74*wb;bv-)6v^~7K5&-01%VjpzA?2p=keN+3e zpK3SuS?$UGtDV`GwLkl{eqkTiU+nL;v+vuV=K-oc`}VAgGF0Ku&1)CPiC=cyS4 zv;N!8zF>d$3+1qnD4+esaoKm&hy6%B*{9Usnn8?3J2iJ;`csPsMh-Q4VB}M~2WDJq z`oQQztsfXYsR0C|Ked5i=0(jQnEBd{9qf;Nl!M)rk3Ah1JF5@&S5N$+{?-g)EZV8L z1Jj>cJTP*o`2r)K+C4DiQqu=UA8P%;=t&J482zaY1T!yc2EokNcI;q(?4um)rhM$_ zxY${Ju)liZ7xlMh5M$9!4HuaH)OLZ9Q8AQ7^ zgJ5e0!PX3dtr-McGYGb35NypL*qTAGHG^Pl2Eo=0f~^?@V`rb|vA@sr)(oPLHG^Pl z2Ep|AIT<-VKU*`1KGqC^tr-McGYGb35NypL*qTAGHG^Pl2Eo=0f~^?@TQdl@W)N)6 zAlRCour)nlYkI=g^n|VH30u<>wx%a+O;6aGp0G7NVQYHA*7Ss}=?PoY6Sk%&Y)w+w z`kt`$Jz?v6!q)eMt?vn2-xIdJCv1IB*!rHZ^*v$hd)n?hPwRWqZXH$F`mM0_TVdnX$5Q--al3|mhbww^L$}lqhuEToDv|CRZww|)> z`p$aFv|FDVwstmb?QGcE*|4>np+5SAwmtWV`RE zt*=D8^_5`jE5X)Rf~~IvTVE;HKVM%7w*C%mZ6MfMJg~KR;O))QT0F3|cwlSsz}Dh{ zt;GXdiwCwA4{R+S*jhZWwRm7_@xazIg00H~TbBp6E>Et1zAg`JT^`uFJg{|nVC(Y0 z*5!e%%L7}N2evK`Y~3Z;`bx0%m0;^D*{*-BuSC1`m0;^D!PZxTt*-=IUkSFp5?rJ5 zRatUF!Q&6OD!xf5+vuuX9wFLWBzb`S_Lz3p6Z-p20&-mI4%|K{OCBNqw!`W{@oo8; zNseFli^HcR`F^LTd&d{U2IcYy(SLA~PnaAF@Rz~Uh1V2-GKrW{cTU4x8^CHs3pJ zzIWJs@3yO_`QB+a-#cuMec0UZu({u1bHBspeuvHd4x9TOHupPh?swSS{;)axVRQJy z=J1Ej;SZa`A2x?SYz}|e9R9F5{9$wW!{+dZ&EXH5!yh(>KWq+v*u3$udE;U8#>3`~ zx7~Zzyz#V~Hy$=`JZ#>0*u3$udE;U8#>3{c&-KsekcZ7751T_CHitZH4tdxd@~}DN zVROjC=8%WYArG5F9yW(OYz}$Y9P+R^jl8p3xKT`0H0PoGnc;wZu8j8Ty8q}m(OPAa@N70RhyN|Wd|R4-mF}XJNUJK z&C2DzgYWxpRxT$VJmB!z(OxigcJ%M^;_Q%9^y}=9|5M}VV%#-nJ{S7D@%>Y|{4L0= zeD;i7J{-8P(u`a#7xxoy|EncbdE`N~)3WX}E|Wpn=1$9e>?`Tt?_|HJ10ht2;F zoBtm+|37U0f7ty0u=)RC^Z(oK_Y&s+r``Pjur(B5YXQL40)VXrV7t#P)&ij2S^%)M z0N{u7wE$pi0l?M*fUN}pTi*e;jst8R2iQ6euyq_@>o~yHae%Gk09(fawvGdA9S7Jt z4zPLtVe1jVtMWPjVRQb&=KP1v`ER>+Gv`0;$RUpqY|ejpX1_G&KWxr_*qr~cIsajE z{=?Q#fX)98oBtm+|37U0f7ty0u=)St+4rRR|6%k0!{+~o&HoRZ{~tF0KWwds9Or8~ zz}9qtt?2+;(*d@o18hwP*qRQoH637UI>6R+fUW5OThjry1_5mTf7ty0u=)RC^Z&!< z|A)>051aoVHvd0t{{LM6eExsf{Qt1||6%k0!{+~o&Htb4pU?jfoBtoS&H`*L0N7dp zu(beSYXRi?=W7AL)&hX71pr$M0JgpZY#j&KIu5XP9BlU)#ySqPTgL&mjst8R2iQ6e zuyq`A{quDkU~~S%)+2z;{|}r0A2$C#Z2o`Sy?@RBPrLd5Ve|jP=KqJy{|}r0A2$Dg zu1`MyKWq&J*jfPakbErw*jfOvwE$pi0l?M*fUN}pTMGcT765E50N7dpu=O2a>o~yH zae%Gk09(fawvGdA9S7Jt4zP6`VCy*8?*3&R2inc^4_l7_Hs?QV&VSgP|FAj#ZP%yf z{HNWV|M0u{od2*n|6z0f!{+?Y_0Q-0ht2s9TSEah|37U0f7ty0u=)RU{qy<%Ve|jP z=KqJy{|}r0A2$C#Z2o`P`VO#l9AN7>z}9hqt>XY&#{ssE18f}!*g6idbsS*pIKb9% zfUV;Io97?49sz95f7qP=usQ!>bN<8T{D;l?51aEJHs?QV&VSgP|FAj#VRQb&=KP1P zp#YozA2$C#Z2o`P{Qt1||6%k0!{+~o&HoRZ|KE1+5%d4kZhZ&XIu5XP9AN7>z}9hq zt>XY&#{ssE18f}!*g6idbsS*pIKb9%fUBH7CVqGH8ZsuALz4C;kB-UZmV_Iu7?aC6 z3I9<2rd%#c_~&zO%H^np?|I;+Tpmlf#;Q`Df8f~Yv#|Tv_}iN&jSZP2myV6GI+Pg~ zI!tLaE_A!`<&yZVvG|Zt@f&2+*CXSZf9tf7@mpZUJ;#0j?w{YxaUb(X$MHNqeZHUdUhlO&=XIUyI?w0p z7l%*pDUSQX;nRDKFP?Sy^d98O6Aqu=n>_2N!>9Kw?>*x1>AlS7k2!pLk8}JfhfnW) zu6*LrQ*9exaLiQm?f&JM={?l1zkkg1-fEY5_DAozjQ8``{GR(+r}u7KzwwyqJ>3zz z%;zuO>z#bhW2X0jJ7011^xp78Z#{Z?&se^LYgG0GF6#l8^?=KIz-2w)vL0|*54fxc zT-F0F>j9Vb(0Kc$tOw&|J>c>(aJdh-+y`9l11|Rgm-~RreZb{D;Bp^uxevJ92VCw0 zF82YK>w(Mfz~y(~@;h+(9r&Az{0>}x2QI$@m*0WQ@4)4E;PN|g`3|`330&3#F6#l8 z^?=KIz-2w)vL0|*54fxcT-F0F>j9VbfXjNoWj)}s9&p(ixZDR^?gK9O0hjxL%YDG* zKHzd6aJdh-+y`9l11|Rgm-~Rr_`qd(;Ice$Ssu774_uZ9F3SU#<$=rcz-4*hvOI8E z9=N;-T-F0F>jA%Fk@bMfdcb8p;IbZu`HQRvT-F0F>j9VbfXjNoWjze@7g-OutOs0P z1}^sjm-~RreZb{D4D%Pc54hY1T%j{^p*XJ@j zjF;Jg%k02qcHlBQaG4#${6%I5E^h*t^?=KIz-2w)vL0|*54fxcT-F0F>j9VbfUj9( zJ>aq)a9IzytOs1y11>KEm-~RreZb{D4D%Pc54hY1TFkZd` zE_(u(^?=KIz-2w)vK|`m`j+)zysQWOx<%FlzHX8AfXjNoWjze@7g-OutOs0P1}^sj zm-~RreZb{D4D%Pc54hY1T~B_ zyU)iic=q)7p#2{IXVc$_?taCeP2;;icl9*?njfv6)_MQldrj-#{gS<=GbHUj!oc`@g zFL>d!rtw~f&F_7Xb*gRE&tEXr{Mln)FrCY9?ljMQT>LHUfa9J&o%^a=K7Z;-IUTNV zc_O&X4qRpjF0%ud+0l6Ww9F3UWp>~)J8+pDxXcb*W(O{_W0}x2QI$@m*0WQ@4)4E;PN|g`5n0Y4qSc*F24hp-+|w? z$nU^=E%G~X`5m}C6kL`EF3SU#<$=rcz-4)0YqodF@-SYO2QJH_@%D9D9>&XR!DX`G zGFfn$ERDC9%VaTLCJQc;1((T!%Vfc2vfwgVaG4#rJP}-e2QI$@m*0WQ@4)4E;PN|g z`5n0Y4qSc*F24hp-+{~Tz~y(~@;mS)i#!xumIp4&1DEB2%kscwdEl}EDv0k z2QJG4m*s&^Tx5CRa$E2P@moSPlzX2-eNac*{;n;qw7 z$GO=X=QeLX=Q+;Jj&rl)-0V0vJI>9HbF<^z>^L_&&drWP@moSPlzX2-eNac*{;n;qw7$GO>YZg!lT zz46@Ux!H~9X2-eNac*{;n;qw7$Li-`$IgqJ9p`4px!G}UcAT3X=Vr&b*>P@moSXfg z$E-Uz*iXO16K8nchrVt(=4SusA8as<$GO?f&&`f=v*X9HbF<^z>^L_&&drW@5wkfJI>9HbF<^z>^L_&&drW9HbF<^z>^L_&&drWP@moSPlzX2-eNac*{;n;qw7Z@lZ9o85SBcAT3X=Vr&b*>P@moSPlzX2-eNac*{; zn;qw7$GO>YZg!lT9p`4px!D_UFXU!7o|_%#X2%b>?2zGe;5aus&drWP@moSPlzX2-eNac*{;n;qw7$GO>YZg!lT z9p`4px!G}UcAT3X=Vr&b*>P@meB|3!FYo^RZHB((W;dRj9p`4px!G}UcAT3X=Vr${ zow(QX=JPyhoSPlzX2-eNac*{;n;qw7$GO>YZg!lT9p`4px!G}UcAT3X=Vr&b*>P@m zoSVJz?!(;d#&fgd-0V0vJI>9HbF<^z>^L_&&drW9HbF<^z>^L_&&drWYZg!lT9p`4px!G}UcAT3X=Vr&b*>P@moSPlzX2-eN8~2>5 z`P}R{H#^SFj&rl)-0V0vJI>8M%vreEac*{;n;qw7$GO>YZg!lT9p`4px!G}UcAT3X z=Vr&b*>P@moSPlzX2-eNac*{;n;qw7$GO>YZg!lT9p`4px!G}UcAT3X=Vr&b*>P@m zoSPlzX2-eNac*{;n;qw7$GO>YZg!lT9p`4px!G}UcAT3X=Vr&b*>P@moSPlzX2-eN zac*{;n;qw7Z@j&no85SBcAT3X=Vr&b*&FZmIXAoU-0V0vJI>9HbF<^z>^L_&&drW< zv*X9HbF<^z>^L_&&drW9HbF<^z>^L_&&drWU_D9p`4px!G}UcAT3X=Vr&b*>P@moSPlzX2-eNac*{;n;qw7$GO>YZg!lT z9p`4px!G}UcAT3X=Vr&b*>P@moSPlzX2-eNac*{;n;qw7$GO>YZg!lT9p`4px!G}U zcAT3X=Vr&b*&FZr=4LmZn;qw7$GO>YZg!lT9p`4px!G}UcAT3X=Vr&b*>P@moSPlz zX2-eNac*{;n;qw7$GO>u`3pBY&drWYZg!lT9p`4px!H&L3pYE?&5m=k&2Bt5JI>9HbF<^z>^L_&&drW9HbF<^z>^L_&&drWP_6#(SN~&2Bt5JI>9HbF<^z>^L`jP@moSS`^vv9NH-0V0vJI>9HbF<^z>^L_&{+k1CwfxaDmWH39x!H~9X2-eNac*{; zn;qw7$GO>YZg!lT9p`4px!G}UcAT3X=Vr&b*>P@moSPlzX2-eNac*{;n;qw7$GO>Y zZg!lT9p`4px!G}UcAT5N@m^9HbF<^z>^L_&&drW9HbF<^z>^L_&&drWP@moSS`^zi_kTT;Dj?H_r8qbA97n-}vGyN7pyb^^J3V<6Pf3*Ei1f z-8k2G^SQopu5X;{8#^x7H_r8qbA97n-#FJd&h?FRedAo;IM+AM^^J3V<6Pf3*Ei1f zjdOkDT;Dj?cXPPDajtKi>l^3##<{+6u5X;{8|V7QxxO*SBR3%Ce&pQ4oRD06m@ATV z8*@ltj&963$=!{)C^@|`Mhw?=Ic-E=v(XSXUEm&>e2t|bX}@Hx2Ux`di1|KU6<<5ZR=RZxnZ&S9HiJf+@#q0 z9JAPQxo5F@IBBsuxoWZcIc%}>;_JN9ao>L zNB^tSb*cW`wvLtC7U#CbxovT7Tb$b#=eEVUZES8iK#a@*qEw%GjoV4eDt+t!@iwm7#f&TWfx+v41|IJYg%ZHsf;;@q}4w=K?X zi*wuJ+_pHkZR5TE=e9MT+ZN}x#kp;9Zd;t&7U#CbxovT7Tb$b#=eEVUZEV=eEVU zZEEIZExovT7 zTb$b#=eEVUZEiSZd?4ih1(YAw#B(^acqR4LdBabMDAL z{K8G+%YU%rH2+hN*>PIulLzlOt$*5kcASp;2cO?@s^=Tu+HtD$2|wR)s{hNs+HpEB ze=B#sjq5}6^`~|8t@ZV@s}U6#N8iShe= z8~@8L%O_tveh2W^*YC1?#J9)qIsVyQc3pnmokrg7F}p7R{iP3m?>^P}<2Ua<)&J6ycAw76_y<0+?QqYSfBkun8Q40vdFyrqTYt^H zA3Lz)9=pNz1FL8Avqo0u%kR9yFs}YpJCE$V{^SKCJKx6jq51mLI{Mc7`q^>yxq9@! zI$f9QcfHzQ#@k=!x4*2@{<41i%W>OZ>S=$ev;C$1_LuW&e>vaA^`ZIt(>nUr`uf>% z^|^ZVzdBu)>UX_5FXP>x=6By(r~BFZ-RF+m{jZ+(g*w|W>Te%8ulASoZCoFkuRpD$ zZ>_JN9ao>LNB^tSb*X-@hwU%>uKi^{w!iGt_Lu$J{<5#zU-oi2rsc^U8iG{5`SI^ECK?>=|j?tk^P zFVxw7QGff$d9}ZsZ{zyVeEn%1eQSOF?6~?|J^Ejru1odjX7{r!H#^SFj&rl)-0V0v zJI>9HIj%Q*z&(c7joj?UbF*Wv?2oQJ&dJSgJU2Ve&5m=k&D*!a&CktlJU2Ve&5m=kWBsqr-0W{YcC*39&byBDu{X}s-gums$#`BSoRymkH-(!g-l+UM8HE3Fl?Pd6{tjD4g>O=i|cpxNtr$oR16V;~M5Kd|Wsm7tY6p z^Ks#PT#b7_*nDnwoP!JJ;KDh$a1Jh)+);^WXm$$Nlyn?Ksu*@TcrJ)%ng{cAV<}^zP&P1?Oe_K0m(iP^bCZ9df^ct#i@u zY&5X-Pdad9$6a;#$m-eW!S^5LsPn`7jjaC196z%2`raucJKx6jq51mLI{Mc7`q^>y zxq9@!I$f9Q&%5HhxLJ5taNZT1cLnEN!FgA3-W8m81?OGC`CbOz_=x3y+;2Qqz8&NF zc5uEOoNou`+rbxKIr?^Rz8#!z2j|AF<^qj%qRc;Dn$&)sv^>GkIe&)s!;UAp(ncb#6Ze*A{{{Kf0oTh7>Z zdVPERXLg-lKR5mEuG8!1LvOv?^!n+2Q?H)~J>{nH!w=kTn!o#7cbnE(?*qF{>wn}6 zyG_S^?bW+Y^;~}4Zd09q`0L%K`k(VV#m`p|s+X&rrQef{jX`dmHwU!AT?^}Al)H+8)pwfV^A-(&H5Vx3d( zG2VOD|J>>0{pq+{JZfb1{Q3vuepKg~=Z&oX4UZn#dA;n=k)3bj`p|s+X&rrQef{jX z`dmHwU!AT?^}Al3m+>e4@wUS`nt#C8Mz+q6cYDk*ZvD@Gd1S}kZMNMouAVo)VPtiF z>*A5szyEb3JFh$c&SQu9&bM)WXukfmj=r_Nes)}at{(lbPS>mY{eIGU`8nA6`uSKN z{M@WRexBAhKWFQwpTG6l&*l2>=XKY`&+)F8pYM(Px!-)h544Wo6I$Qz4;|O<71iVS zjq3D!NcH>ur1LV~`I=uJtW$riU*8x?aw=aeZjM{PfjiDb(L!id%fl0!d{2DxvLu-E^_{ak3ipBJs;=Sb`O`OVTiE&> zT-b5Bxv+XTyRbUBys-K?zOeJ+{=&|;aeZjM{+5I7)#vKb|LSyIsz3LaW99zBxxaAkFP!@e=l;UEzi{p^ocjys{=&JxaPBXh z`wQp(!nwaN2UORK8>;J-`^%i%UpV&{Horbtr~c&rGAH*J&i#dRf8pF;IQJLM{e^RX z;oM(1_ZQCng>!%5++R5N7ta0Fc)t(l{xY8X3+MjAxxaAkFP!@e=l;UEzi{p^ocjys z{=&JxaPBXx&;35H|NTCn`^%i%UpV&{HoxDKt<&$%xxdWG{e^RX;oM(1_ZQCng>!%5 z++R5N7tZ~KbARF7UpV&{&i#dRQsJCbI42d(NriJ#;ha=BCl$^~g>zEjTv#}N7tTM1 z^N->DV>tg9&Oe6pkKz1dIR6;VKZf&<;rwGb{}|3chVzf%{9`!h7|uC{bB^JhV>ss+ z&N+s2j^UhRIOiD7IfiqNHQw{LoMXoGC*%CdIDazEpN#V-5AzrPWSl=4=TFA@lX3p! z#{G@H`SLz+ZfBfJ8Rw?Pd6jWqWt>;Jai6VfzC0J4R~hG3#(9--US*tDd6>WOD&xG_ zI9E2#m5p;{<6PM|S2oU-jdNw=MS9>=-IhxuFFetFeb$M=$X-Hqp*$2sS5&Uu`39_O6L zIp=ZCd7N_|=bXnm=W)(?oO2%Mna6qNah`dcXCCL7$9d*)o_U;S9_N|IdFFAR`NrG7 zdFGAhn!~x~aIQI=Yp(I0ndh1_o@);0n!~x~aIQI=YYyj{!+G$A`Ct0|<$c%Ne7J{m z3>wcdh;t0$9D_K=AkHy}a}44fgE+?^&M}B{4B{MvIL9E)D~R(7;=F=5uOQAVi1P~K zyn;BdAkHg@^9tg;f{k~5^9mX-s{)r*fy=7EWmPoZ>t0zE#>=X}WmVv^DsWj9xU33X zRs}9cW0=3lt-xh};4&<585Xz<3tWZ;F2e$sVS)eVfHA`Ymtld+u)t+l;4&<585X#V z5?n3`E|&zCOMc@A-&!(sly zbBOaC;yi~q&mqopi1QrcJcl^XA&U1+K9O68OIL{%@bBOaC;yi~q&mqpoh;ts| z9FjQyAfyuBk(`#sb6VmX zH{W-8^Y4yxa#|YCX^C@M;+&Q^rzOs5iE~=woR&DJCC)2|^9tg;f;g`r&MS!X3gWzi zIIkeiD~R(7Hr~&Ryn@Da9^yQWIEN(8A&GNH;vABV_j^JPN#i*raSlnGLlWnZ#5p8! z4#{E8!W)U#-s$<%?+JM$jpvQTc_VS&NSrqk=Z(a9BXQnHoHr8Zjl_8)arthzd^cRa z8!q2%n7_z(!{xi-^4)OxZn%6mT)rDF-wl`VhRb)u<-f%g3xZF2f?i()mt?{mJ zxo^hHeZ%Fx;d0+_xo^1KH(c)9Fz4cJrfXW3pYgK%a9Mu1EI(Y9A1=!em*t1c^225M z;j;X2S$?=IKU^jwE|U?L$%xBj#APz#G8u81jJQljTqYwflM$E6h|6Te<7IK;@;7n$o4EWd65e-oF# ziOb)_P;SH;EQ;re~rsG$K{*j z^38|&>pyh)cC+#M*qd(LV)^oeM=syoobt_a`R2HMb6mbTF5euNZ;n?jve$80=eWFh zT<$q8_Z*jdKFojVmdh`>cKrRn+;ijQp5t=Qak=NX+;d#+IWG4cmwS%OwZ~=Is3^7${@boqPhjr{dzZMyu*bH>k^{OjX39bDYjeBo@ zzd!P6d#zgD|3%~a+pk`={LC9ie$8&HmQOom{CvwB{$$ni)xRA1+()fi{>K-L_5bMu zS1s>#*~sgxyK4DItHyJD-OnGqe3zGv{EAB-ynKsuNB-dX4_+VHhn*Y zvG;QQzt?ViPuInG*US7q$7>y~b?0)s&Gw$I`@`0q&tKdRkN(+S(|xkxm-d?OpG(f$ zYr3zVeav3dHGSVjdo3Sy#P~k(k7uiwue<+jSpRO1T)n*gDdTI%iypgr`7s-eyzbLh zFCX}hasKIhuU_7IFVV-{buW7 z&Y{0py?o1Wjr@0a-D~+XSB-qm@?Oi|{`tsH-fget%kDY;+e;4FYx%Ib1c&FbmgpZw|7Q%^R3_v)!vOGmAqdbr1atEb*RXQ$Ou z&wsZ4>gie>Ht$c@C=a~rk_R5=fya5^aUOV_2Oj5v$9dp!9(bI89_NI|`SWppc$^;| z=ZDAn;c=GrJm){o z`Hyq{g&f%Aj`ObLyz4mc`Y`|H=g<0^U`~7E`Sx+XeVlI}=iA5m_Hn*_oNpiJ z+sFC#alU<=Zy)E|$2s^5fq#{tj@)6AoU!cH5EPz0bkR|9JiQv;H+l9=v>q4~+c!_Z+HqH6jCNG=*?Pc4)Y+Cb6&wkl-tSw*uvZ;n=AN#VYwx|8e zfz$5^zdZJ!={4}!eGi&`el0)tpy}t=T{k*t`uX*MTOBn0{CeUK51f8}S+n06uKL`8 z)6cKxe*D1c=hy6`2Ts3x7_W!s_dDSc_daB*=K+@;GSzv~cMh56tn-sYrhogWpB^%; zX}s4K^ZR|qI@R`|iw?P|<}>E=7r)Q!dGsOEIsW0khfL@GqwNlvdXnegwa)X8^ZesH z|Bd(ie4c;f*5RwidH!*pf1KwZ=lREZ{&5)uIOjhuHv#AW$NB$p{(qeRALswa`TueL zf1Ljx=l{p~|8f3*T&4pq#{rk)fXi{fXTH*p7l4#xBR<2?U3&p*!dkMsQFJpVY)KhE=y z^ZesH|Bbg7^86bwg8=9J$K@vA{Qo%rKhFP;^Z(=g|2Y3Y&i{|||Kt4sIR8J+|Bv(k z43|0z-2n%G97T44!BGQT&4pq(*bXM!7;O*>*miloLs{tzo0b&F3%Pqdn?&H_rOo#IG*CVbJQ)Gx>?Wa@3qHuv!2!e;*9HNJ*)r6 z>uws~f1B&4`5%1w_0u}<_~7-^`cL})_0w@TI`i78Z!fsh52u>%_s>6=^|yw%z3B(D z{s!@ir~F{n-zHwL!4GEr&Eh-XxpvmyG9LEPYiIq9L$vdnGU#22VABDF4F;*>43|0z~y(~GCOdY9k|R6TxJI@vjdmefy?Z`Wp>~) zJ8+pDxXcb*W(O{_1DE4~%W=TvIN)*|a5)ac{6&rfF2@0vs!8q@$wyT`3|^z z2VA}bF5dx{?=Z~Scm3(vc$po>%k02qcHlBQaG4#r%nn>;2QIS%m)U{K?7(Gq;4(XK zIS#lS2V9N=F2@0v;2QIS%m)U{K?7-zX;Bp*rIS#lS2V9QBFn^KbfXi{fA>Z5G~P8Wr^9$T9r$&NoDN)02QH@rm(wxKU*vS)auaa53Ao$@Ty8?+y}p&3V7%M} zTy6p`HvyNMfXhu7<}Y#+aG4Ic912`U1}-B5myvAk<}WfbaJd+`Tnt<;1}+x^my3bR#Te!^-ZS3ouq&qbwr_mz*CxK^3tyY{H|Vo}^R?OZH|QD0p~9)8(W|3O<_Hl5d3ethY4zHdC|(y0$;?tkgjpBo-==}mo` zuUS7g{P|a=K0oB@uT1^_=dXWdx-Q1MzUKG5qMQ!bx||MNP6sZh1DDf*%jv-7bl`G2 za5){goDN)02QH@rm(zg{U*w74GCOb?D7gF%Tz&^Gzhjtx*`?F-=khy@m*0WQ@4)4E z;PN|g`5n0Y4qSc*E~^EX&w|Tm!R52y@>v@1^|^c&y{CEVz6YTs{jfp9PoA zfy?H=Wpm)NIdIt=xNHtwHU}=71DDN#%jRgjd#`K`3nayoDsD7efHTxJI@v!n4| zbIR;6US~)J8(HHxEvN-4ht@a1((Bu%VELgu;6l7a5*fv92Q&- z3oeHRziaPzPOmfNuo%DOsQ1qL-eTDt#>?iwWpm)NIdIt=xNHtwHU}=71DDN#%jUpk zbKnyf*&MhG5nN6OE&~OZ*@4UKz-4yeGCOdY9k|R6TxJI@vjdme(RjaKmDypud=^|L z3oerdm&t<5WWi;!;4)conJlP@m%ze$lj&rl)-0V0vJI>9HbF<^z>^L_&&drWYZg%W^Iook=cAT3X=Vr&b*>P@mtpC-So85SBc5IxRz4_ei zI5#`a&5m=k9HbF<^z>^L_&&drW9HbF<^z><_u! z`!C#Jqj`?k%TJkI{e|-;Hh%AK+-`Q!rSF{KZ+`!Fv$x;#+v+MR4dEXP(nSJBM<8eEd z8afv4Sh!>1j)glG?pU~E4f7Yr>b#Cw=gq_UIxaST=l8BRJM{HR z&wlofvs;}$@*}ss<7}(fjJ)Ot=UK%s8F`=k$wVCalH=Ezy<#!`o;B8)y?8Ny>vcrKlpO-)9zOxT}?j1wTvGH$w=U&78hX3RR_nv+9 zCFA|D)%EwDJ!|#I>%Z_mvlDh4`Mj&{GrP@3Bme5L_nm#>#_=9|@;mQ4`^H5hA9&?` zXBWR_ zGe`cxo7bHE>9a@v%H3`?JNa27Z+PmhW_N$e$h&R0)@-w-kso)$TC?Y^Kk_$!z1Hl4 zAHHMQv-|$(+OvmTIP&o)uRXiZt42QTpVyw<>MLu#|`|$pR7Im^0(hK@EtE+d-l-3 z7KW!Q>cQ26s|Qz){v30w zA1rPC>=TE+#f_hS%=nuBv%6fobmI9V-*?CFFFpQyBk%dH?=7v`=q*D(KfTfSmJZx! zw$7PPTx0g(t6o2>x!r|p%zks>$ZxvanzK8+VdQ)6x904w z&lvd!XRbNhf5VaYymZaku~!~5{M&tgxaMq)Q$~L7kJp?Xy35GBUcTn+v<*i7@CVkM z-ScZl5AzRu*_yMXPZ{f}2Io=@xEgRZ;A+6tfU5yl1Fi;K4Y(Tg;Z6_u?$T{uc>K_x z*!Y8=a>df$-C}%wIOlm+EWPsyBk%E{E0!K{!pOhb;u}k^`pU>3|JpZ}_E~5Ao#ah_ zb>-6Cw;TBZZ~x}7zBOlmdDYTSj~&N9{?V(KzIp1%8-DX&mmc-rkza9(Z%^aDx8Zk& z`D(5nTs^pYaP{Eo!PSGS2UpK9e^C#v9$Y=Rdg{;CYrS&lo7%AP4Zd~F(k8z;Y~cIc z>6)cuKQrFPsA{>ATodui?GjeOxZ{&nfX)g!<5!mF1yUW{-3 zuB(>rdDuAq%(u<^dGg4=Jmboxn}2pOKJWiuFOK`k`E@ydtHXyHwwqtCFCIMd>GSKj z@5c`xYOYS_Rh_sxadqPA#MOzb6IUm$PF$VC_@Yi+owz!2b*}8E@oF~SUN#Rqr41-#qsErPCI_&tLH5pDz9C z&&Khcp767!^LH5e%Uk?>=?(WCd9B~MVd;pUkH4S4`ivWv{_*1@e{}O3m##WuN9eJAzZ(O?a<|Ci~@f(+(a^d*9-%C%tap{#W9r=W9Z(Lg1YUJ%cbHmaje>wiX z_uc#4u(a7lBVW4P&zBB6ems}m7xg>e>c`cOs~=ZCu6|toxcYJRBw?!ABadfWSV_et;H-9Np5cVG4X-Tl`4_l~8u zj)glG?pU~E;f{qn7VcQX{Kc_Wo|o~C+xUO9uUB5*_&@90%6%7`-#zcR@yY*u>V-Rh z@$Z-3eC*k?GrlnL51w}R>?eOa^366pd-mPaM?T>DXU%pvYUIl=JZrYj?jyhFgtKOc zJb2_aUwqc=C%^uSVa=QEa@OqkK0WewPdID#jMtC+&K6*{yRN(WariR>@#Oi^B;J#bEb7Zxayo~ z{Ui^eE&Y8~ZvM-%8)6e7o>C&m6xPIdLiR&k> zpSXVF`ibi&uAjJmHm=U*s~^`-Tt9LB#Pt)`Ph3B7{lxVX*H2tOas9;g6W32%KXLuU z`sw~@+QNbH8!=@NZqm_1`zL>wD}g zMs}Z^vfaq;lN)X`visyoUw+TnE zpSXVF`ib?^{nNPns`>6WY#sL@w!ZrlJFfc{tH=F})!B9F{x|NtR_=xFTlI85tF!yO z?0U_QF|g}6KgPhW@BA18 zyHDoF7}$L>KevJ1C-Y-W%b#=z>I zA7kL*{$Gqc-{$K>>*!DG>s!aw&+5_V>eT=0cU?L!_lbUX9rY8}Ph3B-`t=jnPh3B7 z{lxVX*H2tO8&_xZ)sO2ZuAjJm;`)i}C$68ke&YIx>nEpSXTv{dE5{ z?!Ici`wd&ieTc1JKONV7Yg|30N3*RW}w`D@s;{`|Fb zI_~_nbE;?l+BwxZf9;&=pTBla=QV%5oUUX2bgku2Nb zyZULoe&YIx>nEpSXVF`ibi&uAjJm;`)i}C)UsQo$>aa`RzOFwC}9n zzH{96oqF1L>TKVszkTPt+IP5p*KytR9T#_8+;MTo#T^%ST-oUzMH@In(Cjw$C~cX`FpSFzBS&yGrxUjo%Wse z+joxJzEe;8PMz&9^|$YwSL5^F*{AvQ-`S^i=D)K~>(AdSOvjzSSD5OVzgL**oWEC? z>Yu+?n9ghd{$RR}_0#=RKXLuU^%K`mTt9LB#Pt)`Ph3A6Z{O8V?Sy)V6O+IJhh^KH|`_B69JI8I` zsi%FX&i0r3+jq{Z@zsxc`!xTlhrE4S=Nsp~eOmt|SG;{X?pbS`G}ZIC`=2z``IJYV zG}ZqHPdsTluit&jNz-+#pYEUfiR&k>pSXVF`ibi&uAjJm;`-Tm`>uW(ub;Sn;`)i} zC$68ke&YIx>nEpSXVF`ib?keP_IVXMX$6I_*2_x9=RceW#xGojTih z>TlmUul5~o-*sGjq~qd_i#smvxVYouj*B}kzUMK=Py6nrPdR?tcdxzM@zcJ$*)_*a z`);2Lj+^$~s^gBE_T6zWI&Ru`uig2$ss1nSc-(YsUYCKlKyWPh3B7{lxVX*H2tOas9;gv+?#_{WM-bas9;g z6W32%KXLuU^%K`mTt9LB#Pt)`Ph3B7{lxVX>u3AUc>B)$_MLUwch+y;Id1z-J?%Sn zw(r#6zH?sfJKVnOxb{fL#T^%ST-I|xrT+Gv^J;vPZC^jlU;pK=pVm3;oYzn5Km797Pse@HEsve*x&21R zPIa#Th-0VvzxeoLr}O&slaHOQWBqjh)K6SLas9;g6W32%KXLuU^%K|6#@l!G(|G;F z^%K`mTt9LB#Pt)`Ph3B7{lxVX*H2tOas9;g6W33ypY1#2?K|_^ch+g&S-*Yfxa~Xj zwC~i}zEgku&Uv-(aQm*~+9MqocU;_YamU3S7k6CTaq+iacjUD1mjC3)Y2Q8Zu18M$ z?xOF!dfIoJefZVWzWezbUp?)+r@!#k)4qG+POqNof6ET9p6<_6w|(_=-x_bIj4r_T15`rCKTtMS)gbmTPukY64-t+VFlM@{R$bC;v0<9_Lgqo#Te zc=u6Loriq%sHy&kUVPMaUK@Y$sOdV^Pxnv##Pt)`Ph3B7{lxVX*H2tOas6z(eOEt? z*H2tOas9;g6W32%KXLuU^%K`mTt9LB#Pt)`Ph3B7{lxm&zBAswGrxUjo%Wse+joxJ zzEe;8PMz&L^|$YwSNjgP?>eqM(s6Oe#T^%ST-28)4uzQFCI4SyZ62Q zuxa0IwD)1tzI)@=hfVu#=i47P?Yj$pbm+A2-goJtQ~kgA?4i^Bd5cdSI^DO%+jr)- z@2u0lvwr)|aocz5Y2T@{{iXi)o%3q^M~^;yn*WXY=eSyD-?I;&*1!4J51)>^)h%8* z)$`^1zH+MbirFit`rrDvS5D`3^pjpWUB~+A{;8k1e&YIx>nEpN+Tg z>ZkGgiR&k>pSXVF`ibi&uAjJm;`)i}C$68ke&YIx>nES^Dpvwf%j_MP);-{JOM$F)Z~F7CLvrGti>H0J z@s=;1_T9Rd95C&>@4V=MY2O`uuLGuiH@kBGY2R&f-u_elA3kpX>HfUrHTzHZt?~Aq z`RzOFwC}9nzH{96i+b93>TG|hzkTPt8h_7`FPY{a@za+~>zwq=1E=*r^PvN$<34Py zgQj}+-|?WS&LduS&{Y3V-+It=URRuY&~zQ^r~9XV;`)i}C$68ke&YIx>nEnEpSXVF`ibi&uAjJm;`)i}C$68keq#M>-x+V;ncu#%PW#UK z?K{V9->Ij4r_T1B`rCKTt9^&tcOBOr>A1M#;*N_uF7CLv<6_6X#}CHOQ~k-`o;Q4+ z)A;-|Wy830ZyXzc$Vq1oe}8<>H(xN!H-5J}?lb*cY|gO$e9m@H{HuY7>osTd@ya=; zKYX0O?a?osJ?XpS{I@*mMYH?8XXNiZaR1qdUNZ6x8yqlu$W9}#zut@gO+Ch~Z`^!r zzICv5tdFhlxY%+3eVyuG{_1OoadTGIZ~S%de)sTipS=6KW>3BM_*sajeDUPj6~8`X z7{AxI-ab3|{^R*LnPt&gq0 z>1|IQ>N))2GyhG^E7v#2d~;Uvx);847=QGS&YZpQu#tCr(OI+GKV#$@es$LDwoe%O z+Si>u`-h!I{`LCj%zl2z$lpC}{@H^MjePX|&z&8<)_AO2o_y}?1N)8qgaq zm-EHWS0AuG=nvK(pS?WmVGp0(@%`@__|4zmX7Z~l1|=W^HA zK4NyK>&EkX*RvimyWNY<9BN+4)uYbp!PSGS2UicS9$Y=RdT{mNmGx|N=Z$9fJMDc# zolk!5Mzd2-8Tor3+i3R76Gy(_4)>ou?2YdmYF^3xTWj`j@&A*5+xhBG?BA|j)BP|X z8){q0&GBzvy1`bnA6)V7Va|T*Y&E;_ypfOj<(9L(j~My&|Geewtz{nU7SnP6`Vm`9_5979x0veu;_qxR)&J=m9x|Mlo~-2N z81LWW*2EnPR|Bp#T+O(1!JQ-S+;Kg@^$OQRTyJqb$6X8DHNsuH#;^W^_YC)#`7hpP zWb17E?2)a1yVs8FxaXWPvU=|Osgc!r+NC3_|IJsA?7ZIoospeyBq+h?bd|9*{|#{cT<`%m-N zddB^ybzXei`%mjX>>oCoj=TMd8%_1>@S=^TI``RmqpAK~pS;mSuIIRGfxAYyYuEVNZ#aF}cjlk;k&&(Q+;5F+ z{Vi|(-eHd8etFZ8)$_RRMpozNcOF^&7p@-Jd41wJBRk*5^`ZIt(>nUr`uf>%^|^ZV zzdBu)>hF5FKUZ>djQ4MGYvPWDs{vOVu4df1;LZ_u?zo=ddWGvDuD7_J>b8pv?BfoH`xr=A#k@sIUcOgA!`-^(s`jU;OI?vyASuIIRGfxAYyYuETAuR43!Q|4cC+j9oC&M8}uZ2f(A z8`*K!K5S(59R9YE)%iPTkF5S5e`sXq_45lycD{}4L-X~gb@Z+E^|RyZbM@$db-FIq z-}Q2TuH@zz@89Cq#2pJ)1Fkk)&A4;Hog?ntaXrEH3fDtiZ*e`xT?_2mIY<2Idpvx0 z?}vAm3KYrwcKe_endE1P<^K-VIy?nEg_q)y3vjaCC`On|C)il1xPFqd$KXHq#rgb*` z@Rrm1*B-RxbljW&(foJaMLoZJw=JhSH@wA`Q~h`R^}~kqa!;=0<{0na;?~3+3s(cK zHeAiPbHSY>?%Z)b!SxE)LtJlhJ;z-O+%>{oyTUS zyI$_kmE0WT{af6cxMSgJz}1GU8FwzYbHtrHt|z!&;d+ScEw1OdYk^%m=ZIInuV2aD z5B98VC9ix>y^?z-V9k~6Su7>?C@O!vu3ZjN!>apUGUUOoSvpZ~0UX62cibNOF+ zCf2jQmCxM%cRrJJy;k=5-*eZ_I9~a@*E3<`J*&q(tH(X7$33gZJ*&q(tH(X7$33gZ zJ*#j0|4)DW_-#Kk?|St&O+D;ynz+Ad;{K+I`=jKX9M@zO?_A)%bAkKL1@1c+xbIxx zzH@>5&IRr}7r5_SG~WK|I~T_L&IRr}7r5_S;J$N#`_2XKI~Ta`T;RTQf&0z{?mHK_ z?_A)%bAkKL1@1c+xbIxxzH`xdKfit(-+k!2X^z!*({SHS!+kdm_uVwychhj+O~ZXR z4fowN+;`I&?|Sv!G~<0Y4fowN+;`J(-%Z1PHx2jQG~9R7aNkYCeK!sF-89^H)3EPw z^;sR??W)ecn`TbmO~ZXRt?{ncZ{s^+eTUbv`VKGdJG{8>@Z!G1i~9~Q?mN7=@9^Tj z!;AY4Z{zi$@9-M$JG{8>@Z!G1i~9~Q?mN7=@9^Tj!;AY4FYY_MxbN`dzQc?A4lnLI zytwc1;=aR+`wnm8U9aE9cWHfJzV~0b4jgyh%jvUc^LuUj?AiQtVbf>N=D%A_pFNxZ z44*!GHve4M^ckM{=f9@UXw5$tHhp%>c-PDP?q}=t*)!|+`RwnZKqFtZ(zz`hoRx{xe`;eV+ep7})ii|I8TJ^_u@I8QArj z|BRW&=RbR<`SYJi16ybQvua@L&wqvu?6~uvZ3C-k{xff2*K7VWa$wi%zsg0{`MO^9 z!S$*?u2+3?z3QjyRi9n2`tN#mU0kpKZlA4M`MIy(*5~d#{~VqH{(txk;eYno$ezu5 zcGR)Frs1CT;hy#3p7r6L_2HiN;hy#3p7r6L_2HiNH9o(OhvWXw=W@sX_xV`;>GQF8 z<>zvH)@QtDeYj_RxMzL1XMMP5eYj_RxMzL1XMMP5eT{d$de&#WXMMP5eYj_RxMzL1 zXMMP5eYj_RxMzL1XMMP5eYj_RxMzL1XMMP5eYj_RxMzKh``w`VemB59>%)DI0QWrt z-1i7@-y^_%j{x_q5BIDO_pA^1tPl6B5BIDO_pA^1tPl6B5BIFE@vc|T`i%Fi5BIDO z_pA^1tPl6B5BIDO_pA^1tPl6B5BIDO_pA^1tPl6B5C3=go>$NM)YG#*+_OI1vp(Fj zKHRfD+_OI1vp(FjKHRgu#=BlU>oeZ7KHRfD+_OI1vp(FjKHRfD+_OI1vp(FjKHRfD z+_OI1vp(FjKK$R|`>;LhQ%}$OaL@X1&-!rB`tbjF1IC}fJ?qnxp7r6rzmNO=KJNSb zxbN@dzQ2$A{yy&e`?zO)xMzL1XMMP5eYj_RxMzL1XMMP5eYj_RxMzKhx4(MUXS`>9 zxMzL1XMMP5eYj_RxMzL1XMMP5eYj_RxMzL1XMMP5eYj_RxMzL1XMMP5eU10?t7m=2 z^PJ#3Cpgau&U1qEoZvhsxMzL1XMMP5eYj_RxMzL1XMMP5eYj_RxMzL1XMK%#y?WMX zyk~v5XMMP5eYj_RxMzL1XMMP5eYj_RxMzL1XMMP5eR%#pW_T8X=kH^NXA!t(eYj_R zxMzKhcfESnXWTlTMPTcD7J(htvk0sn&myoo`@LQL{XXBbK6853hkMqCd)9}0)`xr6 zhkMqCd)9}0)`xr6*Lc^fXMM(d)`xr6hkMqCd)9}0)`xr6hkMqCd)9}0)`xr6hkMqC zd)9}0)`xr6hkMqCd)C)@*Q;lJ#;w!!vVPagal2mX>3XTN>!tp#SI_#a>AigO=e?ZP z@!r4nJrn4-o)z@_s%Hq*=~=}5{qu02cos1~#=t%68_sL-tPh(%KgKY}I`d-;Z2kFv z13T{g{|&63`M()hou2ho|NIyO_pHyj_wvo3*Ep@?y?^U_CeU#`E2tjN5W25CTbTD~ zSl=^;&Z}pAj%B<)m|uUaQ{Sv#KOML0rJnk)&aRjGJ?pdna9;o8e;%HZdd8?H`svvt z)@RQovHp8jiCq`ZFtO|9SzqIx^)=tKK5QM&`mpsq>%*>>XMNc9@~jWLUY_+~*UPg$ z?0R{ogzYcSny~wJ{+c_m`+5GFJFxrQGb?l4|DI)G`@%D>;or{pi)UZBXMMP5eT{q8 z*L=_Vuys7^!`An#4?C`BeONu7^Ir#7Ek zGw%8PN*=!dJ0CYEUilfwKF8?a{zu<)G`{jPkSo7u_kZd;hH5BZ43~X|%Ra+ppW(94 zaM@?L?6b!ISF+gr+m)GRWtkZ-6A+gPh|2`TWdh=9E!|%c#P? z_%F!Pa$Gqw<$vM-F1cxHTbW(8GT*AaIdjUJ!{yE4^5$@PbGW=YT;3cmZw{9?hgas! z{rjx0{}UNQYFL?Vv@*x1%qDZnY{F$W;WC?WnN7INCR}C{F0%=j*@Vk%!eut$GMjLj zO}NY^yfU+?{2=2iGlt6fGG5LXF6RrE^M(H}_TD?X%4%C5Rs^MqfPi!q6cGqTdV7$X zMp01&X@P_iq=q7$h_sLZ0g~(x(nv2m6{HH%6%i>)Q3OE*k9aI}5Rl(`-j`?JeeU?q z7~lEsckku=2LH{m#(L*^<}=^5)_&Jsb57OyqO3Y!lvU@;>i;j)9b>g#s^ifu>*{v zBvMwaB4x!=QGOH$_wdKTxz|Hi4R`uZHQXtyhC5}|aHp&q?vz!-ow91UQ&tUk%BtZ` zSvA}#tA;ye)o{1^Z?S95Q+BVn?p~8UzVmZ9f7Gt4`}yaUP%_h&J9V#wHcM=|#O8|d zd*7Bvzg!XJC))Cn$O@SIpgp5_1x$U=zwP{I;r~ESNa<(M_ba=9+tl(X{#2Cpy*c)c z^7y&4E$2O39xpGj<+Hz*!;S;C%v$iQ|4#hwb>YvOKB_gj%{;4Glc7eZYE6zYW2x5U zF@r(1CKC-d)tandq5@QFa!gbOu+}8Ua<6NzZ)(PZ>3dnSV(#=^{Ga3d^j*w$_xwNl zE@r#Fiz(~7n6h&3P*(08%F4Y%S-E#8EB6j%<=&yJ+&h%rbMNRJfbBXfpzNMMN8iqD z*S9leeLGXuw=-pZJ5$!TGi7}{tDWD@>i_??ZaDkv+nKVyohj?vnX)V;KzMU!S+nKVyohj?vnX)Tm!UQ@f)u)dwyu5V|``gW$QZ)eK- zcBZUvXUh6^w)+1IHS5`5-_Dd3n@m|T%aj$%Oj$9`lok6-SuxR+6)R0yG1Qb5TTNLp z*OV2DO<6J8loh*8Sux#|73)n|G2oOH8%|k!C1vfQYF9k(zk58gayZZ~<#wQ~oDYb0C@U8bW#tH>tlUAAl~ahaat%?|w;pAE1FBv5Ve}2cc72;r);9}fealeRHx6Ze z`%u<55oLWVQPwvUWqn&w);AYreTz~4SM%E_Cm5eqt}x2VAx2rb#V9N17-i)mqpTcd zl$E=TvT~YHR<1M3%7I2%xzQ*qXBuVYQlqRKYm}9Hjk0pGQPx=sWu398U3s+hjn8&{ z`%~7L0A-yOP}Ug&Wt}Zh)|mrkokdXA83kpXT~OAU24$UfQ2tl*fa$!B&+5F6vd-%$ z>%5M#&g&@aypFQY>nQ8Ij%5M#&g&@aypFQY>nQ8Ij%5M#&g&@aypFQY>nQ8Iji^)pjxuYe53Uwx{T^d2_2fae%o^)m zQ*2r1b?i@>=dqOkJL|A(ES{N5=9#(1P3UdQ#Qa*6Ez_0-CvBPa-$z%7wEENbT3)tH zPM!&}WpZ^R+?L7V`D9xrw_UPqnVhSgzEFRinG=uB%qi>4oU+c$DeKIfvd+vY>&%?8 z&de$6%$%~$%qi>4oU+c$DeKIfvi=jHtp7wP>pv07`cH(i{u80R{oKV4+edz2@fN!M zLWc(9Y`Ja9j~!}%V9SHn7!DI{`EK?P9g2MZpxto3{+=!GF}{dwGtbiFWqkCN$xlxG zndZG3v&)wCP0DtClTy|&$_&&KxM~%z?7b94PC|fwImVto{$q9BMR9L~^^q zaF`rZ!zw4@;P%0|YVt}&-bg@9>me9hBM14PCmXuG!6 zfBOkPT(6aD;cxQvP()QR_a6*??}kHhuA=E<@YiWR6qhUHTKMO`I22!2%C+#Hz2}F( zYPlBvK0E!8R6Ezgzh;6TIycO<@Rus%ha#K5BEadk_8AJAC050c;St51*o+l8bykE;iHNL*m5(` zg>!oQwMa7f0}cKGbJt?RYEJ|kyH;&qi{}q{qKdIM@Rq5oTGUa#24LX+Vbv8zStU{Z($Q}#FqAi7tR>W#5VawFI+da5ZjCIdSO|q0t;K` zWG@^qQea^_cFzkXZsl9pMve4F&@cHGw%Vt?5qLV^!gh3k4|;x?Z()1-tPes=?mlAc zFv1rhx%vNq&3#_G&k^DmW_Q24b4yvau#aT-Iq3dAyT2#wqq!M)C=?&QJqhn`%tDjG zP;B`+2uJs2;nT!WRO}Ii8Yi-_ZcQlCKbeT{e#%0%>w90qpIMvp_W82r~bTyK|++9l#J%X2(BG|NWu_HlS7X*?#@%SP;oI3$&tfN!g1 zW20GD2YxUCho8>Il=wJ2{n$i&^j8*IXT`yD{zP2m4;?{4!jl}hKtS8Fl(d(qt=AsB_nrv-hqUbVL*#CB%X>w z-8o@+zHJ&J*O>Z_gTs*4DGf!2nc9%e!?4=dU}zGBmPNvl`%W767mq@f&qA?exGk@F z+Ptre(=Gh{vOdI2zw2}u2E3DQ;lFe?3^9GvE&MN>48yv9=@$Ns-C>9vly2d# zk`jh$!_zJNLuZ&dGu~h@_&0fmq0Y?of57iPm)++JZFJe?{?54hi2jnje6RE_xz9)U zcb>A|G4_%C=b)vSa3&DLPiCXA>QbEfDi9gpWTW0UVVJl+5F<}#qm1#}t>8c`IiHQk zhlOE(+d%yMOEzXU4#P+1N5S_-Ha;(E)`Z!kFvh$~CC`VVOX*R#^Ng9-2SPDp#YiO9 zbRuS3C=Qn$iJKly{IDeyF-u1vwu2MJc83C`Mxb6#Ck`G9MfIh_@#;V)wp|Iuv`WL# zZ?rAXT00yEm*#+&Ck2kiw|ATt<{t)+MvZ$;3-gqYqw(EiITq%-rAFialQ|aVgL?xp z_?a9F^QLiu*ij|N!u(i?K%9Fi$HMIC7=;PVaxBbqs*gg&&N&w5uh)#km^X4P%<+{+ zqTJ9N3v=hF5r~_RV_|;2@(85QHSI6Ox-kFJB^E;+!*TmvCrC198^)asTERmwzdXH|iIk95X~|E6oMP(SU7KY z3q)+q91CYyRv_Zb=U6yjxEqM`=JzLYqV;HOdOXL%S!U2^yls4!lDHCkB6`8k%%{Lm)z&$mz9^h zeos~!xZL%7I5BRy>v!_zQ_EeypZA&iF8W>F(=*)ld;8wRaM$nfZL7jvzt3~B!(G4I zJvN8Ce$QXn8t(d?ziVB%>-Ybi#BkSlL8jm+=NznkBg#Jr}q z7d*-rfS4=v^+L(g1t8`wv0li2q5#C)@2VHPZ|8%U%l7w1yZ zMxjoGL@!2@=K}EAVki2W8kV~&2H={J8wtVgGFibmR>hBoL9ZUNo z^}8Gk^PuVeNIsNfVLp7)AD#B(SeVP#3&6oGITq$p!vnB*U5h?g4zxjSi4#uohU)%^XIdfJ7<3x2|boww4N5g^<8194ntMbq`A{c%} zeNdQU@=>P;YJd9x+oyZN(|l(&YckI@UnuK6Bu?*w9(ZPvi9Inm zgPZigdr>B?#Na%Y?u!j+`4-Nx)qF8|qq&oBaQZLz!ONeS_sZb>`6(atKACUfd@{rv z6Mo9KaL%jbjmp>aEu4GTneQp{ok*NJ{0(OFok*Nt8~o$Vw-s^jD(Z!g&0KKD=|0EZ z=Z-sm_jkjcb9cMgNAHaL+;o5E-QOkmIU9dI8vRy8 zY*vb;v$r!Eix;L?Is?W=BP24#()m@jX!HG(V(C1&*@1U=q%htAK@%DxvcWpWJK(t) z4Kcp{I>tL-OH@M?dwCt>9WZNeLri>O9pfEvrKktaR$0e*2Q=#Afv~dc81G=_mIt;K zGtcf!My2wN@Y(G`#yjBptVSsLYa!!P;PFc%T>Rc{AKt$)b{;LX`gh&a7*FggwDc^g z*92v@6k7Tle%J&Z^9rqTM;&Q`Us4M#JZH)_#k=w5S%WjNV^i#lF0}A>8Q2s9BMU9N zej45sEh7pU-vPBVHd6f=GbufcrIdcgSZZ9xUJ4ImGKG^doWjo-PT9qF*~|XofqKLb z^@}%-D?W)wJQJt*Cw}?G-CvZa-f4)Ez1LgzN~RyH74yK4J=a_OY=6N6Gkn%tyam7R zfs0+&TYTPF?t!;Ethac6^^6A|Z@%8*|Et!G@aik(S>wm5agETS#(K+-x1VZ^xn6Q}s6ALSSN?z>7RKYwO{_1*?Q-v(Y8 z1(v_+bZCP!DFv3lF1*(UJ_!YuzXoKt!DdH+QdJ-+K=>$&!2d;HYO)*tyw2UPa3 z$360X2kfb19<*2O+5MfmA2*~NC*%l_hldc+U)i#LudK8Z&>6Q}qme)+}SUzE?TZG-b) z*z1gB&b#@>N81kA>(a}gwLzcH?DgvB8*T8(E_)pt(y}cYZME08HS+pSB zluEbP!wQ5#Pik8funqoa-U>4`vvw)Xm&zZA%7Y1{R-ITD%Q!d^esPJYy% zyh#uFlz#H8aml~%&@aMCe+fVRD7)A$d)Z$+P>=Ybe(}a}#V7HIXW|t9^rQU3+!@;M zn4>}KDswkzy=6`Zt;5Xqp!JzKAhd2XH-y%6=8Vuf&s-8(|CwV#`vTjwU$DRS5$e(Y zLjBrzIIi|1;?X`uoZ7#LU;7&E(tgLBAZib-`5*n66GVEL6GZx%6GY=iOp0*f2^|pO z!ueH?2p9e{p62`X!9LD**~|XofqKLb^@}%-D?W)wJQJt*Cw}?G-CvZo$GOYoLF+2{ z(RxeXv<{O`to)n=Q(>es%*akU>2kM=3z z)c!^M+Sh28_B-;RcJibCbc4@z(y;@hvgVtN}qji|PX?-T2TDQrw)^qZ&b)J6F`cHppUtqiT z3-;GOLOt4Fs9*aI$JKsBJldy-Q~MY3YhR;X+V5zu+R20ZlOO3JZ_-abH7>KAVuS9}tWcqUHqPyF(WyT2%Fk8_vFgVt5@qxF`&X&ok? zTA#_Y)@|~y^_+guI!}LT{ih$bFR)$v1^a6sp&soo)USPq<7z)59_>@asr`%iwXe}G z?RVrs?c_)O$(!_$Pw6Mm8khVF5B(yX^q26{kFtyHvX}kE1NDd>>KAVuS9}tWcqUHq zPyF%=bCzkpW6m{crG9h-+V9 zyY@Tw*M3Jm+V7}e`wqv|endRlr-)Pg9r0^lqg~qXn4?YY%-yE`%;_dQ%=ISy%mJry znHx@cm@`f|nPX1)nPX1-9ouCu`-=za5kJ%~-Z-xKBp&fhoZ_GO)PEqT*AOg^tA*FHi$+Fz(&`wqv|endRl zr-)Pg7x8Ofqg~qX$b;I+kNT50=^>xePo6a{`4=AgML6j%;in&E7u#ho`-=za5kJ%~ z-Z-xKBp&fhoZ_GOW$-mZl`bFzM{iS_@ z?bP-`w{VIpCV4}U&OC{jdp3jqrGY;59&{Tq=&poKl#+S8$-mZf`bFzJ{iXGve$>9ecI_AJuYH7iw7*cl_8pF^{fKz9PZ6i~FXGp} zM!U4%kq5PtAN411(nCI_pFC?^@-IB}i*V9k!cRZSF1E{F_7@M-BYvn~ym4IdNj&12 zIK@Bl%P-6$to@ETWVNm`x2)D%=A6|!yno9y*ZSP5)O6RnJ-Nqp*LuEi)^yi8e`ED@ z*ZO}pdAe&~V7vAU_SZf_J=$NWU;7Tn)qX@g+NX$9`xo(RU!z^x@0hb#?aW!M{>)h{ zJ1YrkNB?IYBq z{e}9q?{Hl0N5rFjia51@5x@2|+NJ%DJgA-gs6Tm=9`Y&uXfe)>^% zv0e7Ezj&Y?@k9OMjpK?>;t|ipDgKFHexY63?`W^qRq~+qmi%ZPCU07w$*0zB@~rio z{A-=3U$p+yU)mSguKj}jwU1Db_802czQb{~9}$oCDdN=rMf}>=XqWao+N*Z*p#J1X zddQpflTVFHo`r|}3n%>|{PdUXV!P~RfAK&);)nXh8^;xP=GQ~VRZ{NnB}%G&ST zW%8hPmHcSEC2v}X$*0z5@~m~6{A)d@U$oBCUt0g^N9_x2*M7nN+DE8I`wR7J-{H90 zkBCS66me?*B7W^_v`hOPc~Cp~QGfC#J>*mR$+N~K|H4DR2q*m|{Pd&jV!P~RfAK&) z;)nXh8^;xP=GQ~VRZ{9@{9B7OI(m^Zo*f0+NpdmMZf0|E>2{U_$X@Sk7B<>7@G zZSGhXRBndBeua3<+?js4Uo#x+SBO?V=Dtf>GfeAUh~uMkQ1tQU$m(jIotFdO;mz?; z>q0nIPU^(VBL9jI#xD%Gv#=Ki3k!7q#_#GP5QAyj5W7A9}nc z8va&bjT`r3E1dYTz{2xvKr3`VU0~rnwz3u0ohY#IPs?is@2?9$yQ*()h1y@4|1X|% zLhS`-v!VWVbIje%2YSNiWJCJ<_sxdJ-O?f(!c$Nq8^U?JOg4nSXvu7sU2K=V>@Oau zNBmH~c;mR@lX%24af*N9mtWldMLD}yGu&Ld&aziB{n*?1=y2FNi=Qi#n_)!AI*YgU z$<6T9hwCgp>z{9i&a>88JdbGF9KQywv;0^*tT}3pGS3=6_WGka>JMCJ`O#xQ3ykT# z&hq2%{Vm|x*=~<-)e^N^*!^cEwM0NYThHz%TVZ^4TYtdNR#;ok9yihWs7G-dPo>{m zVe4Zy&Tne8M!h@sdpNUgYiz$+Xxa6A*Vb^{F#lf|9@I{L)StXb5BZdS@~m;mzwpp6 z!byJ#Km91X*e-k7Up!Ec_@RFB#&N|b@rY;Q6#v98zbrkJj&fx^aqcgZ$FFz>KC0r0 zt@rX!r(*{Cwe-Xrf94@CC<9f8dt%$QJQD+vf$$VhG&J`pX6?_w7gs!S@_ZhuUdq6@ zp60&yH|E(QnOI-og$f7raH?!3R++o;eRt&HaK%gt8-?xjKc*mR$+N~K|H4DR2q*m|{Pd&jV!P~RfAK&);)nXh8^;xP=GQ~VRZ{L=sV zT;!Jb!Cy&vc)Y)<3sv0*C)VcSkL4zwr?n5pni!dxyG@MENFRI~oriK)a^aEg1Md|k zXKzXfs9*A|)kPHpp0>UCe#oo$|dGY@a9_eE1PFEWPap-HVC2nxtU+=x7kTG|7> zOb%7HC*J9SSIqrP_MbbVC*JE|>)HExPfTrU>mT`2FJ#oU$4#Ep3w>(Xc&e=Hg&cE=t_GjU1uSM#hM_{rQuqaVjq?up$q?Dmv}JrQs2ud@G# zmwV!@x$jCn``_+`U*59yzn9+&HO&23j+<_L@!4xOo*L+lR&8vY-;e2y6qDbT_~(W6 zM%yN~U3FLW#ig+R2allQ-!hpVCjBH7@xV9{NQ%=`Z1@A7vNYWiR`S2kH?& z)GyvRuJ|M#@l2fJpZMjMJ{wbTB54SAmCeDO-%~KlIRvrhUiziFsi?Jo2wp9ngDLN( z;@r(4h=0<&J0Yofrf+p;D^oEoj7+S70u83;g?G$9`NT>%KiVbO`d579k1-KW zYutn8?r3FmFO+z?bP2$s56!a%XR#o2cXYPX!k=O8YA%`K1nue(9RUC7PB`bJK<(Q+ zQ(XO5WZZbi>;P6TkUv zeN#uz_;J84Kg=`njP#?U>`*kSl56>~^?O6%SH?VR{5a>(P`p=Ybe(}a}#V7HIXW|t9^rQUpyoq_6oH`8OuXp0p*RoM1 zZx}YMb7I5$+4%UtF!ahd?|*hS=KMJfTeF-vX<{d?wed&&WG9|6F)d9N`{Vd(Cvs{# zapVVoJhj|B+t!K7o&hLt=EXQ~CvFr3;H{}n`1f+6@$uHS{+bEl2|1SO!g*w0rVIaf zJ2PE&v0e7Ezj&Y?@k9OMjpK?>;t|ipDgKFHesT8~MdOpuhfXKOFm4n{RsK$5*q5BPGmkf3M021e+Ki_V<}T0y~3jJ>h>FfiFhb`kQtc ziN6NeJHiKYE!sqiUUPyMBFX6t2IPWBF0-9^@tzp7jGO_d=ig%CQk8BKgusv6V@WW z#WbYU&cdz}YtgymG|YY>3k7A8aACkSJXwSeTg}PuAGIV6OvHl^J)04Y!*tG zINbh~&DqvdS;*L&ggZgg@x|Rt6dXxHrxVk0;*U%Oo=w8@ooAr(kC_;JAqoBRXW-g# zyFI+-OdQ&8_a7fJ6XmvLT6#A8Iuq3kGA;e@c+Enuv`lNA*e z%aMEAGPd~~ow##1j7Z21U zeyCr(aa{39JmQ%+#XtQhzg+x19qn4r#11pRm(|O__nl@UW^X2D56Qs1!86f#S0;+D z%0SnpGZFi7CgOKyV9OUXQR*Wz?|;s~jjFS-F*_5JOJ*W^$}IdX(L7r_6KB4eg{u*n zXwfti+q%w1i^Z9!-!c=|3umM3OuOCVg*o{9Si67eusLWn)YjAIk2z@bwypn~&s>c5 zvBzz)dM+w;vhk#yoQnl*Y@F+#2*%}RHvT8e2V+qaQwPV`b+S@0hBnSb$BpSw`|H8! zQ2#wW(jh&KYNkW_Z(dJ>#_eyuorUN1ZD|nB=-f02e{yD;%PzLdUiKFc)FXbVU%YW# z@ku=5nK;Ei@yjpn{-WG*_e`|7lx5i~nSMNPeDuuES(YCc{yY;Y7qTordR3l8d-tI65 z3*znerp`GSy29>X_PM!8o^R{vJ992_r`h^%9h-~q$J*moH9iV8djj99V@-qc=Rg~0 zOYdNecqhwx4;Q}^jJthoyWSlbjN@-+S$|(p@WqrM@#T&;JpTr}ciBtU3kMhg8h4FYbU@;anPsid<;!!kkF$OnF$NM+p z(f9quxYpRjhSyKP#$}5!w0=5P_e(%f?qVFSosL7n2?#&77_+LRW8B&VoGW7Pos==p zZcaea79rSFBpr=EOTeVjA^6i^eDPocmajGU75tWb`i|y9A9lrCHE>C3bN_)Q*swOu!e8~9^@tzp7jGO_d=ig%CQk8B{PK&tzbLQIT#P^8$*}B|Og}C(KKiO} zhQ-gxj~64bPlm-?o39t+c+U)r&udo~qg(e3i|6vyLU6ggIg>X0`+J3;_N(Su-!`ND(*tyf3LmL~%zZi-&JJKybs-66( zKY5cL@+tk~S>uv_;h|rIll~HZ`cZbVUG}oSc%UBfL;d275zoXa{^>{gCFev6 zKDZEqwI|c?cG*<)xfFt#C(_W>GZiVfLQw8&^Zw5;XBTCcV78eT!!uK{qwx~_eV>{4 z<}Bq*-zA7P>p{CKsc1ZZ3HBG7XG^Bx%?(TNby^zkR!+mNUzVU!Od2lNFzbKqP+SSK z+yCqzii30Q{(;Lw@ysM!&(fWts5;WtfBLsj_ztwky;Cs^H{Z1JY-kaN5hlk4aaQgb zhNInV{DA|)FsgGJXjePGFmyIKF^VOmK<$-ArMUWsHcx@{TrZXa>EC`j85*~i`F0kb zN~y^Z&cRX15dOdw$u7ItE_>NuJW!ALp?>kkam6R`h-cyy|HLo9xciIp6AcWvchfC< zCDV_`jF0~K)9jyypSoCrg*VOnZ~VCEZL_{zPPhEndCC$Dy_9bG(Jyuho<3)O`xrkK z>|X*LH_sYBetpNRZ)RT5k6oLFB6M52MsL&ebNjiDzKC^&b9`7>3g(9|&#SmKuhQ z0qK?>)lPoYpS(#A`ILV0tZ~V|@X#;9Nq-4H{V2QGE_>NuJW!ALp?>kkam6R`h-cyy z|Ma8$l0I$?B6A`zqI(K@r?0`N!U(+9Ed@BU2Ag-7yWO2qu)ka^s+!z{o!h5i$ZN4U zcGKMFHoBum#p0^DZ#}3%3R;B3qHB*xEPLKOyEYah=R{(4g%sS#GkJT~MdH*`Dfnf* z>3=B_8~#kT+MlT%g_XZ1Tm9#}6NRtOCR=*ehM3$jUz@WfqyNf=D3tx&@Mp#?dnO7W z??|@r9Jm*S2Aj>Z24};HCg0XNQ$y3>pHs&HkNjlNuGi~1@Km0OFK+oC?Pc%BxcV>KAVuS9}tW zcqUHqPyF(WyT2$ucQpd10#hw}C6k9s#z!BGO11cD_hck|hNoJ*#ny<##v!Q|pYL>t zMBRR=7SB@xB5|}=s>T1l6_I$Nt9jP=@#o!l=ck$Am9s^!NiCMQmVns)n& zkx_W6oZbJixF~oRwe{37u?lb9vfq=*ccZZ2SNr{0X?)c5NBh0%*~Njx@9g(2_g#~_ z&CE06e=N{}q_0veyN-@^VAfF+(`|TAJNZ$6@+LjxQ~JrX#wGv4L%#?o{U!YLqwHe4 z>}7xPKt1Az`o$Z^6`#Z-o{3ZZ6Tkd2`IEKyu~8J}T}nnZlap;jvnUMwIT6|Xm}2?an6j2#`PGj4u|h zh1yT|UJLbqv$}~RexT>$UlSqy3-+4xkO$*lOi6U%IUQzlFh0Qf(j0zM+xVMIH~k;j z#dg`t{^Egp#1Hk0H;yYliAOvWr}!s+`NiE|lt)Z9@itGVTJ}n&A6pwA9Vwk^`Ekjj zD2yzTYWeY(c(cAek!txdZF>|t-!*v&j34)0h{A7IQY`)}KI_2qe@n6a(z=@i4a~ft zAJa`9gfWLwEI;lpaKLMq-TwXG9H{e=-M@FuXbjJ=^#r{hjR~=~{@t^qv35m@HSRg% zqn?XXEIhG$qVaLCdDgsd_fDC-U^7#!_psNcXngX1ie=aHzegi_YKrAYwUZz9CvVb2 zKBb>LYh3a#JoJlj(qF<)Kguq)%U<>u57Z-ms9(HsT=7Xf;+Z(bKm91bxaXZ1emfB{ zb7J6oKItEFN3gy6o*3+SG6moMl!CuCjK;YMCTGKDv!515q1}+BaH_51S=p zLFE*5i(QRwRgy8<%r~Fgt5N9*)2DGV-tQcPq{~ToAtMP9Q(_Qg&N#oWl7#XrV({ac zB$Ll&EviSvpuUma@%(2Dql2Q+HzLKtP~uiJrcE|ED-4G1lUCza-xLeOr{`8~2G3PYu`pEH8iSvTr&t&wj+-^ENQ#9a{+k#iJpPaN-rH1&l%&om zzA)e7K^WMc?$HIaP0YT@n~Jwz=!8GlnH(lx7UFDDCoD2KFky07MAqqyM&@pYyPp62 zY=37bj5l}Q`0RO)&ba$&f%WX_+|Eee^pE;EmhNLy*0YqGPPOweur}%~M?Kt5T!)%3 z9NVr`OZ$+-d_9g}RX~HY0wrCxq(hG2)e0?08v8bG?NjY5ptNziGXN;g>tFAUtcmh2cbmv=j5JKKeU?UFx^n&9H_$@~c}TWZ~z;IeVYl!-3e z8&wZ-aWdfNAQx99PfT)gSoF+f7q>n)rnoqF$Mc^th$~`{EyN%ji9xm#gE%1uaYYQ` zkQl@*F^F?_dnt!@dku|EzEH}-KzZ5W*N}3#0F44B;=t=&&~;)yYF?dy_xpFo&SfU= zXwC$5@6!pzOit1NtjGP?L#Mi6b3}pl?93lKqh(=%^{n@qPMC4zAN9NEvEjISmhH-E z^Zx~p-pT(-|GK}2|I_pCUs-?tx7Ks_edoWD@5nv>+ryS;&pjWVd)~Q+Eia{e9z6H_ zdk;gt$A6Yb%ROh;!@np^o#eOmu zhhjn>$Z@yQ$=;+Z)*#6NR%$S?Gl<`?~?`9*(ee$ii=U-Xye7yYIA zMSp32(O-J6=r6?*KFW<_=gRx9g7kq+RML;!I$3|o3HnQG5dN?7|XBu z#Tb9hFUJ0Bem%;mV$Uz;1Q2h`2_Qb16F@vOCxG~8P5}9Z{?h!Szcjz-FU>FdOY@8V z()^;oG{5LC%`f^(^Naq{{Cbp&!=7LNm0TP=GtvBF46ppi*k1XUF~9OVV}bQPFh*GK z31f#fzZg@j`Nddc%`e6v>)e3t`hCUz`rSo6`aMSd`klscm1BW;lzV|Vm6L(^m8*ev z{ok6yLGz3DYJQOi%`ft!`9Z4d=JC^xjjx~0Vd3+S3YRAAn%rUC&v2u@M8|~Oh#;iT8v5oFAR*z!h z?3lZUIVR3MHs?_+l^v_~Fvn84$8n9efwZsZIFY=8wrSMJp^NGO>EVaqyG|3^ngEY^et6-A6IYMMn_Ovr7<0ws{0WUmtxP}6x@_u4cZ)~x zYCrThxiBw27LV_O{BZ52sa?Ax4!v9Y!NcS!s%7e8J1z{tK~wLw{@ZbQ>cb&eS|R5j zYN@-|M*rWcJMUhr{nM!qSDnzu0vxXTp{EBpTy;ew2RmH#Mk|`Qfn{5~5uB5UV)GrY z`lNePO$^GHURbw34^t02T=h)v7KwJ%IW5sX+ExFw_Kav(T~z1RXji?|e|DdfcS`@C z?uEMFL3O{I`rmy&*8N_t`<-Fl;nW>k-ksLnTHc-3om<|W)?HlQoz@*)-ksLnUEZD6 zonGFZ)?HusJKOGex&PTcaQA!Tyu+!x=)9Bv-+3S2{T}{*rM{$l4c~{MUbA~G>4&*K zGVheC&b51;V%{lznCgbR#{@l!1G3|c9_Bb8_t?ot@sf5t=EEE>=^kVLD6ZU&TYs42 z%6S&|DE~&fbr$#UkblEHXVIfPMRp#fhdEEtqkL|5Ubugkd~WVJFdyZ;wDW2{%y}=} za|J)j4{YZj=3R(~H9zp9JnD8n_J5Z=>h85C9@U$$>sdU^^(NeF^zg2%>c6nQlIp^+ zzLM(2u)dP&$gsYW>dUaclIqSps>@^7A^PvA%foYB)iUEP&q8HrPM z8;M`_9BJ48jddO$)x!lcIu_#Jr5-N*rTN9!H_b1`zG;3j_D%DPv2U7RjD6GmV(gpd z7h~TvzZmd#nd>0u1D^fOjh<3>!1aN!9ZVDfQZZ;v-d7UHWO5ia~^JR@9o zv0e7Ezj&Y?@k9OMjpK?>;t|ipDgKFHexY5OU$j^Ai#%w4ksr-3@}~JkJ~h9{v*s81 z*ZiViG{5LC%`dj={bYZ=x74Henfmpfb6mau#G`pZoSHAhuX#kfG{0!C+R20ZlOO3J zZ_-abH7>KAVuS9}tWcqUHqPyF%=bB}0#F_(q> z$XpikFLPPQ@62VP_kp=A^qw%6h29_Lve0{#ec0rY%x#B$%S^q?W67@fknNgZ?63Eh zdNjYNU++1`)%#C8nis^W`9l1fN3=`xYklAUXy04wKl-=*`&yTtlx=HW`k8w~<1z<@ z@Gv)pa5DFZ@H6*_)(y7HUiKFc)FXbVU%YW#@ku=5nK;Ei@yjo?OY@8N%8%qh{v|*1 zJ9*RlKtA=JkY~L=*UL$*0C8&%#6gg_C{}e)>yxv0e7Ezj&Y?@k9OMjpK?>;t|ip zDgKFHeqkOY?}8q9#?;+o9;DzVJ@8&sJ}#~Z#;J5)Y%sMfkA?+fY&Bm@-e__sMg+ru zxsUO^sZ*IAjGvz}_5M!gqr<1ccrwHr6Mo7^pUc6RSIHZdubVo3FMfc%>%4I0u>wr+ z`v5!qy%1Qk0QHhSz}NM>Fuq&?s{QQ)>?-Pok1G~{Ihx{bd7|-i1z=93Yj=lX+8I;B z@L~u$mNqrWzRLmgBMqAFkK{w<8$I0QWH{-MPJ43DuYU;2*9*YGEjjqCdI(Al55VGe zIkN9Gqyf2-)xXquUWv`)qzVB6jpZ`vv)6{wv{U z{;Nh$c;WBHuEe_GMrlccbax}Ux55u#g)3LWzG~QYthW10#@y2xrc6=FT>gT1SS)K#C zPKRN@JEq3$NCz&R4MR-dbaZ*%ffr7OVO_s;B%X>w#_ljg4oXMlnkZCB2}3oLtGvjt zC=8tuhBD&~29u|GlV=#}%uEOGZLWDb4EGnCx*Q2{c)aQ)L|@6qq~ftS_40U>e$Uj) z>KTh4UmcIFruJEd@K_Y~8IL2wP2J{0u^1LI9;1giQM*JOf{%_zVP7YTw~xcK9usiU z*NNB>aY!?{6nl4cVxzf3=vR6ox-~WR2jk;VHgqEDo7!isv*O_UOb|wtcOuuwGb4jA z+|>2r-B)4Yeb+^2C*kkkW`p-#w-1>F&r8|(G%*xaP6T1)pV?Tq#_;VEgf~i=+F!|` zSi5~9idJ`G--b}U+-f2kG<2fo@lbT#Gyy%^nYv+*nY{1aCg7Tv6Q4B;!xQJnW6N8n z&gb|r{IzmCx(#-sL_rwJ_ZyEM#@@R(!thx0@mOtm;9W<(d%WwIX5PIs=G_}GcP%Er z=!NTMuC3a>7B9Z*g=M7*5NPrMcTV=g@gfE2-5?3a?wPvAxAJlR?IesE>5ZUYOg_n} zNvM6=8-b@yKFOs?I6A-wJxyN9xu(|A(`S7UvOOQyjoe{`FG5Vt$?9gE+^?_BF%Yy9pZ z_~Er&>t5^9CVseJYA^C$>#U`II9$)vQZ)Bkx1aFC^;)^sz1AjA4@H!zw|LduYxQn8 z6z3|MKIUF)o#sPvxk9dWuXX;5LrrbMThS$9PPUdHA&sMiV+jgdQguxJ5*ct~+E@EQ%w9wQ>pOOM%sB3Dee;JvA)89luV@;j8*5pqf zfQD^NeXS#F@lN@75VJ86KObC+mOsCV*p_Rte8O6!AL@nO>(-+5$B8KOgAcOJeCqU3 z0^-_vqVk#~`1;2q=6V+tyPt%fW{t|L+X>rE9`fcz*Pz!Az}3~}_eh!5sMop!c7I`V zHQ$NC-e&D__!pBCy?Zq7y|fY?=Q*%CBL;unip1XND6DE|Y6KjKMAxJ!%-m%1D@U0; z`S~UvSnt(1>KlpjyG;J>tI=3>IRcIoQMi*9jY&(4ZGS|e-58^@as*Jyfk|CWKJ|oE zsA}pE#5ak?=-R7Ly1N5ynnuGfc_sRpd&<0D+Qa1c{-J%8m52GuQJ&vZAaU&N1~OG41mxD<|_)G3^omy{VyKay8$s+8%pdW8sO@0so=R^(N+yG$kf^3d0^+_4e-ZJ zQ)|GS6MpeoeayR`3Z5T^&!~^%#nZrZ#oubxN6NEl;CW-l)>p8)mZ`gC&LQ`|{tEgv zOasp+^{%qL|KxgD+uiOzqeMLn>0|3@p87K08j@z|U+MEQ>Woga#_fBzF5WjaT!`oF z$8}NM%wOWHxvVbM1gBZ}XHKkZ?tR;H@c78OXt*E^CDNus?G0K_b@i`!WQt4A&y%J= z`gz`~aq+`s2v5Vp$q>%15tCi`k1Uz&vWxAqm;J>9^@tzp7jGO_d=ig%CQk8B{PGLe zmXDrjjkNbnEnnlWvVXS17h_T^9>$(-g_aXiEPk?cTVcPMr}S5g@vSgmc8bO4?dMw| zZ=uNpZ~XPnzLuD6a>&zP<%YFHP@JjjVf^yy%@$~ym16lz>j~R;Rc(P8d+h$_^O~de z5nE53Z*zE@w)NlnqZ#g+d)yrNlcZ*N{j!b6+rJsk-Li2mYTgW!|FZG__*^rbc|6rx zuU;$D48=??ecG#b@}U0YM|#Mc^pj7GOP+;?{0k@jBK-81>|(p@WqrM@#T&;J zpTr}ciBtR&zx={;Jo$^~dur#opR2z)50oCB6G}hN4>c~&6@`cAjl#)uNa5%Cr0in5 z>}7xPKt1Az`o$Z^6`wqx6wkyd{)u0HpPYOTJCuJAgWiR`S2kH?&)GyvRuJ|M#@l2fJpZMh$+NJf7_G;dd2iJTw{Aiw% zH_c!2sd-JFHQ&j<)&crO>jV9z^^oma57}Sq4E1RJp?NuJW!ALp?>kkam6R`h-cyy z|HLo9@ElL`i|2dtBhUThU!Dib?>r~e`@r)pkbVdjE+>^MW`vUx;7xh<0gy@qAD1Joi(7o(D<~&k3cU=Z6}X=ZeC^ z^G4z1Ii&FOd{TC?UG}oSc%UBfL;d275zoXa{)u0HpAOi z-Usrj_k=v_{UQH)ujm)OZ}gYmL$>SvWPiQ4)T8&A`t_c3T)qFqqj^D`nlHq!c|^N3 zzi6-8$%FcnAL$`)(oa4$E_oIn@-Lk9i}2H5vWxAqm;J>9^@tzp7jGO_d=ig%CQk8B z{PGLW@#HU_@2Q>Ve(KNjKsh$}YCcUiKFc)FXbV zU%YW#@ku=5nK;Ei@yjo?Oa9{dp4xftr~W(-lpdZFN|(p@WqrM@#T&;JpTr}ciBtR&zx+bGv>wu4%{%g-`AB{=Psy9+FZtBGCeNDh z)pL}Xu@+>^$UpVO(;itc37u#ho`-=za5kJ%~-Z-xKBp&fhoZ_GO)nHVLQ=D#@3f{kZyn0iNgZch4_pkOGY=T{; z1|#oZ)tS@;E8aBE&db5+GEJ~>a4H-ta`0DjV|0Bl6=6|1*w>;l0;k#SOFwOdr3>u- zxdR))ccrao)GZIZ7H{kSG|mIhn3|j%H?+40{0nV770Y_y+GZQ)o97yunzT0l{5=hE zWmhU_SE;QHQF%`)5}$KI?FDDEq5gGqvLQX;bFy9fnX6FaZfTJX;o*HM;k;cY8^T|- zWVXvLw##1j7Z21UeyCr(aa{39JmQ%+#Xs@OFTCG)>25bv*_j01Z|rup8#?YXdEz@} zAnABFWbREuUQhze<0 zjGm)iJ0sD|A?j~($<$rykZg^6ZA~Za?w)MnnKQ5x-s)wZH8?-^=!Bn49XH~yQmzx; zFty%j*W{-fj@>ggyC3L}KbGbi_x}1c7oHojX)c^t zmImSX4l#9+AK1lq*~|XofqKLb^@}%-D?W)wJQJt*Cw}>b_lFnV_d<)|NnozRAFg|0 zzz9dG^gboFC+gB90_v49!E)tKG39ISFwi^66Cy zdd7Qp!^g*M{RjWv6`|+saaY85#rKzNJk^GD#RT&{5NH1;T~YLwjeoA)F<@cS86pe(QAE z#dg`t{^Egp#1Hk0H;yYliAOvWr}!s+`GxoM^Oq0CpGOnG`}w684#x9eC*V@uR0IYN z#*z~WnDVZvi`jNCYMxF&sgP7Oy)y`TKPI4aK`O302jPj|OpWd%rq=MAgK+egdG_a2 zJpJ21d|EUSNw-qb=)-|nP%aUUd#281g@MSdX}51n8-OnxBwGEyZ#Mv8txfGaqbK^r zyZE51sWE8u-<Uhkb~jk~qcyGZGmXyNJhdw;a>GtU~F^LF&dXTuXM{AZKd8WAfH#K!trDu()6Dj??pRaNE#U{J(Y%}#8g|pbyWC(xR ziRM4z2X?Vt_OictpdRr<{o;+|icjJZ&%`PIiC=zUywdx%-^ZyRW5L{aM=QUN$1ldB zpiB}P-<^v0evU=^&SvjBI2HGQi^b6iNw~RmD#CBXqJ;S$WNSxr)^k4=8Jo?Tcwq|G zm5f8dktBQ-JOvq*;t+T?3D+u4!H7C>7;I|neVjfSp-t@e`E4d6uY=t`^~*^Z>l0_` z88UhjhV_lJ^ly7+5}FQ;v&Q{kXAl;Qji`KAu$13Vv&NrZ47 z7?cR%KW^S3*~NC*%l_hldc+U)i#LudK8Z&>6Q}qme))y*n+e}8!pApOTXp2WIA+dV zZmzcKr_cO!5qjQPZPib&ns3em9*eQ+rw<8Vgo(vttorGl0vBO#xfrW{`XB8UA)tQig{q!G) zEI_qoF;@L_wfmU5836(>p1sWunJQenP*M?-zI%lVRT!ERsVNqja8`U z>9Femre0i$o^RRhA$cniWd3ht|0*+9qRBX0&kfI&c**>?LH(&!SK_M4v%)&gi>|JK z*D@Q=7hkQwH<32Z_dZ^MF>7r6RdZM1c)Y`^|Ld8#0{0ReR{dYKv#zfCv)-=sunw>E zGoD@JvTm>Nu%54Qvd*vYv;ME_V!P~RfAK&);)nXh8^;xP=GQ~b03ul&Mzz@96I zqSE^bU_4;v;-Tm;Edd+e&&HEuh9Z5Y*{8Cz(Y3=+wEZ9fC%?(Ym*zjs1B(;zjQPKO zWu6~utxQ0U`A_|ixBT#1ta-Mr6Ip)@!TF2?jPrKlz=9!IYyKga7u#ho`-=za5kJ%~-Z-xKBp&fhoZ_GO+0p@>9{XSe!L(%{^0)R3^^ClQDk^nwkBPI4{0E1^cSSS@^rO znPT3>IMA+y##8Xl^Kt07(cCY2(EfUGx~u=59_f&tMm5tR{fv*+xc$v=Ybe(}a}#V7HIXW|t9#4o=vU&OBiLhwz@YA|0! zwRb{rf6Z!iHQ&Jdz095Lgw;4SBNd~XhTv|>Y795ut~uq*oowf7#G2o7%P%d)4axNR}=cbI2OrlDHsVx)et8h0zF!TI)L1bnj^musXUyyjvozG$~k{%H|%uG;;J z7A`V(Crk}+qvzb*MdnV7sSR%QhrhYV+{KEq#tmw)2p>Lg_BDfNV<~eN%B(}g+4tH) zQ)f5E!e8v-LX>M71KQQ>+(NW|H3r2JQlR!qqf%V`Lz|mg(GT=oFO~x7XTAuHTg&{G z6P`+`=KuZ&I0r{1L-+$tjd0n;cG=7R;(>a^5A};Tjw?QiM?4d!_$Pk(h52({Pc?O+ zoKaRC>N$z#{&!B4RiD~prKw+E5Czsl|6)cY&TNRX>RFc?5NUFInS0#kH{sQ0k=Xrd zlvPJN>B&f}JZhdb-$ir3j=-Wb<_zA{(S9Z&0^NRzvg&AG9ck{}-m=?IG%^;LY1x#tB$tXS)W?{S+`nxSkGGenLkJ4vi`O3ur9W6vR=0E zvyQgxV!P~RfAK&);)nXh8^;xP=GQ~a}zw*11o0Us@Gi)!XOl=9Md>fxzMsn-3O zp?Dd~TBTa|XLfkhMcIC-*8Q2Q9xq|VR8s@p+@JZR`-`ZvGS#|2(_n5L{BGtSbBlSN zu8j`cQmy+l_lMWU)B~y3{h2G(Yop=U<~+*WpXpb$HmaSl{|lDPyDRF$yDNH@cUPp7 zcULqP@2&^~@2&_N@2&_l@2G3+hV=Krww-qC(m)xI|fTv4P; zQLxbi3F(c%+>{UyxO8a=2vQCNL6KgLa)eMqk&>MR0tq2a1SET-2N3)rU63N}pwcXe za<~T%sDxs9=Vv|pv(Dog?;Y=W|IiC}?EltSWBum(&hK1p&NYAQiTl=?SMp~r-FQsw zliw2u!#x}4_c-!9<6u~Ctx>W6SLT)c8T%rCX3V?;;+8e%l>C{!&fO@@H1qcc&P&{M?d1bLHX*G4JHegU)w992XNa=1Ts|89%=?9y%!h5An?_ z-X3OpEot(_Qjs zULQX#zV~o<$)7p>$;;!x-*lJ!nbQuqJQgfFz2wjQ_PNVq#(Mc}x6Ge;;lRt{S6fdn z`7;lVm=VW(th?mT?6T90*yW?$C4XkyJgY9ZMt8}dxp%Y7lUt{|+=-7#F)|9FOZnp}tw`hv&JW8^z`OHn}|?UuL7&=)flD=j4|+j7tt~=G_y|Z5X#4(&S)R zPi}+l$$3x?xe&@HN5X!|oe&Q>72+hOM7`hj{G2B-so38!6VP$lz(zC zvc~8TpzHP>jw3%C$x8+L5}MW@?Dqc*Yyf}xsHL;^$q;4 zd+6nQh`!dtgYDr*Iq;@@__SYm77zT36T65Xd#M-o>PvfhK#u$%U*70fKEWf;;FN#x zYZr1AoL}THXh(7zv@bai+MQeo#{)SMjuUbx96#h#IIhUGaJ-R&;W(t;@kx8fEpi;s z$akF6uj3y)&I@olU%>A?LNDhRISkg5+hBWg9+X2ag!0LeuwQZ~#6wPnILWmTKRFoc zMZNmcULKGmKggFi`jt=c$TK+QAN<+{y_{d@s~zD%`@)ZQhd0Lqd^%3x+3^Gajw|fq zc*9{LUlva(TXA z?3dgL@sLv?PI4{8PY#B9QLnzVmj~p?5Ax-We&rK9@(fP-2fubfFYQGRgZ1P#*q)pR z<&X=Zd~zi0m)r^QkW(Q}axKJ94u*PBufDXG2js{P^5uP@yDrhM>lJuh$H3|O z27cE)^m08!U+dw)_VA+|cvC)n+Alnd2mZy0UBr*Q)QfucrM)~LM}CkmZ}cml;E`u= z%0KwE3%Mm{Y&bN=e`tQmnfb{&Lu2xX=a-zBk$)W$Pv`#{$eB6*$3x=C)#sPol|NrH zB>xMM{#WMA+_mkH_@5ihFF7-x`t9IYcX0kTb7p>e*5Ft*|MNo5%sXojj>q!Olbo5m zzqNV%Veh7X>Xw_w+FxkeU;p@^__t#lIforHD1LNWBmbV&2E~ww3i3u$Pe=6jeg}5Jn{@q`6p*ayO3M*@^Rb8{HrrpE^|({ z$$XfHX3s6TD6@CoKL1}jx8$fiw{GT0EXwhiIWtE*KR))qX>O3yvgtR*$BnnjGs{&>6i@?&#LZp@*FZB*xjO&3$~Lj<`b`ecX^(FmFK*i8_S|~y*721g zP0r66=WHF%4Zk+f>$o$vj%7w>tSoa*tS1-6_T;E2hujtAlhb0qV^$vei&+s-YyDC2hB zF?OFYx8%&6`l%h`rJXY;E^}s<`S}iU;$Hdx?97>Y;L;u9!JPNx%xpM%hnV?K`Pmd`y0z!L!y=+r_(&HaI`GV7vInQw{#!^R|n(GdBUf zR{Gj@@u{EY|Nb-Q#Cmd3Y)_7ga>!j#J~=J+ORkG}$bk_jxiR7=XGXoKS6|x819IdC z`SM1;@(CV!2B-XkU%QZ7a>KF*#gv<7mzk!NtqKRGkn zh1`D@oIINOFc;oEtK^~#Jnp1;^S)UnN9Cw(^RDejvr6vD?>}%-tn=io zlGAd_cTS8iJvXc5x~zFX#=m}(zs;PP$NqRi4FCPCk~8yq#%o^x>#UM9bL+Y%#F{H! zRqD_D_VKaB$1^`C+t1zZ_;_ohCiiCIi(iTV7}n(EeDCb9#2s5TxjO%xc`vK%(B$xZ zaLI8och@GjXZs%>7bEv>a(=G8{$x%@bxhu*i zr^SBBbrBCaFybUPM*QT=s2BC>OM7`hj{G2B-so38!6VP$lz(z&vipXfd}c6f4T z$vN36^I?vCYG%nrdHY|^jh{S||C8QyPRyK~cY@E)EIBjJ?{seb>7|(^XXeiJ&yC$* zn^|&Zj(zi-_|)6^+uP>E&i9@ZA6@Q>k{k2f#plEmt7bg@kvZ{$eb0#{pKR*qefpeO zXJE$Kv;Bxyr^L_3Tv6n#dfSwEY<%8zo|)}0m=ag#e^{^BZ%$mB`7p2V*W~d0X8e>m z>)n^z~TTi<@o`18uGA4!u8Q^NUKT$Y($s%&@@4Vot(x{T zMqC!R@6^aS;RBb&;(ewU`RhM@X?*pNeAg;-W|qr*m?tOae^yq#Dt5Z~(l{*t=SyzS zD<@qVOHQ6%@XtK*(m3SwjK`#2_aAy`oOj0bk~3pHxhS?LM@2d0t|*_J7W*aFMLgud zh?CqH@sl&7Uev2E?d1VE@`HSNqhI+1k354@{>hoqF65Sc_JfDS+`VR(oRbBa5A(yl zXO~=*5B%cb7`9*TQ<*cfb??D(-+{AB&dfvkeXD&ApIvfhF5cka_|~zrOU}&ydhqjc z>Z$qL%$Zqu_~+x;DYHw?%meQn6az1tU2*<*D)Y!)KM8lcO^q=DH(hm0Xkuk3TivKbci>RQ|{I zr^doB%__Momn?T`j6Qi*$(h;vmQ&)wGiQ}tmzyV@5(iw6zs;PPFTQnh>^5Uo$(gzM zqLX9A`LjyS%;!FJat!Nf>OawQQtaDl+Q)>GVvXD%$(ecU7boU@Y$Jc4b5D$){G#di z<6}>ZL9aG==D(fy8E-T=fBDb}vBz5t{;qGI5VyZOtK`hgntww4@=vo$&W!csqS&4s z73Gk-qI_~%?3Y{@@sI-}PI6N@4h=T$eCH`r{~7%_cZly z%sn^8{J3fV^)Kd~#B+_D&u?*Vy!zWl{>m$!8{f-!7s%Cl{nzKjN`G$fjJp4vn6qq? z+w;`7&xv6lZgPIky5^j?YQ-x`&P>m&bK;)7$0p~*dU8>0PmYRm$X!uBIW6`}u8Vlc zfe|OUG2$m@M!l$4U)sw9a^wg3@^i@@-~~L)wWlAF1O45 z^SW6#-plj4Ki9O$S$)6cnzrrLKJ&E8SNl%3T|V#5|GEd{tpM)_ z`|oF)`{MV){cQi6ApF_!P_t9SMc_Wc^AC>Vm=0M zznG`dpU2YV?fgCRSo+^qYTjsizr3x~wpTmHuU+PiEc42Ed&+z>-pDc!jW@E)PvZ?M z^VWFV%6zu|e7`2Y@$ZrEN8V}w8+4g(_&#}qu5GV&E_A!hTY~1_@HFdB_qM&-|3Pk-`~Q#Jyod8% z{y#GI>ijKZiQib^JrlpZ!aFB^lZE$B{8mf{H71`{niitdJY7S-v$Dw-wXo3-x5MEzcIwP zwVv^8d&aqP82`%0UiQm7LgL|lA#w8Vkof=6-(1sP=;&KF?J_+0z6$*K?h3s59t(W> zP76Hyehd8jt_ybYy%+4|J23t4fHm(%GEU@;@gtv%D|u$T$v@*zyYL>J`yKDpxvuhl zo$D>{+PMz%-ks|+@8G#^^FE&Y9q;D3-|?QF`(6LHDVzO{clP9sclP9yclP9&clP9; zclNYP+g|NA65Hke_Y#}^?!Ek8BKC6q#9r=q%sclx=AHW;^UnQ_dFOt|ymP-}-nri~ z@7(X0ckXx8yI;`WeFQn~FUWV_po)wm-(eT`JM86t z*Z;0;v)?gJRo4O@A`ur*Cph;Uh!_T>lp7gyT0*mb6xlH-DcOrw!PYKZnw+*?{7Ep%=hy9 z+t|xUox| zb{QUwXTp!~pu(H)qr#`}royxDslvbStYSysU&UU&%ZeR+ua$b=aqa(3LG#@Q>?qIJ zQU0-`cKO+F=7-;*pnT;f-Eqo8)Bon16z#Vr4uAWa*d@Qi_RB5vz31~X|MnX*;;zxt z%QrIay>LdHHfDPHM#hBWX2gfOrk8JI42T&qcIWBk8ySE4!}Pdu()99;j3qPjz2|o(H!{T2#tDXh)OR}C`tn_pzr58Q_s#s_kT_=-!A#{+WGGD3Ny;LOWvJxd3=168Rgq0lh?aEJ~AOW&2N_+JnypD@30x= z`ze3k@UrOo`i%c$-%n|O!=?RA8OmF3J~0Mvan0X+=Y{rSe*UM^>bGww4}NZ3Z2M-u zC;cAyHccD`9995SN4pnM$IkX$655)u5nMk7y6Mqu8Ea?xl>%f zS$@|hznORSxE*5cS$SWV-^aP~kK4s^f4#PRALpixwu#Q(`Ay{fKF+ScjQIT(^UC*e zHW{;3-1G3f@_n59hHn`^e)Vs^4a6ENKmR-4+HLrjQ1?CKV(8oXZLSwii1SVx7cVb8 zzkEw*>t)8pr&pO@z9ls2kS*ev_2-vw3H|Vjv9U$IOU(C-x_igOkM@~gz9sZP@95a& z#QEi0LK|H>Djw~gAAG~e^B(>BU7^4CH;mffPWtcPRB|8u?`_&RCw*hRxa6IMs{7JhatCJL z8M*S97_xPKzy6MCojV`P@BZZb9~qDBob@lGV~sr)M8@qqzu0JWyfiU?J8@cP*4?Ax zr~kAdGH&0wW8YCR*@rB-|-_I^HBL4OE2G5iC438b|X>hLEoqoX&8~n$fGCa0_ctN1ogU1e!qaVp{ zIo;pgu|DJT9ouJozN4Is&v%rc@%fJZW_-RQo{Z0T#F_E=j`%Y^U-hD1eQ7Tb$dMo9 z%Nza5CwSx;obnHT?b5avWqtg189VA%Vn_W=?5H1#9raJKqkb!P)StzU`nlLq{}(&D z{!p*KOnd!k5<&A#j6Fl+^PWcDFc0sQ_|8-0(|Kj2@@0Q#-CVuh! z;xg~9cy3Ib{IkVn-c4FzY`pZ;;xg}^*lBF+`N-lj?^eov?JxH%F7xiD-;a$Ux8-k> z|3B`#MU1;~ahZ2d-MvMean0f~?^YZ-F7~^;so#FixEOv;(|&^wZy6_^+Q^xF?3Qun zF^&8c9^5i|ztHr%<62wAf%`XjzQ4~_@$eoE&NHWM6=Qd4@UM66R`J-5i_5%w;QFoN zn>#En^UivBus!@J2i}wqpY{vS;(>p0Vi)maFZH5ceQ7Tb$dMo9%Nza5CwSx;obr#o zv`gDwl%HF3Y#e)CPtozrPmhfqzu6P~cKxl!#tZX%0-3))dTi`8rzhxZ;`L+Wwi!JE zh8b^A1M_z^4Au zzmAJ5cW>I?IC;x>Zo5X#A0FK@elxm}-#uWfSbI>@@8c(L75A>+;Mw7ptz!7P4bBg} zyj9Fuv%!DE2O>tU-cxM1$44SoUahB$N$Z)Lwr9>Nhqk!NtqKWm6~Y1@nP)8F4LhTpod=s5H{o5caQEiCiy;u)L8 zy>~1u^X}mzH;aAmURdVcJ_9z3-#)mo%)5_2yJ>9s9*>FY#kX^`c&VX)h1Rkss_RZ}cml;E`u=%0KwE3wph>^1v8;NN*Xp7kzAC zEPrrs8P7vT4UE~7ddoO}*#eik9q6$mU%aC>gMsaHJbWo-`YG5SiWihy+a4bRqyr`IZOR; za4h;=PmzD^dPCx;FZGmuU-9eivv}ZNoY+PD*h{^rS6|x819IdC`SM1;@(CV! z2B-XEFYVH{7v-;fd0=#Jc5_)<);euqd}-60%YOI0=>ucAjc+dd-5K`{jN?9YbJ_3S zSawkS{9`wlF}e9(gW|$fZZ7-Xk8d0l-(N0&o0!*JZS(xjM{n8h{&>db@!|hS|15PJ z^y=pE@{3LV;rkDcyPoJR?Z@9cIF`A;x5$~g$&gs-d%Z>ez_W%#*G;{p-yIdgi9>nX}4aE-Rlo zZokZZ@h~RE$yyd~ z^_^We9~uKzTNwF0qt1;_4v8h}E{y!YM(2nx4T=A?$->C*A9c=Mc1T=5GGh)OzP_{D z^!)bIwoUz7n+%RW?AEj&^Zm`EcTywgjr}%{MMpOBcmK40Xg!6e0if^`2>$VgH!&& zuU*>qqI~A!p>f;5d~35+hKFYt4viNFHFg|3b!hA~w6Wt!6Nkq0>C40C((4Y5V98x)78&(647W0mIrT-b5X zUkuD|fHdQ9aemwDjk_DYR=9m&tbOl-Vn^%Y$M*219Qaf|Jlik)iwC=i6MKmtJE|A; z>PvfhK#u$%U*70fKEWf;;FN#ts9mtvCk`DJ>s-@Q#_io-92S3^-BZT%;pY#F3ug5c zem1^!SS;!8DZE|1WLO-LegXFS>Gs28wJAM?=hLql9^0LkzfF7Hwd{!4_1KUik{xc_ziu=+pz+S80 zJ1UO*c!THsWk$!(^Zbv!b{>{7(iI#0ukAWIe)*xEG7c}>Z*<(Td{42L_3&VO_)!kL zDIY%V7oNof|Kh|h;>TXxbw0BxUxjJv-?B zez$BR=g!kd#XE2H6#0kz+o%}$TAokPaf8wE4Cj`_v-)A9W5V-21?SV3jgFh2X>4@L zO{3$pPc^n%_qNfoUY=)IL#)Tvwr9>Nhq0l2#-#l+_r=4Q6eoLu_}L58i+c5?y*waC zevmJ3^edm>k!NtqKlrsv+g|xUl5kC{zZN#vHBhPf4Az7_=9R{Z&$&8ipm`ggR~zeA4x9rE?> z=vV&^JoBIPyG>i)=z;wAXJ!j{X$#^|Q+O>GQw9qhAJ2{Wb9G$Dx=09XwbMKemTAaT%cKMuY0@6gwJc(6VE zC7iIlB+UQ5{ zTm1`U>UYqW{s^4Lshvfz$gq@Ow{(Uf$nfQ|qy{?HL2gVQeU$F=M}sCGjxE#L3tb zKVwq8s8?Uw%L8)c2l?_wzw!wlc?PHagI~L}?M2!9yLK5KyeEPm?~mZkdnNevz6qYa zhk}3ar?89nR@lq?EbQn#7xmtM(cXJ8byIOQMw+6BG5 zze8W|iQvKeBlz)N3EsSKf=}p0Vi)maFZH5ceQ7Tb$dMo9 z%Nza5CwSx;obnHT?b5avW$*83<2@0-_5KK%-Ye0U_f25%9tv#UPl4HcD|GQb3mv`Z zqTc&2+IugC9Pi7J?>!p*dcOu9@7=)ZeH{3`r$aCA@35)$*xL4t0p&0@l+T#4U&fMn z7-QmO?1`T-sb18pFYV<4Ir4*id81$X1dlv}Q~trPUE21_+@9*+W&UUNBQh_v`WKlm zTK$g92d@4|<_T9nCG&@?|B`vd)vvjI+6mR)$vouh2T`woM|=G{GvBz%$$aA~Kl6=iznO1b@nrsR#hH1<6@TU%SG}m$ zzoWhW9dh*VkgtD7zxsFJ(Z2(y{vG)B@7ngFtbf-o!-IYV{ODi6n|=p;>W{#)ehU2S zzhD>r8tkRNgB|sQsMkNDy?zsN^rw)opH;?BpZ^6O{W5UsuYq4b4!!j6;K6$Mu|2#g zr|{V)AD-6h`#EHGcj~&&EdiABfJRnDYkS}laE1%$zXK>0t__Ygq>EEHRegr(| zU%-!k2fXQzz^8r+JnO%}zkUsN(ci&d`a#s|AJJaF2|4;x$k)%JU;Que=$C<0e+~Tl zapPvfhK#u$%U*70fKEWf;;FN#x zYnQgYDC^(RMn8hz>R%vJzk|N?N5G(;0yg~@FzeT#i~bHe>IYG;e?)uzCgkW(AzweM z=-B6ffk(d#oce3v*N;Ol{X1-GJ+`(zV?a4&O!moV%-AnuNj!`(aWeMA&zMv%>eZL_ z@_-!qLB71vuY7_>p1~>q;MXo~dr{WEqm6z9ztz7$rhW%~>5qUxKLu?1FJRWMK^OfU zbkq-`UjK;p`c25upF+NV7X9jffk(d#oce3v*N;Ol{X1-GJ+`(zV?a5K4dpXt?3b}5 z9>$nB8GGVqOsW_4>PvfhK#u$%U*70fKEWf;;FN#xYnQgYDC^&~%kZEd0YCZ|@TT7Z zpZX*4te*n^`Y+f;zXp5h?_fv$AnNsxXs_Rd9Q`Te>t~hm)8~JIN52f5`fK3Vk3%p0 zJ9w}jerykK$|-#I$%kkAg@5s27ja@Q@nc8zqF#MzFAvC(ALPp${mLhJBk-x80?+y{@ULHkUG#UbmwpiS`bV_aZ$gg#6!P`6=vV&> zJo;te)L#R?ejIw~-=VMd@L+rRQ4YK*A3p6Dp2Y+I;>0fE$6o41z53E#9*`qH$d@mSix zzX>_|Q^?oPqF?)#3cl4`&2Oj-9aO&TI zU;hrh^zZWhgj%2PC)D=&enOQq=b-be{Cq#5_M7h~R6O~9LdBWyCsh3TenQoYdi^`v z>)#3cl4`&2Oj-9aO&TIU;nOcFUtCN?J_**N5GH%1-$8Zz^DEQJnN^xzy1q$ z(XYW?`a9TBKZtt$BiidXAxD1-`TAL9{Pg)>;L$Gwr~VrF_2bY>{|+9khacO+n{o=D zee&Vie&Js{*hQS!OZ?bTy{K1T+RFoS5l z=y$-I{s?^Pr@*uR3;gTXU>E%z?4=(>z5WsH^_!5RKZSh#Ec(^|0*`(fIQ7@SuOEkA z`giDSJv`VRev|`m%7;(;g=g`=zc{gr__3FIQLnzVmj~p?5Ax-We&rK9@(fP-2fub{ z+l#XP9c}a@_-*wsQl@?fed&*YK|cj-`Y&MCuR$069dy(WqF(=q_WDi8(Vs%Tepb=3 z&;LS4{W5UsuYq4b4!!j6u&MRf+V+eA<&-hmC!aB6zlE%w?4`eh9rc5#*FU1YeiL%^r;x9oRmM-B{{j_hyy=g?r+x}N>%YLiehqff-@#t`LDcIX(O$m^Ir>w`*UzF~{V(w7 zmw{7%4gC6X=%s&$zShHo?cql`@TPqDv|o4@5B!T0yNDlqsTcL?OM7`hj{G2B-so38 z!6VP$lz;GRm$tnq>)+8vKZ4&@{~~4TchHyq2pIHJz^4BKX8js;(ceKw{UGY~k7%#o zgdF`TX(62e+~Tlap%#C!+iM6WexM>GsiW| zpU>RdFt0vyYr}l|%&iUc@H4kI%+Jr<+VKAf)SJ&wd-ME}WBxz#{a*n6`hNuQ_&)-0 z`hNuQxBib1{vRQ8Q)_+Ztk(9K%Ub1Rj%$^lxv#a~%!#ddGFP_Z%pBT^KXYrVUev2E z?d1VE@`HSNqhI+1k354@{=u(Z+V-N{`aeP~!-IM6@MAtayqPBtpG)`s9|4}ttA~H{ z?Xin__}I(*eC*iD+Yj^kX>XoCa?JlnzW)oLU;i%v9{)!GPXAv3e*brXj{YA39;}BS z+ryi3;8XeVY`^d?9_%7c>?MBes9w~oFYV<4Ir4*id81$X1dlv}Q~trPUC_(_BcQK& z@94)m@NB+4{F{f5z0A+YUah?SFrT0H=J_MX{D0*8zX1C6{{rCg ze+1z4{{`Upe+TI0{}IsFdU&us{3r+Bln zU-%afb`dA`5byIOQMw+NEtT%EmL>Wq2@d20zBr;LSK2d>Vg)XXA44 zZ@dn>7{|k2#`mzJaX;#f2h!d+A##i#BHy@T89#mTM(`Mi1gG&y@Ef;8FXNf;U_JcU z9^RBw`0SGp&-M%d;=wNB#9rdZj_O6d`qEw=kRw0HmpA&APw>byIOQMw+6BFgXQHoh zGk7qb20zBx;LZ3Od>WU7XXAD7ZyXQ17~jKQ#{H-_9!PuRgvc>|h}9MEI~oI|-q;}R zjTs`xSR(R`F_!Vu7kdPcF-dS5s|3F>O!P9g2@lr8kL}@2Ifc(Y`S5JN@Gl}A}KdgFn#H%^EgP5Z!(q0~rBR|NOH~N)N@W?YbP5Z!(q0~rBR|NOH~N)N z@W?YbGBPV6Fn?4@4R zt1s>40Xg!6e0if^`2>$VgH!&&uU*>qqHH{~U4{o^Xz*if4c?5o!Kbk}cs51{|HkgH zi!nXyWvmZ78Uv)>*dXnV86wA6BJzzf(yy^c@EDT>r?E=#8^c5|W1H|`J^a`n-joBM z%7`k*F5l0o>uSC^ zQ`g&kZ>O%q`3_HApYwg5x^CyYJ#{_Lw{hw^pYQzC^*`Unsrv%;?iaLoA3=`$3-aA} z=-2%SJnmEAbpHas`x<(=-{spfwLagRsqOPEnkpyXsHyVv?V8$ezG+kOfJAB?>>SY_ZQ^5@09V=w;zGWeF~iJU*LCNLofF` zc(5LRY!7eBDSYdiNT>r6``vUdu7qoXDL5}+i^4)jn*Zl}Q z?o;4&{{p}J8hW|kp|ADuV0-vc4!kKJKJ6Et#RLE1#4h5;Ug|}?`qEw=kRw0HmpA&A zPw>byIOQMw+NEtT%Ip6CDoyT6T|Jc!efqM4~ z+PjY+$NdHQ?mP7Begq!(DR8=ff!}=%z1;8M!Fu?yJ-jIgK9vv8_6z^w!7k#&UgF1& z>P5Z!(q0~rBR|NOH~N)N@W?YbGBPV6Fn?4@4Rt1s>40Xg!6e0if^`2>$VgH!&&uU*>qqHH{~U4{qaX7FP? z4c?5i!Kd*zcs4Ev|HkXEi*Y>cWqc1i8uz2#cp&YK6C%g>A@YqYmhsaUZv>BVNN^gT z1ix`h^fI0a57xtv?cq&1h0i|u@NB>EFCOe7PV6Oq?5JMUt1s>40Xg!6e0if^`2>$V zgH!&&uU*i~cqaN9H-iV`Y4Bs54c?5u!KZOKcs5=K|HkpKi}5||W!#T?`?Z`=~SjAx>+_3&VO_)!kLDIY%V7oNof|Kh|h;>TXWv4|-Z&w0j2|N3xMCSUeep){7>5L>@k#I-w?r@Fnebpe{Ma7elvDWZ zlMm1K3;*K5F5<*q;>V8aMZNmcULKGmKggFi`jt=c$TK+QAN<-Sb64tqm$^E1UCkVx zy544PPhE%SeD@vt zbw2`+`xH3czrgRlhF

nX6OlGl!?P&)l9WCv$$P{LBTa{br6(#gn;16=&uYRs5N2 zRQ00X{f_qTcgS(SL%#bR{mLhJ-0#5Yeg}T{ySBY3yWh3T@Zh=%Kd!g%<~j_YuFvr7 zx()xX=h(${9(%d|V@LM|>fJAB?>>SY_ZQ^5@09V=w;zGWeF~iJU*LCNLofF`c(5LR zY!7eBDSYdiNT>r6``vUdu7qoXDL5}+i^4)jn*Zl}Q?o;4& z{{p}J8hW|kp|ADuV0-vc4!kKJKJ6Et#RLE1#4h5;Ug|}?`qEw=kRw0HmpA&APw>by zIOQMw+NEtT%Ip6CDoyT6T|Jc!efqM4~+PjY+ z$NdHQ?mK1t^zBFBai0RG`xp4#*U-!T4j!zBAKSy5atfb)^5NNj;a@!1MV#16{Mb>w zs8?Uw%L8)c2l?_wzw!wlc?PHagI~L#m-lz*YupSTjHkhmaW;4}{sy1M<>1+P9sC=| z!!E}6u$T8-)Em#Fz41)s7|%q$@l5(Po(Ue~ncy^@34Y_5=w&<;eXWNF+ry7?;7$4P zX}|C+9{3k0b`d}JQZMS&m-h029Qi@MywR_Gf=8agDgWTtE^T{JHlEoo!-H`%_%WUa zZ^qf+)A$=a8<&HB<8|1@I3D&gzK0!+`%!N^koLw2kz@Q2`NkE?`00x`g2y-{IE_z& z-?$}u8P9|V>*2@t@TQ!?XP7iHs_?J_(VH-jJJY4B#84L*&(!LxBW_%~jMU5w*l zFXMaI(YPP=#sg_@oDez250P(Nk$#Ogg2y-{IE_z&-?$}u8P9|V>*2@t@TMI2R6ac0 zFZ_!KyNDBei61+v7xn5(dwD>P{2*W6=vO|$BhTQJfADLU{O@`7@AAL))sM*k;8*`5 z|C?X^j{MJl^+)o*{MAp%|M*w`CI9#1E>BS`1SA5OaCtaYhUa0KlrtM{x`qM$^YzE`T1Y|+Hd~Hzv9XN{#Ts&CP2lX zZv|AnsMo)vz5X3?^zV?be@DOici_>#1E>BS`1SAF_M)tR*Dk|@egypJU%;Dw2Yl*} zz_We|{OiA97yTOSrN4t6^@FI_Kcc;U6LR#YkguOr#!sLB1s?q}aO$stUq24L^zY!o zdib$DyeX&f*(V>K?HB&VgI&aly~K|l)r)%drM)~LM}CkmZ}cml;E`u=%0KwE3wr6_ zp|5@fJm_D*kA4Td>5sstehNJ6zreqK4R+Dr!Cv}7)axJ7UcU)B`cuf)&!S)bFYxG> zfm44C{Q7a|rGJOM*29DC;YT^}rhNFcUw9S|{EHL2h#z~Y7xn5(dwD>P{2*W6=vO|$ zBhTQJfADLUw!J9p-?hu|pdSH0`WNt~-vOWcBk-)B0{{9i*hRkvd+G0BNBtn`^^a(; z--I0fDdg*CmGRT(e}PB844nFF;Mb2sFa0}supWMF4{ypTeD=wQXZwYJ@n9EmVlVMy zNA;p!eQ7Tb$dMo9%Nza5CwSx;obnHT?SfwVcj&7h0T22Y@T1=WZ~7zfsh;wAXJ!j{X$#^|R<#{|h|&W#H6b1HXP8dgP5Z!(q0~rBR|NOH~N)N@W?Yb36`V{s=tlr@+7d3wF`3!Cv}1*ik=-di^8X>o*}se+v2fS!Mk6`Cs7CF9WCk8u<0& z&`bXg9;}BS+ryi33ZH%Q;n{xSUp&}FoY+hJ*ipTxS6|x819IdC`SM1;@(CV!2B-Xk zU%Q}}{vG=2N5F&r1^noDz?=REeCnsbv;GVG>(^ix{T=M3A4I+W5$*MxkfT3^eElr? z)&ByIei=CR*TAnIhhF-3=xaSZ*dBhA18>TQPy2;u@xZ@0v5WYzmwHjJzO5 z<&A#j6Fl+^PWcDFc4^y-vi@DW3=jGd@S}eLZ~7hZsXqeG`YG_Q|AJlgYp|F84tCTJ zqF(=q_WDi8(Vs%Teir@ee}PB844nFF;Mb2sFa0}supWMF4{yqWPvyh2{ldR^u!}gc zm-w-xdQq>ww3i3u$Pe=6jeg}5Jn{@q`3Jvt$#0!^UR|_B{KtPb-#~AdZ$5j2=$W>N zZ=-iC!$bf6xFF#9{jxurkHmP^Ph_0yKQjLHE14Jio6HyeQ09^TDf3Iem3gN>%X~C% zhx&g1ePJ0V^2vOZXXc~)Gat1JaU|y#@g>hW#GUH-C*x6`i-=QsULtP(Ul<)PO%@=ttByI?Qp7xvPQ*sIz%?WNtZm*W9@ zIlr)%^9y@9zp$6{3wt@gsCRzR-uM`DjE^DT_!#{fA0wV=d<>k%$G~rV484qxp|ADu zV0-vc4!kKJKJAw{qP{2*W6=vO|$BhTQJfADJ;@^G{l z`8n2;w_|(qd6Yw*kMha?v0w6n#6!N2ILRXte}8^v^Zj@7i{y>`BKai0NS?_rl7I4x zvml~iZ>3&;miGF&$kG2rzJ4+N zdL96eel$4sufeb1jb8fW=xaSZ*dBhA18>TQPx~d0OFZOviIco9@skgxUev2E?d1VE z@`HSNqhI+1k354@{=u(Z_#cz@;{Q$7^S>wC^M5Gi@INW#^ZzOP<$qP;;r~|Rmvw!jbEP3PqS@OyMv*eloXURYR&(bc~%k>a@Iq$HS^AUSFPqCNt7kfFcv6t&1 z_HsSMUap7O%XOZ5*MHi(FCfSL0{QME^y~ft9`_w^x*vhxeG0wYztGouc(6VEC0t__Yh~!1TWlR=$V+ zzIY!j&ru!M!#sy{oOgLX={O(r+|qHL=6R;${LOPt$9bLSpN{Kco{KuJhk0J=xE|&? zs^dCOz3V^i-4~GKet~@V5&Ct10gw9*INguH?>>cI?q7Lsto3=GtnKrhS>@#Uv&zqN zY3(=9s})b4V=K-)-&Xv2?yY)JufDXG2js{P^5uP@yDrhM>lJuh$H3|O27cE) z^m08!U+dw)_VA+|cvC)n+Alnd2mZy0UBr*Q)QfucrM)~LM}CkmZ}cml;E`u=%0KwE zOU9$>{7OH%+A;m>YTxv`tKBnhQ^!Nb&FVPGcv>Al8E32GD&uc;yk%Ujjzj95U$l3A zA;+@{uN+@`kAxJ{LlahobX<2JS5jN4Q^8Mmo8 zGd@%CXWXXhMZNQj_RcTlIKPnZ{Gwmy7kHds;Bs^;=NI}~4-dA7 zALYQC^5N5d;aNQJFHY@#Uv&zqNY3(=9s})b4V=K-)-&Xv2?yY)J z@BE^@^9wo7FXTJF=-2rL9_JT0onPR0exaB13w^aCJZN9|(eCi(cz{pG2|PP~;NNkD zT^w)N%W+7(+^lf+CJamta9=_%qlhJ-tJHCl@s>J%G7eM6RmNxPc+0p=9f#CAK56f`MULYc`Hpk?b^L?Jc>zx6 z3;3N!=;i#%I909B_*HG6ajhyR<6TvL#=&a886T^7GHzCJW<0Ip&p2Dvi+bl5?VVr9 zaeg7+`9;6ZFYq|O!0G$~zw-;d^uN&8brK$2KjFu972aHL;nQ^(o?V~e-*p?ixSnG# z{V(d>zi99Ng&g-U!xDE&9ef( z`B&&=URK6QYJJ8}YWs|@O(%8j3 zYV2ixHTC9Q)82e+0t__a&!;f7 zPpkagXKTN?|5iM?FISwoUswFxZ>ksd>PvfhK#u$%U*70fKEWf;;FN#xYZvs=UU_b* z^?9DD?em;d<>dLN%FlCA?KjU$6;Ga{D$YD#Rs7sP+KYa*7kIQ6 zIJFn}+x9X~6@8s|@ZfxeALl8&Ie+2Pc@59bcldW5z%H&2*voZ;de=kRyB;FP^$_{4 zhxF@u2p;oG!RdMke%C|n<$8#|*29DC;YT^}rhNFcUw9S|{EHL2h#z~Y7xn5(dwD>P z{2*W6=vO|$BhTQJfADLUj2qPbEB)?TpZ<7lpMH9klm2^^pMHJqH~syJC*uGWXT}FA ze(pEbi+c5?y*waCevmJ3^edm>k!NtqKlrr^dTFnWlhpc*pVamlSE+I`-csdf9H#c0 z@tKMz<2Ds%#&aru?l;wodhJDf?S&leg?#NrzuF5t+6$c83;b<+xqqRr^9~-IkMQF> zg*WFfd^)e;+4&Ctt^?S`^#OaiZcy)fNPE{qjU?jt{c?59@5_R5IL@g$ag)YU)MwMxE_Mj^$`57hv?;cnCHe?pXbTip8G`Q zJ<7xn5(dwD>P{2*W6=vO|$BhTQJfADJ;^m08! zU*{b>I3MB1c?xgNU-)!h!?W`p{#^&Ki|YgSa^0Zb^@R4WGstoMLB8t}{kmR($8`*x zu5aLX-9s9eivv}ZNoY+PD*h{^rS6|x819IdC`SM1;@(CV! z2B-XkU%PM*==|b-Q#*2RsC~Il)b89fIv%)xbewQ6>GP5Z!(q0~rBR|NOH~N)N@W?Yb4ykv1(%x~49LF>A9q07x_y>>k0-Vkl z@H>yt%lVb(##*1}$=W{8nN?1nKdbyam)3ssyjt<(Ikw`=^KHe?{ib?R@BE^@^9wo7 zFXTJF=-2rL9_JT0onPR0exaB13w^aCJZN9|(eCi(cz{pG2|PP~;NNkDT^w)N%W+7( zhx=u5a_=mD?xWR0t__Yi7fX=UsdsI7SJfzw;<0RGY89%AxA>%4_oMgPEj-QOf)Nz&Z znL6IM-*g;O@A#y>;}$uNXXHE1>DTcO9_Ix(oiE^b9-)`>E8|qPKI2!lea5w_oQ!u> z`56bR{bqcu;>oyK#hLN6il6&U^`hSSMSJHLa-3htcYe{Y^9wxAFK{})!0-G*FZVC> zb)AF<*H8FyU4=K-TljPxhG*Aj_;=mLF0SX;%XOZ5_b=MJe<8>H3;FI}^y~fw9``SB zx_^P+{R_R^ztGouc(6VECnD9{fNenOs?>bnYgj;il10J9cdKacdsfKtoh#(~{uTZ1)Bo;PWL%=ouk`Ed{7Qen&aaFE z)cKY1fjYl3Zcyh}#uMuN$~Z%vUm1U>^Naga-&djD`9*u@7jm3m$aj9xuk#B$zV`x7 z-+=+Y@57*%@5W>trq*YCrnb+xO_h`JoGL%#Jhk79|5Q8~7pgcjUR3dOf2v;8`)&;F zeK!U;K%s|Z_Y3Hbbi6J^9%l+ zU)aU@g}t0#)H}au@BBiJ^9%XTFZy+Ufyejg!09`6;P?GH^zvOh^tB!yY!5%mfj8yD zr~SgSc;H{0*hT!P5Z!(q0~rBR|NOH~N)N@W?Ybfx9-^=H@L+rRQ4YK*A3p6Dp2Y+I;>0fE$6o41z53E# z9*`qH$d@eZL_@_-!qLB71vuY7_>p1~>q;MXqbrM)r^Q|mK6Q`=|Urpn29PL-c= zp4xB5e=44g3ssyMFRJ*tKUFX4wHNKR7jm>0^0gQJYA^6;FK}uv@VD*d{)N8IJ9uzD z!jJP5-kiVi>AZ$#=R5qn4qzA82khm#LA~oC?OhL%<9djE*F*YsJp_;IAvj$R!S8yA zy<88`*LrxcJ^UyK-jolY_6yJAfq!vg7x7~+^`c&VX)h1RkssvC8~w^Bc;p$J@(+IP z!hQFdi-*Q-0~bWbVdB|^L*vCk3nJq)F?QP{2*W6=vO|$BhTQJfADLUJV$lhzw#W?ao*+m zq~m%?hJQsCb2lBksaed(a)OCY;*F)O79wNu}5c#f$ z^y_*E9@j%~x*mex^$@*W5A)nu>+?KW+vhp6%9)e*n99#{Y3(=9s})b4V=K-)-&XwG zpQ;!2>PvfhK#u$%U*70fKEWf;;FN#xYZvr#Jw#vU9XvQ6;m3IjZ_Z!%bY8==^Bw+O z2e6Cl1NL&=px*U__O3I?as5HQ>k|FCUV+DT44kfS;CJ0aFV{o#wH_X94?oI*H|4{p z{lc?&;9s2BMf})Hy{K1T+RFoSkEn#hLM$il6&a^`c&VX)h1RkssvC8~w^B zc;p$J@(+IPf?m!q^wo~=pnc&-yThB~0X`ik@a*`3f5#PealBzK$07BOPue?fk>hwq zzT=#J9sl5QUVyXCm&ETpLNDhR`dSYUwuc|(z?<^n(|+MuJn%10>>_^brC!vlFYV<4 zIr4*id81$X1dlv}Q~trPUASj-e&so&+A+^3)xLRdsdmrvOdSt-&Z*-h&p&niul-}yzq&M)vdFTm-10l)JIy_{cpZmjiro~-TjoLS}M z`LoK;b7}22&#M(ro?|P{Jl|IQ+@Go!_0BKaJHL?Q{6fC-i+-J7;BkI|)AZ@KUGJWsvn zVcL66MvmuaTzJ=eaMoo_l25bHA({?wys-eYE|ipHlH~ ze=Sb#wZ+eUw|Y^pzO5<&A#j6Fl+^PWcDFcHy4U`IT{xYR8O+RQqO}q}n~> zCv`kzT&0eajJMSBlW~|jt};GT#~b&jjzj7lpR{+}BFFKJe8)NcI{v}qya1>31^mt< z^m2Y>oT}Dm{HnIkxK@>u@vbUA<6yPljE_}388@pqGoDuQbAPH{)H}au@BBiJ^9%XT zFZy+Ufyem;PUjc+onPqX{)N7-lknjB2|uo@@aB38pRU93?D`D>_^b zrC!vlFYV<4Ir4*id81$X1dlv}Q~trPUATk((M#LJ^;ebuUq`Fld27Zd@%A-0m%C}p zdG4xjzvsE7zAK*Rnfl&%o^$FugC=cW3dd7h){JLh@6s_&n3zv;W^ z)camK?R`fbIlixseBWKCU*BT~kMFdD)A!rK@4N2k^?&1g@95>XY0%g2p1_0OLxCT^ zlLBvkKLtMht_nQ+y%qTPJ1p46@3UYpzuQ8+-*ch8-+4if-+w{A--V&yBOf0UuP*2f z@c11WaQb~2@NYM1XiVzvE%)sIH-3*M;|6tprQcoWSNh|1ex;vY=hvLPXPkKb*tl&* zPo!U8=U4jsb$(?Wpw6$157ha^{igGadgmAIonOdtej(raMZeB3@HoG~>HGq}^9#M4 zUl}K<^%*~@?K7@Y_3IKSY{`30ZOFL-u-!N2nhyEwnFm-CBy z=NIjrU&wKOA>a8$zs@i4IKRN@`~tu83%#6Q=xaSZ*dBhA18>TQPy2;u@xZ@0v5WYz zmwHjJzO5<&A#j6Fl+^PWcDFcFBFb+AH_LTA%x4ZJ+yQm6Q8vm7n`;?Kk(| ziYNEwiZl1?il6&U^`c&VX)h1RkssvC8~w^Bc;p$J@(+IPf?nDy&n>k+&oi}so^z_4 zJpWYrc`mB`=6R{&$#Yc2ndhsDpZiVqqF#H^UV9-&dm&$Y(XaLbkM;tm_5y#~UVdu^ zeVupk;CzH1=PA57f8o=44bRSZ_;($^F0K#Q%XNc#*F)O79wNu}5c#f$^y_*E9@j%~ zx*mex^$>fx9-^=H@L+rRQ4YK*A3p6Dp2Y+I;>0fE$6o41z53E#9*`qH$d@5UwhH7_5zRg0;l!@f7@Q}U+C++g9qm${5VhH&G`$T&TDvf zzQe!k0CsVGz+SE!)Vm(i-t`bUu7}8XJ)~dPL-4pBg46X7{H}-C%k>a_t%nEO!;f;{ zP5JO?zwj&`_!lR35kK})FY48o_VR!n`9Z$C(XV`hN1nkc|KQgy+}kd?XIOlFa&Nhh z-sO>DG4ZJ0av%NLE5qXT!+XnpbkEwuWQ|_a!=bqR0-2W!dG6{sAM-rcah~Qmt>gU7^IOMx zo#(oa^F7ad9oK<82XaXm!7>mmKR9)id95S*@u;CDSlFW197 zU)B0Nch&ZJ9;?rqhJdiABfJRnDYkS}laE1%$z zXK>0t__YgqxgMgg^9~-IkMQF>g*WFfd^)e;+4&Ctt^?S`^#OaiZcy)fLVMR4>_^brC!vlFYV<4 zIr4*id81$X1dlv}Q~trPUAPByer0^1+A-q>)xH@|sCLgdLmdwpf2iXm;}UiJWW1t| ztBhmR@y0!%ul-}yzq&M)vdzrgAI0>ASMy_{d%+gi_ksO`BYRSx&3 z%I99yez|WI5BIR*H&oL|Uye$lV<3p~y*a5}%h@BBh9=NI~FM|jY_@T1+~&G7)A zjuUux{J_8C3cEPou$SYIddDa29k3jjd^9a41U+8N+JlGz7 zlml zcn$}r=X36DJ-4G*>pWlUxxcnO_u9(gzFYa+gWE6n31^mt<^m2Y>Jg3%YoTs+W_)nFS zaiJ>_^brC!vlFYV<4Ir4*id81$X z1dlv}Q~trPUGhG<{`Z-(_s*1Cchk}SuXO9b)qnG5cH=I>VMDA+GA|YS?8>-w^tqzlwbeMSzXUP zvQa7DI^wLZ-LKxDln>tPtSU!YePn7a; zgU;?c=b3d&`Rm7@-L=;?P5J)Y&+fW&rFCP*C4+0fl?erEI^H?U%CsQnp{p_Dk7*Dcdh)`=xBZKl{zlczWL{T@#<&B`8my zFs1962b%KZBd2s-wV)~gdBZ7PvyW-YQ`ef(b>wH7@(UlH(zVt-JD1$5OxP+h=z@ zGqx#Tv-Fg%)$ZD%)Svc|DP6-p*OZU?*p#l}Z%-)Wr(L!Uw)3}?l}XvYD2suz*eHvc zvbs=KN6P9>SxzX+6=gZ3EVq=~oLg?!Q-0y?^Q&Fj<(Oxr^DXTkWIiW09l;x1J z+){3H-Y(y;!PKt(j+s!#=XM{R+VzA#%c_2Zq!m-;WhbAH!F zr*BuwyI;3$Dbr@9pKViryJ+>MjLh#(+`81$*OXhjN*N5_+N`UL|906nVD`6^!Glc7 z_C*;yV6Y4}+kly}x=>a}%IZ$J%?ahVmy9hq56T_F^^6oi47vJ5KAIb5#%U0t` z{S`U(F1@QMPt7s;{hhZg^^{+JrYX~AwJ&T{>iO+HFE?dm{{G-7_4IYjqfNQZNxN(t zF#B7|%A{;xl*M2fY_#$M=!P=4Ve8c zWo1&fFUn%D3^v<xTW3P!jZd&TG z*V?BJsO4uDZc@s$nfc7d^|!-TZOX{pVgHRvJ$(wsX2HpKF<^PAhHxJZ$=>Pu};U;b( zTguigdv#9d&^ecxM6?l7C~dT%MMNpv>AJ4dS(1HA6e22Xmg-!UwNzwZvc!$D6K-3Q z-#ljKd7by|cl&-npZmVKmoNXEhiR_YJm>YAnfJWkGw*rJCakhxX@I2-mS$LWfmKIX zb%*5>SiXYgLs-6rlRi)K)%$1dqPZa!-AvYQ(?9h6Jv(LX+TFvLaBJ7BtyvTJG8gMT z7KbrpS@*1+KP8MUJ&wuRx+BAwGw6t{op^8zK&z{KGrJn{~F(YFed>HtMOEdP{1%d00%Gmj51b(Sc#y-43 z;L|!~Y~M5Y^KCN8%7ahzTUa(>l?6)!EN!qf!>S9cI>M?uET6#g6)YdZ@+~Z%!-@s0 z7{Q7ioQ&zHYu)|(>~MYj=DM^U(=70S8`E~9DZxLt-I}%+H3>ZK?zEkHM~KV4HEBEl z(7-E}r0o-*huB@YB5ilQC-9Ju()Q-^!0-Q%wqr*IPH&O11!Dp~+$3WsUlX`V^NjuT zvcP+qj4f*z>?h-rWaXh=`YkM*u*!m^0hTscnqk!iRvls09hOgE`3jZ~;iPZj;lmF0 zZS3bP|0nZP$4&3Ce%zxS-o9I4+TqN5!#tLDIO3GRw8QSL1Je#~Y!#SxIILS>+ToLv z0@Dt!sT*w44(C(`rX4ogFWghm4qtySFzs;QUE#iib~tlfxHq94w(A-0S!joMwmi&h zrX3FZDKPD@+k$pJopyNh;BZewJN#Ss>B@r-^;=jrVU-0-11xQ@G{dS3tUAJ~J1n2T z@)ax}!tyOFpTmj;tQf(H9h{75l4-;5*AITC4Ug|0m^S=WRbbk1@$G?W!=K(6m^QrV z`oOf|_GbpB4c}4_m^M6fWr#0r_{q_MX~Q3E7??KPKONczZTPdb;U4PeZB=bpd8n6u z3(F>~vS4X|r45#5SapF_M_6@-DweL7R)6SBUrJ66;oKThSdgOwGCKp z23A{w)y818Jy>lLR$GPDhGDgBSZy9wUx3v|VD%%P|39EDp))zw(U$(*uRHRy=Aycu zlCJBl_y2$RTuAdk>Z17}ta&4>`6R4)Can1;47SeGRPp9a#54u~38*&u%SS3LW|5C6(%lJW!d zA{amXE1n_i`8FE#+#A;Oa9GdDVLd;G^;{j+^LALz;bA?WhxObZ*7JN=&-r0J|A)0M z0MqxiKE;?I)_Mwgw9W!+{RP&#jJNYITC3W0-*S8PePN!Q-M-v@HZAaV8=LKHz zW!COh5_tJLS=-_5FyH?A#jL$xMBuqgvbO0LVNQPLBU!uqDS`XuvUbU`FmInZFKh2> z9(dNCmHBcvy{0ms-u0@=eEznVR_5*eFupQxf8lwR`EpkctIX?pt#@T!=T1jf=Jhu( zsm#}lvL5_0-20>9`QhPN0eQxpADG{6dRt&@w)r41W$n^7JWoKw$M*zA+hHxkvjsFC zzA!L#nbJL!g`ZUxevk(IqdfRczr~-jiJw&#{+9;gB5lM=nu#NIVJ&r&A2PPd^pT$1 zt;^WuMS;KiDPz|xKFgl?W7mRWn(hJp9l!P%dErqA>29$CBLnSp1w$l5Os z2|Uc*TV2#N@U@-YJ>5=$AMH__e!<|{{Qb_ZwX<HD{YGGPcB((h=RtqX-hrvt zt%ZT9uhQ{@^5Y-b!EdsUKUFS%mLB{soy0}@6))~1eu))F@+gk5;s`5_u;K_Sjw#SvBw#SvB<;ba`EcCN^`&nFvKqWZSE&0`+v7>g5eYJneRlh)w`U^VMkI=9FMZMJTsISuTgYx4a z*}-qJk3Ur|ewH5mFP+3i`V}wY_)Dxfl1Fib6-QWcgcV0vafB5|SaF0EM_6%$6-QWc zgcV0vafB5|SaF0EM_6%Gy84~sNV?((D~_<@2rG`T;s`5_u;K_Sj94vhYb<_4x-r#%*!`YIhiC_ny@9sDNy_*3QLXX(NJ(n(yT zU-2T2zr>0oc@#%jafB5|SaF0EM_6%$6-QWcgcV0vafB5|SaF0EM_6%$6-QWcgcV1n z;|Jx(Kd|BmD~_<@2rG`T;s`5_u;K_SjkEZNI?i{H#M@^cR-~re22>2d2JC#}CSne`E*0 z$v*y6x%gRnh?jH{FX<;=Q4Qi=U+j|4S!vk$(Cb^&*bH#EPThj(=dq z5vE-H2`i4U;s`5_u;K_Sjw#SvBzgm^SWx_ibHY z=v|sIW11A3BV8Z4q-Vw~*|pgF`4HEx#=G>RUHTW3GiHFxzmv<~Xnw|g(i?Fl#niSY&26Js0nvHKVRBGT%6zSGLWX^uQuB$mxH- zYt}SwQDi#1dUflUH9h{)%6#bRyWq5}dHw!YroZz;`!lj;`zu-m@PtBO_j}(}P9DjOY#x!zg81#31ai5I2Zb^aZ;CwaBW=#8+3d|7a ztJ%9|%=Fa-<_%}xY?v{pt}ih2ov+?}KW(}-E;NS}y0|=(HuVoHG}kq+w$IK@oBhr# zG@H7yXp`I1<~?`L!E3Hwbtk3GQGYHp-S@1vA6$|)&+pR8Ory1m z)%vbpH|#aUk7@V1-~NyZJZ-0Hd)Tvq58b@lmTfxJ=lN=Fl}+szc#n^&Y(>dX-=~r+ zo3vrsgk=+!O*m=u^P{Tl=@Y}8XP)DG8iu*eGo7mJnn{7%xcyQ0?-b@O1;*_ezAW(T zg;n;UbtAo=B+Djc$tEnDux!Ffn|H0Qv}fN;~5Iz>kk}dn0cOeDsJ)d*nHR8}zHRg@u7Dj&=KTUmNB1Cs`WM zCJnGOz|sIq11t@&G{DjTCpEm+ywbK?8J?4z(6rJH8yooZo!qms%>#e1O{HCbNqF9J z#vdzfW{benx2Uu~mIwbQSvDz4HeuO>WfM-?+~<@E+w0CS_ipR%2j|WVJn4`M+xyDE zH?^#=s|N*sZ1)N~x>?|U4J+(pFAnqmOtNfJmTbbZ3Ckv&w7F+R#(we5alQ?FF*aj+ zUL1IzGc$JDwt*X;p0USY+STXzabU)txKZE_2W0G`k;nS&Q^uy8*C-rYU$&FD%2KhR^b8WT# z!v}%KUggHUzJq=Gs!OVEyB7o7ifX&sp6b(QUr=pNyy;Y5_aw_EWyvNio3L!cNt?}D zy1AwEC(l}Y9a?RVJ34T^Zq@dHa{^yIpxUmR9r)6bZrt7^#OwSrcP$tm`1|T=yY>5l zXJ1imuRlG+eVD7`o8JXS=fzdWdi_b32DC{7EDf+Uz|sIq11t@&G{ApL1NBY%?dOb6 z@~BV2tKGAm*X|zf)2(~{Gw_AL7vEK3x7q#-pMJm-6?T_%16Qx8us?nixXH&AcJRd` ze4aDDudrty6s`rkZ&YdT|0?k3o4M!k^TM?tInE?mdZ?H5z|sRt4=g>f^uW>sOAjnP za8i%PZTyfN_mZ5dg;Lr z(gRBmEIqLFz|sRt4=g>f^uS3y$vH-n)!*??lGS%ePmYI4PUg||g8a!bGs($3eecZJ z+t!D9$bODL&W3AZ8@FF>-+0};cUs1NUKOsP(gQ0_RAsRx}Rj(r0%i_ z%O)(FaMI@aZcXIXYeRf@AMf@ve;s(cbF=osHlaP-e`?m|Mh6~nV%CnD9QexiS^JoK z-i6I1%O>fv3Ckudn{d)*{dHOU$Q}cI+v~DPxm}PBJaMaXd+VCOm$>z;#e>2)zvs^7 zwrF+Wq9$%lZEzUp?`~Xf2Y(Xyx}D1HLqo%uU$0@gz5K(#+iy{BKRM|%U)Ba2mfKGs zKh4)A$4BvOmL6DoVCjLS2bLaKdf=p<9fxJ?_A|qLZ*|{{eYCziAKJCCXO79( zzw`)v_#y84ensF#ZlB&M_XmElamKFC1^#Ap*Jfq~p1n40=Vk(5?Dpx6YZv&(*VA^- zFG5)(o=Mx?s{$YKMB1LeP2i{Ir|s-ZLpwZZZrV<+7x=D+(zeSv=Xk#*S^BA$^uy8* zOFu0Au=K;y4@*BR{jl`I(ho~NEdB7$^>^I7m-p>Xu3i;oCwcDX>O1a-o}Sx2p0;nE z7xa^YTsK9%Db_Ooz}yYl6Xozf}r$scCy77N2Q?y>b5JGOJ+eYeZn)!&41?8gJL zHv91Zc}$ZY>Lop}^uW>sOAjnPu=K#v14|E_)T6N!KP1PcBr6ZU)pddVV$#(gNl&uI zH`0^sD#^(_6L!tmiFL;N_WbzAm7cMmWaX*8yU2(q78K@r+L%JqcF$mEwvr!j32gj`*83B{%N&aVElHCd$vG2{v6&QFn(UQ zX<*`2vEHrox;(_I|5t&D*Zc3+rl0yoVDh(nE--eUTND`kz2^s}+yfs7jGpV29dw>WKQy*|#ob6Bxi`c&FB&W$roPbxMWypXm> z-Z(DIyAsTGfwCA|o_A$^Jtpu$xwO5^1jhc$8wDQe-Y?krnQ?wx(r+2l^jlcJh4ouF z`CIAvI$My}_VV2Y=Kd$s_LLXKnMNxM%(92mwt9=S>HSlIInL?na&X#A*|E?Z<4MPc44_W z+qL=eZ>R06ca)nwhZdW?-Tb8EW##7O9>u2o`LuoT9LLW7tqX{N_m0N1Pi4*YM~cj3SC@CM%9^|96`7A*T-uGv8nuUQ zdb{WFE=KrVtTCVT?ptPT^B>AXo^@&4_JhEUKS|r3O9D52Gi^_w61ezTr}Ol{^PINl zng_14AZ;gn8p>+t{QU84VO>mR5l58;-xbS(RTiwWV3h@{ELdg1$+A>O#gzKCX7Mkasw$Aru&1&~det>HmhrX6IBi}19Z#&;!?|i#>L4kSE)$7|9<)+Qm z1*XsPv~77xxp{I_f%*28w0(U-xfwN}z#Q~W+J16Zxp~+1@m|hXBb=``99Uq!{yJ@2 zzgccd&nYmEu6MuvxZE5zvB2Ew=9%aIrQE!Ems>AzKL2)YxjFxp0yCzeoB#Y&Zi?y_ znjVcZcCBk~$!jrnobC3Z^?zWD?>m31{U`hBi{}-aU7fa9dyX^BTsvIyg`4+oKhAtQ zpx893ld*GNC^H8a7n}FC$k^)Z%gjyR7nz1TWb7lu%FMI}i_FShGIm1eGV}e2B6IPd zGWMFnGV_dElN!Bu#`f90%ryPnT_g6**weQ!GdsGqn{I9n(0}VPQ*c2m^Qz-L{#a)A zc54$e9e?cjV)vf^)BCw{w<$B9zUk%_?zd$-m6?}j6q+rZ&BCV6{<&^^bMuV{T9lby zoeIsu-Q8T;mYE-RDKrnccbX<2Q)U`}S74gC{&@RaFMpHj^eQNJe*8-p8o)K-@B-p>uJtNwEK;Qw#xic&747}^H?m5plVZ2SU?4wimVcCaeAC`SM zX@B53<+jfj;rYYBapm@i+2NVehL@JxqfQO{{*5lZW#9+yDz{hG54`EZa=Y`ounsl$ z8JA~+kbdi1<#z23fp`79++No%@Pr@BZT)QI&BoiuUJC0|6A~;v=#(BZyNjg?(%4xjxokS60|@HwV69QiWYPH}KUnD%`mufk)1*u#fK<`tQqb z4s-6gWBhoVWZ9%F*@R^imQ6Tmv+Jz!_S@m%K5OMev*#Xffu{89bQ--cvZ(Ld+V0vzP+W}y63$e0>65o8y_wRyuUkx zqQ$J3zOy@z;@Q9lZBb>XxoZ%0e`sB$-F#i(PHIzMK=UzfA8EfELoB{?dq-a$6L`k{6?X3f1OH+B3fuUl@EmMr-3n`u54__S zTWa&Yt^uW>sOAjnPu=K#v z14|DqJ#bQw`XGKtj(bT~9)7F-LVhvn8Yf9lvicP1WvQS4=4{P0Cg;!^UePUlYZgOl=S7{<%%`T6$A^wrR@<-Zm3cn=Vs{Qe)Z=k^fZevzsBbdgzgjq}5E7n#y`i%b`{e*OOU7n!f!ec7VR zs%^hr%S@@eU%Sh#3x9fanR&N!v8m(yHr&loZ*li}Jw{jCruUYaRu>eTHY3Gj9cTLz3Vu0+NdH^<@OXE?s!2_ zk-6OM3re{>1J<-MPq;l)d$?HacW*1x#qA>+?(Fbvg#Br49e3ZWl__`WZ#n+@?Lu?5 z+k>>B`|UxK3(XaKSKA_I^YosD=BfSNUL(hExVict-M*$b9l!dKdp70bezMDd$$alnjwmq3wZr`$C^Hv~D=^odUu}<{TxRZa z_W}*GZa>)QGBf+(0@Hkg+p~RSnK@upf%(|Q=;J13rsu|mrs(QwJL=Pm%-SY}<_p*U zN6o#+)N58~9(J+5@%q2+YxI$4wym~%ZXMd~n2oCKPisRvKm6+|d&X;lZ+O4T_PD3a z_q!zPx3n?+7Eb=Qt=s>(ce^lt-Y~n$F8d&iv3ES;&L6uW@aE6C{pte(_xN*_tvV#| zzF$^Z-$lRrZnz7y5DFiEdT)^8Es5JG(XIg%|krY&&;W zRr|o7wQ+k^m!9v_-*Wda7aS3IfUUA0Ja(Q>AM55V*R>7&M|WSdV9{8g{-e9E>EAW* zwmsZ_Bj91-Sgjh3SJ@x;3!H3| zN!D+%so%oM->MB`KiM9VoXn$sNB(4+Npdoe`X>1YHLSJ^V;^7dxQDwok&e#4b)C|0 z(X8LX`mL@bT$j1u*ERaiVeWa$)NsAtqe+peoEG?*CtI1e(*rXO?{|CPPCM47fAd&j zKL3!j3iEa}Zg07Nm0z29#f{rA&%j@B?H1TD zz&v~J(eH@mlZR*ZoEr?2e!+;^{5PK$7(3gI4~+fFO9NBxy{>KZTl9395*VEa zI6siiv-*9VA7J?b=2^GWc?PchJR6rCo|(%&&(c*c&)B7hXYbOj%bu z>2`rB_Y}7VK_2vM;MPQ7biVD@FJSb);np}{>czeYm@!}JTnm(+YlQ4@?T~%0DJqw1 zjr4F0l1{Eo($6(Z^&(yMCBOWD9r*|Q@*CyKpXiaF(JB9C{*G@dJz<`~xdqu;K+PUa;Z?D_*eT1uI^#;sq;Su;K+PUa;Z? zD_*eT1uI@kCtk`=ykNx(R=i-v3s$^f#S2!v;AFhSYO9K=Vn@1S2P<~4Vh1aBuwn-* zcCccnbhXvr`&t-t6g&K**ujb&oQ#*&3jZ6{vQ-z>J^xwzH-2CH{>Rt8nL}#L`k%FT zNH%G=|4sX9evQ46JZI2%k;IJQJWo)%m~`?KotCkDM+rXj^o*Tx<6fS39q!J6Z4r2n zvorR=CCz+#$MfBJ=0gIXFg{~<-Z}7k_s+t~*Y@;z-k#!qJ0tMqJ2UpAiv#mLqchWi z*DR?`pY=*@{!8AgwbRO-oi6)r-5J6v_td)X9IdEl$foWr^r&+ucTT(XAHPL5UoX-- zl!ZEyzuD)3v2(CHr;EB{|J2!mDfg8P_x0)MY1l3>I-8vx82#5=9+-NSO%6ev^ItsdDkN^x%K#BrejgcoD~6V#Sd>iX*Hz!ipoTIKqk}tT@7oBdj>WiX*Hz z!ipoTIKqk}tT@7oBdj>Wilfr;gYx4aSaF0EM_6%$6-QWcgcV0vafB5|SaF0EM_6%$ z6-QWcgcV2l=W!g~;85SjNZ;kAww}pZ6zDmar%8!3!2fxWa{#3d6S$c?WiX*Hz!ipoTIKqk}tT@7o zBdj>WiX*Hz!ipoTI4T`KC_nyz6-QWcgcV0vafB5|SaF0EM_6%$6-QWcgcV0vafB5| zSaF1taXjfT_l=?0?t3`)Jy%2`YIhiC_ny@9sDNy_*3QL zXX(NJ(n(yTU-2T2zr>0oc@#%jarA8<#t~K=VZ{+v9AU)~Rvcl)5mp>w#SvBWiX*Hz!ipoTIKqk}tT@7oBdj>WiX*Hz!ipoTIKn@V zW2>!;{n$?Wswr-NfxAwTf8&C{*jcl*l~2e1<3j^eZuiE4(X-Q!??VCt)M{Gj~!M|SX=?Bh?Bi=U+j z|4S!vk$(Cb^&*bH#EPThj(=dq5mp>w#SvBw#SvBez=|WRIKqk}tT@7oBdj>WiX*Hz!ipoTIKqk}tT@7oBdj>WKaZpC z??~7E5&3oBgdN>aVPE%Il&kwM^yvN$ow~n6zwYm-m+tSVuhQ{@^5Y-b!EdsUKUFS% zmLB3Ioy1G}iI?g{y6%t2ulpwK=za?Oy3e9q-G8A+_hsnR{TljpA4k1(e@A_ljvtgC z|Hux0lYRWDa`ChD;D6~PF49k5(|3)3i4{l19sj63;5S%tgcV0vafB5|SaF0EM_6%$ z6-QWcgcV0vafB5|SaF0EM_6%Gy6*23N75BXSaF0EM_6%$6-QWcgcV0vafB5|SaF0E zM_6%$6-QWcgcV1aZyD=d`424GY$Dby&~UVLexe^;{j+b9GqH)#09T z4GY$Db*2BlCi3^KiSVv2J|tee!wVBH-tC2n7w`PS#EW-ZjkT-KhXhczteWDQIDS;JDjNLPKyFF#;M{=vTdM!E7QdgNzx z%KzwBT&NfC>Z-oHs|(`?-qnTi5AW*2_>FgUVf@Lvx-fp`U0s-X@vbgRym(g^CSJU& zt90JgRes*pg|WlCx-j;6R~M#S-qnTC!@IgLI(b(YCSJU&3sW!Nt%j+u((!}x;~&|< zZ?ca+RW5#(9{ewz#6|jvm+D2j>Pvq40Xy;!_T@Lql|RuVKciFrN5A4iz1Tmj`f9%u ze$YNB{GjQ~oDjipwuu@3;@*+Nb%9m~^hi3%A_a-}~_V2gZ)lVWq48@;<)W z39R-5t6jlrZ?M`Sto8}3-NI_mu-duOf6aI8)qg2VbyUCpeY^_S<^PoNN@qc6d?uzE zw_%Ovu*P{<<3FtH0?hcMvmF?h)DCrhA&;&*%CEB{u%k02u&=WwC|74tphss@pi^g7 zpkHTM&?f&|&m_?qGODBc-S6|d(C_|J=5=bHv|F7yLwnX)G_-S_QA7LJ*){YFooPdV z(OEb2JDq_;|I*nwnun|3=`0=c>x>=j=AFdqgms@N)^m?9c1zngo(}8j zb6TbC(Kj^p`TKTF+mkNY-SZFUrR|TiclCVuJ!yN(j=Okfzu)4g8hakGf5w)-60XJL z&T{L3hy3+*`RCW`mMg3BdD^;n1oT_x8?rg{CimW7ENjk-)p-rat*_2&TetIsyyi!n zPsrCLIZtRi{U3j)3H^H41J-*Su-*fL^&XIC_e|!W{a(^9y)&ZsxhOaJK9}AHAzkl- zzC9Eqb?!8*bEjdQI}In#oz_{hq$kg7)w!&sn_u}n@LxLjRcDx^L1&o5 zI>Q_;Ftz8R>s(gSbuKHcb6H`X%L?mUR#@k3@?2J(15dinWrcMPJgjrz zVVwgHC(nUTp501&`+LuV=C?YdIC;LS&QGRXou3Tr{A5_?C&M~F8P@s9u+C40ljkSv zTv^g}W-P2Tx8Z%x{P#LDJb9k2&QC_C&Pa!KMmnrB(&6M8={j$jbe*>h>%3)H=PkoJ zZyDBk%dpN{hIQUDoIG!t{f9bRQs-onN9Sb1Iwup>IhnA|$%J)ICaiNZVV#o+>zqtj z=VZbr774lV@h?++fmmZZNEK zgJGQ;4C~xrSmy@AIyV^BxxsMq++gkfBc1&%S{GyAi`L8752JN7_Q_~{jr}uPcVl0T z*5lZ3qjfs=;b{Gi=P+8=W8aR_+0Uc=?DLTw_W#H}`+`(1`-P-O`~A?b{eH0a`zc-P zV&vC)8FsXehJCHCQLfhA(4+M@bZVUr{aU}HURu|qzDmar%8!3!2fxWa{#3d6S$gol zbP^Zo*Pb!OOZ$$++Rp$}FI~T=udZL(&p;mSXMpjWu3y^EK)Uub zz}n9MYd-_5@5RIVUOcSt#l!kuJiPp!@V$6g-;0O!y?9vPi-+~Scv# z^}Tpl-;0O!y?9vPi-+~Scv#^}Tpl--}lsePdnUizi**i-+~Scv#^}Tpl-;0O!y?9vPi-+~Scv#s>JTe|tVNzvZ1Te*0UV{i`z!DOYE*!8*eb))|Jd z&M<^^h9Rso3}KyN2s(e?=d!}d zb6Itc9O*i%5Y{=Ou+9;Mb&e>UJV#V#8 zI`a@to_VNmHAUu@zH1NbyY{fYYY*$Y_OQNd59_=3 zFyDE&UJsSZ{WsTX6;=Y2Ht0ftZg$p z#NydKvUbBW1J7=ewO}YuvEbxM8hv!&>8p zwZ;u=jT_b)x0tnlSZn=a?VZzFKj~WQhqcxZYpoyFT0g9{epqY$u-5uv&HrJ||6$Gl zVa@+x&HrJ||6$GlVa@+x&HrJ2p9R+USzvvi1=jo@*8CsVw?BNIfAV)mu&Mb!toc8z z`9G}rKdkvbtoc8z`9G}rKdkw`Pml9|_-~zIPP*p*u;%};=Krwf|FGu&u;%};=Krwf z|FGu&u;%};=Krwf|FGu&u;%};=Krwf|FGu&u;%};=Krwf|FGu&u;%};=Krwf|FGu& zu;%};=Krwf|FGu&u;%};=Krwf|DNObDPYb2Va@+x&HrJ||6$GlVa@+x&HrJ||6$Gl zVa@+x&HrJ||6$GlVa@+x&HrJ||6$GlVa@+x&HrJ||6$GlVa@+x&HrJoqrqB7gSCzZ zYaI>NIvT9?I9O|Hu-4RIt*OCUQ-igp25U_X)|wiuH8ogkYOvPSV6CaaT9bttfBxOS zw#+qUJdJcHLT~=u%1`LdR`6dc{Qx()v%sd!+Kr~>v=V-=hd*DSHpT<4eNO|tmoCR zo>wdVzvcZqtp`yr;>CIpto0yR>p`&AgJ9ytdJwGjAXw``u-1cMtp~xxi*+KHc(Hy2 z6ED`4VB#hF#EW$((uo)AQ!w$;`_#ls`iYm`%O?H5;XP&QOT2Wx3h`onoOI%)b5w{I z=W>uvyf~KzCSIJ&0TVCIv4M#f=W@Wri}i7sc(FbX6ECF`FXbm*vO~ONpLnTU;w3%A zOFD^*^b;@Di}e47^BnM-_A|h&o2$Os&p^8NGr-!<0Bb)3to;nI_A|iR&j4#b1FZcF zu=X>++Rp%MKLf1&46ybyz}n9MYd-_5{R~Q1ytJQzbnRz=wVwgjeg;_k8DQ;afVH0i z)_w+9`x#*EXMnYz0oHy7So;}Z?Pq|sp8?i>23Y%rl+J!3<=6Y;*wOpr*k|7kc_^3l zRv10(^MTRH{vR0qthd6{i}hBR`YIhiC_ny@9sDNy_*3QLXX(NJ(n-9eU;Bk9i*#MT z$j?3;(y_z-92ooT+kq*U^-vf+?DK)q$^IW0{j96P)Qk02nEEOmKPW%`ksbUd`}kAk z;%Dh0Uec-kLfF?HSNI)w*8Lwo805%JHBY~R72S6xzV+r1drR#dxh9iHmbwO3Yl z*zXE!zbmZ$uCVsI!rJc&YriY3{jRX~yTaP<3TwYBto^RA_PfH`?+R)1lE36ukDly+w0EZKEL+6lCJ%(u=cyc z+V2W$zbmZ$uCVsI!rJc&YriY3{jRX~yTaP<3TwYBtbOUQ_P4{@-|q9fcZxUN{2X5w z?QbVt``cmdX@|9^9X4@KJN){RO1pKp(caFFb1LoViv#a9z0zKNXW&&=R@xEw2Y!59 zrG4S1z(4TUZ!ad)l%8x%*Dm=@ZZN_O+*-bnR(}wWl2}hv zZKsF#gGm41e4mK?dM60hJ3+AC34--bkY_h9<((k-pYd%V?C6~!IQcCYy%R*b-U)*B zP7thjf?%z~!di!gS$BBg`0yRfwDZ-JHD`GJGw-glXI&9^?%XO{@6f z_*@tRc@E$1{=ht+KWRo_p4%&(=lROdbAH)jJyiB@cHfRsxl3DB=k+{Q;=a!nb&hf0 zBV!#I{c~)!eYZG_38WX?9+>=FZFiQ>gPmsQ2gZKa*8*!D7CY!!e|q>nDLS{B92or< z%?(VwPJ1jc^;J54P=5R)JNWI9eL{ZxsdDkN^x%K#Brejgby&1%9TwI)EUa}{SnIH` z)?s0-!@^pJg|!X~YaJHWIxMVpSXk?@u-0K=t;51vhlRBc3u_$~);g@xSr=1&*2`e6 z!@^pJg|!X~YaJHWIxMVpSXk?@u-0K=t;51vhlRBc3u_$~);cV#by!&Iu&~x)VXec$ zT8D+T4hw4?7S=i}taVse>#(raVPV!QS%-zS4hw4?7S=i}taVse>#(raVPUPq!di!g zwGOLv#Y^k3q-z}();cV#by!&Iu&~x)VXec$)QfdkSnIH`)?s0-!@^pJg|!X~YaJHW zIxMVpSXk?@u-0K=t;53f(^FQYy&n4S(=!6oudf~#nEw84zrc(GpLGb#_)uILm~rEf z;=qh2N@tu=e#Rf!VO)}Z#w(S}I3_)eZ=coAcx{Y(Zyp+$@i2Q{ZTfx>1SWr@PXc3S z`Yu`jTkIcvRA9;-c}`%h!{P_6!@^pJg|!X~YaJHWIxLKT8e9`>;y2mHpDGtWOAr2+ zPU0f{r|y`wh2J0UHDA4d*4{iga5uMJ-)%uVpT1|OtR42#VV-a8nzeVf41C$~S=+AX zp+0?CclVvyapBofk7KfS;9cRl(4Zr-_VxF|GoLoCv$oNGfsbyMwQefwf7{f3)A^dZ zfqS|8#3v^ipML+_89S_7;Lo1O*c)2~UNIwMySuK1AC9;*V@I44xZbFYoq2EIm-@JG z&F>a$p4KU2H@zqD7t>uB|f9bwoe|$%uUi@9g)_pzjaT{dq5#2iZ^p%@s?e>oauG&6p2k+L|r~mk; zti5q);OC0m`x>_fzWVU2ePwarmz-~Vz7Tlj_mz2Wvboz!9P_-}$nD9GzkSGkKUy~T zE~(0w_0r*0c@2Gzsmg0R|HP`i=5KqucT{6tZgJ1_RL2pHRrh`_k9<;jg3}OvwT=7E zwR~98&Ru7tZ#x}Sm2X$@jD3UuXEm*|*@prjx^0!6-!rs_@te4|x=m;^FRgcHE4>zY z$l6MK^c|sH!55DW?TtLob`0&1-xhBj+A218TN0SEP8b^6b6=-z=A>KpiJ zSC{Uq5B71n&egHO$$_g}-B-Vo^6BvWPJzjD*(0Sso!@poI50Nvd9=i*Q&w@ez|{Tw zZ{3*Z+A2JJp90Tl>-1n?G>_|1=+mjokOr+hQ^yxx4NTn|-X5N%!(BN`$=M{&RUHn@ z|90IU5Aux7)r$jDR^uT-1KJ9nZt3%&c}}0e)Me*YEqpq4e5G$->OS-3<~|)B*D)}8 zx<7n?Pv^G{Qh~8~_9OfIbjtdnYhdcW;G6w?I$X5(pFE>&s|Nz3`G^z4^DF#NuyuI$ zMIEnwB`|e={kFaQZ{Z!z4bPg$)3beezQk`I*)lvY!sg6Hfhp_V(}D)tYVp%ey&c+c z_kMwC+n0T?hfk-?+kt`U3v1up-KWz>D!T@z?<`!pn@^`t4Ll++eQmd=clGJ?!DIRa zrf+UgCop|>>HWL-JoM$K&I?Q*zpO`K`u>((0y8Fv87q{BF+{&*Y>`dI9F@gbBn^yF z(#F^&&5UWP3uB$?$QY=)Gd9X6jG6KkW2t<|7%Sg$eNn6#hx?ux{LlFO@CKo6FmBI3 zBQWFnw+jL@&NuilFysHyPXlvZSo>69t`}3s2j)8R+%AE+zT9(dD2waPk>7+i!1ZY2 z!GXC>)g2ky4A-yuQ$kzfy0*vS(8jpl)vO6^kL%#t-2-!d+@^nMt6Vo1%?)jMPvf3d zHVox9X`ZovUKYxF*nNX+@->0eTV!m(n85G!Z zVPUKz&u41`^V|OEFg9ZIgAJ{3pOp3F=)h>0xiT=?ZYgNv^Psu?nSrUxqU!@w$4}#W z5OpuUJ*4B4r>X+utMT0fAh6yC zftSbkL14WP0_%McSnq?t(!gFjG3m*7VSb5ukLFi>N9LMJ_g(LOjMtf9=^pdM<@9DsLPY2d}I13=+ygDr0e}DSnp54dVdPWhkKO-`+9$hbiF?Xt6b_XCY`o~Hnpq2#lO}2W$2+# z<>M8#kuD9e-f@HJJE}W9oddOzzOH}dEmH(2ku!FtCHR=M~=taRG8(&6#z3RAb# zyFImV%gMRog2L3Bm9spbzM@6yn~(1CJaD7^Q*Unkfah&{D|k)pZ`?4!={h^6>s4FlLlBCU}=D*0hR_> z8enOFrNO614RF+uqrMG7y62cbq=&kAj`lsray>^qo}*6BQNQO{ufO7?hJ>~pEDb(A zYJjBymIhcFU}=D*0d^X4F22&1bMf`;^5uf^QecH&Rcr?0M8rkHe=qL z(@*tW+C4KbJ#UETX7!8ajo4?n=Rdvj(A){PpW&G@588W#(pxLt2&%_rQg-7G*Pe8HOF=I<&yvXM-TIiop&m%XY5x#Q{tI&C)E^t zM$a=t3O%Fq&+A%vcJ*q#=z`{+sn<^H4^aACrQ-+X$3L=z-((+us$BdmJ@{WbiHr0r zUW^aF#EK(%6h~NbgcV0vafB5|SaF0EM_6%;={}AzzmFrVIKqk}tT@7oBdj>WiX*Hz zDjh#4KmLIgM_6%$6-QWcgcV0vafB7enC{~k^ZPi$iX*Hz!ipoTIKqk}oQPwM>gD=f zjp_@_53u|L%Wts!3Cqtg^@{zdhI+;RRik*3M{$h#)ladb{)>I}YsyuBM~}t|I$fZq+jt0?J9p=@bQh~kB@sCmwbDOdVdB z`Se{!H&5*|He9EiKT=%3Tuf8H#LiDCu6N{dZ6U>V5O)4faeaiHpHf^mVHcki*HhT} zDaCabc794RZotk@DaH-hm7n5z4ZCvk>8_l7epgQ3jw>f`-<6Xu*Oimk(JHB4DH`Q0^_(A#ckL=(# z*~gzM7e7l6{+CYTqV}fPx%OE~eD|6a=2yhMZ=*23qCKQqhxrxlWZhf+eS4t&9Q)~D z&$O!^hlcqT?QQguVLqL9xaH6=zoLEC+da&$Xt#U58`5ddZSNcI^V80Ey>_T)+JD<= zr+KDdjQC_=?z|_Ll@2`j^wgD;PR=zNv#j*^y@#ciEa{bdcDH4vXVp6+)$4{6a`v62 zr61K9k(zu^*W4a&E-h`n&4|>?3y#dS*=|{Bql3;!&FI=b*J$Xn(%Z)lOEqeAXm0C; z%SvZ|czUX!waJ~fa#`uPhNq<_-t7BAjmo9}CiK)Kbk-#F*Cgsylc;Y^!VfhG|I{S> zR+I2&O~TJL3IEq5;!=}{SB>K6+DtCVi9VQ1^ub)B59ShmFqi0qxkMk#CHi14(Fb#h zKA21N!Cayb<`R7{m*|7JL?6s0`d}{62Xl!&m`n6QpC0?5&mY^iw-ejEw;%h0FE{oP zuP62$uQT>3uRr!RU$58)eSMXl=!4!rvXkh8-k&Nr(FeW%rBi({886zHVh1P2TOap0 z4*T{H$7kP8;<)YGPaMyEyNctyZ*Ot@_w6uV7kvAS*9+fn<8{Qh=Xibb?L1z0eEW~r zBi}E$PPzVALw{T_;b8h>4gImQS6ljH4gK+($|LBHHT1^^KkH0?tf4=iKloVsV-5ZB z_7{$)Ki1G653Jvd{#ZkQ-0ib|^v4?dAf6S>~ zu0Q5fU)LXV@`LM-Ir+!+$DI7;`eRQ1bp0_WKfC^zlmA_R%qcD|Ub%REB#yKp#xCNR zi{mPB%*An)IOgKGN*r@>TqTaVIIa@MTpU-4V=j)X#4#7gRpOY7<0^5?#c`E5=Hj?Y z9CLA8^?r-vs`n@3>e()i^Upm!*T9Xdo4Po@y7#c$olo}4J>cT_X}vRYldeA@x8~!e zHMhKVMs8%^<8nP-URuMoH_id*n|bE?9IyNIP5KzuGWsTc&okHgc-{AZ`G4~8@8pB| z9lwXMhh3O5DGz20P&$1}`56ObhrTHLi~%Z_zAHV90n$ldmwv^OvPjpMLw@yT>}brv zzWP3YHRkZ|8Y}pn#vJTvY@uEnb0}Zw=u&?4$`19Aed?!jskijt59!2D(yw?WXS};)CgrrS!+!dbg!NmeL>RR3AZqETuoLT-1sFSgM%1wwn4SPV~)GqHm@WeUrJX z`bdg47W+;r(Kl0xzL`q&%~YaqrV@SA&pl(`OeOlJpR3A#qHp@SZS0$=MBhv$`X=`s z8gqPlY}-D6Z1dhu>l=@~ej;=qJ(jQ-`=th4mr9Uoxtq1+Fl>V4m)rbCAN`HLg@>6nl*us** z8(r`3A8%>#ddZhROiIyyM&G-pr27YxQna5&m;Y4K_W4OE+Ry6d8d&(TnE3K+1E!sE-|X|dv599PF!kqI z0!-WG*@@D*FIRq^wZPcnSptlGo+ZGP%d-TZ-|6950*p?cCBW$CSprNQl}`Ine%g=h z5HHy$jw+Y-BR#}jI%z-BPdib)Xg{hi>GA{l zZt3d9lTx&wvbt+aE_i)XiuUv6As>`X{9;my_VdcZmrB;JpOi|rAI9@3Wm9}x8aU>( z++MGox7^=#nfTMZ4zAsDe^+|XrT@*WaeeoQ}B|p!MYhu~J%1lTS@Hv#|B<Z%B>b;&NzXa)|L57dJ}~!DJokXP|KT14=Dv&PBrx|s+_S*kr}10`=KhC! z9GLq$?%89y_Q?6YNy^XtkL+;YDEr+1s9f$drHA_;>E!-L`We#`_0rzI|L8qbacuPC zQXD`3isP8+@0;S7>G`*~Uvn|l^^5qzXcPPW1Ejn7r(#@K3;4I*^AN{*)(HM>_X5Q+ zQ}YMk9^`-NCl+!1|9zb(?#uc|)`=2hW+`JP&%y9HVKS`f#{6mz-6y_N2T zL;A09U+LoI=PH!@Yu~^B>{{?Id2UAg)L8Uu-@nA`ppRXgQ+Vc?s+((grhm9Oh37b@ z@Eqq9p5vUtbDUFnj&lmnaZcem&METguHWbLyMFH(JFee*#=h(Ko+;P$d(W}IdXD|r zGx}Y>_Z<7Z(isnwpK-!-96vnAam8~SZ#>6w$a5T@JjZd%a~#j|>8{`8^Sil~XY9B+ zmuKv|xtM3lb#pY&=y7v5&x~jCf1CsQbd6{9i&)=xc-m_`&@riF4rG8wja;Li|Y^R z#Ea_>OuZ;Crng21j2|cu#y{wW@f+pA_>+3V_?hxx{7-o>@uEDK{zZ9-^wx>|C2+Lk zIokIe%k>=fc#b+f`}XF_!%nQ1XJ6l#jxO|(2fdUBQxD36sUPLR)SL2P{6Tpzexf`W z|0U|>{hP=?4~}*`NBf>*xt^mQ&rzr6sNctha@>3&#a~}vH*Ub_V%&hy>*gJvsR!c{ z>C}($3Z~wSV=(?;e1nM>;~q@B++04N&bUE3`58B0>@aS?*k{~;DVK2rMi1i#j84W4 z82yarF#mDy5GXKyQyy5qg=G^~S+F#~(gsU2OdT}_s*Xzkeaz2~T`7D*oBW@Q`NWR= z$vDz(6<^x3;x3!yrTwd&&@a?}=r3wl^gFdT`kmS#{VvfynWy{qLw>bq?5Le%U+tfA z)i2Pa{(?^RBlL4!PPEA!9NVPl*d{&4Ht9LGNzbuOdX8<uV|(y6VU-0-11xQ@ zG{bRh@z)*IQR%w&$tSY&`?cHq{}->_#13C2;~3km;_iRTzsGj&(_{Ph9Q%dm*k3%m zSkR9=)9=&{W53I%6FcmapZN@o9byM#pLrKdxy-v@^f2#&>342?@Qi+*DU!~Av=#pP zHtEK0m^MjUfobQoIhZy{TZH+`|HJ${`Cxv>?_t^`c43v1NS_PG{PW;w$8)srIhN}= z>hTjX^uV_pK&{+O4*_=0%}j4zm%!1#iB z3GCaSo0q_p$+az}`}s=D@8>ZvzK|V!A^Z43<>CwJ!57krFQnhq%daJ2lXUrq{P>M@ z?BGur`}i5AT>KBChq%DRjQGODk~qTDi}=QLf1Qi@{q+yVKeB`0WFLR3T>LCO_+L7S zi}W)mSG-*Les4DRnTN{{t{lI&oOD-?-{TFta{S(J*p=h=gu|{J|84{9%JF;4VdmkA zm-A~r-IbHi&pcf5Vjiw|xxe{x-M{DcFb|hb=HZH$D<@ws(p6vb%MaL*f3PpVQLg-n z9{CxaiWmA7FY2XuQD3Fw2j#~F82^^vVwPkbUZ>a;dlU;1B7w1 zU-HWj*pYv*FTe3u{^Z}~XMQLDV^49R9L05Wj4?jH)5918qmwZPMnBgC7{4nW|0q9x zlO6mi`}kSq;(zHOF49T7q@OsdUc^`RC0%|Xzx;z8`3?K>C*{h|=#l@?skp@UnLppm z^%2jMAKAxOtn|e7F@-N;`%mGE*e_D}BKDUQzKH!Og)d_NO5uyx?^5_8_Qw>yi2c`J zljC?xx~`Ap*Yy!Qx;|oG*GJ0L^$|U~KB80CNA&CZ=!xgl%wku<>>lFIl8V?Pu*>!UAU>F82^^vVwPkbUZ>a;dlU;1B7RN9^nKf% zo#@ZjBmLJn*UtHk`x;+XF@@#8#9&+Z&Q z&dK!b&hg{?OwaBdKhD+k?CO%@JVtE({2HXX$2=+W#NT?3Ha*9(JVyVDluRosS^~ZC({&)Nkp^tg8I8J(`ZdqzLw3^w_X>jHnd-YPv_e|&np{&J!9YXN6(b&`lDy`xc=xFovuH6MnB^}b>Tn!$X_2XcYTNP z1Ac_@4}OI48-9fO%m2gtJNaOK$M0d{gE%;;>9=( z6EDVTn0PTx!^Dem8YW&`7nII*0VY4!1sFSA7hvpjU4SW<>jI1(t_v_axh}xy=ehv% zAJ=jI`gp~3{H^@NL3W6b>=Q4QOT46qcu6O5k$&QpsF$DjQ7-xA2kgi{*q7fZSN=qg z{ESZdAN`7pt~CqY{h+Qja6Et2-!H^-Sv|+|T0O^eTs`ZoT7Da^k0Je+&&&1qlH}L5 zCjQo6Ykc~zcP?=X`?}V^y4JwD*1)>fz`EAJy4Jw)`si)Ox_H+7fjpX5_}|94MEosh z3y0tS3g`4D_WS*&?=8l1eZ3NU9e?%r$P#<-{NB{K_fPMZdOeAEm-H^GPfxtNq<2?+ zdg9%sT;km&y#wp>#C?W2Vj4Agc6&SZj<9|k(re!lR#`qhYVaK2tMVK*dye}UJtuve zth>_LU#)alXAb;EXE>l=;e__~kOn2@niE@?cO0)e+kKO#LkssU(f0P$Hx4pqwrXJ-+}z$S z=yZ^2xKj)B+ym`x-Ngr*svnx0kC(T%GmkycEL_ptO!=g}J@m_BQ}aM`v(c6v?1Q%# z`?KhGDCl6@jxIJ!o3=Fjb?jg}^eZ-7e%I2RHLbnFtOTAHIDYj3YxbD+uG+|qP^rM*4&!UN6fY)dox^Y*rK z=L5~V16!IVn|H7?mlnHky|y%y_U>SF)y0Oo-*AOXf3Jh*zvTyfQZcrJo%TZquk(+S zJKAxX&R+l8bVob(`p&*y$Mo)Kd)?dF*Z07KI@)@(I(t97+@PbKRNdM8=cvy+*qx5) z?EUuO@(#As`cB@To88yJ-g{Li@8^9cb+BW1>g4_Z%=iv=z@;61T%;kX`ST7f&A@Xy z+WwO|n=gm9G@Xy`XzO3q+04JBrTJ)|j`pUJolX0@TAEWf>1cN=>1=L&vZYzJx`RFT z{Z3}nl`YLKOFP&(7j!a9KW%BO(=cwsPUehnTblQ#bg)Cu?Pzx0bf$Ub%YNqkL#CR= zZDyK+5Br&0+DtN3udbMBj_=*i6m*?x{#bXG zX|z>8Q-0D^bLZ}}%$NuInr?&KZ%byG!ejcHj%Q6Z!#d0|-B$N8n_e{4oO0AGv-9Xa zX1|L=`g?!qV~&{=^4FWv+x&5Qu(PnFx7lcRu;2LYUgm}Qq1-=T*2^?o9Q2%iY%eos zdC+;s9=%Mb7lZzdH|b>_d}XSy*U3MgWZrmnsu}&v45ReQYiAhcU*CU*k)6TCGmPxF z+;WCdxtD)>hmoGjm+mmq`P`yAjP$?p$Q}85k*@lZUw*)j{DXb@jdJBr^vKWXl>gDM zxFq8RA9;B{v)!mEzP@7Oct=G)bMWXXK8_m?>1U>oo#Nwo*uniwN!b)1$K^lvHOnfd z_&8pEcVDy1;+o$+AF3a{YH$5=L$MK5o`t$~IAlSe1!d_;`SE1Y!TJ|yzuM2wK`QjvV>_#DuyF7N1 zS@nky$MbJH$#mHw#PQY1Cz-Ri3~^LC{!xDXCOi03_VKgI#sAVnT%?nDNk4H^y+~Jm z$uB=(NB+US{6@L*Cwk;(bjtt4QE?%5A02kG8U4{r-|sFt>SS~5hckV=3Qj-Se6VV! zkJn$WJJ}rf_DmnI(^i~p9(#4BkJoL@PBFuund#%ze%vW$>f`RWE?yH?pJHatnd##- z^qBtUQ`dLtcegI=ZQ108e z4m8XA2R+?a4KxS$3OaY#c96N__@KY0#UNvko9WwOpOQgl$F4Jdzf(GXP=5R)JNQlZ z@u$kg&(eecrIWZwKk-t%NLPKyFF#;M{=vTdM!E7QdgNzx%KyYmaY@Dt9(n7@=B@i@ z`TC0KcRSvFvY9jc|6}jXqq3~NxA9MzwDgIrngiS;t)mN0HCwV%BlNqfu18v6ywd+jBI%pIyv4+DDJ3Q)`P^$L}wV zrfMtIu}a6rZeyt4l492J{+2NmFuRy_v}-w*>?Uge_!VQR=1?8q_n)!k?W^-F8#ayt z`{?`~cZ{Q$9=h(Nm&a3AJB{ZT*YTA7p2nFqb3D~ipWndmx_Uh2wa|V2kvg6hy;00M ziXZ$)Jb05l%%_(aYeOc@8k|e^>xR=(^?g(`CYQ>F z45x;r>U(EPE-iR-Y(2L+H+n8#qs^9z*E&+8a3kqH}|3dy@@Z*Jb5ks`>T? z#&g7XFr~e}fpOM)YcSc_Z(#frs|=>Koi`Br+WTk_?e4OHiWlUN_$%CUNa7tDO$+q?dzx0cE;Q@JsALJL_P*?Z_9^n}{ zg@51|U2OG&y?NzudUQO4`xP5H)`}cXEl*@HKNBYor`XdO%v-)XmuPV=gZXrLJd8>& ztM479)vUGOh>po`#yUV_Ohfw?^SHh36--@Si&?M43Bh#GshIT&Ob(_V zy^2|{!>58Nzl-|3QhHT?cLe#jD`vfl7LK5$E!D9~uUo&4pp^}ZS+8S0BkB8U#XRp` zsTfJckBZpeyWJ>?zOKG+Rs5StqiDbSKE?bUt3H!YoKW9uDu1;Bqv_=XMO?Q}_GsF= zyNL1Zyfm6x?o`LB&xeq@V`%xOMU1~i$1(Kw<|5W>PxmqOZ%GmBC4TTA@!&`DfH%nx zKBX>r7Chiza6%Ws551%>_@!UO3lGR6{2;&ZhPuKh@CeVqDf~k((ZyCT*r&6CX-}O^ z+^^V}ccI0>l=j*t=I71*!PKeNCg$zpgJ4?!@+Rgpu=@yl^_kW&K4Jvzyr*^S^2-SN z^P1K%#APJiKd*HhTso4vAJ;mrd1DmS->dxx;zrTmpX>O-`=iLdNawjRcr-a?==`g< zji$*7=J0{__m>!1(E5=al{9^9QJ7o-wo>$B|iXZ$) zJb05l%%_R>{+=GxzKg2)bqQ6g=|Nxi%%-}xOK9~$clyvN zo7|h0(tt2`%Js~q-z=r{X)AY{F+d&bS4tm$;YJfiW>dk)Qd;5fM(<6@ru1>8>b$Nm zd4*_yi#dI1TC|QgYW1a#i8{~2d{=sVgU%n=&y{W$>AKC-9^HMnX*{`Ky3pxe8t1R8 zTxilBjlcIy7do*wo6y&~NiOvG+icqM+a?nKp3R#`;=6}!Qs;*{&jz1OB>5+`-b7OO zVAV||c=lW`Cc#rQ(oX0eW88{KKp)GXGq+DGnmZFUyxc(A!U(V{HY zvF#o=dNocRt91Nzm>a#AoW(j;xzm?+XJ@gFhnDuGE1R`Hp;2F|{)LX;R^&?i4(L2n z-CSwcDV_iDUoI4PQP*9)-i0n)(|DQ%yU?`T8s{K;7pn3wi^t*i`Ytr(vF@vG4Hrsy zlEpfTAN)u>c#}NLrm`2hAo1Ww@_;wV4?d+Xcosb1UvNSf!4JKpFZiWj#0w9|Bm5x0@P@j= zC-4Z*z$yGgFVV$TFW4pZJn3mxDfcTj=AB=2PddG!ly$tI@av(MXkfsu}a4eKl37oPfA%w`#05k;h0j^al&$M@(I-b z%*Wo;)>FqX9M_LN`atK|d!Qf9cF_69zw1Kh61|#ohx-o&!*7*1+-(nD@EsJQ`2h&)TpH^1#VHtzF0`d z%3a7?eGmUsr;u*-ccB^w)cIG#LUmr(hwM&k|Kgc_$p5mA&#K;s>fO?LhUPj`wSRT~ zGEZkZSxue4tGWxGI8ocWIgIC(3MVRSoWnT#u5cos7CDSR`x7VH@m3C@uczak=zOaj zx{{Pn;=do9PZIx8`+RkNsPmlsH_w`X{mDF%y3an#Bf)b&Esq2zt;i$6?-7${?F)YC z7xBUa@(4f3FTA0y@CiJ^GjIz3z%RPk>IM7S6IW{TRTlRvHgt5o<4VS!EaoTclq(hP z&0^kuQRfo94rVc*lP0**k>gpcW5=eh)avIf)^V9S2e^4v9jkQgJH&;qsP7}_IR0iI z%6XQ>I@*Qzq3>#G9Us*1L)V*V9UB)qQ&DTJ<8c>f%Iu_dw7=#=Q$H}r&pIdiy00Er z3x+yTfR7$;yE-`0Z~l55HmU1G9|mS~Uo)#Y(cGYH)=~W6N8-Vov()%Xy6(ebS_q^}76*8)es4$11(v|InRE zUMyw3s_$~A8}~|BFQ@lC=-}@q?4O_FL3uxwaD329p7gu=KE?daP@lN-jBh7!gfxXz25*O#zfPjbAdS$YZUC4TTA z@!&`DfH%nxKBX>r7Chiza6%Ws551%>_@!UO3lGR6{2;&ZhPuKh@CeVqDf~k((ZyCT z*mdi;(Z#2w+^^V}ciWn{QTe}G$DnR*^x-3|W7Dy2RB>19xGKku+F#c?9=h#DXMWW> zPU+`P)z4}jKilF?4GwD^h!7hzx0m>y_%=vFOBvj-?chVo9{en z@N%91Kr1hb3pdBlCtlQjp2icp*^Bbj_bGIw3tm)jvL1&QAA3>31l?C;Rc{I(U&=a) zAN)u>c#}NLrSRWpOE>qG$5VAf(vM1@O=6^Fr8kBFQ5eb`4m1Zoz{O~ zqxxgh>Es^;bSY~djh~WEGiwx5Z})lBZJs)|RUtk4buP7wNT;q2h16``Ty@Pjo!;+O zNWa#YOSLn!zbI`Ebt=~JhaBe6%^f;V4$;GNm@%2|!4)0J7Y z_7{zF+V)x0;i|@ec!)CyD>YJD(&^#}@e{`5)X< zbHuDWNO3E8`d28PO`Ituc_jF=3-hdf!7u$HUU)zr;RpGJH`EnAfk$`-PT?Q;MHgGW zU^jSoK0Sy|<9@}4j#Hb>rxvkktmC1l^C)_G8tYi&*gR?$pT;^SteQu~scEcZkn=ox zAt#M>-2U5KI$ENRRXR>vGMBz7OJf~ZH=ax3`_fp)K^x~#{t4}WtJfSlbWz7Ue?OaI z|JHe)OrA{(AL;yq>&>QqRn779%`D2Qt#vF|I*U3t(mGxpFpIuzrgiMobCx>K(>i9@ z&7#1TT1WANABhKVl85;;^Mhxp3;qQUbP=4;OYlQS=?i}87xBUa@(4f3FTA0y@CiJ^ zGjIz3&{1@Oc3V!*r$J8&c-{@XIG;K{E?~VL{yU%cKPX_m%G-xfx7!7*m&4=`%2D4- zn0FtSg;4*C1*})?hM^RGN*$~83YZs4%MTQ=UY#$8(vgY+)@!m~7;W6F{W-hCC?Z?O zFKM@c_9f{&`&TZYth{XYuN(oI8x{Fzqx>V4$%4UdM>0%p1Q96+J)4}N#n^ovydWs zYMh_Fw1{qXR@Xcg{+H`5q9}Xa*O^9(Xrx^s>nMKkBk|x(@_$z^tRx{|YF6$Xj;-%>n)=M3$aQ^V=bgJXLp7Gl! zPpA2=>j{0uEuT&s`mU$x<2I1^m)LEv#y@ROca1;6x*c;NwggdgM=-cVQg1RmiTIE8=U7hP=if<33z9Qx^U8uu$U zbUfa84!v+Sjrp;AGMhg7BaM0cSe;8eQ{P9>@xk)hwCa8u^IUGsrpwRLnE$5gT;kIj zTE`z2&7uPJeFPovHk?J{-qt$q%AZMb_S(O+=S(X7K*#4EnL!_W>hTafX$FlNsK-gg zYct4Uq&a@Rnobdu^th@SKAjp(*W=B@e>!cPqsL)hx9QX%B%S+uvBPw-gr>8O;s-wx z58fmX^J(S>&r%os3m)hqIH8x|hmO)0{L(Mtg$Lvjevn^yLtWt$c!X!*6#k*3=mPB; zoSZ`+1QqhQ-Fbcvy&hP|dJTCzhl>3RS+5rF&!r|lg{)V?#JLpRw~+NZ_W4}u@}p(6Et ziuv1KeI{?eTEO`a{}w{O{ZznpYjg{x_~QkPXQBE`e(|6>R?R!-oKTvww}A0q-W^I+ z_7t#QF$Y5F{O$tQOZ?zL;=zyP0dJBYd`eyLEO@}b;Dj!MA9_h&@Jqjl7aovD_(6W* z4RwW2;1QmIQ}~BoqKmCwu-A8;OF6AJa=&6@-Z>j{DeSF{%+Hk}bE$rdjm%qq>|9#Z zcq8-q#(}x?cb$#Q^PtA_D7D%~=Kt~Zd35NB*3s$oJUV?->($bEJ~h6qbqv}(pYER0 z{#7kP=;(eOKQ$(V>Q?CSu>E=nHQ%DgNuYZu`Q+*G6Q2}H|D@@0RsB>bO-R(^?O>HK zI=NDh!zpit(MQV)xv%=|!pJ4AkaZM4_>p+2wZtS{6gb*i;%&CznP<#n8BMspR68OSR|4 z(6NcBbaZ|$Z5kOvqo=0Q*uq@8?G!_IXQxt{y2gE?X$-k9N+rkJxwPbZG`$|Dj;)bL zBg&(xR&pvmX{^@wBBJR)b}HR^Bacq{MAMDU+Q0MlXsZ8(j`z3}MaK{5JgqlJ(Y{kU z|H<$uO1!A+em*3M{Z`#6=**W9{MwEjt|x~DRS z#NTK_4oQ4mmmHEj_p0WQBN|YgxzQ0ns$(>{`}w zRf}kfzN-B*e~Y3`cXWJ}tx@#Rf3%Jl7e>*DT3W|deow2qxGMpBPXT1WANABhKVk_UWBe()@H!N1^vE`k$!34Z7( zeZepNB3^hv9^nW1g*Vg{K7mJg22SB0I*KmPuGh90a;%-l^R9MT3^jN)kM#=vE`~N% z&ttv5x)4LJSIJ|&LZ8J@e zRrj!{dAIgA#z3MW0wn!bTJ|BK)zKkY^;M)z^KyW%Sc*bsvQ4SNz~X;=zyP z;dy7~2cJ?GJPRK1FF2u#;D=t)7yQyM;)Ms~5q^+gctc&`6L^GY;1vFWUv#n63-;nG zF|^@K9``FY=AHkw7z#P9bGR9jn%frLZGf$K7_Z^w+m}tmFBCv6Q0zj=|@r z-O^avzf~Qp=AGa6SUQoX)+E&D=bk@fsZpx>9924=Zxu(kmudf_L2-0=p^l%pGLBxG zq4O;NDvp|t*ZI%=9Y{ra3meCwT}Ihk|OCrlXV>bctj*^YrT&1oaq=z8#}Gz{82AN(!3AWaoveO zM$qBD>ljZ-Sp*IDQO7Er{jwwImj61&|2QFnh6b)9^woA%1ce8!qnKJq8Rmk1RaN;h$OeJT1Th!NSf@d{qK&8 zq*cB;e!G1n`3}{2;-5y4%LJX@`TGc}H$&HbXJZ773)SOlVr&FGT%yO@D>EV}E=G^T z?PDV7-m+Bg>vC`eHCvI&I*K3sNIZCxJm6FEgJ-D={sj+o5uDIV@Iy!G3x4Sr@xlZ0 z2tUX#yrHh}2|U6xa0>s>QFMWJ*E>g3i%EGrZg=;HriT;qSg*Qn(X?W09_uxIcr-l< zR^L}juMP{MX=0H2yi)VdD>s@N`l@RhYTl(CkEXsZ>R2`JzN`{MANEk!A(dVoEin|| zE|2G(*C#PFwT1SNFNh(}x;p;UxfoiezE6?opVwk3S>1<={GK1g(s$Q$x$cB9u{85? zF5`JyeJ1~^zE3glmadB>-_yB_|5RZtUHKuG^(rWdr7w@?vR>i`4-yZ4BoBC#{NPjS zf@i@4{skv=5&Y0g`hs8jMZEBUJi-t13vZ|^d;*W~44lG0^b%cc^@81LOf*Gw$>)B> z#=NUCF`9;V&S!oG&WWbGcKOWP=PROViIvGu&P4b!li!a8| zrrPRQrDK(@F|^~weAaQsq!@an*6{H8xpG4co%~(vSbQdiw)~`ZY*ss#ZmaK8=t#X| z>EAtioUHsfmh5)u@v|u*mVQ#}h4?(5@L4Q*Ua|6nX_-=N1~(;s8Wdwm}Fb^UxS zwNB4t9mNlRBp$p;9`Gso!L!r_|AGg)2u|oF_@Sfp1;6x*c;NwggdgM=-cVQg1RmiT zIE8=cD7wu2aswrvOr(}`lBwCl4fOS~L~@&(Of~GXX!@Q++7gmXiKEngbw!EfvN)OA zug;=@afx&?I+;ePHIN=-66yUl$@IdH>YluAiS#f{9joqd_@+uCT`x$cJ^#t3fTIai zv@MxFubNFgQWEIc9_?>FGJ)pU_4#8biVI)BeY@ihC6uG=g(o(?|I zct%9T)6gm@jPu#Y@pPkl3gh1t98ZH@O(FF4)8KeoR6B(ZMQ$MRpYz>767Sc114*7; z*E31-N9@fcse3gilLXJXW$O7r6X&}NGD+~;&&#y-1;6x*c;NwggdgM=-cVQg1RmiT zIE8=U7hP=ig55tik;;mbxL>iMPLlSA~ z7fGz+oz98$^}Zz5G3(_-T60_-t8`p=B7vgLC$WyNWh9X6pGmCao$(1Y@uBvgwojlH zRke;29>@2wE}rVN)jFP<8Bb$6X&svlh^Ko!^>{1$Af93jJq{<> z#nT<c#}NfQ}TmnsSExE4|EZn&`a<`N9hZG=@;?B1M&zz z$S=I1uJ8#w!ZUCR|Ikr%fp!^B6RCMi^|zza>ywv~=w6F#*6ZuKNfg&CoAr99Z4y0f zn9X`!a8IJ~wX<2Tf2Sr-EXeB=Y?`i}m`YN;0ih_rzk}J#kE? z$tSeG@r-10->2iF)f|l}Q}@KGJVieyQ$k4==YLWyg}zny;$prxwM(JtsacHYq)!U{ zvPK=NJ|DV`OQC+tvlxHW%oO@HCX4kNJTHYRqO({p@q-762S1Vryh(oWDRsfK-~s=F z6S@d~=p}u@Fa083ct9TE2l<6J)D=E~M|cKK;U9X5F1C8XzT7d1!mp{d0UH}SZtt8# zL;uh^zT%ujx36d&Ck{$d=dxPIcjhJ0;WJuC=gcIUcU0>be>jPXzEQ`jdAI#p5^dk1 z{?<{SpYL`}rU&XCb?E3cIhlS~ul>Walc_}gZG`y4XOiirx_=)!-mH;AkLT+APCZhn zy}CCZItB-)(3vqBPt%1d3`t6%&(ytPz<($wg**dvUm1ld^tQTx3_OS*{75`_ zlRV&4@`Goo3;qQUbP=4;OYlQS=?i}87xBUa@(4f3FTA0y@CiJ^GjIz3z%RPwPgzH9 z0SQ#)hh*~2Uq`ci6X^XD$wcSZ(c4Z5lyEwk_Sa3LJ#7=H&ADU>?wv-}Y9!Fk%gK~9 zA&vgH6tA95N~W$cX_T@po_>C)j@^((vzElu_v-uTerX!L>=REb>!#43pQX{YM)CAn z3++F0VGW&Wm%{PGH?E;1r48~p&Rs)sE-9SW3|LL}l#9v4Kohk7V>hD#_b0aO4B>#?? zsU&rq2B@_;6Hnbm*ReSGA5|>RjS0^?d{#_neIZo*NLgP8~!)iL4sBwO@Yc)+?r^jK_lGSu-z3$7ca5ep# zk<2=ZAN)u>c#}NfQ}TmnsSExE4|EZn&`a<`N9hZG=@;?B1M&zz$S=I1uJ8#w!ZUCR z|Ikr%fp#B;CD1eVY!38#J3N8T&d=uYJabh7O`Vg?a3m*!n|9vB#~x*kj;9PlqFJs^_&s>2W}-& zySH_G&-aq(<3>8qF!h-{w}#HYDKd!))xEeFCkNGe(}4R~j3-ikCV!*8PciR)yPQN0 ze`GQKo_CUHpSnJezG|xTpv=ozte5z~gT#X$$phXbKlqfo;92m1f58b|1V8kWzTlUB z5idL-kMM*1!W-%epTHwL1E=s0y+jvVyksEhjn!EPNWqr)v-#)@e2}ZZ3DG7 ztn@nlX(Iik?or3*=bdYbwEdCR@wHY-wC1|jaY0}bolxJW`25@ulSCIzXdQ2>bK5!x z^!TZx&Rciw*5m5nze(!eQ$60=H%zAFPxUxlpgsdSY|iGs`nO4@YNgq%qxiv(#Dh1< z13o1`c$T{0U+_Q|!3n(tKXjD7;Fo?8FFYWR@Pquq8|n(5z#}{Zr|=IQMVBwebfNgM zUdFEBUFg+QUFiMMUPkqiUFfeqUFn6PUdFlcUFgN4uJmDlFQdwgF4XarZZxB}m(e=B z3#A2hqs#5Rj3WtM=`JIEOF=%O5#-E|yInyz&E1|D$Z9I+n%e&H)JDo}Vt0Fp+#LsWhnIw`3PRv`!9$rTG^PQN_58HSd zgRXaCp7%8HGG6#kXXd}@Q%_@k!_KVBD_1;?=nkD($NmS@JB8djvyOX8JPn_b+TSJK z(?|}{@nLg4jRuK2&qu+Y#?#`?od0WgPh;Jl&Rn-kS5KqQ$}zMS?Yp+!2?|cC-f5h&{6t= zU;0J7@PItR5Aq9ds4IK|kMInf!asBrU7%g#`Ci7S>b`L3wK&wv7+2!OJZxOzWvt2f zVt$6K^fEq5^J3n5WOx}K%e|P-eOtYZ%=uod*R=g!#!F+pSg*yGyo@IOyjZWE|9Tne zoxNDEeT}`1fF{~Mpo_Or^O+~dzv}C4thnOId0I^HHgXPo>ii45jcPkQ^}Ji-Z4A%# zWIUa-yp3K-o{aPICU2u*oG0V2wawdbTI$Jq&HCKixVzYs^%6gLka+MTd3fHL`N8Kt zvo3fRJm6n&LKndgy`(SrrC-Dg56C0@aDJ0F)D=E~M|cKK;U9X5F1C8Xc3k6SEOPC~ z{fZ48a}vCa&VBkZKZn+N8Nt2!F>hh{UPcdxe$3~P&%KOBt@<&~*A93YQ(o)G{I9v_ zWgPp*n{~-~C~Y3OZC`p%nm{KMYcc&kMF=XiS?XX16d-FR(g+c@Fv&2{H)^fuaCy!E^*^ERrt^Jbhcf9q}hs-E!!e!IioM(rlv+*is` zZ(~m*Z`M)#;78(l-kEv8r{o9EQWyLS9_S)Cp_kx?j?x$W(l6qL2jmfckY9L1UEvdW zglFIs{-LAj0`2Nd^EG~7V$c2Nee7#=jkIST7L4;XsxP-^ehv@zHSAODnYWvszJ_1E zJ@YxTyRY$hr#AN)u>c#}Nf zQ}TmnsSExE4|EZn&`a<`N9hZG=@;?B1M&zz$S=I1uJ8#w!ZUCR|Ikr%fp!T?eT@qz z)wBIducwi|#+o18Sg+PAe2p&-sptIFI6uAC*GT@#jrIDh(ASu?)s6M)Q{ihI&TwPB z{`x`9%~&_q>)*e8jlR>}Sg&o>`WyR$+*q$ZZ}&GAk@kO2{f+ML==hjH{f)93I#25K z{>HJ}eRckr{zm6>>Kzd3{PuWSe&dd)!`$f)lz3e&{8A!7u$HUU)zr;fM2^ zyrHh}2|U6xa0>s>OLVc-3-;$}zDDsR5AIiN=-4vD*BCLugZc5u^EKi|dN6PQZ1FY5 zs&{#S&(mM|8qRL&9UtoRZQMy;BejbM>sVW9_iqai*0E*P{zm<39<1Z(H~Sk&*WFpi zv5x(Xem}Ug|IWbvMwOlJ9AETFek@f%)_H;{zkX0?U^5svHr%;iuTOg@4xA@)nV<2_vJN`` zEI;F`4IQ|y&nQ1*;%6Ng&nJFpO80YT3e#X`#9TH+e%{;S+d-XW$h6 zp_k}ls~7Bvqx=o`2JN_Cu`%!dGs53UXw;7RIUVG0Onjpq^Y&gpe`95vcFd>82mZ#^ z?(LZ8vbO%lV9$2Uf4%zt#)IH?tjm8M`571Iv|}ATF8CS4SGQvw%fI$B@{6>;LxG=h zbFYq{wcO8`d_m_KJ=4z^_(10`ALeJ=t)<6Ldrvu0>&r#2K70+=s{Q{MG)(mk;}}URf#r#^EWn}?!$V0xzFGD=bJvP*M#$GZkG08z2-geH>M}|VZ9vc1sM0j`mkPK zb_g(vM{9pSj{sw|hmNm0Ccya3PUmS97GV7Qx|u&dz!>qOuIrN@V0?bVnenvyJiti& z#hG#byeGhza?+XcS3MA5q#ki*y`~%rF!~*GX1&A@9wZ+8NFJVdW`6MbrCAp|3m)(< zIH8N+hhEYb{L(Mtg$LvjemK9$8|n(5z#}{Zr|=KGL>F7VV0X^{zh9DSJpA@ zwE)9t@5(v`ydPkEUC)(uyyO~S%zNm<{%Iov4Eysg9RFTufbrQkE}W-lVt{d=*oE_7 zEDA6>B)f3kXPR1rKx)oX|_~Lr3Wge(4wS!UOUMKgchEA_5JkBW<|fjPO8X#j!Tb!|aeiW7O$3%+KDbfkw=wHq6`a!GT86tv1Z( zAn!mUph{cjc}v$o<5rWl%zsAnK;tKewyeu>mHaq&`3PnmhoI4I?&khdt1iY>%)P@`8#bH ze*@2f#;1?kvR*}Q1C3`-+Ol5a2M-btek2cgllF7VU|*RWXw2;S9``FY#%<`NK;tXN_n4o6(Sb&y z^Lxx&c3_~ftKWOf=eKTw#`&S|G0)w)1R9Z3-(wwDyb)-;6Y(DF7*-|Fcs2b!)^YD2 z1C7}2@3D^Ej|?<^IHvuDTL&7=|J3ofly+;YwBbA#77R3&G}q&#`-Fi;%T9Xy6a)-3 zzH`yz>Y&R&<4=D*-kSCtXw(hXI$F0BRm7A@DCkD7ihP9ZJ^PkWp5t0 z_tym)f4B;*qC>XKMOQ=Y;|IOoXP`@%SBGi+wE@yjfzYs=JV*OKx5r%C)RQJ zwLs&}0w>n-Wu@JKiB7CzG+(; zAmf)mdUKv_89~PV?|bX~+k=cjyY%?EzCXy=QmDt(fwMuzic~$`LaqcE6ISYRnEh9f z5g*-~`>J&#$Z(77%{q!7{75`_lRV&4@`LB$W?k?vc%X~mgkFLlI!a&gOTUO09*{@) z;ru3Vs4IK|kMInf!asBrT{b@2LOXl)qJrHyG_8+%FP3TB?q`v_%8q283)rngf{b~; zzDHeLds=Obfy(dAw#4(-{9cAG|DC@#EB~(VzzR1E=!6Ve1L+pLrhM8;1AtRle6$JwvSCkM}&h*A(v%u6*x$4&nX1@?Lkm z*Z05cd)KkYLFK+M*@XQCo`-#5um@A+zI7W2`yV|I`_^HP$jW_n)pOozf5zuwUtO%# zS3f++*!nUN*8H88I+4rqQr-hv{8-zU{h+b_FZ)E}x`4#nUiZQE9l0Ka=Y8Zl5$?m3 z>qoeMPp&KB{yn+ggy((aIu!1kmFrV@-bb!m;dvjqo&~>L=R&+(|3V(QE{6Pay$p2^ zR9>g!>sFQb5jpF1{^#UAqRRW6`|5T6=j1-;%IB~=^*aA^@En%ybH|m>iRN zBJa<~z7q0Yee4e+@7u@z0`eaI%6$s-z6}2r`xMyj%Y*%EWWOHlUncwbVE;1N-v|4b z$-Y08`zYysp#E>}qhz~pAod58{RFY^p6oM-{Z(cELF{uX`x0V*RoSl)`!mWuhL!s~ z>U}N$EB1M`-PaiV7t4Of*#BMjLB{^?vOhBRf0uoevH!d5r;PpIWuN8BeW>-m+y52& zP-C6HpK~w`?ORNbZ>YT|yn?B#YcXAGolA)mg6W`BG0hsBOM%J3)T381)r`rd!>58N zze_PWZ^@69dkp+Kf>t&trY!Y7HBKMl>Be5 z+Anw{6+bFsfA4mqDEfL4$G@30iuV6f#CgU(8bv2g6mkA)14h%!2a33EpX|}Jb$1ct z*?DO+wcM$WRX9WHj-lnB7BT)79mmkyn~Mm2?dd*-{w*n@;srS*{tCAoYrKPc|CHpx zI=|!}quwnqb-zu^Cc#so-nS??tIp0Q!CyzczfAgqU;0J7@PItR5Aq9ds4IK|kMInf z!awkfE?DQk<}!-rUMr$~y^Cn2&nWWyqlmW8DWXmvjiTSLDBg;S=k zogGDApDCi(UQ~OUzc-qu9xb9xt%}J#d^BZ#qmH!{(~7I3sc1(LP4OtEk3Sqk*Hw;b^NZBv2=B*&hz5GW9imhoj)gV9JQLF>;95Ej*g7ccm`e> zM;{E+I2$(@PlbURf4Tj5G6ISSeFa;_QxpFpntOC3i9aS~BT4+zF&jzpV4Yv`JJjAt zQg_YuLJ~YNCksh%e*bMD3I3nIDzx?mzx0cE;Q@JsALJL_P*?Z_9^n}{g@51|U2N~k zx4pODcFq5PxfXECLRCfw8O1)W>B_OKWcRZpIp0_BJ^NVg2VvT{E^x1jhcWBdE_}T} z;&CmY@)@f(y!Q3HJY!Y)40wCi>v?$wyz(72_N>?Q@{XFycj&2iEvRSEo`-kn;aWiD zJARY-p8x0J9ly91P`L*|GT-z6JnTV$YXOyeB&G7TfahV4BwP!q+{01d^Zz{T;fQMi zm3vI5^F9BIpMyQ7aV?<1yYuNmbQY7v`8xE65e={$;Fo<_J9P~+GY#yOOKLi^w9HHQve)bY;W&!$+l=Q#2_nLL{oKGOLI*PBiKs-|<@7T?UG ztlH^}r(o$U>a6x02hOVlX3@9J(iwlBp0m{Z_tOb|W!TN4z?SKRz3j!0J?m64z_GA&R1!SFarNX^gglhr6RQ0EFJ0*7Rdwu(h17S53tdrrs{B-^kjCHaLpf?+fMX2{ z$u7JPeOD`+{SWH*q3cbuIlghBGZnSY<~+w;oGG(YHs`m$=0sD~egvp{cbyY`-8Y-@ zEEwuU0Y2(jg>zR2C;Cn8u>$-}>N?SfY9AK#HM5!%%?-+?D@plQ|NY>6Yy3y;^GWjH zo`1=Yd;X>Fv(NHK@L+9UaMFrA68s)9YVS0&FZiWj#0w9|Bm5x0@P@j=C-4Z*z$yF# zzvzN%0a4G~sq0v^-;lZ%aOs{q4H>8Qt5MeijI-{vcVZUdT0q!FcN#QR?K!5d1yuXU zovzK!B3uhN*xa3Hk=kcWT?=TtN4;k>P95u4O1}m;`^rAB(Mh!7u$HUU)zr;RpGJH`EnAfk$`-PT?Q;MHj4@ zZ(cc^9v#o%we(t%!>Q$o3|?cOIB__|p3dO4_k7E6YH==u*W?`@52Mn{8N611uXq@} z^mhiY;rsgyqvH?NvFcjDtA7ureO1&xTIyOr$0b84qHZQ%3%K84C>6HQ{))UIbfjG- z$6s(9Ld$w&a-NjagK4pg+W$vgYj_YknELyw=gHJHi1LnuDM#&#j%yRHHwIDH5$afV zEg*dNAo^~s+6!G>%lIXG5OtoI$=3oLQwPzYNtt{tK>S!^mw2qbOCGGrOMa}?OI@tt z3m&ZP3r?*03w~S+kiOuTei1J`Adm2a{K6aR3ZK9uJOiijk81&<3)am0trR5FxVB^hT`n4c~uLT^82&N6&GWc3R{OiH=?H=tPTsWMr9o6xnG@J^5)_J=A zIE>c+uJb1>97dDx=(<4;!)W&tjpx#>q2#B=1Fl)T`Snn`QazLLhvf|=-&fWC_NuQl zX+vpN?M%KFAbzZ|OFY)zB@fo*B|p~cr7qU+1rOHt1t-@01wXC@NMG*6Vr{>2AND+6+kYPRVaMA3;wv$<;Y=RkK7apfF%)t-k8q!V&chh0 zdqVABukQ1&S|^smj^q*U^WSY3OMiWvN4U@b{J>aBQEP0t&);roEbZT_j#c;h`)!Y< z6M1UgPTl9f=g(Mbl$uAl&;NX@IJ&(|`yUO8qr(ez{KS=U^x6!aXZcrg)O5Vgf9~%% z@*1k^K5n>-9{6cI+q*8Kab6l{<9^HNxU0rLamX^7;G9S3%W=dqa(2q2su}92^(`qB(K7VIpE``0dk#L{?l_7Jfev6HS`~34`=hC9a z8wvOMzj0tL{at4x;XeOCjptEnwT*=P{2x!BM~9vi67KVNIz5k0-z=nwzhqHM=lRt5 zav=>@`-}!{o=ULJXj@+POdCu{8QcvqmPyq68fs&E{t5_3TgVd4J7_0b{nkm4I$F0BRm7A@Q<~9(FJSZb?dm%#iymbHomQi8O}srp%UtXkXuY>PWJ zI9$qW`0>p>XyEQrUfVwy>p`79)&7_M@t{}pbo`~!p5(h$=V|kuCk)}ZsuP^1b{m;jH(vK;nyvE)k-;+F6m-5>F#Cx7} zH>#A^_G|X{qSj&RShcqQ;b>p!mevzP;MRaQc{1UfZ9rT>Y&RsQsCby{WCIj$b&g zAAR(J&a?MGKbq~J^N)YmhYDKjy4f>)$o~zEr^%;2w5OrQ`O`%ova6%%hdux^Q z+Wy6R(Yj76+@nIyUi|`J4NLsZ*^@yq13P zK`^a1qUq;ZM*Ythz&t}D&TH9Zso|P!ySj=ntcYBVe_p^(6ZQnk6G@V*o%xnAK zUm8u-R;pty#njks4AoP7;y(ZTTgFhp>|$Qqw`)0;>?Uge_!VQR=1?8q_n)!k?W^-F z8#ayt`{?`~cZ{Q$9=h(Nm&a3AJB{ZT*YTA7p2nFqb3D~i&l%u31=rQ%DX&E_ukHVl zI-VB2QOs-m;>Vh~#A7X8^6>rkW`3-_OI@tV3m&Z13r?)z3x2HaOJDFyzlawekVp7I ze&G#ug-_rSo`F;N$J)N=f_w7iK76d_+uFA4`L?#a=g0Q`f7|B;Y~Sr~`z(O%bp+dM z2ex%>pBI2F*BWe(wasb!Jc8}}g>3gAuzh~P_I*S*JRE4;Y_<1ysyE&K*nzzJdm6P8 zy{SU&b$U(h-@Rd`H@TNM(CBKO##@=5@cYe+UODeTZyxY4b}aCs1J@nM z*y>?~zvM;J9yrkD3=iYud7iZSkprd2dl*HRJ$O$9dH0bmHrxFX5dXB$-Ec^ObTz_(=H75OVw!iSU)A2OEov$}2f9)3z7CYy*2CBp*Nv~;$orbg zx7pE$!##~*TfFJZvv$+tDet7j|l#H#Kak?xnurVKn_veb05Vr|m~P z46mnNbkf6~YA7DIBzjTuAbWa0)x!vB>O~)nwx^>}9>&;Jo)k9Do}xoMjGV_FTvx6W z*=lV&2L7MVjL7~G$n(c)cjNs{7S7*rnY-as&%$*tDf`N-o{Yyc!QD9Xa}UN@FU#Hd z!m9`4|9+dh@#4Pj+}EE++>Ii??%Z$2U+zYq+uaB}RH^M@Y%kFK*gm%+7;MM6?L2}l za|E_<3tReyEpy7V){DFTqyD?F=6LzydjHwgw(v6x?CKNmmPcQ6aD;usxLEF4E1c~w zXj<7{X*rFqB)fek%<1e#`FNbZ8 z2ew5=_(ez9q9be*C&!!kcfl_@!Z!P5zsUo~i;jp99bt=(uti7Mq9bh45q70s;m?&` zh4uUM=NGh_aLv0sAgT_}FH2OPa?5}fY`5;*rM$5IF}BB!eY5=FmsK4RuYQ)Rf3vNA zU#8;NR>zg8+h!iN&HUwNU#QEriHB_yC)=n4z7TKrC4TfP@!)}NlOMKC-q=PR{2O@`9`GzU z!9Ux`C-_A#e6E^){$4{J;Dg`H!?u~<5q`5S+a?~iQ3t#r26a?kw#~l8&w3%oHtmZN`HIwprH^wuy&r z(UFg>oOe8r%<;^&=xDWD*m52MTh2pZ%XtWFIS+v? z=OM7=JOs9!hrq`8#QA~guRNbroXB|yIFa)Z*m52MTh2pZ%lv{Z^9#1jFW9E;{P`pE z3x1hjuw{Pnv6Y{b|7D+(W3D9gxUYVr*RJfO#PX^y`CDLrxNAlE;3G%bu83PwKIY2n zj__and_sAXzJ1tMKg-p>*;coyDN1aE{ zI~%{nCZ6p|y_PVa{~h!iJ}!tqC!x_7%?FhC^KHZ$O&jD@{`t!ZY>%DbSU!B*8Mf2+ zzFR)3Nliz@tDoiS-)yVjm#H|m)p2F&c(zr(GL@HY%r8|>{1)+}j>MymPH-Zh;71+QGy8(S47M51wwZ@*Gk>|+7wWQY;$hpw$u{bMFT|UDi68w+Ja}N+ zowuy&r)B!Ju zK^>KsZL=@&vtEcXd0@ZE58KcOJR$}^@o(6o7i^P%#)dlJ5q{ANw&^dkiDz5%g5S(v z4%@8Dwuy&r6DQlE7ve=P*k->H&w9ac^22_UH?~ba*%rMJZ}QJLOZEKtH z7WhR+oAJPYv#uljCLXp$NBBiY*rFqB(b4p?j%Ix2yi@#$j^IRege^M4mh%v3E$1Py z0! zc?fKoU$A9Gcs=+pDsv2yYeTl!P zO}xb>kHsdx#ip*s29L!Cr^N=p#ilR#rC-FCnSCJ-+o);78|tzjHPN%?r=P`!e~XPS zJ#F=(9>>c5>2K3m$2(6hmHk+x?J>?b%XTIG@Ag0I{$l^-i+MYn?!CzN zk3sL0HK})u?J>^N$~M&6!S=GLsb%;ddEmqEU?UdCz(x+_f{onZ1UBj`e^2qNc#FiV zJZvM6%Fj0PtN+h}U{5@^rEjD>9Hu)_!buBh{EH*eT zHuzaarg-(X-Ao&0@p9#YUH&|6lZ-Qu{EEfr`vkJGaa_ z!DArgY~s#$V=wR+sJ$_LXKLZs9MgMB?XntW2RNp5P5rXv-X}TcoJ+H^6Mmm@4E5+= zw%}wL$5iYJEISeZ4aeMhGOFyO#Tgvqb2_4|s824(3@VN-t8r-)$9(?V>N5NeV-m6W z9mXVL@jHx3#G(dbP!lx}gPN#;7}Nw-!~i?6A_mxj6*0h$o)H5M&@*Dd0eVIZIKY@d z40EYW#9*$#jTp=om8Yjoo}M;&dP*LJ$6|xWVuQybcvN2;WA?={W?vkGz7#(kWAei> zCO;ele$?+c#^jk}OrALgT&fxzW9r2*rd}KaE){niW9rT^rtTaAE){niV~!t=F~<+b zfJ?<4$AB}%9ml{{+;I$Sn>;<029l?z(m?X`w83LhS_&SE(o*nPZ2Gb&?l?yEWl`L5 zjOxo`!;eLA$1#c@i{g%B6h9Ulo-Ozt^g=9t2fYw$qn8CW5QCbiff&@Z(cPlB;}~F9 z+;I%B+l(KJ;!ehoMR6zNhd(#WamY4mflF|QTHw-VJR^^cXXKIb3_NA#I0T+Da~uLs znK=&87sr50oB4&lI0k*$%v12gc}#vd2K-=*q87Ns7)33UXO01v80)&P{?LnKOuaY; zT-tp8KzEJ-mo}e27Mss8j315xmo}ec|I2ru&3EE|`MC--avd|5&s%J5oCClQEI2oS zjqh!oGr-38Ilk9n%Q*~eeE;J-0JfaNz?O3u*m4d78#QrmWBU0V#*F847}%(Za~RmD zX;YWaVcK8*r*APV1qN9 z!@xHC5v{d{M&+M)hF0ud-`6txy;|iBJA_s&3|(Vc)cN1C!F56_HbqugT%3O{^SBpMLH}H` z%+23ccIIqIMZK9XI8OcZC$>lS`_le{yU^1dO*FNz}u7* zvS^G|3rmM3RxK<~Gpt%T{$3F#S~zw+7baRbhCc}tEgWC1vp}?PENS&W$J--=$6HT~ zw<^Ir-YghzvlsAqvtYdak;dcAg7LOtCyzG^#@i347obN+jJIwN7NAE*jJI)(7NSQ- zjJKD&EW~(o#CWUr;X;fzM~t^CQx{^qIbys8uUv@n=7{lDt7IX@n+4Ui5l9c$`X6tKvu zZ zlx5ami)2n&&OcftbIS3D>Wi&9&TF#Rs$*3d>9p9YW4B(5rANn~Jr|=#)^X%u zb?l}9*0JfN#pscB44AhVJ+h9QqZXq_)^UH*Vylkx^A=lmthar!RmV%;EVk-6`iI3< z9gkmHY}Ika?Zs9due=a$)zPO;xK+nKZ-!fS{G(&IRmW8nZq;#sd$?7{ybr^r$8xU` z;Z_~LpQ?^Eb&OpYZq@PY72#GL-%Jm;>e!<=+^XZX@^Gt;;RnO5I{N(>Zq@Pl@8MP* zogRi;b$nWFiB-n|uP?FcSn=)>tBzZ{EV1eswoSatmB#uBTJ&QF(E zb=>mmQmc+1zp>P+<2UV>T6OH;xYVj+E6=4?9lsm2)T-muiA$|IcA2r%s$)dxQt7e0 zUEETuj+;}}v8Ij_H!ij6n6-1MRmZ3MmRfau{q$0+j{C1Jwdy$X{!*)s4pk$pI&P^S zVb!ta+YweB&vlBh>e$6O!m49h{|Kv&tAit~I`)_vVb$^cf(WaQInfbT9q+D=kRBaV zGb5}zzPVW)YwCFB%LuEE^^QhZb)0f8!m4A`UlCRvdpwD->UgYXq*cevrjb@1-)b9a z)p1piNUM(h+#{_zW(P)Eb*wcm(yHSNvm&iJ<}Z!3>gbaYY1Og*`beveWAY=V$MPE6 zBdt2F+^dc?b#y-&Y1J|Oa->zq^S2|dI^KUF%Bo{Q-6*S$z2Azm>R87<%Btfkin8kX ztY4H>$6dpstUA{JILfMHNJx}b$7!)qRvlkYjk4#-QN1{lWO|+uFD^HJ+t2TdG2M_%9_vG zd{6D}-qqcEch@<4W1tyF-<^SG9HaLIs(sX5&jgxr{Bcu$HYtvgj|0s(zWNks#<6v} zATy4G^8}f3%u_nZjAKO2ATy5Bngp3~Ox7vLjN|A5L1rAwj}J2A=;IS)#_`FlATy5f z%Y)1~21EpzajbA4$c*FblR;)28(j)g`)E9h4>IF8>ZSZ_QXESs3pV4}KTEI~M^Px) zjN_H^!Dbu-YX_TgEZi#CjN^+Q!Dbvs4-Gcs7&|4{jN{^NPGq%9iS;!z z>+ky1U~jwGMEJBkde~oUw7NrVqUPCx`k1{zk^fAviM2WZ&?^mlWS{6`6GKN7(06|7 z!e7j?iBtBRdTiixJGfKp0{Z*cYa+pqoc_=|WnZd+D?cu%uRTV<5 z7Tx~mZZ^x?Ci1OFuJ8OF!_tkniIpx1%&XLU)_$l>yj^&lrP-NA&(g;xI_y}>QfOKA z@f~cUzTwTn`sC4%yVyjg+_l)U&js}Ma=+H}xS$;iFQjLxZW9$E+ah<;Ggq*wxuFmJ z!=~njekZd{%?-Wm4|8s?S1-)D!R95HbAx$YGUo<6eb}5ETGgHA+;IMDjX5{$iSx|4 z!N&)fbA#`hWX=uVcZfMR_=j%h+%QtKFz1HRlbLhF*j?6~8^((w=G-ur=W)ypS#uem z(gmw?+?eo*=09>L!*~>=&T;O2Gf17|yyRK)9Os#Yd5-g*Tg`Laeq^b6jz_+kVV>jK zI4|=YXDP>;=QwleZ=U1qWqb1+mrF6tb6lTO-8{$jrzOmDTyK)gJjZpfjOID6S4v@? z<9hHLx{gs@nd&ZG$EdDsd6}+bR99v{M%OW_EBEXPROdKby5782vnLD8Yqi!f$h=lN z`?{LfYJ1Az=CzuK^)#>5{8~%%TFt#`o7ZZdx1xEiHi{QEuhoV}7V}zdT>U}!BdRO2 zzNh;U)s+XI{=6UMkEQz&a$sZLIl3QF9B=KX`w?%SyT*AqVCa<^-r~ zHTUodP}gev-ErnUH!|ly^Pa2C?QGt2SqT^Op38>RH1D}ATWRy2%QoaS@45QU^yWQR zclu0u1!@_6@MFp=P|N5m<0-G8^ReBvpLxZmlayCb9820Mub?=N*hqN=#j$EQN_bvq&V(gP5B|k z@#|d54=IjE{3t)9I1ZUa`60!z%@E2DQIql|T`50AO=?fwjPgU&q>(i=KXuR5c9r#0 z_gvPbfSCicpp0e?%&LB+JRdbFJN1n6eAJ}+YmHdI)ob*er~7rP*XTLVz*AJO zQ5^T%sa~Tv=GjE`8pW~03aZyAjwu%Wtk-%4QN2cSygG&IHHu@Qp;WI?9Pf6gdX3^3 z)RO8oisR_oRIgDSMR}^%D2^oyQN2cS?2?)4H9T9;uKX}-Qa1RdS(CDj@n%iRI$rcv zxf6SQ*jwdJ`n#P}cT*hOuA#b{;TZhT9UIl%6vsK;n3;g{} z^VtGtXUt~{{ElHhTi|Y6&1VaS|1vL?I~j2^==ll7(Rms@KcP5|pGeP7D2~NO{Cs}m z*_)o9P#izBrspRVNBLvp=KV2sC3=2Baokvho}W-0XJw=3Cltrn)Gb-pEPxQPnaQyLd8G~=1l zyNb7)PP2mJ{CK4TuA=%kJ1gU|l0Pi(D)PFnVQoin-mI>xh`L~79Y&nz{o1;UFC%)g zcTsV?K|fcqIkEuzl=lh$I>uF`xfG$Ld-{?u_jVN#bwix9c7Mgo&2bg`a&@~IzLo;2k7x?kph9&r`p2m0``Ee~-$+ErXUyMix$wUL*;<0@9a zHF)@q8T|QcSMg|UG!N?8pU+9*CW?K&&%>(};kmNAiTH-^`TAUY?QTWg#BHx+M&mNh z_HO0eMDHCbjLgfjGVJ5@Hdon;ISVxK?a#67z};1~z>EJ(WPX!;?cm7caje6OG;~br zCS3cEXW$#2Wi@Jqxr^?3TeH<&&g}=?#CV@e zto4g99_8aE8am%&WtMg40~@)C>w8|Y2VLa&a{I$~d|-F?Hn+Ff?<&SUdCyYs`{ulS zva4uT^aZ;)W2e@mfvX7IfA_!i3?Fe$MBGi$9(RvgmKm+3m9KVvX3$n$5b({$lQ; z>ECDBo5OZ?zPY>TQRfkBz!tHh-QC63r^)n|orbgSf4hs}?=t9RLJPBrlifv?S=se( zPAj#E0q(*jERSB$C1Q8CdF~?b?R@%}QLF96*0_smgYxMcn-}BPcesmkjdJTL4~^l| z4!Mg*!CCdVGYj~(D0dNlJw2@-SLaTLaep#!pVRO8hej)ijfYYE;Fz1lH}}lo8(w`S z-d!LWKbR_o4*iXOGb%)sDAu11I}=ZwVPYOuvb%i8B<(Na=V%2gJtOXwaAmKj^CRNq`c`}2IkCiD zvXvI6*3`TBhr{EEOM9K+-^0rh*C`pp`(zPz_!>L@ zA>aIXcqI62o@cz!Gan6H=jCJG?@Sg34$G9t-zDoo?6mC?@A+j0@wg^}zq`GKIA-)J z{^Qg!;@Yo$_>7Dkk&OGUe)781dp3FMR zXKf1+S8mQ`+SHvq$LtUhcX2yARdN|$IUz*k&l1HZ<@4tSy36BG?mnx2wLKqLH$cXCHu!-|;v;W7li~q_qkmqy4`J`~0xH&JKes9-NetES`jGXt1 zjlTSlm)k0zV+5RG?KUMhHtx2G*imbk7MH;oDQsfJTX#0Qdp4u>F`GCOSeD&?pVMd@ zWfOnR-J%@|%Vo5=ViTT6M$}xEGlwxaM(QKi+l%=-86o%N^N?PpcyzYZ#=d7Zap=|r zK0N9T|M<=(K3-hL7xul*8+^BkD^m~fGi@UI{4^n=&DL979~8zvWDXJaqF?i3pL_7Z zc|yb+=M=`X_;mbE;SfGVdMKOSp_79yq` zPi=TlZNl6dhKN4eH@>%g5NpvgMEIY4$hTkE$jWyL5ovtS@xX-RtZ45LQMGIY&$>32 zl^+};imwXch5Nr`tw+oAXlZlq*ZT_#ni3)wba`&Cqy1pFyhB8*H0kV{Gkj%@LPEr@ zkk;Dym#^5qun;kRY8tjNLjr5OOm1gXC)TvwS(dOaL}+tt%-wl6+b-wQ{9$WYn;YS5 z-kuQA`KnycQ_!7-?++2h`bM$xr5dp-$3n#0ayMCY{CJ+dQizBj`H?&SI6|DN-w}TJ z!bjrft;X@h&gl(kR#XVId-hLD-0#j^E!yW9X*Q*w!4CNEATBm3n#u2((prkDjmNM) z8{&vx%&5e&)O}1m?$#Bp#=;lG1=eJ-vfZMwTRzJzV-kOunA*O#OmXrRo~EBY`<1mC zG(oey>?Lz#cLq-n9%Em)Yp@+WYC|o1p(`JV8%&Lg3@uQLzkW2EuCusbP24e)c;?O) zoD~WtuDSdKf5AP7Uq8xb%nt2K+;*OB$UkCfGvvP!ORXV4L;EGiFyvUoa%=-W@SpSv zI|suKA7JR=1B`Lt1B~(U2Zjy*28I@&0b>m117pJn?D)@OXBIuPjH6q|*DZc^%l7D& z?bI#XuRFZZe!;Hx7kXmp6XTFh`o#Fe(kJ{9!-jvuSkU4#V2mNRpBQ6X<8>hO68%K0 zRd(nk8;Z|GEF%7Xx*H#{b`J5iX;*l!Qh~$=G8Z)R<{eGEeR(qjfA}nH_%|@L_zW0h zU@S1khCeWTN;^|_sV9bBj-$hlapd^K7+?Mo!>9Z=V)&GwA%;)sgBU)o`)IKdvwco>Xz-NW1O^Ku&e!ro)|tY#|PsZ(8DM84Gf>yXU8}NbsP&Yd|Kkd z{twrG5c=XT)?OAPSj=L?)0eqBub;ZYu~)IA69j2=Lor$~qa#@qs99DEk6 zJ`2WYp~0W>r5MK7eg^B-fvr)3=7GCt-feb!+! zw@0^ZC(VD1gRw39Me|?TEyqEQXC5DnZzSy({1U?__8E2@1IzKJ`477~W-7jkN%379 zV~b4dUJw7C zuF)~6_Q_2LV}HR@N;f0>F^|#u`d*EQ=MNpP7n@p__;#Jiq=8;(z)Ay#W>22xq_4Dd z6fx}JgD<;~J+SRxda=Jd5El&^thYMdn%HyWFw#J;G+?CxLvyBCUeX_M4kCsfoRXCx zd)o27`t47}i1+95*PCuEM4Ub%fHcr64OnTw&|GcsC+Qpf;Y$oVICiEp*-Pwn*G~sl zBQDZzn!b2sMdFB|-lTzEX~0SYh9=djaink6sWCC^;6sU?WOoXwp)b|lh);wty{`Kt z;(uK0kp_CD0V@p{noSF*l73-Gbz<1TN5=Y*y-|*m`oR-E#F4Ga>eI7&6DONki8RnF z4OnTw(AcB9lD^>N{=~3@C*K}O_8-oj^vLjj#Odwb^o|XC5o^VJlLmUF0V@p{ng;(2 zBK`6X9f@HFH@-cV?7Nya(NEqRNgR@)h2HksP~znFHl%@GX~0SYhUWN=G^D?Dd^$1g z-~%=Dko~J)kpALGHe&WYSRdIi6Y-3pA*6v`X~0SYh9;``BaUm%$s@CfVFxc>kebG+ zl_6C3dhvrale^5&zs!3}+&gS0X`ojcu+o5`FGcNV%WhxG55)y<@+qXP1{?< zUkc38zim2CT(;a?(m<~?V5I>=v+dnd())a#PYgTw^3p?OAKNQT<6vIHAQn{rRJf z#Er{3G|(#zSZTn}EZRDX^l=py5yK9iHGeVL?-X62_n$e_!Ep=py{^8*b7m|g4fIMw zoTLFm6XjZj^qr4{6T=RUju}e!=`9!Oot<4B(7d{vF^M1GU?}dIyBHL4OnTw(BwZ?a4*K+EOT=( z?BLF>i)fr0M;7aQKC~sy{dBQD_xz1W=pe521lxX~0TD<4BD>k4TSm1PnV^o_A!&xhBskVw^AXTqDML1P$~`16CR^H1aw? zdYt26*unC;L3Ug#cu)J@Q9rsFk zPb9|uPTnhtaUX;RdZhs?4Hz1EA16KT(O}rY^1e@Y-0S5%of!9Pd9NqNeHLVDyFVA#PjZy`H!6`7L|Bj1p@3Ni8!XrNabu+o5`k$Dv9kt2a&2g|&R?8vob zPDPA-N#VnG+=0C9!`4X*kIVfGFK-%a&?)L z6C>Z2xjHfOaA=@c8nDuUp;<9BnDlL50(UY$r+LLc2HfHdQcKlH@Mfy4#- z=ALrH(LW(s21!P|B^{KntTuAeU&LYgLhob-p@(~1ASn3goqD-Bp_ zz|h>>Je%~LpW^$VvuS_9pL5P2`@DR~^&_2U67$&iEN{>(;=yB|kOt!@4OnTw(Cm5^ zM*8A@oEUcSg*y(v!&b$x_wVMAW=x7ptmUV<#LZhDCk^yU16CR^G#TbEApN$UVZ^Y5 z8x@>K_UaWP*_Q7P-rRZ%dw+30*$?+xK^o|l2COt-XbP=bMEbDmJ&9olr!X9Ti+`TY zj*eJJn&uDuS(z*j{mszvq=8;(z)Ay#=2Di$^x3QDGZDiM?j{`LRPEn|i8|q=5zp$d zux$=5GNdGFpjR5O(tx4a9^)AQ#E{7v7=q7HkJS83Uv(GIRRCsqsH=HRGuTS-IX zBx%4(1BOPuG>t2QQk{j_f(A z{cW5q+L?HN%7KRK((c3~L|@WCuQXt#0YkIbZ8+%<-E2h+JGf??!*5#e9!B1>14y$o zeHSBppCQDjJ=&87dZhs?4Hz2N3H3?8V(&y^*ulxBRw4VR-d@Jw(3-?`|MWBl+H~TS zp01>UUTMHe1BNDkU0c#uOf{4kcJQ}h4ak1v-2~%k9T(#L*~c0)zP2D9mS-espjR5O z(tx4ax7~3)Oj#-;G3?-JtsU3oxPSu2p^HH@W{o1bjatoY#6vb^B@OgS16CR^Gp*ujIv z6dI>qP;Fz^C=cS~Giw=5Q+g3M@U2Q3=#>VnG+<~V+$)p*?jA2<*uj}@79qRX=WpCB zQi^y$AwT0`mvY2=$M}#2dZhs?4H%kFXA6_Qxl;f!?BM3JvXFi4Y@3lKeJE{1HICKl?Dt=|4WX1scx&+91J_S&wIypDYa7u<40>pE_Ziw zDx?1bM?My{=^JUFR~oR=fT20w*O5Ez=nzE=JNSKON6yC6zvN-gjvOq*jJteBM@N3u z_RDqBK(91lr2#`zud^d}^73C#3_Cc>T!-IJ$=b11@*FD=XHO$<9Y-86^acV*Uc=jM(a%(>zsUOJUSpT0yWX`ojcu+o5`i5ua_ zmxkx7P7FKodB-?^we;j^hB|VvOnE36fdlN#ui2COt-XrgS6eChF#({?cI z;L5%ZzX$47;{QB$@Xc+x`P_yMy?>#vq=8;(z)Ay#W>C5%bUk^PWk)0!b}(Du80Xpd zgZ9m59Xuj*rhU+B2PfvQZHESWr2#7q7#f*}=(s*0#{k0)mbnVqk*mm@gc$jT%vFey zhd=|p($M%x8Zb064>r|T!k2U2sF?u4OnTw(8xT5^vE&5 zu!CJE)F(S~6`7L|Bj1p@3Ni8!XrNabu+o5`k$DK|kz;^i2g|&L?8sGQPC|@)L*^>P z$U~rkUTMHe1BOQCA*4r+0frqc^A@rrSCKghG4c(Ws}Lg(fd+b|0V@p{8kvVUJ}Yw! zFli*qT!rk&Rb);=jC@1pD#XY`pn+a#z)Ay#M&==;M~(r89W3(}vLjcKISDcH4VkMD zBM*TFdZhs?4Hz1khmamQ1{ij*%v;EgTt((2#K<>fu0o7F1RCg-2COt-Xk;EjdgK^j z*ugSyAv-pjR5O(tx3nc?ju|V}M}?%e;l`$W>%cLX3Pv<|@R< zL!g0PX~0SYhDPQgOywb9*pY9@yoJU=t|D_1V&oe#S0P3o0uA&^16CR^G%^pN@sVSI zVF$~+h3v>xWKKeid_(3c#K=RSfnI6AN&|*Q<{_j} z9wIf+D-Bp_z|hD%g!ITUz_5d5-a>ZdDl#W=Xk@-2a}{FbA<#gtH1ydd4Hz1khmamQ z1{ij*%v;EgTt((2#K<>fu0o7F1RCg-2COt-Xk;FuA->2lz_5d5-a_LbSCKghG4c(W zs}Lg(fd+b|0V@p{8kvXCd_ax?h8-+(6|z&_vcT~y6#0hCRme_xh}1x@G+?CxLnHGL z(j&(J!w!~t3)zvY$ee^2`G(9@h>?dt1HICKl?Dur%tJ_z90LqHSmrHcN3J4s5@O^V zGFKr+9s&*YN&{9JFf=j`Aw6;oFzjHNw~!sVip)ufk#ERcg&27VG|(#zSZTn}$Q*<8 z$T7gM6OV8_=R~d|a}v@Z-;lWqG4c?Z+mK#q@L8n+LnHGL(j&(J!w#0Y3fYmX$ee^2 z`G(9@h>?dt1HICKl?Dur%rQuh90LqHSmr8Zr@ZC0LxX%n<|<^TJVa`sR~oR=fT5A= z@ko=j9*;f?o|N42*@`EUX&L1EW9WyBd{#@Y%Ob|QEHKU;F!W%h2SY!9N_|=zhILtK zrq?0vzdbe29aEin^afwvE}|6i{3!?d_c1w$myQ0w@ki^&qz(TDh8CXzV+@Q1#@K2d z7<@`QQ+BB*hF*?CjB(`n#PBKqbm-wz{u?oT%FhtPr}RM#pV9|$(tasBv*?*+9A+7x zS^Vmj?a?jUsav++T&D-0mi>jECmjcjLkypm5_3$w-xe6O)V z$JNTv!;WpiIAClG#s_0t;1`T-!5Sj$rt-j8Acd9X8AM=$7r&E!$6V zbd2MOBN*FaISv?y!;WpY95)^N20Qi@`|KFU5l1k5TH-=+ggt4$NRR#f9k2iX@j~yj z(bafzEHK8#Tmi$U zv@>N#A4a9e_e#JRM~<(9F~0mGhEMr##PBJ75W}bRK@6YL2QhqF?98I4KB5>OJ}u+x z7Qeb>dvwco>Xz-N^Ug6&JJ{9!LQf2z*w&=|!uUqge(BgZFnn5$Gq#iL@M(#Q{BF+A z*jenqtq|E=SN*kxEcntor%%7`QEm^+9&7;^{n0gSnWc>>1V!57| zhEL1!r}GYW_(ZON-_^%{;XVjf_d77|vAA!7agW9Q6pVW;{=l%|-@wq~GhmgUfH5|F zfK`5??6?OjJ@NrC#=$)sjPd244u((pZ^ZD4`~-IRL{0!!`3X2_zm%QwlO#RmCt&!r zj8FLq?66t3hw>BH;S>1@7(Olg1v^)E%W;me^nd5 zWT!&?HTdoL?KXSWI32_HXHPym$rhArM&F+u=e~z^O6g7CpS^uzEz7@SDSdy|$9W#J zb==GF{n@x9$s6{6YaWG;62P5(K;>X%!$!RpJxq)9r?#7W;5 z#&?0qul&AnBsl5&!uTFBPx`(vankpN=@=&Mqt!2Q(mv9@Cha?y$Jw5AoVh&Cw7>E= zb9tP}uRP9N9%u3^k29CYnf%J*%;j6yd?oop5XOAZ^HSe+QyT^o+J!R%dhCgf%Y}n?cRcFm$^>ffRL7w0_rl`-U&GZWxjFCJmi-7$u0Bt_iqu%1Bvhc|4;cX z0_$A*uf*Lte=KAEYrmUe8UJ6qPFl{Xf9;xPxt{!QUw{6s>jRzv;}6FS-)RS{?@fd8 zU2x0yyYYQ?(%`$`mhXd0oB2I)`V2n%`+M}}?+NIZ-lny-@%jrXA`^ZC2p~NI_tmiC~?iEQ`zs|^a~OHU;L(D+=Siq`-C$y-(#mA zR43lC^DfmNh*6UYi7ZuMDE+qK(1CI6?a7Q3qy7c1u?D?c6AukI#e84+5f}Qh=RZCh zU0|N}a=-j7xLk4U)X1FdVnm4WTYrV^AJ&7pt_Ts6vmTef>o}dwkiR8(F6BS0@%{BI zz&At;2wA|c@%`+X{9VD`MaQ$%?ibkRLGpL%232Cun%-sux`c>W=O}I8{sd+;4G}%O z_T zS!(&4dv$9sGw z12@=v6-ne*WdDeUSMo;Iz8c3PWM7GLQQq1g@(8WTCi_HW%*YxIImuh3unE`Q?U|8m z7jO0^SloIY#5(6#%q!dr7N^#%VbgoM^W9g2#h8ry*f|>`-gtPU1gT;j>YuNRJJK2o(!D6#ZFk4vTBnxdAEbfo%z>4L&#;R45 zJsqxQWXVp%vC<{vn4^5P3B?lGk6gi`!TpSpxm(Awg=vFD#-r=(y9-}t!#)Oy3-1f^ zh-*h!ZrMZOQ}e%g)mqzFBiTctVx3uhVjcP2&a*+{&81CTxDRJDWDkX$g%0tuKT5Gi z+k!;7YM1z|HHMa2_B5%|FouuJzsT85_Bt8$DS;pP*vmd#_CSeukLP?*az07+MoGQn zI`46}880+2NEBRmnunzG=V>|ziN25b@HHJ*^7Af1;DJsR+LS8nj{`GQ2lk#FqpUdHo6vWLRsxZ3udvhQ;KZ-F8#*$wB#@4{ zajH}t8?!nGtJ_2NK{$Pd1x9pd_ge&t4~>qq^OL8uPkNvz)8rrKwqiYdQ6W&wzP^Bk zd+%r6We@` zJ$jyXuW3)0P3yD}m`obDgbix-_9 zd8AK(xSl+bA0HTLuhT9-B#eyV0b@$?6b%Bz6YophHOnx*yGnrA93p#tE}zT46blfu zdv4~<|JlmF<_r)WV`uS2BaZNjX#zw6V*vklIhx;k?=MCM{lS-(jOCji_zU0Eo9wy% zNaS^H_>20-N=7!l7svCT@fVZJd1()OT;tjH`HSFs8Q9^4C;8qj{^G`mcFe8*F1~ZA zzj(APi19v)`TUvwVr}m=>_J8kUew!P47gyh)b%y~bgaK<()Aom{W-zD_%DC)DfumC z*z(z2{5qC(se5iunqt1uNB8W zUeC@pr}7m;o?T%D-gaXh-uZ}DlaI5WC8x6ivTs7)fPdKB9_v{***9TP$%U+Dv;FLt z?3=J8Z~`k=<^uEMKH|!Y%B)_V+f3i=BT`Jdpt=2%z(SY!i0i&jo!@7bEc@1_&r{9b zO#XK24%yFceE4(w{ZD6E?=e0iu4X+x?5mws>+d7B?(*Wz%dcWrI>;Uk8pig z#y+B9r9J$0v6d{XhL6~r`!wf2QZiP`N3`gComW0GSgW7MM@;M_uWf7nBg?1v5yw*} z@&iZr*f)Om7NdP*__qxu_~<9zBGtxAJX!alyy$Ij5qbC!XYJ`DzTI1N9Y2uwh=}G*S9*(d?F;jH*UvE)s zPu0jGZ{xWCL~r4p!&CEdzb5a~-s0f+^eorule~CWZ;^(zW4XO{@jse*i_0y7*r$z) z`47!o49vZTrQGMir=xsdYqF}ByhNAO=h=^DuI$rcFR{(o$LdrL zXH#~0iD1{YY*YQ6Y`{7%k?<^-9lUsg4PM|SNqLEJQ_4+vWb&8j$ zup>arRVtBP80IB{a^Ky1a(pZs-OEd~^I2`*I`lGYBzq-n9aw-DYIu~rs3W)GT0g#U zpIoyodnHU>Jd-Ef3}d;AdWmbzH}PB#MzF!zy~M4p2e}?vh80XHKYQmQ|8{4;#ve=* z_FOT%L#}ns3uI5sMlTcigRx!gUb0tam3i^}`i~#>WwWM=xC{ZMy1E4;WDAN5-HIh}Bf6*`-n zAB^@Cjq6-t#*amIx80tiNqj6@vOE9YTMIqKIC&1vs5MLb%fnM7G>c;cGG}KM`*@11 zS+6oT=Wfiio~M|!={P%lDTFO9>M16i_=kn&T+e)Ek6O2J3)!a3`&s{o9-=Rs$jW{{ z&k|30h~&Gguw~zGu{N7M#NeElv{{=H*t1X%VN3nSxn2RuV?9Kz%a!b1n%-n}I(Z2H z?@#S{N=M0a%0sN4P?xWE=B!R058>Y1i?^7tin)Jw7lr%CbFg;+D;Dc67Qfuh^Ch-q z$q%}V+4oQJYG+fiHY?r5_ZruEM4Dk*Ctr8*!X=)k>o_&C>=1Y1n?8}RDzV%CXA5_6 zW?>9(mr$JVE$1$toxj9et@@kicXAg?KON$?lg;HzUbu-JcQ*6bvRnCzXg6_h>TDj9 z>1oF+7F*-TS>RTkRk6Ch|hP+(hvW^&(HCkk{*a zZo=t;tM+8^HGa9Mn}}JTj@ABhk{3zoCX#!!Wit=#;@R%GiY4y@S=M)p`MHy>BJKIr zEOxjjf3ewBT9TVmLMrGJ67zk{_VUGSGLN6peFeYdly+-JZWV|&2k_zp8b*D?u?oxC?SD`tvI5gW*HrQo8`DzmTH!sqb{;FA4XBl z@^^-VZ2EzDRI}Xm+Q>Rjji8!k!nPT#?(L&gvrOcDSd+__sb+beHy^vXDVA!M`iGWj zPGu9RW^s>LSgVd}9MvpeCxqBbOt?xli|hU@Ji6`)s#zj(bm6Q0b}-Z|594h-S%*ao zHA_&_bv&}+WQLk0dXV6uZ>llWECD{}dC{n=8funhyKnJ!DN<^vSz6Ca;8oj|vZH1x z>zu#`wR~tt%~EjTO@5?yZK_$`ZH(eG_f4gmW%>iocls@%n&n)R)%=z7ZmL-}bPD8I zx}Tz&FlY-a)@TSv&Eo#oVRp5DF^-xg zYyN1KHO&q?Y8G}VhV_{^C=xYG*{q3dZSyf2YL>C(}G|(ucDfz>-i<@@McamOT_SLtc7P3)hu2=YP01YH>qYh{@{@|reXrs zEGOptsU2G)S=KE1e11e;Ja>y~mVA}2*t2XsPc_T+iq-g~<$|GR*)(eszZ1HSp=Ozx zdJ%tEErg+FdEH3%tUup{p=K$a=>#7boRy(wN!Q^j56&H`p=P=DcO0K*cZ={-KvD18>@6rLP zS(uYxbrIN6q5Y_Y8aT z^s5~;OGud;tU{%BcGN5fw#2i(wjIu>Sq|S%VAYZz)=;x_etesSWGG8Di!uKqJJN6z z)hx3b9%Nm{&ZC;;_OXpDN9_ozS zHOr0$2|Q-oeLHHFzjxl`H(hnAS;k$B;+34HQq5ASxWON2OQ>e)AG(^0PrImQDYh|? z*DiC4YL@0vZMeVv8r3YGPt)@3S>vf@S$1KPy-)5$s#(&8wscCoN=XE>ns9EaBYxtdE<04VBoXV8QN~Rg9QO&~Q*~`GxRI}vFcb)moZbdaqWqyja z-W)(R%kw?ES*Ja#sAjp6Zz;Ppnp4fv)X9sDZ5Kr~OSZ#x*o%HQsb)#$_e2XQkw7)e zxGUwgOlu^|n&sw?kCB%i+@hN0)vRdyuxsb3X8Am{D&KTNFw`u)V<+-rm)9}WEFU5l z@}mJE3^mIiDR=N!Azc}2mUcIe^QxV)G1M&kDqZDSB4=o*S(_yFTTb_d- zr!KamW?6kcmQVN3Lp965f>(G4m)=yfWNLDZcg;A1YL*u=H54`X8EJg zNA2R{GgPx&-rk6P35(>YSqkp)Veh7`;HX)e_gc=TXZGW$St=~w%Z!~a95qY9%4b;F z!0&d{EORs5V774`?WkF1u83#fGj4H4&2sih0*mZ_P(#g3+7>$VG8fvz)CGWIwg{D%C8l%4Fu7R-d4nWl4A^z9jWdhMHw6v++@n z7ctZo2cuXA0X< zvt($Qz$<0HXGhKAd+sJbwue#8ayZ2~KBKoM)ht{382s(?#ZwGv#HH$|`Ti$%pHL6)$Bh&GP$>XVJ$(_^9UO8VP)hupG|U5koc0nG##IrPHIS zW~rRM2y2x32uID*zu+L&qw-dcnx)T_*{oCAxg0gipRt=+rGNhBs98$AJH*0X73Zi~ zj-I{5{9Sh2QL|)O5W`yZpB9OlrB?bxw(jsy4K+)~X7Mc4NJTZvbm!~LcBv)REK?t! zVk5c)P|dRE-EKB&)GDf3$_-q~L^Vz|%lv^}Y*_Iqs#zxa)n!?l+@zW%dy!|_u>1*B zvsBGnSu3_VfohgJp06WUCc8~F%f{Ci?F*7$pql0Fnku|!j{OWZOLV!3ykY+J3^j{3 zVj=gu5yDWj{CW5vexzwPhMJ}Iy5s!LAK4jdmU>QCd1&`p8fq4wrg1!lPwu^_Sv<=p z@g$WNojH zpqgdSj)Tnoav0StquXv`<@au*nkCDsne0rRqg1nGdeDz;8+@5+mMjwsFz0cxRI@Z* zvs!yoGLdSQzE$qmVjJVAW+^)>z~14;RjOGs_IBczubiNoT{zi;ux^4aAg$#n8B;)aJwtt~(R);yG^6hP_%Qd8b=;C1pU?}KKaura`=gi93)qO4b>EBY8_`472#7Fya~l;7 zn7z4;*C);1+{VE5Kl@f^kndJu!q=46={=poDBCpUX@^9|X|-rV;3MFUk&=g6#;&EDMFth#~dcZ^=Z>_=;} zH#ghY+w9HFa*Q;4b2E4MK7>NF==pn27%6DEH*9N19 ztp0ZP&%V{+E2wWZ#j)^q>RU~5yncZCR-+d%%YL5vR#O~D#ZcdB^pItNPpNOUE_*sN z=daYa8a-sS3mMJc+|DcVo4vX1MgKH=bMslwW^ZoZx|!LVo3HL__U7i92AjRPjpP%} z-rUA|KN$;04_Tv481)}VFJL3bGU`8$UciRG$IrgiRXLoz>!r_o4vWUe{%SnaV%2Y z?9I($s+zsIS@niyZ*I1vo!OgPpWWBrjHB~t>OYQNzOW3#ToXk7$0?4vhWzYX zZA_%T)fC72{?xac;`k|y`c_jMtF58F)fC5>JE(6p#c{(S>RU~5?0%8@R#O~b#Z%vE z^mKMU^n&_Uqo=dI;dkm=t;@N}|8X*VbMuk1c2no$QCZWe^Ra^NXP%G6T2TLSIv-DV zr~c#U>1>Q1O8v(vj@8Fg|8a`ry7oW&R=4a&eXA*s7e`ayYKo&xzL!zw;}QA3MxBp^ zmr~zqilg%u>RU~5d~8tPYKo)J8R}b2aqMuD`c|Viw|42Fj~T}XAAMABZuUK`ujePQ6y}9*njj8`Q#qmc+>OW3#JSyLRsq?XB?Vo+CZ?~Yn z)fC76J*aOr#WDXd>RU~5?Bq&)t0|7#1F3H{#qrd9>RU~5bX!M#t0|7z_fX$zieutY zZ`EVnJ|Noc&CM?*n!UOCjMrvwZhkL0^&h9}YMZRof1IwXjS5r$af;)kiqwCc;y9}= z^&h7=c5X)f$0?2{O8x9xJ)#Ent)@7>ZcKfvDUO>vQQvAhAMXyJzSVR-)*nZGt0|7% zy{T_C#WCY->RU~5T)o1}ysnOmFne=rZ-kc_$G@V?-rTHkjM<&EDL4 zbb9JPPH}Y2NBzesjz#{Y{^JzKdsV6bIGvB%is4;MvSheFey%qa_YR6r{dm0ag4q;RRnmXr8w67FjaI8$w6@(oZIZp?VP5%*_+#* zw!PV#o8KF4_U7h&XPUjac_vxksq-;L)_v;!c;cbio7>2ciu#XJ9RJBd{l_VelL}G) zaf;*l5AJFojr_Sh%==@>>K^9(aY089^L)%O&ci$(56|#0?~iY{cwiqXj$O}sU>_-t zfloZlIF?TDiMdMWW0_L&{Z!KZF-;Rs^L+Fg=xLsh6?{Fhk90nMU+!t%A0G-&^SW9i z#uN7rilfh0PxJohB;SSMd`x?!fN}kXyNL6;sjbXe$VhS5T@=kVN81o5`MJ9Y>YQEs z|Eou{^&Ji7nOax&du`b7wPC;4hW%a}_IqvE@3mpS*M|LG8}@r`*zdJrzt@KSUK{pr ztquFtcUyk1_4>Wm>-So(An|*x*YCAnzt?*GUhDOHt=I3hUcc9R{a)+!d#%^Mzt+q8 z9g~9N{CK4TuA=%kJ1gU|l0Pi(D)PFnVQoin-mI>xh`L~79Y&nz{o1;UFC%)gcTsV? zK|fcqIkEuzl=lh$I!1oy5+%8f++W{0b|_oN}uC;OfKdBjzWALzr&wmii3XjgIZ>qK$pW9x^jK*c0?cK_` ziQYR>&~MI^sNp6mTu*6;8>_SdE^Z=i%algo+M>+0tD6{G@duxEcN81_x0^T}^NOe6 zv6wZM-zTb;Hjd|v*vCExyNQ!dCwRu0H`vT@H_^T4Cf*_H6-%?(P0U*o%v*+}(EA#0 zqF(cs+-Z7xeaRU&(Xik*``iOgy13;gQtV^)(%&-cN1n*@Ll(chl4+hyIw8nKx*n{}1_#oR^Hzt6Hahwbcq zb9d3B&Lh@;D z8B6bW@%~z0+MeF+;{7!%TaDiB;{7!nmz&=0;{7#i@X=Gf_hd2GJ=J?pZJXUwz4vs^ zyu^I(X?L1tzW3yn`kC)N`R@AWdrzLOnEBq5*OY5klhy?ptsZ!&_nt=>;w{@ho78J(`jcKg~#W8P9T5CaZ{85V5THyUPYmFj%&eP}} zJ=P%@<0sNPdaOe*QY`qnW~NsVt(l=XUY$Z~X0Q&yC^VGT%upQfcBeHnSckxaTGE;s zisR_ov}T6lD9Y2C8H!`cLbPTE>q#QJWTrJUSQn&S`C+anVS`_q>q*$gcym1o>v+*y ztwUgs4|}V12>QF7wAKRaN%XdBXsrd-A?O>zXsrds@s5qwT2LIvZuz

C94E`$Tbc znL%rxD2}01Y3&omvEyi3`$Td4(2v$WQ5<92)7mGBV}*va_KD&+uPUv5qBtHaPHUgA z4#D0e7p;B5Iz4_hwXa%-!1KNLQR@)+Vfj6dq;&|qyZj!9Iv)qh?{Ubrh*(cz?6=dJ z8H!_`O|)i);@DvYt(l=XCLH>?hE3l|YuG4`yI0d1Hj3j{`5OXq?GwfEi2Mx!bv_P} z-^WQ>Pr}>C-w;SzPr{dUr8R66$JEVe4I9O=hUTZ%1!=p=`eCgF)_1Wc1-6}?BIY_hzA~G+PLDgMG}q}Fjo;E5Hj3lYyR?Rl;`shD ztzn}$Ryjj!*eH$%pZ;7^nm?A-lu{h$ouf6S6vtcpX-z4`aa9DZDW&t#WhJdCrSq}E zoB%V99zFqTU6B3mICH&aWX^%+dP{9?XLG$JE8$|Uw`4t>yOUCni~_LRfTb+bIIr@3yHUu$Wu zo8?}$&2_UpZ$)$6tWjKkw^5ys9$CzFv&PjQw5F8enDsraDWy0r&l9Zn(fE`uSgr3e zCVZ0XiXH2_3`72|jyfN`*e?`;n#Q`sc_uGtBkR z+Bh$B{WD8B)?EM0T>6{qpV`ay=K5#ZCcs?(tk0=#u7B2_mN3^p>rHZ*>z{Qm`MWym ze9T3$~iU^Mcj-EPMBrva1 z?^*kyHt}}hah7Ih8a+!N`Fm44*0K~@R(*U2o2YMiv#>sS^y4lzktugAw(N5Oy}fP| zYkFMJj)fP}GgY^V3XyF!>u;|;nRS%U+7=?N+?>s{sXKWN`JMN;i`&_$lFRr?`91gi zS)$maeEz&Z_Yg6*+p17BE??m2m{5+P#7jx_q|U2E+RGsy4D4{*|* zS`LnU{>mm&z09W9O5acGa>FM4dgs(HZv3vLKV%bwcI4E@g}Sik8|3d_z0I!w>Nnz? z*5#yr#2LRWrWyqO%i6x0ON`!UU}(TfW3f};KxJ2-m3rze2>Y+bw`vA!F3$MuiA+lj z$&re&&h3BY%ep=IEHvt~id)nvL)(z;<6@&i(fP!g*Ulw|1`G`tnqTR2PI*Y5)%q_s z_T}13Tz&Ooo~vCV;k^UY!7^?eSt49e94}_ z2KEa*e@j(rMLeWL7h-6@(14-&m0tE5rq80+u~T!vpvST7WlW4d#j?jS zG5Qx{d^INYVCb!Wt>gSkZ`~gF!Z^wojW2zxqi-_CS7SmChTiJeI?k{3*6o2WjH7&k;Y;>bCco&d{Izmj zVwa775kmup1`N%w^s=WjeHJ~PW$$KU^ktSkor%$}8RM%lp$9{6^=lpHS9(=T~~`_P`g$QNF=XVJ4;_U0x=-)-5mn;8ALF}@lTdNA}>zt(YnrMGSm zd|@2r3k+YfXE*sp&+a`R3KJK2JcSq=jOoKHwN% zjR`#%daGaSIKR?cw+Fs3j`9VDFWD=c{GwO*;agdVXE*gGh6W4`7@A+{Wsh?DEP9m7 zUgX5+GcJ3S6Qln)##duP4~E|A*E-Ix^w#ZxFN~vnf#FN`C?~(@QJ%W%caGfSLYO}> zG+=1J(ELg-d!y55(HmX%K&LU$-(2=aCr00MjIYLo9t^$JuXUVX>8;xXUl>RE0>hW= zjZWKx-ss(4-XiYZEtnV@Ff?Fjex;W^+3B17Xk`Yd|T%U<)u=p!$C&^zq1zdXiQV?qyx-s;yn&ad>=?SU_hqkPer(wFQ(PkzyZ ze%9B%#CICcCWZzK4H%kV=|^vEN}rvWDI7iSiP68l@W?5|=xdMh)tJzOp||?Aj`J(M zb$j3o<0xNX_&RvCA^Fuyh8t(2a}h6*a}o><7#c7%ztV?muc?M=-(j(_=0G+YXU?~9 z<7CIO#8nqL##duP4~E|A*E)`M8?1Wk_P`g$QNFz_15iy zFKCo6F!|~`m;CPN5XGBRbL6Pkt3(q+13oS_U}(U&7yQ5V?=#OLJ5T?ThdIwC&M@OH zpV4s+aoaD~|6@$(F(&j@zt(YJSKDCKTeka%dQhxvTyGes{_|;!-1a{>PZmV@&9+ey!ucuC~Fdw{8!7 zL8E+u;p-QdcV*Uc=jID&Oy`P=c7X=ep(TVQKp-^fp-B_+ofVoWAVoSVMG!=hrbxRY zneuu0Uv}!=_@|bi9JAr1K0}XB^mW|Y5B6RTmA=l0SZEvzCf5BY zj#CaV-Eq(08`HLP>5yfo?!stbG%%We`p+KS_Rp=WFW0^HrIw$#dhYJ%wOaqjF7TfG z+b4P$eI2*wJiXAIE};wexgm>$+Z?<+=&G#XilNaKl<(AB54sXkaw`^qn)> z{9paxw!tgzYkAM%rws1=r&&*SXbx`swSO$qhfw4R&rYxsea-d|>ifX`wd%1z(@G z^V#pT{j=E_WdKG4qk+-%(_iy+>*uar4jLGKb<6iJb=AO)d$+v$s9#Ou6FolB*Kun< zbq=+@&WBj|aV(fvTi)ER4=a3qi_U|4w|myXdoM0V1EYb_^wU2)OPl}W56svZb9H;4 zF1X8Lotsx}`Q}$wox~@4e4?-8)_$-%hgx6fLo76o1ruwk(yr}`ynAZr(4Vz?^u;^x zD@FsOfzkBSFK|KIKVw$frnC4gEk7}Qzs`^MY}eZjes}C7KGEY7eI2*ZsjSZmMU?!PN7GokaFe0F;GnsdZxU^FnAe)<_sZ~N!!ZN_xoeyH6Of3)rSohv_R z{a>-sm6P~Hk5BY<+}aOz=TPhGe29g{v0!37_wJiX#<5^x zy*p?7e0$o*r)Qi&vfQJzMaqC+~?)a9h#SYB3rZ4UDFr z{_#iJXVfQFo~n8Adne1!t`AMyJg`tZ2R{F`nI`dx9-rvzxV0bb&Y{-V`49_@W5LAQ z`^W9I+%?^z&FY_O-x+TF`W#|3Fd7(5KmGZ;wf%$sxtH2^jT`z9!r=PyghgkS=ESOkvZY7_2o+Zw6H0fb9=+X4k$Jv(Ja@H1S zXRV(&&x&&{G3Q)yF4psj9-n!B*Na>G>8G#rAr^i(ry~|jtT?xl&pgi(=Q)}*FdFn| z`sokZe+{+etS!#Y#GGfvIhUAot~eL#`9zP;JiqJ3t^M@V*ZB|&KaK?xE6%OtGtaZc zd5$JMj0QcLe)>4uQd`d2;_OV!c~+cri8<$rbFrRJ^!Uv4yI$PdPd|N~53%s$STM2T z+)6(4JWHJCXwt)I(4*<6kFzbc<*Y5v&cvK&#W|OlbFMfS>-j{F&pf~D#jXAH)7SYB z3qOtp6D!WG+8o;REODNrNe`n@+tBpW$Jv(Ja@H1SXJXE?;+#v&Iai#E^?ahoXP)2n z;?{op>Fa!mg&)U)i52Ho@|ovZ;yg!_9!7&6O+S5{ZK*A1ZE$7i13_2Slk`swR@h=m`=f{7L9R`QwWS>ilLlO9Hc9!)=eoNcKsXKitI zCgwaV&bh>#bH%w>&nJ3(=J{POZtbU^zRrhO_;Dj2OUyY}oQw5*qQ_^R-}U0we){R_e29e~$AXC!=T;q_H}X77oabmA zG%y+%O+S5{Z7Da-+T!d?%z0LvbBQ_UigU4^PxScA^SfT$+D|`yoe#0_<5)1U;@nC; z^E^wO=V;0SMuQ$rKYg5SsV!%1adsx=JS)z*#GG@*xmeF9dVJ>jT`z9!r=PyghgkS= zESOkvZY7_2o+Zw6H0fb9=+X4k$Jv(J>a6XuyTzPm#W|OlbFMfS>-j{F&pf~D#jXAH z)7SaLIi37C7Cwm;=T`EW=UL)BN0S~#gC0#keVlEnEoW_UcGmig^Q<`M5_8TK=VCpd z=<%87cfGi^pMLr}A7UxDj0F=b&aLD#&$GmNjwU^f20fa7`Z(KCTh7|z>`csgR-AK* zIp>OVv7S%#_{{UWUfkMGKYg7KvGC(qFtOr%YJhbk&$Hw|&(WlZ(V$1uPakJnYRg$$ zoSlg|&x&&{G3Q)yF4psj9-n!B*Na>G>8G#rAr^id3no^aPiei%^DJ?mqiLOi(V$1u zPakJnYOAxhGe(Fx&x&&{G3Q)yF4psj9-n!B*Na>G>8G#riE}#naV&fiE6%6nGtaZc zd5$JMj0QcLe)>4uQd`c~;_OV!c~+cri8<$rbFrRJ^!Uv4xL(}aPd|N~53%s$STM2T zd`dp^JWHJCXwt)I(4*<6kFzbc<*Y5v&cvK&9W;E5m~*Z;7wh>%kIy{6>&318^wZb* z5DPz!1rsaIr{puwv&4ChCOwP>J(_;{INMTN&f4PaOw4&!oO6je=ZbT&o=^1n%=5cm z+}ck+eVq@n@Z(r8vEtlHKJz?FoaboL>l`gK=+X4k$Jv(Ja@H1SXJXE?;+#v&Iai#E z{ncma@tNm$y|}fXetL3nKE#3@3no^aPswMVXNmJ1O?ns&dNlp?akizloVCT-nV9pe zIOh^`&K2ikJ)h|Dndf)CxV4{t`Z^zC;m5IHV#WECeCBzUIM30fhtZ%%(@!5~TWYJb zwm-E#InRo7F4;NfigU4^PxScA^SfT$+D|`yoll(8$&X{0vbJ z(e%^Dxs}>-)^^~Ot$$U(&;9(4*<6k25K?<%}%Oyu_SC#rc$&^Qkz`>iI;EPxRP%HpsKKo}YgD zIv--;$FX2y#krFF8G#rAr^id3no^aE6Hb`Ly7bJOL`a$dNlp?aVDj~91A8^oGZy^oF^l>Joww#g0 znU|Pzs5qYzb3PU4Sv{ZV@tNmty|}fXe)>8eV&TWJU}D9&l6>YllsM17q=(UFa!mg&)U)i52Hc@|ovQ;ynM7 z9!7&6O+S5{NvSPoWO3#t<{T={r^K93#d%iGCwhG5xmz!8?Wdo<&WBj|aV(fvajqnv zdFC| zblbJXr|-7kBtFsO6MY@G_JiFy)cQIfVo8&+U}D|&$1N0h*v8*z4&UJO;NqnNmC;B>W?FYMasP%O|#6sg( zFtMiYEUviI?ss(amG|cnfA#6Z#AskNFq(e)d)J>=ZEqcNe6!y81;o?;;JD_gKQAo4 zWu9Xv@rfRv=>%ZGPefMX?H{Q6P7!8aDM$=FK z_?k}?_PyqwVJnIk+~kN!e4@uE`Z{jy2fK5q^>sePLgQF4v2K6v zFvXqeq|Y_$?7xTjxzDaBMgyaP(e%@QwJiX#<5^x-LX%*j;%e%V$D`tw)u>DVG%JJ7!8c3pZ@Z(hb#ZF zC#}?+JZpQlGQ|PQHMiZ>p07>VaLGx0qQ@utI&SR;yK|`Zbw0#G<5)1U4ti=Q<@4c? z&6=g3ZSV1|MrThn|DdloUs-Eg@xUV6H51O-K|KB7mXr8Ik5BY< z+}aOz=TPhGe29g{v0!4Y^VB|yd&7F4Zw@(Ud-0)ntSLqVqk+-%)315$&T4z!m%q|% z{PW$!Qx1Nqx%-8^#3#-0g-Lv($0zzaZtVxVbEx%oKEy)fSTM0}UAbKY-#g~`X1>#= zRSt_BakLl>j0Q&2Pk(3p_X60jAHMVCX0Nqo6pz^Lq~;HI%qH%9aKa=$(c=?+9k=#_ z-8t0yIv--8aV(fv!!m>!_!HtGKg#FtVAr^F88q zra4KB21X6A^qQ@utI&SR;yK|`Z zbw0#G<5)1U9zExF#ocGyG0o@+mxz~sW4IU%j0Q&2Pk;4W=cw&b@1EYg_WSYTb(TE6 z`PltG6#x1Qr%mD$JwDObace)=okOj!^C1=*$AXD9^7L_v`}{&@G$Z17g1JX-`_f1; z8W;_Xrl0=ItG=bS&n$ChbJHP5i${$Z+kE|$Q(FJewEpcAJ&eANTl>NO_w;o>#6sg( z@beMtk*9Z4+>^g}X0!ejjd=82qr_-nG%%We`uh)AP;EEA$dcvL*$*^68I>8B?L=R+*mv0!4w_{wL_2XW3r>0vbJ(e%^D-00FL%+;8C zV&+546ZvGG#JuYHM32v$|Gl`ipMLr}A7bIhv0!4weX1Pt{uSrCAw7%+J(_;{xR=$I zwI$XHG52rW*JAGLSO?052+`=dDbW$9rw z=+X4k$6l$n?A@^!i`gGz-xRZN#y;Egi5{Q%JkX0<`{}2z^C1>~91A8^JfFyCKF_o{ zw9iq}^Bjc+J(_;{c(zenp2y&+<5LqgC0#keLRa6)(xJG<5^dJc>av%QZdh^@f_Rpi5{Q%yxogi z`{}2z^C1>~91A8^JpU`7tQW*trzkFr20fa7`lub$mRcri6EXEd)DdFph^RYyKGEYd z>!V)W+D|`yoe#0_<5)1UqF$5Ftnb8GS4t0~L64@NK59L+rS^v3_u2ap~{gC0#kebnY^%e#W8{l(PdQKyTk z)1$8M`9zP;eE-mkTl?v!uk#@mejE!XR=f|9&wPI(&i6Lb!)VZ>>8Fo(DQe5Rop@Ix z=KV>$R}u4GCEmmIe4@u^zAx&wJiXAIE};74IA6Gv7~&^S!9_ zFdFn|`sw3crP}iDG~R`Zc|RHNEycXIjQ5;9pXl+K?_+y$Yd`(;bw0$xk7L2aiuc3v zneUUu`5s$(7!7(f{q*r}S#5dO9q+Eiyibnz%wpa%$9w6XPxScA_vgL1wV!_aIv--; z$FX2y#ru5u%=iD|Ja>>DMuQ$rKYg49s4Zs`an>N_{ePSbh&dOCbA+Bx^!Uv4j$Yi_ zPd|N~53%s$STM2T{6#+VyhfboMAE}((4*<6kFy)Kn+-+ktL&wrj}{KTLA;LP&DJzI9*JueD{0;Vb=iR$pbKd&m__M^{#qsYYbmC~&jrQX3*A2g7;zT^#JGK+Ydg9m*aqOQz z9hZN1KD2Y5_;dcmsjdrqH?Ir5IQ^8oF8qr#t~m1%XP#o>&|kF8>$08ewVr+uXa9(a zLqAsiDUN*TXEE)ZC;ps&JznPVb38b)=G1qvryp_pZ?F@e>x45Oapox|KK+Y^_~BRV zaZJ0$5zhXxAB|)B*Eqr+N7&;C6NmONap+&z<5=0dm0s*|#Gd{O>~VxWj&SBFjmHtY z#}Ur!l_vW^>~TcnafGu!rSUjo_c+2HM>zhk`wrgqrTfZe!$#_QJHzfMoy})%uzz~R z8^Yfv;+=OsuiSgRu^-~tKYu!I z`|oW&v~!;LbNGp;!E5oexa;)GxE-m_1=X!x_8>$RSK z5NH30v){xKm;MxIKZ|KcKawZ@od4weYku{~tyEBpo1e% zt&=cu@Z0)n*U8G>t@H)X^;Yb45_`s#J@XNJokWxQ%kFhD?OG>ck0YG@BYpOp*y|)3 zuajz<>m=-Tvh~xBV`ZN_UhRIW{`~hFuT6B{wd1v6?02)~c#;0W=jS6qp;U%d0q zpNf5Rng)IR8P6e~634%HLnn@Q-S}Y%arle*wxPJazuNnPIJOhVdg9m*aqOQz9hZN1 zKD2Y5_;ddBGx74euy^6qi_?!d{g=Eh;)*jLapoz`{Ka`)wsXDK(+}e8A941Zm^l2M zxRDS2>^$jzG5(xC_i1%qlgF!_hyN?a%VS5~mt(5>nmNMU!k%+LoO7eWo^wW=b4kn` zVNRoAj&KjaIVWw`y@oyKu@ ze}OZuIP(!_o?_o?=zXujdA-)_Uc;XKBYXCnIQvuVdkuZ|zw-3G*7|AhHQ3MpuAJ8qRvKfn8t2uCL*&E2VLLjh$%VrP1D8Br&rf$A*)~*e$rH#eHG^=r6{k;e#u8@^;>=B) zIg9gJ#CeV4ymoQ+i8%X8oPDU=Cim@&>XUzF-+uDaU7IZjZqOW_YN4+;cOP=Sp4Aq< zZR=*uEw7b*&cn879{SAHvZKG_m)DmMPnm82e&y!t%CmkqbWgv;wx{&`JoL+xdj7Y5`1oGj&9*zPm(LT!kLl$(^}a{<^51**qjinsmi9q7 z_2Tp+PXFSJ+eM%Gh%-;|j&1(pysp;XUavU&L7e>~&VCbTe=2VFvpD--oZ}+?N5+(K zpMQbt%dlNOG64U6`s>P=osJq{4m>mUwPl+HUmt>figm9o`_Fm4G{e`wrYw5iEz)c- z{WWFefqM-wPac2fs`A{`_Ya}%3tRl49D2v8(*MUfSC@Bg`mOZyfBWk4+Ni6fpKFGz z${$C3LHyD_SC&6sd9XBBzkFr6b*_ii_SxC5C{L_ETL=F$Uv)*F+(GY%u>&Y0i7< z+;aK@?KSRv$=T)cpU)x9Sx1cS<^RP+#+FkzSW5QS%PGC~qa|T$y{})1}Y06RKE)XpVd1*xp+A z`W`1}4&!Iy>L-*-W<65#IsK^Zmu5RQ^4U*qGwuZRZ!dB}&ri0Ufd6&pj{L9LZjiX0 zsfTgz45H6i^7-+dPblxq{FdzR&Ua!t^b@Pf|K(2}&;6pdIgVX?e)!Ro%07!eBmLmH zCvjg$ljGhcR?ZXYa~!+G-Rt1t<%X}`BL6w=($D?qsItyn%S)g0MEV>@#maG4+bPc- zT|TnIQD<=PNT2gWcGkT`&s$CQ74I8UzIoF0^8bxrpTYeiP2P91qknDGGSV-; z_gL-=Y4Sc5=Y1`G-gnZ|cCT6Hls)fL=@)w7lJfoC7neQnYw7d86X$&@%~=mzT<+ca z<7)fJ+n00iNR#)qc zYp;05!K>nT3qP2!#I~~x_1*z{uZO+Y!`|y*@Aa_vdf0nC?7bfLUJvJ<*pWT=df0nC z?7bfLUJrY(hrQRs-s@rS^|1H)%05`>#op_&d#{JR*TdfHVej>@_j)+5t1El%^|1GP z*n2(fy&m>n4|}hNz1PFu>tT-<&msNTI9B630DHV(j~DFmf<0ca#|!p&!5%Nz<0bp#`%d@ifAzlGf89BUx>mj7w{r}2 zt@Pq!vk!F*brj z_PYYu?+ReQE2wxvr5S|%t^oGC0@&{gV81JX{jLCZJq!C?0ql1Lu-_HHepdkdT>yXz6ybq5;PJB+F8ChV?v(7QIl?s^BkYb)6G6dKn%v~_KQ z#&s6#8VZf;5!$-m!S1>PyXzg=x`smIdIWaef!_5Fde>9fUGJcGZGzqP4tm#FuaJzTh}|-U3Xx2y+d2qP-t9_z^*&cyWTY;1J%z^g4sBhhpmCiAyM{vVdI!C06WFx|de=?pUGJcA4FbEqK;wFcwyvSDyWXkV zPN-r{K;wFcwywEg*H)DuwRJsG#hrkj`ipnuRa^OYy+d5rCRMCK?5;tuyPm?o>m4+% zJFvUnLGKz0jq4HEbq9LaJLp|oVRyZQ-t`D}*E{H4XTh$g(74{At!ooBuCuVSw^D;( zcRfX0*E?ujcVI_Py@TF06dKnfumBs2O|ZM(LGL;Xc0Gm0^$u-a zo1k%>1-phq<9dX)u6MAz?!fMPhqkVv(6}CfU4x)^y@THM6n57;=v}8^cfEt&br$S; z3XSU>?5?d~*G=`_QSB*1;K}>)^V;kGJNxpdw?41wj9H-2pTAl5yyp93<`Pf&wR4+Q zZ<$H_u~*M-)?4?Z;-9{7R`c2|A9T@Ay~WsO%YFVNUSQ+XnyudXo%qrh;=jW+_8IZL zpB>Tcb@DI8H*IiYv)lWRiLZWmTyyXOOUdWuQ;u!k*nEii#TQ36-&*DK;yeEI&1RL4 zcEn%aY0u{6->fd);--C@L+)Qk{M2oSG$)?BzWC(Jj%-$3?Tg~Co^?!f;aMAsrx|yA zbI#>0?|RC~&2@XVnv1p_*=+bq+jh;Fk7+*tRC|q|{^h~V)Eh2TICF6huycT&1MD1N z=Kwng*g3$?0d@|suN`)u!0s#9;{|)XV2>B<@q#^Gu*VDbc)=bo*y9Czyx_V|+*jD$ zKg;ZbKEolAGpR3nhzIwRs7Cr zS2hpqKXV8Bz6XzQmK(XSc&7I+Zboghf_U%dg65_@Ru#{;(Yeic4p>|KqYck$p4xaF z@u~6OAfD~5)x`%MHLAJdsFlSx4qn@QxW=1W=aW_AWIkH=Qr{(q^dnCH;*2ZKe8icj zIP(|hb&2zO6>HHs$233u-2S@uWS#vv2l~x9z|H}74zP28odfI~VCMik2iVsRyH6_C z*|Eo~YC8aXykL(P?D2voIbl$X?B7k4vT3T=KYJ_qf0w7ue$hdt6|T3tW$jW2yi1 zo`oF?b}ZPjV8?%Zv*E#DbDp%oa?GM*IRL}!{S_@#kp>ab3GU5{vyu( zQJnjuIM+sTuFoBE%Qa1$Yn?dPKyj{(;#@Puxt7XjuCd}=d)v6}GlMwy$A-SDb1-9f zKCttFoe%7MVCMrnAK3Z8&Ihjhp=QUWPaGF^T-b48$Aujic3ilQ>-j(qo)56+1MK+# zdp^LP53uJ0?D+tDKER$2aNW0c|L1dy#=_T*-q#NM+F@Ti>}!X8?Xa&MuCLwwjNNk* z_FRRXGyPVx`whGM4R*i5?l;)|2D{&2_Z#efgX?~CEb?(I*s);8f*lKXEZDJN$ATS; zxKUeZF2Ye;sK4N-E!2;2)E4SrIBJUy{SHTM(P2E`s4Y5-6CAZghw+1>w&*afaMTtZ z<^deFg~kAm+CpOhM{S|!Y&dEQjRzdHh4O}@w$Sy!QCsLb;ixTi{czM4>K8a_3-uQq zwT1c-j@m-~3rB6yFfZY#E%ZE1U)4F7u{$5w`M}Nxc0RE4ft?TRd|>AT*Zokl}!X8?Xa&M_O-*lcG%Yr*VpcT#_l-@d#=LHnSQI;{f6EB2D{&2_Z#efgWYei`we!# z!F9hm7Wp_9>{zg4!Hxwx7VKECW5JF^+^8)Ed0v5|wix7D3Xa;M%kv5xwMCcb6*y{( zF3&4))D~TySKz2Ex;(GIQCoC*UV)>w=<>V*M{UvN`3#QQVgk?5$wSQ4I?jh$#CmEJ z`=NHRe`*@XrPgsi)IiRY+Q|7+Gx@rxrF^|nTMY8tOg_{ZFnv|$V8-rzVCMrnAK3Z8 z&Ifiru=9bP4_x;{&5lc+jte_3?6|Pw!j20&F8nufH6Jn`&4>I&cwT{HZ7)2pz_I2Ro>$=5BMQ%CFz+LIZi9JG$@3f>Yh&R#503S@>*tMF z)4F~RiM6il=aX0iyMAtowXy5xnOHNse$I)twD5e1&sbv%&zEqly@lsXnD>!9%fh^; zATJ0IBjz|IG*`=MsXB~QnN9T#?7*l}UUg&h~J<9a@j zgXaV6`2c%9z@87V=L78d0DC^bo)56+16=oQ-TxjJG`@D&*ADyIVP8A!YlnU9u&*7i zuigEO-E$K5T!o!8{Z_O44ZHgdcE7>yH`x6KyWe2<8|;3A>wa@A@^LKKv0%r79Se3W z*s);8f*p&vaW9tW7u^?euaxL7aoj^C`cWMBR*C)<$30h~-(ByQ7!PsWqb0^k9QSUC z@e{{AU1D6taj%z{2jW-{3eRoi5bH$Yc@B=Xs>Jn+V=XB$2I5#_O5`n$wWq}Oh+|DE zah>8=t4dtIIM%Qd{UVOFtweu`W6dkkkK$MhOZ2Ze)`P;ctor1a2N#}k>8m;iGj`_# zJ0IBjz|IGDKCttFoe%7M;JP1bc3kpwT-b48$Aujic3jwT;X1D8137p;z@87V=L78d z0LR*_`2c%9z@87V=L78d0M~sR>vXUGJuYZ`?Xa&M_O-*lcG%Yr``Te&J6vD8`x(3E zB<#5gJ7@Z>X7?L*_Z#efgWYei`we!#!R|NM{RY?l=2+z8Sg>Qkjs-gw>{zg4!Hxwx z7IEWQzVN&P$Fp{c=PhwOgBPAxu*b7`;h7SSXZFG~B^=N4g=b1Qp79IMlyE%z7oI8M zs0j+slyKAvg=aE&^|P)mr?0TTV#RY@q29p0;*YP@=P}^4>x?7ydMBJYi_>QZeZ~@J z4&uyBoH>j0TEuyc;=Fco_K9NczwQ`58-Ee8qW&m62g6$)HoE-cxi@MatTa9c;o4iD zZ9jAv3+D_wXV^Kz&KY*juycl;GwhtT=H~W*l}UUg&h}mT-b5pzZaJrJa(|h z6!utGc71Qoa|65QC+ztNdw#;6pRngA?D+|Me!`xgu;(Z2`3ZZh;T&s?V~+JCV~WOe zpwjDH$^DGo{S3RGVfQoaeumx8u=^RV``J0G|Ev4U{Z@^O=A`=#yZa4xzrpS|*!>2( z-{8969IMJr{o`2Gwdg#{v9LQ9>{zg4!Hz}TT*C{TYr8ntd~xmt;@l&|xp#;7>*^jppD6YTC2*nI-KPhj^6>^_0rC$RejuKUEX$jz}}$ATRTb}ZPj zV8?3T2-7itT=04an_sStT)A3>xr}8 z6laYl&e~0!HJvzXJ#p56;;aqDSu={WmK0|VF3uWU^R3RoOdmQQ*!jTD2X;QN^MRcY z?0jJ71K0gfv*R*$jte_3?6|Pw!j20&F8uf6l7q(u_ISabGqC3j>^TE_&cL2Cu;&cy zIRksnz@9U(=L}r;e?3MXJ2dVe*!=^$e_;0y?EZn>Kd}1;uKUON&~G)nPq4dBVD|~^ zK7rjQu=@mdpTO=Dxb73jA~(l^9Se3W*s);8f*lKXEZDJ#%ex2GBRKj&>k%CNqxA@m ze$#pcM}KNPf}@|c9>LN7T94ou7p+HdjF;9UIL24|0nGak_9U41BJ5RgT)Xy8IQpOS zS=l3J&TYkUEu80y;~F{V700!6{wt0?;apf8eWkqtpV5cf8{p_$?F}&RKiG$0-ixq5 z(O1qP`%O7ye<}yqIl#^Vb`G#}fSm*E9AIBN>^_0rSFpzm_ISY_FWBP+d%R$e7wqwZ zJzlWK3-)-yb)UGeu)BZgH#2sR7wqwZ|EK$kxb8RDabd@W9T)Z(!5$;nV+4DQ;ChVQ zC)jKDxM26Vz#bRa;{tnJV2=yzae+N9a6K-LMSnUL>{zg4!Hxwx7VKECW5JF^+&s(E zeUWER;yjZQ=UJ6F&#=UKwk6IpFL9oQiSv9=%=-Z9H{$YHPHN+1&a=dMmSjEWv*J9b z6X*GzIM4OOdEO_^b3k#P4~p|lO3b?-YD;p+Gd?qCuUa4SOigw(edv5(=L0(**!jTD z2X;QN^MRcYT=zrGj!Vvt3p+0CxUl2Gjte_3{P*H2pY}{#{owJ++&GtP?d_Sh*mDMr z=M3yQ1AETEo-?rL4D2}rd(I?lKEQbntGFJ!Y|Ht+?Cu}z?jP9w1G|4<_Yds;f$RQp zKJ;77|El|ld>kut<1+*Ql>Wc{vPFCEC*enD{XzN48wYmb2_L((Jh#Fd;@rPeHzVE*n@5s{Lu|4!1>myEMKjFWz|M;_U z-1zr+*Vg6}?HcD9{u<{WaT>k{N367W;M9xLPlG-Ei!-h`^ATsB;)p~3V&V`luZ!!o zo_-LMFY(Z1zlpg%;$i2yi3igk#Dl{h<0AHZJnVN(GpcO%myNpcdYhkAhCFeP_`O|^ zWIZd`2bbEh?0fENV*cds*!g#KFzsj$;}5?u*G0UvcWe)R$NKQo*iZOx>_7f&95?>G zaX!(mah~C?asCmfH(qJi^`>5&ej4&g|Kf}*&V0m~r#Rw}zc{bUcCOcY`azuiBhG#k zbA7}k2dRbL7ekMobyM_e5XBn-(Rrr zue9s_f^**5kM1w*InQPH{e?a63)z{!#KX?KCLZkjtFm|C)Qi(kgWdNRoN;CM{e?aA zl->6icE*c%a9*!C`@w#6f2DucCE2q-#lFALWdAEq-(T2$f5AD9y51aLagKXIlk-8G z^F*BUN6dVuJ$m0?aLz;9b$?;cd22tqzp&>#m)-XlcHdtx^Otxq^O|_D@2|?1ak^LnMpey|_bA941Z*!LH0v!7-6{e|847yF~%)kj{v zvp?)HUkZ7^c}6qISqy%xfhXUaJE@=lo$pPL*WZqB&H!QaM)`& z~8mcWHXJ3&;B{y<>&r{g&RbqPGUF?X^DUq@Lr^nDLXW z^Tf!9?>uT#_4`@SoQr&fLVAoAlPuwzk*$d?zEl8UOk2LO%1o zmN?&cNpB7QYkRHFnpb)={>u&un&Q7# zQ?&iuelG5B$Jh5e_P_V}DCS9=cj-(Njx(tL^xqi49-mv#St)+3hif~Z{pSo7d+jH3 z&^uH7#C-ct|BV9dsnKVXtjAAn&$gP+wV%v^xi&O&5N8hJ%vqoJv%b0(*{#Q3`^hsV z`N=aWah^$u^IWE(t@Utiw;p@#C*R@APrgGo>pNClSH9Pkf9vs6+w+~XG_{||p>WOk zVSKnYIC9W;G~mct-xJB4rH5;~_1J4aoR@OV_=!IJPoMF|9`Or(L0jwL+8%lRr_Ur; zZ3~!rZ4aNlGh+Kelk-9T|Au>KTRx8|ooih7hR?~)wNJC)3S#=?{==6M(^r3*c5yL%_|$vt zIyt#-|M`8(e@}R-?a$L3=D%mY?|J8n`R{DMeAwAy{(I)%-RMj)`n^63&HQr|`1I$` zDeFBxgLr{C&*t;z;r*_T~Z`J+GLfThLw*>Yf|)*k++U9Axl_pJ@r6qCr%z+b@IJ-PM|D3X4zQ@^R^9!dHukx*N<->=jmgbFR$CdB= zY{tSoIdYma%br8#lKqrJQ#P*5$^QH{Y9C zJm!ou%AE7fsJ2_qHnuFad%1q&eb; zqsl_J|3?0||M{45@TcF>e;@ww*GH7A%hR$?yy(>O{KBuu&%<|)Dn~x^fi(LrHN1>E z;7RdMUpuk<=3Bp%eyvqTl+WJsg7nACII=9T+&i)#dFIJwkt?5<{@%HcFYkZq7qZVX z^2G9sM}95+Gz$(dA9PklH|9DinVAWqrv%yp+miKmS zuW^?9hLxwbe^r{}zi?PD|2Nk^x_ofSuVr8Pjstqvd+n`<_wtj~yJ7~T!_r_oLHO)i(U-HaeW%S7Dq~G|#oixYLJht-J z%2S8Wt#RM<4{P zyW~^S{Q97s$}2}Mp}2Q#x>LFPkQJpT*4A?@EcpC2my zGDG(%Pkeht*%|kPMy@XX5pR6Atn~7FvNKOM@2n|3JkK_UQ8D*VmPX`;NAZ7y9#N zSWo(g#~fXL`tdcS;XeIfp$+bzVzI8_+h+gd&~H?f4EP7c);hSzxT~k%gMKW zUV859tM^<-dhR>?)0X>mt4&syX6?5|meb!`Q*95M|8(^^8t&`$zqOk5j~{qSd1b4i z(tLHsGc|VP|LDzQ)X&US)=9=1`#!s$(HpPnt{tWRM8mqe?`6x$4{Ps%e_Bd<)=9>l zxF7lRnBI7?u72fL%Siv&tml^R{$?@hS%)_~Y)R=^Cz%hlWnI1Qv#rlr-Wyl`_~%7s zXYGCXON)zd{MFd<@>z=%{(JS_J7Dkiu=je{dp+#E9`;@jd#{JR*TdfHVaAKSUiRGU zVej>@_j=fSJ?y<6_FgZ0?)9+udf0n?&mMcF_3WXr_j=iLuZO+Y!`|y*@Aa_vdYJ2C zua`addf0nC?7bfLUJrY(hrQRs-s@rS^{~gQewO=N_Bc*{X8ZSiW~;}sH@@+V4Nt!B z)>J?IyWV%aH*l@We?!}~690W{*HHX7v0YoC_qzhv?+ReQD}ep30QS2A*zXEpzbk0z~{t5KhpnR`x@^LtED)j!V6R-u0K;Qd^;My+d2q zCXPkTh21p>cGpw1b-jbebq99WJLp|Qp>aJTpILXHcfEt&wH0>PJLp}HV0XQP-gOr2 zdJ2u}9oo7!LE}0LyK4~auBT}0dIyc`4(#ZuchI|rLgRV_cHM#A^$vR4Qd?nny@TGh z33k^z=v`;QuBXtr-l45)6Ev=~VAoJ+T#wM!^$vE|9oSv((AG5+8rLJRYY_CVchI|@ z!tQzpz3UY0u6NM8&VpS}p>e%~-L)0$x~bkfyr=LEAD+A~4^cn-SNCPkN8Ww)sVXfvd(2xnt8YO`|q79 z-e>W925$aX`(2?e#ym4{>L1(hp1g9>O9Qvhbe1&mM^`&XjArF+&hNFIVT}vL`25vR zFBTJP<0mc^lfz|Oju(^L^ebL2Cg;xfEpshPJ=tow#_6xROd78J&F3x=(3BAisqP$M1U&@*A0O{O&9o2L&hLa<&+mlWPxv3Oe|{(2arvF_UOw?V;m(ua33vYdPIz@)9e(4G zxcsg-zkLYfhu=h$J^b@qi7;{b%|DoY_-#d)Jo(K_4un>$voDFQ4dt=c#eY{Qr?LW!(AQU4AH6TflYUc_DS=4S^-&VQ2Z@jK*${I(f(egm1`2BYmJH{3e-@QK5vIp@7E4sLPH zG2-|Q^Fe;k41N42`5?cehMwO>=6A@j?{>?;;9qV&PWqQVx!8o)pEz3f_?`0!{H7ZE z_)YRbey0t7``e!!yzIdfq&Z>hxhGulmt))9ZhU*l)(amaP5kEh1b)j6{rzi9G2!=1 zp3rLIchsH#(w96th3*$-p-8yWq6_ zrw#qL{_^<1xi629e#h>dolOpG$By4uXTIe; z>@W|}UsT>7XyzLwJ-?&Q978kb_g3xfF#DO}Sg&;dk^{e;&RnG}zn#v!!oJ^#r90ci z`L5gUGH`A$7QbhPCe}Lnp)J3o&K!n^E-nMWr!P52n%^C|XlK{a7pN`2GtciMIu^g>MsEDRI=^#$r4s-fpM)%l$^?2P*| z3;(LVeZpUez)!0oyJ`- zxavb!t1Z8&PM@RUzUDXQ;8Slnaqz_t+iT?ay%{^=@|)`PGdZ(PGS=AnO>d7EznxBh zqG4TK>e7qFtiAkZ9(vYE#+_LF*0;xtb#=ZUwPU^7lAZ2yKRI7|)?t3D4?XK7^8sdE z{o)?2&)JSyqWjXu=ePOC+RN_(qFMXQS-ZQOe_s0@GM@){H|xC~_FfNrua`addf0nC z?7bfLUJrY(hZ(Q@_j=fSJ?y<6_FkWM?e(eGUJrY(hrQRs-s@rS^|I$)4|}hNz1Q?6xXV}!*Q*|`x)0z zypwTlh2HN9V81JX{jLD^y8_tn3Shr0fc>rj_PYYu?+ReQD}ep30QS2A*zXEpzbi2F zuD}}J6~MIRT>0z~{sQ-xa`qR{;Mb{m&S= zPJvy6FkY^Au)7|CU3Z{yy~CKgZo=+*2fb?(?5=mvyS9Q|PoZ(WLtED-Xk2H(uA$Jl z9-*!49qg_`1-qU?<9dg-u1(Om z&VpS-p>aJzTh}|-d7h;1!0viSakGX(<9Y;k-GQFxSn3_=v!254dI!C06YQ>c(7Vop zT~DELy+d2qDQH}0!LFguyWTmAz099GQ*ySB0)>K)p;9&udi9rUih+?Lu3jq4rSx;AkvYA)=qL9n}?qOI#4 zG_E_ayWTJIGasdv!3hC<_d1a{q#epK(Er!BP=cGo-TU7KKcy_5b`XTh$g(74{A zt!ooBuCrj*P-t9_(AM=1cGn%)UGLD=H53}xBQR?(H3)jwJLp|cVRyZQ-gOFg*E{H4 zXTh$g(74{g?%E1=-Bj-#-cxvo4^Q5g$EzRytNSwNAnR}PUMJ4*8hE2?-|x)u&I#gI zemzAq=Dm}}r!V!9W~vFNh&LE9U32bqqr}HOHdAx`!=uHY{LviEV^f?a{>)6DXr4c& z<&E}Ou(@u_mbV!B>E_Fax4%pE!xffp{`_I<=Ram%zB&F6Bh~ixmsVuO(pBMIu#qs@;W`Q}+7RUEa`2LAFzK_E9Qd+)vKEBh^^0JHe?C}}T zo<6=m(eo4Et7z;$zHiYuZhQ};aX#_=jK+D!_cj{mAD{8$GslW0`>>ogi%xt-p<$lHcOW|P*$CNh8}?%7C%-#I`u+BJxiix$r^z1Q z;poI?o1~BLSajmE5#lT6d$aS_$Tse{mHyQE{VSu@_R%x`+_~({vC_nMI6Cp!De->W zzSnu=gHxr6@3Qb&ZTUZ9{tr99-s}w7<9jfCA4c~0&Po%XQBd2helT@&-fzc9^NHWi z+Ek;wO?);&{OB#SHFuvsR&5X2@Z-%-4mewF$8NJoGxx^lN)z9?;k!5DXD|AAbNsqz zN)w+Y@8v(&6$>}FuGF@T&!qRRH$F4o%k%daEY!?8OWSshomOtPJLW9;iSH#e@tF+e z5T8l!^+SAqTzN9q?|iso^Yh!rO8@KCR%`ZM_6+IcI|_XEUAe_)($x=)^|^a|wwY^z zwomT*bkl5b(`jnE-FMe%c9?Ut^zj`9KKm}-^w^b~hmRdCpNBrWMzi2w+Odo80W{1v z=3abryp`mFIIeBN1FKjj{MLzzE99Fhv60WU88yM-s5|IrrED;JM#nU zH`i`|xa`D@&jv{!-(BeWq3sv%Jw}=ZezHz8+r%RjH@?r&#OIBqCsuq8N%r_&NE4r1 zlKrN^_;2?;ccj|JcQ~5(Y?CyMV|*4$_V_MH6Q7ZiKEA8b#AocJVcZW{?3-fdNqp8y zdd4w6gC%`@7o>^LX35UD54&t( zrJAkQ+gWYnb76e{r}ZE6BtADLdwjpAiO-qIzRp%lG;6N3huX$x(D=@eG~9QzWgOAR z=i8)@&$~7889QmXPp7zYdolNQd}dC1?mPT2UbKzR*vZa)y1`vLO26w@rfK#)bVu2_ zujBK1(sSS8pSIkm7roNE7+o=V-XE`arHSum zbr?JHzx=2VJM=Sim35M_#vb3n>Ug|fePU|$CmPn(lgAt)J!@}##!-6KNyeSH@g1y= z$BT9Kim$a}ed)?ibk@A`d(yKG$7d_0XPsm|(3W-ei!-)!^_CN!>kM1yDA`$itXNpvgck8d#{JR*TdfHVej?g7%%pEaqji7_j=fS zJ?y<6_FfNrua`addf0nC?7hBckG;}*_E6Y+z3jQy!`|y*@Aa_vdf0otIIfGmUYvV9 z?7bfLUJui6?Deqsdf0ot?77#&-s@qHSN$yaw=DhSXST-UNdI^oVUHv1aTMn`ivNkv zZ1p(y#y7?bo_yc6_l3ucKJj?L9xw6#gZqwmDXvv{hvQm__cN}ccqil93ccSIz~{sQ-xa`qR{;B60ql1Lu-_HHepg`TU4b>cD}ep30QS2A z*zXEpzbkc(7VopT~DELy+d2qCTLt|!LFguxE`Uc>mBT_ zJFvUnp{;8uG_FTr*B$6x@1S=*h28ZIde{n8NBchI;7fn8sqalJ!Z*HGA9@3<{Bh+|P}pmDuJTi0B$Yb*Pq-l47Q z5yz$8LGSv@ZKmBs2q0qPmBs2N3grzLGL;Xc0Gm0^$u-ao1k%>h21p>cGpw1b-jbebq99WJLp|Qp>aI| zyY4{mdIvpisjaZP-a+r$1iR}U^scjD*HdU*@6gt@2^!Z~uxltZu19F=dI!7f4(zUX zXzLmZjq4HEH3)jwJLp|cVRyZQ-gOFg*E{H4XTh$g(74{g?%E1=-Bj-#-cxvo4^Q5g z_fbFmSNG*OySp&v=g@<1*{WwjFl;~zI`o?mNraeOvC-j{r|<$3RJ_BrUa z20ed1AAg7WcXTlAXbkzC+6SLWu6lwo)~`-ug(AB`6lvNJ2Yu;uQ%ejAJR{QhB)pw z;&7ev-{vzECXV}`IP@d-dc27F<9$Cd^b4EqEc+(I=NWqEg1b+`9>yPjVPZ0-mAzZ(3!Hw$ z>0g|2#hK4U^qHqP^A|^)MIxT<-N?gw@)L(2;)%mQ*WF#nDYrk∾}5^snJ>hH)84K01x`QW^e@i1 z;>>3v`pi?D`HS&Z_XeuyUy|6Gsb7XF_3OhlJ?PK1RKFfK?zjJ>v z_jF(8JZzX3IS<26@BXr#d1yUz%zngqe~Foo{2fi^!+dj|;>=&1*JZosCwk9Y{BVCs zQ_XYYc>e3UiI;i$ej$JEFXhkumFtG>+;?1;???M7*weo_xKe0>*+c@twApH`35PK1OAA5oJ#@r*cXXYN!ux95T!8>p7 zeYUelSkL-zKjQQ+&bTfAbuVr*Pxb}pFXno4Psi@P1HJbYu1kBZa`@{W#C3UZA|Lj? zHtt{dGV*8dYx9r3WE}C6cJ@TB%X_8$6zu6=oO@r(f8C3nr}{ke7xx>xYRze?wW#4< z&$UHsWUeh*J9BN}-&r$RPqfzN+R|{Z=h_l}dTXZbtS#2FZrG1F*Gw^M41Y(H`LKpK zPjTiiuJ(eaT655AO;10pnbKEl7je9%>AH!BzFGsxpEXnYGxr%gG-+oowZ6c)W{T6l zIOB@xKlgLyIgz%RznJTK=YSnp6Uz7(=j*&b<96bWPCT=7`YT@+zjMH|onv=gOZ@Zo zW^ML}b5->G$=_lA9UV+N+Qaz6FH9V+tFp7UST9aL;`Cq8WL$CPBhEa9hxMJvPaJ+a5l0Gp_#`KhPPVJmO{rcj?o_(}4<2FOY`#v^Z zbMWkoi20MhGY9y0bTI8`591HNF!P1$s_d*S){E1RIQ z-i9 ziSrt5_uhftdkTKo`=qJ%AmXqm$4VLf<9N^dnCHC9lhS zuJe&S^AzXaC+;_P)taLnd?w&XYA$ z9R64{#nqb0b$Ko2y3lv=pMJ#Yzf^I>xn_zpPci+6U-Z>I$Qtl}@|mQ%#`=0E?-BpI z_6Y4!x%X-BVsDOpM|)cCeSXH1ojvg1_1Tg&bH>r*n^kPk#1FjxyY38I zohP1g^b%$ECr62wnqup6?{B{+jz3HMT^#>jLMM)PCEBz8m+*&Qal|Qc52y}GJ8OPP zy*T|8?CD>eamAUBIP(-|{^GnY+dIU=CwUPMCST&gTnF(oZbLkn>n0vde-IC*pNI$3 zf5fZook}lGKMi*J&;6EhWzT%XnWvckBOYyu!?OZh?djTkT@SJ+=iaTonr8*{)icB7 zdi-Blk2CL=+;#)q2h2m*^APqtggp=8oF~$I9%A=Aggp;o&%?^zsq|vcL+qZ1u;(G{ zc?f$R!k&jP^N@IH*Se80g|2#hH(o`U-V zar`^aYT{_uM0;`g8ybE!_actY=7^Pc&D+#B*wc?V{fjfMIP(!_p5n}ZD1Nv`;^lR9 zi3gJx@nG^L9?W$R59a!a2Xo!TgXs_A!SoaHVEQjKy6@7i>rH*B{D{-PIOB>lA93a> zrvLDZACDdEdkyxz2K!!veXqg3*I?gku5&ei}6CUz~BpnU6U0 z6leb8ye`}S&#aR%H*|k--{t(|%ue%&`2jP(m}hX#b8*gpao!hV<}dRDJ@cCR(fVoc zugb1xs?;~w(~mg)i!-h`^AR)OX;0hCe<;j&aet*<_ZOV=)_xQZd(Ly&eScy1{RPt> z#Djf*!M?vLyRJ9&1$+7t`~Jf2`>XY%`(2vMQ|$Yz)%QY z4<1L@XAr_Wr8u|HO5&_c;?jSNVVP^M|Y<{wz(+d^Uv7f^dd1`Li^4^X|@{ zff46tW5oXkpQT}bGG2Uks8pXRD*4$b*{jbW>GP`m9esR8=-=&gzh3_*e>N{a`}gnt z*}UHKWK->HO|`Ez)xOqL&;Qif{GDfmrh5L@^El71*sJIN@Y8$#x1Hw`>)AW(M_fJs zJFe`Rk2v!bXZ}1>sV*cQ9Ckndb6q_D*$>a<;_CTd?+>`n%t!k=T zr=5Mx`T|$a|Mo9?#udkPk&ig@6leZCUlGgiLwe&C&#t}kf<0a^*Fn7jd%R$e7fgQ; z5B7M$9I53u>FWVUf46P>>e-d9xvGA1-o8LyWfZO#tVD)k9=moIc^~yn(Sw> z#|yj1tM$`+&bOWSA-(ac{1lk}BOaV_#U3y09xvGA1=r(cuE!D1e$e=4|9C#=deCrv zdOqtu`rmlp<@-9_r`3DNrg{(A zRPQ01>OEvry@zb7_mEBX90 z1^c}*?D2v#Pw72g*z>w<*LbB~>e-J z;{|)X;G91N_ISY_FSs5rGvn*A%dzedJLiC6!yY@>V+VWe;2aChF^?T~j~$%$$@f}& zkGr1>V@&^e>|l=_T#uJI$G5|L%5m4&!ISSheIDlD=DzdiTJv)w8ZSPxIr+1!z0aU( zJ+*#ej}qUy z+Fj+Ajnp z(9U_{&-oLF^&_tfdpEBOeaY*>k2w8{Gp;!E5oey_%zt8aU1H+UkJyPrKf=VJAK~mb zam1xR#r(VTp`G)@pY!*49e2;_LqAyi-9p`V%kHbkZ<~HlxZZcST5aeptN1S(kC$GzPuGf0{K};O_5q<{jhvu(HlBwR`}s-<;gpiY0!N0hS$sH ze_F0V^U)u^QI6PU`3B92A3RxRoc3^O&b<9s<(6?rN;Cag&z7U&zfXwf%CSExpV{C- zX+AN-Ps$scUo6cOSKe91-EfIC@$V&c(!{@)&`A^jUP32L#3>O^nut>(o-`4sL_BFC z-x7IC6Zw|NTbjtXMBdWGb$8?XrHSkA#`Q}R*WHclmxi&6dqWyH?v0^bJ8Mzg8$-D+ z`mgfSsr+>8hyJVbX{vl0=R^Nh*VRekM*e zUQIP#jmL|8t8s6tac?~CTz55pnri+uoE=AdPdDcwe!6Hf zpOW*Cd`iwk@+oNYx}>51m>+29KjsIT>>p|9Kjs-4`j2^rCi__$`j7dFhW=x|qRH`+ zhW=yTqoMzp_h@q5rJ?`0f6&l>+&^e?{zyaraUY_g|F{p)FyC0CxptT}8V&u*8l8Ta z&-TN7wjbuR^Wna5KHL}1hx zvVn6C73bb6&OKM0d$Bn8XmRe{L-FHh6*%{L+4C8|e)Oz@CZ8E(_p?goqh}S^&nmE= zRbW4>RCZl&>I?RK<`Mf@1$)Mo-Ono6Gf&ww|B2Z1y2N?C;_L_e(X&eW=NZp&^{j&3 z&nmE=RbW4>z#gym`DgNTCjH>C%jZCzZ~c78ToQZi(0J@%k6qgTCC{0MPq}Kx&m?d@ zt90OehG}4)eR!6F^O;AS&qCsSMiTSv!?PWFo_)fvnDvlnyR;L}dObs8Cl1eua6Ze4 z^BGUi&ya9lmo$03*6SG( zP47S$LuNjDhJ^hL3Fo*de~(vv58gC_+Txb zc~v{0$-THi!!rfXI%sn5ZqV>d#Iq5a-0P*uX8>t;_osVjS%ty5Y8v2iCSz_fgr>{%30~-2|XIV7) z>?%z@(<+~Q)|Doofu(WnfS-J3mL{L2rE%?mhW;aOV$pxqxT|(R!*y5lr>W+TY6mp* zAN|!{SM(qMi#~MiQ2FViq5l{UG>ik|QRP#rd!& zYX>yh&(dT+OOySqSUFzOeaLmuf82*?TstV|=rY!5 zG|Wk@(V>A^qtWDiwjbuR{V<=U$@{|js7A6E=dP7%-t^L6S%`5CsE@%9ZkHa{Zu}w zzstuOfwHU}C@YN{^07w1Cyg7*$66r8T^a!&YX|b7{kVR7xbEEjBkfS0L(6MoxjC`+ zS*5(rre}#?+p|hM`#|fK#B1CGPlXpg6Vr<+hxQ^L#s}IFPS%u~f*mh7wVTUTys$f7u;T^)y?7Bv$L??0am4O8!j2>CIKqx2>^Q=XBkVZBj$^Vb zj>%u~fK$6=u;U0jj1O z=fnLhPVFX6?I}*}EKcpOdZxID9WUbek2v|Oucds%DgP{YpNJjDa-OyQj&^VyVaGAo zKI&7BBX-9Tb{t{H5zfca&m`P4ehz{C90L0}1om?X?B@{J^BU}V4febSdtOU+&1=bD z&mpj%LtsCLzA^4Gnc@)4)}#i?9zs*l*uljP~=Ntk{| zJ0^RHc7#(qIG;c}Vo&WR_PmBYwX^K0{lzIR|Eb^M@BRh5f5GlwaJnBd*!>Hx9VZv4 zZQZ|U6ZfxN`^d-r3%mOl?EVG2f5GlwymR9I1-pO2?q6_H3|AJG$P<`CLu)BZ3?q4~(-v4p`%H^Z?ZQQ@GyMLAQk=~b& z`xkciFWCJn+10;b_b)iLkMeQK8_>oIKqx2>^Q=X zBkVZBjw9?iCVTBT8Qa8hq)i-0*l~pOar7P>F-?1OweQ`fbx7L8>yWVbOkwYt!rX_n zW3sbHEKYmJV(*#a<2_T@d!}&Oo0h-#OtE{<6n0;O-M?V>FWCJHcK?FizhL(-*!>H3 z|AO7WlD&4EjBVonMVq*P!R}wM`xkRauc71OZ_qboJtNz3mvP~hAGZ__*=cO}e2wkI z3kHu4PYl>eeB|MyLfvM&i0{2~L};~OH*xPpLqnhSI*32Gc2F3#QI&Z4sRKi+`^)wo zhg}wWt=(SsuJtYsVV$<(x~Z&yID()NPjyf6|&6b?$ZYk7BN6PQRbU zT;qgmejGya!_%%EA2?$h-ly@H zz}eXFQM--|U&S-F;Rfps3!JeHk9hp5z!}@J54yZ!k7sLF{AaFuZY7_uf9_SuKc0PE zDffrECum)ZeAYbW*h)Q*Y<*0n{_$+>%5}*e&t|qiXKcgd6W?7g+hhKmv5lQ_Ib$29 zKAf=)Q%}xXh8x8Cb7nTob;a?$Y>(G#JMCb9+Q<3OZqA?fbh)&%>qGmyo{CGV|1XIt zaesKvsev;i;W4eJ1kN|*9vISca^Sp4>^Gk=IrN#`THOAuNrAH}@%f_Fq`+CK+$WdT zy)JN`CH9dQO$>*;wv+sCeDJ#P=0zQ3e|X$=fip7kU)*{^;H*}7?6ud1J9aLYdql$t zaerYqr5)N~eAwjMJ>;|S>G6RxT=74C(75o2`n$;IlDkF+&hn((V_z5>hAk}0{`_ZG z2hKFbe(&^a0%wAf_UVU5hc#YlFP}a;j0iuE+E@JO$3p|>nBu=@`>O-zr{X`b{;0tD zqu4LKZg{xs+`Z)gc;mt0k*u5S>y8>4I7=1(y3Ixe&S!-iFCG?p9=Jz2&u<5X9^db+ zw0C}bdH8zXe)8FOm7#$%T=8Fb>7el9q>l0#yx+x@`hVH=iqQ4^a@uweo?E%z`HKfs z>RIoJE5iFbmebz1yiXXoVQ1x&eRWpg>{9B#=r8A0+M&sLm#UuF*Qh=>oHuF@`8WOf z^f2#?qWp*7adzO$RO+@<;|tXe@NrL_AHL{XkWc$2XN99Ku2R|?9yl=!Y2Q}!Us#6sjPTrX=S`>{_^pBsd|6KWX|LnL1!vWlopL!#75_cPoLb3;w7;9N zp?p@HcVc+yu?8x4$w4Ou&PB$bvN*$)>$7n@Sx=K4|l~V&}FyliU zIn$InAKdfIz?rG|KQy>k;4Ei+i2IeNzFUB~PdL*Qf8xkls`&3zJUehcD|X_3eZNoS zf5{gYh87RJCV%b|&QisnIC54iOx$PH{a!wY4Z1k&HScYujpy+O&aqbh@jl@USL(pH z$C>5WOK)8g8eR3d(#ErY1LtJpL%$;}^}(O>&hd}u3&R>lRzn}WP(q6pT zc(pk`^lQ$Vg`e*?GTi;vSMoW${&k8S}Q{TZ6#i7&L6Gz#D{V9 z(3{p!>==7FD;IypN#agft9>`N5--Npb9$9y{oHy}L$^~J%AawVGkWo7oaBCh8CM%^ zTE17;{c%!w;h^tWCJu;+T&(_9aGu7^F>SL|`Fv_Eqw?73d{G}ptP z>tWCJu;+T%b3M#;G1tqU=6cw3J?yz2_FNBpu7^F>!=CG5&-Jk5#WTh~V#g65#}RfM zVaE}69AU>1b{t{H5q2D9uYG3IGoIr}n>dcJ;|Tw~I9B2tpRpZxp0Q!a3wFF<#|w76 zV8;t~ykN&m_S$}@e(HG9CXN^Ec)@=!UYzl5t;*Tr)=HckZVkm*;nr68d#wQWS^?~} z0@!N>u-6J;uNA;vD}cRL0DG+f_F4h#wF1~{1+do&V6PRJSu3y)YXz{^3Sh4lz+NkW zy;cBwtpN5~0qnH`*lPu_*9u^-6~JCAfW1}#|C076M%F2?H3;#t-ob7?0$X?BW4%L6 zt(&l0@8EB3g57!te`_n)dI}%w9nxBx;A5QyTSMVvJwjUR9qiT}*sXU+YYl~u^$2X; zfxq<*{?=32t#|OZHonzwB3V-Vz{H;x3YYqIZ zoA9^Z!N(c|w!Xl}dWW>uP}r?^oE8n@vd|j%SnrV5nhUnJaz5xC(przWT=Wk9)?ZGG zw!+7HhqTrvE(^_t-5LbD^%QBXckr?9z;3;Rzcmy-)+5R@=??s@cks8i!fw5Tzx4=q z>mB^9vta8fe5`j!Yi)v$bryE!Rx}89>nYM&@8DzIfgOMJ4*u3q_*jp?)*bj;@8C~b zv=w&i9sI3Luv_ooZ=D5OPvK*|Lt1MSe5|uzYbboIM@VbEgWb9VyY&uft)cL-9)Ybv z@VDN<-+BtW^$z~lDcG%d@VCx_t*7v@-ob8d1zR`e=MK*)tl`78^YYIH+Tp)CFS93d zQ}e38JqkDL+aWZ({tEF+r?m@LO}tdRbF*DToBJ*l4_MSHe7D(o;!gcqh9?L270(&c zJPh0MZ1MHGHx0eE?k&FHjV58)MP=?C)(fNB^pU;c#%qVptc*NONAzvi`)0gFhK1rmXK)juumg zg9nTiQ@1;g7$>IAZw)Ln*YaGQGINc0K0QW0T>I2D%lXhIt1KKTJ8d=g$Khhyu--RA z#IrR+QKJ7+mh5pY1I8b136l?+Q}&oYS`?1^ z6(uwkOnsWheG8a+qN(7wV*Sxn;&@%GUx?%N+D<#zKfSLdAKK0N$Ni}Qsw!b*;MFgG+@QHf}foE3k zleoqocy7S{_8OhT+}~X&{|4hbg-!48EqmOf2t146ANLRf&&2R&)zzU}{Q>gn-)8r4 ze2>0L`|2fy@Ru&9$tUhn1fG@gAJMcbjNJJ=`NX}Nz%vu&4qDVc^c{Gn>~Wtb@a%{^ z?#Tq6y-3?@@~+{VUZ*q zdrE<4W&Gcn*)+7c;Z*s=wbDxc@3_8Excg7#v~kU~a=md)v{KJkXEzRw);mpU2fb4# z^lx#pIIg>wct)iDam}^T4sm@{^~Aoc+p1yEymH#58-HFp=&3X1AJ^bZJeyLtxaO*M zfLp$?dZ_p1S@K!A@3*BJ7ym(JJ$wCMOXt=-SN?GgKJXljf4_(8gi%|aBmZ$9e^~mm zeK~eJleyFmVNJ-fs`hEMgd<)yVc3>3#_L-k+kAJ@oB z+^eLGYuF|3E9@gyTT!apx9m^ahQ|)6l*RKRKJocf`H(iQmzTJQ;g)xPROcFN_M7615LT*-&D%N`#rpFnk9!>@o`bOy_ZRM;Apfqb)C=uCo-8}}3D2zf6GxtjVdCDn>3I2UF@EiE))(cn zqV5T-7vRHv!m~2LZHp@pV~=}` z!SQ;j_pWMBd>B`sU0RMEV=tNnf5u7TPFZn}F*sg~s}H?1Qu+7YdB5=D`@`hVIE)s; zpK+4=0cKqNYE(JTcUIp!j5&9h?2NtWE_~W9-6J%7cxYe^&~pduxgPdh4|}ecJXTn~G$hnaJk>tWCJu;+T&(_9aGu7^F>SL|`Fv_Eqw z?73d{G}ptP>tWCJu;+T%bGu-6LUU()`> z$T|hK1|eS7JJ_v9VCxQitapg1brW{$9sI3Luv_ooZ*2uzPvK*|Lt1MSe5|uzYbboI zM@VbEgWb9VyY&uft)cL-9)Ybp@VDN<-+BtW^$z~lCfKca@VCx_t*7v@-XX2E2|m_Y zur(Au)+3~~-ob9&f!%tCwAN7gSdYNg9r#=C;BP&J-FgRqYZL6&JNR2?!PZmwSnrV5 zIt3r=EZ7Hwy?~vA- z3%0g$KIk3NT93F~^bY>kUrvj*!pC}twALmr3(bYy8U(xb6ltw@@UiZ|ZoPxQH55M9 zBd~P`{?nYM&@8DzIf!%rs ze`_dwtVdw$4*acm@Fy+W3cK|V{?;bgt#|OZ&VsF{@Uh+@t+fe0)>*JM6h77?q_y6` zZry?1dWW>uQ21Dnz}6u6Tkqg+J%!zR2Y>4n?AAN@TW7)6Q}|f#V7In{t()?5hvyX5 z@Zs8dd7RqezdA3oC(`x69}C_e*?;~|1@Di1xS~$x{gLrItd@CyWZ$dT%)CEx)pHFp z?~iQ$#|<*?k8Imulg#@g`=8M)^Zv+TqqfPsKXTVDJ7(S=`F5Q)nfFINd%tbw{gJaK zw9g7@f8_VybjZ9v0(*Z1AMcNl*83ym>HQJP^8N^Q@csyO^Zp2R_WlUh;{6e>(fcD@ zyZ1+E6Yr1ER^A_>4ZS~7+qUKXk$+~}qKo6Yf$m|}YS@eBerA1!J#Cov6ZXS%`v?W^ zFYvnu?>oe`g+gUNBL1$z`xN}{!TT3+Z9%`spxn5&px<@Cacv>X?T=)Y{gL<%o$YaL zq2eFc7ApC~wS~<2^E(xn8?~f<*CFj6f2ZPl#goLserMx-kT{p={Z3!6?X-jaX`f0yvE7_Mzaw$Ew6p6& z`+I+c-=px3Ao>52m=bs1-S++n?`3;`g!i(&KXS<9Zxp;g!aM2SAK_hW?~m{u}cd@-c5}$uE?~nAnZPm>CBb&UvPW(=0d4Gg=Tf9HQyV%|z ziO*enN1uN2(^~6g-XA%&;l`QwM|h{k`y;%U?fsEw?`xQOf24o+jWh3$OgO4}=KT@g z>+$}`8`C$=ygw43Pb&3qJa?2z$JZO5e=7BS@5U`N?~immv0di^yo_fa4nfFJQY?Ec)A35g2 zE}8d7;2z$NM8k9Ft|+SKmRKIb;hq!xxg!{z%BgE1BBmAbv>+Qtd`y&JP-6`|_2=|Hi zM~I{MM~J)kM`qo%L+1UF`0TCUq4_?^?T_epiP*dJY?*m~BtGZs_i5CbewW)H(Qg;= zk2*rXNyCSJ>irS=wf9Hpce(u${npX_)cYf+9#S{+{s{fr`y=!_?~l+=y+3l^!E0pR zABkG2;QbN$wf9F3I-p+W{SkiCu}vDf<}EmnS9@cxMB z4%Qnrr=)dS&-K_n*Tc+B%(<}Vdf0P4?71HHTrZAuVr73M&Gpzl*TbIcVbArj=X%(4 zz3geOhdtNBp6e_2v_Imx9=qpynEaV@VbArj=X%(4J?yz&oaTCQe70e(hdtNBp6g-S zjkzB7Tn~G$mp#q(u;+T%@ygHpf6I;|cE=HR9A&S4X7jr%|KrbW`8ZbMTifscSM)p9 zQmj>3!?9Lkea0G!H5qFw{JmBHd#wQWS^?~}0@!N>u-6J;uNA;vD}cRL0DG+f_F4h# zwF1~{1+do&%-$dIT7lEDRsegg0QOn|?6m^eYXz|NEbO%c*lPu_*9u^-6~JCAfW1}# z|C076M%F2?H3;#t-ob7?0$X?BW4%L6t(&l0@8EB3g57!te`_n)dI}%w9nxBx;A5Qy zTSMVvJwjUR9qiT}*sXU+YYl~u^$2X;fxq<*{?=32t#|OZHo|?!e!A2Y>4+?AAN@Tbp3F-of8G3$~uZ z$9jjf)+zW{XTjD`_*?JbZ*2lwYv6C)gunF;KGq-Z z>k*jy1l@tZ^$z~lR@kj~@V6epZoPxQbrx(rg^%?PX{}B0vChKIIuGw?VYi+lt@RE* z)*aaK=Y25zt)cL-9)Ybp@VDN-+Bjs>nzxM3Lono(psC~W1R(C zL*ZjRLR#w`?A9IFt#?Rk4TX>O2y6|4zx59O)>GK6cks7P!EU{SzjYRDJ%x|;4t8rR z*t#h{cX&?m{z&b-T;3n~ug=Ttk9_~p2Q_cam=xC|dt~pP_IAy2PfZms+~WC~51zk4 zeA?5Y=7`bL#n0S3q2|jsXNs5CJ*H-@TV{)IJO9UpJG?wcyy5Sb-cvaCW^vUm6FRK5 zYnj{3YE?D+h_cV9lLuBE@X{>#%;`F}>a|B_h|k{cv8s9>4p;op<&~F?HDdixFb#cHc&2rp_Zi948J+{3KZ zY&~svG3!eokKRelI@Ou$HWK5%a%!j23GYwK;C=4zP@3Ohy7;0l+n1((GOKK#+@$o? z*>lBPJn&=9nf-4S&z$t9n!X?3E`H;pt7<-6bccB5$Te#oeDO}Pzx%DSMy^?9d-Sie zf6S-K`NaIIoc}(Pn-pAbtWTj*pZhx$T+dklg6kizy}-4n>nfb^`)kGVx(bbVA0sB8 zmPd~)+hhJuy*Nxvxko-dSWJC-9CMYJdcHJbpg3Mv)vA525OZDeKig|;rycB1`#2xk z&H2acD!E+Rxl*6l{;sFulIs6UVoKZ}uE|Qx9-XFppiQ$~OFJ#SDdQe^^^@&OC!Jol zzf)(Y(hjp`$ftYb7NzG$&XUhgn>H^^Xn0e`eKP*ZhNWq*OqIRC;HITb|2SR#v+v)q zbV9?MWnXeolhXQ^%#{B%TdrL?>iZkS?T=f%)a{INxreu^SK4FAY^8nd$**fx{`nU9 z^r)&+dg<-y;@>X%pr+-EGv%}OwEJpCbiG~qH(T^ZP5ajKWFLFtOcWli%x6GCO zwEL=RmX5ex{_k(zV&U_>%l=0-`)uLstIn7Ir&sS+)3{!_&R_T5yk_$YZ&BJIM>biw z*@5%Rb-VlP4rjK!Q~qz>`ozNLUoZPV(Xr0L*P7j0_BrwLD%XF(pP>v`|>i#we1-YrV|*Uz7;TJXEu#NVv*Rn;wTm+KJQp~~$L>sduTiS?9af2`VR zQaSBcC)6uEvgSP5&))j=swG|KxgDx#2V(uqPBW{{_@*4w&DZ#`YT7k7m&-l0dExGl zXUS*5;rCS?`OF;gSwB2q)$+L6%JYO$qe8#u%CU?0TY>v6-G>G4L-L;*5%jA zCysT>hqUn?E^rUS#WouhwwXDllFw25m($Lf-nP)X-dNdVA1NHa;#&FlTDMUpAJX11 z<2w1gbJ5m?V;7E9xv}pQJ_{q|Pg&djVS?-jtiFEX%O1mJ-~WL6g>@H=Q`*>H3JaEw zk`Hm*_@p7SZ~4t?g~@l0kbmqKg^x}gEg#~(!AFC{+$V)q2g#o}u3UYX{7--3&8k!H zA1OO=pLqKa`MeU&q-~oGxU_230p+q{->I70 zYM}gMf2pdOI!t-;9oLmlT_O9b?T)HC@0_7Z8~aO#clWtUKJ+`%k|+LGeQ~AyW54L| z*%{@!(N7P%eW3j5*ROUe*OPunKE#W(UpFte5B>CqMdkco8FNR?$O%^|fBN-+JqJ1e zh2&3K`swUt<+LYGy0K>H1%p*qZ1Wo093T4i{7yr~*DM%X^Ln@PHOAPLh#mEh?Oa1U zbFVT^5^L-+UM0sXwr36Pi4WuIc8|6G34s2O^^@s80`p2>N%!9^>J72e6>A1PqW~|M6 z?tnelYt1&z^|0r9+0$GPd#;B)*TbIcVbArj=lW#VT%Y_k*TbIcVbArj=X%(4z3geO zhdtNBp6e_2I9J-AITZF>FMFEnVbArj=X%(4J?yz2_FSLrn(LFl=6cw3J?yz2_FNBp zu9rQ{^|0r9*zw{S<{z=+So_TO>wIR*$FUOM_>2wv85^$ccUP%Reog(3brow>)^Mzq zSf8S z1-1quUe-I*JM z6h77?q_y6`&hsR?1H1K(%1s&yAL|j=x&wdf9r-6ch244we`^!$);suHXTjD}_*n0d z);a|r>nzwB3V-Vz{H;x3YYpX}bQAv8JNQ_Gz}6S|pgYhzq_u{^ZoT8QXb_i$*1*Sl zhqUn?mga)3t(*^fhqTrsE*HInzx9{XqOI_;-XX2EiOWKBVYddsZaqa>>m7WoJFr{t z;BO6ukM#&_-GRUL4*u3w*sXW)w;sW6y@S7X7HmC*kM#~|txfQ;&cbdDg57$GwAMQ* zt#k)={Lwr3TSMVvJpx;Iq*sVLTTknw88VVol5ty+T4T8V*4*u3t*sXW)w@$%sy@S7X7HmC*kM$0A zYb)5gDL;33PGJonuAP@hs2%>R^D=uPtGzQ^njGG1j}h4xuRqp7dnKK(&faadcNM(o z-H}=MC0C1^Y%)5l|J0r0yB3Yj4)3!}{F?>WX8n7-CBE{-iP_2HJ`hh>b86P(>379V zH@zV{Xvdeu-9Nl3yKnCY#b+HkGn>7~jpEb0&d#3h(pTJa+MMjro12Jl{O!%z(G9z+ zZiyFCx8zd;r?ldfr#O`*PIVBcx`|Vr#pzna=^Dl9+Qq3&#P62dN}SqIb*pXLchx5U z%(g`@vu4jY%UTU%ZG5kBYu0lZvtg|r#Wg2<@Mm40wE&oPeY6V9x;|?MFzfoPDZs4j zvz7s~uFo0-%$fxI5HR}^tYyILSFn~Ld(?=wv%g_~_C1^r`ytMseG-?;{)y|uzKZL~ zev9jWL{<45TgpoI8aVljQ$FI9zc`g!!avnVoa!lNABMFFeA0E5?d9tgr*;sh_7SIc z6Q}l6xv8DSsr|(%F5+JjQ{v9rBy%&&x?`LdtGEYPcVu42zNGF|**T4_mk(>MJQLu< zS|iV_+$XFx^4x&^%`XRK7d?25{QrE*;Ov`w-j+XWt~`t2&srnT#PBOGMxJ-Rd^S36 zXtucV(@OhJhvC^vT^s6~|E#(4421tW?+?$8Yhk>t)}-^*nj{)NIqu)|b!vb?0PPJls_L z%-1((JR?$n_NLqp>>*H3>>oWnE8G9(b>)Bj=kv0yH(XWr?I+A(ZC7<;Z;E!Hp7*ag zGaIncSBlr6C(q3u2p_9GuV3%>Y{wCQQjCrrHjA}g@x;b+vL4ePm;cVyw`RM3cZdAh z|KWb)9%FBc`;h#nUN$$o;^qnRXa9$L44>5xyEFUnjp@24AL)Om#wF^{-W2yLY1#AP zzQTS-`}tXut;WkgrCpdSs|KG=N6c3~q-CFqdl+83{;k=}^)A)@obplH^9y&x`t()W zRPI9jpW61;NFkPvoEC zsIpSrmG+@qZpv2MV@suFUyJnu@=y1P?2LP?4PhU1$&J~`!`4#%Xgk&;sAuYTvg6OX z68`K{v6g{P>Zjt=ujQZmo%~4~HKgpRpUQvcMWeDCPTx-U)UV~A`kgrSQ~B(4(KXrQ zM{caN?0fLMPJL3p7Ek?vMwZNK|bu-6J;uNCBYVa}%p z_F4h#wF1~{1+do&V6PRx*0ZqJ3Sh4lz+NkWy;cBwtpN5~0sKqapBP!Ez}6td%X$a9 z^$2X;fsgeLF|}^OZoPxQwF!3X9sI4WVCyM-tanIjZGw+=7HkcLkM#&?t#`0ncVM^P zA+0qOKGq|!bqD_Gxk%?ASWjWM-ofA61iSSP`CDhf)>HUc?~vBo1Rv`x*cu8S>k-mg z?_js?z;3-mT5BkLtVdw$4*acm@VB1AZoPxQwF&n0oUC@R&LXY#6h78Fq_s}L$2tqP zhQi-^2Y+i5*jfXB>n8lIckrj9sI3Fuv_ooZ=D5OPvK*|Lt1MSe5|vuGq<8auv<@&)_MmY>kjPrqj&JPhQh~s z1h($L-+Bjs(xR=fTkqg+ZGt`ZYvpg9MOy1Ae5`j!Yi)v$brx(5g^%?JX{~p#TX$f$ z-XX0u6h77?ur&z&);suHPhq#-!QVOsyY&wK)>*Li6h78F*sZN#>!$qNk(*OGz-g|j zf@|mHWt#VY$-K;-!ciOd=9}00y~C@I_Rf4hd-G@dWImt$iOu?DPo(qNFTLb~%;&Q& zdiave=d<7Z;^mpoXK%go%FO4p@7Zcd=JVN?bR3@feD<#!j?8>M`$m^ullgr1MrV!5 zd_Mcre;S+leD?0~_ZdE)9rpR``1pKw()xUM^7Q%al;!i;sYB0nK09^u`Rvr$=d*Jy zKA)Xy^!e;uyU%B*O?*B(ZRPXXX+xjSUfZ@m>5Th-X4|4?y&5@!K02->M*O{Qj1{R|UuK zUGXh!+2i-RIM+lRzjvkYUf~nJ7ge#x??_erLzwM-NJaJ#eZ&2|~f2FOz@{G*qvtPOP8JW*#-*VAena^jB-*(bBo=Dq!i{6>f zXOG|d;#>c!Prpmf&U`+5{B9HHsmLC`>BTqwRo1BM&&_;3`|L9=&3rz4{I(NkvB*Du z&xx~DpeCk z^ZD#y`>~nNXOG|h$@q;iaf#pTskB4AYJiXO5na^imIc$99^V#=nH!1V^?D3mGoSmSwU9z#+S?PTCmyW+K^ZD%YJ4w3V zxDVqumUJJI|30(EXFi`jeh*3a7(TaOI5qS6?D4n7mGLTmV@dZaY2!DLbYF2@M;$Xc z^ZD$g_4(|S#qW*riN9~IjCJvQOS*^2=dL!_Wj>#se0)CpR>w`rd_Ftn@|$P;KYlBVGevam#NFq!A2nrU=JVOP zPx#F<{=|{rRKvvG=d=IenX5CO&mMm_pYgp3e7H~etu@!hxW~6euvgEBzd=dov&Y}) zb7qWu=y#;0p7`@!68z)0$2bp0KJ-(c&rZMQ_tN;&@5l##((-*1?DSKg&pxfod6~~= zr(g5iZ2akW6%6&N$3( z>G5Zr}jrtJ=epY z>tWCJu;+T1c=6pU+0$GPd#;B)*TbIcVbArj=X%(4J?yz2_FP}F$GOt}%%QO7df0P4 z?71HHTn~G$hdtNBTo-e_>}jrtJ=epY>tWCJu;+T%bG__ou7^F>!;Tlv75|7GM|>Pd z*m0D-_L=Qp_RN-#VmB^9tzhdZe5`j!Yi)v$brx(5g^%?JX{~p#TX$f$ z-XX0u6h77?uyqIi);suHPhq#-!Qa{hyY&wK)>*Li6h78Fq_sA|$2tqPhEm;<9wDvu z4tDDf?AAM^wT8mSdIYxaz~6cYf9omi);suHn_#!z!QVOyww}VrdWW>uDfn1t!PZdt zTkqg+Z30_s;BVc8zx572)*!I;1wPh0q_u{^ZoT8QKA+uM10U-h(pq!D)>h8P=d)Xn zxLouO{?=bk>+{*Icc_E4iOWKBVYddsZaqc*);suEcVM^P!QUDRAL|j=x&wdf9sI4W zuv_ooZ#{zDdIx{&EZBMqAL|{`TAScworT>R1iSSVX{~qgvF^Z*KY9m$YbboIM_}s? z{H=HJCoS3vyY&wK)+X4kcks8)f~}|UvECuAwFy4fS+F$}KGq|owcf#Q-GSYDhqTsE z_*jp?)*$#>@8EAeh244wf9n+N);suHXTjD}_*m~?x3+?ueU_#lLyIc=|c}6(5Mt`0$%z|26B}OWKR;)~Wt>;u_+udahR8eE0fg`;%){zxPA~@e6x3 zsMs&Mu3^RhPqQ0WJD*K@Y+UX9zZ|exwadM2y)CL;p98*XR_%IjviVlkuK(JXZ&mH< z!oKanb4t_=|IQ!wtAWX9S(CjBF!}G$Z@HLq?|FCg3_JBXWwowi>UsQcPZm@E^+g77@%*X9btk^6*ulr1 z_*(I_gHH_b4vXF>{@7-mc<0f7DYk8RxA^*p-Yagu_U6tbfCYFBWrM`_;c(%=Ow%JJ_H0aXz%0^QS#s zF7534(EhF`adG_}uP%oiREZtz*ujn+?AXDM9qib_jvegS!Hym5*ujn+?AXbkVh1~R zuww^1cCcdyJ9e;RXFJz!f7%3g>|n@idRY0QK@X2KpbVUL+Gv181HJ!Znu*Xbz*m+-T%!IdH@pW5s(aJ4#+=lbSHQTRN-FBk|;!panUOngMg<`I8!x<%U zy&cxB*gKxnpyGeTb?a90xp7FtO8)iQZ4i$dESEd%nnu;G&$ZVyu68|7Zq=mP^>2GZ z6U}#A3-%Z0eyG^tzs8j}iOFZvKUIs#zrzVvD5jKq@(nGjNK1Wg?^>q-Q_q>*I*O_P zL6@8&=DHrb;~X*9Ydh^=f7-|S&~DD3_H?@7JgFQF=MzMnj4fv)w z=Dm&q{^a&=i($rz;!ZQZFJ9l|3h}<(e=5$c9xcAJYn|$52Tv1^+i8{RJwKi!Zm{=i z)k7E07e9H~>eVfW+%4uBSF~6t-oEMD75j%rG^qHWboRQHeD*%9VI}|PzFoiC<@W5} zsM__peDB89uIJsaH?DU5_urr#JFW%$bEkZ)F%$nQKba{epD*v_ZKoaVPy09@+RgdXo-UVmc714n z*OR!o{*D)Oah@GJ?2aAm*ujn+?AXDM9qib_jvegS!Hym5*ujn+?AXDM9qib_jvegS z!H%8nT)X{g6WFnX9Xr^ugB?5Av4b5u*s+5hJJ_*<9Xr^ugB?5Av4b5u*s+5hFP?$j z2VswydNxjDChRd2_LvEK%!EB=!X7hWkC`yn$e0Ox%!EB=!X7hWkD2mMV@gGemcE5w&?_l>k*!>Q6zk}WHVD~%N{SJ1&gWd07_dD4A4tBqT-S1%c zJJ|gWcE5w&?`-#&^Y1!lI*#tA%pLB(%qg(r2s@6j;|M#Bu;U0jj*F!8F@=H+&) z)#kO@oOM6+ORY9vE{*2(Oxonvrp^7VLf!mqse0Dx@n4-D=h@P0DX{w&?6oi0YhSR} zzT{uKU+_P^U*P^l`@4U^UhjfywObwOvVXO9+wQsh*h2{Xb{jtR{qCX1p!EuHVNmB# zIP_}qHoLZs^V>4vH*b*N1ejC;7SlltX#LR{vSo7{3#-_1|*3-V*k7z2bDe;&i@{$r|T7`>lLT#6{qWUJ-J?Sx?VBY>uYp7r0Y`q zz-~9#?FqY`VYff*xWK9Y863-LL3zop_$GhF9Zu~dpVV&R)Slwh&IP4S_ZytzqWg{Z zBaZ3*B)+9|f2ti|w-4-ggWaC6+Zj&R6=25&cD$0E>ynS-i#=VJ?CHA1>AJ+}x?Imd zdeWxra=bz=Ui3TJYwyD?bZ`8c?!)r^e4yerrtq8Um!|IccX`0dmSNu~KB>Xysok~; zGqyXk1fM*had>I!Jn?qL)xyp1zbfW0|6k5?UI{;#bfkyLk9=YJ9c3qbmF>~LVEO(t=X%EW79`hqEs((Iq$zB_;@_piV=Kc}? ztK(H3Z_D#|8bALn#{YC(`FV};U-MlW|HYmk@%Ow5dp<4a^Xq!<+Opp^aokvSYwA|> zar5k>-QTH!Tc5dEHY%K;dGLen*2}i+H&cA$nkx%)S3W0>e+%*d#qr+@(NFVfOjn5M z#WBCCn6H>|BbH}-jqQ|Uf68$_l;iyQ>vH*b*N1ejC;7Sll;h`+WUorsg?|A~`G`~g z;#96U)hEM0)l*D4F<&v|(2n?|>$N}aAWrQgPVMG$X-{#i5A7@_o$Ez)m@|Bb@3lcD#~Z@k;)R7o6Hh{;AzuuHuD{;{{U= z?Fgs1sQ!*u&aUfC{)JpVV#f=6Dp&SYpA5U>1v_4_u7Rym=*Q{%>Ti3wWHL!J! z(w6m_>S#`#6$w{TIf)5Tv6nowvrXoPrqxU6v4tv8A( zYnxpchzp0V6W6;Q6!#c3s_NADmx_ry_bYiudyVbUKlanIf6OPYvz7CS`Inr3EVtxx zV|_}lPpoIj^^El|x&HCGO1>`oe(rj)*QD#kU!3wOrRybsaVl4w>LX6|6sP)&({+g{ zld{wG(hl~geZ;BV#Hl^Ssh!2C{lzIR;uJ5{KgCf@8&mfG&HaE+|0n)b_4O8O)WCCh zonF;*(j_(AKmDKRQuum{L9%zBazfSHZElr)?yg%GdQMs?`~3$k?Qq*&kJfOHZ8~vG z;q%)blTY_4Z$;~No^>f6i4}_YcJEJs_Xd zhVn@ReH-SWxW={W*6_`ZE(<*xw=2O54(%6qIOtAs{OvhD0sFDbx`xGC8F4@y_mpDClsctcy*7M0HJ$K0-ud5O-KaZ)bwC@9_eAEtpuEXx< zJvh}TQ`)rO1pB!WF3(2?$|qf~{p0-GS)AHOoZ3yC+EdJRQ=ZC7`xc?-K zELFVV{ce9W+}!c%68u%4`@?A))(`N!qvwbCEfn!%Z%z*5re7iEFaKZ8r+dH;CLQTv z@*`iE=L*V8_JZxvU*%!vn=8&I=ASwL_&0O8@!#=NKCv8?N7|U5$}8uyRPoB$b-l?y z!=CaHr~JjKTyd(8IMq`euZ#MN({3>V@eoeqkNnfP zB=&fSPa4N$Pve{FnZ`Y_$3y&+y#ObFampvd?(q;#<;tGwBldWRkH3$HW`$U}X zAF=xv{_bBe*F|~BuJT~_FPQs_^5Arzi`~Dlr+y)O>MvsVuW~-+{skwyt~dE-xqQU# zU)WQ*vZwlp-M{d0|ANzX$tPW}{nfwlN$n$hYB#a_7e1+-Wq1F=p5pSK;zfKNyT4_} z5xe6EJC3m92s@6j;|M#Bu;U0jj>)e2CI8xSGPaN7NSip0u;bY0H`RqkdpxXp4PK}C zVCZq@kP>|Qex>lpq%{IubKBg|XpgX{(I*7#B`bK8OzCB|5y%V?$+d=>;*XaXK>0#obnf^ za>c1W;#dy#Ec@I!MER0Wx-Q$fUi;GyV(LqI_@{OgbA6PT>O(t=V>;SjO#8*_QvDsT za$hb#ll(2a-(h#ZgWd07_dD4A4tBqT-S1%cJJ|g$*=xto*e1VZ{3O2*!qJCE&X4G1fv*>%fr_4 z?Du&M5cb+2>@`E!Yl*Pe7-6qH!t`a<=HRqPERJh^TEoO1>#Vg+INJY5_R6{5+V$J= zdg=d$_1k>B%J)@y?H%?SFU(pv_ZjRpVc2WMu-A~`cz?!uu&v%nNNexnbRUYnMvZ^E zZ|%?8yExtFVy}Uxa`hVuIQ5r*_|5}o+1%8;DwMyU+aqh%w?nA+%@Cby^U`VU!q^{& zi+66eYglFBNb!J0t-{nbM~gf4YZ>l*dW?9^kmljJI^)FG@7^@LHL%PVywN1waYUJW zhxNk21IEgy;l^u+?^c%c`EzmgF!+;EvOjm+Dq+D%SBvMLyt4GhrNhKaXa88b{e;04 zK7H3KD?WuLmy1dJ#PI{fKE<7C1 zx(Q9=*)VWC11Ip^c{rYp6Zr1Dc*drI@6L-i+n{2P-d^M_EZvQsBhxa~= z=M}|rU%jLdW`8+BKJh%6!1rqLAJMcbJoEE4@`>l_1io)exq}w94=Z|HD|;HwhDZc7yDzK zwhjI6oFxBa3!8^a#+Uu$nLmN=3*#Tp=LvkX82(~-i}1+x6O?xUl}*D#=T27I)}L+= znjA1yK1Xh_Rp490_`fr=X&Aisb@GYlT2$(P$MucE;$Ylm;r!d}H;{xM{gfR_^<4Y2SOsDebe@|Fv{nqcQT2=cNR`S&VM*cU7T@;8Cw@y<`H(iAZBpVM zhFjkGQEA!ZgDd&e?ORUU=et)*^N$@MJLU3yVf^DcDwTXl+wJjz@;RizUrP<|y+q~4 zvt>$rE8J!AU1P2*o>5cco4?qbZT(rP=FLl$Hl8O_;=APd5J$fAOP%AnG$ph=lVd7rz%d_OO#rU;D&wWl(+W3v?z_;D;;XdKJ#?&XC^%wY#KlUp=ZxA}QJws{Z z_pk%sj>m_7M_THGKW6~oAJ6#-e0Lrn`e~hc$BOCKe47}5`W^Y;Pg>3rz)nBicgYFz zKla-;q0dDp$WFiJJIMIc@5mpfpHBa<+_ndP*E*ci@f4-~<35Ezo8v>j=KIU=xj*h0 z)_?0v`NVUg0j&!=CG5&-Jk9dU3oi z=6Z3O>tWCJu;+T%b3N?29`;->dz$NE&-Jk5#WTY{V#g65#}RfMWv_i^`Oe1 zZ+ymv9WU7NlD)RymHStE#->de|Np1^9pAvWR^@y9)=GR!-x`YV=UZFh@3jKhYXz{^ z3Sh4lz+NkWy;cBwtpN5~0qnH`*lPu_*9u^-6~JCAfW1~=X050$YO+FY6ub)+4ZW2R_z2 z#MHV8yY&wK)+X4kcks8if~}|UvECuAwFy4fS+F$}KGq|owcf#Q-GSYDhqTsE_*jp? z)*bj;@8EAeh244we`^!$);suHXTjD}_*n0d*4hLg>nzwB3Lonc(pv9ex9-4hy+c}S zD159(VCxS2t#|OZp2BXugTJ*2cIzGdt+Qb3DSWJVNNb&fk98Jo4TZn;4*u3Au(byM z)=l_Z@8Dw%0$X3;W4%LKYbfm2J5GxRaam{$e5`j!Yt02)TR9)}4r#4NTrPSCf9o%& zMO)!xy+c}S6PJbN!fp+M-Fk|&);suEcVM^P!QUDRAL|j=x&wdf9sI4Wuv_ooZ#{zD zdIx{&EZBMqAL|{`TAScworT>R1iSSVX{~qgvF^Zby@S6s6h77?uyqIi);su<7Hx&y zdIx`N6YSPI_*-Ye)>HUc?~vBo1Rv`x*cu8S>k-mg?_js?z;3-mT5BkLtVdvL5d5uo z@VB1AZoPxQbqaRt9sI4cVCyM-taq?mTfx>%`MJY$3Tyaq?Yw-p+Tp)CFQ0W=$iDtz z%)N`_w;zugvq(IAuYJOKJ3lDiZO5}i!=sjpPuYEVc=hq+;)hn58aCSMU2&bBw}gIg zeVMrefdhur?L{&f8~V^668* ziiOg$J;l_2$zDf_xh~uPa@&fM{YSq!qU3xosQXim z^Z#O%3p%*mH4m;=aD93$?^SR;r;MLeaQ#w$?i1z#_Aw*&reAM$a#k-yuM za^23<$L&u&9T)1Kk5`ACYqIT*F30ZGra?TkdDrm73-^o9SsBdu5Ugs zo-t)w=rHJQ@y&bQ7G9qDt@zk4LRkOE)r;i0-u@4T;cGP%*IDCn#SZ(7FPDbTH`umf zKl8yh760`f%f#gK=8Ij#T~Vm~bdaQ@Je^Lb?L_iCK~jWus|aJfCFZCr4DR%>xd!S(F&-SmR%Uw1`N?6|Ip*FISA z^|nP7Oru=Rssd={VI zBA@YOd2E3XSnybQcf~dp`>V&bsrdg;m5Iq`RH!^=y)55n$)u=^nFJ_x%H+D;#|KYb8(AB5cpVfR7UeGqmZgsJ~YuN_d_ zzV8>hC*NvR=CNyc442&3UG|GUJwBZBQCD%@7cL9?E$%FS?8Z^yoTID7{Z5?{Mt{AV z__jaI3aysxB!1)M+rpO(T8QUtus~xbWzC&=R~WkP1{M2(ht;e2f4I#mV)EJG@~<-d z$^Vpl-xX7CtK(i1Q=gv}Jujx7yES}TO#OEmuuRN7Y5OzHKP}mRwIgpXIiDvM9aM7u z`!Bw`#^s*=@{S!`pSs6}D%Z3A1Dh0F|KD!gQTHVE{QctY1z#_Aw*&reAM$a#k-yuM za^23<$L&u&9T)1KkJmBR?^|p&`fJ6m`6pe)*WHzc7v9)g-0|ci!}(Ws7XQ%Zys+gr zyNgemJUDdjStV}1d`!6dgGERaZ*xCN* zli!x?f8kl7|5pf4;>$>Vi~IQ6N{dz z^7UeOJK*p3As@FJ`MW(S*X>Mw-2T+laiRYCco9cGXA)o7{SJ1&gWd07_dD4A4tBqT z-S1%cJJ|iscJ62UbDzWRcd+{%?0yHk-@)#8u=^eCeh0hX!R~jk`yK3l2fN?F?su^J z9qfJwyWiPPzq3F64tBqT-S1%cJJ|gWcE5w&?_jPg-v`|{9XrMW#}0PvV8;%2>|n|n|nkP2h8MMyxD_rRs8p>zlxZACRBfw;ZOdLpZ>0xaz9x0H8J&B(ersR_1tgvQ)22L-+33)*KB|G z#ZOB1@AAl;lJkjeP;&m)pLa)%%e`*Sp&eYG_RSxtay>s@(X`kdQe?DIM^^+4j9Z}r1e_zG%!|br)jkEfQ2Vc~q zxZ~in#r@hIQvC6l-r^3I9aQXH?=10Ey$>v|bIcjyf7f*wuh0Cut(*OK#l6enhwJ|7 zc=2CKH}^bL_s^!?-zlws!y&qVrqsMw`r(*^b^rYCvJXl}&OcE1Po393Dy@2b52d~M zlrg2H(+|+S^vn^Tlpd%#Sos|N$%N7ojSo^j7vD3bwC;)nl+QL*H)D&``SOf?mCwUF?q3==t*i36rOT5GU+KD!^650Fb)yikG$H==8|^GXW3ovR$Ve%`;?uA~5wNgHt9Jy;@$>rN9pIf%MvC#6nos`eUhc%Di z*WO0?yihf|kiFbO`D}FVz(VI6TPUAL7oJnN?XVWg=eCb~YTRSYnSI`zLXT}*D4!Qv z>?=Ft&qv*^6EpridEhWH<4?BUWn#vkQ6HXMxMyO+N`2yZt$hBl;?TmFFB?|s(|OPJ zEA`1PT)$GECm&wFQlFLQtx;*8?Y~~XQlB5TTeH$WD<4?1(mri>S*y}M4VSD{X`dJ0 z{~_bLh}WT8*Q>P8fuH`Aab3h~!EGxuu8VlRbzvRlL%gmy^f$_fczsdxzVhMzdF9pL zC?De0=8%t+5BJXzqd!qT+&`Ok_$;G+xPNAx@wYUuKNe+&@qM z@S5`Be(pSHh4SHk{_C{2ln?iFsqnV);ePJ_;*-jU{&m$W?qbf<-?eB)ZFKk5B+`ipof$Xu<-_>X zcHv^>!(4yDXUmii<4^MkA5=crKj^eX`M~Qw{iyPRhj(~F`M|EvYp?AUKJEFW^1<%< z^ggdkaD8s;*g3d9PaeHzaD4`}>J;2Qi%&bNQlCa=cMNWyWi!qQZlA@SP77|I4=z0= zxP8vw>7?LztyUNs+&(8SJRvwdTseAt@cr}0561@IKOGj04!)mX>~wSR{WJ4-*970sYqy*gd_PaT zaC-3l{O!OSgYW0&?@tTvUnh3EJNSM+yzA89{?+vHJA(UHyFc9)+`qmXc1v*o+HB&@ z!TtTcmWzY?*P{>24nL&+e&R79xWA8Xv@p28*O_-$aDQLrf;)o8pVKG&DY(C1-v9RC z@n^Rw_Xm$Zb$478JpL??=R|w_8Q1+Dt#vbQ%sKPn;PK~zUGI{eaijG6KZ+SQzIgLK zG5!6|2j45EzaRAB!r<|l`o#NB#J|3T`kLL^8 z$MXg4W?@o-b%0&tJsL^B3{*{6)Mxe-SUwr`$iDzlfLTQ|=$nr`$iD zPq}|QpK||re&>Gne9Haf`JMaO^E>ym=XdUB&+pvNe%_#ed4A`9_VWh)%g-D1FF$Y4 zzx=#G|MK$>{oT(S^e;dE(BJ+1Lx1=45B=TGKlFD$gE9X2`G@}Q=P||~KaVl~_<4-+ z$IoMoKYj*d%*pQ^cu%2rucy4n^lRMfN$bo-=AE?8T+FRA7jy3s6?5+q6?5+q6?5+q z6?5+q6?5+q6?5+q6?5+q$)4WNk$-w`NBN}pd6a*8&qw8^_kUEM^j?tancf#t{nL9y zx-Q#u?-3Pq?-3Pq?-3Pq?-3Pq>&(U6dqlM3)hE42q1d!J4LEb zdZ$SBbX@#SQCyqVb)_}TO1!W;Ua;c@J6^Ek1v_4_;{`iju;XQWdXK0QFYLMZh$`_? z+Vl<>oO_R`5-;qz_lPR-!tQv%ju-5B!HyT~c)^Yr?0CVB7wmZ1p58yH#0z`w{gX<( zu;<=Csl*F=?)?+hKdm{JudDpNjX14|iPKtEG51bUG51bUG51bUG51bUG51bUG51bU zG51bUG51bUG51c9?CG5%`KNb^luvr6NcpFCid1fTr%3fl?-Z$?Y0XOYPwy1zx@^y_ zWfgPpfE9D^fE9D^fE9D^fE9D^fE9D^fE9D^fE9D^fXSZTt&)Fw=Sumccd?XzdPhs; zrgyhgpY%?b>gl*p|FkEr>q>j##oV5FF}EjP%^&+@5$bw4sZ`!0 zD(3dYWlwwJ@=tr>$|t?gqx{o*J}Ni8|D*b(_kvW<^uCblpWY+Vb=jWV6EEiW#EZE- z@nUXIyqMb)FXr~di@81VVs1~onA;PVJ?)9hKfOn!eA0VF%0InFq;k`HM5<4Ek4W`& zT>L&m+;i7;rDx0kgVS?nG54HV%)L`o%)L`o%)L`o%)L`o%)L`o%)L`o%)L`o%)L`2 zdwN$#{^=ba<&)m+QU2+jAC;Tl1yX&|J3^{wdUr_mPwy1z8g0+LQ&h~oQ^ft?cZ!O+ zcZ!O+=gea6ouXpyouXpyoub(Om3N9{Pwy1TKfP0=e9}8b%0InRq;k_cMXFDFr%3g5 zT&REAAJ=uI_lPR}F21i)>36XE9qfJwyWhd?cd+{%?0yHk-`SqtBdYW}?0y#o_PZ#s z-$jA_E(+{-QDDD|0`vS#zk}WHVD~%N{SJ1&gWd07_dD4A4tBqT-S2Eq?-5n{9roON zM3sJrJ@+0_rQc!Cy+@?_=i`+hGxO|zT04H~{m)7q8Lu2i*l~m%N7!++{hu*@*6O=4 z|Eu&}zTef3lfV9PGOxj{?`n0oenV8zap-94IM_PQ`kFOo*gDSkf0phhf9C7Frpt4! z9{=_0@$_Db;+Wo7DdyfID(2oJD(2oJD(2oJD(2oJD(2oJD(2oJD(2oJD(2oJl0Chj zBmeZ?j`B(G^CAfJ;GrcdQ`lt7ZbX~UR-XkjJ-Xn_7x|R2cin;fQ zin;fQin;fQin;fQin;fQ$j9#y$)4ULl7D)SNcp7qh?IYNk4WXF_lQ)V^d6Dw>A2+H zBhq!{*G$s;B(kUXh{WkVB5`_;NSxjy5~ufw#Q(1A75TREI>x`l`qF<_+|wRbkv*)m zZ&l3gTNQKrR>j=DRgrzGw2xL~A1&=+71_f|`)I}7K3Xxik5qZQdlOZ$37_Vv;} zTJis3?>(TbDwe))hMdD>CNKe%padn(>^@{fkziJmD4>W56JQ`1$S7F}N>D_ihy;PN zYb%111SLnwFbrXa3ysS3h(vIdq#!#jOM+b!h1dQo>5uv8I|>(QCaU972Y$N_nr#xJ;vI=Hv3X|e3^YIJig4n6dqq@UkZ;evrmS{yV;k*_$L!nT{A2d*aQ-p-hjEg?(S*AMCS|{<8LcDQn-Cvi5x`?E8}V!9FzUFYNo0__6k( zDQh2^vi6}V>_d}y#=ba-AM8Vuc((S%DQjPxvi8L(?2D7}g?)Mw&)63yuQ? z%G#%=uuo6MJN8w|_`*It8SmIvDdQdcDrLN5U!{z9?5mXggMF1U-m$Mz@(=b^O8&vV zO36RiS1I|&+E=NtuTt`lwXafH`zn>SuTok2Di!usN`8huk`J-3Qu4F4&r@0ZJe9T2 zQ$Zh@FW?`^&(KHa3v1u0vi6-SYu~AYe`Nkbf606S|H%Ah?Stk1GW&?Qzsx=&?k|~7 z5kE42p}%B4wf5z5{Fr@296x3s5yy|r?}%raPZ2*dzgzo+IiAfvB93RXkBH-0)*BdK zGQT69WxZkTTjud)_7U;;GW&>le98I;<6YJp7+mQ7FS&v!!x;g)teMFpp%swK{Ke7fx&auBckna(!`#ZAk@5s8pBkTT-zvGbaAgud4 zvhMH5y1)DTI}!7J%|H8{h<$Hvv)m6_{rLBNdf@w`zs!BQ{f<@M-~IhwmG|%cCEu%_ z-F&Ai**>>#_OdXlUbnh>dTDOorCDL*w5_3@%gXKh?xipqx}m0u&!5NlcDXS6qqoyl@D_JRxb?j+1mq*I@flGa2;HmXJH6m3z>_)4`G>T%bzRI*3q!) ztivyt!>MAQfDW;T!>QWG0UZv_45znC)?yt#Zy!!0y99I?6%|geSFgi5oXiMgh7MrV zfexsHYoP|-peKDQEQ(&ZoXmYR@meHxk1WT1^wf$- z`eEoT?4MhEM$*=Uw{jna-w{bPw>_i6Kz2Uv}Nn?SMZ6g!&A*dxsNVA6+>Sv3}yc`x-W+2ZVcl-DiRq( zId?^HAFW$cno3NHWdHczD@_->MsXj7w+S%(14bSA2X$~Q{DW&D6aIlrv<3g5t+qn~ zI>b(nrBBWWbm%fTmOd{P&N@_W6-(y^1avr^JC^e94d}3!V(7%ofDUy=2N*hlQ3pDp z4z7g`xE3;@17xBt=zz9t9sUYFv2_^KCf&K(_JSJnej*jAdd!&-eo<}fkw`IJPdM{O zT~w1*A}xI|(}|pWQFS<-K)XZEILVJ+R4ryD(9H2?ojPOcq7!L`r<*Fq+AfK0Rn9nhAo!(YKCwhrKri)RG; zsOhSVU?1JzBs17Yi=M~~_R;qxGlPA!{l$!6A9a{}GT2Ami=GVj(K~b^*hfdUp9uER zsfSMn`v^KnA3+D{Bj_M~1RbQ0po8=gbdWxR4$?=^LHYk6?|gr z08ah>aIlY#ym2JhN2f0x3HH%LVQIlW>agNSu#dVY9SQbP&J%}&eH8xPpkf`@~B1RbQ0po8=gbdWxR4$?=^LHYk|1#?i43rTN+wDKWI@^8_xxdM27)i%C$$3Z79Z#Y3a(Q8)O<_N`q9jJ}Zi;NR(06V6MU&kZ z;2y7MDD(?tzNQ)R0N;Y8kHCnro0X4VUQ&gBl%aAK#ZYyxxC+^sp=Kq-l2gB!s+E$d z-h3gJmUStjTBuVhdwnc@`D9@g|H*0fZk{+gQBr@)tZfeokD~+k1^AX0@iZuRDVCXh zDwZl<3&{NWu{gTp?SRZlU&PTj(*rUS3dGZAp9W-pq2gKQW9KdfWr88omT$M4D=R|1 z+AB+aK25L9YDY4!-Wx+7yk3_1i$jt0-jV>Xjf=j4E9!FS|En&y>sQy;qI`+I_Tv39 zYJA@eRc3iKl{r~jO@1pwo!Ayl5d%uAdT(T?|iCiA{auk744u14XY4v@} z6DrS^XgZXvb*^ztxj#iy)P)$eC+(SRjyS7Zb z-R7w=s>XdMRE1(O)VpJhnpE?cI-56!Uak?V`W!u~O71F6hnmKz##N81pFb^4ObP7dcIK14gEE&XpD;2<@avTTD3ibwxm?hzq62`@|}nvXH0oDaCN5IQ8bd8y?=|UxAT-LtnayQ=JTsHE2>Mc zoKQ>k{nxb}6;#dm47Ipq6y5(;1vTqhhT2&+iqf}~S6{BmRNItoAVSp9bHiwB>Kq$&4TQuj?uS8MgX-p`vVs<9s&Q(y0iq|~#wah*ODBIsa=O6mt) zC(lr=|EP*8ariOy<>wJpB3C6f_&~a9t?wTTZLX@8>poqq@2~G^T~(EDcualRBb=s% zR#9ulr>o{m!*7sj>u^1^8u#7qk0K~@d{uQvBYo{x5fuJV6?Iu(TlQ=O^$)G8l6Ps= z`q*vR*H&v^S$&b1sYaBGq;GmvRZs88P#-Lcpl^0oRTK7~RKq^g`o{@Gn=0y=s7%#H%d9`3 zih5dekG0`cV@DO$HX>6Ms}Vuzr>m$RLNirr{s`KUtEyV5dB8&vbY)u=^-6fAYWH(E z6;7|Brj*E3F`tFg&YUXhHC-M(DuNCtR8_NedBVa7f-Mi$Jk7S)c0qrXLx0NY2#gvH+C)K9GVPxxBd#QfrGyRy_J~E8Xrc_t8 zCZwyav%_e?lsnXbr;n=VuZPj?Ayw5|v(nU*7avCAW9^@(yS&uu5v=CP3! zf15rhr1A+By)o(r`56r>swI=tRCsnI?HyNM6|Q(x#XJy2UddZko!052j$el z@C?=TOcaeRTuwE*nxXO+jix>c<}^pKNJEt{O9 zR+o&Y(@}ZUll^nlhi}Kzv`r!E(5`DL|B86(-zG#Y+mNk>?~W(`)DV@Kby0O2n&CGEM%)O-UYEp(Of1OKhyW^6&H7A~~*UqPEx5?$}Q7WD~G|!_} zx5(w&-#wmI^$t-NE9UaG-4ag^9KG&D9J;P{mn%c=qgS0VYjV`Ncgj$o9ao$|k6lwy zGt1D*21Qlh^V#avPh;t+b4AqW-LI+cU&qp|9~MzRy_BOC{SZsJ?k}v@qSw{&{Bb%z z6jT`vbNQP0iK7X1OR!xkUo1V?u9(_Y?y~Z_#M0EgMb)jvuc)r?#8TIUF!igp@wL<# znmJAX{@3@H)q@YlP`(cOH=d#|tHK|}(8pa%vY#uhj-mGk>)$haG)INDj-jnbLRHw4 z*HrDh0(D?7>Wt{De^aS`F5knq$57>{2=(rz>uSX2(zN9P{aiQkx{4aD@6E4Ass%-I z)UVx2)2`d2)C(1_so_tTrrOn`)c3l-8a`E;Y88r7AyHS<_7_T%eZOy{rpV=^{;T<>7ZkKXrBZccv_#$rDMBm?F6#*vE}^mMj+;$ zW@YHkVR_U69rK^fEkjej3sF@o?>&4T1%?c_{kH>tA<8K(tww&;{1LL$*-8jlMshE0JkJEuu;;2eOF*U#F z71hoEuN%vDPO#hU&>>7A9>%>IOD)qv)xFDg9(X^Nx=+#1G<2Rk@N+C3c|274T5HaG zW8Sc@9WgVID_VxcQRJFX^^VRJ%|^vi6xlyYyV8m7y)y%@O?(_o8j7xJOxIy*PoxvTQ4QS8qylXO0`CtO#t>tbk5y(qP?aE>}LBZl(45T)8wxTa=K{&RDz{Y=TWCF|}e)jaZw%BOv9 z&(Xbm7F0v$WUH-T2A)~T^Q(?!3aJiyPXBJ`jnBC3x!#_~G1f4rBZt^BkM1m>e$i`y zd_Tw2rAG>=_IeGlB0c^F9d5Qxc>cKp>R5vu)vG}~z1X>cI@vWx$4WfC-?)JKN%Ou- z`kAw}PIz-d2>0EB@C35;dHj()s;XXN6!Mp$qos1IjXSTYR#(gXu60Oi+uW*OlYm`z zTfb*bV$Tt_ZZU^L)Q(G+)y#YeG`(kT^@*OZ2OKR!bJpcnbqZcqC90R9y(4m~JBwUa zn@8yR<)z%JuI9(j$5XfdxmB;?m(?k^4At+RTfMJ&-V0^uz(cv!9L?1?##5cTd-#1y zoeRm#rMqV1F0as5Qd9koKCZ5+r{78KToOuWfAlHeo?~j{+E9Ar2c;&QJ*ui+ z52bktj;eQSnu>WijMf~kqbdzJtQM^aqs!%Lshl#0RQJ~5^!bH5)fd?Z)V1sS{=HjO zb+z090Gu?jiTJX!QX|_-|2?_)_vAx6fBvi1!1kK(pIPhL>%c#{ zp0w9*H(NK_YqOiJ>+H47&DL!Hsx{2b))Mx5!+vjNzbCrcyB_Qtk@wx$Px9}2=Pvsq zpu@jwZwB@e$=(C(Ba*!b*heIL53r9&_8wp#k?cLdJ|fwB@PE69$KGf4@7n8S@5lRh z?FqE^ZT`FVj@oMpdkr(|d_i7glx!JC_q-ff+nlc*_NT6Mu$Ghcm94|*qqTT__3nvK z>hnNgebw>PP|7nsu)f;bHk4NHO6B!cR$M4`KkV@OYEfD#y66VhSM&U(Xjz-U`l{iC zQk3Hc)>lsrC`I0{K5lnW-%>ZM@$9vwT?dRcr_}$m)}Qve*Vf@$|G>KUg^{J`iGG1~ zZ;_Ry$iFX@*S!~FLuvEpfpzc55uud#NKIb%-k%soUo8r(dv~r3qw!S(>)z6R!>RI% zfpu@sMiDe+SYW+GXFE z)W+kveJ?F6NkdOJ;PLX_tN)3KrS;deFEqgD2+`t8DK!kB96#cKOhm0IES zV%gi(sWE%iD`f(4IO>VL3UP@31tZ21>K=2Rcw?_>-aV1l7Chn@Zo8b7)Ay^VvXbc3sqIeMhy%)>l1!tcw>g_f9aMX| zCezVNTbw1+4ynfmCKG&)wFG>Avwr+D{}K>WYAFaC!3 z$GnEIfO~U$T-fD*<`{XqT0f9-iLq2*`?<3N4ndA_=T|1v(UPB!`%eq25-l1O$aOv9l4;+Efn4|Xd&yKc?_SPz*Y_vWho=I$Ztxvt zX;-%$oa^?!QkMFR3*@?xsby(X&#j#6dMzt^L$0&iwdWm_V-A8oH!Hu{IQ?wvJ!)p7 z;@+_bOVT9G^`G2D$2H^INt8#nE5v+!%}xTBozq+$cy0%ssZdNKDIJ%}D-L|0ddf>X8bY)HBcSVz%{ZHFbx|Gd6_n8gXHp z+WW$Ju9Llbi(0lU&7F3>x!N*rgHo+1*jA$tmIwKdv%iQxFU)$`i z;=aX&{mgf~QPS5c;cMo@uZH@P+D{9}FCXrEHfAjIv_TQR@4p+s9P@sp?~Wl|nSZGi z<(ts15p&8DQ9k`mf3SSjJIDANZPXus>qKVA$>>>$d7qX)Zb+G>&>!vIk~Ss<41N0b ztB?wYp3C=jV}|~&8qN&6PV^qn410age8dbt+!s248U8tX^!`-%R{RFe(=@Md^^mXF zpVK?!_q~#`kokwf1%2&{1o~y`qQbsj=K|$-Z7J%Tet90(N#9!B_js!Qtq?8ekvS!O zdDEsacWxHy>s9YV<~KeM^R=2VkooYuaNmr1FEJ-P6XDyxz7=!fA0vFBuU8K8^V13k z>!`^a{E&}p=j6&*go#z2F&ouz58RC;VYa82LFo>!HD60S?{rL5!+2(9>a|I54|$}hHIe@;&#fC zl3b2>er<7eX2ki1^LI1jS}i+O#@D%!ceos55ao~~b)bW^1x6id7kS3!?0N+pTc%xK z_=^`Wr%GO0GAoZGd1-U`T#j7_{ABU1YS0tWT)wsAcJBAl958a^8&DuhpGAB2xu6+}^{^0ssR900V^Q#xPs+ghem<#0IuGTN^ z9pHA`Sw3__Tkq|e7c93KI!GOxQ3vJO@w-&FUf(lMEVNUFP1wl%*j?LI*wX#X2M=sf z8#`q(Z_nJQa;jcoF5mBGbz*-A`bl-6wW@oUe9SouSE_0w3NY)usP5PA?O|g9t+VJB zQ)Ih(<^Jzj=QT0g)P;xEGe0?M3+!QD-+PmKv3(kI-Hczs4B*UV1i!+d{iIZx6a@CeZ`DwNo?0XA@Pa!6^XC34@rEeeM{n7 z?Q;^J>%QQ2VIy>qSVg(b5+|akT_3Dto+Re=SRfe-dW?{a5j}QD#*QAdgmGu$;eXo7 zy`3bsb>PcSJ`PP#;3)f0pI%ksPOr1+fa;eU--V~E# zajliNSq|FObD}46qMj=~nJe`i>d73c=T=YVRz2r>GUw{K*ps-E~elQn=|8+g{*z>_rt>dRUJa%7DG`LgyvyRs&MKC)JUp0b94{<5}# zU9#qZy|Na9A7qULU&$Iw{Dzp+^Png5pq?K+nIHAM>B+pQ=TlGSQ$5dmGSBMy*OU2I zuMIqzm-T$@$$YKnaZl!PJ->T0zw5PuC-c5u8+fuF0LwZ7b!7d3Yh_&lnX=wMTe1#; z4zfOhZnAEH&a$3?Ewavmjk5lM?XoU{Ph`CWUs>x<_90>nF)Zs_#I~$^5yLvKx$v!A z3r5_^nilaaYhA>-tbuVY*5NX~WSx&OXsyqgWqhG6FzQIV82dKkzQC4g*B8e9h~xy^ zr$}zW{fk`(tnWt%_ak6^pF(n}E3I6X*%u!1^AF3c4c zdoF!1Mz|NV@AY!&|NY|6&vRe#HTR~5?I^(9d*15QJIWVfUhs9O^Ww0Q%&{LSXZfKh z=1;zR!b#3dWIhqz$5CBwV?MoOuruLWE#}HSM>x@sHez1z^(bBkU_M28>V|f~`b#Tz zWrm!{Wv?+qezlao%xHIYQa@(s^UAt`%+Rys+e4V4|CI9YGsCV1-vn5f`=wmh_e*^( z#}zqRzAN%|yRNjW^>IZXZI>&0YW-c&U)#lfY3y>vUep&qK#uqa^2KjxSNsWm#Lv)E z{15%5U+n$@Z_g^q>kx3=v4feDUrzNe3lDJqPZs;t$bnq`dCmOpo6-H5A0B+WyTE&g z`QoG&Zcfd&n5%SuM*lwF%glA1UT&oVU6|+G*3WhQZJ9r>8Mv>*8VTiNpKlzjUm-Dt z8FKJV6zV|!Lubk{qurCU@iX)k|3iQ2 zmnFl0b|!?dG8;cI8~-pHzcCwsG8;cL8~?MOreBz)zw~+9E^;Pp{4HagV!Wap;}_!?jB$}587U^f0? zHhyC^{$w_OW;Xt3Jx#xGKVlq6d}15~<5rIwiD!%hiF1qtiGTc+ae;rA@q+7Q96_Fp zFSH}$PM4=jxvrlo^|c&FOjBy}wi*X?FjBy}wj&UIIkH0c5@b5BSaGi`J$dmDfHf7xD@>D6;^;4z3mg9&V zE#DFO`mZDH>VJ1cAAOx8dSV=i{<M;&b!$2-{WFEGX+)WaSGP+I3Z5KdVQkh;C_hLEx~dZ#}P zp#FLd7PQNhbIvjKnT;F=`WX4lrd?*E53|veS+7H&KeMrm+1Sf${J?Dd!)*M$Nl?w!nHVO^9)@UP}{VAFS8Xgct?uwKQR@ zfc09MFy_E|Eln76VAzN;2i9xpV7XpP2kYy#bWo07O9$oawREsuy_OE@qu0_wJ@r~T zsJ~uI2kkQDJnx(O%tnp_eT;l&(=M~ohuP@KZ1iU~b}<`!nT;QqjenSp-VmzXbj8j|-#`uLyFvd070%N>G2QbDrbOU32LuWAZ32Xr) zpTI^bhwV}yJ^@1xd^hY0oVHf(&l;b{K>f`>M8L=pG z5Q`!ou_)~#7DXS#qUecO6#Ws4mR%gHXczUx50E4Nfqd~B+7*97AMrEBjQAg8N&3a^ zFEGZSnG^9$i5Y7Ej9HXpZGf>1#+m_R9E`OD#y%Kp4CDkb)+)#qVB{3!5HQv%uu;m9 zbEH0U5g2liqri}l+yzFv$Z25cgIouOp2&e+%WYX__I97!>47i@sW^JH6@3gm4yYDH-btax(ocd+`3e4wwo=ly+^LFN}qeY$B z{qAHwb#H?6QA7&!rX9CCty|Y;c5bQZyc%^k^TgBqZa!GPzrdOmZf285p@pk9lU~DC9(x zBX=Q}f$DbUtB5{Of$ejB%m! z2{YnF=M!d(JDpFM5idHQFk{^5wMwvD=aXQ4ollq{N9Pk}$k+LV8SUzP!VGBPT+ivuh<`n& zGhCA{1J*P8c+`&e)g>pTo2kYxOJ-}Lyp3|8jU(e~xXjjka z%+N>A>CDhm&*{w2U(e~xuuHGOq#Sd-)W;ft8F4Oh5dR_{<3ifScoBWf+JmpfxD)*` z?ku~ohT%G>FMfa=@ekyS-_Wl36Z(jsG490w7Y_VAu#9!RQN(VyAa#cb?lHhy3>{$VzLWBJCP%*M~m z#{bNwUs!+XFP$q1xdk@o)JBfXGDMG8L`onV?9BpKGqFn z&LbFI;?A%wLGkAIo@8g-=tmmlNtU)d#D3{z%O9aFRZ`x7y1|Xt!Nvp^9f1Z>U_d+gL0iu zNa9@Q6O#DX`GjO#=zPL)gZet3U_7{Bolkf?gLOX9asqi$=aXQ$&L_e8I-dmP;J#Jl zW}9PVwWlBacAmtJR3R8Mt*<;?ee%V`Y;`2C)p3{SJ^qd})ujlk& zyLwI!>Z9lMpq_e859*I+ePWj>=eRZXIi8IiW+R{3w99Pt;qhYhWH$OU8@rf|z0AfB z%*H>=#&0a&_>+XM!bXf+c5yC1*05oC%hk36`7*mYfNeoN1Ng`!A`l-(v>lFiXxv zxoH>oqoNP9*SOt9oku;fgz*SOt9oku;fgz^cVV3=032Q z6Y&k5%$0s-vsM8kM`Er8n>m-+%*EKJEps$8axmng961c_fz4bm^?9v=a?I7pyHu9NGyUa!(2X)MvidohwC^vRV zIj>breO{}8jeod~@td^EYZcUywFY8a_&1*Kh=`MY~(YWcGYyeqsHkzc2>n8Ov|kJcr@@W1i3WQO7*DVb=4z!uUtIp5K+^H$A^A z$$NT!S6D-$j-KC@*=XWh9kU#bOu5eF< zw)FhY&&R;>e9S86{Auc^qTI+~Hu9NGyUa!(&U;2rW}`o|v5VQ*%WV9>Z2ZG){KoQ) zKbei6nT`LMO~0fdE)kz-4>_vU?1LTN*AYc53cEz92NBoRDBL3HQ z@p}ZZOZp2oA|`d*vAx2WhY`0Z$NY@=1Y_Pte1b8bBR;{H=MkS^tRoPg%z7Px_yl7e zf%pVt9RXdW9Pugj5ueOj4&oCG`G`+2+C_YVp%3B{3_TH_VCawd1j9z;7E{je6ij`7 zrvS#d6*TI`QkUUEB=H&;%DR$ z@xQi<-zh*Q?2_?d&AlAY7(XUHv36ia{9`u#4+ll9mF@-=+A8Il5$xqp+253ayjB$Q$zjHa_T;w4BF&+3{Mj5~}6l%pNXE|jyqXb1XPa+r;LX45XS(Z@l3qbD=kfxl3WcJTZGjCSx`!qi9p zVTONnK4FI6bUtB5f9ZU}jQ-O3B*5DLI-fA39i2~@(O)`tg5`MrfVR+II-dks%hCCS z8S-^LVMe<;pD;roolltI51mh#p+BBKh+TO8VC+Jkk^0C#%y>%P!CDJoc>aKLSL{B}ZGedv9)?$WTc>aJo$T?DuTqO08Ger(^m&iv>lXj8o zL?7f#(GxjS^heIr?QmNt7kg1(`~W%PAIKNKp+4%%d|$k_gIVf8PVqbRSyDAl z!X}l{BF6XTylu?Oj>q|^W#F8v`4`Lh?pZa3%jCZfQUb63tsZE$)Sf1>g|G;%WWVVh@ z_KiNs&?w%NkIMF*Y~M~?=)tfeajAYZ=bvQdeH&0QesZ4 zpYx@1`KBZ3%6YvJbJ;ux)SPFUF%Ox!Lv{V4C9~Fn0=lq1B>ISMw$5PP7FqU^*b6yw zt=5g8o6(s>XKf3KE!swcjYdA}0M@#Z=%#fh(OKIt^c= z)-mH*aqc0`p{MSz;I%r&Jj58vb?kW(dpagPiAf!+p2Vt-VNYUM$F?W2tz+JknAc;$ zld+)3h$mx2j~x$Vhix~ufOU*{5@R~{Jc&IWlb*z+j#W=$RmZR=F|1?Tli1cV?@7$- zvEa#A&|}1tF`~zghq1$PV9qCm4mhh&a)lo6>?_-c`duNP>xJ_@!1_!KoYTa%=rcY3 zkF)r2t<baI=`*vLGlT77NT24>x6uzbtTQ+}!6c=b%b$k9IVi~K1)=P#9Z z$IpDY4))MP2b|j@dS)JoPZj+?f3XqX19BZLhgt0X>2xW!J$&^tcW_cc<`x57_x)Yh z9Msu(dcIq;b_VlP&8EAr@7l{eBV(Lfw8m!U`^i8=lQZ_{33rrlhsS4-6#DEQbeEOC2OaOo-ff`siOZQM@9wh z!Z}O-$X+>r33h?a`7KJ$cY+V$AH;)ZJ`={s39`QShI3#LSN1tDsE<03Z*(K*W^^X# zY-}OeVr(SXXly6gZhS)UiSZS|SH_0~9~$41bu9G*HmuKIn z%=cx5cx^Y#VV;?`Q`+y{3tL;q{VUSx({kF>=ziw%C* zE9LNm)Q5jW4*Vwa;ZJE7einV;f6){DBKk{z-SPDs{;clV+;`ye>#}LW_EZ-fz3wW7 zeEk@6?iX|D$N8@@Pk11gHy~snbDeo1-W!=CnN^cKUfrK2Ft^T^&r5sYQ|40#^Lx`D zn8pknpPKyzb73kREdO+T(O`YAb@8B_<(Vad@}Fp4D%fsTmrzgi$*dFRiJoao!aULc z+9BN+IuFAZl&>0k#ScdPD?7erhMZTn4q%4-AG=myM!TK!ezp|#q0f8El9qs>=c#@b zQozuEVBImyu&e9Znar?P%Hap85C4c9_)X-)pVBV;Ec(Fzq9^)A^tby<+sNm~LLY6T zPi)sV`ot&NMxXdf+vtD5~@3f6R={s$sPx?;V=(GCHCw-@F43=vfgY~tIK{?vS zpnPp(uw8AV5`DCdO7zq=D$!rtsHE>uF1Dk-_ylsqSCB70M7!c!=p#Odp3)c4U;0S* zolp7>_DVVYAobxNkpsVpeE3t^g`Y(q_+Ruyzli?QUl`*$w{YM6mUW)-N&eA!#wU46 z=NX^mE1hS2lE-wO@k##FdB!LCQ|B3<fvk<&u9;U-A;vQbLx9fT4 z^;h@NCzJazFFw4VMs>kAvK#zgb~s35+fQa5)A2Apn>d^Kp}lFe_R&Sm&6XXbl8Zg& zZD&tXm+LE-v)Z4gFGE%{7fnA$>n5*Ze!IsdnzBAn{zc{$dT`{AT;8Kr4pq*xjCtmS zT;A^HOPHbOr;+4BpP_V(QXkBt*9RN?Klivot<&={x6OBnRSM8C+9s) zd%w!hI1xtESgK(bV20!|uM#^~RIc>tdU&qd5p7cPdx3AY?W|;?3 z|L=9nUwhs1!$+~MJ*NKXSd(}d{%9@tOj5W$To-Ein$W0@<(~R${FX}4_i0I*_oVk&NXUE*=P3AwgK-s-(J0oI(@UB z_N0t(-g@&cx_IsY4NCpQ`FcSUTJ+f=s_dKYOrG4BN-aG?JFm=hhNm>5apltKk)}%> zU!Ml#|K&LCxc;5f>DhX8^z#fF9rB~2k3Od=!%vf2WwkRXsnhjLH>T-b)Lzd)Z{$DX z-nIEIij6!#-eSzD%q~-@Np?+j8ednl-fn74J6M?YL(> zy>z@0HFBr97kaLt^o32x@h@<@Wc)xGp-t(D3g5XqGrpsHtKCh5H>`3Gj`UMl!FyA$41-S7rHE^BHdciOH+S#D_;7RW=?NO1MB|adZ|CqiLotcW!=T@ zv$1O^tZ{QXv3|Py(!1-a^Sowsyy8dh>c=)x^+R{lTVKEHemr6e-IjJ2732{O>fR=8HnyC(G}mgSXeGsdraahnj4s`@bzkQ{zf2oPXXYJA!ov zKln}x+5WU`x#!j@>aw;A^=-C)pT$0#7tb8z%wD@)yidW|GI&-YXUl+bW(&?X0n6Dk zU^!a`EN9Dr=OXXJ^?Amdv>Xh z_wQiYCjgdx0$|xE0G53MVCaeW{$SZB07e{QpMWXneFCOF?-KyaJ^`@o69CIT0kG^7 z0LwlBu(pf$34mpvfRtmOfYir60kG^70LwlBu=OXXJ^`@)KOqibA6U*+ z1Iu}9U^#~kEa$U<<=i%~oaY9XbKbzn518M;SW{qr1Iu}FU^zz)Ea%IC<=ig|E#C!7iPqv^cVK4pg*BM;uif3#(ov_KN$N}5Eo$VS3$ghv0nvo1jcwl zJc2Qf5RYKkg?I!b4y7D%DD|;lMdV<=ipa-)6=@gyRYV``R}nq2Uq$ps-VnP?`G3VX zp?{CB{2V`K{4)QQ$CvaM?t^Z|G9FP!#wl3FFIdJkSjIb8@&H)!16c9~Sn>&2@(ft= z4_NXNSo{eVKZ7N|flZ$DgH4`fmON>d^SPRmS1mbw4yWW{luLdFOWp=cJ_k#l2TT43 z%e(-V`2sBS2w3J9u*^GPnUBCSPl09r!ad;4?hR3nchqwK3vT%SdbelRLM~riXr)`{ zip%`!%B8M;C(pbyX{Ot~&uZq!CysGPPhQWg--WsU)f<_2L^pAV?%cw>u5dB8ihmok zw1s=^f7ktf%iHofV*BwmwVc970=lhi-o;t^?pD^*`DKW6U2SGA(sqjTYvKmx$v-b} zqUx_>UgH13**k9)^Qdn(IpQCYkKZGkyMK-I>D3?U;eH`1?8# zQ|UiZi)XW)r{>ReN<95Dt$X=`Q|Z%*&XiFb=*j0ZoxvIJJ0r6<(f65$oEYD$&hv$~ z(oeT-ce)?C*D3MBHu_+}8mIQi3Qo(U?bM~M=jgu19vJ>z9^q{LyJN3Sf8TKnZl=eF z-R{il+Q}L8)mFOwi-(=!uhwwxIk%0rcYD(jo$-5W!gy97*JeI^)|G3Izm$jM+J~nW zC8-a4g%L{Z2`T`#0TehWzY$1D(YiBKZ9>xZI=&?>@aZ1AMMPgtx0s zC+2TL!@bi*-eunVW2m<~Z3Od>+e&#;mri7^c3%l^h~ArlYa2Bz=FQT3uE12Ph}TK) z%>aL{-!Ef-7kJ1A`MqCEd9L<(y}myM>KAR5+gqL#kTd($TwZlIAphg}*Jw$4pxtfJ z*;J%>K%WLxF4GIXfSxNuvM9D@K!5y()WonjZcAOdM6XUi=SREo`7YBB`MzfU>Dw!G z_14bJb)v7)*2IHLQKxUNTwebrb(esjo*&}PEIcv=eC5MDUhngTQo)5M<@2tMtHs=f z3V5MT3+5&V3wd)@fIrVw)cbK_pw5zl#l8Ek2CjYJWC`zLLO^DNNu|7jM||AYm!V-^ zOzwaV-RgyVdm;k5JrEb+4Zk{%^=vgY!rM79V2kVxfIhNk04#e6z_P~xEPD^YvL^wI zy#aV{4wgL(VAm1hDK?0LvZ*uwq(F?nRm2Iu4Tm#Af)nr>Fn%}&48S>%suq4(x*b6%@?nMQ5tV3b3%slpi|0>qamu?tX$ry1uNbnElY-2v5I=Qa?jeC@TUF=a@}GZ)?4G z8hpE+m!H>rEWwlYe2v%!%RX(eUVo={IT5H6v!zLDyX+!dr|=`?Q)j=Fm-*=h$5Y%3 zSGcVm&ooY%Jv5VfZhG;hUC$h1o?f(oe|^{8%;C@V@K3C?m3hw4#s1W`0lQiky@Y2D zyw?}){x|Jk6}#YDyH9QYv-?+mmlL|l?{$LZcRax|NBouNwaIVk-@V*)nHGgEaKT^P zoE_l4W3{w1eg$IEoC#AN0Z`>xW| z@t?SNtV(lwyl{mgj(_0hJh{txY+M!{4(Y*T#NLZ8<3;u!qkq9t4j?RxfZTKwF0>YKlnI+E0sS`67sWiQ^VHgsxC zn_3*9Ci$AGqG#&ULt{@+<|Fmh*~^LsJaC5IDN#q2c%0nJ9ZPz(H%@hWhm1*;Z-{I? z*S~Zt6`q{i+m%yHJzcpp-QFX=x2DGxr^?tu6knjQH|wF@&Y=F8Zl4Clyt=o3=VZRR z&0Tt;xL0Fh;J4jvdqqBMm+y~SSG~^_M!8+*-|_8_?T1h&+S#92#(Q(s=c)5AcW`FK zC3?56PD^>Rz}wE;kR-3y(8rdvDKp%uvpdOqx>;5KLr2Cs&$UhVzMc26|Lv_GI}d!A z>~#!T?f>kZNzM#P_D)s4=-;?%vh&n0$zGe`rQ9c$Pj(7vo?X3yd$rRfXR|-qYcZp) zTj#rvo%GSk-q^_xxyQ1`I)mCJd%HJxbt7wyb}mNhZ=FK=xcx^DbNc79 zj#DZ+$(uQ9ocqQzPdNh`CVJKMJm|e#-#P0fczOFRcE>(j#3{2f-aArtjoZIv`_$TR z#_Ij{d);~77=QIkQQpAhOYTGIo!v%v9HozaP3YVdy|2RXmbu@$4<9SxH7Zez+SNJb z7TZzOYj;Z+JyNY0_0BBljZKfC-0KtQqX+VOvx}9Z&#F}=@4g(0Yf*(xS8=F&^f?;$ zVha7XukC)9Z>(;n!^fNMqVPTYsB?vT>AC%P)4J##)L>If+W+i5)G>Ao^;+JFtZ~76 zHq7{?N-%PlA}ZKM0}hubObYD;?k zo9*rsw``@fF|DZl)?IG7*v-^4trZnd`qdpdb|bYbcptxW`oGOTf986_o_}rrtF7%Z zuVF5W>999N=C}*P6H;aF`zoPMD&{!MYt{BoNs;;P*xwsGM8|$k_-8&FlxJ&rh9>$8%X3SV*Q>OWUV1i!=cdHjYiL5)b*?|{{5r}y zlf_&&;}@De`84zT-ka#f_G!#dj@m*+-rB{yCT1I5cxXLyOp)#M%KhIt_C6xCCHsrO z^4t>qzx|%L^rPON=l+rBlX%8xKYPSH{@?x$o%q)JCXr)Ue291!hCijg&G;4%XRG3D z2fUXA<7@|L09%nm9InH*F`Z(J`r7AV>^<$s^! zYWhycL$L3_(sy9#JFxT}So#hueFv7l154k5rSHJfcVOu|u=E{R`VK68XO&}ZFZHqJ z7dgyEKC@|;+316OC3-R&{h5tj%*I}3;|FHrA7&HtEZ>X;W-~^Z&Ddc!V~X{cv4-&m z8+B|3&x!%#3>NqVtmB){iUI4m=d)tKdOYx1FK#M zWHx8TfFU0?g3&H)1VbO#2!@`p5iDoLfMFMGH069&jH%CO#egwxMGnTZ$j3OBb}|0p zbJUl!V!(1%OhC@R?>EK%KIezeoBEGC=SRWgoJj9-x4F>$hVS^~`@V!b%DPkbMtbi~%9|RiWqzV%_Pkio5&o&w7-wuu z$JELL;=F>lQ)+sF_U_0hBfL8vxa?-#zM{_glvwYR$F{k>njB0mn;q|ckeA$_es-Mb zqY2)uQlGi^4rt@__&U+cwR*IhwxYX}**VE;GU+|HXzhMZ+P)<3^zmohPM;2P!ef%X z3ndz+Bzd1-p6f5!{~f0zC3y?_5AlB)|C&>>O_CS(QL4Z2 z@h6<&yA!=z$X$9@&&K+FS)zBW_TW0lcSktk8D+e$e@#kFd3-}^#bxo{*6Kr2Z|3ti zi&m$`t#WzK3@AwVElr@SUGjU!>RooTM;E3;6^nS^%uaLHW@fsfZHjwCYwvQSo3x}C zzxtKGE4;HxOTCA14_)8?ll$7i7F6o`9$J>L+ime^3(6U@k9NIw%uRZ?IW43E)c3uM zZrY>w(i8ey$SFCw=$`fW(B|ik(px|0qsZ+|Y5BLuDQb8j+VpZ0TGb$v9iqiiK}!xkFGzjCRG@kLlt`# zCeah$;Pfp~krsJ*yoV1ja*kK3LTy5GdtuKkclJM9U4ILf%UfA+opaBaI#ev-D&@@F zx1f9+Eixc;v zUNaO)*K65T&KdpOVW)eTvOe~lXIeL>&WQ)9)Q_2S%-e5ax>ly#w}tvGVYwau6S|pX!BI(!l+{O!T7@7 zT|akssy!Mzy-h=558jB1308L(3JVG5ZR8J-V!NF0I%5RQ0!S zd)B5oYqwRRR@L%&N8099ho7rOUtGFI+wYH5$G@#d(RW;+wk0d7h8G&qwdh`|{azDQuWu`QrSf)~GnCIV((Aen zc-Eq@4l+zv-)=>ZmEKM-PrRF2?Q21!PVJ!;OPbK0hRtc@g9oYOnufITu4c4qa2mCU zs7J~38qnkU&e6wdcT)GRHL1_49NN^mJiRph7FzgIUN3G}93?glrA?m{@|L|HMh)j) za!)TP=5=3CMBldzbpGByFo5?A{3q-mu=@+=BuL+ZWxoVi_ECUke+5|fU4Ugj23YoK zfMx#%SoU>*Wxoel_JM$9e+XFijeuo830U@-fMx#)SoWoWWxono_OXC%8)YAb)R%J! zWZwnKWj_X3_Gy4+{{~q0b%15R2UzxjfMtIOSoV#8Wj_g6_L+bse!#LX1q}a-p6D0s zW3j)7wdZuq-T&LSz4rY6zpVlAUB5l=i+p_7Z-1X_f6puH0pwM?jxEQo^LuiyJ-^s( z+26YUp6`xrIsYm1ls(Vd_S)aT{-=MlY}+V|?__Nog;8$T`75uH?6se*|9{Fi%eMZ% zXYFdQfo&TnTi@*ep6~H(Id*=t^PVl!p{#Q}l$_(CpZhB7 zn{kEpHtf~k?0h%R z;CL`&IXLd@F^G7;m^J5<_^k6ud^n#3@vqMz`9H?8nIAd!%zD6QokQZY&LQzx=aBet z4vDQB%0_&^HR)nU3s>FXS{d^e#03cdYu0DoDhX` zLd=;P3TK$ua?F__$~rSdS!aeQ>&y^kof)F6GeeYhW{9%R3{lpZA?p8Q?>*zKD7JNP za*hiYAQBfMf(j@qu)3O@qlyUyK|l!-6bYh8kemd`8I>erAcr-(CK!mKl0lFtAW1+Z zOL*%URnOdwXZzlL?!Nonea_{BzxB5mJ;tapDs*+vt_tlLqC$IyDC`;He3rVn@2ym5 ze-*Q5cWi$Z7201#h4xobq5V}nJmArqqdzdKfVd9># z|A!c&-2A>mg}xP%YyV0Qo=cnG5~#!PWenUNChE8QG6(J%wK{3`d&m1G^9>`u^X9%K z!fxLZVeAuPzNZt$_toY*J7KqPiLl$ZMA+?HBJB1p5qA5Q#LCTge=&LUJ)p4Lw?x?O zTOtg*=DR{+_+!3X6n6WT2)lhtgi$Z^-6G4eF9hYW--WQ-7eW~OPEfzw??TGmeiy=S zzYAfv--WQ-?;=)izFUmRo9`Bd-F_FsZodm**kwH75993iyAT<---U2EU*sq1q~o3# z3e0Q4)Cs07Fns{iH!$i5pTVdj>H=mRS&rOM9=QWER$#^u%-Dh%b1?iwF2HW@4q@ib zl_w&1PCk+HMvt@slpFohHo(TNXTCY5Kc4yKR2XfNexgm%f3`_n%eD$;8wQ(tdFGo_ z(F6VFn^R%fMeZO2e~>#c+NAmBR2Xg2d~+%s&KLPkzx(gg?{Kyk^5ypZ5H|Z1U_TIH zvwwk{#ReI(uYsJ!1~&U0$XRS)vk!ut#RkT{C1zg*xfc7Dn0*zT9yud0R&MrH5Qe}d=FXR~q=)qZRunYY-iwz9BIE#(`;4C&U z_K9Hpu}_5A??TE^FZ6B5pbw&NgV8t9x54PM=-XiQW%O+@{^I|^_;<*GaUHG)Lm%{l zVF&g?Ceo#Ki_$O@iM2tOQqd#Ko3F9yR zA3osUA?N&z7<=L;^cj1?81qB*LV03HUfAjJT)m)Q*x40!{s_Yk;}1K`i>sH&kTI50 z#*M3Tts8GqM-NO}U{^;er*9}nY!FkhtD`XM7%EQ+$qO@9C}#}8&Ta(En1fv%rQG>1 z%-lf+v4kH^9&M6(&?bcuOW1>q`HMCwjC#W!$`MQ010$BO2WFcLl_!Seg`FM`Fc7u?0JSM8^3k%p5_6xdS7{$Q>B5NA8@S|Cap@`((j?%nO)@z?d&E-+(cXV7>uk ze!+YO#$WtD82=7AFs{S(VCaKhFzg_Xp>pg?M0v@V(N+h zH>RJsH>Uqshq^dopD`If;DeJ#ys*!h^jEOc?}43NVdsyq^HbRQFYM|i?CLA*;vnqe zBkbZP?BXfx;wCZYc~Pz$6R~jna+|s++Vr&7dtx}b;SJ@+7TG{ zS7?u5++Vr&E%|co9{Y5~%5i^1dE8%75ALsAyT?9YF}t|Ga_t`bhQ<8E{T2Pk{V?n0 z%4I(;Cogq(dW4;RVP{w3=KK+MehNGPg^@3eAEEjRyEq8D_z2^E*wo9iji=bfeXJX& z7=I~uc@h8b^e?&J{cqF1m@hnI{43@-2^o%)V2+buj+0=HlVFaMV2+buj+0=HlVFaM zV2+buj+0=HlVFaMV2+buj+0=HlVFaMp>o-ei{m89IZlE(PJ%g3f;motIZlE(PJ%g3 zf;motIZlE(PJ%g3f;motIZlE(PJ+YZB=5!1$1%^u<^_B2o`iDDGn_{-&v1UhU(P%D zcg{zl`?DZ)-xgrp;=E?cq9BW{TJ_J&A(%PDDBEzhxMVb(TDXR)=|cv*!mFl;<^#_ z;(8MG;yM%c;`$Ty;<^;|;(9f3etOXF{16n6Vb3Y*`fVn0dY-F81oVYi>8Fy9r1_864+ zhT(Uz|F_a$)x^xeDzw zsY3fqs?a`@Dzwj}3hgtgLigU|* z?(s@E;Y=Ylbyag=)%t#QDrYa@$u}NT=XMVf&hucw)@m-2{%u#1ndi<>a& z2YZM=>J58f!~^z1c@Z}4Q0}WxZrWkM`kHnaFb<|228@qshXLbe+F`(Wnsyj4&ZZp( zum_!{9R|#cX@^FS?O&!H#>!1QjLDmJ7}I0gVNAbihcUaR9mf1I?J(x2X@@cY&A1V( zmn)b0I(cEIN8;o33p=~Q&L3gtr?B&1*wste)mPZXLDcKcd z{TN4R7vl*1!8k%cF^FQCKbVie@DuYC82)4a0;67- z*IYT;C*{#@g%Ka>LENYx@uXeEnf@SO^b_%;|HxOUUNVovF60>p=wW=IpK*g-#uNT9 z&d3+zk9;vNZvSEY_D1#w|1|j(HP-DvA6N3KYEs_r>pm{eAF56!yWe~LMK@ISU+g~c zecnjs$0gbQ;mtmB{&~0m{I({k{2Oln`DP>1_+#8Y^X3~*pZm{G&Ym$=es7h`G5NfY zXN~FUaewxh{%vdGeA@jYE~ig_&ZUj_>1UDY@jm@Gdk)LF*r+4QxBqxnzBPt?we|Ca zp~u8p82UfxzDV|;huul@o-T)L;ScuM1jElWhw>+a;s30TRfSP6qemF^WjW$NdBlf$ z5I5>aJZTqkray>3{X|~qKhHFW4>;2tXPtx1x2|#qI@o*zD`%sNpYF_bu=!?I&Qb@P zZ)xR>b+GxyR?c1rn{RLBOm;Bpg|phh=3CuZx%q}SCU3s&jp;Gp{KoW~Z-M2kc3f+| z5tg&#!8p?#XSIXPH^p++JlK3|9LpEVx#v9Ox#v9e;B0irLqGSNhh3bdj&k_Jz2e~~ z&R$13{KuK>VAKm|wS!S#mLm?7M|`LUaif0ot#QmQ;!J-KfBK2Mz<+aph5eJIe@!xb z&JX_XvTAqpkw_=A=X}e?S5*5P^&^Wu+3D4O^r||(xn-o?^u6Adr?07O(KjP&Hy`r$ zfAWW#uzo<~!D1)8O9gMJ9$DXuTpReCSL(x?YDj@`kwrVNdEGN7^E;b8=btot&flYx z`7Oat-ER@m^YYOMUX%xD{8-9{67rys6GE8oe_0S4X`S z-LI?Raha0#n?3Mvow%l|zVduh<+8iI4DVl6mA6bvs`bq_Z~A~MDz53bN!`sJ_`e># ztiHSVkE9|^H+zqNaalE5m??t$bNWWc+yPEmGnK!7=oi9so2BtPmyhlF?>Eh8_if&> zG=tyscUxX#dnSMG)deDdd`A}l#l%m9pZPSKpX%5L!maAW`8_L+6Yeo9hu?7WAmJkm za{3=Hculxqn|S}=cMXLztcmyI-h42|?Pq6*$*38dli(+={q)E8grW1DnMH(QtI6@k zDG|7$`2YY`@O58-(^`@ z{k-h=uF9lLn>41K?DwwDzSu3P?ESLeyQlMPu{w5td$~_I)L8bn zm-~cMDP@0qxlj1Eo$PNf_X!hy+23B_J^}YJ@E^I(WB0dLxKF?y@+ilB0_({A?adz4 z3hefo7a3fOa=F&%1Vblmfnf_ifN{?N-@v$MfX`suGoUVD+%ur>fN?Lxa?H7u$6QQ3 zn4_s5b2sf`PDdS~2Xj6B#61B0$GrjS2pQz@&-FEXeXGU~E|oZ#J;2px0~QIJy~O=( zML!qjy;iut|Eu#7w)O8kmvu3F@LnsP+@E3glLya!;HLV->@yEG`_HQn&HnRW_Drpw z_~4f6VfK~>SNQx7mEG()Kf2;&@8E&!Duvlw9_+Qas_JK*5oxscnAfhuHI?$jh=_0Y znQu7pidu8CtKP`Pr9a@hyi=!ZO6%CWw~@8VF7_kZ|Z92oB*@w+%M-WTF`abUc+#P8z3 zc%O;i#ewmj6TgcCc{4Z0^awls!p?5Q>ap+J!Ol-9 zcm4~zda)euw}lZ0#L?-I_y1tT4RHkHFa95lI3tc=T!-ty(1$pJkuTT_l}mk{d?L!7 z9$}|n*xB{09{c-eu=7*OVTXBv9h?IT8PwObPhrFX=f*lcXwSlkn`wu_h^J|X!pN6t zhr-C0X@|nFW7?sxYZtL{(+*?urX31Hk7kE0t0eTo8=x5wu zm+^!@j5G4Z_#o956=_sb#?SJ3&#CWICkk&pdR%#LRuwLi@{szp zO&wu#CWvY~r-5?kamclKZmHl>z28*zxN@rhjY>iM&{JxV8T*pns1{7~kE+ROYN{>| z)(o=r*{{Z%b3oc(sudh>yGxBR=YzQOK75?_u{iOUNbQZ8{j@!kJl!x&aQ>4F{!7sv z-mC3%1zGM(>+gE`f_FL3JwearDgDj7FXX?G zb&l}sKNt32FE>DV#)1TY&dln<9llEN7d?3^2|63+N$|&l7>|n>1Eni*q`}p z>7;RA4D{-~RMb&7Ko>RzwX>-x?S$}=f`*l@8zi;b8i47mR$9t@60srj= z;}V}dbT)C1pWjb+b7P`Az<7~v@4UJy;zRG?MW+o5Px&thkwF+ zj}K-WaQ85#|2&TUB~5>o`;8!f%G$xg`n%NDEDeK&Pt^<#JhNYQ%~3BnF~52+W$$4% zGIMR7S0ehuw%q==Ds=XT3Z4C-LT7)d(AggGUs$CoYR4FbAE^7`5oq5 z55;pm%y}P*=Y5!SKorjbG3SFQo)2Qq4N*Kd#GEIhaGr=e`$P8q2>)J-amH`S%=>Qn z{n$VHdocKkTtFVoJwU+eR_sv0rj#!^=DY^kvmY|%oCTZ-Am!$q1)LQiY|dH0Sp=ffoChI$_CwyBvmkr+gK=-j zvp>uk1hMjV^P9%x&7S`;J?1Qcn0|9cK+LW=J0RwdIfEePr#WXK=D#_EAXYC|E@yu@ z`9%2R^awls!p^R+^T&g{^HbRQFYM|i?CLA*;vnqeBkbZP`dvJQU7Uqo{Doa!#DC_? zW zz?un+GcDNfaMlI;9r_c_%76^|8T%dnvfts~+3#>2&(MKBo~;8r>~}b;gXK8GgYrgC zBJ~*kiPUfYCep6?caQ#<>pc2t^m+6jXN`pFg>q@PPF~ux(34`FVj|btHXzL0q1@S(a_5hSa^?=q+<}=pS1!48@{&8Si;w7Waid+y9b}k0VV66w z%ZvEWe9@-KE#?Wt672%>2VyBq-%-vwfmv6uizV6!<}Ha0*u@gP~sYMA+pH%-n&QJ1}zxX70eu9hkXu<&rxmFS!FVcVOlY%-n&QJ7JeQ zFmnfH?pTi8Q69MycDVyHcVOlY%-n&QJ1}zx4(H3X7d+ci_Su_o5Mq=oCxdcfJi~_$ zl;asbo`r+)3?I+P!FY!6-l<^EjR4QoQI2Q$c-9WaGkiRQ2jdw&p3Q^t3?I+z!T68Q z^6?Cx<#>iqc|60X9z4URemujcT|C35KX`^uKk*Eo{^Oks>*dPvjt6^aKpyXMu!jls z2s{0jtz8c?&L3gtr?B&1*wste)mPZXLDr!P*=o{@`xYx82xzHC^F_R-Zdsc z-uye>H42;S@UBtV=)=24X>Z1ktRo=r%B8+eUgF^N2s{14&aTAM`6KN76n6d#yLz#l z@9Lx-!Jf@$?A@NUJJ>@x>IZwSUWl_W;sJZkfA=lz;{o^5LAhy%cn2u;HSJI_4yGL{ z#>ccndAA99yn}{4uxW?#P7-X|p}gA!n|7#}7xVu{k9}8W+F`8Rw8NOZX@@aArX9xg zn|2tpYuaJVAJYzFewua|^PhX^zz0_@`Ev3S2d78a=@)i(C7#Y7Vdtl?^IzE2OW4&{ z*u_EE#Yfo1&9d7|2Y$LZiw`dT!Y(iH-+a^iqsrAJJ;o||$3g!3(;WWliZ>!C&+<@i zf7K(Wh0E8^>%X;Nr|{~N`TU@P7G89zfM0vv2f`Iw6!I4z?<<_YNMZltJynH&EK}I; z*EG5CwK0YKd7t-5g8o#s3i_F*Tv!fn(m20gZ)S7&sc!Aa>(A-3Tllj=7t~$(N?;6E z4NIO;gYrHqJi5&<>c>BP;S{$Hs3m=?3C}OOTh;Ale{X>~0&@qhH5`zQOh6fPZNO`d z&VV|Nt$?ihl2 zHYSKeqcJvCh$o)I!)L^;`s-tb5zqct`UxZclmXA_cvZ^Hdki_Z9oJ4QyeBxZ?QIYI zO70(n#!H?P-qB)L@OEwco1>Sq><9)o&m-ly7Vl6XZ*m)8e@O7nC2NDyqtXhu4mJi| zTc;K-*8lt9)WPJ!yUuJ0ZkDLE4iMOxu_gN|!U#tr=m_{OVO6`LD2`}o1$;VXGNb)T@>pATlQOc zY0ru=G%-<(iHVhBtV|3QV`yTl7+Vv6d2a%r@w+wV1@A7|&Q0!o=Fa3)F{hAWe=%*q zXB#kW!)MztZN_JtF>T3bTQY6TXB#tZ&u7~+ZPI6(G=0HmTQzOiXB#$c+h^N0ZQf^_ zH+@0AxjaK|SMwL;WhL#EU8YGG1ITs#9fE ztxHNjYsR?X=&j0X%gGe}*k7{;eM(nR*_x*C=l*QD;;vH)d~`!)rTd&vQ?FzXN>8e! z+NodE?#JSSIddzh6L%j~Z%&O1TBK6yn^HfkR`=!zPJLZY{WkEBdUbP-VA!ok)UzcI zs#fE21|zqZRvk+pP)~M>4_dW+K%E_HepB>pu3-H4#nkBL`&HqZxr0LSXFTu~RX9i= zJ>fO)v0uIRdEsE`;GI1|vF1L)%%VRO%dvxfh}xn1te zFF$lnu^&38*vC1=?u;;#yUh`Io}hoMPwK#(JM81!VRs&}kMoFMZ&t{A?%{&|(tN2B zKfAl3SMilX{?7iNt;jH_qgU}!^V^}(`IGur>+5A(S=j&do54vbstxo`T`TN&d+3X# zy~T%mHA^P=8&>T~TB3)06&_FUGv`Yl`SH*QuV%9ZzwvjuBh6nK;hlai!7n?mWaR4? zhIwf!B=~VTt3`gxG}wDBF2OI9>AA?tIsLphcNg}L=6*HO=+`&BuX_~sXEg5{nV;+x zFaAa$zhl1b{ zDs+ag3Z3DrLTC7@&>6lebcU~5_O~;9Rp<;~6*|LLh0gF*p)-6{=nP+lGko1SfN~ZO z8E5pkGXYK8j-8vVLgyx{J%2klS%uC`R-to~Rp{Jg6*@Orh0aY@p>vZ}=-gx#IyYH` z&P`T0H`$%3=ZDUN_Cx1E`=RroeVhmVSM9vm#LJP)OEdfR7iJ9lR*4HzOiS;-Y|iJM zJho`?@WxbrhJE>h)~`Pr{QTujRjpmIAm!4^L42~`RrJ)uJpWhW{NMC1)epXCcR)?v zUM+aKS;OGN{kzn%7PW%uM;iu(Z*Ehc)|Gdy0oEFSeg;*$SHqxt$z5umIgfbHj{3on z?EBRN=A7bR{JO!RsYle4=KSLC_ty*#Ejp>jnRAWnT&NoKsd!G!H|HI@bC4CzLH_v3 z2ZINjr|@gKz!TjD9%CW zv4Z)1E12KCg84lxnBU2Q`TZ=I-_?Toy)BsE;ez>nE|}l#g84l!nBVz=!{7fhcgQL0 z3uYX^j1QP`12djr#u?1`gP9jF^95!e!OSn1c?YvSfZ0yKY(HSOD=^#JKQc#ieqUkE z;tZdihw}f`8GqsXgg>9n7rtlU*^%yCU^&Z=_XB^v-w5jopIaB6`@+}$BlBk1?mu$o zAm=HZ@yB!7z+oTU*~I_$^KUqY|C7%93+E-AFEZ{i!sqCP=k&15zw>xjDiJD&p> zj;%X`_#eJs3g>8sJ%jikKCd%;-xa<#JdTCOK%Qy-ZNstN+kJnFoVh=X&NytoH|(BF z!Po;Cbhp;)yvyI^3s&EsR`1(*%-guLM9{EwN`3T&RO-m9j|Fos-w1X+k&E|50q%?3 zcOn|!iMVf10(`gf-D~#-8D^x=dv0b{uRM5H@IbdTdPBEsUdajRgZybT=ue*7>kS@o zCeo{NW?kXlRo7|aORmx z>iks|41Dsppl{Z4?p{;AJ0Odnc-BDw9pm5WzuZrTztaiJ{4@8fE>;S$`e(lV39r$@ z-vRxfx*rbL{h#@^DC}o=9UcB|DC~cD-5vgJC4BAw3v2LjeC~Y5l=VM+#}sZSyw}2W zoACEdTWZt^)(tr(>(j8zKeOfye^>R-d_NT$PcVjJEW()ZpI%dk>-&#8NyqNm; zV9K$FgRX5K4SKD+8EkD;EO>2X(O}89sdT1=xSyRo(*{<}PCd>_}O+}TLx-I;WgqB(+RN@otfB&e&&0Ek4l#c^y4>!eDzBP=Sq4(*F3)m6FZi_O}}fC8qW;f*ro9;WZ0G)$26WL zx<0P)t!4PyD-V2K?n3#y_0;EfMtW91oLJxgx6e^@olpRv;Xb@)>gWXTRpWnj!IY#v zJEnL~j!V!jlCMwtsPA;|;~+tweehD!mUT0{mw!mm&yUO=Y5vs=FTLUUW$ueyZ#muD zmXx6De_SC_Zq*d;_?QGeVa8LD6IUj9gPSDiz1!MGay>T2yOb+IFG}7kGGNRw@50=| z`oXcoBGsq$^|I$FtmloM80pdGWp7}WLb`O}k0bi^O5S;|pib3)d1OMnj9!7Y`SsCK z8zKW5G)*k~*4;Yk^!~^KJvOP#<=lEu!sST#ek|Mu!fhjbA9&%$Q{D@Az2^Nq`|b#M z--g$`lMUj9i)`!c?Wmen_`7`Fylb1%3-{^$miN{DsfG30-rmFs$%Q}p@m+6Tx0^}O zQ|i_Lufr?Xg{zbt;ys-EhVZ&d!@b6pl8OAK?B;t^Kc#SQ|F{&n-) z7o%tEH)FjDUYu~fF5|rEUGv1a_|5_`nIYMV3gg<+drAmH=k8xi3By(-%Ok?@p+m;9 z!tkx+>T<&Hc~qYA!l+B5BZfa+FD!f~ zw*UIr7MR<{d+4<$(uPwMe#v{{Y*XQc)z5p)9&RC=^POkBieuUcL;m?vMkZg52smBq zW?s#m8HE2x-O}q6m(rG>Ywh*E`$`gIF5T?l&Af3+cuvZ$-r(Ygg?p{*>CHT~M>zAK zcfFcDcM6aAcA$6R#&%ntZCI@Qg)(OEc_&{peoRcyj0xjo`g6^g6tkN@=hT=#$NWzFXg!(eZ}k2A-%|-o739cFzrSXbk0lB#vAy1YLQ>|eLL^M^(?}fZoTT| zygQRzJ0Rn$-u*3;%e94dN3ZeRGfB|DW^f1ZQjzo`|60M#^Qrn=go;{WFb{I3O48O1|&SO?^#d zZVemn?VS3DTwCX{DPDz~DJ4hg%pSO>$K8}`t9fI+#t)^C{O)Nn$h+n|GnfCX=9LC@b+}?r(U@v@119uzC8PGkr`5as}~o$gay?3V2~#arK_jL5^*^Encv z{Mk&Cysv5|N_qFECwjxW7n5t(j+^9Fe(oWWK_0sot0d*Gx0~Q~9$Hr9S8N^cZ7Eh# zWRUm%xvL7Joji7`n#d!MpZ=^wKGoH+-k#UWNICM}eN;t}e_`54?~zkAr5x?#>BPz+ zk34QkR!$gs|GieC$aLEFo;T~FwYA~QQ19unbwmd3q}&oubYk55w0>PF_h*mrbh-+1 zZPrmky}d8h5E=A4T#I}`eny6xB40bjP;bLsl|%;p^yaAA!syrMI@A(*^gHN5zHn`H zo{bOs>C&#%MSe!L?%wd#)kPlt`t$bHL>~PP`f)A#Y2(K$ip=L#dwAooSC(tNiybBA zkU_t$)v%CJ#Xi5 ztBXooow*)s>7BcJkCbEV-P+(j;SH~~^-fJL5-Hv!tK!@N=3EcvTo2}4FXe8o2Xn3m zbFK$-t_O3j2P0pY>!sYy^ zJf9VS`K$oUX9ZwBD**FZ0hrGUzdI$1cn}E62fIQbtkmq^_GF*dzxxRo5 z*E_hDYbca+y~As<2B9siH6X+F4zA^z3(U0@^nU8z^$ujX?m#)@vEG3^*HDn*dIZdM2jscl zfjq9o+6v`d??9ew6O?nk19`5qz+6v3hU*<%%e4t)xXuD|4FwslM{q6IJ1FP61La)r z;99PsAj9JCNr(3(WNtWVqfzIoDQTuA9Ph2j>(# z!w27)m&-{U{&(l)Ok;|x?>23ceM!J|7Ho)oQt7=U@WsxnBW-hMihw_DvM_?R5_sd` zsgZHB%=2Ds0=lQb^S1zX79NH*(M0pnV zb>ykVLz2Ml>Lf+hPe~gAul!5$xnWu+t;# z^b0$?!pxc$YYaD>mtvc8lD6$Gdmioxh_KloPY5bkv50w2sdpvC9<;3yTbU3|F>?$a|DGc0B4a`aSA5e?8hY|L)NrbDc*&jXsb58#~emVat^# zf}Okvc6x-Jeqm=<*!d&u{1i5J;J+|(2Yaqws4wLa2VwXNdysK)6Gr`D&-sHm3nLz| zhjOD2c}YAspmwYef?eNC0=qsN0b>k9p9i}>F6{cgup1MEF^1uK$h$E_81+J*cjYo> zg56joX*c=CT zW3rTE&cXkq+>PPFm~(JF$~nh@Imfwjnd882?w}r-<3z^IabPzGi45mBlw%HoJuv1L z*aLHp3za8^1T88^p)T|7m` z_#<;1$~nh@ImdxH$A$Y~-d%NL_bMoNxxO=gx;|)QCF8k_W9)+{XCDN!54v*cgJAYS zu*t#y(eX2!JFuG*lfZ7SjDT_PfVmdz=2l@h=L);ISQz&XxE}JnR{^7rxL0xIa<2k* z_W;x*_bMoN_Y6|bdli)PUImPM0oViM9s%~iyjKa8Cx+xbFz;2syjKA`yCQ>o2gsq^ z`6*P~tY?`B^X z>yNq4qn}2fNB@l-Sqs3HD^CPFd10qV*y;BmJ59&PsCr?=tEv)9mjlOedo$$-HrGm4k&kegq{8f%AH+d=Z`S1 z!}XA1zQD|vE0=tMT^y)K@`Z92Hz{YnP|keGwJu*^#0mDm%vY#9F(fa{e4(8A0z11N znE8@xZM%|k<_qP_7ueNTWLzAm2klwd#Z8#`!nH2W^i%SM^1qiaz%DEOmIoASU_BAm37x>ONSy1Bk?=(&p$kk5mE5AR$9(UkX z$qxkWy0jF2y3wJa>9b>n$K^X3Oxm(UIAf)gL7fM-TKRG3g1h^j5`Ojc<)BBpWC8TN zlRBBcGC8eqLgQ4rNQF$c{D*Y<#CMs6cU8|EEAKfedrbbDkK;A<o<;<8V8w$!;`P5WPkWzWX^$pgqdx&2m9e_cA^Ds@xoBX4FFMt%Ed&MLgTQRZ0r<|WxR z<(F@c*HxXKZiDX9)L%Tvr)l@l(*-sCX;rDPrk@+zCusVAev8c`{6Tq%@pF^FkbivQ z3oF6UW5%6CF!X}%f1!lg$%omvX0yAG=<_pYxftfEb^95$U zz|5DFyL^F}FEH~3X1>787nu11GhZxceVH$mGhbll3(S0hnJ+N&CFL$(VCDwtI~5v+>FFM(;!64^yYmJ92+2ys|_p{YaiA!e`$| zqvzdRA&h$Eo^AJf&2WFlSb3!`nPc+LP0AY6^U;v(G5r}H%b{s^*!wv({h9E7yr!S8 zl+2~+|06AP#rCR2`L6l)d|$|?9WYaJ2R(Ox;|oK7xt9GTkFfj7hec(NT==t~RiZ|I8QqW8>VH zC3k=3LA@>qV@_0xp#1EDD?wy-E8)tsuLU3E>L*;g-i=_sKU#Qktz^2;lQV?JJ(xmQ zIWtcIW_%xw?@3CpUV!!Yx-Y5hs`7Eg7O`$&&YfM`2lC=2t&_>)is5oze@ILD787nu11Ghbll3(S0hnJ+N&1!lg$%omvX0yAIWzn3rE z1G5kQnK^#SeX<)r!5lxq96!MvKfxS7!5lxq96!ORFUC(W$4@ZFPcX+%Fvm}kcjG6R z<0qKoCz#_WnBynQG5$~<;}V$TCz#_WnBymy<0qKor^vhU6O4Lc`~-9S1atfZbNmEz z`~-9S1atfZbNmEz{6v3ezXP-1f!XiC>~~=HJ23klnEejSeg|g11GC?O+3&#YcVPBA zF#8>t{SM522WGzmv)_T)?^ymnVVp!=m@o9lFf(`TvzR-;%pI7y12cDE<_^r^D zIz7Qd9R4%wbgWtUd<=YNJ#Npw;qy$y$UIh%N1>&@iX7_zY1$R=ZYp4 z{Zu&nyj;<{O3W8d+?Xpmuh1vLEq3IJUd=i$R$k}U+?f2Hi*tmbXT`PI!q7h^=j~kZ z!c!G!7ficg+6B`tn08qXyOf7rFzte??1_(VdSs~hka}Qzv}n^I!Y>t$kFJ_ISUC9? zIirI!TR#6#&S>xHgQR@mXE~yi8e6VfG)MH4N|rZHjf*yU%5o%kT(rd4+c|6(OuJy( z1=B8=cEPj@rd=@Yf~UTnJ=*VymEvdSTiK%)pC1nk(|+EQ!xxw7@(Wk50w%xN<`sk0h zZs)KqFl~Wp3rt&J+5*!Sn6|*_YyGY#_5NI9cxdim!gC)yuZKLoKzQO$zv=u> zFBIOr>^I$_7u&A#p8HKd)5o^AiS^Ix<$Y{BY_rYi>}cC(@?O8|VO4Fr z-Cyg1j=N@gX32}X-U!>aRq;#u>8q~&KYUp~X?DWGn3k%_70v!a4*L(L|6uwLrvG62 z52pWM`Y-a%f01$igXuq*{)6d1nEr#)I{(4poQ7jg4$FYU{iRgj_~^@V<0KCEr-_et zs5?P8Z6s&(z^qBaUwxP}x+=@mSow@Mr^n>8Z~Z_Rdh%qPDGdF8HJ+oN!Ux&~(=M2H z!L-YA*rhz|f@v2V9?wVq9v}Uow;kJ~nR7)aZLs`TeVNxn53dFDS}?BVJh;49eDvM| zwmol65g*<4l5N9(H6HR>=;5_sUMsdj{oT8qIl8ff?Y}R-kTu$4sO2jH$*^n0mnB`GV~~+%Lj1;EMx?`e)YKe)@a+q5h#0wx1p>G}J$t()P^^vxoR^ zWwL#<%#FeR$UiK24`BKLrVrqxM+f^oQrY{NG|7kf4=%EN@8?7OtMAx*p2g*c z`k%M3_d>;|4fT6HZ|{-**ge!Q(9GUD%{)2OKik%hho5g5>fhhRwjXlX7MQlcv<0Ru zFl~Wp3rt(!kxx|hTO`=|aY?S~{`UTMeta=~O@DY6%USc)_9I`}xw2!Wx_-x*mS?xF z@Ap|~`P+9J`Xf$TuG8-c|K^kS+8Qr3@-rX4ox^s)v6>z8x`V;*I=lq426@KdTjE>|90;`v#_OVEP88 zZ(#Zcrf*>S2BvRd`Ua+NVEP7LyY-sNS=o-yuTHqGT2!AQK3}?aQ_XB<$M8;$kW3_VhG<$()v-UX{)-aD0l$SNSD_U;o7I9JULlT`=u} zX%|epVA=)KE|_+~;d(LV7_Z1-8F0A&{#9G04CKT8rB>VWe!6MnrM}mPmGr-@W#_~X zt|$19#@o7gPLbPx=<@AxfIo~+SSOe|!PE(+PB3+X!|j}7AoP>NGT`v|{PD=4evVIU zTb=OnP`~7Rwyko^fgW=BS}?B#^IEX68@pdJ24`34?&9T~y ztD0lD8E-Ymb~6rZj`?PM)|?B>xUD%ynDJb5?lA35b50?LZGmYEOj}^u0@D_lw!pLn zHf>&Wd^Y2!=D2OfRn76-jJKNOycvfz$A2?EYt9R1+}4~g%y_OjkC^_VIlqv@cEPj@ zrd=@Yf@v2_yI|S{(=OQb_kd%s8TSH?$!0tZI98i+GT<0)#?OFbyBSvlj`?Q14LBE= zaX8={VaDfxbB7tX1I{UCJP$b6n7$cs4kCwr1JgG!eFM`sFnt5lH!ytz(>E}E1JgG! zeG~a#GH8y^X8hC~x6Qb!Ii8#GR&$&;P3AEx+aU zReM|7d$2SG-%;Bp+xxE4+uu~(SK9lonG3tB7uMMIJ~?a`OuJy(1=B7#&e;XiE|_+~ zvU*08yeYi%+ACg( zasrVEO>24`BKLrVn8H z0HzOM`T(X6;13d(sMmkDao*5pkt%(_#{cC;3)Hko{5Fp{ z^UPH@KD2z}g_$ZTgjbwyKZ!T2427yZZE-2_iE;ai?1Q)kNV#YL|-t!QSJ2 zF>IH5?(k$O|NWj_D*r`$kJlyRPIcjyy&oor?Sg3+OuJy(1=B8=cEPj@rd{xtxi@E}E1JgG!eFM`s@JB0NR_s%UAMdC-q_TZ&`e)r#(_xm+jP0c!Ze#mq zrsMCb3uA4c?U!qy>Yd*824`BKLrVn8H0HzOM`T(X6;P80Tph}X;cho)uslWUa z)%Sb*?qJ};X{vP@`&@l)w=t^o1O0DnC-9%`C#(}ponYz&Qzw`@!5nj-GdzZq!!qFO zeN#m{#eI!$AS(>JnKJss%a)(-l`?wjg>R(%{ZuKV_nuoL{OH&e(KLD13uh>uB6@Po zMtkj^1m_C5%1DHO5 zhdCd>^Z`sCz<35rAMl=tzTy25ea3qw)&=jISVz2vV%_n6iZQ`^E5-`%vlv4>J7sLi zVIRQs0Zbpj^Z`sC!1Mu3AHehhOdr5K^4`){K7CEvTdQAg=}D@y@a(q9qF?o~_ZV|d zC5xth&5eOwlSezGv}0hmR4JmLJ!bi?F)5;T(pg@RKV@`U4=Z2hgOt%t?^!)Na;1uX z*1+n&r&p@z$giy30^3qWuU_mZc5CNI9c^@}z3>K=I@)V%JKi?q+~zh8`wyo7 zVEPZH|KKyue=z+A(|<7i2h)Er{Rh*3F#QM9e=z+Azq&17^nq=8#s6VN@<%V`xl8!7 z=J})3O6L|XGbDdBu2{Tq`l>ao}`t#B>!s}nUJ6eB#YT-)z@;bL z2GeISeFoEKFntEoXE1#R(`PV!2GeISeFoEKFntEseK&iw-c!}Y|BI>PqV*SAo;55k z+HIxf3t4kSN4K{;cw~;~_)S$szDU}f(NX)V2q(RfGdgB=W#JK9b4G_fQ0X=f+XB-T zn6|*Q1*R=9ZGmYEe0ca(z5cC~Vr$RnD?0rPN(Iwr+ zvpH>X@S={Yj3Pg9(nbAh)6BPVSU;Hh!PF0?elYcesUKXzKdWn(eOC1ExaX`c(!8;7 ztHiUq%a9j@E4_18=bqJ6c-*P8`l%0_2{(K9oc7*$Nw}B)o6efKrSP`g=k?^4t%O@= z{9X6z@Urm8>=$&`BCiM+EOJo~>~lMZ{Q=V-F#Q43A29s^(;qPX0n;Ba{Q=V-a5xTs z6?4i!KHT5`s$EeA^5J=>#f_ZN67>$tJUFvse6;;9CxzclpDTLbp7X+wnBOG4W)3~Z zynKCr?&y!nlS$m3oR=qh@{JV2HzIdMGgY$f>aY4Z?ZOAz1=B8=cEPj@rd=@Yf@v2V z?x%PCo;9kK?Sp%pW{H-(-*ScTGDUL~viQbA@R|tE=#@Hp=Hc|H~2~4!1N7F-@x<@ zOy9ut4NTv_^bJhk!1PUILi6u}9yj#X&K<<(2Gjr0>%Ovc->flLb%oFD+;`tAm-WdC ztwrXq`UvNA=%-FFb%LoAOr7BHxU}WlKXm$H$;H;bA8zPr4_%k`mUZYYJ^H%~!W+9K zi*9}Hv~cDt$)d&Leir_#dpYWdE$RnTKbZQ#)DNb9aQMEI_fF^wMsvF^ zdvWD5y(^bpmn|#0Ouw4euFG~rm+Cr2dP{xR4O*%bKeNwsO1`^PXZpUclt23UQa$3- zyTZdWEYsC*^b_tecA3ueM}Og;YcAKl_YDw!tKbT~cG^JUJvmqE@{bJ?)`gPvlOI_w z<3;p={kL=2XE1#R(`PV!2GeISeFoEKFntEoXE1#R(`PV!2GeJ7{Vz7?c|Gj7-8tI^ zefI=AwvVc_UO#-^j`{stuG4KMG?)6`+hVOw{l1+S@-$eZe>nD{ln*ZTjovcN^2ID) z>#{2>pT6*=e(X^zzwyLsoiDr9)8pbQ-LksXU$)>XeSE#`<1coI>QbZZoKohf)+gRevoYIlI_w{ zYgo>AX_qehjnz3|>uz1-Zp$f0{istuZhd&U_#WM+ja`FxpS(xUZ)czR6g;>`f7#SN z^C5@*2h)Er{TFurgXuq*{)6d1nEr$5KbZc5=|7nMgXuq*{)5X5I;3;1vVFPNj6-_p z0^7$o4?CnQRkeNpi+YFjfrsswu=?kNdZTa0iZzW6>V((r81n812lTbw-6a?Ezu&J@ z^|8-_R{y+D*Xd-}LC25&q<{a+u7keayH{taZ26^4dvy2vEw79Is8@Bkox^^D=_ijzUmnEJug52k)F^@GEH z&c3itH|sJ4gY+kmam;=hrVZ*ZMU;p?b4;(Gl9Qq&$J64XctVoVA=)KE|_+~v7;n}_B(7sq}JQRL^vvEN9H*t#V4+li)om&SfmG5q4P z*l#UH4F);v1DHO5=>wQPfawF6K7i>1m_C5%12}%ya=oDWY{|>=b<6Zy&s#p4 zv{dKqV|m{4C3@^;%in&pSbtx8j>ykBzDQ3#Zu#bYi}aR{=Sulb6T|ic?A-K3+(JF; zO*>~z{Az*D*VE2rtEVl{8HU(7?#o#Vbjyi$?rXPefzCS9&X44R9gDkNi^SD8Ewb-f7lX`mJ;Jom%#JU+e8XEJwzD zqbKZME;55!uF+kyTYfXsTJ4osCgmRvTdQXmUn<;S-&*}Z?j^zn%{c%4wMD|Y&aKru zezLy>n!RAH9=paqZ=Y3VtuCeQZxL(FTce--);^ObhkXXqXE1#R(`PV!2GeISeFoEK zFntEoXE1#R(`PV!2Jh;+TBo~Y+mE+$l`dV>@{2!3^>^KD8|z`ljdf>jJA8X@pihpm zd}vKXZ+h8sk57~IidSyuuzoQ0gQ*`({b1?`Q$IMIclKF~MdYvyINZM`tY4w?b+*1O zOIoQ5cDdb8=%N4NYr(u0%xl5n@hWAvh5G%BwrvzlT&OoRvh9KW2>Qw4Yr(u0%xl4H zKe#rWBXU><+&lX(`u+^|{-oH|V>$1i$ieS3d${>5MP`>#xw_MB$VFS{4~oKR-DywPgx%M{+jr&r%UscKPqg=A&5B*o75j{ryu5h&vQE))oN%B1mvzUs_CD>?^Oy9d z9%H2ZQsO23!)$xc*0;q)-RgJyPOWjL3wmH{%eCA5t_!5G{Ml3I^|39ZobTf6kQZaT%r^GLPhdf!AF z=cjM|qI=J_@h6A<0n;Ba{Q=V-F#Q43A29s^(;qPXk#gq`INYw-M=&Ok!!qFTI6(g) zPY%m~!*PCL_c^^`yp7>E<9^fkt+dQG13l#MwP0Qg=CxqFcg|GRzTd>}g{F75?>+H5 zqEf%w_o4WGQRWTyJt=;7lrOJ+e~RBDz3`iTuZrI(b#G$dx8nCpUEF(Eyj$lxL~__J zn0CRm3#MH#?Sg3+OuJy(1;>BWOC29_MxOQ6{JMvFjZ;!PF0?elYcesUJ-J;Hg~?sSM8* zk-mST?LKuQ*FC~B9{f@D=w&&_{_SefFv|rdZC3RvSbn1CCe>`Bz4qQ&>s6cS339Ev ze~l{fY+B6V| zZ0WT9>@O5vee$JK-^H&K-hA(+(%Dm2ujRHjSZ%P{V70+&gVhGB4OSbhHdt-2+Tcyz zm_H4@a!B!IvO)8w11_4m@UI@5FMYAwtcBOwbXc1A2eTL6;^H5rY1XUjv#a;dlP=zH z&RYMvxzfvn<|@47$T`xaTUOqGr`ggan|+_#?ZUPT+b(Rou}TQj_jk|FzV7?<#(9btxBYXPG<1va_doIVrTtmh&%%Bdj_d0BJ&N(I>$n=@ zUf1z9#>1}TaEy~($LAP7yN=s2u67;IW4!G;&c`)&9slKayRhxTwhP-XY`d`S!nOM*!ZyVVdKNbhm8-% zJ=t~qjPb4OxEkYL*YP&S!>;3SjFVl*=NLb`j@vP=b{)@SyzM&9$NkfF{FmG9!nO~BGQm$Ub_+|~xG4OSbhHdt-2+F-T8YJ=4Vs|{8g9N*LI_!;9{ zc3l0{b#rCM+ZYeC<8X|V+3`8X&+NDz<7#$1kMTA;&c}F|9slKayRhxTwhP-XY`d`S zmihzj!nO;yeYf3#vAXDK*MZyPj~-E9Zr6d^-|HAByNltZhsc`v#_6q9YgqR`@1i<>%hxhcyZqHx%!;G$<>$S8z!&M z%lGz=&MQq;d5?Q9%`-h!>#TL(WqG~7R=)J+%k!Gw)#v@?MqZIO+r092YmCVcpH}At zR(fSjo_PJJ@|*JF23O{FbA5*W)wx&Zu>;Sr2j6mKesWBGhJ9+xmHB~l>NBj|)(NW< zRwt}ZSe>vsVRgdlgw+YF6ILgzPB`7Uc^>qO_sajYsn^{s|NGmw3Qs#~lf3O(Zxo*E z=8f{tma6OZf4O?YJZG=|uiIn9`g!?pUM_WB+U7U;`4209GJKu?W@#}oUg|)5zAFh^nxW7IZeE94tdBz>;^TLK-telVBq`t=@w>86R zhSdzK8CEl_W?0Rznqf7=YKGMes~J`^y!Hnt}dBLOW+Sd8^Z;`*-r>=S3yy#Z>@2l6fus=-LIv@1S_qp9JY`d`S!nO+m6a_%-vUbjZsJCEr%^%c!f=m%J=;ImxV`t zaAZDl`(G5ke}^OUkvA>#J#NQ`jSm|iHa={8*!b|!*DufM+S;FMEq{4lhszP-DUHjmFly=tH&&x zPuQtGBdl@VvU$jfKPnn_Sn8K~>}A6W-!#>7`HhR~GybkiE}#Fk&jO|V@C%3MC1+fy z@YKIa`NUlo{vNm6g>4tMUD$SE+l6fxwq4kEVf%{T$M!uVx9h-;pVV*niQKLOx9{`z zZ-m^g1GmS$|Lr?&9qPC5pNAg4GOu)3onw6dm@D&ii`O|`e>c%Aw?7N}S=i6Q?f(NO zOuQhkyhHu1U;MjKdESjH@4Uo0xo>RcJ@+{?U%PkxpWqlvyK*}wY)sggurXm{!tHVO z%jvex(|vwGxo7UVXq!Cljk=!x=zq7)FW<3EDeqrs%e>}W8x&q_nN9McH?3B9xmDN8 zD<3_)@Rle3I!|`hQicDw`_OjLV7svG!nO}{1ZLr#4wZUqG)ds5# zRvWA~_|p+rHS=#rUU+qSbB{Xzw&%6iq&p6)^KYwMb8Y&=%60zj+tdG^4!gY0>n^?B zb!ma~9xVT_R-A5ZI$(xJ3Li9bY+Cfq#|y9g_Sm%06i*diaOk+S=?2dg{$QqYX_u>C zDtyf=W7C+=>i;*ntqoQitTtF}u-ag?!D@rm2CEHL8>}|?^X)H42Toh(+|tVDr{B+0 zdGYzrOW!>_wD|t3!K2dUb5%Zj@VV)N8R~r9ql=%DUb%LrQs?Sj&rYvSHe=yWC!Cd5 zoTu)6`1LktrQN2Uu9nYpR$Ba@Qx|@HhO^QyPM@;y(Mz9|F5G1D!cQN0R@(iig9>jm z<=JV{MJD+kw>86RhSdzK8CEl_W?0Rznqf7U@&V1Tnqf7=YKE6t>fAKRoYnWS%bc5z zdF0u04-DGz+%(JS|1A9C9p|S0W9t3$(5j=-YU3xA^5s7qm5$%3-fw60pOgxIWEr!?eZUn;#sPZhvR`!khnY zTzY5HdN2L;fwAd=59&R3eym-ueo?*mez(YVX_|ricAv%no)#H4OZn_3b6uOZf3fn9 zzq>jOTfWXA|N6zN(ltw0-t?|3Q|G=~M{a9|)eNf{Rx_+-Sk17SVKu{QhSdzK8CEl_ zX1G0$=`X*Ja=Q-Pz7IEB?A&zNZ{9BV*s%|tlWyMOqrx){JtsXh?CZk++jq@4#54|U z9N0K;+xPJgjZLfl=?BG^p?i!?53TY=X=|>1$EM*U{#DrVkZY0KabV-X#(|9kx5u$T zKfff+c5xlAMo)HmT58!krs*|p$?ea=eirt#F!M9!D`5WCJO<3`n%{u=Uh^I>4{SaJ z=7-Ibz`U{f6PQmnuLAQ+<`|LN?ZUPT+b(Rou=r_kg>}BpZ_k!Hk0ILC3 z1FQyE4X_$uHNa|s)d0ud=cb<{pFr0<29al=Ykq^sKhQPrLF6UqnhzoJ6?Dy$5P1x` z=1++H23_+i#Qxl_`4;4MyRhxTwhP-XY`d`S!nO%nm-}(8+6U95c{LM=39{4?ZUPT+b(Rouwcxauh^_~Fb1X!DgMM=_#9sJ*b27+nZLr#4wZUqG)ds5#RvWA~SZ%P{V70-q-@I$S zg2*S(HIG5$8R(kdAo34%&3h1e3A*M(hr$OWy=$h*w@(*;)fe?8Ky5>fRd<9)|CPW^CuDKKCIzr6bC)XEZK0mqc5cB-W^@y1N zPp(tMxl(3+kX-MG^@Zd*NX&;M*GJ^GPFS6=I$?Ff>V(w^s}oiytWH>+ zusUIN!ZA;kob!))_2gPW%(o}k2x1;Sxpolq^T{=Zn72=^HN<>=at$Kp`IBoCG5?=j zvxs$pVjUs5_7Up~$u*If`%12r$ZgHAnqf7=YKGMes~J`^tY%ovu$o~t z!)k`r49EOca_u1I`IBo3G5?=jYlwA$>jSm|iHa={8IOfBX>j*LbpIl#vb%Er%L#!7h*CS#b zA-PTw>kG;Ci>jSm|ij(OVTdO^(RC)W{TooXBGwU->ld-UkX+Y@`TXR1hum%#wq4kEVcUgm7q(s4c46Cv+x@S<{GQ6~ zI&gcOS10x5b{)9=eR1rizTB<@w|{?QT_Cxp5bFiWwFdnqj@}O#=3%AGBnCDNf z9mM>9a!n!D1(ItGv0ji|gYfs4cI9?V*qE>}VPnF^gxlZKn14>rjmNxna?U*FtCMr- zF^`>`V~_dm$Gm!S&foEe>yq2rV70+&gVhGB z4OSbhHdt-2+F-T8YJ=O~yI8+SuA9WVMshtR);p5xEU^xfTz`r6k>t8eteYg)Yhpbm zxsKy+2iGpQ+l6fxwq4kEVcUgm7q(s4c42>iX}A4bDYxsu>jStg5v&=Ry7ah3}xBO_T(k^)jPkLsG!sI6${?cTH$y+$sI& zSZ%P{V70+&gVhGB4OSbhHh7)sNB2$kv&G7_KXmwIeLH`-c;N-MxT0^x_m(Jp+OcE$ zX8Lbk4}E*`EBg)}woEC%`=K#?*RJu4!Z*HjMPGM^`d-IRR=vD$@Q(F;kHx0Cv~OZx zeGf!#w+q`YY`d`S!nOuH1O#a3^Y|Fyr zbzI}j`h6tde&6MGyRhxTwhP-XY`d`S!nO@AD<@eSi3-(^vlA?q@$sOg{_z zS-9;>TJw~?!&h3T^#8MGozr*2KC2Y=K0%M%{w(ZgVLuByhVa?;y)C!vz|n90j-|{e zJH|54?AXivvtu&z(vH>4S38C?kL}pb{I+90^WOdzFlXgGBeylcYJk-Ms{vL6tOi&O zuo_@Bz|lWl$J-buyN<&#es&$7V_fYzZpV1rbv%!8xa&9{UUwb;<#v47_^|O|> zjSn+F=9tO6sADPfrH--8qdN97zv`IGysKk1^RbTM%+oryGk@!t&%Ca`1}{1ZLr#4wZUqG)ds5#RvR4Oi>~8pjC)9odb{(H%{Omez z$GF;cJdg3V>o_0daM$razAs&W7vy%ku4sZk2Bs& zj8SsC4&3es#|rAp?K*J#d#zssV_@;IT?cM|zhZpucWjSwyX%BCuLbs6V6O%CT41jQ_F7=C1@>BCuLbs6;Mj+o z+|wQVrjvWUV?T9r4|wdePVNnl{nyDo}QYt*U5eEa$66q9#}o4d_WJZ9#}oFdSLay>Vee*x9_Xi$DP~*9{anKd&AYq zxFNSc3;S8v&%)jhe6~G?$n83?-&5+hJ(AmX%4grm$=r95UoM#wFY?YMbLB-ox?~Q$ z$Wxchtrz+0k~#MxuU#@1U*x+>=IDz&c*)#-ksmLa(=YPoC3F2nKD}fPz{s&&gpv0znYS?V0VeYqMxMZAp2Nr=n9P3|c?FYs5hLGVGGF5Tw?3B4 zqZs)Kllc`RZ(%a;V&vvZ=3|uG`eF6M>W9@2s~=WBtbSPiu=-*3!|I3CUwA-2tbRCh zjwSQ#MSi?w{=LYXm(0r-`SgGLPRszZ;*-?-x1il6n8+c6`|Qu<>Ez!^Ve= z4@bVZWd6g*H<-+e7lk?ylldMazhW{EWaM*8=7*HqI$?Ff>V(w^s}oiytWH>+wSLtJs}oiytWLPy zZ;=NtnSU?x<0bR*Mc%yB8_3re`Sg-`{36d@GQVHs-%IBGi@bcve1MM6{O-u@c46Cv zZ5Os(*mhytg>4tMUAR5oM&80?PQ}P)n9Q{pc@C2~7$g5-GB;!7MNH;wjC_g7T#k`P zF`45r@+&5DKStigWKPJ)$C%6&>3z<%%WZA2+F-T8YJ=4Vs|{8gtTtF}u-ag?!I96l z`F)T4gz1)n+=h|2Fq!kv-vac@?a#t~7WT8SV;!Guk0Elq4%{Bk{l4&7xm^d2JYdN@ zdy&^JnSU?x-6iw#MIO9lzP`whm(1fAdGnI_{UV=UGVfpH*-PdFjQo4aJb{syFPT3u z^7SS23Pv8kWWK@3la|awD7SUO>V(w^s}oiytWH>+usUIN!s>+839A#1Ja5fe#*s&{ zIpa9;D>i2zN8ZKeOytPN*qoIdc^Z@FW=8(T=4|E2>)4#R9QhubvzQ~dTXROU+|~fA z0ain)GoS%h1FQyE4X_$uHNcUNE}2g+^57-&>_vXO^zK0Zy~vxF%*z+~^pg4dBF|nj zk6+}AOXl~J+wo!J!^SUl2I9lUhm8+Mp1Net!^kU`%!L^F29r4wBM)IRcVgrxOy*RK zyoJeJi;>STnS(L%942!!M*hQO&c?`#n9SuE`4W>k9wU!pGWTQTS4`%FjGTeZJtMa@ z!)k`r467MdGpuG<&9ItbHN$F#)eNf{Rx{l0PyJ#%k=u3P_V>bTq`us)1Gn$1$Y+?$ zg&27blQ|L{2Z$rLKMVU=*w4c4@h$QhCUYT1p2K90M88wSm)oC({VeQf;YB~5*yQv$ z_xUHX`_8VL@OXCL*>jIPmfd$Y?5#($`_BF~$D`SOXD|Nok?g*+(f^u|-FNoSZ%P{V70+&gVhGB4OSbhHdt-2+TfLzdLw&& z({i7_o;|Ddbyi(z5SGgmv z@pN6!+V<-^@-Ao9eWrh$cxT>h$m*reKOVd*zmV#_&MBYyN1l6zHB0%gKD|4?erV+> zXC9xQ7+HD3()Z>AhF6|v)yScJRQ>G4mG95@?OS8+u;2sv^_hNM;>_^Q1NrAWuKGQ0 zYlhVfs~J`^tY%ovu$o~tm+}G4u$o~t!)k`r48Q#3?fLfud%OO6V=u3~N^jgtoB}>?3nt_!^o@N&8P2J-{1Jjd++3*FInGVklXQL z>jbC^mK5Tq=_dmXv7yfrDI)A_YOL@vyY95LEe*bd*&EdZ)<@fIWN*@1k<&BPb zHUH_(%A1_{S{}VsZzYH*e+>)~xR#{CSGVLwieoKVge= z-pa3iSl?SXZpydwzTegN85UdX?Y!+usUIN!s>+839A!UC#+6b zov_;YEo*x%x9h;|@7Eq1-Id3DRQF3he9zr^nJ4Ogx|L_XH!t#5-H$oN&+gBM53l<) zZ=B)5eCca-FXw&dJ(OSiqVD(n=&^_MwWrm4X|GEr}{1ZE*YdYsClO$XCo%_jiwb_|5$0 zCiR@1*_L`cZ}d<-f5-0v*CMy$z{Y`%0~-f!|F7`3jF@t}4&46T89#q7|NAe?mG8)r zhjjDtXD(gXF^V{H`?Ij0h5ant{ytu_+VgqUdunckUA}lG|9+GD-C6sTry{3HZTE}? zpUkUHsC?DEkLSy8s&&R3{%HQ?@9OvN)14;dtM97c&51`ol%IQG#iH|n`<+q)dei`` z0agR723QTS8elcRYJlU6s*dLy#<_tV&pnLu1UsIG80QRjJSQ>EAMAL3Vw_9Z@m$3? zudw5Ji*b%&$8#9te8Z0CGsd}x9nWoy^AJ0p=NRWCc0A`X&QI)k{$rf0m^>FU&X!7^ z7b&;(!|I3C533(mKdgRO{jmCB^~36i)eoy5RzIwMIL@W&`2R4@{p|SvFwO(*`2R4@ z3GMj*FwPI{`2R4@747){FwPt8`2R4@A?^78FwQ6K`2R4@sOp%1Pi|{~)c~sjRs*aC zSPifmU^T#Mfa5%@MnjzY*=URNKpV|*PH1y2aeioXjd8AMbM0~7XwxTg4r$X@aXx9& zhjEr%)3}arR&GoJ6^;2UZWP9#}oF zdSLay>Vee*s|QvO9A^|J&xMTh9Fylo#yOA4b0p*Z$K?5vaV})?+{rjEGI<_loY$5- zr&4amhm8*#A2vR0eAxJKoQ>G=%*{9-v*THuac*YEGdklu&5mbx#yOiE&-9G*H#?s7 z8Rv3#JOeb&_3L;xsN8M~wk_DUVB3Oi3$`uTw%|BdvE$jPaXx9sGgaf<(vD}X#(Ab4 z&tQ#nPCK5>8t0#OJhL^6vN44YGuW`O=$1`E$+|`a}#m0H89nX-B zb6Pu|EgR=cc06-dZfl0s467MdGpuG<&9ItbHN$F#)eNf{Rx_+-Se^W5Xx|%hyAIs` z-HdY;JD&L%=PhN~8RtcIJj>F149#*|8>}{1ZLr#4wZUqG)ds5#RvWA~SZ#27JdAT5lV?Z9`H#sn zCF5MkPswc~lF zao%Xhb57$N(vIh!#`&Zj&qa-MOFN#I>hBJk<#xNU?ZUPT+b(RouQ?$A2vR0eAxJ~@!|IW0soWG zmfWrb`&&kx_HT;Zt^>z^>ExVG%&R2lf?~cUIY$)pFv+>2n4d|`DaBk)t#k^K>{w?OalJjyg50;#-i}|tSJYLM3 zCFl2IJ}o)#7xQe%`M{WeOU@I+ zusUIN!s>+839A!UC#+65=9-f8u`!RDoTrWX+vNOh%)2J%bz?p@Io})ew8?qkm?uom z56kWNu<>Ez7aoWY8y_}4-1gV_{Fce>I&gcujd{7`oMFt@CFc@j9xpk^81s9{xyP9I zOU_Bgd|+~}GUf@BbC@xIn4H^;dBxymSQF^`v=1N65Q{c`)Wu%CtfEZiP{{H-C5+^z$+|8K;6T5?V= z=Gl^SeKG%*oCAz`x#Zkn%-1F73}YTI@)*?l!sz%|543ZC$}}gYJk-Ms{vL6tOi&Ouo_@B!2Poh?ksXz&DZ_FsKK2re_MIw`G<6_ zT%qz&*9_^Ly;-m)@`TNk$G1DJYuH|<>p1E`TC6y;XYUa-TTOC`4tMUD$SE+l6fxwq4kE;fEKRrE}`gOG~@s_nM`1%h#1>8Z%4h+0QO3 z<;%x2*P7p5UU<7FXX$)3!@{E;CQfb58xy z3!Yr+5a*s@^}IadzcuC5IFq$!vFB5g3de#iS3{yc5;RsHT?^3%`K z+9y(ur{njiW6N3Ve4K7Rw2nD*eE3n?_|Q5Q?VLYK zOYc+1sHboGC~dd>xZ>AY&wrHW-e_#$%NPGR9lPFjgBbz+OSnkVB^5;@2S7J_%65Wz>!n8c?T@=emC!iMLzK6 zow3Lh-n>f|`NNxc%p$LN^X^&X8*ko8i#+7byK0f2ym^N$@|HL6wnaYk=AF05UEI8X zCAYP~YJ=4Vs|{8gtTtF}u-ag?!D@rm21nlGY>x5Bg|Z0_{PPoB-G9(l{Nxz;0}c{T@oGdAzf^ z$0Ij&HYd5<)(oo|Rx_+-Sk17SVKu{QhSdzK8CEl_W?0Q|Ko9{jHu4nVW zM?Us!e)!1Kp3NH{`P;MkKa|*s%>4dcPeDy4h8|OJOz4F6)F6}GtpP2qQ zvYwl~{N*FlR%bs^ayrej`bp`*x$4;mCqHmfT6~Inrtl4moSa_lJYVXZzT?U1k!$L? z3A-F{a$4(`^?fSJ$KO@YuBHCXOVxAAh_myq^*yl?f5Q(;9NPWmQ}xU;^vwTCeg6ub zH~jANQV0FZu2bJPYu~eryx}g8h$44-T~Zlh2QC z^!(tAqZ^&`ZgF&@f3061-CP&tUN80S2jbX2CH_Fa(XRc89{U-c_CNadrR|s8_7T=c zSRY}1g!K{DM_3m#g>us*{22ay=A7ox8B2x4C_t0 zMz8Ru*ZsJ+%uF{Ges}60_ino6+QPZ-N4@oyzoPIDe=~3I!+kcPS8elcRUkzx0)c~sjRs*aCSPifm;P5d!&O|?C@8{^B?0p{n zmc9R@KeOM9=;!P>6aAn49)*wD?^pPk{oaL-*>Q$)#~JE7&Jf3Oro$eF3P=L z>e~;*v42YZfpLa*?N9XB&*-%O(XTIUzvQ-$us*{22KEnD4>m#g>us*{223eKEnD4>m#g>us&LjkJiUW zSRY}1g!K{DM_3lH{4a;s`B>_|u|S=(CC(OO>s&7JUz@qk1JmwhYur}8kLX!z<^ICx?E6n;^uPLt zZY_`NdhF!N+un9TQ-1%}7d7=)c<16K&b{l5ZsH$z*riRoOaA4uM$eCbc6p=o-b*fT z^xt%Uln-1Nbe1!E8)<;+$VSR-45!OdoA4~lK zA7Op8-0Rgx%JmV}$5Ma5M_3cj|NK zRO51faF=?H_H|!$^UZtLXVQrqck}#T)N`~qo7kU^dAXjg_Va!E^K!G-y+0c**Pje~mc*Sf%DhCjO9F>)t5Zy?@iX&kj9zY*q6i zqjSo6>Rvqb-+yXluIrEem6!POolW_B-`v^MpEdTA8t0Ek{-cS%)&h4o?T)|V?nckM zQ{B_(d~oG^8vW;Qa!+$zlzY9@w;zaO{}A7Pqh0$GJ@zv??SJ&^OWQBG?IWy@us*{2 z2m#g>us*{22&c5YqUBK`#%T~Nwt_rT99qvx~z>slB(XMd(L z`oA7>QK`>$O<1t<4-cKIDS!W8b2aq`Z8UciXNhrhH}TJ#be^W&XIGx5(ewV^^E5iQ zJb9j;`d2%5p60qJ_j;*sKM=?MA-?@ayY?q~>}Pb^|LE73wqJ7FM_3m#g>us*{22 zQQ5!OdoA7Ooj^%2%bSRY}oYri)SDEBJYJNFL{EKEPVbVOzPXMt7z(%k=ZuW?Xe z`g7ulgA3EoM}AkI(eUeobq+1%_;uC7hZV-JHK#kgDSzkRm8pN}1NE7XIFFt6w^E1r zi)?sgVf>o>)5_>MbiboYIXXxGvoiXRoT)w!a$TFwUzzK*oPMxA{bL;Z&G_`E?b6Tc z!7p{!RH2rM~?@9Q%j(_8aZmpXjll(P{sqUtijO$!#BDeT4N9)<>BBq+M7a zVSR-45!OdoA1$XJtWW>I`UvYItdFoh!ukm7Bdm|GKEnD4>m#g>us*{22c=myi*m1*`t}2H>>uLWZ?tQFqQ`zlr~Qw9eQEn8w|#{55!OdoA7Ooj^%2%b zSRY}1g!R#K`oa4253G-{KEnD4>m#g>us*{22n?L`T?aXG(0}?5|F-g7zy4SMOpJ8w*c2;;#PnU%sXAgrmFtlg{2P{EugD>Hp;D+Y28v z>gIm;k5m5csCrgA^`D#efhNxJt2|t|#9zFw>Co<$W9wP)=vkwGVyT19r-#=yQ}l1K z;8UfX>$-Bk%Hyt@wrlyR#}4jV|Ff@W>l){_hv(@U|BQ+Abw3zrch9#M?5gL4cNXcY z^VB;Q>#BdrZ5Ho(U6gyh)VCjqWB-)+1N}z3_9uGmXLQ>C=+~FFUvk?=SRY}1g!K{D zM_3PyfKgq2FMAg!K{DM_3^$iAix>XGif7~%He9Ok15cis4`1XLg%^A2!aoPXnlNy^%2%bSRY}1g!K{DNBD2k&(K@#w0i&Fy37xI^S@mA$nB=@{prq4%00Zs zdDHbaTxzqzQ@l5A@4TOEQTQk8PurXC_?kCk{fX1`JXdA2{io^uXxIAPnPP=$dLNJb zeX0M$#i!}H&PDl}2h{Ho_2<6pkEITAJU5*9vtL-hJG6V@l=V3jJ@0;9pFPp}(604) z6aBNTU7t6(uFub`{F^st_`l0B+eV)d654V|GB#||4$Y=wLY)$|K#;O>hl`^Puy=s`LJc`a~btt zoS{C85oekgD-(bFv$`cd?RJ*Sh0$|se`R#OFlVonqrbOtWv=VwT`TkZZaKgE*606# zarmELeEvV!F8?dk!~YX?^8ZBr{6F!!DEE4)Z$A*n{vp2oM!WVWdhBO(+W+X+m$qMW z+ecU*VSR-45!OdoA7Ooj^%2%bSRXB?AFNOR!1@U5Bdm|GKEnD4>m#g>us*{228Ep>+N|3v=JQT4y#YEM0$$KAJHDSz;{kLT^v28A#G^s(Ik z%!Y;Uz4fuY%*h)S{^Zif@?IO)-%!f0o3s9gQh%W*HgDn_x@Y~*N&KZ>->Q_;?mP3> z_g>KR(jwcIa&#{6US;&Zz3uNxIoCDvn93Jj^i)&6)xl3U^^aZanI_JwlRw+U&zC*h zwEN42pUdjm^4RAZo$2o98vQdq{akZhlzY9@w;zaO{}A7Pqh0$GJ@zv??SJ&^OWQBG z?IWy@us*{22m#g>us*{225*M~r4I8^{rlWen0cy&zr3q3^H;~ea!+CA!O|S}7iJ!8@nat<%siOyzEVE_ z`SpEr>d!KLodY4xy{kT3>X-OSyik~S&m33R@zHZcx31%(b4aS|_~<`lq1Q`&uIu$b zS7si`^7mt&(E7|f8Hf2O<1 zUHcO~_A@%|fAs51+b_B8Bdm|GKEnD4>m#g>us*{22m#g>us*`qzwk+R z{ch-gKF+QaZ94DA+4ZAE*Z(NHuJptiA7^jszdw-B!pW1ZD2ibM2{h$7K zc0FtK-T%(6b5ZX47xi5iBaZ83#CIKyc3odXkLzyebUhCJuG4W{uHS8N$EQvC4@Z60 z)L(wr&zm@>{^W}${vP*y(X{){ufJ^cOn=3fjn03+`emd4uFt=0u8VT7m-_YtaqJ)B z+i$dMf1<~JMyLIcetl{CCAWQq^%2%bSRY}1g!K{DM_36^%2%b zSRY}1g!K{DM_3{3qr!LL@P-G3c^PANyv&Xb>87@f!OSQ-7hUs##zTJeU;FRXl9Q-1cm{Z0LQ{?*^a zndgdb6aVYgbJOm=59UVCS&R0vIuH1LuhGBGfxYIsDEE4)Z$A*n{vp2oM!WVWdhBO( z+W+X+m$qMW+ecU*VSR-45!OdoA7Ooj^%2%bSRXCNN9)r+us*{22m#g>mgA%K@e$TXSRY}1g!K{DM_3=>!%lxKJFoKUxL32! z?+ZNjO7^+_>#1JJKJQ<&?#tPEfbrM7l${?~bJ3Tw^9Bn(_+oZGVYQQ9%+53Hb-}w`+%XyU_?f-gH{``h-H1($%_GT03 zchA4s#P2)!t)|^uzI&_D^V~LXH#)oLyxr(O>DsrO>!RH2rM~?@9Q%j(_8aZmpXjll z(P{sqUtijO$!#BDeT4N9)<;+$VSR-45!OdoA7Op8+<6s!q+B0ieT4N9)<;+$VSR-4 z5!OdoA7Ooj^%2%bSRY}1g!K{DN6Vd8(MQVl5!OdoA7Ooj^%2%bnBQ@q@A!T9IfCDP zpD*}7;ByE66MP=w|AWtW{IBr&h5s8q*YN+u=Nl!Yv}hmj_dOIj^B67`Q5iZ{|Ai2{{-Xn|H0=w{#U4n{~PM$|B3qff8upf z?)6gNejtwhQ{oRi-_fr9i5~kIo%TQa^`-5X-1ZUHM_3ic|09G~xq@ADn)`h15TpYPD=^BwwqzT>)lzKiGdraYeC zoBHuw-^7XM{U(0Q12pZ%{6M28<{28DG0)KGk9mgXx+wR0sc%0J$NnL{{YJa?CwlB> zblU&u*O#_ma@)t^^?;ACKEnD4>m#g>us*{22m#g> zus*{22kI#4L^!X0`t>?Ss^IbeIH0ALe(bSLUizZGycQoLk< z@x0UMjOU$3e?0Fr*G0M4OMUx+IQ9?m?Kj%BKha}9qtpIJzrM8nlG{GQ`UvYItdFoh z!ukm7Bdm|GKEnEFxzBg{NVz`3`UvYItdFoh!ukkvjra)bBdm|GKEnD4>m#g>us*{2 z2mwZNBgyrv!mM{SN)D z^}FQyU91N+<*`oG)Q|O}CQhs?HSuG;scARXp&C80p4I4#^{hsJtYv#G{xjw@B z2!ana-{~Xe`UvYItdFoh!ukm7 zBOLF)CEw4C_s5d&0mge}$@c@}eY50ygYh0(@_oX1KP~y5VZ67Nh7G)*8SlR(-%E`5 z-;(bu#`|x{_cJN?{YL8h-Xn2*Ka=>rpGmvEpNSsd&qSy1XQIFLerEFh%y{3gDc^PB zQBD1LKd^}t?+rHb<9))W-FVNi(G%}0Hag>d#YTU;uh?7{!anqpQ(?O>m#g>us*{22m#g>us*{22uJ>kWPX*% zUy;n?5qTk!`8^_EL^AJ3B=f68zK*6m@_6)FKk|F@87K07^cg?$ zf%MsKm#g>us*{22TT zzenVYNap>B{1wT3Adz1pnI|OjP9*b(L_UgSUXjQ*lFT;}`72T@4@ok=3iZveLLBp} z5a0YNv}=A9^q5}-o#t0Te=EOAGQY|)n~eIu%g3G5)Q|igO`OR4(Zr8@AWgfGC#2C6 z`9>O@k#D5YANfX_>!RH2rM~?@9Q%j(_8aZmpXjllBi~5V|LE73wqJ7FM_3%5!Oe`&99=5lC=+~FFUvk?=SRY}1g!K{DM_36^%2%bSRY}1g!K{T zy4-Kh^}4T_esI4t{o_7p`px~(^r!o#>1X#-)Bom#g>us*{2Xu12% z^^tOYg!K{DM_3*idq>$CKO>$dcd>$&us>%8=*>*n;c>%#QE>&5uxIx>E_zD&96&eV53 znmDdgm-qwg=Ctd&HhNs|MyKoG=y!db>vG+k>$RMIus;1`9Qw`p^r!3Q^s{>Ce|6%Q z`ti%_qTK7HzWqQP`=`VoSU0C#`x8C(Gdk^m^y^F8FS+d_tdFoh!ukm7Bdm|GKEnD4 z>m#g>mb-4QkCf{ptdFoh!ukm7Bdm|GKEnD4>m#g>us*{22m#g>us*{22*>*X$?sjPrzic5b@rt1vHqUCA7WiTd7s33ee!!3>-fq0D%SUt z_glOVkh~A$eSmnUvgU1|-20aL-p|DGJ}>bHzIU|i_X0hBU(o6I2>pJ)xGukU@%}?o z9`8jo_2YesCQiIZ(ZrAUE0W*4c<-Xo6Ypa*I^+F~Mt{7&(OehhUN80S2jbX2CH}zo zj&|)&^w`hnwExksFKxf%wvVtr!ukm7Bdm|GKEnD4>m#g>us&Mu_f8)v*GE_%VSR-4 z5!OdoA7QQ$A7Ooj^%2%bSRY}1g!K{DM_3DzIQ=C`#uK!?|T~f<@+1><@+j>`@RbGeP4w*zOO=j z-&dhs-&aA8@2jBG_f^pE`zlm#g>us*{22GP$FFwNh2-+*yrA7KC#&U-e{)99{B`@TR-v)3^z{X9~f@@$V)KXd}5KWV7PiB@4;|&M&5(r>W{n!!@Vxb zyJRt`>m#g>us*{22nL9N6PgP z)<;+$VSR-45!Oc-@7xE(^}64LesCWO{p0==`ptbS^r!n-=x6u2(Esj#!7um4;FtS= zD0d$a_1ypmd#xDN=O?gK)<`+&GE_W^OemeUW`r+A3zKEnD4>m#g>us*{22*>`WKlY)^`{z_ zn>cY^MiYPH#@(jfIA5dD6X$d^I^&#m#g>FxQBW zus*{22cTIsG_ibNvl#-aoaeN1bXw8)s;u0agR723QTS8elcRYJk-M+ZGyFOY+(+ zAE;Bx;n3Wyp+}sK*AnqNUSqV|@!CUA$36+29s4TuckIKsu8w^h*W0nr|A(IchlYV` zDH>okz-oZi0ILC31FQyE4RHHmtwTAC=6JWK{ZQg?U7iU`pL9@!BmPs8h=S zXZ`=v{o}hI|A+6}|KG+F@71{8|6}J1kAM8@zM(5#SjNLYocT@PcB|I2mOlUbzkQc% zbABn`^Yb618O}Jb@HSUZnr8p^sKS3bb+WY1Zk7LX{uJq_Lo07|`&4P3w`)$DmEM{r zt@BRh+i!ZU@0L^R85~dV{!R0Yf5RJJ^sV^ITT9G?4*jIB^RGJI4&L^IzPwlEl}5kU zxBEji7whA@yxq6ncQr@rrT4$lcj~}d8=pV*THn^w)SRw&T=Ht)`5)DDI@bQht9|1i zspogRe#)zTBd-}-+M4pKBbw)e&yE_A{yo0d`DC{^%ln=B*_VGbBE37P#+>HTW7C1t z)pmdO?J;TOe=7g!r^lqX@2}dX{MFHE)jw6u%l_i1bn5$+r<&`?H1ohUUNLe+8ggaT zaOM>w(oavUeRAz%BhsS#)bk>5`}r~HfXV8)lT%D`Y+8I=5$Fq8I=EddPJIMn`_E7Uh?jU^uaFI7G7~DF zx?z@8)5O2k@~x--bvpism1mf1jnscv&8@V@3Tvf3E~$L!PV1yY$5wvu@ZY2p-mkpo z5$mV_ZcsnF`Yy|*sm`l8l)gFcr|H4fYks5)zZsT(K6AYv_L_9owA2@s518Y-{N>d( zXY~$meV5Pf+pB24beA9W?mBeu!k4}GgWlwS+^6ur_noA-`=EUb?>E_`y=#6^dG=E$ z?X5XgVMh@i4p67|ldS89EM~S({ zkjZ-+e!g4b`}-#E9rF0Dg@3>9=_+Go0@^#PuPrmoAT4(gBU**m< zwa!An|02KJ*{Rf-cfQZ^QHR#t-HW6T@*2z5T&7R{p?|qPedr{3_y3OGq=HYwS+@y!3kMa!D*WBPw%=&RYXZsz>XLp+RlYGeT zI~E=})2Dgg`D(jIo&8zh@lD&KeDpu*3d@@1a-;K>TVH};D>{E^8E@BHEC z`PrSOEPU67pXZ&2PhEJsmp{wBzG(|T_TYc=)C*2h_=QKl&F3xkP5B+1VZ?X&l!rep z{J?%c=smt^J(F?zFMrTmaB$82IC#}bdV6=CDRsU%Y%<2)!pHr0P;dPmD{p?tpx%31 z++E5~o@`KWfe&lG%AcP$X>W?z?knZfEIDcK-Fxa8AICjAN$-`n>lq&tPoJbW>+X-0 zI%jS_NpIc0Ckv1I%S=sMN8d8E(J<*bLz_DH>@>9b?DX>uZDOAI@Q|jh9d;SgXqfV= z!Hu?G{dI7odHU~WYOZCwZ-@34S^L$Z;gUUO?(O#0yM+&*dY0Zo&wgBZnFnU+{qf_k z3V(Ceti5L@`9bO14aUsYdw1_i3xC@`dvCfGs$VO-5a;4;Uj6#R6La+zdt#1K=eYUe zoV(d(FMQ3mbN9|$a@N8>J9h5g;00$cJoTu#d-G2-r10O*n!C5~+cOqUf1SH`+9N+K zyv=%Z_s*X%UEvLE_7Qxq7`HR@-2%-ek|$`(*e_bM{`laf(vszTeH+ zTj#~9?S#jN_KsU@g;KuO;WPEt{_QG-Kbw4TZ=JD~M;|x1x8JRmKb>Jn@08stA2V`D z?~I35F7@Y|a%k_Q7gj2K+ulQar(U{Z;n_c#p_lt=o#(dtVehAlR_;7JU2n*bYMe*b znzr}V(A7%)n_io`ckMUz42wO_pQ?B6Kh`eg$Ng=}-mlkNzwiO)P0^d|ZyOh0=Yz?6 z-QimnzTl9_d#|jwUE!^M_DEh}xjGKt^2_`3J=0%Y%KyIBy?N^g>-hH1@5bjXpRK=- zo4z_e|MKJddpgypAiWIed_pm-g5Wl ze-510c>8Sk<&8(3R_eTe%DwrhzB=~acGdWN-Pa>a`Ifuflh=Fmgu?qy{71fW`r`|~ z_{E)h=YvNS-szQu5?R#@xZQBD%`PR4Il%JaA zFNJTK|EBzhDGx6EWbekj=6ruGeDBdW=H;(BwD3<4zcEiY;jqF#zxKv_!h44oK7N{; z@~Yn+QTTwYyEs_?TzZ_Ug7qUy;%x-D;Tapeyt zxh+q6Z5`X!U8I|D*}9I&KYJr`;+;^(y>}y_vW3?+_vxn+l|kYpIpb=+19-$Kl0|*rTmyB?#_>$SNXFa{v$7YOXc@Jy)*yf z=e7O=@7$5+nyJP);IrHF_N&(T%g%dye*3<9&uqPWFE4S@4khNDUp=@90YcJ;qQuX(q z4PVZ~{#1QG{KA*=*H8bsw0qTr7xQF??pOGZ*IvkL?pc3x-+try{K+-7-3On0F8^@F z%D;Q)+5G24E6@A#v-!@gt|*_~@L!MQ!>7Eu@crW-&0F3uz>(kki{-B=0BOZlFo@5%>$SpV0} zH0B?9;sKTWPro~#`E>msc=Y!7f9yr0$7cV>-tghr?ElzfcN>@eAG__)>$Cr3=X>q??Elyk9={>`KX$94l-XWeyOp6j6M;~nQ+m!~mpxY_5IBIZpm})RolAhwp;VO`&2&Q z>f7=yzpwn%zIWuQKCf*JzxDRKj)!**b z`{zj)Z#ZWu|J8MKrI!cIRd~mdbEHYPti1nDv!zQmtGxN%OQo}?ezW{%m@w=7$^TI= zZ?Rz7@6Yvr)IldMoDRLD{*M}a{-Wu~6YBYBXCJh9x@Uo!_xsV=mq^QPQS*Mkwab!e z@xk>y+uOHWDowJ)#1jA6Z^}YJ!OQ*hzYku!VC!E^6J8{X_ zefy?cx&H53a^n7d=kHbjk4-V}!F@~otNu?raQI<;)8AkJzYX5%Z+&ykQUBNN_wvzw zTYOai@9p&W_v<_K!`g4XaeMdee|`OLcFlyn`Yzt^#ZrH+9ro@! z_`~`i^@4@(>ig@1^A;~g?fXjKG@H&>_?=x|==*k-pA^1e@n`xDIHdBB7bo_OJFfCP zXFuAvcBk_C2R+oc%~|!c3yi+6Z|C!emCyDqdQaaXoBX)&o}Yc)_vwxE6u#}B)1;wW zRIeAC>eBASzP?ialT|P84&HJ3!Z*HjMYp@dFALxO(3tMEYy6_{+mm0}J$TqMg-<(n zOn0XLE>(DeEw1RU_}&tQA3FT9?#^E>UU;49M|UUt*2>zIHR5uUXvc&x7?ZPk(Ggcje zYr!wxv}*qsZr;7%Jy+eRe~WvD7ku*_h$k>DIVr)FQX{-?C`My;;}xzp{A6+uk{$ zfA9M%-sMMU^e?sHf6Cv_YG)tU|Anu7rr2=)-rw!N@z}WvzHNbR`j=g7o`TO_d;R{t z=jSc>r9D^aKl`cq3!eGf;QkTsEm-i^@A*sr9-pmi4*J`?-EEGmc$E{D?5;X@#XmZI z^X|xN>YB}go$kct=Pv*63)`;WU43@7;iSXX>fUL*rYaEv;ZfYDiDV}N^Pbto79A_#1Y8-zlE^8c@DPC(FuPKge9LFiXYaHJx?ju)R zo~zifacroVv2o0(STY<-D#i@Qn2J5av8UqMa6GFxHyr0GRt?9hiebYstYX`6Y^#_z z9P=s`4#&cZ)5CGP;`ea;u9!L;Q!CaE$J&a)!!fvG^Kfjgm^~b`E0zz(@`~}pF}`B| zaO|&~KsYC$96~sUpxi<@x1gLuIOm{TL^v0rTuL~XqI^Z;e1-BDjq@1FZ#2$tDDTlY z@1cB1<9vwnB#rYV%AYjOpD3@=IIp67OXGZt@-U6_Fv`y~&d(@s(>QOVd`{zhj`BR= zJdfh3#_^Qmtj2Mc;;+W>m*TR57XR$Hj`58^_CvqZ`N3imw~T*NVFv$K8s@8^_~{(;LU>ir*W@?~3ai$MuT$8^`;~ z12oP9C_m6RKcIX<<9veh42|;)%0D#DKPWHJI4_}mMdN&h@)(Wt7|L%n&TlBM(tbmf zZ~32p<8u~o|LrSJ(tZ<^KWV=e%B!^B5anCiZ;SFU?KemHnf6H%a`j1`e(>QqbZGURuAlu#+;LL%NiKfo(Rl5M`W;*2Z;!P;*rbIX zjE5e6yR5U@q7TN(k9}0|QCH5651y*uW|MJya|?N6#td-1QjG5oj7l{v~S#91#? zdrr8y7ehx>Jn9$SIOBqK%bZy&_u{WV+qmF=>~?!>di$mY4|?+tvHlOXEO`G_{t&M$ zzIDNm4ZSyh|C4PB9=zr6W4F=63ZA|0Ju$NHTLmw$^sIPvY{lRF;CJ!Li38(L{Wew{ zRPk?BJMnDP|M!QF-5JA|tZRPn<2&Nu@mrO37TMyC81`iKg`S)t+g{kbj6XK&{&@Ni zn-%=QfwSY9yPAThocvI1v~Ts(rrq;MOrBBwwDVVaJhq%&-|^eOdLrVwiVyzisW@Qw zI_KK0o{25*?knpY{=?^DwZBHeYi|2SZ2w;Mf`No(d+T@yVdvm>HM$9 zIk(hx?%d(EIP+W8hPi(BYHUBDu5;g+uf)G5Ry%h;>*biZ_czP>yZ-W}_|cse-}B=a zW7Y!||Nej%VuzC}K48D+V}Tdz|NG>>-->CUUAX+eUwP}zSby#6|BRjX=Q!^N)yH^$ ztG8m_Q>)MO{w;6CxG~i~8UCNQV(x3|-~75u|0O;e$R94Z&Kt4o{WWiV!vn9yYrEIH z@n-kE8don~|6Oms&Z}Yn^Aw-GJewO z3pbB_z2c=8S)_UV`BTdH{$m$u_Pe#>rIuc_IW{ZqjbF6+=UWvow9Wf*;R!XapLg?r zwD(gBtou>y)OTxHr?c9JvFkr?Dfr5-{XM>YX2s8K^Fb`}@ys$l*Dv0W(}z}k(4&8g zGme;1#>a2>x0rci%|Cqp-S=X*6KnqApnNaZJ^IEn=gArG#rOBCxrp)4yca9(T5}PT z*ZNzW_MMuGcyY4U98u$azU{7S<(q%+`LC>bCk^zTvN3T~;>WlqJ)r8j@*)O~nl?xmY2_N}(f{KeAER|i*n9$0mm=6j3O z`~&#hr6!g4nswAN%`G2Sy!e!5nm_%$#`2r!T>I9X$z{&>A77?1PZ8r&zBsjvGk^Kj zYd(Q>Hd(pm6TW`Z(#>*7Cv(68eIIm!Aerv&VTReD)(+lRgL;q1R_Wa=eGs-x2KKAc33&#Hc^VzZO_ z63vKRDjvG>lFigjD;|CAlFfy~EB@O$OEo84TJc=JS*khpv-RJ?zF%6px&6wD=Nr9r zv+~~c-_AdBvF6Cl>i7@#8q|y&Q*qx%pKbndc*S4nzakwYe0j>{dE#O9oE?4XWx4IK z_53~b*O%s{U#sWx`TdvVj9=FCdXsl2Q`KS)(zReSpCNCao5yreqViqt)H8g*RH#4`Q5)X z=b9Wc;3w?9!gaadb9K(qYyBoyA5!tYt1F+j$kJv0rHf3@ZLX-k#|eL!o|nB-eUd%* zy&>P6yWStoyzhp*{mtsP{BZsobI?sSj-EB>#=Q8bg~~cVe*K30p3oTmK{9yL@+-z{Y+q&kE3-hIUtIZFsby2=}U454em$*1D z8&u!%n@dc{$tzTQ)>`?Joby1%G4#?rU~sj0@ue=x`-gm7{;p2D|Dv3^|9b@wU-RNT zX@@ro-t&8B1{W zH$Sr-zj^Rk?fe)2a#p*}CX>gu>o2p-*?Hf|AU z#kk*>`Q8WC@&1(c2lkEUdOxwp`;495f9&_~A}+o(SERV?(wu~MZuPIOxeCR7*ENTs zIPtpXHWXK0*PMsq(CeBDQQUf6b0mt3uWRl^aq)HC{Gr z5qr$>h@Iws#QsllMW(qT#huuWi<2-tUtERhb;MzqUSHgX>F0{`Fl~>x5Yu*wJ27p) zxD(Uw#kk*>`Q8WC@&2&B_l@UzKe5OAjGf+p?Dy{?4!88#z25E|0#~abbY2c>)LT~*|qb3)wz|0b*sO0( zKb~u@KkP9FAa;`Qr9z*AeGWyS})9+UJTRsI^DjL9Lx5 zq%CXv#WmEv7vp|k=6fGl$NR(j-Z!4>{lp&cGj@9avERQ7?`3Wf-q#!y?1Q-}*dKFN zux~34JHG5W`)Q5~_SxJQ?7ulN_+8AE!S7`b4aUu_!F+RWu#UMnSl=8SJa@hiMwRDc zk2yWC(_A0eZw?UN%iJKmugBR3&u4$U4*TZy*-t;0eYQR9zwP9AvHkpBelN!TzRdSN zu#WeK^}TOA*ZYY*-e>Ie{$sy?7v9U9fxNG|>DUKz*0De4vSZ)OamRj|`;L7!Cm#E6 zt~`DhbLjDVxxSilbM7(UTzsr!jy~2mcOTC+ryus1>km840f_zP2IRfW8OZy3oPF?o z_Q&h6Z(g7M^mEx~+r$3bPJS2L&+p~;V%+b`eD4G6cz;;m`^IyIv;P7lC?3``v4=9@2jI;H&4f-@W*fbF;R^!{VNe;4tz^vtm%4v?O?T*M91GslZKLwe?Z5r;|7oG{`T>6t4=+#@~L4~Ubb zXKopB&h*SVBMy_E;}pitvBP|G?68hGc39sWJ3QAMJJ@569qcs64)%YFW2a}19dWk& z&-g8iwe!XC(yk-UnRb0~!nDs7S4?YqwKR zU0+&7?Q^AJ)Y>C$qt;GoA+`2P3#olC#{Is`_dc+W_lNbpZ#>ugi9OzD?DYO)zke6} zD06J$Uzy7hzsnqt_+#dN#7{FPB>tN@Hu3AsA&I|dZb|$=b57zPx*v^kb8Ir-9Gk3T zj?J?E0LLcJHOD6Qm}3(=&9RC7=Gf%D%(01o<#GHj&&MD0I{0Z`AOFo9oA`CM2Y=6Y z;s@G({6oJN<9=V}dmmWG`%~5*;MnB3-cRiDK4Yi%AN&2g-1zMK>G(_BacMtaoN{UZ zUtDwPxIi3q>3Bihbm=%koOS8=LR@y~xI^4`>3Brkcj-8VamO#rcU;3dj(1q!aS+dS ze1tuYo3PXI6!tsL;=LSyiR-T&7YATFU)+H0I^qm$*B6&y`&@Ahw)Tj7u(eZMg{}SK zDs112albF~y$`J8{b7CY8_)HAVvqM3JH7wd@83lle`yU$Y2>w9_R`L4HSVRUm)1s< z)?QjOQ5t+{Ek$Ybr8O3%*_YN{v^G7p&DN#|Gj0t^=39f3b*w?j`qrT2xz?b>9&1oy zr!^?C|5F;2X$?wg8n)xoI&9}l1F>C4+KBD?(oAfhD=o#=9%(GLc3PXBcd<4-m~m@R zGT-~aI^G}F_rCF5?edhb-?>65(f6w_I`a93KzyHklxxhL;FUtD=)ij5@wf$Xm zF8@~xTmQb~&-|~@!nO`C-(G9)f~~y^M(ft!RWxw@y|wl(bF94!w)QUA+Ph$D?|R(l zm$i2pxArdB+Ph$$>+=hHe12JbmpRtn1zUR;Z0%jJwRgeR-UVBG7i{fau(fx=*4_nM zdlzi&U61?xvi2_H*4_nMdlzi&U9h!x!PeddTYDF5{Z_CwTfu0d+W)s^E92H|1zWQf zY|U0M8mx{xtl7%AHCw@qJN{z6<1cHrGRK;&U~9I5t=S63PRC!?Y-QY-uTAyHReS)p^>2c=|t@X*cwLZbt`UG3+6Kt(du(dwH z*7^in>l19PPq6Zh|Eo1ytry9=SR)c_jYzOHBEi;(Eb|96BEe`ox<0`gk&Ig-5^Rk~ zkGuZC8j)Vd^%B;IWZW8&U~5Eztq}>v{!i6!{6DGnX`Mmd*V=+$YYT#{EeN)@AlTZ1 zU~3D4tu0vQ|5qcj$evhR5NvHhu(buj))oY-E~V9o#6NUBfbt%V@12zoX|?T? zCuueBls{>;@RV0+HS&~ikycHuiB%q^)znjdrq$Y0-lnagW!(4a%y&Hi>$o0(^<59Z zb6pRBJ+249PS*oq|EKB!{-4zr^!+mL>w8T0!S|c&kMBL%H{XY{pS~w$pM8JI{`+2) z-^KT>{9d2Bhi!a6%Y5J4vX1X_S>N}(JlFTX*yDR)?DTyx_WK^0zeC?IE3ep&E8p18 zS01um2Y=q{D{t98SNY7=9_2Y(JC*-z?N?s3eJ{rSzRdSNu#WeK^}TOA*ZYY*-e>Ie z{$sy?7v9V9GVkknnSF4)%>FoDX5Snyv!9Na*=NVg?7!n>elN$%{9cZi8F#$Qe8c-;AUYwj>^%^k2ccfi)%0b6qiY|R}o_J1lr|No?Rl66~nUu(61 z(LixMfVEl}w^j?-S}kB}wScYFQs)0xbEo)+)@or-tknYk|Esy9d-MNlwP@c|Z}7iH ztHt#jsuTFH#)p18)s6gLtMOrd0sd`TQvhsD0kAa%z}6H1TT=jRO#!eq1;Ex609#YQ z> zq6eFc9&9dpu({~L>I-PO_ZfG;gSqIvj{6wZ1#alamRx?d0bKh>`n z?$=WvUpub;zIML){@Qia57@4+KEZImp85w{d(>Ch+NplS)_(ONw(rHb-5~LWnOSTfT^;XQg>0#4nNNmk{qnns-8c6lp#R@l>RFD#Txr=C2UPMVjM6+!tx? z3vqO$IXcAMk>>6YS4NsE1Ab0(Xoy=Q&8;EMjWp+mxH!^W9OCFmb99KiBhB3*PLDLF zhqyk{Tp!{9NppaR8zjvQBF>OBXNWjP(i|h=9!YbLh?6AENg}S2G*^i@Owt@C;xOz`_+;8%Z}CpFHi(ZR%|{`=h%{e>cqGz1 z65^Lg^Gk?#BF#G?K8iFSg?K8`JQd=vNb^^S*CNepAs&o04~FIi5 z#UYN4G)IScHqtyB;@?Q~Z-|#8&C4Oajx=9~cs$ZP9^xKJbB~CVB+W@8K9DpYhPn z+>c@IM{z=iIU&Ur8Rm)#(UuQi{Gu&SzIaDl{(SL~w!He{ zDQ)@o#b4U;@Qc^9<>wbiYx^v5qJ}w9#g!W7N)?A{m_t?Es$p(baju3rSH;B|=3*5` zYnY=|+^u2mR&lz9IbFr|8s>Tx2W*%FR@|^*Zdh@~hB;%!c^l@u{l+OThWU8K(;MdL z6-REEBUjwHVeVXU>V`RW#kCve+7$7WZ! zVNPaoAcr}S#f=>1Miyssm@`>i%3&^LaV&>9mc_js=3W*jbC{D^T+LywW^p)&Ih@7q z9OiZw=X03zSzORzE@*K_hqE^hd>%-t7|=C%JgeW1j(@ zbMc>t`On2+9_BC?w|SV`T%6}&&U100hq=(jksjtq7pHodQ(c_QVNPaoHHW#H#o-+0 za2B_7nA=&L&tcAIaY2Wm=5xu);E_2DoFwYaIn+|=T% z4s%xTDm}y#CY@LEX0L4VMm#%yT*0$$ek1n2xN`Wsvi+O!?v0giXV9X5jyK<^JUq+4 z@#lErn-$M_=B?NxD_75FU-?VS*}vi?K72bi*tp`ci@XzS_f`D%3h&1Ahg5vR;;+XV z3twEG`?-_;7IO}%97MZJe=jcD;EFOn_Re=>>!&OJ;Ffn{iCunO#*ew|ud(MP6`%g| zx8u(@Rs83@{t|;Os(7oRZ^ilBRs6ZmpX0uV>pE-dy$)Kv;=50LBYr%hK6m~=#Xf)e zDCRz*{zl(j!R{XSm=BE{JZJ&8- zvB5mL;@9nS|Cji0`^cGJLcmRPjAOOz2fifn7?Y->J-b=s)|!3wM0C;Jc+!bHl5L75tAy_lZS699i&Rw%s!h9`?(E z51qYF9RKgiEjDwFz2i6ARD9{Zd&QiiPb+h7p1xXIv0vp47;)|J=og`uVcj16+ba$YW(4%`kndtEmPz1DfK(^&5NhT^nvfp zb309q?X!LlH-B+TJa%LKPJVyblz3oV{eEsd_UahEXZ@~DnmIYXHK*cje}7ec=Y;yK zBkq|Li$78EJ^d47^LeYyyI*r<+%#Xs&zw3n7G0};5AT0qYHWU2{eC`h%(R&A(E5%2 z-Dy+f(p4+(+@oKd7K0 z>+inpCX-{>I~AY%)FtuTDfM^X?u!@3QAgCjvDc@Ki=B=?3oV$*`}-G5Y!nz3HN6W$pWXYIE^!JFC?0%rXb@I3Gf8~kpihr+v ztG_w@iS8aR)wA-&&J*3GAFO}d(>D2Ich+6?Z+^iu9_wE7yL#qc)_J6R_0#ol@5m7k zcIW?G#rw{=ue-;-^}N1($W7fJy?;}A)+vWx-1f%4e&l7{8{^h8{>fffc5j=z;-!|G z-2LQ=TgvzaXHM)XNK0KE4Lyj(GS_>&f| zcEXeY?h+Ma!_gy8Ec4;>cON}``|~e+bQy<-|FA16hM#}p_@9(7m>BMX+l z(LG_Ix;{DuAB?NdmA}zl_n>MIx(0inUhPEh;P81Xo_x%?-J{m5-=fjeFXbe3D^4N%2gEc_zg_ z8Rnl9A7;zBEuPFUr-%3|TTX28Shif*;u6jx-JD^i@6VNOeNU52?X#Vr};mK5h? zm~&EGlwmGPaa4vmD#cwH=B^Z{Wth`aT$f?4OL1UE%Yiv~e3%4u1=kU>2pwLS^6x~8J9leboQmsKAnl_Gf`({`mEF$nm$8y&Zf^< zoxkbxSLbs2T-JG=KCg9-r_XVn@9Fbh=YIO!mp_p92jnND{RH_BY5ze!N!lloucEwh z^;P6=r2P%~A!$EE{z=+Dk>8T`TjbBA{TcaAY2QgcRobVLUzGNX48|6=?{Ym+m zX+Kl`XWIXiUz+wy<*%mwRr#@LKUV&2+P{@Qoc4$1C#U^n`Oj(pS$=ieua@7Q_S@yp zr~P^P;b}iy{(0Izm*1ZD+vU%v{dxKMX+K~7f7<_743dsP6q}@D6U7nfI70D7I=)cc zk&ZhQkEG)f#VP4HMe$2IeoG(@= zSvoFLJeZCL6}zQlH^p@6m`<@?I@VJRn2rGz8>VAJ#f<5gQL$t?mQ;+HjxptnrhQTQ zsA(TnK4ID?l&_ff73D*weMtG1Y2Q*lXWHkKFPip6<)fy3RQaxH-&Hu2Gk`fSCYv<4P_rnRx~KdqUCU%JA8mKOf1HMa0$t-XbRYfUa`hqZT_ z(iBT;ib>lmt?ebvuiS4y^GjM_X)Q2mgrzmYq#c&l4wI%>T2o9~V`;51X^^Eg$fQk{ z)+Uo?Sz5D98fs|`HR+wD_0FV&mexU&K3ZBIO}c4m-8AW`rS;ULvzFFblm1#-e@(h< zXHMVff$4mp@`UL;q4J06{GsxS>Aa%yjp=-&@{s8~r1F#L z{G{@h>Aa=#ndy9{@|@{Br}Cfa{HOAw>Aa}&rRjXBa=+=^uX4iaoUn4O>0GOFu<0DE za0GXIyy+aTa=+=^uX4iaoUn4m>0GgL$mtxia?9!5vU1MpoU?M# z>0GpO)ae|xa_Q+@y7JrU{I>Gm>Abh{;pu$1^5p3}x$@`f{JHY#>Abq~?dg2G^6=?A zyz=we=I6I~Bb~QbUN@cBRlYZ!?NtgbspA*&sE%vM zuR7i#@9H>+e5_*@p6l3+9I|6Na=DJJ$niSnBKPZ9jGVAzG;+m`-N+$3rX#oPSdW~u zV?c7zjt$9CJ7!dj+2+;J?7 zR-of)SR36y$KdD*IyTq0uH%>;{Xxg_$|tnzE6>nzoIV^77T9mk}KRXdJV z$-_G?CO_}LJ#y)eZOO4a<|X&;SeTr=V`Osmj-AQjJEkVL?^s(J^l1%x>BXn@;-w>> z){&RKd|F>#y7Ot>dFj!o_2{KjpVq0DetlZMUb^;aUHjYCKQ%|rTXPrJJv=7YIJ)YC zT>0lQ`Od*L$MUZy$K>GeURz@S)h-#6zu2?pTW;KFOkVf>n!EVwb*JS&e_rz&^Url! zu609Q^Mb3##pbDh5_QL1n{PUNsHtT{bjB2%0H{4)!tEsxc zH&1D`R)6%hQ(FzzZ+voUtIfLbq|;i>))&4wrqyzN|1fC>ym@1J?vscAyUkzSKI7%? zE$3F-UisBa-LcnJ+rGWQOWj!y*1XdlSH9G}^u7B3e)z=8-F+6WIj%|fzS=!^@tWg$ zzhc6q-QM>X_WM=Q6lY*|^8vlCDtCxRE3{Iz&C|5J{h?XMG~+7WJ%KBt4^^^^By=)c(7cW>Z?TNxDdB zT_ouxrS+1eqmen z)`5~fR9YWOx>0G}C}~&qtX(C|sh%~bq(#-U7L_!rde*3tc2&>XRnoNTS<^~dS3PT8 zNdv2A4J_&P^sLt-9iN_ce5CKwv%Zh~8Tz<8D}Atw{<{KyZw1f(`ijks(gGKexk5%?tBiS#Wl~*nDS`s|)_~LSJfTTzOr=dtCn|dU6Z?=jub6xrg-%UgDS` z&3cR6Q}BqfLrQ-u&jr()3}()bJKs_;|L=3Zysco?M00^TJZl}*DuJRCNMOE&augKX>BHrd>> z&3c!f-$n1(^E-m+?HzdEp7(_R*L%g9-b0?{y~PIaIkx$?z-IqOyo-N3ow>o8%d>P= z24^K$XJ~MSf_1hAXDe7|ZgA#;bruI_F<57Ga7Kf5b_ZuSSpGxcKY(@C2WLH4K0x3D zfaMzmz5!T1L*O%jSyaVeT49-EY&d1<<1nb-k z&P}k+_YUVfSm%E6W5GIqJDk5@oy#50W$+T;d#A&B4c0l{;T#9+eD83+gLUqAIQPNw z2RirzVEG9h`~%l|30pkVn$rA8Dif2q`tg5^h*no_X*uE6gC%O4B;F|d7XuzhT>eQdCOY_NT7 zuzhT>eQdCOY_R=#u>EbY{cW)QZLs}qu>EbY{cW)QZLs}qu>EbY{cW)QZLs}qu>EbY zV@a^SKP83*JB9^2h6Ou@1v`cXJB9^2h6Ou@1v`cX^DN?4u;W&+<5sZaR` z@;x-=!P2$w(We8J?mYfj!P2Ae(O<*3bn1Kb-GHTE-=iM~EM5B^eL7(2-S_C<0iXV- zxq9^VfFC<=t{(k9;0yMft4ALYnApV6B4)7-#1x)Gtl|Hc7{qH5oA_D8EVhAI#3#Rm`vyw~yoU}rSo+{S^ufW> zG4G*c4wk-o4}Ej6^u&AUiG!sx-a}^`EdB8w`r}~flK0Rh2TQNKhh8~YI_5oe%)!z( z@1buFmhO2E-E;8sGsP3WP5pb2PI?cWbjGEh-a|hfEM4^;y6RxnkS8_dVAX6VHQQj- zawoOi1&fQG8gH;_zmwW;uxi4SnsBgc#gkfbuxiMY8gj5|%ahu2uxieenscyf(UV$q zuxiwk8g;O0*OS_Huxi?qns%^yLz3PQuXW*9@E_;QN^0Z5s+mt}=E16^ zPipDGsIF!80l?}JNO}ao z>K#aW2f*qnNO}su>NQAu4Z!p#(t`k2uSC)-0ag!1(nA4O&qC6(09G$U(#rr=k3-Vq z09Nlq()$2bPejra0amX>(klU04@J^L0akBC(pv#m&qdO60ahg|(yIbi4@=U+0#AQqq?MR=-lxuLM@F zP|_;|Ru56qLj+cDQPNukR?kt=a|Bi|QqqeAR*zEBqXbs(QqsFr=RceDG=bIYl=M1* z)dQ9EK!Md8mGnk|b@$rg?iH;2(+>BiVBM>BxK{=1zO}=BD_Hli9qwVlx}WWEKMU5q zZHIeXuazYNyB zbBB9pu-QaE)tUKRQD+SiwYjF1p)}3r{CkxhH zZE#l$)*WtehYQx-Zg95?)}3!~=L^|6ICte>-K}@HTLxVBdFxecuiCeK*+m-C*B$gMHr(_We89ci&*&eS>}X4ffqP z*mvJx-+hC9_g&@>+( zSAbnp0d`FV*fkYk*HnOAQvr5O1=uweVAoWDT~h&eO$FFB6=2s?fL&7oc1;D?H5Fjj zRDkvOS!yc4uBia4-=s^w30S=$U3x>n>KWC&qLRu4;;9u~0rT)OnRfYtxfrT+y??JK=DU}|FN!2wghO1})4x>ovV zz|_0aUjwENmcAP>^|AEhfT^3MPX|mrE&V%S>U+Ju@&Ntx88NP$LqB~$VCr@04+2xi zOWzQf`d<2pz{)xF(`N*x9+>_kFm=N8C4s3Qre6unv*@b=Q~ylA6_`3?`kuhlC({oF zrf!)&DKPcS^iP4QbEdBfO#L(cR$%I)>B9n3FHL_Im^y0uw!qX^)6WG~|5rc#Utslx zb?FNOt6!{3zZh8kL0$TT!0Pwu((eOSA5fP*Ah7y_y7UKu)i>0oZwRb@qAvYJVE4^| z-8Tnz-yGO|b71$)f!#L;cHbP>eRE*dv6Q|!u>0n~?wbR~yN3?! zenzl+D#7ll1iPoQj1Tlwg56UIc26bPJ(XbhRD#`833g8<*nN~>_fdk~M_J|%^ihJ{ zM+tTxCD?tGVE0ji-A4&_A0^m*lwkK!g55_6b{{3!eUxDLQG(rL4tCEh*gdmg_soLb zGYfXlEZ9A>VE4>|-7^bz&n(zIvtakk7Cg{13wF;e*uA}A_rinS3lDZLJlMVPVE4j< z-3t$PFFe@2@L>1C*ZH*<9_(ItuzTUb?u7@t7ar_hc(8ln!S00zyB8kpUU;y3;lb{O z2fG&@>|S`Vd*Q+Eg$KJA9_(ItuzTUb?u7@t7ar_hc(8ln!S00zyB8kpUU;y3;lb{O z2fG&@>|S`Vd*Q+Eg$KJA9_(ItuzTUb?u7@t7ar_hc(8ln!S00zyB8kpUU;y3;lb{O z2fG&@>|S`Vd*Q+Eg$KJA9_(ItuzTUb?u7@t7ar_hc(8ln!S00zyB8j;c)#?*gUxFM zHm?!byhdR28iCDg1U9b`*t|wy^BR@$0bV1pd5ys4H3FO02y9*>uz8KZ<~0JF*9dH0 zBd~dmz~(gqlQ)3Z2y9*>uz8KZ<~0JF*9dH0Bd~dmz~(gqo7V_zUL&x1jlkwL0-M(e zY+fUuz8KZ<~0JF*Qm@H;57o9*9dH0Bd~dmz~(gqo7V_zUL&x1 zjlkwL0-M(eY+fUuz8KZ<~0JF*9dH0Bd~dmz~(gqo7V_zUZXN+ zfY%6YUL&x1jlkwL0-M(eY+fUuz8KZ<~0JF*9dH0Bd~dmz~(gqo7V_zUL&w-LKctBxh8V*#taC8%!!tL`PJdjYE+Ca8x2t4=1UlL4!KCa9k& zbMn2Qt_G}no1osN%zx&+pbiJD`kbIX2duiCpl%1OTzx|w5m>qUhWa9~a`g@MKVaqR z8|s3<%GEd23xSoZm)}tBRIa|EzKC(<>Kp2gz{=G()FYMuch2GsbxL5>H8s>VfmQF+ zQ11j*ZB;{Ul`%C}VAV%8)JK6;H`P!#1y(&(Lp>E(byf{^RvxGR%JZqq0<#YFT42?8 zHPm;3Rrl3U_XSoxSVKJ+Sao8GwI;OV)Q@>Sb!A}Iq23IP{nWM@Q}YJqxzwkDv7fp% zF!oc=2F8Bs+&oVGo99y(2WB1W<-n@1YpAaStM0C$?hdSazlM50uxj%fYV*LV*=wlT z1FM#=p_UJ<8o!1bKd@^58fyQ*stIhU2?VQFu%T8EtQx|G8bYw@of_($z^a34sDlEl zKB}QU3T$pku(>6{=9UDTTM}$;NwB#k!RD3(n_CiWZb`7YB|Q$er02se2{yMR*xZs} zb4!BFEeSTaB-q@NVBQOENwB#k!RD3(n_CiWZb`7YCBf#F1e;qDY;H-gxg|Xgx1{I8 zEeSTaB-q@NU~@}?%`FKwwx3O08u*xapPbGL#o z9pG;DINYtCzr>;+7tA_vw=!<-R0d)uXnYqbLtCklyTNy z`J-10=D9O}{BptAbKk)=Z;YLtH|y_?{kMMdT$y8TWS(noWU#rB!RAH=n;RKyZe*~z zk-_Fh2AdlhY;I(a!;S3uXncdsjSMz7GT7Y6U~?mb&5aB;H!|4V$Y66LgUyW$Ha9ZZ z+{j>aBZJM23^q41*xblqb0d2kZe-6#iyUljWU#rB!RAH=n;RKyZe*~zk->1q!#xf* z_c&PEXts+f9iypefC=z_xm#6`@lNhAJ+H2@m%jG z_IRJM)BBJ8Xvh1#*1N9O-}1gEe^N2~FyEWMDgOr9pK%9IFPMEh>Blz~%jAQ>^t2|LKe}_|#shIcmIQ!uF?2p$mw?BKre!esCT=v=a zu>ZD`-^KRxd-=T>_xm#6`@lNhpR)eIzVTe|C-!)svD5pH{r+97oq?U!&H!6G18nUK zu(dP5*3JN1I|FR(j52>fI|Kaj+eToy?>0Z;d>>VCJtlQ18S#^cgXq^_Rc= zm^y#$C7R0@7+Em({Q2YK3dYX+4>`VI>|gHNKdfamopdDZSU)hOvJQ(}Y3kU$nZw>;qa|VD<;CE-?FsRu`E4 zM5_zTKBLtI=J!IY3(W6@Ru`Dx%k}(>qt)g4Xmx>E2dyq}SzlURV4jOM6Bv7b*{yyQ zb}kv!zrz0WSAC_-;k{n@X~n#+$N9ZHpZ)PV)_!7rYd?Ycy=;#(xWjhxyV!nyFTWS# zeqZK$A6UoxQ`R5YH=gVL#2)W6c6$G@-@l9Q3X8THwpm*ZY;85Lwbj7ZRs&mG4Qy>S zu(j2|BL=k9z}8mtxZl^>YK&W34Qy>SFwgbxg+1P9?DYO)zke6r%fA;|avn!x&hycp z^EznKd406%RvY*`LBr0!7ut6Iz0ka~{b=F&_hQ_?7xVplv5tSQvi`vD#dH08VUK?= z?DX%2{h$85&@N<8cwaQ~!0ZFsd0_SjO+D`$T6g<#f4yAaIpg|;9Vd(bWfV<*~$VC+Y`5X|p|b|Ki>gr5tz8JVb|Ki>g=kKYQeMTF!{J;9W_W#aB1@n7-QT$4b^LsfT z#W>oao{u&tn02dFlFZisxQ6to}Q~o^6NLe>>RO`B%l*|I(o~UgN#oD~EP%JAQ+B zI|t^Yb?bG|!1elQBpI8I^wqQBIdBIXZSqWa;igZ4Kzu>M-d*4iqbd(mc5#<8b+;D!Zb=Q7KE zqhRb`=jgQywst)0SUVnU?Rc=Yndi*BLUa zuVB_cdG!qn=DC~hyiUQ`GtU8Q6^xyGoV0qu*x&14wcxpL|6}a(mF)_?;)*BYU)xr^ z_s^eoUgc(Es+j-z(ly&b>)3&Y#_t3JAC!K`!Qk@dG@{dHg2yNvVPH&?EIx7hRi z>fbBl*!k7BD#rddzPE1~=e@?BTJe6*Jl>8^{>{lp&cGj@9avERQ-v+u3( z<&)1T@A&M{+v211D!y=~{&?b{itm2AKmN6L{k9Cgx*Nxclb^rOkGIL#X_s>g{>gnA zQ$IJZ;PGqp;)!P}9(h17&b_7HXKi;}FV?;I{4$5}hkssu80Mcjy!tJybL%SAZ(;o< zUaFYqzI}4_VX)_*`Kk|too9%T5__=!@XIUay*9h4;>&(`Q8WC@&2&B_l@UzKe5OA zjGf+p?Dy}2ALaZ8{*~is{6ojr_+yT{@zWfSv(@y-}}aMy`R|Qea24jKlb}~Q63{BZ zr{gun-RU?^@pwAEQ=Fd8Zzz6G$AgON({ZBW{dD}OJU}|GWZdy4^Bsq>j^op^{y^Ny za~;oOkK2xFC7rj|{YyHZuX~wv zo?rJh>HNR$ankn!y5C9P7wDcSeUG4fqV)ZO?uiN)3V;8M`#ysCzNcUv-(Rr4?^AfL z?>n%^_aNBm`w{H-y$SE-`xM=awd1-kYv=18tzAd=Ywh~FcWa-k`?%H~-Rre>>Rzw4 zU-x?Ldok|!Wxn@;b-X{U?|tLB-cRiDK4Yi%AN&2g=sTZ2zx16XN?f9DzZ_n-Mb7g)#V1?&49;kiCvu*c^PcKSTRexFmkm(MT0Cm!cJ zim za?7{FxX&-<`}|@ZpI>GDf%A*!`uxHkpI_MN^9%cZe(_#DzvPFsz>q z>&wsS`TUaq)7m4ysI^o6Qft5bsP?@W_xm#6`@lNhpR)eI`Nea+pV;Gl#!l})_WO5H zoRW^ey-e#g(o7iYwdqV%+b`eD4G6cz;;m`^Iyb|?*=c(?&`+d&pe!So3ukOwJKUL?@Z-0aN_BU9^ z{s!yY-{86SH?YV426o!tz<&E1yqEnA)d_SxuKIzl=c}%u>vdFb(DnMNL+JXss!!a zJNJC=to!Jm@1u23-Sa)Q?yq~7d}Xf^3RU{|5QCd&-DPR6ZoI;TNZ2QtFEA3 zM|BSE`l>@{pR4+W)*jU@w05eVp|xLi4()p}?)PQB_knf1KdkS4F7%hpaXsoxf6EE1lO;zAK&YQXVXw2UDIchYaM$ls8M~&6H0| z=hKvD%TMLm()l;$J1@sN&eyTN^LRYh`917$-VZz1*|Fx0vH!khjwydjyw{lDRII#W zJFa|VJ70Oob{*v>+x3;VY@e%qW^0e~qOG0Ei?;SFFWSBr<9=V}dmmWG`@{O)H=gVL z#2)W6c6$G@-@gmr4cABUJ#ifl-x=5E@cnV!4&No$^YFcLeH7m@*Z=T+b6pVML)Q!O zJ^WN1QNQbpnD4qH)^R;jS%08TiRZdL3VU4Fgq^N;!hY95@m{Wv;(Ow8zB8WB_s8q- zUGn;TuUsF+cg*(ieY2f>_iR7kL%$c}eqZK$A6UoxQ`R4-kK(!BPweqNW2g5Y`~AD% zNBMpk|H}8v_+7qV#vk*&Cw`jmm+{|xzl>k!`(^w+-!J0_`o0za(A?$UeEc!5gP-R0@!$Mh{5so%zh^t~ z18qP4q2G&fzc2H>53J+;VSVo#&-H#{kM|inz5m$n--X}H@fYuFKc9WD|Ihw7E@0mr zFR-7EBiLuh7wo^|4t^KMBm7>DQy6#r!hFXytmAlx^&JQCT*pV)%n z?)!A+`<|V3eE-h+zL)2@zOTm~-{WJa@At9a_x`+>>j8LQkFyV+&;EEF_RZ_FpMEa; zYI=w2uB)~5s;f`e z)vMkhsg}`KsH`l?UqfRnMQU=U1J7y3Swq|LOXF^#$ao`U2AZ4$OBS z0qeNmf%TVM_A|wQ;JNqiF;~IZbI0D5KLI-z7(7oI$NqcIt(f=vVSmNygJ{RqAJNWN z-$c8P`YGD=)o0N@SN#{QJ?i6V?NlE}Yrpz9+V^7I@5_Ae1M7HySl|1`bG@I~<9)_X z??3kYcTt@~y3b2>0_i#d)eq#@t7^@F>I(A2eWsQ@QN2N~yhrW-QXN9RaeD3lQhh=m z`R=u4j_MZDbqlIzNY^u{&LKZl=a8=7V7}`&SjY7etnWGsp6mJw>~Y-%cDfz|``bDV zy_f4ZRM*jttKOrXuR4%+9o2`l>#J_0eXi+oOKHbd?~$IbI*{}_st-x8uey=+b5&20wnud-X**SylD1!UDe3oO z-0#bL?*r?2e^}r9#&f-&*yDZ1PVYbV`*%@aTQ2t4>{1h}zOdZq%MTW;ezAPksT3 z&-H#{kM|inz5m$n-$nYBiGC$_Qqr|dbS=TsyG-;h!P3D@bTGlv$4vAw!P3o4bTh%y z(@gXrC`I!P4v>L(Ea7;8D!5<7BpJ+RRrTLg>K9=#> z;}b1NurwkQjYzPxBNOdNurwtTO-Zn{CKIhmurw$W4N9=IDHClBp)S7eYau$6t#-){+Xk~(>p_yoCf~BpQXlsI{xtVBgf~CcoXmNt2 z(V1v;f~DP=Xm^68>6vJHf~EDDXnlgEN!mVFTBSMV@Aco8G(+>?YpQM163sn!db-S) z#%QiOf32mL_Gqs0T3uh7q&ad>{kJcz(){Wr)gEb>=1G&QozgbVLx)!TrFoinoK)XS zTB!Nj5%qngotkK;Vw*Ho6HQgHv{ns90PF zvBSv~ivuARc(MM!;zo$o{#w@*_d-nj?80RoaWcgEYgZmE@hZf5KbTYA<^8SRig{11 zf4Aach;d`;->vu=V(x3|->rBX;-di`SMfZ=uJ_mP)eR547O(AIdqTwv5mzr>e=qS- zgt>FYQ_=Dkibo>Mc`JU2Fc+?PC&C=L;-d(2=ZdEy%&9B>iZIu%crC&lyyCkEbMuOq zqkYy<7tbzQxBN!p%_y3)VDV`bEn2X6Hi||qSo|AByA~{7j-qJ`7GFovx&@2JqiEoQ z#qUwHalzvKD4Mxo@qrXAU9k8=;-QD@-;a1jV&%u`-;el4;)AE^-;a1m;<|BlpT$oS z&wo_E3F0k@NiWy$mH15J;GWOg2ibQuPnZG!Q#4!-~Xi67K#HWb{jpc zjEfs5M)rNH;02bR6_1XsSX?^s%83KxPyIGl98|HmcjDQo|F1ZCV)&AEO>yxjcAhCMk@Q#wPoy|8(;VbuNc^dB}WSlk_P&0Y21pg28ZqkZeYadCabSyafXLE!^Ptr=J6K4cbMN> zyx(EoZ}EYL`M|{!9_9%be|VTbT)g73?8JIsAinW1-?(_l!#w2TEf4dSi_bjFXD*)e zFwgn*BR>iApO5_foG@p*xZE3axr;BoF<-iP)Eo1ti(kDlzq)wW8}qJ~iFaG(){PW_aZ_G`3;zcGiu zxc3`#?~9YaF(<#c`Wtigi^IP$hrhV}8*}@M^S?3Yzq9}vYXOJ@yfFv3xWOB9gNuv1 zF&DQux*KzJi@Uoqcegmb8*_S#>$@@6w>ZEXbAXE*yfHVpIKvxrhA%W>#l~FX;uvqt zF)r@$#@yrLByY?~E)Mg?9OmLSZ_I5j&hy5c=i)+d%!MwF^u`?N;!bbOoi0xG#+>T# z!}vUcH^%vDaj-W&kKlXpc?1uP&m;I@d>+9Y`{+97g5Tc~D;!nv(of8c z>%Uj=Ax~T%gRZQ(qdO;FAN!53Ii));xjq&?t>&7>-*tVgaQxJ={*FsbkBP@lDfo}t z=fg%_UGRTay&)dHx<2=+H*ScF-l+E6_q!Wo_OObl%)BYaJyf6js(6?_e`3Wm@0k(D z?OE|kn@o>;cdoz7JjYCra|U__(cdu_E?PO}twlq}e73)omZf=a(cCfrt$1-e=EX&$ z$9%bH_n1c)O&{O+ii5Xv@&E^~xOqF~<`pM!$DF|8@9mhsSG>L*^ZJVKw`0Cv@c?(s z11x^v&d&$kQ=ggfRF7SC|UJj3Fc?U-X$+_N2X&x${`v)BNCtaxQR=9LxS zY{z`F;-T%BhgSTw9rM$Q&$eSeTk+iXndcU*AM@@iH{NGHUbJ}3i;G5&`Et?jF^?{q zKIYd&>&LviXaJdy7i}Q(^r9JL{$8|%%&yJ6d{&~UoEqZ1wKkJx+-&l4`#9T)fyx1eB z#HM>6Q1A}hj*iuqt^VHOXN`(uezcCtuzdYcE#grbE`=B;G#yt7Uw~f*Z%Hzy3(T6OuuSK!NacKFqS;)iv_=Q z>V|RVfrAU)w7X%sk5 z;nCZ%{!M=SoipRj!B>?3cb;d*#a+sZl|fSeO_Gf<}Xf( z$8OZR`aAjluqpAtxJwG&c)n@V4Zi} z6BatQVEEqAbY@)VT^FrqF#PanK!f3pM;jUppS)|gq;uCrSDJC@-*wTO21^&Oiw-qd zdU;*+sln3e>!O7XmZn}8jcl;A_PXd*qJPb}H2b>fVuPjS*F`TI zERDY|I@(}q|8>#V21_fgi^ext8ftB=o%GJSH^!}HTsml7^t+iOeY7sR-eBpbb4uyp9U=%<6FPuE3P9W33tE_&-=>DhJBVFyd+u8Tf9So(L} z6aHTPG3nxU(Q{{9dU^fmyo2G=fBvfdBT;0+@f{ z`ZtM2z+qQZjCR1p@%3*QO@YezzOAo%D0#}$k=!Iyq|e8FfItbWZe z3RWIF<{HRjE4LiZEi307&N(X=9nM87M;*>lD|a2vT`Q*@&S@*x9nN(t2OiFWD>oj_ zjVou~<{p(-59igDZx83&m4^@K;dNgSzAw-{Liip*dHZnQUitiRK3{qMaGqcJ|8V|a z_X6R20o@mb?+ZSdJwAMop!O2T&~xIj_!KG zcRjiT3f}?gZYX>=q&uVVossU6!goo^)rWKS%HfA|_{!~vbNjk$XmiE7gJ^$8-37F{ zT-_10IbPizw7Fm1DYQ9Z-8HniV%GM(NX8PRJd73^?bGS)IS>^H=9``drp|oj$L1 zzNgQ3o%`u?U;aSaACRAr_7miXr2P>2Cu#pgenr}^kiU`kH{^$;{Sf&lY5zoiOWJRd zKa=)nrTsMdb!op& z{$ASOlOLG&1LYs4{X_YUX}?kaWZIvUpPBYE<#mUeEI)r|6g%IIxbMWkd7A=N2KEj#TV)LLUBhr?of=Aj&T(Gq+=h&FX{M2aZNg| zQM{9mcN7Pu;~>RH>G(+TR63qgoRyBV6n~}TFU4i)xJ>a{I$l#8myY8U-=*U_#eM0x zPw`+n9#ou|juRDorejaVlId7dF=jf(RP33KJr$FtV^YPc=~z{oFZui-HO`d|ORn8l zvGiGTgN-YeZcEPDzhddREzr;)aOcPCyzL|+9Um)ynkf1 zQ@T9);G|!bb)?sm`@dh`OFBL|`oM~%?~{Y)uUI-YIp>h-|4Y9n*I2mPDP5SHZ_VmU zOD`sG-LA$O(vit?4yf^k^ks7J5jCce?o9r8L|sREH2MFr_a4wz6zTpp86@YN(;*{> z2nQ+i7%(7W094FbFe`{k5Cud)P!RN5a`Tv@=ZB%5A4bpaLOr{S zp6P{prWZZy3-zoodIlKk8DR8mFx0cb=$T=tXNJ+U#8A%?qi2kvo-szx9z#8QjGjq` zdL|h?tBl?Yj<1cQXPBX$VMfn6Lp|q=o_~gV{uw<}4fRYlde$21S!?vXG}QCb=s9Yr z=cv*1)lkn@qvx)np1VfRV?#ZUjh-imdY&9TXHLI&96i?!^;|c4-W%$9Z}c2E)N|nI z`EaP`!_jl&P|uB{=gFa-Cr8hjLp^7XoFcyg(jk3Q2VTzXzSCY*PB z%P`-lIQIu%dRBNt^*G1>(dn|V(3f$JU(n~$@L0Q;m-fCSeD>=&ugBkdQP^`@%w0}z z6LuLJbCHVYhsn7yUwgv2;lRT2Z)cP~C;aHim=h=W3%lit@3SVa9uU@lAbtiucK3kr zyW8XY!6Tmx2rGAvpVikLH6VPvV;ukQwipmjz9GKPsy(@Xc<8bCUMx@c{$a!EvCQEU z284|U#de-BctBWU;xx1QPfra<$3xyjebRA~uVUY{A5UriRNB9JPkTD;_j?=lOUJ`W zKle+=N&fNu)A6&p>VR}y{diZj@9ucKeRB8F^u6}Bp z8NB*^9H0BwZw;=^AIInT#oL2n#p0M;bNjBK?JqH(Ic`sI_p;;n~uXzeeh`+d$|)|n2`+Fwd%J#b#L&Vb+?XPphf`OZ2sf^(mBmIUWP z>x>D`iPqT@(VAmQXHrCGYNYKPowX6_tc~bAi%{oTMCV+DI_Ki0&%O_J{zY^yMyPW! zZVSH;bzVkvjz*|+G@|o0LY=P>ox2h0+>Piwj!@@uMCWvbI;SH#za!N79nrZSq0aS) z&ie>;-bZxiNJ?jpL}!JhbXG`ohDb_hh(u?Lq;$4ObmmA(XO2W?k)(7MNpwa@N@tWr zXP2aOc1d*3LQ3Z>MCUK0bpAqgE<;M^GDK%Uq;v*EbT&jvXG28iIHYurLv+4FO6NO7 z=RTx#?n87QL`vsDMCU}LbWTKcend*=M?~jJq;#%CbPh#I=TJoFQ>1i0MRYDkN@rof zIwK=G&myJsETVHUQaa}%Iu|3Q^Dm-vF;d>S7%82XL4BR0fgGK$5uL}8(s>-wxgIH< z(-EEPk<$4c(YYS!_X{Z3c^}l*IUvZ<`5@@5vq)f_Q9`>qPXv8*&ItPJ{1Nomes#)q zUJ3PejtO#fzDaZ*N=oOUMCYWWbWX~FJUNolI}u^F=znJx%4R%&%#5tOo%bauKW%H1 z#LVVfj1T1Lop`bNLgVdq-c0b1I+XD@n7aH1Mh3EAWYY#rn^Ad7l}Gh6RX>trjGRcm zG4i8-#!Crq^z!r%$G*XQror zE3aRzy#BWG?0}pEy3wX*H`=vw+N96ap-s>JnVw%-`u@7BM&;zjhOe0KZVW0IADO%{ z>(Gdj#xGoTRpRX*^BLb&EQ5(jz8MR?dn^7Cak?*Q|p8n>$d*%2}_03kt<(Lg&`sB5X@1&3Uf;!lSHsDBh^zHw2 zzs#p9_w0c0GAYNFv;kvF{=t;-H<-G#0V9JpU~K98>zt}}EN;k&i;Grk)xSln+4%9M zp|z}h_n@z`UOQUJcyNwe5(h^VGd`#4gv8t>*^GPD_#_ei%S1+0mW=*p9Mw%mzcG$v zBqLcZsT0XIKf+P_lxL}&Hel-028C?*7vz4d6`H{A;tJh!Z%MQpfj@oSH*{xO7ZYzFE8GnoAOvsG%G)9K! zmzKZfyX~VYn;$Qovngv@hcd>MJ6xS;*`t8*#YM*?2G84{iLYA~S(%9b8AoM_=x@eR z-DLC|<48s_lGT#>k!_y}i}k5Sx%x}}Ov0;-j112&mIt+dnQ3u=pT)V?XV1K=`)5|3dws9W4Ts~H=r?z6=3}!jn$jn&va?7YaV{GGDp*C%8Z$T!H!PrUilsLq8}KH-Tf ziRXVl)`H)zOCHH8a`J48tBid|qxyxd&WSg7NX&S){%qJ@hXbk6;jD8fX3L^Z>#}pB-!@KAr$?dF5>tw0OVHMg0~2R& zeYj$RI+Z$2kA8cT)hU1Cfh@01i?et2iR)Z2IQnf*t25(3y)3V-mgk&5$?BB2sij}1 zrKfYtr^>%?br!bl8T~fhR!gt%ex2yIX`M4Y8)kZKWqN(j^nB6M(>eNW+J>2)A6t5T zkA9o>MWz=6Ej=4XzfJoz(~Fswo-d-`reh=1^J7#$9ZM~}7|8Tu=D%ITd)M}V-*ZLx zKHP`>yWMm7*M8nL;osNl(X}zx(f`iZ>iCZPGOmTVH-VWSxi^8ipWxmE=3a(-9GE_F z?*nsR!atZY{svQ*-@wQ~7L07#fN7Ka2bFVQq59l!z{ue~1V%nKg=v#}6PPx+H-TxB zID~1_@1s}FJ(ud+JZ86(5f->#oxIh83_f9)QPa_W2b`Ca$R z-nB<`-4$QkRQl$HKjnIfYl%qjR+0SZ`XtS?YuAk`=NbmzdgWH<_;2kRH0Dxv{YQOt z_O5x-*N2t9DP^*}`bo*rH6(R@%MOta>G~d{zg-8$?f%y_p;vBoj<=PdKgV@Q{`WfR zYt)3NkHxlEKW#U^j@Mt>O55;>SvOmK+ANuQgYlVzt0WG6cBS#V)kh^3@BN4I6SKA_ z>KtlpoSaZ18T~Vk%97FFh}Tw8-DLC|<48s_l4Tsp=ANr2b)q&YPr#JZ226e0kQ~~8 zkB-6TCv*$xg=% zw)FZ-ed~MFCUT6C}+RGbWCzfAbIHv-Z?ZM*obXGGfd)s+){{lZnhoMlzCR9LYA{Q69BPc><=K zHdLQBVC2vSjC}sVl<_y1y0if!16eS#X#>W0UU{ZhKe{(e%ds}7PoKPYtqsbfy4D7a zZ9M(Wc9dgFufNon9gx#Xa%cm_mi&V$qm5Wjc54GhMx?)$Bir{EOwRE?>hNFmLO&Rr zAQQ$`v<1^Y+Jmtxy203k_F(KpdocFnzx)ro(gsX9ZNSv04H!AJ0VAJ(FlGD=rY^sM zk)bw_O&gTUcQCqm_04ybqq`^Hd`EdyhRsb5Ht_T`-%&?4gR!O8U$Z;qQJdyF7&)HZ z%y*Pi#@}G{;Wse0R2#_lpHq3yul|0n7}<(ve*bRI75~n!zgB+v{(>1l$wQyXN6Hyz z$kXFv?B8=-WD|{(*aX{PBUob?j4c_}-4soF0a&2SJlX*_;-FHOs@y9%q zM~8oQujf5~{#|Pap8nA_%zxb<{c+F3|M|V!pYaSIzj(INy=UUjSc4coWQx0CZ+$m3 zdhg*t#VM}Y*81+8rDMa5Z%=kbgZi#Z?QvoBy*^jFM}2o*^ghJ!ZST0-Yt?rb_Z=Vh z9r}*zo~Y-pdHjv=$4lOEBV0ZA<*U)R2`j(j2E13-mHT2s_*u4h+`~2Mx=Wi*3{(5x zcB=-~aZR3^WaV}DXSm{fqi;|}^-JHB;m$vMvdPK2v9{~gXNt+s=v>?7iT1OrP$fYPs^aPB%TDyQY@gcVxQhe|Pg*uJV=dM&B}=;!dku%dL7a=1rHJ?D~HA z-?@3Nsc!0-C%YEg-VNJ5Fx3sLaI(Apv>9Qa&!@Vv8=JXPKbjG~c!=u^-oVQeXh<^&wXBPg6Y}4c0E^g{hOwLt;~AvjJMvjaby1J_1s4z-V7hRVv19F zM&&6^^)LKtvXh*?S(BaQpEqQ(Q@bB^ne3!bqbnvm=~?>R$^WJQnUmA~qFnu@zU+V; z*$4Tu8|})T=p#F$r|ggZ@(cO(*#$LR_EocNJe=IRhMV#2ESoO|l&;}EKYzB(Bd>j2 z-Oc)9w#_eFpQ!G_30XGp>?>K_EgO@t`KZK*YVOjxNt>r~6|Ls_We;us`u?%1?)}SC zHm_ZFdo7Drde>edZC#!Jd-OyrXuRkE9Rtl=Ni&lK#wV>KEneFZE>y zEc^K5>(d_-k;Pin5sJH=K;XW5=H*XERn2 z*u3`QD^=Y0H@$E3n*7DQcC2YtcS)`}R{!Q6Rb9spDU);d2UXnxV^!fO@YVN{w0@HI}&uZ?8!%5SB^z+r+)MZHAVDUzDrA)R!HQBl{px%K^-90}pwehgdOXXdS;>&El$aQadcj4X3Y#u4!BsxPk$8wuruGvt|HC(pb=AABG z%eht`uCV#&*&oZg_qVUKdFt^y%DMwJSKIt`=O<-c<8EtgUYmbL8CT?!wN_qvQfarh z`8um#pj>H}@yy32=jh;4uJe-hCci?-Qf}MsPpsVrZq>C&#GJNV89)3a~! zl5WkJ8%_V~_mpr)M{P8Jo%BTsH#vxTZLXT`#)6+&xtP2gcc6wVUH>ziFM6%2;ZA$% zGn+?-52@kGSNPoKmkljzxT@Pfw|QsJit4V>7hl+Xl>f5o?%iXXY@Rx@xSHG3dW+3p zyH2U*st^6r=Cw1%RCPJN-)iMA=dbFvUb5ZlKmAA*SAN_Mlk>=Tm0i27J5Bye(V5Nb zbADy*zLl@C+kW&b(`V1LN^Z}B-KJ-b`zpBwo%Yzg_QeI2+;=ngSih#WuH?q7+hcZ6 zIpd`2Gfqkl_)q?C;G_F=qdZ7zx+bKlz0DW{#x~H^o`V&>up}R=lN3ZmpSWgzNj#vlsj?g zdYeaDEGp%0I(NOzFDrj6Xvp{H+>x6XWd%brPi*qd1~U@rQPKxt+RQp z*#6S)x_%$oye5A!uRZc?8JEgfYxOsMT*fW#vBu=2DwK8Cf417>AL~%o-O^^YwVN1R z)}6LumFd$qS=J?QTV;B7*;v+nTWOW)U+%lIuIk>EHg3%RsjPc<^Gci7RL*>%`phGe z!~7!o%sXnA`AGUOPf1VaueAQryrzCpuKrSAc0kUO_)q?C;G_F=qdX%ugNdO z;i~8xwVO(Bw(;=wABwr5CvUd-;_;=$Tyn@}n@3)FrkH!N))t#z);BBWMt--&=AB)O zi@J%szO?x$@5M!3;}f>oJauq>5qHaZ+im{Z-n58&b>t44*WAd$?(ri#t^B3jg4 zUs?UW_ZM<6PTp;D9@<^dt@vh-$$z0sL3df-%nau#&g=l$07+4Xh-ckAkJP0wHM zD&Wq%{(7fH0as~r%ola8;MO#b&V-NpD<ectzJoRABa?x23 zKiT|s!_czsx%c+lyp}vt#@$=;pp}=rxr}Rf{~@cNeQjyif8k-1^TYY2-3NJ&n*8D` zO1Xbz{A}&kxUrOLU-g*jb92E`uH)`wre}|3CEdwS{9^OkRpU##Yd8F2{i^p;NmumH zFJ=doGybSPC*>DEKJl0Q%X}ffGmj`9m|qkp%sYx7<|D-w^OWL^`Ac!gyr%f1TyaZ%#WQjg z=g3$5)2{LYeUvZgsXRh|<(JHdLg&=jy*QNoPTj4cX94LHt*zqvXHCOZ+Cp3HMfv!c;G9Wr)uUc?B-wb zmCb9 zedZC#VSbT(<{h=md?bCCr=%zIS6csQUQ@p)SAVH5J0R!m_)q?C;G_F=qdX% zugNdO;RPK}a2IFpv+=OvMJKrI9roFLaj@12uHKA&Hjfn9k}RY0%ko?<_nKoSXYbj$+^hMrrO2-$i*vdyFJ()SUsbQo>252PJw<-qkT<8h zvwQXw`PFS<4)@9Y>?!i=^4D^>yMM@@qF))&IRp!`=P+KFRosoK``?+o8}W8=ceq84 z6ywi>eT%!nx8z7MELgkJW#)VPV(f!MrBt z?s0`&*;4sT{=hngT&MB*tld#zLHA{~6HK2?w-j{SpE|+x++Vw(Yq$D@6#B3ErGVRU z>;&uMxE~6*(+lS}JE$D{s6KX+9PBCi*jeo|zDXa(J?Y7KDE%2H)i27`U+T*a$dP@J zFT2sM?1?_IGkVJY_)&iGE3qw?-Q&0q7+%;jno$d+P#?WXgi^CWU+OR>II7T;%8%&KW6jPtJmjt&AR_=^IGmnxt&{i z)aEt$i+Sy?GxNBSU5;4&wa?^nZ_Ybxa;C4!<4&t_*yR6EIIlZ<=pk!&^4WP^rBa7X zpR@1D>qbmDX!F_)L-M+1HyyNjt$0WU z-AA7uvHt$BI=j1d$q}=|sO{O^OCyh%eUiCzxMi0fF}q#bB!@fq>)4)!Zq4DUb&c(O z(fAy$_7{iD{tb5LaH-aZ%wNM!%IOvjJ!t+q_lcbD;V%zZ`H>|#T}Jf%9@bB9D4EMO zd3wM3>x>S$+~OTSnZJ4t&*fHJ{*$$PYBcw~`N=-hXYIjUuEzcQOwYY#bGs|+>@)pe zX^`9XJN%>htJO)lU4=bAn!i+z9aJCtNDg+BeC(-qv9t8S{?Ze_r1g*drG8Pa{!(9d zK#uH#eA$h5Wl!{xozYYF$6xY`?=Sf8Tss*4m2yq~!grtEli%GubEn1aBM;|y2jAFf z@m%AX{H|`dofhY3Ov>-BX%s!9j`ks}|2V(-M!56mYW=+bxf# z4=&&?DZkzFtK6prT!*gPEbo@rEa>vh*=psz?kVVI7v5_1cV!iHb8r08@^0a=g0ADd zEhaxt>q4$`(=FES-1`c-7Vm8~eLB2a$j!K9v+4Ozs*u~2YqRNJZA~FpZv7_9yAM7o z9c?q@)}1%1SHGQ@WHpf6of5e|P6n?y}QYSl(SUu9Vv|db!CT_+=@# zxA1an_q?*D-Qwq#nLeA&D(%i`u*~#4dShwVZOc;A|ILR>yNT~EwY)p`@zSpKxTThN zDkq**pE#Es;$QN~3$<(W)Ny^tBk4(grS*^UPW_@>{iVL_fE?Ke`LY}B%AV*WJEN!U zPu|HdzQ5qV*8)~q-u-3P0*+ECHmyEd@=s#UX+d$dkq zdG~48O0M1`Nh=?itmHmjn6Uak=Bn(rRZLjktv$c8>(L|2)`l_<~INxm3v-b&A+zF}ZyTZ|ZO~Xo6T&p3oEbo@rsNz=ioMm~Za^hL_iF3&z z{w1HhP`fry9oL6ElAh#OTK_2T)Gx}_U+T*a$dP@JFT2sM?1?_IGkVJYT{D~I- zw=b;ep1F3SdULBd*N z?UL=^wDRKD*LHV|d&BB?n^@aDcxb%I>F`}`SE$2ylmAk~=-q)u z%wFZ=d&`>@o9T8A%;!qyES!Rm{Is*R_{_I1a2FKp9a7$*OmpMto3-isum|RA%Khsiu4nWv zFzcs!&y;m!y?@I3vffK&-C6IevL3DXSXrmm`>m{B>%CXjwe>zM>)m=!mU6v6OMSgp ziyXagi+sI@OS^hM7k%{JE_&*HUi8;{zVz!q_5I(!_embJeL;VfeUjP>M0{$W3303a zC&aV%r4Z-ZuR{E59}9V*{Vn8+_Pvlt+7I*h{-1b%)bHK@qjyO0m)=jrUwUs5f9ZWj z{H6CC@t59z#9w+Z5`XD^N&KbvDDjuxucTb>T~c4~W18Rpes9$F2g?5JUy@%K=l^~m zYPXGte}(sh<~j@x&KT?T)Fh_@U0T7g6X}Qh4A=&%YtUbnunJj+Z_IU;S%G| z%X|{vebZdyBEwdOTW)^OxW=ms!!L%9HEwj`!tlGMZLOyg6}y&xFBd8~1d!cBua1`IKN_sM3#!M)v#A02*a zP^0^0#;cn@8BAT-$T*xiDR?GlA>-R?ei85w`IPZDn7aH1Mh3EAWYY#ro3st13p&B* zh_3K&^&J~v3+&mXT(97R@-vNVUD-CsHf^l&Yv;8H9_=y2_?bjz(4ky+<8d!v89cxJ zGUJ!>JslK!w6XCUXH5=1{;H7itsOQ8{6juv{0*iqzk!i~EEw6e0n;XJ!{~xeFgl_u z+^2EPlpha1D>kSj=D)-ZHlZ$z9N!N39N$w;ED#egF+!}semoFg#2GS)JK_%}9*Il1 z>)wW`=-H&{Ja}Ntl-IniVJfrmVDnM7qYY9&PkhDrjy4TakMw-gcy6cqsZmX*8(-Y4 zUaD1>r11$~)JgT+6UTYS8#7W3?pYMqUs)^FcJ)$Yzwf@SdM;_0I{eaL(`Q46hN*Lc zk;Y$*X}~#O#%E8cpK9K0hHZRJQ35^dGshfIabeto7`evlEbzW-a<+jvHHQBbp z7(3G*ef%w(V}I&kPwW$&6K}u$En8tX>L3$a^8dyB206Y=bU`P|(Ggu?bf*t6eWGtL zeWlMZHoz7zw!ua)Hp6zX-$(2{H?lkW;0OEx;~)G4<2U>V<4^nw<7fO0&Fk}ZHKxsl7rt&x zn^Rw3ZA_bAzVquBFa;(-^xh%U?W6Id*;J$hF4U zH9B|97`qO=X1OtT?fg?Vivj%X``2grnmXdh@Af@a+2^0xiaN3z|5bcOXAX^19QrcR zMZQKy#Q?f1Ht3ULhQ2D6uz_L>+bH(1nPSrKBlecB@q=Oj|0p)_n_>okDwgoGVhsN) z_J|9`B=(^H*oVHu#6z764`i*WINA76>oXJe8a-?L^an2|W)HsFxYOZXi9R!G8uMTN zKfmSg)PwmQzlV{BT-dicEWdPUyJYr9-%m1qzFn{=tKe7tj4R~ooOr85TjQcxa}(j4 zC5`zn{~!JNJN00G$M0d}As6<2`dfYXW8mOp?ZQG`%LZdBl?m5uYZspKaOI%-pi<$j z*M1ee{Mj_)Gx`+^uU_XZ90VO`VBL# z_e#fb#oJ?y4~^&)o_fPHXjgJEM$oy#wvTAw4P>_pJI#F#M7J z#*bY-Dj0Fr)7E$2r+!>bJ8f7X|H86^ZxcTTeEFNpy%apNyRWtN+~gO6`@ZgF{OGsC zg0f8>HLkpUXfV9=ea07!7#g(x@HXRv1&0M~x_37A_55ti%R!McPnyoV9(gI~_Eb;f zk9NHnJln3D@s1-e1aq3)Yus%13&Funw;4ZL<;CEuVb>WK*w;7MSTLXQolo}(W?Yoh zcwygO!7pzeu~>Tc&=bM;gTFJL{mo;+$kAUKAN{FEP`JrDh*eE<4>@%z$j zYQLcHFQwubcxPa+|ADH;%|0F+)c&Quah|e6g9#m57;m_FSg`E0bBwFZ9u|CXV>@Ht z*R66t6Xg6f&i#km3=U2zT*>_Y!#hKRoA0b^oWI-)!KMk#jb}doVz8py*~S|`elaLG zsGTwQ6BF9^H?BG^dPj6^KjZ6K?+hoki*suJ*W1HYU&OKcbg(U)KA@M?+4&x)fPj9jEMO(LouZ-~EK3>$w z82R7)qn0u4epf8+Bl=9gy|k61=g+-jJD~reo`tQPe&u*P9w#gH+mkN;{M)b7^}C(+ zZCcLEuHU8QU-8i1bi3EI`973B?RR~j*7Je$qI0W{>%aE4AJYAzT>YiK?0_8E2l=ua z?aH3$BRiv~?2rEPi|;S^?fVB>Z1{XnuU%oG9nV;K;X^yZC(amPytUuGI99aEmau%*)mHx2kn>`-q(ev_g1*{zXTXf22Ouvqt7LNnV zChkd>H$Lf`bo~xvzfH@jxc9qo!EyPWihQ4Lx6{GzL+NwExF164*`UymY5ku+@yB$( zC|7@}FFPPd_CdbvX6+ugC;G_F=qdZ7zx?uKp&}{eUElVFQ}S=EF@;j{`}%_gQ;LVI z>k6h6C%1oIAf@=(eqVu<;_8l?1yYK)4*T+_6o>V;<&T~@#Cb=#;+Fc#JLD+Nk*~a? zUF9A6DDTiyd58YWJNl)(>$9Lpx_n!=qUrigs~1blX`3jPmj7Do;^}s4PAHz%XY~H! zX+5XZE|J!MQ}Yt(eo?OeQeSpJj_iYc*^PE(PxO(U(Np$EfBD7t7p%PVx#3xbQ}XZ8 z#|x$8_niw0rW6l-s}@Wt?{*9+kW&2IQn5fvaW!~B{*>bF=jZaL6o=>cjQvR7QLenB zzTz1iEp}+Euekt!Zt}l`XQeOLmo&zd7yU51L;E^ zNKf)W`ZI2+UzDrA)R!HQBl{pKEneFZE>y zO-sb7?@r53bl7#2UWA}Cg(aH{jHhT-)CRtCAwE}Y8qOT%!~&XvLHhYF|0H*6HXo^Mrf z&r5|<8Lm-epH;#6iNevhWE$Bz!Y#YL4v|UuLrZr@-@IuQuK9UoFuvZNa88RxVXyaA z2HA&1-^DE1C_KN#%3%1uJ>ijc4a2Grtq4xJ=Ie0B0}aFH=PeJ;8vk|pT7`yTzj3Kx z-qgCL=evDU!8t$FO-(ziVc5TXD!8gqy;Qr&4Z|Zn!eIW5^->QXY#3hsdJr@nUN5!0 zUZZgD56NK9%xJx*b))e8I>}(mNA=Qr@|+w!@5#3;c=3%|#;={fIJmQ9hH<~e^Mh>n z)G?+n)Tb}cowPFOKCYJW#V;)jN)*d5-q?0gQ04AA#!DZZ8?1_Srar%&b6pW*>~Q6f zA}QG+_q-x0*`e)E(RI~vJG@r6Xi9c?00#vr;pZd=nKz*M^+tf_UBpg z&Vl{R{*(_tWoNql>Goe)`RQS!Sy%nE%lz`xC8y3lI(V1)<=xI3XWvqPm-%J%{EM>| z%-v~zxiRIo{;!KPsIr`6_b=JuF!M(fWl@s^vrctVY3^0X4NWec0c!CBA46n-hAd8I72>hNBqIW zBXJ2+Uwt7ih!5ltFT@Q@91%}2@kN}$_*}nb?2#Q9dt?X39@&AhM|NQBksXLZ>Fn#{ z_XTFWqg|M>3H`AlsUGN!}yQ96@n%!|Z7dB(g*Op<5J zi^L>(#=J;Ol4s0|#6LFwXLj)IL#(PT#!j`x*r~P{JJl9rr`lrdR9nQk+9IbUle|zl zV<&SD@z2=F98CN(b}|PO|BRi?!NfmfCv!0I&-IUq|ICbbU^HDyKcw=Q3J0L^gN1oXpcIyuX6NKee{(a`XTxBPwmog>4QC_Cw7wl*iZeUT>YiK?0_8E2l=ua z|CK%YyX?&GWPjwzFTTHEJ&*F4>szibb=}MLCCv4(U0+7bbu!nNlym*e^(D-8HP@Fg z*XLYc!d#zoeF<}YPJ1e+J=Nzr8%7T8!N{jQ*xHT$Kg{3lejs9gr{__~)AK0Wp*`x; zzRJ-{_0d;y=m+gtyHWqtF8!81*h6|^C+UwZ)i27`U+T*a$dP@ppX_Gs9=9idm!0{Y z?2kP8g>_5T1&L4AGg)^;XV$}6zl3d#I$Eoyj$h9DIqT@uVO^c|b(r;b*4<&&;aQJ| zS)XT}9%kL1^?R80eAe}0*7;fQhuKHKJ^ehjn$<*J0M%S$Bt7hi5$= zW__M@dYE;4*6(4~^I6x2S?6cHA7*a?`v73pIaybOS^s1m6lPtN^--AhQr1mj)=^nc zg;`%^ofZBqJF_;+8XkRQ&6c%Wn6+HibYa$bS?h&a`(+InW=)v2VVM0F?8AWBm%$o5 z?XsVOeHAeKEZA=W`+fB7%pQ$fqrDo)VebZeIAGRzS^wj=tdX+5NV%^+>x8TqQqKAz z>xeMximWfftT(dm2(u3PShOAqvp&f>CG6Xrbwbt)X_xgw))8UW6=9tE0L~UbP1I*qB_CUbwiC}L8%w7rhOu+0NV6On| z`@R`YZ^FJ4n0+YhM}gU&!afz4eJku=f!WW(z808$F6?)K*&ji_#H`c9tlP7G z53`=nx<1T0KkNN4>;LQnfY}$o{s5T$0_+=r*+;;B0+{^;>@$GbcfkGws~_!0U|#~v zJ_YtGz~4vv7ud%Dv#){u4KVv1*!KYcR*v8=`hve$w`ctxW<8&EeVBEA*85@B|Jers zvoC=C0WkXo*f#*PkAVFIF#8MGX8^PBfc*zB`w`fe0JBel{R%Mq7ud%Dv#){u4KVv1 z*!KYYG3NWl?+fMfk@olUTkQ?TCfXZpe0{t(7}nlknCnM9&*!>Q&xEy47@6893~Qe- z%x}3iMGn7(Dfi|0@_jwEFP-|@mkw)RI;?%^u=b_H+LsP%UplOP>9F>t!`hb)YhOC7 zed)0FrNi2n4r^aJtbOUQZ)fdA#}3+y4r?zuti9;4_M*euiw3 z7F_Xi%#G(P4PH7N^L6W&1P`_Q+G3#R?8QOP(J?=9$D-i*O)-z!zaaRgXe__>tse#r zn#SzM($MYE^S8_6b+qTNUKvc<7<0ECD}r_%hTORW-(SGKOPWr~;@X7K^ zf>)o8xoML{!N5f^zgS~I&}LuE#5jG!k1%ax2fbSX>)i@i?^eLR-TZjaI~~Z>I~}mz z>3}I#<9bJDio>c0E zV0w`sjR)K?I#^LEUZZ?)!^9wSNW3mtt--9|{r<5Zf6J$retM7TfIfZ8-XA<&?U?zi z>4I)S{m%{?_v+9)SpVSx<9Unv2Y2t=XWZcE&|v$c@%mcd>7#=Acki|G&7{G@A*;)6n*wDAR?+fhHcSIhu4|>Ar>Feyl9VYh40hpX1H(+vw zoPo(9atS84$T66lBlqCweX*c=`FIVhTE91fPqM|l_rp;^>b-aktNNf9g37I89#?fx zF!lL(-KzDhr-MEVCLKRvi(86TeXNH8ps*Z8-5fez6wx; z|H87fZ*xBe$PeiZOO7wo?-%17&x~k`yoBkm-`4Wzx!tPXu^(68zaS{}T+9PFtJID!o)1G3lq!4G)#;W>oBoT4#4=zd=s(n3-XD) z!sg@|`394J7#%Y)R(o;G z#NLXXF%y%|AC8&)pl{ev&swn$@kQG(aYx%Q@krY+aZ1}T@k`q(i3zMVR7bbVHFHBBjUzl9SzA$kl|HAUG?`uB>h%ebk z&%@E*x0P>0#-}HHl}XPv4_;T=n4D;QUMXX8;^Z?*8j}-GT^8>ZAtyRK74HclC-!WL z3IZhFWSPcF!mw7i>K9=WcV#J?YWUB!HdoniX! z+uV-(ptu&PwyAhT~X7x*|Ofj#%VQ--+%eBVCG}hjh7@I39f8e&G@(a(zV{Z!MdJx ztY05JGa)$KIOggPyc%qom|^AhYP=A9w6C`D+O-3NcEw|UGtoDCu2sv*`{(KzoVBTj zas5dT2d|E-Zv6O=`+}d(t7h!mhnUh_L#$~IA_g@#5u2K`h*`~L#Ioi%Vq9|{v9CFi zoY1ud_LncnC(SkFndTt!PjeG_sX2>$)m%m%YmOtoHTRMCniFXkTjO`_-+;f{G&@*3 zq@LNqxA}m1GlJ8fjcwlhA2WkPV`6@N!mOZ6D(3Q=X9pi|iTR>!S;5H#>YAL~lM}(s zEn|M?lw?r#&X^y1EE(h(9rL{rzp*yvQBj>|^2R#sc_$J4qh-wXBAE}}8nYjhdES37 zc&t$zpH0G9!QAs>t~EF-Xx266L(!V&l2I{V`9u)3{3zzR{lXwyvAPy}TU)1suI*x; zIU*Izelg}L5%1p^^UA2sX;tf4{V~yRCtn|P-ALyBuf|ON$)~XF?AzS;JMSs;jw<%o zJImyz?~AodrUX+*)Hi!R-+g@WNY@6&r#F8&xT9c0;|JOd3NF4YX5XjtrcVnN?y7I{ zd+&QAcz9t0<6lmBCD?aI+-~U=gM#%dV)peXC&&%-Ay>#5m>eRPU~-EbgULB^4<;AM zN!W5U%2k-$C5K^hnmB`fTQMFmE?^VJ3C0VU@q=*$W?W%>ff;WYcVNaL#v_>ViE#>M z++zHK8PA9z`1zG**?Yw3z#7z-&o@lnHKkOTy7KCDx$hU>UwRi9IeJ$YIph%jgSF;P z9b$x7fr%Yr2qvb8Etps%=3ruwScHj9ViYE3iCvgjCZ=IxoLGm6eR2RMC&&$$Tp?#* z-wwVn$TRW{{mDP_5GF6lPndiqZ(;J7e1^$y@*F1b$$yyffN=q4oM60w89x|DV8#{3 z7nt#eaR=5OA#`3ds%27RlyCDphU84g|M&;jCzTiNZrbxTNx>ao+or$|FB!uG?@*u(4yDcjJaP2>P86^A#Pd2YX(Q^K{qU<${xo z$6U5#@u2Q!v;tHy+bgZp{~bo;&7zm*x$Yoe__Rmwuc#xUfe&u71=te^4+P z&v$p`FA|K*d3^4BvQ%(Zr+B{W^iHKcXJ zq;>99XJEQ7weB34?&I7s&!qcaeNF$gO-7yYblO($UEL>b!=uX{OWStJ;QP}y|M9}x z(!TKX*UxLXeam>PV;@1yx-qlApyZ)=Y-HcTh>0{w^8 z9UqJtJvY^k8U0u6kFT%j*XSKFvu{D=>}ODY_Blun`yV8qeGqDweGt-zeGt-D|E_4K{T?m^|#_bjE}D3ZRHDO4s$`W~lJ*KJAN`|Mi(ep2^DPo4jA zQuj)~6&u+vZk)bf`{>1n>3fij9(B_9CZ|=dn!abrHN9l|Ugn)A@}%!^j(xBvse7MF zk1t5-p6H4yuO@Y`M80az(z*-lq;lZ)N=LPc>8b^g7YFQ-@lqZ-1&~{QCMx{>v4Oo8DbJb<&KI#%oGt zq~>)mY#c7jNWE1dzwwfR(KW-&yv76D)=iDMI_B=h>!qG8dV-Z#SY9u6=);1>^&YLC zDt1G0<7AlzsdIyJ#y7s&Ak}4bb>qtlG)$enw1M#>of@W2-G7Slui_{DJ}Kj(_K7iG zYX2DHsP>gHzG}Z2>x_Lc<=X#7eeH`wj`qtTU;F52 zSNrSGNBi#3Q~UAIU;Ffk6Xq@2Vq8}_BG1#JsH=fKl8Bq zMY;M*ec1syvJdiQH`l&s?wZGMTU8h{bRHygv zH7=diAa%6UqsCX9*&vnmQ@m$j;jH?pPe#V~KJzQqPbCJ%`*{jKSTEJ^-8iRa%&(jJ zJV$&_^jqT+^A7U_V}Ir;t~+7oFRn*n<~6QUVdguoUtxcoq+g7g$Yh@4+81X2 z;+hy{UgKIBX1?PZ8jkFferCuR#r-Pf{&+4>==3|)onRyy!-e&%Wna`QmVdi<}dzks3 z>j0SR0=vpSJXTnt)y^+-O)t${3C-vMlTEk81d2Ie2In&Q+*Uv7RettW@u z-MNdar=RzBcr+u>bKu|dH9GJt41Fqgn2^--)!aRnC-vO5cKf|aJ&!&0tGwywwAp)= zNiSttFxx7?V9>F2@{)E`((%o?Vlkhw6BJo(0&_oLi=!jt1pa~=sKj8pV=#Fi*;m}z7t>aHF2jHARZMP#HnJ2_*Ev$~tG7L$)V{k%=g&=QKiHT}j zL#5LD`VM!mn%?iXeMjx|KEU7V%g+nvC$uMXUX_cI+FzHkazs-5?uI@O>+=2sJV&Q)SN}kYAz#| zHOCR-n)`@-&57iMt|hR)d_g{Gt|8Af2a$i8o5)MeS>&tcGV)k+9Qm!ekG$8MNW0h? zzcYTYhYx04fr%gA<|i$hn9x4exvQQ_X#eUtwH{1pUu(wAZ4%n=TBd(SLi=FP9-Kd+ z{jpUB?9S4@*?GNJWobXHA7jn4k4|Wx>L(ZXNNE4+Yc)?xXkY6kC+ACOzw6+F)3dY> z_PgP2va~<8O{rP4wQu%lr`fZ#pO*ZP&0*QWw~6l;?8CdhvJZ@Xd|UZ8^yRa^j@Y6; z`|gN2nEiOfBFsKLViYE3iCvgjCZ=IxoLGm6eR2RMC-4*O_l5m+j~ zvx$jiVy<^^T;kgw@tQW40 zx$dECiMoel{ogs`93q#90dk8RgULB^4<;AMNthfZS7CCO z9EQnhavLVs$$2>I+AYaTFZ_KyJvrsA4aTRp{31DX*=NRIrB)|r zuKU8cZT9z*MP_a`&eij+6NtIDQB-`HmiSfF}zE3{*{s!Z`r|eE%oa^(LfBr1_T!T%Q*T(`-}o*^vTw&XOb1_o-?rop`Gd{LC;E@yi96yCCLW1Pm^dX~Vd9rK zhKXz98z$a~dzd^RA7Ju>Jc0eb_gKVDf`Jfyo>42PU7$E8{57$Tyh$BM)KnlKh0pS7Hk$PNQpJW9$s0 zn{RX97sM$(pbqhit$!`k?<4Z~J#}E^h~JjJTaHY9w;a}Y%VB-D9M*Ts;n~N(TMp~H z<*>e64*PwKuE*_L<>(V#r`xy6;pqC^zEuuK*Y)JDanV3d@Vw_lqf6JbJTfPpzu8%MDO?Cc; z4u7^yXp^>RS8c(vKP>yhvOg^Q!?Hgt`@^z7%orQBW#6(8(?|cEg+KfK7qw;I@%ZVR z@W*@$?3*6zmVXmYKDN-f_t0;`O&`VI{kY+rZ^93rSZd{e)HgA>$Cn+%*n#I5|Ehhq zY70Beik_w1aq)-N$IEv`-&E-q+u@QWMN^;jj_uHIOwrVNonkxuQQslaUU75~V+ZcR zu@C%b?^jn_d|&1Fe22vUwn@)!h0?Z4v@Mjj;k!)>rES|TdZr

-iOS5Yu=6xzL~e z3{7oehd=5&Jj6`Xf@SO*LBvvn^6iX?vD?S>HzxLey6kOZJ%>RDF?R5uZ~WQMg47ni zz(>*z-$`eDs=nZB_3@ATW|Zz1&_RqH{Oi>}`<{iim>clL@A*EJ|II7L(p--fH(xWx zp7-gw#*DqwFX?5xB^r}&p7ffr-UG!BV(h@!fPV0w{l2Z*!VbUZJAu4wf-UF^^9i08bVCE%k0iy%?fDU5%ZtrItfByVuzmKN2(1&r0+<=)Y$PJjeg4}?aE65F) zzLOj9@A;M^Ixs#WN33{Y{DS}N_o}czZ7Cl9i0>t0E5=Itg$)@iVQkA-31f4{N|?Nq z4qU^k?~!il^-!Ld|CwurY72cBBc&T-q;zJCR9_e))km(u|A=n}q66bKI*8-E_^)+6 zp7H;gYhL(5x%qp(1Bp$PBiKs0gAJ8a*jBlQ&6R`bz<5YZim}7L^4YA~!WWF+8oL4xuq&$k5qZx~Lyt!}E$E%EmZ zi`R(uE6$G|i$pfb{$-ui(fNUKw>RsgHbm#-QGWV^by9CG%QF5v+S6EK&n)A9(H@fE zllP4MJwIY}_V<4LyX{kwZuF79+`Rr$`%Wf(oO1RV#`L{Ji>Aidql@VL78gmh-V{BTkNUN2*%^tW&&OPC z=_859JH|X_{)j~JCNa}j^gsvynY{lD`OjVpP+RDXUg!s-FM7lDgZ{wukAA{`)OVG2 z4qbz_jniil!a9o()>(wG&LV_$79p&&2w|N?2n*140g&U}P*<|C{#A7P#O2pVVK=kdWhj}O+lZ?Mj2gLOt5tTWnRozVvCj5b(jw81)~4c57S zu+H^^b*>+*bNyhxpU1g=u+H^^`Q9Gi-Ggs&ur=la1q*ALdYelXvn zoRSTbSBge4R9W&RcOR5|P02UcHTjXAK!99UxxtT6}Hm;-Cf zfi>p98gpQcIk3hYSYr;XF$dO|1N(EO`hs6nP92s1y1vf&rT$-iZuQ4lzwhcJeODi0 zT|dCOet>oT0PFez*7XCd>jzlZ53sHuU|m1Jx_*Fl{Q&Fw0oL^ctm_9@-`B-Q`j#@R zZz;q2mNKkw@WT2AFRX9y!ukd;tZ(qb`UWqoZ}7tU1~05{@WT2AFRX9y!ukd;tZ(qb z`UWqoZ}7tU1~05{y^4ulSl{4<^$lKF-{6HSAO8j~tZ(qb`UWqoZ}7tU1~05{@LK)j z-{6Jy4PIE^;Dz-KURdAYh4l?ySl^L`^&M$g-;sv(9cftKk%sjhX;|Nph7TV91~{y5 zfW!I*IIM4g!}?IjrxQ!}^{%tnZn_`kp!L$MAnz zd@|Pfc?zqKuyPPq4#LVoSUCtQ2VvzPtQ>@ugRpWCRu00-L0CBmD+giaAgmmO^<8Cr z_s{ZCb<}si{$DXqm9y#>V-Bpoz#4O4jXAK!99UxxtT6}Hm;-Cffi>n>{XgKl-}uY# zi^d=1Yy5#V{=gc4V2wYp#vfSY4=kCqC7G~f!jcI~CM=n-WWv78KWco_Sm)~uOFpde z6V~_%Yy5;Ye!~8kDf#HHa_Xr3*Y*GGG1k8Z5c@j7(gD^u4{MxcFZ4`)6$RzF=f{>c~^i0a?(!Nb(YTqWTeVefMZNl2O32Wb`@$r3|u=Z`j+P4X7-zMzq{C}l`^ub5c2bMmt zYy!(BuxtX$Ca`Q`{6E;s>ibmsU>}tuN9C}}e_hAlKlxjGHL0U#u>X^I`#t+ov?m8W z{XIXwXYUZdK!6j?-0RyhX~d?M6li=g7pp&tapfDy+Z`+eHmEqp1^wd1lGGJ zu--j^_3jC*cTZrwdjjj-6Ikz_zl+BLzJUPidj+uGorm@A zJgj%;VZA#K>)m-+@6N+|cOKTe^RV8XhuM3jeAGTw%Kx|fJbnBBD{Upa5lhkmmJYD| z11wfU$FcI`#zEm*iGfsQTeay|Eqnf_gH=1qyxGsu3*I#thj;|SFqv= zR$Re~E7*^ve->k^Bi;V&y)MKC`y22P=bZk(&I9$&67~1S(--zBBIkd*$DZHv9b1ncFR=Uq`@WD4*iGfsQTeay|JlCtb42Xx080m0@dGPm$ zv$q(V{BPg6;5t*e$-RK&aBah0b7ZoI@qhDv5Z5Z4x596^hT*&wm}?u(TYSOTJZ3eXcqAhB?f&DBm`Rxklxi=P=i< z8bi3I)!4$duErc}rM&a)_Rq@ki^^f&p8rbw$X31%uylasBUnCyV z*!PQcz|JbCj>>;s|6lD#eJ9`7O*){PVhL6(!HOkVu>>oYV8s%wSb~4gdk}gD1bh1L z6p+Wn9OeJpcN4IIeoMTgD{{yK`T&z3^bIC&=rc?{VGEc%!$vUqhwWhU5}U&0E4CIB z2e8glgLR%7tn<`hou>xtJT+M7slhr=4c2*Tu-`}DR{tM+Zvw7k_4fTY6QXERG?>SV z%v^V&B2?I$Y_p6hks-6aH}-_gLrIZ@W);QW_q7R0#v(MBGmA>nAobp#bM5c-yBpa&w&vUK&y6&xZ{GxVP?I!1Mwh8tL>j29yu>1nc zFR=Uq%P+9}0?RM3`~u?_`Qp!fq(0Iu-2bokU3krlr4Ks8(gD``fwg{MtshwH2iE$5 zwSHi&ADF$S_cdVZUDigQ+#8~tz2Q0ce;j@6>e9y4%hb)Zho9s9tDhOx-&J8;{aqDU ze^&+8-&KM2cU55hT@_e=R|VGJRe|w4wU?OM3uY}*x52D2>N%LTN1X?=CaM2m)+%)& z%o?U%gjw6vkuYnX`VwY8QWL}MQ}O@pdqZLS|J}C2ZmcEg080m0{(|K%SpI_LFIfJ9 zk8Jog0-$-tt(jT3f8)UwXWdsT9OXo zHAWw`!`!$1cb}2g^Wn%x4tMmheh&oZyCA+3g87b!?}}jk)(WiOv4QnFHn4uj2G;M` z!1^5vwEm{f-T+-?4%DK7sEQc&=NF9i%h-?|#EXeUS6-<`uR>c#h%Es{Q_og~IY@fe-zN&eo18YD!z_K|ko5Qj>EStl!IV_vQ zvN?>+W#>P$zxqhGaDV-7CpP@6{URSppP*j-i+?*bypN;<^Hn?gs2%>R-%HYaUg&Vu z+{KxyMX#-!kf|E=_U;#Es&-}XtEPoj>!QDEt^eD1oSCma%RW*q$No}{$G%hT$9_~z z$UarA$o^Fg$@)=k$+}X_$$C?r1FJ^W-{Zgz`gvpZQ3Aq+7WE zU+uf_9uZ3))x*+(cC8;+>j&2Qfwg{MtshwH2iE$5W4{>{-P+@nKcRV9pTA|%zoBFP z#zp**@2#D`ebKJ5WBw*a%cs7xcK%kzd%eFk=5J^WzU!nhe_LbM$=Gi-#$@t0H;Seo zH;(-_Y&7QAp#7G4M}qzxy~D=HS^dpHW8|kr4;VA<;U!-iqtBkb`;F1_Xnn`%zxL~W z*3P^hUFDd+#i4fo7Ki%tw>Tt+zr`W>{4EZR%irRVKKv~X>B-;XkpBEF4$X^p&6obN z19D^^jIn<9O+Zb)zf)aQ3fXu6DHC^NydY zR5jY>I>#Sfen+%x-xFq^2fivFZTznD(S$W+qC59EAEkUOEA!NI&}*L>+OJ0M5) zLB8z9xUwhu$j;~~`=h`7^3VQqd-FeOe<>cyci}h*D^9|Sld$3>tT+iPPQr?lu;L`F zI0-9Gs+~Ba{=^?xaS~RXgcT=Y#YtFk5>}jqnImx$R-A+tCt<}&Sbl^RCt<}&SaA|o zoP-r8)lQsLf8r#pI0-9G!itly;v}p%2`f&*%xh1zLfOh|Z+^CNn``;24sA34M^^J>+{F?m7lkZRAdEfvTZ1rm=5Gzc_=~?a2;(pQ)*y_(V&~zYoxiQ9 z{`}2F7&-hcMi}}0jYgPp`P+>!`tUa$Vf5s0J;L~lzX1s|Fa9HDNDg+B zeC(-lv9t8SU(yqQNq_vMdC{)<(qDE!j_iYc*^O~!PxO(U(Np$EfBA)Zm3qV3nY{4Z zT*u^#^`jk=M-t;4lV6^>(lL3bXtwhU`DkK$$K}jq z6(?cENtikQ|M735bALu$CjN8YB`(99cZtg|_i)5znEN^6GR(al>lNlckGKqT&qrK_ zx&I?B!<=`qquQ~r`eSz(IrsxcK7N837yrTNgI{6vWPQNs&-#Fw7wZG&ysLK3yXw!q zpyY5bDEZtAYFzFGr4RRl(vy2Z>Ce4|=0&^aOMlq`IkFG(WjDr^J<&&YMo-xv{pA1KC&}<%Kqptzx=bm+&=wJ+Fy!? z@*VL%%!-q=D^9|Sld$3>tT+iPPQr?lu;L`FIH`8xjQSIQV8uyTaS~RXgcT=Y#YtFk z5@ue+Nmy|bR-A+tCt>*!R-A+tCt<}&SaA|ooK!n;QvHdOu;L`FI0-9G!itly;v}p% z33DGKKXTqx{N%i=xXO7~@s|5J#bNI46rZ`zQ{3jBPw|}lKgD^@yNV~YD=*Mr`2so0 zBgj{NVO-@M^ie)SPvt4}SN>vN%4?i=)y{cW{ka#E9PR}rpL;=#%e|oV;a*UBat|T> zxwp`~XxDt{FFPPd_Cdbv#<;R4`pC}cDf^?p{KCAH*SJ?x{N%n(ag}>G#ar&@6oLk+zUz$_kxnoy`aYBUQqgQFDN~^7nJ_o<7!^CYrgcC9grjYAYXQ4T-g(S zWM}l0{n1~3`DcH*y!M~8zZ4JUyKtO@6(?cENmy|bR-A+tCt<}&SaA|ooP-r8)vmmz zI7z$WB&;|ID^9|Sld$3>tT+iXN98reN!k@BVZ}*UeuNb#VZ}*UaS~RXgcT>%uDqr= zNxR}CtT+iPPQr?lu;L`FI0C_bBe><+bKSCpQpIZJ)hz^ z_kTg0kKGF@p3olTg;;;(3*;z|AYb`~ag}$_NBIanm8Z~O`HOieuW>J^cJ2k$pL;>c z;a*Vkxfj&9+zUz{?ggbM_Yl&bdkf8rcFmXmvIBBtALPq!j4OMhkL-+|vOoIEFU(7M zje9l4Pwv|kSGk8%yybpQahQ8S#b@sG6t}tOQ#|MXPjQ}mLCuSH}jq6(?cENtk;<)~DK)*XU3Dph0mWzXgW@*dmnoi;PZa0LGnyCe$_w;Y zzCe!h2=bL*_^4}}B zKlanSXxDt{FFPPd_Cdbv#(!l`{#|zFbFx43tT+iXZ}vH?I0-9G!itly;-uOcPyHDWR-A;9&v>xnB&;|ID^9|SlQ45+JXmoO zR-A+tCt<}&SaA|ooP-r8VZ}*UaZ>G!r~ZrwD^9|Sld$3>tT+iPPQr?lFz-%=|301m zUY^?3M}ISjb~yarWtiz7{=4DykG*GNf5Vz~-sR!%O^fx}Kl_`B^g$nF>hCUvna?iI zUnJW5JNF%K>9H3@cWiRJ;EAnSr+Ye{HEdqiz>g}JoZEBt%lha@d1HMReLDPjK{RPy zMbm9^yNy|2COBT6e^%Df7b{r%b7$LU-Lo)uzKZqVkf&f)a{qG1*VJE-N!>$xox#`yK^yO$NZs-R1l zGOwg@>>U}KFLJ{As~!8O9S*mP`K5((}P*HbkZWS54POHLvvpRz@{neHMKx9oQ6=tuE-WJ}Mgyn*E_Y z<3XRMTl}bOUaiXFsC@BDfmfpP(Y?`GQTguIXC?$bWh||2SZiMG*Z~gxz0TloiPFxx z4bK;SXy^NhFiVd92Cn+3UH!kUJU@Ed9Us}V&C6>pjSh=!cHHU1=)m1Oj59iKj6Sq) zud(_wmiim#^oP|S4)?EAI63;k4eyzrB_D1Yz2NPajOR405gj^gqVd?wTG52ULyYIm zd^kGwV4U$YxznOo487fWe*HJ2+mBvh+&y7$l>adnZTuTdUp@mP16eS#83Sfa#)i=a zonUlCR~XwchcIJ9%?sANV9g8GykN}>*1TZN3)Z|~%?sANV9g8GykN}>*1TZN3)Z|~ z%`42zk#)gZp&g&&OPIB=JmzDVHG=P9_2;wd534_{{xIto`EdBNYPVP#``fwn2{U7{ zZ={=;KCE%|7l(C&^*1!b%x8(R~?*~Ax^cthNQi9^IAnD|7Tg7sPELd<5L!|Z$Z zKTJFzF2KYI;ss3nAdbMqY~l+{ydmzu#3AC5wTJ8$wiPjqSjJq4ZNxa3m`Ch`iG{>O z&6l{0%&`72?csTe!|nR4{=TPdLOz4B6?qQEhU7mO+maVyeHML~3%OZ(l4D@>C-=b2 zi<|^AUvd?!&&pQhIkQ#FhU7mO+maVyY)-y}@dbGl#z*8=7~he1VSGwHhIh|+DO&u6 zkNhfERrB|CT@o!YWwUXwE-RzEuKV2hT$6RtX20(><~MLy-}Kk-;lNElT_0V!xnwq6 zq0icA>&~T(la8;9UcS4GaqTCvq7POnXZ(ESccLrXls6ufv>@8EaRuXZuRa&O;5Wy$ z@=u7C=uy$yS<4f~ImTDw-FYqw`Yf9JX_h|wQIok@lG!PD?<|e=WciX=(qa6_Et%47 zN$>ud()otQxid8vy&uiI;Mji5g3C1dY1x({ZyNvN)yph*+tbErAI!{LI-#v`n_rJ) zj#^y8nE&#B^I86#elVZo^Dy#|3o{Pm!K?={dZ8cf=!@Pk^I$$O^JAVc^Je}q_P{PM zcEVmTHpY%HcE!G8?5;le1Lm{%2}UOVgBc6I!svj%VRU01!062Su>P^Rux?=H$a;cV zUt-oB>yLKUBkK}oow8nG)-UTA{(bPU=(3*g+4`*0pi%VYy)PLL%U?O#bIe5JcSl!= z{`}ow3ybb`?lU19bzcLA`zBY^cC0j%!`V0}jb>pKEi-x0w2jsVto1hBp%P&;=K z>dzeotnUb5eMbQ6I|5kW5y1M60M>T|F!SOr1=e>2u)ZUJ^&J7M?+9RhM*! z!1|5=)^`MI=k7!Oxf6l)9RaNG2w;6j0P8yfSlhSLtb*F*FFmV3yPj2m^{fJ{XBA*Qs{rd+1z682z|2ej(z6P* z>sbX@&nm!rRsq(t3b3A4fc2~btY;NqJ*%L0`Ag3#(5`0{U_Gk<>sbX@&nm!rRsq(t z3NZ0R{?ap(wCkBkSkFwtdS(*VGn25MnS}MsB&=s9VLdaccKM6`+FyERl0JH764o=5 zu%4NO^~@x!XC`6hC4cFeN!szPSd&rHI4W)jvjldztdRJ;78XC`Ua zGn25MnS}MsB&=s9VLdYm>zPTIyCC*6jQ!Z>F!p2r!`!X1pJDD?+0QU{vFvAA>3r9bOk^P*kzr9W{E9grjYAYXQ4T-g(SWM}l0 z{n1~3VP5QK&6j-+V+Zy#jD6V8Fm_`?1kYP4cm)#>LLk2m4D; z{38AFm*z#g=1YIs0Xeb{@?|&1l|9i%c1BOxAN}PQ=EZ*2eA(wPc3?ll*oXZL+d7Xu z0}W$O_A`u~+0QWkVn4(9i~S7aFP#@?Cw{3vaScWe@eW2laS&!);vpJO~2d5i}$4&%X$uXglOfAp0c<{|maPvbIg>4QC_ zCw7wl*iZAKUGt^C?0_8E2l=ua|CK%YciEZG$^OWbU$#77Gi&R_afZhe%2G&j%z&nVAd}$IzF4!I_vJI9dEh6d)Brj#}__$yZv4k zdVV&&V)R_YTTM>sVP&E(%qnJl*G;!X>+dOUe91dkM^EK0Y5YdwWzpsZOBw(E!SSrm zPCG6-Volb*S4&%a%bQ=w`t|mIjm2+0F;?tMnRVIoR~i>dSeUi#eaDv$+nCiS7k}5` z8oyNhcUg~TIIeRvS9E*Lg4TXv@-@-8LWPVMq}>v|x4_lLJr|UTURLTF9W^mIOdGb{Wki;+~vXaX*bF-pDp^JV`P>p;+V0{oxH;O zqr-)39i!VL3mv2LHIp1Omrq7IW{$D%&g`?;R*Zl79XxcvCdb$3GR9UH{g~Sr8?Mfq z#~9nbmn*L^Hm|(TF}`?y62FyyjgOC>E#$_+cU3w&W-NXKkUr-=TAkUg-ig@nuwLV@ zy7_^u7e8`bdh@ec&wYN<+9!_wIBRvU?~H$FcRK6f&{M`6rsa$FI(^!>Y5yCeJ3jo$ z_?AwkqUCq~YP>0b#c0~CzZ>7V_SMV^m7V;RpG?X;ai!yXOAg4Ky5}3~Q@U&8%%s_l zugfT%`BZbq_e{u>`OL4!tS7ygXj_C9KJb6oD{ zd6_4FIAr~w&X=88c(3En#+}F-SbDp)-~9Zktfo(XZoF;y_gMp0d}*Ak`mwABFWKez z+|H~?74{f^ciXzGXxV+nXX4(;N;q0CpuPd3IT{7$Uw!@U)(`!QJeW3cYWVBL?wx*vme zKL+c54A%V^tot#T@zDcDFZ6@a7rkNT!F*tBiA`Z_jICkj&HQ2Pfn8wiguP(whaF+; zihW`1ohxQ{7(d_-82{iW7{B2^7(e5082_^lVAcie17^LjZeZ3C>j`FkvCd%D9qSKf zJ+dxg)~Rg5`W3UTS>Glnw%%FyF#CZ00JA^XCoubl{R6X~*jF(7jQs|)|Ja8x`=0#| z6Ay?BF#DB#3$u^e&oKL&eGaql+5a%{fVcn?Cx{m?@q;)56IX~YFmX;}5&wvTv=g6* zQ!sIh_yrTsh-)x$j(7(X|A>Pyagq246EBIIFmaT4YVEPHh`%uLn79lRr-|1v@tZgf z6W59FF!7$a50eMT2Qc}8JOPt8$R9BIM1CaCh{-?dLtfHn$ybs|9@ALlH|ap$lWycg z=}ex~T*#lABP`pJ&t-G+t!zRbmaWLovLSg}wk4m-=Hz+#g8VNZQ5VQ}{4S%$qJE){ z!6wuf)EO{!2lWR`JwjaqQ>Rd`z|=3)F)(!v^$kqDL)`;Y2T>2f)J@b+F!dC56-=E) zy#-T$QHR0QWz=V|)oZc34W^Exo`b3HsPkazKI%W1dXTyhrcR_@gsC5?BVp=F>PvXh zv*oiBiYFTn>Rll_zRRn|J@Zw}etEzS;|CwFnB8;Y#Wok+?ekf9>gM{^&OO2F{l*z@ zYf>irlJCYE-#MXl_L?4JjQi}2+4D%6@r;_Kva?5yHooVzlG(E!Ofnu^wPg0s+nzFh z`l}Mz1I|2VoO@1*>?RL%G=6q;iR{g{#T(}uQzCorsRqVn7nR8NzOQY3^2ZX{eUk4m zZj(?l`{a)$jpy!&$)8!oxN@&j*>^5>e%x|R>FiZQ@>{#Vp>*~uH|8;3H?B~#+ESLSuhc4!n8(Kd5sz(Z1d)9RovKvGT8+U%8LiQ80 ziy6n|t(bk!`U=K_+EmQ0bEdj6_RM~`t#OTx6|=92?`~YCaK-F4E1opIc3Fk&-`Wf{ zZdtEF_Oc(7jX!$7eD>$FQjAv@DW9D=F5Ni)fO6Rt-*xt1yt-`mu8W+H7%R31tq=a~ z-*~(+e!sigOk>u=)FCe$vre|Ii~X&aob~hVo~6dDt8xdH8MEGwzmaLoI()u*mNDz| z$>EM!w@>9T>-mkGKCJUg-*lg4{XdW+lYMc+UN;u|W$wcFO(y$jA4g2=Ys@|^|Jp!f_HV`|ZtbzJ7i2mcvfsCEb+#f7lq){X`rEmr z{|m;%jnBp|G$xK|EaDr#`;V=NKaZSqHY6@BTs+I#iC1%epJGfL%X_mMi}+SH&gnqh zdu?{2^&uV}Npw0BCu^p!m#;~yIn z&lk;GXH1-b<;C^J#Q*$lHyD!_s%~;jzTi7GhG`Z?_JqEB4NQ#oDPiQr>yqm^!4wZZ_!s&ZpE}9d|gNQjguf-1(GqN%Eu4 zchqk$eCn9GPJZMrO04fpnWMflh4q~&tnW-=Jp%yi`%_ropThe76xR2ru)aTq_5CTV z?@wWUe+ujSQ&``h!h8pdELh*4!utLc*7v8dzCVTa+yboU7GOQM0Am|$B-WV@Tk5Qb zjdcdZ_BtEl6P+3HmClm*P-jehtFtFQ*O`>Hrn4|>P-kS;h|aLA9i44iQ#$jq)^rwT z4eE@{+SJ*ZHLEi=m8m*+V+xv$u5iXV2+QfW4@@0`{ox z5ZJrATVStiEMkD}D2NTZyC7x|JMaaugqQ*oV{`{X?9tr_F-dnO#46pT;8WePz`A>( zkM3mntnO-%sXH9T(%lX^=*|b-bQgrqx+7vPx;tWy#BOxPwqk6qJ1%UZJ1A_WyD4m_ zJ1cCfyDV(3J1%^oyDxmCJ28BxyE4WiN1_8cQ+ImgG~Kxsi{(1q#gPMbM@Med-5oho zcY5Sf-Sv@Ubq7f9)!iVuT6c-$aNRMI+jaLy&exqJwSev_sS$LCN$sG!O==3=c~WcW zE|eNXccj!Nx;v$2(VZ%_jP6>gaj12$3AGP35KK)(Z3I&*Q8U5RP}EW|wVRl_Slsc; z>d~)SyFT+~REVZu?zm;^V$tI>o%|!c3P-CJbbS5Q1*7r(oDKy><%@o~(%tcH{yKMb z*QJhgH_H{>P}kkxHrt*n+GLo!BmJy*o@l--cX#?&o&wQX7dtLD`kH9{Htv44%^O9d zU#@X?u)FUs9eufx;{ydNM{6D{VRJdN)Qh%V=(ygY`=h5)9bZ+qWx#EpcqHia#MMs( zpY6YEP$2WSI?2IUQ=6p(I`ki(9_Y6Gt1*Gj$z{d`b1C`QxL}SeUmP3Ez1WtFz$VXM zo)*|@N!w9@4S(A(Jh1Is6Z!=<|Dj2bz!!Q34Bv6Skxx1I$k&{Qv<5gQX>D|Ge>6IC z=i8QRF71CX8hO>#pEusRFZ%sjR}UN=wKKZAtgBt$i|&YaT;=$?Z?;75o#gngYMY|p zOm#Kw3(G!^*50@LD78|y>IO&e;g96*TUWNtXVxGTJ*h{)_%dK$Qlx>J8tV~T(j+j=#YDy&8sX*kLLfw-31MQV_fu1 ze|J|t5rVmrjX((7Czs&-tcA8xQGVoOH`` z(HVnW4Y{}QGtsff+<9Tro719wzj5cmp(m$Audn3Ji8mdb9G!8kJ1;!&?BuBTVGol- zEu%AgpX4L{6^F)Jd;VVz`H6MineprNgZ|pdZoS=F=YYTFw2Es|Rwnyy9$v{Am4K zt=-1G|9WHeS$UybGw9i3US4ZQ{~B#_8#Ax7ce%B(;nm|o`|Wq02>K_ybTW`r1i=g(IAZ?Q9x`X64CFI#d_ZpoJ|e;t~bH(TR&E0Q-``b=1pCtG@+ zo0KP8`rn`Aevb%$(Jp_{U;aXl?1Oyy%f`*IC;G@==qZ1pzx>6#6(3VD826>$3kLcOi7yoBnKz?Qp#Soj?)Qk87wwua{bdK_$UexI z-E7<(f1!`;jGnST`pYkTSIqigEbPbnfUzIz1IB)=4;cHgK49j@`hc+?>jTDqtPdFb zu|8nzr?Uy|><9H{pTNjr|G>y+U%`yaeuL46{S2cg`x8cg_ASi3*v~NbQ#O0Peqmm$56zeL z0b>W&2aJ7KA24=feZbh0^#R*@kF5_Ff3ZGb{KEQx@fYh}?d%8jXP>~xVgJC$XJ5gL z%YK8=hkXd6C;Jn|U+i0$d9j~i=Bsw>p#IoLaGvmSd zi}7Im#dt9OVm!4op88{V7&(jwBcJhL8#nfU!~DCgj~Meg#Y5yV9(@=`@sRP=j$Z1I zzLLW{7|+Iy%}?VpZ|Q?Qq$hTg{@73RqFwW)zwCe<*$4Z{ZZ>X?J^6Rpna|1o$dg~F zVX0-&liHRV7pCT=_Jyg1sfl4~WNKxY+L;;}rlzL0hN-owxnXK>YH^s_oEjabR-$Ht zsiCN)VCo?1A?p*XkEoMi>L%(Zn0ku33Z~AY-h!#isLx>PHR?8)I*xh{roN-jgQ@$d z|6uAt>Oz=$mbwQ?Gkn0l7F7N*Xn z-i4`use@taV(MdTejGId8z6KRAcL)bG^sFm*lkJxsk% z-4AmP;5-0xKH!`Hb8g`L0CS$;Tmf^=;Jg8I{@@$}b1vb00&`yB+yZls;XDI#zTun$ zbME2%19KkYTm*AY;=BZNuHt+JbKc_I1+!Op4vgQJ)pK;Po}+{H938CZ=wLlZ2kSXH zSkKYHdX5g(b98EFJoUHd;d10K9_@OL4%TyYu%4rX^&B0n=jdSO#dxruql0-q4gFv} zM+fUUI#|!q!FrAk)^l{Qo}+{H9G%)3PyKDY965|fyPl(i^&B0n=jdQQ$9S-wql3f# z66+a4J!>c5(JtS?@*OPS!SWp}-@)=7EZ?bJ&k)j|@n}a5MSMN8$dcO(Q z`%N&E7EzX{g+O|af?QoHsY{mlnCa_|j(kdMz`z25}u{U%uNH^F+p31(i} zcY42xcD>&O>-{EJ?>E7EzX{g+O|af?g7tnAtoNJLu6;*;?K{2SL?6B11nd1KSnoH% zdcO(Q`%Q4zUt-pVdpeAC@2SChPYu?4YOvl@Q@i$^-czGp@2SChPYu?4 zYB2f`TVcJY2J1aFn0aa6@ty>+n|8gY2J@bT#Q0RcgXKF|zJujESiXbhJ6OJhwQC5?;FB;-w@XOhOpi@ zRJ-<_-Z!LO?;FB;-w@XOhOpi@g!R55toIFJ=B0h7_YG;+`-ZUIH-z=RA*}ZeVZCn% z>wQC5?;FB;-%#z^cY5EDcD-*1>wQC5?;FB;-w@XOhOpi@gv0(4<5T$#mhWKs4wmm= z`3{!vVEGP~?_l{(?b>(p9qsZREZ@QM9W39$@*OPS!SWp}-@)=7EZ@QM9W39$@*OPS z!SWp}->F^uPQIgEzJujESiXbhJ6OJhOOKU zObt)2g~=P_T9}&OYJwP(XUMg*vk%C%FzwV9>TfkitQ|SjBD5o)8U)rqamhc@hckloB>zZ%;+Ez`yXH%O*#SAS z5AtO<#+5zMM|MU}*&qGom$1LY_*A}w7qt=0+|`av)E`?(4mOm0 zY^!mxx%9zz(i7iFe|)ET(XRQ@Uv@x_?1OySjd5j9^pTy>Q}#!H`6cWxF+OGP^nv9& zSiXbhJ6OJh@P7sW$yHW)EaUIvrh3l~aJ==Z$w7OA zeG`KI@mrq`?ZlxQ{!T1>4W{HCw`Is|M=@a(_h8TjS2P|ti1+nuff`Du=X0Py#{Nq!FOH#toPJ} zOdnodV}^HYu`J_glWAU~#~qhyGbP}gdQS@ayfkG(@LBCUOa8 zF9!3{e*8P+GnRL1zCYuSd4Zk9YL~5OmknXr7M9In`2v=Y;IQw)>kT{49psx1VOAeL zi=IhmmYDC(XL1d;QhT_+m_B0WrT*fuAHy~Yv-%(hJ&W|2ZF0gaTOnWV;r_7tz^rZQ za6W5ZY7h4pYhLt`eZtIGQSbbpGU;4{0VV%SC3fn~c0y)|*l1VOuwZCBP zJ2)&SY;#z1)E=R~_71E)1#7Rt+Jn}fvp33d`59)&Q)v0ZRv1y1}YlVb!iMYlGSqR_zL_c7$>!KZzJTQ;SiXbhQ&_%+wFcn-?ph_EN*`GIz|u!Km%Rf^A6WXp(ntMOhiH$} z9(9|WYx-%9koGX z{~zyhGKSh21ExP?z{p_?82S7Urj37t>C0zeWW@A0MmA&69=k_-Db!vo)W3E}PVJEV z+M#h{_6hW<6VkIzNdG#$3tl{rv9M)mzVxq6du+@)A^X$`*^P0n4{b4h>Nq*GYV#Qw z86m&a3aw{b1N3og>A$QQvsKO-Hu;YKwKmX|wZ!L<4>Kpmg_$e*z}NsiVQho0Fg9ae zFt$Wj7#m{;Shk1dceOKy`ZETM9L9i=&;MZB_&1ooi~%EqF<|s(3|M~8X*a*;^f$l5 z=pK@9ey2UwW`2jUK}b&HeK%S{m=~Hp74Nf#v}pIdR-$F7)YAmz=Be}=6M z=_WnZt~I0eL%Y^hnDI;E?5DhopR6A#ef9W&H@-F5c=Tlrf_9j8=0bn5+9fCa*)SuY z&;C1^=gU$5ux|QnSdR1w_t&`L&q`w8O|(A91)( zSdQ8yhyG&5MNU{|xIc2#Uo!Pswd=FAtG{&n|C(1MZ^>Ye*R8D`FzwQTcF9*C##KA= z)h^a&C5QgvaG&$#NFVjreDztiOP_H6unub1Sdvq%>ZP_mX@BLmYXYYI%*nClU)s-S z#y!7X>-^8;(Erb5hUJ9&h_yb$pOwzxK9UpeFAnRIy0S>*(<5VSUhuf>PaDswP%dbP zX-B5|z-q@ZAU&hx@?cdC^~=ReQLP zSaVmO^XF1&V)e+~XWe?}a#Quly=NTfTU0GF{IKIu4XZ^GHaq_ISk=h%HyxLmSv7KJ zs^ht>szx4t*m0XORU`9?J6@NkYGlwi{)zP+BPXkXW8{Co z*X>8feR`>5^jSBg*UvQrJ)ga%R-pgWH`fa0MZ4xpf7t;!vJdiQH^!Ac(MNVhPuU;+@e4kc zzhLEPuiB7c76l@)sEPuiB7c76l@|W82m-^!`SpI_LFIfJ9^u1mmhWKs4wmm= z`3{!vVEGP~?_l{3mhaU5&t7{f@Etah?_l{3mha%OzoK6r_EbN>s%@&jnkT4{VAWmc zbGX0c=(DUD&H}Wj&mQP~H0hY}oTP!?4^@vEmwsTNcfJl`Ie#`TG8tDgVabFgQ@Z`x zywFX0sy}0i!=IHtVL5LMKki-ns5>v5D06W{OnalD6D%*#em*nq`R#mG?PBK0XWx(Y zPh9J`O^mO7$?>X%1HJHAVU~Q!ln(0iXP;$UwTE?pr2{M-&hO8+@%y4cq7Tu6IN#mU6c3cdSytv_Ia))r5CuMg9w`|94frp#NLN>I8M;yXPtg^`T^< zr`oZP+F`ZRM{>^ZuRiowA6PojUmWgpzD(wV{^$1(e^z~vqq);xtaiy!|8O7p-`P;@ z;XY#7R(%)?)>vT<+feQF54Vr)`cNdZg7fe9$qz=>6mwkndidl|RI0>|jHxvOLJOt0z~{eQa7G4r}8zvEK(Hx1gimuwdF zKXSTRAg92h=7Id@o5cm=zVcaIpihme@qwPL`@{$O-!nQsm>2DuFa2c)(FLem_^^$h05adF`8* z8byAX;5fc>qsRj#9dByTD3bZ!1d~&;d85c<4IE!FvQgxjFI`M7w!KlLTR+D?H*Or+ zl5;0ka&P0vj1Qd7oyIqb6dmSxZnFm>-R^UIPl*R37Zh`R#{~~XektHM&z^@OpIzy= zQ)bi1_!5qHjcpd0+~{9x@1H&Ol=q*or-+B)bsOfjbDKr7j=42?{qd%en+mu!JfU3E zNW+pYHr_VV3-0%FJsck}?W*Ny7pp&eM2rsVuXg%V6H2C7a@5XeB|qGUy7aME;%r>% z)#S6yjTJ+X6CNw9!=K5d7L`m`GGWOSpFc0!B@=GhW~e`QLi0%5zUh&B9&rbj+K?0D-P>5+v^hgtt3H>F1oed_r173q=L-G^KI7Z;>Q8eB2LxYAE)kOig@ey=`o6V1p zpfkK;eSCzuzy-dEk1$90-pg71I^zSGeXMJ8jJH&P( zF{blPS3AG&j_F*btXmt!Z%Ov2#oCeo0nh2Bi|--y*G$X~F1xPP`ryxAvL zuS9=ItWIFjp@+b@ z{JEt^`juXA@)H{;`Oytd=J86&e(k+Z=G+@b`uSHmnM+C}`<+fXIXw%E^!M&}a$YEs z?2kC-KKsyRBmG6cxzEo0BiUbE!0olfv&nwz8{J;p-Dh;LuVL+LSo<2*zJ|50VeM;J z`x@51hPAI@?d$L!hySkFLVSMr(c_-tGpzUwD?Y=D&#>Y%toRHoKEsO7Fl&$a3=>zw zvHI`K5%)fm7UYPgKR8CW>5bEaoYM0J$2OOvj+x`3vKiKgxi@R?7@K@I+A+3zW|m`Y zIANY+Y#a7<(N-xzylqh5U3v%()?rA}ezHnSx zkh}NgO9^62)gmcD+?Y`=C5R8D=cNSkZASH!ASSe0nG(dYPwJ%vG2!*yDM9SIu5xM+ zdyh3v3F1S8pHqT(RjYk!5N~HUPYL2ir~IiwyqcGm8pPX<@1zF#BCBOe5L+I)B{hg$ z1>Z;w;_XexQ-gdlx?*Y&#~#_38pPYSx1J*X?z#-|7Q?s!^y zkgt!nOAl&{R}Q8HHO!%I=|R40x+Fcw*Y)P52ld9Yb<%@6XVv!fAYcEsH$A8~%8gGC z>Yuxgrw2JYQZOT^F%ImA$=tmWbqkp^!*`=&v5BFhb=zCXU8A5 z_zc%QeAwbM+@#(Si_g@$6CZR;4ScSzV`}3;Z#t%CuJngvYU%eLIclG!#{OfQV`}fG zTO6}?YVyQgj>Ea&@618ex?Uq^Pio-isg9|QA3x%lnt4*M!)9}8>BUzaF{Z};YO`Z% z?>cjjT01p)|B=Uxsf7-ocJ`#s`T2QgXX=^mO`QFy$NCgKVm7CSdE=tP<|FE^Ve4Ff zYM9GcIX_ZsEg0rLORYGkgZnJ?OwS3<@6=ZhRdaHv4=WZrV*aJh>GY^uC!fdat7*SD znbe1U*E^ZixBZqmnbbnpGdB1O+eCoqZ7az8DPJNpe z)0zBBeO@)w$>&TlWTBH!t=RlqC!hMZ!%I#+_4&19j+mV}UpzeQsM&}5_Tv;MpZfgi zjz>&B=Zh1~kDC6RcY0PkX8Kd#zSi%s?Lq4EuOdfGf6f<)6_1*H&OtS=KW6f&&vTVJ zV)}Ewxc!QwCZ99W!Lv?2XRbvXoqX!^t=Aqg`J69)J>}$cK5Dez$>&_wHrvVPeDUfY zC!h1t9UGi{&TGHEbMNLmF^ zs;^+xSFq|UnEEPQYyF)y9`%*tGpzUwD?Y=D&#>Y%toRHoKEsO7u;MeU_#BSauylZ> z11ue2=>SUySUSMc0hSK1bok%$FEycZ2eqPd3N@s14Yj3m5H+WA6Sb&v7B#AJ8MUi& zT-dg->`C3O+(A9BoI;(iTtoe@9K^Xmxry_Fau(+Z zPF7xkgyE%mMP1$CF=81D%4eTb78xBrW|+bOZk-QRYo z*dlUhv*SB!wutUe3l7LhJjWY~Rg?z9$>aYY?J^?HlQf^v@cZfg;F zu!`f0FKQX7Q7a?3V`nVg55u}2hIKy->wXy4{V=TiVOaOWu+?i=RkihWm$ z4Obo<=8wO#h3P-~wPAkNKqtRz#xTFb0VhB5@Nhr-Dz|1*@(=fadL-U#((avM{(#+1 z{<05-`A-xoczVrll;BAocwCp$$s&Vo&4{=P4aiwa`MybC;4-?I{D9RNcP*z zaq{{l-C`cNB$<3^bO$`}%kUFe`V25Vecu?tr0f)%@9#V%N}3s&rc z6}!Um8K#~m4*%70Mt9D{G~GWazM+HS8?5*SE55;sZ?NJUtoQ~izQM!_<}RP=9++`; z4-D%b7}h;7tb1Ts_rS33fnnVP!#WeejQdym5&2p(rQb~na^n10?WA1!Rji&=4&7Zi zBgm~U{+62yd-U&m^*oOs)LP-+mbX0}TSV#S^B$L>pW;_dy9 zqz3USF(D<0As;`T7R1{&O;dw-m9Qs0$QP}9qy_P|Wc}12c0D&gJ;)b%8^-RLbK-6O z+NnVtYxiXOzw$-Jv>@Joy)+}pcagg3LB2@2AuWiv_YBDRSH8P0J;)dDl^x|2l;MVqcK6f@#}3F zLB9UI*4Uu7sdLGgpx#KkA|uGx`45Zfn4lJ_J3S+)H&!(q z6VyUK#?D!)F>bzmOi&ADwaEzTilmqwR0|D!D_rtL6hhg0h!@3`abw3R2ei+vMFs%Dwn6XxkK49~L^Xxic`32r}`$5Yu zaORMMmS5n6tb>+c;MLzAwEO~hx%QCd7dY>2hb+HP^GuoTJmch3!(83a$*1nR z^IO-48fN1pHx{*4>3RoEA8MEL)sr^nJ%nKIfx`gN~Yf&KG;uJNca5zKuU-@;M(> z8*|j;b9Vc-(=n6DndtEuM@=SYx6-|inHh&SC|V zk6E8^%>xrd*mr+*oe-``V8*46Wn9&M)F-g&6Ik^LObtnW0;@iORiD7BPhesrb(i8Z zaUjfpWt?Fw#Y}Vvv&N-e@eNjdgB9Ok#Wz^-4OV=E72m?Pr6yGFpjK2)p@vkhp|(^G zqUKa?q83%oqDECNqjpt}V_ex2{wwE&eAzI(ZgoG*8rJ@-_9j@*U?O)fJpCl&`7JmG3wcsm9=Zp?pn!u6)P&NcG0H*!e>F znzNW{8_q|nH#lD?UvoxN&BOUf^#$ z?50|XGn#51&SF7rlk=M`4VPy`j<ynJ{@q~ zKb8@B_BF?QTW3W4j*iznkP$h0h2xv<$%wqPWSaG_63K`>)7mk42j)FBm_9Il_$+;o4xcffqq z>7D8Rnwkg9N9~JE@h^?rW%8R3nBsp{WtYh>y=sb|c>OMupLF?D|KRUC-P*fvs=xlo zPLn@$;8cIt_MIkw&2v-z1t0G;`4_%3)t~smPLrSi+ywuUsoPC{^8FM2eciX4{5q2+ z`U4}|P5xC|Ci<5b-fr@9=b7X$`+1wm?^S)0KYI5zlfSpsB)`h~Z6?2MuStH#<=agD zwM)nP*AM-~=FX`H`m z(q@yt;`liK+d-R6{+@H={H#YeoBY@Mr}}SJUvKgsjeTdA|MWVOzhHl=|J>qrCjY~N zX@0$->rDPbb<+F~?q6r}FKnOY&%AY=$^Y!BH2>mD)|vdvQ`7u|-+yfKm$ymsmz-K- z^7p4D`Ss_oG5Jm2PV&>+uQB@*Gd47sLYklxTlYjSB$$rbFADa9LvFCga zO#jg2cfKRp?=kX2lRu(nKfmk7RVIJ$fPVgyLspsm^f&wY&sSJw^8J1N{Cf_qH2J5l z=rTN@)uX^>YqK~Vo1q*y7~{l>0(IhmRh^6qL zt=%KUSU7$`_Xx2U-aNRweOJgHe5$l#_U1R0yIDJX_JxtSW0voq^q>_TUM)Ve?Yf!2SkD#Gx|ttY&)2@$&HT%HuK#H_lh1md^KCbi&w8$#ySuFu)^oQT zy4(6;J&!8c-PRTRG0*xgCg1ks_gzdr`|;Lmx|)3UC!RcW zXJ?a7Jn3Aov&ko(^ljYPYTxpLqCM&yFUa zcsOckN0U!HJdxJXML0F6|DLS zR(%DlzJgU>!K$x_U163Ev`YtAI>6EamJYCVfTaU09pJDIiqGhy_zWvP!-~(a;xnxH z3@bjviqEj(GpzWG4q=uKv`YtAI>6EamJYCVfTaU09boAY>D$MnmZolxEAyl=YiaN2 zj>#$MBl=o9xu)*b{fx;$Nz)vYn_B+vn4C4OaewPWF8g|jV{+W5V;mD#nY;YEv3z-t z-+rY1@J+QmeiIU2U$UXcZ$-lGw#Iw>h9vyQ>JA>iEeTJ4xrfJZPQtnF=XXaMmiJVjj5|}qQ+;)^a!pV5)%3?|daAG1zfjXt zeRaY5nx5*buTIwVRA1e9c`Z-%RsX`ZJk?j@`rqfNKHR$DK2P=G{F@tist-r?Y~ZOr zEcRLhPxax`dm4DE4=Y~Q&{KW*SccMcn|rEn_g)w0slIJ9GR{+d`|SQWPxWo= zJw;FT?UjS$J=M4GzZ&nUzP4-__Ik;>xDoJe@C6_jL1gzPO`PcTeYwn?CLC z>3ngdd=F3Oi%n1T@N~XdGoy#6^TqlLANO=VdS}7op3X;Y>-X|>KFa?|FHh&A3mmeL0?bjyP7}r^>n`5d}}{X=R0BuzYD>>Cbq!D7Ge%e%pn%R#3Eu8OpGFS!Ne|N z8ca+h*1^O&VjxTmBsRjtM)sg;UG}DGVD_wPWA?IYX7;#hY4*NqY+{0HZ(@aNa$<<$ zKdkr z*0bs>*0bs>*0bs>*0bs>*0bs>*0bs>*0bs>_M_@U_M_@U_M_@U_M_@U_M_@U_M_@U z_M_@U_M_@U;)&{8;)&{8;)&{8;)&{8;)&{8;)&{8;)&{8;)&{8;-Ttu;-Ttu;-Ttu z;-Ttu;-Ttu;-Ttu;-Ttu;-Ttu;<>3l>!()oydr1KH^ROdVLsm^!gQ=RX~r#jz} zPj$W{pXz)^KGpe-e5&)^|5kk!j$MCe%v^p`JCEPrAZE5c)YjAU&tFH{dV2o3PsKK# zo_}tdnc(U9=XKvb?CJUE)w^4GdUmVz)HqMibhRtq%+vGF>t1-!(=%YOo^yls>=~?Q z2w^=#20$P z7nsq~G|jUJrX=U^Rr?? zYfsNVr+%2=>G|j1ZcOm>{PUM*5bxZBqWAlK@Vc3OD`&7145B5o!fV=eR6I8-0OSRx4!j$_`2TZy_V1OTf<~#&+K#d zHD}J8{cmr0{`t;*?G4XA*AH%Qc>eiXWP8K&U=OZrZ+QNB{k!c9&p)py)ZXws*hk~q z8lK0SR=b_y`RCDJw=+BsHlR{l!}EAUPP8>V|6D(*o#FZCclWh1JpX)KYFoqe&$qT~ zZFv6q^BHXn&p-Db($?@iTlVd(4bMM6*rJW$dAuSW+ZvvKF7Z>O;rZte%C|8*|LhfR zWqAI1S4O1a`RCiuwl+NfT=r0ec_9D%^Sfgr4bMOK|F*T^`RB;>5r$_Szj!6m@ceUR zW`yDS=Z^Iw4bMOSv>?Lh`RAu24bMNXm=Ixj{<+@J2*dNwrTRt~o`1%D&A9Q^sOHKj zznL)v?K5_v-#})+C}->fGj@R)yTFWHV8$*mV;7jQD=IHT#y2qI8yN8oW2b+cWH;5gy7zQrjkjf#4TZ?o>xL_ntFWwRpurqZ(cHIiuRW?T=bAE?g&ri~D25+&;9wj+A50^QQR>U)=J5 z&+yUCgxac2ca-uOJ{{1-N;!OeIM)b6P-pR2t6ucl-caLh=i`kvj(z=3 zebtM-MH^|nU303A>Rpk8^;IthKh{X&?UliGRqx6_<$h}>|9hFc8#K~*`{VC*RqsX& zYM^@Y&CJ@W*K@knQ@wj2rGe^2?n8A{ujg*6r+PQ-%Lb|!mENzTdi_g<`l@$dO|`nN z*!^5x)$6eK^;PdOs?^ps#^=lHs$RDkQD610{pQ-b-k4dqp6d0)<3`suB|6s8^~Qik z^;EAr#aLbQyuG82t~YwVRZsPLQmxv$7AjD+uC6z(d{bN3Li0z~)ip-F7wYI*sAO7Q zT~~}*T}RhK(S_>jn&;6c>+0GDy1+AFSnKj^7}mf%GlsP>&yr!y%rjnol|!kUL?gs?v3c`B^0cpeGsTb>8Q`jF?Tu-4+)B&=_F9t`V4o~Nqh z)?GZOg!L`YgJFHh^Hf-$^E?~Yw>%Gq^&!twVSUc?Y*^p&JQ&u8JWqx7InT3UearJ; zc)s9yJgm=oo(=0;o(IG81<&JQea`c2Sl{wI7@jY99uMnto@c{z5YG+b`GV*1us-K` zHarvY3?ZH`cpeYybDn3z^AXPz;`xH-@$f9hvx|5>;(0Hh-WmOX~eS_&n^b8dBBJp zxbJTEIw5dP0!F`FpMbeO0dsu<=K2K8^$8ejORP`8T%UlsJ^>>(;@)R`#u|)_@|ziF z&^}`(`VD0Ei*m*{FykAT@eR!Q24;K%GroZt-vZ|rYeH%V){4{=tRbm2SX)wqu;!#T zVJ%9{!WxxYhP5j-4*haI!8dbUXrFT!c->+>Pwl`upPGX8KeYzW1=JusFHoEC96`;( z^98jG&mGh_+!wf(Zr1gQH4kG5);5e4Si>+TVBN(yhBXXh0@hlLU0A~~CSZNVc!f0# zV*=KPjJH@{F%F9SBzI!^Du^BeaLu=^%dh4*0B|d_ld&`kZ=)^)2-R&ll8dtk0=;cn;#a0?!xJYpl=BBd#~_ z?8dbao{6}|z_T0ILU<11x&qH`TnphDjcXn}i*aqkeFo%cG8a0?b0u;&o%+gW^FNpQI>Ipj^HcA?V3_|I@t-+1 z!OXD8XJ z_qV~^-vkV9^KwB|8u`e?F{oj7k;&kVgBc_!y*myKQHdm&M^OTx$HKE`JdZu zjx@~w{BqG&hWVero7&DW|MT$kZ4C22Kjq#EMGu9!zufe>p!Mv}*ysyE$ufe>p!Mv}*ysyE$ufe>p1MhJ# zZ2;2-Fl_+S1~6>^(*`hY0MiCAZQwot?tR2(tc4h#!Hmyf#%D0&Gnnxi%=ipudJ{W9$c${e4%=Nql>s zF;|ff`;0l{vl!+!(AV7eMmhJr!QA%-bKe`xeQz-Ly}{h~26NvVjJ|mNfO-9ZdHsNS z{eXG>fO-9ZdHsNS{eXG>ywbIqYU1$rO;syj?a)LubW^{^s;!@;xwT5Z=Dtv(k!taa za~i5fk80XbwR>&jW*S?{KGIC%M(a||G(J3idsB^Xtwnx-%C1hcD)kRSmSNOX^m7bhPrbXjAPzcjWphFytk3+MWcHfsopia&{*SJN9S zQ1v2cVMEosoSuy|-VW>CQ1#-z+Z(Fhz1y>)YILbKjWqU_d9Y_#lCg>`T2Tr_qqD2cQNbgt6q1g+d$V9XWy@{dY9g+ zzUp=6()zl_cw&A7UBl!?*H^v!@j^Y->ucrf>v|(1ufDExuIAKJy`J)JJzZ}+-mt!| ze+o~lry5<<)YCP_N7=6Z{QS>vov*9wivCa4)3wmmuj}gi;pt6vb^UYSDEADNzs{K& zQCHV6h}C#5#(fQDE=n+SQG%I^63kqbVCJF(GZ!V8xhTQRMG0npQLJ^D8xw0_=FG&} zn7K5uW@e5}tfiTI6Kibd*BsX^S|#(ZK8%$%9r-$pt2x53=s z26KNK%>8XJ_qV}V3o&;h);Y|Ji1iHfA7VY$H$VR~)-cR@h;9IAMBW3E>`2QhCdp52)170)}&kBa9t z=6A(&8S}W}nTt7EvA*JcjrA4Repp|DxxNB(eFf(F3e5EtnCmMr*H>V!ufVwP0@qr9 z^(}w?3{>7S*+JUtqH3e%(Y7N$w)F7-msZCgmQnRo|rIumsN{tJgTQKJn%=rX! zKEa$%Fy|A@`2=%5!JJPp=ac)}xQ4mE4d(tfnETsc?r(#+zYXU8HkkX{V6250Td>Yy z+`xK<@d4{G#y6~C7!$DWVjRO7hA{zaEygaa6&ZW6o?(2z`ik)i>qCvVZk@xpf%O&R z71oE0w^-j&FR&J3Y{6QKu?y=%##^j!sTWvxF^*w<$astOE%gHHbLt(|V~lTDA2Qxz zeM`N-`kZ=)^&#Ue*0-gmu7yXVGu=wDKDCNfBai~^zfM%Ojf;4 z!heLh^HH~T5&opgvu1bquELX(A2I)_?)#K~yW;0R#{$0Ge}MV-S8Xl0?NfctTaR=U z?sTAssr~Plg}<2hrkT?5HDP`W`QPmX&JXKw4*#m}B?J2t{5uCqf%$xHcD|j!9DRRfKGncn zc7J6Ky}-PPuz_c!Z+4Do%rpB6%rSnme**%~N<1_3SDqKeGX?woE6)f8p8J9gob#J~ z1|IXwz5>6YxY^&hVT^pYa&%&5z?m7IGd%}V52mk7`9C-HUS!M16 z-0Xehz&&s>Y+%1&?pK4kUk&DdHJJO=VD49gxnB+Del-~W<#=&zlUa^E1eSvX&*qU) zezW&60&O6}e)bFI{t1}-Ct&WMfVqDH=Kcwo`zK)TpMbfqNXC9+AahRm8~3n{-#3v_ z=Vrh2rJaHHa4h_GmG7ES&UejVzH0{aT{D>Pn!$Y64CcFLFs>7hmkb*M$4*9lzUvQU z)W6y1ngVSj!v^*X=6NbG&r^YUo(jzKRA8Q`0`oi-nCGd$f%h^Q3`=ZXWW3_c^}>E--Tgcxc1l=n7=^-=5Nq| z`5QD~{ss-0zd-}$Z_t4G8#G|{#cP}AoiHaHFB$d8s82?D;P3U^?B6(JU+9;8f%$uC zVE&#On7^k6=I^P2`Fm<${+=3`zo!OfUl=c$<JZa^WNRDx z&}{onpCM-FZ|-*hx6ZP2+72;w>$I`2^`2#4u0O<_>fgo&2hFnWYYj0C#<#I~i=%9F zSN_<5Ha7K{C_Bj2Pj&Tg**eo^xpwNg-_$$VYo>kDwg0he|A$*=+WD^EZ(P3zznG!6 zZ5Z<>W8al?2<9AuIfr1*A((Rr=6K-?GUgDBy+M|PS^jKVu*@gwfH_yF6Uaro&yjY1 zd$_O-Z$_hZl7=vbe3OlxiyPXHJzFkVM88F*_sQLq14raM6Sy9WuEHAgdrj~Jw#dVAh%V z*`0QK-c*^BMUOqIjPmJw{CPt;xzXNA_Pyr5uMeNO;|6A5@7(vO_J#UKclq;NxpNiU z>m~nh!H@sTpPvE8o>b1c{*?ah%KK|6pRQ`O&eLn`4a_#5ob{}&bJe%G)7{V7h8KJ; zl~v7-JmT}XCe>`mZ+t#=tg4-#>GQ*}RqfLgeNOC9)pl?1^Ggp`waE|oyfL_{9eQHA z%+>A!RqdP{pHZGZ+-KAuRo`c{vnI@Ew14JD-!JHQ#s@ybo{bB9hMmhs`3(Di=<74a z#ryq_g3oDr`@YX<{eyd-({=__t*-6Ym{?u={q*bVYERIm>S||9nHp;UjC*S6xKPgV zqCV#V?Qnk3KIaYnaz0@X=NWc#{$W4;g8Pf{3NaJ>zZ1i6#`{OUn}cotU*GFNU+#Tt zlZ*?x^UJYq!qB4=;r=^8=+uyp4(Qk?ed50p{GW7(Z9aq;|+f+b0_z$nANfl(KK14bLpeqpqYK2ZMFE#r~` z%4-DFuNlxz&4Bi62K4LZNA0N*OW|bng}DqEFY4Dsx$Co5!2Hw-m^bt* zbx`K)spYq`s3!gfj5Y%NQX}AcmTLfY{OjR{YewcO{~DI|eg5;>fUUSb@%LySj4`2K zFvbddz?cKr3C7&ORxsua;{szYVJjGOjClZa?!ojs%h3nxqYp6JK_6hWkN?0Z!@q%1 z7kz-y2KoTQe)IvR-}B4G@A>t`?_k&-(7yN`<*rQp4#pe=*eQLW9CHT0`|bFCXL-Op zNFQt`VBW;*dqs$F>PlDQ*tf_FJA)qa+C$)sEu@8NG>+PPW&7Uf`+?s4rw|;ok%$wZJ3w=A) zCNw;1PLJ>EZQq<~>wTYR-iqnsjjxhsH;&FT1-Eqeswbz}<5lxaTE))Z#0S&uKKI+H z9hP_UQr=CsyS_hSX1v^16ksvQb6yOvm>-c_IB) z*=3dUOp5C_debWVRp&etKdZCX`>tGDcv+r#^4>09wa&S=-l;ru`13B_dkML=ex0KR zHtgS?Ym?n?v(~KD&D(cA*B&}|)btGQ?v)8%Z3nbIX09CU?mbg_wWTj$8|MM#oS zKEwV(2Xmzy<3eAkgT6+z^cnMT=*TK5$Na#4)Peo8e#;TYeD?mg&zR@?--xkQGfLa) zX{)?%SI5}4$HVQO(z#xl3bFR}hT(Q{k6f?k=vdo-Q<%+3&-Hfx9BV5M4zo@7=X#ON z;_TS!VK)16uD3fq&dw|!W?PnA?Ya16$A^SjHx6Og0PeeWq1fQY>XrGRM?wvR(cXK9v_1+(D(O2WU zW9;0arET0ZtGt0H7upYMm$nmfbG#9I7TQ}vO54^Aa>N&`e{ZqX_DY%3wq}PM@5w{C z_IN~Td-1y*Z^{R`Hgj}oo7-rWH*RFE&Kv!OzUW7cm-7sJIRCJdeu4e;7sf?DV!ZS( z=7E04{P23fyrD17bH}H0Yz;U6!`=K3nv-LneJ;$taV6KwJC$RDdxzPFe#rH@HeF>e z=Z4wG-_P|vT)fH_x+UCRn~>|}9$#gD85M5pH_!DNJ(X+A|0mpT3(EE8bx3 zf4l02`#12Og$=x~Id>pZ&hlyR)~?-?h*3iZAr}P)?TD zWQWgXgR;GHcVx=n9&VZKHRhO`%MKnHYD-Sb@IF44W!p!G z+H-3%y!lnK?fA@4yYfWWqBQ5&9>JIhua^{WqEb(&9#S@y10;nv1y zd#9>o*`(LP?W#|+y=V5Uw0pXS+u}R3z4wQ$v}3x5+jV=gy{&hxv;IiK$Cm!U2u6ncE6 zSEN^lt?uIUOPe#jgn1cu)~}&o0wS6}x?bnS}?QwIUcDlJy``w)BxZGUocu~%I zKz+^++TpyReavr>i{!-P#^)!p=`x_ze3OwDTGMVmWk#^`S3p2fD-dp-1djbSmE-=ojsTuF-zz z9mfR?;&@Tcc|d*658C0pp?%IL`sF;s9?n1Pq+eivpufP3$*_SsSi4uM>R^?xQdI{h zS4dMGyt_x5>foi7X{v*f$J0~?Gww)N9o$_jU3KtuM7rwWa5vA?!3a11)WOWE>8gX3 z!qZg;*BnSw9ZY&RO?7Z!`!vO$4Tf>-g7=fr!u?c$4{qUQ{8orSO;DEaktOV zJH{XA;H}O4Sc>xQV|_;bhVSRcTh~s>BR-@3rs4h^qTi37^cnWN(adMqIijP_uz%L8 zK4V-ghmNp5^o8v}ci2Aki2XvRXb<#@c0$)^KlF~{f(~-LDCaz&KIaGRaNf{9=M(*M zo?#E?A9m6&uzzinc$r&_E2fptxW9hx=`-|Y%Y2`qgCW~}h8`U#pCEq=oeJsYGxV$c zdY_?dPd=I`b)a`INBImLoP7Sz^7wX1QU~?Z-}4#md|xzK+fQ%dGx|L~$!FNJ_dTCs z=e=8ehW%G|`;2k196G}K&=T`b3 z4(AQ+b3V~8=Na~J{$VHm0{a8~1*Q(d2I^qK@kG_Z=!QwEgU4c%R0qc#O;R0vsdBRF zU~Z3O)xogXWYxjvK2BC0Y`ra6b?|_jXX;?i=492u@Z4n8!I@FXs)KjElB_yd^qyqZ z!M%HuR0lgvOi~@pt(>Gfcx6|j>fp$siK>IqcP6S1&iXt-bujy_1l7T^4pddyUvYQ9Xz!;UUl%JTM|?U zKX@}ib#U@0395r1-kPX7Sh%!k?LTJI~J=B{@QJ^>Y$goSaq=cvBj!`{cm5QIv7`TiRxhP3rkc7 z>$rKQ4wiNE|5EKGlJXbGHb?~-Rv8sbZ6Ju2eLtl$k9h~~FSk=J}S7KBL7kn3^ zI#^^&jOt+EoUd~C3w7|ZV==0O8*YtN9gKWFR(0^sIkBpP6@H0T9XwVmPIa(Cbe!to zoNaNcgMohM_3+Pq>c@n?<9+(@r+z#{{IOs93>|5=%V+4zwG%!=clw6qkiz}{CMly*>=chv>zJg&msC9 zTg7MC^Ket2VP~BVKEwXDulS5{u^c+W`p_4)1KnZ!&?EK>ouWO^FWL!Rqy5l3jte@- z@uHmbfcl&tw8MEr`WlsgR*8&KbAtuWegnkS6*ofZnC zU#F46ZVy%8_rXr5sZtL6`F;@NV!7M1)cS7EQrmHRmfF7Cv($dwo~7F3_AJ#-w`ZyL zyFDr$m)pD2@uJ*mnAn5*PTPdhj?+A0wD0a=Vf5=XQW*9)?G%QcPE&HQaX= z7^Ax`?erlfEo{L1!9BxE+SS{Z$@{_h@g?p2!^`CTVCvkGws&xfydRvFR?@bunIi88 z-~Y0tEj=_v-VcsCRMOtQHbveKmMKxnCWbDT_k(jQm$IpymdpFWf*nfPB5Rk+`@s%l zO4%M2Qsw<%R9Y!JaY(AXAB@@I>TFMy_k)8km9ohd)8zeNl?oxY?tnCTKX{~ih&}wi z^P_t|xT|%D-FGHU-Va7}3$gL{q|5uky@Nw+xjO0celU1ci0u)XF7F3djSjI7x@!sV z2RDxhv5z%Rm-mBx`-a%{Po~TJ!DFw6*d@W~@_sPAafnUZUo1FbM@a>T$ZNi>q@_w+yu#z@w^RgTK&gH8_S7pU*8+#aF6&vJW*`ku?}DeC(#x7Voe#oQjGzAtlolNx{Ao~6EDL%Gv1=@<2# zwh5yhr+LC?-)W&R`sMpU*yFTQ%3-I|RAJc9_k$Q0%iW%()^~fB+K$_^)b`z;rS|Lg zEY%*jXQ_6&JxjIU?OE!$+#a)z7v)aF#2(al+9r&4oaPCmeW!)O=+|kaFzj*KDGWR5 z7ue6Z>YhP0-nu?_fW55aVLG+q2aAZqHKNaeJ29zT30Ze%+p> z+T->t)lRo(srI`)Djk>GyVCKZoH~g5)IqdE9Yp)oLG()jE+mQ$ZaM1eL?nq0riBIDVoQ@m2Rl6#Y?IC=i4In16>OV6n=Cq5yl1ej*)Lgi zaQvuXTln2%(ZS%E!FKrCWYIx0KiF>Bo-8_;w;NANIQ2eIUO8XFWA0YHd%Bq`@Ucsu_Z}#u*LNf_S%Rf(LuAP zgw1>~Np$e8+!A)#xBmQd&Y^<`yOgkBS4tEejIUY3-n%J5bnxOWC2XC(38I5#PZqa3 z?@ACIymf1F+h|X`=->}I#qFv%cP+VdGB&=r-S<|!=wQ~|;b+dI^F?)DTl&bz%vjsI>BQgy-Y zO=|o(cOXf11m)C0)Ta)j9qJ(3rw*cD>LBc)4#H0A9qgwLVq7eDdzMI*4|tgJ_>Rh<>Squ!lMbJLwnL z&$#NIK{ejGJwJ`ZZZA;dv)d!oxb5~1HJ-aYMUC@ruTkT_+k;eHaC?(FF1Kf?I)ZZQ zAnH>G(GGPG?NbNQFLe<1xV==-ci2h2gZLBV<2hk375baY3(Jyrn_D~05C*vOM5A+u}A+4Cj z7@>pbmKL?J0Xk?>i`uupi4h$P$|-7JIus*182))t`*ev|(ZRF(irNY_Vnqk2aciyCRF(an0gH2P-{V%qE?R z6&-9=w3w~7I97D9(V?O?wQa2EVChXoZMh1uqJ#b3FKTO?iV+?BCB3Nax;sX6uy0CH zJ7`nP4SwhK@Xvkf-}`^Z`;(a_~Z60RYy=x9YlTVAlji0qJ8Qh`lSxS9_k?Mq~5`P>LA9&a<^xx_1&JO zw&V6JwSBi|sr|Y=OSQ-CS*o3G&rN0*&YWo?oDGK6~Ni{%#{o~QK>d^K0w z+1X>Rwx3vTuJ*g*n`pIX&b(-~Go?qg+W%@qw2o_h<7gc(%Bh2>PaQ-%)IqdQ9Ynv> zLD)kbgq@6gus_gW;N9yATZ|Dp_|PYXENp-d_WQJuJ=ii@bg;(8Le}dPEjrlX+d_8! z{sil+;?9PQDfgOMc*+v*phMF;PwRM^%vb43TUS{Ak&r_U7~d}2^xyW{7%qJwdZ z3){!cJkh~(Ulq1xR!49ZW7##1431zUbiiUkck^`~CUnoI?j2%`0rDKRQoz zFsMgidw9cK(ZN^ix;#;D%@rLSd1qm}@XooSgTt>CvL$y%iw-vYxsV+m>#imDJh*gg zA-lLwwCG^D&kNZNZK6d7lf6QAU$f{N{Lbs)pZnC;!N22uN*%<#$#`3H{XC7svkT1E z_}sgyi>vwjcu#kpukpO!%=sGUe_c6WLA9&^5SjgY5n&qxOkiY{l%WcF0SV9yN16%SNq*LW3Jls zTCcfk=ZCH5s{Qc|=IXen)t;;4MLBg4^{InshdPM%IiKj4ItY8HgRql+f&GlD<3pk} z-e&cW(m1?+SJa>Jxyme!+eOCD(s;gelPk}E|8-lj*&6@TI*9hEgXot!xYOA~9fY0KJJ?Sh#JE`AarsQGU#HPbZKv9?8QOl)1v9kY zsxQn?dw#!dhT0i?Y`WUN?wjd4t|MPf*YTp9I*9t5AGAXqMElf1^h+ItJ=8(i$+!pm z1N{XqzQ2I`-Ze^WShf5Q0~?@&O;`S5>TaDbI{4jZf0+Azoh~|f^5;LyrJxz2gB^nk z*dL#pAv!qm{sMNCLuLKpe;e(&ml52R~R-&^}Upw&>un}nhXS_S$r+-9*-sa+SL0@g4rbh1!1ie~Lv--W*+0yI+h>RlW^ek#6gW9u zba3vfKg?shri%_{rvG7TZk&FD-+4X!bD#P;_;J<8= ze!(8#>MiUJ7;SBGI2Ato$6g?YWoAK&D4IYhRjrZ)*YXrc2?LqL+vm8 z#S9(SNpFUZ7vLBc)4#H0Q1@<$p9+^H_*e}RYmc-3Hxcpj{< z_p*Tv(7~(&mrZhuiK2t`&s;X+-<&8q*tYZ)^U|b=qJy`aE2jPj6GaF654d9fI6qNz zuu#qw6I5%G=-?Aqu9&E4lSBs}ZG6=%_-T^pV9|wF&DolhMF&?MyK34moGdzcueoLh zoS!T@SZ&5NbGF44(ZSREu9?}1Q~dXXcV9P8oSq^&xc#N;X4f-QMF&?zT{mC#nJPM% z{K0iIbJ0}M!R+1FP0>%LiVl`LeBE^TW~%65ucOyZX?HE*c`)wab#wdrsiK3wtiNtn zXHFFz+`II;nLcT%=-`V(uA7Ce-L>R&aDlyU9=&a<=-~Bh*UWbtr-%+#TXoG$95zLC zuxyuW=DGW)hz{<3;F@`IpFjVcbLilUldhV`M<$C79;kBFq_3YOIymj%6|<@LB+TBQM{XV4*!e5NH1;3uGak%{-lQlj+^^A+F`Okxw-<+cHyxNQ@ z8t2n8r)d0-_PaQ-%)IqdQ9Ynv>LD)kbgq_qo*iRkA zxLCd=aQB;fwX&0R zyeOv*qCRyH?NA5NKIaqtQU_rVbr5#aFR-8YSF=)MHQo;DH&)~D%$;NZjL((FY24m0 zcAUoZn2oMH|9NnKk?|V;zon>i=H>I0XkT& z)OiyUJ4$pg?Vj^y%a@}>2S2WT-gw1Eiw=(NdEP90cC_f={)F@9je(;@2fP1t-gI9x zT6A#U!@rxe!DB=RXAk<_TzP$r=wPp}em8B_j1e8IaQg-GQMs|AgOhq*Fnb1!6&+l> z=7MRvWvu96`=E>F{C(s6ebMJHn%QrS6CJER^`fb^%K6bf58mosG!LH~CpuX2$VGFe z!g$fa@OC4!(2SC9|gGc+tU~z*DbwhuIzBvlGDNe^tx!KM~@R7>{RKZvCYPb4le%rf;oC=tmxp#xfe`a z!dTHk8+pOZZ9i7#pK}f!T$lU1$z481bg;o|znjn|V?+nfhWu`x_-(Z4VC65)n@?j$ ziw-_K{=9jn^=Q$-wJ)4EiRDL&4vu>GyqUUxl<43arO%sRmW~n~e7pF0Q((@h8~o1e z;h+1|*Tlc$eM%j~y~%j{W}~qhhd+F0tj6bgIb$_$zx2ykjps3?#%Y`nd19Q#|C~nS zR2Me29jEc<#}~(`j-Z@6i2Bq)v_l<4`_w7)OZ|d9)Ir!uy@UPKL5z##Rd$Tg`rpQk z(RTjmG)CKhuId==_iD*8YR{x&qt(uzwvSf(H+(i)$CdNRXdN%gse`Cb9Yj0SL9|aD zM8DKQ*h3wJo%9RrXI$-AZivR)te=Kx9R6wPP>s(QUKyrwyF-!T8qY6A57#(9r1%Jp z|1Dn~p}O$noDn*%xyd6`M^H{3M1ATY+My1jed-|kr4GU#>LBc--obwAAjZY=LM;Ys z{q2(nX*+AS4b=8ud~~4pyC!yk+Ee3S1Juq=+xn~hJL3B5xbB|XU&o7b>LBV<2hk37 z5baY3(Jyrn_D~05C*vOM5A+wfp*d|ZM(E(tr%xK#03Cd%#!0htVSmxV(k)M#IbZY_ z9ekkANmIAf0MWrCF(*ywJ_AGt>uft|rW_d{I=C(Dlvy}vpy=SWcBf3*ZG%JyFD0Ea zAAUMWba3bSQ>M?L!J>m>8=p2co){uJcrxa+>34XD=wOj!r(N#Qp`wFc)iWle-Z0U@ zr$(GHM-B`V9gP3rjCrc-aM8ixC(f9%-whWX>|f@rNvSqMba2#DXU*IpBSZ%e)jMly zE*c>^SfkNdlbJL^bg+A^v*wc-BSZ(YE1oqMUmPJixU|q&lUQnm=-|V<&X|vq-L>R& zuyfoQ^FzhqqJx_|o-uW!hlvgrDSgH)JUvu&@Yl~yn`?E4iViLvecGJN7$Wn}Ifo8D z{Oc)GIbyKrVET+x=BJs1Lh5@0>Kj zRR)L-9&UHiMC|J?I=G?sNwYk;zv$pE)lQl(XZ63q@4O!Vxler^{5#&K)Ir>vjJMOL z4beFK+_fPZpHFojs&V`6FNbP8zgTXV#`%LU4%7Jm==5Q#3ooS&)A%!S)iBi&lv4*$ zpE`(ksDo&qI*5L$gRqA>2s^2Fu%9}Jak0E&(qOGW{Hej(&S&cfY5Uc>57K_ulpUn@ z?A$p}?VOZ2Q0;F&exQ!)vEc)CyeOv*qCRyH?NA5NK6McNQU_rVbr5#aFR-6+_3pAg zG~N#Sv4_Utl;oZopFe)Nm&Wb83isA{{>hx)8s|+=AC3RFz0yZ@Vd?BXILA*o4x)YPAo`^a!XD}%?4;hoe(E5`#qzJ4ch~y!Cw0?y#(dLN+rQ_LuG;Tt zm;age6sXum?R?~$&T9XH*v>kxUnY0f@uHkMi2Bq)v_l<4`_w`7OC5wg)Ir$ExCi?K z{RLjp^O(UHp@R``KB9x=+ng{TckClNSnA0Wrd!EAqJvR|PMFb2?pks>xOu~Ill)+B(ZQ!DA2&gB zdWjD9tbN?Pa;m53VDmG_%(^-~MF&f*JZ5rM^pN@IoI?krZaHSox9l!Dc+1B}&9WKY zL{79DKn@^4Rz>U@LWc|H7dpZYrZcf3!jgSa;tZzHGn&^UbkN)L_Cxt)4y+^+jY zPmSjvm+hr-KDlErjsK^o_EKHAFSVD(pXNEeR7X%w9YlTVAlji0qJ8Qh`lSxS9_k?M zq~5`P>LA9&^5Y5JwSMgzwV~(U+vmW`yE}To7xkzqpRB4BB86=f9JTaIxggU zci+0pdjXVF2T`9oh<2!hXrDTWeyM}7hdKy5=@;0K+}+IA&7AGX;~lzYk(3Wvo$d|n z9WT87KdD}oElI-Fa#OrhpDz>MkeBS0x2eLVRwQ_hE2Rr}zio-$Wyym_+H{<{h{H=sfcBa{OEw7o(pef#{Z_{o6$^S85jh}YIZzA;iaFOJJ zFa3VH*URO$LjL*51=74bU0xvYh!0Y{hHIAz|NdLD_gZ!THv(SCao-6( zxg-4FCg|HR)*JLhhSV=tf4;Y-hR?4&Imdf8-mg=((oFByH~hcd*lenYYaV^^ng{cm z2lJW-^O^_qng{cm2lJW-^O^_qng{cmXF0BU*2gsu<~0xIH4o-B59T!w<~0xIH4o-B z59T!w<~0xIH4o-B59T!w<~0xIH4o-B59T$`a$NJQk82*xYaYyN9?WYV%xfOZYaT52 z2l(rsc(q@Bhxd>49hklY(|2I{4ou&H={uI+jCd93FWz^2=7N9u%mwB%7nsjnU_Nt! z`OF38GZ&c8Twp$Pf%(kEa^81*=0Z82xxjqp0`r**%x5kzpSi$%<^uDX3(RLOFrT@= zeC7i4nG4KkE-;_Dzmf( zex&bk&CqvX`VLIrf$2LieFvuR!1NuMz5~;DEay6bzC$^E2d3}9^c|SK1Jie4`VLIr zf$2LieFvuR!1NuMz5~;DVEPVB-+}2nmh--&?@&(Pf$2LieFvuR!1NuMz5~;D@G1BF z!QAr)bI%{lJ%2Fw{K4Gw2XoIK%sqcF_x!=!^Jh8lJMQ_ToO}LY?)ihc=MUzdKbU*| zVD9;Yx#th&o} zF!%hy-17&E{rUGD#>M-NzJpKcJ1~6*rtiS?9hklY(|2I{4ou&H={uJ5zN7C@PTzs) zJ1~6*rtiS?9hklY(|2I{4ou&H={qoe2d3}9^c|SK1Jie4`i|wi@8~;}(|2I{4ou&H z={qoe2d3}9^c{T4Gbdo4IRW#`37BV2z&vvT=9v>P&zyjH<^;?$Ct#jAVL9(Ro;g7| z&zyjH<^;?$Ct#jA0rSiWm}gGFJaYo(nG-P2oPc@e1k5uhV4gVv^UMjDXHLL8a{}g> z6PEM76EM%5fW`j&`wrvceMjHHr}Q0|z5~;DVEPVB-+}2n zFntH6@4)mO%X#0?cPOXt!1NuMz5~;DVEPVB-+}2nFntH6@4)mOn7#wkcVPMsOy7a& zJ1~96a^83J9m?rDFntH6@4)mOn7#wkcVPMsKINHbFwZ=LdFC0+GtXe2c?RQ5GM`^~ z<{9NY^9<&hXE4t^vz+%G&pe}?XP&`4^9<&hXE4t^gL&o|%rnnmo_PlI%rls0p20lx z4Ca|$Gs}73@ys*IdFC0+GtXe2c?R>$Gni+d!D4^@eTQ-J zzN7EpQ~C}}-+}2nFntH6@4)mOn7#wkcVPOC<-G6cJCxIRVEPVB-+}2nFntH6@4)mO zn7#wkcVPMsOy7a&J1~6*rtiS?9hkmjIqy6A4(0S6n7#wkcVPMsOy7a&J1~6*pYoeK zFu%D2^P4*`zqteRn>#SSxdZc?J21bw1M{0ZFu%EDIqy4ubBA(%a|h-(cVK>V2j(|- zV19E4<~Mg>esc%rH+Nuua|h-(cVK>V2j(|-V19E4<~Mg>esc%rH+L-OeaCO^P|k1e z!2IS8%x~_%{N@hKZ|=ZifBt=kaq+&R@8DDV4ou&H={qoe2d3}9^c|SK1Jie4`i|wi z@8~;}(|2I{4ou&H={qoe2d3}9^c|SK1Jie4`VLIrf$2LieFvuR!1NuMzGFG>JNgdg z^c|SK1Jie4`VLIrf$2LieFvX1=L48IAHdA{0A|hyFmpbDneze6oDX2;d;l}&1DH7< zSkC*7IUi8YoDX2;d;l}&1DH7DNFmsN9nR5)xoMSBKeaD<*C}++wFmsN9nR5)xoMT|-90N1w7??T7z|1)Y zMlLVBg99_?7??T7z|1)YX3jA%bB=+Ta}3O!V=U)=$DCs*XU;J&bB=+Ta}3O!V_?{c zcV}R+KmWeNxOm^uckn5F2d3}9^c|SK1Jie4`VLIrf$2LieaCX%ck~^~={qoe2d3}9 z^c|SK1Jie4`VLIrf$2LieFvuR!1NuMz5~;DVEPVB-?5zc9esy#`VLIrf$2LieFvuR z!1NuMzJpJh^A^mUw_xVH1vBR@m^p93%y|oD&RZ~Z-h!F)7R;QtEa!d4oVO@v&RZ~Z z-h!F)7R;QtVCK99Gv_UsId8$tc?)LFTQGCpf|>Ic%$&Di=DY z&ijtOLpgm1rtiS?9hklY(|2I{4vcZ(Hy7YjcZN%H`-AzL3t%^|@>>94_fA`WBLM8q zama56fZaI``Aq?^(-8Ts0kAvAA-_QYcIP$Zw+X=R9Ebd70n6PwLu^2OxBd`DJ8oSf zjP~7nMHv0Mb&N3VaqAml*y+|o!u-tzw2yJIoWHq%ayPHqj@uK`_T4!S?bn^-PA)xOIsz+IQ;}Vf5?PF~YFNt#5>3r&|vR!*}@2S&ob47(44@PS_6S zitS?#*)Qgn_F&FwCwxcy;X95CzT z^dstkF?Redn7#wkcVPMsOy7a&J1~6*rtiS?9m_E%tdF?@(|2I{4ou&H={qoe2d3}9 zxIW=KFntH6@4)mOn7#wkcVPMsOy7a&J1~96a`=w*;X5#W2d3}9^c|SK1Jie4`VNe7 zx&HL}bav=<>+BQ8oVfmkF;}iXVa%cHPZ)FS`V+>SyZ(gXJJ+8ueCPTThVR_`YPst} z>$^UL(T?jw811|Ngwe12H(}W0`VfYlt`A}O&h;UTF|r(EXMM~G+reD1eas>I#oW>! z%sK6Z?`S`K$8o`T952c_52(-iK|7o`w9olOzno{-!}*7u^o!UZ;4k=&encHG#*V)Q z(|2I{4ou&H={qoe2d3}9^c|SKV>#x8^)Xjq`VLIrf$2LieFvuR!1NuMz5~;DVEPVB z-+}2nFntH6@4)mOn7#wkcPxkRSRcLv(|2I{4ou&H={qoe2d3}97?<1AbUFOO>@%fT z>vIbD(6;yFx+VX=)#?539H}2wWVJWzH=hd~%=JS0t&;Nh5^}vmM|>X9GS_qeNx3WY z+`kFCx}N(RVb_M|+7fncd(IBO{wMTl>pZ!zyZ-I*QQfpnoOfkk^`^ORrt)nl z<8@ZsQp$B!n~N>(eR*ZRTd4j`ED)o9KWlu(_3+4SpK+ahdeLWGKMVW#&%C&< zZaeEUuD9pj@t>D*9sZ*!n>8+B?Z>zTW?TX@E`b@Bz>G^^#wC^`F0nr15}0ub%(w(* zTmmyLff<*;h)aQMIj->#hq?AceCC=Eahq#J#B;785$CzKMEvKP6FS1RD0GDP6xVOC z0p(oNqCVHUXoqWHw9mCM`sJD#_HZo?JGsV&{r|VFy#t?l`7Dg_@);TPz-MR751*+q zZ+zCqeDWC_^UP;+%s-#m;TJy3!(V*HM>(JUQJ;GPXoq_RXrFrs=$Cs7u!nmNu#`K_7v-D>)aU%59nKrtch`j2jDFoUAq;!)Tm$=I zC!Tk}Vt@WK5#Cp_9PejY-^D6z$HgjbAMbhDFW&#s9=sQ(op@hNf4Nwtv6(yds$A6~R2O2OyuL$OOMKI4Rf_YvM%=3z1o>v6(TsN5Ky1_ix4d%ISFwb>^d9EAG zbKPK`>jv{&H<;(TSx$fPTsO*jt{cpA-C&;U2J>7unCH5|Jl758xo$Aeb%S}X8_aXv zV4mv+^ISKW=eof>*A3>mZZOYvvz-3oxo(v6TsN5Ky1_ix4d%ISFwb>^d9EAG?_a?D z{sqkMU%>qS1Z?_a?D{)OfA7r%c&Ilq4a^ZOStzkdPq`xh|3 ze*yFR7cjqn0rUG8Fu#8R^ZOStzkdPq`xh|3e*yFR7cjqn0rUG8meXJS{sray{sqkM zU%>qS1zY_%WJ3%nN69n@+K`_4)1oJyVFuxN7^E*K>zY_%WJ3%nN z69n@+K`_4)WI6rC?*viK?*zg8P7uuR1i}1H5X|oc!Te4T%Y%Y%Zwj+H>ABv{pJQ#s!C|)P{#-Az zS)3hPJVu$Jv?X!)(iv{yP!A`@lO9a>u7~Yz?J95F$Xp#u;@63ilc)5>MDN7bWZ{>V#(S>}_jCIU2wmbG z_%ubz->MULL%yK@Q#pdLzxr9)C4+Ys+-oJLtvY4`-)n&RekYLejsWGo_lH|D|Mq_> zzqi@H|2v|n>o6)&24n!+y-7Vjqi@JbBC6;anG#s z2A*7KKd4>WPRPyiM(kN=ZwV=FTQ|s&xurdLmvP^tp%%HA;GWQX``KmlPUVT- zEf1#JzAY}Bek&$;h0CPch1V{bJ0d5@JO|D>=c>AUuk>=&V`j~w?p|D-RJ--Vqh{XZ zZeHlysWzeEQFD5HS8w~~R9o-+JeM1`i#NVXn%y`$&lKF!*{hzMW{+3RGien&dlMf_ zxBIRiF&&n7@>1SSx4XVSVrIPB$s2qz-QK;zAM)j zUY2K`ytj*2t#huecPh^u{=AF4-t9Phyk0om{&3En zS-m&guDUcHN$A$wRoXQ@Gu*DO>UonvUVN%X`_9hj4Y{a9eX)w&WokS|!{zZl5iA2+Q6U zZughVmOO;b&V|`&TeBn&;o+@ew%W)n$wRm&CCuhk%#u8Wt0#uppT1iu`2dS`4zqZ_ zj68%xU2H7$_)5t`SlzvAera>2dw_m8erC)~RA#Bnm)Y|qLl8125ze8<{78&B-=|f7|mp3dE|Lz%H z(yrdNO#B-^zNDRhc$xS&b#6)9J2*xBJ1woGZCf)%{QLfwC2i@UDdOKzhf3Pp*QSVn z%akZ(6GNAaf9F;%Wm7vX7ylOQP|6lryIlO+VN5C8qe80qH!7`^oj4>_{2Q~w)!CjZ z{vCX&lufRfCjPBbA;i`lkS6{;Qa!{Tem_n8yQ_7G-FGHU{2S3N#Kzx~F8-Z9u;DHM5c>>SB(y_54KAe|85=;VjpXsF8=M?H^i=gGF|+8?9~vvBsg9Co8CCY zrtL`+|2C@>Vrwl(6aS734zVX&q=|oTKU~VjTuT-ImRMWLHeZ@5{ynz1lx^@*s`$6Y z+ode_Z{gn+FO;&KRxB6)_I|LG^_nji|9)|`q&;vtMg05oo|3ljk`(dp!PO=0FYQvq zziEp~+Q>Uo#J|B)O4>oEmx+Jh9$C^R>{%xMEitU5&Dy+7_TG8_7U{Xj^8Wq(i$#|A zZ;Lw?Ti(CFc3W(D|9Y8=E$`p*#}-@Ozx{7tVtN0@)m&nE|K`51#Pa^F({_pF{ag0= zC6@Q^fM=Fi-oIx;mssAvqrYEldH;4>vRLom>g^U=-oIZLU2J*(mRsq@l7Iic+-8yG z{d@3YoaOy{Aui7H{ykSO&hq}f?NqGg{W~-<*7E)heJ$4V{+;@-Sj+pj!<87z`**>2 zF_!mlku5Qn_wRk{V=V9ARoi0p{(bCNjOG2i;nrBo`#19WSj+qO&N;D`_iu$?V)gz# zRx8f({;d!lXLOIH6L*qyBY&Dor+{teGfR{ze7N>=~g^-8k(x9B~|>fgP4lGMMQ zCMKzWb1NsQf3NIHRR4|~nyCJbcIR5@-&vn0sDHEHN>KlneIP;oyW(KH`uCxfc=hjv z;qmI|rv8mQo~HiI zxFcQtySrAp`uB81y83r`yL9z$L<@ITCtrUvtEQ`eD}|@4f7cvHQ~xHto2LF9*gj4D zTQDe1{TrF(#*%;kE^y~?c>msUdAa)cNq2sd{(Zc`a`o>Er&H9wIY}w%-=?ppsDHnF zC`J7neRY}ocgOe3)W5a2E>r(H{Zs#*+P+Nv+x7S|^>2|fDeB)DEmG9K?W0rFziod_ zQU6x7%hkW_<}O$NZrQ$E{fqO5pUy09-Ss8<8$74Dy*(mc^mk`maeKLQyy)+N^x}5g zlz7o!Z(VWw!AJ3;zsJ8XZU2;vNus|M zS_Rvt&nAoh7VjBsYxYYP{T)9l*cN^_S@bt}X0RQ;Hd*x7%n!C(wkM1J<}C=elXfSI z{uYQ1wlg;-i~c503bvK9lSO~;9vo~7PE8j5J@{&{4QZDw`a7~-uzj~|vgmL2eZe+j zOOohsi|ZxqwGm08zh+MfoB3dp=+Lyb+;hkI&baT(C}U*s8#D8n zzV_bF-s^cX{pe&p|27|zz~Fft&cCM`CNP`wPuBDA#E1kY+qOx1{(Y1(f%)L4NqYWG zdo#Y-mwA$&e^c#@Z^|E>sOR64OX8cQV*m<7T|}x8=MLQ>4mx?QiIU5ObyacYA^sP=c^r-5c`|DoF7LahVM-m^oszhlM)ngTLR`+IL=pcy=B znD#f{?LagC!7%M_vGhTvz-Pm?zbQoq|l#_eN-cTZ{@a zaef-1{k=9X$ZQ@rLi^itRgifV_aQc=rhH?`Io>%*XpjXnz~64KmfYjL`lj zS{`KXEEu8v?J+gTZ0tQk`&)iMkl9;(g!cFRPeGpy>2QIF4W;@?$7fB*S=VQ=o=3qybZ z`8zmo?%%<2p9g{eXMeN9{rn4<&yw6{M((q`|D9)l?z5-=)$=BNc4=0s-6CU##o)P& z%im2ph`mfIPtx&##LZ**&-(jiaVyI`zt|_0Z(4rTWUqt_|3mc)jNK!98~mx<;{I;= zw)$Y@L%;2oX7z?BhZWo{mwz1^gBa)wOkZI70@D|mzQFVarY|skf&cESZPyTe4h6qt zVn&Gr0Yh&YVTjY!ss$zNF zduQc#YRg@7os&%KgEcn37QXmeFkcJiYr*boV|Qfpo|oI1aXD}0oJLNM(%GmxI;Z(6 z(DJZDIZfkaBUN4^PA;=A;RxlTsdAaF&+Xj4OqR=xzcy6m%OB=6-<+~D7PL91IeXI1 zUalTF&CT0(CXW}+X?AC_{NvUfrqK6xZhO|sVUF*yu@yU--K_oI^2Qq3O=QkNI;)Hm zc`;5f;{-EKFyjO>PB7yHGfpt$1T#)B;{-EKFyjQfajs}t)C8RBuQ6X;Th!zXu$=2v zQBx>sKb3FF^R^k8ps(_p@V8BcXT6mN6o1>)zuHT=T$Z;@?vp*0hukV^W}N7uyku@s zv*cEH<)*cYn&BBOKfhDN+^gSB_ zeV9b~biPZneUIgQMJ~&LVV19Cz9K8jT26QUibS4Ftj7?SX%oI^6HJ?6+62=kt|e-9 z%3;Q>91}C?y9FlW?>Wq#4P#Z7$9?GYjP~ zy?z-RbMUYECQp#ZhsMTyGiScJvNyYVukyH<(GsrmW% zn5(_!n|5K@&8}nPRX*x!HdCq51l8}oFq`RdbAsAQ@_RPZ_{WKAe^i5$u z9+#b@@$7q+)ifM3N#ksGHme!DbCSk?VsBQn^X{Y=Mk@1 z?}eFGpHGX~*?OVbzBbI{SU)Z1lRgVgm40C+xXknzGi;$LT_wzv*)lz*?5Kt2>oj2| zy7~;2w?C5GynA|v>NlH^+q7&nQ|;XOA-Ac1ai-c|QarZ_sxwRd7ER*us#zM(imSOy z)x@(k&d>JbG94<+jzRou*5)!%O=oLf-B#r?H-DY2b)X!5q(1scJLn_rqmT59J~AHk zk#VArj30euUXU|i=(7&6!}`EJ>juB9C*on95hv@9Ib>hl`9!|#FZ#v4qhFi{^ow(X zesO-#FU}SE#d$-&IEUyL=M!?yE%Z6hu){frea=7pa$O)Et{23~b%gl2zL3|RBNVF4A>$`C)p~=lUXDUx!zvH-G)SSl8Wy&gsqjuNJF3Rk`$LW#1*LACM@$xu0UG z+Ud1FojLr+Qng=sN;=akaGCnu{F}!OmuWno)J$g%EMKN^UM!W)#J#&ru)K707W26JN|lpQhhNucF$KO|sq=h!Nfz@%kCi&-T}EdyL)Wa-`49dr zi#d}#QrAWIPdxrPQrAoQ&@AT9i;=pHwq3|nnOrX0zyel&-rYEi#+8ev4N5 z!*?>9se!9h|KgKSbGq*;wbOKcs9B#NM(r0I9BO`UAESQfH1haVjK)*6T&P)FI9B7_ zl0Vd3ZxXBPE<7~Ui|2f5A3sU@XLB49@ZIgvi?|i?29{}=okBod1l`+=bQ)3Kj#GNg7bs* z!nwja;=EyfaSpNWIG>PnZlTY4h8@m1>~sF%m+J!YaJ?W-t|P?H^@Y4XDwe{ud$nHs zm9%gQvmnt1o##$jQWCWvoEQ6*k_BzvuR;c^Wo7g8s|47lA52=Y}NSp^h#>xmfWgy zIJ9e0bGn@6LOIi#M!#)WIT>}hlR2#!(|xzqHkpT-29->&oDd2bq1 zrPvN#7cXa|F`tjvq3dOBn=~d)!kxN~%6*W=obSC;*VntjX-u}{yL8=E+nU;p8na8~ zKMhQ6QsvpL`rlMfZ9bd7TkTxPoZ7roaF5!baXpneJ7JId&Ara!fV~>eoC&E+k!pK2 z&aypInYsh_>bhInCY2evc(3O5Ys*w-d+c7V1Lc@!>SNAn2lG$+SQqq*^}=|tjuvS_8oK1dBFU0POvUG zKUgoEE36~V8`c-+5bKWf2|4E$`kZIj;he)h=O2E#E)Wmb3*zKDLi}7`$m=ifnf}!r zhqYh5`@}a{3Ln;ae$v+4%UbQQ&iS9;#5X+$9@hC!XX2avClBko7?#T8(noZ?)H)kt zx-C7T>*)BL5Yy4tiPasCxm(&c2VQW{nXn_(B`7X z8FM^MaiDLZ5Yj9o7f-SvUA)JrNJ=N$Gq|M1Iofq1xH5GU6W;^+E8ULE(ok~-zD zYrldvzmfq}uj@QtocT(&wz+Q4cWqwDgGJYM{<9Z-C1nF{=(@;q{H2ur{)VoXDQ#cM z-9tBY9nDMpQV!OYpk0TuQgUt#+<$ zdM3G_-B$Z8zJDeMe!Qc8nhR&d8R(*oOUq(w2yT`zgRDf2kVG&Vtp}w ztUKlfIrD`+>i|2f5A3sU@XLB49@ZIgvi?|i?29{}=okBod1l`+=bQ)3Kj#GNg7bs* z!nwja;=EyfaSpNWIG>PnZlTY4h8@m1>~sF%m+L~$cdyqA;^aC){9IqCA@12$P8<-6 z8iK!C7&jI*1e;oMV^Kr!xWKrvs3AE1$~dv8A$UuhII*Z9_;~3!v8W;VM8-I=s3G`y zKpfqV0Y3ZSmCg+1h>iM)84Nqf1q}Ph5e&b`9gKKT6ENaLt-y#MH3TCs2Wr0H{@(;@zTj<>0ySUoii3fgFL?QjK+P9CGEI=?3!aiW zC>AxR9Qjfo`GR2w`GR3zXU1drMZSOg(ehjvgm+DAR< z7j(LY|&a}YT6+C@DFfy;Ke zsOKPXxp(X}54dZfy%qvDyLZ7~caXCV&}V&MhjoK}))RhNXT-z$BTn`O@pIiFFRr`4 zGyD5s$5qW2eJ|emn&u1sHP3Z>&h^;)1fb>%dA8CwG+*%3**7#_@T12!{5g!ydsELr zknb*WQ}YEw&UuDD=Nxu8|FF+>0l!=?h==P4adLejey%&@NIB|2ebk3`P&e8~J?R&9 zW<01r<3wM$?$}4bUx*jVx1YP|4&U#L%iH~Uc6QwE$GN-6c0c|kaqT?~kjd7-62l)1@XJ{$^If=_8oQLJfJ?D6V#3KgL-nVP-o5?>d$q@eqlb* zFRnYtx$dCPbq70Kcd*ZO2fti*h==PAadO=ue&*$Uj@g&jtFz4451nD}?IWIJua@}s z7yhus_xtw6#eO_>+AsFwtXpWYAOFagi*ycQr|Zo{e!h^i4$xseby6xS!cw< z`Xf&E1@Uv;Auq1Gzcc%rXv=cH?;p2Y;m^Z>94q}fSsA&~pP%~mefFV_p=;W|Q`TwjQv>kc_mjyg~u^`RZqjrLJb`bC`?59-f2(HE{e_7Uq2edM}> zoa+wyTz9a;bqD)gcks(~hj_T|5GVVB_}%$re~~ZyjyiB2P#?|->c;s&JvmpXGv^KU z=elFRu|Js9x}cueO9T1;mwhkL zclXcyC+r=Zjg`E3Q!Q77u=6+N#_oITj z9~I2~s9<+LDrXh@_qfju%zbWP?sEfkpBtF_+`!!D2If9DF!#BExz7#EeQw~io&NXt z=|P{fO6LAIu4Tx%e!<+g2IjssF!!y2xqiX_C;Lk|d$7a#0i&nb-wWpcUNHCfg8#er z+;Vy8X9>(%0&|wYoF%Y3OFV8s&SM3b#|kiy6<{7Kz&uufd8`2Q zSOMm-0?cCtn8yk*j}>4ZE5JNffO)I{yT^Q&-C1&(wZ%Fj!w&mPIeP7$H+kN9)2{2@ zr0W6p>rH;oY4-`)uQ%!b(wqD|h5dSy?!&*y&z;$?H{p3Du043| z3U;qQDaW-6<2Tvo3g*c-8X`J4%~Nvdk)->fqM?={sZ?l zaX%sY^(O5@dsFv+a^E%j^(O7teN*?z^Yba_*PHaYhCOfS=ZW|^KJ@EN`ux|M__<47 ztMK#MyqAS*7582f8FJnmB=g=N<*>>7Jnl0oKJWPFIh5V6`0x503ccg~88Gf+@VV7L z&+BdP{+*uJqer|y1IB#}_UoU0O}1bEPWzhBBi^3@<30xa_0RrK+pmA8{h#O&@6Uj7 zAA|k+XP><7*T2g?d0dnH&z`yCnuKy*pWs&ZohHdx&!>1=NNx7#VPJPdgGVFNvm0{oeQHD?NcgpbT`A~*W&qoC8z^CU!`E_2D zmvr>Q9XsKU{cy)`xD!vf6KA*+e}t1)gp+TCQwP|ILTvEq)D3=B4xh*wI`HY#Kiug{ zNw;6ka%PDx(r={puKub_%FpH>i+nOFweqmqwWH?Vi?7@)=lG~%74Jqtzx~JCqVNNT z48H?I7q0=s25f<08##jE)03B^+|v)IzGp`nc0Bvau9MV2y172l;=YkK0P1G z@ag$bhEGRc($Noh?1Ve^!yUijPCOA#oDoj^+Pl|zLC$=kAN4w~2&X;~PTk;Fb>I^@ zzs@V%seicBmy&M3kmDaavPLpTF#ID&F#ID&F#ID&F#N+G82*tX82*tX82*tXn7sqP z?p-A1@Iig}0K*P^fMFj$V94-0Fm&Mq3>)wPM*Q#rew`QP=pFU7RV%a&Jt z!~dtrvq$tP5wQ~7U~q1gUmbWQa^myM%7X$LMm-*tLb+VFnNjPu#!>E)^Kg{+6OPw; zvS{yj%ARht_Znr-Mzm+Ewj0VCdpC zVAy~yFl@sI82=o3Nk>22u@mmt4|n`VIPpX{aYi`tM_4bK7v#(r`m6)&D0@C5oVrDL ze)aW`;dihFT`x{$*l_w%@_*I43*)kAAFHfB6}hNRI^`^NzKkl_K9TaL$tOh(TK_N{ zy^ct>E6V#(_GD4s@02~=Xzw-3o{ebFR!Qi4wxbaj*qax~BPoXuF!bRA3_I`vhJE~i zA;a&$(8X)OumK-n*oF@&ZohHb&7Y%n7A-})xd+w zO)3r!pZ4&Ia=TjJhL6qlSh-`G4B>y(j}r}>d3KL3>G@NJe@7na=tntrq8$5Cj^8LJ zo+u~IsLx|X{mzcM6BV5ElIHbs{ufad-_N9+`uDie9%~)Io{lnfyw`>!PQ2EsVU$zb zD5vI8PA{UI9z{95i*$SH@&D@#q#paAB=nk)I+A{!_u9fy&}pCK z{ip>g;zYsM(nqsbp8GX43ObqVF7{sAKy@+}c@*jBl=$#+H>*>5koVfosCeP`u;4HbY>vjnVEmN zhIg**|9Q{lz4yWUuz$DrT<*1>b4~cqwYqn0jO*xs=WBKJ4)4owPQ-f?GTyU*@qPmD zO~80BgZDUKI&!?{qQ1Vzd2L7E`+(uo@ryn(9=zvLh7Bivy?(NG z^gS2z)%R$SL*J>-|Izzp=i0-&?y}c5nQsjHzjD2VYY8vz2+zKEed06x>UAUKxQ0P* z9l7efeyv{nSx%$Zf6zzF&NYvJeVF-18nxx_^A7xJ#?fnk(8sX_id#_RUY(#suls(&i zoSsj}qo5Bte1M@3AG8A>VA#hG7&7<(Ll>_B!v<`DVH-Zcuk)fj+|dtr?1Ve^)dybd z$>d%DryYr0WG2Mig02ZkA5@0wX{81Ea2p4UBrg9~gClKQQWt|M3rXg%2>~ z@BxNCe1KsGKESY#A24M29T>WJ4H!1)1GeD7qBQTF) zVAK-FGRkp`qdty(VA#Pi5zONxn8!&lkCR{?C&94oUY|JEE&p6kde?9Nj@Of3FZJ3O z@29ZdaGmMB4~j;QE&uELFGmM+z}Mp1M(-!%J~4FoUg^K1l-Z%06i+7Ix?|F9M z#P40h{MY-V|GxX-|MT~5|2OX8qc2Xal+oY+8_yu-?3!k7cD*AhCmoG>l5CdGkXL^z zfmzURx5~+or~c}OEO>HK)X$HR;pF^42-mC4bYM8b9s8mn)|}gQ0v^zNRcO9Ii-8B8)b@1c!)AW1S z!L1uj*Y8~iPkK3BzjqycX4(w>-gR(}+B5Zg*TG(`_4~TPdp6DT-+DE?hi+mXm z@@1UJm+`y#vJUXe`hZzCFzX3sox!X>n0*1WUtsS?`v_)#!R$Mj^8n_YfH^;4&J~#R z26pF=y~E5fUoh(cW_`e{8<_P3v(8}FAI!dhJ>S|dF#8B*f5GfKnDYSUoPaq$V9pho z^9J5jaH$k%YiEWG`SeFyq~WHEIzME{54>0?g*Mz$xyyVl>h{YAOJtAtw|>B5zF#c! z>e@LBnzBer$GxS;9O}cSE2lo>v;+Ql{z5SYZ>vqR8xQ#QxrH+OlC|G#%R*V0(CWK! zx^h=PB-_-pFOWK^?kf-a zWPudU{y@1?&js>XzK6;gt}Kv~xgIHRZ?#ZrCV8wip)cg(%Bc@I?SN??Out~p17@6H z#t+^WJX?PJ_O!;}^1Qh-q+6-m%(vG|b*oL2ucz7T zrC$?ImmfOYYp?>Br^|{Gr_@gJ(=+7iX3OWU&y;NiPHWv5GxBof)Q6mQz_bshUohhV zGfpt$2Qx1)^98dGVAcoBx`A0waETUkCI2m3e=_9k1vupJYwZ5^R=i_%YS*7HZ9lWz_PYhLr1TlBE%gzPE2lo>v;#hs zd!xLpZF^0I+>L<@d1U3S@?9J|OD^-Zi1TFTP4eo#ou#UAH%r4GEKl9CS<0`l^A^A5 z7Fm7K&f(O%TjcojgBm~Wz?UnhzRF+Q0nV>m+L0@M5bK`Q2Eq7pGshnK;g4~Wn&h}? z`N4r|lKz)?D&KIbnwaPDVs(~Y+XuUH>O)RDVA==MFPQOw87H{mUU%wS}x)ZF$3vpQJ}bsLFfP zYbhsUEq^n-rBp7TS>=b?w3JdiEyuk2NkXe-(fZRqVsPcuhn#l6v=63VFyjHcac)Z< zBF%m-r@qLTu`%bf%8RSzHMVwZvdFyeDkv}cJhSxLZn@8dOfo!oMU|(E%pmoeTE06w zom?4Xd3U!oa(bEN)YVc+&y|)N=S?A7r&#_pRWf=1H_J0}B#|t|E!Sv}NQ$4ezIL5Y zAXnR2-Z4MEqzbY8aBGO%?`h+l{eFn#dS!EA{K(gpQy+5L0njq{$!K^d*?ia}<`1(^_7cQemdAr8Zn)fUnB0pYwr8*z&4Uye@Un*aU zjW6AHzEJ)>PC`k2_PO%B0g2?>)RrH8kwh9aeWq)KHsRNmQy+5L0nZU{_9k$Y}>m z`(XM7Gaj%Tr+b`tna51zMb_88UcZ{JvzB@6g52dTNBT;_XIXWwT#g^zO%_CDS9$e{ z-KAW4%gvv3mwhL*seJC19+IM$<-tpO%4el5KUmmHzE5U3Z**^&a@X3=yRDCGy_QvL zNc)J#l~W&b+5yu(n0~>G2kgeVq)|2*Rk()wBBMTcZ)cN{U)I+67vIY&IZoD6j`vws zIZ)H`*pRH!XKPKBx6hhYN{Qvi!?McV#nvY6z^^N(KIF6mrhTyMcm3YM(&~8*jgyQx zhnE;2gA3Xkb}Tbc;(lcL>-PuApbnM?<^4l0ueW^V(H~MY)b{A%j6Wr9cgv}Y4VGh% zEe{+ySepK7ebGMRaply9oOZyp52jx*;{h{H@V8yZ$%{~1H)siw94`t$_( zV5#Meu@hw82h~;nTk{E0akJ&scg9PJ3N=(7_VIW*6=~~FJMiVosSi2rfN390zu*ij zb4vKyI%?nLd6x^z`h9g(erbL|8Mevt{2uwG{uIlpI^>g5KUjWuY92Y9&hoDKVbX8u z7y8K=@;zAvpM@K=@;zA!VsW5^&zJnaG9~Qq}BHFYLg84tdQlhcb&a9YxC{O6$3n-#@=Z z?#HjB>mu%r#nPsVfiU)blH5;zK{6e$_!~S({h%VXlqmap1b&Xs(Q9O_|tMf$mtYr5q+spd(OW0qS!nI|9Svc6~^@wjs8Lryzj z+6U7wnDKxaC-~i`>t)-%{5l&hpQ^V`Ca%e=@+!&J%eq4Olx5Ujibw0EZ{fF8 zo-FSMIU8m9qQ{?A%&)zs9r$wP)Q6mQz_br`{mx#zQ3~dGPi>M>|8FX7lzb20))?mQ z@c8F|3CX&+3# z;A<16$mH4feXGmqmQRplnRBS$B{L?-sbTiopz~i7q(@TA%aTr%FZSxa?Sws$&kCp7MEEc=(x;dDeSn+ zwE+3c-`C5u$^~^!(*3qxj%+NXJoL_bDPW2y7dpQ|x=t_pFS7(+v;*dhfvFFs9Wd>K zUB3|xX3FBm-SmB>%SW=zk<*wk-oOT&=s=yQ=3=QuU1NjXq#{Q_>pq0 zfvv;E0g!uk9lSS5AG%X$MUEVEP3!9x&qs=kB~zeoiz*V{`fW&ed`<=>U~4 z4_G5rat~BK5xhn^eK1J5+OgGAyY?T-HM^{qGY$S!Zv8A)e*S8(a<@-n<(^pkt=h*( zoEMhE2dEaxoh)$pc$ZHc1G zrG9J6bt^5Cb$f?s-55V|bmi2CoOZyp52jx*;{h{HFyjX^FEH~3vkqX^2h6&GSx+$Q z4CdMa*SxS;a*ncd-l_Bwc{Jwr%saD3eH>@pnWR4Ct{wIo_HRyGB;^AC(7IjhI$su+ zAE3-*1zt;iuq&rN|Df!Hfs&#+jk`0Pp>yecne#P4af?EjvOEX>5Z!^pUuY zEuZ_LucW(c`Br#8X*J=n>b!NcpLA|^MEO{U{&KY1QRVQ9{iV@o$CP{I8X&!D+vkk5 zk9b@;^&zJnFztis7tDCTj1zn`S50YOZkqaa`FXd`q;>M~DlhwK6`3)`@~N{`G2kgfA(cx_JYQmrDi;R99&z@S6Mcd!^6tBmCj%BGjTkL)osWt)r= zc+7IU*`e~*P0P)9XOUluSevv1zpkA6kkbyB_Q9^-_&?T>kT30hU^3!dm$9+5$Zend zWa!#RIvlY)aOw9F+Qi;J|2Ve3blhio;M{NJXv$|==Z^+_Ej`05?`>XBUL>*H;_JF{ zev9=*`-sPtQy+5L0ny-(K{r zJtw-1d;9I4j?_4D|9|9(5w^D8^N8o0hb!ZG!Tb%c&xzjii1!cM^BtZq3`l4h&mI2w z)}H%l6MkJe^&!Xe2-pGBJ{Zp<;1|qzz_58E&pwUEW#m%)1ACl-ufuEX@dv(+rLzoQ z`6}CE6nsV1v(KR6t67}`e(t+Jw0kOOlQB?EeaLACO#5K^1v4HnYl4~oJ0maZkU2|` z5Begvv`%H8O^+OvQx;V`r}|-!vq_6NcJINyUYVuPCw6bf#IG~RMzP1$ug9d8SACDF zKJ!8hv=4UW)Q6mQz_bshUohhVyK%xM<_+;DdY)YN_OTpyXiBM<$1;yCcrEq8uAKUi zyLNcah5Z(>U1fi3yZ0$mfp!uU-|qi;G`*!Pt6=x}@HhZFd@b0OQy+5L0nLTxUwCjTBXv9Om zU{_9k$Y}>m`(XM7GafMG1T%iHn^(f_!(>LW?z(1O9{6yKq{!b%<=y`rBR>u9tb8tL zjLdG=MfscRqb0>hU6m(yA0-8!S|Df!Hfs&#`$XI1eyL;Bkctlxqo+atRyT~TVqbTX`Cb&R7bgB*YUC~V_oGv z87Ij36JILd?>|9WZ2wAm*ntVs@W?mHo9|ALyAQup-g<6=>`ZH~;b|Z7xN_=4PCH=Q z2h%T@@qig8INzGOGIY2-@3=g+aZ_nq)n1c)x395W46!;pLVl1`qb)y4*-&!Fv+vh3 z1T>IJMv`&PErwOn<>*OI!N<&dTIWL=N(zKhb zU7u6AR?qIT@O{h6XZDb0SuJkL+m@rgqv5 z>ni~%@+v2LubnD+QDLrdj~mBS=%R(r3e z#I!upq_(}6LYwgG%Bc@I?SN??Out~p17;0ztZ}G1#BeWuSbMyQJE@|HELpnX#Pmg0dr|#?a4{dHjJLz837t zsSi2rfN3AhV;iYapN0YM_iBWzP$(`t_1*`Fm`E=CKIAXb0@dsSi2rfN390zu*qTsKTU03_O{P@BCn@1TP|3B*gln+STv`7Uhp~|#O%tc4>|3C zX&+3#V8#PxoM6VUI*n&02T#eJNnu*gw$D$>jtZ79mpv(y zkLOnTqeUmAeSOP2E1!_$B1hue=YW~AUy-ddimJ|)HkW1pdzRBaxFm%li>SQXgiF%+ZOh4jyCh#sFRXFW z4t%+C>O)RDVA==MFF35$BY9S@xcYK=!S*;N%?11Xam^obOp?a$sm?1C$3&mDymHAa z8Bo!_HgfYzX)?}o@P-$%<+$bV=RKE=K_&FH`35|b!l^A^Z~9aQCbV3o>Juq=+3K&U z_*hcSFRnQ<2E^&gsSi2rfN390zhK4#W}INg4`yCq<_l);z%ipQN%T_teC?MCmt=0$ z0vc!U-WR3lv$vExes@8dEzhU?(eZPVxPM;dg0Id<_HKEUIb%4k(mvRgQy+5L0n&b0}BmwBv%JmbBjCgq2@wI)&T zBr-=A*!pZg9AXwuwDlZ!Kgje8w$Cwd4-YWscG_o`oDKM*O|UDcKIF6mrhPE|g57w& z9)CzelG&Mb`PX0e%Iqt4Zrca!lP_CX9=2kiLhFbC&~B^()K8`W%!} z`R#1e4(i~_sSi2rfN390zu+8cS4)fUKhgE&^4WmD_B*XbC zDt~ljtz4XK`N^#{lB%9%lXH#idH%WT^k}QrX;AhJ#mc&YuE1zh884qH1<K=@)$VZX6R4R#WY}{AI}? z(RGwh@%7!4b@h!XO^YHv2)8+O4&$3;E%)AnI z&u4=Vg3RP4mXlozG*7bI{ht%M2b$@fEniI*XcF$QocE6alOUdr?R@+IlP-_tqaEU! zGH=(^IxtS;;>xKHIqiUHA56bs#sg-YV8#z-USQ@6W*xw+514fWciI}qBznKH*4gC} zKfjQ?CGCE;yI;MO{7o#UDEUe{zusTh=lLrc^U}&2SB+yver5N?#TyaF$ks|)2ik!z zS5AG%X$MUEVEP5~mbZ`Vcr@<*lkj(=SvSa;O_`x>M^TwgU9m2IlCY7?#`#uewN)^$U4I>eSuv$^&zJnFztis z7tDCTj1%m}U-j4hGNMdXjq@+>{FN@RP{}*=7Q#?nwzMxOPV4gRj<1){E&>=&I$9Blckh{k{GUQVHFX_ME?t>*m9@=@g zT!^&q#eS^2Tk?Kr-+#48uv>oHV!2`eU6Q-JegC!T(oTt4ZaGV~osuiPegAbQe22_v zWO=yRE@`G%4t{%^Y~E~ne&|+Ne#mmk;4RW-m*qMSH%aM*mWSNmC=Y(O92|e6BrKX; zd&)SGuPdiM^u;0<)a{Hj& zk|fb)eeYke#BRx%eT#CFQoH3r#8%}rDRxWSYTJ|>uh=E4zTU2Ux9Bd(QfG(W8=)Qe za^=*AoOZyp4|e@ltFm8;Cb!Rk$e4%RUH3?ZFYUgI3}5b*LEdv!$mgWqCl@YS9y5KP z6g^^}y>3XdU;a34pU)PruwQySu=_4(2Yy{S^&zJnFztis7yN$374k4yT0JkgECp7| z^*Hu(h$}mG2h2FZn>TEg5AQ71+PYl%MT`_0vP|U-K8%%w zU98T?m9etE;}Vq*uen-Q3|XvvBEuRPv2l^|@#kwKBD3YtCu^nc*o7)@7P4NRRIr>O z+Xe~CVL4~SUy`bT<+h)1lwZHMT&(scS+w2q?#i2G=U3KdgX~*mS~}}@&w(v+_m1TU z-))ulm+Z4M#*Z9bIrSl@9Wd>K=@-m+z>E{j_`%Ez%zVMD1DN#zvut{r|S1MI)|$1*uy#D0b`Udl)*mDYZ) zxx#>G$yv>QHu?PRRkCkoe4W*b@5IR2!ikk|3CX&+3#V8#PxoM6Te=5Yymxy;#yj>}wM(Ek_yU!13SjDj69UhAG0T%H_uL+-6U zrTudGgZ4Ki$D<1>-?RUQrdG7aF_#Da7HaZ;lSzAe`er6mqmkva-)AyMYgw*v zCZoyqw&f`eGMW;PteqP7GMM=@GwN}ScHqmEQy+5L0n*ul`%Jc7|IM=H-BD zoOZyp52j!6)eR@4ZN`t)zRLx2?~~uhS5oG2h2FZj33Orz|0q%zejcxB%!)qT&{I4x5>E1p5G^i zhMA0I>@`51_ruKPZI*9V3NwT1*lULArNT^{OO_X<3o`|NvTG{K@!TfY9m|vZm& zwCip_-rOc=yXED}a+#@FZ45uWm&+{r%5tUoIZfSOmdj+%X?`7Px!#Z*ruUzg=f=-r z*0u`OHOrWhmn)|}|nIx;u>+g%h znsUD{jy-}-kF8KZO z+IBg9ue#3g?*(>C^ho=RmGg|(QXlNfsSi2rfcagE;2|I1kVK{IIVgSj4awQ@U(ZK~ zf%;&cr@+()(+-&D9oTo7=MLzQp~GVu-#P8`#e9M>PNlLr@W5y-8A$4 z_~YlBuX&*k%<=DxeBbF=Pv;Q%rnqkz`R1wnmCBKC^_7;9@7nlZs~q{hs$?1Yruf}5 z^6fIhGV*OY$ujb#9Qjfo`O*&ZrG4Z}zsQ&IAYaCbd>Ox+FYADOSsyU#24+3MtTUMP z2eU6=_6zL&Xdl7sFPMD?a~{B)6ENoo%((({-oWl0vUiwO<_l&Wz^o6Lbpx}WVAdJT z`h(dQu;*L*1!f@S#o2Xh|4oD(qT2h6zwbKbxm%k7mKbL{7=U7j01y}7XX8(l{( zFKpgao=PH>e^j-Zj9OyfBNTqvT%MH*R{4Q)KTD+>_Ir?)WNj-Q55`q_&itLdXSH#Z zqiT1T^||bKr(}8DTW&wM`yalzFhE|;exm37(5Hi?Xi3W_laBP|8J~~!^*fH4pBVccCdhZr zz?3RSzHO$ZRz|*=ezx!Hk?)Wz=~Rw<+rLP!jC|Wn&!CKazdU6b`BIL2sgHbV2l>)I z@}*zo%XpA4<3zrU-_4hGK)$RGm~{iQo?zA)%=&}b7clz;W*@=qFPMD?a~{B)6ENoo z%((({-oWl0vUiwm<_l&Wz^o6Lbpx}WVAdJT`h(dQF#82&AHnP|n0*Ix9>AOvFy{x% zxdL^DK0n9l8 zbAG^_D=_B`+_TMa`7})mT^H3Z5BI)LDOkCj_kAx@ay(rHo%G+0mekWODTjPEP9kp} zRIYM$q73e`S@}}BX>xGKD&>z>%#wbEmMZs}I$zdaoUdFda*6cMI!`&#&XvBrLUfF; zKj({ezMV3?H~RMb=iKW1ZI^t9AI~QxcKLCB(08{Vf0F0BH81p$IsToI?_QHh*9h{h zoFTU|@=Z~@kTUXpf605w$an7*QAWNC*OygBzBN--R7SoLEA0Ds{SJ>jP%pz^o^jbq2HkVD<&feu3FXF#8K;-@%** zFy{o!`2lmTz??Vm$pP_9-ZUTRwPKrV@l4Z85z6)BhL}P}U+@3f6yH2bY`@L(wb!elb`drm6UPh%?oX1~Lv+fNxxz3=j>PU-QP&Bh?hFSlj) z<>5zi`}(b>=kx8POk2>m|6P(IzTZz;zwO79HKLdwXW}aF`teVh|E}hRJ~GF@GxEJq z#yTaJkBi~}ztE(LO1~0CujC}8Hs-=v4 z`{uUS{K%JbJS5W&CcwtON38eZZ_6nDqp+&S2Ib%)Wrx zFEINEW`Du#JDBqT=A3{zKVZ}ua|PzSf!#S|?=Y*(7tA_6Qi7UkM@3&M=9N^!F>Afe=m&fT7&%X~- zJ9mhGA12}G`2KyEwZ{_p_hD9?PUzo}MgNf9n(b`8C+-@v5UTL_<;XYQeapzVa~u1)9^^aqpk?ISBSkOON4~XlTSmT=BVXzx zU)n*ww2yr07x^+CjP%pz^o^jbq2HkVD<&feu3FXF#8K;-@%** zFy{o!`2lmTz??U*JBREYW|jGZSqCud17_X8tS6Xt2DAQP_65v-f!Rke`wM2@!JG#$ z=LF380duavoHsD?%97UZFM_<&J9ZBe^w-zAtZN5$M)a}Y6$ATb*F}}XZ~a1+5zpm0 z7yNa%;Umk4|6Fp*$Se5^`>Y@NQjR)MAN8Rf)Q$F0Px?ij84v2uIMElzk2yqM=p%Fd zJ0sti$5sdVw%u?4ZVvLDKH2`Q9OV1*OS`uU`5t{?8Tr=eZ2v9^`qK8aW#n5YlilBi zd#uPn}NdD^4B()zf4f4AqaeNum}L*eLLkdo$~GHSar(xJI)fBBd7iNTi-aXd7+QY@$Za$XMAn{ zb`tWfA7Q_H2l@VyzW^qqA0Op*4IX_^|6`1n|cIS}2!>lr2FzWzjeZZ_6nDqp+&S2Ib%)WrxFEINEW`Du# zJDBqT=A3{zKVZ%knDYjnzrMJCKQnS$aZ@VNegNfVvZa%kI<=4c|zAqPsDU4fSG6$$s{srrWd`b$rQ z`*teji}3CDZW7`9Z9O5vkLQ<-5q_LCPDc3ge{(Uyzn{q*(NmX^Z|auz^FGM8*jCHP zcYo&6dY=vXHfd}b`Ocbc8Tk%BWf}Pn4Yr>ZLcVRXSVq2G!Ym_S%8@VikuU8aU)o2$ z^ox8M5AtQ4$d~cE`LYhkm-PX&ZeZ3E%sPWve=z$3X1~DfBbfaKv+rQe1DJCH=KO#; zS76Q?*quZ63$x06!K?$A^#QYPVAd1NI)hn%F#7^#zrgGxnEeH_?_kaYm~#T={D3)E zV9p!(a{o-`yOZ|&4ekxiWZHDKynn8@w>h8Xefu(*We4ncHLQsrYO?jU{Hju@IaAT{ z&|#tGek#lFUI{f1u4mWl(i&wln^XrZ<34SI9hM6`{V(|^)w1~dH>PLt?R2}F#kari zovgm!`9Ea!n0*1WUtsnT%>IJecQEGx%sByb ze!!e7Fy{^I&LR7SS!KRp)&b1=fLS*%>j`F^!K^=+eF3vyVD=Hr{({+eFy{fxIRSHi zz?>^E=M9YG$<2@Kerc@7z}t3TG}h_a;g+#}%apZ@bv^fy-3yKN{^N4XI1Y5_Vj0JW zu3uQjabsc`%Q&743%88p4COffP#?!7+QIRP_Hi7eUmV{U4~~0`6URfwkK;e`LLZsq z-x>KHondv5@6$MTA2sqFQ{6K1Ei%zE@@;X(GV=X0t=(UZeCvv3-+DE?hi+mXm@@1UJm+`y#vJS|X^#QYPVAd1NI)hn%F#7^#zrgGxnEeH_ z?_kaYm~#T={D3)EV9p!ZokR8xv&wwItOJ82uHBM(cx}Cgqz>%3a_U3g zBISDDzRUFG#sI$c`$~E5)4IA|Ty|gEGia^UooVCQ7r0t_U$k5-bBr|m`2S(=J)pHJ z(rs-O1Pq9h6vd2~W7`JySKBOV+uChvZF6q3ZO%Eg0ToOrDh5DB5KJh18%!voqL_06 z5p%$Z@zyizot!oHz5M4N-RInU&K{@7=&>J*TD5A$Z_TRromJNPnz~y(9sf$D!ec1bj_q*<{bm&rhsh?GLpQ%&jd_SeVci2bu&DD0`n=c%h zPJXn+u0OrSi1h9@d+R)Z|Mu{-$b*H~%Q+4^EVPfx4|`x}I%|{CX0;F1a@Xg6b~~`! zhpYQ#EZzMy(>M2-`ew?9b$?xP7nGYRuWq~kGe6gU*r4?Jil%RCyS6HPZ@Jg8H7wVv;nx$npOzE|tI{0SPXJpQt2wJ9TxRh!j5RLfnT{<|I6 z?ZegmUN!3abkf0hHBnyWYM-k-r27l$-D}@ceKW`9ZQ-^b-kc_Ue2d~jue|oQwDa26 ziqE?F&h%j4E5v6$cW>HYwadlbei)O^>U@=Wq3I8$O;@{K{Kk=wr@1z}O+4e^r_!~p z?iVjT;@R}t4^RAWeXf?fKF8&DV7Cu@zp(oQyPvT84_A+CrQ3ToF1~)5v#4_QoK)F$ zI6u98yj~SQep_FFW%UA$)C#l#Y^<9HJ>> zw_c4me^xxW)_8KA#x|D~kE7S?Yc-yK=`O0XfBV%MUz}9Fss1!&g~lD%D$mg~doSBK zZD@JEuDoyY#@$va&zl{;eYmB!M4?Rj^A~Z|7X5?X}|iO&;LE^cj}-0y`#l&5D26{g*-M+eszPVX0LI zr*+RLaSltIJUAV{e2H`T;r+qs=5d9OJ#a``YNHb8aMQ0t(vL$6zc={S^!*Qom)ZHY zR9~UQJmmeQ$?FwNRZEeqS0iY*v4spD}D! zKd)M5_^kflvDWZe$3=PXJwDR!7xmi=`%p|fkF_pL`_~>eUFGbz`zIfW>CYx-7N(z@ z{jMvGP6>vMkG4(HA7b3VOa&a?Z&`FB6LF7ChA{^Q#HXRLQw zT~E{N39>J*(+B^v>r}FBbK_=COnAM7;&VXtEd|0`=yR@XhOu4(w+VXak; z-Rm>LUPluC&sf*eYf#d@*QV5dBM%*Ro-FMAS=f2Cu=8zU=i$Q6&xM`03p<||&i|hk z5A6J3%AFSsJ6{-f9x?3vV%T}du=9~&=PAQ2F)y3r@^}JlJq}x^!`APxbv~Rm+;~{WM9RK0CJnjm6+!FS9ChT!e z*yEqD$3au*Y>_kN3hJ2ZlX9413%dZi(aMI`%xC z%={_L^X2(Co-fbS@qBsyj_1qsdOTmA@8kLMJRr}P=LdPdJa5SJ^*{58|NML+*U0nu zu;;;H&yT~NH-|l+4tt&*_WV2Sd3o6L^|0shVbAZwp7)0x4*)w(0CxNU?6?Bh@dmKt z5a5;=cfoNv-U)WR5bQW2*zrZM&kJz9oL9y5a=sPU%XwH_FXv}*y_~nj^>RKJ*UNccTrcN; zalQU0FYKSs3-k42z6R!cIscUF<-Am`m-AJ*Ue06XdO5$9>*c&xu9x#+xn9nb<$C>3 z{%pBkcq^kd<;?1Kc`M+mmR5NzKe*nUK?eTrcF7s2*5g6($% z+Xo4@KN4);B-nmRuzi+b`!B)vWrFS31lz|6Zi&8C9GCs#VEe7X_F;qV&j#DK4Yr>f zY@avS{%^2-;b8m4!S<1Z?Jo!0cMi569c-UE*#32}eeGcT-N7x<-;d)O`pEo^Lr!=> zb6CfnFn{9{{ht?a*?s=TV_$ks{QSuI8uwYd@bA~3uW^$xWsU3^56s&*^x(oz{BGXH zk9!xscKAGv?Y1wx!%Fisj<~3B)eqU;zx3h1i#KxBfB3-;|KI+`9GCrj;eW-m-TuI| zQ}q`9SN!T{=Sy7mG5-9luTsaGUe`VF`GsGmj&qk>zmsnLA`R_Zc!hU9Pfu-J^8UuJ z`+53vr;_Wp!l=*E?|&)mwT&oi~(PytQ1bgivn0a>A zxzlmQT0*eb0D}KtuQx{@yjBtHwXWcQW$nM}dRSg3i#Drk&w0%w%Kw#h=)6V}?RdQ^ z_+MEwuDULj*Q=t<@&5tqYSGTWvVNJ@zN8(mcL{sFPWWG0chzfj(vH{eguSLG?6p2& zuK@~sZBW>2hQif#Hvg5iYrT#qZF%Y?nuL}=*y?EH`$irS29)5D_!1PSl{k7jGW(-U-zS~E9 zP{^sI=>4>NI5I?u*!1VrGyNOpl>xT5yqPvP0m~efX=h9uo)%E4Q&O7^> zOG6!)I2v_oj&~JY}H?OK>zgD^9$d6&NXS(pNd!2UOQwT)ISuS+Im15dh(g7 ze@@>4>BxR(h`km(?R$-Q*lWkbUQ-_STJvyqUHi88?w%f*>vFZZ-S|CI=gkUtpSpK? za@WG$=Grf9xq0E49S=y$&0Tm>+rOnw*Y?x4`@C>a`k-y$<2$dK7VmkU$~RfLXX-M! z^m*$ud#1tD%dyP2_VQ`2Z^|(q)VM;r@UwCrUhcnQT47Q-S0}8$aysqebJfn|_m@kT z%z3)_sl%2_uN-uWc*b8lq&26M{eJ(~_UW>{OW%g~nJ@L3_X^cHX^wf*2Co*LKCWH5 zbNrPm|HJcb)6Y*_B|dMXwyFPHSBsxoux&c|$Nu8^eqJy=e?e(~&MP{m-Ip)?=F**0 zhkD=A&Z|qM-v$;weDV_Mm^BKYJhXdS>GR7}r{i&prdDqh-f)ve(uLm_ZoN#`^u@-d z{?BJ`n~q)Z2GxJP$4=>#%?68aJz}Rcdfh?dRrlE`9k=`~;t4TWq|-MWrt&jJ?vR$+@gDKxr~DC?|27uVlBG+n;K)8Ye%9G@w}Baf!mhv=QmEhIK94o`Nm%9^NZ3MhrXt5 zzvy*QI%?pn;;DbTFfBZzw0Y^N7o<54Dm-V`KIzTfN-SdMwf~X!zP`j#e!BJrY4XN} z$1Hncn(|hR?VVolSa|Dv&QE)x)W783{ZsdY3wJx~z;xtFD|TjV|Zv(!Va3j_p)pHTz$)Y`SZUscNU^4@;#Z?s!-H!ugA*)&5v~OK#k= zTY5Z|Yr5xv&gr)cUsoNT&2={{*O6!Hv*lk_^S^U?(xa!bkPP!sQw3iMyJO&I81y>yV2>B{SFZyvd07I)cQf< zRj#-{-M!7<#9c;=N-L~zpm??W?n^gqdw{sZ@O#s9PnO?>Vb|Z2*1Nv&&(A!V-d>=O z>MVE0z3J%r%6n$lE$>T@JYRUdHAkg=k1g++W!KF6`n>SujUGt78p=E8q+Lg+XLc^U z=y7Axm75p7<$`+ZGI!x#mo%l7uPWOfb;{T@$1kP*v;R0QeVqy)`_s5|^d9A1w9}an zruX(M?~v`^crfj}b9uMC)#jme`i7UP&!gsgDE)c4OT?cKzAJ6ks?_=5tUJ@l&C7AU zw!|Ijj5jY-ore8xOLres-pNOz5dC0oArS1Eb_x$E(+?Jl{ zU%U_xnsHm|eAz$LPWy{)PdEPk0`V%F4^3yTTiPGiby)iG`NLJd#szn$aaWY{-0Q@< z((tf~W* zrPmHs`#Vj$J1u)nY4h}r?n&PdDE!3I{nDc^lzELi8ZS>*PAJ?v`}Xg9OW`a3a%FyZ z6>h!hRq54*3*W!c)#;*p|0+Fu&zP&zdK(q)nElLqJzVnIhJU#FtoFM-uQo#(DRt3T84Ty<7IPx)Y()T(#c*D5oYPIFE!d3H0t zTq^b7t?)euE|soXeMj~4hbxy%Gwv>Y%92Z_S}GpS*R@?TUGQY#xwl<1y|h#DbH4lQ zCDSr*7j9QSJB=8#wAz{Y+J$M}pOzG_@YDs_`#re+k95n7!rzWOKkeV4tk2u;p7YYS z8xaVyhP!v*6Wk{ty=ie z=li9jeqKg>xTJr-bjb0AJFVR>z41e7=et|`rmp7{{^vu9qf z;nGtJpSJNOY0f_s{?qdV(;UlhulDyo>-zLd_i}!EZhb>~XLLD-4}Nt+TCaEE6AmAk zws@lWV?RD_U>d$*;XU6Sm^RF7qw^kKW0wJGw^hpdT(#ddsqF#f8u4yi;jB4S2R`)Z z&BVMv+k9Hy`Mme`JEZ(B@IKtT^Uu1sc~5qpQkeJW+0XoeA+yhj&c3_9{I5lTK;h7t3$T0XHv|wisWy{dG&EU$-kf*YVxc8w(VEXX8cF zq?tdc%{x0Rl8)$H%8&f4OZs*9!n@A%$254_TsoE=`);3pJFAU&{5#vH#-HaFfBVw* zX^~?JuYAn*X_?PktNe$i?b5Wv3a@$JpVK4XwNm-SegBl+xTx@;=e9|$)+jvS)<37y zhR>rqTMz$pTK&EG#hc%}ecEuo1;z86{Fl_NTPN|4OYNQ}{Ln=_{iyxY0oN=detNUR z(s`dODqd&pBhw+zEg>HJ+mWgJ_Jv#Dz}tu`-w?(Tn2Z;k7&^6`_7 zOy@Qfp8oL>>466qQ~5_@4o~%M3J-XH$@I&|WzF%S8?;S5ek<4gyC>VGZ_X>_lkRMn zI<+lpkw5$XJn7?;3-7q!d}-Y&g>PM^eOhAO;^n?grw(a@6AB-+!b0iETMBpHzEe8y zfx?r|?vmcUukeha3#X3;6kd3Ax3v2qg)bPmSh{Mt!uR}X@pS&vWnU*hv_u-dPvPqN zchxoWCOy%*v2Cmu`KQLY8_(VJG2JJVhGu?by!e>;+BELFWa06O!QOpEuKB!2GdkJ5W{mpTVu{c$>Khr&1A_({6pxWZ4~ z@o8H5kiz$kot8TM~#QPuMY_Szgh?LKYN|u>YBn^-#IchuKJ~}=~4@iOslv5O8nN~5$V*q%6I*LOhcy^P4Ut%BhzZ*3r|?}-n7bzpK04;HoPZ2_e$Xb``?|0@A|pQTiD!YE@ABP*w9&}I>$jPhj(fK7o!y^Iqh2Z8X04~v6HgSrs`2U6<(9%< z^_rA!J+SZ+OFff%EK+#F^k>r8QRN%pfQz3^%WYoxhUK~$u5rr`N-v*Z zj{U&h2c?T|dPD7O^vIwz*PTV5?z;WpwCCV57IFOiL(<>QC>nN^4~L}t*Lz3x7ku~D z^zjpgr+#`{dTN!@=X=&0p3b{&vg-VP)w|O>dzIgm`41hH7CvHv%J+O@blQB{!{Xit zG^M4d)x}%=GB&Mt`F-N*y5axb)|BUd^Lps;j5VK4OYBm9PY=5P+0?XWIVW8fnw(DD zzWi1mT$`M}Z79E$tFAXWExUAChuS&Ufx#vggqiCw|4|=PYKvw6RXB>7eIqV#B*tzGhbJAhws>9A< zhn?FFJLlcyrIoGgrv0>+E!_M7?ozo3F*Bf>YILvX88xA{X9Cj`_>>P90x#zHR z(qZSS!_Hxco!bsu~TEU z<9o2j{a}v=!X77tJ$?v#ToLw|5A3lZ*kkyx$Khd*&%++K7sq%$>~VhBv zYOv?pV9&w9o|}U`4+wjH5cXUi>^VNzbAPbs1Yyq=!k$BfJ+}z|A?7h*&u_w>ql7(o z342Zx_FO0IIZ)Vhrm*KyVb9ybo^ORc4-0#K7WTX??D<^S^SrRi1PTZ=>SD?wBsNb*vZcSTfi#X7HGs-%M8?yN=pCt?8}w`-2J} z{PNpr_%Ve~`tY4J^yFWJ9Z8}Wv&;}Zbz)AeO-C~3u*LRg|EBh z#q`RMvd-qwXTFrS+auQ8yx`?jTe+}f0%>PT#0tW%eEeu03*Am_-uC(8Q0laM;l^bjO3(dVJh;w1@xk=`#fAHRKQ7f4EZp{{ap~dn( z{o6L;8%`US<~h2s;}YqE;}~JbH^Pp4gdGnFJBAZ>Y$v?PsjVB2=vVqV;*QphA9X3m z_1dGY8@C!*_@nWy8y{b3d-dnlJ6kuNndcGMc9XMOHx6HK2l0Lzwr;%np28hIY1KG$ z>Ebgs@SIkSL(VAtafeoo^G+(f!ew(c&NKH;+V=f+b2To!d|}6z(!S$SVaKV$j$eh> zJNlQj!ungNof&)lnpQrz@IveVmd+Sf_=2B*O9Or_e9(4tH1^+POVxM0AMMO|=Ero( z?Y&jL=zc$>zfCP(YV&UTT{`j8%~am{v~SXYr#2Nk=8$b2iwHYL5%$J-}~|OOWS?KwYwirV}9FH{K3i-(m{*tA>QYy32EvcyNNySN}C>! zg+1O2dmI=ZHuIfyd(#uz_UyLrq|;X_yvv$zr~2O~sC?5?-%8hA{kYg;#cb=bW!PiR zu*b1sk8i^sqlP_p4SP%*_Eu&p^{~hDVUMN59%F|+_6~bY9`;y0>@j@UWBahj z{9(@pz@8(3J&yo;{23lG^M!QqLR;uuZTZ=YY19jwi*NhkrS!??n~5Lm^h)~Zpu&r< z^J=r?{B2O>-5&PeRh2_U3^(--(%hE*W=-^$H`&) za=`ZMfbHV}+usAW?+0u@5ZFE;u>C_|`-;H!8-eXZ0^6Siwr>e+KNHwKC$RlbVEdxL z_Dg~7qvG2ae1B53qe9VEaYD_K|??F9F+k0=6FoY@Z6){uQu&Enxdy!1lp_ z?T-Q5Hv_hx25g@V*!~-^eK}n2>*e)0DEB%Yu-ET^y{-rB^*&(wX+M0g4??-u4S~I$ z2<&x6V6Q&{dtDOP>y^NqXZ!PeeG|&P?g?z)0N8#4uzdz#`wzhOC4lW$0Ncj^w!Z;v z-viiw2(Wz;VEZS)_EmuGw*cFR0k%H_Y~Kdheh#pG9$em1)~92gM33XKo*?=493$%q zl3x$Ao*?=4FzX4DUk|gMAo=w$>j{!y53`;i`SmdC36ftAJHH-w-aYJmeAs#Vu=Dp} z=k>$R_lNBR0NWn`wr_yTz5Xoqy)G^7ocrHw{amk~&T+M*b;g~C&T&=ORrh-9lzSa^ z*z2>yUbh|gdhW2-d569JJ4_z>ZFcd6Hlr`+qv!(Lw=_PX=1*Q1BMPCe}P>tU~J z4?9m5cK$5vyjs}#wy^VXVdv+<&fA5Z&kH-x7k2(H?7U#u`NFXCh+*d!!_GT~osSGV zPZ@UpGVHu&mtVi}Sf56}YV)om8-u`0xv+Ckkis|QHzwIZc z|9`usubAT+ux4S7*X5iC*XR7W9nPEE=X`pwm&3n-$>YglCXUyVf#Wu^TA=~iNnqxhn-grJKr339=gk~xu>1ZKlOjAwGq?KmY=l})Bb5M&nafV zueF;)On)Bj@r#}#`uXM0KZ@!9uR~{wIj%L=FU;|}ob%xNoFBKtd2{=mPw$uW?EY~6 z-A}HI`){8Ij?4ZJuzew5`$fR^k$~+l0o!*1wjTv-p9Np423! zpBJrmubBQn{K1`Kj_cwjhl@F0mvbImpY!8(IB#yB^XdI^p4}hLzx&B`asT-~^!f{Y zAL8f3G4g$gpAXFUA$~qE--r15zFN#`wqeOBZB!p^l?${_lbRS+>YNr_SK=B{rY`HfBYV!pMJm5f4}!Q zF24^sUYBzoT%Ysfb~tZtpY!SWA?Mls;r#o3$aQi5xn5qsz9p>>Zr?UvN3Uzo_40c6 zT=%Oln6BrJ>(%(|2V$<*zN;1HdVP4uG?jC`Sf8CXxn5HjEX?&<@R#>h&h>IR*UR;} zUT%l$<@UK=-Y?h7{o#7KpIjIB-@b_S!G4LbeH3B)E5i0&gzd)&+out>exbgcjQ=gih;K9gw=jOr z_}{|#JmY^00 z|8Us8;;{Y3Vf&E7_9ut!TMpaL9JbH7%e^ih^}Svm?RXtM+V}c;?APn=(I2nJM?bwz zAN}|GeH_>St#$qEx4?1PhXJ-f18m<0*nSSMeI8)@Kfv~sfbBa0FShhY>B(Ey)b;x4 zxDV5d>lE(#?ew(T=rvTn{lMwzptTCykAiLOSpnNa0DkDQIU3u?{OoUyd41A%%be^3 z_xzUnY*FS(M?djvI{5m+ZN~qSCcasC|KUHU$6J^A))o8wlveLt_|rpvOqa}C_|MzT zOsjra>f5h?{o2z2w$}k{4+PlW2(Ud9VEZ}1_IZFWy0vrTwbw17^KjI(&W%GlFDdTb zp-W@OD+_~LX|J8XD|ME7KOH{iTk*|3rls3AFTBWlAEf=}D16-Z)6>l#eWN-9 z4*xLC->Q`FcjiZF`X35^arVb)(MJl~yMw;jCj>t6=eN_O-aU05KHTK(bn~0#-TwVu zZ>3ZAE&R+@Z>6W-DZdx?6=7TF`@_!7hwTXfJAWT`UO()7f7m_%u>ApG`v$=F6M*eM z0Na-UwqF5k9|PE)39!8sVEZ1x_CtX83ZDen{t2*s6=3@^yGR`Q5PdzG3H{ z!_G;Eoj(pcuN-#1IqW=i*!k(O^VVVKv%}7Rhn*J>dmSa%>np)tcM0}-Ot9B!g1z<= z>@}g_KX-UEJ+j)0dWWZL9!<5Oh426V(RAVJE2+H03ggq1F@?Qu6x(_oE7)sJ!5e;b zYdYe##kK9mU)`4GJiqXOIfkY^PA=SI!8_6`=N7(ykzuLFkixrk8lDb*qp;V;qD`+` z1baOr*lQ=jUQ-Fa=hlJgoh!@l@)?f}Oy@38_`U^hOuJoFe#iGa^TzaA&IhOd`HS9^ z8V8o&{jM+Hl+Lad_Igaz@j6qm*PnuqJN~|OXJd&eTI<1k)3Fh2w88uLq;J}l_@X&K zyE`5C=fWf2y(_(acHt!_j7<05Q26}YMx@nlD%`uzovGoX!Z)8fJe|IK;d9R%mbU3u zc$*vVNVh&z_It^@L(@__6@It((Dd?~C4R~4VbM>oy#)`O^mtnF=-=ts7wI`6oiVfU zl7E_zc0G4(m0z~ig!FL7-;2Fg7uz}q8Fs!f>^x=IImNJZjbY~?!_G~HowE!(ml<}B zGwhsb*tycMbEskGR>RJ@hMkKIJMSBIJ~-^$ZP+>8uyeg(=YYe`4TqgG4m+0|cHTPd ze0JD5>9BLvVdt>J&TWUC^A0;l9(L|L?A(0V`TMYQ?P2HO!_LizowE-+mmhYHKWrZW z*g4m*bFpFPXv5CkhMm(5JJ%a_4mj-GaM(HHuye^_=a|FJJ%^o>4m(#Jb`Cpi|4i5( zn6SMuRUV$1u)Q>4du)o&D&Cv$BG8T7LtItwX+o@`2>^q;PmA-gSY#&j!wPz`O$qC&XSKezeJ)7@-zF6aq2Ns^P ze_j{anO?8)z076>Ct%C9)-8ObJ@mS&o8|3(#tj;-@owg zmoL-!kG_TNTT4IfqYK;f7Pc2IY>!;n-npD5AHrHU3B@vYIDCcGtXbxdDdz_^2A~1kHgN^?zG|lj)BTsG5>@{)N}xc|yAD>B5t@dLliuM`?4vr6;Dr3zz*q_tL~P zRz?3{Plx$v-a zeya4q(^c{lPiL&XNCj|Kuyj^uF?!raNB0y8+($`>&c7 zT6T>Zy!CHyH|_r58RFp^KGrnu?7`yvw<-U(IRAT7t|!jhHRbKaxxIRBSImC${t|7n zAD6Qq*JnR&hyA#H{(8UsyZgg-?kDZJ|LkYTfK7YEaZz56xb3b!?HTOU7r*=fgvu|NvQQiPY zeQ~rSj`qc|-x~F!KjP?T;Xlqp|HVgiY}JGP#c^@GuFrW8$N3S*c@uMd?2m0ZZuS@b z@qG2-eqn!X z%YDTDq8&e{wD0Ga{rb74KYrfnr{4qg-|vUqpE<_H^X2k7?N{zwx6?#<3tz9e4^>{dZ+lhl z=U$cjyjR?ZrOkhPE_zj-mtNc#+#j41_7l$+<=lrV=lRI{b31-cY2VK;`}K28fBd}n zVmr2{{kRW(Tut$Oxx9foQD0oSpWVL7EBAk|%5%YS`FU~wYqXi4uR-yA`FK?x=RsU~ zPJP}~UU{y4p50I08{)Vw;@xjuNbkd|8=q~Ma%6|54u5&F7kvBM?V6U@w08qMp!d)9 z-EZwHzGV4#>Z3NOi}T-l{%>*q_j;};&fC@V_BFQ6?TyLpin(5Se=hIka`xl;?8oh} zAGgn6@0Wjff7s6bq&@ea{p9PlY#bNmW8%1|UytLW9dWcTj{Sn~oiSlVmOl~n%l_lu=@r!FggakuX2 z_JbCX0@9dH;n)682uW)_OO}eHd7e83#x4zglUGlsA#Ov&{aGGb+J(_d9 zQm49Y{hg~8NNeA6mFicxe#~|q(%~;&uJSYHT`f%m9>h3kEuZIjOWX{5?`9@aLUv;Cdor_ODc*1z?R=3KATscu^za^v^44R3iy z^($QOFnDHdjkTUu`L?(GRO{R{QM}85UuwT@IH5V$D|M>d)<3x8-P)vmr>lO2>(75a zrMB!U(^Sr1{+oM%y3}jN^-7)UwsrbKpQvBqI{l?jlye*$56rQ0oXxmisZ-sy&bj2A zQoq7=&Nt_ja;^i{1Lj(BotkmIQm49YoqK_Mg8CJ%bH8v;P|khC{RDHbai2BgdZkWv z+dB6$_cZk@T<3o0o~E4Vfad|`S>ZWp#`Q{_>b7;BMV?9OSGdme$}>qh&oR$4%(Koj z-;C>(I@N9KgXX@!Vakn5s(yv*5A=Do;eh>1`OF0;H~h3*;jWjy*>LleB~-t{^-7)U zw)NANd8F4m%PpE0TZRUNA@xF2&##H)arcKwWZd=dCSg#zfnd7bdoaA#=_qodFuwFTzX3mN0RJX0? z>(x}bUS_UWldoyM)=j?F`5tJh+z)21sq0j?t>^o#sdB%Wx!;<6Pv(2I$@gl$hnp(* zvzdF+b*kIe^YhYFd0xysFHL@?^0U_DXDvU2O_k@-%roUW)ottfd2gyb?`EF&CchK% zyQ0bOiu?{~s=QCkyc1lfx@|qbubL|FD>Lt_Cco42yROOay8I4os=N=)ywhB#x@|qb zZ<{LbTQl$5Ccl&O-zLASbKR!O``pYs*>$Sh)^lH)D!&(IelME*o05;C$-g!ESeq)p zM`nIgT&KEiJ)g_5mESuvzjtH(o0zY|SpQb$Yc;m=durx4(RHfZ*7LnEw(@&z=J$H6 zf7A1QG}gcM`Cc1a`5rLyo9;T*ZR`179$Wd|F!Q}J*54%gIT-72mHe!Xt$fdz`6h9l z>bCX#ERN;9%=@;&d@qfi^-XojVq^WSm7n#omG3b#-&C$s-In*qSl-LDUt!)QV|hnY zp5H@bdH=%sT{V{Xax>;#-k+cmiIFCD_qa-%dxzpDbMfGvAlob{H`6#JGvS3 zu63R2w!Dw2U$4}MU0>y~uQAk#J~U^yNqKc!-p3rT+NrRQSLJc8#BmOrv(E|T)otr> zy_)D-g?+tL9@knN_ds*@HKn||E#J@FW2#?a-)}09dsQ6wb944RNqKc!zMpwURKLQ0 zUQ`~>nmC@v=Im#R^6IvHKl6;Meue$Kt32Kn;&`7lXTK9DuWrltGw&$Xudv@&Dvx)a zINpcN+3z&UtK0JZ%sW=~EA02J%Hv%vj`w+U_B)yK>b878^BbZ17549i%Hy|29KT1+ z*}o~2SGVQ+ncujvxt#B3vw!bY9>101_&sgT{!OI3x-H+&{6?#Oh5dW2^7yS6$M-;U z_HR1n)ouBH<{LxxE9~zLmB+V=IKF3^v%g6wuWrltGv7$6UtxbQsXV^5#PL1Woc&Ej zd39U9pY@K;WK*Z(VVG4>xCj(^6jD zmhWf1)9HVO{k^Sr;#*zJZw2pY>Q~s`D<&hHrSXzK7=$2+QuMo`0lcGWKOZaOInCK)GL%=h<@=fOBGs?3$BR^sj^Q0m z`}tZi9@U&ZrbKylTfUze?^68=d%R2K=rG>Vw4d)a#?zX!$HXYFZp-&G<8`WEVUO3T z939C!n)dUv!gyeF_Lv^!)ouBHX1r1LE9~*cQeMU?#rauhJhM4_Op@~Iw!E7Y?`8T{ zVZQeg?^(+8w{hYf4d-`Ns(eqH`6hIo>b878C*I3!TVcLe6JrXLGY-K!8fL7b@;z+k zo7Q!z+wy%&9~vrsgWVsM$FYdx7@M>E+P>ykFwbbs*;{ko*5x}HCp^3m6JNv-yIMEv5oE~$I#U&V*C&d=0)-NsPo z%)`5;cgL+I{{5$2(>cH2OnlK53#aX_+)muO%VKHs!%i1h?!$)vKlkB)PK&0)SKqA8 zzD{{~;k4uhTZnh*xo{fWeM|8+_jFBfufCP|&@Nrm0~h^KyvBeo>B1wo6ED!KOPXWc z&f*7u?wmFsxu)5Kf;+A-a7*@xo0 z@9UUue(n?TZ6|k3n?L%M_}(sgjoEYO(7S79>yByR-R2UX-l1c9Wb4-AbyLT**2-Q^$Vuh>yIoQ`+l`dBttt>YBz~wV=52{%l~pkTF57Y0UMAtMAWI z%XLn@b}jGH!(Un`z1_IF>Wpt#D9w0pHSz5e7EFB}E4;um3#PL>mpbcQ+aay@Ug28L z4(XRg*Hrx#Usxc$aqU{-KIblw((%6+xBsktx^Y@fy!hnyX~Nx&;%g?gPfHEnP~7+P z_Nl`a8;i%Ry+FF8@228ou3R9!zuD&E*2{HBC%xBOy!yr+(|7M|Bd+{5H87URcqPX^ zyWgf2$1IRm+3_&d>2u8dslM?c;uYS`o+U%dZ`t98%$K&ov%+5cOBR+O*-HV@nXx)lTP~cnc^kd&!0{>>RfTo2}_SyaJZ#k}Q8vT0t9vGATD)!i=pXzV;L+jM$)3WV~|7e}w7+!dxDXr4=mlp1` zU8~esFFa}TTzB(8i@ zH82LuI4{ROyKk!9F8Z~$(xD?%XVjm5ti6BSaPfp*Giyzs3=?m^&kwZ|uPVIcV&B(> z?O1rRncvnr>|40ar{C1B9$EOVj^ETK{;st1ar>`p3-49>@Zn=$)=s+cF12}G?=Ndp zw!d5a;VIbPcsJ1vCr;%_4kuMu3fQEsWbK24{B3}Kd$<1o}5-YvQ6QkKfPa@ zd%$BVZ##BsZO`=z|8BsP+Mdf7KK18Q#6MIevUyG%$9~_&CQtJ1ua`SufV+IlJhH5fdiY2HyXc>Ob=0v$fIR zzFD~Av$gGxExhWxlWHG+^@hstfB5Ozy^j>$f9O-S{x284V9b-XrWH&5xlf%~+oW4* zbIWTUubuP2JKFZ$uOF*zvTxb%7e_r-yKuetRKE2ZkJX-Az4ZC0l^&~Iv)xpcPv7sc z+NMXoFTVY|$7=2Go+h3!U}Ejump>6#bXEi7`i$Lk?6cEZx4v7iO+4*e)tPqe1GUq( zpCRts|Nh#>Cw?VvKW$WP%V}SVr#^gN?V^nfe}4PDwcEb^LggL$-BU}S7JlK{yK8SO zSL(Fd{I1%2GYYS?)Sb0uHu_riCm%GtcI#_}w|HS#ZOa?KQTa;8534m^TKe<#cEf7V zjrdOG>mM(eMD`<4Zo>QMZ-2!bZEouH0%ef-&FhM{Z`Vp zO-tNRdv)2l#E0*4eeIDu<`nNS>blxfI~RU-@POK_Kg^->L$1EIHu2HI3!QaM?WB=~ zS30kMZS98&Ke_nTwVgYcZEqWQd9A5KX@9qw{c7`XSNQ#H`qjP}R``#v_pN=mMCs2G z{rlGX4lDfOm3?cwHn!G&uXwL-ZR*E`_gMLg+E-hb@x99UKto02H_UE)VE+0!wZZ-8 zQ=6UVKdbiH$a%!y?R92tjnxY;Gx?0#@-LS5cN%(n?GFbOzG=v*wX2pbJkR+j*QU-{ z_@IkUtnJ>q@ZkfFtF66R;j>OXqSn1*Y4fkI9aejA%fh|)I<&UIfWr4~aY*fgHuI_v zZ(eY4?ZZn8pT5PxwI`M;{e17LgKOJOF8tZ(!)hCD-9hy$V=oPr@sozxjlH~Z%O7jw z$1kL9cj~rfZF0S|v;I%LYp<+Xc)dA$*Tz0u#$IMNY*yQS$HG7Ev`OuvxeFh&#YVLk zUTUv)F5hN@TAQZ|U)#G@d-MCkzr3|}t=$!+{yRN>SKH^I!V@oAvvx(>vacyytWo>% z;KD=xyn5}r&kJ{aakbh{rrk6#=dRlJqz~q+UHZGy&cIgl)!w?flgj5@d*0gkUWNZQs9kN{`#P%p?^D~w!*!zz_xpHC!>5~+zJ0Ohl!kl0E_}fKQyShocMG>Y!hX8oFVtQh^8b*vcu znsuxg{hD>G82y@ctQh^8b*vcunsuzWGLOK0&e%<sT@RHS1V0`ZeoVG5R&@STXuF>sT@RHS1V0`ZeoVG5R&@STXuF>sT@RHS1V0`ZeoV zG5R&@STXuF>sT@RHS1V0`ZeoVab^CC-!<+Gc&MZabptM6g-Yu2%1^lR3!V)Sd)v10UV*0EyrYu2%1 z^lR3!V)Sd)v10UV*0EyrYu2%1^lR3!V)Sd)v10UV*0EyrYu2%1^lR3!V)Sd)v10UV z*0JKsoH+W07%G*|ZcZHinsuz|pkK3&6{BCXjuoR{vyK&`U$c%aob_wgv10UV*0Eyr zYu2%1^y>$w743$8%{o@)=+~@c#pu_pW5wv#tYgLK*Q{g3=+~@c#pu_pW5wv#tYgKM zcms4R@m(sPUAzJMHS1W_LBD1lD@MO&9VG82y@ctQh^8b*vcunsuxg{hD>G z82y@ctQh^8b*vcunsuxg{hD>G82y@ctQh^8b*vcunsuxg{hD>G82y@cthf>sZx6zh)gPM!#kqD@MO&9V zYu2%1^lR3!V)Sd)v10UV*0EyrYu2%1^lR3!V)Sd)v10UV*0EyrYu2%1^lR3!V)Sd) zv10UV*0EyrYu2%1^lR3!r9A7`tYgLK*Q{g3e6M-lHewxBKD*dC^lR3!s)K&bI#!H+ z%{o?$e$6^ojDF2JR*ZhlI#!H+%{o?$e$6^ojDF2JR`W9G*Q{g3=+~@c#pu_pW5wv# ztYgLK*T3!hz8L+Qb*vcunsuxg{hD>GnD2DH*U_!$SI;%`UGF*QJa0vur|O_zvyK&` zU$c%CqhGU*6{BCXjuoR{vyK&`U$c%CqhGU*6{BCXjuoR{vyK&`U$c%CqhGU*6{BCX zjuoR{vyK&`U$c%CqhGU*6{BCXjuoR{vyK&4<3A%tRORS7&yVN%N@7qocZq(@I#!H+ z%{o?$e$6^ojDF2JR*ZhlI#!H+%{o?$e$6^ojDF2JR`aUp*Q{g3=+~@c*XO#RU$c%C zqhGU*6{BCXj_pMq^lR3!V)Sd)v10UV*0EyrYu2&iI4*G(CLqy2clmGXa!@pde+%F(Y`$BNOfS;vae zuUW^6(XUy@iqWrG$BNOfS;vaeuUW^6(XUy@iqWrG$BNOfS;vaeuUW^6(XUy@iqWrG z$BNOfS;vaeuUW^6(XUy@iqWrG$BK!4BLpkK3&RUPze*0Eyr zYu2%1^lR3!V)Sd)v10UV*0EyrYu2%1^lR3!V)Sd)v10UV*0EyrYu2%1^lR3!V)Sd) zv10UV*0EyrYu2%1^lR3!V)Sd)v0~!#h|lBL<9kM2$xR^s$~g-S=+~@cRR{f=b*vcu znsuxg{hD>G82y@ctQh^8b*vcunsuxg{hD>G82y@ctQh^8b*vcunsuxg{hD>G82y@c ztQh^8b*vcunsuxg{hD>G82y@cteBWVVh1_)_>L|0|1Ix>*f!^bG@xIzj#VA>Yu2%1 z^lR3!V)Sd)v10UV*0EyrYu2%1^lR3!V)Sd)v10UV*0EyrYu2%1^lR3!V)Sd)v10UV z*0EyrYu2%1^lR3!V)Sd)v10UV*0JKyDdNyC;?OnX&^u!EYu2%1^lR3!V)Sd)v10UV z*0EyrYu2%1^lP4n6{BCXjuoR{vyK&`U$c%CqhGU*6{BCXjuoR{vyK&`U$c%CqhGU* z6{BCXjuoR{vyK&`U$c%C6KhG#CD%Q4t2p#*sb9%yLceAmt8(;f*0EyrYu2%avwqDw zR*ZhlI#!H+%{o?$e$6^ojDF2JR*ZhlI#!H+%{o?$e$Df+V)Sd)v10UV*0EyrYu2%1 z^lR3!V)Sd)v10UV*0EyZK#2$C*kimx9OD?`7~c@1U$c%CqhGU*6{BCXjuoR{vyK&` zU$c%CqhGU*6{BCXjuoR{vyK&`U$c%CqhGU*6{BCXjuoR{vyLrwvVP4vR*ZhlI#!H+ z%{o?$e$6^ojD8()!*60@REbsP*khbZ9OGBw7}pY`U$c%CqhGU*6{BCXjuoR{vyK&` zU$c%CqhGU*6{BCXjuoR{vyK&`U$c%CqhGU*6{BCXjuoR{vyK&`U$c%CqhGU*6{BCX zjuoR{vyK&`U$c%C6F*BFEyo_?lj0b+6vud`82y@ctQh^8b*vcunsuxg{hD>G82y@c ztQh^8b*vcunsuxg{hD>G82y@ctQh^8b*xzWb<4u&*Q{ezj(*KLR*ZhlI#!H+%{o?$ ze$6^ojDF2JR!nR!F}@soj7y7SyjmRN*kbf+*0EyrYu2%1^lR3!V)Sd)v10UV*0Eyr zYu2%1^lR3!V)Sd)v10UV*0EyrYu2%1^lR3!V)Sd)v10UV*0EyrYu2%1^lR3!V)SdC zhZUn=vyK(Vyn{G$M#M2sA&&VAG5R&@STXuF>sT@RHS1V0`ZeoVG5R&@STXuF>sT@R zHS1V0`ZeoVG5R&@STXuF>sT@RHS1Wh^y`$u=+~@cRgQkmI#!H+%{o?$e$6^ojDF2J zRvhz9;>c$a$NZEy=B>o&SK^7ePtdQ#6T|3N;)!AOEAhlI`jvQM82w5-F^qmCo)|{I z5>E`HUx_D%(XYf4!{}GyiDC3>*0EyrEAhmXqhE<9hS9IY6T|3N;)!AOEAhlI@!G@_ z!!iFTj(JIO%vXxhuf!8mAN@)^F^qmCo)|{I5>E`HUx_D%(XYf4!{}GyiDC3>*0Eyr zEAhmXqhE<9hS9IY6T|3N;)!AOEAhlI`jvQM82w5-F^qmCo)|{I5>E{0MfAM?&C zkNIeE%u|ceuf!9xE&7#sVi^5OJTZ)ZC7u{YzYE{0`&l^yaKsywIF^qmCo)|{I z5>E`HUx_D%(XYf4!{}GyiDC3B@x(Ctm3U$p{YpGBjD97a7>+oTQhzpH6X;jsiK&l% zC7u{YzYE`HUx_D% z(XYf4!{}GyiDC3B@x(Ctm3U$p{YpGBjD97a7>@WNasIul5l>8c#3PB(uf!8mj(#Pc z7)HMmPYk19i6@59uf!9>=vU&2Ve~8U#4!4mcw!j+nsuxg{YpGB<>*)9iDC3B@x(Ct zm3U$p{YpGBjDF2JR*Zfno|tmE`HUx_D%(XYf4!{}GyiDC3B@x(Ct zm3U$p{YpGBjD97a7)HMmPYk19i6@35o=_ZdhT{C)OFo?#{YpGB_0g}y6T|3N;)!AO zEAhlI`jvQM82w5-F^qmCo)|{I5>E`HUx_D%(XUy@iqWsc6H|_UC7u{YzYM_jQu;*G`VSK^7;7X3;*F^qmCo)|{I=6P5#`jvQM%F(aH z6T|3N;)!AOEAhlI`jvQM82w5-vC6Z4C7u{YzYC7u{YzY{mJkN0C3y33+Kpgo6V)QHV#MDQ>5>E`HUx_D%(XYf4!{}GyiDC3B@x(Ctm3U$p z{YpGBjD97a7)HMmPYk19i6@59uf!9>=vU&2Ve~8U#4!4mcw!j+N<1-)ekGn5jyzCt zc^)=vU&2Ve~8U#4!4mcw!j+ zN<1-)ekGn5M!ynI45MF(Cx+3l#1q5lSK^6Pp7ks7#4!4mcw#uu!;(KMj=V5&=vU&2)n+A^Hu8B@9(jV| z{tva6PcQYix@Nv~)hFXszSP=trw2YO*KXvw-`4s+)JOgQ>#DES9%v} z4`w^IhiQ*?Vf-7}UzFEfp6fTcer~5}Ryz%&n%sW=+vNS`e{XVs@^)k0&)nWv_doAv z?8bZT--CTcc^!`WO>nd$j`qcQKkQc={VC<8pJOZi7vs~*{-Rv_gX27?JkF2X=e&vY zU(TnP<7R(s%lY8Ez?`RiTbLzuF(nakD>|^TGb$xGw5{c&@6vnLlbn z#b*_+vu)H7SNvLMn|B}i!n%JVUsxRZ!s5sm7Dv9YIP!(X==+$bCeE6CVUkKAV+d*nWgBllSx zxzFOreHKUVvp8~}#gY3gj@)N)a{+#gWG?jy!I0v7?``|KP~OmzzP+ouqr&ybN!NLZoOCf`ND&KB zkDPRsM^3t!F{Frvs7Fq^$|EOT969OY$VnGRPP#a9(#4UJE{>dZapa_nBPU%PIqBkx zX0-ng+Ud(t{#C6mo zzh32$UoVdQdU52}izB~Y9QpO)$gdYy#y#v4MR|)F1F4SxRJa~q0Xh%i6(A0;0C9K) zh{G#D99{w9@Cp!zSAdwYy@*k%hgX2g8QY5(m3nvus64y^#Nibn4zB=lcm;^VD?nTs zyR)Adby49_T!T?}0dc4+@(MS!q_OBt@G6|RRLMau7=diYU@!;eB7eiY*HqY#H5g*f~u#NkIF4nGQU_)&<% zk3t-N6yors5QiUyIQ%HY;YT43KMHYW9uOaRd@Lz%Xi0N|)%nm0*TY*w=OMf`#Nn+W z4sQ){cx#BmTSLrPc*Jzo!&^h;;jJMKZw;}=!b?n7J-jtk9^M+_@YWEAw}v>pHN@eq zA+F42vt9sxr<6Ceq!}} z5rxXL;_wL(hfj!@aec-(c(+uzp(Vv;RO3=ATo2C^ z9ea45h{N+l9G)lQ@H`QR=ZQExPsHJQB4&;vV(scX7ta%wGe;4zcJ=T)QF(Zth?%2^ zSi5?7o~S%LPsHJQBF?dP@*(9qR=A-h#TQj$t14U%{}!Ex@NW@^e~UQ$Tg2htA`br+ zarn20!@orw{w?D0ZxM%oi#YsS#Npo}4*wQ$__v6|zeODWE#gXCoPD+_Z)iy|a@F|2 z3fIGnM&}{CXvE<~BMvVbad^>)!;3~7UNqwHq7jD|jX1n$#NkCF4lf#Uc+rT%i$)w? zG~)205r-FzxDwmRdPZI|sG%jrc~)awD_jp>9i4~p)e(oUjyQaE#Nn$W4qqK{`09wm zS4SMaI^rD9iLZ_rU)YG}tcS0T%EMPj9KJf@@YNBAuZ}o;b;OnUWc&70-q4a_m8)^u z6|RRzkj_JR1c}2VNE{wP;_wI(hewb&Jc7jG5hMpM{1(30ZqtGNahu7}@|&O`VeiNo(m9DYaQ@H-NR-;p@{j>O@2 zBo4nLarhmH!|zBOen;Z)I}(TAkvRO0#Nl@&4!`7#x*hj)|C zLwGld!@Efw-c920ZW4!glQ_Ja#Npi}4(}#$csGf|yGb10P2%uw5{Gw_IJ}$0;oT$- z?Kp!&6Hfo?7DY)DnlMmN-1M#NnwW z4o@v{cxs9BxG`%^HRpzwlz&>yy{&LP{K0hW;SVMbe=u>5OUEBf9R6U1i$9n+{K3TG z4<-(OFmd>UiNhaE9R6V9@COrzKbScD!NlPYCJuivah}JSwfr>FA}etP2Y(-ViEo;dvU#NnqW z4nI9{`00tmPfr|vdgAcY6NjIkIQ;a);io4KKRt2y>50QnPn_qe>?7oLR4H#!o8&KyVyaC1G4JZz8Kyi2jigQj1-hkrp1{8-kpg6n%#o-Mo4sSqlcms;V8&DkH zfa355Eak-;P#oTX;yhVio@qn96pEQ@HrG${M_VC&fFExV@vXO ztNPki7_SRF8+9JSvr!zLjpFcZ6o+S{I6NE0;n^q-&qi^0Hj2ZuQ5>F);_z$~hi9WW zJR8N~*(eUrMsavHiYuOkuZ>io;7&9A28@@X{2Am!>$pG{xbiDGo19 zad>Hp!%I^fUYg?Y(iF#gra5b!6Xvcs_W$lau~m=U3Ts^p=B~Jo;R`AbUr=%Qf{Mcz zR2;sb;_w9(hcBo&d_l$G3);lK!WUE=zM$gp1r>)cs5pE<#o-Go4qs4l{O&hr@~v8o z*KvHmag6pj)$zu+oH#sA#o=)(4v$lDc$|vE<5V0Tr{eH96^F;EI6O|p;c+Ssk5h4Y zoQlKaR2&|s;_x^XhsUWnzQda{`Bp8)uRF9A$7sJ+9dG!xio>r}9Dc3h@M{%^U#mF$ zTE*elDh|I^an85GuT>m=t>W-&6^CD|IQ&}0;nyn8`BwO~io>r}9Dc3h(8bM}e5)4Y zIUnO29HYHwb-dv{D-Q2jad^*)!+Ta7-m~I7XNC8yIJ{@Y;XNx3?^$tp&x*r)Rvg~5 z;_#johxe>Fyl2JXJu43HS#gY0HD~gzTFkl$G4{wY+DBK%8$PkKpjk$7hcr}Z|t63ag&EoKC7Kc}}IJ}z0;nge-uV!)1x5BGg z9A3@h@Ms^Yi^F$X9KO@y@SPTi@3c64 zr^VqrEsnUO=1jg-i&+aVV#zp0yeOOaM(4hbSTb>VXp6%`TO1zR;_%QGhljQ}Jha8( zp)C#%ZE<*Li^D@(93I-@@X!{AhqgF8w8i0}Ee;QDal`>OXY#FD%zBOy+sQHFr`m*O z<~l}fr#Sq;#o-4o4nJ^l_<@VV4_q96;NtKD7l$9XIQ+oH;Rh}bKX7sQfs4ZrTpWJj z;_w3(=X@*tz{L@l+nmX_YB6h)Myxf*h$nCpV_00rh_x1nx4AgH&BftuE)H*Vad?}H z!`oaO-sa+*Z-uwHIOkj8Z7vRPb8&c^i^JPo9Ny;Q@HQ8Rx4AgH&BYNX-<-*}YBB5T zM(zX0h_7{>F=eh}m~(=HC5c5(Q$iz9EPIg@YIV%CO^{3DJLZ+3E#bi9#^Bo5Dcad^&)!*gC7 zp7Y}HoEL}Zyf{4P#o;+G4$paUc+QK%b6y;t^WyNF7l-G(I6UXY;W;nP$A#y7b0*)a z#jI~0xq%!b>kDY^isvzM19j}-pDzyod~x{ai^D%(9RB&@@Xr^Af4(^U^TpwxFAo2F zarozp!#`gf{`unY&liV(zBv5z#gW(9oXNM++!ee?j98YoNc#0#(Qye*-;>ht7M~>Fw ztOY=wdaMN?j9u@-V$8 z!hRNju+96N1@Lyv@2wj4u4ude=33Z)b1m$@xfb@{Tnqbeu7&+K*TVjrYhhah@SAI4 z|IM|q|K?iQe{(JDzquCn-&_m(Z?1*?H`l`cn`>eJz5LrTzqjIC1Imk^Yas0B8VLKj z2Eu->fv}%zAnfNF2>ZDP!hWuSu%Bxn?B^N?`?&_fey)MApKBoO=Nbt6xdy_1u7R+> z_u%cA-&-~8UD1#J4g_I;2ZFG_13}o|fgtSfKoItKAPD zLD=7cAnflz5cYQ<2>Uw_gl$dU_?kSeT*@AYp$;kg&faNZ8*IB<$}9683il3Hv*Og#8^s!v2mRVSh)Eu)iZn*xwN(?C%H? z_ICsc`#XY!?Rg{TWxO5pdn?Y)(DO+@J44vd&JgyqGlc!@3}HVzL)g#G5cab(g#GLc zVLv-V*w4-o_OmmD{p<{3KRZL%&(09`vonPK>on6BI&Mskp zXP2=O2Ob_x4CyM+CnUBdp(E@6LXS6`=pXP2=O2O zb_v^F0PkLVJLdORoC896@pC|g{TvWsKLUr8!nTjo#6C{K{NAcz?}~o(cjyWGJM?V>p(pI`&=dA|=n4Bf^o0E#dcxMe zhW#qqk}$uw;!G3Di=SyCY`?eSOcP;0(?rVDeUjG6!v#o3i~@Ph5enD!v0Q6VSlHku)ot%*xzX>?C-P`_IFwe`#UX#ZJ&xW zS>BHMy%p!PP+t6e7GXc1McB`05%%+0g#COLVLzWm*w1GX_VZbU{d^W-Kc7X|&u0<# z^I3%bd=_CppGDZuXA!pFTX8;%u+1Bs&+>N6@2wj4uINX9$E>iwV^-MTF)Qrvm=*SS z%nJKEW`+G7v%>z4Sz&+2tgydhR@mP$E9~!>74~<`3i~@|h5a3~!v2ogzP_C|#eNlS z@%ILU`Mniq%?SHhGs1q>jIf_IBkX6*2>V$x!hY6_u%9&}>}Smg`&l!>e%6ezpEV=w zXUz!vSu?_Z){L;9H6!e2%?R^eK=!U^SHk?>YLLAv+V1as7WQ{O3;R2th5en+!v4-@ zVSnedu)p(J*x&gq?C*RQ_IExD`#Yb7{hiOk{?2D%f9JEXzw=qx-}x+T`&5JMSJ9S) z`MnkA=1^Yz+#F#)H%Hjd%@OuEjxunYS;*oFNa?85#Ic42=9yRg55UD)5jE^PZ$gX~w)mW27e6=wiZ zUi=IoVLt;%*v|kG_A`Kl?e|uk0VM2a015jUK*D|okg%TtB}LS=<^35z!hQyjFz*Ot?~1l0%7Ana!%2>Y1`!hR-#u%C$_>}Mhf`1U4c1Un7u17 zXA84;1?FsF_O8I3EzI5(n6ri1y8?5zFnd>E&K73x3e4HU>|KHFcPoSJUA+zK99{nn zi_X#I{cBc7=jihOH8AJs^8Ph2=jihOH8AJs^8Ph2=jihOHL(4LWl-;5Gt4=|KF5Cz-t~Fy|z*cLnC0WcIGWoRiGn6_|69*}DRB zPBME}V9rTq?+VO0$?RQ$IVYLDD=_CIvv&pNoMiT{z?_rJ-W8a0lG(cgb51gQS72}B z+cCelqK%Z--bP_>qp-J8*xM-VZ4~x43VR#Tx%M^+dmD!+_cjW98-=}%Ep@z&!rn$< zZ=0?7k}OzAEg#D(t>0?7k}O zzAEg#D(t>0?7k}OzAEg#D(t>0>~ZGpm_4gO_O56<=b5v21@@RD>@i2!V~()L9AS?+ z!X9&kJ?02|%n|mOBkVCp*kg{c#~fjgIl>-uggxd6zZd#0o$FW9d4DliVh8d&m@9=R zrSrVfd5$HW^BC*BhPL~9Pk2%~11p{5SD>0>dr~U*eJJ5c>Fk(8UcItmoYVG0KlS~F@elTWRbk&t6`qvN zTlwlQPHKqnw0Fv>zS$7>!JZo+?D+t~lhPR_do1$hhIyU#9=Gz24f8$N^IL>Hr$u;D zI@e>nDMvM|=VIcJO>}wbygJ zg(szR3e3+-___JN?qg}Y|7Jn$_1`H7PfG9hxA@jYe6zUMMcjKYybs^zwJzp0oA0`q z@7@dVkhk?r7wZ{Y=X9~oc`v+o-PW;PtYd9`+r|3Uf48eKKB>N|-0ojG?qi8>c3;!Q zeU1MPUFDPN`@QYHwc|dPw%gy1`&cmfXxztwC)IaiTR(T)$I?dY|Bm}u@O$As(l)+_ zxsRp2HtvVHj|IOM-o0#beVF@L+H3KCnEP0;zn4jPQhi^s&F911$I@P#=ZCqE1^c_j zgeTQ^{MtHhnEP1TYwNpV?qk9H#)$h^@TB@)T)TfA=027-+PZ$2`&h8;ISz9l3!YTp zCHte-7a!(6mNwe`+%WgCV1Db#eJprVegCSrmpyduU$H|0+deGs*A@2n>k3aw?<{pc zSG(N*h2IPB`SkeK(bpdLgwuO6*@qqWyt^_fy&Kc#HMQ60JK^+hN%mofJ$JNBO7D~O z^^Dr<>m1?qKE^VszJt-%v1+fcZ-x0CSmg6hs_!lI`xmv>?`wql?Nt0GWm0|DpWnBt zy?#F{%`|@09cBRKv`1{`^Y#z3?73e?F=9`g2R+_rkl& z{JFH+>(8r&-wW^i^8E<4*Y_!e`OQJRD`Qf9N0#qHslC2GB}|?^_p!tQa`U;51(Tc4 z`2^tq_V-Hp{-fIB`;x-sw#Pe*$YSEm&o5GYJ?}{Pz3^@s&nr`VJ>N_?y_;o{eIJYG6RN$Q zXDDp&odj9ot+vQSWmr*VorJ zTdnYGjTigd*#Cv?`^M@C+jWC>y|D2O8n1lJIvI*#jbC-*7#cE6-JK9i}EVU zkrVZi6FkTXe*T7Bz7Ku4F7$*i^hb{M*;3vv%3E(2^^3O)9%1JfcDcf?kFe|6dArbG zc=x%cUK%@kIqelj4tAs*IoJ{Gb`v(a*i)GALm#dSJ>d)ebAJV%>Y!tz?^pe_`X(n4*5} zuY^mgBY#0xt1o|{4d5h8{z986Pr8+)bMd}If5l{M3QldOzWTs<)HmQ{L$#IvQ|^5y z?0qMU&EV~M`f&&La{82ZY1}2A0`|TWPCi4s&`0I2XGeY4UpU5{muuXC-43eb_6dI3 z(dEjHVDCHC@xBxGev$sUzXID>j=m$dMBg!%M>xUWcPh6w>i?97Zs5=v?0rYvh`tk! zwtId0PUT@M%EN}>ur1j8PC7(iP#%2*#z!n>o}bE@3!?98aQFb&`Bm<6g~;`#`vkw_xm>jq?0u&?-gm;@chW!iSF9PV-|JXQfPKw?&(ywV5M~Z% zPNm$}48p!<=*xX=Lmgi;41Nnt6dw`u^<-TSRjx`K*Vr>KVHNznIqBC#306TiQ?CAAbvU*dOfusQTWI(%;%eKeF~4>EBepOFY8PFYI!K!>_3C{m9xc z`cc^XG0G*+>&IH1cEwsf>=trktsZt(x%Z=Rj4wE24B{s#t}2Ex<|$8cxQ>`fdBjX` z#7uC+OmM_Z@c*r~%I3SyrFF|zyY5@>bJaY;=RCG~eeTZl3;%u3Rq6-!UPSo8Dd($a zy>cnx)gS*y^{FRE2_HMxebon_T}k*)!&g-+98wE!^uV{PCr(&Pc&qzQtJb@GUE%BQ zJ*66Z+1kxEAD^*+_q}PL*=F^_g-;v3e6!x=w+S!)mHC=87kgdU{?_*Yj{5d}ZS{oh zy4tSq@yBPZjaQgBX7ZxEL^*PzK5~KwIl<50kjwX>57&jB@P+=!VGi~<42x!5!G!Op^57ka`M`se;) zp2ep4>O1K(KG#nYYw16Hc#dY{FWp&fVPkF7?sGN&JpN}DW9^Ugy|4N7(ESx-ZSOf2 zYWC_Lsu*kcoH}E(`ljpG)ZcyOC7OeGe57LBJuozLbM|f<)m(eZCzos1-s7o?F?hl1 zvp0{9-?WBj%o?McnNNPXdep|_6EDo&bh~U(!#Ts5uUY?{D9$G?UZZ(&aH@J^8>dg* zyFjz(v)k72UwqpX&AwNiEdJxpTD-aE7rWH(@ATT#&AB_DF8(v#zg)BK-Fw&YAF%Zd z%>#RXTl{x^>JRk=btnD}S03H$w$3>5zw)D5n^~_sU;LNf^GH3-ayN>9VA^?_Pd$05 z`2RlcFZI1o-y;5*URtpE;Ilsv|Mkt^>X~-?srcbW1~yr6hb5a29#X_#e*BO6p0EB~ z{BR=!`yBT4RLw2z!{QgW$-qAI&pl)F>lq&tKitT`KG+5u!GG8Jvo|}>_BZjvjSTFA zZLksia3cfzU>j@%KitT`KG+5u!B2nEukgc-4D63>uo3+9Eqx3>w!ud5)3@|7{MZH? z!B5}P$MEA{_!<1z1{=Xo-_pnM<9GNU{PZn-3_m`IFTzjX(#P=QkN740!~n)W{PZn- z3_re!kHSx#eQhp*AK%1B;isH=1%7-JABCTC<`~z%4gK*=d=!4_F!#9rZRk%q^N{P` zhW?Z@C%OJ@=x_EfVSm-Jxyto#Lw~b>3HzJ=ZRl_IFJXVvzYYD({w3^h{!_w#O#c%4 zoBd1J-~6Y9|Cs$t*x&r8g#VcROW5E1r-c8Q|CjK8vwsQuoBx#XAM^hb{%`(M!hg*F z3uDavr-c8Q|CjK8<1R6N&3{VxkNJNI|2OUu)S43rg3*Me$6&r#2@S1F5;)z zri=JvecMI+G~09$f2?o2h@a-0UBqy+O&9UU`nHSsX};M-Y`4DcB7T~0b`j^TZ@Y+} z=9^u_d>dOGe#!W5*K`Fvez$*t-~C7Yu782w?O)(`{}I32zrgSQBYwAkf#3Z{{OpAP%``0cQd$Da=Sd;IL^Umw36_V@VHVSkUG;`jI?evhBxx3NY15x>Vz z@!QxU{)^w^kN7=)ir>Z-@n8HNKgDlji}){okDubVu|@nBKVyqAhW;Ku#cyMa_%D9y zFvhTt$A9rt&KSc!9{F?{Gus`bu z@%#EG?9ci^{J#DXzpvlK@9PKg`}#-xzJ8Pc`}#-xzJ8Pc`}#-xzJ81G%lcFNzWx!v zuis+)vi=mmuiwP)>re6f`c3@Ijf^pmKdceO@9Q`5GdD8EJpQnLj`7R-GvW{H=NP}N zKO_FIeilD#6UG?*%iPEqV|+2UGsfU&ZNeDCKbhMZV;(7*}wzo?={~GixZu z5cH=jG*KBj+IN|TD zbz5`8gbRiF%l~y>Y~NE4%ynE3hHpLN1v7S#=jA2Jt$r8vO->g)#@_|M{p~`oecy#X zc3l^G8ebRso1Ec`&iv@o$nx?6_WB*zd4!!`*yRelKEkf2u*pGxVV;j6&)Y?Nqds;J zMqlJn$L%Ie`;h1QU}s_Mfjr8MkA9KmwhVS$LI~SFBh3<1E6b&%9~9>$v`T=~Mi82lnTv9oV0v3j1?Z;do9+9rm<&z6qZEJp4cRJp7&XlNn!~ zVsM4OT~qIEKKZu=ryl(Bv)9)X%_p~9aN5CpepG6Fa-}Dx8(e(T8)|&=!Lc(8E_B3A zH9oof?K2L}@Y$Pdd~)64nFgzCZmCZ*pPX;2nFn`2@z(kb^T|7xez7@Wg_RrlZ(Hdf z%`!`@*1&)LRIfLu{CSNA{uj#>gD>n_H}H>YrW)Mj%)ti!i}#s&@Pj+8*~sU=FwNlH z-C7O&KYwYO!KY67NCW@lzxtnM=a&x={~@P5)?B^#MDag2{}as{%N{QNo7aD;nc|Hj z#Q)?h&o;j~?I`hoYtz3sM?QA6_}i(TZ&v){G2%b+eJ?b-jyqQT<1YSjv*ETEi~rIW z?`%Ht{>#MwQ9IA>(VM;}{y#l(U$e`iSBih*&-|j9{)0ad|7=@4(5(N^55+&{gAX?2 z7rsXPGu-*BX7#^ZBYwD%fqmdc2KIp)8Q2GIWMCh-k%4{SMh5nQ8yVOKZe(B|Y=e#9 z$2Qmqer$t{`j~S>gN^!_b5w(k`j~TcgN^!_b4-Jc;Kw%D2!8sOK8ByZrH|pKZ|P(B z>0A03e)^U^hM&HrkKw0pSF}EcpT4D!;m0@eQTXvqd=!3s6CZ^i-^54Z$2aj&`0-7A z6n=aYAB7*^#7E(0j$^#R4<;_d4<;_d4<;_d4 zUy}YM>0grmCFx&6f3ts=?B6B(cgg-;vVWKC-zEEZ$^Ko~-~6Xb{?jG@>5~6+$$z@! zKV9;lF8NOv{$u{%CI9b||98p%yX5~}^8YURf0z8f3;#FnE{)$Vjo&Vf-!6^cE{)$V zjo&Vf-!8_l*``bJr%UmtOYx^m@uy4ir%UmtOYx_R_+x$BrTE#U_}QiSIh^9>aEhP9 zDSi&8_&FT$(|mI{#sA?H|A$ljA5QUqIK}_r6#s`){2z|^Z)0ni@zBSgX@&dvGrh3J z*Bdhk_wi>Y;XeM%EZoPRS%mxeGpjJ;%k?kt+t@6zd^e^z+*h2pTzl|;QFYw#g zLjMB4jV<&q@Y~oz{{p|;zk}b#7WVJpx3Pu&JNRvEVgC+(8(Y}FgWtv$_V1+s7pB4f z9sD-7uzv@?`;Yi-Y~erRx3Pu)h~LH*{v&=HTlkOoZEWE`;N&-12;0T58TMWK5!!g`*{2jKeoX}z5g6e{1HF4!A8CR97X&QKeoX}z5g6T{1HF4 z!A9_V{1iWZOCQ5e-_pnEPv6qV@YA>SG5XWD^fCPOt;Nq_^rvs>WB6@s5&wtrAAA!Z zg&*IJ}EVf_>S!}=%uhxJeR59^=sAJ#wN zKdgVk|5?9@-`8*A_w}3jef<{x&-yL=pY>b#KkK*ff7Wl}XKrMSVSnbvG=5osil4bL zjbGNE;%9D5Xv-y*}^V%Oww-a>Hns^4?YMdGBD)O%i|P zK2grI0qg=c{gw9)#(vll9QM4i&sVRh2M&9J!=5Ui{5ygMJA^%Z`@D0%Bgp*~IQ1|2 zUD59y*!@A+{X{r&*r?-v)tA4SGs*Z;JE@cM$|4t6dB~9qN}V(P_X}XpE7N%KyfWd) zHKk7Epn@Ye6->Lx-SP6sA*VihY$}i3SL#GgEI4vy!KM#+Y?AA_xWXwvhj!`r3)J`W zNiL5%_Gc|$u2{aD_BZW0c}aV(CGEGCw6EH-&qIIMGw_zZ9kAugwU#d@Z25An<;w|g zb^mECd1chG=dNwaH)~TKTAT9I+LX7}dR`gNY>j6m&#m>mGL@6R1}}AxgFLY3mG!vK zD-$MP40+V?yfR_WE903k`b7R7dPZI!`Zvg<4tZssFBj!CcvPP9)Zj`tDKx|)e&T!j)M4R$D$a#sp6mni7FQQF(9c{`>A?Ky@ypA^IrD)ID^E%p;mjZX>)sXWN zc^z%aOKE*yzGl3qyp%TO)sXWNc`2>$%h$FqhHWA*h@6+mOKE*yzP3HG*7xNb_Ol^iO$Bt?$cA|CHC%`o6sMC;r%&5x?)ti{JOUdrm`bS=z=1tElLx1gkVt;h-yfXCH-lyB2eR=7x zI(=SQOU@4apl<)j>qGy@i)+a_vN0z6kh8=7DE&*$k&Q9g$M@xH?C<;XVgJbM!+#<# zv5<4b-mUvji2v8@ons&0mlwb9 z%gg`aX7AtqC-M^U|H!Lk{6=0V{vUajjNix$#s4F(lJOgPp&DBee|%qF`uo1T#uqtv z*vQ9kzx_y!7{d`I_AK#Z3 zKYdFd!|(g@is8O5FMf-kk(aBSM|>3h>0A1k{`Gx%@`s6^k(W!(3;Xiq5?lP~^Zc>D z@6n6j_vpzhHvbvP|0n)OUa`fWk>3Ik|0A#1;?KzM0z!ZC3Y7DRkM{9rr<`F#qX)M}YlZfAR{#{-yVy{`Up&ryK+3ugHrC{mD0A{))Va(4X7`=C8<$ z2>%g3Ih(`?_}%{GMKFIwUPsuUyom50@-D*u%hk`#*Ud%Gvb1 zj_`l+r@W5vfAOch8s%(yUI+76&ylC;Kyg24B@}kA>^KaOnylC9`qbl6{O zME4)^qQ&p)H}U)WLHxe{k^a7ZlmGkrNA^#7m9hSj{=R;T@vAjrAAgh=Eq-6W#rP#J zTKv9#6Th!NHNJfPCVpRkia+JG#`;bCzW$8(Ltb=@U-F_O{*V_PXQ$J-|L?7&AhBO1j zU9IO|_4kZ#=7Y5`e< zk^k0u{*~@Gk>hz~QC{Fr`C7r#QJ(U{rk9{$0-irOV`J@9Zh) zoio_^UwQWaPWnm8D`dGY(cy!d@zUi`idGY(cy!d@zUi`i-+M9^sn#B57NKBFF#2C z`o27QU#;)UllRs7zC3wft?$c=-}mLk@B8xN_kDTs`@X#RiCs3{#1HnoGOa~DuT0qU z%7i_yOlwQeD--s-GGWgvLx1+=L;uK&L;uK&L;uK&Yfb;iiz|#R&nqj8Ezc_}j4jVA zE50uu_K&>2*6bg7eXZF)^7^oU|y$m_%Yk=KX)Bd@RczI^yk+ zqRm+&d5Jb>jpQZToHde{Xmi#`USc8Vi@kID*Z1Ya|0A!m^?mv9|H!K>=KqmbSubB8BdBx^GeJ*_;fBIZ{ z#xG-w@rHdETVP-F2xA|{7UjO?5k`N;7UjeT*PpzC(4V}r(4V}5(4V}5(4V}5(4V}5 z(4V}5(4V{l=C8<$VE&4{25~75-~Fdc{v&?(pAP*~UPnoJDdGPe_Hq9gf67Z~ZT^b9l<7_xL&N^H=0GMf@bMDdOia_V@TnUQ@(>^1hhAA}=fAKY3XZ z|Hbd|f0+LD_%D8s|Kj)fFMjT2STDj4_PjD-&npx5yfR_WD=XCZyfR_WD--s-vY3BE z|HzAr`8V{Byg25s$csaNtr4-0&%dF+)`-~0*AMF7l-Gy-Bd?G7EAskc{UH1J`XTHe zd3~{dkbQjp6aEubX{6F$4@&CxHWd4f0%98Rb8NcL3i{ICuF@7U2l=&<2LK(l27s~jJywKw7Px-&E zKjr_veipy4pT+O%XX)?j=ZHU%*UJ1Ad9B6Q&k=t*Y~=BiylCMk!j@vQEv6CsBb*N@EE@^{Pqz>rhO-jOp_suOp{T=gG`el?Cpy3fmFXr zJXPYalH4lkQzbpCq<@{-Rj2mW$qw+e=!VQ>H{_}unY5WY$V~RHQoju3{@QJ+Ma%nE zyjXp=L${FdtKWZk=#_8HBYeu1Teg=!H-qqQOMRzZW&OXm)E~R?oh=_QWqb#wF4utJ zfC~&aZ3H9J$_Jv{>Q_R zD94t_0Aou&V9NLoOkHGv;Xno$Tju^+ck$&U8~LA@V~P66HR|iZJD&J{-VJxo6UY5! z=$wBpqB_S<^~Lt(Z_O#Z?&24>H~(}B;qgoTs>6R?D8@D5+=ajV zGx?Ou#wL^cx^JgGGSC4YWPsu41E!4cz|`d$FdT5f4>vNv{7dBnseYAss>ELa+6+FZ$W7+kvq&3x8scbKB!@d9k9e>)G#V?IUbut$inKb&FjiY#hb72B>e`h4z8X zUnn1na%6z1j|?z8$NT5I**tE359f2ZX=8{)yFvFaAaNz%90~&RY6q;e+N~pt@~`DGHp+-h0M?$rDC? zDj!Pq+r-l*{x->NlRj@I zsbkkx=*hLohHbKKn{3{uzGzb)wW;rha-SOh-}=BjXT30hpWJrdazlsy^)BIy4?cTn zp0mC#pSkV4i-%^O;W(9#-s#s?XJeILeDGrJ$*;Y>2G{wbH~6qyLLp@Kx%ug zW7m%8TqPS;NmiBGUZuVmNIKiKBQ~s3KMtg}+qENoQ6(Q3NH(-`( zIgxvlz}&Ndxu4+P1kAk*_c&nM#Jvxg`w~82%J>dUU9JJc0T&o<*mJ8>bngR3W|B)khCbYL3B!@} z*ZQgF(LGnRSNCX?Q$N|~U%FpTYY$s@^=q3&o;u|}vR+~>VS3lbZ|jp0j9jf7qntGi zeVfWv$FJ4eugCLh{YQOtPHUc#_2D8<%`2`{zhs{NT6o@EE1F!b@p{fFN9t4V*P{Ph z>Li_`Ty>&8?QtDSy4LE9$Ze_P`pCCa{Smw6I;p+L8nNNQ*X^YG)SajLg7DhMFV?>D zn=OQYxa7CnpFI09;e)Sxv|a9%6@|;ia~JyvTUoL1@YmYv7Q05+IErxz8~2EwCX@1( z`jjIBOnqbo4>G{;^8r(a3@~-M1`G#WV7QS1_I5>imFicCr%L>i!L?Q<8DMOX^pp(B zv6=lI>jE&gOzow<+HNx85r!w(O)|KaGQR719z{=KIFLa(+_}H3PwQouJ6>&^uRBRSBv&#hx4M!6 z#x_ZR^&REdGPRfbVF!5X;6Vl$Tk-)@hK!zPO347jVfw2a?%ZEsp7VGc)mHREKgzKQ zoP3Y1kOiiF$fFK+MK{W^2lBw!33*`b$6x+oS7dN4<;b9%`pBRh9%N7sKOf2|<2x{Q zxrRD$gbcWmK{@|Yx%!SWbWA+hF!GmE9@FmdQTq zC$5E`4|TAm=_5>CuAvTkn*J(>J3psN&#xvwS2SDk%i6+q-c+X?>}+G51r9H`bYUA5`e$9>4YeE7idd;#$@=dY;U4 zV(P@b(!cAOJo=>jrnrBxIr`tTcaZeAHO!m$NB_R(;s5Je1Cc4wdaLb{^y*bRE&BPI}f!f6YDKF3MYP7xjga ziLR6*lQw{nN!!54q|IPtVhb=bu@M-V*beONigN4_^|6mIG82EBu}#vG_NqME+w;gjTQKFw0Apih1P?O6@bdvvh72%uxdsdeTwrXB z9l_C$Uao%k`tk=bx+i}8GvrDJb+AFwQ!*&0U!osBJKw(L>T{N_=+n=AX0Nj9w3i5< zGJ5Co+4)`)9{%U2%a86~w5HC^>kk(D2wPdP?}V*xYu5-HM{8Wd#@(6>VPvNAD%GzN zPnG!VB)3lb)Je}e>7Uz0x%?KH=!E{rL{~5}X@j>*Z382dHiMCgEx^dcMqp%OJFvGa z%CSS#Zxc_8?Wm8;Bo{k}KG;9>q+f)Q8U2Ni;Ggig9}2r43gc_|Id$9*Yq0yFu=}B~ z`=PM=p)fM>6|O}lV;F4p@k3$vLt$hlx$;r!yB~(0;-WnJp|wl?8Rh5%Mkcxj4{ZQj zyVN!?GHEjyeXs=>J+ToO{jnX`+ZE*+k6vHn6pT!42S#R+TarE{=~=KH^^u8;t&cyi z{^T5|mFXYetODPC>&fMzOMfOj|MSO|PtGx4P5J8gA5uQF%G$!a@A;)-A7Lvi_MNcR zEq0BtakR!IY}~EM5JqMyuTuRg@zjaGPI67x5q;{UXPxwy?Yv!-x85%53nLRKY{?T9Pulh!&(c!71k zS9gz|EWFm;m()|uf2!~)t6fyTeBY^z@d{at@f6dD2`VRk5Ra%cIrjeFjlJ)LKYZ-i zRVw^#zt;{fw|=Cm@VEJAI<#E%+qEkE?a-kk%C4KPSK)7EqhrhA$8TKWZ-1Ejn`N$h zuF|!etYhcb{pu4HzIVZSCzkELa-DcS@alnOu0uAh@WXZPJ*j-@(9J6RaHqphE~h^; zEdJT|Ii!r);8yWp`t!reb9?!9K6j3#ee;mKVGJq|9v(3FaOW+<>mX{SEK)G-#(-? z2d*UktFGR>{OW6Kh`+k;bLGb$9~A$%Gqx|rD}IwxR^N3^@!!1Ij>UMzZ*t1>&#xu^ zH=f_AO!KFYi2u)XeyJF*_)ShRUh$ipV!YxvImPTEezQ|CUh$ipVs;U~*{K+>_)ShR zUh$ipVs;U~*{PUa#BX*gW*70Bor?9V_^qE?vy1r6PR06F{MOH{*+u+jr($*yzuBo+ zzlz`bxwU>3zx8u#{VIOz=hl2q{N{tL^{e=;pIh@k@tZ%k*018Xer~N_#c%!GnqT(z z|Lt0>`K9>HPh0a#@tdEv7DL5POf|n0zxiov@l^bjn_r6G{IoT{6u2Pgfjq<@w4uaf<%q<@v{UnTvkq<@v{UnToj z$^KRHpE}vUO8!$P`&Y^SRq`LkRrn9%D*UHT{?E7y|EZJzGp@pa7+2vxb@Kl@`G1}K zzfR+~PX1q~@mnYVuap1RY5dk{{MKpw+8jI*f9f=TZ9X1}KXn?vbsE1mPmjbOo2N(O zkImB~@uyDl)8_1v_*19&Y4i6;{IU6aB>vPXe%2{|)+v70DYn-se%2|@*C~G1DSp-| z{?{q~*D3zj__425>J#0zc!7c?EvP8S^6gGtQV-;AfmMFQPx=jCloq#u@Vp{ERc^ zMf7K!F)zZ;IAdOfpK->#-uus#@QR;t#=PG9&vfvLpK->#2tVVDdA;|anKZA%&p2aV zho5oAx&(g48S{GYKl9YAOWm%z_BV_gD2g`vmyG+$X>fPWrdpGr&)I(!b^Y0e;H4e}EsH^k@DJ{h5D5 z|2EmbP5QUV{%z8q`8V`$ll@sgg#B4Rg#Fv(KPB0}P5x7o{aHVR{oCX}tbfGs>mTtm z&XWI^`S^6{1Qv787Ed8-lil3~X zr9XB`@rU()#81}$5kFb~NBk@){N>^R}2_ME3I`js7oKl#fsg%53{jPJnIDg{f~mb?_L! zF#PrrMyAOSMy6dOj7*auj7*au?Cpy3D%GzN4{cB#WG1qfg(WL-K*QaKaOEsq-fPS#{`^`W>BvzkuD&*h;)^t0>1-QD4^v zC*{eu@+v{I2Tzh}WM5m~a zu3&Vh4Pf|b8yK0i8H`M90p>Y0HUc9P+kw4ZQLcS1udjVBFftQ=NpeflrzAb;m(af; zqvz?Ly>D{h&Gp1<`)BWey7Q*`x`Pf^o!K9-`-s8*jFl&bhw4vk(Z~NakGQrTwel&d zv&g(x)gL?W^d6t{z51a=&JbQ{+Dq$8N1rKt?WPyiGd({m0pK*-v3%gEV9)7l;;}-e( zisjimcU1X(8*W~1{Z_v}GH%+vv)nqB*QtJ;c@ zw$!x2+fI43u}*ErE_IAM;}^E}Rwh^2+FO}E!q#5&6t?!Fzp%BJb_rX1jdMgd>=5PH zC+cH2VeFRpOOo3reKg*qA5$AkYPlwJRS}CSE&bjXqzv zY`gNKd+!zJ&%Sbex$dCpYjj)YiZ7SB24}6&?SIbQyG*m`FT~mX;+y3YTg+9X=a&0@ zqda`$65_e%{te5hmFKO|`PEg&mvdfNPCT3c?o;Js=gnWE^QJ2vT9#OBv^e+w_15Lm z(F@h+Il~tZEB`ofHF3Ur|Bhvq4~`M%7JH8_r_EA{bL)+FDWAOPW8!>bvo*@kHy7;#-?5(&=Ztf&XYX|Sj5zOFYOXTZ4O@xxJ1=fn zrup->;@tDQ^Ot9D-&ULx&fBDzT~y!fRBqgH7x7QI_+n+t!*&q=wF`f$n2mI;*{rO4 z|DKX{$?umg^LD%F+IbfHV{5k4wPwq5(J}i-?ke*yS2kXDZ(Td(a!MvvDy$5Wo3FyUoBj>GSx5A1dqqdV+ZV@DKZ4_KJs! z$82BBKP1cirTy-1hlyw6ep43n74e(zwAKgWu|6qRA9|#&{lZ?;6!RN#njf_r{`~0P zwwFy;%!kBdKGm8}OCR&`)_h3UnoqUn-;!(o-kN_)mic>YJ|rIVsn&d5{O0?u`Fh{R zk8aXhtQRLS$$VX$=KHP1eQ{E5abKKZ^L25W@3%Gwh?Da3))^{iWq9n;XPQ`R}jp^?YjVhpK}g+gF?`Jac+=+z}^<^O#3J zTz!B4@zQOpo6fF&^;EC(jjyd*UHjr;(({>#7gbO1{jHvJrh)2-2acAWQy+DCm3*dJ z`^4kK`N-o}RLM`OO&|KE^xW=+A6Cgf>*OcZc^jQ9{wH6)wo3k4C*P>jSYT{RH^zGM zjXI4B#<}!l+$Z0t)3{*F_kCwEV2koG+2_C?EmJ3-snZxC7N{-6h9yqhM0VSL^oQy+ zM(SVfu%&c6@5EJ!5o#APBaM-I;Z?VjZjUa})M+f#UpRF~>GPwXty!Z7u@1e~{`D@B z`{WuQt&vBpLq0Nyb;$hHEnktW(TA*8!%M6~4qU`HxKsSB;Ud1lo#LmhOGe^n4HvNv z?i4?5jWQB5>lEj0y)qIr>lEkf6z6U2G7>-Q6zA&{=j$}@)G5x_X%4E>98{+`U#Iz~ zPVPU0o8!{<%xDNf=du@6pSA+f{fP3$R7;vX>%PGTPOfzO-RQ=G&+<^Z2J z>GuLBV~ZFECozxs?(=4C^QL%g-oytA{EQ)+H^pP~CO%Mn-mGoj6sOIb^m~DmF=6wj zIBnjnZQc~8&6~B&o8q*2v$lCtoHlRPHgAg4=FQsXO>x@1S=+oRPMbGtn>WR2^JZ{ES7`F1;TvL~PWxHgDFf zx6qAoX)&<3?Pb&9L*ikKvKB-i#wcqqA&W7}8WDcRC~HKu z(bkOIBf-g>#TpS##whnoa8l0w5}aVxh;TASxp#t-a+^2BWAkRqeH8qZ+q@|rn>SnT zsoSmVH^pi5W^41NIBni+ZQc~8 z&6};wn?2`D1Fg-Q;M+knktQjlKitI-(WqdYgtbw|71-i9avMPaZ!?g7Mq`>o6T1x`3!4I>A>1D z`Dd|tOR{VpV{NInv$nK3OzpBctt9_sZ7CgCTiSdkPMhCK8VkkdHu2b8SI`4np_k2V zy4L2pf;{Yld}QED$h5glHnh2}z>6;-2QK^v?i4=@T=);%DSmR_Ax>-z7rq2{il5wT zh!gvzIM2O?II&ZT^V}aroaeqnoY*GCdG3!Q&X+VFaeowXo_n{LkGOY>`H1_Yi1XaX z#eBqlT+Bz@yTu&DJzC5)JVVgEE#n33&#d(9E1q|yd)t54y|$kFAw>;-ThyUI4 zgrt8-I+xTI@LQfmr)MeB;otb|2s@8Fm*%;#_qEEy{-$%Z{VmUp)3yJ`XHaiGD} z;MtVy#j|LhcVRo83-P=Q%=03icY%41#PcpN&zE@K1?IUE&%3}pkAfe}Kd|o|sEz4a zx1OcPbN;?|{~Qk-eF2W=c;I-B2ae}>;CPM)j^}t_{3_`n9M8S!7uUziN9-U!jqXWk?Ixx24866lK634*Uma+e4+uxLx>L}LvwR)}yj^~PC{2}R}=Zciab44(I zmD;7an*1SjusS1lQ=H-2ct#42XQW{Gct#rK#0@a@Q$MP$v5%8%uK45jmu_6kzyD0z zN7|+5tH}9R`!2QdU-Z>C$7veBdVY?c|Khm&x5bk*zUcQDcj{mC{QvR?zUSYOvrJc} zU!&FgT}MwnP5H?VtIKCzd+OEp$XN~(eszV%+p(Kp-s5fWZeO(z*HXrJJh0AF#l5dP^#Z19_$wU*i)FcCVkqZXPfkw{bKJa?X|I2RZ%{9 zukhWuSLnYTQy=l0GJf|(fBA36g!v5`zZ0X}e>+x#{kLPn{@XEO|LvHt|8`6mKST!C z@_R32fcYI5GQj@ZF=7AhSjgqKW1$bf9TVpFYRKT)`0ZHFqu=_qQH~5S^^pPQcW=l5 z`)~aUm@>WtQ$i1abVmjlyCu1jK{+-^dP)Z6*bEtW zom^~>xZjHhv(L=<0>}6Q$6h>`{bcs7!R#lqpABX|nSF6E`^oHogV|4JFCL7{RIa^v zudls$FniyLU;E;eQ^t2-WF|eeFHSk!sa=vC<>&-PM|2Gy+5m>%KEkmVPdPHN1sIvw z2poIyU~gBHYcJmGYcC#*%*3y~c*-eD`e6UivtT>wAT!$K^Vb07%q_%EFmnrW70ld1 zycO=}FJUWFe5Ty$w#03)aWH??VCEL$JQ$g&ocSy2SHyYe(L4f1W|FIUhjQvBJ(<5k z|B?Rk`D=*!$V4YFGSM}7XoGM+e+eU#HdBrbumu>I*a+Dr-f8k?FcjoLh6NEp!_@V7qtDY?U(DD<9 zK77bY!fU)ZP4(RQ#|eLAy9=rZhbIazbMF-Ofs21l_|tbSUk^RCnJ|C(Kl<=J^}t-m z^n*9;y#~_)wMad;N9wbB`V&yxzXo)MKAHTKEHZTv?A@@&w^qMqgG> zHN#1awF*wgT8b@{n@hZiU}|`1upcViT_r&+y#`l-nP^T09%9 zKEC|(ch`$&^t^|b(YxLtp5M-VMA>?cm&Nnd+*jkY{qJU9Q&&O5sBQ1Ps}{a1(X`~DH)+49`44=sM( z(c;--o&$&Wc>H+rocD?GL(9B)ka%{#@6mxf?>bRDfB5r+p>w9~dB#ln^uVbz_B^|d zd10WLt>^jV75^AGpz3*!TX4$iGYj?C-t>d1t35YASUPOE=te^~wT! zO4eV;Us3J6?_tvC*Uz6(eecTsRsU-@UsLUR!8p~wVuMocH0~(rIp)l>t2qvyp!&P) zd1JNzs4t1!gt#ofiT$jOgY&7Ozr+6717R(MJdXTQ2YKFP%eb(AhoHIYaM19sV8;NJLyGGT2 zU0_%7jJ|i7`jFwx#IwrlE7ntdWmWO;_m&+$qicWssNMJ6zq>fUFltnN@FTT&_ z4}Oi`z=I#*)9~Qq56^a-uASTR&hQnk#dq*;`0;nf4?K(~#t+vrp73cn@o~lv^%+ky zuD+5uKlZ(`H9id|KK_vt))3Ea57_T6Z7gvuW9ySEj1lKy_Z?OS9Q`OI{wXy1d@U9b7j-Ix@5=Kv3UkRg|t*?ZUYwIiYY~evq zIFV~>E%a>RK~K}Ig$LbCpB5h1r-cW7%>LrR{-#e05Biw>#e@CL=HkKTW?S)KTeG2f zu%Y=_K_7g~>?R)UW`0%B2fs33D(HhRna>pT!Dq}*3i{wDHg?3r*fD=7=z~Alco7fd z#m0zu7$Y_=#KX8S{}&JbZ`X^5v1ooS9{k*{7Z2mlt``qu&aM{^?_w*My>C>{-r@tsq`m{-(HtEwQecEK7HtEwQ`?ThNVV^eHr%m>0Q-76Y zpEmVZN&Qt)f0fiySNpG)$elKiPm>cfW%@AHR+yPZC}hww(<+o0n^9m@C)OkJ)4!vPmKxWUM@@;b_`zA*KT zr=c7k;}?eCKElYf?}U+Q*9ariWHht`nI=Qn&Wb>Gl-Ja!4l>~ZBNKiwGWmch<2x{Q zxdsde`h(#%eU}C!6WLLYPGIVzD;OTy0EXW_!pOAmgpq022qQCWhs@kx;Q6lGYz??F zratA=hX?HK754TDdwYewy~5t!!nNLB;jks;-rgEaIWnR?GQi$mVQ;Unw^!KPE9~tR z_Vx-}KQ4_7II%H0fvrCNDQrCQ6UwnMGQik4>4SfUp7KNLU^Ds=j4hE7<;VbIOJsoQ zD`bG-=L4pU@4(be_QyX}4)^W9xu&7t__zN8Ka>x@e*V}p`=gf%?|S#k<+BHWTln_h ztlAyF>CwW?UAuJl5w^0Q3-u{SM|i;K4nLSSAp>k>4Kl!1w?PKjI2vStjk`f6 z7+WGE%8>!4J~F`YAOj3PA24Nn2c|C9fZ;#}81CF(VEUKur~~#k3VR!cy^X@&MqzKG zu(we@>1`Aa`S5!i<%g7G6Ux1f9oX9_>}?eGHVS(ig}sf!-bP`@n#qWAd@}0elfuR$ z-$1VM%V)qQSH9%>$j88Nn2gY0{zAF6i}GkM^@XXAuE9ea!0^*HFmh>g&m*4{#x|*6 zG}fp?e@*T?Z2sTVca!I}ejZ`&#E0MQ^V)=)eyW(sSbOQRI~1c2{>3q6gTrnRzT?W7 zx^qswLU_VW8+M~MJ5%`NPaV?PN7%|b`%c*Ec6N=hadgI|dCj;xWH1MqOv*KvQH~7C zsgDdWJjejU&j(By-+`&iHDEa40>h1rUf$Ffglu%7KIP~L4;bCy2h%2GfUT@S2H5I0 z$N(EhgAA~7H^>BIOJqbjGQiYF1{fY>fZ^u@ri|~v)a4p59LNB}O*{nikC=&U;xzLL zm{>}T1$*2O_Lwj1F<+SZff!DGkNLvPC&=h|Ca*)V1@jmmF!LLB1~czre=xSBU%tS%LhrzKP2FH3B9B~62>tQf!Ro25`)~d!O%vu$hl*f7)OgS>5J~F_u z9tOvH7#!CFu<_`=32gkjp8^vjlRn&!gr2%DqYgI1 z2YVjfuSI*QFU-9KGN@zif?pVZK9p0&cRi2p*M#9f2Ibf?_ZRs7?vatc14rM1(HBlI z?LZb78zK*EWxAIEV{_zzqwm1jmA(T<-$gkxqCPUf@E`*WKOZnE!h#1B_i0zxs}HD^uTru|d*PeMfopUC-0^U6dy~sPBR&*-d>%Ic3P`dHTKs z!+{KN^c@&m5+~_XFyj%-cx0S{8K;b2FyohT4Q5>P0aM0zVCr%W7!J6=G1kGzBo;@x z)fc8dv6ymrh{a%!C&C_2ggu@Jdpr?FrpXYFH9tJaG#OE!_%Do1lOc@EBv)&G*GFr9 zFdRw$F2)@)kxd=ug=7b<`GbcxfRRbtz{pH?<~~&A*e3N$$^8Y+{TP_~V03{8j4tql zu^V#1=)wm~8Q+1a%Qav)-~vZKf{~9Mq8weLJ~jozL)*ac+ea9g_MI>?u_<+siS5A1 z#HQfrM=w`DdVTdH7@3J*{YW`wNgwqi<;YC>s~>xwz8}HplI);-prrb+g1uo30RBp!mXCGikU{Aca~6N8DXVCD;p5yHe^ zK9p0&cVOyr4LIg6Fx=5!F@HrlF*@oqUx48uri0-pHi408-w7j=xrB0LnhfEXzbKFS z3(TC8>X*c$`OEn=e}R#i^wIo9IUI0-k@-%pLq4$e@yOF}IM4XdvBH}#yI%eKYY!8? zWAR(-qd&2q@CUY@y?Oln&k5hR@fwYNgsrTx?}V*xW7iZojiWIxVdGYRQEoCRH(O2^ zpd1-d9~oeHkO79D512B(15+0nU^w6c!;K6u{gui~s$UXMm-xFRw@dnTNzX3n-_*-3dEs9?ZLb%y4|OQxJ1}**1`G#W;NS)$)5_^P zm0Nvb>Kji(IXuQM48MJZk!jxvBh#)CMyAP-uOQQ8xZg~Tj3}?EPrH!`Pj7=c8~DM< z11>P!=m>WItfL%%j{5jH*!@%3 z{ZrWeQy7_yBkCiQ@dbAO6lPva<>(akks*vslOb&U8t?E>mh@44pd1d95&EmYD7SV| z9_^*RF!j-uI>=0RL$1n^OPhNh#S>v{lltW?{guZcb=U>>ypK&QZ z@w}1eO>VQs?DUT1lT4o1nA`t*<~90@bu7NZdk)&g+)d|iVnM+VsE>jv!ewXo0E!aiRM`+P0z^R+PgBLg1RlgI$GMnDGG>a)HQ zHXf~WC})j;3@~d1WPn*CBt5l`q8ytszQEWL8BvZ5Ft$Vn7#?JR;pYRUjPJnIVjJ|M!X$P{v$U+A&?M62+x}h@| zJJA*}_M`8>*cBO3j*O^}46wIR7=AvKdmDwRiww%)KnB>`D9pT;%JIplFCU;jx+i}5 z4CPjaPpUpPNP0F&f9!fe&m*6V_ENv099tp-3{SEfa#cU&>L9)o5R`j&pgCioTo2zLLB81jyeLE@*4d5t^r@xY!>DD3%!!k$kk?D>Sk zo=+(3`GmrrPguhlxqe{JCoEA;{vp`&357kMP}uVcg*~58*z*a6J)ck*{Y{22G1Fv6 zIr*PaU-_23KFa@8x$!GMlX8=*yiKs_qkK-+Q+b|X=e_`pOk_tnIz@eS1;axd!0^*H zFmh=#*y@u1DU5AWzmWf_@)&oF(->=D;sN6vjDMxEJUM2XO|Z?oA!g=&O#Mq9Z}hwJ zX5Al@PwRf7JX()9rtf@B-i1x3iD1m38)=u+{DC8e!w;j7xFDxV1i^zf30O z>MzQXK{@r20fq+|VEFlfDdRgZb-4x%2V7vdkpX6XlFI8;zezkz;%}1NCh5~8J)5Mz z)+fC_HU{5pFZCPBO(s0TCKG;PlZjkm%J{D5S*zh1FdU}8Fx->#Nyu**^IwxslKTsv zWS@?C4W9(lr}!k8zQ!lP_zOM>#y9XuF#dv1g7Fu85{$p#lVJP>8DPdYGNK$AQ6CxL z@JVp^BshE$OkHGv!zaOTBLnR15=NI)pE0X)bVmmDX%jNQv^D8NOi($tN&4Hma_Xh2 zk1de_#+Jzr@N|@8%Vam?s+=;u>v{SZ0)`{?OUeE9UTGsSC;AZ_{phhs{RobJ1V=xD zqaVT8n0^FDKZ3C_GQiP~QBEI3ePn>6AHneR0Y^WAsf!G7^dlJkkpZ66<^p_@c45o6 z`KNrFaf40VxBn|+%Z9TYGJM}RyTMhTIcH4s$!`olw{DM5y=kA}@9tPs-krL~@NLfz z34eQ{SjbNM#I@89ck;Xlo@ z&G0L;UoujD_vIIk)PHq{^Mv7v14?DmU_JKd_hTO0x`h=a)GwhH4(J!=Xh7WvSZM^IQ4$>7{2DE-u{bhFn0LYpXu>3A3bn*{8^W&{_iIoF#PGC zT`IiDYzGXV{`bC*_IYgok#p#!WAwS@ z!V6RfJip&DLq^Ik{ON>|`uClF=m^iKPfZ-*pZ58QBXY;> zbJ&PJ7d&v-aOgR4&cjFa-}3#3kF<;OXfO4{4)BD1;19bYH|&W%VQ2IV`=fvKON=k` z`;qYlj`0PK@db|Y1&;9rj`0PK@db|Y1&;9*<@jgR$8W(gzQ8fQz%jnSF}}btzQ8fQ zz%jnSF}}btzQ8fQz%jnSF}}btzQ8fQz%jnSF}|Xl@fGzMU*H&D;22-v7+>HRU*H&D z;22-v7+>HRU*H&D;22-v7+>HRU*H&D;22-3HR zU*H&D;22-v7+>HRU*H&D;22-v7+>HRU*H&D;22-v7+>HRUs2BZiu#N%aEvc-j4yDE zFK~=6aEvc-j4yEX7xP#27dZM09Q_53{sKpTfup~`(O;@FIUXt|M}J|H=r3^e7dZM0 z9Q_53{sQOz3QRvn-+`m=z|nW$=sR%q9XR?99DS!clgHYBWUOIZ`fl>N@tl!)4d0G= z4IJ|tIOa8Q%xmD7*P{GCy>5*DioT;CW6ckqye2tI<0bkIn?&D%qwm1ccTxVIUX##w z$eL}1qsH9v^a6tqExyGKH~sanx8SG$ANI~WtgGu;_hJJ(_J+M1dyUH25_`vzsE9R| zBzBE03dRazMFlA;qF7Mu0>%PZv0xW9wy3eUsL|Lj?;2m8b#lvd@A;kFdrqGF-{+ZU zm^CwN_Wo}6Ub9xS{IarXHzP0MnNLpc>uR`>b3PeeSGo6xyfPs2Ya@4PnNQ}HP)`4Q zJ~gU})Uhc0`&VA%Z**H=87tKsQ zFiW|48*eFfNIBJS-V$G}p0Qu4tB>4YQ_uKM`|!b*Qy+5L0n#_x$Wob_x`nYx#x=OoGf)O^X=3~d7#JicpD2&57c3F=n;Loc z=fRRCMER;uh=e&cGxA~|L*&3DHMO*@yF)ajAf) zjQP4$J6Oh!cQ<}6O&=_o)2eU1*96Im8OrfRf@HqKrx=F?%9tU_{>zp~yQ9icTLNTi z?w-cZgiZe9*h)G3^2O5qTOF5U89yyK^&zJnFzthVK8*{eKVbR^rvKmzO@d{vtHx#X zwvJ0AEK678=aBM&a;B&9%bS5xEna!tgdnL>t((ztdK4tL*DG(T87w6$Yi;;;43_EJ zyPJH{CdRep)Q6mQz_btMxM2DNw(n^+v;Hx6)3+@auPt91KRuiHNz9-x4A*NuPikCm zWO&Jm*%DTyq2VeIW=Y=a^^MQ8gRyKm^&zJnFztiwaal`{li{0P&o=X#g8r9J3P`rz zn#18W3&@aD-HdPi&4nH6gKatWA-C;tu3>*|!(b`jL9efm$@ibcZq~G zAG`ZWodX>W_Z#acVbN}e&)oBqy_-82ZV|aq`bM=kye@W;cGx8Ig1EpM?vTM~q$yTF+k++<)L?#9)zdaTpw_a2*anU|}u;tW;oOZyp59YXF z`U9q);QY^LOY=a@zs()~oG#nLG|v@B&5&GWlzsBfl>R$(F792KDTg{KpNsRB+i8`Z zcKgW7!)i0&@GJ>gp|Evg6R*KeuBsM9wm`6l}&DK z-u!B`d~v0kkuN(lN?!L<&XabORJc*q$RE!cDL!8-4<9p9o*k{CbF^oqbZc0}_)j|+ ztEDBUKIF6mrhPES1&0?KE5-I!H}-AL-e$7on_kn%(|qnFy#^~c@R%eQMS1hcALZho zHH=QhJ>#Y0a%G2><0QUT4dW;6U@TiseaLACO#5JaT*t-JBtuM1W0Q<~PR&}rGCWTG zAM*1oc~Db*h%Pisx-V0H(aT55yj4!{_Li*8)c>g=Go{L8)Ym8aPjgi5_tN(X3V9Tiw`}V!U zX2u2kUE9o&#R*z(O&#XT%QRYVa~dp^@E6J) zjPwU=%c&1J?SN??%yGf=2TVV~^dHQ)z>F8nJb)L>^^u?YJ~MvWTzUCi>7Q3~;yG=u zjH;ly>M3)Rf1@>rM-%4A#9B|x-~L{4j^r=&)UeBt*>d2vvfo@^c|QAhBmW^_mSoKO z%;bUg;e#!wKIF6mrhPES1=Am}?WgDUx$=I`1v3^IwNdGfkHmF2ZT#7n%2#qmDvx>L zE8aEE82O^a*)r@`kqdM*gVqTnP+3XZY5vxe^n2-f)`ZbEV7LBr_K6!yj8t zeaLACO#5Jt3#LC{`Uy@PKUVyg9WmqD{Ib(P8QoOnkE?wvhoTaUj#r)U#m`N-f43nL znqN6|`Y@T2Rr%M*5i+x?@{4_=BxbnFJ7wy9bTTXq*X$MUEV2%r>KVbR^ z9#W&HWVrFc_-ymNl-K9;>Zt~cSA=rbHQ&kpBKmw@BHgz#eTwqk5(DML8RfM(`ipB;eO52= zYhQ7$s_eA9w=}M&?AfcQOsk;0s(KG;kxtpMe0PaHsCLSB>?)BXlpS|}CF?UOM~&3}!pTC@3M z1{Vo#>0q8kT}Ky`bbC`79@n^_6sfHIdGb3<_xgGbrc3W4k4o$HJM*QB)GMmjc!(61 zY}MWw`wNoaRgUlb*6`r)ViK}b$88c>LdLl&Z@O4Yjy`;CbZX@*E6KVbR^rvG5Z1!lZp<^jz7fSEV&fuWxAzMB3& zW%KB3<7KT|0h8P8Gk=sd>yda3`~2x9%QtEu*vH zmfQMBc!r#YYh)ZGgOBGnT)5(JY0)U3Va^5aW3&&p<FzV^8rcv)u6B?7iez!BE4Q4)>CT;wubaE7@D>)(kVep;T{~*J`D?KhQqn zvgOo=oOZyp59YXF`UAH8tkt=obgMbrj73J?-o#{;wasT6e}+dn%gHmohPR&0Ar7;Y zSEbG^jfW}ksG3*YrYg5~%P(OEeT_}p!ML`Z`jFEOnD)W;xIPVfN|nd^j7>89{PAdC zxmjVC@$JRnep0aZZo}nv^pm`;_82a_qMtPAz1MKBYW?KF@L0oXzU?bZM#mZUZrevn zeG_ju?oKcHqmGV6`|!t>Qy+5L0n&Z%BjE1C5_!wKSPlma>7UX*5hpQ>q6yP`?5&YVOLGAXa{52a_U1)J7C%eb6g|; z%u#A?o@4w;ZSiTh*RJylEi&@r+h4m5|LAA9^2Il<+wLte{QZu1t`l#~H+-f3N7oUr z<{6Hw>>$(1DUV2%M)rEmHS*hO(n*fgbB+JB4may71#d(X`lX3 zPJQ|hJ7B~G`(VV2al!NlZ2QSrASWX(Fy@PLGUpWXw1+cDmhN+mPLFn(WylS^Kk!;+ zepnB-ochqQ?Xb3Ce?hg3;(y_avHxVVlcZXv%$(qFsn4-E7u1KGcEG%M!9E#s`~FFW zoc9pulOeaS7n^y{hyLz!9x^gdgz>-iCJ(uFbCY4G?!6?-iXDb|-+)d2E!dV*A9C6O z+xA~xYAyw$_4|m;ODD9DVsmw!MvG=GrCpA?<{6`RbW14{tQ>u`r6iQq?=SIQEv3OW z<-m(AB&4pZ`Aw%C#AVB=4>|3CX&-Eli@I`3)85!5BbGrAa>?_b^?O{M1v%wWW&KV! z<#BfD;itSev$M3jsa*GM7U@?=zw2#G$Rsx!C?A=bLE>8|N49X3opqIm6-p+!F8nJb;-WF!KgxKEVNNg9py7{g#a;Tq^d^1IP?aqu+;U{J1Uoy)Sf8{c_ zvr1CD^6BHw@;|Evg6R*K zeuC*gm~nv_FPM1%Ge2PF4a|IknP;$_e_qRwlkNGU9CHV@YtLrhXYjX0UNw{K0iT<> z>yoRP>|9veu*1csvSC&&!^@jCljT$N`^%7S&85i{{a!OTOG_y*U%z+ICdRep)Q6mQ zz_btMxM2DNw(qev+xG-AVzI9aGUTjn*t9ur=L+eVR{!U4~VQhAcH>rdel)n2)8 z@G2SWtUT`cN^#n&@1y(+tdv0>%B5$9$@{1Jt}H%(n2Z{y@2O}XKG<^VLryzj+6Qx7 zF#Q4BetvkfUrHx`w}qUH`E9W4uw<^P-{13i9+qP<$_;ZL7TA_oOZyp59YYw+dX6C?Qd$|X4l8DGWpYeKHsao^8Bpc z^AEn*BVLb{S3cS;GoC9~xVua4-c&wy|7S@bt9;_^PKlqXoUzzW8Q(y^JJUXVu;tW; zoOZyp59YXF`U9q)M!(b!@%Q^+o}VjNytDr{xlm8vy+o$jCJ8b6uEyc`R_Rpr(|eo! zTcuvOz5|?kZ>w~0QNCYqoAmY9cYq~gwn_ei%DZ}Ompz^JJv{Bh2U|{k$Y}>m``{X% z#s$+KF#QDYIiDn@00 zsPdx&=f!jKZS(v|I~dEBQy+5L0n{s$d*ebhzy&RzX{ zyycRNzoUF~!7tJ+NWV*NYkyhxkGN;%G4Gwr^6dcqjyb2p6)8GGzi+$dy$$&1(Ro0!A{&UNidkF2r2U|{k$Y}>m z`(Ta>raxf%31%&UKXbVtJ(Ft&oUP9VS@=Mixy5~q`e0j5eaLM)^dEAYSsNJ3X66?1 zdvj08-bb2;gzyux->t0XclRsek3AX*W@3A)X_Xzq&ny;6JFZ6fK;n_y< zTd3=)CiUAYQ%CFX#jH6yWbOi8Q^CJQu53B=A*UTM?Spx}V_chg&xDT6_HVS!_HzOm zHu>8JJ7mc1`@hY6wt@cD#MSb6egQLgT|L&z@4NMVa{1Pq#9?6`BX8}wRc;l_Ww`gv z?NVV(cEgniMakKfSq-OijFz*zG8z6OI!e}`(&z1`UOVL3AL)#o_igw_AHcSp`jFEO znD)UO7fgS^^b<_~!Hf&cc)@9>uarK;XP9e{4EdBntHn1`-={5|5iXB2DM#;1?tgEp z?_Fz@SS6?W=sQ)~Qxnyx4W6G;Z!~_}i8%<;!X_%~-UL{M&Ns zLryzj+6Qx7F#Q43PjJ^$o0FecyP9!r{=H^|L|y7*m`$qrM zxM2DNrk~&n%cG=Te2nqI=Bh)IpLx3IyW+xgV#H&!zC-^0ShW0jPv0#MuN0m9Y_B{m zxjt(+?J;)l4vvzn@AMsYc>5@6eCKB)pW8c1hMwAK;-Y={V9TiwIqiUHAIx#V^apJF zdH2oKjC`K!aoG~4oU=!w+;dPJ$KfaBa=dcpVJ9W>dMl&f&+U|Kacg6^ zQufmlk)@sC(D2hzHf;yP)w7NGfH{LdM3Sv))r8*VY|vN(=UFnloQWx3^j#Bd{@UnJG^ zqlV*>F3BJLj~VuIxFnTIA2)m`%SCbCqw6JTA3oS}>O)RDVA=6s;BpjglD^@OF|bjcR_3SNvZB`|7IRxpMMMH{DP?urX8?tpE<|4 z4*ip)S5Ljx${jr~AH^Iix2 z;%Q@KNYqx7pC-Lyp7 z>t$ct@QuaJ~VY}^R?u@B)_H4 zjJ#!=AZgTCd2!c3Ir6iv4;O)RDVA=GoECFKm9?Hd1=r)ZdP$ zB{xd{s>*|NZ;~%oss4fdo8?qv zC3DV1arM>fXy434neU_5m*?q3c@}Wd_)j|+%a&6ga@qmYKA7Wz=^HrPvqT9iso#0C zzDX2WqRhEQ{ZRj}wM2c$Z9BZCU_VunRnn=vuK8Saez|<+qH95U@50|wA8gC154mlJ z_afL|;2$cDoKKnj6s#I9zdX|4!HlEV$%V?t{>{9@4*wR+dH_=&OgmuPKJQDA+su1D z{IQwy1$~=Y^Uxd^j8@l}ah!n-DJx_iH|XX}M3zkJPbfAO6^K>O)RDVA=)5bOvZH3Z~AL)AC(Pp%0sdpl?O$2&A`P1 zN2K5P%6Xj=evFfVY04e@#K|{VluJF0l_}op=i2qLa^}76YeD}Jqb;XC{!J66V3((j?EljpsA z;^*cXqz-J_a_U2F-&<_9^KA2jw1MtsVmLZ=k4J#rI+&HDyt>i!)8WaJNez?>YtP|&srllODi|&vsN5` zQTvP9u9K(Bn;QRVA3oS}>O)RDVA=0Ik9>A)o8i4LFETK zMN6U2biIn#iYQ46RQ~nY4mtT++2zu9Y1X8piLt?{ZIWSv^6Qwb;=M$rAs$R|>Q64ie70~@5?0Oj~n8zk^)2a_NAiCAno^&zJn zFztgmE|~s+=_i=}gBcf?@q(ELF!KXu-oSUJ#*4>sonM>VIz`LvJYSf+dEbkc<+~dj ze)?OC+#IW%|K(2E(o#7?j$JaShVr1QyCt%g^08KXWJCw$J74dW`%{$9wvUzIW6EtR zB;OCq=~y>z#mQ`c<%GjCw#6U;n=?YXeot}C1EYu{$( z0r$_*wYST!4K#;W3vH3|wKQ*A6C%a^k0z#WsSh7)IrSl@9k6|E+RXbK#@)C(`G3`n z?M(e7K3^wp`;aU;KDS+&GH3HnS;{}f9M?~lLBTK9yTjbj<=X;czWOxsdi5J`l94_1+~=v z`l2BhpefVI@sSi2rfN3Ahal!NlOh3Uz{CkUEUVk&L%{L|wm(rUS8Tt8#LnYVH#fIw^ z9wK)#sQ!`S-%Gb2l|7xlm1g^t%Um5GKVMc(zx5kQeOS5g;=U3&&ELdD`|!b*Qy+5L z0n@2I(%8Xh4Lkc1Rf z{^qQU*JWc;TcjAhHI4>|3CX&=mS!NcR{%FKENjeVP!x=xb~Kj$#= zGgYUH`^4;qpVprtsg^h!PUt>UymKo@d3ww9m)VT`TBwgys;}~4F|#DwJ>@66eWm|1 zwKIJ6Y$@fI)9C*?WR5I-pUZHStaIi3ojiuUz2?e8hx{g9`U9VBIrSl@9TV3l`(Ta> zraxf%38w#G#sy})U^@>DlKaZP={?Z+M#eqx$71=V{rs`U|3hu^$-oIe7_M_6uheca z%5anYd8JmS5r(~Tp-r$Yr#|Gg177;cKA7WzZGU)8!Oze(1!d96NoL%%-xZLo%O)6RuJE_i z2itP$Lryzj&MEAZA-C($X8zVdf6$$IveH+77jBK5C56WN7=IpAn=U?8v=8XJ#*?M+ z`Z-3PY2rB9ae2OB-j^^IZGvq%^&zJnFztgmF4*>mzf+Lg%- z(EU4Uy|tEk#&}%qJIUWb`Lmth%HTxZGvwWiL9(Nta*ulhrCd7Y5z7W7uMgDs3H6Kh zmxDus%y|KGzQCMEFy|M{c?Yu|z^oH6>j%ub0<+%0+d@`JqF+aI z-SzZdC4ohh-?v^RPa@rny#M``QoD)r;(jY7;y3*tHgs>8RPj@ukt$4@w^z zUoA-S^KtG4DgHYjnQ!94JTk_=GU6?FQQv7J-USo&eK_LH;8fpSM~HX+_YDjq-cHLK z8b-XYm*`%ji1+@dcSneKUcA09LcE@Ll@TxHh?n|^mv#^@?IT`}i+Je|;-#O6m;T%F zG7pHC`2jO;VCECdJcF5kFy{r#`2uqu!JJ<(=N-&?0JBcOtRFDz3e0)~+jYpfL#;Ai zF!KOre!$EdnE3=V&tT>s%y|KGzQCMEFy|M{c?Yu|z^oH6>j%ub0^9YrX~=i-MlzXN zYUTF5EZM4kaFt&Uk+-htjr?4bk<#Lk_C#zgGEOF)*M5f*pLxkeC+%_A`Sn!USMt62 zKdbPcGv(;d9y&O)=|EiH6TS^;9YQv{-mJL6g#<+&u^lAkA7=Y z#%?2ne*tz6#uWgZZdHpUdH%WM!ek*XEFB;#QVCwvth&=F(-#%#QVdl zT!s;E!I8SI81eeu%WLF__s93T_89U05T4)25wH6-WyDK4;-x;~r5(ge`-qq0B3}A~ zcs%y|KGzQCMEFy|M{c?Yu|z^oH6>j%ub0<+%0 zb{%r=a6K|!F!KOre!$EdnE3=V&tT>s%y|KGzQCMEFy|M{c?Yu|z^oH6>j%ub0<+%0 z-HH#9o}(ho_3|R!PzmX|*6_u(!=?9#m4-cEkCykRml^JHW`guz6=e9&sguPeV}Rkg zTc%0HPx~Z1@8Bcd{#an-l^e{JfnoCv|K4$-1XWeuI&evf{7L7fDf%7%Sdn7qUh&l_ z_N(t%mojeghz%+J{Be3?il28%Zcg!k`{K=Uj(Fp8 z?>3BhzxpE1Fyalpy5BJ3op)5%_8{KA&voB6#M`;aQKN%+i$^IVUdj zyc`$t(jUZ2KM^nex8r3V5HIrsX5PTeCzyE#Gyh=D3z+i-<~)KqzhKTgnDqc=oq$nKv-=31*(b%s-g(0_J>yIgen@FPQTVW<7veCt%hO zm~{nay@3za@Rzo^_1)>FFn_sH(a~HZSsn$*!_seeLFaP%AX!}Op5X)6L*#bS1;fGp zLdEy+5yMVnR>|#Ndky#abFHj}JC)lE0bG&$r2N>J8B;@|xp!r|8dm z8<%3|RhEM(_K(j`NEtWkyJIQ-OrMsR;^)o86Dj^5lanSc%p+s`D0@V+vT9EVZ>W*d}G6i_uz)6h7qq++DE(`7xB^`#7jRBFa5XUWgZYO^8;qyz|1F@c?L88V9pDe^9ANSf;qon&O4a( z0A`(lSwCRb6`1t~w(F2{hdN}uVCDhL{D7G^F!Kp!p25sNnDYYWe1SQSV9qa?^A2V` zfLSMC)(@C<1!ld0zxw&SI8D@blAoP8FM|Rvn(Hoe#w6L0yniWls(hOylbatg<++sn9#Yp;9{T-~93P|H|LiaFy03D&sLLtxxCK{I z^dI-SnqsGE!D}h@i|@LYGHyuy>nZ-kExn%NXXwT2DgKXsblt>-d1Q=#WyHI>r>?O? zynX9kHrEK^otHuPs6o7U_bDUZ{rz;GCB)m{jxyryo4j5Z_7U$FKPe;Lyo;3)FXf1r z`iPfy5HIZ`UXF`+=?~(ipNN-|gDzLk`Jxc%DoZiMdhT&Bo-*Zr-OGdD{mH=UJRW=<{6?{679Gf$;S zk*D%bC)EGCl%vp2#y}^b{kUH;2*-`Op1hCKCx1RJPu|Dulb^A9G7J45P(QOEF3cli z{3|2g-G8bM;vIMPfze02;VZNs9Pxf|*WL=md+EJ0;_dA9*ytnPao3d*Z`XoPj2!V+ ztgMW9DM!52N4&IycxfN;a$Lkqe-JPIM7;Fhj+c2ryvz@nc>^<_VCEUj{DV0!V9pnq z^9bhrf;sPC)&rPz0%rYySyy1z8`!Qx&K+u%@q(ELF!KXu-oVT!n0W>>|6tAwnDYhZ zJc2pDV9q<3^#Ep_fLT9a))kob1}^m7Ntu^j_vrY2(n)EwT>G+5$DEYD)s+9pe@a>( z)!yyl!Kb9?5arf#TDBBYUiIp&KFYbWIlQ!#r~b|E~bpz_wmIPf2Oxh{;m1s=K$|ZDgM_Bxn$zPJTk_= zGUC1dllGn?-aSv15%1Zr^t~(MO|@Ma@eWC+?`#ooL{nwNyZZ-a#9L{hGUCm*R2lJ7 zj(Dk$cxeam(mvwlxQLhjAYS^3cw461WnAy+ ziz(wiaQIp`ql5cH)JA38H<~U`#{I;7rZVm`l;i$GecYF52lp%5$9;_B;{HZ|aNnb! zxF6Dg-2V|5=8-Y}l@V|C>8gWxv%gSAyk)w3n7>85ouZWyZ=92!4TpF?wopdA*~cp* z-pT&Ti1)itWyDK4;-x;~r5(ge`-qq0B3}A~cs z%y|KGzQCMEFy|M{c?Yu|z^oH6>j%ub0<+%0b{%r=P^*j=%shaZA29OLGMyuOmpo=v&#aGpEmIM1E>lY=8t>|E@! zKE?j_SL;*8tulT?ia(t$ZAkI6X70!o|DDQ3rd)T75p!xY;$__;Ue+_>Wt}5l)<5Fq zb%A(!y&zs*M~Ii#7vkl0hj=MRywpd$w1aqQAMtWr#7ln=Fa1Qk^xuw`c|g3(514ra zGoN7Q8O;2HIWJ(&7nt)1=KO*=?_kygm~{eX{eW3lVAdPhu0zfj>XY$;nFlcQ17_a9 z%qN(61~dO)&I_3H1?D`0Ilo}eJDBwVW}SdpKVa4snDqw6{RC%dgK<6L?0PV+Q=DB7 z#`TM{>%q9Ladtfz*E`Ox2jf0~v+KdQKj7?oFzy?LlFzOO<9_nP?Qw>2pP?N0AL`@2 zL_4@&(LU~D92fUD`h)u({lxu{{^S0SxG;~5@vn?{?>$x>#JlRql$8JPP6bRgjCjj; zoMssDrhB1`c)fm@Zsdq}<#}bqJ1x8JtAlvIE~SikDM!52N4&IycxfN;a$Lkqe-JPI zM7;Fhj+c2ryvz@nc>^<_VCEUj{DV0!V9pnq^9bhrf;sPC)&rPz0%rYySyy1z8`!Qx z&K>H9@q(ELF!KXu-oVT!n0W>>|6tAwnDYhZJc2pDV9q<3^#Ep_fDsqw3(UF#v);hf z+TWI#kGh988S=ADZp*x(`fl@nyJVdg%DpRr&D{(p7Mr`cT$9e#^nWNa{O4HU$X~9>`S`=UKE80B`bOj3FzvDH&_&8kBJaBP&#D}{ z>ZWVoL7JcF`PW<|3CX&=mS!Sn}A zKf$*Dh>`bmGU8?I&?iG4*XX|ME8mgk{!FGmfA7ZlUvh0eMt|cnrMv8!ElGdZvh=v> zTKbm$W*waWt81Pz+D9;E-fylqHjXwn=>x{K<+lEWl zKQG7Q-~F4o;Il2KKIF6mrhPES1=Ale{RGp0FyjI1j?AZ5b{zgFlKl-hK-2Oe{ZzAOXqu*A@ zc}^Vo?>M`V=eWVXefAvBxr6*a`YcG;Ppuz+6`b=6W+Q*P(&AJ`K!uYhbQt19P1l znCsubTo(uCdO0xH(Sf-WH1*9ZP5u46=8Tu%k&dL%H{DS^3u z3Cwj(V6Jxpa~%|z>!ZM2HwET;Dlpesfw}$)%yn5{uGa!{9T%AEyTDxc1?GA%@IP_= z8{*jA)ACjjR90WjAUfVtiP%ykH0u1^4S-2(WZxK0Cc;rilte_UVuPKWD@-|ujJ z@w*XhSsJN5A%o_6qlp7!zHp5x+u zKK;Rae)@^`|MdT#_n_ zHFNh5?SJP!42bccv|oX}4}-lw1NUt}yxh+L%zYlf-2Va0eIdZuSKVUc54w(D!fVn>pnEUpCxt|Z1`}}~p z{|}h^0)e?-5SaT2fw`v^`0v=q?8i_0uo)jd?PUk%US#0^*Zau92YXL5?saB-{y*4b z4f^(;U4O?ujod2?V{u}9oxN)9y=}QyE#mrD z_Wic^w&i}mu=#iF#r?mt4=~TyfDix5xgI=Y0(R{4ICxG6!&kX_FXK?%-=OXd!4~)h0M8JQ?Sw;5wBRrP`WAVHaFwZdo z^E?so-*Ltb&lH3Gzw<0M*yq_~V4hh9=2>Q7o;wEqSIz|dpPf_oAAL?D{It&w(FKKmHj^vvkeGsEQlQ)T}GD`k*}o*zB#_)2lwtK2tum5g=Pv!q>r z3YVz%%I@Puhp}sS69z1Gb<aPpw?$c2-G>Pj7Ubf5|LU{FT@4%qSIpQV#WVl5eIc zpB!!z6C zwz9ao@)vpANrTner;z1FTPa^qd2p7NQeb{{GuDu9&85i{-4}Fu(`K@KitZQcaIvXu zn5Fw>cgfXEb}rOCMT@*@CfNh@ETp9qT1c_Ey6@=AOU7K#P#*LkmpuPj_xME~oYJ&6I%9XdcFpRiJo@Sz z*W;h|1pW~B&b7!2)!*Uv(X~*1H={qdzJt{FQufQ0Mn;}h9#$xwxaQP-i6dJ$%FepV zM`mV__!i0=6Eew-2Fi8cW|4k{l=o(KmUcJQ&XmX5rH7w#odr4NQDtTLd?9U;Stnn7 z`)k)%#V;7HeDRIzw$Jrk!tZyybA2G%&vK>yN7t9-b$^?<$_{e#PvsG*(#YCS-RtId znsm~osP1o*`ZGtVK3o}N%}d_D4%ZjtH8;;O4E-Fb=Ng8cyBAX&Pr{T}Ty%a9whjr>haR$1FzxmM?b(ygX)Yq$Io zc2M`3-%&NMxJ^}Fl{&XH9;UqYYz}dlr93>!Sx%l&KGmR`w0#p|><>NCONx7}GQ6Qw zZ<*I>rQvHOdrRG#VTLmu?j;GuR~X)#y_Xy-7-~3`V^8rcv)pjWjXfl|^)kaNbGl2} z`AZG&KIb7L^F$bKy~#sv-P~l@se3QUvSNqfACLBxn-z8$_G!>lsyyCjIPOj_`J;}q zciTQv>YI2YPxEbGSu$Gp-|JPapF9{IYvhGj^pgg?_Zlv@qo3q$wa4&_!TqFQ?cIhS zR?a6adg%OmMI`UvQb_kNsv1;ub)j;GB01!Qk8o7zpD)TOnLBuucX?w)JErIa?W!`>piV{QFl3TC$o{e zb@z~K8J!Kc+}20JGvqW}BjX?$d_1?|!WD;0i$=Of=;&+XWvyEQBR??IQ{Gq8-|n+c zUUGhe{=SD+@RBnnl-m^dlGp%!9%y{lQ${!|yJhl}wQ~v@I~|@(lvjC_v(Nld)~r|i zU!@r$Rm$sgi^Js3GCI3*)W|LpyHMG2_gAt$lRm?g?buZ!M<_d%?=H~?l~+~oAuZDB zGmK}io-(b1veWY3(zu>-iC_DQb5-TFIr@uhR^_`T2Fi&uYNtfHZ)N%v<*aMIll?`M ztEU<)UJ>fg#|$nK+|t3sCBc=Xbif-^S3P_x$i0%viC>qO^VeS+d98e9<=JuNO&3ea z(TB=SB1_0PSJfXJUQ9xEDla%yM8@}hYyLJw3QM+X?+nj;=_2)tzBimMy^B05{lW0( zBMXXq{f~ynH7+PcDyK5OxsEO<>Gmpz7aJ?Z_EtA?hnC|czLx$TRopXPIxbhvu^AUlD)L@=2xTTi!0U4SmS$- zlE@hSZEd+{q;zYjzmLPmjFe|bl^@R;DL!B8?`fX2qol$OJrDX3C*X%078#O8*_o z6-UjGTxHb$T<5v6JVO8W_e%3*MYQtUHuI%*obtk<{!*!LQ4?cCaeoS3;;!P zgXB&_qB|*65tg?=L4E+8JIKyGU}JRBjQuQ2Iu-H}W(0{ABNDeg5e;)=$Es^*Q9R zyPwoK(9!6W3-FT}Cp#JTDZ5aXoat=1ea1zy6bO9&1$R zV)DJK^9zluzLSe&@>GBFzIKuR4yxa|L1FP5qdYMA-dOOevQJns`B+u$WM5N44i8hl ze4>kuB*8%;h9fP?o*B^)F#AnJYhJ7XPI;x%6?BB?tVk!^3IZ)o-b~QFXO#faA%v6rOJyhB_ zDmQ#GLM9KWXLK&j87*J0uWPu|LN8e~u#VxAe@v1d1C(oOEEU z9DbzyWyUcw;7hgB;>uK+9;EW;;Xbmhw2oV;tB>4YqvNLf&0FHDDK~H9Eu{|W-^MPQ zDL)TXeiA=J&gEBjyfj?~TvnU=uTPT~o0Y3Pm?e3uYaW)Im@Q#N8XEuWHJ>Lnt~WC5 z*~Cv`27O_8`nJX5wdG60D?I~c@D@D-(R;*FxiYD_k$-5tRD9nxGhFOrh#Z)teAOpJ z!km<|KM$5HAx(|W*yQUaqP}v#z~p^spXeEj?3YAuEc-pd>;na}KNQTqQ84>S!R#{y zv;P##zEm*#Rl)3I1+%{u%zjcZdrraZIR)GO`|Lf0oIQzP_9}wyetGsbLe8E?Fnb}v zcE36M&>?4kI+%UyVD__v*_#Pw&nB3?oM5|On|<7nv%ee6zHc!5!NKek2eW@1%wAM5 zdsNB)Y9BZ3u$LCh=OQqlZNPly0rOc1%x5GppPj&brULW13(V&+FrW9pd}aglSq{u+ zJTRaAz#pHURUP0nBF!FrPiZd?o?&Sq04J zA~2tqz5lCz#KoU_SSP`8*8fvn!a-v|v8#g82*#=Cd)F&&*&xON048GMNA8g8Bb1 znEw}p`TsJQ|3`!Q|23HZ*Ms^0KA8WTgZV!@nE%Uz`9D6G|NDdaP5{hz1z^5g0P~## znC~LMeD49~`w%eSU4Z#c1I%|FV7>zZ^W6xT?@YjamjdQ{8!+GJfcZ`a%y%_lzQY0Y z-42-Ve87B11m?RVFyB*w`Th#bcTHfvg97v26qxU?@M} zaI6%{sQgo{IPqUlQ}-J=94D1ZDc_qAFAMkAFmm?)!Y2EI!90T=%${N}d!@nbI|kPd zJSJm0)H62M+&(HB;*^JEJ1P%~>N!dm3mlPt-z(>JPLP|S%I{ttl5=~N6Os-}*8|G; zcOHPEk_B#3)M@x+k{}jx=R51Hh!R%uNv%eM0zE?2&VZrQ^1+#w^%)VMM`)$GO!v(WH z7tFq0F#CBa|EHY8!hS=<#XdwZ`xC+JTLiP85zIbEF#8|D?281mUlPndN-+B?!R)&P zvmX=8K20$DH^J=d1hd~0%sx;s`$H-Jr<^0e{x!tKzBVxX-N5XF1G7I4%)U7=`{}^! zvjemL4$QthF#Gku?BfHozYom5KQQ|N!R!+RvwslGzCtkj4JrSp?1RmID8$7+DKPt| z!0f96v)>BLJ}fZ%v%u`z0<)hB%swwL`@g{K3j?!X49q?^lRq9}UbtH8A_v zDF3JI{kV|j}^@RRxtZs!R&_xBM<0%1+#w^%)VMM z`)$GO!v(WH7tFq0F#CBa=k*1B?vo5V+z%Y~xlcI8}dPwsmR|G6JB;`+b2 zKRM4C!F*vK0K|y-!ae|C%op|n0As$e4*(eRg?#|Pm@n)D0LFY_9{@1s3;O_o5f}CW z03%+?kq7D{KeU6q(LVCYagk^GgZ$G^%oqK~d@(M_dHx9Wc`ga;@VpY(um4}*{1omV zf*f*R5is`~0dpS`F!v_`bKep$_cH-=pA#_mKLK-J6fpNo0dpS}F!xshbKey(_hSKb zpB6CpZvk^(7clpGq5Pk6z8m*bLR{Qu3C#VMz}%M!%>A0c+{X#b{hh$v_X*7XpupTG z3e5eZz}!~~%>Aao+=mLx{i(p*w+hVttiaso3e5elDF3INKg;ui5tn`5F3;hGoagg` zd2TP5=lOzp&M%nf|AKigFqr2BgL#fHnCAPBED07lV1OF_?YUVD?{A zj&r)Hk8`@g|JBZShR^Kh1@l~TFwZLo^Bi+9&o>A2+;cF`LkFXum*?8^{B+29t~!|K zt%G?EJDBIQgL!T{nCH2JdCohS=f8v5XANfmHRXXtI+{6x{*y>I!?07ki8Aa*{MNz9 zF>Vz8)A01bB~tC2^7Tall2psv$l3D?o9sIV2i#mPAywNMor3#AC2&l8!<(nCkP>O! z45up{CjApS8r~feCNFn)HtcslOiG^l%JAUib4lFabT!OgX4p?ZBUmoHX>R1RA_Bx= zb|b?}KlMsOhdtC__Ev-0_YGe9sUIACrs{NYpQz{RKCM4PQY~>dHWRwf6z|;1QJ&uN z{AD&HzZU8vmFlZ}Sj;TRc2D`qZeQvDOzjL`JzGk-b0M$PZZXPmll^(6R;Ce#y>jG}+NXyaUKX2Aev2Gz zcxFO=X}S43!|bnzP4*On*=r1D|1voITv1uFQ|shq?IPm!Ue6Rrb*+$u6jlD_tc&C; zKgHN*zcc=py}jUrouZ}CXL^73S`j5lfy%!g+aV`kE4y6Up1i-e-rF0T+9nw$D8EiV zlh=ERa{u5ha&wvTDX-0PXSVXlp_{~|pK^m?8zrWMa*$7?1SP8d>IXJRy#dPXFNSaI zI|j428q7Xru=l-aS-!imxvxI`Ek`=i10r>&Nk z8QU6tw+rEtJ-Cfwf46XHR8+axpQ|KwP-`P+4>kUFk-1aH6M;kiq zGX=B%6wJOkl z*mk3Yu2A0II8rV@Qhr-;gT!WfV{{7VTQ3vds{Ei+giPA4%zkRvWbZbZJ>B5r&L_mX zlzt0d_b^dL)VpeI9tcd7G0EozLuWvtL@Ctxx?%QxL(V>NF#E^B>`w=?#~l2}=3_GQ z7oD$_qmE1FRXUHEb0&(bug>qjnTayrN6&O-Z#({$eahgcB{xd{s)vm~gL7|^FIF8= zpYv~)Q;n5Rl;0xzGb=kb+A4u*mG^hrCcfpB+3yUS>&Twtwy8YNcAsXo4jJ=d+2v;$`uzURJDcDVZ(UhKM3 z8aLNx3HJQLCVPaz>>UQPrx?s$V=#M=!R$>2vu7DxVR@9)i;pqmvTqvl!gFH8V{@#L ze}61me!REW@bF5}(lM>_wCE_Q;k3ud?+%WVtnYRi4sRbNjqm(ym_669$^LFI`@X?> zE1i=ZO-~s8(FM=S-HFQXY0gN)8Olo^osy*9%Ipot-?En+%pP+vd)vY111?LQ23l7+ zLoSPlht_9{VVA{me1aMGV9v{O%lnAoMn1nts_91!$0c2oKl&dt?B#GtDwRHNnEmpw z&pu`F;yVcve7mL5N%#7QB<59al<$~ik7!}!^IVV1mN4a@Y7N@Z3n~bkA@HI(*(1p61=njHn~tQjrm=O zOtVcAVp1D+IKEXnRaLIBf2-6BcQEp)_qIw07v=l)wn<~96L?-k4*TQGZX!R(U- zvws%MzFIK*ZNcor1+zcb@Tb0AFnfo=>?sDb{};@@U@-fI!R#Xjv%eV3zGE=^k-4*>eqMFE%*etG)94Y!#F9gD>`o*JI_C zk9Nz9=gJlC?vlGVl~3LOS<=TUpLn}d;%6$ej~h1GGY)RB>#$_5s{Z8hJS@jzlpE$g zEWY*hY^kl24@u+}~}0<>UQPrx?6G>Y{w-e#cy!kGEWs@pqJu zF8D>d1>H6BZS611{t@>K=e=`Tz8!Gi@SF};r09qThS`q{o9tf(v#%M3TDe@W?Um&z$Ahe#1BBAIipIU^Azltl7nchI-w8{bkYr=*mM zg;2?9A(m*Zl@x1Eb9R)JM2h$-e512YsC2TQxAFSiU*6x}_1o9}WAE>^+t<~)uFtg| z*O=oo#$!Cj`~CjB4r9FDC!hW1?R(xI`J=yk@&!M<;Zqm?-pLm~Xv6JR``z|=;dXN2 zc6H%)c;R+?;dXxEc7fq`pJ6j^c8B41is5#R;dYSWc9Y>>I@(!=+hvB^afaJ{hTDmT z+m(jfp@!S7hTFM@+r@_4(T3aI9{;2LU%0(sxP4o=JzTi`T)4emxP4x@Jzu!}U%0(s zxP4)`Jz}{1Vz|9yxP4@}J!QC^Xt-TzxP521J!rW7Xt=#;xP5B4{cE_rZ1{3V``U1O z+;IEdaC_fydz5fHk8rz?a66K4yOVG`m2kV3a66cAyP0tNn{a!baQmKcd!TUpp>TVn zaQmuoyQOeDr*ONda677SyQ^?Jt#G@pa67PYyOVG`m2i8DaQlpKdya7Xk8pdDaQl*Q zdz5hdm2i8PaQm2Wdzx_jn{a!ba677SyQ^^fp>TVnaQmcid!}&vr{i<9mkPJ93b)4! zx8Dl4_X@WUJNBbJS-AaKxbJ&{`+gs|@BM-Mjv=`39)kbsvmbEs)i2+UEx-HN15f_Q zmu>j#@BPguFTCc4FMRBSPd?^jHvG^3$eFqbK z{7bKQ^4l)Io!frP&tCWBUw;03=5NPM?sJ`!_y3yhzWk@$ms zs_k#hXWji;C;#Pke>VP4x!<);KIqf8zfCXvjcc9!>#J^mNACNiYoEN&M{R#Eu72@# zPJZq+-aY<(-xCgf=M>y`QNj24;s1K_k8l5PkhX49YzV_thp0?q>$4bn;_X_U&u;9KY3+_9);J&L1e$@9} zaPlEH-SoNN$qP>2@z|!@Z@%UUCm(UEzaBn+`x#F-dChBY*ATAt&5u9%sz2WFk6iG> zC*S+{?K(r>^EENwaly%dJ-3|~|H^qkeDbOn|IWmD==*;7>mGmd!SCGg zwIBC{lUKNOy9V-}>s)a1=}+IzyWjOg7o5E8>DzgC-(Mzv`-X6Ph;aLfaQlyNdy#Pa zjBtC7aQlyNdy#Pal5l&JaC?_<`TVnaJ!#yJE3s9qHsH;aJ!{&d#rH# zt#CW4aJ#E;JFRfLu5dfBa67YbyR>k7yKwuwaJ#o~JGpSXx^O$ZaJ#*5JHK$dz;L_C zaC^jX`^9j3$8h_|aC^#d`^#{9&2an9|8Rv5JF|BFUU}a7@AI#8-r!%o@MV{M-%f0Co^^WV7%b1EgS^KN_?$T4dE$Wo^zNuG_Uh$-`lzlG2l|{i&`sX)kyFh_bsay@ z|M)>)jve+(jZgfo>t0rku>5L-b{|QSUCx zE=T@yz~aaOi|+?!^KUR;Ibbp5fbo|D_If$6>s|h%)lr<$5LVMcUcHOY^nwp<D?CRI@8na2Ri88adukD0n^eC%;w)Zhhhv z@Yg;0Q^)@2Px!OTp7Sr)9(=)vef{Zw{P8OfzWpa(bo!TnQ8y?&0ZDu?+0e{Z!llK1B+1(vE^Vt zs%tPV2mZ$o;v7GSfBYcti32_-4tSn8;D16M|It+rn3e}Rh%=h3oF@)+JF)W4@3Z;0 zEzU*97tg_Bh{Z1U|5@+e{mko3AHVb$-hSE7eC0I;U*{|DbNblBKWgw@KJLQP7yQcK zAJ^*>AN$*<*U#W(JH7sG@bW#gerNECac0Fj#(%}0_aMApFYK3PmjmW62P}>pu=svp zHvb0m^*gW_a=>EC0jv4Ie(b>i_(7cG2l0;|*7;C`1A8RP+RyT-h8>^5B#pT9rs%Oh&Mm_ z_*?(!yc6&b{PHg!f5a=UIvkhJiR*p)rwzWwD?fM~zVZEDcI-VL{=UH%U3l~3FZrW) z3>M@1@AUi0(2LUtJvx2RyUPxHy72$y zYv5|nc>gi4lUF_WMwfl>U%qzmMUQ&+WmkK~x6NzjRnNWXvXA;tPZ;~n?*EqMbLX*N z^r-8ee#*c8+pYcX@16PQ%RcsVUNNt$8@}&fmjB0$&&}@tm8W0!_?x_f&m-@Dxzk_! zGe15)kNCU?t>1m*F|WzrJM*y9Z+Z6JF5~lt*S+VmkNfC*jL*A1>UryTU;GL_kG%h* zPv83;myFNDuk;I-eb%X8IOa9{_Se30{qE~8olKhf7MIZ?|$9*eB#ai;j#mt zTYtfyK4$azq6^mVe)ssi>>qA?*+H&jx4+Yi$LFeFckIyT*a7EbkNw179G_Po`|kC- zd#+;#wIBMd-`zPMKhW^_L9XKmwI4s|#jyj<>vwkzk012$*g@^sQ9I%|uAF?~I$lv(}ERORKSbUnoaymDG<#cWW%jtCp%XwJif!#S*{&S9V z6lczTU^x%+>SKJIa}5^bfd3pnZE@zDt9s`gjh+92KL5AQmk*9T)^XQ%Y;*1RJoSIc z@seYS#rwpHzm89KEbkmQW_Jvuw+Hs|Ir`l>Hr?>m=lG95&IiXl z$srD#e}nn@9as!GV6hMTwR(EuhBvxkUbEMD<)a4Q_V}qCPne{uz#auDYtXP9r?CBl*%E^8jW|t#>Ibd<*fW`L% zv-vleuN<%#V!>j|0eejz*pDChuXDpa&g9^)rh~kbgMIl<4wyCv{HJ&9v^=Pne>#YB zqBwHEwDbeB$+5+`+~k18Sp3H>_F=zZ_4$vF|Ko)pOcOC-TFC{gPd=EgxWV+052llR zF#Y`Be{_`tW|srzF9$4+9I*I)U^f2-^YuHh808RK4tDjOX-@&x(D*|NTeHgL+4Ic3K|jGkszg-w#YnIbgni2gb7;Vjo_oI=FuIAJ-L^ zR<8N|d%LdqAMda2_5A;p_t#;+V4t7fhlkkvk=^Hv_vz7R?0@`?TblGaNfX-82&S3i z6PT7h%d-27%im`oERN4axX($r&q=t?Nx08RSnR{&lY`@y|2Upp$8Y~0k0)0z=Q!E< zl=qwCOy?AOyy5@({OiES>!9CtY%|xBT_@(#xzhhr*W~dLQ|z$wse|j!|F`ZP9PnSq zFdsTU`hV_v`2YWNxBnH_@b%?DtIj=7|F5_Qaf>g$;fd=%;i)I}<$_3s#?eu)1-B=^-CXC$+%!4z73E<$(Fi0gEFCEWRI@&A-8X z{SGWfIq;W*-G2x6=^Y!62XUr%>}op5JH2CHzSBFHHgdpe2GjDO-sv4X{{wxdckHzE z1IsH1%-8S0c$P!#!+!n3$6V`tKK^^%CD$DMZ@=;Tryux}R~h`~N8RJheLn3Y2mivy zJmbtKe8OK(%uApB>u1)_;AK0r{%!E`edYR{!7IiqSFGvdiv7wh%X#Omob1yVb~*eT ze>q@r~iEU2P}>p zu=svpHvb0ml>-(-4j6wqV6V{w`@Fx7{OA1z<9-l--e2s?Ht#Q(1_wOn{l!i*Ikq_0 zn)g@s10Cl5Rh$Fe=KaOaCdU?Mdw;=V$N~5Mg5~u7f_+Z=EQS4z@EHqxt$EGCKJR`0 z!pr7wP=9CVZyEcFF@MY86?;C7mIFSj zEBpK{JMy2uWiajs@&8>Phj@Rf$$!08dVjHbP3b%A_3SkVd!2htz+RhPqp;V$*96@A z3-%iKfB*IVg4yMO`O5)|BL^(LADGR*!F>G=EJitcf3f@T!2bXFzh8&_f_qIK;#F_& z$N%`8T<=G(S+5mZc`bXb!0Wa1|Jvu|yI=p(bBojYZ+O!A=hic`cYI*?EbZ*4KK~PL zH~1UA;pd7=`oLQ*H~5Es;DS?s@H_u@*6;qs?Vo(=25B4VG)wGCoJO3_hx5uv%8_gVnw?8N75m zg@?TVKbW4`&mH{kxr1EimTu#-a-Cbc4PLp<9n^Ae={ELN%ekf7;8n}HrCYU}Te?-t zx%63@>{vh3^APhn=#gCK)N+(-@KLU_>`OPf1~1*zGCoT;wG2M0Ww2TfUNh&u{1J~h zCC&%_;n=y$J#@oAcgeAHC%$gO&;Q0_=YHh&8-DiU z!~Cy#r45Vo({K2$J^t4`Ys2#X+Cw&s&vm|H!+757b{oe3BTjBuUD?mS&GFs;E{{FF z$NA`AKYp(G-*Nd9d){BY)rpk8JI{}N)QO${>z;ICuj`Y4?8II#dpht>A92!6 z{PdJJo$*P3JnIYoSNk7-Kd-AhzU_HuAM|@0{-rN|-q}C8WW&$;h3B4q^0#dGdgnj) z>{nfP!*_bsg=b&&iucd&{_K4(Jo}#8ZusFJb>Z0upL^ffZ~D6Doc)r|-te<8dd}Hj zyYRhZ|EHgL&e^p9IGFvDzVGjL|7Trp!{WU92mf~L;@|8B8sAO4)(|F3SnVR3%$8#XNd z-#ux=@_zl#ZWy1Be(i?wyup9p@bG`fhSin*OTY7?-T$I{zi5whjnDk4J^sz!^HY1? zPkZu<&&KEd*LcabRksh$je>zgh;ci+F= zF#9L|)-!kiJN(4628;9Tdpvuv_}}&S8iWP({mfqPTko)8I{fPkHcX%I{PdTO z58b}}H#SVqpZ?yT9Xp-h@?|d@tY1(4%%2;qFSoq%&kxqGH@=*p@%Xj}X&wRyT zajtf+%La@8*Z;U-dB5plr^k-Z6aM>#@qEz7pBcM;-R{O4R#$fQ=1+&>(5LuxD=$6c zL+5zXKmPhsUHVnM?CHQieZ)yO@zYb@bjBzB@vJZSU--5wPmSuj(}!PWulIlZt_{=S z%Z^`l*XNF(ceTNE``~w9eK0*QegDS~rt=k_{0W2g>(O`m#KGJ9>so{L>tEk^?cM%u zKXl#Q|8+OK-e7Sa^^EHe7XMa%_$hqRE9N&Qfi|@NJV0nFK20ZWg_1zmVp1xxP)-T_^0jn#!dVTi>I~|HM zujixqbSp1C<3s0o(m($CQeFC0z3l10KYheWH}TU`-gL$%{qd|X_&@!heq*oen?L3^ z_j>Porw!BLTVJ$c`ux>RUOPT?d(CS%Owa3o|8I?*&Ud-T>jvxB|911=9;{z4y6Wo( z>(?Fse#7h^{yT5j{crx9-x(~<>&!Q$WlpEoS;J09`7W5?&i|8T>2zUvcyZ|wT@ zikog&zp|@0e>xP0KE(d#@zGtXW_{)Ro`NQvg)nGcG{KVG` z*00Za+-nCP^=q(xed@E`xZ6MeN^jo%Uw!+x4i@LrKkE+$i~pl9efwZ}AM?t04#wxI zC;w~cy9VR`u7_?|zp|@0e>xP0KE(d#@jvR<lRnM!~Xhw-y=6nhx0%03-{OaXMe#R2h;7(zVA+h z>G|}3`l7*fe(%%nJXpWJ=`ME}y!GpDgZ1lAe*a5%`~9AH_uc;$H@(MTalY}wuNW-; zC;!ns2h02Me|oRM`gPxnzH%_0*S*fY2kY0XZ@*!6Wmj+hbSMseich!l(lb7Ejwk)& zzx8XYOTVg@JstR`k2vWjetOEA&iJH1p7jO)b$xzb8|r%fpKVyZZ~Dbg-(R=y|D~G_ zrqAns?`DJP_M*3a&R}|e^Cc$+)A{wE{P~0R>!ts8$H7Pa8mwOz-sqmY{d=x(-`)RR z5B<8q;=JgK9xzz^@B7jR4VL%5_y5+x_&ogUzkRTNeb3477>xgQ-?m|OWmj+hbSMse zich!l(lb7Ejwk)&f7GwZt6$a2o(}xeN1SvMKRxA5XMEBh&-#MD?`G@s(08`M>h)c2 zFdcly8%&>T-|69l>E=7(*hkL~K5{UfeTN*oe)(=WSijb@Lk8>DpZ(Q_*?;mk9<%$u z;m5vrusAoq`}YkN|0CYFVR^s%+aEi2e4hWN4deNJSN{I7({Dl@KL`8>({Dlx39W(|5evuaaLV}#b0#| zmUq=P7@t+wU_4h{gYjRl!@=sxuHO9VP#pRcpKj%)XME@!Px{CIs9%#yzp9r#9r&k@ zIO!&Sddi#5_@qCc>-9GA@n7dDdtK{1Ww3hJdCFiqtn-w?^jYUAgXy-;QwGy>ou>?@ z^Eyu%tY7OqWw3s&dryP)Yn`X;_H~}J`>*qq!Q!m*l)>V!^OV8zuJe?^_^k7k!FaCo zl)?C~^UA^cm0i90)1f%@DL&oGOV9YwIiB>7zrIwLepN4fI`B^)aneov^prQ9@kxI? z>kIzt@A6*P`n$Z>yZ$Z@ro;NXJeWS~@A6=}t-s5I>AC(c52o|_yF6IG*5Bp9`t_o# z-fggct-s5=ef?eD{ny{+!Q!mH%Y(&Vf0qZ#yZ$Z@#%KLq9*pPuyF6IG)^XHe{mQQ1 z{OM2}`V^mT<)vqQ=p0Y_$6sHnOTVg@JstR`k2vWjetOEA&iJH1p7jO)b=-S?pNH$X zcd&ZbaqnO{tmEFn^jXKfgXy-8dk52V9rq5V^E&PwtY7Q6cktG)*ALdOb=x^? zc+x-qTfert^s9Q=(}92bh?8#Or>DH>j8FRGSzqv9*8%p|;kpj6zdqM>fWdTF*8v98 zXI*C)Ot*C%U@$$`b%4QiUe^Hz>({ytFj&9Vb%4S8wXOr~_H`X#_g~im28*+<0}K{_ zT?ZH}@45~!7@u_=U@)HRI>2E4TGwp`>sNO5=1+&>(5LuxEAQxe#D~uDq<{SNrMmR1 zdfC%~fBJ}%ZsMn>yy=Wj`r}z&@L$)l_qx_~?7iM~-Fq+{*7fkg^jX)*2h(j`KOaob zbsc*!o!9mD!TPnX!w=s6er;I4)^+>czOG~M{_8sSU~$%U?7`x%>)3%PNa{mQQ1{OM2}`V^mT<)vqQ=p0Y_$6sI8=hNiUuj*w_2ma|JPP&Po zp7N$MKIxBVeZhZSx7q7j*KPKC*L9o0bXeDI2GeIgb=_t#J=b-c!E|2NZ3gSt zx^6T0=<{%}ey!^^yZtWrc-`*5uG$=TgJlA!b!TPnX zvklg-?CQ;*4#lBQ@#$7xdd7#&@uYwJ^<`a;nq2x-z3l10KYheWH}TU`-gL$%{qd|X z_^%4L>9oBi}VEU}{%E5G7=aqx$xy~yG(|Mg&4%V-AUO9N{*WCu| z*E+Ae8?3WlsnG=_5|MiJzYGrZYb2k7s?sf88hAUx({H(f;~e z_lXA6VcjPhOrLe1XfWN@eWJniT=$6v(|O$|8mwRIKG9(PTK9({zZwAedcNg)&l^nVCx6EM2J6>*pY=bE@z<~K{KhB$B&=V{ zep&YAe;Ve$;tUpN#UCvG$~#!z#peuvd=}5acrN~f@n3Zf*01d9&7Tg%p-=JYR$h9> zhtBb&fBg034o`d9)TLk5%bpJW(?^_i6F)uWO=o=4AJ6)N|4rWbxKnDs<&|%B>Q=AY z@VlS=Ij0`^3md+|XMfJAZ+qc}|K>MtdFoA%-SDse*IS-?_I)?}71zGysVm-W!`FP< zElxf1Uw&X>e&kDTaq5CsZTM+VxW%bI`QZ)!^!MK4)aQNqhwOK|_J{mm^=IEdzbnpX zo!PMX|M=t$%lnnzvSEDgcJB@2`D0(aVf>$WhYhPM`(wW6R=fY#{LQWQINx#4&)wrc z|7D-M=e^2D-1<~}?s|t?pNi*KfBUU>{=f4hx8CbI^UPcC^|Ge}|MU?j-Na8%dD9u6 z^vAQl;QxnT_!P%C=RfEww>$O5J8$^97k>V!ANr~d-}V-tf9fgUy5XC=_O_>P@stgJ z@SAUY>H)9Z@RP1{+f(QL#fI(}>Q>4LpqH@(A#*+1zK8|MFlOE)ae`ETE_ z_}}`GPu%lfmks0p>v!Mqybh1->dl`H#i38}=~iBP#)r=Fq<{SN zrMmR1dfC%~fBJ}%ZsMn>yy=Wj`r}z&@Na%YUCjxoxA_4&G*>{Mb)D_3_oIF_hd|Hf z6X@LB0{xq3(3f?cZGPALtN91^<|6nvFCk8I6yi5uA#ZaR_%x4!XLB0(H@~5-?CQ;* z4#lBQ@#$7xdd7#&@uYwJ^`*M>t9seffq(jllWyXtr@ZNmPx|9oU+}-r58QiRx9YmX zlQ*p1mtV4BI{f_vU_=xl6uh_8ozx1E(x99!foi>cmmA`Alcs}|^H;n%`UASR& zWmj+hbSMseich!l(lb7Ejwk)&uP@c5U)9T=4*b(coOBaEJ>^Yje9|A!`hx$ze)mU@ z4(j@oAKb8d?|IRN>F|xezhU~k@S0cJb-UUFHcZdkzIwxSzUOCt%=pm%bDptbefi!i zeeBrv>vtcyVfL5)<%aqH`rSWne8hR*r5hIiYc6-?J@0cqf5Z6v%(rY9&+9*N!}x#n z(>JWH?CQ;*4#lBQ@#$7xdd7#&@uYwJ^`*M>t9seffq(jllWyXtr@ZNmPx|9oU-0k# zvbwsDsow5y(xLmF^yz-6&!z5@(zE-gbnd0 zn4VXE!-na6lUslL_|X4~FW9iYeC0JBI(GfK=m$2;{@B0YF#l)%=kFLFab9zJ!{UGL zM}6m>_aS%QFg}lc_=fTP`ybyh{_l9+hSil_z4_CjIP@t#-O5YP_|Q3?^pC&3RF{5L zFMB%hPakp8P5ktfH=XfGe?038{@4HhFBu)w_0dn-uzDYU@rLQ}gg@LceSY)0ciDA2 z_TUZE^ZviJVLCtjmUkT=`rrGx8$Nn}ja|P!@V$2%%>L%T+c5w4eC3ypU7Tyae8b{@ z|3`k=*uB4g^^P0H=S|=Fi!%y0WV`e>xP0KE(d#@jrTh z4LAL&UiNh0pFZNGoA~J|Z#v_X{&?0G{D1Uu|7CKi>(M{5VfFs)r5mQh<=?qs`rP*V z->~a;@waT4p8x%~H%#Zhz12645B-1p`5V@k>wNqJ#;#xA{QVndzw`Sy%>Qfd^G)L; z&J!-%u=xLS#Ru+rkALxo@wxNEHjL*he{93}zu>tWR#$fQ=1+&>(5LvL+fiP6#)r=F zq<{SNrMmR1dfC%~fBJ}%ZsMn>yy=Wj`r}z&@c)*_eA?)suKPTG!|HwQPi>eEfB4o7 z)8|^(y5X+d;~uzSdj9-tHcaQ&-t0!>L;s(8)`s=v10Vb8W7n@cJ$l3JH~i}j^FR3& zHy$5xzVT-_EdHA>f0I4$)o;IHd~Wz{8^-fTpS)rGAN`CCt1G*D^QS{`=u>>Um6x9J zp>sUxAAfzRF8!)r_H^K%KH{XC_~|KcI^&c6c-9yEo5xmHbHD0s9+(cz3Dc+fVV_IQ z71OhMV>&m7O#kMSxA)hd@8@65GqX46%)j|(ahi)3zjVKOU5@6l>EC>^zBIS&{nb1(dvnhGn|~IkxoGj5mzK9V zYJ8fn#A*jI#7Q^t(^KAb z#wY#ptS|UC->a_XNY&eXDIJu&q|tNB>==4Saf zPb*Gyw&FK`D{phT_%yGJXLG#xH{YwS?CQ;*4#lBQ@#$7xdd7#&@uYwJw|;GP=~wl# zrvv}=5hvZmPfvN%8K3mWv%cWp{JgrF(^hZu+jMBIn?B8Z)2%shdNv{`ogHtlpn}%ZBOj z%D>$(eZJ}{kKX_8Kl%8E>3O4X+%TPg_8A+d|8w8CVSQP1u=Be<5C8THHq8Fchi#bu z125UII3M&b+Ibr%-`)GdH z>%6&QdagOx`K+UJbI9~>KKZC$`{!Zv%DhiRo!i@`fBVb&vaU<*{c3-iz5QkW?F)<3{<8S( zFU#BhGCu7u9g+h4yN0>|2vqT>ptvYIb$@xV&%<@!dAG0ou)F`d4?B4Jb>9t(zwX11UEXycb}&BcKJ50pi|4uz zI~f0U-+ZvTva2_LIuwUK#h-p1<)vqQ=p0Y_$6sHnOTVg@JstR`k2vWjetOEA&iJH1 zp7jO)rQKfF(sZwPX+2oKmUe^bv$PvbxAilap6lNR(|P^QVEtO!4c4!v-C+G%xp({G zwEHivgT+}j3>JUYHdx+O^I&|I7K8Cz8V%O3rQKlt%C6r0=};W{6rXP8rDuHT98dbk zUtg+Azp9r#9r&k@IO!&Sddi#5_@qCc^#%VmOR?9rW-Ru4*X+e$I;>fW!Sq?P6ocuu zW+?{KbIno=rt_Mm7_47wmSV7etyzk}`n6^ecKe!9*!|b+!eDXMOv7OD*Q~=}dDjfY zV0_kW#9%zv%*0^*TC)^`^((u2^QS{`=u>>Um6x9Jp>sUxAAfzRF8!)r_H^K%KH{XC z_~|KcI^&c6c-9yEd!B>3dTxMv*WB0qt)au3`x;E2oxHUo@1b2J>OvK z*U#^Nzj_`5d(TPW-}4j1>A4Ex_q+vp*WB06XU%=>JbP{f{yon@UD?%}KOKrgpW@T4 zy!4C@o#RRW_;3B%>e8?3WlsnG=_5|MiJzYGrZYb2k7s?s|8u|Rn)~bUdOy5j^*;GU z8`iJqzh%Sv_0CWH#POfk`8REto)7!=4b%BapY=)OL;nXobHnsNO5=1+&> z(5LuxD=$6cL+5zXKmPhsUHVnM?CHQieZ;xzk#6Frr@ZNmPx|9oU-19F5B}S{KGk)v ztA22>dXL>@!*ux17jKw85B!AlKBU_>Y?z)`__Ynw`C6ZGx$&X@KRtcJ`tn5|{b6I* zuOENJhS?wb7aQjP_%FNs_=t1*k`0T0!}C6T&wKydZWy13{N|2^M1c|U1Q$w!>)S* z`~6w=?%VS3ey%v(=M}&Ezw&lp7@zJJZk&U0Pk-}$d=|9f5Qp1@u&d-s?5cYj%&?k|hq{bhN(zl=}!m+|cWGXBkP zsH-^v^)^31hvo|C)4T!QnnR#x^9girZh`*IGw4fm4*J#n1AB83{F|2$r#TAoo3D_! zxeI)n$H22W4g8zmP*-;K=1+&>(5LuxD=$6cL+5zXKmPhsUHVnM?CHQieZ)yO@zYb@ zbjBzB@vJZScYQ-$oky#;^J_YE-c6s*$LZF2`n>*+u5Zw}^LqMszOOIsW$Rbh2iUuA zz`yGW;@tS?`iA&je~`E968Lnz0?)2v;NSHPb!As?{&Xk~eTq-F^3pRtbdD$e z(7$;GeQC}?znXtwZ!Us=^Ah4TM1Dq)&ez z>DJ#(diM8}&i$RGe}8|s_t$n@p(5LuxD=$6cL+5zXKmObMYpYAYs+T<-_@|FJ=_Y=9%A3ykq(7eZ1^>>! z)YWmmdOQB7L+1tb>3o51ok!5K^9wq6-a-G)NA#uV&goa@FYKMy@b7#_oX&&9@BB#K z&YSS*d;s!Sq?j)`RJ`&V>fka~)d`rt>7)3a&yz7{FFh1*8c`%;q7)3j* zy0WV`e>xP0KE(d#@zU8n+0~mr9g0Jr;?u3X^o$Rk<4OPc>q~X%SM{=| z1ON09C*8zPPkGZBpY+GGzTn@yjk=oaP;c`dbZ8EQKFx>Ft+^3;Hcvw5=1laf`4j!> zIf44syb61BEc}~q5vREq@tcQ{w>cSnnxDb5xf=YNw^3Ji_2y59;?Sq~bSp1C<3s0o z(m($CQeFC0z3l10KYheWH}TU`-gL$%{qd|X__v>;uJ$0*+kONc+MA$H`xJC*&w`%q zU(mU|4EndPp)c)m=vVt4?CpKdLO({OM2}`V^mT<)vqQ=p0Y_$6sHnOTVg@JstR`k2vWjetOEA&iJH1p7jO) z=A+cr9FBUM&!IzeJM?Luhi=XJ(6jj;IyVSa#{{^=u5x{05j@}@IB>5pf9!M}Yyb+s3!-uA`l&>k6m+ApJ9duQ})AC1oK zsnNgvHGOHXO~2ZAV{Z?RfBSLbv^OVy`*iZQXNOPwcX+m!hkyHe>dLO({OM2}`V^mT z<)vqQ=p0Y_$6sHnOTVg@JstR`k2vWjetOEA&iJH1p7jO)?k}sW`9T2yMIdO?yJ(j`>p!YeOUeK{w#a^?I7 z-CtH$cJ<~@hvLwu_;f2TJ>x^?c+x-q`chr`RlV%#z(0M&>Hf0#=_zkIbH!WpwC18hyIIHo6_%ccW+bEArLzBFg9 zU(KJhH^Yje9|A!`htJ+*y?KTSG~;x)1f(G`ZPaGx8{oJ*}O5G zn?t65^T|j3nz?2DYMzA*jI#7Q^t(^KAb#wY#ptS|Vtucxl|!qnTo7#-Rp zqfh%~bi4RyUyq*cqtUrNHTt)|rZ4Ta=~w%1?CrtvZ$D0)_VvX7m!o|>dE2wYr~NxT z+snhheLZz$S8x7wC=Pv!Pq*^YGd^^VC;j8EFV&@A)ytj^{L@FAbQ3>4S~Tuz0H@>p}AA~G>=NR=2Yp~{3@NBYo&kluKLm(tbR2g%ii29|K@4MY0g&s z=5OU~E*GEXb@6PD7yssa)sA92!6 z{PdJJo$*P3JnIYo>p3v;oxhH8JRfH8I>zxFn8E89$8%r?uVWm~ff?*MPU|@^gV!;R z=fDhJ$2gt?Gk6{2cn-|qb&Rv_n{U|jqt92 z2WBun>p3uk@m$Y=8I1pWZqHzKWnag1yZ<`Y+vBWbz&-vtHr(^BV@A)VnKE>+<}l>Sa#{{^=u5x{05j@}@IB>5pf9!T&kG_q@HX7r%bP>V5AoZI}*! z{-O=j=Zhb=VY*%It2a!~M}GE(>HOY*d+x;4uMhwA4eQr^F4(Ysz3eMKWPjClKjeS> zFE5ng{q2Wr7@uFe&xY~5(p@%;|0mpO!}^t7z4_CjIP@t#-O5YP z_|Q3?^pC&3RF{5LFMB%hPakp8P5ktfH=XfGe?038{+GYUGxvUd%-uGu-h143!*uwP zPv0%V;AhV^T`kH=rXuJNXy7|ed7XK$GQ zGrwuW;(X-E4U7N!t8G}`o4@br^Sk)m=xrOu^TEHhVf-KV>l@au?CQ;*4#lBQ@#$7x zdd7#&@uYwJ^`*M>t9seffq(jllWyXtr@ZNmPx|9oU+`bgF`L?_uHW9Ude?K$#!iRz zJhWY(^_;Z9bX(6)8%)pj9J9f6Ue7TbO#k&9w!!+cp3gQ|zt(fxcKdpc+3vrdV>Vcv z^&GRo;;-kJ4VHI3$84~E{m@r!7|-<_v$5m9o;x>KUD?%}KOKrgpW@T4y!4C@o#RRW z`0Gn`=~wl#rvv}=5hvZmPfvN%8K3mWb3I>fYB}texytP3E%P^rSse43#h*Fbqkfs^ zjE_0bc$)u=zq!!rGA~-a?CHQieZ)yO@zYb@bjBzB@vJZS*DrNtH*cB0In3gi&n&*V z&GMS(jE_0bc$)u=|GIa**JWO`dfC%~fBMY4=#g&Xr>DH>j8FRGSzqw)cw_21I^Ixk zfA8qf-$DBH_mOV>-K1xKPwCv>S^D?)S6@2b(65d+*!w%qzrXL|bi5&c#~bo?yn#>0 z8+dkHfq%yv>dLO({OM2}`V^mT<)vqQ=p0Y_$6sHnOTVg@JstR`k2vWjetOEA&iJH1 zo*i%CzpjhUdre*Iy69l_uIr+M>9DSg4yMn#E;^WQ>$>P*damoDgXz4kiw>s$x-L3c zU)FWe!TPnXi|+PyU3B+f*F^`5v#yH{7JpqA9W3v~_=P85fw$4)q({r7t45srsPZ_LV>pW$!ey!Mp^=qA{?Dln@ zviq;|l)>Vx^OV8juk)0_@~-og!T7B6l)-qe^OV8(_xyQvWmj+hbSMseich!l(lb7E zjwk)&uP@c5U)9T=4*b(coOBaEJ>^Yje9|A!`htJopQ5gHUvIB>-PhZ7Soie?(`Vh+ z8%(!#UvDry*L}UgbYA!M2J6?luQyn~)_uLf`nB%s?e=wFZ}(sK^#+Tx?&}Q}f8Ey` zEbqFnHyEFFUvIE}t^0a|^{eksQCD{L=1+&>(5LuxD=$6cL+5zXKmPhsUHVnM?CHQi zeZ)yO@zYb@bjBzB@vJZSuer+ob7Rd_4p#4)s~k*+HCH*9K5MRWFx}Q%4? z%H6)^DtG@iS2Ct4U-umbi?i-K z3>JUgcNi@1y6-R;pLO41uzs!k4ukcp@8eKccJ<~@hvLwu_;f2TJ>x^?c+x-q`m*k) zOkVw}UiNh0pFZNGoA~J|Z#v_X{&?0G{QG_)b*(wQz1}sax9hOx^ajuC`RMzJ=(gtc z#!k;Qr#G0+Yff+b-PNx(r#D!?`W_$sT6224ea-3Z{%cNeusCZ@Z?O1lPH(WhYff)4 zK5I^IuzsyMy}|m`_Y^Yje9|A! z`hve}D30OPb#yIkj^|xNVW)#@C@_6oLxJh$8VXEL*HBG+?X~TnCu^^5|D0KSZG-8v z_Sy#1?Z$WCFg@2^+t}&6_S&}JUHw{nZG-h|%~cN8ueH~<+t*&(?!Wfh28*-y+6Ie% z?W6A-m3Qs6jUAu0*S7uc>et$98|?kn_l>G6yL$7dLviR+e7cpFp7Eh`Jn0{QeW@<} zs$TYV;GaI?q?`EZDQ`OClm2+t7yQ>8?EX4jbFhQeyXIgAd)=-%*unH!bFhQyw&q|5 z({s(i4yN;(gB|SswdP<4AN6aneyus!-M;2vcmFj9J6N1G2Rm5&H3vIb-Zck17@su< zI~dP32Rj)5HMcxizp|@0e>xP0KE(d#@jvR<u5vJa)?DRax~;j&!Sq~nm4oTL<|+s4*P5#w ztY7QAa!(egNoWo%8*PO#(dDoo7V0_k`!(cquoWo%KT5~Cb^((u2^QS{`=u>>U zm6x9Jp>sUxAAfzRF8!)r_H^K%KH{wTkl`kNddi#5_@qCc^#y-32mM_>nnjqu*Jcjb z>0ssnrjMBem~LhcV0xN4faz@J0QUYea{%j?SqfOc%vfYMdy&7H3|Jhq8nF0gIAD3r zcEI?U`GD~}nh_cPW<=QaE4zC0r$ce*Q+&FWm!9#Vb3ExEe|@Pg{iwB!|+4oz~x$nKwufG3Fzxw_! z{p$O_*!x~B{(aw;IO{oPqq+Ef|ChXd{}(=e{}-Np&lmoE|ChS5t2ci-6o)>=r(1dH z86P^wlm7A7m+I25>Sa#{{^=u5x{05j@}@IB>5pf9!C#JEhjPH`m7~|K958+4faxX& zOiwvrI?DmmUk+GbXb0<;9NB4|zZ|eQa=_yIf!X{U%vTOr3^`!2<$&ePj!XVH76uWk2Vdu@ZKUq|0Z zFa8~mzK>qswbwR2_^iFQ?RQtd)?V9STK0YP>dLO({OM2}`V@cqb(EKu@u6irX&L`b z%dIZ`s$TYV;GaI?q?`EZDQ`OClm2+t7ySEvb9Jpb*z_-hV!u)J#y zb}&9`4t6k}YYuj>e)aw4>dLO({OM2}`V^mT<)vqQ=p0Y_$6sHnOTVg@JstR`k2vWj zetOEA&iJH1p7jO)_1vEQb7MWXXa77|&+QpZhxOc^!Sq?r?HNqB_1vDp^jy#F8BFK( z+@8VuwVvBESijbDdj{**dT!5dU(fB?{nvAQ28*+v+cQ}F_1vDp@_ys*fAnB{)^mFX zA*jI#7Q^t(^KAb z#wY#ptS|VlJ&wJu`#fpG>Ro#ryAErQV=#Tz9>-w1tv!yx^jv!!gXz5XI0oz2+T$2} z^m#Z~zt$edZeM#GyZ_qb7%a}(;}|Ud+T$23@7k9cjL+KR7_47wk7F?YYwu>Teq~p0 z{&Xk~eTq-F^3pRtbdD$ebe_PxFM_kF%cbPYzIWT}x$oolI`4bBz5e_DZtsh}*W3H6@B7~Ver?|a?)}yGgR}R&;r#nPadG;d zaq;{9ae4b*a(w!}ayq!;&?q5-|M`*UjOm&zKEyy zOZ>f$s>}PUdfC%~fBJ}%ZsMn>yy=Wj`r}z&@ULI$%I@`q@r4+0vPB`ioIt#P0r=oZV-^rTZ^9c3%ef z?$@ZP`#5Ut{tgYg??apJ2hptiM6~Sw5qtNQ_;pX&`763LmqpL!wdmX&7yX;>(wFAG^s9L=_U6R+ zH$Ns$b7kT;ZzgYZX!tarhG%nY_&3j{uI%c~pAN;LPx0wiUV6rd&heyw{Pm@}^s9Q= z(}92bh?8#Or>DH>j8FRGSzqvPeqLS8X{)#SZ8|j9O`qny>DC-LJ(~}wb93YLZ=PIV znlsn0=Fi!iOXuIbx;V|Ti{E^^yv@Di(>y$$&B^26{Jgrdt2ci-6o)>=r(1dH86P^w zlm7A7m+I25>Sa#{{^=u5x{05j@}@IB>5pf9!N2><>gqnGdb__#hwgjM>-p&ZGTpjQ zInm*q`oe9|A!`htJ= zm(|sMO!anulMdbYq)+!l>DGNxdUpSm&fQm~fA?GUrTeh@b?>A5%k15^<=_2Wak|ed ze)oUn?Y=NR-7m(o`^flre_37G)tf&ZibJ2`)2+Ppj1QgTN&ookOLgg2^|Ge}|MU?j z-Na8%dD9u6^vAQl;NSH_b#TO<;4$U#rr};*@HTOu*<{|0a zoFx65pVXJ;D)p;*OZMh4`8S^_PIH^$H_s_=bDsD#|A}XFq4+m1s;=zn&7Tg%p-=JY zR$h9>htBb&fBf~Oy7a4h+0%i4`iPTm;-{y)>5NbM<5^$uZy#1&?eVF%{XROh_eY=h z0qNFWCq3IAq;q?P^l#r#U)rzKul5t!+gs${KBGA8If~!@qrB}!;?uq)p6yZM-+raK zva2_LIuwUK#iv_&=@}n7$CLi?*O%(juj*w_2ma|JPP&Pop7N$MKIxBVeZjx^Lv=Oh zrrze?=+ImoeVUh}+l`Or59!%_9i5xIqkr>w`qG@9el@?x-drF5=KaKJ4p97SAI%@i z+uR^N%@g9;oFV?rAF3<6dh@44ap+Tgx|Nrn@u71(=^uZ6sV@DhUiNh0pFZNGoA~J| zZ#v_X{&?0G{M-LhS9?b4ZU2Z4?IqEteI>fJ$3)Neo9Nu$6aCwV(wFsjdG7z}SNl`! z?N#w_-%6bJu*7daOWyXj@M)h5&-T3VZ~seO+0~mr9g0Jr;?u3X^o$Rk<4OPc>q~X% zSM{=|1ON09C*8zPPkGZBpY+GGzTn^U9Msiw1Jv8|1nAIn2I$lC2k6#w3Fz7L3h3N( z4CvqU4fJJQ+neiq`qlFg*n3U_|DK;9PR~^kzvnH;+jAK3>G=$J_S^>id!B>3va2_L zIuwUK#iv_&=@}n7$CLi?*O%(juj*w_2ma|JPP&Pop7N$MKIxBVeZk*7fR*ojb-4!s ztJggMm=5j%!1Qqs0H&LJ05Cn>1Ayu59so>#_W)phac=|GFZVpMyBCtbdnB+p?w!Em zyQc!n>s||tk9#mMp4&aqjlX*~?CQ#{-u&rM9QqWWZsnzCeCQlc`o~{is!PABmpvW$ zr;j-4CVqO#o6h*8Kc4jk|MvCN)n1r>wJ%18_Q>edei_}`JELd&XmoB*O~2Y-)35g0 z^s9Y0_V(cTw;v}?dvoHqPbY7CcKEb^hi7|v__wd8uI%c~pAN;LPx0wiUV6rd&heyw z{Pm@}^s9Q=(}92bh?8#Or>DH>j8FRGSzqw)`2gx_4_&=iK6*X?9ok!`Py6h2YtNmY z?Z4Bxy?FY!FRw4{(d$?H_3Z84^KTztoc8p^Z+~Cj_WJQ@-yhGO1Au?e2T)gb_2y59 z;?Sq~bSp1C<3s0o(m($CQeFC0z3l10KYheWH}TU`-gL$%{qd|X_&3j{uI8rH+dLH= znzN!$^H+3hE{mScYtgwmF8Vj$r7vsFVL#qz9*n&?G5*buiL;*5KK|l2ZzgYZX!tar zhG%nY_&3j{uI%c~pAN;LPw_{$qrCKt51r#l|M=@mb?I02vZn+8^bsfB#7|Fo(;1)i z$FsiR-}4;Q)pG;X+w%nI&~pap)AI-D)^iEy+4BnM+;a@*-}4Q&er?Zl@c!y~2<$y4 zfq&0W5U1xVh~M)Te8?3WlsnG=_5|MiJzYGrZYb2k7s?szx`!(wI{3I_GjtPUM+pvx20Qqxb$p4m(K0& z(!YIPeOdR3_V-u&zwGS=^KV~Roc4&tZ@*aH_Kxvs9~sZ~l<{wWSzX!Hn?D_jL!aW) zt-SP%51r#l|M=@mb?I02vZn+8^bsfB#7|Fo(;1)i$FsiR-}Cg;)pOg_+wt9seffq(jllWyXtr@ZNmPx|9o zU+`~#SzYbPs<-`FIEAxDzO?77U+w?0w-?O6ePMCh zBNo5?VtLy;#;1K`Jlj*ozx`!(Wmj+hbSMseich!l(lb7Ejwk)&uP@c5U)9T=4*b(c zoOBaEJ>^Yje9|A!`htJ^De7tuLcQ%r(4oBv`m|3$xArXP+5QEc+smMT`x^Sv9*2Il z-@)GA2mkg##A#1N{PsuWZLb8M_D%3?4+a1BQ`D7Rz4_CjIP@t#-O5YP_|Q3?^pC&3 zRF{5LFMB#ne{c44S~Wqy>~v^ zucSkJfAsm6qy0*{wI@i=_6O(5LuxD=$6cL+5zXKmPhsUHVnM?CHQieZ)yO@zYb@ zbjBzB@vJZSH;?U_N^`%iwKNax8ccJ-uFW(*?3zt;#jfQvZ|oXRbI7j!G@tC6Q1jTX z6*bSy-kdZ4=AXrBE?WHNrR8mo8lUE?@oXL&|K_oe>Y90M*NXCYt*AJz6&2sLqVl>{ z6d%`$;^|sZ{9P+*9^19O>Sa#{{^=u5x{05j@}@IB>5pf9!GF!AoO7Mc4BeVb8Em$0 z&7}-BbGPPF2AjoOb18$(=&iYw!Djc?T*_cGeQPdduvxz~monH4;F?PrY&LMsrR?@K zm$Lh>xs<`;thtoI;;*@s!Sb%Tl)?C{xs<_puDO)K_^&yl!RpFxHZXs)fyFT!SbVdA zDH>j8FRGSzqv9*Rl7y)^+T?-gO;& zFdf!)?7{R|*RcoFZC%G6OwV;4doZ2Xb?m|VwXS0iKAPDatY7Oo_HJL-v3LJ<9ec1i z>pJ#e@z-_i!Sb%_*n{y|*RcoVxvpam)~|KnVX%H>S8x7wC=Pv!Pq*^YGd^^VC;j7p zG|M@;^s9Q=(}92bh?8#Or>DH>j8FRGSzqv9_hI+C)_vH$-gO^#Fdf!?*unH!_hARq zZQX|*OwV;6b}*gSeb~YJweG_X)~|IRcCdb}`>?xx-G|-%*L~Q*;;j3ygT-I>VF$~* z?!ykoXWfS#jOV%!J6ONgee=Qkm0i90)1f%@DL&oGOV9YwIiB>7zrIwLepN4fI`B^) zaneov^prQ9@kxI?>kIztxOcB>9ry0_uH)XpbXdo|gXy!5dk52P9rq5V=Q{2kOy_mn zJ6ONgaqnRLTF1SE^=lpX?)G)uyZf*6g2Cdf-obdT zf1f|%^tmK{pI7qsIfhT4Z+P~(hku`k>dNl;Du2ga#c@1Ve8*|!b^I0|$93^^ychrN zcz&zP@nQ9{rvv}=5hvZmPfvN%8K3mWv%cWp`%7K*QN8t-4)vWry&mY+>x7=Ye(2om zivGRc^rhFKe)alf?{&++*Rwdi&c*NbFK_P)e0sm&+4~Fs-e2mZlXabKu+N!w zoo%qspLLyWu+OD+oo%qst96}iu+On|oo%qs!*!i)u+PJFoo%qs!*!i)x3BALyZ^e* zHdvf>oo%rA>pI(DdDnHe!T7A}Y=iM!*VzX9JY3gB2m3tC?(-ynpEJer`BQwKOXc-> z6(65t@$~r?f1i8R<@2z5+0%i4`iPTm;-{y)>5NbM<5^$u?|8%Ou)k|wpZ&e_y6x|v z*K>a#z0Ui)>Gj{=Q}2uZ&U(M}_t*QVzsufV{k>-I?>PVdzKhe}eepXUkhkLmd^&!> zv*QZ5%+^;~?f^YVKA$H)63p58C<_dcpF@2~1*PY3?#BTl-BpPurj zGd}5$XMMrH^RM~bI6D7QZ^!?1=)8bFoiEU>^9Xu&enIEXJLuo}h`w~5qFwQhn-tTnobAbMR zKIluI8~WAf345P2{QLY7r_Uwv`@E93&oO-Ze8aQPJ^cGTR9ANO=1+&>(5LuxD=$6c zL+5zXKmPhsUHVnM?CHQieZ)yO@zYb@bjBzB@vJZSuer*zu5bM46E87WIry*dd5O8o z!RKA?5_6SCUvuf6_pv{CsX5PybAuOOYW{QZXZ*^gJO4j^!=-y&Z++9H zd%f)Gz(0M&NjLG+Q{HsOC;joPFZi!HhrO;f=P+2kYtCUX9oC$~VEWwg^R70SZfm|` zFg@3t!(ckEIfudewdNcK>({!DJy^fioWpKka}K-znsXQ|&YE)=EdH8v7%cCaa~O=z znsXS8=bCdEjQ^TT8LVH~)tf&ZibJ2`)2+Ppj1QgTN&ookOLgg2^|Ge}|MU?j-Na8% zdD9u6^vAQl;J@a+_PW;G*Iw_M`x;D#HTN}`K5Oo4Fx}SN*I;_Cxv#-=UUOfA^=r+2 z4c4zU_cd6**4)=_Uvpo(|C;+6EY6zy8Z7>r`x-3on)@1z&zk!hjOUvB8mwPyPH(V& zWmj+hbSMseich!l(lb7Ejwk)&uP@c5U)9T=4*b(coOBaEJ>^Yje9|A!`hx%3>`AYwg_(*01d9U3(v6r$cc@pQHG6 zD=$6cL+5zXKmPhsUHVnM?CHQieZ)yO@zYb@bjBzB@vJZS_x;Q2T5~CTy=yLIFdf!h z%3%7exs<_lTXQLc>AB`o2GjX2_jui4{aSM=gY|38r3}`uHJ7s6*Idf(zvfZ~i?ilZ z28+MuQU=Sr=28aZv*uC;dl`H#i38}=~iBP#)r=Fq<{SNrMmR1 zdfC%~fBJ}%ZsMn>yy=Wj`r}z&@bCL!)wSln_IlUc*RI2w`x;E2HTN}`ZfovqFg@4Y z*I+uYxv#mvn)@0o&YJrgEdHAN8Z7Uc`x=bTn)@28 zUu*7buzvOZut>?fDrssMN%wRgN=fDis zuk{?5!Q1=mZiDq}JqKpDujjz*{_8m~gT-0Tff+3RdJfEBdDnAb2II4y12Y)U^&FVN z_^;>o4A!sg>dl`H#i38}=~iBP#)r=Fq<{Rk_t#dJepN4fI`B^)aneov^prQ9@kxI? z>kIyC?`B>b>RNj@`|ES<-3+F~+PfJ{pS5>0m~LzDW-vY1-pyb-uf3bW`nC3M1|Rin zuzsz*o87+lZg&5*cQaU=wRbaE{Iz#8Sl+dFGZ>$>cQY8zwRbaEzt*1AV0C3zZ~k;B z4t4$xI>#aYi487%&KuE=0{*Kn`UA_6!p*Zv@KHbVo&-l>{n4j=K)S8- z*^@p?>Dm4uo!cwaul5b~t35>hYCn;^y+!`*Gm6umqxkE*a&pPrUL-#4OXArcCI0PK zsw=yC^QS{`=u>>Um6x9Jp>sUxAAfzRF8!)r_H^K%KH{XC_~|KcI^&c6c-9yE+pknt zdwl9`zmE>>{n4j=K)SUjNYC~M>D*o+{o6M@`aB%X^{f3v_VyO}x6dd}dye9_|0r*J zk@&PPiD!G1__trFuI%c~pAN;LPx0wiUV6rd&heyw{I~bl-KH-6s$TYV;GaI?q?`EZ zDQ`OClm2+t7yO%_S66e|>TQ0T4$XDbr+II>H3v@5=ELdS+&KN4C*S(@`n_MxpR?cP z==;C;H?J;EbL`?b-!5-+@Axzik7sl8_%}bVuI%c~pAN;LPx0wiUV6rd&heyw{I`B> zb?I02vZn+8^bsfB#7|Fo(;1)i$FsiR-@cx@+6zdl`H z#i38}=~iBP#)r=Fq<{SNrMmR1dfC%~fBJ}%ZsMn>yy=Wj`r}z&@bCE>>gqWU>h1Xt z`qgtG^sDDZ(5>f4(6i@D(7ESM(7)$V=u6M3(663f!QOK%`1iaEae5Ah_&py(-kzI* zPtVi9v*&E!-}5)rm0i90)1f%@DL&oGOV9YwIiB>7zrIwLepN4fI`B^)aneov^prQ9 z=k;^+eR+7+7yNskp1OK&n|gbm8y$Mi8-05I8{K*?96ftp9G!cP9Q}K~oW88<0OvbC z(XXCI$KG@5`1kxeaeA(u_&x7V-kyVpPtV80v*+gF-}Cg;m0i90)1f%@DL&oGOV9Yw zIiB>7zrIwLepN4fI`B^)anfyG4@b|3mp7g9Nq;=+3;yj_s;fOd^|s$fhxY#H(>@^G z+7qN_`-60DuaN%j8|urtjy<1U`qh3SdwYxg+h-J~{YvrIb?o_FdE1M`r+rC0+oQz4 z{YrIZS8x7wC=Pv!Pq*^YGd^^VC;j8EFV&@A)ytj^{L@FAbQ3>4S~Wqz3unWp}jx)v=2zP_5|tK{ve&(E2Mw>hFia$vG=R}ME3R;`M1v~PJ52xxBn<_ zdy)9GFNtS+l=!z_sjlqm&7Tg%p-=JYR$h9>htBb&fBd(8ZFT8a^|Ge}|MU?j-Na8% zdD9u6^vAQl;NSC>)zx!-)!Xxa>Ckh4>C^Lp>DF_D>Dlvy>D+UM>EH8*^<_O*WdA(u zdByBK$C!W5Hx{So9*f`ekmc<;$@ujAWITJWGX6bpSzX!Hn?D_jL!aW)t-SP%51r#l z|M=@mb?I02vZn+8^bsfB#7|Fo(;1)i$FsiR-@b#onyXiD^Y(OT4xc{zeE!m{xqW&z z&rj#({ORBPzrK9`o1Qt(Y4>^9z5siB1pM1C5U0HZ@%Md%mA5?weA-{Yvwa8r+jlss zYxW(~n?D_jL!aW)t-SP%51r#l|M=_6=@Hi>|H)_yDxdO_x#k^ zFZhKGf7+8@eD=PNeA!vY67RppOV0k*m;T(~$A8yL&fee_+kMHu`uUff{h?2K`Pgsw zn=d*0cb9*~VD>w`d&B%+{)+9sq&RPQ=yoqs{8wLVyZs+ z73crp>fFQky{0oCiQ_nrDn%M0s+3YmHTfN0#}G_YgVw2~RNGKRb&S%eUPVYEBoe7; z6N$vJDV=K7VSisU)2UO?prxu*wW`BV6H^r(%>7yW{jA@<<`37ku4QGdd)@c<_q@;Z z?7jAL>LqvIn*VF}x%<|-&-&-PZN+oe<#*eP^FF_Rx2<~J^k?q2Rj+@1*xk13gM!omdET@+w)5ZfqGP-6fBD+6jpu@6 zk87O&@TB7!|IJ@;T=#YFvySV2@yi48@L0`8! zY1;VrJ#yN_f9~niCeI_znKt=f@vdo8_fcP(Hh7LZ>NS-UoToo>+Tg$RoN3e7-W7-Z zH@oJ=9skwir%j$eK4seEzv`T6Q}-9%Hf`|S;6u{}=P{q2cH#frwCPJfIvS6@=0SJ! z^Y>s~{!YZh-;X%?yAnTtZ}!FCq5a~Q2jb<2Jn}|<`J}EqgGc_ssV?C6_lw_5uao?i zdi~@#*6S+2yZ?)HFe#5>b9@wdUffY*Qg{w@&j?*)1M z9U;HJFVyvS2R!~Bfz#hF@ca9<>#KghxEC;6dH_L|4?Anq`AOdpBo%`qEFo#>0bo z;HUG4H|xTuc;H!_@GpLJu`l$pU;Oewy!?B-kh_5Pv8D@g;lVuc)A_@jb>UMy@GMUF7eBh#7kb$*et95Xe#j$lHZ&hK6$r43jWh;jF(d+6LP8)yDY47-)(_S`ta!z~Md*M-rJsI{hX?b(Pv;MB)`d^;z_U2vU;I2~OuI!S8$}ed(uPUEoX7lB^xKgaLBbmHBwP9FEMli&UA)OFuGc-#*U zPWQ=!-~IFSrJsI{hX?b(Pv;MB)`d^;z_U2vU;IHOi%y6`C;corx8iyvL=3%%?YzdR5xKje`&@;9HUE6?DOe{iY` z_;Zd~_x0}crcJ*&$E7!n3WBmImfJQc+NRyWusTlF)JIra*kQq z=#_KK+JD+NrcHd#F)KfLa*kQqnI)d_;VrYoWy5D?iOYuP%o3Lk|CuE&8@)11TsC@T7PtMG(e3!m z?v_oS%=DH`{>=K8jb51nE*m_V4K5p;nHeq{y)sKYx56|J>l6oQ1o&>bY2f%UL2yA^Q8ElGbP^nQ}Q^MN`B{6sp}joc${wqr}MDjcOI6$ z^wY2L@L(SJ>HOi%y6`C;corx8iyvK_hea>@#V-%U%MW?vjr`4L>dG^C}XZQKTzx)5uCHGN%zu~+9e&+~?cfNo;&K;27 zc?9Y@rvM)37r^OU1NfbHpfCOOYdk!d2Yxz#c(X2iiU*#>3IF0p7yCjl`^7I0#LEwP zH>b}zv#<3Bl>mz2p*hEf*fa<2Z2k6!xe*LZj^5Bzlg@Mc~36c0R$6aK}I zF7}09_KRO0h?gJo$Q${a&(xJ?@W?+n)dl>Xm%`tnbLjNzd^$Whw+=tfv%{Nn?(pgS zJ3KoVk6zBpqnC5^=;eGpe&_CqcOIWS&gqli`F-j-*AE`&{lV!u0O0q00Q%BTzsAFZ zdElq>hd1lOr+DC5obWGxbg?h=vS0l2K)n2rN8ZTae5S5EgGc_ssV?Amo`}AjTcKa) zS>VAr7x;1h1>T&CfludU;MqAE_;AS_^rfGEjfV&Gz)$B7Z`OrR@xZe<;a~jdVqfTGzxd^Wc=;iZypg~8OkH^f zkNksEUBI7nZu`2Cb8h>3l5=j$hKHPUTQ>aUoZA^6-g3@u+3=ZjZp((}oO4??{O6q8 zve6~`^vdSnSI)U@f6lq>_?&ZFHhFT+ZQ10{Ik#n_SI)UD8$3DZwrp_boZGU|E9Vl= z_~@mdevO9*^T1E%4{z3mPw~LBIN@LX=we^!Wxx34fq3~LkGzq;`Al7T29NxMQ(eHH z@2GZP`HpJ$oA0QW4G;N_YT59U@2JlB@RskWmJOfzj%wNPobRZXjb8bVYT4+Ob-l9D zE8kIVf4-yI@%fHw+2qN0RLdrRzN1<;dgVK+WrHW*Q7s#s`HpJY=#}r@&iLr1pMH&p z2lK#B=MQhzg-`LovpC^j{ODp|=w-k7<$-wlA&3Ie4>^TPL<@pBa<+%sw<#`DBJtu*9&rcwa=PHoj z^A@O^xq!x#xq!y$xeeg=JO}#HPrt^)gL&Ym^M^OS;l39 z^9HY+HhSgk;~5{l^wY2L@L(SJ>HOi%y6`C;corx8iyvL=3%%?YzdR5xKje`&@;9HU zE6?DOe{iY`_&uMEzeCRfqu(=k=fT2*=Z3+L=ZV3a=ZwLp=a0d&=aQk9=ar$C=a`|F z=bPd8+%w`m4~;yYlSY2ePou8qs)5Jz*1+jGY~c5NHu};}zsAFZdElq>hd1lOr+DC5 zobWGxbg?h=vS0l2K)n2rN8ZTae5S5EgGc_ssV?Amewn_UlcithXW_xQTKI9^7T%o0 zg-_>m;n}%e_;;QcU9t{4@-CqEM>+qC-??DoofjsLbHwC#zL>hs9fQYtWN@#lFzXe(}o#@$y3+c_V-GnY!`}9{C5Sx`6*h z-~CQq|LN;dH~Vhc^n1d|(}stidCRon=c%_mtglOdeaf`q^V;v7Hay?vuGgp-`2W_c zr;RQTzQN(;=ik=_&zm;>XMcIx#Gm!BBPxbG?|SRB$$!VguGw{e{yx(N&$EAJ+Ti@+ z%cc$fkG^UbpT6|dukr9;9{B0};mx}6DIRzhC;W>aUF-|J>=(a05HCOEkvH-;pQ$U) z;E{iDstfq@9fZk4`pS0@%BJ6Z2cc|u$afIRhM#-~VaDh0{4LL%Hhktg2<3<8dsPO=}SNT8V?WVfuGJF-mD9s;(=#z!oT>@#lFzXe(}o#@$y3+c_V-GnY!`} z9{C5Sx`032)isKLU*WWD`VH4*!$Y_$8-Bvwj1O<&u59?s|5r9V=f5c%y^^bJ^h%Ag z(JQsvA50w|tYwqOb4$pd-pY?&>A7t1gp0Dl8IH;Zf4H0R=}SNT8V?WVfuGJF-mD9s z;(=#z!oT>@#lFzXe(}o#@$y3+c_V-GnY!`}9{C5Sx`5yB`Jz|$Ic)fSq2KItC>tKK z&!KGi$v%g&;Vt_d%7)MEb0{00v(KSy^vXVmve7HK%SNy4b7+6|IdpvXIh0MF>~koa z{MqMFHg&Vlp=|JEpF`Q;%sz**!SDBc=}SNT8V?WVfuGJF-mD9s;(=#z!oT>@#lFzX ze(}o#@$y3+c_V-GnY!`}9{C5Sx`5yBwb57Jvvt3D&(=KTJzLrEllN?8!&~07l?|VH z&sH`(=RI55=#}?uWusT#vz3irdC%7Vyl3n9yk{$$JbBMnHu>|Ot!(P%JzLq}$$Pf4 z(JSxS%0@50*G6CZ>DPF8Fc186{_tj9_!JL3ixd9Ek1qCwUiOP$9*CD8^2i(co6pph zXYj~BIMoIGey@$b{4N;%`n@oC@H=Ag91+2qf@ zl(Nw)`%=mVPxhsh4bJRKDVx8y>?4}-=}SNT8V?WVfuGJF-mD9s;(=#z!oT>@#lFzX ze(}o#@$y3+c_V-GnY!`}9{C5Sx`5w#bM$hqnSPyjh6m@M;m7%Ccyn$VKAoqAXXmWZ z%lT{caxNRaoY%(h95?aKcaz7tZ}Ml~*Fk<;sq36Lc$^;xr*q}tcix=7^wY2L@L(SJ z>HOi%y6`C;corx8iyvL=3%%?YzdR5xKje`&@;9HUE6?DOe{iY`__GhT{|>Vcw*Nk} z54LQ0$UfMz;V1iGXMA|eKG?G1Gy7o6hUe^qEgSx?e&MvyCES%Cy|NFsZ2Z{=+ws{4 zTQ+&J54LRbXCG|Y=#_o2WrHXCV9N$)_Q95oUfH)iv=fv;5j+)3KWw>^VH><@r2QuX%0{dU>7?{_Hcae>=o`{ttOP7l{0x7ermp5dx3r3xU&f zhrsW7MD(SfevO9*^T1E%4{z3mPw~LBIN@LXQ?J<{ag+@|nd6v$x8W^w9A(32<~YiR=ge`G4gZvce$5A$VWsal$nd9jA%yE=Wp3HHSP5#Vrl#O1Q<0uKJ( z^lLmkmo7M;H4-FZ;zW55&t4dE|}!&1dS$GkD}5oazF8&bY7N zh4jT4_t^By8TZ)mz!~@0@WUDR6(8O>;~pD6IpZE1o;l+l8@)K=9vi(lyB{09IMZK$ z=A=5FZvfyY58npBCO_W{z(y~=C4dbczA=CePQE>W4Sv2!Q1R(YKm8gH59WcN&L7^a z3!mbFXK}*6_|e6_(93@D%LDQ9Lmqh}fAg8T@(dpN2dBD#-}4XoJM^4A`t|%hc<@|4 z`0>0xc*`7O{ac1l&-a68&;3I$&jUoStm{=gdU<{ze$N#o-tz{@<2i)nKXP~eA$2{s z5Imk|2u{yA1i$AW(wBbvH69+!13#TVyjd4M#RJdcgn#j)i+!P&{o6a|)k+{}i76E-L){y;OAZ zJF4jA_f_%x-BsfK9xHkBo~>$;-|x4gm)~^-kKcPmFTVo|e!mY(U;63Scz7@m{B-{C zW?lFc4?K$#{>6_j_Jv;di(ejymml)T8~K~h)RkxO$UivM1^juB-Peu0$1av}Ujyk%XlZ1~K&UfJ-Rb-l9DE9-h?qgU4T%0{oO>$N}YdL5s2y|T%Zb-l95pLM;m z(JSkEWrHW{dS!z%>w0B_KkKkFK7Hw@U*qAyJn+-`!<%*CQ#|l2PWTr;y4V+b*)M*1 zAYOjRBX8tyK2uko!6X0RR2T5`&0v3*vu@t~^37oU@W3~NvEher23LG|hn4zVTe~(Mv!58V?WVfuGJF-mD9s;(=#z!oT>@#lFzXe(}o#@$y3+c_V-GnY!`} z9{C5Sx`5yFMY(QxjwStOUrJwRvM;4<`0+eUc=Mc0`1Jftc=lXP^zyt-^zs}|^zwX8 z{GQuMyytn6$8$c(@A;q9&AybzlYJ?T({n_@@A;zirJsI{hX?b(Pv;MB)`d^;z_U2v zU;OA|U+87O_~n6k`5}+Ik-zy&U3mtN{DV_nz@L3z{dbssU;X!)eP3nscbk1*WusU2 zea-mrmVIAk!)Nw=l?~6?_fDEKc|rKf2f#df6|2 zc_3bX$Rls$Z$493p1~vk;8YjzXJ2La_0#7}n|`yevU$k9%Cg}n`zmLAc+0-Zvf(rP zD$9oF?5ivry|S;eZ1l=|wzAPH`zqU?eU%-beU)XCC;KYPCV%!-mW^K7S6McAvahmi z^vb@8D@g;lVuc)A_@jb>UMy@GMUF7eBh#7kb$*et95Xe#j$l z3IF0p7yCjl`^7I0#LEwPH_}EarEC|<~aKAGjkke!$amc%7&lJ zam@JemN|~H;WKj_Wy5pkILe0q%yE>BE}7#f8@)2e(f-VFbbRJG$|g_dILan}<~Yhm zugr0j4W7(#lnu_zag>c-nY)?s(Mv!58V?WVfuGJF-mD9s;(=#z!oT>@#lFzXe(}o# z@$y3+c_V-GnY!`}9{C5Sx`5yFvH3gn9A^6Ud~A5|+-CUkJZE_GoM-s-{AYOfTxj(2 zylC|D9BK6Od};iiJ59XjQIp4Ws>$#9)ztM|Yw&p9H8?#78~mP+O<(%y*LZj^5Bzlg z@Mc~36c0R$6aK}IF7}09_KRO0h?gJo$Q${a&(xJ?@W?+n)dl?2@V=KC-Vaj)8y={E z4L{VV`0(brrtnD({P0W-Z1|@JHoCwaHhRISergy`4Q%qD4L14tA2vSzKWt*DflUr- zV3V5~6`z{=!D2iZ%>(w%AKt7>ui}9Nal(!G;mp3^(th#F1M%`h9(f~w^O?HxOsxEq zLtV(7Ip4l+WX`v*Cz z3IF0p7yCjl`^7I0#LEwPH>bxGw0v5=VsHd=V`-(=WN4|=WoNC z=W@fR=XJxg=Xj%+=X>w2Nqv9ldEodxC!BcC4=0c3ij&{-#;NN$aUGjHPeW92A;+F^F<%c}-M*ikAb>$g6@()gR z0l(jOpfA58K)-%p03Q7A0Q~rU2YB;41@P(j3*g!B8o^{=>2Ca~sS4x3TPt8_RyVvFxK8%l^8t z?7JJwe!Q{l(;LhFy|L`;8_RybvFrmJ%l^Qz>>C`*e!{WrGaSqQ!}dqVj*q^bC%PZX zpFPXg&EHAm$=^@o%->bx&)-}3mA}L87r#6ZFF)jwH}W^1sVmRmk$-Ti3;37kud&?c zkLCV3IF0p7yCjl`^7I0#LEwPH_}d`D-lq`D3~NAIo#WSe_Tg@*FXi=ZmpCcZ}tEWGv4qV|jiV%X7_Go_EIb95j~a zqp>_Ujpcc2EYDeEdH!lY{TdGs=7FEiAKt7BpW=aMal*g&(Z#;d%YO081M%`h9(f~w z^O?Hx3?BIhr@DZjYwqqoYV3YHYcD_7T>QCy4z9V_xvmbbxfP#pw=T~SgKIAS#15{x z*vT=t=3*!J;I{-jHAiZxyNsO;1n{6_NM zre^!;*LZj^5Bzlg@Mc~36c0R$6aK}IF7}09_KRO0h?gJo$Q${a&(xJ?@W?+n)dl>^ z^VeAJ^T%@kKbGf$u{VPyfc>Pps_q3jpey%EYDM8dCnTk^H=-n*LZj^5Bzlg@Mc~36c0R$6aK}I zF7}09_KRO0h?gJo$Q${a&(xJ?@W?+n)dl>^e9BnnAjUEuF_yWBvCLD9WzJ$O^B3c^ z-FynaU(3A4Smrp!GT$+lxsS2TgN$WPWGwR|W3!u2;rDBqHyO(u%2?)8+E2g6!-IL? zr}Kw5>%yma;8~pTFMf2fFZ8ls{PIA&{E$c9>hIzD&zbLGQdgeABmdx37w|9hDPx&~ z7|VRbSmq|iGEXshd1lOr+DC5obWGxbg?h=vS0l2K)n2rN8ZTa ze5S5EgGc_ssV?AO=2ONp2QilUh_TE~jAfo;EOQpQt{z?2I`mrRGR88mk?Y27`g*v` zcZ_B3BiFI-?L5nz$XMn_#xhqjmU)x0%%O~BKBfKiYdk!d2Yxz#c(X2iiU*#>3IF0p z7yCjl`^7I0#LEwPH_{{9(F8qmt&d79Lt>MSmrm!GS@kldC#%T zfsSQ9ldG^CW!_}G zYB!(4^YSvE(ti3i9v;jCKb=3kSreW92A;+F^F<%c}-M*ikAb>$g6 z@()gR0sk_eGL|`rvCKz|Wo}|D^Auy5vlz?##aQMt#xk!lmN|~G%y*1s?qe+TAY+*m z8O!|0SmsK`GH)`LIh3)?r?j7bjfV&Gz)$B7Z`OrR@xZe<;a~jdVqfTGzxd^Wc=;iZ zypg~8OkH^fkNksEUBJK0r;KF|Vl49!W0{*6%RI$c<}AiCe=(N1jIqpXjAf2vEb|>> znfn;aJjht)M8=WMr{sOqGFLK|d6Tisp^RldrTz44JUo~OemZ}6vo3s!2cE?V|Kdj% z`$8}K#V-%U%MW?vjr`4L>dG^C%yma;8~pTFMf2fFZ8ls{PIA&{E$c9$lrXXt~`TB{=um(;9urb#xe&nmidUW z%uS4Co?7Gs&e7|UG7SmrhIcX)W~waj;nW$t4v^B`lH6B*0=$XMn|#xid*mN}IC zyXg6p_S3KN@L(SJ>HOi%y6`C;corx8i+}$6nth>{{o6_j_Jv;d zi(ejymml)T8~K~h)RkxO$UivM1^mlA(OBkI#xl<`mN}QP%)g9fE@mwAGGm#e8Owal zSmtiVGLJKsIi0c0?~G-xXDstRW0?aQ%Y4vS=7z>HPt<<;H69+!13#TVyjd4M#RJdc zgn#j)i+!P&{olw?u&sgSw#xfr?mbsy^%oDYrevO9*^T1E% z4{z3mPw~LBIN@LX=we^!Wxx34fq3~LkGzq;`Al7T29NxMQ(eHn%oB}eZe=Xke=4_fg9{&RFJjvJUdL&a=$*jAh0bo;HUG4H|xTuc;H!_@GpLJu`l$pU;Oewy!?b1`F?ml?|(%~%yma;8~pTFMf2fFZ8ls{PIA&{E$c9 z$lrXXt~`TB{=um(;9us6#xl1umU))3%(;wZ{$(t4F?kO;=ZSdVyUfvyWxj^@qOI35 zk297zoxJzERmG5Jnd=$Lyw6zXfW|T(G?uxctXuUwQTyrFcz7@m{B-{CW?lFc4?K$# z{>6_j_Jv;di(ejymml)T8~K~h)RkxO$UivM1^mlA(OBkI#xl<`mN}QP%)g9fE@mwA zGGm#e8OwYP@7el#xXj~>Wlm=-^E+di>lw?u&sgSw#xfr?mbsza*PU3kxIffSzsAFZ zdElq>hd1lOr+DC5obWGxbg?h=vS0l2K)n2rN8ZTae5S5EgGc_ssV?AO&LbMjxi@1u z4`(dr!qK5jfV&Gz)$B7Z`OrR@xZe<;a~hyuh|!R*)M*1AYOjRBX8ty zK2uko!6X0RR2T4n>ge0=_c>+xPW@QEUq6=b+K=UX_v5>N^3i?#x9nf~)X|rg&2{V* zcYS=>tS^84qR*c|4Ev+r_mJmbhRyR={O{DC_;+CwpFCxgC;7`Jf9jUa{;1%2H}R}5 z2WQ#rj|%>>dEcA9%I4pfe)=^Y9?Szjoj<%;7e2)U&*FrC@uSNv9({K8g`J2zwm1pqCKRDF|{LA+pxR2U{2l~x@RN3&5`>3+vC-+fh!&~m7%7)L}N0klF zxsNIv{&OEyHhSegs%-SieN_8%AJy@>k1CryxsNKF{JD=Ro4UD=DjPhxk189SxsNIv z{LA+p+E2g6!-IL?r}Kw5>%yma;8~pTFMf2fFZ8ls{PIA&{E$c9$lrXXt~`TB{=um( z;9tJ)z;nu0z4Dw=Haz4xrEK`gb4uCpmgkhR;WN)EWy5oxQ_4oKJg1b6UU^O_8@=+J z(*8WBbbOvu$|g^qQ_3cPo>R)EZk|)h22Y+-$_8hiQ_4oK<@*lpr(fgY!94Z%Z2s_O zUHB9aJc|?l#g8ubgHR zP5!(GD4V)@4^TFE@*bdU^vZjHve9e#zC-)z*LZj^5Bzlg@Mc}~5)V9!6aK}IF7}09 z_KRO0h?gJo$Q${a&(xJ?@W?+n)dl>^_Z@i8#+rRy5A&X_Y>qO##9>qKS4Th@unhR>`Ml?~5XCn_7gvQAVsdS#ucZ2o;^ov8g;C+hgD z6O~P#tP_<@{;U&~P2H>$l?|S(6P1l#StlwRy_WAgw4Z*BhX?b(Pv;MB)`d^;z_U2v zU;OA|U+87O_~n6k`5}+Ik-zy&U3mtN{DV_nz@K&4{`Zyj*|O<3>#+UrE9|SmJQEYhbDPF8Fc186{_tj9_!JL3ixd9EKmUErUeL>a z@yi48@y=9&!KGe%D$8tpT6|dukr9;9{B0};mx}6DIRzhC;W>aUF-|J>=(a05HCOE zkvH-;pQ$U);E{iDstfqDkEr{~{-W+T`-sYhhwLLN8-B8nXvT-P>?0~0KC_RgY+msDId2ci0!&~0llntMGZ&Nlr=eDPF8Fc186{_tj9 z_!JL3ixd9Ek1qCwUiOP$9*CD8^2i(co6pphXYj~BIMoIG*$3NwWq)kz$Io7M;H4-FZ;zW55&t4 zdE|}!&1dS$GkD}5oazGp%t>`$nV;%@GbdFxJY-I)Z1~BX)Qk^rnUg9TJ~Jm(Haure zs%-SioK)H9l{u-h(JOOO?a!Q4$7fEeZ1QAIs%-LS?yPL|%A8c$;K`g++2G8aRN3g2 zxwaV}z4X(s@$g_C`04!N&ARX@9(Wcf{EHu5><5LUiOP$9*EDJX2p<4-pJp4rmj4LNB+U7F5u6cZ~q-; z{$dZ1~BX?~D&`ne#0hJ~QWAHaus}w`}yvoNw9al{w$C(JOPl?a!QV z$7jyBZ1P<8N7E*M=6uVKUYYYP8$6lwEgPJf^DP^_GM7E$qnCdAH69+!13#TVyjd4M z#RJdcgn#j)i+!P&{oZHhN`_zU=w?_42aOD|7Vi&m4WnXO6yX@??&_Z1QK0 zzHIc$9DUi~$sB#z;LIF-+31yX4`zJy(oes}!-IL?r}Kw5>%yma;8~pTFMf2%`2bZ5 zz3dmiJPH=n61&)|`NaH1_e z7!OACfW7mlC+pIyc;G;sa3g*=voE-`U;Oewy!?E ze3-Jql5=3n24l{FDI4rL2WG~Hx10l0HofK?n6lv@=fIQ=H#rBUY&gp~FlEDK&Vgxv z&VlLpoC8xfd2$X++2qeTFlEDK&VeZ#JUIuZY;firn6km2b9-id^wLki#>0bo;HUG4 zH|xTsc;Hf;a4CMcv@i6sU;Oewy!?iY{+31yXmdZx2oU_#aoU_#NIcKSC z^5mSQvdN!wmdZx2oU>Fmcy9XKX@fK8ER`Rk%Q6_j_Jv;d zi(ejymml)T8~K~h)RkxO$UivM1^n5k*Vm2g)9dR=_UV-k580-g-`E1Nvor&l)lvrn&V^vXWHvcZ#m zdS!z%`}E32uk5Rw@zF~^{TdGs=7FEiAKt7BpW=aMal*g&(Z#;d%YO081M%`h9(f~w z^O?Hx3?BIhr@DYY`(XR;F#BWs?=$;g%Z7*SgDo3=vJZB~hqvs5EgL?w54LQ0&OX?( z(JT94%SNy4gDo4qvJbZX*$3P4*#}!Td9n|-Z1QIxY}x3QeXwPNC;MQ_250ucmW^K7 zw>;ycmwx&+9v;jCKb=3kSreW92A;+F^F<%c}-M*ikAb>$g6@()gR z0e|+HcVF3m-u-5udD-xgedcAuPxhJ5`0$o}=4HcY_L-Lr&)H{QHhN{BdD-ZdedcAO zSN55=Kl{u(KKsneCQtU6mrefcGcOyxvd_G1@MNEP+2G7R^Rm$^a{)6xdg-TM3IF2X{rjp~=w-k7<$-wlA&^YB?VYw78$Y}VM*SJ|w+r?0YE zlTTk|vsRzJ+Mm8UK7Ex*ST=p>XRY3N*6Pi} zTD|#MtG6y|_2OZzUYxAei=VZ6`(kf}{o-JNB+U7F5p)$-ht`o z-I(#bGcynG(#+30HtX{4O+37l6DRNL#LqiC`{Lc6{o-JNB+U7 zF5p)$`qIz4J>z+|XCB_|nV)xi*5%!vczCxbPTuW_pLcuq#k*Mh#V-%U%MW?vjr{US zU3mtN{DV_nz`y9VS^S$NezWA+EcrJ}-OYk$v*6q;_%};mo26f_8})C2>*vDHX5nqK z@VQxd-YooY7F{-rUhU_4Vm#Lw^Kkt!Ki4Jea=j7{*D-N&eG~ugdRX|m9@;N{c_3bX z$Rls$mrv@-GkD}5oa*xbT@Txze|H_9e~+Cf|4uu9{{42{{JU;E`S;#9a~){>xjwXB zoIPW|_~n6k`5}+IkzYQkE6?DOe{iZ7_|+@d!}jMo+3~r4cAi{UJAbaXT{qX^#*^!F z8tGB^{{NNhv}>R>8s<@SJ~uAUuBa&eU(k! z^i?)^(pTBwOkZV#f4SdiKi3oExz3n}>yP=lE?JlBm3X+0iIeM__;=UCs>}7ze(}o# z@$y3+c_Y7kQdgeABmdyc-(lqkzk2O{m&?!ZwekFpn}^?b^YgoJUG4|O!+nA{x!(}~ z?tY{4bH8D~_~n6k`5}+IkzYQkE6?DOe{iZ7_|$g6@()h+0{@~H*A4sHEb*Hq&t}QL zS?X>UJevjQX2H*O!@f34zg#!U&-HNOXS49OS@_&6JZ~2Mxo$N6MX&aAJu#l^jCr{J zn4jyCb-7-NhwGR)xxR^icRj4STo3IRzdR5xKje`&^2;Z6szSzrYzxd^Wc=;iZ zypdl%sVmRmk$-Ti3;5NGzVx$~)A*CKr`0^{v+* ztg1MfRTV$8s`kZfvHjwg2jb<2Jn}|<`J}EqgGc_ssV?AGuiPWHpS?fEvnR+r>=iOU zdx)&d-Xig^=SZCFMG`-Il=(a05HCOEkvH1VCOc-A`1!&-;=S?jPa zYaQZYtwWrwb%>v}4*Ozl%6{?71M%`h9(g0bd{S4Q!6X0RR4?$WSMH;RerBnSXU5t* z%wC(HnQZGat1TX8xW&nAxA>U_w=ZVF?H9j15HCOEkvHqZ59@=SKkJ6pWj#?mtTT#}^+)luE@@w^SK2Rrc_3bX z$Rls$Z$493p1~vk;8d@5z48w)yw@G{bJmXWoWWxr&gL;cXZBc^vwXzE89(CW>>u%S zCXjt`R*?PTmj~kIhdlB|e)*)XJcCF6!Kq&0SFfX9wEqr^|AZxe-;!tFl7HV)ci)0% z|AKS>f`9+g*Z!s7{R6HyzN`~+_&(&Z{dI6qRR=(zpn%OqvHYNqwfLpME3*c z=Noj^&ELrZ@#OF4fH?DabwK?2dplrX`8zydzxd^Wc=;iZypdl%sVmRmk$-Ti3;5M5 z_Z#iczq^jlzsJs#f2W7?=R2*|&A;o$lYj4xGuMH}pX)>SmFq_Li(ejymml)T8~K~h z)RkxO$UivM1^kEfy0ZPbPIi2*pPeVy)y~hE#MaGqxbfur+&FXHZv45PcVC=^tX}xl zi+J@SkGzpzy{M~R;88Ddsu%bV>2+oM^SjpZ`Mv8r`5ioz|8Ae@y7}E~Jo!CsocWz? z{G5gC-yvsL`}c`oy@*#Y^2i(c)hoZt%`@Rj?oSS?d+u8f znm_k52d$g?oP*-Y{m(&h=Dz5l_;bH>(7yO~kb2=)FXGjUJnBV$^`fqNfk(Z-sb1h$ zFZ$A-`^JvX{bc9KeP-v+{b$$BeQD##{c7XPeQe{;{cZQfx1Q`5zdR5xKje`&^2;Z6 zDwb=3IF`90so>```H_4JbMGp!`?vivp3MX>IHuFqA&f-sv6I%s(F}IH9xbe)@4>z zJj|+!lUY^qGplM}%of`(et95Xe#j$lkL?WISgknTNBK z%+DE1*5&La@o*-SI614S@#kzO`{Hb;?l*pUAYOjRBX8uFPwL7uc;p|P>H>cCqA&fN z?PNS>JDG>Goy^bKPS)jYC-HE$lQ=osN&KAcWM7=cWxx34fq3~LkGzpzKB+6u;E{iD zstfqlEAO%UI+^#tef`Y);l8fsy>VY}^FFz+!+Fo#*XO){?(25mOZW9W@2mSd&spR4 zi(ejymml)T8~Npvy7CMj`3I-EfM31nOMl+mcYNOGcb>fG@BDfH-*vMt(0H<5&^WV> z(D*rPT)j9OUcKdQn%sz@uK^R4?$WSKb4(KkF7RUc{>xdDM&i>P21k0*`uuQ(eHXUi76u>tY?B z^|H>Bb+pc(^|h{>b+^Wo^|;2Fb-Ko%^}Ftivyjybzj_g`UgS|P@~anh)eAi81y1z> zzj|dIw*6Vh?D(v2cAl(zcK)n~cHOL#HlD1XHqNZ8HvX))c3*reUcK zdQn%sz@uK^R2T587k%l^x^u^8J-YK`ox1a9{krRBUAysQy}NN{9lY^peZ2e1x_S4D zU%iM|FY>4t`PGZM>IEM40;hU`U%hgj-{{YEa$|h1pBwY!y1FrcuD2WO<~qC)Pp;36 zGuQ3LpX+(|#kYgh3%`01uU_O)FY>Dwb=3IF`90l#|Dm;U^&b$ovBI!}HFJAZy3 zH`dMX=0-gEJ>7^izq1?h^X(w7hkWbFe_#03i+K4VkGzpzKB+6u;E{iDstfqlEB8_D z&wWV8=l-Pg5|=Dz3<{xfdSeetc`?l*pUAYOjRBX8taFY2ln zc+?A=>H>cCqA&fqZ|wNoPj;T%XLkPFe|Fv6mo}cZs~7R= zMIQAczj{$uy}+Yh;8ZX0t5=>Y+n@XVj?evn=gD(H=g;#(*UfW8Dwb=3IF{q0>66YJzHNVvo6-x&#agA zbv5f~eZ9^4T3?5=?$+1mtjG2BFza-EJ>`ex_Jx@YIldT7_pI%(s{`f20Lx@zOkdTaN^w=(?qgAKlB(s;6;q;Y1SN#oD{lkO|~Qo3LK>P5VIkw?AAuU^zuFYu@rIMoIG>P27r zvk#}^vp=WvWZzEb&wie+n|(fwC;NXIXZ8g({_Gd(zOs*~`^B$b#H$y1)QkM;MP2m* zk9vVqy}+NoHtFfW?!LEd?uWxe+1w|GpR&1s4sT_1UmZTn=6*Xom(6{6_%ECL^ZYw1 zdv`xyHuv-SJ8XaY>iG0kHhI!l+2l`OWm7kOl?|TsRW>-&SJ~jt-(lIi=ajO!A2y!* zWb<(UY<}*mt;_wkc(@N2C->*#-`&qwe(vY(7r#6ZFF)jwH}cCTb>$g6@(<4Zy)}OI z+C5j6pXW{EPtJ3wd3ZiGKhLe!<#|>-Jm-p&=U?&fo|h{>&&&3UUml2;AM(f>`Q?+k z@(dpN2d8?0U%htk0je&~o5u4TY95|X&CheIb$Ol@56`*c&wC;3^1ets zyhjoz@0Y~CdmmN#c^_rJ_~n6k`5}+IkzYQkE6?DOe{iZ7_|+<^|9)5Sk$?uW)cfVhipWiS0#V-%U%MW?vjr{USU3mtN{DV`yz^`7r-{q>y z_1}1Y7tF)&h57j%u`a(a;^B8koctb%fA{-U`T6~_U;Oewy!?+j}gUEaE^*NcaBd~veAFaF(rfXdH)0QpJ|XEzV)@8)M+-ny*Ui-&c5ak9QI{@s3n>WlpV_KRO0h?gJo$Q$|Ple+Q@9{C5S zdVycPav#OMl&Z^q730~*VjlLln4f(w)@478c-SW+PWI1;f4ASJ^0VK@e(}o#@$y3+ zc_Y7kQdgeABmdx37x1eWed%Yvit+4YF%SD&I)C=PSeN}U;$feRIN3iV{@s3?>Wlq0 z_KRO0h?gJo$Q${a&(xJ?@W?+n)dl>A^s0SdRhRu>#`xQ_Za-V)XFr?$;+F^F<%c}-Mt=FEt~`TB{=um(;6J3-L)*`OFyq-LW*+vBb^h!t zvo8D1#KS%`ak4*6{JZ^Z)ffBO>=(a05HCOEkvH-;pQ$U);E{iDsu%dx>&H&N#%221 zZ)rUHFwMjMO!KpE)4J^E6c776#mW9p@$dGFR$uHFwO{=5K)n2rN8ZRUpVXCS@W?+n z)eHRU^`bA|^s>c&!V=H^%pIOf*|%AC^6y*f?pyG%|FdF(lYOCO2S58ocX@8lKGOCt zJnUci*}w3{KGlk+?!xoFh5vnvE+?p0ewT;-=s1jzzQa7xeVCtp(bmo1$q-Neeug;n zcQwSHzqesu?8mlW{PIA&{E$c9$SIEM40;hU`U%lu{f9@MQKKGNIC-<41Klh(q zH}|EDC-E zUhQYS&v@1W&BOYj`B^u#?uCcfI%8pGol%^uKZ<|1URg1$SK2Rrc_3bX$Rls$mrv@- zGkD}5oazF8_1dkQS6$ZAjc1+RJgmQ)pLKcbvR*G9*73#3`o8$Hf0A|B%FliP`^7I0 z#H$y1+j}gUEaE^*NcaBd~veAFaF(r zfXdH)0Q$g6@()h+0>66Em;SuB@A$mW?>u?W-}&?Yzw2gQpz&nApmAm$q48&Zq5I-I z2lc|QUc{>xdDM&i>P21k0*`uuQ@y~iUU?7D{;acfeAZt&Pu68Rf7WZdZq{)cPu6!D zXV!fhf7XM#FV0I*FZ}97yn2yGy~wX#)KxF=s24cZ1^ntoU;48y*6}Cj91`P3F_qON*@N4>zQF5p)$`qH1@wT{p4UFXT~VCT>8W7o~^ zX5-24Y3r5W+14w+zpYn(ms>CV@<6=&kVoFgFQ3$vXYj~BIMoIG>XrMb_UAsN<8yz~ zd2-*<`Ex(hdgVT+^~(KE>y`VW)+_f*trzn|>V;puh*vN2s2BOwi@NFs9`ypJx`1E3 z=u3a@8#_Mtlbt8`nVmoPpItZirHv=|tBo`Fv5kK>PgK_>=85|6GxJ31MZ9{EN4?0e zUer}D@TeC!)eHRUmFLR#=RUvVbN}CY@?6mQ^Ssb?FU&lhc=CMFIP=`m`13r{dgVE# z`^B$b#H$y1)QkM;MP2m*k9vVqUBIti^rb(~WgVaAwa%00xXz#FyRMt(zQ&X1!N!^A z#KxcJ$L@=HJ@vw`Uc}1}dDM&i>P21k0*`uuQ@y~iUU|>f*U7Al_4PCBWqn=EI$B?E zv%c2vw(K;CvhZec@Lx;?;{h>P3F_qON*@N4>zQF5p)$ z`qH0u%#P3cX6MPeXXnp)XxGg;Y2(TIY2(bgYU9s(Yxl+ZHtL06y@*#Y@~9X2)r-37 z1s?SRr+R^3y|QlJ{;WH9eAc5oPu8hBf7Y+NZq~IMPu9B|XV$?Rf7ZvlFV2rrFZ}97 zyn2yGy~wX#)KxF=s24cZ1^ntoU;498pyRWDpz~y3LFdnYgRYx>2#qKE6B=jsEj0e@ zXXw5-KT5sus~7R=MIQAczj{$uy}+Yh;8ZX0tJiyOROgu0bvXMvIzIb7I#2e2bpGrQ z>AKlB(s;6;q;Y1SN#oD{lkSW2+0+ZadJ(T)v$^M_lnSDWxKl_EcFV1IEFZ}97yn2yGy~wX#)KxF=s24cZ z3;f^n`EMLdPY164*Auo+|I2Cr@mo*W{{360ec6*w*uLVK)BeI8PuM>8sA)gve;vR5 zvv>SU{kK2-&f~XVxzDuEefja*XKepZ`M>mx%O`c^89ee2PIUqQBcAuX`Zsmb-(0$Pjb~5$zdhvAz5P#`_C@b`?cTX3PW$Ks zuig9CTTlBze|E{<<^ObQ{kLy>+$DSW{{3m6di_iGe(RT}eV311y!VVdO#3x&ym;@f zpZWEQ|JLtZy!SuPn>PMWo;+>hzwd_ACeQDG^tqk?i5E?qy6^o@(+1D?|J1a>`KbF% z8~oQgIBojUf8|pz>-evK^RmwKj8k8?Xa1AE{<^OF*+;*=@!b6PU*9-?{!6cK{8!!h z4c*so-{uY7FMfF-UVg|UZ{(Lx>dG^C1YKlZgV_n!I1r`Lb`;StjY=aKiFHu$gDKW+Nb{~sQ7ddJ^s?1*dht_~n6k`5}+IkzYQkE6?DOe{iY`_)mQ1bz85ierekD zdzVK~8y;S`Z`$zlPdAx1yj}R2>olJ~^4e*`^RNEwwBi2=x0*J(9Qmi)@-rwyJPKV;hAe9-aJ2LCsHWZLMZpMH&p2lK#> z`QgpF@F^a67AO3RA6@JVz3dmiJPG9S3lvTt$$bd{mqlM{`%TAX`0opx{yPG{|Gwx;|JVND0UiI@r#ztZ z-1bfn==^{5l@q(}lizh>I)C*4nO`qz?=WR;M2b!c=qoK{{4GH7yk~?%fCoRi&ARX@9(Wcf{EHu5>H_{hc;YAPUh8%*d*$}ACr^9-`(L^J)=j5<&SB?o zpZL~KRLn2`==s}o?=55&t4dE|}!@=0BJ29NxMQ(eHXUcd9cquc-I z`)}9r&%OM1o#!6kd;8A6eb()}?g{U|ed9U$`o}cRUp{b5Z%ub)C-*I0)F+PFa4)H{OFD!pTBMAxz=-T+xdU(`)=EHzy02$8qdvN zcvR#3;KPn;{1+T|RQL6?J0I2k;#V)?)r&mpMSk_7u6lt-y}+qn;6HGibL;Q$^!s09 z`^D=_d%WWs+taRiMfp#;)8X5%o-*yD&OLm4)Zd>|{>!gAe0!(OwC{N05!;(Q|LpSL z_$5bdFZsQfm;IP`9@7XVYc_3bX$Rls$ zmrv@-GkD}5oazGpoBh`x+~awfzV`lU+VuPUC)}z0@bK0jxO3U?^W*pUp|auagj4TQ zHhezyTX!uRo*#V4-O7glZ~okml#O2RJ?_}D(d)cx{b>8|`~G`&{83LozHIV5{3|Dv zP5#Y~?Jt|UpSkaWvcYqM>mDo{oPYkC(+2-@-ZX9c(oes}!-IL?$NcbS-QshH2cE?V z|Kdj%`$8}K#V-%U%MW?vjr{USU3mtN{DV_n!2i70zpDD>y794hO`Ge_f&@<6=&kVoFgFQ3$v zXYj~BIMoIG>P27r`Moxt-*NNs`)+=I_pQtQfOxo15GVH!;^)4?zPR78U;Oewy!? zZ*-TZZ9Z_y31$E37oM_t-pw~<-}}L*Y(D;g>&^I2ow50&AG%iA|NeSsZLa>*HOfBo zB`@E6=40R4qwbeae8uLNPySokXWsRdn>&BvTV-Ex=U25IjMxW>Uu|MiYlHukS*z?_ zt+IEu>c8F9Dw|sArDAryl)dYvYk+Y{Ogm)5|uzm7QL;;muyQ;muyQ@)J(lMqBw@ZDJOUsI{e+U9GZrwf69b zH)@p~-sq)b!W+Gmz3ZiHdRhKv;H3Qgjq(1IoV?fNJsURfdwKtc&3j|EZt%pT_h46PrA||HLLg?%O`c^89ee2PIUo4>kIV7dtKgRWAnb3_uJUK2j;yuHt&adACAp? zW8RZv^S+w*=h&xS|B^l4t7G&2ne_#1-b=H-fX(}A))(}%zF<7>^Rdap`T{ojdH;`1 zUDg+{!Nd9jHaJ;Fzy?3-3)u9fpZC4S^B&kdydO3{?~Sd?`(*L(o>`o{e-=OQrR|IN z)%J^D9*CD8^2i(c<&(Pd3?BIhr@DauhWEQ@OJ83)`we@yJ89Z4c;oB$_C0dicX{9I z_CELYY43ggvb{%~Gwn-{yKL_j@0#{oUY>XOUz+x3uXpL*aYwzTaz5}4uiZQSk<amRo4_-T{pk58F4`L8->+SL7pw@n*7H~7%B!FkN5 zr(O6zH*NaT{~w?8#*TmEW8TzxZt=r!?)-QE%A33H54_^{_Qdlqx43*yoM%1v^2Yzw zw_o0U-S3LayI=hBK)n2rN8ZRUpVXCS@W?+n)dl>l5u#W2UTs+;#Lk-GmNi1`tQl@u zBgD>{;g&T*?5r7XStG>Gn&GzAEMsTQaLXDY{;U~pStG>Gn&FnUPwcGmZdnu6&swSR ztf69)hqYB~^4FScZ0fQWiyu6!(PD#>wOefPv!;tpU;4Ag+wocB?L1lI?fhBe?Yddx z-HIn`yjyW*jkob`Q?+k@(dpN2dBD#pFOqq#hzOGWlt?O zJg}!08-CbRiw$q=sl|rR+T$A=o}-^kNUOe)bj{&z@s!@~{^f zoBXv$IW~3KyNn+^>}kdZCwrZ-(ThFM*yyF7evO9*^T3b!;mx}6DIRzhC;W>aUF-|J z>=(a05HCOEkvH0bo;K%&%W?lFc4?K$#{>4B4ea*hm%YO081M%`h9(g0bd{S4Q!6X0R zR2T5Gr`EpMQ)|EMsl|o|_S9m-4|{5{;f+1D*zj39UI=*vyKg)wTC`7JfECB>-f=&J?q%$#a?`D^kR>`e)jGg&z^p4^03z* zoBTBc5SzNp2H*z|GXvP*WR?IMy_hk;Mlb#JYdk!d2Y$>CZ`OrR@xZe<;a~jdVqfTG zzxd^Wc=;iZypdl%sVmRmk$-Ti3;3BqwJ&B+?Uxx;Y6&rq-LB)nQW>B%=vu0vr z!!t9e_|c0QRP3EzWuq4}xB8jIHJ%w=Z1OO>i%tHT>5WZYW_|I4hZ$gOa55W=jb6+Q zW22XT`ZXRN%mY8>hd1lOr+DC5obWIHonBQ7z3dmiJP%O`c^89ee2PIUo4 zdo=BfJ(~8*9!+d`V2>s?{IEw88{XKXi4C8%XEZiEvquv@da*|nd+PPjveAn@sruQg zYCL;bvB|^UR&4Uup4ZsaWiKp#@UTY~8=UN&#YQjo)MBHTe)=^Y9?Szj=7%@y!l!uP zS)A}M{;AjO3%%?YzdR5xKje`&^2;Z6F0C19f$XDDE!mwx&+9v;jCKjw!w>%yma;8~pTFaDigRSUiB7r#6ZFF)jw zH}cCTb>$g6@()gR0Y7_c?TbCN_RF4HYzOmt%J+;{A z#hzMh^kT0tHhQs#SpVxj_=1jS&oO@TuooGd{Iy3pHg(y%j2}GgX~qU8d!4b->rvSQ zjg4OV>DPF8Fc18gAKt7BpW=aMal*g&(Z#;d%YO081M#&7I(WzdG^C}Qud>lAeU-h_t8Da2U+qs{9iP6+ zCQte*oBZjkZ0e@3vcZ$S$_8ipDjWQqVP{|Z>DPF8Fc18gAKt7BpW=aMal*g&cY0MV z^s-<4@<6=&kVoFgFQ3$vXYj~BIP>>b`N7W_TlSUbl(OkJ&nacYL!ML0hMzpAlnrlr zPAMBc^PEyPJm)#3Z1l==O4;a@S(mcWE6*wI&vQ!0=Q*Wp^5i+CZ1U$hrEKcvIi+my z3IF0p7yCjl`^7I0#LEwPwU)xoq;}ce!lx=Xbem>gIR3Z1CiFxomLece!lz;>8>_q}DqXYPB;hUeV(mW^Jy?=5@kb!FM;mHXcI=f1b& zbKhGwc{ocBY~;^Olteedw~A?%zJ>c;UVt<%7!1# zq$VET@*bdU_{@8Nvf(-J0m??Nyay;7z49KQZ1l=|fcED-K*#4jK-uKUdw{aZpZ5S| zQ#bDc$_7u~1C$NUyay;7y*NYMzVy?t@$g_C_%T1cS-1Gy;elsy!oT>@#lFzXe(}o# z@$y3+c_Y7kQdgeABmdx37w~gtu6^Y_cK4h2-eto>-iMbBKb)DXUYwbW4WD_BT{b-D zJ$BjX#hJOp%-^qRqZelc>(6`aj?a7SvdNS8*kzMH@3G59ue`@D8$5ZBT{bxL9=mMx z;*4YRbAPCxevO9*^T3b!;mx}6DIRzhC;W>aUEXt}*%x}*FMfF-UVg|UZ{(Lx>dG^C z3;Lxrfhh~dz-T1C+}^_hPS-8DH}fX-llAL&U>4((JSw5%HCZM z%SNxfw`u>$IZGW3#OJ+D+2qN4o3hED_cmoyH}7rA22bAGlnu_jw<#OF@}8}1^wLki z#>0bo;K%&%W?lFc4?K$#{>6_jc^_4^(93@D%LDQ9Lmqh}zkE_xp1~vk;8Yjzb4H|k z<+-x2|9P$~8y@mpSvLISxw33{%X4Mf@R{ezvf(+;m1V?JY2{!WQxw35P=DD(L@Z`C&Y;fkevTXF?Oi%mLPrv_MMD7A1g4_cR8Ctoih+sr8O2Giq5E4TGn{Y`G0r4b?0>V0n zI;vb01d7ELl}m@p5Gw*IEtN{=Yp(BmW&Lr+nBzI~H=oaZ&%O6|@3rQ9R{l5?2cP2O z*1mYA2j_I+pZ>F6XI|=6zSiTwKR)8bP5gM;H_r6LpU&z+zcb&bD!w)pZi2>i!=9$ z))s&66RmCExlgn2anin@(q~vgvmQE8FK`>+;PXhvMK&-CD&PW;oaF7Ng7mv3I`Rle5az&}3X z#7+Eo+BeSh#GlUULjT+U;OB22(c^FY%tz1s$EW?TzT$U0dcn7!_8Yv@?|AfSf9#wCQ>7 zN1isFU;2KhP5-Ok>$K(7`e*+S&%FFU_NSkD#rZQI_B*fmU;Vd#=e6&f{IX{~O3w$r z*Rvj_^AG*$XI=XL*T4L%E3a>R<+HAQt;d0Xe8h>H`0=!Foau=_oz;c@A9?SWZLiCp zc$0U3^n>qz+Hdt$zxUA>eAH<_`?25q=w*NEwBP=Fp8e>tm!0-6{_$r&`h?@OU-BEC z{pj`n?P-7Tzj(JtU+^2gcw;{MZ@k;1Kl>r4{R1z4w?}$Uz2<-7FTUHO@BWV0t$)k^ z_d5S~f5yw#N1Px2gQqS2ull^xw(o1c_O$8wmjC&*>HOsHJ8k;^$Uix4dA0u3XTSU9 z|B9b^_bbld`tbL-;{WL1d5>$~_kV-;e3YKQ^xp6JD4nl({(D~fpZ>+~dFAzUU;ds~ zzSiTwKR)8bP5gM;H_r6LpU&z+|FggIMOVF^`8}sC-=F&7)5hWd{@K&U=ZoL;3)dgF z@A+M)jpxUH!fE6DQ?ER2_4*h8l_`oHUgPkUd759{*HABW=LQ+(Xo7ti$IoKF1H zuP)`KUgc{&4*cUIPTa(gr+wp0PyFeuF7(&GA+P!bK`VjD} zKLO|Z7Vxj1L0#rL+x}bculgUX*B8ORehG2vqY%IT3j5Y~K~Mb{bk?UqfBhTsYF)nh z<4_!YijQ0S;+Y6g8$arLoqy_|JZ(I`@*kfz&foMqp0_^uzwFhgtuFua%|3e9 z)$6erp0@Qj{*R~4|7||%W7bEUKkzN5E&kv8<$v(n_ZQ#ywCQ={KYQAAe%6^b z?-zMFdy6e!XKb-?aK;uJA7^Z_z0RGn#l~~b{2Ci)XKd}i9sbVPVyla@!`SNOOtIFT zHI~0K$k^gIn~W{~o>?}weVt`yogQbL?Y|wJ&OT$)|MWQ%jV-U%<(oea#lffexV0~y z>A^Xj_@`f8%1gb<*LocI$48vFi62k<#+jb@(^*~U@BXs9x{oQ}?r*AB_dW6Hekg9; zC&jb-r#N?C)%#_BS01>jm$U5I>ec;O>)p5I-~C*1y3Z?q_kZo%ePMdKUrcBBk?HUL zvbv7;8A93O)emw0PXL{mKXLX_f2maEh zUa!M%d)aBr_qYD7)5hV^|9RT@e8zwKY3q;Mzxh+Ajpwiafz!tM?Vt6h*9ZTnea&gB z%SXKV^LJgnzV`D@+xiQC?zH*8@}vLE`iS%0-+J2O|IT0W>DRuW`u?X)&kH~EwCVi0 zFFS4ef9%z#tzNCmH-8+8gHQ2sYhOImgL69ZPrtg9mwJ`2^*Hd4k2rA?Kc4oDGd=OA zv%1j#n?CmgmV>;W{*u#{?`J-7+BkgSkDN9>|LCorb8&m;Pd;rt|H${AHqM{<_y?{J z{vY|O(|&k=?YesX{O3G(ZR`K^XHT2|zx#;azw6@sx^F&h@jv$sKWNvzPX7M;oHji_ z^k+_+&i8)#Y199VuRLvewJzWMaVQQx#mB9E@k|fS>BK+%5AUzlre5W1Jr4ZiBTn4J zkEea(Oi%pjtS;yk-Ai7d^_NduzCZKY)5hWTfBdxZdG>GmxQp8ppK{uG{Q%nh zY;>1n-c-lA4^u(Xe>O%jgeD+%}2YEg3MW-#_@A>-E#^FbP__XnPi??{2i`(aa z(rM%QP2YXmIDgMOzU}(p|Mg#f+UoN2zw)>2x_Z6uXPvh7xB2&{&Hr6L^zGJ1oR9y; z(-!}qzW&=^`~K?pJZ*a3=F?7_&M$fCY198%uQ+XawJzWMaVQQx#mB9E@k|fS>BK+% z>QY|nRle5az&}3X#7+Eo+BeSh#GlUULVx|(@~ZDwzV!p+P@gb9^$+`8s;?N&`i*g} z4;laZlh60pPhP*j>SwlIpELjZpT(&!TKxL4?OPu;J@r@9S>HAN^<&Gcb@}FxLvipa zK5p%cXL@i>C;sU_-(P25>Q%nhY;>1n-c-lA4^u(Xe>Oz10*z&6HSHATF<4~V4 zKJ^ddR$nom^&8{-oQHmF{OeCvm-?2yzv^eUUY|4n`k%$AFIxQirR`fEH9hrL(^=m& z{q&vC5eqB22)*zqzHWT#_r|S0a6Ib|$GN_7{Oc!wcz<2Lzv@4?USB%@ z`qjm$k6rxw+wEK5J3aNo(^;Q9{q@hwt9AM2k3(_rDL!uPi)VUpPAC59e|UdwUg}l8 z*5klGKH|hp{CL_o&h*5e&gw${8+^xK*uUfQ`p^IHwB`Ga|Ho$p4 z{g=MWY2*2}AAj07f8#4o8~<1R;AyMN^ug}G^?CR+?{V7JfBZ8}oBt=h=CsB6B|mc7 z;=l77eD<~PKYi=drsu~Voi?3c_5r6&|BF88wB^;heDlYlIQSGFxAw&|JvgTm|MaU% zd8t?VT8{(&_=poX@#AUVIMWk7!uZrb>~&sWF`m;0yPtJ9 z*N2RM{mBpYx;_uC;sVIm-14t^0giZ{_znfZsNz&zHz1}{&ZFs`sY6E z^?5k=Vb_-L+_zmDhq<4-Ha>HocWvC}{_om&&VAUmai06IYvVunk=It2xxc)&&%?Rz ze67!Y*vo(J!>+yc`k2!ef9}KXx_#$9?Ar9qec1Egj?TFcyEgrE-+XQLYF)nh<4_!Y ziof-G*cZ?A;G9nU)2}Y&rC#N0Jr4ZiBTn4JkEea(Oi%pjtSCb*Zf)G=zqRq4|F<^I^KaHxuVJ^gdJVg^)ob>?)<@IjKU&uoXL49u{K;)?`%cbl z(=#mArgIprtzN@!ZS`thzWL)&9DIt8Tl?af9-PyOfBMy>ywt0Ft;d0Xe8h>H`0=!F zoau=_oz;c@>7}^xnjVWQ-|4+r8;9woSR0?|rC1xc>7`g3&*`OD8|UezSX;fOmtt-8 znqG>v)oXeYuJ!3rxcsMgVQq1yr(tdJr`KU^`%VwU+Vo6s#M*RD&&1m5HN6yTt5@st z%^!#2;8T3u+859C;G9nU)2}Y&rC#N0Jr4ZiBTn4JkEea(Oi%pjtSh@F_lS?Tcr6a84)w=|Agr=A~ZcYdsG9<0DSo z#E++a<4jNd>8vjFd&W%n^*m#SEnm-=VXK#C%&^tVGiKQPI-h6Eu<_hy-i(d2XUy!s z9sZs%!&aBMZ@#womuKp>1m>p5?=)$1{G|bUtsM{lli; zGlAIZ)w+E1$Dug*6d$+t#WOuPrxXA5t4n#QSNU3x1ONDl-2c$+5X$n=~-xO_414~wtBTL-~4eX4nD=l zt$p!K56&HguluTVjrqFYI@g%5`>=CQ;JQC+z5BNOyPqpg z_j$$d{;z$zFHBGOi|On>GX33OmRIX@P5ttpYwcH@xdwm5pKJ5izH`m~(lgicFP(FZ z|I$C#{;#~|p1_r__3kh8@BXql-Cq{J`^)z2{xUt?U#7GB%ks|)>I-;h_o zqvhN0YaIIBjZeSFaqD;bzWyJsZ{XbTdi?vnuP)7Ht5??ttasgjf7cVldAo<}8{&8U z!Mywt0F zt;d0Xe8h>H`0=!Foau=_oz;c@zHi8@ziaaC?;Q^P9mJ=uiibG}=zjr05lSR4QOZoRg;%y;Xx)oZ?+UhDIn z_41$ZvTKVo-*ML#f4=*!ZQuD$yf!`aU3qOf=R5S;^v`$ewdK{ieDlYlIQSGFxAw&| zJvgTm|MaU%d8t?VT8{(&_=poX@#AUVIMWk$Pzhc5CA^?AFF@ z{#zT*`G0HUJpX2G^%{0-tJknwTfJuQYkf3b{-bqmaVCeg#h={Pw(sP;Ha){)Z90e1 z+Uhmz)>g09<(oea#lffexV0~y>A^Xj_@`f8%1gb<*LocI$48vFi62k<#+jb@(^*~U zuir*q^>xU%eh(b#1Hq^M5Zvk;!Lxo6oa-}Duli5at8)U?t9}*h^|A1;zeSw-Uc|2- z#=iB*&{O{mo%PkwU%!pKT9U7YUAi{Jfv`*t6np6>6{*?oWd>j#im>+;PXhvMK&-CD& zPW;oaF6E_Ot^azf06b2j`-J)Bu;%w;@7`q-};*9so#mt`k?5qKT2M$%Qt@< zii1z_acf^Z(}Qz5@lU_Hl$Uyyuk|?akB>NU6F;8zjWa#*r?a}yU;n(k>eH5Q{o6Ry z*Nsp8-ni8Vj%WShIM+9hfBobS_1fQ(=__4?BJ*RL*4eeB}b-)`Uf-s!0yp3eH@ z>92oYUaiYFe;kT~Pw{bUUp&);b2{-)|3ketFZC*4>v7;8A93O)emw0PXL{mKXLX^! zc|CbG7bf54#c*hj44>x9aBJ=i&*sr^ZcYvV=GWAvxiA^Xj_@`f8%1gb<*LocI$48vFi62k< z#+jb@(^*~U@BXs9x{oQ}?r-AIeNTM4AG)vehx^NTcK;OT?yKV8{Z@79KCF6mf7W{U zZTWXUSDfziir@WT`*vTLp6(aZ*?naCyT2^2*5#W&4#mNz__(z%p6S6ko%p9;UCK+n z%GY`v_{T?_?k|fUPy5E1p7_&QUFh$ArM$W?Cg1Lt;n00Fe7e83+#c?`;o1E-oV!nl zfA{ayrTcp7)%`x}-3R2~{XucMZzz8E6Ybl5MtZvcNN4vY>F<7}yjquU{x}o|pW@@z zzIdhw=XBzqesw7?^(tTMao`^xak^hAemwVe@^D|6p7_&QUFffWUS9QS%eVe*9O~=F zr+#nT>I28K{&1Y@8^^zXa&@WCT)pZ)w_aa5|N7O%sgGU!`rGYW-#b0^!_!%xJpJ|0 z%d2(y=8r>h@F_lS?Tcr6a84)w=~tKXQm^v09tZyM5hrfq$J4%XrYHV%Ru}r~$Cg)p zzw)gg7>D|V@u`0pxB80ltlt>t`jGLjKl!0v+qbM<^)p+q&zXPy&*Ibh@F_lS?Tcr6a84)w=~tKXQm^v0 z9tZyM5hrfq$J4%XrYHV%Ru}r~@0C}5r1Gu56o>jw@u?pbxB67^tbY~f`daa?-&I}e zgH^BkW3AUW%fEhFaq6=bzy4eM)|X39{knA4$4h_xz4B^ZzWL)&9DIt8Tl?af9-PyO zfBMy>ywt0Ft;d0Xe8h>H`0=!Foau=_oz;c@IS1yE->~x?$N4a8&vzW>z^pyrahwCQ z_I$^24$Rulahh{r)}HS;&VgBbzT-FtX6^Zo;~bc^=R3~aH$QFXN6k4f*ZQ0TbNSCX zFl&o5=fJEj{+t7|wteRun6>Gdb70n{bIyTToBlbsXKi`4KHups|M{+W#hLGbSN!>I zcXjzai%B!bXFJozw&>3 z^_ACO|NhgK?|=Avr;Wo;e%)!~^M0Ry+PJ;hA3AM3U+_++jq`u_FR$8|>h(*%>$KJD zc`rU~_4?Z%`nvUh@K&$$f0zI3tM=cD^VLtDw)lVSi%;9W-}kAfP0x2c@3iTBqvxD9 z{lE5oPg}iOmv8*t=fd_Uybr;Wo0{Fc+k=ZRl_+PFRc$6m4j7SA95o2QNQhrZyn)$5PG z_i3xwd~U42dcFA%{ZDIKf7`D(ZT_$P#M2h%4d3;&#sB^{J8k-$byzH{!`uH!K0ph%R5b=q{!IcB>~|C~Fw zw!B)GZ~izG2cP2O*1mYA2j_I+pMG^IFZC*4>v7;8A93O)emw0PXL{mK=bSIMx!mie zud;Rhmig-!Esp-o;%~p`L%sBKrbnM=I`vnlU%zO1=@%_u>v7;8A93O)emw0PXL{mK zXLX^!ddaJG{g(Ob!z_;e%;M|YY+wDH>CxwzPW_+hpL^F=UiwAL*LocI$7lORAGnDh zPy5E1p7_&QUFh%o#^&|#eM7$ey~ClugZT9K5x4$s;@RI*oclYAe}8|~rSBW+)%OkS z{T=7u-*<8Pz9D|!H|*Q@4SM>%L1*79=!SN!lh<4qU0c3$U36_6=DO(G_{??DwQ-y4 zqHE(h*G1RHd9I7DjsIL1U0Yq|y6D>KHP=P2^|>y3`OkIHwZ)n1qHBvk*G1R1?_3vM zo1VEYx;CA2U36{w=Q{S<@@iea`QuO=e2R}-`{J1%oYRSa`qibp)T?~0$AN!*#EF~u z@w9K8>4`s`)rJ1fpO@GCPI*_~?d3baQ`W{|ey6OB&-_kV8@KtLvNoRcJ7sO0=Xc85 z>NUSp)>g0iyS%n~&F_?JeSW80{_{I!ZE@yz%G%=3@07LeJHJ!bre}VqtWD?qPFb7& z&Yzc8>+;PXhvMK&-CD&PW;oaF6E_Ojpy9gTN~%OueY{(&3(PK)obqSt*u^jU+-F< z`+ArE+}B%MoVl;Jw)k^jZ*BX|eZ95mnfrQctJmDuTU)()eu}(Wmv8a&0`PuX1gir>}Bt^_srQwbg6pIM!CL>8rffr?2wzpT5eq#hJd!wZ)&l z%C+q~eU(?ermym<*Ys6h^_o7|wbiS2`R0#9aquZVZtaU_dT>rB{^?hj@=~wzwH^ol z@ewC(;>Xjzai%B!bXFJoJAYnY(^q-rJAIWGhv}}BtoTsmH zZS|VI%C*(2bK2Ew`YNyW>8rf_r>}Btai*_wZSkkCa&7xgU*+2LOkd^NURTpsxwiM$ z^uewzuh!+8KMuvgr}((FFP`baIi2{YUtP*ey~@{m9QemaoVbY}Py5E1p7_&QUFh$5 z9P*m`4p+W&-{Img_Z`;8XYM$Od-{D%H z`wo}?+;>=8oVo9?w)k`3VQu@)eTTK_nfnfFtJmCjSX;e%9*4YImv8fQ^*Hd4k2rA?Kc4oDGd=OAv%1jV^NHj&eR@~E)2DZFm_EI= z_x1end?MVYPjA=poIbs^ah^WC^WRRrrcZBe_3Al3>NS0O*ZTD7UH;Rjx3)Obr?9Bbn?a~x~q zIddFq_l zW{zWRI=}5@r%nIN-R!!&T9$KI&HKW#DOUmChCbl@PJ+Z}iO^R(_*Q(g`xaP&C(={))db#GsmRIZY%^!#2;8T3u z+859C;G9nU)2}YBdD%<7%GY`v_{T?_xQQQ6`^K4`_|sWk=@|wA}>+@vh+OE%; znQL1cpP6f08@IRn;M2x)=Gt~0=b39e|LxRk=GxX)uj#8?TfJtk?OLC?w#$F!+SV3l z=GxX4|1BS$H)`LRYuj~tX0Gl0w^Of~Yg=2rdfuqKT94RO{>vsBJ*T!f1VAsZN z`e4__bNXP{#(DZ+*Y^IJKG?M%>b16dO&{#FK7Fv4|MbDGEzb18t}Xub!LDuJ>4ROH zp6P>Ko6hNjU0c1TZ+UI?YF)nh<4_!YijQ0S;+Ys|)?pS9#?%eU(?f(^t7R4%1h;Ha^o=xi)UoSGhKx(^t7R&eK=9wt7up z<=W~szbn^Puj#A2)~B!X@}IuSwZ(boPd;t&r>}C??K^#yYtu7*mFK@5ozqvjwt7t; z?Aq$px_tA;p*Z*yAGh|!Gd(z`6aVz9OL?hR`C5+y|M-X#H}T_X-#F6~e>$rR{nO`g z{I^rD>2p|Hy{6A$ZS|Ty zhiiTM94`Oqb68uP>2p|H{ONO8+rHE1ur@u@=dd=N)90|ZdQD%-+UnK1eDlYlIQSGF zxAw&|JvgTm|MaU%d8t?VT8{(&_=q$8A*)UNc-lA4^u(Xe>O#MsgZ?h-Iq2`To&z=x zdJfq5=s95Hrssf-r=9~g&Uy~m-d}nS*y^R1f~{V9ELzulk-we{wm5n<*y8KqVB1%3 z2b&%}A8b1Hg0R&~j|f}6T9JbS(s&M$a){+D|7{4e$D`CsbQ z^S`Y3TrK`RZ%dpx$84F4-}Arh+w;HZ>G@xD_M9*Jd;XWaT9<%MPWT8{(&_=poX@#ASN&V1u9Ms*Rp=h549=Gw0B!!y@*eNUdb zwzX-Wxwf_CG;?ih%XQ}3*2ZAw+SbNq=GxZAZ2Feh#&YJ`uJxH~yZmRaZSAes!}I9H zf1iiv(c5?C+SZ4jnQJ@$?bK`L+SbOh=h4fnb@}FxLvipa{?_YZUo6vuWje7;KbGaC zUgc{&4*cUIPTa(gr+wp0PyFeuF7)?&b9qf4?Cl(>dq%tgT*i z&eGcI)w+E1$Dug*6d$+t#WOuPrxXA5t4n#QSNU3x1ONDl6F2eWY2P^06Ms6Z3;i?4 zapm>Amz=hIXO83IFmoJh<1=#{YvVR^9Bbn_a~x~qJaZgttJlnNto`tLxVC!D9LKdj za~zld%yFzO&dhPFE&j}LtZmv7;8A93O)emw0PXL{mKXLX^!=lS|h+H+%lSM7PSzQgvM zS>J7Y{;co3J(t#Z;htCPJ95vl_1(GW+xkxZxxeNw{C7TYeb?@JxYm14F8`jND^AbV z6~E{0+PCNM($n*K>Fl|^^!Gg9hrIULzP@Yc@4I$!eAh0%@7nF_yLNhf*G{MJ+UfUQ z`_q2#`J0#DM&)Zg4*cUIPTa(gr+wp0PyFeuF7)?&bFafWckcT9@A=wZw>@{;>$&G~ zd!6^3Zm<8I-|c_v?HPxc67j2e;mH!}<3-adCRixcEJP+`c`RoSvRn zPG`?C_x|en=JIOY>ob3^+v0dV7vJl=eZBtE<9(4%@0av@AIviWzSiTwKR)8b zP5gM;H_r6LpU&z+fA#V@Y~AZKf3Mr(cs&>2>%4uv{?p@qkxuWI^m`wbm-kosT8{(& z_=poX@#AUVIMWkHU&^@1yea{wiPV zao`^xapER^Jnb82dg4!Kb)moO8}hP;&nx-bgN=hd*!b9kjhj8#c-n)Fvpv}O+k>qx z_F$`*JzBR%{`O#tV-L3Y{$pG7|JZ!(!4|_FY_Yq(Vb9iS$)CpJ&|Z8wwXa;$gF!m6 zNk3-gg=P6#j|2bsh!Z#Q<7q9{YxwtjN1T2KiQn%d`}Vtuo_Ukm5@xbUyPOI_;wQm^{Ktk);Tzy2|C>MIk!elz>l zhel8RX>``NMt}Wm@@iea`QuO=e2R}-`{J1%oYRSa`qibp)T?~0$AN!*#EF~u@w9K8 z>4`s`)rJ20=jBzOwtVZ~#-YA$eCqectv+x(>kr4dzH$8PCs&vH%+;&@bL;h`^RHiB zoch?sufN^C^}W+mKRliF$v7;8 zA93O)emw0PXL{mKXLX^!`^)m`KBj!TzllTlJ@@teaDN%M?vw88|Ka{J&fQnVzx%D{ z`|G^dtX|!pwcdSO{@u?Nr~AC(cmLPE-4~{(`^9v2ADRB{FUzZS`R0#9aquZVZtaU_ zdT>rB{^>v8UuRzGRle5az`y&;;>1n-?l0Rn&h*5e&gw#c_m}0>eN6dwe-nr9d*ajm zP~5stif8vvaqhk<{@rg?m+r%=*GE3wU$)+TTmIe86{q{W;&=bozTFq5r~Acpb|0Dk z?k~%$b@}FxLvipaK5p%cXL@i>C;sVIm-14t^0giZ{_znfZsNz&zHz1}{&ZFs`n!H8 zudY+cx9e9pbX^Odu6N8vjF*Dors`V!?^zakFxG2&ByBX0FQ;#of=&h<&+U;m`K)K{rq^;=r650iiW znc~#9DSrK&_N~v8p87xOtS^-Q`bFi{x_tA;p*Z*yAGh|!Gd(z`6aVz9OL?hR`C5+y z|M-X#H}T_X-#F6~e>$rR{msM5t2sXTHs6OsbAR|W4~ScHop?4sh;ws=_&0B;F3ne} zSM!P1n_J}HJfk?xIf~!>qkWr;q^EgFI-8@UzxhgewJzWMaVQQx#mB9E@k|fS>BK+% z>QY|nRle5az&}3X#7+Eo+BeSh#GlUULVx{-@~Y2GzV*N1P+uHA^~>S*b`SlBc-CKs zbA5OC*N>+z_35cs{d?By>*HU)pE&gaieG=Aed`;fr+z{@>ocUk{zG}SF5modC=Ncw z$E|(wOb^cK#6SJ&QeNs+zSiTwKR)8bP5gM;H_r6LpU&z+fAe4RYR*W$%^%^=ToOLb zE8*506Q0dC;oRI4{>?+F%luv5`@ibd{FL?Ps`xi=B~Ei#;y0gV-{!XHX`YMD=Dg@{ z{!3o1%Qt@NU6F;8zjWa#*r?a}y-+2!5 z>f8YNcAfwZoil(>=MUi4xdeE2UIEUXV}O6>8>q{-Kb+^FUY&k-ycYcC6ovR>z z=PlT`a~SC9d8vjFy9eMJsl40+=z6Jp09{9Q4}gu2djM?Q+yh|a=^g+ZXZHZu_`3(d zRu}g+*y`n;N9*o|uh!+8KMuvg zr}((FFP`baIi2{YUtP*ey~@{m9QemaoVbY}Py5E1p7_&QUFdIKPhQQ1$+vki9GWA; zr};A6nmfa@c{H4xQ&X?z*VL=IHuY-W&3bci{F{#xr@1-to2RpHb9VGJe@AC?dGt50 zC$HA!n?DZ4!Ke7RwJ)CO!8x7yr(a#lOTEh1dK~!2N1V8cA5Z(nnV$I5SzYMwd;obh zhc4gd({X5S9iQgeacj;U&*tB8ZZ01G=H=C;IePVKzTSFs_xzj37pFOW@tfbbZ*%?h zH1AJm=K#>(`2g~2UB3C_P#k=Uk6ZiVnI4?eiGTXlrM%Rue67cUe|*G=oA~jxZ=C6g zKb_Tu{`%SERo|3+>!-q@J}Z3czrwA)EIjMi!nr;!{Oj*hm-@cct9~%+^@;JXe@vV? zr+vSlh+n^%ed|M`r~WiL>szD0el~fvF5modC=NcwUv3Zk;+YUBJKx}} z*Lj|UdUYOx_0CD)-}wpRbgqKrB{^?hj@=~wzwH^ol@ewC(;>Xjzai%B!bXFJoJ5Ntuo!chg z&U3?|bKdaj{5RY>7Y@(Pi^I8dLUf9L7Rt9AM2k3(_rDL!uPi)VUpPAC59SC{fquky7X2mbL9CvM`$)4p-0 zC;oI+7y6rDmREDK@@;+=hvsVWY2FsM=5X$rR{mrMyt2qeyHXngQa})S9Pk~!=7I-#)fpc>i_&2YiF3oYM zSMwd#oBQD3Jcu~WiHP6)h<%$Yp{IEhI-5hGzxfn-wJzWMaVQQx#mB9E@k|fS>BK+% z>QY|nRle5au=Rb%&)?sJ;>1n-c-lA4^u(Xe>Oz10z4EG$RKE3>;!xiyKJ}yGR-Y=K z^{?VwUn~CgyQ<54k6O*@Re!AY`eympPb*G+w&K@+Yv1~E>8W3r&iZ)iufJDbt;;um z9EyWa@o{TkJkx`7I`L1xx|ElCm9Oa@B2T@ zSK`pzA3neEFkgvVbAos_KZtX4h4?pbs4mSRs#o)g)|*@8-#nu@PkhS9ZGFXW{?We8 zMbgu}B%RGs(%*cgyjquU{x}o|pW@@zzIdhw=XBzqesw7?^(tTMao`^xapER^Jnb82 zdg4!Kb)mn0Y}Zuk`*p3Qeqh&N>JxTtrv72qZ0aj^EvJ5C*LdnfcI~JBWY>i1$9Ao# zerD_SIrFdoS)BT!#jju5zV%VlQ-3v`^<&dtKlVdj+mG#9QU0zK700!r;=5MVzOEIe z$F-t#x>l5a*NW=Lc5SbGt;d0Xe8h>H`0=!Foau=_oz;c@=}URabv8Y8)0eWg-n!{a zSzFKD^rft=7jODf*4CppeJN|}-J8CYwe|E(U&`8g{iZKvZ9Ra~m$J6r!0Ai5)~7G! z@}ItxwZ)mfl(og5zLd4?JAEl@(=&Z3YtuP>DQnX|eMD=^t98AB`RffVj^4oH>kVvQ zy@Bb`8<)31CcdlcvP0w7%UYpLjj=i>e&3%Wp)vI;+=8r>h@F_lS?Tcr6a84)w=~tKX zQm^v09tZyM5hrfq$J4%XrYHV%Ru}r`KJ1m(+=spLo%^tB<1qJO*T!e=!>*0n+=pEo z&$$n~HqLV&c5U^V`><=P*W8C)TfOE!?6p4kVK4u=54*NFb02nX@#jA5+V-9MuxryZ z_hHwjbMC{gtzL8Ad~Nk=UB3C_P#k=Uk6ZiVnI4?eiGTXlrM%Rue67cUe|*G=oA~jx zZ=C6gKb_Tu{`uZ}wk^vw6(wdtJiy=$x2{7zYW zKj$CT<(oea#lffexV0~y>A^Xj_@`f8%1gb<*LocI$48vFi62k<#+jb@(^*~U@AJ_2 zsNQ$JU-f?Uy{q@B?_<4xeNXFs?fYBrci-#!9PoXw&xiB-{Q3Fj`(d9a*87~{-{+4w zeJ+XL=aqf?9HXbtH#+;=qrcBXdA08QRsOzr7036n;`^S~zP`Vu$M?E)`o5R`^ZWdn zm+yz=YdsG9<0DSo#E++a<4jNd>8vjF_x_Ssb(C-Q#i6?6)9V4ZUMG0=`oX!^75=^6 z)TP& zC;sVIm-14t^0giZ{_znfZsNz&zHz1}{&ZFs`sX^^^|>+E*{;u%xz4t>&zZT-wzkio zxz4t>&!xG}wzki!xz4t>&#}4Awzkj1xz4t>&%?RSwzkj1xz2X2&vmxTf3CBwEzVqL zTU-3O&bGFF=Q`Wk^vrd(wdtJeY-{^Goa>@%`#fyj=SluPXNu$Vr}#dX+Slh*dVG$h z)8||IeeRW)&%^Sy9tZyM5hrfq$J4%XrYHV%Ru}sFzTtJ)-!-q#{@!`r_IJ?hxxbHI z=l$LE`tR?l_eFnaywVPUW$&;4UR&?)IRE~>i__nI@%uht-@Yf%)At8D`(8nR z-#6sdy4Pp^Ubn^ZdM>`#dHZ_(r^ovuo!&3$_dY5w@2~Q;9tZyM5hrfq$J4%XrYHV% zRu}sF{k5MP55K?U+xLGQ`dxrezZY=pcLbjOzQDQP9r*WqL|yuwqF()evEJ_*{{7w& zr{6*1_xs4c{cfVC-&1tn=;dhyQ^T(k$_!J+v_Qf+jIHwc;^s7sGsaN@0 zj|2bsh!Z#Q<7wYG(-VI>`~7wQJd{`OJNfp0#G&^oKD~c&>wS%9?{}R09KgTN2X*Ol zL%sSuvEJtl|2}`j>2pc^KCkTC=NLVGzR}s|9{qhD%Bywx=8r>h@F_lS?Tcr6a84)w z=~tKXQm^v09tZyM5hrfq$J4%XrYHV%Ru}rGukuOPH@@VHUZbya?SKDauhCbz_Urw| z*XXNU`_um26Z$IG{?VtN&{w(k*S`D-eU)oJ?N2|UuX63z`-w1%FBQHD%Te0?LPP~t}XubRjzH{>8o6up6RPxo6hO0T$}#sgI!x*tv~wi z*IfR;{q2p{cpZEDaZ?-mW z(_gVRp3~>BHqO)Mu(oC;{0nmLYZedahW z|C!@hTb!BWSX=y=<5=6iGsm&^zJ7k}wCS8Vj$K!;nY&qAy;_&=%zf-S4#inM5Aktp zUp&);b2{-)zq*u{dX=yBIPi~;IB^p{p7xD1J@Kcry3pVAm*q8mDObMJm$Ehv)0eU~ zKGT=7Hg40GvNoR6m$Ej_&-svlytaBxU&`9*HGL^-tJn0UT&kcfzAg^a_q8@Y)AzMDZqxU*HlEY>wKmSv z_qDcqP2bnr=ijeatgT+t_jRpL-`C|oeP3&fGksrci$8r|Yuk7FzSgE^`o7jyuj%_* zTfKTdth`#6Z~izG2cP2O*1mYA2j_I+pMG_j>+`#>dX=yBIPi~;IB^p{p7xD1J@Kcr zy3jx8z#M%)oO58-mhYScvo;QM4$Rv4%sDV?<2L8Otc~ZK1G6^Ha}Lbf>NV%UtbM+} zp1Zbs%{egF`kVuE`Oi5pYl}1Iz^pC)oCCAAedipQwdt92VAiH{&VgB*{yDd2ZS`th zzWL)&9DIt8Tl?af9-PyOfBMh&*O`}km9O=5E%eXXb9!rgP?Q)>f~XlUiF|t;;um9EyWa@o{TkJkx`7 zI`L2cL%nt{^(tTMao`^xapER^Jnb82dg4!Kb)moK(aUSj6}euYbFRqsx}9@H*2ZVf z6a;?v~BA5T1E3&pYbFRqR;?KDv zYuk6u6ech;<<+`;^T(k$_!J+v_Qf+jIHwc;^q=+m{?(vfeU>gdNrSDy}3pH%`=MAoTK>jyK?ukZ*!6KG%rbKbCmQqUn#HF<(oea#lffexV0~y z>A^Xj_@`f8%1gb<*LocI$48vFi62k<#+jb@(^*~UZ@yAq&GE^%`92()`@^SsK-`)W z#IyN9oSQ4ezj?!l&%1>XY{^l#?)w+E1 z$Dug*6d$+t#WOuPrxXA5pYN~dZeHqDzSiTwKR)8bP5gM;H_r6LpU&z+fBp0Fs!v5=)UpGGWd*fCgIG*)~<6Pf3{`Hfe_4@v+UiF__f6l}6zxda$E>3;y;@979-}>I^ zsUM!s`sC@ae_md#%Qt@L-do#EL$8qUqB;otn4x-{43{nfmi_2%IC zHyj0O|=JM!oUQb@F%Qt@NU6F;8zjWa#*r?a}y-}xKz>YNApcK(BUbuNT@bzTH+og;x~=S$$+xfA$z z9)-GePKA1PeueeUwcy`*7vgjdhWMS2Vc*Wppr`XR= zpU!{7t#jeh@F_lS?Tcr6a84)w=~tKXQm^v09tZyM5hrf@dU!Y=-oA0B zC;oI+7y6s8lvi_n@@>8khvxq9X&w-_<^=I8vjFH(x2Q=J@2>d>;BdX=yBIPi~;IB^p{p7xD1J@Kcry3pTw%kt`6U-@?4FAkjpj8EqS|AB~J8xND zt;;um9EyWa@o{TkJkx`7I`L1xx|ElCm9Of6V&etw+m^T)sbe|7oXAA04U)9&-Ic>(Lq5%6!mK%C|d#J}bd zX5Z!%=xKg|&gLEHZ{Fb{ubp?0Z~izG2cP2O*1mYA2j_I+pMG`u*01}r%}c$?*LocI z$48vFi62k<#+jb@(^*~Uf5wlW_acAti~ib^FZ@rZ{rf-tYoGjyXFS}C{K&6+^3T8Q zwBP)zDrZCqL!|fBQ+_CH~W!f5VgC`}_aS+AsRE z-|*ybe(bz2`BUHY4Nrc-um9#wnAI*5CJEoi_h({+9E;q&PqD{PSL< z_}}>!=lw_fzWi0EP0w%tWyi+(+R^#qXP-9x|MEjlTVAby_Sb&R<^Nm1^RHfUp8OAA zeZ_zE<6nL4`^1Z1ed+m;r@i{p`QCr+RhRyM^$D-K^7^6=ebtq(^*Hd4k2rA?Kc4oD zGd=OAv%1hez z=o{YQsdPU3Gv48;>h;DS{SHr6uYdhP@9P2UDp}%^` ztM&K#!|!zY|Li|`rz_6aJ$mel|I9Cc?ArHl{`6y)o-cds@k{5w{KJo5`hWFjKYr!) zZZCTL%GY`v_{T?_xQQQ6`^K4`_|sWk=zpVk|MKmtl-F;1pVPMfE+2N<{D16EoVGZB z;3cOm{!730wC(%hKY7~pJpNW+u`%iV{0}>A`d|H$)0Wqh|LAq=Z~9BW^78+wXPve< zf9K;)Tl}AW$!Xj7zyHS5rswJ3bJ}$N=6`nDtN+JNTVAcJWB%$}9Ca_g*F*byoutR> zC!Jnb>GygoFR#P$wH^ol@ewC(;>Xjzai%B!bXFJo`}^f@W}lP(miGDSZ)~5d{`U5H z>u++O!~RzH`Rs3apWFVn_j&Gb{&&9LpZ{u~nZ673`ER|y3;g?gAx?is#P9EmefzsZ zPk)c-?C%%-{r!5#YyW=vE|9$xN;EMnIKH=KecY*ZyE|5;&1=8=kz?*->7j0g? zyOpo?IPi~;IB^sI;yL@qnV$I5SzYL_pG{u%P06=@Dje#w!l(W#-0I81vwkg{>*K<| zel~TfpH02$XR}_P82|dm#HpW6{QBAKTR$5;^|R4g-x~e(v&pM<`R0#9aqzj~54ZNk zGd(z`6aVz9OL?hR`C5+y|M-X#H}Nl?vu~W~i9emyh5qT?+|MF;P4DK~@}1tzwQ-o< z&9(8F-p$j0xJ~co+IUXy=Gr(<@8;V0Pw(d1>N35XYpd7vK3?n76M6YhujJa|Ob_MS z;!kho+Uhkumuu5Ay_jp$IX#+d(?7kNr~l;Dx_tA;p*Z+l@rPUc;+YOz0>DeBc6gnXNiz@fPbe43}gtvL%ko4>%hxeWDc zUPHZ_<4~{WJFLIpVg8GM^C03hCnA3HBlc~sgr4S2=xh#!{^nEU)w+E1$Dug*T=9on z`{J1%oYRSa`qibp)T?~0$AN!*#EF~u7th%@&h*5e&gw#c{ZaC&4@bWB=ipG^4nFns z;8vdxp7sCW{G5mWDE#XeQkVLO)T{m?>-8P+uOCUA`jo`4f62b}HPKVQ6P@)z(O-X* zyjquU{x}o|pDX@wYhOImgL69ZPrtg9mwJ`2^*Hd4k2rA?|Kd6O#+jb@(^*~UpL5!; z&y6{!{rWtabK2L&Va{n^8=pC+{q!Ghb58r(%kz6r8|Tk_`~!C#|2e09?XzCbU0c0= z{&P;-`kd2#`Oi7+Yl}1Iw687xoYTIxdd)fQYtu95w69I)oYTIxdd<1|r~lNeb@}Fx zLvirA;t#j>#WOuPrxXA5pY=NRt5^A2j|2ZX$A0yQ6F2cMp0jV9>4`s`)rJ1%E4>bz zxHTt;XY+$NH&>`$%^RxAw?E9At5@@h)|*@8-#nu@%{hwS{G)xF zi=?M{NjjUOq`&z}d9^Oz{BbA_K3DwV*1mYA2j_I+pMG^IFZC*4>v7;8A93O){>5|l zjWa#*r?a}yU;n(k>eH5Q{o6Ry*Nsp8-ni8Vj%WShIM+9hfBocVz20K4MW|Q(=ho{> z=U>0NIQ6lMUw^xO>wBlCet0_Tlc&G_d3m)i-~4eX4n9}>;nu!*rU&PA;-CJrUT0qF zRle5az&}3X#7+E*=j&p}vQoOuqy+Tzc15Y|?& zc@Dzb^vrV*)~0iwgRr)G&2uYG|EX8&^35NI;^1?|A8zf7XL@i>C;sVIm-14t^0giZ z{_znfZsK1&XWux}6Ms6Z3;lDB*_GF~z3jB*JLi~P9OfLewegvA%ufH|Hs_eFjpv+W zwl>alj@jDkHRqVEtzL7E+1lzg=a^mVFZ{XF=0E3{?YcN~j@jDc&pBpmtJj=kwl+O; zj@jDkHRqVEP5+!bcluAgT9h|NnK8cdo!R5HahO@+wegu*;?sY)%`EZSc+M>G+BnZF@!I&$ zEb-dvHM7KPtJlopUh6ZXd->1o?%LwaOz+y_&#dp->NPXKYtu8c!E4hwGsA1E*US>1 z{!_2k<(oea#lh!_Kit|E&-CD&PW;oaF6E_OB5xbT$u5fAg^NYF)nh<4_!YuK2^Peep~W&gsNI{p!*@ta_EN^*Hd4k2rA? z|Kd6O#+jb@(^*~UZ{9&(_0`L_etR71!^fxoeBA2W$FqKZoa^()zy5!9neS28_l@QS ztT#u%zxe`jnmZ7`c?A15r$A5h3v@QuK!5WN@@iea`QuO=e6IMzt$p!K56=8te_E(xFJm2hj03D4%6aBl7i z|K_38r8z0@ujZ$$H&?aquZQ_Bahk&tzxglwHn&Aj^IUW`=S6?>U-D{QzWL)&9DJ_$ z!>xVy{q>*+=XBzqesw7?^(tTMao`^xapETa#dG$JGd=OAv%1hf=d@p+^K(x7_4z;N zw6BfBoYTHGK66g{=|9}&oc6WxoO9aO#(B6~-g*H*7NSO4^%dbKX!{BbA_K3DwV*1mYA z2j_I+pMG^IFZC*4>v7;8A93O){>5|ljWa#*r?a}y-+3ushs~kOxA}A&np?-Gd3M~I zbH}s!cbuDxSFh&f)vGyr^=iJ}dUN;uo5vTYIeqb)-?wjb{q!{NPiN-<(BJt0@@iea z`QuO=e6IMzt$p!K56uP&IO<5UvO(K2G8bYaBhwU|K@AdW%juKel?F{y*VBJ&F_fQT#xw8``EWRAbOe) zqO-Xn`kN<`SL^c4ABW=LbHyKS?Tcr6a84)w=~tKXQm^v09tZyM5hrfqUp!~uIMWk< zI;#u)bI$GcxiRP5UY{p(&h6Sb%sIDf<1^>np8msa&beJ1&pGFIZJg(v+qLnZb8gpG zm+8}6+xu(IxxLosoZHKP&beJ%oH^%qZSm)v+qKne&beKio;l}sZ93A^Xj_@`f8%1gb<*LocI$48vFiGT5&edA0|{OPPN^v`ot zue|0ts#m`A9M!dPnCGajjn6zs_4FTZ^BmQ+@to(Vu8s3NM|ExWn&+sltzL6qZ*BFO z=cr!m^BmR7f1abdwm9<~)wRW+=cul&Uh^E)wdtAXsIE=tJV$kH^_u72p8iv>*5#W& z4#mOeia*@i7ti$IoKF1HuP)`KUgc{&4*cUIPTa)5c+S3YrYHV%Ru}p^&%x(L=LX1k z<^uM!3x}BtSR0?tAHc113GnQ^0-QU?K)pKOK)pKmK)pH-!FuN;@bCNtaXME){LWjj z@5}{UdS))*(%HEU^mm?vyjquU{x}o|pDX@wYhOImgL69ZPrtg9mwJ`2^*Hd4k2rA? z|Kd6O#+jb@(^*~UpRM~~^udQBlcJQ@6X9{2bbJp;PuYl}Z;6R)jab7t|{^vqetYt#Ak zFFtMcnzN5j|EX8&^35NI;^1?|A8zf7XL@i>C;sVIm-14t^0giZ{_znfZsK1&XWux} z6Ms6Z3;mtX=5^RPVDkNfhx1@@=-e=TI!_F@&KbkA^T%-RTr&0QyfXFb95eOmd^78v zd&a->(8TGSH1Rt>&Ay$hMo;Ih(b+j{^mjg+yjquU{x}o|pDX@wYhOImgL69ZPrtg9 zmwJ`2^*Hd4k2rA?|Kd6O#+jb@(^*~UZ+=-`&B@BQ`B@yAtHq~zTilw%#k2WboSWOl zzjs_BqKm2j0jprMD$7$pI7QgMkS|9xX-@kI&>hk-Z{!4aU zy}sC;sVIm-14t^0giZ{_znfZsK1&XWux}6Ms6Z3;n}x zKcl?AhUwb!9oB2(FznXGXV{(o!)@5DjpzKowQ-(*v$lFothLo^_E=lJX76i#G+q9q zb!~Avw?zEOZP(Rna$cLBVX-!y!)R^#hu!Hvd9^Oz{BbA_K3DwV*1mYA2j_I+pMG^I zFZC*4>v7;8A93O){>5|ljWa#*r?a}y-}8LcYx*1>>A#il^f|1J!}K|5b?mj(Yx*3n_33lC{HM=hZE>d0VQulJ&tYx*PM^ct z^h}?_+H_8z!`k%sJYRXWF5modC=NbX{NdKVc%}#EbmE_Wbty0PDqrhy;2$4x;wJvZ zbM}ohJ@Kcry3pVA+T=CY*{*!&I@`rzuCuL;&s=9)8@IX6wlNVHd z)>f~%&bGFC&2_eGeXg@z{&SseZE@y0+uGvKb+)zbJJ;FPrf06Rt*u^joo#LP>UnMQ zYF)nh<4_!YuK2^Peep~W&gsNI{pwO)>Q%nhY;>1n-i|6bcXL{mKXLX^!=e5bJ z=Yq+%=Y`?WbHwoJ`C_>B+%Y_R9vRMa-+Z~LSI;j~ubykBUOn&3de1@Q-}BML>A7j* z_dGTG&VBQ%UOj(}&be=X)vM>V$*Xnw=8r>h@VVj-xAw&|JvgTm|MaU%d8t?VT8{(& z_=poX@h_gUZ=C6gKb_Tu{^?8E9OX5ADObMJm$Ehv)0eWgdQD%-=|9}2FJ)~!r!Qq~ zoTo2kZTzP%Wo>ntzLd4qYx+{I_32Bw{HHHvZE>bAWo_}NFJ*1@n!c2^>6yNiwdtI` zl(oIyrjO|KpS)U^Z~izG2cIkcaBE*Y(}Qz5@lU_Hl$Uyyuk|?akB>NU6aV5l`^K4` z_|sWk=x^R!y_##5Z}ZMLGzX1O^U=69H;rfW)HpY1tzOMvt5ealq_2#(wH{UHz zbKl}m-`BhP+iKtD#OY~%oX+OT>2Ka#UaiYFe;kT~&lP{TwJ)CO!8x7yr(a#lOTEh1 zdK~!2N1V8cfAO4s<4jNd>8vjFPao{{I-EY(>-9N(uxsNmeXwieGkvh9|8Sc=*tPMT zKG?N!o<7*M@&EbHIc;?rcDt@#(+9h@_34AX{HG6gZE>a#c5U&e4|Z+!nm*XI>6t#* zwdtHb*tOMb`j$`ssaNar%^!#2;B&rB{^?hj@=~wzwH^ol@ewC(;$J*x z-#F6~e>$rR{hdeTb=bK#^6fkv96BclpU%(0t#fto?7SVEJBLTTI-lpP*LiM_dUc+U z_31O;_YVKg{}HEifyD2;Ap3TX5IvnQL}%v?(cgJQ@@iea`QuO=e6IMzt$p!K564`s`)rJ0^H!820{0`qKA1ZT0GTqw;E9zWL)&9DJ_$!>xVsOb^cK#6SJ&QeNs+ zzSiTwKR)8bP5g`J>>Fo#;!kIFq2C$z`*&gTa>jkXznpQ;#=#l)YW5NTfLm!&sHyI`nNuFQkTDH09Y5tvjN!Rdu9Mzy*x{RO^;^`u<7*d z0k(R1Cc*koUaiYFe;kT~&lP{TwJ)CO!8x7yr(a#lOTEh1dK~!2N1V8cfAO4s<4jNd z>8vjFcmAQ*Vdw10xAXUK=v+R0IBK+% z>QY|nRle5az&}3X#7+E*=jO%iq z$G$!{<~sJ;@}2A0YvVB2vDe0Du4AA6!)>l(uZ`zi$6g!fxsJUy{&O9B?eqP0+Uhme zv9I;Hj(z#hb?mjpnd{hVi$B+~*H*8&j=k?wdgeOz+H}r!?6v8i`wnZXSL^c4ABW=L zbHyKS?Tcr6a84)w=~tJzKEK-3t9-4;fq#6&iJSNr&)GN5^u(Xe>O%kA*E=~(UUOe> zZTZf9y|rkwdtArdTY};_x0AMf9}Jc{*zbh^35NI;^1?|A8zf7 zXL@i>C;sVIm-14t^0giZ{_znfZsK1&XWux}6Ms6Z3;muM+~4K7Z+_+LnZf-X_sn26 zKAsu8{=>~PgV}g`W-uFP&kSa(muCjE)yuPx+3MvP$*p^Ka{ivF%ofM9mf7Na1~Xf| zJe!$Kk7qWs)yuP-+3MvP&+9++YF)nh<4_!YuK2^Peep~W&gsNI{pwO)>Q%nhY z;>1n-i|6bcXL{mKXLX^!^F@7bbdIHbr!VFDoSD9qwejgZOx!vr6VJ}i#JO`d)vNP1 z)vI$j)vNP4t#@uG|IYIir*l5V@BB~uPG8EUXZlhuot+~}f9H$Jt9AM2k3(_rx#ADE z_Qf+jIHwc;^s7sGsaN@0j|2bsh!Z#QFP^h+oau=_oz;c@>HE4~htv0Uy*{V!Yi+OF z>HAt+y{7N$^dD~1_q8^j)AzMD&eQj`HvZH1wYIv<_o%hiYx=&f_38V%{HO10ZE>dW zYi;qT?`v)Kn!c~K>6yN-wdtI`ueH@{`t(l!saNar%^!#2;B&rB{^?hj z@=~wzwH^ol@ewC(;$J*x-#F6~e>$rR{nJ-@<@LOmoVI+YukzwBeU)qDGkuk(|8SeW z%C+&FzRI<6p1#Vp)oc1H*H*8&&bGFCO<(1;K7Ey!|MXR^Eza~+t}XubRj#dG(^t7R zJ=0gYwt7up<=XU5AMEKr^=e(d`QuO=e6IMzt$p!K56s)R;JFgq(&hb{S&i7WY*<(Mu z)T{Hrt#?j1|IQB=r*p-{@4RvQb`Ci`olj0@=a$podFJwJUB3C_P#k=&_`|Jz@k|fS z>BK+%>QY|nRle5az&}3X#7+E*=j>%yC?=&za*`8;6*W# ztzI+7u{J$3$FVk@Gsm&Edd=L;=|A;qUB3C_P#k=&_`|Jz@k|fS>BK+%>QY|nRle5a zz&}3X#7+E*=jO#Lg`rd1gz7N}jje|Yd_}F9p zhg;{G;%N`-INO7bzdhLMf*o7EFm2r)`P+jnj@q!r_aEDu|HtNQ54ITgV2f>!^`AXk zrzL+Hi$nVrf4H@;T+@R=IX3lqQxz3#L+8E57@7mbRobTG0&7AMrSk9d9wLWvc zm;cQ9t}V{Y`K~Sg%=xa3<;?l6P0!5vu1)96`L2!S%w?bcQ?J(Ln?DZ4!RLxU+}an* z^kA7zEYpu=d8t?VT8{(&_=poX@h_gUZ=C6gKb_Tue$V9Yb?BMgy*@pYn~j5Kag5^at$Q|k{+?OR7RR&9+2VV~Ia|Fv z`jdU=NW`cJ)Dmv8vk>ecz)>NR~| z*Z0HD1GnBe;ru&4T%67o7r*ny?b|uz^mINsot;}wf9ILYt9AM2k3(_rx#ADE_Qf+j zIHwc;^s7sGsaN@0j|2bsh!Z#QFP^h+oau=_oz;c@p6?*9o+BXNo-cqy&mF+0=R4rm za|-b6`2{%lTm$@j-hsMIpZWex@&4-h2-bUU0{@<;AWqL&5WnXy*th30(9`o8=v7;8A93O){>5|ljWa#*r?a}y zf9pRyZhdaYt^e(~^~D{xe!1h;M|a%%>yBIB-Er&3J8pe?$E|9l)(3dp z`U8(!-{5iUCp>O_hR3b{@LHcbUj9?xE6&vYb@8WXxqat#a_O1Z&!ux-SC{^Iy+s6gdK~!2N1V8cfAO4s<4jNd>8vjF-+q4`x9|DK?fd_6`(1F{elHxi-x0^{_r-Dh z-ErK0j~ut(DaY;i%W?Z%bKHLK9Jk*=$L;sgar@nL+P^T(k$_+0UaTl?af9-PyOfBMy>ywt0Ft;d0Xe8h>H_!rOFH_r6LpU&z+ zzt7xftkY{pZ=Ox8D(m&s^){d-%*{PmIH7E_-4h z{+6(3&tvw!)<@IjKU&uo$KNXcv*$6nt!)-za$cLBVX-!y!)R^#{f+c*XU}V0zWL)& z9DJ_$!>xVsOb^cK#6SJ&QeNs+zSiTwKR)8bP5g`J>>Fo#;!kIFq5t;#>$rW-KW^Xu zkK6BpG{Z2VbU*RI&Qzeu66n5k3(_rx#ADE_Qf+jIHwc;^s7sGsaN@0j|2bsh!Z#QFP^h+oau=_ zoz;c@+wZUA_C5c&eg8jhzYC7r?}g*`JL0(gzBq2bJC57$k>mC|<+%NRIc~pej@$2@ zsps@{x}o|pDX@wYhOIm zgL69ZPrtg9mwJ`2^*Hd4k2rA?|Kd6O#+jb@(^*~Uzs;u{w>gO8HXm`^<|dBYJjHRF zvp8<^7sm@9=2QIry3K1Gw>ggEHs5jF=01+wJjijI6FF}4BgdnM`4oS@Zu2I`Z4TwQ z&8J-J^35NI;^1?|A8zf7XL@i>C;sVIm-14t^0giZ{_znfZu@%p6`y`yhnaojOi%pj ztS;(k2r2~6US|y;<(LO%-_LZwfp*>aGT3GZu1)RIsYry$M=ofe8+K{ z`IKMuvg=ZZhv+859C;G9nU)2}Y& zrC#N0Jr4ZiBTn4Jzj)5Rai%B!bXFJoZ}Ta~Z4TnN%|{%!xryU8PjTGlEar3dH}172 z^}5Yv9JhIm`P_Jm^--_ee8+K{`I zKMuvg=ZZhv+859C;G9nU)2}Y&rC#N0Jr4ZiBTn4Jzj)5Rai%B!bXFJoZ}YInZSL~8 z&0`+7InCoXzj@r|I*;4D=W&|@J#O=%KIgCZ*KMBkxXqa!xB1iKHkW$b=2ef|9P4qL zZ#`~vug7g3_F9*3{x}o|pDX@wYhOImgL69ZPybo3GcWZjU+Zz;A0KhzCjP~9_Kh<= z@u#!8(0`jJI&O0-$8DbFxXrm7xA~XjHWzc;=4FoC9L;f?ukkzOs@H8E=eW)39Jl$M z<2KiG+~$3b+Z@nwn-4l}b3?~%p6FVaZ~izG2cIkcaBE*Y(}Qz5@lU_Hl$Uyyuk|?a zkB>NU6aV5l`^K4`_|sWk=)cXU9Je`$<2E00+~y{Z+dRc_o3l7>^B2c$F5|e(YaF*Z zj^j4paopxUj@vxQahnr4Zu29@ZLZ|F&6^xw`Y@m3_wsE%gO8HXm`^<|dBYJjHRF zvp8<^7sqWb8vjF-{w<}+Z@Dk zn~ykda}&pHp5nO8Ssb_di{mzzaopxLj@ul^ahvZrZgU^UZ64&f&50au*?h`ekGjp3 z9JhIs<2HwK+~!lRb@}FxLvirA;t#j>#WOuPrxXA5t4n#QSNU3x1ONDl6F2cMp0jV9 z>4`s`)rJ1se9Cc~gE(&U5yx$A;<(LI9Je`(<2HYB+~zWl+q}kH7yX3m@7Ha<RUbb0~A2_K)sf|37>G9=vUrmi3*`MAQfhL5-kI(`*C` z#0^pDck@8dh6ZAXh(^&Vh`Sjvvsicbh*fuDz9~ zLwV@4`A4_vrDuHT98dbkpD(qGU$s{}9h6TWdD2b()pP1iXMEBh&wRoEaz5pDIR|mO zoR7F&&Q07d=P7QNa~8MD`HS1-T*mEkUSs;<%hs>U`HtJ=+{f*59^`g8Cvv--AGux5 zmE11pO>UQSC^Ihhe9FePxAJr-4}CWO=vKY-j1QgTN&ooY$Jf1G{Hnd;>7ac2$dhjJ zubxwHI^&c6c;*ZKm-Xe_WgYW&S>L=});({R_0Zd8o%D8DKfPVnRd1K|)_IS*uP^)l zx~$LMF6*|p%X;qZvd(+EtpDCF>%zCodhzYDjy&_~Z`}F$;@VqzI+TY#n}2kxUV6rd z&heyw{P|M5_*Hww(?R+4ktf~cUp=SZbjBzB@yr+eFXxGFmvbw(%XyaD<($jya{lFZ zITv%goR_&>&e7a1=WA}4b2qokd7RtjoX+iXe&=>M*K@m^_qkop0o^X=gKn2|L$}L$ zqK#{B<>^o!`fUEut$OJhA3DdA{_*Ea?c!JM6;B7{(?_0klYjM`dea%7^v5$_@V}fV zx?Rq#+%D%?ZkKZ|x6ApL+vQx$?Q&k`b~#6LyPU7NUC!OyF6VJ>mvcI|%lVz#Lx63)5SqJ%xo9A+_=XN>obGw`ax?Ro(-7e>bZkO{!8`s{-)1f@{+5Dqh z_0lswbdD$eqQdyPR9OUCy)IF6Ufs zm-8>T%ek1_<-E-8a*pP9IbY+wci%TI=W%YAb2_)n`JLP4T+i)t-sg5X2Xwof54v5> z4b6MPo+sM4_Ew$_<)P2!AKj{#p7Eh`Jn0{QzSJ&$)n4&*P(FR+NjLdd<^@kxI? z^9BFQd7|6p+{*28p5=Bq=W@H8f4N=G#mqe9{XCKR-pe_f+vR+XdC~RjavtY)Ij1x8 ze(!L~$a6W@bGw}Pxn0fy-7e>YZkKaIvu?HLi8ijim8U~_=(G7px9X*5eCQlc`p2Iy zwToZ1S3Dh*Pak>GP5#w$>P=^S(jU)!!T)le=yo}`a=V;oxn0h=+%D%|ZkKa0x665% z+vOb1?Q*`xJlj4GFXwS?mvcI|%lVz#e;yWI0L^R$0!^IYx) zx?S!Ix?S!Ox?S!Ux?S!a8lC^f`c+(eD^G{=&}Z|HZq-ZA_|Q3?^pF4DuY0@rReQzL zLHYENC*9;{gv?bpuO`Rbub;~J?dck%zMR^24J?daQ=RN9R{4c-nuyO6JJRQnIpUpqIRWCi`L+5zXKmL5FUHq!O;_0A#`pA=R z@~@s#Z#v_X{&?mK{+Hi(@SXB3zvesTU^>iq%E9!R@05e-Hs2`+({sL44yN;bryR_$ z`A#{QU-O-EFu&$IW#jXmvgPMHc=R4(K_0D(7!T8K~%E5Tfcgn&1y8OPw z#sUxAAi2oE`HTs@pMo=ea`rL>31<+(sSxfXMEBh&wRoE z^7{_v0k*v}53oASJix*9nR$SN={EBK2h(%r0S>0~%mWR`DY&BVD-*Cz`^*;Jix*Hnt6bO`E~hyhmC7*<>^o!`fUEut$O(t zA3DdA{_*Ea?c!JM6;B7{(?_0klYjM`dea%7^v5$_@W1@NgZZ~x<7?*G4yMD*vmH#I znP)qgZZpqzFg<6U?O;03Jlnzint8T^`8Dqw2lH#@*)~4&Y+HWj*$$Rx=GhLGf9BZ^ zR`1NS9gNS+vmK1*%(ETLugmW{Y+QRQPlxi*XY-G4)l1L#&^ey;k3U~(7r$z+cseMb zKJuiS{Hy2Go6h*8Kc4x5|IB0G|1Qkm<;(8~n8)6~3p0;>Fnwkod;9s!V;@Y+<^!8`s{-)1f@{+5Dqh_0lswbdD$eqOh$StnW@W}WC@`pi1f!E~E-qJ!x<>qH0BdDe*z=GUwf9n7y;Cpy^pnsuU$ z&pOeTpLL>x<(YM&gXN!fqJz~t>qH0RGwVbL^J~_L4(8Y8_Z>E_y_Kg!dFZqGN4M&w zXME@!Px{B7FSUzbwO2eHlusXd(oO!=bLvfJe9|A!e8GR#VRwAZ`s~5lJL|AJzGfYE z$JeaG-ph|}vkrSOJ!c*EU^>q_?7{q+b=ZUNex4h}wYTzgC=Y!$|L9h|^o$Rk<4OPc-^bUz zE&Qsz;_0A#`pA=R@~@s#Z#v_X{&?mK{?7Lv>?7LpvybRtd1fEc!Sc^OqJ#N0`-l$4XZ8^t zjOXklI+$Ox@9SQE{3@=!m8U~_=(G7px9X*5eCQlc`p2IywToZ1S3Dh*Pak>GP5#w$ z>P=^S(jU)!!GGp$_PH_hHv2r8d7FdjF!MGC(`V*w?&U|fnYTHZo-=QAFr8=K=3su! zyv@PLxAJr-4}CWO=vKY-j1QgTN&oosrFQYF_KK&2^64W_y2-zKPQB@jPx|ATFZj zm|wFGcH^@TcFWH`*n{PneXs}1Kl@-0=GW|lJs6+a2YWD{vk&%Qe$Bq+d-?IJxb{|_ z4&|ZG<{#avm!9#Vb3ExEf4dHeb~YLntiYvpM9`f ze)hp0EYIwNJy`zP2YWETW*_Xq_{=`ogYlewum|&N_ATGbk6*>LxAJr-4}CWO=vKY- zj1QgTN&ooY$Jd=dziO{|Iw(K;gbyEi(oO!=bLvfJe9|A!e8GRtacsNhe8;wT&T$+} zhmZch-7$UU9LK%<=r-p#4yNav<2abkbB^O+e$6?KgZVY*I1c95oa5N|oa5N?bB^O+ zdFC9)!Sc^Jj)VC%=Qs|=XU=gPjOU!=IGA5^?&e;8{3@=!m8U~_=(G7px9X*5eCQlc z`p2IywToZ1S3Dh*Pak>GP5#w$>P=^S(jU)!!GF$4ZM)|D)V6odNgYgwIVW{6ede6h zz5M7l=cEp%=bV!|n9g%f>R^7&IjMvBHRq%b=GUB)+W4H4+VXQw>R@^1oYcYc&$+XM z`8DUH4#sEBNga&moRd13UvsYQUVi*4uDz9~LwV@4`A4_vrDuHT98dbkpD(qGU$s{} z9h6TWdD2b()pP1iXMEBh&wRmu&LQsK%ImCncHRnd}<;Sn$+FN-#l!rc>e{`!}dd7#&@uYwJ`7(dMPF?(}z2fPh{G8J~ zW#maW`B%@WH=XfGe?0RA|2gNo{cz6zZvUKfz6aA`&iNippE>7yFF(4?Ip2fnIp=&2 zrt_ThJ(yo}&i7z`%{kwL`8DT!H$LZlxBQ&*Jy@PE`ETx6{yFD+;{2L(z6awo=X?*w zbI$o5%&$3@eJ?+L71!R%)1f@{+5Dqh_0lswbdD$e_KK&2^64W_y2-zKPQB@jPx|AT zFZip&oV;~dbu>S(4ww$=fa#--Q+{-tdnyj5r#i&xtPYr8>VWyB4wzpwEv}Brs{@vY zH?aKvgT?$mSXp(za;O8ATOFtT)L9&t%Hvob+&BNUsd}|FJ~W6YZQ@U}+C|ISE1nL@ zr;j}8CjaU=^`^73=`TmV$UXPK>~ntZhdCIRxd-N89OoXGgK?jGVD9Bdx48%AU~Qdy zU=F6i+yiqkZRQ@BgK0MRz#L4=xd&$Ba}UgxpL<{qmS^sPIavO=2j*Z}&OI;(<1_cb z9E|7O19LF`b8pYR{P|lK69DebN1;SOy}9BcQC(ZpWeazn&qxH*{63fzhD;YxY&%%a32hwYTzgC=Y!$ z|L9h|^o$Rk<4OPc^QCt2tM-bggYxMkPrAv!dQQFRj8FRGnJ@UyKG^Mtvp;tG=j?+$ zm=3cK_F($VKG=Kt(QWp@9!$^K2YWD`XCLgr{F;5R2lH$8!5+-7*$2Dv*$2DjXCLgr z^2|QigXN!num|&N_Q4*E&+LOe7|+=UdoaId-}1fu_*GncD^G{=&}Z|HZq-ZA_|Q3? z^p8JZY8St1uXs8rpFZ-WoBXTi)SJ%uq(7edg8%F@-*(OZ^KI|!Ge4LPv(Nls`piD_ zd->6A_L(0{&)H{wFr8-zU611`N8tcKJ$a+pMB;B z^K15*AB@lJGd~#5*=K$*zvf)Pz5Mu9Tze}|hw{*8^N()TOV9YwIiB>7KVNDWziO{| zIw+q$@}!&mtLN04&iJH1p810R+$*xrjk#}RpC@y#$iZ}&dqobW&uiZAr{2qtZga25 z!StMaMGmI(+$(Z0zvf<%gCFDTV1CWLA{(E3MYjChD{`m_ulWz}*xh4q_K|n&PO_i)pWgAgtL*i6><+WP z|Ll(E8~w@e`o24M=h>UR@+(eGccJ}nzv_6#sYM>?^nY*Syai z%kv-p`a72Y(>~*l)%&jh)g9yW-v5_7#`Ayv<~zp!?|thXYgci1r&ZqFY2|TuTKQ*g zW9xNyT72A{7EgDl#oyg&waZ<1wO2eHlusXd((T;M_Rv$k>5NbMB+*TL4_r(FkIlb?1SY^{FUwee}! zmY;SVEYGy-;Imf$`a4$dwClw2nRea(?eLs-9gP3f>*%zINGLQG3PHLHYENC*9;vPxYoVKIxBVzTlr<=D>=Z8>_rIv+|fr zE5A9m>NWQkA9Hf?G*=gYb9lAO++OV!PY31GN1k*$b9)ax)tk=vq(7edf`5K#S8;QD zl{dFno-?=i$Zu}1dd=;{$J|~#&F#hC++OW67h8M9(?R+4ktf~cPfzuxGd}5$XTIQn z@$1PY{^U~r$tBN|Oa3R9dY@eQJh||Ea^e5v(yk|$_IhrdvEcc6(dWrUw9 zbbfNt|H;LdCl|jq?s-yq&zbUg{*>Qysd_!H;^R3MPtUjbKc0t&zvp4?6;B7{(?_0k zlRrJxo6h*8Kc4yW|M5KB_>8+PKjU%p%sAcrGk&+;8Q05a#{2S|=fLux=fnEt?wQ&v zo({^Vk38une|oAno$*P3Jo5|x{F>+C#^*V?<=s6~o_Vfr{(0VRz4IJiKJ$EDp6;HB zzq@DZhwci>FY)|RKELG2FZuIJz4?Vte&Ly4_)oi@`TO;FZXE1+GCCaWIWz4#*z;#} zJJ@q+^gP(}YIHu>b8PfK*z;}Lb@1bPc(CW;v}@zjt}Q?9I#`}**TM2nyAD?GwCiAe zrdSQ*&!6&pE>*ARReU_h;_3Mo|Ht$2)a!Xzd&Sd1`Sg(| z-Q-VC^`5u31!;>HX{CfOdK5>7qEAM@yJpR6y-{1Y}^*#_E?+Nkrz7hY&`^L%d zeWUh@r-Sn8BTu@?pPuSXXMEBh&-}tazaH;Vr(S=rEAQ`kdHj7ZzrXv{>wO?T-V@^K z{UQF3_l=X^`$p{*PY31GN1k+(KRwl(&iJH1p819U#V^l|+V$j8{>dfJlS}?5mwKOE z_&mArd~)IMxly~GT-xioapInb7k!>wbbE5q^T|c$Cl~!aHXgSE&h+^;i=d2u=a|lgYxMkPrAvUp6X3!e9|A!e7QaktqByjR#16s z2<16z3yP=^S(jU+K!au*X ztGKm}%3JFwkF}2STkEJ^YaQ{i))7x@9r3r;QM;^7)n4&*P(FR+Nw>3>^3YSg>5NbM zVry?b)nd_Hx!<@pMo=edI|u z`O{Oq>5NbMubn-u<*}Eu{PuEIuf3e{v6nNR_HxGGUe4NO?``cB zPY31GN1k*$dqp35syChSNq;=^1^@hVrn9)So|Sh7v^?i*=p(-~qt)vyX?&b9ji5pf=;GbXGRoq$C$~&uC9%og{@2qO|I;$EV zXI10rtZMw7Rjpml7S~?!bWlEhGP5$&$Z#v_X{&?mK{`sX{#qC|H zyuC~1v3IHb_AXVgy-V@2cPXCsF2rP^h$S?v{12j$a8o^(5VqaJ#yH=XfGe?0RA z|NNRc=8ZcmQ+a1-%5%=vJn}npQ@zgO#K#$(csjcie`k7Xm$N>#S3Dh*Pak>GP5$&$ zZ#v_X{&?mK{`sX{#hvx3yt6*#an`5&&iYjE%jfJ=e4O=(r?Wosch;wNIh$2`#nVCg z^pPjsbN>b2GvA8UZ|v^E%jYlgMU zT4L=LPY31GN1k+(KRwl(&iJH1p80}*erZ>6Yl)S&mRKHZiRHJJSiRN~<6|u`p4JlM zZ!NKQS^KTM;_0A#`pA=RXRY#~r+U*FpY+EwU+~YbS##UCwSvl9LnzN#TX^KR=1{%X zBI09>BA(VR;%`l(c3JDFz2fPheEP_fZt|z6dea%7^v5$_@Xs&pDsHW#^42=aW38k7 z);g-!T1R}Wb;Q$JNBpgI)GljNwO2eHlusXd((SCJJoHp=I^&c6c;*-W`8DrRx8lxH zSKb-x@|?5RkNnPLSFf|$@o|Pbp3Zj1-&ye5yJS9$Az<*`24^VYgy^;%Dik9Ed)TCa@1^~&01y|VU-r-Sn8 zBTu@?pPuSXXMEBh&wRoECBHsw9tX6;yl0(?R+4ktf~cPfvFRr87S1k7s`2pI@)|)aT#r5`WdD{BxH) z&t39Acd7Te3!mpNJfFYtfBw?0=P&Jj{-VS47k!?;==NNGxufW!^K%#dpS$?-s>}F# zq4@atLgmNb7s@lfzfgX^L07%gPhN=6^q&{vIsNK|_)mX(p>|C_e4+M=r-Sn8BTu@? zpPuSXXMEBh&wRl@zvg{o<1_BI{EWxVGvoB7{PR1l)jQ*Q`OJ7xTYmoDZJzl%_)`9# z`<+|w{M}qW^Y?Ul&fnSP?=Ix}p}VW=pW^wYe16H3Zt~~X{9Rt1@yRbd^9%p{n)j#| zi_d$=ia{m8KK2I2)84@N+Z$NB?B%Sz;_0A#`pA=RXYb)dPxYoVKIxBVe&L^A&U6-c*0b`? zfR^W+4SnQyX0&>pC5?|Wrtx(4H2%({)-GpNYp-}ZD4#y^q?`Qdsor$PC;jovFZ}aM zyNWxjT6t$x%j2wS`JGj*UT0O~NkcseMb zKJuiS{OPIQbjBzB@yr+e^GmymyW6Sq?sh7VyPeAKZl~&Xw^MxF?G#UUJH_AKPPNNj zT(ws`9h6TWdD89N9re&tz3Gfk`s0}|_~+NmWAAfv=7IP5IrGE&T%CF2ecsM|@;--W zo_U|oGylBL?U|R}=lRT6?{nT=$b~p#pjoJekq?{^5mEN`K8|c!Y9A*%oqIgOS_8Cy7QKw_2|tr>(rZn z)~~nTS=U}Zv);WtXB~X`&-(bbYu3%Tz2f<$e16H3U-IXddh-jP{K7N8@XxP#&Oa$W z&&em1pXcY3^2~E}_Z!Uf_DS{5bNESo=J~ul=efQ7=Xt*E^4mfAC7xf(=a)SBC4YXY zH^1=7FFf-F|NPRf;`4WH%g^7t%`<-oH~;*7d{Vvhck@Yn=I`l~c+TJ1C-L{&K|K%s z)>Gq4JinArA9>PE{`^vJI^&c6c;*ZK`8DrR8=v=(EkExkn`hozHvhcOY`ycIvwY_L zXL-(h(M$Y4udWQo^`iU&^9!H+!ZTm+&oAvNKI@oUe%3cP&#ZfH z{#g&*dS{(<`ONz1@|<R?5Z?N^wK7{2n`xBPu>|0p=v!7wx<+nidOFX}n z&o6oMOaA;)Z+_vEUwGyh{`vJ+e)6B%`0VT0^0VJ#^UOYw%|H7?w%*w{vV3Mg$?}|i zCd+^JpKQBkU&^*uJinCBFM0Ay{`^vJe&Lf}c;*ZK`K4XOXCKa%pZz(TXZG!E{@Ks7 z_0B$@ zu=nB7;b8B{qtC(KpGUWYy;qN(2YcThoe%aNKKdW*{d~sJ!H@U(gT2pBKiv4VYs*i& z4wh%yb+G)?u7lM(?K&8rY1hGcPP-1qfBNCUkMER&y$@I3dvbZaKbPNob@h7Rj*s{7 zczQpN|KolB5u31x8Li z-*;>E`ksxC@7#F${*C|Rd->$|y8ajy#wY#p%rE@& z>oIS0>NTHJdGkEwG5=G3^Fq~Yz9>HCk>Y87DgKZ7sFUA(RP7Z{2j$a8o^+ExJ=L4e z_@qCc`GtReJ?7a?z2UZ{G_7sbasQasHs#s4uMb@H2!s=earpnUqs zlWy{-r+U*FpY+Ewzwpnm$8-MF>-k@Ke;3N*??w6j9jRV_U*hBMPCWfRivQ#9*U9hi zSM3!~2j$a8o^+ExJ=L4e_@qCc`GtReJ^n7AdOiOu@9#o+{Jki@za!P_?@N6A-HE5a zNAZ9B{W|&m{i?m<>7ac2$dhjJr>A<;8K3mWGrz8XzaH;Vr(W+@mG|CN9`9r2_nub0 zFQ50f_;|02r}w@1Ki&^de(#61S3Dh*Pak>GP5$&$Z#v_X{&?mW{`vKI?>+T;zpA|V zuJU*vE5G-&>h=B>AMbVX^u8DW$NS;Q@BOg$il>9}=_60N$)BF;O=o=4AJ6>4zw!0> zPC51ZeyP0gn)3MGDZlTa>h*mTAKy*!^gR{-$M@IC@B6Fvil>9}=_60N$)BF;O=o=4 zAJ6>4KffN|m8V|cFO~OQQy$+t<@X&_y}pm)5NbM~Gop zv+t#P?T3kveKPU1e< zyj6buy_IKtzm?y<=<1z*a*NOOpIbbqU)|zA{q0t}?8mOX;_0A#`pA=R@~5YI(;1)i z$1`8>&oAvNKI3l7&v@KCGfrR1Kl`GqcgFSdneo0n=Q*(a=lQVhvLCzlil>9}=_60N z$-jC|z3Gfk`s0}|_`l@WITvuep6BG2pXcZ1ndj=}ckZBi=Q+H5=J~ul=efQ7=Xt*E za^4}o#Pdt}{E{c#Ycxv z%V++cF3Woi*;hA6f=hwVPJuN=(Ax|qm z?uR?=RA$iy#G9n=e!p^jsLtaJ#BnBPn2Kc`K5e*$&+sK=a+i( z3!nVLGr#c9FYPKm?~Pl2-X}NDyk~CydH>vc=e>0K%=_x{ocGw}Kkv8OF6W7AuXs8r zpFZ-WoBZji-gL$%{qf8f{4ai4*E{{tdSB(O1D417VEL^ZRwx94K3IP1hSmFqmz{OS!`V7x zJgq;*|FK?q%2=<9hA>6dD2b(^i*#;b0I; zdF$-uvHo6u>+;oWy*@tH@#ATIKmL#X04Klw0JT><9h6TWdD2b(^i*#;a|~`^7gTm$NrY`+xJqv_QS--KACvhKNJ7Qew&luew*4Wo({^Vk38une|oAn zo$*P3Jo5|x{CeyoI`!JGQhEDW%42^^`R#kDUi)Fj=w#))%&2?sLd5@%&OgzvRg;`SVM?`Grq@;hA6f=hw^wY<$*P zw*0KWY@S({+5EF!v-Qq8&hnY{o#i>}KFfdBgSK7nOUWz#GC(~7KUBBk<^7n)j%U&wI$0pZAl^Gw&^%f8J--uX)c|zvlgC{hIfp^=saj z)-UIY@=H9wl+Q1D@=N~wQg43YlV5n|3;y|~UB&0Uam&y9=ZVg9$$6sfpL3olzm(4}dGbsC{8Ddz;ger@<`@3?HQ$vRpZEMNKkxsW zXTA$I|9mfOy>FQFbn%(*i{&}r9m{{dN7k?TPTBT~=a=&NB~O0IpI_?DFMRR~&wRl@ zzqG6Pe3xzc`Ci*R^BuSO=lgE!o$tQoGv9;DbG{Ro|9n4gyPVg{FY)|RK7HiLFZuIJ zz4?Vte&Ly4_~+Nmv+Z+o*2VVuIqPNnT%C2aecsOc+K%g4ciZtk>v8)Wn02~+KFs>v zJ~!NN)A$n4FXi(~p8S$Ozto#w_~aL!`GS9bX;<-C$K3L>zPWj3-E;HLdg#_W>!izP z)=!t`tg9~nS#RBTx!)$g#Pdt}{E{cXzGy8v* z=j;nw{8JnVXWsD#|FtiA`sM%Vlg_{Wiy!$#Pv8G9-0>&HqS1cP##Guf1dC-~O%dSf0P|&7ZjWfBhHS zv3kGmciu5R@Ax0zF`mErm)tS_Kkmgl)~@1j`mJBG<$vG@zhv`#+$a5+r{#am5B!;} z_q#sgOP9}2`wL&XJb%+a{?g_D{XgZ)wq1YpXMNeWS3Dh*Pak>GP5$&$Z#v_X{&?mK z{%`+DA9pnQJKz4gr(gfO?)cY!%x64(v)^#X|JgtPjHkc)m)`OJ>-T)-)2Hun$KUc# zKlACw|HI#Y{_RKqs?U1*mS29yU-;)g>*)u5%pL#JfB0EXf6=?%@$Y@>Klt?f|A&t~ z<=^=o{@~O9`g8AC{0+bCj+OtepLECaeEge!+vb1wH{7v$KkIkgF+Sh>EAAN2mw&(= z`SCyT)0gL8`o>RN z{y*nSKW*Ffsek;_w!Px%pnUqslWy{-r+U*FpY+EwU+{nR$Nz-&>-&Gp9c%A=};c} zl%H7KVNDWziO{|Iw+q$$M=VB@~5YI(;1)i$1`8>Z+yMa4}IXXeEfue z|AU_8@9RGOgP!I42mSRAdRBkN}w(G4v;?>(;@pMo=edI|u z`O{Oq>5NbMthAGJ4s>5%XAsXx%I@kP)251s2*^sm41rGCh-`lopPR{8p~ zJoR(=>;LL)T;S7q!LxCMf8$HLifeD>=};c}l%H7KVNDWziO{|Iw+q$ z$M>E~lRrJxo6h*8Kc4x5|5yI{Z#(Z=@BD{8|Jkp7?Hxb=4WIw)U%u@f|B*L){j*>H z72kTw{I*~C`e&c}o_G8{zv=bQ-thbX?uq{&|Iq87{TF}jzd!hUzvA`Je(LwnJq2?{ z=`+6J_0OKZ%^iR7x4r(^fBYWba^he89j|}(zrEi#A1waIKJral{^xw=-#%ELxA~jj zbg=yI@a}i4-VgnvxmRNH;L?DoBwV8^5<>6f9DT=-n008)NlQ~<@q%q{&~y)3xDb7ZM#16{XTEoE1nL@r;j}8 zCVzUWH=XfGe?0RA|NQ!sU;oOD|Ly1BdCPy|m%sDo`2|1yT{i!--}NqA@2kGyU6#)) zf6}`y&)@dKyDtAX{F-;&c74NdeAjKScz!9LKJw(3{Q0Hc{K6-{@XQzd^Gmym|K<;W z<(9vF_d9K#ANPCSY4iW?w|}Rt_lLjk70c(R{r*=h&%g1@U$OlE_`mmxZP&;CoL6jn z#q&$~{E{cXm>JK0M zYrf_!o_)yQ_(KPO=C{4Yv+wx_fAHYH^bg+R*(d$bXKno5e#RXu|CfI0XP&q`Z}`;D zI9UEK`yXF-uzJ7k*W58a@Bf2;;KcF#t~cH>{;&J8JJzn^zw%9Qw&nl)N4?qR`JevD zk3KE`H@?@8KCRxr`{_UOG(K_ti7N7>)!Lk>F^al`{x`?pI`P1{+)yA z_Nq^MuY>9NTmR*IA57;D`J$hDF#UhR|bw{Nm>iR_}LyzzYZC^Hx9M#e?zu+rRIQ@&7%4?vAyqxb{|_4&|Xw z`RP`@N6!ZzI>(d#@#jnJ;#chzPY31GN1k+(KRwl(&iJH1p810R@BPw0cG~N?@hx9_ z$DSwe^Dpk$bLJaAV&-ecQ_r72@%Qi8bLq2x|DQN<&#OQGOaA1+o?}1b-~Lkvd%k_# z58koo-nagbZ#Z$!!x#Vh7aT19`G0=qoBTbR@^A59}=_60N$)BF;O=o=4AJ2TjKfnB4F7EGj<^3HmkH7Eb_jkW~y${64dqO&p8(ULJqn%kS@g^?DzO zkN1RldVh$&_lnx(eWUh@r-Sn8BTu@?pPuSXXMEBh&wRn(eALW|zF?lsya#Ol&3p)K zUd}uTY`)I?32YwEyb5go(0mJQ-p@P?Z2r)E6l|W*d=zZ{(0o*J^HG&I9|g-}J_?rK zd=ac(^HDH9=A&Rd%{#&Pn~#FEtGM~M%A1!fkNLXto5!nO^Lz0z?-x(=f$=v_Si8(0 z)?V>+P(FR+NjLe^Q@!boPx|ATFU=p;uI3W8@rsrAyvj#7AK`q2^AXNRI3MABg!2*3 z$KuT^D&M?fJ}Q%sa6ZEM2y)yo2)&&O12o;Jho|J6qm~=N+7PaNfar2j?A}cW~apc?ahmoOf{E z!FdPg9h`S?-obfSym6Oz;&}(>9h`S?-obeX=N+tFzPtI@clYu7@!fsAetdVseRsos zcf);m!+m$deRsoscf);m7xz6|dEeb|-`#NE-EiOCaNpf<-`#NE-EiOCaNpf<-`#NE z-EiOCaNpf<-`#NE-EiOCaNpgUaXnUChdVExwo7_2{=H-q(a^J%dDZ=MY{F3i8d#*2A5xcN!A`AN9>$>Qey zDsMgzmd89HEWi0fSiR;aVSLO_!g!j8gz+~&3G1K5_1ntp&*kA=`St(mH7?>~yu{PE zGe0T6ac6!KZho?OIw+q$@}%1t*AG3_o6h*8Kc4x5|JAP_n_Iq*yMJBgmal$U$I(yx z?XzA0`&(}v0rn1HeF64vVBG=s&R{(P_AX(a0``t!{Q~yxVciY(u43H{ZXKt%b)3pu z$ARUsjsweY9S2sgbsQKU>o_o;)@xw=t>eJjRovhD%6kVWk9ULeduOO#?-KFxjuB7q z9@Y)z_pVaATE{7#4$7yGJn1HXda5^_@kxI?^9BE_Uq7}6cYm*IjW6%K%jF%McW~ap zc?aiR@qZO-a96+b(fmXHnwQ9T^A+_6^BDCL^BeUa^B(mp^C9)O*1PpX^D6bv*1L<> zpOvql%TxcCzj2}7#tS};BRm^l_&4sftGIcI%A2n!k9myp`!=s$-{$f0Z5~hG=8Zew z=C!N!ZtW6J2j$a8o^+ExJ=L4e_@qCc`GWt|uYAlqeJ1bVyo2)&&O12o;JkzL4$eC` z?~2o;^0b2U4$eC`@8Gy)yo2)&&O12o;Jho|xXU~7yo2)& z&O12o;JkzL4%ROFg7lO21;OnLg4-7aw=W28Ul82BAh>-&aQlMb_65Q13o35EP37&w zf!h}Zw=W28Ul82BAh>-&aQlMb_65Q13xeAh1h+2;ZeI}Gz96`LL2&zm;PwT`}AP_*8V+M zf3~j=*3a$tgY|#=0Ab_8{y^Axv2PGI?(Cn0jXV1%;r34!w|}zo_D{m{*gpx&Z~r8$ zUi&9ueC(fu@w878#^3%)SpO`p-&S6KE)Va@um4xCaS@+0ULHJ+JNrN7H|}az`zMR1 zgYxMkPrAvUp6X3!e9|A!e8Ky)yo2)&&O12o;JkzL4$eC`?~1pFIq$^t4$eC`@8G{k_w!;@Vz$nv{oD<)>lw(l$Ov^T*#iUi9~lceShYINBwi z4$AlUPM&m=KRwl(&iJH1p810R)vunPdB@YdgYyo~J2>xPAc!$~*DAgYyo~J2>y)yo2)&&O12o;JkzL4$eC`@8G;E-ru{t6VE$1@8Gu*Kk0sM5$@a~+_^=#bBo2>f7Q7~ zae3OWC4c+4I=84y=N944EyA5!ggdtgcWx2x+#=k$#Z&%qZV~R>BHXz}xO0ne=N944 zEf#N|SmzeSJGTgTZV~R>BHXz}xO0mz{#U=+8>Wp{+&-~<YBb<+LKEnA3=Odhta6ZEM2u`}%5E z=evuigYxMkPrAvUp6X3!e9|A!e8Krqhe1!86&PO;O zi~ra;{rmpR|8LIey9Yx*ng7mx3vl;fz};QM_+aQ6kl z-4}GqJnjpEyDzAC26wL-+`VdW_o~6&s|I(kTJgqR_o|6^uNvIF zYH;_e!QHC{cdr`Uy=rjxs=?i>26wL-+`VdW_o~6&s|LUDxK|DCUNyLT)!^<`E8e*4 zUNv!f-1`J~uNvIFYH;_e!QHC{cdr_(U5&fE)0grN&O12o;JkzL4$eC`@8Gy)yo2)&&O12o;Jho|-@CjM&pSBp;JkzL z4$eC`@8G=SWA{(O-9HI;|0LY~lW_M>!f%-SA$yPN{>k%iANNnf-9HI`;N$+u;*GoR zpA_%@NmzdOt-;+t33vY_-2Ibq_fNvzKM8mLB;5UzaQ9Eb-9HI;|0LY~lW_M>!rea! zcmHJZ#$ESMig*7c-2Ibq_fNvzKM8mLB;5Uzuy!@>@{Xr@2j?A}cW~apc?ahm{9|{A ze&spCn0GYEJ2>y)yo2)&&O12o;Jo8w_w>Tu(+hV`FWf!7aQF1W-O~$qPcPg(y>R#R z!f*Asr?+_Hu6ugLyQdfKo?f_ndg1Qrg}bL0?w($_dwSvS>4m$e7w(>3xO;lx?&*cQ zrx)&?UbuUD;qK`z-ni?YUh(efg}bL0?w($_dwSvS>4m$e7uK%EUEc9D@8Gx(_xCRE#Pbf$J2>y)yo2)&&O12o;JkzL4$eC`@8Gy)yyIi{nZw;@4tJk9+-iANQHV-Dh6Bao2t3;@xKscb_@jedciYnZw;@4tJk9tX++}yyI!!!FdPg9h`S? z-obeX=N+7PaNZSf+~u8k-obeX=N+7PaNfar2j?A}cW~apc?ahmoOf{E!FdPg9h`T? z8+Umpo_BEG!FdPg9h`S?-obgt$A0$#?sp&He)j?HcOT$>_W|yAAK-rX0q%Dn;C}Z3 z?sp%GH}3k~2l0OQ0q%Dn;C}Z3?sp&He)j?HcOT$>_W|yAAK-rX0q%Dn;C}Z3?sp&H ze)j?HcOT$>_W|yAABs2b`rQZde)j?HcOT$>_W|yAAK-rX0q%DnVC`z$y)yo2)&&O12o;JkzL4$eC` z@8G;E-nh#<@w|ic4$eC`@8Gs@ z1NZwlaKDdJym8m>s@1NZwlaKDcO_xm_-zmEg=`#5mFj|0E<@%uP%zmEg= z`#5mFj|2DnIB>s@1NZwl@Sk}6K2Gt*UB8bb-tXhU{XP!d@8iJzJ`Rkh`?TSH9|zX1 z#$Dd=H1FWNgYyo~J2>y)yo2)&&O12oiZ|}^PCW16yo2)&&O12o;JkzL4$eC`@8Gy)yyIiPBL??7VsO7B2KPH+aK9r4 z`<<`mRr(z<@qR}P?svrCen+f$y)yo2)&&O12o;JkzL4$eC`@8G;E-nh#<@w|ic4$eC`@8GG@5V3sJq7=E-lbpkdsT41 zw^+P!r+n+?^7#D-W#n(%sn_pEh~wk;BVasRzr)|}M~G`z@%eVx^7BoxdFESV^UpWP zlj@yslPB?+ZH`Z!b z<1X)bns;#C!FdPg9h`S?-obeX=N+7P#T$2dC!Tk3-obeX=N+7PaNfar2j?A}cW~ap zc?ahmoOf{E!FdPgUGc_U-ihZOoOf{E!FdPg9h`TtcID&Dv8=x{_p-jvoXqxznXB1; zGIKcFe`aoH`_;_(JgL9UT+oxoo!_6WfA+hyr++?vmljsOelAb_U;f6OdK-86H169h`S?-obeX=N+tF z`8aC|>+h^Jtnaf1vHfAzCbpl4hFXX6h4t6z<~yyI!!!FdPg9h`S?-obeX z=N+7PaNZSf+~u8k-obeX=N+7PaNfar2j?A}cW~apc?ahmoOf{E!FdPg9h`T?8+Ump zo_BEG!FdPg9h`S?-oe^+@o~Q+e)#Xa{QORqaq+u8^A+d!v*2%f_gC(|rceG;@4Wji ze$jWm%YNUz*Y~{Z`F$?sf9Ds!+xgut_!qwY&pyBB1%Jo;|LpTSU&R}D$~W%hY23-* zxKnTA4xh#yo{ca3FXL|G|M>^M!r=r-?)>faVLM{PQ8sgd>VInHtz7h`gIw1 zrwmW?4$eC`@8Gy)yo2)&&b#7`ySx+6J2>y)yo2)&&O12oVC~AsnPa)-@4J1$-?`=cPk-xg zyVW1Q{?&i)RzG>qpZlG+`p+Nzs=t4$U;P)ie{ie6z1@r7bL&0x_3!b$xBf1C?Z0+ zyRG+)zw@sypTGSv&z9%=|Kr>8fBGYD+;)BJSG;lCE1nL@r;j}8CjaU=^`5pf= z;D7b2ahG>I%{w^n;JkzL4$eC`@8Gy)_k4H<=N+7PaNfar2j^Y!#$Dct=N+7PuzGn1=N+7PaNfb%^^%Vtw*G$6d;F^P z{ZroZBey?%?s;;$9~20FXjJ^ zU%2&t)8GAh%jci{x9_z)zxA)a=kkBk|MKqJuJ`%Sci;AkH|~^g+{x3plfQBI=ceAq z9X^daJR5iTU;TP%+}*w7Y2Lwk2j|`K{ox&)cW~apc?ahmoOi_=cX=nCcW~apc?ahm zoOf{Eo$_yY_YTfGIPc)RJLMnV!FdPg9h`S?-obfSym6Oz;&}(>9h`S?-obeX=iMnk z?aIer{JJ;)lKlOFFZk}S$@kBB?~nT0`op)s@{7N=e)6M#`J2DC{_`FG>koZx{pwpj z@U7oifBO$U^zGl+-@D)VW$*OH{@#82E8pdf{k;=!+$rCOXngFS*2Dbt(VcCC_u0{LfwLeeS~N`3ukIFZ`dswCnjxd!N7P@cc!e=P$ZF zchU2?i_Xto^ndQ+%d4(_HSY3`r+EkG9h`S?-obeX=N+7PaNfarSG;kTcj9>m=N+7P zaNfar2j?A}caQk-?os}D2Tz{k9X$DucktAEyn~0&@eUrI$2)l1b-aV8UB|oPjXULe zCoT`~VEK6mtGB;*`0!4A+I75xr(MT8m|yugd!%2;-x-@PR&oM-#;pT7m$uK8QA?G;Z4<-y!~z7jkh1pyY%+Yd6(XP zE8e(MzHui{<4*p@oq8L0_%!bDY<%JW(ztum#^>8%%g;B(=9zDem-7GI@7#Ll+hqC7 zH_P&zZ<*yk-#*)}`S#iNiZ||*Z`{e#xRbweH{U+1Gd_(wJR5iTU;TP%+}*w7Y2Lwk z2j?A}cW~apc?ahmoOf{E6>r?-op|2Cc?ahmoOf{E!FdPIchK<;&O12o;JkxrsL#N8 z2j?A}cW~apc~`t~mv`cM2j?A}cW~apc?ahmtX=syb1X0B@65ftnC~+u^J358nX7rR zell}7FV=r%Zs*1N)y(~Y_^?lCnZGV_EecMmwtl##ZIRm);YR(33f15Ld+YjfA;r7otW4QfRym6;| z<4&H&o&1eE^)~MCY24x2_`<(&r(MP8Oy!oJvzD7@&R}l-Ih(ol&Y8{SGiN!M=bZ6e z{&OaD+cjrGx4q(xJLMa9@-*(`Z``T3afeUi4$sCN{#U;mcX`Ltyo2)&&O12o;JkzL z4$eC`@8G;E-nh#<@w|ic4$eC`@8Gy)yo2)&&O12oiZ|}^ zPCW16yo2)&&O12o;JkyiD<9|V`T9F&>eu%4`2S1KXLo#+=sCJR=jbieB(}@#-03)JM}j1@M+xP+4#c0ai?9y=MI4_KX(gk zp1E^i^UqxbTkqUauzcq3g5^1P8Z7_017X`WcOYzg#T$3ZH}2$V+{xd#Q*YxApT-@Y zjXV6Wel_m$j;DDC=N+7PaNfar2j?A}cc;w5J2>x(H}3LIJnv4Khj(z^!FdPg9h`S? z-obeX=N+7PaNfar2j?A}cW~apc~`t~mv`cM2j?A}cW~apc?ahmtX=sy>%r^q+@G_) z&%HX^ALhQD?I&}G%=VwTLuUKc+#$35ZSIiSemHl?Z2z1)WVYXmH|~^g+{x3plfQAN z-o_n1jXOLWU-&ofw5#~sceLf_9;D4P_akloxi@L+o%@uQ&)l=LJm@`5SlYZQSA0xWlt?hyT^D#$Dd=H1FWNgYyo~J2>y)yo2)&&O12o ziZ|}^PCW16yo2)&&O12o;JkzL4$eC`@8GxP?aIg5Bfb94-s$yy_Ec|wn7!89Pi7DH_Mh3Cz5QzTY;S*?z1-UmXYcp+ z&)NIE{Z_njr+nj1p2nU0jXU)=?(k{c;o11Yzj3Es#b>YkmY+TFn`idMZ~oaczxB>u z`sFiw?3d^4y5PvZ{H#vT4wzZ!RW$J4xn z^A65CIPc)RgYyo~J2>y)yery)yo2)&&O12o;JkzL4$eC`@8G9c{y8JI_0HL`mgk%`TmEx4ZQC_x)3&|hjXUKVck(puy)yo2)&&O12o;JkzL4$eC`?}|6>@=iSO;JkzL4$eC`@8G@z3uJ3bZcKgGerQLoqXKc6s%-P%RS92zJ``et=-F`S{d$)hi+1~B9;*C4y8+Y5PvZ{H#uxsLJMAhyXPLMBoN?YfbM|@j&zb10cg{*LpE*OlJm+ln@}INV z+pal_z3mlm+$rCm z=N+7PaNfar2j?BEUDH3G&HHBW(g%CTp8kBWckk)v2YV-<{(rD{^%)ljdxxL#ap%6s=Nk9YF&dsnYs@9^>QZXZwY{PBN$Bb@xc5o)h^Iw+q$@}!&m>8ajy z#wY#poae^!zxoC9@$nsWaNddM9h`S?-obeX=N+7PaNfarSDYr5rxl!caNfar2j?A} zcW~apc?ahmoOf{E!FdPg9h`S?-obeX=Us8$Ri1Zn-obeX=N+7PaNfcAU;WC*$K28J z*PK$mn`^2+n1iaHn47BqynN=Y>R0Bn>Tl+_>W7c{%#+`oSp8PK{;YicT%P*B{EZ9s zHeT>)9O2ox!@qI&nCmUn6(4h1@ifO3|Hquz$!|`q_KK&2 z^64W_y2+oO>P=^S(jU*p9sXCp@-grDn|E;D!FdPg9h`S?-obfy%G~EOPv6VC;*Gn! zD-R7%nTL09-obeX=N+7PaNfar2j?A}cW~apc?ahmoOf{E!FgA_ahG@Ec?ahmoOf{E z!FdPg9jsmX_*g4B{l^+gzFS+VKUj0ApID2j|5&4`Us=1Uzgg3%A3oNAPJU}Z^;_}! zv-0(GdFuc2H!jrMc)_P}glFRp|Hj>8ZR^x)4W;tdR?1_|rTo@ns@ED#e5~EX)0$5F zA8SA-zcrxRE1nL@r;j}8CVzUWH=XfGe>@v^_+R~M+~pll^A65CIPc)RgYyo~J2>y) zyo2+uc;hbb#Pbf$J2>y)yo2)&&O12o;JkzL4$eC`@8G%j2wK`JG{`-Z#AL zoL4=Zoq3F>vykzBoSi&noSm$_;_0A#`pA=R@~5YI(;1)i$1`8>zxvg<%R8Rt9h`S? z-obeX=N+7PaNfar2j^Y!#$Dct=N+7PaNfar2j?A}cW~apc?ahmoOf{E!FdPg9h`S? z-obfSym6Oz;&}(>9h`S?-obeX=N+tF`S>_ffBKKJ_WAA%e*MAO{Q8MA`}H4Z`RiBC z_}AZ@{jVQB?g}{h-4#&36|X-l-?)>f{x5&yLcNU_d>Ti1Hoow0+&%6y)yo2)&&O12o;Jho|xXU~7yo2)&&O12o;JkzL4%V)GeB2>(`j5M1^4*;?^#^y+ z)KA<|Q~z;yP5sK9HuX1m-P8{scjKJ=?#8L#ir1f&ub<0P|ChgUq29&|K8+(h8+Z6O z?jCpkoO<0YQ+apJl*e5(<#$I-^}4$zKJK)Mr@Lm=N+7PaNfar z2j?A}cW~apc?ahmoOf{E!FdPg9h`S?-W6}$<(+um!FdPg9h`S?-obeXYgax#=4?;@ zF_)X~=6LH5=6>rZ=7j4%=8EfA=8)@e=9cS+kGbfR-&}P4R=obKeEnRW`oH{*3-vZ$ z@M#?3*|@{Marc;GKlPf+t-Lwj@|gQAzd7ORHCG%TbI9>Dw;cb+T=dCrF1q%Lr-Sn8 zBTu@?pPuSXXMEBh&&D18SHBu}dB@YdgYyo~J2>y)yo2)&&O12o;Jho|xXU~7yo2)& z&O12o;JkzL4$eC`@8Gx(H}3LIJn!JVgYyo~J2>y)yo0qX zA0KO!r~g>H%=g#MdUXB4T4(*l8fg8;+GzdCnrZ#bT5A39vG#iMTYIhFir1f&ub<0P z|ChgUq29&|K8+(h8+Z6O?jCE(r(SE9mA9r@9&4TDw+33h)<)xF%`~3YQse(vdp-HB zz1CjwbWlEhR00~?|7PbaNfar2j?A}cW~apc?ahmoOi_= zcX=nCcW~apc?ahmoOf{E!FdPg9h`S?-obeX=N+7PaNfar2j^Y!#$Dct=N+7PaNfar z2j?A}cd&Nl<6}?G=|A@BL>R6)PL*+s$bb7RDZK~sDAj^YjpD4YgE4# zuRkkaKbNQeFMs1gy^R-q8b^3G?(lEiJ@!zYdhOMzygfYSvA3uE_WV?@y+HA?M<|~5 z4#oem*XZQ8*QoZ2r-Sn8BTu@?pPuSXXMEBh&&D18SHBu}dB@YdgYyo~J2>y)yo2)& z&O12o;Jho|xXU~7yo2)&&O12o;JkzL4$eC`@8Gx(H}3LI zJn!JVgYyo~J2>y)yo0qXALpI(S^mzu=(BvEchqO~hk18>RzI0{+Gq8jdDnebznXX8 zXZ5#vH-1(>oOkJGbKd;)&v}=AR=*XmKPz89m#6+Of8#>EjTd|xM|d{w@Ne8{SMm9F z*z)sDv3cfOWAo29$ksdGCd+5OS)RsozGa@qf4+U5)~@;Xd0KnL(?R+4ktf~cPfzux zGd}5$XTIQn^{a80cRbBIIPc)RgYyo~J2>y)yo2)&&b#7`ySx+6J2>y)yo2)&&O12o z;JkzL4$eC`@8G*Fx3lAJ=6rVC&0NrqyO}%MaW`{EJMP5m&&oIM*0xRa-GCx7Eky^TA38h3a$?(o0*)ws($p5`5#cW~apc?ahmoOf{E!FdPgUGc_U z-ihZOoOf{E!FdPg9h`S?-obeX=N+7PaNfar2j?A}cW~apc~`t~mv`cM2j?A}cW~ap zc?ahmtX=syYYOY{tTn9fvj(yKVb&(LpUj%Y_MbPr>>amX%^Jt{w^{qxemH9-+dpTm zWc#gn<4*a;oji>@`5SlYZQSA0xWlvYg@5BtyNb`+(3YPyqs=pGNt=Jxn6}5PvZ{H#vT4wzZ!RW$J4xn^A65C zIPc)RgYyo~J2>y)yery)yo2)&&O12o;JkzL4$eC`@8GGhp8+Z6L?(l4U;eQ!-8+X>e^3LFw$JzYy zJF{QC&hp2{8UJ`X`yc+N)kM zGd}5$XTIQn^{a80cRbBIIPc)RgYyo~J2>y)yo2)&&b#7`ySx+6J2>y)yo2)&&O12o z;JkzL4$eC`?_l=}@ea;AIPc)RgYyo~yW)+zyc5qmIPYNf@(#{BIPc)RgSG1=AJ2Vv zr~kN1E#KX-R)28!TK&YGZ1o>^wbifO;Z}chw_E-2aTnal?=HCdt$6)e`TDs$^?&&r z7wT=i;L|w5v+;%hOXKd`Pk8Eems;iBu~r^;uWkOhldXE))fOLjxW&`mZt;KI1$Xkh z3$FHxr-Sn8BTu@?zj{u+>5NbMSqPxB7WJ2>x-?+@?byo2)&&O12o z;Jho|xXU~7yo2)&&O12o;JkzL?v%gZEqVHL-ihZOoOh@E!#g z@=iSO;Jky~O|_ip*??$CU9r)d4bU8D6AcaYY9+)Y}) za%XA%&0VJT!^hpHr+>Qpw0L18qhka3RWd}?0zbzP73 zTYq%xaa;TKUDs<)?IV4*@ATikdzWAT0pIT! zfB&Q2yGEaW-ryaii@k&NxbCZue!Pcv)p(cb(Z6?}wl42PUF@BxM-CrwLdSGA70-7^wqx09jCd&xx=}`xx=}`xx=}`xx=|@ynUBD})oIA`Bci4Mtxof0op831?<@x7b-(7e9uHOC3-{HH@`MZ7hKR*lhy5?uWUa#?TP+vagDL3=)Jm)X+~M5e+~M5e+~M5e+~M3c-oDG7@!a9u;oRZe;oRZet@_6u z&K=Gj&fThi+~M5e+~M5e+~M3c-oDG7@!a9u;rThf+~M5e+~M4<`dQb@9@qIDYah+; zqTBoYj=JxM`Q3HjC-Xb)zJKO--F;up@4)+ho8OK1eK@~M@B4Fpm)`fS@%Eki_MLgU z|IOdNbKUlxe%g2XY=7zh<$br#TUqOx|905*^WPMEp80Q$m*<}|Cc5tYx5@5j{+ng@ zIsYxQ`=9^z+3TAB_Sx$--o8`czB5nz&iw7W`EQ?{vwqrl`fT6n|Md0pzPsIVnme33 zoI9L5oI9L5oI9L5oV&)`ceyj3JDfY5JDfY5JDfW_{~ffP;@sif;oM;va))z=bBA+> zbBA-+c>6AQ#&d^rhjWK>hjWK>hpj7*^KUF)n&0`imoLrx{F}^|_V@7oTg{htpUl7E z?9YGa-*)!r!t-xF`}5-Yx1jww^8DM;{(O1f3kbY2TT@JYBb(^;7=(%!~d{U+ufxahf}vJDfY5JDfY5JDfY5JDj`5+jqG$ zo;#d7oI9L5oI9L5oI9L5oI9L5oI9L5oI9L5oI9Mm#@lzfGoCw~JDfY5JDfY5J8WHf zoZnTp-+4xFd!J|b_Wdx=^zHj(p7q=J&pZRT@2hz>aNlq9%;3Hc=NZF&f6g<8`@S{a zzEj`6Gf(@@{Ovo}ZQtpqeW%a%m;T##*46ktQ@QKsS<5}oJcGICpJy}ob?2GQ-OoJB zx%-@FJa_-|Oz2+MJQKRtYrK7@zI|t&_MQ3LcdpyM(@*@1J?*ecxB}Ed0LT z<{9~YAI>xN`~I9~>i2zXynUy>eP^Ebo%!2$uG_xTPy0@v?Jxbe@2sowd56HRpLYxF zdFGu1d;WPB!M^Ui17Y_w??Bjn&N~fu|MQ-Ty{>r&!d|cO_MQ6noq5`K=5OD*Zu?F@ z?K^$8@AQBAYTxCK)7;_Q;oRZe;oRZe;oRZe;oLRezRR8Q+~M5e+~M5e+~M5e+~M5e z+~M5e+~M5e+~M4&oN&`^fe??_k;9=iMy( zewcT*?E7Ti<+AUedB@AXujbt^`+l2u$n5)Y-XXK^&v}Q;zHg1U@6@;N%+tOzfBVjL z+jshD-|4gcrT_Mwbu~Wk%-QwxE}cEkyklq2Kkwez*PVCr?0)85J-g3&=g;nc-ubiF zHShe{>owlKQ{TQbPy5dN?K{_P-|44)r_c7C{!d@+yWDY_JDfY5JDfY5JDfY5JDfY5 zyT;phxig+SoI9L5oI9L5oI9L5oI9L5oI9L5oI9L5oI9L5oV&)`ceyj3JDfY5JDfY5 zJDfXgU3r}ENN>OM-RbRpzEi#LhxxAczE9>m*!%vO?`H4&YQD3*@3;9b_r4G3yWji% zobP_``__2-PJR2%JncL4x9?oHeW#!Hoj%)N`fuM^SL5?t_gz2Vf#37YcjNc`^PTy9 z-T5y4?q|MZzx$l;-tYeByZU=w^IiSDUgPaM_3b-xx=}`xx=}`xx=}`xx=}`xx=}`xx=}` zxx=}`xofAKO+dR9p@56c4Y2Tmotkb@4jkoXAx9`l;zB7OO&UM>&`f1xF)AqXN*|fc0-xx=}`xx=}`xx?0#$9MkT|8V=A zXJfbbd1iLs5A!VTzE9>E+kOAcv$y-cnrCwN{Wj0)?)z|_?cMk1JlnhPTjT9J_3bhjWK> zhjWK>hjZ6>`!09JbBA+>bBA+>bBA+>bBA+>bBA+>bBA+>bBA+>bBA-+c>6AQ#&d^r zhjWK>hjWK>hpj7*|Mt6o{}=iF{lDuyUgZ5vKlnXfbU*y@zwn9|-6x;+^Iq|y`{y0s z@f9z+ufE~y-u*@Q+nav>yT9mj^Vfa)yT9mj^I!aH-~C0On;UQ6sc+wzr+sJs_MPjt z@AT8Y(`Wlj|Lr^LYWy{y^!<1JEB@*C-}C&i5B~vs{-66tf55)(Uw^Y#?tZ@4kACIu z^A*43mAn7n_F1po>-wb6edS)S@p4dKKISPm^OvXVma~4!U!Qr=|LLoJmpe{#hjWK> zhjWK>hjWK>hjWK>*LeFbcgAyvbBA+>bBA+>bBA+>bBA+>bBA+>bBA+>bBA+>bJuwL zE_cRrhjWK>hjWK>hjWLm>+rarH<_CK9LoIJ{d~&Ixu08^YwhP*ricBU%k;LNf0>^5 zb1}2V{k+Vq@ul{i@%Eki_MLg!cjj;3xo-PTKkYkx9{X!Q2Q+Kkf3kbY2TT@edoIEJN>lp^x3}C|LN=4 zcdO>{yZ-Fsea(q;hjWK>hjWK>hjWK>*LeFbcgAyvbBA+>bBA+>-FyDd#JR({!@0w` z!@0w`!@0w`!@0w`YrK7zJL9>-xx=}`xx=}`xx?0#$M=5g_uYPf?f?9~+xyS_XYaf3 zhhO%Sf9SqXzVMIz(0%{B&42!W`@Z^dAM}3ve)}1}^!@gI_*Z_*`|bPlPrv^C_I+!- zeW$*CXP)+*`P+A{+rHCJ`%a(jJN@_b&bk`^yTAK=cKuuYkoVd1{IkFK-h2K(`}5y> zU-!e`>AiP9Z~yhL+I_y||Msfg|8M<_SM7EE!C&{PyHqZAzRMk_xx=}`xx=}`xx=}`xx=}`xofD9=f$&U zU(9{Jc=qy(x&If>9)B_WV)5+#7qed$&)*3z#>L|KyW++CTwDD7uCmzgD)am29-lSt z`nf+Bn`iFN#pa*;bFu5r{kd2_bAK+@=iHx*^*{IIVn5Rx_p`owzXLSS{N20fpTCp$ zb?5Ku7xgoLhrg)L`MZ7h|NO49uH|=?)@!^R)R&KW%FX=c>AK~tpYqq|{JpW}*Z=7Y z^JtA~aPDyKaPDyKaPDyKaPDyKaPAtHN%gYAxx=}`xx=}`xx=}`xx=}`xx=}`xx=}` zxx=}`xx=|@oV)6|!@0w`!@0w`!@0w`!`79@*@N5f?9J_c_UyhNW-ssiWcK*Je`fFR z`)dA9*!SD~U9s=O`Mc%C{P*3uf9CI&ecu}IepcUoZl3m?`P+A{+kVkc`$(VdFa5Xg ztgG?)yL8vj-?4k1`MY<|KYu6h>(1ZRyPx?xeD^tjx9|SvXTe_A{4Ch(HQv5c-@Y?X z`_BCBJJ)UB>8E|C&-R`EPhai3+;N&aoI9L5oI9L5oI9L5oI9Mm#@lzfGoCw~JDfY5 zJDfY5JDfY5JDfY5JDfY5JDfY5JDfY5yT;phxig+SoI9L5oI9L5oI7k?hsT!=zb_r$ zUpnrGmyY}7rQ`m2>A0_6I_|fZ`uqR+U1jY%zpM1~&UpK7*68=KRWoaRseLzVe5rjm zYkaAFH*0*UeK%`->DXU>A6xUx8u$1(-Sy*o&olSHo`3F*ecicdc0Y43?LOxo+x)3az=JC7!?BjjSiDl(lScZDQvhDA4 znIHGtT8o<8;oLRezRR8Q+~M5e+~M5e+~K)Dmphz0oI9L5oI9L5oI9L5oI9L5?DtIf zYUAaQJL9>-xx=}`xx=}`xx?0#$NAZ}{m#$C?R|b$?)zbWhVJ`hezxxWXMX1H`)Ym` z@B7VvYq#&7|2ALur~fu@-x+V;sc+wzr+sJs_MPjt@AT8Y(`Wlm|Lr^LYJ7f&+4b|g z&7Nm|=h^em??U^!^E=Y+XMT6uefn?h`hWi0e67oWo3~!$?K}1DJM*;f%-_Cq-S(Y+ z+IRYF-|7GK)xOIer@6zq!@0w`!@0w`!@0w`!?|m`eV04qxx=}`xx=}`xx=}`xx=}` zxx=}`xx=}`xx=}`xx=|@ynUBDMpZjyM>(2eTSU+=rF4pJVpNsWB_vB*hYTVEI>irJTJbpK5e!nwx zUB64zkKZxs)9)Vj|NO49uH|=?)@!^R)R&KW%FX=c>AK~tpYqpdUi5$Z!aU{<=MLu% z=MLu%=MLu%=MLu%=dN*?R4*%>JDfY5JDfY5JDfY5JDfY5JDfY5JDfY5JDfY5JDj`5 zxvQQ#oI9L5oI9L5oI9L5Y+aszu(jH4_3zoq*5%pB)@!^R z)R&KW%FX;c&$(_n>!hjWK>x9T5vICnUAICrc5affqbBA-+ICs@^hjWK>hduYo9nKxj z9nRgVpLM;(m;IXccQtqa{x9Ba?SJ%d+$@tfe(TM$`lz@0q`Q9Heb%dQmhF4|+?%=k zqn~>-cVF-|H*+`N!(M-uyKntbHyi(3zw&1FKktigHqUqbhMUd*{%`SX_jUjJyWgyz zZ+daFK7YrLy;=XC{u7@1Sy$uMUcF43M^=0O$*}9nwti$@pWM|ycdd)N)@!^R)R&KW z%FX;c&$(_n>!u#3GSAN{hvikX-^VE;KFZ|M*W&7%Xd^2}{?p?lM&B@&#`|z8&d);T=%-x%R z`OD+q_Mcv^|HL2ihV^I7^R_?ZX7hi@r`^omKm2_+>*w44%+31z17CHs{y*=pKJ~N4 z#;v`2nKX~A_WYA!*OhJk$hZh$5^ZcYQx!L@G<~#lLecf+=&CU9G>tAuRK0oQV-K_tQ`TVDT*4VhUS1*(1 zk=34mGVHpttsj}!CwKMFUF+hm^%^e+_2pxpax?$VbFN#?`YC^X=0*RfFPuj;ICnUA zICrc5affqbGPbeU7mmF_c6~!^n04;AFxb3|A1xX`G-|M z8G8N!%hvM`SmvI8z}$KM0dwd12h5%4JsS5MNcEl%!RGPY2sXdxNicVwGr{`t{0Y{l z=T$Iwo>y7*v&P1)y?U86kF56mlVR7DZT-l+KDn!Z?phajt=D)ts4pM$l$-f?o^#!D z)=&BCGcWo-ec?Q+!Pf52;@sift@_6u&K=Gj&K=Gj&Ryd&seV0c^vokebb+Y!@0xu9d|f)ICnUAtA5tydflJ; z=)Tn-mWk_OS-IY-A9t>YW$SvFJJ-Y9xgO@uznNn0PuC>;W4C+%h^)Iv5CCk=pyd2b*k9o??{5#LN zZaJ$he{SYq{w&TN&fThi+~M5e+~M5e+~M3c?i$s*2F@MM9nKxj9nKxj z-Ku}w;oRZe;oPnI#~scc&K=Gj&K=HO+@?~d$az( z{3ky3v#!Riy?U86kF56mlVR7DZT-l#KDn!Z?phajt=D)ts4pM$l$-f?o^#!D)=&BC zGcWo-ec?Q+!MVe^!?|1av+wkPbBA+>bBA+>bJw^`s+Sec9nKxL?_`d1hjWK>x9T5v zICnUAICrc5affqbBA-+ICs@^hjWK>hwVG=aPDyKaPC(9tjqV(`nllyYW=+M zy)-P7`ToITSzJIWoyZM}cF?aL%{T`ps^>_Vz z-oMy9^F4sY=AZ8eEaq;$H?UYgz86@ZzDHR9zDJ1tENa}^tCvah$ZF3&8FpRS){o5V zle_xou61$OdX1NZ`tmVPxtV|GIoB;`{gl5x^P>OL7tW&^?7sD9aqe*LR{i4+=MLu% z=MLu%=dN*?R4*%>JDfY5JDfYLPmZwuxm)#*JDfY5JDj^!|G2}s!@0w`!@0w`Yn;34 zxx=}`xx@AycQ|)AcQ|*ee%9qZO5LB{uhf0(JxW+6-lK$NGCdy-b=%R(t-*u&s+|@sKbDec9?pm+$a!_AB<|#Mx?>y(a<*c9b*Jobz zfBM3CRD-SEpT)Vuxm)#*JDfY5JDfY5JDj`5Wm5fmXW28442|aw=MLu%=MLv?)j#fV z?r`pK?pFQd4(AT%4(AT%4(G0M?yBbw=MLu%+jrdI+~M5e+^zaq*H{0BkJ~>N{`6%ja`jL5ka##P{wJz>jukmtFUq0q3H}mg2=ep&rpYqpd zUi5$Z!g*AKbBA+>bGParcQ|)AcQ|)AcQ|*A%cOc);oRZeVf#+zICnUAICrc5affq< zbBA-c>K}JFcQ|)AcQ|)Aca3vbJ$E>FICt2-;|}Kz=MLv?)z7+|FWb)r=g#)?!uhgT zCeD||vU0xcs-Fy3g=kH?kIF}cj-+8^5 zJLmXf{W#wj>(hC_m^&mu%WL}@#)jxNwi@Vlqyd2b* zk9o??{5#LNZaM3x{Pmd^{hz*Y9@SuL_h)hLaPC(9;|}Kz=MLu%=MLwtahX)V&T@X{ zk)iS2;oRZe;oRZet@_6u&K=Gj&fThi+~M5e+~M5e+~M3c&RzA~;oRZeVf&6doI9L5 zoV!(TU7zw}_x<@@fAh`O{t18RW|@4(H{2|%zw|Dzz3a!_`~Sk5W&5-K^3B|R!h8R? zRm0s!e!+_!aS!3hYUcF43M^=0O$*}9nwti$@pWM|ycdd)N)@!^R)R&KW z%FX;c&$(_n>!u;9Hd;N=>W%X5W`@in{|1E#m&9Z&{$J{LQ_xRm6bN7Az z+Rfa}&!6>Yx%=54e6#Tn|HPZs|E>T1X7hafH{ERhKlGhmzpwjazyHnp`LGYXS)bqS z$KR~~H~X-se%95vwO22b=8@H&e=_X4vaKJP*C%)N&t2={uJsx(2leG+o^mt)&U3C? z&iW~Teda~~r!SmGH8^)TcQ|*ee(rxg;N0Qd;oRZe;oLPYlj>!KbBA+>?K_#{+~M5e z+^zb@9nKxj9nRgVf862R;oRZe;oRZeHO^i2+~M5e++q8UJDfY5JDj^!KkM?o&VC>B z9#3rT-q(p`;(eW1R^HdS>L)|*>%_A4zD_Lj*Ur0EF?ZhAiSNHNziKge-cQ=N_m)=g zeWutv-gAo0@BOEkJMTrs`tiP0tWWP(#rpSt)m1-hY~0$bmr3);YR^9zc3s)lkId_n zyZXQX&b-&cUF$Vo4(iLtJmqHoo#$M)ob^-w`pk>|PhU8XYH;pw?r`o_{o@Yj4(AT% z4(AT%u5p=Ezut}e%p*hNxx=}`xx=}`xm)#*JDfY5JDj^!|G2}s!@0w`!@0w`Yn;34 zxx=}`xx@AycQ|)AcQ|*ee%AGd5Bik-^X|8Q$j#RN<3I9dnS8`AzFAiP=ChvqarcA% z^v$yUbN}FG?tc6`ed?N%yC43OZszXq{Vz9j_nCk0k$=O6rO>(83!cmK4T z&HvXv`DX5Z$?v&YKcD!2-mK5}{fe9Q|H`j<>Sv9OTYL2~X&zba`6t7!E8F^!d3|zM z|J=1M?pm+$a!_AB<|#Mx?>y(a<*c9b*JobzfBM3CRD*MebBA-c>K}JFcQ|)AcQ|)A zca6)WdRgJz;oRZe;oRZe;oPnI#~scc&K=I(s(;+!+~M5e+~M5e+%?W!_1xjy;oM>S zjys$?oI9MmRX^+Ue0x6^Jonzu3(vP>nRvb(%gXcZtA5;hz8%Zf^X*vXo^Qw8dA=QU z=lOQbo#*)*_nd$Ap8v<@@m>IIe(wvw+hjWK>*SJiomle((&K=Gj&K=Gj&fThi+~M5e+~M4<`o|s49nKxj z9nKxjUE|zUzuqPB%)_1W++q8UJDfY5JDj^!KkIV-Q1_>^qq=XMKZIrC{2?r>cY4hy z-1Xzm`9sEK>--@sbLS6X?wmh_xpV#y=FWLbjXQ^_dgn7?^EkH&o8Ng(m^Cdy-b=%R(t-*ubo?&_br*2P`xHC_(t%f~$BX8w07 z&$(_n>!Sjys$?oI9MmRqyYU zPy5;X=fWrbmYc2pTmSIQGI_JVb+fEK@ZEmST|e&r&@aAOw*T)}-pt*%zVFXnHQasW z7v9X>JAdzwUgO;Tf={{G_=o<>o7Ml!*L}>YG0$iG$(zmpAHMU?+t+>dhuo~65B-%l z>+_Aj{bv1t(HA`Rv&P1)y?U86kF56mlVR7DZT-l+KDn!Z?phajt=D)ts4pM$l$-f? zo^#!D)=&BCGcWo-ec?Q+!MVe^!?|1ak2{<@oI9L5oI9Mm#${5ytZ?pd?y!9)bDTSz zJDj^!|G2}s!@0w`TlJ4SoI9L5oI9L5oV&)ktDZZYJDfXg-*Ja?hjWK>x9a_U^6md= z|6KSf-}Bq|&x`ke?aeazsekBZS^d1X`wsj5|GJ-Zvuxku%WjtWJO04`Y}Ii0?|$da z_urY{agB5LJAT#8#y|ca-K_r8f5Mxs8uR?AFTUCQulNpczOVbUKJaG!eEcuES)YIJ zGj8VYtAG1bKWl8<+N+mI^T=w?KN)si+18KD>yx|szyHp>`{%Cp8ZQU+2v)=D%&Qr%Sah^JsmGjhB{bcAobu3%wsbiTtPaSjTJax?7oIkXfJLktY?p*om zoi~ro;~aWye&^F;?wnhX_2WEytk2*29^br}yKnyZn|(jCaci$$Ce0(OJ^y6bb!A&W zGOthW>YuyT#a-()UJmNZ$2{d`{+;Jsx19A;{`$;|{!d>xk7}^B`?ENAICrc5affq< zbBA+>bBA-+xJ;^-70w;b9nKxj9nKxj-Ku}w;oRZe;oPnI#~scc&K=Gj&K=HOor~u>dVJGS zjys$?oI9MmRX^+cd%yli?0xsupLw&jf8ZayStdX6Z{94c-~7%Wc-N1+Z~p~1%l4IT zx>@EQ_^SVQ@4I*T{F}M^pWfz2u5s>O`n5M3|J-lAnd?9DQ-0K{G0!*tA2*x-L*L>@ z@9X}C558GHpZoDQ>+`#Q&dvJ&SHJ72pEWja?bXYqd1STcpA5UMZ0kqn^~qiRbJx1K zYrV$HL4Em{r`*iH^PKCJvwq57pLx;$=?mvk4bC0T9nRgVf862R;oM;^tOe%|=dN*? zR4*%>JDfXg-^m>34(AT%Zq+~TaPDyKaPC(9;|}Kz=MLu%=MLwtaqg<;4(AT%4%>I! z;oRZe;oPnIS(o!=*Y9t`&Yi{9?tIyPe{;SpmX-5mSN&w@d|518=gVT5J6{%a=X_br zo%3Zech1vo+&R0|JAW6O$GN=N{Lbse+&RY=>&N-Nm^{fe9TjB=HGeFb<0^l<*(1Y=>PPE^QZ>r4$H)x zICrc5affqbBA-+xJ;^FXE{If$k2H1aPDyKaPDyKR{i4+=MLu%=Wf+M?r`pK z?r`pK?r`oJ=dOD0aPDyKuzgp~xig+SoV!&&>-rn-`h7p3`}2SNJ^$5WYyZ#>dHcmO z`70mvR*Plz_22SuU%l$b-M9aVuU;(MzwxebSj^pL{lK5Tn7eQLU4Q%i)pPgfKjc?` zA?9wz|77D+|EI9}nP;(iX8y(IpX)B>Zuh&{yF4pJtzgYjXuEqZQu5oLxUM9^W zt3Cf@*mY%FKQgaR?&_br@ADDAX|0R9)@!^R)R&KW%FX;c&$(_n>!hjX{;A9px+ zICnUAICnUAjdNE$cQ|)Aci6t;4(AT%4(D#w&${OOR6oo;?EakZQ!Tdk`99TRnaua8 z7RzeBPj%OiyZJ8AV%g4jgci$uzB{y-yZJuVV(#YO9~N^r->2H+^PQYsKi|n&Y@Yc( z)nfC{_o)_hH{Z!wte^Ql)na|lccm8Vf4)O?*U!2dxAy8~(mb--^G}9dSGM&d^ZMkj z{<&*i+_hfg<)FTN%u{aW-+9h;%UM6=ug|>b|MZ3Ps0QZ_=MLv?)j#fV?r`pK?r`pK z?i!a#^|Hdb!@0w`!@0w`!?|1ak2{<@oI9MmRsXodxx=}`xx=}`xoe!e>bb+Y!@0xu z9d|f)ICnUAtA5rs@0r~9=e%cf-?#Ig$;C36_e?I9)x2l&t{->vj>N^Xop&cLmifF> zaWQxEp2@|xyC1)pyLr##9-ns=?)rIG;bQa5dnOl~f8H~>n7esb;bQ&FyCN6sbKW7j zn7etmp4(ATrciiFJ;oRZet@>HlyjS@}Kkw$f z%8RXi-mAP=Ci7n9#j=|BD&O_vZr%yJShn-7;KeeZcL*=$Zr-cBn7cVgU@>>|UgbSL z@8;e0^KRb7=9%{@FE;|PhU8XYH;pw?r`o_ z{o@Yj4(AT%4(AT%u5p=EFDslooI9L5oI9L5oV!*3xWl=_xx=|z^^ZH8JDfY5JDfY5 zyT-Yzo;#d7oI7maaffqStYZj=;V@=Ny53-_AJ#i)AwJv|lW%IY;2GA9r(( zz+&0XyYUyxeBPPAn7cVgU@>>|eX7OW%{c;leBMRB>*rnci_J6V2rM@LoFlN9yLlJ= zV*SiH0*m!IX9O(fZq5$4>t~IPTYL2~X&zba`6t7!E8F^!d3|zM|J=1M?pm+$a!_AB z<|#Mx?>y(a<*c9b*JobzfBM3CRD-SEpT)Vuxm)#*JDfY5JDfY5JDj`5Wm3JYaPDyK zaPDyKaPDyKR{i4+=MLu%=Wf+M?r`pK?r`pK?r`oJ=dOD0aPDyKuzklJ&K=Gj&fTh? zb#iSn^EuaI+0JJ-i)B8a=`7}MKIdA@-F(iqn7jFGXphflCA)q;D_Lxw z`J8L9`R8-4#oWzjC5!blpK~qN=X{2>n7jFG>#m+u{`Ix8N%)j%T>z1>A%3q&((f{cS=TQx|c7GP<4(D#wKkjhuaPDyK zaPDyK8kb4+vckE;xx=}`xx=}`xm)#*JDfY5JDj^!|G2}s!@0w`!@0w`Yn;34xx=}` zxx@AycQ|)AcQ|*ee%3YL>)7|_e6M5QxAVP@#WI=ibu5o z`Fw|AF?aL5j>X)~_c|7HH{a{n@n}2U#%-wvC zagWb;;dcFe7jCh6=6j5b%|G8`T+H2k7jChB=DUcC^*P^BT&(~3?&4iPYi!)wtCvah z$ZF3&8FpRS){o5Vle_xou61$OdX1NZ`tmVPxtV|GIoB;`{gl5x^P>OL7tW&^oI9L5 zoV!*3xWl=_xx=}`xx=|@Tqf1a3g-^z4(AT%4(AT%Zq+~TaPDyKaPC(9;|}Kz=MLu% z=MLwtaqg<;4(AT%4%>I!;oRZe;oPnIS=W4TfB#&V@9poO7xTUS#WI=ikS~_id~g4* zA9wS;{l&7K@1if3`FuxxF?aL5{l(n@dwjn8z3b<@-;2#N-QGQ^>cqVo;%~Y!?|1ak2{<@oI9L5oI9Mm#<{DWJDfY5 zJ8a)^hjWK>hjX{;XI=B0+I>F{&vR;vt$m(TTP%}#W@@pl<~g;ye%#G-YKvt%&t5H- z`8<=gn7esSZ83NAoZ4dU<~g-JKF>Ps`gzuAv3ce>wZ-P2=hPN+H_tjP*3UerwpgF@ z4BBG-&$DTF{j95TYp-4=%_FNl|76&8Wm`WouTSpkpS#w@UF$Vo4(iLtJmqHoo#$M) zob^-w`pk>|PhU8XYH;pw?r`o_{o@Yj4(AT%4(AT%u5p=EFDslooI9L5oI9L5oV!*3 zxWl=_xx=|z^^ZH8JDfY5JDfY5yT-Yzo;#d7oI7maaffqStZ^T=xFCFwbT0 zpBM97_F|dLbJ>e!HP2<=_2cdb{KT7OJI@-gahcCE$cwp~=du^ye`nsz-8`4Q$LHDJ zT|dwEE;i3Rm%Z5h@AR5aSj^o#+q+ml^KA8EeaW8>Cdy-b=%R(t-* zu&s+|~d6cjmn=?pm+$a!_AB<|#Mx?>y(a<*c9b*JobzfBM3CRD-SEpT)Vu zxm)#*JDfY5JDfY5JDj`5Wm3JYaPDyKaPDyKaPDyKR{i4+=MLu%=Wf+M?r`pK?r`pK z?r`oJ=dOD0aPDyKuzklJ&K=Gj&fTi__sQqJa{pYI_mJ$L7xNyH#WI=qkSvzfyocnj zA9wQ}lEt!}cWW$``Mh&uF?aJGlEvK3dq@^@H}4_Y<8S)GH>;m_S*&sM%)2ZWn}6Oz zvY5Mhm&IcJ%)3Mu>vP^QvY5Mh_sCs8Yi!)wtCvah$ZF3&8FpRS){o5Vle_xou61$O zdX1NZ`tmVPxtV|GIoB;`{gl5x^P>OL7tW&^Z0-Im&K=I(s(;+!+~M5e+~M5e+%+zf z>ScvhjWK>hjX{;A9px+ICnUAtNw9^bBA+>bBA+>bJsX`)pLh)hjWMRJMM7q zaPDyKR{gAN-n+H$&w20GzHjHfTZ?5f@7-D~t9kF%T|e&Ty<3ZAJMWTOEc1EC)MD=D zy<3a9oA+)l=5F4*wa4e(O}l>H-L%*|^WLq+=AZX&E#_|C-LzOg^WLq+`kZ%aE#_|C zwRP9e8XLFv>SfYAvfA@chFw>-^&|88K}JFcQ|)AcQ|)Aca6)WdRgJz;oRZe;oRZe;oPnI#~scc z&K=I(s(;+!+~M5e+~M5e+%?W!_1xjy;oM>Sjys$?oI9MmRX^*R_bTuEbKa}G@7sB= z@?x3HJAN0-YTm1S*N?k-ukvEq&bxva%Y5D;yqLRrukvE<=DXL6xtsSY@9}vz@2;PB z^DZ{eyjOX#`RBdLi@BS3^DfrUyjOX#KIfgui@BS3Dc|+8#>TC^dYLqjtoHnqVb_&y z{m8sNxvPKfS{HY%*LXRoFCX)ioB4O1bKP>*PxZ+~M4<`o|s4 z9nKxj9nKxjUE?yTURF4FICnUAICnUAICrc5affqK}JFcQ|)AcQ|)Aca3vb zJ$E>FICt2-;|}Kz=MLv?)z7--y~_LkocAj4`*z-|yjUjlj^D+yn)fQ-_2X{dtGrmY z^RD2SfYAvfA@chFw>-^&|88K}JFcQ|)AcQ|)Aca6)WdRgJz;oRZe z;oRZe;oPnI#~scc&K=I(s(;+!+~M5e+~M5e+%?W!_1xjy;oM>Sjys$?oI9MmRX^+c z`XBM```;hl=k0H{_K$nR_uKzo@t%L@zg{e>_x*09+|8LUi)A}!!7P^foDs8_ zyE!*!F?Vxr&SLK7+?+i=XRqw~IeTTXdFI@l#pa)La~5;=bN`?3x>!GR_RV5_&Y3ui zxtp_c?)q6{&mu%WL}@#)jxNwi@Vlqyd2b*k9o??{5#LNZaM3x z{Pmd^{hz*Y9@SuL_h)hLaPC(9;|}Kz=MLu%=MLwtahX&vE1Wx=JDfY5JDfY5yH)?V z!@0w`!?|1ak2{<@oI9L5oI9Mm#<{DWJDfY5J8a)^hjWK>hjX{;XI*nn+`d2OoVb18 z&N*?5Win@$Etb`s6L;5-yE!Lrv25q;v&Ax>Gtm}vH|NAH=5Ef3Tg=^@6Sv3btg&4` zXN@g3&zuvt*!*)&++yzLtg*%VnRDV6>vPV4Tg=^@4R_bi8XLFv>SfYAvfA@chFw>- z^&|88K}JF zcQ|)AcQ|)Aca6)WdRgJz;oRZe;oRZe;oPnI#~scc&K=I(s(;+!+~M5e+~M5e+%?W! z_1xjy;oM>Sjys$?oI9MmRX^*Rb5Zy2V{*Px%}skGp`qOH|Kya=5Edb zU(DT{1HQ-SEa_c8XGt$M&zu9k*!*)2_+swnEa}DinX|kX>vPWdUd-K`{e9QZ8XLFv z>SfYAvfA@chFw>-^&|88K}JFcQ|)AcQ|)Aca6)WdRgJz;oRZe;oRZe;oPnI#~scc&K=I(s(;+! z+~M5e+~M5e+%?W!_1xjy;oM>Sjys$?oI9MmRX^+c@}Kyd_Wk)auf5sY-{D8xER(l+ zkDF!nv2Xd*kGty|KXd(A*?!R+u{`Ix8N%)j%T>z1>A%3q&((f{cS=TQyL9nKxj z-Ku}w;oRZe;oRZe;oLPYlj>!KbBA+>bBA+>bBA-c>K}JFcQ|)AcdPz!hjWK>hjWK> zhjZ6Bchz%;bBA+>?K|#p?r`pK?pFP*YjV8i_oU1HIr%QO_Q`#*OeV+0vYH(4`f)co zE|%^5Z;NFbBA+>bGParcQ|)A zcQ|*e{&9zMhjWK>hjWK>*Eo08bBA+>bBFCa?r`pK?r`o_{jBQ;{-A%l|2ya--r;6z z|K;EGE&IQlKJ3@rEUT~kkN@PZA9w%hbvMiQi@x9=uW_0G@~{0zi@E#KfAbITd1l|e z^Y^})yI=jPf3U~@@1Oklcl~esw7<95JTJcT|66SS|KY#6nY+LL2mbCF*Uz8*kej*t zJKy7G{eO@D_|2=v-zSY*d-XDD9$D@AC&R8Q+xn4teR5a-+_f(5TCeePP+vagDL3=) zJm#2 zhjWK>x9T5vICnUAICrc5affqbBA-+ICs@^hjWK>hwZy^&Ykhx;oPnIS=YyW z{!ib(XMWOeyV=^``d8d6lW%{`&9eG4-|49zcR%S%e%k&$^A#U;v&`T6U;NZH&fTj% z`DX6E`E76J?z7+Ux>aNRkH62&>Ob!*K5C7d=i`3S&D_1kyWY&*mw)3&t{VOPi7&oc zpC9yDH|zg(pL(->*SNJ;FO%kx)t-Mc?7Fh8ADP!DclFO*>*B8U8ZQU+O(&5sULT5`!jBq?I-?_n`QoO|LF_XoZP+nm*33Y z>pt^l?*7<^zdZiu-sR=`SO4SB-}~+hzw~DF|NPInnY*w2xSRF!Wv{zgpKtZroAv*8 zuX*ZcU5#6N^)hK5S?&2J!>%ja`jL5ka##P{wJz>jukmtFUq0q3H}mg2=ep&rpYqpd zUi5$Z!g*AKbBA+>bGParcQ|)AcQ|)AcQ|*A%cOc)Ve`lk=MLu%=MLu%=Wf+M?r`pK z?r`o_{o@Yj4(AT%4(AT%u5s?F=MLu%=MLL<+~M5e+~M4<`dQcU{PJ}?*L)q%J733h z(AV*N^mRNpeI3tJU&nLS*YW)I{5RzNy!ov0I-b|Qj_0_qpjoh124}%|IONU=bqX9%)PYxoO^QjKlkKb*W8nPy~fKy zefgND+|0l8oa>gee#&2;dC~vr>v-OL)jWRJpMAWqIq}>N>srhE{CBe+@Z3MEH$3;% z>KV`dxz>W`{#b*#TCja* zjW~CW_xYXrKEKPI8uQB*+jla@`r%^DGktQ0_0Qd^pZl}%+!@au&fThi+~M5e+~M5e z+~M3c-sg9@GoCw~J8a+e`CabTJdZn^yH!8yIzA7&j?am%^eR#yN=J%uH*By>-gO5IzErPj?d|?cZtc}` z*F3V?^G}9dSGM&d^ZMkX{<&*i+_hfg<)FTN%u{aW-+9h;%UM6=ug|>b|MYcyez$5k zb>H^+oqczFuC%VTywClw2W(#)pHHoxjoU}og6%tN#P*%FH{R!W>ihi8zLTLE^UD_7 zcQVKJ9T#h!>61IGf9_WO+@Fo-&Uo%{?pFQd4(AT%4(AT%4(G1%KEKPI@!a9uVf(I} zbGPPs+~M4<`dQcUdC+xyPIMigA6>`iO4spu({+3fbse8iUB~BE*YSDQb$rfs9iM+) z$LC_#@p;*Ge2#VnV*Ae88}IWw^?iP4-^oyo`DKgkJDFqqj*B(V^vNC8KXhjWK>hjZ6>pWo%qctWft9+tUWFc+?e@Bc=)KfmKnzKy#^^{#=N-BRx{lAYuH$pA>-hZZIzAV>j?c@k z<8!p@_$m= z_MNq?dFJO`pWoRN*4}uZ->L8OJNr(C%`aPQ-^m=?cU-J_rcds${<&NAbAL9TJL9>- zxm)#*JDfY5JDfY5JDj`5`}{6<#&d^rhwZy^&fS{laffra>StZY=Rw!;Ini}|esmq5 zD_zIuP1o@`)OCD5bse8uUB~BH*YP>mb$tGH9iNL`$LD3&@j2Rce7<%apSxYh=W*BZ zIo)-9ez(W1y?XANM^=0O$*}9nwti$@pIp>Gcdd)N)@!^R)R&KW%FX;c&$(_n>!S>srhE-2ZyO_TBOM)au!|ePk_bp4oTSi0wOTZ@ka% z)c5(FeJ4XT=9ewD?_`ecJ1*8d(N?Jux{mXw zuH#%PzmM&I&pghtx{mX$uH)RR>o^bVI?lwXU_i&;73lY+oGbOs$@c+eg-dpWibV+jrL9c;|4b?;I}sPKM1dTWsIS z9NTwXta+wS?y&y3TlI5)Hl91Im zn&)wcbGPdKee&`-T-R~l({-E!bsgtJUB|gm*KwZIb(}MG9p_J7$GKGV-ze|6J`?Be zILGQb&bPXbbFZ%BJgn+u{`Ix8N%)j%T>z1>A%3q&((f{e|IEQQ1aO%GGXR&>EoDa3G zwY<;$uLo@39p_A~o{if_*0ScApLf=XbJuw1aH;PcF8fY~YRoTNY~RTo+jm^7d8SY9 zu>QGQ^>cqVo;%~Y!?|1ak2{<@oI9L5oI9Mm#yf{AcgAyvbBFD_a?ahF=W&N~x9VqI z$GJ||ao*E)oC9?o=R;k`xlz|~p44@mGj$#3PhH2kRM&A{)peX>bsgthUB|gs*Kr=! zb)1uR9p`6V$GKY9ao*N-oWr%pt-X5gnnzZ9{>iZG%C>%FUY}glKX%#ZV@uH#&)`3&ejhl{)89INX%-)cU)`J?Mv<~h#8x{ho`~II?mg=j&r#7xV2Z$UGvCl&p#PdVE!e)ZMx49G zJBLes=WyjtjrnDZ?K_!c{cy47nLfG0`sZ%d&;8kW?u_RS=Wf+M?r`pK?r`pK?r`oJ z?;Nh&8P6Tg9k%bvId^NG#~seys-JZo=Q>@-c~94I4%Bs=4|N^qMqS5wQkS!e>`j>; z=TBY7xm4G2Ue$G+V|5+pTV2PwSJ!bK)^(hdbsgttUB|gv*Kyv~b)3Vs$F043?wUtd zd;ZC=>&mu%WL}?K)IWEvi@Vlqyd2b*k9o??{5#LNZaM3x{Pmd^{hz*$bGTLwr|#R% z;j-_J^P$$YmiM{;^?>aQz2V$p`^Z|beP@l>zO(kmJBLes=Wv-vhHA_&TWsIS9NTwX zta+wS?y&y3TlI5)Hl91Imn&)wc zbGPbeUB|gj*Kyv{b({lr9p^(`$GK70ah}w5oHKPD=TBY7xm4G2Ue$G+V|5+pTV2Pw zSJ!bK)^(hdbsgttUB|gv*Kyv~b)3Vs$F043?wUtdd;ZC=>&mu%WL}?K)IWEvi@Vlq zyd2b*k9o??{5#LNZaM3x{Pmd^{hz*$bGTLwr|#R%;j-_J^P$$YmiM{;^?>b*#TCja*jo7}k_QpGhOMT~X*>^HjV}99U`%dQAzT;xeGktQ0_0Qd^pZl}%+!@au z&fThi+~M5e+~M5e+~M3c-Z@;kGoCw~J8a*TbMDqWk2{>ZRqyYUm(K&bj&o>mx4+N*;qEw>=Q_^o zxsG#uuH$^4>p1u4I?e;yYuyT#a-()UJmNZ$2{d` z{+;Jsx19A;{`$;|{!d@Wc|fa%Q}=D>0oixQIW_BA%lq8_dcgL@ao)}9*|>dVE%^TL zyPNGhYj3>sfYf&$Q0|&vw%ERtIkxXQ4@jTKxj)O@s-OF_@!T2D9nRgVf862R;oRZe z;oRZeHQsqZxig+SoI7mam2>XaJdZn^yH!8yI?k85j&oJoEF;8nJz6?TvRHkowL8 zvhQT5#{9Cy_MObJeaFR`XZqv_>z}(-|G2}s!@0w`TlJ4SoI9L5oI9L5oV&(54=8uW zbBA+>?YnZ$-J0idhjX{;{eANCc|g~3?#y+ZM{^zL)Lh5;HP>;j&HO!lp9duK;~bpp zI3LHqiS5ttj`MV`qqAG$wmF&e`oGR{F>`H*XBCTySa{YaIWKgoa;C@=Q_^Q zxtuBE-(qqAG z$zA<()VjE9y~fKyefgND+|0l8oa>gee#&2;dC~vr>o^Z+)o|**?K~j+?l`ArU2A!t z`(F>(zB|slSv?!)!dkF>XN}mtv-ZYiQhnzE*>^HDZhqNf`%dQAzT*PxlRK<`?pFQW zpN;3vcvdGx8`}=;oPnIS=VvC%ypbQ za~IXl;J{?2ur%X1y)^<2j} zKG$)+&-L4%^MJTJ&I8)x)?Ph#%_FNl|76&8Wm`WouTL)OpS#w@UF$Vo4(iLtJmqHo zo#$M)ob^-w`pk>|PhZD*K&ysRYwtWD_w#X1&AQg|KKH*Kuzhiyce8pnZr@o8w(qPF z+jrL9c;^AB?>r#;PKIjCFI#Ni$sF5vT&#JfPwsH;R{h+cjpxpI?r`o_{o@Yj4(AT% z4(AT%u5s?FFQ42Q&mFe!$~kvyp2r=|-Kw8;eaUpce`2tzw_Vy#Z}|K z?;5xE>bYwkS?&2J!>%ja`jL5ka##P{wJz>jukmtFUq0q3H}mg2=ep&rpYqpdUi5$Z z!g*AKbBA+>bGPazLp|W!;oRZeVf)S+aqb$IN%gYAxx=}`xx=}`xx=|z^^ZH8JDfY5 zyH)?V!@0w`!@0w`!?|mmyXv{axx=}`_8oUPcQ|)AcdLHZb)4&T9p^n=$2m~faX!>_ zoEvo==Sf}1IaAkh{?v7xOXYiv``=ZLbF8l8e5>m?_v$*%!@7=hvaaL&tm`;e>pITc zn*H))_rI$&Ztc~}q+|~c>?p_ynt=D)ts4pMx%FX;c&$(_n z>!gWD!Ja@)(hjX{;A9px+SmyPaJL9>- zxof<0xN_G#<(50+_FXyWZq4(!!?|1av##TOnd>-r<~q)!xsG#cuH*cg>p0hD-al}k z2PE_39GvSoAIEq6*3TgBj`MV`cWIvvK>#TGl-C^UfM^?i%krAoZOGlsh%% zmo2vMWRC4SF4jELCwEx?+^zb#KO4`T@!a9ut@_6u&K=Gj&K=Gj&Ryf32b4SGxx=}` z_FXyWZq4(!!?|1a{yus6JfQ11cjh|Iqq&ZAYOdq_n(H{%W}buo9_#0e%#U+$uH$^1 zd1m>$@1J+ac{4``2Dd-dEkkF56m zlVR7DZT-l+KDnrW?phajt=D)ts4pM$l$-f?o^#!D)=&BCGcWo-eI4fktr||+pk_K~$r#)fDF}`U$)r3lR38U zxLET{pWI>nbGPc}{%kyV#&d^rx9T5vICnUAICnUAICqVA9#HO#=MLu%+jr%hyEV__ z4(D#w&$^EDWv=7gnd>-@<~q))xsLN|uH#&r>p1V``sC+4ATEycajxUsoa;DG=Q_^W zxsLO9uH#&u>o~9HdhwhG#NBbe&vl&pa~*B8U8ZQU+Rk$pT+jwaZb&;*7830zaFrC zah!LvdN!WBHP7rjYsB`QwKv{*KnbGPc}{%kyV z#&d^rx9T5vICnUAICnUAICqV6SAF^9&Uo&yeOJ!8Tk|~baPC(9tm}9m<8{2J@jBk$ zcpdL`ypH!hUdMYNujBoY*YV!S>v*5!b-ZWtI^I8d9q*;Qj`vkw$9pWViZG%C>%FUZ336KXExxm+PUhs9C zBYYj_3tz{%!}H$=_c_bl9p@BZ$N9yVvwD4&$K7$>@pYVod>!W_U&p!0*KwZmJPY*B8U8ZQU+RkWbC&J9u00e?4IP;y6cm^=#ZevKDOLStHI}bBA-+xJ;^-70w;b9nKxj9nKxj-Ku}w;oRZe;oPnI#~scc&K=Gj z&K=HOx;yZP?l9-r^R?fUty;9~R4cL*1of4;}K zn7jEd++zLAcM%usbH2y8SpW0g#k+pi*toSfE_+~M5e+~M5e+^zb@9nKxj9nRgVf862R;oRZe;oRZeHO^i2+~M5e++q8UJDfY5 zJDj^!KkJ(B?SE@i@BTcy6^G%?)R>r@5V1S&wOWovH9nF`-{1o?|v`V&wTfOu|DT}`-}BI z-_^hCXN`?pd-XDD9$D@AC&R8Q+xn4teR5a-+_f(5TCeePP+vagDL3=)JmfE_+~M5e+~M5e+^zb@9nKxj z9nRgVf862R;oRZe;oRZeHO^i2+~M5e++q8UJDfY5JDj^!KkJ%v1orP^^Dg@Rd)mCa zez8pEJc7ltns?pb_2X{dfxlR`^KSgbGM{(mFXnE}L0HV)eCJ^?cXMvS9-nv7@A^4M zV6l1T9sY~WKj#Q6=5EdrSgfBpM_{o&=Ny5>+|Ahmcm1rfaci$$Ce0(OJ^y6bb!A&W zGOthW>YuyT#a-()UJmNZ$2{d`{+;Jsx19A;{`$;|{!d>xk7}^B`?ENAICrc5affq< zbBA+>bBA-+xJ;^-70w;b9nKxj9nKxj-Ku}w;oRZe;oPnI#~scc&K=Gj&K=HO*pEF#pao3GZ&kGo)2Bj-8^HsSU>ZO z=VE=%^P!8mn`c7r`dMS+)?U3#nnzZ9{>iZG%C>%FUZ336KX}2JDfZ0b;ljf9nKxj z-OitV%`^4q*XKM_e}3K0Gx*CgnP>BtWi`+2AM?lEJj=f<+j+)+S?2TX|1x)TCcrXx zb5_7IcXNioIX=(SpY!L;fo1E=Sp>`0pYsrwxtnL|m(??88Z4`G&O=z{Zq7hB=Fc7* zxA*4Dq;+IgTR~ao2v0mxKA`W1Vud{+Z`ox17~e{_4z&`mcTA zJeq^;-M_`T!@1k}7k4;!ICnUAICnUAjmxC@vckE;xx=}`xx=}`x!d^{cQ|)AcQ|)D z|Kbkk4(AT%4(AT%u5s>~&mGPk&K>r;;|}Kz=MLv?=g+?844L!yyE#MV{QYjuoH>8L zo3m)n-|yy(nq&UBoAZB`WjkluEX#b(x>@FK&i`5FZqCM8=5Ef+ImhP=nREV}v9oNQ zIeTZ>`g11FGIw)^%rbX#hR-s0bN&muzWL}-z zRX=y_i@Ww~yd2CgAM2Ex_0K%#y5+2%@>geG)PL;@=g}N&@BS^8i8ZmTTx;iF+~M5e z+~M5e+~M3cE|ccV3g-^z4(AT%4(AT%Zs%Xz;oRZe;oR-~i#wb@(b0*s{f85PkZOgKq zGu)PCK4-fvb2n$cEps=|y)JV%XT+W3b7tB(f6kO!w$7Y2w`~16?{1m9IWuipJ#%K= zvO4FyyJha?jJsq0?6GlsZ@x@gM^@+hlVR7DZS}~!I=QQU?%Ef3?bmoYm|s5DDL3n% zdCqmqSv}>i&b+Aq+855FIoRI)Tbw(byPbb=hjWK>hjWK>hjZ7sOqwq%oI9L5oI9L5 zoI9MmoqutMbBA+>bGP#^?r`pK?r`pK?r`oJ=dStO;oRZeVXr&xaPDyKaPD^g>}$>l zJ-%ja>XCVMa##J_wJ+}4ukms)zkIAyZq`5Zoa>geddgp&c~SqhFPuknu)X`Y zICnUAJOAPi=MLu%=MLu%=dN*?G+$OYcQ|)AcQ|)AcQ|)D|Kbkk4(AT%Zs%Xz;oRZe z;oRZe;oLROUGuraxx=}`UU%H#+~M5e-0l3?*PMxcz8{-2vCsEubB6Y^Oy+FuWm(Oc z+sFKIH)nA#%XZG_UY7Zs-M!4+oaw#H-TZxdnY%dy{2ZS%vCsK)X85vo<}C4L>(6=S z%iPVG*vsmfGs&0LIp>)#b2n$0AM>I{^07|2S^vy)u3OIPDSvh5Mg7;la30OU_U_-}+~M5q{EIuBJDfY5JDfY5yT)bG zd|Bb#;oRZe;oRZe;oR-~i#wbbBA+>bJsX`&F2p14(ASg-EoI= zhjWK>xASLTb1&Tab7Ag$2#R^{WH(GZaJ%`{MDHk z^fniPVbfT>vnpz zEX!nixGc+Rdb=F+$KCXNS(feef?1aN^oUvJZhFTob2mL@mbsf=Gw1m9UODGaZ<=N6 zOwXES>rdaDW$vc;%CdUy^2CGHIel|>oV)3jbIhMTHg50Dmr3i$>Rf*^?7Fh89+_7s zch%2b`{J(s8ZQU)%f~w9X8kkIxo$bDr~K8K7xiEJ!g(|Y+q-{@bBA-c^Dpjj?r`pK z?r`pK?i!a#^JRr|hjWK>hjWK>hjX{{FYa*eaPDyKcK*d3&K=Gj&K=Gj&Ryf&HJ>}2 zJDfZ0b;ljf9nKxj-OitVO|P-@{n+#xJKv{GZ?a{XOwY1qSxqmqWB$0C9%sw4o!)25 zGM}Dk%iK+`v}Nw5huSiC(_8HvpI&3<{OQHEY@O-Rwru_B6SvIW^cq`M&-8j*R_FAI zTjp+h!yWTykB!@V^JUUHvO3qF47;vut4HS5$zAnx*S@%GzsAeK{PM9*xmo|rbFN#? z>M4J9=0*M2zHlDR!S?Ro;@sif?fi>7oI9L5oI9L5oV&(l(tKIr+~M5e+~M5e+~M5q z{EIuBJDfY5yPbb=hjWK>hjWK>hjZ6Bcg^Px=MLu%d);w|bBA+>bGP$nU(>_={Q8_8 z?&sI-^n72I$@GF>meur#Kjx3Sx4z+E*-lUS9hdp^nqTJb{XXRTm${q!(U!TJp7rPW z^l(4tPmlX$>%8DmFIcwz6aVmF?xu(Pj;rVHZ$4O^e|*;$?KpQof8T@Wcdv8Y-kUFz z){)h@{$$v7Wm`QmuTJi&pS$+OUHdg&4(6ASb;`~9XP$H2a#m0It1~a^zxIXmXb!e_ z{}$&C=Wgd;+~M5e+~M5e+~M3cE|ccV3g-^z4(AT%4(AT%Zs%Xz;oRZe;oR-~i#wb< zoI9L5oI9Mm#<^=gcQ|)Aci8KWJDfY5JDj_nKl_?q(&ziJ=_P%>Pn+J;%QBgs)XTD( zUe(9^aW_4zmt{M>t(Rp!J+GI!n_k$<+)a<{W$vbT_BlSiq|f=&YkS!`(}R22`qKw| znY-yFy{w+;<-M%V=>xvZ-SqxG=Fc7*xA*4Dq;+IgTR~ao2v0 zmxKA`W1Vud{+Z`ox17~e{_4z&`mcTAJeq^;-M_`T!@1k}7k4;!ICnUAICnUAjmxC@ zvckE;xx=}`xx=}`x!d^{cQ|)AcQ|)D|Kbkk4(AT%4(AT%u5s>~&mGPk&K>r;;|}Kz z=MLv?=g+?W+0$-1zdoP+9S7U{pLxZ>GP(P&9xSWRyw?Mc`Qz?i|Gk4{`+NWPV42_H zBR+EHaQ7Q8IGDQ!+~uQooV%w!bBA+>bJsX`&F2p14(ASg-EoI=hjWK> zxASLT^GyBm^*lV!)GyonoQJS1lX*6OSyuDR{xN?toM-u$WjoLKFUx$M{a@y8&IDNI zZq5o==5EeIILGIi`g8s~Q@?DTIg4P~`g0z_GI#S#{jz%IOoL^0&UpyS>Yp7oI9L5oV%TW zaffqbBA-+ICstG4(AT%4tw2khjWK>hjX{{XJ2!M%=z^>XULpiw{zyqvP|YI znq^td88yfJaW`kzEX#Jzv{{zYVd`mbsfVe~$UH$Hwiw`7&u8S)J=ohFw>-)g$xj8U*qLqe)(9Z+^m1*IoB;`^_0Il^P>K1UpSBEV0-s(aqe*LcK*d3&K=Gj&K=Gj z&Ryd&X}+v*?r`pK?r`pK?r`pQ{>2^69nKxj-Oj(b!@0w`!@0w`!?|mmyXJF;bBA+> zz3#Zfxx=}`x!d`(uQ@YqKa24B!H_^J31vSeD70iLorJIV*&53-pEEa>xtnuHmJfH&UFL4i?l{Ni zEQ@pgob|D6ojC(!+4^%1$uf6ymc_Dq<}8tAb%ja>XCVMa##I_yQ5C-+OP3)Fu#1PQ*PEj^PKCJvwF&3oq19JwJ)4UbFjVpw>Wn= zcRT;$4(AT%4(AT%4(G0MnKWNkICnUAICnUAICnUAJOAPi=MLu%=Wgd;+~M5e+~M5e z+~M3c&Rz4l!@0w`!(MmX;oRZe;oR-~+1H%SdwzY+*}Ui1?VRPiER#9ocUe|*_U|!& z+|8N5%d(xbf|q4JXY(#|H)jhkb2mRzm%00+ryXp3&gMPm&)LPx)|s<;m#shNDlc<4 zXY($rXU;}mR_C0nyv*I4rF_hvJvMId&6i2*$m(2wGVHpttsa?ICwJA)UHjs${TeR^ z^UKFNbBA+>bBA-c^Dpjj?r`pK?sopg9nKxj9nKxj9nM|j+%=y&oI9L5>~+T-&K=Gj z&fU(ReN7*M^ZnTL5jfwcO&@_}nM@ynWm!!hfn)x-n?3@|vYoT>mt{U@<}Y(MeFT;d zcfYXA-SiPS$LB2ibN-w~zigd3!+&|dHvY%K+|60^JFcGTBe1N_=@GEZ-SiGv_WrqX zdvCr>T1QsXr{I`B8FpRSR*%f9le_9a+#P%2uKgM>2lLCvI^|~lGtaqhIjg7q)tMLd zU;Dy&GzZ(ee~WX6bGP#^?r`pK?r`pK?r`oJmr3(wg>#2hjWK>xAQOVaPDyK zaPD^g#U0Ka&K=Gj&K=HOi$JDfY5JM4AG9nKxj9nRg(pM6c=ob%_x_de`kd!Jq{ z=g*Pp;j%2N>FsjNA9vI9Wm&e<3uam7(<5e?yXhUX%-!^qS>|qf&79-Yd*z%zy;qj4 zGd*jTtv`KpmbshWE6eJc-Z#tKP2Zel^-r&yWB%;1aeHsROj<`)=lYXj*OhJc$hz{efb<0^j<*&}XsQ=m*&Z9XvcUUIY#JSt~7k4;!ICnUA zICnUAjmxC@vckE;xx=}`xx=}`x!d^{cQ|)AcQ|)D|Kbkk4(AT%4(AT%u5s>~&mGPk z&K>r;E9cx9&mGR)&Yyivud(y%b9#-PU$@hnY*{ALvus&b)649bKklZ-*|Kb>_t~<{ zrzhGnchf6vnY-zsw#?o1Ry)V1*Vs9Kda*5AXL__PTYvh*Eps=$#+KDHz2279Iep@m zxtrc_$Nbr2k$H7;SN+_zFYel}@p3S~e5_M$)<5%{>z1>6 z%3qy%QUA3soJVu8z5BN~cQ|)D|Kbkk4(AT%4(AT%u5p<(UsgDGICnUAICnUAICne$ z;tuBy=MLv?=U?36+~M5e+~M5e+%?W!^SQ&h!@0v=ciiFJ;oRZe?flu-^wvDzk4Dt>4kdCpFK8i@6DG<>&WU{e=_X4 zvaKGOS0{JX&t3cCuKgM>2lLCvI^|~lGtaqhIjg7q)tMLdU;Dy&GzZ(ee~WX6bGP#^ z?r`pK?r`pK?r`oJmr3(wg>#2hjWK>xAQOVaPDyKaPD^g#U0Ka&K=Gj&K=HO zi$JDfY5JM4AG9nKxj9nRg(pMAag{r~dcnEMNTHt;te_k-`ZZ0`?$*xi?9^6wsc z=Ve*_>hJ#119$$od)JS?X<4>!e*c#&%lw%i`uWS;{lWA9)5n_6-5VbEk6wzooADoO zeCEFvn?LI;TW8i^w*FjqnY*dyb>^#Q>ReXm)W59$+1K)AU(5F1e3`V4tj_f(!>%ja z>XCVMa##J_z3*p#*Y1nE_G`Qx%r777l$-U>JmhjWK>*SJiYFDslooI9L5oI9L5oV%TWd`-R%=MLu%=Wgd;+~M5e+~M5e z+~M3c&Rz4l!@0w`!(MmX;oRZe;oR-~+1H&P{QP}CcGus#|7{=eNe4glaUXHp10Q|x z@Bh+A-1h5Ve(=k0+;rRDe#XHc_57P|d**8o{^!4U(`}#iTL(YqrU%^ifcv~)*L?fq z9&p>YJo@0j@YDy~_L65D{Ge}tz-_nw%)7_$`kpU5=l|}<9BiE*`J#iZ|NGB4*meKz z4iod}aPZdu>j&Fc<8OV^{m=Oi_;dF^*Lm`bKKxw&_iq01^SWRC-|lx? z^?ds)?sr>t-u$Hdo%P@4^X_-<>py?`{m%UwF9-9>$2#R^{ql6(a#m0It1~a^zxIWB z%pJ}h&fU7cxWl=_xx=}`xx=}`xocb|&6gF<9nKxj9nKxj9nKxj9nKxj9nKxj9nKxj z9nKxj9nM|j+%=y&oI9L5oI9L5oI9L5Y+v_(+i_+Qe)>BPHs?3*f1Fw5-~OX#9c;}< z+~bG${hMoj!oNCL4Uhf0<18b!{oJSh$j-6H54`C(zsMfH?Jxc4j@#q!-~Khr#y|Nt z4mSTsUvr#aWSuuX;k7%*`fs@BaZZuzKKsQ7tLMZ1^y_zyI=}PggVq1`M;&ZmjdR+3 zu3N{~Kjz-b^4mDeqWRA%hzQ4HC_(pmydPI&HCl(y5+2%@>geG)PL;@ zUwe$r&$V@M9&sLV9&sLV9&sLV9&sKUmrwKMhVzK?i1Uc^i1Uc^i1Uc^i1Uc^i1Uc^ zi1Uc^i1Uc^*f@{P=Mm=-=Mm=-=Mm=-Uwizm@A|=8^ZRN4@MX8={bir?@>~0Qc;65E zr?>WX^5MVpPjBt(=dV8Vhi>ib>YeZVid*}7`}QZk;?}+nfA?R$;?}-CAN(_~xV5ia z<9$7w-`BZy`uewiuM5}h^`f3$N9yeLrT$)b_SN`PU-kp%{117<|9P%+>mR)IT>m8x zc*TQ@~`+XA2%I}j{hJK&Kvi18Umbu?2F?W8S z#N7Fe19Rv1=f?eB-F&}qW9#@m99!S-=h$`q-j3Dd_kYZt-~X}t{r->bt8sg8zD!z2 zR;@3?t}EN>k$H7;SN+_zFYel}@p3S~e5_M$)-O-jEob$VzdG}x{%c=2kLKXqVVPJH z=MLu%=MLu%=MLu%=dN*?G+$OYcQ|)AcQ|)AcQ|)AcQ|)AcQ|)AcQ|)AcQ|)AcQ|*A zbJu+CaPDyKaPDyKaPDyKuzk&Q*&o-}=RB{yZ13}2_OeXox$I?G&2!nyGMwkKmt{N8 z8ZXOyon ztEc?cnHTk6`@(rN2j>pw4(AT%4(AT%4(AT%4(G0MnKWNkICnUAICnUAICnUAICnUA zICnUAICnUAICnUAICnUAjdRz0?r`pK?r`pK?r`pK?y!B;ryke8-rnnLFB3h}y*6bv z_w6ssP;YwUvela&%Un-(%$?r!_;7d6W$xy_{c~Jz`sV9R-#T;O{<8JwzWrs_)tlZN z^~}BZ%j(pF-njbprpNZxxV<-DCaoi@)|X+|m2LINygIq7{=?m|FYel}@p3S~e5_M$ z)-O-jEob$VzdG}x{%c=2kLKXq;oRZe;oRZe;oRZe;oRZeH7=9p%L-dZhB$XPcQ|)A zcQ|)AcQ|)AcQ|)AcQ|)AcQ|)AcQ|*AbJu+CaPDyKaPDyKaPDyKuzgM6ob&zI^vyZn zr%m6SWtmLhoMl-}-<)L`PT!nm*-kH*WtmTpm}Ty!Z_YAz(>G_CyXl*Aj(^-ee)^n0 zy;qj4GktTGtv`KpmR)yxuPm!)dfzOob9&+|b2q(mmhG`|dvCr>T1Qr`FT<`Y+v<^d zb#hnz+_f+6+OP3)Fu#1PQ*PETPuDGH^_0Il^P>K1UpSBEV0-s(aqe*LaPDyKaPDyK zaPDyK8kb4)WrcHxbBA+>bBA+>bBA+>bBA+>bBA+>bBA+>bBA+>bJsX`&F2p14(AT% z4(AT%4(ATr*POd`{#=-Ix6YpzbMDr%Oy=CJWm(O+Tgx(>bGMddJ7-BP%Y4q5TIO!f z-CE}E-gi5gyE%939G|nB&iQk8)3SBu+^uEn&$(O6t~+NpEvskF&RSOIoT;_U-JG?x zY>$oGd-G+|IntEc?cnHTk6 z`@(rN2iv=Ui*tu_hjWK>hjWK>hjWK>*SJiY&mGPk&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj z&K=Gj&K=Gj&Ryf&HJ>}2JDfY5JDfY5JDfXgU(>(i{Q8{!9p~5W^zT@f$@K47meus{ zSeD`R?^u@Y^rTpp`Shw-=5G3TEOR&gJC?bd{vGG|^nf_$PY;M?>rDTSW$RB*jb+!J z9uUj>we-+~)j7R6cAUHE*|BVojobV5?AURcw9aOASzm@-SGLt7^XlZT`nhXg+_hih z>C=*S>Hb&B6BW-{Rci+~M5e+~M5e+~M5e+%+zf=F1A_ z4(AT%4(AT%4(AT%4(AT%4(AT%4(AT%4(AT%4(G0M?wZdX&K=Gj&K=Gj&K=Gjwy$|! z=KT7c=Vi{X+j(AQStj$m%(ATJd6{Jy&hs+MvYlr@mSsNAhAeY8&&w=xH}A)mxtr%@ z&hbY)>gUh-^UTGvb>?}QW$VxLGRv+z&s;34XP$XkR_8nmv&`K*BeQIejoW+kWzssb zYJC}YUD;NT%&U{T>gTR~ao2v0mxKA`W1VudetEiXIjg7q)tMLdU;Dy&GzZ(ee~WX6 zbBA+>bBA+>bBA+>bJw^`nlCGyJDfY5JDfY5JDfY5JDfY5JDfY5JDfY5JDfY5JDj`5 zxobXmICnUAICnUAICnUA*uJKZ!1?t#eFV<0+vy{)ER*RYuq>|(Q{xWydM_~DI_o>U=O&@`Ce9odj=g(R6%hs7b0?XE)J_5_GJ7>`^t7m!vEUR;R z1T1qmy#to*v2lBEzD!z2R;@3?t}EN>k$H7;SN(^(V_)30U*qLqe)(9Z+^k=ou3OIP zDSvh5Mg7;la30OU_U_-}+~M5e+~M5e+~M5e+~M3cE|ccV3g-^z4(AT%4(AT%4(AT% z4(AT%4(AT%4(AT%4(AT%u5s>~&mGPk&K=Gj&K=Gj&K_ySZ0?*&Z9W_vXu_b!650GVHpttsa?ICwJA) zUHjs${TeR^^UKFN@N88@(uPu}MZp*5E+%l|Bw`}!*_PM>x=QFNl?&|k_e9t`kn{!uxaN~Mp z`?u!nk=;7=8Ml7@$6dF+-)g$xjdcG!uYJ|uJa?St4(AT%4(AT%4(AT%4(AT% zu5p<(Usl*UGQ_#Vxx=}`xx=}`xx=}`xx=}`xx=}`xx=}`xx=|@oV(_8hjWK>hjWK> zhjWK>hwZDrPPl$g_Ff+-nbaRjR`rdNVg00Jt5;F47d?!69o3iWaQCS@&Ru=1jO*pp ze7&4nr+!%0uTPfi);~)<_0>{m{kGI!A1?c9+}@inlh%<{>&vj~%C>rBUY*=k|KaY~ z7kBN~csZC~KGrEW>zAkNma}@wU!8eT|Fy6BaOIBE+~M5e+~M5e++nX5HDj+kd%?NG zxocb|&6gFnjtp_`aPDyKaPDyKaPDyKaPDyKaPDyKaPDyKaPDyK8ZU?38P6Tg9nKxj z9nKxj9bR7#yYK#d!E-;=vc1p!RL9St`FfuFsg`9m_fsv)aPFsCmhIdlv@G+vcW9Zr zxu0tJ;%=F{xu5DBpL=r7`EyUsvUTQus%7iX{Zz}YJNG^Asavz1J5*CiTmZRedyMSbq)K z>fO-KDLozf`Bk3|?q+PqxvQ^-alI{?ueU|()E~t9^$l^|`iZEgJ|pU^FNyl=OJZM* z+k5k6(mJwgeHnIL*;bFttCPFx=dOKm*M5zcgZbrSopQ5&dAe>ntEc?cnHTk6`>HQV z?l{dI&K=Gj&K=Gj_Ign>_PVndoI9Mm#%0ocSz+tQ5a$l(4(AT%4(AT%4(AT%4(AT% z4(AT%4(AT%4(G1%a>$+W+~M5e+~M5e+~M3|`|5lu+__cu-g#Cs>6|NBb^etMI~Pl~ z&RpvC@`%fMV%&AU*6}^_7tYsR=W!W#CRMLHXHvCJ=XzPc^S)fSbHLQo`C#ho+%WZb zo|t_#Ztu;PN$bd}^<~&~Wm`QmuTCzi|M;GH?2EhhYrGuHFCXiaoAt}nb<0^j<*&}X zsQ=nm=ZWQx)7;_Q;oRZe;oM=b7d7MD;oM=bJ9}?jCe4=>wvG&O?r`pK?r`pK?r`pK z?r`pK?r`pK?r`pK?r`pK?iw$L+!@au&K=Gj&K=Gj&K}@Z0BBuWtq=C49ncjeI3i(&3zrq+|7L*=lI+kaL%851D35b z_jN2=f9~s8cHOzJV_7|OZ^klrbI-=I`sZGbW&3K}-kUFz){#}~%dqRpwt8ebBA+>bBA+>bBA+>bBA+>bBA+>bBA+>bJsX`&F2p14(AT% z4(AT%4(ATrSLf~H&f&LrXYB9KpmEo^{j%yje;Ibpzigc$-_I#$%lGrEegWLoM}WKf z3mA9Ce)FBN-#YavuzvjuT(`ak>Z#uWclAL~fBg~ct8sg8zD!z2R;@3?t}EN>k$H7; zSN+_zFYel}@p3S~e5_M$)-O-jEob$VzdG}x{%c?LN5~zgxx+HCCe9ts9nKy0dQmg> zy0aIYJDj`5Wzu|EVe7~c=MLu%=MLu%=MLu%=MLu%=MLu%=MLu%=MLu%=dST`$er=r z;oRZe;oRZe;oM>S>RdS7d2#mMIdU@Td^uU&>vE2t4Cn95`x=q0v(9?GI0LQMQRmum z*Lio`bq=0!XTddp{ziGO(|LN<@0>l??fgCUbS|GdJFiduo#SU;joW+kWzssbYJC}Y zUD;NT%&U`&>gTR~ao2v0mxKA`W1VudetEiXIjg7q)tMLdU;FADzua+}JDfY5JDfY5 zJM8tMX6$umFF1ENca6)W`Le>+ks;0<&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj&K=HO zV$5h=Jm;$3c+7VmJm;<6 zc+a1D_xK&{uWH>zjOxV=%GbN207|D1_??rYAy(@I%hPqsSv}>i&b+Aq+85?AcQ|)AcQ|)AcQ|)AcQ|)AcQ|*A%cS|T!nwn_!@0w` z!@0w`!@0w`!@0w`!@0w`!@0w`!@0w`Yn;30bBA+>bBA+>bBA+>bBFD#zP-49zV=?9 zUzybZS61}}mSO#ZWm_L%nb%*KyZR1uS3hFz>QijI{>A3k*VsDsJGOp(kX^U_$m*$Y zvO4Rhtp55e+gIcE-h7#~j;vZ=hFw>-)g$xj8U*qLqe)(9Z+^k=ou3OIP zDSvh5Mg7;l>a(0XPIHHIhjWK>hjWK>hjWK>hjZ6>eU@`)Ja;&EICnUAICnUAICnUA zICnUAICnUAICnUAICnUAjdR!h`Yh+pcR|3Z;5!cH?x%n9-Q%zM zU+|pi0=Eo0K=ih(h!Rr6QUpm+x8@Ko7bJseu zYJC}YUD;NT%&U{T>gTR~ao2v0mxKA`W1VudetEiXIjg7q)tMLdU;Dy&GzaGn=MLu% z=MLu%=MH-v*$d7c&Ryd&X}+wmb!3QhhjWK>hjWK>hjWK>hjWK>hjWK>hjWK>hjWK> z*Eo00=MLu%=MLu%=MLu%=MLLf?^~uv_xXNidUT)fbEePp`Tl46JfH82rbqYrerbAi zpYNll&-3~IYI<~^@4Ke|_W6En`f{J|(~S52&HUciS*Q1z*6)3$>-IiVJ-yFVXYVJ~ z-}_AaYJ7Tzp3xXZ_PV{oL2|R6qA?y!V;r z_de4)z0b6M?=xMu_nGSHeWp5lpQ-+9U%k)F9jCd&xx=}`xx=}`xx=}`xx=|@y!V;8 zGoCw~JDfY5JDfY5JDfY5JDfY5JDfY5JDfY5JDfY5yT*H;nLFdT!@0w`!@0w`!@0xu zReu?;!TQelo>M;>-;3%~<9k&7YkcpjuZ{0%^}F%Cu0A-vXVxFb_ssg{_?}rm9pm-c zF~9yh)~PR#_3PK;y7loGS^*AK|P8uvY?`Mwvmj_*;e?|WC*^*yb6e6Ooc z-!rS<_ssU?duIDJUJmA$k9Eq;`sL}m<*c6aS7%<-f9pHznREtPHkOl4l5Q|{`2%H4c^v+p6f zt6!?|`ly;;e^u+$ch&m!V|Cs7w5q56t?I0=tNQErYF~}pd-G+|IAsa-&D|JwV@wy*KFlv-b>r-}YXj@8{lQ^nKoYkG}tVuhP#2 z?^XJFVZ5Is=J)f(I{n~x1Uq$>F1X^`?;q6e%{$v<9^mR-+O@8@!p{Iy=UmU z-b+-E_ZZdby+`$XuhPD}S82b-%fbBeu}-;JzdT*HoYhnQ>dcG!uYL9NE_a;f4(AT% z4(AT%4(AT%4(AT%uJL}}<<5BSaPDyKaPDyKaPDyKaPDyKaPDyKaPDyKaPDyKaPAuK z=UwiM=MLu%=MLu%=MLu%+gHD*<9>g)_kORJNx$#Qs?Pyr*yjVX?Q;W}_jv*rea^sL zpFeQd=Mu*Iyu$oG$FNSHZ&<(2JzTfXL)6pfB&UA0W!QCP zTRk$bPA;mSyY|Ih`!!w;=9iCk%FX)a>AK~tp7K{`Uetf>tIt(($7$|x?r`pK?r`pK z?r`pK?r`oJ?{k&h8P6Tg9nKxj9nKxj9nKxj9nKxj9nKxj9nKxj9nKxjUE_VOk~`zM z!@0w`!@0w`!@0xu)%%v+*3AeU40e|0Ap37s;^qOS0{Kl+1g7#YOMCxa<8G zcfC(D-upN6dtYar-tSqz_kph4`$P5gzEPdMpHzSEGwrK!dvCr>T1Qr`FT<`Y+v<^d zb#hVt+_f+6+OP3)Fu#1PQ*PETPuDGH^_0Ild!MQPYhS(3%pIq>!@0w`!@0w`!@0w` z!@0w`YrOZFxig+SoI9L5oI9L5oI9L5oI9L5oI9L5oI9L5oI9L5oV&(*pP4)3xx=}` zxx=}`xx=}`_SN5maDOMV_x^q)lm4zGtNz|3!~PB>+x|W!^ZstdMSsuYuD^3}*WbU4 z_jfV#`+J#n`a7ES`}>;f_IEe+^!GS*_IEn<_xC&dYTVwNFO$}hRqM;J>&muzWL}+I zR6lp^i@Ww~yd2CgAM2Ex^~=+B%UM0;ug<)v|Jql7zsnt`xx=}`xx=}`xx=}`xx=}` zxof4<;yy3>__Hs@%{P7g*)QX-|Lo0YAB}f?+0AEvjc45Z=Ckj{ zXZ*(po&7j&{$~%mQD2fbedmL2eAC^&e*1U)<~Q#6_VqAcUlQ}{OJbe+l32gKB(7Uu z67|%VM4j~|QGb0&F8kVEB)2{F!RP$vzT?5?IyLcGdEJNK;UQ-|-};FU zIqQ7x6CPq;TmPND`yn^J`WK(D`})J@@A&p5FN|eyOZMOT%<2msbFj~{9{$e9@3_ynzU-S0_L zZ#md!M~(YTsrf!@Y8{_JwZ6}$x~|Wxs>f$p)#)>?>i3yg`|_Ds`!!w;=9iCk%FX)a z>AK~tp7K{`Uetf>3-f4?=HT4n+~M5e+~M5e+~M5e+~M3cE|ccV3g-^z4(AT%4(AT% z4(AT%4(AT%4(AT%4(AT%4(AT%u5s>~&mGPk&K=Gj&K=Gj&K#b!>%ja>XCVMa##JwXVJ&LxNE=0%fbBeu}-;JzdT*HoYhnQ>dcG!uYKV> znuBwPbBA+>bBA+>bBA+>bBA-+xJ;TaE1Wx=JDfY5JDfY5JDfY5JDfY5JDfY5JDfY5 zJDfY5yT-X|K6f~GICnUAICnUAICt2-=JWRb8piW^`?9^y=k3cfna|tLuk-o5eOZR{ zdHb?#=kxYuna^j-%iPW9?aSQF=k3ef&FAgs_hjWK>hjZ7sOqwq%oI9L5oI9L5 zoI9L5oI9L5oI9L5oI9L5oI9L5oI9Mm#<^=gcQ|)AcQ|)AcQ|)Aci6su{U!hK{QCUE z=NxSBPk-{kGWn{9A1ten{&NS*@TXtn`@GLPSmsav!zb)GcQ5>T5N{bLR`|1Z4ht9RTw|K%$Ww*Hg;^1-fq<3D}X&QZ^Yy!v2uzV2BEtN%^k zdayk2Si z9DaN6e14g9ZojNL&tHa}^DkRx$oqUo=FXPK+|@6DyZQ)lSAPNHkGS+lFu#5T)~Qc{ z_3K~Yy7e_sPyG(mSsw)T*B`;Y8n^f6%cON=)%r5*y0WbvnO7%w)z4k~;;#J~F9-9> z$2#R^{ql6(a#m0It1~a^zxGvsgxqnOJDfY5JDfY5JDfY5JDfY5yT)bGd|Bb#;oRZe z;oRZe;oRZe;oRZe;oRZe;oRZe;oRZe;oLROUGuraxx=}`xx=}`xx=}`_ErB-TwhUp zuivOl>O(54`jg7AzNNCAGu+PConD!}?&^Qa-Hh!xclAp(K4+$#^Xsq5U42)rUq4pY ztxv0Z>ffr)`nsyWey{e`xV<-DCaoi@)|X+|m2LINygIq7e(u^AckS1BIhbEQ)+smZ zm#6ENvwF&3oq19JwXgcU=8n_c;oRZe;oRZeVVSELd)?U!&K=HO<1%T!tZ?pd?r`pK z?r`pK?r`pK?r`pK?r`pK?r`pK?r`pK?iw$L+!@au&K=Gj&K=Gj&K#u5^`mS34lP>*U zUAI21>ZyOLI_vAI{`$SzSL62He3`V4tXf}&U01f%BlGIyqWTYa$G*60zsAeK{PM9* zxmmwFUALUoQ~v7Ai~6s9)$cWToaPSa4(AT%4(AT%4tw3%3(g((y0iDjWzu|E;oRZe z;oRZe;oRZe;oRZe;oRZe;oRZe;oRZe;oRZeHO^i0xx=}`xx=}`xx=}`xx@DLB`^B? z^Y@@{_@0C9{Vq>DSSIiKNQ*Zs8oui%~edWRGeCRU| zR{vwZ`Cxl&+}@inlh%<{>&vj~%C>rBUY*=kKX>hmyY_3m9Lz5t>y(@I%X7bGE;*~G z{MDHk^EPPtjXJYBb( z)l>fJ%!~T3ebsj|cbw)9%fy;EcQ|)Aci8Ji&DiVCUU2Sk?i!a#^JRstBSV}!oI9L5 zoI9L5oI9L5oI9L5oI9L5oI9L5oI9Mm#>*jh#&d^rhjWK>hjWK>hwaP#F}}{R`)07c zyFX@M3**lHF<4gakHIo@e+-tb`(v=o-5-OwbAJrx&iyf%JNE-M?mnUByMG8<$9+ZE z`tCQvuIoM|tRD9#VeZ_|gw^kUCTw4g+k5k6(mJwgeHnIL*;bFttCNfB=dOKm*M5zc zgZbrSopQ5&dAe>ntEc?cnHTk6`@(rN2j>pU#F{vFICnUAICnUAICnUAjmxC@vckE; zxx=}`xx=}`xx=}`xx=}`xx=}`xx=}`xx=}`xoe!e=5vR0hjWK>hjWK>hjWMRYwp`W zzdq-_{qyT~?%Q9M$=tWUEUUS1e_4ie-~O^}=f3@Ana@4y%iPU<`^((T>tLC?xo`g* zpL@TT&7b@Bm#s7R?Jrw@?%Q8>-MMdnSv_;#{<1pfzWrtH=3f0}du-g^n=g~rkyY!< zu|CQG2i7s7&fZDy#aF%CNqrvegsQ&lj2Nm5I5l|0#Db zzw6N#mAm?-8lRp==luGsTBp9N)~_F{>(-}LJ@s!@XMJ7OU%yxTYTVwNFO$}hRqM;J z>&muzWL}-zRX=y_i@Ww~yd2CgAM2Ex^~=+B%UM0;ug<)v|JqmmUUSE3?r`pK?r`pK z?r`pK?r`pK?i!a#^JRr|hjWK>hjWK>hjWK>hjWK>hjWK>hjWK>hjWK>hjZ6Bcg^Px z=MLu%=MLu%=MLu%+gJTVaeYPYy?&!IsSl~F>Q5@ezjo>ODqB4d7^r&T@mZ&hb~UDaQ|SNm$*-kUFz){#}~%dqRp zwt8e{>?yr}=$SN&dd$7$|x?r`pK?r`p~ z%+-v&?(7BU4(G0MnKWNkICnUAICnUAICnUAICnUAICnUAICnUAICnUAICnUAjh932 zjOPyL4(AT%4(AT%4%^o}m;LVdV{bgz-sidO9hb>Gm%S{jc`kcdhVxwZvTWzM>}8qH zGsw%_&2!ny+|6^@%iPU#+2{B?+k4KR=dzcrGtXr&TYsL*UUuDiE_+!$^IZ0_I_J6U zW%bXq*vt0VxV<-DCaoi@)|X+|m2LINygIq4e(u^AckS1BIhbEQ)+smZm#6ENvwF&3 zo%6i>?nV9AzHlDR!MVe^!@0w`!@0w`!@0w`!?|l*Ce4=>&K=Gj&K=Gj&K=Gj&K=Gj z&K=Gj&K=Gj&K=Gj&K=HOi$JDfY5JDfY5JDfY5J8WOmH)ns=;OU#QZ12-I=lB^k zU(eGwXIWO$H)mOf)AMCnw$lq{S?1FtW|_O`o3qT_z3+A~chhU;9G~7R=ltotvTU8{ zo3m{F>6^3cy3;pjSv}J?XPLX{o3pI`>6No=Uya*)^JUUHvTA)9c3s(4kIbu+yXxnz zeR0=*jhBP@hjWK>hjWK> zhwbZ5-*=bu=fVek*TMGw&%feenY{4h50=#z{HcRw_}^dk=l9>r_NPAMV41)AxBs^t z=kAxj?qKeocISh+`^e|M*UmBi=np&C{F~o!=N-4s`#k<&>;K^04|d%z{(tVYbJX+b zmmRFm-~85t)&IY~{$P7-+}@inlh%<{>&vj~%C>rBUY*=kKX>hmyY_3m9Lz5t>y(@I z%hPqsSv}>i&b+Aq+855FIXHJXcQ|)AcQ|)AcQ|)AcQ|*A%cS|T!nwn_!@0w`!@0w` z!@0w`!@0w`!@0w`!@0w`!@0w`Yn;30bBA+>bBA+>bBA+>bBFEg{xAIW{Tjxf`0Ru2 z{g=P?V43{uPdZpu-}Gk=mf_uh^waj=%Jz3Y`(T;>%I|;bj&t`%Pdk{q`TSwWx%-?K zKXTdllOJ%f`Cs^RkJxeReC*#p*!n+npMzcZJAUnN?Hu(y`Idv#d8cO_to{%9ri1OP zaeHsROj<`)tuMo_E8FUkd3ADE{oJ)L?%J>MaxlMqtW$2*FHhGkXZ4i7I`g9bYhO5z z=HT4n+~M5e+~M5e+~M5e+~M3cE|ccV3g-^z4(AT%4(AT%4(AT%4(AT%4(AT%4(AT% z4(AT%u5s>~&mGPk&K=Gj&K=Gj&Kk$H7; zSN+_zFYel}@p3S~e5_M$)-O-jEob$VzdG}x{%c=2kLKXq;oRZe;oRZe;oRZe;oRZe zH7=9p%L?ZX=MLu%=MLu%=MLu%=MLu%=MLu%=MLu%=MLu%=dN+?n$I219nKxj9nKxj z9nKxLuQ~r`zlQOg|FdlGbNNb^Xq)h|5=vdod2^d+d2PdS>|)r%`$g${?9UZ zbN|re|5;Y&od2_|{yFn!*}fXL z_vXu_b!650GVHpttsa?ICwJA)UHjs${TeR^^UKFN~&mGPk&K=Gj&K=Gj&Kki+i~l> z<%AK~tp7K{`Uetf>3+K@soI9L5oI9L5oI9L5 zoI9L5oV&(l(tKIr+~M5e++p=_fpdp*hkbo=hjWK>hjWK>hjWK>hjWK>hjZ6Bcg^Px z=MLu%=MLu%=MLu%+t=Hl@bFQ zU(42i-Bq`ek+A`X{ejR{xj1@?iUF+}@inlh%<{>&vj~%C>rB zUY*=kKX>hmyY_3m9Lz5t>y(@I%hPqsSv}>i&b+Aq+855FIXHJXcQ|)AcQ|)AcQ|)A zcQ|*A%cS|T!nwn_!@0w`!@0w`!@0w`!@0w`!@0w`!@0w`!@0w`Yn;30bBA+>bBA+> zbBA+>bBFEAxq-dzF6Vge-klq0Tqe#9#Ika3AeNzX1F>wK8;E7@+(68oa|1DV&JD!e zIVZ7k=O;Gbxr*32&RfLRcMcela^N8|hbg2BaxocnCwO`}qV1D^nr`)Vxo~~QY>M4J9=7qa!UpSBEU|+ZXEzTXz z9nKxj9nKxj9nKxjUE?xozN~QWaPDyKaPDyKu==^fxx@C(9nKxj9nKxj9nKxj9nKxj zUE|y}pF5m8oI9L5oI9L5oI7k^uGiP6IbBA+>bBA+>bBA+>bBA+>bBA+>bBA+>bBA-+xN9`uHE`~5?r`pK z?r`pK?y!B`=U2aW-<#p5eB8nI{^Y;=HRt=c$9~~gF3aj0KkdtxW%%+>dHk|$-~NQh zEzA5VcX;eFcQ5*&M=x_XpSLe__v%0Sq;vci-tXhj`CshjWK>hjWK>hjWK>*SJiY zFDslooI9L5oI9L5oI9L5oI9L5oI9L5oI9L5oI9L5oV&)kYd&{4cQ|)AcQ|)AcQ|+W z`gP}7mi&6gCGVc|=D*P&-|`ug;YPG7gi`+7FN zuXF44^>6)N7p~juMLoTa)YZb5*7uA~*Y%7}^?079Iz6LP z{hq&RU!KcpzsAeK{PM9*xmmwFUALUoQ~v7Ai~4)r*;lW-+;N&aoI9L5oI9L5oI9L5 zoI9Mm#(Ul6&Uo%{?r`pK?r`pK?r`pK?r`pK?r`pK?r`pK?r`pK?i%lPmpkLR!@0w` z!@0w`!@0xu)w$nZgPjNNdrs$s`(D)f;l4+8uDI`Aoj2}#TIZ1aUf22LzGrq$yYHEu z)9!m_=bRgN*7v?wocW#8Zk^6)w|?ieyKd*StEY3?)!8}i>hGNP%f9xUcHeWF?|V_} z_#V~zzISz9-_xqc_qyuzJ+u0K&+MFb-!t2<@p3S~e5_M$)-O-jEob$VzdG}x{%c>I z)1Es{bBA+>bBA+>bBA+>bBA+>bJw^`nlCGyJDfY5JDfY5JDfY5JDfY5JDfY5JDfY5 zJDfY5JDj`5xobXmICnUAICnUAICnUA*uFY{*lVzJiG9!Mykg&rI>*@esLnU`y{mJN zeNXE=WZ&yLC)xMF&QCs`J-z4t&gFY%=PeuW9A@)7pV>N{+id;Lb9UX%c~(#7KdZBI zq1E4c(e~B2?>Wu)y{L73k7|A2ySlFLY1QLAK~tp7K{`Uetf>tMj6B$7$|x?r`pK?r`pK?r`pK?r`oJ@4V>T8P6Tg9nKxj z9nKxj9nKxj9nKxj9nKxj9nKxj9nKxjUE`e>ojc>X!@0w`!@0w`!@0xu)%||B`vC2| z`vYateS@;n|bI=c^3{oS8wUya*)^JUUHvTA)9c3s(4kIbu+i|XgDeR0=*jhBP@AsahE{C<1}|TcQ|)AcQ|)AcQ|)AcQ|*A_xHQp8P6Tg9nKxj9nKxj9nKxj z9nKxj9nKxj9nKxj9nKxjUE}@zE_cRrhjWK>hjWK>hjWMRt8?LS=f&B3=g7&V^W|jK zxpOk?JUZESPMypl??fgCUbS|Gd zJFiduo#SU;joW+kWzssbYJC}YUD;NT%&U`&>gTR~ao2v0mxKA`W1VudetEiXIjg7q z)tMLdU;FADzua+}JDfY5JDfY5JDfY5JDfY5yT&`mFL%ashjWK>hjWK>hjWK>hjWK> zhjWK>hjWK>hjWK>hjZ6>=lJE$c-!J8uK$P4bq#EdXAWp%BK2d*1lxfevOxd`Q>AsahjWM3?;1FFICnUAICnUA zICnUAICnUAICqV^M)O?*=MLu%=MLu%=MLu%+gJT%aD8X&y?!(@sZWip>R%(n`r630 zem63&4-R+r$KkHNIdZL^j`8~Jm|y=L>(rOW`t|E^-TL^br~W?btnZKd>jz|CjoW+k zWzssbYJC}YUD;NT%&U{T>gTR~ao2v0mxKA`W1VudetEiXIjg7q)tMLdU;C;bQ0_R* z9nKxj9nKxj9nKxj9nKxjUE}ow%AN7t;oRZe;oRZe;oRZe;oRZe;oRZe;oRZe;oRZe z;oLP|KcL(h&mGPk&K=Gj&K=GjwlANb_H)7Ks@UFr-rCO*pPyn``TP{i(C4REwmv__ zGWYo@=ECQvm^+`JV(xri+_=w?oA2{wY#pCFW9$1o8oRE~sj+%|-i^8Qc{f(S&%3cb zHg50Dmr3i$s`X{qb!A&UGOtc9s-L^|#a;U~UJmA$k9Eq;`sL}m<*c6aS7%<-f9(tB z(HxvREE8+u+~M5e+~M5e+~M5e+%+zf=F1A_4(AT%4(AT%4(AT%4(AT%4(AT%4(AT% z4(AT%4(G0M?wZdX&K=Gj&K=Gj&K=Gjwy*k!;`)l(`@=8&US(1rQd#}aOTSkc*0)r) z^)r=ueNMTn|0#F%Mdhx3smAN0YJUAyt#iv)e9^vktY1G?*R4;hdg|Y*&icBlzkaXw z)wsPkUnZ?1tJarc*OhJc$hzAkNma}@wU!8eT|Fy6B zz2=V7+~M5e+~M5e+~M5e+~M5e+%;am*W4M;9nKxj9nKxj9nKxj9nKxj9nKxj9nKxj z9nKxj9nM|j^?S{o@!a9u;oRZe;oRZeVf*U&W!!Vk_TKZ(GU+*JS@nFh40~=`wmnZR z^PaQjqUW!K-gDgM_k6c?dhXl$JrBNLGnePh)zkCi>g>64_4mBF zeKl_H&6i2fo6D;8W!QCPTRk$bPA;mSyY|Ih`!!w;=9iCk%FX)a>AK~tp7K{`Uetf> ztLM#g$7$|x?r`pK?r`pK?r`pK?r`oJ?|Jjw8P6Tg9nKxj9nKxj9nKxj9nKxj9nKxj z9nKxj9nKxjUE@7(o;%~Y!@0w`!@0w`!@0xu)$_}^=bG)k=bdHJbI`Kt`DhvT+_Y?a zo?7NTXU#>=Uvt-U+1&NKw(*|hHoxb)tI(x2M{XK7PUya*) z^JUUHvTA)9c3s(4kIbu+i|XgDeR0=*jhBP@bBA+>bBA+>bBA+>bBA+>bBA+>bBA+> zbBA-+ICstOdGp*E&mGPk&fWgoi#wb)-2gex~bo?xlJ<4^y3;ld1mB&$O?` z?Y;TjwT`S>Uxr;*w$&r^>g2BaFYb0<+_hih>C=*S~< zm&v^6&ba7#H12v%jk}&-Gv0G;=J&jtb$SlY`aK`#x;;0io}Q;uXV2fMzvu7lt8sg8 zzD!z2R;@3?t}EN>k$H7;QT^PtFYel}@p3S~e5_M$)-O-jEob$VzdG}x{%c=7f0sK> zbBA+>bBA+>bBA+>bBA+>bJuv!-{sDD?r`pK?r`pK?r`pK?r`pK?r`pK?r`pK?r`pK z?r`oJ@AntEc?cnHTk6`>MZr?l{dI&K=Gj z&K=Gj&K=Gj&K=HO<1%S}{mpY{Ja;&EICuMRFYa*eaPDyKaPDyKaPDyKaPDyKaPDyK z8t1P0^*7I*@!a9u;oR-Ny|}}wH)4I``Fh=fRraIkDF1{8;OEuB_{J-mH2$hgO}PPpkgUt+lVl?Y;TjwT`S> zUxr;*w$&r^>g2BaxocnCwO`}qV1D^nr`)Vxo~~QY>M4J9=0*M2zB;!ycbw)9=MLu% z=MLu%=MLu%=MLwt@y@Nyo$=h^+~M5e+~M5e+~M5e+~M5e+~M5e+~M5e+~M5e+%?|0 zwYf8%JDfY5JDfY5JDfXgU-iqz_0hKX`fJOizT2{@AGZwa(=FTjcgwuK-dxo0o4dJ> z@%;U+{@}*z8*YC6#H~}GaqHKA+;!_quAcgptFu1l>aV}KeKl_H&6i2*$g1^a*mY%F zJugeG)PL=({^q&kGw74Z`XS1yK8Z4{f1+&bt0?pOEpkyGM(*m*$X$IK zjn~i7{Q5jvr~Z%DuP>zQ)-O^$^^sI({Uz03-%0yw+}@inlh%<{>&vj~%C>rBUY%T2 zKX>hmyY_3m9Lz5t>y(@I%hPqsSv}>i&b+Aq+E;xibH{1!aPDyKaPDyKaPDyKaPDyK z8n5qU?u_RS=MLu%=MLu%=MLu%=MLu%=MLu%=MLu%=MLu%=dSVkPUg;d?r`pK?r`pK z?r`p~eRVDz?z}jA?;JUqbiSOdI(JTnoku6z&Z(1m=ht!3xpv%r%AJn$?zrn5JmZ~@ zXMX4AS*P>#tlv3%uG{&0>gilQb#`8#`a8$Zz8bgp=F6mYWYzjI?7Fh89+_7s7uC;Q z`{J(s8ZQU)%f~w9X8rPX-Evk>`KvQ8>c95YIexk0Gun!VS5O(ykalU4oNWLO_J+1B4p=JkE!qJD7P&EJ>L_nGyNGhSag^XoTf zo%+yOzy5TtTi-hM)Xz?x^|@1j{qO9naeHsROj<`)tuMo_E8FUkd3AD8{oJ)L?%J>M zaxlMqtW$2*FHhGkXZ4i7I`g9bYhU%h%N?h=!@0w`!@0w`!@0w`!@0v=clO?R{qJ&T zJa;&EICnUAICnUAICnUAICnUAICnUAICnUAICnUAjo1G!cgAyvbBA+>bBA+>bBFEg z=kNQXeJ$WWzU#sEe)l)OaK~lx&aXXKR!{uH7wotUU+}1dW&6*%rXct!Rmk2JO6+7?gZMltgi1pfhjWK>hjWK> zhpp?MU-0eo+b#U?AK$UHU*RD;mdRh;ZpX5E^`&+!!*71YJ?62pz1H1#Eb}Y;=|7!z z?r!uWJLc{`U2(_Uo%h^tn?Blq;U+uQ|JiT3`?MS9U;c|78~>75+p&3H|2ub^KI(b- zOLnZz+dOH<>i@P!?by0%xAywWq;X``_%du>*;bFttCPFx=dN{e*Lt;=gZ|}XoN_aM zd78JJ)l>fJ%!~TBzHlD(!MVe^!@0w`!@0w`!@0w`!?~+nCiRyU&K=Gj&K=Gj&K=Gj z&K=Gj&K=Gj&K=Gj&K=Gj&K=HO?cCL$JDfY5JDfY5JDfY5J8WI;w~yP0-`d-sUncF_ zFRS+Rmtp(-%eMXhW!`-Oxa)oa+;txT?z+E#_U=2NfA=FWPWLG=e)lghZ}&A&Pxm`e zXZJx+fA>eQuG+1={xWGCSv9^4n^(5gBlGIyuKKxaUEH-^?d70<`533%j9;GSEob$V zzdG}x{;jX>kB~b~bBA+>bBA+>bBA+>bBA+>b60!!N64M_+~M5e+~M5e+~M5e+~M5e z+~M5e+~M5e+~M5e+~M5S-u)4Br#*K#cQ|)AcQ|)Aci6hRe<<$0qSoI1MrG1{NM+Ui zNoCl5OJ&>rOl97EPPyp*r`&a4RPMT8s`l=qs(<%aHBR?kHGcPFHE;K6RZsVCRcH5g zRe$$;on!L&KCsqaf0;CntQud2%`4mLk$H7;QT^PtF78^d_Hxj_e2i0W#xGCvma}@w zU!8eT|JGOcd(9oExx=}`xx=}`xx=}`xx=}`xvRbVz2;7P?r`pK?r`pK?r`pK?r`pK z?r`pK?r`pK?r`pK?r`pE?|!ej)1Et=JDfY5JDfY5J8WHf^joL=`VCax{SK((!EdHI zPW+at*w#aMyaZmxKQ0W1Mm`etDX=oYhnQ>dcG!x4v*5 z^})Hrxx=}`xx=}`xx=}`xx=}uT_*LH70w;b9nKxj9nKxj9nKxj9nKxj9nKxj9nKxj z9nKxjUG3b}pF5m8oI9L5oI9L5oI7k?&wl4~=a|7SdfSez{X?(bu}t3g!X3-%4v*fk z46pdlb}ZY6ea((#{-KXQXU632vtPes?!N8uJLc|X-|~s}*PQi<{s;f{f_bcQo_A)) z#{ZtD?AW|-{g*pd&uhPJ$LhT7H|$vbSH9hjt*drxufI$hM^=q5!{(K3^~k(BxvPHe zS{HY%S9>|=Up~euH{+M5dCOTn<*&}XsDJAV=TRS=JDfY5JDfY5JDfY5JDfY5yV_+^ ze_7$&;oRZe;oRZe;oRZe;oRZe;oRZe;oRZe;oRZe;oQ~EUH!Skxx=}`xx=}`xx=}` z*45wXxWC`6y}#>a(%<{C>O6o9J3k=X&Ktf#{xNE)I%R&G0 zF;2M|zdX%b&gv>C=TVI`5$sMP;!@0w`!@0w`!@0w`!@0w`tG)9oxznCIoI9L5 zoI9L5oI9L5oI9L5oI9L5oI9L5oI9L5oV(gPuaZ0Mxx=}`xx=}`xx=}`*0sLpI0K3U%l?c3LPCHwyCyOLq!tnayojlaI<8aD6xo@-b=>wB(Yb*}HQhSk5m+Zwj_ zN$vJNslWX*8pr+_jc@Oh=C$`p_1LGRI_-T@{l|Ns%v|<6X}#LZLI3hGPPrMsJk49q z>M4J9=0*KmUzkU0)CcDd=MLu%=MLu%=MLu%=MLwtcA3;)RycP!cQ|)AcQ|)AcQ|)A zcQ|)AcQ|)AcQ|)AcQ|)AceQg@f9`PZaPDyKaPDyKaPF{mt$j$2dfu&lNQSL_?L#sw zleG`Yu&mZTB*QYi=z%+y?b?TA+GW1>+}J&KJ@3{&B*WaTeMpA6Tl`YtJ|x5HS^JO-t8?u`GOYf!_sFm{)^6?fmr3Kus_|vmyt1tx znO7%w)z4k);;!{-F9-e0$2jF?{PHw!Ijg7q)tMLdZ++oB>VtEKbBA+>bBA+>bB8_e ztOe%|=dN~{)L&LOcQ|)AcQ|)AcQ|)AcQ|)AcQ|)AcQ|)AcQ|)AcQ|*ob60=vaPDyK zaPDyKaPDyKuyw6{m0#KOZtbf)Z0&1bbBA+>bBA+>bBA+>b62}e>MtvtJDfY5JDfY5JDfY5JDfY5JDfY5 zJDfY5JDfY5JDj`PxvM{SICnUAICnUAICnUA*t*vBGW*YC>w1~}=d^Xb%&<(>^)kb< zTGz`A%Wz#UGc4P6z09!8*R>(T+^uUyhL7D1bGNRS*|)E2F82M`^)kc8S=Y-98-HCd zGi=^Ri{$40E@xkr}qe+O56*GHD!HHNFg+SGLt7^XlZT`j6esT->!@ z?d70<`533%j9;GSEob$VzdG}x{;e;ZM}4rhdo0c!&K=Gj&K=Gj&K=Gj&Ry*?slTjn z?r`pK?r`pK?r`pK?r`pK?r`pK?r`pK?r`pK?r`pE=dS+T;oRZe;oRZe;oRZeVe4A= z&Dnn*TldY`e@~tk!*VhGn?!n=>rib>Ey}nXh}q40E^cn={Pa+RuEL zyLI23efzri%CP?HzB$9jS@+EuHvYPA&aipceRGD@v+kQStj=$H;*Pmn_sW@eYpmVc z>o1eWkyYc%uz6)$JufidpdDI76 zyT{_(;oRZe;oRZe;oRZe;oQ|OllsdF=MLu%=MLu%=MLu%=MLu%=MLu%=MLu%=MLu% z=MLwtcJAuW9nKxj9nKxj9nKxj9k#A@erkVwuJcyI*1pb94a;PmpBk3cIzKfm!*zaY zShnl@)UeFg`Ke*<*7>Pn?$&vnVeZ!XoqhW{@3Zf}&Ib(}XPqY+HvT$)G(5-5ZFa1l zb-ro$*j48`KQ*lWb$)8t8f&-q`paaUpPD|hYW&IYcwX67kIbu+yXxnzb#d2vwU>kb zuylcQ|)AcQ|)AcQ|)AcQ|)AcQ|*ob60=vaPDyKaPDyKaPDyK@VuTp>Tdhv zbNzmJf84I$4-d;^{eE~@R_ph}!!lgIA0C$N`c3Sx%-3&ahq+t7A0Fmz{eF0uyY>6w zef#c0Q_4eGFQ*6)XhjlX_BJZ#?e`{7~rtltk0t8@J}c$mBOo8e(=tliq{FO$ZR zRpZOBd1YHYGOteVs-L^o#a-*wUJm+~k8#S)_~mKda#m0It1~a^U%&U>uM6ihjWK>hjWK>SG!E=FDslooI9L5oI9L5oI9L5oI9L5oI9L5oI9L5oI9L5 zoV(h&t3P)*cQ|)AcQ|)AcQ|+0y4L=#dyi{>*Zpz3_IDkY$=cs_SXOI)*I^m1{auG; zyY_b-mia?({Efrht^Hkxxm(w%4Rg2lcip$IJwo^W*Z!`<###Hj4jX^%?>cPWwZH4I zde;7~!|Gi7yAE@=_H-S##@emD{xWGCSv9^4n^(5gBlGIyuKKxaUEH-^?d70<`533% zj9;GSEob$VzdG}x{;e;ZM}4rhdo0c!&K=Gj&K=Gj&K=Gj&Ry*?slTjn?r`pK?r`pK z?r`pK?r`pK?r`pK?r`pK?r`pK?r`pE=dS+T;oRZe;oRZe;oRZeVe4Aghwjfmtm{Mf z=Oxzlp~Es+*M|qu=&)?p^`XNuU)MqobGNRM96ok8%-y;^bl<+NG2HiG z*M|-pXI&pUZ2Wb7=&*U$^`XP+S=WaSt8-l+I?Ua=CUn>uYq$3L%cOB+)%Y@OUfEWU z%&U{T>OXcjb8**twU>kb zhjWK>hjWK>hplVvtGs_-So{^etwax;E;nzx+QQ~v7A zi~6^|a31x+*6y)5cQ|)AcQ|)AcQ|)AcQ|*o%cTCY!nwn_!@0w`!@0w`!@0w`!@0w` z!@0w`!@0w`!@0w`tDU?0bBA+>bBA+>bBA+>bBC>K-Jfy)zOe4kxPQM`_h%fI$+|z| zu&i!-^D7R^aNVDAShnl_jKeZt_aYqTZrz`8n7eh}Z(yQk`j?M!%FX!YY2I>HPx-4eFY4d=!gDH8bGP=E9Ja>V zt-by-X&hNKz6_gJw$&r^>g2BaxochAwO;Mzpnv%or`(KRp5`rQ^_0Il^P>K(FPukx zu(f+E&K=Gj&K=Gj&K=Gj&K=HO?J}vqtZ?pd?r`pK?r`pK?r`pK?r`pK?r`pK?r`pK z?r`pK?rP_*{@mf*;oRZe;oRZe;oM>CS~>1NkF9)%t$pP_ER&Vvu&h>&!!lg|56gD_ z+px^nV}`j~V-0h+<{Rd2)v<41_3itwx`&Ok)-!DUwa#JluJsSAXXQAo&Xwb^`d5y_ z)>yl>*Iy=$Bdf-jVe`tidSqUm+*Ln!t&6+XtGyibFCXKSoAJxjyydK(@>geG)W7wG z^QaHb9nKxj9nKxj9nKxj9nKxjUF|ZdzpQZXaPDyKaPDyKaPDyKaPDyKaPDyKaPDyK zaPDyKaPDg7uKwKN+~M5e+~M5e+~M3|>sr?j?~l)QUGe_7UDpo}%Vb?YJS?kq{qV31 z*Y(50vR&5?56gUAKRnFcx_)?=yLFxIFn8;CiD z+TV5mIc@FlIxLg5zw5B9*8Z-;GFa2=wU_BIcWZywVeZ!cuEX4|{ayF% zYmd-<|FysCuyNM@uEWM(`@0UCckS;wte&;M>##c4{;tE^tvy|bt+94%ufI$hM^=q5 z!{(K3^~k(BxvPHeS{HY%S9>|=Up~euH{+M5dCOTn<*&}XsDJAV=TRSQ?H-GBhjWK> zhjWK>hjWK>hjUlEOzJNyoI9L5oI9L5oI9L5oI9L5oI9L5oI9L5oI9L5oI9Mm+PSMg zcQ|)AcQ|)AcQ|)Aci6ht{;vDubM5cCKW^9luER1}`@0UyYVGej?;|o?`@0UycJ1#v zEc3OO=`eR|f7fB|*8Z-;+^zjx_w8$s(0%{4zw5AZ*8Z-;#$Wrp4x4xF?>elWwZH4I zI@kWL!`!VsU5Bl)c5AP{Od3a4jW5IIm2LINygIq7e(qWqcdb`@Ip|+L#wj=Bm#2Bl zSv}>i&b+99>kH>mA8hR&i*tu_hjWK>hjWK>hjWK>SG!E=FDslooI9L5oI9L5oI9L5 zoI9L5oI9L5oI9L5oI9L5oV(h&t3P)*cQ|)AcQ|)AcQ|+0y4HPj_Q&Vx^LA|Q>%KYr zmL!?IoXf*F?ix<}0JvFmxa?wd2r-MVkiFn8;|Is5h>`Li8! zz3#m-?Z#R6%^5cSx^K>~dDne&hSjs~n={Pax^K>~`q#a3hOM!7Yp=gd8b?-*FT>`Q zZS}~!I=QQU?phajtyg{>?yr_Tc3+GWEoI5NNW8&Q5+~M5e z++i-P1?LXuu6CK!UsgDGICnUAICnUAICnUAICnUAICnUAICnUAICnUAICr&kSAXts z?r`pK?r`pK?r`p~b*=j|?%(g${TcV~ckBL)`}ezbf5!d$-Iv|&p~Es<_h%fI?YckX zu*}!J2#2{__b43Ry=FdQn7eg<#(n#`$KSsHxdzg{9nKxj9nKxj9nKxLu8;k@%k1A5 z{_|sYZ0+Crf*s4`yMJxRvbyk#FFXBZc*XnfShlx#-Hv7ctzY$d(}%m8{N#?g`=QHT zZrZtf$HR84{b&E{j`e^2oi9IqjPs{2-LdiS`B_)k&-?6K?pQtl{((DI=hdIEWA$I= zX*;&Y+O56*GHD!HHNFg+SGLt7^XlZT`nhXe+_hfq<)DB07^mEfU!LYIXZ4i7I`g9b ztuLHMeQ@q@?r`pK?r`pK?r`pK?r`pEmr4C)g>#2vxR9++A?(Z{4>);*$5+ z_y14-`a6e>^TONTci8wp{7v6GY~Fj^>-&b)^U!;L|1futIOjpb>Obo}JGRE!t-by- zX&hNKz6_gJw$&r^>g2BaxochAwO;Mzpnv%or`(KRp5`rQ^_0Il^P>K(FPukxaPF{7 zjEQrHbBA+>bBA+>bBA+RyG-gYE1Wx=JDfY5JDfY5JDfY5JDfY5JDfY5JDfY5JDfY5 zyV|*{KX*8HICnUAICnUAICt2(`a9iTn*IH5@6i6Px2I@-@7rs%^8mB=>G63Ldy{tF zz@DX@Pq3G1=NasM+W7~2pLSkCd*>_k?>vTaI=^B3&U=`*^C9Z#Jc&9xf1>`*t5{d< z_71JTJw+SGUZag~57OqfH)-|Qv$Q(xWm^5~JBt0f?0wpLwU>kbojH9^_#Nox=xvQy(br42g+U7hjQ0-quRTkRR69sHBQ%`8o%pO=a@OZ?o~Zq$Ewb* zZ&iQSy;@i8)?R;^blt108efLZE8FUkd3AD8{oJ)K?pm+*a?rngj8ksLFHiH9vwF&3 zoq19J)>qfP=8n_c;oRZe;oRZe;oRZe;oRZe)!uclxznCIoI9L5oI9L5oI9L5oI9L5 zoI9L5oI9L5oI9L5oV(h)?lpJXbBA+>bBA+>bBA+>t*h^YaNiSId*2_)r0z;(Tv~sYv%2HH}&*=oI3lSPW^p< zXI-^hd;Mk7II?Pd88)wMt4HS5$wl>Z*SffCz1qt`|MD?Txf#Da&0EguDSvh5Mg3b} zeSeobPIHHIhjWK>hjWK>hjWK>hjUkZ-{0jM4J9=0*KmUtMpW zJ5FbBA+>bBA+>bBA+Rd)J%iPJ8Zf?r`pK?r`pK?r`pK?r`pK?r`pK?r`pK z?r`pK?rQIP^W16A9nKxj9nKxj9nKxLu9f4QC&Vk?VQXJG4$EZaI4rA`y;btvQCdTXpQ)SAF~btL|artn~~Vf30)aylef#>RGuAt8?Wztp1hb zuyxgL?e&*QbBA+>bBA+>bBA+>b62}e>MtvtJDfY5JDfY5JDfY5JDfY5JDfY5JDfY5 zJDfY5JDj`PxvM{SICnUAICnUAICnUA*t(v3n@8@C&!4!%j;;MpciXW{?)tzT%jzRf z+OZ73`t*)v`{ZW8=T;M|N!9e|6!G)$_1l+_5@u`j#E5|100VV{5G4+UqZq#*tOy%dmN6TRk$b zPVTCoyVk{B>(yQk`j?M!%FX!YY2I>HPx-4eFY4d=!gCYX4!}zQoqve#J6rA7fdyzp)J4_gJ>=hb;5BqI<}GLSl)pOjqW-O~_KVIPr@6zq!@0w`!@0w`!@0w` z!?~-y{i1WHJ$E>FICnUAICnUAICnUAICnUAICnUAICnUAICnUAwYOh%?zHC)=MLu% z=MLu%=MGy}zkk5}F2dUTy@X8q9fhp=eT5AB-GyxXJ%-Htody^EeuKMpUH1NY*Y7>F z_d5{%`+bOUu6z7@7324N67%*u6ZQ1_6Lt2x6!rIe73-?q+UqZq#*tOy%dmN6TRk$b zPA;mSyVk{B>(yQk`j?M!%FX!YY2I>HPx-4eFY4d=>h~(S<1}|TcQ|)AcQ|)AcQ|)A zci8jJ+H3FkD!J31JDfY5JDfY5JDfY5JDfY5JDfY5JDfY5JDfY5JDj`P`@Kr;wC4`z z4(AT%4(AT%4qI3I2H^G+u=e&DkV*Rw$f|t_WY~TMvTYv&nYX_I7wvm+>~20oa@Rfy z+S@-t|MpcdPWvqwzkL|Y+x`sdY2OBQwx5Ig+vmZ$YPa_K%cOB+)%Y@OUfEWU%&U`& z>OXcj>*B8UYA*-<%f~q7X8iIrZ#k={{MDHk^>2N(&qMAw%^l7i&K=Gj&K=Gj&K=Gj z&Ry;8^N>63xx=}`xx=}`xx=}`xx=}`xx=}`xx=}`xx=}`xx=}uy?q{Xr#*K#cQ|)A zcQ|)Aci6hx_Zzn#xV5)WxJ=qVTvqKXF2nX4mu>ry%e?)`xoF>V?%L0syY@NP-u~zM zw=cSJ+ArPs?W1nq_E%R=`>w0A{n*vtKJC_3yS3L}CXFMj#+PC9%C>rBUY%T2KXM@x#KiuP^0+`d)T-hNgxX`d@uwf~h2+ZRi=?UyC<_R->^{k3-P?zI1$*?wHw+owza_U|%I z`+6C_{l3iGK49u;e=v2nZ*;bFttCNfB-?`hZi@VmV zy&Uu}ALEpp@ypY^<*c6aS7%<-zxCCAV!7iqcQ|)AcQ|)AcQ|)AcQ|+0^Um69Z$Giz zY0n+b9nKxj9nKxj9nKxj9nKxj9nKxj9nKxj9nKxjUG42BmOJga!@0w`!@0w`!@0xO z)qeZ9efX`t{rP3mzWuUlKYtmv&%bQj|6k_a7l4cI7jXQVxqseue*x{?cR>H{M_`=p zQ(*k=Utr$uYoMO)cc9MhgP{KIk6>N3TYLRw(m1ked>J;cY^z7+)yYNmAHQbKy0~k- z+RH)z@-a@i8NWQuTh8h!e|6?X{aat%A0c;~<__l$=MLu%=MLu%=MLu%d)`@l?cEbBA+>bBA+>bBA+>bBA+>bBA+>bBA+>b60!!N64M_+~M5e+~M5e+~M3| z>uR4I-2OS%-o83AX}=v=wGWRB+n-0a?b{>s_VeMQeSWxW{~zw!7f5^i1?k^DLdI!- zA>+62ka^pWNImUSq|Wv)Qh)mzSy%1WUVoW1j;tDAhRrM6>XCVMa#8)jul91# zzkG~SZpJT9^Om!E%3qy%QUBIg`x@nr)7;_Q;oRZe;oRZe;oRZe;oQ~UzDBvzo;#d7 zoI9L5oI9L5oI9L5oI9L5oI9L5oI9L5oI9Mm+S}JCciMA@bBA+>bBA+>bBC>K{l0w8 z3E=g+^I>aWzegXI$@+cyu&mba%ZFvSeqTN;+x7eMVVSSrmk)EXeqTP!-TEE&Fn8v!S9>RG=pA6Do3efhBZ*YC@Rt*drxufI$h zM^=q5!{(K3^~k(Bxu|~bS{HY%S9>|=Up~euH{+M5dCOTn<*&}XsDJAV=TRS=JDfY5 zJDfY5JDfY5JDfY5yV_+^e_7$&;oRZe;oRZe;oRZe;oRZe;oRZe;oRZe;oRZe;oQ~E zUH!Skxx=}`xx=}`xx=}`v##U&PU7xwXzktiP$u0EQC8h2QHB>i@IG^F%eMO}%Dnq6 za@TzrcdwcEo&MZ)-$w1-&r$#G^Jtvz|7iTbJihOwdAnbvdb*FKI=jE5`n&I>b=7X| z^_NNG$g1&W*u1i>9+_7sch$dp&D^bvyVk3{9P}?A3sJMFo{xx=}`xx=}`xx=}`xvRbVPUcQ~?r`pK?r`pK?r`pK?r`pK?r`pK?r`pK z?r`pK?r`pE@4l0{)1Et=JDfY5JDfY5J8WI;w~yP0-`d-sUncF_FRS+Rmtp(-%eMXh zW!`-OxafWX+;txT?z+E#_U=2NfA=FWPWLG=e)lghZ}&A&Pxm`eXZJx+fA>eQuG+1= z{xWGCSv9^4n^(5gBlGIyqWZaOUEH-^?d70<`533%j9;E}%pBi`LOtcL&b+99>#O@C zgoD%b#`63`n%rTx@x!f`pcwo zWYzdGY+l(`kIbu+i|Rjq&75^{*Lt;=gZ|}XoN_aMd78JJ)l>fJ%!~TBzPjE#cbw)9 z=MLu%=MLu%=MLu%=MLwt_O3V2o%Y<}+~M5e+~M5e+~M5e+~M5e+~M5e+~M5e+~M5e z+|}Oo=DE|JJDfY5JDfY5JDfXgUG3L_+sDJ&+uuVb?fW6C_5+b&`-I50{X=Blz9L+- z-w1c@L&9DAlW1?>68+oH#5nD9V*K_$F>m{#sHgo>)Y(2N>c7nK{wmg0yS3L}CXFMj z#+PC9%C>rBUY%T2KX*_v+xceJgd-pw*N%upPRrg7hVfRmzZTD4_dG}l7qWds% z*Zmo}>%NWJyPu=}-RIFb-T%?}-51il-7iu--A7WL-Ct7u-FMQuYPa_K%cOB+)%Y@O zUfEWU%&U`&>gTR?ao2jamxKQ0W1Mm`etDX=oYhnQ>dcG!x4ydXWbQc49nKxj9nKxj z9nKxj9nKxjUG3d>GI!c@hjWK>hjWK>hjWK>hjWK>hjWK>hjWK>hjWK>hjUkZ_npk0 z_T1sz;oRZe;oRZeVe9JtGPwKBSbO)QkxBQdkyZDvnGBEb2PE6>cO&!egTqDl$KkH~ z=5W{jbhLM$9sRrij&Zs#kMX--k9oU~k9xYlk2<^WkNUeGkag8=?e&*QR!{k>GcW4j`s#i_x#KibBA+>bBA+>t?L%Ad)%Dc$2Wb`j;;NVe`Cio`STC%SXNK@f*+gyGJMm?9n1Ef z_ua9~|M(d@=Hj>Bv19Ij=(3NW$8vYQ+w55TReoT{`v25RcWj)qe`m+W|Gv+8!hYV* zzxIyRbCs{%u{z)W4Ler<>+if{>#E(_>o1eWkyYc%uz6)$JufidpdDI8z4(AT%4(AT%4(AT%4(AT%u6CK!UsgDGICt2* zGRL{Yxx=}`xx=}`xx=}`xx=}`xx=}`xx=}uoxA#ThjWK>hjWK>hjWK>hpp?kzwW&K z^X~0mzhi5E?A>=Plk>iB$FjQ7c{`TjeP6j_*W1gfV~z70-@aqxU;a@$Ht$Pbuw(VS;#E6V=L6olWA)$b9Xqzh z+O56*GHD!HHNFg+SGLt7^XlZT`nhXe+_hfq<)DB07^mEfU!LYIXZ4i7I`g9btuLHM zeQ@q@?r`pK?r`pK?r`pK?r`pEmr4C)g>#2hjWK>hjWK>hjWK>hjWK>hjWK> zhjWK>S37t0=MLu%=MLu%=MLu%=MG!fx-R?Nb=~IKH@?D6U6(z)_6TuZ_VC(g!gblh zYmX4uWe=}CLR^aV_({eO=qT@4v3? z9X8IoE_>Mc>$>b=^RDZ%ht;#L%N|zey5@RV{p(unVe6`W?TNDQzxD;$kF)kr*^j^W zR@u+H_FQqD_>8mmVsZWW@YWxuYqr^|l5+RH)z@-a@i8NWQuTh8h!e|6?X z{aas{$K2uE;oRZe;oRZe;oRZe;oRZe)h?6z%L?ZX=MLu%=MLu%=MLu%=MLu%=MLu% z=MLu%=MLu%=dO0{>dzg{9nKxj9nKxj9nKxLu3x{}HBNfo{rD4Ja`c@SUUm4~H@xKN z>+kTz!(Vl=mmdAP9a;de0yK#ex3cc+Zy}{ng8VW%x%P^U|YVzuI$$ulb^v z9zE&$-#&c(|M1eI4?XkuPw4;NUwP@#gTMPp&&R*|=Up~euH{+M5dCOTn<*&}XsDJAV=TRS=JDfY5JDfY5JDfY5JDfY5yV_+^e_7$& z;oRZe;oRZe;oRZe;oRZe;oRZe;oRZe;oRZe;oQ~EUH!Skxx=}`xx=}`xx=}`*0sK0 zKD+1L`hI!X+Sm8X!!lXlFAvLVeZM>`!}b00ux!`&%fm8X-=z+7x4vH<=5GC-YM8tA z{qnwjeMhpSIPYpmVc>o1eW zkyYc%uz6)$JufidpdDI8z4(AT% z4(AT%4(AT%4(AT%u6CK!UsgDGICnUAICnUAICnUAICnUAICnUAICnUAICnUAICr&k zSAXts?r`pK?r`pK?r`p~b*<~v_U{YpI<@`##kx*ySSIT_wP9JU>(qv2xUN$hmhHMu zZCK{(nyg{&*0oy0J9j(gZe6FgZ~un7yk*~iU8go|oOPYru<_S*YQyGT*QpJwXI-Z@ ztj=|v+Aw$P+O%P7tliq{FO$ZRRpZOBd1YHYGOteVs(qSFu6?(Lxm$Z}4O?UF)?R;^G>)tqUxv*q+v<^d zb#hnz+_f(5TCetU(7$|)Q*OpDPxF?uddgp&c~Sq?7tW(T*xEf7=MLu%=MLu%=MLu% z=MLwtcA3;)RycP!cQ|)AcQ|)AcQ|)AcQ|)AcQ|)AcQ|)AcQ|)AceQg@f9`PZaPDyK zaPDyKaPF{mt?NVg$LG2}bbs8g>qCcSvaSyumesmGbXbP#`p{w7uIodGWxlS39OiCa zA3Dt4mtSee+^y?F_wDN%!+rmCedw@p*7c#o#$VTm4x4vfA3Cg_b$#ftI@k4~!`!WF zLWixfc5AP{Od3a4jW5IIm2LINygIq7e(qWqcdb`@Ip|+L#wj=Bm#2BlSv}>i&b+99 z>kH>mA8hR&i*tu_hjWK>hjWK>hjWK>SG!E=FDslooI9L5oI9L5oI9L5oI9L5oI9L5 zoI9L5oI9L5oV(h&t3P)*cQ|)AcQ|)AcQ|+0y4L{|w7& z?f)|@!?pj~| z|Ie^_*Zx1l>RJ2$46AeP|1-?p+Vf}F8f&-q`pcwoWYzdGY+l(`kIbu+yXxnzb#d2v zwU>kbJ;cY^z7+)yZA;@7(Ry#a-*wUJm+~k8#S)_~mKda#m0It1~a^-}=IN)CXI; z$Ku@K+~M5e+~M5e+~M5e+|@3V`pXLE4(AT%4(AT%4(AT%4(AT%4(AT%4(AT%4(AT% z4(G0R?&{AS&K=Gj&K=Gj&K=GjwyyO%#{KcRe#f{!ZrAS^hh?&U$2csj^*hF48Lro@nzV&vaKGOS0{JX&t2={uJvj!2mQ;( zIOS&i@-%NbtEc?cnHTkMec?RngRR|Taqe*LaPDyKaPDyKaPDyKYL`j zbBA+>bBA+>bBA+>bBA+>bBA+>bBA+>b5}ce_2&-f4(AT%4(AT%4(ASA*VBqI<}GLSl)pOjqW-NfoJW1IwR}MSX6@}0E|c~Tm(@Bxr;iNR@i{EpmHDvD?Qv}! z?%KEf*xj^q*FNXk?e$&%_C+_&IzFe}`0b-^-u72lPy4Q`v;Ek)YoB)Os@>Y_FO$ZR zRpZOBd1YHYGOteVs{h#C)X81z)m{$zmydDE&G_YM-f~t?`Kz;i+SR}H)jsXHq}`Hcr=l&#`fQe{=J8ow$0seq5bhSFZl9H@B|Zt-by- zX&hPYuQy-EfAh+=dSqUm+*Ln!t&6+XtGyibFCXKSoAJw&yK+`f`KvQ8>fie6dh^_I znme33oI9L5oI9L5?0IJ`ICnUAwacXbvckE;xx=}`xx=}`xx=}`xx=}`xx+H#4(AT% z4(AT%4(G0R?&{AS&K=Gj&K=Gj&K=GjwyyRc#_daN?d?}AllC!|Rr?#uuzinZ+kVJ0 zx7TjZqxMfeb~o+ZwcoOKdk)vX{h5u^zRkvOKWFo{&$D{k|5=^w3$6b4i?*)Xt-by- zX&hNKz6_gJw$&r^>g2BakKOIx?^>_+a?rngj8ksLFHiH9vwF&3oq19J)>r#Q=Z@3d z;oRZe;oRZe;oM=*J8QwY!?~+nCiRyU&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj z&K>r=YrVOvKX*8HICnUAICnUAICt2(+HW7X55KjyKfg@cw_jH6=P$$d`Il|`|I6Io z@;#5bU%<}Y+xG8w-CsbvJ@)J0{RoWHeF}`<{R_<7eGSyp{SMUGeGt^&{SmCIc5AP{ zOd3a4jW5IIm2LINygIq7{++wsy0~k-+RH)z@-a@i8NWQuTh8h!e|6?X{aat%A0c;~ z<__l$=MLu%=MLu%d)`?K&K>r=v-a9$Qh!$~S&`=T4C{nCx!KI-Oee|7b=@47nIZ>44&^|w#E zb=7X|^_NNG$g1&W*u1i>9+_7sch!IFZsz5#^=dB%{maKVbBA+>bBA+>bBC>~eZO)0fm?g~gv+G;!)4XJ;xcT% zaoM&Hxypxoe+u?e_YvfBT{vr~T56-#+T*ZGUz3wC}n)+mBuS z?bB{uwOf1rWzsmZYJ3?suWYMF=GDnv^>f#{xNE)I%R&G0F;2M|zdX%b&gv>C= zTVL(do;yx+hjWK>hjWK>hjWKL@2myq4(G0RnbcoaICnUAICnUAICnUAICnUAICnUA zICnUAICnUAICnUAwR2a0?r`pK?r`pK?r`pK?yz;WUk7d<4{L9K51F*@hpg83T=N`} zVf%#0w*5n7Zf}a7N9{MlUHg!5*Zw5h?a@*H_A@a~`z9{NxzZ7-0kBa)+ zU&Xp=xAywWq;X``_%du>*;bFttCPFx=dN{e*Lt;=gZ|}XoN_aMd78JJ)l>fJ%!~TB zzS>_Ucbw)9=MLu%=MLu%=MH<`Sqsh`&Ry*?slTjn?r`pK?r`pK?r`pK?r`pK?r`pK z?r`pK?r`pK?r`pE=dS+T;oRZe;oRZe;oRZeVe4Agsm(Eu*L7;c*1oP&8pHbz8LsQphGo01y&9JJx+ZIwyLFw~Fn8-ZwPEhob!z+eb*(qwLyRK6kR?oUlZCIV_8nj{cuWQqWt*drxufI$hM^=q5!{(K3^~k(BxvPHeS{HY% zS9>|=Up~euH{+M5dCOTn<*&}XsDJAV=TRS=JDfY5JDfY5JDfY5JDfY5yV_+^e_7$& z;oRZe;oRZe;oRZe;oRZe;oRZe;oRZe;oRZe;oQ~EUH!Skxx=}`xx=}`xx=}`*46#8 zare=-_U^AOlkU4MtM11w!|u~9+wR{jbN7bs{j2+Z?_M*1a@x7;{@~i(BfI|HPuw`` zcl*hjWK>hjWK> zhpp?DSH9Kyob;1t-{(H}KKhHxy>R$fo_O}O>r*?{e%V_+bNamR2^XHZ`fYdogD?20 zGY8+g1L(e<&%}?C%b8q~-Gfz6)@kNh+?wNn`z8(MerJsA|#%Dci z#{9YqpL6EX-@4;Jyzg_)Jokw^e!{mr=ggTmexm&gKKt4G{(pS49UJH8@3Uj$fAEPr zHt)TEZpZ4m%$s(s&TIbWj;H?L-LZAm{!I^l!M^_s?)Jj{IA8QtKfNFS1|Rt8{k&iC zq!*p3o)3S~i_cW&;~w(jef@v@3oqWU>sD`k@qWG9%R&G0F;2M|zdX%b&gv>C= zTVI$*YuvK_+VhC>i1Uc^i1Uc^i1Uc^i1S#xeCjVZoJX8ToJX8ToJX8ToJX8ToJX8T zoJX8ToJX8ToJX9;+Ig%$k2sGwk2sGwk2sH5{a5_`KRd_s^tSJL?wRj>=Z;@}hv%O8 zgO}|1nZNj)Gf#Tpj<0t1bI#oTtR3I(H5Z(D%_}}UkNvrOTyW+Cx7hJRKlg$&4>@zj)i9OuKqs_~ad{^Gol)WA*>*f3{=ms{L*Ed)~hPhd%PW{WuSJ==0As{%t?> z{QbPYeb=8lQ$1h!Ge5Pj^Iq@!seSz)yxfKRb^Z94UbtVc_Hxj_e2i0W#xGCvma}@w zU!8eT|JE1g(Hgg`zxF)hJmNg!JmNg!JmNg!JmNgo&SU-MhVzJxFK3)boJX8ToJX8T zoJX8ToX6>Z>=EY?=Mm=-=Mm?zb{^}`BhDkvBhDkvBhDjMzxPM%eQ^6;`D@p^$+Umo z_3nT4hWnft{tth6-=iP+!gGhe_V)KV(#LbQKDa(upSR!U($nWYzy6p{>aTs~J#NRw z*|u*V`?9b6d(;2(Fa5Zqzxegf8h-4f9)I*(zxwer9{c`(^rWL}zWaY4e(d$1a&+By zeRTM#*ZqlM^HPUb64j&R`vJT`s2T@|N87V*16UC-Z+ z$#d89Yj_>o!|K7t!Rz>(ad6|{b$re^(|-M@>>ta6F|{|QI%~(r?Pv6m%gt*PK3?PS@fv5$<24Si=kGjLojn%!SlnZAkDd18$2PAT zv>Rs~8#6DbSbMC0T>Iud!tpbYb^NSja@g^VXZ*$b$fFbo*QG`BiVe=g}`+ zaN)i^e)l6keCC#a^qc4Czh#g8lD~ZOv~Srs_207j8*|J0y!4*$o^k9=d-reH@yXXe z<>;eV*zprDcK*>lU-GW$^F22?|LDor+3}6;b^g&ae(0Uk{x5#){G%Uy%{zww(@V}j zy5a}lKKz*1pMP}b@;iR+yU#!RmTUj&w7=p#=O6vIoBztN_Mf=N+xGph``EV*8|U(G zddsl!zvNmwHt!uS*sWbXKX>kq)%lMvzGL-&>;rF_$68nIm-^|39=U)N)Ae%^k)+RH)z@-a@i8NWQu zTh8h!e|6?X{qH~Pyfco6uXxSp9NqW3UO#KZwZG`C&)>J>FL>3pr~jjG{aHt6{>zSE z`HIgv`nUh=I@5li>soe8&xkAN%f09KH6&HyZwh-@C-od4KOF`}SMD{-*o>XMOL@ zhK+OQ51be_{<;6~y~E^tLHM8I%im&Z~b>WR{w)vxMS<8{Vs32*uMWyfBVJu z(yQk z`j?M!%FX!YY2I>HPx-4eFY5n+pZbYe@6%s*wWD7>-0@paUj67sf4<{~y!h%zZ@la7 zHRNlqbd95@{mzb${?#>(p729Yo5!Ab{WXq$`c_XLzS`$r^XST7^pnHibM`fl9`KPJ zKjUuKJbKsfK4aQn|DD%7I_C|~9M=AnpMKW9|0N#w>|x`4**O;s8~+P_f5+zi{qK6t zw5#VKzr160{^lj0JMHSf!Buu_UA5om&R5&_f93CAbwAGEd+=5F<3H$&uezW2W3N5y zsCvHehtAs9`OE+KtbP4Yz42N5b>08EXYJRky&Uu}ALEpp@ypY^<*c6aS7%<-pD(X7 zwR`=kzt^S4@p{$xUdNi(>s$4B-K$QopZW4SnJ=%O`O=;*{maKV`7(aK%$qOui&b+9<_dCa7ud9yFUT+<@y$(B`dwq7C_qy%)@AcgCqStxPuio!Gk9xoJ{ObKq zd+&Gp_x@s>-tUax`<;1vzf(`|ck1kYP5r&!Sy%0j&-y!V8^`h7_>S}Db^KS4=S6jT zzEr>GQS0*jYQ5UaLI3hGPPrMsJk49q>M4J9=0*Kyf9aFY@qXuZ{y%@tj=lc>$Qz$D z?cNvu_&z)KesR_xJaO8+k6h>69eaPd{J(v|w0qyV;6;xg_WpJIU;eRS?_YoLdygCT z{`Jtm_|bj)Ke+Oa_5X!iKX%%U^Nb&U%&_q<{M|zMykYss4a-fQSe|mma+W{N3+9Ed+Ig%$zt}juW8*s> zuz4LPSUrv(tWL)jR=?v7cf4W8Vf`JSjpMj&e8+S1I?k)d@n4;u7uDbM$oQT|tyg{=X$6NJ#J;(k1g1ydrJ;7f8z0P3o3toS)_Y1E}*!zgrEA0Kn z>lpUFqIUjqU@_Jai*U9>O{lv!cx{8hO^%k4g>o8W2*JrFwuiIGtUe9rVzhLjn z_4j_=INrw_-}`&>df%@ep9iYb=Y;C-?=s{2T+w>9mxKQ0W1Mm`etDX=oYhnQ>hyYE z{rT$sSG(8w`g{Fv9PbN_@BN~Ay^mCn_m}GQzEl0ZPZ{6)RO{7V4*Hjmamvm3 zR!{k>Ghgb@SMR^(^}bwx@7ImveZ29#zc;V<{p#^~pgMg{sQx}z7~kiL)~mf7^e-Rd zl$-I()4b)Zp7K{`zSQsYt-1Pqi~D?w`+ST0e2e>hi~D?w`+ST0e2e>hi~D?AyU&gF z_jwZc`4;#27WerU_xTq0`4;#27WerU_xTq0`4;#27WerU_xTq0`4;#27WerU_xZMV zpKt5$^DXZ4E$;Iz?(;3~^DXZ4EmnWN9EU#lYUk1CVa%`3$(VPapRwb?=W6UYsUF8q zbvmwmKG(jJtbTuwVC$;g^RE7$ zkB#Gb+W4No&FgtxJ)ZB?>2<*0BgXgo(7O8jvG#J%zkG~SZpJT9^Om!E%3qy%QNQyu z#`nJLJOK8-?EC=se&@Ua_CDx*0`~ssJOlQ=>HGuse(Jmg_CD);1@8O|?)*&c&U@6~ z`4DUz=Si^foj<|mb$$k`$N3qoPUm5;`kkM_)>XUDA@%q9q;Y(1X?&k&ns+{b9@pdZ zPj&hn<@}8CeU5T|26uj@_Hxj_e2i0W#xGCvma}@wU!8eT|Mr|4Hdp83aGx#x&GMP^ zZ@cq&`ISk2aei@raei@raeiz6Uvd6zd%pBD&&}Q66n|Hqn_FLPwQpr?}NDaLEQTw?tKvVK8SlC z#JvyV-Uo5-gShuW-1{KzeGvCPSbOK?dLPu@`ylRp5cfWadmqHT4`TIieSPLL%uk-3 zJMSsE!@0w`!@0w`!?~;df5m5*t*<=x_X5BDy@30B0r&R;?(YTM-wU|E7jS3o&pZ7)|J>gT`t zhjWK>hjWK>hjWK>hjWK>hjWK>hjWK>S9{O9+-d)t`diPsKJ&fC?)}Ai70(y1na-&`edOQDP zy`2}b-p&`bUdQ2Q&X4WR1OLA{KbA+&!M?Zhn!}gl%4-o{*lQGD*lQPG*lQYJ*lQhM z*lQqP*lT9Tr`ODmTkRds`gfcgr{mxFJul4bJftzzi&b+99>#OHl zub-X^dBpnnyfaSEJLC7fGjGp3_4K?`XU{wJ_q=Pp#R!{k>v)4oQf98AP$DiZ8%HNgmg}1)8-?47F@AW?Oee3Rf-oK6CxAyzh zPyL>~-TQE+n2Hd>ywolwz>a%^UKHJ|&#GkIc{PijSxVb)EAM^fo{i~oBrPLpI`D3hv(n)b;Eyn?F$e6ua7qWhV}Ir zYz$*zV_$6jht0X#Pt?BpAJl)1Gi;nS{;=`a|HI~7|2AySHOH_y*BmE}W6m|l@bS88 zKe6e5uo>rIGycJ5-h)j&2b($%Huay}tn1`vy(c$080S!J=G^3F-f1_dHS1%}P5uWP zFDJIX?sttZKmGc@|GBR;|98CdD#QQ#MZbCKFP?hE;ivqQe{%TZ4_#{be%E;B;f-(m z!9)EY`t@%-^gq_-->|+OgNRuusPQp!{%Ib44ZS)eqz)AU^C9aX8eQAya$_lPHyTvxv78L9j{A!>(&48cwHwq z`JCM3X5Q&zPHR41*TE+LgN>IHTVHF>=Y!XO?jId~#f@He@Wx;K;o*DT>sbf>*RIXK zVSNuC`5%T4?(%sD_j%u&hQIldPdKse$u;a4Sp5zg^VFrUJp7=4|LTK_ZhY#L_N%?; zmk+M}#*e%Lzx-iu#W#yrpA+?2kDW0+c8x#daPhKNy?OZZU;LmGS9|AchkxeIA3pK$ z2b~`N;Nx$6@YeUgX!xPubKipxKk_GrZ~Dl`9sJtqhYx?tMbBAd?(4M9Xc-x~kK&phdB$9$)Q`~KMH z53kqhgKItJ62t#b`#<>2|8d6rv$HUqh}zv0wXp7!La;e#*v<<$C+a12@y4O0T&zC&z=+s~Q{B@_#_dNd* z>#>i1g>er5={FwU_ya#WeeQ6jr=GggIZr)dy|=pUkFUpGcuJoydEB{&kNB%!m_9eT z!fj5y?1pc7g+6!qk*BZ6Ugl7rJ6!3D53h61o2SohKK`gzT=i8SJ*Ce({^-ZnV{bZr zZgPd!p4#-e*;~Kk&WHLu;DURt$KG-J+~(t#I<=YW#B*-`=;`xce)NjlJ|{LcpZJ{* zJaziq_XqB{9=o6G#AfZ=KI^gjnh!P^Zs$7Kto>l);>4!r_1Jxe2OEzkHfvvx-Mcv0 z90Mmd8Lr3fogQqCnG+iq>#_S|c2mhPHc{WgUvCsUW@k6$G^eXwB7UZYi|7j zuSEx*8;j?8dd$=Ab)a_a-+C^8%427Y-DCe```E>wsNcWu#{82{?LT81bKA%3)bVSP zF^7-m-S^kNn|JE}q&^<&HFopZ!)jnB^Mw5+LPxWe*C)copEn< z^;aMI-(1@K8`jrjurZ8^6S%Rg?$y806ybNXBF|I2fX zt$9yB@ST^O?6>@p4?cO?FZFYGS{XiW`0kH<^UC%S!{+(;b?-fVtE=B)xwyr!HveW! zeLV&n!&unZYRBeW?FY55{=@onq}@1c{9)s-|A)=F{%zQt>oLRTTyqSYbImbq&Q1Hu zaNmDryC3J|X8h%1Kkst1uV=a2*SVbT>mS$0>(btO^&d9pCLiOU*591ghRtcsyK$~` zQWn^p8!rd{BYtmm_BWos+AT;1};T?O%PJ|9<%J`~UrEfAcNA^z<8Uddq3Q*yXNw`YxaIONYk% z?q9pv=|B3;FPQenKl(1G|KOcpH|-yI>FrP7=CfaMX#8tG{eg3A>HizAzSHU7xY0*X zX}|Cd|4#n{?fS3w6Sc4Lr``B#oP)+$^_`>O8rr=j3KxCpYz<+~ja_ zv)(zDj&nP?$w&Wk)?S{*pZ1lTamxSX#-n*pALn**|+O zgN96wVTu5{@9$(31D+NSAfmAX`gci z$NlGA0XFAm{5e;kUE8J}fBRRba{?#yF}C-T-8f&az4hvUs9lX}#cJQ=Hs=boTdOti z#(CzPE5PQI9X99I7j|yJ{9D#vyIMHFYBB!txrp(I)#86FXLVwIJqG6y8(XH>oNB6F zt@W21HjcGn zRZpLM%s(7=7kuA8IQ@_ZeD&}>A9wxJ@4n=9haY>De|Y*IUG>`kC%*TcZ#?b4dXJBv zdfMf$H~hm7f5_o?Kl#gtAA6OTAHM3=ml?kFz2AT6f8%KLZ&+WC!NxEaHn!&pHveir zQTytDQ2#Z~uyNM-!^U6#pVY^k>)(dWx#k!)=bB^KoNJC@b8gyCZ2BK;#yQxGf3TVN ztT!>Objua=b3>tylkYFwU?!H@Tg(w&QiFXV{#Z{0}x>PW+Gfed5!t8V z|Ks02b*(?S`WypqfA=4r`mXm~caDJzul(On-RL{6G=0AIgLgZ;&4aHpecpH1dmjGz z7hYrfeDwa`bNG2r{rl7B2uG={mkKuZ}{Ou$J@n^ z-hBAu5B=DoWD^pV-hZu;Pr-SokmaZW4; zjdNl-Xq*$9dJdM$>N!|0tLI>|u7j1`^jXKq!OCv>taTl1@;O-9mCwP-Zu+cz4mLR- ztnAA9z`w~*-;J-6=8&N|&7qGuH{MUK?52;}S9a4!?VIE0w392!SGo9CBxO`qd+O&{ypJWu5_ePp?L zo}P4!noE|BQFF=CF={SZI@XVmL%vS$)-}GSk1RK@KfF&LS$Ymn&MV8!>zLzb`p9zg zI=0Ruoj|6^_b4eRSM*cisb#_n~#b3wH` z-%)?(Ua)bTAHl|7{|}pU{oAlPooCU1soB_@b!l(C`VXs7t>!Y$CO7j=yE(17dN%pbxghQ4+bpEo}9{QA4~{M!1$&d2uJh&{hOH;>QLe&#&+%B0sunRu=9I)!^}#9ohOSG(87 z`g?7}y*6U6$6gz8uZ`I2@h1OII#0g!WlXQj{@Z+S@|o|mRvy0NT3OBaXukXU+wgtX zU-P}^)ag4)-&gY4_pm#j?{nw-uHAR9`|m~%Hox)spZq<{r~i&v&3%Xazu-wMk{mdt7-i+@%<@ql7Z}xXJdl%!U@2Ppj{QXV+-ey~W<2z~r36`gu3Go^$qV-u&|63$OX2vmgGH=L}!( z6+e6SkKgZ6!}q@BsWr|w4?pM$M`wTJ`d1jf%7cID>~H$#Pd+sM`+w^{p8dU_|AWuP zU-#nIXg{cZ^*@RAU*ilLXN^B>{59{ec~?Ed>RELTt8>*qtp2sGVQXCLJ=uEicjbr8 z+Fy0k^Ur?hzkJ~T!QNZPN0}@Szc?)JEU>Wn;%F(>Yx(IGEAk%%orJ91T`Yj_pIRy_gtaPsvzBZe6E_}S&y(2AX z@~CTTS>A@3<P=>D15gK>p2wc5MyC^h2vWUvwW=sxqY^(eYR{*`nR*(see1mSwGn$ z&-Oe%gmza0yCpotlzGeR0 zUx}sN11ydTI}V9hioB5Fn6)%p@QZ899HT;)2rkfkonsfq2{vYJajdEPliI!bre7EEJ_){Y0t%dhFJX#hOd^>DEvsfd{)J8D3p}*bEHuK+-PQk2``V!22kqv^` z2C_{s+eS7EW}9g&f_W?|KdAlVP{ox)6>knz96D6-=}^Tj>2bxgLlx%^Rs1`$lJ?bf zt_zmS^}_81)4E_i+nwuz^$VtT!Tk!Rb;0%srggz~3Z`|z_6w$U;ZVhugVu$ND~Bo$ z9kecF96D5S>!5WZ? z1+)E`Z;lD(aY;FkSGH$ANImQysh|BO`(=Mhd)Uv?PWHdFpXcSD`AT;GPn|EGyQ;Hl zx$|1%Ic4TK<+*0&x#k#P<{04EVCLB1m|^Ca;aFnkSmGFC<{0DHW9Hc7m}HhQ$;`1T z+j9&{JsjIoKgYc6m)C-{hkY*XJ{*n6GZ?a$Zr?iLtEbV0fOZ(+o zWBoi|YXj{WM;|+%Ne-Fxx}^5#MoRJISAd*?#h; zU>=v0lb>Df$^R}rG%qgwG+(ZMX&!0L6nkiX-KCv0?=Jf(9$e$1IB|`a<QJ{W}a(~0cIW}#|AUU z2FDCD#|+03GshCg7&FHhuQg^Flgu2Gyw;?gV_3H5*k)!uyw;dmKd&`r?w8jZGuy*! zjhXG_HO0*K^IBt;YmJ%Lplr`;Q|jS0EA{hQmi_V?m-g`5mv-_VBJG!Z2YpmaFyrsg0`rpKSP7`c-|gPO)dQZFl;X74zk^(g~j{B601*_Z2d7o2$TYPRpA zZh|rTME1Y>OkFWNMzr}bzfPN9Un@K$Z^1TC+Qtg`vID2wn)Olm_i+X{DNia|*iE*# zo?P2f>bW=m<<`E}qs8A|I5KhD(DDk8v}J8;)FMjA&m^4K#(vm!{I)yW&vIrdm;O<= zXZ_qp+Q}^KWR`X^OFNmRoy^isW@#t0w3Aud$;|fr)dsdr+Q2MrV3sy8OBXvk1T2H z7*g_WHn(YBqNSt%!Ha^M;JHz?9A)G7ZR5Yq z|F{NypFGOO%;!>)yGc2u;}ojCSd)wO`}vYiT#V%ZBYiMwe}q!OUY6HheI|xyI6NK)k5O zWqbJEOpcx9(kI+r`ik{PAF_VwTkco-ob8cw!FI|yV*BOX@wg=am(QcP*OFu8`!N}- z%raJ)WvnvGSY?*6$}D4*S;i`}j8$eCt5VMMF57dgGRs(Hma)n#W0hIPDzl7LW*Mu@ z&R7-ePO@6gte$Hpi#Y!;kL|W{?7YUA<@#lo>z7%sUuL;}ndSOrmg|>Uu3u)kewpR^ zm2zIcvOTX~X1RWu<@#lo>z7%sUuL;}ndSOr{_8yQex;T(JLAE%r~RwDebwFXfBc({ z>J7qO#s5|J^K!1`{Ho^tzjdz@cx10*=#sgDkB9Acbo_3i;1|QtQU0w(aQWD5$GcJ~f}5Av?3gzqP4JUy>l}p- zrwdNJwZcJnDT3)f$HD#beU$8%S@z2;`(>8>GRuCMWxvd_UuM}av+S3d`&HTCuCmQt zWwX0#Ebgi?x~s8>GRuCMWxvd_UuM}aGxw{qfn!hF z#xW^v=2#WXF{2tI$F`7jjH!IWYeC34CRILksC>(DCC0@u#{D{N6a6}E7X32IewjIj zxnE}4FEhuy%2%Ramh&3newlggsP^!`HLt1q{ag1p-Z%cg*spl~a=#p7f9Jj--!gbD zSE!L!+)Ga>xZnMEdjY{m>+E%pd{#*Cr*C(;mw!-H@Y(0v-IoQF5WMlkW_NdEDZyOZ zW-nbvaG>{c_jh@eyY9`NHg|as&-dfpFP~$$UzRhooZB;Vd)C9udRRX*>*s!%xnH)2 zneAaanb}UZpPB9FaWV6_R5mzNwmDQbJ5*zFsK)3}joqR0i9_WphsuZi#x4B7>qs?5 zA!mD7uCh(&VL90>^fS{~M8C{5Mqv*#ja}HuOg<6zGn22xxR}X@+}94dmZ>kng;!K_%^@bE7ra4lRp+zc>NaZTG4kK4$EdQwA^Rdd|KsaR+Q6|b znQYrGZD8g)5Vo1`PWcU&nd?&c4VRhgRrn2;nci?6{D#X+Z@3PA!)2y7TnE45GSeHb zgWqtO=?&MxZ@A1{Kf`ah%v@I^<@9FlYEN(3E!b?P26P#bxFXxxX zCFML`*`EC%^{{`We)gN}m;EX2VLwYd+5i0J&Ry}msOL^H#}czM4#oUBWA$IoyDElV z?KvKJ-{8KSG4GK4H}4g~2IpQOnAa4IQP{)Gb#82%v!+5Y*IJO@1al1r`BSj7rb4i@ zrb4i@rb4i@rb6`Ptf>&}tf>&}tf>&}tf>&}tf>%soHZ4Koi!DLoi!DLoi!DLoi!DL zoi!DLoi!CMIju)mds>fzoi!DLoi!DLoi!DLoi!DLoi!DL*?wA&f_YrD9tHDwY5fXj zKhU}s%>JSEE|~pB`+#8fr?iLtEbVmGz=$?HFLLf=Tsh-Y$W{BNX#dx_=D(F~C~hgo zDf=@s#{jpN?A+_5eEa`&PFJlLUW3AZ=X#W5;q@i$cd@#SnrSTC-Jw zIG?I&ylmZsnpN;RQAjHRNBM&RNBe;RNBw^RE~?ssH$xf`IqhC_NrPq zk*`_K`c<`aBEPeo?NQa*iSq!<*?zfB}Oe< z$Nrc0^Sscw#QyV7epK?*zk7aE&lfYt2G5;jJ`d3R3OSz>_?*LS`24`<9A-WbP@D+n z@lyN<=JNo>m0&&(P`ruHiF_WQ^QvGz5AgoadgM8Wna=~VJ)Z}p9zG99{d^vf{qlK0 z+Qa7oX(yitr2TvzkmKSp(s~rOv7FBj+%LE1a|JW&;qwMF>*sR_Gxy8q6K1xD&n?Vs zC!c4S*?vCfFw1ieGmlrcXFo_i>>sJ0{U-Zme@c7U&(cozzqFs{g>tvZzkmJA#d7YK zo=}yS|8#dM_aZ)fFgwox;&X(W zoo5Ddwo$We!!e^~9wX~ydnBvQGvb`4vY+BjjOBkh^RP~NmQ(qS+KanxbsaDJO~{>o z6ZS|Ss`N`=wWafzyR<>FJPWa0%}$?7JJt68=?o^%cszEMP8ahzO?6N1nrrHh>z2tL zNc>dybIv+E?XD-lIfcy!QY9 zRu8W_JMo?-{KI~bXC&SmCj}z>Cj}z>Cj}z>Cj}y%AajNsr zpU%c=oByZl8B~2`tIkEPI||CbuDc8VjIYYquDcGt6Hw)M*WC!;A*jv+uDg_f?pR#k zqx^q#$3k-__e}NYkw2|9)qc)(ETTQvu~2=BV6Lm-dMb`>u6yA+D`u{T;rc6Pu9M-q zEM~5s;d(9Rzt(#3XEB!ZXOO@1JzbSAIBtb)e7C0hjLdN>sQ^4@SUEJvpuT26uui2^TqbdxpUqP3OSEgwr4*`J$%O~ z^|Rk(zkDYt?O{JlJNXV%+RyXSWppI?Z}EW7^Ahkx4;{qc>H)PU#$(>&Cc(!GCt|y$ z(J)Kr0lj;s;=gJi;LyUS0X^Z5({UJiNDGI{^@Qw`ap*X&g@lW~P~a@_eJylJ@r9FD z;xNw#Ei51J3x^-ZVUdD57~|#(`ploC^YQ(!5ioGSCzw9W z$LYHxAo{Z>JbpVLGp_33!*|_b%Fbl`bWI0ypZmb{9myDaQwJ-~_`tbs$+-NU4*b^n zz~c4Ec>9SC3NP@1i%XL+@tqE;hWbF?JN%%B zDZPB)&bVX@`cV&Udi%gU-(*Z4qz4VPY0xGa2buJ6@fRN$SuPpB{;G#Rmia)bS4lXi zrU6d8@qwJ@lkn3N18nZr9qJxT!sk{4TuSW@o%bYRuR{hX{Ioml-JOIbt{PxQjUF(A z!pA<$X!`XK)d5TAb>dLj!De*mg|Xs zij#m#CTMiO2L#ti#8P)n@ceZTsM9qOEl*4kQqUJ_j7r4QuT0RfjxS_~CSt-n6U6xX zLe~X}c=WvqdWQN!y%mW#mE?xizHoC#BF0kt_ji5a*|9{dM|#>=7aq~QVLAvZi>{x@kj=y5dIlRV*C4w65JhHHa8!TWV8mb@JeC#rfvty`&B<4QE# zf9(Mcj;EsLY&5JnNTQ{VT~pNR<`$sw>c89 zyd?sPW_!W4&+~=PD_!j?eEzTeKkTYe=$|q$NyO*HdVNHEs$h9g3$RGuz3m z_S?#mk#O^ZAI#lKYlqf_{fr;9Pfo!4FC(DjUOz~SOu+RQBS62*4@Qhjz>0e!V0Ek? z)b5dh?^Z>?;K6=iYMp?)lOrI#wjWfem4FY;5rEHoLZ@;GxIa1qDz5JdqYEeC!te-a zH=`%)$@{N;b@HeN?iU&WDV68qu$>z4$UgvH2&FBy9Bja%#$)7-f&`*g+Uuqvwpg)8T zi^t`pr`5@R;NLqQ)qc1eA1!>+YH%v%_cjW9I_^$HwQW2va*igyF+j{W{h&3iks>b) zFtJuYI7@4);R6Hg_vi;Th)Y~Cz&B(1!FXDC?T#AYO=v$jLF;khRs&3p?+2TR`(zm4 zY-&IFh1%qeGQiTTez28vz8+zKE1CVE$l)a1)7}7PYSZgv5{BiWwHZx)-AKZ#+w}0Q zZ$HTXl7yS4>%k*WKY+T)xTK{XhOg=i{RSlCwc>hkAJiB2geBvQ4>~AVxG$7UOvWy> zU)g`{1J-59=ygX2`4juVwN1&m@VX8n$M*q~BN?mFzL(Rx53I)IKgF9m#!B3chH(Ks zVG*sz5jUgZ>5iVTDsLJNyc`Yfa`*v$NX6P`qG7bVA2fK7iiHkEL*jHl2s@pMh8@wM zUE~L!vQx3ahG=NJf!fc^$p`(QoGBGoBuB&6vwjftODY~+7!Bvo`@zlesrawv zOT9+yr;TE+HxEw23j2*B2Eu6V6y0JJv2nat5?)$j6ftwgBMGl8GKyF_-8u<_G)56) zwQJGe1{g)`buXTTHOCu8Odffkh+q2~MXa{DmWbc}VFCIl=-$U77#lYcoYBt$%(;KJ z;QHwbzx`mr%6f$_y|Q2ztHS4gv!Hpa!ga1#aLO@->m9M+m}?4m-E6`9j}?BOX2D!< z6+Wi1VCml#9yZm2-0$SaAo{)Y$pR5%+c(oJIQfkQ8pHuS)LO9kBMWp(0O*%t!8%th zusR7~`xer3)B;U10V0oDu*DV&*wzA6yK2D_85Y>Q17O5M3%1r-pxiNlqOUFJM&p`( z1>g&fOWm(}>~SWu%MZ-kG~U9t_-_&*IKHFcz9DlV;Yw%0uW!Y{hAUkK+dIU;{m&kP zpWHHo=MzuC`gLaLn(U>tPclQbVv5dj8nf87Mzj83~9N#!}*ouhYu$3`KCJ* zO|@Vi%2So|lRVCXu}@7<=Zg;vm}9}Ik4#XT{&vkw3$A@&f_|rcKs$a8J3jmo(lP3NND=U^|PJ_Xf7pM*j5Q?F~OYS&UVS zn_q9XTk^Jp{~fa*SpMRJvZmS^%xHY4@Q`U{jCroGS06JLyQ}cNHf9X_Rbfqa zGq&HYaGPRgyt!QAsb5T(Yo5YsFHJZgK;haCO=usiaMyb#T-{#bviD8+V-1DpJvL#L zf(p-lYr;aWl(8Jot=L&Y>ke$^ev-$%a))Uow-vHLy&LY}M(uUAEKvNIJ4_-yTRK`` z_cnKELHef-x4@pI?r@O$eHvnc#TIw)dt}1>2^M&6a);xuOqjTW`i*vn9A8aXa*qXq z!`z`#aWk$zYXN{ez>d}@KqByZ(w#%Z)i1&6!C<_TsjME=}4 z#~sE5oBy&;pOu>(f;QJHY~eS zC-k)KXu}q3bVC35H&$G~L?`;~v)YP>mg38`l5rfej~vxw-syD)Wf~Z5zwHp6@z=~p>y65@T$5MJtOo`?w8?k+{=p9 z*6LyZyJ4_6)QZMidZ;va7#zvAV&0MlXxVibgyphfnI8?%|Jz{@>5GVNIWJe_Sw|Fc(ioPW(A`pw~%iDC5lg6(NM zGZW9BA)RFB^2|(pyvrc$e|;zu@AxY7wXj+y?rLj*ty4$A@LHMpyt)BGE{=i=RWh;8 zHzaR68fur!#P(10Fk!)H*#C+8J)wv5w`m@)*ipAe54Ngf;QdBBE}E-{N4{fVh1QPM zX6oU`$z$MRe>)Z!tcRmB$H1rRb}ZFdk=viy@O@*Y{j6;^^s1)lDI9CVpl=oZ@A}&C zTq&jBm33`6yR=@|6PnkC0Tcslr~ZKzbu<@j|BlmE9N9uI=4nf1`mNKaVm9 zJzgX2cxHM&@IZbIjENWuwd^*WTTuf!?hgUW z2^&6drh&f0hQQ@qcI?zs1E(GjhQ#)EJU5Nxa|c8BC_7%BtAYA{gQ3GQJI?1_BI*{MW1Ei#tbb)o*D{2mRf=bR%xM7*f6NpUpgHp@H7tj)9~_nYiz!2KH4M1EI9{4o){i-QRtobch}I zM$j31MNeok+m0;$D0kzpnp%FzedpB_|*hkwY|XF#*S_$Oi(aiZ#bXd zjwh2%uzpf+$UJPrev?hGcyn)fHQR<=!2|(!d&6Veqw6#Y)^mVwtZjKUr$mVwbLjKa?S*VA$O z4x_L?WP3W6xnLCI`XwtJSG_kvvbQhvPEW@+l}#`ytp|84OUHOG6CC~09SZGE$6ua4f3;p@yZMf{bS@c`sybb4{ zGYfmXOWN_tQPN3v?(JyDoZ0kwgzPUe&W_)EDf5+c7v-krW*G8QPdG;VWR*&0a6i)% zI-(7GTWCMZ>Pu|1}omLqqL9cXT@d}6+QXsTrskQ zqW|8j40IG$`i(o7fj<>7348ilGjMn*ldyAebOz3(xnTRXQ!~)7p-Ie_W@H8icQnCA zlP@@il6;T}%GaPfz|k34d8P^W?CJp@XJlZBc_#QUt_O_LWuV7e6U-{#1CA}t!1EN7 zi!XPFPA4<)G~EYwS=k+ue$T)j-Y;_PC46B{uPp3SPYX*1 z`@-llSy-ru7Rt``1^-_&asE>c*w^~P+xSe>9oNA6ZNBiMPbS8%(m<(|zOW{LCVHAR zP)O?wiTmu>bGin4_V9&1(RPGB8pxZ&7pi&MF|CaTHlKgE_-vbhFQal%@ zHY>VAk1cfW%Bg{$D|LtO7uxXB+gKPH>jRs@=;0we%qIYi^H{W z^tlJ1nZ`R&3uEScK$ZSk=+{dN7d$**B;~JTt+WtR)B|o`%EW6Gv~cpbu8@oJ*Mr|R zQ08J+_@2(0y{>2=_F7k1P>kAa)4-AsT_NST9VaiQd)?X|Fx+g%I{_M4JJADj^|oW3 zff{&?9_8K(O&wYm(X3`mwd~(s|4S!6w;c#n|*t-ILGvdM7Q6dK|erCirgQG-lvfne}-9}L& zXWcw*#IiY~L@vv_)QIk<=7=2UHq(e_Q|E}>SD=*<2Tq+Ma$?`-2K4@Mj>wfg(hXR! z>>QCp2l*KA_KVp`ELeEwoJ^C)6E%e|0qQhg>*`nXmTXlHb zHe1+}5voJ&s@cNM+CDn`W#?>R|Ml8BEPrXX7}teTI$Za0w#Y%7i|7!l%n`Y1d08DM zbekh`*3^bN92GoAE4!9NKff0e_f2N954y zqYRk0-yD%cqZ=BqPBmjFl?~iyV5cgBcs#2ogDT0NtZjNDC4<)V|GxKMW5NIkeMadKUG9jec>Mq78voHc!}GBM$v_v_?96 z!pj$CJV$NdjR)-7V#Z%*g+PJz9x#dSPWO%sfr;TB(7KHo-*yTC+dvPP`oV-dz6*i3 zojkyAvk9j>4u*@ z-R&OmA>N2T1_r^$Kj?jYj1hmU76gyFdqQh4;)9dqljWXJud)%#M+L&yl3p+@j}aIB z7zl4;yWKyzOokzgU27H!V>Q| z{N+d}1TUKghk8<+goVP2KGWe>k2qXYD-^oDoesqt$6=|%ArKTh16mX$zfp`G&Fv2p zF3_EPo)GwXf^XhifbXi3PO@{r zY6G6=5+v*|YA|5=pdc}>{Id+`l^p~_J*UF`X$BmXKN#w#Oo7XR1}r)(7>u7MLu$MM zmv0Y-VUs39&}IV;s}ur-pG|@;4-MEPG6cqGC&8>Aj9BAV2!yqp1a+nvu~WNHNGmo8 z8lw^S&JBh7IVM4kl5{73Rgnk%WWwj=!$f;CnlQjCOz1gK!i;Vc!i4_B;q*2U7$*8% zm1)LOv%-Wu*KV2d;HWTRXTOqh_#DE7{pl^@u))w!F|LF-GhS^T3YEr9gW>aOJ?0IC zKTb}Ab0#y+I~f9fnoWml5oTPyAOtF#ro*=JX6!I91kx@~haR40tVZz}UVa8#tV(}- zGZ;>L%z#LGn`piy7#fY40qOfp_|iWZc1)Q88{k+-1VrLxZ5mK7V-TZ^F4{gW$|!e`xoE2^X9Vgg^ZJ zVbTp+*9!un@5>qBkz&Ns!vmpv&fn zk~s}t(SC@uu4}%Y3i)Y297}tk&V4EjqdjopodAf8odTt4y;Oe}02${d!-tm!oL`Fe zhlZ0uSHg&O+tMDAFbO`lHRAnAfzYSOB!KBgG}!~;Wa32lW2F(--68pp6Jgy8BWC{) zL@_@R>~1D}F*OL@T$uo0V@#;s5(JBWodD;~(i;C71YI9ZfJPK!+AhK1|J_9Rmi#kV z6AYIoOoUbI%^12j7-CONgj%o7IQBy@-0nUJZr6*$-8DjB@AXOGKR6DjdxSt_#AL8V z#$m#6%4_wfKujXlvrP(t0Td61vy?MT&E8YR8AiRQsrjG%?caZY<1>t$$M0z^zbQ8j zR#Wb-)+Yo$oSz2m&2bpiEClB2r$d`baacZo2n05m0a_~SMoD+YomxYIY>8*isVl{dj-BwjAa$m&-nHcn5BXVM`4)nSEj7G@MJhJ1M z4I0sYM*`h5B+(rL>51-OM>J@J{Tx3aw;;j8PoHsx#a!~DGZ5TaM zD{|93dK1r{uN67#b3r?L(>)UB#GjkkvGXad$ZrIn#qU%kQa-w|GeADEd=z7znoXBsQ>OD=(|Lkv*;op6K6K|T%c@%G&loMTVnv@genpIISxA0{XpqcVM6Xh=lofwFwuVT z?*{BLC`{=2kYT_Qt;2-=+C2<-_lGdi@48$DY*RN(*mHBY9&@)36LzjN=`ne1n6Q84 zcs*W94in?b=cmUacfw$Hr;#w(TaRU0hC@xm2q@7>U%@}?@QrJIzkQpENDf9I)&P4fw^i!S8p7|zxT{BYD&$Ka{ut6b` zw;c_J2ouI!jSzJ{wdr$f?eqvy=X1c5?si5;h&rD^)lAsphX_&UQ}mq?yFCjRbv|wP z8?jt=xTy0PI@gE|jf%X$5F@@D8!p;ks%6B*p5a2zwATjw*gRb5AGFti>*|Gzev2(O z;5QAzg*`X@4fwWoxUlnS9|KnKB{|t&rM&@TO;RG~jgq2vLXAH^_kDYa&E_&h9h=j(!{=>UN48Ghi*M z$>%zso1f{fwSJ_i^FjK|)uNLkFFnqPe*Gdv`%X!8r#d!L=vj5bh$m?+a2?T}FGl?N z=Sb0S;kqU~=pQNUarZUh>B*78&W2M=xN{`Qsm|y3IVSNrv3BSf@i}o}{~(w{HB@gW z)91uO^x3K%t*MGsAGkM=&WfX$0> zdvF-M+iJj9zXpKkH^X4m2?H*9695hR4uz2~=q}}Z`mDNU2z*=Fi2Hj7!tF{!U|2sR z9*PeHvvn{Wq0jpVe+`669R|aOn?@{LISBH89t52lnb1M^JbBLzg7DcUe7H3T${imB zJ@Fq=LbjvEG_Fb?mTLf}E};n3(<9Oj!x zpD(D+C*@S!pZ2tW_P776{Y^cO2lXNFZQuyFcqk5koEZYgyNrar>*BCwmoJAYMpZ+IG(^3aRFop*rbi3*>|k&eFa6vle#IDP=9Pqf34vT48Q~>!!l2r(|=JOaJW%k0iOql||pdk>h2# z^aHn-{$V}RZ>(SXllzr^W_zUn*-kkxY=8DpWsE$o@%^1+r|(y0bXIur!c_cNQ{ny> zQ*r2L#h-girD4g#3K#WA!z`1+%ciH{Z`~B`6_J=-X8ni473O~H_f?qfiKg!paXhe{SY2Ta**~e0!aOc1|GG29)&5yf zic3%9)+sLi`#zIDo&5$LPIlRIEiKt)XN%d%F8ilWO?HjzyPuL><7K(@1Gks{VLj4s ztY7+*`;~rXd!+x_PB|}Zza>p0z9Vq1o&n3nDO|~9z;;ePOz-&L(ESE~M<9K86 z=Ur{YMlThvlE;KC8)-$G>pe~A6Qpp#c_#EbuJD2VCcIW#C)zBcdi$O_g{OQq;oZjy zuggt$^4;~KO~?0?v&c5C(_q_nUR3IlMjbWb@er!n80!PK=&UuQy%u(TN8eQ$X~Iio zwNPTq(VZ~y)8(%?pL^rxaY#_-qsAgk-ci7&a?$|9F$em90S1pa0I$s0Trgw*> zrHvRyzDjOE^;)kCSlOh35f^;mR{pou#a}D??K?5!JbOYaEhChufn0y;~ zz#GQbHef{?)$0b*TT*2M{=7s3m+RAaN$9K_PBk-&?s`F`FM6!LRRd*pUa;qu9^;N{ z;OjSD&}D-jr$41ykyuaI5voUB87(9g@`O8G^=R#)h4u^Sd!VKD=pCkopK5tP)B8I7 zyj=?=9bMsPB&Iu@q5ZqUfK(mcp*w_11-rrny$;{eJyPejUEo@X4n6McK-aqqtO(Fy zxlVf6m7@zhnXSW$X?iHKtuxq?sJ`O4p3YgFVc9NvuWx36?7^Mk=@T7Jn`nUI9Xi9T z@APO`Xn+olJHtvJJ+`L(wpgvsaA39`4^WMLQnk+THCvAf?+x&=W@j+I*W=)VR7*+i z!&=hWsf-ble(VhA>Ak6I1**gB-x*T27;tDgBl!K&8E(Hf;M^icIIyrY?4&tz`@;a! zu`~GoOn2$`4e;VoXE?Qz-sO)N;6ueOaOJiU=Pje}82WXA@@42fah3rFrFMbEekT0b z!T`31#q0U0^X zxDj>W)7leGQ#`u`=%CY1PssjkLVZgec=z&x#m`I_U04UFj(S0%TPED_jOtxGdP5gF zrxm%Wg~2J_aE9JQY?tXC?2f3ng)KexIJ2+9p9<*lJ$+Av^}Ii>!;DqRy6cpo!yLW}*NxWU$tTL%oK5q7 z*SThwQan_wqsSxTb=cmy#wTym;rl>ky$^e+!}SdnK37+d3+OJ6`+6EcH6gnco^nEu z)mAEfMO-$aH+|oe+q7A2!cDyu-b$a#zF(~HlKLi$KdEr>D@OGHps@FBBU(x*e)z4b z@lXCKJ40!+gWeNcUr_oQ-GDwX{AHive*aze!2k3)z3{W*^MoA+jG^!Bvu`ivH6jjD z_+dACe|J}SsmX{T^qn1UQ~EIFlpD$%4W~E6y*7nE)ihz=Q3~5S)934o3Qy>7!nJ3W zICKm(;beotEFauOVQ!zCTVdAInC_*yFV=rAL1FIKdy>LzPlk`eZ08j>h1q^xGlh9v zQtmg?;A-E#5!Jjo^~`>%cj+&)o@(2i{T>ddyAh{74g1pm=Cm`mCEbBI?cZ5l?;6*X zN_y9LSuXv+?WKQMkMtYsm;U5_rJvaz>3_CU&I{YW`-1X4JMtyoxTx^9_d0Az-;-ru zrB>AA{#y#SYp)mW{janEZqI)!xylXt4&AyoP$5W%o$0%`k0RQ@xvDyRRVERPUE4s+ zNi9C>mtiC!LT2-cw<{4oDFh=wfVGID`ygHZRiGZ7c@AqM-q&< z-5SC-Xz)u~5`Fi*HGECfVA7i;7~HKjEHrCyqjxfW|F1RdBwnAM36qaLb|;FxPGcd&_BY*Wna+RJIjd^w46- zcPS81v=!tG*W&StsW7ZqE2y_ki)GuS!jbZ=pyLNE_UoBS?_#Z>P8%J@4od|;uU4=j zjA{xUI^8qi z_GgJO^GO>xPv;!RrbHN>vn{x%7%**iBIt^@g&R|;?y+|wB$jUrz1om%^%CKi@7lu5 z98^P6FcCg{+ZGz`(POSx7ARY+EzF42V^4~)TwmM36sq5=cG&_~p0$Azl&943nIk4i z#N=*TkDd<{USE#t8@nY7c>>wLXO+UE3K;SG!YM+&@PPp%$X6WCwdl;?yH4Q~?ONUKbE4=)*7IPO= zxKxrBM;=%7ukJ>16|L~e{90_^Sm9ZxH8}iN#pbrlHCTh@i1l}!uffU16z*&yIn4{p zM=jQ1YafMuHfk{FRicnLzNtZDhQj+QXz|Qog?o&mSgo$`rj1(M_fc8P#$r0`byMNm z({v3)srTtdgH(t>^a=#tg8Zh^Kg)<_kUi7NM-)=MDoCbngS9{9OEr&JnKhvRwLs+e`nj9_csMFa62=NpV&ZazgXp`x_I&B0&DfV# z-0_pbtEryhx8n+HO53n>vkcLORIYg}L9r15P>FGy0{% zZ0E{CHqoB#k1ee*kBi5cC(I50%A?Jx&~Swt6#XR~^|n+vdBhD~S4hVTds4yovK#b0 zo`#oyONEiw++d&~4NI3x1MPV?IMX8yqkPg}&;d92B>{%GYt4RQ$eH z26)A{hN9+FTreR6UiWMbyOL9}$?^=)6m1QqH>6_E2N^Kxa4QHrm5RPqtZ;vJE9mzo z6?J{AFtv3n_^xsq4vwEM)_??^{5`hIFh&y!Y4U@bYast}AGR zs;1^}y>$jw_+*80-I~MlkPLiu(+c}aG=~j4GH?T0L4UUy{Qyb^K3`&mV`rLyy^0n6 z%~n`Xv0Gf)1iOW z7Vxwb)zYM-LqlB)2r6mA*8|dF{KFQof@*KZeUlFRhP8z8udF!zNE)2o*%Hhbte9#_ zgKbq?foY=^-}gy_`Q+#C^%S4g(!hGP6~qrD``=RhG;IyD>AQg|Po_e-sMbL9gXXoV z5Okt7w8+fB36@moT*?hL(s%t{8&bj3#|&hV|N_XRbjTXbaRE-{@o1}=5a}RR!q99{et%CE6#E@suI{783hL9d&_b+BTkA9QeWV{=HS-&YB#u7lz;TSCkpD}H>gh3TE?JBE#x z;D^Wboy|~BsG(VcwntjXIP3*e>`SmdG2g2%UA+W59GE9~Ss5FCdOBb1A>UkIij^PD zhX>Tx<|9k7^Nslsy{S2jN?3|>PRxh1)YqIJm*UN}^WpX3)=+ol60CZE9&|X|1=?+* zy13Kx;7krr`n@*#uI1r*u-@PW)*3d{PB+7rv{rB}f_|^2x*5V^+Qa?nnV9#H2`=R8 z3f8fi7?`Y_<#K+C#>0Nf*zetm#YsbyGvWR>(fFW(a-RIANDNLmtFT+g74X&l!aXX?pY%Zz6y9-j`dXE;+ zq=W_!&r5+J5iMbCQ4P-cLN$A3=`Q+WEKcaAfrf{>!sS!3cz0eb{BqU@f!{}uy}-Mk!7QxDMUPt#UoT(n>wf&RQMQ+b*Q%XQ1Rw) zyMP9#$7|tz&K5x5wZ-F=sAjbooh!UFSaA$}SNG>u5UkN)t_{I(W@HzDD|$To4SmO? zz6Y$UYQP7r0-^m_PYCF2K+VnoSTflQei~rFk+A{Lzk@g297*>E0Rhl&r8jgRL$&cE z7J&XsONcukgX=G)Le!0>@c3&C_L-3iHt%MT>(>~JZr>$^wXc^e7QgvE4R({Bo2_H_RN+{>yd@5r)@Tnu z-i*blaf=}T{WdUtSuFOp&xcj{+QGo}v3M(U5mcsoj70Kt>nHP}S)+DzR)|Hnw?@dd zvjfy2dFG&a*!m0Up?DtEWgZkB2QZT4AB!Zwgih_?j~lW0dqh0^rfm@L`|4X4!M%!YVdH1=Pu&D4-M1ZVdKruDi<{ug(GF1g7WG>%0s8lA2PI#} zV%VU0km(O_>RBxQXov^5xc1QbQS9IPJ7((Ni2GN+t9G@4QN;Y+7YVqaTpVPib%Dd@ z6433I39_Dcg%YneSpozBwC9k=Y#>)T+F$O}Rb!$h3k0IZ;kF(IEj82cS|z;1}W*O zo0Np>$^Xo`6O!=JZwA5H;YnyrQ1~4EzUA_+3OBBwgpG14{O(1f_&r9cr+rG2_}i7e zE!cFS!Vgzl@KvP3Px2>XzF`W_9+HS&4HZsUo`?_WK8^LXB%Q-nDZI8`5)K=#uz_qi zPj{HyW--}zb)7}Q(=PJA#jA#o{I46JqdVs=f>0S6rZG~@jGSKfU zDmugHotN*#SU=y1-L@$DpVAv{mEgrf9vq`XUmqpjQtA8b)4~#qncz=snjGv?Eyi9xP()LPUOMB5iTu`y6a7oIW*A#w0Id}8=WYKS_&(YXF zN{Qz|Kg8gCuT&uqni+%EuL{?@8-uOW(}cXm^jPG(BOZ&qJ7Si1N6hl>h*{npG0VFn zW_fqSEboq(<=qjpygOo+cSlmrcSo{4-yJc_yCY_Kcf>63j+o`$5wpBIVwQJD%<}Gt zS>7En%ey0Hd3VGt?~a(|-4V0AJ7Si1N6hl>h*{npNjcvg$@YAA#4PWQnEwy<&I8Jd zVq5=65CstlCR9K{L@<(Ps@Z^nAq+VRNEVbFM8XgTn4E_p4GaUrL;(Y$Aaj~hLBv2X z07_C65fN07sG$7!SKXUi*LV3}-+IsY^ub+=F)Y!@2Zx$Be2XJfo1Lp zEOSR-oIi4Sz>>oQMh*;eNWhZA1C|^fu;lQ7C5HzrIXqy=;Q>ny4_I<|q#QXsQXe@y zV9DVDOAZfMa(KX!!vmHa99M@4i8vzc)*gw1C|^fu;lQ7C5Hzr zIXqI193H8U93HUb@PH+U2P`=}V9DVDOAZeh=MPT@7EcEjPX`uH2Nq8U7EcEjPX`uH z2Nq8U7EcEjPbcN@N>U#l3M`%uES?T5o(?RY4lJGyES?T5o(?RY4lJGyES?TL#P@Vy z@pNGEbYSsxVDWTd@pMuSPbc-^>A>RYz~bq^I4(RLSUeqAJRKP4k7pm|YVho{pM!to zxrsXXtUO!6@@xg;*?Q&o@b~&X*!^YC&)6(;0&-oWujRT1%XJNw>l!TAHCV1|uw2(* zxvs%-T}!#lfn1rZ@#e(jx`sY-U4wC5U&(!a?Ba71IkfWJ1j}<1EYD4_JU7Ae+yu*W zQ_BC0+*iB5u8ev9USl4+zmRW+XRG9!fhFGzEcs?&$u|Q_z8P5Z&A^gx29|s?u;iP8 zCErZSc?@mNLGsN|F8O9)$u|Q_z8P5Z&A^gx29|s?u;iP8CEpAz`DS3rHv>z)8Cdeo zz>;qUmV7g?Pw!U^dripAHmX(VChG&^dngM5iI=( zmVN|FKZ2zn!P1Xl=|`~iBUt(oEd2)%6heYOQ@cWVZ z8L-UHfMtFLEb}v9nV$j6{0vy;XTUN)Bjs0edmg?xKLbrJ`K981i^A=jit1 zwOVL%_<(3#d4PA$8#or+iuZ3p`JO{j`X)d2ac*CfPW{*$FAX^prFSm$#;7CfM(aA= zy?MXxDbcz^QEyH)qBQ3T&++)VtQgMM;{Cn3&0}q1_4q*^m%A>`F!};)$H!Buc=JNT zIffW=#N+K8?|bScZ*4^z6|LtC^7_3-dbHkKI??1k{_cxl}$3`^EuaYm&fgMLqtSW6I-LXPm>Cq&WR_ACDc*b-(I8k53eh)ulQ{nL1xT5u=~r_g|oX z-4CMmv6sEIKlOV?>$@j=>nS>viPrc%pbmZy6FPh48~df`*>k=6Ys;r-`qpb_R&KJc z)7InWcO>h@o4w=4PD#?&4EA{C`@B}Gs>k!LP5j%$%k25R0|&hCSSv15cmKlUf^~~@ zv-2L;IFX@u1$p}1_)vzP;A^#VBHuI1dK&KEzCc%8>Ty|qXXRHdJ)O&cl>Se-CHbjd zoqRV-=a=^DH_X!gd0#B_%Nv$T=$bts+MSIV51jL+#uZ zJGaEH^FJ9g{e9dP-%H}QV2Rs;C2k9rxGh-XwqS|df+cPXmbfig;Qi5)P-^K;w07)L zU2_xXc#P;oS3k8>H&~WJue{rd7PaB`VR5cS-J3d7od-B)b$AMu@6wsvl1uftb}97K z%+54$PnQ0iJtXQvN`V6Q#iNt<79I_o4YO1^*>8C=lOBa65Z-RvN`_?)t2ac zP9&S}_1jIne?rL=YRm7etXqN0tEA9~Cp*x(TbAgPK`C_eFYRg6JxlbVt|`=JNqgEw zOY|M%Qs{$@{JzxQOZ1Ag6wce_cPK|J(fKP=Xu-jDRDR_WU43f`srTB^PhT$4kAIs& zFTT-^KEE+bH@V=IKf>=%=~q70)Snifr7PT-YT7xoDocM;E7i1L>FX>V|6r;)?x?a$ z^%oDMn)7+S-co(2W~w>QoQ_NN$9JTf^B?~-_lwnESKd+b_j*T(-Cs{1kEf<}MpMD3 zIl3vYB_FeRG_Om{(a&s*r;gW-p~E|J^ulHF^!%_f)L>JNem*gt#=bL#Hougk$ByLp z)m9iw{Zsgz3+?$GwH?ROk!N!B;X3hDWBOQ{-I(9Ya8o=*EE-F%UYDa=pXYby<&ULz zKg-tb5Ayrn#o%ncjNe_0_7gaFy~JyA=D790SgKbt z<9yC@{!c+5&YWk_jHOz?!|zJt^M5dk*I(@9ce?TSx}WbM8@`L9vKvRy0KT^@C>l=> z_8djuPg<%6-w{uro*BvO4*30g!SQr`=196WYpG7*y-gC@kEF5uj*(SMrk#6k;{6z}PcZGbYR-EY@;Y=Jcgg4+-H{pRvukdS?r~j$InV9<4!g&%N-*c2 z|9+0P`|HZylEdlmw6~<)Uq6?PGS7uQU-3Qz=OWGXBJUesdvzevJV$QleJbu_Ux4S` zkdNbZ(27X&+$j>^{o;}$>sP!Z`ix$Vl^?sxmH4PwWtBo?n|<#Od?(BF*#e(9Lmr zPo+rnygPRwR_`z7mCt)IR=;s9!qo4<>yFFtJJ9jm{EF8@1%DP{+JEE5Sl<6R!W{RR z?_zYb?GfgD9@-eAgZSOecrMpx@6(pwA&%#D|I`>=`&5MaUi~826I~l=o)>e&x%|#Z z^Bk!f6{F9pNb`L8gx6<%*FDlacN(vV(RYrIG|!{_4`TGooR^E|-5o#0=;f;->zq z{{q&L^jxxvng!lb8@KBUFpE671^pRRo<~&Qj$?w9b5@pVR_YUqCtG}+iPoypV zo!%#6_t&r!;pVwe`td~0&*wey_<6CD_YxeoDcn3qLLW`ki&uo3=SzCMMEyc?xOwh8 zbO-N^GdkQnk2e0wd!cs>H_xedpC;&|^}@~b>&&tQJ?fTl^IW@mQi9GnKg~SvYBx{N z`CF%%@=Z7J{__RXO#N8i3%yAEG}BIbUgz6${4~@4kK=jY$Pv@bant#|KhKPuX3nSY zJ^X%zuxaKzpSqUcC6UT|2J-pOIuWNG-p3NpyHvi1B<`AKo)_=%y(P1FxOtAW|CaX; zsS<9UFU5F&m?xcZ^V}JBJ+J-j5pJGGpYl5HYP=65o_GAdP+gh#(!}#FH#}Z1TorDf zcabZ3-TIbr^Sm3)>)BU-?UnDS#CztS@#|H7&SUG&E3 z=D5Ya;5G6Ur%=;kqzJ9tn&xX90W6NUG&H0yV#QkFR*Om7R{Jq{UVE5PBib?cy zFz;W-W52mYlBi66cK>hDW@H(kO38tNyYN>9wFTu1wy!2AN{4<{G^&gWk*I!ibFCBb~J29vUMkLwfZ;FbY2oPA~O8i{n* zzyWkBEK476%H>4{P)=Ny-pe_n_44~uNq#qCsmY17>52aI%v)JHmFE(Fsnnl#@OsIJ z*Ar>g(SCGiMP8S*o!_hYVLv*_>wGKx$m+=;P*3Lon*@Id2y+(c59NU-}L}{ zw0n|FJ8#~Ut+O6ZGVSkZo~<8mkYtWqbqv1?vVM{|pLX-Ib@qcv<~$$a^+&1Ixt!0x z><8J}?yoEFW&V4;m)Y*GbvN;QwfMRl^>_k%pPA-&8`P5bME!1t`8}_EG(i{paEAGv z7pIm29c+ndMh?@M{*)5^u`kIqat_1o{|{Yef_H|=~=!0#9PV!CPnqX}{P#og1* zaiiMA=^lHgoAc>b6MLIXH|II96u$@UD3|kfH}7PuR_CXi@3r7itnPio4D-AFkjJ+V z)|_E}&)s<+ty7P1IbU}r&+`5}eP)>7|B$kA`ueFe%yqH(0p4FLV}`k28g+@&(SCb0grh) zebt3Zm0zUW?@6TJ4t1d~A6}#@9pZN)pY1}EIxf;b9!sS9H+H4h$1c(v&n8m3)0L*o zS)}LwmPkcLcBSXnEYiJ-CQ;)RU8%}$UV~OViF#k(joMt3$@AMulrXCsHFh%fyfcaP z)xhrbPI#uib5|nOIq(GC_;scpu{4p|9^k#KTl2mODv_G})SGU6bFn^^pTPTp^r!qg zmgqY##M8@94x;;8FVTZ|t}p!6XDIoxCHi)re~Y+h7(G*diGH7R-iq`eP9yd%*7NU) zqv91uQ1xYt^_RT2@cQRQ(9~&*b&-Ryl)7RBm3VTo4%-?_8Cyrt0JT^*b7Sew{Uhkp z+ZOY?Zdsp$BPjZ}OuaEHme*O1ph*XK&)a#i^zrr)yl;4>?wu4%J>DEaZ!OQ%TccuW zL-q&?PR`V;!nvJkBdF(?O#RuUSo)#a2pZcuQ~xkNmQsq2pu_iOn!S-l|7}xaY1^yA z=y<^*U1M%6J@m{_dN_2EZn!y?u4?}beezj`4!t{$wj~duEZ$eP(_3*gIHo_{bZ()( zKP8^d73obwH!Re(o=TwZ<$6%_-3#@BcbTVlr+Gy)^!_r5R3)Yx&A2Z^k7=ApO@Hc2 zzjesatA-^~{+O=RKRiQ6BqY+7`?^wW9>*ec66tucuGIG344t$(k#75;3%z`hd3_=^ zKiGvb&t>SWy|Hwb_ii2jMuz@nAM5#JD2-Z|p(pR>cL04HN;}qO=w+;Phn1l;{}tW? znfIc+ZcZqDR*<0=oMwF{hfZqCpbw#U)0&xcZlpBCyKcgNG# zlc99g&V~9H-otQp>o!zt(?b2@(sZ=-KlG??s&2mMXu!P#@)a)QT^)r9R9bo#uTiV@Ox3&RlL!JY74mD-Gu3Hs<-;lassB zRz9D(ugBAfl&s#7&rNZA9>eoiaQAqKwM71(>KJSy<=Y=lRwR?u%cS9UG zJ-X2PDH(e7*;p!dT^B09AVWXS{gt!5GcA2SL$^E-OC=X{rhTtv=((TAQuyG`l;~#Y zySU%4YSo!u)EOoR0I}mMIU)bKoRI!!y?l}d7kGW>DlgAuJikk^Ql^)G^6lhAz2prq zMt{%Qq<_l4MV>7*mpogrjb*$zewFuQ^*axF@%<8mz4g(O8*t07=`@(9P1BWUafi>y6;s@#Ua4u2!2kE;0 znsmy3ndq*)>AGB2I;~zu)c0_@ZWNnNH*Y4o{zSSC8kJ6?_V5;2XT3beVMmCHolDmZ z&ZW~wqlw0hn*C3CAbM8;4O#FomH#G9U$>=zE)=apG0YFXUO-Vp>QJjgY5J*!1yu5* zI@I;sG=22B0*Y%;mzEt))9Zr^=qa}@?LLyG&mGFAYdX}Uy+5Ss%Kh_s&+qzFcp^>T zI53Y+2Q{G6=hJlIow>AaP(yn0n%VmPby;-gU=TH{Is2dXenCzSbo-ykhxs%1nX&h@ z85Esl_K5iAmvo(+m_%!%`Q60a7b(}yrb#J}81535O0)MoX86RH$+T)ubHh2!lIffC zA%>5BnM5s)wlEyGGKrdJwDjsPoRpngIpT9qAmq?u^)LLmu~vCE|t&8)O+{lQib;Q zXkF<=`rNm&6`YQ0ihzs8yGqx*=D8HhwWp?NgWDD4(nQ z4_HhurqreB<#P3{Z5PwF&2{O`(z&|9$wd_NZe4N@=j!o?7Ez5~>e7?^j>QuXEuc1= z8qoLr?$JD2KrQDspo|yt^i8}kN6^GZ^vJnf-61!fHhtHKdauaUx%1QMSXLwU!@2tT zjCA^CQzJUHDOV3HoI{^PHKFKbOZBq1=g_sCno!c$OZB;RbEw3~CNz4}QXSoB7A16f zobqb&9)LQP-ss$%UM;y;kGwsVdS2CnzA4PqX_2Wk<;&*u=;=(}x3GX}hS#Cfo963g zcjVK7#k_CTo`t&h?fDe(Y8}er@qAFFd^*U#f$WV7^@y99_tv4t>lW&>BlGC&qB`_O z_eFZKwLkI^eVxSeBZ6u!ryf_iznRK+yv^TeZ6{A{*^xDVMXi;cWD)CUR z-c&Pz zryDjqH1tTKUh_ygy|vciJvlkYzE3)>FK}qn!9@LiSUSy5cc{a6iF)H~-upe#p)Efp z>IKVrJQm?l5q`Hz`Ss~EX^KO4+>oSS`6Qj9m{6 z8@5Z*BTsStsSd4vCP|m(bADrnLjxxz={e3UdgiuADf0C{f3GKdUn%>&GxqyvuDrM9 z%6nV>$a`DtIdD4{`v212gIC@GapfHlfA%{d5?|r{nTyq@Po9aCS7 z?nB<6(^*0f^1hM%nd?klN;j3SORGx6>)4%nwCu*ZRAf}DKD|DVYPYCM@yvf@uEU~#?K`(G|K-|}a?Kf+!gda3oT|66N9?KPPHUF$3D^_%uuFzlmf=4AYR z6v5c*>CavxX0HMKv)Aa^@8r7F9Oj?#zA%i9p(n=138y{oH8M#@{^)T_e%E%{uRVS{ zI7v_0?s0TAeuwE>9tW3A()*WrJmR-RU38Ymi;pMj?&CeKc{ow$^z^tnkDp&`;_*#9 zu5Mc0<5@i3u3F0DRJ>P?$LBb=Ej&KQxE+jf``b5r^R7RBK3}^fJnnFEzK-MADC!Km zE}hq|dYn=tU037$G?W*4BwhFBm@N3rlj*wE5s#ney*fWQ;c>g!={kpV+fb+G3+Z}7 zIgh7rNY`8L_IS-so-b|eakFpIb$VBiUpStwUmor8^F05FIXAR}IXAgpz_0KeDaucA zoyu_@@A@fSKfcuC9p9$wq}M&ZcTc(=zS-m2@2Bg5`#f&GI$f7M;_;cq>AEO;2ei34 zn&)hJt`*#SM7qY@FBo&bC5}cA-QAL^mRYRdVea)s3rf3ovF>psf^rtNpnXNS{7?k# z>)C=@oygSXIiGy%oh_)wmzlcy9$rU$g5RaMB~wRpKKV-@hS03nGxdh|Bj}4&A?*1x z^{;P6P^ruidMh?l_gNi58<9r?V3cv62$yPMEZoWRSocCm2){-J_%hwl{#8A>z zEvf72Jl&GlZ%%!>1%3N=o}NE7hCcW)gmhA#E61|u&-+?09LM>4KSa@I*{$f; zVcGw*SGm2O^uKE_^#97bSNq;;-zWdkZF_QC@MLOP`gji%t%s=ObED+;hpg&&)7te|<}OwL`LA6ca`b zvs=*W>dAUcEVuJm3p#!*N$=n~bTWkAT$7}?KNm*Vyb?k~dEQ_{zc3myHG~@Ref!j- zVU+zu2#q+)@A|wwj7~ioLLF8o>fuKw(UQg?RAXGC)-O$>cbkV$?FNbZmm!m=T%Qnn z?w17pVdY75byNu5w1MAUxMd>M3WU(vlmy*$!bJM{SH2GnOwixnHIcq+(}EiDe!qvd zO`x&MT2SrE3HsKV6X-(umeiZ`<>ob=K&PTw(u>D9PyV_IG@t~(@Aa#Az5nod`j&O* zzngR8_m8LUAGM-GoTE5n@-(AWbg|hwI(izdXwr&K6`8GXO`k^B7q+B*9MgH?m1#7o zeoOlKbeevA0IvmD6GG=_&DLLb3#Z=-L#RvGY~3m(oEE$nLQ|fcttZqEr+NoM=y0>y zy3*a@^nKA5^mFam`iF|))TUMo>U8UDJ*GrBE$-fehLxJFAN^q(txae_V=tuXGux-p z6B}Dl;@LDk>MdRiaJ~f{IhCdl^Sxs5&bl=8rYyaEeiX&_u1A~7@_UYU&!D;~JYRGq zNuS#>gSyOfXxH8(9sAx4dX9NJ&+|CXOs9~vCN#TrqQ1Hh-(!n5q`{lwb=A=kRIyk? zI`c%lF3#oe#WbSqC2{(b27C`M6->2miqlp0&ZJjj6|K*T)yF$VQo~jC>AUA*b;bFS z^z0jrXa}#;sTmVVOT&X`cfT0D=Gp0#IkX8?-yN$LB}CBpXBCAc#pu(SGilp+hXz!Q z)%!~EKK$c?sLF+C{m$BOnm({8y}2V+U)_xF?Z*{OoX779e0C+Z*aWw63>EX_*u{=xHZk-XTiCZF;x1hP^#G=UvJKjp|{=&r4Ci|b**_Z zRQOyQ$~~W_XNSj7Or^HeU~`^cJCNT2QP7qqq~z)CAu;q+xpp+8W1j9@JBIRmwxac@y)oJ`5;hdM-(W#VN9lIr(URm3Ynug|bE>kpBSkaDNDw(TW@E#qd zW7^Szw{vv+QPI@CZ9D25k)x?|G?ggQj_zuaqZbE9(`%V+sZKfG=e$}pwYsk@E!dx} zU%P?pEN???*JNwws%RQ}M;od#H(T#I6-7@*h0<$Nvh_QB|6liQYl<6@tyB1!m=xZc zHvjIKXy+f=If}UF{Hr`e`~I_=??2G6%&k}k*_7_<`X9v zJ?Bj2_cOMhVD$X8O@bbMH`if3S5{BZ)2`-w4(mCySb|>r<9MUzEk}4=%$MVhp5OC2 zotpc`8$BQ7dy9P^w(m3Gzys|G_nZ~w!)gDg9VnIOT_^B8A?M=`)FflJzVA4%3EI$s z7Kigb`JYXrxaT`i-$AqWZR@Aei%}h@X4~2N^b6CdXU`6l*l4zXD`OhRgE~;98ngA` zq-msoq*if#j$75>@z^k4&wg`are4n1?CYO&po!0B>JR2d(9WG5 zX#e0$jcf4koId6nypG3XC!g+1t@#=(QxHRE@99T-`5Iiy*Wj!@{pizQ^K|U=7@9b> zKRvpY_xv9eLtmC2z;Tg0y{2UhwI4Tt61(Qzf0p8;{4{=KVTKo*6(PyL0sm z{I29qw+y6(JRW;{e>A;abs$Y1m#g3TFq-C88%T9{Y?itrny$ZbAjOx+)sM$U(Xv7 zV$rm2Nk3}4Fk3g_eOlI>?n}v2vvp6t25UUlmvV;lx@Nux;}ZMOFHdLdO+Q9a_@}*T z<*00Z{m)U9Riih}iQsFtWHb$&_9WHF;qlvT(NyG{UX;EyTmM)$n!5DvMY}mp_h|cQ z`tV3kTF@j%?-;8N_byW;KQML~a3d+~G zKiu7EgtT-NEg)BC8+V@=K_&VA@Dz{JVx1Axo5yK$4~(bqsNq!cb6!t( zdOT(A7)EE0^Ltw=@VMoHVH8^~LDy0|wwXPY&Z`9d&Cm(dxy(?aQ3*ORX98_oFob?x zk)T%|;PR$JXyq|}5Boh6>AoUEC?_aU9~&`|PVRYzE<`5km^Bk=-u7o`$0vz;`Gtwp z{JUr9!8?<5%;S@2%PtNEn4r8%EjT$$EAlzR%w`oFW$_>*7PhsJk9c@8ul%G6*ERZDu50x5#p{~;TCQvKwOrTe>xl%G6*ERZDu50x5#p{~;TCQvKwOrTe>xdi7{80KKV6rQtXtm|M)|Az)3)x(y6vG!^kdrrlyqydzG2xU3gi3s*PkZo zxx*(>^K!f%a30SE-9L%$3mr&hJ0|g(?uk@#)IfTqRFW?K?nJ6GaUjj)IUiitH75@= z*Y(_P6KTe(&H))$|E8Cw2gR5tX1%KR$sv zTr+@DLK5_5z6Ps}?oaRVHTcev@tjNEkM{7pMZVcOp4Q*ckG|pY^SA59)3fdS(u=Rf z>)^HHX-j+`DtI|wpM7&YZP?VCPQMKLx(6+)nWT4im_!pR@qK$@l3qK15^d-E zd7F(%deW{*GFkf`x@AxjeK9zcDt(=$7xy{+1+ayDgOZa*kic(n*wmER?%q@OQ@yoq=%ez9I`9q8?d)npl}{$<_B*1f<&id& zwlhILzcHG6{KTJqJwfkW!{d`5+R*a(3HrdyXk!}+bmR43>Csed zNgEo>`%h-3MbllQ+E78o1U)60=Y{IGp@sZj^2&+P)c4a+I{tRNUdNu|yKbyiYCNyk zi>CVPTT{E<@!F2X_uiYp?^*3i!=G5Fb2z`W;kK@{y5~Y&X=4ISyQUjW;qvR(B+yan zMq4^A)Vp}yM~%_l=;M%ude6KB`e{)&`l!)DJuy0g>b>2KYS!S-j!&TTU-24~8y4!j z2PaVU&)w+#GYj;EZV41pvO5LuTcAs};{58;-RY6H7U;+WyuP)2ds_4P0$pNDBBgxU zmbP5CK#%8jC=Y(qmL}c1Kv(!Wk$ybUmhR>K*3yqAQdp^WRK5QK&V%CjcHP^K3MVhn zvri{dWV?3Me9i*>0sjWtPi{xG`F#*0xIF&FcC>%p0v*Nm&wSmEe%QP~*XDMbRBlga zKV6`=w&gV-eB7EtQuKH?#+=WuA0_MXcQI$kdn;{A*6z+2n*CWjy5&0RiP<*+XuWCB5Sg!a;onAMzqoD*j1_etyiOshRqJ9XottB(6;$| zDY|$b|HfGJmtRcL&6Y-+zNkJoMVI2=4Em@^c#0mx<>O2QeI2O1{`$&#`M>^pd3&FVEBlI!q`&&UBKCehSN30O&ud5j+WRlr z`<`9dr|z%6Po2F#V{$G>Vjw>~4Yv8d?AE_pR9FGe4flN=iswtyS*R$)u^(DD?b*Zp8xzB!%ya?s)Zrv&1Y9P38@i}}RjP}qj7{}=zRIk7)FSP0hz}BEmznk;L|3`hlzYJUb9jx~_aL z>36BG{O@ISwAwf2R=>;nm~#I-O z%TKcm=O3Bwe4~>L7j>pPZCAw^ZoMjqAX36rHQgMQI;mk(nMLBC`%J%X`(Dml%e;COBo_fsi#4@9u7BxOM+_gHt_zIAf}_V}w`# z)|xY&J|}mZ`YmclI$7WCHGEf#c&BuyFAVQ|Kh@b#;GKiT%F;wxnkY*XWoe=;O_ZgH zvNTbaCd$%8S(+$I6J=?lEKQW9iLx|NmL|&5L|K|BOA}>jqAX2R_(%Pnw834`r#1%$ z4eaR*c(=Lf>%FxR!)mS_ZdETp|vya*u94Lx9aHZ`~FVDZ$8}F*;b{h z;r_+CIxp0#VtCxc-JSc^nBR6_M0^kDsaHJScCweVxVBfP-%GunXU{@0Eh^n@+Ig?yP-o!D8iq#)o^wKX)iQkho70`r!|wk*D@zk)X`(Dml%QcVcm1M!~(# zqnTrjR#(4N!znp_h~Y)QR(E0^9BjDC>Z(rO^uC7Qf47QLYiV!8b?>R-=!3lsf09?( zX|wGK!zDhg?2PTx&2V;P6{jwBG5l4zJDtVlI~m@1zNYit^Pz?xq1w)Somv}?ZFIkL z@6J|+j zqAX36rHQgMQI;mk(nMLBC`%J%X`(Dml%O#>U`aNq^Uo#bup(PeU#zEsN&9(4|u=%WuIK*jITb?lo#|W z?F0|?&iSd@6`i-I%rND64&xb&^S4-8nkY*XWoe=;O_ZgHvNTbaCd$%8S(+$I6J=?l zEKQW9iLx|NmL|&5L|K|BOA}>jqAX36rHR6L4dXWaPAm?5)PvNum1Y^OetWl>n)Pm? z;i7$;souxp4JXDoRwIkV7=HTM#_Fe&p0+)Cnb1qudYq)2skdUi-`L5#=IXvM?>CmT zHB^mQ?)A%-8eP@xB|Sd1b&6WEC)~7ox@v^_f_F1Oe?3w;M%{7J zcWv{2Gvk{+RakeQch9+|R`0@hKK1nfd0pqin(OORh57_0M=kU+Q1XnoXoqu}A@ZdGaz3&xQ zacS^#tLK<=V@-m6O#&7xOA}>jqAX36rHQgMQI;mk(nMLBC`%J%X`(Dml%`1hXd&zz2fa z69?b}!R(0x@PT0V!~ys~Fni(vd?1)TaR5FL%$_&^9|&eo9Dol5vnLL~2ZH&&8u0J2 zHY-aLWoe=;O_ZgHvNTbaCd$%8S(+$I6J=?lEKQW9iLx|NmL|&5L|K|BOA}>jqAX36 zrHQgMQT+UM{b#Yw0rtc$d?0jVPwc`6g4q+h@PT0V#4dawm_4xz9|&eo?7|0v*%Jrg z1HtTx1Mq=h_QV1BKrnma0DK^rJ#hd&5X_!903QfuPaJ>`1hXd&zz2fa69?b}!R(0x z#s@O9Cl0^|qMSW(06q}Ro;Uy>2xd4(G2ZGrXyYPWv_QWoHAecR|3m*t(Pwc`6g4q+h@PT0V#4dawm_4xz9|&eo?7|0v z*%Q0)fnfH;E_@)EJ+TWP2xi~s`X10`Woe=;O_ZgHvNTbaCd$%8S(+$I6J=?lEKQW9 ziLx|NmL|&5L|K|BOA}>jqAX36rHQgMQI;l(^>F>U0-FQuiCy?W=*FJdg%1R?CwAcj z!R(1$_&_jwVi!IT%%0eV4+OI(cHslT?1^3YKrnk^7d{Zop4f#C1hXf0;RC_!iCy?W zFneMbJ`l{F*o6-SvnO`p1HtTxUHCvSdtw(p5X_#~g%1R?CwAcj!R(1$_&_jwVi!IT z%-4jqAX36rHQgMQI;mk(nMLBC`%J%X`(Dm zl%>V{^8}&^<_Sa-%oB(vm?scTFi#+wV4grU!90Ozf_VbbL|K|B zOA}>jqAX36rHQgMQI;m~#4h|W>tl0(J+TWP2;JBdyYPWv_QWoHAecR|3m*t(Pwc`6 zg4q+h@PT0V#4dawm_4xz9|&eo?7|0v*%Q0)fnfH;E_@)EJ+TWP2xd?0!Uuxc6T9$% zVD`i=d?1)Tu?rsvW>4(G2ZGrXyYPWv_QWoHAecR|3m*t(Pwc`6f_Yr;`Y|t?F;5_x zV4grU!90Ozf_Vbb1oH%<3FZkz6U-BcCYUD>O)yU&nqZzlG{HQ9Xo7hH(FF4Zq6y{+ zL=(&th$fgP5KS;oAevyFKs3QTfoOtx0?`EX1fq#z|L4LRvpzNl*b}?(fzXXTu?rsv zW>4(G2ZGrXyYPWv_QWoHAecR|3m*t(Pwc`6g4q+h@PT0V#4dawm_4xz9|&eo?7|0v z*%Q0)fnfH;E_@)EJ+TWP2xd?0!Uvi4(G2ZGrXyYPWv_QWoH zAecR|3m*t(Pwc`6g4q+h@PT0V#4dawm_4xz9|&eo?7|0v*%Q0)fnfh0`+G*bSTsSr zSTsSrSTsSrSTsSrSTsSrSTsSrSTsSrSTsSrSTsSrSTsSrSTsSrSTsSrSTsSrSTsSr zSTsSrSTsSrSTsSrSTsSrSTsSrSTsSrSTsS57|&vt^|2Z8Vi!ITy0IsAjSpmIPwc`6 zqMSXk3m*t(Pwc`6g4q+h@PT0V#4dawm_4xz9|&eo?7|0v*%Q0)fnfH;E_@)EJ+TWP z2xd?0!Uuxc6T9$%VD`i=d?1)Tu?rsvW>4(G2ZGrXyYPWv_QWoHAecR|3m*t(Pwc`6 zg8ebu?-}u8(FE~g(FE~g(FE~g(FE~g(FE~g(FE~g(L`CAAYLq*AYLq*AYLq*AYLq* zAYLq*AYLq*AYLq*AYLq*AYLq*C`%J%X@YpMXo7gLXo46q#`fq_n-MQ|;RB%?dtw(p z5X_#~g%1R?CwAcj!R(1$_&_jwVi!IT%%0eV4+OI(cHslT?1^3YKrnk^7d{Zop4f#C z1hXf0;RC_!iCy?WFneMbJ`l{F*o6-SvnO`p1HtTxUHCvSdtw(p5X_#~g%1R?CwAcj z!R(1$_&~7l0e{bk7mFr{7mFr{7mFr{7mFr{7mFr{7mFr{7mFr{7mFr{7mFr{7mFr{ z7mFr{7mFr{7mFs!(gg8h(FE~g(FE~g(FE~g(FE~g(FE~g(FE~g(M0)k1<=H1#EV_{ zK<%4<`!Uuxc6Boh|M()bN2||M( z)bN2|myz)njl^*njl^*njl^*njl^*njl^*njl^*njl^*njl^*njl^*njl^*njl^* znjl^*njl^*njl^*njl^*njl^*njl^*njl^*njl7uTu}3UEk?Z9fe(ak?1>%tKrnk^ z2R;yt9BTMLFmkBj1Hs6lh7SZIhZ;T*j2vqCKrnKs;RC_Qp@t6xBZnG35R4pZ_&_jn zsNn;_$f1T01S5wUJ`ju?YWP4fa;V`0!N{S84+OI(cHjfS$f1T01S5wUJ`n8Z3ICoE zFBVM@FBVOdr3vE2q6y-~q6y-~q6y-~q6y-~q6y-~q6y-~q6y-~q6y-~q6y-~q6y-~ zq6y-~q6y-~qKUFJLA+QrLA+QrLA+QrLA+QrL5$deH)efoM!eX84}@;Wp@t6xBZnG3 z5R4pZ_&_jnsNn;_?1>%tKrnKs;RC_Qp@t6xBZnG35R4pZ_&_jnsNn;_$f1T01S5wU zJ`ju?YWP4fa;V`0!N{S84+JBJ8a@z=9BTMLFmkBj1Hs6lh7SZIhZ;T*j64f}PRVA( zi$xQ}i$xQ}i$xQ}i$xQ}i$xQ}i$xQ}i$xQ}i$xQ}i$xQ}i$xQ}i$xQ}i$xQ}i$xQ} zi$xQ}i$xQ}i$xQ}i$xQ}i$xQ}i$xQ}i$xQ}i$xQ}h_O}$bB{K||2go1&<#1%@PT0D zP{Rj;kwXn12u2Pyd>|M()bN2|J z)q0o%9|%ScHGCi#In?lhVB}E42ZE794Ic|M()bN2|79%Tr(0KKfj0HK*)h zZw_aER841E56^eozUhjW^t|NDnLV7!>pdUJ|8@BPo8Oh~9V~BkS^Fve9Xb4aGWziE z%i-VIe;7Yo{^GLs6nuYj_&#OEjeOs7`2O`D#*o$+`?4Na^K;MP=bzDspN9@V7Y+Z5 zaa1tISJpV{vKw3a`Y7n&>t@*hEgANGieYQ766E7uR{OX3*PYS9za9$EV}jB>2g!dx>L>$EV}48}Sw%r%3tP78C*U~9h)qMN|qMN|vb^a2*!FH%sGOwUI%lIV64}{oFf?Pbui}$#(EvhIfAiX2Xl^Ktk=Pu zBN*#-Fy{!ydL7I;g0Wr)bB^ zj5RBmcLQV13g+FwShIq8H!#+$VBQUkH7l5R17pn!=H0+pvx0dyFxISK-VKa3E0}i! zW6cWY-N0D0f_XPE)~sOO4U9D_n0EtX%?jq-z*w__c{ecDtYF>^j5RBmcLV#r#<1^q z4Er9?updh`jCC8Bd%|b2ZUb{qV65A~+!Gkb)IFh7cM1K3}mWf-|v7&oBYTH9#yH!*HNxwW>@XdD;E3oMH^@f8A zP6zHjzrgS{saLyKpXzORYLV;R{W(_|esx$mclz?8Cid~IdxQJsb2H4Cq{8Xa?!K0H z2GHhP!NuIj_a++-p8b8G*{lM?t;2-Ls41WWoE@ZG@puK3PiXaFt1&;}ZTp&7IT%ew%;@{RzoygLBQd+#gk^$+&n z1z=d-L4b03Hv!mx7k~qncNu`KoFy|aBICeI#Z#=}E9EJpd`D5HrLkHET7iP2nk`wUxg zE388|IrsR@U`&Cr1sG!uj5)wo>j}L$SAmS;qoRFkbNEHMkxzZZKL| zF=gy;ATj03Vn2M$m;13Qh1h~0m%;rUd7(xh%&+@#oXh$h6IT8P_8`LAF{2OSHh#PY z;|Ju6nsO@#2K(?x4h;6;ksO%+v+r%e@5ql;VP7w-pE8=@cjU)wFfK*Ds42H{tFX6~ zn^@?4Qt}%ooiSVFYjEFwPvRNAMx5& zF6d>qrpDI?^CzNP0PN32820BV3}4Rc)cott=-^+EhW+c#uzx*zbuQzzpZ@*a#c#>K z&l~pd=Z5|Jyy44vJ+(hhFgp0-2gCk2!LUDmFnl@hQQ(h1jSl{})UZGPH0+N{4PVat ze)zt|)9N2<0L9msa^LS5zMS{c@%^&V!S~UIeZOqj_tA#2E*ZHUxW8R)`&0SzFy_1a z^E0AP0I>>a;?K_*wqk#m-JWm${GQRlpZ7ED&+i%b=lu*@G3Co{A4PxO*y!NTCmZ(X zjSc(r$%d_5h0AVlQY(K0^9&dFJ@(@fMjt;;Vc5!nx$O4);_d$rzM)>SQ5 z2cyows8a5lYwIa+%S~6g4V#+x;HX9`js%VdEjQ(U4v%3j3-I3zbKL-c#=&Q~jR3c0 znAz;|0DAcmzb{z zSo0NFNANHAEBGUx{SqEOV0nC56N=xAz1JMp3SHdi^HM(d623TK)t7aYrhTivy+6z) zz2POiWWbM+nKmsi`A_?B{t-WQ3I7$a{MRM-xA`L;*oz7qP6{LLG_A z8@9*oml)^E`Y+SIRUew0^%dyrKQh+6#MoHYOquqru`zx#$iXn>e`I`kiSeYYGcxU1 z<4IYQWy=4^nCcQ^Fj<>p+Ofu90js{z33@^QON~P=F>b*<0qa@J{ozu1^?n}R|M%H_ ziDx}>|B#Po+P9wd0js{S!uk7k4Evuo?4N_VpZlLhx$)C}PM{pilw0-fbxblgGj00c z-LOBFGwf?++VM3pY}FUdO}XC}4$j~2Bg6jq*|7f`Fl^Pw{qx_h!}5Q7=Cl59%&_le z4Ew)f!&ZIVKmYBTIR9EOpY^X1!@jRH>|cY1t@^ls{@eA5{tExBeUES0_x@h{ z|H%2l{nI?R(AQRdx#yt1+>6X-{d<&QJMYE62byyKUS~dQ)t7snDYxp&-rCZpdB&r! z`Lh>uMf`iXspH?PO*>X@iQKDAxm91D1?IEhXPCPI#@guSUeP1JQP?w6j(eISaRvD@8zPfHrt324MufTpghW+*p`^PoxpO0bR>pA!=jsqRR(s#IaL|d?E4wk+E z`x=^SP5KVy(x+hQYq0zVz;Y};u99-F)CWsDU}+yL#|6vzfaN^Fa{gfdw^3k~LtCjI z0Q>D2_S-k?AJ?#dK8CH|hMYfs56b#&pj>_%_+F-uQOEBKX;-3$6Ge`ZhP8OoP$$^IpS2y_5@R_S;6wYn1$?(CN`Gxq0Iw-^6z^IGQfYAop0;6pl z1B_#Gd61NI{a~rj?HEQo+`eJ7&;JbLnEW@xI3^#%FpkN`P-q9ou7Z%KE;_(gE!h;@ogdOE(3+uJ`sSx!ihkj6qe_)j1 zZ(!8LXTWF!ZGq7?z9SgNqOc5sc&GJA!e191o1+<2!y9cY7NfbqM)F}!vvn?99tO9%8_Fv_7Njsb?2_ydV&oGx2^4|<|-2i{aFt-ulwt`Tf+csK) z`S*hIwNj2_fKeaE0HYlo1B~|Z4~#PW4UD?@3>ayF_oo{vUJ07O&yf+`6#cQtYCZwj5e%(G1tM} z7gn3!0lu4XiBGQz9yV#ODKGKq^x)mUc)y95_3MMDyk5baBiB)PK3Bu=&F+O@aIHSC z27O=rq~U_Bhl5uf*l!qZ-1YrCh95nW7mR(P`VZ&kF`UPiHKWljEjkgAG z98e^HHt+dxK@cC$Fph7PueItITJ02C?H5|dEws+3&^ph;_PVh-?y|z;g;!TQWWHBu z?OzL9G`Y=i#YtBMn2io#u45Q=__M({Pkh$Wu+Y-B(9*on>Wf0Fj|#26TWj|z^S}KK zRLnRPgx|@=r8U<^9NlcVVA|rf6*I<}-^|9P1#3%RlVr*tdTJNf2{q*f)2bBC{`LQ{ z_a^W#iZ?j4RQHBhglTw<| zph0tp22G?8-t)WG{#~uRf6xDYpXYw=`{{mPeLnls_j6e1aU5&?&U0PYd7j5w*OA5? zyEX67suB%Xy7Q{~zTe{ZC%ZQF`gB^oZ0tEJX>)&{f~$KyljGXlcj3VJ*!!DsPHxQ` zw)%tF*Q}z=o16BmI;D6!*JekthvQ=xtfbBTeTJ{@{MlmH=H8Rmt*UF+HQ^lo^z}9I zv0GNr=FLsFu72i*9j?up^#-qM^<;rnv@vC#kB_apnl|^Ibm8j7rxsXEtYyDExpMp9 z@~df6q05r^*xs(qne~2I6|`x5@$M16&1K``V;^*FmiJmC6_L6ZA$fS61Hg) zuO28_9u=ar?x%)Fe0ul7n;R@4mwa-|dgxbH(>Q z+=u4xSCNTFh+~dIXiF+TI z`x5?OZ2TKcTaJP8fiD=}#Dj^+{e$e>SExPr8!&#j4}tN|n8L*5-UKEl_a-ngIS*lC zhJ6g|+;geDyT{4*zJm67p&x%Net!S17{_(r@x0H1iT2p@k0t-VYZK%wyKAHN^d~=ucz^Z8 zv2mM3+|{(n&&QqHLHoqGg>8cV5-Tx=53K0p+SB&5*hgOM%W>>Gk!Kte`)b-_Ck9M= zV#p6MVEpq3V?BXe_#g&$e203)nl`OoW4!BQ=`{~HuGPIk z{Qdkc$B)l_CjQ>u!!hSkl|3yTxA>-7Ui{}cwsDR*j@#zN$0Xx3_K_F+avb}1+F_4l zVqXnoCx+S+1I7do+7biC2fko@69Y!Oz@8kmkM9i=eq0RN)2AS=i-A3E z>teu+O_0CS4m)ER^q2M;2mCaZA7a3aC4VqBVt79VT?`l>asJMZ?@%w8{_!7e_&<4( zAIzBG6K1T41=By`!Hg@p!Hfs-V8)4fFyqJn`HyiW28^8;Fztx}_FOR@AD;RB)t)OJyT1JS{O@vog?hov zpImz(b3I~bp5Z#ppJR`G#>Hczd6F?o{pbh7Nj^(?J zd!Ed5V%q3l>A&llJoyCoO}c-HKcoM9-W>$_$KPRozd!o#dmjGh_iq1;XZYw6jFn^b z{b#&`KyAsIO`kp$ zQ}~0i@o(PGmZls7;{#tXzKH=7GqC3c?ehXZd4c~mLEJS#K5K$J*97^mnLqu7sy?4< zu;;;XOxin+W8%kg925U*XcNa=!yk-|fAfB}kf&pO;0rsx<9<0FSTgC6z|J_Rebc~? zi;?f2@pNtIYmg7)?{Z^og8WmY*SeF-ryP0p{bc-XT3j~ey$9Mgg>QMZWXigeXE^R! ztw_q#vtM>xrp)(E`J)Xs{tc!r$H4f&7mROWz{CvftAqA=fuFp*V! z)PeE89dZ14)HP+@dsS0tGoyJ6_XlI+-@KnAO*sa}2fko@69Y!Cz@8Vh&kOwI5rg)z z|209}H9raS zu;ZH;aD0wD64)6BwQm~uX&U%BVSZDdZa(B# z<|O7r@5j%FvNO-X%vHpInX8zWVEpq3W8>do+Hwqx4`RTY4`I!R`F1xS=C^nAAx!Rp ze-{ILY;!SS#xls$#lX&(F?RUS^#!9N=Pk^+&-n~q7as>x(v=%fx_V-%c;@$6sHvbKa^w=QGT?PYjrI zpFbEI{|3{R7%)DF0qgpLb$#XAT~7J!T@0Aq1OM*&!p>L*`MB!~J7Yr(m@$)HXPwbM z<-%!ITz{93>YMU;#W{|v{MseutTVoLoVn_HEgK5h#Fh1}F zTF#~&E&^|BllNb136U1E;>6-FxOXLXB^bNY2e4jpgnyG;xf+4hw)dQ=;D|$W9;}(dcoKk z2bi&Bd|<|s7%*eWAB>HEgK5h#Fg_H6u_Oj|{tN6*FKpx(_;Gq+r%yp#rx$j{Ajs3{ zg+2D|^n#_A?8JZ>OU4Jr4>4fr1!LpiVA^sFj1OYK(hHVe`F5ulOpbvcrx$km6vTCU zVUOE7yfnH|r= zvmImO-@Kn|;(2?6V|?HXJHCkl^Iu?J9kh=>zY>1p&##34ydZ9Tt|jux3-Zhh^3RLM zt}1cjnAqLDZXA>LdD!Ea_;DP^#J}S>CUG5Ow%kjGJTn6vSnmot-fV@?^M4FOZJefbq{CjE#STY0EJ% zK8OM9J2sr(FWKF9?ELobJ2p)2fq(ZM8+&YX-?3rFAjs3jz|NQj{lc#P(!MEe7|URM z=!3K4pFi4QBL+-cj)CzJ=;F?K?8M}phtZRB9!6*MhS8sM9_GB@{D3)MIOk!`qxcxd zoL{jom%q+O@5i6>u+Djy_Qa4MV!-(455`6en6?}P>zs#m&cpfra&5>ZXz$MXd_V4- zhv`!g*PZj&b}W z`p177OXgCTKbU_D=G9}Lck!5T9&tV~K7XapJG44>zxMBSzovU%uD3rj_r}<{zvEsJ z=Dv@6X_)&#?iFF(cf;8DH(2-GFh1}F>%JT2yb0{?zB|9YyYGg%&m{)Ty=f5F-FIW> zUN*?n-FIV;eg9wmoP<6edk*>U^&AqtIPaOm|HwR##m;j}o(01^&*T{>tmnxv&p-Kt zdDhFn!L;QVSkIGTd=n2QJ~8s`Jf~HA_dFRp&sGEf?s+oy*tRCf$30KR9{X_5lVP6q z>iK^h6TAD&!p^f`wI>Fw=gBbs`GfU58Kx~UU_DQU@l6a^&y(}*jDy;{=gHW~J@D^h zV2^Ds2FzFndAbgy~b@pK*4_GR8qZ=%PHGjvUJv>$;PUvNJv|*1zd{w+|nY>64OZH*tV zHcvP2?f7Vki_Nst`Z``)uaVh$(~XYPAE{}MH0kH~#r5UPz6U(7NNT@Uylz0BwXAGoTQ;{!=!*Os2t!*TPwCazu5x0~bpR%NX{ zu%naXCab5ctzVeL*ClxOo^K5K)24Uh9gaEnz33yy`0SIn)iJSV^xo{4 z9A5k8702ZE(6ARBlXI&Jo_9=NMmJpVm_B}yzRody7c(ZCPV;RTt4hnCb8Xxhc7MS! zV|!E5%Z?fI*%_}pZX0zql?J}%xNiBrX8YG$9AEe7t>)WP-g9hf-Dw7|{@8K#^g(9S zTHnX5PYgEdJFGFG&D@>s-1u;8%^Up~;`95wuFg)Zy_>o_CWozKdM22B7JiXom1oF| zbC|P^RU6KwkkwxP|EL`~)Baz1{wNl4b*{oXS7Dv2u+CLj=PImo71p^5>s*C(jlf}C z*%=?%;m|JT*ni|Y)v@@|H4f_ z87tz#p&!{bhRQ9pi#e9_P}j~sd)`ni;wl!bISSSs1#6CiHAlgkqhQTZu;wUO*O!<+ ziZwqdAI7Tj?bFsy-r34_pEk|$$tzpgZn>Vn8QsdZn&WwR&sO%kCp?!jt!&X1o;Q?l zWzT!b^VmYI?CuXd+wWW2ncsQtzrCehTsX)1ANXlYdwV(0*c+Vhnf5JPd&bY9uAcF~ zWT0o_ZhOEp`Rp6xnLKAq@l5_{Gd$C;k+VFPE!8??+=#33Bp;14d20O0A6emx!D6W4%N^Z3>^4$g}z>=Oyy5a@u)`eqq-Dq5otOtoUQ{|UKiCGP6Z1y%dZiQd33h2md(D&h z(L9NN&6C8{JV`#9C&^RuB>8Keq+gmR_w@SRe#(S0iS|QRl}Y&7{YjaG|HenlB;wv$ zwrnDwwYAG8@|@VXY$E?LDPt9g=q zG*6PJ=1KC`JW0PaPj(pdyM5@&-`nr_yg*`}ysk*W#5_5#dcnjz`ChYviFvYmyMl>% z@=%Y0iFtB=?}CYW61)0KdyNBrG(Py(xDi+5Nj@59^3*&@{+cJH7uTcof~6NMy$!Y;jF=>#%4WB&(+c_wb@bkF4T%|y@SSu@8o`A?hanSPa??b$r~yS?Ma-`n4~^LIZ(3pPpk zUtYFJBJTBdnk4f1plK7UJXc=a#47*gt(qkIg?+=#33Bp;14d20O0 zA6>Wxr57x{VCe-*FIalP(hHVeu=IkZmusJ|m+bUc?HLDHdb#%bdco2QmR_**f~6NM zyE^zWJfQxM=w}yVl%X^k2Q!7{gGnb<@tYb%yx44*stBc<2Al8%|Bw zVeFg(Y6HuTPubznE5FyHr5 zdDU&vk)HS6TiuSFmo;#dY-S&$-7ui!S@%d6>OEsH$z}v5js@X@+^z(D4 zmDLjSC-y!0p9Qop@}O^nAI<0ZubJoV#O?F8XYx5|muK?K_}Mf0_dDX5e)TEnwR=Cc zM#6s5%QX`1Yad@T;pbXgGvWW`0W}kG%TB48$mf)$H4}MmdZA__|Ce5^ndldG^_TV< z2mI*s7ylYJ;%Yp}N8?PM8h`Rf7qpgMu=IkZ7c9MC=>QH z=>ldco2QmR_** zf~6PyXL@nnNjq5D!O{+vcCfUAr5!BoU}*IJH~tdt;WUnqlKQAtZZRxzvFpBhZgqX!hRmEQnW>4 zZmhq#x!pa~+gC1VZY!+y{Nn89iMbm4QRCUa<6nr57x{VCe-*FIalP(hHVeu=IkZ7c9MC=>c zRhTwkT-M&g9D8}q&W`ap`PFWYiFIGe8yu6v$X&f0liR%deI1kY{v9_urY{}7>*tvM zE^l>{W9k6K_aEr9R&6TZdG}f!Tk*HyYvps_==8OUm2|% zMf@%%zb{-n)ZNi9n0h>zHX0L-)mY(EV@NEGEjeh+$xT|2voxYF((Ydwi}BR?qqx)@ zs*kYx2&<2<`UtC!u=)tAkFfd(E3Wu|LQ|bf%8hdg*0}`hT!M8j!8(^Pg!k`%d{*#h&m8m}6+gPCfOSs+ z>z)GEJq4_L3Rw3PuF{owES6pV@PDPY}Gz`Cb^_1OXIvmVxGJ*>}q zSfBNt9*2DU&hxJ(x>$6_=W8c$$|Eyox&o(29td2X+FWVF{i zO<3Y}$COxqL@&$7_dPVzM^&bv(a%W3#!szeh`}T+3W~)boFI z-}KLZE)n(})|y1wxwn#C_i$Mw z`;V-L4c9yWBj;Fn&#q@sjKe?sxdC&d)`b2mpU;HP9JuZpWkzmYD%WG}Ci&}sl1O|LedcTDSN?w;iN>JR#wnmavDXy3;)xzxwKvRrSoBd>9^VDqC< z$jTYJa)y;Ntej!x3@c|?Im5~sR?e_;hLtm{oZ&F%L#3;jjx*c2v072HvYA<-z2hR; zmCUL0Jy*ZJl6mL+4$l5?S|zh%o#zfGRW=u0+R@nud{@~VeYK1oJ+{xuo;^5!RcY}OBn=h(nnt$v0p|`4=Lf846?|rzY zY5J(=l=3L1JG}CcV4QKBqoV!O9I*Zg7~} zH7jz>Y4dBl{P#aU-F&^=bMlrMroz*nYra3zY|Zk#_w89`V{gxAuAOaaSN5DUc8+=Z zwR4=GlP{WUUhnJqlg)F@JNx`Nv~4oaY#HMD*?Z=hpMUma*me9o^YFl$ZhS&kZse@o zVC4oYH(0sB$_-X-uyTWy8?4;mKjwDs+%sLjJ{vO6Tv^8R@fXZ9WhR$(_MDgJno6g8 z9#wy?**Le1vu_zX$5c-7-1p(x=Ibv@JNv0iXPKKH@!ag`ndX*3o_EciVX9y6`J(aD z%_UtuFL)r=ymg!B0Yh`lMbkZJrcE=qZ1bG)AZ~Z94 zlo;;Mliylqnm3Mb-AR$7*=?Tyyy#&n?%_H3JKJHs{YXR}A-gem!`e zx%)sfmk;B!{MKe}+(K5r=&$+(t6#AC1*>1M`UR_Bu=)k7U$FWGt6#AC1*>1M`UR_B z@E`l7^DXSxA6ad5&M-fO*HOq}8(nv_563FxuuYxUuQ%QI`p>5M%etEr27CUhbr19T zPqm#Ehe!4>clGz&^2Q$K#?Spd#e^Tao4#E<7yVmzQ{Vy-K-PLtW3{?UM^}59QM4UNij34*JZBF zirvM{J1afk@XE=i%^}YPH=knK)V$oadG?!1M`UR_Bu=)k7U$FWGt6#AC1*>0h*st4mRy27j#oV}!cPe>b51u#lE@lp2?ERPBS=3yy!1J$*PB7Ig`P@!?t%$j7j_1V}7BN+7`0v1s z|L04KJ6%Fnzv!>}1*>1M`UR_Bu=)k7U$FWGt6#AC1*>1M`UR_Bu=)k7UvStjony=c z;WZd?*hc-OeR%zb9JbMUOZ#x#{>Zv!CvWX*rq`^MV5dOpk4z-z;~#sq?ev+O6+2MGttsb>Q7*+fL8@9~x|`ukoCA z$35os`#hIBf0((UmgjBD?lsqL^f^@c;XX6JO(k~@gshwyTjdNZXIMGI${AM9uyTf# zGpw9pOM?Fn^EYCf;uQ_GB*d-6WVEk3Slj=bYJ zb3ql8wBl!Hukuo5^VXvMj?cKDviW%VFOJP`l}z0ie|21;TxBzT>jB4KPONOc{q&&Y zJG)ger9VEj*5x0t^2e_HVdW1ie^~j$${$w#u=0nMKdk&=(3 za+=ooY>H|2bRoyp@0wyhKgaV6A7z`|B?XNjiUlhc{AaN^Pr@+|Svk-~Ilzt5rg1- zU0Gk7;%|C>ci2~^*IS;a-niS8{l@bh-FKOL&-BN>-v3L}q`T*PC+sx6S9qTF?hcb$ zsg(2Cr}+-EV5;X|-`j2;EPI->Uz5At^qS|n`smnx?&;3{^^@Dp*Q-1)|8={`yXXvO z?|jD&Q)iv$yH49_R-Wgdc@EjO)0~}M+MOpMtB;JW`UtC!u=)tAkFfd(tBZt?*p8?1^^meV)z46YZCEYPc~BS#ilnabd-U6&F@q zSaD&+g~PacPn>Fp@2%?et#o!tJ9vrbqFE*FXWcya-CNR@`n8H{Gx?%Y_KOjoZ@s6K z9bVXTuNkH6ko?ct`yMZ4ANt9Ew)UA>$_~2GbN^wbY@N?4IzRWeC}n&1@Lc1UlJ?PW z&T{sQX(erqRL`bXN&7-w&(|(K)xNW*f*YTZl|TJb{;=|gl|QWfVdW1ie^~j$${$w# zu=0nMKdk)WFn?VO%nxDyA%|_$FWUF7UBVVQ`)oHp7r#;5ZXV~~orUK~$U2rBbSxYm ztMdx~;WZm_*rwhfKFVZJqt? zXAhZ^KJ>gjeug>VqIS;y++Bywy^}m&dG8VP{3g$jXB{z_fSp>;^ZYN5nv*(T?XIto6_5J?}W7kS$%^bBzgwY|-O9e_bNU zp7@5>clO96JO4q?CB8|r2P%8+eNkaMZ>c{|T0B(PKGoRs`-=+O;miDa_0{!wqKp@xy*fq?Z8R?yzSbguzjG+wQhVuR{r!$`NPT|R{pT^hm}99 z{9)w}D}Pw|!^$64{;=|g!~CTw*L!&Wha9$%?zC@JxUjANvOnLJoK@Hk_`!2H4k7DU za?r7Gc&x?^|KYV6a@b~GzZGUk%?sRla=7cWW?os(tFB&d22}L?YO7`D*<{a0FJEdl z_V@fj&n2e&BF~*CJ!4)-YUKRv{PbzFzMtpQuX)<6+~#@qmy1na`^K(~iQjEa`M@*J z{J-kn#GL~nD>wS6++gJfD>qoV!O9I*Zm@ELl^d+w;6LWJzpB@z`(uku^pxjv-z+vS z)%WM{-cC=O0ZTmZ{NZWSqMAR?-(B#GsWis(($pp9qR%}~8nV>1tD1j}+_%h3yvFmu zam&q`8$EwF?^#p7pXaxit}uJA^}Kx5N;B>3Hg2p!X57e={FNuHJYnStD^FN?!paj? zp700xdBVyQR-SN}XS||FfxgiRTpue>SB*y41C~dHVji z&ct)2Q+_cMKWXjk9ozk4R$c2k>84-IanJc@mFbuLVqU4|`K^QdP5Vb%y7n#Z-EX#5 z@%->xKbv!(y2Oo1$jXhJl^d+wVC4oYH(0sB$_-X-uyTWy8yw~~`N=oTdnNt((CofV zra^JfIah2py?*uQQk&DanC0*JxiMrNi%%U3hsQqn@{i`4(igfhS^4IVX44q!xc*Z= znp=}R|J3D2v*&)}?B{&;gV|Ha^M&RIvw2dAv(Fv;y_tKS=V!CNGsVAX>gEV+(SG=h1qnYNv|pI; zzxATu9Ca|=Fr5!BoU}*oO~?lhm`tho@;&oL&~Z9Jg*w~Q%dzN*Sj|J@7b5qcBSXj4)0HS?u72nKIqE> zDMv5$T)pDqlv9U#F5aqu89vo>e0`gn=Xy?mGbv#&ka3(*`;KQ9G4gX_?g>WzpZl<= zQQQ@uooJNL(K*G8@?3vLaijciw8f43g+1$GU(ZbYXB&FP&zwzNT>kjK>vqq?J-)JM z@_G4FU)N2ZD;9eu|CWXRx+s6?g^nRh zJM7X9mUghTgQXoT?Ob&Ke)%nb|tn-{} zT<1U6zOD=A1YIx86}pa?Lv-E6u@l!FbB^rHMQYC+B|pqv^3R;6xXg9RhdEPuGG{7( z=1lbqyUttM>wLzK&U5_h{3oui3-ZzRLY}&g$Y0kN{nB+ue`RMJ)SmH?AI44o8BfJ! zoRtsbuRPI3`7>wIFLVr9+F_S=u(X4v9W3o&X$MO?SlYqypVJPOcCfUAr5!BoU}**%U!WE7y)h%WZjPcLw239-S zUOMtRXFp}iskXtlZ5_Ajb-F!%Nqfg5ZYyi|zSO~Svso2v=GlJj)sfdKC+x`|oSkTY z$NZWJKPAtolknd&{v9;Mz4Gq!6ZuqZ+8~i<@oO6<@_%?y!$iNZ-@MD;f6@Nj_<0L` z$ImateeEdz+s~}$?8GfH-`C2LPdV$?Zjk3?L;N}g^6%Euzc-;@8w-1;zp^t9YR~w{ z5922PjHlu<&dP`JSDu4nU6jA{LdTG4gLc@Z9W3o&X$MO?SlYqT4wiPXw1cG`EbU-v z2TMCx+QHHemUghTgQcD9^j+;46Ij~8(hin(u(X4v9W3o&X$MO?SlYqT4wiPXw1cG` zEbU-v2TL!`y+s=uCC<-PuQjr#-R`f!>DwFG2CsU~J+ZNUr-H9VOpAY~p#M#tUwp8! zed0;aU0!c&r+n)9P{k%T>-gsG94>!P6FcZE&qcO2vBRr*-dis@VK0@LoM^x7& zOKUbw_)qWOG!ggi*-aDq+_kZ3BF}c8G)?5+Q*jw*<-_HX`n+pgszBoNXjAb@fyEa_=U)<@LIbrkTo|!8)ZT8F@^7Jmx%q^?G_spClJ9ClRGe^k} zbC>)xrztLTo$_JMRG!S4%AYw?{lY%zA>T*Zx2x$HKg+jPaecvmrA*Jn{k*kj^4V9) zGkN~}ZDrS<{7Y^1Ouvf0;hFx*&N!$&<0C(eoBT7Lipw}FAI4vKqKoop&ZJ-H7_zj( zF704x2TMCx+QHHemUghTgQXoT?O^w_Xd!Dh&56|A^ zpJ(!l%d>jr!!v*7$uocD&oh7Z3;P50zj8UyenW@dj`1@!W0zz6+s$7(CT_2DJ(JJw z1v{OcJYTrnGx={n#WVdnNjiUlhctXN^cuq!V1rI`iI;Wj

y zd$J#gr&7O58JO+))ua1TMjrJ1!Z(Lfo=nakw;%__B~QhL6&F@qSaD&+g%uZ8Tv&18 zKkF}c<)Cq3ev@5u-IG;|nCo|a>gJ+mtCGx$*`DjRC}2LHd3UusWEg{wbzeEF3XVXwI`O^!)gz!J*@WR6Sfy)|K+7x_Scn_ z-T5zex}Q+S?p)%}=WidYV0+c}=k4~ERqc$$-o7@khCTlxfBt{^aUJ{CZvTw#v{C2V zuU2<**Z#t+3v8vh-X5R#?QUWhUFhooU%V;B4m;1ktNP?PYpcJ~(zSWxX={Htx0&PV zeXLC%kl3|J!4_*84GLASXg_;!rC(y4)=`Jo{-qJ7bUEHQ(^6!3Txj~ zSo@~J;l8Qb#}a$EkEQm##2)U?sXb1yYmZY{dz`}B;}q5&r?B=og~L5gwWkVp?L`A? zFB({T(ZJe^2G(9Qu=b*XwHFPny=Y+VMFVRu8d!VLz}kxj)?PHQ`QPlZLz{3<80{^C zUHdh`+OG-Leoe6UYl5|36RiE3VC~lgYriH~`!&JZuL;(EO>nqhQ@Ga+d**1L9POb* zd+nhFYY!z@dnm!$LkZR%N^rP`Qn>z6Yj0_zwYRX=-ojdY3v2BythKjrxb{|SHnD5n zB^<5;)w*fyS~m@A-88Iq)3DY}!&)~DYuz-gbcU#93u~<|thKtZ*6PAqs|$x~ zb+u*|``@jZ{ZFig;aEQJw01`8HL!>4HMG71yVg*^S{nsxZ4|7vQLxrV!CD&yYi$&) zwNbFvM!{Me1#4{-9IlND*Lr9@2yL{+4b~brSZmy1t#O03#trWL53Iin*P&=l2R^lC z2iBS$SZj7*t=WOKW(U@q9aw92;Bd{3){J1+nh{uQMqsTOfwlGo4%fD54HtH;;exe> z3)UJgSZlaot>J>Th6~mjE?8^0;BXC>o`+*U_Wr`}SMXPUf1&q==ymKpuU`ZBSANgS z^+hd{t}kktVBSwr%LMb@idrU^_gU03!Mx|9mI>zl7qv_<@5QKPf_Yy?EfdUpG-{b( z-ml5ddpEV`eVqJop36V)?-ZB!ddlbjwR#xUp)rQX>ISVlm;TCigR0j>uVeMq^_*UR z<@#!^Ye27K>rnhV`oHoz6y7Il4H54dSu=%pynkdZm76E?*IL57uVn2N%zI4MWWl`O zWUUs=dr#JI!MqP;Z5PaYQr23+yg!wl_o`~o`&RkkJ*@omepYdLZ_Ao5{QSSRUXSZ5 z9!J-At}oW4GY+gXVof^C`Xkn)!>mhUO*+haCDx?FtYczLI?Vbe)}+I%dtyyG9RD3# z*Bp-n<918D=AAKNJXwL@Pbaj~ zo=&j#bb_^~6RbU*VD0Gy_x>mDNrivyn*?i5Cs_NN!P?&p*8XO&_BVsIzZtCk&0y_s z25WyaSo@p7+TRS;{${ZDH-ojm8656!_8;v%r9H=JuRX_L?KuW(&oNkgj=A>#!Cq(D zlZrOso>bba6T9}jg|+7`tUYgG?Rg7_d){iVQS9NKpV~VVyY>@?wVyDo{e)rdCk$&p zVOaYK!`e?6)_%gU_7jG+pD?WbgyC>M;czcg?YT-D?Rg7p&s$h~-oo1R7S^7(u=c!# zwdXCYJ#S&{c?)aLTUdME!rJo|4)?tMkM@Jrp0u>rp0u#`q=mI7Ev!9h;c!n{?G1}P z+#5FB2U~lC(?)xP!`d4h*52T-_6CQwH#n@l!C~zU4r_04SbKxR+8Z3!-r%tI28Xpb zI2`T`u06W3YkzN8dxOK;s~^^0{jm1xhqYHf9PZU0?kgVd6R!R3X|Mh5VeM}ZYkzxq zN0a~gefz`TYSHi4kehzL2G;M_!2i|X&EZ)6Mhwie_kZT^Sm9s4S)<>YA+CO#3I417 zwp92#IQs1#^3?Ao!TP--Umi{azBR-%EnS-%HZ(0bvh+4=DVtG5r=EZS-4s zuzm{<)^Fj#`Yk+Izl8_uxA5Rk{u95`M|=Ga8XW#^ntsO+yMD(I*6$d?`W-`9zhemN zcMM_ujv=hyF@*IyhH&^hhWZ^h?7W}V@4o4`?Xc^&?O^@39jxEBgZ0~XuzuSP)^FRv z`fWQ{zikKWx9wp4wjHeBwuANCcCdci4%Tnmg|$_%>PcYLlfbGufmL$_tIi5m?HR1v zGg!4}uxig>)tNv)?5eYZRjUcBRufjOCahXbShbq4YBgciYQn13gjK8Q+6T3osWIVRsRgD{ux&NGpzb&IIMqG zofUS~S;4Baf>mb)tIi5mofWJ)D_C__ucn8x ziNUH9gH;;_t2PW)Z5XWDFj%!=uxi6#)rP^U4TDu12CFsG!S z0P8ay)@M5Wull`0V(B{`tnYa6fA?>O%D;Y#Q{VBh>pLE-?|AV4^zUzygKD~9)pWtC z>4H_$1*@hDR!tYInl4y1U9jrM;P5xsRLh55wS2H@`C!%Z!K&qhRm%sfmJe1fAFNtF zShakxYWZN*^1-U*gH_81tCkPe@5;fd--A`Z2djP$R{b8V`aM|nd$8*FVAb!zs^5cE zzXz*+4_5sitol7z^?R`H2Vvb0!nz-Xbw3E}eh}9EApAe^duPPey)CT!Xjsn#U_BFn z^-KWPGXYr71YkWAfb~oO)-wTE&jesS6M*$h0M;`BSkDAtJrjWSOaRt10a(ugU_A$b z^&9}!a{yS+0bo4`fb|>z4)=lAb3E53|2GR@J;#If91qrWJlFnDemelWo*BY=rU&bp z9vtpVujjhh^;{R$b6r@^bzwc%h4ow))^lB0&voJdj=lQvqi4CWp5?-NmJ91yF05y{ zu%6|@dX@|8SuU(+xv-w)!g`hq>sclHvOm1?(VqXRfyAyFNLV$HuxcP-)j-0kfrM293IAvI`KP^VAYs)&!m5FURRamD z1`<{cB&-@pST&HaY9L|NK*FklgjE9xs|FHQ4J51@NLV$HuxcP-)j-0kfrM2939AMY zRt+Sq8c0|*kg#eXVbwsw;eO+Pwii8Z^j;O#dsSHPRbjnXh4o$))_YZ0?^R*FSB3Rn z6^@@Z9NX(V9tXWwWlZ#571n!ISnpL~y;p@*w*aed0ao1t%zA3=4Xe5Z?5bOURkr}E zZUI)^0<5|PSal1q>K0(tEx@Wom#gF!e#lQB9 zC9d|8B_HiEOP<<$mi)CRE&bA7we(kZ#zE~FANgV2kZ+7A=feweWK!-TaTCanE1W!K(l|L%L4s&1Tqu`c7-9+>f*@E6_#Q|mI&OY1UV z?Y{?W|2?PavAq-BUJcrRk1^5yd$9K3gSG!2yy?Gb??kP8!l%|f!P>VC*1m19_HBc; zZyT(A+hFb625a9oSo^lY+P4kXzHKn;GLG%J=g0rg_S{pQBx9vINto}G+M7%JP+{l$ zr}pyVd#U#L;`^%h{^EPA_5|bmt@aAzd+)J5#Qc5Ge{~Nrt>;Axt>=Zco)^}7URdjS zVXfzdwVoH&dR|!Td10;Rg|(g+)_Pu8>v>_V=Y_Qf8P?ifSZjM-`{4JNweB0c)_ucT z_YG^^H>`Evu-1LUTK5fW-8ZbY-muns!&>VNYppk|wcfDSdc#`l4Qs78thL^-)_TKQ z>kVtIH>|bZu-1CRTI&sKtv9T--muns!>SvERW}H$ZV*=8AgsDUSapN2>IPxe4Z^A$ zgjF{Pt8Nfh-5{*GL0ENzuxcG))eyqr@4~Bw5W8v!Vbu`Asv(3`LkO#e5LOK#tQtaC zHKMTUPGQxZ!m2xkRd))j?i5ztDXdykShc3GYE5C)n!>6zg;i?`tJV}&ttqTpQ&_d8 zuxd?V)tbVpHHB4c3ac&%R$UORx*%9}L9ptAVATb|stbZu7X+&=2v%JXthyjrbwRM| zf?(AJ!Kw>_!@3~VIANzR4-c&AzUQbm47+N>VAY1fsttox8wRU33|4IztlBVGwPA4E zCiBdeA+=oGXYZM3e*W3#pn5Rcs2&VfJs7NdFj)0qu}k<; z4^6eV<_@u+eK|GyaLyFF^`oJ7;BQl+*Vbg)q$T&--XCX2B|pxx%ZuG_hfd0hhMtgR zZ~pXtyXNf4(a=jK+h?miV4KgI7#+=-C#{>P7vnzxKqfE}2p81ruF91zKiAf9o~T<=Luldi25ai7x;C8%9NqYfp0h>eh2q z^w{&0Y>kI+vL#!NiYDJR*%lky*Y+7WDw>j#WtTkG%bxM^sA&3W+4kY0H`vXi)1#96 zvu(;t*V~H*Wki*?O|d8c)YV>=of&<&YO3uzt&45=+34ubantPl7dqRYt{5BLacz$6 za$jeA>y~lRcfaL0`={4Wh!&5|b?xhXJ2C2UAlLc1HH)T3 z4W5{0(~8|;uNX5m8dYeTz4q?A?Dl$7qY+n4wM!lzWG|gPC7L~Hid~vI#D4Q(b~O2& zY`duVP`mQmtf=al*>*$iVRqm9lcR(EvTVJNhuMNpOp1nXoNRN-+-uAAofu7SG}+lt zJ##`dWBnx8{@|u@QG-5{oS$9e#zvKDOmhCm_ZkzW#F`Sfc>B@OO(iC|e8vyRj7Bw> zp=9+w05psBc!5 zU4L#L`+BpCsDJBh+r2<9+vn|!=&Hg~?Dc2eU|*P$8FhYsitRbIyZt3~boA=IQ|(oQ zueW(QW1_uvrrFOocC(9K85`ZXWttr_x|_`^K0fN)J;&K+b(|1g`)-bFzwF_O(W>)u zou8MtPm10ckn8+cDv=dE9cxP5dF8XC5ur zvze!7N6BZ6x6f`FW=l+(97T7GbM~1@lcK}h$GY}c51J5NF=(vw(`f&=s9>G3&VRx2 zW1|iyj&*UTT|Or2RAQ{lXH&z`(e|ceU7n}4&x~@$jdl4qTAC64Qh1!}SFP(ZqQ29| z*_v1OwVyW3h}v8^-WF@r%hvCn5w$ygf?aZL54+>_jHvUT3HFht-Rz8EnbBLDCfbzS zyV#TZj*dQGGRc;h(aDxc9TVkFnryo^?`V^@jE&B}G0V;$(7~=x86TZrE8BLh-oZ9q zKOuT*YqqmLb=9P3VDBle{h<#hM-|_i;{25AnjQ5oH`V!XyC?XV=+gtsaW%44&cml?k(=@49EZHWz(5H|qFErv2*R5Lx7yw1?ij$KD#HN29xC+Upt)wW}AWM>!W|+VbOv+H0nzM?I@#+L`g^;Fm+vqqmbX z?Y-rO*@4%kNAK^d3Tc(LEV1|D^-cqRfm8*RN-8NQ;)v%&;rR4zats#rEYH_Wi0u>}|c$q7GX!?C|x2 zZPh!{qRaMV*cE*T+p!sG(SyY@ZNsvI?Jtj~MI~xw+78gRCMWc z-v1ltrbpksnCasFt#f+RJZAFg_CR`c*}6=ZXUCc8QNv}KF8^9f)1%L$TwC*SC!6!b z%xKkSC*ZHZ!WyCD(SD*u}1Wd1mx& zO0NC*lPla`w#Vg;#Ry z!P~pql|RmiURmPpZP(0*9-p1#+Lswlj`K6S&5Wq(s2u12-l{XA`yYzG8^m#| z{W?9WH6q95v*)epQRR#rm*-E*rbmska$NouXHSnxJ(A=4b=IWmQOe33`^)%Fw(Yps zz9lCce#$X_XpFXX&2|( zDIayPA0C|^O^!dCS}f{d&#yfrI^}^}yK`a(Te91X=)9a<+abM!Ju+cNRQqXf@3nD8 zbma!$e$Js8QGvI-pE7l4MsI!S{U>*y84do-$DNotGkWdQ_;WDM=hekCqqjfEb$Pz< z#>^<%l{6_AOa1&nl&7MNbaSa`|6fa8{HyD$Dijs`%VnJUz>upCjUPGHq#=J8w_g zKQn5(Da)PD>kH3{T7Hw|&hwh(XGQlG&34yUR?}Hg@fz9g`Z}@atmycb+3x!4Ic`=o zqGz_dzM8L_6+Loqw!6O0-8(CqJ=xnQ*O(oxpYPjm={7sMbGi4^dgAQpl6BsH|L0~$ zUvJ2Eao2x4JFW}PcKIAUbxzc3ZMMsEU)?#;c}ucg{x4lJC)&AwygLtni|2~93&*?j zb7MS*?93YP&Rf$pEh;l~ygQ#WuS|=obsO)_^GX+_Mc>=;?)-oDjI^jnrSa~%xbTP6 zs86Bs?t0n1AvM~)bDX=rPMDk;z4Y2RcYT%Xo*KQe%-dJgOpO-K9p~B)-8V8iFln6g zQ|P&oQT2>*&i`igj>TyxRL=d2_!^zrWc>Um^jRCkHD zZ>*mhUGt)EpLA1dl=P1GGi*j`wDn`}f7a`%(XcOk+!{deu5F%XaVH&nDN-jow%~*$zDZ zX1l3HZj@eevi)e#_;wr563t^2dYkp?w&Qq`JemixM|-;9l-)G;of zxk+QA51$<4@;vX-G11H4k8%0m^W5m@mg~m4eoeb=boBD(vG(efee7|aMn@<29%ny4 zyO+It*yt$l#PRlwH9hPn?~abvMdR)AvDe$d{l-M|hEA}{7Id}mo-;OD+<2m0^|vmz zXt{Aw#k~{lBZWKLH_ja&wSHuhZPd1tT^~OidAa3eyQxekJAdxPXz|v`&i?eCNztQM zWV!Ym8)ro)Kc40MY#WjtRoX+xJFCX2D4NdXX-6^^(!i_jix96=rs^&ptRhYIEU8`)K+2 zdt>v_@%zb<){f|EpFEHmO?Z2R?X{_^{rR!X=+wC*Y}4Pm+J0AOM#JwIVIMBm&DQ%V zBf4w$Lyo7_NsoqPr@GuKy`C1=5T)4%8eC^T{30{jawye4Gxs_>|I5ti!1h!-u~-{h z{`1VJ_A9A&_kcFG|67?+lZB~v$;)kQfxOHpXrT&zvfm!*;@Crhqk97UIVPtyLrf90Y>ZNP#lm}yba~IMu#(-8J^H*V3b>Ka?&r}SvS(o~zf^J;tdS^tZ@_YAnA zO4hc`2{0iD2q=OgqKJ~@>Al-P5F>^$r!i+RBZv}I6dpj5U;rekU_ivo-n&g>922OZ zjyWgHIevB3>U*>BJ(ufuJOLl+qpLD+z-`}p-YyVk$ zEzZ{}57nmA?>#QPYQtg6omanKI>N_)+xybx&awX+&iS#=&(0o|?)>6W=`;20oHlq= zI_kEg(?c3uk)`{MN_QIk_w;~uuE;*xWK{Z9k7LsMOE1s%erIHQ{g20_7iO1d+uk@b zeSO@q=?{Z0&yF}{Wcu@Z$EBxrxIDXa+mY$kryrMY`>$cyD&N(nQ)eBQe%yapcDg+; zJn_hW*7v?Vi?4&R53xS;_nhP!E?qP=>$3TzwCn8S(u2>Lnl1U=dh7#^OUw1AW@o-L zF)eO)TzbJhQ?h%WnV8Oe;@EV_kyEm^4^2#)?tW~#M%^h{^UB2ZpLZUU)_G)dHpj+~ ztb0s4@6yTH?axk3zd7jd>7e~5XK%baF&BC_tohaM!>~!y zvTuh>Opm|#jC9pQre`0{y~_F2@z-ZfA0MAScFfu74p&dfUi)Nxy6V)k(s5&^WOFu} zkk)_m%=Gt3Q?d)YO-N_AIWygDuK9NUgfto2H+^f-l&t?P6VgvU>yy4`&*lx@nUEfP zMxS)!Zd0?H8eNq>xkjJ#%i5{g%X{0qq0$-Y4X;nl4jz0}`t+zX(j7WqpKY+gxOCb> z1Jm=5pPIG1{|e`I4j+;2*ms2c^Z4lD*^aG7xSt!oFf99ezY*z4W6wwrC|;heW_`ui zo;)M%dDG=tck7ka*|JYM-)i7F>y@>c*(V)%#ueGR^GBp77W<|p>qFi*Z$#SQ%f9Ke z^@e9ltXKKi-Djr#b|0QSIeJ9e|BAEH_s<=kwcT&HuQg!Z%d)us|2NcI@2#%!+WVt{ z^}$x$KmSMFKi|B{ko3ewC#DTPzaqQmrNFn%ACaB4>d^G$_fJeeZ(5rTZ8J1|z1d0W z+rw(JhkFi9>kT+5-P`V;_c?56y7dnyr5o=(G8=iE%^!PmdeF>~S?6PirVYEFlAf}3 zWOmR&L(?bLJ~iF2&8V!`&O_4yubr9>{@bYR-pz)lkKcV-dTgIj*{!DzPG>YYKfR%5 zbau|K1Dz)}8Ihg-&ERzB9nMPY^camBeOFb4Nfnea!$JOfRWkcUk9Zd-gHjdw&%#~re_EF_~Yx3%ubj+$mb9L zS8cXZ?I5?a;q2P%@P32b{uljfvkm$T@^!D-%if3f9pwJ}y>)GN$c2O4&lA?J%`O=` z$o(Jp&4{dU#~_butljgEdSy_$-lJ!xkJ+=p)YS&3+Z}#py6;CLvePyloG$sHZ@TIa zBeEk4gVS}V_DxS;w>Fz_*x+>JzJ1dr+ty|+`wvd%ZqPT~`){>b^GSo#!{61B7+X60uFr+q7Z(zD*L&F*O3F&`9F2<6kqRRA7V}7_sjA1D1O%*_jBSt zPke6{-?PQ*u5x>=U*k4C{>JR=4x|10JGF~_kN@y+AK#$+jO^MAYW@27Ouy;b;gf6A z)xSP9-S*7s*;bF$rWMz4@Y3(sxEp&*roqnHCnGoDQ5nJ^SH^k?E&9 zpPUYQZ+bRi{K)k9hfYf8Z$2a2@~M&OQ-__D)}A&aJNS>0=?&|hlgUYNPX4OauT!&^%*u9tz1FW^Xa8$fcFLo*eqHOg=FDunMI(IvmVIVs10NaTcIMX1%x=Dagxepv&dhA} zyGQuCo!*?0-C@lAz_0hu$Yz)9oxa^CtTK5*IB9kqV_-MstE?7n~2`t^6+3ub0_z7xjJzHMgqqCLBDy}tdOnc3y5 zjdVM$8_voOU3aA0-=pWO?Dq{v`nuE3nw9Nu%>BSC6K7?I)g9@6zIfNHtjEeD-T#}O znziCRtX+TqlitI|@6A{2wZ7?p(q4=6^}pd<{lB4S66+9O%iAb-*WzANeEog)l`;N~=GyP3X1hE#&Uubq6N}bctY1;>nNDq8tde&;>==7K4jz~YUYxFf2j85P9;PAA0 zqv_dUeQo|;ho^5nG%cHV=IHe6YYt1F?l&zPJ8*Qm%ZrDmEeq4^JKoXh=#>vm?_Pge z)_%T?+dHfmzrQ~FuHIOGw{n49r=Iy~jK6c~X4kLp-X7!cV(vd@Mz+=CWBeV>8Yj%i zI^S&HXWBcXDSOYz{-_<}?{s!(HzPaqj4}SMr@ZEj?7ZG%{2kEo|C*ltw8I#GXLRY! z)3YUw#`rsgMW#blJ z>Fcg>(X_0%=t}qJ>4T?bonE%@N$lO$qOQ}jJ>I?2{r{uow5;_vS9)B(H=LIBUUQ7U zbLmju#y1_~?_w&AtT)(ojK8Bfv-Py>!-K~7yPH?iX<4)L#`rs(ZbwbaZXG|y-}NlG zbXs=P9b^0*(1v$R%UV4<#@`Kn{r0r1$46uQozWW&re{0-5yp4jb9#2nhGTvHpuy9# z`Ypz~ogeO;o_(BG!+cot|Bvx}Egz3q{`?=~ zQS7CNlOu21puq90_0E~=71lfWsTz3B8*3Gsci%06uiNccn>W^Zbn7>hdv+>0^S}K6 z%;CQ?59TZ``?n*wf|m{KXzPMeww|q{I_+= zeK)+MC2Qs53*dZy3C`^}=k}fRb)9p6oO3_Rk^jzpH(YfV>*eFb>zwQ0oa-a|=;lm( zte5+Pj?U=8dW@r!#pV8^q1B;}$9c@_P2<&i%jYN9$>%#qc`xPm$-Czv*VFTm>+E^R z_4hpBH}mtjobz}Kj7NF*eUay#apk>4e0konqr78ZdFOwXcmBKb&T+~+{wweH->Z4o zIJ#+m36AnE`#v7!UHFYR{gqow1PaniR#S{ORN;NyiJ9SV03*~xk5 zUE3EPXqq}7-J?z6v?iUL$M@W_u=bQ4oS$ygvhaD!z%#brtgy$c9ejL~yPFk;oY%$q z^`|x|>@+yoKl8*Ug_CCO>f_rqY+U%`y1kq`+}xnh^?-AoZ=KMf@J!tco%esML1F&% zAh^O~L86pFu1b-r5JnVeg z(A5ej)(?E)ZmSfAY#!!pdiF|%qc#Y~es=G#Nyk@%%`Y$hB3WmfSNzxw+kc*H-}5!+ zxd$yxUOMnC=eD~qO-3E~p7U*=FHQc~=p*L?TYizW9`dR4)t$di#;*01^WYnQNKX9b z2j}hf{Uhmd-S5r~YgR6d`eLOr`>yxGRSQ3iTg~~PI%^f~KCYhg)*aR<%)Gw7^J(wb zDGXY($)7paEs1nXBHfagmg$y6x+RfrNu*m6>6S#gC6R7Pq+1f{mee=h+6UbdbbB%A zmPEQGk!}gPZ5eb+BHfZf%XCX3-I7SRB+@O3bW0-Ll2!ltdotqER<7G>%Q)Ho;SZ95 zCp7o*Z#Q`<8TZk~&i%f6KAC=31Lt2`JekzLXg%k(4|z1%v|-50w$mO=mVC30kI$c0 zN*bNIw(}#i?@1mQvX=8pP39*Hi-8CHaa;2AWr25mVs_GdVwiuyV-u5Oe_z+Gw*A>$R7zPA=NLrQ5mqmTQwc4&TE0`MOh*N9VM0p8fsQM zL<$>fvU`}ntTAXrtuX3q#&J7wRVG)Cv6gPb($cwGRAZ|J!T&x8BU>zkboonl(QQeDm28 zYmV%=xsPwQ^2nMN_l32NJM_|;=Z^?A^VYzNYpz+Zwa;1o!*gpM+Inl}uWmfM=I>+L zIj?=(pqdNDhq%`HY;esgi#z%FgWC?QS+skN^OpM`Skw67ZqB`?ZC7*Tr@K2}Jbaa! zJ3s0DXHGgT(=CZ~OCsHpNVlZfGTo9hm+6*7x+U)|(=EArnQlp!Wx6F_EYmG{X_;=x z8_RS{Zds;V66uyix+RfrNu*nXZbt{*lC?~?enGb+(k+Q}OIk0}E!lmUZi(r(Aks~o zOn>vB1y2qRI!|alc)@+if|!3kqS4eYw>=mk@HhT6FDm1`IL>$*^f>D#jxG#V0Wsm?*!g1cvhnyi_< zR_XLVnz@~84_dGEeaBFTckQ@wsq$*z!#XrCEqpP|zo|~E(jj$&&Dwu#Ra*OuP?N88 z->&pz%iu%v=R1`;b`5*v`rEpeuIm{5KWO_x>8@kKK00|yx6TVmIRQgmGqC%61K zwKTPP*!wG8Ik|Lq66&Y_3)hxDKOp38^!MXShc6C!KWYBh(p$f8;e_H!zVDN3O0T^YuFG%ty0x_M ziEy25HumXO%4g%b-zXw?Vc>Xc0pL{=#!o;RTc$*-rsOxsl!dd&y5dWQrc*7@PEg`hozC1hZw(nTN3G(M7kxBZb_tD66uyix+V5pUyh#Z#mUe$ z+LzZ(LmyyxldZ}zp;p zdEKcSmmjD%-1*r(8kS$`f2s3rGa8gTH5lx?+vo=68{Y2ceD9VG%cs3@y7RD)8<(fv z(8GD&(kA78yY1|JY5%6>Js+rXK7IS<<+igsJMaASrsd<-?CAW=!!627?g%}Zp`W!X zuX1tV-F9nJUgP&LXHfli<@c^jf}Ni2%Tt~xI?uVUV|k|wL;q*P3)1qc7l*!0ldrp% zAH1lG&#~T7S$!nyDT!m*X!VYs`PFE8{n=v3dEXwm&;xx^m0%$_F>8Vf=_5t;(I6cW`cY{}$!1 zAMWY=S+CaR&4(Z8d{lAk@;BF>HVB{c(YUa)7>s~{$~4{ z@}*OTIiK0MTlw-2Z**Se;a=q)Ydq|nYxQT2bxR`Ml1R5C(k+Q}OSU%MHVC>U=r%m) zmZ00lLAM0m%0agT-To1DOVI6}pj(1&s|4K=bekD;OVI6)gIu=+-8ux_lBTBHS3$P~ z-C6|Q5_J1I=$1sfC6R6kx_uIKOCsG8bQ>0QOCsHpd~YV?F5j~-eao`-dwtycmSyYr zI$PheZ2ewm>syws-|KAs-m>+3ovm+Kwtla(^)1WR?{&7mW!d_@&epdqTff)Y`j%zu z_c~kOvTXfcXX{&*t>5cxeao`-d!4OsS+;(!v-K^@*6($;es9_Oz0TIREL*?V+4`1c z>-Rca-?D7|UT5p~maX6GY<Yt(>qfs< zy3y~IZuEPl8~tACM!#3O(eIUR^n0Zn{a)!tzgN1^@0D)!d!-xwUg<`^SGv*fEnB}A z|LONiw`76oX8m3tk94EoE8Xb#maX6Gb0Xd7_ewYVz0!?-uXLl|%e{x|mfw@O9qad& zt>5e8*0(HMzt`FNmSyYrI$OWDZ2ewm>syws-|K9B%d+)*ovm+Kwtla(^)1WR?{&7m zW!d_@&epdqTff)Y`j#c@_c~kOvSj^UXY2Qttl#Twean*dd!4OsS+ahwv-K@Y*6($; zzGcb!z0TIRELp$T+4{XD>-Rca-?C)=UT5oDmaX4gVBcBavTXfcXX{&*t>5cxeao`- zd!6(9-aj+_Ug<`^SGv*fm2UKVr5pWT=|;a-y3y~IZuEPlTN3F;zgN1^@0D)!d!-xw z-jeluiIIM9$@;y{k#6*Rr5pX;lJ$FiPNWui0?lJ$F?t#4Vfey_9jElbw#b+*1`$@;y{*0(HKzt`FNmL===I$PheWc^-e>sywr z-|K9B%aZkbovm+KvVO0#^({-*?{&6*Z^`<-&epdqS-;oW`j#c@_c~kOvSj^UXX{&* ztl#Twean*dd!6&=`ag558~tACM!#3O(eIUR^n0Zn{a)!tzgN1^@0D)!d!-xwUg<`^ zSGv*fEm^-8-{|*BH~PKOjef6mqu(pt==VxD`n}SPey?<+-z(kd_ewYVz0!?-uXLl| zE8Xb#(mQh9BBtM4vVO0RTi>!|{a$D5Tb8Wf>ui0?lJ$F?t>0U+ey_9jdrQ{ub+*1` z$@;y{*6%G@zt`FNy(R1SI$OWDWc^-e>-Uzd-|KAs-UZh0b+&%*0_*oWTfcXK^?RMI zZ@Iwwz0TIRTwwiPXX{%ouzs(z^(_}zzt`FNmJ6)k>umkr1=jC%w!Y;8>-Rca-*SQV zd!4P{yTJOr&erc;VEta_yl?qurr#^w==VxD`n}SPey?<+-z(kd_ewYVz0!?-uXLl| zE8Xb#N;mqw(v5zvbfe!Z-RSp9H~PKOjef6mqu(pt==VxD`n?OR-%Gsodly*0*E!OS zey?<+-z(kd_ewYVz4XbYo0z_3jrDtd-1?R^*6($;zGaQ|d!4OsS!4ZPXX{(mSijfV z`j$1;?{&7mWsUWFovm+KWBp!d>-W}Jzt`FNy*1YFb+&$QjrDt-t#6rFzt`FNmWlOy zovm+~SijfV`j(0Hd!4OsnOMKq+4{YS^?RMIZ<$!X*V+1(iS>J(t#6rFzt`FNy@~aE zovm+~SijfV`n`$ud!4OsnOMKqIe!=PXO4BF-z(kd_ewYVz0!?-uXLl|E8Xb#N;mqw z(v5zvbfe!Z-RSp9H~PKOjef6mqu(pt==VxD`n}SPey?<+-z(kd_ewYVz0!?-uXLl| zn^?aWP3ZSZH~PKOjealh0bRF<>02h&@AYx(TPD`;b+*1`V*Orc>suz)?{&7mWn%qa zXX{%g*6($;zGY(lUT5oDCf4tDw!URz{a$D5TPD`;b+&$QV*Orc>-Q$s?{&7mWn%qa zXX{%g*6($;zGY(lUT5oDCf4tDw!URz{a$D5TPD`;b+*1`V*Orc>suz)?{&7mWn%qa zXY2PS*6($;zGY(lUT5oDCf4tD&fhgV=kK85SU38;(v5y^V*Os96X{03H?e-Nk4L)E z@0D)!d!-xwUg<`^SGv*fm2UKVr5pWT=|;a-y3y~IZuEPl8~tACM!#3O(eIUR^n0Zn z{ocg-z3#vDd!-xwUg<`^SGv*fEm*&o`K5^ITNbR}>*Ln9ELgwS+4`0R>-Rca-!id& zuitN5-!id&ue0?n6YKXnTi-IVey_9jEfeeaI$Pf|v3{?!^(_QIv-K?# z>-Pq3wQ|Awz0TIRELgwS+4`0R>-Rca-?Cu+UT5p~7OdavY<!^{a$B#w&GiwD(BB!v2OHxr5pWT=|;a- zy3y~IZuEPl8~tACM!#3O(eF*H-^;r6dlT#TI!C(E@0D)!d!-xwUg<`^SGv*fm2UKV zr5pWT=|;a-y3y~IZuEPl8~tACM!#3O(eIUR^m_}|?{(cGrf*rWey@*P-?Cu+UT5oD z7OdavY<!^{a$D5 zTNbR}>ui0?g7tfyt#4Vdey_9jEeqD~b+*1`!TP<<*0(HJzt`FNmIdqgI$PheVEtZa z>suDA-|K9B%YyZLovm+Kuzs(z^(_n5?{&6*Z^8P#&ercOSijdf|5ngB|Ar8bb)(-a z-RSp9H~PKOjef6mqu(pt==T<^-|IFb-RSp9H~PH=>-YMcNH_Yu(v5zvbfe!Z-RSp9 zH~PH=>-V~yNH_Yu(v5y^!TP;EC(@06Z^8P#J|5{tzgN1^?=4ur*XLN@vS9sQ^)1Ep zEeqD~^>OQ47OdavY<!!T6KMA>suDA-|M|x>suDA-|K9B%YyZL@8{fWeanLNd!4OsS+IWZ0>-UxS+IVu zv-Num*6($;zGcDsz0TIRELgwS+4`0R>-Rca-?Cu+UT5oD7OdavY<>&$t?2g_tl#U5Zr1Nzz&N^Dzt`FNy#?#{I-{HQd!5nk>!2I` zUg<`^SGv*fEm*(T=SRBH?=4ur*T*B>c)y?;E4_Tw-i7s^S)Dp8t#rm-h24@(od0Ss zN5>}7u}O67a_7%uYdaNwJ>;KmbIliaC=?!j(fO~gP4W3QIyQ-pUG9EhpG9jH_MQ=* zFV47W)xu>h{{6jHeE$#~n?%PhcYnLM&-mnt3A_5e#POYmC(Y05?)+EJ4)OhPbZinG zyWI2I^9|c|ZMxpRZqxXF@n1a)N6&gmbS$i6m+L>+x+VE+{*)BUU-fq4enoU_5*@o- zKh1P2OLNn+tX%w6uQKkxMaL%5vCH*`E$?O3jMYO~we(lL_qd-N9h*eQF898}>b9(! zw|XvXFIb)P4z7lM5pfc~ABm1-FX-6i-rwcprF?&}mUC{$Ies^qujP9-I+p#VW0!j$ zoyX;N@_3zd9jdH%{kd+8OB3hl*yX;j$n#Rh|2$vLfA#H3o_FRbr_Rx_%Y84D*OlAM z>&-c@!#{I;tZLHjN5?Mr{ad~-+)lnach1iP zf9CjDofF)CbnJ59C!21Z)7(yezH-jbV}Ir(f5vp1(Xr%$^Q4b+?#=6=WO?VD>~)f# zZ=Lh=@SoYg)z|m=(XrGL=XtNC{MzB1Ul*LMp1IaI=hqRh^ZZ_sab1I)qxtMXu35}4 z<>y9^{lAmn{9NtxSA26@<2wA+H@E+tdXB%JU-8X+8`m@X_PZ2)`^`D?|GIzU{kY;c zFRQtp(Qh|O(Qh~YTj#6ze6r#mR5ut0t0*Cyxq-9+>Z zTUzl>=ik56$?w};!~EXKIqnZc&+MfY?_~e|JK6j>%QejJ?Va;`era3%zGB5U761O5 ziu}3Qb<3Z%o#Xyb{C(7lZ=%9?1<|)X+|TRV9`!(6!@M`*9QV8Ez3BVK=-a$f^le@# z`Zllh|L1QS^S+Z`)AL@IbKKv{`(r-7;+y2Du0!-~E%)>KwwC+(|876idnqe^Q}FM9 zQxNrFrEQ6Or?`I`^;Ef^U-6qD)90^#6O`|9*D&Av&YUy#+q9^M%>Dd|-}ITD(QngA z(QngA`8BAV-_P?d#yRfK=hu24U-6sVfB&1@{2s}*%I}?=NWBE8*{X!TS4Vu>HL&|NB?4{w@}*zn2B)e>cp1;O|!P_q_6P{%)AF z{vKCuhxL3d{+oh378GDm+;ESjIdxgF=+ zzH`2=v;K}5^K(B7u>S5Dod4Z0jq~^7oO2zVbA4nV-L!6kj=4YR?40ZGj6HN@PF~yC zT=A`S_(uKTeQV9%({Qb#XDhvn^zrD~iuZB)?a7MYO@!Z@{N?W^tRJOs3H0vR^^Bga z{M&%M@3-Q2PvQ4sfBCzo=-Eo|`q}&Xe!w}uk9CfotycVQG5p?hx!)~D&sP7{_a2-} z<8MD!{O&mXUi&Y9cN{%iCGqzy@%J#%vlZWw>e*_=-wgnUQ?{~SsTWi;JeXF_L_m=thB(7on?Pc`s(~7@49sXW7_w)LD-Q05)^6#$BU%bA}`3$F9B-@~r>U1#_`>~g>BjJ|#1exC1gUAOqR*mgg!-?p##U3U0A z`(OSpJHJPA4fA^^=jhuf?&trjzelm+?<$19N3q=BRfxWQ(!IUw8NE+Q^1eOqBa-NS zN)o+K@%I3{Z(t7Z0rK}9{vIHI52Am6r_7w_eTx459gXXK3iJKF2=nvz7qai~Q5cWj zr{E9oZ+uSlJ_Y~zcUav2=zWUDy@!_1_iIG-K1KF@JbIrZe|$W8pF&*z@5ta=^gc!L zy0+2#6zL=Ttmn-C=I>LavyVsbQ-^UjTVjH|}re6JPY{N1IqYBitl>%r0rR?WltUUU1}BaCbB z!1-SDf3u0bmj7E<8vp;qzj+krE8--|T@vN4x_?a{-{0g6j&fH$4=^6(u6o{JJjz}5 zJd@8??yBdd+&($;wW8eN4>|VnD0ld;f3M2yRCA|saz|YJ`&K15x8t1Kcg}0ZIj<#W zj^lWa&1=s&`uD07uaDv#mD0bZ7o=jZtth=)326aw5A6o0Y=5a{k-dUD8!rj&|N{VwZGe;Y#NdrgurZA2r7L@bO*J0fWXmk3YRj zI%Lu~=PvEKq~A;#@4V%!ozt&IOmP0-?9S;?2Vdnp=9f-sAL?~p7CFEU>ys~Cakq!`2fo|SU$sw1y+o(Vuz&(EUjQ^2uoXd@)_$^ z{TDO-)xYYcWAhmA+NWOn)_Ebuc2Ct!d;J_VIdT8GY3=@jSN^n4`rsu&!_6nvNw=R6 zv_0t1I_Z|RLGz0{)JbnXGvwmIE$gHQ?j3R@W?jvJbu28Ku-1a*11#TQ`3x%-n6=Kj zF4U5k@hi5glkPSr)Z1OV*Gac4hnl?S+&bxIuMGFRi`{-cCq5SLFr#kz?%chKF;m;! zE~%SN9ZTvQ*v+}euXWSs7VYBP`G9)q6|3*; zd_%cjnhi*u&+fEt+A=LVueD&^wCSM*=K(#}OV3)AI8R=@UfN=A;I=2OpYF6Y@Oxjb zpMEwf%)jOA4bl^8gB>ycYYwbqVcCSW7AzlN`3B2pSh2v05mxN5G=ZfREDd4ljJB(u zS1&#C)x$jA(;lps9&p$x&i@=*FFpK?e$M?Wb<>~Lxx`s{nvuz&VeyAKR(ZBpE5_|%+Wa9;isPIs68+Dc*Trw{dv!H;bB+! z_`%QgOus%h)b`brdZxb~5o-RBeR`&c?;7^PCExT&SFacL%f-Wcq&M6fxPJW}X{8v> z!$*(ro<4qE;0NnZ0}6&#*OW;9J8+Gz&aL|O;~He@&T4_uzZFU3;aZbrs``g_R5(|N8E<#(UX^{0 z3FnPTH}6x~^O?XuEZMj6#X8{}(ssiGDrYqcd}pr%D`$Kc=4^f1!IckZ1kO%5w6bf< zz;iksUTHrdtaa@}M^vu5HJq=Su5wi6#0SGU?c=3KRr-~Od7ZSo_~=US*_Va-nR|5Q z)7ndyWA`(k1M65=Hesy=%LiD#!SWeaEU;pP6+0|VU}*)H%}?!XG2;(kcyvX3|CslV zs_2}s{n8^VI#=8?<%o*TAuU!qyrOf^Q9faM!3pJBxUzuDlSvep$desZN;9z84U+50ZJuUy+M?BxfC-Bs?j ze%Rv=yfd$SX}7TV2j6j9`N0Ra_WVv;`<8OQ0pVQn#c#9AC!G||A)ijZsl4=p_CDv3 zFK;X#J8cK&-+#TaeCe|torgYrQ~B+0Iy;|{%qjO+Ih?!pJMxzDmLJvlc>Tt6%XO~{ z_ecjHen)v}y>LDhIu@2qSZl%Z0hVvDe1;VZtQcX%4oeeQTEWr~mbS2bW{-;* z*Is5^%(!ZUapeovICC@(Q^WDTi))*4&0!qw^+2T}J;jW_a%EPL=1-*$RFsQuk3UdR zjxOHf!HRPC=0Oiul+(2id$6Khzt`@;ifUly;s+|Kje8DwprV?|=42JsQlHl=71dau zZ_5?cUiRL|9e9v)CV zhu42-VD;QS{N0PI=lr!t4X$1bTHZXQdX0GD!J*Y_$C^)GQoW{ZQo6Ky-4Wxb=D<1@ zmQ7e|!SVr?Z?JrZ6$`8wVZ{zh6Ifco{huCOtp_pVyX`-ydhXq?*+tcJa@RT+R?pR& zY}3Db4!?YKzv{WY?oQ`d&-t(Ic3$;bFks%f)oTQ~(_Ry^uI9ix7M4v|Yr*mXmT$0p zh7}8}wKyk;HLmjjMSe82$xyE~%)GanIvRD(Yi&cza1j zeGD<{Y7VSpVcCSW7AzlN`3B2pSh2u2|9wJbtM$S?m6-9yW5!pmej<#wd3#)?&W!ME zHSdsdm4R1yZgAx zY43y{PVwn+m3Lnr@7Kpp=Z~+X_k^C$rMph39C2>w1zpzms>(0*Lci#dttVDqxj63~ zb)8gM@<`yldS6}5ml*%s<#S*i3(F>~wP5)G%Qsj)!-@q~jId&dr3oypU}*?TTbNv{ zk0fS%`g2Pv>LcxO-I9v>NIiQjsi==6X1?ac$HF(<_+;gfPCZ>`G2=f>eX25Mr5=6_ zJz(xXD|c?$-MRnMPgnjvx100*Up`YwuM51xhR;>rSsJ*}R?k_$&%MFU z8tX5roVnRp5TV8#kvhlm2ul0Vz7b{0@+S|v6ZT4d2 zUnlM7-2I0aDhqEuU^!-=Y7VSpVcCSW7AzlN`3B2pSh2v05mxN5G=ZfREDd4#3{QG& zQDyq;$GPTz|8h~KW#L@s0q49}ncHTlvvS9LF?rD(SjWP$32QA_=L+noe#Gh*X`K1- z9*^rm;~cATI6eo)`%B}@(Kx*H%PyJDpJLYi^}-!9?b#hx?V4#XFC5x6(;naNhpw6S ze*YtDGMy97n_rXZT=D5QHJQ#KbvH{gom-}MN-~{u*6x^OIu{+fNs{RtRrstX)4A)9 zn`$zh(=Ok)Ceyht{itiE^Pw33H3!zQux!Fw3ziSCe1qjPtXN>h2rG72n!wTumWHsj zg@10{DARRB%=rBs8)drIj6JMTrfblVS2xOZZ7O`$DAP4-`T>nIUCU1XXX8xQxX*hx z$#m`8=Jh6-u8E8LY*Nj;m~}M=*0Hc`!deTK53qcLlyN?cnL7Mpk4Bl! znUAz@l<8cGCOY4WIaYIE9SiT$W7ACMPch?-o@}0R{$#CFcWIt+{)7*n-z?+&33u77 zS;qMjzVOPX8Rt*<^3|GVoIl}-mu!-8{)ES@ze&dV6aIc~lZ^8xTsfvm#`zOY+cwEK zf5I*5HOV-C!uzh(B;))Ef7P@}#`!a5eAXOT$HKA+Yb{tl!14{2&#+>F6(g+JVQB(O zD_9!B@)_=Rcax0sCw%<0CK=~Xc<~#JGtQszU*%nMh+W6RvKeavYmdXqZ#>Rg8i(VW z5i=kDul8Mh4vhDO#yM8w@S-_wi@NU>vu?NkZHwwn{qfP(MfI$9_^nM*y{viVt%~Y# zW$jxR)%$w!_$`X+iS2x1%c6Q^Pj+ijR1a;JdYcy2TdVg%)1rEAx82aBs9s$6s~Q#6 zqicFc!=n0lV*Jz`SjWP$32QA_KEUz~md~(affXaH*kNe`ODp)8(anqM7l|3K^U`KT z^|Dr3r)5z+uEtHbD603><(Dms>WMvl^;Sjo%69vxO;J6x^WWUMsNUMk=eI4Y=SJ@I zJSApb&4G0+ESs>_g5?7&-(dL+D;9Y5nHv_=4-qqdar3$b^+SHTagBodA?=S_rJ#Pu zUGMy!s2?)x>0c7{L)N?Ymqh)L!}j_;Q9q>9M=KZ951I7G>IL;f4(VN|pnk~WJ2oh& zAF|}9Mg{dl9{*;ug8Cs_p46tGen`VcI~0^JG5%`~tYcx>gtZndA7J?g%V$`zz={!8 z?65R}r4=jp9;FyI%&j@1>J)k*XDm`>vpSwngWCUC_PU`0ig6bdNV~+NTBG`&~Qp!-DP!KRxB$g6ctbNk7_SI+b2G_Q) zKARuVrG538{q+IcRiEWQJ*8ds8GoI++g6|bKRUH-wLc)nf6ak)EG(O_)`H~&EZ<=H z3@a8`F~W)+mL{;Yf~6rWZQ=JXUbDRPyU@=UGycO-E0r5B4)074DtuL1Gk<@2*_&^b zwjLVZ1s+?8SxqbId&ME4ge`@*MqOJ>K{MQ^<$HKA+Yb{tl!14{2&#+>F6(g+JVQJ!= zYXwU~SlYr1cdZol+$W|!U%I+d)N|i9&s2(f?xQC4+$YA4=D<1@e(u}*i|Rp%vA;p{ z1x59#&fI80QT?mVFW+BOUu(zH?k}p}_1N?G71akDTkpQ2`eVad-&<7QY~~jC6xB~F zuXlG*eYWnO-&s`uZMCQ77uA=0emgOJg=xeUi(?M7kO62e=$C54yT`-1JH6kVR@A+5 z>Feo5-8296)r_LNRpyWcdcsC(~S_Pe2|d-82xyrHOj^*-C&SkyiI_=9gO z>fZj;zuj2WJ^$J*Z!GFr;MsrNP}DQRfrT52dUiN|)U2YODPAbgEb6&KjQ^Sg>sVMe zVXXzr2Uxzr@)=evuwsN2J1k9{bFE-$2uoXdud@!UKF^97Z#C+G>N9U?;C|I-;lq3P zu0A8TZm@Ut+4=f6_NYEnZ&mJ9eb$~(=~;aSzxk`~)o1hjPUu#BX79YkuGMGxQ@ZX_ zea7En&d$|m|A`muThouQDtzdl9^RJlk zF}LhoeMbIz*Ila5&Mj(otv*vv9^S3`ti65f9@S^?-fQeueKtR_(eBk}_9OS+v-&K* z)`Y#Q`$){Xngi=tST&feEJtUUs&-r{j=Y8+OsnIk>L zdY05U^VcZtlBquNR~@?3t+tRcCb1OueZ;p6HpWXSM#)o|$@C_FY+~ewWz&%;&&5 z7M4v|Yr*mXmT$0ph7}8}7-7W@OA}aH!T6?n7Bg<&PiE@**!Po}dO`O6WTqaGeLtD0 zcVypBX6h-~_mi1=P4@j{rXG}iKbfgFW#8##>W7F~S94$;3(F>~wP5)G%Qsj)!-@so zxqa*Ex?;w+zhTQv*P~yWZJFtMbi~vxGF^{eYqLeB>(O10w90fny01^GOxL4bw{4Z_ zdbIhry9h?_=j>PcFE?j~zB*UN+^(z^!hXmks;ApO0_*$h>U!6@fokI4?VN^@wPh#W`2W(=lM8xK0YTf_AhK1n03>4&hSG|_ytg0X{!F!s?FW?eLg z@rPW%_(_gn{3my?atD8LaL66JQj6QGcFtQmw`%{*Y;JYk*%Rk_?wG&!`ExyYe(X_m ztN!=uJ=b%`_yK#&t;Wl^bXdveOCRh=H|$GK)|JlqBmMDHdBOiUUvVClU*;(99IJZ3 zrs{;XR6qEjy23Zr8$PQJ6(f6r7*)57tDc#!I>(OcAN$%DtgHQkKiWt5sr`ljH_kZS zYna@XuMSL3_qs4JxvtqWFg5V&+JUK!(f6O`$5J!L9ub&Y+UvVheVm%?b9rEDvU$V6 z)Z}xsPVqU6f7LlK^Z)hS$v%#qxn~E){w|vbX5CfaKFR0c&sXyT6s3rMHjmdv%kKAFOnpC`uO9$pl zAM8js>`PD9mCpDh{qa+I!T&g4aUPXl<|ywRt9rnu>V&maKlq@!!Z+0$KC2EDqxPNZ zmT}cH^Ht~AQT=0I`+{|~U+_o!2tT#I@c*>wM|%x>O->3-PB$13m|Xv{dthqdp|t{2 z8-Kg+C_k2(X?=KLYH5RSkMwbBvcs^z)Z}{`1*Rq^%sj&9Fn&*`z|5ca?BPC+opa9$ zjQurQ1ZLeQ-aO3b;Lp9c2gc8y;{xOV5my8zE?D)+9GE#A3v(0c8#Nn=A#vi9W;cokG3%DqB)E|>Bi*nsJy};e8f8gX#+3RB!mKI#i6>cdA>)RnN>C(W|zRSE|IbYWv+n3O_VzjWGjMKT{H!}R zF#d0Td0^s#RiDg(nZvO#$6^!4CTqd0g%2=3;2Vr@_zdGSvA~KECPre{IGSiaTEW;s zLm2yL3$reo!}vokVEiOUF#eM}Sh<7AspgYw*`WqxpW4v6)QtS0mgFZjCjY5Da)*8P zo#JI&Ixt`QU`M)PUwX2xbjBa)kDtm5{>S->^QinXM|tO1)dMzFC#L2^s7p$xOfRuI?oKEf+m|Tz8 zEig5(*BXJTjW_S^?#EIy^A8D3ElvKan~zhI*(HIg$-Wx~rY1L?zN^n+e3uS^ncw#5 zU3?rnfAk5A{jtphv+e<}@9cB%XP4UouVPYh9jiZU?qZN!DG=#B_wlM3WIgCH#0>)2r1mi!sgOxj& zoN7L~mK|z9_Nfi6OU=k1YDs=lWAdNcBX`(m-zi?kr33S&4|b#*_N6E5N@x6${`jf9 z;D4O2IFHINbCh?ERXt!+b;4SzAAC?<;hX9WpH+v7QTtAH%ed;9`Koj5sQ$69eZjig zFZiQ=7fvL&&ukYk@7++(Dz|8;hsg6F5oqwDW82bk`3(UHWU+ds=@Mq0i z1LNn!(Sh;*wo3yO7p(eZ4$K^mg*g_RFg95WW-WYx@d4jpe8XoLpNR!lj4&}0yT;K( z^U(^%4jRJPM_ZV6(HzDfaslHfIfC(@+`-BnOineQT+0qMAp6vY)}?0T549vesWJIa z?U6g|v+ooy=)#i)I!x@BDT%zV{3c2xh^*S=s~?HByfKEhA!FZ>@exvkeQxtlaDFga~~ zUSM+FphsY8V9Bb1sf|FRKKoAbGAI&afZ}_Y_RE*kps$0fY&&*eyV@LIm zeeDa@)qcSr?IZlu{=)yB*ERPVCU-}S4NOiyJ0~!?ezjX*YGBGLfvJt{?6(#8NzJT! zU|?$Lv!zXaoSIyBaA0ckfpr5@lYOUb;&T`uyIo-BU-(25AIDDb(*k4v?IwX)ch)P7 zeGdMNn-ds6TZ{~h|6PU#CN5a@$sCwD91C+SHeqbC7R*}s0OJF`!T5&HFg_CttQcWp zBzBFXiRPmfj2$$Dv5&Se>!LY~KjZ?&PjUp~Ke>aIJD8kmKDm}1YC!g>4XsPf$RBD+ zeo|xdpV}jL*k|7P+j4h>J6WXg&J0j+IOm3##PVESDj-=^^bk+3)aoc) zftkaxFvnsO#wKgQtc4FSKHwXSZ}<%3GqJ#m5hg}r*EpJJK3c)pK|>h(XbZD0n#1@* zE@1p5M=<`AJ6O4c$*Ja(YuTX&WS`p5y3~yPp_b$)H75V5J#vSA_MPHoTskmc`d~-8 zVPAT(u5`v9>5rev3;xIXiu0)aGDmsmSk(hIRVS>a`oRa)6~3w7@L6@J7`5+Iw~VWv znXfv>j_M!#+83;={enN*NBF7zh5rk$Ud?Nm+pp?;^N{+1@&B?ve)l=V1*<-p12czXVUEQnj7`>pSqmRve84vt z-|!j6XJUaBBTS6Mu5mQce6)hGgN88n(H3T1G>7qrT)_BAj$r&Jcd&8?lT*zn*Rn$m z$Ue29b*UNoLoLZqYE1r9d*lxL>^sHFxO8B?^udmF!@l%nUFnQJ(jPyS7yOU&73Wd; zWsdUBv8o4bs!mu-^@9(pD|}PE;j`*cF>2qbZW&iSGhcO%9o0YfwJ%s#`vrfrkML9b z3;(y>?u%-D9=b_ja@zl`&wZR+A2>KLHSp?hOMRT$`2C2$)Xa@DKJ#&EssD?gI#ZLC zA3t%XCYv`5Oid2z@Nsqgk%K>~&Yv{=Luc%y&wb#G{o~pNX5Ei&dEdwJ=O23p#?N=x z4~+lo|Ms5Gp(bI~Cv#xta4gKR*o3jkS}<$j1B?&&2ICt(!^B7|uwsOXk=QkkCYp~{ zFm})o#y;A@tc&I_{*Vh8Kgkh{|KtuPMvaqG%_rBgLk-A2wV`#X8Tmsk$xmub{!@G8 zjB+j%8Gocdekw2cALlF1qw>of<(*?y57<TP zrh3C?)uCe4zEj;Yu6ky^>Kr?&f9z{tu&(wC{%9ZJr}h{A-?z<6)%tv|QDAbq+8ZzW zIJti7qQKO^3BSDHixxUllfAxw-kF-T-%L4Elk05%Ty=b( z1D~zV-~94toU!wy{cRI;!2aiL1GDZqbN=b$_|tp$!1&o`-N5*N?axp79BL9)eKJRN z%ds%WViU$DYr(9A4=_I98;o!G3=<=+!Pr4V82e}ovo4y$_(LvW z{3J&(F_Jr&7&T5#HJ@C|4mBYA)P~ljX5~DPG2<1M{U1cBC8j zr6=o3XZ(@=_^G_$f1Iy4kIFA|ly{C*Jz!IH!dj{yd{ABC8$MH4_^diqjM{gqTgFw- z%vYUbNA-_=?F-h`e!(B@BmC6l_`8c(7<#YEsQ@*8T0qJA52}UhNqeKYywd82`8Uah}hiCSlblb5yq+3v(0c8#Nn=A#vi9W;cokG3%DqB)E|EGE%u$_Wn4NiU;1E2x?x{>vaWQ-AL);u$_xI-`HJ(X z{4$4Qeec+@*o3jEI$CvX1?kiJF0)|YhSP~n#&(@ zAwRXh@c-G?(|w%W{aimVIc@yPG#@9|-(3)x8W`~X^*&B*Tz_C-YNqFPQ+=FTYVyn! zXKM1OuO>TFla@DUYI3t}uB(n8zwfox`CW!yVDN%(_?1n&jj7bA0!} z_<8Btf$@LdcN2XMalxuj=D^J1SeRq631gGBVAjG17$5Kr#y5P1iIG@f#RwB4v1=Sn zG#{;C?4TixeYAyH7tLY(Ar~-yk|P-Z$sMfR!Q@o)sb|@tCS{-6(7M!&{GpcQCp9Mj zsXeppYf+PmmvQO9eCdN7>4tsj$-2@Rf22QtDlhmS=PS;m^2;3MonuuG*i@acmg)x| zR9E<>dc$Ycp<>j&Q{6JIdS<@r96PFi>}y}JuJ#N5XdmIH_80yivc=`q`n+s|z~pq+ z;$c2ct_PnVm>O99+sk~M+SvMlz|_pbt1tC&YUzfjE^($NKmL5EGc~zK-N4l3Ep3KW z$G_NnaCQD=e_ZU0ofk)3+!Pr4V82e}ovo4y$ z_(LvW{3J&({*ybH7&T5#HJ@C|4mBYA)P~ljX5~DPG2<1M{U1 zcBC8jo8@}4u5`v9>5rev3;xIXiu0)aGDmsmSk(hIS&O~HTB;v>P+j4h>J6V&hl)}A zPIb$;>Y4efbL^=8v9Eo>y4o-JqkV**+F$tpc#p%X^|@*Dz~uC(*@sr^x#35LI8y_g zy?d}TwQ=Gev%^?|H&Op zj2b7Wnoq7}hZ>N5YD4Q%GxCR8lAqL={HONF9c!`g6ffh_f%(!0JJJpN(vx+iGyX__ z{8V1>Kh9U2N9C6}$~(uZ9WW&Tq7IrZxsm-rSj*dA4;6 zXKLxZ+D)CQ$=_aR=1fi6yH{swa>(vYs^e>qYgC;-@4JT1*!g2{183~_+G!(a*4@9R zzBB%;Ghjn!YI6700^|Sm*EaBRY7$m`GDmgGu`tJC6UHWM!K{T3Fh1ZLjBof16C<&} ziV-G8V%IpDXg*rO*g-=W`)CWZE}FymLoQ(aBu6kYk~^3fHBL@7pIplhH6Z)chSsHK zP+j4h>J6V&hl)}APIb$;>Y4efbL^=8v9Eo>y4o-JqkV**+F$tpUcdLs ztVQl7ZWWlE)-S&6@X$hRML#!j0bA9lum>D&jMS@*e9GiUtS`IE9UepY@jIpcqy z+XE99tome*>Xu_+j>RU7P1b@vM)Lv22YiF^4WD6RBo78)@J;oG z&#FVksC}opWnA^leAT(fnAbn{wJ%s#`vrfrkML9b3;#EL?E|6gg*vZU+X@i%SeOiuUOv#~R|UevRmGd1wq=RYlA zKDF`3y$hYGnO9oObf%WZZF{scHTlidckX9CHTm%e<8FYdNgMB~ahqQQGvDkuW5?_} zW8czA!JVxg{Mz51RM&~?6=R8K|JVviWV!ULfF+ z!5*V&2xA{@Vb(=+7=OqGjGyEP#(#1L6PL!xspgYw*`WqxpV}aI981l}A8JW{Qe*O; z+Oxij&!;98FXPgI`O*hFbTuMSLfUP zvom(=8N?a;cK__mx_1BUj6Zh&?2Mmw|Llza_Uz+KO~R^A=D^J1SeRq631gGBV2{y! zfbjv}V0^=8m>7u#R*Wz)61&FHMDx)K_83h=82e}ovo4y$_(LvW{3J&({*ybH7&T5# zHJ@C|4mBYA)CRfZSZYT8P)qWY8k7H_CZG5D)TH8NTskmc`e29L$-eYtUFnQJ(jPyS z7yOU&73Wd;WsdUBv8o4bs!lw{yncvLb%k%LH+)tdDn{)))h*+yXXdNUJ;uELv9Eo> zy4o-JqkV**+F$r@{i33-ch)a*Ca2afawgZ-FLI^^tY73zZCJm^nVPYFku$Yq{UT>- z()vZt)TH&qoT*9c7gfitUsRoM{UT@VSii^_`_?aVW?kzSIpdG@i=6S(`bEz8Z@oTe zY7$m`G6!Z3$HE+oO&FW31+x}D!1#b~Fuvh4OpL?=D@K?YiCyDpqWNeAV+Rdk?4vEr zx@ZpL54nKxlN`bLPwrr1)HpfSd~z*2)PU?$8(No|kw4Uu{G`U@Keb2hSc`q9co~-t z%$Gjck#5+Ro~$dK@kjdOr}BdTalYa_D!uSH?kMhJGj{C#h%@%>{fIN` z+WQe_{IT~V&iHBXN1Ulid$;9GO~R^A=BREt7Uo!N!q{Xjn6>Z$#s_?Z@eQA0Vk8z= zF~Y=1>>5WC%||O3J7@@FA8ldQMROQ`$OVj_uJXlWWT^tIS`ikETezB+j%8Gocdekw2cALlF1qw>of<(*?y z57<TPrh3C?)uCe4zEj;Yu6ky^>Kr?&f9z{tu&(wC{%9ZJr}h{A+xGy~ z`n2x>s&#AM12~gw`yRlV8fdorKxb;hz6WroX6$P+aK^rU58%wY_C0_z{@C{b&iHBH12|KY_AQ4qH3_RenWMVp zSeRq631gGBVAjG17$5Kr#y5P1iIG@f#RwB4v1=SnG#{;C?4Tix{br^u%(`d};}5xj z@sk|E#7OR7V$?V})qHX-JJdk4+&;CTb*UNoLoLZqYE1r9d*qI_*msJTap}N(>4P2V zhJESDy3!ecq(6QtFZdtlE6$_x%N*sMV^t5>RGqMv>IWZGSNNuS!)Mi@V${A<-7>Cv zX1?kiJF0)|qbuJ#N5XdmIH_80!!_ixquwC~@lb!*?hIg@Mq{>_;huU{hD%^5rP{hKrP?fW-p*0t~7 zobkuLe{;r9`~JRU7P1b^03m;&7z&9A*@EImXVu2MS zOpL^?aWv65rev3;xIXiu0)aGDmsmSk(hI zRVS>a`oRa)6~3w7@L6@J7`5+Iw~VWvnXfv>j_M!#+83;={enN*NBF7zh5z=wceOt4 zd+%!9+V|ehStcE-Ma@9oUG_Pw_={@C~4&iHBHdplE;_N~4%H3_RenWMVpSeRq6 z31gGBVAjG17$5Kr#y5P1iIG@f#RwB4v1=SnG#{;C?4TixeYAyH7tLY(Ar~-yk|UTH z$sJ6L8YickPp)N$8jyWzL+esA@`qZIpVXNAr}oGlYq9SXFXPgI`O*hF(hd94lXayt z{z!lPR9^5u&R3jA<(D}e%O2raY{J-7ov@bb2Om^d_@;WpXVsx%#11j4ZW&iSGhcO% z9o0YfwJ%r~&E*fdke}LL_;0^&@^Nx!zi)CTr}q0MXL4=7Z*ryv?DtL1)Q0`O$(fq5 z-#0l^OZy!7tTQ!fzi)D;CheOCXKK=Z-&7s9-#1m~+wYs4v17k)a>l;>zR8(&?e|U2 z_+!6sa>h^leUmf(+i%mHi3?VJGDmgGu`tJC6UHWM!K{T3Fh1ZLjBof16C<&}iV-G8 zV%IpDXg*rO*g-=W`)CWZE}FymLoQ(aBu6kYk~>(rgUPApQq_Jy1sMFajs*n z-*5f*bw2F94!zO2dZv8zQhDmJ^4EL36JJkOul01WKYheWH}TWcx#=vQ^p|J8$p5Ba zH+{@sd-C1a)(>LVC(f#WclE7xn(VVP`|ERY>VNTjE}Yx*BA=ck zdG>tCe?HH9`g1!tZT@3Nkp&+{(p z$;UkM7nk+qe4h8L&*yp1{`oxbvN-d3-evLU^SsN>ozL?w%V$2%yDZQ7JnyoeoX=t} z>q%UH+Jo)!wb<8+iN$mlc9tBl9OQ=OCTFZhwcu*RYE*mcG-*GrusAft;?ov8m*!YL zyukA05tcviuo_$EY5RFy96eBcz0tXPrhN2LdFsjX*L%EkmglZ|t*3+i=_5|MiJzX% zO=tO}zdZ9r{x|))>0|!dlkdK^eh{-haaR2!hx$rx^_!gQ!)olgt8cB>&-T~n;?)1* z_gpx)=S4m}NAm3XlK;%FIQ=>ED^B0e{EB5>&-{vIJuvet?#NAV%>0UFJu~wwmi5xi zuUOWTGrwY4PtJ^vWj#6bE6)1NuQ>Z>e#NplGrwY4{Fz^|?A)1Ou`HjNU$HFDnP0K2 zCujD^vYy2Cr#y6IUGv%X~%2SV(zux1WvpjdzYdsz8Pakp8 zP5kt9ZaT{+{pFc2^1tcVO&{~uo_zPU^@Eu8iL>e-In-BjtKZ~YA68?}U43i4ezw0p z7pMLgzvsfaJumXw%fqw5&H~UemIknR!ji zdTHi0E$hjd*R-rBXC~FMo}772XMN^1o&7VfX<3|^*R(AD%xhY9?#ydime0&smID+@A1xAp1bO`o(}e> zk2vWjetJ4Lo#m7M^2`_c-}LLIkNIm)zWdtxLCpHZS@n+`>MOa`Z*r~=tFh;PM;S0h%V+FPed`)P&6 zp&=HZw%EBe$MWF?mM4#}8hMA+*g8+!&+Fpof#U0p&eb#JqnFB4kCngP z9qdmZaneov^mJ}I%P0NinJ@Cc>DNsk^Vgny_qFwdnDvRX>K{4OS8}W0nU3Tuw<6V}| z%;Q~_=gi|>){`?!d09{5`qQ5J*4JWRD<&4xS=d=}z;ciqmYbZh8r6cU5vx({t<$9a zw8G-h5Q|S+>|B~-`S1eElSf#Myu)g2ou}>Rb#e4S@%2XM>Y4Jb0H@_NR|H=_Y=9Iyar=lm7C|7x~}x>!y$SYfrxW+WJAv`ovlFj~wbNxz%rSt`DoR z=dQlBUO(GkpNmufi{EqM+@2Tt^c=~v=S%)GfBy96%%4AfJM-t4c|G&zm-WDN9{pb~ z>y4Q|zpQ6w{`|6Dn)&m~dUEE^FYC#fvA?V*Xa4+IpZW94_RswJWpQTy{Id8ne}37y zGk<-2uyb64#&h)VIDC`&u!vn9jn^k^`25+_2o_jODBrT#ZYUCYOW9vL^Kd+0U2a2yZI#k6tQIJy!mD zk9W@U+*Pmjbg(~t#7Q^t)6==>ET8n3XTHe)re8OG%wK!*-PhI+V%8_ls(<8AU&*b0 zlXHDojXihut@ZlZ{`y>;`d|E>3+MK{$fxH>o;_dkpZiu$f6jd?r*G%Jm1SN(>t`;k z2j;$&UDq3P-^#L{nfq3j_0rt8vaBcPzLjM?Id{q|>&dxq<*d(rD`)@Qx3VnG+_$nU z{@k~+?A*C;Wm!IR-^#K)AO6Y<>&dw*XV>*4u0QRmZ+$KHwPIp1orRqx2P_AI=lZZ3d+zF6>-Dq!^|?6pzxX{D&h2@TPtTD&d%om9_luqWocqO=c{=xt zoqnGC#g_HJ|MA!dm-WV{{pkzqnYmwV*Y(oeFSe{F|LEViu%4Xv`0cu$eD8mMVe50h z*x5h#i=8-gzu2<)bHCWKbLW1sW%?}E8ImivGQO;P6YQfcr)u{H?Y0`dLVR2}P#iuQHF3qugc!A}~BdkW=VKuhS)AsYa zIC`M?dZTmoO!?@g^3-GHulIQ8EYDr_T2BZ2(?^_i6F)tjo6hn{e|hGM{BQbo)5rX^ zC*OT-{UBz2;;i~d4)vAX>Nh#pht=3~SKnH%pY5;D#i{?r@40Yp&x?F|j^x?%CI7ik z^YrK3r+NBz?$cc6_1veqtOw>k&1JnY_h~NcnYmAMSuf3fn#+1}?$cb>lXGY2vYz~u zmtENU+^2c=&wZN9;>>-T%i_;{n#<0e`!tv3^Phb6h2=T-Y3{n7oV!q$^(3x8?Wu2l zE%voyVlkbCoh1h>2f1On$r-CrEw~!78r9x9P1;W@EDjB^__W2&r8$-lFR(m$gw@D9 ztj5-P+J0UaM-LQVZ*;DnDIdL5o_ehO^&an><+-a~>*-*B`iPTm;-{x`(^)?0FVB3D z|4qMc`k24=r>Rapev;FnCIQ75yJr~aHd67@g zkvx08XXgIsUDr!y6IUGv%X~%2SV(zux1WvpjdzYdsz8Pakp8P5kt9 zZaT{+{pFc2^1tcVO&{~uo_zPU^@Eu8iL>e-In-BjtKZ~YA68?}U43i4ezw0p7pMLg zzvsfaJumX63oX3wDp5yzliF){~$6TVJ^Adh(4gzp(X}z30OAzvhqs+1(?~kNwbv#ed32 zz380#{0A;9pO?M(!t#92t1c}6pMC9x^(3x8?Wu2lE%voyVlkbC)hGun2f1On$r;O8 zEw~!78r9x9P1;W@EDjB^__W2&r8$-lFR(m$gw@D9tj5-P+J0UaM-LQVZ*;DnDIdL5 zo_ehO^&an><+-a~>*-*B`iPTm;-{x`(^)?0FVB3D|4qMc`k24=r>Rapev;FnCIQ75yJr~aHd67@gkvx08uFu_DANrQJ+<*0M`TE=~ zU!S|>>vOk!eeRa8&)xF%xm&(IcgxqFT)sYcXMJ=y`$wPU>vOk!eeRZ>J3234pS$Jj zbGLkb?v~Xxel1`9TE6euqsujQ*>%U8dauYN7-$?@x~k6&m1__ciXYx(Ne z^3|{9t6$4kzm{+NHP7ArzT<7{-Ax{UcRe5N$w!=zI3IC7;(WyUi1QKWW9xiuKOb>E z;(WyUi1QKWBhE*hk2oK3KH_}D`H1ro=OfNXoR2skTjyi@`H1ro=OfNXoR2skvHa(I zmGx9z^Z($odguSgWjf6No6Gc>|4*0cHvi8q({uj+U8eK=zr4(^`Tu&EU-P}nGQZ~k z_p?6#@1Oni{lKy~^L@gy`1Ae4vUBJAie>rC_Z!RdobN-HDIaQEFU_TC%?*{U)9C0>b0H@_NR|H=_Y=9Iyar=lm7C|m)m~vj*n`*$@W{%N1Ts1 zA8|h7e8l;P^AYDG&d1j2(|)?)e8l;P^AYDG&PSY&I3IC7;(WyUi1QKWBhE*hk2oK3 zKDN%s_VW?vBhE*hk2oK3K4SUL&*rB;=jXoDxAXJhG9BjU#AW)-&yUM=o1ZI}={Y}d zF4K8_4qfKg{Cv91uld=0nP2ns>{*|mbI<B=j&y8 z&d=S;{FvRwY=OfNXoR2skaX#XF#QBKxv32^ipKdrGaX#XF#QBKx z5$7Y$N1Ts1A8|h7e8l;P^AYDG&PSY&t@E+{e8l;P^AYDG&PSY&SpM_7=+mF`d(P9h z^ZU2~FFSXBZ@es@`F--TJm>e!%lw+(KQHsEb@jHN4#lBQ@#)sN^ei7b zmnXlz%%xzxOTEVg3%dOrQDt;47Qus?moNjLG+)4Ay^pY)e! zzTEbUcYIXiO}5`U9mK);i1QKWBhE*hk2oK3KH_|Aoj&cS8_q|Zk2oK3KH_}D`H1ro z=OfNXoR2skaX#XF#QBKx5$9v;d~81-aX#XF#QBKx5$7Y8|Gd}e^yj>f<@D{mzh#*Y z^S+m5`po-bmgzR{lUb(cynkky&hx&SWq!^3ZI<~p?=@QH*StUHtk3&)&i;8n&$2k* z{iX|xKkxt9b?46ef|lho?-yE@=e&<-nP2n%qGf)yuHN?3p*Zv@KHWN(p5;U5^5j?f z^Q*e}RlU~J!T$6SC*8zPPv@qye9~W@`EuJY-tke5H`#vcbPxyUBhE*hk2oK3KH_}D z`H1teb^5fQZa5!tKH_}D`H1ro=OfNXoR2skaX#XF#QBKx5$7Y$N1TtX^RfMW#QBKx z5$7Y$N1TsX{`212)1ULc&C|E@e$Hh&%=ET8n3XTIF_ zi+6lf<4v~TIvvEp`H1ro=OfNXoR2skaX#XFY@I&sryI^koR2skaX#XF#QBKx5$7Y$ zN1Ts1A8|h7e8l;P^AYD`>wIiKA8|h7e8l;P^AYDGmj8T~4)eK& zW%|tL9hT`fpMzMY=X^e5na=aMiDiDx=P8!?HJ>F}=GT1w;;hf-GS2?_yvDLP^Er-X z@n7?yk6Cu^eC}geKJ$5yWqHo$M3(tApC4J~SL^C+KOKrgpW@T4bLm+=bS_VRl|R3# zi(l1iJss>%A92!6{Pc8gI?E^h<(V(H{o)-T)p(Qbw@wFfa6aOE#QBKx5$7Y$N1Ts1 zA6utS`{{=B5$7Y$N1Ts1A8|h7e8l;P^AYDG&PSY&I3IC7;(WyU*g7BE&qth(I3IC7 z;(WyUh~+<@ojmuiitNi&@UHqzE>*-*B`iPTm;-{x`(^)?0FVB3r?HBL( zsK%RYzjZo@gYyyRBhE*hk2oK3KH_}D`Pe#r+D|u}k2oK3KH_}D`H1ro=OfNXoR2sk zaX#XF#QBKx5$7Y$$JY7Sem>%S#QBKx5$7Y$M=bxD74XCT-F!ZWzO3H)eEKpS=5y=I z^qJ4IZ$Hy*KIgtn&-wiOGM(ph@yq=BwePqvzh+jzuJh|vUwdKe^SS%8e?E_Y;>_pt zm&KpY?=L%dKG(l2pZUE1vOH%Fz_R=w`YRXaSL^C+KOKrgpW@T4bLm+=bS_VRl|R3# zi(l1iJss>%A92!6{Pc8gI?E^h<(V(H{o)-T)p(Qbx1NtUA8|h7e8l;P^AYDG&PSY& zt<$Idbi?A%6Xzq&N1Ts1A8|h7e8l;P^AYDG&PSY&I3IC7;(WyU*g7BE&qth(I3IC7 z;(WyUh~+=Can5r$b63uDH}hD|b2oEZ&T}{OTbAiIb6u9{IrCnY={$2_miaaFVV3#z zm`DENGQVb?%vql~GiU$IpIH`X=F%*SKl5sqojY@EmiaaFZI<~pb8nXUHS=(m`PI65 z+fRq$(5Lux>s)%451q@CU**rQ>f%@RT2BZ2(?^_i6F)tjo6hn{e|hH1ZNGTOM>XDL z`>oSK984eaG2NVt^AYDG&PSY&I3IC7woae+(+%e%&PSY&I3IC7;(WyUi1QKWBhE*h zk2oK3KH_}D`H1tebw0MAk2oK3KH_}D`H1ro%YSCUo&KCTW2bLt{@5}dW-i$>eP&+S zGTmm5*)lz6zS%OJAAI&ZmiaaF(3bf%v*4EbHS^QX`pi{3`)A(TvN$t`ZCU)8&$jH` zncKE3pPA>jEYF$qw#=`Y|F+Dp*45j7IuwUK#iv{6(zAT%T%PFL~bmQVW2Ghc4|#XCN#@h01EoetvQe8l;P^AYDG&PSY&I3IC7woae+(+%e% z&PSY&I3IC7;(WyUi1QKWBhE*hk2oK3KH_}D`H1tebw0MAk2oK3KH_}D`H1ro%YSB{ zp8lM1XU^v`zh?gDGQZ|Mr_21Bd7)>0 z=7^sCGhcLBoS8eiEdITN$AibJ2`)2(yq zSw3_wPkxm@zp9I0)oVQ+>`xzY(oOvIbZ$D!C;jD_FSq^T9Us+rlkK-o2XSyd;(WyU zi1QKWBhE*hk2oJ&r%(IohVv2UBhE*hk2oK3KH_}D`H1ro=OfNXoR2skaX#XF#QE4d zAKTAIoR2skaX#XF#QBKjKeN71f6g4~)3-BUdYKM0cY2vVGmmGw*ttU-N$UWq!?k?6W>|v(NsSr@buB%-LQRf97v5J9p-CFUx17Qus?moNjLG+)4Ay^pY)e!zTEbUcYIXiO}5`U9mK);i1QKWBhE*hk2oK3 zKH_|Aoj&cS8_q|Zk2oK3KH_}D`H1ro=OfNXoR2skaX#XF#QBKx5$9v;d~81-aX#XF z#QBKx5$7Y8|J>zt`g86HI(<9$2QAZK?iE_5&)he(Ot-m*XqldKKhZLs=iZ`ae$9PG z%lw-6F)s6K?ms%~b1%}_Klddqi!=8qEsH<*D=j;B?p<1z&)mnfEYG>8X_;Shf73F* zT32uT=};W{6rXOLOV9G5b9wTs{P|T~{Hk8->0p2Qh?8#Or>Aq%Sw876&wRP<7w`C} z#+z)vbvlTH^AYDG&PSY&I3IC7;(WyU*gAdMPdA*8I3IC7;(WyUi1QKWBhE*hk2oK3 zKH_}D`H1ro=OfO?*7?|eKH_}D`H1ro=OfNXEdRN?@bu^0i+B2V?#o-I!`!2{OrNKJ z#>XtvZSLJ$rsv$pw@l}`r*D~GbAR75zvl1D%lw-A{?7W`19=r(5UJvwY}Wp8P6*epMI0s@Hlt z*q=V)q?`EZ>D+XdPx{L^KDM8aI3IC7;(WyUi1QK4 zf9~piOMkzcdtjHx4SIQxrcXI{&PR?GQV0^Z~N&` z9QqWWZk-mWD5$7Y$N1Ts1A8|h7e8l^dcpSeGMnQn78 z{W3l0zV&4~&pqtR{QCZ1fBN#puV*gvYwmMD>vPZh*+2KcFN-sG(=UrZ_r)(eckYp2 zme1TTzbwzWcYc{)b07UOzgkys`{_^|`V^mTolDR1p>uiitNbs1UFzaj^;%B{`_o69 zbQ3>4otw_`Nq>3f%Wc1S$452ZWc#htK^&ZqI3IC7;(WyUi1QKWBhJUx>C=9?;e5pT zi1QKWBhE*hk2oK3KH_}D`H1ro=OfNXoR2skaXz-r$M*9P=OfNXoR2skaXw=C|J36@ z?)Ucp-50#!am(s`;154)nGXNxX^&W@&%1u>Wjep&$(C0d~81-aX#XF#QBKx5$7Y8|NOu3 zR6TrsJy}-o{J*eFhxvbDnLhLX!ZO|F|Al3G&gIP@t#-8z?^ zET8n3=lp-Y@o)RZJ3gxMCfjd4A8|h7 ze8l;P^AYDG&PSY&I3HW5Py6YH^AYDG&PSY&I3IC7;(WyUi1QKWBhE*hk2oK3KH_}D z`Pe!i+s{Xwk2oK3KH_}D`H1B|KL?%uoS%c1)jK~2Ez@Cs4qB$q{2a7QxA{3}nV$3g z{4$;A`}}2o&Cfy07r)-Q%&+-5=&aB8&u9O9|GX^D{2a6_{`?%Y?A-Y|Xjwk5f;vFB=c$4k7o{u;maX#XF#QBKx5$7Y$N1TtX)2ID(!}*Bw5$7Y$N1Ts1 zA8|h7e8l;P^AYDG&PSY&I3IC7;(TnKkL~9p&PSY&I3IC7;(WyNpWpl4-~V^>d%tD% z&hPz}=`g?dTc*$a-fx+1^LxK#dd}~!mgzjd*IMS+{N8VwU-NsvWq!@?{m%OQzUb_q z-xn>5Gr#v+7Jq*4x9r^cz2CBY=J$2W@|@q}Ez5s?zqib<*45j7IuwUK#iv{6(zAT% zT%PFL~bmQVW2Ghc4|#XCN#@h01EJs)vC;(WyUi1QKW zBhE*hk2oJ&r%(IohVv2UBhE*hk2oK3KH_}D`H1ro=OfNXoR2skaX#XF#QE4dAKTAI zoR2skaX#XF#QBKjKY!;s{W*W^Y^J`dCuRh zmiaY*&syeJ>*{Sk9g0Jr;?u2j=~+H>E>C`y|K)Y^QWw9f*LphGpFZNGoA~MJ+;o;t z`pYw4Zu`YMKC1C1+i#r?;^2J5`H1ro=OfNXoR2skaXz+ApZ3!Y=OfNXoR2skaX#XF z#QBKx5$7Y$N1Ts1A8|h7e8l;P^Rab4wx5qUA8|h7e8l;P^AXE`-q&&ZbKci+`gY#e zu}p_~U&k_i=6xN@bes2eEYow|pRi2ldEde^zvg`%%lw-6bu9C1-q&%~=luX@|4Tpc zb<5(+`#P4zpZ9evJ9pmKu`Hi?KgO~==Y1N>{F?V~Ec2^%^|qf5#i38}>DIaQEFU_T zC%?*{U)9C0>b0H@_NR|H=_Y=9Iyar=lm7C|m)m~vj*n`*$@W{PgE%-JaX#XF#QBKx z5$7Y$N1TtX)2ID(!}*Bw5$7Y$N1Ts1A8|h7e8l;P^AYDG&PSY&I3IC7;(TnKkL~9p z&PSY&I3IC7;(WyNpZ77I{+#zQp1z&;F)q_#-p9C1pLrkSGTr8VjLY<#_v0TN$AibJ2`)2(yqSw3_wPkxm@zp9I0)oVQ+>`xzY(oOvIbZ$D!C;jD_ zFSq^T9Us+rlkK-o2XSyd;(WyUi1QKWBhE*hk2oJ&r%(IohVv2UBhE*hk2oK3KH_}D z`H1ro=OfNXoR2skaX#XF#QE4dAKTAIoR2skaX#XF#QBKjKkwT={W}Fr^Sm#8nP2n1{bhd5`}UXlHSgO$>+^o^vwz<2y)4eW zZ+}_*dEfrBbLV~g%kr7`+b_#=-iN=;uX%s|GQV0^Z~N&`9QqWWZkbJJNq=`YWGx$PJ4_^8I4Y`=9nh=cPH=OfNXoR2skaX#XF z#QE4decDeqoR2skaX#XF#QBKx5$7Y$N1Ts1A8|h7e8l;P^AYDG&d1jI*nU3Ze8l;P z^AYDG&POc&`JCG6&-t9%>D&37+A(wk)6deA%)*=W}Pv{F=|B zE%U2&^|qf5#i38}>DIaQEFU_TC%?*{U)9C0>b0H@_NR|H=_Y=9Iyar=lm7C|m)m~v zj*n`*$@W{PgE%-JaX#XF#QBKx5$7Y$N1TtX)2ID(!}*Bw5$7Y$N1Ts1A8|h7e8l;P z^AYDG&PSY&I3IC7;(TnKkL~9p&PSY&I3IC7;(WyNpU-8V{+!QcpT3>XWiQiVK9{{r zpZQ$>r8L*~|2t&lfM#c|Lc%%&+-e_AT^46Pm%S|h zd_H>Fx%0W{W%sxE$2 zul01WKYheWH}TWcx#=vQ^p|J8-1duid{pC2w%4otw_`Nq>3f%Wc1S$45PRlkK;j zk2oK3KH_}D`H1ro=OfNXoR6*3r~P!p`H1ro=OdO6U$8v+h2_sjtj5;!(Rx1Oe8l;P z^AYDG&PSY&I3HW*WBd7t^AYDG&PSY&I3Kb6XYSVav$|&P*0OqM?$$CLX71K9eP-^~ zGTmnG)-pY3e$+CZXRg#TzkcHDF3hi)yS3~5nz>uc)@NSR*+27|mc^O5Tg&3l+^uEj z&fKkK`OLhmWqHmVt!4Soe63}5wXWXw)1f%@DL&mgm!9QA=knxN`SYu~_*K2u)4~4q z5hvZmPfzEjvwYHDp80ayFW&J{jW^kT>-mWD5$7Y$N1Ts1A8|h7e8l?`MW$|auB%FA?^xysA*nYqf#bep-#%k-T2z{_-= zxxvf)nz_o${F=GS%lw+T%4dD%@t*xNk9S#|nX9}k{>)WgcJ9noUY5_yLtd8W%t>D6 z*UV2|=2z?LZ9g4~L!aW)t#j#FK6EZmew9DJs*7LMYdsz8Pakp8P5kt9ZaT{+{pFc2 zxBcQBAJur1?YB+`ad1B3e8l;P^AYDG&PSY&I3HW5Py6YH^AYDG&PSY&I3IC7;(WyU zi1QKWBhE*hk2oK3KH_}D`Pe!i+s{Xwk2oK3KH_}D`H1B|_XwQ+oO=XL-_AV(%XFA~ z1eWPD_XsT0ZSE0RrsvGVU#9cS$zSHz+#|5euenEHnO}2{z*(R9^Jo9epI;Vd?h#lP zf9?@jcJACGuq>aM|GzBHxffuWUvpo;GQV0^Z~N&`9QqWWZkbJJNq=`YWGx$PJ4_^8I4Y`=9nh=cPH=OfNXoR2skaX#XF#QE4d zecDeqoR2skaX#XF#QBKx5$7Y$N1Ts1A8|h7e8l;P^AYDG&d1jI*nU3Ze8l;P^AYDG z&POc&xi{zZ=fhulVfD_vIj5iJ-kfFn%)L3wbenr~mgzb7zbw;v?uA+A*W8=4%&)mO zXPIAfZ_Zht`&Q2Wxo>4zoVhn=S^T*-XW6;W`kCLiET6gWW|?1e56-gu=YE`JezmUN z_S2y_^eH~wI+vd1L+A43SNZd+y7*PS*3-fM^bsfB#7|G>rn7v~U!M7L+b`bnQH?j* ze(U*&=_5YQN1Ts1A8|h7e8l;P^RadMw4ZJ`A8|h7e8l;P^AYDG&PSY&I3IC7;(WyU zi1QKWBhE*hkFE2u{d~mvi1QKWBhE*hk68Y5Pu%IxxhL-Q?c5W$OozEAZkaxFPuw!y z9`ysCy-d%4{ka#W^W1~B>-?H~;+FX}b4Zr?HTT4w^|@c{?4SF^mc^NS;+Dmqd*YUz zJNLvb%V+L)TbAeC`?k!lxesocU#+XR{d6b}eTq-F&ZTGh(78PMRsQ^{E`C+7^>na5 zeZ)yO@zc|}=`5f0muJ4*_KSCXRO3yy-#Q({!TE^u5$7Y$N1Ts1A8|h7d~BUQ?WY^g zN1Ts1A8|h7e8l;P^AYDG&PSY&I3IC7;(WyUi1QKWW9xiuKOb>E;(WyUi1QKWBbNW% zi+cKV?n^y=JNKe4(_!vKU8c|6i@Hp=xfgYro^!wFGM(q%&t-niy{OClntM@~`8D^V zp7ps;^X#AdG?&Ghdr_CgpLsxE$2ul01WKYheWH}TWcx#=vQ^p|J8-1duid{pC2w%CgAP z>cZ-M*^4hshvz?VVfsAfqb^LhAN!#{yI)Js*ZlDd)A?oZdEu_}>y0nJFuy+cw_ccE z_r3lFyT|$`{hkZk|FI8!)vk;4?ytPC_+RsJ7k2KQpL_o9k4otw_`Nq>3f%Wc1S z$452ZWc#h>BhE*hk2oK3KH_}D`H1ro=VR;iX+Pa?KH_}D`H1ro=OfNXoR2skaX#XF z#QBKx5$7Y$N1Ts1A6w^R`}v6T5$7Y$N1Ts1AF=%3^X*@|J^c8;^}UB5@n_zI-|BrV zH`$(h&*@u^zx2spoWD4KasJ}`#rfO%{}<2cz3*o(e%&qK&)oaD@8Z|p@^jz4-;Z7V zx?6rfcJJ>97r*Y7za!lHd+WuoyXEh#_uiLs@#}7RU&_7r?_K=5Ti(BS?|se}zwVaz zIr|)epYQzMpwAuneL|l{@Oy?nr{MPweSX33CHh>0-&gc`2fxSYa}a(X(&r=mKBUi0 z_a~Lju-7Rw%?#-*Y_;t6;tGPGV>*CklGS}H9Tkel`KYM>q={|RVkLaFvf2ZjFcYnW_-vjJ^f7h7#-pl^p@zS|} zTpWJ~aW6Uc_mS?Mzx+MrCA;qLDcw_V-TmzCcRzb^X1@2b_%q*o*|{^{ds#j+mwQ>B zGp~DD{_}gAWq&7X-TO1!?|qxa@qW(Yd;ekQdjDbhc>iH}djDbhd;j6gE#I@e|FC+k zr-S|JBTl-BpPtT5XZfVRJo82VGZ*^QHFKd)y)zejnGQ1-dYL}+d$wh|&0OeZdd_^~ zWq!@v<7Ix$TWXP)q~b7!9LvV3L^@UlE-KJYTX=I;*6{Ayjj?WaR= z=u>>UbuK;2htB0m|MKTcb@8iut*3+i=_5|MiJzX%O=tO}zdZ9r{xgU6)HQQxPrWmT zc9{+{hjy7h^LL_Uy3HKgWqQs$)nz(A`0RHq^K0hNF7s>V&@S_9=Fpz?nO}PL&-~J5 zab^zfviLKHcG@wYE ze(5qjXAb8woo7DhGQVbi=`z1&e(5s5W`5~epShQ3|IEEy7H8&{E{i|&OP8HH^GlcI zGjm6m*{Sk9g4I4e2q`H&ZTGh(78P6U;cclE`C+7^>na5eZ)yO z@zc|}=`5f0muJ4nf8OVC>YDdIoO?$EIW7JPqHkZd7sI$Jm>u< z%lw-6r7ZKSb@jHN4#lBQ@#)sN^ei7bmnZ$ppD)$Luj;j)4)&*yIO!&SdOA0q<&*yM z%oq93yu=UI^-UL6@61a)I?TMpW%|tfh?eO#^AeZoIdlJ(={)lQm-#jG5|{Zk^AeZ& zHS-eB`pnro`)AJHvN$s@aasJCm$>ZQnU}aMpP84q%&(b$xGev9-`6s~T32uT=};W{ z6rXOLOV9G5b9vIg{P|K{{Hk8->0p2Qh?8#Or>Aq%Sw876&zWPnwa9uiC zzx?@9UHqzE>*-*B`iPTm;-{x`(^)?0FVB3D|IBCmU|s*ih1EOr*^Uk~pKX~w^FG*R zy3KsHWqQt>v1K~X{IO+z&3v|He$9NgWq!?kwzEESz0Urb>$NP-%x7B`f9A6-J9p-@ zEz4)-sx9+t=B+Kuf8Mve%&*qf+kQF}hd#yMKEIwz&+?&jdD6f9`BGi{s$T2qV1N3E zlWyXtr*qR;KIt#dnVYw@$baT~ow{bO*Qs~rdM(po=6WsDXWnPNOt+cqwM@^MPqj?v znOn8YubJz$%&(d2wal-X>vh&=9@N=C^PrZ+`R+GeSp1pmwd>BExn9finR#5x@|-zc z%lw+p1uXNcb@jHN4#lBQ@wd;f=hCx$=v=>UbuK;2htB0m|MKTcb@8iut*3+i=_5|MiJzX%O=tO}zdZ9r{xe7DgLQq&h1ENA zgpLj~M`)Qo^Es(yy3HJ+WqQs$oMk%CoSbET%^aa+e$5=AWq!>Zp|d{oXU_haKeH^( z%n@1^f941+J9p*?Ez4)-|19%s<^nCte?Hf?%&*qf+kQF}hd#yMKEIwz&+?&jdD6f9 z`BGi{s$T2qV1N3ElWyXtr*qR;KIt#dneVi<$baU~oVsTI%&B+g&n(kn=FcqCXFi9x zOt+aovrNyKqq0ornXj_UubDry%&(b0v&^rVKXcY+Zpqm{b4!-RnfWuz;?Mk4otw_`Nq>3fi~MJ9$p`ED%NJJf%q=-O%-oV?`poBim+3ZhOP1+5^Ea01Jaajg z`89J(miaYvOP2XHb4$+p%)2=IXWqrKI5W3oS^W3i_od6uow+5;@|k%f%lw)-B+K%j z&t)(3t9A9ZpAN;LPw}_UujkUUeCS-B^e=zDR2RRh*LphGpFZNGoA~MJ+;o;t`pa|X z$!sn1pLrLju9YaHP%XFA|7t8dSc^Aucn|T+@^qjd3%XFT34$J(Sc^Aw4nt2z? z{F-?eXMH|LfA-Iugk^DN-o>)`Gw)*Axijx#Sw1uGVp*OuzhaqRGxuPbU#+XR{d6b} zeTq-F&ZTGh(78P6U;cclE`C+7^>na5eZ)yO@zc|}=`5f0muJ4n-~5O9edSZHa~_tj zvmoaCp8x%+H`yNZAFN+>Sib78eAQw3s>AYChvlmd%U2ziuR1JWby&XYaMsQDki%7n z<*N?MR~?qGIxJsxSib78eC^w1b(zy5KHtr0!PmZBzV_|%wQrZNeYAoFzV_|%wQrZNeYU`CwzUKIqT*iwci{hEY7^nEQ@bGgLUVcLxtsIKGlBh z<#lFR{^nU(SC@HKSiSA1LviR+e7bcmJ1iGsrn5O|m|y1LVSbs9 zhxui0UhC$?wcorrEROkmSbXytuyf7p!}2l556jbhKP-Q9|1iH==U4mbP#pRcfBXD; zEFL~bmQVW2GhgIy{==zj<_}k|ImVb@<_}}~n0t)rW*#!8r}?^=&gSl7&zHH% zm@nonV}6;#+`9S0?KgiIi({TM7T|FDov3$&h#_}{T8uQB>Y0R(I)!TkL6o)>= z-#)*dOV9G5b9vIg{P|K{{Hk8->0p2Qh?8#Or>Aq%Sw876&-wkp)*^rNAF9io_UbjK z9n--acuXJj;W6Fj_e;z4G>6Y$d?N}Uh@3Hvi zGhpYMlaJ+Nem<6`x%!x2=IvvCwXWXw)1f%@DgO5P^;~+E51q@C{^ie?>f%@RT2BZ2 z(?^_i6F)tjo6hn{e|hGM{LO!;F85hfulp=89o(0J>Ej*^OgHyyV0yZ*0n^z%4%qYM zo({|}_jh1^x!0rhx6geR?RTFA7RUV{SbXytuyfrfg5~3$5iC#lk6?bemjv^xb@jHN z4#lBQ@#)sN^ei7bmnZ$ppD)$Luj;j)4)&*yIO!&SdOA0q<&*yM%oq8a|8VM>dw;6e zy+4=^?iIrHnZHvk)6G3Z*6Hb98%$^S-R#$nU+y!){Bq9`=GXk4;;g&(r~U5z!Q!|_ z35#z&19q-^m#}=?$AsnSo+ivM_cvjFwXWXw)1f%@DgO5P^;~+E51q@C{^ie?>f%@R zT2BZ2(?^_i6F)tjo6hn{e|fr(NiFg>|Dn3vk5;|zS;KU2{~D%`d)YAE+}DQb>HaTF zXZM0(&zF1OFu&Xfhxz56xYpf|)_(V+VR76yhs8Ia0Xz4L=bk$(ANST_dAiRI^UFPV zm|v}{xBYY|4t0kbQsV;t1ul01WKYheWH}TWcx#=vQ^p|J8$bbIM z{=vHD9?9x8{~;aBf57xH{{hp@{0B@=^B*vs&40lBdez(qiuq;!1LoJS&3&M)oBz;$ z^B=G{=09NZ&40koHU9z2$NUG(FY_NTzs!HY{Ayjj?WaR==u`ad^Xs|vEFU_TC;iKx zFV)4b>b0H@_NR|H=_Y=9Iyar=lm7BFmqRV`H~*o!+_zi3?%Tz5aGx)xk9&SG-Q53+ z>FGXMOlSAZVt%ci(RN-M5Ryaepxu-+Tt_T=yMg`M3ue%hUbH zm|yNq#{6nsz3rz%ap+Tgx^*r+%ZJY8N&oWaOLg(9dab8}{pll4x{05j&P`|eq`y4# zMgHbLRF`|ntJl5cm=5ke$MkU@I;PvaPi&c7Qus?moNjLG+)4Ay^pY)e!zR2JFhw7U5VV-*DeVEI1nD=2W(`Vj? zxlFftALcSW=Y5#Vbe{KNE_=S_eVEJqnsb)+?R$vwz-)xh&4S4|7?3^BLsn z+<717vV7)!n9K5<_hBycYu-1z%&*qf+kQF}XZ!gYpKhH?&+?&jdD6f9`BGi{s$T2q zV1N3ElWyXtr*qR;KIt#de38HT5BW9kb3XOX`<$2QFz<6-rq8_3d6{nWKIdh6&ikB~ z={)aqUgp=l&v}_&^FHTge$D%w&-%R2`Rt$fIWLPd?{i)j-+YGrn)f*`%V*x_ye!Xo zpYt-m=6&hQ{Ayjj?WaR==u>>UbuK;2htB0m|MKTcb@8iut*3+i=_5|MiJzX%O=tO} zzdZ9r{^mdA*L;rP)H|OeSf;~#j$oNS^ErZLe$D3ymgza4BUq;Me2!q5U-LPFWq!@) z2$uOZpCdTy^EraEe?CXBEY5t6U|IY}KjX#A&YjN@EX!v;N3bl<`5eJAzvgov%lv9x zz3rz%ap+Tgx^*r+%ZJY8N&oWaOLg(9dab8}{pll4x{05j&P`|eq`y4#MgHbL# zb7A#<-Wxyn=o$)w+7yPlw{rr}%X1TzZxdoy(K{<!0!4&-#6@_-$wZ-}-ltTo&g8fBs{a#ee!|e9W?Q|Eo{`Ez9zG z*jIn_GQXbj8!s&X`P|~J^Q(3Bwx15gp-=JY*17a7A3B#O{mY*(^Yika#jonMo(}e> zk2vWjetJ4Lo#m7M^2`_coBxns-}ZzHtM|9u|MR;}hi`bxKVPQLe9m;4ZcqH(KeJ5F zfA9zY=`x)k`H25(nO`6OT|d5jdA{Dc%&#YZn ze1@K{|MPioU6#-9`^C2`%kzhS{mskrpU(v^^Q(3Bwx15gp-=JY*17a7A3B#O{mcLI zd|m3|SM^#?2m8}UoOBaEJ)N7*@=1Sr=8OEzf5@+w+<#&9zW57YaCG>*Klzo*^qJ3b zFZ1hrKJ$6Y^!yhu{DNgVzvMsqyk&m<^(Xw18izx%sST9(g0`H?3s^Xr}O{)A=u&*$!!`PI65+fRq$(5Lux>s)%4 z51q@C{^fu1>zR8NzpB@II@q5+;-s7S>FL~bmQVW2GhgIy{zHC!!5bd8tlkIy@S~RL z@QJ@W%12tut%RvK5xeInLL-}Ir%Tkf9hK1SL^C+KOKrgpW@T4bLm+= zbS_W&mp@YYAZro;5% zGJU2Gm-qR4*QYMibNX^q)RlzCK^e{F**I>(hs4|McPVK3|{tyk+stXUMPV z!)5tQA1=#t`fyqP^SZIDuGZDtemWF~KE>bX>v}Fd%ZJY8N&oV{K3{tlzpB@II@q5+ z`+Qw>6F)tjo6hn{e|gU9!^W4t`49Ouuk*|5o!9wgI?U_*GJWQCetG}@`VW6^nV$1H zzf9+OonPkHyv{FQ|NmO%*SyZ3^?98?`{#9jS)6&DUl!kdhWwh>`DOXc>-@4j=XHKr z{`3FxGQV0^Z~N&`9QqWWZkk6Px} zd>^&UulYXetk3sRXa9U3wJgqjAGIvL`3(6r-$yOWXTFbGmgjsQwJiVnzIT~lt*f{F zbSMseich!B-TuGkL+A3OfBEyJy7*PS*3-fM^bsfB#7|G>rn7v~U!M6QfAb&mYkp2S z_0G>J%XFBZQevP|dsIc1q&^K;7b_4RO>U-NUyS)ZR%&i?s1 zWm%m0Ib~UV^BMAMeok4I&-|RSEYJBlWtm^|bLBF>T32uT=};W{6rXOLOV9G5b9vIg z{4dYfGxschRj>7Qus?moNjLG+)4Ay^pY)e!zR2JFhx{^U0IS#h0Za#T2{3);_W;ZM zGRMF=J3zjpjG4*~PboCM4-^AlP(SE2ppEnsox_W;Y{o6lg~x#l)t`IzUh zUpsl4^MK`V{sZP$>*{Sk9g0Jr;?u2j=~+H>E>HTGKVPbgU)5_p9qdmZaneov^mJ}I z%P0NinJ@A;|Dn3f8K_?K2Qa_PCBXDCuK?4{90N>G^9?Ya%{{=LFY^%a<@NB@%ltAw zp>=Z=+Hc+h7RMY0EWY^+*tzC5VELHmfaPh<1Ll|c513!AtGE4hC=Pv!Pq)scXZg^% zJn3KleEB=S=~4^7s@Hlt*q=V)q?`EZ>D+XdPx{L}5L4@3EKZ zV_tzhbTh{Q)6;wdOlNZsFu%-0!2Ftjm-%IWLhI%#wBNi1ERH!0SbXytuyg14*vs;n z-(xS!)0_u;_+|bB=2z?LZ9g4~L!aW)t#j#FK6EZm`jG^9?YaADsCQm|x~0;LHDC z?_B1W`3bF?tI&S)7O*(;ccNwS&1bOgTyq<+e9Uv$ubn*2dBFTK{{i!>b@jHN4#lBQ z@#)sN^ei7bmnZ$ppD*S=IE!D^Ydsz8Pakp8P5kt9ZaT{+{pFc2@;CpXy384>|A3uq zZUdH&c@9{f<~(42ng4+K)w+7yPlw`cKVRe1t#j#FK6EZm`j4otw_`Nq>3fi~P-hP~+A$a|Wu{{DE|s z_Yp1A$GigTbTh{Q)6;wd%rA2f_G`y4^AIq<%t^rfGC!epa~0Ze-U1fK90n}D`3%^( z<~CsYnCF1`WzGZUm-!D^U9GFP{d6b}eTq-F&ZTGh(78P6U;cclE`C+7^>na5eZ)yO z@zc|}=`5f0m#6s;YLUPB57lMPK=qnGfazc^0j7_61(FL~bmQVW2GhgIy{==zj<_uJ?`2&~^ z<`Q7~m{)-5W{v@-r}+k$U-LfLWqz55V4W}KBw&7-pU}Fw3fO-07O*(xKVb3AXTZ)i zw*kw?JO?aKa~?3i%zwcAYF)kUr$ce*Q~d4o>$&tSA3B#O{mY*()y1#swVn?4r;j-4 zCVqN4H=X5^{_-^cK`rt(|Dn3f8K_?K2QVGXCBXD~&dh(nbTh{Q)6;wdOlNZsF#XL# z!2B{N0rSiJgx1YfXuo+2Se$vE`Lg)tGgx=7xeZu8<~i)wPM+pGV1AkZfce$BdfQKj z;?Sq~+vnGF=~+H>E>HTGKVPbgU)5_p9qdmZaneov^mJ}I%P0NinJ@A;|Dn3f8K_?K z2Qa^$HS-@ZeatJsbTh{Q)6;wdOlNZsFu%-0!2B{N0rSiJgx1YfXuo+2SR8X0u=wUP zVCS0KfaPPJ1D5B*XZ{1`m-!EvU#+XR{d6b}eTq-F&ZTGh(78P6U;cclE`C+7^>na5 zeZ)yO@zc|}=`5f0muJ4n-~5MD*UTBHUh@Yq9n2-b^qJ2|Ez@m2C$&sZ^9}5wv$+TR zwd2=(PHLH7<|J6>*L+UutedOQe)ATJWBvmc-+Tt_Tyq<+eCBgf%knhm!8*Upf57}| zUA^t6LviR+{O$AWx%4a_I+rK?%bzdR#jonMo(}e>k2vWjetJ4Lo#m7M@-+WJE%G=2 zp}Nc&s9y62FdfV#!1OV%0MpGJ158iz4KTmVJ;0tX^AIq<%t^rfn$IDgb#oQkZ{7kH z#~cPMzWEH;x#l)t`IzT`om|v}{xBYY|4t0kbQsV;t1 zul01WKYheWH}TWcx#=vQ^p|J8$lv^jQ`gKHs9y62FdfV#!1OV%0MqUJX8r@Fr}+k$ z&gLFqewl}W`DIQ5=9l>it(&XRe)ATvIOacK@!vP|AFy-HZNTz*VCFwyd7ATp`DOkC z=2z?LZ9g4~L!aVrpI^_VXZg^%Jn3Kle5o#eRj>7Qus?moNjLG+)4Ay^pY)ff`44K5 zzxfZT)U@ifsk9h@{Zsr(ZdYW&5>1^%+=9hU0m|x~3V1AjO(E5Ci{_Hnz z!MZr+Fktb`XTZ)iw*kw?JO?aKa~?3i%zwcAYF)kUr$ce*Q+&F0Ecm3M;-~THw`OlXh_R8OI=eIrccP)R*`#$W>fALFCS^nu? z{_s2V|Mc-R_wlzVoObyYTe(ov-+Y*I&N&#V@+^U7!7i<#`tF{Lv@BaoKE; z_x|SZIqQGr-&}Z}kvq?R$M^2KIA8zj|7ltLpL)*!yzJcn?cZNmKA-&6e{V4x!{fVQ)^S=JV^!Z1F4>@?ZX$W%>NYU;K(?e*O6Oe&w?KU-`J_FRSaRPrtBwTc<<&=~EoK z6`!7+OXu>Te|hqy{P|T~)~nb4bPy+f#7{Tprl)+;S)S=H|9nx`=e+5c_q9>IZ}_lZ zS*F7${_=(C^MhahZ+4w-uYb|MU8d*9y#GDRbbi6Vdhg|H$FEO#?E9Db^6)?OA*&(3 z=69*f)?fb6hb?=)KI9ued|8~&`S_1m7XM-2@sZ2U{kuPX-?Dsu;AbDUEYA=8wU1hs z|BpQK;mhj!Q+F<`-qz{Re)<%LZpEi(=hC@+=wF_EDSv)dm-XtkKOMwLAMw-8x#=mN zbe3oO%RgVHFV5?s*)=_PX1Vk{n&r}SYL-jS?|ct-o@=vQdfw-Iw(~k*mP@Y>^F7{q z-LT&4iT%CKh|}w#_`M!Fx7S1Y^m-`IUf<;3>!G@OJ)H0H&bpa4?KkVDIP*Q;iElPe z=bD*QK4$5Zrx`otZ}v{F^VX}^{$3BoNgwfhJ#=n*$|s%Wnf~(67j^Y|sNSACI`ll! zr{|PzJ-_tqxu$c^JNgx4Sy{*%s{q!jg-HK1o&ZTqt(7!zSQvUp^F6-56e>#YhKH{gFbJJ5k=`7Fmmw&#f ztJg#I_T15-=aD`=r*!N2rDxAIoqOKt-|GNhdVSzmuN&5TJ+Z&n8F7035x>_Z=k|If zpI*o0+3TD9d)-r4uZQYwoeu4%PjTp0e0p{+oy&**<;j=w=T~)EuU`ApL7emvKi!<0 zp7Kd&d8WVo^Tn*BzCWCw@y~N-R#MNSSxG&oW+nCfnw8XZZB|mxyID!S4w#kH>x0== z=XGP&dp)tg*BNno{Sm*{CFk~fD4$-(Te|hqy{P|T~)~nb4bPy+f#7{Tprl)+;S)S=H|9nwb zuZQaGxuZkRBYk>K>DKd0&z@^K_q@};*8zU@`oORAx-sj$p4i{(j5xjih~Mjyb9=p# zPp@P0?Db9lz3!>2*F*KTPKWl>r#N&gK0P~^&gDb@^5jeT^Q*e7SFio)AWr&-pKi`g zPx+*?JkwwP`C=AXuZQzH>hs*0Mb`6Z7Fo}!S!6xGW|8$=n?=_1KEE?RuLEY0_4;6T zT(29}dp)tg*BNno{Sm*{CFk~fC7)i$YAeqCj{U@+ z-?5)_&3r2#v*60pjJWbQJFdE{SFioO9*UDb;-{N)(^Ed_EYI|pf3Jt?>h(~)J$H2I zd8ALzDcyR0>DhBl=bm@^_d39rULW|?>xT7SPwek?Mx0)M#P4;!EsEr$hVcQyjV#pPrpd=klR{dGe+F`Bh!ktJnT?5GQ@aPdDeLr+m^`p6M_D zd{I}ghwAOQqeIUleR@vm*7Hlxo@+Yyywkte0lxJ5z^`66toM3if3Gv*^!g)yuS?GD z^-4ayj>)svH~IIvr>|8pR5Bat$F_NRk5=_7u+ zIX6A!lg{!?fBEOj{0{QG9-8&nb7$6H&!bs?J*Q^<_57Ok*K=*wU(dT)f4vUO--6HU zgV~Jdbz|0hJ+Z&n8F7035x>_%=k|IipI*o0+3TD9dp%TFuZLzEwr=KO`^`cuj@gXG zH#@O&=WoO(AF~$A(+tM)H=D7#toM3oe>#YhKH{gFbJJ5k=`7Fmmw&#ftLIC-`ACQS zrBA-ot$v_qeM0B@hyL{yzv?%Boj#oP`qTdUR-F1-{QBIv^}l?2F67zsBLAKvb@hCy zw{<$SpFYK*Tk+}HxpXcc`j;nP%Aa4=WxaasPX}?*NBneiZhFcmo#mPS^3NBu8T)?2 zY{q;vn=yaQX3Y2Re$!J9|Cr5KUzyEVznP_3A6lG=}BK6h^Y zFQ1+ZdG@@>zvoC@Jzr)~wr)mc`^~N_j#-+;pZCn1bIrgkAG0yb)6C5BH%qg+tXHr7 z=^#$}h@WoG?fH^VI?FTt<)1I=>iJS{KGGq7>67nts~_lDpU}Dfp?`hFm->xg^`Z6p z)BgHaocdY(`rNtozkGTwDKD1tc+F##_Q$LH}^X1(7Up_q-^6Yt$f6tM+dcMpKZT;<^{DiaLtkL3_ zL0WvXNjulf((*COv^>o?Eq}95tIK-z+Mf>Mq>uRN=G^p@Pddvp{pFu8>gxGYZ$8o? zf9aF&bgLieS)b6k{-J+;#h3bxU-hB&`qTdUR-F1-{QBIv^}l?2F67zsBLAKvb@hCy zw{<$SpFYK*Tk+}HxpXcc`j;nP%Aa4=WxaasPX}?*NBneiZhFcmo#mPS^3RufFTi=e z%s$OWvrqHa?9+TV`?P*A`?NkW`?UTs`?S6?`?P*DtM>Hatk<9R*SF%-&*InT&aMCD z({mxuo-g_L9I314Yu;0R*3E!zzuBa{-| z#7Q6V)6Kc*DW7zfXZp)OU)0s}rQUp`L;lhy-|1FA(6c_FbNxgA`ifum8^2B;&U*c6 ze|;-X{VaZc?%eucK0O!m?0J!Y&yl)%zSP?~9okQy;?S-5^z2+Zmk<5RlP~4Zuj;a1 zz4oVrIO!vPx;ZyJ<&)0xOn>?3i&?e(|7BKfKAKgVzh>3uyIHmMgITrpiCMMvk6E?# zm07j*o7uwkq4oOH{`yv&`dR$?+`09?e0nbA+4Ca*o-cLve3{MLx|zN0H_Nv;X8ac4 z?BCA);-7r@$;YhV@-#!Z{LL1wF6-56e>#YhKH{gFbJJ5k=`7Fmmw&#ftLIC-`ACQS zrBA-ot$v_qeM0B@hyL{yU+Oo0)rZ#WPy6dzaq4IB>vQMU|MKa%kY~?}{Cken)$^s^ z*6GlG`V@z5#iwWI(z$%-U!Hs^e|}Y$_3E`h9mGi=@zc$@=_#LdmS_6QKVRmY^L))` z){c*63+J!d!uf8taQ$GmaD8I7aQ$PpaD8RAaQ!x)x%*%r&U*c6e|;-X&zJc1xpV7( z`Se`Kv*$(rJxA*5`I^t%opm#o+i&)Aam<1)zFEzkYld_AnC)DiW(^?a!}AL)?4^vQR+)erQnPv~6#(7(RoSN+DX(}%NO zf7)N)ic>#}U!Oa-{+CbBg*_(0cu8e|;-X{VaZc?%eucK0O!m?0J!Y&zHJ-zRbRE-AwHEo0VN0 zGqj6uwsz;5xm`YHahInV-Q{m~cXe5>Ui;HQob(Yt-JF}A@=0fTroa62MO{5#>di+w zeQc6a`o-JS1dch?VQch@Ioch^5=ch^^Dch_%bt=EUv>reaZTXE`V@#}Nv*8lS9 zxsYeii~M_z)YbE4R(b0W&aCzJn{8ekGtY}}7JBEJkzPJ#rg8|NdUaW^Ui;HQ zob(Yt-JF}A@=0fTroa62MO{5#>di+wzvoC@Jzr+aw{GTq`^};+jv4jE zHygimXGYD*XJ*u#Jl{LB@yp+A{OYn^z4rHfiPQ5Xe!4j~J>`?m@=SmE=Zm^}zSNtK zbjV-&W zU+Qh04(+E;ap+cjdUh_I%ZL8u$(QoyS9MvhUi;HQob(Yt-JF}A@=0fTroa62WoBEQ z=gVyTd^8(Bf1fsY2jsii`1OO?`1Og|`1Oz3`1O_9`1PB+4C+Jc^{4$kU*hz9iC>>P zxBiz;&xJgDUgY0%q^_PXcLB8Sj)3;NJD@o36ezyC20GUr1m)vyg7S1{LHWDOpt`JA zul?yDPWp(SZq7|l`J}Tv(_jAiqOP7V_2wfT@|QmOPPh7jp7jZx>mT~pSA418_*EZT zuRratZ^fyf#jnquTmQ?a=R%%6FY@m>QdiHHdRwPM`{`30x)qtPkh!(Pd~WJpgwVz zLH*+{gZj!{2KAe}C+b7%^{4&ytvL0w`1QGS>wo$5T*$NMMgBcU>gxG&cSGy$bZEc3 z9*Xl5-}JR7{-dAq;&ZM$Bg)5J66NWRiSl>%M0HuOUi;HQob(Yt-JIL=C7*PbXZp)O zU)0s}rQUp`L;lhy-|1FA(6c_FbNxgA`id|08^7v9>-DGo^{qJdv-tJ7bL)Tk^jyfZ z=SBWKN9yYNQg7>YXg__5L$~77vvcWOKJ+h7zLY<|s>^!y+Mf>Mq>uRN=G^p@Pddvp z{pFu8^S-b1e7SofAKg8XzwVyMcXv!?&zEz1zU0$$ADtLN)W=B|*|-NDg*cXJfSogKw@mq+Kia{-|#7Q6V)6Kc*DW7zfXZruYRNZ^9H&#{N@sUdJ12qX$fsi;+i_ z`^(-&Y22GB&G(i{e!Q`g|A)=nF0JcLmhgD1C7j-H3BR{pipzNMnja7R#1H@RX5ILN zC!XPqfB4IbxT-JlmPb64U;LDJyrlR&(_6rc<>)ic?rLK6_@eiH9sEsi68#s&ARak zPdvjJ|L~WW`Mu4>oe#b3QXakSQhvSdQr_q8{fpCsw_VbSw_VbYw_Vbew_Vbkw|LT_ z@$_kay5%Q5^PkSGoBrXcF5s+Q;IEFvRegEOrg3lFG~e4d`SB)B{=Jpcy57(UkGFNg z>CK(+dyA*Ij2Ex@@xV{~@E>p1jZb*u8P52Jzr2X6`Vwz>#6$VTPkF~%dcbEo!E^e- zf4Y*F^d?{F(0KYZKi%?^p7~Gb)=mHLR2OhoFYs4K;;O#H+c+MYkDvVDE&upzT|9>e z|KXIE@XJ?m882S*6V}L%zrw!Zu*C(x`4BKfxkKu zSM?>{#_`a6{Nx93`NwDL;yFC{52w6@U%raVc=4Ja5B$Ur|M6zs_=G2(;f#Oy%ggH? z@qI6=e|bBpJbF8+{CYd7yn8z-J$O4Qop?Jb{dhYmU3ohxy?N^@9U4!c=BHbJ(lh_* z+`8!>p6UY5>IMGl>xI`|_Oj~BTTzXBL#p}SmdcMer}FPDs@C;JRd~Ez6;5wjh2L9O zXX3h{c+HOoe&UD!c(ZPN!V}MM#y|Y!MZT&p@s>wClwbUmcf6$se5MmTryu;MD|tz8 z@|6yar%&_KEkEg*|8#EM^bb#U0cZ6Be|02Z)t7i1$3ye+lOMe0AD^v@=kVY^obnZZ z`8pHV4aIAIJn$1g{KuPh;}f2EhBN-*FE6uioU6X3?#`9RsmF8Wck1+9d7t_{mma3B z&!v;8_jBoI_JMQhYW9b7>CM|@>CkxkG(X+)lb-oc=hjXC@KhIYRxj{ZN8+l!W}n>g z**|yw?5pc%_S^M8`|z$i`}5+NeS2}ve!lpk;3t0gk2mYaCp_^CXZ*uo zUc^;>iMKrBq5R^fyyGoB;4_`zIsM>2UCB#&ldp7WJbjvi{HJs4rhj;<3plG6 z_^TsvRbS$591qRMPk!*0e|)wsp2LIxaLP;g<*T@i7q9v8z)$?}A8*!;Pk7=P&iIGF zyv(_G>ub)9o5wj%Zhq&Sxp|-S=jvh3rK^)UudaUP9J{)j^X=-*TXN~pc=cs|^~F#1 z#eel>-RcXT>I=^53;y%<^_H!#Ip^>Aod0+J{JUWN%)b}b|NJ{**PVY~ES~vy$KsrS zk1T#~$rYFJ>dXA{O9ZIEn8pWEsuC8zxXNdcuNoXOec6w zKlo2q@{-=D;>MAD-$0&gupJ>WB`jFYz{xhvwraKX}VOK3f;h z;lY16f=Jz%y^{@H8$4Pmd--n!(-}ybs zNqL{&pPZzJ`Mt_XI+@?MoTQ)mJr9&7QM@eF7D!(U#+RsRxidBj8c#ZP(1TYA7}I>B@L!GF4vm-HrI>Ckxk zG(X+)lb-oc=hjXC@KhIYRxj{ZN8+l!#M?L?nvb9S;4T07Y+XEu2mj%em+;G1aTzaO z^W%Y^_~Ad^tQ(*3#50`n4}W=?zP$DIgn8?*JkIa)H^1|H{>}UR{(to_e-~Jt%-;)E zKl68l)z$ocVfE&%#&l@B`ZB-z;-~uJzxuLn^#xD$1!wgIfAuA<>TCYavg7mjmz_U< zmsvma_nP%Tf5+K%=kGgG+up~ zUw!dYeeqv?S-1Lvr}~1k`hvgu5?A##pA*>e`TW4npU)MnpZUDO`k&7s?7H*$gvB$T zTUea)d4|RBZO!5`UVWKgeeqL$@n3yexB7yo`hv6ig1`C_SM?>{@`#7>i=Xn2xAcI| zbb{yfga33TFX>Ib(xLJ6X@0upCq46@&aIpN;i)d*tX|-+j>J`ciMMe)G#@|t!CU_E z*}8ZR5B|d`FX5N3;xb;m=Enm+@xy<-SvNl6iDx+DAO7<4D|fkW>uWwYwRxP+Q*D0d zb5@)8`TW)DVLq3&I+@RFt$yZnT&t`3eAnvDTd3*Kc=cs|^~F#1#eel>-RcXT>I=^5 z3;ya$T-Dcn&TYr%^KUzUJ{Pxs=JRsve?CXI>(1xv7SDX{ZgI}%@fN?gP>aiW^<{qb z#ZUFcfAwYE>I5?A#l-p29JeEj4GZ~4b(>*6^)_z$PNgkQdj%Xsmc z9}oP*5C8FI-S~tjp5cst_{+$r@akbcSG+oz&l|6P z=5xras}J7sm8&;z*QP_`)tC9z7eCb(|J9dut1oz}FF30&_^U5*RbTTt?H!-bZ}0s1 zT=)8!&wH=``5gGJJD(3H^N{ z1^((tT-BF&8^=TQ@sl6C-{P|we`kC)5t^fHR)2=(;Z(2O_ zy{E-F--lZK-Wo10)fYe27ys3lb*nFUsxLUJFZio3aaCX9EsuC8zxXNdcuNoX zOec6wKlo2q@{-=D;>MAD-$0&gupJ>PTGGmv|e;L-X;IAH3xs zpRJ4M@Zdk3@)CaeDlX&2YkoZN6F>aNn|0$8o_K~c{^2h#^S#lnule5P=5fA{x%r*% zX>Q)<`H^N{1^((tT-BF&8^=TQ@sl6C23T7KuAfz$Fn_Ya(=hq;&FG@ZWlyC%evJUJk=MR)ffELm$<60x#wZW=l+MC zKlehcpSdq${m(rTyYAdCaT=bvcj7dh-s}$l+*5H{eHpL5%&)%qslND+H|xeHJn;-? z{KH>f#8rKXw>;vZ{Nks)<1IblGo9c${op@c$xC{ZuXJcUeVU(c`AN_Gr*rG3e|V}3 zII9=pbDz@U_x5^m8Lz&~ufF)HzWA@ctXqA-Q+>f%eZgOSiL3e&Z+XN+`NdCp$6I>9 zXF9=i`oVv?lCSh8U#r6zPoL(eTYl0r|LNSi=^viz0?z6M{_03v)t7i1$3ye+lOMe0 zAD^v@=kVY^obnQW`6@2s#cO^%@Do4$$D4KI6P|d6GydT(FY|Z3t*^PaZSy$yxov*u zp0~~W-2b+En0w(?Cv#ui>SykeTV2ila;vwwcW!lPy!tY~`r@bh;=lT`ZuJFE^#y13 z1%LG=uIg*<+1v5Ce{bi{y?pEEb6$0i^*{Ic?YeWn-{P5j{}$)m6S(;2p1_UEc=cs| z^~F#1#eel>-RcXT>I=^53;ya$T-BF&%Of7jFMi59-qHg;(+Qr_5B}4YyrehzN{7bN zr}^oYpY+UsI=626ho`!LvwDHQIucj)CEmvI(0u&l2XFbuXY1lQJopc%yo6uAipzNM znja7R#1H@RX5ILNC!XPqfB4JG+?%@fHTRBg9_K#N&F|b(x_O`bOIHtbuj%S!?mJ!m z%sr^9tGOR_^)~mWp4Z`wS6}8=U;I>G{8wMrt-j!?zTm9B;IF>KRejApu{%EZ$L{>O zS9bl(eY5L-?xEdv=YHD7Gxydm&biNa@y|WC8<+9w%lzt#pX!VM>dU&-7d+J$oYfcn z)t9)cFY%T~Jd|Jjly|(P2YjXzJf|Q0rz`nNZ}PP|obmK&e!Ar+J@cQ=t(*SgsV?BG zUf{2e#8rKXw{bi)A3yoQTmJFcx_Ax`{=+FR;g_%CGG4sq#{)m{!+*S4H$LHsXE@^@ z{_-;Ses6uvz1f?`xleoZJNImF-sk@9)x+G&y*ioux>rAQkN4_o?)P53&As2NL*vz# z`PCOc)ffNOmvyTzc&aZrt1tMgFL700bIx*;lV_*DpPy5DYy!tY~`r@bh;=lT`ZuJFE^#y131%LG=uIfv?*T|2mk3xUecRUcxV5#bvyB&5s9u;)nluvu=FC6VGtQKm6ro-mTdBns*;IkMkbH=6BwS z*u2mC5vzxJS7LQC?@g?J<{gUF)x1x!dYgAER)@x`FY~J}eyT72t1s(TU+`34a8_UN zS6||)zUG~d9iR6*cK*EUv3};gkM%$Afb6>SKFH#kcS9EEou2oQ#Xs+iY+S~xFY~J} zeyT72t1s(TU+`34a8_UNS6||)zQkJ|@lby8Q{M5G9`Kn?@SJ||pRVL3y~$TPG@d@q zPq+M}Xa3WmkO{PI;?#*5ed zc;F{~_>VX1#wR@S3}^hqUtZ>OUt3@EZqep(-ZR?#&O1k&_j&(l^)T-utxo2>q}9*7 zqqMr3_mx&}^X}4l9nN_5Wq$R=PxZxr^<~}a3!dr=&gu*P>PuYJ*Ss^ef%eZgOS ziL3Y8#M`@Ic<8+_{Pd0(-g;jQpS?SV=iVd3fA5sZSMQg}*O_y*BYSj)&&sCqH=0KR#O*&*8y;IOQe$@>N{Mi`V>k z;3t0gk2mYaCp_^CXZ*uoUc}XYDBkK057i@ns#CmGzxb@K@m#&*zkNWy+8^X=_l+5E zKQX_3hM)Ey{@a(V+kOR4`xu<d6(|*W*`=NE)58-J)gtPq+{`Nz0wI4q4 z8Q-+y^FHa$pLa{w&%9^4{^y<3U3cC;T|DzH>f)StR2Toeqq=b!Z$C7@{g9vbL;l+j zt=oPGPx~R9?T7HUABwB}P`uS09;!$DRHt~We(_mde|KXIE@XJ?m882S* z9U@?KAwe|M1_wWZm{Fc-qI{Y=48leNSBNhvID<56#C}(r+BM=@mXEtxq8Qc`+$74 zKgiea8#CU1Vt)G!KkYyKw=Y?@{R*D;F*w`b;BVg(SNoxO8^=TQ@sl6Ct)>%auF-`fqyj`uWY*K6(9LbjPc9-OC?&)#7=^ zQ?FW_w_JPG;{W5Hx@zMx-hOC)`yoH=hy1r6TDScWp7ujH+YjMyKNMH{p?Ir1JXDYP zsZQ}${o=E_#&h+K|MmfSX@8Kf_6_6hC+4@$@YDXofBTYk+ppkhAA_^~4gU5$akU?c zw{bi)A3yoQTmJFcx_Ax`{=+FR;g_%CGG4sq#{)m{!+*S4H$LHsXE@^@{_-NO_CxVj zcX+5C@l&1Rt@_1hb&coh9slhE^3whwU+o*l+fU4IpW&zdhyV5^>$YFP(>?}g`y2f2 zd*W(86mR2rXg+@OgSY(Svvu(t9{h(>UcxV5#bvyB&5s9u;)nluvu=FC6VGtQKm6ro z);XQOogdxn7k}pT;>X;2a?$ZU4)!&_ddtb&tlYnja7R#1H@RX5ILNC!XPqfB4JGEzf`2__^_DK96-e_VF2e z@_60Fjc3p2W{>38_!V#az!5*}PrmH$j`;uZ{9BK#%l@e6eZ(<5>>vHmZI9t(|Izzz zKWly2!9Mwxk31Ha@eBUd9gfAze(!Vca4f%#DzYxLx24D*3W%!bJJ1&Kk0#QIBMNzKJqt?!gJ%L zzjhSP`~S?1N8!hDaTzaO^W%Y^_~Ad^tQ(*3#50`n4}W=?edgHbfyFp=daMt!r+$z1 zNA}e9vA)TkdOy}r*|QHE>$B|HACC23_Us$S`Z9a=lVkmwJ^Re@{C~%tPnz$1!sf^M zgw4P63ER5PCv13}PuOrepRnO~K4FW?`Gh_D>Wv{hBRb`gr5|d-L^u zHb2e-Z2p}S*w%G^V8i2F!G_a$gDqdqA#8CupRmQ-I3AjhpZwr0|M+ZOJckGW;gpx~ z%U5w3FJANGfuH!{Ki;expYX&pobeBTc^O^oemMV*+q#>7-)%k4zx%dM=ih@{zaP5b z(yiH^LvBEKfgEFxQw?Sn%{oNPx~SN z?T6NFKZK|K5YF~P_}dS~)qW`6>JAUpBYvt=yj8#Wtgi7~z2m=qKwjD(9U@ z?KAwe|M1_wWZm{Fc-qI{Y=48leNSBNhvID<56#C}(r+BM=@mXEtxq8Qc`+&T(Kgd`6 zhVk|j^V?_mY5(EBeaX7*SMaot!P))>fBT-e+7HFsI3AjhpZwr0|M+ZOJckGW;gpx~ z%U5w3FJANGfuH!{Ki;expYX&pobeBTd6~ac?0z`E=ij=U-~Vqt&ff*LPUr6hTfg&n zgstoO`@+`y{M}*qf%$vH?ho^Kiu3!%jJF?}-+stX`yv1Bht_RBgs1%w&h|t2+YiOn zemH-Z+41>%&CZ{{CjpL#D_{k66@{iBf#dCP@A5M7*zkC&! z@!~Z<9{7nL{^QNM@d-~n!x{hZmltuhABwlS!$b9mpXwBE)h|A)Ydlx)_-`MOul5J| z+I?fj+fU4IpW&zdhyV5^>$YFP(>?}g`y2f2d*W(86mR2rXg+@OgSY(Svvu(t9{h(> zUcxV5#bvyB&5s9u;)nluvu=FC6VGtQKm6roKF6~A;d~Bc>ux?Dvh_Hh8`(OY&y#HZ z&gV?FuIKY7TkrF^l-&pB^D4VP%;#8k-!R^OXny-4KkbM7w;x)!{Scn^Lpa+H;cq__ zSNq|7ZfD2m^E^9$KIgN3=JP-6e?Awq>(1we7SDW+XmQTxju!uX?r7sO-hOC)`yoH= zhy1r6TDScWp7ujH+YjMyKNMH{p?Ir1JXDYPsZQ}${o=E_#&h+K|MmfSX@8Kf_6_6h zC+4@$@YDXofBTYk+ppkhAA_^~4gU5$akU?cw{bi)A3yoQTmJFcx_Ax`{=+FR;g_%C zGG4sq#{)m{!+*S4H$LHsXE@^@{_-NO_CxVjcX+5C@l&1Rt@_1hb&coh9slhE^3whw zU+o*l+fU4IpW&zdhyV5^>$YFP(>?}g`y2f2d*W(86mR2rXg+@OgSY(Svvu(t9{h(> zUcxV5#bvyB&5s9u;)nluvu=FC6VGtQKm6roeh0bx;e1Yb>ux?jy!AMrE8aSt&l_+3 z&gYP~uIKZ~TkrF^<=qG7^US+H%;%iX?;A7TerSICAwTVh{I?%kxBU>F_Cq+^58-b= z6j%Ge?AAke&+Mx>wi8szU$8C$rsOj&U|ss=g$}ad@g?hcli& z%}=-dq-XxqxpmV&Jk&7QM@eF7D!(U$JdpcWR^F5c%<9z>R^E=;**}T8()fcTE=6f`&llgwl z>Sw-pv$~q^)fYe27ys3lb*nFUsxLUJFZio3aaCXQy`&wV?-RcXT>I=^5 z3;ya$T-BF&%Of7jFMi59-qHg;(+Qr_5B}4YyrehzN{7bNr}^oYpY+UsI=626ho`!L zvwDHQIucj)CEmvI(0u&l2XFbuXY1lQJopc%yo6uAipzNMnja7R#1H@RX5ILNC!XPq zfB4JGe9v_2Yrdzsd7STWZhq%`otyXhzUS&;z6ZKGneT_Le&&0ltE>4w>FRC1XSzBx zUVWKgeeqL$@n3yexB7yo`hv6ig1`C_SM@dDtKIQ8eC~aB{(KL2{ml1s*Z+KPch{Zo z^DdtGp6}wE?*%XZ`CjnGWxV<_zxv{*`r^O(vTpSSPxS?7^#yC^ml%TIddKb>1Q{limTz*)V(Umc07`Vw#BcxXO; z@`JbhelY#!(S zfz9vSOR#yL`wCVM*Wcz-Rwr}6!Rlx3Jy>1MeF&?!xhLVg4rjdjGQaxbr~2Z*`m%2I z1yA(_XY~bt^(C(AYwm^E@wqQz=g&P7>u2tlSpReH#I8H{Q7oRhr($u={S}LU?zPys zj8|XgS6}>8U;I~J)~&waslMQ>zTmIE#8rKXw>;vZ{Nks)<1IblGo9c${op@c$ya)l zuhrpPx(h>uc`G**wnuIh)_PS7-A+_wB46<{qBa z$=uJg`k8xsR#$VM&+2XN`B@zrufEK$zWAxW_^-aKTYbS(eZg6M!C!retNNOIjdpzQ zJKFhk57PRX`;pfF+?%xPe#h_MY4OZGON(>vWm^1mFVn_ly!tY~`r@bh;=lT`ZuJFE z^#y131%LG=uIfv?*T|2mk3xUecRUcxV5#bvyB&5s9u;)nluvu=FC z6VGtQKm6ro*4g@+d)_vWbN}1sckYGTyw81ctB1KqZgn#E%dLLq-nrG)+();1n|tcc z>u|=aFY~J}eyT72t1s(TU+`34a8_UNS6||)zUE%O9iRL9cK+Psw|?e+zx6-&{_VPR zAK+1V=AOW#aL)aKN8z7)1$|EB@L3V#)tC9z7eCb(|J9dut1oz}FF30&_^U5*RbS#Q zk9a7*_$lvrOAq)=CwNXj_)k~zmEPoQbvWbc)BJSHPkQD*om)5k!&6UcxV5#bvyB&5s9u;)nluvu=FC6VGtQKm6sz=PLXB z;oMVtR37L4(xdV__nID+_kaAxzdTA0a}VlKI+^=XS3h%a>gsClQ(e8yJ*%rji+}FL-MEZbU*=a|{8V53$D4KI6P|d6GydT(FXF1c#9JQmP=4`K-tm?m@R?5V zoPO}1uH+@X$yYiwo<7Y_xBR4M{?oa2(?2}b1)S9j{MC`TsxR?2j)&&sCqH=0KR#O* z&*8y;IOQe$@>N{Mi`V>k;3t0gk2mYaCp_^CXZ*uoUgnSyl#UR}+7;H$T}Cwz5iy!tY~`r@bh;=lT`ZuJFE^#y131%LG= zuIg*WB);5q%^KV8X7dXukoXgqzIpKkd{ z&-|xz>!yErstY))7x=3qaaCX9Z5$8H$4`FnmVbPp1jZb*u8P52Jzr4&l7h7NRPQ>PM-jCS)&btzu_jzw(^)T;HtWM^Aiq+4&Td}&D z_bgU#^UlTU(0KJ_e)Yvq^~HbnW!>rvp6UzE>I?qrOI+30yz8;!^WMkKpLamk&%6(^ z{^#A0U3cCSSv>R3$m0Cq9bdWl=UtMG%Xsx=e)Yvq^~HbnW!>rvp6UzE>I?qrOI+2L zc*`Rm$}fJ(JKoX*KGO-F(+~dBmAs@k`AUbz)2I3AmY?*@e>%5r`iG~wfU|mmzd90E z^(EfM@z8wyucUQ+C0wtN1NY=zUU`5@AF>L>S5kdTAj@MN~@oFcWHGs?=h|3=AEY1q4Da={OXIJ z>WlyC%evJUJk=MR)ffELm$<60d6#O(=e??(KkrzrpLySE{m;8syY9S)wRq;8ti?I+ zXD$ADS8L-kUVWKgeeqL$@n3yexB7yo`hv6ig1`C_SM?>{@`#7>i=Xn2xAcI|bb{yf zga33TFX>Ib(xLJ6X@0upCq46@&aIpN;i)d*tX|-+j>J`ciMMe)G#@|t!CU_E*}8ZR z5B|d`FX5N3;xb;m=Enm+@xy<-SvNl6iDx+DAO7+(?+k8z%{zUY$9cbR^E>bQZQeig ztDe4kn0EkIC-Xkw>Sx{!TwTq3f~&WAXK;0By!tY~`r@bh;=lT`ZuJFE^#y131%LG= zuIg*vRowA;Z*k|(JB;h+tv~#<^?#3tKXuog_Z%0`yz{s?=l#dUKkq_rT*j*}^Q$j@ zsxSVlFY8uc@Kj%LR$uT}U*f91#9JQmP=4`K-tm?m@R?5VoPO}1uH+@X$yYiwo<7Y_ zxBR4M{?oa2(?2}b1)S9j{MC`TsxR?2j)&&sCqH=0KR#O*&*8y;IOQe$@>N{Mi`V>k z;3t0gk2mYaCp_^CXZ*uoUgmROTVM0e?B;RapWXb-RcXT>I=^53;ya$T-DbTF1cjK=e^*aKko>y zpLt(+{m;9@yY9S4ym;oF;>9`d7cc&K*LdSHUVWKgeeqL$@n3yexB7yo`hv6ig1`C_ zSM?>{@`#7>i=Xn2xAcI|bb{yfga33TFX>Ib(xLJ6X@0upCq46@&aIpN;i)d*tX|-+ zj>J`ciMMe)G#@|t!CU_E*}8ZR5B|d`FX5N3;xb;m=Enm+@xy<-SvNl6iDx+DAO7+( zf7jdkns?GSkMn-|=6Bvz-@MOz>#K)(hkbQ2@3XId=H2$y)x77vdYgCNSBJ){FY~J} zeyT72t1s(TU+`34a8_UNS6||~!~H(|{pESre#hs%`sDXzR9|pbU+`C7;;O#H zTORRHe(_V@@s=L&nNIMWe(;~Jf=Jz%i z_xt%z|B2tZxIBLBo&VRx<@a?D`NNCL`~5!W?H8wq=fCP57pIdSJohITr=PnWz3bw1 zbeQ|nw_m%JVon~4*HC}z0Uw!dYeeqv?S-1Lvr}~1k`hvgu5?A&0SDapZop&|5*PwT>h)O?wjYDvGDxMKR>rPPyX?S#edl^+^}&OFJANGfuH!{ zKi;expYX&pobeBTc@bCjCEoIghw_V`@{YIkfX{S-=k$aBbR{q8O}^5h@$_kay5%Q5 z^PkSGoBrXcF5s+Q;IEFvReg!KaXd61Kl#C1{_)wmcn%N#!znM}m#^Y7UcBbV13&S@ zf4o^YKH-UHIO8Aw@-lsS>+2=={hH0=)&Js~H^1+`^0AxuSA4~Ht{$HLl}}uqeDk+| z_v+`VkGo=Zb@kDcS8t#CwkNL+jaOghS6}?3Xa1`%>sDXzR9|pbU+|x=uSaivz3Lwy zw&QQP=a=sM%YNa(>*p13`-1iVrr-VCUH5PQ`vVrw@BQli7Ux^ucb~=oz(?F?<1$`- znO}YJQ+@GYeOb5qf~Wd|v-*Pne0@E7>r1@l5f9}TKjj^7=>ebV1kdRQ|LICz(wlsx zL*wbw{B+Atdgec!TQ~i~Q(eGWy}(}`(P8x^-p29JeEj4GZ~4b(>*6^)_z$PNgkQdj z%Xsmc9}oP*5C8FI-S~tjp5cst_{+=d9`SuItAG9VPrUPs%j1uI*0(&U{Qkkce(FKx z{hxm6rU#{mx83}~2c?tWe(0SaoPHkph);NMx_az?y61z_+aKKP-Vd&S8Lz&~ufF)H zzWA@ctXqA-Q+>f%eZgOSz3|%0URM8_@n3Fy=D)W2r-?-1)PwuAkX&*Z=IpyYB4Ii)Z%j#X0-=;-7tf<1${n=Enm+@xy<- zSvNl6iDx+DAO7+puIfv?*T|2mk3xUecRUcxV5#bvyB&5s9u;)nlu zvu=FC6VGtQKm6ro&b?b-b8g%`&Ute4JLk;J`l4|6VEoy>W4^)u(#)zzGDS8sFf zT^$;)zRa(__^H15ufD8XeZfbob&II#XtW}*|>~XU*=a|{8V53S6|kxzTm08;HT1dBj8c z#ZP(1TYA7}I>B@L!GF4vm-HrI>CkxkG(X+)lb-oc=hjXC@KhIYRxj{ZM|4l|qVNTN3{C?&nz0L1!PU>IAt1t7b zFMg^o{;MzRR$uT`UvO4m@K;~rs(;PzsdjvRf3@@H_gd>`e&4nJ=l5W{?)-ji@yzed z7U%pvZSl|V*)}fY#cO^%@Do4$$D4KI6P|d6GydT(FXF0yiMKrBq5R^fyyGoB;4_`z zIsM>2UCB#&ldp7WJbjvi{HJs4rhj;<3plG6_^TsvRbS$591qRMPk!*0e|)ws zp2LIxaLP;g<*T@i7q9v8z)$?}A8*!;Pk7=P&iIGFyi8x-`g+18muw#A_xYRO`91&U zeSZJHdYHcptWM_d1*@O=JHqN}{=Tq!o4-4(4vkk|=2u_*RA2m8U)HU@;HkdgtiIr{ zzQk31&EHveeE$Bj^XKm}>u3I6v;ODrIJ@rreP{8^-+dP6{5@##&)9=-XUzf*7C=kM36hxxnq>SX@jz51EI zgRidU@8het`Mde*(0KJ_e)Yvq^~HbnW!>rvp6UzE>I?qrOI+30d`@7;=ko(Qe?C{R ze&+KA>wi9nutVyjeFs;fZHB;~)O= z@+)__ZtH74H??`3&r@xF=W|w@_xb$Q>R~>YwK|#4Yps6fb6l&d`Fz*vZ9ez4Iy7E= znO}YJQ+@GYeOb5qf~Wd|v-*O+`Vv?5HJ@|a@%jAQ&Y#c4t)Kb4-1?u-(e1kP`MSk3 zpSxR}^Lf0*KcCavxQtg{=2u_*RA2m8U)HU@;HkdgtiIr{zQk31iMKrBq5R^fyyGoB z;4_`zIsM>2UCB#&ldp7WJbjvi{HJs4rhj;<3plG6_^TsvRbS$591qRMPk!*0 ze|)wsp2LIxaLP;g<*T@i7q9v8z)$?}A8*!;Pk7=P&iIGFyv*m8x4!0cznjPTJn-gs zJ}10+pU)4k9_Dk!tCRV>@#<$jhrGJ_;2mGNdYjKJuMUk@U*=a|{8V53S6|kxzTm08 z;HH^N{1^((tT-BF&8^=TQ@sl6Cd<)gWq$R=PxZxr^<~}a3!dr=&gu*P>PuYJ*L=@t$LIS; zJAb~Hw0`FMO6z~V$F%Ft_nQ{aeD7&-&iA1f|9nqs<1$`-nO}YJQ+@GYeOb5qf~Wd| zv-*O+`Vv?5CEoIghw_V`@{YIkfX{S-=k$aBbR{q8O}^5h@$_kay5%Q5^PkSGoBrXc zF5s+Q;IEFvReg!KaXd61Kl#C1{_)wmcn%N#!znM}m#^Y7UcBbV13&S@f4o^YKH-UH zIO8Aw@-p8W-TIpEU2Y!d`G`JU$HeZIfBdYJEZu1@Cro~xhv9_Z?7z8|`Jo9~UT z4vkk|=2u_*RA2m8U)HU@;HkdgtiIr{zQk31&G%$?e7--s^XGfD>u0`iyZ+~UxV!Fr zKX>uW_jVWOe4lsm&-Z*cF5}gg`PCOc)ffNOmvyTzc&aZrt1tMgFL700;w_JOD8KkA z?|4fO_)I5wPCxihSMrkHg&tDm{YV0AV38?4^u-hWiQ1i~s7& zy44pv)fb%A7yQ+ixT>$Y=V8a^{)e4E_d=|nxi4b<&pi^m?%XeN8lJg#;xwFdPsM5Y z=bnnw{_bGB`ZB-z;-~uJKi;expYX&pobeBTc@bCjCEoIghw_V`@{YIkfX{S-=k$aB zbR{q8O}^5h@$_kay5%Q5^PkSGoBrXcF5s+Q;IEFvReg!KaXd61Kl#C1{_)wmcn%N# z!znM}m#^Y7UcBbV13&S@f4o^YKH-UHIO8Aw@-p}KY<wxxZ-V&%H+LXYM;%|8o!0t~>W5EuOhIX>rbdN{fH)S=zXaS6}8=U;I>G{8wMr zt-j!?zTm9B;IF>KReg!KJmR7J;-|dhEj{2fo!~kB;6Gi-S9+7L)!~e%PxI3)Kk1qO zbZ*`B4^MRgXY~SqbtJCpOT3Naq51g958m>R&(_6rc<>)ic?rLK6_@eiH9sEsi68#s z&ARakPdvjJ|L~WW`MciM*WBB-d7S&)HotSv+va`le_K7wy>P3Oxi4<@Gxx}?uI7HZ z)!W=Vw>mUleVJc<@l$>AUwv7(`hutWg0uR9zxona^)>hG?fBfkxAW&-zV-7tue!(j zpL_gv-MQay@yxw{i*xP?T>NuS;KpUV`ZB-z;-~uJzxuLn^#xD$1!wgIfAuA<>Px)k z5f9}TKjj^7=>ebV1kdRQ|LICz(wlsxL*wbw{B+Atdgec!TQ~i~Q(eGWy}(}`iL3e& zZ{v7qK7R6pxBTO?b@3b?{D)Is!Y^ONWxROJj|YC@hyQr9ZhXQM&v3>+{N-itP2KvM zdq+2qb06vEckU_OywClmtB1MQbagWKovwc79@N#<+>g3?n|o8w>u|=aFY~J}eyT72 zt1s(TU+`34a8_UNS6||)zUH3T9iRJScmCWfyME@r+4Vp7(C)f(Kked~dutcx+-JM^ z=bqb*%Xsx=e)Yvq^~HbnW!>rvp6UzE>I?qrOI+2Lc*`Rm$}fJ(JKoX*KGO-F(+~dB zm3*Z)`C1*$c=|Ly-SU&3`A_H8P5jRtDm{Ydv!JUd#~Q+-tX0+@#@R`>WiQ1i~s7&y44pv)fb%A7yQ+ixT>$Y z=X}TK{_~wb_oA<#xi5YF&pqn9?%c1wc;?>q#X0w}FaEiwed97-eVJc<@l$>AUwv7( z`hutWg0uR9zxona^(Ef&h==lvpYo2k^nlNFg6H&u|8ylU=}o@Uq4D%-e!Ar+J@cQ= zt(*SgsV?BGUf{2e#8rKXw{bi)A3yoQTmJFcx_Ax`{=+FR;g_%CGG4sq#{)m{!+*S4 zH$LHsXE@^@{_-;KR&0IEyAPYkc@JXqJMTnn-sk;@)x*3iu{xReCRRW54#nzf-ltf- z&ASz=L*vz#`PCOc)ffNOmvyTzc&aZrt1tMgFL700^G?T(&-)!af8O<2Kl9$l`k!|| zcHMa&Wbw?qA&c`)&wI$?pLa$!F5}gg`PCOc)ffNOmvyTzc&aZrt1tMgFL700;w_JO zD8KkA?|4fO_)I5wPCxihSMrkHSx|jT3yZiN~^bdcj>$iXT16{zxv{*`r^O( zvTpSSPxS?7^#y&%0FXXWpw?|MQO3t~>8rEuMMzYH`kcSc`w& z$=bM#S6}8=U;I>G{8wMrt-j!?zTm9B;IF>K)q8E??OiZD^j;W#dPfXzy)TB(-W|hp z?~&oZcgp0e_sit#%)4f%y?17Q@1XJ1`)K_4Zkly_PYs^lS%b6p*WmA6HgWY{n|K?? zL-X;IAH3xspRJ4M@Zdk3@)CaeDlX&2YkoZN6F>aNn|0$8o_K~c{^2h#;%Yw>Z*_-< z>JdNHDc-7Id{)e|KXIE@XJ?m882S*Cb=H)={erVnHLwMQ`;cP#Izx_~L?T7PD{f^K3^*evwwO>E;-u?Rj&;^(7x(|B9 zrHkj0Pq}n)o_oQii~r>>y>#O;-hOC)`yoH=hy1r6TDScWp7ujH+YjMyKNMH{p?Ir1 zJXDYPsZQ}${o=E_#&h+K|Mmg-YJZTg-8W{u{lxtC8GhP-_-|jbZu=EH?PGAZzro+W zC$9EG@ivZ!=Hn+nc*{RNTNlsa!GAdACH(SLT*iyn{CMCee)x|!>&7QM@eF7D!(U#+ z)qW`6>JAUpBYvt=yj8#Wtgi7~z2m=qK)%`^-zYemv6m4;8mCJ zK5)a2U%vapO+S43?i1SQJ}(r+BM=@mXEtxq8Qc`+&T(Kgd`6hVk|j z^V?_mY5(EBeaX7*SMaot!P))>fBT-e+7HFsI3AjhpZwr0|M+ZOJckGW;gpx~%U5w3 zFJANGfuH!{Ki;expYX&pobeBTc@bCpp?Ir1JXDYPsZQ}${o=E_#&h+K|MmfSX@8Kf z_6_6hC+4@$@YDXofBTYk+ppkhAA_^~4gU5$akU?cw{bi)A3yoQTmJFcx_Ax`{=+FR z;g_%CGG4sq#{)m{!+*S4H$LHsXE@^@{_-;GoX+3QkLL4prx!ow){~2l?{ToN`PExa z9)IIK5B9lhK5+7Zs}FaBo?d^uzc~5$M}PKV{71gvJtv=k^F;^yLzlesWPZnbu)p|; z?>M>l;~sUeU;J}#Ke_DL-*~X!efPJYq(kFxdg+xr|IXib^}*)nz0Y~p!RG(=pZeT` zZQZ-x{9^|jo|nJ%aOe9eoZtECYY*e_-}cHE9qbRsb=|?f;)%CEZTw-cxx;DmzwnKB zJk8HTuDQ!;{$GFVN1wLtg@1L|)A0P=x8D6UoL}~(7oLXy)1G_b)|c_(H9sEsi68#s z&ARakPdvjJ|L~WW`5f$#e9iYcPOo^|2ab%hKl!r1J2Ibr%kytN;)nfF&-;jD{@FkJ zq1zr?m;FcYzx^>h?2~W#$YVI!7yPR`9K+9k?{n^OEMJX_xA}Nr^MfBY|9E3t7oTi+ z@XUr2|7`f>h5g~UuKWM&JOBGv?;LhN%g!gewb)@`hm9>pnAu_!3%eK_7kl$@!j3C; z9J1q<9p~(F!7fMaa>xGlN4@KiJNCU!-*(6y`=LMndxzYy?|Yk@j^vL0Ne_I(k=(JL z`N-cmk~{W|m;TyOIPd>6Hy(xmiFdv6NbbxrUcBbV13z+?f4O5@SMJ#G$Q>I_xnsjG zckFU^)|S)eu=`ndKH06s7GwGeoAEHSi-lc`ji=ikVf?bZ-v;QCa zoHl#*&tvBk_Ux<2&MoZOZ;zd4*s~8GJLj-xe?E5pVb8vO>|Dg2{ruQ@i9P%Lv2zrA z_Wxs_XKviNvH8x8Y<`>@+59^pnAu_!3%eK_7kl$@!j3C;9J1q<9p~(F!7fMaa>t&Ye#jkrdi^1H>^TD* za>t&t!6A3-IWrt`$DXsqA$ROKV;pkFp0mdxckDTn9CFuq@tPkG{K%a-{L3BNx^l;c zNAB2g${ibixnq~Rv$i}ohuzPz^T}>4b{N=UV~3e7#&lSWji=i<$xk|uL*sGFj&pXo zV3#Ad7@hywa_XGPmTTuvHVrtJvT4J4l}$6wv20p$zGc&-b1$1Forl>pS-&&x{M>x! zYBoR4+id=w!`aq#K4-(@+|Gv6d7cfwb3R*K&i`j^d29~5pJnHh-CFE0u*1d{Bh2h# zVHacLVsAc9*m1>Fne&jCya>ur=+_B-2J2sqh$A(|-*yZl5EsxD%_p|JLvRjKS#`F_5 z<6=y2#bUe|*~Q-c^c+{l^Nta3wAkTi_yR1*mCOM3v9Xe?+7*x`1b{yHvGGT zO*8&I!lotvPGQref4{J4(!XoiH0j?vjr(^{^ZomX&5wUKvHAD!DYkX}JBtmEe}A#z z^zSk@{QkYh7MFj=owen$IqZIxolkaavBSU)8(WMpv&ASDb}=?C_U7Y+9aro)WXCN# z&e`RHU5?o0jxDEh$ChikW7B}#v1vo@*fb+|Y+8~#Hcf_;_QFq-a%Yb5;x#`W_>sH( z%N^Uga>s^8?$~h39UFeRW0$+Lwmde6-OsY~$!;yS7}HPKjE9+BEbL-zJl)2L@wj5g zAv~h4OJ#5dJ^LxuZXU^|4_nbMu=iGDV{Qh&#nIF2~(miL+?@RZbIlo8U zbLRYhbYSM^kIiBCv+R7b zTZTdR_rB-M z`JMcpGv{~pd(NES;qN(fez(8p%=ufuo-^lf0ej9g-Z|6!&YApl&g8#yrgb}K!qYhu z&d!@cvy#tt*PSlGqbc<0PGF&kVf?bZ- z;_93!r=2t9x^pHCbk3xW&Y3jRIg^$;XVO@GnI=1D(&Vgn=t0IiXPRH%=cjWf|D6-8 z+c^`S&Y5s_&V;{nrnow1W~bZEGySabe6m}M9R_yT*kNWD3%eK_@0=DV#^Z_|hwQjz z$2q%Pu*(s<+_B}fbEaH(&ZL3PnY7V4lV&<+(o*M48ta@%li{aHxwDq>&Y9+S&g7?a zCjXr?t=l;hp3a$YcFu&qyqwKfcDgOU{jBkPvRjKC26oukVP+Q#yBHf!w{c=TuGn$N zj$3w|v&#j$9I?gKIa5wMXUcWwOd9B%NgJIrX{K`~Ep^VMvCf$^S-+;q&Y8wLXPVzR zlb_C+{C7^UZs$yRI%mS!ITQZQnd0i4nVoJs&-Am#^T}>4b{N=UV~3etEbL-zymMNd z7>_G<9J1q<9p~(F!7fMaa>tg_&Y5!EIgW5O@^N)J7*g2 zoN0dNOny3N^4~erx}7uO>6{5?=S=v^%h`Nor`z(|&l=AsyS3P1V26zzW_Gc#i?Q)^ z8z;u&iXDgSxMjyVyIio#5qm!GwCBwEywILA=W|4R&YaH|?KyKkceLls`8?8|Gv{+k zd(NECFYP&VKG(G8%=x_2o->Vi&NRPsCO@4s`R|-*-Oictbk2mcb0++qGsV?8Gn+n} z!|rF<`DC{iI}GfwvBS(R7IrZ<-Z?W)jK>u_4%uw~uGn$Nj$3w| zv&#j$9I?gKIa5wMXUcWwOd9B%NgJIrX{K`~Ep^VMvCf$^S-+;q*}o3wOyiw1&F`Ga zPv=bjJ7-$Ab0$2UGvVx<34iAhadpnjPPd(B`dQ=oWVaSO4D7J6!^|!gb}=^IIW10% z#}zvc*>TH`b9T94mm_w$W6NphOu6oyNduiTX`^!{&2-MBrOuf&);W_V!%vfPXD#EM zGtKXu$xr7@{yS${w{s>uoipL=oC$wyR+w-!4L?69%J%q|voF*crV zYPbqoik~&eod2| zGmUr7G{18uKb1U1SligbEFtEeM4l}!0 z*u~g*=d?I69#`x*WXCN#&e`RHU5?o0jxDF1Gv&H-CJl7Xq>av*G}AegmO5wBSm#Wd z3_neF&NSXR)BMhv{B+LbzjLN_J7>bvITOy#nedmFv-!$Sx8=8=HJ(p)Yq7(?4jVhn z>|$XTW8>*IPK?JDI}X`#%Z_t)xnP$g_I%H1&zbW*ojqsH_jmT3Ip6EqbLM>CXV01Q zJ)k{j&i8}%oH^ec+H>Z7pJ>mS^F5|$)Zb7q_vk1KW@vg4K==j?L9E=TNg$DZ$w z?KyM4Q?}>K`L5ZXGv_;Kd(NEirtLX%zO%OH%=s?co-^mWZ+p(1@4oFh(|G4h^E+qq z(>as>&Y9NjoC#0oOgKAd!rwXbY`(H-wK?p5mYq*_Yq7(?4jVhn>|$XTW8YPbqoik~&eod2|GmUr7 zG{18uKb1U1SligbEFtEeM4l}!0*u~g* z=d?I69#`x*WXCN#&e`RHU5?o0jxDF1Gv&H-CJl7Xq>av*G}AegmO5wBSm#Wd3_neF z&NSXR)BMhv{B+LbzjLN_J7>bvITOy#nedmFv-!$Sx8=8=HJ(p)Yq7(?4jVhn>|$XT zW8>*IPK?JDI}X`#%Z_t)xnP$gwzxWH%4z3Jx$c}v1D!KzqjM(Bbk3xu&Y3jUIg=*q z*EHEV(|G4h^E+qq(>as>&Y9NjoC#0oOgKAd!rwVWT%9ws({1OOe%5$C*{#J613PT& zFtdw=U5t%)PKy)cam9{9cHFY#oLw&1<%nJG*mBxAQ?5H_(m>}-+UT4~Go3SOsdFZc zb^Nta3wAkT&*x$HoH_Sn>^XDp&DeA1+^4bU%(-V{ z&zW=o#-20hUXDFy&V3zw&YXKZ_MAEQd+a&Wc;`&>J7@CKIg|g+nbz%`2~X!tI6G&; z-#JrUoinrPvpMX3mYq*_Yq7(?4jVhn>|$XTW8uoipL=oC$yD%(MB*rq$-K`&o8A*{#J613PT&Ftdw=U5t%)&Wsb| zam9{9cHFY#oLw&1<%lh=`kkEC@8r6EM+5ac+Nj^rO#P0Q>UT6&zoW_a4VtXq8L!`& zU%%t0e#d|P&bswGc*6-kNKNMH}E<4?}ulBRX^T}>4b{N=UV~3etEbL-zynYcU z#^Z_|hwQjz$2q%Pu*(s<+_B}feka%UI~u6p(MJ7_X6kpeRKKIK`W;P%pC;>f#_M%h`Nor`z(|&l=AsyS3P1V26zzW_Gc#i?Q)^8z;u& ziXDgSxMjyVyIio#5qs{7+kQ9qt!=-Xd)T($&HZfK?_T!mi?-j*eQw+D=AO6hcXR*S z_PeT`&`W-*@JO1l;)~(;cQ@?|=eg}X3PF(f7Z2D{tyPsv}ligbE zFtEeM4l}!0*u~g*{Vq<7#}zvc*>TH`b9T94mm_w$W6vFc+wbOX!0mT)XW;g`xl3^S z-P|#_{ci3a+)%&*_^Q@`WCerMhK9X$0rIO})t*YD2e zE1OoE!|rF<`DC{iI}GfwvBS(R7IrZ-x;spnP0!-r+&wO{m#1eJ9z4MaMthOZ$A`Q z{VqG*wy*ZH#`DQ;Ep`~#VPl7xT`cTkY`lIEC&uH79f$0=Wyd+YT(HX#yWFwmw0j%Mn2v{b*NvHBfNhMy+ucgE{?=GX7|so(Kmzq4-r4xaiQob@~S%gfn( zWvAQn+s_)$C%d)SVPJ=i9cFg1u#2(rbQ>qev!-rrH)bD7cen&I)J6fvW(OCVCCfhe? zvVLd0erJCDj-UD+|MffT*6-k{-@#eGgTMVyT=l!`blbk#&l=AsyS3P1V26zzW_Gc# zi?Q+gMVuIqD|Q^R~g^_N9=OPmecy3T-WbtpngXi^*frW-_cV2j>hVDG#P%H ztlt^0-_G<9J1q<9p~(F!7fMax#MB`-Mj~}{chfg*nT(fM{K{FcO|ypU4NTT*?u?g zP;9@O_bImD&AS!b@8&&=!=7nfv#Or@A$9ZS+{-%PyG(g`W^iBJ8{+Tvgxxq z?0%M=Pj+ju!@v$3JIw52VHacL^}9GR9#`x*WXCN#&e`RHU5?o0jy-RbY`>egOSa$5 zn3y_Pco-W&7Q{nX>(E-cs3qH*c(LzcXIHGrxYvPyLSn`ki&_cktBj z;H=-lU%xw>uWXuW4!fUa=ab!9>@cvy#tt*PSlGqbc>OL;jK>u_4%uF+1TB_gCSpAMB+c#*kerLRXXMX*TpZXpD^*ig<@8GH5 z!CAk9zx_~L^}FnJ+rHY*8qX)Ywb)@`hm9R(cCoOFvGMvvoEVQQb{w+fmL2Epa=|V~ z>~hDJ)B2rU*Y9Ycen%ViJDREA(Ng`6#_D%88Gf3q-x;spnP0!-r+&wO{m#1eJ9z4M zaMthOFE3~Fm7Q+OZ$E21pX}CRhk+e7c9_}4!Y;k1KW@vg4K==j?L9E=TNn zA8q^Hyf3!>Zr&Z+emC!tZNHm$%C_Il`(@kj=3TSxck|xa_PcopZTsE4kGB2Jc>T`& z`W-*@JO1l;)~(;cQ@?|=eg}X3PF(f7Z2D{tyPsv}ligbEFtEeM4l}!0*u~g*{Vq<7 z#}zvc*>TH`b9T94mm_w$W6zs++wbNryzO`MM&9 zck^c7_PcqrZ~L9``kndpJAUeS{MYZSTfc*+eg|j$4*vSx*?eWwYIE5AEIXg<)?$Z& z9X58D*~P*x#>VS+abi5K*m1~?TXvkY%LTg}vBg!tlhgX0T-WbtpngXi^*frW-_cV2 zj>hVDG}*pEll42}^*i(Hcl^}v_^;ntw|)mt{SMCh9sKQw;;P?er`z_`e%5$C*{#J6 z13PT&Ftdw=U5t&_FXF^_T(RSj9k=W_XO|0hIbxSPww%`Q3{@zk{=W2Y-1vo3HG2TYmdl^Nta3wAkT50~5Tu6^2Vw%^S=w%hOKecSDK^X~2T zyLk_H``x^gyZvt7&)t4E@9J*9oA-9N-x;spnP0!-r+&wO{m#1eJ9z4MaMthOuiuHQ zewR(3&0+Vm?0m9Yiya1b*w|ra7Yn->8?WERiSf8%$00jz*>TP;7wmGxE_dvIc;QEE zzniy}x8Kd1%iHhfE#~ca^G5UbyLr3$$Q@by%$v?f-Fr4~Js*XC-hg(8VS+abi5K z*m1~?TXvkY%LTg}vBg!tlhgX0T-WbtpngXi^*frW-_cV2j>hVDG}*pEle6C8`*+6c zcjnjc_^IFVU%#_%{SKb`9h~($_}dS~Rlmzlx9zL_tnqxZTZUXqJzoVJ@9WB-GXsmumli{aHxwDq> z`kndpJAUeS{MYZSTfc*+eg|j$4*v3THecE4w*2<9#`DQ;Ep`~#VPl7xT`cTkY&_k@ ziSf8%$00jz*>TP;7wmGxc1LLUXP*51pC5I9=2dU~i=*z(eECcN&r$bh{^K|PulnPg4|^v2>ptoIhdq=1S)cR%!=BlA{m%UQ9Y6Iu{_A(v zt>3{@zk{=W2Y>xeT=lzbnrRNZpJnHh-CFE0u*1dzxh3f+_Asyv)^;b9sAFI_D{Fp z{m)1I>Gr#Kee|Dhzx(K0-@X0Lc=4KFzvHKV$AA6Ky7fDF>UVI~@8GZBoy}J^%`}JI z&$9E$ZY_2g*kNObnO!XGVr;yA7bnK!iXDgSxMjyVyIio#5nEjKJ2|c2$#wmX2I_aT zQNN>^`W;Qy?`W)kN0aRvG-=PYuJQVv`Sm+~>UaFt@2p$DgQtE6XZ;TT_Cs;i@3LvE zIqZIxolkaavBSU)8#~PGVqq6!kVf?bZ-<&G_<^*gz)-_bz* zjyCFdG*iE$rTQI>)$eFB{4`m=GhV+lzkbJ0{f__ooptMX@YL_%tlz<3zdM_+>~vdx z`&r}pWVaSO4D7J6!^|!gb}=@dZsWvwT(RSj9k=W_XO|0hIby%!Zg1Is_pn>uviTfe)sN=|K06(uX(`lZoe~L zzcasn$4~u^|N5PE>v!@c&7g)$eGseS;?JcgE{?=GX7|so(Kmzq4-r4xaiQob@~S+YiN6 zzspXy?W_H)@qDsdiya1b*w|ra7Yn->8?Rr)iSf8%$00jz*>TP;7wmGxE_ZA>t>4LY z{f-9eceGKzqnY|0E!FR6tbRw6;it*^o$>me`Sm+~>UaFt@2p$DgQtE6XZ;TT@^Us` z+3B|Y_Or(G$!;xn7}#NBhnZb0>|$&@-NuRWxMIg4J8s!=&Mp`1a>Snhw%`5EU;nr5 zcmLtdzqI}ChU;Im{qF8x`^($!-v9T%y#4M8PkHV3yXXGVYq#G$@ndh;e)nacdBgTQ zv#Or@A$9ZS+{-%PyG(g`W^iBJ8{+Tvgxxq?0%M=Pj+ju!@v$3JIw52VHacL z^*i(XJt05+`z{X6k6U(}v&#j$9I?wC`+1-JU$@`=!DC*%{q8^i(0|!}_iumeRom~b zy5Fm|-`)E1S1z7EeCR6|=Lhfj%I$Zb{`bGQ{myv(&iwivKlMBQ>vz_z-@#MAgR_1I zfBo)kzOv{4hZxImKWjXn?ABt3fgLt>nAyd`F2=^|cjour2S2@!5QpZ+Ej!NH<$_&~ z*z@1^J2|c2$#wmX2I_aTQNN>^`W-FR?`W)kN0aRvG+DnhUcWQHe#cM!j{o|db?bNV z)bHS|-@)I0D6aZlcDij}?PrbWligbEFtEeM4l}!0*u~g*{lfhE2tW0gI5aTP; z7wmGxE_ZA>t>4LY{f-9eceGKzqnY|0Ero~1!by|ir^))A@%o+l^*es*cl_7ytXsc> zr+x=#{SN-}ayDPt^Z!GP<+qk3;k0mL2Ep za=|V~>|eRdb=&X0`LC|qe)oxQyng%LLtpe0+wXqztABF)-S^z`liTn9_Q@~aec%)R z;KjQ?{KMT|vi5g zy87Dfckg)J3%1|g_C7Dze)p`GJ%9V%W54|Q+wXqpg6D6)`^CRKyi<4hJA(20o%!`U ze(HDp*YB)bzk{cK2WR~b{`%e7d}Y&WbJ+bXJD=>{f=hpceK<#Kx6F>G}*pEll42}^*i(H zcl^}v_^;ntw|)mt{SMCh9sKQw;;P?er`z_`e%5$C*{#J613PT&Ftdw=U5t&_FXF^_ zT(RSj9k=W_XO|0hIbxSPww%`Q3{@zk{=W2Y-1vo3HG2TYmdl z^Nta3wAkTf5n}y-hTJKo3Gw}_aA@j2e;qd^nxGSe)pMQ_4Ms`xBr``Z@>Hg zE1t3a?q$FCjO}+%|CncPzx&!xf9Cc(v#Or@A$9ZS+{-%PyG(g`W^iBJ8{+T zvgxxq?0%M=Pj+ju!@v$3JIw52VHacL^}9GR9#`x*WXCN#&e`RHU5?o0j{URu`+@Cu z@BcU7zy0p%|Mb1v@80^uPuqTXkB2{X``u@J`BS#vz2gVJXZzhf?(#j`@2+^yRr~Kd zv#Or@A$9ZS+{-%PyG(g`W^iByR-Sqrq$-K`&o8A*{#J613PT&Fdydpb1dv) zY`lIKC&uIIFz25+WXCN#&e`RHU5?n|s^7_J{Z6jycQjDHqmB9<&D8H`seVUe^*fqu z-=N9*o$>me`Sm+~>UaFt@2p$DgQtE6XZ;TT_Cs;i@3PZv`)WUHJfG~=VuyhpHg=fV z#lkMe#_JbxVmz+cambEacAT@z1-l%v%N<)z>vwWpzoUWr9c|R_XtI7sOZ7V%tKX@w z@Y7`d&UpRK{Q4a~^*jFSch;@n!BfA3vwjDEc{!V}>~vdx`&r}pWVaSO4D7J6!+e3{@zk{=W2Y>xeT=lzb`fLunpJnHh-CFE0u*1d4Wc6*~^uam$W# zcDZ1eBX+rCKjD%~w%`5rHILkW_ribpitTsrd-}t--+lgsUz=;*-77wE+U|Gk^*ih9cl^}v_^;pDw|*y{`kgrIcjB+#9j#aFthNUC zTAWYZUbq-=vEgFI<$}vGd;Km=*wYH9Ax>MI=D1qmYJ}xgzf;rtom$uLoPqkCvr)fu zX6kp&QvJ>utKT`3y>B>^^*i?Zo%QuQe(HDp*YE6GzY|aWPMq~S@%Mfxulilwx$S+m z*Rtmmw-+u3Tx__Qak=1f%wE4p6ZW*iX^7Jnr#Y?`xEkSVht;%xr`Gj5XP|!PY}D_Z znfjfxRKIh^>UYj$@jH|CJNEjW_4PY`>UaFt@9bN@6Hon4ob@~LSC^ypiaWQ}x7V`g z6So&G23%~om~pw_a?IYjO%wLC!fA-p7NnCot``rgm zJYn~{A35(fyWidYW4GP??oOZls@?C-e#`B4zq{LUx8MEliu>Gt_dE9bo%QuQe(HDp z*YE6GzY|aWPMq~S@z?LE1ZTnZE>38YJsZ}mRJ2wP3w1RUB7b%>UYjY{mz-G z-#JV5J7=tZ=S=p#;Y`-=*z0%J*YEhL-|=6+vv2)QJoP(q*6+mM`=Pw*cX8*o_tjp@ zo=@CfxEOG;;bO++g3B>`{US}+(+Z~{PFtMjxLV+9gsUA^)B2rS*YBKx`kk{;zjJ2l zcg|A%&KaxUIg`cjOxEw%>vz`I@A#?T@n65QZ~aa@^*eFa@5EnSj@B#g+*aRS%bri% zUbq-=vEgFI<$}vGd*?Py*wYH9Ax>MI=D1qmYJ}(Sa8B;~2)BFVhfePM2sgXIAD-Oz z5#D#&M^Eni2q)d;PfqUp2(NwD$4~D22rs_)6DRk3{2QP0$&>s2{<(Mf)XBYXeCnJ} zo$NbY_GPc%Szo{7r+&wO{m#DiJMq--#96-+fBjBg^}E>lYz^+UIG?z^a53Ow!^Mot z1(##?`dyl^rxi{^oVGa4akaqJ2v<9N=a+q8)efI>^Y^dX;a7a(w^r@&N&oA=uG-;? z&VJ9T9sb?3E?u?5_xY=fSMBg6|8~);9e&z7FIu(BUca-xe#cM!j{o|ded~APso#mS zekcC=-O+l*&P;1?uf_Sq?S+d07aJ~SEXU4aIcD$Nrb&J}=V{2Ewm8jkwZPQ~%d38; zru93uuHQKW^*d*ye&@{8@0_LjoikRyb0&M=a3v#Or@A$9Z*|&Ztp8B0Q z>v!Vs{ZL-@yV#j&4eqr#pSZnnG2mju#f-}Zmt*$&MVhdu6;4B(wm8jkwZPQ~S39hx z^*gn$-#G*IJ7=SQ=gidaoXPr~GgiNICX3&htlzQM@2s!i@l(I!zkX-m`ki>{cjBzy ziNAh#v|e%Nw)*y3_I%>@!o`4#4Hq*m7hI0nJGW`Vo>n*waoXZE$JGK?BRoI1?tb^? zJ3MOlyBA&ial7Ar>YOL;e)o$HI&1g4mptt0yWc(Td!D)b-SfZq*}LDp=#=N|es`-Y zp0oQMd+#&W*YEhL-|=6+vv2)QJl-?KFV6a%_^;}BXCCQy2kd;d2KQQ=PuyO(7;v%S zV#eiy%Q1WXE=}0e3a24XTb$;&THtE5)*sdmzw6%~u>0L*x4z%*cTaogy?4L+#VhW% z``ris;A?lk``mBdY4^Jizvrag?=Jhx6L-J6>w{0+{f@nUXMO#SpZXpD^*j64@5G~a zVisrpPW)H(yQ}Kue0FbXjk@<*oX>Th5BI{wfQty;xxzA z0#~E8e)6i{scHRAt?PHrK>g0ysNXp=^*d*&e&>wU@0`irH=N1(9ee%G`uZI|^*jFS zclNE{iKl)i&ibABdp}gKtNPsmcW!%M?X~Rr#O;NP0T&xCW?U|~9JALi(u6&&a2n#Y z#c7VK1+GSG{bB8}n%3{sx_;*j)bE^)`kgaVzjK!Acg|S-&Y3KJXR?0BUca-xe#cM! zj{o|ded~APso#mSekcCwQtisII<}_sT;21z&hz13xEOG;;bO++g3B>`=Qd5)(+Z~{ zPFtMjxLV+9gx~kzA9-s(-~Hno|Lhz3`R>(se*C@q`R*epyyaf~e0SxqUw*HCzPsY@ zzHqO8zWcq?Z*cGKy$^Ztarf@$yC=Tw*7xpx<0B{B_TK$`$6mj)zJA9~{f__ooqg+f z;;G+>vwkQ3`klObpN!S9HMrN}eB$=P#ejP96VF9zhbPX9`rgFkby4w8UKcfA zg}r`fef^G~`W^rEJNwq}#8bbUye_QYOv-dsm*YD)j`(*4~wFdWEoKM_d zxEOG;;bO++g3B>`{US}+(+Z~{PFtMjxLV+9g#EiyyF>fC>vyyM!us9#xv+jW{x7WG z&Au1b?UR_8MfE#pviP0J`W<`y&ieWtKlMBQ>v#68--)MwC(ioa(a2n#Y#c7VK1r~q*zNV*NT)&$>cya$8 zr$1iYzticP7uWBmpI%(Qn?8GS{cig2#r3=C%NN)0rjK9T`^NO~i|cpn^*ih9cl^}v z_^;pDw|*y{`kgrIcjB+#$*X=BJD;t=y%y&aw-+u3Tx__Qak=1f%wE4p6ZW*iX^7Jn zr#Y?`xEihXhqc3V|6H}hb1z-B!*gFUaFt@8UYj$?;Fl!{f@nUXMO#SpZXpD^*j64@5EET6KC&x;;-MSSN$$l_txNEi}Q)w z3l{?}HeAfOTyQyNuV17Ids^W%#A%Du99Iimjn?|Z+F>=V-#L@@J7=JN=WNvPoSFKa zGg-fL#_D&@Wbr$b^*i?Zo%QuQe(HDp*YE6GzY|aWPMq~S@z?K;)+_GZR^MLBp3ilj z5BI{wfQty;xxzA0#~E8{>GQ>em9?U?tV9)f9`%apNsB( zH=md8f7kOl>h5>*`ReX>^SSHpck?;z?sxM!?e2H%z0X)*zvHKV$AA6KzV$ot)bGSu zzZ3se{qC|O{qBIB&(`2xi}Q)w3l{?}HeAfOTyQyNuivE!ds^W%#A%Du99IimjqrTN zzG{c(_Y1q<&F>v{znkAj?0z@Dr`Y{&et)t1-TYo-_q+Lh$L@FY`;p!6=JzAJ-?7*4 ztgqkkQ@`WCerMl)z7tRVPMq~S@n6;NuBw+DySKE)x$U($pSZnnG2mju#f-}Zmt*$& zU7E0`6;4B(wm8jkwZPQ~%d38;ru93uuHQKW^*d*ye&@{8@0_LjoikRyb0&M=a3v#Or@A$9Z*|&Ztp8B0Q>v!Vs{ZL+4^}7S^-1ffOYuWRO+Y1*1E;d}uxLj~K zX0KnQ342=MG{k9((;Qa|T#azG!)jW;Q|tPjGf=;CHtKiIO#RMTs^2+d^*d*>_?^l6 z9ee%G`uZI|^*jFSclNE{iKl)i&ibABt4p;j$LiRc&U1CoCwqJ0V!*|Qiy4;-F30Sh z+caTME1ZTnZE>38YJsZ}p1;Gnq@VBR?^rJB=ezm)mP`8iZvO7&l77CMzlXV`d+hw3 z%q9JNH-A5KN%!9QyP8Y-`ELFW=aSwx=I?MW>E}E4`knRlJAUeS{MYa7TfY-e{Z5?q zJMq`=J~p1(I+wZrpwXsdR3{yuHh4$t4Mt=i%Fd$v_OJb(YTYKQ0V-&XCi*YB*a z-|UZL---*9|ceGxyv)UTmYjHktd*Nch#fFO+%dvAEpRo$@~YpdY5h*E>vzsT{m$8_-#Ih&J7=kW=Zw|woXOrdoXPqfd;QM( z`W-*@JO1l;_O0KEr+z2S-uJ{`zmr$*ld&_?8r*AfK5={DV!*|Qiy4;-F30Tki!@38YJsZ}u69^W>vw8hzjFracg{xr&Y7v-Ig|A}XRLnbOcuX0S-)ei-&tS3 z!J*{vW z;3=8y?&P_>}iG55T`9pb6hQOHNw>n&-a6Nznkw3?S41kC))jPzGt-i-F*LO z_q+LC((ZTjeWl&+=KD>%-_7@%cE4k<-&tS3vw6wo>n*waoXZE$JGK?BP_4_otoC~)VhA>4Ak$O zjryH4Q@?YT>UYjq{mz-}eZ!fo-?7*4tgqkkQ@`WCerMnMop|bZ;;i3^zxP9V)$iiY zZSSkSmOY=iy>Kz$V#CFZ%LSKX_WDJdu%{JHL!7oa&2hEB)d*KRtfuulwXWYe1NA#+ zqkiYi)bE_7`kgaYzjG#w-hx*V-n+_|m3 zy_P+nxV>;O;9|qYjLQX=WA@H%ny{x8PD7lwIL&djz|{!P_vm-OoA06TemCDw-~DdB zx4!$`e4l;yyZIjd?sxP3_ucR2d-1#9%}jvZ@8)~-yWg?b@2s!i@l(I!zkX-m`ki>{ zcjBzyiNAg)uj?Fs|1NeuTZ4No&L?g!TnxC_a51knhq>T#%wE4s6ZW)PYYsKUX^Ybw zR|{N?aJ9oT|6%vLnG3P|-OP*F{ch$+?0z@%C3e4?xf8qJ%{+?T?`D3*?sqf4V)r}t z`knRlJAUeS{MYa7TfY-e{Z5?qJMq`=j@B!7R$GI6EzT!yFI)_`*l;o9a>3=8y?&P_ z>}iG55T`9pb6hQOHNx_$->GT+POa;A&OrUn*{I(+ll41iseb2-)$jcK>V3nRtlzQM z@2s!i@l(I!zkX-m`ki>{cjBzyiNE(ldDZXY&Ta3jy_P+nxV>;O;9|qYyw)7%g3B>` z{US}+(`v0b)DWjFPIFu>a5ci!4y$SXPOa;A&OrUn*{I(+Gxa-Xseb2-)$g3i;&&$N zckJ~$>+5&?)bIGO-`Tf*C!YG9IO})fuP#UH6?bl{Z?9#~CvGoX47k{EG2?Q<<(R#5 znEpRo$|K*0~?S40N#&*A(`D44^&0MnG?`B@v?sqfCZ1=mFZ?^m0 z%st!vZsw%zem8T{cE4k<-&tS3Kz$V#CFZ%LSKX_WE6#u%{JHL!7oa&2hEB)d*KRJoEi_zni&#yWh<`z}@d=PT=l$ zGe2y;xxzA0#_p}ulk*u*6-B1e&-C- z@0^YLoikIvbC&9N&RG4UZL---*BXLwVKj z;?8aFtG$*zpSZnnG2mju#f-}Zmt*$&MVhdu6;4B(wm8jkwZPQ~S39hx^*gn$-#G*I zJ7=SQ=gidaoTd7mGgiNICX3&htlzQM@2s!i@l(I!zkX-m`ki>{cjBzyiNCrWtykQ+ zt-igMJ)gL}a53Ow!^Mot1(##?&TX2orxi{^oVGa4akaqJ2+x1J-_0E9-S1|;^zL^v zcY61`nMb|*-OQ=p{ch%0?|wIPt#`ls!u5Z3_q&;cz55+|{m%OO9Y6Iu{_A)4t>1~K zekacQo%ri_@~Yp(&Sz_Iuf_Sq?S+d07aJ~STrRjAv)Ave@9+Hi@jD=E(h#RDPIFu> za5ci!4$u7d-S1|u`|fu$?|t{XnFGK3-OPvI{ch&Q?|5dO{El@!o`4#4Hq*m7hI0n>vz`o z`)Gdp{aqSbpSC#7akaqJ2+x1J->GT+POa;A&OrUn*{I(+Gxa-Xseb2-)$g3i-Zz}d z`W<`y&ieWtKlMBQ>v#68--)MwC(inv_vzsT{m$8_-#Ih&J7=kQoU!6`CX3&h ztlzQM@2s!i@l(I!zkX-m`ki>{cjBzyiNCrWtyet%UpZFaUdx_O++MgCaIxWH#^r*` zF?;9M`pz>yo%1xbK5cQD<7$Dc5uU%v+5K*w6SVu?JU?jnyLqnA?sxONq22H1IYhhP z&GU)&`@lT6Xum(qbB=buo97(ue#c(Fv%Y@EPyLSn`kj62cjBqviL-tu{@xGeRlkd! z&(`2xi}Q)w3l{?}HeAfOTyQyNuivE!ds^W%#A%Du99Iimjc~QY^L(z|@8-E(yWh?8 zymr5v=X~vcH_!jt{cfHMw)@>YFKqX_dA`{0ck_I)-S61zch=YM_^IFVU%#_&{Z2gf zJ8{38YJsZ}p6A%^ zemBp7-TiK!54-!_JU4dtyLq1M?sxN?+1>Bv`Lny<&2wpYznkaS?tVAVvEBWSy?$qX z{f?jd9sl(^`_}KoQ@;~u{Z9P#J9*XbV&}6pxYy!*;`YMDfQty;xxzA0#_qk?eIK*dH1_{F7xhp^StKW@8&tqyWh?8op-;R=RWU#H_wCK{cfHg zz5CrfKYI5&_WGUm^*es*cl_7y>|4JRPyJ4u^*iy`?~c|hc2--1do9ia5cj6s^6(;{Z6gxcg{fl&e^EnIWzS;XQ_VYjMeX) z$=)}d$@(38{m%OO9Y6Iu{_A)4t>1~KekacQo%nk{lvn*O?%eji+H2YKiQ5Yo11>gP z%(z@|IcBe4qzQXk;WWf)i_;ue3tWwGwZm#!zfv#68--)MwC(inv_^Zp&dc~dF>f3AC^NHIF7XvOfT+Fy! za5-l0+@=Y8TH!RrX^YbwR|{N?@Mw8y-$(eD*I)h8zK?K=J74|MzK?M2|9-Vg`#!=) zpLDfL`#!=`zv60__I-r!IRDDs@4n%TD|f$p^o_6F{q7}K{@d<%?DaeA>v#Or@A$9Z z*|&Ztp8B0Q>v!U>-^r_f7dxM=!Mzse6So&G23%~om~pw_a?D=8OB43A!fA-p7N1~KekacQo%ri_N9z?ktF6Jk z7UvVU7cK@|Y`BUYj$?;FnK?6>CcvDfdcuix=gzvI7tXW#mrch_d|Kr?_y`H zHMrN}eB$=P#ej0NHj=RC`cTfJKW7c~npO1R`G3z}OfBNOetoKa(#TOj2-ZQh; z@2s!i@l(I!zkX-m`ki>{cjBzyiNAg)ulil=%(MpgTAWYZUbq-=vEgFIa_s%T9JALi z(j-6imo#KgTb$;&THtDgs~!IRfB$8>-@WT^zHIlq-+siG?|%1B7kv5dcTc$bvAf^B z>3+xVe)p@-ICl5D+x+CQyWbu2`eS#$V=rIp>v#Or@A$9Z*|&Ztp8B0Q>v!U>-yN-2 z?98+V_gb7!++MgCaIxWH#^r*`F?;^lioA!%U-{;zJA9~{f__ooqg+f;;G+>vwkQ3-Vfzf zzl%G!y|4CK_I%>@!o`4#4Hq*m7hI0n>lbOlo>n*waoXZE$JGK?BV6sUn%3{sx_;*j z)bE^)`kgaVzjK!Acg|S-&Y3KJXR?0BUca-xe#cM!j{o|ded~APso#mSekcCwa2LVT-S1v? zm#^IY?uUN+=DXiL^eH#r{q7StzxnQWZ~e$|yWhR~7mwTh?u1tyxBJ~aUUb~+5&?)bIGO-`Tf*C!YG9IO})fuiwe5eiu8Rt--w(=M%RVE(Tm|xR`Od;Bw4fze^ML zw8CkK(-x;Wt`@i&;cAC(_<~#Pe)l(jdyC!guJOp@cfY&KyN=)e?hRjZ%iZrjdjDJQ ze)l)eyyfn9kA2lGcfULRXKuOs9ee%G`uZI|^*jFSclNE{iKl)i&ibAB>vu=%6+5e~ z!Mzse6So&G23%~om~pw_a?D=8OB43A!fA-p7N3A2{mvPv-#Hug zJ7=bT=PcFloU!_yGg!J*{vW;*j_PgIbvw6wo>n*w zaoXZE$JGK?BV6t917CR3?sq4C=A_;4PWjfa-u>>$|L<4te)oshxa013H$Cl+yWgGo ztUK<0_u5zAare6yo_ELH@7U{i*4OX&so(Kmzq4=sPCWHHan|p|U%xwAuh>~_4eqr# zpSZnnG2mju#f-}Zmt*$&U7E0`6;4B(wm8jkwZPQ~%d38;ru93uuHQKW^*d*ye&@{8 z@0_LjoikRyb0&M=a3v#Or@A$9Z*|&Ztp8B0Q>v!Vs{ZL-@ySQ`P`)aRc z&nIp#TnxC_a53X@!R45}evu~ZX@%1er!7u%TrF@l!qpC|Y5h*E>vzsT{m$8_-#Ih& zJ7=kW=Zw|woXO&MChK?X^*ih9cl^}v_^;pDw|*y{`kgrIcjB)uN9z@LZmVyvWzQ#W zFI)_`*l;o9a>3=8y>pu;>}iG55T`9pb6hQOHNszi?A>?2`}3c@+wOPQ{<^#Ee)rk` z@%6jk{kQM``rYro_4u#f{qDFc?z;Qkm;UlycfULLm3Q6!?pJ>FuIoM1zU=io>+5&? z)bIGO-`Tf*C!YG9IO})fuiwe5eiu8Rt--w(=M%RVE(Tm|xR`Od;Bw4fze^MLw8CkK z(-x;Wt`@i&;cACp{Gz+>e)ojW-hKDG=RE2jyWhR_*Y2_V-Honw&)x4Hdip(gzx%Fd z-*fl7-}{gE-2LvNH{5ggJNEjW_4PY`>UaFt@9bN@6Hon4ob@~L*YA$jD|TjDgL^H` zCvGoX47k{EG2?Q<<(R#GmnQ6Kh0_qHElzV>EpRo$@~YpdY5h*E>vzsT{m$8_-#Ih& zJ7=kW=Zw|woXOrdoXPqfd;QM(`W-*@JO1l;_O0KEr+z2S`knZDKa^MfF7Dj+zS?Wq z^NHIF7XvOfT+Fy!a5-kLU!)0pTH!RrX^YbwR|{N?aJ9o~TEA24`kgaSzjHR~cg{@x z&RMG8Ib-!ZXR`R6$@(38{m%OO9Y6Iu{_A)4t>1~KekacQo%pNE(R#(5+v?kE+4G6p z3l{?}HeAfOTyQyN@7$&dds^W%#A%Du99IimjquZNbpPG&ZuRE-?S6OPyWVg2yE}g1 zzPsOD`Lz4)e)p6hGR_dE9bo%QuQe(HDp z*YE6GzY|aWPMq~S@z?L_YG&Ve#c(Fv%Y@EPyLSn`kj62cjBqviL-tu{@xGeRlkcnx4p0STK0V6 z_QJ)0iwzeuE*D&m+3Oc+!k$(*4RPAyG{@BfS0h~Qu$tEI)VhA>4Ak$OjryH4Q@?YT z>UYjq{mz*zerK|N$6mj)zJA9~{f__ooqg+f;;G+>vwkQ3>Ty;xxzA0#_qEbJBLdd(6*0boaaGfBi#uzx$rwIb-*` zZ}@>TcE9_dw>o3@yH|efTXw&D{`uds``t0G`j*}AZu8^cvilu-{m%OO9Y6Iu{_A)4 zt>1~KekacQo%ri_@~Yp(&Sz_Iuf_Sq?S+d07aJ~STrRjAv)Av^ggvcr8sfCYX^yJ} zu12`p;V=B?nY-Wp;XjD#aWor~4_tQQ`zGw`eT z{jOzqHr{sn6Bau&k9+BNFLsu`{EJUKchE97&z@7dA*uJm%^B-I+o}c)uXDk-yhu-nb#o~X>tuG}13a24XTb$;&THtDgs~uKTwZm$y zcGwwEJM3(z9d>5a4m(R~hn=zFbS8`6nN&M#*vr@Ybl^wr@~?K-zG{cXqjp%FYKO&N zU8)^>+_|m3y_P+nxV^9(J3qz7Ud*^$a5-l0+@=Y8TH!RrX^YbwR|{N?u)Mlws%iI3 zweFtj40O+QHo9jzGu<+t1 z-804CJw#sJGh=mZ4eqr#pSZnnG2mju#f-}Zmt*$sX=%cqRyYlD+Tt|F)dE)|T-5+9!PbzGwdS#~-urnZN$d$LxFN z>92mwzGpu6rH|S7O!n@X)_2e3r+X&<-81dmJySg0GsW3GQ~cdC<<&hic0OB!do9i< zZZBL6xY%$p<8r~}n7w;uny{x8PD7lwIL&djz|{y>JABt4`;L9jJocZyW8X7R{PxG~ zd*;9UjmPbK=5Jo-@%x^6$_+2 z(>;^_?g{qoo++O0nd0o8DgN#u^6H)$cW%4S^jh|O;`YMDfQt=Hd-qK1 zyJzy#J(K_LnfC3TDW2|`;_RL&{_1kHUUBEP`u1A(eB$=P#ej=p2>grO#61v6i@d| zadyuXfA>szb}iG55T`9pb6hQOHNw>n zKkdiQ+V{+deD17$&wRpTpR(_nuYC7Y_C51oulv+}&%D=zpStgv5BZ^|?tA9NKmF8w z&-{g-d+NStvUkt4zI!G=-81>`o@w9ind0f5DbDVh;_se$v|h2Z+8W$zaXxW-;bOqW zhKm`O3ogg(-80jKJ*{vW;Kz$V#CFZ%LSKX_RejZu%{JHL!7oa&2hEB)dOlPBe zrZdw$(^=}C>5O&HbSCT9&SdvY_U@V1chBUfdnW(gGws_wQ#{=>#o0Ym{M|$3)jc!r z+;*Sowe0!C?S+d07aJ~STrRjAvv*HR6ZW*iX^7Jnr#Y?`xEkSVht;%urdoH;bOyR- zIvd?Hotf^L&QkYGXRLdsGg(a2n#Y#c7VK1+GT;+y1X}_C52uzwqpR z&%EP3pS|yyH@*B>`=0ri&wSRtXa3M_pSACqr~cX5`<{8Hcb&cOnHT-k+54V(`ODAV z_e}QgnbvpD;O;9|qYjLQX=WA^TuX~LdXI1O>y;xxzA0#_p}ukM*@ z+C5XPyJtEB-7}qy?wQU^_e^K0d!{qiJ=2-2UptfY{ za5ci!4y$SROttQw=?rwwbT+zYIy2ofou%%X&RF+MXR`R6Nwu>Vd-qK1yJzy#J(K_L znfC3TDW2|`;_RL&{_1kHUUBEP`u1A(eB$=P#ejb>`itiL^f`~Uc*=kI;re(w4HJuW}j zefIhOJubf56OthE|^E1(6`pnNni|IB$6D_9a{7kf%&hs50RxZ9N_GL!bQ9t$pcP zJajHj`WL^tl$UyyFMB#zpFaGg8~^EP-*gsF`irx=h<|=pa#dchJz)9H?@G1~^ShG8 z^qJq4ET-H1u4FMi=XWKG={&zHS*%|3yOPD~HNOK|tX}i`uWg^-i|zIE`?AIS%+>0n7^S~OrQB1 zs>O7hzoA-8&-ojw#dMy(p<1k7^EXtB)ocDXY_WRH-^FeF{Jq>>KYvHJn4kIky2bp@ z-`y>?@BBU9V)4x1=`9xL{9WH-^_suyTdZE$<=c8XpvRJ+5`!d@;-=kS<{d~V>F+cOYo5lRU>Xrv=-}#=- zvWsWFzq44q=KDU2#XsNoS*%{!<=c8X;+*fotX#xD-~HTq&38f<%Xhx}xtI>~-Ot7JneTosrrTS8?H-Hi zIp6(UOy~LT=VJQLcRv@a*L_kS1jGv5nd%>R5}c(Hxwd&G;y zGv6;>EYA5p@?!DN_mLN?S9bZfo(}n;PyW|AKirp|#Y5-fq<`_NOL?hR`Ld^j_36V; zy78Z$_DyH;q`x?;i}+_Y#m;MHR_uIdHpOB(%xsFq^qJWdi|IDADHhXnW>YMt^US7L ztX?ylVzGM7%#FqBHS(hsybmKog?VHZxNq=!x z7xB;RtgG^R)d9&RVQqGZSpF zdd)nvZJ#-5d;QE$Tg=bQRa?ye%v)P*-&*GtTanir|)up`Dt9;qh!TR*!C*Al@Py42`c+y{-GwW>SBL11}x$~Nt zpF7`~?YWo^Guv}9eP*`jV!F+2&&Bkd*`AB(JhMF)tJlo-T&!L*vvjd~&AirapE<63 z{mge=%+JhyUCjT?gI#RjC;!ngi^VhZV;75a=FKivubDTySiQ2#xAk<$4}J1axAvuH z@zA+A>0kWnQeNs+zU=8>efsc|Zv3aGebZSy=`YUeBL0~@epOztJYf0G?D4I`%pPA% zpP4h-!GK4A5l&s~;Xz5eC(S6|FNbLRK@nLodnpP5U) znE#nqzu3Mr$Nm&Q`-^Ah+b>qHnTNkv{4)=Kv3g~fZ|muhANu5fo%6$e=~+B8Lv zzq*u{dX+DGI#{1R{G=QI>1p3|7Ek(%b7sY_+{Hi7M%j7IGgEfH^K6vGbeLzOET+#q z8)Y%w{_U{`OwV~X%CggWo{h3tz2?~{i`8YG`LbBO=6N^UKF`6~>*x76i}{)7<}Bua zo~N_ezVn=&#p0Rg?<^MQJg;Z5dd>5C7OPiw`L>=8`Jqq#>DIpVEFL-+C;f|GUCK+n z%9lMItWO_)(vAQ0v~N0#C;i1)UBo}nZrgdyGu?K+^X#_8beLziEvC;ryKOPu=GkqF z={e7CTTJJ9cH3h0nrF8yRQY|nRle-$V14@V zlWzQ{r+w2|Jn1ja>LUJmw(QPpo;kboooCA~ro%j2b}@bC*|Ll2HqVw_OwW0?>|#34 zvt<{n*F0Nxv3kwtm5bGDo)^6B^Bm#5ex5J9n4fv>@M8YwdBltDJI^UzES`CO@nUg) z;ra)xUh}-;Wmm84@@+jG^0UtKp?|uyFFlKg&c#Xp;#ZgQQm^u5PY3JMho5xgKRxZ6 z&f-abaaI@cfAGXN@4Wuy#s@6l<394Ht;6S@bHMa@-sgXI+3EJPk33*{p8hj$Ty{F& z{CD24SiK(i_vbBEulWpnv3lM5PCv8lPdxMWd;L9L^t#3TeEfYsy_o-NoOr0kWnQeNs+zU=8> zefsc|Zv3aGebZSy=`YUeBK}9;?#FjtFFE#r<@?qT|JbtA;RVk=VESC^pI)-;bo=T@ z956jE|LGrHb~^w3|9J6Y_4>=dd(mR`deAWktX{u#(hIl!GvD%pz5XRv{`- zcrpLSKk)gB?R)!g`k}?*`S^>Uw^*FV-|&FN|Lnhb?y{>_cKNoR4*8)^{^{1f^ei4a z7bpFTUtP*ey~>w89js3ue$tKq^t5j}izofXSzW~czSADF^Sae74_LmBd;7O-9d7pj zJ$f;HZvDweEvDO(-~6qM>G>OXdgNj{KmI2lu~@x6{YMX5e9*tnT&!MCIpd6N|HpG5 zve&=H-W#r8e<8^3w6c>d|%pT1bV?t0w=7XK?gaoV!0S9bZf zo(}n;PyXrFzVs{}Iu|GXi(g&l^TV~5dX+DGI#{1R{G=QI>1p3|7Ek(%v$}}?iu>Gt z=XJN^4p_ctzvXsYhdX`ps}|Ge?jO7DV!HjvdAC_i&kvq>!eTl<>nCotSiQdZq2m`H zydU0Tv3kAmfj8gw>%RIc_WBDxceBO(T={~VF6RFM-*}V7_I>!hZoF7L*L&WL7OU3- zuX(`YfAbZ`F1vbVmv8IokRSTwpKk3-&*GtTanir|)n$HOUVEum`Ld^j_36V;y78Z$ z_DyH;q`x?;i}*iv&ZkcHvy8mXy~6>^_r|Aua@pzd;)_4Am_Dz4*T)yr?WDW>$zpoG z@3fCDrt{5i@P~`l>vnJa(BgxCUzaUbuRFi&1KWPe&ELP*zv2_WwV0oi{?~t9%>PAa zzh|+1e|P@myq~}B^H&!y7Uw1ZcF|(-Kkc0dEU)bHZ9N_GL!bQ9t$pcPJajHj`WOGf zzpsP5)T?~i)4}@m;V0erPfz=%vv|^9oYh7Ax4PmvD@S>~=#&GN@AJR+*;|Llea|x& ztJg~&_VmSc`^5*HwV0ltI_HUt>HMN=KW?#lz4;E0T739^xLCd3^=}W@_RDU4zrFrx z@4WY7etz+ayDjGbgMaX~i|zZl-@Mae@qG9_CoNX5%l`7j#p1u~gAZ6<+2z}MI^>5w z`KMd^(zAHzT%7bT{)2j*x%O4B@?}p4>(hsybmKog?VHZxNq=!x7x91OgxlV`e_v00 z+pQPN_aP5HZZREx@AMlirq30B_l0{|Pq!<7{qn{1{KyG!Sxo0w-}&*2)$1SM_-Ef> zy?QoM&eezGY_N8a>(78D2U;OHF`nSGm<)vQb%bpI_rw>2r#(#R+H=V_k{^G1I;-7PP zvD^>O;bQsDIb2MKIfsksGv{#e`uBCk-4@ex&f#J@&pBL7|2cVi&&{>Q5pL4j_zH<&2i)YT^VsXwnTrB>1-&lP3zOh)ot*1kN=#&5T@9S`1 zdKM3ziU%w$JUtX+U+10D{bjS~V@=v$+rDyTbxj5-x{0H^A zZ0)69<;$K9)~63Y>BfJ0+BcoWlm6nYF5;hi)Fu7Jn)T?~i)4}@m;V0er zPfz=%vv|^9oYh7A^K;71Ykp4I`OeQNi|H^wr!1z={G76wZu4`>VtUTcDU0bmKc_5K zulYG;@!|X7V)dGzQ?`A6PTA|{=aj|#%+D!{`JbOt7Tb4zPFXCT`8j2=IOpe-#p*Rb zS1wks?DB0r9r8n;{L`&{=~+B8Lv|G~enGuK|~Rle-$V14@VlWzQ{r+w2|Jn1ja z>LUL69AM`)p9AcC=W~F?bePWp7Sm@w2UtwE`5a&|J?C?P#dMy}0T!#*d=9W!z25w`KMd^(zAHzT%7bTesw7?^(tTXbg({s_(?bZ)6>4`ES~fiXLS+(e9pG>n$OvG zzVkWTVmi#{Y>VkLpR+Bd+kDQpn4a@F+hRJ;=WL7BYd&XNeDHpF-eUEd&)K$pK4;tO z=X18j{LJTUi}|0=*%sS(K4)7jp81?@u{h^*w#Di-pNlS5uk7+|Jst8xpZwFUed$>| zbS_T%7r(mvmm41BqF&|8o(|Th4?pR~e|p+CoyC*>;;b&>pU<&(Uh_Hj&UZe?UQCDi z9D6Z+=5zAJbeqqy7t?b-$6ie5`5b$(dd=t9i`8pB$6l;n^Evjm&*#{C{d|tSn4kF^ zdolm>Ird`v&ga;R#WSB{FBa!~j=fmD=JyVZ)hoMvTTh4l&?o85@ z<)vQb%bpI_rw>2r#(#R+H=V_k{^G1I;-B9W?Y!pqL_6R4J<(!1%Xlu-t*1kN=#ziCwJ$x3ht9=G|KeAd`Tf`0OTEgM zJsqr1AAZt}|MawPI*TX$#aUg%Kfj0FdCl)(cfRv`*u`|1-@`7Z&-@;CG2Q0(u#4$A zzlU8+=lMPCV)dHe!!A~@`917n^_t(qZu|TmcCVk`!!G7$eh<5t|M@-aV*AeTVHb;M zeh<4?ob!9w#p*S`H(#t?+2z}MI^<`a=R^N=YhQX651osX{>85@<)vQb%bpI_rw>2r z#(#R+H=V_k{^G1I;-9~B*m=$0IqZDr?;IA>VgAlxF@5Im94>YLr`!B}#bSES-#IL% z^ZcE|V)dH8b6Bii^LGx5)ocFFVcR`xo=@vNgC6ta+4Puy&#Z4>&$7qj@r-*c&iOls z#p*SGm$F#Bvdg#ibjS~V@=v$+rDyTbxj5-x{OVF(>Q%n%>0o{O@RM%*r>A|>Sv=`4 z&gvq5&#jj4%IoC^EML#9PKWtBqQ&&_+-i39^4w}nPtUE!boSh8On=X<#_Hvn&RD&E zf1dlC-LsNg?-|ONAJ10C{Cnmywy$R~WAS)KGgdFpbjITMOlK^w?DB0r9r8n;{L`&{ z=~+B8Lvzq*u{dX+DGI#{1R{G=QI>1p3|7Ek(%({sku3W5Mp6O`~yJvm2-ZMb+=8o=IvAeezGY_N8a>(78D2U;OG)Ug}l8 z?CD^A`tXx({HLdV(^)*}FV5;Be$NfudCjvC%hz)QF&#WN5YxwV12Nq^HxSd)a|5w@ z&ELT;Rxi&DWLFo@)WhoKnRMAbs}5W58FrW-&$h$-d*&UsuV>+5@pwia7N=+GVfFG% zJ*-~Y<=c8X;`E$H zxrpC$ugc5wu*%nSuP_}v_X^X;bFVPnJogII({rydojvyo)8BKiuzGnW6jm?KRLbsI zORe_|Cd|+Lo%v$^J+q13zMkcT#p4-ISe%{-h1JV5p|E;omv8IokRSTwf1UHged$>| zbS_T%7r(lcmwJ^idpcO3KK!H`|LJMpbQVwgi?h0j-*a2a%kx~y*K=Di9Ud{yror@? z?{O@qo9DK$)6;WXFr7WO1*@0mwqW)0OcShLo(YoOvqD<$86ub;&lbV_d*%qXuV;~9 z@pwiF7UwbZd={);o@s*BE4zGKPlx=_C;xP7UwRe~or{zH#jh^qrC#OBo(|Th4?pR~ ze|p+CoyC*>;;b&>H~)O+H8bAJ*Zgx#2lLM{edc>oi|IDslUhtq^UtlJv-#&(z2w89js3ue$tKq^t5j}izofXX0^#4rkgpUn4ac{V)Zgd6swmxqFBAm*u?5J-$UGXvnyL~rX}XbtV_(l z8JO6*uK4zxdUqywt0F+0()L z^x-Gn_)ky!rn7j`U!2uN{N{1(yk_QD`I^Ut>0llgrjL1Cm~Q9K%rQ()^SCgb&EvxA zWgZt+ulb(uV)ZiXDZ3d^tv4GA^J8Wd=Ko)3UKX~m8B=8`Jqq#*Ev7jm!8E#=i;P)@vBRDsaN^3r-SwB!%w>LpPu$jXYr)JIL%L!i}=m8 zC@=Fa%GX>AOb2r0kWnQeNs+ zzU=8>efsc|Zv3aGebZSy=`YUeB7U(Srg_zupjEMm_FtY zu+z<40!&Zy3NW3`F~IaU-vF!2=&)FQ&3|A&tnXs=HUA;IxeC~N^A_@B{sZRU{0D4b z^B=Hy%zwb*H0J?}-~0zGuk7?`J>Bv{&-~N5ed%93>QbEQRs4tbU3;l-`Ld^j_36V; zy78Z$_DyH;q`x@Le~^p#&3`B_a|X(H-e(rm!CV4%`po;xV!D}Qz)nx|4X}Eddw}V0 z9s)jm|6HtI<|kw~SE2RhEnt4;eP%KL<}Sg`|RxZ9N_G zL!bQ9t$pcPJajHj`WL^tnEzle^(tTXbg({s_(?bZ)6>4`ES~fiXLS+3`42mhxUp5_~1I-7fd)oc3rV)Zg7fnB}KPr&TvDzx6b11^%+ zRe zZ|muhANu53@@+jG@1nuK4zxdUqywt0F+0()L^x-Gn_)ky!rn7j`U!2uN{N_KD zmpKFFYyJSHgSiBlKIRo*x|w5u>1nu)0_vaUgkew^~x^a*3%(B^vOTn+LxZiL+9e8fAOnJd8t?V zvZsUf>BCRD@t>adO=t0>zc{Ol_|1RVdCi=G@-=?|)4^Nw89js3ue$tKq^t5j}izofXY5s#;#BcsX zd6_d%zUB{LI+#m<>0@32rkgnin4abvVD&Qh0IS#h9&oXGnUlb-UgjrYc5@Y4Z{7mt z#~cRCzxfQ5w`KMd^(zAHzT%7bTesw7? z^(tTXbg({s_(?bZ)6>4`ES~fiXLS+(Ob2rbFn!D`z;rXm0MpZa z159Ug53qW@ZstE=bulLatJlBG{DZ?B*)8 z-n<3Ok2wsOfAblzea&sa;xW$wi_@G3tX}3nVD-u_-`3M1KlI5z-P)I)#Y5-fq<`_N zOL?hR`Ld^j_36V;y78Z$_DyH;q`x?;i}=ldC@*sc%Gdk>Ob2rbFn!D`z;rXm0MpZa z159Ug53qWfhk(_~oCK_1<|kx7W9C1!-n<3Ok2wsOfAblzea&sa;xW$wi_@G3tX}3n zVD-u_-`3M1KlI5z-P)I)#Y5-fq<`_NOL?hR`Ld^j_36V;y78Z$_DyH;q`x?;i}=ld zC@*sc%6I+_b1@y}?=TnB$Gie-=w^-qrl;;b&>H~*o$%o!+O^9L{;%q76|F|PpA%^U+v zPxB2hoy|SK>SZ1RRtv7E0^J5MJ=HGkN5MRz0|9G+0()L^x-Gn_)ky!rn7j`U!2uN z{N_KDmpKFFYyJSHgSiBlKIRo*y3O|p7Sq#w19m!_dw|u;JOr#><|JVCGCv`^xeBd+ z$;^Mi{FuXl`9FT(hsybmKog?VHZxNq=!x7xA0_P+sN?l&|>%m=5L=VEUL>fazwA z0j8(<2AIy~9$@t{4*?(auQL~`m-z|V%~fcXlu-t*1kN=#ziCwJ$x3ht9=G|KeAd`TTJ0rC#OBo(|Th4?pR~e|p+CoyC*> z;;b&>H~*o$%o!+O^9L{;%q76|F|PpA%^U+vPxB2hoy|SK>SZ1RK6pR8#bWg`KOwuh z3avM90rO)H1Log+25et*8?boHbHL&>=K-si`43pVvdg#ibjS~V@=v$+rDyTbxj5-x z{OU44FR#7St9;qh!TR*!C*Al@Py42`c+y{-)kXZ~Ka`g_1LbS}0H%Yv1eiYN6=1rV zV}R*tz5%AQxd&Li%tOEj|Gq9;tX}3PWH(o#_2w;Le#~LO{F~2!?Q3oW7LR!jSe)iO zVD&Qp0jpPb`L>=8`Jqq#>DIpVEFL-+C;f~6;NRClUg}l8?CD^A`tXx({HLdV(^)*} zFV5;Be)Av7%bbDoHGcrp!CV4NAM*+@-OMq-^fcc9)7jhutX}3J;KTRB#p?C0ng5X8 zT!q$~w}AOEhXM0%J_EL|xeZu6<~d+-n)86w%lrqdUfJc_dOGBXKKZ9x`_i*`=vukvM22kX;^pLF9tJ?)#$;z@sTRu}P`|4?4$43w|=1DFox5@7n6SAgke zjsd2p`39KI<{n`6G7kZ(*PoyH>YvBzWqv|-a}`=|-U8;w90tt4`3%^;<~CsQnCF1S zY0d*yFY_O;dS#by>*uK4zxdVVT|a#8%1gb0@32UjM#kjsd2p`39KI<{n`6nsd1L@ZZ;B z^)f%f8g_FPT5sM$e&!r5=HGk2;0~V+G4_Lj-f57UMUB0cSLw@L!|Ml6Xz?`!R)UggW44%Vm7`uBCH8~^EP-*gsF`irx=h~NB&@-kb5b#00E?cZ#<|kw~SE2RhEnt4kVZi*G&w%Y~ zZUYvNc@9{d<~(5aGXDXqS9bZfo(}n;PyXrFzVs{}Iu|GXi~pcr2YIPi`Ld^j_36V; zy78Z$_DyH;q`x?;i}=ldC@*sc%Gdk>Ob2rbFn!D`z;rXm0MpZa159Ug53qWfhk(^< z?oo@?%lw4w<|?$_{0GdBISiP8^BJ&x&27NqG0y>u)0_vaUgkew^~x^a*3%(B^vOTn z+IOA*!+7Xiob)e#bty0PDqr?=us(hGNjLt})4u5}p7a-IbrHY$59MXfK>3oM&eezGY_N8a>(78D2U;GFEzRp~GsaN^3r-SwB!%w>L zpPu$jXYr)JIID~J&3`B_a|X)S`~ge{a|tkgj(_0u7t_rg19p1O=Kzc8Z0-TOdYOlS z)ytd&tX}3PWH(o#_2w;Le&%z4#r&Jkz;0i28?boHbHL&>=K-si`43pVvdg#ibjS~V z@=v$+rDyTbxj5-x{OVF(>Q%n%>0o{O@RM%*AAhK)ebZSy=`YUeB7XB9%FCRA@-=?| z)4^Nf1e!}Auam-z|V%~fcXlu-t*1kN=#ziCwJ$x3ht9=G|KeAd*=OygUggW44%Vj+ zKk3GQdfGRg#gqQxtS;g=|Dn9h87SZR9D6Yx=5y@D^f9l%8oHTdfaz(z0j9IL2Uxw# zL%`}~P6Adh^Aob0tI&G$7BD~NFkt@8XTbKI&#@PaXFkVXEKYMCtWhuXAFz65mv8Io zkRSTwpKk3-&*GtTanir|)up`Dt9;qh!TR*!C*Al@Py42`c+y{-)kXZ~Ka`g_1LbS} z0H%Yv1eiYN6=1rVV}R*tz5%B588iO@tCx8Q_@IAXwphK)PsnbrLhH?2!2FoQfcZC{ z0o&Ky1}q-)9I!aedBEyr{sUI8?DB0r9r8n;{L`&{=~+B8Lvzq*+JU@!G5U-opc zK7IH}H~!PpzUeHU^cQD!5x@Bl!5`I0mAarjL0Am~Q46V0xNwfaz@R0ah>b z5U_g9?_n3Km-z|V%~fcXlu-t*1kN z)_FekPq+4^XYtUvIO$*f>QY|nRle-$V14@VlWzQ{r+w2|Jn1ja>LPygAIi&|f$}wf z0Mo%-0!$zC3NYQwF~IaR-vHCu+yks$^LGx5)ytd&cJ-RSbJ%us6=8 z`Jqq#>DIpVEFL-+C;f|GUCK+n%9lMItWO_)(vAQ0v~N0#C;i1~{)1e^Z~jAhnKMwn z<_};xm`i}^V_pHKn>hxUp5_~1I-7fd)ocDvZ?SsK&y|bS%lrgu*v(aFy?G1yF^2*3 zZ$1OIuel9aJmxuIahmgh)yw<`tX|pW+j=_Whd%kITl>65U^3BW+t=I%EFSY5usF?m!0KiG16Hr>@@+jG@e zZ|muhANu531n=!HFP%j0IS!0PinDxnUlb-Uh_SvZ8uk;_2w<) z$NUG(zxfQBCRD@t>adO=t0>zc|f*kc;@ue<&|=2Flm`0Za#T2{3)kE5LL!#{kpQ zd;_dr<{n`6G7kZ(mpKVoz2&;uh{FuXl`8S^d+t=I%ES_U${sR`LIS*L9 z%zwb@m0iBAr$c_|lYhFkFFlKg&c#Xp;#ZgQQm^u5PY3JMho5xgKRxZ6&f-abaaI@c zoBy!$nmGgIYyJSHgSiBlKIRo*x}87sA22=5H^6i@_W-Mxc?ej&%t^rNWqv|-a}`=| z-U8;w{0Geczs~#zY+rL5uy`Ia^B=G{&3VA;W&Q(Juk7+|Jst8xpZu?Lez-3^i-*p| zN&n(km-14t@?}p4>(hsybmKog?VHZxNq=#g{~#CfoBvQ=<_wgt`2&~^<`Q7~m{)-5 zW{v@-r}+k$&gLFq^)e3utCu+mSiQ_o$Ufhr-|Nj=VCTmi2F$5w1#Jn)T?~i)4}@m;V0erPfz=%vv|^9 zoYh7A2S1zN;*|N!^3szZ{>4k~aq97l&wbD5FL}~?Z@u{9b3c2@XJ2&t#c#OgUtjVS zXMWA%pS;^&T=I2)caO#Ydd8p449xp4{)VT2{F2*#??V^A>6icHlBd1wv5P--lRvp+ z&f>Oz@aN9i>u>PgFIvpcr(f~X#r$9ERZT#o|2c*Iu_+{MR_= zXBHoR=J0>;4Sw*~R*u%-UW@aI+Y1*1E;cMjF=IK(1(#!XxwoDsIIVCR;~weDEEdTP#1%zT&f|I2(N4;%WbUinDRx|BI(M8~A#!x%#Qj z27cAQUgK0}1OM@7u63%jfiHRdm!9fu;OpM^I;YYHfBF^IIn~+7?rgN)*}(ib8<>A} z!S+=z{Q1{@@f2qRi__V_;&(RiL0;!A{_hX{D{OP_2=KR&ZpTvmtOC! zi>KG0`m?7Uu-QKE{rLkn+vn6f{QO#Dw$E|zKVY+cp7G*eIC$;MR(j*Z-nQ6mpU2$! z?TgJ~ntv19{?q?(z-9qG@`LYKc79%X-Y+fY|0Cb}%Zu&%pZ@uP#q+h#`;}!E=fC^t z0gL}`H$8vZ<#nBt4%jTC>}DLb-t43Nn2D5svy$4^45i{RTd6qBTq=IEn97U2e63Fh ze$t2kbhB@IiYJ}Lnf~IhE=TJXt7)~v)ecuXTwZqj8S36woaJ9qL4p%!|?Qpfj)ecv?>}uEgbf|Xh)ecuXT$4Zj>*NO-ayO<_l{h0%%)w`em56e!&UwH06EvD^FzWDjYG=KJAeBt1= zQ@ayy^~J?%cg#0mZT(wNyZL!wG5bp|zs6#fAf#8 zyI4HG{-@VlEY2(6bp6HRf6vX1SuC&bJN1C&o}DJGr&WGvn19-~FU^Zb?TSlLeMwZqj8S36woaJ9qL4y%QjakazMF1y@Y zPZM12aJ9qL4p%!|?Qpfj)ecuXTwZqj8SG(+L*ZOp*cI?&ee=~LG z@!DVGq5ln`NP=kji5lz3Af^gQ@$6ke%tblI8akLMr3fin^H@h>h#^{2C+$hq@#`Sj z&vAa*YE@~(TrG;ys_C?}#{Aaj-p~8W{om)cUMttS*7do+>srsw-uE}=F6J)gF6J)Y z_O;IGxo7sBgzhtaC!u>z-%05H({~cO7kzJi$D{jF-%02mwSM+E_p82>(7mhgkaQnw z+&!)N?r+6$uPeU$UhBFCmXG^kdAc{2zx!nSa?k8L7>)PcjOO>9jpD4IRZjfARg`cU;eyo`@%WpF6J)gF6J)g zF6J)gF6J)g&bWIfca3uwa~E?La~E?La~E?La~E?La~E?La~E?La~E?Lb7$N=le@;b zi@A%ri@A%ri@A%peZ}sX?cIH*nz-jwEBBvj=w4K9-IuDldsHsmuX5+!mAkdxrXMx# zp4NQ#x8k_h72kcYb=?EY$NjK8-5bl_eX@PIXSR3a)x`X2B~CRIzuH>2n#(5_^30w5 zb7xHC@e_pnI;hb_8a~E?La~E?La~E?La~E@G+&z=K z#<`2Ri@A%ri@A%ri@A%ri@A%ri@A%ri@A%ri@A%rGwzkh?rF_;e=ClAUGd%bTGu_W zeB2Mq)4j3$-6z|ZduDq#UQNueR^n7c@vE(MtGRq~A-kxcxR?9g3qq#aFl1 zRnPKK=kiql^5okZQZ`JT0VW3wLJTdYx(!x*Y?%8 z{Wjk{vpDKge06JG^(-HCE>HC@fA`F7UpS}S#oWc*#oWc*#oWc*#oWc*8F$a*u5s>S z?qcp@?qcp@?qcp@?qcp@?qcp@?qcp@?qcp@?u@%1a zy}Qp;6Zf2I<^EF*-HWQN`%*P`kIIGnRqouoa<`uO%{{Ym_q67_zZJ*5uK4bIt?M3G zKJJI*>E2lW?vw4yJ+r+VuO{YKD{-o!_|?|B)m%QgkZ11XpF8_%+x?&dzW#@*AJ@BUUC_qyV{@3pRbVEMQomZy7T`MXcHFZay$ zZoHb9U#-NchT>OS>sE95oyCe|iUmdr|Lza9`>j z5bjayca`UU)jJ^EyLxAb`&i@dY0Yaan|oPPyF?}&9iRr+K^B0;E-qU=8%8y?69xK?YH^vnZ;3`;;UQhs%QDA zb9t(N`MYOs`@%WpF6J)gF6J)gF6J)gF6J)g&bWIfca3uwa~E?La~E?La~E?La~E?L za~E?La~E?La~E?Lb7$N=le@;bi@A%ri@A%ri@A%peZ}sX?cIH*nz-jwEBBvj=w4K9 z-IuDldsHsmuX5+!l{@#b#@*AJ@BUUC_qyV{@3pRbVEMQomZy7T`MXcHFZay$ZoHb9 zU#-NchT>OS>sE956}wQ~QdhVDhx)_tj(yGP~1{VI3vUAc1~ zYur7p`R;GUajz@B`(Eq12bPcfVR^bYmcRRC`*P20@5ZZ%`PE9CYAAlSwQe<+PcGz{ zJNf6%z8bgR=Bq<-)Tj9B*1GChKI&Ya>RD^WCIla5e{ikbPxr?1ch78J?wP%-%XshbGQW3wiPO8r#P3~T)?I(| zIQjJMFnRV)G5PndG5c!VJ+t}hP#pCszPh!pdX|qmm#6xdKQG(9a89|4xr@1rxr@1r zxr@1rxr@0o?w-kAS z?qcp@?qcp@?&57@q>#Aq@sB?L$fBEyW?F;9WyO_I}yO_I}yO_I}yO_I}JLCEtca3uwa~E?L za~E?La~E?La~E?La~E?La~E?La~E?Lb7x$?-LUC`Sk8ZdG=05`S-3y z`)b^No39SVQJ> zU3+(~RukuKwQ>$uL+5j~b#7O4=Xoxi^SN{W=T2W}T)$|(K2jY0rTF?z>*`14qfeEm z{#E|^TKm%P+Pm>;Vt%y}ry7c1ZLM3)<&z6}=1%^(v#-YOxB2Q&9Q7%_y0xx)mXA7@ zr}~#aFWbIwPPvP@i@A%ri@A%ri@A%ri@7td-*MMCcQJP{cQJP{cQJP{cQJP{cQJP{ zcQJP{cQJP{cQJRy^*inw=Pu?h<}T(g<}T(g-uBhIQ}w&vo$6fe-Koyo-ks_k?%k=* z=iZ&_-0t0}&hy@#>YVT0sm}l2b*nElu3t1?A1RLhQhfccb@ik2(WlB&|0;idt$pct zy(`xE`)_jG%le+}M~b7r6kp$IUHzzh^r`aHzsg@vVooblelZGP|O7N>WG zi{HDvt=l`k<U3+(~RukuKwQ>$uL+5j~b#7O4=Xoxi^SN{W=WhDK z8rLtHua6W*e<{Ac)4KXm`RG&SsehHfzSh3#p1G5M z?(C~^`)$5D6i0oEuWqfYp5>#?<*EMV&&#$ioKx;%?qcp@?qcp@?qcp@?qcqY>v!BW z&Rxu1%w5b~%w5b~%w5b~%w5b~%w5b~%w5b~%w5c#as7_F#<`2Ri@A%ri@A%ri?@BP z@1~x9x4yG_&eio@)^pyj@3@|GczyTvoX_h!vFF@g-<3V*`T7p+Ip^1RYtQ+=zH@u} zLgV^H^YxM9=r6_BcUo6JDj$8SJoT^g*YDbwez(4Jd&bvyZqNMno!b*ptq^M@&BJJGUp#^_|<3|N4&f*;nKGUGw$3;^=q9*Y8?azbha8t~~X-^4IUSec_yP z7jqYL7jqYL7jqYL7jqYLXI#JIu5s>S?qcp@?qcp@?qcp@?qcp@?qcp@?qcp@?qcp@ z?u_eq+%?W!%w5b~%w5b~%w4?gE7tGYyK}XgIB%zx;XG_JwoGUCdp~UCdp~UCdp~UCdp~opJq+ zyT-YTxr@1rxr@1rxr@1rxr@1rxr@1rxr@1rxr@1rxihZcao0F^F?TU{F?TU{F?aE{ zul0GEe)rmETw>1E^{$OMZ`V6G<{Vz{=9u$&y|ZJ^?e#8?InUQSKIWWX@BWzcf4vjr zqQ0=k^}FWlcg4}~im%_bu6|cO`dxYIcjd3&wJ-hdJFmO=jIVcs%>4CEkcqS22{Q55 zJ3(gM^-ho-`K)(>?8tMy6J$sJ>m4rrZPVuOn;O^eny=p#N53n+e%HGCUHRyD<*DD5 zzkavv3+I%(n7f#}n7f#}n7f#}n7f!eS?qcp@?qcp@?&57uo-tjq4Z9*GGz@zZ75JXKuw=VjX$&M9{>cQJP{cQJP{ zcQJP{cQJRy^*inw=Pu?h<}T(g<}T(g<}T(g<}T(g<}T(g<}T(g<}T*WxPHf7Y|j7n&a&wXjq4Z9*GGz@zZ74;YhC@WeDu5W)bGk)ziVIm-Fj!)jIVc= z&HVMwvWc_aSvK+4JIiL>_0F=%XT7s*@?7sMoBY>1=4M}w>vzr9?~0?}6<^(2S3S!| zoy$}G%b%BRUpS}S#oWc*#oWc*#oWc*#oWc*8Q1T)Yn;27yO_I}yO_I}yO_I}yO_I} zyO_I}yO_I}yO_I}JLCEtca3uwa~E?La~E?La~E&>iuJqp?p&=V&f99`9Il4W=W6TR zuIA43TsY@*=lsvzdgeF%u5taM`T9t4^q1o6JFTl9m5)AEp88k$>uc>xziaQttBLv5 zN}Osaezmo3HJ48=RCSOT%PJ*{=97a!a3zG<}T(g z<}T(g<}T(g<}T*WxPHf7c(>b@-yHMvm zU++krbAG)$b-xXiKYhC@WeDu5W)bGk)ziVIm-Fm0$jNk3v zADH>;ovIUOy;F7KuXn1>y6c^)lh1mm>g2iJsXF#p1G5M?(C~^`)$5D6i0oEuWqfYp5>#?<*EMV&&#$ioKx;%?qcp@ z?qcp@?qcp@?qcqY>v!BW&Rxu1%w5b~%w5b~%w5b~%w5b~%w5b~%w5b~%w5c#as7_F z#<`2Ri@A%ri@A%ri?@BPca==PTklMtb9KE-ea_qUj`cZ**Spu}d|vNlpL2V?t9{P% z^$zzr=hwU4=loyqe4oD1xPI4s{jNCrUGeq1*46LIN53mi{jU7=yY{8ut#`i9_g~s)Z=IbNH(O-(M@3gLdR6hDtdFo%~udlT){jR+muO{YK zD{-o!_|?|B)m%QgkZ11XpF8_%+S?qcp@?qcp@?&57<>z#qq?;iY(v*%pB+TXrm&fD9+{x{|v{>^*;=A6%`f9p5r z-2UcM-#F*_(VuwZob%uL;Wy3s|AAxQG<~6Q{jT}?U2*ig;_G*t_DR&wlO1`Sg2VGx0BZ>}zJ-7rynZ$>*WBJ8SZM?q$!K{NMh~ z%{#%`+rh^5yXNb6#nJDIuiv$@q z>#Aq@sB?L$fBEyW?F;9WyO_I}yO_I}yO_I}yO_I}JLCEtca3uwa~E?La~E?La~E?L za~E?La~E?La~E?La~E?Lb7x$?v!!-zx(~;pEcuO`>9`>`OmxXnG@&3FMh_vzs8-O zKIS?qcp@?qcp@?qcp@?qcp@?qcp@?qcp@ z?lyA{xr@0ouHSLjICq;lhup>7#oWc*#oWc)zGD5Zy*pQ{iSxEvIftvE^SRnOx2w7H zJQvRS+&TYqr!O?FUo>AIDUSY9e0`^N^`r99r^-|RDt~>ged%}Y-FP)Izgme?4aLu$ zb*s62av{&2FZt)rz8bgR=Bq<-)Tj9B*1GChKI&Ya>Rn^3?CjU%zW# z`rTvhcDEV-_gCL_=D+Sccb+)^^1M4u{F~nHjQ={p5M#Wp6+Ezx1=G z&b}Jg@0zdQ6-U1-zJAxb`d#_xcjc+ymA`(s?F;9WyO_I}yO_I}yO_I}yO_I}JLCEt zca3uwa~E?La~E?La~E?La~E?La~E?La~E?La~E?Lb7x$?OS>sE95XTn`tvPQ$ zaO`#F9RAg_e{9a@lm79#b8g?@bN_A5^C!LKdUMX-{ODum{QuOgkD0#ExPI4s{jNCr zUGeq1*46LIN53mi{jU7=yY_XN+G%2WR;e|@ce>38kjcr`J*H{ zg*PETEDw;z~3WW?>8o#&e#)VO}veEqIC`d#t$yVlk3%16H|PyMd^^}F_^ z-`(&<@1OCVtNr!Nf9YrcV&WYCU;p34Kle%Ro^?O?=!28bt^f7B$#d@q=T82Q`@?f* zUya*u^VOj^>Qj7mYhCp$A9XHI^)G*3wteB8au;(Ka~E?La~E?La~E?Lb7x$?5&vW6N&zcltu(`bG2gk>cnt#n*RQS3fEreX2b5 zukzQ|+LwOU-i=oi^Q)CO)lmFuYu#!tpIpc@ck<7jeKl^s%~yxws88|Lt##G2eAKx- z)xZ3C+4hBV%3aJ|%w5b~%w5b~%w5b~%$;%lj=RRWi@A%ri@A%ri@A%ri@A%ri@A%r zi@A%ri@A%ri@7td-*MMCcQJP{cQJP{cQJSIwy*VXz3F#vI_|!6u0H$H51#Y(^QS#@ z&f(v?^P}f{e%?<%e$MR&KkS$1Jb(JbpEBqCvv;04=l``n_0;JLjq7*K*YAp>-xXiK zYhC@WeDu5W)bGmwqJDRe>38q=!5wG(@2-8Dng6&yyw$|{y-(eI;(y>HH<@+6`G0OO z`F!-<$4{Pr_b{<5 zueR2$=JLsfJaZ@i+}T&-_S<}QD31CRU)@?)J2 z#oWc*#oWc*#oQU!@3?E6yO_I}yO_I}yO_Jp{6p?y?qcp@?l$uexr@1rxr@1rxr@0o zuHSLjICn93F?TU{F?TU{oB4;_#qYh#ufEm4@BaNa{^=IZ)iZDSkXt%$KXIM6+|oIG z;h&s;OXu^azWVK3I=4S``y+4VJiqH*j=q(1{-M8f?OQqjKXIMw-par48rScduiq6% zzbn3e*Sh*$`RI4$so#~qe)qc9KJKmleYeK{%=nuBF7sEMcZsv&zf1hJ?z^nJ@;O&N zE6;P~x$-|({%c?7Ztd$_`)$5D6i0oEuWqfYp5>#?<*EMV&&#$ioJa0r?qcp@?qcp@ z?qcp@?qcqY>v!BW&Rxu1%w5b~%w5b~%-x~!jk`nhH|}EYV(wz@V(wz@V(wz@jO%yY zHO^hkUCdp~UCdp~UA*lpc7C>Z=V~=^-c~E;a5Z#3S6kg~s)Z z=IbNH(O-(M@3gLdR6hDtdFo%~udn4!ziaQttBLv5N}Osaezmo3HJ48=Xqj?Z&wdJ&pEt$>v_)S)pO5tZm(W^p7VV5=<}TOtEZpm z{9ir&Jbj^Y{i6B$NOAO+;_ExDs~?q*K2@IjSNZE}?MuH~cbFMpcbl2N?mQD`-GwIp zx+BfH>+Ur9tUJ}@x$a<-|GIR+G%2WR;e|@dbq<+`ljaL)%tCcv_Q2c6Z-D)nM zT*xzb^3R=pHEzGnSBK)LPw~~Qb=9+c)VVy>zx;V=Uwq*_au;(KbGLDQ$X(1`%w5b~ z%w5c#as7_F#<`2Ri@A%ri@A%r+sr@YF6J)gF6M4C|B$~zlO^)uBux7W{F=R99O zgPn7J{mgdG|MfH5=?jhPcg@%Dilg5ZU%zWz{jPlUyYkfU%KxH%_jl9p*3YPCeEsZt z=C7Y=Pn`9$?uoyC20rVqpN&sG>u2VZ=lU7@UZU% z-<79+SN<3EyNi6SpG$At<&nFXyO_I}yO_I}yO_I}yO=xU`W<(Ta~E?La~E?La~E?L zw=X}>*{f^VDyMFg+@>#zVHF>Vzp_=^H?@-OY z8n@r(t3z?rr}*mDy6Raz>Rg`cU;eyo`@%WpF6J)gF6J)gF6J)gF6J)g&bWTZUE|!v z+{N6*+{N6*+{N6*+{N6*+{N6*+{N6*+{N6*+!@#JxNDrdn7f#}n7f#}n7eq}SFGQ) zcjsy~ao$!d=WsQ2K37}kb~SgN=fXLkJLiAy^o7Rti{|Si#nE4iukW<3epEjCRC(%O z<*%=`Fa55)8?PqjS1WO@q>#Aq@sB?L$ zfBEyW?F;9WyO_I}yO_I}yO_I}yO_I}JLCEtca3uwa~E?La~E?La~E?La~E?La~E?L za~E?La~E?Lb7x$?*{yqqu-UM zepmkbUHj7S*58=S`1;$EnZN!fW#X*ARhjtfZ&+sC^|vjP&-$B}$#eaU%;dlRMrQWa zxPI4s{jNCrUGeq1*46LIN53mi{jU7=yKP@Mr`*Nd#oWc*#oWc*#oWc*#oQU!@3?E6 zyO_I}yO_I}yO_I}yO_I}yO_I}yO_I}yO_I}yO=xU`W<(Ta~E?La~E?La~E?LZ~Kb% zyY}u}ttQUfYULcRhR)||>)fv9&huP2=X2-$&z-)|xPH-meWW=0OY!xc*42;7N1rNB z{j2=-wf3dowRhvy#QbU{PBj$2+FG}o%O@A|%$@vmXJ3umZ}ZimIOv!BW&Rxu1%w5b~%w5b~yzOiK?fLY(^*8BruCBjTpYwM84f~wK z>u=lVd|rQ3Kj-%PTlhK8*Wbv`IlsR5V9x*bH}%sO8rScduiq6%zbn3e*Sh*$`RI4$ zso#~qe%HP(bLj8y)^`ZZ`1)>vnZLesVB)OrBAEE=I|^pq_1y)N&-zY-$#Z=N!sNfc z17Y^nxPI4s{jNCrUGeq1*46LIN53mi{jU7=yKP@Mr`*Nd#oWc*#oWc*#oTS?9C8

S?qcp@?qcp@?&57<|NHW1PrqB= zIX36&`Yy6LZ`XH}%{jcjyKK(q^_^yOZm;h;oAZ2q2ilzT>pRot{9oUhHhrOS{jT}? zU2*ig;_G*$~G-{`yY2iL<_IZsM=+pqq8qchgNi z>pSZv&-ER5lmGgTyV+Oc`d#z&yW;3~#n5&vW6N&zcltu(`bG2g zk>cnt#n*RQS3fEreX2b5ukzQ|+LwOU-i=oi^Q)CO)lmFuYu#!tpIpc@ck<7jeKl^s z%~yxws88|Lt##G2eAKx-)xZ3C+4hBV%3aJ|%w5b~%w5b~%w5b~%$;%lj=RRWi@A%r zi@A%ri@A%ri@A%ri@A%ri@A%ri@A%ri@7td-*MMCcQJP{cQJP{cQJSIwy*Ww(bMnN zcS_H>y1r|A&fE1J)N>B6@1~yfd3|T~oZIWWtmiym-*G+X{I?JPqdEWAcVbUpXk5Q* zzJ6C6{jT`>UF+(1<)hz~r+!!d`d$0d@78yK&-nUo@R`59GkoH#?-HN*>pRA0-Syq$ zlh682^2u|3hxz2czQcU>)wq7weEqIC`d#t$yVlk3%16H|PyMd^^}B6fIH%mj+{N6* z+{N6*+{N6*+{N4(*YCJ%oV%F2n7f#}n7f#}n7f#}n7f#}n7f#}n7f#}n7f!e^|kh;-?ew+)x`X2B~CRIzuH>2n#(5_^30w5b7xHC@e_pnI;hb_8a~E?La~E?La~E?La~E@GT)*S4aqeR7 zV(wz@V(wz@V(wz@V(wz@V(wz@V(wz@V(wz@jO%yYHO^hkUCdp~UCdp~UA*mU{qD;2 zyY-xXiKYhC@WeDu5W)bGk)ziVIm-FnBvzr9?~0?}6<@z=UHz_n^tle+} zM~b7r6kp$IUHzzh^r`aHzsg@z%f9{;zl1PG4wTziYmJ zR~-GW`1)Pz>UZU%-<79+SN{54`_k{$JA7w+z1w%@uXp}Vob@i?iND?vJnOD^2Twlh zox+pndI$03zurMS`)XXjYrcM09R05N`d#blcjcqsm8X7J{`%dvFPu~EV(wz@V(wz@ zV(wz@V(wz@jO%yYHO^hkUCdp~UCdp~UCdp~UCdp~UCdp~UCdp~UCdp~opJq+yT-YT zxr@1rxr@1rxr?`b#rj=)cdk|w=WVre4p&3xbG3DDS99liE}ZkZbN=T}UuayvXudvD z9Q~#E`cCWWN9ChWm8bqy{`y+`((l^4@oHjzwGyWqieGK5Tg~N@3wh>F{<*WS#_hNH z>QEf@DZaY3u6mY_I+v&Vmp?DtzHm;ti@A%ri@A%ri@A%ri@A%rGp^rp*En}EcQJP{ zcQJP{cQJP{cQJP{cQJP{cQJP{cQJP{cgFQQ?i%MV<}T(g<}T(g<}Tj$wLUKg{XN2W zUU%_>&ef~m@ZtxZx0n9Qiyd?hfAWzRJLr6V>{Tyz(7FAfb1t0o{1$h+aL)Pr{qTiz z{y*=+A533pT)%6+epej*uK4<0>*{yqqu-UMepmkbUHj7SUi*wo%=l?vzQoM`^?P1& z;=Jn*FFEm#z1U&1?!!(w?4W#3d%|G{<@v>z9d=Ou=fCE#gZ|E#Aq@sB?L$fBEyW?F;9WyO_I}yO_I}yO_I}yO_I}JLCEtca3uwa~E?La~E?La~E?L za~E?La~E?La~E?La~E?Lb7x$?{AwjmH59+vTDO|ZCl~U}o&0lWUya*u^VOj^>Qj7mYhCp$A9XHI^)G*3wteB8 zau;(Ka~E?La~E?La~E?Lb7x$?|Ve&N=)ek3MqF z=ifQ{$T_zk_3G*CeGVxpQKhAC-?jRi64+`Ri-#OTTOH#;b|>)k>UdD1NoIZZ(%rF65az`RC5Q8n@r( zt3z?rr}*mDy6Raz>Rg`cU;eyo`@%WpF6J)gF6J)gF6J)gF6J)g&bWTZUE|!v+{N6* z+{N6*+{N6*+{N6*+{N6*+{N6*+{N6*+!@#JxNDrdn7f#}n7f#}n7eq}*ZNz$>35HR z!;j9ndd7`^bk5sf`KznVIehoWTy4(h&tC0nb8f%&6GzW^e&+8TJ?H#&UV8ML|0h5D z=;;fM>vzr9?~0?}6<@z=UHz_n^t^|kh;-?ew+)x`X2B~CRI zzuH>2n#(5_^30w5b7xHC@e_pnI;hb_8a~E?La~E?L za~E?La~E@GT)*S4aqeR7V(wz@V(wz@V(wz@V(wz@V(wz@V(wz@V(wz@jO%yYHO^hk zUCdp~UCdp~UA*n<+gCV#`rX@poVobwO-^<(Dzf8ukFxu`F!as96O`dxAKyW;D2t*hUakA7F4`d#_!ckN5R zyVJ9dpYdbAcKpoWxzF_{&ZGX<^(X$vE_uSNd*xG4n0$_X@(GjYS!bRw`9JII6J}qH z>vzr9?~0?}6<@z=UHz_n^tnU*WQg+6Z5N;IMq=6YHQtUE}vY;Gk5aOoqaWKzs*;N;;2vY)va~avwYOK zJk`JadD-@bbIM)JUCdp~UCdp~UCdp~UCfx&Q=lrW*cH*4>|MR&guC))n|89-zcg@%D zilg5ZU%zWz{jPlUyYkfU%3r^0U;5p1o_*4c|NPfan)y$?@5vMAt?xW};$P`fKQZgx z{q{dG`TX2deq!?c&?|mo@;~*{yqqu-UMepmkb-L@~B zQ|@B!V(wz@V(wz@V(wz@V(yIVcic73UCdp~UCdp~UCdp~UCdp~UCdp~UCdp~UCdp~ zUCfU3+(~RukuKwQ>$uL+5j~b#7O4=Xoxi^SN{W z=T2W}T)$|(K2jY0rTF?z>*`14qfeEm{#E|^TKm%P+Pm>;Vt%y}ry7c1ZLM3)<&z6} z=1%^(v#-YOxB2Q&9Q7%_y0xx)mXA7@r}~#aFWbIwPPvP@i@A%ri@A%ri@A%ri@7td z-*MMCcQJP{cQJP{cQJP{cQJP{cQJP{cQJP{cQJP{cQJRy^*inw=Pu?h<}T(g<}T(g z-uCtQE8TYb-L>9yn>klcIq^1g-k$LOQ|27L@NuWi`FzGTPnmQ3UjK0GInPh|pSPZK z{`~)O>pB0w_`F+BUuayvYrcM09R05N`d#blcjcqsm8X7J{`y_}((evF=e9F`_BU=j z^WSm5+fAHL|G&4J_;eR{qTfcGY?5lD8uKD_1arC?5 z>vyfI-<6MkSDyM^`RjMvzHm;ti@A%ri@A%ri@A%ri@A%rGp^rp*En}EcQJP{cQJP{ zcQJP{cQJP{cQJP{cQJP{cQJP{cgFQQ?i%MV<}T(g<}T(g<}Tj$73+8H-MLy#oVV4= zIb02$&(+qsUCo{6xp2pQKhAC-?jRi64+`Ri-#OTTOH z#;b|>)k>UdD1NoIZZ(%rF65az`RC5Q8n@r(t3z?rr}*mDy6Raz>Rg`cU;eyo`@%Wp zF6J)gF6J)gF6J)gF6J)g&bWTZUE|!v+{N6*+{N6*+{N6*+{N6*+{N6*+{N6*+{N6* z+!@#JxNDrdn7f#}n7f#}n7eq}*ZOX;>30u!^WEoMefrJrKIiSj{`PKj4&UOJ?l$N1 z-(2f%b8f%vAAf4j^QWKlQ*+KAamG*0`Tt`t_^FHf!W!4_ny=p#N53n+e%HGCUHRyD z<*DD5zkb)g^t*3A_Z~C;vHyFIng5mh|MbK;`cHm(;=kaB?m6rJ`5o^$`F!-L_nbWM z@alU`{y+Z4d(OTZ*YBFI-xWu{E53f$y82!D=y&C*-<7|9x9tn(l)IR_n7f#}n7f#} zn7f#}m^0j>`HLGa&JAz;_zf5T zAK&sz8*bfKec=fkE}xhD>k~Izo)^6Bmp5Ggue$b=Hr&1r+;N}VyYXsbezg*(8j4?S zty|6IlM8v~PX4*Gug2}S`RY&{^(nr(wXS-Wk2;s9`jT$2WiA+;iUefuEWC&y$|;GjlJx^mTq_?n{65=?Ba`>QDag0dv2) z{h1G#d)EVB_<*^OHSV6-eD}=axMvpMJ+pP)Gt0+4vpn51%ile-eYt0z`1}XW_)-7y zpqYQ{&pdeI{P#b7@WlT=mwCvnd*PiPGWi^J`a>qqXPxzs$^S8LddTdnareyTyJr^1 zJ+t`knXT)dSw8NW<>{VT{_dIEzHm;ti@A%ri@A%ri@A%ri@A%rGwz}s7 z{_d0Q%RRHb8?PqjS1WO@q>#Aq@sB?L$ zfBEyW?F;9WyO_I}yO_I}yO_I}yO_I}JLB$|+%?W!%w5b~%w5b~%w5b~%w5b~%w5b~ z%w5b~%w5b~%$;%fOzs-zF6J)gF6J)gF6J)Y_7%Hlws-fLYT}+#t=xaAp?guabziFH z?oqjLzsj9^SMJ=$8h1}?zWZBo-0O<(zSp|$f#u_VSf1{UAmv#-Y8Gn?<8SseGw;=5j`|c|-C9>Y%SWBdQ~k@Imu+7-r`*Nd#oWc*#oWc*#oWc*#oQTp&*ZLg?qcp@ z?qcp@?qcp@?qcp@?qcp@?qcp@?qcp@?qcqYyJvFOICn93F?TU{F?TU{@wTtnJ+r;L z&r}oloNDF%Qw`mVs;&D{HFuB7h5J?R+`Do&_pvqZp4NQ#x8k_h72kcYb=?EY$NjK8 z-5bl_eX@PIXSR3a)x`X2B~CRIzuH>2n#(5_^30w5b7xHC@e_pnI;hb_8a~E?La~E?La~E?La~E@G+&z=K#<`2Ri@A%ri@A%ri@A%ri@A%r zi@A%ri@A%ri@A%rGwz$I8wh6g=$;{5fyo;vYQKKyC3 z?vw8Nw8`iBPk-9v`K{MJZSw!jTb?%iYTP}u`R6}wQ~QdhVDhx)_tj(yGP~1 z{VI3vUAbG&{N|q7xO-aj-QSAiURQkgz1DRPEFbs7@^o)3fA`7u<(}EzjaL)%tCcv_ zQ2c6Z-D)nMT*xzb^3R=pHEzGnSBK)LPw~~Qb=9+c)VVy>zx;XG_JwoGUCdp~UCdp~ zUCdp~UCdp~opJX}?i%MV<}T(g<}T(g<}T(g<}T(g<}T(g<}T(g<}T(g=FYf#CU=c< z7jqYL7jqYL7jqYH`-!18fFEKm2w@^_zXU+$Uh-FP)Izgme?4aKjv)~)99$%Q;~C;!~p zSL62Ee03;}`V?Q?T30>GN1e-4{mY-1ZC^O2+{N6*+{N6*+{N6*+{N6*+!=SzF>`sJ?OwazrT0#?lm_2>UV!@?~(7h_J+@U_1E{l{_JBm{D#B6ym!@m+-SouzxhA! z-Sn#`Z}@w6`=`D2d!HM=#p6G{cio5IeZz13gMZk2+>0K#;m`lbKkVrXjep?Hr_KB$ zf8p61F3uNU`oawt|5Dd_*@j#9N?$#5!{zhaAAa?Q%k$CieC>wI|B|P@e#86wI(x%U zdHkgg8o%S8Ugn_rC;jc=2gNz{)t5gg{@;B6iU+NGejmISw8Aqp6XxzylnfzIpr?qF6J)gF6J)gF6J)gF6Pd7 zdpEzD#N5T)#oWc*#oWc*#oWc*#oWc*#oWc*#oWc*#oWc*8PA>hxr@1rxr@1rxr@1r zxr?`bee0}e?4Ezdc{@iw;hhKL_0Ez5hj{(H&_!&{??3UV-G{woXEXnV%bm3Qzs`B_ zhF|%Bo9$ly?_a&)dw%(5yPy9*`~0V;-F)}B)Asr0-@W>!*4$6-z=iQFn{mhg1_x_E)KXUhsLp5owC%k??pFe)m z;k(!V#EUlhyz@?n@80;l{d&Ie#)t3T;rI6QJZk19#l`JU{n#ECcYgiH_PBV{2S2vQ#p%EN;k|Q? zfA%K-pZ)rW_O5&2NgF=vFF&;RrhoW_4d3oRFW5W(ZTH&nZ~gXP@7?d_x8Lx8{>JV)^hzJx`=_t$^Hq=gyS?|l zWq_&pY8&d*3~BpPzf1SMELVN&BDkn?L0hd%J(U|19jh|IEG5eSH5JxyPN(+(XX?v;amL_5Lx{>~YDH#&R&`F;ES&fI(Y ztM;GY<3D@m-r;ZFe_oD$`78Eb^H=+Me(3j3*g5lz6F2#P{3$2weCf_VzTu~Q`uaQH zxblrRe1|U`zw^mU-f+Y3f6Z|_=l!=6Hhl7TkJ&l)1;=mr=&N6E=MPRkZo`+j+;w-J zaqD9@eE3JMz4N2Lcg%)=?q%29xz1Dexplw%lIL#5ul`3@**W@s`_J#~UUk)-yZzk$ z^ZP%4>uNi9`P+Ry@`9`HeC=}kIiGUmwRWCx)qVc!+g@kq7r(hb=hhFu?#>tAyw4wg z==FAPbKQMDc#~syZgTp5{I{QX+|H~1;DwuYZ~Fb?cOL%k7i{>#FI|7-4_s^eSKI+p4oDW}q)aMTPOup_dUp(M5dFC6xe86Y&6}S7^ z0iVeaJ^BA0@R@waHNJVkXYv=0|IY(HlaF}ue;x3d{LV?=KHxKX@9Tg2fY0Rl5B;wL zK9m3aGEnY{S>{^NkpK-t-pTVIn%!M=o9Aoy4(>roX_x= zA9bVoZ2!aQH=fV@y-vQ#JPTKT-A(2hdBhuUGSAL6?|hSarp|utjptc=&ns>;&)@|= zdBb@&Z}vMU%rkr9M~^$S2`LpZIv;T!>{?K_}`R2ag7af1bx%i=v`pt8X z{^3oXP=+<>CepgeGYtM=Ktq|FLs_d z>$~)K*84#>pMj@*>gzk*le>pp{c-=f(>;0rPV)Vo?#c1xUUl)^?#b~P-@D{)_vHBR zzjmqJ?#c1qLw;ztJ7Ij;Q!caHT`~UROE0tA{oizw)CK=eSFpza##Sp7{P9>%QQw zf3+i@_dND5cI0`&+upMy|HohHJv;W*xcxR?9g3qq#aFl1RnPKK=kiql^5 zpSQ>LZ@S%nt{$&{>+SaQ_IUjpaJQes$LrsQyZwAVUjJs??dSIK`nTk6KhKZXzcF|F zIe)zVO}g99kmL1l(%rr<#dtr1HNT&q$HnRA=W+4-`FY&B{ro&GpMHKGmuEjekITQG zpU3U1_c+As-{3R8{%t<<*T2~(&ic3f#9#l$pLN&2{U@LGGl5-suAd?7%76U~VfNLy z{Wf16ilaWoSGU$x&+<{{@>Kuw=cRr1b65NA=dN*e=;y9+_37uXadqqGu5tD3=dN*e z?&q#?zWTXqoUeZN80X99uOIUE|{SbJw_a`?+geKKzxs$%-Ndh+)~(L+ss8fJi~RFtUya*u^VOj^>Qj7mYhCp$A9XHI z^)G*3+E+iXv)_JR7gvXVUKdxNeqI+>w|-t1SI>T47gy(gUKi)9pV!5C>1S4PzSh49 zXS|>JnBULq;^Or4y14lLye@9teqI-sPd~4V%d?-?#rf*zb#eRZ=c{r1HC`ReuRh{b zH}R{db*r;{s=qw*BL95ZSL62Ee03;}`V?Q?T30>GN1e-4{mY-1^|_eyaQ(m3dG6N# zW1Z)5{lC|FPS^jFo#*#^mwoI!*X#e`&hx(h-|n0P>;DDM`LO<9@SGcsJ5QSLoGFg; zu=viy)^#41kMpoRormS`JZxXi!}b5ZXMFuX@tME=U-`sY{||lQum86`>#qOjKKZQw z7e9Hf|93z6um5*H`)b^I*nH<J*``vejmISw8Aqp6XxzytFUp zVf*#mRR_;w_3@lmH_vbN^jueG&wKTE4&=r8kT2&(MSH zPv=|tJNMd`^RWFIuMXx{A91Ri_|?<8)mc8(U!Hl9f4=Oiar%^gP$=cc^UFS?_ghaZme`M-+9=&&cpI?9+s!`u>75e?aO(%e&>9~*YBdw{PjEP z6KDPI`ov$q(?092-*umS*6+Yip6hq!C;#<3^RutUorleL9u~)WSbXPU>pBn1$9Y(u z&cpI|9=0#%Vf*#mRR_;w_3@lmH_vbN^jueG&wKTE4&=-Ekgqv6*0}Se`OcZ*IDd-o zTxwnCRrxr_%G3E){?5Jj@q>#Aq@sB?L$fBEy$zMO~c*K=1LJdf4Kb6VXzztz)oU7bDe)!#XgFXuzP=G<80 z&XeXlXNu$eDZX>5b)8q`;~Xnb=Ue$Z_u7~9u>BgZ4(3-MajKj6)ziAwSw7WYo_Udf zzU-@U`)$5D6i0oEuWqfYp5>#?<*EMV&&&E7;W-c2-ww}nxBjMhp2zjK#`B!6zd@eo zcl~YhJlE@Qmgjk2f6F}Q!1~+gIUm;FKF_()xbv|2&cot34~y?SY+dJJ`8W^D(|K6_ z&cpWQJY0Y4J>%DPOF>ew|aW6tF!05`a1{m z;(W-LbE9$RN%NgE#c}==-?`Mf&a3iqj+LkLt^A#P?aO)CevMZL^Q(_I)lK~BY2E59 zpXx8qyvRRa_SLxkHeVfzqdvt~x7Jn9@=@pVRR8klrF}UM+pp)YI(QzdkLR?yd48*> z=ejz3-mAZJATQ2`d^tB7cb+ugIa3_xPw|~gt?RrhALm$kI^W9Qx!1m&hwayRbuhpB zh*RCfub$Se&hn}L^303;^JQO++i&yLp*ZSOe06JG^(-HCE>HC@e_qzlGUq&8-`O?K z-TE%Cc^=nye9d#ZzWZyQ-}Rkf^IWg*3Y+JBeTUeb1M54-=6qP+Id;*xvBsT;&37Ia z$9Y(M=V9wQ56j1SSf0+q@^>D#FX!RpUzU=V5s|56juz;E^8 zy}J24R8OCi>g@AV{e7v|+!n{@x%fWkt?Tn&KAwy6^t_b6=cs*o zzS^(x>R^8L5vRI|Up=i`o#j*g<(U`x=gYntx8LTgLvhrn`0CcW>RCSOT%PJ*{=BU3 zdY$KMeFyA#T;B~le%E)#j`z2|^W^zFtnZke&&m4k+4=me@1&j2)%p(G`Mj;~u$|9g zUD(PtRBRd%oJ2=WBgu?~JeS@}2qXJANn5`tIL}zrGWA z)?MEfJo&8e5S~2OcMebf>pO>MUyXadn(z54j_0fRp0C#Re3g&qt2{kl6g=f8YB7v<@B zDSyvV`|^CXU*pxm{OTi4brZjOTDLmOr~1n?FY?cqeKl^s%~yxws88|Lt##G2eAKx- z)xZ3CS?>;*=WD%FU_7pO4UFIQ4ubK%-c2x{hxN{a`JAkG8O-Nrz2jg$SL>Y!^LbnE zM3~QEUD(PtRBRd%oJ2=WD$KV#eQpljCOodS}GMS?`jV z`0E`Lv+jEL#N@NyNilh@cUVmR>m3%euf{!J&G&p2$MaQu&sXbuzRJh*Ri2)&^7nkT zFV9!|<*_>OTYY%1Zaxpy)90i*`}|aYpR2t1yyeU1uyLQy=KI_h$LG2DKIg6L^Itxm zi}Liml)vYweR;mxukq?&e)SQjx`|&sty`VtQ~l+c7y0MQz8bgR=Bq<-)Tj9B*1GCh zKI&Ya>RBGPOI_0-gPyfhc{f}n)5kX@5Y+X&w6Lpe6H3z zw&wG;-m!Jj=WvaCzMAj(Dvsx?_@1xU^?a3&=c_zDU*+%lYG0nO^-i%FU+)^5`Rg5I z6KB1fY~rtXmd(2BU1pQdddJ!1x!#F3`LB1P&AuA-j1l&sTYR zzRKV8)xJDm?U%>uz;E^8y}J24R8OCi>g@AV{e7v|+!n{@x%fWk zt?Tn&KAwy6^t_b6=cs*ozS^(x>R^8L5vRI|Up=i`o#j*g<(U`x=gYntx8LTgLvhrn z`0CcW>RCSOT%PJ*{=BSro6hsK-g!D6*Sk>1?|Mh-cwg^MozKI1r|Nu8*1J~c^RwQ; zI-jfc&er+7t#`K0=df|lSMxnz#qoR<-}BYFp0D!pe3hr?tNcA*?aTAE-cdW_>)o|8 zf4$Ro;;eVwPW<%_+*$WgA3tL9S?|o9Jl8vRC;#=1-Pu>;p0DP6zKY}dD!%8dbv<9@ zAJ0X3dS1%kbJV^(U+vd;buhpBh*RCfub$Se&hn}L^303;^JQO++i&yL zp*ZSOe06JG^(-HCE>HC@e_qx)^L)Mb8J8H3r+xVn)Ry*kSWI zdDtn3&FAN|Cmc4Pt1rInu=%{5|C+-t`W&ut&sXz3U&Zl!72osKx}LA{@qCr1=d1iZ zU+v5D^_|yUe8#VS!;8=SOaJA?Ce9}xd9jKA*sES_)_u@97w*XC7I(XFN1pfl;R|=< z|GW!-(BI8$eix;2&sXz3U&Zl!72osKx}LA{@qCr1=d1iZU+v5D)qZ)b4*XUh-m9C> zL-q7Ism?w>)!*kTUp{a7n$O`H_xWtT&uwvho{R5u-nu^j<>R?1PtQyFdyd+d=d1l1 zuMXx{A91Ri_|?<8)mc8(U!Hl9f4=OiarU^&5 z|D#`<&)W@e{I&TUHtzG;e4pFm_&gWi^VPbZuk!JHm8a*c{5@ao%k%ZCC;rQfzvsSR zn)zqF=!+9)_k;gD@qgh)|2*q{>G!`d`TY4^zA$-y?uuWS{IB@^&(FRZ_k1zx;V=U!Je_%VTxmxBBp2-FzOZr_V`s_W7y)K3941dCQm2VdFlZ z&G)%2j?Z)Pea>6g=f8YB7v<@BDSyvV`|^CXU*pxm{OTi4brZjOTDLmOr~1n?FY?cq zeKl^s%~yxws88|Lt##G2eAKx-)xZ3CS--zM&(|Hl^>^d(un(O-et-Op9~$p3dcXzq zd3e}&FPP8CXP)ul`TQLAj~|}T)#tDJk@>v+=?y+IpTovIU(Nsj**gz!tE%g58;yww zsL|*T!Gh965F1Lk_wJ+8#1b2^w-gg&i6v45J1S`G6{FZ<*M!)j$US?5F~-dtEh@-!VufNz=e}PATfm45h zUw@I8{#tg!M{|C=ogc~dYtMW*byIOQMw)+K&hnf`j>{X4RbXFYmn*0=N0xmow` z?{-(};hq29l{z`-sClWMGygF!b#>?}ovF9c>vpCNnb%*e*I&fZU&Pm6?5n@PqrbqZ zzre4*$V-1+Fzin`|Ljh;=lVaKbX&&x(F3<;{HcR)&3(VP_Lju++_+m3=O^87N&Ex; zdvoT+y#8Xn{vwY4BEJ4&U;PCh{RK|_1%CZSUiyoCts^{GU-+@^@TMN%Q=P!G`hkCS zMP1Yz^-_n-t54ReTjHo^;;VD^RsZ187vR({;MYgwrN7A6d3bO={1^w`j1Qmg3(w+# ze{oV5@l!AJV%~gNFAv0#AL7d!`^qPHN0+BgK0NY@)X%EVUXi-`bfqg(Z;uSRGIhwj{$joUB98tdzW!og{RJNV z1y211e*HyW`m68IOLBg{9WKuGBc}g02KC=x%o4NyFXHPj_SIkD(O=-yU*OkY5X9yl@U zyYQluvhM3nI63vO^am%WPL7{EBlUCjQ!`RmCx35d>TS0HGt*zp>o3;pFXHGg;_EN= z)nDMzU*ObV;MZT|rN3?(d_vB@^TXqF{mEY)n{l4}%`q8&^{tN1eFu&?D)GE@;X3Q$$$E859Q90mbGBPU<3l>SbQcn=k9-fjII*e0gJE`2>$VgH!&&Z(ZWKuk_dJ&+M3W-1qDW zS>L%sch0&WaOEzkhrX}wnmSqKjonf|`&_?!>T1n3_DH?mH+GNIA@ll+_4AzuFa1Tn))5}8FZ@_{cvBDX zsZQWo{lLGvqAu!k)Cmj~j=5Ao%VedQB8@(fP-2fuZR@AcAOUp%pT)^XBl zYi4~P8MIc`{kYj{rye$av0v(B=&SuxKNGJSkhNbT)WfV>U+PdNCpKU1P(LdbuXd=b3)gwAL%qE= z<+TpKCt_ZIv0i@>M}HAtf3dIr0+0Rzr~U%J{vt2^wce=@<$Tfm{#<|h%lBrS!TH$902|TMG_*YldMZHlkb;!K>WWBm2j(R4(I%i+?4<3C1PW=LY zeMDaRi+r7j2iL=oap2AP@aewrEFSn5Cv_1&^)fH!&6oA^KpgoYzPz!oe1b=w!72aX zw=VIzoc_9Uon5nz)4#J%*7vn3`(@p4*!sZK!^t}ynmXC%=SQS|j{e2u)YbIj$kf}K z&mWmOWL|%o4NyFXHPj_SIkD(O=-yU*P}7 zUpu6~$k#f;gY|_U>ke<~0Y23UJgXo0S69?Uy-_c9$h`Vwy}BiidM3U)XJ7RX9(@5$ z{Q`b{gbwu=`8p2|u7@Avz?<>m(|zGtJn%10>LPyXWnRpiFYD!jIPyb$d1GJs1dlv} zQ~tqkUGCfFxT}5rdjGOlMq0;n*W0(v`aZkXRc+S&t2-CAsfXv^{-jNvJU*^xyZYI7 zn^oJ@)qdCYZC7v4uGO#I*DvPv7wh#Gar77Q^%wi#vJ{d&t$ke#QJ< z&d2(Bu8%nLj1%$a89(-&=e~ibQ#^sQQ=EanQ~Z%vXP3M>&6oA^KpgoYzPz!oe1b=w z!72aXw=UGn*Dvz5j__c8;m5ken|gpxbpp@o2maL+by08BOC2(=K3T7BiKCv0ug=+5 z{ewqefK$JKUmsB~{YAdc!-MPL$2jn2eE4)LGmHR43v0ruvCK&{S8^ADZed z`bJY7GOs>auWpH>o{6u{*;oC8M_+(bzkpvKk(d68KAH2;KXZNb)r=GUHsePh&V8dl zC!Xlri8K0n;*UO`c`QtS|gncX(3| z@TpGVS^dDjx}q-Xje4m==G7KEN=nHV_7x3#N^3q@A>pVQT9)64i zZ^nmD_l0Niz`r=Di}b&U6u zS>Je{nRSo%pQ(pM}HAtf3dIr0+0Rz zr~U%}H~xAo{T1)?b3Wex=lb}&AmhZ}3mHHDj>vuE?~B9}e|IF#_jH@L+x6$GXFtdVo)L0?+CP{?!$AQE${s z9Wt*zS+8!1qn?Sc&e>P}gGXP0Q@?;;AE872MZV6%gX`hPIPhkC_;g=*77zT3le&nX zdYKpV=F56{AddVHU*6bPKEWf;;FN#xTbKCUru6kIKKCfCV|*S`THpAbq_pnw`AMlB z;&YW!oy6xYrTU4_VM=uspU;%)Ek3s?ef?ryf3aSF5l4R!Uw^T${sNEw0;m20zy2aG zU%%pWs+^C{uX25Su9b1(^RA2^pM&MT@%dQdiO>WzA-L*~^d>(woB z)HCtbIs2-A@aPM0>KE|qBl6N;HMPxpmq@xZ@0sf+ljmw7R7zO0uA z;>Zv2<&Ayi6Fl+^PWcDFb&1#I^w&Y#ZI^Y7&-1gs@i~9iJwE?WJ;e6{sgwA=AoUa9 zBc!h4`-Rk7eD9DtWL|%I^ZlQ`r1pu`{F6J=h^>o3;pFXHGg;_EN=)nDMzU*ObV;MZT| zrN7A6I>LkXg&*q0Z#n_ zetkq<`ip#>hX>cgk8$A5`0(kz@GKtq7bkTQKlL&%=FOM&@<1Hp1~>q z;I}UEy?Od8zIV<##`n=#-}s(7>mJ`Om#);<*GJZUVko(5-35h43 zTS%PoJVWA-=NvLG=Jglr^%rsU7xDEM`|2<7=r3^UFYxOx^3q@AYaQXi`ofQOhd1>A zpXvmj)erouE9#=&sFylqUVXA&-4aJV6JMRPulfg%z5u6w0lz*XFa1Tn&clQ2;m0`e zW_*jGNmBhTQJfACwE`OD2tf5mfCS;u&u zD(f51S!Lbh`K#1JJeQR^iRZOaKk*z_>MEY^O1;H%U#Uap^%v{)7jg6#@%0z`>M!u< zFL3HF@ar$~(qHkMTh7PxZ@E66i_19iyj;eQ=jd|Zc)l+2#B+CvGoHsw{PCP#=Ec1J zV!i$%j{YLP{$gMK1s?qcPW=Ub{Y75-i+rskJXl}&vF`Au9^g}*z_a>+e|1G&)Eo6u zhs>)_)~j3MsAuAp0QWx=4 zFY{vFd|59K#E~E3%NzU3CwSx;obnHT>k`i`r@!L4->hRi51jRl=Y+HF@%(V=A)YHv zoy7CTsh@ZbId%0(_ghkL@!WFika_*Zdi_Nl{Y8BJ#lHFrJo*cq`V0K}i@fw#Jg1%W z@%(nKkLS8GPCW0O@#8u0+&7*NPdxG5c;bxb$rFD(XP$X6ufJHYzlfv1h_AocSAT&= ze}PkffnR@-m;NGO>j)3l7k;ceyr~EHR44GPe&AnSQ5W?_z0@J|>XY^AmN@E}`0AW} z)jxRj1vvE!`1KKa=`Zqi9v)l|KgNMK!n1hbU!2rM{M5_5m^WY6%L8%bhxqcw zzVZnkc?PHagWtNu=QioD_}xm@F@DdI^^M=TWZmQUFR6$4T}m%~g zU*zjNJh&cyj011Rhfnu~XYs(lIH`;Hsh4>%Z@#RT2ja*N@#T$uo4-sU-3KHoR8nn=KAA%!_&b#d`fk9Q{Rn{l&ie3q1M@ocas=`is2u7x`L8c(A_kW8L9RJ;0|r zfoJst|LTgms5k1R4w+YbyIOQMw)+P3-mihYm!#FpfvW{_{ zKxKX7oPo-^$N2-5dWdrgDs>X)6{LRR9D~$VoNthNi*pZBhs^6Q*6T0g=r7{yFZR`6 z;L%^;)L-D&U*x5~;+%(^kMkdLeVhxCapJs)j34Jn$VgH!&&Z(Ybsf03_sga_*jKh_=I)B}8~6L?lX@UO0@ zi+ZD8>X3Q$$$E859Q90mbGB zPU<3l>SbQcn=k9-fjII*e0gJE`2>$VgH!&&Z(ZWtp7d9ody{pH^Ki1haZXOwJ>sgpQwC-oEO@T9Kde4f->oZIt_4r5+@vR>U1M?Di?f3dIr0+0Rzr~U%J{vt2^ z73UP?e4JmD>*HLbj1%V_W&Ah?Dff-@krGdwo0K@?Jf*}R=PYGj%o4NyFXHPj z_SIkD(O=-yU*OkYm-{#)uH&V@^z#CdV4pEyS@ zbrt8!rQYJ)xzr)^`iu4Yi#Ym=`1*@|^%r>b7dZ77`1Kcg>906vFX!X@y<8vX@@1U$ zZ(Tj($2oqvZ=CO!c;ei@#2M!VCjK}lF!N$wf3aSF5l4R!Uw^T${sNEw0;m20zy2aG z{YAdk5gx2B{8)E*QxEW|PT*Pnz`wepF6xbXsYB+~C+pQManv*M)j9jBfAHuFaOxNE z>m%~gU*zjNJh&cyj011Rhfnu~XYs(lIH`;Hsh4>%Z@#RT2ja*N@#T$u^K27;oO7FbF|WT^ufK?+zlg8D*jImnM}L7+e}P|rk(d4=U+V}D))#)PJG`j} z_*5tGtbX8MT~ROfM!iypF|R&ZuWpH>o{6u{*;oC8M_+(bzkpvKk(d4=U+3Y$_3&dH zcr!kHx-UG72mZxLUBpkl%!_&RWxYHQM}CMeZ|p0d;E`u=%0Kw6OPu?i{)%(6vyO3| zcGfq}+0MGh`P-?7IF~zh66bZNe&QVO)K#4CoqCINzf*_I>o3;pFXHGg;_EN=)nDMz zU*ObV;MZT|rN82w^PG?K&vSj8i=J`fy!4D8=cwntalU%uiF4NzXPn2L_~V@R%!_&b z#d`fk9Q{Rn{l&ie3q1M@ocas=`is2u7x`L8c(A_kW8L9RJ;0|rfoJst|LTgms5k1R z4w+YbyIOQMw)+O$(NPoq>4_U{!4%Pe;zj z{T;bJ?)Atxaoj)3l7k;ceyr~EHR44GPe&AnSQ5W?_z0@J|>XY^AmN@E}`0AW} z)jxRj1vvE!`1KKa=`Zqi9v)l|KgNMK!n1hbU!2rM{M5_5m^WY6%L8%bhxqcw zzVZnkc?PHagWtNub6@GNxVI?l821@vedC^^tb5#llzNDJky0mdUsCEP?omoz#r;aD zx43ud8y&{H{$joUB98tdzW!og{RJNV1y211e*HyW`YZ04%K5l|D%Z!oR2e7ktIGIs zk5%p)_gf{Nxc4e?#(h|cKkmuOyqMQttk++}(O<;ZU+k;Dz@xvwslULlzsSq`+Q`>? z!QjFB!r;ey#Nf^Q#o*I>$Kcuf$l%|5%BYw3mr<`S_nKAScgA|}K_ia$qY>YG)7aPh z)WG9CYvA<$HSl{c8+mzO8~Hj953YwFGBPU<3l>SbQcn=k9-fjII* ze0gJE`2>$VgH!&&Z(YdCen`Ih4j%L){OD77)4%Ykui;t0!@qridf6YSSN4sVx1X@y zK0_S)5Ap3w>}$UQk9`cB_BZg`_sGkBNWRX)gX`hPIPhkC_;g=*77zT3le&nXdYKpV z=F56{AddVHU*6bPKEWf;;FN#xTbH<(Gy7rOYni@_`!3UuS3I(3`ZVsxO#jBcnd$4e zPc!`<_iSb#i2FCQKg7M9**BQCAF|$lNF4hi@$HA~Yd-{!{Sch?L-5-V$;*DY@r=E5 zKJF*Y^>J@$#))-MNOP>k80wNdsH(o=Iw{9w;vM6en@=#A^X}7 z!DBxJr~MH8_CxZrACj-Wg9rTxKl&8j^e=qsYk1c0@NXZWF7^lNW#3@le!_bD3~}r~ z#J4Z8ul))<_AzkU-@tF*BQN_Q`8p2|u7@Avz?<>m(|zGtJn%10>LPyXWnRpiFYD!j zIPyb$d1GJs1dlv}Q~tqkUC7IRNWS_G9`qyp=u>#pzwoKA;aR`KzkPtZ*dM5ueS>-X z3G3}M#IgSn-@e4Y_ABt%$G~ZS1HXNbyzGbM>pVQT9)64iZ^nmD_l0Niz`r=Di}fprLyy)P>f9>xM&b*knAF|$lNF4hi z@$HA~Yd-{!{Sch?L-5-V$;*C7zWNRx^dtP}Q+U(A@TsriS--=-eSmt|AE;OMjhMHe zu--mH9QzOP?Mv)yzXFea44n2i@Z0yu%YI0{&clQ2;m0`eW_*jGNmBhTQJfACuu^0FV2ufBr^{Rlt$6yEeNeClg>*6;9dAD~|L z2kMo5Bj)WVthdh)$Nocn`x5)wufSs;1E>8B{PsQavLBMK^YGw$_%RN=86Q5~7oNof z|Kg-B;-_Bb#k~2lULJ@eKg5?e_LWcY$TK+QANC-oln3VoKs^6sab>o$Z>Gz?xPRu^gdH%%g4-0=YG5ZGd_Cwa&4~b(xB)O0O0K_j?;|tL{qv5@_#?Vc&3z|sJ2mmlIC^U0{OGq+ z6aPQ2nwohrZ$D(c{g62JL*m;H+1Gvu9{V9U?T6sEACi~-kbLzWJm^RG(WmgHf8kSK z!?S*efBOJ+u|H5R`v&v&6V}^jh-3dDzI};(?N{KjkAc(v27db4dM#817?@z(k!NtqKlrUn>{G>W zZ|XBYJ9he_Tx!ZC_4vXCAC(8*{@Z%oyzt%f+9xlp$CrM4QMuyV=hox1H~Ck&^qObZ zUl#l#wNd97BDCm*_W<^1@$%T%u4 z^x^K6amHS_TxI+RzgVGi-<986u@cY6KmL9t&e5Y*uEf9gnJcHim^WY6%L8%bhxqcw zzVZnkc?PHagWtMr{K>d#(P<~ud9AQ`T($l6C)eYz{x+_f(wtF`yPr9(`o)5o^>|S+ zuDam&t-8GZ+}P;1r`Gcy>_4^|)$cd;c>6cTRImT8HNIuvG1ad=Y>k(Hd~|hquhZ%^ z(?^f4-dVOaUU%-OYMX~!YgQOOs@m=+t?_p{+$9r49dOU`N4o{anD9Qf8AsKs~(qh)Z<}O`&R?s zXsgHn8Q#Ad`>m1n_{pXFS1-T6X+7@0xL==>y)GM2jbEXa<7cZ6tWF!& z%6-FY23BWY-Qwhl=2eB5_dDb2Ld-jNTvLeok-uD1h`C$8YYQ^C4LJeGaWxtX?dO!!J3#)&}F9e|UC1 zUV6tni{<{&>alxFoLii8cWeCjGw&+?IjJ>%dDgsQ{HGVx>kpgRS)8_0YuvU=vsiHA z`StvNzi1X4o_}6FK6`3e3_PvXtGBqfEN(pPoO=F`zdbtlI-@ zi|e0l?RCc)hZP6C(!y}od50ITKGVW>-0QzC8h5lXuX+5$Vy}s!q4hBix$r<`gKgK$4ehRub4Bq^;)@bR9WWTnPt?$B1Lv9GRc ztJGM>TWysZ+r3YFrN+7qZ?DwYWt+5DYOF`!_DYQ{dcUnwW0P)etJK)kz1u1^w&TYm zD>b%o`p8O+ZM4+LN{xMf)DJ2(w#C>rD>e4sYP~Bpw!<>LD>b%O&)$_9YYgdKsj>1W zy(=~L(VX6u8asQ1K9w4~@Weiq8k_m;)hac1)LE-lYHUQ`c&7AgjqMuG4XUvNw^*Z6 zW4-QQqf%qz|J1uuWBXmvyHaCMy|`+n#`<)gRN9}%&o4_~Yp#9luF@X3`dVC{(`Eq%>e>F%RTU(1gB^R&{}xbr_cGJfaP>H}9DIHmM8 zvG2N*OJ6G|G$xh4hAuy6V(DvZbI!hrZP>B<=KPzB_sR9EExAv|x%lqAGX4#l?3w#k z2kf4B);(y~#ChBJofH3%6(?j~A3wcA<~!@g?UILK7jK*VeD{v6Q+wdFUfZ0vQ`Ygr zXMdDDzqQ=1$^W<4+CA&C))ISWz3#YludL&Si}%j@{^YfNvhIIAYTwkuODo^qROh?y zc}r9Mue9o%rn=g3@0*(H?N{wLG}YnsKVR2WpI?4{ZByOu_U^S!^}J~Ibxn2t&KK7= z)&CXUZffd_<8S#xQ@_lA<>sb7S}^1Grv93H;@qab`(@c|>c@Cr-H^9<-`h~<@qW0W z&f|S@L!HO_=Y~3u_tgz`9`Cms>O9_uH`IB&KX0h>c;DWTEA~BOo7UeH3zi(!SpVOx z_Xf?QM>QV*Y3segi(igv9DHkQJon_$jsJbBHD1tjOk@0`t?|C+jcMF>No%~)N@E*k z(Hb9n>e$9LceY}l`2N_&(mh+_-L@Oo*mG3tb?~BD;~Jmu)p{M=_2F@i|NOM&k#*l5 z*I2km>u;RDt-M;}=|@`c`S-nd^~8VW@YNd=uW!A_ZohuD##=?}z4y=huh!_XQR_W< z&p-5OoN!F*z52sr`!x1kWk~CF|GnOgUEUp9kAHky??&4ft@r#Fo!+~#)q1VJJI*+^ zcjHfow*KDv{i(eh18>`;UVr%?dN)S?tMxbRj&JsEEc@Tq-x{B^^=aJkOnbei{}p{2 zk4-J=@kg_c;qUQ|_`QC`_|O&aDZU;zy39A6UofzHgZBfhIc5Fs4c-qhzJ06i4c-qh zzGGtd2JZ(Lv!3?@jA#F9xd!hC7{B+Ao(62`P0`nZQL`smCNro9nn~|_ZjuS{n4*SG?wglWve`yQbz~?q?y!V?H=70Tq)5bo#wsJZ9vrQVS ze$g7wow7+|ohhx{cUm;O@!Hp%-1O`3HGY0tQSZC)?|L*|owIE{9(`hu#_VZZ*W=HQ z?$J1MMqKec>gtvRjnkYB9O*lclY{Mx%K zG~PO+wSK8dJsW#Jw@1DHpane}6ZSZu9zQs}XJgM7r_|#qWsk-u%br+|^*Hs?Q;hW* zV?D@NZ!*@ijP){OJnT+kFjP0?E?I(=wGmP~wV|~q7zcaQEFt$H1wr?=DpD?!1Fm8U`e;C`B7~8KH z+s7E&-x%BX7;pUY)1}^LY~PqRVPR<>cy#jPrF~$VbDk*e1G`-OWN9Dx-&6ly+6Qjl z?Wxi}@T(=BF6{$LAN_P`AGqVbr%U_5w%cEnd)@fs^Gp6N0Nbi(pI7pC0pr0hpIh>G z0ppu@JGbQT0>+a*J*VXF0>?I7ckyot8+{KE?`_d zbZ*Jt1&lYDd|t`l1&mJ`b$-d;1&mJ~azV-81&r@m_rj9D3m6X@IjiLF0>;-|dw=Nl%9AC37cjo*xhG2gE?_+8S5K7uUBI~GiN{O+E@1qf z6&^47yMXa$gBO=1ecLC$6aZUw)7cibM=fRS{ z3mAWV*#jki7cidn*T+l#E@1rQcONhLyMXbuBc3ezyMXbyu}_!2MqK&m)1|K?TVL{Y z>FdbVXY|Y3{qwE?$;q8h4N9&y{`=tMaQJmYlG`UXTQ51k=e%KAi`leBsP&9Od1Kz`PIqPU9b-SoW9;X9jQ!k?v7ZMr_H#nUetyW< z&lMT_c`0K*hh*&MlZ^e`lChs>*5j`~=Va{XpN#!nl(Cz)NydI=$k@*k8T%O{V?TRj>}QgU{j8F)pJ6igvrWc+@59*d z7a04!17p9BVC?r4jQ#$CvEOSj_WKUTeh-pY? zvEPd^CO+T$F!p;i#(uxX*zesK`+XeaIRB)G_y6_3{pX}f9(Vpz z1>YYrUT4XL1>Y+%?z8bjh5OFj_HPB>Lot8P!S@#89CG751>ajS&)*h&Psf;f>&1F` zAP(P)8K3XV7_%?mqcH{#->)$SC*Qj<20!1&F>d9xT0Nfp{JS~7+94n3`j2LPk#Uy2 z;9CvjpY!=r4fp-WJ4?skL@hk!zTa(#v)dNSG{pb<>B}_Ci+S^9y*v;{euyt`>?@z( zk!NtqKlrUnd|%w)To-bT?~xlk&%ijoUvBW61LOGKxxw=fjN|+02G2z>j_;`(JTJjG zzQ1np90lX}Uc15b6^!Hi?gr0YFplrR8=QaQJkOc9p65&$6Nl$a7!#l8Oc=8-&zUd= z56_t}1}D#%Fa|%*nJ^|Vo-<(_-y`RIe7~IQ<9p|f6W>Q?{P>aMg zyzyKFWBBBG3C8fua}#QR$|rc_8JzMDe(OSBJZECQJkP)w9(c}yG5qlS17mpOxd_Ja$@3D7;hE%Y|BH|6G5hiy2=n0K`4Gn7X z)Qjgy7?T&znJ^|_=i$Ni@M9c!Gd_H}FFcC}{>4dM#817?@z( zk!NtqKlrUn=py@JJZG4`i{}s1kMUe$`ZS(bO#jAnjOpumzA^nC&pl=zi034;Kg4sA z**BQCpRnFOLmc}d@$HA~Yd-{!{Sch?L-5-V$;*Bi&l%=?Jb#$$m(|zGtJn%10>LPyXWnRpiFYD!jIPyb$d1GJs1dlv}Q~tqk zUC7IRNWS_G9`qyp=u>#pzwoKA;aR`KzkPtZ*dM5ueS>-X3G3}M#IgSn-@e4Y_ABt% z$G~ZS1HXNbyzGbM>pVQT9)64iZ^nmD_l0Niz`r=Di}G$|uO!k5Jy-fCp z_#I954d(5KthXN$$9_nB`yu<<55Z$U1gHHF{PsigvLD9pP;x$gpOWk2cPkkue$SHe z<99B(Z~Xox@xrYNPPPt``Qn|V?P9^{Sf^2L-Mj8 zlCQpl2mJ^?`V`*uFMR52c-HUmZy%s8_6O=^-(cQ;!g~7*aqK_Dw=c1;{R%wxF>u=7 zz;E9pFZ&_+Iu8%7hacm>oAKe(ec@R=@Gnm4B7W*+Ud)>>>*aws@+LhdvHuX?zQn%v zEAZIIz-fO2zkQFq?1$v*JUqA_evAWe#)nV$g=g`=zc{Ij_^Fq9F>k)Cmj~j=5Ao%V zedQB8@(fP-2fuZR-y>%~jNd7z@8b8%>Bsn8bNV!X@0|XP-$AFZeET8$+7H2FKLn@!5d8K- z^0FV2ufBr^{Rlt$6yEeNeClg>*6;9dAD}Mw2kK?tVBUVhdixA<>_5b}FR`!v3Ox2P zaN6I%Z{H&?`yu%{4-c+~ALGEA@!`{b;aNQJFHY(re(Ggj%$qOk<$*ZzLwtE-U-<-& zJcCpI!Eas2%YI0{`VJoSBmC%7c+%Z@#RT2ja*N z@#T$u-XA?xjj#IYX|-+sux_CxU455Z|a1i$@|yzGZ@j!n+T`8K&e&b`Sv zaUM>_k8^Tz-#9-f@x-}0i8IdIN&ImRPv*tE{gCzcL*m#EiElq-U;80=?1$jAAA;Y0 zNM8Dje61rqSYPK{D%0-X8<{Q8Kz^cVR$4-c+~ zALGEA@!`{b;aNQJFHY(re(Ggj%$qOk<$*ZzLwtE-U-<-&JcCpI!EasSywLPloFkfb zd}xDpvc7TdXx2T>BTYTTIi;zSIKMRY6X%+yuHqcj)LWc`nmS}&f3aSF5l4R!Uw^T$ z{sNEw0;m20zy2aG{T1hk=6swln(O1-(To%4k!Jijr!@DC^Gg#?oNJmmke<~0Y23UJgXo0S69?U zy-_c9$h`Vwy}BiidM3U)XJ7RX9(@5${Q`b{L|*!fe4U2}*Tau-;LZ5(>AvtR9{3k0 zbrC=HGB4)Mm-X^M9Qh%>ys@u*f=8agDgWTNE^*#<`YX=C&N{~V*je8=H#_Sd=V_-N z;+*Z&Nu0l(`iXP7Q&(|bcj_(9@lG8wufJHYzlfv1h_AocSAT&=e}PkffnR@-m;Q=# zuya1n$IkU}Zg$3r^RzSmrAw}n`^Nd(i6_qGPMmRGcjAw8yfZK6^%v{)7jg6#@%0z` z>M!uI9zE5B#eu>Z0DLmpWu#eX?HN5=T7~ zU!AkB`Uj7`0H=Ndzdj-_{YAdc!-MPL$2jn2eE4)&%Z`}Kkb&vZXQV(%YMC#;#XL_W5;$Df= zRop|7dW(A~QisgzFV^cX;^;5p>o4}zU*OSS;M8B>*I(qNzv3Q;oR9k*a(&$Uka6NZ zh>RciMC874e?;PmdnFQQ+&7W<;~t94i+TOUdi_Nl{Y8BJ#lHFrJo*cq`V0K}i@fv~ z`C3PKu)gqP-Qi6=z^6KaXY~XB>WaFkH|nJhnOC2zSGUAb&%{^f?5qC4qc6azU%;=A z$V-2buk-NWdiXI8ycr)p-4~w41OMWrF5;(N=Ec1EvR)pDBR|BKH};iJ@W?Yb$GD#;>l^nLW!>XGqtrv(bCf!X`;Q9s6Zaw&>MHI_D%4xtqg42O6!ZFv z_4@Ul) zkk)Cmj~j=5ApRE`|2<7=r3^UFYxOx^3q@AYaQXi`ofQOhd1>A zpXvmj)erouE9#=&sFylqUVXA&-4aJV6JMRPulfg%z5u6w0lz*XFa1Tn&clQ2;m0`e zW_*jGNmBhTQJfACuuo~!iv!?;JUu#R!R zUSWOX-n}?uq4oS>+{ag_hq$M&P$zMJU-~QV^-F)neShh%xCb!(#k~Gvz5XJO{vy8q zVqg6Q9{mMQ{RMvgMPB+V?$OKnxL+^V$Gv+Q=gYkoXZ*OQFZYf6`w~yw>z6p=zQ4pD z_W)*I%o4NyFXGD^`^qPHl^pRX5HgH z+0;YaGn+bz`)5->aW8G^D(o4-s zUvUp?&d2?*xjycV%{XzNY{rj!W^>=Te>U;Ny|jrl?yF7wagS~0#k~Gvz5XJO{vy8q zVqg6Q9{mMQ{RMvgMPB-ge61rqSYP~Yd(SgY z+=rg=`B>YRPmKX~*7IQ0wo z^$~gLFY9Ygvv}ZNoYY19)XTh>H(%Dv199Ys`0~cS@(CV!2B-Xk z-@5QyBHthO9ePRDalaid&iam+{@bkkOZQ!rdRS`EMX8fhuAY_p*>B9O)YVDdW~JV4 z{_w)oA@ll+_4IeSS6?IW>)Jq*QuRd9?Zi%CwiLcJtSN(%WUw~7; zfL|Yxm;NGO=i$Ni@M9c!Gd_H}FFcC}{>4dM#817?@z(k!Ntq zKlrW7);*@Dzit|QLe}w}A0D6eJ^8C+v+hs+=9tvO>RTP1IvF_TsMOC(Cr(RUt-jo} z)Z65LO-&s#ufJHYzlfv1h_AocSAT&=e}PkffnR@-m;QS5?ddsx%>yUq`h^#rlyTOb zaB{|9`h$~m-{U9GNIX|RH6wAJ{Joipf42cMGcV@#7wh#Gar77Q^%wio4-sU*u~Y;lcXCk9CJP^#Gsh1fJCo{HrVKqTZ;NI%HmbvR>U1M?Di?owKj{2amo0 zr+xvyJ|ZvuMZV6%gX`hPIPhkC_;g=*77zT3le&nXdYKpV=F56{AddVHU*6bPKEWf; z;FN#xTbFq5EB$rQcH3ng-@kC%tnbC2Zk=_1^W?2k4;zgcpE~K-Y|GTo2gi;}U2WWL zT+X!zwg--a{b()J7=5& zuG}T#_kDHO+;^2Xc1t|_T)%tbTyu>*690W;_sG1M*I%sHU&PU0#MfW!tG~dbzrd-# zz^}i^OMj8Cb%Y1&3qRH!-qZtpsuOrtKk%=vsEc}|Uh0r}^~rj5OC0q~e09#g>K{D% z0-X8<{Q8Kz^cVR$4-c+~ALGEA@!`{b;aNQJFHY(re(Ggj%$qOk<$*ZzLwtE-U-<-& zJcCpI!EasSd%g7630w8fI(9p^SJwCD4_C>$e|7xIsfY2KeLr=wQ`<_ZpJk`5n7Z2P z+bgEtu6+J`sYB-V7wh#Gar77Q^%wio4-sUtc`2dd^QeZOvT&$e^_{ z&T+HX&iI?Y*e~}T`fC5gGx4eciF1=x2PXdKHy@aJF|WT^ufK?+zlg8D*jImnM}L7+ ze}P|rk(d4=U+V}D))#)PJG`j}_*5tGtbX8MT~QbHM!nP_^XilJ>Xta_nfU6QebqmB z^aVKe3;6XBdFe0mbsipE4?o6%H{-*n`@*w$;9s27Mf}vuyqGs%*2@EN-86L^cV5<7yIfj@aQja>M!u?FY?k~11@_a z=U3_ZbgsW|>~k4s@cJ)g{8_iYl>468d^z!~RJ@uvFI?xf#Q)lq*D^2W&6oA^KpgoY zzPz!oe1b=w!72aXw=U$RzsT1*!h`jNAL|Zp>H$902|TMG_*YldMZHlkb;!K>WWBm2 zj(R4(I%i+?4<3C1PW=LYeMDaRi+r7j2iL=oap2AP@aewrEFSn5Cv_1&^)fH!&6oA^ zKpgoYzPz!oe1b=w!72aXw=VIzoc_A?%kf#q$NG-S`X2Jf_N@C2&u@}?c;xRJq)tA( zduZzCsRe^mSC73pDD}4SHiJ@!%o4NyFXHPj_SIkD(O=-yU*P}7Upu6~u3Tr= zoS*)keRBP4Q})X^H*9@i#y@$-Lv!DKettyaIro4Ny zFXHPj_SIkD(O=-yU*P}7Upu6~$k#f;gY|_U>ke<~0Y23UJgXo0S69?Uy-_c9$h`Vw zy}BiidM3U)XJ7RX9(@5${Q`b{gbwu=`8p2|u7@Avz?<>m(|zGtJn%10>LPyXWnRpi zFYD!jIPyb$d1GJs1dlv}Q~tqkUGCfFxT}5rdjGOl?y`>OuD9-+3lSIx8TU){NI zo_cux?N8>ZlgG#P>{LJ7ZnJ8qy4vr$zMbmr*|qw0`ufGZ{$joUB98tdzW!og{RJNV z1y211e*HyWzJA60NatgHo9iP^n{gt3oAG1cHunuY?cxcX?cxml?c$HT+Pmb{ZoaIS z2ja*N@#T$uLkXg&*q0Z#n_etkq<`ip#>hX>cgk8$A5`0(kz@GKtq7bo=+KlSR8 zSG)PLULJ@eKg5?e_LWcY$TK+QANegVHeA}{?FeKO~xf9Cq= zs~IQyZN`s2ocl(9PCU`K6KC}E#2lp7Rv%c{@GwUAjKT{9!zBF|b?^jbl@jf-86L^cV5<7yIfj@aQja>M!trU1M?Di?owKj{2amo0r+xvyK0=53i+r7j2iL=oap2AP z@aewrEFSn5Cv_1&^)fH!&6oA^KpgoYzPz!oe1b=w!72aXw=VIyP3h}beC|4?U*-DvTr1+e|1G& z)Eo6uhs>)_)~j3MsAuAp0 zQWx=4FY{vFd|59K#E~E3%NzU3CwSx;obnHT>k_Za>96?QKI<5t=VyK6bN;M*eEy$$ zi0=hbC-Hqj>LK{D%0-X8<{Q8Kz^cVR$4-c+~ALGEA@!`{b;aNQJFHY(re(Ggj%$qOk<$*Zz zLwtE-U-<-&JcCpI!EasSd-L>HeD9ofjPIkfzVSVE);+$zPCdl;+NqQHzB~03--D;F z;`{N`TYPVxI%Hmdv0i@>M}HAtf3dIr0+0Rzr~U%J{vt2^70(Ied^|sp>*KkCj1$ir zWc+vzA@_~v6B186w~#pFd4|Lv&pBjX%o4NyFXHPj_SIkD(O=-yU*OkY1^H-^dcrGh-63=U;e&RW<)Kxs+m3oWkzEX$G>o3;p zFXHGg;_EN=)nDMzU*ObV;MZT|rN81ix15jX-*SCC7ngD3dAW=q&(Y<+@qAt4iRbPT zXFQLW_~SXf%!_&b#d`fk9Q{Rn{l&ie3q1M@ocas=`is2u7x`L8c(A_kW8L9RJ;0|r zfoJst|LTgms5k1R4w+YbyIOQMw)+L@>PJhL7zgfq49yse8 z&k1MUa_TCcPfoqXbIYki=Jglr^%rsU7xDEM`|2<7=r3^U zFYxOx^3q@NoOaH~^V_*Tp6kvy@w|7&kLSR1-*`Se@x*iEiSv{0wAzuFa1Tn))5}8FZ@_{cvBDXsZQWo{lLGvqAu!k)Cmj~j=5Ao%VedQB8@(fP-2fuZR&u!9Q@w=6*WBi^a>l?pw$-2kyUs4b8yO`8T z{9Y#Y6ThQLUB&NfQg89Qo75rm`iu4Yi#Ym=`1*@|^%r>b7dZ77`1Kcg>96>mQO?Kj zk8*wdE-B;0@0Bus{EjL2jo&vVp7`BU;*8%zCI0xGROZFJ{$joUB98tdzW!og{RJNV z1y211e*HyW`ip$6BRp7N__6NrrXJu^oxrpDfq!*HUDO-(Qisf|Pu8nj;;3iht8?~M z|KQOV;M6bR*GJ@~zsT2lcyK-Z7zf^r51;M}&*Fi9aZ(rYQ!n#k-h5dv55$ol;>#QR z$|rc_8JzMDe(Msy8%=-3?=G{B@q5gyZ~RU(>mI+~Og+T!I#Va{d(YHQ{0=mA6~7Nn zy~XcFQ-{p!FV^cX;^;5p>o4}zU*OSS;M8B>*I(qNzv6eYIUm2D&GqrS+Kdywx6SzR zJKWqiexI9o;&;1=Gk(vT_~UoJnHTf=i}m`8IQonD`ip(_7kKm+IQ19!^%r^RFY>jH z@L+x6$GXFtdVo)L0?+CP{?!$AQE${s9Wt*zS+8!1qn?Sc&e>P}gGXP0Q@?;;ACZ^- zB46j>!S(QC9C$N6e7Y|@iwFM2NnONGz08Yw^JTp}5J!H9FK_HCpWu;aaLPaUtxN1v zE%WvBhjDH|WgX)@fy(;EIRlk-kMjpA^$_P0RO%$oE2z{@oMTX_t2p1FQg3nYLFMQ3 z%o4NyFXHPj_SIkD(O=-yU*OkYcG6#Q4o~_k&gV&g#koD{FXr_Z>-86L^cV5<7yIfj z@aQja>M!u?FY?k~aZXXr$N5FMKF&4DIC0)l#*cH5a^E-~De=U)Nr^MgQ%d}C&Qj*Z zy#8Xn{vwY4BEJ4&U;PCh{RK|_1%CZSUiyoCts^{GU-+@^@TMN%Q=P!G`hkCSMP1Yz z^-_n-t54ReTjHo^;;VD^RsZ187vR({;MYgwrN7A6d3bO={1^w`j1Qmg3(w+#e{oV5 z@l!AJV%~gNFAv0#AL7d!`^qPHb7dZ77`1Kcg>906v zFX!X@y<8vX@@1SjuP@`rIexisobQ)-;@rQ)8Rr2e{x~Nv^I~3qv0i@>M}HAtf3dIr z0+0Rzr~U%J{vt2^MZVS%9;`3?Sa*0+5Adl@;932^zq+C>>WzA-L*~^d>(woB)HCtb zIs2-A@aPM0>KE|qBl6N;HMPxpmq@xZ@0sf+ljmw7R7zO0uA;>Zv2 z<&Ayi6Fl+^PWcDFb%}FR(_eA!Xx1^#BhC88Ii*?mIKMRY5a*hvPU5`N)K8p)n!1Yf zQB!YmZffd~dHuzD{Y4!8MST6mzWNJ1`U{-;3;gzgVxoh@-!VufNz=e}PATfm45hUw@I8{vu!N z2oKg5eylsZsR#H}C-AI(;9p%)7xhNH)FJcgllAJBIO>`B>YRPmKX~*7IQ0wo^$~gL zFY9Ygvv}ZNoYY19)XTh>H(%Dv199Ys`0~cS@(CV!2B-Xk-@3%P z-|4S7H#_SX=V@nsK{D%0-X8<{Q8Kz^cVR$4-c+~ALGEA@!`{b z;aNQJFHY(re(Ggj%$qOk<$*ZzLwtE-U-<-&JcCpI!EasS-iq{B-20GqjQb$6zHv`P z);;czNIk^85~-88ZzA;*_fVv+dR#Cz^%nP5qz;+aU#!<(#L-{G*I(?bzrdrvz^T8$ zufNDkf5kl=IUo0Ta zuWpH>o{6u{*;oC8M_+(bzkpvKk(d4=U+3Y$_3&dHcr!kHx-UG72mZxLUBpkl%!_&R zWxYHQM}CMeZ|p0d;E`u=%0Kw6OFZ|L{)&5xvW{_|QPwx^Im)`n{YR;XxECpP689yg ze&Qab)K%QClzNMMmr{q!>o3;pFXHGg;_EN=)nDMzU*ObV;MZT|rN82yshp4dr*eJV zOOaSXWWOC_~V|e%!_&b#d`fk9Q{Rn{l&ie3q1M@ocas= z`is20uZ?`Y7YrV}FARRXM-1M)UkpCIcMP7rj|~33r;NIIe;M`aa<5tCeP^uq9yH>3 zKN|79H;sM0PYpcYvj$G@Ujx7QvXPhfwUMv$@Zfs*F%G;LA3og|p2Y+I;-oI(r(Wj8 zy!o}$UQk9`cB_BZg`_sGkBNWRX)gX`hPIPhkC_;g=*77zT3 zle&nXdYKpV=F56{AddVHU*6bPKEWf;;FN#xTbH<(GyCDjGxkp3#eJ9Q$G8VGeH!;; zrhnt!%=C5Kr>JG64_R+NB#!-%`1V8gwI71Veh5zcA^7cw z)-MNOP>UuxoydsH(o=Iw{9w;vM6 zen@=#A^X}7!DBxJr~MH8_CxZrACj-Wg9rTxKl&8j^e=qsYk1c0@NXZWF7^lNW#3@l ze!_bD3~}r~#J4Z8ul))<_AzkU-@tF*BQN_Q`8p2|u7@Avz?<>m(|zGtJn%10>LPyX zWnRpiFYD!jIPyb$d1GJs1dlv}Q~tqkUC7IRNWS_G9`qyp=u>#pzwoKA;aR`KzkPtZ z*dM5ueS>-X3G3}M#IgSn-@e4Y_ABt%$G~ZS1HXNbyzGbM>pVQT9)64iZ^nmD_l0Ni zz`r=Di}FM9kyB(aqj{DZr@7o@AaQ1+Ofcu^$rOe#pM|L-5!S!D&AP zzx|NB?1ynrea^@I^|?Oowa++ne*Mdgzs1_W%zc-7dH=-o-p%_b&J)htKk?5xb^pwZ zdHW&j?T5s%9}?ew$iDVN@YoN*X+H$N{gAxuhvcj8;6Xpak3NMr{R^M^8lLq#{M!ep zi~WIm**BQCpRnFOLmc}L@$F0OYrg`IeGHuTH}Ko{$jg36zRtsg>*2>Z@Me7YbYFND z5B!Uhx`>~8nHTfs%X)brj{Fc`-q=?@!6VP$lz;GB7xJu=7z;E9pFZ&_+Iu8%7hacm> zoAKe(ec@R=@Gnm4B7W*+Ud)>>>*aws@zMi=4)b#s|qo-yc_~^G&vp@Xvs;SvGn71FY-hN0N z`yuh|hwN)V1dsg?oc2TT+Yiahe%S5W$vHpd2a|LC$_poDoHvh{l<|-1H!1gRyfQKI z483(?;_N(sV&Y%;n~9kh^Y%m5+YgCjKP0~WkbUik;ISWq(|!nk`yqMR56M^G!GnH; zAAJgM`WHU+H9YHg__q&G7yASCvTrbNKViLnhB)>g;@g+l*M0>a`xrRwZ{WA@k(d3D ze4U2}*Tau-;LZ5(>AvtR9{3k0brC=HGB4)Mm-X^M9Qh%>ys@u*f=8agDgWTNF63oD zBwu|85Bd>)^eMdQU-;D5@T}kA-#$QH><`q-zQMfxg!T3r;@E$PZ(m|x`xSWXW8k#E zf#1GIUiL%sbsipE4?o6%H{-*n`@*w$;9s27Mf}vuyqGs%*2@ENfCcSF5>qA)ugw^Rc~y)VLhJx*KyT*E3aRV7oIY%dTy!p>hXVukE@#f zht%UU9*)mxXAZ8%_wGEl`u&J?>hWd^$5h8`KByiqIc7}N=Z1mxc-LD;S8GjfjoEk6 zX(!e5-|39c!yh=c95022_iCHtO-_8w^VP8(uT8I`isQE}yMFusUs6E8o2? z8&Hj3p~b`Vg9lV6jc)OC`#t@u1@qUfG*=(0V*-z5dny`wy$fYk#YMwfM*l z>hW2N`c*%@VxxN8e{sL+q(_F=<0qHyU%mYPruFzg!~0ibzcsQR51ZP*8u&(AJ-+U- z{#B1lI_mM#JKk9=_m2zf@gIMCbdIYR%VOsro?Xvxac^1Nc-T4h`0S}=G4Ql=>+yfT zXcilue_lOq+of47IPv^?eAvv+;C%VKE9MNIUaw!Ycy7_JV`4pC z`!92gD_{6oJ%03qyNZQ3PN>HlT>Zylw@t>?E9>+z<~+*SO~tJ~J&!@fVS*n7?G>+$#2m{+ZwOA)8yi_o?nlTpIGcQvBm9ium8Ge+|lCytn&^p zUVWxjmpjfltT^bER=tM5aA(GBmyNy{T>52f^x!Agey2lkZt$}uJM`@BuYB3A zm#=>4vvxhc{KcQO>-{~p{j%Mju*nabVL`fBM8d&q9vcki&bJaxDhgL+l=x4VY-s_bv)?9r>TzwLcdugd<`@m8~HT*>Q&j_-r2fWWq-S8gI<;W?Wq@6t?Y06UD3O; zzm5M>@5=u6-fF!o`&+O3*Qo4i2X3)OWl!5Ro{_Vsjp!TCH-6pIjyh|#%APj!+pAUf zve;)pr|qyz@5-Jwetuc1`Df3n zN;UsLV}7aTN8dNURP)CUSWv3@mv&iDs`+L1SWv3@*M==9)%;aY%`esb9TVo4YQDOm zD%JcUFO;R4KjedEspdEMu(MS2fBDzEQq5oc*j=Tb?bCTuX%9L6n2DvmZuvPAOMBgf z#-!3-*LU5?rM>Q|1E-Ysy7NCeGJc!WdR;s2&(lhK-AZ>KUE1qTef8MVUf1o6<4b#8 zzZ*{|?R8Hqm|oiJzI*?PrM(Vp_P41I9iRBO-08T|{6f?QeaCPA%=82{KtvP4k-1pB%?VIyId2OFuzv1G&GtM2C?v?S^ zT4K-K_uFgjo_O9`Zr8;5;j=$V{M($jQ|86K*5bQ&Y@Ib4cJa2!$*dcVVy|MmKD-XV&iGyZ6ePuD0YpS?f0!?~@uBcI>{Xja~P= zrK$d3TKVp#y830=Y^t}pC(doE!v!;LZ>rDvuiV^Jx5wY|ho*YIqT5YPb^gv5*EiMw zqS@Cq^~G-QUfa|!Uw(dVQy)$L^L0)A^{e(9n)+_Xy>Dvj$CXx{)6}Q&cSf_{N2fNI zi2t3i;u7_E@C~=m>vq5goy?!|?+rWO+3e+d9A{v3&TrgTkE`{s>*PPyFvtJLn6>;H z#>5~NV`3k=;)(qkvuDh=IUnoWT_17kF>xY(JtltqSC82<{=a(6p0P(gX3yB8gE;IN zd(`8v^K!ne%lh^%aoW4YZ||~ioHLqu+PmOv?}ERhOI{sa^6lut193XR#-3exW8Zq7 zJ;|9h?Ae9?_AYg4i{F{nYsl-D|9+?*|7hmf^V(+KQ;*wrUaoWC#<$nw_>Q;p=Rd!^ z9zQt$M?u99`%?#BUU|T&)B0Lf1Q`}ZC%#4cZt*9C4PICecQX>Y43uwy$k;KE_pF;zO3*3 zIxphXWA^OA8~fJt>`Bfoes*Z@!hd_0y0oG7O~3V>l0B&-V>Cj28KV*E&KQlL2gYcG z{}?mJ|HqiM{2Ru^AQod{vj=1SM?ub7uK*R{$k9Y z_>1w^c{yME>+AKkzZkP;m-w~6m}jmFp4wl`vuEtl#+W_vS1ZnvwZEM2!b9yZ=E2^D zx7uIKlPfv5;{W`Dz-w%T~xPuex#TcI9jRJh zVr;z_6F>f|=dBm>Xaub@wqA_U2wG=My%E9=PEIx@D7jIE>d z)Y0|Sk+F4TY#kX}N57R`0&Gc2q^k(`kV|p`vm@&PX z{}?mJ|HqiM{2Ru^AQod{M?blmv9D{+^LpWWUPl-chhEQ^`0-yoX3zNl>M?urI#vJM zuV2>~vnQ`>jL{^ocVExfuWMhguV2>~vuBt1_3Ik*%yq$2zpmB)Huj7?+87g?Jz8-d zt6$fg@4`dzTKXjKM;D#_$HG zjKRWxjG5#AW6WCq4P)!bnAqgY*g857R@cKDeLug~ zeLv4_m!AE{_42l^b$*Ux9mlcOIj!^B=rA@IePRk@Gkzz=CVAAcEswDC2xF62xAy1! z^~np5pRW}^L zqT)qvd0=?t*-MCDx#cg1_usda_^St;GyLX;uNR;GzI}&_-?prH@!PxM8QU%=UgXC= zm{|6a5flH^J|*=ZB%MLhA0)ej<$`&?hG1uuDwD;SVtpho9O1ST|;@ z&#Wb^8|0L=gddnTeh0Ibu>QcTCI77TnL2!Gx8r)|DRl_D4q?|J>^g*9hp_7qb{)d5 zL)di)yAE5s>ag`!9m1|d*mVfI4q?|J>^g+Qf6XuW8FNizB<3C?>@mU~BkVE49wY2A z!X6{+F~S~WYkyYeT3$m^9<}ED7h@lJzm)3 zg*{%_<8AF4Z|ncRb`GUh(2Vh_{zfr;`ZYtUji>eDSo%|&&(uM)wYxsm@0tC5Y-(5k z=1*^b=$AF!Kg~g|bLunuKT{|Eerdhx%C-9VZ%JJF|JI&aeb8+ERU1CGwX47RnLgN` zf7i90ytFZP=J+q{+8DFvl>6tp`gdAGJoY@Nhz&oCo&TnKqsE?Ad-Qomy-{PTZT`zo zuGQ9Gb(q@SAAR>1r~Yown)IY`-{X6oV0&k==2we*Z$Ji>QdJly|y^G?)~<^ zh<~)4tMUD$SE+l6fxZgxAk+3oNX z4&TJ|37^F}_VZ7Q(Tp(``eQ4`F2;w5i5TA^R$_dPv4|N<#8%wmT<`(Lu6@HUY`d`S z!nO6^u%`P0ay5vKbeCv|WT^dW5##qwWONvQJ zu_`HsCB;^Z59A!X%{SSF$uoA<9`%J?nEJvlOnqS&roONXQ(q~D1sk+uA11$Ws=bnG zvZPuqsfJ6c?Go{I%@=${lbEGBQiw0@#2Cg07`re&Vi(4D?81x*yD($LE=&xt3lkgc z!nO+&OKJ#ic6;jwFq04{@9|nV0@tFV0@z%VSJ`WVaCFofm@s_KET+u zZ`g%x7iKKjg>4tMUD$SE+l8?kHgqhxh4BH7--(HL93v*)p(Q5XVM9#3!?u`shfiYS z9lnZ*cf@zp9&1v>SKQ{2e1NfwZ?+5DE^NE7?ZUPT+b(RoYHxO7@|=8NZLx3EqJ7pm zhM0t=)@7J@r?C@X^(W6MR>W8BB9RC}`v+b&FfVHdVtnEFaF zte;=$Q}O{@Uz)tJ_<1W%s$V;BE%AA0&sEQUs))CI=wLd?JE|m{4ieH_#I4N zj)BoY3q~6oFgE$YAKQg(7q(s4c46CvZ5Os(*mhytg|Ugf%=X8=kq7sI(|i}xpSqwH zGowj+99xoRNw&mIUwty;TZ~`r_#ERGGnN>?m@&rq#f&|E#Ka_iCni>LjF=dPmYCRv z4Kd@xPy2>l*mhytg>4tMUD$SE+l6fxwp|#z_>h@c(H^lF`v$vD#8lkoqxw99Su5P9 zBaS{6PWt0^;_h~GMt|}N)BX%rzFQw%n>PKDY&~slOm+)nLo?b6v4F`5F@nhzv4hDW zF@?!3v4+VxIe@7JasyK%Z-@)|d7#I!452K9@7@Pb!Cj1VjFUP>P3)?PiyRhxTwhP-XY`d`S;sd@g{>=2D zJ^S{?bN|*q_~B*rjA;IQ{vuxP(`OA=JLP`ynO82=Z?@tM;y0fA`Th&5T_nDEx08B) zIF>ek2h*2hU^LKz(dIc6jLm2txIOxJ?jJg0bV6T@e*B2B8NU-_Gi->l88*b&3>#u> zruISV-zA+c>37L)m;C9HpI!35OXH&5@at9L|Vh3Y0=j#<;-J_Cg=Hls_jChw*K2dhNXLq$9x9FB- z&BaE%zztiJS(e>Z?YrK(S^3OB!Ok7*+`-Nr?A*c59qin}&K>OBxt-j(Ke>aQ zJJ`8{ojcgMgPl9rxq}%OaZL3oX6(e>^-LULVnrNbV#p6n8^43;OB`V|(1Kg;#Ms0S zx8tAt<2Q^B;SKa5S{2xF5t!q_B^Fk^H(Hr*ea*1@Lrv1z-s*&q7aPc-a* z%bjdt)8nPxaiG8BgO1~dzT=5a#~GWBKQ@USW5H(57wkOJ2X^jY?4t=gcd&B@J9n^i z2RnDLa|b(jZpT0O$8XrVgPl9rxr3cM*tvt9JJ`8{ojcgMgPl9rxr3cM*tvt9JJ`8{ zojbSVll$WOB!Ok7bxWZm(^;yCXar7zSpE!;!VNV>ICG3gAR^f+Z zY2$Y=eK`h311%WsuqVc5#CO~tV;uL7F^bWNJc-ed{E4v{c@<+b>O+jps1GqVqdvsg zbUQZPADh;}ruDIDyR_LK`r1!4>_6Hb7dAa!+8qb_J3i<*ZsG)&QdBJAR z7u@owJ}tjG7IyAn=MHx6VCN2Y?qKH*cJ5&3&h7Z;{`d_$cd&B@J9n^i2RnDLa|b(j zuyY4Hcd&B@J9n^i2RnDLa|b(juyf~jd~$z$g`GRtxr3cM*tvt9JJ`8{8P`t3qonzR zDJQ{|cK8Rg9wR<)ikIPOh3x44^@o_7hSe88Cc=3fhpHSjQ9Bn0jCyu@) zjuD4O2`zDGm#`tme&U+?)O2i3nl;&~$%mSJtI6k@#!}N5;nK!SA2Igvm3Hhi1{nK{ z4aPoWhOtj9VC)kk82iKy#y&BHv7eZjxDT=NvBXe}{bY-ntDUyw8#z)t8fh%~*_z&y z;REk+cz*`-o`v^nFz;V@-v;wuhWBtV?`wEJ2lM`j_jWMvcX-#R_Gi4yrnYF0=XiRS z2S=NpEyD3UP|p_OcuuHii*P(Y)U!o6o-69vA{@^f^=uK2=a71~2*>kDJzIq1x#iea zJX3tyyN~ovR`1g2&-*dnvBA8j;@um}J3!va!Mq>iT^-DOD&FD2ydUG;9?W|xp8di+ zn`g{0J`ij7A=WU*5^ESuVhv-9Si|^0tYLg3*06kzSi`(?vn^uF5AC!OUznH>Uzk`C zUzivYUzphP1JlOuVES?lj0RdT+KdgxR(c=ttiOLuwz}lQv;Lkp#kQoFmlPA8w>wrm zhZplaJjIsh_G*tdp683BFVEY>p~3TiacGZi#aMao;2P8WbmGtaOSQq?0M|@OwNz4# zl~jBGkMHsGJB}D{!4^KGn&()xvzDYef-SYPmZUj_Zyh?UCE>G}wIt0=#;ao^-nyP? zHAYO-PD~8t>txM}(m)65B zt&{8}(6PiIt*h)kP&+Y;^+HT6XIwiyx2~PI-=j8I58}E_9M@F3KczjcwPxI7MjYbW zTh9lGNnFG0ULB5W`0;rvYG2O>+)nJ=KdxWJ=)`rcIIiLKe1JZ24L^=^To;eyAJ@y{ zyu>xU?knj}zPNvY$rtw(FgCeQfU(Ja0*p=W6X3YU)^kEQuDuzT+T$9Yafzt~)-3u^ zBV1?0v~&Fp)1T{d>u|jeqtA6bj9sqpVf^7f0me`66JY%3J^^lZC}zCwPaLd6e5_C0 zY?pZ2AL493$(Q|a`I0{Q@_1=?9O&EA#|It94SmNG zyN)ydIR5zQyx@PjpPH`sjM!acy)TXKRi~UJ=6;U*H?_z89QSW9_eR{m!R>xZ%)J!% zZ?w1jDKYn6+`rM@?x)1utEGF@%-qwdPrJV}KdleGQ3Ko$;v0+|e1o}v3_ry9#SiVY z@jIBl90Q|)7L0bv#nb#ru~L7=MgKHL>C=vWii!N8oi=_4<4cOI?%8R_m+V7u!8c+9 ztIvp~<97E+_pSJ*W3fZd=+k@?6BBYqd-F})d=oQ1awh#}+=FL-!Vmd|@AUUr!nPQl zuq{R(yY#_s{D@nQ#Q2H-^l3Q~6LW0g54I9hC+dS=iJ#UdjpbQ+R)B5ADtt*kFvsN^ zZRCh?;Y%8$o<-13oKj3miWPHE$CA$!TjuOYKeV$C!PWl2=;K57r`z|e%5z=XVEVxH zr#;%rXE!)byv_<|mGy5pQT)W}XO`bAI#vAji@sU5TkurzOy4@a#E&@IO8ib7eM=l8 z4vi98;?R~Y>|%>{n0ETZ^hXCq2YncQ?84Z^9~gh|6UI;chw-1Wd0a5<*yYD@pdZ|P z5H}yh%?EMwLEL;0Hy^~!2Qk{%!Y=l)Vc)O;(;pi!I@o~G=Le>Z-@)|d7#Iy~z-Z@j zWxI)$<2LsH#OP29DQ=1j{liYh9vt>7e!$^Z#XmUwDJHT@J9hC0#-9{h`A<9k=W%7b!IeG{C;C*z@?Ww0@H_g@7hRaK5Eqy+ z;s@M(784VGXm37?o6ll2(4r68*upNhX!lsK0k>R;(LtYf^!b5XF2pSt;+6|>%Y_)5 z&$g{Rt{7XvPuk)~++r)n7wU&TEw9O$EV`jFQ)UNpsMrkvt~+Obb8=#TwW8;nKm*!LKx$GIt= z6B9q{*9>WlnxDiZ>_6+*a@fEYxlPRZTJ2m5aD77`t_8U6fjPf(Jp^+tz;zPLwE)*o zFxLWHSHWBhaP0_lE#O)r#xUy!bxj=1)IeKLR2y)sXSGu^)DrEjp2gHSwMToaXEAev zTBV&@rG{Z_Cf54Z`e4t;{;#c#X}q$HE$rhHjF0#VW1lg=jES+q%qPYS69ZxaGoOeN z%zR@0z{HaH!q`ttOx&lWV~L^Kv7c-abG6f!d?QC{MJp*mQqvS_hlf$ENMlW`F2wKhd!NXk!Cg*z|a5cO2;N_@Lvs zq3?KN({aY8l88*b&3>#u>h7B<`!-g1}VMC0~upw^w68rfK zc4-eA;A;SI>g8N#Laezr~M($ z_LKOB4e7UhiT!*AyR+=;PJBWb+M4Ygx4#iypYF~`&gn<>uBVYOp3<%Q?EYR9JAvFZNUv<^0{ zk4@X9&Hm8WexhOj(e}8o>G9I;IMCnmLC0}J-|@tzmHZe8L#^j2kQ_Y>k~KIC7$+&INML+Z~t4qWQ%-xytF$G^mlyFaoo^% zJhAIId(R2%JtwgDoWS050(;L1 z>^&zidrsJg0J9f^cjRW?^D&R)Bi??zBQ%YdlFh7 z?MZ0IYEOdNBi_lD_9W2mJqa-JPCjc-0`0^*jj^P$mlTtdVpUQMONwntF)t|>CFQ83 z+?ABmG2=_B0qr@#Pkc``qdh0I6L0pMz{G$(C$RUNz{ES%D*I|&!*EX@_JBkmvG>@F zkByvJlU%~sBF8X3kb9U~NOO>}sGZuOhUmi>&BQy+abl%D#5=7C#8&OZo0>+4cvI^z z@n#Od#GAPR6L01WOuWPPn3-d=6L01o%zhQ-Buu=St1z_`V-^!{)(hH+H*+3l4Pd=c z`_unsMaSAfJMm6^m_UGvBtE^0oQj4-n6L>uMAK`0`i8C;sNri5>pDlX%J3%rTtuz7LE4JlhJx_z_3j zFn%YFzQZ_X3YwuY3@veJ52*>-!zS$$FzwiIe{8_$U;{>T?Gn7$lC zA2h;$G1@s_$G>)y!6)zdsK$8M6(17+W8DQOF1U0(@eO}Ha^k6vtt>wNwZEOX;0;TO zPrK@+!}t+L+c17N1)bSf==(KcGLc zz)|yxo#DodBm;5$CkfM{NSPeuz$~!;SN=LleAkXYp15@JImP&& z+NY%cgQPP^`h#S5ko*}WKf7G>X)erIquLtsueL^Uepz(KQ-}O}9GrJx&UKuRV9tS@ zr(n*FoWEesnViGmXw&ro%sG~G7|gksa~RAynVN%rJ>Yh1xIZ>vbg%)V&ksx+zk}(E z4Hyk<*GYoZsyy=Y26T<9cAEGrAstX-{!LXFxl# zOmV}m+G*o=_9w+(*8{W@%bYJbUGw;wVaBywyVfFi#D}<&JD9kVJJ`8{i6!xMJGpaz zatAwiFnQw#cJ5&MVgp748?bW+Q%SC7om-SO@(i}zk|)^6L)&K6(u-M z!wWiewp?w$!F4a6L;QyKmqEQ~Uh&uC4fGY?m|x7?pSsbg{l>|^nE3OdlhnTJV`~q0 z*kxw%+YUNnxYu3xNdM%6e>mLk${&i~d)__6n}2zP_`$7b?x*a(j`+wgPwGFh;V(6o z8{R)}zsgbzzXgAO^o{xZ^6=Ff`^UDJw?F@5YY%B({iI3#k!v0y{?oxT_dj~y55=d> zfA4Uv-R}`E|DsEVn|xsAp8lVn|H$F8J5LhdyU4o3S=OCb{J{R#PMjY$=<~Lvj{Dxi zpBS|t^!=YtIpnNS|66{!)?lk?Bb~cvJz{X-8uv>7rkDM2aQ`Zoh%a9Ip21@uJW_o5 zJ7(^_a?ZM=_D@Xe@*E_;*rKM=oSm^|Moc{Kh>zzT?0E-!-nsqRSTnh9^feWnu4(^A z*V5@a=Q(pdHrEx`PdW6QZsLx=oiq5rdj|vf)4w@!aNO*^=lWS3*XLYUi{tuy5ZBv%yFMSpb+|aL&!@!oxtKLAwNIq}T<2Sd>woKWUm)hb zAo(*)e(F92yKx^UZgtf~Z4BGBdKcHm;<#4lnpqsz>Rd~U<650-Y;jzx58~RpZ`bOB zxF#3JwfdB}Ru}UODz#6f{#^50hkF6*bB`eA9wGTNOnzqn#ra+=jnVg9|F`?N=lnfa z8*lfFdraS-{@?CN$MrnpoPO%?xq42|x%+omqyC-NrF6dbb0?mCnV{M zXxPqooSVdPz8l6lOC0CBVVujvalV^~^PM=(cbTW8K2y@MoI|b2xmC=$HTf{$efE>{ zAK&>sxS2hBF#7@7%LlWUk3D`c`vKYe2ebE&ADA|N2h*2hU^LKz(Z(L!-lvNfS?AjB zlKHL{e{#Q9bw}QMh4{2v7wg`1`H#d4UHQ81!uu~0|8l;rJ9pb&{KXHh*R8Yl1>#3v zvQ2mLBaeyaJ@>rfdHerO{KRH+_U2WVTcdZM^9Q^2K6c5!9^G5>-mT8-ZR@-5_(^Xc z*1Pw{-o71v&3(OnUjDE@_a4i|w?E!Hp4T1tg!VcR^WXk#rRuTYu*I9JW3uf^ud9yL z7fxEVI)-~+_Oj~OPWs)P)iHm4H+yw1R=xlE)j7I;ftjjv_qmBD$9CCMk!nDDQ(J9l z&ng@>qrI#!ds$PBY40oTQD52<3rBrvuPhwe?AuVB*`t9y+F|y*x(|C{eJu81G_eOq zE#rfjHhxDteX$3lfjt;)Y{1ww6X%G(+KGR}L`+N~R$^imF%%QSh^?5|M$E;;JaQo> z7m*_|If~qg$z9}BOirT)#MD64hM3xjnh{eoQA=WKDQZkijYaK=slBL4F*O;rDyCMW zhQ-vdnc8+AYTm~(7p%z~u`T9~ePB-6H|CmsW)6BR%uUCW^}%sw-SF6%%Z>?i+_7Tr zJBF+YjxB42W6m1lT(Gt{N31!{9cz*8QfsLOSnCuM*1A+Ptc_}?mQ#(fma0Aavc`&8 zFH^0SJN6mX#!2s5x?kan5%0a~D*Ze6xmf+rIN*bQx%h|T?{EL9{*)~*70-3n?)}l* zT_%3uSNrtu{P~Z?dw=$zevNH@D&Fk9U+>pm{wnbi>l_*X*6lT;{_7sqzwl4L9JkM2 ze?9I$>4P_j(U~~^#!>&!Klh?hjbV5GEq|+a{F!v(tz!IKXp`GU$A)x;=|Ms!$9(>g+ zhaNBOjsyK2A9Nfy^c_#^I?njx_~WPZg8wnD!aC5#B_>}H2QhJoafyjfj7v=1Vq9YK z72^^U=NOlme8srLEnlPlk*^rnxIM--?jPe4qZ8vA^$-0Rml(S-E;0VZxWxDw;}YY4 z)SwilR3D2j){n_i5WsCb9w9~T1$6mR{8;Uiz{m?SSws!27D)wRR-Ipx(ZSG4JFZTJ4 z<6l`kmcP7dq2lpk>*A|6mp}OM-8XF^rq52Be^kt|*RS_+F`8HXaVs&l9$ji%F+MDJ z->1d+_K`{3i}87#opu&87TY4WZYK`zPkgLH+^kPLZI?LPAL4I6$&39bUq4>!l#coM z<72;6%(uRIt1{CMKCJflZ@qun;7^|vfA}r?m)VcqP5k%?`<1)q+eiG<)AlVNI`km% zx*P6O&U(=i;^FWs<>=Lp6(4ug-etqZPZWRoiapD3cRyKt;MaFA+ibCIj}O@T;)&lB zQCl4>#<#(%_7UUr#YgQbW-PYF zcxx#!8YaCgEmw9 z>sH;mta-{u#0&oQC%dB<@(iP8VfmY)}6_q3b8AjY2${PBxo{5xa#;-LP5gPuMK>Gi;9i5AE@|!sd9qv^x&;cYM%s+|YMCvFkYFkK>P@ z&I|ryqvfk&116T(fbkIX99jcwNCV!|ywG*4< zKXs^fVwuKE9gh2__)v#q{S;5?Q0??h@uv>ej&{n|xE){IA0MrQ@78Bbw#!)U4>7Qx z#K!&;Gmnc{dc3qd4)k|?&~e<*cRXoxoayWMqv5=uO--aa6h}LCD31Qrp*VD?LviR+ zhvKkF9g4#ybtn#-)S)7Qx#K!)&`6XM#(&MGwaiG8BgO1~dzT-)o<4j-29}Tn^ z3)&x_Yj*LqTYa`{``g*XuU+gj<;AOyc)15YS#DbQMQUI0rfte*&zn{Js+_&oEaC@Vx@9?HyP3q_U*O|qrO!X5>w%4S|5&;I_kR;_zV^q;*Ejjgxc&4$ zKP0CA&e!}wjLwR4-zP?Yp6l-xV|S4i?iAzC58idV7(f5M;B8|3pY{A(#f;1CyMBB7 zasTb_+HtINz@s~l^}qS+FO2QJ?Q>rm`!jLLF2#P{H?iy3|25yU+jv~>+}OxFa|ip`7wl(Wu%CUwe)a|X*%$0*UvB5wm;3YV3-+@w z*w4OTKl_65hi6}~pMAmjpYt{2IoN34Jy)KC<$S^9)Xy+sKf{Fm3={S}Qy;pJBp&h6(!_ChTXJu%BVV z)H%6>{R|WKGfddeFkwH#g#8Q?_A^Yk^9u587Ay!n6RH=!uZ28OxVvbVf@ee zO7AB09*RD^lbW9I!mx#1eBoUN%zF~valpJM;oS%9_inJ?yTN|%2K&7m?DuXk+G$)R z+2#Fmc9|XtP^*#vp`yklwgW!lEW7PE< zHeuS~_)&YbJ?rmSv4vgRg2@HG!sLiCz~qjx!Q_-N!{nM+z|=q-Bc?V&OH9qAagkHC zGj4v!FKzUPi4Qt3zMv1|3wB|A;RmLT-@)|d7#Iz-V6?G?pSA_t7HnH>EV2dL7HnIv zZNat$V~h8ju-_NMeqRjxeKG9!#jxKO!+u{3`+YI&_rzuSfVZWs2uUD)q-VZYmjdAIBM^M3hXH1$)01?EPA>_iMr4uLXO*7VQ06aNDn? zwYTL|Yck9p824dsjE`l{4D9_pu=n%8-p>PjKM(BvJh1okz~0XTdp{5C{XDSu^T6KE z1A9LY?EO5j_w&Hs&jWiu5B$va)_Z>b-S#i>PL}Vh{Qj4{^M3ye`~5F{{Qj4AzyF2( z{ulQ9U;6v~Z?sS5{V(r)Y3IGO-~UeUchK0yPrrA@H@|m={oa{Ae(wzXy)%9M-kEm4 zcZU7mnLfNqp1$`e~WT??xALr_O&ux%9aG#0wsDLRnz91H`Ak@5D0miU*4K z*!(0h{=?|N)?vKXfvrOybmAE4gkFjN7l)k^{lsCv#PQ(Gu4{kXouXZpeTLq8Zl=?CLKHekjDqXVOZzIAA~PVi*w(2fqrpo0eg4`YXZF!nhf z#xHbX?7-N9(SfalzIAA~4(;ef|B6oZuPL52#kr>V*RZAjVM~k-j1Fv_W>-3J*p&_( zb}PqV7d`$T#t!{p?1$fC{6d#@?7-;2=)l&2tpi&pcyiMz)=7E9uG;BOTm6{B zxO{i7a^KNE7Eit4%jFFZUL!vLgI_HNuY8mEqOa{!E?M~=@yFl2ul8kO_YeE-TTXlU ziE;Y_kIhnOr~e|0%_c@?o2qQ#$&r5+5CfJf66O9Q0(WD-&=p||4rq+<8fW}{r8N= zOS|Jhf5!(M#|?eQ6T6Nx{y6^l>Ac|ojQRDPoL|$@{F;{L*R(Xhrg?sGEt=-nv^2k_ zrTH~E&97;mUmTm}m)cw1PD}GkI&FSQzs;}7X@1F{HoxR&n@94W`Gu`Czow=6HTgg0 z*Iv`o{F;{L*R(Xhrlt8cInA$WX?{)f{K9UUU+UlHmvq|vl0Nf`{%L;6pEkdyrTHcQ z+j^*c%~%^}=~M3dl)FCVu1~q^Q||hdyWY8Dolm(_|NpJEG3V>=CoNL3MSVW7=!mJ$ zlTTkr?d1J{m0vDqj9Wf2pO`To`WjTd%otyP%FJTM!oGKGF~*$^ zdr(aKI}f{4O#i!9{*4%&6aH|u82uOA`eQM6>j!=)#-BsKQpNcBx5FmH`2X9(FBCH_ zx3iwOKkJEgSWm3aytZA|6Z^w@Vn10Q>_6*?$HjW$@zU-%(BJVv$8kg7@x-pYIQi7`9&SlpZPVa!@cBxTQ@W= z+UY}mwz{26-8LPaADjL(>fCmz|28jlp0%IMm*)TEG{2@XzuLUh`MSkH=Xc_R56mye z4SmNGyN)ySi}=$YKb;p{Z;aLrjVrGqGuFvj`sdO*Iph1g;xmM3N zhJ2$3``by_-%i5*b`titld!*?g!vwk@BLtZI|=*SN!Z^`x*Z$tj|~_dY{33@685)~ zu)m#z{p}>|Zzo}YI|=*SNf;lo0XuiFznz5r?Ii4PCt-g(3H#eg*xydN-Er`@leGKW zN!Z^`!v1y=#vhJ>(QsbyKj({YYk6^kJ7^fJ!F@7=r#2Cf+8DkXVe~eMwYEsPD-Jh6P zhgeyk7}_qewLiq%eiB#v-*P8?;_C6z?l{oj@j=INL*MbluH%e9jz4}z?8g4*e8J?` zxr3cM*tvt9JJ`8{ojcgMgPl9rxr3cMw-XchCswd?2RnDLa|b(juyY4Hcd&B@J9n^i z2RnDLa|b(juyY4Hcd&B@J9lm;ckWN_VCN2Y?qKH*cJ5&34#xkSuaw8}cj(kq%6m!m zP*ReKS8V_V*(2{R6C!Hf@kFyqD^Ogyj$6DRD!#Fa6^&YjzdiTh&%cJ5&G z`GK7~*tvt9JJ`8{v59Tixr3cM*tvt9JJ`8{ojcgMgPl9rxpTYY;M~#f+`-Nr?A*c5 z9qin}&K=CSnCH}O8>5)9N8H84B;qJ0RuMxnF^nHEagE=JiFq6&CU>DFZn+bayYOS& z9{!E{hu>m!VmxB>W1M2_#`wkf6LAsaXT(vA{}D$q<8nJ=cYk7H9b#pDVraX>*8UK4 z`$;bBf6JY0kvorOB z!Ok7*+`-Nr?A*c5o!g0t`x7hJxr3cM*tvt9JJ`8{ojcgMgPl9rxr3cM*tvt9JJ`8{ zojcgMgPl9KlRNh(cd&B@J9n^i2RnDLa|b(jFyr#~ApgwoaqPqN`2H?^`^NW%m3>5E z|5^X86C2pVrrF=4(atv!{7p`HdVC-E|A+4{9Ovo%&7JL1Ykc!bPWcv+Z$V+ck>ndu zm~SWfb`<8D%J>oUt!4a9%r~8JjF@jTLrcszo2iDU>vx?o#)8j`(d_TYXrJESwegJ@ zcK_YJpUQuOg1^hk7-#&=kQ)_;f5pEUlJUKkhX8_I&jxPbv$q zFxtQRneU%i_@S0)<99H9IR-`pEf{TVs886$HjFR$1mh#V!uX!{=>B*2W>=0Se(Z~d z*>B5!S(tse?4yO*pUeJQnEke4PuyZ9Zm|-#SczM##4T3h7AtX!mAJ)9++rneu@bjf ziCe5jeMYeow^)f=ti;5M{mP7m{IeGsCVuR7hS{^s-es7*%n>6odz=&hkN1bC7}gZS z8vaQ?Vpzj(am27jy@?}+HO4897}glSIAT~MF5-w`jd+P8hLs=ur;Xpi^yL^B4YXji zv7tU;6WcJp;1i6Gk#8}+r`lkTx7vwcs-lvssfM+;oOW_W&S315 zOSr{K++rneu@bjfiCe71Emq4Zm|**E9MM7lmGwe zUibXBS@^rt=*;+AI+rO9|B8Q0C(UuKnY^p@ni=o?r+LkUy=KB*GwJU&lXkC}u-8o3 zYbO1@W=8vDubK4mn#sT4={1vfubJx8)=b!ICd@ozzQN2t<{`|Q3AcKF&YuhThJ+Y$ z9)uZJW7U|MvBQj?KI9bU*p^?lxBQA*e#I@n;+9`=%dfcQSKRU|Zuu3r{EAzC#Vx<$ zmfumIQGUfOzv7l(am%l`A;X;1mBDZe@gp~;-U2JCYX9KLYA zmMx!yu>d~FalsxJ>~X;!7wmDt9vAF!!5$avalsxJ>~X2jfAic*{^%dM)i-FF z8EEU?D{dn~ZW0(&g5#{zpS zu*af4Z7i_I0(&elVw4;$nDVMB~g*bt*1KVt00@5J~MHpKWDHpKWJHpGm}?cvL~ zfA~1o3E#*1F{ZKI7;CXV5rbksBQ|6IBWB}qMJ&hTrQLC$zvF|B!NjvY+1=<}4`V$}epyRlqPdsVIuH%e9#2+2} zWPU{-`JeLz`#n@<&qv0K4t>z^{6!zTv||^4VEn;P7(ekJ#(%~Id%WeKP0 zJ{@Q3)A6T1otIXhg&4N_6w^+uX{SFqfYBj0F#6;S#xA*pnJ?rRW*(7ynE8bbn0bc{ zw`0Tou>qrl4Y-X<+{Ptt;}W-ViP6Re$F}uE-0D!=>QLP3P~7TJ-0D!=>QLP3P~7TJ z-0E=L?l{oj@j=INL*MbF&2gr$EA#|It94SmOxHpiL1 zjz1dC3)<8K>#FA$?D++Ie!-q!u;*9sWX~_!J-=YjFWB=7_WWYqrX3sZkB#8To?o!% z7yUiIX!rbrJ-_JV`4#OxUl*D^zhKWV`gnf9o?o!%7yUiIX!rbrJ-_JV`Q>(O1W)$- zvJN(A_xyrAzc|+O3-%IX5(>1EXU)e-EpA5C#mYC2!kbRMbc{8H0-r>65! zP3Nha&R;d1*T(H(bKE~{j&;K3SU+rz?S{>xKW>uC-vz#Q=g9iGuKICM+{qiim6*-O*{R`0gMj0fzc;tFm}l$%zU9%VCE6E z0=Ic5X5L}L?bvXCY{2MX18(CIw{eNvxWsK-VzjZrv28sO;|o5~j*r-YTOEp99g15W zid!9uTOEp99g15Wj@umv`a3@8IBw`Wp0qj6^mY8vzy^NeKWnka#aax<+RXYdj%TbGX4Zdktj(^=wJgzpC6bu zeh1T+V_-DUg3-nXj7_)Wi~HlFb@1K#jLCKxtNkGc_LJDy|8`!JEn?~M((X9W-|<1m zaYNtnq|I@ruj7w~^MbZ&BGyvRFV` zp&c8v(;pkK=NIhx1$%x4Pxkym$McJJ&oBCWe$mJCi+0a1nmxZ@&oBCTe!-q!u;&;3 zJ-=YjFZ$4qjo`_iU)I3}?D++Ie!-q!u;&+y|2bc9JS=VbF_Q!T(I8X@m`WXp`m>v z^x+*f@BH9+FUfvOalDsgzoq)edr9_Nsy*IIvfol1?KKh%nw6hNpP1@OqnBx4L-@lRSNBbuk zqxVlTcJH4I*5B79UbIL2p0>Avc+np5tHjI45-*NL^SQqNA?ifqqD~k;VE6c|DFi7G(G-JlYE`YbrN=cZK*Z0-FL&jwuF6c8U1J67sPcQ zG4Zt}F?_b}3*x%Gpx>^Uwf2&)xQ=aw>1)|o~&b>g3=l`4MlO^u2q!afD#rcYRhvIz2Jw-|SrP<}VYr!A#9{!Z% zXG#8-s0sCnaTRP(lQFJ>4UUa*6>Lxs=*0bu7=3=|PaD6Z4}CcXMguMSpp6YQvFUbv zp+8;lvFYf&B>MDcOwBI$`|^kW#K3+M8*I>@m|=rH)V{|{dy50l9~2+!IBw{-cvAo4 zI1@|99}VXPZE7NoON=kn1nu}3;}R2}7+1wEV~QWOGuHT>+KE9Nqjtq6?(IWoGBINg zqe(2owwU(tNypNkIZPjPVhm#RV_ahFavx3~{E2ai@iWFH9sK8ho<78q_F$f$jQbM@ z>kuF76SroUb$;v*`NB^$iKYD~mL3=R3fuC5cE^GK#D`Zbu*Xzn$lQLy)!3OdtMTKi><${&(oO&&~JR z{x`h*Z<(P3``>XRFZn*v?f$pk=%4?sH|}BcJ*M?(&-b|zQ^lG1!Nk^#|1H;Qe@5P) z_IE|d4gL8WBj(V7rQh0ZOYP0pnCY|nneSxG!x+!vU;5TN#2c?YTffuAQ%3yOul7eS z`#SOJXI|F7>XQqIkA3A+ef)GB8*QO;nK=5^jokNwfq)ZV53UDD~2ewXZ)c#89 zQ|CB+?sDAvpVi;|J@?+Z${MThrS^?ao2$&c>(|tN$7kjc&#}Qz2WR~DMdDYix_Wo) z>Q8j^+4!_Wx&xQIRs6k``i>vkY2$Y=eK`h311%VB#sgzB+J|nB{=NH$ju@TL7o#6P zVr<6m#MlfQm1D6PHpJKr8{&x1;;DU@`s1s07=!iuWS23koxaJ>n*7&wSsNGa9&b%? zs3|_^cl5_5V}r5Dm`6H?D0VP5Q(lHSU(>Tr?!IqI**0*2IXWg-o>hsCFZW^BOuGi|=t#{n9 zU#HHmT3zkrUkxufV^Qgxwb3^HpKqJH92s@H$Ff%s*SlyzX)d$oNBT{7SzMY6|D^V3 ze{#-pOw{uk{m+Jb{$O6|U-q>P`=y@0u=F2X;=BDmznVk(>wWw^{TffsEB#AmJG1}9 z5-*YdcV=I!|JLy@m3}>ITK~o4=al|7=RVTkcJ*x1Uwi5r{RZ>RCjGVFeL}y)OtVY> zLr34+Kk>EaOaG`jj_x11VixKDW2syEiPz2~{h42Vc>l4rpXivU4}JIAK6E=`7kBQDa9IMv9j^drwTYD@Z2 zYc=8`{fJW^d6jjDjl4=f@?4|-2E-@ou|{5{A9=1(iv!{xwHfntuc^d8 z=1q;fNkqb>);Kk8KHGW28Jtx=Z);vaRYcJyNnu2Gi*;vaRYcJyOC#{V9D{ExaE zkl(0N^+7+@Y5X7Bf7V0vW6j3@q5Y>F{aC;8e`x=iOXw4S`i$ylZu}qGf94hX#GiR( z|Cv|l6MyEF{bydGPyCrz=u&@%sUPMQ`qV%33VrH_d4)dp&%8pP`e9z7PyM5dK6aQ_=u<}09i4*e*ed-@w^sz%+&?iplqK_TofJokGl(?WzoX9Ks zV-;^r=nqiavQ}UZGE&GOy5&xp)fm3VrI7 zd4+zoFUGt=pE_k;p^s+rzhhpZPn|Na(5FxGf55y#AI;?dfO&;J{geNL6#p)+m!yxM z$^Su$f0z6pr1*Eq|3Qj>m+B|`KS=TKQvGx({#~k{F2%n~_0y&L?^67`R6kv+|1Q-} zm+HSu_0y&L@6!A&seZat|6Q8DCDnhI=5I;$-=+E6rS+$z`tQ>G?b7;F(){hx`cu;U z?b7;F()wA_{O!{EQ_}ib()v@<`dQNYQ_}ib()wT0`qQQLv!wOEr1i6;^}nR`v!wOE zP_Lu)r&uINwzNGbE?W6T)>5|re?s2A$)}P7v-=QD#tfci{$Bx#YSKzH3ZO zk$%jxlCIyVAL++DE9v@;`CEuTcGC3^_1_Wym}ku2LVmH6uHTryh5TYCUB5AZ6(8)x z`Xhbfl&;^HztYD}tUuBxPBDMwKXzjMkv?&X`78gi6YEbI)z7q!yy8E3j`^$jU?!G@Po9a(sD6&_V*Qjpc_uES`Z>HKujrF!>JokGG}a&K6Q@`|rB9yIy~%*Q zqEDXFeae8mqEDXFJf^ zl0PN+S(5)Hp6N^*`SURC9xwe1?O_ugao9v(Of31K4{iKzq_bV&7#NN4UyOFn*O_}f zTt2kTPP!gAc9Vz7N%y=@&qiLb*MsGe?Uq;j@1OX6xqhYv)V|)WzbkM3-Q&6@IqU6r zm#@wJ3q5CBd8OOSUEe=f&tz75^yaeWb;r{__4ZHQSUz;^k+d(q-0j!vnU9{;9Q`Zt z&mTFwTkGbZickF3JY}xG48_aczCk&9({G5cxOBh556_Ee<99H9IR-`pE%>O=rcPjN zMtkq}=wIDGbj0X{z8L-Z5o0rcC&p&j5MwiJh_M+q#HSv+>g3ekr~WnR)TCdN-J1NV z$9P#de+IuuX~_u5H)$m zMW^*YyxGtwbFlbo(1cjr(7-lqh7s0 zJ!XktNdL?|wyXOrb&d3o-Q+X%n+N_}`Y+h)Q}vabUMc59d{bTj|xh|Fd$}4@OUj5;Vq`&f`8`ZbWG$H-V%dz!si(M%Fv-dcr{^9)ZN&oNb z9$o)_`FEv%);UMk$G137`cHiO@OsY)-(3O7Jsi7k>?tD zm44*8MqZ^Kd9IOH=|`Sx5S=NfsHe&o4EU3S!G)M<^n>{v6SPHWU<$C?>+TB9yI z*378W8g<#RW=5UXsLPHuGwQTPU3S!G)M<^n?5NMEQ=Q|`k2xnsKh|b3`mr{P(T}xR zjDD=mV)SEe7NZ|)v!4H;zw)Cuq2KC9`mKJX-|9#Dt$w86>PPymex%>(NBYzc z^9ub||I%;uFa1{k(r@)I{Z{|dZ}l(zR{zqc{?SFh&0p!a`78Z4f2H5%uk_pem42JQ z(r@!u`pjSAf___nq~F#b>9_Sq`fdG@ep`Q}-_{@LxAjN*tUu%x{kDEezpbCrZ|kS@ z+xjW}wth;#t)J3w>!`@^N>BGFDKDnM@UQwU)PyTnT3+S^>ur8p_ zI>EYtKI;VQ0{W~ItPAL~POvVZ&pN@nfIjO)ihp5Vq0c(Uyh5LKj(LSX>m2h6ebzbV z75c1m%q#R+=a^UMv(BaZDayuCtg|=yRRLyh5MrEanyZTxT(_(C0dfd4)dLSzM!z)}M#P z=yPvDJNn#P!02;t0i(~o1&luT7BKqUTfpeYJi~vVfAQbvU;Ov^7yo_!#ebiF@!#iP z{P+16|9$=?{ssSIo)Q0&;$KqyONxI<@h>U9_ik zeybnpxB8Jj^^>mOsDJ6V`j>vIf9bdSmwu~%>9_iqeye}!Q~xo46(8)NOMKe=m42JQ z(r@!u`fdJ7zs+CixA`l5=5MS&(kD*DWmG>}f27~mAL+OCNBV93k$zi$q~F#b>9hWj zSMp1qnOEqy^;7z7{gi%NKc(N+PwBVyQ~GWFls@Zcx_@E)mwsFSrQg9_S?`fdG} zep~;g-`0QWQ>X2|Y>@7w2i&i<`?vx3j_v+#z&&NV?;CL6*X{=g+=I6J!~yq-?f!AV zJ!`wK9B?no`7G`SL+5(mhpN5ZpQ?YmZaJ%0W)3@Ch%g=VdEdSem^q_7( z&$QIe^8p=;kN7(BN6!bW@B4S`@_az;#31=uh!Mwfk30MIQ@M|3T(ol^t@acLbPDb0 zq_`Dq&`uk_8|mozfEW#I(2jP_*Ba~J%>EYT?$)WdvA;#U!+Ce{3{brDX1^=(+)uph zp}*((UPm7Gd&7e~)9ZMy^6SYDvA+dge4Q;GW`B#?ce(Uo_O}G@wRn5ZBW}-sI-dWu z=RzINh1&C?cqX)+pCffVM{3WPI-V`H=T04c+w&-CwC7YE+V~gGn)GZb+IcRg_UK>X z_WVlRo?nUE^DA+CekI0c95d=OdVVEt&#%M>U9!XE_FRr}@r=y<{d|vc`MDqC^7BB( z<>!Qq%g+z-)6W(0zjEGbbwmevOwxjzu4Q}BX_27UP9oNq^<#yHN!@oJ9KmUfiRFm)6>g4`;Pu;7UT=Ar- z{TmLsUp2YZcHii4-t`YWTkbZx>ePO>3m@Qla(C!APwOw5?P}@2;(PPgi3P5e{&&uJ zc|G&q>!iQfXBMuvZFHmb_x$rK>gpTcBK?~eU$n0J%Uh*Cd|(%E^m6I%aNbAjSKoGp^mpEDt9s7NS4w}` zL$|4$toC#1@ArmJ)!iPuTKd19{F%DWOMW5!b+*{9Zu{fYrT_jDzgCZ!?@Z}`@M8zp zW#9O1=|A+m!|F9NpC|p#ZE|>BVTbQZf9`FMtbg0#d(waJf=AaU{&Ioz57_9K`ltIY zl>R$jdu$C|>4%*fy3!9jHFTvPc53KKKkU@dm44W%p)38cQ$tt!VW)^jrN)ztz9=Tm4JF)xY#x{Y#(vM;HIw z{FQ#2ztV5>SNd)KO25rt>9_eS{WgE4&-^7W=(qJp`fdG@ep`Q}-_{@LxAjN*ZT*pc zTYpCJiS>uPqTkj}>9_S$`fdG`ep^4K-_}p*xAjx{ZT*x!>nHOH{kHx~zpek$Z|lGG z+xjp4w*E`Mt^d+*>%a6_|Cv|l$2G}f%q!}X=O@f7>Jw&OQJ-8#Ft4aju5FlC)FnyHON9)hcV)VJUpdEegEnxJyw}8>--U3FSdkYwS?k!-&C+;oM z`4|6v{>6WvfAPOd{`>rk|33fXzt6w;@AEJ5FZdtxjQE!n|B~WgQv6Gbe@XE#DgMRr zPuD-xkMvvpNWayO^jrN%ztxZQTm4AC)sOVKPE6Nt)W7sw{Y$^qzw}%EOTX2>^jrN) zztz9=ssEV2iVt?sB|dHbO25rt>9_eS{WgE4-{!CM+x(S2^EcKX=@Td7GO8b~KhkgO zkM!I6BmK7iNWZN=(r@d}C_b_NkXQ0co|#wZxAjx{ZT*yfTR)}W)=%lT^;7z7{ggiI zXS#o3{g-}Q|E1s7f9bdNU;1tRmwsFSrQgH_acN6-CgYz8siG0J+zOzs}HfZM?j`m%Kboh3H z_Vzu6xP4C{rf>W1Lw>gJLF9k?PK0yl)YQ)RFBMIEY~P76F4>@+F(tbiGwpoCk^J;` zF8E*KT(0|QVwuKUQXEQ(k8HGYVYjp0_MM3QN%5Br`kjQ1srH@JfN!VT_frGf+ILk0`nK<_257YJ zum)&TCp=%mX0+?MR{K6n+`i8ex9_vW=*LgxSZv1c#Mq2u#O?d65s$vl67&8mY`DEo z{rjZD_jKwL`aM6`qAhILAAcXmxN7o0?yY9gbGaB7?H$KrGsOWNwPQ2ItunSYF8mQ= zlUUFm8hlST;?ehXV)8pZ>*TgK&dKxVZmlhUHeBk{bE_twIOylY+ZUK$HTnLDYlqv< zxsYn|bM?mI)kn;x{%>7xjsDYbT2%G9+ehylUN`Y#9ed)oYxak~_cf~3cYNl7;k38T zA)UMTSg(KE3d`~gdGO+|KQ_GoFY`#VZoNVOqGO-r9ZL7UZ4T}4KYazBEe{@DapwMk zYhEt>S3I<7fBI$5lm1TUe!V~NxK~O4>R)Z$f9%Owq<`{ONA<_N`Zdyj=T+PHU)bnH z(!Xx|>n|)1^G>ImecPY*p)38c(=WKiV$xrF&%W<} z@;L8$23LRTmwo6;KkW2hd2nXwUpl<04_)bpo&II>%qIVTGuu6V=t@8A^br^7N1XaA zr_Le$tzPHJAK4O`VprZy1Z8!gq<33k$%LfhA!`z24Sa0T%;dys*y|SM{aBA z^6qI6c51{$`VprZd6jT;m<^G%DY5BfWuJ8zA;91x$VQ?;WXYjBOa91x$VQ?;WX>oNWh?SIsz^rKGI2mM&5 z@qcLlSr5^VH5>nj_Mdk2WBtbeq5Wqrp-=od{}KPC_w4Y0X#bg4=o5eDmHlU4p-=po zSN5NIg+B3TUZGF@Ft5<}09i4(f$V~4n)Pn^gr z`s5j1^sz%+&?iph6@BtdT+k;@PUIDR^31$KpE@Nj=o2UMiavQ}UZGE& zl2`P}GxG|4>Xf{qPo9}q=u@Y0K9WB5OJ30@&$0eXpE_k;p-&&?75daE^9uc_>rX4tU-Jrm+LQm9SLlc4V#)tOihswvLZ3d#|3Qj>m;4{3 z_;<{+d^Fnpfy^o=NfVQvGONq0f0H z)sN;C`kZG{{b*jH&v_=z-!9cpm+D{h3VqI#ss1&u(C0jv>Rr1hty^|Pe)r=<0>r1ig~^{1ruv!wOE zr1i6;^}nR`v!wOEP{*VCnfw2+_a4xi6=m9X2c(ITLrVt9QIN*-);=K61c?d)O=w9H zMbwet0D=S&42>d)fGC+35lJHF-E{~}5CoMZIU^28&YAw6>wfP#Q#ivnv%b;)cMh;t zFRoRm-lukjUAyku&wi?@=Fg^@|COgVe&%ed`CsY1@iT8z&Hqa8jh_X${tot8>s9l= z^7Q7P#kl_R{8f5y{#l0WFVA14_vW9Kx&HF}rTr83<33X!#(&&rTz`4~(*B9-kNb@4 zFVA1vKXLtWpK<-=`AhpJu0QUxrdt1`>iJ9iC$2y4v!+`A(Eerp!1$4U)``{nf$<~z ztP{DfxPI1&)%t<)Bl~fmHP!kpRqLOoTEC@g{nJ$IH`&ELI}Ke)>7?--iCB9NMKfe$G(8VxNAF`A7C?C;Aop^mEKVvQInFuh^%b8JE~+oW}ek z`?M4NihcUI(k84+WS@SnbPDSd*{7c?&B9tlHtE|+v#|b?9mZp&O?U<=KV!}Mz2zSD zeoKq4x885PFTtKb>wO8a_a(&a8F)XT^}dACvEluP7Tc83v-3e*4%)%{NTog1c5dhY zR$LDH?u6CX(SM|K4fGuxdDY)A`%?5B%zhPp2S=Ht zcS|~Dl>C$dV}~+e*HKIwe9nQ&g_Lf8A?3Hf5Z@;jKP$dZEdE#j zPv7xT-W4DI3FA}WV8Zr^QhMn-(o5gL_KE7{>G?#7@nzzg$zz|W1mhFMeb=+o`v$Y5 zQ%1>888CJz1IFiyf3SU`#N?$6<>~oEiMjr$m$-a`Ngmp@%8w6Qu|pe*!#-^*rfsY1 z!G}%hrSGs=`VKCASJJC?kS`qRrSD+u^ADz6{su>x`UX>Z{0%0|_1FEyJs4v~I?m6# z#C*U#OFHue_cF}32{3-+H+AI4igY-yK88B^7U8m+u(rGjHjeBp`BQyYGuISz>`*_#Tsw7uX*cQymwtq41KI+njpH}s(vPHX&robTjow zdi%n1%eNEv93%eY_G`4OEj3zv-E`}<^X@!K{QJ+Z*Z%2&k>b8R)^ESDTaQ0=$Oi33 zkB(6K7TrzSG5hwo|2v;;*IK5><5%3az5j)&TtmBG+NB+}O^?S-{boC1j~hU8N-rVl|>*Eegl+i!bE*T3GcA8PM?;BD~+8$R65cKuu8ogaIoz4(qd#dCh{vG$Cm zdVJ%KkGIdA`i9c?Uh(Png0H?V{^o2W^3gl=c%KbNuY=M@cqRX%mbVC_$P~hG=J^h z52=n{T6mfK()K;Rd#;so|4)1My?@S?^27NxUE9X@FQ2zcuZmw7w|u^IPpRDFj@do$`u1PNU;o~2`I~P%A)fN#-SUN_d%Wc%yXO7x`!}V(z1VJf z?VJ80{^_H;<+)ydO#I@sd*rK^?D0z<`9hxh&?8Ep^YX9ekAJ(z>p!q>-sZ?2Pnf!Y zUOc{s;vU)Q{sZz8SLvQ@H{JH@`OqnUR{FD_I3(|LRIl87e|2b{Jpa>5KjRNa=0|Sm zwa?P)e=q-j5XIJy;!eppPGDZKKJQf{;fAVJ}-P>&*tzQM6 z+U#EOt!o~WADVEF_|iuw0%AbjEH;=kiyw7Kk%g@f%Fi1YI1OZMvZ z{Ql?XM?co9%Rx_EkpHq#uiQN%&haK!+@Sm?9Q5%?#0eNJ9~|7*qLEJ_J_aB-x%NHwN5@iZ~NIEFFW>veA%r%zU>V*ixI91g$6tvLSnu+@_pi!+ zJU6fU+kD8GJs$hz>+?g0oU8noYB%W~DZTX{LKT-V5nA`H>=lxhb>CjvA>OVd~ zyw_Z}<_iz_k@)H-Z^`?A?RfF!)7_e9T<xd_v_IzGoU~TaypMEa?^tLs{Gq3ero_TN$ z@%TSIoAW@w_~eV9&BraC#K*kwY<_Cg%HlJB@qAuz-j&2t`d`TZHhBf{%41&4AKGbo zal6Ay`I|2;C;sc*FXyMn_0n%0_iBFYC%ydJp8Q5WWx1Z6>t`D|7|(3wk7xK`Jj=!L zY#)qgyf~iugYoPa$68=;kFDkq?|$#7!OIVuQM~Xx@8r|Bm_dB}xo_nqCr&T^-Q{oQ znO2)lyveI?;(Fr0>@aF@`HAa_Uz=~5!P7^s-s5}648|H=9BcN$b5@*F zyyxOG4Q{yYD;?GhKkc7s@XMQCBi{BiGY!76-6Zh^4~!W+eBX)UwJ#n$xc59;ir0N^ z)ZpmZHW5F&_o%@sE3PFz&k~m4DSB+ ziQ>uEj2JxUUw%43`gg7#G5FW3|16$x--yA_UOQ`-^jF4?96VyBRm4aBbmZWf6E_gg zw$7-*-T%CWc&TSb4Q{gkZsHftm}c+`zdKfZ`$p4IFERCs`iiM=zf5Df!|rWr)Tz@cdd(J*jmnn5%S9GYej4FiX!8AQXtp=mN2 z1`bV=(J*jmnv8~lL(^n53>=zf5DlX|&y5&F!@!|w2GKBZXqrJZ3>=z<@hoOMqhUyA zoTFi2#y=Vc=Dt9~z@cdd(J*jmnn5%Syv+ksGa3dCO_R|uaA=y0hJi!VWHbyMnkJ)R z;LtP~4FiX!$!HijG)+dsz@cgKH$%g~p=mN21`bV=(J*jmnv8~lL(^n53>=y!?;aWk z4o$;6CT1Q(!;sGWhK7Ne_s}pf^C21r4ox$NhJi!VWHbyMnkJ)R;LtP~4FiX!$!Hij zG)+dsz@cd}8U_wclhH76Xqt?MfkV?|Gz=V?CZl2C&@>qh1Ba%`Xc#y&O-94Op=sj# z$4`kv(_}OZ>7i*d8V2V1g@%E7uAyOIo_A;%nCBoG1`bV=(J*jmnv8~lL(^n53>=y! zqha9CG#L#8ho;GB7&tUdv`??B&@>qhLwabMjD~?j(_}OZ9GWJhVc^g-84Ux6rpag+ zI5bU0!@!|wG8zUBO_R|uaA+FVEn?O!Xc*F2&!Ayo);VYxnDq}D1`bV=(J*jmnv8~l zL(^n53>=y!qha9CH2I0pFmPy^jD~?j(_}OZ9GWJhVc^g-84Ux6rpag+I5bU0!@!|w zG8zUBO_R|uaA=y0hJi!VWHbyMnkJ)R;LtRzSH-MX(J-X5jzz=3tZ&gUFza443>=y! zqha9CG#L#8ho;GB7&tUdM#I3NX)+oH4o#EMFmPy^jD~?j(_}OZ9GWJhVc^g-84Ux6 zrpag+I5bU0!@!|wG8zUBO%vC1kvKF>M#GREnkJ)R;LtSa6frsl4MRHmg?}(<{0$~A z8U_wclhH76Xqt?MfkV?|Gz=V?CZl2C&@>qh1Ba%`Xc#y&O-94Op=mN21`bV=(J*jm znv8~lL(^n53>=y!qha9CG#L#8ho;GB7&tUdM#I3NX)+oH4o!nT71Ou$G3oRqh1Ba$zUqZ}1&Am-J z_d54H%pAa605dnBVc^g-84Ux6rpag+I5bU0!@!|wG8zUBO_R|uaA=y0hJi!VWHbyM znkJ)R;LtP~4FiX!$!HijG)+dsz@cd}8U_wclhH76Xqt?MfkV?|Gz=V?CZl2C&@}8v ziJ8lp(@AHJXRe2t`*{YyJQL6`aA=y0hJi!VWHgNOH|u6J3>=y!qha9CG#L#8ho;GB z7&tUdM#I3NX)+oH4o#EMFmPy^jD~?j(_}OZ9GWJhVc^g-84Ux6rpag+I5bU0!@!|w zG8zUBO~XE4mnnx>0} zfkV@D(J*jmnl2g!4o%ZV!@!|wx@Z_UG))%`1Ba&RqG90BGy`ZDI5f=w8U_wc(}#wE zL(}x3Vc^g-9W)Fanx=z>fkV@D&@galnhqKU4o%ZR!@!|wI#sA&@>4R1Ba$bXc#y&O+v%Kp=lBt1`bV=&@galnuLadL(?QQ3>=y!p<&?A zGzkp@ho(tr7&tUdLc_qJX;QqG5r?KpXc*E%(rfJYHaA=wa4WsnWP1B%Z;LtP;8U_wc)1YDC&@>Gi1`bWrpkd(9G)*;+HP!sq zRP$a_&4&#dhTn#!Y0xlmXqpBM1Ba$*&@galng$I6ho))JFmPy^1`Pv;rfJYHaA=wa z4FiX!Y0xlmXqpBM1Ba$*&@galng$I6ho))JFmPy^1`Pv;rfJYHaA=wa4FiX!X{zT} zQ$5$3>Uq~x&%p)_!*4^=G-wz&G);qsfkV?YXc#y&O@oGkL(?>97&tUdgNA`a(==!p zI5bUzhJi!VG-wz&G);qsfkV?YXc#y&O@oGkL(?>97&tUdgNA`a(==!pI5bUzhJi!V zG}XGLsn#>$@7-%#_HL{7PlJZxx1nhoGz=V?ra{BNp=la43>=!KLBqhIX&N+)_`FFC z8U_wc)1YDC&@>Gi1`bWrpkd(9Gz}UC4o%abVc^g-4H^axP1B%Z;LtP;8b-Y4NevnX z4o%abVc^g-O|@Qas&#Brt#6xZ-P@pH_-$yK1`Pv;rfJYHaA=wa4FiX!Y0xlmXqpBM z1Ba$*&@galng$I6ho))JFmPy^1`Pv;rfJYHaA=wa4FiX!Y0xlmXqpBM1Ba$*&@gal zng$I6ho))JFmPy^rqU@*rC*v#*EE&hY0xnIHZ)CxhJi!VG-wz&G);qsfkV?YXc#y& zO@oGkL(?>97&tUdgNA`a(==!pI5bUzhJi!VG-wz&G);qsfkV?YXc#y&O@oGkL(?>9 z7&tUdgNA`a(==!pI5bUD>C>jttxct8n@Z<4Xc&GQnx;X+z@cdxGz=V?ra{BNp=la4 z3>=!KLBqhIX&N*P9Ga#=!KLBqhI zX&N*P9Ga#Gi1`bWrpkd(9Gz}UC z4o%abVc^g-4H^axP1B%Z;LtP;8U_wc)1YDC&@>Gi1`bWrpkd(9Gz}UC4o%abVc^g- z4H^axP1B%Z;LtP;8U_wc)1YDC&@@f8AJtU*R86&i)nDyv^`l|97&tUdgNA`a(==!pI5bUzhJi!VG-wz&G);qsfkV?YXc#y& zO@oGkL(?>97&tUdgNA`a(==!pI5bUzhJi!V^jG_k{nh?tf3=!KLBqhIX&N*P9Ga#=!KLBqhI zX&N*P9Ga#eN z@Y~Qd{b(3CG)+Gm1`bWrkA{Im)AXZZ;LtSvXc#y&O+Ok24o%abVc^g-4H^dC{&Q0s zGz=V?ra{BNp=tWjFmPy^el!dmnx-EO1Ba&RN5jCOY5LJHaA=x-G>rJ(G5ythhyLn) zM1S?3qQ827(T|4Vx1nkJ(J*jmntn749Ga#d4FiX!=|{uBp=tWjFmPy^el!dmnx-EO z1Ba&RN5jCOY5LJHaA=x-Gz=V?rXLLhho=!K9}NSCrs+q+ zz@cfVmpC*H^%aMvp&b%=LetPbVtmceFr?#ahK7OhHABO|_?n?%V0_KcFfhJmXc!n@ zGc*j0uNfK!#@7rD1LJFkhJo=lL&L!MnxSD}e9h1>FurDJ8086HGc*j0uNfK!#@7rD z1LJE}y=P>cD?Ky~<6j(_hWkQ{uNfMK-{NbAhJo=lL&Lz^JTSFE!@&5OpVPJgC z&@eE*X4U&;<~OB>reWR_ho)gZ6o;niN5k-2e9h1>FurDJ7#LqOGz^Td85#!0*9;8< z<7FurDJ7#LqO zGz^TdSvo&@lWKUo$ie9Ga#97#LqOGz^Td85#!0*9;8<<7Uo$iejIS9Q2FBM64FltAhK7OhHABO|_?n?%V0_KcFfhJm@m@xZuNfMK zbbQUwFfhJml^+r7Sfz)iVSOtOO~blZ9Ga#t&CoC~zGi3`7+*6q42-WC8V1JK z3=IS0Ylen_@ijxk!1$V>VPJgC&@eE*W@s1~Uo$iejIS9Q2FBM64FltAhK7OhHABO| z_?n?%;LtSa6me)8^ouw&4Z2258h;}{dC@R1zGi3`7+*6q42-WC8V1JK3=IS0Ylen_ z@ijxk!1$V>VPJgC&@eE*W@s1~Uo$iejIS9Q2FBM64FltAhK7OhHABO|_?n?%V0_Kc zFfhJm^d(H+(#J4;PT#|fh0wWT#t0gQbbQUwFfhJmXc!n@Gc*j0uNfK!#@7rD1LJFk zhJo=lL&L!MnxSD}e9h1>FurDJ7#LqOGz^Td85#!0*9;8<<7FurDJ7#LqOGz^Td85#x-P1B%ZV0_Kc zFfhJmXc!n@Gc*j0uNfK!#@7rD1LJFkhJo=lL&L!MnxSD}e9h1>FurDJ7#LqOGz^Td z8FM$xTps&WV&?eRzv?HQxu0hM%rgNE1LJFkhJo=lL&GS4_?n?%V0_KcFfhJmXc#y& zO@oGk@ijxk!1$V>VPJgC&@eE*W@s1~Uo$iejIS9Q2FBM64FltAhK7OhHABO|_?n?% zV0_JZX2U$gd6vUG+j+*rJo95eQ_NZb4MRG zFurE2)nL|ctl?nRbgb=Q)_SpzEoKdfh9MnaGc*j0uNfK!#@7rD1LJFkhJo=lL&L!M znxSD}e9h1>FurDJ7&tUdLc_rLnxSD}e9h1>FurDJ7#LqOGz^Td85#!0*9;8<<7*c0 zWyJWJu|_AIH9Ko}n6*4>dYCmnYkiotKN<$c*9;8<<7VPJgC&@eE*W@s1~Uo$iejIS9Q2FBM6 z4FltAR@JLp)wf%<1K$Cu{mXZ1{I>eOY3RFb()pgq-{a^TTYsmcZ*TqmPRln#{;r2_ zq_V$n;v3lVeUrXDq6}=3?(c?_pE5|tj=wYd;M?BbcW3lVJ)WgGX{*qn(wy*c_`b<= zQSv)t#&hyJVzJ*5i~WvR?03Xszatj=9WmoP`5m#??}){IM=bU`V*S?dh{b+KEcQEM zvELDk{f=1dcf?}9BNns2Qr(-wcFu7flizo%?tb4b_WN$J-*=1szFX|~-D1D*7W;j- z*zdc=e%~$j`);w{cZ>bLTkQAUV!!Ve`+c|A@4Ll*-!0~O@qT!2`Wc#dhWeYz#J-om zsZ4%%uQu_!d$Hf$i~a6i?05HKzq=Rv-M#KXzq=Rv-M!fF?!|t0uiyIJz1Z*W#eR1$ z_Pcwr-`)4}#G2>*u=evhFxd}5b+;da*nS9VTl*o1?S~+?AA;C^2x9voi0y|UwjYAn zeh6awA@tIFeh6awA&BjVAhsWZ*nSAQX8R$CS+~C*^ozAjLd*DD*JPgxwU2!&#P+EW z+owWop9-;kD#Z4w5Zk9hY@Z6TeJaHEsSw+zLTsN3v3)AU_Nfrtr$TI>3iTt}^ZlT~ zt;Z93+~4gc`-iAa>>nbwe~8%rA!7T7i0vODwttA&{vl%fhluSTBDQ~s*#046`-h0_ zA0oDYh}ixiV*7`P**|$d>?3(kDY2*IZ;+FHUDOWtbrIXwMQmRev3*^7-1Bu2+t)>G zUl*}`UBvcv5!=^AY+o0#eO<)%b?I@>*F|h!7qNX^#OwjSANE4MFPhjF_4m}temiOh z`|XJBw|PnA*X zxry!PCbplO*nVze`?-nj=O(tFo7jGCVszE}!N0}6F52^OEQMsBJ+*^<_Qdwt6WeD` zY@a=`efGrm*%RAm4|Do9ahhqC5 zitT?Ww*R5n{)av8`5%hecVzE4%F=%MaP>1}ADQ-Kznu4uuze}T_N5ftmr`tBO0j(@ z#rCBX+m{kQ$z)$jv3)5ANVhMg*uIoq((OwrwlAgFzLaA7Qi|EfYoqK+vV*7=P?H4MxU#QrApxip!(X!Rcs$uv3*>{+w^=~#rAO( z+s9RGA6Kz`T*dZr72C&^w&lA$d|bu$aTVLgRcs$uv3*>{_Hh;4$5m_}S22ATYdM%$ z9K-gTg;vHf+$_SY5L zUsr5@U9tUj#rD?~+h12q--WhqcWZz?@+xJ*(-(#_TkHz*q z7Tfn&Y~N$CeUHWVJr>*dSZv>8v3-xl_B|Hc_gHM-W3hdY#r8cG(|57g0k_`k5D&L+ z$70V)^|c?h*nZSvVs<*dO|l=g((OkrwjZ_Fe$-<7QH$+IEw&%E*nZSv`%#PSM=iD= zwb*{tV*62x?ME%PAGMgii@is<_1>d+xPAW^d&sJ87u&yG zZ2xw#{oBR7>xj7qmcRFK{SH0m9o5&q`eOU)i|wl~wy(a}zWQSO>Wl5GFSf6~*uMH= z`|6ABt1q^%zSzF{V*Bcg?W-@gufEv6`eOU)i+R@(&wg0G>%%pcLaYN+Uw?NX_IC$j ze|I4EcL!pBcOdq62V#GBAoh0$Vt;oa_IC$je|I4EcL!pBcOdq62V#GBAoh0$Vt;oa z_IC$j-gU%Ue2{*$?}~W1#RG|TIrU2ZhC+4sHxy!jLm?(!uVY&!e?y^ke?uYmHxy!j zLm~Dz6k>lvA@(;EVt+#+_BRw_e?uYmHxy!jLm~Dz6sn8Ap%Bw|p^epd_9YV!x0p7e zlT}}T4~CAt&i=MV>~CAd{GVw=H6S+amV2EnI~}pV(-HeS9kIXD5&JtG zvA@$1`#T-6zta)>I~}pV(-HHo!((+=$H()WgFiXnu&D0-hDGdeSj5D)b}YCQ{^W{h z&9jyG){X_2h;Qv!aEbWVjs=&9Z|zuciTKuz1((8~oVW?PH;HfUSa6B>){X_2h;Qv! zaEbWVjs=&9Z|zuciTKuz1(%3#UClG>k8}OQI>w{d0Qi$DHaGneYXHUOhKbc3`{Qb7 zVs$&NT_RSuUx+*I z7=4MjW(*W(*EzAQQ3e9S1TI+um^?6S3_b2Qm@c z-fEzAme&2;(RV$GqLSse_Tv#`)c1f`(41Wj@$2d zI{1@k$F#(soU_K%CdBD?Ov^-^e#f*-#OZfT%S4=h$Fxku>32-aM4W!dv`pbo&RJu! zNt}Miv`ob5cTCGfoPNi&OvLGTOv^-^e#f*-#OZfT%M||PoHZt!#OZfT%S4?1>OIc; z;_L~(W5u7GbJNr&@s5>q)5M%P;P{-0GY1@>GjZmC<8vm?9B_Qj#F+z*&zU%L!0|Z~ zXAU?%XX4BO$LCC(IpFx5i8BWrpEGghfa7x}&Kz)j&cvAmj?bAmbHMRA6K4)MK4;?0 zf$F_#_Pg?7eSV649`GmU3^?^&_&jh1oS5?y9BVXjeu86-CeBZAtkD$y$6{K+{3 zPUUibf@6&)&QGZP9I|~^hV>ah_Cdm*e9&=I@h9gzJGBpIK{#$|;w%WqO-<~VJ8o*? zEC|OaZ?j#K{#$|;w%WqO--By z;kc=ZvmhKdHE|Y%*%spZbw=EgSr#arR zi3P?6~LuA`X!a>wRPoHydwyovKh9Gf?B-iTxKCe9miY~I9q zBaY3RIB&$UdGROb%tZN(bKZz!^Wsm=nThf<4}WsbOzdzyoHydwyovKh9Gf?B-iTxK zCe9miY~I9qBaY3RIB&##r+WF@2kp7~+lSU;HE|DmtcpEW#U86-k5#e9s@P*y?6E5L zSQUG$ial1v9;;%HRk6pa*ke`fvD)LmITMrjI<%YT9I@vdvF9AI=NvKn<&HC~vr`;r zSZAj=&alo-ahzeDo#HsdiT!fN8P?e;jx(ItFL#__ot@%1!#X>~afWqvisKCH>=eft zPVARE&alo-ao=g4@wZ6YFZZ`d#19`<=eqKqm40Nu+%c1N4vb?a>l_%zOx8Itj+v}; zU>q}9=fF5-vd)2V%w(MdTE}U8%PZNVRbe!eh>5`>pI7OPVARE{&Ql# z-0`0i`{j=RoY*gS{O81ex#K@4_RAgrIk8{v_|J*`a>sv8?3X+Kb7H^T@t+g><&OWH z*e`ed=fr-w<3A_%%N_qYv0v`^&x!qV$A3=jm%Hz@4)?dZ_>&LY^R@9qq955WcPwlC z$vIFk#~mUUvk+_9_^`{j;ho!BpTEbGL6xno%;_RAg1I%@M!V_7Hm%N@%)v0v_3)`|Uc$FffBmphhqV!zydCtd7s=kX^Wwr9lS7f3&{ zU+%cviT!fN^+i) z^K{sI6npPc?7c^^_a4RGdlY-`QS7}(vG*Ru-g^{#?@{c%N3r)F#ol`qd+$-~y+^V4 z9>v~!6thQ;pDz6fJH~iozuYm#6Z_?kF`n2jcZ~7Gez{|eC-%!7V?426?ik~V{c^_` zPwbaF#&}}C+%d)z`{j-?p4cxZ-U`>lez{|eC-%!7V?426?ik~V{c^_`PwbaF#&}}C z+vsWSzY7riU4Yo{0>pk7AojZevEK!V{VqW4cL8F*3lRHVfY|Q>#C{hb z_PYSF-vx;ME-#ozVmpfj1V!zz+(i8jT#9JW``{j<8p4cyU zy!6C=x#OiL_RAeFJ+WWzcq+g?3X)UdSbua@zN9f<&Kx0*e`dy^u&HS@m9D7 z_RAeFJ+WWzcss8?3X+Cdt$%b zvELK><&OQH*e`eN_r!j=W4|Z%%N_eYv0v`k?}`0#_nqFW#u%XyCSylirBs@V*9R$?Yknj?~2&I zD`NYui0!+gy0Ayicb@be?3nzC{c^|TPwbaFCVyhT+%fs_C+DnWY$o>09g{z?U+$Rv ziT!fN*v3-!`96vBeSGdu;@qEV9W`v@5BprF#JNsB?l_dCRT(!4j^;&%F+*2J^j=eH)F`PDm0 z;+3iH!!6dO&*#;e&gb^(Y`5w?J2Ch44tlu7hxED3I@`_XHS27*%2#CA##BVFvW7v^ zpkrY)jeXUmY3!>eO=DlRG#ug(vUfmzeLl4qO=EvcX&UyA$TQqx_r?5{sh7{E7BlZv zey5yIt@Pm*?=GHesu$0-c;1P5-c`QS!!|}-tY=hTpHD4jom2V$b3V1wc{jzoD8|Wf zh^rRsSk=YnQ;U5*wHQsq`&8;X++vZ1eo?)AKDF5AQ;X3w_ykb*;TFFu`dIby`P5>c zPc25%@C^@jA8s+P;@(!hd_J|<=TnQ(G<^3$-G^J8sF>4LFP~36NF9AXwHQr)=W5tAqQ614V)%fSVs?z;V zT+Q;CV1*H$?Z~3czs$A_~4dTzox^6gs{~j7fb>!Jz?OXEg zn9_&yH{W-$V{7*8zWuy=1?-SXJr;ccv%J1lX@l7A^V5mEqhIcb+htM_ehwtEc z_eOouG`y38(KPReZ^wA&N`28Zyo-g=H1CJ+t$5c?ebF?$gNM;H?}u-cLc^%OXc~Mk zs5_eG{qS86zBSYrO;deG&`y4|H~zmg`{9c{HtrdXjmt()Za=>9qvCb9?Ho9cR+>N=b1`kS*) zzUEA9(w0?y$={GpTUPCZeWlZu{38!(aXn)4@|$vC%!tl^=ewBd zTPpdP@ms&Ek{xtU_5Bq3R_XX5R%7NpzdiAHD10wg^0a;rC_8A2>RxNi#Mp1D`|&-$ z@9?)Cd@EY=w0_4b`>fxqd8}~DyXI=Hd(Uqu{5^%vsPa77`u(-+vqr9-5rtdc<5$m- z_xw(w`u4o!Y3&<8|F*0{tLJaw79WY~8U3E$0{FWCoq6ZyduzW7*=Ma+t!)ao_@7kk zpZD~)x9`2qM)caL<#+yVOIj5RqA;7ByFVr?o-^q#)i_R}VYQor?7%eeDzTgFtSCGq!D zzc8*Vz4@O0&-R5T)>g^Wa^Lv3Ezh?~rx(`uot2jFuQWdAdTV~>UN`GIPUq3H!oTI+ zCcdf4&s<{GcbU~bNq@C}!ujut9miZ{);FNe)7tkHn=QVt)&5f9lK;Q-mE|2XcDOe0 zU&&^a#cx$swRiWfGtHyE{8sZE&q$d1^6nO9ZZntmR9WQlZ`D@SzUaHo+OGCa>934U z`YXnOm@!}`W^Bo$KJ{i5HpAI-Ua*2ZRYYkl6~^{w|dr8@21~%CS!~h z+41vk5Sz?lyxV}8+sx&8N_tBk|5ne+7`w{P+-5G%Yo+^nE#`S0bD5aA&0N+4q_^aW z`$WudE1wGPNu_(eAv<1gh?&FKqv!gW+svHJ#C@*ck|*wAF~6<+RSN5DwaTaEJ$-xZ z=Tp{WvdKK>-)gPpJo@In%HRF(_|N#-xE|&;*=L^fZ(HWMs=mzQ%EO%J`tt2C^Em0! z0#$o5uPHzCT-7G!w=KV|`U~Bp{LFdmnPQW<%KgRnx$p7=sm4Re!}_iKmcGu_cq`0! zL#xU@b5%7~-{ouJvCaCe)!QV-gBd3kyUeA z`7P_WT+O$InQz$}lzpz9>!7cxQ#GF#R?Ir*VNNc;W&M_`=S5+j7wo&rChh9yh4y2s z=TUjrtk{Om!!xD)mh~I^)w07_sGfJ3alkb*b{GdRW2$dkLEe%Q0l^OnY;NdbDO!;SLv>=m^qAR1NoWT%%wd^SDWw*fcY)YA@Vb~ znM;2u-Tft|zj)4(pSjJ<`i(v%U40sTE#|j8N6F7TXD;JS=^k%l##@YGvBxv4vmtm+ z!yeCKe#<%l`^&fI1$^I^|sZ$1?B+qe$p zXPz^c`Bv$kZ^g`EQBN`RoVm>Bq-#!&dW!jNw4?Gf&zZ~fLg~zN(T-x~u;?c-^PIUn zk4V=uCHhIsZ(|%NKXaS8Jnxk5=UqQ-$Q%~qOw2rIF3(fa^-PR0B>Vg}#;)=+x0zYL z@w`^LpVwmMu((ge%yVX)nHXc8bUoAkTRrPne)!JjH#Z;O`O@s87yI#vw~PPq!tw1! z_x(=%vtP`SXM4FTUismz@`>A@CBEV6Z|C?Yj z2mN9#@x+a%Py1il*W=Z`l}=b`S@C-3U7HsE;ymJ$7kVf051XX%H<-K=<2NuiumxkA z{b86gBfTx@kzY*yup`D!*cW3z{$=u0X8cV|neiJjWkwl2jxwVR@!2Pjr(Pw!t@5{( zowl;yR^{gEdUAE0xw`%wZKwXC%&NZRPh2x)R_&9kcFWYw_2PQOlu28VPMKA|Fb+xY zR`*wzG2;I1(!cKaE@Q;wq04yiIO&q+@zW)*$5j^_9&cU7i2Ez-XdKcPN{{>*_Ba%K z9Ev>-#U6)Z%8cKLJr2c`>HDi2{q<4bU(}0vqvS95DfP-xhSI}+xv!~Lx!+Z z16#iS%zi#hnN@ws-?(1b5o4!nH_BBy-YVo{&GKd89VOZF8%9% z@6zuc4_(Hf$4Qs5>G9KL%z9jP8CM=}UB-CnFONgjmvqYDIz0}>*zq`*eUE>Y%iqZF zaVYjU>~UPb@2}{uYtEny@^dYeA@0o^Vy?Zi&%B{)pstibe%heA&N4qxuO{AIslRB; zs=nk;{Fb(?+NY`7jd`OX4{4MElb7GX*q{t?T>r##W@}DZ{f~*ZeB{fsh-caAcio>q zFr9e8@$0oGulH6W&%|?n&`w(NLGh()v~BzoM_L zdbgxg226g+fU!dvF!uQelg8g*^70!P8iVO3e{B7e=%U+Q<+u>F=gxm@~?cBU-)mi8CZHnb7x^oi@GK5>23 zCvFGziLa9~OTR1K?Wz2ffld0>?JxV3K{{#ttz3`$QP=7I)%CmI+p6D5Fa1vbRN0~Z zi+%bmboyvZvDz{TzPp7)hPIdh; z{|wbDRrO6(J7A~FwNYl(Zj`HZ%B0TZq0FlNJ5|5*)%~^CVhgt4o#|7oPtVvn&nJHK z{CfvpKXFd+@e?L=&wFt?@m`DlwEOY(U+9wmpp9RoJDKp9tQ)ZMQrpzk6ugc%4>~t#oovPeU zbv>!N&Qx80s_I30sW17vu2-tsCspl6xynPC)YIhRl zb%ZIOI>MAs9bw9+JecySBTV_!5vF|V2$#Nt-FE{eoia*(%7C#$88G(w2b0F%VDeH1 zj19_wxqixk%b0XJeOL0Utw`tEEBo|aDVM%0*Q355KW#%9FykW1IJ0MGLG@`#uiAmW z>yS=cR_#W)N+*rK_3ZqVz7u1EGDxQ_>;772;iWWgsN*KHE|QM^M7oTA{QR+tEB&vN zo)|dwtp&u#jM}yP+KID?*I9UScgpWZh!0)tu5SG6@ViKB<8R`~+s1FiVWSOOeYV~5 zfBuW|N!QqkGRfa1o&1ymV}~+e?DG#MjlaR<hcaO7^A9GCzrp0?H!wCR1I9LG!1P^}-dE-CRCYR* z{Z3VGr@Ee0U1zGUUwzlRo<&G6^(B9Y^e8h`?USl@qg>@7Ev_f^?3~u&H!wD;e$jof z_|!`^4(R8?AG&j7XRib9Q~HPQJhXGq8@(}c)RZZmuU|HY#zEvsi|n_Ac%D491241v zC4Em%^OAV-X&>vH_vk}nY%Kcpb>g+3JiEg`@{`8jVDj=C7#rAvu^sLHQJ69#eW0XA z{%*-1cEs4(@$u8dr%rog=bmjZ7k}^63p#ny9pXLLKelt$D^G|I+-k?pPd@sZ_~5z5 zcCOudM2pQOZ$7Cn$`jKzRr)}czgyYqR`$D9x!vk|y47`dKYe+>%00LHe0SQ#{!R7T zXxX>B>#s4Nc+LYxw!vx#IP!?e6Tj_no&2_H!*12K-Kx#IRbOE2 zIX>T4=jp4ix$nr2T&X<2?fXXjcBrhrs_u23`0da&cd9n*RAqIlx_7F+=&PqfzSgr@nCB{Z|{aQcu>_~H!`bwjbPX4NW{zrPbT6@I0 ztGBjU;OXQ4A?qd95^>!r?8o|Kh$&a=#*)q&hQ6)RmB+u;8nnlAY5hljuDM$CC{Hha zF4?N`x3!&;=e^n?u3;#D#azGEfxUA7eN9-UE04?SQXgMK`|dnLYgFa&^=NEY`G?vK zJ0(w5U&4jlVHoQ{-*qH{!6-hAnZ}9=gsblk_h6Nv8~${FG7bPzH>B{=uYC225Ul17ibQ zFt#ZJW^Sp{J5~NpWv5fwR~h^^(o_aa8&ub+GDr{GLt}=vtm;dC)ji6@ju<;tyQvK9 zkjCF&^70!P8()3oGL$Ef^y@*(17w*Ppn&-W2eKJCI-x9=ck94-3vy5hB; zT%wJC;z(nRi6d_tzv*BzY_wrZ9JbYWq(_;gcVW^gqvWRy7(0{!W1oL8Y5WZ)FJ-{k zz!r>c%7E#+D!o(X4{bPPM`e(oI#uPW4ALX7%7AH`>iX4oq|=sFeaTslJ1;Q?;A=j&#!a8_f0a8<@5%WnjDB zr>gd^KG;``wqnokpKV|9gZt}$*Zo!Z7tH+0eONR1Bk9aD+^3#nKX}GPo0NHyHlb~3 zBe=|AFm1_PR??Z{N`B@(xXhC<^DzJ5GEc%~o`lOh31honpH%CX57v{he*0%!Px72) zZHb=Ze(UjEEqz?lE7qFAc^C)fx2$cnpUgfnc8XT|d+o_{4cNqXVf0kB|NK9CcTin_ ztYQ9LAN~FI!~b*b_K(=Zr(deJD%!LAk9Y@h{~622*~X7`pF3yT{=4>ADu43Q*TjFk zbJ6_W%}2GQ&oy>|oVJ`syxlhQ45e>={cJ<|H<>ikke!!rACvdL@^`W`=Bm+onnlhP zr+*m{c8(CAJk49}k~6I;-etPi+r{tv%>ZT1Jm$5QF#nnCUD8JiBJZ|F3)Jy!)uZ*K!;^(gDqh7uID>gamC4TLf{Wpyda z)wO3vxlUJo@9*XBl5RU<+ZVfBaot~qx88W3{+dfal3w}|F8v6XeuPUu!lfVK(vNWI zN4WGOT>23%{Ro$StkV0c{2jRTBV76sF8v6XeuPUu!lfVK(vNWIN4WGOT>23%{Ro$S zgiAjvzxxp`{Ro$StkMUn{9U;8BV76sF8v5Ea`*E2$$1}F{`Dsgbj{)N6+k(~9p~Z=Rv_N6(mTDE|yw&opG`fbWmVTW|b(+1c|;qw_uE&lA5k*NCul zqcSyG#vF(dpuGrTj_H~MV{i&*# z*!2~=9hBegBfjvom8qBbswv~Bmw1)=JJd`3#t)ku^%6fi_v$(7rR!h*#NK^JxlUJo zoxe-E?TBq(>~h6*e-&PM_OV0#2$z0@OFzP;AK}uEaOp?5^dnsQ5ib1*mwtpxKfT>23%{Ro$SgiAldr61wak8tTn zxb$O{K2YWF!lfVK(vNWINBG!RR?R!Evs?>rG2aULrl&gM8{5Tm^Ov>7)a#Ka*A?%u z-<(6~cg#K0Q2rCsG(&d2yY?IH%RA1i{40%orah=TRo8RiEPrkvdGb2(we5ZF+p`@d zo_USC+U=H|LEOoA=)U86oZf+*Uu-*K+ZVgsM1Eh7*w-oc^^09EvFj^#JBZyr;$3F# z&rvV&4?nhcj(Vxwy_Z=(+UGj)r*7XcN4>;n&Av&FdWk=L`zCtcacxfT!p<+Y9kK0; zU2aSMy1xqVH~&Y5(&5sNaOp?5^dnsQ5ib1*mwtpxKf23%{Ro$SgiAldr61wak8tTnxb$O{-mUVB zOFxoc`VlVu2#-H+hkV6{=TBdKd+z=lzp!h*^N>Gv;J2RJBfs;z3F3Vh{({C#mENuL zi*2VReZB`LJx*Cp@4(J4ww*+}?TcNm*w-WWb&7rcV%JN2ZLhv!w?i+z*FIvmo7n9s zuKR1QukMg9`1X8h+MmtS|CbxK&##aENP4Po-u}0*`&^#s{CUz2SIyhM%`YeB(-)g7 z9lrS3{{2tdF5fbF_B7kxWBY&fy>0S2PtBY*{{7hguZ*9NH$Q8-wAXYoHtyRZpE~#G zq;XR5ffsC(AK&ug-u-gc#Jtpex(acpg*rM^UmTI4qqkzXySh2>kn8e-!$)`V%qT3xepib{F~W^()-Szb}0Y7 zXTR1KJ7b@HtS$Dhz3xwKDfc_SxW0`#%FYg>uV|xQy3Xy#4zy7(@ptC?jm8Go?DP)o z{9@Zlq}#sO<%)ehVqd4&*DrRx#ICQ{?I3phh}~{tx2O0YF&?g1e%HMGjkk9gW6SNg zOFrw8TRV)g{)wN@ryusm4rA=BWp~auPj^#?F}CB#o${7vUf*Gi-Tm9`^VFrMbQoi= z{A!Q&WKb5A3P2$F)tn(+>H&xAn{B?DO@~xz72Y+g*9M&VM_1H!;_F z@E3O#bDew4@_BJ}on35R@r50gUR`Gwo4(F2HhrC4Z2CI8*z|RFvFSFHO%0m1$(PrYP3DBp zo;6*|bv`urgna7Mb!7A2k8PD-cxNryY(KGO{#|zs**t!oEn+TeWOJi^H_zMcGfp&I-IPdNDVvUye7 zC{Mj`2iaWi(hc&xU*1|ar@Xm#o_g_-viZR1PvviH^BLKk^Q5)&sXKmCHcy;p?fl1W z50}k%c3dkTwbY@qxxv+I=A%Azuxzez+$ZzMTlbaC120-Fe|G6(WpmH9*2rJ_ zm(A0^uyj8En(xRabHxSUK3O(5d1a~m$PbQ`P10W+5Fev z4YV=OYhGIUo2R!i&&%fYx1QO?JTIHaZgx%^^So?ce)Z4WnCE5l>t8&-jd@-+4?L&0 zPGhe7)TtM@G0*pGu5hZJ(ad!V9dWvtx$fu>pCx9l+vezV#LRU^taF~2xz5+w!RDRc zy-?}QOTNwyHhrBPZ2CGo*z|RFu<7gUVAJg>o4(EtHr<}G>GqUOx2J5nJ!RAFDVy&1 z#C5toWz+qhxK8(b;yT^$iR*N~C$7`|p14krPuX<8C$7`uQ#L(5Wz*wRHa$LN)8kV% zeILoD$ER%iK9Wt}N3!YrNH%>R$)@ik+4TJ`o4$`^)Aze<`hJ&9-|w>N`&~ADzssiQ zCE4`-E}Nd0WYhDKY3K;uJ%7rk=Ox+n{3)BBKV{SNr)+xulugf{vdKIg z^So?&{*+D9W1g2yIOciTgkzqUO*rOx*@R=BmrXy9WRvum=VjB+BiZ!xNH+aEl1)F4 zWYf-(}O!_g;JU zp6{~h=eulr9U_~4zRRZ9A+qUph-`WtBAZ@^$fnmJvg!4bYGhIq zdc7o@UN6a}*GRHcbnfW2=k6~$7cM#%E;<)3Iu|ZF7cM#%-u%I9+L@l-p}qOxxs<-d zDj#pJxo1xCB?teyOM21iqI5|E#@f_D%=;o6UY! zJLR3HgwBtn=CY=tbL!PZ_aoeqqGw;-cUAZDIBnYW`p! zrnm3(zhNJSetc@hUGhs0KcjJY^ZvW%4}bqO@elUhGr#!KqT;fLM*gkW+%v}*?!u#f zzFUqlEM9llopX%gmh{7aFfqp%7SFcPmN~|-_{b|Z&M}6?W$f{evg{YZWxoh6;|eb0 z3NHJ5aJja^F%NVWoqmkcV}3|0&N^NHp;NZXF>fT&%Y9A$GB3epUV_WK1ebXUF7pyx z=A|mVQ{@+z{WsFf{u^BO-{5jD!)5;sF84BA?q#^#%W%1umG1pF`0v%8rLSeveGQks zhD%?=rLW=A*KnDW;m1$v%O6?i2YT;6?S3odv5Ws$eAm;9=IMWSvUv0H^9=FgdB&kU zYo9P;=(pwFG&ak-X}G+bhH1ACd<>>7?}#-f%e!gXr@Whn?K7Y}<=r&t<=r&=Kk+fB z$AIt0wz^MS?o;k%p5rCG_-y>W#v$WjiB&GqoUmv+eO~2`Q|dWEej0zTdvN;wR~oX< zTv6sCxXe-ih&jY-B-N|7?{d|)Fl#5;ysWAIo^xY8$GV->*KU86>-JH4JvRPc^Fy)8 z^Qe@?`mkIB>&C*gL&-xsl;1Mu|8HZptUpU0?3cPzZfV>9Y`ywlwf}pyTe)VgzvLi>hN*AKLw(_LuQ~lcj1$sJeM_FIzKL?nJw>{&Q{@(>+>)mnZ@TaP zcHGw2S+2k2!M^)Q<(B6=>C7P|e__fkd8+h{8OFNhOs-&0pak(1j zB@gAorJbGrAJ!`Vt=g^R`CI$-cq?O-_AmC~GH1g7lXaS};Xi1ra=&nGZYycAdQ8^$ z!v92zmGMbkJof&>*sjM$SyPe!AECL*7_REB{;J1GJwD4bh3hHnI+%6~9jY;0)^((p zbsb#WDPy=A5C7>nDdV%OpRx1bS?B+EG+_OX^@I1Sz4yrf%^#7|bS?#y^fv@Ih^~FE4uV(2ld~{2H!Ns>0=KlJ? zM|z&(m%aa zm-+i=SZIZ2rS6Bti(Ip0^YeA)6<<8>BF!C}FCd<0(~mThF7NSCC(Y6P^02W=KW+J$ znne>idrselcc16^G|h*;BL4MeucqmyOcq~$j<=AB!7`zPmVj@@;B@mgaRY{t#Ip!nSD zKHB_b;rYZ1ZM1B&)Q{#6@4oBDn(HncBi{Gl#x;AN^sMaXvr_ZmmDh{+{`wltJa3&W z{@!QSYTim)h%cXMe3SROYk+Hb{woxbON?)RGU{5@cedZG)ogb1S{>3a+U}Fh zqi^)uXO<=Un-48Jp!7dI)oH%|#8diKZ-Z0TXij1uhUE&SXTUv zH`i@ux^oA`{JZX@b(@<$ypQ5t?mKy%=KDLX)a5$PUU=>1H!B|_9`ltonhox`O1#dc zoo4DO&xn_vYt`nKS!d85#McK_Xf8Q*Uh%JQU$WWhdy9(yUrrMld3z+Y0-OLhFh98aXEm*QT}u-G#x>eZp#^$vSEMZLr~z4}gy zdWlCZ@FD7z$aDVJW~5%?{U**%y~G2@kELGX&pfd(^%AeX&{EV(yw}tfsF!&A&#p?n z#C3nobzWa{+sls-tML=%9*nrCefK@ON^|nKk;F*t`}niVH}}pti}-~7mu!|kXnN~bz7vkRbeQLKS)5QmFPOR9z zBd&Nl?Q-NIUHJ2RzL2`7A0a+@?bp*W2V5e4euk0EE#gf#nU;FBu-IsiF%1Y_x=7R>LsrG ztM11ImRY@NZuyP+^x3o5Z0?x*TjIUOjBh@D_(#R_^sUo;e3z|=>G_GXS6-*t;17Ec zxAYSmytH<6!|O|R;S0aDW^>C5M~g3=+TWb_>jCl2`}Z|dPx!OAe~yng3yhzJn53V0 z?#<ZHrox%Cq8$-g_|+oSXg}DSH?DL?%LyjJ$m-$_Pu&}(u*@TU+&JP zJUcw{q2{oYMvLb@as=a3Wi2r4Yboj_-hb}rQ`AfR^(~%CQ7`dQFFcW=UaHFsQ=dpt zFV*p?1D{G!uMXGw;%A>vQ7`ddKmS^adWpB~j-X!RXBM26dL{CwaWhdb@k2MyPQAp3 zwqvQ6c+)Evre5NUCND|7#Lun10`(H#xar5Km-zChmuU9+<*a-c-R?Nc^37#uj}hN@ z$;!>-kuMY9r(N@+)#BWR+r(Etl$tf?`-S+fh1O^uKlniLT3fE!%(~cE@%NTlwt0Ki zsht;}`EmQTAFkM(`pbJeSMGXzJL$Alnx#j!on_}guKn`Ht2HC{I;HcMtBz~8dA`$( zndcjw>tFv-`;nDbZx)}jVdtbpPHG?f*Y%pEHtxkiKKIBqnvblow&sm9zBR77XWTGR?0?v<;`xqPw3*}4FN)WnZ{B9Z>G$sO-7`0@z1Yk1*v!*3E8Wxk?Wr@olFnFq zyz-nd<6qJz4_`Xs^BjK0f+ydVHoLSpM_sLuRkOEXh1@vP_1L%mvTK05cJ)Jy4)PFRk5iP!z;IO-+7ceyp1 zsF!&A<<@JWUgDqpdE+MPCEjR}&6}u~uI=K1Et{y9_?{n3Xrf-K%kC#nXrf-K;~aPV zANJldI;y4X+?)(voCOHcQ-}D`&aAYg( zdHHsaQHm+OcI@Q*&Ub`jLF?E&&SztM6(wyi2`>L`fMU|{D!X|3^OJ6hht0YQ{^8wQ z(LQj1;4#~56;I|(5uE4QUQyG3zTlEmn<$!p3=>>sXibIkFNq({E2jwh_?sy2R;7sI z-MYzwgNwg*ygt)g@b-qc9I20jlRunxq<#tR{^^h-^-Jj1Fl3J-^-FNdwq1_YFVUBW zM|U|=zeFGBY}?~V{c_;?Zya&hk@_WA5q8Fr`sK*W!w=kYq<#q=ap1Kh^-J)H&?3BF zg6G~V$NMF?*|D0uUxI62ZNmE{*on30{Sy44p&jp+;5qAiE2v+BYYuc$lss5hoC6!e z+!afGzKMP9=fUUy;&@;d|L*!OyEy|D ziZ@g9I1jJut+4U>U2u3GcZL4R55YsrI4MfqtH-~&u*=n=P|PxP6MWyft76#}SHa!8 zw^c0NJ47(s-dJ(Zdz9dz)oUqY+DZJzSV5s0Ce`tdFRrLiTKcUj@Qb4m&n@{gyE z)GxvBXWVq8ehD3JUOewe{SrLR=cFU`OR#;JF?{#Qrpmtg0o#d*I3zyDf+_e=2XkXpQ7g3r}! z!uuuIKBX=1m*8vWuDoA@r+!cH`8tm2YD#-Hu@^X3JIm_#Tv%F3?%j<`; zyskLQ>y5L#4mr!~le4^TIm_#rv%JnZ%j=)Bye~M*`-QW-k2uTwi?h7%ILrHyv%F6^ z%lntJystUS`<=6V4se#w2hQ@j!C5{}ILqe@XZif$ET2o9<@1WOe2#IJ&o|EUxyM;P z4>|ucU%&0*QQEpe9D7-xCyahBI4XL+r1 zme(+6d2Mr+*F0x=Y&pw>NSNILmvAv%J?h%X^Tsyf-<^dzQ1jmpRLOoU^?5Im>4P zXZft)ET18q<+FveeCBYL&mzw98O2#XyEw~d8fW>e<1C+noD0sE{QSaw3;+0h{{Qv) z$aBG;H~)F||L=PCm*?*Pjqk4D9p;}q=YRg4v*7donUQ@I?!^{~yRnz9kHRVWzz%-z z&3e#VF`?UCaeof;>!s*a+g04F-P%F1xuRb1>voQc#?LkhHZHVPj6HHr@W0D1v3Nrf zF4KYQvvzAq#k3wD1h*VtUQxDgDRFHoT95i=A%A`zT~OuWrHnD7c1WBi={Bs!g?d9|aeDe*eec@}KW- zDd<1{C*JX&AMYr*-%TYeavy0P_mOTkmEk_pJnkdSNGQR5q&)HB_59lMlVi<*%Jy8(EA75I zIt6^O=X$0;`tF#!)>HU$?Ys*qPVO`aU#@LzVMXsTn}jd7;5q#7IzJ1_?6$C!Vr`Y% z!sk5BP(g9`>T}_9e$b$rA}`~!@Hww&Ra-HmaS=y8o?$H;C}vJ8>Bz@ZVQQjS)v%l+ zAJ2kz=YL`^3ff1%eLWR4hW306J2ZfT#&9PeLzbpc&=~IIV|cxXqk_gz%=Ozl_IwP* zT)$gm$H!32bwT_1zhQGfZ0O9#P^`&gmbQEh#hUC_wFMtTu_mKSH|Arwi;v;@GWGZv z?&4$kGN~pX!(Ds~3$FA3i9M40>(#b+zD&;Y`s6IH0nYN=ahAuQv#by2g1?oS+h4g3 z=YRL!)K^^|xdyThSa7<+8?H1JG-@SKuy9LKzX5MZ=9sXT$B3V9fx8RzQ znYSy~;r#F3kGx%Z{S;*0RzV&9UHhwKxh(czU43*eoP)#L^?&1G#hQq6UPtCa_0w6+ z1P45>YR2x<%6#5ZGl?~A+y_(ET5;GbiPbdr#>xmQ#w8}P^No6A*bpnWzfWTOlX~HH zGb_eglG*iBJ@NFm1?{4ju``wIAPgHF9O?Ql1w;W+%TIT=A z8EbuVar>%{4YunCyWKhX;%H#2DmuY)XbuKuC9vNw_Cb?pR($EAVy3-)puR^sgsRv= zdlx8Y=fdx=Y*wRgR}{N!#sZciC;$Q<0s=u&q zHd79=!BCR3#xa{kMB1Qs84J`?vYF+K4LTIEU}jo2t2m(xs=YMhU(M;QW@=XdayOi} znBkkLVmU)>F@J#>13Rl&=cjh4?QF)=zcl&dU^7v}wm-IkAI)9lSvAuJcg5ZlX0fj1 z^;2*y^_v*Q0=B#0+u~&W<)vl`x4qD6MgoeT&P+?KTxrL8QwT~H6F!2so1Ki-Z=6&9_7oZ z*(7^!Xuie6qn?^wtLlw~RTE&-LCv~;^1_$)3Fz8W&72;RZv7K5d{ZO~>E?#dACho; zXcYUA=Yk=j$#8dxVyQ=55I#B?LEWNQ*Sjuw+&dX{nn$tcMO^W@Z8Ba|i(;N_TrsG2 zG6IT6vCLtvm{lejeP2YfojO;{`Ah zlvJm^Lpnz2HSE%F9vELU9Y4=$*!PtlsQM-iBbsa3U++9n_(B@K%+|7P{XNm1CF!o1OTbt?R*T)WO2w|1u@ zj_QBB=ZzP~Q_+^>^lUHypDzA=O%{I^!_eFfjml@@5b>y+u1G4Ki4jj@m^IB6*9%ek z!x(mbq$}Ltno#9V4Ew9GD_Yz(q1n|K_Ta4x+Mh5%c{YZvKjnhOJ51PrG=|;W?1ER> zCVc-RhLth7V6WPQvD;$U!FU&h`I|6neGL1maY5iX6BdO<(wgrNWzl58yE+UI?7daV z!jgTl*&_i3_ejAttW-v_H9g(&zECo18zWhTJU3kbmL$f!{UK+kGZB3@@EfE z6YKL*+reUe7F?^|_hT5>r+1}HaOQe)E;w#$szk9{7k!YpgZ2*X3+ovl^h{4iyVsGd z%6=bYMkQm@rAVe(>4R}ol2LbGBwH8fgH~S2_^>vTjU4F%y`b@G^!Jt#X284VIKW{;A&lpKav zg%h!Ni;^in4@K|$2~ez2vTt{W!ud!7isdR<*8@YbVO;`xo0aTM#!xg{nt(FdO4efT zQ1pySz!WNfhM~~RPJlPnk1RD5VPg`oisaay^hLm+1QZ;HdkHaOOl(J*P|{r|^y#xV z6$N$U^CHjDtan-#TiO?Pv`5On(y|#Xd~ufcRELLJcF@Ha&4?>s)w0r)d@+^wU5{g0 z_Abm9f6;zixy)STFX}C`eFykd^=9duIBin{E;;5>#1c1 zsx$Cp8p4aw-i)EPZl>YdP7SN&?Tfr0Y1rzoVJ^jdfi~$_-d)4St{np3Vd=PDNy8K) zhG1WKI_7>-vohs|ph{{w`q6o1JvSKUmFaN1t7aur2jlwIbS%B0W>HfIL;rg^n$Wpd z*nKe8vGl*Kw}NY|^1T=~C2#e;rG@q&yYx3yFRQw#O6KmDsdMavtH?pZZ zz;m!sFu$vC&h|A*_WG+4oBSny|H+638i_BzF`}PY;`5J;Fzk@H^;IKgAD6i8Q6nZ@ zm)Lom5hb5W{4vvrBJU+Wt~8?BSBb~?N$t*h3KXSw?|w0|NYbtJ93y7EGqU#az+;sW zm7W+`|75^7+lbcJjBH&RuxmTXIc8*?bAYI0Ms(Y5WR?v;lWRs)&Ni}byMb|!jj&T2 zSg||l7Q@{MLg6>*>Z?|CI-_~s(`*=+-Jeda1yv(dnu)7_-{X$ID$q9k*Q(jd;g2VabM>tkT)r9ANI zr4erS26l6*2kP82qGu}ut7i5<_9Y{})iN-zlO7mH{jFBkz?Q%Az>{4@%q?VKnMFKt zVGWJLCq45h?THE|BZ`roYEY8O9J@B=o5#`7ZI_>F?dF730S4Pr#*ozbt9G`;YcA%y-hA(fV z;P>JZ`@BnmhUD<|HmjTw$)peGgce3LeI#+AK1Pfo9eDZ2(MGtF4xCp88*%Kd#NNq9 zSgF6fywzGGf+|bAaK8~JnoGR>0xwXdnab0uC$Yk=!np|(4?o)#L< zfW7XR_ACXBD;e05S?(zJFy(J`4zx9}I(j!eJeq>B&IUHQtQ-1lNI~-{2Bu1K#hio` z3|neo73p5rdRz)7oiVU}b6ilOSqhFv$FrPP&KMD}43h&B*o?bQm=v)TOB9RQ^tyc! zOE#|HxUIjIBKml}x&fTG7w>`pJLcoS%U^wx_LQU60Nn?PN6j%H_NBybgAJ&7PvQd( z285rJSlQHoo_i&BsA#~gRTBIC(4)v=i8Ej8F)UExR*&_tj+EH>z8>p(N?hZC9=)1L zy!fdejmk)z_+F2)Z=}AQC@Se$S)~Bi^B|SSzfoWgm0QXhS=*Zm*i(IV3nQy^T!EP+ zXL}zb+q+YNZY1AttdZ?op}=8k_j#z1r5F|Pd7{U`WFvd2SK!1OJyKUwyD!p@5a6HuxAU{$_;Z%~*l)R(Sqo2~yLk@Q#%Y<&rU|HbF9(gt zZcZ9K5iPIg;AmGZEB0d|ChpI{x8hpXIerpU898WrUPCG6lkxkE9PG4cSlfWf(6-A# zuX!3)W%p!Ux@SeFej4`r$z+^fV#TXE8aDCEWL)oU#h>rhqFnvdf-4u)qW-)k7S!0I z7IGZ>SkP^~TF9UJ&WugV)uP?O>&*Cbg<9y-EWixEP4pZ@damwm#)t!Iq5p&iX8a_Z z%lkE=G(9i>P_r67<6&RajAqR>?0(KTv@d5y$N&v=9y8vik5YE9)s{A7F6%0WkYL?L9~wrLuP2%{ZeBPlw(0y zyi|Vts|7RGN%e30Skdti-FZk(og6DFU7))S$$#<2ilpmW(QYC89E8*J1=pw3{2W|3 zLo!LvRXI6$`iEBN|Mt%u-1U~`YiW}l{Nbo&JNzbKY>OPcY^r6UmnPt1qa3s@P34Xg z(W*)gdOp*z=}RW!;1_C_o_R0ap?SP&g?hb)SsG8m$1PSYOVqF@-jlFeWkr+u8rEyp zBwQM5MX8Y*c5MD6d}(S$RVS(3`oe;bouv8;c3R-pM3Pf3&Vt}tlKc-tEI40PYIjW= zdakdg5&DD`w;+(#0M}FV&4Pf;@bqRkmEMqisQ4i zLjIUUEBxnbMY}71x8i`mR_Jr-wiSQT8sK^!`)S3lu~bg_r&Q0up;Jn>wCN<+49YCgNU4E8^NKnb*+?sQcam zMGYl;-eUqx&fZpD0hUVGneB+_fqn!K!JDa}VB zU`h_od{;7O$B{U`naUff*u2>zvGqp|R`ph~D|sW~-Y*w=AvVWirqDh zLIlgj=mZtp-*Gf5yvW6tY!!<-H5$FDF2|v@Dpodp44SlGj)=|VXRA0CQ|y;x`c@Td zZXJt7J(i>3nO2bhIp6;C&$oi}SZ~`6SP$uPKyPJv)m_HGE-&|PQtC;T}6EU<-E)G;wv63Gr z!sQCtyH`p!sMaK;Ez7}yTS|7I(IkY?**h}Jz}kHEMzv5Y_D9kkd-VWxTWCf1;Rg1^ z*9X0Wthm+Qz%(D}`D+}VjX(8lhiV|q4p!LzrDtVI48nzyR-8=NvrRJxA?Jt%zO(c! zW!oUUS!jVX^eph+AUvfrszfzCd-8S=KHf0n#tWS&H>=Eeby6ql>ut;*ecK!Ni<3_el=!1&ch*_-@dLF!yMZPwj&_8rn7OG#=iGKZ-n}xL> zbu8W88-ud4;Lt$NW@dW9Wn~r;-1O|&4^Nccn}sn!dX_QU6AvC_!EU9V^`|@errOys zU(qv*hJ0>Avr(7srMr82U}>Q8Ab!0CL(=y)Hr zNU@N=PtR^#^TDnl3sP6;+3van(QlvySsFd71#%px{{odbgvj+S(1PMO*VcnC$$@YI2+T->xDi;%-I-Q zRWI}$8Iz6qG#6Zdm0vb|I_SlGDaU6cq>r9`)_ddk(NsP{&uTX#AK=7nG?=ev`~L94 z=egOayjagZP4U76bv9f!=-GnWUO2uY8y9Fzrd;tv-;>!mP5!`sYdn$mH5*=~4eUX@ zCqmnqF{i144UhB0)Ny9aaFEK6EipsuNzVvWztk~`5sWejIZ;0-MnKOLT)w4)1zTqr zM7y7dTTq&q>thpXLFGvXp=bLH3%(6A2>lCfw!oXtYVJ>SqqCat_puKB#kpN@-xcJ4 z_TYd19xOPIUpJDCF6@C;bZ#GCu3~%ldccRy?KX67=PmF=&bM47N2!>qju*Ng&&AG3 zD%N|27lIOUan41>CRg^xqJg;>+*ZYwkMzdG>bWReUd3u8dL!Um4w9ZLnRSCV-Y4Wh zeL~4L?es=3j~pbdRkEsUys^Gy4qOdNR#xSW)B{!w@K>?{UfviSV+95)S@A;NXyR%` zrh}4gHPKqFY{iGBO6K0q3#qqgJy)VSt3Bbho$g(Qm26&pPc&R=!R7aHY;>FlwuaN) ziSAmvAN7aE&q8<5IA)0IkK@xV05M#bt~+B%MXIw?$(Da|M#c#%W~Go{ zx0MUV8mzb*sAL;vxS+@&D_Rd%vbW3yYwKCjw1<+VH+6;jnFY(5DOts3u85|y^ixG8 zyI;c%_p|AI{u##>XSv~q(t@(@;+VFxJJROU9g@c6lEoe0XIU`T94*eSz(+b9UKlNG zP|6D(97aY9+ho13qdRW2uvxcG=uo3@w6JBxSLmQPwMf`F`}sPYH7ydhuavD0!~GTs zn>gg97VfsVxwc5yK9_@PG%O!2 zZ0P558gy`s7B;ldC=L83M++PJZoLLeHBz}-2`yq)O7+K#(!zCbw2-rOy%udwM+^Bg zziYAPQnY9{ysr*RFGdS}){^t`)d`YGHnimi9g6)PE%f(4t3%WN(tJ&7ufx~w(ZU9G z>`dhiqlInCX{&>8v1nnl-qzD$(!)iOVn?;=YT74UOrbMcJNGd85x7JZUS{zq?-p+xn86nF$(9t}4lQ9jC#b z3R1gox@s`9;v%8X&Waj3BNhog*=sd|XfC)7eR@@mA)OY9`Fiq~8sSchgbiwVjLJtX z61HjODK(k|E)q6t)J-+2B`*@T?9c}_`fpk!Y+R=r8eE|@$!%z^LWA=!773g9W10p7 z%SH_Jcbr|-dn^Y~+GsIZ}0OFXg$g$f(GMIVomHlf0XmYNZdPQ^oo4K>=wBj`kku%TDK zlRq{oMA*>#dx%Gb2pf8MkpT@Fga{jYzPADGZw3n+I*k0Nbuxp64YlsnqvhCOVMD9T z*CVA-u&|*&I_t6gUXZY%J6`LsXibo?p|M+aa1IUn3EDcD@W0Hni4LEs}2s3LE=kh4Roj-9mIZCal@EmIxOoI z#NNlbVcjb&MwSa=6N|g!&K)goJq~1#XdEV7(PG%GKsM~OJ08+lS<8mAr=R?=+&vz@ z9Svh4E9c=-QMJX)utyH2o>Uv0b&5#@qKyM^oOu&P3^(C73GEj~0RnWX2ibz1z@ zFIebbL90dW;9$|Ok_)tO%L`_sUH$N2jusP2hOl-SvvDOziwa{xnC{ywm=d&DwJU^; znK=u=+q4){Ka`bwF%$hBYtcC>luc62#DbPOG`k(j!h6g_>p42~?GeT@E6zkGro;Zk zFxIZnOf;)PKKW}>dGItnUe*p5^$kpqK(}xq=TKz>?5Bqd`Ke z6J3{wu#S`FBI|%2uLDBZ?%8v(B|(pGPEz@Rk$U9OTIKbtw9sR4;SeDw?Tro_o(Bv0 zLHl%=d@oqE+hmyzyYB}JeIC!%VeRW+q34T1I$Wf=;QH64^_an+Hm?$4JS&yPq!bJV_ zR6V9ghY2~={?eoTvM?dPJDqjIvcg2Wy4D61$_x|w9P%=tQc{@E^N(2uJO~RD`X|wu znVb{MmYfN|(m(WQH9DA;KM;Ty0eU3X2xeze0??zS9!t&!vF|&* zWavI+dm!Apv>!7y=v6HDY@O_OA8}CwiuNm0*N{76b!L;UQz-q6@E5Bg&?&@^> zjMYQ6J(w*!Hy!8C(jNaA%$%Q0M@L#?s(v9XpxzABqVXB23}Kh2&%oME288VoVR5Hs zpv7AQCVvWHcRXj}PTP3wZ5GP*-uM+N_Uv%gZ#uDrr?=YkpDT~{`1c_eut6gu_5i{cQxl=9ogQrswW6N>P61i4~JJD@Fa?$>e89BOe0EiJ`bB(<+7h z4R0-Qj8TeqO=~UiiB$@H{N|DmlYAFk&v(5nxSORE`me4}d9Zm((JyN$3mVfiKDUXB zC>FV{F!>h9CI(Xct5|!LutAPZEjT?=C2Ug-Hw#wlRKjN638mO2Bi{nq#Hx7~7+$D^ zjXPA>3R69`u!$!ISaHKyEo|ams}&_?N#)hQTJcV!7WLcu3Fv3m(y2aQ%0jvfw~vm6)$>cU@XDgge zsf3L?Hrk54&&WSUHgPribMBN-3!AuXpB2~Zt3~HXq!#t<+UH;+yw=$27T3 zlw+FQCg#U9$tKD%O>PtAm?pQ0a!ixk#Qc~h*~I*qCfP(erpaxh9Mj}BF+ZkBHZeb@ zNj6cAX>yw=$27T3lw+FQCdx5QZWB{~#WcB1%#Uf3O_XDr+$PE~O>PtOW13_W<(MY7 ziE>Pn+eA60$!($>)8sZWKc-1GF+ZkBHZeb@Nj6cAX>yyGAJZh8$YYuX&$NR4&-peB z|LNzOh-vz=`|=)lP+ra*ts;EYOFG`YB(v=rSK?(QA-CIb7(!W~v64)5Ar-O896{{%$y1*mpc;xoc3pdjxB) z9f!(;HJFtY!CK!Kic721l{=d82W$oDO}mrSenLbx7PN)sH!(qx{b(A*X30 zJ^DV667t{8(__T@DADeWJ$iI}7bWyj6f)rG<0zr$oUR5$T!<3-`;Rc-p^r3QpX2pp zFGxP+$?Qwg<8AXOkw4>L(4&1>DyKXjZKNKt*CIupPb+$EZIu-%@_Y`tl5b~Xq{#Cb z(L|4KEh9yqPlXRU^nVc{@_ZZ*>QFN;Lge|3PSl};PAV@oN{0`VBSihnEp$k6jSzC? zyw&1!*9akh#C|O{wv7<&R!q^Nbo&UQ&#eG0-rGe8J)aNOqK-F}lm3l*YH`#rLd;iF z8!aj=ix7D-!^sc4=}?5opSj&d3w)z;%JWI+Lq5{(ks{yb?Qkvp10qEp&X8a&BGyNW z{G7d+T1d1`pIhI^*V-;h2C*gTiMSa@QZ z`IMT71Q&X?rDwXPb0^?XWgQMZ4P@62kH=N=t3UWFknO899uLSr{AhO|`)$BDtlLU^ zWM?2dp&g4A8?^ZJM{%r*McGOdzAMyDS zh*+q{;~l}Q=7|v)a9$5%i4f+0Zv--08F0ZTgay~3+@4?qcBX`|bCmPrd64`_mqXap zYa_9X{7&<$gtBQ9M+x7QL!VGK`{yW>4~@qX@<%Dxj7A-LUPxX@&xTXR;0ue#eSIi< zSad8p9*;+f#q@kZc|IAZ;{SH0{d2zkcb#tq=kc&6l+_9vhf9CPqu2aUcB0>S?B5uV zY6C-=UC9Y3r;A7bCglIwHUTGx#l!1i2z%)@5r*3FsI)4Cg;H+MJ@R2LogKoQD^EhX zW#pG@Pkus=NvJr`0JkT>tfc=W^eJONu|I=Z!{AAXrX1b(3)F1sCMWbQWx~lwiRa8V zp;oHI%9AD(Jt*5#jn9HfsRi7{aPN>AZ-6q?9m6JZ@Z%fSe^!+L^*S}LS zgZM4)mt0=Ul96BkXRnNWIq&Y#J9oe2A4p8kZ}**BdcHneDyBo$^T@rleEp-2rsel5 zm)^mV`^(Gaap3jk@!@jhapUsk@#O8w&co*tR($s)|Z&~ zOD_MpCnLZ9i{OlWIi2h>^5q}+M&tRb-Jm1s`TAVXOwZS|+rspG{r&vX^ZQkAT6%te zdAU3eyuLg>T#h_$T)sS>yj^*mxjypvb3NsG;rbghmEs+N^KG@L882~ty%s%w@sXEw zXCVIue@CF0582|q5*J^mL&w(=H!7w__l_!2=f(g%Jc1=Ivse$G6A~XfsK@nIYEfs| z6S|kGC7%6Lk9$ug-bgw8hdrfte*1hRn?<_uJPoefo=Z|b(u8AroCu|yjmaLkO?RzP zJyqgPzzmlzi+)B`cam`B&X_ zFeNEj6Ms*vsHUTQWy;6sM)_KAv}mALvT+wZ@cMujyU9oNWGKBClc>d$WF_miuRpxU zX#du)5E|R4L++T`N{hM{%GV8|SW*Km<}FvUEA8lA61wX~P|nPKc`%gI9Kcr(?DHa#nQ^U;;yp>=6)*Hb1A(CT1^A@a21=@ z!UZ-D)cCeb#j5=7jCqWhd^n?rI%Akgjl1MSs9(kz4>f9hAU~4RhJLsns)ox0HB%4j zht+{<)aS>@|s%5=9IbjXuc-YZ-Td{=`4lUH+&~+_KYvP2Tc^V{t)UwabouK=u!N@X{ zOG)*^yVKpNx{jswa>50QH#yg#Jj|g^$k?vM=$bm_^P3ayeAFVbypA1O>V!QsNA}<8 zy?*8d?|I})f1qWro;cyu8j8yw)v`}@`{C*x9Tu;ocMN^{p>}nOCoa&k5vG1f@zLXR zH!ZV#>xXMvJsMEIK8|qHsCQCkRMR|?y^qh5C z;(cZfP8lUO4$xr!5Q)E((%>V#C&J}?JfTMRT4~?)%~qq3x5RB?)HwM}+M5e$-tYa| zvnyyl)NL)5M<%Gz^Vc4qwN;IeLDGI7^H_~d9V9;AMuR2fi{ouQ52T!sKO~<0mj+GN zNNq)4(ZikI_vCdP*6Fczki_CV_$0CWLLH2irEz%FSogQ_ zsWDfovzy|Hb{D0#Cbp;Nh5yqz!`uB&IRpRO=TzNAn)l@0T3of4*k`^L*&Y)2>`1v` zGbLX5T!Z_`5?9|uIbh^B=5ui*f_w-?r8U-J2%Q7{B#!G&z5=bpdzxyn;jF~7>ud0~ zt~9^Ay!Zr(dHwwsiMgDPHznrsL+M>1-WG4ShC*Vl4;vvd*E5#BIl$|1{V&dwnD_4#^QoXBtROaJLZ_4)n!eY8Hm zzr0)?2VP$uA1+58H!fcuPu{LP&RidP{JEa;ym0;ZUX&-9`u030A|2-o1Si>45W%)p%1qmFb)v5PMRE7kyIM z=MoM$9j(HT;8ZqrpFPI(QsL&#RCYGl9ve!i(4ue}+tI-u@fVdC?v=*I-La$hNR;@I znZ}wewZqR;CDPudv621lu+*T$7WZ^Er>GtF5O2y#XT$%n#pyI9&OAzI%XGGwuu%!L z$Y2SRZ0Rgj;`X=Ua_m;L)=ZpjT-q&K+i&QrMnFB7+J?HnWscd3l zM<_D1$XuAp)Ri1@(~t5V2c@#q+Kw3LK)SU}Wxv&P#QZ{(LsBM{eX8Y%4*N7H^2W$& zRCL7LC=CYC8Y}YCf%5XmE?hCPt1lc-ne0@-^;sx3P3*_Lv~FD=O1!BinPoUU+!*Us-eCb0iB5ADnUT#5m2Jej$M^cW8%Ug+q+iNkurAgFry`+JUhs1uN zwEo9QoKu_bEi}Je&Iz)2@xBsY9H>TTJBe4lRiS7ZiL0imF#d!je_elCS1}TwEU7}z zP7*ITt;E=KlFp8+lxRkC#N|6DDKV>}#7=rDr+MM!6H=70^N`qMixRETT1A% zB|cC`g)<{1_L@LzwW-8gx2SO7v$U6W71bDcOX61kYIOJ_@sAV@5*tbNchGtGhUSsC z+uKo#qDc~GM^e7%HHmBO)M8P4NuQ472P-&7b0$jVWmaf0)kfl}K3e#`m3}+Em=@Jm zNNh{%zvEPiXD`v9QgexCP5-~1KU|;xr}OHcwb2>>&b471AzInt^zV41{Z zm++a+0X{DoMJd1fro^59q_e$>H17|RRp?LWIj=)@31t!_HhZX0_kzUN>{S@sKw9&3 zkAQiK#JqgV8i{%RfEN;TIX7BM`-sbLGg@Na?!h>TxjwUVB<6Z{-68R8(m#$#%=;ym zzax7m*Do=F*4{5U2P~R=`JHZR^4q0*M7};X7213~_l(fy>reNE{C-`UN6&h{`pe7Z zap3jk@!@jhapUsk@#O8wg2M(64gRXX0y#xt?pvT7*olKYg1_Fz=UK z&ZcGM*Uv4Hl`ki4Rc5~YnL{)4+fA#OnXk{t^YlHIUwY12Wy;sTMS>~6U!F=+et&tn zJPy3RJU(2GJZ@aRJf6H=d7QaE^7wN-<$2-y7o0E7MZ@jE`&jV%Z@pfan7Owd@@kne zZl{Ue+-`@4dD)0aF|naF>@jpiHqPoy3@-L4-XI&BRVEfN(H>48vi>W-9ar#sdIiU1 zzn=QO(jJ2Yvk;MOVl9u@qekN_7?_E*yKIjp7c$ZOhKYq74$Nd5_uFG_wM-man9161ut$SeCgg0+WG9!|BmI;KHy>uQZz1+D zZZqM2{VY~_ggwTaO=vwNi%srkk6TG5T+Ga3y?@%lMr}gg+bmZ5cRQF>CT#7O&HU!s zQB2T;^2yoEr-dC#(V9uRp3Nqow?)cP6Z$tcvo;HDG4GuT-N%?&!#1`swaCP@Kw;Y=4)r1v6QMVZ;716|N#pc$n{nAyNXUC=z(jOVlg{eryt&2v%ux-Vz&OM3$FXpdxb|9Go8O1wzaSzC|$a<75)-~BR-NJ=KkF{ z%p4`%%?`ec!NWSz{i<~NSWG`Fv3;LdiXBULk7`M=aBnQFnf2dev45S!v5|3D-a=Y4 zG1Zl*(gbAM2NT@CUZ zUy8%@{z}&2h%>!g7KeL_y?;3Y_PNF>aaZ8xyM|Z?uh{dMMCKi3u22X#+V(?rOv$%Ib zk#n&~=$^?!4K}!L8;6TeGMM&p7ldqyMW0O>tQGN;rLlOv$;94M{kBEoP`Y6z+e>n8 z*~Q^0J$JvPI<}W%!NM|`h2%tq#^I0NI#&Bu58Rxi#F~;B>|lZoTx!Q+UVJKZKF}RA zqhoQp&QdlF4medV4p+9vGn-~T(d$+mqNgllB_BAze`Op7S(Dh>5<)1k;?_zt^!MdwQcamFJ8|U^{*zIkcW9^jplzO##MJ`RDSJ&J>V%Q7~Ud>t)6#lfaQGF#-?1E(Ly;b9s2F6fcosC*|54O=8L z!@wRW`7#bed>6Au{`8$Xn%|=81omFv6Bnp{(;ds${ko3W@{Pu)O){%CqzAUXjziB% zdUobmZ#1|~?Y2#3Lw$Ro%G)@Ek66rd0)SI5;?PT*!0h9D!s$ue|EJ#^EBHOPfAtNt zYwdMn&EI>Kj3qVWS$1YW966s1``db!``j6oZzp3ueV-xng$wpPOh$L6V>LFrBIju` zdPnKlQ&%@Uc%F=HqjYRbo*O#9Oh#c^8;kASVM8)E+2~l}a(CMSm*XtoXdA<$LSK%z@1#y=1f;h{0L7e5h zAkK1L5NA0rh_jp*B$xBNAh|xz3*s#21#y=1f;h{0L7e5hAkJJ*p8vyH&I{r!=LK<= z^MW|bc|n}zx#KM71#y=1f;h{0L7e5hAkK1L5NA0rNG|7jL2`Yb7sOf43*s#21#y=1 zf;e-1dvccJo}A^lCuceC$yttja+c$s zoaMNuT+ZX3a(y26ZR&T`z7vmE#2EXO@LbNzXonltZL!I*VHmgA)V#IL10 zl{}B!e#!I5S)NDE@;q{u=TR>I--urqoJT%id`{*0;w(S&mI`mSYo~<=6ygIW{4e^Vo!3pT{OR%drX0a%_UL9Gl=Q z$0j(-u?fyxe;!NX%==X^u2hiaSO$;L$T5z8VoZ`>MV?2#r{sC$EYBlnc^>8R|BV<^ z!FlBK#phI>FV6COah79(oaLAxXE`RwS&j*EmScjP<(MF6+Up{wCYSS=pj@BF1Ubtw zLC$hakh2^U`S4u&ZTJt(-}LO6A=Ozk$oRLu z@N&K$c)9$&`Zj6w{~Gk&ey#)Of^}?u_4n~QBi=+wzkOCR6(z<F3@UfCvF8^1)g@ST6kza!UwrFx1 zo;=bD&ZGY7k|jP*cHjjc4ax7WjUN>IhnMq@(Yu6x zwIr_fOowY9=>KI%&VhRLeT+{MGj}aU)tBmg4y83YNn+1!YRo?-@!+2-dQV?!%W;&7 zzTq!%Cgs44r(9?*bM{0f8cdXQ-cSBpcX~gXmtTDthZ?_pIA5>FA@Pi4XJ>qj!-X{I zjyk7{5;nu6aT}JPgijIanIfhv<>4%mctN%b4&~|lnI!X-ry7CuolMS^>Dz9c`P^|X z=+jPUDBXW%li$zfsl?~VM>l!BG6`&Aiue2E3~JM-o=pk9{GXi(>QY-J{mNbHdbN<<&qUXBJtZIYLpomC+gfAuEKEo zzBI4j<(Lw$Hb}X(-9{?WJWR@^^eL|t>w(wd>mg{cRDN)L0+N?X^>oXw9?afb3pIk)pk#mqjEJ^|;AfAjlsA0QtG?%%t6SL$OMjS0hUO1xrs z26}&!xW(IaT(+0Sr+TM!1pOMTjlpzgR+Pr@*11$vGfQ02ITd%@q&P^G(?&5Sye&Q^ z%M+zK%YVjUcvF_ zEVo31iBmZjJ3c+h^mkBxYf43Ek^>F5G z@wm^w(!twfnW$r`LGKqtNUWs1%`#^t{v55uYL^sIXT@oXFIbk@aDTcLelXS1B`Yi@SqosSoh?cQPax)3}!SiEb{wZ{nv}ca~CVI%`QdMX?i~n z&;F3Of=3*Nj+1QhfMc;(T}86dfykP?K8|{PLwX*QeK7rNzG64Q9v+&S2fq7;Pz-45i{`>@XY#{x2*ci%RN=jhQ ztJ41o#$;jn#srpn-y2mnW}(?%3C!_`H{RUNLcd1|Y~3Dj+@So8ofbNH_SgF^td4~dUe7zO(=Foq)Rh@?k3H1Hp0rY=u1LxuCbSoa)XjzMe^N`$w zzENC5%VIL-VM{qH`hTPUky$q5rm^yBV+F!jJxMWxqzqS?6HE zs+}4kUsuM0;#)PM-EKF{*htLv`L@%H6}vP-&mxpx#17H_hLHXp<0u#L0{y=U^{YLd zA^V?bSjB_>m`GvSFi^|ZRi1+<56q~uM9W6r^+TVk^eyF$TK4UbADTGP|DPVyvN^l`P$9^I&3B~o z0Qv^hx%X22^>-{#7SjniEo;!Xi7M!Xe0OL1o)5i~#oNuAYsElfuFvJAR*Wd86MCMb z|8wbASSR#fe$={rjW=j(IDIAIsA-l2EyzQziBk^6x1b??RsJ5rC{ z*=$F5cy8}zoYBC3O{}mxg?7=mQw*`f9xYAN;I}!k!cH}uuR*X+tgv5)T{ZaDHCEWW zhcz|0S|?W6yRUcExK>U$#z-J+ER!{SovIPWd}ALe3rXZ#Z0v5%Tv`SJSr;V??{t zpQzCLT#V4C(?J#N>3u1(B=bW|8IornH+`GECyYF~s zjC+6Yp7&0l=O2tQ$70pmbFVblUUSax z{s{^iSTtEI&u83kzZ%J6{kzXN|Fmhc*p5eIB|U1FEVe(7v1PQKlf~zrMU5mk)XPBqSX z@d%9(+kX+t7)rr0;&b(kfj@P6jHu7VmW&k~86)cHUzTx|=QDl|>%ZWQl582%Nw9bG zc@NQCjuGv}LEc*oC1OQ8GW;Ru(l(40?MrdamG-oa741%7CC(QZA1m6Ui=5NclrfP6 zd&k^a)PQlN1bdektD=kzv7)_8TE{tD$74l%H%D#EJU!WlR9CN^zo|JsH<%Xz@5v|8l)}TqNW5 z18ev1g|#akuWdD$FUE$kT=?v_sE8I7m-^9#t0p?YT%4z>`jg8A6Ma9fLB%=#lzoVE zL)P&<*a?5KU2CHI%!AXm-ekJMTteQnnGgDWn9FKWpEsO0;e1mq>RFWIY`q_IIqTm|mPHrjE=H%X$vj#C#vkxSaK`eAGnJ z@%q70`1j%{l#bWVTFf!Q>u$ziHGlggi1W7hP{s#)952r2bpzE@{8YR+&x>_e(@z`X z#rdCIU(Glq@#4DZ%lW*%bD2kj*WKxhjN3LgUR*~>D^&EkPrSJ9)<>x5cH?+)-JKhv zqG#nS{M9&7pE0e3 zJl{A`Prq`^3G$T7dEG63tDrt#;>7n#f1n_*D)HjHJ;mqSj;-Rw`8<{}CEg9-a$a|( zKXR_Rcf2_N1DIQ+QgpnyE{=6ztclEcalP~!tt8p@cyS#iGRDZ43(QNx>u!vY@Bb=Z zTzB2sww5oGAeO7@a!zaA1hM}1;VL@cIzeowX`+hqx+aM2_uk0(Y`qf1=O)}#QC80c zQJ)RW3sBHGLDVy^iJBI+;BsDfA-xzkMlxPMFa!Tyn1Ryq`bYPi|0st-dPn-7WB#r8 zsM7fVA6RFD=>C-<9sv@Cy4-7%$GN z(in1P{ITmrwNNh@Lw#)xwD^Mtcl^fE!B_(|zN|r)yW^utu_+dDUyqGPhD$UOz-uMDP=p4k+6LV?T^!Q|T~ zoBHoipz*C>x>z@xdEdBy?gf+Vn}H7GD$w9|Fh$&D{I|sloH-Xv*A5xTORK>6-NCeH zg@H~aE3nTLOg1_LZHVP|VuHyd#6XuK6nNf0m}U(#&~wICN+}jhk6If;pNv-E zlfy89c;(PL?Gu}r#EQGGN%Q}Lw=0WI9= zERRu#2h7uL?@rBFu6k94vVQI~g`eA(?{D8mxzh>OXVF#_f>YdS6U(D=`A*y5PP4gA z$pjUa=JOilHs4HC;cA{cRXm(Qd+k)va-9(;GiV-TQuR&bXWis@6~4Rv$<>{hlL{C!(0kQra%bQ4^(so(jvq~X=Vj8&j|!BlFq*2RXVPFEFY~!kWL%a> zL+>h3I(-yf-;_y__@{B{kY$ zi3tg1UZFY$ORUJlC=KQ8vcv|o{HXm)4Di2G?C8I1%(fK!?!SWVmUi9}3(@PCmR3x+ z$O+4Je~E{Y#!5+Jf&RO5Ng6veeUT;RCqvEm&!;VMLCqM~Q5x@eM{kKkc*fX_jUp`Z z2@y#OlEyatcd>B}RJ8c<8y->6!A=(ce#t48Hm$J%Qe1__m5t~%wJX^?H3+oS%yGjr!Br(PrB6E*1My`_b)YX7VzUskY!F3Rxe9K7~AqDOK)Re7w(urwm~Ts?CT z=&?G3=+`ZJs&Q10&Ur+!NA=Wwiyo%6L`|;gscNnsn|BgTe59vd3O#BcBdYX9PrYa8 zG2<%Hw~u=2@mY`4Gl@cGr2QpU3YV86AiXnHyPrxGjxWXcVqHkia>uPpksQ#493P~T zf5uXjKHY`fAEwgNxl5t!(Uq1zN~OIvOX0txD_wb#N}nGTpp08Ly7oMk8u%2TeU0vn zags_k{qpg?cMp31C6%@}&cn&cJ!y5BG-|&y7a#8Rrv9zcnBV!o7jI@~T8gkp&hO4# zNLw{aG32){e5PGUegR8yx_ws)V3~R@#j|!@Da2_p6@6R4{)?_O*l{s=?assNIo+u7 zPg!ItorhUpy3ps8Y_hMLhsDWVDXLL6RsAUsc4NBI3XZ93!sP**yE3M(fii37q4)i+ zRPhGm{G7@|7l&^2rF|9^y^)70KX;>|4p~(5VIFRBe)>}XEUNs$gvTelkW;N(dR^L# z*gv{Z#LFB?s+xz-t-4abfNYxMlZu(M2U4>z1GTAeGBaPTylJg;7(fyCO;o2^Ds~?kNcv$MZ%{WCN9zxy=OxV)Trm|F#to#4 zjm%WC)>4#+?Ly-}EuoyU1*nzQg8B}w4KI$##Le;Xe{^jP3bUwfQs7F<~E%i|`N9wgD*iy1DU9ZX9D6f}5_u7`G z7uS-hydG_D+H&r`h7>LIsB+AfrajTnmH~R~*=9@K?{nO;w;p?!+R~wW8hRF~#}d6Q zxjoj^5EV-ubIsXNtXd3_}_-c;{S?Z2>%t7gXGw%w^Z=Un7Z zdpA4>i8Z>C@)Y9~+2)`lVC(3Mmy z|5v_ArQg*5?3@>A-1|Q}UR{b={g1wj{~4IK()_`Hlr#8$E6+}v_xC@QvnI`nljhe5 z7(2q9!+*xl`Df?dNb{+Rh@^;&XMsW)^t?pSK&8v&i!WE(|`O3%VWW^SN+t7i8hwzQ495_wB`vCA6cY zMRt3;gp};V66yq2&~rYZMNVmPdzz4vB=9fhwJDYi|m@F zCo{(&33Xbn(oXn|>&a}wO_?ud|HxSyf z-Wyou_59r}$nUsL1Eod2{8~?gjTZU*Lp^D?TIAMO^%Qi>BDX!FC%@|!dB|oxm40H8 zKV<8v7=JqmZ61^HJpg~p3$j4ZZ%_0mdoAgyva!J*>dEK?n!gz8fipl zIXXY-ML!Q=Jl@l?!h0BL{#Sl$1#EY9p{F)R`mH7VAe_3Qwy{>U6R^&;_Zpgp;5)=O9jF)Qtv@&!hFQxUs4a6B{+z&k_tl1y7stjd?iYr4$wO&1^Ba0p2!n4)<~h2f zqFawb@sRt$=L*Nc-U`Lo(~k6j9O+$=H2PT|gG!A5cAf8? z#;uP*ME9Ze$NN+o?8|Y#TkPq}f;754CKlhe+tcXCG;*|$MfzcTn&+8DVclcV?XEpN z>Yqk+n4|MqF$emiZ5lnV5ew%w4m9%TGzuvhi|nxu6j&~e20o9$HnjuI`kqQ3&c$Hd z0SD52Or;rnIPUk013h_{N`03mVy?oTbF2+i@@XQd`A}+9F`EvuJmIDTrIyX6@lO(A z&TydXMY#MyBCdNlkmDNzRpa>l6OA3H#ccyMyUID#Zleq$2p&93G;KcvL|mX=NyGH zk5zy@6&q=$*5hP&1AAIk&rD7GGRIa^2U0xcJe_7TR9@^r3C!93v9b*JY7M1(xr|Nv zJsAsfhSCk0iORoChN`n8Wz69i$mhwpWOAghfqc&_!8?^=sD5HBAj6&kr1+ihtC?Rc zuD3nOg7WFyl4K~ny3wJ^j5~299$i!T9_fjeKA(@r=*6~l`5OBW565FJ%jfw1$98HQ z>{IP1t-OXxdGnYS>q%3X546$DMARtWlRhvgZ4YjGIq=wfL zuwK!J_U0<+)rchY+|ZpK&s9*3B}tgQs~4T;Jd0NHBp72Ezj~6Kw#<%$VVWH^yP}{h zbs|D%_aS?&oZcG}a5B`Ed>bj~dO5}^ozt5dewWd~ZOmQk*N=9eS5T?`JeOYeq434b zdonu#U!L1imEYwQ@Qm|THuk2nB^j%q-z7K6jw0D7buTj!VR3!v@GQ=w-;sdL23xAV zTTV$oB_k=SH^se^(WZ^DC_b$pjo8KhrhhOG1)gPZn_(hf_UCnSlrQQ;t$GyDu>v{v z>~SKuMg`PnG4rs`b*8*8`IHtbhrEsp^*EMK+x+C{ztn}oQg~eKbj5KQ)^BsAeolEDiy}kym9Dg=bROSP zGghkHmD2Z{Y4{8ohP$}Zs6;c-C>cr?ait~>X3DmaVUxjyx>Pj_SgUYs=R)bXOth&A z*ID6AE?Z1wTU3Tw^_{8VA`@MHmkiHjC)za6L4sjWnK8&|Ud26T9fy5Zp zT|bt_-q3mU6hCm7u@L96y_=5H7M}&3Y_&K*ZD6K|AXti z<)lKc^95HY6>^=2NBb0Vo!>6+TgY`je2(vbaGme=E#x{c{lT}8>wM%-e*eLB-pEhn zIzM8e2m%-(T57m9g>#mjz&-(gME4Bp%#bwx;Gl^W-hiJ!`7+c;?Bwe(LJa`SZ7&MX0 zL7bP$Yf!22rcb|^=+KK~#9s8Gbu&y<>5pXOw(z2biM(b@%itH|NiEE5JL<|%F^rTA9^J!zQ9I>Z7sbBR1I=G7W(s|62-oAjjvg8<7 z*_$T!E+AolXg)Gn+#eeL5{b99r_*ZQADWDc#K#NM$xf@I@UD>%cFDRuk<4i| zlk)rMXymB~2)y=>i!dMb;s^-5_AmEo$=N#s?#yeyU8W^nQ$8Ouul;g+Els)?4uRMH zdkHOR4}@bs^V;9KW8vLicqT;T-EQR>j*9z3=y?e9Zr2LOnI$3Ax21-25}EVbErh0V z4$*^!VHo{tCfR2(H@$ZloWo~Qv=8qIoxGNKajlul+qXj? zDXOZeO&>n5rcI+SebjV+S{O!EoJKT5O&W6;PNoOY*Oh8ocbCii1<<;e%qiJ29PNq( zkh!;pUIsIV_|>WOJxN3IE#X*vZYrHWtDzO&!!hLXRO;AROY*@H2&or9KLu*ZLl%L{ zQv+z#dM)QiMo@SBQcVilbc<5+`eI#OI0?8E1yxZQq z&$kPrq;wsXn8qC32%^LJI?KA|u`XQKJl4b5wpLs!7svV<+tzJtTZOT{_%)vtadL62 z2cF2M7L(=TSj$rLY0FT#IMy2Xd@{9{i(@^8&v^S8^F$bH`zv|0>ZME^>kK~Q?Y|`x z$2w|G9trDO7;Edg7RK7Tu7$BKT-Q9-)^#n6wRK$!V{Kj6!dMrsYaZ*ubw3|caKs1t(Yrui*X4OF^!1~Vy6k)17lswDeCg*CYAPBRhJ^}Wx|yt|_k+XW zR>qf7?A3IP*I?6`K6H@R;K3)MxOQj~U1i*}`zJ!Nx5^~C&*$fdJ3}#h_(WR0Nkul> zLUCN>O-t7@C+zM}>^tN|@3*Sx^|??ul=UK?6Dlfr8;bU$J!ukuZw_t9d&`;$^b>!R z9vB&hJM|}!mpkXnq=Z3h^q?b))pY1w80z=;pbfXwRG~pQN`4tn13PMHM*z#`$5V8i zh8}GVNA2U|nM0WQSW87<#_!`PtCf~6xJ4km4)5FHTH3ZG0_S)?cRrw{h|3X}a?OK& zEyw$3wMhKpJAu!w0@hX}g1%3nijg{6$Y(a$N>8f8dvaPFujR>J^a(n;r-{Ua;@;Hp zn2w||EpObk$SmVTA7AKcXm2fUPI00-zw61al@>LOPLz8|PhWo0!sVnBIn#xe9B0BY=T2pr``DnT60bFAP@2nidd8H~p!GK=8XK>t;Kv%Y z;@_^B!}nu+|K@(0xr}`{7KP>6W+&?AqNg@|7nkGcM4vnAsRG~Q4caw~W>wUa6cb(= zpCiSG`A7K?QlGWdm;HC=eU|#@y{@SdmF7-C<1)z1@qs;0y3=Nl461WLjhHfHXdahW z+M>o&8bilNWYA@f+ix**44tvhpsS13c%3zdPWQ^7aG4t2_K%@fE%>*gYJ9oFIRaHO zsQDB%WPgmIBOlV~`xrIsOOGX+>*-Y5k>g{_kEH>7(kbaK=O>OGPFrrIQ_15Rq}+C) z;}y~=l=BEW-glvh*6CFJcMV>=aiP{j(nhtxqj$)Yy_Hb>+#yP2@9T((CyW~n`&a!-8j=@>3bn+_OzK?P&pW;e~ zAL*!KIR*TByOQ#Yj-2?;|5|ldimRT&_(2ME`{+WS+NV%AJLa=~z|R_%!uKIEvHv$X zrO?Tvj3LH-lGR{7dF_&kef6^FeA=^7CiY?fdnshgXH=nYha66!68X$6&V9aibqe)2 z%EYl~wkUf zpEQ5=N51pFe!jC5XW$1e#B};s$AysMvHZZ#8BYJ|_&HMCsvkIG|N1y%QhdK3c#Qx0 zc#J>th=1e}|9A66amw1x@O00+!TUd%Y{I87j z{EztEqd{OW&K zp0$5henTmz)s!(7E`T2#WR|@6e?<wL)^oi=cJ){pIF>C*;Bqe4XTc@Sh3ok6f@KCYtvX9-(^orJ<@QZHplN> zu&1&1X=qx8WB+xFTrUkd*JDtAoC9^PoQC}0V&K5Bd{0ZHVe{q~ zRNu!jir-Sau*HBT{I+j(U9ClLvj}l$sITb zR#jvCtI^bCYX&4f0!VxWkoX87@ex4cBY?z50Ev$P5+4C1J_1O51d#X$kb6vp4h3Uq z$LDlht)j+?-tOeMDFXqO)wmktPM=n0AiaVb{(Id?nVo@JWz^XH-JRSt8Bj3BwSSK> zw0v#`HhpCLZND*OGa&;TpR3R?X$+Mbkb$>%Rk)!aLrq#|;M*k?RA$E2sg?mDe(cXU z8LX}$NAAuMR4y$GVQXdhY5XYiyq}4|+hr)mya3I=XX5jI8C-{sq8qicV9P#er=FvT z+Gk-Y#~eB|97Uh|XW{038B&UlqNAg-5dTVskQ*auihmY*aEzkc=8>eGm4z+E<#?zV zNu6S{u&*5ZyT^~DA@VHLts+N6%aL?cn}z7=a#Vjag0?YdxFog*KN~pClVge$p$2?f z&e+QwQ`9QefSy|t#h9WgtC%-?Z=x7elyks}6dS*bqYs>}1 zF-1vV3}}BlQH&|_E1iwO94{oq6qTx!4M{B1Uv!Z6k96#cE>>Y@#u$3ODjo5oRfy#N zKRq=a*UGB!oyVnf=X6xstVGj3V@Odl9m6IlQMBwBD*8~5m){he@9a)qmpNxHM}dj+ z-KpdiJzNGdj*Y83y?CU@yGI;9S=&q5WbK)qvS2Yut z7qE{eU=-)RXClSGK9q^0s2X#BN$0A>kMo!PM7q8telBrt7a!s*&TXOJo_!oD&Z{wt zW$@y7>>;X53}hX0>Nt{H`%J{M4)yyu(#I1Sc*#DUKl~hNQ%DAiACaN%Vn_N=Cj%!x zvCgL)slt(TlV6(E7?S@_403 zmm~!o>oevO=L%>UBdD&Y6Mf=5#pwP@yj;xw);oHrGL`6a%!wj7S77*SC9*y`QM0D$ zQ1(;dab0I>F*Y4-lT_%@-I?m>(-E~og?o0+r2Z`(FVYinFxsBv?gor|mR0`2}X68S@k@ z-{VX@W0BE;L|W21>9! zD!a;sCT-66i)|9@lvOvW&QhBtonz85mG0-#eO?kX{FnVrx~?VuSxEe|koadI@y|ly zpM}If3yFUg68|hD{@K5rTcqciZyehx#BFvil?LzR7%^_MZlyF#U%)Y+9Jg7vZW>M- zW5l@4jCN@#w`$Y5VOK06=ZgE;>4p$~bOIcJn(z}C$3A;pP&BrK3)QE4Aq{yHCn zbL7}5n?!A^6kyA8IocPQM5!$buy&msRc1{jS@!}|=Qz@WJKmg=T7c6VkQ?Nvx!RLLDimO3iX2fK$N2eKKB~sZ@p$_L`tVym zN==i)X2b;gl9i9-QF8qB!Gm@L<>P4|IsRDgL4WkhM`mNTztcTPQzRe7OUdCe$b%*v z$V18_8KT>I(0F+swj7h;ZZi*xcFe;|wl8^|Jm_GBJgiQYA=Sl$I-D|Nav1yZqdjQl zLNjDu9K!|=>g;7k#1P&eDo>!SHf9(*acpPs1Um59gfaDHP+XZnQ_e8{M+F%gj_{;* zYfQ-Gyo2^n&2jB6$rns%+vq?p{=BiW!5C@OjDX#d%U@ zl;(43LV0hhUW74bm``W3%$xcR$iua(Dx9e~k^YFt!@1KcoL@JQOiT07c()3p#xTD3 z;XDj3P{CZ(hcO-Vuqs)FF6(`$-tT#6G*JaVPhV_;Cqnz4Ak5|3T|XocL2CUclaiDNY{jWMH)hZ0BU_|d1PW>g3tKQpG4)?)jN5!7{n86Pfb_{=(jo>wYIgsQPLdm%mdv6V+GQlS7{*a73jte~; zXTlQBp_t>zc(5iD7O~w_mvo`$Y&R>j&H8Pz3tg;e#=+5iCNJSify2zO3z6Z-2v>^W z`I(g>gG$9YS%-NaUd!KH977mYF%M~{IOl?MxDJfS!`+uM_;Y#HC3(>Dw|O14D}Ca< z^mPY0GDo^n^ZNOi$={w;O1V=1@%f1Gm!nvo3)Nnb4;k~KPU+%8N&E8An9m`~wa%pD zbI84HIZ8KiCeO+Rh+QGauL>vX*NV?S>*d(^co=Q(S%5$IoTG{xMhp0yBgv^mJ+9M~ zb1GNxnMcm&rM*jsQulfV=*?%IzTX{a|A%~BRP#B?-+{Ux%E$aLITD}P(~bH0F#5>R zUCVj3tY^+per|tzy3!yYUpe+ZytF-CWE`@#{ElaD4WYi7c}VAX?{IPmd5z7(fs=f0 zIXi@uHS#cbwG7jq520#j%*f^MR>ubRG<1O(->1uP)YG1Bjx*yN_j%G%dpg(3j0=4^ zhQEjd&Hlpcx0MXLeH|$1ya{z`$3x{Waaom^?eWb*Hei=^3*hVy}uZ8WI;WPjyj9}dL)b4JiTVuk+d(73MbE6hK|JxkW z;KnsK`Zdgi^rgH%*BwEFN0^YK)S!yv2zu6>ZBVcV!IMW&#dk&&8>PXQ>Ac_WF`_i% zgbU?6RLqy#+EPEp-H5JrE$x(U%J#9UrTu%abFrg><+-{;x%j1`M$~7tF&Ey|HKLv# ziMg25KqKle56*>K2aRZhWRr3cF@SOAHLkS7lgr0z@N+Yc&GyYjgE<=P-7WH3qAK(6 ze4Ok;K8jq}uhn4g&n|RqX)Z3D;5B%~nFgNB#c7Vy9=y_-GCt?Rr7Uw~>zpaFoe|TU zYB4U^nWjwS^Sq6v{OCeHlRIn0`elw9L2Ubkc4EI7QH9s0(7vgI37Z16;&cBPXF^$) z1%0~2m{8SEE9%*vzjwZjWnLlHzsLp?Bzc`kk!9sLY4#Nw$|ZTNF-j_I#7uZTFjgpiG`2tX(zPMjf>>F zJbS*Q(_$9qW%LW-T>b%COlum6y-xPDpK~S-e2&1T9`>{j8k{^5fzh4p$#0$pJyRmE zpYz1)kp`WeBalCW^Yn{q;8r{W2@&@6?64Z{8^dv9tvwaxnEia8aI}BN`Rr5GI8!AY zw}v>7`v5h}d%`dw&w++ER%2IK7*13kN{UiyeCr*CF-b$I$ZHj+fjZR^#QpX&pYMLLOAzXMUV` zzDm5KKo?`2c)r?gRN!GA|CY~Jra%Rztcw%RSL^yS*TMcc@qG1jQ^jA#PCBM_Ip0}0 zUrpn0P1&1J@qE?pg$g}6XG%CqvjgXI3FoWUyEQm*FI+rd&1RgQX3ZnS z^OfgNEgnyb5YJa~r52CUBgFGn-XSeMpNJ68R}tT}sQH!ip7?zAsFMzkoWm%builK; z;WXor2Qyn|2(X?TLXutB>^4?e?L9}ac>Z#%PfVr92&MHc((Vp=%1UuXCz6yrryiVE9 zF5RVqNgXfR+2N@ww44zy+S3`l&y;lMb;@=&v4aZb?JVVu{^0M|wwC&L_bJh{zNMXM zDN6WPx3uptQHfoZEYE%2O^Ioh<3)Y8RpvXen(?BZc%?vCqj*vOCs+9ntW&(W7d<|q zz`Q~6qMd4Zl*=c?i}q{TDFvE@#*221`7}|3`L+Z*d+@yi!`3rS2;0F+|OaQ@iClEayFeiUd;*?+Lg3BYEtDXh^OOuiPWC z_HG~zn6E?a{*kEZ8A#{Dby&@NP9*2jdU@#3s#qi*G5^c>9y-*x5`o@Dr_sdnI#gd3 zfuHgNsNq%4p^S{cAL9bZGhd5-_7SMoAb?&5F`r?T2#kL-m3DX0qQ%8UoJKynH zDJvXz&rYQ~TQqp!%a|B9r&1fkq|$6R zT^R=>zg!UIKUQJF9md315=8r%YbBG<0F_z?ll}s8bl(WYwC%xU$9I-*?uVj@<8)ec zTZLPk^Zw}kblS&fi4_&Yki>l1UCXQSp-mXhU7A6LHfp%IgyG__nG`=3gj_r{IKa8{nOm8QoOvCMcHuZ45<;0<)F|ID z9G9wx(7|bHJgFFtAj3?$(t^)O6~b}7=1e-w{h+NIj^fcX$bOp&&wGcX?bYeDjrWJ* zQ^N7Q^K|MMsX}sYIBLk4KZx&gPCp38teZiknx(>no)I`;7eq@FnOjB|0o}?#>S0o$ z(^H-gtpjQ72^EG7i^PUsr_lxWp*3F~iR*sTs0E)}s+Nkvqn6WXu11YH6QVG`)HK?0 zRgGKAqi~St*xvTc^YbDK%YU9m-QzUq-Eto0bFTNVXEiXn%|nUIY4o*;7OjHj;YhJS z+8wCHx3GEm8XZW_cuk#|Jr8v%@>oC6V$Z~RsJASLTx;s!*>@f?U3e|4(|L^+3r=;$|-a`rRlRY(MO2F;|6Df}Hg$WlI>*ZX$H z6cXxJV?NbUMI*#^GG42(_F1^tei+|7`u`p-KDP;fH|^xJsG!fInQE+h6)x)ee54u| zOGk+M*CjPlT1JR#p$?xhZo5WcyDFGm+jDtL1gT}RViz=y6qMpJ&a6c+a)IT+z@2L3B^G`eti_e$sveoA+*yTc>FWY6S&sVU^R-dn6 zm#scu!7f{UzJgu0`g{euZ1wpHcDc~!%XYcY=gW54>hl%sa-q+c?XuP9E7;{ipD)|x zLZ2_&WvkCuu*+7TuV9z0K3~Bu7y5kJE*JWI*)CgszJgu0`g{euT~f*cm+i9E=PTIdLZ2_&4K3}%WR-dn6mkWKq zY?rM*U%@V0eZGQSw)%VpyKMFO3U=A*^A+r})#oeNx~kE_>}ZLpetw z+T}CV^Pr#4b=WSCnVg3c`3li4r*Gm|f{hB%E_;5@L)3PKXqT1!^Wndh??l)x4~WQz z=W4!BVY~daARj9-nfH+Ga^J)GIGLaj_o6}9^U>2+A=+jCyBup_%UphJmuFtd$0)v| z5$y6R#_CSK!}t7bmrrNrV~_pa-EyxBj6{-`(?ZQrFlM5i}2iIyByLe9|!NrMLW2w zYCg^~K89eIM}Nvg7WVNOqu z?P0s@)-(?hjV$F)dA*P0_&UKZui0uw{x^=L;dXi^vCrtOOl-gAXfryp?@4$rTAOi| zWx*~dl`!M%d-mnAo~rvMJS-{~_1}8Rg#A_J;(Kl8JN9SI8P}2R^3z>h-j}h?*e=gK zV8Vj2a?uX9I%h)S9Jy#87d$axd#YTtn_tSA;mH0q!7k5YT>L?&I4+m%@=;GS_B`bn zB(}>dv}W8X#cPx8^5VT_T(7SX%RhfG<69?=W8wO}+UH>%V}JF!rZ$KDyk3Fd3bTw36!f<}}1OlJIcJue_?dqO1 zpTB1_Zu0l+K2JKyv5ln;g<@HZ7tQ8-9`p84G#cnl?boZYkL4<5Cz316{#+;c*hIR* zb-FXoo1J_T&EY%n)DmIX-qVL>6;)$?*Dy@E;6oR>vTvL*+-xTLlKTukPcr`GI*yB* zyh)8#Z^H1fr5_FEyZX7r-=q`$sKf{jew`VPK^zP5O>X&awT^GyM$ynaOr}Bn+Zw0l z;X}{Ka#xd{$xb_<4A+$)7&v@*Q%oc?fdwXWU2?e&_GL&^>;%u9ylo zZRVk2b3eMZM~UKg^UyTRmsT?8YNr1@9NOhWE2r?idgeSaMxvCP5*6>xL)^eg6zHf# z%^uNcu9`?yM{%rEYBXBk@TO%!91Hw08mIevQ}7~=kC+sLtJ@g^knf9b9gV>xXD_P9 zF%iw`a6I7`Pa5f|!meSla69Tr!Q7vA;jvh=-IFeI9O!^tOZh3jikx{-hkjpE$!~(Bl?>{lKf~V`*`c! zkHNjt{`5yxEtDK@85!zNnyVU=YZ-(7r~T<cUlgGDo=(V)*{I$w&v z!6joSm4A$*7yX^aQNqK{wu9#<#}w^N)!V#JuJgAN+h@r@BT^Ji+S{YWm?+Qr%$2RS zl$V*H#(V#0vHoSggIeMcEw(fLjS7Esix%4-zfXmAZKK8KR$jtf#O_b|w?a(RtuK66+%8s( zi9#nex(~FJ*O;t^n|rKSe_#gR3H!&2?W{V%KDc1ctKyiby&PvWYgVlI+zM?pI1~~q z>SODw!RbKG$>Nx(4nZ31n#AQC6ZJV>1A*%y@+U`Pt_M*TxC{hY!UrMBgClGNZU}Vm zs70r_Lut;TB{<68!+mc#(3yfI%%P`6(r5>25WfV6S87pyr9G`3x&*Jv>cD{YO6JI`wFt8=r6Rj@KPpo%6%sr;6qMI;467sgKV5=W98c0S z(2+_$u;}@}(pkb)0SQ+HBwQ7ca8*FURRIZC1teS*kZ@H%!c_qYR|Ol`EWaJ3USI7C^PKZ5*^-q)vm8m8_NIX&SXGan7Uh@74Xc%XyfjmYT zNWG>-xhf)$C*s#=;kdyf56IxV*ZP(|6gW7>tr9ss@tpf{;5MS_)Ad;VR*zpnh z_~kM8*9D^YIeKilrpMq1M0K|?H{ek{4t^xs$?w~4E5A!QI|{t2M-!tSztyv&EBwAa zlzON;*wOyidfZ`dkpeqAdie1lzq^Eg1QPxcNccw};U9s7e*_Z#5lHw)AmJZ@gntAQ z{t;2O_Jg!s!a)N;{^dn)fsf`d>-x91OOWYpLpO`Et*@d-gTXd*p0NN6+A#NGdmFmK zbMWCnJxbNFq4gYVbIg;+xU>yTXL&=Y9`!%;rruoVONt(Y9`&YPuQd3!R1f)$-Zbqi z%h03u#ojctq86d2^f-UEH|=kr#l;)UqssEP&RU%1F}iu7H_7p;S-^OwE!p*mgUi^;shxeI|7`NcIEY7Mi0&1+WE|) zr~4O<4Loa+b2;9yLbWjeFWL6k04w15oD`Af^5}CkgfU%vQ-~Jw(29uR(%9n&_}9U+YF1& z4i)*XXoE#wJ4=DFyncm!<`d^7gjcup&z=q(Uq8kopN&>R!pAMPX>DJEn<3U0%7ywu zJAy2vMw>V!Ed$=BTjZ<#4Y=CNA~&00z}mA4vCcO?1IJcb zWT8B;f<+eUPg=`4LHsPColc$>c@4Kesis91p4*snY_0lqUu%&CJ)bVL$b$aW_|8zM zBfOWjy!$rJ@%*!XJ$|CY{%Ipqp_?@?<9eXRX2=xH4nLI30$CUK2F zKF)E-6)f_}_PKb+@xj8{udU)(#}gL0``uiu)LZ2JU5$tvYms#kM$E5Zk(X^U;?&^96O!$AMzct$U>c4ce4wBYp1iwLYu<}T4do_&5K!N zL5GCn2C=@N+qHa)Ea=>q^K1qEg?AYyv&h0b3hz7Y4)e(TC%Ix-&OMX$pl#!GaQ(dz zr=Rzrv9)p#f6a&p_nx%rTsGdVGvedfp0q`gjrGZ#e`V8)UJlR3lu<@JH1r~6{cQYP z--uq{dy&s81G?VI#Q@LV^zf(w!wtE}+1i_~uQH(T*j((ZVnd%68}NIjTvYV8p%+R6 zy6nrr`HeOd!1|7!n}c@WZRoYefQ;5Tct4;Iy)hWz!MvH3WBSnf?FQH_%Eq~MeJJ;~ z0qsU+!~Sv~s$V@DrE6zn`kOvf#5Ei9?;5cGTOWFonvEd-O}$TjDCK50blC=sdeDc$ zTIQfkiUB!C`Y>Nl4!q?C_9gV8(3Lsp#qy9@eW>~K9CYIT47KS)tGGW`XL9)`8yXY9 z+~#WxxU|8BHkxuV?KJ21yV#KX<6J!YZomURZ(2eI+dUpydZ-OZz7opv{)7Vc&gm2@R;5*&u_#GocKIWpRp&RwyYsASmMrfE1 zJvzsTCL@hlIjI|k#29fZ#E9$(-Dm~J?$**8(VEN44KU)5d?T&}b)z?pxqPP)MdQ2C z+agBzp5i%|*^PW|=HmN3e%_&ORAqfGs{O%p;~VoLMdu=@oCzUr-O1O6%XzLREa^@U zi|77jtu^O97v?8^$wBaPi=1C72jk9L`Wal7&i@l+53XzG z-w5(_Zeu66CCDwf?T0+S1=*SBQjM;bH7Jy~Uucnq`aNG+WTBm323gjx(0(tqMHZeL z#yLnrJAyvGuPm~l=SuE(pr+w4SMhNx4@H2#Rp`Bm&8GJ0P_oelH zg>q{@2=%S~BeY}fH=+H){^aLc`&rP(+W&%{)^QQ^?^Hr7zSlZFtM1}BB;g&Geo-KZ zzo`Uy8s``GXUus)KIp6z>pz-IB-9svYn2_@hjDOkUmEZA|FQSh@m(ED<3Cp1y|}xF zK*>30aRNbtLkaHgg+P!5;t5HBKp+Akio2A2l7XVdiWZ8y7A>VX{AT8y4SRDRe)m4l zeR`kX?~DG!yOaIQ*|RdcGrMOO&w#%*4<__7#P~vfu<-!KwV&(4?zk`9kHdY>;kp=! zbF{Z^^I&5uU9`kGuS45;aQ>AhZdS!LEBr>o*rthHc+Q9M2={(1*2E0-ah84`2=}IG z;@y59Xd8fg#l~wQaK_Q5Cu^cnoDcM=9|*o)ni#Xx2Zm=0ggG&qD7*mA3%M2m z_YY|zPmmAP!F_D$aLmer^W_=7xR0%cE@lV&z^`~_%ckYJ=)D-vJ}DXizn3#a_IMw- zu+JZ3=7u=E&jft>?%eVN!!?>m* z1=rAa1^U6$na#vCdp|fa(+@hlY$h^I_k*Y@eo(`sx#)Dx501~kZ@n)!7uhTOLmo`; zUA%>uhU*S*R^a-0ixzm7nm^3hLTsrV0PFMmL#072#5-Jf zc+t!s4z+I~^q>HEHVxN5YP1kHcLYF_t^P1BT?^3{*Kw9S#XYabnhWhk0My4A=*-aO zA`H)~a2*{0tGYKAy9)-w!PNnfzfg0L0sW*q7}FfRvza(pI1oI#2g2+2&BSTkKU``B zerxuqsmT5i&l9>52(81KilxVJ-(!(^(6mWY(Qjn{?sJ?6eeX39Pi6$b7~H#gG`NYl z(iZmw#^Co`c=};rFQ~?|p%OE7l*$e_ZGX1Lv6>X@~WL z-|3V5)j3}{aNXp|=(ArfV?Jv#o>h}D%H$%iaV>Y3$yE>ffJbpN{{^rON8o-+(sMe* z2SP8K`~ur*9PYs)c~FE8_JacIScx`HM*I+AN}1QG0s9d>!QC~V6(|H(BGZ?$mF8vry8}* zwz?brSLg3c_C|kqVT#G;(ce9bwuAJL{9ap=DSZO&@g+Iw$$!XX(%%R70?OyUu4uj^ zQMKL&*2?$M}SNUy{pmp!BkQNRKQx(l5)Co-50l@*~Ti@+s?u@?U4+N`9}% zkzr6XcqO!ntt);Q9R|*GSHiA>^+fSWVereim3S^yJ>fkw46<}v38BB&6W0U6prqYO z$TY}KWLXvlPHz+8`0sY&o-GVEu1|!=i|dPfx57Z+H`O&p+lx1qmcZPO3D6~>f#@2& z1X7Y0!R6yP*34dkd(T4QW5-tFRwew-_s~M<;p!+}_{YEumxYj_S8H)-KYkZqd?6hF zs*QMlHwNziu>k7&wh_zT#z4&r3!odWReeN1rtOghFfhzX{DFRq*TDra@|=@+i~g5# zhY>XRWgg$FTXkSO6h9Zn@4jO;zSGe#NUmK^jGM6%&$$VMCN=HEqlqg)$9Eo9wZ7Oo zXeA_SVbHmPy=d;d65bwN43#G|5c_Mag!k_jfzyC*#Is)$q30yr+cB|)Xn!LfHhAHh z$h}s=VM#o$i3dUTk*!7EY4K1E*J6f6wGkah#6#XIxc1o#^EoIUw4_ANPj(20mroLy z*KLc0ts0JIedvTe2Fvs>2Zcjad2|f|h$j@p0a;y-G`walbcgy5t3cCmqGnL*7t$ zr59Y8gm;A>@rDB!hbKGm?N+=4{GQ2s@rhu9@83xNu9y#0 zv*wvUU&NDe@0nxtp$*p9A{K}zH^liKi7U{G|XCy=Z!3{CrZtWhJjo0Zs=U~#iXQY*t^>Y z#!s^si_))vYUh0L+>eH$>zoxZChpd8;%X5Qa0&Mr5WiU%0cUYdlX%Ij z2>ga{ohP(@H8CS)G~F3t`3LHeNFc09S*;_oBS|KIMiEg^8NL= zzK?#5e6Dhj0Mt$&!16y(=jv7_*QpT!fuSbq2d5YT-7*g0gmwQCyQlK_T&!sl`Bc3lu+%s=9tnO~|Y47E5^Mn`618yyYCc{lG zQEM4|U)toY!*N~dHQq;$zx{P-B#1vujyV_s(+itvetH=W<-aw#N1br!mTdAZ-22hQ zFrSrlVhL!!m>k?}30(6v^EUcK7}Rj`W&J@o-=TRCJ&Wc=x4W5T=sPzN5+jze-0x{T z&J|ZMUpR$xkgwyI_hAhAVC4kn=K3<2vMP~z$YWgh!FeX>qv;F>Nt+`}N z^I5~n`9h^#Kdxqm{_h66U#MXV!1|4EZ2yM#Kdxqm{_h6OF69(%k;EHOf1)kiRBtGv0Ni2mTSbsa*ddn^8clO z{b%(rwZ7E#9hK#pg0zz~x0H60SlUTqX(x%Log|ial33bFVreIdrJa;=xrXv(t;dWf zNIOa8Bkd$H*~$OJd5$`NQ+)@QbfzESTO=CtkML%nV#t!^Fz~JyvkRWDetee6?_HMR zH!>z?Oo)QV8BNZ2Clb~?$GZTqd`gv#gj_g(BaTRnfS%dSGpW zuP;8rf0mD+*4OQ~rX8+~XWU+xY;yM#fiUu=>5tUF@u!K8$;<5nA-1x~O>iG~zl)}C zSQftvTZjA9$tE8-;SW{3OwQcOA8a#Ce!K(sW(1j>Sj`VQ?l9Ro#uwuMF!?sdJ$5^p z`pe?p>YAHO?$aLcx2a_2ZRUG#2w7?J**)ISww^hrl*ZU^QH&2$9tLCF^>ll4+P_Y(?n|) z#B$Aoc%!vuK`hrSh-uA2&BMR4_M!TfpIaAD*C2=~4-sp^c};;>t|<`9H3ec?Q=qjB zVrnO8*EL8^dT3pPSgvaj%XJN6xvoJh*ENV~T|>>=zp_3;>vZieO%k+Dmth0m=Tc~j zC_OlV*F8yIdPo3FdN+gRi}BtG<&Jw$?zo2+*F#`_jxJ*7q!_4jFa++6?IJP{!Fy*` zhrs3^@!o{?G4L@U1nv|!ucX?Og zxq1bhD;ffwR&^CirmTR==}oy^Q#`x-aWJRO4!vg$f znVy>&*K~|i!JMC?J)*(>7d#&m^LeUKG&tQ1hD|Fvi;v}_q4M)!m|efK_<-MNIA;lg z4hK64y871ak$$(1lmXQ9rsZ3yAU|ixua;_7x%F* z41q@lI*KIEXh_@?0^zrvMgC3EP~oQ#&<;6^->yeP%X=ZPewVYjQfLJ<{%FdZwOs)N z^3Uh=v)xxffwJ>i&&w?s`>!^i^%uLf0`Kdb&(9s7CkC$8n$P)JRX+yqR+-QFjO&bd z1C^Z5`JXyG=5OjtJ)2$SFXy!X_0MS^{tWl>)|((!o{NJfxG!|#@(E%h-a#{Be*kpO zHc{OFISwLl@9wJ6c+Tg+I9N3g`|W{=;^>Arm^2ReGZ&a728P7J&5i+Zy7MIQ>xekG zkMq(>9+O04gk-nNn&fxIB5G0?>|bMB!0yE8am#_eSs(+6dMb*PvL%JOkWA_ zBAKz*pY^PFh=tWVagQwO55)alUv0xZ#`s+Ot1++%ney{)C+-ci;n};G&kT{ckNyCj zrGojdjo&vaNCpf zKXAS;RDXf@gyMKNz|$AHWb@+jVlnRVsb1EL$B{DV3%=64czijHdsZLx^x|>HSnCUA zr+V>tlz0U19>hISG~Si`4gJt9UOaw%SIQ46<9-Pm@47kTeFqP`c)V*m*AJSf_hxy* z_kJ+Apf{(#`N$87l=o&mE@l1UehqKdKNHVr3aabP&pnOzR^6=Q&H2d{;}5@9!~IM+ zE@#<|=X;m-=KNpy8S6!179TREH4`(4Cuh5}}@p8WW2i_6s6tp5p) zIr+xU=I1VL7XTy1&F1{{$8U3by3OW%4#9im=FZ1+gfRaL@Gdod(`y0Yy&f`nQmw4xe?#|=R=-dGi+RL5CqjNO_pgf)}M&lISw^l05 zoyV_u_W+34;?Cop7mj<$$J}|mn{XTNRJ>)%f5z`+&b>6#7w8xW{+T^kPrzKf(=4wC z>tBcG%Vj9!!OzWj74H!!=)w6hGT}Epxji_a4e@-ZHW@uQ|JlF6dQs|2Jp)xHxEwa8zMTKjfIaGlg#zq5V8Cqo*BCd zV`4uI5&FhhxPx~dRWC7ATnLGUev|S3qh3SB*paa?2G6V)enUk$5eu&x&4WepLxnS* zPkXuaJSekasF-jbzZbyR8p(^t#lSJVLxs{m!f!51;oUQ&XRa0l&X@6wY1BU^M+~g_ z1^sJ$Zh8DBzQ_4M&d>9t70@2rE9Emi?wRWM0Ogqf`aUb5;T!yZ4d1H)e%swE_dK|L zY>*g(er0t$BfH$-LE?qm3V7B8<>>~AIDh>1AHOB3pEyut!8@U{&%iUez8xq={ICM% z_# zZqJ*V2SUaZbGV&nz%`DdTjp^4UtTg09)!-}eqrF9w3=Ne&n?# z0N!eIxPNV)9st+N&f$J{2KUlF%5KVM=fk@jUV3o)j+gwQ+~~?m`+@e(gWoIst{?QxJBQot z37p^7t}=()bI<#J`0XmnvEOBR$&EfVx67Pt~J!=m4i=%k9&!WgV++V)w<_|te zbGRRQdf@!|EZ#4J{jLXomsa@M9PW4aIJV}%g>;x~9^zEWT6*@-HD zIY+U-_^Y3zsD7KEeuJidzwo&jsTvnmzYS5p86lQ&)GzCpCB?tGju|w|Tn~K_=?@<( znro(WvHz-jY-leHt&_^VG{kZ*4YAxyLoD~w5X-$Z#BwhUvD`~TEcen7%e^#G{$)?p zKffpHpZR`S{eE0s&z%)#uGMM}{NSthCVS%Agu34Sxpt!VL3K_1xb@xrnn8FM3C0*{ zouwn*Z>XM=`DdJgN#||;qccTSyQHqM{=fPyu)4z5<&j$8bG8PDX|?HvI-F%O-p`opo|5zyhJz1WOr7EPZK z0gfs5Vk+{mi4kz`fW3HH$se+0jDQozkPo5X_c|QzowpaukNQD$WH@v`YcKM8_(7h9 z;ZXgSy%^}_2ZiyQ!FW7JG1G8AxI8Ev&nm(^kMV=}rs3fD#9nOgisxhGTLAs1If|r$ z%b{b(`OxfDYjL3Ha`3-AAC5nB6aiv6Ji3o-=%*dULOd^P=O6Q7>NZEwx*DE+mv0fg z%l?hn2EI@s$0C@2x1l(OYZ*nKhr;oN4MipV27UGAQ1I^CP;|m?(9iA-g-cZ%ihdpO z9;8*Fu=8C5F&e+W4h{^3pH4OqyKvv#iVVSU|6OZQ&qwD#=u-%S=?oRo=*K*kK{u`n1 zUI^aLBEf&AorwH^>7PWx;pujw`dgeM;W?xcu6Du~_e-|=70*$fVkhjL`$5Kgk?`(2 zJCXd@4}xz+LJpLN;GAm5wMck_Jp7Iy^hidX_}g(dyk~i4BzR7>6WQ@Rq}JH>CgZby zZ-?hmWsZc?ZgwI*mmhRK905c9?8JNg4m)OP1dI-{6Vng)LTMuc@6<*)e)s>OQUvb3 zvlD%=%#Rj`fa*)_#7;L~XuTsG&MvkS8SyTrn)9&DEV2`e3}2WsG#pAJm#ggy+iNd? zGkx(~4*ZVQsmcO)Gqa5-*?0xy_!tK6YwL@cY4 z2s|;y-Po~>=u%`6T=^~#@^)+^ygr6PhT(y*vRfOW-3|pkGoC*%q>Z?+J^(&9mr&;< z|5tksKQ{+f=hc7qnNFXZGpqCJf9GD)f9E$lv}cTbgtYs<)O}+A%Kk2O|Csvi5AFS< z=l(nP9DZ((-@medFYWo>^e%LM_`h;y`2W>;?CLr8>bd>0zUV%Mf9IV7>fH@=KM0jA z-3jtnzF$MVujH?M7r?joJfU5=HsWmV<=~9_C=L~AE1KqA4%t!uhyScNBgTLcvxZ?~&Q%C|0`Q{H2IHJUZ(r zdOC(e`K-9M{=rc+t{nL@3Yf<^_LRhh{t=zsjSwm4#qR& z-QZ||leiQc4AJB9?$=CCqBh=3o-oM`?#yW;uDS+8?I~`sH#_R-77QN9bE8^|6;*@b z=tMWX7p=9(^fCx0jKI6jA2^B>2!h~m-QX$CmkQ!tu9KR%L6eD&qD!+N7**a4_Tc<# zAFg5Ue>)wvHE+PlJRR?tcNBwX&Vz;_(_vpDM^Qq|gSzdfLqcaq@f7bY>y#1i zv7PQH9^qMZ-M3DID;pg}`mjJq7&r}TzHk)lMg+pCywl)XtJb1>Gd$-I?;r0S-&(Z6 zvk!N4z{!clzRxi;2h3(YYu5G><=cud{pIge8JY#QCujM0Pkz!U8PwZ#kni-P(80NoW9md7?JT1{?rF*9d9N2_Kb)9$9-Vm z=~lwOU_4A&?}O)FwG#PH#lZ?ZC)BBwqiC}r4nB_afg^n!#no@|e#vflHt0%6ai&Tf zoHcx)bGp`I^1E2@sNw^=2elSsevXA=g?-?gldVOOt+8+%zhy3n^W^1A@Lc^j-mrRa z8&Pj=EHwGe8@jc05+5eTLV?Hl-OD;B;WauI#6xc`lj0*{p&Wkuoau#~D6(?_#OCmZ zgwytT-}(a3-?&4=4^6~*!2X`j1Ma?PB2FF({&F7&-UsoYbRUO$e+u!!3cdM!k{xK* z`n~EUD&tvG<`!yVv;`aqjtGkGHKZV2oaJ+}Ivx^AZ z91dM^EjEXji>ST?@1(%9h}-OO5oKqGLlwMlWd!Qaf%k@7D}(13uk03^`A=Nn&5? zNZ5n-t^5=?NrcadgqzFo?&dv{M6Y#`P;0dhB;J}N8l8!R=!)QSknw4;&J?&}^uN;DXNcS&H}r?NIo%&3a# zz3`m6pn>9JOcY#u5&&+$^%b$NBJsWeyra&gkC-9Da=B-`iedQqu@% zj%Nh-de%*p``%=?8y%Q0;@-P8jk*h`Z4odM^Kfx?ckyOz1cc*W>mhr(3;*SKHwvCx zz58Q#(P$=abMQ`+75I&4t;8N88SkJ;9~J;95k17?b>T3l8nvg+trk{*XRf50U=fQh16nmj}nYi@xWV!o+Al=s&-^`0Bz^=+N8` zvN(4aPwp>;7x#T(S@!N?OV)7Mv)C7Y+uu!i*yA}>Sf{7vbQ9Iag+tFAzL2hYH&J72 zI2<`k-yC)m+pvAE*x&=#Pj?kt@m#kXi+x~rVpnlz3*PU8HovZCS8+REB%EJ>XN8UI zDjJQCgb-|>4f}T$`SIQvSNu-3Xs@oK51x0?GRX%r;Qrx?A0y!{o@wsfrmMJ8I0|%Z zpY0lU6{2Poti0$0txI|789>kDG+ zETyx^9%}Lr>)SH#!8Si(Xj^dy+kB^7zR;vhTQMmh3Vy~o&W_7YVwHOo9K^G;U80@D z%n4BtgLiA~7~v%D?B4Oih@^o7IVnk zHe%WbvrHbnYQtsHBMi?p#JO3kfJkVL`X?92xs#u9pFD#=X7RhIcSE z#l1v<%i4>Utaw~d(m(<+H>r8hwrx+yMiO2F7`*e!W~31ek&P`eZO$44&pWT z{o2@nV_Z9kW}6})6ZY|J>pF-5+aq9Yes{Qbu9KMmeJI=t@nmj@XS0yMV5`+pkiYO@ z)@&F$wWFw;ITZTgU9^u^o*d`1nr3 zsTuOo+29-2N&M6^6b@XQ4cZn=KQ0u0{$n=o8}1}Fd56O7%y@_C=}y9Vc_{49=?-Vl zb`tm2gnrg%QRnByuTO9vxF6W(`BaFHYbR=;y=+*(6~61!UR1_+t>4%c0>A1Y zIyJ#N3Z}Tik6|5zgBy;M8(iUiCTDRR?=kSa=L&~AJB!P>&#`I6X%GGXW{FQ z_b`M{hrF4cMf|}ac>B|I$PnK_O#c`Jh2BqxVf8wQ`*niBse&8$Z)}g}vIfJ+=5COs zTzj#5MlfV?aRZxQI}x`i7`{W_YU_ixqGWt9ycvV{Tzg;}UKRW|=b);4TGYKUpPMJE z^Fx1}H&Pj9#czmqzx3uZJme7zOS1TI8ScgJj24&l;WB)DDi-oI^5HT(mn#kq;5?Sf zaCF-^Xgtw}%W%4H97KiSIF4l)eh9z8L0d;FsWf8yvFlesSFqBiGLF}pcn$Rd5R%?z04Eh zPIVG~Q2>LiA(TLyFYc*1(`P9l2$GFWuf6I@(635Scz zpw7>p5M8B{Soa9;V!DLq7d`1Hyx!rxJl8#;_~wpcaF*rJ@)n+pJE5bTlZ8zXE^!I48qfJ%Ut@ys`zZnDF7Sm# z+sBL5za>D+XdLevj2G4OVw*?*x8{a%Vqv93*tiM%QMqx#$377Xpue0jf2=r!?f)e9 z1(9y7(2*bEe6{lUG2$lr&fl%V?}%=W7FWxoAC10qp+2L<#GHxH1^b%Yl~Lj?_O*Po z@&1?*qr}S}6Cm>_{H`heDDf^T0ld578eYOkkvt{=9^(4k>u*Pj*WV;SB;J9Mztl)E zFI@s;#5J8>&qs*f`{NpV z9%#G#{6>jkXuBTd^np_8M~fO8Vj&XG@~Amyw1{003vqbHY(n-iqWR2NsQ$zo`YahE z28@dZC-kFpR~;)FpdX#*kvEJ=8Y?d0{`o1-yrG=aIMHr$ER25b4flT@C;EBC!l_K? z*WWr8SuGZq5Sety4sg1C`84*GQTfzvrAij$4w zK*O^wlDkb56~BvvU2}b)W$;9iaeW-jT8=t*OcZnP$HDs@K5+ENM3JKu+ETO|)UFoe zc+}wPG;UV|Kg@$iMW%DRs;33P$qv)GUFDh*1R3T|=XRBGeGq;ZHl5p5of|>$)wSu| zu6E@M2A3>u+^!yJ!H}ye#`LgVn8}s1w@2=dg@@AX| zg)n|d?JD$0AiNE6<#v^R3Er7L#Fg7s6^u7-7p~l{4mU=BsH7{mtKbs2o|(~=+f|ly zf#CdPDz~eI2LaIg##C-s`z{4QB*qx2T`k2JW2Gxoxm`6zAL#j=sobtMTn~V2e@x|e zwHITRYjU}AyRyp>2rsL-a=ThqEf6|%aOHM2rz740G}V>cRm&NH@I#y{x2yW=0%7J^ zS8i9nHv+*s$24wNLyOOYOwFfpySj_tf~223joa1O0K78_?bYJ)gFo4;VuMrdRr-&E zKH002gHr9)qJ@J}?NzImgHr8P#d`x&?bU{v15@qQ;w%GG?Ny4;fKT=+-GEQ_YEu7H zdzE;j-zR(3sb8wSs`5kMPxh*Q-%s{xeV={~9UD$%9yCwq0jZ>qh@GreD`y&9dPf2zGIAJIS6UOlKZ zAk|)ZuN{zTuYRsN@RPlY9QeszWgPU$UiBXI$zCN4O0`$5t_}KRuQ1Ld?bWdogV|oG zce1PdC)K@q|0#F1t9uL8J?H9q9epna!i>=FV$8P@;B^zfQR>-I?6?vRaVG#wt?;%AGajbI$oKFmdN)vjBQ;v9-E3R|=7KL$-Zz5ot5Bf9v zdWb5xU!&O6KzMhfhiIQS0xAv*1fSPE#Nn5CpKp&qaLm$EI9v{gEKax|J4a8^?1ykT zj^`*5N0pineRuhAny2Y;uM3{@Prq%7`&;z2KCH9Vp%BP~{xv;oAt_F1wx=+EkCILs)Kk_GX#A-yzB062T`SM2>jH+4??aZj|_pY@cTI8 zV>!cN>iKz4`wseIRl}jcExhmSc?VIo6~;mz&I7mX&Z5G=a5#zgwKuEkERtq~L+Bs# zz{}ZLv|5DmpO^EX;|ym}9nXpxi}C>UU#_KugEyvsdCOTmK8n6S>S60iwmL6tHKeP2*X0^T~f7`x@p|Y$;lFND|mi0(1>ycR2BeASUVp)&GvL1ycR2BeASUVp)&GvL1ycR2BeASU;_Tn%)PF5{kJI0b&8L?;_m=sR zV-daK%ZxTkL+{l;U1nzI2jx=bt%IthrZ0QGW~!b|E9&Xrwm-&te%RAMztCbWvt0=X z)Z@+kW}&WE>e7(;W?`Y1ubjmBuesFhcl2CK&h=%bcObc?huPB4Y(1CR$`7-ZPi8Cs zn(|)E*84JB<-qB!@?oAHl7-%jdE~f^^j^%b3ZVjif!)$qNTLmIr&@Vz+yZ|lC~ zen-!>ycR2BeASUVp)%hypfXLfmqffv8+d8S&ziB9*Jc=63codw%$u4mi0(1>ycR2 zBeASUVp)&GvL1iV7L%=BJ2er?5k#8xp?-mQ48)btDfuus)9B(I^r7*LecFRa^KpON&D^E0+u zYt(aqxy_lj`ulvo%<=g<=)J3FXU=`51CMuG$D%!791(~lPQV5TyR zE+-onE_Fja8Cj3p#$GzU7w6M0zK@RY z#XK~wFSiZKvn6+6Hq$d(dNh(-`kAfgGF$m!w(`kr<)7JlFJ|j~nXPhQw#tXuDmP}U zJemKD_HZuiO0DLRGY-_oK1^Mu#cw_3KyB>Osx?~7oZ}AE#&YIbubs$x)PdUAq5&JV z?r}dlP#cRovsL?8b&mtJv5}cpXaNO!vYu&&cWSMkB{@)gtLGJ??fbnO>&$j4PAk8? zGwWQ?IZ+F%<;*%^?<#G3a$D9pbIf|}NR^hX(=E}oOO&@Z(Oa~@(}t$J*~bz0@gI<304Q9iBmWSy2Buqk%Hrq}_SVh3!B z9k5Y8Tj$uT{rbX@bxuN?&^11*jq(}RV4oKKu_fz_PIo~2?L#xxdG)u0+TomV4e02&uaVIk7b>|dY;tEtf|d9UFx0Fs=ge>IyZ0rMJqIDIO{yn z^@0{QYcT6P{qUmpaZ`WR`TpeN?;DzXuTHG9R-H#$^Z+l` zS<&UOcHCty>+BW%MDwlU!8-R`eyaI?HH&qg)1GVTPkqNaH_pzWcdfdBb$VQVp^aNN znss{Y$)MLv3Spf;RLQ72`v$Sjw_zFe(iH<)XF#S*`r;FQtn=*YOuA1WFV=ZEERX&} z&84jKQPNlX=3(xv^U%&b`s=k}taHnwJbJnQi&$rkN_q9AR~N8Or#^Z0F=Inmr{96R z`ucqVtdnfTM*j%bd0ES+-sI!XRIV>s(1&bdB}brQ#vU&K0zPp(|RI*Ah>&SRY& z!mFj`ljL3FeOc!~*J`QxbZt>BHJ=}IR7=h0^)ppd^BFU$YHB{+HaAQy&klc7NzLc# zaSc<;b7Z!LspVNGyg_PtM%QeRTAtnd+NYN1p0~|)S?^+M{nYX-7~Wi$^}aMyb6wW^ zhXKuWS?^AJo9eRO8;3U0Wxa_>}QcEkEL`%$~^ zy6CbW6`Ir^<;A()w~y=j!M?24UDZct39ql~Zr2**& z>S*WLE}cKvPe(h?cIl4|BXqR$tn+cZK04ZYwo4114A;@lv(8F~hUsYMS?3Mkp*q@m z*4eJ(5FPD2>m2=dppJH)b&kC#Te_kWMR~4y4n{rvvG<^65Z2t$aF=POCgw zr$J*~bz0@gI<4|#omP3WPOIKE%BNMHtkbG@jq+*LyGHr!W!Ae!`Lya? zqkLNRu2DX%_Q^V}de$Jvq)@hBKtkW9bS*JC=vrcP# zXPwsg&N{8}opoCC5Y}mp@2u0BhpO}Uc?j#Y<{_-pnuoAXYre!ft$7IRwB}2! z)0!`_PHVozI<5H<>$K)etkaq!u^#E?W^7*A@ZQy4cmHa#jW}Ps?)pimuFP}i_t8t9 zs?FSL=pg;Ys4UDGRt?kleAtmh>A!6{Qa_sCfm!;zB=^|UL(loBzwN~JLI%kz+10o0 zyHJpM>#S`_B$qxrrI$WCvGm!AsV$MuPAq+PV(GK9-16Cp|BQFB-qC^dTkpDNw)8Mt`kAfgI?!*e{4mRWlAIXrgG0G&S(wpoXtncZHM(5gr=dO3NG@#`rI-Dk zSlTXPX}gG}?IM=8i&)w&VrjdGWxS49wg+MvuOpW6I${~GBbI%fSoU$2Tk$$#*~f`x zA19W5ocPZ!XW1U;S+YG4%l1Gl+XJy|55%%P5K9|QENwWkwBf|kh7(I0PAqLWv0Te0 zmTTF>axI&f^nBTqkXf!NbKj9`*;GDqEt^=bWfRM_Y+|{Vt;qjJdlJ-oxB8|{>9aQK zvsPbDl5)8h;(x2{QG2Llx0UTfwyAY=yR%WMePEmOztsoJ*|MeTx8^haTw-aj{tO#p z&7=6eRQ=X-xonAPenn+2=Uso6om6eFRpwmpR$Xu&tg>Rc+D`rz`ylnuSSIz;98x}) z=9ZGF9Ap|Q2l-oS^Z$QsRnAdm8qzP{m!2!j_P?6b{-g5$Tv^FHQ~qTdsh|1_J=dyh z2Pvm9QO>1_>3wAydS7DM*DU$pwG)!d_myds_vLw`>{BGS^2yJYOwW~Rl=jB`E^WJ2 z^C|N$(~y3vj`+E9tS33y5Sd;wJy)ht>X)CZ_ER;VlBwKe8mV8Fv$R)IF3ZPyF1Kx& zhMr3-%h{6u-Mq#6Eti{2lUBdl-eg;)dYAf%rOhOk<2A7yuZiV&O)ST2VmV$DTY309 z|4a54%9~YI?60Y9Qtb<}FOyC=))Uij|B=5Y+b5;B+TP!_ZMAL4ITfY&Je6S)_cSnkComV0rDhg7iM zi{v)zy(oRM^yLAXvyh)ndv!HjwGk&P&pD? z<;IN9rSfE^zsvm4?_@qnpUl7G+Lp=V@@I@CJu}ucOYYM?8^71o-Hnp_H1uH(t5ZGM zaqWKQGGmG)N0k1+O#jmV({JhTl#ZBwN55xAeWaI|{1SSeCD)`J(`zz4>d~Yg)UQeX z_^&RXi+|T;e(-m?%qQy8W&ZIwdP2lL`CcT~=($#UW=jvVrJvb)u1@K#{4iVjG#T~L z^C%6LUj=%e^f5wL{ivwL@m5zc^64p!PxfmHtI?YKJnt?2nkA)P73(W&fq;%6?7xk^Pc>&gx(CePw#G z8_ZVuFk9uuY?UYHLFw6r0%HvGL#zeRmXsFxZ0S1dkH${nPfo+H!K zbEF=6j?_>8%IDJGWq#;)GM}VR=AWK}^;O<_FOnx&??vft)_aj2W=lV_^;~8vKg?D> zldbon{4e&}~HpQKObzeSgmTH|dK zI6c){<89BFQEroRi#2+dm4?~+ZCbXeawWY@Va-ZI&ywkhrJQt1IqSE6%jp%C=~=Gm zB)QB#>5(k+|6l2$H1sT)p7;WWy7slQcOYy7aH;ZnE`#cEZyUF%%QSn;ST%g=AC zWK{j3Jagqjm5rkFIku}QY*W&xzqNgRyo_B@JdWCHdhGjFB9684FpkCRH=Ef1`Do#0!DXV`>%QhvA`dgc4mA86{f)6;o!nW$2 z-s@p0cUj(a@<;v6fZNQMeoSX{PJc5k+mtlwZ*7#8enag?VH@eA-;kW1L(e0oyih*U zuuVy${?%$*G>H zzKN+VP&-J&HYJVvTN|}CYIBrcVH>qaYI7u~c1rD)nA$S6<1}nj(x|_+QD31xL+KT^ zQGcR7Lvre8)Zd7yFH%2D!!{+2`db_Ib?WDoUSS*A1M2f6Cp$s*f|zUx*_1SFQ_`rv zwQXCvU0Yth8mCv-*2#Xa7WQjZmd6}DuASas@_>Gqv@YZSj%`XB^|!Y2`VS7vgQ~M0 zg>98f{O&M(mMI_VRzMp)(&Xv4YiO%G{~gDVfSdrcr-u!}>~A>Ps@!SF)^Atm|Z1 z*VqPQtste`~|`maMcl$<*GGWt+sdnk?HYw&7%@JxiuGDbuLGwPAlrR{D!% z>MzN%Phnq6mVFKTV6xI5B~zc0Y1H4^u)ilO{arHk_he}k&{iZ%TY)wtS+OUQ$tK7& z>ThjmuaXseC7JA1vb1Sv>yo9dLmQZ^*h9%=(_|X;w>Gr5$%?&|O!hWe+GMoV$UTB#tX?bUL?yg1)q~F#~RE_vN9e?rZGjPQGaX0cTG{oJIOTO zrN}W6%PB>Ul~|T3%6KZ7#zdJ${jCk_Dn%KuCDVAFBFA*B=M*{CV_Qg3<^z&xOqXfY z-`cRPr6}_a$u!?ck#iDkrzvu-f^9iPna@b3If+c8{?>+lB}JJpNv8QyikwqnKTDBw zE$oXa%6v>R&8cJ>^|vnX~7PcqH-QskTv?L>;4E21q)QRb79X-+89sJ|uqltOl& z#tVhXR;ADwKytKmDP-S?(H5rA7?6g^7Rog0Z*6F6Q^@YK{!eT}dz?aJ0Ljr#r;vRo zMq8djV?Y`vTQ1Y6za@K5>1|4SVws-h*0Yi*jg_CYEOnAx{VmyhdSBL~uzX*ZTV=&; zm0?GQ3k|}Qr%lcxuRoBc`dq~T&PD!r*mgfJ|#yGvgvc0j~YOBmvdrr%; zO_E&wEzSR_k8pa0Wq)D0)z_G<{+O0!pCY;XTbln1AJ8^!4rmiCI}maSv9>|t7#HjU)!Z)yHdHkQ*XEbT4JEnCfO+4Hn4Z8FK#-_rb_ z#)uS@)BInu94}apHP$d&<560cV+!lH#u{d8ykq?e%khro)>z4Gji+f@j)^2!e@pX! z8lySA!g9Q3xi!`^Tl0amEXQ<`tG}iBKg}^Xy~1+7!E$S^!fefF(z2YBkX-#O&HrhR z#OW25^CgyBb1i0TK9-i{oQmY?Z)yHdb39J3u$=F)+?p#gTl2}ZEa!wISAR?Me;xx+ zt|=_%tE|VG>oQyO;j}F0w5;En>oQyOZBDPSoNu$-nyWKg^ZB$a=j0?;e@pX!9y2Ka z3QK>1^;o_JGmS+w22gs1rBA{7EnkC~#yYb5lwM)!@35T4Ng4wv4UMHV2Bcx>6Oml~ zEzSSQU*q%&OMi{!maoT5a{;A2NR~bw>$iM8W}0h|-KYF0Ed5QETfQnY&1IDKELr-b ztkd#UnQ5*>cAxYsEd6DcTfR0k&Bc`dC|UZ{tkd$fnQ5*^cAxYsEd70!Td@LWnoBD7 zM6!$tuudyhz)W*hviqc8VHvMrxfSbRrnxYU0hC^08Pg!S`dga+Q@lmmTgfus!g89Y z(-=THX)dqWbICF$!#3H9)i7gPiWl*36_)WLmXn`BV*u&LyihzUEz6h^$<^P|{GZ}o zoL*rW?_xRmNi+tKek@Chr=?{X6C=6$TblnThZOPw`$(uds~wvYg@sGzO44T`ytoZ>Vz1`ty$N14w{ra8Gx zqyCoW=adIc$s4iE56i80VYc2eEz3No{jDq?PG6~2d81X>GUn-1%NmjH;ml(b%NX4~ zmoRV6SjHH>YZ3FnkkZB$zXi-KT9!6qvjj7rC|%lUI5L3wQlZjD+XBAKmphg=uIj^? z=T9qb1YhmTT;}`IMtjem%$_;R7>>odFegqfV_Zw>z+CHY8Kb~2ZJCQVs%SXGHD|WU zli4amW~=-isNAeNVs;)|!RS43EOYin<&3@6zh&OPtE^#6>A+mBU|FN_7~M=CR>p|f zT#U+Bq>##P{lw+@853=Ce_BXXcd6r45&`p3LK?mNt?b^C&UQ`qRXb`*2svqDDwjVAlM6f#OSHPiIFRnTy2Z2tB{U_s+)$XHIlvQt5$^2>21 z_bgyEw428K(7u4-6XM2P*(hK%A2X8~`W7(W8MB$gmliM<&TwZwcdvl)v5^OJ$LV;E zaD8uPWt`P0?n|*MFe_FuYd14+TWsS-G z&*wHqoi%x0@7zYTVWzM6K9@1zjLEZi<}$LlnL79Ssj7)K7LbO$mFaqGaJpznY{bE%!bE!lSk&sY@B&+ z^25Df86yHsJ;QrvG8S&$!g@}X$YfkTwv~Bh&P;}D(l+L&g)jTf~zsz{e zzx~GNw0Pw*I7_dT(-$!^iZ3P0Tbc za~;!LB$#}q$|3#bu~(e_N$(%^3g4U0>h$`cUUU8%mS;P7P~Sh(^qYnqIH<38eaG^v zuMXIJm=aD{bE~_m&0~Fw6MuXHf_@zXES-yo~`=sQYJ5Ww?*&S+T^3hHt3^PnL2O% zx?X=?z-CDGvhZ_*s;}1{+%`F>`zF2gbJO2c{9jG+ zVYScszh#%K(EByZ!#Z2ESgybOF&A@e?PYqAvL=V-j?$CX*1-Z{q9v*gG^y+!)mtY=>1h5Fk8CKtH2KreREWRLX= z^uq1T{G8jk0Q<7Z2XijceP0&f-zqT#O^E|&pNk>Pwt4E+XBOt)&e%FfA9Bx(B^KM` zq3^acdHhay{qROp|LH-q^=AD|zSnoA{>L{a$GE!bTN{}C)tPC!T|1MD29DRW3scY8 znPc@CAtu*sI!3>G-{eI-M(YQ=6yiK=**8j0Ib!mYC8PA@R%YI|Cydq02b*ycB@Ux0 zu@vodaTrm%z5ZJZGluzKUmJbH5>t6WulhI9lUJL3@v6{IZ8LdZ3wyoQX!ExoMeX#ln@sMKR9BDAU_Ptc$~tsWh}56MivBl?ic7FK&?}$Dm%gJ{{ACj4T zNAw|?$#+B_l9_x*^dXtacSIkOnS4j|A(@rfKDAGZcd-0(v3>F#(TC(TbygzOCMhhh2W)jfs3m^dUJ7`HtvAGL!F!J|r{wj{hHf?*VN~Ri$ks z7nF=3Ns<8&2}VTW?7hi|5fuXl6mtR_1LlmO(N++ZpkyzCsg1O9ch!+7DxjcZ&Von~ z1QS8QZ$59m?{RtlW_*8-Pi@Z~IELdstW$f|%C+8FbImFZDMmY%h7_Y6OGAp$j-?^R zXvfl!VzlE&o;W-!(T=4dm5z2S4Jk%DmWC9g9ZN%s(T=4d#c0RUkm6>aj^{ppK}x^1 zeLA#bX-Hjzb}S7kMmv^<6r&wWLyFOkr6I*=$I_5uv}0*VG1{>-q!{g38d8jQEDb3} zJC=qNqa8~_iqVdxA;oCN(vV`bV`)fnv)9S`4c{cC-`ZX$+OagGu0cDNh7_Y6OGAp$ zj-?^RXvfl!VzgsvNHN;6G^7~qSQ=7{b}S7kMmv^<6r&wWLyFOkr6I*=$I_5uv}0*V zG1{>-9^*$fOaemscX=Vr6I*=$I_5u zv}0*VG1{>--q!{g38d8jQEDb3}JC=qNqa8~_iqVdxA;oCN z(vV`bV`)fn-q`2{g-q!{g38d7^7Xvfl! zVzgsvNHN;6G^AMC@l(Uz3fi$Wq|(ujr6I+QKcTc^_E=e)XYaN4eeloJ^=QY^kYcoB zX-F~Ju{5L@?N}O8jCL#yDMmY%h7_Y6OGAp$j-?^RXvfl!VzgsvNby}uJC=qNqa8~_ ziqVdxA;oCN(vV`bV`)fn>z`>KPNk!5Or6I*=$I_77vkpN!mWC9g9ZN&bkdAgN4Jk%DmWC9g z9ZN%s(T=4d#m>Lj-q!{g38d8jQEDb5fuL}PvYK0-T|hSW7^$I_5uv}0*VG1{>-q!{g3 z8d8jQEDb3}JC=qNqa8~_4qV!?G^7~qSQ=7{b}S7kMmv^<6r&wWLyFOkr6I*=$I_7E z+JB6nKl_jWS3iHWV`)hJ7VTIXQjB&i4Jk%DmWC9g9ZN%s(T=4d#c0RUkYcoBX-F~J zu{5L@?N}O8jCL#yDMmY%h7_Y6OGAp$j-?^RXvfl!Vtm~2b)y}-q!{g38d8jQEDb3}JC=qNqa8~_ ziqVdxA;oCN(vV`bV`)e++OagG7(Y9F>?otx;bO1P#a_3I(T=4d#c0RUkYcoBX-F~J zu{5L@?N}O8jCL#yDMmY%h7_Y6OGAp$j-?^RXvfl!VzgsvNHN;6G^7~qSQ=7{b}S7k zMmv^<6xaS^&g`)N_-q!{g38d7YZbFp=?*m_xP9X+9~ z(T=4dm5z2S4Jk%DmWC9g9ZN%s(T=4d#c0Rce-xt~OGAp$j-?^RXvfl!VzgsvNHN;6 zG^7~qSQ=7{b}S7kMmv^<6r&wWLn_bsJmULE{{4PK?DrmG{3zK|=NhzQX-F~Ju{5L@ z?N}O8jCL#yDMmY%h7_Y6OGAp$j-?^RXvfl!VzgsvNHN;6G^7~qSQ=7{b}S7kMmv^< z6r&wWLyFOkr6I-mUE+U9{{5ax?Dtn-q!{g38d8jQEDb5f2Nqvg%INq1V($xxy5g%3A~9r0m>@dd_* z7509d*!y&1@85~hj`*;0J=zf;Rv7Jw4=apz#D^6|JC=qNqaE>KC4G<5j`*;`Xh(cl zVYFjuNHN+GA6C-Qj`*;`Xh(clVYDMYtT5UUA66Lchz~1V`JX!@?|oIJd%soeeONKt z5g%55i+03^6-GPa!wRDv@nMD0j`*;`Xh(clVYDMYtT5WKG^7~qhz~32Xh(clVYDMY ztT5UUA66Lchz~1_cEpDjMmyre3Rgdrf4Q#t{}EdN?T8O6*P|WrVTI9-_^`rgM|@ae zv?D&OFxs&+q!{gp4=d?tM|@aev?D&OFxs&+q!{g38d8jQ#D|q@(2k`c#b`%-SV>1a z;=>A~9r0m>?dKr2|AW|m5n{9>KCH4|+7TaC810A;D~xu;hZROU;=>A~9r0m>(T@1A z!e~c)SYfmyKCCd>5g%3Kh0%`qu)=6Zd{|+$BR;G!+7TaC810A;D~xu;hZROU*8Zay?T8O6 z>1aoMSYfmyKCCd>5g%3A~9r0m>(T@1A!e~c)SYfmyKCCd> z5g%3K zh0%`qu)=6Zd{|+$BR;G!+7TaC810A;D~xu;hZROU;=>A~9r0m>(T@1AD!qwaV?RKp z+doijzdbODGINdnc*ST(d{{|GJL1C%qaE>Kh0%`qu)=6Z zd{}jTX-9lmVYDMYtT5UUA66LcSQ=7{cEpF3bhINrtT5UUA66Lchz~1_cEpDjMmyre z3j5rg*#6aG`(2Cek1a+!;={^s(T@1A!e~c)SYfmyKCCd>5g%3A~9r0m>(T@1A!e~c)SYfmy zKCCd>5g%3_BQ*HoVSH@mX>yuwnkgd=4IQHk){=iWlp6r{pK`SIKAM zvXcMAYpwjOK|JBb+}G*Er_J@m^Nby_=J}(~WsEKO|cjVL8h@1GRw|dUn=S@&z>-rv{Nxki|ZOEcO{>vCklj zeFjmQj`=a)pSi_yqr>nd^pDy4@*k|g+K2tCDnR>C$)Qf$l zUhFgVV%|sEr=|0mdZqhJz1U~!#XeIn_L+LI&(u$<{)vrDY_$12T8Qt-9jlG9ByO9^ zKt!DWp}& z9dAL*yK4J8b&j{7bjMo|JKloW@fO66w;*=B1+n8Th#hZ1?05^}W{uLP$Knt>7KhleIK+;{A$BYdarwd#i$m;K9Ad}f5IYu!*s(ao zjSpDj9+N&=i2h)$&s)QtV#f~=JAR1R@k7LpA0lr254(m(3(*&`^|x%ebIcQ!*D+7Tj(H+>%oDL= zo`@auL|i_H#5@r@=84!bPsEOSB6iFZv16Wy9rHx&m?vV#JP|j(uZeR``e-5g!PY!H z=j+>W=Qu4Yuj90c%TJOxEn>%M5j#$cxb|L%(;{}97O~^Bh#jY8xMqmcB6ge>vE#Ie z9j8U?I4xqwX%RPm*NJaWdiiNDJRj`V&%EKzv1L?V$CeR0wv5=ZWyFpxBX(>Vv17}K z9a~21*fL_rmJvI)jM%Yd#EvZ^c5E53W6OvepZ|QV#Eyp}c03%hbBha+}89I@l!h)aLXeJ88o z(Ly|XLTq*RUFcU0caGts@;Zi(*fD&>j^QJA3?Fg%&=SK(>=-^`$M6xC4=pi##E#)3 zb_^e}WB7<2!$({`w8Zccmk%v5e8kOJr+mkR^wB~*_f+qZ=FWCC+&S)$%Imm8V#gg4 zJMNI!afif?J0y18A+h5Qi5+)HTzfCX9TGe4kl1mD#Ev^8cHAMc;|>k!e?4c{E%Y;Y z?YY8+yLt!P+gG`BtR%g^b*v<@VKtR%5xC5as? zN$gljV#i7n*ZXk3Poy?#ctM``Y|ped+&R9J%Io+}V#jw9JHC_H@twqu?<977C$Zx@ zi5=fb?D$S%$9EDtzLVJToy3msBzAl!vEw_<=g~quYh3+n?mTtFonum|jE+eqE}w8> zQi&atO6-_a!}UW^NFt$I%iy zj+WSQw8W01C3YMwaqYb%u0q%Ff{d|Hej{^nBpU7<`%C3@>@Trne~BIYOYGQRV#od( zt{Gx~i5>e(?ATvo$NmyK_LtbPzr>FHC3fsDv15OUYh5|_z0QV53o*V&`CQG#Flo4} zy%*w@sl1L?CU(3svE!AA9j{F6cx7V8D-%0jnb`5l#Ew@ccDypNqNDl%y}n*fMSWoQ6BcSW|f&V@>QBYhuS(6FbJ5*fG|`j+jte)RIS;+yVrsQc;vFyZ-WhZtlJF#Qgi5<&M>{xc6FdIilyt}66FdH%*zxzoj=v{v;soI`P)e<9AHxX!;2=TPi8hduTk z=TPi8hhoP$6g$qLxX!;2=TPi8hhje;=QHPD7F-NfuUjZfVl%2-Uc-nTn^El8jAF-T z6gxJf*s&SKj?E}`Y(}wTGm0IXQS8`^V#j6_J2s=(u^GjV%_#PIaz1nZWtKe{%D7PC z_j=8*JU7hw7vf2(jE*NMc05V3<4KAgPg3l7l48e`6g!^ez(YJqvExaK9Zyp1c#>kr zlN39iq}cH!#nxZ*ne#6TE_SqaF=gSbI(k{=>A0$G{Xj2Bz3C zFvX66DRvA@v14G09RpMB7?@(mz!W`s;Nq71JrZR}+)kCtaXZD1 z+bMS3PO;;5iXFF8?6{p`$L$n5Zl~CBJH?LMDR$gWvEz1%9k)~LxSe9h?G*d{-hAf# z%YuuU@As~hg%};Yk5#$+4p!_~qhiMz6+70b*s(^%jx{QFtWmLJjfx#>RP0!zV#gX4 zJJzV!u|~y?H7a(jQL*2L&u7lREV%DAc+Y~e5Fe&z52l#&FT_U`J3gw|@lnN&k1BS2 zRI%fuiX9(S?D(i+$43=AKC0O9QN@mrDt3HSvE!qP9UoQf{iFHJ`IiOvtq||)&C)In zbN+>xt}3Hrx{4jsRqU9qV#jn9JEp7HFsiy#_v}L= zcI;fSW9Nz;J6G)3xnjr86+3pW*s*iPj-4xZ>|C*9=ZYOWSM1oiV#m%EJ9h4H&EVTJ zpGWrXA)WYm3*!4+_Onu+8|M5A@qSfC$NLpK-mlp4e#MUWD|WnJvE%)U9q(7{c)w!D z`xQIhuh{W^#g6wYcD!G)5|2CgT_Jt#z*o+I}+i><#RGu5={0lLPRYu1s7CT0< z*fEO5j!`^ZKg1{&J4UhCF^a{GQ7o?WFT^MoJ4UhCF^a{GQ7m?hVzFZsi|sEupE>`s z;J!;}pI*vB9Mqn7Ow42U=@mP!veGC7Tot(eNKe3 z5dV3~z6EvSGb3WhuNFIgwb=2i#g1PscKm8_oqr*Iwb=2i#g1PscKm9w<5!Cvzgq10 z)ndo57CU~mxbjc@>iNw1mj(ANV4ty~EW{qy9t`c`Ggd02V{VHbb6f0~+hWJu7CYv) z*fF=oj=3#%%x$q_Zi^jrTkM$IV#nMTJLb07F}KA&?>3(~|FYn|L+x{jlx5T~=U=oh zP8&H+xXSA|;bO-L7duY4nAl_N!SGwh2^Tv~xY%*Rhiis7;bO-L7duY4*m1(ejuS3+ zoN%$vht6ltzbv?Kp!*CjWf?Wh`4?iFtBiaXi#-_X*|E*Vj%_Y>Y;&<=n~NRWT=RFT`Ufy>mQvvE#9e z9gkh?c|)1b7dsxixb)YUJs9%bFy~*0 zML_z{tY1$086r7J=BY2*i#>Aa*PQv11X49g9HhSOj9n zg_zHre<6lE>78T9iycE=>=^Q5$B-A-`4?iyiycE=>=^RmI{!ipd9h>2iycE=>=^Q5 z$B-90hP>D@v2MhUbt87H8?j^Eh#l)j z>{vHq$GQj@2)AtbVa$^@|;=U+h@@V#n$iJ66BgvHHc1)i191;bZn-=t~WA z{$=cU<0Hq0;`)(eLx~+5O6=HBV#kIOJ2sTqv7y9{4JCGLD6wNhi5(kC?ATCZ$A%I+ zHk8_;_AJKiyO7U@Isd}<1xWAweF3q*FCg~!1;qZofY{#`5c~TAVt-#i?C%SR{e1zk zzb_#6_XWiMzJS=@7ZCgV0^%yiIQvHpbN*%Qy`+(2sd4?tvDCzlr6zVPHL+u{x1I$5InJmYUeH)WnXZCUz_}v16%;9ZOAI{foGE^O^H6d=r86&fi23`o zoX?zp;X4kbcm9rp*xzvw`#TO|f5$=W?>LD49S5<$;~@5T9K`;PgV^735c@k0Vt>a$ z?C&^;{T&A}vB%hhAO%g-uc@TVt;!=>~Bwq{p|^{zdbQr zGkkkO>~Bwq{p|^{zda%LwzawyoH)ZN-jlD|T#Kv18kc9otsy*tX(Y@AHj}`ONtj zzL!CI=kH~R{k;sazn3BQ_cFx(UWVA;%Mkl}8Df7gL+tNmi2c0`vA>rg_V+Tx{$7UI z-^&maZ;U+{^4u`zUncg28#xv<*NhwsTI^WRV#k6OI~KIqv7p6{1wHT(3tH@0&|=4e z7CRQS*s-9+js-1tENHP~bkAqbzwnI@(mQ|SL+o#Si2aQZvA^*l_BTGn{>F#c-}n&w z8y{kS<3sFke2D#x53#@TA@(;u#Qw&I*zwZmGv{9>?7`3$j-4)c>~yhXr;8msUF_KD zV#iJwJ9fI*vD3wloi29lbg^Tniyb>%?AYmI$4(d5e#?Y?7xLUN=U@0P3F)1`OCt7n zNyPpxiP+yI5&OF&VtSH>*7_bG@op%uzcnECw+6)i)_~aG8W8(i17d$`Krl-x?76 zTLWT$Ye4L84T#I{eZsyAHXGJ=IN5`tUHA?sdoVEH;bad6<~yA1!N7cnlRX%i?{KmQ z1M?kD_F!PX!^s{D%y&51gMsV(%Y;1`xb|Kq?7_f%hm$=RnD2112LtmRPWE76zQf5L z3|!|CChWn?V||O#XA|@-O5#J+HTo7M@u6V8MM-=pm~T-M9}4DMl*EUEi3>%1D7elh zOo$H!^DRo^L&1EDlK4BLh_Fd*N z=U*o5!Bl$3w?o;3f%$eQdoVDu$Jm2``F1FKFfiW^We)}>_85CGFy9Vk4+bXo7<(`< z-wtID2IkwL?7_f%JCr>bm~V%&2Lto%Q1)P8z8%UQ4D7PZ=aI`o`p9JwyDVatMeMSO zT^6y+LOw?>i`ZpZLb}T$c3GyRyDVatMeMSOT^6zX*ofaY%>LelJ(x=8{L6$r7?|&! zvIhgZkBQyK#O`Ba_c5{inAm+x>^>%T9}~NeiQUJw@0WF6^NcBr*E!;a_>Gw6dvjg$9lETsRj!5py_M#> zfnD=G!Or?lWwgE<%3I%_W&eQoT`1o!X}pRm#P;Soy9hZ2w8IeI~^VG5&d#YnpOZdG)PX%4pwR zmCOFR;)NJXy!vOC{#pH28j>>FZ(QZFuef+2#^tVgrq4W6^G~1oXK9LYUC)ai4N2S8 zbEHQ@!b?-U=z8w=Xh_Oc>wz8(2`^2tmuvmjqai6*t?PO;B)l}mF|KuZkA|dNwLb6B zkg(6FiWhoJ;L=k)8j^CA&g#*Su+K+}eI{DG5aa7snR+xN<*KswXh?Wzid9>Ea~2Ir zxvJ03q9Ng>Deh~{F|%k$%2jjEEE*DaOcJr+Si-x3JwKktcL&A~F{YXIl*(nDCFYz;&UY;I_+Zw>Dwp-L zcxj5Y<@X!2JUjf}L%cM_t@3*+mCNt1#7k2QD8Fx1x%?hdyfnpA@_S>I%kPuLOH*tj zzyDXcye}YLn&SL;A4lc#{*HKQikaj6IF-x$bmFBc{*3okRW7tL8j|P8(iF?Z`{OE? z_szviQ(P4LIjCIre-JNCF-GjKqH@`fMcl;hSn%;W?02Mc*&j*V#KBnbu`ldDrgGV@ zOx(njSnzQq><6fF**{R+#AjIWF&XU7DLrLBPw~n+?)+x@aMsOZbjwtc@}YV&U(S0t;Tl@ z4aqtjpE5KgyfmFt_Bk@`JhNO&3)0yAWQj_e*;p2&hR2lzzmUh9PpLMykuj=xS zDC08qzneB!9KY^u`+jS*?f2H!`sXEEJbHY|O+)Opn>Igc{JbwMQu=3)K6`xWMpvkx z*T3WXZ*l#7QrC&=ca!?Pxa>{JuKG;fXL7)rixzWVrz;P>eoVUUh;3i&`-+{P3D-NH zV&`9cz?yH_l>2cF_ve1TzUO{0`Q?5v<=}oW<>P)Z<>r1c^}+pM>WTZo)ZZ>o|K+Al zy2|V8d(v%3Z2My0SM2=Eay|9O?_uX({M1v{=xMVfcerr$ix;onufF$rGw?@$vO>S{ zZhMU2qxbl8_taAk6CbkqPrJ|W*oo`kuKrtGfA8u#as95V-;eoi*_)PKan<4Cx?j>~ zlFof{J@<(n?i2g`oBQ(jG5dBxm^dL*6uP>-$0nS6!N~)hyuryc?6&J+x1E?eCQrUz_k&YcaOx0F-NJ6W4tCp#%bwbZblR@& z_aWHnGtKoQ*mlIWFZO-K&X3q_H|Dp_zc_u;>9n2FT@PZ{PwcDDbG_?R>8@w7>t9Sg zaX+qa+biu@>0NV;`U`m_y|KwX=_g8e+liaJbxoc-w;lQKnlh43+bO-Nldh>N-G@5m zw@uxWAGI;*ZaZCrJ(scU4C9V#oKBz2^&Mz(`YRyo6fVGL%5-`tj zo{_NE3}UYt#9lLqy=Iu@daoJ8UNeYkJD%lSlV`54*RvSTGaAmb8_qKw&a)oQ8UXg1 zfqq+d)|;*Soz$d{n(N1K)*f)yB(U$RYn-16>0UF4oqutyO-`a7xyI$q^{ny4t{<`M zP4-=%$q#EhvFl&#c2WM@_6pY;hVo|Zmv&_Bly)4$ZbxzMOM3D%*wI>)HCx(IoN|%w zHEq&atL6Hv{nCy~Pkr*+)H9s=hux0Ko7++OuX4>Ede+NX`^~j)b3N<2*b&>l*!LBu zUvYi2_M7X6q`MtwVV75&{!F^tQR%L?+&63W)U(pvj$*eXYu6ETSoP1Pdad%f{npg{ z`Q-gxIeNus))Jp^+2ckhK7YM2edxC@dBEs92X3VF@7`|R(W;-`MClK@{HB@5UbUt8 z-D`ehX6tM3uWK%y{mjh04jPFc{+(lIu6)lI&x-@PwY;4l{fJ#};<_*Onfy@CVt$u=VlVk` z+pESxwcW73{b%->Jky!Cy#~-6n`b)dd8Wg8ro(xr!+EB|d8WfvCh0q;>zVHB^-PEJ zOozP|QXcY5Cq2(}IL~xA&vf`__q*fx5zjk+X73tnTOP3H_|J!aeTK32^L5u5KYq!# zW*BP+-f@HR%laS8FxDY+uXNB>14m?)&&wuRCMkkGW*?-tJ_Z{!Q>zic%#xqwPulni5 zvj2$-FBvU&&(mdp`{mafKlZAR$^LKObj9eRYtEMam9AfZy!Ex8mHpGk*Ns-%|2)~p zHus=T)_>OB$6FuN$$s~hn?@J@+c#w&+uVctdHXfXj?bR{Q1)fJ?m_*mcc&G{-(T@E z*~d2bpnj+u>InN6EM9&5{MD|LeQa|N>W8|ajP+=Ke3Zm1*d)3&rR_Ng1{2>Y}xZH#^DhC0GNZA%+tpZ-NZ!#;IG9buogrH!#q zzoY+QpSGoqu}>eQFJhmzrH!#qf23bxpLvz>kA2#fHpV`ElRk=lu6boWOR!Jhq>o~s zvBq-+`}9rvDE7IYXN>bdP5$Yd^ik|{4bL9uf13Q0&U485pC`|Ec=# zQvcO|y7Zr_|1R}k{ijR+ss7)k|5yEYssHLfUHVV;|1SN%`cIesQ~keVjJf}G=|9!~ zyY&CE-DUh%|LM|ys{eQC|7E+&_^tlmrT>@hF5|cQf0zDWw!4hqs+%tJPxb#U{l9E? z8NXFGedeFC-Dmt(-SnA%%66aeTXoZC{;9U@GiR3VKI6CQrqBFSZQE!5th(tl|5V%d znLn#;`piGowteQ$>YIJ$@T!|W^G~&HpZT-;W}mse+P2U9S$(t5JYQ|wXa20d*=NqL zvDMQr8DG`5edf>Vn|YIJ$ z{~BBRE#u4ipAPfSmP%)QIsen4|J+|T8DGx-6#K6KZkT^Y`Yq$j`JZCn_1`u5pJLzj z-!=K4V&C=OVc-2n_MQI@`>y{E`|dxo@A~hs@BSnEuKy1E?mx2c{xAEkf7y5ck$v}n z*?0euefNLacmI)n_kY><_?3P4AK7>Rmwk_4*?0e!eUD$+cmJ1tk6+pM{3HAB|FZA# zEBl^*dg|Zfx2JwQ|Mb+q$8S&lc>d|Bf6t#i?d$Q|Q~#cSdg|Zvr|f(Fk$umfvR`A1 z`A7CWf69K1E#`mO_xvOKoxbl@=Wptt^+WQ{^EdU+`a${k`bYi8&)?KP z>j&lE>z~v=>j&BQ`X}|z`a$-+{*isJ-(=tG2if=fNA|sbQ~&q+NA|sbQ~&q+NA|sb z%lKveDf?dk$iCNa8NaMQW#8*J+4uTW_Pu_SeV&bsG0#7&5oO=&H`(Xe$Qbkd!}>Yn zm-T1nAJ)$qzpOtq|FC|Reby$7G1`}BBV&y5#j~9;hJDs1j4}Er&vwR`=TFxEvd^=f zG3NP`^}p=1wqlH7pJzK`%=0Jff7xek#TdgrYZJy8_E}po#^|4{O&DX?XKlq8qkdSA zFs`u4dWvyHo>@aNmaxORiSeVn4H`t(pK*_sC-iAF?4c{JIQih7XG)(QaMrSu^PaYY zH0%qOyKa2OJ^n-dp!tKGz?_um=7p~{zCfv{IUDE6NKG&C> zK6c7}AN%!hpZnI|`{bv7H=BHxz1ify?o)fC&)JlFIlWUJhUlJn*r(pal#ly4Kh(3>^)IHLs$9x{+g|7GyQyhWm^Td&s&< zKWgPikG}S+fsc9YOGm$4cRi&)WRJJZy+=h;=Y1WV_js`1qxP`hql)uBko3GKg!BFo z&U;0ee!}}rr}G|FocEKY=e;GI_nC0sbHaX)syz5Ts@U&QyTQ)V|33Vm*-!qk{mPRK zpL5RW!0MAfdeW+sCq4ViqqkL`-1SMTPrkVAc_aGdMqAYPZqB)2M4vpnTXVAFpT9n$ zPd;V&wI&-y9uTeRA0ktUY@mjvl7m*7eDaisjCKp`4=NS8ke{r?R$=`U?82iirsO;Zy<3Ep|ap+;P z|IqUzuhdty-+5gtN7frtQt0QH9 zr4M{>y!+|@CHoKf)epxHecNfWf8nw}9slgEo$UYH#XlcE`wg?Q|J?^)I$ri&r_26P zdt5f&b>>XjKl;nR8o%y!XUYD1yUWM-f9Tn=k8SQj{a~AWP(Rq_9@G!Exd-)wZSFz+ zV4HhTKiK9T)DO0~2lYeUP)FFOZm1*dQ#aJnFz38)OdSn#&ilvI(J<#6F{X}&Ip@eR zb%cHDhC0GNZA%+tpSGoqu}|C5#@MHAX=CiuwzM(!XjD6acHpV`ElRk=l z`X+r8`}9rvDE8@_^ik~7H|e9;r*G0nu}|Nmk7A#`Ngu^N&r-%4_F?8_?8D5<*oT>y zu@5sZV;^Q-#y-rvjD47S+4=99{C7?MyC(l#lmD*Cf7j%{Yx3VE|5g8eQ~!Na|9w;c zeN+E^Q~!Na|9w;ced@pZPv7*PzUe=G(|`J=|MX4&>6`x3H~pti|Ed1pH~qhF`hVZ_ z|Gw$}ebfK@rvLX%|L@cP%XZ(4-@X~YeKUUhX8iWe`0bnV+c)F4&-ksn>6`hdZ|0xA znSc6b{+Vs&pV?;qnQi8u*~~xHwzJLrIor&iv(5ZD+svP{&HOpr%%8K({5hNXv-;+2 zGyl&v^Z#r!|Iaq_|7!Vg6ZNJj_39%rZ_GUp2PG!~CL{~h*gY?1#C`!%-6e~0}VTjamPevK{i z-(kPT7Wwb6@A~htUt^2<@3CKFi~8@eUt^2<@3CKFi~8@eUt^2<@3CKFi~8@eUt^2< z@3HUxBl|VB=s&VwV~hSH`!%-cKeAtAi~b|~HMZzKvR`A1{v-P}w&*{y@BT0QHMZ#g zvR`A1{xADAw&?$|Ut^2@FZ(sN=>M``V~hST`!%-c|FZA#EBn~y9@G!Exd-)wZSFz+ zV4HhTKiK9T)DO0~2laz(?m_){{*is^hB_Mh&tc3zvQOPmM??R4Kl9J*(0`6#{+S*6 z&ymbOvqS$mlKE#A`<_2%XPL(#F`QZE0id z*VtnImwoyseH8ojP5LPI>6`RX?9(^tqu8f!(nqmR-=vRXpT0>S#s0}hpK}spjQrQW z@rUdACHrWcdVa}1>5MV#lU~m+*(bf8U$RenJ-=ihuIE?suQ7&wKYx>dp1;XI&)?*q z=Wp__G3NYhj5+@rW3GSJ52=6F52=6F52=6F52=6F53`ihtxmo2j$=EpY$Kr zKj}ZLf6{+g|D^x0{*is==BEF!{*isJe`Me5xAcG3Z|VQ6-_rkCzoq}PeoOyn{g(dE z`YrvR^;^a->rdI|+1QL<)}OM^v#}Y!tUoh;S$}5yvi{8YW&J7pJlh##v@g&0X8vLQ zEc-m$oB4K9OF}Wcj_r zm9G2wdig%V*6jMNHGA$Wzjv;&W>>m3yV#mt`KSJOo)!RWq? zAI_Z5E!W^9#Q6o-emhH@A9eO;%U`Z5e>v@M)_d}<*?aAp{nm~>ANp3k1D~?bgI=h2 z;8XT?YK^kE{N<+QFQ@eKmz$QqoVfhuruda{O}&quHvVSQ#t&`U_@_-9zqP6T%6Mm6 zcIN!truHjSI{s_eBmel7@!ptn zjcaX}a>d^)*YnOlcEpX}TJAd@>?l9t#{Vt(S9;aorrgiviXUC-A$H<-mwHpW>ofVm z4^Zs-7rR}=ZF~JQ`-%7T@hj`L{HyOl*Z3QBjgJBTFY%G+8oz>R;}_92eg)IUFQRMw z3Z{);1U@gF{W|b@iC@9A@r#%?ejT0nGUgDR6&rAFwrj1|6 zwDC*9=cTt_$F%WF(VnyYI;M?Z3bx}{gU?I+I;M?Z%GCSvBgT8xoci&;yzF~lUi}~2HO7>G@5{@+_vO|9@mb>@ z?*H+tWcQ&TO2%*eLN&HB|9D?s_PsAJ`}o{ZM;^cN3uXR^U#oo9xCixv&mF!C zw6FK&m4ENcj~HLxmzRC-%ges^ZPX|l@yo^MCBDQp|ExKtU($cPM=$%{qsOnf`p=yIKl6Y5ifjH^ zZ_K&{``)|9uej!)jbyXQKYj)Bd8CgH^UvIQf#e^*g6cn8md!Rm;J`CBmH0Y8^4b9f7xej@rC(>vwo9(uRk;Y;1`|oi(ho+AN-;-ep!EJ{=qL=_Gw%Dm1X^@ z`OWKR+4uTi_Pu_VecF~bX8hu_$r_RT)3&S;J^$kut@+>U=ggn@Ma#amiROQ=|7G7g zMf1Pc|FUn*f?rwI{IW@Zv|ky%`S?F;p0_p`=Jr8@=z9F2cz&S)8^5e+gpt--BR&3RQ~O`(8v9?#4t`|#UGZD{Uy1QM<2u>= ztN$DMk6&EnXXT0g%97qS*Y~jPh#UVd$`!va%7wq2u4(+ll7D>0rnPUfsr|}QUZuMp z#I7INalPff_{)i1&tliV*zKbHx9ycZ*77Txvj0OnmS5SF{U7G3AO7I{Df>UHC29|7 z%Ki^rdrTesKU`mXG#&dtq?cb=$Nmq$Ex)p^{K}MGer3E={-a$-ejH zWuHC6s-wv;=V)JkGR!&Jm!DAo>>09mNc}f{O;hj7PiSB7%TH)u@5@hUU+>GyzW3#2 z-}~~i?|pgM_rCmu`tiQJ?0a8c_PsAJ``(wAeecW5K6{4t%j&!@FZ;}0HQr<&wqKdn ztM)4s+pkP)zcRf)v0s_ker00&m38>+u=nZw$1iSL`Hx@RwDKRnxG7_+##r*tzI^h} zzP##(v1Pw9>OX#c)PMZ?sQ>u&QUCGlqyFR9*Lhz)^&h{!uIfL2eVzB^(|_WZSkJ6E zzr=cG&G{wPGi%N-v7T9Teu?$Wn)6Gf|HLn`^S*rgfBY(^)&JvHIj#O5zshO#|M*pQ z)&JvH*;W6KUu9SQKYo=RK5N{A`uDzk#&7&Wr{0&(_>Es^SK~K+pge&ZL) z{1d-c=AZbrP8nO&5&hr$^0Lp^qK+6}-j~n(6TjBZ`|=vU-j`SYy)Uo)*Zdj3T;|XC zW8sayouL5N+0H*b#%SgJW3ztpTU=&`KR$KNdECF zOaAdINdECFNdECFNd7zQGq#u`{QQbv0ne}aMezKJUj)yu_(i1tdq2P87s2yuV!sHU zU-64b{r7%;#jhj%rzijJKYi1GWZ(U#Z~9M9{_FV_zmD`D*?0f%oBl8R_56xoO8UR- z*YhiWDe3>R@BZIYKkoms@9``9_56xoO~$YC@9``99>2=J$FJ;r{K~$^uk1H|LDhfc z7p?qz{*ispKeF%nXLjg6bACaYe`fvsV*bG|DDx+NO_@LOYs&nIUsL8!{F*X<%D(5% zS?a%@U-4_o{3-jM|7E}N%gX#O`=0-0-}Arhv$nEdS;yG2Um4G@_+@oy8P<#BzsAsJ z_A8Udv0s_ker00&mFc(kE338cqRs4ACbnN0&o9PU@*lrA@*lrAo?r2cs$@43Il{~-VSIP4$ew94G z;#bM@3%}@$-}r@2z5Z1H_xdyAH-4dv-}r^{{EA;F<2QbxSwG9Z*Uy=M;@8UaD}Jq0 zub(sj#IKe4Cw{HWKk;kL`d{|F{+E5P|CN8Q|CN8Q|7G9nf6WhG|7(8m`d{+{eUm;) z|F?e0{2#yK=$Fj@@hfKjk6$tKfBcH0U+^pICKs;MKX;o|${%UN$ypn((SPRDb;Q?w zb>057Q#TZ!aqPzZq04VPq(5h~ezRlO7aw=cR{f!euPHuv`TO^it#2>>`s*Il@BOB$ zDt7CJlV5Hz?pHeQZ1K)l?AU+x7l(_tJ#LqN%_r?4Ug-hl?|RLW?YaK=<96#$d+(c1 zgU|WFuKls6-?#*R+%-G*pZvyirts}A-=Tl;Zx@S~{pn19z}gpyH~;On{o2d?QGAa* z?%Qwlkd->F-*?3=`8PZQZ>UZ7yUwDZ4v>R^h z)_C1%;vIjtO#kO~ej7_oZjNN$FqM;PP&K%^k%jZhKjG&bxlO9oJm^ zqszKiUHs`K{C2d;mEGgN^ROwr+Q)y>?ftH!#YesS`tHczT_E1MTc$tht~Y33cb|9N zzW>(GS5-NGyvnNme?4mh@%>j?tG|5fO~rqHi zzpMC!cixwBi4Xq511Xny%Z-m%?iyNtp2 zeC;mVzi#U_`VG!qX9U0YvUU4AoU@_$imzZ~uX*Num|Hr2`>Ex(pj-n#{O*)XyvqwVpj_hLy>BhbCBAZ*)hL(v z;g{Tja*0oV;j)xV_SbvMpSmiS_*LuuzN>PHH@@(iuF568=S5d_RjwuE;nMqG)m6E+ zgYW$3Uw2im8KrM@U03B2-{n=;cU3O&Gr#|ruF56eahc^Qm$+@OwjJ+&$a4Ls_x;NZ zZF;9K-O@esx!)JxZT!dX7vK1V_@c9a(>>>=my2J1$W`5`-(5+3UVlaR;LCrw9lyPP zpDVk|pZn1z@J27Zy1VmZcA3I&y5P6nhZY?!-toydb;s>}j`$J3zFoiXsaK1?|AssC zYyJ8T9oHYQq{iTn))IekzqR@o?Xi(~_h)R-pLOM3#gBaU-TN1O>@MQXci5ue=skB9 zzjMib=%3;hPuiAp$^MBK&h%9-@%n4+*jKs4yFPlCzRD%O?uEPcRW9+lkKMhma-Bwg zKD}u7zRI<|%JuqP`zqHAeAW3o^;ItMD$7s$Dwp`DyKhIi#Cv`2{*-IP_5G{1rd;B~ z&fSc1i7&foW6CA|$=BAUT;k<^e@DtCe%)s`?zcQ|?a}_59M>Jb)q4H)$FC*6-T74;L`5x9h+2)bqsm|IJO^;XgS+eBe{>+~4b? zD~*14%~9PI7u~7<&wJi7bH;NI?>_eV)%p#7botCy8@|8$%epJ|PkZ0DXD&PQ{oRw^ zvV8x_1J9cI%8f^Kuifu<{r*q;%*+Sx_Q7t2SKqGx)wz$=T(RmpEB6PU{w(pmc3iuE z?FIXb_xz@ME|9u)(~H~(q8@k%lugL+izERLci;J?-4)X5l`&bp8RQho&|q8>xum?Yi^=v z!N*^)cYo-WkDM|Gp7pTD^)Gtf=f!V-!=w7AZ@x^&^$*?hq5T6Mc(;yg_ITsY{p$Np z#G5SHj&g}N-taz@OMJ_3H>F(S3*NOp8f1ftIt2Xt8%F!DwnuzubW=;mu}P5pD}vksRt}+ z`F9upx;u2ohbsMZ2mh#h|6W^(Z(i%d?oan!LHzPxoYSrTy)$R{?TdE$V)wa=pDcde zGrR8fkGR+Nq+k2AzB}-Z%TM7A?|o)>(cL~E{=mn++I{IqSBjtg-fwpYOxN$Y=H~}r z+FiTXNc^97{$sb#%oD_G{bad*|KndMK5xI(``2CaO7W%7TEBnV@vj%J`jXB1SDgG> z@uMcSj#}ZR;!hqp(^nbApZW5xeU(f6&8r{YSGmNWIAyQC$|b(`jJ^9Rm-6<9HJ;K} zxx`n$X`jBzwS;_rZrOeMD%T9W(a}%pt6bur?DP1($|b(>`H$+WTqCaOuHK`sa)}?e z*^YgcOT6ymwxwL+XPmnw);oQ@+yC$##5bIAe)r9* z*V&%A;ycG&&@FfHx8| zuX2f>v(5b}mw5kWx1e0&uN`<7$|e5x#cNY8@v~pF3gr^F?Uk{%@tL)E<}nDTec`k_ zoc;i(pTOxqaQYRT{syNX!s(xI`YoLP45y#N>Hl!X1)T8$XB@#9UvS19obd=}oWdEu zaK<&9@eXGmfHOb9nK$6fCvfH&IP(vjc?r&Z1!o?EGrz%^_u$Nj@NMn&`s$ktv%S)G z%*km}&F8m0GF{IuQQ^W9y$hPiFc`LDm` zZ1w(8AO1u4xG%g^Yu&$Ga$WcO-8U9ra{6z&yBz*5t&I=b{Wslzt@**zSOXvR%4@p^ zob^4epC9$8-*xM(wd<7hXZP24r~lVG#ec8&5;s0}hrVnoKhN8D)Nl8dPm4b{`=I`d zzxt+l@msd(@BNr-#n1Zcz5A{1J-qAq(?_@Hf4JkST4R5HmreT%wy5uRS3ci69ryLF zV+y}wcE|n>H#}Q>>1TKDe>SUaM619Y!X zy>SEHy>!@F?ap`WuUli_Lyo>jzr*rtDE;HV+NvLQD~dP#>3#dHx?5!bHP6|$-||tH ziZ6Nk_WirQdX9L%b8hLbI{WkDr+jTu|H|EdEZ+6z75ZPUe6#rQuddd=<*=1x^Fhn6 z-H)EPrnuGbx4m!q*MHyAzCXWhzvEwjzoQ-RU%2?Lyd&*+N4m>1?!i0KDep+%{MxN} zM>^#l>DKGtmv^L7-jROulMmn>>6CY*pFVdx-jPmuN7~Lsf3G>DwYl4$$NiF{o-rk# zC+;-qf3(h@mXOakym8XsZtL4GA)hZeZPMR!`8~ELpWnN7(*O90%jsS2gE!fsf8Ra! z)Vthv9{zusGg~_!+G+d#mbaZWL*5R&VVnMs&pci4neVjGefp!<`JUc0@AZW(`$Y#{ zqxZ}kKII<$%O1V#h&uel%kSR*aJyAT)M5Lq`FlMh+UMhi``y%49V(w|U2-PEhk9g+3h+AC9^>XYAp&Fa*r`sC{0y%Y7>QJ-(@*QGu?>a*?V|1Zy@ly}dqmY=f; zr+>of4{+KMPW{8l58VDX%=0(bz<=+t$$i^=hPhXphrjn&2qcZ+@$5uv5BJXKcyS*FSY<@h#_lZ@T}7hjYZ=edFW1eeQ7w zrJr7Le%4#>H~Q_TkN-+n{})$U`M3<}`=jQ*RX=n288`VH zH~FtvIGdcry{OBkyj(vbz3xezCUMZLo99h~L22sQinu-SlVm0j?SP z!{787)s_3O><|3czCm8;pZp&CFlFMtFl8k_Fm*saVd{pw!qge%f~iaL3RB1A6;9p5 zY4@aak6h0^VC--Y82kJmCXK(rT+2ORY;X^l{BsXD?e287yRTQf!{oiOuXZQB($wxS zb~Gd^U2&i zQ|)!zcu%|2_o;vS7Mym6)9x^1g1!Z(-C^pIex7vN4CZ?70b_@Iz}V;iaM~T_T7Cnk z-C=CE?FG{}_*=_OKe=uER{f+MsjIXjoOXoMj&RyB>HmoFyV||pxx?KLS$neaI#j#N_{OuN|0j-T(0eQ{JRg54oQDi5==K z_NmX@mwHZqsQ=`Xc1ix9x5FxP?RCaFt4wBZ7~1YHC#*bq^~FQmec@*-O-}yMua(a; zf4Ji0mVJhHT{Ks+ZpZx0Ik8|H82mE%N{A~G~YsbmwDT}ThC;v}8 z^*3|vMfw}Jxk7p1`m^^Q+73HMzT;O)$Nml%4(-T&pLOqn$(!ddT(EPwY@{u}^*GzSMK_L;WY8v`g~8w3aLV@Z%SLc!!j6KBs+2 zPrJkE4{-Vkoc;r+U%}~baQY#f{t2hw!s*X&`Z=8b4`*D!882|g5uEV_x8+Uy=6c#4 zPJe*YPvG<)IQj60H1UTylIO_^H>kYVF zhotT3t0^y>dVo_uaOw?CeZr|{IQ0*wUEs7AoOXoMzHr(dPJe*YPvG<)IQT~N^#G@S;M5zO`h-)@aOxjUyTD6hKcrll z|KZG^aOPDw^DUft7|#3*XWoW0pTn8wVcLuJB%J30oaY6c=LnqV3!LW;oaYgo=M20&${OHGZ&HMLx>+H!N z9QXyNzGe1^7Y%&EI&Ya>wCTXh9emL2=4X6N*I%*9L9?suKJcm^ee>*#KmSpszh>Vz z&z`d0z%RW2n`dA5;*ThOhfUr*yXx7eh)F+g?SZ-ez!#mYbnH~yh_S!g&I5Db-+k#M zrIVlao;fi2eCv7xlmC}rwOH3su7~_+;Fo^kZFA|z?ECh)>z{M;+vn^o`>ubVv%k?D z4xYR34KF-+EW%xRKFLq&nS7@H z$$#1c-W#n5&_}qPu*r<>gVD`15Hd7}pQ^qzu z*Qe~%57!^J-@RwkXW+ZN;^Z-H`oiaZWs-C_>A4;|xhBjtaO{L@UuaA{bNzg#-*P?a z;r3py`}RrWtE&%l&7F5#JihpS1K-r2IR5rK2L8|!PZ;0lbpwBU{o}{m?KklAS3YjM z&)x&Cc)w%E>+C%6`iC7e{{1}%e#d=|86UFxz{x{f-sG9Q!MPre9XR&k+!s!M;N%ld z{^67hZp)jxqU_r~=$JA66MovKjv3QG;rG7m*fISR{?Y4?8`D4GP0u}kO#g&myvvDW z`X{{2uRb)Uf5MATIcZG)gwuB9A@_yb^juGR?7*=P=e}_A11Fzw@(;J=%6KF{aOyni zT%UBVp?{{2Wvr2&F$iaD!Wpx0#xk5S4rlDcnG@hP54mshlfIqnNsk>k_Tk(YPJZCz z6Hfl&wp?x5GY==v%+GM%492w$J|~`}R(6|Lgo8 zW=z4EAK=UzaOM*@^9-E%2hO|%Z{v9n&O8REU%}~baK;^+@d#&}!WqAC#xHk&K54x8h=C7%)Z+2S-ZStP-#&5tleZ6i z-78NRzv0ybziFrA$3J<#`GLocpZ9q4(~lj$Z^wbpKKq#Q)te7|k7pkbME!={f-$YegB^yGtTv=o_Opyc0P9U zapTy3#^uM4bKf6FBn;ocRQ%yjhcEJ|R8x37q)^&U^xA zK7lizz?o0r%qMW>6FBopIBV%VPxIS<)H(tCjO)~M`W5NvS8)0joPGtTU%}~DaQYQI zzhBXZNzZ%&XAXfghrpRb;LIU#<`6h@h}d(8*mDS+IRwre0%s0^Gl#&LLtw@ua|oO{ z1kM}+XAXfghrpRb;LIU#<`6h@NUq5k%p5{`<`6h@2%I?t&Kv?~4uNlN4r%Y3xrOVK zo;fyi&Ods7``@S&%A5OA-uayInDktq=RWD-^cn1=&%o(3aQY0KJ_D!E!09t^`V9QP z)mL-hHV<$+W^)boll1l)IO7`5xP~*X;f!lI<68VbTpRo=%q__S`Jd03Z<9{F!C6wlFpi> z<@Wt#%hX}oBJY!Y4P^Kb&@f(_V1e5l;KUX?HmN0Zu=GGZtvCmU9j1`7Ioq zaP9>s4{-7ZC(m%o0;h~=3&v^M=pXqWz8&K&XMIkcWPJ{2eGX@R4rhH1XMGN5eGX@R z4rhH%*)x7gZ#iR}^o)Hta{`>X0?r%)XKsNr=fIhZ;C3EsIoFW4{1%Q)IQN2+2RM0y zlV><(p-t20;mj4}C+W%C{BePuT%UfDd4u|dlb(4#^^DDo>s-Tl54ZDD_MX_cVlO89 zbm98l+M|Z~G6| zw7;Ey4Zppu{|tR;q4b}&y~1rf!kGu)%mZ-d0XXvjoOuAwJOF1NfHM!knFrv^190X6 zIP(CUc>vBl0B0V6GY`O-2jI*DNncv#`Q}`?&lI2E#7Q_`XHNe%w!mD>0j{qz+PR)M z1Ak@Cs`~7C2NUaih;?v2-x@Feo8RghpIZ;>oV#rnbFMkR9nQSlj?UHAZ@E5snD^Vc zJYz@KlP4IP1OLr$=WKFDl)v*o&W`dgXM&q^yE-pVdaX@4x31rEwzxU}tMl?)Q|D53 zULGzReRGbuukzfT^tvbMId{zUU9RUIFm|{HT=(R@V$%2<>0HY_U~E+W#n|Q^q*I4Y zy3Wh{dYzYt%MRz4WB-4AZo0n5w0N-dk3Tov^k?+}?mP62zv(k7i~HNi*K}>)pxx6q zXm>d64pX0;F^1FbaM~TF&Zs*$?GC5iVd|cChtuv!=N`G9d%$UTIPDIn-C?ff9&p+n zPP@Ztcc(i}g05G)lTO~b2VC|YCqeghoCM`Z_u!hkr|tn$XSDlZCvg&n^vaX!gzKC7 z(LK1n?#X?14fk#8S?A@s1{+PgI8MU`{nS<)Y{Lp`)}5$#TY;D6ZX-?TeS zeUcxTdM2N6+8w6OC>NY|htuwG+8s{2C!Kr1T+cn=v^$J_{tu_!;s3+ldq8JZ>}}sb zD(L|!id{G=sGuTB?t2f22vP+EgoEu-dhaMjdhaA8Bq5jvA&CizNf5Z>AXd8cq97JZ zD2FZ`{r2_0_ciB!T+h4K`+e(se0|=t3VCoL0 z?oRsu`0?(m7Z{qNZNBVtoyffHTt9cluiaO;mT|41PcR;Ft$@*If93c+J1bkiS?`7w zoHI>VXp^l=zPN6ESa+JPR5M!-Zgbrl^6^ydS0!67xpmFDr^8fzJu+K=k#o(;x-vz$ z+wQHx2dZUj@ZR22b(^|g{^7t>UDnCViA|?z)P+2#3+3b#pRyXS?W-H!o2}n??v&+O z+D9ih&eq%4p0pOv=&d8hX6v+`v^wK-GX6q)0%B(?&J@u4&IePPiGOPTy9=c&> zjz0ZdnUzzkhn`k5S0A{2!s@cJyUzM3SMND=!kYV5cRliIuD*ZA39Dw4?)sH>AM3+g zPFNW)cp344H>}T<*#6bNyI%IJmjhF}>xT+*Bt5HI58a}nm#gR=x@ecTElpKGvTD=a`)B;E|=(Imrh#!Li*?`A*=PU*G^eCj`Y#> zqgNX(z=#=f&iD5+;;(R|MAFeNl#e_pe@t61qaTi)D3)~e4`N0h#Ju2NMZ)OM0srA; z^fUSadC>n4zniF^%ZpYGbBgu%s}psn(@|<)bcwD~BT2vWa+I3Uw?y}wkfeuhiBv_o zC3^QSNxIg^NY&zCiSE!cSx;&hsS2-`=)JkgdS3NN)i!jsw&!I%B|K80P0jC5)N$`e ztK|B{didETdQGEfHMOKjkJ-0GR|=0-uQe^wgSRiy0}e(h#05rd;3_|O8L_9AOO$l9 z>7wOjwDs|YUPd2$e$~t9nu8UqqU%v2RvZSMr5hv4F; zTwRLv)5l8m>2}fT>JLSF=9&_nKOtI`G%MDV$Ca3VL#%9X*Jp}!jNK2T?S2@ss7OEm zLZo{4Mu{#vSENG*M5;%BEYZDM6zl6Hk?P4$OZ3{5VqKw9l)5#wM3YeY4jdl{Rqbb@#tJY5<3qJ0)Ycszi>43vFDIP-ZMxpGp`wbuny$e}2Os`C zOLu4+s0KAo7DhVQTKci%dH9}r`g)5zy?D<-%U-Y1yE}OKi{Do1dk1*=ht~^q@DeW{ zD=N^h?DBHeph8{ko_zW3@wSEfl>uJ<$IL?g+9oeY7Z>V&byi89e{L_-r~`G?-(RRv z2N>z71C0Er1B`M|2N>n!A28DJ-@wR=-+)mD$^xTo)B#4FOh+utj~H1FVrThi6YE7= z84vn^aiVV+Kl+UALSM4INM}DFKl=yeu-{NV`x9yGXXIu7qYUbTvVHXe2lj|msDF-K z-~0BssPN<}?cYC7H?-%9Zd>zp+TuLD;An&zGbCTv-kzsdt&dRQ59I61mGgD(M-gh` z{ycrLd%hkuHA0-|F_RHY$#`qEvi^ea6hlzKf+_wBGs@B5Dk)uxTNyRDy$IE@eV*RdtU&i45TTy!m8WYhEzl#!MX1o(dAjsefqp$ULS6FY>G*nu zdP;tTT6HZ?pYKL+AIsNscNXexjU!cB zqgA?^t!b^kkt%5EDt&faq3#wNsUEquO1D~FsC#-MReJjZy>UUIe(C2(_2P;G-Q}%9 zecLZe{dlQBH-4~C7e5@OCcjXqqYo75GQ6sdr6=}@QXBRa>h1Tf(o4EWsZCo7_2#egwbeCB_57qzpBbF5 zS2vGRuGxjUUCn&`e!VEw{B`@f{V7jZy(>x`tX8PsU74p_UW!z+w-@MoWApU!?UAa% zxB@-s%{;v?D^iu!D$s}8=IPbbBGu17c(ta!zPj^zxHC?@WBl(pPRlj%&Vd-4RhxUc zVDl>dRA(;-`W5Is1HJsq^Y*;Dz{@Lp73isJy?lH@fo^@$%m4hOKtFoFcg`%gr9hAC z?B(j;7nu3y$s+|Cbzt5@I_dx;Kk5LZ9Ml0u`S=HnH2gO(^5QpOl!3CqC>wQv(JrPV z7UoBcEC;c(e6)%6qOFVveZV-;H;f;B#(5Qe$@U_h{eb-JAC$v>L;37aq_Llom;H}2 zs0+$|W77)Lt_HijjPW)8jF&O@_pO#CdEf~-?Y#`I7@g>4cu4LUFT-0(URf#m;W^uL zybLeG^8)%19#w0Emyxdadl~s(c{WG#pqvk;c^T!m*zRT2J2N=f#53H!&qtYv^RqTy zM*In#y^OwOI(&rr;V&!)zQgk2N32(T%83Ua#W>+nj309n+l9G`?L|8K0r}ZKD2M%q z^4XuLm;H=**#C%=x*&dEy}+C&&+S}ce6ZK)6~+hst7I7;oZBYL_~7fYS;hxD9nCU6 zSWB%mKG->KrSZXSJ69SXM0@FjjrwOBAFTIHw(-FkHFAs(-rqOJ_~5lwImQP&oX#;m zn0HUE@xi_BT;qf1+vOS`9Bpe#A8co9-OcgA{O59w57vpwH9qJ$oMU`2sDq!uX)CzP`Hidbl%Ay>r6fah$%l!8;#f{(1i!FJq2h zxYx^=`=3ASWq3kPq<5Z#SCqZrWq3$_Z)g6rJ!+PH?P0Ei=lrzS%kU!3Kk%r^ExmIo z()&#EGV;ItsWac&<%FK_GRkiesRS2iabvvmcP3{eyDYZz!MriF(=3h==`;IH?Qb z$M@&-_r&&I#`yZh{=S#~vd#XM1`Hnz-|1!e(c$W8k`A8=@9$;!SM`lvhOa$cJ6-a? z@7|d2W%%HX%l}SK?VKTbkU#emFQc480hy-!+%{fDy{D&p8S(7@#LMu(2e)|{@!#0% zW$49p_z3gEUsw)&hvmbMSTDvGFfvOXaAra_8ZD)f1+OY zGvZ!YgQt=*j1NvcnPGgeTis0KgC%`4jSog9Wf~uR zp)}L@;A=ZFjSn8SHKh+0ZOt@37*&#Kd~n|UOyh(1y_sozFyMhqg%gJuZKJ1)H}xij^p&3#@;y)^Un`2dl^1*siT+SFNp)Z z4BrW#?`8N=t2JJRPeqq`8P8b%vadb*V3ST>hTn1ife(({^zZbo<-Kz$d@!qlmr>5Z zo?b@zx%0h@dLJnCGUEAqla~?a;R9Zl_z!y-?P5B7g!$nwEC;^B^5I9U7e2*!;9rar zzQ*|BcWf7YknKe}`vLjcKPZR&hVt2;sF(eWc-a4lle!@Ohc+fk-=bYNcX%1&tLbSk z!(ZxEO_DtDox$zA3_ohL#LMu(!Kb|p{~FUgS@OfzVza#rAHWy$oMlzQ@b(LC!z$!Go`O=Tf9UHPOq+AF|q+Z|!n+9P={DkBId4 zA?lq}&&!DCu@+uNoQ=D98S!^|)5~ZV)8Qk`4}W1f@Ew*9KVrS`DaHf;Vw~_b#t*+^ zyWoRtFVfi$$j|;kIqWx-&;CTc>}SNo{zshD1@ZH}1D-)Kcf+T!=7+f(jI}__-C(R) z;+g|v?GSS}7;B1{yTMp%#M}+W8YJd!FxDo~cVMhpVhl4K9>)CeS}@9i=Ydf^ybz3f z;gMj(1MdVQPIxL9@$>y4+QoFNSu#J?ELjfLELlF*ELktsEEx~hEEy-(EEzx6sMs#7 zU9r7LXFni6`v>K)-%vjL6ZNv65fA$xaZ(q=@2eL$W^9;38|T>Cef(;e>i+Rcc|SOy zW|-2gR?7RquWp8_!}huz-Vgq=FH{X)mL=~8kE{+=zjn@&_k%f0Lsf@+v*i6?$jneR z;`|DEKR9+=s7l+nLf#Kn{2){nZ1uKx&Ztm@_Tv5EzR{s-^^O(telT@PsER+nLf#K% z$Azi^AzAW%aCT0p>g39j_k*8)9jc<=&yx3psQMA!7dZSRNore@_ulBPMDfDDqG$UChoHH?97(;gCnnnsmxkA z@_w*hjd1niupD_mc%osrI{vAB&Die;_q-Oa4qV8Q_k-tg@miKZF1!O;N8c=RN}2{c|TZjeVA&sJX_umo=OQ* zO}k}_*3{QmcU}*7#;JF_{~gCE=5EYI7@L^8!C3Rd+zrNBAm(l`)(A0ogRypqxf_f% zMaP}9dW`_ z!HA#l2hlF3W6hHJv1Z9~ux82fv1ZA7v1ZA5ux80Pv1ZBmv1ZA3VU3yXMLPQd`Pn}x zhy8}~*`KJF{fv0n|A>>iAbyT7JcDw4Va<>8FxCRi{A{mTa^A+;A?I_fDRQ32S|jIw ztU=Njur|qdVa<|0f^_-|^3!)v4*dw_)2C3c@h>|b`WoV--ywebAlk)rtXVQY)+|{L z)+|{*)+|{s)+`wh)+`w()+`x6)~MJntX;9aNM}DFKl=yeu-{NV`xEuDpAirHA8}F_ z#P6#YcwlTrg*L(mkMyjlzO9okKA7sNs2<#sCO&wzQbpBxaGLmF)w98B_kC&NgO#@j zt7iLB#Rq>Z3RcDTH~82mqf&#_fkCO_g9UNH%D=OH7N5OO###`pDz)~u_w#wd3hjjt zhAawJcehIwAKaZBtgiP+6(2mD8?1KN=W1e~jNTBe)~rhvA3S|1SPj3LDn3|rD_D(H zY2t$|9;~PW=B0@be%q{~3Okx6K3IQHMf*Jcbn(GCODd{uN$KK)U)X!Y%C4k~4{keY z=V_NAKA003q5_v^h!1vuCPZai%n%=}(LO}Acs^5nFt}fcat+B8ADl8iMEQM`DLxo7 zFGP)ApD8|Q#fPYEJ2S-x%MwD=bo;u650;A!QS&xuiVtQ^4^edrGsOq*9~q*`&&m`Z zJn~kE3h!)Rx3&+CYZ9V9s+uW2SolzgYPT&ze6Y>!it5&w4Dms0UqzK)GedmvzLJV+ z#rIyVsjsi@ydLh1Q?C#H9mgqs5Mz_`E!O-v4`VHm^E1{6Id5a_kn=g#6gkght&#IT z)*$H%SexYhbID$_q>mt-{(}7U9h5^qLizM5)Jy+DJoGihNxwt<^g*Y91)~Ow+GVFCbJP)=E2viMHlEep_9Scy|osz@{qqhX8YW9A1 z_~4LF160hpMDf92a|2Yby@}$3gR=tEh%MgsURoZY&|dhUl^vkQewQdd7*rIXx*bat zAB_4kKs{SANqq3)fdEw_CP{qofy)7E|Hvfq!4s7O)sfHa^+Nl3aNP5Os#kcj_~6Yq z?S0PgC5sRCo))M!f0ishxPDcjs(a5;@xdzx0#&P#OT`Dvmk&~#zgsFkc=#Vds!z=n z@xg=^K`L-)iuhpL-a#sNwSCRl&x5W>K`P~ZiumBC@ja|}cK6vk{Aa%0iGV#G@bAr@`7R$s3_b&@l^Xe@VA8bE2NOiBcOnk7?$RIU%uYKLx zK3Lc_NL7eW5g$DILXawIogzLs;jSR{*3G5jgM5LiVwEm8mKD%bE#-eeSLN3 z^>AmLdVTQkI8Nz<7@M4LvF68l7;Ax?pRq>Bc^hkooX@eQ$ax-Xjhz3n21#GQ+9c;6 ztXa}WkWPO=e)K)-%vjL6ZNv65fA$xaZ(q=&++x}yv1g| zZF6a{nTLCJivRcgTo`ZW?KJ-cGoKG>onYqq!f6R+{$E;{V0_`&mITwT^?MSGk071? zg8cLyltVv4`SdB&Yy8WOhrWh5>34{qK8SWP{mNsDP5#5*#F=t-_l+~C^g)zEA4K`|LDWkhL_G9C#L0ON@%!op z-n+ri{#$X2#Rr=$_EU3eFBTsR>g%VDZ;BHieCtI&6)-4Hd~n>oern0RapHrcZ&gsC zdt=21U;d?n8l7af%l5(L+bgJ)fwAI))xNBtHg${@AI#Jh)Pa`X_CESq1%>v)2ZwxK zK^g3k;>8EIyyLI>T!q7SDsdHu$TKn-ataLs$E&3#$^u2d8HGt8Zo`hz~ZK z>#ufow69y+2agW+SKX^5h!0k8=dY@6jTav*uH&yZjE)x{%=GtH!ybtjADr^5pXz_m zt2OoY)t%SFopI{*!N21;r4M3ka=vwKTx{myh2`SS{5;?}dtPKg!1WAsF(hQc<5`0lYWQz>4Rt& z(}O!MHu*oPVb8brJ4mdf?mKSJtIoP>)TeQ#-raNKOgwM*k27(ueJ#$!pV~Cev}<;w zIMZIF(+82CK8SMYgD9WIJbnQ|JOnrq4rNSJHteeTt{CZ6B!nrq?=IW@<` zzu~(%rd=n#nPb|EbowCjvwu(yeGui-2T?D55b@9l5hv$8#P6#YIQU>Wg*M`OaP-IJ z)Vb_=;)AY<<QYYiK08-@u<+S(>Spp>@xi>x<Qg2eD_@O z!NM(nSmn;n5g&{z{=<4=&m8f={M@R;<*MjDX4|WYIr+#{2uK3`zhs&v@Bj$<^wrx^QWtPqrA3WNloO&{Bp7`Lq zbIPgu@6Hn+{I0m1nqN9keDEJXmQ%k~pD#Z6W>9$*HDbQ_VDGx+)%@-A#Rr>qDzBb; zWP$kL@1x4At%Dbc50=E2S3^qdYsP*aOfM*}-aEHIeDMCS%d0x~EfgPIzPr3iw-$;I z9{8cW`t8+);)9b9mshJ^TPQx5bfCOi{mMe|LA9;Cdadq4@xe8o^6K&6h2n!BWR_RY z?Xj<0+Xt)9D6hVaTOdBzs#kgSL8}GggD0AlS2b_U7a!bTqrBReK3{xr&5d&EyDsxZ zYwGK(JFka3+?e7mgqd@~PU9zWmA&pV3en|V9_==^`r=iv*?Jm0+T z0yF>rtN8-s3jwb$F!N81Hx?KlK{|a9`RRiwhd#L5E}uSydg)(?hdzin>34{qK8SWP zz2EM6CV!RWd8V9(J?EM7hc%dI>U}PJo{49}>A5D(8oTG3`2D_`Yua^I&o%8uI(-oN z>4PYTK8W(^gQ%B2h4gu!7SqoxtnL1c1_tm%lHV=>4V5mA4ECyL6lD)M7{LE26jC3LBvVF zL;UnXw2SGUM`xJ)8DCE~U2}@lI_z>JYC|ZnK=9RnP%dDeGvKSgD8hSi1O)!sFyy7c<6(Olk*ZhCbndCFX2md+!rq$u`8RCP7 z>)o_+H%=EHoPFemwPnC`@xhIYZ&+{Dm@YoJq0^J{PZJ-kP;|oza!(f@eCoyxYyRx%;)AuD-?S2b zo-RHZu;iw7(KSPSu=vzX>-8lw#0MX=Zdt=F&k!GMF!z>qvCT~J!Se@hSqsx=dfyM; zf7^QM{7mt|o!xF*d+N^;AN+X!ZR?wXv&088*W9+|EuAGkSh)AL74X?C@xf}xZ(Ciy znl7gZoF-+&YvYdxPSR=YtHmp;)DMjb=z9uM^sjsi@ zydLh1Q?C#H9mgqs5Mz_`ZTW9!n0fg1KW3Qu`I-9myy`p;UVm?-{ooVLzocx() z{%`l~Oydi^_sul(&$u6E8XrMAeGvKSgD8hSi1O)!sFyy7c<6(OlYWQz>4Rt&)3b`XK714+gjMDf9< zZ~taRyfRUI@M8FH)>HqQAU;_4tIO8sNfX2eADeR7s{h&q@xk@4UbfP!PY@p*|JY?~ z*1_@OgYQOPwtihcUVLzD@MWvqB5!*q1zfh!Uie_Ou*+6>(s=Q~oChvj+rAzzK3Ll5 zvZVtjh!0NaciCF;`~>mAgK3wocZW|9AMEq8g81O#$9}UehD;P6TsY!4>&811 z#RvO;^PAPtGf{l7#@$z}b=4+`4^HoQ#o9M)lK5bX=Ze*7+a&S9*MqKFmmiw!T^DVA z)mk`cviM-bSy!zF#r8F0KMz*cSFOj+P8J^wJ#p2#P-BYtV0Hg%RxkGy@xc%8x@LLW zP7xp6UG17R+`ew%gB2pKS!0_|5g%-M^{RFEQ&YqT)t;-?*}y5{gBzA#wQlUPuUp#( zfA4?QniD%&e6V|+tCngxS$r_%mn+uEYm>wW$HiT-lG7%M52_AVthm=FiPqHDS9e|y zcgCsL2mg-als<^D$@%uZW|Pc3y!OLMW`15=G|9}{-F}^9=JUj`$!4Ape`>Os|BISU zHomZ>(_}OM{PfSs#z&A&A4GooAj+W+qI~)k>ZN}n9{M2Sq~9Ta`XJiH^m@A{n*84< zPBi8G(S4#R|Apr!ntE@BPBigMKQ+O``SZ>RCjL!dOfc;#`fP$}FVg9Q$WI?cIrKr4 zPaj0R^g+Z!A4Htg1@Uuyb*(na%(n$Uk23S{&&%I8^YfKAKQQxl7yr>_KEE0}+RXE# zg2$NozwKLNj4%AOXpCuBT;>?#BS@zYB0qf)<>uMN&xUoY^s_vEu@EwmRt_+iXhYxk0&;)Bs`&svMV8Y({c$iTDKi($jW2TvrP zwW0?O6CZ564Y0CLx;|NoJ zgFYiny`HKgOgy`H4>xg6PakgLe|^eu)2=5*4>#>aI(-oN>4PYTK8W(^gQ%B2hC^g)zEA4K`|LDWkhL_G9C#7VzH{PaPzi|OCC>SOZ9Pw#EY znfP5VQ~m>w_cHZPu+M*HJmqTjG;u!uT@Mp~LQ)UYu3u;LFzrP;eGvKSgD8hSi1O)! zsFyy7c<6(Olk*T2jcJG#1XfJ&5Sno1xNkR|t!S~0OS+9TDLws=7(lRSBw5RxB+l^(`zWzPM2eW=J zv)Uf-DL(kTI%&N%yqEakds9zZgDUqHAAEb)N$bP)y~PJ(9yw*zAKpiN@Z^Y7)*nyw z6(8)h@s#!avA*Ji{i>g~>M!XhK3J>!X=~Vv{ly0pvrk)jhx&^T2Aw!|$pgg)(}th1hNTY_AKcORj5T@A zK=Hxq9nV;$T?dK}hCO}8>K!^zd~kk+GuDI*`?|G#aOMuUn zuhD7i&2#<42U}e@Wo>BOPkbh;0D<2a=cVr+80?J%pa znTK!R=xgTZlJ5P?y#3-={mgt`TD8BK=QF$ZH}n7bS^bSKJe1wv%s;J)`WqiXI(-oN z>4PYTK8W(^gQ%B2hFt^)dMyJ>AEYGvnLdru>_|dYgJDROxNv zN!-=T#MvgTmx=%0$-PXwaP~X*iz1yqi2U?HltUjx`Sd~5OCLl$^g+Z)T@b(T-zM<= z+X0{L&e5IQ-m>z8X6o_Z=jx#|ez(4vGW$QB(T#JzdDeG?XQ}Y0)wz23fK=g~zh~=u z_P0{V)1V|vpZju!@TRg%U0r1hhkcx;o7c$|?sL~Ntv~dh0iND4Nw2M&C+W}I`E~0ud8*c#r;ont z{q5$Kvox-G)WvHa%xfOZYaYyN9?WYV%xfOZYaYyN9?WYV%xj+MxaOH3*F2clJeb!! znAbd**F2clJeb!!nAbd**F2clJeb!!nAbd**F2clJeb!!nAbd**F4j4%`-o)c`&be zFt2$quX!-9c`&beu*C19m+yS#%N!%r5&Pe$BbYjZsUw&=f~g~zI)bSqm^w23&fIm- z=!ia{j$rBt_SKQkT+o-#Twp$Pf%(h@<}(+V&s<7*Zi5z zamO`(q;t(5%r$>7*Zjd;^9OUyAIvp>FxULST=NHW%^%D)e=yhl!CdnPbIl*jHGeSI z{J~uFXFA6n*Zh&rHGeSI{J~uF2XoCI%r$?o#P5tdw2R~J&&+X09icUK1XD*abp%sK zFm(h|M=*5+Q%9zA+)+oQQ%5j$1XD*abp%sKFm(h|M=*5+Q%5j$1XD*abp%sKFm(h| zM=*6{I>#M#L^^c@Q%5j$1XD*abp-qB$UP^}mwQgY+;alvo)a+loPfFK1k61rVD32q zbI%Ewdrp|namPI;NavmtF!!8*x#tATJttu9IRSIe37C6Mz}#~J=AIKU_nd&a=LF0> zCt&V50dvm@n0rpZ+;hTojyvu-K|1%GfVt-c%snSy?l}Q-&k0!Kcg7vs#c}s%=D4Gd z(3(1esUw&=f~g~zI)bSqm^y-~BhxwVs3X#;BbYjZsUw&=f~g~zI)bSqm^y-~BbYjZ zsUw&=f~g~zI)bSqm^w0@#ONJR_ZZp26Jn4CbC^F!wxzx#t-y z@jK%V?c%umGjrTgM`%qQ!PF5<9l_KQOdY}05lkJy)RE~NchnK-)DcV_!PF5<9l_KQ zOdY}05lkJy)DcV_!PF5<9l_KQOdY}05lkJK&T&T_kxm`K)DcV_!PF5<9l^dj@|!#8 z%Wv+${N@hKZ|=bS<_^qn?!f%!4$N=v!2IS8%x~_P&T+?Y?vT!J?!f%!4$N=v!2IS8 z%x~_%{N@hKZ|=bS<_^qn?!f%!4$N=v!2IS8%x~_%{N@hKZ|=bS=8owccl_oK>HOvn z%x~_%{N@hKZ|=bS<_;|JJL3-R;<)=WbKFr!XiXi#)DcV_!PF5<9l_KQOdY}0k?9$1}%}&NIirJaY`pGsnO@a}3Ng$G|*u49qjfz&vvdjI+G(4i3yS z$G|*u49qjfz&vvd%rnQpJaY`pGsl?DamO>qkj^v5z&vvd%rnQpJaY_;I5CdE62CL< z&@PU^A^lAZ^1nC7R)nm!94Sp=^S^+&-Zsc^A>q{<}H|K-hz4NEtqHC zf_dgGm}lOCdFCycXWoK&<}H|K-hz4NEtqHCf_dgGm}lOCdFCzCIqrDoEz)`BEtqHC zf_dgGm}lOCdFCxx;&;X!+Qo7AXXd!0j?kJqf~g~zI)bSqm^y-~BbYjZsUy=l?x-Wu zsUw&=f~g~zI)bSqm^y-~BbYjZsUw&=f~g~zI)bSqm^y-~BbYieo#T!=BAq&dsUw&= zf~g~zI)V{DJQbSad@Oh^80TieQ^Dv@b1&nxbPXk7rxCa6we%u3r(JrQA z9|!ZJFIf)OgjhcIaj;(O<6u14$H6$UkAv~!8fUvO4%l9#vmcP3{eyDYZz!MriF(=3 zh==`;IH`-o@1qyAgN|sUFC#zFsUw&=f~g~zI)bSqm^y-~BbYjZsUy?TKg^GQ15-yZ zbp%sKFm(h|M=*5+Q%5j$1XD*abp%sKFm(h|M=*5+Q%5j$WIA+Ye&`6Mj$rBtrjB6h z2&Rr;#1Bv9^$D-#bqh}gqaWa@VDt|>6^wp^r-IR+@KiAR8J-G;Uhq^f^uoOY7<%Cz zg6X)oV1C?lfKd+aMZhQ@_b6c0i+dL^;=w%)7;)kr2n@Y&4+Mr@OhIkNeOh^APKl%+!9l_KQOdY}05lkJy)DcV_ z!PF5<9l_KQOdY}05lkJy)DcV_!PJrI(2@C}BbYjZsUw&=f~g~zI)V{DJeAicyq4E3 zJQa+7fTx1dKk!sA`VF26Mt{On!RTjrDj0gfQ^C*+_X=R>g?k95fKe~*UBHM3_cUO{iF+V0^uj$57qUPu9`rNggkFpv zda+&5i|s`^`vLjcKPZR&hVt2;sF(eWc-a4lle+v_FK7oH(MDfJex#!xP!5m z82yPl!02bx0ft_v0}Q>;cVOs+K4m)UV1CpAMmeYhjPmgh7-{%#VB|#|V3dJ6z$hDa zfKeyYrM*sm#K>|GJIhC#STEYjc+dxo6Me(@(PwNI`jYKMI{N|n**_?U{f6?{pGadr zBQN_OWl)zt>xKHDBkK2MIkNeVCo2_j$rBtrjATU9n6n9z|;{; z9l_KQOdY}05lkJy)DcV_!PF5<9l_KQOdY}05lkJy)DcV_nT|S`A9aAKBbYjZsUw&= zf~g}I@gLjqiJlT3sp?0s7RI#-<}(YKd3@9HTjs|;b1>4X{NUvQ|52pV%Oy(sf`1k1 zi%G0F>Na(~{KJ8%x~!9z6Pr#mUfFnUU;Rou@80!{7rN^W>%Du| z|JA;`US|KTJM?W}N_YKGf!D{gs`bz<8hW{k?xBlzdCP1vyQdyA-pkmhU8jkcPmk}d zm)+~-rxAj3llf66%R!wiA9b=`q%j`kWt=F3@uO^vAJmI6%ejklk;Hb#Q>1@57okr$7lAn! zfjJj39rFnDV}1d1E&_8d0&^|`b1njNE&^jNx^wUC?VtZC_uhBbD7wn5xF8vGl6!b5?E5V$J=S$4FU_4*)9-i+?kdC>8^E2O-Af4|@z z3FF~AWu)_+GMMj_!F;F8bn3--%1GxsWiZNTfAXC&(h(2!LY&lv z@05{;@07uOrwqnA9QDFF9LwiBW#r*IWia0C}sRZ&(iX;@%sibMFlp@lY?sNnL#R-e4~u)44|xzvUi9F!v~e zxknMqJ&IuNQ3P|3BA9y=!Q7+Bbn3-Dib&@kMKJd$g1JW#%sq-=?okADk0O|R6v5o1 z2<9F|F!v~exknMqJ&IuNQ3P|3BA9y=!Q7+Bbn3-Dib&@kMKJd$g1JW#%sq-=?okB$ z?oq^^XX?eh+{nYd++gnI26Hbrn0vXw+{+E-UT!e=a)Y^-o9Wbxd%2O$z1(2#i$zYPTQ+dweC4FvPsKrp`zWIFZYw}D9Kw}D`O8wlpNfna_c2cwvZkW*ZZ>Yiih8oOosKNY(8q9B~!M@*6-#IhH`wr{xerAa8yNs^S6zQ1i zk!p14YCU36k$(P#NcHZG5?yw#NQVrFRFD2xqIKI&!5bb!%#g zE;(JSe;psCUTRgMn>|yatN$LQb_A8^#a&Bujn|^pJKq=U$>U1&b9vFKVNS8UE8+W* zhu=*!>EEwT)SXU8seREUx{CexZr^!1O3mn7qWeuq(nGgIs-oNyz5ACWU29~dYH_ec zcd-A4?xcp1s_=S=-fRDD-FbHWZSDBezfG4jcA~GQ>oeOkg}W_J)o+gWp4BrfVwpbt zd6uLPYMlJHIR6LF_Bq9;t9KkY8>8dlUTlXn)e zTZ;8J_BnE?3wr1Q_mybB6=l}b5BAgzdX(rU=gO?(U-p#u4lgx6DeplJ?kv%n2`4R= zySF}Y*?w1X>7>;!q>ru=vRV&&?UZ%nNFRBp!+3oAq@n#T=8fl0S)QeRbaLZty?yOT zYw?WUI$~_LPJ8*Jb$&`Oy>n}}ZgQy1K0~#qo>DJIZ=O(QmEYDwH_Xh@r=Kgca%%O^ z(`x4G1Gi6DT~>D2Ss&%(MbKmN&M_$d<_wP7i)ojxJKlQoqSyC0+Wb2YIu3I10 zou(_*%+`b3T(^dNJXQNu$<|A5U9;}#FjfEWoH2!KuR~k=Zz$W>9TSJON#WE zeM@wu@M!f~)1v=01|JMut#4F`R<15Z`srgO`gFT!b@hiLJ#$To&YuviN}3hR`|&RC zL@1nBhqD1Q-iuHj+vmyIfc*zVsAqfS$=QG-$3>{n*?Dp{;Onsw>XIi<&IX*4AE8!V z%agMKTW^n0s~hFZ*?_-Xh)|8@=gZlE@7QCu`LTRC8*p3WNR`&eK9hcbp{~_8QUxtt zC1(S6i;Yx|Tw5h)1NQVps`T~+ayH;gKS!z;R}{$EfVcgk)Q^|!J*y8E>f(o^)Z`Zm zmyY71Nn0HW9~;0YU2JpeX)DK9yK*Wom-kG zXFu*A5}_&$$&<4mU+Ed4)a!Y2_T#?)h)`|X*ni^%^^FQuZ){p2`tBPYs#fnRTgQ^qrp*rlyU`7JU=hYoGntvQD^i zC*+8}<3hsK*)}<%@7>44RN}2{(YNCIFx6^#w&;5*B}_H#mM!|mj15zm&!F$euZF4a zAFmXB2hhSq2(f5~qp=$85EYbJK>QMD-=Pc1TXKASFaBr6A8!|Ig zjX1wT^c_1cRHf}(A^KMQAXF7>T_HZp@$27jsTse&eYI3`{I6C%3iZ`#_!O(muZgQWY;py@muohGR^VZxYIH-eyg@#ra69x)nBGLelOVb9mns4 zLn)f$xA(FXGkzO(PSG5{-v*>;j^Apl?6x@L_l=HAHOKFftI3+<_eyfI=J>tT#P)b+ z{N8mgNpt+ZpPr;Sek0ya(j33D{$c;kduRN1xsj+jeiMF3)EvM5+Y&X$??W3CHOFu9 zjzlwlpE#AMIes@)PSPB|9a<-8j^BG1C25Y|8owr)@q5ahtT}#b#M*x|+Zn%$b|h<# zU#u@v-?Y=|M&H<%GmO5ck}{0G6HjIseY@4oH2RkG%{2N(CS@9ZUntEq`o6X!)98D6 zZ>G_=Xltg?H>xDl=sRzIrqTDlH#3dC0S{yvefRInF#2|%mSOZQsheT+y|E|V=sWKH zbfa&qy*5pK7krs!^er5eX7sK4NSe|2<0Gj?-$%1jjlNe#ry70hzmaP6O>2{C^j-f- zs?oPY`&6UvCi`qg>f0+W)#!U}YpT(AU8OXm@0$10jJ`8IOEdbet(wS}L^qo;7$LM>1-yEawwN*Jr-wvnkcUsQ)&ATVp=)2dQYxF(eF4yQg z+MXZjzwO%Cdud|5{+s_?uF4h42wobj7r z@9p9Ez32K$qwmx9yCUlQWYd*K-&gJVk>j^0Bg^R9;+-s`@7IsoKIDww*qbYizPk>s zF#0yyzQX7W|Ks>Qw{wNjx7XUxh<@!!L_!D`3MRPkTEAy}Sn};=jTDLX>Mr zrugra@gd6ZqfGJNka;0$^!iNkUn@RDZQGeC{#%w1qNdyP2mTgMx!4djZ*!*jZ|3w6 zRi`jh{P+HmA*%eWO!40%Z-uDv&Y9xBi-S?%5|5n}}teWjh761LQC|DIIr;7io)L?aBP^$QEL0qu%@0=?BYb^*? zm0G9D{ne%A0Sf*AeXZ;OHTJti(Ko0lKy^EoDEdZy8K9o6m?ZjMJP@F2#3YHn4_ppV z`$r~;z9%XNsw1D-zLZ?3$2}jYdW9#8zBk{rpCjH&7JYk93sjpwOBQ|CuL@Lk?^!DP zUO5n`T8&&P`j#&rq&9!IRP;Ukk08~jW{T*W&>~0$4owk#+x8ApxvNt|U)Q7{m2y5s z^!+qGNcFsbndqyQ2dP79ndmztFG$sEzfAPKcU6!&*>RcZ`)p2-y3k^o=(~SekeXM| ze#RM`uiMWJQr#;q6MZX<3{r#l+VAY_`>VpPL8?N0is*avg&*i9? zcksUgRaE9u(YO89KvnUdOGV$boIr*5chI-;hk>fLy&mA-KTq%J5U3{G>jY_w^K_ls zfhxoH|JvK_d%1u>)gUEF^lf%5KxKDI5`Ck$1gL8E+5`TkPXvI(Klvu1*N;kioQ+1ub|>*#EQPP&R0<5 z*2apy9YXz7!z;0(?>%+=)QeV}=v&a%Pi>wPC;C1$!cXn`B~J8BPVrMuSc^s9OW*jZ zMTv_=-^b7Usr=s-i@x=%`>Q8jjTe2RmA~4W5ij~~dBaQB<1kpG1D}S|UM}p}4>NozX^_~RLx7P-L)p1jT=o`A) zUtL(0Ao@?o|>*-|FrBRn@KWqHl2>f3;zByy%h+V1>qn!omM(?H+9>TeJEzRU3a9*WHO9sGM7NauSH-}fW`Z{PR*@4SDh za`%1iXInk$iGL~7-R6y&?)jhB6b|fF$K9*`eZpfaJmVhnbCmEaH=lRUdbFJIwTCTt zeDwZx`0dd4FWTi~3D@n})E#-GyKuu6&D>{tmaRpeUrsl3m$Ux|cG4Syo%}IAL`KDzUS%Wjv%zi`fR7u)5eOM9LC>!e-Ya)h1og`Ijm$m7H#?8GVT z#4qft7a4U^J215aQ#&xV15-ONwF6T-Ftr0yJD>E1U}^_;%83C}J215aQ#&xV15-ON zwF6T-Ftr0yJ215aQ#{aJ15>*}l_qCUJD>EmNT+s4cgk4@rgq3f?T}9Gz|;;* z?U3JBFPlp_?(96J9C!9_OF8cBGD|t`?7B)h?(7&mX54MK;NiHlWA<>|*=_W2+}UmP zAQoI>PP$yTPJX$b?KYwuVW)gyr(TzHeIg!VCr)7}eqpCw!nUSpm$0oh+9hmX1Ew7N z+CaM`-M(f@&A4m-qTN5}#@=?Q+s(+&TGWeA(9|$`N+T7k29P zpj}Qp!cLsRPW-~YdXZ5#wF6T-Ftr0yJ215aJAE$K6}7{4LhX=;+JUJZnA#yfwL?0! z15-P&6OYVO)DG#?4ovO9)DBGTz|;;*?ZDIy?DTmIVxx9Qr*>d!=aaq`Ozptb4ovO9 z)DBGTz|;;*?ZCczohdmLGyjVb9(xVVQ>E4k;b$AI@U)(HNVvy?1)g&+Z4n;ZW36ZG z)*|7zzS-az`(wQDkL5Rc&Xn{O_8i&nd3x@H!X2L3?NLD)4N<=TfxRBP{f~fSO7|gs zEz|A%>%howmm`dF?DBb2t$Mm%<$!idw3Ul{S*?Gkp{CEV)Ag(m;qx2KzO z{05IR}SNo{zshD1@Zgp<**BF^kpZ%%ST6-kB%-M9bG;;x_oqW`RM5K(b46jqsvD} zNq723@;f?8IgXA}zN4em>*y%)I66w4j*b$)qocHu={`ETd~|gA=;-p%(dDC~%ST6- zkB%-M9bG;;O1h(?Ga| zjQsY0^B^7N*yRhOe7jy@)N98hjCkxgg%PJ6zcAu=+RJ`$vF%P9Jw9#p__WdE(?*X^ z8$CX4^!T*V5XZItqzHcGut8zmm6jS{ERMv32PqqNo0 z@qcwaP;2y$y+Nn#X5O^Z3kZ;x%`?X@uwhPjBMb z^qqfjzrl3;zjHmiz|OVm@)@%(pE2w58M7{*G3)XfvofFj9pb(_JEb&a z|06Cu?>H>aH51n^Ee*N(vT#mHa_Q(Qy@cy+PlV42*Y287x~;}S;iC3&rP&Qrgu8vW zp!Cb|Ea5@_np2wHDqr}a%`-{^Jf8@sO`THOrC~AIO}6v6naBREo4>WobhAvmE;sA4 zV{kJDJ2p3CvtxEMX1gtJw#9Cv+itJa>#z%Lck&23zZG`M6n5$oc482AViR^^7IxYq zY_}I}B%|%jgFX><`bya8Lt&?Hg`GYZcC-+7G!k~S6Xr7x+Q?^8FrP`md?p3+nH0=t zQZS!M!F(nK^O+RPXHuW^JL?JFbqo*sgwLd4K9hp^ObWL3ve!%Rth?IR;s1zr*SqJA zm3a*Q{#Ee@r6<-F$vx_Viz7>iHTp#OVz=R?WB0BS4i6Ywx^dpe!j;PnF5NR_rSQ5p z2HNv*hOmBgK)&?O)ofR-*9M+WkvQhsO%r^~#)ydkj0>&2&4zoB8c>+$_f~ z-=6op<=geTS+5~OW27) z*ojTpiCNfbi?Gwr!cIRh5Bf*g={I4gKZTus7Iyky*wIDU(M#CTQP{a>^L@UM_VWG> z{ot?%%=s3~`4-Ii7R>n;%=s3~`4-Ii7R>n;{ml6m>6~xDch&&+%X;bmhc!T%Z_$VL zJS^|I!1nws@43MCyp8ukqOV;(<|Sc!?NQ!yA&>KpLt?PkD&;*F((k-0=`MX@U(a}7 zCTw5lc#pOY*RwOvOMlwq!t}E}UQGYn<4ANt{y*I}%G{e>xt+(kzY?D%Bc1c4FQXi1 zK9PFKKIO>06YtrabaT(<#NcwulyqN)?oPcjSCEm%ckXgnVj%nG0rQ^RhoxSod+!w|+_PhwdIHJgwIf_eVvuh2J>7*gbS$f^gQ= zMee(Yr3oL+o9`YpDO-5UeRJHIeO3wYd2@z)vR{#~GuDKC<8jhmh>g!vU_NJo`TPau za~YV=YhXUdf%$v~=5rtTPvcbj5b3-R0rUO@%=;EF?`Ocg&jIuP2h95-Fz=VZzM48Q zNIy7vgq`0CJ7o$xbqPB$2s^O}J24A8Z4v$}$BV5g)*1d&y*_i7T%R0YNawf%b3B4M zPQe_%V2*1r$2-`WD|r1Q1{eDLzk6PC`c~?4+Aiac={~VZI_Ec^wn#eXL!@(_1atlb zb6y3rU0`P%NuU289?R1I&R7<9#vqIw}Su5dGf!SpK%Y#bSJjI|9I2&b1`$TuZ{vwIu9ZOTx~zBMe~Djy#&^x&3m0aN@qNJx#wk?LmJ0KmHwz|BifM{0_ed zqdb%gMm?y{Cq2d|zYFY?BkYtf?9?ml#N$SOCr)7}eqpCwh6g8Ab9+i7rGGDvtm0m~ ztFrJXp_SbQ&({#HcO=@~rq6@Ie{_s;UvEo?xzIrdP9<%REkF2nQ4?Nct4Q|7

i{O@Reg_p7u|!5MF($Txs^&QNmBHs90KQQw`z#S0YL;-R>WQ-#)!2qO|NE_pSpE zybw}a?ulRz_)L^v>8KVxgx|v?r&itsNrc6erW`bzkoLAjp(5yyn97ftk(`u`#P zRwKMy zQqCiD*1LY1x<`0Y^`BjjCKU*~%iVI-et)`fKxvS>YhHcfz9YlkX|;2tEy4bg?&2=( z8X|^Ax`w$!#vYdT{xmbdz2oUNE~NK~{mqrVWsz{f?gOsZv)2i4&MR?!?tfVLNtdyPdN>AA5633z;h1&m_29Qo zJf&dN!?BNgFouynW$|}0pS@W{#?g_itudXORF-jc@%2qH&;Jx9n@Dz^)o+rWyhRyVSX62>oeDuGsj(+ zAFi!m=L)X(tCaIvleI4W_RmsIVVh4~tAGDd%89PF+O>PiVJTj`wv4SH3|X|g}S{prd!QqHW5 zO74MuPQ;*3Zod@eUXk-_4EnbAeUa{W5B?m3zU`kB?v5UHBnEvuGAGRa?ybWy=-bc% zRot(y>e>*$y;#1od(h*Z8{)T9_eQ(F8rHEPemkI5lsoIW4h`|!vd)q2fjiqZ#BY*^Ejo_#8R9ex|#ILcjRYTi2h_QiD(?k5X!*WtJCZ47t2=H{%!Z^!Hm zcTf1n?ZIzPObvCvy{4fDzx}#*h<+E^oCm-Cb-ABA ze%4(1?XW53-H$b%Ex-M8OgVSlBeUeU_rLhN>y`W&^4lhhZn<*4nJ&NWRQI%N&XhIs z+cWQ+a7D~0k>6IDam-b@O0oQQTa8~`gP!_CetRM5XV9dXo*V_xkUX-#&bEy(_T%Uiod-6Cb&X0&mN2YbP#sy><4Q z{PvNq$*$!WuE=jYmn6Dg>wH;$d$?eU>*X~U<+txue9yI_X-Fyh%JatCu5W{aOVL+N z_ybxH5z8Y(Fb3HIMpcH*|Wm8wz59$7;=&MHq%ez`%h?d{hK5{!IJuXsydo*cR z%&yi|N-?Io9=I9v+@J_4r*ryuFh!gR+G9;rXFng+N)Khe0Pm~ z4NHzzk}@&3+xGyHXH}0q4JWUOmNJoU-w#OsPaoaYaNSc;Qa;k{djt7x{Fgf#_K1m; zx{z+)Cz#*b_X#GyeV-tC2K=#P-Fw}uN?m39;@35Q`7SB{a*w!mSAVqk-`Ra@_s=@^ z&#DHo>kb!3v47UFe-5u)xNhf@k?fy!?4O`d7Obo1ieUe&^XZ>;KK-+f{qsVnXFRQr zM@c--?X2tZ{~<%&{H{ShyFic*6lf5JbSdJeA( zlstvQW_pG`6eQ)hn>^h!tYLtZf2jRb&zNXGDYMs$Q#`2w6{MWONeQ0aE&U{ag+r4( zFRdsiWnLb+*i$gLy!^KD?-MmAB;j|D)pq&#c?m z<@)dQ&V0{_PS+%VtNapAhxHddxK^LOzsOVA;hc=4$}bdn9v*gD%DMDizUS(~lTuFU zu`fI!FPBOFxmQ2-Y`o`$lzF1o=blEtAC=z@-j(ZlH1?R3zpdhDp0O={mU2c<_jsy~ zJ0j(LI%ln?)<#At5-TKY*ED22#B2q8KbMIXlN-3qx4T?gP5*ZR2HK;U`QVB_s3X%5S4H6AB zkS3bvG!jD5Z(ZxV*YmFD9M3tO^E>bPE5V}Ao%yH-foiN9t3v|L9KeYR} zzu>AjS^oIje)Sjbn8-4RHT=o{e&uT{=bAf?_$LlbU^y5oj2ZNq^4VekV)6>h#8_d> zpwGn0hx~$z$FqEl6~+wuV61q|NFR(9#tiyktT1NKr^Bv%Vdw9Uu>3C%=LxNcKEyIR z&(0NAO>fU~%1+7|E?)is>jPhgPeY%dZI00Fwze!2ehvSIKAT!(54SA8m*vB+;or~) zz6_s+ec;RRY3KuAhEGGECu*G*UcIph%m1KK(eTuDg;-|IuL_0izvgE-EvFR>KYf#r zg9nuq0M-cx+!XCLM|#YBGgVXjk5khO_GQ27jBxGK=dt|drB4rUoPRFM{Qdo6VS2A}Ea%exMZ=V&EXzS$L|lVDd;cgL zS`8}AG7%SX9roFouW-1hXDODCxcE@9?61Q=r`qI&L!>}TsU+s^$_P0(N_H1XdnJ96{ffTCzy1EFyy1>>OBwVr`Vz~D{=;&j|FE3sKP)Hu5C3-4 zig=j6WT;j6&X+7F+p#Zvv(YP9PKhs<`sVj9V>vNa^Kb8Y za*3}~;0u-+V>Qc(@tNhs_{?%*d}cW@KJ#xo{5;jK%=0VDT;As`-?h(AET`coZ~7X8 zzGpd)Jvhm~JpK^Nac@oZ#m_jva^kbh!uO_)c-=SbvyWxQXPJc`#^)EyiO(;V6Q5r! zCqBRUw?l?^_f4M4%QD9ueaf#MkelVaz5NM)b<>;{{#<Ude7>`s_eH z5tg&{P)Wb{ctMtP>#Q^U+;0l7oTjBq_);zNvz(vHobC@joR5DSb0n6DxJdJ#R?N;~IL&aE5%S&!? zLu#k^pRrX&%pTr9#TT78)Wn_eg;{3N(!*xoc5jM1vV$7C4vP!1%r&13o_*(UDLKU_ zJU{!yvXq<_=M0*CoYqUQ^Uli#&hCBVzvGd-;v&4_D7@k>yy7&x;yS$IK)m8cyy8r} z;!?cgSiIt1yy9fM;%dC&aJ=GnyyASk;)1;5h`i#CyyBF+;+nkTpuFOyyyC39;X;>x_@(7fW-yyD!v;^MsG=)B_YyyEn{;`+Se0KMXo7`Lij*xvf+6^twF zrgid7l|7z^xf>O=d3&GBxXs~F_QGoC-FxE)-r1mn9(o?#0ONY(v--y!bBD{j*( z&eMa}i98Z>v5`k&jyCd0`1cTbB<6G@kL1DYL>`IcoXPJI;a>4NcqC~Lj!5J%j@&F` z@JaZ8w2AtFFA_Z&NBvW{SoVpyAKEB>3GIb`Nd1^jT8&!ouuJ^E)n1+Fx0OeW^;@&y!Kji?J_t*uFd&y|Fm^(p}eG zZJynni{<=$&NXIUm)tC;Os?8y?9x0e=cOm>m^I7tvYZw7)iYDpbH*EaY&hD4 z<@9+wpKV(FR+h6oe?gnq-@$Tz99+QuvT|brJHJu6pgs1*rUZ7LH@J{}{g*8X^w~AG zus!W`fX>{GNxar@z+y$S5IIVo&kn%p=Iaz<|~Y~OsLNgCwbOV7Gy z6K+m}oawh0v-ecJH4Soh_bP5{HoGGYa#|ER!(LywMH=KxnOe|pZU2^oobe3{+3uIT z?I5SmjKcQ*byFSWd^x{}{i*CU2RYex6|*nSoZ%p+O}o?WEdRcPoT7(w+gE?M+(S;U z0eNh-`PDq+>pP$Y<+pz0yO@wMPor_s1I#IfL#jY(H3C(?ib2yN;Vu zQ~R-;(cOPHS6$bi<*Yn3V&`~a5o^4e^6+0;QS=lRof+O4M#VL7Wh zZZ(@X&R{v;cid)HPI{N+On!Zb*?jl=Ea&@Mc9|6)%w#!V&fRO;x0%IqE|`D7Z0zS) z&Wo$(nU-t6W;xGIpKmHJS6ajx3W0{?7VPR3)8)Qt^hmdZPwBx?Q#d$`L#FhHov#e z8(`mupdS$r%N?P5If! zliLp#Vwv~uS(J2{Rgl{sGg-{|0!3N=Pv0y__LMBlzkQ}-HnXk&X?(Azn|_|0Ua<)O z_V*UclWYx&ar^4KzD&Xw#ktLbF)PzrmnqEmTF~#ywBz#&v;3QeuS)B2K~a{8I83pZ z+gx+*>a-C_F_wwz^epD~yBe%ZyYt@SEFahDxy-+PFUy9s#)nJry>OkL(fnKNyVEn8 z+XK@xn%npnhPqZ|3-P^9qz!Xx=NDr6RVEI18!8kL`#7;raW}%{tX@>?9F&yKzo{iuU^Sf3WxUFa_wkeBu8yZ<6znbxrw z_l{LA_IK{d&pMbawf(aba&h~;n`-+mX}P)mtT~na#m5S=KD(A&=RX{fhku)ds{Ysm zMOdG4*VOY*JfD~4+?O=)w~flr?KgeU$iGFuh5vlLqo?n4-wF2T`@8h=cht_p@;{%` z+uLWevdqr2p7rlMnT_SNsy)QtcHS@C{?}=J{d@Q4V3`$m5AoO5`jzLxr@#02&%Tq3 z<>ziR%x{@`jORt0yNCOg&;8ExV*a3!e&ZWi__ueJ9ObKgla1T2nen#2`o5hke^=+J zervm3Ec5qsruqI;_OP7a+E4eLT7SoKY~_#qeSyf&RU=vNgS&+_jpeAwUn@pzVb=6yf- zn;TAGIgeHS(Vz9qt1Jg&g)xIZ`&S(GOSitxGBH*dGw5@)&~g9Pj7cmXV}&t;J{T*E z8T7$eVa%Wp#tLHweJWp@J+yiCUY393y6oY)N%yhLa_8g>J$K&Eavmt1D||b?9m|0) z!>6H7jkEHEEN6CPnec1)H}tvop?sm^C6BOt_%-|+`oNdr)6fUL44;NR@MZWk^!ecY z{Nakb^05463-gDH$MUeuyU!^Y7B|kva=yN}P}q4}ewKrIPw|nTo3>t&FsN<8ls*&} zDL(Qu^xTh&g;lExvwX~ZijVv}#aySDn0lU4ETovo&r{5Gii!L@-AA!@aqChn|Hfg3 z!(+uuv&z{I{nO8|9J?oHsQ*e2mJ{b1|8~M7SVN$A(^}h3EE_##Y3?91Q=lpy!%lWqPLBAv4TP!En`tN=2 zp;K8-j79w0-M|0jk3Tz|WyV;CJ-{!sPYu`H0T9z4OHOq`PJEW}Z}YXD>My$N7nT{HWvPCpo?k2{KEGH_e16%~{Nm@Ah420J?883q z{;U@M+-%e%eq#4*7XEzakB|DZKFx07&%+iz?pMyuVd2kTJlNGg@?kEP6QA|`+lI5c z`BpjevdsA0XF2g%&vN4Po#n*mJIh&?^>n}CwtOrnKI>V|8E>EN^Zb~P{w-o8&3~4OxJdJ#}Gf3{URxSzPrU;`B_nxGqvQv z*-u}V;%WvJyTjExbQ;Ti|HFZ^E3ZlY_Ri0myJ}rZu*?dlJwJQ5O>sC+ml-_!+{P&m zXL{Pu*|nZZaX7cVH+=T6TqzDm@j@q6GbUWq##|qyw~sgt^=81-CP9sv##jEbz-%sD z!hD)Pp9Ow&aA(u^k*tizte$8-TEExe`mr5L&E{E480TC5omtc6b;hH<$ZF>d=)^eN zwfStT^~D&E>tD#GeRWNO-(K@{A^YLv1`fDMnS6Hr@5Mdv)S+2z=jR_`+`7_trsv%g z8FwnR)GY6@l<`#uUN@_r{*H0AK@XdEr)3TJ?X-PVb5JE8 zw_birGQG&8dwIDR>EJ~N(k+N?q;n9RsV_nLLVXO}$7-2L`hq4a^heq@bpNui!+hadO-{UnGN%HVL~cH24VP0(^*Ye(Iz8t;27BP5sstr{4}s{nn|zJJolm`tDTUo$9+& zeRrzwPW9cXzB|=-r~2+x-<|5aTfb_tS@XpccEOg%+|6~rG6O5Mwuh^ZbZ>6@+SI9b zgB^J0boc(Km1c>lZZW2+eWKbYs(qr`1AFvs+wXF&}H} zUgf)OC}%MrTTWi*?R95co{v9n@=q2lVKE=yesh<9`^KUc^KtdKL%#M!1uf=dv#G!O z(>}~=F&`V>kS&BPxh>}7+G2UaRV8v-%*R{u7YcV~%V9Ae`<5&oE?%15Vm>}q=BzNd zeGZHHIPkO5;r)a-Vw#Urnw=A_Xr2pw*VrljozmYa{hiX^_57#)PU-KI{!Z!dl>ScX z@09*d>F<>OPU+9@RL6as|J8Q~)Vw&UIn}A{vtjPXr+Mh(A?~tR(b&NZOUSUPYR*ZGbA3eHxm@s>QuXg(Mr2DZ> zq1oUb{_)F4{w1FUca*v;T-y7(0Q+2XL6vaY@G1fJ`QzIQL&s;%4m3}by$vgey>shx zn=SWV7{1xii1CqoDulKhZeskv?W_F6PSyDNGV!{j{^|PH1lXtM^@YQMb8iT+&lhJb z^4ZU?8ZbBS89m#-@%tqKbF;+TQ~e*8UK}ttYmJ-WcXqB6FgMq9tY z)B0Z=FgKUp^Q1p;TjhYcd0VSC{?(&Z0_JAjqBr`*w_hGGH_zE>{jt_p2F%UJFTcdk z%TXg>Zr*=;Ie)|X*96SX0bOaIV_IE)RvtTA)W3LD1AbOkn^nlCeb}rnfg>0wolJTN|+5Z>au`o@MV`x07?NQoGNx#XnllxmL^5O4+vamvOFjXR$Ii zN3{iqYX1)BTIY|eXt#`-$hp?XtuL|f<{QVk*31e2u#*nH z$hp?lHLkR`5N`?pX;-?Y-SqGfkJ!F>)zx<6h<3xBR5}Rdk$Zj)cg2AQmS@!Tj{r~=E(4a$-sB3*}dTGPMagUl; zCvQv^%&%#yp7E^ttq7fKKkI5+@W24muK$+_<#jgZcu9lHAGE&>`OP3M&D?jlJ-6v9 z1G}yJ{1$sS&kO^*%`X3dt+G3tMVs9R@3j|p&cnFT=+?HxzJiSDIcw!Pd)jN&ZTIU7 zSlBJ!6O@B|Rmj3_lg>HI7NKV};!^n!i`h#TWape=ca8$K%XK+8XL$dtT(-j-IXP#z zu3Z*ec5QCX8TwxEv-xp(KF%3Nb=+?n_9$c#m$Gf!Zl3t280QRYCT%c3FF1p9hI*UV zm<^>%bIwrcov+LlE6Q`u(6quzQ`T4HoZ;R2E6mhSD|5~;YTOF*bnky~&Y<(3lgXD( z-xW-&@?F^uLpRJY7v20cyB^zT)!>cEY{=B;^dTZgOI zKBKqpbQ907&Gwn`S$5y9XFax0^IZk}k|!ImeW)*9`a*s5(#JgS^z`qn>4f|udLjIYMO}yBIY~{sPWLqC|SDj}j*KYgTpK;|4Y@aa=zVhExY|ZvjIon?*=cG9j zWR4W+dPCT~vJl&6+$+_Csat^ULvt#~oT9lFWUkTN3^F(MS}fm+Tf*UdGYsa}*nM}0 zYj0X*Fu&9~<&<8dA)m!w2G#i(RUgH5NwIE<>yl6pgf_7bigB!iVvM?^SeIq!cU*6T z_OT8M^+E>siSCLv{M(n_z_`+tQ%sH>S23PmGtJKH zzSy8mjRiN_Z>Hw+z~@aaWFI|xRsimM{=np!y-gU;ynmO!|JEvu^IlmuyuG+Tw}<`W zc>V9zcTs&A>d9yvrOu798u!2J@lx-A%eefzdOYMLcz2a@5~p$-r*atZ9+Ja2mGd~2 z^Ej0wIhAWUl~XyDQ#qA`IhBKf)03Rdsa({loYSeC)2W=(shrcPoYSeC)2W=(shrcP zoYSeC)2W=(shrcPoYSeC)2W=(rXpsWq=tYhI_;yiTooom%rcwdQqd z%}eWn^fj+jYhI_;yiTooom#UywPuIU$QmEMBwPV}MmPcZl5he}aR^Rv2$)mCKWqN{ zFT+18&c`Xv2Qf!DBE%x$nhQ)@b>)^tv->6}{A zIkhHrYE258$QoAf9l$2C=7p_f&3jUN5Q-~siW6{(6L5+XaEcRfiW6{(6L5+XaEcRf ziW6{(6L5+XaEcRfiW6{(6L5;taEjBwoDvQMb4|Du%qihaFxP}Laf)McietfEn{YDN zlSwvzXbocH8pNR``oj$+n+8d?16tMdep41 zc|YT+X`4;^isKm9e{H^b^5KseKYis`vu^8V#=lj%&*U6@l<_$~6fhk&XAh85YHf|A z|FPVHonUI?r49Yo%Wp}h7nyV~FZUuHyy!r>dC`q@4x%&lB}iYWk3srKeGk%ivWXX) zkgdGfifrh`hGbhWwk4Z;u{n)}m$5+Ig^Ur#YjClA_L>hqr~WriZ0!Pe(QS(uqaK6m zG=RA_16b8^cva)!RqcmYH6dQrig;B+;#F;lS2ZVI)uMP+qvBQVidQu)Ue&sIRRiNy zZH!knGoI>dq?QI)YHZL(YH#pcsmXy%snx-~q=pANNNo>vlbRpsEVV%Bi_{3Ak5W5? zzDrFJY$CNru$9yx!G=ACz@dbV!3dapq)vFWUK zN#RzT8BaabGWl@aR>pPb-an~H7~oFF*~E!W$W~5lMK*L|L-{SmG!ykV z5kr5*Vt-s$*i(CH1B||-J;sam0X`WX?BDQa>2(h3w~6A=fQ3U#6c3pw9ujpXe_9)$ z+GomJYM%3Ccq+|nDV(U^W?J`hGCWTPUg)13QKEjEY2DGu@FAK%Q8-b*#h&<|?%ye% z{G@6RRQpVMbit|Yn=L7qs@8c`{m*K3G4`^RX6i1h#4ng%%_dQci zPxG7#XIh`2{ZnC=8TY7Sh~{P!#la?ugVpt`8vjR}t<>azzZIM)E-OQQj+*<3Z|S_2 zYM+7oQZh5hSDfBorp`yz{QPA&Nxh$|aH95bGt{lAX9u2-QuCJSp0ARr_m2Nh)xZ4} zdDqPL?)CFs;Y{oLRNr+?V5S_k-mh0UQG4Qv+7m~PmtJ?OaHf0cN~W$2NK|b=qG|&Y zRU43~+JHpW1|+IBAW^jeiK-1qRBb?_Y6B8g8<42lfRn06)pZU^|5LiQLFbqr7E1Ly~_;sY~;h~^=}G0)jq>sr^@;D9&x7cBVaH1&)x~jZ10%* z`={@wsXglq?V*O~lPYD*L+plfUrRZEkoTAD=lQRDxp_D0^V(6vd4s`*J& z%}=7Z3ym|a5z_Te3MZ=eDN(ggiK=}{RP9ruYM&BS`;@5Kr$p60C93u*QMFHrs(ngS z?Ng#^pAuF3l#u_YzptV2U#518=D56LqHEX^RjZcaeG}D3-S z_F;|Ukd4~6HEKWCsC`~Td%?2*3oQG>Xe0Z@_^s?CL#FI6<6g4w3>{=Y8oJ3oHFTE! zYxG6-wb4h}??&Hc9~?H3{c+ez_RV2K*-wXUWuF~3m;HB)h3v~?jAT!NapYYwrou&I ztc9b74+wXi&Z9;@5x$z_r1RBA@zqB0)zZeR-!fKwwfvT^N6uET@YTZi^7Y8&GFE)G zp?e5l4Vl7MLm%O*r49bdb;gRL##}%jJ>)4Y{o?Dfzl3!oo z<$EctZ6f@(v`K{L*Y=FOH{UB08=}9$|6|<6{=$>Vyq_l-L9zbh;<`MMfkuViYh+ly}at=K{K7kIzm-&_~_@V%4{(qEQC*JbYD zx?sr1c=2xq$Gr)@uJ+~MwRa~GPu!pN7r&J}NA4SARHEAdr+$v#YB{PeEFb#+S8c0x6PqK( z%2)u)7y*m?R2=@NK4RzC{y)v%q%Y7}J!{hQJzSSOF!qb{Ltyn=4;*diMF(o*)o;Dz zkhreyCAkXkzbhX@8-BK;z1Shj-K!P_XFpAJo6eShN1Rc23pQC6I$!Dc#3^ z+xO@Xtb^Pa`l#QE-*OvuFQ;lU#Xq@C^sE0bJBSU*AJSz4i`{^gU!~g_*JX@=W$a>m z@vHQ)#&xlY{%sr!o-e>B;~S9k$i$bpe)#mHml;&&1;#&&+GYIH&ojQTSb4ke*`ACC z6uiN&vd3 zjq42#zF-Ug){go?waU{5+qvDoVSKcDZ(FBNsetPxLR)+HMRggMsdA0ov9CSjWLF9M z`TA!WSG{4m$+2<>A|59=KnJ!ReS3cnS_wTn0t>!jl zTz<*5;m%^68DE_1jL>0tf5x`g=RQaO5sddNspBs%F^2JX^9Q8u$Tybp=%3n}b8jEb zxYnv~&5MPHGv4=n8M~={U&bRIuWvU!*MV`tTRPd#D%54%y;ncGdD&TvJFFOPf0@3D z^?bsOwncW{##qMd=TUc><W2j}!wz`f#i4;nV>(}CBJLOa#rFe_cHryL zK8&N?7^8o!I7dA2dUQOW-de$*r?;6K*aP5IK zQ>(#v#tmMoVve_ah4GlTE1JpkCNR!=M|m@>?rV(CK33XnxcYU*^#_zPyJ}5jOgfp8 zAHQmEx%eIreC8cv?B1DM7!RsB*zT%T0pnrHyz!I`7u?L4{#yEf#`N!&+A*fz;rEP5 z9^^8HZ_xeZx|i#?kF>{qL=NsF^6^*hi+>k=@H^2H@72g*_RQKCm<6Xn)od z_YwW|c>Sw=qtWWocE^c3Ok483=2wleyI*W-;CuHUA7d|?(9FR1Uf%w)ZMdtsf$#nH z$5@;D@jDHCuS=uxw(gCs41BM{%2({Hhwe7;y~~#jw};+e%`%%^I>Jt>w}xdd**3y% zYq*wW-aBukEiz;s%Urzd1v{(cH!O2c!BKYcci*zi%H3YFKV;j)GHeIBvXx;J2%g=;=)M}2<- z%lxD6<95)SjacSG6S~;DUun!TArEq)C*(mc^n^Ufg`SWHxzH2xAQyT<9^^t#$b($y ziGHL1kcoby|Ec&;+M@rd_)x~8|Ec&;)}sHZ_)yNG|Ec&;-lG4IiSfZWK_ef49(l0Ch$r&sp$%AQ`?(<^&=Wlt~mq;U^w+=CkTpvFC@aSv+TgBtfB<4*n= zlz#^0pF#O&Q2rT|e+K2BLHv{C1vQU?nnyv+qoC$dQ1d9Lc@$(GQNM$l??KJ?pyqo} z^F65f9@KmfGT&)@f{IH)#igL)Qc!UzsJIkVTnZAG$d7`GpFzdXpyFpx@iVCS8C3iX z5-^cOw)O;V$I5pp2VVs)p6BwuF`)iEh^HEO^ndI-#(?cftJM{FB zN&XH!J!F!!#`Oj`8)iRWyX2LG9eFgp(o@)F7$*v$c3Je z2f5G_@*o#_LLTHo&p6*%Ci;#3r^dZB<~z$oztR8HxR=FzXPM|X`kxy2@|f=|GsY#B ziSfZWK_hN{sfuuBlr_!!jIrjJVumX!S6Bd$h9cWvrJ%$^DGmX;ylX)rZ~?sfho?jOkj%h zq9^-3WX9)_=*fN`^<=+~da~a~J=yQ0p6vI~Gd?%Po_KDGJ@MQWd*Zn%_QZ2j?1|^5 z*b~o9)-yieS!R5`vrNP}HST!6vrNP}HST!6vrNP}8TXinu*{f;u*{f;u%0mwVVN-x zVLf9W!ZKqXk{Y8_zQi)|+)(of`4Y>-b3@G|ZaQ{ocxPl-#&KP4_9|MVDl z>x`KHW1WO`8P)|}trtAj6LB5k z)%wD#b%)3A@O%7Lty4UnCvp9P>$0vvd%hpqt920MV_n8_;<}8nT2JA3SeLP$ab3ok z?!#+#$W-e!Y42mdWPOKz$+}PO8M~^+)(*VjaE1GRm!CB+i%`V_e){o3cybYZ@~OY(M@pqum%s zdom_{EZU)cSw=3ty=31Sxrt>i z>pjXo_~HhZIpu;E?eLesVVTDYyX^qkVXpRIpGDGNPcx%NqWW5p&cvwEH1|_!0aGGT}$?C&)xR!5n~0V8lnr1V(&>Okl)E$OJ}wgiK(>N5}+5 ze2jW}r6>D+)RX-_>dAf|^<=+~da~a~J=yQ0J=yQ0J-xE0SN8PEo?hA0D|>peCyjeh z;~vzw2Q}_NjeAhz9@Mx88F%u}p!_o^{|xYZ^qu@ODE|z~KZEkmApS}6f|^G`&7+{^ zQBd`i=gl z#=Q*YJIh4B(f`!Am%@B!ndmqA51HieJWeVuu}q8)#tAYpJ{Tw16XSz%f=rAL#tC|2 zd@xRsN&e3M1ex$7_!IPmAHkm>6Mh7Lf=u`k{0TDQNAM@egdf45AQSl&{2nra;rEaU z48Mm=VE8>`0>kei6BvFEnZWS-s3)FBEHgfjL{B`AL{B`AL{B`AL{B`AL{B4n#^)x> zjL%K6C!U*PPdqopo_KDGJ@MQWd*ZptddBCwj60t1EE91~jXR$2EE91~jXR$2EE91~ z#y#dCEHmaIEHmaItY^$aSZ2&aSkIV;u*{f;u%38s!0$0ecy6e9WYs)EzQi)|+)(of z`4Y>-b3^74o^SAb$i(wa&3EK=tS6ptYQ7_{V?FVFQ}Z2p9qSqMPl-#&KP4_9|CG3d z{8Qo*@=u9N$Uh}6A^+sKgnR*h4?Sa^Eb$Y0vcym1$r3-2CrkW9o-FYbc{0l^{@xH< zVsLJ*KT+63jG7ZOdgM@>w^TKpaVHpO-|049wGqtc<2B5Gi5>lYTZ?)Xh0Vu9s@swC zs^hxZb3>ZF?lQ}GU@2plnh&DxKfWRZL+l~ z<4s+v*>f*x#rXd5Rc+}#T!*9Y<<-5sx|dh?^6Fk*-OH;~Q6}SfFUC;^#!)xMQD?^SUcjOQ zV|2j3wDo=vqnjHMna*1!E- zn?!X`{}Z)IsHf6A$=|#d*I$9Jllmy|QBpT0{2TL5rvk4fV~274U#JO8uSLu=?88v8 z&RBc*wacBt$s;vC2+w96ZQuW7O>(@;%rNMM7wjv|HYGXh%nVgeA8uQGwIgXVX=a!@ za4#S+$Ve4 zr~4dCvfMQ{^l8zFkuwPU-BF&Q9sFh|~Kzg&C6;85T+BMwTcM02h@z-6$6?r~mJMVk>=`i*61#IV{-MfdgI?Q7` zPoCK`Y=1Jaoxd&pY$&p2Hru)PzP@4D2ea7D-{u<-e$MwH+u7Xne0XBdOt$l&%|pY` zTW7MJbKE;JEWdpw+xghWQQ`3ZnQZ4*ON|M;UipCSOnwo_C)mykJEgNzIy=+0Iortqo%bmt{N8oV7L#e5xed`K@!;g*Q7DWjo(ietlT}dOo&uooU~M z4Rvy`ozI`WA*?-d+`ylAUbZ=``|$?@e}1;mw(!c#?+pC8MYWybf(|_O!n7KO~AMr_oxH0a>ouTT~;R)hKm5+9W zvn!hfaid|L9pS1OqtXyJ`XAUH&fRwUY{ZRP?RJF6CY|mOH!44|Gc;b`!@|y7qvxl7(c1mZbbaqN-r*w8o zXQy;_N@u5Zc1mZbbaqN-r*w8oXBX#PfSnaiC^iSgJJ^|Gb3nXrTVsk*e zgPkch2gEzrnPPK5yn~%7HV4Ez*qLH;K)i#UDK-bhJJ^|Gb3nXrTVsk*e zgPkch2gEzrImS2Wtg%x%JEgNzIy4?ACS>$lDq98krHg@ zob%R(H_Df0JI}ptU07AB0^9lFR_nt#%P(R(A3yO;*j%70+j&9r4dJHkm$RMYbA;`z zuv0oarL$8yJEgNzIyPNL*UdyD%< zITkWw8+=nzbgEkjGm<5#Ha*@pXMMSlarwg~?1BZ3agi@>wof*F zoAK-Q``Ej3jbi-8hOzeMIZrcw=FoKeYUSFDXZ}3Lt~rsD@e>0-vnzk-$NDenxWr=L z4*IL-?_cJbyYtLkbBdfZn!lGlBukb#_l;`nJDvSXlH-S?Vbzs2{SEhgn3UUyKoaQ@r^if7`vo{xb1o zN6jPQh7lbx2a~q_z6&qZyEVWjEgq+w=ZWhAY;s|aAHq|8J9C?33l4|Mox3o`+@(3g zSU(TVeL6fo<|j)AvKgz4O>6DknLm^C*mS zjMd3qrMiW8%57nrSnAS-FYY*f+v`z|G zdm!hbbyC3E133?^lLFQr$a!d;!&taRL46apQ9Ta{J?Klc#c0&22@RS2TAJKM+UI25|-P1sHJ%@d%jK zF&^<0GEWwX*o5*mgB%Dpp?u9C2ZBu~Uo*&oU=zyMEOH>&gz`0u90)d{ ze9a;Uf=wu2v&ey96Ux^tav<1*@->Sb2sWX7%_0YaO(A6hq9_h7Yi(DM`p>=~rE)M(9y1^nBhka<>V3CW% zKD2JI$i-nFS~pna;;;{`8!U2h*oR`H#hL*=PchR<%%oUr5p!W5inSIo7xtkTYbD0g zUn{YferF|CgDXPJg-nXI7BLq-L$TH(=E7%a&1w;IVG~-jTC4*(w$zzvu?~byXw7P| z4&>M}`U8t~AZ$WwR*Q8YY(i^Ri*+DuLTgrwbs%g)YgUVOAZ$WwR*Q8YY(i^Ri*+Du zLTgrwbs%g)YgUVOAZ&tMlE#nqr&w#{*-Ek2BId#-6l*PFE^Ib| zCg9EyXJHd?=ZLeg3Al5_S=a>JIpQpA0`44f7B&HQjyMaOfICN=g-yVnBhJDmF&?u1 zF-~&7D85?6S=fZ)t3{lJO=4W-HZk5Zj`5jsjN2@e;;TiRg-s~FTEtn{gyO43oP|xW zZ-Y1sn_%CDxIwlF#aD|s3!7lyhPXkt3HEIeXJHfU+aS)uCKO*S;w)@}eH+AC*aZ7F zh_kQ>_H7VnVH51zAkM-j*tbEPg-!IDJw8vt6$ppGeT>|~zgzpq=Q6j6&uhl<`OY{# z_t`!aYb|0f>_f5EBId$A*atw&g?%X2TEtw~2m1hsx$qh615kd;_Q5^?VlI3J`v8c! zun+bD5OZN4>;oX?!afvh4Pq|rgM9$RT-XQu0EoG;5B32Nb73Fs10d$YJ~8iN{bN2> z1M`SttwGF%&rqy2h`I2Yn7?tGnAb6mc_8DMAF@n}wFWU4HlbK+5OZM@aQ29~un9PO z#9Y_}oIPSLYy!?6F&91q&K@xrHUVdkm=AQe6L9v3xv&X1 zd&FGW1e`r$E^GqM9x)d-iTOF}AM#ek%+ml3HV6FT-XGBBw{XX0zMKk7d8POiI@wU#C06&k6Z&W7k&c%05KOf z0e^s)3!B9CAh(I@M8pXpdYNF&8-U>TGB52Z*__3HSrVT-ZeIJD<{f<&iJqet|!r zoR)0@{(y2?wh7ifh_mQB)p0pcudqV_J4)1I>X ztyu3O&Z1x74-jYJC*ThdXW=JUA0y794c5(wv%pwqBhCV2{f#&qbJ~D73!8vHK%9k5 zG)MhR-_PvN_w{GKy4dzP_DIKE7QF7=3#Z#7i)%CfWcXP7-lNYjF1X=Y`)=D&jI+OT zlRfXlw;4b1@acA9Vb6H&t~brxY@af&Uav>8zs?fIU0XHr(`PSYyuJNF|M&y*8Rvh! zdT2QCea4-ab_xx+AB8TJ$kxzev+?W16h(7eYAbQe$g6L28Nq^TeUI!14 zexZE;j&c}B`HbUz8Ap8><9GPI(w{Nvv~j<99sQN|umj_0AI8ycjL|>bFX{t3Gp66c z{)}Ni>KE&;$Ls!`w2q+v@)tYo)Vhqm)xO_m$(GN*xNwb2C>JR4(?NG}i%srw$_3oB zpSXHo?{GgI*=eV}Fx-{@Wv`n&YlkiKL*fR#a==wOdxvd2J+{#XmU3GdRUF zIK@ji#YTX+oAbO|Se`Y7REP#-1S3+khUdqI7aa4)Ej67B`{QNq2TK1#S3)JF;T zg8C@oUQiz;+zaZXgnL1KlyEPoj}q?1VI33sBB%Hwr}!lo*Fk~et&8g;#)^+}iobG- zze4SV@LjSm87Nje#nGXbNjN&xG6_eAS|;J>P|GA79cr0`qeCr|aCE3;5{?eFOv2Hj zmPt4|)G`T2=M+bWS|;J>{>yu~aUH}qiR&ZAaoxmN@t;odpDwPO*d~hmb&BJ4isN;P z<8_MTb&BJ4isN;P<8_MTb&BJ4isN;P<8_MTb&BJ4ikEhZmv(X8GzWeX*FlWq`iOB{ zH!)T`xl=s3i|Zz~NnC?4R(k;_EVhNPjPYG#CC{l5XNfH z$f-Rer}m7T+B0%$&&a7gBd7L^oZ2&T;4kBzkyCp{PVE^vwP)nio{>}gTu$wCxwvlP zd7<{#TwEW?Jd%Ahr}o{P+IK@d!Mcg<0R9_m2E-P%w|L6cJ0aF$JwrLFQ~RNav9f=P z*em<6F0PN*CUM=wSnba`wLgpJ4(f{84zNw+)lcc#BwFvvzPVHT=6Dv%K0BV#vR{v9 zvFyv^87=$rPVM76wT~~gscaMMtzj;~Pfq1JB2{1ERDA_d%_)MpGOL;DH8^v=Xj}@L1c`WK%*d~hOMII|$F7jC6a*@Xhmy0}BxLoA1!sQ~5 z6)qQftZ=!=V};8_9xGff@>t<=k;e*`i#%4iT;#FBWp6^G6;loImnd;rx-u3g?eJ zRycp;vBLQyj}^`zd8}~$$YX``M;eWvNwc0R`!OF$I9Li@>tm$LLMu7L&#%gZwPs; z>w}={k*;_;nzw9ld zhF|s;QNu5Li>Tq3y+zdU%ibbt_+@X=A=ZLNh&iq7hYD}NeUE$sW3}HZd;(ur`?JVt zWq($<6t+p^SQx84Xw=)w9yIFhWe*zl_Ob_!dVAS}M!mi4L8IPY_MlO3FMH6ax0gL= z)Z5D*H0teT4;uCMHts>A-d^^g9rkeIzBzJQ**6z{iTfLQC&rOqVyyP%k<-dPK5|;w z#~03x?VxHHkkd-70&3%>Rspr~QmcU4cnj`;_RdfnFSQD&jh9*l)W%D#0&3%>Rspr~ zQmcU4c&SxDZM@Vfpf+A=6;K;5wF*wvS0JaA`U>G8Q~BFJ>pFyolw1z=EsRyY2Xb1e z_YfYH^Eb_}j<2%AHkr0H?UJg8+~`8Ik2;`b^4hrluJ#kV?D|5lC&M4xRS~?y(ezew=InN=7mw;!Z7L^8Ag3O!>Dg+81=0UqrSmm)VDc| z`euhw-|{f(8z1K8e}4PJsBeN8^{o)2z9C}Nw?&Nl=7>?>A~EV4B}RR_#K;)}u%Tc& zPXPUua|WdEICB7P_iaB4eYeG^celxZQs+!Y zJ>}aytk1Hk4_ll&F|_$j$+;CeF|J*wq4N5+qydrwlaUI)f~a(7Pl7JQI#r-{9i zA9J*4{L#73CwEqF$N2d-UP`W*@&MyppH58fXr01mKA6>flmC9cZU=2o_6|LCHJf*{FUtVXrou9hzx7X9T z#*d_AE~EX=mUH-g6*KGI9cIXP&$67M<<^_}+xsw{P<)wrzg1txtG3KH54A|)itA^Z zQR`D}+BcqJrhSw8ZH^bmo1yph=JrdDj5Ia+@wbgkzNv%Ef9Bh&RsF;+!dqFT`}t16`WgQ;~6Q2&MmR= z>=c}NV&j=AI9J5RvsQ3Mij8Nm;9L3w!bWQu zpHsJvedx2}jNcgeq%HecAI8n6cD6^V^kw|=kq-96!TyZ%KYzb%G3I&3-@e+$wktf6 z@sQhF+3!k?WxQp1bK9xU8;tciJa?Qi#BP1EEMFg$b+FBMeRan5y9~0!TQ*>vqwfHF z+l4I|SE6qi{eD45#$(3!u^skzWqjr5y=hZy86K zjN`o+M;#bP-55um8OOdbj(ubtZO%B_gmJVL<7h+1(YB1E%^AnBU>toTK>s*)d_9gS zV|`Xk^Z{-keS>lI8OG6<7)Kvt9DR?mItNC4m9PIR&YX#JpXJ9n$T-eT#xdqFj&qrD zoa2n++-DqP0^=Af7{?gGIK~#nG3GFiF_3YLQH*2kVjN={;~480#~8>s#zw{@(^Fh! zoU_m+ZcM&*f)l~iM^AB8e(Nc&GA5ax;wodhm#4VOm~`+IR~eITp5iKF(%Dm7WlXm9 z6jvEjA3eoY#?*IDag{OI#8X^lOt$hAR~eHHJ;hbVWLr;hl`+}eQ(R?CW8o>TGA5r1 zqrXqxm&PtoT;=ODrh(!rWAfGX^NuL420A;7uTxwNbaobFimQRn&SFe)HPG2vj47@L zIy;Lo#nnJ(XE7$940LuDV~VSR&dy@|uQ;!X=6ImEDswPUTxCpiGf-S*Ofe@=TxCpi zIZ#|>OmjR?TxCpiKTup{Ofex)TxCqLB2ZjqOfe)-TxCqLF3?$Lj49>>imQw%76po{ zj44J1imQw%b_I&7j47rCimQw%)&+{Ij41{NimQw%HU^5TjN`owVh){+7U=vmJ~J(1 zK1(h3k=w-IGLAAC$9pl3Ixvp9F^)Pjj(uSq`^Y%joN=@X<7g|!(T0qpZ5cumF2?^q=at1d!g8XoGLAmXIQll@=<|%@TwomM2;(?+ z7{@uqIL>{>aSk$$bCYq5IgI06W*p}@<2d&j$C$u4#tOzUhA@t?g>j5IjAIOB9AgyY z7`qt9n8rB9I>s>uGN!nS*vOc2S0}kE<)}__RLWhQ~h@2X>MJQ*P`eH>RA~ zNzP2Uw3A$#a%?9#Hs#(U)$%eW%i>?^hc2T}z|BcWKJ}^E;SEeIL`P?`9hM&L(lH{GClh-`T7Xzq5(! zR5OseuD;6&Ir6=$Y=@(gtf)r30|&206UGLmR<} zd#b;XpT55P+n-Z8&tJu#!BRjE#Vd}*D~`o0js@r63de$TafM^?ievGLWATb(@rq;dievGL zWATb(@rq;dievGLW1(}-|9S4Q;#j=mSiIs`yy95A;#j=mSiIs`yy95oULMb;%+5(x z9E<#x+bfPm?#0&?$0EA%b;YqrU--J>Sj6UhU2!a8E55Ec7O^c~R~(Cs1z%Sji;Nv# zR~(D@YJeRS$0EML*A>SizQorR$Kn;oB6Eb>L_UzQ;#lO|X1=b@^_6p;`MNsSSLP01 zk8_H#;#g!3@^!_rc*U{ET;?{4W0ASf*A>Siv4XEFjzwY%UsoK9#3jD2I2MUxd|h!Y z68HGJ;#ee3^7WWUF;*OlCoCKb`Y0R=ek&XcVytj1xR-D&UU4kYO*j_BSm9U@SA}Ci zTosN5eHV@eaaA}L*h)AS#8u%~U|Zo>5Lbm`!B_~#0-q6%1#wk47L2KIEbvv~Sa9C5 za4hf*;aG4!vv4f%CE-|bp0jW)@IB#JaQ?G!EI1chI2Nxs7Wg*K{bu`<&*MCB#{bnb zw-v{NxGEeA=B98gh^xY}U@i;Cg19Oi3+BFXEQqVZu^?6m$AY*j91CKda4cSNEQm$I zu^_Gr$AZ`;91G&Aa4d**!m%K(3de%jC>)F2%fz@U91CJBFgOSiHs|Y#V-er5=t~?sZlgFB@l|f4I2Od! z|Mr>lienL9W%-I@5#Q$Pier(vz}FSWB6EkYD~?6xK3`WHi_A^Ft~eH%%Y0pNEHd}` zy5d+QR`7Mju}Ey;>xyI1>qm)E+(vOM64Us);#edG@^!_roYWc?>yF5Wc*T==#h-Y^ zt9Zq?c*Vnb#m{)f+jzAm1(x-WSL=GO*85)Z0ABF}UhxKA@d;k>3|{dMUhxuM@fBY2 z7+&!kUhy7YtslMONxb4uyy8_n@huZ0--7GH!=Sy-v2sYjJW{+3=0&U#Xk8;*e6V@R+Rlg@l>#9X!~#*zOHyJ z*xyIK1>@oe)p>#2V7$aP6#sznl|5*TyX;NFA7sxOej@E_UZhF{6vH~dZZ#KEh` zo^=Ke=Va<;)qC8!<`(B2rN0}lYHo4d%wR-d|SjrEZ^VoK*Xa_3i(x`4^cU`ly=!M7<-BoXk4{s=d?$ z2h_f1_C8LuA-7Q&XNjbrm8X6ywnF<1XUC~`pycd`IcTHanbPg0<`!*Sti@%l+Ka!j zZkfG1qu;erI8pE2h)=T4>b)CzAD`uC_8v;~Np7RC{;j;@&+^qfEa-dsIdbZ~IXQ2H z?W5ka)9qmsIbRO8lJn(I&n)N5NzE$XSG}v4#F|yU9&1?{)A-66Zm0>Dv)bSra#kCB z2DPtfFEyWx$!>CX8S3ig>@tjzoL#0d;zRm*XzI5Z3;AtA_enn=EY?Y~p0R$CajdIk ztlA?!$hlz|-se^Ar4~`<)PH)W7R?Nju+!Nj*L&H z?pL)JU*g|JA7iZQs1b*y?iw-YKdrk~?PV_1fPGZ$I^vJiuFIU_HYZc-9_K9DyBLcY zlT5tV$vDP3#v~K(f&N>J`^vip5)aV^dg3fi#`+9_c(wrQCI3G2fzFtK9Zt0~AN2RN zOMd*S#rM3SXZ#*FjjB$1g-A}H2xvqTJkencLa37J6 zzj9yvJK9A(1AY$-d2~OfO~-`W!<2?yb`KlzZQn@^CpX5$jOFnVy}f z`lZiZbpOFS$T)kP--%Q2mg2m9d4Ds*d8BGxpw|?czVE4I%DFx4C+gkRQ~F#}{qC*O z`ILL#RKpPu)w z_%zMMW%~ZIk}2mR;vM9_%(?OL{6@Cnsr>%9<|-A=^sIZ;uSDTY->KKo&RO;)GM3(kDYz0Idg?G{Z54HBhC}XH!`@tnVmBbeJR9q zqU7w;OusV{eKml~RXEf0NHdeK&Q?98zgH6Dp^s;0owDb_#yF3?o(%gw>de~=-&j%o z(%)yv^o-n?N3owMoT#%;PwDRy#XOevS2~|^=e4SRL%siq^XLEcn@Xx*`g=^7o?#nv z47P*9nSN_Y?QddFIeo7aXXMZtgU^1{XYDGPa@Gy*^_Tf(Q_PduKBw|o$9gYV;Y6M1 zoZ&lDs$cpWRhgdu9M_?22Zg~?{poky;@Wl&o(l?RdcLlbDd%XhpQy8f!Bd^G--C<% z3EM~M44z7KJ|)gKj=T__*BR<1)EUkhzG0{O1)fU2e+QmQzIm77%;(5|vKT# z;S8QoFnB^~?^Ju#x=6j8#+iO+Hl8)g_E$L5^RY2j7$@Z63WE>-)9=qlPM+5(3WE=q z_8HFcRx&flS7(xg4?ktUV~e?kc?J6@oxz8T&ZopV>XaL#pBt|*`0zjd_O9v|`0(^T zs`eSqmPf2bJc1n*2Ja!~Eob*24Rh>llkH^jA33ZzRQ72kuvDGJ&xkmv1U%I7>OkQm(;MIMeSI#aIn{Vx5Q>&bH0$ z-03)%S$~BSb!KmdZ-K?Q!TKxgRQn8P{KiGl>UxiIPLjyYFogQS-1Dsp!HDV|i`cX@powkwGL;^Xk&6>}=1$@(bbSnXtS ztZYm~94i~Ef2mwya{m7(<7Z{<%42EmWU;h%vRGQS@3xElY5$qnTUmV(+sN0REDqOB z7Kh7nNQyXImP1m+;j$c(A`X}3kQ8yaEQh3s!)1B-L>w+V$3$E(JD>l@;(ulBve^9p z*W73%M|Kp*6qch>)c=QZzOwpq`f_adSHuF#Xxho*i|u6b#dfmzVmn!Uv7Icw*iIH- zY$uB^wv)vd+sWdK?PT%AcCz?lJ6U|Ooh-iCP8MIx@>`1dV)>ZJ+Z8dtOdt45;+kdS zCXaFchk4}WV^Vhxgj%D%DVhnk?EIwL{IWL#RM~gY) z=cZyf(KvD*cElhF}tm}41DvF3TX zEFN6!5ne8f2WNS1+1~HTXv*TjnZ8<>b5Gu`to}cYAD7h^=Q*cea5i!*i~AO5DKD4B zeT%b~m&@Y5#aYeEWpUr)jOFD8XCT9WdAxbS+0NT4kTskKS?sxxW&e>kA7PB5cX#FGGR)3lk#Btae^)Ln8BIGG&A&W{xx8JH1tRA;(yJR$(KKXB#YhBJi=_EZV7cn1`zdHYz ztX-z_uzA_e&Y6N7WgN@$j4|Dq<&Ed%vOHrzvpB@5+HDqsjC=md~HjXSNK>^Utv?uNt#`*mnVVxh$`mSlhgu<^5o}C|Mp7)1k@tgPkq?Anktc*w%C}9a)$rnb!8{!o!YXKtvx&0 znzR#rWOYOz85VtHSoD!$8P9gIzWk^135$6wpviOi6tu;2_%JNykzp~942yYWSj;2C zV$BF#u#f(qzSkr6!k@-RtcLGjRZo{gWz934-3|7 zFsYF}9{S`V@sk=0?%Ct_{5eYHl9T_(JX(PCKbF1Yp4gorCz+-h%y^VQ6M;z7=v?sF#Y-?K$PD-+ti z$ic^aYji(s!q+u97-H@Mmq#WHn45!VudJ}>n+XdBeXOv&iW$3~XJc?j!qjf)`E0nhvO;)uGbV4(#)39h=t(%toQ;pxR`^!cjIQcz z)N-`K;>u>Mo{^0={#NKz-i!v0*+^Yx1*?)~*w)NO$HrZ7=7R}Wk7vQLzBTq^d72Av^d~TNoyC>an-Nyujs|nsmI^$GBGj6$=VDD{(1r^LVFvx_QuU2sWYQlrg z^czDLq&+d=5Y1ENhSty!&FIhw9I53DMe$^gw|8*k*maWvp~)k$VQ>N#?oi^(XgB5%|*H5yQVG;o-nYT+On_n(Sm0w~NF>vpw>Z$Au1%?Av`?+{j1R4c|8J6eocedbuAw^|1oK>oYA7&sgc<1k%l@4w21g= z6vC*y;ubBQVH8dbO~aLZEn3VOg|qf)xR#>Dn~YI7(>)DA3N5Vnk3y>!^xK76e7ide zE|t^Je2Nx|&!cekV=8`((!##yN<$&1!>syNdv9V zDD)VYhK(;YXc#vNrTV4e-8~I%8b_f?>ok17tbxWd3ei>5;QAmIZ2k1DoP{;jmB`sS z6lIe$5V%f(+GB^q^IEenKp6Uvft`k4*fW84JrO-;>(Iy zRNd!}R!N!Ywj~zod`f3w;Qd(in&XC26|=CaY9wzr@z>-(@gN@``P>yv(O_rV zD7;vmis%sUL~9`NRy8K#6xx+C%CsyM>O$J-_8l2PNv~io&ukJ zoUkb%4aJWtP&dU1AM2#y)EDCUv=ho7O+~rxO6;iUjOx*;s28b3b$4gHACQW=XOswA z>JLV>8%F5wsZiH*Fuq(eBD}8}uTloX`mPb0bT#ab z4@SsWBi!Dok@0CTnl(*@x{n4=>$;%D=v1_g)1a%33+fnC5xP=?2fbaOJ)DY{sj)a1 zZV%WySP$}bvha!y9Ul%saO+f5yRXB`w?oi+P%4bibOWV>&X`O%6!7bDkZC9pZCY5W}xZ?KCRK!#LkM~{i z;yBG0(dpg54WBNhBJQ4!%f~G@Q@Jb%xjTf*0{1H#{Os(4w$j^Mch%QZZgi8BH-QA9ck^7QFcoNQfIrv zsUP9v5m2VMvl$xPLkD=r6 zEh7){!)(i@Zfo#g>tkvtSHrG&=-4~!$bBjJex;cY!I zR+)<}#}&BO%md+0xp+nLCAX6Y4wlcwnj{61hIpXEX$vL?(mDzEz^cU-D7+Ndzsm!i zy(|bGMCU`LamZ+6fvJ-MBW8}nfv;was;_|R>Nrd}YsS;^3N#$*iFRwvNdFO!_UAld zUSx*leLV6#ywE?)jJ7Z1;rYZ16K9#>^ei5gg2$ulG&3qakB48m3AjGpj0Lab(KKxW z2G29Y?{hq!wwQ?Vab}z?p+Nkqi8!5MMqo7sF0`HmyPak2jb z#@&h*c)BTYZk#vH^tQlmngToWywQBV1-oMu7%{%Kvks-uSY7hl}yYeBJ(DwKNWi<}o`T)eEph`qj0rI|5cuL|)YzIf?m#^-e^ zB-ZoA&p%9g6^jNFHj(BgR4mM%>E*0+Gn}qT$$>ut* zLSBzah^}Zt*EcGhFigan;wFr%p+?)s6L7PX2~)^U40o7-ueD6DnWl#Qrtwg9H9?c2 z#(JyqSUJ&z+K1He+wX5I$vE$B2*jn_|oafa5geD37@@gw z<|K@7k&Bm2NpHVA36~n>qBZI5zuI}DRn=Vdex}B>#ojpZh1T#%H7?$zwRFt_)mk;o zjeSTLvmhl=ji;_YSgEw2$$T~X`1#=SC<}h_P~+HqAAD(QLA3!=xrO%o$4*lH1zXK< zY$DMqA8$rbZHfMe5oTPdCbhe&jTuqZ)tsMDx^q}aX9(j{O?M!w=2TAn?>u9|L>o2l z*Y5o$#5$^xkUS9|_Lwkoq8caKOhouW6Y7Ri`JoADf5C)OMm28vPe8&m6RfwW5zuG? z-jp+AJMD|yJLBO+_djdisxf}Uc&zZEv$3)UKc$REn8A!*Z8QkejfclRGdlN`%GZ4| z!)3UJ*T2=?f^U;FoQ~r}3y%9~IDM}~3ue#J@OGE)uwege4d>_b9ScrQC%udKJodwa z?c=GO_+MHhmvm1(+I)3I^$-i(qx7g_A-grog2UtV813MWoFEGhbkSqzJ$Fp^q5G@S zdTg6L6kYmR@bR*abk?DGQO$y1mg|r*Y#1J0HRDCF4m(Z5@XJz~3l|;kTpETJu4Ytd zri1eJFt`;l!{a;I@-K#A!Wt8v-O$4I^e|+2n6PZ07UPx-!|<{uIIh!TSHEF6ydwu= zELt47G!%{J=b%Hj77IoX#W1tHm{>~#TPnD-*iwSeV8kn)7|47vOO!8 zaz)>NNFq!b;M4l%y~Hw#*SW z_3~j$I!~`34%q)O50|v0NBKIy<`CV51}YKzyFG3u=D{>c2^+mVJ`tbUj?`{ndt7ah zhd(+k?<6Jr}9e_YS89!E1Cb4xA#r<=h~stLI|D8U<#&7=)^4 zEy&R+;MBk#j*Be#F-w7Cp7yvk#)9)S=5fpHalVxW7keo%w1@-deWU%`N`XDz4)DKV zMxB}pbU)*OS{uzcRZ4;C_KwJ+b$I+sJXY*;gjI|gecr@l#6Tx}pKC@nS_6+(J0Z@` z{HL`cUo(k+XfddREB0n*BbnClPw_+Wab-4scGKa>V;AHc$i~@l9hQ2y;Onz&c&^o9 z@ZG_5*5zQ}ZQ3J|gRyFS4r*1_BgS?xmgeWcx0fE3Dh)>9ha6m(tcR-DV7zvu`&f-0 zZq)}PKFfq*%k{X?e=t_QGhy-`Jq{WM5*<4g2et79NVgg!(dkoooxBjUijbCum3-sV+|dpv%2UWI#;dr7&p}o z$4N#ss;@`Svu^0O%Z#DL^hmOChheRm-WzoAG`OP$t^YQMbhvrl9oqxVbiYpLbKRjB zIMj@6wGNe?hT?g1l0h?dm^pbUD!ezL*l-=b&7$*muL-4lN##26i&1*~jQaey8^V+MA5Nxq}&-rt5jTpU0R{hA`vDD#DB^K6=h)d$M=Fjn;Gi zi)=6>cV-AbV^^;*AeQiPjT5e$4alAyf>Lxx*D=X}ytyHG810B#fd+J35JLC1^rkSv zfGEN-84k#4ZNTw>5WMc`fD#||m@_Q|i=WzK=Po@AV?yXI&z|n+^qAW(1bqVRF|3~+ zGn$6rx54(d7I*N-TE-ZrbK!qOJe{Jiz}S%rE-qxpGTvWp5ABcu6w>ou0{bk|4o^VUwU zg5%w2e%@9(p+cRiG5oy!O8VW@-ZA{Vz2>dPm8miOyd6$@Sw~$AKX0Fw*I?Aj7=GSX zB;9KIZ!!G5wcV(}mNSIuy!}vw?w>Bl@bmWDKrLoois9#NuP7~6orvM*?K{$0PHm6j z=k2C*T8uZv@U^}0u@=K)Vz_>l`$CIjUNKz1D)~r@!!|KozdAwhB(uuIaQ$it=`vrg zQeQ~F8cOsxuZ-sUm6HR#jf6&X{i+6y^Hl&FRvw7r`qh?&YPkFo#r3PUZPf70i{koK>|GVCOi^6F+GA4TaW4Iq^eeNU z3RBicas6t2UlqpgkK+2(&rMZ-nmhTN*1fZk>sK?#)>OP*$n~psFE!{^Es*P1E$JT4 zx_2PguiX1+(R@K5*ROhnXpyuwkn2~ce$^uOaUj>PZoJo`Z}T9oU;WWlheV$su3z0I zeX~Pu5ZA9-@6qApgCMS7%`2%#v*y8Ezw)HB^XbH3u3stDdOS%D=K59cAw9mH4CeY( z@DDv|{1MFct0$cdaB3F9^{cmI4LH+3gzHy(LJcVG5yJH=%VGoO(|%<7RsCE8zW9f5 z{p$U4!=J|F@AW(s|4!?Keo4RL9O*G;J8efpv=JXVKG>DufM)=5ngxF)AMy&E?nf(<(Gs7|rF{xLYbzPmbpD z?jZRcIR6sO+boXU!noE`i7u}ryni^8L)=VoRFI{;N@XJt70K|GHnLN zb~T{-)nM2boq-AE45+p`7`5}Jqv16@ZiNKn^O)&$e(TZ4J{VOSOvfvKJt|ZV#@M&h zu*XV|7MFq$esvmlz9(HNBMA4-O~c(SIy~|Yg5}mUw4w9Ur)?0D{+NbD()G^03q+Up z(^0v&j_w%)vEP3>l8@0|NC-sFUDHu?sTR(@ff!ML23nCmuo;0+sb=74Z+cg+ABYA; z{a~Pd(Ytsc+DH4LG|5fZmkW_s)*pFKH5hkyAv~A*WB+vx(n$xX*m@?6qyx0Lxezn9 z%|vgyvwZt-A(}YN!rD6;-2Si-PcF>DKGG#tRtQ9#$82;dr^UxMfjED8HZt32F=R*} zE;-LZw3`+U76#(iU*=$7s1|!If%G;Q0PEFSgk228ju8P+-qj+$To48t0x+3$*b@DN z5Vs`&k4EZHbY2jS9}B=tjqXqD>dTuTtb82+^%@--tPFz7y#NgH(BZ($Af*2qfUZB0 zo!2`ECjtVHzD0|24TEsGS^y5t(Bk(BLGaIyoHLJtF!z=}G;=k0)GZhXdi!Hp ztOjw0U>H{Up{rSgPS0pPwD!a3lNvZXhhW3@8Ms)2Wb29$-0+!!7NoaSDHVz*EoWeX zPK){DLXlW%26kN2;`WMA9Hce&TYDYqz6`~RpJ%`(N(bAPVMuhDf$isXFuRALMEVT; z(L|3{{$V&;%ny6~^!OeahCjmn@SOJ4*?D28Q-S9Cksf;|grVMYf4J5#z_V8v(udGq zp!IAi7lz+I%|yPF0rQTAB6#^M9Co997Z!?@!)N2Xy#Z@mgu?m#Y*Z#$Tqp;*V3aa6zZXqEjIl-eoqLMCh?*aR?gdW@GCV zJ^IpFopp6KhB)Zaq+STZf1ZQOjp?^^=AW^jgGf3Xt@DG?(Ps{__v`RFAQ(IS=U`(3 z*}(&(ayQ!V+ZssqtG3W#c+p@^C+&?E>z)U3`hj%s=zBkix7&p5rk$jVGJc-S(PH)M zAkOEDVOm@&9nAT!3oQ~_2J?Q^Asyq6YcRHHX2O+pkA#R|Tx~oPSFE&XyNT?wUH;Ja z)uPhNU~KjA$NSObW7ReU-D>$`LZB9DQ$sN3vL7yH(r+zfW3KQ+2RgS^H$srF^FzgN zS{$zuiaN1=_|j2_y}d(uxtFgF#V3dI`st}UOp6KSbgGj*T_Giu)9*_1baZwoZ&%w| zk0M#2oS%b3^r)N^%K2pHz{Ai`&VN!g-BHngB$vgTFO$pS z&6mk#@#f3qvUu}la#_6jGPx|?e3@J>eDfu_T=?coa#_6jGPzv%=1X!}y!kS@T=?co za=Gx$m*lc|^JQ{by!kS@EZ%&XTrPa`CAnPq=1X!}y!kS@EZ%&XTrPa`CAnPq=1X!} zy!kS@T=?coa#_6jGPzv%=1X!}y!kS@T=?coa=Gx$m*lc|^JQ|m@XeRxvUu}la=Gx$ zm*lc|^JQ{by!kS@EZ%&XTo!M>OfHKzUnZBun=g~gg>SwjmkZx~NiG+@`I1~NeDfu_ zEZ%&XTrPa`CAlo#e3@JpZ@yw(1$|U-x!j^}F0|(qTrNL-Zozo+e_(R?Y^nt(GU&aS z3!>?6naO4E?`FJ-RdBh?-igK$W^#FQm>K&t3NDxLIh*k|Rl()*h!$pquUBxn ze4Knrcb}xYWs=LEikb0%{PCDvZdJ;RS3fJcTpm!1>I_tJxqQ~fjOz2q2Y}@Ay9s8P z%t|ho15)Ts;hd7o<=-xuQL?Ct%jIf~Ea=vb-lj<|kC|zK-!K)I%U*jdP|sI!xqP-- zE{us(hvf38$+Pd~^Hy=W?0b)VEqbcBT%L0^55wt>hRNmCzmcEA zUApHdxqK!)539((g30Al)AP`ee8!kuKHoMEM_iR$E;pgK#kr8rogDu? zk2CP^G>=KNR+%o>xk(jfu(Sc^h+4ZKjgT<@)3gv&3D=<#Ml4xtQOLe0xYPyEn~6a3iVw z8SVEm zh)>N!GaeUJa{hlkZN~m8O5U%{bjSX@xsuDZXS=Dqmy*l71qaMnG+N2!V5{?H#Lic8 z`MBtJGqxoux!n9#)&eJbUt@B4Zf6SyoF>0qlFP?DE!g{ve2_>kuhd&`w-oJ7lFKQ- zS#YDiikE-=Xud->(tAdI8;^wjElIQI#LS1%ugOx9zwG8mIy zd86@0Jw_c1#yEvHlD_H@Rw@KvOL*gZ57Obghakak5)RBZAbvs!e(aqHWtssE!bsOD zGZ9wX4A`IxK~wU9`EtyF%Za4JM~}yh(*^{nLa=hD7p5IDV9UG^?ELPDPU{WmG@S0x zoIEi^Px^l=vcYr5VflCihQ1BP=<4Gzrv=#yqzfU{19k4}v21oQLVI{%WU8L*gJy2nm78QYMw|Wdp7MB*|YmRaq5Z&r4B8` z@(3@?qkA69wuNZae>~d%Lh%`dE0>u7SHiwjXXfz}Q0mvqu z;DZuFb=W>92m{C$;=59^TgCj=Z4?fp!(ttk!elijy)uMgH2)1XJ2Ff?rLgWG%6DBe2^O#{8LN~cD; zZx{~ko`h9X=w3ZNjQdEGa#y3my)Z=ep9nuEHEMJXM{~^tR2fdbPD$ZteRDjP`;#y5 zr*NFT-#jtQQ-j^kk#IleiJ3H> zy@MjLcAFAT4{ z_FW|BrzgFY9DNeW`J6>>YvC6oIsdcA(jCjTNZzj+bM#0_i^PjnldyN89>o_%qR4P> z^r!OjLn5*3jW_mr>hVkCNFdG!JA3I-?_mTUl=j8vDtf5N-!f#OFLc**DBCgueb4yf zRGJR&kA$OGwaIX&H@78o!qLEPGA@)N8(cPba{Tu^dg0$`9v`_&>*upUN3w&~C;1fp zmZZbm=8@djsE1yM_T{LYe4;cFz!)KZ6VPG{Cz4L)0k zbNXZVX|TR+IB&PoQVq(q59j>c4$$Cz_i)bVbMil`<4Wbkf1}VCVMsw#z@^;I&(cw@)BTV;=Rj!W^ni~+k24}#CL6#PoDWFs90!mU{fj^0eb?p6J9 zspb;Qy_|%s(tYq#y(F|NtLN{eqhBmVemOn)usXr_*;2G3f0Ax~PAK_E;`9H+^A36g zWBj|nTM9M#^E2#M-iYMq5>9AgMAOF-F4E5kuSXL8=xK!0?-E`fWW=$z5_U~C!a`>y zqtj}&5rK5BF&wqeh!f2vyyc=1mFetb<$WI-VH_#p)f6YPj?PL}zWkFB2D-0dxH!dw zFuYsm#PKU7z1y90!n-d~ynrKAyQyubO4Myb!Ms$CvLsl^tJXRRdhwgd?mvO=76eC)Hqx;;_w1)}?8tHST0NXLNVs1b-M!YA#<2DuMvPev@)H%8o@ZA5y?;|Kk#FOFZ~cOc5&|wAqN#zf1UImJ!8htXcVSn$zmEh8XsmX$0##!>sS}agdk4 zB0g9hJB=O;Pkm|2v3y@2rahBBz6Wjv8U>5w|YdLP7VI&EFa^_=YWdPS9iiMf**zjKMV_g7-sy)d25>{@$686?us@@c->qTM$`Uf^YZ1q3PIJR@!8vf z{Od>=NkdEFY*BM?*F|9umC48G=V>>z(lwYTEii2QvUe(OR zyHp8Z>zj#d-6h;?Tqf3?Q}H_AeKN_nO2Vw%ue^j={fX-+Ca8c;Cr=5lCHfOac!^a+|Fb<5^I@9>uH)I#s`>7Sg|yp9;}#l?hZ{ zz|WcHsfBzpxhD9}xJ~l0pkMng84LT%%EdUa`eJ+-9WicQni*!6lmhkP?8R$fJIIO%a#VV#3m&W{1 zd2ECAU%w z`T4RbwUE!DDXE40YhzOj`(+zWb6U_}RxZYY)feN#=!kJ+^u>6xcEva|e#H1QKE=E+ z{^P5g`5u3IA{(nHmVoW|nq6|>{o2HFhs8Mvq&NgtZu>e1-L(>)Ho%0b^vBDotQ-B0 z;UKEpo_@oyFVUz@v>0APv>#I&3@fP3ol_;u$}OcN%<8AE$SR~WZIpyzLpYWsNecOjte8gw0c|@ltJ~`%e>Yj7vN@qEW)06qg}Wy5E$)Vww`m@8O?dIP z8x}0g!UZpiGtqQM$Cg>xT7%;B%GsjdvrPQ7F9+A+ZQ;H%6YXg10{*Z?gY-=NUMdIY z{CmJzorzaD*|>S32b!odQK~29Kj~tJyT(l1y_1D8p?1L5OpHj*!nR_$wcMtb~qoOjoGxOA0^wN-EXvyh^GZp?BMk+8v(Sw z!-==G*0eUL5BER!!1C!i=&~^rcXE56KjnQ%I+scJv^`+`BIi%*R;=g0&l%}V`&T?? zD$`lP&T4kH?3^Ouyg16WGhD)pds99hiaTX>F8+~)4do>~{kJSky&|3Y4Gpw5Gb9}A zn?*kG623kt3+-x3xQ2CB;rY3*eHL=54MvldCs7*=v-%gP4Tc$=Y19V8jD7?9W0a*Vp>_l%H2Y>5@v0jvq=e`be z#`ePO8Y-+iNcY`ud!oxJC7xKwA3C)srjzdWHAIJXgL+~h>B2pnb-41$4)|3!fk6SNpQkIo{C0-n}d zDC6wlZ&YAv87-nscBr|C@`&8l;K>m?RMIQZX{!cB=zJ?pdUU9g{M!cfM1(Rl^TQ2_D03dN-TV= z!noaiU=>X7hZ|IQX6cKa^tQHJtHP_Wezv12v4AsD&d^(RC`rxKB z`3joIZ?9_~{9Z$Y#pKiTa#wF0qPX+7WW%o<)thpfP|WLB9YS9NJG!ay2iOaF%tJ2-_cbYH4y}xMSl`G-Mvl?s~CSjL!4IIl$xWgC? z8l6$``en)yZ)OSCpfP(uIb;}}LnGCAw@||S-jh8`^T)~$C#f(=C*kxiG(Qx-&&oet zQsUqp3C|;2{#GNYt$CEgCU1s>Ykj6S-rW*zeMo_*x)T4@Xbq>4pCzMnEQe^!;0jco3}=ZNm~{u}2=epbuRjoh580d;KDv z5v=|Vvg4C>N^4k6_Py(T3A6HE9VN`_M?9DI0;5yy7YQ@^hw0u&wA*fkgc(1vT_w!; z+|^XVjQ<(+CCvII%HNZHFY1>j`(DsFK=!?$-U+1 zUi9k<+4rKqtXzx(t1rff(Glau=!@}W?TT?`{D|>qe2RHt{C7%P#>XLjdI~=5&*#`L zGZmWx^Elp|PxlqBxg3{D%|h{el09BFH0Mt_9@`t1!O`3qd;L=28nX<$t6QP&+!S1% zwTyCISs^|w1*JzUL-IQ-+|i_6_?y)78kEcNvX0}{lX4-?rMcUmVo|$O93uIse6LAwYFQ50 zHa{0PNbW2??ug}6aD4ox?wqtMgLJT)55e0#CY! zY1%0lPgA-ey+;$|d2`NPE1lXvUc@i*RqAJz5h@)6+$`wa6aUbt#9BR>{wb z0oLTpNjl2eqEHU3W5XJA@ zwZ}^G=NV3ZN2%o;vEPGqjO2xw@WBzb6ocj+vJl(io#5@G!QlWYCbyxl27!y?_`Ys* zJRZ8@l6)DlBpy}XXfW@P6&?{bP`;q$bWat(G#>NmTwe6b2IbP?;qyd|g=M-!pB0a~ zv*NM2)j$+K5RdiO4J0QtLvVm#HzPl(1PUSO!8mdI<^~ThEqO8DjzYn3tC1g zVZB`eWoKJ#pgHlM6pQg2d&4wB`KNR5pUENoUp+JBXK%ZwQcjO$BrBNh%-&^$?aZ*S zof#IkGsD7mW_Wsm?aZ*Sof#IkGsD7mW?0zH3=7*?lr!5|)MvIc!@_oESlG@Cvv!&7 z%&@SX85XuP!;F7+*TFFBm;ByCj)krL_Z^6Iea#l{hQ*x~ z!{W}0VR2{0u(-2gSln4L%=q8BobtF5wh7C|Valh+@MyZTT`^L^=i;+)?{pk5*WAxU zpQ#eA*C7+XHk9zjsq~KaIhNP?-Iz`e8WJ`gN<(l>sm{rdsc1Sz!lOE+V#E#!-(Nuf zExn|+ww+!IyUP+b^jnJCN{KhW(EXU8NO7HLSj{YZw-G4a35& zVOZET3=6x4VPV%WEbJPFg>7rJUBj@jYZw-G4a35&VOZET z3^V?j9m+84m)s_mV_^sVZJ$cIgqTORHpDzKEas76F^>$3c@*V;g?%cYM>bz^Cw|g z_>(X!{7D!VbH}joCt+CllQ1m&Nf;LXBn%6G5{898i703OB%(g^Ct+CllQ1m&Nf;LX zBn%6G5{8983B!zk`FuV2Dvec3%5`^jo`gr9)?zy4(Pj19k^JeSkZ_ib7Uq@`?nC}u z+=p~%rMg_Mm5_UByk^4cy51J^k z$4R2!n0&0-ua~f=3+1_QA@LUWM?4aiN%-P#@o=`1=A|Loo3+U%Wjy$ht#{5vlAB+t zeB>nwEBBL~I9fV0KmLfvof8t)yD6}da$U0DzS=;!8_D;W;jS%}ls8Gj#queK;&TZv z?Wn?{KP3ElhYD;A*_qGAP;T#sQr}s5?jFjO6ffZ<7d6)9N%+S_H6GoN@Vn8J$Ct*1 z)!#(-{CO$~U+Sg>K1nQ zS$|*}pO-1LPFlQ{aIJ79PHWS7`JA_O?_E8Ed5FjBpWp_xxU# ze8>oA8kBHZD&b1srQfo0_FFj}b|=i%1G^Ju<)V)KuJ|8)-$(u(qEU+^d&mEQ3C$@_ zE2CM5zJYTfB#+~pIT>hsFrVWQX{r1!TC^)~>%V$0E&r~N{Ch*pW?_9{I=|e0k$*?2 zH|5!9byf{Cf?>uF!@|Fv>Ce~6Z=Tipl9Yyv1wOh3Csjyli;U{aPb{P+%U4})w42yOd7VR=D+GSX@ z%dlvdVbLzbqFshryYjw|UMh{lJ|pG2k&O>4XXC)iMhhauXZUa`2m(JS- zAxq&~Q#xa(r5kbTfP~XlrgF^s$T0gY!_0PLzhzkbmSOf=xt%4q#TZRNr(;p+j_w1k zhZTb)+^Jm}w8;{_K3k@jOy4e%@y6(|ehE4Z3pxx7It&Xs3^O|H z4$bBIT(CQ|VrwY}dyNHXNZ1nkQij@T7BxKuj4F^GC@PhA=}Y-GUl@4( z59M-D=C*;;3BR0;ZWj%l{p0&+}(>(*{ z|3}kow0vve{rXPd;BqaUfFbmKhc4BqykP=ndb(q0?QFcWO+c+LZkXLNn{p>5z$M!a zSCEbR^Am7vs2lowkw0Wo0-jf+?@z^MBY%AYQXjaY>U#2FJDC8xBd&OJCmRDFCt%HP zSKO?TgWf-+@_x=am{>KD*N=$ILAAz-oX*D$bdT63k<+hpKZm}tmB`zjUCD%79TGV| z%dJg#)GCqlX&FlS{Oc!j{ufTAd6CVRJfEr@|D9X)Uq83%)Ys%^V>JiME?Llrd^Q5I z<{*Ib#!ow-!O$`RlrPMJH1exi?nk+~=&fhDj`r=r032Uy!Q5HoYgBD6CM8&K&rO4K zL+9f6X%;*o9kNB#TqO6RoEtSYh|QRbjpZ$H{zl&{$e)YDlw;ZL0ljTgxwqMjj%Udi zi0ZeX{NbVd)SS+m9%iiAO8zTEUrX<&B{z}(54CG^%Y^lW89(2)(%b8H%9lrc7E32z zyn__~O#F9@C!cE41zEq^(;2ewDfuTIml;Y}%|NNsC$mdI*FG7z0&K=>8fA!oEpDV?4xp3{S z8mGU;ae0yVkbElc#c?@O?+*EU9Es!dWjgH-+f{K~?i8W*UR)o?<k7}uLtxg=5cVF+RaGUOvnH)@^yfwRD#q#=NgXo>~E`6(x z<@9&gpd7;IVtKpMNS^mSAItgabU+E)tFfF<8?xhuJc#A|PfApx?R)yR z7s>I7u}Tap6UXJn5_$t{+c=KPkw#>6 z6>2q&=X5+8tMQ~=Jf|N%F z1)3Mxe97~g%JJVhPKV%MJ;$lv+ej`K$_>mG&kCdmnXC#+9eib!H9vjK!(WUkpG^KnXOir7!J?nwu8tQc;|aCWgL4QaOs#Urjk-iq(kX?H0d9xqqui zaejK0Ab;D6QJl|il#{`+cogTqYLxOk1eDNH#NPFL~8kc(#gp!>rL^L>$Zi1NIxr~9juzUaBmjED4{g0}T0<7$E# z==ZF)NgqpoN=C@>(|W@y7d*9K7yBjzif{%A+x65~l6VK_cag{8DEUEYf^r1 zTA#BAYRUGA;p^7ck-nAiG@7sH_5HOdema`3^J4TKQF}u)U;kP4wRlQ-%h|r@Mc)zi zUO+j_X}_GgL^)?hNArCYw^DsukUtU zjV4c`IGu;|<}j4Lr@-i+2~=av)hOO>Jl*Gyy%xp!8P!S+w>wdsPoJ`skNp{y)4of2 zr-I$LDBiEsM=E$#j^^w3H0ie;TSfErJo<@>;!3ET_Fd^uD%=_$&DZ~Q%IjV+Jeu!| z;}nm-I6a#0m+m9fP;86l`zSVw^yiC|6Q1_nDDvs9`8t~KI~$U%<$j9cfdjU_3_WX zIqJiux6AkGYW!#}y>G_Q{{7$TAM(G|FY7-OTO^O|lE1x%TcmeYyQeCYbdhi@y-mp9 zrvK48k?%qI`}L`Un7EbRls~+O^ycD5-z1Xfcls;xR{dx4fXUA#`FrU9)>s?)Tl0VQ zEqlW@=}p$Si@qJ*OnNu0eO&RE`}51s|Nmff+NLqeR^oXV)u0VHlYnlR@0!v;B@R?VS{`0=0D3d9YxpL zKvhddCatoQ^=MQ|E>n+Ln~-YNZXX zpQjwf=hAR|vkg{+s8Q;18on;K!NWK;?%YVD@6u6x6UEE#iBH2;;=#Q&egAoC8it&) z!7r3gAUHG)_B(B`knog%G(0|NgI6uoC|x`ar%w<*LU!NhR6M?7gRJ8!WT&TM9pWBA4<7m6)o+4ewOSBS1X+tB~6_74|P}uz5JedV1^&G}{pgbyKmG;{Vq)v&S^+M2wz5 zv1e*~ENVw@_+)!WQmmZ8DG>`a8W`xCm1}w@VlUa@uhZ-iT{aPCC}+YG`o?9M2MJi* zpYl`ev`4Bh`I|LSpy76VY$89zY%2w(?6K$h&fksA!rDK&qvxI^#J^65I*eiizf=8} z={Wj-vG?9lRutX4KS@AxQjj2uL=g}{U`{ogBspg!OB9ft1_l91Gr+(QhBO%_G7QX+ znNtS|iV{S^07_1Z5)>6BD*X1dPxrkgcZ~~wzJ6csUHrjXpS9Ut(`R?}(^Xx&cTKED z6(8^ziED?2`c|U=&TVXTooku^AO+I$G=De~G!)V6%YLtU(6*S?#H-`V#uPwM%MAk4$^Q%U&xo15q zb~XCr+W=a%B9uOuUyUYy7Cpzv>W#*6lw{i~C%klds`Fm!5;D4&l=YOk)s#$y1thMW0FVuPd zpR5CH)|W<2Z{!)Gj`!1C6Wgqd`!v_@-8;vh3NLWc)q<<2JMW(oJ=TYoy}gQxalXZi z=bOcj;G=q0_e3K&1enRvFwh2kg1PXN6=zcIg;kE5uj z0i^3Src*D+(I1s~Poiv%xsGxy?*|q@X%`w%?XXx1`N^LuA8JHByTsC-L;mz>S|gfM zD3->p^XG5r8&QFyF|?BF{xo~JF*RKjLyw00^FA$&>HNFAk4#6d^^?$;j+Kw06Se)R zU4|w!=J#m&sJuVz?AwHf9*?G?FZxrhBTcCArf53E-zpa3XKUp0X!_#*EK2;ODZMp4 zn(F>Ci#j%JMh{0vQ^6lOuYGMZn)yLA(T!OWlVXFSsWs=NAU^f-aUH?$XHbh$P3c6Q zNXo&y_jD89&oYw6vQLj?P3U9(1~cix3_8%M37xvlbu>@Tpku|F(133v$bDo6W%!{n zWjY!`75B}c%X=HsS*~X|bH@y-w5Bmd#YfPcO*6e4uvUdzsT3lAGpohrff+;3B8$m>n$Wbt5%Iy;4OzT1SV z<_)H}y;G=3U=zBLC78BsnL-6WX+jkrE~dV#r_jYaO{m<1#gr5|h3;44ebSkyO`0OH z^3NRnY`^uHPrl!}`A*&(lRV9}Da`SV`OU(={he~hB!5Z@ev7IEM$xDIT~Nt8)#&<` zC>poJpWf;6Hobg5iu70hbYoymS~hbfmEv!cv;0<#3a2ij=$x}CF70jJ7j+R?_oq_L zhjr=X$3YaA;UoI)x4Lv>U(mC<*<82z|E9XxW}S2J;?mva+rX`t`CGWVU8x*@tMS^g zxs>B!SE}+nf48xl_xaA-jjCM_p%wg1LA{FIsKu8dv?ql3i)z=6mTd^34!r)Fb7nWH zxSVT8b8Wz;ySve=Q$nab*F_)1?dR+rLKj})dV&evX+&KKFCIcK&zi$E zfP2#JTPx^t!8!EqJ>GNb^a|b+bT&21-j8ncegZp=aLvbE1L+>ubnjZ9pOvGBP!8V^ zD#rbG?*3s^CQ~Ra2=}L;+9T;>{tluv*KN$@JBo@t2&D+-yswX@Pn(3%Zmx^|W#DKE znHENuBY2O+-J_}N+Ayk|=uh$Aj3%FBVHCB6zvH?+n#SD@qnJ~J)UVaO+Oe;!zTn#yK$rFr(eS99@mh0Wy?rvTsVSu^WJm5 zAB`a2+7WbX>TG(o?J#<=R|Nh10_Sp%7(zAPi=b-!uBV(DNRukC|4go3Grtc#S`|(g zZq6mYUwTsX-7u~-&3nmo>p}D8g;8YTKi)Ys(VR%GVa|0VcRuPwZRhc~oSbXj zzeZrAfhp|pwrR>_&2DQo>u`jz|VxfPwMRE1D__%+v&jOk3%xc2x; z{)V%1d}s1J2%(J2=F;}i&h#UHr!}o3$AOPMGAM-3aNgb{ZnJ9D5X!S<4!x#2)9mL$ zsCoA}l=1n_l#%!E_=(@MTszc>dY)WCqoQV0?}eS{xl=2sRfE}-t#v25d36Q-b~S(^ za&)4N*+Xde(g6BpPe=ObZT_~8uj$cg9qIMqA=D*j0A*;1!8LI+OZo4}5=nfvF; zWPiGt)`2$hcTty?`qPy74s>NB*Wu?eTh$pI=-d2ZbaD~bxES1ld`5)P0`8wRdv~A$ zTp!*y#h;3F?La-a9z{d9KV{;a;WCfH=mFOlZQZm3oqI8yEbgBzYIY#16ix}J{i#XG z4)lQcDL8+{pB7~7KnFU6(=^`ebJV%^G_Zd-)p+1fZMU?i`J=;WYi6#;H@iK(Ifd)O z<={R3y0)iA0pV1P$Db3+wWkB~!)bCsuC;fo9q+vmPU{Ns`?BrrC`YiDcdctKyqo*{ z$N|mi3itW8yr*H^SDMr4x#4u2-`#9I+l*FE4X4lV@qQRl&FI6C;k4?8KW!b z{59qrGm4LGTPcjDaXd?Kn|HqqrJv&b>0ZBPw3**)X5Q~l#kelqoud5h z71xcedbkXASqrLuX$8#<owoXe5+#4c&J9DF!(zn~5 zoJ%h?Z%GyT9b3pZbLn8GmK61RC{5#gKNJ|zlKOqX zddT;3;;xoda|-J@-*@}3wxk_Fp;VRc$7(OOA`gH67sdDfi;Y^*J-+v=@cp~Ww-wc2 zA4*yH9)EsqD|&BBC?)ZpRu{f%OAEIJ(>Dud2-oD=DHzA<%54ba*oTv+(17u6sA|?= z>cxA;{jj|a70VM$!xv4V+8Nr?^TmSc$f_yS*J?|lZv<10ty3suL|bZBpZSX^6tJu< zec2_LKD#i5)JFCn9!$q?PvKnQwzPg$Fnybq_ZmxUORXb=X-}@HbmBx?`hHDtx?}0- zXS_ARCZCu~#V(Gg-4~kE5Y7Sizcrp>c`u|lSTAc9^rf*qT2eXwt<~%JQs8r~sBK-Y z89dIH_AYBhE%^Jrne2~=WT zYr4SoYb(c2pu?%HslraKVf^g`>d*Euyq{I+G83t2U~B5pbUs~sZz6@YZ%qMnxGr+Y zM9P=7HN}2DpB{WUkut@$qKS{@(+hu0q=9d>qN{HPQM1y1G$*Ac-Rc@dM;iE1wo)x= z=cFLY*3FOf>=qQWB#6ci@}o`Hnp26`Ai6)4_oMuX`|#?ZKh;Jv^H|J$7&A}CoadVJ zyE#1XLkzR?cSAex%#s-H`zV^0XY-dBe!|}tEiK_MG5ql;?-A_dFERWocMN^T^H9X_ zgXS?*XOzFhaAH6Vg)iXeIL9z#AAfhlT89`;${kC=tOJPQo_4Wx`6qtPvOWLuSenne zgc#mG9ZSDd4v-j@DG^5_S%(qBdOW9|*grsGSa?w!`A-Uv7|#48j$U05ATbR3A&$O{ z43HT1$Qw^n*YLQ4V_3I*JZ2Prd72D8;`eloxhTm|lype4vE6<~YxnDW^V?Nve z^#8s6PoM2O|7_p+*UI>FJ@o(VzVpxx>^r}dpGP&$PoRPOMo}NG+5bb~iIid8D0)lH zrz5Q<($T4-DEGMelxg}z3a*d6?C0~hU=yj~uOsQrOY`Zu3lpjIvXQhSe-L%c#(NyU zF_L~zL6p0KA1&E3g7Wm{Z?fOVRH-vh23!?Iw{OIbSA=I@-5EVK#k$f@^q24)zsNmX(R3vUNl|0RR;QCFZ zd+!dW9&z)jZsUnm;N`*e6W906oo^y_y)}q-zBQl9el>w>nh&Dwyw}^f@CkG|Z4h1B zI*-2V%k@al52DxknclDB1X}#ZAX->^9;N;2OVuh3rhJ*_(F?n{PU+CW6nr3%9xU)B z>*K+caXIg8+TWKtmKZ|i2L;j=@}=3chtU2yJRd6IOD|{qfP#wi8Yb_{Txr?|l#Tag zZhe#YWzI2_;;zl5?w7_>kL5$@(=&4^jK?r}Dh#6)JccQIZafWf52HFf2fB4-Je6uT zoRTljr3<&m^LN9;=@YJRx+b?T&E)S`tK|%&JFolFv9Cu^#Os07s+F(wt7-hL(97d} zY1@X8)NoQD?TYc`_p+m?`r1JH@PsdUI*y`%OMx^i=LBjPG>Qfkn@3q1OrV)tNAb7v z^C;t(3G~H*QC#zi_i*56^wQV*(Od0fY1t3FmR*$haps!IxA^^e#z%eW%Y(7hzYNch zcn|2r>~ZuV*NI)SxGzQ3jiaNT1E^8MzI1R*96cHuKxMw~L)~KHD3NQGCV$w6W`7w+ z(--l4Ia?n}{3VVWM)CgX{_pX7aehYg`}Rs1-lN53<0)l5KlexXCjYnNsUW|fkH6H5 z_VM%j2tT{2Z7;Hzf8hCb`CUEfaw3_rT=CSN#|D$C z^q>bkHpoAPzms%#r#pM&DC-b@|In^G@1YS#vpR5|!JTg885&17IEUa~VmG>1D~`gr zhJL}}-DqBhILgfH&fVVWM&0+s(t@l0G@0L-bPb55t(?1dxpX(0+$@%U;`w0go89QM zT(PunG3U4Oyu0$@7#iT~Pt_-PqogG<zqil(!z}tBXKy;g-}sFCc^17E+M8O8iKY+k&7x~% z-=khLqv>cCf0~u_9vu#kCf|booPXbk)b?l+y$b6?B`-(QTpsUj%iNbP<%yvlZTu;% zdtW+ICx#T)%JIbYr7~k%bu!cKB1XsZr14Nc_xr11$UyM?}pM$-gDu8mo~KZTnNP+38b3*USbQs zdnvjnkfvnsOdqmOo~`^1Bz2~P?Lz5fd?1w_*_n zN`E=GI#U)}p2mD7fEtGLyzF!kWx30FKLcCSzN`E^%E8|x`?RJx zzXwr^;Y!PfLq!3A8eWHwd5+ltp<7Vun;_n!H#6_szkfWB-sn-*MT9=w2_<8R`? z2Xlqc_>;WP`W2pwRS2Pi-|+q;w^~t!M*J@H#ys-N(V9y4385pruWJ1Yt;szpgo1DL z9@wp0Q==vP{^!m-YBQ-dRa_H7!`MET=PwtwhtMqczw=FN`tb{%`*S;WUT(wtfN-79 zXYXL2y@UOm?_kZEFwbiEJpDC%%vvJPYQH@FwO`B{6whjgw4tZHW{6q4;90GS;q90{>ek=X#+x9-ZzWsE6+ivDJR=myoN_MYFAzYKK%ksJO$%E?T`gj%n z%DMFIi&UfYcUI99uD@}<(pz+l>#dnJSIwNIznfF^pQ;~g*0cS)HFc3!j5?V&&-l}e z&Aq&xx!dbr&UVS4ZsqWD!VQ1g{)2a)g-*Zo`-wC!ujF;7=eB$KLHPhWo#^Fl?*vdl zxR(p{4WPkGyzIl@L?AC3f45-_uO}yX+po#>_I~c{<+RCMLyYrU;IoTsBXl|A^}l~? zHeKE5<&@F0sbZ*?oA7rT|EapEW<6NsIpZAur)$zaUQZS0fV!;zqz>wn)Ppr^1^?f& z*NIuv*sOnk+Q(aa{8_zvZ;julv0nZEt9u6hzq(gfg_j2D9eIjdBL)Tf*z7SF_S9C% zUY|a_^frTQ8UBushka_N}{la|@98vfOJ8bwrFnk}pnI>%Y zN>(4|JtTa8T$~EtxmWmi9jXot{#5u^y+qBZwM%$G^~I`T(pKT?)8?xsH`WVRYCcCL zuUsQs;iVa>_oxJ6pI%c`-?DMSmu8Jsmomf(=ZG1iJa=P+bG!Pe%J;l>&+T_r(;M+( zU%s!c`YFp=;kudYshLsUzZKK!Ew#GEX0gwwit6-*ZNfFilv7=HdxUFMETcY;-zj{v zLTPm&;WOb&v87elP6vfYM3+;l=277zg)6FzVJC#EmZ+j;HM%5xW@c^GztUCV(g*9P zoz)%*U&vKQ)##qXLOegqT|*7Nom2RwhOerWp1FlD*UzP91?LfNRN_b1s%F`Q*OyFn z?P-)*xTOCoSHsi?(&n;zvt8xx{wmyOo1g2@&7Xu_zmIdh-R_ET#)L_(BkH_xzG35B zI@x>9AFS=?y0FcAt*?LG&b6eW_cxaP(Z`kY|srwV|I24_kD{r@zY^lNqhI z_;fkHN9RaJ*X@2fjoo@-ZTALXZ z`*rkJ7cUDB@FktAi1*y4j8nQ{y|27J5mj_&_hI2C7c1xD`qTbNudV2eCp2=_NcMq-;dy(IKbj24Fg&$UI zu1`D{C*1#|uKK|j-h1Rw|9<-WU%Y(r!w+=HT+WG04zn)xmqwv7Sb9MNu-ut&qq4~Oa^-sj!J2+UEi1A+EEx)hOIXZani|uvR zYC|`)p(onV8Exo~hNj@YV2#nx6fkRyhNgg7V>C1c%o?MiDPYzZ4NU>F#%O2?m^DU2 zQ^2e-8kz!TjnU8)Fl&s4rhr*vG&BXw8l#~pVAdE7O#!pUXlM$UHAX{Iz^pMEngV8x z(a;nyYmA1bfLUWSGzH8WqoFBa)));<0kg(vXbPA$MnhA;tT7sz0%ncT&=fFhjE1Iw zSz|Ob13YaxULsP)4F&dfz zW{uI%6fkRy9>$siW{uI%6fkRyhNgg7V>C1c%o?M!vZjDpV>C1c%o?MiDPYzZ4NU>F z#%O2?m^DU2Q^2e-8kz!TjX^wx5l@b@h8=O{_zNTcd|iZbU7#uOVU6)XQ^2e-8kz!T zjnU8)Fl&s4rhr*v^kUW&Fl&s4rhr*vG&BXw8l#~pVAdE7O#!pUXlM$UHAX{Iz^pME zngV8x(a;nyYmA1bfLUWSGzH8WqoFBa)));<0kg(vXbPA$MnhA;tT7sz0%ncT&=fFh zjE1IwSz|Ob13Yawpx*^OO13eLDje*Vx!-oHZKYXDnVAdE7 zO#!pUXlM$UHAX{Iz^pMEngV8x(a;nyYmA1bfLUWSGzH8WqoFBa)));<0kg(vXbPA$ zMnhA;tT7sz0%ncT&=fFhjE1IwSz|Ob13YaxULsP)4F&dfz zW{uI%6fkRyhNgg7V>C1c%o?MiDPYzZ4NU>F#%O2?m^B8^M-Lc%8GRazK90T)M&HLh z0LDE5O#!pUxS=Uv))+T51F z#<-y=VAdEnGzH8WsAH6|6B0%nb=1x*37#`r)}z^pMYXbPA$ z#sy6Qv&OifDPYzZ7c>RT8smbdfLUW)&=fFhj0>6qW{q({Q^2e-E@%pvHO2)^0kg)q zjCi_?IAh!>KG1mMx+rK0j%AHe&=fFhjDn_sSz{D51G=0?yI*fBSPrhqXw zf~J5mH-e^sF*kyyfH60MrhqXwf~J5mH-e^sF*kyyfH60MrhqXwf~J5mH-e^sF*kyy zfH60MrhqXwf~J5mH-e^sF*kyyfH60MrhqXwf~J5mH-e^sF*kyyfH61vGVA*i|49qO z^qxjtgfsNmprvYO<-tqa*9hU3J`~v z6<*agPGwk9L^#B6rMmf}x3A_&2v^rK?Ug=!v}ULp(|fFNqo5G=@)GZ{U1r3qvi%l_ zT`%0E?(y!o`0a6hHmdIDa!Q*4b5hh~tAy~C5lO1g>gVJh@z1bX9X{*Y3jYERLsYTq zi`?MTb3)YZ<1K_w9ST!H`KJnRKfF?9=rKe%W1%%_L6M=t18&BtFFy|x9?5^}-nr?* zZx%{XA@#kwF}r`9O6lX}uBTV4!0X=ee20u{Rg@o7RZW&85qgI-MZAs`L`ovScISio2JqJU`~q_+9Pq z*3yAN`Gn8psjou<^9!fuYN_*;EFj!zY*)S0ruL8 z$+N;g#t+iF(t@QgHOewb=gsho@OS$M>Jd%KxzK*d@BQ`BA8QMTH6E&e`K_Dq^qyn& zvC@(r2D+cNQH}(mSxzJtj*sxzXUu--5XwG@zhb>#`h_qY6nMXI)`*&nkIL}Lk>*gz9bd>T++2z1#9OI_E8~);-s^g+8uo zi+$zM20G(&UVibQOV>^H`sB<~N%t;LLwq`JeMJX1@M>nh8in=4Ft5*Vh4bjLQ@naU zKO&1>`E4Wd|0eP`cb;Nxgs5!?z`@F2l@-&9#+xaCEn|wqv!q9A3Ay4>E7mIYR9e<#i!I;p42k0Oc(Au zYfkFu+cSl)%zig@?#KY)rW)B7MGR9d(K63FK}ILG)&qFOp0LKln z?sVIgy+m7K*TdT`+#_+0L_z+(ec)hwR~ugEt>eKBf>aF?)& zYJ6$$^Yn$GQ&r)-31XiZK3(1ZX^HTdZ>On1fA4syec)6T{cT^d4}N#N`f*uZ;StXd zQ-6~_)Rd~Cb=ybyshR~|6AirCdb-NBW1#TlpJuA9 zK9Rze%Lb@j1Ah^2)_%6?ai_2w8Zs|!mipcA4dJ&-Ojk!;^@Rt$HbE`!&|Ww&$53Tx zxH7a|8Je$*XMy@;{th|zyIMWfxX>fQ4;S@QBf9lwaAZzf6q9_6&N%_c-*jQt}0Fah5Oa)?YdKBmhkbi2sl2ybcs zed>_B)4c7!`=a~oDDSyViLBuMrMvfhYG$}>ofDSq9y}qCHc}X|e`eV!M+J1G! zo;k9t&U5Z9;eL%uYoqUJqfct1uj&_zos;{*f8-jSv&0X=S1Pa8{qlOpW4S8F>dl?! zi9PgGie8zezwnU5%XHJK-ZAQt4NGf-afwDWwg5cS&1SA{n(2~(}Qd;iw; z9g*s#dKJWf!}eHJ>SRUXE}d7Z4W(KOd(MZekcA6{lM3^Cab~Y37ked6<;w1zpZ5Q3 zmCEybybJeH#rP=IJXfgj8`mP$^+@mdt>ZgU>bVOm#2!C3Mfuh8>iNlX$*RTK4Pqbs zdy=wV_O`!a_iA;!eLu0kzI20XeX*8sLfsYW*q42TYm{29T*F2QKdQS@?M}<(gL6<} zDZ0 zNuhe)n60V!ThsTg(AP`lmcP~SP^4bcC6n-@J0ZGnh}T}~@+v)~-U;!~a4}lndj6R3 zzW2hl{T{&Lca6?_0Lyp}U>WZLEPmH$C7hSBvGwcnY*xN(u`WIbE8&yOR{kk7gxi+C zr`DJE6W;#lS5@Nvc;Qp;{;W>S^4hO{^^N-J(m1hyy!*WBQf!#;#*wGg@&Y}C(;6OA zbJsN#F8<;nl{mM8@K;$5sIjYa3jf?{uNrdxG-6_9{pK@O{_t?&!>@m)wruvnZ?vj? zwntU(vPQUR(a%(!$aBK;uY9I_?&osDr$XdjwSK?MU#tp0>{qv2SYnTkIH(r3Xes>O z+`}s9_ddd*zE{O$K(a$R&If-YH2if6PA=C3P!?Breb<6hA& zE49=2>ZM4p&#?2C)#BAke0EO1pf2^PEWG5qe zh})xln|gV|h8-%Ywbv(Luv--=;5~M1wJl1&SVjEjmDs4xRq+uX+9O%{rnMHX);mF^ z#)(#2Mc?N4mKo$ZYwc?ut8SDYC_Wp1j8Pk&m*=Au)h1T8>pM>D%UZ^%8V}`JY32MZ zUe%71XP$BN>Dh5NkviCWQYx$v~9 zpQ*9UlY~!w`@i1hT3D~P-~C#~yI+gn`#SG_Exh}Uoth@c&drme@-06kJa}@v`mM(2 z-ZmSsPEPz(xN6E0_2Gck$2!$CiigF_~RI{ADBBpE$!vCw^`p)-8dI7_D{;RR~IUI+x%gh zQsLK9#QycXYHIu28-)uVtgPXB3znv_t!iRg$e_oN& z>Vr7%Z}em;qc-e5EIudpRZzA1%G!Z7djr4cn{rm{y>i!5t6E$Vp5MNL##W(&>_|xVdxO+jxcnHbw?OF#JVF49b(-Ph7Pgr2t$WhcZ8ustUJQc zA=VvX=n(6UFm#A@M;JQ9x+4r7V%-sj4zcbCLx)&*grP&MJHpT*)*WH!5bKUGbcl6F z7&^qdBMcp4-I2IKhm4rJ?X@Ia3ulc_-p3o)LbLA3vCtvb9cdFf#JVF49b(-Ph7Pgr z2t$WhcZ8ustUJQcA=VvX=n(6UFm#A@M;JQ9x+4r7V%-sj4zcbCLx)&*grP&MJHpT* z)*WH!5bKUGbcl6F7&^qdBMcp4-4TWkvF->%hgf%np+l@Y!q6es9bxDY>y9vVh;>I8 zI>fpo3>{+K5rz&Kn&Yf%LyMesZD@|Ot_>~HtUGcnbcl6F7&>&S!3tsM5bKUGbcl6F z7&^qdBMcp4-4TWkvF->%hgf%nMTaiQT)=`3vF?Z+I>fpo3>{+K5rz)2?g&GNSa*b> zL##W(&>_|xVdxO+jxcnHbw?OF#JVF49b(-Ph7Pgr2t$WhcZ8ustUJQcA=VvX=n(6U zFm#A@M;JQ9x+4r7GM>2}dyNUtVvq66^%&1$59^LR$Du>4JHpT*)*WH!5bKUGbcl6F z7&^qdBMcp4-4TWkvF->%hgf%np+l@Y!q6es9bxDY>y9vVh;>KCGteQ{9bxDY>yD2- z{?V*E!q6es9bxDY>yFDF|7g}7FS8D@?g&GNSa*b>L##W(&>_|xVdxO+jxcnHbw?OF z#JVF49b(-Ph7Pgr2t$XA@h5T%6wU`aWUoVE{DW&DcIXi6jxcnHbw?OF#JVF49b(-P zh7Pgr2t$WhcZ8ustUJQcA=VvX=n(6UFm#A@M;JQ9x+4r7V%-sj4zcbCLx)&*grP&M zJHpT*)*WH!5bKUGbcl6F7&^qdBMcp4-4TWkvF->%hgf%np+l@Y!q6es9bxDY>y9vV zh;>I8I>fpo3>{+K5rz(7tb>?CbNHVy*0(X%fgPH||Ae7MtUJQcA=VvX=n(6UFm#A@ zM;JQ9x+4r7V%-sj4zcbCLx)&*grP&MJHpT*)*WFU|7g}7VdxO+jxcnHbw?OF#JVF4 z9b(-Ph7Pgr2t$WhcZ8ustUJQcA=VvX=n(6UFm#A@M;JQ9x+4r7V%-sj4zcbCiw;dW zD-0cC-4TWkvF->%hgf%np+nr)EyNi*ggF=(I)phG7&?SG7#KQ)c^4Qugn1VjI)r%_ z7&?S`7Z^H(c^4Qugn1VjI)r%_7&?S`7Z^H(c^4Qugn1VjI)r%_7&?S`7Z^H(c^4Qu zgn1VjI>h52VdxO%U9dxkFz*6GhcNE~Lx(W$0z-!|?*c=IFz*6GhcNE~Lx(W$0z-!| z?*c=IFz*6GhcNE~Lx(W$0z-!|?*c=IjF`KOYk?daC+1FWwv0tF@4~UrA_sb zz|bMgyTH&P%)7wQA_sbz|bMgyTH&P)*WH!5awO5Lx(W$0z-!|?*c=IFz*6G zhcNE~Lx(W$0z-!|?*c=IFz*6GhcNE~Lx(W$0z-!|?*c=IFz*6GhcNE~Lx(W$0z-!| z?*c=IFz*6GhcNE~Lx(W$0z-!|?*c=I49!7ajo4u`GzWP&Vuua$E*uLT!n_L%9b(-P zh7Mug1v_*I^DZ!S2=gv5bO`eE--Wm^DeOH5YM~7&>_sbz|bMgyTH&P%)7wQ zA_sbz|bMgyTH&P%)7wQA_sbz|bMgyTH&P%)7wQA_sbz|bL? zcQHeUFz{ettrr@bfkFRq2E1({{N-Wo9^ zOuhVOfY`q|5UDyWY9M^|W{ldl^Bv)j7DcGJ0~!g>z7nS@9QKZv-aNEcRayM5*gsv8 zq>lT{7oPbbUS%3QS9pDfB(?0#XyL@?<5jz_ynpxnnf2tIsEN7kl14>(#6VFA3ku9;X&W zcM~pgc9~i^!5fpy!7J3huV3-{-w9JE8_3#?HK_1P)#QzEu|Iz*LginwR5;BFRTSg> zEhW>ItD9eYfBUY@%T$N;Rb9A7xwmgr5xaBXeW3NI=w@|3xQf_&CMT8 zw%2PcUa!&idX2^FHQHXUv3R{k+v_zJuh(dMy~g788f~xFSiD}N?e!Xq*K4%BUSsik zjkecoEMBkC_Ii!Q>ov~WfyL`J&YFV7>ov|=gT?DL&KiWp>osnBy~g788n?Y(WAS>8 z+g`7+c)iALuh&?-UgNgcYb;)`aog)P7O&U1?e!Xq*K6GNdX2^FHEw&o#^UvwRC~R~ z;`N$T<2x_sTP-V{@44h#Fnhhm8s1~0kG)=F@p_GqyBi`Q$MwJpTTS@S{+owYE;)>$J% z%w6_+jm7IVE_=Pk;`JJ3uh&?-UZd>w8jII!l)YYK@p_H2*J~_ZuTl1Tjm7IV%3iOr zc)dp1>opdy*C>0v#^UuFv+p@;h!)lm?e!W9Ym0Usj>UO6%Fe^FI1fkJc{mp5;V3%~ z$KpI3W#{2ooQI?AJRFPjaFm^gV{smivh#2(&cji59*)I%ILgk$u{aM$*?Bk?=ixYO zuNLRwIBT*N=ixYOwHD{$IBU2T=iw+j569v>9A)R>Se%EW>^vNc^Kg`%hhuRbjw!c{u!Cp5)9A)R>Se%EW>^vNc^Kg`% zhhuRbjw!c{s|>!?8FI$H@(_I1k6k8L&7H$H^tII1k6kF|arfN7;Ee z7U$t8I}gX=JRD``;aHr9qwG8!i}P@lorhy_9*(l}a4gQlQFb1V#d$c&&cm@d4@cQ~ zI2PyOC_4|w;yfHD*TUjF9480E;yfH>=Vn-(hokJA4U6+|Ty`Fg#d$a`I}gX=JRFyu zhhuRbj?2!&u{aOMW#{2ooQLDG^KdNA!*SVpI2PyOxa>R}i}P??b{>w!c{naR565Z~ zu+Yg}u{aOM$!W1T565Nax>%ftw!c{px6569v>9Jif^V{smi+s?zWI1k5d z=iykKhvT;Ma4gQlaoc$~7U$u(?K~Wd^Kjh8HFX=;+R4R2A8>NC&^NT5hhuRbj<)k~ zEY8Exb{>w!c{tk6!?8FIN85Qg7U$t;I}gX=JREK3;aHr9qwPE#i}P@_orhy_9*(y2 za4gQladOpgk2pDOxObe~Hr!KA&KvGEZRg=woQI?BJRFPjaI~F=V{smiw)1c-&co4m z9*)I%INHv`u{aM$+j%$^=iz8O569v>9Bt>}Se%EW?K~Wd^KhKpKWL7V69_GGas{DL zP7WcoOWS!k7U$t;<;}yfI1fkLc{mp5;b=P#$KpI3ZRg=woQI?BJRFPjaI~F=V{smi zw)1c-&co4m9*)I%INHv`u{aM$+j%(9a3{wS+V13DLi3%ROgsy;orhy_9*(y2a4gQl z(RLn=#d$c|&cm@d4@cX1I2PyOXgd$b;yfH}=iykKhokL09E>U*VT3ooe}sy1%)`Uj5-S7$PK z*NDfDU!}IY-W4D1UZYyw?kZezX}nsyWwCI@s_Rus=vd*a?iA%)HAT2Vu6PyH*2{&a zC8{B(62+b;VXZ3rS(NahUy@bAcam>lm3}Ef`D|Sv_TeShs=|I#g#)W5s*b;S&-r3f zv`UR$CH92cD^$__k;2^%EKxcBs3!dF`zusXhYYD0Z}+L5pel!75U#m8UTr$`3-ZCN zjb&rhv9f2y9uOL>V#{XGuy;ugQ2~YTxWWBUY}F7V^#0vndEOZN{UkB-}qd7 z60)yT6RLaPZx`;pM9sgLD(AT`EkcK0oG#Zo?ox!FIAFWXM_#WGtLxA8&NUu>u~zq; z*hqZ3B(K)nd<)94+h5(RH|#1Z_RwJ)b=!w4<@fFhOw#?wddDQqe^1sqQY0_MdUx*z zy}m^u@i{bmlRg*yvatW+B%Q5ZacMJ8q4j#Ko+IZlvh!L!U{+zV-)j`FM~+@D{w>~& z&`aO)@}un``h{9Ed=Sq&$3mR@!zhkyEA zNqVt0)>h=*CHg$xD;sMoveu4kf%l;HI?Mm@9gy9Q_?T@z%LOWK{ad*}SOajb%d_v@ z{v+SJ$#V_;+>9;OU2tDOi;Q(%+zVpI{bKuwUfDh#tPj{ea=(~9W}DCQwTl01`C3?~ z#65!bf@k01{`2o}IgS!fjDu`8bK#^O6tBUE57uPN_}h$iWaqo-|08!Uz4o8w)D^e> zt(-d6H4p9))}&|k0XPo-v_60xPZ`6SvE}Cq;wzbz@`IF3Gbj}u7MaI``_a$C+`>IE+RH*> z0%J4B|NqDnPOtrE`NQ&F>tD$qHs*lO>b&ti@=xo$8S`|EnVk7M#!NB?!5GSzk7JB0 zc03=9Ik@AGcVCXb9zmt zo1=g4nNaln}2K6>vQslJ%3fZ)%KUXV&ht;n}=-FEp+mzJ%3em)##H?l#gxH zZ*=m>J%3dz)wrjgC@vy+e4F57*8=^^?DizdaRo*Ud45 z`KOAm%#WUm`qf5ETt=*X{#!K=jQQPDQHR{Pr<8H8{nu(Q81vJoqMp2=$xlVi2V;Ky zRO}02Jky_wS`)_mfu~}B2jl(2Q&Ho>c)#&f?9*YqKY1!@Ynb1po8OhgUL&TMg>Thi z2jhG5KlwcNO}gWQZ`Hy0R^9w={qgVF9Us`i_|Dz*dHh>=#|L&WzL7V59{-Ns@qrzT z@9RyU$G^dMd|(IT+kDf<{FdMJfgS$%#^3ZYV{7`P7h5xKW=zcAYyOt>&cSTotUdL3 zO)8u-YEr=tMy)E-=ka=0jt}f$)VVT!%(_^n5A5(qy)4tmtes{0zz%=Z)G~d{dRe9q z?C?h&Et64e3wG4nO0VvgX*XkK9t%6#L9Ehi-}Eu#nO+>s^Ec}@m^Bb!$KORg2iU== zjbQpbUO&O{fgOyx3Z~EFwHF*8*ukjDVEQ~>x54p&9gKPorqAOw9~>Xp!Kejc`aE7Q z!tsF}j5-n(^38RX__dhzO=T~C{jrz(ouBR+ma(|?&Z|iZ?7zO4aEWhbx+b11W~r4) z>SR8D*PGjlSwoL`dCz?>&rO=`I+s|?+E;9?0>7BOxbVV}(_M4oi&^)6U!%Z7auyf% z?>O6aA-0%R=7qHi{6g;H!c99*cjaXJx?5`$_!`^6*Xzu7Me+IfD!5j-1LuT*_qE|R z+1};nHNtb)4xZ(j?P|mJ>jl;d$FLpzdh6+~25jH`(;DFoYzLchd%XUJ6F1nwsLQb| zZmGmDc?#G4V@3?Y@s~p-hPAl9$H`AaByNH4tPwln3HzS!mPxF#P?9iW1s;5Ng~ayr zh&959E!a1In8Yx=b)qn02(DIbxx}#Y8%e^5Avmd6n8fg#`ia7bA$U{6m&*zhTvAsmP-sjESn^Z7=rh(KVo=|__r`4hF~*pX3Y~bZm=VUsD)zs zJV{*?v%ZSi4vs~ePE8fCQ&Rc+qajM_4$zgdgM^no4zs8M73n7U{Bq^EnPrkQ$WYLTfk zriP?|oTKG<_bgOX>K)4o1C7)93M;mW~hX zVAQ%aeIBoe>G;47Mx9L4=kZ#ajt}f$)YvqA9UCYZjSxieSe%qm~iuVAL-%eIBoICeQZ0AX8&puwa)@cXFf}Ogx;JkL-S}^L?;#e?h-kR;0wR24$*x`?w zx~9*Q)YmoZ_nPhCShVTX<^?;odBLd7i(|p4{cE=KBz1rvuOaNTgJZ!?4PmfTLl}%2 z!Z;R;`om^BX1!w52X^?Qjpn=@yt$jlmPUPMvxc+j4?B)UZD-TRtn+Nvh&KJ@4&Z5N}DGRhN>}by>aVyE&NaS z_20c8|L%SCPx|)X?UPT^f70s%PjZdYi?dmq&a5d1JFW$4*1--&tvS=@@p^QQ5A0yn zsWW}ddUvJ|?C?h&Jk#e%YT`X!PtR!w$AX=DdSIuX9vJoXa4ZIZ_I`hnobuSI$>{JX#XpPY~1gOBC>>#Sd<272}i4?eY2 z&FOPixSMO4S`mL;_=^@{>W@)B2wUOds!Nrd!oAN#tBmgR!a;rG)yTcag-20>*r6wm z9qiZ<6UPpQ9qq%%X&>yg@3iwI=TNA^RnedQh2rG=ajbLxPW$QoF2n&oP8`5a9GrHZ zBv!o}q{%s~8n#rW7iaTt!3XW*S|EmC#N=_i6DzY#bAJJIzW~_bk9`MV2V)-r)93NM z1{@#Q!PtYq^m%-r0>=k-F!nDneIDQA!0~|{jJ*#`pU3w{aC~3~W8VbR$J}SZ^no4z z*nh$FF=J)=q!%kQ4(4w(&p*AtYqn|D_B88c!jAJq%}?0DsGn*2JYHkd@qrzT+MA}& zJhh}GCR zDZ+>q_+qaDsff?+1M7qlH*ltxk8DG%F8ZYiBUa$s_Y0&VJ|FH_Cycm(M@%@n4Y7LF zH$@n+0_S?QU@GD>*t1R;aRdKx=;$`Ys>=8jVZ;hN>-B=Eh*hj!CyZEu&G?vgZq4|> zj##1ot?Bb5wQ$Xvx@J2#7Hv9pbiqy?T`=nC;#e^1@iyd|z2N&?v)8QOYqoFJ>@|Jc(AMcTNB9wJ_spUYGP@nBMQgI0w&VXWZgEqthF=V2lADj6KX} zJ;qnCV_acA-~Y6yxv?)f?0hXeve!A=!Pu`ny}ipH-{0Kv$NuJE>~9VqF!n&-n(nLj&=5<2jdz|9CJlt*e*6vf8=vh z_>G$JvS+>HgKG!Ibxf~K^E}Nsm@zctZ(dXLTDPsbQ2th>ozeR9xc$P5u0-nB=7$J( zn4F|nWIiUG8k3+0=Q|^ut68jG+u>{B?+>h$W4YgYa4hU#$By6P*uk(Ldi{`_pHrSW z8zY7JIVHS!+X=CkNsZEA*uhEhX~G{|jub|p1jmd$;^yap>@3e zXdga%+Z=ZDv&^%1L!|zB$x%12F?p8njnq5Cj=6bV&yy=xl$uP)|ke2^Trtn??;`cVS!wRNxr%$*osZPHFCTaFGt|?jZh5fr+jMRGbVK+ZRJ;k~GBgtv*6U>voiPTdf)7&Nb z*xr{Swcq#0-Tch;RO}z6cdkiu&tjinIaX!XA9nL|){~u&ee?QpH$Q(pFAa#&%c9fV z!`Xg?j~%h`u$!O1o&xN%Wp$dnCvyrPyDB!#y^MV-FrT=3+|AEr&nj*oeGL7<>0?em z`K!JMAM`!*ShG)>$D)72AN>edaM!y0V z;eHOjR5w8weHFYV?X=jp&5GBDR-chR`Od>Qv7_I@p7_ow>9?JJi5EMLg}vaHXQUrm zo8xrfE@z~FW^EX+ca=CT{Wf4{ydK}-r1a+_#S`?x;%B6P>H+ck+|D!7CvTjL(~rJ9 zDSdcE_5@vF@@eU}@iFl_bnhAIhhd+`>Cf+-mcDvtT)ZBdcv|}EFH7Qe(?utxKc6U& zpv!-ETKebryx(Z{J!hm(es(xc?@Ku;eK;j|f*!l$wDj8n^W*h5pPi9D`PLV4dd}I? z(r=GVi`U8fPD}q>JSSc+T6t3XaHD()I{xd^(my|+5w9O``{C*u}$MoN*`{`KE6j!OTVqo$C}z@_7hX<%zkqFcnj%Erw)bjo=viko~PpO z4EqrXwYURU>`{F3Gd93OG!QK_(zsWaAb!CSCW@htPv&|x1g5};hG$={s zW5)gRCG)LG^W?s0(sPZv#|#Z`%G`QZkUSHw9$llFcWsU!iW{PN>q%*>eD5wg%K;T8IzFusS=;r{o}-r zzKU4E4u;+IN$KPD?|Pc!bA6*6+acpx)#R(y!Y{N)R$qP|COmRZ%AeZ7v1rpd7VI1g zc8&$(ShJmb=cY@WZx-S`E_)0S&RA%T_&EOX0Xsfm_-xxdMy})DOzZx1?1CagrJVsc z<5W<7*-z86{qRchagK!#*zp0w$Mi2&-Fxq!o)aQ=#|L&W?52;YW2TR(Vc$)DsukVvw7xSJn?=@3@Ozkpt($v@v^=n|y8qbNDiRz_# z6@)izk5#baJRLh2cGIWS$%^9NrSnR)p;T*O&-ri_vT&hrQsGc_vFj1xZQrhtW1V(z zEZ8{~>>LYrjs@dbvz;zJ&r3gfzE_BPZRM-No0o*CR^6)zU*8d_0@~LQ&U-Ifj&<6> zv0&#|uyZWfITnm#&357yY74oG~;`)yK_M#?@!9(5o^;_qA+vwgIQzvZ+EcG?6xZGxRP!A_fCT+<$} zhT=V#XON3?Khn9@|Ea%=7~=2#|G5@V(oe3Q$tCR%x*x3$esx0n)xcZfDu2EFVvp~c zsLKBIlh{Z4r>Od^*9i|;mZ++1h!uX=B}N!A2g3*axQ}_P`M1(*r{LEoq#c~ksZ$B5 zcxEN2l`8F|Cl%w~?VBRh{I+Z5TAXVTr2_M9OU3i+WcEn$!E+Ekx!&1>_mG~lts~Tj zITD1|Oj;>zV%~=~N8j0!if7r@l98%#&JE)8TWF-3{L!a)C+X?iDMI~rDqc9>yp`(r z73+n4R!6F4Z9m0(NRQPeLX|6(n2KlC{coexA1hK*@tmr2Jwk2Uuq74GzBy$g)$kuT zreeOcWMJf8){~gXL`($D3#2Nm_#$LNX#tHg%al@)hEU8rD9Hc zbz6iA?{-UK_0{kQwS^fm`I`9x`yf`=*{AlMZ1Svk6 z#0+~?=E}bJQ!yv)elS8cXGYw5GT$kkUB&-#`bsK z%r0Yz)n$3VW@cQAHO%?#Q>N3p?#)+#_K4pg+JT zAU?Ou4Lhf-6UI9Y@E7MZO8mdIQiKtIaKfE@axHe|SSyVF0Ip0qWbD`NgJfa!2k^%y za*6*B->(yfKR8d@OmeLU*Wmm>W?V<`Z&~vTH-C^MjD7;1kUO{d-#E2SUFw%Z#@KZR zBnzWIfZ>C7;8S&ICb_0Ns;3C!I)bBf`sy}t~=OoSPmIyZt0h-E*H%$$G-p7 zI;B62Em&vqG>=%T zz_`BP(D5G8x9Y*`RR4B6Q}N!ZMD}E1Ts!dTl>KrqhaOE<8CxEa`@P*ODZ;ql!SF#J zfKO1wX1SM(^;#>8YXlBkct-B`4~C@(qYr@J585sMZ`4T^hCld1rG0Ym_wsldeE^)J z>t?yf>$hGjjB5(s9ei4J;QpW#VO%@#clURRJ+f-DFzn!^hxW=n9=FBIxbEO0O*hNE z+^qRpVO&%2v5u$Zen0qriZHGnxWkEEVy{s-SykM&SMK+>Hz$i7K8_vN9rp9@Y?k}I zWwW)yxTfF|jZTaGBW@E6J9td*u|Bx38wG`^!)IMv!37?Mh#k*v#}0=iQVym9SpnabC1r7e_Wr9s{6T|F8r+k9zRdEN(f&W z!E@LpuL^gW5iiF&?ci9jb1c|77VI1g#<6BQE3$jrT-7#C?2ZrYVAxHc3`>g0IfVGF zR5yRjESx7HTwTkwSI+-vP0sr=;%v5qW6`E_EZ8{~>>LZmwLm)#<63}mUH)#H_`Nvx z|4-b^>$`8}4LP5RXX4d|?d5we&r8W`Ri&>br`nTyMv8j1^L6prJR(l5E<8cFbwq^f z+h>|prgeBk4p57;>$r=2G` z=gDW>J{Tv@-jgink7IHEX8Y#vGTX#&gun9}!T62vciKrW4rZH(3H%WgvrRKrW;|oeUpVk*^ ziGM=f6=HXMU|U)7WcG5gSK{PYryU#%c8&!*$AX<>!8q1zCs+23(tiKX zR;fI{#|u}Ck5bKZ$zH&oH?BoW{Bhk8e;n(ygJZ$Yv0&#|uyZUJ$EJ53|8ARR44>q; zo7c#^zGmOJ`|VQsEj8auQfs273%@;Rty*#p{#Ha>6 zCkP*D87s#kRyY=RuwzFY96K0x{9X7sf7dzoug(WP&iR0GK4v@VowM2I?6+cE(332` zCa4o7!-W%ft&!h_Hu1aAj`O$7-)pw-+i#@{Ga zr+_f|TU!HT6x|MYVcgZ^Q!isY2Hr3z%7yXOl@77Om|KB6E?@4#II2B=e+tIf3H-`; zVJ@uq^X}~^UjBUVXe?UB)IGg>)jPssG zUBo9tj}6+&D|>=_3N+iOVMqUQ>|oeUpJvHz<=C(t%f#;Zzz&Ap^jZ7qVDI@nSSohM z2X=5M+fAR5+<$QXvAq(+?)bnChTZh}V&FRQU*We{?2ZrYVAxHcA|5UN0f~#m?)bnC zhTZfTR_C7h_u05w?2ZrYVAxHc{#Cvg|F$0|irw*n9Spnalk%Kbdw=e*Ty!+IOod9MQK5+ z?l8G@ki*Dhoq};8o@ad=CVj6BwfYbn-=Ybj=G2|LtP ztRMRm_a%-)9K$&Naqi;0$2AkzTU@K{ZYcW@^|sH4vlf1_PvG`1PG5)|KP88e$2#Mi zZ)wN=`r{1?M_zvagV-6gc(Un8A01daFgjhf-u@xx$xDu#y70!WmfQ8?KC33LXXp3{ zPug|I=eq>^Iu<#MJk}|Atgo%3O7y*P;e8dy81LO`hUrKj9auUrI;}3NW$VC2EpJ%3 za?~i}!7ol-&(6m~N0`li74I;)jztb5k9GDf)y4E*{p9Zp51Vk4^`+JB_n40K(SfA{ zqjPTELi3?$#$5|rHQLvBudf%ZXJ>4!e>_Oc*E}2KIu<#MJl45&+V+;OuATgURzy0; z(MP`fP2WC9UM8QrU}4Emx3WFED`)-PnDY@F+j(Y-a%S`8vhz$XJIG<=vCc=m-ZY;} zo^zYYrGp$s9_u{T^exjrDDN(lO9wfOJl1)1Ng0cI-jpDh4ssZItkbs3Zl?eCqf<>T z9po_bSZ7t~SIwWrZGv1n$YJC$cd8%mS8wtDO$%Z21;=(`c|0EDW8?7{_dV`c9K$&N zaem{xQ)9=s zXR+e@)!f5J&i((~d!fj+j{s{Q0cMXNz8>WI7kTdWX6|(#I=R<|xz}sxa6KEZGg&7i z*E$)_U6sxg+ZgNfEGp-(cpsIBqy=l4l!Y~9AVYv~Wc@|1 zIH0fiU`KJozT!!{iZlKw{`jf9;QxCk*SG%CuWtJWroSiMeQXwo4}Yka#pm<2b&ZKz znMV_2;`w;tL$nk?n468FUjez^ofJ)5FgnmZfci!${*q^KZ(Em zCok$3`BHz8D-P%@KG;#*u&;R1uHuY8ia&lTFZjQ@)s@N6Bj@JNuRYSZ#wqjG;}>0* zOb7m`OjXktqc5G9u_+zd=UCYn$2#y|^>au5|EBth^97S@jeS^SA7)HZlQ3hAT7@=8cYwW`s z`>@77tg#Pk?86%Sk~8+D&)A1G_F;{ESYsd7*oQUtVa?Sr{nEH*9?;nQtvLaGpO|YsKra5%&dYJWVC9{2H%y&#PKT*~&h;?kf;9llcwub-Gmcm@z>F`}60p`( zu+~(t)>M+SR*^ojg0VvkVeAuIn08rH!T7_P3dT>?PB8wnrh=(w$*FVcQ~$EVxR8D2 zj$@TOnDHe)8K6BYEIFp}LVTgO=fS`ZEy1}mhiIO4Y>fWCRRTBn zI+D|t^s)a+s`H_57kT%CcSw-qL(KSzJU%wo#}4|~p)GhrZN>g<`(Wpyy{dkjzvC~B z-O?{Q73E#?wtvqz@D>+rmB52$bS`@E@okf3Uk85XftT{(&z5v5s?=-y#! zn3%w-4g8Gz75lFmMkm&%ZixwXOKro%D%Ou{JFfo$BWqers;?OA?r2fVV$!zM5MyEj zm%O#6#iZfN!N$Y{p4PpV#pJAQhZqwR_>K8BEhb-mIoOz(8274WFxj&)$hK5@|4hvTs?9mb$^G#+<;sg}j$lG_`*&QI2~nB2EK zFfoA}Osr)wxpqNdVgi4DUrme2-#-paOyF|EYgtT=y*Ds1fomHuzsSj|I2BXa;I@eAfWz4a=9S|6s z*Zn-wJ5|He=t^ z7xF^=ps$*QRgTr;u#URSQl=h$`ko#HAFJwM|H z$A52J@7Ysa*>3``DcQ(f-EOtX&pWS?D?K9cagY3qhc7J5bozf)m>qlPZo`~xjyP(V zQ@eK@J1lD#9`JPwvyaYqIQ=lU=E$knc5f)9!bteC)x39Mtusg8wp zEUaT;9SiGN>~JhO600wgqYqO9YM0u8m3R2AH1DwT4(nL8tGd#$$Tw6oal7K&I*jX6 zeIbw3AwH>ITGg@mrek3p3+q@|$6`n0OB~x&Y|+`T`qozG6?X69I#vr@ z;=Jar@Qwaix`AUHewkjSqOCt9$pTS;p5+ z?dl5dx!HK1^Sini7u{;yrA${h`-C~h{qOGLcCR(p_?6SUxbFuCKJwGf8Pl&_YXr93%1z8;=r+ME)8+R=3@&&+-PflQHUEp3>g?= zg>Oac0^@TWH~9E()>@9@e8G~FUzq$7f0+1_7nr<|FPMChN0>a4Uzq%ocbL3W4>0wR z+ZO$`TKbdgC$8JLkL%U2uV?%u@8ktmUSQ<~R$gG`1y){QflZ&&iZFxSBvkFCT~r*|}->1%=tUsY4B~pPrkruY5iKd0}>Ldj0Lf?A%oNSYdWotqA+T$r7Y-uZOsdTpsDX;<^Pm|B80*AWNJ=lHDooW5v2r;nP?>AU80Vxsw+ zSZO{dhMLdS7InKhVjkx=?xW;Z&(*^m3sZZK3MM<%8NH4x6LS<1rQYF&=j?e&P?~9k%%R@h<-v@36)@tnm(Oyu%vru*N&A z@eZpk;-I$RKWlD@`xVb=n$HV;0t!h1C{) zS6i^!g4GtRwqUgdt1Vbr^l2HledyFor^a24vSXLseM)BY(I+kFcg zW4YR&Ke{#btCIhB>d7773tDKa@@Sjhfl*P96bth*r-{y)_ zvb->k_N_6(#%8bCC%86auE-cUV@L80@xU7G*E?2rBPN)(?s;>k7r3^@h%O@p*@HTzqa4OU^jW)z3Z0p@V+B z-d5h@^>FT5S~?oP*!inY!rcDvtP|xi_j*n8-@3jdcUrf=f1Mvg9{-)^$M>++TQO`z!nMf%wQbIM+Vw_PsPa7M4HgY>d9*hQ4Aef9MM~)!*N;k524c%(2b5zp(1( z_xdaQ@&SG20+!FRkG|R^{xPFdzTxp!O9wOOj{r~2n*a#(WwiCK1JUu{W8c4$|2VA&Dp`X)cI1LJ4R_>8>Vi$|M$ z=c|XfBkl}*@R8TJ@n;5pV8u0V*ZYn#omSTlb)7ys(s;M3h3>2OYZ*85`yf}{SJSxq z_QTvEosKZ>+&b`&@4E1tBgIOC7vkDtm5{;S@S z#lx*0$Rn)$N=~lDs!!DqHKw|fj`aV3s0aE;OjPr*Y93b2!>V~$H4m%iVbwgWnuk^M zuxeg%YDxOk7_6FyRr9cF9#+l6s(Dy753A;3)jX`4hgI{iY93b2!>V~$H4m%iVb#3k z)V%bmc~~_MtL9oe2x6U=hCzfk0OCFE$IEKt8==@dl zf3rCJr`9}ka)++xX7m4;w_0T9g?V}BXXlG`*R;&eBc1<#L3V!m?4DNHd1t~kt+Vq{ z#j0(x^VHo}x5>_5Bd52?&TGhZzC&N$+G6 zj@Na6)lXPA{-@WE&THgLbG33uPBr#njeS^SAJ*81HTGeReOO~3*4T$N_9fT)L}MSh z#y+gE4{Pkh8vC%uKCH11YwW`s`>@77tg#O(cd*7jtg#Pk?86%Su*SaRTAyg_BiGo6 zHTGeReOO~3*4T&fKh76p6L~xjEb%?yI1~0Q^&fg zw+HS%eyscYoxpSZk9B$91>UZe=cTX@Kmp*h<#t+>) z&>hx)u*q+0(A|AwPz2vYVrW%lKWro7JS;@cBS>1m0rX9&W*~z<0dyFP*l_I%dZ(DgQ|h#fvSaV5e32`cwzb{67iIm0 z3oa?Jb|0#7vHP-J=;K3wyTo<;D)j5~M?1OiT8F;mebdFgdt^`3Uw!kXZoh#&j7z`N z!!0@MGUNU&uXHyp>}LG!QCGQ}9_?zp#|c-vRb2xw^f4E2=W`LqAAbGmL-UA9)e?h@ zn+@yk=8PT~_>3OzpS1=U&mMcZJN?Ig#@$cu>CSuWD&q?~^m5nj+sC-v(mw9k<-LqM zj_T)*-97N_#|*F1Zy0@ia+zGoA(v(jN6 z(6Jku6XYjzhDeAjdrzPE~x!n=e&%O$NFMy#`<%YjCNPtH|dzeI^?;Z4!_P7T|RD~mFEY(^~T5d z!OoapM!RI%w4-6^!?W)j?dl#}wKgo9@TWHpa24+Aarg^&<{Ll$N{_>lSAW&-*^Gbc z=$`ZP-6tgmy6VZp$2>pB>v(?2GddMk3~-a`9A>=hqXXOfi^2~mu zFZtDnu5WYrh|%t}`rqc=`fZ+T`2Hw&#kXJQUHNOC>se=%d;hR6^L8zh?`qyS(%oJ9 zv%E8Q$#<8R8tG<_{V?yNz4P7A{YSXPA1%w9S1sSg_Qm+HV$uj#y~(@gPrh1TeQlHUjn96fG)}dA>w)@%a zSDQZGU4HU9V>f8LTR!tg$ICXz~uk%$F{w`pYg%o z=F=ziGFJVdALp8y*_1k=HdGIrn)gkOx#BatN1l!AO^MZS#h)B0w!KoD!+kub92D#; zwu^iWNBS79Ic)v$yQwi(uKy=%c)f8KjnjB+#`A!3&D^4~&s?E;$ep8zxndH>AXD;GQS|t|8JOEHY;$A9tEy_m%wXYFK`ui4m`1z-=~{?mgyfkY>>OUY~XsY z406Y}Z({PR%MNy><~BAyu=Zfr>-{s0KRj!&n_D69N9PZAZ=HBXCO@_R>6w1H$4)cG z&XU~%WB=iyr<$C0>+Td7f4+XOk;(D1=itEje|h)7^h@%#eqU1hH`X7R+4=dy0h#?) zqX%T|p6&My;B|632cI_p=fE3eM_i(GL)U-7|?;)Z?2lXewn{89Yz zQ+dIE^0kHkDPOSi1uI{$@&zkju<`{fU$F88D_^kkB{^~ER(`9Q=o260$``DB!O9n` ze8I{Wc9bvV$``DBp`&~uSH5873s$~ha^(xT@`YUaf|V~=`GS=% z$;lV2d|^}hLauzl$``DB!O9n$o3FpdT9_yQH;pyTjZyBBXgns-I8CDQn?&O}iN<>p z%>zj^KP1t-k@)qb=946vXOd|CNuqfviRP;$ift0jZ%H)oC7LIFeJ0U7naTZl%=G;@ z&FuK`o7wl{I&0UD_skzZ4`hD&`62V)&nH>G{Ctx27rEkqzT$%&#SQz4C+#ZE_@nsa zr}BdT(L8DLbUd0q?8m9uf&KV3`>-F^)^0kVm_Nwbo_i`@q}rYe8KobzF_<$U$F88`+3sj_^Es$SH6%dU&xg&ekn@G4<^0+?YD|^OZ66@5hBP<087QWIi!D<4D)t>9`BW`f;c0 zZsfj?nZBP-j2U-+J~76=pHITEzFj|`7~_whPmJ-?&nL$CA6<86a_Uz4)U)i6JJ~09 zYM0!}A95!@$({U9b7$?6JM|a2;()&5gB`^U`-&&+D$e+$_~WPYg8$@;F__LL#>y9R zk0~I53BxPkfLoU$F88(=Ks_l`mNN!jAHVoPLo< zSouOn`9iLI!O9n`e8I{WtbD=B7p#0qt~e-P$dxZx`GS=%SowmLFE}?}e~q;;PyTNj zYnmswUN}2{mrEbYU-8|3?$D#>7~iw?KJLUhbB$LWQpMFNIp4UTZ)G>G&Yi~9w%Of% zP-}s4`FD45t=_ob`0O2bcDI*s#)Y?4bPGp6YJBN^72Kj0Pa7|&Q^B23=Y@#vFT-d)FA7d$<13n6|pL_{10=p1$sLV|;TfR~qBF{hMES>+$@u83E?_FnnW!!&RRrk|9D~&6^yO(RR^XJB;%2jrU7Jh8J>yX`C z(iL}^mS`Y-THbqrk;JB8&l`L{*9@BKQ4?J7k<1L zGp77FGG@9*tsIV zR{r%fzA!G_@5uaBKYVWd%vDF_uNV?|k8;P@e;`vcI<{(MzXzTk3lH_je(#TkpGuE~ zcS(yZ3<%L2 z+n?p_!xg;!k={PM#@m0_+lT+*?a%b~;eOu!kKR7~xwl{6+c%vjwk<0B=_m8yl5X1; zO+F%Uv!UA*ttnh*@=Ax7^50Sp{P>iTMf`sqeg8*#EOt7j$HLA1v1|RY@UH2x@Z$7X zI6k)hqos>#?Oi58E{^TP$5$+G--AG>X3EH8{R!WeE_(c$G70js-L@;*`?J91kJ`Ry z{PAT?esH}qMQ&{1)&t5GO>6by(YBVYNz_Hd)jW#`t{v{wB1#s z>$@k@c6+R=@8c8NTG;P6H!5xSg-XY}?bCM4J$$^|CvCUQWhWH-|Nrr~9&*1EL9Fy0 z2Y6$@0io{;=-UdivoYUg(6C|pCxM=L?z=yvvsOX5=@2__(`Z^XnIu_Qku#Sb}b_-^2Y41jT{oqJ9 zcK5)QJ{sw|6qGRenl1fvOdo7v{9L6l);Kp|$B(;2>~)OM@y8l-thZ^5P2ZL=ZS8m0 zh-A+Ef%!+bYnwFMVWe@LN}i7lys~+ljBo$@-9^$l>EH!LI`+7y78K2|*2|8CFX()w zaYL`udauB@`D4Xjc$?Cx?c36^_>jx=3%S}7OCH;Vk^i239g7bzKFE&zL@p*i*o^JV zPxT%B-|M?oUMv?rN9b=TFR@K>hd#N(4y^oUc8bZn?5IxASDna? z`XU|TCLNfzemuN^)ke+JuXV$Y-aF$uS5+~tb>OuwsUEnjf3IJ>y6JIFIRMjxMLlfKYLZU~IzJq%D}X@BzjLe1q|g{)%(u#4Wckao=H% z-B282`@{-;{E;2S6StBo%)Nu z`m1Br7wKR}IxzOtFLYpzh2vx6wv-o+h1FJZd5LYJBR^$F`9&_4Z?S#ZQJtW#I?=J} zi*&Ff9T@xS*EJJv%W7cwy1D;~|G+sJpZx8GiRxtH?Hv*wJN~B*$(Cu|!h1XzYPInv z9g_Rg8lL3!f2kJawVHKE)Zf#*P4Sn$EyWEVj(r`gyx@cE z$WL^{mKSd`wl7A9{-RHRi33a=h!0GBh#UMzW2l;x9obZTB*$l1bGi-zF<@BqSLh6D@E8ZU-hYc@jm6YOInP0+2of!yIt~d zg_n%G?zVlhck*gJ`tVoVzGnQlt+!9^y*DuW2Ojjg$;)1`U2=Ehzz2AnV%n1a6?2}* z-z~M-yUY{$Y73SR=)`iEzU1o2fAs|&7&~xoTeK@X#o3R2hGnxj|6`lzs9o7n9FU6@ z|Jc45ooYUw=o8QTQk%q?_#-F&Z87$yEc2IW+^LzoGhx?JF@x{ow?2p`_vwR_U-l}5%t{{6D#&SP5`Uw{5($#qM+8Nap9Wy##RgN-Nba9J|H z{8qLefY-ec82vSsOPc%xZ&SSD?qQiunH`5`$8LZ0@Z`YTf=zf?+HP5|Q$O|XV}EQe z6CdQU|1fg;f=yU9VcFEN8`G}(h#goq<74Bt;{L+uZ>aCFO=5^X@sS`uc>a&s%mWnGgqJ zGJEk>#^|&t8<@V={&i3tbl|%NcQwZ5i(fQ1Mt@YlQ;e~BLFW^Vsh>6}Q)5e0eeyCS zwMjjwEm%IFBj3nTF5`bJ$A5H?!?8^m`S016O?-fJ{lsV4Db7CqMMwRO?daHzi3u@8 zUon);;$j=?kMy}fpIp4)V-Ay}JALlpw|(x&Df~zCt2kgsan7|Fw-x6|aaO&_ALV*O zHTnMDZEbE`va(O|{Nrtmmn|5Ubh$I|ksl9BF25qM^R+ahO5ok9dw!_3=~EBaj;)vR z=<0#dnfpdvlP~he-Z?dJ9dGlL!oVN;wmv>2@R}>G${3$N>=WeltH#m6CNY_?bMOJ~ z*EcY^c>k5a=-*H#^o!iRm-dkwpe^Df`>^aQZt_Puj9KYu{7OeYbF5hNK-^Z`Ul{%0 z>bva3I>Ze*aU-5E@f_vj3=`+!KK}3@%|)D3__u7vZT*p&iS1KY>I?M-Q*YEEOdZk| zOnp+fuEeAFa>g>O8iO zj@sfK*pqr!&YQjEAbTG<+s~s+s7JzeCUW|*3M&$Cv86}`KI=0yrHC!;NdaH71$UztDJi=drPGNzI$Cv*$mbyK``IZ{6U3t0vbZ>n4vjpDQdMn(XkP z-^262Js)LC3%XmZJd>x@e*8lG(b3_ee((|XRxWXWFmJf+T8*Nl#1701v;HeJ+~i+pgA zZ!YrLMSXEmA6?XUM@;CikBN(N8t2+Si)efrukrfz+07*o%_HjJrrUmM2M|9y2se;F6PHcZZV@pj zwPWZ@sQD;XaSW+9*>q7`)Tex)ZjHTf)U&bonL4*z`@T^BCii2|MSW+ynB2#NoCY1g zZyV){dh>o(&hzo44vl@BsZV1cf9lrQ=fy?&qRvh3^GN+0`~12n?~E6d`+9IuOsHWm zpHj!iirO~zF{I{={XD?9vtx7WZM_)AHOZJ|uGT!9vW?$u7fv)eb8pJT!I(K2MxXJ* zJOfip%rkIWOF<{pl5tu~#%V1Xr?q5EEiunvC#@x8YANpq-q0Nn{O`99jwrp;M zsSV~vn3`d3guTx;H^S5yb0bXcF*m~0By%H7twyn;9xR?d?>2`MXXfxI<~HXe_qnih z0i2F0J2o9t#_59ao9SGgh~sB1 zI5w5@3`X!RjOFz>wHdc%;|O^=F3b+h{DV#EkogBr*8s-p8o-!(X8u8kI%ocYsek4l zm^A?N51g(6j2TCf|HkS&^8>8&1+4Q0tn&q|^98K)1+4Q0tn&q|^99T}V*XJLGykOd zqUMd$b%-%zfw_ggP*==F*nycdQ=2wtrfu1r32V-THD|)qIddkgITO~L3H!d=oCz~$ zMm1w>arSv0E?|nPo z-)C;|?>Rc&>xcdOkIujEY3$#Nbo>tha{s=hEox~)5m{5ZEBDu^!@v)W(T={k2SOJ-*2^ck^A>vv;SA|@54Iz>EDyh{P*wGX8qb6|7Q}- zhxE%46Z*^h#V~Q;y%3=`+*Jz4r?@-$z@9RoOYO(&b6a!jzEHGg+pKF~+QkR0y*JnWil|*%yUK?s4*z9M%YV|Q|67~D z>3`BD(f`>RORoP~#O4<5f6hz)>oP%34M-ld*RgidC#UG7`WgHGv@}kAFvbVpZpPlv zOh?Rh2kSj-ru~iUA=#YQYh3%_1J}#ZeWcBCU(u=E*ay#!_@vkGb{z-%|Gu`I!v24= z*JI)@orvu}^Hcrxm>i}0PMp(j=9|xv`9r>eJWV@sbJlwf_0w?=Kes`u8Y{@Y2BJUs$u(o-Q53=tDcLcdv@PRwyl3)sEW2o2E59!4FLScVeVuI9dv3H#F4S(Cmp^?U zq~F%zX^r4a5hSceU^V)_a1m-V=oNo*=CE1Yx}=2DZb-`R}cRov9~9OIggYqGdH@ngs8hw)OqdEgcPo!{N61)k*J1-@bFR;Kgl zP9t6UZh>F*?+&{!wlsNv|4#9wvjRWj-!(pAUI~+L@z0U&-5*1JmiF%^(-vdo0^e4A zul|UG!n0VDeLWvIDX{Z(KH%HHAN%@WcSJaLg&!ARw+Q@qKVCNG9ZdC+c}Yxv<&Wg@ zO*+W^`^eT8<{AH53qcI@xixc?|tXapOUBXap=SGf2a8W zZOGUEoFGRhw=Z!Yf9t;*(AT^K7xzC8nwQY|GyYd0{tt)W`cDJe-I)JF(7c5HpYi_# z@qZm?UZSl(>z!`BKdyO+wlpundjA^M``57EzlK>4=zk1g)d~Lt6SHbb|M9}H`frew zvl{d3t3>Ooc&&vzz3y0V?H7M@r?_wT0*8P*rrvJW4vi;em*Ky)k#tJGqk(?94(D4Q3E%j@j{nw1@ld}fcPnHQf5hqcN3xjvZ%-KW?TP=XJjxE= zYKiUp@3SP)_gRwY`z%THeU>EpK1-tSv-od_BtNF#k%{e#>0?|!F>g#Q#rC87X712e z2P8X83E#5W)EbNL*TwhfsLB1)Z}DJri+_F7XFXOut5*32hnW7xbsNjY={GwPeOCzm zm{s%CjJ{){`cJ=gvPolMyWdGfuw^XPkZ;&N%%xoN@YX zIOFu&aK?Nau0riG#(a}&`%A_fpXI-|b;q#4W&C#``^*UZVE8tc>7@57jJc;Fou9Vp zksUk7e|J(g+wg6yv@O2z=f4qV$EM%=GfuzT7&v^l(K!8XqjCD(M&tCmjmGJB8;#TN zHX5hjZ8YXPgZ_JV#>D@Wv%|eL@-pV4z&HDEfPOS7@TLA6pwa!e_0DCpZVx#{XZ1UQ zIhKBLPR#A2|3;+A)9-{Dr{4)RPQMdsoPHqjar&K597$pIk^^a@G&X$(M9;bBA2HgOxj&`%7^ii_3Mq zRw*vO@mNM*_R&|n)B}t^=)?FQGh-h)eT;2tPCy>(uA1W z4ur7-$2Mbmtk0Z@zUE9=b0!?mnegw;u^T(Da(=|V^kL1zu;yWyd075yPDajrrM^f` z{UBH0#gZ$An(JaaYAZfg@kjsPIUnMi<`!7(xZxq=WhXV|sm;@cqa1 z`tHB%J8M7Mul-!Q9!~fkWqN&=@U6P^`Yz%7mFe|e;@6G#ZB5!b@u2Z8UF)v5hvKir zTzY+%_%)|XukRARrI=pdnZEW}{56z)!x5W&OEJB^vt!fiy9Ar*^<5%;zXr~DV~_P? zf4%)3?E&E@ZTaiF%x13rIObx1eV6=C!l_M`7_Ceimdlj!@KN%Z~AB>Mhl z!Z#w*>$}WP?5i!}7S~VA8&gZM{rDLMe|_iD>$_xAYb<_V0@gDU)MR>nXExL8yZ^$f zXVt2|UMse4r9&LV==`&Ym;;&d07ti8y7w1caQ98?AJocegk_L`?XNAnN7cD$lCJf_pHCLzwR*m{<=5zrIWS^@8d6>x+#2_sSE0jbL)};@AAf{`{W! z>pNqAjllC2;n?upMaF(TpXvDZyfMd;N6v$}ee~-Yll$wtq~e zOW!v~oN1TZR?LYr{9FFSI&m&w^vR2k#bzvz^~oLj${noSS-asmnJjn3<=U^`GM(b` z8;@o5WgmUDOFh8&gFZ}OVrCvdPQPNCx$}c`a^;Lc<_+2TEtbx|Yi`k4U~XYfqc46P zYjc`$I;X*!(_qbMu;w&aa~iBU4c43nGpEJvGQT0mhd2)Lycg>*2cpj$80*AyW2_U) znKL<7b0(}g6OQLh`1j^mzn0GC-VM#GoFB0-eOUUi=3$t5SpI8HM$UYtzDQ2}AXj|E zk}IB?>tv_6I*)5L&e7(q4fRFmJABsp4*tE|p|i1ZR$IC8`FEZR@IQAh-I)1vW9B;T z4Y3aNYdq}@v1ZWT7VAUpTd~H|eiqk3+UGKTJzvWGd|h)z`(<{luCuVI>o30!)P5Z6 zWbNgx_k41+f5&y7_Vu_P)PCQ3&pAhXKwNKXKauNA?I&`5p}kA4ZMApFwXOCpxwh5b zCD*pvyX5-I_WQX0QcSomQ`~Z&zulM^%4VDkyS9qjigQ$~{=fFxxE9l18`ommYvWo> zdu?2cX|FAdNqYVD-;Pi0XSDyqb)5Ejv$p83azVS%KF)eMjrQZXX4IbGdNzy8HFc%y zi@3(3{Wz;PUB|J%rIupl6Z)T}dra8zYhbg#by!P> zw*1=9pF@o~zi_`4AJXd!+}TMwjr zf^Ge}f>_}L=f}S3p5PYS_DB{C3-UYs^`LZE|5QwmZQ|Ej(kbPyH+Aei{(4hwrRz7d zpROm3)AeNFu%0wd*OSKSdeS&uPa3D|N#k@qX`HSnjag6nb&GMj#x~}<_{d*Kj(VWIH7;O{3s~a<#vjc^^1oYH*&%6}RQN_uNo4ew< z4#p<)9{RB6I+(dmI?SIsc0+Tid}HpFZ!q&GHZ}Lc%)PO``l~q{9gal~BagYbxh}R7 zkE7zo0yU3)od;pYW;_oRH%@cs7CSbrJ^8#j=e;;Sas1;v7MBa@=sbx3IuF9RwGr2? za-p$iaY)CS@n#tB@f;ODi_Wv7Jdf)CTV}KVXGrwFAM5=G$iMMFXY3i>f9L-@@qZfR zg7;YYKMicC$*7RkC{|@Q@ z)$d3a_uM$|EU52#XCaM)$@w1T|Ap_{(#Q1K`$X((&sguaApaBJE3vkC-{+6KH8)Ybp@>VJL7qy7^Z)_(%S{O@c0AFZ4E|FOCM`7E28`hV0L^S{|@ zOaJ3dTl$}HSpNqO)8F|2rQ`oa*MG&+_xL~C^*`_&E5@dDXiLZ9L;QdB{NFz9=KeQ+ z{9pPT^MCBQ-z>nUzIg%bdk5l8{Vs#__00?H=sOg!zIh?mHxba0ZycNZO%U|;oe@~y zk%9G%67i;fOGWznjtqA69U1tyzBwWt9jkBdAm^Jt`WB47uY_FR0}|`IB>I++j#b~W zDILDQqi?C?emhBRp_BW~DQxPSWw5?oC6@i%Z)3>^eX9$7eX|VKcfQ1GcVoXPrtie* zn{L?AH{D=;8xGd@=3spj5Z1Tq#GCp}J?YbyzPqPy#$glRiv50K^o>P*Gx4{+5s4jr z9~0KMCSiTQ64v)I;oNUu>U)lSW3kPcE9@N6YxW6FJg`Q4w{MN`UACCf`KV0Q1e-6q zE{S-4?UBjqR^gkNF{8sd=*=U(&*xkt=6u9C4tdPz9RAh8Ca>G~@{F4`=V!nTd>6z_C4+`yES!dE-hhv%#5b) zu?1TicmJTNn_sk*@%}ZNxgi5f8XrBnnJZcsc+XYMT*qo#o4mw%&D~wgCoNQ4-w&Q^ zjC|Lcfzh9P>>QJ0XU%=L8e{*!TW&U{-7!^W8RO5^^`;x+=aMQ@jPYOgkNmW=t5RvQ z$q)abtK0UJpi^mOSJ%E(IQD=Sy1I9d3O28u+SL`@6WZG6{I2fBMZt$IWxBfACj{U6 z-`&OSUMu+g%IRHP$DczCvAo88r|`ux{CV)e``U0s6`KN}zarT49GXm{udS7m*C=hLBCAK(7E zFze&Wbyi{4$F+S5vpyD_R+#nikjjNwAF;1KK3AeJ>tlx+ zg;^hmUr?C!@y?-zSsyQ(SD5v2($j@mAFI7vnDw#!7yq(PA4}dBV*ATsz1@MULw(k% z)7w?wF4SjX^WLs|pAff)hxK-e3-Mg@Y;SkKlOfLYD)(`}4iE7!>ea^`RWjsg*0MgX z==o5S*xzsO5L@K;Ru8#Gf9sn=4Pd9{*iakTpIRo=4DFUbB-9fAyjLdFnE4sKlODgX z&9wvnHKA(tonsby-Uu2 zT*UuqjS{U&s~1Q=B6)3XUgkSO&+ss-na6=%swoexh(y0haHva!|3B%`5Cn`IV}0M z>{wX(Eo$$v9!r1O)0H!QSpF

#_Xr za#sD!e^~mtj6OBL&2=j*zhd;`u^>jj-nDPIzGHtieKGp4e>=_OF-yNhgGS~L`Y<{= zRyx?!vC_w8tS@sZ;LFR;eDSpGtXdV#DeykH8D}C%}-pD;R))~IfzFB-=`BU6HBYkYf`jXSGxee5~}bqj@j)Sm_|wd?=Pbl4D2nBs!WW#quZCiI0^&b~LZ% z9vkai*YeA3zJ=vaar3bBu^H=2PP>w$BRgXGAM3=&9@=f^tbSnmQ`|f+eeB2jlH-r$ z=*W&({=_=*vHP{%D)R@HKgFF#q>uerUvm7B939ya%b!>$K33-=?7-5`W#$KTbZ!#M z|KjXOAAfX?)3LEl+0pq99a#S4vW|_eaSgCme(JapXCddpT(VL zrH}nsUvlhAj*jez)!$erK33;z?8N8mTvp#XkH;+ki?btr{LvbKwj>wJj@ARnEn;q7_=q1Sa!7DKpw9*a#=pG4vG2q>_{Jfw1%NA$;Gns^#{jg_F>73 zTjxk0`?0>{*q0m~*%4zuK31$gPR&0#^9Pnc#a(wuA3L$W4fQ1*ynuDJ`=`C2S}ov)GWd<|=@C6>O{Z^*TNYx&Z^MAscp zUi?tTl5?!&VqG60*L6*-sf&EGm!a`~h4Eb?5I51JFOudy$V?Zo<$OCS5<_*luM&wK(S&t=)y zoP!83ii9DBO zU*|0B=-ecZ?Zo<$OCS5<_*luMuWK3Pxh(rSCt^qEK5=X()|XuR*cZpgN-llf7e$`S zvafS4c64qP$97_U$)%5daeS=g(${q>@?4gEoztA+K?3LVFrYMP-V=o?7J-L2fk=@73 zJ25}mbMV8)x7Io(nKA4U6CYQ~A!g$3oZIcThdB(Wi+)l~$_q=3$Wa%DB!{%=U zo&9?yJ6-**aqOEIA6BF~u#Sag({$3dVEF*cH&{Ny>I)qA_xm}`-EZ|>a^ev4dCzrp zipe2`J)L6mTwZ}wOlD0jbc)H!WRz1(4*p@RQ%ow}I>9L>ooY>XipjmBZ*a<&+QnzJ z3#(mN?ZRpoR=cp;h1D*sc44)f%eo$q<-|mC__S)%+~Qx~vz*>pb(*{U;*j5+T26Ca z-&khy-K)fQY_A0|@T9zf z33Uq}wZ*`MdWN5VtT6eaX0U&7)#1tc$GmFt{ZGF(8B%hI@#FPJB%^1(Z2au^Ba%|P zzhwMzn~}+=-Y*!xIb>uq?78QRN3|N6++XEcXW6FZN1iRS4Ykf~HC7 zv;SfKFS_F7Waqz!^U*(NiU2&wRh@=_Zw65;;*}Qbkh0i!z-MQ zJ$KnaC!6=2S?JW(?1M)+_0c_hgHzvk8#dX=w*#t8a`Jib-4mSpa^9iio%*=%oN-Ql zZ(q&-H*Ok}0T1|Z>87#j*=Dp;3 zb8dFZ^^m2vIMqOdV`e+m#+M!DIMqzw^XEF%(ycq)=2T1>$Np6#!dRo->0dl;a{Srv;=uU1Md`r! zU*&~R!}ROahXSARK|v-TSE?Y>?|96>%+3z|2W0j;Jal!|Znt~;XZ}=M-7oXA!`1yV z{}(mum-P#|`is8efE~pL`-&UwDxUbGIOC_{kN?U`$B$>3 zPIiV)pXy|P{x4IU+O5%dijzNOD^GFq^N{y%bn?IX^EW!>3%T-zzVd|~r=59A=Fg*d-IDn^ z>x)}5|9k#=OV%&s>M#0=19lW2>?>}xt9as%;*6h)KmIE(E80(UMLT?G>!KG6rn#~o z1wMG{H23<0ADLWh71n99ww~tp8MWNxdw((2J-i~U(@O3(&23rl9h3h!a+<4gYgngE zY%tyJf8bjtFHB~*pPmcrw3(e|x}uq3ownE0v)s;igmv1-C*AD!SR2-9T1V0Dh;wgt z?|&EMbsFF7w)|oJwH!KHFTq;N!CK3~TFb#&%fVX9!CK3~dj1W*_VLNC*PG33&r5R7 z>5{{oN6Oc|q;AX{duRKL+~J>IY{%|6|4O&bXBQdou+1R%L&J{7dDjhd+wOFsaqaq} z-L$jY8n60#oLhB3E90knPjthkpJ%LgW8Y|3IvA`R6sCj$R;|BWth z*UlzyQ2qvYZNtFVwVmV^HxB&Fy%XH*qXIv->v*^Nhj8rbiR0Xq>jOVucdQ#(KJffq z#<)8#5A8mD|6sRUjo@3aJ+5*0E)PC`Hg2dZb$j4ty9{$@ObqMtn^h}ha$?x}0 zl)IAE`z6Zh`27bY%JokEKAUP_yO#?R)yB7P4oXxr%V!QwR7)@IKO|9&J>PmrqS~v_ zcu1m}to-BPM728UoWY4|_=3v@C93TPjSCXh{5L-jNHo?Kyw@ku7<~1u-igM@8;yD= z8asJMd3idf3UBD0Xsn&mvrnQiSoQI%5{=CjSM^IYW?vtBb)vD{Ye>IDV}I;DS0|bi zbY5UC8u<7m_tGz+mOglYqWk3gzz39?=z6{pc-_$xT>II9XZ9QK4(t&4$z|8O2P*|` z)Z%(K@_|sd2d*3Eu528*!J=_)(uZOEcAq!So!mVz^0iw8Mt_fSVZ38!>q7!#f9VTh zexTh>{R89Aq3OJVpOwo7IsVW4I?OHf>(Lc~_ntjDlP@c{A=5A2_{Pjmo9(A$_LKQj zvUVRhbZX|$vQbkrKZ_Pm&HTUaovB&BkgLDwD-PIEe6X*$(XQf&KZ-McD*pJdyzJEA z%0&4(ef!>t-Die%pBdJD zW?1)`Vcn~Q<7<=LXT9`3i`FXWYh46uy##Bm3u_GwYi$f`%?xWT4Qq`JYpn%q?FVa} z25Wr?YuyNIJqc@_32XfcYh4O!Jqc@$g>#>c(ep66=ZOycMB01O{uFZU8A&JJSIT{! zP5Qady69LvyMoP_bDu?#zMd^XKjz$LMWnB1KhTdk_gN0<>)8zSW6pinLi&1k0{xhC zpM{XVo^3!s=GjVm z?;HJ?bN8~Puf1vXW6s@cmcI6m(T_QIFIf88+eJU-+`U@#^=z$J`QlmAn3X&9Svtry zF3^uzV+S2EI;vY(^^8u;(m}3y2K|^dFQF5&@{WGYstxqT=xDBkH8-LYbF8CrfxgBI z`Z32ks$29`&*;Y->u6p=U-K3EF~>TZ_t4jTh!F88SdUJ5$^9zylaH(H!tkr zjyrvn>vvChX5go#qui%oeqs7g{9}(q?QV5hyF~I@E!rm1Pxfk+$WFu8&rM{%?R~VPWmV!rF(0wGRtx9~Ra= zEUbN4So^TB_F-Y|!@}B!g|!b0YabTYJ}j(#SXle8u=ZhL?Zd*_hlRBd3$spU?-gcE zF4jIQa_z&y+J}X;4-0D_7S=v2tbJHm`>?R~VPWmV!rF(0wGRtx9~Ra=EIj{+DemEh zkDLEf-BefB?};P-N9*aXl;10dhnJh_p749<@a}Gwt64Ab`15b}|F0K#5uI?$9*y5N#mXU{^|QApEjQ2_f>Blx!Cv#zu(&DuxE`=^ZT&xyz`v# z0RwJx-(35Gaqn`sxmOQ)$#{12xvs)JF9)4AbKH-WmKe7>e75_d;j6}%zIcm!>e$ze zwJ(GJ+5>{M2Lx*m2-Y4DtUVxDdqA-EfMD$b!P=98wI>B@PYTv`AFS&>vE~_F_aWCk zYFPKEVcnyKb&nd>J!)9@sA1ishINk`);(%i_o!jrqlR^l8rD5(Sof%5-J^zej~doJ zYFPKEVcnyKb&nd>J!)9@sA1ishINk`);(%i_o!jrqlR^l8rD5(Sof%5-J^zej~doJ zYFPKEVcnyKb&nd>J!)9@sA1ishINk`);(%i_o!jrqlR^l8rD5(Sof%5-J^zej~doJ zYFPKEVcnyKb&nd>J!)9@sA1ishINk`);(%i_o!jrqlR^l8rD5(Sof%5-J^zej~doJ zYFPKEVcnyKb&nd>J!)9@sA1ishINk`);(%i_o!jrqlR^l8rD5(Sofu2-Is=SUmDhZ zX;}BAVcnO8bzd6ReQCJ3XJT~^1Rbs!S?5ci>jlZh=ySawxfnU?cFD!aS=&o4M$UDj zXV&q&)N-jpub+_bV%r&5VfYmP7iIT&TqoY3R z`jNKKkzCi9$k9=bkjJbXp%b%e9{reA^XSK{n4llCVuF6m$|-W?kz*x?B}Yd!k3448 zJUTIJ45A;i#vuAJYfeC}d4OXjhb2cxV;0spMMrX2a&)*ap$+d??e6)uJ zYYz+79u}-UELeM3u=cQE?P0;%!-BPkB{_Ro(q|6~)*cqDJuFyzSg`i6VC`YS+QWji zhXrd73)UVMtUWAPdswjcuwd(zopcWi)*hDR>|sftJuFyzSf-QiVZqwNg0+VQ zYYz+79u}-UVpw~`u=a>y?GeM;BZjp{3~P@V)*dmeJz`jU#F8st+9O7;Jz`jU#IW{= zVeJva+9QUwM+|F^7}g#!tUY2_d&IEzh+*v!!`dT;wMPtVj~Lb-vE<5^_K1;dj~Lb- zF|0jeSbM~<_K0Ea5yN`s6V@}Iu%7vZ^~@)%XFg#)^9k#jPgu`zPkj&wRpq<`dR4pRk_!g!RlPtYQ*xg9ls?aV!g}Tt)-#{5p816J%qOg8K4Crc3G10^SkF|$dZrrIGu5!3sfP7T zHLPczQi!=k%Fs$(1iXQ;l5DRKt3v8rCz_u%4-g^-MLaXR2X6Qw{5xYFN)y z!+NF~)-%AM=eS28S5ihhjp(W*1dYuiT*QC{|6{J_uFCJ!-tFe&kfzfM@RSY z;rO1am}jwce-+mKRao~|VclPab$>Nx?8^=;JFx7)vIEDl6|=vf{SkEj?3k-9+ErVy z@(U}!u<{Elzp(NPE5ESv3v0e5Zklgl&9|`TTUhfgtoat!d<$#7g*D&8nr|i7I}w_1 zk!!w%HQ&OTZ(+^1u;yD>^DV6T7S?O&=37|vt?B%m-eHOJC8j20 zRvwWnkFfFxE03`92rG}U@(3%Bu<|JRU+2wDKW}PXN-b$!3Ts^oYh4O!T?%Vm3Ts^o zYh4O!T?%VmD!InpU+*G?ck#3?B|ci0!djQYalXXVf6U4wa^(?L9%1DXRvuyH5mp{y z-rtm^*gNVcUaf&u&&=>UBAP+ zewSR&4D0$Gxvt+~UBAP+eus7a4(s|I*7ZBA>vve!@35}lVO_t&x_*as{SNE;9oF?b ztm}7J*YA?+nPFYOBiHpitm}7J*YB{d-(g+9!@7Ql<9vzZJi^K&tUSWXv8P^c)vLY~d%IqT_y6Df_mjQfz1zp(@Y$#9KCg4Qrgg4sJuj?0!pbA8Ji^K&tUSWX zqvTubF#q{FjOv`^RCP{Rbxv4yPFQtLSanWVbxv4yPFQtLSanXxHSf0G)%V}0sLn}z zROf_M=Y+$2i5dSPE04&PM_74;l}A{4gq25Fd4!cmSb3CO^GrGh)e!gXHk<>w&T}Y_p~7 zf$EExs4rNxM_9E-ShYu3wMSUBM_9E-ShYu3{)%;nR&vEeby9X_ zJEE}eh{C!f3hRz2tbXC}uCExm?&!k0qYLYfF04Dcux}yv0jxMY_y0Gr(!n&gi z>y9q0JG!v$=)$_A3+s+9tUJ1}?&!k0qYLYfE*!=|Oy1=?EZ<@I4$F5~zQghzmhZ59 zhvhpg-(mR<%Xe75!}1-L@34G_;P9M*kuSbf3&>Q4I~wF%p^zNxk!GVuv(`(oPYjy-zBp`73TNABvY4SIB+AJ%<- zSZ&a`rSI&8_XE{0HmF}%cLibH6@+zH5Y}BmSa$_s-4%p&R}faeaCqlaj9m9KVcpM! zbw3l<{Y+T*GhyA&gmpg?*8NOa_cLML&xCb96W0AqSobqw-Oq$|KNHsdOj!3bVcpM! zbw3jh;~*yQ@*S4%uzZK*J1pN}`3}o>SiZyZ9hUE~e23*bEZ<@I4$F5~zQghzmhZ59 zhm~u1OW*bVqdUgLU;VFMjxnq|#<2Q@IjivZI`CJFT=$}3 z-HZPHZ>5Ldsy(dsFlVjb>;HXUYJ>jpuDBSv?sdbu*A0ii6{BD6VYP>)6W-Ey(f{ZU zJT|LeSa;xI-GPU72OicPcvyGfVcmg;bq5|+zi{|ngBZEKL4frQ0<3QkV10uC>l*}E z-yp#H1_9PL2(Z3Efb|UmtZxuteS-k&8w6P2Ai(+t0oFGNu)aZn^$h~7ZxG-x4r1~y z-(mR<%Xe75!}1-L@34G_ShpL1)-_gMOjs{l0u)Z7O{G;!NV0||P>${$k9e3y0r5iP01OR*XFSW=f1)zeVSk__w}Hmbls_i<;?||cukTzV`Ss_ojgR@M zY~ucjXzyfs_uq_N+r0aYvD1-vx{RIfyz9f5J_C6!XrBx84>66&OuFnGlIdM>X;$uvo zf&P5ZFL9PV#9wxj7h`mX`GUKYd&1dPZ1RlFCYTswE1dajocU{<`Ri#^~fhmq3R_CP=5Q~g>Wv>^t8oz@3(Vn!c~ne+C( zE?G47&>Z}?bGs+?wx45sd!5UY^Y;GMIQ{9I78yFQHRGmz(k_PIb$F3=wZ{W@C<_C$f5QDA>G>#pTC@92}hGrwqWOrO|_ zoIdd(^UHjL=@Xw}`Xm-GeG(&>K8YR7ybI*SLGAN_o;%{ADM3F-EuY z#Ta3Hq9+@N#@RSDW~?#JX_Jk^2+qc#aW)Q(vvFvgjYDJlWUTO8`ec5=u07+>I2(t? z^cnPPW0dyUIFy~H3pu*~C$E!jZkZmPx#zfK$5&hC;AfZLmb^0eIpcl49+{lE=iU+W z25ScOW~Lr$Og?Dgy&5et|;i4jbn#13YD z1@e5*J|E~IZq}YYgMNv#$!QzdNnT{X%`b1yxWZgxemj4sw{4k54Za&-y!^)`y1D#N zJ3V!mu$d;e?K-oIizG#*(u$9U`cbH8Ny@wpu1ZJ%8RCl9>d zD93mkykvON`HWL?jJKrO$Yj_p&2x;mx3;@ADfj#X_S+UGUXx6C`ScuPZ^ra7N&71o zo1Q~{?46Vwct(zKc;f1@Nyou0bBx1FhTWEo-;|pEJ$ejGikmJs{c~R!ntauLh3P-) zf}4^C-)$3NTkWbBCe;_MH2s@Dx;eSI{03`(%(~@oX*(<{SLw_2Oe79z=2>a_#8kiLIKHBs@u;}dM34BT zTwF}Qi&NtAYWiKC^DZu?-^D3$c{Tkm&v_RY)9>PxxVV^p7pKJK)%3eO=UrY+zsqyp z<<<1NJm=k*GyQH1=3QP*zsqypjX%@x#$(>))%3eO=UrY+zsqypjY}W@*Bj;CxHSE4 zoaWuQH2rRz=G_`<`q`)4xHSE4oaWtnYWk78acTP9IL*6pY5Ltb&AWBh^wY+zv!)+* z>#XUA1N(Ds%{BeV1N(Ds{Wbl_-TG_#;lTb}V1F*KKNrM57ucT*;-3rb&jt49g81ix z_~(N7=YsJQ1@X@X<0lH@p9|uj3&s!gO5=xlrSTI58(pLwP6!@Sb?iGuMT z1>-*o#(xyd-zXUWQ80g_VEjkH_>Y458wK+>3g)ldgA40V6wF_@9~ai2D44%dFn`@X zU08qIK3!OU+&*1cf1+UhbbEGT{fUD0)9v4d^~desh4m*2*3T$dKcis%jDod23f9jk zSm&c){fvV3GYZ!KC|LiaVEwmey6mhH1?#`bvvW%ntp8E4{#%>uJY$@lXNuA!fK#=4yCU&P<^GtXF;v;B+sn||gQ>l*r*XROQF{>Au7 zvi*zklVtlBub`iK#=eOC z%ro{C^fS-c7qOpt#=e4n<{A46`k80!i`dURV_!r+^Nf8F{me7=bw7T#L9gj&p0Tg{ z@v{SZO+WLDeG&c4Gxl{qes-~a9sSHR_I30#&p4N$pLxcw*$Iai^ddB(X4{me6-6VOi^o)gdy^PGTw zIIus@GXwgO2lnTAen3BRo*&Q;2lli7%6|4=*`E*MpAYQM2l3Ab_Ot)W{(KOB&JT(| z=Lf|+Qh<`p9KS>aO&JT)zJ{Uioe@uUN{xSW`vtaxu!T90)X7Oj91>=YFkLhQg z1>>Ldo9WNaZ>FDl7R+DHZx(;%SulS&zghgV^PA~so(1!l^QY;jpJ4uSezx&LoPznw z`Pu9zPQm=;{Av1`XTkcz`PuYm=V!B@c^0gnoS)5p;uNf(oS)5p;uNeuod30ca{kx) z$@yRFXA-Rcod30c@|>depYy-gPtN~ZKY4!9`p@%=)_LbTk9cF6%)AJYK zaI^8`3M=zpjqGoHVAl%Cepg;>eCCVA3IC8gWc)Xnw)_T02fAQ%Yi!V`liPSe?%EsE z-sy>?$LTjlzx&6SK3yNi^yz+MOrK7dF@3r|j5EI^&jsysfgXIYHuM?v8wK`6ft^uc ze{@3oORVNbpMk%$R~*ojWPYLFm_G3hIei9kw%8%3&mb?kN6S=+4tjnn#p9DG+^+l{@gR?C!+d`e_!LQ8z{BQavCbA9vvd8&i z{h}L2=c2w3xj0Nzzfr*Ws5W_6I$?CW-*kc)y&Qa3hc3WPRMz0 z71(d@xx60#o(rZ=Y*Kq{g|QtUVD#e~OrQ7+(a2 z&z0%1_gpZ22K^Fe*^>lzk{6SsJIoi{qW7|B$io9n{@%*RqQ!lO8Sk;)Jx9bNjXz44 zM5nj%>;G}XAC77tbGyl_R(v38Jbk?9srN^(RGnaa^!9V3xpnR`e)x=8(Jn7}W?Z@P z<;Kr%YsgFeUbHp#ikV}QU!G}g{M`II8DqB2VB@eeCK#_Om&-P!Q^XBJv&)`r++`vfBS2~expDh1?{6iPZa2nf_`&>J#NkU zZJs(`a`@OO5ce;#yWvd4a_ zOy|SLj7Ww&yiJ5X7v0-Fd3^P1)A`($wK8VYC&Oe554P~&L7uyNa`L|Y&u(AQzsd>Th4U0Y2GP0b5>*1 z`BBSblNZh|Hl4rBy(%ePu7&BWT)k1Ue(>?8vv_W|WbcvZn$DfepOWl!-npi8)q&-b za!b!Qos+*gH7WhU1*Ws>?0u5YpS-|y4w~K~adENsE>6j#9Xgr*ZT7F0v>tk~>3_J& zS&560{no`SIeBeY>ub)N2PG9tI@xb4RC_z`VrRc~u}o%-=wbcV-RIz>d97>gx7!^2 zao)wze(U0zv}xGKY?%4Yp~*A-``T|`tF}4sVrsv2F;3h#F#T>^Fg-3O$)dqG+HWuF zUOI8(#&o)Ilt1-_n|*BW-63&f$n>}|m3L#>>~Ui}@5Ye*){UvW8{gKi8}E5HzO64e z-t%q@nI1Q$@@}k~emC~>ZmfGBPim2OYrW}YU3FvKbh@#hck90CMDEso(+Rt=ZaUrA z&$~UqbRwUAVt>=qan8Ouw;z~(SwlUX(u@MFHf_ZLsGVg=25e4&tIq!4l)__(?V~bDk z$7@Exn2CZp!dhUyur?epu7$9H6xfKQI&e_&9;pP z6h*;Yh%UOLgW2==bH_#4!CHr1Cv50s{eFDxNfG_A*3mzGu-4J%%THWsebpIwN`zk4 zI{HBu>l?a*^)o^j>l?a*_0ye83hQTtF4j792kWOhqZHQ6C|Kv+d8M#sM!`BC1?#*! zyA;;XC|KvCV4aVGeJ2Xm`6$?fqF@h-f^|L$_M<4+k0Rznwr@tkeq{3OY-XID&7xpG zGI@4RGtSOw*qP7vN0Vn~Htfu2dnI<}v%S*VWal^R%xC*1cILBvlX#j=)=SooY~LiF zrjvD%wGW-Fg{&RfzDYbyC+i<;96DL^*blOOlX#j=);#urY~LjB2|Afuta0dM&0~Gf z_RYxco2JL@n~Z@3{mdb^Z<-#rZ!!jwY~PIBzG*t$zDeE_bTTL0zG*t$z8SfF({#Fh zGjjW;>2&*MGsXY?VG04?VFL?H%+J8HzT)inohTGMsD9Uoo?TZ+*)Be-M$&Q zebaQheUtUUbh>>ra{H#~bo-{AC;ZshhV{YpyL~fq`=;r4`=*^O{5aW>HNpCF`)1_U zKo%Le*Emtnqd99eKT_Fq4n$b%^c?sKbFd|CYTLw-()?s-@1J>$63UWv5FDr zCv0P$xwXRVar-7~qv>(`W{xw8AA9>moU5>t`RCR~)8qC{#)|1@E^>D92dpJp64j^BX|3z z>2dpJo@XlbBX|3z>2&*Mo@Xj_B6s_y>2&*M-tC*F)9ssiw{MzGw{Pa%zG*t$zL|IX zrs;J1X5Q_arqk`4dADzx&QiNH%)5Qlbh>>rAB>s2+c!<8+c)#UILW(x({#FhGtYT9 z8=su7Oh4xlGnMtlnJSnINiaT>U~F)nwBK@`48|vCDzkwzRWL7- zV0t-++LSp2eHB~x3}4E-Cmc_AMv4o`d}>4r`y{shHkG*(92k&A9OK( z&>gIw3Az|R=nmFTo;yq@F-8|-3Ejc^$+L#(B!0m<&$EWFP&-0Pid7e8=C$S0E zd7h87&L_cs#PgBXd7j<0AMxy_{fOryt@Av`X+PpQPWuthZrX!*M$=wH4Z)sm*;nDL zW<{M)wX7(3w*9l7wXN>=TV3wYe+K`(Us*lS{8e2ps0})K!3JuTg<4`z*QFL=^@{(y z+C`zB^ZQz8Lal&WaZu~{r#cV0`TwgY1okI^%}L-3{7<#$pq64b{E4+A;+!bv)Qz)T zn_TgCHp};asv8Ht{S#|YztzgnpV>fdN;QA$i~2BiA?jT)^&;wBFm)vAT`=_}>Rm8( zC+b}=^(gei*_67E#K+{=8?>>tF8i(36*HZT2lZujMdYe0 z!m2C6E)L{c?-z`f_rL}xFZgKd48PSn1FJ>~qmLS?zveFR@&9qG{x(myz`Xm@){|goanFH>CXrK5@(YWgTT&wV85-I z{vFoVcZI~^-{oDQ`zFr5DZ^&IDdYPznD5p2J`Ls@G`>xP-8XUe4~&fe2Gf?`!07Pb zr#)f1=>s|AFp%>tr`q$4r}XfRt+CU;^_x={H)2NYR^67kcg=o&!MyY3eKV|g@vz>- z!@RF%EW*4`=6yEI`()mW!@N&+x{UQM9yxsma(fq_wYPWinI3x=5A#l(e_;CLy*Nyt zft~hV967rA<`m}rKYdG%O)xfMD~uj|fHl8h`ow3LK8XcPpTr2(yLgxyOCYy*@mYI& z7Z1}Xv4iO|=r;-MA^x({-o?`%-O5+Ce>FtT-op9`v$wFW!mO*Tx5j?|GIlaspOL$^ zdDd;%>0tkg;B5agrq4jm{-yRg*7;12?ISRK2L0Mzf}FO2owk=CM>l)7*JJzF63MX% zrcZ2z(Sr}he*ZG2PkcsB42T6xpTr2x_AleiFUi@z)IJ~RVgHhT;%SU5u!sH2!&B)&<%yk6ABZ<}vGtw`c1bNE}#qgEjL{UjzTlyod9YyO)eH?salM73N+i zcQs+|b#jLj=3XcNz{vP-Fm3q_j1F|c=x+UwLvxR~v0C-3K1qe0kIpexH~la$Y1zF& zj(NQIA@fa7 z`t0?|ldmo^Jxv=7NPc?b5z|wr;^3rC=cT6S^<9T2ZI1oU^jvjI`($nLGSlM=AU7D9=;)$RR8i^)6-_JM#-S# z&NDqX57;UB`ozDPp4-1XFpGgA1Me-H9Q*whrl-&Q6_R-suQ5G; zYgZ|0x$Bjt=b;Oh=R5t})AU@_y-KqE4cD5UA?;S?dw$)=^pqa8CVzXA0j8%x-Szp$ z4;f;59-sDF{@jDEH$4L`=#YPL{V>zBZqK*#ONS0HJ=F(Zk#Bt65Yuzd!tVJqt{iT9 zo~_&~-*(6d)3fx{{`r4Y>~DGwJmS(N&061LdX~L0F#r9`!KUZ93$I$TX5Mhq(|X#q zOZH!Uv+23ILhmJ4e|U@OnST0!B{je4YkIn@+1PO9sxhYLtq%q*nYz8#Q@qV*4e!|5 z>$#$MbHk!CUeB5He`t7p&g&Vq?>4z}EBoI*_TYB8u4nf%8(Qx-Hh02^L1x1%ppooDp7_Vb%2xl8)rWOf$cH6^!azd_c% zQ`bjxy=r$fJqu^Pk^8*KNVB=^>gl;Lmv%8dRd0JgSJZWw{dV6vf6q;x*TZ!79QSGN zlw;c2Z^t$*741^{Cj0H^nk#Y(YV|SwAHMcwZc^1tO;7JvOGg*KHo){utocK(ZPhDH z&sQ6FitcLE()4`YvqH2_`)>BzKAU!puJ1Y6bdEgy*WBxiTAQ9t%PK{?&+27*`c&UD zs@MDi({t$6`$hFfoMd`hesWNB+1$SN+iiC$AN6R|!F2BW^#Reu5zS0b%T=|bPbzgb zJ#|*sj0UDHO;6olj*LoOS7s@b6`7+nAoG znl+5Bop8MA;osQ7{Kc*^@1JaX`1kq~FEl-SZXZY3!J2?wt=2a)J^ULxSRb&9xS)qP zVFzmkc5S<674$H6hy}kTHslPQ!50mnZa)H^vQm7)Oi`+B04l$LM5SlQVRZL&hl?o1VZ)u_3(KWx=#lVhhlUm0VkJ6{=Nn>$|_)2};UVP_sa z*vURizwWGsoq6cQH3T#N5T! z^blJYL(@YH-55)-hcV{jW_pO58&?VTFs|HKO0b8qbJ&YMQP7>^4oVdATdYC(I zJS5n|cyRN@^e|uC95Fr25jQVP5A(u}f78SGcfU71%tbfOO%LPT{oeF2|J?6Q4|C4_ z-t;if-0w{f^U3*RdYD7*_ojz=0z!oe@qW^!uex*oPUgO(_`!Q+`guV z@$TYlda`xf^f1O*ArI`y2lnIxd-8!j z`5->|z@B^%pS&A?icda>PdONR0@lMnvrhrglV438wx;t;yKe?u?P~-;mRm-@xcV7o64Z zjOjCw|J%QNqW+_M8o@V`Tfbd(cV_su^uOD;t6{#v+TE6}u`uqbx6tR-y6c}?cdb~d zYSA&xYDE?1JympCn}dpOdF&wL9XcLb)Uj?=<38ISUDWmMJ&l|E*r4d9TBVG?s~#8K zQTC-AzwOrYc&BH!@sXFFRJ6yN9gG_`ZCv!pr5`q=%{w1AE+Ut3CSL+)?el>i<4nJC z)^9?a%pT*+PUFme}m+^aRK8T!OX8)}t-nVBVY|G^4Z`M9%etA8{nSSG}--tGuJ;s@x#+m)b zVZOwl&)y+c?qKB(R_0?gIIepnV?B^cX95$dx--xr3EESh<6h zJ6O4cl{;9ugOxj2xr4i9xr3EESh<6hyFlJBXrF^KJ;ur%a^((I?qKB(R_@?1Uye&O z?_8S_%{%wo63siOvqbaG^;M#I=WIv{^X~C463sj3W1@NId`vX&oR4NVq^?yVAUI&r1(lyz0(KC2cQCvWW+_j%(E<3pdW z7Ju^4<;EWj+CM&O*- z=y&}Z)339~7<-(Z#@OlXH^zSFmvQEo@sfA%5v-nv1ERUuq%cJSf@@V~L zc{F>nJer+Z9?kwNkLIJ~K^~JJk4ccnB*o?1z*^}kb>{MQ`pL?8c%-i}SCXX3M%u{hDPiP-<)&{xFU)SC^_^q|)J~6-j zYDCqTd&cmSFYX_6Um0Hb(Sh+k`*bm0wyDDW`~e2fAgqrgX#XFgi{%tzCc`DpqxAFbcaN3$pM z(d^88H2amu|G;?AI3Yg&%v&6kmGp>E!xRPfp-)g+D!gJZL;^$l#LJ4Ht=v#I8+|+PL2q>9&rN^!8o(cIJ4O}^TpWti;rS_R~uqtoW;sG zi=lBATjMO|##t_mvm6;`xii)?4nA(JC;VH~6I{J?Yu(k=DE=+#u9Zgiv2~37efgqZ zB_AwVXlK#UU-l^Je%yn`U;gcyl0GlaH{N~wZY58Ty3e?LsjExY4Zg=X-{vZ}4&QCO zwAPg+&(E1`Joxe}N;=lK(|A?wD@sbP8EfqNwKbD|oxDhL*S<*Yot`4;ar)i5=k>dO zi`1{Pr%3iVJBwtev%g68JHLwLSJqcTznKljSsUZ*x5k-Hn*JM zExfe`IQzd-4bawG^5SZPybp?CS2N^&kg=;J@;=De)ficqj9u-~-gD7@>${RtrHF&x zbHT0_&3iGc)BaiSN`7~4w6(YPobqvYzKS^Kh>>fZ3>n+9^~CZh4)oaBNoTf9UO2O5 zHYAx&lZTw?XMIjWrcJnZWo$Nx!#1$a8xvAjlJv{$L2-GHclkxw~_~JeNA0Cv1sP_6O0eucvn&T@$HTO)_FqF z0hMkr9@=qy(UgTZ8@GA?_M&cAjWeG8?Ujn}mu zUNmUCg~r)jGY;*^QL4UOO{r*g)Jqx+^GFW>Yti2D`o(OBNgtdpl@(cbe*U3LxpRqym%(lPe zxjV}*ec9OF68q5~?Snzg?OdV#3%T|+SoW4!rWB7FyDnaP-^(TNHy^K# zOAdO%c-Ko-#a+8EFuwADr{Yg)O*6ir>ErRii*Gl+ZRaGO-E)-jhFcfKFWh~z@yzn` z;ufcmG`{<>+404l#~L5CVp`l})gkpx4GqwLyQ0ZivR8M{f;U=f5&##{`VR6$Ryba%1j*GYd!Q1x6^~V*r8sKg2{9&WwMvG6j-*!F!_~LEt3!~T(b8uCNFbJ>EfaF zn;3Wdar@$9&uDJky!B4SX*qAhlg)Q6ZhG-qCSUzTnc||_=NdmUqg?UIvsxQ(Si4v8 z$kpc=w?C$G@rSp2zpBruR@`Q?=UzJ;R6PG5zDIP=Kj ze)ssk9-eh{ar2A44QtBQD}HB=x9!On>ld%O!`uAp#sr z$-kX9J6?F+M&rkeXU1JeerDVxzB}IB?0e&lOQyv)PTSUOtNqy2c>1n88;@!=HLkaC z592z6rp9eA*(>dT%FMz%g_Ubqa~9T|g*9hk%~@D;7S^1FHD_VXSy*!x)|`bkXJO4* zSaTNEoP{-KVa-`sa~9T|g*9hk%~@D;7S^1FHD_VXSy*!x)|`bkXJO4*SaTNEoP{-K zO`gqJSaTNEoP{-KVa-`sa~9S-g*855jZawP6V~{IH9ldDPgvs<*7$@qK4FbdSmP7c z_=Gh+VU15%;}Z_Yr{)@RtvRsP99U}(tThMLngeUifwktqT618nIk46oSZfZfH3!z3 z18dEJwdTNDb6~AGu+|({YYwb62mV)UPUw3WAIaI9H0J-e?Nh`pT*nj#SO~!2cW8Px(t6yZ0WNKJiGr#F*eX`R#d=UNJ`J?8a-2C%e9;%vfcN4I4gs(iq#` zI(eCI<7{5LVW}~`w0yk87$0Zt<{96`rB+^+s?F#wJyZR*_ozXsbPlX@Q>wn2d~{1H z8;-x_wp6yA{^Ph*Hm@l^A(bz^pPrD)M_9hoMls>HiWNE)L;6x|u|YA%Hsu1Fl_Pvn z?$$qkX{>%>^-COfsC%Dc^qD&LA-Q3&!3DvAs#>PB5Skp!{+fFZ?-qC zxbB?znHfI6RrhQgkJzJ)$sg`;QT*jG=NWgt=aRVL!RHziXZ6)#;OK(y^ETg-s?EBy zMy2}gusJuU(m8n7;i>xi`1V1mYx~yv|n{RJ;Nh)9HOTJ@6dZr&IwCVn) zXMTIyfTwM2pmV~ZD~;)E@`~q-v7!EPe(Yh}gPmSBIX1ty{~N~m((2gvjESxKA`X%h zAGIfL(nCC@pE#>u;xBv1i|iy{vOgS4;vf1>F5c4PDqJ_jVZX4(Gpz9pYdpgm&#=Zb ztnmzMJX@RJ%_H(FxyE)F2W-kO=Q2G%+QYn_3$&cIq{ z;Lt~{b)j7Aykf#StT`g4{a?8bhjyx8Y|#1-YyF3{{=-`TVXgnxCR_hut^aW7qxPUs zPJAR+th6U$CoG*>WB-c%k+B{23#(sP`!cM3+1h0LGOT?W*1imDUxqc8@m-8uzK1bE zzOlpPw4}_talK7bi>oi3oc0>F(YWS2lhbC~eQ3P?i^;YQ(+0*Dcv1Js>B~2sYrO2o ziRqrdoM(LItrOCLE!rBtTV_If{f_O7J3Mt~+V&~W<4W#KufOR6lc%5EneNuSz47EW z6Vg^YUTA#dc6X&K7JI(p&AZY)&%4Ov?|n2eE&9N7r)rbawe2o8`J>&Yr1!k%`K2*a z)1^Z?n7r(D)6(PPON?*dXL|a;_Lmxu=r%nqv%z!Yfz#7%ALwZECZ|kK_ZoJY@p(^7 zOW!!Vlkw$0OihofaJliIFQ=quJ?i-;7qBP>SKfiHgI%-$XXH*%H9`cm;<)ukCrF&2H{Mz0(rY**K{>Rv1 z=??dM?pb+g`p{dRmo6ThRyxY-dGG69X`_#Pzt`W~DgF6dZx3Va(KEgMj4|=>CP&6< z^W_7_#ro|{hqZ{M^U_Z`#`0y)*Di_W%ebBw$MWUV)$L>XGJkX1SiY2ecYZ8ip8TX$ zEMMMw@9bE<{Q6bPSia23T^=ij-+gjLtk}-_tV^tzPd~VOtXv#9ut%&M-T8K}Sh*{G z_zkggdV7ujv2tB@%z#*9V3#!mV~ve3ULF){%)B*iaICSky2g-LW9-@XLt>4+@-2tN z8k1GN9UN<{jz4E`tTEiK>!4U;yK&2bvBv!8KlhI{7Z$#GeXKdS?v-A#=HN@sdc~T9 zQGF-R=HT!Ny<*M5Q+r$=YYrZ;ymzcQxUu&QvF70VG5uoA!7+>a#hUxknFC_232j#o zu=6Tw1AYNPd1C#f6G2C&qUw_u^Fd$y>>zgLOu+gyikxefe zzr1EheC(9<#?uB5jyDW@$$0dIgW~RYziiy*>VfgVk2V;0Ts$Cdd-kiwc*^%9;x@aj zHh#Lp$oR6$o-Y+`i)qqQCa>SPcf6=d ziSbA0_KAnzl^P%O)(!Dtzb-YN^HRUKZt-KrKkPjqKKzWwjmKRvFkW}~GUHiq4T_ts z@jUl~9`S7l&o+5(-nH?`uitIFqILJU!4miW$mQ|d@4CbXt(#RGV^xhinULR%TDyXU_|4%WewlvxCV{l zt7HG$JI~9-wO<==?RVL~UVOsl3C24;SSNm~r?+9}qYjUEJloqgXmRbhW>;@>&DMv+ ziyxU~?Wa%NHg5jzV&k@N?iAlP-Sf!r%EXo5dD!G7k5-6ZpY@RO*fRUZJAA*;_|?bv zi}UY3V0=-&dc5kI`NpeXuMuBZa-Z>;dmkJRSvALa#I*XU`r5N?+f+6bRcVu|P5zzp zQvJ61qvxj5`S&N!Ox0K4@~5Y=Vb<~{scgIM=Mz%de9C)8seIXCQM>fWe%|*tDqonM zbd`_EPJ=q6tta|eEm(b7`g2vEud6m*nReXX=j(`x-P5-(^f8ZD_DU~2&gUYn-akEZ zme0}ZD+i@>CU|~+-q7^Gs=m#S&)%56cZmP($VDU4la}~=wLa~Z^sPsIzB&)NHQjWC zw_!~4vFW_8r&z3By#2QH-JhoWc(%Gdz2YdJuNOLwPlv4V7H}bx(off@#1!K)9su4^`u_2 zIceFIew{h#?0eFv##(ECSk2k#^=J5XY2J#N>Ha6ZX!7@)%t$ML?|J(6lhf*>-ZJ_A zA5Th`ZuIM0=}ME+ZI651Jzp^TtoZC#?l<`(hn*AGx!!Z9Y3Ifdee37N z{_nPmH=OHvuMbU?c3dRUVP4TbB(LHTG03}{oHx# zr?ThGLD#3Uvuc^^Q`z6+{a&f^gQ=&60ykb?g0zaCQPw||eJ1$$ckNwKaXUhl0oj&n%f8^}J@f|OFZaQd4{Lm!NJz5TpZ;d@a zx9hNYuf(q#bMG4#=l1nnhf5@*tKfgXa{@YrA zRzY6!xnHAb|7!)$=vmwN8PkLQ-Xr{)M!!=&_G=yX9Ms7(c9z=NGxk?|&YyGet9jmY zi+2VVS9>oX!iW~hZp4g)}W2fSe{mM(n_ot@H*VEfgO(oy$;3=uvzjfZ^RC7IY{v9L`%T^MF6cSs@EHaD2R=8W(C_3kW)|#OwqRz#&gmb|EZE=U z*O>*skjr1%D-P&Ue9*7B(XZl(J&H4SD*o87ybM@AK3)Bbf1Z8k?Q!V`Uwf{(!??7^ zOP+sda7WryX-anQ-7hl;wmYpZw(?6E|dzbW&l`rJV7wwfV^eA8GSH9?1`NAIM z3p{q_!2!?3@r? zS+M`B@>dr8LN0%4uQ;Gb@j<`hM!$+D_9)KSsrX~R^3rw9$?;zAB(`7F?0aH-+hv}& zt#N$Z_ZxqP@9<=Cyzyqwr|fxrd{SB8X8+4ijBgm^S?|1f#?(76nEDd$pRRec@4S%fofoWkUa;PI!FuNf>zx;@cV4jGdBJ+; z1?!y`j19bpQXAeG!FuNf>zx;@cV4jGdBJ+;1?!y`tan~8u~lDs=Y?GFykNcag7wY| z);lj)@4R5W^Mdux3)XW=Sbv69e}+|mhE;zStCp_%Gji3RVbz~u)t_P2pJCOXVbz~u z)t_P2pJCOXVbz~u)t_P2pJCOXVbz~u)t_P2pJCOXVbz~u)t_P2pJCOXVbz~u)t_P2 zpJCOXVbz~u)t}*2S^XJS{TWvM8CLxnR{a@P{TWvM8CLxnR{a@P{TWvM8CLxnR{a@P z{TWvM8D@@9bB0xahE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!t zRey$6e}+|mhE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!tRey$6 ze}+|mhE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!tRey$6e}+|m7V90Z>d(kke}+|m zhE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!t zRey$6e}+|mhE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!tRey$6 ze}+|mhE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!tRey$6e}+|m zhE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!t zRey$6e}+|mhE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!tRey$6e}+|mhE;!tS7-HS zSoLRE^=DZ1XIS-TSoLRE^=DZ1XIS-TSoLRE^=DZ1XIS-TSoLRE^=DZ1XIS-TSoLRE z^=DZ1XIS-TSoLRE^=DZ1XIS-TSoLREHD_2gXIM37ST$!@HD_2gXIM37ST$!@HD_2g zXIM37ST$!@HD{PwF*Q0^HD_2gXIM37$*EzgJvB@iJ=8E^)tq6~oMF|RVbz>r)tq6~ zoMF|RVbz>r)tq6~oMF|RVbz>r)tq6~oMF|RC8vg|_S7(8)tq6~oMF|RVbz>r)tq6~ zoMF|RVbz>r)tq6~oMF|RVbz>r)tq6~oUKh(bB0xOmR$K#%^A6B&ekTYIm4T#M zsyV}|Im4T#MsyV}|Im4T#MsyV}|Im4Tz;u6(KHj9fKmST$!@HD_2g zXIM37ST$!@HD_2gXIM37ST$!@HD_2gXIM37ST$!@HD_2gXUVBysy#JKST$!@HD_2g zXIM37ST$!@HD_2gXIM37ST$!@HD_2gXIM37ST$!@HD_y+)tq6~oF%7*srJ+`Vbz?i zO;&S;Rda?_bB0xOhE;R6Hd)OXR?Qh!%^6nB8CK01R?Qh!%^6nB8CK01R?S&*T#MsyV}|Im4T#MsyV}|Im4T#MsyV}|Im4M46Ei0tL6-=<_xRm46Ei0tL6-=<_xRm46Ei0tL6-=<_xRm46EjB zZL*p(teUgr%9m=+$W?Q;Hd)OXR?Qh!%^6nB8CK01Ry`S3JsDO#8CG2yR$UraT^gp2 zq`Se?k;LI$blu6P{g%8NFMGJ-4R7f?=lH9>!u!>K#a(XIa`n9u{%(nT(cyE7`1iHw zE%E%KS~q=3Kdk2?SkFhWo{wNXAHjM)g7tg^hvQ$2{68}0)rR((7qI39to0DqdI)Ph zgtZ>RS`T5Zhp^T|SnDCI^$^y2DEZcRa8nEGAu-W<2x~orwI0G@zQoL_kd;T|$|I~i z!pbA8Ji^K&tUSWXBdk11zI9*w&+ltGH{Q-}lhDk@)D`2g|@(3%Bu<{5ikFfFxE03`9D7ogH z@`!xv`M;BYb{OdIoDdV`5#D;I%irJA^EG2z&)2Y?uVFo3!+O4k^?WV)mb}vy=1Uyr z5#CxSdD@;Mlt*HsJi^K&tUSWXqvTt%PNF&_V@7pISanDnS6lDC+WjBZA&JR<)!o-H zUt-2d$jT#f<?nwPC&2hV@<>)_ZMO@3mpQ*M{|8 z8`gVm$@Ogx?e%Sr-fPoF@3mpQ*M{|88`gVmSnsuAz1N2IUK`eXZCLNMVZGOe^?nwPC&2hV@=sa($b#CBCH!^Cb@R2rG}U@(3%Bu<{5ikFfFxE03`92rG}0>wUNK zh+KJul}A{4gq25Fd4!cmSb2n%M_74;l}A{4gq25Fd4!cmSb2n%N6GcRTX{tOXWdUw z%@dts#*b>J$p6)Q1ht{P+Q53(0PBtrtouB$?(@L9&jaf|53Kt zJh1Nbz`D-^>pl;x`#iAj^T4{#1BbP7F)@)}u>6AM7c9SE`31`_Sbo9s3zlE7{DS2d zEWcp+1z*F0dwQ_$>A||E2kV|5tb2N}?&-n0rw8kv9;|zMux~B*0 zo*t}wda&;4!J)rm{FRTee1zpAEFWR{2+K!UKEm=5mXEM}gykbFA7S|j%STu~!txQ8 zk8pU0Q;hGSk6Zdar~0B_^#$whD6G4qus~ahd(p7& zMZ>xm4eMSstb5V0?nT487Y*xPG^~5kujq ziTn1_PhZjx>pnlM`~0x(^TWE&59>ZZto!`1zM+8iy#uW89bkR$0PA}PSl>Iq`rZN7 z_YSbWcYyW11FY{IV14fZ>w5=S-#fti-T@BdFDCx-1(q+ce1YW)EMH*x0?QXzzQFPY zmM^e;f#nMKh`pQD6F7d6G+y?!D+cDcb8hCRpDw{gIyE{}!G4 zEv(zg}R-`v6a<_^|3cd)*>gZ0fFtZ(jMeRBuvn>$$F z+`;4Yc3+uPAehYscd{-+D`wjIV*SET`zSV{Gtu7qu5u-=Hh4oul zzlFo^j>YKwE5AXOongPQzI}%E?K7-zpJ9Fb4C~uxSl>Rw`t}*tcjd6YD~I)6Ijrx> zVSQH)>$`GT-<8Aqt{m2P<*>dhhxJ`KtnbQUeOC_ayK-3HmBae39M*T`u)ZsY^<6ov z@5+dJP`uhp6{(b_izn=i>?ZS z39-^|;eYkFAb$V1BlI^&!{3Ur=l|yKA?v$x{T6%v)!(wvePG&%!+w!V4|3LO{w|09 zZZnLW_4D_vzxgb={!Tvax5VEJ3IA4!IJ5zl4X|v0^><5P{oN8+f42nI-z|alcS~UX z-4ZzLSB$?f=VZ0fIb3quZ0Wz{LXPw|WW=F8@?}f@ZzzQQit(LsrTQ^utiSUEhy9B29WJaDzx&_dkbF!3 zogB@5VWyhZ@l99+E3>dSE*9V+P}GUUh$1rc)sV3dBqQ}@Vs-6dBv;h9Bge$ zwVPKwce3XuE#?(}zsDgaKkL+a#Z3ozMqX=^XWGZ-*0wh2>9o)@`d`}a&_cfzPxg#G zwXXGyo#V!M#{K~lJ>!?;#Vh6)+8% zcqR@rHh3mJZ|}QrA#N=?dnTT}pY}|gZ#}ZIwITjpCV3_=kCv%oa`IKCzh~s1eCnC@ z+nrO@+Mwsi2R);I(zg2*`hDd@&)D-xchA__=2p+x-}o-iHV!j6{;EB3kRIYA{lrcE z5>MGfoMk8Rm;K~LevvQvi(GM_z2bu&#SQ(6C;ckU*rWJkr}BdRLw@}wX5Qgf>+-)E z<8Q;$Jrjqv^E?xuEA}b%Tih=5OgwjZ(lc?ca`-mZhWP(5!83U|b+>IzPQLEE!87vf zKK4xek!NmaZP1gS?-~8IN|i43d&%*hvFEz3p0V?TQJ%4X&3MoFB{}}8J#mm8;v@aU zP5ly2*+ZOVC-Im4*Z`mob14*0d( zt)B6>&pgk>VbmL*iO(qhl(AGYI}g?^Ve@r*s|dwRysQ||DL{YOppj9-%Dui6s_=^;MS zPu$cm@svHpS#}bC*-u{N7x|LE$Q1|LD?aE^+|aLh(y!u-J&HeeDlgbS?#7N52mBf^ z)-(QovA{EN*zRr5#OL_xmlfhRubXG$`RenYiSrlrJ6Rjz|NIQkxNaLpx*QKkeXF#@YNbCSMQ! z(xf0?z5fY?_E*i1jL|dawR*MGfoMk8Rm;KrNvVO^z{6(%f&|dLDkK%@Y#gl#&XPaMH{IOGc z!T$HId(Zm9uR9L*jKAgMcMEYCRPwel@fqj-chku)aXaM5*NutiQzyS-Oq}=H{Uu}a zRb%p6W1p|p#^mep8&?(N@xChx?MJ-*cVqM%^4&6H^e5LmW=y}&U%u2Bdm4RIVobi$ zUlL>NziPf`{E{4h)t)#=5Al(H;--Fyr|colvXl7BexEPz7x|LE$Q1|LD?aE^+|aLh z(y!u-J&HeeDlgdY#$l1>mm7!1_`CkGLyU=o8;8ck$Bjc{n_sWhGbWyH92yg6Hx7-- zmm7!1+59plUv3;0!H!{L1G%VF&2ZaGZ8B*$O1 zCl1m>e59YasbAtLdx*2_B>uAB&#yDAFY+aSkt+_gSA5W;xS?P1q+i7udlY}{R9>(@ znRM(@`SrqB&-i;`56{G*MPtvzr`-0QiQ9}t4eYnXvu7*M#QCDn>zkZ>4I1c~eAO-M znS5=WQqS5T-{EM_wEz5>x+X`@@+&=~|J9^8r$5B@xR~lQ~7PmAep6ho-2*B`DIML z+;e3??w%_P?cH;wF?!r{r7`;5bEPr;y5~w`>~YVP#@OkeD~++=)d7t0OLF{Gd*UEH z#7FvxoBAc5vWGa!PU0{7v-xFxkuUj+Tydbi;)5RdJZ|mLuXx%x$>NMXia&NLFWCRq z-MtEaeRHR0{2kiIGjX`4xo6_jU{}w?ZAHGP{g!x6YU`Oe5B=sklasG|hI=Mo=k4v8 zeC<4|hqXa|=&_z@UvbT~CP&Xdx_d@{?*l#4Z}B_VSR3p)>_N}incU_X``6s$nS4o( zziLk$q=)!OKXFsP#8dVVXW2>oWj}e5U*t>vB3B$}ulS%xaYMi2NxzCS_9*_?sk~sn zJ4dBj58XM+7=PV4%9uE~bCfahapx#w;^xj##>CT|ql}5OJ4YE4e|L^D_Vdd#`Euu| zg8cMzo-4F>=O|-`rSFon10oWxt{MQ`f42!`ZLH!~ z_0gX3_knJniNn+rJQJUbw((5dzFx4W{g!w>eU@k9{NN{hn4EmA>+6|(4c^@|`KmXu zjI}}D>Il!YKmMuRO^%)lmwQJ4>`I>Lx6{kJSsUzWb&qH4{NN_f*#C2X&-f)d{;EB3 zkRIYA{lrcE5>MGfoMk8Rm;K~LevvQvi(GM_z2bu&#SQ(6C;ckU*rWJkr}BdR?!ANg zj$iJ5gfafQ_YTIy!M%4V#K*mNFeYy9y@N6FbnhLEiL-m}U`+hodk16k;@&$LlP~w) zp&)nf9SZH;dk16mxc3gm=y&fOjOo|CcQ7Vj?!ALCcDnZt#@O%P6B*-|} zcwzkIZ|%awfp30c;=?z;FmdCXUzm9E%`Z%x`Q{fUUwrcmlP|u}hRGM-XiLsF+G@`? z+Aw+-estA~xrmy4e<`MUjxhYIoyXD%wV zzkl#TWAvQ;%!9`0?{$c0`u%y<1186wR~ma}Tz$W*XY8->-2!Vvz9h$AwI>eJLwuy4 zxT#;_DSL>s>?HoOpS;K~@+E(fD-N_*e9)t~pCREc*zeB0#^g(K{8fA6AU(uK`iYzRC7!Z} zILl7rFZ;=h{32iS7rEjc2_~(;fx7| z_6-K!X^fsXpBitB{_Sdcrr+T+#+e*@I-KMgI|uLV8T%J(zQfv(FUj#&?TLf*5FhC$ zZt9nK${yk@JBh#SCohkd@qUpn`HNg}puOUQ9>op)iYNUl&e)^)W2f?h{jP3P@XOV0 zjPcjiZH$S7tJ@e8A6K_ACT^~7V@y0<-Nu+WySj}r^UKw3jLDaK4{J=mT-~N1cXgXW zdsnwHMvtr87^C0SZH(#H)oqNi$JK3&vD4LUjIrO<*^J4TBe`_1`$qn7H+uSlyU-K3D4iW8!@6&DD&_*UxLK8vFTG#h82zXu5AfzVn!U z3hftc-pd$0zxJar6ijU2&ENiUZ zWzYEA>#ffU-Pi5U)qOoO9#;4D$oN^^*CXR?bzhH+ z&((cBGM-oW^~mCDbzhInU#t6iWd2&+*Nw04>*lZS>yhbM-Pa@2zq+qSw(jb_&R?th zdSp0P_w~s9wK~1?SL5t$J|5D8pY-Fcb@3SOO|INqeFZxX{ zGM<0_-}{%IasK+eZ+MaU>&HLkMdq*n@Vmb3nPdDv`{ggP`QPyue$z8f&+quE7n#3) z?q|Ko*8Q*k%9lQK;Q4_+`69#l1>gK4!~bR9_#(5barQPJ59z^A`tjDf_zVx8!-@a! z^GkN|SN0l@2lL~Ho_M1_KCK(i@Wely`33&feLc3bYjt0b%-+>~Ju)6v_jUYy^y6P- zysh5s8OP`9z8)FRtNVKS+ws4;uSb5#hc7aJt?ui_SNC=ESNHYE^sMgdk?CLE*CShZ zbzhInU#t6iWH?v%^~mtAPVbSQefaJ;dz+7k^x!A`cxzpJh6m5##DDntW%X>&TKtv0 z#^b^K_@O7>=#Nk9#xp$e4`+UX|0lowSD#()`<54(y&wLaFESo}|F3zG@$-d0_eI9r zU-{F&>iJuI{;4l{k@5WD|La#ixf{D+@kvWvg6*LXabA3yZO8~yQV-FSv4{^86o@bBFFs`KH_y^qY^ zoqHb{4?FihGJbyTKl>?;{O{cR$o#VRqL0j9JNMrB&b>E( z=iW!AXXoBWrhn(&N4DKi*mwpW(rC zIPo8Te#tKW%3kB~V1E426L0j#r*-2Qp7@6|zreruY-iWrvz@(r&-Tc8*n74|#?Rif zJu=?*p6!wGx%X_3jOV>)du0CFd$vdBukDLR=C8eHyYaneyZL+1_Q>??J=-JGzxQm9 zY~8(Qdt`X_p6!w0+oW0G*LwfL&e!R6VKEs3OaNf+F-sX|#FWd7QFn;YMIo14G)Hjhlt-rGDf{d;fo$kyF^n@5Ic?`<9# z&b_yJWd7QFwnyf##@X9^JfsId>Bn2^;xjyW4k!M@{}Nv>w(wW>8jlC_Kb-jm{?)-=UFGUvADO+YgMDN?tPb{(@v}PEN5_NutAl-HJg*M+k@;(N zu#e1NfAk;zkw@mQ)xqBQ>R@mF>R=z4p4GuVGX1NAePrvd4)&4ZSsm;n!?`-xM}~iO z%a6=ojkCA;ct{U^(vP>+#btrd}Q{1;jjC&N5;c{`vpJmk@53C{U0Csv*zRNXMW&E9~qxN_F3Qc z$awzd&;9a8=CA+z+yB=;V?KZVstKkD=Hnqf_(?zBS{I+;!E-qAAAWxMi{JX4k6rwgy~g9g z{P>|K-sq1{>&7!Y@egNyfq%bKT{Z4sg{@U-98{hAgo4?;Fk4(>gr#v$K`)m% z#2fwbY2A2+C;s8gFYvEU@9bKg-r2i4y+`J+)#*JletyGe{F9H2x7F!AGCo(Q_sDo& zo!%q!*Xr~hnZH)2_sIOUI=vfTo!%pxzdF4~rsuoA|3#*Mb$ZXZbyuhN$ndOA@8xfY zb9H);%wMakd}RJ=oW0G*LwfL&e!R6VKEs3OaN`N2X`*MIV{|y%&9C>+ZeiBg3=zqK^#c-itmmf9*Z?BlB0|>}@_C z(u1G$@^+_=En~`@kW1qS~s5IiGMir3;e75x_!91uiKxi z`+8(NtnTZP@w2+GN5n3C{CYn8=r_H7^=_YsM}D^##M{Q-E1RQF zf^j_PlR(Cgz6xZ#>61Xlr#=j1JnPRu#=pJ|WPZ`lfy}@9JdpWU{|7Sv>I>2MzC+!7 zeG-h*qfY{veti@{Z@ZdR|_zyq7 zc-~oyzp~eOJeVIp^u!ze@oC+7h9~~v%rEfklaO8dBxJ8X31mFzlR(CgJ_%&J>61Xl z=k9AfGM@EGc>Z?&+Wn44<}ZB`jPuu*t}g`HxIPKZ*C&BY&+e5xGX44_7`LuI31oQm zNqGKtIQ2;&^OwFBWd3TLz0Jo%dhnBeytOVq!-MB=;y?WSl3o0jy~g9g{P>|K-sq1{ z>&7!Y@egNyfnQx;cB$*jUUhwB{!-UR#*ex_GTzknk@2ankBnz^ePr>au8+(w>iWq1 zrLM1Wb$!iO*GHyDT_2f#b$w*(s_P@eqppt(r@B5ef2qSH^H<~SZ9X2-gP-){t#$Dk z9z2H=|KaDC?BcKNH69P<#}7U6Mt^)-H=f~%e>n3C{Q6pCm%bL+yYFj{j0b%!jN@nD z;~x3h=j&@>9H07Hknyaq1)0C}wIILb!xx#q^tEVQUyJ7JYeA-G-x(j7etj*BTUTET zGCcZPJbyc!`dX0rOCJ(4e>KkD=Hnqf_(?zBS{I+;!E-qAAAWw(uftmWmA%H}!Tk84 zM;{XN>5otA#xp$e4`+UXUtf#t($|8_-rZ+^Wd73E!Z?2PwIJh7Ukfrm^|c`5Szik> zf9Y#Mem5UJGJol7(YU@A&DYn0Opm@6Wcu~BAX`^o3o<T6*fetk&D{M9&n zn~#U|;3xffYh8SX2hZWefB5-j`S4kbzp~eOJeVIp^u!ze@oC+7h9~~v%rEfklkgt9 z9+|!RBpAnoJ_%&}=#xNx{Ixy_WPIwAK*qB^31t4#CxQH~zaE*t^hs!3pM>V?lR$p_ zwLS@C`t?a5TUVb1GCcYukm1xPfegRC7G(ZvoW0G*LwfL&{>NYMu8Ys`;5nT55C6OV zde-8v>@^+_=Eu+DuXlN)KR&G+&+x=QocdR=1%BTFv&(nD?DZXxj0fKV$@uXdkc>Cq z0m=CE9gvJ?-vP<|K{qbqtc!nqb z;mj}a>ywaO`XpqpJ_%$z=#xOkk3I=xynW6WzsUI1C&4(L^+|aCcK*^Qfy`g}B#`+_ zpM=KsNoc-431oV959pEU*C)Zab@fRg!=q2a^S8sPPXd|0^tB-KSL5t$J|5D8pY-Fc zb)WtJE*?CG6aV4om+a!N>@^+_=En~`@kW1qS~s5IiGMir3;g;dWS2e(*{e?inZNW& zAmc}$1Txp9C_V^+_O$FMSfo@8-it<}ZB`8rLVG`T8V~>Cq>FOus$}Wb5ja zK!!)31TviZB#`+_UkfsSHO}7V;~_oxNk86N7oXw5b2#xIety~W>sgDxve$S#m>)m% z#2fwbY2A2+C;s8gFYv27$}V+B*{kk|j0bf`Wc=*?^CRO;y_0c#syia%S>4g|xAT{} zBQk%fJ0kO!x}(O`9W`Iw5t$x!M`Zfd9g(f8?uZPJx+5~2dvE{9{H0FJIDa+H-sa;W zJ@`pK-dY!*;lXn_@gIJE$u9oNUgPm#e*DlAZ}i8fb>kVH_=hvUz^@K7yVPNl*{cpS z9@Jry@uLotj5l?dWPGZ_B;#2fCRu!`!zA;UI!rQu?fc-3tHW%*I!rP>>M+UltHUHe z`(*X5WO&qJlKD#=CK-Npvt<5ioW0G*gL+PL@RNSLwJtuxgXeJKKm7cXUHp~3#^b^K z_@O7>=#Nk9#xp$e4`+UXU!R2R+V9GDlkfN2Y(jD&*|y=Qx5JnTK&Bjac9*&Z2hd(ZaB_}qK8N5=Esvpq6@?LFHg z^Vi<9Ju-joJ==}%J=@LSd$vcWXYbh_nf|?Jdt~eGJ=-J0v-fO|4CmgnJu>|6ePmbT z>}@_C(u1G$@^+_=En~`@kW1qS~s5IiGMir3;g;dWS2e( zWcKQlK*qzq<2*8c^hq#|H+>Sw_|zwXjAwlkp1+;H^hqG|mp%z({?aF*aeWe+uTKJ* z9(@wX^y`yAwyr)2WO(#RAj7Fo0vUdNEy(g=+#bon$=d+eyZczMW*e>Dx)hr@ozJJnP#@<}ZCa$^5mtzDMRSeLEZ1x3l^B zc9QAQx06i2zMW+2>f1?%N8e5|oceZ>`AeTwGJiGB-sa;WJ@`pK-dY!*;lXn_@gIJE z$u9oNUgPm#e*DlAZ}i8fb>kVH_=hvU!0#S+cDcu$z3y?7@!%de89(lElkw&rHyNMq zag*`v9ygi4+~X#{#Mg%(nZMlQZrnZY=DWvDrpG;QGX3sxldbC>HyIxHxXEz3$4%xh z_wLF3)i`^bkB9W&C;fP9U3`WI&*8*>_+R4d#TNd`UgPm#e*DlAZ}i8fb>kVH_=hvU zz^@NUcIiWsz50-l@t_Y089(}vkny(n0FR7MeMpSsSs#+;Z|5(4NXY!94+)vS^dV_n zACl(lLqeu!?*Sf}etk%cTUQ?vGCcZ_Jbyc!`jC+MOWznWe>KkD=Hnqf_(?zBS{I+; z!E-qAAAWwxF8<11*Zi)3f(%k4*pG zvpuqP_nz&M;n{n(M}~9n*&dm{^o_}`#@X9^JfsId>Bn2^;xjyW4k!M@&o9}Sw_|zwXjAwlk z$o!>G0{P|n^?^s`uf4aqaeWe+uTMgH^hqGouTKKmy80xL;n63745vN`Wcc;9Ad9cY z+1q?Pqz6Cg$6M>-Gdy?>C;r3FFMA*Lti@m1Ydjvzj~{yCjsEzwZal*i|8V9P`1MK1 zE`1WRSDyqj9`s2d<7fAq9vN@?BpAo1J_%(0(kJ2h+xbhM1oF%C>(d{Zzw}9HT%UyI z>ytpHN1p^T{rV)3t*cK086JHS$Z+bDK;|!fEy(=UID4CqhxFhl{dj9#e1-?l;lzLV z`DN$BXD$B9UgPm#e*DlAZ}i8fb>kVH_=hvU!0#S+cDcu$z3y?7@!%de89(lElkw&r zHyNMqag*`v9yeKh{eQcMPJVfQ{p?5PuRpMR>y5j|-F)}B$@I9#O{U*HZnAaV<0ix7 z9yb|I_qfUY<=#D+zZz$6^YM@#{G=amt&7j_;5nT54?n-SpKdMw%3kB~V1E426L0j# zr*-2Qp7@6|zre2#WOnHTnZ5czlJTGqBpE;YK$7vM4jO!qM;}Ns{rW(Xt*Z|t86JHg$#CieN#-woJIVajID4CqhxFhl z{dj9#e1-?l;lzLV`DN$%XD$B9UgPm#e*DlAZ}i8fb>kVH_=hvU!0#S+cDdi3z3y?7 z@!%de89(lElkv7XheyVzd)&tH>>l^?xAT{K++_Z8kDJV2?r}Hn9(VKI<0jMN9ygi( zkM3SP*}Cp=li^vN!z07#9=CD+a_^qZUyZZ3`FKbVe$tP(*2QOd@ElJ3ho4`vi@&nh zcs!UNKlH>K{qbqtc!nqb;mj}a>tmc<`WR=gKE`A`=wnRAk3Pm^yy;_1e)j+RDwFZ7 zk1<(%t?uiQU*hWnkIY}I`?_&`jGO-x>+_r*eT>QU>tjr|u71&Ec=RzQ!>NxknZNX% zCi7S0>}@_C(u1G$;wGd%GR zXMTZSpP%f~=O=sh`61&$pC2-Q^!Xv|K-sq1{>&7!Y@egNyfnQ(u?9$ggd-ZiE^OwHvWc=)Y z(<49oeEsB&<5OREGM@EyfBts<($}5LU;4U}`Ac8-#`Se?zP|2cdcJ%8@X7S+>rS?= zzV2jr^mQl0sjoYkzx3fJ^H<~SZ9X2-gP-){t#$Dk9z2H=|KaDC?BcKNH69P<#}7UF z;loCMd|Ef2;fa4Z^9%g$ac7r%+}Z0MHyID^ag*`m9yb|p?s1dx=^i&3&+c)P#g}{B zWd8c0PkNF0%RTPK-Q#Y)d)#Dt+~X$G?;bbVy6$n4;c<_f45xeCWd3sRp3Gm3v$y$p zNDqF}kGIyvXL#@&PW*?TU$Tq8ve$S#m>)m%#2fwbY2A2+C;s8gFYx<6GTF6r)Y-dp z)Fb0z=cq@<&(2YgjJKVm9vPoIM?Es0caC~w{@OX}kzbx)FEW4a9ChPgwEw5`aK8CF zM?Eqj_hfv!cTdK%d-r7ia_^q}uD>3czudcT+`aqeyLV5f$Gv+p{qEh9t?S-B86NlU z$^7NsJsEy|63F7KarQPJ59z^A`tjDf_zVx8!-@a!zw57OE&j@0t>@^+_=En~`@kW1qS~s5IiGMir3;g;dWS2e(*{e?i84vm- zkny8W0vT`mB#`l`PXZaw`XrF~OP>TXe|_bj`j*co^Orsejq8)pe0>tgkH6Mmf=s_Y z31sW)lR$KkD=Hnqf_(}icuXoqQXL#@&PW*?TU;g0Nf74?Z ze`T-ncrZVH=!rM_>61V!%QHOj4`+UX z-@W_nTAkk6>)w4lxOY!}_Ve!blkw)>JsF?w-IMX`-aVPW+`A_~@wI*eWd3sRzH#^N zoA2H|`H8RHyC>7XI=x4>u6y^!;c@T&`P=!+y?Zi$>61X_ug2Nid_1HFKk0vXdv{%Y zh6m5##DDntMLz*+@mKa5j|cPPhn{$&UmpX1Yu$K;C;s8gFYvp^on7v6liBMYH`%^* zkDH7i_qfS;bB~*hPxrXVcy^DQ%wO(tlljX%ZZdzZF6GAE<8Hot++=#(<0jMZ9yi&# zt4n!gc--TD{&qOs<0ixJ-aVPW8fS0w@sJ+;q#tjsi_h@jIh^hAMW5{so8$;$VeSXN|t8w-=9}nrlPx|rJ zy7&wap2La%@bgP{@mKa5j|cPPhn{$&KR&G+&+x=QocRTQ{U7!{`>pr(e|T4Z>`iWt zyPyC1+wXh&MY#Lk3a5_ z-TnNM&;AD<+1<~d_51$*M|St~8-MiYJhHpG+q*aZzF+gRZvHR&1wZv*rsv=J>mPY! z`ak8Te)5s6`-gwm-+N?u{>)eY-A9J=bNEI2e$d{ z#-_)e+4Q?h+q&-9hR5C8aJrKles^`V%Xs#h9}o1z5B>3G-S~tjp5cst`16a}l8^f( z-}~^Uw&a)pBQLVrl3)Kn{)uN?ZOJeD-7m7*l0W_b{HM>j+L9mp4KK3VlCS&lAAiQx zmi&u<;g7w{SC3G-S~tjp5cst`18x&mA!fE*Zz*jF11_V z@(W*NwOjw)AN#kTakX3j{@?oQM^?M_Er0E+9$D?y|MFe`)+4Lk`rKdom5;1;>%afz zfAf*mZhhHb{@^34wcEF)8~>{x_==nV6@TDgdt`b(`KNyCBh&wzzwx&`vUR`b3;xwd zhUfb}|6h4zIRA~W`@`0g=!qZtU&A9<^BERHGGswOiR`JbTTL2YTX%{&=%)e8LmYaK=CU`NcjgAKIVAoqbz8 z+Rw$QeO~<9|HZYqDBi_ac|d%XAH-LA!+80`{PGMvM? zL;JIF`?mS^b9(Ia^xOZfD=xw#UcxDk!Y{tE%Xs#h9}o1z5B>3G-S~tjp5cst`16a} zt>R1VR(@2wm4DT4<#)AP?FY46?Gv?I?H{#U?JKog?Kib{?L*`3PxITi^t7MpZ=YMY z{SQxZ0cY_7e{saF;!CYs<7(KNueL2cYTnYX7Or*G$c0DkTsYO#gWC&;8CbpYi^$ebYI|Iid59^G4?) z=Zelt&KsShjCZ~=zjGHooyX|!oMzq5Z}4=kgR}D<{G9{Y)%no#x^d6(=6k-U$8$gZ z&I7IMoDd%8hj2Pqgx`51yNqYA`SCzc{Lmk7){Rei;u+5Phd;llwaZ^>?HX5W*L<~h z=}~K!ezkV3tJW?&YVE?Q)-L>NBeTnR_L?6L^u!PS@n+rlgeRWijDPs^3%l}{+QP=w z95!DqVtUjlreE!1>#AuCk6OoYs(}o@+Q{rOp1tPB13mFWf4o^YKH-UHIO8Aw{KBrD zU+gVU;-UPBpYkf+%D4C|597J~jQ{dBzm(7Ut2}SK{BM5G1$ug3(BE^!x;A3@E z&m;JIPO+=!7keAWL-X;I9=xR=pRJ4M@Zdk3{1Sft$}Z#CYkoY?6F>CFn|0$8o_K~c z{^8Frv+JFnU+y}UC*5@_f4b{bUUk>0eCw`LdDva2^0T{6FV&cg@1- z4qEu#P0KFh*=v40&=WuO$D4KI6P|d6GydVvFKU6xhiZX}JGDT?qgtTiR4q{Ps}`uZ zRtr?Ts|6|#s0AuNsNE`W7%!igU!I|-{6l|v$-3n$c*wHsjZb*u8P52JKfk#9nZNdq z`o`V;Y`(jn>2dcn{qBC=y1Qc=9(O;(>F#Iv-PO%5CFn|0$8o_K~c{^8FrYQ^)HTJgreXf^ZAS1X<#wc_blE8e_hK zyNqYA`SCzc{Lmk7){Rei;u+5Phd;ltD}SktZ(PlM^VQO)M~!{@)!w(Rn*8vn)eol{ z{_v~q&o1NHYkoY?6F>CFn|0$8o_K~c{^8Fr>?$9!x46SY@ra+|6mP{ZK8tHS7w`Bl z5AaL*fxpTd#>*$>muKiH|IlAvvTpebp7I!+@uFc=Enm)@k4*SSvNl6iDx+DAO8HJ*F^E9*F=8QYa;*ZHId)-nrJ`h zHPJrNYoh(5*F^hDuZi}X-XQHmHW#{)g_Lw~$kH$LHsXE@^@{`|6i zap(DcW4&{uyH1@a-F51m>8?}fPj{UXXkVHJGZl|^SrxVjl1*Je0Rap=k?wxAL_kR-08hjJnFquoa((({OY|^T?(z%S+ZRU%^uzgR}ewe|e8xD=E8-XRrD3Ku`S8A8*!;Pk7=P&iIEvzp$%($ll@( z55*&Xic`E5zxXV!@m##)zdXP%CFn|0$8o_K~c z{^8Fr?8;y6b~WzKSM%KkOV6k6Zd&@?9cx{8%EIHWSvcK63%|Q**=0O?&5s9q;)nit zvu=FC6VGtQKm7THUFAde7I%0k9`RG0;;s0_XK{_^;vN6x0e&ez@K<@mc=^Qq@(exY zANtEn)-7MbQyzn}d&7QM@eF7D!=GRD`YRvm^_L&@`pdt1{pEMP{@M?E{k2c@`fLB__1C`A>#zN$ zH)H$Ic>B}*_ANc_XZqXc)@}d8Q(VAVyue=^v8(vf+puvx51X$SVtVvQOuycVt*fVE zc=TEfryh*q*PAiBjAyU;@jy@f&>wHsjZb*u8P52JKfml;bLT^MbvuW+tK0d+UER(t z-@7}`ooC$D?VRJTZs#9&bvqZitJ`_W-RjO!#yek`-?@vP&SUgU`*Ka^vnSH{V_6^tj`k{*QkAhi+YWqQmorU-O~E=?-=H-L1|pQ^RM@-`Q3Zh_JjAa?Gx{5+dtmlwy(U`ZNGWn z+deej{xrXROHccm{`R?b+yC$s7jPCY@E1qyD!#lgZQOg*=6k=I9`9Y#?|p3RdQTf3 z?{CBDy>9ru@69gb*=v40&=WuO$D4KI6P|d6GydVvFYbQ!J;mM6{OImy{&n{=zq|X{ zesK4*ed6wC`^VkS_LaMz?KgLI+lR*6pXL`|^t7MpFTSkX{)eZyfU|gkzc^x7@#U^- zkDBc!o3n z;mwHs z&0p}uGo0}ce|}+C{?bdiaXprsulI6#^kh!IUd^qmhjV!Jb`IzJ)(blPdO>HG@$5A} z9_Wc5`tz4{;}f2EhBN-*&oB02`Oy9>?(Ey*(S9yY?epT-{x7b@Me#0P$^+u4{2;!{ z8^+5g=9g#aDgV%4Ub1fa3ZC*9oaHz8%X{o9AKIUd+qccPpVMQXr{Df>U2zc}@e)pP z6n^oQUB&7QM@eF7D!=GPv?tN8!tq$i^eq4RdtNgpVomcsN^*pcI z53BQe)jnDM&#U&&>VjUiuU0Sgs{N)ne*4gP`_ugPEj{gL`rGH$ZU4hlT)=~?~N>0e#et-E@y!?QZB!@2sd!|#8EWS8;$Wq$smCx6kO zzpR_T;K^Tb<}dj37rXM;>fCO8^=~(Sb#bR>^>U|wb#%Ax>gx{A>h2Eb>hTW0{}qy5 z#`Bl?`HPWU^J-^u7I3AjhpY-4@{rGHMJckGW z;pCU_^H+8m&tCK6fu8uGKi;expYX&pobeBTe%W`uSNUt-#cq7x%WnR@qn)08UpxK# z?sn_$d)(pKce=y5?{|k^Z;>0;b{WrK=I1YZ@)!O2%ewgsp8N%8{(}F# z{_6R~-r^1q#Up--Q@j)iehEK+WtZ{nH9sEci68po&ARakPdvjJ z|M2IR-Q&3U+C7N#-CMcw-DkP^yXSIxcK_w{?_SKUyZbVSN3W`I>R}ary{)p#c;|WZ zJI~Y8d7l2x^VaP=4^QWLI6Ke7-+6w&Q{E~c`rm)Wo&Wt;Jo?{%#p(VR@XyZ`-H9`L{a$`AfmV|l}P`NaJ43_ax^`pZk!EnmS?9)q*|27h^vUFAdn>#%YE z1F`x3H)4ABKPXSX|E1Wv{>Nf?{O`qZ`k##9_rDsm%Xs#h9}o1z5B>3G-S~tjp5cst z`11?9I&ZMIxWhy7h@avVZ^bV@i)%a=@Axkd@JsoDzseiN%O~cS59ui%(qBHbZut?$9!w{bi)A3y2ATl(?Yx_Ax`{=>;H;peaHGM>HW#{)g_Lw~$kH$LHs zXE@^@{`|7%^2L|lR{2qHtNg3CResmos{Nq1Rr^G5tM-rHR_!ajt=eyTk+lzvw?EBq z-_p~5roVk|-Qo+L;sVa%1^(iQUB#DPUXAPV)qK6b(xWF>`t=HHT|LCYqqkT%^&AVo zUS!#2JbTTL2YTX%{&=%)e8LmYaK=CU`NeyH-bZ;qP@eSOp#155LV4ADhVrfV59ML+ zCCbmv}H{9`7r{={-jHz2C?#-Nd^&+GQj_SNh5)%M%#_M893^PYY9y8UT> z`<9;eGyUyz>$d;lDK6kFUf?f|*j0Qj?rwbXc=H#hr)Tkd`WM%??&AIMEDs#c<%h%X zfAM6O@$5A}9_Wc5`s2;I@d-~n!x{hZ=a=RA*TvWJ#n{P{ZnF0a1M@5{HZ+Yigb zuiGcf&#&7*%iFKpSIg(G+i(7tcl*$I`_ugPEj{gL`rGH$ZU4hlT)4F;ymj|HJv@8P9?m^~5C5LaXP5EpH9sEci68po&ARakPdvjJ z|M2IRfA3SjABnYhAtL!lQRwIQ5PTzg~a&%Xt1WKY!7a zzv$0j*3Dn=!oM<|7`m8;%i+!`og1kUpV#j z3%_1}@3HF#v)BB1peKIlk2mYaCp_^CXZ*vTU+ly3q5WCh*|)``{al>d=f$u6UtEie z;$6Iy2gFhNL41`rjF%71FCWrVKBT{VXx;K5Jmo_;%ZKoPEFXU0@}d3NxP9Av`#C-K zdHU`D))g1w5ij8sN8uM=*=0O?&5s9q;)nitvu=FC6VGtQKm7ScufP2DdFyT1xL$wF z*Xu7mdi|weufNvSQ!zYx{e@GnzwqnLm|e!R*Zg>(Cw}OUH|xeHJn;-?{KKDL*wyn( zZ^Op*JZ%2ztWJ*}iRsrnv32!S43A!m;nagM{CYEHm+|a1KOX3bANu3Xy7385Ji{6P z@aGqH_4|vxo%8X~`5!<1F2GyA7x3Bd2t4=u0{{K);Fo@n@K?W6jQ9J+{C?Na)9)Sn z`yFK6ejmZp?( zCw}OUH|xeHJn;-?{KKDLmUl0{RyTEiTs_tKcXd|h_tjtBepp@B?UU7O-Tqk}*X^s- zcinzl-Pi3yv45b$5qz^>~MWb$Vx)@#4$;;)|Z*i~i!vy2Tef#TT5#7yQN7>dfEnys{&vq_{n>gh8}E5- ze$R1wdcM=&bKkn12jJTi7Y_BVfZ_@`&}`KNz%`?v1u`47+P z{14~q{|~?ZY}sWzd(Dprdg6!vc(ZPN!V}MM#y|Y|WpybRU#sglKd#>6{JT1k^ZV*U zZa=JUQ8RJ>CIT4H(q?1UwqM1e9>QgS-1Ftr}%=i_=3OqVps9C zI-DC{ea_8a-OlM*JCFn|0$8o_K~c{^8FrJI|lLR#$)HtGB=TtHVD%tIt3EtJ}YI zSI>WVR_A{>SO0(bcQ4@VGM>HW#{)g_Lx29VZvKKNp5cst`11?9^4IP`-1zQC-2B~} zI6b>har$@9;?~{$i^H>f8HaQCH4gvoahzSo^OyPgi=O;NfBv#={(>ie!I{6{&tLXo z=Xv|HxU+AINBg-rwa<%R`@gsr7sb1HDG!LF@`Ly)Zx}BhnqNMor+i3%`Ov!MLwL%E zaF!3@FCVh2d}x0*Zr?WFeol{lo__nkb;U(^#7j8EQTWAIb{WrJ^W%Y@_@O`EtQ(*3 z#50`n4}X5q3%c|C`Uc#&as34DJh?stcg|e@fjfV$FTtHl*RSBttLtNM=h*c(xbv;v z-JN@lcOEvsb22@hpXu*hZQah>@N^D`v-3Ipo!i;fd47E!ZhZY8ZvOg0oSyZIIQ{D* zaqIrJ_3jSO`c53q^`kiadUt1+@y_$+cb=!G^E~~X=dIg$9-hwgaCV-Dzw`X|#pOf2 zpo=@bpo>Snpo>$zpo?F+8FCUs;KBT97NPqdzy5&Q7 z%7<{458*E#va5Wk_jTiXVmDu}?DXiNoqoNwTUXER@aV-IPCdHAuXlHL8P8txEq5WCh z*|)``{al>d=f$u6UtEie;$6Iy2gFhNL3~}_*m(KS{PH0^3G-S~tjp5cst z`18xYS6)6`AFzwN^#{9nT;H&Z)AbX(`2Dt@{h1$&>tFeqmk-yM?DFCIm0dnuAG6Dc z#)~iWi?8)DyL?E0@nzlO3!dT&&f*LH;)`9y*ZQ{I`1-ls{PlS|J?sB=`qvlk)?L52 z!?Qkehjabq4*&Yjon6L@FY}8pdWtXli!bXIU+@%Pa28+i7hj&soew>)JBN6VcRula z@7&_K-+9J)pmUCMLgydnht5UL6`hxyH@5Gep4G-XUzy*zi=NJ7^mk6PZs#|6I@iJ3 zc@O^1f$Zvh=y~0^=Xmoy-_zr{pMK|o)^$z@kMlz~oh!ocypdhTv)BB1peKIlk2mYa zCp_^CXZ*vTUv>}i{Iz?0H@^FQH-Gp3PS5TGp8nkvymfbf@bK(j;o;nU!^6LOh-a7a z>@`0g=!qZtkGHKGpYX&pobeBTeqmSs+P%vg-+j!Rzk8aeXZJTx|L%3(y1VarcyKz^B4T@^;gd?_Le8{Q2xYEd6mD)xA-g% z&7QM@eF7D!=GQ+)%z&+mM8I0{=`pt z6>sHRe3pmtTzV*Lcq_^Lu{L)A^A8o?q7O`2|nUFF1RC!Qbe|Ka49@bg!88P8tx<(>XBw&WG7$JbTTL z2YTX%{&=%)e8LmYaK=CU`GsBi%lWEt=dR{EkEO>sE&a}Kt?OJD9_PJqItPZ|`7pbT zXRrD3Ku`S8A8*!;Pk7=P&iIEvzp$(GA$xnS;i2apetHh#t>+^?dv4;n=PCYs&hkso zU;gSGWxVr-`JFfD>AXRI=MC$2-hij`2ArKY;P1S_uFf0mZ5$8H$4`3jmVSJ;E}p}K z|8Vk4`1vcljAyU;@jy@f&>wHsjZb*u8P52JKfibnkiWbiXxw{)=6j!zo}b=(hV*;? z(7N7Bgva}eaC(mse(yK3%Xs#h9}o1z5B>3G-S~tjp5cst`11?9@|X7mjeBpM? zL-sa~hvwraJ$Oq$K3f;h;lY16`6c}Pm0iZO*Zg>(Cw}OUH|xeHJn;-?{KKDLwl6Lp zdY_XYz30il-v8ux?}geA-WRn`yhm#Pc)!%X@;<8l=6zKA(0KdP{Prz9?PvPi=hkii z!&6+qS-iks9I>nT@;;|=?|GW<{ZD$l7fQePMXl>SQh2;y3a9r@;rBi&yNqYA`SCzc z{Lmk7){Rei;u+5Phd;k~572qu`+?4l-WznD^gf|;ruPh;KfQnGT&mC z(fQWN{`o>-%qU?YnUC?t5{0z<1>GgYV1b4ddk#^UE{zlz-?iFIl&I1y6Yl&hi`l zCFn|0$8 zo_K~c{^8Fr?CQM1-r^1q#Up--Q@jH%&a zZoK_ze*2c5_A~wMbL+PM;VCZQEMDL*j@VUv`JUdm@9fR@{XIRt%ctM>`quRwKRmwg zhtqfe@T&*NF5}s2emu|kDBc!o3n;m1Z@m0(e$NGZdS1}qbHutmU*PGv182`8_UGF8r<9$Uqy~hZ@_Z!(|JbTTL2YTX%{&=%)e8LmYaK=CU z`9)o2@ul7}KYqhc{?7BS`po>UZnOQMp0j$d;lDK6kFUf?f|*j0R~w`^P;X7kl&rbpdo`qgu`t~$@~sQ(P7y3p{e7tJo? z*=v40&=WuO$D4KI6P|d6v-pBPzieMze5q&7kLsNBulncwt}eR$@X?R|(Crg-)a{=y z{F)ElzEXGHep8R#J~ZC`G{1dIPy3nv_PKT2|L_zSa27A{7f0+WzSJ`}uFkpn>Yvl| zy#Cy;kNWCxs=E%qdhF~np1tN5U-ZNe{l%Ac;}f2EhBN-*&oAx;ln*~| z_XQevkD&SP7o^9%gY>(P(7Ns^gvb4baJttJe)k>Du8n7}`SCzc{Lmk7*3Dn=#50`n z4}X4PSN?KepmFyIn(ux=dfYomzxxQS>z+b*++PT%dkx`t-yyq`?)x^&x>FCzql3`#k+VZ4~V1kgZL_M7%!igU!I|- z{6l|v$-3n$c*UWCqe!rOC?;3jgy+eP$gRI-{BY67V1ZTge;O}=9fA#x| zy^Z6c`S?i>-qMfH*2Qyp@E=b83O|3n$F3jDUi0IDp7^0Z-mDv+@WeBm@ehA~+3(8N z#h3e}`O!Vo{OkT{es?dm{ouZ8`@}ug_K*9m?JM_Q+i&i}whxWBKh1C7($jvXzkP1q z_CGwu1)RkT{KXNwiZAy`8+XsN`R<>l$Gz0_yRX{1?y-i){nl{0_ZoipVYAD4_L?6L z^u!PS@n+rlgeRWijDPs^i@pb)H}pg3xu#D-&pZ7SdJgKV(DPBhg`S)GF!VgtpP}ch zehxi<^>gUCY`o{S`8~(!>G@87&wcB59)PEF0-T*6;O|_)uFf0!AvCT}Li6=cNRPe> z>DO7$6lJ?*$W8);l0lIH7Ak{*3a(yyOM>*{k79{o?ksV_?S^-IYvN^yE{fM&5c=nnf5A?(j{qbhq_=G2(;f#Oy^UL!5`D=Od#+N^D{_^VS zS-w5}%fq+s^7G+Y-aeem=Z9avuk13Oz2@gHdh!?j`OCWb3!eN1Xa0i!WB&TU`D@R$ z8{hNp=I=RpdiH!g{d;cSx_h1;o;_y|=bpcZU%#*HGM>N8&tLT9FZ%PBb@LZI`3uhc z1^>tV^&{7x&HgOz?AzkeelAY!^WxY3FRsN!@h)D<1LCXvAil~Q#>*$>muKiH|IlAv zvTpebp7I!+%Nxeahvt_L=_w!5Up};M`4FD+A)Mty z_{)dv>iMOgYUBE>HedhM^ytf)e*IcoS0C5#=kDBc!o3n;mZ=@n{g$)Kc=nnf z5A?(j{qbhq_=G2(;f#Oy^9#H3mwv^K>toz}{f*P3?{WI|LvCGtlEb5aaya!>4!?fO z*=0O?&5s9q;)nitvu=FC6VGtQKm7T{J}e*FpT(VhTRhs&#i@N>{M!G;wYVtW#Y=fW z9F-r$S9!yD`NaJ43_ax^`pZk!EnmS?9)q*|27h^vUFAdjvvK>j`Sx>q?DO>7|E()7 z!XsY7DUQM~zOu`B_L?6L^u!PS@n+rlgeRWijDPs^i@y5hL;d#iqdxrkSAYKe{yAU# z^|v4N^KYN%^WXl_|G$0Z{{pn%{J((qq4D;o`R!YJ+Rya2&#l}3ho`uJvv`5OIAT}v zrQd$z`tUbjfBy9RrQiR1PXA}T|7&kueg4Cv|9?3BUx4uYe*xKLJbTTL2YTX%{&=%) z@dZyj!x{hZ=NHfA-bZ;}cMkC!?|kC<-nqqdzw?aqK<6Cigw8+C51osgD>^SZZ*-0_ z-ucS>&Rz6$9;3f=nsqzB!PB`8&dz)AcMfD%=R?oy#y!WI@A;k{&;9f}545gxLU^1X z!s%QQe&>zsGM>HW#{)g_Lw~$kH$LHsXE@^@{`|7vU*|9X-=}f^_ow;(A5ePypP=;n z|3R(m{|bf2{~HRY|3egh|DPzkjAyU;@jy@f&>wHsjZb*u8P52JKfkame|>QO-=}f^ z_ow;(A5ePypP=;n|3R(m{|bf2{~HRY|3egh|DPzkjAyU;@jy@f&>wHsjZb*u8P52J zKfkc6=NEg+lXxh9;-|cdxAHAM%fomsKjXi=%`fG1{wmKKFaMk0bAg_o7xecWv2M>7 zczW)@+4Bhgo>T1V`NiJG@z8wyqz7;5$7k!}IXw6eC%=TBzp~4C_L?6L^u!PS@n+rl zgeRWijDPs^%j$^U$zQ9(d8hH!=e*PW)$P2Kp4Icblm6BDywkd?|9K}os|$K3oU0dl zC;a}uUUnJJUi0IDp7^0Z-mDv+@WeBm@ehA~VORcI-PDb*p6ceW&g%56{_6CvF6-7^ zz1HDb9oOMp-Phsw|MjxVc=nnf5A?(j{qbhq_=G2(;f#Oy^9#E^?w5S;bElZS#T_1s zNBk70cq@MKSzP0}c*lQvfM3cF{8ipCUOq9uJVQ_UhyL=Cb<0=ql*iyKzrkPLV^{f* zy^Z6c`S?i>-qMfH*2Qyp@E=Zo2|s^jm+|a1KOX3bANu3Xy7385Ji{6P@aLD+eO-L5 zZtDEFdaCp9>a5Q1tG~Mau)3_& zExzC>zThmr;4i+|ReY_^?Z#LCcJo&kcY0PYcluXHck8ac?(nSc?r^Ri@9?iq@9Z*O ze3@T-(NlcUUwm1&_=2bSg0uL7zxdj{(RVt}@80D*og066|0lQeZhZH{a>} zxqF@ObS~X}&v!bn?jGnnonv=D^qtPP{-1B>UgMpI&F`E{Pv>X)JI`CU^E^DA!{O|F z4u9u%c6FZLJ=q)I{n?wpd$p%$_ia!A?&03LyPtb_c5nA^?mq9~_y2se%Xs#h9}o1z z5B>3G-S~tjp5cst`18xwx%gUL$N6#f9_QcHft=r0A9DL)btAV=R!?&KXLTmGuU3C@ z`_2E$F20NxU*;EI^b}w87hl#bzThdo;4Hr2FTU7Se60@W##f(n^H;ZXdREVK`ain= zXWhE1|2aIX3p$*u7drg@Uv_pGFTTt#zUV2w=r6vkTYSM&e8E|K!C!o>?(5=fbyMfZ z)l;2+zhnRZJ-@I1>h{CxvTmQOUhDSH>bP!St-kB_oBv1OJ~Uo@nO}U-Q+&~1d|9{n zf~WX`v-pC)_+nS_wK}&OU;W$7UtQekS-srpUme}8yZXArv%0&(xjMbW@Bh(fm+|7u z{NjtA;*0*`%euuEJn;-?@dbbJwR7+JYjyQEzIywczdHQWv--XLbIE zbM^m+fA<2;F5~&j{QN~v{-QsBSvP;dlfU51U-0KIcIB_#gSheCkGT1}H*tD)pW^iI zp2e-Z`xl32_c9LW?rR+W-QzgBjOQ=&^A|n&i~js&-TVbl{(>`q!JohE!_M>eXK`oW z7LWFGacZ9zzxID|EiQ_8@lqZTN970cRo*aOJ~Y34NKg5Y{_>J_%ZKok58*5y!e2gQ zSNYKXY}~$WzWtmY`#k;jf9r~i@Q9aiilgw0uk13Oz2?UQJ@G?-yjeFs;fZHB;~)O~ zvO4pNuhnUvA6LJ9{#{-7`F-`?w;xsqe*0wg;kSQQH-7tS_2jqTR%d?u(0K7>e(^<5 z@kM{}W!>Tnp5hD6;tT%bi(SRn>gsQN_4YS^b@-=e_4%iNb^EvO>iG}P>iiGq>i-Y_ z?ggA(#)~iWi!XYLFZzow>lR<|6kl)_U+@=Sp3D9I^1SYx?>XN2-}AlS1)lr;UT_}h zcZ737zb~90`rYAN(eDxGjee&X@Ar%O{jQ;>-#hg8JIK2IK7yy;O>p*m3jTg)v8&%- zp4W|gjyK=)Jw2ZL>31GzUFU@GI6s8bxgz||8`)(%d(Dprdg6!vc(ZPN!V}MM#y|Y| zWpRA@aQ9>{?sk9n;&JzCFHU#g_TqQ@`0g=!qZt`Z=*eI7=P&E#FL?47ocRm>{Kc;PweQY1zVFdDf8VK3 z&%R%u{(aZJb@#pd@a#MI;oSG}!@uw5XP5E(Wq$smCx6kOzpR_T;K^Tb<}dj3mwnjz z(Ecp$?AzkeelAY!^WxY3FRsN!@h)D<1LCOsAim0n#>9axe({xE#Y~EWY3`zSvcKtXYmDp@#VSP`Ox#abBO17 z=M&HO&Mlt%ooAc}I_EeibpCOE=v?Gn(Rs;vqjQw;&R6Dl?xLsj82z2otlRkwp3Ze} zcHV=(b0E7qA9`Ll?m6Ck&-e6r?x){*pmm)S!sGl9PUnj7J8xu{@$5A}9_Wc5`s2;I z@d-~n!x{hZ=ac-b^>gKNx)#+J(s?)!|Rk!Z?SskABxjLNde|7lR7whaY zp1tPB13mFWf4o^YKH-UHIO8Aw{KBsMwLV}szW!i0e|^JF&-#g-{`DEVb=QCF@T@P{ z;atD6!@oXeXP5E(Wq$smCx6kOzpR_T;K^Tb<}di)>#v?)>@82?q5O%T@+#iSxA-g% z&7QM@eF7D!=GPf*PRb{58}=tyB~4q zlii!RbIa~i+<9jAEbg4M`xkfq*}aTA7wx{rotJix!Pi^(&cYn?OukyU{@}c?VLwd@G^p_8=b!%7?cchq=RZ8F^FN&Kd4=Eouk12jJ~Y34NKg5Y{_>%9%ZKok z58*5y!e2hzd+axzH$M19U-YK&)qA{Y{^~&9q-XUZZ_>ZIkvFZodXhVDtj^@l8>>IL z^Tz5@?z~|Z^yDx4^Otq=7d-h3&in=c$NcqyH~DLII5)ofoSVP8ozt^=p3}cN zpIdkJKZj>^L5FkoLWh5KL}!=r{AGUrq9=dRA8*!;Pk7=P&iIEvzwlSjFZPxv@lgK6 zPk9w@)iehEK+WtZ{nH9sEci68po&ARakPdvjJ|M2IR)h(aD zR`+}3s|UXMs}nvws~5zKk|v+clcMge0CYnUi0IDp7^0Z-mDv+ z@WeBm@ehA~VORcIo%W5de*5OHuKV@&kXB z=Z%*S%`YF)Q$D1>d}!VBAw1QL*vDl`NbDK#TWg>mvxITc#1DLi!b<#FLo7QtJA*m)oxCW{5xl^KL5_2pYi^$y>sd6`R}~CI{!PzuKxedx4Rc`=U(HT z=gsdtPfzE0`a92CxAQzao#)}~JP&{8d3JT4-#v&M-~EW2zk3s>=X1XJ>remgS=_q2 ze{pzrFXM3TzQ*C-J&v=>c;|WZJI~Y8d7l2x^VaP=4^QWLI6Ke7-+BHgzxDUL^P}JN z`qj_-s_%cBygc&OyYk!bm7AmQnSE=HerWbHdEZ0dw$I7>r`i8xebvMTS-&;$Le_^( z9Fg^B6JKO~+r%ANKR3_u#_ikY+qYzT>{~MZ_AS}E_AMD6`<4u+eM^Slz9qBExr?kH zTI2epHDCX<^ysUWe*M;3S0A?U=+72TecQsXpIder&tCK6fu8uGKi;expYX&pobeBT zez9*o7uaP#doGaebI%2`{qMOz78jliWbxv;Ko&=y3uN)-x$w+c+<7jL#iQp! z$YW&BBl(T&IVJCrJ-_5bvgevSN%p++eY0_Srup&=nI3tDOusxswyr!whDV+u!zs^@ z;g@H~?DE}~?0M0+=ScHCU((~blYY;m*7ckUkLOo7J=enTd6!+rv)BB1peKIlk2mYa zCp_^CXZ*vTU!1%0m-ATT&S}keeoK#YUHYB(TGu%+JkE#VbZ!j4^JI1z&tCK6fu8uG zKi;expYX&pobeBTeqmSsavp2kIj#B5Z|QNaOTY78>pBO9$N4av&W+)Bp3E-e*=v40 z&=WuO$D4KI6P|d6GydVvFZN;i(Ecp$?AzkeelAY!^WxY3FRsN!@h-l~1LCXvAil~Q z#>*$>muKiH|IlAvvTpebp7I!+9ax ze({xE#w*TQNF5oO);4hBYReX7$(75*u&G-Hx zJ>E;C-}{Qz^&TTU-fx7{dynvYACg_hv)BB1peKIlk2mYaCp_^CXZ*vTUp$vPA9`MQ z4)GlCeB$}uxy5t8^UP-ugI9^X^K={rmK zeSgU=7?z=|weeXz*?;z>-eWZ1LHwlmL zDdF^;CH%g>WS8;mH9sEci68po&ARakPdvjJ|M2G*cJ=&XZ+Q|Ae|Ka49@bg!88P8txE-*X%HowxbE|EA}c?z?dMeJ^fZ-;u-P`*JvacMiYr(b;7@d(Dprdg6!v zc(ZPN!V}MM#y|Y|#XY$4q5E;g-4Fk=U;KP$=STPHic|OOieLBdifi}sig)+*$^-84 zl^@*iD{mMtpO{~sp{M*qe|gEe)iehEK+WtZ{nH9sEci68po&ARakPdvjJ z|M2G*bh!CxZe4ZP;ZctrPIcPhSHGQI#0 zI{EOZpAVCFn|0$8o_K~c{^8Fr+ZT79SO46(QC)QBN%hj5 zGu2Ud{#0Mxxm4YC=T-IConzH$cfM7>-MQCz=V9|ZC)3mUnf^OhZ{5z@@N^D`v-3Ip zo!i;fd0zc<ZsGNzPfeQU57_Kb~x2(hhP16b{WrJ^W%Y@_@O`EtQ(*3 z#50`n4}X4f&$N8#{%LXNUTX2^zG`vm9&7RIers{<-fQvhK5TiwJ=yYu`?KW@kDBc!o3n;m?$9!w{bi)A3y2ATl(?Yx_Ax` z{=>;H;peaHGM>HW#{)g_Lw~$kH$LHsXE@^@{`|7{*yk_(6B^f7q51kPq(>iy^y|;i zy81SRM?Z&f>hlnO{U5T+c=nnf5A?(j{qbhq_=G2(;f#Oy^9#H3m;MQj>#NXw{T9-r z4@3I(XJ}o08^WWXLpb$$2*3Uh*=0O?&5s9q;)nitvu=FC6VGtQKm7THUFAde7I%0k z9`RG0;;s0_XK{_^;vN6x0e&ez@K<@mc=^Qq@(exYANtEn)-7MbQyzn}{04t{k6q&7QM@eF7D!=GRDwJ0Cz zcab0U!N|Y*W8`;zGujXOX|zxD*=YahztO(Zm!tirUq}1Uc>B}*_ANc_XZqXc)@}d8 zQ(VAVyue=^v8(vf@1k*iFq*GFMtbzkNWXp>t*g&Qc=X>0r@kEF*RLbHjAyU;@jy@f z&>wHsjZb*u8P52JKfml;bLT_-6FP_JtI+vGzlF{%`Y?2!(VwAnj=l|@fAn+cT%^xK z=Oz6gI!77rd}V&;E_ynT(cd}Ex}D$P>0AeA=RNp42ePa4q5cVt>#NXw{T9-r4@3Gt z`tcvSb@gos&li5phYqJc58>DUA-jxculeynPyEmyZ`O@Zc;Xq(_=i8gcrRLfd0(0z zy+_Tz-mm6&?_Jvu-p962yr*sdcz@fz@?N+7=6!Gb(0KdP{Prz9?PvPi=hkii!&6+q zS-iks9I>nT^1ifj?@^oY{c3u=cTKgz5S2@BbC2Uq8dv)#org z`X7c_5e<+2qT$qcH2nIJW|#5oH9sEci68po&ARyuo_K~c{^8Fr?8;yIc{Z-kXY=*{ zOpm^x>DMo`b@dSqkN%?JeBb(xhF?F@>@uFc=Enm)@k4*SSvNl6iDx+DAO8GeAC?d8 z&*IL$EgtRX;?zDbe(nF_T3i(G;-x$wj>-?>tGr>nd}4lihMw{d{pBU=mapI`kHJ}f zgTK7TuJWP%*|>e%eET^)_Idj4|JD^3;Sn$46i49~U)g0md(Dprdg6!vc(ZPN!V}MM z#y|Y|W#`^k#nex|>DZr%1jJjDf^#S8q!5xa`753V0|kDBc!o3n;mK0!0yJPhXulhaW|MB%Z#dyD8%b}ljtDCy<)l=R4)mfdM)nA?d z)n(nftJgX_tK&MHtM5Ae{(nby8P8wl=P!El7ybFmy7>#9`~_$Jf`Z=*eI7=P&E#FL?47ocRm> z_xh{n7kkT-cqo73r@V@{@-05g!+0(~)iehEK+WtZ{nH9sEci68po&ARak zPdvjJ|M2IReb;-HzxG}1#`nGK=I=Y&>Dl+S)4%U-x9+~j9iDxsJDmG|cliDPsq8YI zz2?UQJ@G?-yjeFs;fZHB;~)O~!mj+a@0d5f@0&M&-#t&yzK5RveJ8zj_x<$n?7QmW z-1pYQzwfYTm+|~%e*U5-f6<@6ted~!$zO2hFZkc5c;IHzA@$#Yh|3{J*f`%Xsl+e(^<5@kM{}W!>Tnp5hD6;tT%b zi(SRn?ycPT?z7zd-E%oTyZ>_fcQ5AF-F=zEvwJj$^CO@5eTRSdZq6>_#h3ZT7d^!n z{l%Aci!XSJFF1=Y_=~R}`lJuvd4BgG?%cTh5qF;4y@@+#?moqxKX=dK&ZWD5ap%?D z%eZsw?rYrn*8iXC+-tn^y!oBy>FGRAf9HAYcAkf)^E{lL=i%?%&aTe$ySH-VyU%j- zchBYY?EcH?-@TYyclTuu&+gG2&fTv${Qmz`b{X$HZ+_=_dOFY3-+A7;o#)}{JP&8* zdH6fe?{~^uu|DU(G_J4becmL0~JmCNQmLL58-|~j> z@`?H78G6b;^p}^cTfTy)JO*d^4gT^TyUK_De{SRcuWs}GzuolsKfLMp|9M;2|LqNr z|K}S{|K~US{{L@w8P8txnLi{QQ+&#b~hEo?&n1m4FL^_}JN@%`oU^j+ri_r2!& zrM&*CpAO=rkND}P-Sm`CI?FTt<)1I^19U&i{ejj=_YGP<-A`y;b)TX2*8PXpVfQ6k zpWUx$-F6?N_1yi9)_LV!ztr#gB~I5b@wzDjLeEs?Zd;M~MpmO&O zs_%Y6aolGpzWWcg>%K(!xL;A8?qig{`y2I3dHq#C9mGi=@zYJa=_#LdmS_6QKVN1X z-s}41JhXgtPFnstKP}&#tJZjM-df|tIc$v|=d(4goZHrTbDrDPIK0>RRKIa6PUBhp z#<_MI|MF>G$g}w(|K^c?HNTvPR=IQ1s_*=?;y72W_|99aUFWcskMr5e)46Ts?>x8q zrM&*CpAO=rkND}P-Sm`CI?FTt<)1IJ&fjZ(%{qB6A7}l%m%p>F-plt{Z|^l8W*xrQ zIGOeNUgKxh?R$-@S)Mvj^=|9Wb#UX%^>O3Rb#vRD>*?k**V)Z;uD_fAT$i_B%ImNC=^#$}h@WoSO;7ox zvpmyZ{`vB{r+?SO`Srdx|H|_!|F-9R`6JbT&ojU0k>Y&lhu`%`@!$LFA9$p8-~Gam zezbgE^o1Y$XnB6+_kR4N<^P^%e!`>qr98jX&o6QEOZ@!OZhpxpzvP);^3SiI{N(R` zIKQU+?UhgcC#yeko-EG9f3o<~?vu4U`P?m^$@6Y`PX2exfBJRzs$X~OulngAPWp(S zZrV*x`J}Tv(_jAiVjQ*}8lTNOwtOG`e1&wZYXa( zQNMLYoYo)lTbH!kdL^IMF?qJW$-i|^zgiEC&&rM4>Ko6+G0ux`{MW8|Q9kBNd74M% zZ+_J;<@HznbPy+f#7{Tvrl)+;S)S=H|9qL}h;H)hxv%|;H|Zpwe2Bf6uRN zrrq?EPddvp{pFu8`ql3*{cWF5hxY&U>30F$`n^EUen-%`-xu`ncL!hkJ;JYkrzr3D zi~9Yp5vSif;`cj9yZt_rPrsYw+3zX&_d83!`u(N9mD8d6^eGPAicinlrE~evzdZR; z{`{(6%ImNC=^#$}h@WoSO;7oxvpmyZ{`oTN?#{1yZfbp;=c(4;dCqEmpXaZ3Jj`=h zJ5J_#tsOt}9M_JkdA@7M+dTKR<4}3?Oa11TIL$Bdn_t>(e#xi#CC}!U{F`6;)%=?0 z+_rq4f7|-=T-?T)=jAs3JV&?f&hvGf&pdaxdCv2AoBuqgxBXJy{8GR9B~J58{N|T- zn_u#2e#x`>CI9BvJZFB>eq)}~zUjL5+Bx^E>)kxpebaStp7*}#`Z&*l-*nxa=fiKh zp3ZaQH(h7vdGedCzs_gtx~#nGwfbGh#p(Jke%F2NwjYpB`viHme~^Fs3jJ!oG0)X+ z`8;pG_2)VKjWf^ZZ~S>~f7_ks`8S_=&VTcq=l?f<=d;x><@HznbPy+f#7{Tvrl)+; zS)S=H|9qL}Qg(jLa~N(@lkE7J=S+57&GRQa-sZWK z9f!)BU+Oo%#A$ws-~7^U^GiO>FL^e<aF`6Zv`mpq$a@^604zIXka=jyk7p10rn^Bn%hndkF2 z{yew8?auT3o6kJwzj@B{|C|537qI$%~RvN`D^?)ug#0*yZO>OU>>zTm|yMZmA4+M-+Cxc z>!J9qhuUpDluzrSJX;Ut-+HKDt%t^E<;HFGjpyPR=fyYvYuCIeAM>R=&7<-+zv`Fr z`m26Ah?73zr<-=uQ$Fb|&-9mnzRbA?yPuzP19smy=Lzh7a?Tmpede4$u=~$Bmtgm$ zb6&yjSLYmq-N(-P2D`tVa}RdktGxZN`t6g&Y5y#K`)cjB-rmw)?q{c1ly z=R9orod2-(=Uj-5Gv`HY{5eNr+x_aFf9mEl=T2;%a~{R!Kj&0zzm&J1SHJzdIPK@f zZ$Gcy_Ve;-KQGVr^YU*$KjUK8!+B43=iR(NyYq40tKE4z@7wPDo%e8eUeEivJKyKM z-CYOfecoLk<~`qCH-FcsS@6XSB)_Z?`-oM`a^YdQz-k(?AdZ>Qup*XFF;|3B}!@81RH{rAmh-izNn z=Y9Fjf8L|tekso{_47-d{1QLEw3}b@$uD{4m;Ccfzw&F&4cPKIPhjiMIRhJK&L7zL zb1uQQJLeT_K68%2<~ipZZ2oiZ!S+jeeyN{d;^de3`K8_bl23lgGr#1YU&dkgH;m8b zopIZIG@hHM#(DGC_-|gD7tMF`rFFnOYJD)jx(}ed^-%rRLvdOU#cw^-ZtJ0ZS`X#f zdMN+aL;Y$!G(IagZmVxR7sog+zVTnX=0*9KFXd?-mB0B_zm(Ts_0vI|^btSZw40vt zNoRSczx?xM{$9E3;hY1u^KQ-u+xa->hV49^^Tc-kzUg;7*1VN zw(H@XW47y|^5&QN&96DfY}Z5an_t>(e#xi#CC}!U{F`6;)%==s+qQhpbKClJ&fCVB z^WQf9oC~+@&Uta0&zvK-dCvKAoBy0UxBXJy{8GR9B~J58{N|T-n_u#2e#x`>CI9A^ z>vH=;*X#BnuH)@bT;JQbxbC-~u^(ukW1rCe$Nr&xk$pw`CHsvT_vg%N&jintMB?=9M}Eg+Yi*PeM0%zKa{6^Mfuxr z)Gy`rSN(JlCw;_EH|?gUe9~E-=`a6$nfDOauX&Ge%jf;Rtv~PmZJc=@aO2N=g4^!A zKe+kKdxe|lyl=Sq&wGg5FXi=D{d5o~eZ*hgrrq?EPddvp{pFu8`jubv-sP6h`pZ7Yq-Fe@0^O^TRH_v%Lbn~D0Mz>$e^Gp5w5+}dJ&oAxfmwfU|p7|yJ zYrndF>2K>K9a=x>)4Iy9)?0eE4%4~ynf|TYd}%%BSL?j;)_?W8E{N0hLj0~H+U@!x zpRPOd?0O{su2cN#`lY{>)1mtGDGuF=PtV$=bNSG}Jo!@o{HkBd>#zFhAWr&-pKjVs zPx+*?JkwwP`J!Ll@73SdNjkKC(x-KmZmqZUY#pX^>ofgZxB1d~&adu^D)0KGe%CK? z+8>JF^-H^5zvR>POP*c78TK7EQqx8l>YcIjL`^e<1ols~`fm-70n zemaPgKH{gFcGFWn=`7Fmmw&#vFWUTazce4+N6laNSM%L{*T#eUv5gb=X&XQ8-!`t? z*KNGH-`hA;-uP6%aVt*aS^UPib{qflX)`6B=3k$yG5+%K)%ebnl^zgiskU5oF2 zZ0)*FTR!gJmZ$r=6b~zpC86tNQk1 z#j#H-zWrP6+Siqj{a$(62bRD6Vf|8Gf7MS1aneWpbklBn$|s%Wnf~(67yZgF`>V?B zyQ*(LRvi1Z;@iK~u6#i7T~F!Xb(Sw(fBDruN_qPY_1kZV(|$wz_8Z!5zagLY z8}e+wA^-Lp`qh3ze=Da$_32X_x)qcLUBGg_Zf=s{zL7$FHt`3SCpsw80GK&M*UJ=f7MS1 zaneWpbklBn$|s%Wnf~(67yZgF_XjF>-=O;LCltqhhT^;bP`mC+l#lxr<>@{~`MbYS zzm(Ts_0vI|^btSZw40vtNoRSczx?w>zgiFVw|Pg0<|BQYr*v!n(zAI@=jJ>8TL<{k z`oOQ&4dtyT>bK5_)A}QR>yma`ujJD@CePM4`M2)rSL>nvR!)cN)2BFeD?UAIm(Jxw z|MKKZ`SYuODX+ikr-L}@BYwJRH$CN(&hkuu`RB`wi(L=h&&fykdGgo&pL};;sPW)_ zQRBpYq{ff?ON}e{of>cMM>P(WH$K&G+=|n97Qb<>-NwIsniukHzR16Mq+iW1_j4+D zpQrln{}ji4q2jw=RJ-mYm5=*N<>|gt`MV!gzm(Ts_0vI|^btSZw40vtNoRSczx?yX zeSr4!?hmwYbl;%;r27f&Gu>xs|LOii`%?EM+ON7_(LUCFjP|$gZ?x}K-hNp9_Q~S3 ze-^)ewRYQY%cp&~JlmhkzkR!YwV!u?pmO&Os_%Y6aolGpzWWcg>%K(!xL;A8?qig{ z`y2I3dHq#C9mGi=@zYJa=_#LdmS_6QKVSSEw)N28XPbBaZrgnH_uS^Gzwoj5w`7;t$X^_dZ@pZ)1mtGDGuF=PtV$=bNSG}Jo!@o{HkBd>#zFhAWr&-pKjVs zPx+*?JkwwP`Qq>9%`bmX&qse}&tHFk&v$>9Z#?*WedEO6@f$z>zTdd=cmKwl=K*#c zPI==~{l=|0jc4&2=h|)j%cprE&*qE#n@9T9{POqo%Ke?a`u_f29DkQDzQ5PkuD|1# zkH7Dir@#A`zvlt!m-70nemaPgKH{gFcGFWn=`7Fmmw&#v5770?{ejj=_YGP<-A`y; zb)TX2*8PXpVfQ6kpWUx$-F6?N_1yi9)_LWv|LS*L5U1;f_+3Y|+x100U3cW!^+^6* zr}V4qm-_>iyKhi^_Y;caK11={f2dveCCbPBit=@wLD8>h;(2nfdOy&BlZ0IU6UQ^KATh{?3i}wOr51%{l3smksg6ey}pg7(;D8Ba*YS()T<>UQ@^7LLq`Fr1C z`!(hDSN(JlCw;_EH|^$^e9~E-=`a6$(XagSzCh*PBdEUj3yR~tgW`K1p?1BeP(I#Y zC{OP-l)v{K>X-8RtA09&lRo07n|9MvKItsa^p}6W7>BKg#%J@+xNSZf&&^Zgy!mVV zH?Pf$=DYdQI$$2PKA2yv8_HWx)Nh>;r}ant)+Oz>Udg9*OrEW8@^9VKuhv83vvT9M z`o?o{jPv3f|Fvsgl#lsRp5{^cn_u-ydHq#C9mGi=@zYJa=_#LdmS_6QKVQ6GnP1*d ztlWEx)%QMQalGePeD6QjuJ-PdZ`yD~&eqYeP-yMAE_XxlGoua(o zFY5QZMx1`{h~MuZ?e_afKK*WzXTPW9-|sAb_4`YIE2l&C=~EoK6`!89OXu>Te|hq& z{P}g&ueDulG;$-FvBx2k)yk zPQ1t3`0;*gUR<^7P(o`FkI>ekrfN>ZgM^=_7u+X*WIPlg{!?fBEN& za}U~YI1i!gnsXAm-Z?*^>!5QLx;{E@q3fn|7`mQ1pP}ol^BlVVI?ti&vhuFi>USL% zr|Y};UH7%yen39$6XeLob(Yt-L#vY@=0fTroa62W&WRW8EZgM^=_7u+X*WIPlg{!?fBEOjtn=&Ftdm*v;=b#>#+db{yw z9o}|lecpU#-QGNBJ>UGD_f@}?*I)JXOPu@?Kfkn_U-HQ>dFGe=KkU~_*RQ#*ZTVd9 zw*FiPH_luiH~w5Vx81p(Za#CJ-8|>|yZJlst9~iZFZJ_Foct0$zqFfQ^2slG=9m0G z?AJT@d^Y2=d1u@f;4);IaL?wMb$hsI~+#%=YD=i(UW#W((I*Sshn^QAn^qw+Vu>X-8RtA09& zlRo07n|9MvKItsa^p}6WIM=cLyz?I0H#!Hh{p1Vhe8~2h&W&vU={(8yrOugbzv}$S z_OZ^TY=7&#%J#j=+YhVXK3Sah&*HbQ)^7W4`Lqw0XZv&cw{O?4_VdnrtlT+})ptH* zahw}jeCJ8lu5%{K$N7`x>0HY4cV1=vQeJ=6PX}?*NBnftZhFcmo#mPS^3NCNrgr^u zo@(>XIjhY_=dU(Toy*$%bzW=p+BvSxcjvpd4mkI<^}%_ttsBZ)57loy6sPr2{MJM5 zwjRo-^-!Lzhw^Vd)UU2z&Qq=2Ijhxo{%UcY%UXQrwbrh4T+7G#uI2fGIrp{vod;XL zl-FPN(?Oi{5kK9uo1XGXXL+W-{PShjjrGfU#g#k9xcbgFE{=1Li|;(-+I3EH`8Yqh zJe{jt{?1#jU&`yR`spA}`iP%y+D%XSq_aHJU;g=`U-{*{;>w+4Tz%&o7st8B#djWZ z?K&s9e4L+Lp3YS+f9EaNFXi=D{d5o~eZ)^U?WU)E(pjGAFaLZo4qFe6&*q(R+k7;h zo2SNk^Vj%qUYi%qck`unz&vVwFuz(il((L!-#Q~s>yP-YOWJL{l27ZHJX_!7-@2z? zt%t^E<;HFGjpyPR=fyYvYuCIeAM>R=&7<-+zv`Fr`m26Ah?73zr<-=uQ$Fb|&-9mn zzBpIE_0W0y`RE+}{B=HmzCZhAkL`GHo`2)SIsc6x=l?gZd>5ec=6eB+L*qm;M5QontdIPJ&8Z=a^!_HXiOUnkG@d-87|s9)_5 zU9T&59k0IYdvRR%i*G+ryY>m?WB*W|_7&xCzfr%G*I)J1L7emvKi#yOp7Kd&d8WVo z^JRX2tzW+HQ@QW{RNwc2isL&$#rOT7+Vx$b^6|Z)^7I{|^7nnB`lY=7s-F(xq>uRN zrrq?EPddvp{pFu8`juZVpYQur?z=zL_dTHE_)bvqeLtvneOIV_d~c{ceTS(0eV?d) zDX+ikr-L}@BYwJRH$CN(&hkuu`R9v%b^X%c)=4_Fe$uCPm2R!K^lTlbbL%txTetbr zdd{!bdF8GD>UUibr|X6IT}QOr^+i5icjVdiNd8@?^sDQa{#H(h>eHtZgM^=_7u+X*WIPlg{!?fBEOjJV*2(zveld2bItBIS;Bo&+R-Y z&OFcap!oBg&x6{X=YJlQ&pa3OpgiY!p$Fyf`+D_DdHq#C9mGi=@zYJa=_#LdmS_6Q zKVS4Kzvj8AEuZJ9w*EY4wQ=V8tBpU;Wo^6jyw>J3&v9*@^W4|w@B4c7OL_fOKOMwL zAMw*oyXh&Pbe3oO%RgWAtLvBkHt*=re56nFly1#mdN!}=+i}O`ANbX}p}h4( z{ni((7!zS zQvUp^U&`yR`spA}`iP%y+D%XSq_aHJU;gV&hPG^Gp5ampIKY@ta@TZGOq8`6bWhm;9Sw`qliJ z=iIh@o`2i=^IY7r5-uzO(`6W*COZ?`S zcAH=FX@1GG`6d76*St6Sp#A*3cln@w<2&X%x$P(CJiOXq#h z2klqqJP(=e65@UOw%^<=OsR{_WfKtNr}E zC%fhI{_NJD_i8uJyl=bl=RMqQcizw4eCEB~&2!%8-TZyew|*(Fzv`!hIO!vPx@k8( z<&)0xOn>?3%e1reYo6;^ALn_G^>>~FS>NaRkR1>6+{liTd7fm)&pcp2OMlc|K?B&vQE)XP)QT_`f~h zv##BF{%7-<=YlrRd0uGq_r2`;rM&s2e)CJ5=9l=*FYPwJYW$ieb=e2hH%yV2juIBl!9dEuz-#Ap>{8GR9B~J58 z{N|T-n_u#2e#x`>CI9A^el@@5IkzpJ=ij#eJQufd=6Sh|KhM!^yYqbA<}=UTZJzU- z-sbOn^z}=5^Gp5ampIKY@ta@TZGOooo#om5l7I7S_Py)ZJXgQv^Su4mpXcy5&OD#L z@#neyZFipM-+bmd|IKrr|KI%Qy@2hP^88Xizr@Ke@$*Z&`6ZwHl4pL&Kfm-VzvexN zEuZ%zw*I^~v2o^oij6<-S!}!W{>A1q?`3SB^S;LBKkspDzm(^f`uQbJeu^*P{HkBd z>#zFhAWr&-pKjVsPx+*?JkwwP`7+O$@BEtQwAaUZetZ3$=epPTdER@+!#oGR<7A!> z-|;igjqkXc=gD`x&2#2E4wW~*)Ng)?)BF;@`K8_FmwcLE@@#&|zxkzK&98Z`e#_^1 z`>j9E;cuLIK7ZrSbNk!wJkP)R%ya&m=RE(v`OkX++b`wKFZG*W;xxa+Z+>aF`6Zv` zmpq$a@^5~*F8BM(^}2n&>v;Qr*Y|!GxbF9R!G56M5%vlFzOaAjcZYpNzensh`kkV@ z-!JO-yGERT?}*>;Ano@1NIv~;l4rlCviR>>tY0zM}l?H|m%2`m26Ah?73zr<-=uQ$Fb|&-9mnzRWz{^>E&k-FY|f&+dGj_iA^Z z&il4If9E~io!9ez?)~QbytjM5bzt7-z2EvU@A=+u-B8|oqJHa)IITb8w=QY7^-4ai zWAbc$lYi@;ezhLXd(B%u?>le(c@KKy%=^(Bf8LwkcISQST@U9y>s=4${p(#1=e_J* z50%$n_0vI|^bx=HP`j;%@@YMkXX~N-TMy?w`uqLu`_1=xFaCb(z`QSizx83>qrcxiN_p#{`mKlJv>uAzdZ^vjL;18G z%Cq%Q{;h}l)p|JR25kA9C$RPBoPmw=!7u%_jX&oSY`b$_!R9mP7;K(%zQN`{=N@do zl-FPN(?Oi{5kK9uo1XGXXL+W-{PSi04!eHM-!Zp*{=T{O=kJ~yXZ{|#@#pWP+wT1R zbn}_Nt8Sk2_twpS{tmnSQl4Mx=a)G7C4PQsH^1bQU-HZ^`RA8@<=6b(dCTYT(OZB1 zPQ7vF@7EiD{;s|4&fmK?pZPoZ<~e^K-~8wA=G!mj`K5k-iIZRA=a+W#OFsD}&-{{q zei?`D4~@^}opIZIG@hHM#(DGC_-|gD7tMF`rFFnOYJD)jS`U@C9;)AZC{F94_^pT9 zZ9SAv>!Cbb59Qx_s9&vz#%JZmZS{@k;uz<}H~wqayeJ>@r991}@;ATgm-70nemaPg zKH{gFcGFWn=`7Fmmw&#@xd*#HoO1(qA2R0&?EYlV8Q6WxoIkMpnK_qW_c>qv^H1IV z&zxhh`=UADVE0RN?!oS(lsCWBZ+?l>{1U(UrQPP2e41bKY<|hV`K4dYuQ}&o%jf)u ztv}~NY@9hSV&l&_65H;aFR}T|xf7e`oJX z?YqQjKPGuRNrrq?EPddvp{pFu8^PKtmHRnog`J6Yk_2(R_jWg#{ZTva6 zYTKRjtTvxH=W6qu^RG7lITvgDrM&*CpAO=rkND}P-Sm`CI?FTt<)1J5m0xoX*p|=v zU|WCA4cj<#p4i5pbH=vaIe%>PnRCfD&pEGb^Ph9fwqMHgOa1&3C%?qcFYV@+eDX`4 z`6d5rzq)?uZ|fu-T0iO2x=Od!TY9z*)4BDT{;k`5X+7sx>%8*TfAzaAh|~2#{H`O~ z?fN30t~>JVdL;j@Q~c`srN5Qaq5AYG4&91R&)TJP`Ov>S`BMJ;s$a_MulngAPWp(S zZrV*x`J}Tv(_jAiGX2{9;k*a2`;d7*V)rNW-o)-(=6#CY&&+!kyU&^TFLwVk?`7=1 zXx`V@{nEV0vHK|HUBA@t`Xx@+FY&v6X}9Z_e7b(gv+I}qyMF0c*ROeRWy|M%maRYU zxon(y|7GLPdokPYyf3r)%zHGO=e%FD`OkYd+b`u^ztr#gB~I5b@wzDkye$Bpj-`AVxwD-NRd47A}7n|q0_dT+C-h1CKo9Dpyy|Z~feBVc#=f?LvwRxU= z-(U0oSL?j;)!JKx5B00{aGtB*@_F8V>(6ue8)u%+ z-}v*~{Bh>!CQUhvK&$YPa=JKCOrHY(12J>*3tT zzTbZ1HYkg=Ww=sp3m9(^W4tHndf;n{ygWi?auQ* zo6kHKw0X|+LYx0QN3{J?o?q(cmpJ()e!6KlJ>`?m@=SmE=L^5Oe(7)PBpq5m>C?JO zx7J&Fwhq&|^_l*y+k9y~=U3~z^45R#yDo^+^+NovBiilyBA>21^6Yvf|E^Q|)%8n% zE2l&C=~EoK6`!89OXu>Te|hqy{P|VCl-FPN(?Oi{5kK9uo1XGXXL+W-{PSg=TVB8B zx!*0H=YhBWJSV(y=K0}`KhG6!yYsy9<}=SBZ=N6cs2|w;=egzWm-70nemaPgKH{gF zcGFWn=`7Fmmw&$KSANZN+FL%)Z*Tp1u6yIm^WGbOo&(=@=lSr>XPz71Jm-1x&3~RV z-+n32FZJ_Foct0$zqFfQ^2slG=9m1h{c1hb-{u`1nve8pp3<%POV8#toty9UZyn%E z>jS@9=ash}s^5AjPV1rgt%ureJ(N%Dp*&j;<==Y9uhv8Tt(*?kr%!R{R(yKaE}hGV z{^iM+^5<9mQeJ=6PX}?*NBnftZhFcmo#mPS^3RufZh7a|Jomdk&hxr~GzR&Z+ zJ09k_;vFaRyz!2oc@BBU)jXfP<87W>-f^hB`K5mIOPuDH_{}fvHoxT4{E}z$Oa9F- z{c3*AbJ|-z&u?%2d9Hio%=6wGf1U&1cIWx<&1aq)-#q7e^38vqGv9tGZ+@xY{1T`6 zC4TcuyUj28G{5B8{E~n3Yu*dk{ro&vzx&2{-hTI!^Bn%}Gw1pI-G4sx`LEf1={(QB z`_*~QfA_KT{QvH6=e>a4_bP8cuYUV^aoW#|-+o@Z?dRpweqNsK=jGpiUccJU&wCJC zKJQ0t{dsR<<2?Iik8S*U&tlu1_b)b|c`sx0ocA?0|9OvN`=z}7y!!3u#c4k;e*1at zwx5?z`+0e`pO=68d1s5wSiJMbfB4oLXN%$A_~N(TI9m*V#53P|<7_efw|?#M8)u8* zUwZKPjkCq@Kl}E_Z=5ZLKk`+N-#A+gf5ewPe&cL0{CO{V{KlDS_+?-4_>HsFDxbfl zZhdF3DHq3?Y*>6}wPEc#!wt*F*=|^#&V0l2cNQGhugY(J{HBKC$s% z@)b{PyRZG`CvM8;5B>8eZp!mHKl;Sx|3BXK#P;hKe(s6wukv(IKYheWH}TU`yXh>S z^p|J8$p6|eJnQ~?hw~2S9nL$PcR25G-r>B%d580^a+*}1Rygl)-r>B%d57~3=N-;F zoOd|yaNgm(!+D4E4(A=tJDhiw^RD{5!+D4E4(A=tJDhho@34MZyI%RUAALTyc42+D zc43-WyD+UDnzakl(AtG*Ywf}`w{~IPS-UXrtX-IQ=6>bYgz8%>usGHbEWWh`YuB2C zmANJoOd|yaNgm(!+D4E4(A=tyUJ-&eOlqX!+D4E4(A=t zJDhho?{MDXyu*2i^A6`7&O4lUIPY-YRnEKW^A6`7&O4lUIPY-Y;k?88WiQlq!CnaK zyS)&miMCag0wazVV5* zYkXq)7-LwT#vbOKF^ToDa(%BpO^QRS;?uBpX8agxmQVW2GhgI??H6wSR0r$3|BLeu=N-;FoOd|yaNgm(!+BRZO{z~ToOd|yaNgm( z!+D4E4(A=tJDhho?{MDXyu*2i^A6`7&b!KaSAE{$yu*2i^A6`7&O4lUSikJYx-Qs{ zb-l13!!)rU!?dy=!!)!X!?d->z%;k_z`U~`!@QfZd6;+hW0kw6SKl=qi(@~A#kU{B z+O;3U^06Po^0e2&yt4ADWjZ@5-Nd^^14)S9v<9pFZNG zoA~Le-E@{u`pYw4%0Gp^A6`7&O4lUIPY-Y;k?6nS2<0pPb-{vIPY-Y z;k?6nhw~2S9nL$PcR25G-r>B%d57~3=N-B%d57~3=N-;FoOf8i{Ozyn zg1`M?efPINOcQ_m!?g0ZKTJb^`@^*Lw?9mCfBVC{^S3|DJAc!}yz{rt%KZ(r`u;YG z#ql>&EWW>`V(t1HE0&MHy<&O#n=F>Uztv)WtX$u#Pm|)%s`xalUD}op&C8Q_<4(A=tJDhho?{MDXyu*2i^R9B5 zRG(Hj?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$Pca`(5`n3g;cp zJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhx4v--c_G>IPY-Y;k?6nhw~2S9o8@R z+q*8f-`@4Y{dP#MR<7^Wr%7>W_0Vm68rCjt%ZKLW$-DCB zUH#%+{Z*b0>Zgx5=_Y=9YB!zblm7C|7x`cNg!TRq1;=IFohw~2S9nL$PcR25G z-c?SM>eCA69nL$PcR25G-r>B%d57~3=N-;FoOd|yaNgm(!+D4Eu5#X0pLaO#aNgm( z!+D4E4(A=#FVCiSUGQvb*9*_4Vw!k171PSIshEbIO~thJY$~St^XJ)A%sbDf;>()( z&cnR(Y-i=3`K-QYL9sZV5yj$rb`)#ZGo@HQo;Aht^b9KIoo7?AK31;p)u%~uXjOa~ z)-G+!hvwzUyYj!RnU{X?uKp@d2ldlOoOBaEJ++(8@=1Sr=8OEV{lcxE>R^5Me{tU7 zyu*2i^A6`7&O4lUIPWT_N%d)k^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>B% zc~?2_s?R%|cR25G-r>B%d57~3>z8NUyDoUvz3YW%-7!r(>yByVS$9lB&$?sUde$A& z+_UbOcb;{}yz>k{=ACEzEBDNQ^}P###qo{+7T>!ASi9aS!1D2~0hXtC5HRn&n}GGP za(%BpO^QRS;?uBpXB% zd57~3=N-;FoOhM;uKK*gd57~3=N-;FoOd|yuznezT^Eect{289rit;1X=Qw38XBLN zwlv2y=LP1S@rm;e^UnCJTpz2ik60Yz6N_(rV(l8ASU$!WmZ!0Yd1p*weXLyHt51{S z(5m<}tXB% zd580^a^6*+cR25G-r>B%d57~3=N;BB@8We`@Gf503-97#ns^rv)9Ow0E*_@gr_Q^0 zn6}=%0Gp^A6`7&O4lUIPY-Y;k?6nS2<0pPb-{vIPY-Y;k?6nhw~2S9nL$P zcR25G-r>B%d57~3=N-B%d57~3=N-;FoOf8ijL)tM#%I?H;}g@w_{6j_ zJ~0iAPfS~yW18~<^UnChd53vtd{(ZH)z?QXj`4}bH$Jg;jZZ8eV+_mF*u%UtCb2$N zuJ6^SNpWaZd>Ym+ZOez|<;lD9&pU1LuKp@d2ldlOoOBaEJ++(8@=1Sr=8OEV{lcxE z>R^5Me{tU7yu*2i^A6`7&O4lUIPWT_N%d)k^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$P zcR25G-r>B%c~?2_s?R%|cR25G-r>B%d57~3>zA`(yDm5zw(EtnVKGgd4U1{zY*$JxC2 zcsFPEV%|B+7a#9#%k{nbG${_PiciDZrEU4pygYeV{=BPSysN*;(?R|85hvZmPfzWp zvwYHDp7|pGYrk;or#e{Q{a>7SIPY-Y;k?6nhw~2S9nQPTX;OV!;k?6nhw~2S9nL$P zcR25G-r>B%d57~3=N-;FoOd|yaNbqUyXx}}=N-;FoOd|yaNgm(!}{f{n63-Xis^dc ztQbraXT@MzIV%R!&{;8b+xRrBUD}op&C8Q_<BfoF>($ z70x@HcR25G-r>B%d57~3=N-;FoOd|yaNgm(!+D4E4(DCvysJL%aNgm(!+D4E4(A=t zJFH*Mp6a^b?5VC7&Yr?FarP9Zm9wWX4V^uOY3uAMOmk;XVcz}hoIQnk=S(fkJ7;ZG z?hLN#JDUrOTxxe7u`8!7%Tf6^4&@x8?d?eVP=9R>h}b?b5b< zXkMPYD}UbAFW%K(<>{b)`iPTm;-{x}(^)?0FVB3D|FvJZ^-~?J@BS~&JDhho?{MDX zyu*2i^A6`-gyvG$N0qJ8=qLa#wV7KF^1)7>|x#+lUN@s*Z1nvq&T!HJ`HP^w&g?f^5k9l z=bg5ASAUhKgZk+sPP&Pop4v@k`J}%*oiQlB{IC7Ot)J>(efNKH-r>B%d57~3=N-;F zoOd|yDyK>HX@&C+=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{MDXyu*1{Iq#~^JDhho z?{MDXyu*2i^A78mvoX6aI2*I;g|jg+O`MI1Y2|E8Ohad5V%jBjP z#+>y)~+*1v3#6Oisk9dQp`JNnPPpcT;Hotlj6{- z_%y6t+LjN^%aeEI&%64?yZWm<9n?=Baneov^we%T%P0NinJ@Cc_6xUus)P02|HXNS z^A6`7&O4lUIPY-Y;k>JyCe^1E&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d57~3 z=UwHzt3K~=-r>B%d57~3=N-;FtY6MX?z-S?WUTMbM#eO8HZrD_vym|kosEoX>uh99 z^B2$A$e4G|M#j8zHZta&vxO^n=5Y0$MU2I9MllxO*~M79&NRmIan>=Gr!$bT{GE-A z^|5k&uRcwRL#yJ`uy$!%J~S^+-jzS^>KE_oukv(IKYheWH}TU`yXh>S^p|J8$p6|e z-1?~w&O4lUIPY-Y;k?6nhw~2S9nQPTX;OV!;k?6nhw~2S9nL$PcR25G-r>B%d57~3 z=N-;FoOd|yaNbqUyXx}}=N-;FoOd|yaNgm(!}?`>c3m(&yIvTdm?p+2rj_xDX=r?6 z+R_};oEMmP#wX4@%sb<=a(%46K4Ni%0Gp z^A6`7&O4lUIPY-Y;k?6nS2<0pPb-{vIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d57~3 z=N-B%d57~3=N-;FoOf8i?8mw;*pGF+uph%Tu^+>(H?wa36T zxA(xjvme8}vme8}vmdM6HNE<-=~x{5F)Y6Q7}l=+7?zJc6_%&H7UrEj7}m$i^}YHu zDGsfQPs7@!ZTZl=Jb73CysKZltG~+ALH+a*C*8zPPwl3&e9~W@`6B;ozi{iPI#}QR zUz~S1?{MDXyu*2i^A6`7&b!KKQhi$Cyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$P zcR25G-c`=K>hlig9nL$PcR25G-r>B%`sIFm*9G_6yI#28j%nh4JEoQU`Iv_8w`1D6 zhm2|N-ZJK$`|X%_?zdy!x!+#7d$!eg&lZd0emfT5{dTNf_uH|2+%w1WbT1wA&OLUl zkCp3t^=VQZS{0v$wM*Obp?P`ouKamdzj#-Fm8XOH=_5|MiJzX@O=tO}zdZ9r{?~rt z)=zb?zWcv8?{MDXyu*2i^A6`7&O4lUmD8m9w8D9Z^A6`7&O4lUIPY-Y;k?6nhw~2S z9nL$PcR25G-r>BfoOjjd9nL$PcR25G-r>B%d587Ox4^nC_!d~#3*Q36H1RDkOe^04 z!!-0QFiczD0>d=-EilYG-vYyzHS=o@^Uk-lD))`8>ihN<7RNWau=v0IkzadQyT0M2 zTs|-Q`U}g`H@}qg&bPp@K31;p)u%~uXjOa~)-G+!hvwzUyYj!RnV0-|SAUhKgZk+s zPP&Pop4v@k`J}%*^F{vGe&NB%d57~3=N-;FoOhMer24eNd57~3 z=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{MDXysMmd)#n|~JDhho?{MDXyu*2i^~<*f zyDs>)VAl)Z7Q{61Z9z;c-xkC)^ld>*Ti+JMH1};m%sbx}#Juy(M9e$iQmouJ7OU^u zi&z}rWW?h8RwLG~Z#ZK4__iaKr*A%D-uV_J*2l{Az4|mM4y}q$!`h{7`Ov&Pc~}0t zt6#jUzsl1={qzwh-Na8%?WVJQ(qEqWBL8c@aOC zag0wazVV5*YkXq)7-LwT#vbOKF^ToDa(%BpO^QRS;?uBpX8agxmQVW2GhgI??H6wSR0r$3|BLeu=N-;FoOd|yaNgm(!+BRZO{z~T zoOd|yaNgm(!+D4E4(A=tJDhho?{MDXyu*2i^A6`7&b!KaSAE{$yu*2i^A6`7&O4lU zSigMxxa)#%A9ua@nECcGripJKV_Nz4F{Yt!A7k43_A#cpZy#gc`Svm9oo_m0-uc#Z z<-P%3ecy)0;`nAX7T>p|v37l98q3GGr?EVJlN$5Rx2mx|R<7^Wr%7>WReT!OE^W() z=H3g;cpJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhx4v--c_G> zIPY-Y;k?6nhw~2S9oDZu__{x}*M+CP{=)kHn#V6plW+O27pB#J{J0mN`ZRprU%N1E zzv?G1O!L=#`b$n7-u;E|zA*3R{GU_KJKv6XjZp5J@>qS}n#bb!20a$vx9PEVeX}0R z$G7aUJbmLH%m0sj*M;@5a(%BpO^QRS;?uBpXCag0wazVV5*YkXq)7@t_4 z#vbOKF^ToDa(%BpO^QRS;?uBpX8agxmQVW2 zGhgI??H6wSR0r$3|BLeu=N-;FoOd|yaNgm(!+BRZO{z~ToOd|yaNgm(!+D4E4(A=t zJDhho?{MDXyu*2i^A6`7&b!KaSAE{$yu*2i^A6`7&O4lUSikJYTqCgkSl0{tv92Tb zW0+RADWjZ@5-Nd^^14)S9v<9pFZNGoA~Le-E@{u z`pYw4%0GpX(A@hJDhho?{MDXyu*2i^R9B5RG(Hj?{MDXyu*2i^A6`7 z&O4lUIPY-Y;k?6nhw~2S9nL$Pca`(5`n;e!g+`D z4(A=tJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k>Jych%<|&O4lUIPY-Y;k?6nhxN<* zpiVp@4W6w}cAp_sPbdBik-$Gi)PdFTC5%scOgV%~W_v~uql zR^K~@SRC(%V)4BninZ(gP%Izscw%{a_Y?EZJE2$~E7$kx)1)}GDn1Qsm$v0Y^YY|f z`SY%R@viTUpXy+J_kVHT;k?6nhw~2S9nL$P zcR24Vr%Cl`h4T*Q9nL$PcR25G-r>B%d57~3=N-;FoOd|yaNgm(!+BRZ@2bx`oOd|y zaNgm(!+D4E4(r$5H~opdF1-66U0C1$(yJ~^lb5{k!nAtY@4PS#|H%*j@$-La`*mM@ zVVZx%Z~n1U&bx2?h70rV(?90Iy!-F}_%lu&XlP;?S!2G^}0PmJiL#lXvCMyZXhu z`l~!0)K4FA(oOvI)NVS?k3%7o%gYypO9nL$PcR25G-r>B%d580^a+*}1 zRygl)-r>B%d57~3=N-;FoOd|yaNgm(!+D4E4(A=tJDhiw^RD{5!+D4E4(A=tJDhho z@34OT&&NJ_D=7v|k7pY}PYoOcht@xsc#^Z#5}{kMI|=bk#^{L&9ySo{|~7ai4h?8#O zr>Az)Sw876&wP>pwO_dPQyrXlIPY-Y;k?6nhw~2S9nL$Pca_tm`n1A%hw~2S9nL$P zcR25G-r>B%d57~3=N-;FoOd|yaNgm(tDJY$=N-;FoOd|yaNgm(!+D4G%lPbfkn!2? zBjXd(#Q4OtGCna4jZaKlnq!*t0`t!J#CeB#XM9$!kJZ;lEROMs#Wy~&c8yOgALA3t z)7ZnjGbXVWReT!OE^W()=HTUpXy+J_kVHT;k?6nhw~2S9nL$PcR24Vr%Cl`h4T*Q9nL$PcR25G-r>B% zd57~3=N-;FoOd|yaNgm(!+BRZ@2bx`oOd|yaNgm(!+D4E4(pfwSighp$NGI_KZa>y zKZa>#KZa>&KZa>*kAZ1!?}2$|KZbc{KZbc{KUTSGdi7n?u{ic)SbY02tX=ytEFb$Z zEKhqa%sYE9tdEuJd-Z8j99k8hhP6xE@}YTo@~-@OSHE~yf0d_$`spK1x{05j+D&Kq zq`y4#MgG@*;nq)eu)h1hIPY-Y;k?6nhw~2S9nL$Pca_tm`n1A%hw~2S9nL$PcR25G z-r>B%d57~3=N-;FoOd|yaNgm(tDJY$=N-;FoOd|yaNgm(!+D4GYrbvq{H_c0ZHvSD zKHs)DOq2Ou#$j5`cQg*uaK5i`n6~rnhQla#;NNZpdNn&i6zP%V)kba#)`8{gK1+pYM_!*2l{Az4|mM4y}q$!`h{7 z`Ov&Pc~}0tt6#jUzsl1={qzwh-Na8%?WVJQ(qEqWBL8c@aOB%d57~3=N-;FoOd|yaNgm(!+BRZ@2bx` zoOd|yaNgm(!+D4E4(pfk*>%DA?0R8*VwxDAm{!IorlIkPX-jiVb6#NH8J{@sFz<}d z%Js4O`iR9bKC$@5C)TdSn0Lk`*2l{Az4|mM4y}q$!`h{7`Ov&Pc~|~< zr!C&qU*+kbe)@=$ZsMn>cGFot=`YWGk^i+{xb;&VtndCW&O4lUIPY-Y;k?6nhw~2S zUF9^XKCN)x;k?6nhw~2S9nL$PcR25G-r>B%d57~3=N-;FoOd|yD(7AGd57~3=N-;F zoOd|yaNc44nzO$5x-e&b@AYEN`aVpPIY0a`t>#?u!!(@p#t+kW&aysC^Eu=CFz@Ev z^25BF?+6^`-JEm2<#X2e)}OP!4~sMBr5_f5&QU+C-8oB%d57~3 z=N-;FoOd|yaNgm(tDJY$=N-;FoOd|yaNgm(!+D4GYrc!R*M<2m>RvDAyQqh0GT%i# zOsn}W>R}qrcTo@1cE0s_nC9~h(8Ii&@1h>Qcz0pm&393^e7>!@_2=7~hsBxiq8=81 zzKeQTyYpSt!}6JLn;w?ueDm}$@8(;mhxM^?eXl-EibJd7)3A1FTRt=|Pu`XP#k)(t zcvpXwr-S;e!g+`D4(A=tJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k>Jych%<|&O4lUIPY-Y z;k?6nhxKc|6Svoe`A*zkFXlUOhiNk3i91ZIhd%!`hiN$9i91Z&$3FD;4%2+TiFTNG z^PRZEyqoXD9p>G9CvMB)zBP7OoM*r6vBToecj69fcfJ#MSU&Tux5M(BZ@?Yq z-FzGFus&9<@71SCacEV18rCjt%ZKLW$-DCBUH#%+{Z*b0>Zgx5=_Y=9YB!zblm7C| z7x`cNg!TRq1;=IFohw~2S9nL$PcR25G-c?SM>eCA69nL$PcR25G-r>B%d57~3 z=N-;FoOd|yaNgm(!+D4Eu5#X0pLaO#aNgm(!+D4E4(A=#FXOY{LB?mlkBm=D6XO%p z%J{@IG(ItHX^v^m3(Py?6XzY~o$*<@K2~2Ju{g#j7T@^9+BH70e2g(HPh$`B&X~md zSh>DepC-kjRq<(9yRBfoF>($70x@HcR25G-r>B%d57~3=N-;FoOd|y zaNgm(!+D4E4(DCvysJL%aNgm(!+D4E4(A=tJFH(1zyFE7E_~pleqgT`zwp8f)8zmC z(+kt;Z$Im8rw$GO>`z>nw%`9v|MHa6{5^l>2M_b^4WIHuhj}-1{V?x-=6x4d{;fa# z!(0FEoBs7-aenWYy#28Fzw!PHYxm_}|Kur`&$s-S3(NDBPrrN0dG|TbzOX)4uJ6^S zNpWaZd>Ym+ZOez|<;lD9=Ux5cUHw&_4(g|mIO!&SdTKYF<&*yM%oq7z`-NLS)xrAi z|KhyEd57~3=N-;FoOd|yaNbo;lj_q7=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{MDX zyu*2i^R9BeHk+v?@LgYnQg=L-X?FUHS8_e(|pUDo+RX z(?^_i6F)t*o6hn{e|hGM{IC7Ot)J>(efNKH-r>B%d57~3=N-;FoOd|yDyK>HX@&C+ z=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{MDXyu*1{Iq#~^JDhho?{MDXyu*2i^A78m z@%e9VpX)F_vA!Fhm?p+2rj_xDX=r?6+R_};oEMmP#wX4@%sb<=a(%46K4Nivxd- zSig_#$1qLo$1ttz$1n};$1rW}F)+>TJuvU=$1v}v&BMI2AFJFoz51@{SRDH?EWZ61 z)~@{+mXAFZmZ!ZI=AAtl*2l{Az4|mM4y}q$!`h{7`Ov&Pc~}0tt6#jUzsl1={qzwh z-Na8%?WVJQ(qEqWBL8c@aOB%d57~3=N-;FoOd|yaNgm(tDJY$=N-;FoOd|yaNgm( z!+D4G>sMd>t9QCCeETO}Sl@ro^Z(l^r^z?o`{l#5dgI%E=`anS^{Kyjn6^Lmf?qgH z^QV9Ge?H8+hu{1&hj}-@gAViVIe-5hTmJmt|KnT#AN=xvI4sVy-v93oi+}fT{>WkN z{`A*8I4qyf{NMKu%k%yR?;e)_E8coxeXLyHt51{S(5m<}tXAw|=UF^A6`7&O4lUIPY-Y;k?6nhx4v-npB@w zIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d57~3=N-;FoOhM;uKK*gd57~3=N-;FoOd|y zuzo%F3;*z)t_$z{Ul-Q*pZk$#opPG|-+%kbhiUaw|LM~X)A0M=`x%F6`--{b) z`W)|WbrU~5wVTfJNq>3fi~O(s!mXd`V14(0ao*v)!+D4E4(A=tJDhho?<%KB^=XCk z4(A=tJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nS2^#h&pVuVIPY-Y;k?6nhw~2W zm;G4RJNq%L@AhMuCiY{PR`z3WReT!OE^W()=H3g;cpJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhx4v--c_G>IPY-Y z;k?6nhw~2S9oDb8F5J7iE*#ePxh@>0$y^r>(`v2@hiN$1g~PO+weB#@XAL~eySXkL zzFjj9^KPySTRv;c)}OWIusCyFI4u5L7Y=K8t_z3dGuMT~@|-pQu>9v*a9AHJ*Z1nv zq&T!HJ`HP^w&g?f^5k9l->#XbE#B2%<>{b)`iPTm;-{x}(^)?0FVDGNpZM~>_6xUu zs)O?m=N-;FoOd|yaNgm(!+D4Eu5y}GpH?{UaNgm(!+D4E4(A=tJDhho?{MDXyu*2i z^A6`7&O4lUmGiFpyu*2i^A6`7&O4lUIPb82&F`RlT^Hte&|!U_-$93IGQWck(`tSP z9j4*jA2>|g+1nqc`Rw@*^KO0z9lm(?(!;!)-$7eGd+Dt|d+EdC%>9kS;?M7(!`hwS zL5Jltzhw@~bAIC-mjC?rIjoPB>wEQSQXE4(A=tJDhho?{MDXyu*2i^R9B5RG(Hj?{MDX zyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$Pca`(5`n*Vdsw@Z&!g(gXYxEO&&mI= z{HI@s^|5k&uRcwRL#yJ`uy$!%J~S^+-jzS^{?+^5a{9%)`l~!0)K4FA(oOvI)NVS< zC;jD_FY>?k3%7o%gYypO9nL$PcR25G-r>B%y!+gjzv*F|ca_tm`n1A%hw~2S9nL$P zcR25G-r>B%d57~3=N-;FoOd|yFpqxvjc+;q%Dc*WSAE{$yu*2i^A6`7&O4lU_;%hs z+V#%(?DvuJiEq6-eCypK%5S|peCyreTkj6vdiOl_dH1?6dc(u`*1NY?u8;V3-W|U6 z?(nU5hi|>RtNyKbhi|<*eCyreTkj6vdUyENyTiBMo%pxj9lrJM@U3@;Z@oMD^X|!K zz5ev;*1OZ++j;khJa6aS;al$x-+FiW*1Jd5zxD3$t#^lSy*r$Dt)INZxAX3B-YL&J zoOd|yaNgm(!@PUt+uran&b!KaSAF9X=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{MDX zyu&>D?#Et#`jvN;TTiNQJ;8a0^A6`7&O4lUIPb82*^jw)VEZww@AhNo8Z_4t`?0Ps z_G6fa_G6f~_86Gv_8ypb_G6fLa}LR2-r0{;?wVeG*K{n7{TLSCehh2Zehl-@ehl-@ zUJJ|L9t`VO<@#QIniPjt#iwEI(zbkPUY@)wf8NzE-ql~_>7ai4h?8#Or>Az)Sw876 z&wP>pwO_dPQyrXlm?mOkT4@XC9nL$PcR25G-r>BfoF>($70x@HcR25G-r>B%d57~3 z=N-;FoOd|yaNgm(!+D4E4(DCvysJL%aNgm(!+D4E4(A=tJFH)G*7uDy7SCDVhxL8V z`aVpPIY0a`t>#?u!!(@p#t+kW&aysC^Eu=CFz@Ev^25BF^UM$PZq7O1@;U2!>(5!= zhsBxm(hrM2=cpgn?wqfFSUz*^`eAv_H%|}Cf6i$?tY4Mud-Z8j99k8hhP6xE@}YTo z@~-@OSHE~yf0d_$`spK1x{05j+D&Kqq`y4#MgG@*;nq)eaNgm(!+D4E4(A=tJDhho z?{MB#PLt}>3g;cpJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhx4v--c_G>IPY-Y z;k?6nhw~2S9oDb;wuR>l&m5d@TO8K+`L@Mjn#{K?4%2GBqj8vq^L>rOw4HA^9H#kv z)8R1h<~tpSc{kthILy2GuE& zKIt#de3AdPU%2&C9h`SK?{MDXyu*2i^A6`7&O4lUmD8m9w8D9Z^A6`7&O4lUIPY-Y z;k?6nhw~2S9nL$PcR25G-r>BfoOjjd9nL$PcR25G-r>B%d587O`0RQ&-_64wVTfJN&n;B ztuOMw_6xUu@($~}|BLeu=N-;FoOd|yaNgm(!+BRZO{z~ToOd|yaNgm(!+D4E4(A=t zJDhho?{MDXyu*2i^A6`7&b!KaSAE{$yu*2i^A6`7&O4lUSij~w;Co$|?||?1V!i`@ zm?rZb@WZs4?|>hs;d}@DFm31C)`w~S+TVKhVcyMmzz_58&;Py)^KQNazUA{R>8(HC zl0GcXd;e!g+`D4(A=tJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k>Jych%<| z&O4lUIPY-Y;k?6nhxKdD`rhlpob~%M-^yVi9-@AK|wJTIpI>w9KBng0Lqne}S=f5m6k!|DGUpIL9G|I2!2 zJ)i!M>zTQm{@?PMxtsn!^O?Du{-5&^pZ>4!v3~l$zGs$a`v1~rmVf$x)Ms|x>Hk-s zSv}MLyFRlzr~i+AX6~l{r+sF7EN<_u*OT(-Rr&R>>*{Uw=y`Q=SN+_zFYel}czv+G z{>W3`q+bN3g-^z z4(AT%4(AT%4(AT%4(AT%4(AT%4(AT%4(AT%t~htC=MLu%=MLu%=MLu%=MLM~^xYQY zxv>2kR&4LncUz3-$n<>~Gwap#JsLCX;q?6)Gwbd2-3>GA`ShI*Gjlh6PshyMP2Za{ zGk4SXdW`t=-4-)jKYh2w%<@d%4>Gg-)AxqV?7GwUiOj5?>3c?I=5G4_k(t#$eJ{z( z_E_BBTdybO(W~<7Vb|5$>e2J+8U-9~2ef^QAzR6!dUAI1~r~a!mFX~_V z!recu!MVeFA}7ur&K=Gj&K=Gj&K=HOaXo3hUg6x~+~M5e+~M5e+~M5e+~M5e+~M5e z+~M5e+~M5e+!g1p_1xjy;oRZe;oRZe;oM>Sn!X2oJQt?#0Uytc>3hIu)|2Ubz-QL0 z>3hIu*29PY;fnQk`flqvuIJNtUa$V`^m8&E0%xy9`HHty3_Z7&#a#5yS!KbcB*swj_;Ydo4)&dW_v7d@2%I9^5|9h^|0&e zZT0ARb#hnz+_f+6+OK$hu)hAtQ{UvTpRQY<)l>gxcWYkMzx0K>e{zTI-M_`T!@0w` z!@0w`!+!4U1?LXuuDG7GUaxTOaPDyKaPF`=Il{Taxx=}`xx=}`xx=}`xx=}`xx=|D z&Ry%d!@0w`!@0w`!@0w`!}jI%+53L>-ur=GpIA@4KCxbTePTWI`owyx=UC6Vz}$I# z;@n~GI4y3Et+z)kkJl%b-|G{*uGc44kJlJhr`I0l&TA6eV{vbBA+> zbBA+>bBA+RTu)lBS2%Y#cQ|)AcQ|)AcQ|)AcQ|)AcQ|)AcQ|)AcQ|)Acg4ADJ$E>F zICnUAICnUAICt2-%wxUpXCCYQK=T;Z6Z06>EAtrEL-QEcTQdgMbF&BL&OC;>Gml~J z%wxqp(_8PEj^#0rVfoEt*mccLSUu)3JiD7_EzF%64A1V?;`ZKpJt>b~m0u6LuHIIU zo>wP#)z4k~;;#LQ*9YtCk398F{`%><^;tdjU!8eT|I!!k{%H-icmEdW4(AT%4(AT% z4(AT%4(G18p0r-CaPDyKaPDyKaPDyKaPDyKaPDyKaPDyKaPDyKaPDyKigVX`?r`pK z?r`pK?r`pK?(n>?H}5c>3-|u>72Ep(%pawqiZ}=_R+D|E=DB;u$N} z^Gknt+d0nN)qk{N?p}H86?3=edAFI@h(G56E4F^GkKcNZ%X7!0S1kWKc3QFP9`!HV z&ui54oOiBRo!7m3#p=KD+5h)uZRt$zAnx*S@%GzvA`5 z`uZbJeUra_x^8_|PyJVCUev$+!WZuTX${UD&K=Gj&K=Gj&K=Gj&K=HOaXo3hUg6x~ z+~M5e+~M5e+~M5e+~M5e+~M5e+~M5e+~M5e+!g1p_1xjy;oRZe;oRZe;oM>SI{l_! zjsJJ+z&qSD{y(mV@4sR_IrM!i)~jRhyw&_1(Zg$wT(RD6`%f#@^SkbTv(+v@elm%V?*@~_)!n{nM2?6qR`ocQ7u&+cBk zV(zXwcg3^2wYa^vUQf!SSLN5kuB*4zqvzGhUG;OW~%d?Zt2V;T+fVjaUC*^=~J4n}7cOnYp|Bjw|Nw zkN5cAi2vhrzB|^RbJle;%k$_fzcaJ^zxRL@yY6@2^X)mVo{v3w#oT@Cb}Lr@?QXnw zUSp5N?Y;GSQXai3zaDm7y{#TSuTJi&pS$+OUHcWU57yTodFq?|_0x6hvwG^kI`g9b zr7zt5(;A#RtS55f+~M5e+~M3|KX>+mbBA+RTu)lBS2%Y#cQ|)AcQ|)AcQ|)AcQ|)A zcQ|)AcQ|)AcQ|)Acg4ADJ$E>FICnUAICnUAICt2-ygoYzd3|<1^7_Pj;`NF3%Ig#B zq1PwYTRq2m&IRVq>l5b=bH{0Mdu+WuVtKqivHV`2*mb>@uzI{cu{yo>Fn3;)*dB}9 zd+YV2JbG1rJ?y%ATRnPSo!nJ_?p%wz_A6c=tgk=v)HnI-r|Z^d_0)fL=0*KWU%30H zHQ3($Tbw(bJDfY5JDfY5JDfY5yW)D%dcDHA!@0w`!@0w`!@0w`!@0w`!@0w`!@0w` z!@0w`!?`QYUF*5Sxx=}`xx=}`xx=}`_GKRHeZT9bd93#X&0|yJG3P5%1ny7gH-^t0E9P$c|9|EPg{&L0kRovcNuP5cvtMcn%*VWtV(evu$ zuKKxaU);4{@%mtW{gJ1>$zMNRw?3<<{;M-D>R2An&bJDfY5 zJDj`XdeVBm!nwn_!@0w`!@0w`!@0w`!@0w`!@0w`!@0w`!@0w`E6!c(xx=}`xx=}` zxx=}`xx@D5_1Sa5>$B&D*C*B!uTQL3UY}SGy*{zt>N(bPE--gqpE!4zJFm~;_SkxR z#PWD;VEMg1vFmz$V)b}^Vs(1$VeY&parYB!@2%I9^5|9h^|0&eZT0ARb#hnzxs#u} z_A6c=tgk=v)HnI-r|Z^d_0)fL=0*KWU%30HHQ3($Tbw(bJDfY5JDfY5JDfY5yW)D% zdcDHA!@0w`!@0w`!@0w`!@0w`!@0w`!@0w`!@0w`!?`QYUF*5Sxx=}`xx=}`xx=}` z_T~Nd&OzRX?|kI_cC07fZ^wG&{dTN}-fzcx>pf(w=iXb!+e2J+ z8U-9~2ef^QAzR6!dUAI1~r~a!mFX~_V!recu!S?Ro;@sif;oRZe;oRZe z;oRZe71xv2>lMx&&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj&RuctTF)KM9nKxj z9nKxj9nKxLFP|Uox#07|*xr4980(484`aRZ`C+VwK0l20)@Nd|p8KpU=FaDbF?T*c zjJfmq;o?4n+IpWs#q#+4FqYrvhq3GW{4iFJ&j4d}`fM;(zt0R~dn|76t=E(C=vDdk zumT*(`_F6SIqGj#EdQ6b-gR8} zPJ6FdJ?oBNu{zH=d&TNM<-8T!V{v*_hq9nKxj9nKxj9nKxj9nKxj9nKxj9nKxjU2*PO&mGPk&K=Gj&K=Gj&K=oQv0uTQLpUY}TR^&IOt7nnP*PnFn3;)*dB}9d+YV2JbG1rJ?y%ATRnPSo!nJ_?p%wz_A6c=tgk=v)HnI- zr|Z^d_0)fL=0*KWU%30HHQ3($Tbw(bJDfY5JDfY5JDfY5yW)D%dcDHA!@0w`!@0w` z!@0w`!@0w`!@0w`!@0w`!@0w`!?`QYUF*5Sxx=}`xx=}`xx=}`_T^rEi(TILs9)Un zUGr;Z&pWNyb)R|7d*`_8KIo+@_L}*-|M%B(+-v5`&t9?D%qi!+XO8p!tk1rCX0L~H z|KnXVd!0Xw_t@k=9kDs;j`x)%Iem1Me&un%2S+0IRa73j&&$$Re6LI1J>22k;oRZe;oRZe;oRZe;oKFs_txtP&K=Gj z&K=GjRwoxYcQ|)AcQ|)AcQ|)AcQ|)AcQ|)Acg4ADJ$E>FICnUAICnUAICpsI3$K6T zhWYhr?{B#0iuL3R?|#V~*Q-DI{&6$w;TyjF;+ggKYZv|D%zD22179>VcV9gF4`$}> zkgpswGk4Sfi7?{dc-oO;{gH3_{h8&t-Hp$mS^mRb^?NhB?mPB*-puOxz+S&QvpSDH z<$uqt{&(JL#rAcxYY(5}_Fi01TCZ2-(ZllVZP(TF>fx?BxvPHe+Lw6ywZ1;cQ-9>I zZ?0QE)l;9(^%H?p0T9Ju`RH@0dq? z`zLHQ)~~zAjq5#g-7ZZ4(AT%4(AT%4(AT%4(AT%4(AT% z4(AT%4(AT%4(F~ocdh3R=MLu%=MLu%=MLu%FMWA0t~t|tam_Q{&uPx_eopg`_u`t1 zycgHJ!dx{#)z4|5hIFVV2)}n_bs?p4H>M(CYLaY4v;Ww0()UU+e3GJoQKZ`sTXzQ$6)r zo%LV+d0G03In5o;9nKxj9nKxj9nKxj9nM|x=FHrQ=MLu%=MLu%=MLu%=MLu%=MLu% z=MLu%=MLu%=MLwtcyng%#B+yphjWK>hjWK>hnK$m?y2Y9)zk0Py07}ZO!r&Am+3z2 zcU#?`{m!fVw%>(yKleMb?(=?k*8Sh_)Os$6_q?#a=ZHK#U*zw(koes?+bws^9O?+Lw6ywZ1;cQ-9>I zZ?0QE)l;94#oANE;`?$75>pIzy`?Xwo$&wXB^`@GLlbpQAHik=JNJuj^9IU-Nb7x{bcxNgrQ z_4J%lXU{M7_gu5Do_9W5Qrzb&TJQ4}hW2Z>h#%|>i5~0_9fna zt*;OA)F1ilo9ot3_0(r|)_?WqW$7#CGxEt?3O!3~Au)g;zbBA+>bBA+>bBA+>b633gRdOeuJDfY5JDfY5JDfY5 zJDfY5JDfY5JDfY5JDfY5JDj`Xy|0ox@!a9u;oRZe;oRZe;iWI!oN4dPGkVgTqgTy8 zde~f~x6Mm>-W9YsGjCSbv8Guzj@NWnltUa zxSq6Lugar`<=5M;tLN3jMRjsl{oJ)L@%C$deUPXA$Y0-Fw|=UpKC83-t3NMGUooe- z!@0w`!@0w`!@0w`!@0w`E8d)$JMrA%+~M5e+~M5e+~M5e+~M5e+~M5e+~M5e+~M5e z+!b%m%$<1daPDyKaPDyKaPIKZ*YtWBbLN|-zu9S?@pll-IsOi!`N!X|G#B|BmgXgY z!_pk(?@*er{C!Gum%m$S9usd)v%dLFp5{9FoA+F|IZ!>#hw5x@RDbiNeKlwLo1NnR zZl(49Zlyf__NV;*CaCNBTcPUlH$>IxZ;Pt`^yzPo+Lw6ywZ1;cQ-9>IZ?0QE)l;9< zS^w3am!+?m)7;_Q;oRZe;oRZe;oRZe;oKE(&di;7?r`pK?r`pK?r`pK?r`pK?r`pK z?r`pK?r`pK?r`pkH)rNfJa;&EICnUAICnUAcF-Rd-`}6MFY)$k zeSMIp{>We7T(^Fzr#`E*{;NMPOJ6akxx=}`xx=}`xx=}`xx=}`xhvlDE_dR&!@0w` z!@0w`!@0w`!@0w`!@0w`!@0w`!@0w`!?`Qo^DcMdxx=}`xx=}`xx=}`OJBJ2oxOLC z(38#=deyl@4?BSNWAlr^_`pK={zNW=PcLl{H31GW$Ns_ zrvA=x_SN~$-izx=>-DNUdRTtF?YeqiJzP{Lch%2b`x0-z*4GDl>W}>O&2{Uidg`+} z>%aQ*vh)>mnme33oI9L5oI9L5oI9L5oV((k?{X)eJDfY5JDfY5JDfY5JDfY5JDfY5 zJDfY5JDfY5JDj`Xo$qodo;#d7oI9L5oI9L5y!3^8KhxfuXY`~wN3WWH^su=|Z=09& zyg7=C<}2=+ySQr}6K_tlzWGg_<~sSC_guF*P(96u>TGUQfAge$HD}s;aXo3hUX@1= z%dfXxSI?`5i|XXA`nhXg;_cV^`XEpJk-xsVZv9kGeO71vSASlXzG6;uhjWK>hjWK> zhjWK>hjWK>SG+khcjCFjxx=}`xx=}`xx=}`xx=}`xx=}`xx=}`xx=}`xhvkBnLF{^ z;oRZe;oRZe;oRY+FEeM)J2Q6oRkL^ZTQhn0VY7PoXES{FZL@v%b2ESUd1r*~|IP?K z7sPvBSl@F*o}MrA_uO&ao=58GIi=2?U+V93Z||PQ3Gx^_`pK z={zNW=PcLl{H31GW$Ns_rvA=x_SN~$-izx=>-DNUdRTtF?YeqiJzP{Lch%2b`x0-z z*4GDl>W}>O&2{Uidg`+}>%aQ*vh)>mnme33oI9L5oI9L5oI9L5oV((k?{X)eJDfY5 zJDfY5JDfY5JDfY5JDfY5JDfY5JDfY5JDj`Xo$qodo;#d7oI9L5oI9L5y!7RF=*^iv zGtfNavjojKK4Z}Q^UkIx>I-)9oKuFon|kIyhvr_Vf8zt23h zFY)$keSMIp{>We7T(^Fzr#`E*{;NMPOJ6akxx=}`xx=}`xx=}`xx=}`xhvkBnLF{^ z;oRZe;oRZe;oRZe;oRZe;oRZe;oRZe;oRZe;oKE(&di;7?r`pK?r`pK?r`q#(id*d zwD;y2J!#I-tL7g)Y%bE<<|RFEj^d*Eio516?wZHMo71dsev_xUPX6XS*KH0|PxGNV zn;X^NJZWFenf6{>Pg<{6<uuN7^XlQEI=QQU?%J1l`?bD4$WwphuWznfKh;y8 z)mi`5pO>YtnA6Hqw1p7HWg6Ua1&za)QY1TKt$OP<9i3H)Atcnzwaq%U*hf8`uZSG z{gJ=Exo-VbPkmNr{a1fpmcC+6bBA+>bBA+>bBA+>bBA+>b631MGk4;-!@0w`!@0w` z!@0w`!@0w`!@0w`!@0w`!@0w`!?`QooS8fE+~M5e+~M5e+~M5er7zzh)tu?OY?^0$ zA4+qM??Y++@m)5}MZU|XdC7O#G)MV9n&vCtQ`6k#`)iuV#GBKsZ+?@fxlaD(J=bjx zR8RAvI-48S-#lqw&6x*H-#t{^_t&)E_t%uicL0^&cLQ}@-x*XrzDuY&eaBGs`|hFk zCEk9muMhInANlK>>()>8)Ms_pfA!~O=_}?mcQ|)AcQ|)AcQ|)AcQ|)Acg34Cb0?lV zoI9L5oI9L5oI9L5oI9L5oI9L5oI9L5oI9L5oV()9nYk0s9nKxj9nKxj9nKwI`ohhb z_TD_BC(Su})%>G}%|&|Kyrk#NQCu`%ao60%UGtcDbDH(dZ}K$P$=|%^y3K*=X+BhE zbEEp3C+({_)832gN$d5hJbGAuz3sYsUOik?CwJA)UHcMmzt-0WdFqe+_04tbr+VtM zI_tms^Ro06bDBGxJDfY5JDfY5JDfY5JDj`X&6&9q&mGPk&K=Gj&K=Gj&K=Gj&K=Gj z&K=Gj&K=Gj&K=HO@#f6jiRTXI4(AT%4(AT%4ljM-=1hBUp3#%$9KCA((Zl8gTR~iMLw`S?NB;Wey7f~%^;whjWK>hjWLQzRa9G@66cUSIyqtZ_VW0ht2BUpUv>yx6St5&&~YZ=baI{|2rd$ z=fV{4d0~Ce5qWyP$lr6vb$cGEr{|P9dw!|E=bC->yfb4LH+#3`RkkO)=%}+XLZ(p_2*^jE9NwJICnUAICnUAICnUA zICnUA#e3f6PCR!wcQ|)AcQ|)AcQ|)AcQ|)AcQ|)AcQ|)AcQ|)Acg1_&bBA+>bBA+>bBA+>b633cUGBtlhjWK> zhjWK>hjWK>hjWK>hjWK>hjWK>hjWK>hjUlF^Ih)5bBA+>bBA+>bBA+>m%jY%d2^<} zwQrvBH~7st{x-k)$KUKX7x`QM<|TjQ-yG#{|C_J;UjfZs{;z=MG4bX!>zm)?X|9vM zdCzs51J%=fsLtj_^*2x2S97MnwJ+{(@LTV1^ULFJ_RH^Y`Ma*a@vk0#`(K^@uYl_J ze+9HJ@%C$deUPXA$Y0-Fw|=UpKC83-t3NMGUooe-!@0w`!@0w`!@0w`!@0w`E8d)$ zJMrA%+~M5e+~M5e+~M5e+~M5e+~M5e+~M5e+~M5e+!b%m%$<1daPDyKaPDyKaPIKZ z7jDk9_vRTrY0lBB<{v$5F4EiPB|UGB;-dMAyXG$Ln#aVO)2wfPlc%{({^mW`Z4OjV z^PxJM8`a-DXfxd~xvPHe+Lw6ywZ1;cQ-9>IZ?0QE z)l;9UUt%Wojmkb8^`Ns!+smb>*|b`Zyc|;8{V{Wybix{(Z=!m6z_FweXnPE zdY#MP>)&GU3L7(^SzfGKk~oqKF5#i zKKkD_jCyvvbi=4~)9W{k`mcKRhOsa4e(tRA=T4q}?&R<1&UO2_Q%^s4>g?xE{r%i6 zeZ`#S4(AT%4(AT%4(AT%4(AT%u6RFpxf9PF&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj z&K=Gj&Ry|-?s6xdJDfY5JDfY5JDfYb^o2X$*?Z>*J?VU*SDicbu=9xCc23dr&M#ba zuHmlp4tJe{#5*5Z-?>Si&QtPt&T`$(U+U>xrq0f5>hBz9U!Cvly||vVUa!idhvnDX zuB+$O!$oy+SN+_zFY)$keSMIp{>We7T(^Fzr#`E*{;NMPOJ6akxx=}`xx=}`xx=}` zxx=}`xhvlJE_dR&!@0w`!@0w`!@0w`!@0w`!@0w`!@0w`!@0w`!?`Qo`7U?jxx=}` zxx=}`xx=}`OJCD`G|qP~JoD&rj@a*KN00Nx^A0&?oI76okz>Yr%Fo$u7&`EKbe<}`OWcQ|)AcQ|)AcQ|)AcQ|*& zJKyC_Ja;&EICnUAICnUAICnUAICnUAICnUAICnUAICnUA#XH~SPCR!wcQ|)AcQ|)A zcX;UwcfPat<{3R{&e5ypA3ba?(%a@GJ#UWUqWOxu<}U80>&>4N6K~G6zByB#=1lpU zGhMeiQ$5X@>TJ$be{-gNHD}s;aXo3hUX@1=%dfXxSI?`5i|XXA`nhXg;_cV^`XEpJ zk-xsVZv9kGeO71vSASlXzG6;uhjWK>hjWK>hjWK>hjWK>SG+khcjCFjxx=}`xx=}` zxx=}`xx=}`xx=}`xx=}`xx=}`xhvkBnLF{^;oRZe;oRZe;oRY+uWRpk=$JG2IOEVU z&+PEiL&u!6?%>15{PWBYA2#NqkKW?&F)!V;@8M&P+To>#kNN79a}FPK*D)6!KISp; z<}~Y@-{fholfQY-b(;g#(|oAT=0^25Puf>==IbvyWW+zX=OJVL1)n{5}hNxzE`LjrtFH)j?xl;?0@XH)qPzoGE{Ert3Cms;4bBA+>bBC9{aL+q?@4l)h-EZ}(`>-B%f7aXX+j`#p zoQv-B+;#uwZu*&@pLgOtFRbr5B2Uj3`FrlTZqFn2^qf*>&oA}&T(hs9clKUfPg<{6 z<uuN7^XlQEI=QQU?%J1l`?bD4$WwphuWznfKh;y8)mi`5pO>YtnA6o<~biUB5&K-K#c|>nJr|5a-7cM&2aMyWU?MK#r351dQ~1hEWh4%T|KWJE~=Be z>gTR~iMLw`S?NB;Wey7f~%^;wW}>O&2{Uidg`+}>%aQ*vh)>mnme33oI9L5oI9L5oI9L5oV()9nYk0s9nKxj z9nKxj9nKxj9nKxj9nKxj9nKxj9nKxj9nM|x=FHrQ=MLu%=MLu%=MLu%FMUm))x5mt z-KD>J;^o~}KX=c^Uf%uoh3|jl<=uzh_0>Hu@BaMRFFxq z^Pl_Py34!&@A2eym-k!{?|ET;&k=cgzR2Hm$8~!isi)_ZI(vSpzvr5L^}M_Ae$N^4 zQ@1^AtiSfe=Z`$^deYG&|LISE(YWqmFL=qQ=jFeD!l?7qN1Zh4zsFZk8v7D&zt-0W zdFqe+_04tbr+VtMI_tms^Ro06bDBGxJDfY5JDfY5JDfY5JDj`XJ@0ZSo;#d7oI9L5 zoI9MmdHtF@oI9L5oV$7bnme33oI9L5oI9Mm;yv$jC!RZ;JDfY5JDfY5yLtWE&l)~+ z#|!S;^X@<2@^26CzIyiVhd-kG?U(O$(IdJK-}IrY9?|{zt3Uq5Bf4*YexF-Evitdd zPu}T~-RGbGj(a|``~R2kb)QG}ToCVhVSUdLd3wIc-*d-xdmgE$=af2oeyP9b+Gloq z+kJc9P4SNupVnX2`YF$4<(cwdR{rU_mv!B#o=w#=)w!uUr}{Tl|Fo}7i+ycszt-0W zdFqe+_04tbr+VtMI_tms^Ro06^O!rFJDfY5JDfY5JDfY5JDj`X<9WB{PCR!wcQ|)A zcQ|)AcQ|)z@!8$l`q>@M9nKxj9nKxj9nKxjUGbiGxf9PF&K=Gj&K=Gj&K+L*!o9Cz z@15WEq;tJqb>7#*-Uraz-XGBO-Z$W`_Y=75eFpBPXYKsHig@o!Sl{~<^7KB2{Jp>7 zy1nnAp56~pXYZ4!zxPkL>wOh_FRmx8*Q@gAVfpp8>*{&+a8aGyRX=x&eQj#L*4GDl z>W}>O&2{Uidg`+}>%aQ*vh)?N`JLUZd7s_k+~M5e+~M5e+~M5e+!gPAmE4Kv4(AT% z4(AT%4(AT%ZY@5$TU$T7!@0w`!@0w`!@0w`!?`Qo`zpB;&mGPk&K=Gj&K=GjUi!k# znfBg1qbJQdde!`+hs{NL+q|Ub%~4!5Uvbym#a(lzcyp%p&6)BvXUgB4>AKCC>S@kY zXLF|dn=`p<&b0U9deVBmDvutPUvImvo>vbS)yZA;bGO*nruJ)neUPXA$Y0-Fw|=Up zKC83-t3NMGU-6pX+1;A=*&WUu&K=Gj&K=Gj&K=HO@#f6jiRTXI4(AT%4(AT%4(Dzy zKD%36KfA-Z!@0w`!@0w`!@0w`E8d)$JMrA%+~M5e+~M5e+~K7!XM~=2X6){(X7BE| zX7cXCX7%pRX87*gX8Z2vX8!K;&IsNAoe_F2i1)m(zUPQMJzwPSx#PM$kJQt1N}WBw z)ZcT>zIxu7v5T9%TW=;Wk6FF^X85jawyz#De|0(|RKGJq`x0-z*4GDl>W}>O&2{Ui zdg`+}>%aQ*vh)>mnme33oI9L5oI9L5oI9L5oV(&Z?{X)eJDfY5JDfY5JDj_D{hB+R zJDfY5yLtVZJDfY5JDfY5JDj`XJ@0ZSo;#d7oI9L5oI9MmdHveYTHN{0-aAL=N#_f_ z>fE7+ok#SxbBdmKe&M2X4R@V)xa%Aw-ucM-&Q0=ko|3yYwlM3x$%DH?q^*w-Zy*HT|PP9 zPy5qv{@?LF+b%!P(4&A-|--rsxS`!|jE{luHo ztZ#mkr@2o4<~`SK4pdL`p*ouz)!#h%t~-2gyq|gBw|rs5cf9qN#`=%%ea*_Byx+B>{%cRXcI->MIn(;)OnI6!MS9!3 zr0301Tr^*C*WATj^O$&Zn)S_Z@-)}U-@NC#&4KD^K2&FOqxzdC?W;M{-izx=>-DNU zdRTtF?YeqiJzP{Lch%2b`x0-z*4GDl>W}>O&2{Uidg`+}>%aQ*vh)>mnme33oI9L5 zoI9L5oI9L5oV()9nYk0s9nKxj9nKxj9nKxj9nKxj9nKxj9nKxj9nKxj9nM|x=FHrQ z=MLu%=MLu%=MLu%FMUnlg*Uzr=*BPHZG7*{@qcoU@qIL(U3ahXJvD!P-o3~7*F5BF z_Zi=7v)i}+*ZBYcH(Yez@x1_h?zHpxzJRYjX6Nxe0^+@Ht?%_LPp@~l8bq{#N9Y#I3eCh2+ zo%?Qc`%(XeU)^EsOT3>u>-)Krr=L6d`?+)7e(u!M&z(B^xl?~XcS~O}r@6zq!@0w` z!@0w`!@0w`!?`Qo&t2}sbBA+>bBA+>bBA+>bBA+>bBA+>bBA+>bBA+>bBA+Ryq~+= ziRTXI4(AT%4(AT%4ljM-&I|V5IYLi5U+7im4n6EVqPLw>^t|&67oBUk>%7BV=OFRU zN7i?4lBe^O{GGF0xAT{JI+v-l^P2iQ$JtlsJ9{s#C#~13^5|jt^|tHkdG&Bno!nJF zckN5O{aRlia73j&&$$R%xUg$?r`pK?r`pK?r`pK?r`pkcfQM= zcpOQ$&(`&wN2X`)`pzlSvv_^ym+2Y3zH`m=Okdx5 zXL_cu@BMc1&Ue;#zLTf(o&4i`H(j^$oq9Uosk8H)`WNTB_5B`UnqfwKnr+7VY33Pu zrdep@pJt?S-D!3j^-MF>sB@aZM*Y(aHufdneyy($^3)&s>znJ=PxaJib=H6N=Vj?D z<}`OWcQ|)AcQ|)AcQ|)AcQ|*&JKyC_Ja;&E*mb$Xxx=}`xx@Cw9nKxj9nKxj9nKxj z9nKxj9nM|x&Ud*J&mGPk&K=Gj&K=GjUi!kF@9e#KMo*e^^s4zs51Whhws}da#lQzxwmC^c8cOJDfY5JDfY5JDfY5 zJDfY5yW-86xf9PF&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj&Ry~5%-o6R4(AT% z4(AT%4(ARpeNFF0uW!zr-t%1FJTtu)y1qGQdXIE{^Uw6&>H6lP={?o;%}djJt?Qek zruSgiH(yQf*{*Nyn%=Wr-#jMXoMwIVn>@{R@;C3fZgZe|nh(|4+^GKMN&9NfoZh1z z@#($mv3`0_d*qqk>mK>1_rS+>r}xH3J=1&Uqt59)_EG=z9{bprc>A@!KFCvlg@TY z{+?@IlRfY3y||vVUa!idhvnDXuB+$O!$oy+SN+_zFY)$keSMIp{>We7T(^Fzr#`E* z{;NMP_LZ-g$K2uE;oQxx*WBUU;oRZe;oRZe74LbMJMrA%+~M5e+~M5e+|BFP+~M5e z+~M5K>(|`j+~M5e+~M5e+!gP6mpk#?;oRZe;oRZe;oQyZ*WAUO@9e#Egr0Q1(5ucJ zdf0hHZ#$>xdFK}{I@fU5d562scjBGztnYj$Pv<-NJKwo(=R5UuzEfxCJN5t1`R-}s zd}r^)^`!NBRUSPozutCTJ+B@vs*}6w=dOK;w_oe)gFN*|{`%&+^;13dS)KJ?{dw`T zmamw{+~M5e+|91n+~M5e+~M5e+~M36?|hd#@!a9u;oRZe;oRZe&FiN?r`pK?r`pK?r`qr^=s}{{JAk_nz5T_%-+p8X7c7A zvwCxp8NPYRY~LJZ=5M}oMriJGMrh6yZ_c#7Ia8kIO!=ELUAH+?JWe7T(^Fzr#`E* z{;NMP&Ip|gVjgpcbBA+>bBA+>bBA+>bBA+Ryg4&>;<>}Q!@0w`!@0w`!}jHjfOCg) zhjWK>hjWK>hjWK>hjUlFIWu?Sxx=}`xx=}`xx=}`OJ9F~oAbu+?+*LPdE@s)clpfu zS;byXLFmPdRn?|0mfBf8$ zf9rMUj_bba?dObop8xoBMxC$R?wnEoB|m%P*q3;7ruEI4@-%14-<;{X&6(bBA+>bBA+>bBA+>b631MGk4;-!@0w`!@0w`!@0w`!@0w`!@0w` z!@0w`!@0w`!?`QooS8fE+~M5e+~M5e+~M5er7zsvV(-l}deWSuSIs|q*j%Ky%}aXT z9K}WR6?e^D+%=DhH>X+O{3cIxo&3#vuG<`_p5{Y!HaDujdD6c6J%YU#*OS)kReAKV z{CeAU^}Kqxs7~&xpS$)Y-hQpG5AxI>`RkkO)=%}+XLZ(p_2*^jE9NwJICnUAICnUA zICnUAICnUA#hWv8C!RZ;JDfY5JDfY5JDfY5JDfY5JDfY5JDfY5JDfY5yW-86xf9PF z&K=Gj&K=Gj&K+L*dhiY(9KSdJ!he2n{C@V&uKdvWz3ry+KRkY)d&dJmGJel{{m(x# ze*b&S%Pt$g7k=$mE*rlue$kGb#_y3IcmGY}_sinVY1TKt$I0+x`~Liru`luFOzWF7ht+6F&^+*2t=DPJ$J@r|g^bBA+>bBA+>m%gU6-k39= zc*Ez$JhRQ`uNrgCZ(Z>DG5?%(&=ThS zc(*T(c}%=H&HCmyd7A6wZ{Bm==0No{AF8vtQT@%6_SKwu%ip?k#P@&JXUF<`pZS@Q z=aW}lG4lU-*DJ<#U-GU`k9wZE@25wdFTBmCNBwX9<)_BJ#M`g+&6)BvXUgB4>AKCC z>S@kYXLF|dn=_ZbVor01bBA+>bBA+>bBA+>bBA+Ryg4&>;<>}Q!@0w`!@0w`!@0w` z!@0w`!@0w`!@0w`!@0w`E8d)$JMrA%+~M5e+~M5e+~K7!-1E-fyRYg=_glT{KCFk` zpY^u;ww`xC=c4;OcisQF>$xD_^TPU`Bl7fok-z7T>-IcSPtPfJ_WV+R&o%q%d1vp% z^`!NBRUSPozutCTJ+B@vs*}6w=dOK;w_oe)gFN*|{`%&+^;13dS)KJ?{drmXiaE_4 z&K=Gj&K=Gj&K=Gj&K=HO@t$|N6VDya9nKxj9nKxj9nKxj9nKxj9nKxj9nKxj9nKxj zUGbiGxf9PF&K=Gj&K=Gj&K+L*!o4qT@0}y`r1OPdb?(r^&Leu;IYrMqzi`pHhP%!? z-1UCDc;`FoJKxFE`A+`Mcdpy{PCcFP)Y4>s5L5u>5-4b@jY@ zxTsF>()>8)Ms_pfA!~O=_}?mcQ|)AcQ|)AcQ|)AcQ|)A zcf~v3C4R7`w3`Nyo@Tx5oCUNYM^N16GXubdH@yPOev-%q?b)B5I2 zd73ljZ_aex=1lc8XR5O~Q~k}E_SKwe#x8F5ZoQejJZAOso8h~z*}i(r{MG4Z#A_tpDoI%hFfOY3^|DaPDyKaPDyKaPDyKaPEpXXXZ{k zcQ|)AcQ|)AcQ|)AcQ|)AcQ|)AcQ|)AcQ|)AcQ|*&n=^AKo;#d7oI9L5oI9L5y!7>? z?N1%gyYKz@)Nx<^t52Oa?zdN+`^s@2zW*~$ANS{9`|0W9zJ2luXN>##+yD8Dai2eZ zhcn0h|G@j6Ii3sRJuj^9IU-Nb7x{bcxNgrQ_4J%lXU{M7_gu5Do_Fur<&+V>{wXJq z^{3zTMp2YKp`{PoRs>!*6^ zvpVa)`t!2%6?2+9oI9L5oI9L5oI9L5oI9Mm;+^kuC!RZ;JDfY5JDfY5JDfY5JDfY5 zJDfY5JDfY5yLru;JDj`Xo$qodp1XO?nme33oI9L5oIAYqg_|?&y?I7YnsfB3`9}|% zi}bd6Nza?3xM;rOuDOf5<}vZ+H0zt+bBA+>bBA+>bBA+>bBA+>bBA+>bBA*`uUT`4 zb631MGk4;-o7b$l!@0w`!@0w`!%JU(f1C5hoar+I%`-kr(46Bl2F*V{d(d3uGYQR0 zKC93iiiO#5oi^qGO; zK1~HzIZ~Ghn?&tpYzx%xZE1>(o|0|&9f_Tph>wAvK)AL3Co;$AF^GH2Cr_|Z=OZ`39 z?5pRUzqK#!Z}401Z}ZFJZ}!XYZ~42fzwxggfBRpZ{;z=Q_kRVnFY)$keSMIp{>We7 zT(^Fzr#`E*{;NMPOJ6akxx=}`xx=}`xx=}`xx=}`xhvlDE_dR&!@0w`!@0w`!@0w` z!@0w`!@0w`!@0w`!@0w`!?`Qo^DcMdxx=}`xx=}`xx=}`OJCF9l8oowb^r48abG?B z&z~{ww;$f^S>rx@)P>I;_vd?l>pA1Tz2kQe9QX6X-uc{dpTEc54;uIXkMDiZcrJ+d zys*CKh&(-CB7({oClJ-^i7bIrbb-W{|5{v-aMZ`^OJfAcS&H1d4!^nFME z-+ufP$932L&J#vGKmDV9MxA?Xx6i2mPrteM*q3hjWK>hjWK>hjUlF=Uwi^bBA+>bBA+>bBA+>bBA+>bBA+> zbBA+>bBA+>bBA+Ryyso+#B+yphjWK>hjWK>hnK!^@2l8*=XX8nT(4K1_w}&%0ra-_ z2lTx64Y=t21nzpDfxF&+5bu2n>wCXKp5DihzxOv>xA#5N)B7Rn?0pjT_x_1}^}dR| z7uS>4>s5L5u>5-4b@jY@xTsF>()>8)Ms_pfA!~O=_}?m zcQ|)AcQ|)AcQ|)AcQ|)Acg1^OC3oVv!@0w`!@0w`!@0w`!@0w`!@0w`!@0w`!@0w` z!?`Qo`zpB;&mGPk&K=Gj&K=GjUi!k#nfBg1qbJQdde!`+hs{NL+q|Ub%~4!5Uvbym z#a;85cypTd&2REF*U8_!=eo^->S;byXLFq+bNsyupFe!cCwdR{$T zR3~@U&t3ZxZ@<>p2YKp`{PoRs>!*6^vpVa)`t!2%6?2+9oI9L5oI9L5oI9L5oI9Mm z;?0@46VDya9nKxj9nKxj9nKxj9nKxj9nKxj9nKxj9nKxjUGe73+==H7=MLu%=MLu% z=MFD@J$Q$QY`MiQ?=vSo`rB{ab4&Bgw!gjSmgby)|I~xGH2-|;4<5Xwx#-zppd#hmCrE_k@RyIzRsx z4;%GwI{#r~U*hf8`uZSG{gJ=Exo-VbPkmNr{a1fpmcC+6bBA+>bBA+>bBA+>bBA+> zb631MGk4;-!@0w`!@0w`!@0w`!@0w`!@0w`!@0w`!@0w`!?`QooS8fE+~M5e+~M5e z+~M5erLPy={&8D+-reKE$8PDqy4N0$-O~Mb*DLng(tY@*7w)yC`}6DWzSoxS+t2vd z$870-zSnynv!(m|Re$!FE#3dGJN+?RdM=3fys*CKh&(-CB7({oClJ-^i7 zbIrbb-fcPUaU*`-PaZecUwYu@Dmw5ZNzCOrPf8?)ku3JCVQ=ipY|J9$DrLUON+~M5e+~M5e+~M5e+~M5e+!gP6 zmpk#?;oRZe;oRZe;oRZe;oRZe;oRZe;oRZe;oRZe;oKGPd6zr!+~M5e+~M5e+~M5e zr7zt1&fYsm=t<`bz3SYdhn+|CwsVS}cYfiba}9T$cev{uB;NVR`p!-Abe@vGbC&CN z{!&lpGIe%dQ-9|;`|5mW@5S|`^?FqvJuJW8c3nNM9xkeryXxnzeTlbU>+6F&^+*2t z=DPJ$J@r|g^AKCC>S@kYXLF|dn=|dJIn&;Y z>q+bNsyupFe!cCwdR{$TR3~@U&t3ZxZ@<>p2YKp`{PoRs>!*6^vpVa)`t!2%6?2+9 zoI9L5oI9L5oI9L5oI9Mm;?0@46VDya9nKxj9nKxj9nKxj9nKxj9nKxj9nKxj9nKxj zUGe73+==H7=MLu%=MLu%=MFD@nK^sjnX$XCn!UTZ#A_tpDoI%hFfOY3^|DaPDyK zaPDyKaPDyKaPErtyvv<JXzoqct_v-je9(t5orj~#+>uPPp%vD&soQ=8*|ZJ@49ZxOJBQY=P^fJ@$Q|+e09ic zb{=!rai{G(<}vZ+H0zt+A@!KFCvlrYWop|nW?r`pK?r`pK?r`pK?r`pK?r`pK?r`pK?r`pK z?us{O=1x3!ICnUAICnUAICpsIYkIwmpSvsHe$?>$lZPBNynp4&BggCEea9U+UMG9q z`^fS7+4`GDjMvpqE;(Yn-cI?8BgX6SoU@J?uTSw_x7PQ1mZ#Ub{Js8Nx1S63^z)+5 zevZ`N&zF7mbN9kCj~?;;es=U&|GYzv8F^m&kz+>w|Jv@@aotBe`Pfm2 z$Bz0he%rBQU*i4TS>Ml{JpJ6s-_M=v_H(D6e(u!S&z<`Fxm)^*In5o;9nKxj9nKxj z9nKxj9nM|xe(rK7o;#d7oI9L5oI9L5oI9L5oI9L5oI9L5oI9L5oI9Mm;{Dv^PCR!w zcQ|)AcQ|)AcX;UwcfPat&JlXj`9iNccj#f~5xwo4qUW7oxaeHNUFRL{ItPh&KC-@Z zlRTZLg2BaxocnI z?brJHAW!{~zrML{{ZvnVR%iWJe_ocpVor01bBA+>bBA+>bBA+>bBA+Ryz^b|#B+yp zhjWK>hjWK>hjWK>hjWK>hjWK>hjWK>hjWK>SG@CG?!bBA+>bBC9{uD#=- z<9zq}iw+s*h!5_0$T(kI@Y#dMxnskN4<6@{ZSQsPIH!E#>j#bV%ZJ{7&^XuZbM`^w zymQE_4%*WD?c$y9tnYj$Pv<-NJKwo(=R5UuzEfxCJN0+Iv#-u~dz^9Ti0|;zL&y4c z2Ol=_JoCecjruVor01bBA+>bBA+>bBA+>bBA+Ryz^b|#B+yphjWK>hjWK> zhjWK>hjWK>hjWK>hjWK>hjWK>SG@CG?!bBA+>bBC9{aOXRFZ=TVU<{Z6h z{?WtcBE4;1((~phE}E~nYwqH1`k9|UlP2DrX?=61Jk6Q%H)pzTbEbNlGu7Fgss83n z`)ba#_u_iedc7)-9+qEkyRM#B4;R(RUG;Op8BlL`mg@H zEPchC<__l$=MLu%=MLu%=MLu%=dO5jX70puhjWK>hjWK>hjWK>hjWK>hjWK>hjWK> zhjWK>hjUlFIWu?Sxx=}`xx=}`xx=}`OJCDxHOHKJ(A%Cm=9!m2_^D&gdBJD)AM?+{ z|8V~?7k&C3`~T0p^tGpqIqK!_d&-!vwtwAI#@u!9GoLc%G4bX!>zm(RJLPGvlfQY- zb(;g#(|oAT=0^25Puf>=<}Y6Pv=RT(e>`oh|Iu@wKJx7Jp{I}hXa4#D`S~k)B5I2d73ljZ_aex=1lc8XR5O~Q~k}EOJ6akxx=}` zxx=}`xx;#{Hk>=0JDj`X&6&9q&mGPk&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj&K=HO z@#f6jiRTXI4(AT%4(AT%4ljM-o_F@%eN|7o-|AKOVLj~rthe2_^}PEz7v1N%>;BJO z&js3>uGv@5J9{s#C#~13^5|jt^|tHkdG&Bn zo!nJFckN5O{aRlia73j&&$$R%xUg$?r`pK?r`pK?r`pK?r`pk z_q@xUcUs5WQJvgXKX>g*y!~2VALOY& z^4B-lt)J?t&+4rI>d(v4SIlYdaPDyKaPDyKaPDyKaPDyKig&)top|nW?r`pK?r`pK z?r`pK?r`pK?r`pK?r`pK?r`pK?uvK5%bj@caPDyKaPDyKaPIKZmzlHoGtJn|GiLAR z95Z?Ik6FFB$PC}SWVUaPGV?cIIU_W8IV1GGpLlbo_05^`G-t}+oawsFnd)iIRA+Oh z`kOQDt2xt*UEJ*5dNX->%Fc?_apHL1ZFlhrf9Odg&nGWCY2<(Ctu~J9 zZrE?*sOOBAZya^r@TQHU{%>5gaqLUH=biOE@8s!uCx6d7*X?}Q!@0w`!@0w`!@0w`!@0w`!@0w`!@0w` z!@0w`E8g=icjCFjxx=}`xx=}`xx-6exbvO8caG4L&KG*sxkC>-kLYdZ6g}_!!bRsA z?mF*q*EvYM^O5zPo8;*{C4c8E*X{hJp3Y_J?7XJ_&T;nD`Oe;p>q+bNsyupFe!cCw zdR{$TR3~@U&t3ZxZ@<>p2YKp`{PoRs>!*6^vpVa)`t!2%6?2+9oI9L5oI9L5oI9L5 zoI9Mm;+^kuC!RZ;JDfY5JDfY5JDfY5JDfY5JDfY5JDfY5JDfY5yW*YiawncUoI9L5 zoI9L5oIAYqg_|?&y?I7YnsfB3`9}|%i}bd6Nza?3xM;rOuDOf5<}vZ+H0zt+TJ$be{-gNHD~(FKyjZXXuZ!El*eZe%Ku-}=SjM*&ni@p&oES{&pcGW&pfm* z@%C$deUPXA$Y0-Fw|=UpKC83-t3NMGUooe-!@0w`!@0w`!@0w`!@0w`E8d)$JMrA% z+~M5e+~M5e+~M5e+~M5e+~M5e+~M5e+~M5e+!b%m%$<1daPDyKaPDyKaPIKZ*L0sA zbLKDKe6umn+;#VxjX7uAf7)uyKi3?&)tHNpz4KOMUOM!BH*Ic?diee~ZEn6g@D4X^ zZtgn$reAHIu08+WT)a8W`sO!zn(O3m-gDjNK=m{qsii%%!iG)7;_Q;oRZe;oRZe;oRZe;oKE(&di;7?r`pK?r`pK z?r`pK?r`pK?r`pK?r`pK?r`pK?r`pkH)rNfJa;&EICnUAICnUAc- z=vDKN9yS;0ZS#_zH%D>Ne8pXJ7kAV3#?M`In)S_Z@-)}U-@NC#&4KD^K2&FOqxzdC z?W;M{-izx=>-DNUdRTtF?YeqiJzP{Lch%2b`x0-z*4GDl>W}>O&2{Uidg`+}>%aQ* zvh)>mnme33oI9L5oI9L5oI9L5oV()9nYk0s9nKxj9nKxj9nKxj9nKxj9nKxj9nKxj z9nKxj9nM|x=FHrQ=MLu%=MLu%=MLu%FMZv8$M0|M_jiB1$M-fj&-~+azPq_O=bW>y z+uZ!~=qtaoxw+`~9`K#b%}d{X&$l->M}6$c-`?DO^{v}|dvkNw?QXnwbMu&ZbDH(d zZ}K$P$=|%^y3K*=X+BhEbEEp3C+({_bMw!?KjIs&{=ry(@!Nhl^8D(MAC3Ii-1wt$ z-DjQr<5ADXZ~S=F`P|>Ue$>DF1Fs+Z5^ulO*9Up(kNow`b?c{k>a#lQzxwmC^c8cO zJDfY5JDfY5JDfY5JDfY5yW-86xf9PF&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj&K=Gj z&Ry~5%-o6R4(AT%4(AT%4(ARpec|5EwD;y2J!#I-tL7g)Y%bE<<|RFEj^d*Eio516 z?wT{jn=`F%&XlJ)Q~u^m*KN*JPjjX^n={qloM~Upnf6{>PyU;|dw=>jtI9iXqEU&> zq1B<%Xg6Ylh$5&hYP9<+h#)972tgDPYK)Et9Gy|)5e*`T=vYR~2nInx84u;yw2bjU zf5BvQ3J=IZ(WoI3Mi6yCpW>$>i}_P+1ubML$U zv?>k_i%;9erFndK5l`O5pLgY@y?pgg2XWFz{B$#Jdg7DLc&0!8`Et>(Fi-Oi&O12o z;JkzL4$eC`@8Gy)yo2)&&O12o;JkzL z4$iyU+h^vT_Pm4h4$eC`@8G5e_!DbTe*x;*-vJra%7qa?!6aPxB7WJ2>y)yo2)&&O12o;JkzLuJ-ns zd8a+^;JkzL4$eC`@8Gy)yo2)&&b!*%XXc&uyo2)&&O12o z;JkzL4!-CY+MBjDx3sDb)3EwX+v+yWtLMC^&hxJN&%4$I?X4I3w~mO@`XYYo zj&WO$@M)dGv-J!A)-`#x-pRdon$(|G#i3#GY1_Coj}I^6$-DUTuDrCDum0&EPWp(S zZpKYde9{@u^v6G6F8USbY2Lwk2j?A}cW~apc?ahmoOf{E)!urSciQs~&O12o;JkzL z4$eC`@8Gy)ysN$SF7LGG9h`S?-obeX=N+7P@I}Ai?(gK@ zeFROqzo1q39W?BIgtpzM(7gK>UUXl>yY6>**ZrOL?(g*P{!X0k@5Jx^&bZy*;nV#c zp55Q!-~FAuy1$cq?KG)Bt%^g#;?uTqX&xV5#FKaN=UsVeFJJxBL7emvKi!O*p7^9Q zp6QQ&zFhPx%+tJs^A65CIPc)RgYyo~J2>y)ysN$YyS&q$cW~apc?ahmoOf{E!FdPg z9h`S?-obeX=N+7PaNfar2j^Yw-QVS%_Pm4h4$eC`@8G+GpBh*KY4!e|z%c*sB-c9=>ty?c-z5A5ZrP@pq35OOkxZZ=acW+Vc+1J2>y) zyo2)&&O12o;JkzL4$eC`@8Gy)i+(-r zj(6Vwo8SL=ciR8YKK8zM+W*@=@D+F5|L4B%7vFLJ&-+8y+;RW^`$fNb)&5`ju|Is( z{=fJw-+I;lANd_mxoZEvtiAO@|JD(4T3^I(-7#+K5k9R`c(#7w-?}ER*1Okz|@mueV+j@sj>m8o0clfv7UGyu=)4YT84$eC`@8Gy)yo2)&&O12o z;ER62-QUT*`v{tJe?hD6J80Pb2yMGhp?UW&yy(7$cir#suKOVE-5=@SeUmudPl?}s zmT|lP!l(N(JiA}Rzxz0Ob$=)K+G$dMS`~+e#iwoK(mX!Ah$rvj&%5%{UcUOLgE;9U ze!3YqJ@H9rJkuZle7WdXn5TIM=N+7PaNfar2j?A}cW~apc~^V)cX_8h@8Gy)yo2)&&O12o;JkzL4$iyUyT8jj?Rf|19h`S?-obeX=N){}FSvcC z+}qF4q1N#Y#3!Bc zOn?0I<)U9@c=_L=y%&y-jDOureZ-ERr%?>7d;@!Nyq`%OaQ`mI8I{DvW(e)AB2zj-Jx?d7X~ zI*5}#;-{N&(-WU`#xwo#&zFmSg?XBHaNfar2j?A}cW~apc?ahmoOiXi&&)gRc?ahm zoOf{E!FdPg9h`S?-obeX=N+7PaNfar2j?A}cW~a--aa$$wC5e1cW~apc?ahmoOkd= zznrDndgtuW>gp>${DZgNI%~8#>c6v3XYBJ_MSJUo z{;eb8w7!Vnx?|kdBYaw?@NE6UzjaMst#{52t=*ZT^>@~2ahyR~d}ot3t}{#H<1Ev7 zI{P&K&OR+K?d7X~I*5}#;-{N&(-WU`#s{Vy&pSBp;JkzL4$eC`@8Gy)yo2+u_SU<+)1G&5 z-obeX=N+7PaNfZe{hDu`?|S!T&wszItIxXM`)$4b`d_%)*5OAy>26z}-*~sXZQXv+ zZ(XzX{5yZ-nyvHq__k}d{(sC`FhiB^@{;hWx{R;Cm@8GxZ zZ@tSq?Rf|19h`S?-obeX=N+7PaNfar2j?A}cW~apc?ahmoOf{E)!urSciQs~&O12o z;JkzL4$eFHqF->&Rpj3NJ59Q;r&ag+H0(J5ZF@dI^PU^p27Odj6oj=Mwt& zyh5CwV~F4L4deFQ1D~FU;MsE${Cj>Pub!*Oy>^<^pH{`8Vex6(xHOLsFXG9&`17v3 zw3n~`=^#$}h@Wo8O;3E%8PD{`KVL5T73OK)!FdPg9h`S?-obeX=N+7PaNgD4bCtZ) zo_BEG!FdPg9h`S?-obeX=N+7PaNfar2j?A}cW~apc?aiR?LAk?JMDP~=N+7PaNfar z2j?Ap(J#1trrg`l(4>71t=j+4uzeA2+b_|)eH1U+U-7Pe7w_7SX>XsVfBQFa+SiHS ze$Tk=1Mz8ph-dpo{M%2;t9_>2Yo|&5X;mB=7N53_OY`{fBA&d9Kkv#*d->|04&tPb z_~~Zc^u#Bf@l1dG^W~ynVV>q4oOf{E!FdPg9h`S?-obeX=UwgXGxJV+-obeX=N+7P zaNfar2j?A}cW~apc?ahmoOf{E!FdPg9h`Tyx6jNw?Rf|19h`S?-obeX=N){}ufh9! zm2Z03-S&48clgeKu)mkM<#yGDD%#s;>fb(7oc5XGx6d?g`%HY=XX4pD6aNeQ%>BK}JAUojZU1Ng z)7`iKtL}A=jq}f+_kkP#qkrcg?zs2)-G8)vzVZj|xjgTG%?B<2*FWHcHZSe%Gxcwu zDNg%L@!Mw_w|yo)?KAOgpNap4edhX=cRbBIIPc)RgYyo~J2>y)yo2)&&b!*%XXc&u zyo2)&&O12o;JkzL4wjdD1UT>Dyo2)&&O12o;JkzL4$eC`?`m(KnRnXr4$eC`@8Gy)yo2)&&O12o;JkzL4$iyU+h^vT_Pm4h4$eC` z@8Gy)yo2)&&O12oYHy#JciQs~&O12o;JkzL4$eFHqF-?P zOu4t8p-KB3TDAY7Vf!N5wqK%o`zT(tzv5l{F5a~t)80N!|MqXwSNlx4*G`lA)2cW$EIw@;m*(-|MLc;If8Lds_VU#~9mGi=@zc$?>4{G| zy)yo2)&&b!*%XXc&uyo2)&&O12o;JkzL4$eC` z@8GxZZ=acW+Vc+1J2>y)yo2)&&O7*`U-Mhd%l$6;!@lK} zm)pk>UripzxUU+{jPWX z_uKy!5B}|qbMO28$BqA-m%L%e{pQPWTt4q}4{G|y)yo2)&&b!*%XXc&uyo2)&&O12o z;JkzL4$eC`@8GxZZ=acW+Vc+1J2>y)yo2)&&O7*`U!QW- zQ+K`l(R+W>*401$w5M#nefr;iy)yo2)&&O12o;JkzL4$eC`@8G=M3NW#s}~72kotQ`nTSR(|RX<>z#31@9=58!?X1c|J&EQNA7c#xBTX( zZ~GI!{EUtN0l)j$9rv!k|C!6@2|xT<%k%EnJ#P8G;=zyGytKF8 z>EC)MPV1fct#`(4y~8J+@oc@r|MvCncE9qDr+EkG9h`S?-obeX=N+7PaNfarS9|MS z-f7P}IPc)RgYyo~J2>xPdG%Z+@3iL~oOf{E!FdPg9h`S?-obfSd+S}^Y0o=2@8GkYM&|h+G$dMS`~+e#iwoK(mX!Ah$rvj&%5%{UcUOLgE;9U ze!3YqJ@H9rJkuZle7WdXn5TIM=N+7PaNfar2j?A}cW~apc~^V;%)HZ{cW~apc?ahm zoOf{E!FdPg9h`S?-obeX=N+7PaNfar2j^Yw?KAUEd)~o$2j?A}cW~apc?Vzg>u2xu zyxnJhzjlg6uioc{%l}pPdg11!y?v(s?K8z` zpDBL(OyjoC#HW2Gp6xU7Z=ZS5uP{&Z4$eC`@8Gy)yo2)&&O12o;JkzL4$eC`@8Gqr*#U?)-U{9*W}fD_iKOpliU6; zU;R_t|JLXK^u~GL&-|H<|HpsvGdu2+zW$}l=iC3oOPA-D-SyVx|DX@Kb@S5RdZ&Nu zoj9#`;y)yo2)&&O12o;JkzL4$eC`@8Gi$mdwbP{jv?>k_i%;9erFndK5l`O5pLgY@y?pgg2XWFz z{B$#Jdg7DLc&0!8`Et>(Fi-Oi&O12o;JkzL4$eC`@8Gy)yo2)&&O7*`U+{b0 z`{o;+c_R1rGc;+RL#y^bG;Ci)+xAN|Zy&{r_E)@X-^IKBf2X~DrvB|S#c7`@e)~-0 zw$H?;eI}mmGx2YqDX;dKa<82x^`}*FXjpvOHZINM!;5(GF8;hLFYV>4e>#YhKH{gF zanlo@bjCCN@z0lweua6OcW~apc?ahmoOf{E!FdPg9h`Tyx6jNw?Rf|19h`S?-obeX z=N+7PaNfar2j?A}cW~apc?ahmoOf{E)!sfc@3iL~oOf{E!FdPg9h`UYMZfGhTkq_# ztE=|j)mwY=>ae|f_1PZ2x@~V?J-6qt&bvpb{<}wLUC`cop?~X$IIS<@x9%9X^$4HV zDLh-h@NZp{SL>ZUcJ21w^|vQ4j=g&E?cp2O-abC|{PA>;5P$aw<)yuR^-l+J(ntJs zGj4j~lg@aiKmPf0(XTL1^A65CIPc)RgYyo~J2>y)yo2+u_SU<+)1G&5-obeX=N+7P zaNfar2j?A}cW~apc?ahmoOf{E!FdPgUG1%Rd8a+^;JkzL4$eC`@8GwbrKJ@?bz{hj{Z--*-xo%r3~8Mpg8e7e8G zv->;zyT6lH_jhuyohJ3CRdHxoeA+fH&Evz1c=9g(yelv5<*R=>h?73zr<-xp6Q6X( zGyU<;my3Rdd75`{-obeX=N+7PaNfar2j?A}ceQtamv`Fp4$eC`@8Gy)yo2)&&O12o;JmB7`@6i;o_BEG!FdPg9h`S?-oY3B@;~(UnSL|Se#UPJ z+UNLwSNlxA8K~WF3F_}R2F3B)gW~&5LgV_aLVWy&A)bEo5P!dUC@<~h ztA9F(lRo0N&opj&;*-vJra%7qa?!6aPxB7WJ2>y)yo2)&&O12oPM_PngY&NT_L+I7 zJ?~DR+q{GG4$eC`@8Gy)yo2)&&b!*%XXc&uyo2)&&O12o z;JkzL4!-CY+&)w8?PqAxK8IHAe`wggh2Vy`6lM%@E$i#-M=*7 z%DmM6YQC*`seRXcTXV*~a=wc8_G$XJe-o#Do%rqdjN3jCpZ14%wr|A0{iM9wXU?}o zw|%}by8Y+dqZ?>8UZ1)4&Ut#Y%4?eBHJsOQUf2F#a-LRWjn$e6w?Wr_Ve0GiUC!Ceoxe5pGR{TNB~dM7T8(=GQy#`>yErU&DRh)Wvr` zADip8XDqJap0U6^V}X0d0{4ss?iow%)x(~#Xzv*d+%p!qXDo2fSm2(qz&&Gu`PKcM zXG+~ic-GYYg=bLRcX&3{{fK8)-KTh#)%}ZST;137EZSH-i-xs#f24o+P2zMvC4To= z#_j$KpYF@>?0yaZ?&IXu{hfSkr$hbeQyjV#pPr3N=lIY+p8Se`&!Xj}z56@;(?Oi{ z5kK9Go1XZjGoI;>f4=lTAY=7EJGlSZ!Trw;?tgZ0|FeVppB>!)?BM=q2lqd_+Ix=F z|LnB)KRdYp*}?tK4(@+;aR0M|`=1@$|LoxYX9xE`JGlSZ!Trw;?tgZ$|F!iT%>Uqe z4%Ywd^yzx^+F!v+IP;T|e~iy5d*YTfc3Pm-ent{kv|( z>3SBw>)g0q|M)a7@NB-|-#p@1^NU}#^Q->+Dh|Jj&#%ViSA6&tPrk&z-!|k|`Rbnz z;-ruG>1N#Y#3!BcOn?0IMPA)^%eVVGI&|MhpY8|g)_o#9yMLr}_m%YTev>cNbAEN- zt-bqh{k!iLr~7X4yYDt`_ucq(-;HPY-S~IkEwApoQA5I(5?9NY+O3WhyL;8 zSN!=^UfRo7|8x*1eZ)^U5OOkw-9~7vi^$ z7`OEWpVl2bTaWN>osw7UmwaodL;dMf9J&>so{dZA_|QL|{EC0?Udc;)>zDrNAWr&- zpKiuYPkhoD&-BMXU*uIilyCEn4$VjUG*9W){H15}n$FF4`d0_|QhngpFYV>4 ze>#YhKH{gFanlo@bjCCN@y{2}H`;G_9@V<$c~tA2=TWVLo=3GlUi+|jp2J{H`5#UD z4gb5T9{L|m`wh>d+HZIs)qcbCsPyzaDxE!#N`KFz@})C0jN6$faA%&top}Ox<_X-H zCvaz;z@2#lcjgJ)nJ2Y(eRk%F_Rc(kJM#qY%oDgXPvFixfjjdA?#vUoGf&{oJb^p& z1n$fexHC`S&OCuT^91h96Sy-^YHxmZ=85*sJb^p&1n$fexHC`S&OCuT^91g!A-J=l z;Le7EI~xk_Y$&+1q2SJjf;$@u?rbQyv!QBlKit_++B+Kx?rbQyv!US5hJrgA3hrzu zxU-?)&W3_J8w&1hD7dqs;Le7EI~xk_Y$&+1q2SJjs=fKu*-+X$8w&1hD7dqs;Le7E zI~xk_Y$#Y>?KkAxx<-fAJNmQ^(yjH8o~@g7Zat-c>ny)oe>+3ZxY}E<^=};)r}bU@ z)_vo)AHb)50-o(3@NZusul5`At(^|_r%!R{R(yIkE}i2;|9J8%{+*#GFYV>4e>#Yh zKH{gFanlo@bjCCN@y{1|wcn6$>lz(e@95JyNVnEUdbV!Tx%HI(t+RZoKJaUDI{OXn z)kFPT$Hi%V7r%Aixa|kso{dZA_|QL|e2G85 z%1e9s>Yoncq>uRNX593|C!O(3fBf@h@_Ofa+A}Zi_g~R@+SNm6P&e$eH^Ov5@YdSaI>0ce-OZ9(3p@#IVV`Bh%p%UAz&5GQ@aPdDSH zCqC(nXZquxFMV6bb<($x;J$?f_bnv2Zy~{b3kmL9NO0dmg8LQ{+_#WwZ-3agkhJ$L zB)D%O!F>w}?psK3-$H`>782aIkl?u=v6Hm>&e8~V47 zi_`ipe(Sz*+YjK=J^|165BRsQkXQQ+`PNQ{`qQU4bSpkR8<)=Up?^I275~0LEHCZl ztA9F(lRo07n{m?^Y;pVr$hbeQyjV#pPr3N=lIY+ zo_vWvzsgH{`Rbnz;-ruG>1N#Y#3!BcOn?0I<+{86;Xd#E=hy$iK3Dv?$Nv64Z+yQyyH##TvU7YQ2+jK zD^CB<6~F)U8n^%d;?w_y@$CP_`1gNgdG-J0m;J>bZu{51?*H2UKluG`-8g^q__uBR z-+ss2cHGB2<&T!n*Z!wJTArWvet*3DKkR;gym@J_9_ruoUU7QfD}K*=job5He0tuC zXU}`_zwo?wpKtvAk9hUoN8j|ASMB}v2R`#x_P+ZUU-`EHYkr}-s*^UJu+FMOI`cs9TAZ+^+E^-I3hNjg+N=~G>$TlJQn)nPhUpXp!S z=1cXQU)@(~um0=bx*$&Lh4`%_#%+DUr*#L<)+78|r{vZ8CEwcVP=ERqhi=8EXXDa2 zKJR$)W3QtPW4dy>Y;I~hxk+v@vI)=Up&iOS^=AF*I@I3vsejk4I9<=;cbyxz>mQ%y1)j|p{F_JeYJREz zwObeJZ@nmvb)@*#m&Ud3#K(FRPwQ0ttzYG(y?pgg2XWFz{B$#Jdg7DLc&0!8`693O zhw`mX(xLiEpXw^zs<-s44%4~%O#kXOU#jQ)Y9FP&^-KTOFL7GG#BcpFZtE95tzUSy ze&OHxC9n2}@~xc?^`}p9=vI7sHZGmxL;ra4CI0*>FYV>4e>#YhKH{gFanlo@bjCCN z@y{2}0jh_d4>a#QH)uY3p3pq?oT2&a`9t&CbBX4==M~if&o`HuG=5B#cbXs@2=U!4)B`XhdI$+*=ke5zx3R^RZi?#ZiqDBs%YP=ERqhi=8E zXXDa2KJ) zU;7WQ{=&VFyZOt%aPRLP_<>)z_kHjB#xL0W!9Tg>3-&(ooBq`o?ET|&zU2${zEXSj zME~lHIMpBVt4qeMUg1+6!?XH^e|1k@)x$4+<`-}K!~gt?xBurp{z)6>+kfUs8~?BG z@FhF$$9?LTET4ye{g*7y%isMa%l`+z|4TM6?bSp5tB2xL55=z@8n=3gPxTPb>LLEs z!+F1Q>*2h!x$|z`<=pu=?|AM!op(QX{?0q0JFn+G#GUW+9^%%4c@J^x!@P&Mbwhjg zQ2*+TIMpBVt4qeMUg1+6!?XH^e|1k@)x&vjbld0M+wDK^Y;I~hxk+v@vI)=UpC-%= zTl1Hm&1*V0-|1f+;7j#^U)2rm)f4@zGvZW##IG(Hw|a$7bqvqy8~)Wjc~uYPTRR=< zPoLt@t@!k8Tsp^x{_*5X{P|U0+RIn}bPy+f#7{TlrYAn>jA#1epD*%ie<LH%hL;S0U@~R%n zw{|+zpFYK*Tk+}HxO9#W{o~1(`17m0w3n~`=^#$}h@Wo8O;3E%8PD{`KVRPTzMr%8 z@PGb+$M3xR$@@Qk=i>`r_1Qa5zw&?l?47^wevi-IdHoA-c-+qSpL+4*whlbxJ0G|8 z;qm|Caa%XER}b~C9*R>v6u)|C-0C4d)k8e1hxk_yY@16L*rHt z@u?o-Sv|zRdN{vZ-ud;o?|;Pl_~egz#QOXBzjD+1{*V8MoA!G6<-6as*U7j4&Zq75 z^W>X9ZLh1Vp7m*ay?x*_KW(o=?OmVxcioE9^(=nZxpBMx@o8S**?hsjc_gpq*Iz#E zk=y?7|L;d`|F?bCr*E8Ve(KXV{xjd>Q9JI>KlD+{=QqCQQOom_pZ%!i{}C^E)aIqV z`K5pJOPuDH_{}flHox#`e&N~t!oT??uhuX5RwwCD{iIKIm2TBrdRB+&Tz#g0b(=5M zbADClwO9Z3Z(R_l^+NpC5#zSL;M2N;XX_FEtyA)9{gQ9(bf`alibJ>J)3b5u93T3} zlP~e-S9xhKU;WcTob(Yt-He-__@pzQ>5qTD$gBHh`8Mz9(0rs%^OSDQUwSsL>D+v$ ze|3N_)dzlcU#Y!%sDJfPoa&+Y)kEV}5AmrU;#ob!zj`RI>Y;pVr$hbeQyjV#pPr3N z=lIY+o_vWvzsgH{`Rbnz;-ruG>1N#Y#3!BcOn?0IMV)VcssH(CUC3YSMZQ}{x*n`A zT_@I^t{>}B*Ohgu>&^Prb*R1TQ~$18ak`$x?>aYb*FQeZ3p|@I_&1N_)%;TbYqu`c z-+ECT>qzmfFO6&6iI4Rtp4O@OTffRnd->|04&tPb_~~Zc^u#Bf@l1dG^F?0m59M2( zq(k+SKGjvaRd4B89j0^jnf}#nzEsco)jmpl>zDqmU*fcWiQoEV+}1CATEFmY{ldTX zOJ1#C@~xc?^`}p9=vI7sHZGmxL;ra4CI0*>FYV>4e>#YhKH{gFanlo@bjCCN@z0mJ zF18+eKG3}L+@SgBc|!BlbB5-x=MT+m&n24go>x={JjbX$c)n5H&|W>!zd9pM^+){b zl5wk7_*BR6tiIu2-IG`K(DQ-XJvXSo=LyB}oT2!CJ*ZcwP}t&oScf`9^tZ zFJJxBL7emvKi!O*p7^9Qp6QQ&zR0V3DBtEC9h#5yX`a%p`Ag5{HJzL9^sf%^rTW0H ztsB!`J<-29BTn^4{OXc%t5^6`$MCGa;a}a8SM^Z7wbP;g^eGPAicinRrE`4fA5Xr- zpI_yry?pgg2XWFz{B$#Jdg7DLc&0!8`Qmq#`Q`VPwZHPiKY085eP(g|ZnOA)&)K+s z=NTWr|BR>Ki^kvYMaxTj`Rbnz;-ruG>1N#Y#3!BcOn?0IMPB*k_m;K$9cKOgKC?J} zw^@9@=WJZR^Nf$*f5y}AMdR=HqUEK%eDzNUaneWpbTe*x;*-vJ<`@3?BCpmj`Bo?C zQ2nG&b(L<_TY6T9>0EuLe|4KL)pLGT=e1Y=^>1Aer}aYo))C{jzTnfkgJo4@b=TPNTBBk#ZU^FRO6M{QmG`Tzc-w%&fmwI8*0_?p*WzxDY&{@3fbZa@3m zuitw9V^6z&>%8{rzy7TY;{M3)$_Rsy#AHDs* z=CL2MabENjAG7h_`|o}1j{As*eC+c1Z@=nem*=nktB+m&w?6-4H!tn2U;4LxiPQQe ze(RTUTfgvW{lc^L3;)(Hc~uYP+q|Pg^N~KyQ@S;O>Dj!dbMu}4)d9X#ANW<>&|W>! zzd9pM^+){bl5wk7_*BR6tiIu2-IG`KP`M@c}#EANXSr*gEjqfBAr|4{v$;1Ga8xub${%oe`({BYt(sxYa9ss$+Oo z-|(;Q$*X$!@^607wmm@|mBsao+H6K564W{M{eC<9_QWKX~~(@2elYJg@q$ z2QUA(fA51gFYVPs{i}!KR1d|k9vZiLh)?wp&*~xm)kAqTzvP>bbjV-&hf`9W!Ud=E0)=r1|)2BFe zD?U9Nm(KB_e?0jTe}0vh_VU#~9mGi=@zc$?>4{G|M)(F&-AZu^QC&uukKT{w|?p0`Xx^5m-ww;#%=w=r}YcZ)-U{9zvR{WCEwcV zP=ERqhi=8EXXDa2KJsU^WAz>9k5PSAFN;PqqJ8K^{*a^Q#};FdT8A0AwJbZJgbNJ zR}bY?Jyic|w=UG*dQlwfNb#*NjceVBkM$^?)~WbgzsgH{`Rbnz;-ruG>1N#Y#3!Bc zOn?0IWuA-P*!-GvRBp`2IbY?*{GD@GZp`;NkLAX$hdHO^#;%h&zvafRpE=j%#;&V5 z@8!m>w>byq#;!x{U7z}Q-HOxoEPmIyal8KUX&1x3hfa9G>Ml=kqN8Ik#u?(q6v$r-L}@BYwIWH$Cx5XFSs%|9p{G z>z911lXR$l(xC$5B=lGm-zFmytJ3E{^=l2`iP%y#!XLr(izY6 z$3I`>^`7^>@;yiSHt*=re56nFly1#mdN!}=+fd!M zPS>;eUFXK_`p2hvfoJmt|K^drnqPB{<+jiHmfL^Mz1%o+9_GfMb24|_IX`px%(SfnL0CTX9fajM-)~y}^KGEbOMCN6 z|K^uC%`fqrU&d{I;nV!Wv-yR8^GjasH{{#8Mu*lr`m_$xt@V+ft($aiJ*9u^EMHoG z`PI6tz4coE)^TxK-^Fj;H*Wg@eA*}A+5Q3l_7(DKzaih+=}>?A6o+obr)T5RIX?7{ zCtu>vukzAfzWS$wIO!vPx*0b;@kwVq(;xqQkyrZ-`8Mz9(0rs%^OSDQUwSsL>D+v$ ze|3N_)dzmHE^DtI>R&w+r+O%U_0YK0Lwu@-cvcVbuO7;)dMMx8=}>?A6o+obr)T5R zIX?7{Ctu>vukzAfzWS$wIO!vPx*0b;@kwVq(;xqQnRBGK9?m(;JMZRv=ADmoZu8F5 zInR0L@0|0z^LoyI-uXV~LT??I^P;yt%sJ9qH?&s|^{*a^Q#};FdT8A0AwJbZJgbNJ zR}bY?J)Cp1w|&mj-u`pW_Qsj>w>SQr%e~{ydELur&hcKJfB9ZNzWnFh@6Ahl^-%xn zp*Yn;@vDc%tsdf2J;bwmh=28P-b38^HSh7QkMn-t`aAFat?%skD+bK`dXMcF1!*s4b)4#gSm+Cpcs`J{b|N6Hsh|_u@e(Q*F zTVL>L-NCc<2>;e8d9{AYw{|+zpFYK*Tk+}HxO9#W{o~1(`17m0w3n~`=^#$}h@Wo8 zO;3E%8PD{`KVRh4^CY+H* zL-DJJ#;qRWQ$579dWe7ZP+rwT`PNQ{`qQU4bSpkR8<)=Up?^I25`TV`m-h12KOMwL zAMw-8xao;cI^&uC_~(l{-~3Yl^U=DHzt)Rr~g9^{eYp zd)KG_UAN+NJ&WIUZrrYae3}<{Hec{>9?7furT*7$U8ukHqBz!(;#*%D*SZrQ>rp(d zQ}MTcm6!JN)ju7?Ngwgk&A91_Pdek7{`lvMyxJeiw>n9O>L-1wt8}a0(z7~D=jt>4 ztJ{33p7X1Hl=jvy{ae4pY5fwv^~<=eU--0s;o16yf9sdLTEFC5J00pzpW@K1`1EXC zI>(3p@#IVV`Bh%p%UAz&5GQ@aPdDSHCqC(nXZquxFF$*y=WRXoe4u&fxk2;M^MvN9 z=M2qX&mWrCo=Y^}J+G(^c#cth@O-1Xp}l&de|1Kj>W}!<)yuR^-l+J(ntJsGj4j~lg@ai zKmPe5uj-+En|E|*KGLUoO1I`OJ)75bZobpMI>49e1HY;p+N&q}S7*ej{)k^)GH&$> zpXwN%)i?aBd-AFt%C~kp)So`ZpC$5B=lGm-zFmytJ3E{^=l2`iP%y#!XLr z(izY6$3I_YUB01uIOm+-(7c=T&u?fx&bjC}G*9Qe^c$MLbB_8A&FeW|{f6fIoV$KQ zbzshEzoGgt=d}AiiQ3`(_8Y1v`d4Sfss4yxT{3R<3ZLp2p4B(}t9$aQ9?rS++dk*j zZ~r;Re&fvf_8WiBz29-?JpAP|=j1QXIah!A&$;@Wm-h12KOMwLAMw-8xao;cI^&uC z_~*;~-{FS#hcEo#$KKGqd+NJC;fChpo4)$OKte$5Tlhr7T2Yi_7+Xs@2=U!4)B`XhdI$+*=ke5zx3R^RZi?#Ziq z_>#YQ=(fM+13q#4f9Z=qe&hVe>+iquU-j!BzT^J+zq`-!`Hg>j@8$WLKe*TOzy4G2 zwRveTU;WcTob(Yt-He-__@pzQ>5qTD$g6rN-{u`1nve8pp3<%POV8#toty9UuMY5~ z`oOR1hW6@-{?!?Asz2gamyBDz!lychXY~#L>Ylu+hw`nR4)v!`ap+cjdNwYd<3s;= z@+JQKDlhHjtA9F(lRo07n{m?Dj!dbMu}4 z)d9X#ANW;0)LuQ*zj`Q6^-%okp>eB+_*4(^tRCWjdp&&Q)ri{wr~X~H;&eTW-*s->u77-*7kD;b@NXW;tNEq=*KS>? zzxARx){){{UmDlC6CdkQJgrmlw|4{G|AA^#Anco&U2pAN~KmdFuc2&0qhoZ(jR9e)HY`_p1Z`?_YiJdw}YO_UeiL)fsWB zKjK%HjJx$}_*BR6tiIu2-IG`QL;p{&-T&F^@Bi<`@qhW^`+t4o`agbr{C_{5{_h`u zzXvEU?d7X~I*5}#;-{N&(-WU`#xwo#&lh=B59QmuqeJtNU(HjxHGk>Zyry&Wo&MDU zzEmIhRo&2DJ<-29BTn^4{OXc%t5^6`$MCGa;a}a8SM^Z7wbP;g^eGPAicinRrE`4f zA5Xr-pI_yry?pgg2XWFz{B$#Jdg7DLc&0!8`7-tJa(>OcyIlLs$IJDfd3w1xGk-4^ zf9Cb&#+~_oIX+VdF2{4~!{zw<{#SWvFJJxBL7emvKi!O*p7^9Qp6QQ&zQ`-TrcQ4A z)X(idb#>!Rz1{dzhj-km&&y}(_VS#1zWjavtGu+Aum0&EPWp(SZpKYde9{@u^v6G6 zsovY9EuWs|Ddd{y4b^dboU;owxaau3LZyhmi>kB@u zJ9xGp;omwXukOF(TRR= zjA#1epD(kYzufvY`^L-F$=Od{u71uw^Kx}{_Mexlx3e$3TpgbM>gDS5>|-xiw`YHQ zxq3eP-pkc_?bUz%TNlJ>y%4{3#JH_5__Xfe*?NS3>y*4&zhjyv}k%V+L8mgn4$EdRMr*}Sxuum0&EPWp(SZpKYde9{@u^v6G6ChsLcQ;!{1uvwDdC?e*}H zTMy-1J00pzpW@K1`1EXCI>(3p@#IVV`Bh%p%UAz&5GQ@aPdDSHCqC(nXZquxFVDQ| z3+`Dx{L}CKKmT#_?mIv1i67T|{H=TZz{fRD|MsU|`*F?R*Zj^SB-!@s)sEBE>S zdsYvp{by>Q{x7Zn#Cd6PCjLu{KjXf%afi>X@fn`C#&h`J8vn`b)(d&vTE6aYb*FQeZ3p|@I_&1OE)qX?1wbP;g^eGPAicinRrE`4fA5VV8pI;a9y0v`u zPX}?*NBnd%ZhGRA&UmIj{`tbM)-U;1C+SfAq)&B~Zq-|QR)^_aeWrhPn=jRKezksS zZ~fB0^-G-AFY#NyjNAH!PwN++tzY=Je(|gIOTM+!q5kwK4&91R&&H*5eCQufe#M_( z7xKEbeDzNUaneWpbTe*x;*-vJra%7qV*RQfs{hS9>q7IL*FU@P~PV?P* zR2{HRRUfQh)eY^{6aA|*;#7acuPzz4dWBDQ4A1Ht{?$EsRS(tw+N}%qw_X&-I#PV= zOXFI1;$uCEr*$g+*01u?UcUOLgE;9Ue!3YqJ@H9rJkuZle3^NCsrfbMa$L&CIj`eV z{?0ibm-2ni_qf#c@Yi?vl1p7Da~{a0uAez4ut^zxzu&2z3Wr|u3K@s zp2hDvH*VKIKFtd}n=kk`kL1<-nsZdPea=_e{&Vii#<}^+zi{KvIW0TxoZqs1=3JNM zIp@GE|2YR{^U_|v`lo|9=_7u+88N=V8kuG)p%(+RIx~}FtrAu9JbI#JGu0!ozpZa&*iqrKhe%HBi zyZ-TMUf|h$!M}MVujbdBE4A%&-qiMg!K*%d4{G|VUw*YNYj3^Qzjd5nt?%Nu?i;uL06y&#@NEBpfBOn~wcn6$?R2O=eTqZ3;?uKn z=^P*W$CEGd=T~`YFJJxBL7emvKi!O*p7^9Qp6QQ&zR0V3DBtEC9h#5yX`a%p`Ag5{ zHJzL9^sf%^rTW0H>Y?`Pq5joFajJ*nR}YO_J;bMah-dW>|LUQh?73zr<-xp6Q6X(GyU<;7j?e*rT*umbs>MP7x``- z>3Xofbe&jtx_+!jU02qrt~cvf*P-^VPyM@Y#p!w$zw6w%UH|wrFYs)>;NLuwSMy8# zuid&(f9pkYtRuy@zBI0NCqCArcv`38Z~ZDS?d7X~I*5}#;-{N&(-WU`#xwo#&lh>M ze#y5wNr&nueX6T;tKQPHI!x#4GySXEe5s!EtMyBJ>zDqmU*fcWiQoEV+}1CATEFmY z{ldTXOJ1#C@~xc?^`}p9=vI7sHZGmxL;ra4CI0*>FYV>4e>#YhKH{gFanlo@bjCCN z@z0kz_j~K%oSVJ#?ip|Y>Ya~s&i2mJIe&ZS@0`nh`@DYm*Y13ubG)|>%=zA1ALiWe ztsB~_C;C@s=G^bCKjK%Hj9b0Jr#gmb^$q{(p1i7ubI$p;&-v%uf6hhUICEb5#-DT4 zcicH&efi9}>&tV_V_*JrPW$Giy?UsB^-!GZq4?E9<5myxsUG54J;c9yD6i_Fe4BT4 zXg<=Xc}lnDFFl*rbZ)-WzdFE|>I1*38``TU`d4Sfss4yxT{3R<3ZLp2p4B(}t9$aQ z9?G|NI@F&&#i3jA>Djn+jt~9g$(Q)^tGu+Aum0&EPWp(SZpKYde9{@u^v6G6=3J5W zYtH4^_BpR(`_DNZ8|Oto@i7~J&i&YN=RA<*Gv|aX&pAJ2`Omo`o0sU&hTZeDVv={KEgDU#(yAtxnRR`bnSaD&4BL^sElkx%y21>Na1h z=lrV9Yp?$6-?|`9>xKBOBgSog!KZZx&(?A6o+obr)T5RIX?7{ zCtu>vukzAfzWS$wIO!vPx*0b;@kwVq(;xqQnRAwQ{hD)%wocCZMO#1TT%)b4bKcR` z+c^hm>+qb9wDoz;P1?GB)ptF3>-n6sv~^y4>zDqmU*fcX7Qgk&xUFCKw0_~)`h|b% zm%LiP=3J?5pYx`+|C~d$aprugjX&pB?YMKE)$*Bhu9oMVf3^JQT&&GYd+V3}tzY7_ zeu>}uW!%;;d|JQoZ2iK&^-Er@U-E6<(V_WBpXMpun!ogHUemexPXFovU#buMs?KY# z9_n8`6sLM9e)Z6})kA!$hj>;G@vk1rt9mHk+UZb#`V@z5#iwWE(m6i#k0)Q^&#&^* zUcUOLgE;9Ue!3YqJ@H9rJkuZle3|E>yPuzP>381EdG$LV=N$W;r*ppj&fhur{`PtO z&`0fjpL6oJ4$S%aTOa0J{jD3?t0($bXXae}tv}*#U7B&LSNK%N@T|V!U)_^e^>Dr; zu;G@vk1rtNA70e56DE(kI{f)%8Hnt`jC$5B=lGm-zFmytJ3E{^=l2 z`iP%y#!XLr(izY6$3I`>)$=I%RwwCD{iIKIm2TBrdRB+&Tz#g0b(=5MbAI*QMtkd* z{;gl)w0?=-`eoeKFML|R@NE6Uzx7LAtzYu3oeuSh?73zr<-xp6Q6X(GyU<;7j?eqzt0`qI3%?lj-6N7VuA zRQ197)jmpl^-%xnp*Zcw#IGJ2w|ar3NW zcj99`il=od{?@PZ(q6v$r-L}@BYwIWH$Cx5XFSs%|9pAc9q+vL@O9sK=bd*idF!2b zKK{a^@3Qms&u+QP&fm}dJ6G?#e!(YRz4QIYzx?X010VPuS8si|>bX~M-Oye=(Z4z) zPW4Cp>XLD*SNK%N@T|V!U)_^e_3-}ByVJHm_P%%8{ttY`9XHPVe(@bQ{tsPq#~t^J ze)Fp3^VlE0YI(lpTd!LF?|8~po0s|LUQWnzmAMvY8#;soAQys&z`i6gXPhQo-`OfdQ&-Z_~|9lsCk~SNkaK)kFQOhvHNZ#jhS3w|ajA#1epD**>_I*EP zzI(p!LCp8i_x*_ZPWrw#@i&iu+rCdR-&NoDEarRb`~Jmzhkf76nD4Xi`x^7z_I-~- zd-X*B>WnzmAMvY8#;soAQys&z`i6gXPhQo-`A+?|&-d%M|9sbe1N#Y#3!BcOn?0I zMPBXa1RL}V}b;`APNqg&;{;gl)w0?=-`eoeK zFML|R@NE6Uzx7LAtzYu3oeuSh?73zr<-xp z6Q6X(GyU<;7j?eqzt0`qI3%?lj-6N7VuARQ197wfm@PuO8}O zJrt*UD1Pm&w0>wyFYyES6sLI!^c1Cy4@c>9?7fu^<~e0ziofk{oZf;fBi4qZR0%RNq5`$Z@k;xcH9^J)-}uLJAdSw z<#~^9yJq=+%u}z~ytFsJ^lyHN)BF;@`DNVZ7e37|JeyzmH^1c7`X%4$Bps@s^r^1W zt$It(>M)(F&-AZu^QC&uuj;(^>c9T23*xk1h~GM5+}0O-T6gelJ;J|rN?xsB@~xc? z^`}p9=vI7sHZGmxL;ra4CI0*>FYV>4e>#YhKH{gFanlo@bjCCN@y{1|RS)IcyrV<& zkv`2+x;204x$}B-ZobpMI>49e1HY;p+N&q}S7-QD{Sm*qWZdc%KGiWit8e&M_vBSQ zlyB{Hs6Ty*L$~77vvKJhANt3WFY)JBd1)_S{nJ65^btSZjGLbLq%)rBkAJ>+4$ywX z^MU4_=LXG3&l8%bo-;ImJ%4CkdoIy@_q?Jy;5kP1!SjvQW$o2N{i}!KR1d|k9vZiL zh)?wp&*~xm)kAqz4?Q2K-E)Kbd!A4n&l!sE`9tG+E)gHkE8^)nM*KbBC@<~htA9F( zlRo07n{m?bu$0Q@A~oo{jMwj z_wRc1dw{M(?OmVxcis9uK-aVQd!5g?UH|wrFYs)>;NLuwSM$sN(`)yC_WJw(dvW|< zzWDxM-?;vdA0PkUkEj3p$KUS(%1e9s>Yoncq>uRNX593|C!O(3fBf@hzVo>AYrd1X zKF;?O*WdZB;`%<{TiokmzQefJ$$X!2ub=sD<6c+uJ;%M?<~xsj9cu6T)W7RioUUi_ z_d1_(yZ-TMUf|h$!M}MVujbc$*K*rm`QabD{pUNF8)v?cx$)<_nLF-$PjmUqcQ%*j ze1CKK&v!XDFYV1Q{hMFnG{3}eei^s1N#Y#3!BcOn?0IMPAiI`8Mz9(0rs% z^OSDQUwSsL>D+v$e|3N_)dzl6H?&tz^sml{Q~eRYx@6qy6+YE5JgaZ`SNG&qJ(O?l zbf`alibJ>J)3b5u93T3}lP~e-S9xhKU;WcTob(Yt-He-__@pzQ>5qTDy!|=f@bWp^ z(Ro#u!gH1?eCa~_!P@6HpQrzGzT?H0<~N@Q|M6pAd})63dGNd3Vx0q2{&Jw-+UhY&_~>SX@2v0 z@S{KF=1cRN$!(wCQf~kGjpf1O%x^Cb7Jq(|d9ZQkx0(mzGr!?H7|;1_=fU{TZ$1x} zSM8U6@x|N!zVC9&#`&4+Z`t^d_}p7|+-H32Etlf+kAC!)OY!`$pSxxG|K4kF*}Q)H zH*VQ{wWovr=_5|MiJzXvO=o=4AJ2Tj-?zN^D6jbq{O0@c`IfhKI?Qk252nvw&$qm_ z(`|kOe=t4gH}D73d42n%|Ib`~0?i`_FIA4;JULe$#&CZ-?jn*8O09`SyBw)h^%q)1f%@DL&mAm!9#Vb3ExEf4-C#zsgs8 zI_RH1;-s7S>1o__#wY#p%oqIUouJ$Edd?Lr-+3o!b(nX84yMn%6Lc`$=AEE}={fHN z9ZctWC+J{)UH^5NbM<2mnYom}vr-^^@Y^P8E?cYZT-FdgPMGY8XWelv40-R3tl2h($YGjlMV z=QlG4^J{)Hb1+}#H!}zGYkqUG?ekld?LWU!Iar+e?aIO8&u>}|Htzh^V&u>%?7H59DahE{I+rF86P^wlm7ANOL_6De6^>8{^=u5x{05j#!Y8@(jU)!!GG>~ zH?O(p-F)Ys_h35AJ@3KvnS0)Y={EP;2h(%zc@L)Z-18pHues+vm|t_xdoaJ|o^jjf zUUK`-J?6pU%)RHq;?F(l!N#3?)r0Ywd)R~VoO|1Y`Q_WS`Bl4o>raQ`(5Lw4I=^jP zdd7#&@uYwJ`BGl|DqrpCpnv*^lWyXtr*YF6pY+EwU+|wj`Q|ly^38YlneeK4N0_db|kvnM}TJ*-{6^`}E|=u>>UH7-5lL+5zXKmL3vFMgG;_H@uc zeZ)yO@zc||>5NbM+k@#d&ukB-+dQ*9n4a^@_Fy{C zGuwmtHP37h=GQ#4J(yqf%yZl4S?Iy~&ok14#hGWP2a7+?R1Y@pJZn7|pLqs*Fu&&6 z?7{fYGuwmtRl9uaPlw{rr}*bOzinK4#)r=Fq<{SRQeONjU+w9jfBJ}%ZsMn>anl)} z^v83arJr2zpJ%q4*F3X5SibYj_Fy{9GuwmdGtX=frrSKTJ(!;J%=Tb9&okSD=|9hG z59ZfAvptw!^UQPG=UM3XpJ${8i!;wo4;Fu(sUB?HdDeO`KJyIrU_9s9?7{fYGuwmt zRl9uaPlw{rr}%VhTzbZb&heyw{P|K|{3>7V>7al5h?8#Or>Ak#8K3mWGhgtZ{}JDw z*SBB6@}2(?uMYD+;)Cfk|06z_Zu39lgXuZ{BR-hU^FQK)`8EF|KA2zg%==(|&Hq@p zeg5~l{pWwO2a7ZRt36o!`5*4V#-0D|zRcQ$&-~B#V1CX2f)B=j{zrT;ziO9n{pnB~ z`V{|M=eLbZ&-l^BatV=`+8&1?^G&XU@tkjU9n7!!hS$OTs$IVIr$ce*Q+&ELE z`DW9>#+`3D9gNR>Q=}??=J>M3eZjDRN_|Q3?^p8JZ z%8Os+t34g`Pakp8P5ksUZaU+W{&?mK{_~BY&1=3fbg+Eq8$+wZd}HWf`ph?m4yN0D zW9VRdKID78_h35DH---8*L-8>V1CV-b1=W=8$H`T-|pG|^G%TS5opKi?QSm|wNaxBhe}4t4<+vi)i+kd`+d$2gK`_^wbSo~`r_T+<&JKxeh z7@zsZ?!kD@w|5Wb*L;)rV1Csu-}=*`IP@t#-5Qsk@u71(=^uZ-lo!9sS9?0>pFZNG zoA~Kz+;qk#{qf8f{9p0l$8BDBzwQc_?-PFbvsQ<@{{CkkOrH<<-NznGw=a6(XBQfFD=MSF#u!F__ z$WMCc!N$Ge6F&K1eE#ekA966iuD`<-jQ_X2@xiB^U$x7({&Xk~eTq-F#-(R`=p0Y_ z$Dc3r{P2v$ukzKN4*I8$IO!&SdKx#K@kxI?^9BDo^MCW2Gye~k@0|I6FdgR1|AXl> zXZ{~dw>k6wV0zA({|D1~&ip@^UvuXF!B^_x`yb4&IWvFT=Pdp0KWFS8EY6(0f3Wy- zCjY_4owNE6#%Ip(KN!zB+y7wv=gj|u`Bl4o>raQ`(5LuxYg~H9htBb&fBg9}_seH2 zewDBGbkIM2#7Q^t)6=-=j8FRGnJ@S|YklhP`Tv)*)?xWNYaOP8v({nyIBOlIo3qwo zdOB+zrn9rwVSYJl9lkQZUUM+NoGo9wGw18?EP7ZRXVk;uJG&k>t~2dne4KR;sUx zAO9ot-TV^UK-7Fuy+Z70998<(E(p>sUxAOG9t*BOgn<*Pj%^iQ8Nzi!h_{PZ+#I^&c6c;*ZK zzIByfQ|C9|sq+WZVe0(B^qD$;Fx{rkAIz_*^9R%U#`)HjnEaYLfADSV*TMXnI=}5x z=ePgV`GduoI)AYEQ|Avh?$r5%@tHb*FrHKA59XI|la*KP@~uA|ibJ2`)2(so86P^w zlm79);@4}=So|tq?dhO@`iPTm;-{x^(;1)i$1`8>_wA(e^6ey8zP_DwG#?#&I|-(b zZzsWY^X(*B$C+fuMNzBvVp?^{%`aebo- z#>cm-V1D_g6^y@cUBTv8?eeWZ9g0Jr;?u2h&-H&BA3DdA{_*EadGV`!wWovr=_5|M ziJzXvO=o=4AJ2Tjf9_K@uendzeCIypU^>iw%E9!R`;>#}Huot9({t`q4yNQ@2OD>u100OcJO?-!&v_1TFu&%x&B6StUB30FLviR+ ze7ZF*J>x^?c+x-qd?_z}m9O@6&_8{|NjLG+)41u3Px|ATFZlbGcXh+JykYtJmN!fX z-|~j(<6GV^-F(X%rl)Ut!*up7ZgWZ9iG0i4&(3J>oC7+mv8;)P#pRcpKgsy&-l|ZJuKvOwW0a zeK4KpIrhQ)n&;RD^J|`CAIz_Lj=k;k9DDoEbL@k~ndjICi$Bk?4>s;R$37UJd5(QB zp7R|0V1CX29S-JK?eeWZ9g0Jr;?u2h=@}n7$CLi?=Sz9|A{u=`9IOYbeR7W9ZaA3KheQ-oBtCXOwaj0(ZO`S=`pW5m|ydM zqJyujU#~fsU-N&WZJ+-WZU6Z{(ZS-(|A`J3fBsK&uyN=ALmAIm+T~k+IuwUK#iv{2(lb7Ejwk)&&zJfC*BOgn<*Pj%^iLmg(oOvIG;TWMlm2+- z3;y1PuWoo3zIx(ac$f~}g@@_mU3i#o-i3$h>0Nl3&fbNG`Q=@Bm|x!Uhxz5*|Jt1i zP=99yz~apRVGkDH*#g>)>&yWdA7>Gqza5^=D1iCp>;jlywad5ubSTcbo^Oj!x5lMs zeCQlc`p2Iy<;Ab^)t(Oer;j-4CVqMvH=XfGe?0RA|M{K6=H*@Z^7Sr!I(QczrjK{w zVY+!29;T;v;bA&^7ar!<{LbNEe$DS34(8YV&SBe~2~dA$1r)~_0ge7*Y#(_wx`bTECq`>CC7-u;B>>D^D5U*7#Ze>;B7?}!fO zmv>sV^UJ%guy*gj*5A9ausGhCg~j(SEo@xx*uwaD_ZG&}JGn5wysHcIt9JR;pAN;L zPx0y2xb%zjG%gejfogZbrM^4h&)UVrbN!{T@+9Twla z>acOW!w%!)-F6sH@4UnO@-95guiE8Xe>xP0KE+jt?SRC*4!Qy+@4>qoM0AYN*8wlg+ok5si-X(anl)}^vBaXgL1*&yVd38 z-Rko7ZZ%8??^eU~@oqItH}6)%^z?2uOlR*_!}RxVHOw#XjKlo$E_vxP0KE*%R`EBFUGd^^VC;j8k zm-6CQ`D#xG{nJOBbQ3>4jhoK+q(7edg1@s*%gfoP{FOu&UA(O<*e7*odH{aXT!qcI5QR&-&wM-ah)*>p^Rl9uaPlw{rr}%VhTzbZb&heyw{P|K|{3>7V>7al5h?8#Or>Ak#8K3mW zGhgs`w(#aPXA76FvxQ+gI9nK|kF$kgy3Ko12h-Ep!rK2|_U=FQ|Fy2~xN9&xbdEn_ z1X`YSo8$>onS@L~-_KZ^PV1mHF}LOnS{s%!(O5P#37H1b9~oGzGHjF51;?Yvwmjc# z!$A$2=x~uCj8^sobo-+wI8L_b?fQK0Pv3+6<3EGo{P*DE`aG}4^YM6H&+B@bhQ)VQGi+REIK%ij+Zo2wna?o4 zoCOW@t9JR;pAN;LPw~%nerH^I#)r=Fq<{SRQeONjU+w9jfBJ}%ZsMn>anl)}^vBbg z&vL=vx5>)Ox5>)ax5;2S_%<0#AKxZ}>E_#HFg<;n4Ca?_lfmktZ8{^=u5x{05j#!Y8@(jU)!!QZ#8Hm~{CRr&hX6-)=;x`OHB zTURjM9(cnIrl)URX{WPqU7f!jzkKTo=GVOEdoaIz+pBip{Hniifx+U;d%g#Y|L|R} zJ=nOuDW(rT_rK`|Y81 zFrLoIf$?`v4lFO{hQY3x+FdjCcg+;XHB)@oOyjy{;^Uf$r)wtu=6HE&FJJxBL7emv zKi!O*p7^9Qp6QQ&zW6P!b8_V6H@eQrf&F&ZIXST3^g1U8_FG@)hGK!SRCi%oWGs;&dGs|>zo`IALr!2cseHs z#@{(Pu)LgW1pAF~?S5lif4?y<&is#WPYFYV>4e>#Yh zKH{gFanlo@bjCCN@y{1|IVY!los$F8!8tiFeVmg6)6F?KFu$CW1Jl_#IWWJRlXLov zU(U&a`873T+ntkBf9K@D;y5Sg{O!bdP7Z8b=j6cnI41|j(>XaXznqf;%j?ni-C+6F zPKWx_r#N&gK0OW}!n3`Rbnz z;-ruG>1N#Y#3!BcOn?0IMPAiI`8Mz9(0rs%^OSDQUwSsL>D+v$e|3N_)dzl6H?&tz z^sml{Q~eRYx@6qyAwJbHJgaZ`SNG&qJ(O?lbf`alibJ>J)3b5u93T3}lP~e-S9xhK zU;WcTob(Yt-He-__@pzQ>5qTDOzqfu=pC-+op-yMkKXxeo_ZIo`Rg6D=Jot9c<1~4 zFL>*~{4aRxgLlxX8``TU`d4Sfss4yxT{3R<3ZLp2p4B(}t9$aQ9(o6@cJH9o-#ci< z@eW$?y@S@c^FR0HGyjWUp58%=zjp@9OMCTD|LUPQ)kE>q&A91_Pdek7{`lvMyqaI~ z%||-qFMaZzZe0)b>^h-y*AM->uK3dR#;>kJ?OmVxcioE9^(=nZxpBMx@o8S**?hsj zc_gpqmwaodL;dMf9J&>so{dZA_|QL|e2G85%1e9s>Yoncq>uRNX593|C!O(3fBf@B zUaep9txnRR`bnSaD&4BL^sElkx%y21>Na1h=lrV9Yp?$6-?|`9>xKBOBgSog!KZZx z&(?A6o+obr)T5RIX?7{Ctu>vukzAfzWS$wIO!vPx*0b;@kwVq z(;xqQQRmwqs{hS9>q7IL*FU@P~PV?P*R2{HRRUfQh)eY^{6aA});#3dC zuPzz4dWBDQ4A1Ht{?$EsRS(tw+N}%qw_X&-I#PV=OXFI1;$uCEr*$g+*01u?UcUOL zgE;9Ue!3YqJ@H9rJkuZleDQ8w^J{+FxjuRqFMqwGm+#))>w54`U)PCu{knd<1K4%t z-N3Fl?+kVwYVZ2gzw1_McF1!*s4b)4#gSm+Cpcs`J{b|N6Hsh|_u@e(Q*FTVL>L-NCc<2>;e8d9{AY zw{|+zpFYK*Tk+}HxO9#W{o~1(`17m0w3n~`=^#$}h@Wo8O;3E%8PD{`KVRfkJ(O?r zjtk~S9L>s^+f;bj5yUF@vBS5tzO|%9mBKwhJSTW zUXQ+WzbxO{=}>?A6o+obr)T5RIX?7{Ctu>vukzAfzWS$wIO!vPx*0b;@kwVq(;xqQ z@f@If==nhN&U1t2qvr|DQ_mTizfXG6n|EG&F427Ve4{$x-S+B(=Nr`x?bQ?gt25$M zf5fjY8Mk_cPjw8>>Kp#mJ$Y3RJs+subA$SOo=_am8H(@uL*sfb5g*Sh;^{d?{5{_& zFYV>4e>#YhKH^sojhmkMq%)rBkAJ?*Z#!={zr53$kGJNX-2C+pY`%Lpw(G$=vt1|N zrS1Chj&0YKcW=Aiyp!8?sJ-h`|E^ncx}L@FIyY|DKR(S1Jex20H;?4i{PIq2?cT|) zzjtzrRmtHVeh)~ZhP08ciy`WwRe5$-*qca*R%Lt z=f>^&$ESILXY&RB=8?RbU*37I-8=8~_s)B9yz^ds@4Ppzci!XUo%eWp=RN+;C@3%O z<*R=>h?73zr<-xp6Q6X(GyU<;7kRbckZh4E)<=4_Zqm8+l>V)=d};mV zSL?F&)@%J+$Hi%V7r%Aixa|kso{dZA_|QL| ze2G85%1e9s>Yoncq>uRNX593|C!O(3fBf@BUe!bSHt*=re56nFly1#mdN!}=+QULR?{;mpbAowF#LkItxUo;owL z`Rh!}=C!jfoA1uRtPVIEv-;r7%<6{r>WTi<8F8vV;#Zf9TfM@kI)-QU4gcz%ysC%J z%&gs+ne}&OW^tZ5XN?x$nVF62%*^;WGc%sf%#6P?PRmPs`Rbnz;-ruG>1N#Y#3!Bc zOn?0IMPAiI`8Mz9(0rs%^OSDQUwSsL>D+v$e|3N_)dzl6H?&tz^sml{Q~eRYx@6qy z6+YE5JgaZ`SNG&qJ(O?lbf`alibJ>J)3b5u93T3}lP~e-S9xhKU;WcTob(Yt-He-_ z_@pzQ>5qTD$g6rN-{u`1nve8pp3<%POV8#toty9UuMY5~`oOR1hW6@-{?!?Asz2ga zmyBDz!lychXY~#L>Ylu+hw`nR4)v!`ap+cjdNwYd<3s;=@+JQKDlhHjtA9F(lRo07 zn{m?kQa@ zcP4GugEM2hPMjs%_2Z1$t}AEHcD*^1w(C%P*Qfqnx8ig?i@(?TjNA2(PxAuL<_rGK zBY8Ey=3S?4cP4H9ok?39XVMnmnY4}TOxpN3lQy2tq>aBbgv(2N`Rbnz;-ruG>1N#Y z#3!BcOn>~FU(QBue$Bf->!Y)j^Vb>6`R?rHt_No_?{zX~K6m{%!@29q+0I>W&V24V z)ZX=}f7k82L$uek_+975?fS>3d4Xs11^?!eyqaIme6HP@&-Hiab8(#cTzqFfH?A|E zn_td+j;Ax9D+os|JGT)wEps|by<7swf?Q+;>Kp#mLwQvX zQA5I(5?9NY+O3WhyL;8OZ@p&UfRo7|8x*1eZ)^U5OOktXbXPaDS5Ne>&WKa}5x=@* z-0BrR)iFG)Z}?aD{hiTW z9A|VF-x=MF>x}OBIHNnB&ghQ6Gu6vWd->|04&tPb_~~Zc^u#Bf@l1dG^F>~*U-GR^ z(xLiEpXw^zs<-s44%4~%O#kXOU#jQ)s?KY#{_EemAWrLr_^l(xZGFL~bqCMZBm7&Z zC-%=Tl1Hm&1*V0-|1f+;7j#^U)2rm)f4@zGvZW##IG(Hw|a$7bqvqy z8~)Wjc~uYPTRR=jA#1e zpD*fs^Gp5DN9#iVS}*e5I@0xEed#)}?sWZFkGig`Q(bS?udYMwU7z}Q-HOxoEPmIy zal8KUXrQ;ENAa{y#ozi>UfRo7|8x*1 zeZ)^U5OOk=~lg^XLXp))o1!wxA{^%=T~)Jd-Y%c z)&+4|FT`&hF>dP%KCL@=wjSZ%Iwh~xFZtF^hx*f}ICLvMJsX$K@u7b_`4WGAm6!JN z)ju7?Ngwgk&A91_Pdek7{`lw1%;UXZ_I#ju=ea@i(es4nsplKbU(X+!*Pcr>-#xFW z4tS1Heeisvx}m*#qJMQpoa&GG)g|Lrukfjk;aPpdzq%){>Y?WYwR>(*f6o(&<2gg| zJ%4Ci&n4pHc||-u$B4h@8|9_FeDzNUaneWpbTe*x;*-vJra%7qBCqP9e4BT4Xg<=X zc}lnDFFl*rbZ)-WzdFE|>I1*38``TU`d4Sfss4yxT{3R<3ZLp2p4B(}t9$aQ9?G|N zI@F&&#i3jA>Djn+jt~9g$(Q)^tGu+Aum0&EPWp(SZpKYde9{@u^v6G6W}LlW_D$aA zop1FvAAQ5Oc{=Z|?){x_{x+|D3%L328^P59-wv)m_@;1mLwof^|LTl5)gSSzOUA8U z;Zq&Mv-*aAbx&T^L*Epx-8Y5n@0-HK@lE04KYZ6~cU<2Tj?evXdhPP`P2u?a26TC8 zFJJxBL7emvKi!O5J;W!S@l1dG^JU&c+Y;pVr$hbeQyjV#pPr3N=lIY+o_vWvzsgH{`Rbnz;-ruG z>1N#Y#3!BcOn?0I#ka`2U-pgi=ACbsHy?e|ym{&y>&;)^KyP0AHhS~jH`A*FzNKD$ z@QwBAhW6@-{?!?As)yoN4~<(r#HV_QXY~;O>Y==+c)u#qo{x;`_#WsovY9EuWs|Ddd{!vy!Pt9 z{;dn*v|fncI%3?`7kpZG@N7N8zjaDptzYu3oeuSh?73zr<-xp6Q6X(GyU<;7kO0=<=ecYL-Ub7%~QHHf9cu0rgQV1{?!4#R3G?N zJ=9)3(Z6~qPW4Cp>XLD*SNK%N@T|V!Up&iOS^=AF*I@I3vsejk4I9<=;cbyxz>mQ%y1)j|p{F_JeYJREzwObeJZ@nmvb)@*# zm&Ud3#K(FRPwQ0ttzYG(y?pgg2XWFz{B$#Jdg7DLc&0!8`693Ohw`mX(xLiEpXw^z zs<-s44%4~%O#kXOU#jQ)YW>n){nx*BL7dhL@moiX+xmh}>kgi+NBFmX$*c8CzO~b# z{`4sh-HK1o#-($7=pRqM#GhZ~rM-OhPX}?*NBnd%ZhGRA&UmIj{`oT3#nwa52by=D z8#Et1PiUTc&d~hz{Goa6xkU5b^NQ+#=NQ!o&o`pXwN% z)i?aBd-AFtdOlFQ=LYrnJfS$AGZg>fdH&G2o=e2X^NM(SjuC&)H_A(U`Rbnz;-ruG z>1N#Y#3!BcOn?0IMPAiI`8Mz9(0rs%^OSDQUwSsL>D+v$e|3N_)dzlU-I(_3iT>3Y zajHM!SC@=iy~3wDhG+E+|LUH+s)zEeoeuS zh?73zr<-xp6Q6X(GyU<;7r(2_FTb~}{nwxMwC(TrnZ@zD&Eoq#XXE;vXMFtrGoF4g z8h^hREidimtA9F(lRo07n{m?jl6Yx&PLvPK4)2Po!4Id*S~c^oYo8RTStuB z`hrjE4xX(?__t2UtMzNng5LHyBYOMK+0h&4Js*0`#-FpMcicIHdil)R)XQ_utX}?e zmi6YPz4c4~)-Q2dzr=6-GH&Y^KCNGPwtnH?`X#UGp?sTnbZ9=(r+G@Z<}W>)*K}^a z)4w{vm+Aw*svFv?C;C@s#Hs#>UtKb8^$MTr7@pNP{HuHNsvgR>b~@CbKE@4TL~tarZ8S=L(z<}B;24|DeT)(!2|6aA|*;#7acuPzz4dWBDQ4A1Ht z{?$EsRS)Ov?ronly|@3I^}TWC4DgLVXM^v!b7uJRnX|-~=iTpo{_>x*$2TwS)kFQO zhvHNZ#jhS3w|aytat{?h$UGb&sjbB}d z+PgmW@46MI>skD+bK`dXsovY9EuWs|D zdd{!zQ?$2!>EHS#PV1NWtzX7%{lcg93(wXs{9C`|)%qph+UZb#`V@z5#iwWE(m6i# zk0)Q^&#&^*UcUOLgE;9Ue!3YqJ@H9rJkuZld{O7yAFBV&JL^L8(R$H5wT?7@tuM`M z>rV6CdQ=^-PE{YQU+tr`R}b~C9*R>v6u)|C-0C4d)k8e1hxk_yMcF1 z!*s4b)4#gSm+Cpcs`J{b|N6Hsh|_u@e(Q*FTVL>L-NCc<2>;e8d9{AYw{|+zpFYK* zTk+}HxO9#W{o~1(`17m0w3n~`=^#$}h@Wo8O;3E%8PD{`KVRfkJ(O?rjtk~S9L>s^+f;bj5yUF@vBS5tzO|%9mBKwhJSTWUXQ--=DcP3 z)=r1|)2BFeD?U9Nm(KB_e?0jTe}0vh_VU#~9mGi=@zc$?>4{G|R&w+r+O%U_0YK0Lwu@-cvcVbuO801jyu2RT*UQp&P!Z>=N!fLea=_h z>tW7a-0Nh{W8CX!&S~81YR+%m>&-WXyAHK?ed^zJD^Az5_+975?fS>3d4Xs11^?!e zyqaHgj^(z``Ig&%&b{0?a~|f#pK~&I+&MpU`OLYR%X7}#T>icRU0&LoU-~z{#A$ws z-~2Le^9!Hm7oN>8{F`5Mj@izyIR|Wgob$of-#IsIegB4+y=||DIcIFIlR1BEub(-W zY_F?1uWYY3-|X%>)ZYBkzxgFj^Gp2ZmvNh4_%y%pY<}V2{E}DmYtC)k_BqdO`@ii^ z-?DM${I`ui=fdr{b6(u?nRDcpr*C%0-#6CFOMCN6|K^uC%`fqrU&d{I;nV!Wv-yR8 z^GjasH{{#8Mu*lr`m_$xt@V+ft($aiJ*9u^EMHoG`PI6tz4coE)^TxK-^Fj;H*Wg@ zeA*}A+5Q3l_7(DKzaih+=}>?A6o+obr)T5RIX?7{Ctu>vukzAfzWS$wIO!vPx*0b; z@kwVq(;xqQkyrZ-`8Mz9(0rs%^OSDQUwSsL>D+v$e|3N_)dzl6H?&s|^{*a^Q#};F zdT8A0AwJbZJgbNJR}bY?J(O?lbf`alibJ>J)3b5u93T3}lP~e-S9xhKU;WcTob(Yt z-He-__@pzQ>5qTD%sJ9q59b`_op*CS^UlXPw|VF3oaemrcg}gY@16L*rHt@u?o-Sv|zRdMK~z;hdYj?Q@>?_MdaMH_n{D zz47Ns~%{j`#BX!dHG^`OmrEo0s|LWnq zhq&`=-s4*z=l#C*ci#J3-{*b6y&mR0!M#rA{lUF{=DotbuI7Eiz21Cdz3WhW*Qfqn zx8ig?i{Eu_+^&ConiqIBU+`}p$*cJ_?_F;DypOs4=RM7hGw*M1{CTf)$DQ{*m(RQh zx;*Fo(B(hxjc#7rn_v1jzr<;NiQoJ(Zu1MD<`Y?`Pq5joFajJ*nR}YO_J;bMah-dW>|LUQh?73zr<-xp6Q6X(GyU<;7j?e*rT*um zbs>MP7x``->3Xofbe&jtx_+!jU02qrt~cvf*P-^VPyM@Y#p!w$zw6w%UH|wrFYs)> z;NLuwSMy8#uid&(f9pkYtRuy@zBI0NCqCArcv`38Z~ZDS?d7X~I*5}#;-{N&(-WU` z#xwo#&lh>MKa_8Ek`C2R`czlxR=uTXb(qf8XZlyS`BFXSSL>Jd)-U~Azr<<%62JA! zxUFCKw0_~)`h|b%m%LiPQA5I(5?9NY+O3WhyL;8OZ@p&UfRo7|8x*1eZ)^U z5OOk|04&tPb_~~Zc^u#Bf@l1dG^F?0OL-{uE=+JzmPxF*+&0l&p zuj$-;r+;;TFVzQrRX4O(PxPJ>iKF+8hp_*eJjRXvn%?R2O=eTqZ3 z;?uKn=^P*W$CEGd=T~`YFJJxBL7emvKi!O*p7^9Qp6QQ&zRbFORXv<@&aawxbN=~N z^Ks5aziOV&dFfZp-#JJ9s(C%cE`GepP*#bK0+}8``TU`d4Sfss4yx zT{3R<3ZLp2p4B(}t9$aQ9?rS++dk*jZ~r;Re&fvf_8WiBz29-?JpAP|=j1QXIX{2- z&$;@Wm-h12KOMwLAMw-8xao;cI^&uC_~*;~-{GqL;mxBi7!T{Rzn_l@6u z)jWOQw|wta^Y?Av_PVR)^{f8T_gyvL-~5li|EfCh)>}VtRekunPyfJGbwhjgME~lH zIMpBVt4qeMUg1+6!?XH^e|1k@)x!^d@rB#|@h5-t_WvjEf8NG<->1K6x4{G|$eH^Ov5@YdSaI>0ce-OZ9r2;(b*Jmcden7go$7kCesvvc@A}lg>sFkuXYsqv zjobB)PxAuL<_rGKBY8Ey)c@M83-z~N6vsMJeCtc&T6f}OJ&LDwD*o25^3qI2tCMu7e$uD9O1J7QJ*&fXu0GShy3LpBIlo%Jw6}ig z-})s^>zDYgU&d|y!l(5M&(<&ezqEdReAh4e)=r1|)2BFeD?U9Nm(KB_e?0jTe}0vh z_VU#~9mGi=@zc$?>4{G|Yoncq>uRNX593|C!O(3fBf@BUe!bS zHt*=reB@X2ly1#mdN!}=+Q zJ-nS?Gw*KKKJ)Q*{b!!uF3!x~+r^)GeY5OOkMe#y5wNr&nueX6T;tKQPHI!x#4GySXEe5s!E z>!QxzuKw%ax*$&Lh4`%_#%+DUr*#L<)+78|r{vZBmwaodL;dMf9J&>so{dZA_|QL| ze2G85%1e9s>Yoncq>uRNX593|C!O(3fBf@h_VfFFz1cV3u1?N=@^)s>Fw(9>{oABpJyL?yShF5+uPOi+4tVA&TFs!>)*N{PV0sEts};5eZi-72hY|c z{9C8w)%rF2{B588|Ms8zf{iox3mbp#BX-=mzgRwV-?2RBeq{O2eahygy?pgg2XWFz z{B$#Jdg7DLc&0!8`693Cp?sTnbZ9=(r+G@Z<}W>)*K}^a)4w{vm+Aw*svFv?hx%6! z#i<^OUp+K#^$?%xA)eJk{J&HWU%K^BzO~b#{`4sh-HK1o#-($7=pRqM#GhZ~rM-Oh zPX}?*NBnd%ZhGRA&UmIj{`vC5U;XZV;d#}8@BW1+Kd<`msi*wq=T$efS5Ne>&WKa} z5x=@*-0BrR)iFG)Z}?aD{`1rSABz9v_0UCL50$U}=^#$}h@Wo8O;3E%8PD{`KVSIO{E}}z(jkB8lkarvdZ1_5 z37xxs=-+k4m##N{bscK&`qaPcR-CS9@w?8A+x3r6^8(N23;xX`ezo6_Z|!ubKYfZr zx8l>Yap@c%`p1)B@#oh?UJsS8{^=l2`iP%y#!XLr(izY6$3I{A)%}-ztCMu7e$uD9 zO1J7QJ*&fXu0GShy3LpBIlo%Jw6}ig-})s^>zDYgU&d|y!l(5M&(<&eTfg|#`X%4m z=}>?A6o+obr)T5RIX?7{C%@v)uZz4MDqsE6L7emvKi!O*p7^9Qp6QQ&zF5Dihw6Xx z&brWiv|cn%ts~7}>r3<6y3>5O9#sddQ`HCSS9L>s^+f;bj5yUF@vBS5tzO|%9mBKw zhJSTWUe!bOzjo_F{jC?pv5pkq`qH@8o%mRf;%S|VzxAuUw3n~`=^#$}h@Wo8O;3E% z8PD{`KVN1ZUpK$zT#oB}obx)a^LNhixX$-E-{ZRL;o-Ypd);+1=Yd>z{meNb*Iie0 ze#mv#+ng(M-F2wF>r?-(TXDLc#qT;dZr49P%?mu6FZef)#m162kE-&WX?yr?)sT?ldik2<~*hAuD3a7 z>ALGsd)KG_UAN+NJ&WIUZrrYae3}<{Hec{>9?7fuHRnog`Yoncq>uRNX593|C!O(3fBf@BUhOyJ+qy=F z);s#N4$`glk)FG5j?S&8^lzQzOY1McT9>uAUhCgF&ac*Y@mu$e+kOC__6c~lf55+e zg}mBt$hUSn)So`ZpC$5B=lGm-zFmytJ3E{^=l2`iP%y#!XLr(izY6$3I`> zRXvn%^NtS9NBT5R>DK(EXY-oQ&3F1&2l!Hb;8*ofd-YKN>Y+H*L-DJJ#;qRWQ$579 zdWe7ZP+rwT`PNQ{`qQU4bSpkR8<)=Up?^I25`TV`m-h12KOMwLAMw-8xao;cI^&uC z_~(l{-~3Yl^U=DHzt)Rr~g9^{eYpd)KG_UAN+NJ&WIU zZrrYae3}<{Hec{>9?7furT*7$U8ukHqBz!(;#*%D*SZrQ>rp(dQ}MTcm6!JN)ju7? zNgwgk&A91_Pdek7{`lvMyjs8HTb-ms^^-o;Rk~Gg=~*47bM=}2)os31&-vB*rM>k_ z|JE;YTEE0^{W5Or7e1|Dc(#7w-})u5)-UEJ3-g)=-&%bf!Y;I~ zhxk+v@vI)=UpC-%=Tl1Hm&1*V0-|1f+;7j#^U)2rm)f4@zGvZW# z#IG(Hw|a$7bqvqy8~)Wjc~uYPTRR=jA#1epD%N+$oe(sa%}sY*RlQQ9FL9jo)0}|UImmgO_&x-8E*?`8SVIWU`-_WaU6zr@Ke@$<{L`Grq@;hA6fU;5ShCEw~K9jc%7 zsjkwkdP~phFrBN<^sjF7rFzb<>b&;qzy7TY;N+jqb7`CHHDoTaVv+FQT$Z~YRd z{j>P3U&d|y!l(5M&(<&eTfgMh`ZecDZTp-zwf*NDs*N+}Q*Hb?w`#|o^Q@N7oO882 z=lrYXKj&g?UfNr~^l$wVr}azx)-U6>e&N&lg=gy*{;gl~YWDK(E zXY-oQ&3F1&2l!Hb;8%5Cd-YKN>Y+H*L-DJJ#;qRWQ$579dWe7ZP+rwT`PNQ{`qQU4 zbSpkR8<)=Up?^I25`TV`m-h12KOMwLAMw-8xao;cI^&uC_~*+!7v25*oJ+s+ZqBRU z`8em;?>wFJ?RWmpx%Xe1*Dw4#JKyJ={H+6Xe*V^nIahz{hW6@-{?(Z|SAXk|_*<7| z-0BrR)iFG)Z}?aDfd!MPS>;eUFXK_`p2hvfoJmt|K^drnqTs*oeuSh?73zr<-xp6Q6X(GyU<;7kTwOO1{-eI#fUDQ(dK7^_HI1 zVLDfz>0jOEOZA*zJ-5-``lWyCmpH9o;q7ml7sauT6yN&NxYnKcSdZdqor=HptGu+Aum0&EPWp(SZpKYde9{@u^v6G6 z{`ozR-Fo=Rw>);|-3LGW*qx8R_Oi$AJpJPbAGh=OyZ+qccV55yn;*aP{R3}!{MLcL z^ka|T`f&G8J$~zk_UeiL)fsWBKjK%Hj9b0Jr#gmb^$q{(p1i7u-}Ez&+4fgF<1yR+ zZ~W>#8|N>6?>!s;7oKp>j{7~odH3>p#e45wp1=PicQ5}x`JuZvFYVPs{i}!KR1d|k z9vZiLh)?wp&*~xm)kAqz59QmuqeJtNKFw3QHGk>Zyry&Wo&MDUzEmIhRo&2DJ<-29 zBTn^4{OXc%t5^6`$MCGa;a}a8SM^Z7wbP;g^eGPAicinRrE`4fA5Xr-pI_yry?pgg z2XWFz{B$#Jdg7DLc&0!8`7-l(>*0JicIVxEPj=_yd}ns&>3n~7=kI)%cIWkcuXgAA ze8+a{z%)BacI$@r>WTi<8F8vV;#Zf9TfM@kI)-QU4gcz%ysC%uo!@Pr@BeQ9 z`7ZFrnePQ}{P~XXjyvBM-uIX1yTkkb@_dhY-(Q~Z6z}`X+N+29R}aOh9*SQ*G;Z|} zpXwo=)kFNNhw^HFDBtEC9h#5yX`a%p`Ag5{HJzL9^sf%^rTW0H_EFlahx%6!#i<^O zUp+K#^$?%xA)eJk{HurZsvgR>b~@CbKE6NUec#KN@3Zgw8uQ)ueUC$X^+f;bj5yUF@vBS5tzO|%9mBKwhJSTWUe&|-PW`se z_v^R+eAj;C%=hj${y%)i@9nsM@Qa^WKL7DsKeIf4=W(A|{*U{U-`%{lR}b~C9*R>v z6u)|C-0C4d)k8e1hxk_y<<Z$8o?f9aF&bnAMcXV(dxyME~3b;XyiH-2>;YVZ2g zzw1_sovY9EuWs|Ddd{z@ zQ@7?UlWXm*U;4LxiPQQee(RTUTfgvW{lc^L3;)(Hd9{AYw{|+zpFYK*Tk+}HxO9#W z{o~1(`17m0w3n~`=^#$}h@Wo8O;3E%8PD{`KVQ`O_J`_!^Uk`^e6(IPPpu=(U+YWr z+Pc$xw;ojotW(to>(}n1roDQofAvtD>Y@16L*rHt@u?o-Sv|zRdMK~zq55CDb)o*& zi{e;Eif?^sTu77-*7kD;b@NXW;tNHc1cYV#azvG!-v;E)nYfs!b zFL})qH~w!w@rgU`dp`Aq<@4k3d&2U3%8x!_`9J5aPuRS)H^206eu>lk62JLn+~yZP z%`ZHgU-&n_sovY9EuWs|Ddd{!vy!Pt9{;dn*v|fnc zI%3?`7kpZG@N7N8zjaDptzYu3oeuSh?73z zr<-xp6Q6X(GyU<;7kO0=<=ecYL-Ub7%~QHHf9bjNdUS5S)4w{vm+Aw*svFv?C;C@s z_*MN8zq(}H>J>iKF+8hp_*eJjRXvn%?R2O=eTqZ3;?uKn=^P*W$CEGd=T~`YFJJxB zL7emvKi!O*p7^9Qp6QQ&zIYDMe#7&D=AGvT%}37@nx~#KG=DvRXkL3R(R}y3qB`I? zM)kq-jn-xD)kFQOhvHNZ#jhS3w|aMuV?d7X~I*5}#;-{N&(-WU`#xwo#&lmqUZ+`iIdOrF;d;a?W zd%pX>eAk2j*Y9;Q|Htq8@&EmgLu0!ozpZa&*`aM9`v-o?R&$wOx_%tu@ zY`);%Jd#)Q%m34B_kZ^K`~Q1!{9nHK{$Jm?{*NCY|KE?N|NF<^?*Yn7d->|04&tPb z_~~Zc^u#Bf@l1dG^JTvCxbthilej+4_Y>FO`L5#nKHpp1>tVjbxYx;ipK-6B`EKK0 zSMxo`z24?Kk9!?z@A}lg>sFkuXYuzspK-hX@o8S**?hsjc_gpq*L>G<+kgF8Puu?U z9n6h0-^bke^WDrHcfO~&eC9iw%X7ZJx%}t5oST>S=9m7>FL9b*;y1sH+x)_(`Gsfm z3;*VqyxMQbw{?vUt#|Zk9pqQ*BRyL;>D+os|JGT)wEps|by<7swf?Q+;Y;p_cXVhz(x-V!x8^TBo7Z%1zSF-tz?bR+zp5MBt0($bXT+)g zh+kbYZuJVE>KLBYH~g!6@~R%nw{|+zpFYK*Tk+}HxO9#W{o~1(`17m0w3n~`=^#$} zh@Wo8O;3E%8PD{`KVLrolRtR zU-ACy`EBIEk9x}cujjXs2mjO0J#an0jXe0jedK}b`EBIE@BN7fuIIOr2jBJm4_wc0 zBM*Mms~)(X-$ow%!k0X7J-_)p_+{Vn!1eqVblczl`5UbN{C4!Ti!;9|Jy`ttt?9wW zo!_7yjL-Zw^(HZKfh%?SYEYX|EKqF|7Sev!Hx4v&wg;@zvR0f+;QLjBM&a0 zzw(O@UdQtrKl<jI-kmv^ z4)gBJ!StDTXAVBs`Ri{mJ?Gt-(@y7kcjo4A$FF&J=3su!J3$BY>)CI=!P@5?qU}HL z79A|kymNH0`13B(!N#3;ln%yc-d#Ev&v~cmV1CWJP6was@J_pY>raQ`(5LuxYg~H9 zhtBb&fBgAUUi>Ow?dhO@`iL{{935`rr>Ak#8K3mWGhgtZ-x^?c+x-qd?_z}m9O@6 z&_8{|ncw6bZsMn>anl)}^v5$_@b`_^@|t_YgXKH-h6mGO?hOy7&)gdxe6I8P#%q4f zz2U)ho_oWC=|A^|2lH$0c@O5-+zW5}+#_%QxpzKToVk}jm|t_ReXw!o9{gZ@=HC2Z zJm;SMVEpG^{$TT~cKOzy4#lBQ@#)sM^o$Rk<4OPc^QFA_RleHOLI3m-XYQ#FH}TWc zxao{f`s0}|_|M*T^P0Wu<~w`WgXu7P*MsRZd)I^MHhb5D={bAXgXuhb*Ms>rd)I^c zHGA@d`89j>ZJ#~-_Mg4|!Q#xG|6uXwUf^Kk&OO4x_{_b-!FbL+#lifVdyRwnRl9ua zPlw{rr}%VhTzbZb&heyw{P|K|{3>7V>7al5h?8#Or>Ak#8K3mWGhgtZXPcYXJlouS z=h^1LbeLzG2h(SsZ618C^Vi&9dd{=W(@y7kwt4fnxP0KES|v#&iDneK7v>zwd+jRl9uaPlw{rr}%VhTzbZb&heyw{P|K|{3>7V>7al5 zh%^6#KHS7lPvfRDKIxBVzTiK^hV1CURp$GG8zU{T`^UbgAKi>j7Se*Gr*umn@x5ExL?tD}1V0`9VV+Z3o-yl1f zU-NCUgZWjveCtn#;?Sq~bZcCC#)r=Fq<{SRQeONjU+w9jfBJ}%ZsMn>anl)}^v5$_ z@SkrdZC+pa$`5S5^X;UA=`i0;I`~}A_kHkSy3Mzf4yNaPJLzCL&$p8f=GS~X>0o}% zv&)0|HQ$Qb_W6d?_MdM{9W2g#bLwF6=UY?<8+X1@bud2j?W%+EoNrnk%&+;@)xrF# zUB30FLviR+e7ZF*J>x^?c+x-qd?_z}m9O@6&_8{|NjLH5TU3Xqanl)}^v5$_@Skt- zY+my%p3Qf@#d9zn=36`m(`UZLb1>cJTRaETbH2rMFrDXHJO}e@zQuDezvdf52lH#b zJ+$rfO``4pf}j4`gT*2U^Npl~`8D58I+$Oz%eVe? zC=Pv!Pq)UUXME@!Px{B7FXhFr^3|RW`lpXL=_Y=98aJKsNq;=^1^@YW?dCP#uHAg+ z+qDPNVZL2^Fnyl%qBkE*w@?1a4<1a<`F8EWbe?b59?Y-#cJ0CZns4$R%&+-Y@3zl3 ze7FC6+xK8`zTstWJ6Qbr7VyEwoo@smjL&>K_+UKeo5Bb4YrZvnFu!V-Z~f^|9QqWW zZjDRN_|Q3?^p8JZ%8Os+t34g`Pakp8P5ksUZaU+W{&?mK{y+NL&)>YBeb);%-#>oK z4W`4@U;o>uoj!l{Z@utfy8YqXUUV=$f9ijK%fWR1qo26{V1B*k#VLxW zzxwI%T0SAjS-xN4l{Q1_v!N#3$5FCupe4F54Jm;GQ2lH#bWpJ>( zYL{>Q=};W{6rXO5OV9YwIiB>7KVRm4`HaP{^3|RW`lpXL=_Y=98aJKsNq;=^1%GGA zcmL&Vd04*Akca8u40)J7&X9-c<_vk5p3abm>Ff-7m|xD2hi~TB#}DS0GuUf)HhcY@ z*$#{2EO%IZXS~D4b@n@qk2B$6Je?H}(=?c@wnXWM1oaqYF z)0wU?ot^0l^UIm8@SS>iFu$CMTD!AS>+cLzSR7}o!s0t~6*jK3SYdpe(F)_~>{ggx z&UA(ORl9uaPlw{rr}%VhTzbZb&heyw{BQhv=^2Y(<*Pj%^iLmg(oOvIG;TWMlm2+- z3;xbbE-z;$m#;IEVLCW78K#djlVQ3!Ga06*Gm~LDJ2M&Pmot-Le*N&bzw@auznnQ- zyR(Sv?~Gzt9A_89;ycqAHmuET@zoa^vl{HJal%&*$zTYowfhd#wW^XtyI^o$Rk<4OPc-5NbMEN4CFnxRz3Z|QHLc#R(O(>Yoz6k~M%QvB5e$77WV1D_gQtiIA zRDa)Kg2nM|CRlvmY=VvJTTU=OzVQU(>Dx~*{=NwXn_sodxBhe}4tt2=04@%JN58je$9Q#w$FXa_MiKdgT!?JNGFE z<1_au2je;SDF^dw?kf-GSMBnxKOKrgpW@T4ap@T!I>(d#@xPg0FFj-Nt9-SmgZ}9w zPP&Pop2kgQe9|A!e8GR718iRN9ANXE=Ku%OVV(mVOrLoUa4_BGIl#g6oaX=s(|Mi) z9L%qI4sbBP<~hK@{F>(g+dj_$w*Nc_I9Qx{4sfve^Bmw{Q=};W{6rXO5OV9Yw zIiB>7KVN=jzP)ZNewDBGbkIM2#7Q^t)6=-=j8FRGnJ@UybL`D)o?~ym^BntNI?QwI zgXuHRu@9!(JjXtmp7R|0U^>rp?1Rm(d5(QBzvemi!Tg%%*xNqOvA6#`$39q`d5(Rs z`12h5VB^kn?1S-{=hz41InS{V=GXk+;b4B%F5mjop*Zv@KHVCZp7Eh`Jn0{QzLXcg z%2#_j=$}5~q?`EZY20+iC;jov7yRe{M4Q+ApJ?-){}UZdhxtFz!StE`6CF&q`9IOY z^ql__9Zcu>KheSbn*S3We6xPtV1CX2iMIX4FaOx~pZ^mbEYAF&=wR{Z|3n8Hcm7Xw zFh28tqJ#0A{}Ua|ulc{;!ThRSzV)X=ap+Tgx-~96<3s0o(m(!ung4&CvG`TK+S5V* z^bsfB#7|G-rZYb2k7vH%?;Zc@hIjm{C*JXg>EIoI_*~EPjz3Jd`9JKz^z@Fub~<~< z|NQOv0N%9U-P?^gZWjveCtn#;?Sq~bZcCC#)r=Fq<{SR zQeONjU+w9jfBJ}%ZsMn>anl)}^v5$_@b^xu9OdPm*7EgEYdUzR6{e4OT4B0*rxm8B zcUob7d8ZZT*C*$lR+wMjX@&VUza!dq?~2ynJEX8U-Ytd2_s%J7-1!~R!T5Mb_5AJl z<=s`7U*2hjraQ`(5LuxYg~H9htBb&fBgAUUi>Ow?dhO@`iPTm;-{x^(;1)i z$1`8>_s)2Ed1t(Qy)zEGZoM-O)8}1Zaf9jRopJ5-^v*a;XYY)kza784GY<1>?kf-G zmv^pf_bzt*y`v3_YE!FrMD6gZbs1JD6X!%eVe?C=Pv!Pq)UUXME@!Px{B7FXhFr^3|RW`lpXL-c`g+ z{PZ+#I^&c6c;*ZK-We}1?~IqPcgA5lcxN1@k9Wr5bDhsS<1jtFGY-?)JL53FyfY5- z%RA#Rzr1r@yLYkc?;UMe9Pe(!;(MnXHm-NQVSKy;4&&+FaF}1-8Hf2*yL{_UhvLwu z_;hPrdd7#&@uYwJ`BGl|DqrpCpnv*^Gr!M2+{8~$5pf=;O|V=^16G@bS+>APbr!33e4NpG{&sjeyA|e_GhJbR)h^%q)1f%@DL&mAm!9#Vb3ExEf4-C#zsgs8 zI_RH1;-s7S>1o__#wY#p%oqHfnOt7ZOfFw%Cd2%4W-?44XC}kvI-fI>VR||<8K$!{ zlVN_%dr}AU%bCgA`8DrJZM(CG>+g)>;>>$e2aE4aW9`Ou)-jBaGmy{U4o_zz!~Ak) zGR&{q=r(5IFGd^^VC;j8km-6CQ`D#xG{nJMrXHDZKetH@=o$*P3Jo5#A z-&`v%-&`wS-&}+F<(q3TeSC8brkiiB!SwXaHJD$%xd!uV-a|Z?U%t7fonO9L25a{% zv-#`Wzj z7$4u{I)6JneX9%Rmv4B%{Hk5P^`}E|=u>>UH7-5lL+5zXKmL3vFMgG;_H@uceZ-mf zqYpRn)6=-=j8FRGnJ@VJCRBO(CRF+QCKSvs--LqcraQ`(5LuxYg~H9htBb&fBgAUUi>Ow?dhO@`iPTm;-{x^(;1)i$1`8>w-^{O7Ah7!gXM@1*Bb*rmyN_^|2<$$>86&X! z2xpJLowZWCvr6jk3=>!!XPdy{JM#oKE^T3aoRI?K>FgBPeULL%V0k_Iz8mbmsdo2M z^>?3D9QR+vcVE`H?$_euJ}#c_@8aKCE5_AczWS$wIO!vPx*0b;@kwVq(;xqQx%3Nu z5Ph4FEg6pW`creO2V*;BB*oJj?{Zfkcv*WYzs z9M^yG&5Oo0U*cmP#nb$Xzj;?)+RIn}bPy+f#7{TlrYAn>jA#1epD&kw!JV%t_s$uk zN#~Ezs&mO`*m-5N?Hn_jcfJ|#I`@osorlJ|dG>wIP}2U$`ENJ#Jw17s&b&*1-sQ`s zU*WD>ec-%<^A65CIPc)RgYyo~J2>xZ=Ux4s-3N=~>^@k0XZOLzb#@<&kF)z=Je}PK zyY`&j2g}RZeX!hXr%C;3RUFrU@y(0IHDBUm9>vrAiobd1nlzSn*D9>PYZw;CwGE5! znum?cJ2>y)yo2)&zVyp8wDy^vp>_V4XK0;E<{4V&m3fBNIcA=rb-tNrXq|iJ8CvI| zd4|?GX^)(f`SYjdc;=aIU+y`XmwttLns;#C!FdPg9h`S?-obeX=N+7PwYN{xzx|sy z?d!yEzh~U`f%vpP#It=P{_Q8_)jren-r79}uD|EQ#i3#GY1_D-GsnmC=XiQ99skZa zm6!JRnfkZS6sLV=-szurFh1=w@ob-ofBVc!zx*$+_0IqDs;mB&SH1PWyy~$3y)yo2)&&O12o;JmB7^+NyF5ph~y#Bbd(ZtD>~ty6fme&OG`Ca=~zxz|pU z`qQd7G%UXVYd5a{cgM&7!Q<)w|@mufm&fn%8oOf{E!Iysd zpKR-$|H-!A`JZg-o&U+U-ua(w>)pHNf85n=|C4RK^FP_vJO7hyy?f-`^_%t1|IpLz z%RP7f(yuU2^A65CIPc)RgYyo~J2>y)yo2+u_SOsiTSvrceG$KP$GELW__R*p+4_Zl z>zce;@BDtCcE2mAzuy}ahla(cZR7ggLVWz5A)bEc5dY51mzVa|JN;Yl#A&_DJN@$x z#;5fT&(=HqTkkIYg1b+bd*>35qTDT>2H}d)~o$2j?A}cW~apc?ahmoOf{E z)!uW7ywjd{aNfar2j?A}cW~apc?ahmoOf{E!FdPg9h`S?-obeX=UweRSIIl=c?ahm zoOf{E!FdPg9en8*+&)w8?PqAxK8IHAe`wggh_>yQXx=`P7wt27*FKYXJy+3gtv3ht zw+Dd5u{VIlw`YKjYcB!gV~+vjY3~8!Z%+ctt8?|`UOP?dPpjh4u=uoXT$;y+7xCm> z{CQVi+RIn}bPy+f#7{TlrYAn>jA#1epD&kwg?XBHaNfar2j?A}cW~apc?ahmoOiXi zPs=;)c?ahmoOf{E!FdPg9h`S?-obeX=N+7PaNfar2j?A}cW~a--aa$$wC5e1cW~ap zc?ahmoOkf0Uvs_eKJ#BZ^1ZV&XZ=>$Ud8Sg4`+t+)MdP5q-$l2N^1JBvSAG}W zzN>H5>94(gn*QzI#A#nAe)~P+whzRo{UM(18}V;HDX;dKeg|H=--p-V@5YNm!{X;1 zo_Po79h`S?-ql{dd8a+^;JkzL4#p>)@l1dG+h<<-q zd>8V}HSdPB-u?glF65VMz#^taku z@AU6^g*ZLO5WnXe#_hQWK0Ob?v*#rE_xwa&Jy-F*OzqyIslWGYisQYT;(H&balNM# zAMfwPGwUUXl>qwaTj*L{%o?vM2EzDby)yo2)&&O12o;JkzL4$eC`@8GNzXHB)$>dm_B@le z?U!iYK8hFZuXxwKi+AnEw6{;wzx|sy?d!yEzh_)~3Hv&H>@i?G?LA=p?MYyH*{i^E zubn3Kr&V!iSbW+xF3sb^i+J)b{=6$M?d7X~I*5}#;-{N&(-WU`#xwo#&zDQT!aU78 zIPc)RgYyo~J2>y)yo2)&&b!*%XXc&uyo2)&&O12o;JkzL4$eC`@8GxZZ=acW+Vc+1J2>y)yo2)&&O7+hFMH0`JA3Tvs=ash)}FjNY_DE@wui57 z+uK*q?fI+o?ggsx=lUJH~B2!l!i#&(<&eTi4{(dS{PayS;b) z?a7N{uU>q6_{O!jkB>cnJl!M2-#tQkX)j;>(?Oi{5kK9Go1XZjGoI;>f4*G$73OK) z!FdPg9h`S?-obeX=N+7PaNgD4dY5y)yo2)&&O12o;JkzL z4$eC`@8G-{p!j~1(71l95Ffu`h^OB+#NTfo%1e9s>Yoncq>uRNX593|C!O(3 zfBf_1(yuU2^A65CIPc)RgYyo~J2>y)yo2+u_V$^1r#y)yo2)&zVr)jpDFkDGc;+RL#y^b zG;Ci)+xAN|Zy&{r_E)@X-^IK3W7^xN>EHfMoc49%x8E~v`#^l!AL7}*5&!m+@@k(c z_u6Sve_9oXhQ+6Cy)yo2)&&O12o;JmB7eP-Ti&pSBp;JkzL4$eC`@8Gy)yo2+u_V$^1r#EHfMoc49%x8E~v`#^l!AL7}*5&!m+ z@@k*y-Td0UvtNJj@)yTD{>At1f8#n6AU@6th^I3I;_qyM^3qy)yo2)&&O12o;JkzLuJ-nsd8a+^;JkzL4$eC`@8GJK*4z!IFdM6@5%-abwL_HW{}uM@xho^jg; z;?w>R&-RV@x1W?(`^@i{Ga_nt_Co!g$xs|;H5A_&4vp(Yoncq>uRNX593|C!O(3fBf_1(yuU2^A65CIPc)RgYyo~J2>y)yo2+u_V$^1r#y)yo2)& zzVr)jpDFkDGc;+RL#y^bG;Ci)+xAN|Zy&{r_E)@X-^IK3W7^xN>EHfMoc49%x8E~v z`#^l!AL7}*5&!m+@@k(c_u6Sve_9oXhQ+6Cy)yo2)&&O12o;JmB7eP-Ti&pSBp;JkzL4$eC` z@8Gy)yo2+u_V$^1r#h%V@oC$*G>;E2;>o-C^RB$Km#_ZmAWr&-pKiuYPkhoD&-BMX zUoQO$^EB_^yo2)&&O12o;JkzL4$eC`?`m(KnRnXr4$eC`@8Gy)yo2)&&O12o;JmB7eP-Ti&pSBp;JkzL4$eC`@8C^WQS?6Iq>_TJT7d-CeA zy?XW89=^J5Z(lvP=daGYN2vb0N7!{?+FLL5Zygb*^+o*F9pknh;nO;WXX_XKt!wgX zy|c%z-QK(Y_Ty)yo2)&&O7+hFSz?VxpyBylkP8Q)qMvI zyC0!#_bD{*{)HFa*YK|U9p3GI(6o1dq<{BK;&eYHe)n0%?fwg&?#uA(ehvTbYoncq>uRNX593|C!O(3fBf_1(yuU2 z^A65CIPc)RgYyo~J2>y)yo2+u_U`ZUPJ7(?Oi{5kK9Go1XZj zGoI;>f4*G$73OK)!FdPg9h`S?-obeX=N+7PaNgD4J~QvM=N+7PaNfar2j?A}cW~ap zc?ahmoOf{E!FdPg9h`S?-obfSd;841)1G&5-obeX=N+7PaNfa}e!=ZC<=%dVChc=* z)&7Tu?TcvJeu?Joqj=H&ig)e1c-MYRd;2u~+rNp^zE1r1d&X@ah)?@NJli+o-+oeF z?K95tf1wPFeJex=OH^1c7 zymK~b?anN%zq3q>y)yo2)&&O12o;JkzL z4$eC`@8G9seuTE&r_j9n7hZHKFhe>f8o=88J^v*;op6n zyt==Wd+ju-Kdp*G!{XDnacLeOUc{4k@#kH6X)j;>(?Oi{5kK9Go1XZjGoI;>f4*G$ z73OK)!FdPg9h`S?-obeX=N+7PaNgD4{axN^&pSBp;JkzL4$eC`@8Gy)yo2+u_U`ZUPJ7h*WldT}0j!>c#Gv)LQhneFj$mU}#%@g9F?zn7Qx^3}il zJ8{xS{O<3Jo1XZjGoI;>f4*G$73OK)!FdPg9h`S?-obeX=N+7PaNgD4{axN^&pSBp z;JkzL4$eC`@8Gy)yo2+u_U`ZUPJ7`z4yUkK#r9E8ey5;@ymQekZ2AeVYF5-^6KOCw}`q zy)yo2)&&O12o;JkzL4$eC`?`r=)?A>{=byazwaRnSm07Z}p%BX-0#sP5r zKvW>&fC}P(2-Qa8MARh6Bq}n9IG`c|A_zFoAW4|M@7@?Y#t9ijB_fIlsKh9392)5W zeV%jgZ@DY|Ust87yNdswdTX)vyWZ!Xz23F=;XC?F?uv64a~E?La~E?La~Ds2^;;+U z%pGRG?V_LQw@&mq{nm;8r{6l!7xh~w`lWvBL?6{}o#?OntrLA$zfGebE3Qv#y#B3u z^mWaz-|M>i!1B=_mZ!e4{PmNqOP|?qyNLIjFUI#_IM?LPc_(+{95jnNA2r^&sd=2In%_CA>pI_+k8@dhI%EPy zCpS;My7}wjUANv|KK1^Qp+3(K3e`)F zxj$d_oky&4-~R1CZokU?{JUS=W|jN=6*q6a%Kd+br*FN=zEIqL(Rlkv^VnaS-@emz z?MLNfpDIuLSNYr5T9^IqoQFPt#E-t`0b~4)hrV>o^Qou3YRrG!b6z{Hd%(;7X5@3^ zUmP;>JbLHDM*f>#d)Qc4aqDfoIy8^^G{3raUG*#I>(QyO_I}yO_I}yO_I} zyO_I}JMppKExRkuUCdp~UCdp~UCdp~-Ew^HZh8FNUCdp~UCdp~UCdp~UCf=h{f@ih z+{N6*+{N6*+{N6*Q(v*?Dy`l5y_z`JS1afJYUnvYwe@_UntN`LJI@nx=Q%^}W_#`Y zxk_=*B^vK}Me}%$(fpoobY0Iq%E$AN^7Ndf{5?O(o#!g8UA&qYU#-kj4b5L|UALOc zCl~U}o&0k*S=UPIZM-@(kNPyfx^-RkEFX0)PxUW!Wg^zsjAyD|hoc22pV|ES%&x1?EFXPldFnIEU!R#feP(MHuO`M*H{g*r$Isox+{N6*+{N6*+{N6*+==Tmxhu|H%w5b~%w5b~ z%w0V7)fvHlSC8$!TJPOXj=SRA z#oWc*#oWc*#oW!uFT0Dmi@A%rn~z_17jqYL7jqYL7jq|WzvHercQJP{cQJP{cQJSK z@ynkz?0nbSog=D=^F_6C?x=>&Bh}V9rJ6gx;YJTUe zuIv0&KF($3>AY6{&T;)sI^VT+@oHjxwK7jNG=H^q-D)nMT*xzb^3R=h6}R5Tt3&gs zPxGr=*HzE*QRnhh|MKUhb@7Gs$X(1`%-!7evb&hOn7f#}n7f!eapybkigOop7jqYL z7jqYLHy^+3F6J)gF6M4Ne%W2jUCdp~UCdp~ow)NIcg4Ajxr@1rxr@1rxtot)cDKY= zjOUpTJK@st+-&EKzBZnxz4Q7nkLPUL-1?>Q{B7mIUmVZnE`QbHcwV>bzpfh3@fPk_ zIiBym=G>LzxnFU8TI2O^&7-ete*Iq8)d!Z3{;)jtjpeVO{M33^jOUqKe(0(Z-(c;l z$M~=8e$AL?n}`2k%zx_n*Ny8Qv+DYh&w4xGF!DU*p*N2FZ#?wIv999!%*N|8n@6A7 z{QAtUtIsSSeP(&;Gs|C}*}9wya2~mfxr@1rxr@1rxr@1rxr@0I*JpB9oV%F2n7f#} zn7f#}n7f#}n7f#}n7f#}n7f#}n7f!eaeXFt#kq^Qi@A%ri@A%ri>JO~eP(Od&r}nA zPPNkiR6~7Hwbd_GbA41U^jEplcjZn$R$QOfc>P=R=sE95MCle^;F#oWc*#oWc*#oWbHU$fuB8@~s1`&Ao{-<^5=J2oA^M|0WMn~&eA zdGi@tjNh+$^ba3Ae%EIE8y+(L{r`hMvgP<)fSoqnYW!ZnwYzRLen+6VzuU(9du|?o z=gsf$zw7#3l#kC#dHNiczt30e^0|A%HSRa^Kj+$Y$GVF9+%?|ku6ca!n&0QH>-yZ4kI!9s`rMVj&)w7) z&M9{>cQJP{cQJP{cQJP{cQJS3K6l&|=Pu?h<}T(g<}T(g<}T(g<}T(g<}T(g<}T(g z<}T(=+~Xdd-xes$}*>RCSOT%PJ*{=7_m;hb_8a~E?La~E?La~E?L za~E?b?tI5xaqeR7V(wz@V(wz@V(wz@V(wz@V(wz@V(wz@V(wz@#GUWBE6!caUCdp~ zUCdp~T|D(Q+xu2HFUf-~#cU5<;oLFXTUR)b%=X+B&MC9Kc!l%JY>!^y zTr=C#S2*v?_Vg8=w-3moIlk?pQ?-6D_%!to= zn=yXY^Ne|Bz0jC{)+3GU&U&Yj&#b2!dCq#Uk^ig*8|x}=y^U9g=24&KSGTUKp5>#? z<*EMV&&$*o&M9{>cQJP{cQJP{cQJP{cQJS3&Uf4u=Pu?h?z*{)xr@1rxreKw{)^*jheAKx-)xZ3Cnfk&xU7_!qJ+ob*A1kg;YrOugdGvM7uixvs`oQwhAC{-SvHbOu ztxKPI{vA&p@!7NMF@E+;d(1O?);;E*Jp&)tojn^L`OKb~k3473*hl`eXY6BL#jUsT z>d-vu)BNhzb=9+c)VVy>zx;Wb`ocNoF6J)gZti{AUCdp~UCdp~UCf=hK9jrR+{N6* z+{N6*+{N6@$1l5!xr@1rxtot)b{BIOa~E?La~E?buFvGIICn93F?TU{F?TU{^YP1{ zHEh3Y?e449#QnBfxer%E_vdQszFp1T&vW5EpF8*e+}Rh3+bF{<*WR;?~=Eb!Z;-X?}I< zy6Raz>Rg`cU;ezbF1~Ocxr@1rxtqIQb{BIOa~E?La~E?bZolKMICn93F?TU{F?TU{ z^YP2>V(wz@V(#YSm)*tO#oWc*#oWc*iQDhEE6!caUCdp~UCdp~-F*DAJM4Vd+MOe+ ziStFZa_*>x&Lh>`D^ z{(m^%J$sz*TDy2PF}_-vry82S+PZEvmrpL_nLGLC&bo?QZ{yXWdDN%*)vfEQXZfge zd8&W;^U`OHFPum2V(wz@=B}6B#oWc*#oWc*#oUQI-*H!*yO_I}yO_I}yO_KA_}Lnr z@3~4v#7=30vwtlAG zTc1-;uK%f5*B8~p>zC^7^-=Zw`m4?e`mW9h`pn|`%*N|8n@6A7{QAtUtIsSSeP(&; zGt2)EedZOT&#cE5ulF{-p4>e3>gKP9cinn>`PB2vvonJHJ0n*|aUa~E?La~E?La~E?La~E?Lb0@CPbHlTJ>E}k_`S2od#l^lJ7>Jlx@_xn z#(S>f`n1OD-Kn^nKiRtUnVW6@!4ZGyvrix6A9M5v#yr=3 z<+L&X>RX>SuKTu+o;vb*>29ZvJda)T)RF&rzddEFtGGV1@%qf>(PuWlKC|oUGs{Px zS)TgL^4Dihec_yP7jqYL7jqYL7jqYL7jqYLC$7)rt~hrwcQJP{cQJP{cQJP{cQJP{ zcQJP{cQJP{cQJP{cjEd??uv64a~E?La~E?La~Ds2#rl@kuAiwU`kZQ||EY%hqH3#O zs^I2J1e^{RS#`4!swl41xTDy2PF}_-v zry82S+PZEvmrpL_nLGLC&bo?QZ{yXWdDN%*)vfEQXZfged8&W;^D^~?bIM)JUCdp~ zUCdp~UCdp~UCf=hK9jrR+{N6*+{N6*+{N6*+{N6*+{N6*+{N6*+{N6*+{N69>od74 z&Rxu1%w5b~%w5b~JoUBXx)+T1=2!jtg7JR#-IrfD-rKG`^P=%Scl{S!Jl^x(a_hz8 z{qL*aaLITteB$>n8SjfeG_qy)r184c@56e^E zSpNFS*5!HT`~URsNBnzx|J@k>xnuu!%=6r@pFie5e4F#fb#MRp7e+qU?D2(>=kNdc z3nTw6Z#{3UtGGV1@%qf>(PuWlKC|oUGs{PxS)TgL^4Dihec_yP7jqYL7jqYL7jqYL z7jqYLC$7)rt~hrwcQJQy`Q$Fb>#Aq@sB?L$fBEw=^@VfFUCdp~UCdp~UCdp~UCdp~owz=eyW-r%+{N6* z+{N6*+{N6*+{N6*+{N6*+{N6*+{N6*+==Tmxhu|H%w5b~%w5b~%w0V7H9PB#KJ%%+ zyJGY+Ykcd<(dRt!>~D?!=Y;*P8hz2r{?}EbU;5D-zdib>HGcT*(O=#8fbWdH>!R(y zGy1XO`n1OD-Kn^nKiRtUnSb=i%SU{#eJ>m1w>bWrW1g>F zdg++|m)l)BuKPEi`o_rTS$lqCzH1)myXJSk>$=W&<>P!;p3ZmW?|j#~obOt@cr`J;TA8OBn!nn*ZZ(%rF65az z`RC5Mid%2v)uDORr}@>b>#Aq@sB?L$fBEw=^@VfFUCdp~UCdp~UCdp~UCdp~ow)NI zcg4Ajxr@1rxr@1rxr@1rxr@1rxr@1rxr@1rxr@1rxf6H3eKw{)^*jheAKx-)xZ3Cnfk&x)P+i z$9`9y_Pg@8-%WktoN^a)7jqYL7jqYL7jqYL7jq|WzvHercQJP{cQJP{cQJP{cQJP{ zcQJP{cQJP{cQJSKG0W~^?!@hP+!g0;K4#fn%w5b~%w5b~JoObj-?et3CxwEd~*4ub>Xdd-xes$}*>RCSOT%PJ*{=7_m z;hb_8a~E?La~E?La~E?La~E?b?tI5xaqeR7V(wz@V(wz@V(wz@V(wz@V(wz@V(wz@ z=3|!K#oUQI-*H!*yZM-9cQJP{cQJP{ck$F$tj}!i`k88?}WpK7Qts-V~@KCpcBhvlhnEPwrE>(XbocJXRre6=!9H8g+j zT(_FbCl~VU^Ckb>SyyrEZM-@(kNPyfx^-RkEFX0)PxUWS z^_>TOSKoQ?{Gqr$v+?@O=Fw+1zdp0;>NCqnpIM&z%<|V~wk~~U-x(0^y9CDf9Ru_9 z-2?OYodnnIy9)B@I}GydI}h^jI}g@X+Hpa`fB!GP>-PWn%cuYMU!MJ20rKzP3b3x?*4ub>Xdd-xes$}*>RCSO zT%PJ*{=7_m;hb_8a~E?La~E?La~E?La~E?bZolKMICn93F?TU{F?TU{F?TU{F?TU{ zF?TU{F?TU{F?TU{;`Tf4igOop7jqYL7jqYL7f*f7{$G-@-~IGoo-^*N2fk;YalgH2 z`+diK_?728Z`_|ZyW#oczP-WEUNG+G2Ym8{<37LXCi{*1|5tY3Z|n=j?H7%=k2H_{ zrTOhUUDtk8KK7~dw11VqeXVub?_RyvUL*eNQ=T!#pMKlZ#ymG4x96DuQM)~LTzAD2 z|7_&*n>Xz-^4wv~Jx2cTyngqwuHyE)#@p|j$9~uR_PefYzbha6U3uE?%HMuB^@VfF zUCdp~UCdp~UCdp~UCdp~ow)suyW-r%+{N6*+{N6*+{N6*+{N6*+{N6*+{N6*+{N6* z+=<)oxGT0XYGs~kX#Q&J zy474hxsYe>WiwaeyN)4qjI6Y%ALL|clxp7`n1OD-Kn^nKiRtUnXO&CniyZL%u@}`Uu|8tn#(5_^30w5b7x(}t+(;& z&^+qX{OZA z@#r!Bu;)K!%=6K|d(4>se)o9nxbCy|c|JG_t=sD$}=B3)>Yhk8?O${ zqdv{AZe3SB%SWBdQ~k@Im#HtDQ|@B!V(wz@V(wz@V(wz@V(!HCncNlUF6J)gF6J)g zF6J)gF6J)gF6J)gF6J)gF6J)gF6K^LpUGWu?qcp@?qcp@?qcrZsjt`G?T_o3a#x{6zGOXj=SRA#oWc*#oWc*#oWc*#oWc* z#oWc*#oWc*#oWc*#oUS8@3vFzp?c&wM z_-bXIYH0py>$=rkKDm%*?&P04>nd)&jaP@}QJ>~lx2~(6<)hB!ss829%hVUnDR(h< zF?TU{F?TU{F?TU{F?Zt5cia`{F6J)gF6J)gF6J)gF6J)gF6J)gF6J)gF6J)gF6K_$ z`Hs8d+{N6*+{N6*+{N6*Q(v(@v$gAIs);_QTIqkPp}wfv>X)jyJ}MXbtK8|ka;MKM zuFq_|KC^lBna!`y?7I5Q^3i9Or#`d%^_i_ppV`{QtBLW|$~@K3{MFWVtGRq~AqJ-PdEy}J8zJ-qvNy}kQ+J-_>WX9V~E&ItB};`WQi+eezm{?h#R zovv#?Dj)k)dD_3q-@ewm?05Cp;`QFf*OQy4Ufull@UB~LFQ0mTd3HvSe`f^iDsH`v zSBK_NpXOJ$uB)Eqqt4~2{^ifh)ECYvcQJP{cQJP{cQJP{cQJP{cjERt?uv64a~E?L za~E?La~E?La~E?La~E?La~E?La~E?Lb0==Ux&Lh>`D^ z{?2!;%lWRgi&qoltCe}Gq4}$=>sE95t2q6a-_>(MX$@S3egA9d-cw;KJ`{_omq^j&{_%vPfxE3Qv#y#B3u^mWaz z-|M>i!1B=_mZ!e4{PmNqOP{&tTecbTt#8?8jNkcr+m3l&`M2AS`LAAmyK&w7@4ns0 zXY1E*H}X97r0qujZ#iSTv999!%*N|8n@6A7{QAtUtIsSSeP(&;Gs|C}IrW8e%3aJ| z%w5b~%w5b~%w5b~%$>MCle^;F#oWc*#oWc*#oWc*#oWc*#oWc*#oWc*#oWc*#oUSO zGr23yUCdp~UCdp~UCdoP^%d(gTf2Uyn&@+?mHww1>WiwaeyN)4qjI6Y%ALL|clxp7 z`n1OD-Kn^nKiRtUnXO&CniyZL%u@}`Uu|8tn#(5_^30w5 zb7x(}t+(;&&^+qX{OZHv-_-&{ytx=%jfPj$G>XCpYhvQ zjqxwp|J7rj6EA-CnEyZ4JZN0^@lQW!$*O7<>PZ#o<4Ww?{hcxg>%YX%w5b~%w5b~%w5b~%w5c#xX>#kq^Qi@A%r zi@A%ri@A%ri@A%ri@A%ri@A%ri@A%r6Zg5}t~hrwcQJP{cQJP{ck$F$?0nbSog=D= z^F_6C?x=>&Bh}V9rJ6gx;YJTUeuIv0&KF($3>AY6{ z&T*~F`L4B#R}>XEt7+**yBp=GSL-U43Tx=rhYxpIQF;%+{sPZ0+LJ#Q17uo@!|RYU{ey zTt2ywXYS;mJL@WLy^U9g=24&KSGTUKp5>#?<*EMV&&$*o&M9{>cQJP{cQJP{cQJP{ zcQJS3`b_SMa~E?La~E?La~E?La~E?La~E?La~E?La~E?La~E?buFvGIICn93F?TU{ zF?TU{@zmGsyPBiV-0#EB8vV?XJ3edlIWPO>UZekc-0SulebF~I-Rlqi(hr|G`lus6 z|IE=}t@Yk#j=pP)kN&Vc^^N7PpKM+F%-=D2E-=96k|Kf$u8S`v-;d93P$KPx3aovA<>fR%t?;f`I$n(!m*?Z*w$g}qz>ng6# zY`i|RdGwjhug~nd`pojtXO^cvv;6g$Q(riz+{N6*+{N6*+{M+r++yxx?qcr5^_koi z=Pu?h<}T(g<}T(g<}T(g<}T(g<}T(g<}T(g<}T(=T%XBZaqeR7V(wz@V(wz@;;FCL ze%IRFSF4HpZMAYAu7>W<)z*Exn!BIp!hJq>?*F;7FBG?5G~PbaJocC7x9@aa`%(GW zr^?g*RsQz1)@8qI?c&wM_-bXIYH0py>$=rkKDm%*?&P04>nd)&jaP@}QJ>~lx2~(6 z<)hB!ss829%hVUnDR(hYUn&t zZJkr9x${ddoNIFDypucUyW-Awjd#9l9_PE}cfRYo&UfYGd{>^%cjfPV*SehVTDy2P zF}_-vry82S+PZEvmrpL_nLGLC&bo?QZ{yXWdDN%*)vfEQXZfged8&W;^D^~?bIM)J zUCdp~UCdp~UCdp~UCf=h^Bs4^xr@1rxr@1rxr@1rxr@1rxr@1rxr@1rxr@1rxr@0I zcfRAUICn93F?TU{F?TU{@zhs6r{|gV*!r1zZ+%WZx&EhKU0+lWuV1RS*GJX!>#sT^ z=({>2cALo#^07~qr~Rw^?Q5;e ze)q|@9XjG~{oSEs{FyI4Y|QhuOAZ_JKjx1QAJ;wj8HbO2-g@NWBhTM`;P8?Ek3Mqv zSXXiTUE}R{&11i7e*0b5wcnMG{jNOicja%toBF~ze8*jJ?qcp@?qcp@?qcrZsjpa{+1m9p)kL3Dt@J^?pE%)T?ApXs{<`kcOFp#SN+2l}GElb~Pfy9)ZK zzQdru>N^kmuDCtE2cKY2%Kl7l6-F@^q_x$I(jsEAF zSKMv%MF&0LZlhm%@#pVc&__LPuR9m?S1(xa&INtfad+OaFuV5ry?JqcTI2O^&7-et ze*Iq8)d!Z3{;)jtjpeVOY+d@y54>@;5kK_jtBvvR+I#ge&n4%sKIY&0ZflI|zU)bB zj6U$Kh;oQRBiQ3)m$Hy3;k8@^j*1| zU2lBu^l6RPzcr7(uKD$QT~{AiKKjG*)HjyDezJAxGh4fOH8H+gnWq|>zuLNPHJ48= z%YX%w5b~%w5b~%w5b~%w5c# zxIUA+;@rjD#oWc*#oWc*#oWc*#oWc*#oWc*#oWc*#oWc*iR&}DE6!caUCdp~UCdp~ zT|D)*$p-(r;Qig3cer^$Kl9(8|FZ>s&Z#H-bV2{K%jG{=&=>vrpZ;V)zx1=u+_a#N z`lqMgw4lGb;l4L5=)3NF`;80wvEur)#_QjjM_@V||D?%4kqWBzMy|HZiOzDNCXQSDd?;yO_I}yO_I}yLjp=_B^w- z>u0KoKBrpgf2yIrsM_k6s<}QY7y7H*>AP~L&n&LbY`i|RdGwjhug~nd`pojtXO^cv zv;6g$txKQT+QqAh@zu&a)zJLa)^)47d~zYr+{r(8)>Yhk8?O${qdv{AZe3SB%SWBd zQ~k@Im#HtDQ|@B!V(wz@V(wz@V(wz@V(!HCncNlUF6J)gF6J)gF6J)gF6J)gF6J)g zF6J)gF6J)gF6K^LpUGWu?qcp@?qcp@?qcrZsjt~@P%h{*XTMFkpr4ujX61rDXZBl` z3;LhgZ(J_ui)O!lxu9Q~{U+w^Dir{IlOG9oL=xhUv&>_S>c- z&)ILGj{Il8g*w(%T%Xx^eP;9MGn-%Cx~_Vbk2;s9`jMCle^;F#oWc* z#oWc*#oWbHU$OnJwY#rY6ZhL{ALo#^07~qr~Rw^?Q5;ee%IQ?tBLW|$~@K3{MFWVtGRq~A*H{g*+!g08<}T(g<}T(g<}RN4s^`>a)?@2u>b>00T%Xx^eP;9MGn-$Z*>&}q<)hCmPkmoZ%IKC>QM zyx!aRdUEsBtDCd-vu)BNhzb=9+c)VVy>zx;Wb z`ocNoF6J)gF6J)gF6J)gF6J)gPF$bKU2*PW?qcp@?qcp@?qcp@?qcp@?qcp@?qcp@ z?qcp@?!@((+!g08<}T(g<}T(g<}RN4I(F^*jQ8d{ow3e%Kl}VYU1z+vebQIf9`AG4 zf7ROKJ?|$rTzkC#edWKbHQoz9|C4Kt_r*Vb`&x_c|F<8t)_A{M+( z({=4f{+HZ+-ErNspS(m?#OeC_pCeeU+eUB$GVDJZ{zKE&11i7e*0b5wcnMG{jNOicja%toBF~ze8*jJ?qcp@?qcp@?qcrZ zsjpa{+1m9p)kL3Dt@JyQs5A;QSCqci|cNO$eeTPAR)ps8BU47@l^M~U4%*N|8n@6A7{QAtUtIsSSeP(&; zGs|C}*}C+ZeP=+t?-Cf_cMQzacMr_pcM@E;?<&Zr?=Z--?>xxA?>tynaqDfoIy8^^ zG{3raUG*#QSDd?;yO_I}yO_I} zyO_I}yO_I}yO_I}yO_I}yO_I}J8^v`cg4Ajxr@1rxr@1rxr?X1`nNRgcm3O;?yHwR z;-TYy+rKsHKHR@S>i*onP3pegzgg;j-oIt)KHtB6>i*xqeLB1L{JBbT`$gmJBh6!f zX@2`o*R>y&kA12BYzkO<5#jUsT>d-vu)BNhzb=9+c)VVzEcjeE^)ECYvcQJP{cQJP{cQJP{cQJP{ zcjERt?uv64a~E?La~E?La~E?La~E?La~E?La~E?La~E?Lb0==U$A0(PGaoqatM7gI1IPXL4PV`8+=rj_>W#+z`TC7E8u#swes9BZKR@YH z8;<+@=I`8a-2WeQ^oC@Ur4-|4#cqw=v&m8boy{OxP4%YL`cQ4bpN zfBVIQ#`x9u-FVFN@bfnw^PjoeCgZx-JY|!S&%gc6CL_=N-@D1ke~%AtGS*exe%E;W zUGv!Qn%{ocb?tZMW4|j;`(63l@20+RPPvP@i@A%ri@A%ri@A%ri@6iG-*H!*yO_I} zyO_I}yO_I}yO_I}yO_I}yO_I}yO_I}yO=w1`yF@1xr@1rxr@1rxr@1rr@ms(Ra(3A zdo^*cuU5|c)zEW*YU}wxHTT>g7oI2N&U1#`dHzt`bBV@#UeP?BV>G|#8(r6PkMi+6 zq&z(*DSyvTT9@Z4tzEpD7+ehAD zvwYOKJk`Jad71jcIpr?qF6J)gF6J)gF6J)gF6K_$a~1B2a~E?La~E?La~E?La~E?L za~E?La~E?La~E?La~E?b?zswg#kq^Qi@A%ri@A%ri>JO~eP(Od&r}nAPPNkiR6~7H zwbd_GbA41U^jEplcjZn$R$QOfc>P=R=sE95MC zle^;F#oWc*#oWc*#oWbHUo#%xS9!~x8;$Qpta;J{#`h)8`|SqfdlYvbb^r1Gil;tt z{qenvy&u2cc&_qCN8E2bSJ`uo`;F%+=Ult)c&<`hpV@eQX7lJXn_r*Vb@iF$qt7f) zeP;Pj`poftmD{h{c*I}-j!nn-%eLNp%=6|mwixq2`iBo5*WLbxhm3p<{>YXi&z&~h zYUF?Iu3L?D71w7rUZ2@K`po9nXLenEX8Gtd%Tu3O{*yj)_~I_7+{N6*+{N6*+{N6* z+{N6*+==Tmxhu|H%w5b~%w5b~%w62NIwQo~#oWc*#oWc*#oWc*#oWc*iR&}DE6!ca zUCdp~UCdp~T|D&_>oZ%sex{n}bE=j8ryA;us;z#hn(L!-p})$VzAJb7vEur)#_Qjj zM_eKw{)^*jheAKx-)xZ3Cnfk&xkN&Vc^^N7P zpKM+F%+@YmO^mNr=Bb9}uePpR&E=B|dFD?3xwEd~*4ub>Xdd-xes$}*>RCSOT%PJ* z{=7_m;hb_8a~E?La~E?La~E?La~E?buFvGIICn93F?TU{F?TU{F?TU{F?TU{F?TU{ zF?TU{F?TU{;`&VPigOop7jqYL7jqYL7f*f7zN@*)_o5$m!lkS9GdpkewN?6@cV7SH zRr;T8ZvE0KebLH;zqm@jbor|mSLvg6{nu5i^j8aatX!qT%Xx^eP;9M zGn-$Z*>&}q<)hCmPkmoZ%I=b2l6=&BLlVC}2N_^<4K&6sDKhyP&Af9m z>iUt-dOP1R@;v3CH;(*oJoLt~uHx3)cy(wV^=W=}>$>V$KI&Ya>R;au;(K za~E?La~E?La~E?Lb0@CP=qfKh{;;e%E;WUGv!Qn%{ocb?tZMW4|j;`(63l@20+RPPvP@i@A%ri@A%ri@BSR zS#}q5CvLyvt~ht|G0W~^?qcp@?qcp@?qcp@?qcp@?qcp@?qcp@?qcr5?RVT2=Pu?h z<}T(g<}T(gp8A^o+tK5k{_4H<8t3<4pYn`xu0Q>@r;YRe&ByIIo&!8;x2KNh11p~R zXXClSZ{D=Wc%HDsntP1r4DY;t_woFpxc#p2_Pge>-!;GeuIt+G%Ex|Jp7y))|HFRw z?D1UXr~mSt5kK%f`;74yZNKlB=auI?Z_K~h4bLCf-QZ_082KFV$rp}1H{E2vk^fhA z-*2p|xc#p2_Pge>-!;GeuIt+G%Ex|Jp7y))|HFRw2VdOfl)IR_n7f#}n7f#}n7f#} zm^*R%9e2gKi@A%ri@A%ri@A$i*S(jYt8iDGyO_I}yO_I}yO_I}yO=w1`yF@1xr@1r zxr@1rxr@1rr@ms(Ra(3Ado^*cuU5|c)zEW*YU}wxHTT>g7oI2N&U1#`dHzt`bBV@# zUeP?BV>G|#8(r6PkMi+6q&z(*DSyvTT9@Z4tzEpD7+ehADvwYOKJk`Jad71jcIpr?qF6J)gF6J)gF6J)gF6K_$a~1B2 za~E?La~E?La~E?La~E?La~E?La~E?La~E?La~E?b?zswg#kq^Qi@A%ri@A%ri>JO~ z&sAExex{n}bE=j8ryA;us;z#hn(L!-p})$VzAJa0KNQzzHeR3EJo?P$*JpNJeP;RS zGs{z-S^oOW)}_yE?c&wM_-bXIYH0py>$=rkKDm%*?&P04>nd)&jaP@}QJ>~lx2~(6 z<)hB!ss829%hVUnDR(hI>(TyO_I}yO_I}yO_I}yO_I}J8^v`cg4Ajxr@1rxr@1rxr@1rxr@1rxr@1r zxr@1rxr@1rxf9oCa#x(Yn7f#}n7f#}n7erDYxZ|J_Ph80>EDn0>i72kyK%q$+_8T< z?!(Xh`uXGjeE2r!kNfuRAOFI*pI@`b7sh@5_ka9_asS`)*7L@`P~3jec>756*k798 zzSDK>N9ALmDo^`Y`P_e8F{{TgOwxyr);}&tgE>FuJQJ}=CR*3zx}T3+V9H8epjCMyYjc+O?}~PcGz{ zJNf6%x{6zGON z9e2gKi@A%ri@A%ri@A%ri@A%ri@A%ri@A%ri@A%ri@6hbzT>VqcQJP{cQJP{cQJSI z)K~2NU2E6RR1oc22pV|ES%&x1? zEFXPldFnIEU!U2!^qH+)yqXwat;|ym&0lR@x0=f*7xK)V{Bvhr#jUsT>d-vu)BNhz zb=9+c)VVy>zx;Wb`ocNoF6J)gF6J)gF6J)gF6J)gPF$bKU2*PW?qcp@?qcp@?qcp@ z?qcp@?qcp@?qcp@?qcp@?!@((+!g08<}T(g<}T(g<}RN4s^_%d)nmJ_)_c3()|0yr z*Q>if*TcJS*W0_F*Yms2cSdmk?~GtyC~m)KynUp3>@Ur4-|4#cqw=v&m8boy{OxP4 z%YIjnEne?!d_B2&>ebC(5AVA5_VTIcmuF`L`FBRJuHx3)cy(wV^=W=}>$>V$KI&Ya z>R;au;(Ka~E?La~E?La~E?Lb0==ULxs!kHtgE>7HeMZ?M}3-K-MX%NmXA7@r}~#aFH>JQr`*Nd#oWc* z#oWc*#oWc*#oUQI-*H!*yO_I}yO_I}yO_I}yO_I}yO_I}yO_I}yO_I}yO=w1=R59- za~E?La~E?La~E?LPkr?cU7y)^2J|z1mq4G>cMSADefL0LwDF!tj((}{D(Iv74uk%x z@1^Lw`p$!Xthhd{@%p#s(bqMRCSOT%PJ*{=7_m;hb_8 za~E?La~E?La~E?rAG7Q(=1yFn$z5^o=3|!K#oWc*#oWc*#oWc*#oWc*#oWc*#oWc* z#oWc*iR&}DE6!caUCdp~UCdp~T|D&_>oZ%sex{n}bE=j8ryA;ua;IOa=K82y=&$;G z>AP~LA1kg;YrOugdGvM7uixvs`oQwhAC{-SvHbOutxKQT+QqAh@zu&a)zJLa)^)47 zd~zYr+{r(8)>Yhk8?O${qdv{AZe3SB%SWBdQ~k@Im#HtDQ|@B!V(wz@V(wz@V(#W+ zmfgkNiR&}DE6&|~%(AVGX1{T{i@s>~+n2lOmuA0- zIdk*-6|=MBF0EBl=u1{;c{;hfRb$>{D^3flb zr@pcL^^>hjpE>(2(Gj2h#^@M7`|Z&&&+Ioz$NaP3DjnCI{f6ntXZG8sBhT4yp^p4# zzlA#1Ror?TuMW+lKFzOgT~|HJN1e-4{mY-1sV|&U?qcp@?qcp@?qcp@?qcp@?!@(( z+!g08<}T(g<}T(g<}T(g<}T(g<}T(g<}T(g<}T(g=1yFn$z5^oV(wz@V(wz@V(#Lp zuP5L9{hhCR=1Dux`lLm?+MC|B@TGG;u^^7GKK{20$6flJ6~(9A`14+J^?aTWer5B; z7wxsgmp@^P#oN|h;v+u0#o|lO{qB6sqc(W(;`_E);>FiLc=60*zcY_N?yC=8Jm$;a zp7Z8^{E)@<|NW{t|K*B@EH2!4iO<~cA&bv@=(pzaufFsli?=-S$~hN5?SL!B_-)^D z`J9{QzL#D$=jPvN>m}~GPe13I^LY9E?Ji4Po_nvh#N~hcFD{*rXER?tkp2BhRnzz3IsR13PXy*7cfgHy!IOt`3b?pXO1w z=2y?ItIp-4{^iL_`Op6Um-)J$z0s!^9`%4FzHqhAEWGZlE$8udZv4!`uGc(d&TqW% zvkM=-?7?$B<&e)UTyX3bbAIOoKfiFyJvX28{^xvt;bRAGI_F=ne(u8mJY(ZI@4M@{ z3)@`!z&U^Vx#upt=zncE;-7o$1IG9(-n+q^o9E2+?my?||H9YSn{(H_-{Sq|Ts}A4 zy6&9IbF-tCxcm=!{t~w?@tYs{sWJYfXMb|c^WZmrV$ALY{(02ldw;pa)o0D0eR&?QZtFi~iL2*r$NbYgUY*}@-hZESzIMF)OLNZGH-GYv zbI#Xa-0{T`zt6@?-1xKi{D*nGd5(Yk;+&iRy*Dk)x$A!Ez$Gr9ZEs&SkLT-aUtHqy zKlrmt+`7bDukqEvJk`hi)y;LQr+lijJgdL_^I~23vfkqA(0KJ}9(8Me_3XOpJomL+ z|MKLe{C&RGyZA@L;}PdvKm1;K^pA)4U7vTu_O(^ZR^tU7xS=@%buGpQG~k`D$I_pS|L` zF@E1$emLg&$pe2l=KtpYKN#1&`oe2RKKFXmwIk2hUH<)%|2psc{#e(=Z~FdNZ*iZm z#`}CVkIz^0`+Rj>pRe-q`6^GJukv5? zdcP$upIvW#+dN*LKU}%Q<$uB_mbi6^?|a4F#`sSkc(*anO+UYL!TjIY{>}y0{m$`s zEXe1ctKG36&)1xF`-1$}{`1=xtm~q^ZeOt8;_A?N^=Te;Yku|Yy6Rj$>R+C`l>g~} z_ko4_kk3Eu$%{Yv`G@}x{^B=ZGRDLk{m0Ut-gsR6FLqe!Po~@$_uKx?eXi%9-{sGH zp9}YaJ}>SMeU98W`h2;c^tp4N>GSCR)92KEsn4(bRdM&R#=E~YkNaNpyB~I4_sQ~c z|13}U)$(`0ZC&F1{Ttus!aRLm%-`q8b^CnDr_Y@{`#j3OVw`L*8S>d<)gX&!ZJ ze)a6S>OBAaF4w<2c`5%le*Cog-@q0pzJKvsmn`uUzWV;f9scJMzxQsZEPmsKOMf$e zxzj0&r(d_kJG|_a#rGULdp9@xTl%XLPg(r*Q$9H78_zvu@d1Bw#+={&)l(K= z^Ioap$jnXwJpo|LL>F_|@NZ_MDq%6$GYC}#FNK*i>pK9)u(yXt@+in>#B44sDF9#QvQ6^SBuwg z8($x8p89k1*SEWF{k(kY^X1ujfv?U5e05&nt2kecSD)tLtNHorx_p%nU**Y5`SaDf z#Ot?>uMam*{ki$;+g-PQUOx5t@~r=tf9C@0>bzjR#nqwl>eD>x*8J+(b=A3i)W1A= zDgX7p_|W;^Wc$d%&z89T<<0+Xn|Zu_=iIHfopbxqGat3xoZF`!cjWeSZvQ&ywujBR zeeG%IJbcdWcenoeBj?=y_|H4;Fz5Eilkc(9h(GzOj~?SUeeGlC+&ugI;&F3s{#_pP zggJNJA3S-*oXcmed+$8w^1S@0B`*KNKefcIOT7KX`1T$1v>%zjeady```2FBOW`ycb{=i?Ed5Y*nP>lvip_uX7@4Y(C%-}r``9QTf2WczjvQ>e((P2{9fGo zz46Y=&Ex#u{Lb%P*ZIACoZrjSIlcUy-&>b>_aEcCFPW$NmHE4mxo-D2`E=itXZJ(- zcb~Mb?w{6MTpb#(KFyPVp)C z%%{G$xV|^m_s06(xX)32TCDGl^}VsaH`e#Y`rcUID_%coe0^rD?~V1nvA#DhpZeZd z-y7?DV|{O|?~V1nai635-dNuo>w9B;Z>;Z)^}VsaSG>O0`1;;h-y7?DV|{O2KJ~q^ zzBexaKBuwIY3y?v`<%u;r?Jmz>~k9XoW?$?jeSmI zpVQdqH1;`-eNJPa)7a-U_BoAxPGg_b*yl9%IgNcz#rvEZ-{&;;IgNczW1rL5=QQ>? zjmy9LZS39~yZ8QQZcO`ZartkbmY^;xs^|7%&HrB_+`q)?>D_(zSe0^iAkB#-Q zu|77|$Hw~DSRWhfV`F`6tdEWLv9Ufj*2l*B*jOJM>tkbmtayE_@%6E>J~r0J#`@S; z9~a)Y`r)|yRef^YeXRaD?*1m9?tAidPHar~&-(M&IZ>Ri z#`D!Y_5bGYTo8BN&I@t*bdHG2v-3q<{+&DG)+OHk$N26`=IMTA{_bP0+x<;G-S_0# z{j+mN^LPKWF6TsXb!fc$G>^J9zj}6EbuJ(EFHc^|-+tHMVf|0n>hH6@DDLmJektzn zxjriH@4Wsh?(g6Iyw8REy!T3t>GM_p7JIKGZog~1{jPcH56xfS7G@UM{5{u-yKc|B;_~S^SX`bxAB)Ss z=Vr0zW^vEcjPE&{d3ye4{+`RZZqMuF({ns|_IywNo(DF6&jYQuxH>dmeVRwznqNJ; zt~!^G`j=Y~k9!Z&^Y*y+BRz+YdvDV7`MCEf zy$6iFFN=Hs@}k*$K=IyF7~gw}xOsX{5jTJDDdMi%dy2SxdQTCTXYV88^6x!G>^)%I z`zGUi4`rU-Pno~>R<7IoEcx`FOP;;|lE3$x&ENYn>n*MhjaQ%MQMcw-&#tS^<)i-P z*?S84`+Rv1D9&%=dG{W$G2R2l-UG(o1IFG1#@++Q-UEvJyY(Khxc7ju_kgkYfU)<0 zvG;(n_kgkYfU)<0vG;(n_kgkYfU)<0vG;(n_kgkYfU)<0;yz#A0~YrlF!mlW_8u_y z9x(PEF!mlW?!Lj}{5`_*=c~^n?|n}FJ@onYchcwD-%p=+e^=cH{JnL5=skPa@*XfQ z?(eqo{+^r1-+A-<`|r9w7v^J9zj}6Eb)LURSgwD0@>2f24{HA20b%ct#Cv}f7w

5_{ev{$KH)aq8=?XJ!9?Ju92~ z^4&JybL;bn`}>(b7mfe(J7u5W>F0X-4tn}dd3t}q)A!EtUEdEmY2I(QFI0c~LTq1% z?F+GeA+|5X_670w1>@TnV*5gDUx@7sv3()7FU0K&Q(t=KyY}>@o}9ZrBizN@#oWc* z#oUSiSM2FiU%uC&f6nh+-=kal{+|B1n&_Wn{d25;j`h#tzSp6DF0Ox$_0O^XIo3bN z`scX*dFtz~v(NuuXP>Dr_s>3ezIQkO+}-tkJb5MWteO@{T#eI%C2gRPB#C`63 zzq+{nuJQJ}=II>N_&#@?gW^7SorB`}=We{VZ{?4=3+rDtu^P;8aZ2z~P z=YEa%9J_fu-){c*-t}C4{$9ZMsl2!9Z_InE*n6wkd#l)ctJr(1*n6wkd#l)ctJr%h zao#l5$Ry|;?Jw~D>DioLgry|;?Jw~D>DioLgry|;?Jw~D>D zioLfI_kAkwt%`eZ6?<5EaQer-r5hL2}M?(|gq-3W!J!l2bR`4Kz7P5MKS~+H=3j8JGJ! z&wI}K?l)u%hChqBX3d)as#>*b?b_RYhyK6ioukx?KUd7}_n|Mp-v{&ieK5b@2lM-V zFu&gi^ZR`;zuyP*`+YFK-{*4vye_}rM>)UW2g5&q?w8;1qnzLGgZceFnBVV%`Taha z-|vI@{XUrA?}PdMKA7L{gZceFnBVV%`Taha-|urdf3BF{@1vaG?}PdMKA7L{gZceF znBVV%5x>;y@6TqqpC$X>^4Scj7wd@o0)K8C_Y3|!IqoC;Idj}!!hGj1aNpt2rQ?3Y zpI66yiu)VxU;O!Y{u~tg4}T5{jB*}#u;itK1p0{~^h7DMri{vvq|6k>}me2Jd{{M>EhU=C02=HfT zHmGZNo15=i2vMbe*`yxm=1%siv(?hOo7I7@nma!QhN@3rZBY}SH*+dJ3RREyY*kg; zHFJ8Doum4H9kLM zI&i6xGqKb(Rpgfq>SGgU$&e7$c>5+b$8PSd4xX)a^k$W-Uvp<}-B5Mn;TBc+Ni#b&g8ZDO_b=)zn#1XpS0OF+zvSIp<8A1CDJ_EvvS0ZjTL7(|+EpMpbIzTq_l->hIa0ikkAyp&@Gg zrp?6rYKJO(4_pHCXKl%=mSB6vvxHPWc37N!XqU?er`@$vb#=LN&=dP$5|@kSdSOqT zmVoSYEO>3-3|p<>v-(H#b+_u1iSK{7O^1(cLEP}?L%M73_lU=QdQq23GRlH|(zY>r zMf4|LaP-PJ-Q(MBHaIqKw0;p$NP}PBKBK*r`w-V}y5sqSfgS#KT^qZ@-(Hk+9$?S;fgjEr{Bu50FXtKYaQ+b|>w@^R zzA8cevq0G`df(uZ#KY4@=&LVF5sx_^sgLw3OFV9%)?xOC#2=p8uE!nm5Es9^Q(qhV z5%G-CyLIgD>cr!>@6q=f*CC$${ZHEbmK^bI=O^9qcoTnlugg7Bm9?n1F zWL*%y&`XJOCG3^(qlAAY>Qy2hCE`@9mx*7oUZ!1&^+LJGgA(~ste0t*V!cee6zgT$ zrC2Z1E+uqPLN9;0(a~>j^!58Oy8Hc`{@}0I^b>zPrvLckH2u&Yzv+kmcA0+YZ!gL@ z53uL_zz^pQ{yCqhm-CExIRA)~bwT`MK2&1dDKQ?E7^g~%UnR!1@#D^iX1psg4=A1w z&HSJ~nKXMT<~=iSpq%DIl#6)=erV2tAD$1*yn%YD+{_z@$DNlB??;@(X5K*jJnx}h zJRkbY%{=M1H}j|8kD2HF{>^;ruh-1O{&>v%?2psT+y3~?Jg=gb&ZTyldEVb%lye?n z&-sBL&Kvx5K2a~{8S!xb5hv?{_)R}l$f21x&<}~txI;fAM!z-vnHc@q^mAhLbJPEc z(f`f3AU5M2{m`{vz6AY{*f+k2F}}>W^Ou``=(jihkQjbUKO}~K(+`PJujz-by@|*4 zLt?~f`XMpmH}eKD+QsGQpKOnQ%YM+G*+2R@*Ngto@nBqVoER@0zi)g|T^L{7UX*hl zV9)u1AI=;6b3Rco=Na*E{t+kZg7{Gf^fGgmLLFelf;zy65p{qOJL&+VO{fEmwxSL& za)3I($PMZMBWK7R7`a4Fxg5C$!ybJC3_s8Y4FAv!jC!FZ81a~U12N)6pFla{N1p(r zU0jY_vORLievnJ{k6d!S$R)>vTymVqCC86ka=Xy?xxFaoJiwmw13#QM_~(40Ud}V( z;rt^`)&=nky|gIT!d?qMTKLzZUM=F$B2F#h*P>lov{#EfXptW+@}@;TwaBv;`PV`h zE%fr28y)@jMqj@lqr2a~=@0&TO+WF+WBQLjPSdaa@#EgY?ZR4s+lz9}1ME3J@WXk7 zf6gcB5r4Z(AMv*r<(voDbAI55^9KK%Pt?nKMm(H< z#L2oKezX;TcBIa(U;T21?%jviXVJe6X+rnwUQ5&J9jWILw=R%OZ&>g%apuf-ZT!Wx zD8s+Ge&*S@1`HqY1%_|b0mdIu?h*Eu@M8)8mZ;Yf@hB0e67egy7HSvDJ-#|&Z-Gsn z%J?BRbt>bZ*wl%7iBX1sgFS3<4H!O5{KW8W+C_|Kc2VvX_Q((WLEhNEE$X#JJjg%U zAU7g@%o`dp_~v#@`{)y3^nLURF#10F1Q>mv`-JcQMdj%G zX5Ju1ImQOtW6Xfz2V)5g{}^Ln)QhnPMm!jkV8n^B3P$`G!(iWinHXc8?a}wy5Bfg) zN8jgq(f2tX^nH#KeV^m^-M`2`<|=M4$~h0P=lsAA=MDZjpQxAfjCeTzh!bNKZ9)7( zFU<2?j(MKg*khh2HhwVA6C3}S=ZQ_dnCFR2JecQQd-E(S;>SEs<)&Sj=ZQ_bFwgt# zMSd{PQ#t&Ld}5w=?M*x)|Cr~g+_Xyzz5L}yN54Jp3+xB?3-*uu2-l1I3&(@|4#$c6 z5yy}F6t@faFK#c&IS;Vs{J;{Wpg5B9LYh!cBWV8o9-FEIXy@<3tl5q>|BP@*mB^RT8tGyec$IRjV7WiWt7OGED8< zv{}{nv~VVvy=BSrTDkvRqWc>4*~UT6;M6nJg}Q6inzlWhJZWaAz=3Xg&7Lz=ol0xf zj5|G@)%j+q1)pzG#X1aiE<}duiWN7hj|>;hJYRq1*`#vc9^#bGI$xITsB$g`fVz5eY&-C%wqRoU1)X%nr6v^-#e>*bD9yJPCA4-NMp zc3Op=7(<-+=x!D8#XREE-c4$x@oyQMlwU7Y!lx=-dK&p3oeV71E#lN7el6OiMSHc#gBJPGB5zvcQ%fCZH=C|JCg%rJ+j?KIPQ-yzkLpD) z%M!mld|p2eOQb3po1yKab)m+trf2fR={jqVdvNWTg17b7`BiOjaLstVUB%mhhF7JJ z(Z6LYufZi}p4aVW^&!rF_*b1|!wlkT?|OCWVrz)Q7B1GQ8|)$;6fj;tSbJPoG}o5z z+e#0LyG$H2A*Y_QCysb;ddEJOt<1=qcUevT*3u`{Dp;Y6&iV6H8_<*-$*?Iq%~ zi3+L@ryM2zvQsB@blG;|w#z4}9`CFq?s9RN%A04ZMqe#;RI38}x)JAj_lQcrvlwx` zsuxv)o#$-WTrL!=Zgwt7oNai#vRiHOp#0;?w^f5rzP8F6J~RB*Tl@CKz)dQb>62@+ z%vTtL7%yfFssm+R&XRt<`ZG3i>_|Ut`YIKZeX5hVZf@_L8|_rg7h|2Y3#)p&`^uYc z$mMzIE8mx>sweT*#A?T_G0yxm5&GB`m$#0H(t~m(Q6I*;<+XkMZ6;|ez zwP|yxvnb=6_R|0SeXp#Vj%#x!{SNXuwbpeFMhr6zzb%GRJ$G1*dxSbi^2h45Rd-lf z3{Scr^TxF&KiXk+w?mx^Gu(2-4FBgp*kL8w6zVv=W8N4qw>loMni_rUl#SCP`yH^l z8{SwgPTwAWz#3%uoyKum);n+iZmYv*Q=M`XV)gla`>fub$2t%0z8O!h`Ma$G#wMUy ztWNrLuT|RE+_huh&_(7!=4ba3SBq!%RbASrW5+yE`qso()@M6HoiA2hdt>Z}R|`-h zcMo?eWQo=fZU?ACdCl*xos80LO`pj%YK(JwS(H8-o=BlB>8C~OG93cc9%J9RUbLQ^ zGO>Cm-zaBHvS_{dcw+VZ+!!a_wl}Yp{c5j?2l*du;(7e>Ez+W4ShUX3;}r3sd)NO| zu4HayY%izYr<~ijuj^{FFB1P$BKEB@zb!v9hq7O7+kBk**oCsu`j@~M;#x_fwCpod z>p#=pT$fH*U+YjO#n;!(GgmC}&o!fU!=x{Wm%q5CWjs=A+0Xw>oPTD#%bdvgrH*nA zd7JKUv$+}W&OZr;M5&G+xbsi^vM5!;$8jejRJhLuyg0Kv#;>OiC&m~Dk6PjO^9w%4 zI0Z{T8AiGDSpO{HZ}^;-)t$#s4nKUY^!c>BI~U!5KU_(B>GSykcP_eTY~;G=@$HHJ z$E{d3{NQe@qq%m@=vb95i<^fBRj;dT1$I~gW-iLxGv*DSut9#F7#rz7gQ>ThnbWK( zF>m;JTW+NvnG@MwnTI;QJa5PmrLsiRZ!F6}fiTE*^7tSXo} zcB37os-#M+lA5{nTB2xGv{QiEW#-tewW8Iu6^Yf0kz<_cW24m7y8-HFGe2)Q5~Z5g z2vEa}&CK+F&X25D_P6Lzcb=?KBvzf9;m)7=Zd`wBKa}}@TYh8?8)cE$AI{bU7qTD0wE#b!!{w-0jiPayECE~P1{Hk}_ z5qW*>QmEV4E`^wU?Sda-)QL8r9Ce~?VAP2=gHb1P0Y;t35g2tMcVO)6igK^8M}F83 z^2Yv=Phymbcx(};E#jxW88;qxAKleDKns1nLU;6Y?hoky+)pqrh*2i`l`Z<4E&3tV z%XNu<`}eprLc4Ms}{g z{(@14e*?o7b%5amb%0qfFze+jC%t_3q!$>m3;)O``7vd-hzI%SI7u&Di(E>*z~~RG z9T+yqJD9Ztvvy$Ag}-3d4vg4v4H!P)3(VSqSvz0(-($_>gtbFXkY{KIMlSzxtf3rw znRP-WG+kMLo_)B zueP0F@)Y8g^|RX>-=9l-b%|^kEUIod3qX^n|67IXP-%oc8PMYu=ff-w(xI@dTkMpE#kCA{BP)mHZH0WPTEOE z9#GCYf>}o}>j-8Y!K@>gbp*4HVAc`LI{L~|9;U^WKdJD^aZu*4mOKsJvOZ4%W}lyn!fRRHC!>aBz!?;G-?N zSg#L{j09KP*V%e@Z4Bw2d`D-iO7%}G!e^b9U96v8+kxO3MLS!|=2o|RrN~0(I(qD_ zLYyQ=67T9}fyBY3M|jswElPa%ot<8FIy3R%7EitFHYFrpy*r(K@5e)4_&GJRpxyrN zG~(Z?aKC)1TVM2rs|i~?OV4F27-TkP}Sc4Z8s0N!g0$^ntv1VJ2gw% z^Wtt2Cs>`s?$j@}1)E|clG(W%=Oz9!`kc4&kg~)B`Y!Z-I;awH3vX3#{^!+*fBE&h z$f8GGPE==7;Oy5yRNk;`9Z&nsWr%M*UhH{UDG%}WjF&twvZW#piA`=LITTAVd~!6W zwP52q;sbe0S@kk?aAWJJtXrX)+A^Y4HEYF|XMu%MX9yZoVVJeKMJ~_w92tY=r|M(P z-&VvEzBgmgfa{&D-($*pW{=Gjlrvd#YviaJo|5sIg6!3wST|3$^6X8UIq3Mlde+Hp zV?D`qrl2Cd8d#OP&G5`_mno>-mPS_f2S0ksZ^{@HJhzoqVAB>)<7XLy26pajO(=2P zgLlCBG9#Zs}~L{V|CJn@U~US%s4)wGi8!%yq4rnG#!wt^JOV ztPdU~un^nX)MYL8GNFaomP{yO6&aGmLTrV%<+Cz$PirBzL3?vsJ(6d!5Zl7xd91JN z=Cu&py!8bw`-_qmVk;6;)C#&>ndK+$Y2{J~DIQGmB!29i7!a z8dZv7OWi$_oqSF{if!kUw06Oy*(tUKS<=~8FJz$Dw!O$;mzeb)#dfWG9(&D#_bIjk zB?{ZWZpuKh{cyXiz4V976kAxI%69fGS*YHN85`L_x8Ebys<}NhHW~4+iQC#?_5Yx8 zF|k)CdxdkB#_7-nE$k^tf2MIdqk1DdW67;FPWP7k*#5TLQW~e%eyd@t!?S6eF8;lS zy)V^B8mFI>XlVECJCw$0h67FPwRHy5I9*+}gWY!CS2Rv7Z0;{XDAtnahg8Um$q4IRm3=5@>4f^XwqI4FiyW* z(b}Hy>HKXNr)%0bwfn@DiNrYV;SIJYh3<&NIK7jrxqYnGwMdN9Nxjr?Sl?ZZr8CyXWW?#4qa(uwU%l z=tXQzMt8KIui4~9Y;}?}v*#Y&=tXRMAAM~1Z5QE1Y?;nfvCFR7=|yZ=uPFQ2wDVrX zc5ahp*EtmHMQq#mRkG(tKBL%vH@UriKADZ!{+M6SZrCuhjo3104Ymhf%1u0Rc|H3~ z!NSB9FVwJ46)a7h+OA}K8W*<_+qhqf*hSM8wh>$Q%(?BNZSvZPZBmo;cF(XpHeyS4 zFr_{BL_Qm_)o7E%F1Waqjo8*L`osIjHx+EeHlg+_Z}!<$ZR9O`+C=uYrVS~!G^+z_ zD`5w!HzFpHy`XGY;@W8*dh;dfNxUKUvNxhfZ{jCyfAxkP=|r)8o@%xC>9kf9+mYYH zy!)nqO0n6w$9ul=2=7Zbh*z$yC65XLVPK z?L>G^@3yD?D7Np8r15U-GK}i|XzZ29?=HIh`hy9Pcd`$s^6`J1+IBCm%g&9V6<@{l zqu9RtqFdmktlcQK>4j$ou9;x!GI?uJa%12(8yZt=zjrtnSgY%&6x+>&Nj$&zc4KR> zIM9=~N(+kZbe8&_JeN9BY@T{uJ;y_OQEWpWkMO*A`fG|IX{808ZY{ndel%>eXGgz2 z!~p~Md-mt;MLaIkc~ARS%_z1Pd9HXq7*>yBOR(&cr{Cm{D7K|(&U=0?Q-NX|AAQNw zdv9rqtwrWo&xO(@DQ`a>N?`4sUz%deUp|?Y<#Yv#t-`>mSnz<}-#T&{>T(l^0`CQel^Ewm7_L)`5YCjUJIDsv=;#zLu!rLDQ2{zhZrk9cK`8+)3@LhSBpR=E`CXe=Dd+0be> z@f?lQx=&kKEgGMqF*xF@&#hKryNG{V(${J~aV>GvUj40XW#ygeMiE;XFm;P3wk*y;zPInX>ZgpRpgXXbR?+v$_eYS-7 z?v7z^tdZo}sph^ckyzt>+pfBGHe(SlxZR_Vtb~1M5`UfMLu+E#5#oSn1+0X<64|gR zohzMHr%@K-hxwm);?B71)rZM;c%}?=*Rjz9hI@7$a@V(oTPF6%bs89JW~|x%O#HBc zJ+~3eZ3Lr@2U|3k>Dr06WECle(D9^d;P$BddM{5Uo&0wc3-!Z zIQHwE-d~!XboteM?>Cd;iKF{|?kzCm58|ZjGkMGP3$Wp*T$TQjr~_>3tcW_mrp`dr z0XB7dPzTu5>7hCdn>szQrVf;wIz6ZZZ0hu&4zQ`ygF3*bPPD5c*wksE4zQ`yLLFdJ zrw4U_O`RUp0XB7dPzUj=`5x2(Hg$SX2iVl}o}>j-8Y!K@>gbp*4HVAc`LI)Yh8FzX0r9l@+4u}?=Z>j-8Y!K@<~ zxkMdc))CA)f>}o}>j-8Y!K@>gbp%64JduE4__k6agK)V zQ3o;V6#h{M*NZwh9^{`GK1BR)=!iaqYtX0Ax4`H-=yPE79rQ&o`VRUi7<~tQ7mU7x zJ`G0SL0<=>?_dmovCl8cy}};-oc*BxvwvIEYm0a=j>rZ+MEvyL)6H{swD<3R_`jeZ zvR)X^_=9nPz6!=TKpzI952GJ}F%Hn@!59bl3q~3K4Gddc1BMUy0>d}YS?H6Z{9kgm z3w7d;Zw~pt@+=fcbn4n9tXM`FstS&)0zYd<_`-;e3s+oX*$y?CE?B*!ZFIHDKeP z&ewoVy>z|?Y~rEwHDG-A0M6Hd@!bPBUjxQ>Mc{l5m*ad5+v9u<7=CcR1`Pi=Ujs(H zI9~%sJUCwiHtnMGHDJ@OK&h8J8zots$NBr5l+mAcL|gbp*4HT>h^(Cxvr} z(A1o-r1NfIoa4heIB+lDIYcm@Lj?0VL@=L21oJsWviF@s1mnCR&g+5s93q$Fd>`B6 z+#eWza2^oM=McfD7v~4b-ggcWj5u))5zOZh!Dttk^EpJ6^EpH?pF;%mIYcm@Lj?0V zL@=L21oJsWFrP!@a-2hCdz?cA^EpH?pF;%mIYcm@Lj?0VL@?r)ddV}SlKI>s>xllt zI)Yh8FzX0r9l@+4*qnRypRZ&cQO-Jo|2|LZp3h|+krUPt%sPUhBl-$7^?h#uG0wK4 zZ=oDx0(}LHF@e4U#+X1IV4R&r9bk+J)B(oXT+{(Z-^UmL<7_Va1ec>vus!+&7=F+v z!0?Yg0Y<&(6JW%HJ^@CY&>oEV(I>!Y7nkE~F56>Fupf*G_K&lis*2DJ-g86#|xg2Xmw#V8L3_n;? zg5lrPON@F=Jg&X(dj(;GII)%mBYv!9!M=78V-1M4FUqlYU_V#`vVW`rxn8URIUcM5 zIZmtrv6h7&tm(L2SnFXe$mN^|*mHj1hw}#ioKMutc}6^(f5eG35PTwjsTUYJqK%Sa zk8;)#%sPTuM=q+{45|pD|TyE}BetR=F z`~8@?+3(-n>-_bad!XWY%)L=@ocO*G%*F6;?xp^AnR~3iy(q^V2OHR9?gPUQ=0q_3 zW3B|FUd*9n@B4ldFyh2q3`YD?FEDgO8zsXY<*Xx^bp*4HVAc`LI)Yh8FzX0r9l@+4 zmm@!5*duRX))CA)f>}o}>j-8Y!H8dcZwcv$a@G;dI)Yh8FzX0r9l@+4m~{lRj$qc2 z%b_Efbp*4HVAc`LI)V`o#u1ox1S5X2MpEYgNnfLzGIqq~I)ya@bT|D%8NbA)zbI25 zvFS(3#NpcezIzk)CSE1hc=*mkvN7Y&UvB!ZGVP&qqnqE4(arDQj6Z+9X8if%G2_o4 zrx}0#_{});x6A0JcBe&{0g0z*eL<|qa*#{lLSz#IdZV*qmu zV2%OIF@QM+FvkE!z34Msjy?nCJ_F`H1Li&h<~{>PJm>>p?lWM-k3IwDJ_F`H1Li&h z<~{@FJ_F`H1Li&h<~{@FJ_F`H!{yKd%zXyTeFn^Z2F!g1%zXyTeFlv9#kxg_^^6kh z93|F2O00{NST7kr?mE-lf0bBYDY5RN?`uW>H1~0o^EwUowDvRiarhyIAF;^*}w+QsWkf4Nz=pj~vWSow~le>`Tr!DjtK^@5R4!~-_#C5jWwI)b4KuQSbh?C~T#mH`+hffEh99g&!0?YX3K;cb?Lzh@9;|7=h!bldFyhA=2<)5xi80TxJ?0}o}>j-8Y!K@>gbp*4HVAc`LI&wL51hbA{))CA)f>}o} z>j-8Y!H6GqKvO&;pl&ew6zTvYm#71bT%ryz`X=fCqtBuaF#0m;03(;E1MGV)AjX(L zPPrVpW_xG=h977HhJR=VM!nDyjCi0i7;&OcfDu3X1Q_k&a`YXxM=se9#svGvnBaOb zCO969362wEg5&o+7f@a3``liXa~@#N`GFtK8~k%VQ7`8i@o@eTC+mXvrCwm@h&D=w zJ<3@}FzX0r9l@+4m~{lRj$qai%sPTuM=nQxz_3T&z^o&fbp*4HVAc`LI)Yh8FzX0r z9l@+4m~{lRj$qai%sPTuM=ulw}DN&=$;2Q?V@`j z*tAQFaYXl2l$&;8zlg`3zuf5Pw>SFw{TSW-{!M@I*K7KTKOWP6=$;DyreFEv$MYQK zVwB@KkH;O#IS;Vs{J;Q&(4EH}>j)dx5zIP*Sw}G9#5@UR9l>ZL zm$Qy2XC1+;BbaprvyNca5zIP*Sw}GI$mN^|))D2bBbaprvyNca5zIP*5kJN@`i$v2 z7#qZ+i{TUTV=e}xU0iPNQGR>VNBn+FAMyJ) z_d2?#;#zYLq}bceELe1zS({dao%3Xbei`T z5Z5OLe;HTUDWjLH5ur z%k=mmTh+i@b?sLTm+8S1wyNKIwY2ZIT&BzQO&Ww8j(m_@SJO#@aP6Wb@91LplLq11 zY5U*NajBC9;o1r1QtGSelLg`0esxmHYn8ZGiEEX(R*7q6%u2+pM9fOWtVGOj@Z({# zs4au9?N(WGb|qf3`K%iKO=jY1d2gzPkrOS%e0S?ZmH$<1FZf*EC+bS!JvR84miN`} z@5^ZL^1;_t#iE0W`@|hr-ZDQD&(G^sAI;iMobu*ewY1Y|;#5KXRKvJf;!h^#R|gk9 zAYPqlg|$pQA;$b7%57nZVuZk^QpPAbN)%C}oTOx=}ink_x6 zXYA=hHp$zb)qR4xkWJppXY`=nnaSpCx|@1JP-e0zwEu=)9i546)>XQpTW^?XVeCgO zeWY8=8lTG-Vxw_;9hip!MI#-Wva+++i74N4Tra4VEdoK3X&8MFt zo2j4l)hW-$l1-0c`E`a#v1C)KZhjq?B$jM8-pr?uPklf(^PVoZTU2>KHZylFx8pb8 zC!3{hm)m`cJs}&+6$j2gCL3^-dXLElEc{r)k0tzAA|55;Q6e5C+NDIhlxUX{`B5T2 zO5{h0JS&lBCGxC^_0DgL?E%S`>82HC5nmc+eivm; z7h=2CSsh}^f3F$bwa`Dk zW{|&ovef*}NKnJG@>b=#2 zo%~%VsrtJT1%Z2wPpkq)1qA(Ket-O|H;MY8_D%(Eka6l8zxOSFqx{}(M|J+ak<;_! zbk)ADR^L_)cE0K{Q`NuWRcE}x&XSlAReE`(y4$9)vps0GnlX8siZ9T_3F~5ht7UnF zx|F7=GqA}VHSt-vy8M1Kr*hITmD8MoZkWHh6VWeB3nzGBi0XM_gPL!6#h4H!e~(`N=DYm;bom?WGPY!g9kt_0 zBj@-p)AgN}TEzziJGooW)Il%3s^+F(=lIDGomxk#FF$GQq%AUA&sw}q#hBlzf45Pn zzTu5fubwnzWH4q{Qi5g`C+=)m~hpraC0ZqH(`4Jqj1$DOEYI&nlL^0hX_?TYg4C7 zr#bqkA=^}fvQ3r&kOy41_=k4<$8Nbd%P;o9 zD7Sq6i;H&iq7}#{sUE2_6>+)V?hqZ@{3G%coPE58eX0hb4(#Cv{EvR5e`$kwV2^mD zjf_*;AZFMjW@#haB5h=B(nhxNPJ@c%^V2gSdQhV(6win(ykDyx695yq!`*H8mfjCDoQ*);#*bxqFa8wVR5y3#PLYvVQ_*ps_KJcWD_*} zJvCVOa<5&UR((;2GkxFLJ4cGh>LyWX`9C zJ-tg@xm6*x;_?IHZ6}MUv^~mOs5gDagsO^kZ0KQ%vQ zUj)i4Jo{P|tiPZ5)BGQ(ZPT|?{PljwqsA0<+xW|mg;d9$`Khku+X|?|_tO(Ujm@X3 z&-|V2zZ;NO#g@oSF*LqW#X8i}?LX(Os-9)VKcw=M3kO=eO1p6;UC`4?-KZ>;XU*K% zIviV)xWoBY){L`7h&S&Ew#EkLBQ9OEo;B|5F>1^9+H0+f6CM%IX}-!Ta3LAlOlq;* z$}lPeag98SttGW{5v!knu(q5pK>Yd3IoAD4#fVRRH`AJ&q6~5U1e2`fcgqo9t2xT* zRO|`0F-6=VYrBt=f4tl(!7;2HZEc;lk8CE*yyZEv@ey&p5#v4I%y4z7oOrRP!P#3> z{?Qt*=X&L9#Qpjm^7Pq!ig?tXi=Gj^+*}o$c0DrVS0kwWvk?wP-1$1D7P`7CjtjpYNayV1lMc5Dh9UEmIJs#@tiNs_qz^IYXmJSWP! zZS0?SlQ%&*mmj1EihNbZ<;}IP*iSmSy7cZ8YcF11igNO#_#L}NBR6k_;~v`E8Wp1Q z)4iVBbBpFCzFq&NJ?30S;$P3dw!csCF7fK}33bhW35fSUNT_>MiuIuH9r!SjK3wJ? z@wsOSb%ltv#C-x2>e0S96FhHer-^jSI|d%`Ml6men?W5edyDsZhkQ<2^vGLtzFY6r z$pQA_Bd+e-YNWE~<|#-vcdBHzn{IXEKe#HN{c@Sxu9?fr*x?!7_D*b9)vox^<$>iJ z*c~s#Qr|vucf9w(Qdi&RM^f0Ko$q@Q|J~g2-r)Ef#3B2Sc!P3A5qHY9(;M`;tMA^D ztG&y9{fWxYq@L>?Sa=I@yD3w>JDR!rK6*XQyE4y2DxW&kd?s#bE8>}DMtB#$EKEFV z#wc&1~;ey>a|1DxbA1%6@m58^iK> z7wm-B+&PdGGjc z{8RF?KUYJY+s8wXSi0|4SI5aE+UWeg{x&d6J>9LPI|hs7X{6WxT7vZQE^4BCtSwC3 zxJz^GX`6?*gKnw&j><}0sAg-ua#dR5b(Pv^Cs|VB=4sn%UHy&+aR%0JtK-uiCI0+X z8y)Vecg&j9y6BaYRDN@13jO4g%U!eA)frly4#c%Pn$A{B3c2&ZNHW|G=JV>-cO`-n-0VrPq0g6Fgp|9uMzC+^O{<)q2(l z;$h$XsA|lfPyH>@_zCD->qEpaxy2%tKJ|%;;IRi5shrt{QfvuIE>_2Uv1v6^jmf^4 zu5B5zLN!nF%nSRh2egVjeU$9`FJ7vaO>RxRV*gS#dCwm5IWhS%wLWIxHrRhVf0?S* zs2=$V8L(W1mzhSf1sk6=tscas(k@pAURNbP-Ef&Y&>%B$%+aN4Y<@RC+e5af!#-Zp zZjWkn#*Jaijtwdzu^Zc_n}^hed5^uQH|q95oo=qn{l?AJ&3|b^<)JkX>zhBjTrke7 z`;>C$s2-bl>-j!jl`>M7^VxK*yixDl=d-^yUw;tcj+Zr)#^{tK-2Pm(=4hRugF83w zd~cMVRMDL?%WN5;({DIM^{TW%I z=RJIw%DewCSyw84iMVRnNjhVCcYe6EZ-P$xz#U)P(~Q>#HoEboxja_ezP7w~bd!GU z<7MNQ>F-M%_8>nW-JhpF%hSoHRs57*Yx>U59|{AT|S!SfxYTimwOetZznwJ^3#|H zcFtL$PP+9`I!XP9_NItX=R)=m_(@T+=yPuvV= ze$Ny7@XN8f+{r0UanBCDsn$}RaQH+g+0o_tSe&Dy=8tp695Q)(=eT}ed5qJkYcn0b z;9?$Vg}Sp5U$Pp1W=7 z+UlBm*15Xg-eIQmUDZ=6pz&xOkZ-DU>)l;SrC*{GE}Q6Nd$dB;`^wg{V#hh3B%Y#* zZ#=ArEFI&-|J+IC|L~$Ndw-O3@RR&%;>j3YvoM9&~t z4_C`}A`<=T=$+K+X4m3W-m~v}YE{$Ei8szps|FUCNo?24prY2SBVPPnX7$6my~HEZ zWLN7}pCSJ0VJ?+5cP#PLwE5JHG53fcG%KX0_kBp5{6vvA*5q>Cp7skjwz{c@DjBD= zk!$;90Y%7X$lh<2yjI%Cb@IBTu07Vw@>*&0XV%hk9iHojLpglDK97?A*Eh*Wv0dC= zKqX3%p7`^J`PBDypOXFVQF-53&&zdw;ka87&?QsQ2TJ;vHu4!^!7$hU_xA=Wd9AdO z&lg>@hj`#WCfS!tUMp?nv&pYnUHj;=*_FIj+Q{dcuQ!*c-(s5|pI*sprHy(EC(N|IZ%~Fff67T#f(mYK zkJTGx$r%31vzvT2EZ8bD)%9v!6-&0O^EYn22dDP59?mLDHd7OHwgL*3BAyZ1%G%kl zF!8rTKee9E$xWQGOKnT~m(QLFPnM=}Q6#deN7gHC*DD)%wa<0pX-75&Zryl?xcBerJYz%L z`FUFAPyW*LvV87Na&sT~ZbPq)+*b@11efgL&*>*l0`EC2i#XK+zpf$Y<~3%Po1Ww2^xYN4C56A(;*#l z=Nviq<+cB*XJq-Dt_QheC(t~zcfGQf^44_C&)yeT`(+Y$EceZt%3jmfouh{4%xt%OQjBb-Ovz_Iz2(jW>t~j+`?q!HhdYg{+V3g1 z-gc!L*fJiur%~P)+iJ7FA>$01=Ej+$?wk7$(mv@Lx2{RuW9^jp+!%^_?$~*!xv_12 z_RtMV<|sQ z?L>Ot2M3AcQzp_f{{PgTOs+w3w3av#@bHa2hqvYJ-?=X#_d~u2bmy`An<8u(^T6&6 zycoYz9^A3lubN2w z^7n}=bp6SWALgzh)0f+B%NXPyQM-z6JlHRiu}Pc%)IO5j*9xl>OZvX-Fy1R;es~rDIN}^Xj_|H3(VRH>*5TgI9u*``T5yzC#wO=9IiJXw|5N)&axd$EZw_f# zxs7i9ojVs{Uu)JPcTH6xep0BMQU-^y){kd7YwtC}>BgDPmYx~CDn%sYj%ld!-kCx9N&MNuH}(mo&v*A{Bb#7ru}YfOA|CX|BGo8sXW}%S z7pYy(MiA#6`r}{PW0ZT9au4%#PWK*{?Z%`xVwN^?|8ua(E7T0d(V>9u(B3bo~W58}P=ELZu5RwG_gYnfUUl9@R9&rAQ(KCRsQjR{yv{j=uO z6-vg_ab+utEqwb@b>H4eef8PvrRt-y!?q#j$dF~~z3&>*wXb_Gf9rno-r3K*us z{)KD5Y1$Sgua!2k4@e#5wQ|2&?m6H7u`%VR!1?)lNO8A6fB*g5H}<9Fes#;mu6?_} zjaptSZRB3}$#2~I%i_f5bBW?wX(RW^m-*})@7S&7wbDlJv8P?)#`FFoua?(J8@WF} zbg65f_T$4^UMtIMmvr;c{nkM(_xz*<97G?*Qq{Q$J}(E!M&+Q>6u%jDYlX8N9bGGP7~)EI9$io*h4&_+b~_O zdpPmTOK-mKknb9b`0mSl^L5ZN25BSTQ{4U5?YFDXe52*H(nh}H2wZj4gLx*$yTi1+ zR@%t-BgJ+dCi?-m=V^JZw2|*tiu&R?J9?Rx*Ge1tUgn-}9CeJ@q~*2JM)pbBf8@1) z=G}^X7bD*tyzL!(8mRuInmQs@c$G+U+>qxR^sZpA~yUe~@UqXP$YNbm#6(eLF{W z8+`cD4K3qo)v%sUIc0{k>HbN5d+JynJYkBHAjK{{)MMUtWt`~rAHG5#O{w*R@#CDy zDW~czS&rx>jm9|VL%ZtB-7f07=Dkn)_`2#bHymjgByt+m9St75cl{8+H1`6P%Ra z&(j^sIeOL)~AaF)bpE}@vz;d;ujzcttLkpSGo8WFr*+_qKkQ}QL!BNiuIcM`ExjrKOy^~}Q#yH# z-|bOfggQkUN9pn9>*ywzW;i`6oYI?~J+>z;33amHyr$nDURVEdYldUDIjQA4KABtD z2jsZ;cfR|R@AyieyQwQ>9O=Z*A8mD<7^PF(8|jodn?!Z`(A9+w4UTdeZNTslpUfE&zkDI{C%HVd90?sa%G0I zqReU4b?FDXM9NvtgNTbtt%%nTj7Dcp{p`tC;Fd0AjdUt4?_s4baYNS~V9I-}us$4n zU2lpS=~#zvS|uZ{=#F2Faz>uapuReFPKW0k?W}yKyed8OgpU7Xw9|Y*W3{UFL2W%6 z<4h@FJ~Q^yE`2xMIA{OPF=|UlgtlsocS16TsFV*@>uifAI6)sSQZpVd(Cbr7a=yR5 zR+T9=O@I8;WaqNStIC!dp?~{qsxz_lPpZhmj{3VH)14;29af_r*3f;6&veS(I;D0` zDXZfuhd7DPo>gO>rqb=cn(gEtaz#BlmP!|CGuvr!^oq)E7twLcLYy9P=hdHi-JEx${+?s2gf!MRy*neIrg~E3m@~Fmqkro-wLQ^&J-G!xXn;RFTf^+<0jC zEw#6;J7*>sepBWBy}JF#*!N6%Q|)@~^?)~~yrty4{kC~h&ZV_7xUr2$7p@C0eMWQa zM8l(2xO^dXxLTaqwYhHi&$LC}FXVeJ`3_6I+xmCDla=pV<-1h*p7fu6zbW5c%J-7; zouho8DBl&z{dT#RF8A2~)$iB-r`~_bcU$tkm3${9-#7g`-}U^J_cHRGi+rE*f5Kj+ z+=rC=lmE{59r9hq{|WCbdC=RUmLW0(7cat~1M4gNd#X63%C+*6hNrE)J+?qA8h zDY<9$XZ9Zd${wTKx0L&PZ`-?*dnt0CMDCybnSHRovS%gtqvT$b+((joL~q-pkb4et zPe$&y$h{P~Pa^j~)CJTew)KZm^4ZP{4ToVC`{T(Og@;Z!0}0?lN)Agq(WHo;c#Y=^guAmfOTb z7F_oZ`Z=CB$Igsag%h#5g1NTzmcv%LwwH*{CMu{toN|=-%TArt(Pi6-+b*A^dc3oe zxXZ<5DsP^t`a^SVsiRsI*w>9X&$~xd`klpy>s7s|66`!@!{&0KSaq{=N#bn7~$Nqqh{oO^D| z*kl_oJv^xL^c?2Yd6rP+eZ7x(P>TTdwsuLIY(D#K`uJOOB5iss*hv0w8T+^8Q`&sy zvtNA5YrRbiX>-EYmM+F#wozUyZDiZumd{x}pSf2@*~ixIr1+B>ew!B3rdEV&Kd-d? zRvo3yJYQYm#{O-6K-w(u*%zs^_^tg%+T;jv^FO)o;~ z`I&0$-`3})O~y#q{`smX`)%Vz+NAfzf6ds-zAdknHUoU|_n!XZt>Z%4O!wt8WzRS5 z<@k~|vTwAkn;;0|Xwd!Z)(CTM7iW{Z8?NXpKb9=U{@j$OG3D0{%k#^px&{Q5Tr=4D zzHCBOAT}Uqso{?jy|8}&C~?pj!z$Bk$AmUt^$6_?-Xc*Bx${+xdxUE8!;4z<3im-yqSW7J>qDck$1vRiM@uW#7X zeesk#7;o3`#kuj?U3RY-ZodfZ4P|f-1W9T^R~I-ZDagxWAkle>TP3Tb<`2(la982{b(+6 z`2~Zmi0-qAlXe|oUHEDSan2vVv=R=T;xCV1Il*uL)q7)!;V10KNMiV3onSaI>V4gB z2r=SWkZBMx;%uDaTVlkYwfQ&12Ti-UyyE_7zx~8qkNkeNR!ykbfA^n~DXzCx$5e{r z`QhICisO7$H-qB%>$J?IxLqStW>(x@lye?n&-sBL&Kvx5K2a~{8S!xb5hv?{_(dMN<$Zd=Pb;5Z@ZZa)7wR46(+lzB z@#%#)PbYWvLj3cZxq6{pT)w{CUYqS(U)XB1pTPr`+w4EXmti*7+oHl0o8wuXb+pZK z{UsO59c3ovMz{U&Vh2y|7YjJ zg1+y#m=}^*muR0jD4m)An}2!7ewZ_H&}hTo%zI)#+7b}d&G6nPuk0^s1_a$O_m|AC z5^DKf8E>20vcKzdnyin8*j<){m5O| z{a%a6FA}NlD_t%#?hotxM6Ugr6^||co{d9U?_09%f93uw?=QclZcpD;lFQs{_T3yn z{KcG{>a$m05D)$%gX$34jrefscU9Z#ors-p6RKiKI}n$x8E?t^@;`ge%GIc+>brWR zvnWd%bu_FKak+pOZ}^n`LG}~*T`Mwvc`r`sYggOFIduu&ce9+mK1oZx-gY0C*S7TK z>VUaN|Cq#W`{fq#_TFeWC$mQ;)b?yQS8J_zb@(4{4!b1FsOA0rpIsYRzMRBld|?mx z)Xmk%ylJ%5ZlN!>*Y&D`PSDbH~SN7gqI7^V!tDS=}q!B4d+%Lyn7o zb}Y;BBES3PuY8A$9GkL@a=gntL~l(@{j=>S)je{4kaL2}kDO0V`L4YaQ~iy+Rjjy4 zePs4Vie{d#^XFQxf($SFW}#m2`4&~o@P)`QUBY~KP?u_hod+Aj^ndC*TjY1_$oxxP zWdE1r;?OqtyNsIVSg5D1NUUCr9OFzM8>McByZKBoBudHeJIc^vHs!fU%W$%K zo&&1cCsl~sw>_iecO^BLpGaXZ?n#?ywL7M+!oE}gVW(B-i7~{9kM33hU(6#u?cJoV z-VIPc=N;v2I1;6r*9cI+J^|NU?^FKYsIyJx7=KTEih z?^W+)cFPOo4A)_0T>C{C!?m=RHi>=xbN-nKE&HnM!?MrIu@LUlG44c!a(+u1^sf0X zwcEGedE>j<#CMav@%^ac`%bmIw%^)hK_7&+v?Hq}*EJw4M8J-q|h^OMrwY~b%U>gKFJZzO;JasxM*Y?z}?GLjD{ z-oWd}8s})01ug!qeyz4Zo3-+TR&1aZv!K-%L936yefL#s9E5G7ji@iNON@k%-!yFf zSYNP=F_u@8#`)y6AD}zVSZ*Tm`H0V;T~=#sfBUwZ_BY?OJoJ3b|AVu0jOAwj?I>M7-&o$L2#A9e#&Wx_Zp81(jOg3BSf|!^bcIYEBYBPe z)?7W-P+$X$jkbG2=K6}Ae_^;o~{jX#GW4)$drg`51*}s#DpB$p$O)VAt z>X=F}Ze}cBGE~LCNcSt|IeM}UU-jlIrMot0!?)Jdq^CQy;_~9pkloja#;U_669LQC z-!A8qZ|G6ksVjncgOQ&okNxa6yvSXXr*M}q|6;C7dG0BKxbO83lxMcLj1RwVMD=*B zbLV?EM=L1ZtBWmvdrD8xx?WuC8gZ>_#I>#w*Sbd93|jSo zRz09q4`|i%+r99oxuiAUxKNekIZ5e1=Lx0%oWqpQS9p?hoOIjV^KT8=qm}JPqd!cn>y38a7$-0uJeD^0z22`K_#W zom$Mb>es$UeoOzG`KC1vIa>YY3qEUNn>OJozj#c;=jXlVX5BO#B>%|I8*134@mH>0 zR=ZB^Z%u1miyZC0J+=Rq{FT1An~MK`_@1G*8xLlC1?!jNa((Nq z%4ul3i@12?+TT1x`qjLSnEfL&j zW(zm1qH{a;UMh^rJ0#q{9-Uj=cbV|C*&!iuO-ydjo6Cd|*$0Kx;jy_1?UxJvdmj`| zCdB2gpSN7l`T0H1VMh(Mo$9ymwQBY8w{MDSe`{3xI%;2ct!w(99YZ^|w4Zwpy$9(D zXMgTFT%J=2g+KQkdhIBOxj(<{xv9Zh(B8ZF)7;bkyG;AGP8p3Td6Lve|V4alQBJE z)c;PO^pk(3t1Yjx4^o~*TIpENuk`nS;9vQFwY4eaD%)KvAor=1e^s-qEVOn&?(3g1 zU>yUcdd3YhF^7JyT2Ig zNB))n7h|2j^8BCT{MGKS`hV43pe%)WV-}sC1Ie)mxQX#8H zMy}0_DLKeT$~3(1CudhI$w9_E$Pe}B6E~FdBV&GK?Xuc+=KsupKq`xj`H{8DYS*dV zmUax!m!%m>*fYtahDKf95|W#ej_Yk+sWe*SY2XOd8K~QXXW?kE~r*yUu@q<}Z`R z92xT?YnRooQ+sY`&l&Bq+I9X|yOQE*IcW}!KaMkA3mpGnW3D}(+GC|X4%&Uxj$b=A z?RK@})SjQ(b5DC-Y0nw$Z$xW5mG*w4cE3JJeZ+Ys{OseeIi@}LwEL?)_x@Cmb{_3{ ztKHWBm)|hgc17)PeS75X72f5<XD!dP{`;K_)azlg|v zn>hcsZ<5bDyHA)BAUUnaQlV^Vj;yzdm3)#%OK5%CN{u|SQ!BVr*I7jF^dS&*2P`BW zX6^^GmR}~;|Lh35z4bWe@oa1X?IWy+-#dI{Pj9|!u+(*y&y zX+co#E!;*M>D_#B;Y*%)VwL9KXM*?H>kt#>W>;gLNUru$z5Ud3TA zan;uDeC5;U#5&s>@-73b1Lkp^WW=qb?1%?Fxhn>Z^CliTV6CVc9Y7o}wh$e@v?R{E zFiP!mMZ^wkWnW~AcvjFE3K2g8Y8W`|zy+6>k`*>W38=O~(81tJS@5KCZnlZUxSt$10 zd4SSOhaDC3VsB{p`zmon<_qE{1Nw-L3o41L?6MSn2I_OH$0vA*8rwjY+H8((AWLn^ zunlCXO@?hCOKmc216gX5l}c?OOKmc216gX5VH?O&n+)4PmfFOAHAj}(1Z)FYY7?*x zWT{PtZ6Hf+GHe4`YLj6b#NSsjYy(+plVKakQkx9hK$hB+VH?Oeme>X|jwQB%jAMyy zAmdnK8^}18Qoo3CEU^tt$FamVkZ~-r4P+e4*Vm-~`Sa`$tUIB@jicHVpS9NKeb+}5 z-CL2q4a*lA3I(UYfaPS3GTF4{8leTQ+DYF z(P(EJv25aE(M6#mPTR-DeuBl>>pn@=e0Cb8*Q>cgW|q>G_{PlohZ+phq^BI+sK&N1Hf-y^ zwu>=fS&RYWME(^gGRE29Ku2n~+uB5S=0*?V=EFy_CHwjl_ZXAOYUB?it`e|@^@tx# z{9(dAc4VL?kN)s8?2KJ+N}q0dk8PWlMBJh6eb()81hKICJ{$T>a~;pb6tew!n(O;x zq?(0W#8aL(z6+@>j1AlRukB(CSQcZzIFWzFiHvc+Y2-_7`5rcfZ2-jUN-aUZQ6O<~ zhAqTZk-kSJ&G~<4G=qzW7;)=VUuf}HC4 zX&F_CA6@l>FR!eKdz(1}cWy$=E9+BR7#p_rU)#kPuq?)aaU%bU6B*Mtp1I07#jYMI6(62-NppM%?k-a7go> zKpeHCFMQtHop^4a?l9?8IPtT@PH^}6Y+}QY@vtyyKk<^%2x<#s!?ylwyBGtO#TYP7 z?jW1K%OO;%%nTb@pX-Z8C-Yn|&4agL9(F`b$ORRv!6xEzuqkk-j9uM zj`^>|cLn!TD=5#@Be4)7%Oc*YmkQsEj}X8A)*WWLT_Y}b>I?l>6cc}2+Y{6qD~Q$m z)1cNmL%=!%x^{wRwW|=n-y8u@@`M**}j#mpQ07IXcYWHyCc30jy93j9u<_x& ziTjV;!pQOx%t&WG4QadNyq{ zWU3`yD81UqC$i~63h^u3VD{ZLkvOt#2DOE;VO#&TU5o+CVhk83@~=3NG0ttlU8$`% zr7yDUpXg7#eUMT;%2Cs=8p1O5;nC7PBhA&w>(|uRZ;mH!T5cg4ztZ$^L{Na(<(Q`L z!LlBr)yuw=r+c?C;`Gj%`ukW-65nS0>{t0@>AS3&{vJ&gL?Kr*4)?C#rM56OZ0o6F*ANbhF}?lbR8i7}n+QUTEgw z+o&ph>kG~N+%A-fmwRjGa7)9pVn1~ZwhZB_1i%%%9Ueba~r&P5RKK zRk>`4Ccoh<3yyg(Hq7%k`L*Lm#H=Sci+;tLgOGhi> z4+mTG2KzN!ST};pU)G@X93hU6FEt{*V9=2-S60$9XIAen{QBaD#LeF&a?8xC#QBji zeCF5V#68xA@nL;Rh}*`t=55UlsGj_pKy6`c*w%k-7h}M(7z4(M{3}jmjB}{pIBNH9 zL=wMxWH@n~cRhGvbZ_EO*9URsy+q<31IBVV>q)#VU_3YOVMJVMI)S?_SJU%9YQqHX z6&X+b_0mwjEz6krOV7Ui`Pv1vE~G|v<&QU>r1VDB(|F4PnmRXEOQp6jHf-y^wu>=f zS&RYWME(^gGRAplKBHy*@%gfLC5H~tAl#30ciR)h+%fCJxOFSxV zG{0GYA#w8T5xm#bEyUkC4CNC)>>|GLy&HcSy_fi0>tuenv4-taBYEQ$vnbsuCV^Kq zQ4kle>qKo~Y}nR+Z5Ly}vKRx#iTo>0WQ;Q`>>rN&PrXQD>@V{0B5RI3YqNsic4|u8 zydZ?%bn+yw&I5?CEHdUt{*@mY^GDTwM}28{s|8OPuTNz^)M?KzZZ#wJHV^yH?RJlJ zqq3shou40~@yxpq9QeE#CrS@|*nsC5X?$`~p)-Fs+l12VXZrt^$85P1UmtQ1?3evH zzjpjXdcPGhf75C$`O?8ARQC2-e;#UWMZD^aGuN)u;f^h(xA&>VYn{{Zs}WWC zz0+=8p7q6x`1@e#Z}b&%VpSd8-{RCB^FQ?+^ZdFNEUFnl+_0{EdY&_PsnwJpJXKfT z;2&%5l5EG9OtX|{M%U)OmfLdo7nX9f^VRr@>-PLqt$*Yp$%fo%g9kUtv6SyzUny3O z@aIc9S;}X&{Vq0G(t`W$mFlUb$FpO?c+}@Q((idRf7@ca|MTz7zxlh^ZInF^UvDYT zcw@)|TifwXwJhan2aS19e@AXP*i!y1QJ*g@bKoC&UHQ6a`aHd*9skn3u3T}%nENC; z^6Ay;%H;#}dDe7Wet41;L#!!RWjN3{RHPd4PXF5R_SJR>mz&k$yW80Dc*{c&Rkb!> zGSHUTd~tO?ajFB&jUSy2xV5e~r4LT86c;YA-EDREi--WfWT#_Cr*q zcysp$b>zxkl_C#mL3IXy*X6UO+44&kWkQ!OrhK%-vkemji!@VSzF$T>)#rzJaEUF& z8G4`w50mD+&-g>&YOBMG?t4)B!;O`qYXcw3pEa~n`kt*Dapxi5#hE{BsV$wawfLsF zuH47BuH0eh4>2srl^2xPk&oZ;L)^8_g}V-`Bi~X(hc7zn#^1NCBk!&FE`Im*rm~Zz zF*zr?abty{{6^?^5o5!cF}6MTY`ICsEWx==RX#7$p4$E3Uxjy^(S*3|CS5-8i6;J( z##Q;K@y-{eSbyb7TRvAXk*_{fl?RnN@_(9{$>-K;z`qQ! zCGJ1ej89CqC;r!=3jcV=f$~49)aNN1n-I$v>GG!IY-tR`514aVOLt!M;hm6Y^<6CV zaOAIUei3@C(&xKZG@*D(mh19@nT|Zy>#;B^NT2$P^BLp8*sx#3)(#Zsz%m0K8|KI> z{+%rJAEVD}_j4ky7^25#SGscSSE}a^F?+oO-*u*^a52z;Zzy#l4*y4wkF9XxPwH66 zd+0UdIb&>jl7qRtWvMA|w9cORz%D~x-OQPIz$qQxr@)8$8#$*^{NfeN*EXyvFFv5l zVX7zPS(8yIx?9+BMJpq@V;2+N)xnOBOVpJ|*qZQyWJexj@LHJKSD$BwHYI-Us>>}; z+3^s&Qek9@5kHdQPF$+{UBo$neaGwQJjj+GueU|0f7Oi7v$W^Td806BM-@KzdK11^ zwpOqlrpreT_uy+vQU$l1O40k37q3#QwmeIk!&4P5#D~3fxKer!9Ji_^SLs*hXU5u6 z-=FO==j+DU5x=Z$%x5>Yr#xXRtME!+2TI>{(SSdeo~>ARX1WfKsOv?2?WY+-XzG0JGZSO zzqC@1TSPXcc@pZZ%Uj1g@spAI@>>~tT#WPNwM<_MYi3u9IfEVfjQY=n-m&_8=VN=i zA18(w^6nFyiBqNfYhhXw8pGvBbos;;cD#zkHo^0>5uajU&-(_i7A{<`!dFW7Eb;^C zo~XYO>XtI%hu4$mCuz%A$2mS>JO;8R2GdHDhhd3Cr(t+@j2xUtdy7E+px2OFu^%hk_;gyz@AFzGp>Ed9!EIGryNJpR=Zh{Mlk1 z-p+ST(LIJ%`OzwdK}5O}SICFJD?zLq6zKr8sSi zv|h|Kl<#V8zzw|}=o($RYQTSNapIpY8pzAq=<%Id4#eqR2HeNSf$PqGA>4Uxz{@V! z^ZWD4gv&h)c>`}}{>J=;&|$9*KVRfY=}x07#gF6cxGZzKu%x;%Z*k3@!G22 z+U~KeMO!L6X!m__UA**t0LghmhjCH6&MrbYr9av{RWvqH60da~AgXqS5}!TZM*LwK zODr#O5f2_pC7$VL_uD@9-|Ty9?@KSg+=bkxkJ)zd)4W7-o68l;#nbauX4GYK z+Q&w>`Ja2sf3pWJ%T9tmqm_ ztkY?{c*I;u>+Hp$G2-DGv6MdUtc%#gD1zLkq0LM&CNhcYyyLu5?D`{u+(wz|D+Xjm zklTz%_7gX}iy*f-m*Feg8OD*@^mTO>Z!b-z*d{i#7aw+yCAV>LcM&JXYu+7ff7eKK zUZkXFk@NiFVi$?gZSocl7t=D6iHjWU#r(7|iZjV(vY2`_oZO~Lh+LfLta*nLzs+5| zR40z|N7ix{>s5~=mizjO?RSS${QKW$i0zlD$Zf)Z$i(*vDsr2sVkYK23@5j_kt2w$ zk|N1%lEQt&>cO#8cIiMDv8$ny*3j!w{l&Tm6;%I?`klo4`$CDw&Tb?6Rw^h?uLJ!= zOVe;-v-lwKRG{X%Ja8B+4(S?34pV=AOVRSWCbsSsg0w!ykgGiG*Gyc)LTT+j6EIFJ z*sCPo^=yQg5TfCJ!v~AP4h6;Y_;D9e^<2Yc)#Jspq9)F5XF|nrc@(Yb6=j}c?clDo z?zGt2SiJKtm7Ytl$J>Y_T1Sz4^ppNaP`i>)N?(;aQEdGomewHqE{nvpMoP-FtM)+A z#Xpvuq;isrxPGaMoMg8y6Kfm^B_}!9wv8y$SMt$2PY5ks`is@PLwVwheZr+r?Zvx2 zmE;>f&s5?p!%*U|2!(k5m5SmVeWkhRTVF}Op^*Nc;Syyi@f-j4;`~GLw6Z*dg;_}X3;zBbe#b19} zjHs8Wr1)3Oi4fPG52y6|b>-rC>HnUhdmJlnFCLe!BYJFkbdXpoU3YY?wQoC$s(b~n zJ^r$gc{xE83&W_t4Sj;e-O{~`F1qDulDK1NC^uMhMlfv9PCWZSN#n5h_9)THR>`k_ z-6a%63=}6wb)u`(tkOw5eZDY-|p`zhk0x0>|Lec~%yzRl0j~=G-iJQlW79W(9K62G)@z!1irDxslBqrWg@V(8e%0pHq zh=pF7IW}WVl-N+3&*(h57V%N>z$1t7kXggCk~B`qx#}VX3V-EO=fiskR*y-;=#G-KV<4y%RlEOGuw7I3A>)Vefh$hv- z`IU@|LPc_rsJfuwM>m}krrwkO53PY_KHu<(6`6G3;e5WH(^>4Dqu`bw_6UU^lSQkq zN^+;H$D_rJFJa_GuG@peXGYTVT=JsLA7Vu10R{O_O6yMIj`2$3qaVY?h10`{cRL4& z2jj!Zi>$r`h#ARBx)yf^Mu--N734)b_a}=NzJ-w&jaeHcUc4MeUes+^usG+Kf_K4>a{J(pV)1STFWy^C{wXCzeAhXQuM!B=@$E{nq(Vt!Tj!8Mw35aI zJ*xJ~E@HjSQhz0PDjFRo`pLqGw~lWmS}lpDJdTIl#BQyWRgxD~HBpJLA1KI+I=Aj4T5OFW?l#R;)P9egHzkcc zL}kDFkMESV*LQ7iapd(}l7f zGbPWF_I%>q_sB-pJ9>dIT$5X-c3DNm`fyikt*4fJ^wd`yy#hFOE%g%kz$**EP~DTh#@c9U9$yy zv9vSQIc!c>rmhoB&!skJ^JSiOqscM6Pv*<+*G(jDGcJOO(VFufJ@k&s8o!s^M%wdP zp6$remqk(hx1$&vvp0tFKk#V9bOntU^}OlHMt4Y{whDs}%Kk}%ykBh#)T# z?l)!U^&`lOQhPZu``#Ka+Tq~M-dn^_*_R80nNv^AvsYHrn_+CYR$^>VcqI8ry5196 zqkSrhLHb1^JKR{qLo2PA`^HF$vtPAhS>|fZn0Gm0%N9gMQT@JW3T6J1r{SJY=J7_X z_czUTtlH3t)#@BY>ug4gLfM7d5#%1@Z+($9uLviPD!o*btxAX?cPiL@L3SoGnmG8t z4H=fjy%8+C*fE0Q9I@iFZ0OfWN^fz(k0Ilp&o9Qk5oD|%_k6Ja5FL#>4YzqHv)k5% z);RUWm9l*|qlrf?yCQSmp(4(lq09EwP|^C;R;|SHhdJtN{Oa0aGj`urMe+0wtH+GKhLeZfJ7rGs;JydOgRx=1kfTFX6z6A4BX;gb zIJs73-|B3tbRXgV&zOwbtk;4F@~+H-u1wuPMXt5JYgM+?NW&RV>#`wNyOLLwo>?jz z+h5~arl+sVj!#h0y6-kepLHFj;e$7qBNYdn`NwumG*^SoUq>m}X4=w0T=tFvouRm7vFH)IYT5wu6KzPv(qNP1@C{!gDf zzBC80?|2=(EG2J|JZiv(OR`xHRkY``W5ajZre-SI^GS@Z&mJdf{7R)KV-=61$*DRV z31SXURKz+Kj_fsP{AcRCi?Y0lvDEkO#V2LGr$!Lpocdl?d{;&5a%R&XvhH#frDtt2 zVnqiv>56Z5>|ty)_4iS;09LwAMSSYDEi0Q6O=b623uKG>s>rVr78tPL$C`Qa+1QcI zm98E7&oc`nR{2@Frqa4>zR-d_ZKtAn@_bc8<}b|w-1E6pw>Hy%6h%H$dH6ZH z&y$wsEJga=D&CLn1{kv2(*1?p;fyT{u~N|(CbhF-Pdi1Bx0Dx_%c{PU+QmJePL(oC z>7GT75_B0Kt>GzG_1WFUDsr2=L|e9@sfyg@uD1zOOMS<^ox2vg?5h+T^2!0`Ed917 zeM6=LJ9SJ&ZqsI>J)5eh87r?sGgiDvMQ&p`PmkSRq9V5m=xNKAOjeQG97wcb6?-Dc zNx<-}tYB*dIZ54-Z)NREr01Tr=cDW5$huvKq&=Tqt9_aKZ0Q*#?fC=;o|pM|P|==G zr-Kbylg1I`A*|6CnOS=&e#uoftZm4)N%szNf=NyG=y4R~+5H&U=}uAPD&OJ?WoxXW z$yLHO<;$kyZ=fYtDXPDCkEtj(kd+Vfd;@VzXjyNdRF zdXyV5nRKmj&&RN%Ijhnkl6zu1`72iW@rd_8+C(Zk*NnP);1v-A@E$hr4u%SKOiQ6Wbl3i-pnbOOZ_dJLpH)lw9!qZX)%F3inV=xI(b-hQ2F?y7xB1un9y{yhPi`~g zNfGOJ%9GqC{-07-;OS0#KI<;(z^PT9zXr_gASbuEJifsn&zt?t zxj1J(FLE2ZIwkDt2p@8r3$-4x>?99znFGaH3BUt1#2N*BfKFet1!!ZaVw;53L9uo#@_AAy@6fwg`n)g|mW#3rI9XE2D+6}+4^$#@f zvkspB#uA%)klVP`G=S+Ry(qTTG86E6<4$g4JU}06Zu6%#z1q?mV0YM`o<-f$ir6WM zanI*&mm=2Zuov+GcN17CeKPaI0aB!hrRDHol8<#>3!C%4xd?-%WmX0u)cz2-gG0k=@I^k4SA_~pH+IL zk{x;EPGw8l>ciz1n)g|@rz$Bne12kVrun|Kw)P2s!0z_Z#JqV`F+1Pco#L4}_zio$ zS94Bs+lU9O)jQ4m=!JzJ*t)%bRDWp7eP-G~$}hRi{j2ZT*?c!jU+egZ9XRDjZu3=f zpCveZ)4K2O{)FwY@F2I@vg8G8moB5Ven+E1cD-hE;^hsc|KTf@MF+sLJKB3woTJJg zvyfVv_gSr9{2)fR`Nilq$XGwR4c7lv=0~oQd;dNgtJjts=A2$3tITaqTzg3&o7BmR z_yI3w5obLp|Ewp^*qQ`);>_J|*xbjA)~psG1?*_08@Wx@JKtHa3=i6S8GhW7GIsikJ8|rtm#kd6 z?%1yYk1y4!QSpjRbZbv*cdgrnta!vLInY0^(`)rGhk{b~SQ#jPK*@O&R~o8|K!vYZ|s z3Mw<6oCp!P2>xg~F>lkk#Be&TXU&!j`d6C;p zef)$?Q@E4cylL>3UGQ+Hy(6o2I4D7}w^{z8gcV3J;QLUsg&)}#>Dr;&Tz_54{7R)cDY;GE z9xvHbXLp(>Zvx&i<9qJpHrF@4WPMZI$!*fd=)%o-4|1Dp1IpN?eV+6TSsqf#?4xCw;sw3_tEiZW9oGpY=K6Pi}LyQxS`LQM#CQ8WV@vyclG|*3SIXipY2I6nGbm*` z-`&V<0=+-5+7sN#ZBG5rg&Hrs$!*#^eZ)-8dXn2*vnXZvV?4-hMvp0DZC!oIZS<`l zGV_maR#P#kJRHZTDyxtT}J9q_{rJ&DWgOnP}$>+I428 z>QMcba!*L_t~uuu*3koAibZth=aa23+}xB;d@CRjYB#(?yw|+_Z|B(m=G?pXx%7KE zmgF|wAplZlnvvVoeApa}2I`U9bpGrKYV!{wp4D-R^Z>8RB_f{H@hJ3!6{=ezp4F** zA;9!$`68axDLvj2d`#|&cvk0XqcDh_byvi*IvqYG{_$-2-<*M8T;-{V`!*XEdP1Y~ zFGW17vwXV;+#2;r#IrijgS}zUp2s4d)wyuN3;Gnk6!EOi!L1&!b=xBm&+7QPdxM@! zxrk?Vd{iEAR{B4E_9veOy}tP(p4F*P1i`28`4ro#TCL$-M!tw=b$V?G1ogW+6zAphp)jOHxromq zr4;|ImgOS4O_;<5U-OAAj9P>4txAgX>vaz}W^hl$eVf(K{Gnc(Ta-SgsT?YMY4YFd z7z8(0+@`Y6)eM^0=~Db=!#!c}w>u)b&AN)_5Zdyth-Y=?Z*LA8Zr>I0tWKGQl-}vK zh-Y=))B!MYo$q0X>@)is&}xc7E`v>@KB8>o$iE4d09S zeq?Nn2Xve9TtpA4wDN>jBOi)*R%g*JZ}7cYA>vxUHQfW6R+JO#N^={_Vmg*BD|k+E zo-y?V_cOOBy-j_A80-AS=m5xAKlTgjuXyxU#IrhkQ#@eADHB?o7ApOqU(Zh>u2YK= zJz&7lr^LHPdrEWlG38Iq^@15=iimr+^o5T_Uug_4t@VHnHE)Y}R>yx4KytOmBA(UB zHt~j4Gm5B>oxm5?2R;(<{n5k(Z;A)kcZ>&P!+s%eEhwfqt2Oe1?x!A!xL32=-W$Be zJRlBp@&U!VJ0kWgE>#AWy`PA9RwpXc3l46*Puy#f4^&-Tjn;0bdH!J3;iHIWb)us@ zKpay_ymX%@Tw7Q`+NdGH+i_o&O^z54VOvJM~{vn=lz`sbuvpU}WeBtq+TOyv-d3Zv)zH9PDbekuh zfe_$!kNDhie@LGw)g!sh=5EsOC2xEc(OU}EctGmd7sMB?dO+`f&nVA`4xV7Ns+iKN zcz8i{_B~49)5agZ-O8u_UP%l9Go1or&uaeQdLp0l*lq}bH2qQ$&*~Ij@q{xT_h{S( z9`%P&Ma3ez&Gd#|(Bj4e5#470H*biTTuAfeTd^-F|9v3hzRg$*AJ}JkOT@D}Q`XAi z^MFSp?%R}xc*BB~CG-s0{oE6Dsud7B>iL8H{URE}ZpPBs-YXOFtWNt6Z}#h z5jR$PgOzl)9@CF+klI~zPsFo2e%<^*{^JpiLrisVsQal@#IrhPOFdzseSwH>)(7#Irg>r00Cz%@PsM>NJzqtgGE0iMVf5rM)-29rRi{2V*GjFvSC= zITwhyZ(O}trD!bus1hm~To4A!u0%+G+|CA4< z>)OVEzI8p~QojgD9``_v@33y1ihyx-))RM0PJqvkGKh_jr2Q7>-~7f+`!{HJz6=)e z9P;7uz2IE`I1$ewPa4)4o;Cy#-$_+$j0H!t#^g3N4n@GqXajPadVN$-RC9+K-DX8< z99WjmSEJj+4(kXlmkd#(+xX7z2_JGC)aW**U5C(b*3c#JH*4CzU;CTiyDc#=BDZl& zSHTz)3v!zo$5fyb^+AnpbMC4Nh6!KP=r+gyRe`>n1-Z?P6DoKQ%yMvM$D)7Fw zPL0kJlac`S$^;S5A$N3)gKgszXq~;6fcZ{ud_upy3Lt(F;KQWTa9kx zH$4XYZ>>_J+pKMy2&1es)#zPcx2Hf-@>(^zP37JMa4{c7abA@7gvCKN^ej5|J_72u zv>_j;`XK^#u}n33&ZV^}5Mt#)K5)BfG!&McQ={8l%8Y_Fj@v2z+{JN_xM&sSpB$G6 zC*B+)?zlb%wlwjl_*ZR;0oZk1jc&6cEE?|bIH^Xr*<=|FRdUX%(QQUHM-54j*)OB;2gD^zB&rNDjSm9 zyqgvQ{nAWn-8UJdg4e;X)#x@$bR%HvYA0IjKb(w&%hPR%ThxoBvgiO z6+G^_TaD>&)UohLVssm1Oh*Sm#`@81u>Sj%^~g{BA|jya?NC~qTo!hOS&bZsz4}DL zt4~J622$T6%)hGX-11r#^z*$>{5?McmR)zH=i%aoQQ+aWPmOM~JTw-yVb)}z^t(yxk{94B)Hr*Bwi-n zr#0SRSEKU`+8hb|*>W{{T{FWZxaPEl(#JK9hiT#{HM&ifOAn}dx(>O`-ZB-`I#!$9 zrusb zrIC;qQkGF0-n~+Qlr}#wv2 zXw4nGI}$b@bEUq|o)-may=oAjl&;;=>Qyxk(_aOH*633D#E~laH06>Sy{LPmD7dlx zU+VAICGk)ieuel@c_bVhwvqCb-iQaIa|Yx#Lwc)VpV@gDH^%`{(8yPh+~)OA6?A-B zrbf4E>lgv27u}(I?OO9lSpDv~8r>$-GXm;-+@eOex%D{?KH7dz(>dhpDrovxpPnK1 z{ZtUM_=+0u&7IQyWt;Gj#_+}d2zb=UoZP0(0u^`~RwIY0GDHQB+8Yzkmga52d_&?l z(zUJ?c2$jTbLM^|v@z2mw@I6-g8M^^$zdK#`4{B9SEJAL$XCI*!t=yo$x&dj{-PS) zrm=Sve82aR#-U5D3JyN1LT=MYs{e)mRW-WJ@rRLMU~*lJZnH*=1l6^gX?FZsYVZ0>UOPQKQ>@ z`ji9%dRMB^ZG5FM%-W|*_p**O9||i<)#x_sVGYrUK z>PYLXYyLGgy3NhQk#J|#CN;WEWY2gw8(xFlX7w5sgmy6?x0xd4@Au}t8r`PxO%>>d z*Cn@k^Fal@ldr1LZ8D3bwand((b*WER8Y(PiM!~;Km*@)#61s&fn%rs#7{nUfSgsc zh%Ll0h^e-M`0In%-+n*-H@`Q>Jh#c+M!Z6RH+o+%8+!Lh3X+-`U=d|pj@5C`EA zJ`BBLeQqqw8Wcc$T3QR*q@^%?7c*YUpS*Jxr7u&5fpcwdhVIdPM;x?n>P&U^yCeN( zf5>Ep?orfD3Hb*mF?5fBKqZ`roy^cZ)}<)HBYHMN_c$CM4nwCcrr5%IN5PXenGD^d z_-z=xp0bYW?30)X8O1FbJ}ZVbP{H2EEgAa8H;KE9SWMinOBD2bC8Id&Y>WcmC1V)6 zN5TLFoUxit>4)crLX!crDgX1daQM7P2C}6@ry@)SM^*k<}z_4GtpDG}tRw_gHSQW2;n=zNaJ<`Zrq3&^^+|B|zGK z1;c%nemY@rG(*X7Uu92zD3m95W#}GC>Ha;@Y%p;jLj^S38OhK$)}2*?^59hBdM}i8 z9kK6t9Y?eZVz{qz%0B`UQeqhHs|@R|gpO|qFmw-x&mAByZ5l)ONJ|cdm2+k>bdPyE z!yx#@XyUwX3RrtSkfA?3>Ljf%1_JfH{8%JxZKNVz=@AMJYhx%+y-rGakk*mXN6%8g ztWzT?owrdyy30)JZ*QM45ciBAE|Do9Zo^ERlw7SqiNilN-;#` zCo|kv=`UToIEQqG?y*UVe@2VJG*3QDWAbWqIz#su^r-`+KcCLfJhnE6Ym3CsduQIT&bU&KKG4zc_o=V6t=|8*g(7Q-33N2rqmuD=aq zxUZr}3xyd?!Wr(X97qTSLqqAgC%H$59tyBuGL@lwbb6wMiKhb??yC$^M?jCn!3^DF zeH8`FVNnddqF|pALPG{KbPrQ0ebcJ$#4#oc$a+1U@}yn~1)sv!4EI%LtHL29za_(c zl{{+|v~rxs&^ zeU-u`Qp_6@89D}BP{1C~;SAklo-`&Nmu66U{kmaL-&e(OU*(=_DAYNZ$Z%g}=~)Fh ze(cK7J*xeqfLU8HNI{f(DFsrrB(a?~i=m&cFF~jrO-?ni^LDbem=Wbb!{D27qppawHIJKIj0t%^hj)PWYw^=r$W?I)n2# zLqNA_nr#ntde#DTo6)DNA>G&t&~4UEw1r_E>;T8F+No zdJ7t}I?>xYaTPbQ{H2YY5m_i_+b%TSMUWI+Xun z4;z@-s0Q&ADb5uSbf~TFTRh=}P#w^1lCN4r##1vuw+Xms4J_CU&~4J*OV@o|4M4YX zmC7c+uT5otc-g?%5j6na#$HOt*f3^{jnC2pbbt#Do5En}Yy`$XaF7EOm6#B(yJrJ) zSLsol`zo41hN&s>0S_DK?5aogs|}rDq-ixkw^={L1{S)SQTm0C)^O5Z572G)TRFok zPwA|Wg)>$mTu2k17nGMd7SOL~Al^C3z40NOZR;s%bc@a>@i@ro`E zaQkc(%CED;4({q#B~HF#1D-W?X$+$h++e6dO+dGqf6y9AJ&gd}W?y?dX!gZ~`uNWc z8}MIk1n4&B^z0}eoX;2!#)kbuRy{JLIPb^VLvoA}pxd1Ew1Xv^jENugvW5OTs{{6{ z(`jp{H>C=o+k8JS%`53V6LL&bTR0?rBN5%^^hi0>{Z|*zZL(Ilzy`sPSoz%^?#`)3 zY!z+;xwGn0e{Za`0sZzCls>G~8rtdE0=i9dH77`arw8aZ%Jxm*Kuvu>x5=vB1h#cI z0(2WMM?26tT9tTzrVR|JW&r3mMZ+ASqFqg5TeW5mVBhgN+NA3Ox{dExSC}=y0MKn- z+;)IA&8q^s&8{39*e%oobelTotf6sMZ9uniw6}p17D$Hm(=#LH5Ly#%-b$L*_$6K(|>KZx5^cOV?C#n}*YD;nT^g zG*2vN*}$w!V?ejLKHL^gH?RP7n?4V%;nqYWK(|S(Z3ovE7}EXNVxv7wF*79|;b8+C zb4+LqXS}e1H5c^(-R9smN8sHI0DWfAR|l9R-LuH4(mgx6trU;Mo8Q_)(7S4YZu8yG z1`^v<0d$*gm3A=iq5+`WEFR?mgJ&5L+gG=PdM8bZr%U}U9%~BdHu07=;L_ZP#v!S- z9qchT1azD6?hdfEyc(d}xJdP9?WqRnHtua~Af~@QpxZ=tcY@c$^#R@HN1PKhcxejg zHji{|U}^K3fNs+x+Zr~u(FJsy$@QDT^Sr8nZsR<|2CCZ`0J_bZ7)P*pEUhV$+bD0_ z!n#vci66|gfg93yY%$MuX*|sw^#I)_ysk4Op3?<%o4&R#P<@6apxeZ}vVm5!r1e5_ z8~JHF82#ChuF;~F_Hgy7F`(N#Xm1NE=2szZc1*hWrF#?IrjvAU%7z*Ox{dj9d#J9i z2Iw|zL!=niSx|bb57IMdgFc|!T(ockw=sr*Zu3pFhv;cWfNpcKhO`bp(gSpxhUrbf z{!KMNx0&E?1KQtn8$7NRxx~FKFaG##H|;fA+dZPzxl-9-CYCUvos8Jn&j_^ZEZZfg z^r6bTtjIthe(ZamRh|tb?zZs|Tb|yIc+J=>#*|US^LA$a_T9M&Z=z@|_&F8AHRmZip%+x$Bti#>PiMsBk>dHWx~1@|}KtTW6J$ZcZQ9b(;>_DwAb)uK@e=FT zPfp`t?|7K$)eR)K>5zAyof;EB-eP>HkQvVuh;7oYvwMBzG`6Ff9A;PgwWIX)1G3n? z&jI8%GkV`=M_X&Y%U8A22R6056}e5bfxB7trLD+q;?D18)k<5D+w2*)o3$I(> z%VIrb;S}5B9y^%9#dhR258G$4BC~jkbK{gOHpNAtXHh`)%WRp%=mx9JFSAq4!ioK) zvhA!jarPT^i&-YLAh#*(xR1?B(R|x*Qsz$PT_uF_AMU)Hy_?dW_=!;#%lobw6L$O_ zyBIH>ZIaw3vGHD3RHG%i&8s1M+1&{($ZZ^*_p!{5A>=lp7Q5N>4ecn-gNa$pCO(Aj z<(mKOrr6MJFt!X+f!5ZWd3nrwqbB}o^5e|;N+89co^^;_lk%XOC5^~q=f(#UD;Di% zw`&PhfBDf1taNV>xy_Wv2Utq~7L@K9ypI{w7RYV3lwDwZx(KxHw}6wZ`{)32n~W@x zWeyf-t>3x$8av>p;ibnfQ(1HXEL)VIiPLiKNj52=HRbOdvWpnq<`<&_AY=XLHdy~Y zGlBf1)$a3b;r^DiHoYn2QIVl$7ctlBmWFRF8#4cjiK{GS7JnR!Vd@!XU{%=EfI zV|aJ&O=fW?gxqGx_Fb&!3pu$>y-qnSwr+9FE$9OO{>=&}y zNltNQCm&%8^aIFe9$DnDz!D8#S*m7kxh=_UF7MpK>?X;{XG(76vVCm>iHGmXW^Wxs zXzh+_^_nFM0=bG<`wH7E#f+YFwAL}UxqdLQh0g&tr&R~)yZMzJ40PI3dbZ0>X7MhT z*7vCNEY{6JAh+3DewO7}3gkA5erH)$^#JmjtT&w97#c);NO_Q@#|Rp?$vMeZTeT)$ zHf$GNN9;RZ$BoiAzR_(KKf21cP7ug#y08=MommjM&BvODSbk+|avR0voh&lB9r=uU zL>AlV+k!Z7?mi~(E!88rO|y_|Ec2>BeIGdWCNq-e4|>iLIL#VO)#Mptd4jd^lT-SR zdPi9QGk9S zbCcRdx7llTnb{~6u9bv~`3*<1jh8$(ZLNK{a-uL}%TXb7W-|;nzeV67Qx(#zX&E)R|a+{zo zN7+@o0CF4MU7Ss?DUjRf$j`A=J%h<@u4M23?c1%>HgqAE&`*E($M3jmuhH7>(b_JN z%0fm48`3g`*kgSV)2_41u6Rl>7`tEQBAq$FJtEoZi85#D90Rg$^_=Em?KJhA3UbLl z*{Un0H=6e#Tl*WcfAdXR?Qh1$uj)^3!(D2!!iU|+ZBE;~l|>~alH1h0cSN@6P&B#C zM5kG@y*ZKOHVfT6WCsUG?{1}io5M9%9eVEEiQL9z%9`vR4|{6%ZIWxLt!#&o+dN!2 zRu-x$@jtmi;Z7{9(1hTv>|rJ{28r)%^ytdlpILHqCyVkmWRx&LvCxHnRA` zvh@&4-0S0NS)`O7*W9rm8p!%|(B!de)hxSaX(G9ex4{Y7wZq-1&e@qCWYe$2lH1G~ zSmD<$GnU+@eMNi!>ZfDLZAP>+_OIcPL~hftX=HYJ+f<5ep5@`}JxdeGZNLSxOBVE` zI@_n#P;b+Vp=Z(1=(#cj{TT8AmM~Z55s*s!VR~-%=cREJ=SBS;vYJLQAB32x0j8^)2_)Y)_tnZsj})}j+(dJu&$2$h|1nT?AkYWf`b+ibtKLN%+B3*Ps2S~{tG{&GfbbKmugxzjf{yw_iHic>{&ley8U zbt!t6IQcSU`YJRwAN z=HzI+H=Q1EUo|+&4f(IF(W=*1oRL57?xUJ;!Wrx5oz_>qig7{KPfau5^`|?=aMt%- zstWTwP}_VP>z7vX68k+3dv7DA)>f%D%6+W*Jl(wJ183AWulH8L{=)qo`~lyfU%*0! z?B~>IQ&lmGKfJfG`dmYGu9XXNg6Tu^=u$V-HV*G{di%5a4)1E>S{bWs2e}~oU%hN@ zcWMmYyBl75s+wx+hFaxD;d<3zHU~l5tT5}Pin4M=Ufea*{M?P<*x!&*(=z6@@WOHr z+ehh!VH5EFUin>(Osf=y>Qz7X z_hY7Qf?oKj);@N|I=f%ls2-*}V|nJFHY&Qu70X>4jWqu|!VCMG6<#C5YMCqYeZOhu zt8=}u&an*r481I8)HZovyQwDq>56fSa~}%^YrhYsBQcf-AF%E=#1KC`FJtPSum|H8&L z#5qr>t;##+jM`?er&=|Q&3$-pGrjp-^Jr&R)HaTe!REKTTu|GD`i@nVy1JmYdFMMu zWm@Wr+Gf~R3DzR@y6cUG;&Wc&#C5uy5-%0A*wLe zU;I7H=pW_>S!{u4d`U2`Q_&0Sv|D^LedIz{)Hb)p6{?u3Zm4ZKE{aeUN+VF)%pboZ z<1aRMK-*l8Xry}1#sj>^uDP|1Dyp{&>X{!Fcg+2@&dB}iHByyOm zN*dHQ9}lrQ7adSP4DTE+l8G9;CkjJj#p+d@aXs8=wOl-LYY6I@+ozU`m5vTXu6A~n zn9k~hw#gqHE9wwiEbr}>E)L5dirOaBW4V~sdL-Hm-5VmV_tK!YvDkk=>|mimZIk#Y zS$yWIL2Z*9en9M&V~g6x%p_BE88ZNVd)?%O_-(Q+YMcFE)5Qa6L(pc!zBf9?Gs;Iw?=J~w{)-ACDR(U&90tF zV(cRMz0K9o6mg-O{Lbpcp>#28f&AVkYGDfc2HFOE^XqJn8sJmjT5;q!8}y;q_>JPl z)z-+9HQPn^`u6DO^U4vT$p-mb1M5!h7FDn0_d?#w*NCf@v-<3BQm+s16l`~jSoV-Td``HF{h|l2-qRv%o)Hcy(3F21v+Yz|e8+8p6ySEyEoRYB`uZ42B z)>hXR{aoa?K|H|TnLxSmibKetZ8(Fr0S5b^ZNUEQ5PQ@oU3;z-2gG~fy{TvAWn#Qm zes>Z4Dok8F%m&M~t2T=F1vVbo->~LtHj8z`*gHMO!NJ?bdZ~`M9VR9Ys^i*-jpH6sxk9?6Q9tp8S zZPTzpqzKQa@HeTsGa|+0iW<~2wwZBa-ZE?Cjk-I`up){AyKY_QI$#3=E0y!>8kk7tay zeX})|XN=z?UN~=q{SD7NDjGytBk#YnTO9OCzP7U}O}zh6gW9I{t7!4`K5LBInfZyL zKg%6x8;wDXXr^U3W$$g?>u$lAzDb8EOMRRRX+teMKDmMONjoPNd z=QwfRT@9`wR?eHm?reU++>AZFTfDW_8e_QY`8HATWpQAClj;<^Uc8)RgBoVGWt8a3 z<}B!$;cU*HuPbwl4bkG~NNdzKscUwN#d9>MZBq1N**a!}8b;rBquBnVHFC4M@nX~- zncu4tMb|CXsBO+9?-4gP&|s|U4u})$o7MCElv!#Mr~7AW4Czh zsx4}pN2}L~r_b7=wrR9`o%ogI4&K|OtWFf~h#J&3GaeljlcNTrwlRINO3Y_t3AD}1 zc00xRYVtdokt;Wdw2<9Xn4W2SEgoYF?ALUscyXQ$YMU*SQpH+-*`v16oxVmKTj+q= zrjBvAIODn=upEK5@m{rCRDRoKnq?={65&q2_njA|_E_;v)+a5i zybzNLKpoH+P^a@30kzGO<;L{VgRZD;>P|GG)ni(tw#ojeOHFl5 zP}^*2q(|@HH9&2X@s|PZysHaMZP}}%-Zb$PD8=$sHc-4dMN@$4MCU$zi zUw+T!cfLDgG|mvU&FBpV^mMgGsBPXE>eG2O^ikWKI&Vb7R_LR)(NP&uxB87x+jQ5{ zrwdHe8eJ>{_O6lB}Cjht>^H+q`_+gyuOmKy6cR zP!rlFL;k&uQBZT*EKB~*PMyD7Q;C(sdfRA*0<@Z%h z=;nyVsBNnD(xd*NMtI*}RG?1>Zr4L?b7@FJI(=kQyw~qIq)RJ)FhM@@SQoDa4FK2b zB^#lif1lK+20QCxos|(SkU>ju25kfE$n1l*0sG0HjZvRujnt!0k~-qODQ~|49kZ_q za_U)KdO2GD{fYAo19~e~AM1O!F{1sK=ps9JG^Tn_n_&#IqIBt&{q^y^O;Xhs^e-!Y z)He5*8PP8xy4c5tt&C}_w|b~;44$)b&isMr(^nYMi%puKhVd=d zrP1vSksoFo(1AA_AZH~urW?N1$G-PX_=Eayt&im`9b3`6-3;*lt{2sv_C3%DwTC-*+k?Rg(gP?jIhoiQv*7}!vM?I`597eL<20ZHO+*6 z+Fc*}>sHu`l06NOCv-HS@%!py9ji92X+fz0Y8#8^26XlK1{k+~r6zR6Yy;FbDb9wp z%_x>rrfrrUXvjV(sf**J?;~USe2^Y$n*+HGY1b|FQQL$xYefU9>Z7(fbjgVRdD;Ni zkgjzNY1-Zf$WvOH(DWU;7{ggl8_^3b8ltu-2+^l$f)VPO1RVqVjLlilHtX4(J>6Jl zuk!}9R%!#(Hh)($p_S?ypti9)WJoU@GDJPI+{b`AeAh#cEij@_rZ+%-ebs~(FKd9> zCOpD~R_-hR?r2Y#5jFQQL~Y|1V?c`zH$ZLUP|JiqKGy)X&FtL9)HACgYMZ#;`qb=T zL)11&ee`L?v25*P+UEIRCbVKwebhEbR4wR`T}@HjtlO(gx3$qlZS(QDF`W}{gu3Ns zo<1!x)kSS{pT+Y~mL77m_6?~OizocvW>ZV{4Ttc?sBPY{F*a?R32K|O>|WX4tO079 zL)%Sh+e_?z!L&{NKMiTy;Rcwat`iMuvXLI@ncdAAQU7!L$Tvz2X%99x;l0gmHaC-= zu-{>__cn#42JCxY4N%*}Txv|Ku(b%vFYanZUyf^t+UEW!efp@F9g@M`+tmKb#$H8z z)HY|Y8_^9H8=wWH^!Ek&L-Y6yMqu>^Tw z@8LiB`8(g0Q-1d?QCoofq?T;)q-%A~;y$VM)VW?OKd)NWR1h}nAF zC#7@UhK^di8}}kjE!EHtK~cEB=CP{{y%3*<`=qQTdup4UihH0M*085dFYiVEu*QZa z1V`bXotdnD?x>|${$}hDI*a|C8??=c&GyvOCl_r#ct4b$bX<=6q#7DK(!Vm7<36c8 zc80g$y&U&RjjQcQzn%%geNrcVhq7;|1)^`A8hX$Zrb}_3RBZMTN_`ij&6cl6QroEA zxUb>k2Myh}aX0QQYVuJ-f7}m5j;!rL7oI$Tezx?orT34o#C=jTlN_k~b9Qz!)4gLS z45qKt%dviOJ4d?USP*j6In3wlhq0|4)9vWqK`U^dRK4f{v{LE{+$UAXc>ry-Y$fiK zBKZz?#vS! znpL)M>${g7wWzZl{cI7dp|x6vA+Nb_Pe(cJMEhHhX=uRa)woYe^M^e>xMd}l*E{Aw zW9RQw!*7YJGMkirTNZRk#dr>|0vyz`aiW_i1R4^y9eCW&g)P^v%9R z{k7c+|s`5KW8n}Hu z?volX+ECviYp{={@%59s82_Wgv7dvM>= zRDB!Tchx53MkN|*bTbUuc9}gj_6d^X(8ZY^86S-04J$d(20ItyUZHtcedy3tTXCP% zq}3XFyz*AuCv{|{h6Z<9k9(uiZrIRW4Z@N2-q_Iz_HpvQo{bv1*k~E@qAr6lkEm@} z9$R=N;XbJyLv3h<>{#3e!^bTqCZQ59G`TZSPIEMY!muE7}I?_)>Tw~ohsQgha5XoBHp+z;iqhpoMA&Vsh_ zXR%#8VH0wV#~RwxJ`DFsy}e*hBeJ7#pVSBk8#?4l4DN?ooz41Eybd|+xeeXgb`|nF zKL>hz*(%&8^`f@}&DgLWC9O>ai7%m;~KhR z>u%g9W&TM+KmEA`_etgVaG@qm+5LiP8*zdS{l0P|=E%OS4PDSR0{2F3PP3&I>qQ|S zoNPmPoZ5){r1YEF(4kMGaX(Z6Tj$$s4#Ry?;XCYU-9Lh{e6@=cb;^pzeNx-l*lT<} z8uv-LvHSAbC+l#Z)S#y}blc^vxKGNS<+10$Fx)5QooD~kw^p0khnmChUhLd{{oPgN zJzA+fX1(i%I>ff>C|YgHNfp@H(O?W!+I*d|Ee*;S6?oBwE3-3zPi%9g>c5xbIWz9; zob}yFdB~mfJ!ykApO9zU`u^nS?|eg6`Hj~T23=IJPfFit7LENVn!`S+ou?+yB|3h+ zVV~5jM5djF#Am>7iT96mqtl;s&xCzalSF44z9|dOpZT+y2fb`tg6GeK`;DOAI_coq zdRupnr}M*G;n{jIU1t9BJFUO-J=tR;+GfH&DRRe|ZYzDC0sEwOU2>tSio@~znaC(- z`mT5|o3N_xKIcvyL0tnad&BQ-OveqU7h8780AAX{gGN`9zXku8)nD`?56_>OdC`;lmTv70 z+U9$o5p+&Ujyb#&yS{HCtsHj{&z~tg;70quO~&(Qdd+sDnjQ!7{F&5UZq(oX3Z6ex zdy^Oay!!>7KT~h24_*B@AJ3l&F!Z9`*H#t5W}(-3>a;&R19ZaBOg9=D8=e8bC6*YU znEwLLZ@J{_L&x3Nir=Q+l;}ybYscaFGdgWuY4w}gc$UjKM-Mvm@D;3of0q~StbYi3 zCbRR`^47het-t3FqvO4I;`uW%M_uWey4&&m8U59+bmHiEJb%X4!jo7o%C=joX)^sdhS4DfAReK%T=wi?f$Iqc;^kLSfEYQds-7-%PuMv5{F&{}v~Hwj2HfkDZ@W|bxDez>JD#GvMz^70$X+Ywb#N*e5k??ilLPYHS8@ zq^~<&nb;c76`@a^say9!c;<}NI%gU*EChLNbr-ke~@8xb>b;3-=5_`pDnK}!agZ0?{W0q zwtE?{PijC@R~p&rX$JgFYE}hTTFJ)?&z$jM^Y?(;D&*e%U8q%3Jv=X^xq}Ox6p?}4 zd5Syc5&8~!EWYBL0e_Qflfb^&HLr0d?2~$5*M+*(T8`(>%rbJJjuVdI`7>G7J!tT< zJUnw|&T&ur;9@ND1%37%6;Fo@&^E?d?(}2AmvrcR+b14$vqP0k;1l64)NYLlo}FS; zla1kn7Fa%Ohch+H--zXT1unE^@fkdG=6!2Vx;1wL@}F8ZhG*nros}M*G`&T)OxP!t zo8?RoO7giqd-Pmsh?kHFf0Ghf?nbVkg6Ge4Kj=&+EnbCl?HU`aTVkf+`7_s3ooTzR zC-MB5wp%@D+_>R*{>&qm$EpX+@XVPxY0h-tf(^*m+5Bo=b1BAf@dsymw0n(A_?wg+ z`|gc?LBmYYGc6js(9>gEA+KX|_KQwu9YOn@%$P66c?)Z%_c^2*%2wsI; z+luw;@JXy=vz?9G_Ioqnx5Tc-ZnRCq@C^7Z@d?R|j&r+%=g-{G8&2Phwa4>kirKjB z;A4R~s=&VY((TC{JacAH4x1xS?2(tSI{W;EOn7e-!t$G7*d5QA>7ZrTeu~8NXR5@w z(4#v~WBKN99`xyfDw*(G;{IVSwC|Dbneg6bC3U7vE)K`@XZo@@*Gs&c0sEwuc6OyR z;@0E&GyM*@{PbP*OVBLj`ul-Jif9(b6*rAUyCGE`3-U9_uqf#d+|Sg&prE)2-?PV`Dpre z|6x2^&!MV2-F)c~o~@Vj-k#3zNyoGGjBfR(J@#hHXY1V~^m61KJU96EVSzeac!K8! zA3NQL#%F#(ZS$FF$X9o&QP>0iEq>rHzY(weHu|r=?S3;N3(wX|vb3OYjVYe3x5Tk8 zJ!X-E=LUabJ{aCQiRT6fd>81lx)jgWTj!XEIf)&ixSZs57W_ZtYb!tEP)Zg6S~fmXYFAI}YT zsbE1%*S$dB?ziYirzPFPbAyki5vt#lops6X>0*wC7N1BHK_~n@%#wCvjC;U`Thfpv zFOW|e_oHvUj-a1&T-bZ68ka@b13uuqn%?K4?$ zuk3$A_B{LN=&K_9P0H(@n${4n;JLv|ZmH>!377HQV7Cius(aZ{pLR())RMZt#$s?0ot@m$7_Qo|>8zrHi0#bZ7LZLG!gD=#Zu+ zedvOPr$yKUZarV1liM5>;a-38y%qg5DGfPfpCw)k<#6pVwHE#Cqv}KRUKC)RrwavS zu*n&;4KUb;et~`4@C*^O&6!vI=;pr5_%qbi4%}v*#q% z&#ytKQ`$M?+F#Vv`TG%!Vf;w;PM}CWH@JzHKzD68h35uWzAn%k+s0~%`&{S^t27a`P5n!j^g+#R5tkuBK($k zp(N18mU+k@*>?%9H`I!-uSaXwhuV%UK-QZqU>>3GkVnUvNAYYu-)&a(YyV?-w%(N- z3tFemc|14x$Qw1Cr@DjZ2DeTYXy<}r5q>{hYXzYr4_!jO#m3$}TV{u8o2U6!v}&bP z?ECUz8altSguLuhA9{GiF|6Y(TF~QHj$`@T5JHEW$c{od`WXKO4{1TlI#}y8AC-+;W%?mDU}{v-N6iBDB8i89X=mt%pDt56r`H zGKs~c@`f`a>;bRnBvA3uT|759tW=;I?Q`(l;FN;`eRw+?*N{Iiu`%!=AGry$Z{O@3 z#_&Q_fi{~j;n{jw8~V`pKeQrfo2n%iG>FYv;4C(0T}-o)Ki9UPw%U9=H~0#(Ga>i{ zo~<{>nb4qb$3*!3uR{)0Z|mb_vf7u69mM zH(C|oxxvTB33Sq{R6JYH(9D|t>5+%$2ImyAwb4Z@!rz-(bm~JdH9alDdz<$w1$xgh z57~pocGZi!SSRAWKx>qw`ljh45%z%hc+8GjYjP6L4W872 z&@Z{iF-Jk6gzon|E5aV|8odOX-QgtiSyMvmL>FkI__I^=SYLs^x`R4PN zl>I|yWt9CtBHM|j>>6ZdgECvl%(lqdK!!FI>CZ` z{s;;`p$+aonWh`u3fhG>p>1Gj6MQP`7uZ3DHlYtt4sAl;fT2z3GcdFXu>giPAx6N^ zCd3XH@}(#j74;!L+z!Nz+lP1}Lz%)Ks_>I4{Fj=vOd-u*1!^D7-%1vAJ4$Na+(G@T z?^d$p)_WtC7X_V=D(oMNOl=FKmz^3ScT9OE-JZ2tfNL9BluGL&hKsFO#1&zbp(cxxmI zoOJCe`PQYQ1f1<#NJzIi$We37lR-h7k&i?iAx-b3BafZ1kvLt>M}B=^BH5H)j2v;K z88NN*963>MyD)0iE93{e8k;K0siMB5up=q#ONw?Sg+G$QPf6jwr0AEV=&z)RgQSR$ zGH%ispUdhs27R<%3tmf^Mwiv^8AmaO@kj95hPVvyr zQeBm5g^wg@GrDPmrd^Zh$`t~X$If{voxL`SR5Yupjo5WvG99{7fI3Gmy^@@VX(`kh z-|@M$+{Bkezs!*m?%a?z7_Snb{)G;&CA%5NDAfNW`s>%OJAWP0Q{g=Nv0juWcIELehKoCtf@9k&~&J)j|obUFdvSDsCv@wOjASNd6li z;I)taTS}*G-{7@--wriZv`d`YYVq0w$6}@Idk^v2ZNC)a>vW zubn-pwbY?%DP9Zp73~s5e~BW_q|o<0UJLaV?GiZkDp8C>ayhjM$$Am0 zJsSK#@*LD3+1&S*balvlWaGZMQXh|KWGkOE=|aW? zDtXl%iJV*QI^9-v6mqfWOPcf07dbklqC}%7ASVm8rL=ETk;hgulp@Qnb$o6uUOy`P z_UB`3u}T@o-%6KM(FRyQX5mCBd4?hK%IUMD#IH;Tvc5DjUL>iTH9=n8Fj(@-Zi#%} zJXGqE+79_s{with>2AoD+2N9!s*zJZu9a*DTO+59ie#sD4MINlF;d!N=7BurP^9Ga zR_@oi^%0Us+sRnoVfPy8@rGH*pFW03I-lhj_KRI1S%ojb@>WS9lFgH)$OiqFNDJnL zAXnF!D|PI-3^}Xy6zPVM%&pq`O0F&BI@i2Br8^$-we@tIq}kDdSU+N#tyIl806FMp zU+LAv8OYn&mcC8da-8E9nn}mKeXu;CZZ|1pl`FD?O&4is_yFX0UAss(|B}bRPN}Oj z`hq!@ufEwsT4~u8`O0K-X-srm#+PNE5BdHO;|bjcDB_DE%-L%m@Bg7fG(2B zNgrfY`)*Q><3wcJEHg=0eD=paKjl8yQq!b?Mg53Ne5N=|auU$U~N`mKr<$ft+EsQeuaNA%C!5CM~;SjJ)UC66yI=BjjDR=SgQz8X%{C zpCUCXD&q^jQa!C)=jB;XsmajBSjW1LlQcf4Ir7K3w$i4SrpOwxuhg_s7v!=1*%slF z-pDC^%_QHz{>b`wyZ)4~|C{6LpEV&=`>$FP{+WX-wEs?Xu*iET&PUS&!BTM>N92in zf~6Ie?T`<443^F`vqDbmzf{__wGZ;vS4*U(NowSfIg6!Q9`YRD?KfXioiW4m8u#W% z@iluO*DakciCwxQSI?U)^|Fw;#`G1n?&HY410?sx9(e7Q zEd!;7KZYZpo-;^NEgpqj+GL1ye9l+G%-BUcK5w+U-6W%iA{^A@$dvg4|kX zwAALc%=7(An_z`} ze&|x^=BGZ$!)gafHq`{=*H;%yMMrugA9_7snrGM(x!y{DX^UkK2 z?hKYjr28V97Y~&t*^WoHTJ0u%Y&Qw{>S-@&j=dl9plLo*^^H@IAB`R(eXTkb8T8>l zb76({-)$~{-h;WIoEOn?a(=U>O_hfF%6Zr8H%mG@S{@G>=jTdwlH_r6^xXn!u>BZ$ zoJ0pocEd&@XE+5(TfPoMHe9q+YHH(-e9G?Uw*Hxe)3yJTbMRlCyR$ee}*d3A7ilJZ7_-2Yw|^1#Rm`S#zPiBVs#^70`@W6JA) zcbcJgy8^oy5k;%1fC51hTI z+|EXi;Bxz_WufKm9%>dwxIZ6jts&gc0X-th{eKe@S>CUmA0x~A3*|fxP@l&K?C`jO zeI8F}m&Y0W;qeDQd0xQ(rB&qT)2B&cWN{hSTDFYrDh|UqykO;tWt^KINtTz@$zi;* zjJKCYlX30j=idazzGZxz)#*2g{hgD&yEw*}l<|FL)2FP?L&n3(xEgC0#t*EMeEa}| zpWr_*_z(R8hJHbRfuX+;2VjT;#0MDS191a}xWV`V=5YpwIK%ki<&YO%AMynZc3}Jf zgMAo3z|by?A7JnY#t$&~3F8D9{D<)a%*PKfj4NIr#v8W-t=3rQLF7`>d5S&qUe{pqdEy}CGbzF3=}c$j z1MzI_^_8DbOPU1}^M)g^{HVJ{|UM3Hf3xKQo@%xtJ7$%FmMF=jW5RWzU$; zX8RMVM1J;EXU`xOMe=&P`l284s5BLAZazJpR2w9hU(X#)#+;U)PaWCcCjzdf=1LPtkJOk9yKJs&_kn3jMwZTaE> zWcma7y=Cjt0i^OR`F>&P=tvw*F%Oe%QE z&y3n7LrF+2`B|VDYimhO`5D2PwY8^j*|P&{D?dhlrdZQ&44GP2er8-gn|*_%tbA$W zRHD;Qu3sZ{7O7QBwo^219_dwEw%<8@A-P`GuBX`&vQ1C+=jM?ha?f4%b8`MtGH#&k z|KbI~WNJhCSvdb_Fq!$#0sFO)l|N@Og#N~|`i4#VBb%fKk<%=OP=1)%w`{FKuAH%u z*tC(K%`Z-$N1DBnpYiJ+okc#g7()H^NmB`of8aPa{?C?`Z)LH~W-*8IhP`|UWw`*h zp6^8>SdM^8S=`=UliQuna@U6C6v}6_oIbuO`#F&1dL$bIQ2qxS128s#Az%Mj$H_l) zT>Gz@0n zFMr9NRlo#uJ1zTD1H%Zh~CpLnVo;qBUvu0yy#32zz@?&tRb288?X;AKR3zd~v?B)q>+ z&f@^}d3?YQj~m$M@q~7HoWUO+fAEv%1^m~f$CdZXa=pyX%kqUGZDqc1cUCwYAjkj9 z)Dyyy)v;LLq>WZsF(C$d+J+3FzTqb1S@%+fjaxP%e`<4Bm|s5%xySs2<@x&Kd5X}d zAhNu?g+oMn{XJLLAcLK*LE*??zv_t9$k49NbUDA^&-ml3upIpKcas_XpVeJv$QLiS z8hxj{{?UZ{<#rP0Jt?<8|HRAkc1@k%3f!Mo)jkN^&#lKlmHR(t%9rwfP5<_#yuVP+ z;{f$}e83Km8`$UZgm!tH!5L=<~jtJ>kweBLx8ys0p>acnClQ=u0w#i4guym z1eog(V6H=exefv5Is};O5MZuDcsb}0ULSM_FxMf#T!#R29RkdC2r$HnEyjHLK7 z{lDL!p>!fp*8fnRT&Dk_e$O)f4|ax?>3^{ASEm1=-Jml45B{_))BoV-jq0-g2mj;T zW&IER;^ir3Ih5BQe)lNlb{6~Zq1?W~tXRt1_3XWta)0(2FQ?qkn`ahN?tkJMf6Dun zojZ&2{z5sA1Jvj70XsZyV4uem+U0Que|Y@CPo5X>U#Cp}L%%AQ>HjGIJ5;w!|LYvN zPiK|s|JSRZ(Aj1B|NM=Y)V@sr2aJD9uNcVse|F;!)V)mqzrFs63T68LXwaAPejRV{ zmHxOT>whSJU@z-`s6U}h|AU>kOJw~I_D>I&^*^+GW}2-3!JoEe`XBu4U8euRf3q_E z5B=ihJ7e<8>-QLOw%m?G@QHH!Q&igWcC!;R%KbU@KDFFWJN4mm|3lUsEbrI6?oJTsL$gAc6i*tK947~%i|3G@c4tDJTKrs(U%)(Hz&u~TJYT^7IbZ+GHFj_MH=Ap4--I#w z&%FEhns=Z>KwCoY;C=_pbqFxmA;@Jq1eog(V6H=exefv5Is};O5MZuDcsbnPd40I= z19Ke$%ykGb*CD`Mhai{f5MZuDfT3TYLx8ys0p>acnClQ=u0w#i4guym1eog(V6H=e zxenpwphI|l&>_HFhX8XO0?c&?FxMf#T!#RI|H^#*qaptzcd-8O+yV340rT7e^V|XR z+yV34@$!F#hE(S3mG%_*)Vzw6q~}DU7s>p_#eu9kb`r~egFYZGA=#h$S{Jk^Dbv{&Hp0nye zdHoZw_925EgUBRgu-`Ov4>GiyS-cAw{5i2_Co=e%`g8{}`0t%4GxUp>kG|qsUf*xb zuyQ*y5=NHWKj%KSyxok+6AAYxSo9;@&l&BfmHWRsae8^b%-hWkLoA^U ztj}TzZ2&{eAa=kIONc2ihgkFakON?_1GxbP`;aqWXcuyc^_f2~CV;_D7!$zYKa2@r z=oc@CvBT>_EV&(sCASZ;cj?yUFLsm0pjKHTh@A-0XA6 zF*9;Vl@@!Ew~s%`?1Uhb?Bm3=c2Bwfifq#6X1WUOnCE5@r|{@qz$GiPpgfb8v-%>i zhSg_wkiibKj|}!%yU5Tk^GB}F{9%3~gP+WQ3U5-mtNO3}c>+4P+SeY-}LIm}g@{ zuFu9i8ym%&;$c3_Ng`!M!+yD%oXKQLCgpD>2G|7Bwy z?ZcR7a{(F3*&IQJ`fTnXgB>=fkikBiYskq8v49ay8deTW-x7vjnNfjDzNA^zNd$P3F8+Amw@kzua0ddRQ_uZ9;~%imgq^uvW3TU0%-Se0hDg79fKiwniX> zeYSQWL%VEEK?Z-=T7wLJvNZ@9{AX(uGW1JPu2R%jE9|Hh_SK4Z)e3*q3P05f{{=WDYh`(Bq7nNdufhNE{!n&f!FWmdF9M&Plcz}C9mczQG z7(a0Dm+P~2Q8C`&-jC(5E-J>Sq!_o7VmwQVaV{ywzoeKKl48C{ig_d{=2v++tSh`e ztT)^atV7&BtWUgMShu)8u%2;0VV&dt!@9`(1?wX3FO>5*Kz$w`u*2g9_IW&^T^?uf zhsPiMG1gSd%5b_JWVl2HfMocW46``UGtNLtmi{V2A;<0SvK$Hh>|P{9XyM zRNQMM#XU$;+?yoDJxfyD%Ou4;PEy?aBz~`iSSs$7<>e4dULRt~?LaKKeTXG*7h=i% zfmm`sA(q^Kh$ZhAjD6l;DCcp2`aC{hhsO=<^LRqLJkH<`k3aay^8)@W^r58CA(BF$ zNDAE|DfEn_&^gSGtPf$0QRpIx>qA(Rc5gn_8gd6~71xJQ4r>{d!&(Jv95C2{wGSB9 zDp(VNVXcC-66>?Ilj}oRtGGUdwMwB6%gbS{;`L#z;&x!I;`U*!;_bp(#r=V`iu(y` z755+3D&8-+xA6W#IgbO>=kWnMJZ@m0#}nG+aRz^Q{J~G27w{kMkaE}Cr`33h#V3=QUj|7JK1@}l`m|t*@1cvzq_ekKf`GpMgi;ctbayAaj>$7o) z40hN!LkYR0Lu|tM6gT)RR))E#wWLRTZ?Bx3F{>5U43~LpO9Wty{tnKo0 z=2Lln<|{JTVSPXb`>b!s&@St4Q44O?*u2$4nE9?jg`+}lfLE(>} z@KaFu&(8HL@0ZXi#z+nRvwjJK8XQGt{St<~s3ny3OR!#Jj?DTcbT;%sX8jU;-4`RX zehFhzRw1)~spF(bWY#bBQj-nH&@V-~sHiV0>`;Y$s%V!g{GkdzslxyNv2((I=S=ed z&i7V+=X);yop06s&bRRXJKy>Jo$m-+Odf`LA9{G1=vUJTdFq`|QE!Mna%sR?@nVGh z4dQ3*w~HezY_a^TCS5#bJr=oXHI?2yYVPr9$tN%6$; zyNgp*9gJL&Ri~G#+K0O!SF9_U54M;6$?4Z2L+vP+M;=I4+q9C)h0sv-94py=*X{k( zvjb({?j*iczeuq_JN}Nh)kReZ@`Ik|)!)wcMIN^^T^&0~?$?&Z$?9HPn_{_1N*lpt zTSw%%HH?HHd-*%d)q7PFW{s+h<)^9=Vfe!e$aRXk3LmFcLXH~HPFQlM26E_w7DE3F zedKc;S_p2nHsd_~>z=#tBrF^GXg4Q83VVn=t;9x1?$R0A-E5SQY0(?mw}P8s($gM! zV%lKg51;AC4?hkNr1;gydg5T=OGzlMd)2eX2>q>x;J1n#yv7Qreoz&x37QULgyYtO zMPSF7K0@OhGvtab-Gs``jgg=98Y+wkyoYwKLTUYQBwwl+ZV1I6%-a`1O3dlwl-GoWw-(sD?-d%-PViEGEmOX{*yKf-h z?9*46H>@Yt?>N1-(4>D`?m4$tI-dKLTxtIEF6M4qI%R^u5W+3k=pc)E0#yy=%-FgAB7y&tCiShx@>3P>0OyE zMvldD_kJJJyz)JeH=KzQeTfrt$)4q6^%{=ITRYAWholTbK6}EJoo(!nZ1K2*=(kz! z?+}BE>LH*wSK8pyY{_NIfH%Q25X)4u#HWe-&<9|` z*alq7%CHS!Ru|g_FVG9O9;Emn!_B3O}jBe+oJQY;yer%=Hg2 z*FV5q{{VCS1I+agFxNl8T>k)b{R0g70{v4~j{2vpKI$J}&>NtCfI)|V{s9Jk0{RD- z`Gfig81xM2A7IcqihiN~;pLz!czw_tz+eY-2r$<_z+C?TbNvI%^$#%DKfus0&_8A6 zsDH}pqy7Pg_<;TahPWx(Mg0Ti5NCy-sDGdw@{;TIDdXJAG&07d3jN#feJ1e76BTHc z^Fu`7H$UEqHv%J(^Nb3`i3g4%Kbe~?o^!t@^Y?f$Ap9lr!x>Y=Kh}Rk)=4oE&1P1n zV8^WgoJ?o~n6+sRZ2+@2RnP`7Yf}wv0JApL*al|P&;~HX650TUSYjKDA(pIPSPrp-HlPl~650TUSV9}X5X%p-l}Mja zOSDTyK9ma5Dv^bZ^&=lje@DC(fa$A8l2vpe@~O^Gq*qIGk!!jeT zFGlAIZj2pzJe5Lb<_Z%TAF_HX1$xPK1~z|69E0U+w+wzt9&VCtYT7>`x7W*UwSM-9 zJj#%L@Lm0o42rKr!2ZV(4@u7MO2mWl*eMUmiOJ-s(Es`&EyTFMp`n~SvO(>XLlCGP6vZ=J=&?lL!|8uf-U+eWG!7iJeD;laDWEeq=HCbfv zwV~SET_Z{Ra|en2YY%Ogs3_uc>@bO;9@>4*(L{Q9gfyG!q1`-S6S-QNO4@yN*OIC+ zWLD-;vc}V0d&)9~RPs$DCVSnqJKM&P#pdZGxWH9gDsCc8%ri)bTCUo=e?^l%12ajQ zmy6c9Rx~l6FOub_owe&hKZd({`IkHe*M%r#6hS)qph8p4BNyiX|`VWs#?>Uv^U>$@?2x zV*X;NcK`8p#C@kk99uYR7uDH7{#ryyV}EC@yF(ONF;OIypE_&X%w%V7`(=`=vt6{k z1EWcouncm&k*n6*ZxdN?E}ax#b=B7G8AG0SN+-j%xM?R|k0AjWX=KzqcdeI0ESc_? zMoxKoXtzhk{*-HF?v!~~=5EgYgXDZSPp$L3sGstl{56HNN%Yfhii{$YuO1}vtWIL+ z&v{o~Tfgxz!E(eT?Z@tg#Kq2A7|+H}g-LhG2fY!<1yk>mh~i<$`)1uGt@e2#`_H>e z_U!i(RCbfJm*W4QJZykmuC)KFYug_15*pi2(oQO~$*=vd`lGayuRlWA#QJiB`R{Xo zm|)8M+{ye``lGb}tNKct&|mJG>f=r#Bn4IM zvdDB7auYT$KJ-e$d3v_ndUDTk7qWwY^e^k*VP{pr-0xNOCYkC=kOz&-BPaJvNA7ES zj3kbVKt30Az$UVB{Ms* z+vIquc-%XTlDX&%LMVYS#H>2=c zi?+K-*Un>v+&v4lOIsBav%)dL6@vxZsfNWw6E#+N8a!Xyqee0LHfWqs;a!0C^?$nux-v{3=+WcmkzBrsNY%p=oJjwI_C@7R5U-2Ebu$;?iE=RD$+)SWC~F>gL7 zpET)hMuzST(6;|{fwaBVlib-5pw+})Aidt1lbn$O+Gh{*$n0l9!Wvfp#q1)oxy~~o zl<|<31tj5{9$Cuxsr@zL6zngIj|$M%J6J?MPMsn+Zwt^4yj4VU*$4J$%Ruc~iz3pi z^E}}ln^PTc6q50M_hGqt-@9aa;%(%t%>_68$XRz!cYp8e zB;Vf&d6xBQQZI7_a;vF_e#*6S&MM~%u+q1-2LrVMg*V7uRu12HI92NwDK6t47jKgy z#v?`rY9B@wV4WS;7i&X?-}-6%E61>MY)|tHAwOaRv{K(xlHVzqyqy-H?Ua~GrZ!nh z=9vd*$?a64|6~bS#`0_MCY2;EGRM5@8=oU<+j?W(^~YwD-Y0sI$@T%-Zyx8#(MU5g zdQE`#*xWqw?qW9_1M`MlAZ;9igtaV>Ib#aRq_quh`%yl$}z9(qjKH&o%kr{ z)UW2ww0ZOJ`yDZNi%G?XGm)nh7nA-alaX}~6_aW`$00X$DJHh#MjL;dFoD-SK!Ze#X^?5Tp)#>LvZ=Zk-9{ZX!I!xs7qu+Ge= zUrcDKuW;LAp>_vb-zvTF6`U$8)P6T9Chge$7wU9n?RK_e_j<+^91BV8U&E0rekdeG zCw-8!!i)aPYv%9xFw1cw+NYHZNxIo&q2}8FtxLngpVnSwxpG`xTQXgky*)tN#isC= z>xpu#Dz8RPH?hn4Lr=kKrPtg?>M&QEK;V*OXv zSKbSh_Y39xQmz}nnuE$~kFn>ht!!-98~XD&&tc^-{=Zf$CMOt|1_x>nH7_FBjL#Ye zYJF9OWMF9#)=9`NBnK?tBRhE9{jK%$ckau|`@3@9Dd+p~^K*skg@M{C{fh}PpDS1# z4%8Y;Ma1)}zi?=Jpw?{E&-bt2y=VQu-4`HM5EF=1%lC5MH|yLXtE}X{=fo6{H4js; zj?TeC6487kvU^bxiH|8oKYc3|kWJM~(a&x{Y<=GK4*k5*_7LZ*hlJAwa4Mzw|p2@6?&+m*Gr9Zzjum7j+^|3o<3hQnMYPAE3NxvriFe;ov94vHH{M6q8q#CJC{OZ$2y{mJKHh z9a#MspCZ!W)dV4$l`pwaM1t;*7d9}qN-ZL>vnC4lS)D?&BC_Y@SYZ__4_L^q{WxBD zzAsR_rwY5a>R2I!l{fP)BG-I;g*lABniP?Q?PCOi)v4-LNZR^M5lWe#VNHw3^He{f zgz?6@MP#w}D8Y->e}1TtWLEJL@>uz(Z-u1Y@X5kK#(zIABs+aZ3RbL+?$|=ov;71i zaZ;f6^!P$Dug!Sj(ZoP)NaI4H%(ZfCDCg#{?hDFXE64Wl%mt`(=wTqv7v&gJmMiW2 z&U{hM$2+Y@2p(*FMzMMH^7$~K{mVe@A~wI2V^vvS+3v5dRr>j>xuAUKpnMPTtLJXz zy9*^NpUsue)XHb=_?a0})7$K~*n>_9le{ye=2%sX|)pXUGb=Q5@de8cP-@Wg5 zSNJCnHPyRzJx}ejuI_%5hu4l;b35NZ27K~6Eo-C!FE5jiTfu;DzR1VGi8kD~ zk|lKL`^1|2{2?k8XLYjVcACyj#bPD~++=tv4yt9qJ|3y~@RtS8ll?putxbX3$=s8Q zZ_5I=(_nE1E?uHt8?94)JO}G!6BeSrDy8*9Xn1$NO2JALI3v)IY@R+Na7;)U3`-Tab z_^gM*eI9mHi+`RrXtCwG7Ee4i;9D=Wc%fWBZvWnQEe3TmV5d4-Y!>Rk?R9Nfa2U;FTO7CwCE#c^S!Z2a?@0r#}X#?vYe|CNPy?!Mf&^AXvY zUfO_1`DbJAGQQlm^=-4!tEmB3jmyPxvkdkh6z1ZyaJ8)Sxfrp*fYYAjV(BCUc6ZIi zq{+VAPtWza_;sf*_w(hJ4D7VfkNY+zAp`#iFyIM!8E9#0z&Xb=(2RapgT?0Nftfh? zjz7QFJ~9)3Pxj|FjpK1dd?8kA<_sIFy(0^oBCWd%?0)!~9Eu1e$Y4M z!@ukYjQb7ac)UbozuZn+e(n5Y`8fP^A8ymQA25!0<9@?9#y?Hf;rTv>_HP{HSLYPs z%zeFheZ$fVP`6*U8{gBb3`oNJzub{R6puV;vW?OUKVMgE^l!ex~7HB$V5S3u&1Avp=_Qtf_HZHP+O) zO(rhR!rx{5I6sdnWZ~<*ew;Vsb~QaO2e;8S%(QT5nuG7!`||w8?b*298n=Jrwpw$j z4sS;o+M97(-PgJhV>brz`Zi6_;puMyoQGRY^0A(`Kj$atn+~tt^XK*5u&w})kU(Bv z4A*SkSuymdsue)o)9<+L9%Y8QP zV~aT^;)mCLxIdLfYA|7QAI?duhy?l_pgx=v(`$@WFELJaob6)Et9gmg|9YTQU>z@;n=kjdeF}5C6`X`%lMKV;%pU zvC^2sf6A3{|Mu^UQ^tMTzccD^S zpO4Shn)9~wI*iVloA>58(moek{O-x|qAEG~p_2js)A`{)ov;4Wd9v~Rv+AKNYiZ9=xvziOj*3PrLFMH}>DSUTu{etT5J;_nChT%Rvimcix8>&vlLKVm#M1 zo?{1PXW;W)g!h4sJ7wbcXA18djpyXXbu^xn8_)SyE=)r=I&WuVYhk@~{4xi)P2)9! zabID)M(9&L2_0$}<{=Lvwb&@NH|L>s{S-X!qi}u_Ewotu4|87M@tPzw8Ecq_7~A|; zd5rD<(?057jZMbm+NRD47!qT}_1f?@0lzE+j>Dd6@OYd#$Eo!bvHW!l-e*~*mC`B=Y$H^+C5=3^-@PmcZQ8uPA=JI7y7>abEdSB@)`FTk%^P8^r3Q-GE& z9XNjYT!&d(`f_}KnGQ#_?!)ne_xZU0FKdonJLTi$3zi%|x5&fNH7q#Z-ys)gB@vFV z{mRB;aSF%f4rJk$at5rKk%_Zzne%k_?ir|SW=P-gISsup8gR~;RIL2QU}xar6pR{U zus{A*GVZsq;@8GEOU8%(HXJYBsKwq|gP+Zz1Ws$4Lq_^4Xv)r)%Ler4)E^EmApRl7-Qa%pq;d zT4h&EHpY%r;KX_r zt7K1jcR5Wt);0$t?wi8dEg8zO=~=kf)fDnQvXoW_Gw`;HDcq=-qu5qU$94})Vd$k? zW%-0uTwk^)Oi9dFM$u=n_NVoN*Wm?<*Lp4boi>M@!FnZqbQ1pX2S~BrOSdu;ahH`9 zG;X+G8FX2LSI64IjQ0nW?&CFB<5*vaK6Xf1W{xmm+Yu#ojt2dAxxk)re<)i% zXwdDAJAAP@uJlY##QT-JA-MKQ3Ho`2t4h1Q906t_Ths=;cCUpO6MzCXxc9nI^Dmb)CkH! z)3gw%wDOv==u0Bzgrt9(K zIy=Zqe5SPRt;a{>Y~aY$7fP3Th4|NGOPJW_l~QaGeRemIKy3XtN_$_rp0YLv`-g88 zlXrPI->es`*S%M|uFb_JXUt$}@JHqM!)&~JkZRZUvvRpn7JA#8Lh%}3lokOQxO$i= zn7#O_tlgW2_7% zLbr_oJAI3jlVcMxB-{$#T9qJWE@`m#AY15Bvm|jJr@`@5#|Fje*-cm4lZf|zc|oSOEXm%IgqlKMh+12Y*dNp4upR*r zIlDaBN$1aFNf2}#T7g`kdu3m)1Vg5GMe?OdI!-zl0v;VI5xeUdI58*`em1U5rX*xx zUzbprShosUGc*Sa_JqL3N>z#ObuRW@8VoJoR3#Xkk3H$Squu#xq>4s|zc2X1!rbbl z?x_OoVebn+ch(>aato16@Pe?VHA&u3Jx;TA2fN9&$kD@kJPI!0;ZU2Dc&tY|x|j8` zR~>S*P>)wy^@Ssy>(b{n^q7%v1I{h#kzSiQePdo8$uYE(uWZq&^wBREN{H zn8SoK4am-RbdNE-7c`=)mHMfh$2K96 z`!aBxmnnPBVfK@d+lD3uU8meUwT=?3N^k1Kf?)!t`@smy@x??(8UJ8Nf7dw;54>EB6z)*l= zT}V3JtL)|(3iGflnMdQ%HZcUs<#i*gisxbdaltSuqdUo(n~!dVfzT_y2ig9I4ma=g z2ir(fa^*?^l5V~bI^B!}A1%bSoxC7)Qcpsr=+XX9H+V3q7uiPlrlL1HgVw({x$s1f zD;yjk7tF~I9o;whX$Oy+DC8>DvGV~Nh$~J=`xS-QZ@VP~J|pCDQ~`E6MIhxA(Ayz8 zycuo|Ry!@oQ@VHIJFyo;FSR74R^;N0^JXw%sujumD;v+yc(fg4O?K4D!gjW%u*1iO z)R;-fxFEU_+|`yG_#+MPmN$d@4f~M8jZ$&4cTc!h#g25@nv8Xu_J%>f?8wq!E&7`& zFzr@f^4Kd04{oMZ<=B(TG#*EX=5d=35xf8d1y4QU_7~Io6h*MZPHhvQV2X}jt6&*9N-Ox~Y zyxxn9KAnZN97CbrByX}OAP3u}hrkslAF}9cE>4&h3^R!@`MD$?9W;S3&eV@wy{p5> zA^won-k&^rSAgAL_<+7@05PFDKDY3K-LC@3`LTLDSjruCKL{iZsE&;mJHx5FL1gtq zJ!*dTg8|oriBpaqU+lMoDf>dmetSI@)7wCJbSTkB6k@L^OVF(7Pln7d!2P=kyj(DV zl(Es_>?SluCJrRwujxI7?o>zjL8R8QTx@>a44Rn?CeP?RXYM{zSX6ZgDModS?o0d9 z;zP+k&kQsjLF4iDP?D3Mh6Pp3pwFMfNQG{x*hA?Fzcs^2>Y-%Z`J@+=Up9htn@IP- zYb#K1{77=yCkZcY2Po$~iaZ^ih|O18K^@D{M1MhpDI;y6evL7tAWVZJ&h&+s#m17F z-Wp6F>IiOsk0ouEXt3>57l?QsMlR8Qby#H&m~v_yIh>e?%}RJf^YrngSyB>yxbF+6 zc26KFue3OHS^xycOeB~4(|w5*L2z)>B(mdbDlY#W3{&P#CL>0rl+F+tf!GyVL5ndR|s_LIGwbwl!u940&6CVRU>9x;cxCy;X?5*E}KO)NJy4x*lCmxIsel95V169V^#6 zL$#H2$$6?{M+*no8#a$r&DLY_i*_*6e?B>Gp~njAZJ=D!1;lAVA+8>037#phR4`pMIx&!BTQvufgVJ`+(P%rKH?o8jl0) zVddBel0nDE=NXQ$`E~@+tkvLqD_6MWzl=1aYoFXy4{*P*j1+s3h{yi&hDNT-$>94* z7(Lk!zUh~f4K0&#(B%Md>9K++J5%uMxgfx_6=b40-4nJ6f!gg>lC59TF|KVWR7qS( z8g9zO)?uMAso^S8#WNd+Gz*2ATUL=EI#)l?D+F%WTTNzb^03*FAXv3|H90}=ZI$^P z05+A@kk0K3u*O9{_&s|K8Lt%Lwdy`l_wyPOUtN!VAA5kqq_yPyPCY(e=?Z;btR>1l zJx=m+0?(jzr1D)ocIw;@wjEhVenjbU*#15cYaU7J{3yhGA=VI)8A*Jb72-5|3vh3< zp3G`gfUEKq7!kFe9RHAy-M99J)j!vh=s9`lp4$`hCv6}tFX!MuXER86v4PBNMDM>$ zH-!pAqDbDXOpGO_@Z@|H>3Jg^k1R8VN;VtGPpdRk2GTRBnH$N%j1+82_YgX@-b6Y% zBx9B6-tb_{CNi;v7UN$j(5&iaGPH6M&h2jjxidGDTD=l6XPh-?-)$zTu^KFMr4RH7 z+d?)3XmFZOKe+mM3keC-;D=}@nByN!R>f#A|AH&jKORk*wN1nWA3dOwvX!`gPQ)gE zdqbP_t>p5zBrF-{2No^1k!vIw^NR(-m@V7L`^71^OCJPlN^B?38>Zpb&UB7Cb32K- zo{ppIheE=~?PTDNOw1h>3Q=J@$ZV@@EZ#m8&fnfaW?sp`7lT4zvRe%C3C+W(8o}`9 zKnxjhHXqF)5L))yNy^nIz#+f=;AZkpa=2|Fz4zw>t|q%komYiexYZNBt=mODE!Cs5 zmm64Bj3tk+>#_AQCn&o-mh`xz$A_dJY%H~#G^JX<{nZCHPuoq7G}L4EeQT)nbT-Zq}3q~u}cM?E1bKc4Ki%f)gV%%F1f zJ!HnlY#h1E6y|K+Lsp;6#9h{=(7Ad7*;G0MJI*nM_sbGU@vt=917`5~?*ww?Sqi!? z>zjy;=z8skSrQ2< z(BSRLec;)yBr=!AWAa>kSW;h0D*J1&L47Bvv`I^}TWHK~cZG)4lSykDkH_>Lur@rI zT)CczKlgaUiqFZ!>RJ*W@$`e4V^WAyP1?8T27uMW6k;+p1uw)0!Ghpa(x`MAE^842 z5m!=4#T!D-Djm?833trbOI$$(`eA^j^cV zJTH!2=swB%`#v21pnD^)&-ig%?{^BmY#6|C#a3zf@Pz?iNlC}uvjcg0l0_!Ym|?&L zYqK!wZ$qAd@N9H&G2nTl=~{lMKhM9(CKpHcG1#wMIuDz^G?Z(+$MvdbKKh^+5j*5%y3 zaMxyqQg5CPe^lrLb=_AfTQB9~_EpwkF<_07{5cOJ23W$rk?WMsZ*#H6PJrD*)+<*J z=3t|~1m+KpQbtV3#zFoH_>J47+^v*_Gaj46>8yBy88ckHC*81ffQvdT}KQ`b%Uoz(v%w^ z$vB{*Cxji$P}={L4ca(QjmpSVdxN_;9aHZaMK22||KX9c|8X+TZB6$W ze?L)9G)>0GAvO^I^OjOJ~y-*zJUgGjK_At8QYvoW2I?oBF_YfPtRotmA z59_;ti^+Rs4Atduf*Y)8@=-}0n2ZJ0JfXYEXC=;-?nTpe#Bb9t%6#usY*NP;%JloD zY+0O!pQif3AMQVt*~ikcxvxKXJN{ClO)@co>N2ifF`{3Yg^LpX0lOC`6P{&bLN$s> z3DSn{yGH-=h22&q$pXhb97lC2Z(WLXamdFPE4|=dztSYN9z9E7MZYcTU4{%y)8U4E zSEv$FmK>+?vZA&#l;~fM6x1rfr~wWTIG{Y)@=vE(*+u ztVV{H&ceid=5S+kb#f^^0~5ZR!;FnJNW%cSU$IF6O>|A-TR9C6r4t%>wMg~*DVRk2 zx6#_#L`!v9)5;3mQtJ?h7Rl%yXanBbx+I$F(&kPd$V{t8s`b|5@MwG3l~wZv)be>aw=B3&ihjNIn&4@ehp~bi_u)b7(TYY~Trh9BfRs+NWTIi#M2_Y(l#D zrs9)^zR>4fQ*xTdi`gVU7;?55+4*NWF81+<_UD?D5PFZJ!hV0~e6x}otM3d?ezhmfs4krY9N=i_j-(^irQO=T(4u-LvYhG? z|Hu};H0(?YX}s*1Zw*1syO4WSm%gJd;qMk*$-}3)SUCouSjTSUb9xRo=}DkU@9yNU z{@M7-L4mC{J;>OySvcUnImGudC2LYLu+=Yfm}6%~qCC>^@>T`9JNG1~>3E%yLm=L} z7fJjp1)VG{;7vep;`l5XceJpAFMj4^X>&Sf8*BsP0~FG3wH9x_?E?!35c1PZi>b-> zFmeQt`Bax$^n1^*M_UjL)unPx7pOVhk~BgsrewImj}cbHW<)ZUZtDr_##xh*^qkTx zUvKCz)rQ=r@p7txFVvWBOKQze!xv*{yiD#x-kwRv$6o#rKf{h}?Lp@cR2SXCzGQB6 z7EY(S>|1V67Qf0yC#p;C%6?>d`&?AM`@-s#4&;(&9-a;Jfzu`PzXL`iMl@za8fUoTx;7Oqy+4_j4&*=+u zj=Pi7Gjy1A!xo;Nr)z(zi|0aXh`-=T%s=Mg;K7#g;;I*^az7V6*8`lm=S@7cIrzIH zz2EV|hopsO<1KpyzP#}z0Tr`wIo;cz@zRf!qT|c@;tH&J>rYNO(K&pK0z1D15T$q; z?#(BV`#X@7xRZkSEiB-3v0xHR#~1IGR#5C$FzHYGu~uVjpi7BR(qV-bzkTZi8_V}6 zrlwkalx`1QstzDJs>_LCjxeywKr+rli)r*+nPcTaWWs(r|KIBd2Wt!_^~NNlc~4JR z-e3rM>Xd?4LcAfi=}=OI>N2vfFI;Inj6~9YY{oc0DA|lY({qjLLdTcYZAXyKkcpm$ z{oz>mk)#K`KN3Xmk1Q}BMVy~!V_&LEZ12&eB^_V>{zUhtti}*W|2*^`M(@8kk0p8j z`B;+fH$L?bBf-sdXx-HV77rLl%F^*A0bS`cVB?7`)n$JLXE;830$E6P89*FhlR0OOu1nZ3#@+Hl6ezn2oC(75ElCgH)mMlJ&$K&PUHA{bDn41icrd-8qXqvq{IP zyA>#-nN61dNX1u$1oms^khOPHa3<9yDPb;|`6L-*I$FUJ%{;QXK{8&RX#-nQ=aa!p zwRoni9kdTxKnC=n=TfrmVf@Vn3B!`vHK$ylhL>7epIMG z%zw3*SX*Y|ia-3}#H1ypJ&l)nRF@f_mXJv=vawl3IyalKl+@^vi)&x`g8%QOq-*~? z92@Kd_7M>zmF^X{9OVTem6wq)8ZR|yyi{Aej0DhlX_raAD_(s$=|jht%r8!`VAFDP zo%Un%J2-%S!xhAv>S8mYFKpYfg8WH!8UMrZ@D+}1vdL6m?Fq!s^R`4Qm9obhW z8J{k(ffF4gNteZ1>{rzeV$vf?a~dxjGVGyMm-XaVOD#4Tq%uFde5t~3-s%; zfjl~_#rN0UpsH>Iu^vbFne9Cxh(wVX#}q8%?+vx}QRJ;ZJ>y!>7fxDiBrPJ-@W%{4 zC_KE8^nOJB9PAHKPMgRfn@qfV%pWeF-9%n*%EDf>A3Nu{nLMH6%dN6>jdN`?(e=)y zXM}v=-oP#7)}TBb6X*lGpVD=AP(H?v^@6oyqe)9Tz6_`1OFR0$kp!wsSduFQOxQ{$ z)A^Y9D<|;yxRq?7^RcHU4)od0ZN!i2@@Yz6IR9xISukCP4)<+g^_1={Pc$jxUQ-?BPdv9N9|e$;t#rI9w*4 zjG?;x=l)O)g|MO8!WE2ha9Kz^4{7LbnEw!-85dpeY~MxtprjbG!-2h`@+}g z1TuPa8dh512b$&@a`tID-W=`^afuqT#VQl8(Ri8Pk*=M$(X*_3{J}aik&OO38w*PK zLwWNga??5&*Uu^^MY%CXi1|cI$TH3%Pnz8CLJ

Ig+S+2k~CF^Tj}^R{LfTU z;&?tzA7%|}T+_(Mhcq_95@wuDBQ7*vO3ekh)A40{7XpE&(uqf#Y^>i)0n>pQ zWU3|;m(uyzftML%bj=JL*@^11Fq3rFq+xDt0v?sKNJ>E}wyy#(WPBF6J3a;ND_Fw4 zve~2sJxdnmXAR>vWs`?lS`4pE_dVL@kPp^c+}+t8!Vc$M=o)5r1v|n zID`B7T%s$~Vw{eSDTDIJVtOX|dw?g*e4j_Mm!#my!*nlbbv}tYNbiHh`oicII$~O# zuBRUR!RK@xc{w)&Gj{pIU8@2zwMrH}|KJbJuNRQSDcLy5gO2Zm3rVd%b8u9sAJlwN zNal{B`{%v9A!ObnW%6pef8N3qPL7IDUd}AQQYmgQxZNtHbelrVd*=+<1?v=8TZrNH z9HDXfjmqjgx))T!9z2IfD-X66VwsP&FlWOKCB(82Z7$OHreBLy4sI?$>wJJ#y%Llb z^q%rAg+S8qM5Wv{e#cy?5v2VA$3sR{8Ffg)wDAphEFoO3K*`y#I*a4|*P>45o8zvwrkm?b#j5 zm=~#7woMQ$P1~+?+mwPE*9L&&vTaI<;mNo!(hrIc*s55DY0-hU+c=A8#f{#7tVH+0 z*8beA?5diCw=cOt;OR|@&*4P;bO&w;kyH-za6m^F(a_S6?XBc7x(K zAPKd!Z*TuTQZYUoV0`}J^*k;5cC>?))nk<7K<`sq*h5?GPNgKBll1j*gp5kNm9ha^ z3?1tN_7mb2O@bC@`n%Ej(jLWTR5F(A?Fl&@5|vkU-~P*DZ;0{NDobn8x#B(_h&`OF ze7&8DsV9A5O7B$VXP0z*_R|j9MrYs~+OL+~lBqnXn}yYn_`{yWY~^8mHXbJa z(Cuxml36+z!(017#U484a>qQJm*E2@ZiPx&JG$nL^@6u+P+9vdAEW7huUFlD%C8t5 zM$vQKrJWBbsU-_=b8%;g(i~EL(y{Nzw|;Qx=Mlw$o~gL^w;fdQJf>*v>0U%>TWGQQ zgmOHBo~uc=f=hIb9K4dwN!D9{KJK(UzwzziS>;%%96YH};JnENoNc%)79H_-| z87{Dnu8RZS(Q`Gi?vU8$rJ`gcW6d9QyzBB>(WIncgW5h|cxvyXcA&!GF06C5YhPqgW{- z_@B_BG!gt)^esaK|8-~3wXn+n+puy(@IPc;c_Plwl-yZ?2>xI1t4IX@r_NL&g8znB zD-*&0y>C^B;NQJbH6r-G*{(Vf{M$IyAcFr%RcaE!zjNDKMDV}CuQn0`?vqpkO=;})ox5g`>)!n2@&nTf2XEIw0{%NW<<3A z$VttKX#Y(Xv>>AWFW%Ks@}E1@MDo98UMtD}m6Xx0C$uFljIOpVpv* zFB(*<12&-q~F8f5~5w{NJ5LB>x2yK=R*lp@roCRIH`sKmVYWo$^q?N3|Df8C~blK;4leI@@DTzADaFzUzzv?FWukyuR^8c-_r{w=y8!yR!o37rH|5x5VlK-HozLNjPi~J=2u5td7 z|9K+(;k110}4=|PhJ{WpRo|3Rhb^MY#sGrUcI$-hzJLzpHkb|GUj+ zNdCumnJM|d=srvGU#iw@$^Y$6b0q&JA#)}Fb`kR=|93OyOa4EPS|Itq|8Rlizfssi z$^Y1&3nl-9S1*$Md(;k>{LhFEm;48JSS-JD@}KU#LGmB}V1wj;!W~=1C-{Y;4{{`c=N&e6M+9vt`W6gHS ze{P)}lK)#O{zfX#n{68_@Bl*8_aF68wSKkE5|GldTlK;&kHIo1S zZ#0ts$oYwq|D=0~lK)NPk|h6yrL~fOr)^rvf8DOhlK&kClO_KvAVub9LfKq@wt+J(_(of*fJfr)BTg}QF+ASG(CTwOZUFo z=ab()S=gnJuJJP|K9`MI&Hd>+v~(nZ?iGLd?F*OA=!h3x%h&Mp0gFKeBzaaoZfooX zmp>Me*S&PO;D$R)9a~5i?$_a3Z&&brR!FK;EWn$QPW=AnG1mg@JEI@RzK#VLJfttj z+t_`vVYVEbP19lVB+HMKqi(vWyWzxVmj77VZd+cUhy(7L!PLZ6pS-BT>Pj z!q4_Pl4g~Qv1`m=_ii0|o|KKF<4qyHb^)pQE)#oLn8MG90y5e(0}IEPLek#_Bz8?2 z`m`|v=P`w3=jRlhG_faacvMKA+6g9AC_COvaFKGYF@^~fdf=-H?1)#!PCZ7$h4S&s<^ZRxuv>HD}(6r#l} zE2y|RkDkFOp!@*5D4kF0>*)QIm*y~RPCoHFk&m?l=yN?6@=16`BAP{5f^++1a`mGI zx5wK+tF6f-aW*}}S*A8g?8ccoY2Jfe) zl1}3i(Xyi#Z*QnoO-tT)(c-q13hY{;q(~*jc#hCrtRkMmYSA) zL(jdanqD0hCpFdIj+2_2`ov33EBqNRH9c;qIH7QbpD(KscE@O(Nfd< zeYQ$XbN6kPnr`jBO=?;rX`9qEz3FzT>Ew;{-PWq6o~3q3O;^m?AvL}FdWY0>(U2Ia zX_;#=Qd7O>PO0gf13RUrvwG~3nucWVlA8Y6E>>zls+NJhxsp<52bSzdi-Su&! z)U^J1Ixef4F1oczYN~bHEH!O(Vzborl=T*=>G^^!Qq#~b(Nfdvi=(BckK0B{O%H5| zl$u7>TrV}95wTus`i`DS6LETM$_A7QHC=Xbtkf?%YEylrlxJ_{8rU8G-k2X z^h&)YQd6s?OQfbFzATZNUZ1p7YP$USQmN^hArVs32G=8`rkgr1lbZJ1Ghb>t*LH!_ z)N}6wsi|4Fg;LWr%|fZ^;wFovrnXUwq^2!OhD%Mi&kUEEemxs5H7(^nPHL*_JYH%# zz+{5dv~8t{Qq%fhCrVAdA5W5+-aJ29YPvaniqy2+_Nh|S-HWG5O}~Uqmzoy$pCL6J z<1|xh`l`(=sp-?ov!$k~<>yFESA3fzHEr{3uGG}){5+}Y{W!X2R5dkSH(YAkddUc> z>DK`xrKXN{qok&t%tuR2SGOG_HQm%;tkg8UbePmMAtOv`dhkn#)O6~#P^oF7GySEe zk8%e{O|R@8C^cQQZjjXU*X+Sk)BS-%q^8;SL#3u;KMa+c&fD!QHSNC0MQVC|x~tT5 z_W(Dk=>`{fsp)BR52>kdD^ICu^^#sv(?xH*q^6Cpc}qlbVj0 z?JqSQGAKZ5+9otmYFf%INNO4j!BW#xCLvPOkiY3ZjH+qcgFaHzUDxQIjN123&h9HU zJ-pdoYN}b)Pik6rj)T;++Biq4X}drtscExP&Qeq2qDW2ObRbgGP0c}SI-tCT)YRj% zh1B%N152stjI&l!Q}a}7scEOJHd52a_O?>fFQ3{Fpdd zscCFRPpRp=*j`f8hUoxOHHph(Y;Mo)3&{uOHCVeY#}v$Ri>rX)Z#@;scG}O zCQ{RdXIn{4R~&3DHH}MYBQ@RX-&SgxyR)v;bkzKMQqyWv>q||qhcu9yo^)&|HJ#S0 zk<|1|#x%rkYnxq^1M6HkF!Aax5b?ZQZV{)bwDeblRrMQq$`5t4K{pjI1g(9q(C9YI?)2y3{ndMGdK`f4Q1c(}tyL zNlm|etR*$w_@K7b^uV8Wq^7Yz?-!_=+SUH4h zInv$Q9~7~cx&HE_BGxiNiJuj*ma$#*MGWFH`{FM}tYvoR-&Mp~rhWQ-MXY5Wt$V15wM>(7j}@_&nQHk| z5o?)^59mEORny*>FEwqPP#`ru6s%XoT4t~beU?^T%XFx+UlD7W7cUPeVlDIY+#yA* zWjbq)C~__H^QcmZ-k;T~Zcni5K%IlVZ7KBL_!Lvf!@&r8sI zYB4`Em4Ur=SgxEo41JWXJXx|EhtPE{Tc;oE6OY%%b?12Us03WlvNOlMA1C5LO?!^_ zB_v~Rowgir-N%U|>?f6=r2MbGjVJSlqmGd5#4;J7D zbKuYQe@rMu_rEPUPVm&@;Ey&OZ{JJb1JJlH$Hwon`>%YjK|GKA-}OF!<7e~#yT46P z^z47pv;X4R^P*?}4ewqkdiLM&?u(*l{|)aRDSGzb@a~bKXa5cFekpqP-|+68qG$gN z@7^hT_TTXCqoQa34ey>RdiLM&?y3KjXa9}gXZ}ymY!|)ryy%_hMejT>dgpo3JI{;W zd0zC+^P+d27rpbm=$+?9?>sMh=XudP&x_u9{;%G7Zu~v&qHnwZpZ~VI@qOO^TkoGY zeh&Jd-lsOcKVI~{`u|zqvIqL@c4(=lE)*2KQ8I&GFN{T6C$~lH*}b({Ogb<{YzkLAWG0<9J8CT$$d0e$z_i z?~tIEc3LgoC+!#fJRr+W`h7_H<2&mJ9jpLa4A2x6T$E;pEei$&T zuSjP+i2RHnVTbW1>@z+^xr}GwPwL(n>F1HlJEZ@q5j$kPSh}b$%P)8^)=L?-3nzUr zh2LA%k}zKfv^ zT-=StOLgUKpy!-8eBHDgZv!1K$K%rh?RlQErhD+WO$VOm*TFs5KdK|ob0ArR!-u!# zd6s|D;O}8=c%IKg5;5XoTb^h4SuLi|Xvy<5D3Oe1*O>4;@viiHRh?S%Jj2?i;i}Z; zJWpxcG&DWeg6A19lHza^o`=QM+Zu*E4A)W&c^E$Np(W3=qiU|S^Yc@Vv=euhV%5&T zkvi$mQ!}0Pr~mVO>5uIyy{y+vTfMATrAvjfURMV1ll*)uxli&_YT91OPuVL6B+oyF z9*{hr((ji%AHQ%&#^VpKLoy!oHyo7l80UBddlJI=`LgdYw%J8EKjYsVLZuh*x|?-5 ziulro=ef7z2>xhl%kvC6au_ql+VVW%a}0eTi~V;`kMMqj#eUsN2Fzlg+3BQrmv&x7 zxJx_c#GTt={$!8!ll~km>nHt5pWw^$uzF3;3E_EIy&g3S;dxlSD%b_{JdB^1L4yr> zC_hi)2Jt+MpKlQZc^<}dafcB+599gyu;Dxp<9TJxVLT7hE8J!b&%^Y3W;2@SVR{WZ zJd)>Ox|??y$MZ1V@7E9Gd6@3!W{u%_So;b6HlF8U?I-8zIG%^KpInnLo`T6jpun7ZkA)n!`id3!`id3!`id3!{S2t!{S2t!{S2t!{STSi^Z3y7mF`ZFBYeQ z9~P&A9~P&A9~SR|=Q1?j1Sj<%zX8N+Z3d3Tq!myaDFf8UO42!u6 z!(y(&u$ZebEaoZSj<%z7IPJb#axA9F;`(&%vBf`a}|cgT!p8ra}|-!<|-mTo2xKvte3!S zK4y%I=A8feb58Guv6z3<432u=B2`Mp;dY;{9Q%gs!795uaD2a3B5t|RhT~Orlkrx` zRvbTdNy9AXmK?M8IWxZn#|>WO$n^4ly|Ia%ue_F^j+>W53}#;J&0pg?#TbSqhl5FanfFUtf9B+7=fL|5@$6-%3 zcs$OW<381s(4j^zjvqv7u~BMo*!}P|X5Zv*Q;f2KAME~<#o?En2#3=4LFHj`?iWb&$E=yVKgQB@oRsr(_yF2 z{kY9CFLgNPnFB9N*PMQ1-N}*rFe1JXt2J}xzAbEu`0$+z_c=FmFDC7Ceu!^d`EnfPuE%Dj0yy5+x)5VG265apL5HWm1#mmJnozF1{keV5^||Q?`+a*neK^;v+#ErKYs0_3R(DiuOGK*ADM~2C;RiVHV@3i!FT+*4B>k@C`S$%eeo<134M_;c9rTGf{#hW$ z8-E9h=9<}wxb>4O&wqY-94?CL&3(AukeUQOvcTKAMP1CMRj^3G59&boOV2jvnAOYA%z$Gn(fw65ecoW5%%2#pmv)Z% z@00d#96un-eL&x7EZWs9^CS4po_^PumTTAKDCWMm;n-u0VQ)mFo94Rnbe8|kKtGO| zoj!3P95ee1od2e=Kt(#<2h#aT0dz5$E?00o$(;@ z2U3279mbom&-fJOGMfBpRG0Ld0vO*VR&=;%_izkq7_-*iQ8vXu}>sd2s=5dWg>+9$b57m4hSll_T=Aa)cdLj@RQjS{y$nL)3aP`y8v~a;*BpvFazstQ^J{yLNny@OZ`}!)kp+e#QgGDnA^vau|PgaibU+7igYD=yitD}l}eHm7HP#9ME;aJp{rK@}rhDCiD7WHLV)R$pV zUxrzk%nvo4>B}+mm-)@oMSU3-^<|jVoBf|*QD25deHj+@Wtf#C>Zqm{8s+C$wWDY0 zs(p^tayeH0;aK&PV^uGX)q06^-aeU4l?R@#^24#p8^aA zJ;&6ZLhW+Q+9xefq!)^GR*uNe$`N*0Il?~sE6QcR3xC*k!cS&T_|M8=JTm{)bRKJJ zexlZk+2L5V&#_uA$ErUZtA29K%As~SX5}y*nN796B0uASV^$91k>yc&+Rix^@x}6s_)`7k*E1~Qi(wI8M(K)Ce!{S7hhq_6 zEL|;^r>p*OEaHphVLUOu7*^}Wv07h|pT`%=qw>SkRo*xj@x}6p_+nVZ7sIM9+<&1L z)6p0U?O3|dj$xr4!$LcTg?0=J?HCr?F)XxWxTtUZulJ2YFQzG-O9E>*3~Or@2cOz` zJnnLQKa&ogJ@hR7d+7&s>0d(s&oTX-(0m-z>j=G`V`@*Kc9Gd( z<Ci~xgx%JIl><`UU(j(_+s@E@x|&T;)}<<+HQp%Vq~9VqxfPzGkLq+?M(`CsoRjdd)FJHz#RuT}c1W^B9e5#AsY2M&lYUM;+H#x)|43em0H@J8T@~Se=J+%*tW^ zSN&n*D97wN;V1QKU7Zhbtn$gR$}`96yncy~XpQo$k zaxC;>d4ygJ3%wXt>&5d6z0~|%FNRfqgnc$nbFA{oG1HUfWBG+%3=6#scK)J$G~Ztp z>Ab!|FP2BOLl{==b1d{S*fHqEu+WQPp%=qKFEyR(rRL{6GA#6BSm?#D$|o;Z=*7~7 zUJU>5^fI)8qF7@*2<;da+Nm+}9}{cFdNECl;*Re_O6?dYLOTOL|5#^ACjeueMpvH+^^x~u>Ed! zt=JD&%VqnXJe~b6{9)y=>scP7{cvhWEBi?`o%fS!evVZ;#K=C!YPlSs!)m!aUFgNq#lA7aLNA8Zdhz^1FEu~ci(!=?o=4?Pl*{#Ec~qWxy3mWI z3%v|>4ENWJ(%F6ps~6LkW7Q5}>8#zc`Y^1P%dyalr3<|n7J4x(^itEs{U*VKu*3CW zc~ss+x%~euUFgNI(2L>!onA~+rkxnOjj_UPkRl&u~%P@%y}@ zpW!j3_CNo>#vR+ops{AcIM>!%NcW+7^1d<0cN*QF%I5fc=^-o+*JZ#t2fF@j%Q5{+ z_h%e9roYqukRcq?>lAuD$J8F(M_tGD7C&K zKjT5o!};M@<&9%nF5{D9>JQ_YV|E?m(MT7DX}!aFKgBRBU#&0Qzmj?}{+Jy-%cI)o zSS^=hRt~E_%frfHyfCc#ujUCiVLYnotiB?@(2M#b_2T+49@TP%UR+P%4=YF2i}^3~ zV)c@Gu{zTHMQzg1<_YDKwGpl*!z$-I{Xd{hQh%ggOh@DPDdLW`Pu|X0+c1hd9^Y#F z7ww1Di`wDsiesZX^7f*}9d9qJJeJ=m?nHYQc33;-SZ)6t8^s;-hjGf&)i~m@rp6b? zM)OI%n1`@()%i>z!(tx7u+g}t7xNI7ZZxjx)&5-1(#1T4Vb*W4`GK1L-*z6x;E$Y7 zvU+hpSh~@ClFxUT-z;67=Wwjfe>gUpPqKQkc`r{lnoo*)iF7fa6g&t!e7?xaQhDR) zDxVyyJaeq_&oxqY;rM@Phvfgkep2+GyuSaFWPg=Lc*A76^0r4h$B9Ee zD7`yr4Czn0krp+!a$G5IDB0n#jAQnf{hwXSe!oHUG0d)G*E7uQF}vJ8Er+%Z6QlG( zqx>AJcJwS=wa>9yF2}4Kn(zN(?>(S4D~hdQqM&#Y<$?ktD8WPy0`KV&5tN{as2Bjb zc!7~1f?xs(B1n*&gCt=XKtQ5|r)rQK6c_{vLl|a|0Ud@60|O}E-uqNR;r-wB^R4y& z_q*S_aIINv`|YQ?cc1P$eNOGuB^>?i%lrNda~*?MmJiU6tUo~i`trw?x3mNMhW1p> z|MLH{5BxjY6Xx&Gp8839;3dpAjbB?|XRxzjNAdLkq2cvG5Y}%^3RX{O1U-^xjW(SD$;5@agZ_w!7k|2MY7Q z{Qvwd|IT{E{2hN!OnbCT%y!sbDIb*j!ePf)9`=Q!UE%1DaP(6+`Y#;3vV4GkWc>m9 zCk#7=_Jm>I(4H{=%m2?l@b9b_{WP?ve$pP=69zB&M%Ib)p;BKs>~t&-`@+$#aP&u* z?d15g9gZV^8@yh}*I%_yUw^w*hkoq85PtNe-w*wCk6nbXziPJbn@?>e{PNkK=+58b z3&Q*_|37W=@2p46-|_dvw6_H860;r7&r&`p^@YQZu{`VxN4vt&AK~byFxx?U!sLkd zvV4%`s6RmeR1Q0a_Jm>I(4H{=%m2?l@b9b_{WSibnD)?~Fx%mJDCI+?zHr#-SRVF; zqg~zT^ z9Q_v#URgdsKeGM+{S$^ALwmxoZ)i`L|KPl`Xih^ll7zjDi2=5;d8RSd?xFMk5YN~F5&c< ztdl;In7)?2j5vK}Z|732yHYN`QC~QHChMfnBu<~%+mR3Nh|^~hNB>n`uNN`*D*A8i zRfuB`(3i(vh2^}*at}cqdkJCQW4VW5dG1w+bFV_ocIaD5`G7d;3x^$JdDs_@c7=1V z!aC8en~j|m2mhm;qY&| zHt8qX4%avB5@$PXGs<>q?=XTH7Gw$l3g zzh$k}>&11){U7I5?9=)+`1Z58)?My1IX=11B+h*%@&CzZ^S7T7Uf-*04Zi)1@SOHn zZ$BeE_y6fL0)1xg*JEF;{pZ`y1mK6kS`pSy{39hY*w-^=IjV#kQ{xtlnjyNUC;n>hNZ`q6*k z;FaYg=KbX12R-VS-9Ddu;MBSPD*V~SPPOIFxL0_mOBVJopM9h7;RlWO@0@sn@P*4C z<^0FrvW$NtW?lYju(R+!?OA3s6+htDtfi0}UH zYj_V`ynE(hU+~xG3BSC@WFPg=iK?^pBM!l~UZ@$0kob`zZ{bMtJDZK0w z5BQfp`CsurZ@E|H>;3&W`~Jk+gpWC9e!qI`mBPy|v8jJ>%vr)0?{%>AAMLP=er@T>(c#q z&XWzNJnZ*kPR=>!sdm;*4{J_-;<8ih%a={||G=D_W5rYK*2^bpPX2PwlkJ2(9@3ng z`kRw%#(O7fPL4bEL>sgF1DcbE?)_`~#jW>gPG0|&6YSeRzgPB8KYn3<;eGeY{%h+l z>?>@3kL*vp5%H|;@0R`f-~U1X)f#un{)D!WpETu8**|La1^u=y?vQ<3asmIzjknAG zkuSgBH{0(<+24Gt(f+HC+$j6cJ-wCxY4;ms|FRXf@|RD#UiLq~+?Iac0oTcX_soC# z9P3^y`!DbD9skLct7U)dNB+ZqxXo3v|LdhU^G)`+K=$|iz)}9mB`%Qtvu{1pcRccZ z+5gU0kMtkk`a9YG?0HA{JQL27{beQ{?%yAGuIw-S>|s6?XE1Wju08cozhMQOuZT6f z>g|U(?Q;Ct4(-w>upQdv__H0_rB7fxv`e4Bc4(JAf$h*P?Xw-)rG2);aiM*V6UT-2 zIZhlG+UGcNTxg%;#Brg0juXd)_Bl=*7ux4Iaa?Ghq`5)&b+R)&+E+VO8dOdysos*>&$sc`<$nom$c7$%6UoqoTr?Zw9k3Uc}e@6 zr<|9x&w0vuN&B3qoR_rEc}m|w`&@Ixv`^nmO#AfBxL=H+efnmW(>{GOG40bg6VpC@ zGcoPcH>3Yu>3>)H-h7mHv0xe~f=Cc zAM;1{WB$l~%pcj0`6K%=e`G)AkL<_%k^PuIvd{U0`7ir1|7AbszwF2Sm;IRkvLEwb z_GA9be$0Q_=lq9V*^l)r`>}pyKi048$NH81SiiC#>sR(;{mMSq8OBBS!~e*B_#fF1 z|0Db1e`G)WkL-v4k^S&Lvd?vfbtU`ZKV?7sr|gISl>P9ZvLF6a_QQY5e)vz>=Q_i> zlKt@ivLF6m_QU_ne)xac5C1Rw;s0en{J-pTonc+ce(ZT(_KC5sWIy&ivQLb4 zCHur!SF%rxbtU`U$Cdtf@C(`h4t^o~-@z|r|2z1F?0*Npkp1uA7qb5y{6hAhel5qp z!LQ}`H~2N#$M`q+wH*Hjzn0_Q;Ma2e8~j?1e}iAk@o#1RG^{Jx$NXtnSF(@!)3B~& zAM>YSUCBP?Ps6&BeaxSRbtU_lKMm_j_A!52ng0#zO7=1T8`hQVWBxa+E7`~VZ&+8d zkNMxQu4EtczhPa;KIVVJx{`g&|5ny-qh0zRwnMx0KWv9~>3`S`?b83S9onV;VLP-- z|HF1@m;Q(C6#vsWF0{{a;<(U0$BE-Y`y3~Z3+;29I4-o$apJhpKF5jULi-%2;y)YK zmF)96^SXxrY*<&a&+CkJCHuV2SXZ*o>x^|J`@GIrSF+FRT>O8-x=R1wu&&boH>|7l z{|)OZ{eQ!{O8?)muG0TEtgH0@+Ly-t3wYKgI6k<43A6uPXIv*7AFeZEjt}l%!W%R7{g?gE`!D;S_h0ru@4xJS-hbKuy#KQQdH?13d)&V`{vP)) zj=z`j_qcy?{5|ep9Dk4d7sub@{>Ab4xPNi}$UfIu+5d3<$bQTp*^l`n`!RoHKjx3@ z$NZ6f&Y!Y>}pyKi048$NH6ht~1`(`}s4P{zvx1|Hyv$AK4H8Bm3chWIz0m?1%r6eXg^z z|EK?yeXg^z|EK?yeXg^z|EK?yeXg^z|EK?yeXg_e{6haP`&?(``Gx*p_PNf=^9%jI z>~o!!=NI~a+2=YtWQ|$$yvF;^^v};E{PE{587y(@^Lhr{dc_rNg%c+WAF{?TY?H%o z6khd*XBz+US&wD>8!_whH^j6-Tg0@@eIqg3L^>JxG zpv8S$r&xJUR4a~(Id;6=9zPq+EHmku8%eAJYUyS2|hQ+Ulw4(j-i z?~7Q*zY()8e?v?gv_(wY=-(J(wu$mVmZQF9eb^DE9oQG9ef$$UbG|3Hp{rNU6r#lc$|@+F;VY zlQkzFoadCmGFv~WIr+-RP8_`BLr==i?Hes^>wo1w&CiEkIexI#ZyuA)$tQlyezxho z_ASiSr;a~v@Q3{-%l@)UEpFd??S9!`c8Nvp<>l{@{nf^P(2ig8PT3!G^8&W&&iBjy z(xZ2`$2PoO_Fo(Gemm=@cgg-;d;Hku-T5}z-(j8k?cfRHWq*O0ceKx5^+(yCwD7jJ z;#Y5w{rzU%$}YS38reVWj?Hbyg|CtQKTJN&7W&5@WPi^KzHLY1RRGuN(LU!RuPg2II&&`4KIbN{EA8_-b6(Ou=PBnU z?Q@=TUeZ42Dd#2abDq-Y(>~W0=OyiPp0b?w>5n-tX`l0y<+M-VOicUq&BU}%-%MXj z`}ED||4{ayb!eY{8vP&2{9f)Qq0;}M(*L2-|Do(Z#=pz)NB@Vi{}}%+#~=M4 z%Kl^gyE6V=8UL<~f0yHr`6K(BKN$Zm#~<@Y_Bnqr{#}kg=8x>h{E_{bKe8Y5NA@{? zF#lzr^B?m^_Bnqr|7D-^AM;1{Ie#$!Wk2S>?8p3<{h0r<&-o9#vd?vf`7isN|FA3j zTxXd7vd{SsyRskaSN3E5_V)YrEBjn$7#G>+I)h!==Q_i<$UfH@?8-jZ8OBBS!~e*B z_#fF1|0DZcXINLV&vk}zk$tW+tSi~)I>WfgKGzx6mF$QAl>P9ZvLF6a_PNfmu4JF< z4C_kvxz4bzWS{E{>q_>y&akdzKm5P!hyR!T@c**Ub%u2%``lw-UCBPz8P=8TvmEP6 z_PNfmu4JF(SXZ)7jCCdZ#8_9dPh9%XbtU^OFa00Fy6XFn^3s3$h3r55LiV42A^T6i zmgC=*{?o7J_|q?B|LNCq{5$xy9RCh}EyuruU(50D%KYid_;+Rg(68nAcV+%`SXZ)- z`O{%t$v);!hjk_Um_J>a|6Q3sU77#%%d*dPR_1?)btU_l{~gwq?BhPuVO_~S=6_e# zZ&&7jSJp4@E3(gZR@QGvyYxS7hj!_I*beQ||FE6nf4Z`MyW)SkvVObbe>#o}?Q@(s zF0{{a;<(U0$Eo_)qxd*Zogd{AY)CCHuV2SXZ*o>x^|J`@GJ@|98cIcE$g9 z#ea6i|94nd>Hj;dtMvaJ)>Zodj`xnZe|5$Gt32*s+*hUlS9#pOv?u5IaGh~~&hgWRUY>*_CN2x?0?>W+5f!%vj2Ji<@j6Nzu5o0|8o2-?qAv$ z#{G-qZ*l+P_*>k+IQ|y*FOI*({fqNQ_PNf={(Oa>R@9X{i`LXtew9j?M`+7fr zcBKE2{qR4sAO1)7xz5V|pZ-Voxz5V|U;9GZ=Q=C=^M~uKJhKdy=M?G&_%33=dridj2aLBzOn<<5 zd&KkyjJHQjf53Qq#PkP@w?|BWz<7Ja^aqT$M@)afcsti4+X}4$-z}&-V*08dF@4#I zn7-^sOkeFrOke$pn7;ZMF@5!)Z3M3|rJPy?m9vk-7o^kM`+|`#|dgEUin! zdrMqX=x*>n8d?`!--!DN^L;el>#9z~eS{KLF*zMdLg5hC-g!_El=o$ zj9Q-13mLUMp%*f0c|tE_)bfO0NLs4U3mLUM>i6yQ!H#rLhW8075517;hh9i_LN6ry zp%+rSp%+qrLNBC#hF(bhXB)K7aVzE2L8+X5EOuJ4pE@PBoBAd8Cv{C4o6tM4|9UUS zws_qN-_%X1ei@(CS;;=z;BP|*CCs{I{HcRdIc@)+ni~-xv=ZMOl=$YL#5V^ezBwrI z%|VH84oZA;z&J+42d%_s2PHl`DDl|=-fvUiqIq88vx5?!9hCU&fN_k74;^PCxF(N)VDDm+@iH{FTe0)&i z1@j+u8BjSSt#xWv3I6ynpx2XRmzCS4O{XvQE4@!K0!1#W|2aR!zhz|~m zK4E}yqP|7;F;3LCX#9&lVNmo5gQ8CuP@fR-LFt$xJ~#+{OGA8W5c(F`4}FX5Gma7Q z!9nO-8sbxf(6=C#Wj()i4TQGlK*SBE)ysmG-{CQp9g8B2hz6JB=b$tuwkMu3n=VbpG zAI$zUKA8Pyd@%dZ_+a**@xkmr}pypX)c`gXw={ zKm3pEhyRiN@ISI2{zvx1|Hyv$AK9n>iTGgpPuUOuDf{6+Wk39x%P}xb#2co4kKze3SRDjBoP(mGMp9zcRkb`&Y&{dH>4z zChuR=x2XU0a}l5A{VU_MynkhUmiMoW&km@Ai1;k;Um2g}{VU_MynkhUne!*(%kV$a zx8(exz9r`m^({GnsBg*nLw!rmAL?6j{$zZd^FQO`ynj*OBKsvi&ifbjEwW$Y3jdk<3i?m#Th#y1x5z&C zDO^|KKT}^p|C#y<`p?vd(Eq1Cg#JJEA@u*L52620eF*)3>O<)NQy)VApZXB`e?7}^ zeerpM&o%6S=v&U<`s(#9v!2264}HrRj!)=Y#<2gPZyCe&75bJjTwkGY$@_2WbF%+= z|4n^P_CN2xsn5y&=lwVJIqHAeKcv2h_pj6!<@mR_f2F>N_pj6!@&1+iq8$Gg_pj7P z@&1+isGL8I;}i2o_GA9EGJhJ!C+1J%_{98?ea@eqmwx`p|Hyv$AK4Fm zi|mKKMfSN*EA()bda- zL>-aJLsz5vp{tRd(ACI(=xWq%=xWrT(AB7)p{r5<*#_-%Pg2UM7t(t(_OaMW-45-i zo`>zG&WHV>UP!;?*p&Xi{{D*Bt?;E@NMptNWqeYPB>QY5#*_UKW?lY<<+M?*3-v;J zm&HBUf9KrzmvyIiO4PZO`P`Lx-j(^^m34vjD{YT-E@d5cp{0?|h1ZPlYS?CIX;fa; zDeX`vBRgeXvt5<5toQ+Hgj7x&#cxng(BZxJfborp6%H8Fi1^^3#5V^ezBwrI%>m;W z5g!~djuG*}0pl1E9~>}_5%EFk2qHc>DDhdmkCncqL;PY;;O%&M zV?=zAaro4SNP89WLFt$xJ}4bl#0LkVZ()2;I;@BfN{7WYMf;&|p+025m9APN@u9wj_rZStysmG-{F$QP^7@9ph58)zpTDL3(6=x?sQ$B@_Cw#o_+a** z@xkmrdqNp!_G-RX=~EZ(;l~{ip1Q z|CIgkpR!N?8Sz2+d9JJUpAjFF&yV<^{Aa`m)BnqU_x%QAMZ_)U$y!1cgo4kKz ze3SRDjBoP(CEXtTPd``sPkoE}Pd``sFWp{@f5vBd|H}9*?_U|8<^3z;%bY*dx8(R| ze3|n{x;L6W-e=1C&G8N?f3c?*$;h-<`3`lW&Nf; zf&PbacU@oJCyW0{eFFVY>JxbX>bR~re|VoS{xkIn^gpSu&_1R3pVU{-f2O{I{xkIz z^q;A(p#MyL2>pNRE2JX}eTeo}#eb$gMEfkRtMLD+52620eF*)3$9E}l|4Mxb{lCiN z{+0R=?X!5V;r!%t5;5%;eGBhj`Yp#N^euV+RsFbsr9Mafr=8ya+@JcK>_7E6ynm%W zC;Lx*j{0Br52?>l|GBQ%f9?~@{WtYRIsP5(7kyEVe@FWq|FZu{eUZk$?0=|l>DYhj z$jbgF^-(#0I{KfOKeEsH!*#{+=RUFQe^TG2`Cs-wsqf19ul~pUmwoON%l?h)SN7RX z*}tVeP3yPp-%_8J>sR(;{r2|X(5G?#N&h4J9H+AXOnsgF57!mPhwYU8bL#8T|Hyvm zTQol0Czkzx>g(ix%Ko4JNA@{RW&fZ0!1SN8AO2JJL*JtQQ%4s1K<@vkZ_)grjx6+n z@}K4Th5ldT6aHWJ!~e@Z{Xf?d=RCDzLrSf;%$8kp3VO!>Ramjf%4wq?e{sj zUjGx{=kUGXv7a7q+_Uk0ATi&C@VyE#-;waW3NhcE@VyE#->L8)G0XTjV%Ftvh-rhi zi1U3WG27&Ol`Q8wk*v@6D#WzIcPPZP&-W_CY?JR*h}kCJs}QqIzE>e;n|yae9K5nz z-;_oDuGr~{{jRjzmHu?4pIzyH$LCYpjQ2&!m-UV1>|+@p+E+Q-BsbP!o8;Wv>Axu> zW}D@@=$kT@lNZO4@1O$f{ZjH}Imdx*6SFVmOU%BoZDRI?Z4#_}E+8|%zxQ@cXE6e|{fA2?q*Lv^% z1+LxR)U63qYeqd7%Ttd>OsyRCW5lV)Bc_&(8ZzS4;}KK)MhzJ;HF4ZG5>qS3HnN;; zWPP?lOgn6YnD+UPm}UGMG3&AoV%lIE#I(&eh}mW-?@E2?@xqSuc*NAjm3F1aV|nWF zh&eW;|9bD;+v)Xq#2ia%{<3}zY7>$44F+F={Sw9kLUEaTsZS(j}P(+1lh zrfs%COkU&&zIu+VIL3kXbq!dD<3qm095?bMCRhF=W*PrR%)0yyF~^Lyh-sT^o|tX2 zPg%~sW_@xXrX6x4rhW1yW}Dy>cGreIc(`&Rbny+Gl;XK^)ghIIfp)Trc6cUczy`gn7L}&p*WZ z8G8Pq_)dXw(jk6B5PE(*^SynhBF7}YQ(zo+D85rb?jxNQncpv{oMV^uhIr(>~iKX1n}H%rgFsm}A4=5Yq;25tDD; zuQ|r#o8{!2^~sl*cF31F`4T5z;^a%rHp!Pb`4Y!<%yK@*3A0U(Ti9V6!fdm&%QjTb zx}~3NBm0jw{`<~&`NP~N8m_4=x#CJ)!8k`-*nhoFl(Rnj_OEr=R+g(y*aW^L%T*`W1^3liIV$V$%{>%PH z+xyw{zx9->^O2*SGZ!-@tymY~P2U9=M)uJo^mUe0A$}Y?~Q9-gTw5?Z(f{r2fyo z$XfQ`?e7r2d1&dxMjRY%=nalmI9lOov%SI53P&p(t#Gu$(F#W^9IbG)!qEyxD;%wG zw8GKI@raH3>-Ea&AM(IPeChQ5+Wp`Q^ZL=-Kc}%;^V@Uzdb2(&e8&*mHauE&dSKZ`GUO^^S4)oV86kA3}r zp8cdPwrX$ZvWx$2qaN(>q3?avj-A-IHRbOQ+t=pq`*Y`%N%qLp9zVFoBzs_TKR1?H zY?3Xz%`0m6!O4^D>s!sH>-fEe9!zY+!O;pwD;%wGw8GH}M=KnyaJ0hF3P&p(p_6)@ zqZN);I9lOog`*XYMvm>$e$MZF&$m6W5ifLgKeoSq*M`2`4S(y$WSzDBwI4htJk!;m z^J|XppD{mq#9IFHBUAeF)z|dD;Tu)1-zzp)!~L2^gx6YSbzk_@9)E0TlwbTnj}N?T z$oKhPZ|B-QSMXD2>g~U__;P;u)jgi^^JRSb`}#iIwcOJF`}a?k&6jpt%FlVR$J73E zDL?ax$5npf;Y<0g-|FYvV((klkG|nGm2WZka*2&NI9lOo55B?C3P&p(ZKgLkTH$Dg zqZN);I9lOog`*XYRybPWXoaH{jz*5_KG=`pm=_O9Y{Um&J4xIhyYiR5%g*-+KR3tE z{R=}Ag#Wbi9)9JI`)A1|@7&E#zxN)Me`BMc`7CSq_-mtf@o&tyTjj65`zJnSdXGOf z*N=SdP5L_bow$?Vuw8HS;R)ONZj1MA{qwA?z58d6&sg=le(A>_ke#0|KidDf!-K+S z+_sh9vB5;)XQyrDPk-hi;c4F-?XUc#pG*7ixUJuRMSo4#x#|0fjW{@3;b?`U6^>Ro zTH$DgqZN);I9lOog`*XYRybPWXoaH{j#fAtIevcgJH>s6Kc1D?h;g#F%7691sea7w zZW2CX^a*~<(fzxi#lCjD-}3hxRDQ{U$N58B_IUTfvHtQ4*Q@-SCm-YQx~0cw>~XY@ z|9g*j-Sa3P{lmWg*S~S3ul|qT{SOP@S--vKszdzR8~!M~^%D55ZKhj#eAB`H zx%F-pUh}Ghea9vHetzrmgZ-~_k5~DJSI74{FaAY%mAMc1WhP7(e&0h!B{t&VXoaH{ zj#fBY;b?`U6^>RoTH$DgqZN);I9lOoTff243P&p(t#CAQoP4m0;|kPZ*{(3@yi}RHR^Z1)X#hT znT5{t3&-{N&JUmKU;1AE+b#a>9A9gT-|M#r-gc%xzR9J+6Q+&zQ#ZX#_{1H@`gW)E z{TbVh^>L3~q4KGlj`iz(AiT!uWBsqkneg88p6S0^=xX5uPWY`~uyudkUz+KH#6}z( zt#Gu$(F#W^9IbG)!qEyxD;%wGw8GH}M=KnyaJ0hF3P&p(jT}c^bDH?hJNLbbjdOih9~kc!zx-?A5B}&zzj2u!Z@a_|-UcVA{E$_z_r168@%>-C&aYdi$MbyXTEFnS zJ)ZIE)&Auq{dVj~WY zRybPWXoaH{j#fBY;b?`U6^>RoTH$DgqZN);I9lOog`*XYMvi-KwXgUtc-7RzMttOc z`>6cfpH22>VG@*#2x;XwSS@CPI>noKFXc%Sn_`w4$!&hdW4%KHnC8GoB^ z`LhFrPo8$0FM8pxg!kBNyuY;lfx^e%Gv3$u=t08o{n_pQ(UT4nK4PuAe1~QGIdkzL z4<RoTH$DgqZN);I9lOog`*XYRybPWXoaH{j#fBY;b`RemA`BtzTdfW zMq(qrWT!8w{OT`1?PH!>PxuS3JmyEer^nyl`%ypT^mSD}=U!91+o#889q@>sd1sH? zCV%yBozmBzw%)`3otwX)`e*Gj*-xCXzVP2KpX6h&+DQ1eKTY%%SN^8(9vk6X{_k%r z{IkzY^v^x9sqlOEo#-2^@*lzvEc}q4edy-GzdP?C-{|h|2+#N3N&duc+X&Bf=@ftP zKX(&8^|MbUHsauDg`*XYRybPWXoaH{j#fBY;b?`U6^>RoTH$DgqZN);I9lOo)I2IbWs_I@kQMtnk4${l_d0)Wm0!HcGrrU>dwj&#p7wW+>G3k( ze#*yuy05>;r=IkGe6hE4`ASdtqG!KXzrE=v(|oTf^9r9e;c;JK)ej1 zjPOGHKkI+n?$g4@F87bbMjRZiaJ0hF3P&p(t#Gu$(F#W^9IbG)!qEyxD;%wGw8GH} zM_cp_jz*5_e&Phhj|LNG9~an&KRvOJZ{EAg%;U!V=V_|*{1Y>L+=qJntF2!0v%b{h zyTARSPn+X()%n`C)BU8|#t5&w!3+NWtPriFa;VnM(vadODb>WrQo@w0mb8IX8w;#SEu@MJHD;%wGw8GH}M=Kny zaJ0hF3P&p(t#Gu$(F#W^9PRoyI9lOog`)*W<8=&<#NxQ%0qd#!#*fW1?tSNeN_eZK zUiC*mvXb!p=f3RQU$MOK8RyUNfB*h6!e1Kyk}vkhj|qQo!i#?TqaPN2V4)ZNN9Qak z{JC?d`@0U9NBD$aO!ph_xNpEd{OOA6zQwz55dP)gr~5f~|6X{}&0q9$w;wA!-zqQp z2G5-!yym(y{Ld4P79O?W%YMghM+lFe>lOdt^*ApLHfO(nCeBacn5)E^tHIF9-THLl4Hug3UpV+Q;fJ1|?qikU!4vcePot<^p%yyS+{{E&YvAw2I9kNZhWEG~TO?NfdI4}L^= z)-O->0~cRZc-Mue`fnVTgfFAEM^(ma?)#Du}KkeUJZywe8;bt##FDD#(Ib!YQf}<6V zRybPWXoaH{j#fBY;b?`U6^>RoTH$DgqZN);I9lOog`<%p_T=Iidvb9kzRka{^1oj8 zH$P>OErl0<&%=J>_Wvn-(T$UQ%f-JVyyc9Ce0lp1;gdFa$oIYU+rmFMZ=%2J@J)oj z@ui7=%wgXWzOI|-_s#ze;cX6@=sV1}f$(nMp5#Be?Tf;z%{JM0U-JvXGyXi;*LeSW z!Y4fcu%CS3y22k>XR?3XWDd zTH$DgqZN);I9lOog`*XYRybPWXoaH{j#fBY;b?`U6^=%Zct#e-ct#dS;&qNYQsp0+ zc8`zS<6z+hU-`4|zQ;kr+yD7?Z&x2EyyXJ7`%N$XO8D6Q#{0(~IY4;cImY{MZ`@z_ zqkp>1KYZhU!uQ^Ln?H2SzQTundA#p;?=OT$pZsTUx9lan$<}xH0w3vdTmMc!_QId5 ze2bs|#s6?rj~Bi9E}s_Vhn;!1KQp~Azx}9t{N%0nR{g)6`5@nK2*RoTH$DgqZN);I9lOog`*XYRygAM;&qNzI9lOo6c&Y+gvnOc*A3_^oI^PLwLc%#`(K_jPR&u+#h}Tbm2>Pao_l=(}X8|(EZqxeRoTH$DgqZN);I9lOog`*XYRybPWXoaJZBiTup6NF&Y{H+vZLEKLm4WbMJB{^S=DI?7RlL)l?eCWfKe_f; zfA+ach5vCB${+9N&q-f9(|`KlMJoTy9>4Xw=IZg$`<&x1oN}Sck3Q&J-)zqw&vVCl zzTEG7Jof$P`?YiS_3wG?d_Q^L9`E88_)c5)ZQV5MrF{P{I}r;YRxBVmTH$DgqZN); zI9lOog`*XYRybPWXoaH{j#fBY;b?`U6^>Ro8aX1SBaRW%5l7-3FS}Rei*A2}pK|~0 z!dESEsNcNjc;O9pIK<~Y=r-Yr?>xlcabiCo7P#eL|K)bKsC>u4!T#(Q|0MiF#Fc)s z#UF)F{`w(4=7%>6KfUsyZg<=uytp0Vr!Lmx-%U8uFPw0_$`^U!DF5igJ^s*2$N0vd z>FaE{Ro zTH$DgqZN);I9lOog`*XYRybPWXoaH{j#fAtIU>d?juB%ON8$xG{kzK7SoM4U?2`Sp ze%JZm^;a)_Nad@YINEo+e4_9i^NjYRuX#}Tv_Egh3{R~?;Y2V?R={(??dmMqVl;nUdRoTH$DgqZN);I9lOog`*XYRybPWXoaH{jz*5qAdLgBE;LBQ(jc8Xy1%|R|7fx; z{?~pSet7pJJABg@G$xBKH_3kUwdaK|TX>RPwApjQKRkYty>C>%#y|dnhwZm(J)`m+ zfB1;adF0c=f7CDxd9{S8dKSd%V`%GyC~B_IS!#v-%TjKczZ; z^6dW1y!~(YI%5vs_39o!aP^$N;xT<&YmR%TAG^RoTH$DgqZN);I9lOoN>x+bNF3!O;pwD;%wG zw8GH}M=KnyaJ0hFHhP1j6^>RoTH$DgqZN);I9lOodVe(F#W^9IbG)!qEyxD;%wGw8GH}M=KnyaJ0hF3P&p(t#Gu$(a5pP)h;k~$Q?Ag z{T$wTYzG~(t|K(M9dyXT(CBv1A@}8@kL{pC7KTQ*gAQ338r=>$WMOD@JLr&wq0#N2 zLl%Zcw}TE@7#iIUI%HvJbUWyfg`v^yphFghMz@0wSr{7K4mxCEXmmU1kcFYq?Vv+e z|DnpqZZi5b47#iIM z9kMVqx(zyHVQ6$4bjZTc=r-t(g`v@H&>;&$quZcE7KTQ*gAQ338r=>$WMOD@JLr&w zq0#N2Ll%Zcw}TE@7#iIUI%HvJbUWyfg`v^yphND(QVKn3qzyZphFghMz=wSEDViqgAQ338r=pRvM@Bd4LW3D zXmlHN$imR*Ht3Lrq0wz+Po9`M;&$quZcE7KTQ* zL5D01jc$VuSr{7K1|706G`bBs(QVKn3qzyZ$}@6e>X4Ho zb;!w)I^^U?9ddG{4mmkehnyU#Lr#v=Aty)bkdq^I$jOm9(QVKn_xPrR8+6FR z(C9YkkcFYqZO|bLL!;ZELl%Zcx0QERiK#X4Hob;!w)I^^U?9ddG{4mmkehnyU#Lr#v=A-D4GF)`mgHfVG; z4$$Z}=#Yh>(QVKn3qzyZphFghMz=wSEDViqgAQ338r=pRvM@Bd4LW3DXmlHN$imR* zHt3Lrq0w#7AqzvJ+n_@hhDNtRhb#<@Zi5b47#iIM9kMVqx(zyHVQ6$4bjZTc=(h3> zIWcv}$&otbX4Hob;!w)I^;&$quZcE7KTQ*L5D01jc$Vu zSr{7K1|706G`bBsWMOD@8+6FR(C9YkkcFYqZO|bLL!;ZELl%Zcw?T(242^Ds4p|r) z-3A@9Ff_UiI%HvJbQ^TY!qDh8=#Yh>(QPHBlbAZ>X4Hob;!w)I^^U?9dawNxx|dk zHE47-4$$Z}=#Yh>(QVKn3qzyZphFghMz=wSEDViqgAQ338r=pRa$kS^oeer;&$quZcE7KTQ*L5D01jc$VuSr{7K1|706G`bBsWMOD@8+6FR z(CD@jV@*sQa&n{&IXO~?oE)h`PL9+eCr9d#lOuJ=$&otb;&$quZcE7KTQ*L5D01jc$VuSr{7K1|706G`bBsWMOD@8+6FR(C9YkkcFYq zZO|e2b#9*4phFghMz<9WQetY5T5zNeIXO~?oE)h`PL9+eCr9d#lOuJ=$&otb;&$quZcE7KTQ*L5D01 zjc$VuSr{7K1|706G`bBsWMOD@8+6FR(C9YkkcFYqZO|bLL!;ZELl%Zcw-rs`sKC?& zCP(U!lOuJ=$&otbX2K}c8&^6ZRaRxbfx)(Mt2l+$imR*Ht3Lrq0w#7AqzvJ+n_@h zhDNtRhb#<@Zi5b47#iIM9kMVqx(zyHVQ6$4bjTWWXmlHN$imR*Ht3Lrq0w#7AqzvJ z+n_`4@%}G0=#Yh>(QVKn3qzyZphFghMt2l+$imR*CZX4Hob;!w)I^^U?9ddG{4mmkehfH1_ z<5t0uSRA3zRXH@eqo6|;hDNtRhb#<@Zi5b47#iIM9kMVqx(zyHVQ6$4bjZTc=r-t( zg`v@H&>;&$quZcE9%3J$(QVKn3qzyZphFghMz=wSEDViqgAQ338r=pRvM@Bd4LW3D zXmlHN$imR*a()VPeg@WD4UW_yCr9d#lOuJ=$&otb0?X$>qpNagbQ^TY!qDh8 z=#Yh>(QVKn3qzyZphFghMz=wSEDViqgAQ338r=pRvM@Bd4LW3DXmlHN$imR*Ht3Lr zq0w#7AqzvJ+n_@hhDNtRhb#<@Zi5b47#iIM9deJSVocWSF*Lfocc`5Ai@>^f1V`$S zlOuJ=$&otbX3QgZ(Iw!?+4Z%02*DDL!;ZELl%Zcw?T(242^Ds4p|r)-3A@9Ff_Ui zI%HvJbQ^TY!qDh8=#Yh>(QVKn3qzyZphFghMz=wSEDViqgAQ338r=pRvM@Bd4LW3D zXmlHN$imR*A}3>yq0w#7A*&o3UGC+CV=qUny(QVKn3qzyZphFghMwic1 z!hD_ztY@p>NF8!=qz*YbQiq%zsY6bV)FCHF>X4Hob;!w)I^^U?9ddG{4mmkehnyU# zLr#v=Aty)bkdq^I$jOm9(QVKn3qzyZphFghMz=wSEDViq zgAQ338r=pRvM@Bd4LW3DXmlHN$imR*Ht3Lrq0#004Pn0D2&{JX4Hob;!w) zI%K}55=XwL3aocl(CDfh8r=pRvM@Bd4Lan0Ob#2@phFfO^^7;@kcFYqZO|bLL!;ZE zLl%Zcw?T(2e8&pjphFghMz=wSEDViqgAQ338r=pRvM@Bd4LW3DXmlHN$imR*Ht3Lr zq0w#7AqzvJ+n_@hhDMj~8-@A4F|gh}21n|UlOuJ=$&otbX7-~SRDD@II!L!L!+y5 zXmlHN$imR*Ht3Lrq0w#7AqzvJ+n_@hhDNtRhb#<@Zi5b47#iIM9kMVqx(zyHVQ6$4 zbjZTc=r-t(g`v@H&>{EupmQ5^$imR*Ht3Lrq0w#7AqzvJ+n_@hhDNtRhb#<@F5mwP z^ZkEd#R7sOb;!w)I^^U?9ddG{4mmkehnyU#Lr#v=Aty)bkdq^I$jOm9(QVKn3qzyZphFgh zMz=wSEDViqgAQ338r=pRvM@Bd4LW3DXmlHN$imR*Ht3Lrq0w#7AqzvJ+n_@hhDNtR zhb#<@Zi5b47#iIM9kMVqx(zyHVQ6$4bjZTc=rSHB%y?X2#pZ$|b;!w)I^^U?9ddG{ z4mmkehnyU#Lr#v=Aty)bkdq^I$jOm9(QVKn3qzyZcDsC{Ff_UiI%HvJbQ^TY!qDh8=#Yh> z(QVKn3qzyZphFghMz=wSEDViqgAQ338r=pRvM@Bd4LW3DXmlHN$imR*Ht3LrS6X?u z1|706G`bBsWMOD@86OvBd_1sX<-w6UEa-X4Hob;!w)I^^U?9davYAyR`hiqBTmAVH%m?$GFV&>;&$quW7;EDViq2OY97G`byh z$bFsTCw0&v3qzyZL5D01jcx}WvM@Bd9dyXT(CBv1AqzvJ+d+pc42^Ds4p|r)-3A@9 zFf_UiI%HvJbQ^TY!qDh8=#Yh>(QVKn3qzwz{TO+5)Q<(0mMl0@hnyU#Lr#v=Aty)b zkdq^I$jOm9(e0o^?(2+Ozk?20 z7#iIUI%HvJbUWyfdwj?i9dyXT(CBv1AqzvJ+d+pc42^CF9kMVqx*c@L!qDh;&>;&$ zquW7;EDViq2OY97G`iGtiVO9efu-#Xj?^J1N9vH1BX!8hkvin$NF8!=qz*YbQiq%z zsY6bV)FCHF>X4Hob;!w)I^^U?9ddG{4mmkehnyU#Lr#v=A$QQ|iX(Nofm5Taa%gl1 z&>?F~pwS&bhb#<@?f^PuVQ6#*&>;&$qdR~OSr{7K0d&a1(C7}JLl%Zc_X_Bcg`v^C z0y<=2XmnSD4p|r)-PNE&7KTQ52s&h8Xmp35Ll%ZccL+LUVQ6%RphFghMt2B0Wc42! z-J!xUacZquhdSisNF8!=qz*YbQiq%zsY6bV)FCHF>X4Hob;!w)I^^U?9ddG{4mmke zhnyU#Lr#v=Aty)bkdq^I$jOm9*X+PXnzQQK$v&Eb4zxBQx^}ABPWBuWt z7hXN+ubh*1&>Baycde%VfX#Kvp>Nu!)%{!4?@IlS^@n?|obf$9ci1;iIj=3h?Vr`w z_*Kq%(|*40^P_%O>UXR^-1~?9=D1uom%+2er1b~FUs?FNH$C^&=fSAomHHj)5BHvG zK|4t{Prd5?_T4q~Uc%;ie8QXF57hStQNJtoJJuiWedgq6^iIhp-uy&+@;tp$vRT)i z_NMnp_5D)R?@IlS^@n@!{gKbCrT%|l-dEc>|E719HtQ2Fzv+EreGeJ+yHdYn{o&#x z%kML*?0toHXjI&rx4oLbIVU46Jwl7;|S^97Bw)FvqsW%>#FgZAE>JdDPdn z7*6MdIU}2#1DG4aoExFFP;4czVlGi%b0+F*E)Ay#!<_H!V-90(3v+IVCP(l519yxC zM19TqsIRqvHOSv~@$OD`h_PmcxdyQ|g}F9EyQO#0fjhpVj`~`&QD19$IDIL6j%?D0 zz_$p~w}i$|???l8e0Li4<#VFGe9>?^WcWb8`LanL4&N?J-yWJ_y;BO@@m*8Ym(P#-x);Q^3|%}M$__E^S;D*r;oc<7dsAr3 z^{yju$9Eu6U-zu2uX|a1^ODaj<2dK}{DOO~Fz=zbw+i##8s8x389Z>uXY;79dv4U% zy%>7{{}`a(w~23>^c_>+j?XVqUwfXYuf0&IW97G2Y+7lHdug>5`|9l5pxDg%Y->Vtp+pNzq$@<)1S-D1DuAP@_>g8H{%m>ba#GD&hpVu_&^IChE zV~IKUyv#{2bJb%$>pSZ*x3fOyWY*_g^|D41bM1IpQ(o4Z$9mNF_+@QoeXgmj&$Z@d zjVI>X_u>=0_zDkyqH`OHZ^`=f30a@M!i$eeOyA|jr+M*p9{y10dlcW8_36{HK7E}R zADfuI*Nac~;;TLUxz2$pzCG*HCue>7YA^SQ#JqQSxuSfuk^T|>RhREZ_WC=CuV)#D|z-N_XfO2k1O}?apj&quH5T+maKd! z_Ed?vH^}&KNnMq=(g#+5zExUyH_8K=32NzA=X*5{ri>vOL%uI!N#>#V}E zry5uGTC6jm4=-mMcEnMid#bE2T=sbEPsiV~KV?tIzNwsji~XcH2JXl=>Z{LDUtBPr zjpHBVNzDBf$55DK7<*Ua*y0+gt+-yqx^_`tV;=Q&Ey^C7b3-YlFt&zaoUuAvG`KYh8P@ZwPHf0C< zE3QFduEBWrF|N&cp3)i*%>7l?*P4y`TFd1bjlM-Td5%zdrlW6BIekk!56VXc=Kd<{ z%jZOW`J(cSN#7_tJm01~lhQY;oW3!hXXRr9bAOffsp;EQ zPTwBScy;bGBx8fcx`#ftUF!xtkU-#UouX{1}B>XM+Fx;QW4sm(6 zGl=&;+HYVVqWahiWgWfui#oe?Sk`Fh@pAFFppfQOILw zIv@V6ycdmkwt9y%lFn3rEAO1+eYoB)jihtP-^%;^h&AZl*GM|M`>n)EB95c?awF-y z>$ehziWr&VVk7B{=(iH%t1(CDnVs)HN5Z+vZzXh z7ID-_I?Jo*E&1Jw^k)3drNmxG6`f=oN#|b`Eodw8=r?`0RWzJ!B%K*mbgHfB5Z?4n zT+x@dk#x>d(a^S{KY7#lhDH0@M$*|tMc>h&TshxbGM0HxbCqr}==q zb%xx0+V>)Fogp`$F!I(Ja`W}&qmMP@<`YKVIzw(gVdSkd7G{U{?Y;Qax%%&4KD*edw)`3Qs{T%wEbL!C`$plz4;t;?Iq?GF3zt92 z@lP0Kj=u?`uH!etu;H+!@33IoXTtv&!$O-ZH)58v4Pw@38^pB3Hi&7T|A<+}zY()8 ze?v?gv_(wYY=f9>mh!IDZ^ce4_FHMUmHxES&sO^1Fm_}5{yfU^yIr|)W35Aif&ykl<7&-g=l$m<_$l2$}OQ>?>>~rKL6h_WIM_xi< z}2l z%TE}2?i{)NgpudYk;_jQdF~v!{DhI`&XLPc7}2l z%TE}2?i{)NgpudYk;|_yzilf=EeNF!HH6a>fZGpPD0QoG|jKIdaAcBcGZh zXPhwdsX21S2_v7HBWIj2@~Js;#t9>znj>eNF!HH6a>fZGpPD0QoG|jKIdaAcBcGZh zXPhwdsX21S2_v7HBWIj2@~I8`J#77Ewtm|i-|uwDLFUM_COgPM=E$=qj2vW+JZr+p zLFUM_CX5_pjy!9^$U)}FvnGrjWR5&*!pK49$g?Jl9Au6>Yr@Du=E$=qj2vW+JZr+p zLFUM_CX5_pjy!9^$U)}FvnGrjWR5&*!pK49$g?Jl9Av|OYh1rauHQ|^_d6Z(b~$pB z$qw>%IdYQ;BX5@@H<>Wucc?8xUOj9gcad|txHb>+zCC5&8Gj(lFi$aUq&=Ov6>SB`vM!pL>y$mb=D zTvv{KUc$(A<;dqHj9gd4ej{JMqp#ol$M-uO@QsOLY_b1IN)NqKFMhiDvfEeRtJkt5fVF!B&NaxDoX50N9+k}&cRIdUxtBM*@y z*OD;u5IJ%!2_p}YBiE8J@(?+4EvcW#L*&S{B#b;nj$BK^$V24FwIqx@M2=ibJ>LH% zN3JDdT(_iG-26$B~~%7`b~K`H6&)yT_5AXh8eO-Q&nl zB#hiWj{HQz$lc?}Pb7@oJ&ycD!pPm@$WJ7U+&zx`M8e43!pL{y$mt`Dd^e7q zKElX%!pL{y$mt`Dd^e7q zK0Tg_v0AUk$amxM{my?m?JR95IeOIL_;W95IeOIKs#gO|D;0Pl}j3W<@Fml8=^56&~M~ov6 zjxch>IP%~KBS(xQ4~{T$#5nTc2qQ;~BM*)+a>O|D;0Pl}%&=$ag!ZH3`6}`Kj?OlT z?{_-nRdM8wksah!apaB>MqU+1?igX@RdM8w5k_7WNA4J5 zMqU+1?igX@RdM8w5k_7WNA4J5fomeAt)AJMygvBNqu0UF;={TqKTsE5gV{;>fom zj9es+d@I7pMdHY}B8*%lj(jV^$VKAFw<3&OB*UHo6 z*+KpeM~)I<;Y)XMM~)I<VdU>{*juK(y?{MTO5k~$FM~)I<VdU>{mfVHdEvmiJs7rx6}R|q5L zg(I(rFmhfv@_Gm(=Y=D$hcI$pIP!W3Bj<%9uZJ*lUO4i4^!T829eF*3k@Lcl*FzXN zFC2M2gpu>Yk=H{QIWHV}J%o|-V%W3GLfhH#JfHY}M`!88_d6Z(L^yI`$PV&EIC5bK zBTs}Q7lttML^yI`2qRB~BNv7+@{@R&eBx5JqkVNB#(5uew}$3-|y(XWqiNW;S7I6o&wpy z8UBVm1;RMP-;k$37-#q!@)Y!Sj-O=6Qy`2p{0(^ugmH$yAy0uY&hR(nDG#dv7?~ zzppcHeZ$%Q!Z`QdaJIiN&b>FB?cd`=wlJLSFN|~V4QKlc{=zu--f*_RFwVWtb31vq=bO&qEa!;k8J-=_6y58hS@``< zSH9ora8~>f&cl~YoE1NW^YDdnR{Rjo!xzR`@k2NdUl?b_58*s~VVo5|g!Ax)aaR0l zI1gVKXT`6E^YDdnR{Rw>4__E(#b1H*@P%A9pYuOi8w`vc$qNb6dmGa zefj8PJH*R`5vS-7FB3+bqC>n)7;%aY@iJk=DLTZjH7XH`sW6K)v%G%HGcNm*! zh)u{QViOIq31P%08e$W|h)p!aCWH~2XoyV+BR0_xn-E59q9HaRjMzj&Y(f~Zi4L&| zVZaV~5u4}`n-E59qC;$=FP}WQi|=>- z%h|lew^J9P`sMo_#wHqK6TO{v)^3PR2qQMp5StK2Y@#7H(U-5jWM)NIViUrMO*F(Ngb|x)h)oD1Hqj895JqgG zAvPh5*hE8YLKv}$hS-EKViOIq31P%08e$W|h)p!aCWH~2XoyV+BR0_xn-E59q9HaR zjMzj&Y@#o}ZL5aZgfLNl=7;y;Zvwt9$;LubpXoy60h@hw<&Yb*gGrt-a1Zt9Fp*bw}s$ zT>mCIywA?}CWL)&BI|n-!oD|=^}PvU-w6QzzBiHey$NC8o5=d!gs|^TWPNW!*!L!~zBeK4dlOmT zn-KQBiLCEU2>aed*7qiaeQ$zm{Dh-tr^~a@(`PU6+l}iUMTcj(``(1G?@eTVZ$jAj zCbGUaA?$k-S>Kxw_PvR$?@b8%-bB{-CWL)&BI|n-!oD|=^}PvU-w6QzzBiHey$NC8o5=d!gs|^T zaBZh>^jvy*&V2Nno$Fmihxdy5-h{C4O=Nvw6Qb|Jj19?@b8%-bB{-CWL)&BI|n-!oD|=^}PvU-*!L!~zBeK4dlOmTn-KQBiLCEU2>aed*7qiaeQzS`dlSOGH<9(d31Q!x$ok%d z>O8nK>w6QzzBiHey$NC8o5=d!gs|^TWPNW!*!L!~zBeK4dlOmTn-KQBiLCEU2>aed z*7qiaeQzS`dlSOGH^H^s!qNK__a=mWZzAh^6T-eXk@dX^Vc(m``rd@F?@eTVZ$jAjCbGUaA?$k-S>Kxw z_PvR$?@b8%-bB{-CWL)&BI|n-!oD|=^}PvU-=Fo5ca)^tnW<-``$#>_a=mWZzAh^6T-eXk@dX^Vc(m` z`rd@F?@eTVZ$jAjCbGUaA?$k-S>Kxw_PvR$?@b8%-bB{-CWL)&BI|n-!oD|=^}PvU z-w6QzzBiHey$NC8o5=d!gs|^TWPNW! z;`F_VtnW<-``$#>_a=mWZzAh^6T-eXk@dX^<$gP}zBeK4dlOmTn-KQBiLCEU2>aed zo%H^l|M1R~s29WgP!fK>_-Az6{X6s~>iFJ-$bD}j>w6QzzBiHey$NC8o5=d!gs|^T zWPNW!*!L!~zBeK4dlOmTn-KQBiLCEU2>aed*7qhdX>TIydlSOGH<9(d31Q!x$ok%d zuKxw_PvR$?@b8%-bB{- zCWL)&BI|n-!oD|=^}PvU-w6Q~v^QbzuTP@)*C)~Y>yzmH^-1*p z`XqXPeGO_}+xQTRe&0EuKX0 z7Ehvgizm^$#gpjW;z{&w@g#b;coMx^Jc-^do<#2!Poj5=C%jucdfvX>za#HCimt87 zM%P@~{X6s~?0wux^giw+dLMTZy^lMI-p8Fp@8eFQ_i-oD`?!r;oJ8+^PNMfdC((PKljyzAN%Y?5 zBzo_262131iQfC1MDKl0qW3;0(R-g0-qtoFx0+m7GNHN=~A8B`49lk`v#Xuy-XV(Yulp z-{sitM@7YUwVgf^lk{d ze}{KQ#MjT;{X6pBuK!E#9gg13VfXJO?A1r_@`yRt_a^G3y$O4dExn1{f5&(AruXkK zUVHzD^k~xiT#~yFFJ$+*B;3Q1-e-|;Z%2CnMZ!HF>3taq_kyJNYb4wwlHSLWaPLTZ ze}~*tlHT``aIZ;vpNqE>?sE}2KFBloprrSeh#h<&$3FjHWcYy5yx~{m z_+-qQpBwYY1&q(AF1c?U`g9)hlWWvWB9{BFRQ^hym&<3pPRt?yC)ap|8eqrA9`Yk& zO7kOQP4go;Nb@7PN%JE)OYe#9qpD;k$DJ|q1kvXeyilgO{nkJL+Q62+NB@sm#*7jova)GEpYb|laE zjPizGk>fMUv(0CjJL$ZYoS83QJF974R9`q@JtPL|o6Zf9N1V5{U_p2MmapnGUNG0S zd~i?x<^vZBcRKjj{Q32iKm7dX{2k+zo2}WF->$+U(b;*&mi&hAD3@rwDSvXeuSMQ< z@rL}*8!i_9WyAXXK~=sHetzuw{L_km8{{9aS4O|zhu?`DJFkrRUKsl&u3jRH-!)s5 ziKpqkKZu+-`+liR{LM=)6*=QdDk@ih{{Uz5XS)@4rhh=$BF^m07;=y^`z=2&>df!0 zUlnr}&ojdhb{1!g62+axU#eztXX8R{<3-={fE~*Z_APJtwR{qf<(W7w|HN-~iR)#2 zakZmoTkT-09c;COt#+{04z}9CRy){g2V3n-&e%<#oWNE)*lGt`?O>}NY_)@}cCghB zw%Wl~JJ@OmTkT-09c;COt#+{04z}8voZ6W_wS%p8u++QC*k*lGt`?clgxaPuD* z$Xp$L^X~k@2Y(@4cjb=!6?Z8&d24h2=>@+O`NneV^J{&seCTm&^QV2T$LyMKR_1^7 ziyoWr-nTrzXMH^eFW9>@fAM%d2EXXOG#q!xAL^*b8u|<8>#>HNA!YSA!v1sT>#>91 z@(q?r48(KVk;_Az_r9b|{MVFNA#%pG`BdeRUlejCzwpr_&h%%NFXqh7#*W3E*A&~Uy6=-*MwJ$R;)WY?U)WkyxOIgwxiv4^l8b(qh9Bqh4@Sn{V08Hmj16qT z*k+6{KD|809~?8KS`7~{E7}f8FMsj)8EXzRCCrWbLcl!*kZR~Y&Ovis#Z1P!eU+nn$S9)d6 zC&DF@z2|HdOVOPyk$tu%x6D6FWjX~%gpw^BZX`A9h6y=*F*TamnL|d zAx_3AazE}|{t*K*KXzes{n&;5*mM2Zh5guPkr(vQjbhG?#*!P25w@|TV>#ioV$+Y; z=Xzg0{dmQ`AMY$bUSU7pS$@32e!RJUyuyCGxqiIDe!RJUyuyCGxy<8D!~f)uA!;-) z=f%fPO8Lr6%fW}s-m2e2%T#`(kjQ_p{)3;qBQ|%OaL}yhYfKVu^wdMM9{l8dvA^Sl zzOx#RZYuIs)nD>D6-D0YslBu2Ts5~g@l1R5!&zmYd|YDKGVLR;zdVQ7R#mT-`@nt0 zW}=hZpWPIH*7Lsj z`McWO^tbwQJYzG~VVz3XB5Vq$euF-8^(*oJm5#<-s8aOV+*qIQU;XSRk!x(&34Z;U z3sp>G7LN2KR`L_;MB~M#OH6UCE6aVAmx!4E#8@uHuLe|$#yNus>r zS9I{nn9;{4xq$I$xx;5%uT`}#&C99%^DJt&ym+U)`XvX6t@1-3$-BPoN7TQPx0Toa z%OYks@Xjrd3m2VnrO)9Y;l_PG@wxTSFZBBO*;BQdaQ*V<`dXYTjEujbgD#(ev4JfZ z+tga^3`d?Zxz`s)pL`+5j<+w2eg97wpZ;&c`1GF<#;5loj88vCVV%Q4?sFLQeQtxD zB(m>o5&ZfZg?N1JLY%&)A^s#97jhdf`oj2(@`L?6#)wbG2IG@4!}uf@Fg~NYWd5G| z*2rFwci6Dvx#KSTa8`lp^@Y0}GA#GL^_}w`m^UtW(X9{Ue(=euBLD8R^|^m~<4%#E zamwc09&Ha6`6uTdm-k_<^F&_Yu+#FcJ?O1mY_?cbJ8$hBM~Hk#|7-J>e|e$E*S~y8 z-UWqc=3>9fQ|+bJ=r4Zr%Dlxjewl@Q>WAIY&mc$N%X3Wb?TZ}y-cH8s_;?cZiO2g* zkmJ|KFLL7daf+Nc{dh&rc>TCU&bWL|L{3h89z;$aB6-fIc|AnVoQdpYBK=I{Hxt>< zL~$ljJV`XJB#J+Y@{mO1mARDWEs64jzU3LYyrayy{8{+zjyhq3iErH->@*h zclm7#^Lv+nFf#rIqswPtY+wt7^vM3&Y`&*ps3FM%IZE~k}jz@0eML!og zF%m0G>`~riuK+n?Wz1@4jO-P__#}5QKI3}9>@DCwX7rI03pId=1^ekVSEyk$%)nU$s3Fv#s*`boWl6@e@kF|k|P+O@lk0&*|YN+oLEKV zF*o~jO_9&PdC#mTOP(hDaF0&8EgnB!ctF|LbLX62LbzD7pK|$!9c26sMwidP*uWNy zZH`SCpI)A0a<88;eQ!q?JKnx9_Wi#E9enz~3FFiI5XPtXA&gJ&LzwYK@|;LN6WPf` z_A`;+B#I}A;!L9WlW1JXZM^7P9f&nRyRV@tl@}G(7lJob}_tB@y$sG9U z>hEV&-c(-Zz=DMU)r|G zJ#^H;qO+&ixZFc7K1_7RcbJ^}OT(i?=k`G_=DtvUdoJ_sfZ3nqj_C4RF7vI?j4yJR zZ7D1|SC(6n%iqvJm%pKdE`MWAqKgl7@QDv}@QDv}@JX!b5IeD=L+r$g4zV+4bjSf? zMu!|QW^~8_^+JbSvUa1xv4R{OjumewC$f_h*~u|GKAubzPbP{dWAXTLiB38$(MiW8 zI*iNbM|9Hsh)$Xx(IG$nZ=#dtS#;7oC-@?l-bbS2l6oaNE~%I3kV~IC(MjtrI%(ZS zhg|yHiB39yL?@j;qC+ly?nH<02%kIAfqm{o2afFI_!^j<9A5*olM}_0@wK#gGQO4; zPbL~y#^+9S{2a;n+=-4KS0>6&#^=uRlkvF|9iN{}l;@1ko#i>h-^d}lQN0p;kVAap z108%ubx(ZmM2FaY?nH;!qxqBg+}Zp|eC}-i$hwivLt(8~C1HG#%V<7h$L2G3Y(5iD zZaNQ%CpVpk#FL91;)#wg#w9xGxI~9>MaL=m5gl?F9j6I%6kp_$If^fG$sENOxn!=V z^N@Pw>A0j`qC+mD^@qBP4!PtQmOT4hM(Y^!M|8+#w2t|Gq~Wq=GT+#9U@c`ogS`lt z{S5XfVD>ZEyMWox;2(^PzrpD885kSbf^9Dd#wU9zCTG9H^w|f2vBUldjD7!47@z)c z!uVvL1s!~{7X;&zy&yOpm&s)>DAkv}AQ+#K{Uq|6MDZk1oJkbF%r~_&9J!4bePLoG zR&4rkFS5P<14Ng%ziBAIMIIW{(W+v z6V^-CM)Jd&#@Yz8*0D~(tjC-a!mP)vjV5PpG=0`a*w#iE`>c(yt&K1~SsP(|Ms=Y_ zBXa76P5!Iv|Ned!eWicpe%61{_mqAgeN6h5)YSU0%F@r3ewX%MLvJ(_UE}dTydLKN zzeh~W*2Db+u9L}_{l6L4|M2>meKAM&=_yMu_#b;+O{m4+^q{rx%(3~8y51&^pLw#c zS3WOW809qKi)!K(|hL*`UWm^TwL3$u6CEGK+Zzs1>hOG^sB-TS-jBb5sXKUwC7 z?C??xGkkX88Oyw#sWSg+0y`rZH3%ti~UqCJ?~WC=OEY- zPVLLwP5pAdIx&q$IE_;{jXw|jevFJu_>lH<8JF<%bssP;(cdxVUB)Fmbi!MVOL*p? za~PNS?fkQ2T*Ak-$!A=`BRc0XE{VT>)x0pSRGveeseXodQai$_ec{xvIhpMVXGr-b&TZxy0f59EM`a8>WJLx z2wNRtt0Qc6g#ACMBW!hqt&XtO5w<$QR!7+C2wNRtt0Qc6jO1KPX!;r0>IhpMVXGr- zb%d>su+XW6Z^xb2&$r{w+sU`%&fCwoa+$ZOelGf{9pTiz9D}LfJap1{gwr^M)A;4sNyjB}Uq{9z?CZ<8 zgniu^m$07?j7!+h6UHSm_<6{IhpMVXGr-b%d>su>Z$+^I)qZY;}aKjIhpMVXGr-b%d>sFmuK7$nimbk#XFRN0{S@Ji;7jIhpMVXGr-b%d>su+`DzUTsppL0r>X_IhpM zVXGr-b%gVWZ_4_y$y!}>d>oYyu@5kxF&;K;TKletjJ^lRD z*R!+F(DR(>r{`tgsC%J&pPo4XjqJvAZjg~oY=g$%%%{3JU^ASb~awd zZsUb*ys(WIw(-I?Uf9M9+jwCcFYN!xcwrkaY~zJ(ys(WIw(-I?Uf9M9+jwC=F6Oe# zRoH6!!O9o%Z(h+szW0y$Wm5k9Gd2lVDLyiP#LzQjO&HX*PyUn{w+ZuK{3x0ki}(GDhS!M%cy(+ZfTeF(QxG zpW2l+7pU-E{%wD1EBwu&i}K4>=ps75yfr_6*poek8{P4VF!4N4=7XSfb>X+= zv&44GrL)B*JnGO~@rC~IRnd_vSCRWX{;zzG*!Mm$*!Mnc-}|tA@5A=J58L-X zY~TB^eec75oc}B5Id-g(XFJx2$Bs4Fjx}`bSVL~d8ge_*N6Q%{{FpCp9lY2?O%B>H0;Twdl&NElCH8?RNoezYAddT>#tf0@!{Rzb0f75-*Z0A?7onOIreg)h470lYfF_6mt z(0vu}L(V<$W#=BSU#p}K3;Q)z`mnIyua!P5?Dui`j?Tb-f7jcYD(v@(r4NhT?*~gC z7WVs#S>|FS-`~H}{xAFWe^>vG?C$sWa$@I-u$?QycCH9>FYT&Qhs(Ys&w7G+jug*;f_aV<&xV3|jug*~f_aV<|6pYN z4MvyGz}UbRjBVC=7@s`D%H%xT%JjLf6~+$FrGl}~y{<4m{ojP~$uqT(A&^om}L^9_0VY?p_w)-(* zyB`zQ`!Rb>g6)1xlXE|&>2p6OZ1-crc0VR;_hZ6#KPGJVW5RYnCQR+PPcxOv{g|n~ z+*b?Zllwhk?g8Z=j4X;r?yE)4J)qoA3S*nv!Q2CiZ<7;~=@To=y`+o*#y(?%@yVEB ze3Cnu+(dPe`)ZLhuIM_kf5`J{Qk!xeAkXgl$6a%%*Xd#Z54g7Qe|QbyA91aqUbB~u zSFYdtpFV?&IrjHHgA2dES3i25(*9>~`R8=)e+E~04%@%=Gq^Yw{5gtUL(6Y1>8<_k zHQ133zmY}%zxXVBk(2oQndkrK&*1XC#mVXOto~MCey?&Zbgbjo^RV{%7=-nDY5jd` z?0r{A89u!aVSMroF7)l51sGWrkH6m}JS)uKR}$iv^9uC2 zPb3;I`cfNwdOK2Ie0m?k*ykBs=9e)O8$QW}#TnHlJcEnB{lA~l)T^Sm72Th*kE457 z{*Zf%h)?gG`R6@@3!mKogJ13k;=UleXNUWIG#od5RGyi+f;0k&BmwyHqze!0|^!s%GzJbrlzv8|DzuS2h5cT3W zY5J@ud3F=b?_GYw!u;Olw=K-?UH-wy_#2EapMhgsqM+w*5JX?TyGYxJ*tRO`n{?R!127J`RRQ`Wr&nKFnc`)N8*D!e?cRH{3A9v(|IpT8^Kl|=~<+%HQKclHv z#rQcGF-OmO`h%Xq)oT*Z;=pJ03@e`5CC@P7xl_?Iul_;L;ObTJkADVN7}vkRGq~j0 zNAe7u^chO_?3(@0;PTH1(r0k>nv_2KNWL%9XCDct&pz7!3@-nirN8GHTzvQKe+HL4 z3+})346e!PJoI}ng(j!-&~vXz={(&33@)9A|02)e(siD_DE4LeE@S_RXQ{wETZO$d znCDTkCj;{=7WQReFOz4r!0aEgw*&J`7xsK$p7r8=2y=Wza@h+?_5Xp-;0ojN`+ir- zbGPtGO!y*3VukHFGcaRfY%pVG%rH417qC5N1}10w&o}-N&*1v!oo_JLshwYw{t3^x z3-fUQ@#S;=-#NbGdco}RrfY~W$2Z3&a*l6~S=|TzpS`OBAL)Lw)DE__5ymI$0&Hs| z%=*DNVOtwvTN`0p8(~`;;dET`S=JWTsZ?LqMi`%w{e*Q2IkG4o*1G@X8C?Ioee$?o zjGyuGe^K9Le?RMAw4e1~^gTl#lRhu?q_4_3p7KBU8C-we|NTR+lga#bPkCR@_kZ>d zyL~Z7_I)q-kGQU8U(B+vDDTXYUUtTM-+%NoxR@iAs~nc_-_lFo%enp662fD@uAkZa za1r6kRfc5l-KO{OZYwr3lXJ~Cets32#DDqUe3rkXhn&yxdF0r`E^_k|$>lz#RNwb^ z3r$Mx2&eXQ(NFz~JdH;zX`QK?gx#$rCpX2k$vFH6s{P^MTkzB@`>PsH*L)_@4_A}_Genp%5`Nt1= zM4!*cd4yM#ZX$cc#%Ufzp5{jw|Ku0_G@rt0o`uu=3#WAvwmR}z^AD%;S#YYK3#WF3 zQ~ScHU*R+!;WW-XK5KP^t&XW&>IkR#5&bl8W?$-vj@1!P^DjD9N90yV*pEx<7|C;B zt0SD+$-q`e*y;#d9bu~@Y;}aGqhC{`rq}c>>E9vRP->mIcCdf9Xnm2ho}XN!rpP~j z8+?w>BgYsQ z{6z8$j33KGYDeU${RExVuW%ZVa2ls@8ow}~v3eQDb%fJA$gzfh@{2spn{b*>;WW>} zY5rwirF9XuI;tJ5BW!hqQ+=7+sU6|eejYlhU*R+!;WSR+G=5>LBcDz4VER%=WGfj5l-tOu~{9}j?Nc2mCM*uePOF3I#x&6>Zo>PUL~;A5w<$QRy*dH)eD)` z3%S(`xz!7{dcjt&{l}dgkALWKXWuvWy+;1+dkwblHQ2t_sEd8CA-C@}22jfE$(uU?oqCD+FkC7 zdV9p?%SG;TxAjpj{!24A`O|&!HAn3g9rS;>Nf|pc$0%dJ;$mg|&MZ=3HgOWq!)29; zb8%H=;;&OvnQ=8cTY2e6ErY!9^{s+_kHxKmokmx+4)!;`-a7a_xpZc?4yEnB$kLe<%n+uU8hNOd+$Y3_zTr8;vv zw{UmwRGoLuXzn&v*dt>Z^Hg)UV2SF~AK${2J#w#%z4mu^xgtGP=N#AEWy|S} z?{4mjPEei2+grG0PpQuBqg(FtRm%HasybhHYZ-LzS3cfnN-YSg!u)?iEEuKEGb%^=MuUmy24p`GN z)Un`wt;5*g{iIc>MdjROm^?614+Y#+t z`R|o4sNT-KR#ex4!@j@AwLV$-jdAz5h8HTI+4&xKO-toLZSQgS4c;do`ImkAfOb@uF{ez>ehy`<6HST0V)# z@=TnTf8w{g#Px#7Cu0?}l8fI^CAEcW*tW zI_=MB@2)sPkJEd~ws-3~s?Oz`yv>QKbHSu`u56C#oLI8GJ9LEVynAE^_m}CalY3P= zSGl?Byji`yJ9nn)EV#6TtCg=hZ`Et(8a<^t)4H^G>%UN)rw4X$@4cxyH9NF(Cx4Lf^@YSMC$1wIMkL(z9iZ1OKV$SK-G30Rj!j8e$j#KXqV}JC4j-eLE zce*#kJmRu@LkJrxrCZDWP@Dn`>${GdZi!}-!aE#9X->d)W zk}mG9-fDB`#4c{oK;^nmcX2iTtoBd4w~IS@l*-?#(8YCcs`6(Vb#Y%lqw<$-=;8{L z*BE|zud|!cMRf{X)5Wctr8?Uuc6J>ysb$nPle=V_>NIT9#T{Gf0MQxUV4qIe8#=p&CmbN_&-dSVaXH7SPP0B; z_xbvzvs+wOb-uf+YtZSK-!;TMHouGOcZKTQy|!!c_0!U>VeH2}(lzKja&5N|bKaJ& zA&2)j>=t}IFs@q|`w{ECue289HgpRyAM;kXki#LLcMWws@Ro|>O_?cCE1sG@vNy`HX79py@g^mKc!Q+{N55BEw( z<)!cRaF0KsT=p+L+|x6aKX|@}oBi!R`40sO$@+u-+6v0p`QUtI?036e8NU^}C=<`- zp~}SBV4O1XKl7|ImBUeeSPm>Kkt#=!S8ji^bYatncq9a z`R>Zz&f-6MUGFe1gTQTdUp zd%9hpseI(Bp047>8pG_-J>9~Is&np&p6=kKs*?=t=|n5UCp;u=h<~V-NenR zGx>s^u4!M@d8|uMckN2mxpS}gwO4g+Dc958{hI1D9n{nHFH%VI(E8Y3uG_(dBtOeb z_jKdes?OrS^mJ$Wxks+%WqP?oN~+Fr)q1+NWedsrvwBTWSGTt6lx(t3=kjJf-8~nm z&daCta!u;1PRFkMd^LUDA0v0F&KYg@>2x01E5tmsOfUDseX6tbrCz~Tt>=4%v0w4f zKAj>fdxeC86!=1liay+bYB$GyVbNUrJ~>ezkAzPU81c<(R= zE}Gse%$e#%`ngYQ=&`)s^>shjQvUY-zOHdS<#M(9x@lJ^PyeNl>vD&3v-kVB^4*j_ z9^J<+dP=$cLw(%q`N}u7?&IbxQ9ig?AGfSfVOf`u7p|g=eu+z!v9qp~GWI9*SH|y! z6P1bQ$eGH-+2Va=;-5QDnQ`q{pnUJ;{eryDuzo?m!B_o)otI1X5B7JT-#_>r(YAkx z=bS<4@R$te7yxK1_t*>jlTIEgq^mQLh zSNV10`?_*JtNiP6eceU(XbgL=@9Td3NOgLS>FcT$EiCIsmkav3ynd?FIosFW@T2Pd zIHj+9zl`dvD$v*UeMxl|_&M-kiNZ3*DYLw<%BnMNVITMScd9e#!oKds(^coiFZ#L( z)m5kBXMNneB@4^?Q?`xwb&2Yf+TPbyKU;O0tm)$(J5P10Ozi7!zeRPfI=Wxb8FFG@ zH>{27Y+l~ib#JLUub$m6_?pzNuRCdw>fBSMU(m_Fx?hO-^Z9+{-I63ki*$e_6xpdztb;_y+kYTE3L)+pZbNEhkV&Df7GjG=HA8N7p;eKImbSd6H)bY)W z`-Qo*^4)%64)pgi+ni}XXQ111qaMrE9vJA#-mF~i%z^HqyOeLyjwW5Q9{Qb)Z1^qrl2L(HuKOPk9 z*V#KL_+3ms9x?Keil=Wm;mw|5V2Wr1j zi-GR3LsdSh-axl*k;+Fj9_Y?JUggJnZaqR{sCW24cl;LBdHaTe?y56X#}ydpmP}Kf z{2c>amr@5x{HNYF(EW6d>Qv4f;GX|dbxLm@;6~R_oz)$@ugg_u>7xVOYlRP#^=DC5)%{8nO6i1~;?1KqZFRHsvg zLBZF|69$E`f4+5}PQONjLd+*s85DB3_nJY$*WPY}!q_jXJIAY465c9ktgF+4m z96c!1@q+IMg|Sz8#QREX(WtE!N%!W{U>$82+k@7AMw>aomu$T<%ybAB>murlW@J4P#WKJ(6BlsV67 zIaitUpA&yn=DcX{!9~LPQqgM4oJUo?dY}B#`;^hYW|T5^YUC^tFXulN59dV|C+ABRKj%?4 zF61^|^eqqAvHW1)@`hi_C-GRGiPQ2={8pE^UNC;`JgU<1MPv;@jxRfpD*Kww|KF?6 zdDM;*)h6dr6BI zz1OJ@=TU_gst)H-V{5Ap=TV2dt#rhx4e#rxuYliu0&# zomGePs2?9v9nPZ;xkYt2j~X{pbvTcD@L|>AJZkY!)!{tq*%wuZ^C;8dJnGv#)!{tq zgPE$sd6fC$JgUVvs>6Ad>2MxpF>@Yu^g7kyJj#4=9%Wd1MN%_YvGYz}Z9Wpjo-ip;Zm?6aTK^aW-1dER?fnf;$*-&JN`XwBEk>=zB* zs?0vp`K5GCV1KE?nab=(op!A<`%#xaxKDof=zaPR%u&Y9^-Gnpf5={C{LUy-RM#aR zPmj};iSx^>GV#~GK$&sfcCj-1IVNYH$Mo6%F+1!FnSJ()%rE;$77zPN7AN~o7C-w@ zHZJ5gUi2*w*s=Uz-|~iE%O~+zo{7`)PyAMwxLz=RZ9nSb1_#L+g&be3QSdq6>HPn_ z`s_y?dy(2?KkD2omD!J4eU#c~KWgz!DrY~cW@VMLAJwn5%Gr;au~K7TKdM_=7aqdM$Iz4M0Zupc%01=V3cYR~Jc!+z8!U#JfIQKrLw)ZS&P!+zAd zC91=Il=)&mYR~~iC1&=cOo#m_i<$kXbLupebPWIxJk%6^p18TO;B7VJma z++aV->d1bS%_a7uY!0v=WpjpJ&&~669iT7PcY!kfvLC-yrjJ&4oihEk5(V|xr|{mZo8NUn9Q6`?r z*C-R`uBOVwe^Z-O-;e9zdz9&mnVf!^>C;CuJM`DgK7BXyOFz!yp-*RV(!aC#>Fe3J zklT3Cw>)6S@`HWL8-6XH#AA6TPRl>>TV3LM!T4p3f?KyPDr*#sFV-lyXFd4lxXS74Ei9oi(ARt9F4dv0=O(ER zeZ5O7sSbU;)qPZlzTWk(st$dyNqGjk4c9 ztWoxx2)X@MLf?KvVaI-3Vc&jp;n#kP5s&>wBToD6M*Q}hj&a#{x!VZ+XM7<&$_U&%|l@Cw{9-Trb#u z>%sP054PWWu>IEiz51+CcHYh!W#{>42aDEpnl8fCwmSflLs1#6W3-eHZh-(Rdz_B(|& z%6>PoM%nK;)+qbE!y0A3zgVM8hc(K6H?c<9?>N?|;LER3_WO%9%5+$xEN0dy`yIy` zWxiOWZ0xL2ro$R#F|$Tl4q2nj7i*M_oi)m8!5U>Tvqo7CS);6utWh?0)+nn5Yn06a z)+oy%Yn0WLHOl4;Yn0W3HOl4&Yn0WIHOl4^Yn06a)+n1Z%v+9jy`g+7;eLdo| zz8>*gUypHFUyozl|5UOYxyJ|%QJCW{)yk}64wjHuboF(Uk|zU^+7*bSznJe%6dtxQP$UEjk3NTYn1i%Sfi}3#~NjQ zJ=Q4e>#;^zUyn7)`g*KU*4JZ=vc4W`l=bykqpYvT8f7}HQP$UEjk3NTYgF*%*C^}j zu|}B=Ym~*z8fASw)+qDE8f9Z=jWQk9D2tgj%5umWWxiOWZ0xL2RtwfBiyEG zb!3gQv9m^5Em)&$4zNa94q2nDrmRsmXIP`G7OYV=H&~;rj;v8Omsq204zNbqoZ;Hz zoicm$ zJ3^W3v`x&$Ij$ZfpnTOP1u`N6*B z4ZoI8;;}pvr{$mctuArBVEnR1!9yP}CcpJyeDPZk?t7~Kj`+R$TxWj!aJ9*G=KaPf zbDjAacdC7^GcW(V%DK+G^SvtPI`etCD(5=$Uu$R#Txb5$VAbI|^Q9lF4%eCA-B5M7 z&b;_bs>5~WoxfEbt~1ZHR~@c1KYgC+aGm+*KdKJbnO`tob-2#_*3GKJb>`P@R~@c1 zf8Yz%;X3mYe(sSgt}|cxi|TNld4nPc%kMa@Ge5F|>TsR8>2RI-h1FGu>&$CbQys1| z55D|$=3ic^I$URNI$URNF>{@HuiI3I>&(p;*O}Ycxz5~lxX#>S<~noBA=jCkFRnAU zv2&fd)q?BHEoQDWw;Xbvxz&;D%x&ykXKuCNI&+%?TxV`Mw(u|I*CO+OSXl&EdsmT|$4wS<2XX`#NRpKiE+j zzb6b$6UzCY|Ql2v7`ee2;_q&;#``}EU`{T?G_syAo?x!=q+-GO;aQ~gf z$$fbiKlkg|xRBd;(YHKc$MS=H%Nu?zpTuK%CQi#g@mpQudcpW*je=jvJy_N#7+)NB z@N-w|{QtfB+^^TisZH+Jd*NMW?$^6|pxWnty$17D&i#60pH?~d>up=Aa_-kVp|Qrm z{d)6XRUPivJ8-M&aKGMT9aM+=_0ITGb+}(|Orhd3F7DU6d6epKzur|ps}A?;Z7ZcZ z+^^U21J&Vvz20StOCGpi@4@3#hx_%O{#A9jU++(T?vX3**DG3Hb+})z#p%UmjpBa2 zoJ&-P`}ItR`}JDgpgP>Icf+-+!~J@}m%m?c*Zr#VwZC7_bhuy7V&;Cmsr^)k`}NEh z_v_i%xnIw8xL?m==6*fPA@}Q)Bl5em$E5+^=VI=EXA?Cl0?w)QA);9}Jy{@$DcGm5}M|G;?Ub_5F;d-5GyVu9v zCA{sUhVH~;TL_;v?>6`GH08eQ?sHc)QSLJ5VRvGs=Ax7H;1JimWHaIH^&{QFYE6aX zaa}ZLLH;vmT`6O^_qp%$Pi}gx@b-r`<==DejlyR&DeS&}{$}CHR~_NX_PAYm^a~Z; zwUh1?zUim4-HPAt5?9jbFf}2kCeJy7f2VU2Q7* zYfBDu=<{FxH_YGBgZUhvhp~rUIGzLX+?ZadqZ@YdB8g}IXV<&w%~lIP)~Jq44lW?` z=e@R-+D`H6EC=kOALFGaRcIkDfu-xmVoH}=(F?N0YyrD`I-z3Fc*sZmwoVtjE4*XG zZ|j7UwRbB&^k>hn{wc`MZmaVU{ShafDRS(r{7@PD zg>J7A{Qh~RGVv_DqNd1+^Xf6m#NYH&WybZ`_sTWOtPS$5-F^)ELq7W{*qOU`oiqEb zifjmeJAAVt#MAPDjUmoQ7HxDE|Jt1!!?=*!c+s~!V8`-6pl zm$)a}>alrAnI&%8$!Cbp${zWh}g`?V(2 z5IKIos$Nr=c&?kGOq{3hRwn*8{&be;Fs}CJDKE>c4e|zW{}}Y|uCXrIIkWrvV87ki z4Z&}_ej7tPC)C^&;yiEkrV#&gb2f!>A-D0OZ+XCu`rQ0UgrGsEjPJ#tCS}`vC$3f zRzc)1?%d$MKe?jtz>ynV-Nnk)9@yaOJYFftvki5fME~i%%GmjFYUN{3{A5m^^7#DIIFZz}T>{x!VZ+XM7<&$_U&%|l@Cw{9-Trc>5BKqAF zbIn@Y{e9djpa0@kcTq#-sdcuv<0mMu+_cG!J*vFS?J1vcbakhsyk>(N+pvPjcV;)Z zR|{7Z{$jy;x9S7sHZQN2@p9ZDAJ*jLp#SbkmDQ%Vv-s%erQtxv!h)_sfQD zpSYs;E1y1it~+L`@}qS=cEh$SUvtPuuFS3az4L034_))+$}d*`!1d{@-!HEXd*6Lg z;Vd~WhSz-G)m*52cIo$BjiI%IyvD_63#0$|Ze{E&om5-o*x#GY5ytNobCii^LDh`N ziSzOYm5Kl6XO$V(;91H)E}9qQ&z&a!gQ(~?={}cB@ zX_bF-@myE;V&&;yf8>rFtGr?0hwh0Z^gC!;n-APs6I1T}z8ikAe(x0g`aSo2LH(}z z{_gkOx9=+7*YG_VFY^=mfE&-2;|Try<7*2~^L9S}DrIl~%&s{i$M5_S8DZkNx`#4x zp0ZGx`16V}wsA)c?cEevt~ z(qvJH|Mnh>!nlyzc+s~!V8`-dW%;A-DC%I=T zDpzVY(apR@x&M(9T#bp!4OfnHuOFhni(mMDtUKsYYA zW84?L8;ZQzy3uYyoy&xg&)=bp{+Z8RE^_R2zxoPc?2r9X8NVCa=x6&F{NG#aptsp zDa1eW(U-!wklT3Cw>)6S@`HWL8-6XH#AA6TPRl>>TV3LM!6RS3NaknEXFWH`HGE6u z3r?EozTctz%=Gc@m4+9K{>nSXxwGC>p4won`{GL7-A_vsiS<~dAW@jeai!OEI-({yy4gKNj#Qk;})m3bTUxW-Spfp@69 z?t)RS+$iNEnvQhaHYi_p)CkwH>2>ni!+(ClmENjc>d+_Ly`!!d`5m_pbB|nggK)iF zkGuRM8woG^@^Kk2^AmZ?=X5U-{ioVC79H%oeDY1g*gyOeW&BRRsfoymr~2p0#96em z?n4s)lZ}-b*X3=LclRC>-6n@PZ(2P$ z#Q)C0Q^L5A+j!BpJYdK2gMG^zel4HGV|gY{%Rlj3U0$l&&lSE#=jY3F`?#8SC~v&; zVR!y86ZP_cqa=y;d1JB_6v&K8yXTRdr7lznxxGCZ0V<>mDg_KG;l| z_#YXr%(!MvQGVg&{z2a6=m9~$X!C)=&IKa}1^X+<3=V$RcNh}lSy6Imh_i6Jp&|aJ zj}8svLT=+l-|~PR%MbP~Z}_!*5|8DXI4%FgZ*__51y|gp^ET!J&-v#k6x6vo=A?&R zi(1MZ{I&7*1}eXNM^87WfbP||Z_vZtI#jvcP2Js_wQiN;qVH`Fxvw@T*BjE!6`gUL z$lG1iO~xz7otM9Mq3)%lzqZJXrVqZ(7hl$lqu@An33Ccwn&eLYcwA{*Px534VV%acGEV)ZC#V&iu0;4e?iO z^k^6tavLxDmIv%uez0$O!>{F&cr4GvY56C9t4pC}Rb15_`u%dyo=UD!5&eGY^QQ`4 zU-|MOC%P5AmA|NVylcKu`H7Q`b2HoP_shfgAL|w#tjFfaI>)$5GnB9ITE;!xOpnb` z*)p#833_ZI@3lx7{pADn*u+ltntE(v|H`?__#JnJ9-G8dAy=6=#}?J&l=!FBR%Tq^ zU!+{%y;Fm{`{UJu{>+-ygPk*Gx4hxk@<}|FXX3Q{6Tj6Zt`~gqWBUCP^VFG@+;0P*RUg;(V}~GVvFGN||xJ@q+R# z#ZL?JipQN1^dH<^J=odvM9pBo%NMnR->y??hjGx4hxk@<}|FXX3Q{6Tj7^wO^kPzrVVCzqHvq*qz%~`9;4DU;Vmrsfz}>PY%?5 zl`s4{eAPY5HA_9>#&1CF+lfNYWaIV52>kpEJvNw&$U^t{QB|zTQAqI)dF*|)zk@sF6L%(&kFP`TyuM}xfT zC65RF_nsUU>=gR=iC}-?=fi{F=ckMa@r3-OAmj)@QPBp$8vKg|6HK2ly_X$SH{b6hy3l9wIl}g zw^!3WmNUGagIA~Q?YA1Fdo1`ZUQYK|h-bi~%EWp5YGvZzT2}X17}wO(m5(j*Sde!a z{CLoxx@TCh)8f+M!TvKXM+Cpm{&{4G=eoTkL!6zOj|%ZG8!#%23%QLKeai!OEI-({ zyy4gKNj#Qk;`gn~%|TfN>2vMfr-{u|a;= zN#le5^X(=CJ8Q;I4EFmyGb#8T+I4b>r_ZrdLYz}OO$qTI_|%jzF61^|^eqqAvHW1) z@`hi_C-GRGiPQ2={8pE^UhvNLy7wOQgc(n}7t;OtdZ+r|yt7p2sJv0G^kKRu|L3+N z-4nf(OJ6a<)jZ-akD!xt*06SKC3#d%qnU;r?!gyP!ykAaC%7 zGWwI-A0l$>Y(4f+VeFThp^V?#Y8@tW;#oOPnK*CVs7(CrPADlljBDH(%GsV9f_(Ry zjX{58&gNj}%NARL{d@1(8vJ%`ur0*XVcE72=dkm(JBxqI?c2k+klT3Cw>)6S@`HWL z8-6XH#AA6TPRl>>TV3LM!Nt?(9>hGP^H1)LM-GxXfBM$7?n-|jI&-N|uQjgnkwt~; z)mrVQ_E#==^eT7ZF~vk)u-Z!Z%p1yo?zzIb`wtfR8ON+}8CKW+*3I~Cg&{C3*1%~?EE#%vF9HauuYh<`@a9bsI^ZM^7P9W2dI?t#Zs_zx|0@gz;Od@>XHuIcB#qah4plP2|M?r(Md7YsfL%MPBdq9YJ2; z_?9)Iqov+9I66`-X`PbmLd#BwYp8Jpf%~_ly?*GkM{9M0e<3euZMc?v(9m@~) zEpPa>d=ii4nK&)~#BX(p>jmHO!g9IpDCWms-s>Su|gZp;fD&fLS*SoPfYlN?VeVzO0*|owoE??(PJM$;uxmC4}d=`1X z#v6kEPs=w7W9P_gHVb2a(YP(b_&sXQR$<~f`dPm=c{{}U?ls$miGPh#W?WY;Ro?jZ zjv&AK_MJh$%luuz&N(Oi8tiwgyF2*pR{6IO&uI&Oa~9_n**zit*KhH?bw59e2f2+G zeai!OEI-({yy4gKNj#Qk;0b%|SZ!tg{G|(pOXe-hZ+qs~!hJ1+OXD2dtdz6( zn@la`Y+T4~yy#mVuw(hbzU2+SmQUibJQJtopZKjValPQzH_exM5_7fbzvdrbdV$C% z4cVT5URUK`Ki!zWsmd23-}Kav`I}08DZKsoRrzOB|4Qw2T9&`1>q6n|+$H(PZCE7y zQswXSyWO`~_^>CxlR7d#k$*GxyP#jE$`awN-p*Yke-Org)s;(y@!O)Xt_j4`V!bkP z9z9Ce1maH)&^3W^O{k=N#i@mz$xCMsa;D$nxPzV9+3;!!XZBlfJJgxqHt&^m7S9Le z4tEykVVe$j7XOl3M@StR7jhdf`j!XmSbnf?dBd;elXxu8#A*2_eya=Dj?Vc+uR(1* zdAm!lST5I^K3R90^DhVy-m`v-8(Dv~@SAS4du@bXzgqtFO|I5oHi-P#WgA`94qJsQ zG}!1yy}DDlkpIql^2$BJliu0j?D|;b7i=ml#}4}MyMu(Wv-jqMg|YwO8zqGCJ9F-# z!o>5zeI=R`{h|Il%lwXP zxF^IjcJeFtTwEPpl)g`VMod41i zxkfkU=X-8>b!pnEBm+>+`kxx16Kslz+Z*@UY;p4oWIVTra_Vydh zIYb!0Z|^xwn0VfvS4x;TPpEQ)F!4A0MVWD(b#7^qAN0b`Aa7Cgm!Lmv(yzhJ^_zDG z`%jeI6Z{U}wI{?=fAZcCXU&5O%(nPfmnpFCx@9l7@uF{ez>ehy`<6HST0V)#@=TnT zf8w{g+}&}a8{@AL;k<6|<_T`ixUn+E>686=#c8^Bom6GLTQ*GB`B>ht|9V&Y3)Pv{ zYl9niy{>OZ4cX{En4#Qw@+Q}Im2&Ahn_aUF%5N>&;(C6p9NTZSb-nwf>Jo`(&HN4S z+;Pg!zPZu$-=bVDcawYT1pQ7N_}XT-;p2PxlDY=XP_r{Q9!^yA~*)(s)$GgVKQ^KQ%jdv$r@wD)m;uGBMSC1C1@Ztp5yUrNl z|157eHy-cK?>}5}xb&-WuD}Z;gnxN>oI7giNa13w#<}+1FY|VBpK&g)$y36k7L9Ww zAA4GOS(EW@$19_SKRkSbyE1=_@Y}a+bDut;c`J9-HaGlJ&B=^+x4MtNQQnc+>b~Bf z9Oop?`D@>9b!SgdJD1(K)t&T;@{$shU5)>buJexT@%#V3?46O2gvd^c$|@~;(?CYD zM@n|t8Z=dAMMct9BBF;qvNAFvn>3IS$^Kr~dE|Y&e!tJnfA`z-bzbLsj&q&!Jm`E~E4((aY17q#Ji|fjMX!|x6onI{xWu{h%MN0Nk!DsajpwgdZg4ZmI z!G5O|f;AuQ$KHl+f@jazkHly0f`>QSkJ&d?3%*$pjl;Lr3jUQJ4fl8J1ph168zW;e z%XP8v!;P>5XdvxDmE)M59D`TamkJ*FbU!xFSuS|C!G63oT`AZ)F&bV2+yze^9gPU* z)q=0Ij>f)&YXzUuiblqdb%JG|-xxDQu-NT!s95dOX4(xCm|(lz@v3oCQBMPsHqMPJ)#_H)$J>!7+TD2GdFf58DhU*Q{RD!A#sGT3f45v(2e1*h(EKUZ?#AzZ!V zDCCBrshBuoy5N+Q6g;dyL-5AjgSe+QQ*gZcL0C?hB{`@@aYt3B2 z|B7AF!b3?>I5A7xxz`hLKQ5Pfm25x+hl%B-j0?6QyWi82x#(Yh34qNQh$(tT9L z^)qsN_YwT{Lk9eMaNk_L-WiD6VJqZHpDcNqhMoQnLSEJK2nubd3O>6r9kvH23qBNn z6xeGo_?zc3T<3$4vlP3ut-7N!; z)h7y8`g73O_vpU3tEm6t=@N`|=q$LewBKjL#*Tu6I=q8JQG3A$q;-j-;W~mls=vXo zn0A6Ee=Nf8y5v9S3Xzf1R>&)DFM!rBvW@d=9Q9_Ib9VX2b7notnC6F-puM`T(DO(0 z66o~nBG^e2FL8?%e>dz+4sJD(|p!F2MK zv;uV8L_U=G8UgwcZ6>^P2TlgA1^d@}<-?5zbWeWKJyS&ve;0ku}4^#;aN zeb*{HC}W$kf4Uv(pR!$jtQUe6ohFI;FH{P|)=0Lc{A?eXj~g%KUAIVM`(X0fNgHr# zJAteyfEcBd7}OXT>im(L8*`9 z>mA5=#P(nMYbTC*uz%_Pv&^hxi$J(y8xvZymBFamy?>;>=M?u@0`^pEMHMVR_!f{<@m zwiu_g=)>F{OR?92<)2?zj$Kp91s_)8mKOP6@vRxV5C!!o3VU~-aDm|j#{KheSCkH* z?Z>Ar#jI6c@fv&aWG-VD&^Zcz{1Lk1mc(T&ZhO?b8(wRCBtuY^JPPC<~*BlJV=Czde)^v=< zh!(6zfAoGB71;-kb3}?Z;lk@x3-AI@3`TD zl|Iz05{*kIc-^!2qp>R9TC@SnZTs=bo_&agaSWc{XWyc7JO+I`u+LeeaR5KYjTGhA z+8)5`Il~2Cy*UXFF0uSx`ze^#ob_~3cYtFj)*tz08caTtZA+%3$pY%|FQ1P{x5xMw zw9(ULG8`t+_KpryQO%z|X}@wB9xdQl=9D}gu4QDqqen1h3iBWRHtE<>r@zosH~la& zD)Nve`e_)ti+PC4?o_C>CV#A&f)-uLuU(Td0OZD>60zq7bC?T$3Akp@I{k*nqo*D7 zpP#+sU~!mv(ZWfwIO{l2T=!On6r<71IhB4>#%S`~!`N7@zlhh#Drqp#V$N1~ODe*X znX~n6mV%QR{Mq4G}P+$Ic$BzVbi>2+q?!@Dd8*{=LxpCNkz)IA=rEVPh zv>GJ%^RignxyjtP|4?&`G&d4DpV2duY%~^Sl(A68TIuKfJL%}Y!CaK@Q{xzN`t!Pj z2V@{2h#c*C9K)89@18sX-#0A3y&w~7%KtZB?OPv(Rs%DkPrUvyxMYy`jmW^p%Jg~C z{NvCqqI}fG6X?E>Y~_~;-EEA~i%ll@_Kf3ok98(Ebdlru@RKIk7|WdPp}8qKt`l5yO9;7^eDSgsC$OQUe-s05E1Z(y(4^is#-lz~Rz0|~ihqo%i z^YBK3N4zM)n+%?x;Nw<|((w91e)VNB%B<@O)@ktuI-hC@R&DhLPM$RcFMMB&%B`yj z-s)eB*S9MRHvUgb-7*>3NT?a*Xw4QyhdK|7a@;p zkdNf4p9N3MdkLFzo(Z7z=bTg0f6KXE`YfOj&o?y`KK$9Q2ni2(21U{NBE*)}6Y`hZ z#V~zWNAM`?Vm!H8OK`SbF=C^*mOEHivUhbgAuqaHgmUL9f?HV^!Q4wl@P>p!Tn_&u z)`w3%D?t0WpMqV#y@t=g?}BUo%*RVlt|xoGe}#y}Uxi$@MOq&etkJ_9nMu??c58q1 zeA!sk-@c0}v~8LQ9{Hyqc79hEY~QRO=3Z_l_@#Sa%uCl0oS@qmhmU9q-mcddACGGZ z4qe|D`!ZS!{#P4|pDf*HlenI_%HI@G>1+=>%lo0!n(gF#Y+wBBsxIQF8Pf-LJ(>xA zRMs2o?KK3ONAyPfotlE@MD@m!JT1W%(tDN8P1^{T&&2o}N16ZnLFp4^td-?6q_v99 zU&};$ux&gW%U=Bv+_S|vEE~dhsI)~{|D9&5U|FAWaoI2%-xo2C8mGqL`jMK#Kgw7f z_L+i%gLVk{%a>Ep>g9H!zs3)Hs0FMN9K3M?62@;3+<(Y;9P*cPTp))Z=uu`8U36rqe&`s3e?(-zPy|i4g;hjmyw_Pe&fA}O+{_HCFjg$|% zr*N&Kjx=wJ3STJXO5Gyb+T&RMN^z|RGwgBt_;SH^gYA*xw^VR`_C#1nXWq%WefTi} zw`VRAJm>CseD-k`ygkq!Z$csj8`qeOo=^7(zHL4QGgQfkjHe>F({3TZ@nR|*dV~x9 zYU+SogD}B`LmXh$EmZL2Dh{a8b(i3VPE)bWV5i`J#jc0{Bv^Ed6gC#)^yH^if)cU-h)X( zZoFnFy8ofQwH6G=C-*2JpR{Tunr4%CMvlhBQgZ0!u}CW>YZglNA11eXXN%`!$c|UW zqvQhX{Fgs#Ck?^WxF}(-*1ciSFx)HnzRpN!1d$*6j>f&?`Dn9bY$f;G?$$#bMRhGfg7@!hbeG*+(_x^OlWZ?kc)`yP>cYSxQSiv0-EiVolHj!K-4SehP_Qz-a?U8{jr)8G&YdNQsIqr84X`e-g;Hq|pczEQP;2#r>;Be%q;A@qQVZS$B@ZurH zsN{J>@cpjF$eDRq@XaJ6%ovd-xXVpLG`2b7S#512*?U$<=hhDY?C1<99^x{$st6I`pt$ht9na-XKk|wt+Dg7o-Xv zbKel^xhaC>yj#w{Wq-=~xSTV|evtEMIiHqU&adS>`~UZqG8S@f9wg=Hay@d+F6Ztt zH#cvDB#&$2zdh$SMqI7yLaww?>2sw%at~eRp9ZP zoPD7hcH7<%^43;0;kJStcD^>6PbXXUtOw1eIKQ3$HQLz_Px4v6GS+hLEa%X& z&T>vI=hiaIxwf2h%PiX^=hHGP<0a?Lat|wx^ol1uw>6fCb-OUm813 z`t}*$QCD7fx2HAE-Bl6SO82$KNMrKk_SSeFT1m*)jUNY;anF?eaPL@jmCp5(b*}qn3?}N5`$}tv8yx=# zKU=wvLb1nh!DH`^fOXa{!KW(QV8}1N8^77g7WtdVw+-wNSd)D8qLh=Y<-7Esr1kYS zrF`H1+f6&vn?IB>T>$medVkMav-&B=AqF`ukz zRT~owSbnKyYdpWEA?#{urHyrO$z4~r!^qF%X$kGo@D+L4m5#8;Bp<)n88z0BR|R!N z*DmCL`D*swR`}7Sh45S7y4sjIirmVx9omj3U;W-*dM-e&Yu^czo0CUw?Sl9m`n=_K zT|8Yzu98^|VYL`Xvs%@$<2voiU0wqXqsg6~*My}DS!uh{x8Z6v5d4CEHk(ru&r`{B zOKZbq1?_5YQU|jh^14b}>U?O1s4U838aIMo5?Sfn8=act`b^dnP^S^Bhme)}&$h0D zQI52wznThWl#n%>|IR#C@!qxFuJ4)W1ByjEi9Gi;^Za(cgFPeZOXji5h? z7swxte`d}%;{DaM^mnFxD7kMV6|{a&-kVn$!3OkOiz`*}-I1(zt2$b)C69k8#oCMf zuh_{xk#&>DpdNOgGZ#N3&sg*&Gk;z)AZ05NFwk^hjtG6PV7Y34f`hS4Q@Oc?Y5AU{ieb%g8WFu z5iM7eOB`mPv?ckJjR!1;C5iw33D}6C(mN&ceWbKe=}%9!)~J5(g(&0St`$x!eJTE{ z)J^FVW&PJDc;M+^&XFe?c))E)g7~lJvyHH~<~%xj)<(Fy#0hz~tPQY>jujkJYXi=F zIUv}ryL5KSTyn0(I<&1yt{o_SGv!i@C^Ob~6+WetjW)Ys{VlTnjuj|UXZezI%b@2; zHql&)Zq0eEiHVDmnoT~r#ufgN)JN$b&)|&+wdEYy*kvO;S0o6Zs7l`_owASf=*Fiu z!1!^TkPkN8fWuwLVS(%MDkN6O&)!~#W*X#HRoCJ2nFB)JY1|sP`;(7I-(ZSgLypaH z!?|r_Xs<-e+vLH1%TdXI_2ji!hC_$QpYx<|H;m?W58hpjsx_!v`w|UwYVlZHYnF8G zL7>4C!A(cDz?%V21qam7gxiQ`f`ipt;+FYy!Rr@mp{^#|z`xqV_o>a1Tl=wyg~PPw zxM2B2@WQLj(PhO`!5zXhU?1^JaO#y7sG9m*@R~6#;k^Ha;Fsw$aIzcQr~Zx^c>IO! z)2_>GJgeaDN9Q8t4CU6H7hums^3Np;VR?=*n!d>ePJbAqE_SY{rAAizL>cS&IJBDf}4|fZg7^~4`h2TZMO&~L)f0ZRW$H)aW4J2z8PvJ z*B zU!&H9iu+o73i6W4SK3U%LS3#$*^iirtXt%hDdSOV=Rt8@rJv1rI>MmB&uyglN}^gM zi|ZaeItAu)$ZOtBg4F}E*)V%lUcfb?+=mlTttHp=T3y#f73&R)%LYO^&7W@{?)o@K=1Nx!IkPZ zhvm~8!L>&=lg<{qD|k&=Qw;2XPw<@@&Cq1UeZfjUDD_v?ue9Y-VLGguWQhMhD?5TU zGmZ(q{N^xDKjPZXtn4)St|zO<96}!(@;bLvl#VAmj!QwfA9+HrgLqa#KGHoIMypw; z-K=y3ByuflQos=$t51FraTuQ4jtT!Xj!J{N6?wzXL-5ojSNBiF{Z?cz&lG$eLB6@^ zAP(;*FW8-oEA3ck^WfJw)bpjNbF*3j=IrMEsI*t9&){}Z&^2Kj^I8~*F~z*^YCes? z>eUtPWP1cm+p;~>-Vp))8(cR#@GJsnm!yenby*aNpc-6%n_v}%OYU5k`#EkemR;m} zUGts$Q23ZScda3<(PmKR`P*ZpcS4SfdNljQBJu$FZGIf49wHC%Pe9RP^7*z&XjH=g zDs5N#d_ZI*nx*g_*)%y4nmxJBR%=QmZiDM@XQLt!XU=uGqwS@A<%hXmSE(op$+fwr zSNKBOYtV-=ZCXz{$Dl7`dTq*n%&5-x(;_{8%BzmcAC8=TwMaFY^WeC@VnCeD1k>YFmI4 zzu12M)t1^xzc25_IYMg3eB8WOBJLf}{;$!}iX7j&0D&Iwg#3qUA$IS6D|kYt^sIav z=O7Py7vbd+&P`r=6ycRcktkymR)ol!oXc!pRfL8&IL~$LR0Q3Kd{M?!nyW>ue4{zIam;lsRQob(*V zY&CNaNZQu%Tu3=*L-R;@zl;%ldQAk@)FR(My9XM>xc>hjYC8@N;d;xO8{6?Fo@+bG zSSZ_4@~GXIP=(J&Os|JyZ|FWzzp_rHEj4ciVr)6rYRtW)vsrF&4JTo85Og+kZKv*- zV4SW?9VSl*k@{is_k~+=a3cBf=56Rch5Rp_hwBF7)I6?7S(OK(!<0WFj^0Jm`D0CJ zm)7?nB+Vjs&<=rR1X*puR+NEUv~3$+oFOai-842F8N>LT$h=P&exK&^qZ9Q*(Qr0- zdhSlFFe8^m?7+~GWYdM)(RK^@&aiFhRF(B8ec04c}@9;P~37O`{eI}cW1Ke z&7IP-5Axa!>0B2z@}^knoR(4KzWcY~N;>(6+9s5C<9y`SF>iEz_Eq>q>8o4yq%(hV ze+YSJKOZdF|4pzmc3pS-!+yjM5$mN@e9^bsH^CQrY(e!OY!9w;x4`)XpD~>`2*!sl zDfUpZg%LwRWcm!k%!>)$6$Tq#ra#EP$9duE1J3W>>v+R+2j`go@`=j5jYv7jd1BvN8?o&z=Z`%q zd*Fx;=a}ned!Wi#&OLkl_Q35qoRfY!6H#r;0y5=aP^1^h3!t_77FJ`eO7m_8U9e`J!GO_AO~eKA2<0K1b>EOH%^TOxjZ< z-}}Gk1W0=l$%6v@(P0+v{Ytrh_$8g0BA4-$&c%9S$bO?%zAtu}u|HXy;)`kH+0Q8b zuk??yj8dN}iyxwBWka#9;{N3!d@eK;>lNikq#XYk&$3w8<0%F>@k|n>JlFdfwvJ?( z`i9T(=nmIfJ7zq`lab`J4PKz$X|A<~^?redUC9RwULa#T*IkwMzm)cY+12N@d^SHr zTolhsS^ei3YIG(a9`PI->-rpy?a5!~KS%8-t{bn+zYT|*wCmON9E_~hNZ8o^ z!X0eVBM-Q67uptN)vSAnGb3AFx-UH^A|K1lg;r(qs=W^oaFKQX%WuVNZ%g_#5{jeCOJ|2a>7t z-c|2VH;9}poo{0iPWHVjeM{vgxu8KIUUlYklXUmj(sv)o_nPLT-cUY6NqPSgU#jt3 zmydN`Vp1;Ia`6i^JHfSjtEQ7=uhrA z@FManldT?~LB0-o!xrG}0dmaR4D|72dsD{U-{KScwxLhr7M9|hA=zv9XS6jSx4-lS zIZen(FUxTGIeokR%~#Bj+Kjx0StPAvh4muO+xrdgFY&q6sR7?HaWHu&zM~KLZ0l`NZK?HfFslgC#2juE@7iuRvm{vGu-$nw53SvR@QjO>|= zx(^ul)zY4?KFt~nxlyeYv>iZxTRjzrrjS?HI)p(p$Z@sPaMp(0yXs-M^&snfIE(?m zEBc3jw5$6UlF+d$+t`h>$#~;Rj=g;lz4nuDmZaeR8SzDVO zuCC79Ox}xX@sQ67#EU@j`}QC+IV997=CI?wp07$4<5t!Ec7=aKii zs-OQZ38tx( z3)@rOKVaAs^25oWP;JTo`av0sRT}S6XwAH+_k|A#YR4EYmChd+m0H0oLh$4~@7dx* z!Kk0k{zPfxg>0N{qiR8%(3b8SXTwq;*h7ZU}|AY>Fi)&-)E05`KFh+WQA-5A7 z*J3Q&MGjq2gwn<2hSL0c{}Qs_h5~F3BM+Uo6E)P?{|ukJ1E0*vjizr$RS)vL4boYl z56Nohwqmjc`!TytThTs)+~9Z!`t_ylOaI~9{rz_0>S6Z14yrrwGoP&WbsN6xv48&l zV=MM;AsgvzMb~QV&#SKtfuRq1#?N3BwqPuj{!!Ycyq3~No45YR8`WL(MfEfTajqq~ zo6#1y-qsWHxduUK<3b)+D;P(g?#nW5R_Yx%}@Fxu|!Yw zY0lRJ@aYWM=5ip?){uSTx8RNR9W*&!PV<7Ghi-x=R0&3y6*=1_7@4Pag*@b7FcwQ^ zEz0EsTs+YKt9h2G(yoH8ez4j_yB16HtS&Y5g`QdJo3Ug&dF?%K)UWuq zTEZPKsMYKt%Is<8g^y3k2?spkd7fvh*6{R%%|Sy^CMneu8M}D4s?y%aPkb@Xq`S~F zzO@h3(#WH>Y{IVL`a-VL+Z)~$XZ9Af^Fm~P!wOrqM&&%9fLdoZb%mI-P|)(|a41pCBIz*oqMw zy9oI}Ngw^mJcrX`p9iu-`v`sJbn!&Zj^vkqo_LnfTgY86c*46AIXcG^wiVxpYJOCT zW2;`G%)i>z;eno*bEl8EZov~zJQ_z<8}5bdES`(&!0!4TIz4o_6hO~i#2$-o}AWX9V+)Ew|c)09q-UTNwFA{_hC=dl_|Se?^O`1Vm?5?VTtUp!4hz5KR9ez|5c2F@gJtCfr=FSUi-{6!MV zE53(#DkKSUg>8h~uf`D!zSVMBHFI>r_Pc2800{C{IBU~ZAn(fy7L?9yVAcH zqwQtWrDsEAvyn*{agy&>jP*~%ylB4r(fMiu+|yeK9k!(>!17j0!CIpe5%ap0V5Oc) z{}cx$V%cfFNA!7hBAQ%nDg5@LQ4*HlY$dq1<48Q5-A~jrMSACL@cb^{i9oTBBr$<|I2SVl}BL7j($RiB9oEOY{>Sr z=kzEvT}=*MKL!_b$tugn;d2}M^F)vh9@&y{$qt6g$ab|S!gMWJ>Cb5!laQlF-=_H{ zp>z-5Z>c;x33{qzef1>#*;w&zOjsh$Rw7samVkYm)PBCt;l}(#=}%=$dus&aTpHJ`79|AXX?3naDeF|)a=d9z zWc=h9cPhsKnJygT>b%s)@&!(Eel{!8bq zR|dG6$+7J1N_`wRP&+s@|S@*jbf%m%|}F#O@`R4e2hO%|bsY z?e(Y{gxRxc`W8cy8loBj8J7T^MMoP(%!&Cj)`3#^hMpW_M*J&rhbUfXMej$ zr5|h-uwQLDxDTeMvHw)Yy1}SkC|k)qC&IZeO0zjWHgPmT>zW)B-!(PG2?O@Ak9ATf0VHpl(H0E7V%oGDy_n#U~*c=^?16JY~9}jlQhZu^u6)gyS~t^ zw0$3(HP;lnb;|FB_UYtjWzyajqn1Mc!_gS^PmxdS8l!lamXK$RH^%Q=a_kFZ7&$Ut z|B7Aqr(V#ntSPQL%f}f09%Rq8Mi`>TKKa=LLzpI!E%q2fMY@)}PBJ~)5LJrE&*m5* zZ3FvlrJt9#bVAH~+7%oNSL**9`b_Dm$}&<``VO^3sL^0ts^=$b`tm^&4Y zy&L>b?85RFz;`U;;*~NF7)l~v;cW1FLzhyS}oGH5hwif^W^2QY5PGpDUrZ9RuPRR50OyM?~d}fphZd@5F zB3t${f%|)F>OaW@GZvEdyPIIyyKzG9akw9{ zoyiN{_QkUDu|j_4Q6G%gqZ^-3i(6LE(q#NzR^|}do;<`4fHU+Xo4tn?rwLe z?jtXsV}PJxNzhWtPXB|V#JwHHj8#8Gvcr{4yfzREM)ncgN z-v;{FHh#F^;ol6<+h?TU7JZD+IC8XLrGJ!hDc;ftomH%a4wc-Eu&%bKth|Lf&&&F?!rNZv{w_!b-3ff@RX7c~zw^8QOc?IU8ekUgjG_fZe^|r*U z95W%Gn{0_?1IT(;EOF>?e<6S3Yl+ZyHoEe@VsR!hbg$)tii81X^O%3HU$hFMW zVeUg7;oA&>JIVcWHQ*IUZr-dV9GuDdBidujP_D5gm$XA?H?DgqeWHv-gX${CH0Qnl zFt93qZeqVtqogKI9JBi$A1ZB$Q~#6cHI03gk9HNzOJ)ByD5wUO6xoUPpw!3fV>{?x ztsJs5SHkkv-kDpjw^W$3YVv^7Mp_v3eRvyF^y`-V|2X$OEp_z^cKc zL>aAb)!^n!R+~^2L!Ob#KUYS&75jvG_f*g}ot#xgMaqT7i2v^0SP7rf$R*<|A)`0@ z)yp20;C_m%jD^y-vs+2~yh_+7EL5+Ce!WKtU#+mJg5EpHkw;W;s3!Z0K}#wj)0-U7 z@K0u~Mq@<8Ypy7+Bi}=+rwGv zZ)M%QJJ!XO+T^A>^`W|Wgpj{XRmGW0>@&5`HNcm8gZC#X|X8+t?r8e64CpWUMfp@voQ`sJ(Q){F4 zBaREJE$dLDUbJ-{Ib>+4l zHU4wv=>z2I%fDnA_h!z}X8704hUdt4u71lrY0ms%Xa3L3@2TV!7M1X%0o&x~!IkmV zo~-n_(q83tm9{&*m;u!$9CLM=Oo2{c^2Jql=$}XqA3g?eXE2Yte0UgwrqWk8pAAG{ zg?~)SEa35-e%RF53;|wjpW35L5!03J`AWJ8%Ac~G%krTiycgv1j=g#B$n`i~7$y8K z*FUWb`%L+|4i4-mWqqpJbIg+UJk*#ut*rl553+36^LX-+gY*BBHyP~uU-|wkR{U2_ z!v<^qtG}A-`v0ywYWBwe^oh&$_)pJA$36ekzh(`u|Ll_Gf9;ja|Mi1h&tLz@_5byo zeBHnPl=b=RXIam`{+IRt8y97~WY$Y%4yNRbHzwn9F6G*vZ82jc^S3;Y(QvBI-1t}8 zP}FbCws#?U047sYj9CzgFzDVR)BkQvUq*&?SJ*xsk7m~>yA+K_)niHTRs2NbL(2K|Mb6{%{a<-$@0JU z%H{w1L9XYof8_fA`c1y>Uw_K_{PnY}=U@NJ`u~kfQJa-$qv0spxlf84PPKLvzM5Qj zGoII;EO_lWZ`7?zc8m1HeLZr^-y7kulze^J2E2Jl9-y`!rIV+K|HhwO3!@+8v8Pt! zYVuSe?`^ya{gyZg*6Qw#sDaZ2*Ke^I0}o6R`lMNS!z-2?COz+amQ9|NB3-xnWKpJh zy$$HA-XHK>1r96Dzemb*_C@^$CkP-T>Z;9c=6;oNc{Ql|2<9?`qi0paOAHSxORWAmh=U3*v=R*QQ4PmgsFk;8W(VBLk#orsK%tP6gop{ffDKmOlaUj|UagD;!EfAa0L z#vg;uaJ`~?HzyoxJyXQO)yNsY>X0?NEP~3*8A2ZO#}$`j$YW!dAa^`@t;RBF|Clby z6b)aFKY`@u#w*ZLgS_eP3b=-|o&T%N$Bb~o5RaL{|8`rQ(a4Fceqj+h_b2DxS}dI< zK0}moPg)A6XtJ7g-4%Vw7W-Df?c8)x#z|^pi~E!ROmsuqA>LmjvNyx9Ci|1-_M35S z0_QtQpBz=hw={JKjK|R4mJT-P{+6t7J`D%-=_{oVmA2d+Is`{jsoQWJ8+;#0Tbz1K z!^&-Br9QpyZi3oL_Iq8kywQFW`GEAEZN_Z!TIsp!_Q~W!^F8o$F1gRxjo9r+&L6k| z`_7X)jb4w#4gS~OBda!HcT?K#?&pnVQhzJwMg64nem7nrs|I*t*%@*VKM#0cBfs3T z5sTkc$oFo*ik7UW;KF)LpGKacZHAm{yx(i9N^|_tyx)I}G=pvqIsBO!PLE;R7;@Si zf3nE43N27#$oAtq#tOH$krO@*fYocV&6z>4&|xf;F;eO=Z9I<=jl%Sw;3-;)Iza$w?oVVCG%wv$p;!#Hx``zBI*y*6g1mA7kro&;jogA`xC{E{*t*Z@ztv>tDd&dW%WGnghYBOl- zuz#+-us@1+keei!qM;i5^RnKin7f@E($W;6EjT{L*_xtPB>7+dcQx*hO>a0()vIAD zoz2U!EUl{v+E$ElD#`uOdNap9KX7VVygu;z>R{;x6n1$WsFD;ha19#<}~rGJ<^O zRW5E-BX2HzfJ!l(=T5ow5XSoCU`e;H@thZ5_?ZW*rexKjj}YM2O^iFO9Uj5^fv(_D zrjJm$H+fHf9&YaLD&$AU=V3=(@=mAwNKfUvH@5fg;nOF+|MM>!Z~nfFlGA;KPt@(N zV8WcfqE4ml+f;9%ofJDcj~#DuLwe>&Zn5k-x=7zFmgS3&UPZxt^0r1-5OI}UIV1~d z!#QU+vb=;nZ^#Z^FQR&M5AolYwiocirKjLw7tdqoa6`fO)}2QOeIvm!-sds0nXzD> zhv#wf2f6?93oyCcOUT_PT*SjYy#+ULzl6pW@AfpllZ9_@`v|$ReHQE9!h%a|V<-CG zfUdL_A-AzTW3S`+b+YP`t9Vh5ZM9A6WjHS(cT~?p=5Mk?@4ky=~bqB5u$%W22 za4zC=*oiK;@#7BJ*Xb6vRq#oto9JIid7I@ouuhf#-IIM4^KNskK5E%DWX&KqEWd{H z#ayeOGU_^x&nCBayN-cRO@)6tEx(RVHsrv8*U{s;iIB$@T|?_(-Vyl&*6^L24p|%NVArDH!xIFT`utTt~ zO8+-XPepNmvR{4*wn*>($$iVkdMOxPmwqrfnu6IY$x}9@;>SJmp}B{!LYr&3*Jq{S z>I8Cz>tQ&#lhwSAV38Mj$gXtwxRK9CA4Q$<;7QX>`Db+`t8q4pt6l&&Sm+Pr<5^z9q+xUq-v<1sly(rs)p`SbB~{CY&* z{Q4*+rjw0SGT^qH+@s2IG?VNV?PqTSLPm5Jtg0iugS4x&@SDj2{ag9i6OYzWT==u#2b+-E|?e%^?Sg_ra1i*#d?0OsyHYR_q8;kP~2Z=I-L$N&b80$WR1&;Fi!VCc*1-fOlSN6hKZIws+0UXS(; zIuM4N1>}A9VR(L(YhT?ag+Voq&n60D!%%Yv*TIzSr@@nC>>WHr_@}CClJvcy!Gd?> zB;ZpsvS$5wm>wA<x_!pjU9t{UEf9FXj6yns=ikk>g1Dm=7+-Z2HT$B)==Oa*Jic1g<|0eKFhEv2u12a zuG8*N#Qo^ac;p{t8(1fOS8KO^7ZHnD5pf7TO1?HI4hse{=PA{S!<>iYLY+9Ac4m&G zY(EKe6QEtrwp8^-JZ{YBB7D+tLOd2dB0sDhk1~7agwtNfN&PB$$J;nK&twkidp8IZ zg1A<^F*_Jv9+0m~?=Y*>)lRH?%KyIZzYEWH zk}J0gMYIWdL|!PoZ*q;gwX@VttjYE6g`sEm7@_~4y5TrsMjq8D9MLJGh5T-Q7|gZF z|GG!)9E0%T1=mZvuMCD|PtNg+4uoLL0cU(tOC#vvxqsh1_DtPOR)h zUYoKD4sTeeV|*yOdy)sN4#UsdD`lWLP^UysE3(LIFRUE0@Qn%YCyyZhW;=*}TeT^NmT-I9xuJrkcw-HEsLZ8q6um^A3^c1l$kj`;GyplXhI`_ckC3$*!II2!! z4qP%g950`eJJk+H*ZItcgQof-b1VCVv7LNj*_eI%7Y$#m*h;?D(-*y)ux$@n=8O5k zC8eRT>dE=Sntfpy zZNoW*(znVu2DS`_adql*N7_R-<2L6)u?>&1Cly(Qj=G_(|U9lY&@wJw&Ty(#^?+C|!%zm4PF`*>e$Kfv*^ z;YeS&p5PeTV3H3yKH{^;9S=9*v)TYrkFuT2Hu6KzUXCxZu71ef&oSstBR{yubIfvT z?u)6Je3n|vZ!^>jtb}gLxJ)$+L{c02Rg*jbT3{`SN9)#Pd_epr2tyrGpZ+`2I* zH*oMluPCxIzLl&4G1Y@H^%@<3vHQrD6aBI49@%fXA6{s3u3?ZY>A8gLD4iE^`yu)1 z3~$t!&pFPzXI|+2klbUP7i`CJPBeU=7na>58}#&o-xxk`wHfLKx7*|{o4lYs+CtcF z{8o}*BL6F1DQCRkq|f<_ldc!OCXs`sa~sz5k5jhvg5sThqvZ=bb zR`X)%`+zl@3T_c6eXmeDb5g!%y;Dl0ePqo9x3Bab&g+^BKCtaQG6!i0PFwH+E`P{M zJv;b(fc5<*;<_4{(!Nd$@;rP%MuM7<*A4i9GwNhBy$|sBZY<>M_Pxgw74p)O5*Ti7 zB;=3ON|4c-JXiA_I$mukg7?~;Fv$*;zjVD8mMLLR>T9a=3UXB~Tsj5cJW3vXal z*ie)ibha4H&yh11e!!Nv)|6X)#7aA|@6V6u_obDP9|`^>eQ$_-uW~8MYm+MtEk&cv zTB3~gtWvbCLT+MLio{hdg*;xf6b9ck1@Aic2_06EH|T!Ct(xS2wXs2YA29bw%{OrGm0V_p2R1nL%T#C5v|y@UBT^2fDr z@$<5_ke@sH25XYr3f4D$1DD8lfrn(}W7_pqI=`yekR15@H3kkR zH@%RLkJ7m-vObTGzrsn$Z!#ad{1P9U@IF%dIi*bz3PS1IkLrc++ePlKS|IIlCiiIg z8bj`p*S5{a?M7_#-G{$I&@^(VcTcgyl%XE5y zmH}j&n3tHHPHtED3a!tPJvvF>NKGT(b|`@UW^#r{AqH5HSNav9X94T) zZ?Nb?M-e;QRO#DfQ^@+&-eS;MuK84z&S~?IY?0&Jx7Jf^)n>n%=KB)77ZSw`#Sdd?&*(EwKm7E zgiVjoW*7OA_amrw=J=J9_6Vag$fxT(#ym@oWlH^*-hG0mS7^&?>AF7+*oPm=dW=ai z|5?_d5FZ7>|46beh7_P>|0jMdx+|xuluX{W6Vrtzqi!<3F02GZ(lC?yx;@-aR1v+u(e{3%%xsWFhGO3gwk)T zavo#xJ@#)+t3E~R4;;Ue!=J+Z|LA(}xSrqdk6*GyM#|pVGkZnZBeQ`-vPVXCwu+EY zMiDAyq#~8@?vYLQh(tC?_RjWuo^!hTJ%69?&mZqw_xEw0=Q`K9uIG3?$MyIo=c&lR zhY0&2*E!}tAE2$FTt9S=JcB{4q$(=SubVA_at~+75nhVnr5Q6%z;_jnwqzk z$+*wmcL*s7GS-bX-OS{iF}>L(7B}|FbxVlLLA=z~b*F2a*`^24-ca%(yYC@6pOXKs zVRBxkI59cjmQwuizA`tc-7pWC50p=jMKT8{&#x_W#$C(bc#kmk%lwM)t5WB4?G;8` z%JpxeJr_`M%5}bx8{ahQW^TJ9LQ`||Ia)d`H_ta;(sJ`JXMHEPUu0MPC4W^1ilgd7 z@m1ZZT~$xYN7b3~RQ0F))wt-#i+ILOIj89PQ}vT5_Dk&5R~N~3OH(aQNO?JTQ~Wev*}tgWTGwR%qI}NXlzocwytYC1Bg%hL5!sKZUj;0L zx3)N+Yj@pwDc8S5`qkVxi%;FijbEYLt=x8<`rXdWXX@3o+&sgN-pS4XZsEJR{UW>S zFZruFP#jesim&QM?W%fGKB~@?r>Z~Yuf~NmNrqJoLD`OFlE(G$#JS_zdZrqeGhc%D zVLOEFqZn6{(si79`IOHA!hdu-R*S9Z!v z`BT0s4)sIDr~avSsoyFes)x#x>O}2Pe5#-77u$3COa7`36i3yE;;XvRUsX@~cU5QF zPSv04r^ZD;Uc{ANgrIf03HMiVg1ILadx_om#A1Xy2eVH=(j3fOww?LGl4+RreJk_9 zP7^WWP5^UkqcK?4b|dpZw~;8=WCYGkq_%bC zdF4Ia9*5#5GEX>bhsa{u_oA9lMu;7f?ZziB*f3ce@)(@9BN>7~HQd;CZj^_u%(Q7h~X*`& zCsw-i#7d8zSn1RgEB$)nf7Qn{Z~^Xob>!TXzC6`I>CO`?J$hoLQ%|h)>xuRAO6i}H zUFo6{E4@@=rK3u$^i_$K?kcfWk7vC02T=#7ak%Sm~=0E8SIMeLeMk|8#K~ zMjVy7^cXAPw^ioYrFiY#=0;+F;kzCSU1bjUHs6E+J!PK%vfqNYVX`k|<=c)hZC!q9 z>qhAiT(yw%ND0@S==yyg+dKRXgJ=9w=7gkhlnPnS{3$#f>04GaN5qFA-y%7eUH%-3 zp|v)$-EmqlhEES<{@!*QI(L-w(DnLjQOUvj_bx< z;mifJb$AA7ZBw4X`tPu3EMLt$;mb~3?5@3ouFXlWPNA^7 zwt>0xyS5lCv){BtC6X-K{0Li zEQf*CHu1s-OA*#i*w)7#9kl1-WIvkM4dxT%d^&E#L=2j;jqUI5jzU^mAag+YaCAH+ z=g_YiLvf+EoI@`s42G}2oI|ba55^L0epAeGU53Ez%`#@CU*EHlS<*&(Ck*Oo3*ySP zN1*vsP1{W4tCdC~z{Z~0aJvhxyt2ctk!DFxUyZ_ycspEKY?f5?^=P!&ZU@ITW=VNJ zkHMQwcBt!TmUQvjFx)vefH~B0I7XHm#9ZIh87_5gnS;NKM28Q;_HRdN?^w#Vq}NKi zo|J<=Pkl_KJ5OyXZFlz1(V8b#TJyw8Yo54Cj@CS}(wZmMx2uo;MAPsjEl+BTv^`1V zlbAF=N&AzSv_MG{l$bO^Nh_3?v_nZllvwG}Q(H%VS$?mG@WRhMcvA&N= zznP$tn|l;mHs%f(jO;Q`s2h(f1Ft9j}t5XapHgVMQMLi&Ps=! znDi=1w~|=tuoEjCc4E@KB>hWbrNd6Fbl8cN4m&YjL(zA1l#kLhCsvx~#7fhgSYID~ zo)m|^!K0X@wMd$a#7f_sn6w#5qmg*1raQ0N)#sp(Lq00z?#7vDwzLe7(Yux}Fs-!- zbDt_%cpOwp=J}H>ygE{Xd6oN1djOEUjzpM`yQjG41eXJOCR zV$4sgzl7zRqRjnlU*duGjWN~sio;9n2`R|jqoLOKh54DYZe`)yR72(}wpp-RZos^3 z-wT`%`pe^$^e7Xx_Woja`~DoOy2&^e`jvsFUfNamdr-$Vh|MFfw^7T14ud|Jakty`g9bZ{#~MQu$^qX`R6_~ z+9PB1`(_0Gx=Z~>r|m`f?k*f>ozY&jtDA&zix^J^Kg4`rQy_eI2&U4#nzA zQj^u&LeS>s5RTtAO>3*PBXhpvf!KR$B=bS-J&Nur!gFf|VfsShLcO$iW==b^kMpqY zm>V^MxuES1{OCBG`Cs|p=)4)tmJjFLA{qst=lBuK-RlIR#~cuo%oXp2BebMD z^SIIBh5~wl%ms^o4$|4{A5>VeGQKt*^5Gh+&KP^LlFqNGmW{_ z`h7TCVk+}Pt4NH?uYH%O?O$0_4kEUf%&VV{F*tHvc)I-oxJ9_I&!Ex!@!;wx=9a6Y z(YDb7VCbFnr@5VBdWtFzx9flo8pAN6f*uNeo+ zg3|8s(0Hthm-+1S_Yi7i$-F($G5*BGR>2SfGjzVrPuur9bM)4Hhk_;)NCQgz*7zxNS`X# zwE7(MaZF+}&>*E2_xHu2cc>rTi1X||@Ew}WXuy2-_*?XKuE*T2fcDObM;+$%wco%w zs}}R_dascXByH8vo`d(^Rg>*bAF{B`Ncium7dVnqgY9`XWuo$LVY{i%k+4F1^f~Ku zJND%*K9`o?2pL=7qL!)rcKBINd*7qI{HAc7@di`<>T+LpM81Y)%{t6iF1$jUpVG&- zDKF8Yim=C(Ed1FhzYC_Gcma!1!WUvQQO8^OV5Ige*iigSJl58zw{OS!SKs>u$8O1a zT%X$|uXi}q#)8}R8vGtJtG8f2Jnn<`j(RKRsrx?SZe|?@PC1*4KYpyZ4yu z-;~?3`TZUtotiUW`T7B?LbP@6wEcHS)lV1@)|%PS?K9Hav}LBX`mYXZf*T->IvuufM!~cjk6^f55OsS7xuk?}+Ik*E9bW`Hrrha-Fkg$Tv*;)RBFB zS7l>$u=YDpi(|I)E9`Twuc%)$2j2NVebl#0Og^+NtzCa*<0JMbeSrmIgh_XxwxKZT z5qM62$UdY~uqEyRGwBzET))pux(4^I++!xa1Gm_8X3{}uwc;+bJ~w?1q$#lJ%0teF zv|bvmTMsUztXf0Yii#H(Ec?pFc{^IZe>35AsAsdgP6l-g&^$yHs-t4LNV#e zc4mFM`uHOXhhq4vP284=e~7j&^k(L?UfTNVc>|d*ScIT~_Rc-c+u+_IaBR1gdE15% zRP7hUyuD~BTn27qt`QXq&koy}AFK~SM8ami)=Du8K_mA7zSfG;wCc>h2Jp33vo*tD z-6)vz{Mcal+N! z*yHg4VV4Vo@m8BFRR10|n`7I{{oEH*(`Goa@BrKO?K;oxj)@(_-?Cj7IG&KY9eLOZ z@D<*`MV*^t;SR}R&V{D%I~&Svr52L>J)b4}RF`;)%TkTzC;V(B^;piwCFaI_z zaHqYDW0Ox77}RGc`}Zo{6nR#K$+p@(PP^CP%;nJt(c^bBpBvl=+qLg5D8Bt7?fPqJ z1oN&2je-1;%=3pgLH}7%%;7~WkbOFu`Ba@2s8a1Hvs*+`1Y zyuEmc`9NB0*!jdWhaYZ@m|k(r&h=U&s6;Gtb&FP*kr~50;C2g`rX67Z*WB3qrx~gT z9pT#Mb7+CP@rRjz4s8kN_yp!ld0W9T^bqrmo~@9_E1vmwgH}ix6UTflswGC-#4^{v z)&ixw9Ax&`(j4ap#4tCXR2q8=U*>%Deb?tu&Z-omJTI|7-Cvy3B$@qF$9_(1JMBDk z>HS|4m+iX1Jn&q0VwDRQnWK07NSu7*67%}%e-ix@q^-#E1~~6_h3&q>4B`1l_{y35 z*k*r~?Nz%Jg8N+It*48i+$iDB&5NO;nQ+h&W1QY3+qMiSi3b@HU*9i%{&eq?@~3^% z&^QqVu?m%oc@yCpr$2zK<%C2cN54W_#9i15`XG{P?9I z9(2CK_CF;HV1=LX>)wTM>VRICcG`q2q{B^-<&9pc9{~#Jh%jU^%SN$(|uc- z!}^-*^Cu=B>PvxPB|-O*$$xfFZ5_x8gM^>`O{DwIWUrU~HIeQ|tC%XjK2Bm(DbPJ= zib?mC>HaeDkLd=W`_9C4ADZq*6Zf#J0lMc-F{heU1Ko=!o|#@5bdR36RzOA2y?f%N zj^#o3^obpsl?C1FC;rvI6!Z*$_>-*(=-B{q$e~i8X9mRjKI-$F6J8zk+=BAid88`n zUOe%Kqm@DT=!xUvD}wIb6VttXx~ES(;e1)py?)|=AEuyZ0L1i6fSwHyH-B0h^vr-b zKCwRNnFr-V&tB*m3EA~I(6bSGMnd+cr~`U-LaeV9JsY8CBowFJojRarC&cu8iJtcm z=Re*8^c;xz!RKb6=R?Gm^I3qN8xarv))@3WiTLonhOp6|GZFtQ&%RbILC=sVAA0^n z&w+^Pxez@cBBtj>{M<-mdX7ZTlgLibm*_bY@%UE*G3=Nlx24ZnA3y8b0Hog;#{Qv$ z?BQBj?uWR|vcrpdBY4}b{cU0CKt0#TA{I7grmEvD!N`lxOojcIbU$G=}*#z?r+O?*3-z>ZQCheQrSD8RD1B#QrSD9v^qq;7zB94XcP3W)&csUJnONzSQw~bUob38`l@2@E7i|(9 zc4DQ&PONm;iIomJvC?5DRyyp&N{5|T>97+k9d=@+!%nPp*ol=6JF(JXC)SUV(q5;2 zDeZM)rM*t9wAYE1_ByfBUME)C>%>ZXomgqF6D#d?Vx_%KeD#iKuM;cnbz-HxPJHgg zA#~B+8zz4AH6DvbA7(!PDh|i*$u-s3E3sI;RM>RaLA13KUg92uPlJVB1|2|6FyD9_E-w6JM;yGg_g|@=r9)z2+C_L-z(IIb6fUqP2DhsS zFZVitY#ZTg-un?3F1*qt6XUl%;lAkmsBc$kyHi_AL!9cM^xTP+o;$J9b0=1M?!-#Z zomlC)6DvJ;V!N%P=T5Bj+=-Q*JF(JpCsumy?62#KK4+zMPWgYn`wUkrzva5UNXbCT z);G+ZVxQyU``64{-7*oNeUCx@OO0Nja;sO&zM8I|S&Ns#$6nx3jV$JXlo#kx^aXRd z!!I!K({tu@SM58Ory0yYzhHJtu#CTl$zv6P)5JJ$GWI=T5Bj+=-or zh@LyK(sL(PdhW#jUDjbi*dOd!X_mA$dL2&m`-?Brwd)px^{DdbFRl$TOM2GQ9(UUp z=iJO!IN;goV$3GqgJEeUJfztW)QvY{`%%v!C|6Usx%&`=tuM-Un@NK)scF%qe%kY$ zGb6QkFV7cAveV8}QyZe(BqqU#Sty z&X(gi<3g+8XZ;H7-_EEy#%SL)&=^(ms)-tdg)jc7g->0DjU4O3shn`%4fPR`B5hUL z)DRD63+r>xw>7I`RXn~_p4&C+QXNZP3pbco6Ma7mkK9)aC7%h;zEB6&iNZ(E)P4$B5mxXerqC6xR2>==-t=NtQUfN|!?8 zC}H}&(7u~?4$*2t>uk@^zG)?<^|v!7mSv`OxidZq(|X-srgXdu`sRgeXEni zq;meho(R+W;pJZn|ErJmTZ3|=xkPJj`&|&GwYXRHF3WaWqx;?& zVOqO;QcD?kTGQKci!iPAUG<$XtpV<5A@!lP!GE|2)0*Lx77No_;+>ZZQ++NqddJ6Y zeXaDl5t9$)X_%NFTMNHn|8cg4=;tEb(Zm3w-wIbO_b2i2-YoWU2>g+FTKiU$Y94$l zJMr|USIncMz9ham@|t;q_S<>)yEn}GeDv*hDqH}YFUzqp@Tnm#RFq?8!^Z}=A1GX} zWFAzplH;m(-rtGA#pHPF@BSmv;k)pLZQm06{+45M$h_>tJ0;~9emA}_qUU6C4#r)I zV2FjZrEfQFPC=9m6MNmqS`DWO>uVBZQV@PmBu=OCh445=_*$45oMuRU_V|^7@nx|) z^e>HRcEYvamcTvj8%wHH&xOU&>yP%0rN%>yjnKB5*#DJhTAV3LmXM z+of=}w6N`=64-q!lgDv_cX50>BV5tR2z4@qd!6Zv;5xs#U472__ycd*z&80e$GJb< z7Ct}aym0>GAgq}z9I5^04ov>bac+MYfWDXhFo!MZkC`tezP>Ge%xJ%X@N&q@^Z&Va zZ*#yU17?Tc1CeSed^dC;8pP&dyV0uw7}`*{o%VjmGMB%cTbKF$@Y3@S^Z5dU@b{BJ z5}ilRc@2W=27@Fzk5v0U2#(zhlIT2A)p7yGYr0fMH_If|%{L1lCJ2wqI|b)I6leRe zspGJrp>X|0BhkA?F}52y4TE8NQRa+hgOM=22(w8IJA6J;h}q405InyZU=9c#hywNV z=i0r88Rq(z4KiS+ID6mz1?5BWOMd;uOzkcm^Mjf4dE5URGv&EF`71N!-#qOLGxe+c z3SpzfrMdRk?Y(mS-Ijaj#wogZb#DAE#@ZUoIqf#Axh^-KO_AC=#W{Iq25Gv|Ir-mw zP&g6`cwXDT=e5b+(XkTd)>-3sj}HDRJbM_ zSA7bChYOqfjl++y;_MUWuZ`WFV$7ch41@1fBj$o1wQmp%i!wj(v&9S7!pydP2BP!P zg3QYr4S>hz{LFo=2Ed|jK4uHgfiM`8m)ZKQEvCffVV*Q)Fz$8x1Iq2it6`|`{*yVo zn+rCZerJvwG9CpQW;56QJ_Ua-d|_VrbryR6_{`jP!a}S$A?!6_87?#wpY6Z3`n3DX zKE8GU8n;!pVPFwB=gKz`RbLv!o)R}3>Y!dH} ziT$OI`|bSUTVMKK(bf;6vkS40(cyJyysHTFr8T}NU0-VWGDBP2#9e9|f72U1S4qvc zPxr!HO`DAB;FG!(`7aCW$Bww+Fxht2n%U^zUbtA{>4?2A@o%J0Ld(v=g&K{+%IPv* zCN)RFNYg{7_#^L+KwxJXy9qO#(CeGz|K*z_nrtq>KA!U&d9IQ_+0&Dx@8o~NNyd@l zxRsLnQ2absq;Ax1f%Ct)hLlgFxzv{OJn&v>PWjJnCQSWG`XpmLCVNS)J@AM}u79ik z%X8yY-0htk-!yVnZoAX^`Q+v^$#YF^p5a!$x%m%Y>YLjyva9}*zp4YpQT3tts&3S- zswd^6>P&g6`cwXDT=e5bTTkUi+!T@&6jUG;gTkk5Fcp7$GY|n$D(MG z96yVE9Epzm<@hnjMD$G8Ae>!4Dc{!GPO&tpFJ#s9~`*KL`F^B9PQF1IL|A2OR zd0UFJ>`@+OiXUhr$5m=KPm|w#oTPlB=l*1-JbyNqV=U#LH068lvGjL+;WFiy=GtHV z_Q>@&i(8%>XIbr)x$!G>U7g$RlwUr%`Bd%Xo13Rofwj5$SLwMnw_jve{Uv`@2a2QW zL-AGJs9jZ0%170i@>KPw{MEPw#Z5riOZg2ob;dZ{H#FvJ;HEvtU}Q7l^_@o{-&|q) zsUuNZJI2!WiPHWfR+@lxt*A65iIpxPvC<_ZR=R}5N|%sW=@JqvT|(m9o~{V(Z_MZM zV@8v)u7NS1#|z(`h-OB{d>&VNh2*c#N1vzCF{GUJ{z_kxwpIF)#7bY1Sm{d=D}6~~ zr7uaW^d*V)Z7EGjYFBAW5-UwfVx=ibtTZLrCr49~Sm})tD{W9}OKFdiU1^UJEA3HY zr9Dclv`2}R_9(H^9wpYdrSF&0A*FVe4k>Y&934_(r9(=rbV!Mn4k@udf2CtfcBNxW ztaNONm5wd3(y=90I<~}0$Cg-M6Qx~C{ZiVs#7euCSZUW1EA3ihrCm#`^n8hxhVTEj ztM^fwzyIs6bew5hrQ=MjbexHmjx({+aVAze&csT`nONyK6YJYm+Rc=M(rzYJ+RemD zyO~&NHxn!EW@4q?Osw>^iIsLXwX3wY$*#1viIvv&|8A?#S?O+59HqNWtdFmB*vYPR z*ol=6JF(JXCssP_#7c*qSn046D;;)Xef~;&opM&%>)fv#?R8?My-uvO*NK((Im<=;V1HJyt```R$Oo$8Ua${q&GvE$ zUN}-k*ms&2%yzV5yFPyA125bg)RvF!CViIUN^%=!*VW5$y`}KLt;-P>(wgm#^OvJi zG2tN%mcwXaE4EuDtwH45#vI@7^%|u2Yr^)-20rK#C_KYw73vpk%JyW_m6*9ncya0q z6z^=o_I)>(!=z9%=Iv#d{d7Bkjk>7$jv*vOHrwLDT^umi{&DcKfi6^ebHD~S# zPmDd#g1O2YPk8TZ$*ix#)XTp3cp|4J=QXXIMZ&8h*5OqxVb_W4(HM<*+aZR2*xE(- z$}~SD9&gBY|NVZL(Lz{X+hP^h;#4K6ZKIa!;C7=i*I|OidQ_VxJgBfA;=eaydtjU& z_PPl-Y3z^e2MyW2aF##5SquMcti4NSTZh{n_a_)p+WP7=5A!wJfnC1Bl^nLA`dZ;) zE4HF?g7B{kftZ`WF8eQQ9DuKLgnJ&}1jnNF*q*pzBj)@k9PhgUHXila-c4I?wy9GC zW_>>TzE8H?fr|AdwnBOfZB{$+X0q_`o?-YpSlF?9IGQvO zHg2&CyFS(CIKz#0<3*UTzMiQyLs9su)NOOWo$$RT{C9R3EVMPrspfP1!?8kJXPY=? z+b$gKA)Kmxzyu z6n-y|92%X8!qS4mGkQd$=kl7ITj|hf%=}e@`RUbY4A$01qQ0NI7L5t_sx$u=7LB?# z!dLo4!}wG+whvqriHTuyU$j%-DA**)z1)}UBQg89+yno-FcM`hR$~7rrJ^wBS`}t} z9DV-vF7CtpLlw9$8xQS6=j)Z2EBBAYuIE*l_3fTa)YkVlmmHdC-!I(VDfe<+cSd4i z4dE`1k!ZbJ?)}buvkyfqgu{mI!-cb^9Mdi`Li=u7IQh|D)F>;g@7G9=D5Nx&KE|$& z!l&(WPdo3pC^R+}ZfY8ZzaBaF!?#A_WFFzX-}hmsw<-61RkM9qRatm_zX%jOQ-wEWeGYn`Hs$?rDpsDk==~SQu0za8c_va|&sr?mAbfV6FM<~eU!AoEM;8hA z9pQuI&B6ohR>L@1Sn12tT++8SwfuSvoht)Ho|{1eX+cfaQjnhU|d#sWUvo5 z)fGPab~R4UF2>J&>NZ-9!KaGxb042%?RRljF@Emzb(SBhoG-+6@IK>*vi60Udv@|i zxpZNRr~XK@EyDH=5gRb*xbTv78}Y2XJY(wdcO#O|$+Mo99sKcOY(cK4Sp|RXy-H!b zI{w(dq!8OXkMYOdB88bNYirovUn6{F%m%#6FLCl#--ylHeGjThBV&JjyjYNbANk$& zL+yrz`1jGpy?!{lpb-B)3T_?^qdTS8U!RXY&)eGmSf@d0?u*`kq4w=e+p?v3+m?k7 zphj2W*9Bs5P+O;qa#&dSAi9qh-diLVC+&pWC-xj?KmkPr3zud*DGg7xD%^sqwt1-8$&q43=E&d^%AC~(MdjF@|HwO;I zW!qINA7O8Z9IqDseT0JbgyU=;!y`hDCk@>mYvV4QJ?Sxugvhg6ef+c)kFcSyv{k&t zW8Awb_ets;d5i~rg-@1v!uP&tj%{u81SK2Dv1PZ#6CBwj&zk2>`hb(#y+^8Nm1-X_ z`*Q)FR}&oG0nx&t3*NwJy>RsQSFjEeUVSkOM%RQhOT56ddIfpgL-U`bdW3MQSq6&r zl4I0?cTe#pzZ{o76n%PkkLqF4fk^wUL~iJ>Q^X zL*X8tT5fHGlhn?1sx@91oV~9`Y_{cNpD3#zC|+KezQO6_ zZ}@-4agFsyw5uj#v3JTRd~YGVeA{Q#un?|w?h8`N2uD5rit~?UOgFvC#%OJB(EQ1| z{S8}N3r`IFj(6wsv;A1t9~jz0H~>G;7WvqIvA|EXt0zp~3Q=wphw==rB+te4IqQ9h z$>)Fl>DwQ_+VUKYz6n}ZL7t=0w?eZj%d4>NrO$0uJopW++dphEYr zY+q3R9bVXGGq*XTtyx`D{AaEDh<-7``Z)T&B*eePNP}-2GiLsK^nM_G*Xbkj&y@b^ z+uhRbH7*U596U$8!hmOAcw0NSmzW(Wyk%|{KFts=sl7WCK2z9dSteF)71rnPwC^Swk$U!kp$8!7BG`Gt1RSvb=+6D98m_nH`hf~GR(^=;{W z!nHN?FUHAy)BE>v+Ki7@vTdnRn~={_ICa@Z47e+7a%uydtYu$wsJj8RjtG}H>W}vA zWIvrX*B=i~3+vnRH{T4W$I|XgZLOn@HDvx*wb+QObA?S@HsJk3;jB1+nAyv|(=^f_ zQ5W;`_1>fafAsBEfUoxoukuGduL69%x7YM<;_{J$c)wUx-4GLF?3lZ+FNm304$NmS z8{t^Kq0FC5i=+0XA$&|IQNRF+R)d)DuFZ#E-ge9d-xk7uhaH&p{!d(t;c79I?G~>} zz;2ariCv`-ab0+fw+VI@aAcoK%T4j7w(u;!vWRUi+&j2DLK+Cq46TSa#=<3iDx>d1 ziKEYXl~r-{o+J6c{br0~cZ5H@D2cGTj@+->`AzU`v~b~0rm$KiY_qy7)&>Z-Pb-h* zYlX{|tpw+(!n4~~!Ryw-Ea=gXYgqYv zez>m|HW`u+Js$~w`#S96@UlQ`a))wDI1 zh12KegYEim-1oyT^1-cXH_k!d$FP_pC~~ha+ZT2&hCTy?yG=I6h)5f@Z>Ufb4L4AdejM*stdI5Wr2bcHG{p9b!nP$EV{n%2`=@R-f$>h^IpZy` zzPGUU_8BT?4Cb0x=;lMEq4m*uyUc+hI~rokeBp0r8>4}>@b!~TG2_z^&hxfcGt6Eu zJSSfZ9Ih-(?@diD)tP-l27gXGzFWA!oG*#3+H_%iwLaO2B~J<8y!bsa$*L>c12TRk z{)iEtYn=xVN=V;7_sFZg^Dq3b`9|+(QM)w%2f1b^p4cp0#PwTZNVzU-e{B3C@z4h0 zBE5elUeDi^?Wc_YCKi||{LtJ0$CHGwX#3!01DPikf40R-TYL7`*HGX0`Bv@W>1)q@ zp*mcBY>~^VCi*;y$%k^*$4@tGkAw_4R?j-!9$Q?6JGbtD`R{Dmf6lND7(GR}X_F3^ z{YH-So^kDQWvcMx*X=O-n;ZvD+-r;etAzD==9#FiS5{JTPSDmRo3UEXFB48#qRAgy z&i~6RO9Z(JJ0G<~%lmRZN^fil_x{2s`gOq73v%3BP^CSl_Yppo^FN%Kjru^*TVw)s>yNY{V@ylu#sa?(A?%QnIgxoX~C_K zHABu{`f<_EhkI6SaQcGmF9AhcV8Usc|J6EK;Nmkme(wI<1j!ZT*!#z#DK-w4<8z z#&|eg;`|OQ4Ws$O`nmE9^_?#CGHA)_B)iIK8bkq7yo@ zy_KOg3bYb-UtonYM=ja@d~YW_>@2JwmmmGC(C&^EkCCgZHOe>&w`|iHV^cb@eL{3+ z%4SY2e z&eNhg!h&QDf1X|yjk^nb&94mO0>W*bE24I~jMtvV;M_+Nd|x23PGTAQ8vqSj_7 zR%^2ptF_sQ)!OXDYHfC6T2r0Y9w%07vlFYe*@@NK?8;7SvnzjEo1Iv#%}%V=W+zr_ zvlFYe*@@NK?8Itqc4DdJk=#eiIm!6k>=jp(V#DJRe{OettCy5@LYOqgMqsNK)P0X3e z?yYGaQGD{BVJOcHDbC8_b=gkwEd%N?Q@cfX%X3)DCvI5-wo{&KYBpr1{3BNgQ@@Js z6%Kk_HrL)`Z{=M7kTNxMbalk!n@raV>sDStIC`tc%u@T4No2R&!DErz3c{(&T zzrT4ywo|_vbQSIpR5sThUbS+r|0A0kxp5+X)`p6|J%0mDms#2!(5Ep}K0OaLg~}66 zv~Ra_@^5sY8IL3Nh3u-oTfTT`|m7t_iJztgs>T`t$#)%#guR|C1fap6!0?k}}V_Fn#S?M?nJZRFaU;<%pa$GK7bk@W{K zQ@hU2^1F}n$>%7)4JprqrRDb{<$uvrnELfNLO6c^q+ENM9&Wk*9p}!?jZ?D3qTKlT z-InII+i#plZa#a{JahBBchoC4|3U?29I0PqSN$b_RR@Zr>O=8W-KbqvPs&HtnetTi zr~K8pD6L*P?DUtMYohOq z(!Hg8Ohz5RyH0W~s_&ydAD@f^Sf{=7_P_C!MljixMli9`2qsn0%QrU2I~di%qPrn|{2MMmDvjG_r}6MmDk1$R<`A*~G8w zU&Z%>G7qcGxr!ymaxJZ|&z<~N0Cr@G8PvJQ@hj-tFdq-Zxz6fFc z_Ptn}iEm0mot(u*fndhx_>#;w8Z z`Esor;CdT}Vx*7BJ5sTyxA3*NTR8t!#>M&IP1MSH_c&pD3hcebzG%q}OqnhmGWdvc#!FzO>*XzWe6l@xw4H3d_%WNr_g zb^||e3a@s(j*U5-+{{ky9@H0ZnZAH#}z+(xg%{|*4|+@Fp}%ZzTYQ-E{6)u*#70s{6b?;xJApF-!xL>It zgdLFk(zi0U!m7IPbMLLV9Vpk#`o1@r=ZDVC<#$ciZhs7zEIc)1117B$ZeM2;Vpj== zjopmO(}XK*4#2#&!ix_C!ugfd(4?lT#5QY^IKG-n`e$(Z*Tg&S=kk47}8&4^E6NX;GaW=Q$=qo(j zHx;Mm3tv5T8y9SZPdrP*_58vsU)({SU2>m!__@1i)l}HeJssH*azFXZuXJ=V6E^O3 z55De=_k$W%wEbk$28{zF4>A1E{?%N~`PRC{=Vf`G_&!xS_DKIyXd(kcH z+(g6b!e6@If>%A^&SO*Ys+{l|_uF{*UhYe;T9AgI1HubN-$4mS;pz47;(~V1oc1ZV zi+AzbT{xy=I*hU#u|3XH)6bnGJU$>DL(}E{Lrbmih585=sGpA6C**!b>!`ch`sc!D ziyc6JBY8gJGIl?%S@ag5Fip7Z<-OQnS~%Ni4^H3h z&OR+V?Sjua;R!RsuqMaeP}6;~%JDx@Gz1lM;v{(Qz=pRHC%pM~v{)_erk34?cq_@L zXonz_D<;pWyYJTaolN1Kj$85gqTC;7G;Ax3V{JHx%spFCXtUfa(9bvhzEk2sG(vmy z{cHH-Cf6n9W@pkN^pOY^eUdQBfGOzyYcohw` zXOT3owhz3F$CrhTXI{jUVlqFg#hk~~nZk8UlacsG*g5(v4ED-%z#SfEuyIN=j$^$2 zG)nhs&ivKzH0HNx!R&M76rAd{WKKJN3I(gTV%}5kG~&y&X7)XC8u%mpDfSFbq_$yu ztCweSXLDQThmOfeYA^lLA2&7{Uq?-C|Dto^VC$z|C+KJvV^W#@C){z}-n!C4dtYsN7v*`L9aY0a5?pFNF$J}sD2mz+lJrY)Iw ztvHRoWm_??x_cT)KZQHaIfD+jTC;urkh8eEy$y4T`R7nN=NqxoHc7PlqLF z_ZWrigdE0;D#A-w96@A?#GfVpw=CTi-DRK})wfIzj zt6H(zTKd9+2FBs%ec>ZoJ_BD0e?EE$zwZgJe4c=zhlE=i9D(~B;bw+MQC90C#T=7y z6uyV0T_2ZA@Ye2Sk^M;J%fJ@74;i!nGRl+^o?G$?1}v86m5x?du;{rwqby>11y_3u zZz*^MD`GovoHaWx<4!f<%0*1PA(EQR~^GSe2VFbRs%*eS8}#Plh?vctwv&ZQ}NOJyS1E(-$lhu?W+#B<5*SU^&2hG?SwPiGZtH7zwJooW#=qWK2vzx#Ey6{Q~axr>4eEY zgwGzZg6m9)Z`HLkQXUFVE!!1u+DJY-DtCwb5@G$=>BnMp^-f5+HfDCKNIq9h-?o^d+^cz-Qwt(SN3T-?_Jg@u>C^u>K2c`rA%sV}-! z7WS}PgYGBf-822%sMT*3&J>byAK|ka=`V-z_<9`GbZHL?dtF z+J7ysx(m;1whpV_$~%5zg4ZF?UbypZ&7L6d^-WD(hw7%n@3v`rr*j5#TQeK4!`g=q z%zb^e?}!Hp4?5* zb1UEW=u=txXnv(VQVt6LYo6R#*a_9mWn79(>4>b&!e#bZqNIt8z|dCi&G4YrO_6MY}``J^80j<*|R ztjp=*$1m{4HZy5!zRwEG)}E=+^fu-{d5GaFQo}O%QH7 z&;#3igfqG=!_L#fb^9+xTnVW|+okrJzOan-h+eiRbVqn)!GZXFO*sB+Kg@e5d~2f( zs^^nAGiO+9)kY>!$FvcFiBu|z7 z6N>f6Su5d?vVF1CMcBf!4?1lU_Fvfx$J2#v^Y?^(QyDLPJ@x(7w_7;P3F}VEw(l;C zLChoJk%wJz!S{v2mk#Dm0IqhwxvS^Pe6nw1>uS~%syoqci~4j)h&6_(0*a9dQ%$)ya$(Ek#AQ}8CtJ7rl-Q<(9CJ$h<;RlAa(>xuZ-PZF66?oWKQ{&>%|L9+Tbxg0ZQa-VbDl9@U*8^!oqscb zcdd!Zn~nK9Ao@%HPx;folOHi{N81xqJc>(vX5c4`J|e#j|24;ApMS!#U-Da6doTC@ zQ=k98T9J>c+k`y^N$qpqQ|e`umzi_W#q78CJ4QRn{hYUEe~|4|kLORUwqD~T6M1(f zGTtD`C!iYJ^*MLV`iA@Fa$n13)NizFR*%QDnr)t>aoOg~j|UngJziOjnR3wn_!5T8rUlN22OitTo7^CY#6c*gwh;~(_f`GDE9`EQ&& zc858p>rVulr!t>y`5kxP%ly&TL|?-^+8UFUOZ?<zR6fc~0c@$cW7G6`c3jUk*lylbiOW&54NmUd`eZp~mj3|e+ zBKO(fd1N`9>HL6s%EfZ1KldSX?XBhExZ@FX%!LZb7xS2T(SS;r8vcY?->yD>t+(Y- zx59mHYwWx7SZncs*{p8`yz2Up*|%UtxZ6Bp_A{-7>sF7Mm(HjRql%KJ@6xg;v@ea@ zT47Kg4`-yYk3Rmyzva``BVyIppz6=QwfZ%#TRqw)D0%z2E;q4UEO<|2K|!nN=%=0#u4(5+)C^UZ=~QD*LK=6~f`<#I(B+TP%N zCM>Lg;muN*Yc4F0UG;A=uS_Y22Q6+f5BDkuuU@IlX&cJn>d4#7Ne2d_aKL_UOP{ko ze%jq3$Y1FI`#(K28cB_!*gwqO1%Da}XKEU=g@*|Ltv(#-(ZUz14a1a%(d_T2&Hv=< z!uodg@tbZQjr(7sxGk#y7g*$QwH?j~sSwTfgoNR+8ZW%)%`kMiBiyOCBl1q(Fa28N zhBd)^x!wJ@W*}d|2)66vJJcVCM>+AEBuv186Vk42y~)@DElD8e@Jq@mZ z_c7OZa6@4eVSP;^ijKqaocg>QJOTcHBRPkMYbRlBsBnu=SNN3^4p=r7E649+pHDTX zBgsF4`Iwz2I`@_uULN9!hdso9sD&rody2o;BM&&*ihtNx56qt?{cV)I3=Uy?IL@xZ z%W&e$Zf5r;OA#|cIL&$qYUC3xvUU-Ep4-Jf16MD=$3wy`SGr^Abz#TNbCG2#{%=ps zMq@AG4i#siQ8{UAXygpUToF$CNB#f$dZ3r4FH6T9FFy}#v6tGmn&ttoxl&K#x*iz5 zQ^u?Gv1Mp=e=qy@Xt4}&^@X>tU5aP^d)R*R#uAh*FI*+x5}ZG=o9%T6EyDaY!ts6! z5V1&jPl`KEZ4^fJd8l+lxQEXiH9VN z;5@wk`Hpi?Ysu32vBdT{c+~haZ~HsXJe=$HiFv81J5F}_$b90qyS9GO2WEX+`j~4S zreW*GFC5=-yc^Cm5gyuaCW3-Lv)%pAEcD9y#N2hl98@SF+{tS$>??d^d&^$)P^{Dk z<}NR$qmAVHn*S@bwM@-j!a29pSRa&aAakQ|ejns9 zk@+xU!D@6ckvUMi(rN_Mk~tZhwF=|A$XuOqU^PY#mhp9)untrI3*#Kl4PT40Rl=G7 zjQ2%iv~c&eYfyXaF1F`M^TF?qGG1Oie6-`6j8S22{oBA!GDZtL*J4a|80#m7hxsDB zUO4L~ekkROhCRYrKk;OcCn8S0=a~9@^m!VjYU{-Am$BCSFAng;)(29z)~7wu=&RH- zqOuqI<(2xk4)=oPPvJjftH_w!C?k1^(x z=sCOBY)hB%@6f)p+YpWYoe!OD+@5&I`Z)dn-CkwhacK+Lb>frAF`(=A`o%_Rf zmu*^#*gkx*IN#rY*;co8&)$E@PHu5;+Iq>#7I-N1p?&NmH~qIlQ&T9?a)IX-Xn{f^5<33aHTD-mSKiA^@N3OmekF&esjd=Wwr*Fjb zo@sG2UeBi+Z^r99b>?Qg{vZFn86Owz8ZZ5I9EhXiLwp@K^6Gd}kB&2S>iAQ?&P()s z;S7Br{Pft0hd+(_T#tWj^l)$geN^nXXcxM(t^M0x+vl!*?y}X+mLa^hbLGocv4?xs z$CqsJ9(TsNm+ak28AG3w87|qljqa;S{5+DE_7e*p3VrDRSLRH?#Q7oiH#qbmeu-0V z^5%Iab7-fYG=tsL`O^kB^`HLP&A3`0a?g0_TD*OEY(EP1@A%-2c$`xEZp7nf9egvM z_f+az@p`&eqSs zQ za|v}fxo^LJHlb678lg|^FU};)kA3#X{kZ1sGhqz`(_XX6bD^F7gBH7qGyU$G@%Wn? zxyjpduA6#l9&l6V`jpRy{?uRNQ8(i%m*2hlo+PIB52xH|>VNCrWTrTyo8D!L|6u>S zO?fwWNN%d9b*2=iIzJwi!c_me3sZ#ehchnPHD3DbI1oq2hxj^fZT7Ovr_hdmxU4kf+4;;?@bS~hT3%YHfGv61eyssBny{eyd0+j9y3K3YA* zsa5VwLfc{Pe2Y#cRKDzfedWo7=iAo^eO5F+8O|fuC++j@Ig*`B2|vyK7T)E8+*934#;hdbLI@~qY6H1ciopOnE&Pf z^IHBp{V=cN^_Y0X#pEHM+W%RXFW&#>3i*SHQ*^^q!NmXi?t;POshPJ>FnO+|FC0vs zX^VgF_LOXdrtK}w-+R3B-m=$MW%Ahh{@%W~<74*xEqCKhk6QCB*+c)& z3gogI`*Q^Izx;pV@Zaf&c^$9E#3L>yC;8M~?|Qy?|F^c~4<^pv?-U3o{=bKkNT5Gamb_i{IBxz-&GH}BL&KK7C3jGt$7uNa0I$v1l z3+sHTo#Uwf)Q5Gxu+A6O`NBG1Sm!JBPdr~ZdcH8vGUn+~>-kB$o}XCHPps!B*7FnV z`HA)X#Cm>WJwMgXb3y%iUSK^xv7Vn;&rhu9C)V>5>-mWp7tb}U=O@WJwLIYpIFaNta$&hE0Bc@= zH7~%L7huf`u;v9=^8&RqFHnEx1z7U}ta$;}yZ~!nfHg0`nipWr3$W$|Sn~p`c>&hE z0Bc@=H7~%L7huf`u;vA7XI`NG%nPvQ1z7U}ta$;}yZ~!nfHg0`(es6wo9jHvny1sQ zc{>d!nKYo3lZPsf_4W6jgC=IL1TbgX#+ z=T!3ota$;}yZ~!n5c((13$W$|Sn~p`c>&hEK<&J*R)5}aW6cY&<^@>u0<3uf*1RC} zPn;KE%?q&R1z7U}ta$;}ydd;XoEKot3$W$|Sn~p`d4bxQ7pOn;0<3uf*1P~~UVt?( zz?v6?{)zJf96eu{xw+1xta&=^nx|vU)3N61So3tOc{$C{^O&C{{w=~(l0ta&=tJRNJEjz1pc^K`6vy4sni zt3UH}ta&=tJRNJEjx|rmnx|vU)A68VgY4apdfLs{?|>H1JlN(Hf77zWes}YyY!j@1 zrM|&A&WyLVU-t`rqV2_NPqghh`h`9VUz=oYiu4bj7TZ6wda?n*{fbVuGPm3}_e{3s z83u*+Tveu6nrefCqw%-hoM0E8?H_WbkNq9cUB9>+@0k?aPh&u6KQQ)v+u3Dc@WmXH z?V%2Xf(s6rY+v+_eGe%%ma=7gThR=?gSTDlV^7U~E4b-}zLu@*XcSCK_u|$tm#~s~mU`0O;=hk+!O6&cY zN9&1>JsSV1JyWf3rx797)I(G4(x8#SuY5k$_D&fUT=lJ~vA^qiFZkD#Q|*=cqrLwd zQ>@;&F~PrVo@^uAj17*~{KErNEzj~1p?+L@=g46Cq&qvx$JKX=CER*1ILq0|cGtDh z!BYxPwwkf;?r`ot@7mScjTjbu^PaA@pySZE->ESq-Y4P7#B*KZbxW7kuYp$@#=hH} z-LH-R>RA1DuCrzSbXcgr!m!R(YuV7?*SdAK{gZ|S|FEjFUFq-FXX*-FY)5y$Zck?G zYVCUr41Hd$_PX^N?$>sg6cg=ImWiRgVDAaGZuEpuXLMZA<5nhbcf0pPKPL4TzHXa; z^y43`EqWZH@kkn)Ts5kXw<~QYg}g_qkBjY-=1wRx)&@TOerVtG_!wJX#@#CI zXsc1!J>~W&>+`SokJdcn)A4qz;KWe>rPJfA@p|{EbPCL)Z6a6IxdX2(73nk#Blcu&3f8v$NXAt-|-C_@}PU> zw(d4Q_S-Yuck_mHvm8nNI*%TcX#LUn(Xr_Hz?zkw8(7a1tmh2Y^9Sp>gmuqi-OH?> z=$VZ5+`xLCU_EEBo04HsSy3_~=)%1Fe;={_-NgF$6ziFQb!1F*FR< z4yOOt+20G^v2Ut$G5{^~kzb{z-?qL0Ug!S(fX5OmL5tz?vy_$Kh z*0GuYYJHn|vDUqrFKa!Vd9>EanU8DzocTEGLX3;~IO|iGcGh<={aN?H#L>Dv@wJ{$ zUe=H3Lp`i3Vd`XkD!evUzdkQuT>2b=`K;QR=c+&RU&UcwtoY2Am6v(6>R~>vI+>5F ze&*vE7wsA^{dF9OqvJz-9XImocv6p!Gj;0tQ@_qj^n77`ju18LOIojH-AU`%tVd~m zn{_I!d$WF}^>Eg;STE+euH5j7y&*u)d^r)}7R!^(e(*ol5apzfxY-wNwx5W2%$&G1brdn8roB z#!G)42jb}X5MRfQygHuLqvK4SI{wtJ^P=;`oL%P&>wJZIed77TI$v1l3+sGgoiD8O zg>}BvuFny4zG&C^!a84A=L_q6VVy6m^M!T3u+A6O`NBG1Smz7td|{n0tn-C+zOc@h z+Vwet&KK=EUs&f0>wICIFRb&0b-r-)d|`c#5VfA4%-{9=#Cm>WJwLIYpIFaNtmh}z z^Aqd&sdk<}>d$it>-mZG{KR^GVm&{xo}ZZdc}`-+rOy%c{G?saPps!B*7FnV`HA)X z#Cm>WJwLIYpK90V2zq|fuIDG#^Aqd&iS_)%dVXR(Kk>a+R@vZ|Rl>g)ZS$_Omxs8o zv|4FP&%3`_w8CEeplayT_l^~IZFsfdQeBo?|E1Oawbz!}{Wog_Pl$a7wrkg#!RNz#0 zelT^8F54iO`j0MjGp=>txz~QNI^Lf1-8J$4bt+fD=M{aogyhm1AgUkWD9$*V616Mx9Sdcowav8R48 z^&C6dAecI@u4@=f{dEg93T9lz8@pQ{T^(=lv3*Uvf8m8|<8kijxGo<5$b;+Sc~{L` zAFrp>T^mewwy(4yUVp;|8{*@lUE`&{jstOYe2A~(MqV9H>d|qgP91;h*Li8QcfO5C z+bmqS{qoJXtp(hF4w`4v-*wM9HrFa=ZSH*<%(dD_+}nSjW9#>}2<=tho?|yIw+y~m zaE|pa&^kC}vRI$KZGul-o^2iWwvD&vEZi>Mzy5&s!NmFPlUIX@pL6eP!Tn-+hivZ< zOg-Z#b_}M@GLLuiKC${!4{$TCnls(ShAfD;|M29(c>i?U7RKWgYp^ID|M;#&@w}aj zFOJvqMZd+SI+re6Y^wjePZr0=MZ3mJe;o(n==cy{$Bn!?p46k`Or1LZ)UWdrJzqG* zz$W4PjCyB^`POiOw~v2jo)t>hH1zp=;9RTzg*(&UIaYObv(Ub!@*F$)OY`9B+h<#; z{4ImazA@W=TM+xZpxFIY`A^A-FF#Fw~M#e9ML}B z|HrRhjmOD&__cWa-g`R4^A7)@W4xY11v|y-Ogf@dy#9)dI>pCDyY4&s>%Jq7?mOb^ zz9X;hJL=JWN1eLws9*P8^n796cTqoAu}%E^{C5s?icFReMkMe z?--ZvyPo~q#oI5Wdo|vF{HWLBasE8qAs&B7icayogZ}9huV?zg&ha|CKhPy!|5qit z#K%Ru?mPPHz9WwAJL2oUBd_i|>d}2iox1O+KYHIieRX#D_k!!Te)2iNT+ii;y1C9L zz2oNk&vMw!eX+gq+|Zx<<-$of_fg?t^FllK*Y>C82Xo&o+V7@)(C`JJo&Jv$To{kj zV!NC8gBmXi?c^=C$4xy6B^QTw>b!rDoBFS?C|eG z)LgeSD|$QE^T=LquJg%1xVio_RGSlC%YD&qznl9d&Ct1_o%`r;#d*QpUk~3qKbZTD z@$&Bi?M0R@i1+W>V_`6HDim52O#D;(-Q+FRWpQYyo{x{Ysq^b{OF}#KukPVyT>FN) zxo*|Y^{oC}=ZeGiulU>-%FF$tdbp2NC-;}?=f2apXxDh@uj4=*9UtQBxRF=KlX`TV zsZ+x)Rp^1-}<)e>}^QaPQFn{ljkJd^3G% zXea)Cm6rvRx6aRQ>Uli&cae9;=77|BZMK{GAN|G6xb8ja-hHS-ynS`2O7Z?_|EL^~ zGrMq=c>FwdtH$&0Dqk&L&zt9}#p~SOpnAOi5BgM(kBfGVm;O2q#L@8~zK$Dtbv&s@ z$C)~H{Hb5(C3?Paku!deMEy(qa+WKJ-!JQ?l(9Oo_i)@JPaiF1`{%i5G%jh2W6wj{ ze@Xtdjf}mY!=*15w}v11eUvwEaeJtz-$&msD`t6{`@M5|V6iY>`qTbPS-&sne>z{@N(W5M!e3lf7FQApY7h~;^U%SCIM#d|Yd(%OAIF-HW6j6a&U{?`ndf57 z$Fb()So3kL`8d{m9BV#~H6O>Ck7LcpvF77g^Kq>CIM#d|Yd(%OAIF-HtDX6{`ZFKL znvY}6$Fb()So3kL`8d{m97oR=W=$-*K8CeEhP6J1wLXTmK8CeEhFRBQ{ReA(3~PN1 zYkf@ZtS_lQ>rPnfV_55BSnFe0>tk5!V_55Bm@%?GhP6J1wLXTmK8CeEhP6J1wLXTm zK8CeEhP6JXcGkz#pY<`U^)amVF|745to1Rh^)amVF|6k#=Ty&0tmh=wa}w)08Tuza zC$XNBSkFnU=Oos1Qtdn^)t~1iCJxUf%yXFM71nbS>p6+_oDBUFpOaY6Nv!82)^if; zIf?b04E+d$i$>p6+_oWy!gVm&9Zo|B<};&T#5&ll#s ziq4~~_bs&ReGAt67OeLzSnpe~-nU@AZ^3%sg7v;d?YwVMf8MuXy>G#K--7kN1?zna z*83K$_br$)^1cP@eGAt67OeLzSnpe~-nU@AZ^3%sg7v-y>wSybdEcV`yl=sJ--7kN z1?zna*83K$_bpiOTQKjRS$}xwnFl}Bx&+pG1=c!7=##jkpXvS%1Kck+mbNbqTEX3aoVuto047bq}od5Uh0)to0MDbrrRqVG)STDlV$$Al{e%6by)}MKnYW*2&{TXZh8EgF+YyBB({TXZh z8EgF+YyDa6j7$9)7uNbS*7`Hn`ZL!0GuHYu*7`Hn`ZL!0GuHYu*7`Hn`ZL!0GuHYu z*7`Hn`ZL!0v)Z{1)t~DSYyBB({TXZh8EgF+YyBB({TWBk7v|Z*^D}CF9z?r755oF9 z2=loN>!?_t2Vs34g!Oq4*5^T3p9iU(=ZyOEoWc4$2`aB5h^B}CxgF>Ig&x5c&55oF92YaI-09Smz73~L<>YaI-09Zc=4 zgQ-93U|8#5SnFU|>tI;xU|8#5SnFUodcH7gn>vrO)}?9Jx-{0hG}gK_*19y-x-{0h zG}gK_*1ELXS=Uv6)_XB=SO>;hm&RI`##)!gT9*!e64#|MV`N<#Yh4;^T^eg$I`m0g zm&RI`##)!gT9?LJm&RI`Ry*s`>d(3~*19y-x-{0hG}gK_*1B})lejL8^<7i`{zBgi z#cF5GQ0-XXH>S`3slWSBOyWoL{&&9jtM5Ehr{ae(CjPBZbSzlk>!y#s?~V06aIEi# zV|{NN>-*$5npZK2uXe2dSaGo8W97xF2bcZ-;P0Chllal^_WyVOu0elmz%fyLtoGrS1DkJTO>3)c6*>7(zuV|@o6>$~w--E33N|pInNM6(1`;R(!1ZSn;vqW9^~JG1nfgSbMZ$?a_+0M=RDI ztyufhV#OrBVq(R_iis5yD<)P`x|5JZ;Z9SG1mUZSo<4e?VpSlpInNM6(1`;R(!1Z zSn;vq;}zrU*pT{nhHLfMKXt73_ep~5->PGK%DMN=sbf#Z_Uxvfdr#N4M)}>P_t&z4 zt^As=-1|j4HQ4WkIzK;eFK_XCMDfX`_*n6=;$y|fijNf^D?Z-4E`z0g;AFV(`tDC} zllqug+Ct;?XM2M&#r#$&f4@|%X8G7rgAE4SlIh3Ch-*$D<)P< zte99av0~!#Detz)+dcl&BS~#rRr;RV{duC?YmdviVa;N|CZhJWPccom14UVL+N<-bRUP@(Ud%3BNdZVTiT^wZp9~;;$y|fijNf^D?V0ytoZoS zW2Nki3Ry$myhoq5$2PbRT`6IGia#9MZ?r05_ic86mcN9ZdhU_XzNtY8`**K<(H|wO zc&luoecZQC+w>!D#V42IW5vgcj};#)K306J`1s?DMQzi~d?D}V-Gwco>yyFv94Ta5 zFSsYxEM!l;l|QtvPG88b-St%Pon;GI<_YdbUlp?6Sqp^rT?-0Z?hoCHPcFsBijNf^ zD?V0ytoT^*ajI4?*uHjULf&Svf8*Zz$vy9RuySGL!pen}3o94yy}rAB z*WU9^UHOKc8szS3)6VTb8e{yVSDY)}^U?@z8f{bzXPX(*3O9pFYMfoA&@<869n_l~aPE#Wi2 zcP6YHZ{3Tz6`x#+j};#)K306J_*n6=;^P|yX4{#U^MvDbp!ggc*TMZkg}HXNqq|x4 zd3L3NyK&X|u|4G7X^Jhd1(zNVuWfekLOU_ft(e4DOstq#F|lG|#SDECW8(eaFSW{3 za{Kumw9HzSaWBfe+}_#!XlVa!%yN6Uh5L_#%PsZMT%mnyiWOF+t$R|+6?WiA&d^@r zkL7l?wR`h~<+k`lj?k`L%6zjUYqCd0lr9BW<_(m z3&y^$v2U)w*XlHPnZ1+CUAgfxdwQY2H|ueBsii9Hp4VilZTrUePOrOciKS`p-g0QM z<$B1iT;x?QtXx>RuySGL!pen}3o93Xed#zmc=vtbc)qiCtgZgS-(%dpXpHrr=>BHx zXq)wpd*>VP*~fj|FEk%zTPC|}*BxnTwz!8hA7M}2=P?zZT#AnsA1gjqe609b@v-9L zQ)MUEU#}z&^=Hg7!5Uq1*UdA*R`yR3+AFo4VEa;~41VN?3HJMY?j3C>+WEWuebJpc zC)wmK?rOIu*_LnJicc=Z$BK^?A1gjqe609b@$sypE9~B1)A{kwu+mCB^gwX&l&dV) zv+gr@ueLSK-0!4ZV^!O@7pGclU(|J%Ot#M6F5=F8VVynuugCmo%X;gy(XCwMeJ3#& zRxYeup-*BitXx>RuySGL!fzejWi5V48^-eI_TBbEO0VIuuYa=P1>Dbm{j=q)=uWd` zk1a0muKevU_E`;aAn!oBYK!!~G%-xvA29ky1Fx&P^K z*iy~*_wb5Ie8t3yiQh?#i4_woCRR*bAOSw8@(pjfv?<(PcFsBijNf^D?V0ytoT^* zar2aOtl8=J!~8n^gxPlK+~nZBHDdn`-Z?dRTjAOEWVUI+v!0u6jZ04t{$S#4%l_hw z;1BPaW3B3Z5S(lI92;Er!{9DG=GuoTX9g=5d6f$*7gjE;Tv)lVa$)7d%7wGuC}pQ! zt{0By{-kAWl2;Jzds%pMN>D_iR$u+H`goDp=OuJo{2;AH1%N?dam} zc&4II|Sh=urVdcWgg_R2{7ry>QIoor0#Zbf4WU=24 zo?XG~Pg=o#DCq96se&!tSU$9;$yw3PKkeRMs-msf_)KUok+h=SUBdl#p9=Qi$Ns+e z*y8ebu##K3$g5nqXJRg_Tv)lVa$)7d%7v8+uQ>OpJ@Iy-P}`i1x$H_(_Z`J@+PoPB zL;K~|vs;0x?jgM&u{3wPOSQ;qkMH;QlZy&uwzc27lU&bemA`i@KDiVhD?V0ytoT^* zvEpOJ$E=NPU+KA6GublR&05O2MQ+wu?*H1&+Dos$-K@!+dfLarTFuJ$+^pfu{L9VS zPJvc_Ojz?7@SB^pptqV94#$TzqMe7`s)yQC4^}-`^kF>inZs8tYWJQE=hY_gmc&?)w*{vn4;e+YV1}bMI~(`aC=|gPncc{l@r* zY;95ZbF(tr>?hql=47?AY20Z?Jz_5$^f<~(4a$p^7b`DTUaY)Wd9m_h<;BX2x1`8x zZJ+fT_GQgy<4U`C=E`p$W_7=Oe*tT7(vQiPKNqw#bKO1L$M%_j&YkhoBKFA92H`j; zCh-*$D<)PB-jXmDJ=G8UUE2saC$@W*) z+IJ1zo4T#DPQBgfhpxBRhq|jz-C!f$c7HW*qutZMooDt(b|Ra5z_3lWY`4eP@7=Th zsd}ibaAG}J^CyCRNQM=GGe3UyXAA$_7gVPUwhm&Cakx5U%C5@U1vXh zo!CAuwy(l|_nzr%tZ_1rlWxOmJN1lv)X`Noc9dJW$g5mfxv+9!ZjLVMbVOYHUE-1|~3u`7*zy{={KZxb^fa!)?9 z*t)dMANngM@f8y*CRR+Wm{>8fV&dL6X4$3HMMC`N&&;&t2i)y0d}wEK6b8TMp{;-Ovf$))&M@v-7##m9<|6(1`; zPT6d%jeNUw$aTldW32gL_t09StBRtXx>RuySGL z!pen}3y*6)(h?@V5c1Z^JJKpW@M7@anMYc$iS8eZjXYtO$0 zsX9MnCnq-!bw0SXoTW|QB=}0na`x)`?g#xmSZF?Ze1t6Ig}Z9<<*tE*dy+HU2g2Ia-digiUzi`}}%oi*RUp-*C7oGG@)_V*2ap18ixaQh&myZ5MJ_U3V)CzcsI)CO&Hrx`uO-u&EMWYl0A z_PzVa*g@9)bYlCQf!6C`k8}L%0oJ;uTe--qTv)lVa$)7d%7v9Hv?u1m%7t5`sb`PX zuOH51g$HB%dzEo_y}yqAQq=uw>RR?q1^4WSUa$eJ+=a{4wDRw}C%jw3KHKkp`L60# zuaLh--Scr(J2%m-T;x?QtXx>RuySGL!pen}3oBRXljoF;TAeohX2Gf)C++w&_g@)K z*r=)Qf@zN1pylo&X^&a;J??(Fj@qtt>B4IZ*8J1Pwfv9fSu`OrK306J_*n6=;$y|f zYeycmVx7~6TyOk*z%p)gA1iynZWewpw6EFnyER$hUe@b(>zE@$X#e`f->t}O_q7*( zw`nRmuex8{t z)br@9{dQ0KM}t?rwBMGEarb#@zkQO%f8)M$q5YP9oV!PpSo{5th5kcU?6)^Yy65Kp z&FcT_KKJQwHtm(iLmxSs7b`DTUaY)Wd9m_h<;BX2AFh4b-rwQh&1>4~Z|gSKy{3Ka zcR!zV|K8*u`*5p&$1lgzSM6eUcjwDjtwz1y!`j#QQP=F5F24mgxOvTrblV@iwET6; z`O3cFMfI;+k2=2wD=*i!@?z!1%8Qj3D=$`Fth`uxvGQX5_AX=BZ|`FL_Ab_M?}qlo z-`>Ug?Om+j-o^UuU99-zQhcoVSn)&q|I6R@)o&b=OTTf9^&7`nzj2K98^>6`ag6mF z$5_8vj1`~S6dx--R(!1ZSn;vqW5vh2DowT`Lz{(bV98Tcta|(A!Bz82wQB#m-+f}5 z4UYW=JoRKPFx@JZbbnA_hHd}N`+T1J18ZBzJ>Z@X?U~XZv*i8{t<4=x!)tesnQ5bj zHx5=_YEWLRyjXd$@?z!1%8Qj3D=$`F{M`>t?ALF7|H(Oxn_0_DFNJ#YWoTio^7{Uh zv;J;rW&d*5JJ;GC?C5(@-g&vLoqgY}IK)&OtT`*L@$tn+0FC7Fqq;=$GRqd!@Bs z11Eo|ZTo+15?-q~j9qcC;$X$Wih~sg_Z`~EuH5P!V$RIf*giV?R`9QF8rx?d_YAII zt+A~d^+xc~9gVDFhwi}_ZZx!AZC?*=|8oPoJfcgmVlrN}WA(?1gB2euFIGMH{V|R0 z^n{rqeu?Bwt?0oIgLhSEW^H2gZSJWxC7Rp#y#86n&Oc&*2UNsA8y_OKbVE{FEF z|9!)1oV*nL?5jO3%l+>1LwZ@gEEhw2@fvSg>U4hvzq#fuJ9ERoJF58PQhcoVSn;vq zW5vgcj};&1IJ^;zxA`_F?c2fa z+RV3Qhy32DnQp$d+xbpt|Ka#NTlZtX;9E!MS?{y`gAd03KCj660l~^k4a$p^7b`DT zUaY)Wd9m_h<;BX2n`Ag^jsLh3YM55#jD26nJ-GF0tNo{+ySm*@*_%_{(|Vn>OWoaR z`<$@(J=~)P9=CU=yA_l8iis5yD`x1E7!xZdR!scij_>TXUB0$6`_1odOB;9EtKZvK zr+h7_*^Arl<96=sZ*R9M2mSM}ygj#D-n#BFRkmA^?f$*5MJK(EbQGwun70OxOK81qsPw|YcDp4eO!@cEg z{*Oh2pQ%y7UZ_w!STTvOm{>8fVq(R_iis5y6Py3fzenVxAEp*wkExNknA*vQ854D2 z#!7uyF^R93STV6;V#UOYi4_xbJ~_U`=R9-VG3TH2fw?X?Pnhe4^M|>PIIo!Ni}Q`S z?zj#x*CW>l<~rrN!OBYw%8Qj3D=$`Fth`uxvGQW&#mbBMOtVY6N@4xvrB44Od_LKo zs?*hk*_kSb_QPqeCv2GLPW9Z)gdgvEHne}4=61r}uelHAPGX;Z>fUkrPTQWOO6c>^ ziDcHTkXyOPt6W&QuyTd=#9UapuySGL!peo8-ImlgM?y!q%-RBzIVVg?&8uHe`cUbSu?)&dfVhI)e zI~B@H4a$p^7b`DTUaY)Wd9m_h<;BX2OJ$vF!{4nJuBEI==h?TP)D8aPmwDD_iO)4E zO`2~P8^09VE0$Pbhkx;TN|KKkSn0=Wh4#Lg7ut=NUI^}2FSdtY`yW6MevwiD73ck^(xV2cnG5GsCOIYJM8-lx6 zFJX5KSs(n%lO=3-+jYS|EH7?to?jcB?}uXcK;<>TgQgX=t+iJNXUI^*K7YsG+bb_M zC@)rCth`uxvGQW&#mbA77b`Dj4QglY>Y<*z6|dXSGF5|1-+A4V7JD{$$kc1Lx>}{+ zPf}g8X9xSW{a(YX*7cHK!=p$1V z|GvBXZJKQD(z}N*dfy7a=q^2fl5N}IR(x_PK306J_*n6=;$y|fijV8RvcX0#^Xst5 z==Ju|eeOSIuCpPN{F;1V_FBtO**$Q|8XJ<;efN8-?U!usp+i>LKhL{=7{1ch&3AYF zV1;da)MF|ad6f$*7gjE;Tv)lVa$)7d$`$%_o@KR9`98Pfw$8FG=azsr}}e! zVqFhd*9q43gLPeDU2j;|A^x`SD4RLnf2Skqqob_<9QU2ykBoh%(cR^(k+$rSuHic0 z{?te-G|b)N+z7iT#p|K{;g3heetXD0W5Nh~qhhzvp1jWp>vhqcvBwCzy|8<{eOS{T z!So-I`i*#;RcqYDzg+dr&`#bRTin!Br%=z(PMvl8x~aeKayR2@VeXN?{_plth2D$z z&o=nIc%097ycduERGQK8yj?4eHq~?S)zR@fhYlERs=w#EqvPYEUE`&{jstOYe2A~( zMqV9H>d|qgP91;h*LjJaFInf2@nRhZtmA`q+^~)()^Wz1N5+eFUNGm8@nW4vwKHDz zXS`U~1J-qdb^TynS6J5@)^&)ZW7Kh=UB?IOxM3YntmBMz{ISjp*7?FZk80O=b>3;$ z^?-GqU|m00*A>?FhIJiceTSU)QTmQIRy+SDsvSqa7cJAj*t2P3zlB{O{C)kfSr6FB z1McW|yya+rto~Tvd6u5&YsTWe)~W=8~pNfp?&3_>8$ZPHG-4XPiNT{SNHakY3-2%)qU z%;=QczN*_O9K+$qb6B5u-O=xg%hCQ={c&uj82=u){@x_oP7P|u(ZAi0>Hk}WlJ?cM zN}--9_Y|{Nzj`(}NBP3`-JgEm7hW!CTeA2y^KaooHmQMMS2eE{wvr?KI?Ph4xIHkd zR(Ngn?^EPxF05Qwxv+9!<-*E^l?z8dN0Vt!@>FB1Vl%@YcS(0PvWHK&*K})SZPL#Q z?Q*m~R(~A*tX8Hy`uXF(ZR^{fQofh(@MiUF!+PKQ_tkIe+OpKXKk(7nb!|)Cwqd{D zJ1^F?(X(3x_g`1f+9mTnkk1~eZx4=Z8rr|<+0Y6$Y#jVi>@(AO9UBJ!H6!-BD!5)L{rvCjog zx3=!<>)MWfv3(NGw6T&O*0sj({m0Mu^;tjTE!M7+z0k$inrbBPVCg&gdf<~o+gtS= zz8;mSLONSM`1>$+t&Q+nwR0TQj!X2dVFhpd^(NE5MX##%T3K%|SGuw_{@kz6O$W=H zjdsuNSJu)mbe}C+$`+*b{wE(QVSU!R`&KGy@67Z)Gkb0;WaGb?6Rzz&pB1nJ*?f=3 zD#f3&q_chR$2rCGTbFXakLCMYpR|pqeedyCFFt8kru&}ihgase!WEZ=I4|6M%0Btg z_eEd3y`YURw=%Rx*J|YGxUj~BH7=}iVT}uGTv+468W+~Mu*QWoF0653jSFjBSmVMP z7ml8zlpSl@#on{Sxo*C(4DD3o92^F05Qwxv+9!<-+=IMi_hKvm~|CC;E9%^z#&%*Y=&0 z+d4f|He3URERPi&=Z<~`BuD#W^~d@Q1#e%U!ZL66wcqQnC$X*reXX_9eb*CydZG6WsNK)s`f?`>$lHEX$MbW8GHRv*v!_;xhYir@!{=QL*2qZ~RPn?WmedtZ4lT z!8c>S*IIF1rQps@7TFiAss#VIX`#Jbt9o$s`wVilHmusPYQw4xt2V6Kuxi7q4XZY+ z+OTTF`VIrG`_nNy{BZj498f#QP3=+Bzy0Rp*6^x-r|!_`6Lxrb+VI+&Wlq}CU(*Di z{OY7Fx{^BhNX}DM?(99mFTQ-r4t$p~ct`zHwrFhie zPg;ecNrDG1Jz-mC#J*z`tKri_$L+DjH-o!fJ7y!QTn|oh^Qaveay59!`9E!D_kV&L z?LT6?KaP%yE{f;ASbv0#k_Yb;n}!5RzJSg^)|H5RO~V2vee#>IR> zV~qAuJN;$)GZ$fAftjN)-@wdWn1=+%zK_QI1nafL(QC0@i}l*z#Mk2JcL-%-GT&kz zMIYv2%*Sx_JB@O*KURON?-pYHtwgk)m}QDeax3)Wb$ z#)35#tg&E?1#2u=W5F5=)>yE{f;ASbv0#k_N59)IbB^lgYiEaIe>*^*f*W78RiC?G zexjp&*vNgeM`x?_rLQBk9^TbD#eQ#*{`u;6vy|!G(OhygK306J_*n6=;$y|f`kMl* z{oAAM)T4GB-8)^T|7*81Tjde^L;ZPHWwx?6ehrT95AaTda2as2xZ5iIwSp|BFxCmA9S<>+>_al(tJd@&rHFs;p&C@p$mrjOFZ;!nuQg z8(G%6HOUox<@3^ZWqgj{=$^N7G(J{*toT^*vEpOJ$J&z?YoFL?J7ZKkj_$cC)BlOn z9jx}PvZ3bpue7#G2i?)VVdZFlto~Sgu43(v8f~Wrwd3f1q%!?~KQPi>DqAqrvn2Zn zOTX6r;@IIfwPvBvp1b5Q8+KRW;Ny=DwOM=J9U2d@6Pt^K_I7^^wjb6N4X$p3?Uhx< zg0r0+Y{Qop5037?Do1O;ssXD8tQxRtz^VbO2CN#eYQWJwPG#CVmYZo=^ZB*+$Fm>U z>_jhrdAjwg=k0&?nra=ExbOaKvSrMjH;ik1@%Qb{FWsw;PqelD{CYn8+XUNDH(%(p z_TdRu`I#q!qx-nZ(HgL7z^VbO2CN#eYQU-is|KtZaCF~S?VB2H=bBMFj_yG!)BlO@ zmRj!(S;Dv`ZCGlRevEzJKi2<|TFY#~v24N7eN*M=Yq4I7^;)dIImP;$+-N(w)Q@Mt1W)gF+@|Do54iV)JyPOyXdfN>+oFucPPsRqutT{{22a_2!m8bKA~@4WC#=q; zW5N47ov>R+jt1Yja@I_b- z6RS?FIH>7#b~N57*e(?7+*nfA^*E5g5heczvH<#MeG zPBnR^723Hvc;TU$_C=4i!TDaFW#f{s4{lg_wtd@sL-5U)=GdFxYz)pcWv-q0{iEO~ zlh3zfn>Gb^cz;3cyYwFiXDzkJW-WA|Il9=IuW?s@Z>gQ^?*1y*a!Ys4UmN{yryQ*x ztA4EdvFgXFAFF<>`myTAsvoO8aU?{y&4p3wP%ja{5Q{B6jo zBj+qb#T>x}$DOqb*W7>gJ7YJu=JdZY*?8LeuE-T!sN8AmI_uHkX&FviwyC*;6_d|l z6%#8aR!sb5Voa=F{v})1Cw9zY@t0)1WQDI~4W9bZMSHxDdtm;H_G1cnihh4t zu{l{nANfBYL)AvRYQw4xt2V6Kuxi7q4XZY++OTTFs)w=2w9kC~yfrQ7`%z~)bL3dYuP%xw|sQQHsx>^|N68QKjHhdRQ=+VW%}|z`ad5- z)keE&!>SFdHmusPYQw4xt2V6Kuxi8qRc+CIW2QAeWxsAr8_w4+qfgmdbE^->S$(kj z;OM?I(LH2jYEU1nye5wou!O83(Px)!6%>Sf6E6 z58AxzS%P!lIAEoc`ZcCF#8(`wI9PG8;$X$W+RFv!J$uk5m&+Tj6PX&+2dka_(>^(5 zdFOin1&a^cYnR=5R{de83p^3xRQ&dc{rQr6^07ayLUZ@x*m!oN@1#nSF!yE{f;ASbu>>cM1#2u=W5F5=)}CPa;TCnR;F&hz z+9*_^r7bMfHduRhMf>v}L;bP(WA(@PWqH@CENl|q-^#>UTXC2TUF7Z4W4~c>XotJW zszKHwQ`68tQ|f{Cr${~u=XFL9ywYARt;D+VAX(C16B=KHDJ|%RRfNWy<+JR)@Hu%clS=ck+x!lyHcA` zcA>tzca!&Q^?mLQB}QA$)xK|D%k!fxZAJIBcgEOHU-{m%r4EjQrOf6|{`(kvY@F}q)#~jrW+~kRPK~zTNBMUq*A^OWRUUBmAZ)9$=6%#8a zR!pot)3EkMjJ8vQ+HrKhL7D!KRViM5h0#{6AX9Z+(sBlV^5X{tfOA>uk5f+udn;d}n{8_SfcEz16z( zaOcUe#S;E?w^;FwC0Xq2Ff#{zZIe3tI!u}mzp@8v_&Us$q+eO@V!jSDYSWk2^a)>w z+56d-mON*PaPAgm`pVWn_;m2-&%ZMJ*L`X2*Y^3IlA*oCsc-Dp$)$o1Hr`^NmMI+^ z-Jd~@juC5&SYyN*Bi0zP#)vgWtTAGZ5o?TCW5gOG))=wIh&4v6F=CAoN6%gHJU?0f zoQ1-_9e-E-*@isfuJp-rK*}!3zaLpAmib+Kg51K5c%r`y0Do&$rLET`Um# zbo*|foq5~6`kDQ9?>|q4_H~0}`_6T6x1X}#8twNzev7}o-%`|c-<@xNY%fRO2l(mb z`)qq`eTkaKCEI7`xB0%os-J68^<&kKRX3`ouYhB3w)YeJX@@IcW?QJpH z%GY3zacP=WF6z&^zH_Hrt-Ag^jP4yRNAqIk#mbA77b`DT zUaY)Wd9n6_#@e4b+Ringb{yU7Sf+ow;-hTb9RE9rMcqc(-ueFb5vS9QvffLog>%{| zQ*2-B1pgbEl%w9Y496>n_UOLNax^AZOstq#F|lG|?U{^6{yfeaj`RIA)XrGc9yR?3 z?HF%=|LXm>$JWx5-0S<(zHoJ--OBAA`q2B9<8k*7MJL-UY21q{PqF?7{k6xQnQDio zxbKYpKFqwb?&tSUvtd8@ULV=JOt&9icBkGm-HPt09iFAP@10?vly|?FZidZURV%dr zd~~{1$mu>de7gNI)%PBWjz#q|F4d1!KUV!%^<&kKRXwQbC+ddngiS6~f&9SZPynWfSSym-6&aKol?c13ibN1{HY;sl4JM#4zmg643p6?qv z-R?Q+o^o`Wwc7bysBP55X=Y#g^`CRnH0%6{{|#E*Jm7_r8PHAbv4 zVvP}Nj96pD8Y9*ivBrosMyxSnjS*{%SYyN*Bi0zPep3wVcfO+SoNKjX?L|f({gx9} zJAKrSqrb5w(?9>I9aeGw{o!29ShCG7Jmbz&?&Mb5<=(ovA z4M`hb8~yDtIT{};K306J_*n6=;$!`W7uN4>McWyp+HtQAf7ut4?+&%e^iMk=wyyZR zx3?I4)}G1lt~U6zRV?Y=GUlXx+SNT|{c%gb%iTKZF?+R9@(?rQ&_C_7yHW&it9HcF z?{t6r@*g&ERm#v_X!T+1IyY7Du2zTbvsw29M}Ox_j@E`%8&+*twPDqURU1}qShZo* zhE*F@Z8&9pobQY6aYGI4?OgHH zwP5yqeq^&-wNZoeV&%okioE=M_-HeTCCS%{Wdq&Z)Zo_sZH&;&d<-=%Uk@I>v!$xuXg&V9rL|E z{f<1=Z@a5qee@ga(cd4JiN7;%CfnXNbGSA}-;>T>uI}b<$@#5z;>gkdSp9MIx9nxw z_x4O~Y3H2?$20HY*l)pib*HJE${H5_kB;`o>W}qXcsNI%v-Zct1K}D|J9VlZNB0qx zd2QKTORU<0?xCKhrI*^b$+`u9@Z>V*{`wRhNREqt1sF|$zz`fL>%pp)gNh@M^)xT z;OIV4ax^AZOstq#F|lIeXl+NQpR>m@-nRC*>cOf9tDdMiR@z?No4@Os{;r$9>#3Zzx%Y|vT~F;J?y6^++xopNLVKy)&F#kJmce7k zH?#f)S_f}_x|yx->-*;Q&)m#9>}?xw&sn%#ynp=x?SqN)+b6FE6F=wP*MgVC@($VF zA((o`PwW`{zt}tL_o~k3>*EA>Eydm4p-9o8gfda(~ zh2ky&k`NLCE`E3}KF@T{-0Plo_ME*>&e;b#s}>k!IiCI$6OFO2 zMr({SRq5m6jb`rV>*2l-=YEmT zKA;Z!gZk_n)@47Thkb@l_81@rj;=JNy$AF*FBpI2Z$-!$jL^AH?+kL&~D><^fI1GArC_8H9n zgXs&Heu3#DQON1V?GFrO!2K7YV`UV-_1)0_{_Lohz`KY7|}y;o1-ped5Pl<`HM ziSk*QRT?jy^BXz8c!lzJSH6-i-2;?w3?3qHw%h%+B9eH|rI~&j&wi?pM0tOc!~Jch zob4sYI?YjDn!lG|J;t#f82MNaj5=5kjQUs)jDPX}!T9gU1LJXcJQ($`9vJIjJuud1 z9J-hfy{viK|iPyeWHH!kNZNL`$azcfI93C>a%b7m;J>m}qm=Wtp5XFJE}1BQ{BHMQEAr1I$07TCrS<{Sb1h`BWDTCKkF7a< zur%8~O}W4CV7aBT&Ovv7LJyOGmM*b9wq(n+nnz^aD+_FV7%tUa9NaXzUBu`^_5)l=PCQg z%#pG0?fEdoXR(BRvRLDl%lXN{v&Ib@ERu*`mUE}ULhqht#z9pV$fQs0wdPWR`EsDD zarZRyq+w~}zkgaLvwNC`uImG2zxNw>n3KgX1<3e8vy=mF21wZC*~-0t4v@?Kw#Ry- z10>F-xf;KcBtUv^G|d4c{H4u8+Y4rV$DHfrMO2pHKAyLK99gTJCEo;j5x7RV{j{%T z)WucGTPF^apodSLu_~fH z{c&CFn|ja>>O`Ng9_piiSP!i65Bo(v`+z#^59+gT_?P{}e`lZdaUc4R{?Qk#gV$!P z#d8}l&uzdww*m9q2F!CCFwbqkJhuV!+y=~Z8^*C7^RXV7=Qd!T+kkm)1LnC6nCCWN zp4))2FRTaVxeb`-HejCHfO&2M=D7`+=Qd!T+kkm)1LnC6<5-XRSP#r|8!*ppz&y7B z^V|l^a~m+vZNMM>vSaqY=oh`iyydY5=CKCmu?FU`2IjE_=CKCmu?FU`2IjHGIM!o6 z)&uic1M^q|^H>A(SOfD|1M^q|^H>A(SOfD|1M^q|(>pMaH877gFpo7bk2NrlHO8?X z^RXV7#~PT&8kol#n8zBJ#~PT&8aTFJ$-MV<)~y^Y6|bfbe&YQW+&8<2Dwk^1QR0RB zDwn&^QSP-Fp`16oqdfg%lyZh`9c5g(G0It^J4pI@W0fBqZzmn54pjc}YFjB>y}xpW z7Hy^P-+h$JmTD_4y?g&*-L<3J%G?*-m4_EKL#3aj2B@?u&>$RtcLV>1&zJ-oH+lXN7I8UIBAt^kL(^%@@kDN4Dy|uyPu1}P}D#oqmjFD>l?6E(@^Ob!4)@n|l zF8!tD;8n`c|LGx@F9#_5Z|p3e{klXs;@+2X;){jKrw+A~d46-0YZYlH6J)w_pU>Ni z@3TqDc%FayaGmm@eBM3Sry9@u`CHl8)zw%Gv^}wiu^}wi)^}zTS{~wJ1 zjyy0PhsT3a4|Ty<2kU{cKI72EeCTBz?1S~OKdy^?QxEzM7%r8lT;Wo&0)`)3ajpV5f6K%`6#1)@_;1DSa*VNQf275n>(2@bY2ZKhW_E<#@JVlRLM2x=;R45 ze*NMkm;Xilsjkka(bHW0gga-rbx)?8<@EfRcD7LG<2|#5`lmja?e>K@_ltb?0d?3P z)MwwYF8c{R>@#$-|Iklg7ClKTCrV@wE_N7((D~0?W9aw&*BJY%5o!E>e(ev!{UpbqZeTGiDu(eZc6(6c??TV?3n{o;)>^p7lKjC}=%MQOa(>j^F% zaCoxIuh49otCMZ>3|Bwn_E~P-p-tyFJp;VoO`y(=HRn0~oxR^;z}$dN#JOMOvk$1l z{-8elhIQFb=wY9sll_N&`og(^wKz|}oHJm~A28<?B~0dxL zeLj$kJ?>o8LZ-Hjr#kPnZZ4%>+vnf5XKgO&SKH_12HtKib!sKnoDo}E%EK!@%6u&L zbv#i^i3y9V`}$*QOBu8{uI?*WR7>elH?HpM-(js}PIMgApCLmxiJBXw_dkE-T~{rL ziB>*+u&w-j{=IUQnce07yGX&ld_L(Zmxe?N_BAY|r_?VTDcIMHW4$EP{nz@L1Tyx; z-%17#+dWVgmX6TB%lj1SCrcxZnFIZwKO82Ny1o+ll6Kf|@h|gA;7jBo?{AOkUkQ8} z7coMom(uEQzm!8r> z;`WNCTq~rN4Bj6{dBEUya;@%rfwqTFI!ci-(aNvuc9&%tqm=iz_df4X?6q>CsKF9* z;+1mjJyz~FPUij`uJNh;Cdr9nmb3cZR5@NHLgVvV&y>-3tj@1(=Sb=b@fOO`TQSO)r!A7W8{?|ZAw&G6;8*dL(;x7Y{>^NUyIT9nydt*uY^@ea&(}Vh zll=PyQesn5<&$&gNxCA|!^ih#i|-ig?STt3q`@rf`RZZb?`pL$FXmjDC<#v)bC395 z^IyJGWl7=)^>?_>B#HOQE9LHq#>tQ)=6l~J)1*|#2z^e5m+Y@e$f5r4K+Nob#$WDcH_exEOpv4QXP zIXQpl0{OXVj6Ns($6Y8nZpP?ya#rJoQnG>_Q;+uhNv1Xl_4xYrYdlob ze)4H4<4k@0Btx`){+2n=Up$qcg#MXWXTqX?7D<6(J~|Wr^z{5N)<$Y}|EG?8mIa{*%a`w8-y|2CfhWARU@gG8F%P%8SsQyC5XG^gwq$Gq3;M=4Z4 zUZ?slN)?>^LWbZ%2}a1ve#U*`4VL3CQ);~9kUp}wm~oNu-tm|xg~pS2>L~HACR4sw zrkxz>oK!h|p4Jk6*hks7R!f-@l}OotZ3{iGz*>mU=osJSXI>ds8Fju3i4o+Wewv84 z%2;<|uQ$rj6VfbF89JvOi%^FCvX@^eV_)^A8z&E%=;BYSPIdXd(`L9j$-bTK>M!?x zXNv0<%e%noS-O3pQ0Ie{i=6%o&lb6TA}HkLJ#{4o$NpK(--V3 z#S!a&#`+^=`)cF<-uof*su-t9?|rr;Ai4IlYO&suEZ96s8rn@h+hrd0n%r4tj!2?8 zG2Z)-!?T)SQ-^#hGq#vt@gBE#`$By34)Y87{#D}XV^L?)%{a=aAJEvm!@6-wzEdxt zXXn?^%Fr2I)_jEi;K5POuXja^Gi06U;!oa9cKMn1Pjhu96`1Mje^O_*TX*o=IZjW` z8uOgaPKo9_{W%)Ucl$z|`$azcfI93C>a%ZHm;Hnu_8B_af9R(#xX!wMJ6mwv#@T`& zR8Ap3#Pfc;#^Y}fCYH9{j6a_lPcB9qhaZd%nsh3=<|N+`78LVW4&{v*o(1_v=Ttsa z^I_1Dy1AAAYIHB?pUrucpEbU#*N>==c*zO*U4Fw`1(Z=IplBgw)KAu~urk)2@nsQZ z=qXpUs4{f!J8BI5&GHq~IQCVvj&Ze>nO%Hi&g?G#X5&1r&erGx!uqQd78S1Byip0E zo(2a?33W=zGD7{ucbC!YN9+r6?icy&1M09psL#G(UG@`t*k|Zu|Dm70@OmF>@p>Q3 z>wPe<_rbj02lIL#%c-Ust~pK)9-GauK{U|#QodA$$j^*)%_`(R%0gL%CV z=Jh_9*ZW{z?}K^059akgnAiJYUhji>y$|N~KA6}0jN^Kr`MBN(^Lii5>wPe<_rbj0 z2lIL#%ipe#+17KDSu6#YJQ2De%P(&4JFSb;i)2_itnDEBPbi^EYd{_?|(vU4EL|pSwEi zO4oJu3%0K3);(9FzSA=@q`uR6s$B!8f7RFqZeNIVzsP4FP>20NefACOvY*hyK0_z_ z5B>BdwqInN|Ij-yy#v!bFueoQJ21Ti(>pM|1JgUk;T`kg9hlyM=^dEff$1HX-ht^I znBIZu9hlyM=^dEff$1HX-ht^InBIZu9pmth`S1=*@4)m9Oz*(-4ovUB^bQ=`uiJOu z2kl){U$1TJ?u`!Gw8D6ne`HYAgT^Ozy$afR%Xn+bu%P+b8fgBC<1d0r^)jv(8WPm{ zuyM@NXF-E9Hq@NvzdQ}vINEscn5RLJH~uf)sO}ekVv@hPXiJQ z_4LT%Bh>lBWFMjanVWrt`$C-iMLzq0I_wYXvu{|J{e&L&89Ld2=%+8S{UXCtdIzR= zV0s6pcVK!4rgva^2c~ymddE2S&V2L)Oz*&`j~;^Q9hlyM=^dEff$1HX-ht^InBIZu z9hlyM=^dEff$1HX-Z2jEm=Ev3^bSn#!1NAG@4)m9Oz*(4{i@S5QeNN6pwHXY%U;Xl z$HpbjM#zMOc3;7mj1lsvr17D_ujIl2L=K0jCD7L8bi;5Vs;-n=!|M- z4E^(m8)ILS#~ME^8Rg;~UPrn7*?Zo&I_KL*yZV`)M7wpLc75yg1Rr|qbUuFi*6Ba{ z{;k^=;@mIt*$32Ne^8%&!@BGz^svv+$^Jt>eTnTCS-t+?9hlyM=^dEff$1HX-ht^I znBIZu9pmth`S1=*@4)m9Oz*(-4ovUB^bSn#!1NAG@4)m9Oz*(-4ovUB^bSn#!1RuB zc*lHr2c~ymdIzR=V0s6pcVK!4j_uc$PYTO|`#JTT?aN68rEAh$%41*UmqT9}XPcN$ zI^@o+@i`^)O2U+Rl<_bAKaMZ_cjSTbI6NMVdZ-J=I#`eK*Zb{ze8|68vzW$Fr|iMv z%BcT)qLRv3r%|C&%2+2NeQ9N^v-}rhtn;#H8I5C|Bh8Gl4&zvd`B;Z_unz0vU#^S) zPCa-Wb)p{iV;$}baqbuS>;vksKd8^XVIB4p>#)yQhyBMo^d+`mWOz#N!1NAG@4)m9 zOz*(-4ovUB^bSn#7>6e2Lo1lxf$1HX-ht^InBIZu9hlyM=^dEff$1HX-ht^InBIZu z9hlyM=^f+H!F=cg(>pM|1JgS&y#v!bFueoE_A7bBZkf`pu0B_L71}MWrW!|d-zD3g z8z0@W)BBD1dYUsn&Q6J%QD3?8kR38%TLXJ+)OJbzwxP1$`t34wXd~r5gSJbPca4=N zbl5H{mo|0rCncJ@{Nq91dzap^*~_a_uv9B$)IU7Yem55D)(EuUlZBqg^X+$Lp>tlf zcJ^3L|Gmw|*w_9)jraYs$HjBc-0SjN)ZXXnEPt}k)xSR0`z@yr>+TEP@AOPpM|1JgS&y#qr(yaUraFueoQJ21Ti(>pM| z1JgS&y#v!bFuh|O-Z3BEf$1HX-ht^InBIZu9hlyMWBY~IKEB@JwVrbo=K!3yI5*%N z#yJD$GtMPAw{ecad5&`x&Uu`xaQ@?51;;#&FT^nmz{tmp0HY3HUr?W~J6IR92074! z83cw-zJ5VJU)QiNzTV-ro^hN5Fdydztb=m~*2lR7*Tp#o_268EI&rQ-{Ww?Qz7Xer zk>Ji)KcRpM|1JgS&y#v!bFueoQJ21Ti(>pM|1JgS&y#v!bFueoQJ21UtoUeEE4sm)1 zrgva^2c~ymdIzR=;MjiQ{YA_&{EZdwyQ9~ke$VU~gMJ{)El81KVjmVxm; z9A+69@55o1f$=^ZW*Hdoo8p*f9J7G=m=R#q!R!E|K4uCS>tfb`p$9Vv44s%|VCcsz z17ly9WnjGb#yH-4V?N$DWgWb4%KCWUlbHB)EA5e$= zL4EcO>$0EF!#+bN`w#u}CAMGW`#ZgRVSVrsOdrAY5lkP!^bt%S!SoSKAHnnyOdlCX zADEB+faxQcK7#2Zm_CB(BbYvd=_8mvg6SieK7#2Zm_CB(BbYvd=_8mvG7cY^4$RCK9UmLN_-dNW_35hdiR-4yl}g5az29j% zGS=9)+7zksm+^)}ljT_PZknI0^<vr7`lWckiJ& zsPpPiW7MBiq^HKQ?z?fu&~x{QF?5y;HHQ9fse5TY_BA`JaR%>imy8eendS1YUY+IY zgfE}%>OcO>`&;UVb$|GMj?>e;;9RG3U(dNtzt8BoZeNIVzsP4FP>20NefACOvY*hy zK0_z_5B>BdwqN8wCA0GpOdrAY5lkP!^bt%S!SoSKAHnnyOdlDCkIaXUVEPEAk6`); zrjKCy2&Ru<`Us|vVEPEAk6`);rjKCy2&Ru<`Us|vjKfFf!$&ZE1k*<_eFW1-Fnt8m zM{tuDE9HKzw)$Lska(q}Zfv|Dzjt5I0mivnE|V<$p7GjjOYy(OOr3_RF20NefACOvY*hyK0_z_5B>BdwqNAf zK7#2Zm_CB(BbYvd=_8mvg6SieK7#2Zv#?jTZ*pmUd^1OHQ~g z32K(qoT~$FOT`1mhz}@KO5@1SwA>hVPRB2;an$e7!x-ycI$#Vv5@`&bNeY+IeCV%S z-x&Mq*}`~*_gl=2hYoq<^1Ic3?CN|I?}@8FZ1WShZjEA3ou0qvKXp1QoqX!_&%625 z?F(`47y0Z1>aahk&%R+@_7i&8XXs@Ap`X6Q_KO_bM=*T^(?>9U1k*<_eFW1-Fnt8m zM=*V496mB1K7#2Zm_CB(BbYvd=_8mvg6SieK7#2Zm_CB(BbYvd=_8mvg6SieJ~9p; znGYYq^bt%S!SoSKAHnnyOdrAVZx@udlRD}1wp<$Tvq^J|r#Hzbd$$^I-JD0>Uo{?C zD7W0t-dXc!-^eN5h8aISpF={<7)#0=vazzAufAE5U7Bq(ZZ;^pOvz#ArHCK$Ge&-o z1a@AEI#~xBqyFYo##lFZ&JX9Po}Q#VjG?p5Vq@r^w$~W@+7o1ac5h)9|8_)Cm)|K{ zaaU)-@)EB8*t;d&x>;Y8a(WsbDD8A6FJ8v!KiH;>+ZW>8FY?(3)M0;6pMAr+>?icF z&(O*KLqC0q?H4(=k6`);rjKCy2&Ru<`Us|vVEPEAk6`-9IDBM2d<4@+Fnt8mM=9U1k*<_eFW1-Fnt8mM=*T^(?>9U1k*>x;Un|mBbYvd=_8mvg6SieK7#2Z zc;K)FQX{^-E+m{eU;3vo-nn_6tSDmq*@e0CprdiV40Gl58sic}=SYK4{oseYVW~(YVhSv!zneavD!tVYUohYmE5X^yOXt7gLQ&_AS%G4>Tu&G>x#g)UyW$|9E^kkb2X`G-1tPx-m}TYMM0bw_!> z1wcKiIxG?D9J*|Y)BpRnC2n7cbHB)EA5e$=L4EcO>$0EF!#+bN`w#u}CAMGW*gk^k zBbYvd=_8mvg6SieK7#2Zm_CB(BjfOq`REUrK7#2Zm_CB(BbYvd=_8mvg6SieK7#2Z zm_CB(BbYvd=_8mvg6SjU@R9lO5lkP!^bt%S!SoSKAHnnye5d***|fHyK5xgi*(hhX z8s{4kC~=P)A6&OV8ox1Kb$h*(tM-NFZ?3jpcF#Ayd}y6ieQsQ%^*RY}*GO}2WL_t0 zjvLQPuujfbYwY5Q_8KF9Z|)`5^i;_4Jy@tv!mqsCUZ?(^TbIz7`0ZgV;x_VhkO`ayrS(c9d< z5a)i8&px0I`-A%I8`fn%p@)5jPWB)A=}T9U1k*<_eFW1-Fnt8mM=*T^ z(?`b92j;^^Fnt8mM=*T^(?>9U1k*<_eFW1-Fnt8mM=*T^(?>9U1k*<_eFW1-#^EFL z;Ukzng6SieK7#2Zm_CB(Be;6%XOg8~5`8}ZUErzI9&Y??-6!(ZLgO^UAIp(nj9>42 zBwG?D)%>`r9!Z{d#-(RIlwF66m*;;deR3t!oJx-$NZLilcP~DWx{2(&mWYoYV~qTK zPmEFLTB{VUe!u<3SodzClp2SgKN}cBXQpqAp}&5BG4|!V!FXfjGZ%k*CB)_T-|^hl znd1FUF6)m;^HR8OgJmzBo?B5boz7b2L!JI*4MW|&5a)i8&px0I`-A%I8`fn%p@)5j zPWB)A=}T9U1k*<_eFW1-Fnt8mM=*T^(?`bPBlF=Sm_CA0AN>T=M=*T^ z(?>9U1k*<_eFW1-Fnt8mM=*T^(?>9U1k*<_ePkRyG9NyI=_8mvg6SieK7#2Zm_CA^ z_Wnx}huOK})bXdK)H~zit4>MxPwZUrr{gDOXCvcHNl(g>`Nq3@{VAz$8{fQfLRQtZ zbI1ncPDrb5#t&+okT}`wym3*{6H;b@G2(p^*tsI|(~U4jofFrMQNL|!O=YEmTKA;Z!gZk_n)@47Thkb@l_89U1k*<_eFW1-Fnt8mN5jj~&)aWqzmh6(@+jwx z`$`66H$GS_Tn;rgUO6~S)+{pKbUakD-ZTEYcBpLnJg+|Xvs*8v^G@UIfiJz^$<3$n znG0S@H9up-hbGSN^0R$yj5_CU8KZvJn)ch!Sof-*G4%X;$rw6Q`4rST(EnL}W9+Mc zN#h3lUc30Z#gQ&QRo^IAr%-`6u6~Y_Z``^e&7+;3Y5SvvIv>120NefACOvY*hyK0_z_5B>BdwqNAfK7#2Zm_CB(BbYvd=_8mvg6SieK7#2Z zjJ`IGwErZxHI=I%$L37vkJ6^4SN}VSiAceZ#u!C-kt- z(8>NoKYfYq7df_%VEPEAk6`);rjKCy2&Ru<`Us|vVEV{7`oMhn2&Ru<`Us|vVEPEA zk6`);rjKCy2&Ru<`Us|vVEPEAk6`);rjKCy$T)mtK70hzM=*T^(?>9U1k*<_eFS4) zmoF94nk_D^6rTsii@e|8%$%vP#v`&X7r$P{heP}&(;4F|50^=wmPIrtZMtPL?TPUx zBbUkrzoHtC&ahO<)-%m3UoFw+C)P#0^kMS|`HKeH-$zjAW_tU(3F^meH^#b6O4{Fs zpy%9&zY{@clSdYZ{?1uS>$=$2+(O1pe^}$aahk&%R+@_7i&8XXs@Ap`X6QKGr@SU-sPi zczk_4zW#q6Uz~@WjrbgRZ04LqoO2S)ISJ;R1anS;IVZuKlVHwCFy|!Wn3K%MoCI@D zf;lI_oReVANigRmm~#@$ISJ;R1anS;IVZuKlVHwCFy|zga}vxs3Fe$+9CMQSn3G`o z2 zYyP(WFJ#z#;|)um%YyNFG`=G;M6Tzz^WHiBAyWMx*ATDT$jMqv;_EgoCI@Df;lI_oReVANigRm zm~#@$ImtNYB=a#R!JLy|)W^I6b54ReC&8SPV9rS}=OmbO63jUX=9~o6M=<9km~#@$ zISJ;R1anR@jycJE%toCI@Df;lI_c;EF(Z@aDu2|p!1ql}BqJ1JQ< z8!xQ(r!0PD+$zNh$=tP!zSbN_bX@x0G2T(?m`wY|{ziXr@gH&_kG+q&wCo>J_HW|~ z>HpC8&+)p3c$o(F9y0R%-WsFMt-y+|eoWO$%2>DQ5o72%U%0Zyp|iu2X&e%%G@$G2|esHbh7`@PhVpHE#Tw(|MoojUw;4pa-j#Zd?Qirm<*t4n1M?s8IzQQG5|F>qH-)PcmNlg^>ZjRf zjCH$}Po;6_xwqCBI=enMhW=qWQfm(OwYG$D)kz^P{`TQ>m+xQcrK@wXU#P1;VrZCK zcU+xtp`PKlz2AcWpmTApS5ALu_g8LTh;zTlXCF|9{Xu>94ePR>(8E4MC;Jcm^d^TYMoCI@Df;lI_oReVANigRmm~#@$ISJ;R zWE^vn`ItXo)WKW=b54ReC&8SPV9rS}=OmbO63jUX=9~m`PJ-zpm~#@$ISJ;R1anS; zIVTy%oMb-cB$#s&%sC0>oCI@Df;lI_oReUDF7)g44fM6(-pN4OlGiw2?+x;OE903N z)=QZU#*Mtcy&g)@Q1iE6Un7YZ8V4p>Bl!z`q4AvqSIbvtjprs`Ef=OV(s=QwtMv1| zcwIyMTts7+UwUg3Wz?C_qNy_KuX${YbwdU<(>V0_UN(l#ko?Ux4*l=j7-L_>`WWBZ zz1hXrXZp_NSMR&k)%nJMo2#F7&33nL?ytOiD}B(DCCyHu&Pu~}I{p3&ce;Hc&ix{v zeLx-d2ld%Etjm5v5Bm(A>_7C=m)M_G{`mQ1dv5$Me?Ix+@ny&9f9d$*JfwHA=OmbO z63jUX=9~m`PJ%fn!JLy|&Pg!mB$#uOam-2PWB!0SC&8SPV9rS}=OmbO63jUX=9~m` zPJ%fn!JLy|`UvKn1anS;IVZuKlVHwC#xWI= z=Jc$q?eBE{vccc!&-I(X+ZW>8FY?(3)M0;6pMAr+>?icF&(O*KLqC0q{oS{Z-*>a; z$^Y{A-98>)b`1WPjxWwbdKY_6f;lI_oReVANigRmm~#@$ISJ;R1anS;IVTy%oMb-c zB$#s&%sC0>oCI@Df;lI_oReVANigRmm~#@$ISHnZV9rS}=OmbO63jUX=A2|4bCUU( zlVHwCFy|zga}vxs3Fe#xb53f$cmILH5gqh;C-M7y(mqi~tKY-UY#3x_2 z@8cu?&g^ckPN}l?U3=7TcG4K@u5D`fhJv0vKNv&j8lRr}Sm@tX(HP&yzh2)s&e0++ zKEbcJ%m2P?DOacTk}|Ho@A`6X-HDAV2=xq}R?+F)RkxDUKWKU-w=cxGU*xk7sKfrC zKKq7s*-z+UpP`fehkp7J`(6qk@1J1LjsNBQC%~_d$CvlLr2o+IMZf4>>^TYMoCI@D zf;lI_oReVANigRmm~#@$ISJ;RWE^vn`IwVn)WKW=b54ReC&8SPV9rS}=OmbO63jUX z=9~m`PJ-zpm~#@$ISJ;R1anS;IVTy%oMb-cB$#s&%sC0>oCI@Df;lI_oReVO2kGD0 z_L=lLF6yXW!HVEbMLq@>c{VH*ML~J{kZIT^1pmP zu8+r;9fSX+7iV9rS}=OmbO63jUX=9~m`PJ%fn!JLy|&Pm2GCz+2q3Fe#x zb54ReC&8SPV9rS}=OmbO63jUX=9~m`PJ-zpm~#@$ISJ;R1anS;IVTy%oMb-cB$#s& z%sC0>oCI@Df;lI_oReVOSM&RWt@X90+4vRm@Tl>EOv@!Q!Z`e>zYMR_Msp4=T_&%0 z8E0CsRO*#!tMODnE|Fe;8fVGAMD`7Dr}0QxEa?lhR}NUUSnrRD*EPh`27IY;6!9Npwk(cd!y4IzxGDAFT}ZDFINUz~^ZF7})Rb54ReC&8SPV9rS} z=OmbO63jUX=9~m`PBM-;$$ZR7Fy|zga}vxs3Fe#xb54ReC&8SPV9rS}=OmbO5=oCM=O?Fm}h{NH_Ynw0Hn z{Jhsx`Fyc)s|-`*r`yJv?oE=~jqQEKQP(Gm-x=c}NhZpkzV^Q2=z$X?Cbhk<*e>}5 z>GGR#=-=P!{r2&?hIr@l_Ff|LgC7~APVz^hq9mde}K2vXvL+9w; z#?U`&sWJ9-c$4w=-7{T$koR{w=KJ)WpmMk-|4xVdV$lK!2A0h z_4in~!0iih?icy&1M09psL#G(UG@`t*k|Zu|Dm70#QyDokG~gS&y)Y<-wXJ7eAzMh zUpl@x59wX(ISJ;R1anS;IVZuKlVHwCFy|zga}vxs3Fe$+9CL>Gn3G`6NigRmm~#@$ zISJ;R1anS;IVZuKlVHwCFy|zgK7u(X!JLy|&Pg!mB$#uOam-2PV@`rOC&8SPV9rS} z=OmbO63jUX4vQOCzW)Ba;I-yimA65cE*n2x8xi!n;suS5>-;k4*+t_StDXkE+Imsr zNhUuGTC(So^5f$7g3jIgTRHWQw}S?kzM?#@@~xoa0skncJA5;!XtHZAUS!&mDzz3fe8)c>vLEoH3RbHHt7=owJsjxuz1|JNA$Cs(_xaqR0>C*v3Q;tS(L_azeM zZ)uf8SSR;^WWxI0e@P)+ci6yGLOq=~r55U3(>sk&f2Yl9g!@9A`$azcfI93C>a%ZH zm;Hnu_8B_af9R(#*w^_p*7GmAzYi*S&p71To1mGwtp8=^zYfYZ#rV{s@Sqn-E^AL- zy?+^Wf2Z;H51t3b8EhW4?-UX=xTbk@VZgJXqq(nY{)DX0oL`9hg_(EAe{#XRL!I_p z%sbQ{-sgrs7VGv)ZazX!#YM)@c_!Q#`b(8Ef3dG=-uupY9{zkTo-jUSNdjSh?^drpEmC&8SPV9rS}=OmbO63jUX=9~m`PJ%fn8ONMq zKIRXYa}vxs3Fe#xb54ReC&8SPVC)fd63jUX=9~m`PJ-zpm~#@$ISJ;R1anS;IVTy% zoMb-cB$#s&%sC0>oCI@Df;lI_oRi@8nO@70Q@4XKPdaS$?i<TnY~lQ_fT8xda@DRE~cyM3y&uuN?SWh%`(d zPiGh6bzdYI?J;z3-R))?4yVEE`f5gzV%GlSw zJ;rTkM!I;W7f~*MUyW#2=f%*suKt2i@7%injov#w^B%o-I(IdQar#sCk8%4#ocl#S z`+z#^59+gTSeN~T9`+eJ*?;J#FW6VH63?}tp~WL)(gfobjbBM(-xnG$Iwo9ty?v>i z?#D1$pDtYa(~REt<~BztH(n4bH#bBnA1oFsD_*`;ZuRn|jI9z!dl+-=rP~+cng5Ni zapWIelTaCTHqB1>-Jn7?ex5j^VaF?RPC+Pzqk2Yw=cxGU*xk7sKfrC zKKq7s*-z+UpP`fehkp9<@%Xai^uKg`aURmU*mDxhISJ;R1anS;IVZuKlVHwCFy|zg za}vxs$vEaD^D!sEoReVANigRmm~#@$ISJ;R1Y?hwlVHwCFy|zga}rD+!JLy|&Pg!m zB$#s&%sI(8<|OkmC&8SPV9rS}=OmbO63jUX=9~oAtn*6peP!1*warc&S5V!m5YL$%j9aPeL9kKS}${yMO)@ zIXKGIxw86=t3P^Uv|D$=81MJHKj;~i>77vLGVisC z`XiRTbNfP^`$azcfI93C>a%ZHm;Hnu_8B_af9R(#*w=(P*7JWlhRdb3#*@DZlM4SD zXV?-de|=_NL_d5ftA966`1wm&+~0gDAN)dg6!LyY!Rz_z4lg9zJL76OUdZt4=GVid zFWkNmues})%lBVk-l0z7p5`6u=gec?Vcm?!jG^a#0B3=FQb)($6jZa27J@<;g@qSC%bk-g4#_3=2?Hji*#JOMO zvk$1l{-8elhIQFb=wY9sll_N&`ttGkvg7o>bbN6h(!1Dm63jUX=9~m`PJ%fn!JLy| z&Pg!mB$#s&%sI(8<_z;Of54oRV9rS}=OmbO63jUX=9~m$kC>BS&Pg!mB$#s&Odr9V zlVHwCFy|zga}vxs$vEaD^D!sEoReVANigRmm~#@$ISJ;R1m~=X8uf8`e#9{GBrNY|r;r z89H~rc%uycBg+_LU%_Ef8t?Ubf{OYGhfGKl@ zIycswC)D40;ykx6#JOMOvk$1l{-8elhIQFb=wY9sll_N&`V!kO^3w_#osVGp2&Ru< z`Us|vVEPEAk6`);rjKCy$T<4IeDnuQAHnnyOdrAY5lkP!^bt%S!SoSKAHnnyOdrAY z5lkP!^bt%S!Ss=F_{e%?I)wCf7xAm0HJ)y`je*Non>?$Tn5Kk6 z^)&9S&p323A9`5_`(S20NefACivY+_x z?6W@ZL;uk~`V!kOa^}x6I3L0E5lkP!^bt%S!SoSKA2t5LM=*T^(?=Kg`oMgw2d0l2 z|KKB-K7#2Zm_CB(BbYvF{DY5R`Us|vVEPEAk6`);rjKCy2&RuN?ybjstOur#VEPEA zk6`);rjKCy2p)91r=-eIQ~#EiFGFX^SH<|~*tYW7cH@?xxjcQ_%*>Ck|GV$Qun^yrG|c4;}g4E7|w! zQD@NaO*IGgyA^4!jCH$qZJ`W32|Bb?hR(g|S}8;SpHqynuUlJ<59}J?;u-4uy8O?+ z{@T?^lX|?XpU`)rTeoSS$xhFAm!~+L*M68P)bEpcn%fuR+%NLk2h?GIP@jFny6h+P zu+PxR{zE@~iR~A;(4tJpM| z1JgTjY`^Ml|6N*EOsCJ=4RwBzew~enM+M8|zl=NI`cX>GNUu2~G8~qRlQJlOz3rf! zKa^3q#KHY??9pC)?adZen@v&sPoyY%T9lmT36h@5a)i8&px0I`-A%I8`fn% zp@)5jPWB)A=}T`r#dz-ht^InBIZu9hlyM=^dEff$1HX-ht^Ig{7 znCpVME|}|rxh|ONg1Ii3>w>vQGUo>4>seZ-2I~iLW z%C^qR8=I$-PbPL( zUbQ{1v<~d0-0?{Tx%;k<^6jyWB;DA4$`y}xlMU(mE5FS@N^%^rc&eDG@@8^hjW_;# zzD()cTRGV|e_1)MhjMKFWbB=q!PE?$cQ%&9xnUJU({oyM7_51@2I=VXBSqLZ@a!zjvAC#1};mbb?`6# zKOT$!jyy0PhsT3a4|T!NNeyIZ;JRS03+B3Dt_$Y6V6F@1x?rvg#+o}ypZ7i&^=a^) z_+QE52A7r3{nb|X^nRecsC_l5k~EI@86fYT6@&B1$m6M%@h|>A;`r~#(>mVc@OUul zp)MHfU_CPW51w`YQqa=8&6H0pzZEp8W^3h&6~cllrT$Vm-J*mtVPI$F&27@l_;THq zGmgn8JDc=UuJKJpIkdKqa`=fxk~3>R<)UZ0$)CH7r#~Gj%{v*7Ju+2t=Ig6Dl}68( zzNvdFS8eMre;4ned?3?W$+@(P^6xFer03yM%5@$^%D?%FD|helPO6kCtemS=oZvpM z^C{nI5jXhO%v{R-w#3yrgZ+ZNS)+XjTo5<-`toS)bMl69gUfaaQ~u*poZz(^pD4Gk z94EN)*1O8jL*Gl&4cC=3mVGC`{B%WmPn~E9$ahKkX!$7l=Y@HS8BTvEH2F>@bl9%z zUYWQ>`V2De|Kn!yTW?%B?q=x~WgOaWlT;qEL-Tk3u~Ejy*=dh$zEO^DF-{yEC=uOv zY5eN%-gmMJ?N$!o7bwXij1k}W%N~s*KljYNu1<^E`;<|C`4eNTdwuMFjYH4AP-Ezv z+Tega*3-XxyfOCWzreV_C*E(we~2%=wbkVxU9rv8N%{G9SHH!@?QY!yU+fU-iCVYA z>CF504yQl)qaAKvh;zTlXCF|9{Xu>94ePR>(8E4MC;Jcm^yQE7bG+Xk9isbG>W9}Gsd21(`j|2Fv?w)7brs{;SN<20NefACOvY*hyK0_z_5B>Bd@ro&uy~+~Z`{y;LNUGY#wH{8Ez%Pw= zEtxF&CK{*sVzTr(V7xZzWVzt|9wFvK=S!1hWR0cD*LF>kB!0&A{U=GXC&q0TOp?=e zmT3;+i`E(=-!IY_bqajpuQ{lHe2FpEEqBQndcIB?pgGVPRni#x=hZjHzP@c{{O7Cx zi=S*f)#Z0tJJr>R`(&!CKe)&=x9*-U)102t)22C{f2^A3^dH(d&Fu?u?icy&1M09p zsL#G(UG@`t*k|Zu|Dm70;5*3g3KZ4(JT1+A*Z zeTGi=NnXVGp8Q{-^DtU7eeOZ(aQy zzrAzo=GgJx={eOdMyT`U&oNGayLe3WdwS!m4Ngk+2F81?oRAD_j6>!emnG@!IlpVrF)6p<15f!wmNu~G zdE6^UWm{Z(ZeJgARIdGQJhIVI{S6)L3-Q@sR?z+aqbuS>;vksKd8^XVO{nUde~>^WdEU`zTn=l{=4hz z9?NYFlt#Z8pU>ree?P)_%bs6CubDcGEp_!e}Z|b;O%Dpy@+PzA? z*!6|xU#z!E#tv_!JSgufy@xjZLcFj~6OALk!%1V*89Jq@#!>%VVY^1ay2E}jhMt$j zn`;hq9-Cqe{a+q7#=cViX}s|KW)~0d@SV%gesZg;b1U<9S3hUP9d6y6xpq1|r% zI$xIC<@C32zsv0laqbuS>;vksKd8^XVO{nUde~>^WdEU`zTmsYms_;fy|3-CLgw@| zu6{m1J`FHV*TY}JLyVheTqa-jXruXQUoVmLVa91vE|C!dZ8hGr`(l~Zyq$85C_f3x z&|dlSML)eK1N=g~|5m#$L;i}v9W)1ZcIWS?jQVL$8Drf&9Xn|pdP+)xgTj%ODIpZ&=DE%FcR&OR6D^i&$Z(dq2?V58Ij zThdK#Ux;(R$Y&o=hy6i)_6_T@pU}fTLnr$W{qzOjq09Ti_8w>JG`Sqt_P9FNRPSDb z#>4kamKt-6clVqmN8;GEr*EB!(shCHu#OYt=ki^(pVPa2E0;oyYs?=nKKr_9d|3VQ z`dwr7%ZneZXVzSWsk^7g8iyzG-Zx@)q55h7^vDW5k<{cUJ9+mJ5@vD!_ zQ{*S#X`Z4^uHN>(2kK8wZk}S@+$)WtXMJk(6go%uHirIWD~z$PpSBx!NmkUw^JXjI z@<+cd%BkBN7t%iT0~?$LS7bjfhZIHJvTy;nB;Lj2eM<#k=;zbbC$9wodw zNgsS*ul|6!cJ6_7lYMIE9?&y;p)quJe_#y#VV~H!2llnOm~qxbi(Gu{JU^Ge`Tb&7 zr{5P#UHvWnm$`MnYw7Rww2AR|I>+=4aQbi04siQIocl#S`+z#^59+gTSeN~T9`+eJ z*?;J#FZiwJNMAc2UcYapZ2xecT%(A0-=V`6&-i12q)%n%#w`c?%aX~)>6x41#f1GF6XsC0hZb_@@ z)i3?b80(%LYtI?zY5vj}It$jb=M41!@QpF{HF&OZ%(XQx-mTX+ZW>8FY?(3)M0;6pMAr+>?icF&(O*KLqC1N zZ{j2yoml%b|C=ZB(=6j+VUMKQPsZ^lKa>I)d^D#<`3JIjrg7X%_oZHzBpQ!f{GM$2 z$++dDyCS2KYP>|2yYjqBGUa2h?&xoa;rK#))tTfPNB-%>DO{a9jZzwW_3MNgW8J%x zQfVA|dcHP>&MJ*lYaIGdO*F>7Ci)pa4GeMdCdFR3{L!mkx;j-Jhr0S>l7zc;$ApFp z^%PwF%IR#BIKt`QS2)7$3vuoj`RoJgus^8JzF}SV6MEQZ=w$z)pT6L;vOTxo(f4-z zc8AHyzl=*243*~GhJexiJ`uzgnok41b&hY*+ld2N4os6=b~Jl&vHb&`s1s=b?c5V@XqNe zdj6gF-FDO2wCa1O|48f5 zi*veG@jcN&+0&m_4xIlgsMa{+=+n=GUKG5b@fRx|2favhQTbK&`#~j2T~ZDkb2}(> z+~3MoPu>X17IIm6XMyWM<469ZoND>M`rUTy3-POK{&o4)3f@pgoj(3Il~KR&y<5sy zw_gH#E~k=nBOm3QemBt1IdN;2ZpB< zt~=;xYN4KEpQaV+O!XqIQ2&kc>GZqp*cam5FY?(3)M0;6pMAr+>?icF&(O*KLqC1N z-&TTl-q63fY@75-I#j)>T>nj&Ji2*HIs2?oSv%kUcGIESOIcs$p~kai_l~>WPmRkx zmo0a2ZvyY$yfZ_jMc`}YFLH*+)!*MK-+B8?_%|cOHl{g;jCFr~pGp~eem#>$89H+mOs5R}z26vPU*&41*LdRXkuKh^>>HQAI567PY5Vf6 ztG^`md$;b=sP|4!?Ts-`XW7JYf~o&O<~Z(eVTg0T$Y&o=hy6i)_6_T@pU}fTLnr$W z{q$weMsHpfwdZ!Dna?Es1>;?lLu74Rd!A>U|6GpkGw!hQg$%xLoc_p5=^bMH%jHm+ z^rvym%k}bb?HcV>=ML-S^O^Sk{H;rCCC+wxAO6kMwUY6cz2BZ>z*_Omv0U^2nYLDb z?6g8T;PP7WU$j#BcBgd`v455F@wDruSF64%G9m&AjJQ!-j#BUARq-rnbLZ-Ke=;`Xn5r`F(!dE;Ww!SAH~juk35sO*y*59yxs0cvzd= z;=8rG##{E>CD;GzpJso%?~&)O@esB~D?Eo-A(FCa)}wP>n5X!?&*Zd)_u z@ymXYZk<{v?>}=`qC2!w{a;}iK}Q(ldCdih9JB{z=w^`RU-pGV_ymOhZ| z?~Gdyxi5#NTh7obFXU^#Qkv8F-3wV)qpb4jh?g>JU3uj-Im4uRpm#myJ%8f+hRfwj zm6cO_ueTN3R8j8hy{`S$yn%9?#L+V2ZC&M{pWeuhgP$vpX!u6z&99|Ab8D0=TwFsr z^W8{Uf4;hMt+%fwZM$m938EroXOXJPsQ*=qE6Tri376AL>{vUs@Rf}1WxUG!j$wiL z#u<*kmMO#RSl;5@`EU9D>-yMv3!`M+*?*P8tGtnGr>`mJJ^V&|_gz)qnlM@_Ot;s> zgV((8B(ArbjlT?&T>FhX+*m3TZ`gCD`~78d_*z$eY}h-0`F@H$Kg)Q>bhq=y$!f2V zKfKS`poguxuat^ijN^`6CDqs1V_S||E%Rqv&B!imoXe)4r8 z;2rDrjeqGlNq(AWIT-`S%9RLvKKpDLEDutCsrjpZ z94h77TRi-|uY}dH`ag6VAtO&4|9H-u0U^d;))*u0HW|0tIZ#HPwY7eq(O(ihY^ycP z)afgu+Zk63?InZr8#g}KLE7E6<6`R2PSUlb9Tx?=c9Dd0TkB)BEQYWfP_5`JsOKzzq*Tc&w ze|oaIBs@}1d276?Qsv5rl^V?{WC%H&Xa@gud3dN!Le4-i=W%`$RsN?(VURBT)$jf_9z{XW|Ll3^Ozx$szXGg2vkokGgK#XFVWYwz@d zPupK9G&?$<;&Gi*$a5XvpY$B_fh^2^D$VUiCDSN(zK5CG={+U-eo^*_vPl#@K1cDk zBy^D%tbL8^@e<|0uO|>Z5#W}-O-MRy4rQf zP`e(14T48ew7~|&bDEB!X=OJne*1Pj8NS`7xV85f>Shw8IN5X@J)68+ad+SGRCDDn z#UY^+=;-o5#eJtvq#sjvDt5d+ks^8pC_ejmBHcFHq4>1>MA~NHuXy(B2~<9HyW(GM z#?ZcDJXXz@wlrY{bGWB1P2a;@JgP5^j|f)&wIBAU>SlWsKQbOj)i*Ie_Z& zHk2B~=J{BUpn>+x$^JIP6MR@mK>>yVG}PX0Ll)Xqq+iw&R`X z+8pNou@jm6@5D&t+-G9HWZk8 zQ1Q7&W@K3Rq~e8<=G4aUgyMi3Z7KWjF~vUa?I``)QN=Nj+tCQGBZ@^zNVWbM9VOyvgWK{N`gE=RkD>y0Y-5vipoFK+b=dZ(b-wf!4Q_ zy-ts!v|<@^!1>}-Z8CHBHl?U$73Q6eW$64i{;auQIeL-wuTFWs5o-w65}X&fe&af> zSi7#{`VPkR9@l*^)*q}xV5|>VC%{-YuzrBCo?u-8W1Ycz1IGG;bqI`g3F{LW>lM~5 zFxD}wXJD**o3!;0jP(%fA{c8d)><&uUaY}jte;p%!B|(ZzJjsdV%-H}9maYL#`=tP z8ayLyD2+L7t9X738yc+LA1MDn)-*k4vSLenYpS+tqT+>HMo{5td|xza%5bW?Y^<`+ zo@7HUyUkFXk!3>>PO}uxd^(awht5&lrQ&cpupqzM-wSjZPUjvNC_d^roCdaK9@}6z zz21>e*&Rm?BZETBfs{50N++1I)tZTpA$Za`tG_J;ZRr=nCnl^GhYn`EeZ6^JiH z0mVKjo<6()4VuK&DypLUPX-$8cFpn5Fl8o*#-wz*6HvNAnAKwaNss2XhXs_|)wVU~w!6d4+ zoH>2M6w0o}>|NiGPAz_`KKpZgHF{k9x#9^EtI>t-FBH$cR*jl2d#Si#Ky|X+{Yr7{ z)f!YV_O;^GLu%2y&^LQ5E>tgT8#_dix#Xm1TFeCrN#)9TdX z%3a0zN>-!pFYhTXKCr6R=i-6l)nBVnug(t@-!D>?DlL1YI3Z>v74ti&`0ddtlwcC2 zIAp~n`qP{_xyJ-5Hj4SL(Kt$sX1-c?49#uMYpbo*Xu5odIkLobI+GVCW8_TQ{Fm3| zmm6l&w7h4t&Gy)lZ#B02InC4dYWAyfv+FOQgw4FBC#+sb-a!${etLv6b=RIn#&zJv zC}(=vhd(>Il{2mA%b#_5wT^6u^Jhb*t)rFm`LiaMoyaC6Tzz(5F(*3vB~0;(mfHK< zXEHzT=1BDlG8f;lnsP7gQ$9mI9q98>W^?xywDu0O?e=AqQknhJ&n=-AF3g>3E+&&| zJl5y~izxOcbD#Rb)Vvex?->+CRbx0;>&FIB%{F|WP;6Wf-6g(%_$N4sBD(T@#jyt3 zcUXt{ej{H>Fhv*Vdy)@twEa2@zE`PIDun)aIIc8b9~Vkf3ZGD1M3l$l6IKR zJYx;hZpM-4TIS084w1zOX2%t=ls%Gp(y$oX>BT&%-9dVl&g@<>nPvp?@n8S&)37Z z&MEY+TZ-}@5s*SbMfsZM?vO&|Zt?YMQsWeAzB@_zScZI{-D}?|PRmTDO{@7FUwvyE zrA6{OJD~XnIz5Zm*&g3FP{VP5mA_kx_WVXA_No1I6Gcs9ZfLZby6w(E z-;>uUwt+%t@jdzdFW%%@g73+H8F*99W9DORyeR!TpBDwUc+%ikd@gLS?@6Uf@Hv>2 zxrxTi+bE;Zy>Yf+-+2EBXe)CU2E*`;TUyrXFm(K=MvEMx3xmSY8 z?GEcS2o9!*a6V_f`vy~W51z}g3qjOn70;2h-_ewE=ed7BqFvXI^LMh3-Cog_fy|}N zUemMte2>)V#A|vnkoljoZ>ZE6zDEjZ|AxvnV-9QehE8nb`=ym%o|4Cfa_YV!b{`cw2M&|s-AJElM=ENrtseTA^%(q8W(u>)z_!Fu!jyb)=Q<_wR zx%J+gw5uJD)y?@TeF^68jy=0xq|?)woqwLCL+hC@-z2(QnEj2PpP*IGnG?DlCC9=Q zl+H&NqNq_b=3D81heDDt@N%s-$Sli;Y&S-^8KpAFkf1q!8~M=FWvR#dsm-*zU148zoYL^dox*` zVt#vJGhOP+_n!y+wot9(%wsqB(&XA4r}-XV8kAa?YjMbzN*`qo?dV6>4i`}N31zm^ zuO#N$+OvW`Tkw7L&)hAvcO$d8@fK=Ui0`orFW*dN9?VmI`O=3P95Z=%GL?J6=WOXM z+I#$Z^LaXU|3@0SkI&yCQE9Zb33KwUR7!Zr{%zb+=+pt`v2#Aqx+rFc>KXK5IG^L~ zFJ#iD`rp;Luvq)JlNtNl-X44%!@hUBM$8zi%Vy4-VcjfRlEZoM?)I5F)aCp~ z%+01BX3VaEIaIF|bAwA?=w2n}sJCC~%4`1YwzO|FMSI5%&i9l@-zlIS^Q=8TDB}|6 z{B+NsG`bJ7AN?c?;u>8moJ$>=FweBfAd2SC?s51;B{wlg?@FU?JDEMNX+0%xGbfk* zK<}Eco}(+@lTjq|!zxKssvjSRF&S^^OCdh?vP!(AF^`$MFM2~&Pw}x=yU81J3FBjX z`kx?*I?_nZrJ%`f+ULVu%O;SFHZYfR3!vJ^n15aMr)7m2D}SdJe)M%IbKf)D$hJfi zWsi5;N=r{MAMx2jR_mH7d#`7k$#g6~YqVWZFGVb5ZrNfpeS5(%lbd-_4}XrcNL%BY7BN-+ zmn*xI{Wj(`58bGA-fv0v-*=^oMO!PMT~%Ev>m~F4Fc)$;&(E+GadDv$2hEgERICe~ z@aJdPMm2M#lB@W+wZpw!XvTdD<&*rvg`N##t~fyZoz7)`R?W`SmF}1`4-IgokYIk! z&32_L)hfl@Dts*kPU)oL1b1IVZkH_;uUxU1KD=ihqWvZ;JDu71&vIJ!in(wL2fBHR zc}lm{^mHwATqQ@!--g*R!;u=@=lI4)W>fD8Y>)gsnd)?B_U=E1&MaWQm*0x)w|7(; zQaTN!n&tSjyUq-vDyx`xtQ|rZA2S;)8AdsE`Lm}sji6`N%yh|y%$6|Q6dz5NYnTIi zn`-ah=K5ZK*NU#i^D*;rxhb8ro3LT;Gv)n;I)#V9=39%&Dii zN*@cF99LIy*O_f;cZE8NZ+>n^rul0sp61b(yq%d{)|gY@inWye)e|$ajAHJ#%Zv>A z*H-q)H_fO(3iGQO<`m~-sO;q)kJsK^Q&w?*w|P{iLK($NYuVAhjM9pILuP5m0CTd* z466ErdEd>c6m87@Q?^c~3A35EZk|ZZE;ILzSxikAFdOD`pfSG8agEl}%f-yYJ3G^u zn#_Am-RQj=$8VJGPU)xkUZQ<|AgYO`p#E`lay{S(P zX4|G-WYd;;p@H@+u^scKL6KDCLM1iFE(4>;DuMSpCa#O3do7sbJfkRk7w?VapB_am z$}pQ&j-tQo^7d5%4$wdOnDhVGPkYx_Rxv$V?c2KuK@;*qC11>Jv?UUF)l{D(s0S`(J$g zyuB4oBkhKw@c8ibC?SuA`&u!+vOG2pC zN#>=SL&?pHIW}+~o$SNBvTH|j_OVuR^3Cc*Kguy5>uO1hJo$GGGtXI4%Rj@F&zCey z+G)o;;iM&*KOd&-i7hN?#bD;MgF4Zzt3#FD!LTDO7{t7^pcx&nJxbYI6>dyDBStH( zHM%Kv-^Dy?cXQgYlKK0^7Sya8^PPW8X;C(R_K{0#TC$1RH{6)KkF(F7aYl6K1M`xO zhV-$Wt%`r~MoBtdknJ8_OH==)%<13D(CH`4Ss%(#NMrVISg0a>pTbcYIu(TsJURt6GaD%wvwI{5RfpBIm)wr~u81bQ(WbKS^Ay#yQHl*%8*5ozRG^2Uukk0-AD0f>yq^KOmD>v42n~O z&dlX)i_oXXy_7w1SwR}Ui5Yv0^U8Nu_TZ5@@n^!A3orc=-?n`ZWv@HnTYR~5%=fST zh}T|Ls_cGAzv6$!GB4|vk6x7Jm^pp&(>L3HigV(fEfc4Ef9;M+wE4Y;pen6 z^l|~m`R!kUO0HyXcdZIln8}=E)qpnk=ApgoQo?8U_pfM3 zHzSz09j{5JmouO4QJua{X0BDN8}+QnYv{S;&UCe3H>LUKpsw0?_gxj+*>$5zw#?@3 zyVJCLU6g%hbaz_Plexv!?sVvIXJvok*`0ROXa1VgjUxRxe(FXGYGT0k%D2*-_NH-- z{+@45F}Zv^EL+!#_Sfa(D)V$J>SM*n-p*xhsN!5cR_6z`rIba3S)2C$w-&Li;o_~a zbmcL#QI0iD8OWLwod=U$X`a{bxPDZ+0v}5kqI=Sq;jE|Y&aSlOGV7_m(~_o6VLgW~ zbfkeb_;~Kqu%mka8}8d--xI>x;O}Y6+7M^#w?Rr9;%}MF=Oe~_bAZo5=vf!b*97SF zTEN#&=x>i+q0Jztm-HNq2f(e5}e(gFzm2 zp(yisFHcHL<=^tGJLyG*4>7yk_NL$Cnaf=Cp*G+6x_W-|2D-I^dAYV1yugW#){)jnr=GNTtEP#YWojlCQ%9eKt_sFy>*Wedy7nytVJL zHyxbEyk?jil`P4cS7^U^f7F7x)}M7WVKMWKB~Fy~l(}ccwUj+}oEj@KVGWt*G7mky zimpYESN8U89jK%I1jV&muB6~z6BT>Jtf13%CMn)$Wk-FTrz*DDGLOpJF;~8@fSPn> zetc(<_DtXu<+CzsG1-MMR~)dEmUUq6ws#q=I5%1O*hMa&2hQqDFYGyHovB@D z&QIoxFdoncX{TB-Z5hk-I40J^Rd*{ry~uh%{4N<*^%xYVqR+B zi-z0sv0<^+nr43Ex{vQSoQghSb}urNe&1$3a&ZtXf64q{s}&g)8rHKf^PH)^n+IZWF}Ju#hmjh72;8_RrXwln>j$!sxn9R+$Z zC-rioz2}+z>>kn4SpGZxUcgg|bLYRU%np@&N6>wobZ1sR_eVE7jJfw3g znQxtYL|3ht&%S$1cM37Pe|SRq_VM~P?$T3gYs&1qB9XpD@;Y_lS0eSO!d#}`GxAws zqK@G@6P}UVlje#CSw5ru?U{EaCDQG{X3BnSWFl=Z$-K499jf1i#~s=2miG4rbB!f8 zsA)^)MaQmD@@(d<<*(B2Ys~pKU#7SLyk47kzeKyzm?t#5NQFaMtFdZXU!XVh+bHgT z@jUqrFjM@{@jNv&HCMdP?K};v+E%g0)AN*&%iMYC1?u#mowBbSb&;O#YOlEL%1cxs zZy%t-{mb;@qlL0pw!KQDW^_>OHR(F7*WT}nYxs%UH;8udIv9KK230E0ysX?!8nTAh zW!tVdX?5N{Kyk~PbgMtF(L0LVB)7OuDvtN=8}y_u^O>SI=+cgk%09aHbt-Da96jM0 zeLl$=rY4;vpX0oCPnvd+Zg*p@S3idS#52bfiKQFHd=Gh{_#qm-g1KvhI2wGMdDzgy zl>40dgzFI+n#!DW@+kd&#_az77>z#4Y;JIZRxD+1UEm~DHDXTf7fsE*cl0%^18%4b5RI+=h>Ub?V+xD{%1=BQ_Z|M z$JXzrE$JL5w2k(Ad`}+tVbwr7(v|04qSH>QR*JRt4hx{$$;^AT-(tVM#`h8?V*;p5 z9N&j0hX+v6?R;NxsPj(pUBLGhHj_3{<{Q3$Xt~^%y0_u;G$m{^4Vl9{FKG+Sc4zL` zXdA_OFo#UrPPOMV*Vyhy%PpAK#Q4*MG>$nbatF0^VeYvqfPNKceqgkd<~Z^_OwDaO zDLiF}Ivzsr?IiR5%>GYy(t`-TH@h6Rlg1Qh{xsd2maOE@Rtxf=p38V%Hj_Q*S0SEP zmth_hyN$Wsd=GlxfIsVT!h>qZF)wWHNnhLYSVmVosqG==N9(=lV{MMVYQFZJ&Q{K6 zMx-Zg3*-Ek8|X<3PjQXPj`5&I&-ibF?N8TJPQ{*TE(hF_n{A+|y3A+G`;bi!=Bz(nbbb|cAp`CA-Pf6&3_WRu3CGz` z%a_^~X8Zlyn`z2jzE=FT+e*$3%qvs3(Y3+=%AjrPA^_ZvTH}sjHk>MC&y4mmqyAztr;n2JVrH+PBNRP>`S9w)G-49-%L#F0w}Sbr)ghV`&Kxu#mMW*^*$2f_mApNi zxqna7Ju6<9vu>ZG``ekfM_r=v+nCK)Un7UU%paR-?}s_WIxp{jNa6k2e*5qPy7HCn z6As;{26_AW$9CN#>-B73?Rb~wE?^EGcZYt>XRh1jHsyC?e%UCKYE7%G=HAdFlZHR4 zq_}##_MJ{Q=2?_UC-zrV_L4rCbha{cmlm1i?N&kA9rtF?3j^lG>FH$VUS8RsRZOQ7 zb(m+?{6vkel~eY>5+AkSU^4Ga(cZZ2AwsmqI{;!&!E1qnJt!Tzkdv^s_ZMy zWYChS)f5-*mq~YOR#*JIOcvd{z}%(eXY#eJq3pdAGim1UI*J!w&7!5j%y<1h(}LE_ z23@ns{HUSw*`AP1WtubhFP%eM0%|LJVUry4EySE%Gl#y~Ku_ni#olW}( zF-P9|Osj9QhD)>{bOnQcz5N#kN}S zrjvfgia!_rNKuXr6u%$wlJ2eH=m@CF@x2 zIr(wSriDII?|=CCFKG0Uob%oXb)exhdKkv`UsDsQblx86()UlvEQ9C%aN|=tu$<@K zbox`OUX16yY?jswbO&?zj;Gph4>=FMU!T&{L(I7=6RB)#j{m#bbDA2H8n%8fBkTOGiFmRvvvu1&i}JwSWCHs_V~u$?X}HX~M_zy|`yI=mhieD{m>Y5}zXt zN2k*D!F(WyK>`<55o=drSl{-IL8n2nAkQ1}8qe^;+MMX{zluQFSY(@=As*P`-ADQGFr#kAOA zdYs1k4YhYwM!50$m=YLEzLtE<9~l^{-T{vLTiD-U;&TW7w^s9chd9C2`S?ft$3A=v zVB7|``51tnOZU0%(0O|c*Bbg~7w1}IUWHpR2bf*a?RI;w>;7dEZ|QN?oV%;XuhHv) zKJM5-k90lrZavm@hMs()>wjA8sXi~*Wxnv2JRpwb2k|9u7+3NMJ(6eWl>9@#)TQSX zttZ-Q&VRc7H}YA}{M_p+?F(ZzjQc{fo-z+f&!HiPT%)-?a;TdhWtj|I)`zE%jU1vuM$8UFV+I z-@1O^i@)`G!7lTKzvKaNBtM8RdBeDpPw0_6L#N~)`lT*!-u;QcYtlzupWPbf#`kN_ z+|BJ<{KS#Wed^@IH}GUGS1K#M)a^X~sp;{5>i1Qj9c=kAeySUD)9}>z9y!bl4yMFg z&FH6mqHR;u`>}C;!5(76f1AMnz%^#X@odNU)oxn+&pVhg?z;?T=(*a4|9*ka4bz#S zf1fKe=4H5v*>H#fiM?yx0wn$k_Y0E589lBrNqoaYMM%ayb)hJUo*NsBk?3qvsyK=M z5^am?d$zF4eBm#7Kpe>r;!EBzuH+MXB+t+(`GB3^gEw`@K*?5Gb?&I2fHDy&?s(eB!I?%^a z%M{-?+)R$$S1Yd9%a6)veTz`9Uk|raRONMw*RRXUGY}Qtq(weoI z57|OD>aI~f6ZZJiVOw{_k4|qV&nX)f$8Yo_zu6lUw{PuF4Tt*Z{uk+4Hjr!rfZZKk7lIA%`vN-F(*lZs;#wt!CG@lqV(vXJT)V4b_KE+Sv;*&XPa zF=sKkRN{FJ9JiEay=OMvw46Sy=Qz*O=Th|q?b!m&zkc}zWFF0VYkXrKgYA#i5@1pGBGOJw`W9^W07Hf(e8(0(Nn86w(#}d{iImWPN$+3sEOpZycadNC; z?UQ2|YoZ+6u*)$Ie>oQrN6rz%mvaZ>$~gr+a;`zAoP*FW=O*SQ=PcF~v16?ff2=_g z2WykW$C@SMVl5LrSmQ(|);`gXHBsgTyUZ8x02k3BQAH~xL9H2pM z`YC?#em`AL?yvY@_&B{#fX#geYj%8cX6^-jB)!t zv{4K_?^8x9hR*MYM=6H>5vHRRV_xRA%#)L1b-VqIL%M&fFzs3Uyg2#h9Mf7HmM`n+J5`NCiFfH;yL#FxBbT*)W&NS>in@(=w|m(kku z*F~Mis5#y$8cL(`e%tQbIfP8hk5%@wPJ5~EKg`u0@1fqYM? z^NET(Ee@t<`z9$K(m9w$w4b85ar0oB{dlTwU%Pa=?w?z1reeeiTsKQG;-^2Jtr+8O z{5wZ6^!TLPDTdB{yXGo}{#C{2DaO2RnlLA6`%z*yS`eoDXEzVm;{-eo*W-Vj9ifjq z`)!1-XK9B>5}lJ5M3U(DS{JF$3wD_={3Q>FBl$sm$s5L%d_s@p89F8Z&@XkF_@r{Y zOCAtM>V^1HFN`bof*z?CbV|LTU+RK+NxhajPS@?3tzFxERIPYH1*5kVrwbRF4 z_sve%6A(66*SV;|JYE0!w)6CP!7lZJztjtHq+W@h5{JRF^|8=(z6%%!-Rg!;4fO>@| zGQ-|_KmXPM{`2j_lt1EhHRazXAbx5hGsd-;$G=~Io|EsHq4R=eq^>{Ko*DIe>dK7y ziXC|nf8M`IK>yXVHWFi%!%<^rK!fFW6q;v%PM2y=Jfb7Z|iykCUkV%_{L1G+UyN8@^_VuIGFF5)z#*Zwn_EBS;T$uo3H{-Iy$GOpe#y4kvbs>?%P2l{5t99P(ZY`ZX!GTSx=!b&j=KJbrjGi&V3+yAU-E!Bk{`sEykT6)C-g|3 zp;Ph?{ZbdytFluey+He`Xn>rr#xcDxEr#Vp=WI2A}T&~#^(Jd3-zjK$ac)DlMyrK zD|X~T{E;7tgS<(69@# z)Fo5v6=e~@$L)av>uB-;<^Xb{i$|EBt#qR57ntXFaiR}Tn2k$0kxw?W$J@2kqa4@t z_4&2>ZxU-9T1(AFu>JD>wKOpA{nD_{3;frA*%@ZUv3bpm_@(|bW8Ao^TvO;-+ngCX zA9Q4f{&u~XF|UbznOkr9*WUB#I^DlOO=msMJR4^{{wWVi47OYc#>{cmuMfqix$4&q*yVZxf4R;ej$D5b zU#?3SSFTskBiAwLl+yf}aM#D( zKG$8>)7jfy*I78oUDrQypSwOU*yVZ%f5`*l$n_BM<$8#5<$4G`ay^7jxgJ8lTn`tX z@uJV8d0jSH=0!EeG1qG4MQf(#t=*ZPbZ-gs=fj>9zpWA>zyZA;y*aL+FwFL+F(I zL+F?LL(EI=4{>~o9mlQs<9L=hIL;+Lj(-^!=Y{CO`64=T9*KUOUotP)Wxnv2JRpwb z2k|9u7+3NMJ(6eWl>9@#)CJf1NUg^+_6KnNzh8zK>q6UV%vdix8!=-Y8P$my>&qW& zW~@7h?U}KDZQja^b!z8vW~^Tc&;GT)%E$Nl@K347j5wEjFeCozNz53xo&z)VWNl=I z&YnTc&>tSbjCtKXz>Mp^*s(5%Kh_J0gLOpWV||fvvF?Z-tVf~~>y+rn`X%#%UFHja z$phj@eh^>shH)jI&?9+h(=$e#Izn_o!z>NE@3ZI#AKQ`UKK>6T4&8#vr z?%$raV8(sjMk{9AAI_W0jQhi7o0xHbxI^m&j$;G%_$UARU--q0I3cz2>Z`>c-GLe7 z{vFN?JvU}DLucLP%(y>vamw@8<`wP2jQcCG57W1qq31vB;^juz#bVqaoT17_@R4Cu{_{f*(Xn6baH#OGhT-=Tl~gC8&> zj^kHm#5b?Vb;P*On&;J8(-YB+89ILtVTS&Rwt4>AygbG+V}C&G*f$V=>?cSZ>@!Gw z>_5o3*q0DJ*sl(7l%Wdn;jQu*xY0TKid%A%c`+LUcn6dA-=?^pZ0|#~CcRFGJaH1=7 ziJ#Lb^ya_z50$y@@c%i68F7y9Vn+P>Pnj|9@xpnv*7Ug4V1~}8O_-s-QyXT?Yg$`o z?7xW}`*Pxs{W^(*eLRVe{XH2M`+lMa`+=ep`-Gw&`-d_w*k!)(mpmYj0Jztjc2P8_|G=^9l{cseGB9tJV5TdBRP{5f-_@XvIs^9SXV`yq>VU0^QM zBa61oN>O(6giMNRoT_-2Z6?+H&D_Z_lNP;5Q}z$VGgYq>j0JnwgP(MNzm4g7oFY>) z6eE6}dYOtbZsp6&(DU9ZOWC1wRSYxqztrBlh4`3P8-ve^!<&EA?SD&u)BWeZ(cZz6 z7iWF2_N-uD{MEgF=;K;l|3RWB$>gWj2b^{Gn*CGPAF$@9J}=m1zVMekAdch*@g;8< zSMmuxl4t0Y{6oLg<-he3?rTy-uN_!w2bS7_rFLMc9aw4ymfC@(c3`QU*ik$2M^3G?+?XCn}4Q&tY3)EnuvdLv zK-uAcad#obh_km>5ygoA@O)9l826vj#T7%(#Ofs!L+8eq%+NnHJ(=T2Bp&`HYdBHC8g}>wh zaU?&8FL}ebl27Q7JVU4CANr*(|E-rWYAUq@OYOi?JFwIaEVTnm?Z8qyu+$DLwG%sP zC;q4%SZW8B+JU8ZV5uEgY6q6ufu(j}sU28q2bS7_rFLMc9aw4ymfC@(c3`QU*ik$2 zNA18;JFwIaEVTnm?Z8qyu+$Fx-+G}})V&$$^Hzz)`*kfh?@&`SXn2#rC#OIs)gpc{L>G5;BK2>~w_NVxZMv00YtAA2GuyEeN zzB&7u?w@x5xnjf_75+jo;xC&1QZdGzS@M-)=xOK644t=gn4#a)^tJNAyj*)SpVfLP zh<)DHf+YS{9Sf7haXeXsB>tR&#Yo02UbZ-i9*YOXNp$|QDnX)u-;xrl2Nvc9yUZ8< zk_W_*{2;#M4dY5ap-1uzosxg(m%9A7Uc#uU)DA4Q1553|QaiBJ4lK0;kIJhZSZW8B z+KC-=7k}ggEVTnm?Z8qyu+$DLwF67-z*0M~)DA4Q1553|QaiBJ4lK0;OYOi?JFwJF z?5Lgiqjq4a9aw4ymfC@(c3`O;SZW9UZ@qle%F~NCH4_Z1Y9=IGl%kXQwSEp7uQ^(T zY$h`IaL-Qd&^L9Xr)i_3v=rzKGyX^{Fz=xif;`_ihmkb zPw^+KckzWP8te9!+Hbxv7X16YZm1Y>{F^majQAx+Hc^am*N<+h7<$Z_HB$_oaTl4P zf3R_LWyidl^Aa3W85{iO%y}V+Y(I` zL+4X(X6Rq|oEh`#@}2q5;VQb_WK>PvzsTV_dYt`x>+A7X7HdQ@Zt-hPNc1G%ZAPNA zcR3Rh{i_^I)Om+_!7lTKzvKaNBtM8RdBeDpPw0_6L#N~)`lT-at(P#aT~a%+)DA4Q z1553|QaiBJ4lK0;OYOi?JF#Q#;*XqwrFLMc9aw4ymfC@(c3`O;SZW8B+JU8ZV5uEg zY6q6ufu(j}sU28q2bS829kmmG)DA4Q1553|QaiBJ4lK0;OYOk_tydjO2ioTSi+)b5 znQ+*CDVd&QcGlh#HF45!W#7MeE)AOYM{yC?SybiHU&U?fOsBu``4aHi@NrYID{6jQAz}iz&vqjth$` zhMspuB@{zvVhA(zFVcF2AU@{RrA$f17uPxJ_7@MFbpQSZT=Y1#a$WWKg`(H%<6bZA zq3bzS-jhUUYOJTO-zAy9PsF&e%Y5N4c|aV=58_MSFs|eidL+-#Dfx$fsmp)sC4ByK zb$z~I$pcvO1D3pjC7)o)Gg$HuMjbIF_QT$r_j?y>4TJiNG+I!ec z*#5z16RolvrR@EUx6zQkV-^3h-a+XhlN6^E+(jW;FAa=!w?Z)8YPCRdS-ZW|^T%?< zo&JW9^O3cRk0pds`CwPY*`cA7xWiL%-k z_s)TeXU*}a#6?=a3T@oib+&5n?AoK)WZ6a($##s6mJZiL`{e8P#n{JEPXQEruf{F(zuh%qfMRYO0JEvOB~$uEGz9tr&o-p^KMlV2Hoh=@p*Q_cD zmHYYA*&5n4aZr_nf@l0G;+*zd4()G~#10{3(qy&bEUo9=tBl2p11krS!^pXcYc~!g zw@uR(-*gS3T0hp%%t=)eeqRsK-aYF`lU%AK-2N0op>x;LbDt^+FSXwdw9Z&d&?AgF zjxV-{#-(jjn!CT=OMm|OD&A}uN~w>uXA3l+p%h9hygd{bKNdGqiWj~)Xmp1ngQv5to`)*5nM-}GSb?F)kT^OR+teZ1ETg7pf zzgth^ZZaFjPM|Hn{M39)1dOMqjr`Pnlgo|Qey_J(&G)d!I6BySyPB^s<{RI&V#x&$)K*wd41@b{xZA@Azmk9=%!dg`wFr<%DShbRN-qRn*xw zUUAQq@ATZ*MDe7_zo|p(CW`A0&zCU$o3Y~8Lk$vMyVq4bGu$AdV}V*aqh~i_hHNxQ zc(Ef_?VFYCXOPfle753C5A!7ig{CPUVUaJvBJ!Q$jL&~)(B2n{D{J4;{d4+>;@Fitf$=$f9*lU13&uDYPx$-GeroO>_a4S?t3O!r)g7rM2>UDDGsx)NUO~zDXzT2n4-0JJR)Y7mF?(Q&~(K)R|im?>N6ELyFHPv z9b|UjmF!PUr&uNE|_BW-b(`w0cTDyn&*7@gj zt5#KIZ#m!{ZJJnK@#aRU^aZKG5O5VYoRrv#X`7^iFdV;NsVs2gTJ@tLayry0f z-7U{?cG#xUlVfau7 zMb~7J*`6B89zQpeHb&G@+*|wpak&k%=dUd4_{C7!kNAGp`q(l*%%4r)i!u2x&)LYD+0^PsP37Z%{4+IlV0O~Ji@8&jIrVKiRqn>;d&^Cq zsOt~rtTi9$*A*l6*>lIzXmxZw#io{NG(V`m;vHK5ZbN^*ZdC1-Mte6kQ1-^3Ueb2U z#_V(I6*b<=yf5N4&B|eJ6!V7CTJZI!+oiYkZW#0S_wT6dc;@wm-c!U7=9M*)$+anS z%{m|G_oux0CA7XyJD8ImYCTZe@=a)@G=zOgrOzFh-MXaF<(P)b-hFf$S!(Y) zLLJi+p3#nJ%zw*0qX)ZrzV(9=sYFGdZ_KbnICo0#p#X!f$4 z2bbtXTI|WZ*Z3LP{9$&u_na0z$^ma!sRmzND_-xpoKqUsA|VK2D5tUywxs zK7QKlOQsT4`5JzM-jkUT^O9#tG_4DBkzz@7XaRG2-*@DHnE89iTdG*3g_>_;!?zSX zjd@f28yb0=xuxS9D%iE9@=2WihT0urhJAKpQ)P#Ll^x88bF)AzWk-D5$;=q{;Spx& zq3_JlS*%HGEm{3{!!QS zXv0TcXZ!0Pb^SiCKI-#=UFHja$phj@eh^>shH)jI&?9+bMYs6VV(p#DI3~+y_)(_mNX6Y}`jNvX=KY2Js7)?& zzpL6k)$CEq=gX1pRN)mf?7fEb+64d4=a~^F!o*gOZ|=j4absUGLyup*G0F!z-wkJm z{z{9OF|W?6n2$UT)a@lt?$Z5NdhgcbY#k7!$M?(%A{lq|Qmx-so}R2H!Me_2mG|iS z!<+2U=LNgW7ygn5#F6|UzT^$#NRnf9*a zU37x7uMKvgC+(SMym6*84$KQXIa7yQ%zKZmqst}}m4As5>&VfMIkM_HYFdo%4Tcw7 zN8?v9!|t2K41dc>yuKsOmut+3@6>dPiivT5uVRLtcW0QPv*l-I=$}}Y?>#Ut&+5#T z8oKNDIYm8m|HMQOJx-4H_oBp4?d+wGd-8&pu4hOiZ(V2H6mMOB(dFLyykM94!e8=$ zIFcX4m%L$I$tUzko}p9n5B*Y?x0d^8Ur;}l69?;1x)aH4yf}mmt}q`B-b+?LnFF<+ ziDsSpEB`RUvxo?bmgFn6h7c4?OGdw0yrlFW6Rzl zR3w|%WtY`A$@Dj~N#G5whhQ6(x6@ayQ}h7leZ{ZS)(y-tQ?F6kH_WeIUZudUX3D?s zs;e}7KXY=ItCX*%xw88eF!(-+ z&P=cSy8fQQ_w{+fF7t)IZ*0$(wHOW^OUxi~4?Mo{;KE4~KB=F1vY>_bKM-{k7lAG~?Qp zZ|g~Of|y|ss>rp2e}5Nd#3_)$jQAS|a_ul~@nB}?`TUj{IxQ=4?Vx{NYi7*LzZ3Jl zQJZvolMcSRzklh?dYnTyHtX@j7jDtVUHW~CuBVLcR$b@(?OS#I7xr(}=LNgW7ygn5 z#F6|UzT^$#Nv27ttLse8%+>XGEc8pC7wj@$_)8uTNAiRCk~fSi z`Gg+HGjvM+pM!jcZEwUJM>)Z%M6`WRx(3>AAe@dYvEqz(C?pg`>!YIy8o;w?OEx(IL_LhhQwb{ zE{kN`zT2~OJ+FUc={mcae~rWZ=B}y zWJoAo3}-Hq8$w?v9aQ$j3n4VMag5@exDc&hAv5f8|HLXg{Ef7C=}MfT-QyG^{*E+e zjQhgju(Cr>+-GL!bm@D9Kdb4FSBL9jW_Y4A`&7Dc$3M9)GCT z<6FjUsP$AAJwJk@be;7dMd|uWrbOxUf?ehdf5`*lNPZAs@`iCGpU@+DhEB;p^h;d| zylF%>PGi+^YgSHsj>wDIZJ;q7ie!!qt4DtlnU^#+qW86V-_`SF9h$g+`Qtr9O25ra zr41?6g8z>DxwSS8-p@SPt~NOv^51K)AKT0f|H%dU?={4!K9?Es!)`ERTqCW25NZlN z#V0dEr}Y+Q=y%on{=f(Gij8N!bEt`KU$eNG?mxDsi5_R;juv`+hj%UYajR#V>U#Pe zX{GBdY0_HPf7H6QJ}=m1zVMekAdch*@g;8tzg<{>5PFUksN1#bD`Q43_@IVCi2B zmj10b<%{>5PFUksN1#bD`Q43_@IVCi2Bmj10b<%{>5PFUkt96*S{Dn{foiU zzZfk2i^0;f7%V-D!P2u>`RDa4220Ok@S41y#bD`K43?h7VCgdg&NkvcBVg$>0+v1_ zVCgdgmOdk3=`#YBJ|kf1GXj=ABVtFN5%EW#5wP?b0ZX3|u=E)LOP>+2^cev|Kl+S- zrOyah`iy|3&j?uhjDV%j2w3`zfXC+b839Y55wP?b0ZX3|v7^t3_@mDV7;(^N1T1|< zz|v;~EPY16(q{xLeMZ1|?)T5?nkvrvFC}SQ5c9LNmFnwpmi*G5tIvxc-nKc(xK{gGlIV$R-kL;b^OJ2z^v85IQ_t9AUa-r2;V*eW z9LW#jOWrW9o9awtUfu)BXSbErjr7ta5`q_b{pB-5G*@2~>9a#F=fu)}v zSo+z4rPnQ3dfkGh*DY9j-GZgpE%;VmuUoM6x&=$GTjihE>lQ4%Zo$&)7A(DP!P4s% zEWK{Q((4v1y>7wM>lQ4%Zo$&)7A(DPm4A8ebqkhWw_xdY3zlBDVCi)WmR`4D>2(X< z=f=Hm!P4s%EWK{Q((4v1y>7wM>lQ4%Zo$&)7A(DP!P4s%EWK{Q((4v1y>7wM>lQ4% zZo$&)7A(DP!P4s%EWK{Q((4v1y>7wM>lQ4%Zo$&)7A(DP!P4s%oOAN1>U9g2UbkTB zbqkhWw_xdY3zlBDVCi)WmR`4D>2(X1UbkTBbqkhWw_xdY3zlBDVCi)WmR`4D>2(X1 zUbkTBbqkhWw_xdY3zlBDVCi)WmR`4D>2(X1UbkTBbqkhWw_xdY3zlBDVCi)WmR`4D z>2(XPxs7|>f~D6jSbE)prPnQ3dfkGh*DY9j-GZgpEm(Tpf~D6jSbE)prPnQ3dfkGh z*DY9j-GZgpEm(Tpf~D6jSbE)prPnQ3dfkGh*DY9j-GZgpEm(Tpf~D6jSbE)prPnQ3 zdfkGh*DY9j-GZgpEm(Tpf}ISx*DY9j-GZgpEm(Tpf~D6jSbE)prPnQ3dfkGh*Dbhn z5AJmfmR`5ugMr-Z7A(DP!P4s%EWK{Q((4v1y>7wM>lQ4%Zk7LB?sW^6Ubo=fNbYqD zmR`4D>2<5PCHJ}oZ`x`}z0UIY1zATe$svWmQz$UZl75$GZak+GC3WNPAQramOzYG5 z8N5<7ajb%PG+nIj-A8T(JX4TQO;o|P@ zgADE(n7wiL;O?$7xXUn%;TA}62<}d1RW}kK5C|3sPJ&wqB)D_>sqUVy-+$*^*ZKau z_t&Y_tNQ8cHC4OT-t^NP)I3Zso1yuBohkCiqnh`hm?^gh>-%;}5iM^g(^?g1I!zu+ zqPfcq^*f?Zw6(&Ee-}%FkUir~YM@ENAxO==|C8>{z`oW6I8v)1K+Q>$Ot7 zhtS%*OL#moLp5$_pPSw7%LB&zSX+MgJk`w`klZw3xZ|3L7Foi8zPHT)qLgr zFd6evzfU-B>j*h$jphuEM#<4W%{6`;Eyo_|!8#1uG)4}qs`+dCv2wTRfBn&*zTCT0 z+c(PJN`5fki5OJ2n;i3T=L7|@AAB;(^)=gqramRxTlLO z*mXI7o_y(KR~ge-fA=RiteebHNPlD$F@<9=7@Q@M_ET?;*Dj=ws{u46TC znBGD5S*BlT}bsb^h-^rdB-Y5KcP4L6jOt)A-dH)WG0 z3-2C`k5pePp^R^Wq#K7NwW1gG$i0zJGdw=4V|+RF zi{>-O63S(*&+>TgT1n*C(VCYWO(wJU&|I@zN|__G=B1NU%cBeRwH3ZkEC0Oze}3BU zC?)EcR&MH4jprO$Kd~&Ay@lp`Uq$Qm`n!Zh-o6nrx5n{!y(;0zJXBuh{7ql`=PUI)BpdX1 zwQ?mWBTJvu*S3FGQeLf~`KKG|-<|wV&(rts=Cb3#4t(F$En3S#xwC=;%0%bZ@>cBrSnFLpL( zH~D?z);!*LUkBOtPIKn(T6dBy>bGRhRj`XJ7u<>&>%%&6F0gK_9}M5I1~ArywSlo# ztQiaqpamG(KqD};gr;C<46VV~TkJ90sJK9UfUzgo8!+|?dj`fHVlTniTkJ6ydyc&a zBNh-7V8jSw1&r8141p1kI6q*-8e$HN7#yi$5scVGjDp)=zZ+}6zT`t$HZ&uTKd&{vDHsZKjQVB3~{|#eC}S6ZxiP3g-OT)xT-}A}Mp~fWOsu zru4lAKYt?Qx-BEq_r2GfwitQfC zcF}K{dsTiQug`nUyfMvvxvk49=7kT1ocK=1aGU*mW#`VC?_b;}OHHZH^9LpVNnWU0 zgSlSq7`b__<~8A-Y&b&m9|uTI|6AL4>bFORC9KN!2jcIRWpe3rkz&qHxpbR87rrbz zod+0Ep(>H6q+#WrgdGo?`vj5u=%(D-zl`D3RVm_F5t*o|X4D;t%Yvkms zY^j&70Fe(BHrcmm~;v!G|wuX*@J?CQN#|}C+jk@~J>n0eL}{6}_uT!6>d7kMi8FV*uDQr|;txGs>#JN@@qE=!^L z>ybz5{cZg`jI;2e%=KAwtKbK6f26hv@%<}D&o9l_HvastTve?c^O-mQ$!V)9Ft5n{ zQZ`#tkvaa*SMo|F{dX|U?botmYafsI4frU}Hq&RPb>fdQ>Qfya7Y9Gct^4#@8`0o{ ztUFtu!RSrz<=h4OY-YLlPOiS7&u@)SZ)Li+`dlY?|3+>rs{h_${^8B9@|;Jyypm_W zyTyEZ?rS-|m*!>r-^haTHD~PRlzH}O{`txaIpvh*ook=UV#V~m8b$vj zGhEcXJ?xoW*+$!Bn*Cg!*sZz4+JEKX2bwb+`cL+LruplCtL3AWEBLMdc8QQz}gb8#v2+7YYdnw!g*ujN@S2b@{X{Qu^63AQy|CfmjTk?o%h zTq@soSj`+ZY>C`V?-PGh>IJTn#Vc=Rt~PCz z9G-6r^NGW&WYW(%A0GVcDj9ixBag>jrM~;NVFU9_HD9)A>zP}q-&m+NVI8wn-``Ie zy_UK5O7%M&>fZsxy`nm;lsU@nU{2b3rTks${PyQnE9J)OI`7?IV3n-0XAj%NdAv$) zOSX^sk@_yuqoDoFnNzNjUwuC@|JHe}?3pNrIs2J)GXDb2mA>5|v)51kh zT{g?`otkT@cRqVo(7d?YJ$~!WUOBO+9{=_4J@U{E?L+S~yXEvy z&6(Eil0mIBPaeBdzHFs`OCKp85}ue@y*IE?f4Lxt(|<4s(O#Q z#$)DIOCHOWNggprkAE!Fo_)aFz3^jMe8qj{Dr+9e6`}W-|Ni%(oICL@^Te|Y<=>m) zaE&~z@myI-{k}K$@#kjqnjf}&DAQhj#XhH6@Q=)1_YHHW%}-_Xb+4HdZ~a?-S48u}{&$X`bAjWp49 z_gmR>k>ak35PV>VwkL0}~+Mj*n9>~0#G+)YmU#4u3g#Fy{{H}bR zP=7b!zvOpi$19p^4!a|>kp4bGt|E72_vg!N_a$e4xty9V#}{v{v$l$z(c5_wB5 zXreh)`P=fwMg84@LNT}HpG`FXoaT;9c}RaBVM(PsGHo%<<6d8r(~jxiRd_P#ciFu_ zI-axA)C)4Ox8{OBT$HcpXpZ;OAM)f{&DXD9l7VY9?|6GzrkJ7m`(#&T=FXa*CBLS= z8>PAIk7wlaiuztPrk<3qSEb>5O|SloJlI?F)DMT{t|-kX&Pe%tB5j}lW{jM0Q}clu z`{d+A>G|5r$F|Bs#WbJ&d7J!usOAm7Z>l`ofP zVVih;w#t&JHJ8q`RelZ2%;RO3Y>_|5(H!snX8B`OCLW(wcC(z8OY@VtTjan2#<@%@8l@bym!_D**HwUhg0W< z`g_qyzlSqn#C-X#Msc=p^>n7Z-c)~gHD!+3@<>k2B`VC3Lx0!bhwWEpuFMmnxkb`> za_{>ReC-c==E;piHJ2(mU%vfQ&-t*}3|Z?3J9wE1<7V@JqG4>UKEqvXqHn)82A{}#_J&525mmuEUG?~;&pl-Bnwn=e>?jWn(R?9ZV>x`0pM7{-xrxk? zR$sgPP*a(Cg674c&EzjvG{+s;LcYqQucf)IfPsb#^Q=c7e(eYgDs!x5lr~t2PXp~>BD6P-tkhp%?YM?%Ynd=3~ z9=r9quHNq(xgvdTwm3Aa_sE&yciNy2$R8^xuM|d(^+_{3I3I2M_BbZ^lo}T)KWQ*{!VR zxix#p1fw;#4(=w?pVM4!Y&*GTu72M3%iURKc&Pt|#(dX9woI(&yjP*Myyn-OKeCOy zcT_)DGeotORjO-lSGJujyjNfAO>HN$25Mf_tfbtSFdO^RXLW%5SX4h7eJS$FUQIOz zga@kc&1pXMp@4i@TXTvIg=MF#nwu;rDmPuw^WdpubMk+)$Wp7oAqyf>chiDvllTM3=>#}^6ZlB7C6@6$5AY}#FO)eLcE z&u5x*Wc?z3+NksSHa~n2N7ZjmA%9zWeG6>&9~`gNGr_+pQVvE)NfU{Xu7cJz>ftt6d&s2Xnp>yNQ z|230Me*406t{MNW9R5UKn=xZI`F^I(bzi^fAm@D5dGeWkZRFt#+CFjZ*78dcoqKOD z+g2txp?PrQ_OgRtU;AllM;REdx%F?I<@}YJX9fmH8lh{P4_&g#E6HxM4_&)umB(u8 z&m0Dy$|{SF)}IL!T#`+8SfT6vohP%)1UqlD{lsQDW$;>E$CVGsD&x%4pGEA+pH=>y zO@9_KD>REtviS$U#Z}V4nCUv#e9~ z67$8xS!Bl1mzfXjXe*O`zn%H+zMk?x30=Rh8QWccDX#fpt*$a@JI!D7c9z$-X+D{! zqa0jZ*W(?ORwvGD-juwLJY?p1u70y~{#X4uz+bZm$lm5Vr{z}^NyygyzM$5;UwEeRqBW1~O&6RVEkR`I}d$r#(Ozu3R`EAv4@_y=n z`Mwk0jF1gK=-M#N@=@|uNzI?*jFHFdykwiuOk?HGwO%kEzC2czD)k@p*`eX`yTrOC z9hPK@jF(;4q1_Wrkim!aJaI3D$sODEz4n|9lM65EYdgISlh@wpIpZ{%Dx0U)_R*)N z%5<6aJi8xHlYMJx4c*^|ytG^W=4dg!_M{1C$T%7Fdb^CDE-PoyYb=;^y8OO?*8Kmk z-;mspy@*WJCVsB z?7+AV*Ml)1<^|(ExSt(w{h?^A{g{)*nK94n2_>0vpSg)kGvhw3JCtF@eO?SM%Z&RZ z2r8%T)qT3{(~SGnxTP8QvE#Upwa0zzJh+dYAOCCbi~nx@!FAS8%xC?_eeAk0Zr2NY zs{`h-`e1&m8}4KE#C@#JxR2Ez_p$p@yQliMy(a3K=-KeMa#ob)n={_Xb?Y?;?0zl# zU(?*|*(=#BK-V~fYrT>+hHGBwy_6d-Y0lj0rHrnr|IR+n^is~{tST|I7TUfSY) z?D$soIgGU*nDJxmJVDn!#?GH(>ZjQIK1umG)}LX+KF9jGdgtd@|L6VkId)wbx9f$y z)dBNZeK5b(4fnNr!XK+M{IvSRf4eVt?tKxzm#D{iRAj-AqCq9iH6q`NZf!N!%l%3e zn65c(%Kt>lbH={cGw~&`K41H7m8YUtq~@X(`;xq)%}Jb}G^&R`z<{K5S8xrF=L=N0_1&oTIEpKtKrKKHOL`#eN^ z+Hu6KwMRVLc@XDze#F1MFV2Pa2j|85iF0KA$N94B!nj>8?5z%%$LfRmt!}ul)f4_$ zo#Cg|AO72Y!S7+j`(5|H_9ogP?|#(0Cf9aZeROU9yKukOHrb+P9p=oFx60?O>oS+W zv_wg15z}MT^GjfdSP#M zz&utT%x`tWeXXAG$Lb6}t^V-e?n`^6cakX`S(CF#*2;G4G|y9eRXSZK9zU#pFRuR2 znzLS6E$i;=%;P6&t(K23cVVu7dX)?+-i^7k>ZRUT*PXdp)m5@prJl@%i?5OcuJno> z4;|Gf*8XGCe$1F>Sy+E&%>V4l0A}2G&ews=@MqSuLCo-T-SWZA@P9(GU}miAObN~R z*RP8m&pTv&to_U48)D~Ka%Ds8{7(mLjJ@xGyBlNu8Rgp~t)D%HY?9Xh8DX1Z*M)Jr zUf5e5Fpt#-^IP3;U#lnlu{y&~t3Uj=`_k=pFFC4|?j1L*(NnIdq51sw?sEEQ%_S>z zlZ(!2{_|EBnW>)cNBh0bvd?wRRZex1sU!3`Es(vFyj??|$EMpm%AD%o2EZBlGOeTB za9uOT%Wl@^5%wX&^?AfR)l2L1i20vf*NpoH1?#g3f4m2p;ped``kcc5ox?R_UDqNs zkDA;kcKqLT{bKFs&FCLH&%N6NV&@M}GAQ=GVQ&Y;`m<#H;8;J0r4Nqv|L8ZtvFpOP zT`%md4w%R4gZZs)xUba{{#c#ir_~?++kM%y?q}b@R5|=_J_iWH0-WjhEj+$GQ&!Ps z&vNF{f29+fH!oq1TO_S`-}ndSD)Ul{cXJmqe@dKEjBc}ld0547x5LFgLF=vP$PwXf*mATu3IO5wplb8$k|4M(R9?AUZw=a~V*g)pFVP7dv-=0WJY*Cu|NzJ6oZli5hj7~3x zJSxjJSyyEgGxh{&`vF-+l|Vgz=#cDUe{>ZdFLXSoXcD(7^PQ;NV!~)`Q*>oP@zd3c zJf2~F3DLf)o`2NK@|FeIXe%6Tg`=%-v=xrF!qHYZ+6qTo@#+7x6^^#T(N;Lx3P)Sv zXe%E5pSHr$Ryf)UM_b`&D;#ZwqpfhX6*>P;Tj6Lc9BqZ8t#Gsz&^C3xo6uS856mpm zkG;rz@SAL+{n}H^Ns8wDpLllT++6E-uJt?D`f;uLZ+@H$WlM%}Pdd{-8IK2vD>Q6s zT;`$cey6=pzwo}_SbvTZhks-)v-}LLO!1a^&byOzaLWs3&-V*eE&DI?xvxj4VX=qI z<;owRsXJ~n-+DuoC*lV4Z*hnc{BW81SV5xE#V#;!YcA;8tuxGj{&j$E?mEQ$&$-{I zeoe`|xYBw0Z!9r)fBXkMe&;c#*mIrQyw&694&0{0BMHL0>nqw*E1P-_p%C`o3Qif20AwoMW5E>A%wHtlGEmWbwqF^V;X~GKnah<~rN7 z*^=7s9qaGzqtRA4+6qTo;b8I>$ z6I!P-4St=4xyI{Clp;wc=5{m7(T5Qkn1?niL%)g zeYMTO@RF$B!I1_Q-TT-+l^PxS7sYl*#n2Suy@jvnG#<{uH?_BG5uJz+u z$0o?RSI~vYC3t@af7%$7ICTN$V%MUALLcN~ZusYvpgZsLFfWQTF{osAeRjTWJ0@u8 z9erN%_Z}Bit0JFY|FNWFgOYvJXXFL-3EEmU9bbFBPphDO8PhPgUQszHMXyxMFYo0J z`nHOW&;B*z28~&%&r#Midn-MkrulT{=$JTnHLt#MJLc+RZU4*Ej9&T^I-X}2tmNIV zrSFw>Un{R=os2yH!)g7z8WplK=Up_)n>9@PT(;Rbufk%zmN&h|cxU(MH5NKG-Yfc5 zul?YgDcMxCK@UuM)9D)(hZouP7HX4Dxf_hm+%p>khl)EO%GWk#K$a$jcD87lYXXFlo- zmHRTI&QQ58GwKYL`?5Xi43+ybqs~ydFEi>4mHRTI&QQ58GwKYL`!b`>P`NKN>I{|p zGNaB=xi2&743+ybqs~ydFEi>4mHRTI&QQ58GwKYL`!b`>aP@ch(P+zchS8R5IHN7s za7J6M;f%Ii!x?S4hBMl74QI6F8qR3THJs6wYdE7V*KkH#;bat%Qc+QmTNepE!S{HTdv`Zwp_y*ZMlXs+Hwu&5As54aV%Zxfh<-W|QGgR)&j55As54aV%Zxfh<-W|QGgR)Y$5ox7a$jcD87lW>MxCK@ zUuM)9D);61N1dT^UuM)9D)(hZo#E>5?xWFGINAzFTj6Lc9BqZ8t#Gszj<&+lRyf)U zM_b`&D;#ZwqpfhX6^^#T(N;Lx3P)SvXe%6T1!_2>t#Gszj<&+lRyf*n4QI6F8qWEQ zh~pS>i!;!ml<`2%6*wpXQ5As54aV%Zxfh<-W|QGgR)&j55As54aV%Zxh1)!*GmqpfhX6^^#T(N;Lx3P)SvXe%6T zg`=%-v=xrF!qHYZ+6vTgMqA-%D;#ZwqpfhX6^^#T(N;Lx3P)SvXe%6Tg`=%-v=xrF z0@|wDAP8px`4RFSFmfp5Ltx}bCbl`A-8eVb`kib2&b5AAi`qlY!#0NbUMlzHapb}( z_hm+%p>khl)EO%GWk#K$a$jcD87lW>MxCK@UuM)9D)(hZouP7HX4Dxf_hm+%p>khl z)EO%GWk#K$a^D#Ei8@2&zLmhJGgR)&j5khl)EO%G zWk#K$a$jcD87lW>MxCK@UuLc|-b`UeouP7HX4Dxf_hm+%p>khl)ETb+hFxuiqpfhX z6^^#T(N;Lx3P)SvXe%6Tg`=%-v=xrF!qHYZ+6qTo;bI!Dm8LF;eMlP)C3TEWO zs;*#0F0ASbX5_-Eu3$zktm+D8q7gk&JFRZrcUs!F?zp&b( ze_^#n|H5jE{)N>R{R^ut`WIGP^e?Qo=wDcE(Z8_TqJLqvMgPKTi~fbx7X1sWE&3N$ zTl6oiw&-72ZPCB5+M<7f90@ve&X3Pk!JPl#vs%T-i%e{DJiBpjuEpo){F$t>*SV9v zmUAlg-vq{ye;F2FmHYBIa$%MGGNaB=xi9ZK>I{|pGNaB=xi2%<8Cza3qs~ydFEi>4 zmHRTI&QQ58GwKYL`!b`>P`NKN>I{|pGNaB=xi2&743+ybqs~ydFEi>4mHRTI&QQ58 zGwKYL`!b`>P`NKN>I{|pGNaB=xi2&743+ybBNtY=FEi>4mHRTI&QQ58GwKXgS1_Z_ zP;~_}a$#40!@Q41Tl6oiw&-72ZPCB5+M<79wMGBJr|JsKkN$<#7X1sWE&3N$Tl6oi zw&-72ZPCB5+M<79wMGBJYK#7b)fW8=t1bE$R$KHhthVT1SZ&e2u-c-3VYNm7!fK2D zh1C}Q3#%>q7gk&JFRZrcUs!F?zrb@GG0C41sWZULJw4Ui!#L^;H=f-%H`j8WYp&IG zhQ5~T4E48!V_rSa@cD_JU$M%4c^tX0%6*wpXQ;!ml<`2%6*wpXQt+?V4Jb%x4) znNeq`+?Q=oXQ;!ml<`2%6*wp zXQq7gk&JFRZrcUs!F?zp&b(e_^#n z|H5jE{)N>R{R^ut`WIGP^e?Qo=wDcE(Z8_TqJLqvMgPKTi~fbx7X1sWE&3N$Tl6oi zw&-72ZPCB5+M<79wMGBJYK#7b)fW8=dI^rY-8eVba-M6h z9Y%QcE)gU{IQy*!osg8is7RPM`+Iz#2Y%&0R|?#qliL*>5As54aV%Zxfh<-W|Q zGgR)&j55As54aV%Zxfh<-W|QGgR)&j55As54aV%Zxfh<-W|QGgR)&tUhB8Qn@cP>I{|p zGNaB=xi2&73`bkbypKj(^e?Qo=wDcE(Z8_TqJLqvMgPKTi~fbx7X1sWE&3N$Tl6oi zw&-72ZPCB5+M<79wMGBJYK#7b)fW8=t1bE$R$KHhthVT1SZ&e2u-c-3VYNm7!fK2D zh1C}Q3#%>q7gk&JFRZrcUs!F?zd#QHIt%2d&RHPmjG#BiHmEI}y+H4S_sF@H>kQ|N zkn>EljK58!a$mj{xv;!ml<`2%6*wpXQkh-=A+I~xi2&747|I8Yf)$5-5oIM47|GoMxCK@UuM)9D)(hZ zouP7HX4Dxf_hm+%p>khl)EO%GWk#KWcXu!+>I{|pGNaB=xi2&743+ybqs~ydFEi>4 zmHRTI&T#d2_t9vJ{)N>R{R^ut`WIGP^e?Qo=wDcE(Z8_TqJLqvMgPKTi~fbx7X1sW zE&3N$Tl6oiw&-72ZPCB5+M<79wMGBJYK#7b)fW8=t1bE$R$Jj{i~fbx7X1sWE&3N$ zTl6oiw&-72ZH1#P`WJY|13Dw;$GacQs56|L>VM+djdLfbve$B*;p9~0Rz}` z<-Qz;$c6Fl4&nrL2HxEPqt3v)J7Clq{O*oo)ERhp2jj?v@$L>7bq3zu0i({qyE|ai z8F+UGj5-7F?toEe;N2ZC>I}TQ14f;JcXz<3Gw|*X7I}TQgK^Xu zcy|YkIs@;!ml<`2 ztG~OCMqBhRthVT1SZ&e2u-c-3VYNm7!fK2Dh1C}Q3#%>q7gk&JFRZrcUs!F?zp&b( ze_^#n|H5jE{)N>R{R^ut`WIGP^e?Qo=wDcE(Z8_TqJLqvMgPKTi~fbx7X1sWE&3N$ zTl6oiw&-72ZPC9Vr=}MCZj*{z#I;j{|4%%-aqiUM_FB~1_FDZ8q5ixJpIPzWB(=Zz z?2F&s!CoU5#=ARU)ERhp2aGxc@9uz6XW-o(FzO7vy8}j@fp>Sns59{H4j6R?-rWJC z&cM4nVAL6ScL$6*1MlvDQD@-Y9ky3>hRS`JQD@-Y9gL&Sz`HwO)ERhp2aGxc@9uz6 zXW-o(FzO7vy8}j@fp>Sns59{H4j6R?-rWJC&cM4nVAL6ScL$6*1MlvDQD@-Y9Wd$) zSATaORb2ra^e?Qo=wDcE(Z8_TqJLqvMgPKTi~fbx7X1sWE&3N$Tl6oiw&-72ZPCB5 z+M<79wMGBJYK#7b)fW8=t1bE$R$KHhthVT1SZ&e2u-c-3VYNm7!fK2Dh1C}Q3#+Yg zv_=2IYK#7b)fW8=dM=p$acfhDK@a_&6bq3zu0i({qyE|ai8F+UGj5-7F?toEe;N2ZC>I}TQ z14f;JcXz<3Gw|*X7Sn zs59{H4j6R?-rWJC&cM4nVAL6ScL$6*1MlvDxz14UMS)Rg;N2ZC>I}TQ14f;JcXz<3 zGhF@MeKgvle_^#n|H5jE{)N>R{R^ut`WIGP^e?Qo=wDcE(Z8_TqJLqvMgPKTi~fbx z7X1sWE&3N$Tl6oiw&-72ZPCB5+M<79wMGBJYK#7b)fW8=t1bE$R$KHhthVT1@Ox28 zH}o&8w&-72ZPCB5+M<7fIQPLG&v4Y(V8k z%L44)cgE~AJm-y6HE8jSw9GLn8dI8pbj+*XOnSy#e&Qgy*YpzeH(7hDch@;?Mdk~gtq;6j&9oBDtAJtXcT&FOMRz@h0vjqN!aFK(GXgCKQ8n6Qy~;O_lpM~qI-tW@5P^D z?Y_b{2h!E7@0eRn38tuODR`a*=Lb=~YNqAZzo43wVP zlP;`ILAf$L@qHaMh)T58*X9WBK@ls`@I2>B^rn?_Q}R4(TMVRa_Y&~G(JE zrymDWn(K+F&Voz63Y|izXU(L{sjdgp^eu^)zg-hT8GlI0F>|K=K=Pl!TB3ZF&Z)RP zh_&?hEp9r9p7+(`eRB4oX+Nc5n^u4JqR-Jum|q2kP_}XjnbTYfp$8x1GXHZrgi;^) zqWp>S748>8*YhD(Yx-)}4WWLKNtu76U>fr-5%ag-g;1~lsi9%exElQ|dth@d;acMx z!8bDxIr9+aF>4{L#rRK-|K#{jj{oHNPmcct|BY4zt&Fw=ZOy(D_TA`Aj?M&~O)QZU zOTvjI;lz?aESdNrCw>U=V`7G!m=TB>6DNc?G4Uf1KPG0#i5YTYMmRAe5Hlt|1>&(4WtH#5>v9vFMTJ}xo%b@Df5^6!L)HsBId3eLugCE)YRd^Z@!ej z_M@w7aqgmgXDSY)jqehxc_#RxTZT}EE=ie}p9!X3rxGy-FAt$aty0sXIVFAT2lu0K z+Y#qUd^IzN(9=%w)Uz>%FSm;Gcm-47>;%PqGKi|(O~r9Lqkez-v?n=_xBGUmwecJq z&$01fW9BDke!~352Z9gAXL5Wd$7h1iW{re3nza+wZnPptD{{0VXl1k|XlpbV(A?~) zaQ0L za;$nY2h!(sscG{5cfK3{_M`VxQZc`K-k;(fP04&I^+0Mt$>`kf^S%@*gK7T{sW>Ln zo$OCFZl+}3@N@v}&ytMpzc}t&7!pi14<%v#H%$oDTAG-7=HL*jTP`&X*%IdKxT7B} zT%U@0+OGbz)(2A#nHt*qiqGszJI8UpmHa(a0qlEqxIHy7X{xOI?9Zkw-r{}U@YL+B9^Zv_&t&Qi{kYhuzG500h z*W8P6FXIEj2XkM-ea*TE>oRL0ti`O6utu{k!n%xBt{$py?bZz=WV3^_N_?9=c|4|Fm39PlF#71?*~%OFG=X%@bv!3cfl01EhUXzo63Jv zeJ20#SyG~cAAMsYgXxdu$<*KcH@<`F+Qj)&(WWWKe95N{pkc+5(Uu$$zW%*}sr~QC zsDeM#7x`JmcD@vpXGalV=YIxKsW-_uhS%O3OdTtwrt;5o`@UV*j}FaB0e^gH!Uj>` zgcLZ-KL2;IOkiU}urb#Xt~K+MGe2Q|;{(A5;~T*@<1@i$vlhZy%o+)6G;0@FyU|BD z`UvP_G!)R#Xe*$t(Of|D-=?LY4-<3wibf8i+I^Gand$3uGT1VKjSa!Z)TCT*y7lRj zGmUYs#ry3yy#`;JGY7tX>b>jKmbr339D3fSGjo{IJLF(j=8fah(c+ukn2&VNN;UUr zn?!T-(b34(Jl@qSNcp4n{53`tqRQi{@_76e1t`^@Wte-`2_)l#-|@lk_~3VZ@H;;E z9UuIT4}Ql7zvF}7@xkx-;D-;N3w2QbETzHA6I%9xD`%?9;~$O|wCn><4P_l@{Qk6- zec<@tc2oI4*pEqXQq7HMVJq1au>55#!*R@DG z$~vkG?(55cIu!+$>%?68a8mk1)$p)MHZTKCy$}7D`f|+5M%DN0@jewZQrsw%RI*^LD@60x@9^|8OOWHEO4J=4QQnhB@bg3Y1uGomL{k44| zDscd@vDD|aEkvcSW9>_Qy({FVf*rB%OM^1s&qviev(G^#Pv@mxL-<}nL0bZ?jpx{S zj*SN!vv$JT&3XyzH98PQC?;~8mO zif&v>4%;0-m+E!nYa`cZpw0(0hmOchr-o_!Zr|o2sp1Fo&-<94B5LXR-<}Sn-J{#_ zoV)%gKnqKEW}BWV0_jP&w#?VQDM)pGZ^hiojn zIJ!k3HF?#UIc|e|wBk`mJ)Sy0Eg7lftwXI`)N*-Ob#0U{O~!N-CmYt%-&bfx06ne% zpQC)~T4$i~do-WUlbJsE?abp(ujHfGYj75#e2FjRr#(B`GGEMDkhTW4)_lGot;vd5 zt?4_TCy>1SU6_AOn~&}m?8JQgP9U|p#~KEm`8k_q4{WX_Tx)zI_-5uIXCA^lW-WxZ z82`!fpB(?m@t++3$?=~qD*ugE1g(s=>bvQIcHas6ZgeI`XBw?^HnBubED0x;gcC~w zv1Hwn#Kez4{Fs;_CuYcr8R5i?K+Kr<6o}6>BRX*ou)c0G z>a?{BbLFq4r@-gATwR9 z)q%%9Bq=~2b983Do-2^z*KW(4v3fxY+|!DA^5cSZ;FUgW|Gm#cLH+bON;f_iZ9mzG zYsT8W0_n=_&dg;x=c5YeJ2D3c~cm)g^P${I{Ld*_q&*Ts4rQ zlXPM3UN#@~kEh3Hd=8}Jce-&Ne)VNG+8mBJPvR>g^U=bTcn;_A4gFkz&YtGyd{EXl zx#`vg9k*GYWT)D*_4vCxxvh=o*m#bO2OBd#Ir9_dH$D)2Fg}yxGdVsJd^T$&tkJBU zuy&&rIa-mU6+tVbEkRqOxq#+oPldCm!r4=SJvI9%u#aYc1@_nMsc`mGU{6h42`8?E z6Ia5CD}lIL@Tx1oab8;YVg?%hzAM*~Ssn#Yn!;hI& z+;?D`6{!o*l630xZdH3GDilcPitE^3^k*P#?%0lFxWlaiRDDw?t{FE@Qh&>ib!IL& zJ|7+1+L1Z^H~Fb@cOB2aEXqawu6N^_abtLPT6$1({f#-OiaH~xG5`CVlU}^-!nNds zS9$3DQ5};5Cgh;6vouFt$Vs=Scj21x{oK4XXkKULIXm*vp{<>muZ|C-MSpeUnz3}{ z?3C_==DOW;P>BVaYsciIbi2E9E!pO~+!S_J$8e);>UR}}=VK#GXLxnOGHwRTKXL@o(Z*IB_cw zx8}SEoELLO1kQ*#QvzqooEL%fV$OxYxiIHN;Jlb~Byf(**%UaNISO^+TJk6L_qTV- z&Rk0_Di%l|@9V!EH`C;$O`Y}GT(~wD#W~!WYsu`P`DpRPZd^;|%9D$}4DQ0Uat}1^oF#0NFQg+asUOZfD^*u(<42#=*!UeAKWrKY+^nel z^gmnQ&$0l!_Z=45lIN_LVIUQ*QHS|J_(<9kRfc)NqX6^fsZ*)ScNv(=SBaz{ z`>*4D12J?=G)=9zh`Hm%NV+|;HghAIN~5<%{{)+&CnwO*Dp}!=h`2J;`oQZoKKLCU z{EiQP#|OXTgWvJN@A%+%eDFIy_#Geo@Znj{%4#i3X?LCRmVMw7OOq)7m(rbVQ!M+y zi)2Bpof4_{Fb(^_cP_^B&{ysMXA~7E%sNn2rGsG~xZ++v_ptuiJD!e(B#1#>-28DU zwf?05_cUjAnM&za6o)^)R%fTsqq!BB-`1T>i`V91n>TI4X>qBvJl=S1Bu!kNjmIa9 zjG!tNWDM%%G8v<3=8Em`-p<)_mA=!wi}S4EJ&_($e@1)}NG-T!lSsB5f^ z=h%3TjRzaEcEZ}tdI{?_IuLX)YbR&zCQLeRwQqj2_7U>`&472w`wsWDTj{mt^c*EJ_irX;@>V~$A>Myp%qVt)1@ zoR(Dm8iT%S&y>+LCvzUYcGr+_diXIb^Zc0+bm~F^w*MreC?J$#PzzT{9!;w@{l@Wg zxqUQ6*V)3nVnq~<%5{ltiVTgW)kW4Y|J62%I**yhyn1;gt^YKd?U#>=pno%$WB#0Q zDn%dpJqCT%^#h`5)Sf??$EkB&tJ1H`OPWMe>aPhn-r_0UqFxnHzD4{zU$R82cZt_A4;d6i>lZIz z?y*0Tp62>P#bixia7Z-ONq(C-sq!c8cc+-kw27v(bJD2$J_(w*FVeCHHrEoaHNFvi zGxI24V&@^uW7a}gi}9Zv|H<*69RJDjpB(=Q{u`|bS{ZE#+M0bQ?7PvK9GwX|n^+=nttYFx;C#EbCPr_=9A=N{`exC$}bxggT87}6%UD$7T|v9hw!QN=h@uMi6(|q zyiHk|Q~VG?m)3bP=$Yn76ixkV{K33k?P|Ihv#F^SKZVvnpRxB$=p@NK%!13n5#96rc^(t^3Yf9`5=-y)lbNA zdwEY3W&Y`cIy)15dk3lbS^pRFV0GB`E_G3cxQmpPgqPtMBYN0&#?(MnznY(nElQ~Qe-nePWjQ`Ix4IBwsn zXGOq}&CI`iA4RnETnzfELwYO!=iXp`H9DG(r9002rFJweI2WJex!sv4+EqT4hnlzZ zt4Qh{m5g~w!zc>+kdV2?hA66$>S+x6s(U*-qv`tuS7XpuEu!Li`ejMZ{7J1PdAHPTQ}t3LrTg*$f185ds5!?! zd&XxcPnT%&mAcEkS*^?1c(5_!gmGg}us8Q5+}GTTa4+Kn!3T3+!hOxU2qd7ryvv-8OGkZ$dQ?u8Ey*7JF&YlwX)WilM zHcTv$6HDa85+RmM>t*rz zY_2)4&PDqhG3cvaQ$AOmkkCV4we(JvyKcM}gT87>wU5Q){vCr__&arN$!bYF^i}hX zSAT!6J%~YHHE>uoC4Kxf27T4Ry;QFF<$VnLs+)^P(?3<8aSXTb7ER@RsXf%f0oNj_ zW8W|E$M-y)$`iJH#@`y>dZm?N0vj8Gjk%U^t(l*k`3dtI9|%4e-w3`Lp9wyjwGh@~ z)<{^RS-Zg6jXuKBM?fE=p@4=)TLEp2<^q~$t@0%Xebu-bqN(V+zwpfT;W=-ZpZUgy zVB^-aZv9(0Yd>A{_L~ti`o9q7;7+?^9vvIQysyQhm;tG$Fu!V-$-6m}e}_a&T2a`0 z(J_L@D<`h*HT2&-8+Q$5KDcRt*RdjhA4F7Gv)D5} z_(T5B2fyQk-|@lk_~3VZ@H;;E9UuIT4}Ql7zvF`+K8%_@QTe87$vyEc`@j!!jOFoo z3+7n%fwz_5HB#4a3R?Dot5%9sy`Hcivps9&9nPw4(!L6_>;rH4dm=tF^f$Plz>BwO z4D*^l=6HEk{)!s#(W*jT`JDJJ%u?T+>bbo5sY01YO-${rN)ygDZ=RI&LY6`ErM^nl zYI{4c>G69VDtUPlN3czw$D_U0gTmQn(!`10ydB!U%dQY_`F(BEq}U*D?K6GfBqc+= ziI2kg+Gi0{y>XMU?@N743PgD;l1*YBGkT`iqCq6{rDYww{114}pn7=+c{%g(cu@4D zK3=~c_4tEPL#&PG*m#bO2OG0?!rIMx3F|dF5OgqWCui;CtevoSvo6BAjGqKQ&DsfT zH~NsH4?!QJ135a7qXRiQ5Ogs6D4cy1*vF0irgHD{P20lWDqkq?@4a1Vy!~~DcH-FB9b}rtA1XtF?u}h;bC6lVuO`uk@7+SYrL6#hi{cCRk!UA(CIOv*}L)MNM@<$Hc>ptmul=AgBs zy}NJpJYJemZ_|I!D#{ms;8ZW?MZ{`NU$23Ky(*b;-m->1yXXx?r`-ghV*GE9Z zpk49mSoXl?TEex)H-c|w9&+X(%wyI4II$!UOD2BQZ=%P>4A&Ue8#UE%KfGiangGAnujq@zaQXrpA^nK;Bq-HZsjS=#bctp z&cmj1KlJ6E!rscF;mkMFmiBV0niKWor5}R4fTx;|ejMW^{Ud_M13M1(ZvLjPJ+L9v zOMfJc$4|eQ>fQJ2^YUv%53gG3NRIj5y<2)mWd!$6+ujZKjwg;}zSN<=w`GVPpOj~~ z*GR=bYRU4Y>vXLq(X zo@3)VHXdxu{N&6}nBVw7@WJ>@j?d)yOz_#Pk+4RycEZ|?R^(_!j#dP%jJB#5($Z=! zpt;#o;q0k!_Eca`%{~h3quF19{WW_koIMrTQxjLhi7Vm6m2l!pAg(sli{!p)>4^5; z*^-eQZ~g);y-cOTxlh`a>RnJw_kEzZEdC?CwmnuBgEBt!|k4MZJ z?EN|`g6FxjY^e9VqK@Z?43oWPdm^}hI(>AAmpHDfPgGr*>}`LqVQ(|ObGWyotom$1 z#dEyNExn?rBDjBA{c1h$_^~|0GkMx3 z>(IJhh>CyIl7H{(;LT9$#pf`GPxtX^*VG*Sv75E=92;_M2sY-vg!`I%5$9W&B@W6pt;#Q!rqzvC1-yL`)l@; zoING%sfi6jY?xRgCzi;GB|%A6O0^J313z!@=TN8s$3^CECw%-Iw;n+eoso&1jOzMbu z+1W38cz>3Qr^6=`>I_N^!931jpV*+(YQUlrz-YPOKz*u(TiV0$8eIC-MuCv zg8Ql)R@C*H*JXcvCGNKKN~q@sYRSU&+FK^Du_4%)YYEqy`N^4|Fu(DE;Dhmv;G6N8 z;Iml^VJ&8jgf*JA3#{GfBOHAM^f4L=XlS$*(AH=!YADSk)Vfeh{`0<_S3Mm+GkurZ z^|MT1V?(fUYQ{=Uw(I(_dl#zc@K26Sj8orPd%t53w)R{DhSVzqzObMYZ0aQFN2%kyV19VAkG0{Rsj=}pHh$O~+;tN3`_rsd?}};`VE4YiKjZIl zi=}l3(Tmp|*q^Y@Bj{paD09W56G_HQXFd=bN;!&r&wM>w80{Iim3dn+m5&Vbm?zwr zM9+I2W^NWWin1;Gg}L+(>N{mme`OwitE2US*K2(6J3jawAN-CFe#ZyDp+vQPqOR--#auo2=z-q%CS`1f0Q}77eXsbP7gwTF}`mo-3trHeSIHWOs1%n zW0|wR7*C0E&SslMNvF_~&Wm~cuSQ|iF5dzkf4gf61)ST>{9UpsG`#gbwt3Szl)j0( zgL(d$DfCC{ZETY(br{V|^%Ha4i<7CqE06igkVzC3|7W((U2P!}gep$=> zb!!-oqzMbTDft zXYJ&yov?PZF2cHup9DY6+6ikn`jDd!K_8<7IXVz@Fl#5Q-DpD4#O$MR_EBIT&(E74 zguZ9km{98XejM-b@mdoo+#kXG*O z%r@pP>BH#Nj@``f(oUi4FZVNly)l_8-1L|yg-@bw&k(CMeG%`c(CnI9m_IZLqvkJn zF!x$Bh2|Vt3=M;ZwG6ZDfz7pqYmILN-^@JZ%tM&Rtc9=^<3Bn6ljA=*{*&WBIsOy; zH(C+2GTIWfHTzE3ccU{oIump@u|!TR2`83>6H6jM#gd61a^i;&KPG0#i5Y>IF>ykO z6B9oI@nd3!oR}deW`q+n0x@IaQy@NnYdSs%J=5OpCeYLV5zKYNCR6qUbD3-RnL@t| zI>6lb;W%1;bb1hKgtzK%%1dwd|3lSR$5(MZZ{zNi0>zy|p;$l?X#pBzX>lv?nZ8V&i#uzr3o(e<8znSNZwcoJH_$P;_W}+7_ zRb0%TuVelW{I+m|qPgmziwSu4{aVJ8l@|-8ZepA~B>^v7pRZ^yyne9pa5D8>GGsKh ztLxcd)`^4L_Y*K-_FBfRT6oc~!6wF==Op0qa`P4Kg(hy!#sziXb4-ERIi zmV}S9#GC&uUrxQFHm>#Juzyq8w~eB`SgXMbK0a%y*B9ehF^(1EP>igP*7`{63kM_) z!Wk{jXmLj3EIA_OD7ho$E?S|b6y@Q%yA$Uunx%+VYjQe5J`(L28+zx$653<~vE2#q76vr1_~?iuSy{D<)v~(#sU> zg@euKb-P>N^6>`0CE$ZTTN%H-8IPymuV-B0MFLK`wUO7Eu{;5nf3V&4bESAQ%iEx6 z|C{eb0{XRD$9QjTFFwAwiE+pA33#o?V)kd1^u@CYx?AHRTcm6=}5USSdA z_!VBp`C!5ii)+Vg%iz>DE`e_&iM$%}{P{>V6Si5CZbvs}?!bFdRm*s@t!8{iC4AdRZU)%UeMGF z;#*C=m44CGFVZ8LdPI6kQ%_01XzCZ~3*FrGh4hQ2evv-X)JM{rntJoflZ}e@!V{M! z;Lo`>D4MJGe3pQDuCL<$+M3|Sp3#fB2j>|6vpTL*v=?q!%Zn?AE>bjC4Ku!NJ#3Al zx$6CX=5znXDn)zY@65TwjxAI)SN$#3iy=2xE1Ihg9O=c&BUUMztG1rz#YP`4SF{(7 zqg;xuVh^{RWxh*%KVQ*Yb&*+f+22cv4;(W3_?K8ly$l`x4bDuEsp+%a`RTZb1of%;{f&GxDtmW+R-V55VOdr7 zpBRpLI_7y`j(t&#i)TyoaiITU_Hpo796S~WkHx`baqw6iJQfF!#ld57@K_u?#No!{ zv4&47mbv@25)6cEJ)ya9Dz@I6&xe8V+$O98#;%>_!$A1#V4C%KmrVL!t zd>9CSG+-S4X6VVV=4;h=-(<#PzRar%Oo*r7+u?(j(^QM)?i@2L`wX?OFVA-2*I{3( zrtt|JGq-%Q8j;bRnJ&CNS?R6rJhV%RsVcshJM-$A7OvKqnUvuVeOI?qz0Geygm3rm zs$RLj;lsSvsZe39}M9guX8+|kM% zt=y4vm%Nbj5}rsrC3mFUMIW^ELDENbKuZU-bU;f7BpsxV+Nz_bI{JMR&vP7Ac$%7c zDw^wC`r|KEj@)jo>u#B@{#V?cu^!x>s6rO=Yz68jN2%@e6ZqVan@Q@}5qAb!<>VCg zps_nYT^Th_jWfR!(q47d=`eNI{mt3)WKm~zbEg}V?@mhq+AsNzZPjP=Lm zL2ANXcP6{4p;D*r&>S;|=WLgns=+pQ#=5db2^D2(N_)wgY28$ynUfMey`_)xn&0^e zkGk@?8q~n`OznB&RE7we9VbKKuG3WDca+Oem|1+38f`v@==j=zWHs3AF$hQdO;y{? z`h;uE?Wr=BaPigLZPmfK?u<3=bTgHd!Nm!EK{YYC&|Wg&@9yfN`7M;Ny3kjZG{1im z{_BIzD)ob@JXh_yXtEDGgymeMbA=lcH(3X*b&%GPT##}R{%G+>i$7ZY(c+I5eEt0lUcci+D&S>e3q_cPlEiY-yOWN|1CNGJ9%;(a7{z3AOcm^%cX!4Bs1j#4j zA5H!d&!FWQv^=9N&uH?D_*0WV%RPza*;B`2U#i!|CNn<%!*rEc*`2ZGnwzNRUYWwj z^{X0c_mA=Jyy;bny0g-JM=|@#-+xU~ZO*!L(!h;V)PcP2OzOmdFxA5Nfno~3?yk;F zc4w@a0)o`qYwqlI$;m)f+01vy+w*D z;Nmh-pR3lbr}7MI+JZ@{wZH4beV4|mYsR;)!sQc#l?s)Cu%(q8gr(UIyztn1ssZ{k!f^Zy2Pe8H{Z zz8J@fajY1JVq|@^)<;@jI3RHl&S-H)i!%~u$q^|>$sH+o(F!fC(9+8M&)w%fZIQGU z%{6H*HPxB^ucq3nsivAr9W~Wa>Z_@~Qd4c!R8vjGSK9KGwtS^6Uup7H`sPHQtHM{2 zDsL-y9@?PrI2FGkfoC)m(vsBV4LsNL{JJMnO}%V>cccH^T`)!6%I(f^hSUgCe#UQf zeB++(YO<+2{Z8^v?anI3%mfM7i*BjTo6lC-OFmfCRkbj43c|IP^j6aXTs-+eM>V^n z>(xGAj8)mYPUZROlG2mZhdW$6dS{H9P*rBEQ^%{$CEdB|51$QI->!E(dAM1uT3W)L ztFA9FLCvh=&Q)LZ9iV0#Z_~cA{};W~Tf>L&`7K@5q{dTuewyX}B$d3(#Vh8-ss)AJ z8Efx>6I8o1i9A<5RxU!dnBjVOg4GKlRC>DLhxz>*H0~VE*4c81`MVT48dbb4#0CJ~p#y+HZba zbh0{Q{-1&Nl1nC!R9Eu3v(%9rhNydHMn=EM2aE_^N#wa|>jLA|>-z3ob-{}M>XbQ` z_L3#`4^nTRPUX33mL(Ha>sszy^&AdRiRODU?Irtf8LVoV|8tWiU!SJlCtnSu6_ zSBo|=zk@UO5VmKa|4zF^zenl!AtAWn#6OHPk8bIU;hCw#c&r!?#e5r7ht~HLs9)5F zHDUX@QP*-ahbyC-W51jqGA?qk73$RTj7vs`V*5`%W<0T8IIgNvi*dK_!ZG(h=3WQG zEo;AE^NgJaj29gb!i-s6{NWLWjnmzj+*xX1??UxCrlWbbv7N7Q@K_u?76*^T!DDgo zSR6bS2amOl?6T^J*Nb#$nB+&P?OI3og*mPk0bH;kO=}c70wZ;bGXcOj*W1%?-h~m8)}1NNhOPZb#3iPK8I4!?DBL8hpIk+Hmy03yh<(x5872 z9*&7<-4Z(;QH+1D+Xg>uq&Q|&hG0B?(Ze{;Kh3dKn+A+CcM8JzU)^&9;sf#JXv)_- zL-<`I+;*C3mkJv$hnnYy@|tRXreMt7l@+QAi1NJJ6gFT4T(?=zx|ENIFRFNV$t9NSa6; zwN*z=bv#@6W1xL#ml~#yv&wRPtM3ZIqbDjcE*}|&nUgz?zKDn!G|Y`*D2ZHDUNBgNKh#IrbU;k=^xAwUe!}m)<7(&6}`F6A;59@h%Pg$1hf@hua>an_9* zjQ6hz$Mtm-<7EYc@!eJ8pA0Qaw8F=K5r<^BnWF_B`HZ+F!=e#Ecx4oMH3&*NZLs^~ zK*rUs1f%(r&3N)ptuZ>WHfgAuM2GvZLs-s5I#;+Mag%k>S_f$z$ptAF;g1%7wD_aN zA1(f9@kin>S|MpA+9GKybw{eZ=!}-mNIHv`(DIVDyreBJY4Vcz2QB{~`A0m1mS;41 zMtp+g6Y-BG|A=SM@{D;N_J5wymS;41M*OMCpZnI71^NyXaM1Mcqe_ggj1R*l%RgcK z&4O@z7TJJt)`5-8tp8)6z3rMh;dnB>I^)`j;W(#rO~&sG|J2+b#yz)vhOHtME12k9d+dmwWuGM27*4`F|e@>^Kii2{q+hF>FK*kGq1!G_>U_5F@ zYb?6GHqc!4+tJ}z_#^Up4k%PB7)R};zojK%)!-I*@>zZA9rf&JD2`ZNhkcu+O*jsW z_UGdjyrI4r$BJ>R7>8nHeYDm`T3*Fz>!L8s@Ktr7z3q;qaLh2hKG0nCb+#~kHmD{a&$uoe&lm78-nH^G zY&$_Q9>2K_zAOT~&KYct2iAKScX3+aSNjyu{x`9S>7&bmjK3WhjB|Pe<0f@mj2GFGxspx69(30e8qhBHQZ89xU; z^%yrf7lw~&`2)>W&#e!|zyGSk9$wlc92;+OkJs)MichO3pgqFa(!scJ2Yp{E3BN?O z!b7k5dmU{5JQxf04&<1xGKFC5u3Drm-1ssa`>n6W@sme{<9w3~ox9WI68Cp)j%hpG zTQlAjLMTqE#r+Gra)jd0@IdaP4uwK|F%HGZairrCj}$N0MY^tB3+YUufzJ=@;`>xYoWt($q)No0@tv#(a*`UU-N3{B0YnfcC;i*S5hY-v)4h z1z-rC?&!xo*l|V}{_lDq&|bJ}R4_)Iss}Vzee8tcf|`LqbJgK>LvY^g0HD3_MkfTr z3)BOetG0R(hV|YA0L@iL_6xxZ0|J2d!lkZ+V7b@zf%d|wM?!I6(*X8x!kZBM`e|*T zz3_yg;dpU$ec}U03x(m_Y4xd>VO{qBFcOv+q!>9D>0DVKt@V-C7Y;}qgc}k!;f%yt zazV;Pazx5ea@Ul*=%X!tH0dK6YSK`&)ugRxu1WKMC)5Yp3%4y0hL`6C(%(!da3I)+ zk+8%d#aPd4^6hQu*}uwqCNT86S{qG|>os{RLa%M^`?)53S{W|BZN|Ie1~7BS-6$s#^@IIK3E04a*NDmULnKctIw}l;A!a z>e%K7J`VJZVjl;O#ld57@K_u?76*^T!DDgoSR6bS2amuu5E29|po(f9lTflsR3y5;%Xb4)}TPVm=In9|Q#D0L@+&507*4x$5NhGQJqcigBzMhhijmv~ou)ceHXxD|fVVN6KCDLdr{cBJq^mk#ZM( z(9#DuRrvm7ORjI=r7BROV+i9hBdS8P z@*NmYu36PQOQi?WUNX;yig3m}i<{1E*RCpL_}zVGujhIdcnq#jvQ4T4*Os}@HJ#F_ z6jUok&neB}aT3ZvCG)&T!snZpfVS)1XAx)ou`F~k^`$lYm;MOO{_Ns26N|#EGH(2a z$AzItZhqFHXXO68kZzvGNP9`Irz|X}?c$)>tCw^4@QMB&M~qoEN$F@aq((ZVN@}GrlP0*$->a@KseG~a?XUR@Nud3 zjLU^pg%bDN=lZ_BPz9E(cAufTOO*m|y8GPVt%+r!w(&Ndnf4?DKXFhc$a}3f&sEozFAJp_xp;hBImpzq4K9Kc!_!#zS*Bxi zl!LR^__F|hI`I*_en!u)-m5M(t_VX4c4gnH?<&LkLHulXRsC!QUyNhLI97~9F|s~d z>m#i%9FRB&XS6t@#TkjSRbr|wszsUYQ)c# z;q9)jj4!vU44!|wG0wfZ5=1p{p94JaS$VkoU03#GQuoT{`))VJ(K{=_$W88ZfLrw} z54XqkM%q`#6e|bGk6e7|-!d>avJ1~u51*+F1t)i9d|{Be*0yepryi~ZcdGW}xvJj> z72)p&UD?B*POS`o%yo~~T2lcoCc4i@?fkSXw4Lhuxn-u((0?F*_k+Fl%E5sr?sI^% zy(8+RscA*yK=@M~r64Kw@4N9K3;vfp=QJksQ{xN8@VDRZSVoVY~K(|)Jcw66$V zGjRXH_nr#y^Gz3T&R^aa<4}woM>;O?Nbz!A^S-PqzH1>}OE@5Lkn18{SMoy2OZX%4 zm%Nbjl6;Z!6|K$c-~e-OA@kk@+DqPjQwf?bb)N&g zGqOC)tKN&}s#kJVfX%OZxc93zs0by@vvBD*lY7-GK%s$Mc&>Wnd}Y`(g`WWqt$wHo zYrgA2y$ow+{D+aS#304Uxk%^A`ndl8)<;@jI3RHlZb;mOGZJUX1t}NF5h+K>T~qF& zkGAyDq>pH*Nkh?AleVI{Ce53q^x(Pbf$u9qUGofN+Dq0+E9b*VSYnW3>^-Ak5AEHo z_mhJ4&Qq}7h3bo;_lNpo=$)s&75 z%99#%{LBSed~;HsnM#buit$j)>#n^i-V+n#bp&g|_I2}>2sDfFFp9gIks;s<60-~JCHGsajEJTo%vH^8IS(!kW+Ex1jgah(0P(G zlJSuo%bdDf2D!(Rzw&Y5e1(I@;^473cq|Sci-X7F;ITM(EDj!vgU90F2{#W~iu z;n=->fc7k-?mlyROdrGeO}mZG;#(0wd*OBWpExfD4r4xJ8$Wdx-W>DR;>iDPPe6Ne9Utt=!Sd9VvIo z3n?$*iNsTKN6KCFK}#PbeMASebU;f7v~)nyLF%ZjI%=w8neron_MR!no;bUE4CMNj z4u9t4yD*ILnvzeQ55|vTJo(5Yr_0G`puKQ#v764sK2dz`?&*)6Y`MlT?mF$E6Mu3d z$A{JY+o>E8$H)C&pK{K0i{s-e>a3F^z{QPDA9HjyH)hb0^UgBUo5UyZtD{cW&{)Q0 z#vOEKK9A;eXB^$@e7tNt<7wZgIZ2J;+*#_YbIz`7v5fOwx#%ny=pLW`C!Wc0s`mwF zr|~M`e&3&V;tRQWTirjLUV~%#c+U?HIc;l`KZ77)=6UCrL*&mOxDs*6S<=frzOC9> zC;zK)q@gmaQoxgg~t{L$i%7Jsz(qs1RB{z&{qDY?+;@HoaVcb;;F*K%=_x#yiv-^B9q2OW<( z^P9Q&03384G$#M#@O*avij)7@MD~2!N4K1&&CFib%vFQ;oO3eXi)DO$?L}wDVE1^A z&VM;~#*YWu3%|T@*SUw(cjjK~?teS)1F4VV;JDv;r^Q+7qc}+a=#ukqKlgaWqklQO z%a7-oRKYg)oN5KQAEEjB3(l>I^!KnNyn6bFqnpN1@2KKAZaA|Zjc4Cxg1gT5sqXPx z`LFw894p4LVjPN*_0d`%X?@{<#6dWt#ThNmNSq}{q#Px8q})X-bI;;`TA`&Cl2)QE zlD49`Ce5X$+N!CxYO1NGQb$d7l=^C_uhdjqHPuv8@s+lGr7d4+%U7Cw)iz@c&sD3h zyWs@ip2&W?n(c4r>GUX|y=|Y!$4NLy&o>b}!-3xD^6gD)RDmrO3y3-e4a4}!;Y z%)%n~oL9ACs87|0^=~*Yw{ZW$wuhITPYSyDu8VYCxfas3gaZ-> zxh~RmB`>7BBp0MyBuAtiB`>7BL@TtkLQ5+otweLQG)GHwB+aFENVSuiBGpuCjZ|x? zDOxo}s;PJb$s6J&w7i6tmyo<9-qYkg@v64Gs>!R;3z~XCe5=W~(l46&MS4V2k4R5x z>M7|LP5mN0qNzuucQo~m^oyo`k>1qQo2lk=oc6*^tDkj}>c#O~H8JA6GbkjM`|FUt z;$Y!u?#KA8x13|IVtKAwtnEeT^~Q-jS8Wq%a$FqCbJeviFFOa!xinX8g;$)>MJDoG z^~M*sol;4$JXfv%+hwO>?O2|x-l=-k`Kfsf&sD=R+;A$CbUi$9>{TbA(|De%4#{!P zse6k*v*5+u8&1Rv?q#UB|38d`B?c)*&P6&`)<6jkZw*q>?I8$%J@4xO3xco2XdqMA~jB}ohfE5ojAjNcE z6$zgHxfx&lHUgsi7GPZa+Ca#bw-Dp>EIlD|6Th!n_xvjimalVTiscUi;Xv=i@p152 z96S~WkHx`baqw6iJQfF!#ld57@K_u?#Np}Fb0)7;{Pg}H9|poLauI*?-qqwzJ`9Aj z-+Dqi;FI_W9|ppCBeU^bHN%ETxY>_$#4A?@`Y;gw_2=^reb4DqV=%nQS_lbeE!YWa z?fb`}z2uvX5fIq!KJkIq)kZ+V?rV%I_8$u0m3zrCi@hTuxmYIR2JwGH!rJfN@$sNm zkx(K_KBRSSY#j!Fy`=YIr^54cL*e%cc^I$$egu@<%kPDUCe0!sbWVPb?{j@HwEkZK z#$SvW2p7#eCh6R^Te?Ho0IFRoO!%}PI483+&fY5$^6sX(r>g8NB4Ep`T#UzjJQ5Z! zyzDW6s4oEsk?r7zXR_;i-OI}EM2~Q-Rk~>oFq7Pd7 zAn7AIprr$n4w5@k?xG2jCQ?Uj)lpL&d)9sG(BAF!uMseF`gN{#ktIW+L*)mI|L!va zj{NeP@ptz|LZ^`INPEfd36bD8`z4=yV9rQLEAXCi`sa}_>`GSl$-BLgkXkVx()w$s z41+8C^YHQJpN)VnwemAAo;C#L+{?`|N6JJ%i4FM~f3$8e)Ll@3@tZmWAu_fg$Jb5k z3plz~C|=JcE{J(DID7Jfq1o;!jQf z?6dQ_L*KFYZXOELx;bji9 zKRGmHw+djw?oA`{P~hMtLpjI+t-IiS+8 z2q@eyzxmr(5}dX}VA=ER)H|v|$4D46CNulCvq@t9(&Q_@ud?%8b!=25oP3v+{nl((Bs949(xH9g zg{325gEu?P_001t4F93;`S`frk+8s%4=JX2Z^I{d9>!NPN5F4q^6)yt>yCgc4e~So z{D&dXYeXKNpEg}K0+xs5W}JU%1XORBmvP4(!=Y)lZ0yhX>5*_Ce`cPacDx)3+v{av zT-|tJ@{FvE(~d+!%F3Ml9N^7sMnY1KEbPhKCT2+Atc?FX774k-bMY*7Y4}K}kd< zcU%Pc4b8)N)XEXi;@3<(KfQfE68!IHW?c1pBm*+;BHy!C70lg#m`yND1i-3?Vx%ha`LL*_&?!4^t;f068#>9-I zEgat+3CH0DeP4ni-ABT1lM7+W<>ZD;95d%!BhkT}S7k*+IwA>}2xAmt)CBIPJ~A>}1n zp`{gCS|MpAnxmyTTACwiF116dozxVmrc!I>EHy=|rbsmvZyjH&fxPcD8Aa3$k`*|T!GbJgu5 z;qy1yd9JG4M?$H=IoZz>4~~SKIup-TTbtflI3zpqfrOYysFskOdKo&6{SPByi9w2y zbCJ%K_0d`%X?@{$z4%q<8EZ&A5CWonEP|mvO(uY3ZY%Pi1^FrAzw%qLLZ6 z+L9~1bk%8$$0cm@|E-XFeCCYefi0I$;p4mKjt}hnmpgCW^L|s{)u1Ro{I zL*@qVIWg6oyBA)q?w-E5JL#4R^~%Sk|NNXeK#%XfO<(Sq|Ft(UGcq+#PdiLHr^1P! zUZj=SnZ(D(wyTsr=quu|7gly#8c?!q3ddx~c_tt>1J%gHC)W>nP;wf_9R2wp|7Sar z8E1a*HX!RAcbzSfWdi$u=yKQ-8Xs6XJ<&b4M)SZ$x!iTIdxf-5OEFf}hdl9bU)RMo zJDjS&^Ce$b4SF3EATf>=<5)2c#YpZ*xl6uC`HBumI!Nwl<&IYFNV!X1NO=iQB%YEx zQtqM;TKXXABRZg^1CkDsJDxDPizY~#NFB9RM@@D7;qFwRz3S55UDNwiPvH9QI{9__ z!aw0T)=##ZZgbD=#ifB3FR^rYGw;dtGk)jPloxAnx}W(PWc)h-7BXbENo2oNxK-fbSl=@j3dG4lMftc{K=5G|eBdu$GIx{et`p-z5$~ zF!@xM0OwpXX{ch_JV_Jm5SDY1&J}J*++-cJ)YO`TzaW5QW(Fhv_4?I@dL&GRXtxo!zIa# zD;LNdnEj9&zxSsKfu-w^$8vbWHx}Fe;U2eN{QgQ#%ba5x&r;{dR}END-Nj31eCvPo zuM|Gs@7Sn-wpmknZWX@jYTDDyu0QYp{Z(3_{M1u%5Z3&ofQ>a>+`t*>zxx`k9|w1^ ze}MOPGS8$21>8?-Se`jRmHemuCtv2zMA$U_QNW3O{I^$iKJZc6+3MW;szTt2v?Zo5 zXpek--kt3d<5)3{72{BhtdG|ENb3s+Bo4wEEzW3hM&c|vBIPK#Bjqkyp`{gCS|MpA z+9GKynrqTrYN|W^Urn`DQ%yCMI%=w;)K^n|rKZ}dsivBWue9YWZTU)DzS86?^MW9r ztDgI;URvgzDeSijdRkh~tBE|L8U1DB^b7x{&|J?`Y`K40#I+gCJ(-_~MUNE5kJ$Ich#X1K(dXda)et7s+!17Gfc$Qi$wN60Zk6paL2lMklDqj5^D$i`YxI0r)gi^NE_HX zh4I0*z4>!yHds;|E_xR#5zisbab{fx2cbB;0 zzj76QzL$g_)!cvzmFaW8B&5gh@K>hqXuo_qR}uf4i;_uOXw^D%`jP4M{h=fje%~s+ zhRKESta^LXIvEWqra`v9)B2mw9oh>Q|Fc|L5z}AvJ5ty8G28!gdl@cne^*~(9Ey?S zNXI1}DPFFNbX~a?(zS#G5(l|1(sd;-q`V{-q+BFNq#PwLq`X8cw6sD?DYpE$(H8sy5sU0BRK=Ouo2`w+7k7()<=^ahIBmJVOU!*rR^=4`FIZk`w z!~41fbSgBB=c?Tr6b`s*>Q0{{8y>#imgS(^k7<{@Y2TT>2EP-h{aW*ShZLTx-udC1 zwA1GMC*7|)s?Ngtx6HY;7k<#_)wXE!eTn|Zc;>6sY0;)%=zdkdmLK@NFyAHUe$~ZY z)b{@7Z#&(u8Zx(dT9r>-4~Lx`uzmCEWS*-w-+42w)?4m3@v(tsLMl7zs-ZQjEQywfDc)J8R(D?*Rd($93|H zD1b?|(+KZ~i~;{b73jUp`eB$C^6VVM_=`tVVSC_0#x*M^!|p*(7`JY3G=5Q(enZnU zP9(zHm`@m+_hiCx)s*p&3KQX*4(%CF&ou&s1HBW+$H8N9@K_u?76*^T!DDgoSR6bS z2amU@jdnz6X`40nOi9w3l^qzBs1}4Xn1$t5LxOnMQ z9|pp`y8mk4z3yF7t7VEW9w~n2iok{*FUNKpdVfYvCIQ~$v6c}CMImhp9V(N9UAje03n*r@HPVHeSuq5Ae!m3Ks6nH!84&z7Wc-vC{GH#XczZl1gajY1JVkCE@ z+$CS6d_@QIPM#^g+|kM%t=y4vm%Nbj5}rsrC3mFUMIW^ELDENbKuZTC9VB<8+(i>4 zO{9+6s-vbldiD>bcaFo*n^U1+*ZlOJanHb^36Qirh;f%?Qy}-|B*smOCc)i?zo*k) z@^G&dD7JqxpZj#1(Z9#nj64011Z%VI<@kMdQ($R>96WFB6l?0+BLn-Vb!LIzrEmdrw69M{Vxh}JWNi4kVnNC`^`#(rTfcs{M1TQ;rxtG8NUoofGuxcr_=qa zS*oVMS1}J6H|voC?_Okd==i0($xwd99`?`c+9?pM`WbG?5Px7Q{P6Oy$z>>#l~MUEdn}WF55D zL0U(0LCQt=qs1RB{%G+>i$7ZYk@$;NNLq=uNZLx>k?Jlwqop&F&f+DsyreBJY0FER zyd?fX%Rfl|5znCI8BLxMpCI`}{G-V~;u*9&gO+EsvF*mjq{H}z^_IM+??@%aj)Lycw$D=Q*kisNizKL@2Yfq_R%Ke>F4dA5(lVkzP~r=QNaBD zED0|#3Hq-%LA|5C8Ib}LZfs=V9@(1=KMp;^$H$FL@x?e+jAO+(6eH`SwLa4N!oln- z&3(2mXS6t@#TkjSL78vyb+cNP*^GJ!ZV5V+ve$i>Zi95;QOy0$~Qk4|gTl;D{J^N^w(Q{9!pV*T%t|r3`|DB9KH@_3NDF1gl{V(qI zNb~pYw|^KX2B*M^Yi}8UQ_}QEjcrv`LZhk*C{?9rw5r&odiE*IGWp$r59Mj^vWXQSuIQ6MoWInIg zHoL^VGjXEfQ|K<^!9!DgF%HGZairrCj}$N0MY^tB3+Yk7()<=_yS;CHnO@ zo%WI^I+*VyU++$*XCE#8#QX-6dOMx=k{8V1)sLE9OQ*f$d~@!^7)+ zX)pQ7s1(@O{z^LSCI2=WHvRoXI_)K|nRAakzr-HyZM^h#+M0BF_R$CPP2W{GN_=2= z-xLVDdz5+^zB9TBM#2(<6eH&%oh$33wLa4N!U2hca6{rIoRK(7F6P}+|K*63qvWnB zchN^%`e@QeG}NS_XsbzE(Oi?}hr^Gi(_Zqf;XJ3|1Nxh3oYe@1CPJALhsD(Av+jK^&LN$qd#&Rb8G*sVS| z?#@Y%R{C89pP_pg&78OQHI;ok-TPTm``>+_W)~dJIQYY-D(O)V#-l%fu5y%W%UHdC z?&CmnVIK#N#ld57@K_u?76*^T!DDgoSR6bS2amZ@ z;@x4-d>9B1xiOLWyyKng3RaKzc zb#=a@d%tSc`BzlWKlxg!QNf$O7{`intQd!4BzL6TC10d`MF%7uBzLrOM=N)v+$Arh zyo4tbPstrAchLteeUS7K9njJNNe9UtDR#2Qt>Ld~rMb74_QElLo>jUT-?Ibd%kNjOg57&dPmMUJuJe7J zIXpL?{i(8l=-z+#DDJlUVzYbC>74;L)$>8_J*Ru0+*M^qx$7)TzOL2}8^?UMSH7>Z z<#X?WJ)8JYbv6G7Py2H+`r+?nPb=f+_mCI{Arvzv_j6 ztLo%D>X#tEc{kOCa;%}+a^epkb_mP4NaqSSByO?}TI(RKBe@{uBK*|7oE}48A)gH5?Wr;mY1~UB~4xu|Dfd`B>#wK(DIBX&xlWu zd?NnQ|)!{ucjMK;es+xZt z$+$_LCu*7bOrgE-j>@}LxwbKkPj}g`=6~+qf7)Q>LG{JI6ZrUp#kbWTecYIiKV4Vt z+m7SozcstBPCOpXc;Lc^s^Sj!e$@^;FR3LX-TSrohMiGQ%f#^fG_21J)%LZEzrJ%- zEom3c$31?x)N2*TbJa_4j;V>p=j6jpoBvdqxi{lrca|F}sHl6tDkff4=`qyraS(g) zrb@0B$1|zmddJkQE!^X<>EJarHaqsUK;j^r(c+92XC%&&BT|l%J5uhV61-{ycWS$`~5QbJgB0&Z%DAV)^)l{RdUGrxO@={OPv(s*4*x z`_Ofz7rOUZU!HYS?F}8zYqltSPo-sz;rZ$C#Wz&m8!o<3>zcY&FPe`BjJl;}ndc0U z&o3sQQOlad@mzI&hvTY~1%%Y|z z)&EQk;V#cls~Y3n`&GMra7FFe5yLZ9TzgH;%;Dnk^KYot_2YP!`qBPl>bvePZj|Sw zs%+MwJ@T<#r&YBYaXeT3dfR#RcL&$Q9b-?ZH96hmYcE|;Q7dA2X8QW!HTC27{QU>^ z&ih-v|DC`4LD=|fYC%)?UcVzZuPDFQu{<*^5pq<8n)`yu|F=)?Rm$W-_=BL6>P8*b zA9l_;re-(dK2_eA=hS}l*+;)4wcL3{RlDfo4w*0cVjL?5tr(;jxh~Rm7BBwwU_MJu$lLQ5+otweLQG)GHwB+aFENVSuiBGpuCjZ|x? zDOxo}s;PJb$s6J&w7i6tmyo<9-qYkg@v0`TivKnFUwo@A-)i!$^oyo`ksi_1Bhpiv zdP@4m^zv^=9Vz(L7geZ$5vAcZ}h=>c-R8)p&EyGWBfO zlS}H+2=|`x-pkIY(N|)4uA1bzrj{5F^K*c|{Zkz=&sw3q@U)@EGv-{{3t#=`k}75T zj`qUaUY=6lOmgp6EqwQ~!UOL8s?R1}QqksF1hf|phx2Bx?|S&l8kf{1bN?*ug)gr^ zrjE4bzadbq;5p?ne>Z3^92E2)M#2(<6eH&%oh$33wLa4N!U2hca6{rIoRK(7E=ajZ zjz~F5?)tIGUG&kGKAQ9q4K-;f+G^5PG}okg7Lyn4g~yaUrvlBry0jPmXzW!VM#2(< z6l3pa?ftLy&Kk&D@}M$3u4i592017G%6R(8flxckUdG=S7z2k#?PT0JH5$fOOlMqV z#AGO%em+_$)L`~=2d4v&Q@ zD|RaSetyk-w@Ti!o30CgULFT2uSow?Xg@v*W<1@&F}cRaLa$@={`XXv^!H>aH46E7 zh0K$nNQ)mC-~7=F>sO?5O!l!}m|tZXYXn=3W?-dp6?+ zM-t#|ky#u+BS!*w5~nbBN>7HXF&h{cx}E@=ORXTR=9+bSZ(qu|@+Pk@ z#<5}?E5@N1$sH+o$rmYK(E&*Z$sMiS(aIeucgYJWFX4&AQ*uYjUGzaqA0&N52efoR zO9!-cK+-|#sI59`s^h~ib}E{y&hbV=z|p;2-|P3Hpz-+KjE8g>4?_-V#<$Yq;F|#( z740SG>_~tWdw1};N7u)~AwOiiD_{~-UcZ^++XW}U?c)pi_@Aj>h;6x)kEa?9^Y5C^ z7zTP_!RqB4^LnKh=A?YjIHSi4<>r6Oc;l`F*xP(2$2Ytk54n$d8UOrn5>z{}Ows&w z|2i+!Ik=MX*WY;Iz-?y*$MZ?lnl*>?9y(s|(XZx9t z_v#yK-W`jK10Q|?`x~!d9J$mBt0RA8+-9-CRpv2X{F%wcZ#Ls&#}Z)E(BS_f$z$ptAF;g1%7 zwD_aNA1(f9@kin>TH$9#E72B7Td6xz-9=}#bVkxyyo8pQwB;pjc}bI(#6M{H2gyI; z8MHj3$ur^;B%g?XH2Ft7gO+E|@{G1TqscSkPfh-uvTv`V?*Pqmje_HYcDp!gJOpjj zj7OY|gO3W$WE^@W9ukM{RP-JDmieCk=jt7dS00Ro&x#`B(d{Qe(Dw`7mH#PY%z&pL=1`kj?D*Yh4py>HKAi=BFFid*Qop zS27NtYW1O;nHR5yJTq7BmveHpq`2Y^KN=b%DRei&o8|& zd+8F!BaEJ(cigUMu6m|GJRF@xKF zEgTsS)$6b4<6jp3FUGNA94p457+D{!^^w*W4oDn?Gg_R{;*7*uazx5ea!1Ntv_eZO zw6sFfO0-4NRy5b7xzto!HPu#4HPuw=sHu)pU%k@QS8A%Qnrf=4_)1&8(#`(QSK9KG zCSNUiyn)_3@2PBh@VkV~?6*Z76QJ{g9g60vU!RGEdpR~Lnya=kpLdV4BOl-2dlC$f zUC21`doN__yqs~KHD0Kje<`oC(&$zralY%}zFw&C*)m1*(~}##a3g3XU$U1vVOg0`$++}eEZmuS0;ahkdA^H}b_?Te#S);~q4kR9svF)XK(_Ngv4>kH#6y9d>-cz`3SJn|Z-t_{ zYNI7yI8%KQ`&qB>LbfOL9iSxaG2i_LZd=7M=~KOs_C*?L3;owkhAHiT=9oI!W1)h{ zh2ndeTzVGW&N0I)#zVuX4b-Pfo9{@))~@B=ITqxF?pIbZzMA0m#W)lr$B~XpJW{+| z7wNikEu?D+2P6)1U8L(uUPyTfek7()<=_yS;CHvgGQM(>#S8YSKS(JyzRe1(Oz=t1M}U$yOurN z)O-*5Ajft^d&$}#$HR2Ljl>6z>`#Dcxi?ZT!}-JiVI(XuNHKCQ(z&ueTI(aNFC36K z2sb2d!Wl~%&XS9{&)VzD5h+K>T~qF&kGAyDq>pH*Nkh?AleVI{Ce2HHvQg1qa^SBC z5LA2>{mq1+S?2GFi;=LzAjMeE1TV&KtKlf znZw&dtHH-zJbe6Oh(9FvX~1|=riPF^my4s{H-jlB{rR}JO(-;aS(9<{>ToEUwKC(m z31RTfieikvKG+&g9m&IZ)1~JBpPs_OV{!0U96S~WkHx`baqw6iJQfF!#ld57@DPXG zbCuzfipPU$`7jW^eYOlAzwFB$ zW3FXv4AW1zG50IBfJ2?!<4w;rg?~PC-+fv5Rv1+JvOb@CH%k~K59Rmw!RhItP~r=E z-)<_jYab4S%hcxUK1vLS%`r6@zg`;-_sdu3m{T#~FkyE^#=3kM++W06L7j1J;M{Pk zd#W1ozfkZl31A$&Ap}nJ;OnY^rNVqMjuqorF%HE@?nt>yzDW6s4oEsk?r7zXR_;i- zOO8l63Qr`Sq63l+q7RZjq61nwprr#^I-sQkk`7WwZPn2{yD|ha_GrL!%)z%CK$$;* z>l;|h501R>Fs?LDL7kBe7KWD-s{IWXWuZ0TSPwJ3tcv} zg6PjFmt^xkq6V-h6YyMBpKlF&M!Uy*-)#g3y14k8-A&<9j6cWMP6&nM9`zW%xNM&1 z=2x3>&ne+B>g$?}FB+cJ%aCt_;C)&sJnIp_c-hSmn3ap(QyB!`1cgE5uO8A+sm?8Y z*dZ+EBAqMT%>R0|_N{}~I!NnCF37pK{L$i%7Jsz(qs1RB{z&{qD%N0>*>(l*M>OEy$+LQ!KDhy`aD0Kbte?o)WMcTf%|5?(zEhgMBfM72{Yj4#mj& zXswU5zHmU|Ae_f4?xGc1TA`&Cl2)QElD49`Ce5X$+N!CxYO1NG zQb$d7l=^C_uhdjqHPuv8@s+lGr7d4+%U7Cw)%Jkmx#~JF{WZ(=~e%c0lo6mGQ-Y+N!PT#D{_=im4@b8EIjOXnLg~kQ>9gCjS#$mAZPHpz^ z`(fd*bwPcepDubA3QunPGe#8(^W*&(Pm2u$^RG|r)opKEL7h1so}a$>pe6Kd=;EkP zK7$cEfsdz;Xaz?H2J-!?o8ANi2D_eImgzG%`UkK-3$$njqt6HMEcK%KPI6(bKjRMl zLSftD`i$ql3571JJUl;r`g;o)+|k89|J@QkKL>n#bd6T#?8D>QdwH{PH3xz`)b zAD@SZkHgw))?PES_UyIhoIP>PVrcxXH}Aqb9lUNa{bgFe#fV$hD_%HxfY#Bxt@SO_ zL?*Qd+LL@hKJ^>uH}w_hE7=gRA@v*RH{Dm@zS6w}?j_x0;2zU`1@0^PDrCM2nXdxA zN;BjcLfnG%%)VZUp8=noA*@OCg&}fw`3CUW>Vx z=4vaOt1aegS_>`KLYlWN=51OpE!Im~BQ4fQT2n37R9Y`B)=OF!E!IU^FD=$fT1PF` zQCgcV*5)JeInKNA0rC0!>1->juKM-u8x*_$qD|{-@Eq$G&+k`g4IVVZe-!JyzOw47 zrw`hoxcIt4b=5KB)+v55ae(ToAD_E^@#F?=s;j;guU)Nksk-W8kFH(p@qYb%)u;Dd zznK4^HvPP6^Ud{&RmU_`SKZ_Eb&Ic0ufGxeAs^kox>Q}Y+g)oG3%uCCo}$OR>lRl$ z+F&ggCoSE<0ZuXjnRIR7+N3{Z`UCot4FMaHZ2{Yo%>kR!y#($h-DBV$)4jL2_vD{e z=ARb+Nj_}h!{pl*zD+)F;q!T(YpAaJ#e(Y=$HZ^T@-F$mmU z*9*7idi-kfwR6qe+GfIe;{GpnYh88K+2YQ9W^aA5{+Z%ICv|O2I`K5|SJTbXI&ia7 z#KStz*qY_-lf*L}F@0;h`^MHX^GwqkbV~iZkLH|us@8S=>fe2|-6@?~gBRuZ3oX!E zV%N#x#jf?a-?tw8CM?jeKF53FQIo@>>#rr5w+^1VHSH<&yXsfZPt!W~2Hs5;XuWam zw5`K7)^oY_&gwI??meb{Z(VSenOk3tt9j?cyS4^yR?Cb(aE{jAZ|U36t$8o#-WnU< z&F(mSYB~z4yHfwl?Uziul#hi?j|su$Jk2{t~T;&+@LcKx@v+ zmTqmiO0EBZPgZPo?eT)zZ|OOAYmS4S6yLV;e61}nc|bgU-vwLo-%75Hvf<%fXB0PD ze+1f_~p++Sajs`;s-m0FwL3Ii0@t^gai9MA^zP)t?;Lp9~Qs( z(yifz8*UfB|LB8Zoz*MxS#6JnzZ?|A+rRx(czaS)JoAL-!e*b>?T_C2O1NYHTh)H; zZEuE+?yu+Dm*YMNcbtE>+PlsAahQB%?UUc$@p*V*v%25O(|s9+-t(wr-kxJ}cxc|* zwh=Q<)tc~FZS#uN^sOaldrmT&UEP&=EWgEh9io55(cdBZT^z?D#IdQ{SLq)<+G0s@ zc}5xj@>zZD_FoJN%U@exyXu~U!o-R5OJ?|*1H&GFokzUdU)#dW)6XT|;wawf7^^7onmD$z4++Amf z``4O7{Mq5-!zW$pd!MP>mEqNX3#fgyi*E|=%-SY?c;p++v-=JZ-#%fwu)|_2i~AhA zKrYjG;)tcyzQ75R1EHi&SE`vA!ZDXHT z>#onEW?!au&!{_NYe{5?l^Z_e?D+E>Rf z(bjz9=XGE6-n?mZlQp|b|C`6|(p+t&dBuyJen4~Fu-fM3H$1qx(pmMrd^Y5_%||BG z_t^V^Lz;aj*Y|$gXGb>AJFWJ~CdVGz?Dbd0CdS8@E+)pum@X#9 z$CxfA#>bd0CdS8@E+)pum@X#9$CxfA#>bd0CdS8@E+)pum@X#9XR*4-;z^OknIen% zWsKvxN8);n<6`1^jN@YBdW_>@;(CnZV&Zy?<6`1^jN@YBdW_>@;(CnZV&Zy?<6`1^ zjN@YBdW_>@;(CnZV&Zy?<6`1^jN@YBdW_>@;(CnZV&Zy?<6`1^jN@YBdW_>@;(CnZ zb$g8KF^-Fg>oJatiR&?ri;3$oj?1^i^%%#+#Pt}*#l-b&e^O@8%`$tQmf176jB#B0 ziR&?ri;3$oj*E%wF^-Fg>oJatiR&?ri;3$oj*E%wF^-Fg>oJatiR&?ri;3$oj*E%w zF^-Fg>oJbk@-eQ*I4&lx$2cw~uE#hoCa%XgE+($WI4&lx$2cw~uE#hoCa%XgE+($W zI4&lx$2cw~uE#hoCa%XgE+($WI4&lx$2cw~uE#h|eX~Vek8xb>#FZGw#l#z8y=7t? z7ZcZG92XPUV;mO~*JB(P6W3!L7ZcZG92XPUV;mO~*JB(P6W3!L7ZcZG92XPUV;mO~ z*JB(P6W3!L=jUEq#Pt}*+hF2)jN@YBdW_=@+KKBij*E%wF^-Fg>oJatiR&?ri;3$o zj*E%wF^-Fg>oJat71uvIQcPTraa>GXk8xZ~T#s>FOk9t1IA9NPo#!QtpLveL_@6xu zOk9s~TufY#dv!5!J;re{aXrRyF>yV{aWQc{#&I!mJ;re{aXrTIS|-Nz7{|rL^%%#+ z#Pt}*#l-a($Hm0;7{|rL^%%$N_88Y=92XPUV;mO~*JB(P6W3!L7ZcZG92XPUV;mO~ z*JB(P6W3!LujON0k8xZ~T#s>FOk9s~TufY#aa>GXk8xZ~TxZXXKZ)z?3t{5A_KT5; z>+IcWC$7ghE+($WI4&lx$2hKQiR&?ri;3$oj*Au7ul`s}T#s>FOk9s~TufY#aa>GX zk8xZ~T#s>FOk9s~TufY#aa>GXk8xZ~T#s>FOk9s~TufY#aa>GXk8xZ~T#s>FOk9s~ zTufY#`*SgIJ;re{aXrRyF>yV{aWQc{#&I!mJ;re{aXrRyF>#&uO#De)=lus(T#xTX zFmauCC$-0SsTjw_#Pt}*#l-a($Hm0;7{|rL^%%#+#Pt}*#l-a($Hm0;7{|rL^%%#+ z#Pt}*#l-a($Hm0;7{|rL^|(J56W3!L7ZcZG9M?S(*JB(P6W3!Lmke<|#&I!mJ;re{ zaXrRyF>yV{aWQc{#&I!mJ;re{aXrRyF>yV{aWQc{#&I!mJ;re{aXrRyF>yV{5ixN+ z#uqVhJ(Fq1IIec$dW_>@;(CnZV&Zy?<6`1^jN@YBdW_>@;(CnZV&Zy?<6`1^jN@YB zdW_>@;(CnZV&Zy?<6`1^jN@YBdW_>@;(CnZV&Zy?<6`1^jN@YBdW_>@;(CnZV&Zy? z<6`1^jN@YBdW_>@;(CnZV&Zy?shSkeP8Xw^(@YWEatb!vv4hOojeOn zTqn;06W7VJz{GXsSt1kH$+OTN_ve8;3rt)m&jJ(I$+N)3b@D7Qah*I1Ok5|=0u$HC zv%ti4@+>fMojeOnTqn;06W7VJz{GX(EHH7MJPS-*C(i;C*U7V}J;rtNEHH7MJPS-* zC(i;C*U7WM#C7s4Fmatc3rt+k_9Vn{U5mf7=P5ZcwX-J3vv4hOojeOnTqn;06W7VJ zz{GX(EHH7MJPS-*C(i;C*U7WM#C7s4Fmatc3rt)m&jJ(I$+N)3b@D8dk8zzm3rt)m z&jJ(I$+N)3b@D7Qah*I1Ok5|=0u$HCv%ti4@+>fMojeOnTqn;06W7VJz{GX(EHH7M zJPS-*C(i;C*R#EME88Eoh%d+xZ?Zjni#!YM#C7s4Fmatc3rt)m&jJ(I$+N)3b@D7Q zah*I1Ok5|=0u$HCv%ti4@+>fMojeOnTqn;06W7VJz{GX(EHH7MJPS-*C(i;C*U7WM z#C7s4Fmatc3rt)m&jJ(I$+N)3b@D7Qah*I1thgTYEHH7MJPS-*C(i;C*U7WM#C4vL zFuu*+iCWn=g@^K4jn53uiyPzQ*W_YhP&o$2S{^dw%|2bJDLj7Y|&xQ}}SR zt;I+6m^tiq+qU8>4(=AtdSN^9@3)^ftUjTZnfAmU;jU4?RQtBgCBovz)cRN3uXh-D z@G5GbdVH@i>x=bz*>TOD;kxcyseO*)&TV#jVKeb-LvC!2pLb*NUJv}Cx#YaN)V#~s z_5=U2mw3-#-`M`v-M7e1|V(z}OJbq>clh?)zEW^moUxZh+GUCO z`(o<(u*+(T7N0*-&xZwrceVyYwSF@5ZY4;tA#EVB7o zWb^hPzUA?+`u=17dsDybyCM1S#`#zMKGpo^5Wnm9@TBvfIt%)*`uW8CjOcfrJN+@7 z9ZkP4NWUZKyUyR{zq9CH^}B=q8^0f^#dm7{Ro{-ueAUc;chf(7A1Cv9bJqC>7d+$M z{rt1$UwiyY-1(x=W-di_V9N7wr3D^Xw6a zh=)DDpI@ ztr2#ZVJ>m^`_~Dra~2aXaL@)}<9IHUFLcgYyN8ee z`l|-MJ!_OqFK-pH*ch_k2^O*#6|xu`hK<^!iERVs+$}7* z+M429N9-T29=)9Slp}_Rehc&xUv>1+VbG~_idP&oD(rpBbK0}*^V?&>(F0BwZ}sG; z@XG#ch}R28hXb!UM!(~_@BN2{eFn{|-+evukNbq|yHO$gCRE5`ei(cFYysPzpLMlx z*4Wv_?K7_*W?Q(M_?P=_8E$XY?L&+0!XBS=ReO(bb`G81n_m1{=e@!*BPYw|84uYj z%y#$(wf%?f9$x>&)8duq-6__->;2x`Pi)P5ViEgQ{*Rm#%sXYOL6p4Xq}qgXTB$aq zoMNiuQ~z-tpZbsM_|$(~$1k%wewo$r%dC!HW_A2BtK*kh9lzxLGS%_Rtd3u1b^J1` zv>1I)0he@yo1^UuJduGOOd4Ssh{^L46 z^&i*qssFf+PyNSreCj{0<5T}}9iRG->-f}vT*s&W<2rts)$z-$j!*r^b$seSuH#ex zaUGxfkL&o{u5FipZbsM_|$(~$EW_|IzIIu*XUK-q27RRdB2SBJYwE2Q>`Bv z*YV4&j!*r^b$seSuH#exaUGxfkL&o{^L46^&i*qssFf+PyNSreCj{0<5T}} z9iRG->-f}vT*s&W<2pX|AJ_4z|G17%{l|5D>OZdIQ~z-tpZbsM_|$(~$EW_|I)0he z@u~l~j!*r^b$seSuH&nQnfcjueEjb^K5M~seCj{0<5T}}9iRG->-f}vT*s&W<2pX| zAJ_4z|G17%{l|5D>OZdIQ~z-tpZbsM_+?hdFS9y+nbq;B|G17%{l|5D>OZdIQ~z-t zpZbsM_|$(~$EW_|IzIIu*YTiA_=$1k%wewo$r%dC!HW_A2BtK*kh9ly-#_+?hdFS9y+ znbq;jtd3u1b^J1`v>1I)0he@yo1^UuJduGOOd4 zSslO3>iA_=$1jQNDVJ3eZ&EH%GO3PVW_A2BtK*kh9ly-#_+?hdFS9y+nbq;jtd3u1 zb^J1`v>1I)0he@yo1^ zUuJduGOOd4Ssh<iA_=$1k%wewo$r%dC!HW_A2BtK*kh z9lzv!R;uHdSslO3>iA_=$1k%wewo$r6{}O-fxUXYUrcc()rJ)FQypJ%J=O7bJ}cGn zbv`TA@!6ldj?ezQpx#65%If&+&t1o7f9^Uy`*YXv*`K?P&;HzXeD>$A-g-?UB_pC?m9mEbJy|NpSzCF{@itZ_UEqSvp;topZ&S(`0USJ$7g@;IzIbz*YVk( zyN=KP+;x2INq861KAdySb=^&IJ=H)J*Hax|aXr=Xbv`TA@pV2c)$w&cE7kFJJ}cGn z*`K?Puk%@{j<54ssgAGnS*eb%^I55muk%@{j<54ssgAGnS*eb%xK6!?d&%nf?9W}t zXMgTGzRqW*I=;?lr8>UOXQev6&S#}MzRqW*I=;?lr8>UOXQev6&S#}MzRqW*I=;?l zr5e5V-l>kP{UJ38Y$mQ}GOpvZKX)Bp=d)5BU+1$@9bf0OQXOCCvr-*j=d)5BU+1$@ z9iRQV>-ajKmFoC9pOxzPI-iy5_&T4J>i9aJmFoC9pOxzPI-iy5_&T4J>i9aJmFoC9 zpOxzPI-iy5_&T4J>iF!>UB}n?tW?L>`K(mOXMgTGzRqW*I=;?lr8>UOXJvEPb$tBn zI=x<5?m9mEbJy_|*Hax|=d)5BU+1$@9bf0OQXOCCvr-+O z{kiM-I-iy5_&T4J>iCN5sgAGnS*eb%^I55muk%@{j<54sS*&&)U+?=_oN*mr`I%J5 zXMgTGKKpam@!6ldj?ezwb$s^cuH&;mcO9Sox$F4s&t1o7f9^Uy`*YXv*`K?P&;HzX zeD>$A-g-?UB_pC?m9mEbJy|NpNCY(XMgTGKKpam@!6ldj?ezwb$s^c zuH&;mcO74GJ=O6Q*RwrIE7kFp$A-g-?UB_pC?m9mEbJy|NpSzCF{@itZ_UEqSvp;topZ&S( z`0USJ$7g@;IzIbz*YVk(yN=KP+;x2R=dRzBBm>iF!>UB_pC?m9mEbJy|NpSzCF{@itZ_UEqSvp;topZ$3&)$!S%yN=KP+;x2R z=dR-g-?UB_pC&Kxd~XAbkcgz+>Kjy*YNu+&a0C%1wOv7ForOe`n20u#&0t-!=`aw{-rvdFDSKAy=Uw*nK( z$*sV|a&jv$v7ForOe`n20u#$qUB1lD7?jx=gOW1_scv3!79yQDDEIpNd4n=LZ%}6E z4a)4iL7AO5D6{hhWp>`6%+4E>*?EI9J8w{C=MAvI=MBp2yaDX<2Hcm=81%Iv&BnVmN%v-1XJcHW@O&Ks23d4n=LZ-C!?-T;64ya9gpd4qDTgBSIAgEBjB zP-f>1%Iv&BnVmN%v-1XJcHW@O&Ks23d4n=LZ%}6E4a$ut4e)t`a>yzDecqtl`qm|V z-k|LM^UaHN-k^MQz}Ch7XFsNO{mn@`7W=REmUyvyh8F8=`>A+_C-*2W`><1BzHNTR zUPZa%OyU<$*`qjUd)17}{;%y+Ogl?AwYN{Rb+Om=suPu4KO28P$u+giJY82W@^7}L z+EY1h)@_SalPY`cwUxic^Dq5&YW_QrQ!Vd5ebXoZeN*YY!TBm{9;??E1x&uJ5WAv!1tk=na_RRpv=x2 zl-YTMGCOZjX6Fsc?7Tsloi`}6^9E&h-k{9R8`6%+4E>*?EI9J8w{C=MBp2yg`|rH{kb*`@8|a|IOzO_`PsG zZ&04~)exUID6{hhWp>`6%+4E>*?EI9J8w{C=MBp2yg`|rHz>3724!~MfY|8s27F)4 z=M9KaK5tNVS#SrRHz>3724!~Mpv=x2l-YTMGCOZjX6Fsc?7Tsloi`}6^9E&h-hgL~ z&l?ciecphW@3WdbvwZfT%+4N^+1Z0KJ9|)OXAjEk>_M5GJt(uY2jz-?KYLJSXAerw z9;CB^JiC3SlxL;Sl=2J>>Fj8kogFQ+v!i8pcC^gSj+WWk(K0(bT4rZQ%k1oEnVlUi zIXimZnb)@#KlH?bhwt)OwcV9pw0fMo_@JC0TlAyKGVtW;p{hCCJp*$_{?VU5Q$4(P zyV?ir|6(<5*Q>Z&Ax%^{48A z(+lwt3q4*va_u7GS$4R$`h0;I#1rptR-5#Ex5S2dZo0bKd##7WU5`7rdUHg(_|m(N zt1jK|I`M#O4z3RP)eYj--dj~4_r6X1(%plq4-R=+{MfNQs%KUn0^R-dES5O2C-Xmz`A2XW(r>slkm4j1RXGUxt*?H}0wf$bmI{(}@)HT(HBulK=R)eEC*Uh%i{ zRm0Y;x$Th!tKo0gdj9suMXH;I)STOI&TWQmGi;k-+YH-g*fztq8Me)^ZH8?#Y@1=* z4BKXS+?juBo$&SI@`IW72S%UNnmq6%&22O7&z+#vC_C|z0x@^?UO&Pqi+8 zcM)4bonC*EVg zKj!DP<00$!rx07P)A0m$Jb@igV8;{K@dS1}fgMj^#}nA`1a>@u9Zz7#6WH+tc07R{ zPhiIr*zp8*Jb@igV8;{K@dS1}fgMj^uT$9TRPs~at^U)ymDef$@j8XQPGRq>VehM9 z@2g?&t6}e}VehM9@2g?&t6}e}VehM9@2la@r=2Rq{9CnWx2b!sHjDDx)m;}%XrFEy z<-My_UhChyd8Jp#fk)XRo2RXGulSALmo@oAJ8k?Mj4ao{=s*{YZocyd(`RgNb96H4-EWck0XZlx#wEXk&Vp%jci=n^6}cO$3kJ!dh=D>;|{I) z#b5sJx%My4oKt-2=9@RK{$zUbZavOxuCVsUP2>+*?|~+NVA}XM7+J1?(Sa@)-En?g z4AW<9Z*zN;Z&*I+5u+#S7o$J^5z}YMqpL>MqpL>Koc5oWIcDK`q<>>=P4}HMs=MPL9 z{{|yVA22%T1IB*(fQctrJ7Z^g`6}s=4`J>p>zA>!JsJyS@C|*yQMbmf*0Yet)a{uc z7`q1T_>w+ge90e}HvSDpmOfx~&C@ubDo{?53! z+t2@MLD_fwR68{%ojJSO*I4B8=AHL<5)be3$7cMaZ(qi?5dTdaWkbA19Cd`Kt1amc z%oYBN{nM_w6Z=HINjviNfjoNXgLd@u2d0gGgOTML7#-+>(M=yP|7GoMnS3MD)5!EU zvVM!qo+7ie$m}oZ1Do+{cE8BS@4HQXaqJU4_D_-dt%&{VdfK8rVr01nz35}oW)b~wl(9wiKA?Y z*NCHz5OuX7A9V+8f#ZCkz1{8f0V7WzFnZ_%Mn8XG+W0pZS+0T6K_4)>=>w+Eti3Ih zZ)AEJnf^xBZzHp($m}dK`{m=>o<(W*{UYC>J@#2-{wXrQ(XV7^i}n?47$c zxdHdtW*;q8QF=}RG*Pf4Q9pXSWn7hc{z)AZxizU+`^qs)40zx?opo2PvJ z%>b@_Dty`Ab;XIAS4({QRg|AqGRqFxqB-HXz7vr-Y)I$k4%eS4nL}6EGhTaG8*}oh zaB%b4@q^oudFzw}@$ zUi)Y}GLJpHd-MA3UYE>#%O23a)|H*wkr_D8o$=abn#de7%PP%lXYbUcuL+-DIq|gv z7HA@~;ID3o*X}5p`Ih~>J(C&m^S6$wW&Y#%c-D+jc~}wxh4M?A~*kcx{Kxjm(FQtgl9P?~QCM+A^EtwH-ceWaHSD-Fv*Y zV=Nlk9B9jY7_aRZ(?&LD+On~T*LKW}MmCO7zGE)6WpkjB&6$7L!)JT@DeqkI{fPIl zAKN=uzW2-agj4qFac|5%`p3LiXY6<{W52+=3C#1EcN3WR3EoX$-eq{lfw?E%ePG^8 z_yg0%zro0I4U7(S!RV$xm_B)ba69i6mgju~Mi1{HF#7Q+OrN})!1T$x2~3~NLzq7E zd(7H-=d!%sagrXr`@r;>^~*Tg9^Sdc=*aBXUaHokcP`(r-qC1BKJ(B2=zTfcd>L zy|-EL{ZoIC{SteLXm=6y$NfnM)35f8Zf6g}{K?uSldjbswC3*G{~?df*`B9kf4JcL z-Q~|rK3ETZ)Yqct?|a4Aul9Jg&dwe3w5Mya{~u(~!=5l}myG4>wZXl25C16B(XZYk zlRcW-$!6p`{Fd1q+dKBj^wr_R!*3ZPd1U8oY%gBz_=THaJinRv#>LKU-uKa(;=^xw zquKk5WyIm~IYRs+j%^|S8}qe@vLRk0jygirC62l~?2LWV-b9{u`hbzA59^^182$W# zX`>GqS+0T6fi4)`^Z}>)a(g3_Z)AEJnSS-bwXsco!1y4uQ+?2m&pclEGP_^ob?>oH z^oY@u`AvPGhc^BVMwV+}bkGNk?tHxBm=;U)K0due9WL&(%?fdUzOVT53$Bm*_HD(? zqs87|Q@r}Sy+ZsWj%}JV=!vo+Uekc1ju3T;=WZRYv7x{E^Z_GJA253814ci8&_f&lMmw@x1ET|7$e^1(Xy-rL z`5Rj@d5s%5>AYR+#qUyYfy$3yT z-lx^6{YF%e9J#3YmTxYs+Pf_|XvSwgscsrSs@iwdV&d+zkE&K&Zm~fdE&pjX_3k69 z#+!={dS=+C)riMORQq1H=%6mAd|IvX$)(jtAM}@=&9=F;di<*Xx;F2tIm0E@9|kNb znO?_TTD|pL&E228tlIS4K5Fm()aBL41Nw>=KIV$*XFK*2x8Av;x_zsq#DhM+qI!3W zrN!&~?uu&UCd-IFo&AdHH)|{_zNy#c)$bOs?aA+J&(kihHb1t$$LTsWYPy6|a5RW!0A-)|~rfpV4PjGq2YsncQ#NE^ubGpV7Kb7Px}mdX^%Lcci6pJedWG`&W&^Xqq+8|*4@1CpfLTXmFMlO%YIpT z{yg&emzC!*?ViK1=P>L!40{g4p2M)`Fzh)Ddk({%!?5QG?74(Jp3ku7Gwk^cdp^US z&#>n+?D-6PKEs~Ru;(-EIRJZ3e%rR(=0`p}vU>50MFt^r(V0h9Uu?YSAg=u`KYM(U z@tAUL-mm8#GM;;|=bkvtJ=k+k?P>18o_nz89_+aXd+x#c{dx^zo7W)hH3)kR!d`>0 z*C6aQ2zw2}UW2gLApBL>xf;LLlJe&?-FB&_o^wh0^Q=ijs{wm6`x4?i zw%xJnv{x_j;%DqwO}+Qx;!h49QguJDr}(%oJ6C&+?IAvD$z7@sCM+g?=b53^W1lZ7 ze)Ow7sx!B&`SBz6sh)bJ9@7Wc*}t0M#F|en4ywlOTJtjl4y%UmS@S2e53g<=U-Ng( zhvsfOS1S(ct$TT3>z%6cTPz{&_R)~)joo^Q@9wcv_10mFi+7l`Q+3j5J;k@}{G00H zW)JaFJMUT@{+GqXkG;8D_07*}p7ohMt5ttj&%N0f9#$PYu;#rl+rL`$<3%L@)}{wl zD?MCu_pXOkPd#4qMb8~kJvX`L@0y?AH7r=zOdpXec(T+b!bj;wxr$D)$i^nsDppSmt4?!Eu0s@HBcw@p2| zTK&nIH`sG@_2?S4&b;3ZP8(5mopUki-*NSk)%07`Jn`9))v8z4{M@Fas+YUeHcXl@ zs(NsjnmzZh+4qjk9!J_ejYC{D2m z&d0^;h>g%JkkFDOCXK7u##@okMkGGamd*0Xne;HS;)UBUnI?r)@waq3q zAGpx*)%Iu9JSMgeeZJ)$4Iz%AC37m*c8aqs{Oxv3;EfYu<3han*U>)I9&p%;}+bfn)l&)&$;PtdsRcPsM#{Ck^f8o*jLzQAHw!6Y};VV zW2c#RuT$9T6!toWy-s1TQ`qYi_Bw^VPGPT8*y|MbI)%MX)t=TV>~#uzox--6d$G;1 zZH8?#Y@1=*4BKYdHp8|Vw#~3@hHbOjzejAzZT_y`C%x%1?3skjKe9Uj0vE@Arvy zKgH+N_t~rbZ|zZkd(XjD`?%hECiY$Gpz7`sHLrjEfz`4@Ykt4)0oA>$)cot`_N$(s zrsk(7?prllOX%8u4-Kp4`c2KFeHI<-R97a_DkP8 ztV8~&Wsm64^S~dE=+HmwuERU}ef_239roP3(vcl@zB2U44*Tyr^vI6;qTTn4y#0V4 z`v?8@8~xg!*keCqr~Qxp9+xTORgd*galAZskjt1gT3xxuRGY|2z%YZUU#t99qe@n zd)>L6b!U0j9qe@nd)>iacd*wT>~#lw-NC!sKa3hvtvjOTo#T7T`E%CX zZRIi5Zs)Hk8QR}c;(oYWzI=By`o=(*vclPl}Le4kS~`aNLMDINB7{ne=*cJ6ihsU7y; zebuQQ_eHz!7kT>uJ@ya!?Kk?hKe5Mt#!mYm`#moCc$xEYgguV1#}W28!X8K1;|O~k zVUHv1afCgNZf6`V&p5&!N7&;C(=UF8J&v%)5%xI39!J>Y2zwl1k0b1HgguV1#}W28 z!X8K1~VxWjb)t8+Ik#HzNU^!-dWXSoob$Qt+T3M{;sY)t#QYh)qNY(e9hKpR^8sH>r?A3c4oEH zzBPY7%bC^ko&MfFc}!i;LVlC^YevsG*Vi>K^v||Y&GdWfHPh56PwcUuvD5y?eveB&UgmrpVUHv1afCgNu*VVh zIKm!B*y9L$9AS^6+wp_t8AsUT2zwl1k0b1HgguV1#}W28!X8K1;|O~kVUHv1afCgN zu*VVhIKm!Bw=<5GXB=UVBkXa6J&v%)5%xI39!EH@>;0?hXn8F!uZ#Iz7(4wg3_F(& zJC_bSmkv9Z4m+0)JC_bSmkv9Z4m+0)JC_bSmkv9Z4m+0)=QWWZL!B;Pn^V?fU#*=V z^LotpFjMv|^}guGyle=6^HuI1(D2gupx=PS(Qb@RH38F|-9(PO4P*YEl% zGOnM(uAjoLpTe%6!mgjfuAjoLpTe%6!mgjfuAjoLpTe%6!mgjfwi)|vGi;k-+YH-g z*fztq8Me)^ZH8?#Y@1=*4BKYdHp8}AGU?1-&WxAO(&WrNdW>@BTFcXJ=31X|f_=sb z_8BMGXPjW4ae{ru3HBK$*k_zzpK*eH#tHU$p`5YJ_Q19Wwmq=zfo%_LdtloG+aB2V zz_tgrJvn2W&;R6%jN5ZY#%F|JpAmw6MhNy9A=qbxV4o3!eMSiO86ntbgkYZ$g7dX( z#x~mn+aB2Vz_tgrJ+SS8Z4YdFVA})R9{Bszp7L7N_o;Ka-bZcA^*-43KG^j>*!4cx z^*-43KG^j>*!4cx^*-43KDB?38f9K%{XX^C@2W57^=R+6vBCRo*yrM4pNoTiE>8Rd zoXPaN4Ep_U1^e9!_8CRkXB1(dQG|U)5%w8H*k=@BpHYN;MiKTIMcDgE*!xM?c`(>{ zFxYu8*m*G6c`(>{FxYu8*m*FwPswL~(vb(lC(eVx&V#|ugTa1ZgZ;h+JAVQ@e*!yy z0y}>KJAVQ@e*!yy0y}@=cIT0%0vge+f zv2*S@`lucIr(3ON?(3-yYhLKg!#djEyz+<+`SG6&kLT@cJz;^PI`l8U;L#oZmhT_k zVb6$>BP!cDek*>&qr(C>Xf}Z?u+){-%yVi@)s;pj~9AwiNE6=8_@sS>owEwhAY-% zhdtx=uNgbfzqDrTpZ%_yxvwuDs`-{Nhjz3tyZYfB@^|fdM2DUQ`wZ{UKk5GA9sLel z|Huw|PQT{J4m%Hg>&OoK*Zr!lgJU!8zF*|+2lUuK=(peK*Z#yF`x!g!f9&_Tc)WDZ zFtx*$hph*;e%SrOwg~VoTUS`ip-!HzM zGC%A2Y(L`@`yc+X%}=jK#?a-ynd$J&-ldthkq>3anDchTNqRCXJGGh zVDEom?~7pXmtgi?o^Re?(e8a0?ERSK*`L7Pzro(u!QSt|-Uq_oAHtq*u;(HC@4D{( z-NuV&H{<1f3;gf2KlyihuJLpDr@Zl};1#v|0jC_a>>pR`xB!t_9y%4C%Z4&b-(mu zKhTf;lk^wpO#O!fHYAp9NoSGlp)YaLDUSBgmu0Zo?bvB~>=)<$F^4NovVYogrr&?! z!(65vdHXZt0hylv(&zcOn7KCD7IOaf809h^FXTO5u*VCw407?s(r^2b_dTX-wXRdY%q7X^KKB?Q^H0W6b0eQK$!{U+ zOPp*l;~&c??j?JOCu&c=5=VQ8vEL^SXzq3U+nIV6pmV@Qr-!ND+_V9|c-;wMp35E= z&$7jc(Cu&Y7PNo$=FsrQ$7_h=-y#0LIR1Nxa^iShGhQ!_`kGO%m}gGx&+QGj(~srp z$9m|;`uW@a^6$2X>ue|bY(M?bU%D^ao9Vug7biU--52`Bsb6ujN1W^w(+~dQ+H_xT z=YB1ZAH>N&V*0_4sbBmlj`rYZG1u8n^x1xo*No3xRHXI>oaDtxPeD8Va6fSBSDfq- z(+_?`hJK=6ak?+JYrK$2eo%YzkC=WKr_?X~i9KGl(+}6f^n)K^#%s@RNA=9wo0+`W z<3)R#4*^d7ijzI!WT)8Ug}lcLPWNkhjTi07KWa~Y6DNO)JzmIrykL)4t*2gJIWz7a zJJ@3fd+f5gQNYOtvB!>fj~(o>gFSYsU1OKzr>wQ;ACDbA@z}v0JJ@S2=WKj6Z#{Oj zd+gvT>+S@tk$=^?i?Kw{HOAt~IfsW$y04`1ny~5qq3?z_iofi#Lx}HP1v1+_x^}qj zh~DD(cZmNlj{hE_oH$K3k90UDB_02YcPYUUxA4a6O#XmzaLypPpHJ zGm{s4-O=uGguU)yk0YGy46xT-lHtDGu638>weFG(aY-^>ceE#esy+Ex>~)7s8W-7o zTff~ECt2$oowQ5XrRv#$=X`1FaASF)c+gJkhuiwSFK%ADV)$a%JlaFWzeD_gas2mY zloQA6n(=yZ)Ypu9#psRwxxL|b`az!Yq#x^{AM59D_shTA9$_K1_6V)}`C#av@Qru(%#eh?@B1nfzEQ+wo@<_LdhW2(72Wv#8PIsao@Yx#J2zA%1id>b(H#q&AM2eqepQXrG&k2uXMG4qA> zfJ~Z)V*Y>1y8EB4JAC-%D$|wKol^~5^tI6Vynh$*km=is2bcM#p#95LMiqyx_KrBb zbWJhM%8!WooBv0Ke@71HI{NTQU*nRG7wno*&Z+*QJYlNKh^c!}*CCgf>Nw(5-w~&}k9bP`=!dHx zT`|XC#jv^O`OU!Jyt7`h$*9>HaAVZ!MPt)(;$F+IP+T#`qv9b$7A_vRtxJInfAjw^ z|Bjrljn{EKj6U?j%nkZW?M=7Gewvn#dYaY~^#|*Ze+Ty)|2^2AcwMlaQD3nAv7h+N zKdL8vrS>MARVxL?cT2XXR`IQdP?{m~!S za^Liq?8N`#sE=_G=i_BweEQ8g#tz1p_ykTm#i_4?_GE)N*(T;Xu1CgW2eYrDztpa= zgOg9JM`K5O@}b&2cC>r!bZr_tIE|6)#Fva+*51tI#U4A_J$7*FH^3e{U0csFwR`Mn zPjk}k8oMN~u}gZG+mcCs6MO8CNq)AS8avuOcD0^*t>w&ECz(bz?&73V?6E_}V+VWe zbnTRNr*)L(usHcg?6JdF9y{1$Cm+^pM{CVvN4wV=JZAot3+CsUm+kToywk=j6pwHH zO&jfJ&DO6NG5nwgyvxZ86=UYVMST0uXD(*g>0L2@^Z&J;TN=p0T*vh=`p^qASLr*o zx4S*cH!UCgX`w8?%U#YzvPV!AS=@BRW;?!?I zCfOrSc8X&^*e_1^<#z7Z^7uiFz4V99-9XXimxE@9ydSRY%^q1P3ZjbU!%SSy;>xue<^~b-1`;Gq|Y)`x{*v_ag z*#6j0$1^Uq>)Day#YvAi=?~bJ`V}X8#K}%^><9bBtS|b@?$`48L7e;}PJR<}fAq(- z+&BHf_=Emn{6v4S<0S0o8a!oBvao#kW80H>eZ9QrFFcM7IE}A3jk`F_hXR>2PsC~d zh?(zPkBrwBoaUk1wZ3Ri^VWK_zLI{eFWBn~_WFXEzw`%teZgK|S$i{+7khot?)3$G zeZgK|aI!PNUSF`+S86AoNGAC~?Dd6=*B9*d1$%wLUSF`+7o3lmne~-(l5f!NafCgN zu*VVhIKm!BIN4vo9!GdeoLpIJ+2e>$JdUu(5%xI39!I$QRA&~et@wM*jr$fnySQq; zJH*Fdc}{WS@wbW}Kk?jRn)V>x<(_kkU*A4ayy+U}7Jq*9Ch>Cl;q|wy}8lj;9y*UABh!kiFu!(FQfdVe3na&4=|DkNeB- ziWkT96|eEMdUJ^V^FHr(II~>i+X~_(PkXaiZo)F+b3c5mxP8YyV%via z)(=}hZ2hqH!`2U5KWzQ*q2YwKN1p#&ecko&ZEb^hs=3Sk@3#HnXP>FPZLS#_?;i50 zc*qX(G={D4vG}z27i(NN`a^LsfA7W)=f5X@?ffMg-7bAwZ2k0Q{jl}J)(=}hZ2hqH z!`2TE`(TmA%GbZ9zRcg2u{`57VxghM$J5;BN;9&+T`=_!nDk+&F3Co#L%t|83*KtAqG~<4Gh>vGo%!4Hcl6!2SpB{SbnSf?9#~Ae<00|(Zyj2E z-18Cfi}72bU%gQCMvos|jC-}_J`+b3J1$^~2T=TR&|5 zu=VH6z0CE?!9I-l9_-ubli)Fm_DDZ{SwC$3u=T^%4_iNM{jl}JajZkOe#PIGu{{2X zYoVFN2XU?k{(9hcq1W#9+PUMUO~U>U)a!TJ9oGy8{jy%a`xYyO3kKBdH@wy}d~#yF zes6!RTbT8Ldd-f$w^JDNQOz%}{9<$B-|F@I^pmY-`-tCZZC<>~dCjl)yHWh+t4B5G zzofn91-EKWdi8d3uVsqns-OQseA5?;Hy66-G4Z&?7HrOcQT$n&Z~4LP+^^+f>w(`) z`o*bV*!IA-6Sn=Z?+f<*!uA7f|G@SeY=6S`GaO@b)6WPq_vP`*`P=gGSe&s)XL|6SAwKJa_Y!dr5WL5TdxPM;N8B?6 z?@8ibB6zP7_ZY!@n7H={-V0ejeOW(j{jl}J)(=}hZ2hqHi#K^ZWcy+9f0D`UiTliu z?YG6b9ysnlgZHIz{~5erjr-5weQex+2Jdg<{xf*r8~2~V`{B6%4BjWl{b%t0IqpA$ z_tkO#8NA<)`_JHgc-(&m@6Y4@GkD(~_n*Q0`MCcK-si`?WrrW!&U~;uY(22`!|oTh zJ+SSBZ9nY$f_=ZR{Q%oPu>A(xpRoN5$9J6IcP=wy;ql7(+w$?rDZ2ht=>4&W!wtm?9bLL*+GdK7d z9iPR)&u%{xk;$*MJbEk-TONLRs}9&=6+0U{q$x1u=T^%4_iNM z{jl}J)(_wE`xnD+-g!`cnZGS#dG0aEG;_}Nz#}?89U7y4-%$H~4~1UKPY^e@x+m7h z$BUo%__kOdA0gi1w)o>Wa|{-5{m#v?K0d4X4UPJ7Mf6@0PWxZo$wtm?9Ve5xeJXc@lZ_8ModrZ$Y$(wUM zaF+=ugumW%Nda#=Y;4$R+w;UL9B@q7aJ$pQ-JTp3p6WDC{PR;sg{u!7AwIY@I;=b0 zLE_)9Iws6HF`faAdTyQL_^`mfTZ-qN=ag{v#p{V1{mu%vU;Z=ks=Y1%$^v_7OjPczc*Uy0`f0Y3~f%uCb(e&h73G%iY&cY(H?nZig)oTMumg zu=|B=4{SSO+YkG`VBarnKfv}6Y`?+wCu~2%_CK8VX7za0`!3yMK6d7B%cnh_u1$MC zaoQ7#(_T@W_K@PVw-l%KBDOt@srAFw4_iNM{jl}J)(=~M&fH5{v+6gkWwD=?$mG{r z9zB+aEf1&ty!51Z1aW$I5T|zvaeCJfr*{x>dN&cLcNVer)0g$b)(=}hZ2hqH!`2U5 zKb+pn)R+0&GM2|b={;TY=3EaP^E}O%XVbij`JZOYvx#F~s2THY;+QXL#yp!i=8>8) z&nAxfrDn{tiDTZW8S`x7n2&14JexS?shTm*CXV^55c6!}nAZw1&nAxft`PHV;+O{u zG0!HB`LPi5Y~q+V3o*|oj`_3@^K4@Kf%{GGwz}W+&MQvu!s7IfEKcvv;`B}}PVd^{ z^bRh5y3Qep(>uF3%vSOFmv^?lG57`59fC@;2g> z&k?6Qk2vLj#3?T%PJ3Ok^<#te!`2U5KWzQ5^~2T=TYt{nOWJR%-?R@G`?-lsey!!v zV|m!}Nk4f)>4`RwKNLsX$SaDY&Ey-!@m|P7isL;NF}Eg;_fFnY9DPFmQylG)e)_V0 z*!p4XhpivBe%Sh9>xbi5lN(oG=5Nbb9{8hC}M6+9M?q=b8F(bE{d326UTMYh`BX!To;X)TNB51(TKS!J~JYhvF!_vm)m^04*5F}EiD;?yr}dtloM z+kV*h1^a$s`vJCpVEYZWKVkbBj&Yd!i^j#wSma}5{1$7^B ze2!2L636EYbs}+m?odAxr(Bjex54_c$NFLGhpivBe%Sh9>(7~cN%=ALoAPG1hg_eT zyqU(@^60UA(kXd3KI^H+>Dst|piU=_`wHrJ;<(?St|yNB5bAy6xIdu|D31FU>Vx9A zpP|kuwto7ue%Sh9>xZo$wtm?9Ve1#ywdT6t#Q#YqvnTFjsbx#voa=$({ z?}y|5w(veV?r#h4pX2_v@V+|kZwv3Y+B>mJ?C{INW2J+Sq|?iaQ_uB0%|8RWI;+%u-#mpGxV`u)he0;y-yo9ce?|q!35XbjH z&R2-jxd?H5f8;!dIKEeMPD31@gPh+G=QdbB_EbcHUO(pr(+@v?1V{b)IWIW&tDp0N`FGnB?bOeC(e9t~g6W5I z+F84DQ%OE#dc;Y;IQ1(|_K4$sVW&9W7xuT%lkQ8L?pK`rU_JUdFXWTo)Smn)PJR|A z|BL-|UR?XnVjb;XBe2&F>@@{@t-)S{u-7K+H4A$!!(QXC*FNl+06SK|jv=sP3+$K! zI~KuSv+xhSroPX*_#yY4+@tp}u=h5w_dKxoLa_Hpu=h@|_f)X=TCn$Eu=i&0|75S| zeH40r=zY%j*{l4J@BZB5PyLA?3^L& zTq5ioBkbHG?3^U*TqW!rChXiM?3^d;Tqx`uDeT-S>>Q&w%R~MUIl%9e$NM2`WZa`` zF0gAcuxm81Yd5fKI`F@^wxzwq4_%k}KDCvU4{UW zPn>dq;*=W{rx-3yv0WVZ5eiin)R@moVVV{GAeLfcUxmnofY2lP7)V-v< zs5s?U#VPM9PWf1I%F~Kd{#Km!*y8j~Do*dJ;V;!)FXL!VM|4_s;JmPo`p@?UA^xTZ+6N-3-M;y;B6!8p?IG$%H;u#)sJm*lv zGd$w>oGs!R9&tQ_QN%Mg;_}F+iwjn{OZ@gN4;MdQ?`H8{XWd)ux7S7D=eE3~=)d$> zanZ9?9JB8B;=|^fSWMNUm-xUfZYusX)dM;Mv&5%27GIq(ea<>FlVrr{+6MQVbc$17 z;$(w3*(Odli_^V`(>;pQy^E7i#K~9UsTPW(gUV?9sEM|qyW zo+q&932b?6wmfY4>|R37T^TN|j=`Q|ux+C+>xZo$wtm?9Ve5yj zAGUtjbC|x&-?))DcEZb_8Nq}Hes(>IIU})6Z0C+ zWZJW9WrJe{?T#U^V+-t<1KaxZo$wtm?9Ve5yjAGZFS>DO@vcASA7XL8%P*7C6BVavl)a@3;~_kJol>U_M+ z{QfcL|KXHB*Y6Wcd3FE(G3Eb}asD56{vUS!A9ns9cK#nG|4)Be`;_1FR{wrE`}zO* zd)~apzwf$sJr{Y`b79wWVb^nE*K=Xlb79vw#98gqH3HgQJAhqNfL&{VU4wvKn}A)j zfL+UgUE_dV`+!{&fn6(sT|CfuV873Dz&^_X z`z#0SvmCI`a=<>z0lUVLn4go<^E%}&#IA85lX4wuPdN~A%8iIq&P1GYDdLo45vSaX z*fj$5r#zC{e~Rb&Qm#z)ryQC%<<`V0=O#|MIC09+iBs-Q?79a2Nx43?$6N$IcO!OP z0~wz=hkfQ8PB})&r`)4B_IcAW)w{RMVi22Ocq-Iwbcw5PnZ+Ecz-obuS>l;0Moytg>+ z75RBUaoj`lGYjIlx8!FT#PM17gZ^w$+|PgeXMgk_@l*f#m-xQG&r<1L;`;(WV$(Q)x(4jJ2JE^9 z?79Z*x`sIWc|+F-Xm{-Zc1;0xtpRoo0(NZzcFh8IEdzFq19t5Lc1;9!tps)r1$J!( zcFhHLEe3X719n{lc3lHbF-QJPu}GX^lsLsMaf)eT*EP`Nx(4jJ2JE^9?79Z*x(4jJ z2JE^9?79Z*x(4jJ2J9LE9QP0Ud2l$L@s^!Gm7n`|T?6}F*MMEufL+&sUDtqJ*MMEu zfL+%}{7-+jI_*8=E7vuUcU=Q^T?2Mq19n{lc3lH@T?2Mq0Cv3qb{zqBeF1je0d_qC zcAWxt{Q`Df19rUwb{zzEeFS#h1a>_IcAW)w{RMVi26kNoc3lH@T?2Mq19n{lc3lH@ zT?2Mq19n{lc3lH@T?2Mq19n{lc3lIG>zeb58dKLbXm?!$c3nf)X1}k=H3HgQJAhqN zfL&{VU4wvKn}A)jfL+UgUE_dV`+!{&fn6(sT|#JqMi=rrkMV_@Cr>C7B9G@sgb$udKb1$%~U7anfHP<9Pxnd(@un z6es(|`FL@U#FlHi4z3(?V808thmHrEK)Zbfdv3#?+py<0?70o6xu<(ib5iWNjg04Zt*71( zWbI8j$%~U7-AmFh_S~-Z)cX_Ia~t;DPBNO?sa@X|O!9ipCK=6bIL$Hl8~A_PJ-1=c zZP;@gW^Uuhti6%Ri#@k#_uPh4zXj~M4SR0Gp4;%0@!G-jL9qy*B!B+s$ID|!?8@2e zF2%G4>mkLuDbJMXE3Z3z;&oU1=l|}R!n2Zn75j%N`?nwe{_VS-<8HrvlNtPMEpjHF zr01_<@^?M!({owZS{^-?hrKt*8U6V_A(wGG@@C|}&tAgvTxpBVbulV&!t3; zHisSGIQ<_Od!kRm27SAD&(T zoRLrWDEa7r?p>UGBF?Y1JbEk-TOKAJ@~uhO-{esStooa_-NJH^R1#v|6?2fj$E=c#QwzSi~Y&|cwc%aO7}&(?w5YBFViDV`o*bVak58DKmQ+l=K)nk zw(NbtoO42gIp@q_V;FOem<0o1BA8GVRI+3hR0IQp3aB7PgmbFRNH7P?SwRuQ7%}s8 zRiAynJ?}m4H+RjQ`{sUYT#Mz;qWWL8Q}^!OyIZVBJQm|%Jt7y?Pkv876vxHy8Aq}Y z-ZyD5u6(RHA5%r02jm>gaeQg>M5aDp)Ok#+N#)YUA};DYEcV-?`Zk}B;op2dhRpAS zkmbHX^D$)Y{Rs6-ejkK(ejkLay|1DF*O=c2p3&0-4>7+FLLYt~ggV%t<-f^Cdmq95={^YkWgof^LVxZ32>I}NHTv-TAoSt$ zF|_mf7&4E8K3cm<@TYp<_d)2d)i+1x_d&?oe8|r4gHT7CKiL&Or5-tJ*Hm@urMw={ z&g)0(gY8J`tGqtZ&g&VO*FQ3E7i8XE$Z}4Ui(vnIeOtb7#&%WeN9k9{+IA#6?}uo| zw!?KjTvO%iipYGu5t*+;YS&$99Tu6dTO#xIOl0l4D6QFQ*F}l>x+wba^-{r~){3<{ z#9DoG^x^BV$l83!uFaE}-xr_{jysHp%-0o>`Ff*PM~(52`T8U>U$;c&>zT;fby3Pq zyDmzM^(Xg5zCQn_uVdr&SpNUhKzrRJ)?QDEwbxlwbya-;n#gdN4f4JYwaq*-yB&xe<0@9eYErIJ~F@VBlGJ%GQaL4W4XNU?IWGL z2b@(qTkj)LvSDVy%t_eYE<-+PK8pe2BGq5^M7(#_=V`<94;22lrRY@rY#|jU10y*4N1K zi1BayH|Bu9M?YjdPL4-;qMjU&7~^0)YRiRomEcdT)iFoAR-afKmspz*F~-4qL4SJw|@5^M7z=3@>0wfU2sk2S5G#u~D=5976GyS8t0eHv@%!^avjA8W{b ztl_bItSLJCP>+|3#v0nS{!|Zqtf3AcYv{wr8ru0-L*`=*nU6K}$A4?jS-;`G+in%L z<6ph)iBJ+78GM_gJ_P^JQlyxeqe?D)-`r-3NWIk_17Tb$6&Q-K?W}3I~wnIB_ zJ7nH=$h_^4dD|iLwnOG^hs@hfu+tn&>#srk-*bM6*FUZGVV&@{Ll)bsprnDuq~;uY z-uO!eJ>t{Rhf+&fe^8^n$CLKz#vk-S8~zR%eeoD%)Icp{ z)W&l$GRBncX523OtGK_cLyS7IJ~8UcKg1YQ{v9#Klw%NMOgV-*>R?Pc1~JAI>}G<$ zO3+aW`YIu=O2|hgMSCfV#xr_TEYT5>cIa{rK_fg!iS1?Hg`YcN*|cjs9*!&Z_YT8EyDG zWc0;jkWmA*kWm}!5gB93b~A35{Z-sw)*(h6S)Um7c?EDH;hX@7!%8^ zEtg8Df0fWKW@39`8P}XQP32`o#`su9WQ>nxM8^17Mr4eS@sKe-mJu1_V;PY#K9&)g zw;i&!?NYfNV{m_rfs8sB0~z)42N`YnJ7o057|5uBF_1BTjDf5z7q?^Eaet~Stq#>8 zGL}h*i*3jAp|(IDtQ(AhjQs**C^{z8rra*n1Gb$C?O2x>0~zZQe~{6Jze7e}jDd_A z7y}vWQf#lj^_o#^j6bY$eRKbA<|)WFp^eG@A|x+$+jnE))dqIz&kdjn^OUI)Pe}`J=E9Xg!8bZ6671ee*TTG}OM;?2Sx_?3~Vv`Az)n;zx zh=)~vad!yhFI3n$XaITFKcTsFJ!sDpgon_F$OaF zV+>@}!5GM>k3Yz0!`~sJFCK%88W;l^wJ`=V#uV&kg1<`8Q3?7gA+Acu$6UzMT*#m5 zSjne8+Ie}=Uxju#rnyi*=0d$;T=GGioR7Jp6RpBykWoWu7wQ*{3zMlIVA(jAxS_AI zUv`)5C2n}AZhuw!gx|@Ns^uxwC`Z}Hy#C@Q#I>MMh1|mWklCx^ABf|l+p7|uJS0Yq z2CvQ#_s)-1;Sc(w4S$D>zIY5WYM>S}YGZE57*n>Va=YxW=Kit{G3rcv9!_1+~_m$iW+rPX*2XRsM+*Vq?sI#7~>1}RKZ^@ z=%@vKwGdY=OSCd`9IO((;FTK##h_)tBjOWTtvRmVJoPM?O}C zdE&7`9jb-8RSR{l7TQ8Bw2@k9yHv4FW&VHmf$Ez-nqfali)ohX{qh`f{K}}*>YJUZ z&!ok~rO;XT zQ_yFHt-gB3{s{6}-or^gc7+-C$!v|Q`c~A4RP?!g;ZQ z-}neQb36HPe=LtS2aRy7?4ygTMjvfHn*ZXjt2fa{C@;p+)#1t`w&ah#)m77pe_3s+ z{&II5@xcaL)S18bBVKtVN8Rj8TVhRoHI4j3EZa2l@9)T_yOd1Ra&2PciUV z*+wytu?~bhDF)iH&M*ct)}>Hh^ry1RF;RyYb%c7O7K{xFpo`%!~e{fK+#H_^yH#Igf;YG+VFSC=!-FsQ3JJ*Q5$0*W4#J? zmEbSWQFS^L1O2f~LR^Z0cG;I=AY1@UjCF#V$XHhx3mMCY@sP1zF*jta4~&P5^@Q<| zvHtLH{Dbw1F_6)YF_6(8V<4jr#z01W{6R(={tg*^@fc*(;4x4eW1t=X2zF{av|)~d z4%Q*pr?x{M*@ksacG(x}k>^Qmhd#2lIsT1*ur7u2QoW-c>r$v6YA3X#KK>wMU1AJm z^u=S4F;5-?wZ;2o;XeBB^$oeMaP8r*w!ZQA_)_}wf6Dk0+Y1@bpEwRh#_@=DJkQ`b z)t+PjzQ)OQ!q1afCs;RFN67pfhKzNI=Q3``a~$`_b00G5;5iYQpC^&|c@mkQCz1Ji z5*f9{`H3)Z`FlPo&)@!v^GUfaX>N@7Q#jsmo+;l4X|RnI{_Xvj;Dh~uAB%GvTGzt$ zD)iy^O8=_0LCi`{V^l+ zF{>)8X1y3ftg;MIsaEwSmiM@*nsn?$eD+ugb6Z<&#oH0{&;O&UzTA$P8<$v{53$gWJb$ta?MU^F^-Hmo`r$gf9Z{dRBmIs4Mt`9lv0S_z zF@N5USS}65Lw~KE*8|m~phI?{9eG@H^by*T;%M8E=TAOLdtE{{AG2zW++OF1RhAXy z@pFn8>$yqCL&Rr~`N-`RMT~#rzwuc7J^CTzadY*;OoDXj=ZpU`v{u*Sh4zX6B zSR0pEn-8%zPhxHU#7cWz;&!>;p5y*Cyb#^Lp&)i*~?ZCqk)KExP@*FVPL?IO09wv6ac{RQh6 zSz8ap+WH~Z)*G?5K8dyUOf0k`#nlb5b>zPYae#!%Sf1c&Vywnd$HrsM#2sQ4;F3i$;3SWRkExh+FjrnMy;Z|2Q*jSptU3dX=FIUh~O5VpVn z7;w1l&W9|NBT zc(9wpLs-jCay?Y=B%ghkM#I8F#b?=pF<^XF@v*Hw1`>BDK4mP&z{>Srq?5OA3|Now zB%ML?$3R?XFVg8y!xC%_y~$^=ffe}t>dR)7Uh|teeD!WJxKHWOWN+^|1zsL; zA}*?paxP4P)z6$r({F(lv>Q5)VtqX^9tvVz$bNC|1h}Wal2JCCWou~n){EV%62`Jat>F1CFE;y1D6J_p`& zw1umqY}qdP9N4>=4aByvV-w_apxAGV>e~4B9U96ed-}lf__gf)>rghmrVpgmSo7cd@E;i$;<+g4-ZU`1y_~to=cTpx z>|khnXX3E=_Hh5HJ@b(5;y5a5>{L161c$pjQJ!`C&VjchmJs)zWee4$mBh1FIl?(R zM;dpx>>a>2(t*ZZ_|utSmF-MyUw$^^1}`R`0dJv1ccCjB;zq|m_ zug|8s{b&26SVpr;4zRb=T=t}ED67=p2^QCx!**w`WnLZU!{BAJ*~?FBe$x-z51j@f zJ?-dPEavk^`nlQlIWWfDmW{XcXE|SH!Gl>g?3V8F2CRYd_MX(oP7huUPm?^U zk7?cp!{+i{)W?on1wpur7qyYt-^70V>UZ>2u@4m0)?%HD{`cMIfzM3`I&X*dnh!?< z?CE@7@!5PZv7bxl`7(A3pzWGDbpF3{cmcdFF^8@TVjuWD?dan;AA07@rgM1tz4M_* z<{UcTb~!u`mb)liY`+tXoTBjdoOw_za4wyzgX+wKqt*(4Jv$G2q}kKC^u+)t$k*B* z_nHR|8x?!5n!$O-^`!%yx1Em4eea>7X;j|{612za-Ee|3_Y|Lp zH5_2uBzwxCR=6XiYU2h3IYAw*k82%ASXI%1@=^D8g56sE%tQxx>ZI6@7dk@4a*h;t z<0(gY-9_O)qb{j^Rm7h?UQI>qN>wSmr31#Wn9bR8x z&zQ2L=~$@%o}Vs5v6_zk4C|Vdx5&$A&!%OTl)4NnL%gFzNh!;&EOFNwC8YHe$`KnC z7L&Y86@SOG2GYd?3ODl7m)caSKt7k->Pc_fE4(lH2UIjvc!=pY=$@hYzdG;*+PW(& zmOcMt2`TMTNej>Z^7!0XLQ0P;X>t9K4>PD-LMlC^q{YxrtC-`|;?l0%5*EF_`!mOo zV$xiP5*BeOf$UI}fwbXCaf=0}!R$z+zVv)Zaf|0oLRgTmp0qfzm_<%{2%D1q6GF=r zvnc;Fgo*X=xnBWXSXYMPemGD7gSwWXxC=&nhMc{nDQ>&EUtm;WDT8A+ECi!lWh_1v`ZAM* zpD=!0X^Xel0@&nN-(h0=k`^`mf|>RBpU~q(Sqr`G9?Yttp0v5M+_xwDuzF+kq*5Ez0Evu}cwpQsL6F79SURu}-b^rO7kPSiIQ3id}lCCpF(v%EC;} zA@Oq|-1?=2MgO58Y{LzGNt0QI%F_OezGT#`w8hy6{;b6aeW`q@k`|>02eX}n4J0UE z)?$85FZL|kK=MCQ+QMw>Dt6!7KU_`h;*z^zX^Rezz1ZpbCXz)`DqT-^_cD`8TR=lxpky3 zPKOxw`N3CeOV!&SWZ35&lWR#s^Y%0B^J4%1caA%;ysPw0rIO}H7@pq@Czwjtw;W=4 ze!J^zDqYCm&+z>AdaS8*&@74J`K|j86KUY)1Y(c5Ceq=iyUC|^tg-aybsQc0;ee5p zZxBnGb`f=@m<2niZpE^Xnpj&3+n+>ra{5bciTNi|T`gEsN9w(D57l9RLqq98^e(Df zpD>w!#8I6;{cI@3ZH=Y2*xtXcbT@b>wNdo)x>EL)9n^Mzc01ac*O96{OkyWOLRgas zL+SOx{jA_&Fzf!HuH^Fa0Bar`#Bw(qN+WJ1GVH^(3XP;&-43zfm;iS4R$Zx8|0LFH zqP*S`X(*iu+RdyV1hR|y#!|aMhgprTer)X*Bgr>xAH(suL0wmBdTS3GH$wJ_G?98& zPiAg*K5Y3LV`)Xwe&&15j}@FTlFC;~WQpAZSe12kr7rj48TS8Qip%XAlFWX}>kFRy zOeE`&0}RhC_YWFN5%u=6+#P;2W2{pe^awQq8eja}!( z_ANG%*61g(s&T%o*kEI+(#_or$907!MpDg@actOjUv{LVsq`Q&i5ZObX8u2nrH-+C zSp9CktZSx`w4y>h8}P-4)x29*D&@M9;kb+QH<5n!Phfby>OR3(I)5;poh#(lXX;oFXI}n*g-aA}5LgK6P=yz7(35%vEBtzf zzSMfA!gcDNuDkoghHnRmn-=c__Z!C&cM9tRIc+0|H;x_%lja8zi|gla z9<2j2`+Syu&XbiLwI0~V7i_t_c0cg#dPo@hf;EZpWp6bb;NY@67BR_>_1zl|D?FaF z{V)8P@9B-uW#%*1cR(P!`85J2w9jRMjzKJY$R^m8`;^t263jjw-V7EYPuP#@AuPH5 zR%qJxF*6AdVZoXxSaIngTlO@BeH<1Ie7_iEY}3 zgV~ci#Nu;`lNZOs%y~X+$M*pC{@WzDH_?~bOb=qSmsmrm$*Wj(_h2Tqn*p<&{Fu|o z5awTVCM;O(&)QxI`9semayAZwa^rkh?em^2J83xV3G`ui&v>&=okqgDYd&nP{9NN> z=h5&`UKj0U<;SYL9S9k|LFDfpWC<5yeVO4)e|EI;V8~AlqGNZp8xPh^R#6-Ej~)VZ zo(7T5yV3pOmPsfbTkqg7@MslGn#~(qfnGm9_SHI=t#TOv%gsYc$H{0UESJlT`cEqj z0;?JFI+>i$^SJ47-_)OJMu)JI*`r~~gJ6nvro|92*%(TiRj=4Vi9CN+>uLxK=-e0j zcZ;C7o3{>wuks*pBPi~hZB{UB z+-i!OJGT$~7#&5Los9=U{iP8Ucg4%;@ciX!iu*KX9IQGLM*6?5?+Z7^MUj43#1JTq zh@c#DJN1W7Q=&-U)M_%+ZnKW`9cK*((_;~o!?g(mVTer>=~s%AdsspuzKAId41-lyc2eAxwnBcvt=KN#*r9-vs&jYh!g`+F$Xo(dD;wcAdL6I z^s+iY`rmQ}!??gyirZ?Xl|0sVQmi(!$3o!TJrpakow=Q&K6eacVYklrmsC8W;O<(mS=v4d&#a&Q$99RaYQQUss6QKVv ziS!2qjR)g4X%x4+{7lDrKr+R0jF|+1r?N=D!=j1Mbl+);dup`}7;idEu~c)cp^6cZ ze(tu(@W45X^kWkygPrkd%AsR1E6|k5BK?n#W1@#C9;dh#^4f1m$86F(({L7)+<1}VUaIB*mXD56+^g z^94Hg$7?s((eDQ7*K=M06Hc5X|1-mUVBydwl;@y$ci2^MjWl0I`+)lLW6Et`4PRK? z_%Y>EZKNj@>vokiukH1P^}QZZK7DR^!QsfuO4+Baf|}hPQV!=@_(7ZU4=C=n7i-|- zsXU6Mdg~A0X5OV(?V7EX=kR$HYwPm0@P5T}iZyRwAY{zEO|iDUUJGjPXB4aZsvvk2 za+6{WS`Z4IrsYzs5~ac*r&bQdn%E*7JVrey`;@Wkz^?scinTgE99|aYl8^P6_3-28 z1Jcjwz5!AT?vbWx+D7m#{*?T8Z;pWeCm)ed!i-3;O?W^)v8%Siu*#2!|5eW##OEL_ zb60|u&3u|y)W~%O;~Gw^w>&qfsP6)<+4fA5=L`-57QwQlIZPv8Q+>|Q1LMS5Y~_p~ zmKf~-wm0qAfS&<0FM1u?k91022#3e*hY~x!34!^C#u9&d;R_k}rxW9Ra!-pkG{?hv zUGu~?x_Mp0O>K4ax;`)3>E?Bv*L2X$>$Z7z(#`AI9qB^#jPtq|4a{`&x`8R?x_MoL z+1+*Xx}i;b>E?A&PkYn6&Zz7>m@t0~<r_1wuI=u{^u~m+F6#qf z?OR5Dtiz2+h`8C8HIwHXeL4ogY2zN$moDZ6LFLe16wCIkJG5Wamtqxb>H$-&`;q<> zmk`)%*q`F|i}Qe}`2G}2vuic<8#_ z)(cVshElB0E9U`wJceTRA2%Ns?X#pFW>yY;XXnuJt#R{4(k3s9P6l-gx zMKE*lc#8F?_e`ii*P3*;-*bkSB_>kbMaTVM;G+o?*QeDiSl4(e=?6Yr0vEnaq8z#` zm<^FFrjdT0(Og*XKAkiNxVyolsZ%Kj)5;EzSlNa&^S-Zy>qll#4rTi|!M1C*q_a7~ z1Dwv}yyzfU?^Vb<0etL;HU@k>D-$=J9S4~+%M;g{p8&;k%Mj~t-Vg07Dx7~NS!cg< zL8J3Owf4A9XZD-ZI{jW*8M?UbOP|x_^H&(NcrV85t<}mCaI{@7I=2kpaUAX!XT(8P z$Dl^1uEcMWC5U<0ftaOgpnvnW#G4nU!op^)h`WAD29Nj6iBFC?1Pvpb5n~2%Jlh|}p;^Vq42yZF|2T|NiHVsv?4Pl?v$KdSvX7?s|HRm6L% zgJ+@AtfuUcd~X#o?kueI?8x5a`!f^$v+!w1Gd6XHFMIVf1J2JiA^&YT%CuJ-f zXF;A*b5=0LkF8ph0rI*e>BQ|#hv1efR&{DH3#pt5KQda7=J5CFP<>=Q(ll$52DdG0 zk>3W9&Aeb>ab(5^HdGepKwwG`}$QR{Wf2Z!jBKNNI%<61Iafk zk-qA7GTd8Rmh>z3I}ZC<8`58>e;n)wHzNI{AxEK)lc7>qjWpnpU4`_Qo=ApMN6L|Y zqDBp0+gB%j)z)MfHn9TfW8a&)zYOVbx+_69Xioa;(g13gs7Ly}`>LV(y_%%&Fh3av zJ60lnJa*2VvZOzVB}4C=Dx^PRMFNyvrR0o0x4p_!tdd3=xLdmk>5oyRLcv2L((kF4 z44wB@Cw=s{jH*cbi#H@dqeLZtw6`-=^m}^6fsKJu=XX*P;PY^$ERSoYfSY|o(tqZ1 z7^Z$SBz-)#^}A}MANn)_M%pO(=N*WHGe%1N+t*HnVH?j z4rmmk^q;D`BH_$ZW77XICJORy*QWYEW49MZo>KJVTkZyr6H5K}?z9uO)>Hb=vd>Xa z%+HYOe`bwM;Ly*6^rxw}!3S?6YF~$i;h=VFO!`Slo8bOzQ_}C%e-9iUsnq|51F`Vp zm?_o&()H0${Im(xf5yViF#K*k($9Mx4yzkBA^pjdx4@pT2Bd%e^*VUs*oO2^Z`}xu zt28D34Wr`W+r7qA|5LrT!{loXNx#{QtzhEai1Y`oh=BS%nvs6z#p_{tejC!aT@?v~ zcQz;eA6+)Uo6T)WGh_2kcsf?;^I-?KfyI+%r1}29CMYy(Nt&fvg~QSn?MO3j*hcv3 z-=1_@b=wZFceJK_x{cimL$lh@v1P*}fTeVxV?TF_hJxK4$Y;3gX4o{XGx;<+xd~?G zbR*8#76m{1bt9j4#iAgqk2!Jkty^K_9t+|&N4`SyRUUNBHCXl)o=YBVS&An!E%z1P z*YjkjqP*F2hc9qG!ISNA^kv6)eujc6UhIa6A1jw!0Pos)vsb(PS*w^&(4&D53o8@I z9yolI*LHkaw{Agfu*nD5ID8db)G?U7PI(7m9)4`kmtZ!q_glDg)Svb64`H`XzJb05 zfo$Ew5LVCPHN^A_qU)D9=P`P83#J>IQJ%xvK805c`x7r>ub|7_@x+D~KY-?`J@H>{ zj?_v21>8I2N##1w_bE6(TSy$<{vL!Zw;?Y5@fzG+H;%YM##w0Xquh@q+7>|bn~T|Q zxm|vJ@d@@$S;E$A^JbOVCwNiUh1H(t%hD%*gbNjyvLW^SSjxx`FtYtJ7QNe_nbvy` z$CtZOyCe+#69dSrmdv+iWSvo0Mv zWc@;R@%g(rrvB__@#1sOzuLJaf8u8dY@}x~ZjUd^HMwL=oI=)-yU2Jhea^JD*!UDV`^{+uxf&S)3&h0RkGZrEryWGwzfJ_mcp%Ims{&bxj$7RzP$9C_dS z({RW1SK`UnPe6+Pd*T@R9%222kHn1})o`v>0kLLGGNiQoOq@~o02JS%u=|5VxHm!J zRwr%H3W>uI3 zQ}-2+eQxFvxLB`%?ANLvgK1qqurrUwvR1b7U~ixt`}2DeoXl2ymR&glP5Ty*&(dbc zpzpX3?4@x(b|gL;O4NNvn(M~J!_exsICpNw4N4U&}`ajd%+>^|yB zylkc?3|*|S$q)}%yh`EN&hC)%R$<$^J}~9^3g$Sh9!sn34z9136OT9afYlBPmu~0@ z5Be$GvZWXJFH^X7OK+%DN;x*HzB}~qy_`+&-J5l6=?*0$-PnX~cI>vd7fkV8&R*7U z!k%S%KuTMMe_iDTRb~CTA6v4~vOT$m!leSeAY=4$+7ogt!vhX|b0anm@q*>5d8y^hR?bIXw(m`JBc2xS1zTUc zv8Oc$GKVuBkPxP@OQaW!&URzdUkqcn(mY`IQiVgdctII(V~?aUtdDGuvsQTLHZM3D zjK=STATk&y7uy>txj_4~VX!aNaI2 zcrezD-6?0!-k+4$cne&K3lqFxy@eZ__+UP>lI>gWxf0jh=LLfrxv^UZmawc799Q2w6exVFj4SMr-wncZ^)Iy-L;PWRzq8zbb_YAd z^=GT74;(4(3~q*g)CZb{$$l z4*3yRY`jF?=ipEMr%cPG(D+OM@rMeseY!vOAG6xB{bB&|txt=g(=31LGqXx8g+@06 zl)m&pwmbS$pV|1%1sXmIAl{K7+ZXv$pGkk<0u5dS5C`m+?aTbB&lH@K?e7DK=S9kP zcX{7|+<%&?U7)_aF9X@qOSb#^Q~wzo=K}Rg1QMIu%l06D>Oa2gWP8Ox;(C^{J=CB2 z&tVT2Fs&6xT(Y}t-{?>MC&$qROzH&^=QokV5gAX{SBfGv3I0pacCIx%g;0?&Fv z_7Ok!Wk_Ro{<0Trcq{K2k=LF?p5Md=*2(YX&HL1d={NL+2CqHY!_EzvL%1)vHS%Qo zkL$C`zxqO)zX!#7bln5S+*jg;)$)S;M!{tN#oHTV8Y|p7%LlgJQ+(P!@`X8574BKp z56XEceeb*44<2MGeQ$@#AIelxxY132SQ?`Az0mRj@S=;-x1SXHL$4aX6wBqBfm#}B^W^kSJ0>a!ls zelYByVjrF82NwOk$qxEHFvB{K&Ft5Zne6k1{P_xJSbBrcN`)8B^ad~rVqxuZFJ$rB^G&rU7JtwmjP`jMMSM-*HV;80GEv@PX zzsl`}ed*aES131J>4$c$Tw&`#rJmoaTp_EM(hnPMbA^-Lm42w2;07Dy{)5Lhowgi` z&rtfLdfy5d7_Rh5TT^#bR=9zIFBGez9IK9Y2J?lhXl~ifYbEr`Tuv4Gkst z5}B;;emB;wZY`;&Pa5&S#r;M`etKjn$+FuwV$r{5Mp>z#Ug3W`c2#&OspbMjXQcHDsMPc% z`{CiqT#x6&zV^q6(>A^Y_p(47`RFAS&q~qRSNR{-`H!1^fEaZ?+b0nhu6zzo#}kNa zx6g%D@_s_p5Al8iUF5y8$n91?gmUfU6#tp`;N49NhVXRqXR;Q8A-r0dFsc3xie=kd3`aj`i1YeBff!pg@yppybmc<3ZJQ%H|AF$}b*z8Xx!CLw@x&gFVElEZ z9oyD@2(1q6Cwof9eQ2GwkJw_AyjEFL;rgfUz?MBqTVuH*S1FtmcvEN3{C-{MKg>5< zr*os@HJyG!rK`HQi4Csk@~OD!GVnZ&%UsswZk@}fVl2h`#9gZfF*QOY0V z-jVk>Vc9XC+ZT=#W1dTwpCHEk=R8*!%jHmB85dYyZpV7y{#ZX;2kVXNV}0_trFv&V zzcNX54yp7c9gN=ZCyp~nhvf2yiC@K?0sEdQ#FMhmz>_5!;=}&wuw(O4;)=&JK-zeM z_*bVaupD=qI5hYi^h!HJ+_vmR2)dj>Jp0;ZcAbaoqxsZ8t z7jduWPrxrHj(GajhmhzTOB@w&4{X=%B*wP$8=&ya)7N$O9j;e({%LlXbULTDoY(0O z=yFyUmyb2fnU6JOKGu-=SmSmaYuq3EFft!&$b76J^Rb4^#~LypYsh@8A@i|@%*Prs zA8W{btReHUhRnwrG9PQme5@h!v4+gY8n@$E>n)+djP_002G zFi6tnx&N6)mp_}Q(UlAByu9eo>!Gi_$D>M&QYXzfX2Ax{9?G*uo%66urL^Ok!i$jB zA&%_jI$wq4gG!sO-gX^KGI!|8WwK1+C42Ab?BD7<()lkQ{#2*)w(~Qc{=MWpUEC8# z^L6=Lws-}BH};eM>}Ic_a__^$vzENpl?&|!BY^Da?*_++QRma!lftlWLxLD6TpUzd% zb$M=Saz>Z`)*ETMa-p4<7yWrX6suoF>Sb`7)=6x9D@f07W)s(HT}A3t`8LfzT|z5J zw{o+IN3^Oe4Ssr#nANK+jlX`5{6!y8NA$U?t|lEUyhQ$@&aY>xNjodZ`+?;-_V>qS zrJvEtTKD7urKBA$`Q%^uONb{@ID)5ZLM_`5RP^fY5U{$X=Abjl){l zsP}~YKRsIub?!VS{j}+!(C+YK(!YE!6z+y71o)O@i8E>{{wai8=F zhxW5nWKY$EL+=a~>7VSd5jr+ECw;x$8^IvZoctR_gh4y|3FJT0Fbt|Uo=ooHKfUn1$>Y-tJ4*CqZ#{i5zSP4CPGs{!)5seFygyEX@o zR-8}zei!G$#_V~d|2@kdUT>a9`r>-HxOP$0ns)RTYsl&#zxOZeZ|yS`CMSB3{=79) zp=C2q(yw)IDs_Pe#*_VLT?MeFWCtiXlGkg9+eTz#qrRkSbNoVV@YSP>T8uDNL zsg5*nkwkWRhlaFl#tE{IJXu@PuYQp1=PuWhPE}U=RZ%*V14>BhItCWlE>owKl)82= zB%QK022#fXdSv%qs4q1O{_+p)1@rZ!r?JJzfB(ZTFe|*c1=e%UiOJD2$ZKFWHS=d}7pl1HF2b_P4vm6ql2q1^6%eGlD-`4F$nJ`Wu| zI+Fh;zngF+&w}{K(8rLnVlZ*7yccli)Zsen_ht!_sdzj zl_#!xE?H+^cTJ=7Z?gKhPABEYX`Oy_aE31K`gLb@`Cy)%4Dv{Gbd*1Mv{cU3`Q=u? zg*kV~uFjeZx4v8^E?H~}yf;zqvvM2A=cpFSe0zfHV0gZGFZujxF%V`>Q_gj0&mFvu z?C5_pTv@+Do#g&YbowvWP9w&+di#bEV?GgWl(7)CIt`9}{Xq782`6CZW99j*m9+$O z>whJCqthwSA^sb&&zFO6-~Kx>Gfjf=a}>6>+zkh|DL&^kJE36><=9K}q9OOPqM5g5 z3l!uiv5t0*gnc$|Nypzg9QxTR&w2j}?~-@kQ%af|ri{UydnKeY{`xd7#IY%kM{%qT z+$eu1$E5`M-VML;jK6H zq%X+|*H-CEhU*l5wq9TAIbGq5=lW7y1BLguGm!3ISK^9e`LFgIU)*o7vi1hpRV#=3 zL+_(uu%YHtVsV}$&SAuPkvP{nkiP=bg09oCd#*Ubz>VjLM?IbfTj!l34p}rFhEG=3 zUc~FTI0q1~`{G=p?ZQ!T`j>FhIp;hMN`49?7O$t`wNkvki`Voy7A`Qpv2q>k9_I~L zJ%*ExI4=_CRN_2JoSQXC2nWMD$~otmmCSBW;{p8Zk@MKGK z;yH7p;LeK%#66$Hfa`E$;-vIgF#cGZSnvC8c<`+Tal2_rkhD}emtMJkP{#%=Mdvem z9_WreG3K~VGyL2sU928Q<@GLY4hGdTb-BetmM&*6)AKNJtU1L!w)7&*8?Rh1#Ot^? z2N19O;#}gvmd7w=#8}cP@h}fgF196}{^bn}^IuF{)U~Wq4P$9ytg=p3_7`L6jQnjM zydE8~HkRhsS9qd>u{3DZKC(y6F_!E-ly$%L4v_-G0*Etm5wBnzc_yo=M3U}qr~<)(&hEanxW;qy3)$s$LZL= z!uKftRo8v4gWopc^9N);e?aE*2V_2fK<4v@|H}Lu9cbtLU*{Wr$CQ?W9QFU(H&4Xx zoQT&8@%klRTe%%$al6PE_pfmM73VEto;)|qna>T7`P=}R&kd0I+yI%+4UqZV0GZDX zkonvIna>T7`P=}R=SKeP%1SO818SH5t?%iH-}JLJI0Hwzf1`aGwK9%F`Jq3F3+ig% zT4z1Vb8WN3FfvWyK*J=+x}@+Z(_N4^PT|utw!=J7j(u8nD^$L&Xoii6fW=imljh7J z>)~$jd*W@iL!rf-*TnhZK2X2JbK)OKi(tT(2gLgHr;pp(v#FI7guwi_0;x0FQ^amy8LT%q) zi0zKO0VpD4#y*hEmfHCyDvB0Na#* zF9?}`M+ljJUkI6hcLp7iQl;@>Ya-} z^6roLp7sAv?+c6XLI0j_FNp6K@O}Q`{{R2FZ~x!pcl!o6|Fi1(I!1&@q@xXVc8IX>1o+M6sstn+Wl4iKYG zi_S^JE3==&ewPH|Y?oXpZKQl#Y%)B7koNJ)v4mItay@W= ztRJp}^~UwFK6za69V_wOD{<~2&PiOheS-nX?kx1B9joL29m-~{WTz$$`OSB6#qZOK zbLl)`jxFvh6Ze~md(yPG?Q;MM%zhH<>m|bH9L2uvP8@7Kr1-~wi-CT76`kRpTcOD# zLL%Ym)DLv*Sc`C|((hMd@!Nyqoc!N;FOYIvf~jfW+1E7=Y<{()5VP(Fi`qVcm8^XT zk_`&U-qP+UJel#6^-1o_-Zwi0W{(QVr&8zL@Tu2N@_Ar(2<}_!S)fmh!ETsPSMfPm zxDC#(`$|5YFYN-&heFZ`3fTq?EWeS?%i$5=IPwGe*cfkvr8T~j&rJDQq2aR+(AQ^ql2v zKpyOQG?O^n`VClmy8O3iG2(jHKf6{|)U!Fg@H_~gX2))=9LB`ws`=~2fK%CU$|0lE z1hCs2L@YjA6xU9RdKUS6)?kZz&U?ng5-KLFrQF1|)8F%4`{<*MP;I*Mj60-G1bCP! zjPKJ8s-iHyPgf~WrF)<5YH^kBeLB7dThu!3Kf5OUd!7YXw^#;M45m^&Kl$km>7gTu z#pmfoJ#)VsCcgu9bR5-{xIe+mdL`seQ1*VzYc~(_&Ye@*G8sST`9!k zvu|;Yy{Kp9e`F26sQne=wl9JgHkYU@%llYEv#4Xl;xmQcvv=b6Jg4|Q?^kYXD1RSy z)>EpV-0$mPs`nFOaWA*Hk44=3E$-hg>Y0@Iyja{PBkt7^_w$JRSj4?9;(i-(PmcIp zyQuYNaeuqG?_Jy*FYX8UBkygA=aAoX&Jp*AhgS-vVMcL{%rC$lH~E_z z@}3Xz+UImP5?a6NK=!ceTi}>eOX82uqoDYeM#L5RY=^P^Oo@k=kAoMV42eH9+5^GG zYZISyOoF{WHHo`q9@KHgYAHIO11&*!?8o=Vbea{0pVGy0YIsJML)fGYU2fuDwW6-+ z;{G>r51V-16!%;eb)6OWV*QbKoQGZvf#gCjs*}W1zEJbcT4K8?$G~;eF5v zCvoicG-$tA+0W+nArm$^Z6*5(uM1GV{$}D+Gp@qc$VlS83va@g+z8^tkb6+9oMImt z`WTLv*hKcWlb*qZOUki#)AM1dRTSA5rM`jFTVjakR(}tbU1EtXPke+yS9TM7CKf=& z5Ty_Mp8X6%0}hcrwAvTwwj-5zzt?AIn{t%+qGw8A0-^}@>E-uzN&!=Qf307Dsd7jv(fyT|1{1@L2wR4`lJaTbu)k_vYeSrT8pToF|Caba8L3xGz_nCx~+caqp|RZ&sYE zh;x{t)&#^kfH+SO-+e3US+;l&C9WZe?}UnDM0~$nd{3~@dn-lzXN_l*>_5A)BMhlq6|*45wdPbvG#_`8a@F2vte zMEO+GG;@ z$M*)eHc2`jwJuEOv$pv{Vmvl$&H&>7l)WzEejd(vz2o^K^SwIAe6J2N->ZYn_v#?? zy*kKzuMRTbtAot<>LByII>>yl4l>`XgUt8pAoIOC$p0yOb^Z@~?*Uci@vRR7me_kw z>|J9liG>4dtg*+gQDfJ{*b{s2U97QU0Y$MQ2i>rOWJ?ooHp%b9lKdlSZ^duBtb`x0O%sDR z_z+J1lq`N%&h9?#p3seUGrxv@A^9bd2#;bVb@a)zj7U!8Y*(#J?#4HFD|YR?}UmD zmkzsD+}6gm_nA=P7IfJ4`sE(3m-dB<%SR5oE_52=`p@rY_y5+Xj$w$u3a10mw%2Y=dA zS*C`Ip|?VaGj@5X=zsJSaqKfgM9u|v;yiW>5hYXoY2RHxcU7!ga)J224GkBI6GMn! zZhWZlIeCisiw1^>VoU7APaYp4eogYHeVUveDdw~br@2k+S49)~U3l2zkG~HW`?H>- zxmS9Iij0e=Xl|DlA)?|6JI!_K5hB83{b`TC8h=lWNDL!6M?XZ0%Rhya9Ph*O_eU8Q zNKQAGaB;EZIg&HiHB@xIeTw9KA%9Ouoz-@d^L+FZ@zvb(BxmT9d!lw8C1>K>NKs~C zILRsODc2iyf#jU65-yUyI!AKqRtOb4&AHy;g>Y>VOmcph`9yTwa-QtDIqRNy zQ%%Wf@Fr4>_6#REGk=$BPq{#Hz9|$g3bi~(a(-VNCz>4yA~_p}ybvFH1e2T#E1rl^ zN6(WzZ5Q4X_Et*H+gFi71cj5FXG^Y%7kR@-&bqVlVq|wK$*H$1PHYMYA~}7gy%4sa zgGr8y`xCJ|{5;tsmfsWe{ zNzUk7aiaBwAd>T7?+ejL{vQz7Q(As5c0T<)*|WQc{BDK)-Xv#hzE}}l@({@hDj6@{ z-|-_kj-?aCZ7CDah}@}h@?LQe$=Mb7LZs~sCOK_p-4|=0dy$;+!(&8N`TPBlhyAO> zicUEWk(?*><3+9Oek5nQB|#kMWhFV@1>?o*dqE`Ua-nE(u%43BNq%NmFWigdG@TqH z&QJ9wIpvzfim23sBqvALcrhT%kL0}Rl^~|~wvwE#!4aZ``yR5VcEM<2DXQdjce^hl ze7s0bo+UA27!-4m#+BRTt9UKG{S_mLcDTZDKuXAjx4Du1*% zpSGLi^x1G<{JPGIDXbP0SlD zdf(bja|dp}FA7ceqPctb#fW0^UNrVXV(E**=juM<=hz(~I=0(G{O|Kbi>G2Y@rUoZ zFZ|^9x`MwZ*G2K0eIIcWH${jKU+p2zkzCPY;*Qv8-o zC{D=#x_>P~!*gO#%M*l8777*T#s?DK_4tBl z?{t>1W53H{W#3T3kr~&;i>zUUed^s7%l#Ez*XE%Z(dz<@`)+zF`V>A#_&@Vmw*Hy; z-|_bt==Y=k>~8Si<=&K^m%GSb<4gK}ilOa2#Sikk7xDcXA&cBaU`9>)zKJeN_KE02 zC20KOH=bf+(Q-6?`zLoX=|)ZZUJ3MUcjYQZoZ&O}iEG145T`*IPjNH4EO8RsxQki` zYSQ;g`1)8)nV4%0DoXqr?xbnwR=d^I z1v!@|6s5Uqhwc;SqKebp&t7?mZiD4_%*pTLD4yG0Z0lK*zMrD=+7NT?^|PEZ*R}AR z)wBUJW2zS=Io`eZiBoHelbmt4Jj9wRWl4^UZ;0uu@RFy@^^Uz}HEn>L5BG}D+`ta| zgsok1np^csi0Q*2bxxV<{o%gV)P=bP))ygu;lvQrhaXzY{|l43u9h#Yrp%1I=S*L% z{qdA(=gTk8nQPbo&tu!T(<1iGQ`dz@-CVy;JtI6~V_koZTzi2f zyQB|xj5WVY`slP5=66ZYn)}@RF6jn8J)`dg#CJ*mQ1_|%UDErWJ~6*by0P11^Sh+0 z)_!Dum-MVF59qt3|8M<2sgtiZh&D|U={p%c#%>e~6B6iq6@PxPQMft2pzlL`Qel%w zn2|u=tN4AfEu!P_6ygv5YO`oK`8loK$i7*ujEkr5Qv6}z77^!^LUL9<+#*s>KXdKB zbA{`NB3ne~X7MC*M#ZgS=)`1_`Rd*_G3`St$^3bayKv|m<2vfbO4sszw~Mb{J)-YP z?Ady&xIR0MbWMxfDrTR0MY_tmO3va`(se5THeuX;N^|c-Y!^Fze?oKb-EtQdy8%kym_ulz2jR&AEMP9L#D z-u5RDPlHNsicZwlJUz4u--|Z0bC*^*WYd`$ZQ~bW~E$J$q zxJRVt{YbjJAMX?eUp*&Xs|tIF?>;1xu93rbiF$!)q-$RJz2el|52R~kP7m>+Ry^t2 z@3>oJ+nY+didZ~_@A6lqtF`=2=Ule;q-$*20rBRiPo%5L9Z%70#Y@uFz;Cx$Gx81T zntgV!s3YEyu0n+lik>$`Hplsx7#PYX1^g_y}tAnh2|(-?|(QZesNQ}Twd)J$G0bvt{jgJ3cr4D zNmt`KzM`-E9sBq$<4rA&iDDnrx>gk1FY*`9^*^zenomnbg{bTow4eydjS4oSna5}Ga)%_44HkDDjers$O&fzLvE}n-(nB_I; zst^_+Iy_SAdhxBV$eFBk&HP{!3!FYEA3C2D*}A`{c-1R(SS*ZqMY^u94-n61C|!H@ z+C&8><-_u?gG9n*m4|!U`if`2D_sp*+C<(66|X{_0))!}rR&j}AQ4gc9qC%U^Q>@K zo<_O?y84Q(6_ZKVZTTFWJWa(bOVJ=yhwQ}KElaz-5dC6#nF{M}!8#;UcfiZ;ZFP?dYbDxDDn*Qq_Vf8hx+XNHQ) zz9FYY_VsEX&C3v?K~?#C>SVrsJbheLtFGicTzX2(`YnZGou$)R(LFtxY`FN$F1+(6 zlg|hAJtKZhenp%zV@`_YAJiVX8Eg~3JyAK+u8v>7FMb;&^1oI4 zPCPs*#w5kk+`yz$!gU#!{xjdv^S|{wN*V;t5%C?Dx{l3K$@P4}IU*u?G2zlFvxU>RMT84aoFlv( zszYITlU6Mbm51?6GKeS~UAzv~{^?>vhrm068|;2A!JUpqIv> z6Ke(sIyL`Ww759y@fuaJjJ?$AaEjd!@j2lShi_ZoZ7xFi_ujp22UBto9#wI>?VC2q zHt=V32(#e_7-M)17+lN&h78C8hHR`67&_&+GmlHYh51qrVaSp42}8d8Aq<`JH5Vmk zyG`mK44qO3Vd#`P2t%hf?yT`GnjDKJ-=gWYX!f{hcDiWxQ|vO=g>hal__oY-xoG}z z(fkIz#DPw%IdfeW&HolHF3x(qu*TIF%UXGjz|fC10z*I62n_vLBQW$sA29S|jlj^4 zH3CCF)(Fh81I~<{mB*oj`OpCjInV(N`S=0G7+wPg7dn6;13G|VKXd?Ru8YSJJLZ$G zGUbpDfw3k{FJi~`P%OZKZ=eGhc>x_tP8o_Rk86HF>?|0EFQEe%zQhkO#_$?2xX=L% z8PEX?U+VE{RjwN8hW<_k%DXIWji zyltm1I1rv&G0G-?Ea1yAyL`<88Io(4a|lZrb}7p_Q??y{E;6n#6 z71{Vvdf zKk%!zUhvrukV9DNbb;T%mpWbW1B@}e#`Z`%X&f>T7jPi^&tey|tqjGnOVE9*?+?WZ zm-(Te&3Q&{!kr3u*jAlMwIJ3m`7hh#4`DfGldln$T)Uh@Sjw>m$midBl zE0045F!;~`3^~vN4Egv0#u#1$1{ZUHAp<&qAsae?p;H@o*7z1pjzyDi(ezq0dt5X- zT{Qd2ugaeC80YnZZ^5|K>7x0^Me`f<5(i__9v3CY!-6@$kfFte_Ce*0V-$O=jd8X} zN6V;bcW69Yww=rMJAq+W#o_i49 znLW&Mt8XCTl{=4EgxgKRzqDCv@k)I`czUlv7WYbT3C}88(h@wx!48>KuWWIa`Upe6 zHg47UHcgIAlW)`X+BAD?nw_@JfsIM;e%mWs_KMGFT^(wEvbAaYIpHGH9PJX5AAlu? zFgS9q1$JVt=0lt2Tbt%{n-&Y379*P$JF6a3iT^)ypose$XXHt+XEp1BxNySWvv*jF zxKE^<3HJ21=FZ_p<8_8bOHKzG_nuwWw*FIkBh0;F|6t8u{{-b#)z=>-KOb@G4Ew?6 zzp~~DaApm2v<>myOq`ib$I7|0oRO0^?9*-0J33pzxq2zyS|Cpk;ylT{OU^xT0-RaH z=Gyu^@FC8Oyg}C5O@f?}!}r65oO{Iz&ecn!ZN7t^5T{g~$=2`oJ6OSKT;jBxTiXWC zjJ!>4J_Q|Y(B+@D|HR|TU)aDY-Pcdf9ZH;1b<(UFr%}u2^A)GvDmix!as1P2ST$YF zt=b+SPT`@>I>%YF*?Cc^lf*gaJV(wobvbKm*Ew>oX|qN1p+(bW(bjI!V&SaWEa#d& zv}kd3*48fPnz68GIpD1MP|h`DYSD7WS&N07YvzVUi=*V5x#X$N&D{a$dq&LfY*j<;(MliJ_OyjXaJs49=F?IB_!P z(%DbpqICWPA2w@e9`k%yI=(3RQ{&rpIchHC{Bc&4dg+X(WICFBjAzb;{r`poImkzC zoH)$KYne9K|1HPVYXc|K9?ETvZ~9H=XzPV8(}%N<4p#vB`(8etq-=fK}X!1!1=E^bB0Sq5#c9IT^ zOWC9Y7{1ij3qGw~>VzD^kfZsHbYL#V@S2hn13L*r26SK?vh{e$n7UN0wu6}$W)EXR;zgeBK5=U5<9%CJjWgr#hX9mb_j zjN5=Q4js&g4q(WE4q(W~4=~2?8Zfxf0Splctw+ zU|e!Z2QYl2*-tt!4qs~P1)u!@IW8;*I)LFz`~YJNI+Pqo(g6$^(ta9;Y&~AUSRej? zgTG-H>;r~RAQKqAf-YdJ5Bh-NSJ(y&e?T8F`~-c#@E`uhANUnIfH4joz~Dm%Fyuf7 zFy!M0JsgbTHH?FcIlz#?Iv^W5FpfXkIK>WQuu+o(9}*vHf)41CWAHhROD_D#c2evz zWxL>S{DCjE^^)H)4qs~ip*Ue2^6>)n0&|@N<~j+?brP8CBrs&_=M(MR^3Qov zp5Oi_o+o82>70!BQ`m1fXUg|McEniWfBXJR;~)=sF3vX8Pez{@9Dc9#U)7U`J&^hD z-|K1p=YQ$51I>PUhWX?D(SKb({6Bv0_TSONM_m4+_n7}3pFuPWiL%YC8A|<}FQ?xi z{A|qz>$0O^ggdn6K)pL+g2d|9>UprEw|wZb1{b3fWgHaV90k8 zO^!vAZ_)HxGm3yWWwL$)3B7F+gIYfHF`eXIpP7{?f10|s|V&UJ)06ujwdEwP1gdjB7s+e~#Q z3|~o}jb*mp|HKO1%6pBaXY1vJQ&()VoGflXf$`Qk-GLi1mK&+y>gByNpy_a5?jmor<+xt&fx*W{$nZDn3}vx4(=li}9KQ-(WZ zz27e$BIi!Gf-|&zep~l#ONrAZxrjA7-_{f09DP1Q&b>yQubVuzzV5k&IDR=hotVB_ zSivdws;8Wr(*`+RlGp2;M#a*~*udFy_)FXCo~4N6m-EsIO_y`}$WFwWHuAolYjPTC zHam}=_Y-kiEiPr%bUABl*E!Cb&CZ$+bzO3d3unz{i{?X%7Ds1o?Q*Ue3yYQm z&YBP9Tr;K?EoT~Ov5<4k+;G<7DEVeCIcqs!(Q-!C9CHt1k8}QG@AJO+|53Zt9;|Wr z8`K;+gGx+$6K6&q$6n)cVC*5@zszAiUc;Xnhy6)r=3I&Yuph6haevaO@#P*>dUcMR zYXcwkKP4@*o3u zb#&Rl(22V};6o?gUtk=3oZ(px&h5aEk9#b@(24gaz|e_%ESL+Ocpm`_ojCsk;}6Ec zhfa+zdzk8d4s=33xX_6oV2t54U~n}%>24BavQA}>x|;+(#$gl2p%b>U9IOEt^5qX< z=!EYu4xR7?Fmy^;BnS5E@yfcZroGI?)8yaC51s8!1NzaNB)3uaSrZSiEPHSNL^*#x z{AFVFbupgVharp}t?V5Th92~tz(G$JKfoBnYrx=Q4zTQ3$e4aZ7_yOj7>7>u6o4^~ zUIX(HBVfouZvq(d(X#-CPV_Q>p%Xn3VCY0o1Q`mkE%9OKr`!2%5*9RR)sIFz$)}zG#xbVZLp=eEL#Nc?3=G-Y zx-ib`rJexuVJk3f*Zf930gPjGwcM0Etmrg8IT1G+0X|Jov?|=5l7}@4Zx6twE;sud?dYU9ot-=fK}X!0$ZUW;ari)N>bW~ zmqqixMT?8`e$?Q>8LCv^6@Jk2pE6e{Z{SEYXHssy2L??OL&SHsn&+CRNyaqYo;x)(t7q5W>E_8qcozMXebV3I>&}#>mp9(x`>mxF5+Na(m%w>^bc_|{X-o1N4`d!Og|GR)6c|#FQpFRWX6j)nelQ_ z>)L3OzH@=inQ?c4&6#m04tyznN1V+3Ax>ug5C^`Lz9SCym-HQRfTizyx-8Onye^CM9dTriSTz4wr0>{27U?_ok45vdMf#37 z;7Z@IpDkLvEYf$xfllav51~_wyNmQ4abUaj9dTg0mOn1icbq>i(s!IcF7Q`o9um&X zL&7Rv#UY3D8FDzEA&2uB_SiD>5cb$I^APsfGV{l} zsns#rN197D6TU>x0reC84D=#^(a%7S0vP=a^e%wW&%h5b#_$?2xR?VB8IT1G+0X&Z zy&xV(zk~Vcg8)O0lusD)b{&U{I z`N!jLbKdx8fBn7ommV)*^kDHUM*Yg{$5L$s#{R~h1;+lyUIxbg#t$&Y@ES0~kJR&0#)j5isPSUI0VB{2>gT@-@QHiMj(0bfQiHqdrL;gfrL0<5U|n z`BWQ$p;MDjwGrbO)9j(zh;iuD?03=DMYRze*rNG?Y9q#ByXH5ljTpyTv1VZCgztdi z8!avtJziKp>N5V|a})fH&x7!J3O9}O+e3_>xK;GM7H%Av zzf;)V6dpEmhqxZC@Tj5N#l-IJ#1WIWiO261UbW9%6bRi$6^5=FGZo%cbem}It?*yrZz=5|ejBA^mi5{x_8wAr+J>DX>XDM)v&~L1zK{p$ zo$s|nG#$2s^nPD(r-+f?B?)`_MpAO=t-PG-|i4+s_!O_%RmpYWVPaqs@t0rkh;s%mAHMkx%MiJcA2sG zR{pM0wz=-3-KG!AIPNmznDdK0=GxbU?KWf4W4EW7195Zqm_D5M<8Cviw`zKtIrFjq z9y1oNcI`5AEGiL%<`is?vRed-z>ZrJNPT>*V{X|M3 zRV&7I^cCw@DtvOl5#jWWsuk&8jJtL|NErNiKOZ6tIWxu{CJgyCfAk>?y}fH3Aq;y$t|$yUe`+s(zpAXU zuz$`5g|V&+J_=tv9AJ(YK6lLI=e=~?lw;UWnDSpNv6^~&)wY@TyxnIr?JW4lX4>B` zpWR#+#(BNqvmYRb{R8>zH|S-5!XEZB>}3DLevXSCFJSl+H3~TUs(rLifuRfg7x;K5 zmH&U0zdgIZSnH)^R&+ZmLY^u-YxYr*_PIC7?^E}vSlxa<>0RRHC;D$!lM4qTgC&L)vv;k^Iv>nwurjPb}|pfab=z`HHk2ducB}AMPt|58h9l-35+{-ZvFz z-IODu#{zHSeAn4mJpb(gan|-dDn4s_kmSs`<|F(*?jz2!b-rTW%!9-^bndA5a+~6; z@bwX`Hyj|&u^-kI$&GxuTQG>-U#;57A-5CFm0|McHHz~h1dWyj(M|L z&9(pTf82~kpOpb-4!jy+HGR0K^>H(%_lg9VIpfgAYR2NtieqMO#Co1EPgYzXMc0N@6rI1@8NNb zFyw6YK28|&+if^O7c&uWy!esxCcohE z3#Ob?yTeTR3FE^}z5PmDH0}Ag_M%`ri`}~@*#3cO7tM8HoYxCJ`vG#;KakIUgI@M0 z>|sB{PWC_S=eX$c0){_Pqkt=i`q4fGhAz}7;G2t8{{L0Jr~F<6-+M}C)yW|urtDFY zKksMxU1>d(`~jsxgwFyszG8B)m>H?Ydp!;o6`lNvKlov=m>#BV_+ZF;1RiqVO4~k* z3Ksj9DNfSlv!d9lBea*}zCSD8Z#_yJ?{~psa{d64vvJTFF~RU9PJ8FG;&x^QO(Sik>%pm>PQC z)Ri{wg1Ppua-BD0(I#)0X|uEc1=ELBuF3Dh%Zy{egfMgMo3~vsW6^(7sF?$Ax`vxR zTvq#n8Pi9f&Y3xrwQjf>i+2;xo4Jv&Jj{%v)51_Qm)1|bVCF!DJm<}vLEgsyaFX^r z_IShJ6vp1~9H=mA!mCE7%vv$vzQU*>D-NEfanu%^z&QFzmnEOx6xrC$X-o zeHF$Y=W*yQCrv^)Eu@GwTSIUjpB7-oYxCJ`vG#;KakIUgI@M0 z>|sB{PWC_S=eX$c0)}3$Q9~^9xgy_NVH~=+MiqH~it_)j@=>D_J1d!}Q5DxJj2hMb zoRW_k6`!icQKRf_&yrr$s6i7#%o=5Fe41=Pjp|%Dm^i3W&p#>-YE*Z}GsHoSYLqX8 zIH*wpbI+MI%CGiW;-E&gDtnGNs8PdSD-LQ@e(zx7phi8Y7D^n{sHJT}Ne*h%u4dHHu?_8pSrFMzIf3 zqd1PJQM`84D2@ec6z2eH6#Ec0ieriz#W{l-#j!w*;@m)u;y9v4aW0`oaSotHan2xb zYlcVAzQ!J(7^5)uzFVDZG>)23`+&lz72CR8r*YJf3uSH)Ms1mv=O$s)sNV`l5=M=( z)r=yH8Wq|h+8mD@eaqyRUUZu<tr2HA-k zHEB*1aZsaDQWOX0s3eb@#6gXkzb2YEs8PFy-y%7vQJqRf5eGG@%+_1PL5(_RQykQ& zhexA{gBmq+&TZnLMzwgRIH*x=n%^c4YE($IJH$baVh(CluPt|ogBoSbRUFhP)`c1s zyx}f!P@|ZG8pSrFMm7B69&u2kSQly(uN^gtIjB)=Gint35H*T*p+@oAQKL8(s8MV) zY83krHHzbi8pUfzjpA6KMsW_HMzIf3qd2ChQJgcVQ5*}@D9#PkD2^j)6z39Z6z2eH z6z2@`c0`jHbB`bGr7-q>xTnIX38PCtHEYG~GYX@IM)BHFqc|3*QJe#)QS3w1D2^#=6z2?T6vqNJigN=sisOhH#kqtU#W{c) z#W{mM>XON-CZOjWv07pDqT_BWj2`uho~l-$cm4jO!suyNy`bs_dfk!7Rjoh|{7Rsz z59o~-k4&Mufu4Egx339f{F{=ggu$OyH;pjlOlb6$FyvRN@{Ta{c1ckf_5^KyPvfw2 zK#>oGVgJ+t3S(VorYMY_GmoPe&3yEzSq^&FEFV2>){9;@+k+lB+lk&d+mD_(uM6Y6 zUhvruki-6geD)jkvOi%D`x$n!|6xDJMUNLS^rA)qr}s*sJqQe4s8PT^#Z~_QRX%#= z%f={~=$QxlD2$$Y;u9qwJ@X|+UXxz*%zOQmOnT8X|F}ktqi5cuud)F>^Oto}h=ZQ_ z{8DddE_&vPWnR%E&@*RU=$Th&{*E~4nKK7HbG8{h^Y!Nx2R(Dvg`PRD9X)gApl8lD zqi4=OM9-Xcp=Zu(N6(yNfu1?rjGj6B5Iu8_BYNh%cJ$0S7U-FC4xnewK19!)V~Uo`z$dC9xO>pDZaQI%ck7x#82pa) z9Sro5Am_pfg(2Ugwj+&0Z=($g!=AA(6o#EaRh)y-_-dywmwk2Du|4?Mf2(_Gv=$k+Ql?Pc6ONE!Nx zIJkQ-HcD}D_h9s*55&RU1BXfJ#KGNzvh6cS4(=XYNdHJ2+&$PbJA*j5d(dKs;w+JO z4}RQ~P8{4lm|4%kfUj`(ASg_6aQ9$vVFv@B>*4N!$0EhS-2>*}?!hlXii5icrH?8O z?jEo%+&%DU>_~EO_kcOLd%!m1?m?e9ii5ictP6J!cved%!Wp-2=`U+&$n} z;O+tE2JRkk9C7!6a|w43I0ta|fO95fz%9`(o9h3ZXc8^fmr?lFDpBIl2!*GVjTD`p zC>&b%rVz_ik7(=A8{$PT)fcK2cwKC6rTRZBTU-}wJ3OHJ^V{2NB6{dU!qx9z6VDbt zGRIT*JSGgjYtR$IkkcSUy~l+7r$^QMO6V;#SG})^JcE=bP`C{GvPWnsS0y-ZSMV_qlKC9q9PLw8vq_1Jlk@=N<^Qf9Qh;=DIM> z>jj_v06FX*$Y;MnFZ&bru%BTk`ycjmT=aMW!=I>8z$arK&^`r*F6=wt@m{JQ@>ltL zqoPHJk4k3Efze`4T>aBulht=c&e54~!Be->C7v;ZY*6>?7j;bRkL< zd!cN|*b^xZ1wJ6#a-WJ4t-KZI^}tBsdrt)Q*)M%vKGy8h z9tnGC_KkOZ{le_EcF!Ga_ItM%i!=MrOWdBDecBD3V$Hs>bzYp=$KEvRx!La>|0LGz zKex{sZ}!7yTzzi#jlIQ7vya_w;&!SrGJmPAumM)M?d?G5fEn6c=5 zKgqPY*`g%VhhKRmm~kw5@|C%EkFiN+EQYs9FmvEjrDW5GYaNr!n7+ImZ{|$iEXigp z9NQ$Cxsm$gD>II{dnK5;wC%ejGY4wiOE7chSqTRt&pP$F|H%RwqUS+{r@j3o#-=Ge z=ha71;8%4Y;7XQ{Vpa)t2Vi%D58^uSAT;j#N13?5%w-_c-xeycoRXUch2+sR=0GdDOHtk?gAlfm|6t(wJPJJ)o` zVzB)Ue#m0*x-ib`1)u!@Ida{!UdU&^K`;9g_OPE}C;K1vb6oUz0Yfj&QNZ(lyF_OI zVCcd*3i#`<)#uuOmG84ZL*!egWPV*QLo^RlcvZy=@tea%l0WiBy2w-KGU?q^FJ0W4 zr^bhDPZx6zsqwMy=^|>9vf;C-GOs#ZqPd0FrHjuRT%oz2>U|QwS;FZ|@;28e(d)a* z#PRn}7uRiyv+IkG;_A;AiPQV_M=`Yb72BZ$u9BRUlRt>s4=)jCOT$khW6)LN z7$Y-;_guws@9{yLo_2*elP-P|{lAMKPUrXxQSq?i%&~nC)pJG==b%@**qf+0Rb3nm z=Cs}VQ8XHKjW}1lGsN~b*GNv%bO(cVZN2|V?DC}ttC=yK+|R+_oXIiC z$>3PbFX3o#Zp^IcWN;im+v#9%E_L4IXmAc}eC%Lw&fwX~_oHwQ;d?kZpYZ)0oLl(b z4$doWu8gaQ@-@KR6fhy&#;I_`VR%QGAaG<9xpee7<)CIeZ@p^7)<;^z!{B z*u(dlU?<;qg8h6C3hUzgQ8>tQyzdSD87?}a}?io!8wZW(%>A$cYAP-;=3_8NAaB;oTK=T z5YAD2uLkERzT1Oy6yG(%Ig0P(;2gzwgm8}HJ4-l6@!cMrqxh~7&QW~#3Fj!jBZPAl z-&w*ria9t(@m(XFqxkL<&QYuj=P16jgmV;gaE@Y|agO4sx(pNI^F z(HHu5&k5qAUo`qRD`E7Jz8GX9jQ&!wpY4RvkLou^5Jo?0q=#XSPdgoG@=x9hA`CgU zhwAPq%;^M$9}(9Q31@gMQTegpbeiX+M z{U}~L`cWJU^rJWj(2rstq94UEML&vj2K^|G1^Q8(8|X)I9MO;BTtYvJa{&D)&Y6u( zF5BDXnP-eGbjJ9?xMV;7v%*_kFWRS`RyZj1f_-PP`NZ*2p$Iq|!H2HlxZ8PNzU%APY|LoWG zrryvpYfO6*_Pd#Oj;yiLv_Hvvg}E;1#Tu{WI%`aAeT=Xz{EPvcG4A1Z#(4BHgz%Ei zXN~?ouDw*{=SLA@QEm{FnslM#%$ul zHs?fz;aeVu&zX;Pu^hyRLpm#+!7JGsp>;M=A7j@z5RRGcd<4%r>o zC{AwgQ}%<7^NI5?r=NXVzWEfF`&;+hn=DeCxUF`3U?0V~v+kh%cu~bU)Y;qKa*X06 z74f&PU8OkhTI{vgb5NYS9((Ku+AGfU#|P|VwkXcVL!S1=SClVeC=tXVfUtgj{#$EVUO`R_89ZA$ABRRdkh%zvB!X+ z7kdmC_F#_z!%plmVAzj628?x~b})us)F_OjPGR2xLlut zi5vw7djfj{9PCl-RdA5k$Zv44x3I^+!CuFn2M2osdjlNoQS4Q4P%}_Fz`@?a9s>t^ z9eW-e)E?9+aIi)7+)p!T2!frDCT>XJ1BbqXBRFy^49vdySH zs8ise7P2nXW?nmL7;{il*=E#u_91E^>q2ejwc}aAu|Q2_n^EK0hj`9#98sHj?RZvj zEbxrt96*g{AL5zAF~u{Da|X`}js>1woEvz~a2)Zh<6OcsigN(ZG|ri4E0!25Zp{=| z*9c>?-zX!l{X)VkhqpDlHP}SBQJZSU4<(NiZumnk!^rxOF#g8BF&D3c2aI``4-9#b z3k*Hb$K!KPZZY|bhaV&iIeu>hVaWeFK8!H*?1+jY3_Vl2Jtho2&Us!EhMsF7iG-nN zX8%`&p@+wzhxyRMa-fIh<8RiB*V!J-V>=;_?S~#-7sh$L;Ikhfhy4Tj>^JCPe?kxY z8G6|N(8F=j;{`11saX4iLHZfLOB-ce?7xJ@>n64}s#e}g_+9?$Mwg3L!dd#{HX?q0 zOc;OT-;jgX!2`xT%m;=%$OVQT=;rZ=ZCgx!{R#&OLk{8$4&;ZA3L^|XTbf1@hMsAA z9ubC~1)XEnxYYBxQzBvL5gU>SLl2Kb5A&giBLp{)8U(GxV_kp@-vgd*ULIds;qP*NyTEM41Ko$-coS=83sy^ATQd znJe<-SNLhy*`nRhyfp5)eXginD-X?`kg!0k*q@hhTIcy9-%~XX{<@#zDF$1oOc62O zNrZ=={#E1{^_uXBo@2zmO>YTz?KV;zDfEf(^zacP{jLM)0^VTBLKqy^RoMt*ZqxA3 z2t(%TM>z>YSNXHK3ICbRu>bDOM9RIyGBbsvyzh-X8Jca1NS61yfl~`j5Jj%PBiwNC zc+utBC&J%m8z%;(JJ5Q8>y^qv7@U`1Wh0EaOTYSzFl27Yos%$ht+VDLtowh=lBJ?l zQhpl$BG*dMwtPXtIUlbUGqM#Toa5bk;kiNKj&(MRdsh^$GHRRf@>4ii{w|_mSA`vC zdx-(RDmg{U?h`k97a%#^dmR*>X)5lK1${(~-YRx_4uq{;EDBUDNItALXSujPqY&XP zmsg1iGYS*FF?hYmTDAyb_s=(rCIb~-7`;slYoc(68J=Q*P4RzvvPT?=RC1zH_KP3g zm3)U)hsC)91xQZMZN6ec(?9YpDA14c0r8sD`3U)6kKL|c7Kv@L2aR~u{$-i4WP3`u z-@KJFKjpnEIo@mgDiQEJnsB_&YEfeFH4|Hc!%fb%Ci4H+Nj~P*dLKj>GD}vl5r(dS zyYlz2NRFP{Q;RPUbH8~(b{+{`EWYpcgmB~C%Y^OKJ;F~mtPn-2MH61OZl&l_{+fv$ zvtKkhO*29WWA5hqrwBu4mMeC`&~-KW7-7T>@q<0^8GMI*pC$RVXj1bkVf>AMV_f&G z9{0s}lf}ZwOC$$>O0F#P;yIgsPxVzLu^>P!D+gt6Dk6mTPq zJ=pZZ8p7C{GtU1`7<)D$d9#UE*Vt}y9J_lG#@r^|_7H~5fqC~6hORCn4iVPp6h^gnfm$W1nHa0b~DR9|B`vVt)c-zhd74V;^Hb17m+rar}*cgF|u8%)J~(=Ze%V^GOc=#=jvG z&mWeF=Mw9}^9s)`aPS<%^9)$GP4^p~S9oqgFP>v~o&h88SSIojc?mhlQ{*c!@)vmw zjJ(Dk07kxJ4*+8yFvk914)zVt#eQO$*k`Qk&wPkl$ZJPFA}?Vx@)Y?BjQm9&10%1o z2Y`|9*aN`W2aK^ln1g-8bFrUTCiWTY(*2KT8js^y$9y~kSq`3!EFaHI){AE;V?1M- zgJ&<##WR^@;#tkQ@C;`^=sAGrKl>2p0`@J=3+!{8BRCc~UvP|Y?qH1b2y<{w;kh`! zuuPn5SQpMaoHKg<=@yx_?6d2D^#(2gu2hU!f zi)S*+#Iu@peN%mku`B17fspff_!Q&Ko|=JJW7|*DjeW-zuD5o!G09Wm!Heb^uYOW^ zOpW=5Pfmqz?^|FrSyqGQws^nLC>&p%@X|tyjj;_BF8p$_(Pm^d8qYdwiBWn@Rl)<$ zEis}GRUuqGc!}Y4t}@}Vlb0AlPbv|9&}gY~GprKX`L*K=W69^r<}H!4jfkuY$Arq> zLP$;GBrlt9lpmzs@YC^qpU;j#UEjq4fdgo{1fYqVYONNZW%e1}nJ zL{`G14{S6>#C}FNt>+rUnvt9En(-@){woR)UR`>rF?L*0!kvCyZ0uNCitw!Ii;bH8 zWeMwf<*{^>5q(0%;$GB1!{M;Pwd(dT>b_7|&%H99ql{`jR9>Zo4K!-CQ#dufyYcxV zg`2f{WBMPM*Q>8xk5S=)#f@L@)gs&O)GBWDn_i22sLRyt8R6|1cq=51;@B>a6JhKT zU00{5G-Lii<>wx~-WzQL-ji=*4}UcLw!I@98J=#qR(MOeYiEbRah*~L=gsFBIKR$o z!cm(Y0~4ZN5uTXn82Ic5^`2K>U@0Mf5jnUt5d6661!cy?-yqI}txd#YmKQG<@2ANq&xO zmfaYgsBpfZ+{W;}%KzEM7c^!qQ&^9S9N^{zz2$Ozl&9(lfDWnA*Q# z`w~Q@-D+R2f14_9TUA~;bapU~Y*+PR$-!(!!44`1ru>rIa55C$Frc8(IzeH?9q;|I zcEp|g0D2DSxdFeqPr6I7`!gTHpWr}d%$B$EvzIRkH|p}vSXBK>nyc$d8|N7KVC5JZ zFVZr@IOx-Xux?vHnLqa6F(jwLf^?%@nT~{Ydn&fOCp@O!rn$jg?uaAHq6zOR5iKSh zk0d-d;JUb+=O*DF<^9AZ8?F;x_gen`jsDjNUwUy$>>Cq7IJ~z_v#Q|Um{95D;soQmGA#h ztnPiA)|KA!zL?TBnsBq5x5a~Ak%X(&h!hLf+#u{P??uKrT_+smbwQLo9zpm{Wx3bz=xR$PlzGEbaZ zF2>YUx@H$!Bz#UP8*-S6@u*G-!dEB1HJX?Cf^dhg-x_(oDo40Qv$w{?)|CkV=<(K=*0CDl zwTttJjr}eVPWCG(R)=38+s6EqTlA?PPIzOv&qP!EMZ%lYvx*B{FB6_yFq?2lQocRe z`!gXHDIeB7lUwA%&rO;;sA(mUVpp-g*{8PfcT>IJ8KYdp zp7JUm7M5%yri@c~ty2#XJw@SpA%ny+i^6TQjS+*6tGOYAr;3ItN~SnFS6oR^y7V~e zIXUlGHqqv>>RTojaTGI`UL-#ZS^mj>srhBX-Tgn=n>(qT59;D5j@net-!GY6)E=Pn zd~LqGqVMAy#Gm`2sJP^!_Ta*8<;2hZRWEes?k~lT=4zjIJ?1Qe9xB{s+;^g6!&@}h zbz~3m<+lo_Hy$GVKPt|uIpf5EF$&kXJVSiDMagu3I$!uKRJtAye`Qpk{ff@9jlz?R zMGIB`P0yc_(>@t-rBwg$O4D@Xbdc(s&A60q46d&FX*bGe7(OGjl0AJJW*9+R9SQ%G zFT)tPUG?bdd#4)(8os47>dnv6jZ!sJ2!CGhlhM&b-s6|g)A6-F8Y_kTzZ??pcl=<4 zZFxrc{PB0j=iOrn2mJ8XNPnk#)G4o0jpz*ucV7O+*i-8Xan{Ob>3yr>SBgtEw$^@5 z<7dvjGG0wry(xWf*0?M8OGVY6j9K-`nC+zcmiG&!8vzHhQ|>kDmu?KKo0agvvFXOj zJ&uI;wo5lwH%=!XwoLeBa~uOXT$R~RS$N&$9p5A zXDsnuCciV9ws}tYjODG-FaI;b%ig3KBH$_E9=>mk{7uyO!^y9WCc71XW7ia8(Oo5{ zO}k{{Qk0Uf@6&lzi;6~LLn$s-a(^yb^a&xHk)w<#QR}RUgVRo#oGllE2xG2SfI%2C zTZh^S>wCX%WGS)XR4DnRda?3i?}`w@&6-sbd7GRy@s+2iOiqJML4+~)yCDW)$n4bH zPPom?JI0fRDYW*=&i9NC8Opbl>pw6q*Uq5vuZKJ`@=Q^&xZ(T6xVJ{$y_V0`2l<~F zS??-5bmR-8WiN&2`MoqYWL5msYw^aXyQ;tK9+YTo=%D)Ef3`2Y3f?uIjCn=5G{pa& zF@0GY;lya zS;a3pI^HN*_XEv+>Y8W_N_s;WKCjT{i0SjsFC3vY4xf-)bgJz~cu1YkL=E4ggokC% zCRVi!Fmd$VVTMpC@Cm%V8muXBUerTcSv#4V%WNwwdP&W$p5_P9qJ zJqOA(zh(4&uKK#Y-b5Nz+#Zlj-9O0HGoucZUgY_uUIz&y&v(_>Z{p5x_L`i^p({<5}^OG~O;G!Wi!xO4yqHx)HkS3gJJCOBauuhGQGm%Pmpp zhB1AH>N(5{yJqy?t9qf&Zble2*Sk}UzH^B%qI0O8YSB+ujj88UKej}f2*YXhG2#r| z7GadFpnCXiCSNmhH$6w=>%FcUKORuMZutCAuMMWpz0PeQ{~%YRzuZI^c^+_hGhyU; z$>v*4JoL7^$vHn}J7LWAO4>nK_qiTlTWf0pE!4u^QFgj z!kC+-#ZJOF2SEqw51o(XdhjgM{rPirr15Bs`g}G~e&*Zbz*ORRY>GC%X*Zg1p2D|` zsYM17_HTL1X#Go9!gap9W#sp1N%-pv(Z;FP4GAxjXP@M?H3+|M5M>lhDnqzh!ARq> zUlGDHPuwt$R95x`HMnlPT9l2(V>Uz>f!Q4ipMG-1I4aLEu=&uJmyK@w6s|t~qH(64 z;w-xpX2f1nbM?Hf&@9q8Ghz;{y;Q9zW73RCgv;NHGVbM7J=j{`M;oth^{4S1Goy`3 zu3ZTa8y;=6bZbTUS?*|K_m|FuD~^jYe8<-!ykKLbalx+w;rdH%8kL%qBploJhT+y* z`P?t&nlaZUH;o?{7GcaN{2AfX*RL3X@(hZ&^lft47?md*;jD)*8Wmj?r(ErDD3>o*0YQ5=K3#=)Bs*Pam!{IUUw5Cycp2_FqaEGKX|qOc>8k&Ov3z8bh}Dy<89Ikfu>!l(mtde0_|ICk|I>3j(?7be@NC2!_yo^P z=mW;H6#9VijAe{xFLUrr=DB*T@jS;m5mP+p;Ui!?|KTHGoC_G^yucisBY3Xvf5gQ1 z@&sBJVioE&jxb_4zWpc@hd=nqB%jWL})xmoR+8F-3ljo-mQ(g1lRu zYdm4(W53a(O#CqLCzEri{1C#Jd--^O!jO5#qYq&`SK0q~-f|A(In23@=QHO#p4*J^ zJZBD`^E~&@VoGO(%=qH$z&VUF1?M)-8l3YugD}R~ggH2~@Lc$6kylI8SCbaDqIDrY zcfW5#7;)RstvzAHv;VYCCVqXei^(yrbtjCu6C-;O)_tYN1vypzz;~nkM1ixGdYLxEalwBGnR86&tArOCNl@m zYM!gd8qayoVLbmiw{b4uoX2^AG0qXp!TEyc>i$Pe&RzJH)`eKz+v!ReF>eocW?Q zVa$#3t3entlijNj#&dxEkLLsDFrFKn+jyRE&f_`57|$Q(;JL(e|175TOv{Wfo^_nV zcm{HA|#Gx)7g~c16@0W&R)NRGcv4IbmWc z6X)_SZE_+msU8~UE{~{4W6- zNy(B?lH`nl89`7`f*>FYD6m&;k|;=yl5@^EBX51(`#0}A=N{j<;~gE>d&m33!DsK9 z)zwwKX7}u_p7UN8Bl_Cm6PX;-2Zz0oE#NDw?h9nbmCNIpYoB;Kzhmxg^1mC$;`|f# z6=Q|^Fk^`NHe-wWJY$ZSu}CtEQMxu9YsNSAVa7f6ZN@|OdB#aGQ_K#xf#xk<$H-UHEZbwtN^xXR-`mkF5-AMOaQee|<^j>EnR$AvyM zu9|;Fqpw|BwZhpzAAER%&&z@{4fpw4$TVuW)5&n{!oxnli+h{=@5Zq>|Ac+TSfM`5 z7^1$-*rGnqm?LH^k_=;%t_{bU@lAc0aZi1l@lbu9aZ=3qDH+C9T^sg4F*(xjJJ&{H zmA<6UBO->)x=(cFaJI=~0+}}Fe7+Ocj{VH<+H@Bq z`eS9A7;ufoV;m#1yTB;NT$|_lL5|Vc^_d=?qvL@5&-kD|%($Vx&3K|d&p0Dy{E-af zlCJ%un7T17F20O)>cfnI>f4Ns>hp}5V#ZR*FvjXy=chQGv`KBreYIVra$`Tgy*jUH znMTz^YmBu^x^UTVjmH_sH| zKkgfp@i!P*u7S~kE*Ra^0aGV+!`OmNFg9W<%s8xAxbZnIM&Uld7^vSSW21hvjG6i^ zGnR@OVBR+(FldeHCt3xGu&J z^#R5f^$o@x^%=$@F=Lcu7`t?B*jJ2u>I002>Klxc>NAX=V#Za;Fy89g4^E}G_UB8) zmfjgXZ`Crb)i_cjcKh<>Hv3FU+q1kxY>Ix%ZS}xpHu~KXv7CcjoF+#^^03PJrt*MN z`JJB2OMY1hBcJW*WQ&%qFW`87`!0*>H7n$JRR2wjlJ70-xMQ&bG0&DS>bOa=_A$%q z7jyi}GhfEEe!95hIbUv!iFe!c-V_NU`CI;nJ+dKeTlGlhg;@_2@a_6I)1m=`3OUYL zecGbvxdz8;QlyXR*QKcA&u+aIQ{(Gmju)pHA9G?-amODtTpP3VRqvlhSK>wb{_2_b zM&IKUgWqT`Onbv^5Br3_^Z&@h$RWQe$LyHG&s=j{wB*Q`8xL2DezSVHEg0P(X2{ZU zjt9)kA5;J4amW12|0BcSk%PI8>tXbv7Y^G-{jzz>g>PbBt^Ml)>`8TEXw2E4S1$Cn z)sD%YsL>+Wre%n^XW=r({LBAS&fllsTiY?$aXsbeLoZDH)m~Wb4Yxh)6Z#bK<67eB zVi~ocI1_K$Lj36mF#Ur50n=aTH!%H({shy%=w~qfj{fK5qy3S735RV9+f1B^H}(*J z`T#pk)sAUn@eV5;)AqinmN~{J54MZ(@=;$+DEqx*eAun;G{^Y%&Wz6-f`0D=h^Bm*D8)>II#6YyryajOGI4Cr!M7d1bSPnL!4*l} zI|N!zPY|29X7s)s?GJ@c#E(td_ddtuM^P{3@RCMd9V@pAd%`kdJIV8kIrnKK`rbhM z@p3zR;Kb*SEAFUe4^Eroc-zX77W>6o$K~dyw^kP}JLX^hpKJL$axm9%J&Zo|!qh{3 zD)0Qo*g(E)i5ZU3(`^1i$LKG=_!r02(`CiU3P0q?_7M!&Ta5{s&jfiYmwoX-P&E3R4-Vy zN>>~|G5Hm1zr*v7kGx_N$6a;To=^O&O?c{x|~#(ovB+>%iH{pD=+_MQ!AhUw&VGinplG4KIgV#+9q~;(G6EV^5;gD zed=|`{qntLlfJv=_>-~?Y{%iNj>jjcXL}#>{6{t)S^An4ts2keB=^|X$Z8F|>+CQ8 zUgPL{8GN4hh!c&iO5HoIe9OMZwxN>G<$kquW9yUimMec{S|eMS?xy2I{a&*H*={(F zP1(>YSH14|p4#=TSu{78XS$3HUbT+5yx+q9fB4ZS?2D&;EHdA%VIwPhUa`2EZL9D3 z`;V$x_t~DOk9x!|m-2oN$F5n=C+zMZAIII7YS{ixp8K`0W`#fXyeWQFn}6B!7xu6% z8suZW|7JsLaxBxqbBAO4+^ZO^U^{w`b1dd;wSo*JKv!WZ%yYlB(=eOT;UvxbDw}N);Dese04;Qh6)xA#+oGE6dlleZseM?Cj z@V@6|d&^kC-JZu^EpHi*dQO(KlBN3A^R}CnZAjd2C+z2N?5_66ZR;lbob%Q{<*}8; zFF5;ijL2slKE3F8#j*l+WydAQ=^7NauaEmakm9joR@r}fCUhvm`QNDp)IGf7(GxA|W`=W#A>*HRtF-KCm@?zB+ z*~B`Y7Y}J<%NL|@<=dJ!vLd-WzjWX=i#IH}EB~Xu)FWPfYy530*B`Dw&>;E_6VLGq zG_)?uQo8aIF%7NmBc5AcZ)m&br*P#-b~UsgihJJNtf5Vr>icIn?#asJvXMtlJ74`) zGpB9Yb;@zlRQK7vCr>)A+B>_A%j|jhtgN=O^$AxV?lY-p=Cr- z5p&ep@LtvExyVdMot|DdGT2YQd%kyJW~+Vh*ng@kY=5Sl8Eo#9V@}V|gPCm8@Z*m2 z<;!7@p2^|tNz^B&#iqE=ak`_qEq+?h?>>>wPTlY_yFVyk_pI@pa6uuPGuU&QuZ!5M zVxGfo47X*&=p0sHWDeJ^J2P@x_i3KeoAKPr+AJTk;F>w@*MW< zJt^+7V%?57e>Rzt+P+EcIdy@Qws*&2SKf7eGJ9#S=gPT~*tu+8=B?*b+3!DjKg>v! z%91woHiz53E?Z{n_Jl8gV?;Wu{eb6iEGD1IWK(B&J;%nSvz!w=moAmWRvz;DeSU>yX!Tu5A+QzRz>@->yWyE}PZ$fhrZR zMk2p>j=Xp+a;vUC>(r?5jmVUPo^wsT6)Dri_va7n_eg_{o{N=;Z`DhCn`@U%XkB~8 zwWV=lOYoiN(KC|Tu=SoR#7kk1Zu9&{K78Wpb!Qu6%FU;5M3(=U)%B(QHE%{bJ>bte zwK{z((qNwFtp$FMyjsBblZU%R-%C8qbH;QD?4iA$H|bE_{sMEw>GKq?~yzY_}|)yG`AzK z=JfZIX7z4HR%G$_nd8shh)m1l??tq6cNu?=3dc7xG@(86u8--$4)JYKF8|wqKKI>7 z>OG!s9=jFEwb+4HB)yYhI`msz4Se(Wn7eNRyDt$yrVp5rGwFu{*~ zlasBmhpPIqZ+EJn?WZ3-|B&YwI}^{3WeKXRw9#2TZ)x_EHEHAh)2LZ=?W36Y&w{AU z-(>Xn@J7EawNcTy;GYq%EVa2$cwZ$>wbWYl@$-k|*OplO#b=#N#jH#1#ozs0VtB`; zHl^$ZSKi{zQmg)gpG$nbV3|#R#m^;HOjvH|EBU#^l_@{ji8G#CtXg5KI{SG-kGntH zq7|O8zxDyoXDV#64Au5J{ka!xvJZFcb-oJ6W!v~wR`a<3T{n1ioptH$-{lf+`xix5 zS<4!}U&Z@nt-ZJZfYW(r$BW8Dw=K0Lkr8C$)|_wBHM#@sq)AN}lOSG>dt z%lEeDYtNjt$FBIe|M>hVn^(j0srye`-`2jLB)xRnPPX;^XKKGQR`~_rufE%R#`+iV z^VMES&sv+)z8~(ndB)Do@%^*@;9d6fAn)^@vv*mSr@XJizReyzi}PVGU;bOyXkKgF zxw&vm(?`#~+?wb0OnGCcU7hWDVg55VYMTFDcR78=M$hoSkrHRlScL@MhT9j;Sj?-Q z!?uNeHMqbT8<5QV?YE+5?8R1|2cAA)O=|gmUN7+hTRq12nL&y6+nQvaTb$o(m%j4$ z>{-9ZmbUSnamH?&(8Ti}`62fk2dv6|-)9zmvfu7|#B;0f_F2bR@00zD_FD6}{`Tm? zJyyA_FTeEtZYx&AbJ!1U)19&5@A>=Q?DePZ`@a5uSii|>`>v0_PmW%7%6|RGj|(3~ z-$V8J&wjiJ`*7Q~GtqA}`1?}@?5mg?Gbx5i$Bj5w&y^TYtcOnucvMI>y~|j=M95zShAX)pYMOu zzWdd;H}d)|i{$nEUZLA|`(^Kw`&ZnyC*C~Zd{X3rJNA6r{f;yDy<0%pLnU zdY@;`6ZXTV*4HfKFyHo*UtPDFjXh7=7(Kg`(DU=BZra2yK6b~B-?D)Ve0;MnziqX* z9CU4;)%lK%Ugz)m!>`=2pJwlO<+p15Zl&MZ=lI7)zdIY;9{SCL*0KE-SN`$YgO>l} zt&WG?bI9^6+~)XNqeE6`%WsYk?>uD1_icAvz4u`oxp{}Zq;et7928#!c)Yj3$9 z4%y0)TOAMFa>#mpu+4G%?1!z?Xn$_5%&^1u={wt9d7A7;Z1pStoE?5k8gGFs5Bo6O z78n`YRsQFL)ZolpE=c;-= zf6c}&@H`;HRr_(3=gfOA+jsYP`NtPrvbRQf{_2~H*71I?KjD%KHaV5A_sQGmZ9`IT zPl4v=?aSQW&Z?KAzlj8^oegPf9kNAP);J!u{h+maVy)xH#~rk}gVs6D^3g%NzRI7U z{i8m!{^P?|v)gJHm!a_vTiXt6e2hLlWV3p&b$qPxA=@)w&RB?@xgB{sdU>Pk{CQ1X%A+ zfc5?aSnp4O_5K7{drAK{8?^U?yxvU#|B&O{|?sv9jyI3So?Rd_U~Zr-@)3y zgSCGLYyS=ow)k9|t9R+ZdY2BYcj>@- zmkz9V>A-rI4y_4cIllz*r|6A!FmS~talK>dIu4#cM!pP z2NA4y5W#u}5v+F*!FmS~talK>+SA8Q?e$Y0_N{UZC|8aFtQ-SaIR-HK7~~kh$}xbI zV*o4101n4mc?H-*?gV)Su<{CEssMJh0xG1Bd&P z-t&VVz2^tkdv##tY>3J0fWy93jtBbnPMCkLH>^|dia`&)BCkeFUJciVbt-3ua^=jx z%9(+cGXpDU23F1ttehDqAD1%&huf$;8SGJ>46HmESa~wA@?>CQN}dd?JQ-MdGBEjR zw2gX|t48^kEi+jA=sRuTq(?GZ`{SO&z6$$x*DD!pO7uNE=;^yWqn#M&nH;3{=?6?k z&mZ|#IZIrtoHyC?uWVBu8ajy;*Tc%i;@YrI<$zJH957fpV6bw)VC8_p$^nCw0|qMx z3=X$Zd0*J0yf2u1F7moy<$b}*`+}AC1uO3hR^As(8}TFc(sr0~<>SHRLlJLS`FODM z@nGfS!Q@-fpJ3(V!OF+;GCnU+thgxu5POt=2rK^(R{kNZ{6kpzhp_SwVdWpf;h6qW z+rxc8xg6L@-T`?6u<|!xg4LrYbt#431cHw|PzGCgcfu0=Gh6egG%^V)o+u^x) z1AE#G9BHz1%A=!9_P^F|RM0NU)n4S~2lU84=$GH9SN_Bv`58Oqf9zLW!tsLd6uaU2 zLzpu?`Ig1D^X0AkcCcIJZ#tQD8QR$FZnqpiRHC`XD}Bdtii=HbY^}SF-x%`+7EDRzk-KPQL2eOaGyK=+{XC`OevrIY!U0uE`yvzsk2M98+(~ z*p!a3Xa3k!j3|IE)l)2`G@JZH?-FDO5CXFwpIIr?r)>FHl+SfD@qV!v0rgv&ern7 zoUX6F(jtw0KhyIgNmAJAYjNc#6Iden3MU#~}g*qq0e zzjWntWX{gKj)#xG7`b{epX17#F1YtP@_V5?LxqBYe7#zJzJZ<>Uo7m((Vwtd5y#Y9 zI&D$MuSD(ne7?_2oyN*S60blpo!YJ&<2}I#-})#8>$O{Z+OX zG}U{pV-b@*-5V4$*|~3Mag+T?&lWe{T}itrS9_6{AJ8NJpkIEYUilMyD#@>o-nUdR; zH_LQ2^7EuTj{7CK7#Xr4uj3iR&PBdBkk9e`bI-as^1GwF?c)Ul`2p<79cE z`@g?4IA|B;YA^Eg1A62i^viG5D}Q2-{EVIQKlUpwv`g^{_s_Rx^ftx!R!rX@?qj0g zP*Z={^3Z^wpLD4{Fz7$MvJ49PRj2ubg8uel#=${9yja1vk-b04)o+nke@2h`Ir`QA zsaL-X?9uN9JM}xle*M0ln_t)Nj_`eZ?Do3W>zwZo?|<{WeU;t!fyzUlvE{FN-r4bS zTQuGC#4L|nqbGg;FaFl^_Voga&K1=TV zVZ!qjZ1NYLBZVv48%4bhuf&6IOJpWH~N+ zuCen0d#sGX^=Qn!4 zZX>7oHiqNdIGTSxakKaByl)y>jtQO@Y;R;EYI#2Ya}#^&n2$?Li)Pl~P0!0_ziv$r z`8dA(!5h}Dmgh*y=63O0AL~se%h-$>{+{;Lhh;4`a~^kZ4Eua}?fWgy1b=@nw6KDG z+}z*8@9kFJ%2)FD`EdVPyR^JD{LRwPuZDNFWWRVDT9@fyLyP&gSIGOO4V~lp{SK||hv$78=a*<{ ziPOZjy=8M-wa0V3VsF^Si1$zWD`hQPZJ(EW_2V+ucAe)%qe@$sS97{H4mn!N+MMxx zX;LYBa|ieMhlWp@ReD;R`#e9B z`W@T4((9Q#uD5;H#B;MJ>BG`(z9C(i{k^tMzPJQv&8$A(PwzA8VyuT7243F%9pJxI@_u`sh!T*GdftU z@}4JEZ)Yh=doFmejpcsK^R`b~*{x2VzwOw<>M!s-x!)W1+P%JA;Wmcba&T-XJNjK} z*OvLcqwgde<9XDp?d+!yJvV-!t$jMx^PS?Yqj|rcXI5)zJyLt0{4%7uMPB>Q{<+m= zpp{*c&gs9_YoJvv>$yq8fp&JX|Mo%tGy|<+j=1k2ydV8`?)d1L#^|{DRP_6d#fx|@ zoV&kGS>g5HcYpL7nq55KDi{6k>I0rXsn*+G%HX+Rs$SM2spoKvzAQ7yzFwEk`F2{3 zK{l(D=g0Fz-}&>t|4zh^mC^ak^|VeV-opd!@#q;#`pJs^(K*j?@6X4+=x<}YdCoVs zpXJKwIcc}P_V_OE|K&q_TY~RBzZ&hgL%#AHj&IoiHGl7F4SIW-8wtAG?6Lp(+Hku* zo7dF_?f0?Rzq^}dyW?5&)nr|MHs;~Xb70MHVabV9n=Y>W+|6x5Bz$=7BowD8R zu^&9=e)lcAG0^jw)LkuIbUu%K{GU48C+GZqpy`56mf}6nr7(4(VGi+<+_ z`Jd}_bkDpnF<8HUr_Ipt)t(AjEk0u`w*#F6W z1A=x@uJ$4?KcGkcLBIS)z49ma$j{g*|6{-6qH|cU%v)tThXv~#7OZnyu+FK$I;RHf zoEofiYOv0!!8)e~>l_@cvwpD7Il}Sc&N;$5=LqYZBdl|du+BNcI+F|QOfIZ5xvr5`JGr6$Ns&dkv(m86O2axU4eP8ltn;?8&Wgf1dkgFAEv&P*u+HAXI(rN2>@BRbx3JFM z!a92k>+CJ8v$wF$tHL_33hTTotn;d{&U?Z-Hwx?QC#ntIxvxKnD$H6)u2kU$stn+cO&d0$z9|!Av9IUfxV$LeUIu8izJRq#|fUwR3 z!a5HK>pUQ=^MJ6<1Hw8F=;SZ@^MJ6PXJI|>!+PF_^}G-3c^}sEK74Q7^FFNSeOT)W zu%4G;Jukz0UWWC&4C{Fr*7Gu~=Ve&WlCYjhVLeyEdai`^EC%aY4A!$4tYzM`C^A4=%7g*0Pu%1I9s+AU1lD>8tTi!MYhtk0#9*z7!CDi8wN?phtrFH+r7MqHtAw>y z32Utq)>zT0DGhwY~ z!a9!w>x>VqGd{4+BEdSd1MAEVtTQ{X&g{TCvjgkQ4y-dfu+Hqjnd8pvz&dXt=8Orf zb04tIeZV^R0qfictaBf*&V9gH-}dJ|V4eGbb?yV!xer+9K46{ufOYNz*0~Q@=RRPa zM}Tz(0oEA=SZ5Gmop*o-#GQA5b>0Eic?URm+*un~XKi4ewSjfk2G*G%SZ9J@oe6?< zCJ5G zo)^}6URdXOVV&oNb^aRG`D<9`uVJ0PhIRfL*7<8#=dWR%zlL@G8rJ!1Sm&={oxg^4 z{u^m`*7;mm=W}75&xLh97uK0mSZ6k2oj-+j z{uI_(PFQC-VV&iKb(Ry>SxZ=FFkzi7g>|+R*4a{6XG>w7Ert1pIp5@l`TjQF;fDDx zH{a)m`OY)noQC=SIp0Bt`7S!&M~C@dI^Ru)`Hni@Q-}G!I^S7`3r4@Y&iB`0zQ@jY z*;k)m!zW)vn*>f>6=(lwdn1A_ySl@+*^<8*a z--UqKL zlN#1HsbPJS+R4X#lN#1HsbPIf9oDzhVSP&-*0#k>`Hnhvz@dN!5#t-yYG5uIF^lzAJ>Gv=?`8~kY z#qR_T&(HsgdARhmek=X3=J~MZ`LO2su;%%&=J~MZ`S720-ww|Kq!axb3t)`}u*L#d zV*#wO0G3WTJP-MI<`~k0PU(R)SAjKGfi+iwHCKVdy77ovE|EzhebfRB6Va<(U&5dErjbY7=Va<)< ze`jtSe&&)MbZU+bYmNn*U>TVSoXz*=vCwcY}2 zy#>~K3mjf=`8%wu$R2EyJ+Rh!V6F4OTIYea&I4pZa5d0?&cz<>36 zi}X{M)^lL3=fGOefwi6kYdr_ndJe4h95}q5^LJRQkv-TZdtj{{!CE_V<$pn*o7Rrd zA6`59E7pj@Yp1G4CK`32R>x z*1jaHeMvaHFZu862}%z-r3cpDBCNedSbK}G_7>sr-r~QrhbTShlpa`nk+Ak6VeLi2 z+KYt4dy#+jo}=obUeyI_e-qaJCanEUSo@o>_BUbeZ^GK&gjr9}8p40qvwV16QTAY) z?18nm0Bdal*4hHBwFNP23zA`N0oK|AthEJLYYVXK5z9Ye+qB+-jMiIVt+&8hZ-KSm zB4)isGOV}2T+4b3to0UH>n$)gu>KQf<^Zw>mOZfSfn^UYd&K{*>p$3|wK9D8cUTj{ z9{eMFU}DW09ZVl!jSkit9jrAvF>7>^VT}&vTGr@bbh1VVQx|J=@IS{${*kYc(Yhk6 zbwwCi2=PXyMU2&_F3SbHL{ z_C#RqiNN6)$sX^|RPMKpjP`M0?c>1O_X#uCN* z!G75TYmXJy9xJRpR#-NZqDc9aQti5$ud+}lBTFJwbhyM;a1F`{|mA3#ZZvj@` z0<63RSa}Pu@)ls_Ex^iKfR(oZhkYd*@JTqQLX5m*;BXGf|HNDo*-u+!Kdf9ASh+5+ za$R8My1>eHftBk5E7t{9t_!SO7g)J2uyS2s<+{Mib%DdNkp09?nQ`|rxTlMUD-8(`)B z!OH!EmHP)P_YYR?AFSLzSh;_&a{plE{=u>VUx_JKz9OuAML4|YCFWYm!;*)!zXogn zF3jkZ46MCEWW5fLfh3ASb3qa@Vj1l ztUaSJV}tUXVdXi);k_*}*Ge9iJgoh=Fr!Dg->`DOVdZ|q;eAFidUP$UYhhgrYu^)A z-b& zKjmWd>r4}@GflA0G{HL41nW!_tTRop&NRU~(*)~G6Ra~$u+B8W;e8D;cFHzbw!yLu zmTjUIMvux>?(GkUPj=)pRp2Z#6g#MCAIu=K;y4@*BR{jl`I+Lwg29~x$CkPNJSSY*VM>)a)* zbC+;k420ZueBY?s!|$-z{6QOOCUby<@c|ops!?#BCcHIq7&t z{9Cqq+%dCU%GJBc6{Qw_J}JswZvgp{z2)>wr`=A&wu)& zeOBtYD_{Q01-sDml;cWk&fDNY=l+3-h1v_Ny|CH~tG%$=3#+}b+6$|_u-Xf&y|CH~ ztG%$=3#+}b+6$|_u-Xf&y|CH~AARVYH93F9eM>##n`bO*nOlzgwmxP1a@}?OdX4C} zyw}Hb{V+w!V>Yo?e8;ucAGVkzp0j>=&=%eB^5;I>Z>!t;@3S|Xx7T_OzvlEzNw>!i zx4ZBUOn;LMtZQNEgjE+T8(`T6%Vt<@fz?J>ZHNEJo)MdNT7xCNzs>Ep-6p=Y*Y%Ch zb8WL9OK<%L#)p!JB@as;{%Fb;Yxs@-#{H9TZ?=?GesO+iJYkdN%DdQcmYka`!FxYA z&Uj~|b^m3S<0l^6WIK{gaeQpsCM)*Qc*p%$Z?@N_edIVx`mNTp*GR{8CT+9$PY(G9 zroEDZbuBENu3*~I-)C_A&VsErr$8#li|^lJ7X~MGeB_f&7Mmo#<7J08*xV6!Vz7T!@%8q? zbk9Y4uC?W5z0C04tL@}Ef9;qCzuE^wyiPH3R~uoq5mp;vwGmbuVYLxf8)3B(RvTfp z5mp;vwGmbuVYLxf8)3B(RvY1PyDGI`Y5fajbbYLPy`ODE%Iv-$miWo;Cd=t~#kHjY zkNb6TATwotwEx9j`}oQj=Qs3=@wsGRT?>mZG4K@A|VpSdH;M?qkc%5BTTaa|4<4yT1#r&0B9y&&Q z^uuAD%iGQle7NqFnSpP=Dmo+ZdF?CH0xqy}N+45u?pMLJ8&^yU{4d5=l7V$CES<3G zf@K3N+hExYOFwN9Q=YK;#K4EeCw(6Hw%+OSfzR`o`7Gc%y~YMIJ$H@?uATMDCxQRP z)Fu6}^uy8*OFu0Au=K-WozJ%ZDDdH{FMSaBwnX9g0-x`?I5OaGSBwZ`V&)7BuC2d( zNZ@}lK9LNpYhmexRTnH9VA%%CW?1@Zi* zAd_lN&*0h)Gr9%-7gLw?!_p5+KP>&Q^uy8*hjo6pzDwZ4l~XzdzU}yQ+rZ~*_O}SQ z>)>XA%!me!f@|0Is~`AZj87y3>snYkVbul823WSivKf|s+9IaBOs~3u4+mCyDe&#S zb#(%tcdq+v!0XP|3}o_r^F(m%;3+i%|BIF5`L$}`!@Uz9 z3Vb{G@k)Wu5AG@#@bG@60+~s#6br6B*sD4a4mEE{0i=43)Xk$&1D zM&^mP^9Md0S1wQB+bgT?3w%E8g=_&IK9MPqsW|oC;M&h7-V^v=OkL6sOFu0Au=K;y z4@*BB*12azs=$YrKT8()cKoA>0-v9obvL51xay6o5slI9rkssv{5^l}XoPtS`o;J} zGO(_Nr4v?Nuxx;38!Ve)>Hp`t79QRo(fHe_;m(N0-%P_dM>PIEJYh}1msYI^WX4rn z99-M9;zHLJ>Jn3z^uy8*OFu0Au=K;y4~KOg>GxgW!}KMm2fl6AePZDAY?H?X+~(Y< zKxXV`gM(`;u6ZZ$zZm-^1M6B?I$_lX%LZ7s!Lk{ae%d0Yy#An$k@>Uz{HH?I*CTyX z`uWd{CND?Y^!M|h(l0z2>9@@D)IOCXvs!zZlC?`jO4m%{=FG{92*n0Bcxu-XEvEwI`Gt1YnF0;?^s z+5)RBu-XEvEwI`Gt1YnF0;?^s+5+>tB=#`BS7HzIJ0|vGVlNqD4|6TChtWyw!;Ie~ z1EZg7Vf3R@OkI+}23WSivRVAE>f$%e?*|!v)BLVre$)Kk#QY8=!|xO3T7I`Mb-8;- zh-sJf!_p5+zZm_JK|d`0u=K;Uk$WGEf4KL-_=kI+n0udOxc9+a%e@aqC-=TE(-z6V z=;vA({pb`^mt?R3mTj+y)TVm#6l3{)Zb1m~Wn7Z72F~qb>`eEsZ zrC*GG$)F#Wepvcp+Q{4&#y`w`Vf@3~SIpd3GR%Epu4V2Eqm#LBm}!e-VDxh>jDB>A zsY^200LwO5HjDpNU9^$s2W0RM&lNEK;dw*MbBJVkK7qNG=N6c{-1Ab1X_xfF(hp0& z82yq#KP>&Q^ux4~XFnMK@azZUAD;chJo`z8XFr&0dG>?R$+KUWX^UiF^m8qYesqed zOETC1%Qjdxi~m(!w2|j$WbhBq)iD0yd0WhLxMX-fhq;#Lc9^={dO?V3m-NHZ4@&ok@`R}d2IPXqOwFDcT{>63T zN9HcthE_w#-fnf=aY&)GkVJTz#N<4zO5jAY)q(Q%euGa}df zdXD$@_mLNRd0ta@QKaS?&+ASsjZAOnul?}y%E+bHyv~MCtd9)+#Mjkt{+7u4RNI`+ zud?ijbouc&$1CdWj?5Xp!*RZvdn1#&?{d89(%#7UxAy!4(snYkVbul823WSi zvKdxeV6_oe+hO?xem~Avj^lg?%eSz64*zpo_;wp{p&Sm&zzGc6pQCH`~*T0AtJL820j^96e$I5Q2{tvzl+w(uQ z&xG%d{r?yJesxbKF1lC4|L!=VvGva!@0icX&Od9up*a|KGVenFzdJ8t-YYx*ta+*C z>e$KrTy`=)hnYVxKNtU3=FdDI$<9CP`9;rk*vWI8?BqF4w(%S%{;xb|@fn<@phr8)=KUIoRe}>0_r{_Vb)=(eLtoaMS07zC1ov z?6})o-0w8!t>m$Z*6ejWd0f)iJ~>W1etl%(*q(!ZZtY8l62=x>k<{sIIXyva;+p9l z7djC?Hfi7c91kd!Kd5Wj`U0`FH?DSi>NP7ATfD12*+ZrTsy5Bvh-C;SEDKYR`2S9}ex z9+=F;>38glbn02ql_wo=FtU1wulKF}Martttw(joJw_g}j>1PQtjW&hpPx0^KV#0>pk0)!y~xWC=#hWW zFTYW*{E0pCGj_`V*sr(@Or17X@hUSdO{~gqR8JEt`2$B&$4ZZVkUCcSv)4==t9r|% zO&u$HRvtnA6b$rR`H@-?L}UGK#$^ue#MJ=6))^jys%U8!hXezb}3%l zJEslG)Bct=kS|pJomHmt(Y#b^S3(b0{efhmo8`*$nqq-HKRi$@u=AN0iv{*qX;>_17v+i< z@`@LF6fg8EUev32VUOa4or)LsD_->Xq`mLDv6XtxjrL4E*;ja`o~x9%2GkVUHP3UCMpKgd}>YcmZ zGxkhKk;utlXOjCpWB>Tto@v*6uX?6msGNQwdHRL)&@ZH)exZ8l7qW+bAv@_8vY+3v z+C{nAi@f}R9{C6T@*DNapV%WmW2gL&{fZ0i>b^9qYdh_I^HzAQMHzUFq%=xJKvJ|~0z!NWXL zZ{bazu_t}%oK6Nidsgy{{pnutOuG^{@JxGEjvpkCf20S$Nk9Hnz4%%7;D6akTx37- zQoATudy$tP&?En#Uw)%r`4fBOXY7>!v0rhaUEHVW^R$=y6pSCZPr>+y`xK1dxKF|O zllv5mpSe%L_@Da}OuV>H!NiOEl*;*?OP=39j2`X_F#5S)z|_lq1jZijFEDm;-+{58 z`w>jLxKF{fSLOIY^7u!3@SF7GPt}W`We@(Boy0}<6EC%kaXkpS zM}Edm`5*fg7uv-c!8p2mi}X;v)Nrm)b?S+KasWfFAh={qh_2%AeRHKVzr-kNt`Z?P8v-_A>v5@dNX6 z82>QOhVdKoY#4ts&xY|c^K6)SG0%pH7xQeGcrnjbIrCJ>Gk=BA!@L$oKl5FfdYK2q z*u(r7#!lwVF!5qO4bv{>*)Z)@Iew5l{*fO1CjIzR_2OsQga2hGagqJROYNdu?L}UG zK#%-`e))}hckv_4eHTB% z+;{OK%zYO>!ivw+D<~7p8yhi$&*Qj3RHL{0!jqGGzBm0?$s$G<;y~xWC=#hWWFTYW* z{E0pCGj_`V*dN3t+AhV5d7R3b-$|Z%pY$*vlz!%ks+akr>|tIhJDG3Fe&(TS7v*X% z^6~?E-e{L11&k!qwqH=5?d5)f{H6H)0zHT4_YL$v)TM7w@6AX02KGcU_chts@@^lK{STb$ z6SRwRwHJB$0X^~$`sFw3l|QjZe#TDuANv&-Vny4yZ%{^?VPx@zySGGRg^yr#<2#r- z@hOZg_!`DWVg_S7F@uQ}F@tHV%JG5ZiIwyaE9oazs+U;F9%3asiIwapR%#dJw3&L5 z#}_bq@DYrDd+-gBzMRtWzzv;j*JRJ%bZuvc^LkD?xV81|l)}kW%-zCL zjZN(^eld=rv6Uj1@YdvkD7$8EASiGC9(iQ@{h8e5WLiG%WQt|tuSzgVBZF?xHvcO%h!uc&R*oB5Z!24l~2&3|`{olTnFag6w* zCma;$x$oBCK!4)dLxXzPq!}LA6O(>~$9u22CVy`%DHby zp8E!@`zoyaEv)-6tot*p`!=lmIZV5_&%?T(z`D=Cy8pnsFTuKB!McyZy1&7?@4>ns zs$A{W{gZOtS7F_6Vcmye-JfCIw_)ASVeT6(KlJNtue3;G-_P{?NRkw``dVE1$;8&S zQ!ckwFt%I*+nFV|sbWksmhaapf;vxg43ZGq2;}<1a?8Ud-pX@}>*! ze#p2?d4>vpy$ktzwftHZdR~0duV0}*VKu)_MZKld`t_(+qV{|~-!pbrDec#tu)l6k z&$R2yk36q!pE)Q$x*>ZYzxH&lK+lM;@&)>g~u%MTg{DcAT2Yuto2p28YuVU54=v1tDO;xywUYwP`LnJTxp zthXmQ-qqyU==%icIv(?0DVzVo2FLM!xYv5Wbj>mU^8Z}R-;sm4j_YCcp%Qnjh z=y^2BA2>eUF?t5nS?C!3>mK>VG4-^ovDq>897wdsG4<3ef7mhgtQ>dTG4-%UgnsH# zIrT`MdZdSXq@RCPFMpRkTqirxC;O>K?V?=mMP7bDkNksv`HgzyPwJ7MsYm{&9>pab zFY&mPYl1k!iX*Hz!ipoTIKqk}tT@7oBdj>WilfT0Px9CeD~_<@2rG`T;s`5_u;K_S zjWv@80& z8AT7dlQ@FQsj2dB`#U^8Z}R-^pu&xsK~$ z^r07~9_my1rU~N$`3iYwI!4dN_alzczozYK$J8^f%67-p(_`vE$J8^h_DNqJttWee zbB?Je^2vF})T46hkv#QC5A{et|Ega8E_=96cA`)AQ;*t3x!Q}o{D2<$2mSIJ^~j&p zBR^A*{7*fK3-!dD`_%dW$II>PffJuQuDGL?JveQS<83QTTI?5V9haM*-dbI_?3jP~ zfBetik%PI8>tXbv7p5Myi}KE2j1A<=mYCrfJ66aq#pU1dgOoVQCz<6bK35kUDWDtUSsj+p0d*$J%4ceq*Z^Ym@98uHfqla z&)J5bu=lqXcjeozAGa*mOZaP}`zq6)EakXV@#B`vN;^(;?U)^Xs;uK2M~+#AL*;_< z0lg{&@=cOgbR0jbXX!hY9HYO^x(6In@AmVR9b-@b-48m(&Vs`qa*X}&T=q=6YGrxY zl|T2)nV>v2x<4cNvun-n89U{F>{ndE@e=d9RP12I4p!`7#ST{NV0?~kuwn-*cCccn za@sC=d;%+Wuwn-*cCcaxD|WDA2P<~4Vh1aBuwn-*cCcaxD|WDA2P<~4VyALqCwXEA zD|WDA2P<~4Vh1aBuwn;?<5lj<9d_rtb*_KDyLG!AS?>A1w9$8g-tc_p#pruSpIh%_ zrp(-C3s!h;nthwydU=B@A30^KRln;w=Gm>*dErJ^K051GJJ@HF<7r8^+OTIf2j!)+ zZgGtK#C@L8vwrMWSC0P7)wVgN-ujz8V^8U)esks6nP8%4>@T_1GwsTF%=4~xJA?9? z6?O&k-Oud`^eh{*JJ6rF$ey6youBUs?3sCGPhjWvqI*sDFMeom&@Rf=UgYHm^vFNx zm*1#Y{=^>n89U{F>{ndE@e&hL#ST{NV8sqr>|n(XR_tKK4p!`7#ZKk4UGl^ZR_tKK z4p!`7#ST{NV8sqr>|n(XR_tKK4p!`7#ST{NV8sqr>|n)C<-|_%#12;MV8sqr>|n(X zR_tKK4i3kQ{W|h?81LAxBR>RYzs}_sMw$IO@<}LXzm7Z;nEg8PPhj@z$V-9QuOnXt zX1{J~G;arHf0g_em6P`(dGcXk^pGb5qo4d4n0m>pfw6~t8yGuXeqofcpZpxkX%~4r zF#D4#XWvrt>}N_3`<&9x{-^3?UsU$6Un)D?tG&p}59pD9&@aDHul$KU z@-ueI|Jbj%gySXVd0erB6+2k5gB3eiv4a&mSh0f@J6N$(xpJ0}S1yxchm2weD|WDA z2P<~4Vh1aBuwn-*cCcaxD|WDA2P<~4Vh1aBuwtijVkh~(BIimua6sq#2)z>JLP}uS6ssJ64Or6+2k5gB3eiv4a&mSh0f@J6N%U6+2k5gB3eiv4a&mSh0f@JCzeV z$rC$Rv4a&mSh0f@J6N%U6+1W_FPOYX`X_BCzfS$xoqvdy<16yB0Dx{5=?- zlh+3mJM#TtVn-ezOzg-HR5^Krk|&=KMh|(0F#5?qgsGRjL>PO>SA>b3JO2=6>?gmG za@s}SBTU;>j!z_yucQYbN|{T&Q@bcvdy$tP&?En#Uw)%r`4fBO zXY7>!v0rfs$4g916+0N8C}&c!qg=6r6+2k5gB3eiv4a&ml`H2HdF6sCcE~7puwn-* zcCcaxD|WDA2P<~4Vh1aBuwn-*cCcaxD|WDA2P<|eCw7wmD{@wqV@w;#d!v8ScJkiT zpIzQtv>acN_eMEBB<~Hzx8%LS_?)~qm{^ea1{1rh(Y!a9*wu{Yy{VkMG0Brp2BU{O zGZ_8kpTX2iUK)%&CpKvX#*ujb&tk}Vd z9jw^FiXE)jshqY;9-qL99jw^FiXE)j!HONM*ujb&tk}Vd9jw^FiXE)j!HONM*ujb& ztk|iX*h!w)!HONM*ujb&tk}Vd9jw^F;dsI1jnhAAJNe1#&*Uw`_=XyUo_uT=J>+S_=qG<0re5;8VeBE_8zy${d}frf zpZsvjX%~6pFl|>kK9M}Wk{*00{rFb(;&a(U>|`ggll{a_?V?=mMP7bDkNksv`Hgzz zPwbJOu~YuXe#IpmFEKGy>|lJNoO8vFa>Wi->|n(XR_tKK4p!_`uAF(~l}oSKA*0yA ziXE)j!HONM*ujb&tk}Vd9jw^FiXE)j!HONM*ujb&tk|jiugv)m#|yr%`)b!eX?x-k zp7BZPC7$tBg3N223_kqrUC;P7d(O449G^G)*)y^Du&-YWC3Xp(@avz%E_$Bb$x~i? zzh~qZPxb4c=sDNeuYaPyVsgL!NxePCdB&dF_xSZs?9AK3Gxk3_-ZSm0FxxY+Q#rAd zJh77=VkiB?PW2Ky*+cAPC$W?L#7^y^TgMRsqdgV{-k)N?s{>OgBB^)m? zYh{WZtk}Vd9jw^FiXE)j!HONM*ujdO%4xgg@d>Qh!HONM*ujb&tk}Vd9jw^FiXE)j z!HONM*ujb&tk}Vd9jw^Fik-@do#crftk}Vd9jw^FiXE)j!HOLmju-s(Ti*r0yZ45A z#wRi68DEXe@O|*RYdYLBzMYzVZt%N1yWBIe%h`Kg@cSBBW4>czS3cbjLHVvdo{_IP z`Nu#{kJlDBM*p%T3mp@?B%gZ5o?WRIxpM5B^}1(bw|%T<+O^~x&$M0T_(byfN_z02 z^y6FAi_c{bv6G#|PWBT!wTp7K7kT*sJ@OCw8 zcCcax<3s9#6+4*U3%0?E9n9~Jw!n&=%4xgg@d=C`d<83Zuwn-*cCcaxD|WDA2P<~4 zVh1aBuwn-*cCcaxD|WDA2P<|eS9=vZ$`w0Uv4a&mSh0f@J6N%U!|{U4bs6LOFm2B^ z*fTzPJjOG=%98%mp#Ps4;u+tT$vW1RJ;%9nVwa`bXO4+oG?yqSZ@$Yj z@>?fO2=pXw@VR63*Glw-V`BII$DXmLdCG~d96KvD^^E<^#(1V(Pfzzu+f|NFB#*D8 z2Omm5zE!>WT=ozP*-7kVKe1E0C|7%tmmkn0|Da!fqh9$Fd*o;Al>f0`aS6vuOiUF! zSh0f@I~X5Q7p&O9iXE)j!HONM*r}YhOCF!V=)qU8Vh1aBuwn-*cCcaxD|WDA2P<~4 zVh8^p_TDqts-kPxCWC+?h@zN4l8T5ThR2K%6@APJ6)X?`*D7}KTefz)mvQ8u-E9(ZaJ6P>twS(0TRy$bj;F5a5_x*HlyoMS3SrzZgujiLKB_>y= z?b|iK{#RALKQg(!yU7EQ$$7;GxdcCgyPY6q(wtah;4!DdcCgyPY6q(wtafloz2HX|pBArS#@@Ef>G}0M;g-bY>WbPe^XtDt zg)<_P+lTi*Gcq~f`<}BRquu>0T17^?*7u$h8SM)F<@OD4o|m_u`=1LUba z^z9c#M!U1?UJ{vjHdMVdGTJ>eDKYV{sef6tGp;Eu6Ek-0u-d_D2df>dcCgyPY6q(wtah;4!DbNi03?VY#(qxrs(@pIPebt2>cyG?Z? z)9=-L)r*XFJ65V6nK;LcPfYxk>NJRU#x?Kc#Ee}#Ik7#t(hoV*Ke@GEa&A0mXPjtf z{AlO6usdGbn+N=uAN-p)`rWfQpTuLHiPQWOzq*vvOGZ<*gVhcuSNMe04puu@?O?To z)ecrW?Tp>_twS(0TRy$bjV6}tQ4puu@?O?To)lNIw*&gj+ zwS(0TRy$bjV6}tQ4lbz|e9!A4WA4Y;cVC^DoJ^lq6z$|{r@9|Tjyc>oB{I3a?YNI4 zlk-OxPmhdt=YH~8WVGAy#~G2+cjh;_{nXRG&D)o0J2x_ZrnFoT8UIUv`z|v5t~z*e zWa2rc!jj0uIk4T2k%|A9BbG*HTnp|`%-FS)6Wfz3{g6ZblUw^G=f;C}#))>upT0BG zxT2=ToRCzj=$-OmRMm$2=3K`6qsLDXEu?rfLVP9jtb++QDiEs~xO%u-d_D zr=79eo}9pH2df>dcCgyPY6q(wtah;4!D$Vrjcuyy=iCwv#*ex!t5&~r!e~p$tldfLUIbTuaKO= z>?O+QDiEs~xO%u-d_D2df>dcG?-c?a>ZaJ6P>twS(0TRy$bjV6}tQ4puu@?O?To z)ecrWSnXi7gVjzu+SwlMV6}tQ4puu@?O?To)ebJH7yAmm@7SBBzU)m?clH%}Jy^es zYs~sxu=TrO>vzG{?}Dx0rQPc`?n5lTo~_?S8|!z$*6)Ie$NPmiy^o0B`-^dT-_0((Zj{{Vwd*?}Dx01zW!hwtg2(oaUeS z)up6fGMcI#tah;4!Dn`_u6D56!D}==V8$1O1+7U!m6_d((Kpc|<(k zcf{#^MEu@&jLZ9uy@cA?OK5xcUFwJZnEGd*rv0*i(|F>(&f+-P?`iz(19e>39WU+8 z1Afd8{>>Zxnor^}&%|l|iCLsJ8+QDiEs~xO%u-d_D2df>dcCgxM_r6m*>}m(A z9jtb++QDiEs~xO%u-d_D2df>dcCgyPY6q(wtah;4Y4^TUJM3x)s~xO%u-d_D2df=i zQZM!udf%}(O?}y$rta21_#kjoh*h{FLy@a;6{vm$YkLi79{X^{5KZLD+2wVRUw*H}Z?>p-s zVz>SwZ2d!+e!cIke~6tp%|G$0OG&+CG*vrT?O?To)ecrWSnXi7gVhdJJMG?gaSv(n zJX7sxqjs>`!DdcCgyPYNy@%PVKO(9jtb++QDiE zs~xO%a7n$`SLl7m-Zb@PU!l6Quh8#d_7!@au&>bXZT1!Vea_xM?>qJtdL4RB2iFyL zpBHf-V)1hXKR#dZ?{kNKy)THz=M-^z9}&Oz7vu82V=tk0_7d8jeV6)SKc@cKr)j_J z-!z`Mud_H#_Inz?=X5YG?2ecA<^ezE2mj`ce$6NGm}lZN|HQ8@CH0cgRPA83gVhdJ zJ6P>twS(0TRy$bjw0qyF9d@;Y)ecrWSnXi7gVhdJJ6P>twS(0TRy$bjV6}tQ4puu@ z?X-K}sU3E;gVhdJJ6P>twS(0TE~yv$3cc^xo2I_(O;dOF6?#3euh8p+eT7~>>?`!T zVqc-x8~X~q4%r9ldm2`H|Mcs9K|J0s#OZxR{N7)T%lnSKgxc9l zXnXcu>WBT9`e&b}{jz`4c;dd!;yBswY5eR1bzImTFYV0(e#{U4%^UriPvSAp#A*JC zUtLP-C9_thcCgyPY6q(wtah;4!DdcCgyP zY6q(wtah;4!D0#n&@_yw36O^-sUv7sTWJ zLY&@5#P9vZxV-P!OQ@Z_gtlidp?=tpsekrq+V6LTeW1n@_jMM>$$n4cXCJ8J!tQu! zZyxYte(-PJ=+}G_k9j6e^H2QhQc^D&P1O!oJ6P>twS(0TRy$bjV6}tQPP_M=+F@5a zSnXi7gVhdJJ6P>twS(0TRy$bjV6}tQ4puu@?O?To)lR$jo!VhnJ6P>twS(0TRy$bj z;F5Z=uh9FBy=m&p-ZXV*U!m6n`wG2I*z4!@!@feVEA|z7y|J&*>yUk*UZ2>#ZsR`0 z;_DedUg!At`lny-3*zy9Ax`fj;`jbyT;6x=CDhJdLff;KP(SR))Ia+)?U((V#uN8- z7RSkcPvd7FsN=%!cxi7Q@MC`PZ{FzFd=ig&CQkED{OVFtFBwhM4puu@?O?To)ecrW zSnXi7gVj#E_nq2dS36kkV6}tQ4puu@?O?To)ecrWSnXi7gVhdJJ6P>twS(18yZ4>i zVOKj??O?To)ecrWSnc4FdadW3Vb!T6p*8}?sy-wKc=k>$BLa!_K270}* zuh8p|eV|^S*u8G!KE&ed89!d<`1ks!U+)Xz@qQsr?<3;({$gC-ckCt9&R#;>v+q(r z?8nqU`!wyB{hP)U_jMM>$$n4cXCJ8J!tQu!ZyxYte(-PJ=+}G_k9j6e^H2QhQc^D& zP1O!oJ6P>twS(0TRy$bjV6}tQPP_M=+F@5aSnXi7gVhdJJ6P>twS(0TRy$bjV6}tQ z4puu@?O?To)lR$jo!VhnJ6P>twS(0TRy$bj;F5Y3u9y72V{e-JvNuiL*;nZGz`jDS z6ZZOf{jjgl>x#XBUT^Fx^g3i8sMjZUuiLl}vG{t%kJmZ=z5eOf`+|79Ux?HDi1@v~ z7?<}QdkM9(m(cd?yVMW+G4;twS(0T zRy$bjV6}tQ4puu@?O?To)ecrWSnXi7)9!tzcG%SpRy$bjV6}tQ4puw3q+W%;<>mJs zd(+gHy=m&szCy1D_7!@au&>bThdqE^SL`eFdShRq*CG2r3w_7G-(mN@P&<1GZO^_-{jeWX|LoJWU-oYrPu$m894Grd zjh}s>jtjfvrM-E;kNLsBd81$RNj&D6IL$xtt4m3}WHePfSnXi7gVhdJJ6P>twS(0T zRy*z9cWQ@S?O?To)ecrWSnXi7gVhdJJ6P>twS(0TRy$bjV6}tQ4puwu-gjz;UF~4C zgVhdJJ6P>twS!CQ_3wEi=?shim(COM{1>&OzIRFXTo~-03j=#D4D7iuaLwX#VPMaN zfjt)n_FNd)b78b|E{yFtZw2;T7#RPY3j=#D4D7iuu;;?So(lsrF3yF4Jr@S{To~AM zVPJKHcPpIRV!xgXgWYpsV9$ktJr_nh=fc>Yb75f5g@N(UxiGNj!oZ#j1A8tE?71-T zWwkbhYeuh*&!Dkqt`B9_CqB9Nx-jPRHPODy=YNNd4gQY&Mcuzct8MEd_j_b*XnoSg z^x4{L3%>z2M_w{@O*m%8w#efKtqEIiFBRVr__FI7{&pA{`%@#!My7q|X5}M~E%=%H zN`=VyzkWl-$n?8nj~yZt&(QLfBNOK_?!h?TqW{7Kuy!ydk%D9JMiTKm6KF zxu4}#H|PEvKfgKew^Yq7c|5aj+LFh)ZTOZv{$=lM$;XA=@zUNr;K%&n-@MVU`6M3m zOq}MQ_|>JPUNYaMY6q(wtah;4!DZaJ6P>twS(0TRy$bj zV6}tQ4puu@?O?To)ecrWSnXi7gVjzu+SwlMV6}tQ4puu@?O?To)ebJH*V@vh!wa{~ zi`VLzGq-2`dnSJP{VmzJ_Y;5h)yAyvPV-}%(M{H8t$QaP{_EQ8`CS)8`&rf3WQD(Y zM=tx`s%*C|3nO3jyrEg$q#ZAFEk|Dn|? z1^aEWrBX1SWv}fJjPuxCDhK1Qa%AP;xUf53+M5Ubm>>L`H~KZ7#ABX`)BF>^x|GyQ zMpLze)ecrWSnXi7gVhdJJ6P>twbRbnZBI^MwS(0TRy$bjV6}tQ4puu@?O?To)ecrW zSnXi7gVhdJJ6P?sqn+*14puu@?O?To)ecrWSnc4FdKLbbm${zFI}rYk;2j8mU-15l zzdLw;#or@W7v5j-cM9*X`1^(TSNvVW`z!w5;e8{22VwX3QGDN}_;(Y2{5^$#e`nFJ zzrTpb-(|$pet7Rk|GW=mzq}`8Jn{XZ;y8J)$oP5R z$Z=tJytFqD_%T2DH*fT7K8eRX6Q}tnesw9SmyD)r2df>dcCgyPY6q(wtah;4!D^@7 z-*;+twS(0TRy$bjV6}tQ4puu@?O?To)ecrW?f$+~JM3x)s~xO% zu-d_D2df=iQZLR4;mir1HJr)7Srjm5GH^x(%$XIOIRSH?24_ydoTtH=6ENp#aOMQe zc^aHK0dt-PXHLMJf5O=e+Bvhq_MGJa}xiXGOro$(a){@pI+` z%(ysn0_F@2?VO=ud(J=659gogpYu=bm-A1Ihx1H~lk-oEpYu-~7k0->d-H%F^Mil$ zM!)8hc+4|#nt$R~my&wPXsULw+C{C4wS(0TRy$bjV6}tQ4puwujNSI+1Xep(?O?To z)ecrWSnXi7gVhdJJ6P>twS(0TRy$bjV6}tQPCMG!9_?VYgVhdJJ6P>twS(0TE~yva z(?0LG*Zp4Qd)n_?zNh^j=6l-jXa4njoB!_jIiK@;9)EuS(~r*u>^?7IKgG`x{P=vq zzt0`|@p(i)KBwr%=NJ9>T%#YKcl4v3Jx#W!AN|me{`uE_`R~RPKUW+l{*0e~92a)S zOMCNxAM=BM^F}}BlYY!IahiYnQJ0c>$!Mx}u-d_D2df>dcCgyPY6q(wtajRo$@cCO zQ#dcCgyPY6q(wtah;4!D^Z!!=kUUw!wY*3FYGzI(O!HGFU+_&hZpu7Uf6SZqrLbX zURWLB6N=B_g*}HC_8eZ=b9iCT;nmJLytd~YUf6SZVf=FrFYGzIu;=i?p2HjM#pm$C zElyn*&MBTxKHcT-aK!Ox4%v9@+R*Nf#9KD335R{2_}%}m36)MvbIaR`R)1m#cy~pEeo=N*vm!-KSe(Karb4&c+ zm?fs)H_uM=9Y}>`gVzbt-e0DUpjw%-oD>s8*)G29KA93 zzsrn`dB4B5*p$aJ>8VY5oWFdzDUbilA2#LV!tQu!ZyxYte(-PJ=+}G_k9j6e^H2Qh zQc^FO?^3mc)ecrWSnXi7gVhdJJ6P>twbPDvwnsZy?O?To)ecrWSnXi7gVhdJJ6P>t zwS(0TRy$bjV6}tQ4puwuXlHx0gVhdJJ6P>twS(0TRy(+)UZ=k~E!;e-u&!PB9fVze ze*A{;#WTrXc9+fJiA|ego62Wx4dYgAjNGZ!_Hg8Y4UxYtTdJt?SL-4VdcRcB%QFgp zV<`CCeoX12XP-#d{~iyQE;{nabRV^Ut#pz1AY6C{KDPh%>>5QQ|4#K-=C-d^^w{RF z;@=}Kezt1S(_3dp-e=1WMdfCsS}P--u2|GT*3bL;=<5bW=g#~he)jTf8WkOM+ozFtSiFBx_dh<0 zd`|NNi;n3qIr2xX8y7v-Y;5G4&N`^5OZQhJm)d$z(Y8^~M6Q2hlcJ+{8XS4>z$Qh7 zeL^`G{)U>jSzNhHWIj9QrJ0k-8$Lg2^-^T|YFDXaWMb&lxItuM8`N{wB-#`6_>Ol* zW-PVOsuY18VdO9gj%7%OCwh%bQak%019O?EPrUPuoxWhXrq?Gx83Y z)<2B=B;~N<-G%eee@?kQ>x9Xn#+WVfKI*vVJ7LX9+au5F_iE^NY&xT4_$SYYOKYcd zLyp{iX!zxoiZNH+-+m;V{#ljC9Va~$?z=Xf0rY9>{^77oca8Rg-{>3O?UBy>x^GmASXieh7)^-X{T#>HH+wScYPW&?Q^z%A}J6fdc7W=E?6Vv|uhUwbIPvu7v{x4eD(?%i`gy$bt^^?%RL zJ@S5A-qbUXXUUA7d7LeF=#|GmWba=2xUf53+M5Ubm>>L`H~KZ7#ABX`)BF>^y7>DP z?OacQT~COb{<{_wpP{ZNkQ3JvVAm70lSlY}VlBvZJp8-v3cKzK|GQ?MerLJvN={sN zgzfWmr9m@8sPr?3u z3ij_)uz#O|{reQ`-=|>zJ_R!_*INDi6n6hU1^f3Y*uPJ~{(TDe?^CdUpMw4S6zt!p zw0nQ~_bKfDeG2yPQ?P%Zg8lmx?BAzg|2_r#cVXDS|p7W5e#phTV@1yB}M- z--qtU#_oP>*!|eB`>|p7W5e#phTV@1GcLam-H(mk{n)Vkv0?XP!|un1-H#2s9~*W* zHtc?E?S3D+9~-;-v0?XP!|un1-H#2s9~*W*He8q==I=iE-U@c#TY-IV1@^ra*!Nao z-&=uwZw2eGeM;J!shXpkd#GhJ6nj_C09W_n=|lgNA(%8umSC?ds)w(Aa$s8umSC z*!Q4e--CvI4;uD8XxRD#u=OHf>qWrUi-4^c0b4Huwq68my$INP5wP_lw5yl(BCuO8 z0=8ZRY`qBBdJ(YoB4F!9z}Aa^trr1XF9Nn+1Z=$s*m@DL^&(*FMZngJfUOsyUA?Rq zf!%r$u=OHf>qWrUi-4^c0b4HuF8of(pI_G1!ERk0*t$Bfb#-9t>cH03fvu|pTUQ6R zu8wx~`nM)hs@-i}9r9yc9oV`$u=T89>yN?KAA_ww23vm&w*DAw{V~}3W3ctdVC#=* zS1;?2VYmJmZ2d9V`eU&5$6)J^!PXyxtv?1^e+;(%7;OD9*!p9z^~YfAkHOX-gRMUX zTYpTu_m}m@uv>o&w*DAw{V~}3W3ctdVC#>;*8PL6(+FFq5w=bvY@J5fI*qV(8e!`+ z!q#bot<$Joy{yxS-8zl1bsAyoG{V+tgssyETc;7WP9tocM%X%yuyqomgFX@srQ z2wSHSwoW5#oks2IWt~Rs)@g*T(+FFq5w=bvY@J5fI*qXPQDN)Z!q&5et!E2c&la|x zEo?no*m}0G^=x75*=koW>)B$ro-J%WTiANGu=Q+V>)FEAvxTi^3tP_?ww^6)JzLm% zwy^bVVe8q#*0Y7JXA4`;R=avx&lbD&Y+>u!!q&5et!E2c&la|xEnN6rnb)wj?l*Sp ze#3kHTeCf`ZCdx6oLKi8w(hrf^|J0acI$q_*8PU9`wd(78@BE@T%$zIcI)k9_k0A{ z^ATXrM}R#a0rq?Z*z*x!&qshg9|87!1nu5mw0FJN^ATv{`3SJ*Bfy@I0DC?H?D+_= z=Oe(Lj{ti<0_^z+u;(Mdo{s=~J_79d2(afPz@CqwUA_J%&bHw1U;mx~RQT@wf9MRL zf6q!wdaw4sbe6p?wlV{fTVDw^L4@NK6 z^J^5!@4Jof7V0c_&r>xVF#lZ>!&b! z#dXyJqZjM2*wO3XGs;umSl1&b@!^GHG$Fx1`n=pP@ z_k{7!dMJ!utdqj%#ri3XUU6Nu!05#~EOzu_T@Pkn!+Iagew(v}Nn-LS3)^ZpL&dNA+ru&xL5{toMU+F2K~J?mvKepp9?@z44iOuwwV!NkLQ z988>XU9Z5z&$=FV#>KiG%y_kv2iub${lxF3V*ljRe#x`(pqFu?i}9nET6z zV}9^&-ssnS5|4Q%PV-Ov>cY5K*JE6am-RmL5ZCnzcJjmeAa?S`x*;6jhbq)MhsiVR zj4*n!{s^NN>ymJK-|Cy(&bpZGSuca}!#Wy_f9h7l^h-T!n0Tmj4Wn1AmtA1ur(QO8 z#znnsnDJ^S54I;i`XO)nC!h99o{fk68z;ILe|mnUv0!(+v^Nj zc_vQtPyFh_xLDWYvy7MZKA1ejb-ekwr9Nz#t-XgFnY1R2GcL=ZZPq%9tRU=T-Pfw@w2XnopG_Q2QyynkX2$G8|T z>wV@SuIm--6djkn0Q!^gV8Il>lK*zS=YnPxLDVN8LxKoV0-eTAM&Pu@@c>1*?7pmaiWXy zqnG2t?s#c$9`Iv+@NeGe*L)I>c_vQtPyFh_xLDU?T#T3XKJyUQ^$K?K!@3@J^2WLz zOg>rHgUK`NdN6vit_PzR>v}MHv970`burtsUIycbbu<|NtgpfJ%eos(JgmpT=oQ!X z3QYX0>tSbHtn0yyS37yIJ^9fOdDB1nv|sXUJmlXv(Z%@D%W+|MytFqD_%T2DH*fT7 zK8eRX6Q}tnesy77oae{57%%7inTL3uU%^g(IL{9|dE-1kn0#`cA55NEXN1v<^+y=J zSeJy+i}gzFH45uuwr9Nz#t-XgF#cIzgXx!bH<)->kAu-GuIm+;_*vJ(&bV0DgBh=O z@?d-NqaX67fAVR+v}MHv91TB7wdX3daqXC33p6P^S!})%n3`o zrTN~g73YKjt!i7n>9_T_iHYZsGv-A*ah7=@ zG4UTfCo$vNb$R0NIxNiXXCD4t-u|AI-{pQj8v1?izx)A<@_rW<>QNcbo9hx>Z916S~B{f#*F@{J!8Mrq%j_9)fgu= zY>c1UHjWFsoRCzj>oy^GQ7BnK;cq@vF=7f&Ihel~2XL@4Wwahwz`@o{xOw zg0sUhua1d4_tS$z(eN)LA2z;5XumqurQ~1!H#y+Oheqs8dKkau6PrvbL z->k`~XvfbrT6zV}9^&-ss1C(vNwjAM;N?>OxJ_ zZH+g@@$S~Lb13SN_@?f+g)PlDM|<^}H;2(((z}GmHn~2OI%He4S63DhQ^;VjPm-+p&P@!@8_)Njx|FsH{X@5uUN|Et1;I17a ztqUP}CLKA)Iz?f7BhU2FHq?SE|RmA9`|cyCcZ zJsSJkBdC49?@<_l&{$xUf53+M5Ubm>>L`H~KZ7#ABX` z)BF>^y6_%rzouy(wXyC_;o>tBKXd;MVfC=YL-s2lR_vMH$DGlubhuCRqr#f3--P`lj~cKt8~$Ux$Va^US604edUp@|EvKcq4efh%Omh|d zoYFVVPw;#pHX@LV83g>I4~H`Pv0ICjPt)W4i3gY;QoVyT6zV}9^&-ssnS z5|4Q%PV-Ov>N35}!tAR$@5k@D3CAzUc0W4t?G5K=hxSR_W#4((tbY=Jdg$Ej#8)Q7 z_Rm~9C%g5IiIJNW&Cd2}H!1SNC(q7yyD`0ce#gddvn#r1(SE=W-)1+z7$Rf8_oJe` z{f7%bh>V{}KYkb)|Lwn?5}AI7Je%HaC!TUAPmOls92pW5e^I56qn&Y8+Ar~(?%(D1 zJ%@dtx8L=JMY*484=>LBuetn(yx+E^m*nx3>bfK|&f1?W$>YCv$&!3r*c~tJ%>#bS z5B|*?{hCkWG0((l{)t~*zG%53TX9*+PuA$q?8rM3cdqtFc5YGPu9bezRv(q}Hly}$ zS(_gc4?p|YY~Y(IhljqpJUiy;l($C@TAm&LV#?LsKmL;4H*s3bVUtgP$sSxdJu>!T zTRw?Q`yY1sEHZu;)c!m&{`*%-bqVNq{G7zZQ?F~PlR%swuTM<;i&~`TEaPg_I`M+` zf93Xld#=pe?=fIi?&q`4t8@SBPhOMvd+qOQ@_5Q!w>FP+pD}Cm_;37dZ9XpSj+gf4 z0YByk|K^Q;%_s4gXW}&f#IG*PcP|yHKAv**;m-eL7r&YK-i_O`jvEqpU%fTk`Sz5< zZ^~}X9@stQZNw2y6^K%*)wZW-HAir*;M$u-Z!xg z_6f~r=Iyt)niUy88!z}aGX7s{k?K^?@9drCL_6`EG(ItL{?v4Cv=jfey|*RsT1w}TEzdEIpq5Pe4msz?u&b?ru=Zf+_B5N7#sJ|q{j0jbANr>YC&$Fck9B)wBNh$caiZ^ z>*4Ps#K%pW3-@ZO`?rAFgx# zbN$;d_l5CrzZfU?k@0hXIWFvum-glXKjsJj=8b;MC-InP;xzxnuP%JgpIJWThwuL< z_DRfh;jQ+Gd0w3Jb7Gz&*@G#EJYRmhB;}3g&ahKcet3R8)@n)2AX;32TyOMxAzS@f;_Gf6o>kd3)%m~W+UK)31}DxsKbP%s#HQGO z@axZJrY((y7!mN?G|7F8p$@{(Fv{&m zywR`uBp&ljoaUeS)urg+aasSn|B87VbIZHgtVa^Jzi@2!=XZ&3JNun%;KeIrn-ANJ z$u@6I{P<&UXN^8z73~fF9G%U3Kb`x~yVL0Go1!(*esjaoS*>|%BiG$=bk<;F`mK$< z`5x<|o%Z)0nywT4+<8>GHt=7+VY)Wx_q?@DnO9HZ{|=LHzf$NzAyWc1ir@ z=<&IImrvfy+wb_*`?;Smc|z|0xBe6JelKY{DUWC4>yz?0tFN1s$A866lk;(5cf7PW z5BM=Z_&0C#Yd(p`JQJt+Cw_JLsPiXT`{UF1&$x@GXYXE;_}1g5Wiwt%eCH7#XSeR1 zzL!33IW_xkYT}{yeUw#tG<`=MFlS0O;eqsBG~n_n**ksGcTvY`Q?iZE{hl;k|6x|) zgFhl;-*w5Kk!jz0C?-`=952ri}O^_y1R?8F{}~?EYmQ&(_BZbEx7tcU$~r9)H^n zU*_Y&?s#c$9`Iv+@NeGe*L)I>c_vQtPyFh_xSVe=UY~2^!RHS92a)SOMCNxAM=BM^G3hslX%QCahiYPR~N?R?=Qyd zJfA!`|0h5GE+B9IULc?Tjv&wez99ep?m!oRkD!;ozp(rJi}wEh!jHed@bB+0`t|o0 z@%a0TIQ{)a{Qmx8T>k!IyxPfw?a7aR$eaGjr~Q&=<01dXi7v*EUXBa9oRC zzj>oy^GQ7BnK;cq@v95tdVBd>@wBa zOpHuC%XXL)nK=9QPE7p6zfR1!e)}~s>Zxnor^}&%|l|iCxQM>xG{r<~hE$#>i;r`ToSiiFxjq zY5q#IGaqPLI@LC0p0N0@#LOS&uX`=FVP3J%PNO0--)PeGjog0hxo<|Mea{=yHG`k7 z9n-ae|HfCQYlD6-JuqDx#54Vy#Kd{SS?M|<{_aB(Gp^6yPR#RKJI`_3^L*D2&wc$f zAFyBM3C6?x!8n;$7(eq3$A#VT(%wAa$Nb>mywR`uBp&ljoaUeS)rEO)r@Nksd1F32 zc~D~J$+H(EX8wHFh0n$|%&ULeoS6Cc&YwOP?aaeJ82@}^=I0Z$;gOlo|1r zT8GH{_1+%N+~@4b%bwmCCe1h~a+U2{!e0MWjeNrch5D}bc8)yyq)lPad%Hw_@BEG7 z!WU~rzJ1(=P~nR`BhS3KP#<`YI+35hcSGoXTm8sgmuv{vjo&}=fs3|=DfOyEUN(4J z=vHQj$Up47J&b>&Lgb^a*dE#*S}yXN9k+*vUnw2=)ibw;M~*9;O;s4nDSvGXRaH5{-fNrbf zXItL?efYW0+Q<$5vpBT+C&hX9;Y-5TP5+7Z!>(Bxs&+}^n)A-jVezAdv$YE2T2gI! zD7Pr_wKxA3PPrs;&#`}mA>~s0_1~@t+ZLs>%%1&VWf;I&kSS7z7_e}OJ|1qW!{hc-ydd%<+VPHeCG67q0>8`MxIzk_-fi>4JDr+D?mcu~_{L$=hLecheky{`Cb-1N!`N-u)e;Mi>o7&WAT6mA{{`A>LW_%vjj7>hz zxpZ>Qr(Y97>v^@~XODR5gK)rZbt8ZC%aqWfMg7P-9{+L9uMV7^w;3|!)BLlw*G>%A z-Y+-ShJ?d2I79dNJo&ZC}p& zn)2kxJciakznaJP)G?!SZua1td7HW)jLttha@Fv>ug^L>pT}@*VQ;>%?NQi|FOMHR zEN`>mpr`WBj{Iau9@{k+^vn6ms|MtKwR-%aJceI>d^nG--hUp+xlrUZZ}VpMME==B z{_2zWb-^vY^B7hZ-uW=L5ry|W@m-H^w2#jUsG{7B_ad7E4Byet3gUGpx<`wHJ)n8)yU;awtQyQ=X1kUZpqv+_2J z{@XJDZ0A0w=CQ4Lwqef8#uoO=6knfH_iCEQuzuoUd2F}ecvQ|K%O97w>D94C{@I6S z)yw;u^;MlbhRTI^)Qs)U!h31*8|T!@+pImaX8zfM-K*!ZRXb!^<~_Bp^@_|m-)Xu& z^FG@BrhhW;qkh+v%j29}YKJ_|VK?oV$JyeUA2RQwZysNec^{onIFHQOb}5{>Cii@N zdfukSzz_4!p1fgF9@|~5?#;RG`F-*@zi%)okMoqaL-RO~4lm^V(uUXbHdlU8_)Sx+ zMV<8>vZLFk`+fbmtFs?#rTe|XFBfHZZBE}y)&6LiRoy+^`!_T^Hk;NlwK;iH)9jm- z>9a?ESU+2LSB>~RGwhq%8UN2S1snejrY)a=@qsTG-}C{~Cw;@jLQF6*5-W^W9<~klHq2+a=VAKdI|3$7zB^#zFmhXC) zIC+-HJY!(`;@JQbC(jI+IC+-HJY#Ibvj^t0Jd9q%!cWUXDv*eJcD849q%(e~Ba+uHZjECuqIRQ+Z%oSkbWDX%Sx3CR! z4w%m}7lDbBxsJ>n2&OOQE--O2r-6x+xsJ>n$TrN4U_Q&73GQ%1mF)7vXG9)ar($-( z;hb?8whHt&w%_G$-=tTWe=S z-<}(}-3j%xwUg&Xo_l%IY}}yvk-Oe9fR!uxBp7p1A;f<^t@Q3$SM{z@E7Pd*%Y{nG3LIF2J6-5bech zF2J6-0DI;F?3oL&XD+~=xd40S0_>R!uxBp7p1A;f<^t@Q3$SM{z@E7Pd*%Y{nG3LI zF2J6-0DI+Oheqs8dKkd8=VSC<@fbqk-6EOaHrvj!Q-nD?~hj%bw`r+LSn0|O?1EwF| z<$&o&JN?+6e)K~>`sZK!<-Z#bpEFMU89)6vF6@q%_T~XU<_G`gjeg80{g`L^G5_?V zF4pj8T-NZ1t>GWX{_okT@!4bze{ynv@wvCKHT<>zPoAC1UN-M9YxvWzHT+>~_`}xl zhppicTf-l=hCgf#f7lxS+PyyiJ!3k3Us=PS{8+;uwuV1!4S(1g{;)OtVQcuq*6@d| z;SXEGAGU@+Yz=?d8vfd;;cxqs3-2t!___Vk#gXwpxzrDl>3931iHYaiic6xMI7eQU znD}Qto|th>7@3$F_}ZzBZ+mLy>!;d^3PJxvt5pj2+hR+lU_8rS+aVa|vAa|b#$V;g z%Hg0YX)M_L9G~W#wBN1E!WbuhehF#*iT~$!O-#S7d#CxWHT=ngHT+>~_`}xlhppic zTf-l=hCgf#f7lxSur>T)Yxu*~@Q1D8ubmqHw(s1md}RF0eI@-J0sq%;s2J_^yJC;@ z8=rWFmaiP`#CgoSiHZO5z0=<&7}wP;5|{dULvHUlYGdAh__dpIKh)CKf8*yj=lzzd zxh0Qh)=gW2ac&#FB^dv*ceYToGRA{_>+Pi?)BczlX`LTG_x-dvK2P!A`lPhxZw-I) zKs*~8q`!j@=a|pe#P-BrW_|kG1hu35KD35EpS6ZRYz=?d8vd{~{9$YO!`ASJt>F(_ z!(Y4Kht}}NZVi9f8vd{~{9$YO!`ASJt>F(dF6SH8@W*Zqf7lxSur>T)Yxu*~@Q1D8 z4_m_@wuZlU=Ns1W$8HUO*c$$@HT+>~_`}xlhppic7v?p&Ue@r(ZVi9f8vd{~{9$YO z!`ASJt>F(_!ymSWzjpPqhCg;|_`}xlhppicTf-l=hCgf#f0%Kpmo@ycTf-l=hCgf# zf7lxSur>T)Yxu*~@Q1D8uU);Y;g8)K{;)OtVQcuq*6@d|;SXEGAGU@+Yz=?d8vd{~ z{9$YO!`ASJt>F(_!ymSWKWq(u?doL>f9%%qhppicTf-l=hCgf#f7lxSur>T)Yxu*~ z@Q1D84_m_@wuV1!4S(1g{;)OtVQctnS1)V$W4DGsYz=?d8vd{~{9$YO!`ASJt>F(_ z!ymSWKWq(u*c$$@HT+>~_`}xlhppicTf<+wdRfCCyEXh_Yxu*~@Q1D84_m_@wuV1! z4S(1g{;)OtVQcuq*6@d|;SXEGAGU@+Yz=?d8vfeV%NqXJt>F(_!ymSWKWq(u*c$$@ zHT+>~_`}xlhppicTf-l=hCgf#f7lxSur>T)Yxu*~@Yk+h*6_z}4S(1g{;)OtVQcuq z*6@d|;SXEGAGU@+Yz=?d8vd{~{9$YO!_?^V_p&wov0K9*wuZlU^|FS)e*C>`4S(#` z@Q1D84_m`Oezvfd?C)i3_+z(*KWq(u*c$$@HT+>~_`}xlhppicTf-l=hQD_8vW7o) z{Fop7yUswru0Ifu>k`E2dIj;jj={Kmeo-q+J2kXyPi-yzP;*QF)Z(&VYIGS-tld?- z4ns{Zl@hBi}tQ>;77gi@A?M)y1rozfAU}rf7lxSF#Yg57N#G5-@^36?^u|A z_&p5M55JRP`r-F8%sL9ct6|nr_`MBtUGO^`PU}%=e+YJd2il(BhcJHl-3a5KGvQ$R z<*YcEcsN52CQi=wUY#bS5B|*?{hCkWG0((l z{)t~*7#H(w$IJX1CJ)TBVe-Q~8zyhevtjbdJR2s@%(G$iVxA477xQd5-CyVCcIK(J zXZ{M~hj}fGf9AU|{W1@RiHG?yOq|S{Vf1324Kpt0*)ZePP9AJee)L1$^iMwRmpmH} z`8Q5pE=<47gJI%fehd>Q z^JW;mm}kR`i+MK8c(s!U+mj#t#Ou7+Kl!v@@@zch-#F35_|eO8VRyW=HxKwRKlnFq z^lLte$2=3K`6qsLVO-3!9WV25m^?7ghRF}}Y?!<;&xXk-^K6(rGtY+6i+MJTUd*%M z^nLhjZfBlqd*-h&ewf$7_-DQg(=YR2n0S~U!^FwF8AdPW*)Zc`o((fz?c~As9WU+81Afd8{>>Zxnor^}&%|l|iC`wKjcmSl{4lSD@y~o0reEg4F!3-yhKZATGmKu$r(wp$JR4@b z+R20M$&Y@>oBqkC{gP+nA^*mSF2>Zxnor^}&%|l|iChkE8h5ZY?qF-&!PdBgt#PNF8h5s*#vN>pJJ=d`ur=;rYuv%s zxPz^62V3I~w#FT7jXT&Hcd#|?U~AmL*0_VMaR*!D4z|Xfc52+&o*H+sHSS<*+`-nk zgROA~TjLJ4#vN>pJJ=d`ur=;rYuv%sxPz^62V3I~w#FT7jXT&HciO2DXM1YL!PdBg zt#Joi;|{jQ9c+y|*cx}RHSS<*+`-nkgROA~TjLJ4#vN>pJJ=d`ur=;rYust)@AS6k z@AR-W?qF-&!PdBgt#Joi;|{jQ9n8Bm0~g*Oe^(A0drSE9th9gi;p@)`7aZ|av>(-S z|8UtJ>0OB^(kwI&a_a`ZpuvXY9Hx zGX4)+k-n4ZXZZa2(M~^IF8C=j{rsouACc+j+vzJK)6e}^t&U7T+Udvk^rIj8(Lev% zFaOZ}ek6>Bl_NkNKw`b@}D|ZrS5EroFrO)asq} zXrA7e8S`ns?7x@%9Q8VG#Dm$S)oE?v=OF{Ln)|2qhX)^jI6JRyTBCqVSNJlvr_Blf zq_qw{JM8eZ9)i!Z-%O5e=xgSh_aYO+2SsU*bmXhjHSA{bQT!Ke|0T?COD$ zCtTbin?2}}$md^hbM{@OCnMiCqkYzJ?690Kx%v6L&C4}kj?8CA4SF>)KF^x`Mr8WB z^?|n|S9-Tcw*Ki}k@=VZ&Gq&{Aui&JT!>fZb9^2<{_qRa5B68PHaPa}i%R7@rpC5B53fJ9G0#J#TmH`T zuW8lk zm7gdbc}P*~aPG7+kuQ7m^3bhZxyV0Wad~KcX8FjQXI>t946YD)d!;MF<1;EoUb6Yh z&~9_3$itgo5mx_IHFEa&m0|d8i8nrdRT#RgO0+jVxlMTCyu=^$YZInUs2uHcuWu6$ z*f;S-KVB6|4cH;t@4cvT=oR*iT(90c*GyOg;z!;UjB6Tu+MXeJD*=QZ2vg%$@A7_ zuQl5v_I1LM>$B{W#My-#vMra^j`lYDZ^}k4O}y_bTe3sjrI;TJ+p{ZXCT`rMbU68t zx0Mc)_WdQ=&#&`Ow&SA2o0o6N_WfXav=2LHQ#SvDUnB2%{f6wk`M*Ve<(T!^ z)>7%&efBTq!zcSCpP!eh5SH(g_~?Brgq5`uKXPJ?&~Ufpf9J|OhsIr!z1_$i!y7v$ z-myWIuz11G(f?h~Rtgs_PTX}<&G7N|^x0h|)(Yn?O|doURy%|bQ*7UyR5vX6aYg*> zj&Ifp*T0g+e(b1y!xvpsoClt|PpH`8_t@suetU&hJ=0j4Zm1g`xF*d#Zf#UA95{1T zY;*n>^~3f$Ya%~5uVGkz#@fh#9Ctuidh*|qe_YWx98zgr`XrzCuQ?;E{3i8v&3&hbfBGc;e(fn? z$?b`IbUZ2S|5V~xrB4jw|4uySzH>tMVDfWk)eFK&#r{tpaY^X7AoW$|ly>2_+5g0t zE7ZI?G#jx!@@`$O4*OldEpqc)uMW-YZ;d>DZM#tB*UgcStky1UowO0h&-g(6=A{8>mxr~=JK%k)Wpm8ogaz{b+`F$>HPiN@Kv|OQww#+&v+s6 z6YXY)W*ZYK;7S`fC3OKnD8w=k?9ow#-1@51yxiF^O~ zV`z7FYJYk8AHx?zlb=52mV_CV65p_Daaj9uYQN~~MPbU#iFY0KeR!^2;*F305k5RD zU2k{(xgrc6m9DF~b5|5<45sVq@P}7~VJ*^iHKO{8Fr{v~u3o(1&oHWXx;~q%SP>2{ zldjLLt5<}{mnB}bc|}+`Ch@ipe+lRQm^2!?WqEjFdg6nc{1)onop?j5-@~cvlD_Ys z|3?^iO5#6`_%n3BDP02<*ZvuPza?F_uk=_Ej=mtxrQcb+BJ^yKuI;WB{|Yz%`B%(s znG-(E`<;Ew$D!TLDdslUObweFr?E`v_fdFb*EGg9^QMGBb<@}%x@1at_wQpV z8@i>j?6Bd((D8%h|HwV2gbTN)`|H6@Q^Lq*DV`g)O$jGokm7u8!bf4mB`N-C&rJ~#A4fiJ#-HK3iCN?Z*RKjM)fpf8 z{WjY}#ZqaVu+J&m!$%*bwZzG5w}qlXsm-{K+rq|M#>Mt$W?RG0*S#Bg;^Hmg;2vWm zcUiPK^qTfg!uB1*8z!t ze|cj#vu)xRXBKKEludm8ADhDqcc$mU@?W=v-V@Sq$vvlT4d>2Y8e@Lzj%{J^SLqsf zaNV}>@#rPdzNL_>L+<|}@>wI-g)?tUJ}1{+7tZUD__{~_4i9%ueD{jK!jMOk{~158 z3}2m>`klFPRam|(aj3f{j6EZ@Z&J8^+uWP@p6U06qsG;Z&-%Te>k|H)miW?vcZCNw zCocEq?ct(x_ls>FsBv4E^Ks(Rvu_P|URW>MOO?4L%-x)L#HgFXA7krB`<3(ChrRAj z?@0}Mw0*dvMS4#P`{z~Cds4LD@^xbTRPVok{4D-&KRCTVMZeXH5);p3&Cc_vQtPyFh#@vY|JhA&e-zns!MT=`PU^WsCA zhx_kI`TuKMvvBLBNuyZ@9~wrTl60)Gu34ykZkkW7fAY|9%U6jf4LT&;dD%WO=lyZcUlaQG*eTivSGXg5cHWMWM~}KK zoZUR}izjyol@CeWaOusV&Z&v#4rw2@+@ARDPB(1hb6vjr>>#j%ZaD{+B=MGUnBPW(xH9AYhP85{OT!v!dp!fpH{a}-{8@mqrKm! z1${SGi(Kls-r=JU0_PkifBH;36zrfXyWuI+r(2iO0QhW!USv#1rPX2@jo}c-8cF;f&?!zMg!;HQ|a|6Mr=N z+Hmzx>3iVf$F2(<&QAR38|R0Y_e}Tr(fwP6sh1^Q*y*$|>Gi~a6|VnLx1{zL)jm8t zvqSP(cGclw#PGz~{zr!E4oopzHTkIU&B(+DK6`X%wNvu5YdAK{Xq)&yJDm`Ic{=f_ z53~rsPfA>7%gN!_4-yylGEFX3_`gFIPA&W$eDFlt|z}biSv(WGox~i$vy5oF!D27u9|$xYmFlp z_I6JG?Zty4KX&DplNVmrByyW|rLyjyCoUPYeG!{|!S)5)7i?d!eZlqx+gG#~&TDYI zoZSEuf61}SwBMy|t#JF|CPj~37ILP2$D>mYxee~S;LC^N1nWDdDi#310sL%`d?Z75eG(oV&nSkyNQh>mpZpp81wu= zk^8?{K2&d&^3&y}DxpkBJfuzaa9SZJ^ws3hi^8G5rO(Rb(A<_}+BZL-OL%#QKKg}Ut$PifF6JUKsI|A!9h8xA=nao0)xLXTV0J@UXy{lmP+ z_K(-wUndL*wO&v6QNKY0!qD*zqrK6<0bxy1y4M^FV>BMvcwpm!jR!U!*mz*$fsF?? z9@uzbUNJk)4kF7mB! z3=QpnuNZm5#gB%G|5SWxuuG3J7<059Sb$|dL8n2 zzENmM&U;*~-YqNj&xi+ZSwKuzkVy1=|;FU$A|_-=1BgsPNp)_&z-N zzG_9c?>H-Rx1y>=9sZaXd8a0oi?($8G4i~H6^owe{#WGX3(6PO?7uzo?EjQ2T0XGw z*U^HXlPZ=idTmyX$i2=gQ*^_$y(5#)!n5iBU~*^-ura{K02>2r46rf4#sC`wYz&bL z&riq8vlPZ&G6tEk@GL6qJ&R+MOZtI%4j=mSSJ4m8;ZkkBh|F`i%kXKDc@CdDD@5iw zd_?nck$Dbps`h$hp2MeR&qn4sy!olYk&Tmh>_rVX(%S18H0#}ABup7${QG7o@>hxq|aoXi_w;%7bqGcM*CFym$Z0h0&jC2+}@ z?TdKq3$`!VzF_-;?F+Uq*uG%?&dl{tI434-+Hgzw@~Zxk4_$diXw=}DWG`If=Y2Ub za@otPgjqNK6q$ed-+Y$;Ug$3}pX2k`@rPfSe&|p8tmmH2+aJE)o00LuIu>p4KjW4! zBGb>)C(MsbKli>;s25piLqEOG{XN+W{p?w0Wn}uvhOCNAKicWX_VlA4`q4lC+Asgz zc=()g;?MZ$$8lkIytFqD_%T2DH*fS~KIz9i(~tS5A9X3Im(2H`+QDiU?Zw)`Y6q(w ztah;4!DdcCgyPY8UOr+QDiEs~xO%u-d_D2df>dcCgyPY6q*G zcJgR@;)B%=Ry$bjV6}tQ4puw3q+ZP1-#h)lqEU@M2t&@P7VbMN@%S&Rgc~*-5bcK) z=IyPXOg!|V@?rm-6Ia?&CX~Bn|JdfPUrL3=Z#9a%d$v96`d!1woxj_fowB7tgVkTwW=2xKTYo4FEaisWOXCc?@zT76Hn1&b)ua(M;wxv_y_;JZ?rS6 z3zsAw)PJ|!-eHH@dHcW5-#hp7@L6?o|9gGEU*7NAtLo?R?0!$fV4UsSHwwmo@uWua ztUAVp-SN`iJmAOt;NQH_ulXb%^GuxPpZL|Kq+T+=p&T!49$@nWn>W~e!sZz^|1df- zURb?gb=1yyZO?dNuLs!c1orxYy{=%dH`wbCE;&Z?fZhDS<_$KVuz7~fKddgWdco?b z9er(Y9=sl~d!4{uKd{#o?DYnF9m1S_d1AGy@md{s=iT9szpF&<{mt#+yAg@sxT{0> zdB4OJ``#3~-(ESkIkL_Tq3W<5BENRkwV~c~l_Gy}@zvqhz7-?iynDOQ?#c?04}Ys| zJo}RC6Z;z*%jWHee_bXretw-$Ix_zM$x210-&&vi6ZkCg{P+6pk%_b2)!QNy|DlDy zG0=u_4S6{6^j_U_`{Fr0^Y&+z?UVc2drRNkfBDh<^L}US^k5#(d-H%F^Mil$M!)8hc+4|#nt$R~my&wPzd!j=K3>>7z~%=wZ?O4<%`?DYeCUBO;&u-746a*XByyZM358*Dyd^9-ARSY2TC zg4Izw*Qf2xgVzIguM^no2ll#xz20E2L-_yiw^GU9q%zM+nCE3lX1>bbdQKZruc*?U z)5GaQ?=S3GPrUxJZsDaFiQ9MY9#(8i-0OrMVa|#5WBYr4?h(#?JaNmLdWJ=75-*w2 zGdyucgV?6U4!y#Og}=Grf5_gw;@^5;?5`HqPhi@g->^|+{8WA^}yV>!=Z?3y1ju+n6tVe`EWv<+859Ks$vI1y=>ZI2&X^-$ z7IQ|FH&yfX_vYO9Snuq0?z?B7we}x-`P)TJRdrSOOm|NYJe1h{iMr6de=U@E)l(PL zHc4F3T1}XKKw=H=-{inniS3H3NZm0KU%2*@{4`bSzpNydPb8bw`aj9+Gx`|Mt=KAJ z+rAcZ*3{o*=uC+(HB=J{)=GTfo0_0ASK{9#>O#1c#NN>wLeJ}xo!`?m1>bQJKh)I{ zoQ~z#>Epq`98xwEMdk(Yv;H^@}5_Dn;5B7QgAXjlgFgx@B@ZOts?zL!h{w{H?J z*=HgQdwdM#v%O7(TSnO!&wz3h;r*H{WCv4ILHBqD@-?tonTBlE%2Zh2Efx9XD-$7Z zRWkClohCxq%|v8kAj(}6kOLRB6ka!oM{cO!QZQWtvEnv{IzNwP_+x>w7sBD^8j{ee!za`W|IyICF>ds`y*`5@cxClur^vd#N1qK=mO%)DGm0+J}5nzYWKTzmu(X9UOzbPFIr3 z9El&#{w02sXn^udb=8C=RuU)ARTqEvip1)ihCucAf6)}EoePHALW{|@@mdXi9pTw5 zX`JR=(Gik{OXKwJy>Ddg_BysYC3~5stF#4&@Y=}p7i$TA($1MiS>i4$du(0+qSPHtD8uCRs20?1NZ6Mj+$i28tl~(zUJuL zKAX^)HCnGD47#sx%k1dDwr{H=G+k25*0_NYTW^fE@U?es+if%2u)h5?1;5>OkTadM zh1~;c+xEQCl>PEpO>pXFfbuhgHHC@6bx`i)F0RMzYui2>T$ep^r;5yPAnA-MQxmNE z8laB8ou<$#whro4&D9nP$Je$E%+_H0m5BE@6GE?#8Ff%6e5tnJ z>{i=$$EdeV>7^=?)=fi=2MfV&U^?>H=cWSJ zK8A&U_}tc9I5#W-`Sp8KVX1Kp3;i(jvAOVGHx=cX!_9@^eG*XaQ)w!6(2ZfCAD$^N z7nt{%sN?s>T(H$nMV(FK&4tt56HupxmYGoYC7OkPIK9$b*rAb%ayxf(VMzM~lpixN z6AnL#W})vfx)#E%>J*e4Eie~~OcGE&%E(M`xE{?ye@lL9E=*L*LY;<5%1L|U5y<_QR*+TMuE;Sh zJ`>h-F|vkQC0RGk2f4i8MKUnf3j4;nZj~grhYxa${b%yLcoFimaPd9(6j$UqGs+2* zKOFh`&D*5+R0jD<^8+NOpA=8*>p=4Ro@7&QUr~CFEV|zg^)0WQCR#sCk%zWAMW$Id zMIQaRfYi=!h#WJOCr+duvWGAHy*2~nqdU{dr1f=>nf*!RiK8U%L}E$(%aZ=W4v}Q- z9m$U2?<3^QM9Kav$6zw2l^I@ZGBk+9*7*Zjp3k|9gNW0bKQKSVD}%|J17^tEn}(5# zmzyH%_KhT6#y3L#ayFKX9$6o`@8Kj8S7LztRE#sRst)oyuWT~ryd-xY$CEOJq~HB< z0qLTU>OU;Es1q++-fPg&7vvb?_;>lS3eZhBWh&Z;*;w%nFY zbo>pFO9PU~>_CZ+T1JxREhHU1w_q~fL%J4fblLG0wjFA>)Z!J!8MCd3)KB`1d}+>c zvgr6X~H@fviXeIlxLoHua-Lo=+0yAF=6Us~2-4B|JF>S? zBAJ)`6M55?EaKd+3i+(~`;(SD{DBJS+aIG&wU>oenVGKfSx8i?E`I*1&-Ivn|6X%Nva9F3e)6hvlc3}ok@ z&|sUM2_nW@2C@m8YO{OJ1(9PD2Vy>htHl1iy&rP?%OKKjb${f_+d(99_JDuTf!Jo2 z1d+;bqcF}{qF?c30`iELTEfmQ8n&KUUzmf(w1lR<8n%aqeqrWq5$7}aG;BxfeP(J; z(h|D0(zKmf=OZ(c)e^e6Xxgq``HpcCf46P^dQID?Wfja0b1lKwSJQTJ@0ZNg2tC2w zLI-)@Jbhv287;K`sHeX0!CV{dr|ako(^qJt{c#WUgxZ2O+7A$a)3)wsZL}X2uO}RA zqJ#FU83UoE?{gO7l*cT$KU8QST;?lKr%&U(Z68SP@BD=J!;SZm4)dh@e9q&&q$=hu z&e>kX?IoAX-?Fd7*t#v*OOBeo!`RC63Q0%DYN^)Z-=VU}RKxXD&W9|*v+Br$uBVWU z0TLUZjU%5Dr{QP~smhwKwZ(5LtfnJK7wW8$edreMa8bQT(3ULCtpB zhbHWTCaI+Ojl`W9o?Kd>W_$O+4`z;iB#Hj;n+2UQhNRi-1M5<AKDkSFnR6ieuJuDxEOXLe;eaPDLu4lhx0ue0>uC#xady zn(0+l{B{$ss^V|9`zoRFUn#yyX#A<^0YqP|CAOvHco13lwITBI&7mZ4P95Z_w<5?v ze;s6(fH)H5uYufUUkVw$MGd(mI!ncIk(^2=Vrrr4+FhANDw|zao>Tc6xAl@Lh9Ba* z@!IMpSjW}Nj*?l^^pT&4^USceO|W*!wUUUomj=p>osW{6m3k<@Y!XD~mo&yYj_;hK z(m9}>L=<&3P$#F)Q8Hw|9_s8kbzEhCe$O10&Zh5)WKpm>>gb(5r;6v*!{aJn-hFda zIwtSWsbU-PpO;qD zuum(WSJyPZttnUXJ!kn|^nSBi!lYioI1ltIsUu9Ca0J<^yp9mv>Imklw`DCMLMs@# zyt<5x()@)wpASADBcA*~PFVYZXd6j$^+RQ4M8D@R)X#2qnH)Ji6mg^%@*W00;q^L=R*^q>G=9RdRD$@w$V{R_Qs7(awe6yTHCU_?y z&wIU>SSOVs%j1#9dGCcU@mc)e*RngDiR+YHlyA5#{tm-_Cy@>JE+UWE zi^xusHxa|SH<9IjN-VE`YjiY>_gD(T)?S}Pq6xkOSjZPC}@$LC4WQmO6o zJ}(~&?MB}vfdSIqORU}((sAony!M9OdvZEt4f4wlugLKWvyrpTl#ylXPRKK|Y6)X| z9YU6mS@~FYons(Om=JJIKAUPq0S6yKE#sH{VB2cJUx%K3_wwZ7lwd&6lT<=iM7aHstZhODl(y zIfYVv_s0*#cP{YW4dk;l0#y2A^tY+(G|7lklH)fqZ>Oeft9OxwH^xkve?NZ{TS&eysIxQd6me}W z?PbAz(#YT$$}gq|lLlvABHz3lN_?%~Ap7`*lOKxr$dl3|$&q4dPwZ6BSn{h#+Kbz% znMm9^O8aKvzfwq-Hxei7i}ynvX^*a=b`H6`LXzKn!I6@_U(jaxmV9z>{wL(Y=Z=%3 zdLNMI1P73BFUpaHi3f>?{!`>@>>QF_=7Y~r>!_t&tcC2i6iU zg&#uwn(nLexs$w(@_CWGri$eIB=*Vr#<8-Lk zLJ&G-VQjWbn+Q(n$;f@_lw*dp@#D3FMp7W zzcrBM`jjD_Hkm(2^;->FV7Y!xcG_R7BD#zk>dUW{>&ta$Y+#=<|o${F%Wb>s}~ z8dY+gsOh?6-i!_JlBRR)kY9hgPBtEziuJ8&eIcJyP5N+-wCFYg_2t(VTs=pQgh~7A za$oYf-1d4`Nsd~7^edmg$=5h?`*NFf{~Yp=`t~4+)@0ERmBVvcJ~wtgy`NYuaz&j# zyXSv2X+Jqo<$`UL&*yJ>?jkoX4MLmpIlO!gCBIf4L$iEOVm)>vUOV!E2MNEq1lf6; zC#f{th`wsN&&$^rV`5j5I(2+eUw-YiMyp7CM_;rl_a$G~yk6l>9=-8G9r?3E{;ZMP zm)i_{?m>#C9>r@5^v024t0Is?=X#J~vyNgsHLd&P>#RpM3&^&UiKs8X_EydUqLrVB zHs!wL>pt~6j>NYl33cRaI{DgDZeMOQYx-_7s_!+t_Enqhnay9WA?VvXC$ey(ykcl(nkbTsPd~VoL9wT>~oILIB%UeOKAK}z0a!J1#;S6(5HC-J2XFFzuShB z7$^8$x}yjg;_x78%;LV3EYoUMhz?P<_Y`wF7yh_936tZ?lz; zN%w^WZ7!{TOcI7lHQF_jVheQv7k zn5?;>vOjKriOO%q?dz&|0!CjaG|tsOuc_j1^XQtYT_C6J1$~+autW0$_UEh?FlO*; zJw@u<5Kpji0m>oHk4Ghj`0IU@7}_<>uu#=rDu+B!eaH{B19_wNA)nN*eBbh~a7L)X zl3%2-?MB=?{W#+rF{?cXc~-$YLNpzbMIV~S-yuae;@Hzd)M&# z;1=S%t_Q~aD|I=kZ8rotZM-|V6YYZhE!lz0|F#7AO@|@m<+&}$E6npYDdN z6Y5GXZ(V`xF?kGmS-BPY*xKR5`lr;N2ey~?nxH>}{P1b%oHpn`Jyzep|-hM}~MhZG3|KpK=CF{!Zu5o`3r*oQIdc+q&K6H%WfD9^Y?ntpA-fES`n@ zc;}gNRn(7UcS4ZAq75`;n{OEASo;>sgS8uT53ypX)3jgPmNX zbI4%-{oNbL;MdOLF*3yC9{B=UekMVFcH)2Xe8T_e`E%ttF32I>2LPsLlYr&tk?1)Y zkkhj$z;u5GSiUDCKezn<`%E&OKSK<3{tQg#&%kv4Oyw|trur~11*Y?7U^;&Wrt@cD zI)4VH^Jic>e+H)WXJ9&i2B!08U^;&Wrt@cDI)4VH^Jic>e+H)WXJ9&irgE4+Q+=2} z1Jn64Fr7aG)A=(noj(K9`7&c&$O1#;S6(5HC-J2XFF|0$V(af08R z+0uOy;tAU8igJiEv;Aabi2rD-DXMmzUnMcLm&zdzR3Gv~?LgkBeaI*E3wb_!yc}&p z{=3yFLxy@?wUO?n6=J92^siwt%izPpVK_FZS(LI%Gd#rN;fHy|F3 z$`WLV^K)m3A^u-!*HI4jda+evXfKsR9;iO#huVR>QTvcj>KF1%AY>Gy6_4&RGWefW+Hn11gDoU8oa4VZrK228(q z1E$}*0n_i@fT3RSy&Ew7-VK<3?*>f2cLS#1y8+Yh-GJ%$Zou?=H(>g`8!-LejmqJB zH>wZcy8+Yh-GJ%$Zou?=H(>g`8!-Le4H)8w@7jQ&T~oyG-GJ%$Zou?=H(>g`8!-Le z4H)tX-@5_JzxR=^<>k*!`TS7+oTUtV`2WheT={ua`8m~pC#fYiIeHx|+_&$@iM%^Q(X6yD<5j zRzA;^?;FVXE^0bgEMH&zr_AT&`!hA2NtW+@{gwBcYC0zz-FP{%`uqsboszOK#H;!& zvIEnHbXk_F;_%V?RXT^ZETsbbTae z$mf68HyZNq3;w&liJ8-lD|8Xzn_x7+iLJ6fE4(YV-A-l z9V9`qPmtX`50kaYPmv3~Pm#vk-XM3(KTgb+NM|`3_~w(__dcRrU;K7}$^MMoxpfZd z_vs7rj1HN^YR6aPxHhTe=}L+Fc1tAB@+6&a9! zyS7Kj^Gg-TL^p)goB0yCrgJ7Woez=sL)up%Z}Rv1HNDfP;}P^}{(mJTem3C4xJ%;S$?b#J?(q}P!1t8i^&ibSLt;B9P!4^G^7XnQq%^D> z%DrulkcQbEk@Mb%6X&ot$Y;!=$enFw$on&5$@+j6$Tt3BpDAsMd}VJciSaQ;?iQ1& z;};`_rn}{)jq6PM?tCe+R7i#f; zJI?@e`MHIfz6X?_F_526Nb0nO^z80{_MhBXL%uprMV6mEke?Hfzw4Ku6Q~^KOsZY{ z@!I!`97*NygUIqT0P^?s@^|j?_x0h+UC41Z7q8u$KAj}$pF}orSWF&&xPUzB*CtXg z;|4NapF$q!`V^S1Pl4(Bl*(a!NA+Rd2Ta$ez;t~IOxLHtbbSg;*QdaAeF{w1r@(Z5 z3QX6hz;t~IOxLHtbbSg;*QdaAeF{w1r@(Z5O69OVrTVZw1*Yp$V7fj9rt4E+x;_P_ z>r-I5J_Uw$!TJ=Ku1|sK`V^S1Pl4(B6qv40fg#VZzX445e}L)!4=~gV_J61x_D`rj z?Ee6R9oYW?2K%u80}Os){|6Z2f&Cv~h!ggIfFXX^{{e<}!Tt|0w3o^u4^$uWL+wD` zsC~#M^$U5X@j$(3oKP3I@hdY%NBo+kmO=ShHJ9}>=!0Mqj%!1O!`Fg;HKOwW@5)AJ<2 z^gIbLJx>Bm&yxVt^CVOb=SiqOoF@UM=ShI+c@kiHo&=blCjqACNr35j5@2W-oF@UM z=ShI+c@kiHo&=blCjqACNr2^Nz2xV_YC5|mKU*a~msQhQDfzcQHGStU|1Q3!GjH-U zQS$RtHJx#ipCOc=Kdk9Yp!`g){G71-EUx@aulx+N{9LsB?6Ld|v;4ePO=q*^=gI%< zy!Wl!Vd8x8DI0P25wo-JVbc4}Q}%v+4fbDoR?6q(^0R94vvYs;o2frL2auoflb<=P z>07ElJ6DmPfs~)gtmzvo`TX#onRm(0j{Y;>RYC1KCfZ=_pr$Wh*-Am>f7obl<;W?}`0zv;Qe_n190_75k@rjaJh+eEHda`I&!t z{PLXCwAQZaI|cb3>A&(0U4AC2rtg~N`?P=d%+;}|a&r9;i~B9pu6`t5_nndDXH?|h zCH<$I8Prc*G`LSP6XVU2iV)^3(>J+VxCq9e5piZj?X=HQ8SJa7F7*81gFQ{XE zKaG68@)dR5hUb!yV#&^sdue3GyRVWjhg|ZsT(YyeQ2`kp{SocdcgZE4)g_%#Z3;+A z{ztUare^^$xcw2YmG5=b)c555S^m8HPuUNVKWA%tp8ltNvm7#`h;*IV3F|vyLlKGX z-wA6vvATeGdYhxX!GR*u(xemCcU*%);^JVAI{uyW$VZ=Ms581%A?aaejyf8>@<`ng z%}@u{eS9-x)LGpxk94fx40S+W^1ujnR@M^Vi7V}Z{B5`q>ZqwFsO%*6j#S07<6FGS zPHNjoRXnqjswBi!waRDg3h*WYJWrE&LvJF_aU7iD=JfoUCqX&r%S9jW~9cf0?- zcf0iL@!x-I<3HnXZOH3I8SaOFpBw+{pBtCgt17S$ziF$E;IY4yYczWV|G-~IDEL;+ z-5u`0+lV}A{|hcU#hH)Tp(7Z7|HS3pbmIs6>IgwgHTW>wX?)a1@o$a1t;65hHZ zNnGU(GJ3x=+eq7;T&i=6IJOzjIyRe0LJIG(2hNXSD}NfXr~L1*{19h$q)R=vyY_8% zyM-I8Q@=L*ZQM<^aLG*8;-N0vI=+Op+2p~J&)V#V=hxUqnM>G}Z?xF)##h)|nl zE%2_*-ip1$&Km5@PIIouHZH!))_LN{`Y&$C+L&asOHI_s=SNmT^!GCMcq=s${?JM& z5_wQ-HS+DQmGI89oV}8zMf!HGFB~b!VYQA)T$B8mc+M2`-#)GDSK5bX?C^dCy#4)uY@@vGHQ9+6`jnm5xPW&R zeeIm{jD2lhz#m%JRrqqLjE$(M1>o65+#ieLOaF<1AGm6ED_DTiwHvdPX&DYu%2+2m_KDd#oms1JNf zVwy_%(HF1nE;6*e&YNe%caW6xH`AYyPHhYL!(!g#`f{7{IOVa)+a+)Ni|bMzpkK-J zCeNolKZ^`CS@?VI1D6`wCNxrK9UEsWfV0MbWjZ=^XMlfdmotkDeURO*oM8$)1alQKj4t4RL-flBp=njGyi_!H`I>_-oW=;^b|RLNhE*$ z(*@-2t4{JKlT(m0zdqm_toB3pw))6Fj~IqLYF{<)?f4SokA9#*EIYrp0bk4dYLL~J z=5fG=&wlc3>jpePt z$f7-kXjlAwG!4OTl;{r`{7^agq59y5+5tb*KKx7l!p~_ua2<^k?9uqakJz`Olp~} zj9>hl6X*;246^bbi>$o&Qaf-@MpoXdk)eIyPZV#{>?q)JT{WQzx@QV_%AR1KeG69 zUerStuj9q*kwtsFXjcLDML*D&qJWih4p^zr11s$yEA1mI{UR&lK~~0ztc)KSatQvw zCin+`zz`Ss1BQ6PA2757`~gGzz#lNQ8~g!7KENL^-7 zEBzuX<3U!&iL8ttSza%BpHYqx>`ThAL;K#}V_Y1+f5kDLvaEzT(#p_w_}=~89Gk1i zlgBmSGb2wUrz~^iTl~sF=63t??gbIZ;=jE3|H$Icc~K8pyp9*IM;7hzqFn{p7yaP4 z16Im8V5L3}th9ryw2!Rxi>!1N;F)p1>b4N6l$+Cf&@M^^epR>p&@j1yTIKeDo2|G+S= zsT^3D2OOu${2(jyhOEpdvNF%e%KRfM>w-+{2=-|mfoUCqmHIre(hjoHKC;p;vN9fI zWt_;$_>pNH!KN|~R3GaIa%J97uFNMgt)ns?tRpb3BQUL_WJju_OpfemvIs(%=0?!`guh{CCj&)qNT!VQW7>9iMrh>^YJd7M4xPYndD~+!;0sf5D z;OQt=H#@?3cCkc$_%wkj2zibDZMsheB*e=+|BlfBlE)e0GH=w)gwtc%ErdiM-h+ zgg^GE2Ln2d%y;nZtmh(EaI^Wv1v`*kdsy?gvqF%yHhty%-o+zd8N8Moub+VoeecN0 zEM!_QdF_Cmt6ti??U=;?huZbatCb+JpN}Kg^I`_d*BJ3!TyP5V%zQ0=YO6S8{hl58 zFKfb(!&i*tN0R{Lt-1^Op>=(cw-jvQCtEK=eo6N6K4#;P1FwYgb?vQ?_uq)&*^af5 z&m<@Fua=#`emi+U27mm;B54k=Ig78o@1PCD+0P@39~7IB2ki1ao$oYc0|)HcJ(8~D@JurLZbJ{M8AWe46Z`P7J*N~VGo?L;FL^DPEV~FE*3kjW$1?NA>_hJT#*<07zYcjoK>%}i zvmNqDqbMfRpfU1J&lF~4k1X8ZSQVeiY~NX)2X;=*%VdTP*Tek*$KqtB)U*IO?0Eze z+PN76I?fjRnYZo6AXhxvz;u1I30dRzNaovz{m6HY7%`Qek;n!~d5X)eQ;@X`D{Z#= zWm3+gEb4GnN4%D&*NQfIYE$&ZQ(s~XJdHt&ji<4RG4nKLu`N7pi`YhBfX!rP`S4xH*&7+gyy6h@vWZ5F_g-m@`EX^KBDrZI z%6%O6E3!P&kUh3*DXLdwA{Y0l%-zsMdKOGg9l%}KCp`<^o=xZa#7WPB=kKbyv+Ja1 z!ItT5_`BxecZG$pZ7Nzjhu0AE1y1a5wc@&85r zsYzq_d7t(n+kETHYu^q3Mfw9O(4xQpUzD`1Ro_>NGye9+s_!z>C*3Cs;uqT6aYbzkPTM*54Dn5>! zX&1=#Ia!2!A=aDw{re2^O|wbdk*VjA)rMMe_itQ47W*ByZQMm<8Yhfd=4Cq9AUznz zV~lSiPN!!SvLSbpyLU1UnYI_MZQ0-ims^>E^4Dj1uF5SJ+5J^IH)6hk zTtcF_h#$w1S49PIg-?qlZsyH3Z+I5@w4*C`cJ6uPuJa11VmgZT=)F$+wfT$MS(QtzG`h)4geM;w%hd#06 zT)S|{YRBC;p|#XcDhw8LZR3xjJhj7mPNPKXOZBgKaaPAuQ7*3YxYxU+{s!`xN%1QE zlHoDPU?**PBr@1<`Xd|}{H}X<1R3Hf_XtIXID2f6>XKGJOVMz{PL!{VrI~ zfr6=hbsn(O&_aJ^KLD_1QV(ulM|!vPVV?$Y1u^$XpsU1UamSE92X55pr2fS7yycUu3Jx z8cdIN2atER4Od(o8iw2_>6VS~GLmv0Wl@KtI^wlFy;iizQ=6hMp867F;AsqEY&?xk zjG3n~i*4a)Tf{cH}*Gb>|Bc zJ8>DGn%GXXcIT5VyWm)h=rV&p^MlI+`4#7x{HKl1xxfR9XYkdRHroK}70lp&lx?#C zJ0o0X^8E)n;Mg48aRz^?n$H6{?5V~C4`P0A^0(D)sjZk-)E{|VS06>uIHwF(s} zdpaUta{i`ZZyF;fo@mIVWT+$G2x!N=KYCFCcE0cF$xMB>7kSFCe#~@(*2n{v4Pthy zRrLm)TOS87uV0_f1MYQ=Ve;3`;ecxmv1D}GWFV_0wq!zHyh85eqsvTRT9*f%Wl!!Z z%p6-GuUrzY=(njmvNJb8;jq3B^0^D^Y}!-~MAjIwGq2+niAQ%I!5yr&MfvM5k=)eG zZpcrYJmjkSSRe;J*W-USH$Wb9#e~IXmDYsL2bs}ff(LCfE^!~9WvNvi=ucyO9Y*P#R@reJHF-^gkr><1@{ip7_#qhEfc_7;`4N3Ewu|>Ka*i!ojBVYd zLhjio7Gn#EO5xtN9*VJDUYNucJ{yU#Mej)F4!JvHYzHPMa<96~!q{GIj^Iv@T!nt; z>g?j|7q3MQ3|Pu_YP$isMdmP0v2YVI-?0Jb9J&}|D>na-_n>qZ#@66oL7t&c)bD16J5HwOE0% zjk|u$CV#yb`fdNEq2l@tPvkZI`Y80?O7Zl!nWLC~T#D0UzL(!ZXa7i4*SNINd*JEVEnZ435(x>)}ij%VRiB%We&3*3OB>aT@u3FvDIth~soj zm(fhI!Dbw%jn9r}mMrnaahf>5ok`>5I8B;5 zf$?()?G58}9yg9z{JfhDjMKNKPR!1r0vi~oJLgYkt`04;fpHohHJka>Sw{im^pNFJ zX6?>a3K*x&FK%SGmg5z0e^@s|T&tFDM4r5B4RfP;0CJVxO2%Vr9P;?B)0m%y=?aK# zg!V+HGATm=u@!wD&IDgcS3qn=xBD|o+;S8UTeHV3(>On^5ZiY#x1o7IFt%Tz_RO1mx(vi-+-w{(dbBYEvH8c^Gpiq(A@{yNn7Q4qJ#t;X z4|AhkSLE&IIxq^y&J4uX!q|-IXxN^C*mjO@#B`k8ih zvt@c-lAkNa_TBw%-kLN=jO~@WHaB#Z1I9Kg(uVuKNQ&)d(~(@O{>~Vi!hRNK@o*Z( z=J~~kyB0VfW7Fvq#?`;M3S;=}mC4OxHp78$ah36?Mhfj$Tyb?{~GtytV0}%NK=q z#n?tYs?RsQ*$ZR4?Ae0%v$Mt6qIY!Wopc7E-y!Zj_=`CTaz5y>yfjIop79fkDAE8XvyF>t)DZNZ);#Gjnf4V ze8_k$j4jyRiGSE23GX2jS54uKzU;$$NRM4}`GE&l*uYq*Gjj$1nY6Kiaaz#Mo7dPp zsTYh>192TRH@YR>$KDlq@e^l9Axx!tR!d2D+ZE$;Y5 zX?`n@fildQ|C#uy4(QW10@F4E&uF2=oOSuudj;ca`}KqxQ#Jpy4eH|<4!zN%0$H|3bbze5%0CYB&SS+YQ}W@iPmPO6cj?fzfL*8Nx5STEINz>erA z7yJQ>e)7N{u;_;af54(24*UU&emL+4Ec)S|i~fK`KOFc27X5JG4_NfWgFj%=4-fu; zML#_F0~Y;o;15{z!+}3w(GLgykbj4A;15{z!+}3w(GLgyfJHxf;13w`2mXK|f8Y-o z@(2EaA%EZx81e`HfFXZkyO1G&;1A@GKkx?(`2&Bz@_JE*ekEsGN08Gx0@FGI(>fw6 z>j+Hi2u$k;OzQ|t>j+Hi2u$k;OzQ|t>j+Hi2u$k;OzQ|t>j(^a1%JS_j=;2zz_gCQ zw2sKiIs(%=0@FGI(>emvIs(%=0@FGI(>emvIs(%=0@FGI(>emvIs%LPa^hJspD62r z6aIn4_A10UdJXcLD7JmG$g6rg7C6}+=uoUM+ML&W<}YVet^aF(pmhg1tvfKSJ20&~ z^55h4-!XpwpY=Ui_St4!$uJw}0}9R4How-VAfGH-t{7Kx#s>OB(LNs=+t{Z{ouP_f z>$@mGUd!ur?;+pR6>zO#LXM(OSQ7>GnWBA~3ftJ3sI&8VK<+ASP1Kn`AW)J2z#DaH zc@4E0^34l%Vh$|MyM6pM+HW^$uwtQY66)-H-Y9RCwh!urjLXkkSCNA{XTk$*UVJ=( zIxz>{i`ROf&U^k{-d=~PsN?ABme<|)6zYVG>%*<9=!H5r0yMd@3isX+^RLC$+_bA{ zsPmp*#O-x>jP3Q%SLZZ8zsd!jWBI$dNguYO&W!*c@!C=xBQaW~d1fwtd7$(8LMGSQ z_7BwY(DxFrotFpsX&MllH|xO#)amP1#KkXZZv**>(Q@a^TxxTmGxkfbyxE<yh8qkiL^}rr=W_BByGs0er17GV;#&K4<4jkx={gNYIyBc*aW|-P6nOKE( z+D=)=8N?hyotfP(iq~#N9d<>i&1azmb$)%*=L{@3)VY`uCSJQ9b>6AnwMlGp0Cg@r zZJN7iX))@sD_SZ(3y!GssN%Pc`^37aW9|RWCZNB7I`7n66p2lmpw1o3`HEG$!chLG zVxz)+;x5cdre~x=&B7h!v0V!k4Sa53dvzk4vEqFy8ukoBh8wdvS8w7w?ugM1SleCW zaG!9>Yi(91@-XtPR~1at3&qIdzl`|*$l}i#Q4i1Oi`OyY^~j<_Ja8S26YSCW!4KSfp${9t-;7b-Z{zvS^PJ?IOedU-V7o z3MvObR3H3MJK%@fhkvPG_&JRSuA^~+JsLmwf%ZZ?N;#)&7wGfKc7YvarF~?jUu0!G zMAx{)P$befC3)51F?%U2NzcwO`^gd>Z z{9QAHXqa|GF80hMM~r(QCmzcpFL(4t9(d>&Y3Rx#$F$BS%RTxb2ad}oi$VseqWOrgoqY0E2z#8^GWf`V26{1APe?;)Fg14DmzX1Ezga&d@(;8-ZyX zfoU6oX&ZrQ8-ZyXfoU6oX&ZrQ8>yW3ThOQd8SK!0PTL6jw2i>Djli^xz_g9P4OYx0 z$zhF&x$3I85RcnrFJy=_YqJkB#P57_GcvTxVAz&_U}!JZ0jAdiQ=7ol7ch+hn8pSSZG@PC zp^eZMVA@71hqhCF$O$mb6)?>qFwHG6%{efw1u(4{e8M&?ST6~w#3>2->vF`wWD&{UeKp`06S1S&;k2U zJ7Dk&wF8EDpmx9zC)5rY;)mJ+)7r@y`ltI1H&R(D)%WS@31mlxRQIazkwp81)E{Q~ z4JI#{jac`f#eGO%`YPlu-n~hl;bP?dFT0bS0ke@G7h91jOQ#@LT3V9NuN_r zXO7Sx8LqVn?u`sK4O&_ugRia||3HQq9(*!KhS-F}7RV5D`Z;4{Xv;MZX{>GCXh)pH zaiM4an0)L4N5qnxq-JAq$>kiJHrFWYcaF$mZI!k;koZA)dA7 zAvf&dMq>NUN8Z(M2Dx--0rJ-6bIHQG3z5C!7Lwmexqj9%qSH^(f4FEhsa;#L(f8%ptbT=FK5CrWW{T<1e(*-PRiK#*z;ulHcXtqe+_< zQatt}N0Mi^q&VAtvLjQ=rTFFbq741BwWzaL)BzqKUaKj#5qOelbEIe!c$nzROl%`? zt{B5{F$UmIV(ngvu>og_wRw=>Xh&GCSl=&kQ2uHkS+^`BcD$7A>ZeY zLQV5e73#nX^yFr&$xKxtfG>@d?3veO3#97{r#$YDadn=NY4(?Pr5EWQ^1b%?1d`(1M00p2EPq`HzGqk zH|@NUAVL7u_5#=0Xoc+sesR1rwimed%}&@}Du?z`eP}Q6FwqXQ7Z~hAdx60( zv=wB7~+Ta0@L;a(>wsv`~cIu0n>Z}LmjDKntzbfx&YI90n<8CIn>=k{!EKdd?28vt%9erLk$# zp)1?sq#KUYp#|1#(MV~$?|o~-8a7&r^5eVvv8S%Ck#rUfW5>4fM1DHjf$bdQjl8qM zg{_<@%^B8L&S3pIOLM|?9T&0F%_JUTwT69RCF!i1?8UmzlCC{cxP@IEx(V&93fs;O zty+!z{GLC1yu}ja6O(qctyt;)w!7|Lc3qfs&oO(lm)*HnnoE4YDe_e5xv=5+9`=N* zbnpGzVmI6Ds&vnH*y7J#tknf==2~xOn~!XZ{AJJt&fMyfqMH}a{dWnsZ z&(2@T4zDHMlTZHG#HKfChVuM{o7qu$CdixT`Lca3w?<~J`LUTDr2T|`{=3*w0oEw5 zw|NgMT(CvHm9Uo$*)L?~>-av1^vGmv2b->O<@2veySn_iF8@ zZtQ}GlKkiH3GB}_NxyggNH+GQWamZFVD{)x>He<~(1#s=T6!*=jOxv9?YzPIkD^E=x;yX#-ItE;BFrxEj?_>Y3A zEwugNP5Uv>^!F?=Ue6AkkjiA09X`4W8Z9o?zY_bG8XtdmU@k)qD*Ya+cwa~Xf+d~fG=Y+w!-f}_y7HGU$yJr4}9WbN1_E^80 z?S^f?ZG=5b=Q}{^I<0N-mX46=G*yiM9WRCHd)bvWtKry5ZG81D?O?(JZQK*?ZiHL& zwfo^h=~k!{q1z|NcEZ@<3&kEw7`GdS&9o8Rc)J7mf1fG%`Y=amWj$3e?HNZ~ZU1@w z^BfpDOWS`wx;hD#H`Si&+MA4oaChx_Qsp!VEd90p=d#)o)NiWoKOg_>4d1S4`_H3J zJs@nNw*Opv+XRlgX#3CTl&-L*p7z=%jazwX`%jv0c6XsTKhQc^bF}9-TK{2H?Rkcd z>%UWb{vmr#4%PObWT(ned+s9pN2P1eX{4*$RBivMXrzATZ(dz_z0gbJ^UZb$y~NeC z9ED!upXM$?FY&@J`-NU&(_d~vFY!b3Lqacc`mw`8FY&cHM}%Hwob)R5NiQ+2Lwbp6 zebP%z$0fbQWDn^jCOb(lG1*Ugi50!XiXVs-{}3yFBUb!LtoWH&@jtN=7h)w|#7Z2M zaf+`ppW;re><40HpAakihgjKH#L9jnR`wyW5-+Otie6&H55$Uph!wvPEB+)_{7g*o zQuZ6gOWB7?yl9RRM`gaUpOv`NxUwIJm3>02>>pxfUlA+&jX2jj5*}^T_694voq{vZ zwG2jKU|*oU?_ktF1j6F9JxoQXAh2zzz3d4Wujg(tj{%q&O-Xi4~2+ibi5ZBe9~9SkXwVXe3rN z5-S>&anh*FCym64Mq))Hv7(V!(MYUlBvv#MD;kNH%#9Y>iH|KgEqp>8Gxm(|74ehm z=Y$W51DxW7Z;74c^TOxEt^6*CSP<{(94}%-Y&$Jp#7-Hfm@4xr*2J_9?Ezw1pY{eZ z9hdeDG1)_ViJ0u9Jw{CS)7~Ri_T=A8dsWd$tY{=wG!iQsi4~2+ibi5ZBe9~9Skb7A zEBlt_EBjf|NOKg8#EM2@MI*7Ikyz14Y*_udG_!xC*w16%Wk_;ngy8voK1t5+PYM1u zx*{a?2p9bOA%CVLH$-sz)pcNL^B}=-KO4Z}*M5RwngJvZI3YM_aTD0S?3mz;CQZS1 z{gFT83wFByncq5MzhGKtOFb9CwEm_C+FC}(UHn_ydy_qq?M^X=>^#>PaE%*6nl1E*&!)*<~wbW z6#LVz+DVEo8dvnve8ms6j^ZC$U-26qSMev=qxhNZRQyl&D{=WdUJBnFTlta_J7Ohv z#7gXlmDmw0u_IPuN36t-Scx665<6v_v@7$;C&WtZh?Uq8E3qS1Vn?jRj#!Buu@XCC zC3eJ0?1+`v5i7AHR$@o2#Ew{r9kCKSVkLIUIK@txPq8CbVn?jRj#!Buu@XCCC3eJ0 z?1=x47je~#C-FnKLiF75R;qkN%T?pjrG}lftT~V^*=;@{=G=WzAgw=eT=3>4CDQPv zK7!Y`_$)m!@D^P1{Hrw8-%Id?-QOgszNg^C2Hz!Lo_BOC8vp(3(4YAqhkFR7b(TJL z6HM!u>^dlzj(c;~0l{QX@|yjE$<9uR`vjBy{ibM{boK73#Q=r^k@C6rxN}g_xh*vf9x5iIwvW1?r}Tw$No*fV*lu(aYZl9SNuThDE^`K6~EDO z6@QXFil50&#s6f#5|_W@r7*=*i5;;LJ7Ohv#7gXlmDmw0u_IPuN36t-Sc#o7PO($w zlTV11*bytSBUWNZti+C3i5;;LJ7Ohv#7gXlmDmw0u_IPuN36t-Scx665<6lgcEn2T zlyQokGM{2cti+C3i5;;LJ7Ohv#7gXlmDmyg9k07(&)9KYz4K{(gMHK0yS+Cru$#Ji z_jztOt7xjNce(uCQEFYi3vBJq!gck|q0(L!qN{iBy>_q)mfCtZZ1x6*x_W2fZO3AD z^^V4aboGwr&(YO8T1Ty`ceH-IuHMmcLv;0y>{09L9ogB#KwIy~{yVyQN4i{e_3l@4 z#-H)}Z9n~)|9EgkRMvTMqZ%sfe_v1smE-O!ZGehBjm8+DV&~>rO;E8P>oi407mX`= zX};nIT1W8@t*`ivj;r{S>{0wob}IfS`<1x-9WR9`rb_IHmDmw0u_IPuN36t-Scx66 z5<6lgcEn2TlyTCo%qO1^E3qS1Vn?jRj#!Buu@XCCC3eJ0?1+`v5i7AHR$@o2#Ew{r z9kCKSVkLIOO6-W0*eT-_J7qq_j#!Buu@XCCC3eJ0?1+`v5i7AH{ySd8R=RpO(dhvj zq^o!7!)~$hx_b9*brL(Lt9OPSF0nXWy<2lMfw}1Fon6{_R==^f-hJ(Gj(O?oU9T-? z*cM&AGs=r)?{xK!#{0k4);pTtc7(Rx(K_L}dPnQ`*sZO1bX>jJ+ImO!RJGOCJF;_$ zuHKRT8+7%KblK_Z-Qf9e|BPSoOaC+9Z&UW4b+#lG{8_)_#F9V9ZC~y4AA154zy7gv z;i_+c?6>{*+aFytuIQ!tiXUhl#Xq#Z;x{_3;!m>xeSg18A3h__~7Ilk-*oINq?pX+ymYjw$ z47G?4w=cA$@(D@(v9s-^Jk?$eU`5*Zn0-gVn?;+6nANd{vo&S;VA<+3B`5pqD|B>$@(D@(v z9s;tzc5zE~xq=4TSKEqNja#yK6Ak!nUyoVEO_=!%4dm#r#;QSeS$!uBJo~Z)%j#BU z`cWFVm^&Yz#pTEYpK74_;5n$deM27mQv>(A&%iyde)8*ois8f4DJUl{m0d>`L#Xv6 zJZoKF)>~T)Q}<86`v!J`nd>BM5gjf#)p05&4|^#bA=uh&EuJ;t@3-M|URB(LUjqyUJ8j#6AIcgFzQ5D~z5CP=9KYNN zPfYkN*6-il1@ot+2p$u>4>vEpAo$0H19a&*>HLxh&5qrF;#va$xKy|mh*l>TTJh{CF3jcA%iIxxLC*~Shx?(>z3gqvZ9HoIq z)eoZgI0t6dp#=VUIUVP9*)RB8z#n`|4#dWx(j)!1NpB)%kq@BYYoN$x7qZrRz z$7}Gs)q)F(JkV?L7{MLydE(;^odhRl_+bCT-())0yQaQ)bnpqmZe#uN>8CU`jr(s5 zz|G&!niJP|3BYM-?kZxNUH(}7p-Ax2rM`G(e0zz;OUE5YS80S`*YRFBrNRoqwyuXr zm*6)o50Eaw8neBmOFO^%F485~d$S$s5lSO$C3wp4 z{-jIT)+W6l=@QKBdXX-n#izX~=@J?fDw&clne1=UuovkPd}d%j(#2@J%+`W*3BI|; zigXDs|2^hE#cO8mz09F^Y2gh!^6Li2rkk@qG?r72_c+%&=q)TuLlSr4a(_(HP(j~a0zA5PvS~iq+ zBV9t{@J8K9m(V`X-jsAnq^p1BzNAaA-EkmYf>|{y(j|C*jj^OlaP0{*NSEL(u8T>R z;QQn3NSEO8?RJqa!7X;}{oi3>L!yUkgQliged->x|W+pgItxW%b4SO!xB>$?xZ$u8Xl_pb}sc5g+& zSC;g_x19o2blmX|d!Wb8Tyx^{OS|DgOi&XavF?V2Q#@tj@?|}+@#n9C2PXB#Ax@nc zjR%`ZI6rs1;O<)n2k8>r;f)jN z5?rmy0n#OS&V@syOYnz8FVZD=bfpudOYnioexys-d5ypLlj{;%8a@vsT|#5KtU%Hw zwA(%lAYFn-p7JAI66rd=?gZ%)JZaQ1(j_=?@?p{?nBsNi;a=%-;3o(PKY#-a?F6?N zd>DW9883KkpJTY-QzyY)rk%j9ZNI8$eyja{IP&FD!AmX#U{tFFa~kh)GY~5#pEhne|dmogK<{d11v8>h*F?W4Rf;=~5QgMtrXKrcyA2p5^UXJ2I&&)uzE4+61-uU9qAJ6)o~Z;5`2pHFn`DE?>PR=|C@tl z@IO5V|BmDT=G`awpPqM9=T>F`jVfEDja`OEatdVPYOfdIxzxLYe^;H06+%M<5B)s@ zEuY#7Hcy|5gKISqtbb!N_FvgcO`o-7ld$Kl`R2q=?@q!_dks~@Bfm_>MDMMFy-cTJ zXU7P^(^t;KrTUKq+aH{ZM&pYG-&?;B?*~+o=(A=&m*Ij2bp$7rufa2B4Fof311|bf zU+}@B+t6uLZNb?~cO%y&c-y=^q)V)sW9Uq}1Q$5Dk}kowT=$bM!4I1rBwd0(7`c%y zq2*qb8|e}n9fI9RmrS-<*L5RZf&+^WkS@UkChjL)g3k_eC0&B6KHN*X7=3nJtv#em zaQ!;FNtfW3FSn8|!6SFrlP|St1iyQo0-OIt8nXam6 z5pTE>BcG2DYo0ne9=#z{b_y+r5wX75<8z+emCw0*%pDIOGZga|Ri2F>cJ~%`w)?HoGsAmJLrW z@mg8F`9N-S(ho0mU(!t`+v;o{i5s){yR5lSYzFqh_22osts=j}^iwC$TeVyjak!Gj z$VKirWtpRzw0jJ*z{+E@R2K*T2FvN5xc^0O71?|Z__OIx(2RW8Aixwy^fH!S@HM5Y z-e@_guGFx8MT-gp-Ed<2`zo?+cr<^0u8F&fd}Y3k|ITmC0BJY3U#}1UT}$mQlFfmN z7K;-1V$)g8C9=Wc`br!!qOwHVo5YO7@PkvNLHx5RT@IqtjiF-wBaZyL(#n1kY4kca z8wY-DE|G7OW(>gOv8%=W&tLcAkka`Q+23fQEgqdZP9neg936)S7afER_ltJne#5O2 z`QgL)1=w)%L7}C4@&*h%s1bW|_Vlf|DM-r}?>1o3tUNL9zG5AAdYdXZq0MT9>Dv7~ zxY2Ta(;db5wAqVs)RSPry&EjR+`G<#;|AGars;jzhU@)p!`HdVomM#2${<=-=BSYjHs$wY2o`~(8?d5}d#c<7$|9(SLMapWb zfhC*wV27S{r3ajQ_1lf3k{e1pnrpyu(l*??MPJhIpaIic8?Z`IeQA!F2Es?I#ec@u zlH4X};G1RzM%=3;1+CSdeQlu}@W7m*d=s8S#-Dcwld#vu;N{lypwHgyz8wmbpxD?knuO@hR<~;QIlq;^K)R;dDw|QR{ zyzbIee7^Re;5RKMVbQ9LJ;37+q}n{)}*eBVR51V=S?Azk8FOJ40GU4r9`50WmyJAb&5F2T{@LAr#N zjTs)KOK7}R=s~(vWardr9;8cfOec5JCAiAcgQQFF@AmsimqhdXuXg!Q@%noodN0{6 zw_T!v4$BVWl}Rf3gq;RL=D6Vq=M=TwHVs%*az_}gr>?M@UymK{j;8v(%)NGLVDw0L z>}>nVyvkM$v@CMN9}ZTkp?ps!TezXefxW833pHTh{~-EZ3|BRtqJb%&_T%8l8>(;C z8kn(YAMS3Rrkcw4w*7GzG`aajWz~gW`#rfAE1I0c5m!R6+2sUa$IfE&=Al^JR)(lS zXK?DgQ0$c;!^J@{=ot}#$If1XM2pk7|MV%G-RBBqc8bL%*TV6n(`EShD;Ad)hT)*F zOYliPgVRjIaO6pZkJHZLvLm4wv5JB5^Rw8lNhr4B>(A0Vjr#uKSS#ZaeBk#%{yB6C zyHvjd8x1KH1Q7aGWZZoAMx_H)~X2C|>qE;Nw++;*XX?B})%4P-yJU1%Wtx$Qy& z+0Shk8pwWbyU;-PbK8XmvY*>7G?4w=cAbv_q%>wGTk*7;o6O*W4&FUB6AmTQdhVs@Hh{C8BMT*KLiHO(zXhw^K3 z&k$c0pH+<4YF(9!Y6Y=KKEA;uUQX^9$|8%4(TtsvFI@^_E58+E>x;+bT}{GSvsxwC z$-+_Y`!j?!Zc>8RSKG>lrvq5qmL=G)*($kAb&`3uD#3s6ub1^>yqQVU5)3!pFT402 zW#%*j;dZ3lGB}LUI?+bHa+mqxY+0KUtny)>e5+0vi|ks07Tz1> zp__tOO79YE6|-C}YUs!E`jy~q`!%w^^>KED^YYf)`5$XJ#wM7S;PY7?avS}ltnWW1 zcw$qiT<6>ovA*KZtepio_`*{*qR&XF;>-fHtNem>;(znNWkdmbJbl5;JV7#@T!5{w zJZE)ddP(ax6ri>7Q?_)Xi8LU%0M#!Zvhb?L(wHX&n7I5NEAP`;`uI;F?svP%qyZ*U z+=N1`xa}Hybfb^dcWxo>&P!s)&-IrkO)kU^Kd-U#*;Z1^HibBL#4Xmo{}`$1!vZ{J z`G5_nH%|K7wpH2xVQ2Pg&U0U|8O;YtMGFhC?Y$T5#cD|^SyO;k*PpXZzP+W`g9Z4= z?kQ{P+)e7Az_ko}#FkhaOSF!}|1M9#J*7IE z3h`HF68mN%NpNifTulTd_+ETcY^UZwVY6mG`V=0W^w!z%7%t5l*%Ev=mUHEcvk91*MDZEZwp$-`B zEE#h?S>dDFx!-=tXGEl! zZR23+@a9sedHjfMusKq4-Chb7S$?t}|2v2)cb9@ec(6Rtlt~VIOJVcfFgf#jqBPRF z6zq3@R@sOn~aX@N3t`z2-^;T`U<|1WHm;Ri|~uwE-w@)&=~#-$YO94%EFCI(6;oVedU%~ahe z3YKc^DFs<$t7?%QCfPWaf`hzAqvZPLDUw-SDfmnuAm5suEM1H&1vk&G^5Y= zq`*>WG%{a3^K7(K#O*)vJXZbwTDY{oz>TB7(%4q57`4X6W+FAAB#5r}%=f&U<+Ja4usLUQuC=q~HE`me3<*F^W51{ox4cJAYD!ipL9_p%r!2VBFy&asfWh)H~&QDW? ze{#krHF4#3Ye1d5ST(8Z z0qlFD5d4@WOE(C|7e0k>kpGQ|xxNutc&ZTEKN`yZ?S2Y}+%E*TkG)xvTMRar3&Bt= zv7Lr7_$#Ckrg#lzlTD-X68~)N6T?`<_eh+~`+dsag%gc1y=DpY8c|vPG?PEW#qX2T z_%h!Hc)fE8MEp3cuF*T3?FrP5r>o;w)@3b!+U&zj8fbl+*>Vf}TBZ?N-q%0I4z((Q zpBsD02k(ZkkQLhTbhGN%#8S)kPqsi+-C~ia(hI=x!-~bRPVX{9%bglA{_Ey8oYYcl z=ez*^&YBc02M3#?Q#b88?N+zP3A?m@`}WNiyW|&%xYt_06)(GK1RHPdiKV@YAvSP< ztjB*h-j6>oKz#J49ez2j5yxH9emgqnYtJXgGP^*;uQJ#)ys})d&ki!1l?k7yPgug{ zmY>A@mi{~7yq9*|bk-)`gJ`+YWd}&9UMBqT?3F8o^ED~&dQEeLwGBTBpUix^6Q(WD zj(_?+9PaaTBh6{(+ZTQZl)$0+YPmtIU%%j}5-_ummOHA$&FWt)fi1sI$nV-dHnU0O z_rn+OlgDLxn1$XfftEG4$(ORy;y-adxqXei?sjHE*0mCt|7@kar_}=WUH;i=dE4d6 zlOC!aBTAsR%0nJx@I$@Jw*-1t3z93Jt02$yEP)|rXXGleC2DW?66ibks=Uqkw0gnO z5*WDsn!LPgGxguLWk2~3JO8;=0u!8~8r7ub#bBDdWW8PV{@oj$I;Jr$XB_(QuOC`{0-buOX zjLPz>I6mGdN?zCgyPCz6!1#gj^0|-{^|w5F0QKn+qSs; zJXmr0DXahEJIgc7huy0lv1WSTSo-9A=(qSDdtzJ8j6Cw;N|Re`u+um8^ zg7co|!HbV2Pa?tv!;_p;-6#rJiPYDhC5$x{IP99X!0MM+uyzQN6R>y+kZ3?E81y} z;uHF;;wxHH@gW_HG?6y4fi#gevW+y6HnN#Ckv7tzFlkigkap#>xW?r?e>Y7qJSz;w3&j_(wm~Rh-C&fi#iK{#Fi1)b#d>-dFnsH6 zXl{54&3~N3WWBq*ABn_QH_u=|&3mBtG8&JsKaGnW@4>3RvACf@G}c*u4;DI{#gv!` zG)ue-OQPa%$EqlQ~Azy@*&J3I6_+sje^YFYS z!*yf)aD4T%;I%-;$@>0S;du;L%uwU}UIDn{X(V*jOF*krf!Lz)Dezeyj}4XtI`n@zdOik7YGKL80MWk zS6>Q%h9(i%wEPTuE(nDE1H)1C;2efb<ItTM#`{MgthV>i7L**)dc=H9rJ+ss>d7mGSSi^9v zH^PEt{&@C+j6Kd>0n3vCXmDDM;oeDLY#4-t=Oo}{=?0ui3&zm<@i=3DGVOD*Cul$L zToe0}a*gMp*sqj>JU7KYrrhK?EA}_#EYDrB?}_<77x_SQ_&yhTLZ9XPT;va}$@iYf zD>@e6lOo?}Px8Gg@{sl_-@_t5X%F+gE%KK3w!*aMl{u6P%4aD@lr<@Llw(m&DK=29 zDYj7#DmGJYDq1LK6^+D-cABI3gg&eIiq=$oNXO#2EAowO;JGXEkZj|*EAo?U=D92K zmb55L8kISuUHL5eL|K!3r5uZVSiR^XyqOS$0r_E+zo6u=S7bPpFF%KUn+Jh=)kv`K za0dMw2g2~R(XjAF3|Eqn>ABUGXVgyCV?JEQx~-0bw}&Y7kUj zaRD;6gy5V#{25!j2X{E={x|+dBEjlF!Zf?5wAlsM1}{#sp|n7&%>Ex42(*BahG=jd^Bg!WUC*} z8-~z!lMDqL{Bic9D==!38d6dN(7MSrnELc07)Ax*nkqLTs(U<~cMribt6LDT^E_O! z3&X+1w;?*{9F%Q2g?0Mfg*w4!;G}mXzSh47OZK0J#4FKwWY;}dx;PpfKAuLWjrZXA zfJoTE&lL~L?}B;zQ{evT91g5;7oPnL1E_o+YfikQ>}R03>-IC~>a5t8x;iWNtFF$9 zeXOgqVt?!Etl0OuIxF%)S7*h#x;iV4N5|6bJEAmiRXGMPM>a1X0ofUI* zbyj>gudGmafhU8+3J6*ruzq!e(8a6Z~{x`S4f&AQ-ykBCP2i z4!4?x!0V(75K$BYbGnDY=7({>ngv78HK!me`Yd$46bRdHMZ%ROu`nky0QMC|gV*pF z$npyS&CAo^F(V2JZw0`w_%l#*&%u;~;b7U9*QUPbAucf#d{+fSS@H!~ z*(d~_m4?7t(~EG=EeHy(gu#H72{6h$5N1B$*M05PATov#t!B`FYu4$9dS|$6zea;iR7NknO~Cr@kKqGc|PJ z^?1ZtKWN_L5;Pqq!}@rCaM*GcLXFg5)GQFpovy*fGZ!K2Nf7v|Zo-@V3oz$(2n=(+ z1(u&N)5-SUjt35Kh*0e!{(1yVb*s)*!5P1qt3I`Ob44Dd#EQd9EYnJmovjb)=l9eCN52l=GDDJlBzOp7NdNI#SM4zVlp1%6ZCn zp6f_CPx;Ps9VzE2-+8VhyI$a-Q;?=Q>i(Q@-qt3I`Ob44Dd#EQd9EYnJmovjb)=l9eCN52l=GDDfA5pOzgumn9)?>@FW{W7 zFMu;B{C;;5OzGz(#@W!bKNf@G z?IejfrFJF^>d+I2-|u_^y<)Zto|vqL`yT=XUpjdLuJ*euxb*s3nEvg#U`f>hCfR2T zo)a4`?d()4_|w0W!rhZTE8|QV=krmS&(}d^9lky)>+|EHa$If?D)w+YQL&TTkBa?V z7b?2AUR3mQKcM0V?jKbA!~KSe-~R4h|L&jvf9)IpJHHoXZV7;v?P8JtO$y|U3OiIl zG&MaW#urw8f*$-G#58CA`*i%)SYPn&=J_}#(V5Y>{klRl>@k`CHU~yL%fUHTNPqJJ zuP#Wzf4g@DVo&?K2&VRe<2>SU%=D-*y)UK;KBXVT zI@Ze*jO+Eo=j|(0#wBH(&j)2bUk8+R`1+u%&yNerak)L9*u(7v#ZGQNDE4z*py=Xy zLD9?o0E!>De?ajM_ZujF`}_LL|6Y6fzq|G_gFkz+aPDLI>())^$ywdxvFx^e6FTa~ z+b`dQhdBG1JeJEhY{Gqk_5yZC$4|EFDd{rj5mx$s;tc&K5GgW}l3Zn-eA#aCAT z>Ksd0TnI_&5zIFK3R~q+1jEc-*$fj68{}F9!4F(n?*kd^F&}>!yr0>bzh!;b7QyLB zZp^R6Gxlg&5q#Njh#4e5V3uY@@Y&jvrS-nUuGT7oU(JrQc`a|U{x1r_X_r4+T=yEw z2`GeUuMqawIFT&^?Xhb5Hpa_kh2W^?#$LT{hk^Brpn2GS_O@mlH0s3X{BmWbTMcnk z?;_A!;L23)%}}+!5KQ^IGgQ&d@j`eZe7@z)qK6n@W8XrkY3#!yEt+C(p?2JVTLBv~ zPOEXw`KN60_ComQdMLB`_>5HvErc##1KIEN7wpTmLKynokDXrknq7HW2nBH`S*>dC z*xY<>^T^{YrG7fIDk+52<~}UrOco2hnhQBE3z+|xWH$3@4vbj(leL%_$M)3Eg(@G) znVfx&RVdAYw6O2Yqh1{QpLUPq@B1%?6AHj&*-Lh}tFfe>nFC%@bu>G$Qgy3L%d2|@ zNR9P##rU|UOuG2J0Ge&M$I8qHN+8*2+8Y*P}eKiNo9 z`Dn!Wj$>QR_wsz9In^We<>qe-ASLV`vvsH|H5;Hk*78ZM&7*za!>aM!(0Sx3jO+6r z76y0c&m^9~)s5dn?yl}wgZF5jt=~h?sBZZ1=M|h(o8RkYK@SM{Y4}bB&H*RV0%c28T-g^>@KBmHDw@&Ck%pV;F zq{0pFF1R%@2p6QkhaZv&uHnyko#gjhYh3hTOX7RtyY5BMvXvui9o`KuE-8X>tG2MS zOS|Hb6NNB&-4=G2|E90JQV~pm>FnOt1K2&U5PGh*VYc-S;KZkeu+m@&YqFic|Nd$r zGz?hDM!wjGOZoc$R$I?jA9O|F>-@O2iH$dKLHpKeaI2slp81lDH_oQP{+4Y~b?6eF zUYrgSpSHyQ`SF;MlMW;Mw?Or=IGpPA0S5kTg1y$9!EXyc!Wjd7eDxw4yLHQeEZe%c ztY;)1?2`$L^s1xzgmApLI16kHD&Vc%Ay{6u0JeRuiLam@Z%zpb}-2ZPX zT&dn3&2k@M>x@)ryRtoA-uMI~4yJ-(w+@(W@f4p=PKC5BMric;F{*2%f@jrE*vI`L z&I?QdSTzJ64jeBn+K~cxms;V7Q?sRByl&pFV~vH&S4lx5Qeg5%YdrpJmsHU+1$Ota zMt%8=lo*!^=H3=KwdNZs)ISvtS@y@&+$^bhX)2tXGyrj7o|M`k6=pxT#IQ$Ml3UPw zxavI!oy*@!r@Ouf|LH^cvw!!bNfD`V+s*=;*MA}9pHGDYju!Z6!Aq%}uYc0r0^h{H zlDr0`L3te&_H7*}J>h=N^6!WJdW1@!)~Ca|jlIzQ+fixg$Pdspvm4%=>LRtW_z3p1 zI-~XT&C=4G49IEJ2E(t|Nb3!<{+>OV3YG}9Yk_Ku-a?=E@JeW#j!&3N+yNo&A@w zJ9by473yM0dAWl*-Ib*sEsJ3idN9*NOxilM7#^)Sz{c!Gshe#v46WkA-kwD%!mAiY z2k_s4w?^qO6pLJTxmN?awaO6ZftYz)q4UBF*v{XpnP0RHY%(*TV0LG$@O3$)t;mF_ zy^YXk%p&+&JqsT0YKI1`ZJ?km3mT^y;@rE_Az)<=j9IIXu^Y#Ob4g9Va%WfTN4;D!pnCZaZ4+X6t=(`3!_6lUR_BDlHM*P_W`xC6m z>;}-nF$28#`Df^SPk7uQ1D?p;(b(A)T&`rndY*SZX8FR|(k!Uiv^}cI!(cU!#q1aD z@vX}#Xf!kn<~=pSO%K9g!m3P&R2yTan?IcA_p(j4ZDx5RM?udFeyq9Pta$uX(C}vu zR95lKW0DOVte+1Jt5-qG%^M(4lMD0u)y5@tx5El+UUy#9$D`@HASF5nT9r1!@Xe0! z_-8iw`7}eaP9C!Q(JiDC*A2zqc zsVBc7I0@(32czV*tK4Lyig|_D*vvErB@o^%bwYA;f@|oDQ|)w7iPojfmJXv ztU2xt&4vyWE8(RIEpf0W8?LmgfOfg9Fk)~HG#K!Mbz9vAcLd}>x2VtTo^xB=-#=R% zYtqb@Z1VAJ*t(%ArY}omvsPt;&!%c%nW9qzMi)!b<8b02nc5Q6ZC>I)5C}!riP0{CZ4kYP+Vp*@6 zV4I^k@ciXhX7{!+2F=TXRiD2zLr(*|#Or2c<9}K2QH`)>iyScB`$i?l0p?dT&?ZP8v0z4Gqx4Mq?!Tj$LDCd)x;v0*d>J38XhQruT})_ zUq!G>%tx*@vJgDJ%dBM8L3w3Xf#8MfH?o{X{8@-8&)EE00ZgAiM=|oz1Gd1`pKZ_1 zhXz)6+2_N4Ox>^mj;L<2FI|1vtEmOxy!aZ67~{h}Iu$_0fmd0@mY%FUssQ#RUt$qA z+*wd!0bJRREV$QxHtlHv)HuSJ=B*R+_>l);L2p@&LH?}gHSIp{`tSrhCu{dxt!>j; zhB_Nw6jsA_A67HzNj41ow<^APxQn&;nho!6>*0q1&djS*4kQk)g8O_AuvJTQp!xJl zxOLJY=5jU%X7PQP-`SI0)8qaBm>+DYnKyejKNoDyeP*t!jl{$@lL^Bb@k*NkSkWfDGArrJ}x;>$x{z~$|}pd z`93dtQWf1Zy2*o$bKrwq4YN|0%H12~z{FP7(POZioU=R=ZftIZ(D63AQU3!}nbi?j zeS6LJPE7-!e|q3~zYJDm_j`DoX@-5Cma;u9Q=otQ0XSr51#D>d4q_?}!i?8dF#7RZ z*sy#Eo;gqhPg-Td{qjcmbiqqDv{EJ{a!#FE9UrH@gKNBw_v~+pUMo}J-UEq4$AE5o)_PF1x9(tVn2u^{9=;mGvyFYygZF%nzry7I-FW!khA>CsjK7I2J4)XqC zYPKah>A!`FyjLkWWP-Eiy@f)jA(%5?g@;St!q2q>F)Gg*pBub`tawW_&K!n~54{7g zE&Xx(tl{{Qy@MqFw-}^1R`|iA$mEXby6lzeYC<}G<$r&z&-RMakE&@Xr<>uS{Fc(C^I3?T&z_ww1z%1@ip7l3chZ$QY504UgafNxm%PuX;h;2kMp9N4B0nivL3#@EwvVu>l%^YfDI4t&6Nr%do3f6vO#H6L+ud?(!N?jZFW zk%5pi?N)*TpDSRzGu0= z9L(5JEr04$ZuaPV5z@KTcV<(wj;=-MlXF<710+^OgR^<< zPS1;$c3;X7diB~ZkldceI2hqcItqw?i>~pau z?~(L2ACkUa$;GX_M+!6clHwZVq2WKgpZV@14PBXs4ugKMsg-@Dh4=H&Gv+fp)X!hC zw$~o3V}l2(Xx|*%!+WF}-YZohJ9F?e?~xwec2{*+mxFn{NBR+cT2*u;7Z3B=)Um!= zmE@j_sk|3D`}md0+$|TWM_T{xmMZ>bE>e#))M2SKxp6)=;62j98V9A2$9Z_T(I@8h zX1~0yODe75H|3%1`Wd1vI} z9^NB$G+8fQ4Jg7~-XmF4pE zaRBd)yOtiry+?|W`r!{9m*9hSMd+P9jXg+Qg0AC>u+@Nhti!FP=-asn+5Y9s?bveM zs#k=iydRD(TZvc83ULMRhwYqJqg`epZs7fJjjpzM;Y}fS;{9-5;aZHFqCx71S1(?O z?|ihJw$d8gMHeA`=UU#OCsuGO;@?N@S*NPqaIj|)_I9vk%TzruX=V}9cd=pPyQ4D} zB7GNYb-p{k%qYYM%MY-DU3=jEIz@P*k_)pP(gS1q6yaKbM^@`ccf6rrh;&`0PQpy| z2z`%qO~xlI49y#-qKbbP3tSn5m#^~k`JB$!Vx1p0T9k$-`Wc~@{|QWQnT~4bcIZ{Z z2aURXz_ffre4p-#sgFNm8)tnSARpp+m5X7OUb8RD_n>1@9?JvNYHi1kpa5?(DDZm9zC)luA3-EsL_ekHxYD~L~wT#}Q zKmRUve#<$G=$(dk{JYql@i*~ug*3cczdfeBeu&%Nq+)HkJ?bxcj5ZTe@oKR@F7+x2ki;0T;J_#?ViZiMUaM&TCtfW@bq;oT``@Wc6Z z+_lya2h5AZDqYjj$e=YwPQ8fV!_% zvX*7?z0?RF986}%_GDuD4SgI{{T{Q7&BRN-4RM3vBbJiQ>tNFc*x=$*w&L|$?6YzR z=BcV;*3EaA$FBoSuKt^)KT5&4E`aOmm$B&b_c$rFFAjIeVb@I4u(*mTrVdVJ4c?~X z5x-8j;rcTc7y1#?i(BF2-gnuKu(w!cnHAojQG-99^cIiQ<$cK5I{Z1Ow^+{m4X61H zaZii4DEgeC#@PAoJEUteXNvpd;P7{t!LP{-oNa|pOW)zpu>-I{%b{4>piXv=!ZKU|H0)8Qt|n}JyCtG1zsAHhGBl)5R(khWmGzP zuk4H+ZR?{!)(4F5-xgOT)x=e%8MyCjGc?q%hQS9iG4E{yeDSq11_tNgW`0e^Q}u&Q zOwJN}tVTtDIPf_OuNt&P1E-^4Xq}D439WGPLU-^yk&Ukx@L2!5ABNPhcKJXNTz0AVJHUGgQ<0E0$mnMZo=k zvv5sPI}B+P2DOYb#Cc#})DAGJmBD+h?l`ueGo0<0fqDGe?5MWxPQouifzv|hsP<|SZ>_}*JMwHh6A!NXh~ZY18H;yMp&5Oy!xA=Ym;KEz^})q9!-?$x)$U1sg7)fpIWMw zP>hNE8tk(w7bIJ^5~S;~$683xv{fnk+1jv6rq*zxQYlu^U%~?GSb=YQq5sP$a)L@%9i=BN3Sx_LN|_tGC* z6`RksDMGpy(KXmcH8)e+(*{I0mU=(a;6D#tS zgeBe~Ecxhi)uJxN!iO~$xJnC~7bD%P3VRnQO*bya_2K)Ohvi8r%Cs1l{&r>U+ImV} zJ&JJ^zgIQZ+Fkm5P=j=@YWeO%(yK!n(R+_Mw^zErd-9*1eOT9!15(&X?YQyC2GWxa zT8(4uuc+3972%a@p)9Azb=A}-McAL;t1|9LsEEnE1o&S&(bm`8b-%I{T8+u@;la6T6Y@q1NKSHGIyF6O;o zdO15;v&8)JlU(%T_p0)o%gp~ff3Nyq`CV-d!!o3Mwd*{LU?gX{S6kz-5u~@!j{EH} zg3f&0kKe1c+iwI_IfwImwLkV4K?PMic~R3cFo>!IM{8A*qYTTyaCs&0S#(X^lK(E$ zbZ{m9JhOvZ-L8!PMxhd5!`f2fgb?|fAt~y$^3@&BrLG<^2s+SGR z;8?9H09)RhyZ;~d-aIU)?`l^VGf9m6^yaBBBs7gv|34$ygaOe#|67 zMXGyWBoUD*LsBWt<9**1GJDrrcRQcwzwaOK?|6UD^FIHb$2!iv)^)CF?`!R~)VW*)?3j|aRWS9BCVaBYl7Adl1<@w`!KLeM`LV@S@XdEHOfm_U zH$PAXAMA#~1(%8P*5OqUP~`-UNy^yE3H0{7yCb1wSX9iM1=v734)afYTcd(xFKe+*>Sz>~nhL+0RPo^sy&g_)?$b6w-6E&AP&? zXY}roca>15TSw^A)0n89R)UYr8qTgaB4_E@*KzkP;Ngp(^4}KpTqC2RpJcyZoL>`%|iuC!?ds~t_n z@{me6U11K#?Hh=LX!`ZnjbXK)t$c%N6%4DZ2^+FE$Zd6KS;ckW!NiO5@0HXBUmdWY z{#c$t+c7Ia4>XpS$nVm&u5-c=?rUg?`(rA>>Ssgv-+gZX=k~e%PudUpzx$v6&+UKy zpR`Z@=*~iTnWQ4UejLZ;w#ATXnM&^HpTM~A5}1%JCry_e$C!p?P^58!-0pY`4eiUp zTDg%d7PM zlsvw;9ovVN!UyFw;%B-YH@+!@t>y=bcd##x@-2ru3%8Ord0X&;sRDwVdy?obn{f9= z1#C$gPPXQ*!Ip9b6mAtr<&_oaS(ygStA>M9^=J%#m=2$I4uFvtTyRcOCfqyO2g29R z#DLw|;C;sibOM)SyV8#!``8AugV$jj`d?dBZ4UJ`Hsit{FQ92ZZ)m+@5FQ!+8YZ=w z0qdF$!P6sCK_N_p8@a=9WY{}suwe`=I6DHnraplKgEqpo!XbG0$WwT9e>IG99*j>% zJ%^J<%V6;KK{%1#UlTGb5d6>1L{GY>Ic@%K7yn#{m?jQygm?m?wEznm*OB`V<1>~%)(<7$5Z^neimN290x&^ z6J#5Ne`AmFpBMw&j1j5#5Gf_^@OaThg0*58?5` zY$$fLg6ESDpwFf(nAP46=0ybHAe|5Jtzl1yY_uC2OiY8wdL!W5+2xoqHx+vNI>Q&! z`FOhE4Ul+O@U-^C9M9L#7u_MenC|n5Nr7Kxb6|h68)lt&0cEk?kaKYg7P>!!rAt=8 zo_tp{uAdA&OgBKn=qb1{^AWV(>I>U@x#0)92lUL0KbW0#$Mu25pnO+Aa)ao9pSi^_ z^hq%Z>)HmldKE*QW(hfB-3q5{Ee5}rMPx*i=J?=hG2IVcK+g7}|7WX;p^bkIanEjq zt45W8o=qkZb{S*Uh7uTU^`0CwZ-}cyOQ5q`D#>bKggZZ!K;yJm#Itt;T&h(H^QOHZ zN7L$K^P9zB?UzS7{jfyu^YjijI=%w-w88?S0R7DEWYYGwSlYJ?p3aXVb9CC_(s(80 zP|oKQ#^|4;gz@_ANu99<*eX>Co62m-_$P*V<*5?nT6V-^N(1yrRDxm{9kXAJ(16}) z&>)~8v0to-N$(V(`*0B4O7I$%+_Sx83)V3?p;Wb%6?w zC#@t;qlOayn<_BVokC`ZrwUmyDiCbO6FB25j0{&nue;;OkCy#~ey3HCm*`A1Gylj| z?oq*5ze&W;`n*hYg$fRzb0c%*4l>h8D)_K>7CAK_z`n0V1w3^bMv`*-5#RF_pf%H! z7`*OAM%AbH$vlV`a$mP1OFC47_tgo)3`2d=X>lc#sJ_XP3&)WRdhZb2J}cYjIhvR) ztfbE#kd=HNNEXsNE8JzVvfZw|iSEQosL;?6;(ddMo_c3`w{^pQJp8(j&m*+D|XUXw|LMDKN(8aFaEh!tp@Kc~^s@8g z-uflU5we9plRm&m<9={-@79=!LN@fB-3NvjWe6)De}wguxf$A@VU+nedUO z_dDHH4Bndwk7-$TXIv5u+Gc_U<&ZSk~s4tNf3 z3p=)%VVOJ|mbRvG-1pVRDRdv*_41x@GDsoL8~y=uQUx$Ir}umyzp9$YZE$?Dz;ZsJQG%-L$WDz{Q_?h@cm}C94LRg;vhb(aG zh(bgmY^u_LKRr9)9sfeO_FEHrUJ=k}r7PSPd%mS{uoFKRpcB$?e!F7}&WPUG8zl3&iZ#Zsek zcx@j+bR+MIH|ZYQ>K4(Y`<46R13E5tJ&Yxe`VYnFUh2MgDs8*CkKW1ie%59(%V&?c zsI`*DTJk0BRv!>ebd_{Xc{}O%^q9EwvjUcP@FRv}&x!>K1-vQQPKvTZ#iP4vA8WRh z#49$5x9Po)_I;L3cBr%_5@tW4_obR0*l`7Lw?X%fzqr zKFH(m){&TobHrb{rI0`K3E4I1wAhsHVcrp+Kpb_CiB;78cu$e+(>NsNeo(;T=sl!& z+$Qm%r4punqBgWyDNdsAodtKdkc|fyiMO`p!OK48u=!n%xUEG#9G=)1uB|T@PhZLh zi(AIfqUUGvyH)|Tnq&ko&wmvYCl^3L+xpOR!*?<6d;x^o8NhdXSIl*~kM7QzdeGA4 zyLh1^-CuXJF1$bdRouO_5Hj<0U`pa=@oh{Y*frCJ>(v!v_R?aQZB;?~%zP%!j4lC- z{U1oB{Y}v;?;{v~>Hsf)O%qFXav)@tEttsy#g`{?VD^S~P%$H1+`c#$#`I_dUOtaS zP0Jk4_r6{(R~h6$ho2o_lgwOnul@+G6dyQF#2G31T%+pNN8$9iJWvn|nA&riaKC*n zz30aoj&FDqb9ikI)O}|QXEayK{Q}B(-5y+aHa6@8-8+3RlZ2S=mHob30_L;I$*p!i zg6^ea7-*ycOTMXuKZeE7@`X11nr1>8-7SJUb?d^z_034@twpf;t{(h6+lus{d+J6k z)rZrs+YnKw2t-3eP-$6^(FY3QKv@IWH@PL*PYS`@&=`6?X+p|!3&6RVDfLepk|rAp zz;jt+@Y=6KIz`d*7qkzY-I*!BzmK+Qb6@gv#6x)`{f3!d=1&4A-jrwC(0fDs29TAF z&dZy)mP0F3dKcX@J9+zxGU#_Wfz)fOE$>=R@4=;gtk11i^4wB&pS<}jRG#uf3A?=( z61%c^x$r>=Z)l&i&ORzXnos*S?W?-cXXGdDrbF1YJuPucs*Me4%2!!KaR=QS`T zSsN0Lq(C3bWl;a6Hk>~28X`I@1dEqC@buJM=#QSzt%Dv68T$?vESL^)TMZyJBn{>a zafO+#M$kC%Js9RqfIUl0;l;-USOtOL*vJSr?70tnCImodPa_x~nE+co1HpT7eJId< z4xa{ZgtN0hl9vsVVPu_cV3=D%ZuO@3+IacH4zZf7o|y=EVhAX>GD-VO4h$r~#G zi?-mhGZ&Vfw*$R~&7tn}kD%SW540|?5BJ+;!DFidFh5NbJZ97T2I+ToT4ZyWL+>h_ zP)bNxA>EJKv=Zu@j3RE!+tGJL1?V60AQRke!JO`Kotd?Q{JCZa7yDFzyt5z4p4SB~ zUsgd};vv$xPj~31QbJ`$2-)J+6E;4jKJ0|M#PfYG2pd-p9uL#W>@U4w>6ub+D*r-W z@90V6pVRk3`?>(%x39AV?;+rFpWcf| zzw?KG7zAdwEBSZ+;{F2x=^AJIbQ7ZUa10cks)S~qLr9LM3(WXf0ReREoNO``jy_ev zWW(cRqn^Q3OkF(GA%0&X4*C3cHW z3a!Q}An`yLS?_gT$hTC0DkGfu7DWkqbS)zIc_i6UH%W*$Q9wtN8>D%c_d@433WyjU zNg8x75?q`VaK`>RIUn#-DA}%nY_H2?ctagB@{t0Tojy-Kt*cA^(EXxIuAU+{~PL_Tx66?@?p-pTe$ked~ViaAwm|}W^B#+D%-Sf)epSh8weBXQV zW8HE{$i7aT^60&#y~|;2zc5ngW{UWlp0VoC@e;B8@j_gCupG{|rS-Y{g_uFV*~qHX zWUtLju{gaPLdX9@Y`3R~=5%kWLVkoyOn58aYoY+-z+e)wFI`lbDWJ?cn536xiRtu= z)#66lr!w*9f-+RmH6;UsIq*qKfqCsxiQHxm zDzK<(Be@hd9du4q;)fQ)Nf5e%k!clfJ8MRo z9CL=2mnxC1DOvv*47PEVSV7m6x_@;*QLD={al3u$lT0Pzde=}|vh!9%AaWaE0t&~8v~NeNz`s0}IF zy}@B_88)3)N(zqK!?gAaY~cQs^qeUJ)kP(SHMmZ)9qj3yF)F;#?I0OAq!%2VR)GgL zZY4WEb_4g+3e4{6NxU69K{v}vdKdXf@@St892i}RuMQG2)yxWVEi;j=DeY|XoqXw@ zg~9a)z}mh#uwv^+G(Oauev=tPLP8!6*kKJ1)2v`*SUx6Rv4GhPZDA_?SH5gsGdP{v z36f3~;-1ZBkaMRCyfb}`Y<;PhX)YP+kxIkz&VXIh3do1~?{Qv_i4gv!ob*dc$D^yq zz>%d@B*o}CUZv|xv%eM+pM)3KoX(BePxDBrcM5(oSO)L9=MtruK=-!>!rJJD(7NwK z^q;#Mp1#(GHD@1V{4hV5cA}arc$JK*)U9ypp@J;QNWc=hzSPFe1nkojZ~$FjIzGSz za$Y8&KV4ty(cT0eBqd-|y1o>tX98dE(frx^Qh_lXyq$o@=o(SLJ!6Q7O~5g9?P$vh zW0)JAfN$xV()Ja`@cdQ+Hrzzlphg=*otOmtKsm+jjlqoCX|*~Kvg#Pa-naxjP1lze zJ0URa&cu!XYdMg0_#;D z@prO4Y)x|jw`G~Qu9p+UWw(W=cImihkuyApreJY64VC9y;jps_WYm3!Ymd7_XOjl- z#`!I-`ZOCRDfD4i@7EZ7*c-aV>w)R7msses0v`UT3lR~|F;#y94D!^2{ri*AXtysc z9<2{)^^(w7O=FprC9x@fLs`ThV0#4ilJ|c$>JF&h_I~`-F_C6eKto(Nl+=K zTqq&|uY<^l$WlCRP5VghZgRGi?)|9zNTB|9V%(z)*TiR#>E|~PM{j!1@Q!!nO}~|- zes~#1-Fiii>iLl1vNC)|*Dg|gmyp5vrD#R{-!ZMv(m9CU)lA2o>A<5T(o==MbGDPR z9_PsCr3&<48bw<6xJZ5lS0H=WSS4;GSB}$rq3OHkbI@$^g{F)2UGs9&0Wi!d91;Mhx>r_~f=SIGdcp!VcPlXP_lS!X9KV-ZA zQK8O}i6qOXnV@w|h2hEL$*pt4g`=p#b7#g8J&#?&MLPD^8#t4_C0B)MS5>%l_Dqs) zY(`Az|92z0_TrM!jeL5i#Ei;aWXQA@L|I3Lii~Zf_^md1(?W%g4x5S7(^Mgr{>N`) zxPpAN^${}KDRFV!Dbl#<7_#u40!_AukX7MsL`C$q$c!#}xN%T9rUYCdOSN^dZe%(3bv!}Ng=pYp69pE~ zwX%0zzlfvPD|vnD^*bjXG*;q2^VgBO9UhCRj}%xM>q~Z2XNW^LDbT&=E>hI3L|iwX z?mh0gkNosdiSJVsnD&US0Upu9%B@OFF_=R7JxdcKZYl9)hw)_4)BB?BJ-U}5ZXD@Y zB#PbcD{*1GGijcELv*^W#BCcVks^z0;`ZxGgcEMW{&A?7ME59;-AUKa%r1(t6X;%x zQLZHJW*tm_NcSqVvL}PSXrLL}7X+r{!tI};X_^ZCPE8QreJB!-JyjuFQ(8S+7ad-! zuwLR>S>-kz?31p-j&28Jt*+30sM#tsvW=A$>iiK8=c}-~Qd=-|`yyJGDv_-zRUI(L z3^NtBd#+CoST(}c{Z)AB$X8*@Gb5Zv_f0vNz8CB^8RGdJD$F?%Ev)}g4_94Kp>t`F z;P|aBTHIFQyG9d)xEH#3ERl|v>o&sp&AJ#W79(3z%8F=>N0-rk%jY7<$~*L2DBXMM zd~H2BakVwJI#P^mO=-JhYwYo%1Z_NClX;p3STCdmkNim`oiz+`=hPB3yq7_y7&O3` zx+VB4`6KyV-x%ZQ{^6GA^GRjXM)+kv-J9WBM1q<%!8p1X*DtAxj0c1=z()7gFEY;TpR4EUQ8bW?Z#H;ankJ-=YcY=)T6f&kOO~ zEDf0R$p+tkDa6ocze(0(Yt*nW##1|$WKRb}bn0D#m*|{x>2$UDesn2*ws}eRl%G&8rU#)kqh^yJlnP)UMz(_NO=~@gweaY7av~ z>*MSdxwur;5+1B=h8D^^oRn({itx7RVwXwxK@NmhtJ{jk9W${FU59D+ZkbrpBNN$L z&D;7-#60&8$ku8O^fQ)SKA4G3Dd+O!z4F9dx|f)0FDG(heX0QWPj3SA6V8!}6?wRA zP+Mr!dnf6?IS0?T=mc7)T*&;CY`j_06Yd5!CXaox(CV!K-+G@BLbuSn*6CW!qydKo zud`)1{ljx|dVQ5}<8>)+sLUcVgHA-hTPeD%C?ojLlUxx?uubS^Qh6|d^z2oFlMDY4 zh%g;hik#krI#4wVF23dcxNWN(}G1lRWxuCiI|lPE)UwmD%d|+%P#jWXDjnHpEj9Ziv2h+8hRqF@HMpV%; zMb~OBZVZrXmMgI>^?wJ<-621huf#a&7jLxKBtP;=N#ARWi1nOUc^@qm2GX^f;YUK` z!Kg&GRud~E$n_7GAzQ1d&dQ6q^`#8E$0d**cK^iYx>1{Fh(zl^dF;)hN?dho4;kp7rCF;?&8kc70%nDmI0w|<|GY^~;v&QD>){Q`PFPa`N@Yfi>n7ve?H z7$VPGk|_T|9P4fb9sF#`^PEE5U|AnlOzcFCb}quOt_JXSRA=J6nC`b0RF6hs+BZfN>B-%4=c#niI)YVqosJ8uGJJ7 zX$cv&Imp&({5@XDM<~Jy$_de=@5#0~$^|SzAjMsUH z$O3W38u~t>ePB@WWYL4RZwOth*`((w?l4rMNx45!`g)7r$qM}5FMwP+ze3zgV=*i@ z6UoDV`@|PCHpI502_%G`eJHs?pQU~5Tgo(1^MJZfiiu0b9pOscK>OS3*g0Y%-M7#B zeDdy%qAPtT7SaA`d1tNI&R>b6Xupk0St;%*SKx_x+sKHj%i?Cbk52dFc4F#tPHgZ? zfpx5C|9^j6+*DtQ%Ldam%rOVW$JR<5K*vjB#U3%A?i+Nb>+n9g+r_t83appsN3IXM zE?(WJ!1!;0Wcc<7QTJInMjt;-IvL*-ce$2hN$M4HF)mvC@x2VEExkc}B1Q2emf@D} zF=VoJoap*B6(4AhgUKQD@TejKjnia6wrEMH2%){Y;5$o9fW)f!~pFa z{PCkDeAYdPKNjWUv8jy#{DLu@egkhkRu76F9>Et&3$UrBCTzKX6rThZ;z_!WWbSf| z`VH~?d%MmR54_YR2}@0U;q>*%n59U@p)PCT!yOmgQ~eAJ=>6rRZ&Cc^1&%$m5O$rP zgq`ZV!a|GLbgz^v-U@q-qY|fsNiP}`>iZiUbHEiE>CC`qhN(EA-9(tsY&O$zbSs>W2@}T`a4z;}lK|JVzS@+^_`0PM%3->^mBzk{@TOfoadEm_#aoBTw zAlPJkpyj(bG#wTQk19McFzX54qw8IRPY%SuxJP(cXB+hOaKu;953s{Re`xb;6uu0- zhjmWvf&KMeFiYzt_xoCP?2kQMo}*U7W#CQvW7X-W==WeXT&XtzH+)ay{-*cU5$Jv* z6&p0301C6AH0?FU-kJ{HGX|ow-YeYvc{V)C?~nG*dE76qD%^y+J#ul(0&^Imu>t*B z=iu-3*3h#48q^!~5lzyqz_0EKoRO79_g&k;{_hLXr#KVkmVKy??v8qS=~!kv09M|0 zM*S)U_Y0<<^u|`GK${{$CZsGyi!}6tI%?H)uJwhr~4m!sZ8`oHz? zM*K9l99y^YBg#vgQAjSs1>uKCxY1VZqf>^?@gd}nr7yNlEy2&d?vi;qzPM;YF|NOy zPN2dUhth8n+qYlHRlyhibPDjF)^%ZT)fRL(t+r?CAR5!~f&zz9AEfF0J?KKyGpG+T zHf%S(r~7hc)Cakkw+oXgwx>SGwZ^+pFIIt;biHe6S|DDsR?vN+Lx^GZ0o*l;o_Tq? zj@;cs;|yAsVGph2Wb2wEII&*|e$&5Cx->Y3Eh~#K%_W_@Sab~250xWZgE9q3)V z-irnF?Azm!k)%mlrg%uB97j1^CncYA#EhQh*lNLL@^xB)_+>fGhnA&%s8GzlQjWUU zPZ8Uw0&&sPa#Vz$AVGcd#XrBxv98w<5|y4U4r;2v)60TMX_E}`72O9uw{tMjc%CY1 zwV>_wDVW5Ld@ataqrmZ6$H<(n&&6f0%CY|2ljPRJCt?BJ6W)uicdhd>C6U1j+#MK7 z^e!2bvr84|OLZy28jxf3yi!Hy>!jxheX^>L0==vv$ZHK9;%lzJeRLh~yiTQ1Lj4{0 z`H^IdUb+y_LxE%SuambU9tqA<6c{ovjO^VY3MM;fTi9J9YYyBL0&Xa9D_!q8^gL2% zk)c4%)u&0pz$iiIj{^Tp_=l{EkPBOSDDmK(BV_3DC&H)EbpQ7LU}6;eL1;8tiSy`s zR~uWE(4U^eGE5C7j(dL#i-7tm=|{=0lzOBsovS;?pCmhT8xliROYx3|657^XhdRE^ z#4kVS|M;t$ahJZSn5wCS*|&VL>-)OmOCu%d?ejyE-Iel*ZIw`NwG*BDKbNP-l;E{s zH#RzRRsNIyA8Mqx7w;bQmw%eBgzCxr@c+8FX8(g?|NT3rVae>~VsH~BI9Dvgtl5pk zZ}v*aYT%6#zw|_pnM&|KFb8MreUUrwQG(Hc8Mt70s(dQlgJPvQ4R@s8kl%Yp|DAid zVk>e)euu8V2lbtV&1Nf+#mi{?%MAaqS0Rf@RQ22b6L*7O^m#p}uIwH6!pRdHP3zdt(dQ6Y;Tq?g$S zGmfb6$qg&nkG)Vs-$HFLv2KRx{WNd-|*Ju*Kup zJJc`hvQdSbuGNtrxnzqMm#J{-J9Bw@q8&!hqnt(^<%f#8;4yaTLn$Oy1TZJXV+v5oz z6+Tcc6~^vthn?4`u(#kLOlfC@{kN;o;E+t{?_!DTsGSk#41@t-fpx-^JpU(GmZLWP z#$)kcbi2=|aqQH%SDl_{6+!c)v8XOun&OFz)PEl>6V@y-#hyo1X!h1ySlYi4E~IC0 zzCGI~4Bpom7pzv{lzr!fKO>u92kNKm>qiR(XU#Ebj0$u6CJDboTHqVP>N8b1Slt@` z*s4%ClOy=7Xp8^o(`S=Z!sHPh(dn0x#_0VdTtCwVeaESA!Oj!%*y;}Wc!3I^`R3T4U}36}IdEav``m9y&|wc9?*-OX@FlnVQ= zd=t|Z8=+e?wXLGc-cfFf_i4KF$uXJ!FjI`8?aunx^ft%krJ-v4WM*=#xTb>F&)k<6 zVp|?o<3*i*%RbTbL@ZX$i+-v03e!r?33#}Xj2x)O1}`p=BaJJO#gqZ-k-{Uorp@v< zn{j|ZcQszr%azQptUwkwr@8N^KAYyN`}5r3M%aq3eKCHhoeqvKRw0YQ6nO1|Se&Xt z7L&-lV87VnjS5$r{}5tF9uYUZQ(@ol6@vVqf5eMfDx4pkFElJaBOWxW;LlE7?<T5qaVU)$$Ko-Kx_U&^rP>+aZ*&*%cT?kC^c>ciX;sMLB|RDg zu%K5Jx>5VP(ti+5dsJcFA>W1H%?3g>P5*SHN*Fw?KP>H6g{>{}h4s_>!nsjZXk(Hh zbk%nNy@^%GVl#cH=LGNiSK;h3dg?pG5jJ10LKeSiNaiNk`>u+f(fcYaKD-^iR;uxn z4ZC5qR~53@Ph)>=gAi3E2GE#FCqg#E)nAnu;WdoDpSQwx!z#>aI7IALy%kE^SE1c& z2XX!vUr2SV!r;+8#bKwn!AWg;CWXdk>f3)kh?SM7LE|wUSiTXe&(Je0G=7tn_fT+M ztZrXH=N#G5Qe6+r8?=T~Q`LQgEQuq-={XlR?i}dc`y3^R`5Q#Bp1UfFp4Y`Cdt<>e7qThsboz*eCSWK~Y zXa2^O>#$Cp&f<=FME;FOX41 zDE4n0y3q5LFza)$P<&A&r6*~eyPJCigWuug$3K;DzROnO{)5Y8H%$+3wMYT z-G5^U?%PUZ>J5_#ck20)tkv{?^iyxaJ9Hb-p?m+{J>Dne4c3?(C?sLN8d%K7* ztrEiYqJ{m70?1mr-*0QbBw@swL&S&1={p*gDrlRZAmi!&y>91ngwBo65$o}lVEtGn zn8!zwp_3~ih|b%Bw@6OVm~^3MPRK3jKjY*3=|01VU2@xk^CX;Nh3kV9I6E8?oH)=%J>8k4T9FgcbC-$fiKHoMk0R=naz)>F>+uE4e?6!>? z|HkQiw3NooI$a>N4E2@=&aZ&&vMOPQ%UF3UdS}-Lj~_y~WheQ+o z^{?O;`v1MT@enbi>Iv?nEE#c-?Ei|WAhbF{Tt&i+dx?x2XM2Q5~2ow7p$~);cyGO@0z}|#!(+c z(L)Kk^qr;A&L7=|DWRCYv$EFiz#fg2webWO(R@0Vd=+*i?ZJxGe`5~bU;Z~1Vb#pP zaq%*2=sj}uy};t-9ZC8dx92JZW#VoX{Q$(z{mBKKeJA^&^80(0QoGQyP%4XRL`fs9Pn7DDwiin6McW#swx$|U(n#A2 zrS_uz1f_mL>ky?nr0s=Ld(r-bQvadtf>OKC{)1Bgp>2&)Thso7Qvad-1f_oR?=zv( zqs&Cd7nNXP)f{s4TZogZE8)bAHgLH`EAc|BDtb4+HH2oh5T^~P0_)~>uy#sQF?@a% zT_f!V-fJ6*Hv+5RZr45_bI=h###BM?c>oh1mCKbMt6*f80Z{$oiF}RzC(v*m0{$5n zD!MumVV4(LJ`309x5Vdp!Bp$rX@oukS;Qam-$9Go`hGX-qIbM6GAK2LFi;V9w zMSzAmjX2)s(-ZWMHs|<(U1xaEirP#$lcU>1`ivGFKXR~uVT;T-jw@>h&Abgcex_^$ z7l;1h`43)V1kJMFb8L8!?qN6($#K|vU3j-@JIB+9YVq^4EPr->_W!N3v{v1Bi|_P5 zL+`Z$m^};NSj)UKEH?<`*mn!PbFxUyxzxBZ7;g9F=?#0=gPB7XaolO+PcnMYXpRjG zi%H7Q_8k8Rdq>9i`6g%iPt1No*5@4KIJ8~@37nM`%hIF0?~p}%ZpavR?RtlN8W1Qj zywLd`x!G6A@x5D*N&j_i2}^Hbo=Ud6J8^8?tdLx2xqxF&hwo(d)U6!<{8AUFE{+e! zn=)M-KelYcbaCt?w`00EZf7lHx;VbAGlc2lIQr)ppt?AI6y*w37sq4sX8_g3Z96x@ z3#cxRzuj60R2SD$sl6DeF0S!R+r>b2$(j94OuT{W;&@@U7f@XyOYe7mCQw}*%dbrV zs*B_1Eyn@X#qrC*Lzym)S$oy%5+GU@e}-Oqgki$)kshY7tBD`STTSSHwf8<8yS=F< zi5mbLY$K4^rB4T7LJ=aK1s*>_!8P*;n zCrihlk~4hYFpdOu(hwOQWc7&TB-?TPX!ILmW;cQ3l6D28tmz7l!>qrP^TT&=ET5tW zn@iO8&kbq>B^?j)bhpVCkW_Yn&SF*+f-pF%~YVeI9_El4yZ1UO+OA{x;UP5S;lm6?2~K9ba8xG+4_Imi`MOb*Y=XF3nUsT z)!?aP3f~7E;#l#aHH7)9@f(#L%(4&S>5JaTz}MHGV;`HLuy@=ljx~3Ug9%MtI1WBD z6&_9N%yD=dPf)pNa%}%#KA7G=EwHkDr!IzuS%or&bK`s243=~38Z{oyjo!iWxn+((b#XkeH(|Os z&T{L_baDLE$%5(P*nLhTri)`YQ$41O0Oo7uUW(>o%dfIChG8K&URlbk#kOLZ~i|&vnTqR2Rp^ zhSh}X;<)1@U8aj;)?RUc0?70oUm?iM6#l&TT-f9h+{GO?P5tEWNl-EXi+L7|ZbNRk8FR+i5w&MsSDB zDbf%be&+FzBs}WG@wSt%$&?urIqtD9pLE{1lH(R(-$-f$e~xoI>A_HXZybAe`pQO- zr*(+qsxcPeb^jp8*IYU?T^vI@!gO)0F`4cS7M5|`Byc=XT^u{CbOWl3TJ_i4H z+PLTMVbiWVDhw{@8o~6h1r8@p7vn zkkG}4<28eZ!DVk_jxT#S!Ai|uvFzDH3r4`z9y4SNw{#l;L#2};y59iz=&XN!k*3T+8Y`e)aN+9XIF^rZOn05g)O9i zZOC!cqx3A2vmwW4r?zCeIBq<@3Dd>%468I|x;QRtU7zXV*tJPLrioX)|3MI}g%jx;SpTp&rx4@!WsvGhH0(Z!=-KMD}cn zep9B4W5c?wm@bY#4!2^uIF35o0V*c#6?>fh21)%)p|f(4=pFt8t~+T$eCHivlX<`3 z{PD{%N_x?aYVh7k5Y%7*(XgXA%{6>PU z#)*yQ)p5AnumyC^^brFcH5~GlePCHyioCFshQrwP>4g5P6Hf$dIqax50K04bL`@GZ zhe`K3f|>m+o+mLM0vG2R%G>S!3A%IclQ%Yz@}KTn4t+Dfl1A8x^Bd<9NOzma?X=!Y z-w_wj#ZJ!EbT}RJfm|Nag4=NA;0VxB4Ht|Pf5XN5$>i)Zo0#yE+74sx{U+y#A=i@h z+Z7B8dP*1FmT|B4GzL9j31SLT=dhl`)&QbesfPiY{_qhY{Z3QazfiqsyFGnNz0)L zJ-hO2i4kEoyegBygi#3s)81i=D?KYTpH$Fildc#+H~(Qg|0?eeFl(&^VH&quI)TsO zY=PD7s>^d=4Xok(x@9e3|7=%ozhN>BZ||QbR}Z zow18+d48!EbPp}!{qWAo)*xsoIZml(1zR=L{d0?-4U9Qo%F``=*g>Fn4#%?5-C)e* zR~#G8?FB2U;yCWySq4ReFLA8355V8$mAos}d!mOeJo9@bPgtt$Fw&?qgj~NZZ%fn1 zE4qVWVWfP2jJCt`#6JIJ-NUhI8+ltALou?Q)_==29J{JBa`QiQZE)x?P}WV5f4)!! zuT~EJ|Hb`s|Gvj>(!-X7t$P$(wSeau>b0E)wr#NlafI4*yu z$#ik-JXMG3QscaOOc!DNi(`$LE{*K*8j8^aufkz^htuwBmoVPp8cgdI2XhlbFrUV; zKe7D|c$Hto+~3z>;Kkc8x!XnjBoBuXClKZxxPZBnBOugU1j{BDu)~`OXhrikJr#m( zI@iD;?>1NkUBa9;*Px?b92l*=fa5Z*fpwT1%x+%5PT#J=#7a5jjl77b;3}9TiEvdv z1pVEvLQ)>WViT?Np{6guvh2ox!Nf&dVCe(BZUJ%G#__DY7;xQ^$niE0k)~@C#<`Gj z`@i5l&UJ`xRSHk76gscYVk4s=JSc*r@j$Yg=3vBH}VQW@VYp{lIa1 z!(Kvt8pn&}-!3&;)_i(4$JAykpOb1#(_^J{%9l%gnvYz{hvqMr@~7p>rE;k~a>*WQ zr(Cj=+Am7>Q;njek)@C7`IOth_`?=F=9uL(@xS^h_T9&pUcJv%pnV`dNBjpvxz zImDmFJXhqH%N8tn$@_qN<_lT*KPl?|FmbKWDS@8nr~P4QLZGaA=c^jdSfQ)U8=k(RQd9P& z@oS!59w!RQX0L(unV|^{g&`WLoa6YubIk4TYEIpYCxqpZshqQ-a*J$W(|4Rxc6LH+ zmrQm3#a6Du{*~`J$MOBOn3v{+#EQ;N2 zpte7%tyXNo5;dpiz#j6owr_b^o&4*_OXJmjzT4W?a#)hi^U+K6l6z~tuH|^me$I7; z`1r|Z_DtiPPX1fvc1vDz4lCc^J*h2A%kDAfFzx?re#AMfEv6Z(^Ir`tHUjC9&!$A$Ep9QIZV4*^nK1@ZPCz3oe%2+b9Sn2W_9R&D}i%Zn>J{#wujI@ zQz)vnv$nWzsLsbdbF5(b=P@sfwd39J2mDz=`%*j4r#zkYfvn|^cslDdvka3t4mBMM z);(_WIqKiIzUyS3&gLkelO7ziKKVM=i(}T`>}`EGX5;JMc+aIJu+=1*k2{|Zi(yB4 zEXTg`g|KrqavZZ@9`t^5hvUbSW<#ee^_XR49q_xy(-(S9gh1 zX1bBW7ZwUJyuW>D z?F#X&Mb3HdIR=FBYR>#ivq1GyIic`-sCpxwipVr0dYK^;X4M)qJhAc4v>$kT ziE~(6?Cq@1hxLJ+OKO{09TvX{;T+bcyM|un`LI6YnXcB(+M>UmIv>_IPPMwuIjkMw zMJRuk^`*1E5j>ssfvE?>cslDd*&V|Y9?<|H=87-n-78)FQ!ve+17n9Xf$j4{mS zJT}G{W_GeUkzqFGq;xhGB|aOYQa)_#O8K)fEtSj0x?~TV10*}y+#uP{<_t+AOJ{Qm zE0^)vT*ENShs{9@v;5iI#4szD%~_mJ?O}5n!^}=L$1%+8XLBFJOc$FI8D@H=bXE@% zpVg0)534sRe^#GTxvZWgdszKTcCvPn?Eg>NcU_AZ=#(&?_uJzuqoJ$KM2=tRAVe&k z$ooT&mAB}*u1P%IST2WXn8MQy`p~(p>13YXP8kQiEGP5+);~4|vdgA%PHg%OcsWkZ z@%wcf`i^tw9F=ej(pz|NPWH}7xOGvT|EQmGSfA#}IV0#i@jXDzX*nkX*4n!8vR>1< zYPp3M=N!uphkG)2o==0oaPZcez&Ri6Zh+-8HK)0C<4Xv1x1CU1mPOBDoWr#LvzhL@p<|G7EPjvR9A>j#(IC!Yb-3k?V{KW} z22($qj!mXLu)II#u(oJuq|S%gY@g!5IjjyRAMVFFtQ{M)SKGt1Z<`|H9M%@A^ws&W zK4AIBiI>Idu&Zky&S7o3R2azfVST2Z=P1r$ZSg_Jo^x2=I9@V@b67j3jv_pr^`$d6 zop?Iy1C8GH=jp7^wA2~KG4o@nk8y#`QUAtMd%x!CtbUk3#5in@id&Zf7mp9V!0Lhd zTMV-?^>564FXpSTbmn_8Uxi`jdof>yVdi@=Uxi`jdof>y^J!VkS7Dg>Ud&fvnE77J zS7Dgh$^1-)neQT{GoMD{Ghau_hxtHK{>(R$%4I&2WDoPDBs-apCE3q>FQ%Q9Rg)ge za1CG1a7{iO*W}M}O}QM`*u!y+ogCNLFS2}Uba7mxm*bjx;C$8=%(rCxntJ27ran2Y zsb@7`UH=@{vtUugxNdcb&nLPdA zvA2|CDX{c?OoW;QUsL`x&H;Q5+jF!yNB=__IHxV+oMp{Z z=(C$SXV&~@5ICcf=l>$(Egb56k#nAVvS)oc=k(C0P+xwJb0)Wb1ydH?<(!uB$@JN! zoD;Mp8FVYwan8*8&*9Ol2b^9Z7@NZ5mtDhR1IVb;Z0vJSWm9hG% zDT{MzwEvqE%Q!VQ%UM1(btwN=S#rjy(at$FZNWJ;Hgir*9db@hJMyw>v~x~PTX0TI zAK;vtI^>+1Hszd}KEpXRZNWJ;eS>pq+L5Q%^d+vhrVsG+nm)rZ{YF6c{#MUXfANrK zjy#=dr|)ErS)FVg)Q4kM5A>bSF&i)c#`OJ32{qpMD?J=0m@mYV)VxQ?=#N@2pyT==WEx zo%Fk`)_(fER;!VvOTH50OFk6KNAj&${*uqd%9VUEW{>2fF*_ySjoB~xbgV5TUytdP z(pf!7d{#eFKCIrP{8@cU<+6H~>|ymU*~!{Pvj0D6-#`6_q2%k`*)tp^UvJ`~{wVo+ z0eeTFxIId~-io@8DEWH6_r{{+>lJMTlzcri?U5+?dcEd2 zqvY#N-7*j*UvIk4IFx)n@#;jBe7%uBhoj`{#mBgyYG03)CHZ(%1r4Z}HRa}@3G9J4v9;gb-K*&Id36US_h`ZuOy3ngEP zjxCgYC_1)K@~!CDLdoZ%V+$o;jFlz%Xmo6$;_S3nrRwGN7d?m)0d?=QW7tuQ#B}4U~Mn_Ny+T%!oqC*ZV#1DoVbdM$S!?e7!Cj(J1+PtJ+7P-#nuC11~57KM_p*XL<0O1|D)#~74+z3R@fDEWFWYebZMJ;srIz5d4#C0{ReDx&1; zv9cszZ&8allzctLk$gR7v*hcQEWV49ugA)gd_AW9|6%XFgQOsy|8J56k)VJiF_2Y~ zlJ|z3gJdKJMRGn=H1i1wcn@e zQ{}IoPd)W~>yf`+HPt)Q(>*=YJv+;3tp^#c^`NuXda$9^dKgP%kXV>tStZtp`79t%tRwwI0@h z)_PboLA4$YeQ8Pwsr3T<`>%(Yu}9fDg=|e%0(;cr_`TeYJ<8TW%-ExX+15m)wUVug zNNXrt6Oq8!xV9z==woZrfS$G{3g~ZZ*uWg6oogkL*V+pGFiZc;GA^^|!z_9-i~d^c zVP4EKUuLlb%Zq)O#cs@EPiC>RlXv!K7Qe9m|HQxT-a0~B>s2~_gtXRsR{NlBceUQC zXjMm3Ot?%L9*-)_P5vd_`L8UCw^ge%94` z_J5fqt@S21Jw#gTP1%Fbx>|4Zl@p}3-s3Fakk)#Y`<%3&b+z8^`?UxYpbE={eF`uZ+EM)>==-;(F))-xo-0 zJ(1zMMs#MG!L2Tm)_O7)%gEe=Ww_Q8ow;rj8*&{dV{v^Xb7vXx1D379`Jc?P)Yi2pendN+EmUEw3@&PCB@&sndADAVtV3vG?S@IBO$xoOi zZ(){vhFS6)X32k;B`;!@e2H1|s6abvGt5`=E@sKcm?ckRmi&!b@;YY8_n0LQWS0Dp zS@K3^$tRg5&t#VTlUedoX31Bbyvt*mCBJ3pRXXOrx z*L*O`y$83;eF(GMlQ7Hu3A5a*Fw1=lv)scl%l!;9^h9lmy+ZDDnB|^_S?+(B9LI5E3%B-#j%Xs4YG{fNwSRG>9LI5F|v%@VY+_Y-5|@zT_wxNy&|{E-6proog}x* z9VWAl3xoYf?#u%$?`L={+#%^6CGVs7v$zvNJJx?N;e9+r`}Ml2(5a#%**2(gU3Sz;M^ z+ru*Q)`(^BKFZ#Qvy8kEVi~-TviH~l8Qr7gtr5%MeU!Zq4~(UIl)PCA$mkv=Z@PFa zypOW?;eoMqkCL}x0U6z+I+l^QYAhpf=U7JGxpBL^wc~bqBggGnGxmEHW*dKe zeoL(vV0k~oW7+l2?Z~6#eH4Gz#uK+=9|&d}Tbu`=-NqK)=kQ)(V~g_uwAfIfC_ z3+QS0ynz08FAU5P?Z|sDF65C9fzc20HZb}}{shLj$g5c1>Vtd>3_X#DfuTS0HZbOe zybX-`YCG(p^01Hg1G{Peu&0g-JF7mhzv>CUsQ&-Nzw*|F*MPi@VU{;7ysqS34Y$i1 z7;cw0IovL9U3ksNTN;*;w>>N)Z(~?S-sG^1yb)pI`~;vE$jcD8ro%&g`zeNJ$I|QsxZHFCH9`*sFAJ`3y{$Wor#)X~1&z;<3jyyAG73y%#tfIOAg5_xh1pYoXnDoGE0ui zjCBXSvGydVWtLo*S#n?}?{Z^i$(flYmkzYUzUWhOZ)VBKnI%_emK@&6yWE~xa(-s$ zkM)5*rAAPNJzAHnKJu=)|K zegvx@!Rkk_`Vp*t1gjsx>PN8p5v+a$s~^GYN0t{qg4K^;^`o}Kk1CJ&0jnRu>PN8p zk>$mYVD%$d{Rmb+g4K^;^&?pQ2v$FW)sJBHBUt?iRzHIOeLwHsR3KkKUV=D6o`QS@ zjQj<83>bM0@*yzt9pppc|2N;y2m4Do*pFc3^~ejs$oG*ig5`Zav%K49miPS3^3I=G z-v2Yp?*c;5kIa`@?7%GcVR^9|v)Gea?97aO4S5^-l;1Tl>+c}YuD^o->+c|ffpP757|;iIGpZ-m!kG%;G_Lp+7AHnKJu=)|Kegvx@!Rkk_`Vp*t1gjsx>PN8p5v+a$ zs~^GYN3i-4tbSy9@grFM2v$F8JN&5f@FQ6L2v$FW)sHMMegs2L)B#uf-a(;}G&%upNhx*MjXh zguE7P$00i(W;+hqc{=%j-#N1#tX)a-Pit>N-NN?#FTHaP_LnmJ8_eoQw5uP%>PN8p z5v+b>dGR9{`lCJsV_v9Fz;-_))Rtho&js4;{uhw9`!v~jU>Unl^E!dN-KTl|fbIUu z>k4f5XeJC|KGQ}|GVDq2K!4H>miu+4K~{K z4K~>3W2AYV&BqA$acH;s7~wvS<>d`F*ydw|`#7-8#|ZavV4IKGelju38)jyC+syLv z=9yXELNm)7X=a;`1@zH3*yvy0T63Okb7_8q9n{Wwn!dqCyY%A)OaII=F0<&vEP67F z{+v(ByqIOa%wh+YxA`-n?!Z`LH)gRXv)I|m%NuOS>llmd;*?q9ms#SP zS>oNvyM2IJ_6KI!H<)EVVU~S{S@s`h*_W7Qzhahsj9KmDz+7aX474Mk zK)dX#%(CAy%RbC3`!lob+sv|`Gs`~DEc-vRoD0lyUNB>yL_P!^PN8p z5v+a$s~@!;epGqni(vI5Sp5iAKZ4bdVD%$d{Rmb+g4K^;^&?pQ2v$FW)sJBHBg=~) z!IFot&Qc?=uOOQZW0@ttWtO~`S@L0K$&;BSe`c1vnpyH~X4D1H8|zc@ zb7slgnI)fh@~&QEmO74E>ViN!?2A679%M#8@CVwZ?qHUB#L2sQlNowqeLx=iV|{?7 z-eJakwHPN8p5v+a$s~^GYN3i-4tbPQmAHnKJu=PN8p5v+a$s~^GYN3i-4tbPQmAHnKJF!FT7IsA+K9dQmuUXM5j z+j()EgYCRH&cSwG9Oo?WzMo=wJ1^d6(QfC(aSpcg;`0@3=M`wT^9sn@dGUS$89T2) z|8`!1aqYYU`q+5|^tAH|=x^6yU|wj~bqjf2&*(?v4*l!;$G937&`0A1dTJa&e~mB9 z3;VLpSKDC+l}CN7{lIS8KkTXF!p^D>?5}#lFRFjAzm$Xh2v$FW)sJBHBUt?iRzI@5 z_z|pr1gjsx>PN8p5v+a$s~^GYN3i-4tbPQmAHnKJu=-KkHSW}pXjeai)sJBHBUt?i zRzHH(k6`s981sc6!Rkk_`Vp*t1gjsx>PMCrKZ4bdV7p#8&ar0fI2`9-yIwfX!FIiH zoP+Ip;W!7|^}=xuw(EuC9BkJM$2r*AiQ^n>bS78>I3_$p74w6AM7vXU_XM@k6`s9 zSp5iAKZ4bdVD%$d{Rmb+g4K^;^&?pQ2v$FW)sJBHBUt^&^5RFZ`Vp*t)OOfGSlaz zfp*l>_}&7HcQ5$f0*v|_-&=rDm*aa2FzR)DZvp=IeUW=>1Uvk<-xme@>ujMC{KoI~ zJI_q=@}ePC#~(4^vn2|L#AG_eT>9^vA%E}Q&ph|x-=3w%_ApnfbIQ}R{w^n9DB4rJ zQY!QCD<61%*+|TvcD+`8;VvID-cYp|=GeBUXuFm7s{GkP(O&Jx_V3mH?YLeY*XrX_ zeXO27)zj+l3+P{{1iuZFdHD*jKk4+e@(D%HGNYdky)Q7Mf9jCNjB)S(aM{UQeab!f zo*8<6H0DQU=)bGaRc6d9({{(0ueQSuDsSiI(SBez?H~5kabaiG2liJz;g^8^LH?3l zh2ureL1xKwnC0ALmh+TZ&RHk#@+f9Gmzm|fW|niDSpyA6|>}B%$P6sYm5au;Cuxm zKf%5XhTX6)gJDnX%V5|U=LE~UJf9hUQT>Dc)uZ!R-lI9zQpT9AVTrt!UP~KgiWW~` z-g4q&Gv@pC%pseHnml)7n2)a?q=Z8HOzBrb}+fFtY*d> z56^SF|7PPrd&HwU0r?igLIV9vnN>N^fBsJ@1jb$6u1r9mN=@Gk==u5JQUU!R94Q%? z7uuH}+|D{c{>{2B_R-JDscx@8|J6tDW*Lk-G{Zh-=oA0aSIp4!`(+21p?{4p4l-k2 zlg>ECe6<~RPH!@2;$t?LvpdE37 zJ|!<@mOO`9@*if&i=4dG2l0u|N*=`w{SoJAm%NKv@-b$~)0icHW0t&*S@Jz*$pe`s zKV+7?kvZ63ST9&Nh&!wotS2zm3)UGJ>jmo%jP-(b3C4QCdIe*>U>$?8Ua-EwST9)j zV9XKm07iUkJK|gA5#QPm;#>PieCxP~Z`B9!t$HH9Re!{{&I|2`2aF4O!~+=pARfTz zAMpUjxQGWZ^g%p;p(o-24E+%gV9X2g0LFZ^9d=N8*hl+;-L!w$Q^$p!RUg=2^@Lwk z|6qRwzcu>zeNmi#FT?M|5L5b24E+Cv_eH_}LVkq*OBQPe`4RFbF!CehRbb>t$p65| zkC2Cfksl#H10z2|-Udc~g!~VT{0R9U7;mU-UdxPpP}`9wsyy;X?FV_K_K$p1$3-5h z`XE15J(0Jn{>W!_UeaD2I*7anEd4M`|I9Kjv*;57dC`+u^kKj7CSSG{h7rttbee-_G_#$n~xFpYcTFPuwR31K1SHD!8RWw?AKtM zj}i83u+7H^`!(2}GlcybZ1*t2eho%_tnH|eRUY>W+7Ipy0YgFX`X4%AJRP2o1eLPlLSXZ|Fz!I`psk9>&!?5c+6-2t74#g#MaO!grcyV!qlAJE%PD zqy4~c+CS{6JzYCFNFF8Y}X5+J^|bHLa0x` zcD)el6P9=13p3mGLZ}bXZr2N;J^|Y}`1gI0*bVh0Yyx|to&>|rs3*a&Kk7*^{Gxes zu)k~^ub8EL*}msm#Jn`m#C)|Kc2IfPNBe=@w13!B$Az6$AJ|{@gkMzuV1NDl zzGy1vmj7Gc7X|yv=41SZ3UO!iG15HE=3}J!o6W~a^E#W4k>-0gA0y2JZ9YbtAKHA3 zG;g%|7->FJ2Q*@nZ+-x zf3Uw~|D>ROm09*%X4!|CWq)SId51iS_ve4#7qK1Wd}o$(KVTo^wXl`s3Cxl|FiT$H z}&PW;qv_<-A~)bA(yW z7iKwknB_cTmUD_(&M#&;*O=wJ3$!Eu!@T5tWR`Q2SMUldznG;ibMpT`dtVgnFR2&Ur&32SOMSsCbqBN5 zBg|5#FiZWyEOiaD)H}>l2Qf>1#4L3av(!_}QfDzs{lzSG8MD-D%u>fOOMMq;M?4_z zAdh$eqaVZr82uw2z!(?t0ERw@2Qc(RJblydvy3X;v5;N*K?AO@0QRiX52BZGNeho%li1QMR zdJ+3I7q+!)*C*GLV6@x& z7M6j$y@z2&KlXlx8U5RP8)l4a?{k=;kG7PVGG9jX1Gj@159N9wq!BUK;Nk*X)^ zNYx*8q|OWN8h4P_xI;f0cj#Z^4&!RvK_87f=&5lB{WZQYFO56QSKDC+m4|(_AJ|R% zhdp&%*je>~{Z&u+MfDH%mwX?@{>A+w&L^x@+%MwX0^@!W=NTCHi#X@NxL?#fQ@)?# zcKP0l8TX4gMwx^UsV5Kf8id^t{aX88wb3PBQ9(l@cs_AalrdN z*v0{$2Vffqd`^IE9Ps%8wsFAc3fRU0;+gx$9B~ez-L9iRyIo%adAsfc{n+&w=-;l> zz_@n(2K2G(I-sXr?*aX790cZtcAP^P7xFlVz~~3(5E%XA90FrpoI_yfgL4QBJ#h|! zp+C+cFy@7G2#on^JM5tHu#ffwyJ`Qhr;ZCdt3I&5>IuK7{=xpLUn|VqUJ=jZ-m9|1 z^s7IYx#hucO!CxD%+p(^nLe-QX3pIGx~cHoG#~W5y8fnFceNGQk2i{4H3L4~!L{eJ zJLk+_+e;hByw~-B@zx&39Cd$_Y2RZxb8^o`=5EQY%m@Db$o}2WubCfw_KG=M`8(#r z$HGH$b-c!Gzt4$kzx$@P`?TH4lgitE?BA4e{n-9V`?uqgj%)QH)yL{ds;AYTRDU}! z(s|kWlFrxKfz%GxKBV@sb|bZ$wI``PAD4?Z#p-XRmWzKfFHhNR7LHiL{My^+Oz8<9 zG3Oa~(=6?ipZW8r_skXFEFa`E_j_p85AEUsFO9uxem}H31bpVokLFg$I|f{A(6{Dx z&(E13pWI<`Z@kz{j8?a@XUVLFyguAO+Cu&$7dHDc;1w`m)Vcc&Z?B%+{~H9kI#;1n%#V#H;Z3B zOF^HdpwCj!XDR5jq@NAe-|9?3I#ZC&6r?k$&Q|{bkN;s0J({$X=dxkTc`Ep7ALe?+ zZqpZI3ozf^_JG!;%=SU&3&nn;5>LB&z+ZQ^Hh*((2sn29HQF=oT>~C=^8{6UdpvVk zF)w-FUCW&P_DZU?G?h6=jS&>x>kM@2+Rdolg4e_U zsb7NE-oJ6}_ND(Pas5x?H}3QvlVi+Mj^$HJ_LyA_mvW4o;(JWyyGuCsJ4By14|4Wl znXKK7%lsJqz;sQV z?L+M6e*b}~KY6wfdqVny_f3rovwherV)FcEmf!8_flTJTk4%-=t{%wDsrbnBF4@%s znd?pOnJh*2hCt@rU%#3{X?sE-^XAZBO~-+ILLf71=rxmJ#JdJEJ&Rv6v#P#pAhRO; zs+n}`9Rry;7fzUQg~qeYm?bBSIWUf8W)wPM@>LwiGF|g~O_9=TS>~e)DW=tfH7s*= zaEj@?WDUz4yu8wEnUTse$s1OhhRsr0=2YvIro8=a0mdp^c7*w|{TY_on>O6E%youk z=C>MdIxalTG6N=+Fxk)FV3`WdN|=0eZm>+!?c(O(eLps&D z&oa^7V?%!4a*t*3Mt4}5-&h9w#-Z;Xu?*VlG=HT1_=5WJ1@+_8eylzeqz?t@L#mIR z7X{6Wg62g!FKZtPvJVB>htxjS&J<*43bHe)ovptp$X^uXFH(P5zf+LkDah}nez)s~ zg4PcOtsm0$W7i=CtwRc0hotM!u4f8b&lI$tN!PQD3kr%03W^KTxUlg>LGeXF@kJV6 zHclxhPAMo(N#itl?;Vvj#(eh9HtPQS8FOjU9`k zjR)q!$FqHqKfeBvSvbF|2mIQPznWJL?Fj*=y>QLcE%C15J|~^+zzWHGd zvwzh}v#V+<^Zk9pO{YIkGlzIen0BAsVD7#tHe^ES`^*oYw2Pg$=aIJiwB5>+%G-WO z`?39#_HV}}9rx0N6QufBJxTSn`jhH!=S4a%J73cIT04;1!P*wdcP% zgUfCHTRFqnjIVpj6=b>Ft3a~9Itdg=YyhviFoz5OC;IwifoMcQI-<(OIYX5qgmy4DPD=H`y8 zPaWqCJvo!xJM*w?~?DnWS;tHwSkF!l@YXJu#cy!K4~*qd|8OrBTo;XS+^ zcg)~b+v$%ld0v^@HSyjJozC-mG@`lpNaZhhUfMtU{3gru-lNkN@mRgeX7%pf zzL2>}%Jbd|w-+#XTK=LpS24%lWv_Tk^_$P_VZGn>UQ3xW#dN=0Tp+ zhO^l(QBAvfKKj-1F;S^_M)a zeB|ONNA)6}Os~24x|g|(r{O`ztt!{_{L$IPVD=hqJ?Bn1K09fEXFwSjrys^o^5pC7 zIC9clPo>Wss}9hoSBGq#g3nFmc)a&wF3+Opr|}%GJuc+=?eR38s6B%dzSJeX`%l=zaFf6rSUw$%j(1H=W9JY&&;GO3KiwJjd|XrBaIap2~BKZ#ba} z{W*o>vD2gc)w91lh3BaKqt9_|*H$iFc>ujP_;0VmH?N?4Fd9w})XI|Rls`u|otC-LIoyAvTOeph|*n+;}&6hIwj4A1h zJiL&(^Wt*8E4k(|@2&WbZ&8(5%$0_f^Tl_Y&Rn)fNngImDa?aw74)4bHjz2o=q$c+ zzl~*H_xg|C+mlB!w;q`2tzBRk^IwU>ykDLh#N2WC{gmg^1~8wP@JE#j)~A@)^RGOv zp69yby*)>I+TV8aGmCHbGZ3C2F{*;`4TZ^^%vG>v+q|WFSh;y7n<@%N)PKV@U}@G zd$(DCfqzd(^7b3*)CAgRDd{^BH--6)UIl$$ygiY5;JPfn^O-(n-W>j; zx8VGd%(XHmdCL_W##|xS2=ACHE~a{X`Y5I8_b%3Sj{mO7{~c>`pKa+@QyH?{`&ZFo*uQ(R;i0bmk5(ul2q? zU>fuJ59fM+-Zh1}{I((9{B0&PkNBXv_hjiw%!^O_o$_XjiOegyjZYc9U;=aBua{J* zT;1`>V^gYETk80Qm~@`AZJhjraUq`g@~)p-(Zf7Hc6R-T)Sl<*d)SRT>eO1#bEBL- z#U^a>eD$8w^Zx1Wp7!;f{#loMJ%gLNdEMQ#-P5v_n{T~Jn>=+IIy zEpt7!zH)Y({Qgi+-pbCNUuE!kI(Bz<4$1eldWP!G{`ubj-kW>)Cv+j}V`^9`!Mm`< zNSgZI-!vd+4&Q?d6DYd=UzG9ZUf!I~eN5kOe?lu;UG_#S8c)k+JthAS#eCh)PNVj> z9@EvxBPkrJd zRPnm^aPmw#X+Jyt@+-bZz6I38_ZKzHI?8iCZ7|QJ`N0C7>bdN153COF+<)x-?1cri zIe$8T?!yZ_muHV+{riUg6-d1v)oLg#m+_rEhF(fh;Fm2^7O6I#6| zd&u*jj%WKE%5cWh+Pp z?)AK3ZB|pfwg2-!JQtGGZx-u6B-ct$zXc0OCS_c5I4!bs z8Pm8#$kmjYY?HKuw>(Xf7qI@j=l1vP?X#Tw&-&G?)j!Q1PC2ZdKdbR_Nc7+H*$$mE zrFw3ySjM_#t6b94uS*!q%r+^F6&2SMgZOA`W`$=Uv5mPWgBXJ?mG; zw9E9eKXmC9ifmJ#`IqrqC{N8s%mvDBp_>JoG8c;6OvS!!&fMv060L6Ek~#b8%`|gy zUDIfHKL7Nek|?flee=nTeE#!&l4#!92Ij|)^7%`@nnc-#G%_ta=JU6CnnG^`eigNzSe^Im1|M7{pNej(dDA(NlC}O21HVpnC9G`H9UeA_jf$y*jnoK zv18Q%HhJ=U3^mK&j_1{DT?`$0r47$(%3Cp%y;Ccm*ZJ^hx{<3T&nx@bD0=nd_jq0- zN=DND`EFj?Kl=Qvdv1?cUR#+j|aOPhHD)U{)QV&+Imv zsC@1=JjcN;H`4J{t$B`@n_C?gx8^xc8?%9${m`1{c;(%AI+VLD&vAaKILdpw9s5rE zN1wW`;K!^7Hq(dA>+-nWDr}}~ed{q_-jYPAiS?Pwv`?a6UTeslDSr~(Ti=Me@?VM6 zpYBv3ssr@-Z>>-5pXWF>fjosOvOY8| zfz~HiV*Yw-0zGP6g}K#p8)?}7s?5KQ+(wBsAcqf$20t-X$?hz`)_@A(Oo?)A#-$E8;iXhNZ??8i~vH&UHT z)!2`(-`+?cmGZD3f60|d<@SZJAE$qqMAKu8i$UoheSY3FihgMB=29VJG~Id5&E@vN zXj(YV@tq|x)G^UaAlrjNR>EhxWn0P zNpc*`8tLpAS}>mOW_y=qR0rrYxJop=QmQJ?ad!0>`rQ6qOzblSO)PbcsLFF3nR^|j zZ(o(?Sn&PzG^Jz}o@2ic;;7ntm3WTYKl&V%&*t4n-Fo|V_gcDj+pWV@9V4jT@dm6z zq0p^vZK6h@dr9BZ1d5$B(A}FG81D@mSMI*`IqaM%kxZTI<9je1~ zjGY-te?6(mbL?I(k~-9Ne$@WikM-kd{heXvmn*sa?@W!MJ53yiU5=m;y@qgm-0;;@ zzwtokq_(T5U9P^&J646#*|Q%oAM3e{Iv(u8JUVd+h2?0^{Pyz2)bsp%%o$!^Oc#4L zWd7LRt=9XlCUdQVOX$ssRbBg(rF3&z1?E)~mQ#+`-(t@FYz18&SDd-i-7tD`@HOV$ zp0!l2_$$o!4n|S;xPr`)6V}nW!3CK6*4sd-qa6?WV-p=b;AC1%*+TW&xzAoXluVtU zf1Ty;Zb_jvN8MQW-X^*<&gl^MS}NuF#p#wXaVI6*bvhriziqkMq85Ml{XV;>*=aY& zu2*+b&1NmQT{-GVZhtWUu_Kknl7d;&6_e0eq%AUw&y$a z4~tq%Ie+#rr$4@gip{IYJkjPLr<2Ptm;Ei2K3rasIq~=^>ecHF=F@rBP{-Oum}|yF z(y*3=n2QdIrJ1n>m`gQ|r|In-H-2RkUGGwm+f%>ZOdB^BX1-P>nKm|hjrrAvDU{_| zG3M|qK6+v6o6N=T`>CU+0`sx~JL#<+Rhehj+(q|p*JPgEcNhI-V=dTUh>@QAQ>nxt zS=%rADdDBA?BC+2yfiH5hs;Y}-9c9>x)`aNX&cS#=3-~{$|Nc}*u~U}CkgiKbFudC zdidY99wvl^Q_M=24}bf0IK|Ja&AD#x)~o5QNW)y*-p{RnSdIC^4r}S~n##<%4%mHl z_q)tbhegqEgDNoBY#c+Qwv}U^P;(u%SXY+$bGtupc+c^tO*aJEy|p(6fR8RK5~+73IYJnW@tuHZ#*(zvSAa~^-5i=kAaPJ1(dSRQ}OfG|qezK%vLkAL`;;tS)u~#uzTftI+V4K8C5s0zsTcoDloSc>whEfCfX7^z|8c%pb7A>7pp>%(q#e@brnatM`Ydi=E4nzFVo{!+~b%$=v?mZC@gip z_>cMg>E75zwa521(4yOOD*g4FomrB_a8~5KaZ7Q{j2TRO2b=Jk{jlUBWyWE&%b{Fzd;WsMqyi&jQ)4_Umc&wAlQ|V`$ zlS9w?BexhD?&{*-^KUUXSJve9oO$YIbM2=P=KPdoB1cqryg$+SYE@+}7`@44{lM)5 z$H#6q6Ry|hT<+Q2B=g-bwK$g>cp%X{7gLjSxwSPD&C4BYa4y$p-6r$hVGrkWKYg;v zWXM*H^VO^GMVU&CT>iX$dXzbL(&g1zR!5m`LtGA7dQp@)^SsL~M|>1znuWQXvv%Gn zlcSK!MXyIiniod79Cb~>NK+xUHs`2gM@5*hD3`~U-L=;I*2mRrS^r*Rmfv)&Iv}4s zH8;wH*R00#N*@|!N?W@j5AQo9%G7CTcwQBYMwya7x_Mn~6KTejt}llc0$<||rgsfjFI1QxZ(jP{@%*pjOz)x2Cd;3!HD$($9B1y7xNMsjA~rF|lUMO843Gzr~pAyIlWKU1QAS1UIhg0DVgD+h9h|sKj%e z`eVH57FC(&`2M{(v!+uOo@2*X;>?oORoHh&lh>JqZm!lCKQPv8YFnA-sQsf)U00}2 zSH^EP^KvA(aN|)vum*P-KnyPW=!!K?5}T+ZZa#kNzFKa zlR5gft0mtWxyejgSdC>$f40diedOk@YZBwC4$$YnwLZ0f^qDs#(G>XA-AmL>pJ+br z#cbmdSI~@@`lAcN&^x3eRuM z?Gsn+%i3koHg z>^GaUANTjMe>1&ZGxlTNDoN&4wkEt*Z@1WN{%qBV{iyw;&*s@16vp&UF#G09R z+cDRyz0O?!vn}(XKh~M*wH^0QU2kq2a5nj1R-75U*l}v7c+)i2@#JC~%!6l+PyDdK zoLcEV`})EJ(`S_Hzg?M)ruB^W+`sAoeZJinYfdM)d#X>O*O|Ku+wvSEm#sG&(%QIv zW>B0-Ue<=^`1Xl-v-*4+p5tdl5=_{SZF!E`KlngN@fkGfxqG_w!6`U z+Z@p*xsIFrl^>%_{WEUvssr>Xoh!n8)2cE1@$sJ#W_aT!Jjc1aBTb_POmG@GuqWZu_qmpSWi z%-p=kE;D;<9p=PucbadTdYJv2QceC|6`5~)$Hi$>a6^klFY1+T%9$&R)X;-y4vbsuk~hT8^;&tMw@S&yE<#prM2eK zGFNA<8X9iiDC+90gsv;i;bX4O+T>qu=6~+$tjw`XO|!qtvkrGlFEPVjadlSKmW$2& zXjf<5eQmMH)y>seFNG~O*E6?Z`KUch%-FuJF7{4eX8Ja8b@9AQp{Bt=R~O&ky2{jE z@9N@X4_BMTXIx$U{nSXa>x8R|hc}5e^S*Gk@H-{q&F-s?UwORIe0JN_#eL%JUa{KM z#oY=fo44}~U>%y5Nih@qy1KaOVV@zdtBW6e?>Ff}I&SU2m}Y z^Zj?38W&t$eB-B`rcZ?sZg2lpsyT7Y)y3*B)Ro&3z2^G)lI+uyKWsOdqTgUnm$215 z`LqZ#l}a+pKP$w1V{n4m?ss<@zpk`@Q?Z5PbjPAi(mU>cBY*J-lfP$Sman`$+*CO9 zD)ab=mFBlL#h6DuS#I`SD9zmb;!@MQN_pnmEti-!m8&qn_2FVuDxwB+;a3)$s`VSV z_6dtko$s47fB5ARQ@U0==I_ccGh0fyyP!w?LQU14?v5y>=qmHp&OR*Dsqtzvub_*a zZ+AzSw^~SDJTk^iukT__?ep(?{@<~ly{~RHo!@db@A)4$n*+a8;=K2I?<7;StgCrH zPuyfKJ}&Rtk0+St`@5Pq`E+4wa@U-Jh7oyFk=iO(|WREg$ z-*B~ajv*1|PS=Xurzgi+bFyO<=KOX~h}rA%@N#djHYX?7;Pw?e!c9fH$6}v9vpU>7 zn%;mp^80WzV_p;H^q;Rb%Z9zjTx-A@bN_|b%&$kUHPafmW6o17(!BM22j+3-qRcSU z$+ho@F?El+nz!DTb!Na8SLa4~+l6P7zH9t*sb@7LpmzrN=t8<-Lw)Ju|??P*? zXDeq~Zv4O1;=1zW_~oX+xUyXLZ6ChEv{=@W>*Bw=tuSBpYs59_OA}X^9cL+^RXF4xE}msa*SDZX)w>X+2VC(&XAt0Pu{pVvnr`L*Oh}SCYblA0N2Is za>bipoAl#(CALd2@x{t=t$OYEjb?EBSGj&%lsm!9j~v4G`K9J2Q!J(j>+G|8_?o&U zxb_?$m1HK@aQ6WFBes}Kua@Py^;WiRX7cLSx!&|G-)1gV?Z$QS#j?q!{##9WtZDU= zP3Do6xh`(>YqCifRg!Df`YGGZ@`t^+E*^buhiPZOvqN3q;Q9`e_3Ikkf5zuhOxKXI zT=O0%`hMK@sGCcWu1Ycf@0nUV|qX7$46JTGH^gZS4<50AB?_)ar+ zO>Ne5eryEQD3w6N-u9XSdm`uvCD74OugP5?nyQ?NqaF!v~7h zmX9}3!|gufc@{z5Qyb{sA70a?STyD98c$Kb`OQ50U2WW^4YVR}s`=f1e|l>`0u|k8 z|JKj3NGkC9Mw+{yOwsa@bg;`tx*Op$f7tf3mp4%9s|)J{eXK656ZEmV zuujm&>cTofAFB)N1bwV7tP}LHy0A{r$Lhj5K_9CN>jZtQF02#uvAVEM(8ub+I*EN) zC$SIfB=%vQ#6GN(*oSoz`>;-8AJ$3i!#at5SSPU$>m>GJoy0x_oy0z5eP+ZyWPN7D zK4g7n#6DzwX2d>ZeP+ZyWPN7DK4g7n#6DzwX2d>ZeP+ZyWPN7DK4g7npwG+UD=5GH zZe!tL`^MwrHT09c-~ZL}(^uBexzvqx<)vKyR`!iyxgM#^k?ZEtcLR6QtoU^P?BnOs z{8c-td+IZ~V&>ALw4K!F=u^7=-5k0bvWvcX^n|YWnnNcOcG0`7p3v?Zv*}>!ZkoUI zZ%Ub+i4N?^;0K@gK1Ug+W%Q3c9!=*eETEJII|;njzMJd&m7nfsjG+P_ET(5|iSFC) zHWSV+p^)FbG+{z4b$@FajYvtMwJGb!({efe6uE<%*NCGLHA5*&>UK&@w}HOBA4->B z*iMnZB~YWjE9j#o$#nR|MDom9L6-(4Q`R;~w07AFI?^ebmMq&$ZN6MV$NMJJeam@@ zou%)Rt*$YDQ~!k*=(C$=ecaT>=C4CH(7F%iGlyqhPStKkGrv=M8GZIBiW1hIqCTzHQvYl#nXB439z4#< z+x9atTd056Y0RHBNTy~NCefHGXQ=u5ZFG0@WGYkS3{8D*8{L>cg&KZ)nsRpDN(Dwv zrLWqYrvA$g)86ydS^j#1{q#YXw#-FKr_x&)1~Gr%`Wwn|^d0WMy8j3*468)*C!eOZ zZyupnnpdUq+0M|ScBkm8JULj#yX8E6KJBOvx_LiJqpr;+G5?tD68V4X;e&3^uBXww zcl!CD+nt?h^s9H654z1-oJOOjkM%*fAM#wH*umX=pIZ6(xi3-Iy50G+AvrEl⁢Q zTx~8=>f}Sd*GD~}wHGhb^igAc_dj_;kF#8+{b;}QjFMizM0+gnFZ7IhRZpW`mWMTd zO5wZGsQH6SEYq~(McP>RA#=rJ7wEF}FFt#9$$7eDdBy3cG_~tFx@fsn>XZNDHSp)* z%am*P5Z|;~PyW%of^C&ARL7b!V+KVRW?PwCxX)9ANegMITmKc#s!F43X*QNH#apHikemudIm z(Y~2SpHU&YM5fwkU+2-!sL}_QsME<&zPb;e(%xp5X-VV=-<<rcIXw{3fJ zrc1QrQD5IS+g`Q%C90mOx9_rT&r{?QZRy_2x8HJ(&S`XS?MJ>2{h!h7S1;M`JqNR% zp*b(nrLBW}kyhuwlG4a@`@lEP%J+VfMiH3?`98Jn>3>S2=eiE`HM0Ch?=;Hay{E6Y zl{wTmjWWO0&sXKx*f2?frDKi_i1ZKl9z-0yg%m4)m3N_<%}fOrusU`}?pT{u7^;Ig>_J%8l{ui+Dhl z&ZbebyQ6(uEx&XwjcO#0_KmZA&~m}yqkV5!HVJ8zVd^knyUh>&$DR<_H|)GtX8w+f zK6LxQ{?PL@v!2@r_GNeRj=2Z#3IA!|IP!RcBBJk8|ItV2)kT#kto#F7V9${W$KIjScC53l&QP`m>FBoQtV1tQ zflIr64=o?H=S71ilYDDp#95s^8)fS+Rb7{KdFnRGo$~G<)<=ZTwk3@%+ROf z-f_&(vst}QnW6uTSI018UORh_W01NxYo|tsXg|+CSQeuFFEX=3bli?K zIYjmOe9Y(&)$@~ULqb&lW*G*B=)BOb^M$(F}U_zBS=TeGcWj{A98NT2mCUwT|=cF3o`2yWlC zWpYT$`>UDH_8uKFbBWEJ>^}3;w?jhSSh9?HX#L(hnspE5)Ln1W-NF|R{CM>D@Q^ID+&+gXnS@{Jm2Fxt<7 z7qc1dfAyW5M#nW9^Vsi?oIWw-@*CANqHRH=`cHVltx3!U?K)q`s~ymf+6Vos-7v1& z6Z)u~p{Lp(`m0}p{dMr2Mf9kO^HI}L%jn8`&MyxtEux|JeIfR%|FkdtR&5ato4<}a z+1US2@`oRs@`XxVkNS9@uhIn<*Png7)pt_jy4A2~-!~H1DVLV{QYEhImY(f<-Rt5y z%eu)vpTzZrmZN>YN?f0$A-;PO*Xz#@^j(y=M*9JYYsepzxJExuB(Bl_GKp)9`&i-{ z`ka=yhMtEcuAzUH*IZm(@tK3$zy=`6wVC8IpmtpP`wuk@g>VIVb732Uq7I z)#vnU`APL$TE8Hv{vSLkNIEaH>wF=vc0fOBAM~$w!?QlMKXrJoY zWc?7I>VIOtTa%a<+I7B=S395|wGaANyJ1|lC-hM}Lr=9o^jE(G`z!0rB~&~^BHgfc zgvqvu1~o{as>e^!@&!vM;qfMVyVrRdpK}qF>%W2bw_uszJs~)*gX3KpHDhqD5?ucV z%P3>7_)qfxq+SlrfBsu}k>*JM_uBlNXDe0u(4HN3j)@UlX=jZo%*)ShrR>EgGwWxO zUnxWW_q{|#8V_KZzNhxu|HGs;v*ulpQAQ3HoSOybUBR`y%Hy+ty>^%m7N|;jqEFGz z$A{^Mu*y^tKV78OUHUQy=Y+v|a&W#EoGVuRa|2B~7h#I-PBJ|c6X@*G2-7$r z$%G$GpfeBccLw8=&5OGesBXpx6PbRS88yki|7;Xt_K(+G;*oXn&W{EyBF{_7+p}+D6(J9bsO~ zv)OD#r<$zI*HQV3>rCU@@k!Iy%{6y;-wor&(Dumi`V~ZF? z+Q@tu34zIDcA!{S^^!heqZ9~>Z=KEgTjkOI~8=0N=cNl9MvNkdw9#1jW zHe_vN-h4gTSlf`bk@+L@c4KWr)<$N}FWZf^4OttRE}j%)Z9~>Z=HoVAV{Jp$MyB5J z?a;?SANUKtf@WDr`i%VrUs<2Azu+tDGxisJ zWqro}g0HO4*kACK^%?sMzOp`Jf5BJQXY4Q71~!7fU>n#7{(@~_BlrupfsNoV*akL& zzhE2K2>ya?U?cbowtflU%UrN zeDNM6@x^D5?{OrNqq4hB=N<2ki-}7K@wl^8A*Kc9whO_dyvEz;+_2^@lFz7 zhi?An3d=d6Ui7&#QDDg$u6D7U~d!ob_VNZm=;49cj z;)}2+N_-LaMEGmTjhi7kJkRlWAKBiy7ZOs`@txX#h77)viQ7Ylr!(zFInM9NXgXze zoad|O%y(1W_a;NiE-<&6x$jLzm04geGL-GNG0jtJ2;(r zL;BxeIim@Y{)6+twqusiC*LR1s8O3KZu%1He=?B@T3$bG33WY}ND=pw=+2i*XwmnaN2hbin%j zg*MC0Qu{s522Y&zf2g_T-A)(n_c-hS3^hBlZl?x+CQ#wQD@@6S$@D?KM0#WX3NwB{ zG9|Q2qCBfsm>V6EX_3_-*d|%RR+xJolUcX?V^^3m)01gO??jrBYlS)RFqyVB*hsy5 zg_@P&+v%M~8)(f~`#xua{XNN;IC{`=nK`f^g>v6qM~T^%nmtFn)MQO8eYRw=i7Z9* zcbxt0X_iH1$Z|hb%@sql3okSshNn`wE78=c<_0Qrc&2F=pW7cgJ)T-6%rb2(-}^m| z%IuqAj@vg#AD)e;v14YMuZ!gNH>(>*L!xGy$F{xGpm?gbWR~gJEw_JD@pwAZWtRE6 zaBlw#6i2C9W|>OA=JMxg7-yQ^N9=ZE^h82<<1@#Iv5@T<7CifAFPB8+hE`#?3U} zm3J~9+5W37cQS9hFw2Bqj%S&NF*D7a7dM!d?Q;9U#XK8K=p3taWBW$pop2s&$hPHX zPeeG6^~Fn}W^BgQJk~pHLQPnM)!fgw14E7Jx!Sa{b01?ryJqex(_XmO=2a|%_IGoJ z@n_Nhu*G5AXVp`o=EIb5lO-y*|HL)>w(3!sIkq~t|CLpt=7XAHX1C?;Swc-c|0;7i zGPnQFiJ`_@ceVL+ac+PAQlaLN$G*EVx&5Eea{g_}J2 zolK$f;ikx~T>esfLe0nv;pW}>uFt$z!cDsdPJZ&haPv_{Cx2yKn91?T$)B`(W*X(> ztIP>Ele`%6C&8}NAAw0ALC<~ zzsx_Aa?9EaUWbDp%r&z&IGGsFXG3Jog9n{+@{lPnG14h= zCf&;I)_G^k6RNv)9z6HM)(*7Dtx53s9B!?G6O-H;2LC>Lm1%9)_TD7>TTY3Ki#hG@ zZZf#InBF3kZq|2kF|KbYo$0=sX1`tA!hxZ1$_KoRR zo4M^>``AI@W@uN}zQMkg%u~&^FSYA%aEIJ}U$Ia!IaizHQck8;_iz(d+R2=|A7;L@ zpM}hWsBp9Ac_*{xS(v#eGVl7sOu<1;=EHK~CS!Uh6B!d`GFNx~9I!Foe@brup&iSq z_K0wE;HO;NXTcp|W=VD@KdM`p$z=6`%rCdXOr4*d%-WV=rv95EQzp!eo8V+p`iGf8 z8Qr))r3*9b-*@f*7j0i1)>ZTLjf!HSSd`MOgrWk<*oEC7ir9(WU?T9PL%so0Vqm}* zurP2I6a>55+r&gMF|pn`XSv_&-0$`H{=Bc}dH$PgubJIFyF0U=GqXE8kmxO>k3yfT zuBLz@hL`ULbPKG z=EmZqxBlY1@2wGwjZOr>(#ASWTbJ_Z`T4^MvfJsqW6)O5A4;p~XO{ku6UEDQR`|ov z5wyP$|0{(*lq}`t71{yt(Nu@cc}sW0&BDaCtlni}K%X#}Nqa}>`%JXn90vDkZ?gTE zi7qzb(2Mq_-|cbIJ+Z@lH7;uy4t|?;*qBRMIB-%p46UQXX4=ypTr(Wb4$xsv)3Put zJ{%5^JrsD3ehY)f#+>K-nJ~CCm-A>FghQ8aoaf4}Fc{gJm$%;?206qp$c8Nr17G?s zp-%6~VIUvI>6WfxpiSc-?VEJJ&ia^zT@s>TVZIS-Jt7BZ=Z8b_4C8<7>3_0cOZRty zPV5&Y>YYF*Swx9*D$r+6M2d4Q(9u2kUcZd?ecL0EFxp&)3H0RJQP6oLr#Co8K_l7| z>)B^vP(>ubihsY?OR+>l!WDBpc;AF_&z`&wLb>83@0&nRvE+SrCCqU7aU_f-of2qQ z6Dpst!(#fyz=s}uJxkZNm4O@`daf7Od46aju8a#2X}dXTxb8!!NDtn$4afS1i?nnt z31jj%Mw0efihrJL*#`HkWrOCYLCi;9XHi5V)QIP8ooOitgWkLkuSe&A+YvseQtY(o zYZf$0jDiI;?^5g}(}zshN;)!#76ADRpEJ=5CW@W)4TJwi!%?q?Ht!<#SJ>^;!_>zuHCLIyVU1)7*(b^7c ztA@>+!{L&Zj>vP9bi|0t1s*S2=drZT1)fQR!a?7e^SmV;8Am!Ils_O{dquh?)Sp2* zGLdvdC?9k-44#mF33OF<7$_6|Ij3uD$HMHB0kDYdjQ@gID6RAdPx|&)n)eCcR*2&u z&}qH6y%K2n#_gD}HV$ZU`}V*f7Vgd=n?rVK@%|WCq3;i;h`vwdwf+5J7vY~pRDPnb zKOCON=}h#8jOvYXW`2 zrxUay9c)YVqIaFZmUJ`jWe}D{c7m77dHJaP&XE7Ju~>eFc+Pono|loGA;Ch2Z6N;Z z1Kpvtfeu^Jmtyj}I>Xc9gu95I(AFIsJ5xQfV9Yz>4)3PW9zprx`pu)W%G7@(y0`Th zz84U^eV!NJBZzJ@*^}=bM8C4(cjwpi3Bi)(qeKk+`cW`$8{-AF>DyQB4o36Cqad@9 z4ohqtg5@tq!~3B+?CqXlY}3{YURBesv0iY0CGB@E!T7E17)YRT5O`*%dxDz-FF$?X z3zUS_#qw99p@tqWUp&|gCR=hkGt?6TX)jKy8w96K`MgNy$nflXT(P#dIA5u?g0RPZ ze&0d(-oL+PTTT#I+VSr?SStv+R^N#rS;$z&WykFdhRgtfF*H^iZGypXKcDMlYInhH zz6PXysHqzaqsIZPr8Oh)EHUTvF3?SG^YtLmQBV0g34ap=uNQQJ8yjeU91sk|_{~&nxc?*IV%N3+bJp z1KCocJd^GfZmZ49x6{4O^)yF<>@5d(aH?#~lKO=}iT^0^8>j9M2A_OBkJ9nkN@KNV zK3_9h&x4`4H=lQ*eDV~&P6Ybye7=4JdZi6tSM53nLwjdF*8*MRA)jA?&K$z$^k!Z# z%!}h|Lnwb3#^+ZkpVW@8AA#PynXeO(emxp$(%J}Y76K-;PK5P#;6wz>qB}Lh+V*b| z1${L1#P2#t<&EpM5Z8miGq|U&xV8oQC8r$oKBjMRjJ&29xS%72Z63rss}2v8>jOk zv2m0hbnw?<(r--c5Di}K8jIgs@GKSv{8dk+oo~lOQPbM+ivID}UzUT{el75#v9bu3 z!>Rjqz=CYPbliH)qJN*6O+-IH;jcJoJ+PrjOUI|^V>C=q=s+zRpHHedI6bL>NdL(= z489=8@p)R}m|Xu6hY3S?{RJ~(@U|as*YG-><88wGY#AuW;ScLThLH}t@+21X@A2rTB}BE|c;P)rtp2b?uVXtH>k$mVfI%k@{!M>m)(VTglL_)R1YvO@ezz)8P3$1NLrVG8lbIh51(v*yB~n zp#7EZvbu+Y61dgfJ7cH`N?$zsG`n|vNu}H`5-})k?bA7KO2{UM&Jf?NBq-GL! zrS;R1)=&AJBrG#bfjhJ|-2IdB*yj`&Lu*EJK{77*oC;g77%=HS^}ofjzx&@2>ikdt z^8Zu+NB{OeUFtWmYOKH$uh)rtMBUyS@w-8=NSBqT;ijoFk#_iN8~PW9inP?v5VTZ| zyNUwEfB&3)a(p=_5a!UHQol-$WeoyFU%~A2iFm43h{#jxXCm5X1dBWm+HXVy!VQ8y z!7DipJ$yq&9@8Uf*!`0C&C9a2BTuTyF)Dh-A6SM-=hN;W=U7Y@7E z>#;X0=-k4(FnG5^k8NmAxdct3WI%mEm`@-Y`jnZs%47}SgX1@ zc(Nz?K-^n0&5LSuunvR%ms>Cy<+_|483uJPwO~8iWuxErFsL}ug4J7=gQoSv;9fmr zwtjF9_G=ynCPqf=!^|A)ZWs<}7h162 zpOw=+vpM8@iTKoC>Dr8`DQt7Y5z>Hep_oYMeD70+!#^VK)@??R~>w zy<2nEt0W5_51_U_6aJ*}aoQaYBML~Tg4K9#SOoa&*I`eS)OdJbI2_%j!(7&@ar%e| zXhHwZwp5|{w-JI`a$9$< zi30N8avS(3z8a}-=imCB#va}VTZ+R(pU>`-+n_tyu}fq#x7^wWYO-U3k0?1U4c<-& z6?v`{q``EuhXT)h^1C+)lZiaNFD1g0+94uOSdEQvhwQ4rQ|3Z3Q}$LYk3-H!vV5~9mpO^{bspzZsaoAz!hWzS7zowzxScA zmu%yB{T$fUDHN8I%{;y-8}H77ET}>zsUZV8<|S-wayk!1HSRwrG1c{6#i!E!n`F)ND|j zb6fYIK@P}!g+U{-bpvd(!6Axl3)wfnj@jV4gWI=LSLhCDwGBM)p93$+*4-yt*Kc?Z zG;hIe-SvbVctZ9~N%rmVoE*?@84jDs?imr!VX|+6t;2$B*m$1Xx}1G#aCPIh?n^rP z*21~1TS&3m+SWBu z)4vYcE5X(+*qQ_BTe+YmDi+=1NgoeQNn*l=#^ zGSk!$Og2rhbzei&&~7BRbrq>oI&`=4W>efV-% zLl|I|%Qy_`Q6T%pjV!9PxigpuLJv{NE91w=@)ep8cjY3q}5ln?86zT`2zdb$vJoqi6h{-vjR!KA-;bB~LE<4_c^ZUqRFB6OJH z10NWhT_}!!P4oe+7(UM46MZ0{DbVy9pH#1b;m^mzN1CrJ8voi0eL+q07Z$=#nj@jyvxM>u(YFib16>Q@0?m<7Zb0i$7%QRN z=wSiWp)u6a@`Z;q?{8_|1)k3|Zqut}GgcJ9Hku28XZ_g%xJTFq;(?joS`xAPh&3B!)Wd%(cB4b-KI5j zmFf}7J2Yjmm*!3=&!=_Lj@F4lr_p+t+@Pkl1)Fs^1TB4CA)=QB^QO3fU#rg0hH`BB zybZ<{scz8!rUCODCd2UFZZOT&nq|^^AkXW&K({PwX7VNoKQ!z_d6$~9c0WS!#akC> zzrdO$jF6%JcvrYnZo?KD$?#U53rx|nWdTva=&Gdp=QLq+*URwTJ69OF(U!%fgy5OH zj^L@qpmTlVagyPg6c;eQY|BzzWOyo)^69zRv6_)G{Qkrh_WiW|N37>h z;t0~%hcrGSov*(0gE5(63c}f~mD}i@jnF|NEsZfmMEqL8mNOjz%cnso@PJmn_+Ui!vAXXtz$F;b6yH;$+}`-xWHpwPWMmWbib?1&Yqwu^Q1KP-7C;$Fp04Vaixn_-tjw z3g3pnlOL|o-o}E}JQ4z1yj>xyw*~9jJ_NSey1^FG$1|O&t)5&TeLe;Qog{*lR4&A= zZc({4>GI=|GU!G0ThhBmb3D^V*yHOtq9RstLTQTX{lg80LIm)1Z7cbB!ee8QM1P)Vt zb0Fzst6L%9zHtn^B7L+x8w_=?juFd)_J%-X_p#ti`q*fC2n0U&g72hL2WUKJZyN*2 zq<0VN%HY#&Z%8A3eB43?2S1L1!K8x$H)XJH*BCk%XwE)n$>7lxZ}@Q7oV_=ffq&ju zm`?imMn&UKvQ@(@*vw%v&a0$dg^mU1|OI=OdvfC?jVCNcgI2p z(#Q74A}Oxg3VeFmvkv;vQ0JN<3|83xHa3@_5e3U08bH7@WA<<3V$v9sH2(D`F+PFk z?^xmX7SVW{`q_v2`MWrs9gD=kUz@}*{A*6l-C>!JWkGS6N;&*=%cax4o`}#@@Z_ohlQ2l|f z@pwtu817QLKO$q%^j34w=5 zP!1{OKi!3#itne8pTXq2NM~M)hvm<|iu88#csRN0i%5_1*#IkleHQ7VM4w#r&RxLX zqlvyy^S!%p)a0!E&%E#meK!<3*HSxck`tWkpL zSvogQb>1DLgi~{Wi1i28RKl(HRU$pKnF8#0eH7`t=i}kC;=M>qW2ps+@o?}o@6VD| z@lezDgZo+Pk2m>GDjR(i``K({JUq7kB=&9UPdU7(C1j&s=t+ z0<;poh_Ywf$zj6F&!TLTM+%6XRV9{J&5}b!>KC!RGv)0}o&Qyo-PT44Z|naMdB(*n zz)%01SbnKY4%5_CBLBjx3P@i4Lo6Rcc_W?mzl-I0zDh8-t|9(=J{v{jX7y7ne@A1o z__hWJ-!-A564v&oI|elVhgT`+T)Bq$4?Fm-0*Udk~v*7}+BjsD;vHKXlR=eG#_lG}x5ZA38Q{cmmUqre`7bO}D{w~t}7ty^ zS9-s$>#3TeUerIYz~E4>JJK-`=;4%;LeMoAqQ}kWIw;Vl8eA9tH^wa>NrCP6@^$rS zDAE1+S{l$=iTO+Unmkh`$Gw?+T@CN4#2>{q#dUb|vI3uX;p_A8a|P<8)D+iY*;vYb z@|~~wcOw+oyMnLPn!}aoaru|1N4e7!m^q1;>;F<<-yd8T!fll3RF~_T;U@*g)a2zi zRw!`cPp%i97ZrFXfa{vYLIobN;pHdN6?p0@*YPvM6qsPnb#3!#1*Yuax;(Z-j_-PN zTXEo-96$fX_4iUVy-7Zc+YOJTc${^Ck9i`{I&98u!m8Er*ub9Kq6s78@sl05Khm5? z(%dp`-R|IwZdqckq{8G|DBF2kq>V>k$J>)*xtrSU|mzfl^0l=>v4vCDrOla6L6dM zdeAvx${LSK!Sy|YA=<-~&3~1Sldgt<{c98UbYlj3l*-`cK@&EydnRh?g~F)}lYhiR zuem2;%I5Vj%exiR^xA?x%VZ+`scs^k{k|T2*6Xqz-M8S_J2H`$#(Jc2sNcn#{yVW7 zsUKJxvqGK|jB(U=T)~msDT87;99^>pQfUmOzT$wfTfk_!3>MNj9PgS4-L|e5X`9|#!1%5VCet{)ZjcCz zf36ql@*p3KT!hfhq#64V;fr!g=e6~FQ>K_d0ayIRphZ+u7I4`YXFn)__=Zi{3g7W~ zB&iU#>}v84zuEtk4_R7|v@M5QgR%TvvAADYmW{xYr9~obUgm}4S{xH;ssHWY`n~N7 zJ@B_t@>Bh>@u1@(&&{`; zam3pbBK_c$Bfir=E%N-%hxsRC(kaj!Hdc>M<69lU`W_!Q`%({>+MkbSn+Jno@_9aY zR^=n0=Q2KbHsxOMSM}UUedf|SYaD0`+ci!@G2LM~dZ8O^H97$o2I;WhwI%(QKk>a! zZPN~Fs7{IFFg&drxLq$5$LH$k{$PHMk73-!{vfL!!+h-lP$%p-B+%Wr0TqK__ESC= zF0%$hm+^cqR_quIOA?Dkp5bqX!{h2X9XNjkJguJ7rnw^^uX~ZmGrimsOxp3aF>8(& z4BXDw#=dMX$bE2BnE-D~g*+2YS;#hDxPA{Ihir?~=KRk0F0EhcmzMgUr9N<}e@yBxmHM|+ zo5^rz=UyPwwq<4AW#~L~Fc`eH{)eAa>LdM~ul05@z5P4b10ot)uqB=$_;id1m{+u7 zjmm?uYKjNspV9q?4@c^&k@^XxzE-I(=y!f6sh>*fFVgHGgCWBQLu>k$lx8y6@7@a% z=o_Ve!l%U{FlVR-BvPN(dWJyoSPy7JeKsf$hSX^uP)L22`dg$v4XH0h>bv;c7ZH)s z_W$}Q1p4pt|JQf%w;w~``PeB#R94{myIi1$ z-&DfuA#V8sPmn)}-y-$NNO`1fNqMAg{m%FDzu{Yu z`Z|V@Ps4KYbNBua+p;+Y@vx{xxk$g=EQj&-FGTv%c?B$us^B~~lrZ7^8;E7zO1j~$CVtJnm1!!2*fpHqmS>8k?7?pf?7kCb4D#3yH z1=(fcN^sj#OXOKps(`l5zKA?CzbnAHa~;^%ss)oTR>ENQcXxqbUZ8{;BrDXZcS8=Z zyg!KilT(y1kku0TS6)}ZsK=j0{-}mZ7&N>NH0Y$u7RZ#aM*iJhkbS!=9?U+y6J_UL zR>C#?k>nW9*Bn@zVAd?n<^!&qB@0k>r~0%QDUViYjKTyh7W6rvI%vRaMbIw zDEkqVP@t*<&0-8#y+S24?*H9gkR62a;MeS(C|j$M3WidhLc3YD$?r6#Qj~4{oci;s zmMEL9tAxk4pG8^y!9-`*0l!Q`_Uw`py0!i8F39>7#l!6rZ$;VrW-73tI)!$J(HSad z{Yp``iu#}RwU#Km%UTI_t3HXc?&FnEzoZTnm$qcbAJaQEdf(jz*@%=`B`lfy zNtDfqra7&z1!r2)`6we5)HwIeU66ftJ09d4--xn97OG$&)hV?5xSIkl=)MAEBg(c8Q9&Q7Q)oA0 zpaPa(e<#Yud#j*4@hgLD}ie-dS1W-H;On-&C&GGqF^R4_UDo4X)u`79ph*L)+& z*4d~6eX3Jv*NJ?9#;SLs?CLoxFz%@-%07@O;lYECqHJT*<<~>C;PL`<_Gz>V;@5w3 z7i4?Aiif)gUW>A2Y86yeX^65{=^dPs(eFgrS!-3`JVaBJEmtW)bMHq{*7>{=n$OUJ z*3lO1%1jj$&-&&r^m%e+JPh)CEy}W^Dk!8ng?9bt(VdGH??l;A@iZo5HAUI?+vz=> zppT;L=zB`&yhaPw@3LfjR;r+K*f)1UHt=ga0T+BFVPK=W&FMcHl{ zDi||eQ+6^n@>eR2EdF36_;iU-@PuSD6U&s8v;>J-{7 z4pG1n#amIf^&u7bEz%TaHBXSfSbY>_lYc5frq%-IGHW(xvkFF;d~+9M3u?~&7qO5~X0%%j6Lc7|j3aH=wtteaL9?fZlrYNiXObLfhd=O>Jj7h(4YeAVI zoq0H+g1lE%?t<+1CURK(u0oWpXPE#GziNoGdv_{e&y_c#Y{gp@WT-SnSyR&MJBc4e z+1gH|3-7d`vukUnd7E_YYL&at=a%|%c$iTk%06*TfIO;GXxD4M0=(sKMA;j)65!Al zO;OfPO9dLUKZvrn-Dus`s|)cX+pw|<6|}%AcR{wZu^fhutq^684orYBs#9q9dm-(2 zBj1R!#kvV_Hb+yGb=FgXrTYg_cHmGI^fs*vFXr2`qrX(pcWafqAUnoV4h4-WMA?)H z3E)F@3hi#D{dY&xH==BgT>{+C*A!*lZB*dV@PjBjZ-NSDyVixCQ4TD%X#y;ZsB#x% zm$#<4Oz}%mcE#cZaH2YecKhB?z|hODMcIvz0PjmRMcLl2DwuP(Qk0FKuY$NCbz$R9 zN4C-`0d_2`au;M(ZRL=({G}*6Dl`FVQJq4&FUu70X~Sz#Hh5?P)V`uA$`0;F_2g8F zvSZv5;KrCLcY#08MGkfCUyA%~lM~?j7Y&g=?lr|YhQAj1J-t-0e{H46??U6O)xFAH z=+9M(tRn)H{$$o??$dE4o=|Y?r*5c3 zRp(bC_H!k_vBp-86<=?U$7MA*hIAxf{n7;-TmEmy4y194OBwMvr;_8Vub1W6-izb3 zw^{Lcdk4ozql?IYuEX(O+C4em*5$aX@!oj!@Zp#z$w!Ifia2icCEvdCA;)#SUdS=< zI>%H+@k;zk`;LGu9S_CR8vz{KET6B$$Xy&a&L~shp}icxg-%f7?gWlwpMR92t%~EQ zwCzefOZ5mib5KD%T9$A;GkU!ekHm4@`22(dM^|z@yzo8w{DU}tTTHQ);;kI_M%Pf_ zh0z>G`R6Nf6V)kTPQT;vDEH@h##yPvisc+PHn^$4mGwE64ydW5_l`M!^QD|x*K;{G zcGgzlvKAaijXtl$#Z;$&IU`QTV+}`+XLNQdvDJiX+(@yHbTf{qsr^4@D=Sf0_J>rCmsh5O55#|S0voz3yvr$ZR84Oe2zdK{nM-K)f~;T*pOj8@S-WsZ~kM=LO6 zILA>ZcdAgp0|Mr}qb)~#&GC$KxeD!vaNM|eBYm$a$LCLrXx*A~{5EZ-3XgQ>IQey= z0tYqWIBF}Za2(YsV9u&$a(X+S&%c%_@xyVB-ynwO zVhqR0Zo3tj6vuJYxW_82Np%XC)6GOk_N&2Oy;`q&G zvkE^<dITg-yx806oo6_eh9CVoD#*iwq z!&w}k8(GjgugCFQ`7ISXhI5>J_MQS=V>ymG(>?)*Qk??k+~+38!n+*vZ2hLfRp}fz z?yRrE0Yx02Tenx?_S+o4U9C`2-c62^7rs#7y&)V^ZSR+W7F4HzIWKpm+&l3c3k5c! zw-G`)ZaizK!UeZDK6mP+!qZtCzY$)=QJXnV)}=UjNF$E5){jfTPoFtnecM}(DSbJ1 z@-<7qyYo11eA8Nms<#}UyNx6pzKY|ztfmP#Bb(#oBQ=z0f1cwp-}wo6n(7oVXXAl# ztpAPUF6fYe+MXOkHgzX`(c<{L#}pMd8N%_N$|?Z^4s)D5QCo>uqB(x+9F%~mRHuMH z4QL#?bm4fi<3L)^#vGFmSggX1CL9L_x+P$A3CG5|2?=yBm}At>-U&F@lH*D5akR!< zIQE`9FagsqaoqbpGXZ-OzkoSc`Ki!hFvrqT3?}sf{>gbK=~=0Ndrm|8e$$`4kt97o z@F!;m{O|HJ1ML?7Lg^bifAZ!|o!xga=5en0CY0B`dl+Y`;%`OOyoIS7E5)~*+6CUk z#JZK@TTa()Z=zqud+{wNI=qZ^z3*|Jid&d@^{&X%Q+^9A0`7`Drw;vvv7b(gJYPHh zg%xW~iaf!0Zlj^YNs;Gli@VrvcCN_d5Pt`YYvhVNc5ZjjJ3mL{8QAL{njTV$JYNd# z;!j_t$P+;C*VHptiagS@0n+>LHT)tmfZjxmx~9vP_K(7FPr5T!q01f)i^NIya-ilp zT^2_7_Opx__r>2}{oW8y;8)_WnJR5pbK5eS!EsMY>bf+t$mo5uD9)b7u z=nh+oE_<~k5+BsgfwRwbSuc%947#U=7V)}lasw)lqI+}~d7XdX&Ht0Oqy3eLW2T)FGq0a){u@CRFlwW#g<4bnvq>WUb7T;ce(9&}{I}+!UYP<*=dlc9_{ppPiIZ z{@4jy;je)P%po%ts+=>Sal=XBT&8()~}S&upe{fZ(P(q4bR& zJ2xO2Mww+nW=%b&yEq9xoJogaZw#1fcN7dMP(yc9Jyy0d2|A>0qJK;ScK%Hi41bmd z<}LM@;mJsdny7|m1@vA2GH-_TJk0OD_xRov$hf`SXx-B?Sy9S3|#qB#2p@45J6PWIlGu5dJI~CK|P5%fphPy=w~W z(rU@9UM54|iz!g^t|4=2kpligO+O8CTN^S~ zD+TJirh)BJLsnXz40l7)V9t0$RuY{I8{E?1vXLPhpOgX}PNagO=%2LNnq)BZPJ@X$ zhOBNv3S6Sxwm#J7T_GuuqNMzmv4-sP@)Q_Xng$1h4B5SDDe&=28njz($aLwuZ+mY7 z>j{S9c>bL)MHt)vYCNT5zL@f3=vR-w^z4&B>r~H$KsTzM3n|Z^|HYMeopg#&5&jICSz=q6gb(WC0pp7jJmXjYBX!f zMmI=C+Z)NCFl)(v%um7-e#uaCXiL^@T{5cZ4QxLTz5PYpH1L)uYE-nWuJt!M%g#V);JRQds}loYf4X zTuH~4LD_n9HgaSv^xV4?{627=zwa6g_54?|()xvSgG*C+ThcRx0zIt@Z&#ovD|x$8 z9_iV?{~!O~^*c9?!+5KuP)XmIVYUIoxAAX(=NE@Jm+>)azcvR^4t-c%rRr5`mm&Rrcy+b+XcA2sci7D7} za1cz_GGmA4C1P%yKv*1V#(Y%@1dY}3+Qyu1qgh7b46nB{XN zX3SUzLnF=DzSjx(ZC@a)?rO%G*H1#byX)cPS5wy1Ed>XZ1;Gqv$}TNUL-QiKa}{pN z%#Wqxv6Uf^=WEKW^|s;{ZMvTWrYv`92A-z#fio>lnY91XK1k149&DY3cj!J(t?{O8 zTT?Y2F_3}H1XJcvrN+?uGB`Zhl-1SF#y)#xpw>10$C=FChcdCzIXaI*-(_r~#!1Iy zFr%3%(^t_u75Or#-Qu719M;UiYi2U&PHoNpoP%ajG8ov~lugab#nDco@Xg4Sb!)L3 zf87X$$)8NvqshDRQj>7Vqx=u`+;*ce8C-Z^!a^VA;8e={ zc8U5w(KHt;cZI{x9wu}ag7Wt|m->doF&i9RapfJ|RCBdr?mQS&K~Aw2QfT3c}$s<-utAARDtYWDwZK^dI?x zr1@BWH=a(Nv+=?R%B#D;n9XmmMxC+IP%y%nwWM4J^jhVV}4%*Y)l^vjZ ze$$q;pATE8aY4IS*bT<)H074r5Eu&&?2MW8e6K*8PK$<%*NoUHqSHS_gNBK*NRK-d z1B<#CGskgRI7%-X2JSOrrj(yqV@)&+t#8bFt;)g{7os83-k7cJp~jrvG0?!5a*XWA z!c2{5SaR3sU$-Ugr;Kvlj9bt9EIo%T(B;*A4kdavZ8g_lX^xk>^e@|X8DC>F z+;SkppRcPob+h4H^?IAvEC;Hp*H3OrHmo9>Agn9L+Szc*hOf8Llv97j7QPPuq}_YQ zyJ15ry!?{osrk=1HqE3c^VSx#|HK5$ZFHG2umANqXlMJFr zzxs@$cb`B89$u#GBjqg_*?`;6LY-_VCj054XUe4K!~Z0YjqnDO^A{NyKQv+62IoLx zl?+0)Oqn_-2PXC=J6UPMwl~OyZ!8odFPSjYPPt&(It(iJny>>Nx$tRj7=&&zVS1Z# z0LjjHlTEv?p9}lQR%mxNVJk-D!sWdYFqiB}%kw$(ZxsqG#)S2GNUNnqIK+{Sa_OH7 zE3Cqy)@&2z?n-ZPEeVIQBTU$_8#!R!F&s`bA^USC2W&mVVUi}D=f9Qb=jf_I zX2|!fwT@Y^-Gc9B6Z>YuUTeO03v|5;GH6fx)cuWWa6H2Irh^@_U@e`=@7BbW#js4c zN_$xz@%&C!+8-%q8$$Q&oN2Guw>4)!79_$d!T`Gn1DMnQR};bp3c?0sYHo&0gc*=9 zL#Koc*iTrZ)&lB}BoB-f6aIJZ3-nr<0cTgpz>6?ISgWm|-B%# z8TCUByFRRj$An?DduO6ykA~3jsUsVBh;pFiHiR8F9NBaGJ=ncwBZyNwGDz5ub-U}p z`KgZV=Hr97cV07SqT$F^|H?;`Kt0G>>%jc)(7Qc>tzh~?d*-Qk6x+s_!Itj!Y@uZl zeo@)L>2+<`f;+{yZmlCs%pl)#ixND3qa*y4Z^y1YC_(2n-RR%jmhCuQg4^@^LrO0j z=J)eBUbY?qm*@`r;aA0&xnc}FoNL9VY8BxC-H8yt(vp4LQ-~k)r^DkN7ED`<;mApI zprq2A9nU$8%3TX#${=%gtN8(pU`xU6j2ZLmzZYj@u7KTh%~;Zm9PB+i0B&|LW7kHg z(XuQ6rdye@Ji5d3vhGUgV`|105%zoJTOVRloJ9JfX9KWU;KUYF`IVmyU~O9`wp=#{ zn?9%yQ=*;N&RctM@PvjiW1_;8Ibv~5dw zcz+dOcyvp8&&Gij%Z}lT5oU1qg*}_Lvls{Mw}B>Y?3wPk5jUb;woIGKZT1WTA7kg zG|;nV%c%aM@spvihZVa??b;R2gvc;UmQ4ML3!Voie_60vMu=VIi@}ESd(5Z)@4UVo z>KB`{3-n#Kuo9|#%-JdW-j{n^IvPwD+}U z_a`66Yp)$)lTjP?baOFgN3?+{A#GT6UJ;JcwuQ!T+px4F$FR{8OGqDP&uVTziUV$& zK}NPcy+c%p)2oajthNKYKBxeDEp7!5M>w#cN}7u&2Jk4|f!$wp1kd~F!ORK=cKq#O z(u)?b$inb#Dd>{2bYv+ygjZT@xrvcVs1B_v5t>jmaPA$b4ZR7Vm5X2R=Kp z!z<{$_atqor|-n(?8?P4B@JP2J11sRmW_9v8bVSpCl;@%#^FW{;Y%AQ*7js3w)nOR zdfhUkf5R+nWWN$TXPU96r>OkGYDjxd<$Kkb<+2j42AQ#(!&z8jy9ORtn6b8)jiY`B zKr_;7SGyeC+jtc`y<^6v7-eJh&{gpMsu`Q!JqPn|2f(ISGghI@#(g(egV!fBW@eIu zYY(i3g;i!u&oUQHHw3`pL^C$0K`#2vTMZv;nltC-d+<2r&)>4oj2--tix~@6g6>;0 z_Uis_?6rFpEu7Y!9OS7NsMXTK_!1kIMn{|9I?%25! zcDk9fmuKl6`2ouzzJ@uQwrw9;PxFV9PUdWB*nXTdKL9q5r+?}rc{phGGSF#BIX0v7 zu=(TVFw57ReGSaR4;lWjY^gcrggJl(2baRq_U3G_&jI{cwgLj8%-Npthj7}_#qgHm zp`+U$M91OF;6sc#bFX^{=Q%Hj&_Z)&*zGX3%vuE3^N3t%HuB zbM3{T=t8*^>=E~?7lQe8x`QA?+emxNFljg%09}9NLnIVgu15-y@uyq?5 zp6N0lw&hwdyQd75&VKN8wFTRo&Tv+nx$vCq+enWBRDGBWtFK$I@*f50FPj6oH7wbL z&V_hu>`Vx_VZrih7NVceY#9I3g0;9G7w7`-Nphtg;(w&r~?-naFJxp`JhulsSzmp&Fw zez0PO(~o1Q!UwuNvSN!oj$`q1FNl9(#Ue|OXT)f@e9)TmP?ezJt6>m$$eP8@ zCYv*2B%Cd>W;ec;VA1`N;PS$nZSPo$0~(G1FEbm~?{Epe+B*o|felN#U4nu6L!nVS z8|F>+_S)DXa3hXr+Si=o2EgUDHcZE@6tB!02qW`s*z=>M=w>|#rjvcPqxydqdcd|r zHnfM9BK92s?;6-Ld5co~mDmg9-nQ(_v{L+<-w%3Q+cJ&srMM)hFNChPWm_7S;(E;< zV3ujib}cBy{%d=JSE((t_)&tjox6eEBU|?3St-_Q-W~RIvtx&Tmg0|_z2L<;s^?A# z0zD;L=tMb@Mwa5Vvt1$A)sF4DSc=B&yTY^;b}V^YDZWv=L+Eikws=7ab}Vy+Whbbd z`uycaC+Km(j@|8Cf{zVdpvf;gR?xo`KYn(FSshxlsISMdy;}$9)VVb~sZ)w`%w6EP zUu*VMUV_iuT)?htYc?ah7$b}wV1a%cc19~3*CjQ8IWwJDSKBPq^JxI*=F_>jby>Lo z%_`V&+l-YLW?_WqD#$4{V>0wA=uIa~Z}53XGs0EOD-Y@OF$^z0e{Ni8U^(TTknP46W=F*0W}llEg`_6pGK zYtHPO=V7yfE8zWbb9VM~9!3W*hl*Kb2PP4gFk23{$^L{GAHwOwm%_?ybLJU;2*00R z0-?;DEjWD`hxT3!3o6W+x=lXHjx7SG@3cRD%SXk=g>cZsf}NXn1cy{EfX(eKSOo1s zDKqCmL7)XYI)LHgGjm~wf^5P!hW@MOzBMV%(TFj`Gu5vCj#|al{bH`($U$_S=_Wy$_=xGR~R}-(G^< z!-mrtS<;0@rKq783||-7uu~&SvAw)M?0;p$8ZRzIg;5{qvCNiTA$sBYUX*XhmgUnL zo|(}dn*Oq7p5sfg=ukJ9*3ynW?NN&5(OsZ$ydCTBP>NlK0ptbQu`t4cr|P&td7akm z_~H^=+^Zubjcd*NOvuL6u?->E(us}zMQh%%4;;*}Wj-3ExHh9B1P8SK2Y&k#>>19L@Ty@PAsnIJ{+cvvSuSwV{ny{Y~v0a7IZEK*Te&idt%GRg;6egmyR%& z?3G7p9Ja0F2v7I7X5b`8c|$8`aJdb$IikeF0mfjr)t-80Oz} zWK|ba(K@IJ+#sBJ*&zkz_G$)Rgg@Prk}$7R3z+KU$m$d&;jAASDO%@Qg+@5`HPiOh^ts!0Co|(Rn!$E`F z0E=qFS~$gFTCO8FTeV?h*2m&)PiN52Yt8zG@5J#VR>JCagg?V~;S_KFAM|F|4t%ho z0W6#4#5_jD;YM{5>s z8jJguy29D#h}l&PN2GG$E-49aNTzR3tKx@r(X=(4Cw+Brr9x{vS{2C?+$xt&zcYwg8}Ed z!jLz%%;;z|zFyD;2F2R3+>B^+9^MVqo_1{N{20u>)eCUAEj!yP27CVM4&6W4QoJ}C z*S6>dUmx2tz2z~eHL))|u4&7hTf|_0lfJOti}Dl7qUl}5KF~*H%PK=+P}|u9?w+z? zH)5i(v!WkN7;nq$GGlPW(*e+HDgBpqj6vbv@_?r{Y~aCYZ00!-Dqq^LBFk7j)omDD zI%my1(qb^C_fY8C&4wNJiN(X3BVf47nho)Y!TlG9!%SNn7E>OLi;RbWMxqUi+!~8> zK8*weZ)+A(KNg+ujewGi*33F62D7$}1Xub8+(UZtX8ULe*iZLr2gc#xlU{J-0onYF zSbTrd6CB1^Gv}>wIDCaS9L%y}+h@n(a~E$Y_poMbYivLh^Kr14@|*P?7KisckA?BC ztys6?vFQJ4EEqSpX69CLxHs1ano^xjA8f#~cwd;-z>3w-+ko@r;~^&0iY1PX$FE%{ z!e7@d*&?lYjMtb1ql~Q>e2>Eg+7rPqfc{CZ#$(*+NdVg|*=+v}IGX5>eXQ8}Pa80G z+7wvOf^r_-mE-xdQ$g0xl1;8H$7hC9p}fG7P4!ctU-#*7(ZG^v7%OnN?hLS>V#!8n z$}xKVbeMh6k~#fU;JTeNVBISVCRb9vi`p}xINXx8wWl+Ct7bvqcuTgzgw7>8%!aqA z7VPUFC2BvL1+s>gtj|F@FFM%|t}Ulrg?>tWKX49gs%yzAeG~BImN_tO zMKnKZ!8GcsP#rZF3d<~*W1b2Z-kJviM<{W2TXgtutbmHVRRjs@5(6UUjEVtsUZy*{i#1N~ajxUI z?zh+3Kkokbj2g45XIGd#`>9zq3r5UCS7yZ5J&a^uygf17#h4exMbUkX^HFMH%*PdN zrM!6aX&cLkH!a-4W>1(8&nHHFbIdjt*>3@gJdAk!jBPAv#6n!zZ^ZZ7(|&pi{ZEnK z@?~Z;OKrIjd%79%n%djg*h7o(k^YZr-Pp#4g)c^OvJp4Z-@(rDMfgJh{(jZAv&vN$ zBYKGuANq6$OZ8j~%{N2tpSFWVsh1$Rj}edX+0N!TEkzUB6V#>suNC!{U@ZOH-k!XJ zbtNAxc7_qZ+I=T8N$^6G5k|b?f?aHRo29r)|CQGBV%YA}OQF@mi0>E}%Ut(UKFXtp zyuDQ{i_Z5#_lk7hs`@T=_{uW$qW{5{w!4{AeJ{8s8uFX3cCmrvH#VcXTGwLPh11Ki zrLGarq}(0*Modm1zz&0n_QTl_;<$LL8|5!ix9B!#l1byLyFp#^V8alfW5XMjC2<_@M2 ztX%vo=tmjzYeA8$N5i=Y?`O>I^tQ0R?w&Bxrh8(ex3WGH7vRzvBR;WxG}Cifgr`A9 zyvF_QY{`YiI6KyeZx7wcy4ftnigrfauKzBUH^>V;3}{SscC$FAWzhO$$WIlR$hWyN(L{=$yC1Pm~xLw%87RFFJPf7l~AG??4f|4vV-l1Fq z8};4`8mc>OUINpqxeU9#40%kw1Xi&I&4CxhF)mDGvwN?=pY%V{^m!s%J$wabJR~k_ zO(N4VT8=guhWvTAy(lK$wHooR0T<(OlX%zN#Jk=d6^l{CyZRCDy6DXgbSB>QEb*>q zW4A$njsa>B@7i!<6b=#Znn=8BBRcC^tF1AHc-Lp10a$LvQ)?kZ<2B;IvOx<5v;-iRdLHFr}0R+|sTS>j#S zZw*8ZFIPMu-u1jstMk;l*&&KCm`{z>qy?Sz3}aesGZ9z1n;_*+8^p6c-Q9iTur9n zUB{3-9-93T@$>k1-(~V2f@4A(EF}P5xlDh^+Q%0!MjeR{`rz3 zc-KjU>n#_&tBkh_-c^$EGZMV(LgzggKS}VeJ3H<{m4||NT|)buH)aUlwV`PsroI-u zt3gR1I{6CTbw*(jp4Jk)tJ}F??0PJC*N+cEaQCL*UAO9l;pp(joWJk@7g9{2c~`$yla$842JI& zysNWrEK;`Cgf{W6zIS({G>?35;$5%C$78OY;9V!KPsGEff_FWWxd#c~1n*jxC1R(Q z;9U(e_8{@1;9cupNk9ij!Mpaokcbf$f_MERKOT>N3f?u_BOcwz&Pcp#_>2TJ8zgww zuwL;bsUy2yw zUAu+Riz&9;Jf?H?P1<3|MV8kiG<_Im~I zs>3MW%|-C8VGnoW_+-JmZqV9^A9Droy5`(=+*!E@I>fs^`??)*j|A^puF4L0CkWnk z^|xpYID?S+s-u0Q!7F0Pf4<5w3w%!+oj5%}Bop{&g-=kpO!4m_BcisIn z3Pw!??>Zb&$f+!N*C6*u^f)MZ*Y)KiVV^B{SO1=oNZ%@WSF_;}=aUi9ca85v&ysNrX zAY7LU-gWlL04%*Fc-KDD0^rkF@UEJa0OQ8vzi9r-H;(TL%eH?0Dp|XKLl-wcO6FY4$o>1#&F_Y zQ!Y@B;1n0UAl`NSL4R1W0jNg2YYf@jh3@@vg?QH(`mWs$>Vpf!yFMLAIf7^O#USEc z^-lYt(98vs$UYZP`}?wbA%=L@HT(VG+N%#<6Yn~CzCZSE>54$&U2Tl%S*$0z5byfM z*AKcIdcd1_*AdJ8VOhB|niB6ipuRtzukM0j#Jd)4_Q%0C&M+n3wN{KDV(WCmVd7mo zZ}LOLjjnh~yz9sP{&<}MXoz?HXixDM=R4v6@vZ|>{gB$WBPJ5>>i*CVVFy*%K)ma! z`T_V^?0`A+4?Buy&^1JZs+;ZHafa zUg8hE7Ifb@@vb#L_+zJ2JG3C)HTY&Anlu-@tL2&m7;F=~Yuea7*fU!2u1~c0pvN1* zyXu}vL}ORMyWSjc^I94yZW-t|UQEPTof-gR1&SX9UnysJ897j)NnA)RL8JUhuAS=o@4`UGT2$JJOl-bAoqW>PL56tQ5Sfb=z>Oqk&EcvEouEs+>#kP*n2_d-3B!mfDT~9 zyB-`xb9fMtM7--P@&ngsJK`bnu6A_-VAS0n5yZP5ZkYf(cfq@E-{^;jHr;WI{!O;} z_@jA(J=PNMs`TG}$M;bBD$^Ps#2;lo%$D0n5K!jZ#H>1s%Vj=K*Vm~SUFHkjXwLAp z%tu;KfpWQ&`A$bSW#Mg^Pc>qHHUi6hEp3ln)LtokurXWmaJ0-f`*Y+e%26PEw$Lr7 zaHGtZ`$6SL%Y3{kB>%n4_p3wgY$@{zr&9Y3j|pG#4|;A&nGfkp`nZ(&mLEvZ?PWga zIMTmunJ=0}?{&1yN7c~#zAf`zH&Z_xEc0o9#|KvaN9@v29xLKqqlkA6v^|1@#Jffj z@46>41zm`D-Aue|a`ACgyfYvDiFd8^Ee&QD<{+7P*TYvisuxbj2jX25YG)!odlLOm z8S@r~CowO>1GdDwI$X=f`Ma+8LcHsM#<{TQG6-Xdca46Yi+T}c8;N%f*W{veC@_S0 z*IQb-IPGAMfn=|~p3KIID%N;JylZ2(EbOgm0&U`5+nuL-E0;Be8S$>uwrim8RUcu* zyPCf`j_zItXhyti?&oCW5%0Q+c-Q>fhcJ(L*R906&Z0b4Ux;^2A>P&d@IJ)W7QCz7 zkArx(LGZ45eh1*%Nbs%|E*{3$u7Y>{@jMAd^91j@bYBXJk_7Lnm3j=R>jm#>J}MPj z-39NO{_+HRss!))E>A=Ifr58EW5=;}px|BW=BH!u0>Qi1sGNzD9R%;{I4}!lF~(36 z@2WNIBqBAY*g?GOweW1*?k{-P;*mM9IU;!1_{zBmbZw2=#Je8(xeu>~2;Q~t&%OBQ zCjNt}(U~OA5W%~qw9Q4sP+ROF-u3CL9CW+W2F}F0zOc^4sh#%dNWAOobGevh-WIXM zyLwK|#p1;dxJ|E&CsBoNk z*H52wQ6s)Rf{Ay%Qk;tpKY*shyT0$7hbsd*z@2#4?eTf&6sp1@`etqWmJ5dq9nqV3 z*ITFa5a8JXeTjGNQ=Esw!OqxAylYs4JPf|s6=}q~TFuNOex)-y5bwHH>lB*T>xxgr zyWZE!!_IL%P)xk*srh-h*SrVT5bwIG{3&!#7QAbv3VBFq(+jtVcQyPo59h-K?|S}D zE5ig;I*WiIAd z9t;=aUH5d#!_Z5EFqwGQX*=?u-@HG5M40jEk8)7|^AOY}-gWNET-?1o7$=E$EvS@7 zcSR0?J@Kx+XkDyH6ufKo4mr4cM)0oXi*vC455c>hdX$agrGj@I+%y+nj)HgfQfK3c zvEW^k9dj@bf_F{J$wBqcf_J?#fyVua;9W}+PhwH1;9Wn@%Z65%;9bXBpM-y>vA99J ztM{6dFfA{5SMHmQ@;ZWdZI+S+ll*Z|5%21+lZ_{51@F2j_#|wnOu!uCU7h!3V#0aB zyN0jJ!m`GKcMWNh39T-Zae;W(Pt!B;xSrr$cdySv^YxQ4jd<77n=(*$ui#xLy~{++ zDuQ=C?Vbtam4bI&JuMvrZ3OT7QHJbviow3*Pl?AxDLqf_Du})4;8n;9U@6* z6VRF@c-L7a$I)_t;9UndNrll!!MpY!astPX3f}c+qvPn)Y9SJdcYVG(6>kp<-u2nR z<0y#`yz7-kN8v$dD?StNI%DNAM3QZnc-Pn+Dd@9cG17>4oqj$Atu`(}67jC%w2q-1 z1n*jMDj7NrmcWB}*G5K1QS_(aT@AaY;CP}J8WZpOu67b?*$dwFOub~-{~>r+SH~lG zen9Z98KaKC=DZiW5%0QqMH0GP6TGXo>tW>q-6 zb)Z<*hna$RJsNrlYqtvC)qrAUgXo`H;$62~K7h66f_FWA^B@Y>2;Oz;hXZ(;y#f`9 zchxuFhe6{6@9J%`4?9Bz?;7)AKiO@;yYA|j3w4vWcuKr$qf@zv&2c~z;$3?g<{@XP z3fqWxeeIS9Zsv^p#JjFsoQDU2UFl9JbH1MNmuuZ{h1(A@9I4z4^96R zyz4&aJZRhXMStR5gU#}A&ff(Kh~yOt&#MYRIKyN-OH zj3QgXyXHA1!F7n>U8^oVjCQp5{gYzG?2aCU&Qrm=P91%K^3e$1_07fu*wtO|uBv7G z;bb6q*PtK!iQ5yr>#?JI(RY^MT_ZyFp%?KL67OoWcON1`1n;{2#9ma16};=wv^;n* z7d$53HBEg0FFtr7jd<4pI>#JbOYp8E<{dzIO~JeR8PK@*6};<>=zY+46};=>D*F** zEO^&WE8JQ58V%MK8E^?N{H}rV9s}N)@Pa`MLDLNW<^Ega{4sP_fCl4F8}J{QV;M$J z4oAun+^zh0cFC5b+gt-48Ze%vl}kr^X9GTM*?87&W(Jx))8{9g$FZEWOoVOK=a;gxRMg|lE=2$(zfG02Upu2Y%`c5?9Tk}S<1U17^%9}j*`WW_nJwuyC2K@Eh z(afhZ14}UAy~D?_h(?*{H&vf^^Ymb?lQZyslRoeIZVYp5mjR2x`nguTYHBhl$dzN^n)4jju4cgV!UIDMYEcPxAVEd$k# z>GKZu%Bw#Fi*Ek)9l?=GWMGy9*m~vTO)92ef$FaOh z8R+y*pGSp^V`HYLV`&3}-|E}09s`)&yIfoyr^h3!^=ILcIj|n6$CY=67X}SuQ-5Sp zu2wxB)^RX1d6A8iv3mS!WjD6_QWmBe>GKy^1DIbzHhdlRxM%(l*8kB-G>_Kf7Y>eK zyRT(o!7V+`CXZsZ*JdK=qaIg2H`t;xYiMu=HRE;pB)it^@vO7hR9}~`m~O$IcFTv} zV;yes#e`K2&!_v*bofBJ+kE+6dKgh62A2}`c2u-m^=Xc%jQX_UVrFDiFu;D$6Kkx zukJtp9o?e(w}jW|d`zTVNItf$(Pz$C45axGW9SU41!piOK$k~N?ul2IPvPckU0zT? zv4Mm0P{l!yn-A=Yl|xUVYQ8Ry?%D?rV{=izsUG*qa=_2{GjMg&(#M>?ZC76SXGxhJm?F%;2dO7n}@FV!sGlr9BQP;&kyX5FZ2(*@`Wy6*ts)$E<6oi zrpsHkb;iD1rzviqa;Ij|f57O|$eEzavzIudSNJLXxmuU&Pw9ut4!L;cN_hv`_eH_@ zT#T~Nk zTZ?kg*IJLK>h=S-%R%8Angfmdp>s?QHri35*WVbUB5edw zhv9MAdcRTA4JL(RjR$uhjF_^upEYX~!phci!O;<9tHc`jEF6NfWo!TW=>gDA6gENG z{_otiK2UK_`>%99b!IG_Dre#QMtwS4Iv(@tXX0X(KEE3?9u*p8V8C~MK4s5%*mX+B zL0hu<$>ZSknBnmn1Acvj2M!i%5S4Dg2hp?YuNB`u>AAXt89eEGCzb2`(4ZcD2Mr5G zqwz+DQS^c_FeJ7(C-Ydh8gf+&#|~0OZi*P4ESQF zF~|?izGMecaj-a(j{eln z=^7qLwaCEi5%k@;J_dvOWMDyWeQwj)1KkTVkVfC5g>K{UtV;&^(%pRr^Cl$qJAbWAJ*p+myJO;^GxWG4sFX*|If=r6MC-lZhYm~{i;8e zef~SXhw?6c2`5&wM{N%aIrnSa__j#hE^zAfHZVSG!Ik&w8&eL-w=@1%`P~UZUXpoG z{eQLdf65`Nyp#WTbSNC|%}#x8gGFf;e3-tPmELI!&m9)LUXhx0InWMP(=510J0Dhf z%@H5XEO<40A6CD)3ag4+^8QKQ%=>J6q%Ug8t5jFBhNGRZCAlRx4^gwPm!0t7dQ0AS zpPGGp&>qfTT5@MYHCrF$2+xl#`KEi`>{Tgo;KX|y)>5;T=N$0Cz=FSw^=6I8V=dRu zf)Bs4fxVBhM-e^u(JXIv@;vcT?iT!E=mwUxvMr8mwV?aty_uJ@BQ|DGjI_p^wS4XX zSK_Q1#jDx6d`GNmWWkkv@;iA7e&@ZE{ot3PX0KAZAtc+Jx4Elke+=yp_g!Y(F2#p^ zDi{HW4W>MDvYHiSkH8ocQ||Ry&5nH>fx1&nxm9;HJCfv#W4&AQlAGRa4Dk=AlT3MN zoHz5?47&fMCEr5jqb~s;rnltLQ@mNghR#@_G3Qx!-t5opu9!jG3k&dOeVw~uet5JG!X8f>=nw=QYAKgRDc*Z1eR&b^t{1N!xo0|3F z1EC?lO*BeZ^`mu(_Gy!ti358u+E1a z|1t`0+NS*7IW=?C8iN&QP53PC&E`$zH!#YCreDy&w~=%o!nJ)1*o<%h14B`#3Lr$ z*h$SS2f3nifeGI_NzG=&x?=5j6J9Ay%~DQ|#Mg>+uEE)xt@3rpiBJ=MjN0rqeiXX6 znDF$^-t6N3QP889AC^t|qhs9AeJSNOr8U)Zk{d>PoA5Io)a-GcQIxCKgnz52X4!co z(KNw?r+85g-#%_Q@Y;lbwNx|poRQd^YQn#JsG0j?cO+jm;p-jLbna{yrB40II zt)|@SbatcNH8mTQJPM5T)cI4*4qJ~x{aU7ce*+(OgL01=8k=&M_^^^zZg^uwbNKuQ z*0Y{F8c(G@zfJk0TZ~5kh=0w&D&=DxM{P>|oFU;$qMs#vb)@KL33o01|29U-@%^3L zugcsXe^<8)h2D7P>H*7G6W%pSjlPq|AR&X|EhqWl;c9opd^X`zPWhmuog1cipq#v^ zK5!}&_F>g@HS}_YeHiymjnAKiec&C`a2`r$Coh_C(`jm?#k<0c`u`7VzlUZdx>h#j zI(BsKR&NyE(0sdS>kYRFqtK7$$v4XXTkJLlhI>qSnyWXgEytktArsy~rKWS4BXNSp z_jD^YLcB-9KE;Io(bTYA=7!LxCj8P@Zx~v-VN0+HSG887YDXG(T07@&)4A$}Zm7M^ zgrB6d&RrY0VS=qGUz+KS0f%YsEuuN|%o{KBN1-8|19ENXgNfm8C}(KOFFjGieFJeO z6-;@XY`UAFf;&pznecPl)ObC^9W_f#xNa9UcF;U&MDJ_X-W%p&?wA-t`FRyNe1Fwf z%KmIttVXrr!Va%WRm0|(u+Qb&`@qdme7}@ATzVYyMozx?mi?@y#>g?^Th=^64O|i5 zvR~zbDY)y6ZTE!THtMa$n`B|nbB_Ljim>gbk>2>)PT1{Qt-bN2r?Blkn$vmo zFk$l#hEVS2PU5?eZ0`++T=BgKnnCB1y~THA^B!;H`HF8%5WUORLf|8PYiiM04EGgw zxO=!as#*&Bd}*&YN)8LVJuA=~?=-@m`)jFDxv#ME9_!VhaCq7N|J{C8j!~Y257JW| zaj%sHpYTPE5=#e+aI@fUE^4|n+#YtJ7JOE3Z^S-pgKo@%|BfG}^t*nQ<9ijI5f9s9 zkC`p$SwWP$d3jqj+h)NhP4vdSRC{bBzpld(Z=4y@4%d5I@Ws!)u~^#y{cSBctFJ~S zEl1p`VZlGNP@_elBYu8r$@34X5n0q8HNUpxGmp}_`6vhcai=B!kVS2lbA;X)%w&S1Z-p;pQ->C-Ax8tQ%BH5U) zZ&l|a?0ENMk*vS%XH`&dJHFZ|is{CES4DiX<=^^8v84s&5ExBln?n?PyQLy7_O|60 z??y5kw<_rN$%f~3k7U~_Rzu4K8?L(|f{pH511HDZ@J46D+4j7e=+MrFuP-0YV)S${ zUWfA9Xoax>bk^)%vNb<$9mY(y*TD2I)_nKoFlKnWCI&RL;eFi0SZu}W$UAAxk39@y z+H0yKps5XS{3eXKkE@AlmNvXcMg%+a=Ci7(svY-u9l^4OepR^?+wz`y5$yZ0kE(40 z?D+dbVeH7FYOtc%&O=3EtiEkE^t*4(@3aYLO`cVQd21W~z%-maS68Jw{jGVDnsjbc z4HtUb@c#Y6*=(Dt_*RMZp?i$Wu^PDLY{R3LhO^I^+DNTq!-qViyJve=g)5z#i=>$I z%hPI*A85lpE`+nLygDX~vEiv->CW2`)v;~54L|=VoE5C8f*)OMc+Q{*_NcT9?W5c9 z0_zC&>}oaKT57|e){bC-*D9mL&4yQtqWkLeE91`-bS|%51dAD189KA6&wV3Ut^BHZ z6=lOux<#-#@s;p>gAF&lL-M04!Re_DFUgHy6>C;S{$U$_+8~lWE~tPPJ(ru$=20mES~ooun*1QvHh)|GF+P$#^ZKdUbIz78CjIZ%{-LTu^R3Bx(mCRrD(8zW zpE5L(c~1?Sr^K6beql-4fQvGua7k!buf^XkE{=iHrnm=IPztoSX;xBg>(BMf+A$)iX5v5P|*W2}W0zj?`zb?wyzYx`O8Zp}hjmzKJiO6Q*1 zee!4ZJR9QRZYw@)ZYX=NsR=cePo+G+F{U-~{g^est_fzx)%s8eS@Xtp$9wa2I%wi) z%^h`v+3XwxteZ)9Q`8A&2YTzGxv4cj=Mu~w_1A;b9BV#tQV^>YsE01)togy*K*mPY z#r$U0JobGcn|H?m*~WDC$~2HYI8YCZK3Q?=g8{5xU|kHoY{duZ2ePgXwXrtEiu=!@ zvr7?maDeU#j(pOlR?iWe>oU=Mxj zAv@oS&J_DI-`DjiUc!pU^z~<7JsKi*$-m}g|D8Tpj#1Ape(YQA<}lH<;ud@}OS{w@ z_r6$iWiB}hUyEvti*cg-T51z$y|R?$`*&)Fc{Q#0$%Ve`=DS9y;cdz72rup47^jjf z`K#5wEHJAv)VD18z9?Vzb6gW_|6$3SjPPY!9h;$%z7-Fc;l~nfnxb_ZtAELJ_jh$r z>Tj2|85J*!cWF)7Xsgg)#%V%-2}gDo`YZG6wWa%$Di<|Gzfep5J9U-MYSY6HBkMMY zG4rvjP^s*VPY*jyyA!8-eN60U+;^DCmX|?`pSB#FY

4WMC9jd_iz){j z!FZV^SH8>d=%CbjN)p9LB@w74Q7jA5-U-t$pKA?6eRzVf}Nu z5A2#)Q*$%@FmR+;Q&n08qTL~}PUA}b;o~XRAUhKX{gGl_tC9k+Gf1r8t@8s=IZCWq zkGg?~a1?8~XYF8|$`y7a>2n}X-4%A=Nk%aAHVQklU|JAH2MN33-yoQLRAF203=D?z zKw(>~?geAndSQ#EEC|IAE^OB_iVxH>7q)Bv0DtryC)VtwhZLv!My%y~D+17NlUU=e zhXg|1R;>LUyMnMSMA(F;S-}{fr6=18t%V`@dREww$CjZeA0uqb-yI9(IBErUlvKk}UmHGWevvX^$2bueIgx7DuAhj<2d5Z9876Faq7Fyq2Ra-)|F%Mjy(- zjr^9p=tvy2`=RopoR9vOBH+=z92OeUw|-wF3|IYBg^&-Blplf4)yqS>iY@2$BQY_e z0$Lc`^4douQEiSE#WvgWGb|E5h2@|_{(~pIuU&8jI@@5w(?3R_+l7j7|4Mh%q($P= zhVsZ+LjJ~f%I(;qB6=|L(~d+UZAt~49&O7P_(mXta$s%SOLO2{1m;|?gyGle9-DCy zsJNvPUaD<43ywhex5}uJV#CWtke-Zkf7sjdrrjej*@*IkEU@8K*GJ;{gi5GkXv>q0 zBk=7|Wn7}WlJa^)Al+CSjr?u+aJqx5?T1P@NIv28_K~>Lt_mE;C+vMS9G00?Fxtt6 zYkdsIAfu}2Kg)(6rFUOnNVzS@w;Xvm9M9;!eV>+e=GvEXv2E3cbt4;oA)az+y{`(J z!Q@N7jX=jm+9;oG!vi`}UNHBnIQ-L^m!mlUYB#H)FOBu?T@gqOtqRRf8@`cp2v$5( z6`fyO^O1`p(4uKI^a!-!t@=?rA=S`ntqtE+O#0A2MLPX=B<&5ykh(SSV2BOhnI4AV zv(-_ZeDwug_A)&$T@0iBuex;a)}k_8hw#_CI=J(#Ha8%=y1Nc0_iw=U30K-z3omyx z;d+EO>DI!cH-=o7u+E~I_}PVc8^WPCYd}r^u*x&|$~&z7|9l=_*(d+K-%Q+Z_D{^c znCIKeA7Pzc^yN95z_9hN8e%2s|ITUt~ zagAX)%s;xDj1#H+&Xm3~PMwj>PS+VMV>@c+#U@t_A)TvH`)~G+k+I{;bhdEhL>V7C z!dOGEX)Ylsmum4|4;lxtrUv4DTh5`o9VUr>c+n=13u8r6Z4?~^~2aVVxD9dCb9M!ecT`$c)2u*wQQ-631kDmE=*&(KN`yA zk18dzh7o#rPWEt0TpF`m-%ytMGCY%w&o+}~J~mBe)hg*xo=8JpcsY#?sn$@I-xiU{ zp3OFs<>L#pSxF+@J3-H?;+V|7dg|gE*;40<8n!U7fn3-5S|*#<&`hqos%Z}Uw$?$e z+kJBmi}}z?u3LXlGAq5OgY{&4_qNfnh`J5rc8cp~u`ju%ayzcma+uy|2e}=`YdOrL zd~dm(H`7kC*fS&LcIr;hu+(k!<#xPBX0bK%Oyzc3r{pkG2M4*GRwlWuiB501orJ?D z*`6xInN$B{?d7cA;Hh#uEw^Mb?IxyjJJo;YFqNKz+)h)^Tz0cjZ@C@!Pbb--?rw5B zfyJEdOPeaUGpXPhyZF^pZbvU8mu)fcE!WlWn9YvTzKqnLV;iTlPR7&Zx~3nGu^sE? z%XRN;rF)WhERpNl3`=K4o2SY0B@K_W+0_@w@?nVw*${`Nviy@5ajZv~eBYx7+3pKV zWtlej<5*;wOrO+f7XD4>v+8mjdsZgn8xqZ?tQXJCy%WxQ4H55tZgw zXvBNDHw$LX&We6+IV+qkZ6WkexE91Ls)|0${T{%aKZ!9N)t2%E`3e2s1_iOUJw;z# zIvl{tR}^E{{AeKa+AHQyhrU6q;|9?`cP9j}TwO6nJ*Ee;(Dh=@_}hiD^c*oiU(^j? zK25|}%xo6O4vZ0V%` z@M41;{ACa6dx5{~;bkiS%N{l*`M>PpJ!(g?htl_=dO;>6dnn;Bdah&-B|Mk(k?f&_ zACaDe$R0{~GwCncLkSO{_mb?Pgd0~pf+}PWrSHXE>IcalN_YeH&kg#XN-_`Vt^mnb zl*%6xu1_{cvR#h|r;)EXp6tM5!tUfNJ|o*$Lih*yik`G)pAgQNmeU!XWvIlFjK& z9D?L4O1Q(6Es%Ug3IFU6jWy&eN;sz9PDs9@gxmPULh=)X1~ma zn{11L1=(k5jepnQg1>yB+UsH<`9jiq4=RpAYx0F8nV)u)v%Aa}sxUnU)yXE$BRgP{ z5{04U3rX_sZ$j{#d?87G$k9MNDf5Ni4vfJ!@`b*Ttw>uRg+=5GNp(*g4uL26LQ>tO z(*yCHd?BfB%J%^5D)WWzJH$Zph1QU5=|3zAk>m?W?bMwcfQak4-1fVJTLQ*?} zuLWT*`9e}Vj(5WGmoIejWiYCdFC?||a$^8GkS`>)bF*#$Zj&!0wG$l_gu~$0$xpf$2gw(b&~)gMFC^(-<y5wFJGwBPdal)zK~ScwLuofk}o9H^(sn(oTTeu#{1eCo4Goes*lQNzZpo_(&2uYYaEip{RcSY5vb z+Zp;;#+^o)vo)Vy$vE}01xvj9R>rmKmSg(U?KRSKx8JGFI+x)`CXJbgPiUG{p8v&@ zec33m!CEhV1)s&5&VIn{4Q%MVU z{!MKeFI!~Hx`lq0<%d4)tSPasFY9nq)g|rRjJC2&^_@#J@mB5R^2$4AXtL~to(=0y z)YKZ>MlK(BbCl+MiH(etvxjIxu3O01u9b_%r+o_vm!LEm=k309e1F_o8P7dpf8z7q>oTsBk#s`!>Y%EiJ+-h>0_x&rVdPIxorgpEXioGDl{blF+s;x$5vdr1NEmXsg3jIS9TC2Xri}&*N z=%PASSG?~M`~E7&cLHB{waIDxtrB@|yI!cOdK)Lk_f_*!r^tzKoFx6jPF-*sQuGr_2^uh^zPALZ>!E03!K*A4^?SzA#IFxTKkJr#iu9$wHrHschH#m(klCgOYcg)++ zP{s#4j>ew7`Z9La9|K;cvW(mJ8w1wurTnZ}KSrZe|Duf5`{@pMC2x^hB#NB`0dY`6JGr;UUM#VumJiiDn)kNw!rGMqGSCp#4qEVpAZ zIF{XT7j@^fj%AZKHImDg)=rS|nx!$!J$#*vPf$DEBckQ`=09>5 zt1z+WF-ZrXGrL&rT7{_+*0PCZO&hJ2bz=x+1*Dr)?iQBF)Qw~1x(&}T=342CT)r?i zj-9x2QI=0U702TJ-DT{n9nbu;v*k9uqT|`2$4eZgcET1Vu&#q$=`y}DAfBE1*+s^WFUGMm{p-s(JuHR!n27$_?UBvSm*JF*!))|5p+nNMbL@CU zp`5A)ofdd{@=46K6*g*b^%ICL!;?E5 zLEADJvj@@0%MQmnUUB^YLmlY|NqF#p6R6c7C%BE3D6_N&Qp5@*1?OFXnJU z{!*N<6a8?h^EkXK!|NJs!t%kL;g})Q;H>V}VfUSS4 zny^B|0S;{aT6Jijz=P|)Rpsmw_@(I^)x14+JYGA39Z!9)`q0Xb8?T9A{>R^`)>B;x zquN_lB*hR~y9Tj^bDyYs)1K+C@@Nlq4?>IiLPpw;ZfY-{yUHp8b<}TFuGFS-5BhiZ ztR)%NQs^n+<_(1Yoi{{a|AO}_Hr=_cWuW&7q5zF5}2glAfa=NcR;#;3<`Rr~Gj_^rmp zsMPPB>hcmh-pZpG;TdmKxrEh^AK>NFx2l8m+{vRJu!Db!z4&EairANl-S9l$oIkIT z#VQQ-#==3(d87A<47GQ|b65jDuwnpnS)jqTYX-dZ^aN&g%LbNzpv_g9`h|0nLW`FGuOqP)A~@7|B0yca@wm%_j6{)B(mnKJ22{a@$z|0ieX zf9K5j|Ku#Q^33f2w_Ub`F21(xLd?>m!TVj(YD@ zt0&s=YlO!feWO~w)Q)HJYDu|vXxwZBtoC< z9X?CO8kah3iAAW4W0%!u#rqG+c%4pTw*6qPj2FCX#t!bgCgVW;7OY|O5*fc8Va}ea zU&~m#(1HcednaS1KFa-wzO_~}{nnde_XOBR+zwqZFBi8IIm-|rJ{_S*Ac4$}&S+`m5T2Q{!+A==5!I-V+`$?8pwxis? zsMo=ewS4m2K^hlj`$`$*-p6O%C2YqUA+M~flu_=RJgzdIO>P{PCbh4utCUghxjbys znB_MV^2)kO8RdRWbZKq2IN4q!wXdwJlu_>WIQ`IKy~^a3b(J#8wWFN3%DVqI_g0kq zLGxplXs$16C%^C283#0m6)wqryV7f~=4$$T8NXkWpy~LdiY!y3W2|Py;W{$zcW=Aq z?y_bw-mbevlTgP@#&ZSQJs=17n z?JM`xEKYPuD|gvWUKh&eDrJ=WJ5AN?+dHgiE4QhvtCUgh4fT4E)=tdCN+ZKX-=PwZPKmwP>$)P8q|I2m_Jx#9Tc zMVgFVd^N{2bn<0f>eA-KgW)%19CYExiTiUO$#~9ZgS4YZUW)Si1JiuMgnd@(@OSqC zmHUZqRZG(prm<J_6wyx*io zUs?A*wfCpoe{4^Ck!-nGJHz*%cA9+efZT7B?%r|wdcRc0b8Ox_=|okN*Vkb83aVk} z>dJUt!m7+&)^$GKWH2t3Ev!cHrgEE~ zc&<_(K)sxH1^(cq=4Qt5QsA72(tk#k-?^PbEZY6U6 zl+yX9Jj1gxR_gzs+G{SX@J`ii`4icfQ0}Gvs^63{|MY&Va-a82(s9-7_QH-Sbq;v@ zQnh4SeZboQk*KlX3Frc&FYgFUh!7-AJc-Nm(*(yx8CAWWyse zPFU;Xv}Qq!jGM%)bF$vQQO4Rw*E;RBc9n5uvkgvD-kZr-shiTKDeZ|;=l|6HxN?tv zK&R0-Q)WXXecYD`TjXFe7~#8wPgQ=;Ff7rtk=OhC*{(=`E_|59XWTF=$Ve_fILsXn z_BE98#sQXIRvO6l3 zpDNhJ3Y{*bO8CA*EURa=N|vuUWhZ-5EkyK>BK|?y<`7jZt8uE4EVKOkE>>AzC1ah5 zyV&4{6J>0?I)-I^StnzqZhtp+LK%ahjLm5D)Q??hD!y?_os}}mxDGaL5nEX%udJ(- zQO1Xy>J`CKKNQJ*qO7Yd_q)1*>1jSX9i%=~)>X!qD6ulGBdJp;>p*p-{#Ul6lu^zB zQrB*`nErIb;|u4Gm{&y33Cm35Ue%D9($=MOUz=K@(z zWnHC=GG=Dx!faM?jCFZ13Mj40W(f$bBVuif2u2M!B!xLNa1THTX-xpndfGu|sGwX5)p0^zSyx#;?fF^svJw5DjAc@`qbyhUt+Ef5 z?fko9ij=WWsT2q0*IW2(L;D4Re@v9eu{72nww*7?IKzQ*tL?obW7|JAWAc`#GEUUn z1c%kaU#fM_2ijfV%jL@U|B2YDl4+}<$`^Vn_2=EZF+N@V|EAU4fXC0oKlu7X>kxYM zp{!f8C2R4#(G?kQp1KB4x@XHc^v-Iuopwyd$~Z1%3{`Fmy05tGyR6hfDWi)!EbRi=-! zu2M!BZ#MpM5?+_BBV}EsjB-vY=Z~_kGEPZ(Uz~*h-{Qoi^1ouql=}$3+AmPXt^Fz{ z?PE?DI~Dp$jw{<=BaDSRy^yg(NeI)5eJ10V@xg3Sxu-H##-Z6!Oxnrf`zmQ%B<$?^ zP&I9v9dAvz?YzgT!np#^xmTj#kjss8!r8IR7pfVg zLkr(9*2t_>mZ?8Gl(~I=Cd)jz9mYDXcqYq?_!Po!>51}5QK8H?<*6)RAVeQyV|j$aF=KSU7ryqRv+_2li%!;Pp!}UNs(uqGRP!c^o%TKEz(f z#oQR_8ioe_#C(gW6Nb74&*W!axfP0n+hT5X3k<{UmSXNz9TSGCHJ{33z3ELDGRD1< z+thv#MmbN#JiKWaj-#Vq%I!Q32#5czQdwRZ=k}}ENU8jo!D*x-AqFp^7 zVS1em&8WTPCr^Eh=Y|=YsM&V>@SDfz-6=!ka*JY{OP*q{6_;&k@QWuX?bKCXkILu% zD$cWy_cJ(8=`P2Ac2YmbvLTu@DHim_t7lkJAw4Z&IqeC)e~QQ^-Bc1*wv+VcGDZz> z!3Hxku2nS)F9Ll~w|O(ZaBU)1JH=yKyZYR}dLS-VXBgVdfZvRqj0O!ZAoXA^Uc0m< z?oPdp$`seP(e#q4-|!L~u2PjR(;1=~dgeJA{HVg8$INQCv-=Ae#8u(HiZ506|34jP zsEi{WA2h_? z`ojkWYnt(}T`Ab<90`+Gjrid{iD>^R4y#h@^XeDh9yjZZ>#A$0_ofCv`@K1e&)h+?snz-B^ICXZ?jcNV zs&RusIjV~VC2;Fgm1lPeRCzf(!`?J)zO7$()&7*{7&%Uxhs;QIx__b+^;&52Nl)*> z<3TONRk zKJo$DfBmlFG$+5cEy5#BPZSL`=N3bYq22wn%ImQ$pYBkEP4<1zAkU09e)fQJihfXS z8f?ckqc1~mZC^~kPj|B`;&qk%teg+Z@A5w#Kdg)sP{sq4M0;!OZahP&y*9VLUWtwO zEymiXRr$3!-PnXbu3~3G4Zf}7YL-9w6f&0T(jE9)*fOJJjB8Ve7q3WSGx}{szmpC5 zx6gU30_7g9>0rncTVG*&3VOiytQmiM{5G2$XNYsnC|6_A=`WP9Du;?Wx&ekxPVqI0q^z)qis)eU1QVaM?(q&EM5*n97wE}mxL zmt+<(BPzk1FpJ9Wm~&2;6$1#E69&v;K$NJ6ib@V9vViRN0_Kc4XAwmZb5`_D*x~N; zzL#52&pA(>Q}z4rQ&auz>FMd7>Dk@yZkLXsP~qcY6gk9LS)CmXJ3a-W%XMojPXr0t zwedxI+f5aZwx^(dn+?eHo`o{{P9`)Do{k*KHd5N>-GWV@`k;~aO%;QC_uzzgd(?ef zbEVPRr{MO@5ViW)N*Q|fDSW|ZD_a9~du2nU30pHO=D&n3z1cdMZ}$=`8>hTQOng|+xrcCtT)3c{c`n4}Ri!!n2R_;8?#LgBQ7f~km&%*x!C;G{_ z<}6)8c~9xc!uF%DLki_D8U_~X$?^#()NkswtFYhfx;qQ)5r*#oZfEU|+Y9ZleaE+O zT%?_km&kKJ5Ix*KL_hZ%>6iPH*u(uy?BxC@_Valm<2snXfR3x}#z@G=-&G{z-Tx#M z7TGbM99kFzz5CCm?eU}bfsK(PD|DvJ;xE>%`hO_(RU7Hk9|R-3^8o%_&#@8vsvMH>5oN z-F_%I$71HV5CW|l)}`$q&V_^RArs1BYY)KPxwR-e_BsM-%NWo39t-ErGMS+p5}}t3 z`|Z>7$uOb31(ko7mX0l(tVjod%8Os6MHpKy=kfw7nsI_tAn%(<$#XI|fhNGv9VHNP?}C zna_jv#zXzNY%T%{qG9@AHb>0z!BaAjhf5F2ao5t( zwSfXL0P+pYOiAywdZQDd;B}s5VYsz|Bmyo_DrNbTNQPNimH~3 z?%?wm@lPD)wsFiq+GoTeTGW=e3bUt zr~e7h6=pL{k+``pq0gy)O2&+z;wpPA7<52L-Ouf1Qdy^sH&e2zlr~5h`Y??GNJ3(P35o)1jG2 z|02_4Kf@md-D3K0c_gBLCJ(&Hq=H{b^0vp$` z8hPlt#Kybh-ZRv*3iE^I-)m^=7v`TT_*?6ZEScXNmItGjsy{1F35HLlW5IWYj`FKs zFbq5u0|Tsd6z9`HFnmf3JS(lEJRKVZ(yM5&$o~t*MeEk1K9ARIU=l6`T~S4TTHqB-~^a8 zGl24taXVqGPcr4TWt?FA_?p4kMvp0{ybhKfX5~<>@^X~b(kFS8OMeR%{nhro zU1lgrm3OS*M}vbF0)v_x655X>s**UkM2A`+kP=Shje&_>VIMO zXXESiwkO!Qx-NZhTxe5DM;h%=Rm8Fdjd$}OQX>1PsP&y4^o)4x?B^lZ78%7iRRghft! zsf=#=PIzvZLS>{H{*bjSh06RG>JN{V6e?3W$_adPFH@P!mNVh%v`i|Kv3VwJiOZxi zo&T7DN!nv7Gh~7}7h-_W{HI=!W6e73ueNAQDKZVG>a$i#! z%j8j32iL!$GK%LYtDy4vRHnk>QC8(<K=bBEaxLDQm)xaDr zQ|&1~%^WRJ?YXhv9PLx>`5NtnYUiJmzjJ=40E3o-0H~%3rTgc`;_U%LDa8sT4o{!M`8f@PC-*|-*mazD78=r%EJZJIK zC?N;sHe>NqX3iV*dlZYqcc0&&51A|uhY!m~rWT`V9GNKX#!Ei9Yn+7Rl2Mxcy`AL51>xtA zj`j4oIfC-MuG?XAtud5+@cknP{9R-6+w;G7!XCwrvTmE*Q0{~i<$zmz;KG^Nl&>z| z4>3;`P_E_@46|=9rcC^BBFdR^6!uS@KT9a<;O`d<`nr_zzMhAmiL#9H_1)1BJ%sW1 zqcMdtO`pZV<-hE=Z}buib($C+1?4X5>rurNSd+zUFu9cq`&!JUI!BKM7KGf||mHsw1AR6kb zv5NEkpZAUb|GaNp`z;3ItLAvWyTJClf9?a~`&0j$?gMJ}yTX{)&Z+i&{@QO${PPWt z|N9#pbM{3ef4qi}T$uMF4)wwN9pOB^MC66{JHon^@x4pD-w}RLF$G=6`yFAcJE`b1 z-tP!k91mzA-tPz--dE5Iyx$SdbId?p@P0?QZPszr3-5P?W4@k1eer%r_|n3YC>HN` zgqQ6-tP!c#@{iikM}#mP2NYM19-n9ta~$}Q07`x7&?ddJJN2rIiyhMvz5W< z7~bzlyXmU^$OZ3rgr6q{pxt=CBOK9oHyVWZJHl^b{E-vh?+BNx?}rxS{f_X0$nD4q z?{|b3cHLg+ha=m4(G$Gik#A} zr1hg*|8)`?8{3QW=%^%gGO8Qp?-i3!(ixHR(dr?{=QNYoTNr}u_YS1(pA15g;~+Nn zXO}|J!BecS=O@FE?>FX$r&-~s_w7+sUUx?XvP)q;=|2d^gA22HaD^zOS9=VVNn3mX zRm^4_`syIMhM36w-tgSK5@`ki*hqAqV(ztzP! zRO>zSN#}m?XlV9u+E@+LN-@e44oV6?$;=9D47HKS2kF1VH15DMpt#Jf(8_9BHY{((B@@HH6 z+ZHVjqDHk?d!8JHHXLFcJ}DCYjAp;x9TtI(&tdv~K7}KrL9E{wL&8yqek>OF%_>?C)T-JEtdQ(~rSu%@*dLNk4=JB9qtvq2aPng?4q-tyAibCkFR6VyK}=R zU;7e^mRJs@?A9<2=>!a>oa!8hx|t55Tn+D`-Hs2SJbr#Ws^in2^17-CD0X{4%9qY1 zpfOkbQs%is`sKMpnCA{*o;!s19!@~sMm^|n+q{iOF|)c;-q<4^J$LIydGDb(lrgs} z<(nt<@X#Muil$)-MMgCtpQs#L_`sH~?nCBf~ zo_BEB8NwW^}Ql+{WiHs``zw&xJ#1#(buKcfmpQB$Tn(`XJKvVZ3a{ z0W`i7<0g?&X!&0D+k0Ol(aQ{`pXV&;m**^Dp0k8`&Js>>3rBZvbfWf@2@1#Gwzj6+ zbVoS4U7q=5k$pHCv>(y-?)aVAhP9awUxtUFic6VqgH6Ivn<(aUm!+X-e>j_qmKh=F zt3yxvTb^H}-{Rz#?V}I`O<0_q55PJvF?Q}3hGxaGSh9T_hCI#>r1~393`aMsve;`X zg`@cOLuh;C_i(hj0*lov)g#b_@Zq%mnqdS=?!j_In+u#t{uU=Mc#df03G+N6tc_>R zq`f$?&Es4vPnhQdVQoxuChf(EPadmUdBQxN32WnuGifhQjPZEW$`j@>Nmwg$(<>YW zcI}M%9j~G2?g>XtM+j(%dkw{LUO4J8452Lh8cO^6;iz#|7c^{K4duniFtog7cjPdy zhGHayqERnE5LENz+qD&@%T9)Siu5htcG4D{9Y}4~J0j_>R<`adi)& zok1O`J(koON$m-la|k8x8cFSGas4m~x;K*Av(hvg?avxT?a}64NozU2 zFB5y38ik_E!~0Wve*OqW3;PeC_IMo+L;ZXQviTYqjygVJ{@L*~94(wZl-g6NS_B%< zY6P{1@7+XaNo&`&`vd7UTk4++fpFNH)jTss1VQsKL~EXgEra3UXI3vw9~%M}gIP^w zbQb@Q;5e(n{wxTGuXETLq-+03SenGnGHbgYfT0K2nT1^QKQe^zih)N8+okR?h4R0Q z;|lfU9*-~7zpHIxVZS#g9xb%TuTxT?olVn{3hiH!msB_|(jF4kpN@sd*Y_Jtndk}Y z$?9aHf4x7erAfc{m$2HK*fZt=JA)8AZ>?u%6JmdX7dx|%aRt9-OvcOGi66K;@ekKS z{KoYYfAW5bpSeB6|J=@NcwV^uOKXI{kW6+?nfejW%L`VEmMHupD#^KfY&G4SW?O+!rR{L43gD15r$l6 zBWo%L3Aje}XaBWe6JHH-zleKwSjDAAzgjHWzj+!1g($KvOD_956{ zHI}wdoqrG}wPaj2YK}hQMEYcGlxDKx!M#B=>ndkaivqgn2w@ zSu0PN%M<1{5P8m|o!dj&xjlq=JZo7iPngRS<~9@g;@I3qKLYYgvAQuAzq@ApYR38a z9WvwM827c0f;0OVe`|RF=JaCRC?CgpB&%b4?mGy_F0wjS?05+J9%FUv&g4U|&AC0T z(|G(7+j#sF=J8LM$3J1%6b%QHnVt(rqv1<`*4OY-F|gn?v*D|A3{*HbSZ&{J0T z-m#2_2>cBcqW{kFc)0PI)xA9LNITCv!aVN?^SmQ`ep4(=Y0K(iql_4kQrTIr!l!8X zyqR%g!)VwXz*ukM5qR>6@y)%5!O4gHHu=pV@SDxfn`t8tLFu(N)Hb{82jTdM(Uf`4 zl74y466QHenCC3vF8Warx{m2-bu$vizGZzK+z<&57cv|4t4BiDnyj{8u_Xfhve}um zZgx1NE-reU~A0g`pd#FnCQvQN2ff);L9g=hMK)O3@VRhXRG>?!XWAdi?RBZ z!@#8{i%D%Ra3=X%oV?&UqLnAi^N6rEo;j2D;>0$ObFDmKo(qJvG0B;<7biY>tZL;6 z^LQq#jVsQiy*M$(<4r41n8zextxUnUNEl?y>R!78k#MQ*NLpuZXdVd_#t)};=DolO zcx5z<*1Z*6!oh6u5L#z0Y8(cqeFoDylgAs;U(&rv>l2TWvCz8mNLu&K9To#u_l=$j5b#o8GA?Gp_;7FN_A z|EJNgwst3K&rL1%)VKBBQ^AF#t8Uf=}10Bhx1LNR_ zg0ybzPAczjut4f>=||c3otJb<-cI?_h7hT76<^9OtzxAa*4~r{Y)X-C_w=M}+fS0x z&^F3_rld#@I=WNdlNBT7c6XyZwq}UbV%8?g_ojPEZ!$JeZk;qwG9KwldC@d$=|M&%PHi@H9p!+@Yf_i_uBGgFVP{7xYsNROY_RU^&$wcwj&NrrlmE0@6b`p$dR|8? z5V9sP{bF}-!SN#Ncj?U#q0~}lPlL6w!kHn=&X2cJgweg3{bhGc!rXyuT<>C2gki(k zczbn-6?*h#e$a6Y5p+zMe>Nm~3Ej>xzqyW?FI2Z;{yd{62;*#-pT!z~to5v!{~J#? zmkR8dJr8u>q<%Qc>^w1hN9rAsap>`f#}58tW3f8Cr}OVGjISGSu>RDX$($aYWIbpa z6cVX`jMA3M06;C7Dj5U)cDc}ht`C(deQu&~dk6EI+n51DQe)<~DU+>)W=9yi=vxS_8tkC*uD$cEt*!oL%UAHmb6YO`awJ+lqx7Me2p2XO!+R@afjTq~Ec#&%TnCZD(ro5E7 ziSfk4ZKd!u*6)uuHqyv*%(hu?7fG)VFq?b3Y?4+vva$SV<0XBo;6-gqcJq}o)LaNS zu|tYj!u&Awk)LE0$>PW5&kjka4fE9r7jMZggZVamwwv^OD)adz!{t(z$!4lEvGGJ{ z^d~k)?UVXTOQtfe039UV2W%dB3^c3r3pkV9=kY+=c{~v2@t|d`JYgD=-OyrAWb4q4e!Rg8dAo5!$R1kjc+erC{bycCR{U*wW)~14i z`DV%=N?Qtj&oLfu)m8XD!Hu?8=rT&Ud!6x}^|ORomRo51^uz0g8Z#L4_$Phw_$SQc zpD>Sq!oz&rg+}5ws>id@8ew}PG)Qo(hUc({1fx)aVj(!TE0I_odh8E1ypw$4`DYw1ty>^hOPmw8b4Sl@WY_p1Ilme^m!gW1e?JC(k>=Jnsneyd!MavaED6h3V{=T3%|C>&xuiT}3i#z*yQ3n@E|`RDhJE>e3-#wmM8N~4Z4A8vR$Q#w9@@v#Z(rJD5_^PDC9@|-2ibCxjA zS;7(B+@;ck**scrTrKUnv6b33cE)UJZg)|bWGnz;j|@Z~Hf*Ch>?ddIQ2<@rVWElz%Q(Je3CyTfuJ;q!~szm_Z)4t`Ha z{fyTNq9;**ZED9wjMtggO6{w*Kg%C}>_7|F-tB$k&e^w^o+YM#IxnBbcxKN5)+evI zQa##S;7szjIC;TyL@Q62=MiCTJaZ=P#ffbm=UREfJQoOSW0EszFHU^&Sk=lC=J8Be z8&{l3dvRin$D3B3Fpo*XTAAlAo28X4w}Gp_u5!Y4u~ccpR*1LNRc0)lB8@xd4rYR` z;%Yid8vlI@Y-@>qYcoK4x5o`adg&@(77dmzS#5@a8~)$5o#-#=-lX-3QF2+Ss_S-Y zPvC+|((YBh)Sm6*YfDxhKGdFt-t3GJp7CD>2q>S~)4%!S2JiJiwn9skIsf_UoN%Viu_^*p3 zR#NqxY#J^OR^@Ya!^PujzX;2xsay}UpL+(?vkvP#x0Z1L<`h-tcH&R*sLFBoe~P74 z{WgAqR>#byLxXfZrDDHW>mxI#L(N1zrRInUBkZgyiiWs4zQQEoPPfGpwtg6MqT zdYHT~){XL=RwLwyUfU>N7&S~D80|$l_1OUVe3|W(KbPqtH|?{Na>SPo^6as@DSx`x zNZ#FMFXb{Xs>ul__ER3Z?~hbXH<)srKUbx>FG46cxfUdyb_k=~|KnJxo@+Se@{adX zH@AtPT+lkg>ep<>{4y}B&@RP}Ga_ftBq_IvAS75R>8&vl0e z@*>sFaRb`PWg0X4-?i*2PgciO|7BlUP{+Hn*I;>u>W3wjhtjwrz8Zkr^Ip19+b(7I zmFw==NO?WhqwBPu@{|7UWckD@$`f$EpBgQr?1b&Hs$F@h<8*wpD$=9?pE#h8QoQU7nfY^Hg!y?kGB-(^?IHHUT<&!?=W++$lKak}eL%IEu65}lhb zpsbtsPN;QYHf6(8X@dS|wx0al86@;*=S za~2F1Ry4AwobH_^oHLkBxf`~*&fcYz{qb1V-EgH$=KX$82N*K<8|cg_E%^OmY$9wF z3@vBU_E*Aj!A6=xIcM^B;e_Wx%4WZ+iI>+cqkOA>6S3utHIzTCw-UqjHc-CZsjHY> z)s3>!xQCd5*9y`XX%BGrE|h<`aR+6h=e5l)%0$1(*#OF<-@uIhl!-l~n+H=ScDj7P z_qJ90t;&W`CgZA#*Fe&Ko(2iR(Xqy_(GXU1!lm=Jo`R zx01P?>y5g~+W z$MwPOwRM{-j2{>}2qt^j94+uXAUJQHPi0)z-xG3N7gL_zPft9)XgTHbeX5Hw?b&=q zq59&zp{}&O!Q~cW?Gu|Qmpa-;44LRo+4@Qw(Mivfvc8$6SaH7(<-ZyAMc1l+lzaWC zE~XD;bGN&(zBsito4a)P2g2YZ`>4!$MRxp#>2oGo8Ozq1D^U+SZWyviJ)ysJ_vpQJ{j%H9Liv!55hB-9{?jgz>)(Mq zMBeW>a22^dtClYlxt&Y0=ZW0@L3(pUJ}%PE$4lh7ABZ0AAEKZ8jr7a?N$lZ%CU$cF z6Z`qRXy=Rb(I=XwZp{e*eHgtbq!rcFa`MeP3^F^4?BVj(jg!#M^=J7z7#|dE`KZJQ)5hn4;?IiKZ?dS1HWO&?i zc`}b&51B{8JpKvuydcc;g)q+}!aTnSU;K1a-lOK-(#5Cb4)EGJ~xc$=#On{GzwDa*2dF}_Ihx>=< z=YAvoa(@zgxSxrg-2cRWJ}=t&;;fxV!d#v(*F%`=C(QdL%tCi7?y{Ky`7KgJ$e^qB`%-5nbsQpD{hAyfYpb-ha~ z^Yc)aSTmK$7j>;nEAt%7S6A)VUf0t8Rx2}q`!8{+YJXAJ#I!OMX8#hmtNzr=Yp<mM5;(QO09-o|P{0nEaB!c^AkEb6ykzU7F& zu>EAc8l9OZ8mYeOx9F{yr26pgrT5}F)z3ZNeG&!L&x>BZ7i%|SzB;%pUrbhg)jjjI zXo`JEeB}kN#8^B=;wzZ*S~S38C%)QLGf$j@eL{S-CGm}DT9^4}P0zPt6Z}3i;kHX<{rZLa9Epxa8yi|b6lZ?5I<@|6QSPm5 z(#SyZeqI1obHB*1vh|gbSp{%#T7m4kR$np2{A`vkRIj10^uaQ&Ir?C}Q;*I|dB=SD zFZRzw?2{p8_fuDf=0OJ#SXQ-AYGL-a>jKm6n=8{sJ+Q8% z%KKw>Q`@&-?xo5v#r##(qrIN|{^cei$le~DkLoF{wrs`sLF^#1Ku>W`xFAH8n?Zf0 zz5dg1(+R<{oFgdM&Z4dbjgH$PoO@>v?g#ah%t{G@cMk`69H^(fJ(MCST^u3M7Vq`_ zC1H7#0|W=_DMNoMLfw-yph2ddV%zqFkn?5+?85U{oNL|M>*tI1ZIXQL?BM_&i<9+M z>6AK_pMw%oWsB*s?600u?!-}R1@jWj+VK|UlcKK4k6vgi-Ho$@MyK@@SA!`+a;zO} z$K2raP5F!Jw?w-O(rJ|)-_?e716NRgI=-z6sc#lh*11s*?){iU*)#R8JaexTM3|3$@ZN!KxLj+ZpA(WK4jKMi3Tydgm^T5l0 z#p?lVEZGmsp-$=;M}4n~Dyn1G#@L=yrNnV{X3?={i1o!Os~1on_sUwF^miHMw$%rV zT{^6zoY;AsxCu5={`7sa*m-H-E9%It)V{hpbdX!BHnjTPPwt`Gwliw9yq4RnGg*#T z#}a#WvOHcLe{_b?07=z zuhszCd(GNCSG#v>_vNDQNAE3{Bt4ty00V>cl+DW%q)A^L;0&%4!Y}$ur>f3?&QbVY zww0H(1?*vUw4TznLY&mJ#|%igq^DHPJuE%h;{X$;;(OehT6aywm*UH128vJmZ_xXi zEtg%+SX;A|v|iQL)hVC!(RV*qznxWdP{j`VwD$Ww=BIcrR$m!~>piO@AH`#(3~23l z*zt|nxTOKD{j_#YS)DIFRBONL3pS(01rp50`999v4NX1E>R7Fv+Im~NFKg>kZEblu zcN_GuKMpr={jaT!wSM?_YFDjqQ#}me>3^yzN@%V3; zGxnFf_JzJO?Zj^w44>pU(Lia6x&NhH*>0hMvIEPaOe%mt*Ee#d2?mPg zGJTL8kZ&vLZ6fs%mv^2zV=$}jp#7UqI|zvYhU`id`R|L=e0C7bk> z8knP|>cadX`pO)vCwhn;1T@fB-edi({q;e4j<1Pg*4EWeU+PGQn|6W7o90TF3ss~^ zTM;zPFjodynMxglMfehAuB1EHlWO7G`_6Lnf2rHcCF)3|hX2;yLP=avMKZ=bwXB8W z`MECTYiG=htnEKs|B?F6ScK`g=6{U&d0hlyW){lBeibD5Wg>Xu`v2Fpno_fD0qowI zE85!9=XMC3^Vw!YG!fhpMcS`KED^cC}QrVvzhIhY*6^HIWD zR9oLR#I^3;lhdf47MKGoOsD#rV@4;Z(|(&_PPt-7?dkcUI+%=IK;=JAs{k8o&7%DA zjSj4Eok4j?a-RJA=yb}*1M_5ke9xWOJYssDY#wh%b$%+BCx1w_r#gLa>A=o2GpNj$ zJvz|c*@4Pj?5P877CBOxxNa5T-q=}GW>`*n82e)umD%Q09+qd%rZQzuSBE#=3#d#V zo9b}eVj-2Wi>(I7J};y)MdeXuO?OD$EJOF!`bs)}F8EP@8C);w;dhRCz}}JR&>>bw zxw+W`B5X3?<*Pq1#>WHtT}+3vU;cu2E^M~B!H!F*bnM!ie`Iqvc-2UPLv`_dY0eSF znd_qT{7YZcw?H*Xf?w|XN>O9ct{byEy8$XI!$-VE&6>LfB1_BgtuY?^SvROM1i!z2 zg1*wR{{7S%{-x*{R(qb+o>i9*dthy-%4pB6+8q2#=fdBQq9x7>ve@tHGj4Gi#iu;Z8P>ZrTR&pq8e2xll!#QC)Ltv@}JBd$KjBDE%eXqqX5WK6{#}>rcZAdE!EK-MIW! z2R&QQ){|SaE1;*wY@KQTt2&xFhOIx^bL&H_$68&Z?qg0n!Pc&OnCq!)T1n5gA2O?> zF6w&H%C&r!>U!ckpaQZ|*QK@}%cI2aY+ahSs64v$f~`w)pXi{1(`j}4Kc_)Y2mOD!7F1Hd6-U3;o+0)739ZjegV>$=N~?{@)_bo^ zgNY+?UG>_`TD~z2p5YoR_^3I#>h)>hCh99)*OZqGFHVEji}jWH z`1+5dI!0|>ItRD6RL3|E^L}-VMO`Br(Q1U0ReCyn9j33WTQOg7tT`QOjnG$0y7y`K zO>He*9NV;G`G(iSejld5&xFcKFT5Tim9^{S4=j@@Pk|%&o6g@c&wDlnp4_bbFY71y zt-adb1M?|WUR%q}8J8n>5K1Xau10{imX5Z|5gXukXWU+=nIbk)`M;_jez(g21*%$61zl$Be=_?O0-}L+~ zPC2fx_+SQe9dvQMzVZOepLNwmO9tpGZ81-7t&i&d#Pt#Tt^?zZw zkvFuOk_Jz!8Yy81yx_s?bl7$nf0t*27u-rr1N$0A%82KlaN<%Le6MMw1oZL*%g8kR zA9XCB?g4N6q=7qb*VZsOD?P#VMmlW7^~~`u9&j%0IFPfIwl324Rbh=6`0Psu+qA#% z6nVjyN9o{@`3G_zc)~j|11^6lfR}cja0B1JYd5?Ait4MV+NqJZ2gGzc4mH;mfSZXY zL`7!6(~f^&h3E;5R%XC6_dn2hoF{A?nE?*C?t1Ow3Hr4%AZ5p2$lT}&Lw~13Qo&!a zHS>at8R;Mo(@};W_5kr}24q(Anx0kvzd?b~{iQ{O3YrcxE9?ag-5jVN2_`V+tVw`*5vxH1_E z?p0Q_eGOjPRa%-i89F6ZR(wp_OXGgof=+T}CALm|sd@Yq+OA#mwZAQCzeVi}4d0qd zrbQXy-*kG=-~T7cs-fWup)GeccR?jO$|6!eLm%gjb`w^ zU@2wonW&^^#t;)DFdI1=MocZIwATM6UkR|ItkqeZvyXNy(yoVEJGJc=_dQ^1%QV<% zZ=@VF^@Q>76sQ_$q|9393A6naIC#xS`TNNe3YsZEz6-2fpNq3551ir!)q@lmf%WW_ zya4pl;8M7eGVZ$vl8uxv4ZL9E3k5cwH&RS-d(*{f;J6k0 zzp*Ez`KCc+YbIkhBn^6FJw(PMCJp9~WbIV~(%{ho#+6Q`LF*1iig~CP?B1RRdxjV( z+Oylau&TmyH8;l^)))NMoYkJuigTXQp1*3<>?J%?^Rdl?u0l^WcV;YXFPv6$DsWqU zVUn6_+Owhdtf#f1IOoJ&)xFUsTefco6?h?MybluJK2P^T)m5MS*n6Qlfov}N{P0Ah z)j9pM#S67m_txF7JW*|RZ++I^6K#rMdu#3~57bZHTjMr)qEkCqY`m}Ui4xzkm~njK zfnHd$SVGObP{lfFkax^TaftFljw{k2%*jY0?RiVnppu7?;)vVt2d6>RwnmD5q$k?j zKMe+jGMT#Ao-w10lo`0)-7gKc&u9EyNrQy;MoLHvPjuNe4So$YQnY6)KQA-XLCr_4 z%|+EMMV(uVIzMXlm;YJ=l~LCL>sA%fo;bEXIIYx0u7B}=pzylkIsA>dp&naLj^lG# zP;<7v@R;H*rUz;x_%{8t3qH5g)Cw2e2klbDvr0!o|kJT5<)cxyPjqXBv_+&VJ5r4mC zNoOHtt1Ya@=Mj@UOX2h2DX{B8WyNWmnQ%I23e@pCp_p6L3! zbQo@;qsVw&s%4k~EAVqXO=fu_-|iW3rrKY~Z{vyVwr9ZCvAC9g=Yi%u$pFts1+aX* z2eKG>94a^$z!n`()boBibnBp_XxGw`u8l>FUF$dPcQ(%^1fY%%M_~)DGfVpY$4fu= zqD=g~G*atU-@XUEvr44Ab#efDT=^(8#NSLb8`4|qdu|flyR|h~x8c2|uD{FBc5S^{ zRBc((dQZC!tm)HR@_4~)*mtLc)VswLT4QK!)5@6QdhF!?hrCv&wq~n_<#o+%X{}NP z^D0$;Wz4m+@HJRm+h}zbM_#M{->C_0^DUtA8E5L}4y7$1KVS*9GqJllTo}HT`XM;g z3|d@XO6|NkJYR13YBH5q*6TsbS5qkuPc($QD>EqTyfcQ{_&>0u9`mz#BbR+JmHyVi z_l=y_Xe!ld_xg=o+jI);>)jSz&;dIt<8ewCY%1ANndCZpFr)HxDiheZBIGV~qB4K? zSA;oN9jVMoQ$rZ^!hy<6s#OzSJeWsiEZl42y>}j!(QRc6wU*7LGXGU|W=Z`Pr5glC z+@q;aKF$e(Q-7jq&DrZ*5X_k#Lu*c*(!p>kB8JvQf9eLq-Lx2bok3gQ7N=g-*1+0+ zPnS!=?;7=|HrT*fa4hXYxz+L8a4Nhz<;~ZgK~Ay(yu))>QafX|W`RY30kyfsthwqFS{IsVyCfqXuK#0l~vo|KD@A5<04TM@i>J8}r(DE=s@F z25sG2oVrw7GnCmMfIf^%2ESbiVC)irEZvgf*o-)EHwr*!KPN*{pBR{7w+HPFOo6uj zjzF->ZggtxF?hQC5PTZ93!U{%g~~YxAg-K0I&n#Y0l`tQa;F~(YXb255PlzInH^}} zZUs6SMS@42?P%=6G-&k{|NptAFM2&F9Y|fOtx=1rGfP_UY3rz>)&y-GWpd{kx_;Dv zuCYF4vXI#k12}}&J$vsgRAx6@GqvlxOonF*$P^Eed7pyzTL`Xo3M-|6f%~LZ<4zP{ln7?YYd>&vGA<(2oXe{j}+njBIV$ z`q`-eIW*-6TZivUn8g)zjddz}9#z`M)?vM|chKC1J?J_-_WB)EaYqj-liKJmy7P#w z=i}Z#N5&IM(e~2)v(SFeQgnURuES-F8VfpJ2C!$TxpH=PTcP0^eYm>BT$w+!r!e-M z9&Nw2XpA6k(WBQhwd=Oj)kYX`xD@rd+h7;rW)kzi_8QAHe6ReY7YR?VL7sh~TmaKPyw+LP=iJQK&yv4{~=| zD1Y8m7xZoPAnmP%vZjK8u&7iih;L`1ixd9w6WuXixQ%6W!WdJunn=4I{n+q30 z^x(%t3#CrWHiAQh9*n`y((h?&Ei8`K1KW!K$2Da9tim1Dx6?3BR((4kbGqtVXUw4b z_TQNo?HOUk@1zJp|nk%>)|;+Q%~a<_=#iS?flx(c|1q=@ElD^HIt60^H{U8v2S^V)j5r1i5A{#NgF7fU)8&k0AM=N-lh zuJOyfZAsg&4~&D(Nv$b=*G~XF^LCWatV@KzT2_<~Cmn^?TRT(kg=^Ys6A|UehRNVO zo2}tHM^uHk3)f4^75WCiX;Z7*Cnld1v56 z%EbPC)7ZI~jB8~&q}_S_!i z%H*+~&Tbni6ZWoeLi_)g+fg_!($2?A{L#} z+!TnBDSzFf?r@qqGV?~|mN_tk(o&~h^ytd9SPF=MBZVEC` z*Ze)JW}*!XSYFK2cSijtvAmexc@3IXi{(Yxmm5%&H_MCP)>}~bAeI;QU$>#kwOC%X z{o{pxq_e!ZV(p6}N3pzkwre{I*uwJSq~Q)U--zV}Y479D@`A{BzR2=|=y_?&@`C8U zQkvxj={IOC%L`)9zJ4q(h@HX)mKVhS!OvJ;ka4vd%ktvX7u&-2s~I+h@(o%JD%2xv z>RG6NW<{~E-)p}+6x!prsZF7s3(vPKwExH>%ffMyc0OJr&;3C3aQ_hf+;5~`?oVP5 z_cO7R`=8j)=jAp2X71HxY_FNq>Hvzn#TYe?L`&YVeW!8Pa1@!y_8r|#p=g0A+jrWR z4M7!+*}gOMMi3h7&i0+8cY$dAc((71vJXVhXR>|A&MFW+3g}I9gtXti$o3r~Z~c(% zJ4BD&5jLkpe~cO1cSyejYmKG9CH7QvW%~}Xv(JEuw4K;rek$8*$hclBj2)*ODQw^6 z7*i-8JuI$J&-Jnih5CaxB^LI(Njh3+k6B<+p`GiRB^TPiU|e$HxJWx6FOlbdAbPle zh<@%j(l7TXv4{Ja*vb7*?C0}x?E5a1*p#h5^|o$8X(}h-_S^bweKW=F&s47b`8iBz ztOMWfw^1tQzl1Hl)8)Yr+bF`SEO?D;r*17PD>`c#lRB!T*W$F-8@11({QV|_eoJ3? zkFWpt`gsjje49-9_RVK7wpumH$1CSSvvfC^$Vg84aMgIUK)A)l9O%*oM8YW(9>LmX zmWXisxffx5(&tBK?a@kNpgP6m*N}zvYpL&aPtpmR)!eO>fTZ zNwIx|wzgn)PPmeTw)9~3*P5G;9tvz+!)oNA>k=F9j(g8g&nnChmVd9ItzVdbsuakm zktOq+_BudG&-mKw14$dQ&{g#s!n<{h$-JNb{v7pg$YLYz!%H-vJBy7+pR>@1tPf(y zqc+OG&AF(XV;{=h-SW`NQL;qZ6F%HT6Ne2(o0>FHbjlq^`951vO$&2niR%HhPKZP^ zJJwRXD)^wQ6#&_oS5qGBc0eX3SJ1JTN=o%N&CnC4N2v6;3W|H<>*A0xuTWf>a>`1h zQKHTHJY@2xjFJ~Jw_|Xhd{ix>jPh##X1VSCT=d4OtkUWpe&)y{3%R~7r`(<28|*IJ zLBUZKm3;>5;F7~xl}3$cfs@@9$?ozx`Td*r}d! zpxteJUB54CbFqo?G360BMASo<%`KI*_gSDkVPn7KngO(SE&CkStML3^#VFH*clP-oOA&$4rCni{T1l!U^2~6F3jl7etWcLG79MO zM_x6*trAx)8MTf3Ax}8eRByEAzmqh#<*Wb%PH z_R0QB=2ZJz?Y^wNj-kEoQJm`u+UpqFb9Zsht=jXl_Kc=IyX9VC=Qv`&cD(<*>yN!V z?tjy}{`k8Y$=p5sZ3l;+e*?n&U7i2a-Xp4gZ|6VneP!>t)xP&tJ9qyR-m|KWt5ebq zYmeFXG{$t4io)FEj4$jRAtWcwpzT{0Z55i}|HhIyd@|yKfKJS!ym`=9!DZe&$`i`y ziTPLNQ{Gy}NE~-z5oPC(wZ+8pODT_S+FH!-v6^z|eL>9LwVufvb`|Rexl+D2p_kYu zbtC1)mi@%ZPd8IO)^(uhhTkJfY-q8uzxdVLt5BwXlsDzziM_;+mwhR3#X9YBc2M?j z)>`cSau;Q<`jV;}FVv*#W}N zeW8?zPxAD_D0>Et5cVBmOni90aX4*vsT5&V#hvlorPouX5sZ)2sVH%opr6B~aP_y3 z>ur^|&Zc@7q;YD$^?!en+7Az+I=?)rB#Ww@<`-(q-2MZ@EaX4xxOVHbmYvk`{!I{M z`*(iyw}$O|$wv5$O~z$z&`;)mOPSbTuI9u1X;*U~eXl8z*^Jw}d~>7nDeZd6{ndG~ z%I+fb`Pz>4|5WFZ^xLv0o8PwBo(CtE(cf;xHqTY#q0|#yna9bBUtgpxYW!H^@eWht z%5{5y1h-hcRsJ$^K_>IS>wETK1kK2FVxxwE1@t=I>hW7tHMg4dFpZBq|_qzWl z-^X6%zv2DZ+V>-MK2{)=j++g)!}XN4$V9eTzL4^XrLE;jJ(g3>dEZ^G`*1DgCvAtw zpUQ2d+{AK}Tq@9w@?ObCM(*yEXSWG_eXuHBSJ=(Uu;-wL4oE4ijz*))*yYeiQMni)*FrvC@&jCBZQ zhg!F!ZR0~J+g^#6My?K{{M31p)CYeHme`P6?s2M9JmUrxwx@2q&iH=M2&;2>j6+86 zuwJjW+uA&_wpZm}wVog>EXQOfO$!qSzhL@L&AKJ5RQvsZXnXIlsFG&!Uyzw0nL$x8 zlFcG2bGnRR1QX`0m~)P(7(h|LoU;guNL12HcY`?x%z4dV}+%3|cn@7FL zE|b5h`OV1Jr+?zmyh1BtWs1+95*?goDDN4+PauV*`*s z^w|UR!qeD-9Zz6#dmDIYr{n*X3qNb{v4qJ9I_|jn3G{zu0f*cydEka8;NHy)DlhoM zVb0&l+6+r6vvFEJ$vbT+buLKHBhMo&r42VKd?(|kTkw`*CefE!#oX( zETZGvufKvGS!PU`q~kAMzk=m!zSI7P{$DVkd{`_?V2R(Db^we0JlCT-av(B4w%;&xO2_e`H!M zehzbrnn{^%3tqse+>cVm&pQ|FB6U(vd#@Lu+5VFX8}>GS31>QKWc&NLmvA=zZ`rQd z_Y$hiFqiG?FrGLT1$i#G&=`?IV?+v#5mCoTj<0FFB%9`o;6i%-f5#ff7u4~^v4cWm z2ZhEC3XNUC92a(~Hee1AH3u*^K+O%z8BlXZ%Kv}1{r7w{$^W}`1ILAk+z{h}<0x5- zBaXXdG441PMCJ*O1?Gut7kPqXC)>r?VP460kykkGAmqikWA4dzk$adkvR&j1<|nB6 ziQ@|*uf+Ib?nxPudzcThUE~Ais%#gziuohkMgBzA)5!KR51xqJlkFn+FjpmuT=i|X zjlJBwUwl>^zSW6gPQIz^zs}i8JATuMRYkavDLj`8xBqwMwahD1jwRH6NZZ@u?}4Gt zu~)y+-_^_{pP7_T*RJ}*RvTW^YJdIVmY<%{j3R&J3qM;}XW?8z8KUa{r}qC&z7@`G z^p~h{2wRX#)_nbA+u2p`$oa#6xOtP$q}cF3T(in|a#r()3qM;}C&nDqnB!Q0Iu?a} zEbPnwrr*N)KQzjOk-p32xOX~r9@0a4OJ36D9t^KqQnGfyGpMHtrDBYp?8}ANC!H0+ z&z+vY=-HV>@b5P_;d_QV2=37DBp91dlpLLx1lBruK{WFx4Kklc{#1 z{Y1f`gZ*NcLz+p~}7Kk~f~p zfE$LHl3g35!oWVWB&TjmE@-droKPS?^WnY%J!RhQDbRm!NOVEJyShdd*fZwB&H_72 zJlIiS|JfBg3j7l7$8+1teuaG0rxucho{kfVWTAgictgpe-*VIHNf!3(=vGUzu+yu( zhh$;@oN;cFgKE};`xS9k?Gf=;?G)pp+K=%A>`(TE zaRuy8GR7OQKgl=_fc;6v@d4~lGL9Qyf0A)L0sE7T;|$oJWE_8y2a+)_0P{mK_FvGB zb`{8@y#;#Ej{^PZUqQd=rEg5&j4k{Rlq=i++Uvf<-?fE`mirB3^<;{M33V;;Ocbc&qYa z98^7Gd{q5n+|+)>c&he@aaQdV<+V_Ym`HaaHpAi$~b9Mt0?x#GSn1?>sdZxqP)9Co`v59@ia zK!4t&`vv{h$$wa2&(N8V3+y~J{7HfR78y?p{4%xcg)b&~MX*VaWRrf$rhX-x>>)zl zWT#}4{gO?7NjCW_*%SxKruaxU#ZBrr#Z$5=&XP^>muwmrX}@WHfw0Fkj*?B|E7>&e zl1=#_*_0=eP5C3)lvk2X`6k(vhmuYCDcO{_l1=$6*_7v!P5Cd`G%qBZ=8I(0Jd$jh zUj^+r?+WB`K1w#tQ^}_JE7>%!C7b5EWK$iGY^o2EO?5-Esh&tS)fvgA`Xkv?mn56& zm1I*LlWeMQl1+6_vT6O2Y^sxzP4!cwq#R1mu#x@l1=qr zvT0qAY+5fQo7NG@ru9X#Y2A@*T8|`~)+x!R^{b#A<69t)ahELg;CM(D`f;2ji+*wZ zBnx|RTqO%TF+U^=`!PQx3%@WwBnyAlb`b|vUc^V$BjTp&7x7g46>(PW5%E{;6yu`W zk97m^9VSN1FRUA&)gI8=%%htQ(-#L#!L1)gI8=%%htQ%0M9-^K< z^$_buK|9us0(q<(1$wY<6zIpgQP3~ejRJeHZWP#wb)&$3tn&qanc8JNG0Cg-N9d7k z(l6Q6uVj-wYJC%SN;cUq8SA0&OR~vd$)-3+HpNG>DQ;4~DV~x|ah7a~zhu+6Nc%-z zV1CHl5P5<5Az9=F=7(gF7nmQCMP6WjNEUg4`5{^41?Gojkr$XBl0{x%en`f;A>LCY zW8Eld$GTA<}#a5%vid{Rq1Si++SZf<-^VPr;%e;lE(fkBEz4 z(T|9iV38Lhj)FyAsO=&zRC$pXsveOSs(z6dYQG{cRC`2TsCJ6HQ0*6aq537-)p{c2 z)jA{esP#waSL>4KSFKmV9<`1MJJtFo>{sia@Jp?S!e6yr#6gu8@lo}NxT*R@Jk@?h zoK<^7{8c-}xTyAvc`W9$h#}T3BIdbZG4Dm45{z|@h`Jyc>z^X(gxk^+<3L{72L&Q@cTJ7j;*a7j;+FBkHcIU({W-Ur~2edqmw;?G$yl zz<#W|h5VwTPKkbnyr@%xg&t9-1PlG5P6-zMiaI6b(H>E!1PePwof0h84N<2A3%|s= zVrti`?II4Uyr{dX9uYTHzlf*WuZXj1kBGl&rx+L2{_Nt8Smzf-i@q)-m4{zvZpxZD zHl{S(2<|THZ9i8XWEbBm*}>r*N#1cvviP_7Z}F`7|3Xf%cuqVoSm+aa1q;7Kf2MY$ z+K%#6l}9~P)r0z}svrMN)qe5+Gu0k^j;VH{KBn4_{fPa%>X&FYihfP|sLQWT#}IPxL3+O@68E!e3Qh#6hwtK9WswQ~MS1lq~!f{h92P{RtLvQtcm8 zJ(l&kz86Ax7Fhbnvbqgop>36H=(Z)6MfBSXs~>X+4cN!-MD2ka131*L636OXj)8%G z92#AXV6~`iv$AJ^-)UAwTy-w_dusT_g zl@P~5f5*bFC=O{;_p=LjvCy>%hohPCY;xjWm_M3B;b#lmw$?U=-J850Y@TqK@gjyD z*}orhaAUXR*PaAk0!y9w;52ke-xXx zItltJ1~?WI#ay2z!ju3bq%DkQhH5GDS$#w_i*q>u4I5@a`|N0DR{H>y&&q@f6=E3O zkOJ?k8R1CIZdRg25=5sNq1V?aw%#EbD)mi=rzug)P&NrhHa0?=(ot+gdJ;5@%Yegm zqgjWGxZg4}!pkaA>{x6PWPeGAfTZ2*Y^N015|{x`jz_U-0}|n9oDrr&6ss4J1j8&0 z;CVipO$bSb;yaD7{pT(=*)<6o4M~TTX;Ez3mn3k1nhwkY$D%_D%vqEUSJ6&~LCFxu zjPS5|G*grmtoP}#a&HuC;+6n*$^jUCB#ND536Op^1;U?4vDUBR;cmTy@a%RJ>-i-f z!ds@o^bj2Pwh7>&q`~!%_`S;u3GnM#8WfIm;kZ5S7Q?FG_hBxh&c^mJ%pK!1DER<< zy&KKi=OjY;g$LpN)@Zi+bs{XxN`;WnXqNIY39J*+pzyPWZNqxNur9!Z@rkhFDUM50 zJiP3j2w!GJvlpWiATT2lA};P`4mbxt?MQ;^b$7EUQ7F zCQM0$YTJ`x*t%%eu0aBrtxbe%^BC6YM-nt1m<+-AxtqG#@i5CT5eD|(!?JfJ!o8Snk*TU=E4!W@HQ-Y>@zC zTPMOGm%VIwtwi|CI}vs|$1wjM$#7?73JjROmobY(uxpzLSQi=AI2hbI0kG~etZ@Ly zSlbxRJ(#s15wNx~tZ{H~4(?6;_A{(;FywnYU~OYqlL?Hik70<}6MCtZfWy9IVG0inWblje~D@;{j_M z!x{%JyW;_C8^an0(=NsX);5MU4wl;_0@gN$H4e0E698))!x{(9xe0)^jbV+0d~E_? zZDUyDAWEMII1d=k2bfsX2sjTI<{VtuWCWZC4Ce#HdKm!c0mJzKU#n*V&I5+?0s7X= z0GtO5=L3Y!O9!ks4Ce#%ZIupKKN!vj$v6)f<}@5Yoj4B|&IfQ#GXTy5hVuc&JkA81 z2Mp%}nD5O1oCgf&1I*4$hr-Vmwyp5`i1UEqe1Oe%S%C9^;e3GVi5zeqFq{vt{5S)g z2Mp%}yo;j$vYz5RU^pM3t0oI@9x$8_(A<>+&I5+?0XjXzcSrXmhVucIU>(MJz;Hf5 zvRfA5JYYB!Q^0w^a6Z67k1W7>z;Hf*LzOJRdBAW!z@A!Jfb)Ri ze1Lsdjac^*8O{g%K3*37orGkDYXfviNWr?3z;JDVw#bFY2-gILYXd|KNCR9G7_JR) zWO^##n!s>v0FRmn0oMeEYXg)jbKqab6xRfXYXfwumj<{dFkBm8%-(~5YXZZy0oM8) z09+Fot_|=YDFtv%V7NBG2y4uZvPlfr2B=u)0N|RyaBYB2G!<}7V7NAb<vfGUFz0#HD^UNVG{7|h*X0i z&^ONl&*6!z!s1w1UNO6%K8XEK(^B!Q_?DxbgT!6YY`mwy26caCA> zwxq!I%_%VOFWiF_OM!mHgB_lXSmi!ga>GT=Uu;eHY5{G@`u{%d_JTw@E*Wy}$VxdJ~O(g1UW zVXoksn+}*G408o`XfpwGgki40yGaJX9ATI%kZ{Hbm?I2x1>CLJKh}+ZcP;2p7JtX@ z+AestE*AdwJ;=K5-3`WZdmy(_3LBah1D=PXq1=x|=JkFr4BosO?#INlarixIFU@Yi ze>41V$@u>n%1Ie~j^Xq2S=7f+uhfbCFziqEwY1Ytc64hx{C30lqAEMsoO2oQr9>hW z>%5&c+nNd9jZEcmPZ8-Dg zIHqyzj2aX1tQsq!Q;nhM3w>f}2M8O`Cx*U(unm1; z=o<)|(I_pF;R7jSp8q*k~&{R4*#d-*MF+E{9n}A!tc@HiLvZ3 z?!o&v%!Uz1_p+y0leUIt!N@oGKKm;PTJGV{tNtGL(U=T=TN#X66T=?&N`ZajC{!;O z!)jbhfy(&4rq-YT$(rTt8BT9ne}YD{6)1aQh2)~;>%df-m68`Ns0M+#e`I3q?ZGy5 zk!&y7$O-~mjh9?|-Vf5zr=w&W+ZW{W4>!r*<8P9H#$Sy>fA&cJ zZxHPnk1bXzg2#3}LQ75=eo3xasSBWAk}vtThMp%Y5h4G=*%2-l`4f}k9!@Z@ z^&kG`R|8(Gt1M+aden#KW$Y#2F6j*&t#y*q+BAhN=Uzyghn(>Ni_uw&jUlso91U$q~`Ze!eCvXjMG75VJAMFTRHY}0+AkZHsbu>tx z{h%#89`f`L_w*;g{qS=QYAF$<1q<3%?{+@AaFYU(%Oh^anw|q>tM- z{vha=BJ8~N{ue>NB)_?7Cj64zwXa6_^@pEW3BQPt-_yB-@Jn)~>Gt5cFITx6{0mBK zs{^^dv69aul!7&=pkFgSQ6Z%bYE9eVjBK0q^Y9?Z05cVJT zYc68qEn@PnZp(j(dEv1WEOd%-EUX`6BIA51A4E(Pp|f8fJ#@U3r3js;J~a5p94I_q zh4o_`q|W-5E+P(6=Ym>QMI00n=b#Q1MI00n=U-FH{*T68_#$$q+|>x_*YZ=v;cier z$uq~>LPB5#$v@+*p=rWCy^wcXZUx~zdUy-&?_dQngGU(z`*gJWU+0O?Bl4|HFJGhJ zS*bR#_Q(RsrEe62uamb+_Fh&JT5QVrBa>AIw#1y1yl8Ma*jMGA=tbs2Cx3`zvphPR^kfoRLnPlGTf0P@d zUy)Zg8+TF!Uv1P9q7%X;r$;t}hx7MK4siu=sC?p2dqr>XNxvf0QEc zq|Wd4Yrw)H?zzrlH^%FZ6R)4Damnz z+QW3ShBD^s#`r-(gTXT9mHPQXYiCDA=wzPl!J$czfor|@N#3933)kOWlstTU za~R|G$FHLq1pL-p5b^BedX1pCO)<%bz3PFXQ7Or(tTzORe}%&Hew>T>ekZ$C-;gj4?evLR*~~v~j3vbZU|h2V9DRXrEgqU$z%fsvCzn zid|($LjZu58LKL zM(O5oGUtc!SG9b2-GadC4_1`@%7gA78bXd+X`==zQpyULVHIE=dor%!fnu8iT%xhCa;9heo3S zx}SPueD^RP{Oh)WFF9w8v#dWtk>0H!>~4(Fqy9%2b+RoCNGnU*NvUY3_+vk8U~_FtNX6t z(SCpC*^xSaZL&MGsdmvjf0T|}&G7*9{z3W)qjkLMD-U?{=)C^t5FP(ou?9Tj)s^x6~D;3|OPg!|%;?ndbs6U+q+m zpgreooZ#%XeMU$1n$||N?b8jdQNPbZCm5vNZK#9KKG{_bW|w7#dnm(JRDoN= zPZ$y~K6?L3uxTYXg!R^Ozta`K@kPAhSWg|#@hT6y>{l5op}#K;<>1)l07C-Cq4}h; zaJAIC%rzLFgH!F{!bQl4#kjSLvV(8PwiwULex<=;2N-%{oF7ds1J94IHmpY(^VN1x zx6TbiC+xR^c{#Yh{FmV%#?arU0;IezY7D^`X2n&6rYAZpq=AkXH~T<}SXNQ)BEPJf zM~aO!Q(k-N_%hu`ve@IOzG-6}FH`St(y;hWeFp`{ecw+qYs@-*OcNb%aK#J+_inA@ zW4Bqs_{v3$h1skf=GZSA7(Za2Qkc8qvtdik;QWL=%5%MrAISefW?$Z^oWj1wxP2wJ zEY~RA8tVAZBOi&&@OjD!v@Q7C2jV=q2CXtp%de-jrVDS{(VEEZ!v662$y(l|XeZiW zxf4BrJUp-yt$NduM&Ng=YXo*fNNYxmB8$9;W5R zx{st|G z4bk$Js~6JuzUAnh!PwW0PqsTHeERBlXid(Zn8F?s#hx-FCo(>X9q&-%QDn`m_{soxIKT zPN$Lo!gEm1%WdoF_{pAB8`Xz#HdRB>^AB5jS$KMmYde50!qhB`+i|9(*I~6H{Mr(5X4IdoSq|u$}*r5tNh-^KeleD2Qi`;m2 zpf&A3brg*}gRvcPT^Uw(B;9{b%cn;^Rela1O6yDl++F*(a^{8O zzwoLnTE1+S4G}q3m{ob-Q=g25`3mZfi+iRB`NHgfQp+3JXG{HsS(PbsH=scNddL2> z1L~Rl@{y7`dN8#{`zs%~tPGz$h(@8FopTN=yDdf*@L1wbDs9m5$uGKq-S$Y*VWo~A z%JGwYWhvG)i`MYhyAkA3gpNBOZY$e&%+>Mr<%s0v)37GrZvb9RMw162xE`%<0Yc}2 zAgp5p^pf)zV$HeN48D%&NA94`V4K!p+p#n8S+3&&Kif%}jo9zAGX9b?h>nLl6p{L$ zV+~39olk^qL*u*fXcTj?aGZMz-s#>-d1k%aYwI==e9sV?@|9+e61^gx@E^ z9{;Lhjk_p0(oM&YIou_}o@uDF-n3jI?78Qu<2QP}molEBZiIf6yt$c0Am(^?eAb&1sMC2Q?Tyb~tI`xE zZ6~w_wns0+&t6xpLc7h!-?N@}|kOuFd?Wi8v>UUkpN$gDHP`-R{UDzAco7SG7 z={@cDnA}TH7K*9jT2;F972bS zXBRoc%rPTqC0xf}*}B5$Rimf{?u&vCxxuTBqp1dMD7w-Ea@&of{%D)?`kHWa^l&-@ zeIK#7HYlEfv^DzD&805f9@>kBPS$Y;_xe!O!=I*4(edlvo=~l5Gg@M*j?W77gkt49 zX$rPC^74eX4?L(D@`v^H;pKWKS{a}He6}8RyHSDWV@!f?*MSbd>}Z*BI)1uMEtrh! z#l=xNp4!I)!hG!LZ?t*m4ObvpWob){NyBz7a6P*MjYS_{-g1Je^{dhW=zGxv)uGf@ zS2_dtA-x}0gQ44N7sMxTYi)W8_e&4qM|yJsoc|?-fZRBd02CQx-U2y>dS+c~V)N?=v_N`-j5(8D;u^ zJxr#r4plmo*6~`%gIvcb8|`&`*u9fv!4MyE@s*Yj91uuuUztI^w^35n~JEb=TWAnt48*lgYEU2-c+t^nM(XlAV0~F+zfe1c!rc8&b55*z=?|e z5hq#~_oBaMRe%nM9O)6ly_7oCRBdJngSt8s(rTGZLW zzc`HkGJ;OWepfsw3GZ>vo-$9BgytVpVc}ZL1rA(a5LRNmS|i?nx|-Zw)tRod|DVuPSWu3k%6q{ z=0zkaLBoGH7|Mc*1d*xn8a}7PFt*rwDse$Bx^5V|8$Ol{iqY_L3B%a8$9>2uY`@uH z7<*K&BUyvbmgq2)g;@I#d(`t0xt(FK`~r6gw|+5N%6KAINU6s!f8>w)Xn| zZ1gF2@+4Ek+t%#ECcJkgdaB{fz87o%(S?-B&~TsY-Pt1>Hxns-D!m!I;G(|zWTA?d9BI&(;EINw>_I5 z(1El*qv4@j+q2Yj-N*^llRBe4TUdNJd4n=XU$ti)V4{v#t&A~sM_aNE zc~Mdc;|8zh#0TZ)ebpFiUh*cLqP4t2?i<7S;SI=a)VY7=Im7L)wa8cO%l>zWq1}5o z@)>QIJ)dWG9OFuAp=~!drFx$PH?j!rUte>e-YUd{BpuLl{nZ40hsw3ds#L5eCm!p0 zgGS^z)}m&;$|&tyw!ziU$cZf$C#Y2YGW+3ZXp@6 z3;A+YqyPEY4B4JYw0vv5Gm_7F<66`EA{91_%hT|Z`(2r^VHNVJWv)!vP?+_fH2k=S zGZQwbENmEw?HNU#nXtjuOv{I?Eid`^PYv(U$&m>g4EY*fccF`Huk%8~i{#aj?Eg%| z0~gn4G7iP?UDCF=w4qdSdraMbeGpNmKi zE|0mCQdHWYFQMh7p4iIvL<=o{)U~YSb7-?~t^*sB!S#7!{d#alDOIJ1ckk0$zUuIK zrTQA3p$@J`lQXU;86gpdfU{a&_t70?@cNU69DK*ota+yBd%ZVo#dop5iTTQmHARhU zb8tQ$D?*OF(HX-oYk7xbIx_!Z5u@XEEibXwj)V-nVTiq{OEX0^Loo>jF5dFZ~_I|;dFm0I{acIkTads=>_Rc-Rcx|Xs5 z+b5i=N!-r$Q5ZgJZ*V6KSI<*cqt1*7XA;LFl@hn`J-1pFGA40@(h`4{FDKc7)P-$I z$7@<%HU)pfZ{QAP0KO+)KWt6bTWwV?;k#syazB)J>8q5s=kcBQ-3w*K*brqu`hIuN zU&@CUqNF~X-C^4ZmEI8xi~P+W4$hVizLz;by3_UT!-g_TkkYX?f3W&4}2C-}?*e-iroA?8A#= zOb*=jAYvch1!JPw?L@>rJRNodz04XiP(pSVocWClqF&xF5Y7SyB0}{3ZMhAu2wr(+gtE^ ztg9t!9m*8%hJ{&`aUIr@9zpqyv+nCVPi{xOv2GW0<9af<3$=^a@}K>a^fA8uXb`q< z*?UYs^7K#|jCI~)*!93!-kP`c^1yW+4B{aHH3N} z)^g`nYm`q*`qHXLu_k-%Qf?|;XvJe%zCs_X+(M2Y0t}OYu-8)^jjzf_u>%`|-+#v4M0vu31;xbW$di9!M+U8k7@QR=KmWH$98CHJwyc zX*(-`M&sJID(i3kwi-n zA&RG8Bl^^cbNu5vWgOI_`;KUNx4*V2CAxUfISls$O?N3{j#i;T*gk8+R^@vY2bzI4 zZ+W*u@or#8N2BkJUe8k|U_Ok+nCvaqO{uuRj<&^E)ve^F_*E-UFQPpw;)oQ4$ORqqW z;vU69xY#YvYU5SuT4sQY=80D zU#~$sHsRi>cKUMtTg^zt6>}_MOo~3ROMT@%>eTQ{`md26^>Jw1snyT)<<5rcyJ8&D z4!+aB{oFfq5w_DBkM!>wW*DlYeEw0R-fxqO@fGT?vTC|McD=u`C+^uQ)^XHNjGAN& z!`v?0Fu;2fayyhc*)2fdu+p082`e(aR+bq zE)jpL_JM}SJZ;2sFeVOTL}_ zJqB3m_8vwdKMLhD=X5l#MfuC!^i25P7yGs6jalbClZ@lg{^I@(nZ?V-#xdA_A+a&L z^rp12DB8dCy*Kk&aNFQ^UBjzcC~Vd4UWNpe_qQZ$*v8|H^0BXziG=mc>qH;D)p9q# zaYWRXYsk;ak0W=HYk$CZ=eg5J*qh!o`X%ml-%KORnhv4^^Kd_KY!*2?ZWwLz2KSQ# zgUPKMBWa`0n4d=$k#b!|(^4qo+aio~Fpi|VzT^IOdL)^1XBZv)6W6$nD@lgWV0!r% zp3T-;L+JHB^z3h(`!Cm$soHL|RS_KzJ-&|gFXK-qAnz%$UY^Gm<`VeqhYPF7R*Uvj zpptg2>6pPV@xI(5M;2Gq5e4g8Y8QbTSoxZ#f3za5`_Aw5KDsN9X_H zhZwh~t;Uhxqx;Y?);hlA{a%t&cQD;+qvJbV;)qkv;dFH|9sj*HfsAZ3iXJb4znvSB zBGBdBgeEpNp9vgpgWN(XP+Qjy4Rxi$i`#G$<>)IvK|42JO(w&(*we9S zzgd?A;u}+*ZbZLAtmDXv7FFn2^moFCy`;*;+s4BDTc_hIH}58S?K@M!F32LsJ|fp$ zyj$j2dwkX|Z7;c2VlEl#r{PN+x3DHw@pIH8!%tJNgj&o*JHTcO#q0x{``0bH#rX>(kPooa~P8!jm_#;2OT9 zb0^f_Zxh>R-hd46tl^ROH?sbCJ~IXR%dL$}oYnN|ui?#0tY<+!4M+g;i&E=Z_(>l! zrk{rQnYEsU?CwIQAb***o*gaQlUy07;THL8C2t;v@6P>JOFjKZ;`?mXRgxc#$9MCF z%b7U0DUI#LTdrbdkZ<V)tX4Mx)-wNMz-x@I9ZJLA9CEp{Nut%^==wIz0PJf z=G!8&31brY*JkG5Y&Cwq){@(OIS6C_3L(FJE&0r&1|Y3c$O~*QS0WYKmZhXZO-nwt z{(jISkMuyE8V9-Kc9EcJmi+spJy2}-PO{m?lD90j6Ru?^kfAzDKB3-r7*d9ksYNY$ zr*T`M1wMP;%#vSD+5)RJnPlNNJeM205%1Ac$elNMpLk?744b@~lzNNj;kQ?V^`a%D z!Arb9bzTnkS)pWfu8!C56$z(0EF<(0-iMxF2EkoclG)dFT;m@G-Y#p%s@pog%Vh}+ zCu@oECZ2T%EQZDzOUU6I9j|eCA(ReYNQz(3@yFo{V8Wyz5_%T%ZPa`S`aO{(9Kn0@ zzvh9%D2a_)!_0q2u?@j)!IyLGj~gL)oct>8h2&Q2&xoGl9mG)jyzkmwIX@?2nyp zIE3wWzs`hvvo9J(X6g9wveST!ZECbf{V$h}fre?HjRUaXxHS_YDLB>GE?vi`Tp9)N!QfP}2JM4>xpr9uC#MXgqfg_#$@_U=(J+`ExP46wW+eMgwo*eew3iP^}YMtUyR)fwoMagUCal&+^ulYcP9-j zVaaQq-VS9~ZKmZ*S#lP+1FpSZPhXYB-wYqH6XtH+K<`$t##}vQp9&S;h0!SF0q+h%zdO^Z zwiW)i@CgGfby`C6@b|ipMJ+P@8NXISz|YtKXYtz`y2 z5r5yi-x*kIUP@7UUerQGefEXZN~IX;zk+(a;}euTe75?k9OxNRoD7&^$rpuOfLX|? zXd69x0)FU$v_t!^PC5!vPbQK{=-1sL_?u1ZR*@&&ExBjc!|*g~H5t^~k_SA`h6MlR zBp74TGn0cm?%TgR;l0?-hvZ||QS@ak9WQzCDcL)GICZS6WS^w5undg=I_&iTZ7M^l=M{Hw@E61=NE4MPs^mQTF!j5G)3Q*84{ zQVz` z_yf}9xE=Lz!@HifcSv@K11;vF;g&E`pNcM*uHOY0M(%U+2J|F_DCHSDv#!q*oHyMr+h7Uof=G*_l#5)q5Qcvv&qeq8BBnG4bQ6=*NzEfvRZc2h}ybONWe!D?) zGNHygLr0X~aLI>^&pm30LjB5`wgiekGgQYj1lvy?NSEUl#<3WyddA*l&@G*DIQn&A z$WZcmVo~Ew^mnE6IFeNFqu~_BA;@kj;UB1BBgSgD+dSgaGr$mt`>R=P7LtzFCS|mK zr{&jLEh4@4*ysmf`>^H2jtnCWs2 z{kC1hZ3aw|ycEyL2Lz8{Lgvv9+z&6GDA{+Ph97hvDc9Kwu^OJ_IZE>7<+x|K8Z2eL zuh8%=XXeQ>v~eDIZg%gbJWE`KTz=b2d6rn1m0CECcb>|#M3u!k-Y9JUvizw$8?^Pt zu}IF5T%;ksgScLoXNiUyTK+sdSGL!ws^v?^e3#sz66R9-B23&VoTuRXNQVe{r|@Euh9};R zkar53kSG0$kar4KN8>)kI#S*#XeVp<-SZLhPQenNozW*k-YG1digyYL;qp#l1@=|^ z#4>rO;Ep!5FR@JCDZEG9*5!oBJB8l!G<uZgJB8cJG`x1o0(qySg@!mr+4bhjJB495MrS(* z%R2>%Jk%ms-YJl!*zf&$@=hTT+oQS$%R7Z}`0TuL^W~jFV5ElESutPUDU1%sJ>kR! z@=oC*J{#%2P~ItgLfZl-ERuH$)}b0+!7oJKDHK_x;Tya{<(7eTI%3 z@eFN=kFjQ(A9}JD=kL?G#_s+1DWzB9yA0iGG$MON;(bB$6yun(w%)6e=XUKo>|SDvcCJ2#5pK)wv5b&1M{`~R?A8<_jWJCyMusyqZghh ze_o99@$Y-aG2^f62Zv)WbKKNEo$w51{{I7GhjpA%M zcpsjtM0y&^BUi(ApZ9wVWqR!JPC{<|xQ0>qQEuIO%}>Rvo>J zCisja)BEFRjnX3Nu|?BJhkkfZacTw4+Bc8np*?TMuB0tp{YeDMyo`*bVKusv>&Shr zBkAm|y~(}-_?fX4;q=Gn0pv64Tm(z$t;as(4$2HOi=^X!5|WNGXJ>}f){`5OPbjm$ z$x=FHYHe}}D zt)T7;2r27>&%R+&|9f9N*V<~3?2TjhV9^?>e`HrJZ#a2Bgls^JpVa$(P&pC zoH#__I`}l#7|~}b@y5Auxyxsx)rL^wi84OJ&FTE!^T{im7j?gD>1CfO#2AdZ@z|33 zz8Xl*Vf(2OI=b?8NAh6_o?Ub-O83ugN%}9<@{kEXj9$r&NmHChtAD&T9ynE>Q0!|* zz!Re{sZ9cKPPx6mY3%*lgM3?ocR=ON8wd4rCB4?*nb?<9qpOE2X}%uMhimLK{`Pby zE3qat-L%3O8CjEb-i+tl#TFTt;5}>%#$-y?P~$MmX5=--YSqX9V~cC8No72HnY+3n zt5&u@seorbAO3F4(zZpCQy1}lGqagor$xHJ!+&sZW+LrlR!~316DLDtv!HUFq zvHL-z$;fJW_OAa*>GuA_fV^Pe-*nuZE@VS>tc{LesL#gM&6B4oM*Ij$p}Kl`rh>=?NWRh zY2k+R=*U~z4c{@RqCIWCeV{AbhY~MmZ1?_%b9O$7M*B}&e4&#*Od}cS*E;;$GO45W zq`WoOu@D+$^l$QU#W6h>5awG0`cs@VNlGQ9;gT$7_ zI}Xq?vvPIFO$Xecw6S2DV?D{x3RwT2n6pdkfcQ9S`I^RN?Ca#V#J>{SfP0ed-@1{{ z_-t{rA}ssha8eQ5t*7Jt;EpMzBFew)YsS+2<`Bz@7^^Pkten$AqA7!CuuF>K@4GA} zN;xfWZqTqdotBbG_PBrUs$*$IBS=bV-20ufVsDI*B&7uEpJ~gMO2m0(wn zMUou!*JW2}c6eq43DM#nGRcm8KD&&Z#aOv1Wm(3-#bgo2aD}e}d(&$Hu`|Q2cMPYY|CbHj}*snO36E>*)paq^4Y}LTnWi_ebWys>QF>jC$@BPEeP<}*c zQTgt97}w?V{cWju_e@@bcShb8RJ?mW!rE(}`L|KLduCwmt+nBmQM`LeT&Z~X^qqtE{*JY&c=v1&g!_lL^{9CF)Z>05&(4#IcTX>Dzy1dAlvc)X8(WR2r^ES8ML`)GSB{48I1jJ%JohUcgj zwo&pvy1oW=uH7#0qod7qyrX_2d5iba6@TOBG?Lbk<#-=G?&)e5oA2x?;rn$HTG3FvBmrSTG)PXcLZ_8`+YNfwtKbZ z#EAF%E~ryeYb6KO*1sNhDQ0 z7JDzmxRvlpBI4eB749p{4Wo_X-n_*Q+~f6XW)%14KX>9DY=Ns$+?$__!aIvxTcfx) zKd>9~VeW5(xHtcZT&2R_261nmh8L`jffdDCQM{lc9*b#Ie)#& z;qJp*Mb)|W-t*S|{`*x|Pft%zp6;2UvJW;EEB)q^NPa`BzG9`{eA{7KhcB5eR>rUP zpf!Nub6>GCeswIZ4Xoz|ik0!J9}iN#Eknghzqyq3EDH-);U)WM?>RhHe5ubAzG^@1 zB|n}O56Yjx*AS1_V0|RMorny(F z^qX6fP5$)RtlHN+-$H$A)-X`+Yp!q7NxYjh2*%Q0CWvC-Z)x`j<-SI|hVH+t>I=$! zjnP`2M57nILAkHVU8a-hySNu9_cdmVDTds@1}@Tmt^0f$Z_jiA<=(2-BAvt~qdTeY zytMPA82IizLAkG4yMpd3W%dT;zNUcabzT4{_ceCwbP|J~*{S$-cal$}^-vYo*rSs; zIeEBBX00GPKYuraJr*X>zQ%@l$`!*wdDh`dei_A_Sa$B72P-C@(GjaS z751V&)qLa;R_5cxPS7~u>=LHJhE3?q+%ADB_X2YA?|j^hD(p!-%k;yTa^K-heK2lq zxC;9kQ`uYHXR1AjA^DF=5>?og#*>uML8>#E;nbIxy9Bd-g9fpQQ^=nc*cuASpW@*} zcX@W1g3_O|hOp%!Q&7pDL*qcFwlIBYcQ%Fa(Y9?Nko+mjD7JaV6ie7f{**O@EnF-? z=}&n#kLI}9?NvCO?B8^6XO)~;R4*;-byZ;**)}?>Cn)u7PV~=r={;$}nX|~AFD<~E z{3*e%I*Hv1%wPfeQ+B&hT)mztJc{;XRx`+kB_^=*n=d;)jm`%BjlrwIdbWUKU!Ut4 zLy7Kkc8ch>`;6ff`JUV;j#TS~37m0sV;xA2qqsE$k?*M{@m%?A2HGc`n8{3vBi&~T zweQ)pHpF8|_X@W=jAD7K=$*2@1Sq4ICa`pLB*W3y)B3VPphRmVVhJ0b~{_}Trv zpz}BpXJ|xV>uLL;#0fEBPXs=DaRB=K6yw6xk*H@C1Pw6(?_Q3=`V$Vp!4vU#R&*L+ zP%y~Earj>2EJl9|hWOfXIGEm`YT*$AmV2+_OoJFS4G4h^^RMDLhl{9xI0OnDuj0O- zOXw970;e~}Vnpyy?9u!PtPovNzPpS0YmR}j*##B$_c#TM{bKPlz43G-^At3ybp<2W zrhwn!6VS769NvPva60lhMBR$VslK-$pwTfn-&TyP-IAd^^C;-G=h*aPBJ4Ij3X79D z`i>F9>o-Thy@=zU-B%&6?oo)1;`sLAB^Y}7C`|Y&#+vk=j@9EZ7?+iRZxYVXn=;2C zVQxHzghoMnuM^-z?F6L{*; zRdm{U7s$3)Y118_Y*OpMg)#>-j81#5gP?Y;Gb6qu+w)jPG1v= z13Ls^t~de9u12B5ghM!h+Esj?(})9uaSW%wb2QK5p0B|eQzs64|2T)C3qo+izN@&# zFa~}1gy81|SFz8;i@5rFE!5aj(YBjR52H6(RexjQ!|$Q+SmUCqEoC`|p}3%eZgf_R z=Q{?d=o_~^MgPUqR9JsV7DhHwy#XWV+b5Cg*Om2YmNiFE;Hl!}=W zzkmJ?eZN_O5^HGR#}lhnZ}Owrs7pA1UWkf5dh!8ur1#R4JR5c9;*{x+RJcQ+2|8M2 zsBoO@7@s{~s=|#W_B~c*7OJrJmt*YUU-ZHt6S(ph|D1+%A?GhS@1`Dr+JP1FpN+i) zedbr>`>M`;@b;?ECq3;Q?EF!o=V+S(F#A-Ye|}0K%(zieuD+{e(BVNvd7qBRf&&dI z>@a87QwaB{uur>-Vo2>!VYjLB z0he*ircf20HTNKzyi@&GLh&>6a9rwR6+Pf`D?AjZdeQcuz!D)pywL1nq9yii$QvIA7wf$Rg7 z_944LrQL+%p>Ul1+G?1>P#U{@W{fclRa?Zt)V=4!(*b-)=(Bp099J^c7TG^1+VAuW&PswFLpbI3)EY zHgt-`rYkn%oe3}TRm5eSH*Jeb&TCOD+PH33;h6APOzPvS!iQeRVm)&o6)sP^f^WO| z;KY+J(QD-uWV?OvvC~Tw>ht9$qVcf#D*ibyZsMjV<5jpx^ZOXJzPAd`3wnSz-`J}3 zT-NFV+AXwI=`R_48)r_nSJBPdT|=vy3sqQHE@657cp|#2U4XNUULt#W3(w?CP~q(H zkFdexuByCj6CdKd(&>!>&>9q9!NuB@Y-`_pmNHZQKMBe8orP8+#N zCC7hBIxgAdrNSHfr=z)iu?lZ2e2?R&&Qal+&(m@F4>zu=qsVl8S3HN`r#ce8Eg*c0 zKsd+!yMJB_$LfX4YodF5E!CRjiT^KtFS-IRIQxmG*CZbttxqCa(ixdq1%9-qi2t#v zmAI1V2MVODfvAEmd>bLYa~W&=7k_W~#%!`GWQsjBz;smwzTHC;SnUcdTo(z~OTsr6 z{@s7ct6SR$=cC}0p}@l{#?Oz|!H}7K37^qg=&X4#){|XAADUbDg@@wSV--Brjkm(N znBJ1YI#=nfPZ|fH&OTf?_#F0nT6KJ=GH$piz}-1j{AH~tX8(oT%=bj6wQ9QWU-*C0 z4-h@UC{?^?y(h*Cm* zCI8=%Bh*2t=jB2;Cx82v75G@DIK-er|>E z=~W7s-l>KDmW3ei_Lw`D*228c^hfx)RK9wCE$nz*4rysG`Re|fIFidDI`S3o*I5H) z#l`UH-XR{gj?SnfEAZJt1~~M&ny$B7O&4Mzf6$U*=sGooi_SL3Q9i}s-6@z`_ic)z zooc$_kz%N870gffX^KLAAy3OU#o$|O4}bl}46l7qFwAy4uY1H0XMq|Ed5-Ir zK=X*5{9WDFXxWZP2&$`nwojXzk>0 zKbv4W+2qcMUHnmb>neG9_*CTU)JegG`aGDUrVFu<-*8kh+{ljROA3?trNhNwy*8Ym ze4ES%y($KWcZc~Uw_AK^trD;(3*xJ9+~xkAOW>NrKK^s^LvAv%1T^3H^Jzm;d5B91 z^vm7F53Nn(KNgmNUGNSLL7BYVqXaUyZRdL@7x4Jm>bwSQFM$(}w{x3ac|4W$Pdl-b zFSmWidoC@3^A3CX(H1ZG)5#_9c~u}cxciv*>sBt**k9&TpR2Jj?PgsWXytt6;(|+Dqg)DE5#M=0qsv?< zXL_0xvWf0b^qfyp&>?qRWSQJ)QU5xsdEU zGK8n=X7j;i#gN%NnCHbvxUkO(^%3^jc2r*hlY;qot$hCeG4;EE5MFy=7I&b$R{aj; zaqZK2>+oWT-xtQ$Tz}0&mKMW==_h&U=9g9MP@Ua`wiVj&pU_7*<_O0P;W#7g*TTN} zclx-n&kEb^KiyA-ZT`=(G6-}{5I4SXwAYCx+fr%_eRM4=C+q`FgRY z!;=Kx=rXVo1&9Y2{7CRVQU=|0!o`}GG{nva%3x6M7_rucvV=qaWzf_4x_F({`2@H9 zWzc{9P4WDW%@Pb_KfuaOpF~Zr`9S<*HBPVn0S2rY%3r+R4jbF3aelK3o`leTu+2t| zy^KFX^pCv>#$g+vMQ=5J)T>-2NAE~aSTaG4qkn$@&*7Tlq8-a&WV4U|!js)9cs~9a z4&T?SadmQ*>V1TttGkP*KHmuXoz%EGIgy1GGP_Uqh2h#2g2>8tguPf zX`bMCQH`s!vyfkCLt$E>J-3nm%K8e*?*Q#d|4Lk4y$Jb*HW#K9+JAy~iK@Q7eOrQ` zLe#iJVF~!0YQgKRSc{KpDgK44qhH%o!DF?y8_tYYep;h8*DdRjfH82{KEDiOe<^~LOGIar7HbDdIfX8H)`Ceaj7cbeB(9z zNe4B)Y+k`L??_{uXs5=v+Lx*9U&khr&mN@4M*S*u);-(;6P(mIyKWhDAE7D!I5m;` zTBz~K1rT3@`C_SBWQx_YV3&eh2g z+F58rp&VgaVZOpPAS{=#EJ8a7?J2agurBKOW`M`|&bV!46rMez#s^wuK=`Q6_~d62 z`e(FJ3zVsMdR2FSd-U>$>ayjWHQM^6XwMm3$$p?>kduuy*7 zhYb3UwIljBK8gK~X2Ojb?Xiy0F+4IL3qpEX;+8>2aPf~Uh~H+0TgjJ_SUU$Y3tQro ztwFf?LN1tY)5mVk`!L#31}AF1;iZkXqU%FBO#PF@b$)qc(S<^=n00}BYkA?7CPmOS zC6b>#y&NaaD*^`>+P}y>aC>|axNHgKLnCHaDes}1MPPR7Fqe*=i>Id)LCt+9xyz3w zc>8A|G(CETU)i_{Ew>bc#6OmswpfRf`*QgGEtzXC+k_F`GWcNhnlH-Vf>O&|i0EU4 z+w=G1*D={}V1_B~{Tz&M_hiBEJ{G9C^)Qy?X2P{S?J#Uu82Z>{!tFyHaBXrpx@Bj; z57r46(?5qodmfG|hB|Qpe9qNwRcw3EyBH=eTf_JGZpA^N75IVoRxH_241@1`@uQoz zVLqL2$RDrfTi5yFa5~?(mbQXlp0*up(0*#;Jr92R><&yyE{5DC?tFOSPMjpAy%kL1 z57+L(uQf~lg}ca$q1z%CzNFDEw5Riyg$8rD(fXaZ`Fb(v9b3ppzS@CvNzY$8EBK<_ z+Yv~gANM@@cmuyGGX1&~!^(T!{MX4qtUI&_p7smkZ|fbzKkW-)!|Drs@$+D`Y9fJw z`)lCP-zV{eV;-zdt&eMGN8<^>szh)2!6S+J_RDGp6d#B=?!pw==obbNmUSGLN6dqrj# z^Z9O-^4`9f1v`yRQ52Yn=Vxbw{c~gNTX+@oq}edCFU{3Km(g)c4)p(Ngxwd%;5YYN zh%wN|*RRfE=gxT`S<(>ab))}Cd*s8cTD8%3LL|n`mVk?a2Hx9r62EE}!J08){PC{sL()U90t+FM+h+1?HK>ufRnzO#}YD)mOmVDjtHyHS$SKG^nj5zLP{z@lP((ImGJ zCM8F*t9Li!&saJ9=y9FR+_nYny2)VE>37WL;1;a2sQ@~@`phCSDL5uKAC9!rf$fKU zF`D*k$}%eT@t7rnk0Z5U**9Ozog#(w5rr&p&=zcGB8QEA99TRzKlWlay1s(EnGJj#xH0FZ7jUe=vOw>c;5&+xM4Ch}aCQpu zAMFJ(Yh2NPXBK!|YX`LgR-i>;HrQsjhOC2Yv2~MNDE-n5>S%c5{j8_Z)XoE1tsIC8 zf2gsrEW5nYK+nJd?z;@fj!$1e($yI-{>)&UkpB#PKh1);E`zF+_t5Yc;MjU5tZh1& z{v%C;646AsoI4ChoqY`r*N=q-;UlZ$yRyd7PnZpdx8>goq! zb;skMoj1TJXcycVG6g5npMsHY0pJ(zitbx(!khU!Vc7LaIC}40xO-&_?93d6{ufh# z@AQFt--cD;9~hPd7v}}Q!Yi)WEI0{PEe(L4&s=f&{v_zSIsitMx#EDpB>1!@09xs} z;d=ihc(yJ8%x&DzknlUgk0-fd&445@TN?m-z1+}dZxX~)+T2h#3_p+r7nTKpO`;q2 z4M~D#3j^TWdpG<=`Rcd_K*V=9d>)YmyPX2yyn#E$o=*ZkHUPGEa>uxIf zqeV&*6!ZyzsG;uI?OqbtjSqmP#M3V+3ARiRfL(g-csh>$lb#y@Ss&bR6WJtT3F(mP zhHuU$!4lHP{hS-#icSIp(%EL48`?)Df&Yd8Fm-XGxb!4QCj6tf8=g6x1cAg8NaYP8 zeR3)7rD9jSeYwIuK95~dOnI%QvYbG&`RHVjne73sPj09^SB-@_n=QT$-$waE*dcfH z+_;a(V>Uygi|pVhXyQegZSkErA<7obYUBDtJDh z3zObV#k#T2!T8Ti=oc{q+qu33@q($)=#?veh^2>%v?f8Z_Z<9_o(2O9$3xiDh4^b{ zI?VXp0}iBaN57Am;M|}+ME41#f5o%G&Cv`-8t=!B&2qv0upx|k6NHne=RtyBLzrNPMY%hS+lv38?M`)F@M@8gANq{zdc}Z_3%*_L< z(uS~lXE5%kwW3vtAt-JJ;W5n|NJuq?N&EnY7G!~Js5v~DybqUd%mlZ#9bw)@e;imV z1HS3nz@;WTvEjrwaH-Bn_!hnb-_J<{8((|)tUn)*NnQd=o&xTc?wI5L0{Wse#K@fS zQ2aCaWjGu5KAeV`hv}u01iJek;e-Xwk73!8m9Q&+3N~)=5W4HHhnr)Za6|e%XyxMz zTY5~xjE=WqN3kCm9(6{|Nb*}9H)OFl_F~O#CE#1wiq#DWL?_P@=tFlQPX)rf@D;6D$LZt$D1|4>N2LD+9~F zu*XS-YVGI0%LFB?1nQ=5VUAncU}4`Pcr^bCn_bHSA8c3i3^6Z)4@7q%`atr<*CYN3 z#Q!8h0eQ5B{B*c6CewNQrD2`e*)NT-?qvns(d@`vof_gMRKTjj_U!!q`j~%L0Zw(> zGVO8o&@V>;6A0HNY?7vcjdU+@!h`yF=8*!#l-7mPy4+Df3CR?FZG_8`6_E2+UTv?@ zI{EG@HaSNdQ(mj_+@___&|jDJUR(o5Z&E9w%K za|H}C>&AjhHE}SV6-WG7z>=Ru^MVy>EX=Ev&ayt#bz*)lS^VsN1st`Sz-qfZ;BAg6 zz&>d_YrpmeZy!$jC)=|L%f);^D4pAHaAc#e#PW5!DYoSBG@5*i$lyG4gLlhPcQD<=Qhvp{g#L!#!yXiV=7n`>PPx99t-bZLihbrTE`e7c zcd*;F%eifA35?3z%wmU1xTm}X+S_@vg-_q`K|K_J4OX(j8aKEZ#eY6{E@5l-nc=zs z87N*$SZ<&hF4HW8dDEY=;5Q90=%gHal)hwxPc_8$OXZ+9=nbO?XRK>12UwTEHV)E5 zhx;<9H#3)w^fkbM%`)gas(`g_&xnY{BJU5^3xb6jFizIJTi9f zd@CF_M+QS4$kAJ)rZjQLx(znLz2M$4h|v^194un}(0kb}XS=ghrlL&QZg zsGT5Xy>^;b>4U}$gQE9@85^)F%j7xt0-q#`IkaGsT|t%vnpieTWd zIA+zW0Xh~I!u#RZ*-eXvXu7EoHnMx{+t`Lx>PXlgM$jJ6;BXkzil~LoZHvKiKqTv{ zRi{dy`ghygKi%(yb`XvgLK_Ng{&&VVVSNefw7T(ASl9n_n{U&s0Ic;I zxo}%9KB~VT{dyS`P{00dG?P!AX8vdg66B786tdE!L9~TXIErFIn zdU$f?MUhaSna9%sJO<&D{^Qw;g&EK}u^*N>_hh3cXF|vJfUD=5u!gg;;L+Qjm^Q2q z8?`kXa(-Lm<-lT5d)lX49%_gC58f2H-OhvMMJ70J){!duRME3tE;#RRi{|Z;M6P@2 zJaecucHJ!#UC_*e_5*uk(wv6O;6?^q2<(eb=&jw_CK>c6L4Ta2+y-3E1lvP>(6R1Y z)+$(yYaB?2P1ZwDUmU}lYG=T%EramYjQdRTGy`fc?~jdV=dvchGhlywKip+sz%18f z!r8Tbamz$0TfQ$7mcH+UZAWIaQ(>79*sm{U$|S6GZYErEutRj0v&_bsF#TmejCd+x zd%`o|`k?{1?dv;szGDW2O&NsKdpu;zyJv#NFFVwwcaY4+WJ0?rJA{66Hfw7pERODr zpX_AJbZ{ob2il>rlbm@@$b>HQ>~PykIr}^y6HZ^W!{*)PY`Ik?9L=}GTCZg6>*!3F zGQ$q1dCJ-9;h7L*Z->@ia(295CWLOa!%n1Ik0qJVsJ$INnImUoNT$7+9lo9^XHO<& z!o`ku7%^YYEIl$|TnjrqMfuL`n+Z)e+2Pu`a`wqK6O2Rcu){bx>)tLCo@CmgMUIRW zZ_9)o7y9D3$uib?Je}>gvcqxCa^^TJ6J+D)EdkP@*U(JpGsX_nNVk4{GGW37J6ukA zHC~qqUh=*;y{??CBOA7T(idyqlCkwmGhum7U*un8ECw>6e4QP-FOahHyT$c;`qFw_z3t62B;-7u-X=gc`;Ys$_ zu*1VPR7Zr@5FXz{&R&rIr6zW`k@WXf>P&hbCp`}kP9z*jxEtl0Ncmb*z8guOSESGD z7#TZ3<*m`d4yRFh+Y?VD@$@C08l>BueRkMjvYf3V-K3BqB9|7c^_=9`-&CD zX2LGtKKRrvjeVv5a@fBQzPr?FGifmZ6x;y%R+s}rM%z=*io$-#NUzM??I{W;m#+>jG z=`eBi5Da9T^(7E+<|6BUDvashECf5+UtHc5%1U$9{8!S|^ihXOAfEW!5&!DLrLc?StROkX zM<|Aw)`7p`L)d}%LYP8WgRoGhP)_6gA`q{pH`1Kk*n+SkkWYWX)=ze4W*$Xw>vtO4 zW)7Org`gFk<Ut@Njn_e4H+2>*noX@7Gi8 z^nDrIp%uUekYCd7j*P7^JXl2^p`N4X6~bs5BcD7tz_eToVen5HV*&%&lf{LQb3)4I zvz=@d#dY5>ldvYkx3JihLU>c0%`$V>G1j;Un)CN8Yta%GJF*B;*1cx;>&#=X_7p*% zQ_tC%S8gmckmA6vNm*_2A$E=SHOjrokeY|$X3}0piJb_CZ&ASb8++N1SabG~*8kH= zcQC{DjaX5Z0=mB4%wBd^h~9lCZ0pUI^-mOGqf*e)UdeuU1<~%-rI1VO|I}-db1+tq)FS!NGfNH?J)PdC){QBkFjk9{nzD*Lx-x_b%j*|g3WnNFY*tK~C^NnkMC~Rp zIPNPN6;ld5u8(IwjQfe~j+H{*9eY+I{g3UcU8OK?t0UWLdD6DV%2EhAF^$a;_p#M? zEQO5S^oLD<|K3Zi%E9BDgJ@>`y3Eh696qlsvTgjpicKC}4li1T+m4O_=1Xyj3s(i& zE>0N4`b;VZY1l#AkLO3Soet$7Fa2iwuwXpvv{;SbFD(a147c6mK86`CEC)^3eYW!N z1K2`}U39ihu-!SOC)1u-4rLm(L`hl})YnLU>Mh&YKjT>Zv~uX58(|w*IEIB!E{B*2 z_iWdjjc1D;%b}iTlx^>NW7#iC`?Obz?G3B(%$W3PIV#Gwj{aEYK=fHlQ*0l09M4h+ zFP{-*`=iNNW<~hP#uVEzoyN1vgzLCP*?Jm`WvvL$_f4@~OmtzNZTO`O=0B>-nl0VT zv>KGd&w#HYf4|i%$E+M?*M2LyH)1~PZd(qC0db<>d(Ldym~xns6)4i}F_~R-DF;7o z2a(-=dv<9ql|8DRsFwYND)teMCqf%e7)<}KUUL+QuGq74*5#0LCrD&(HieC9Q4R)j z6veff$vWwjL!$%lMD98B*}@NHP~7H=$TocyYoA>Pb1&#HiIWf0eo+Q>rs~q4C4TJF z@)Bt9@jP3#VG8S)Qvw%Wo?$3>HIFFzM z&3GAjx@v<_+7;I84BfXa)P#%;SJ;YQGBDau146c4WMQr4@X|#C-qbqJYW9`GtCZg? z;!-r*SfdbZb}HBf&3Q~rdg^`4W_DNFvKKpwpsi&p%MoRX{y1j9sK#~>yxS*!dLK0w z+QDm`1U@+%fuj8pwr)Zm%pBGRP6qg}QPXlDyiF$3h+t``NJ0(HgAvyRz_zTzE62EwpR2m`&M}50O2M!O=31 zUFcE(E?N2@4miPbJETKS>;M?i!<_eTT!DuZ7V2DcSvnZL?+?0Bkz!%FPVK6o>k<9n z?sT|M<<*%P#p|_62UFrN+UU*4nx{iH$+tUZ%?n9R4Lv)!H6x0jt5ZSmOY}Ll)1fo* z-`U_@g-0m!)iSabwV$-lKy~ zv@gC;Yy(FFOZdFu8IY4E0{vzWxy@v?9OH)>@MTUfC_RwPof>9App!MQ6*bWOB<*>J zwS_*Pb#a}2E=(i4wZ3PJZjbW7F;gEV{I*1)oQC&l|L&{}2U}a?cZ&ju%GU(V4_)v! z#T86gR|A~Cc0${81#p|%($L-=@z;w2h@rN$t$`JuG?c;d4GJc8YlQs`<&gg@o1OXk zi|^}P2)T7rX}-$gMN5jH3-ytx$P_NLL;BQ0==S~z>vuVex1Jz}t|gglsl#`!=^=xb zON-b8qk33!NeYjszihqO3>&;DfED?F=pFM8D7shx8$W2kADd2i&94B?|E>X{`#YmU z&jM)FQH$PVu*O9%BvAZR8v+Rnb+8LB0*zyF?1JHK9#L2Xc|R_)ho;FqvrjS99)E^8 zYmq6Cs;TiB4?Xs&om{=W8G zSyTIP?nUt)Zw7B+O`nADS6T|lo#4yDJooW(3k9@w^JZF0cX2*i0jBz1EbPq|K4Y#L z@9C$2x5VQ{Jd0W>pq_&-v!Jwk+6w43bPKb46vDTEDuESNTUq^a;apNu0x#uTm^3rG zip()|#{O*gDppwT%UjG=fNif8Y}Bt!{PPkzuWr7KC6{chl5g-%H9gT=0loj?FQxPO zN;y8{%ZPrth}HNppPNK0AZ^}47MH!83)5ziFQbx2n3p%*K`5BJkbTWu&NoqPaQp5H z*`CFV`PZci2z|Yl#p}-ILiv*%)pViEA1>tM=(2{5dhO0fFH+-Aq-P~vM0quTyNt={ zpM;|I3J5yBf(`C7i}zcjravH?>n>f*7Pz_da`F+Zbn#>pUEKNc`D)yZ>`=+GbeRHL z_^)JsFWtGJuNpTdeY~!Du{qK1ypER|Pb6%)uJxC?bEAp-69rt3J!rXZSDpw_LLHUN- zFJsopv-yO5YTTRhy=JkRby?`nJt?nNvX#vIsymO_s>XLorZ~ilnICcIV@YNuu1_*G zMlWN>@66_1NzOOZ)hv$WoFe@zW!@oNNuNjZL$fKKD&C!!k^D-$pY*AebCdE?9P(m& z4!d(_%BvFBro5a+E@Qv%&gLhHzY_nV_^W)^2W-c{W4tNFa&Jq%$%bl&@DJ2alifMn zqj7-eW|Y9_f{G4C^L`1I2yP;BSVOlNQ6i_R6n68g`;@A-ay&X!`df^RZcX)tdx zKMzuSH3RS0IsEEoH5TUOby^OkiRtWD&&%BJhz$BU6tjk2_jvcdQn1q0fQP;k{&{l& zq+HX2Z_7UL2b~LmmuW+Q-xqFLB!OoUwILwl8{d3d0x^^7g7w4ieDp#IWS7;0W~JY` z@6UV?r!|B=9lvpTG|ksPbwPXnXKv|~4^12D!}6o$e8lfO80cXD?*|lfp=~#}%!idCMC4$Xa%HVwdL{db;pQUcK(>%n)rbA3S~ zfoooMzvQ;?tJ2};weV1xfWdbQpU5E$zYaw8SCZx zn7hWw!E|p1EAJg!#fCjQ4mj&AaZqkFtiQesfTl5)_Myln;FBmEY5|o-CM)lrT44I!S~rP z<);e3q|j8>LsXMaRbH zK?yU3sW#I^x7y~?{Xt6zUH>vZXiX02P`QrR@T?;LTAVtqP={fjIdE!KdzhdxUOanh zE@-W_fMijBTRFAEGV9i0Jk(p1yP`M!EJ8H9O}p*!c+@d_HD$LEv7ZFRT+CzD?pUBst}T?-s|Na zwiVjv>|u&szmd)&^>^F;raSe`+=|&%i=`s%C>acBqybC5m5TnfF#-&C+ z55>ZIxkdBWbQ*ttj=U?rMC0U)B0m-|F;<+_P62oO`mW{zqqr^I zU$6_h$?CMx5?dE5Ad=?jURR%2(R0r;HCRC-1U+gzo9d$N_suQ%K7nwMwU3{o*G|0S22fbz5|x`kQd zEflMuoO6{}i|!06=UF9>8R^i5=FJ)t-;0~SshBsFxHajZoM+=FXNjAUFTN6+l0M2g z@!W(gaTa0ayy>?;OZ@hZ8aI2O=9xtLDCggOX<1@(ijkkrr)VS3Nn|LUNRIoZRHS*y^oXW%C`~=+e4>pijknT-0Om5alh1xbztn{=qha~w@^)g_Corcz9U~zChtzBt7sU3G*ER_rQwk{UwuN1+A8q@a)4_sjApg8iQR=8&u?x}_Q zdf^`Y@6?yjw$-&a;aK#a8cYA%=Cyx!z80=$s#}K$*O`B3jr8BV{`^m^y@mV4>h_+( zeRp+xWZ@aY|7MT>PoH)CU!ENa&)ohu=Uu|FMR;B(9Dk}iGyG4Tc?!qU|I4%De|nDi z-^^dvMvxDPVm{woY5^{@)Obldsp^i^qMx1MCdK2$Pt<}p;%=ZlxCnaAD`X$W_kbSs zo>DjGM{ID@p73HbofkE{z&?JkfobG(eA#tBoBX3IY-42*v%!aj2X%%?SIVGXS9iAK zS9|E7Q4ZsVjbhS47U18p9J2Q_w*Fyj(4%#`@@|(h-`PXT!J&|`vjwdov}rjs&>PLB zt+1f8;WDUuz=b(Dw})nd^d3v*O7`b`M~LWE2I9_JS=PKRaQbv9B;7f{I``@ZT}x?B ze;>&@xZ6DE_wAqQT&PtsEG|+{Q?U zfcBem7)tmI;j53zVGYIKI(ZC+Nw>-&fzl4Aw1$c0s`%T*B(p<&xhnovnb+a#@8IBr zakRfSf>E~FP%mR+r8wb8(3AFoV4BBRsptp?_ z+*}Ocn8{SIYaoYN$LfG{xHHTeQV3R-H6ZfvOwe>EpZJqf);if04m!$V{wHn7b8>+f z9#SZut`Bu}r-6UD1ajN9ghG2qm~x8F6I|QCZ>tHg>2ogBv+4+@79-%7X%2ic=m8g^ z>>#-;6P9V&LH4|^AaS}4a=KHqA*ms_thxo0#`uGsdn0IY_a=Bl0CZ{62%cu&gw=$H z5?;US7VL8HhtB_lXTqhM;6wL}JQg>o!Y|Q&0v`u$fbdz_EVbc77*%sK)X$Z(t36Y| zW3C@;<6oGk>m9(uyFhBJ1wuJLOzuLd%T74Fp$2$vz7Lc8ZH2|3O4;`-4`KUbA2`%T z%I=pwSKUYJy74{psQ2PuSeWmulTV?=WlzZLp20FkJ%bdj| zyo1A@W8rN^Q5Agx&%A{<4IIFUVk`>2rGf0+3|L>9#bga$!3@PLnEg4O3H!3Je+l)m z*QFSt2K^!6V-1ivXG6mSJz-O5Ll}2F4`7=mJn%P#tnK-5$x)pHqw$QU-J{Y|;2QX~|leXu= z@{=8*wr&g1nUM`zEqXz#;s$Wbg5tr<`@{SGR_P-`InuClXzo6k<bQYLp=zw|j3$WctA8miE1!V=#pvmQ>u&P)K zCN@olWcg|^yQ&4dk3EK?^}J!TZ!M72x(~(uw!s2c=N}nwHyD?K0|xM}ft;-!S_)4W z?BZiKA?v)P6ozW~@pl)=M}DvrMj!L#y;~t$kWdQgX&d;K2V(Y~Vv{PQDdQ;pPHpGhu*b#*;F4k-B3U`dJ8f3UJHoasDPwXXZYl?rtsd3;--$o^0CF1 zaG%~_ENFCt2gG-Rf`!G9*8Mf#71k40@B;Wc#0YmBae&B{5;!);6z|`d0k1ssVfYXW zY>?{)9}Dwf?SXc9VeUNGwJ;B&4|l-5lb1lERUSn3>4ZLaR#qujd-pt8Pw#;gmMjC8 z{5&X{-X1l+%!jN6`QT_{iNRxL!I#<+c;an_2CZD6=z|0dGh3qbgDG%qp%lg})yE5~ z$Aj;tV$ePLnj7Ei30CBzT(l>Nr}}pU@KnGboeTV4U>oQ|WuNL3$!mZKgnuW0V)x^` z-j1g5+mhb7S{cfXrZ)zmJtL&_)&#wC@_z3Y5E0Oket_P~v zJhgEiJfk;KthQ~h!ZUwLKD0k@?wn5R?2v|gM>C<1e!FPU9&}66t zW&&Lrk!6P3|Cs<+ro-nwcECK6w<~R_eV5+kOT8k~vv1t@|U6nw9gE?Ng69pDA z5@3VOvF@!XaEv7S1an+Y^bUI^pjX=hdmo7cLyC=mH`)SAmPSDvFA0PkvcR~WB!}W9 z=CrfGgdI^Z#a9A8Kh4qXL=Sh$UkS|6-X)TkZ;ApG_YAiHIhkH@bhiql$ZjQQyqr)Wd zbFMiKAl!mvzByx#I>g`OFrB?i%yGrJC|Gtx0^eSkqg!kgoZK$~{d{v&5Z&EX0_RBo z2-07&n(!G5jJ2S&r1LA0ITnzdv6S!U#pXDT=BP(9+mZb8 zrRF$=@CUMa$vJb}Mz)d=kDuHe1E@VDlO3XL%&{-gO-Z-A%pBX0-ENcq+xA;ve^C_p zQeI~+T42xCQ6M8ZE6$taY~n8=oogqXqlibrP14i;tvOD-6a|M!&w3xt(Ka#)o>5*$ z3(e7h@@h%)wZI&^k^Cm4Tj?@$oJ6|SCA@ffh5dc0EQ4m6qlC&bnbL|q&C!~8Y7x%` z;;|>Zk@WdW`Y2jORcW_Q7bRdb#SG6}4ubk=5-|SU8XNlUg@@#i+dIz$L)mW7eO3Tr z+Rbrg+&1VEErmA|o1lFIU$`__2ItIlv249Jbk&lBi?lB8%32Gb8yA9mPfa`_Sqbh@ z6gNAsnAe`Z2qq*bAU^pLx18Y&52dBh|L1=0)n*dtT_}TA>%91nk)t4%VuL#omJ{xl zM}6P<5HB6?2nssq6b-)00~}mnw=TsI)z-p(UaR1^LIyK?)yFvv*TaG#6tnb77x!m- zL;6`Mn3OlcNH1SV{aFAYx3 zy9};ebmQ9w8bR0aGRQeLoj03i2%+(1u2-hu@dL1-)CeDt51YyQqW_}{$75U!Vmb@X@E zV8S*aY*)f|BCI1}y$IWb>PR z$_oBPKW0ns_7Hs~(MOGwf=>qxv}o~+Pw6j(we-K`u?DZWkVh!zC%s#^jCjrwk9@uq z=26<7l(r+i1r$Qqp!qXi&$UA4M8cOh7LZJB%$}EAC9jDgYWm-iBWqKjdhgL;Y8v0! zSB-^org;=Vu%`~TynC157+nBjz1pbQ_@s&s&ut5!?2`@}xj*8YCKkY|c{(=>MGp=wz>r&2JgvD4M6rmg}JFCp~;X z>&$NrYh&@7hA7nSw1(_o`3m)P`6PkF5*_T=NEfd(C;-hr+E|{{1k<_|z?J*8aMD*J z%yln-H~qEnbVPI9da3{{>}z78hA|FQ6hM-h1}>MGVDvyKG`9P}J1=UD8;(h#^O;Zl z;Wks8a-#@l(7W`XT-u>HvIwUCg@yVEZF1{t5!4P1=bP`g!|8g(5Op@354_i|S~({g z7t>sMjPFZmhr+ajJF4kIIYNFRkL9u=$XOl3+tf6{d%KEgtr^432vG!>a>)?%`?CFnlyc^KT!%%hTr*; zp9XmBxD64gHT?^4bVn@0Y^Mv@d-5J3|bgDFu&D-+9Xe z2AD|ii=H<8#cf74!MZJ^&~@t{zWr`vyjM>OcU?5l|5HO0+C*qWVcCWH{HMw&94o3D zPlV%uupj-M{wQo$|8!pyw(YuKWZ*>q3(T0(En&|43OtSQx#EiP2PQ^|OKH5dyQhPi zg&yKTJ){s;tc}AZ-NjeuN#V`~>UVdw#rqFQ;fb#n-f5qfQ2&k;n4=~d246@R-BJe2 zb!wnN+L{FWwK5ob?I&+HV_?GA+7)lND&^}PlEH2oPr7a!kT89U44OC5Kr7MAgidBM z7U$Y*4Nu)Gonx#}+lGolO2?$n_~^*_a=4hB`y#?zk~ z%6}`AbYa@b9V*^&J^fgd{}`;sLjJ}xOP~q;b203cxp-+v33Q-;E?SiI7OzO5_gG4U z_^CX5u}66c1k*nkhQXfV%!U-R@!Fp^s~I33NU=$s>7R>lucE|zttsw;{<&}(oFew= zs(^I*=VI9isaUA<3yP%-qkk^+o284F4pG2;`sZTO<2Z4ljWX6^4>xfP6(4O$XEOB9 z#W$_3;!ZzH;L(r++|YB5_~nxlcuxOZ+~q^WKBT9scNh;C*jel}s|14RY-gWkE3tGI z?T;qC;I8$K@gXDCIORbR1bi2B_Z6$T_oX5*&*FT~r)@lDe-T9OP2~1%{rTiYMew`c zb-woIex65n{pz{h;O6ZP@!#!>pgrE=&c{P|VL>4TO;6#;w~ughiZM&M_?Rd8gz<$E zwS4_6g)s8zWA3&+jISsD#)BX5PkWE@1id2IC%VT!cRa#hJ5mhl?3+A#%>N_ry`!R9 zmbg(w5fw#(V$O(yVotNW0Z{?P91#;>P8dK@%nAqs3K+TD7aItK;6g>(@be1f-HSF}=f@bUVR5pR1&< z>9<(yJs)-^xsoRB1{N{gi_L#liP!fqCe3zZzF*5})R}D7a@;A#uWxl;IX#Q=Rw(D! zz3u7x@uIfNnq3hpurHp4t6M_{J_%u_w2Yp_GoBsW2eYE*rS#e9Z;Yb>ENgEmZTD6Q zlK(iyJ`Th8)4omN#Tp-W@^cBDS>6n~1bQ;hM@_`+)4`vtI zRnR{+XS4e`UhJcwg05`(njLBD&02pcrw{)nH@RNFPurifgcUqd;Ge9FYT|mda+C*a zigUsUrT6T0D|hB(jN_esVs77E*_<|I^u+xyY_shFrdo-6w!&}hrPp2-igU{}o1bi; z>sEFO?Tf9I;M}scEc|7?&DCf#@+sy)%u#|x^0ll_Hty4&{A6eDJFp!R#M^$bBel*f zux}X+lYC(ZN27h@VA&%7z@j@HWHXe@>8C9<>|pIwp}cE3{q`@c_O0Ikh$Rn%t2K}p zWug*HwvP}_Ms7*dRzI2E8&6@AWo2~gk#DT_<3^zo<{2d&`OG%2oF|OOypOv5YTdJa zUm;J6-zO%qm@V`SDWk`wUof^yh1W5UW8?Dgtmg}7VfhT44`2UahaY(ehmR?vmUuTi zyA>cji8)Q#itSKl=F4?^0uy(^xgc2Y-9WZ z;rcZS%%9UXC)D5RQ*bl7!ThHEOd;p%@Z~ASc!v(&sg$gGmi5&Azhlvfdby@|N5~#g$Ff^2NVs~4Le8Ia`11o_hi`{JuK8n`KX&+ImOrlfYa)M) z^Vc$dKje=QexK)$5q`ho_Y?kj;g2JJ8{Nme>AJRi($0bL+mY|*Ke2Z6*GhhT_;LHE z=Q@7d@#kTFfA}ZXAb!8%_sR94$P*P4%uG(a5Z(`v&^xV9GOeIn!lGRgI;YiX_VvSg zVfWb*I(tAQQ=1enzj~2M)+fjKOX;^`wIR(r?GjS-?#s+`JCV9 z`D5g-&b^JzlZ}m|!cUlQlKPO1Ro}xl%aHHA;14$Nx(l0@QbF&3c*K?rb7$WJ@jU#c zr))&>A?CQMf@U;-&W!E6n7OHxI-UbAx|=)r4V2Pw<7eE61MbkRyOfTv$m62lyF*qh zDSaLx^%^?*earL;^di_6{N4#V3^>6_{@?#h?LumSB1DF4j4 zKkx>=O}{Ug2lp=>z7LONnA2VMncIQ-e4Xh_FpsZRg{>%xX<)y4yF%W30q&ERf98fA zz5sW(C@}w7zW!s(^$R|!&$MgeVZx&-dZcg!OF0q`orTEroJiQ-uJQ0AvWm|0AJ66v zJrB2ns%Yzwi7fU@9K1w)c(En3IT;I^aEVVpXGweydM*SUDV02|Bl+egFk)GDg<#DXOZjsd>SQTG%& zd>^WiqrT5m3-%rL`Tc?4rkM-t?+H>lxepwj6!?ZoeXI^UUIXiY#jp-H7EiuDKZg8g z`7z=9tZ$9?MV77P<_z?1P~Sfs74qq(^}cx^|9|zre6GX%XZiY#)vGZ(-94-6=lGZ0 z{gicM-fyj@>ugH6x$S}zmaVC#M|@@6u(l%-1=iJcfy)=}Q~aewokfUojJUh23X?Hk z{`a$&9IBD)`YZP~E+Mgce>JuFQq4^@v`9=iivKKb7IUkcY)ud?tJlB1cE51X9tGyx z+&!h5PPP5YxpXiTO7I^?AgST<%w`Dt&#$I%Qq1*a`mq}aq93E{I5}W zhtxy=L@sld0`ud>kAv;-`e*OWbt6ruDKOt3ep!6q_~o9L%6^q=72A~YeQ5PUA?N$U zm-C->!v8xq7u>nWAy*QgT~pu`je6gFnoT9k2PiOKhyQG2^=iycD4w-@^tl~8TlR{5 zF;L*rwZ-(Fb335@9x#g;#h3@z4%Q$(TT(=mQ9swJ1?*AATsCnJ@Dj9v*O~=%B>s2q zF<%3``{mOoOdndeY6oiv=g}2DgW#;FBMe1Ot@jg$f!pP7unlv}<2sCli8j5#rt3S} zvCkOj-9{fY_T|v@D;(VVJOom-b7;~+3TYl=VDLQ=O+}ulVa8*@Lb>=)A2M?la{u)? zG-Dlsi-p5s!}NEwTjFT2SLqL(#qVf#mysY|(;FuG=h9VGL!s%wZcy%=M^BzL1kINn z;NsSNYIeOpjP0)tX-f-epX@&1<=+;3uM|?Z@UC#gM-9RfM6@|_xZU8!!Qf{i+6(bj z#HU}1esNXh`#j}mschk%E8gA816ru1g)ovC~-A`L$;QnHd{pREHr_OYb;@_wTNoXGJ&^< z-=dxQ$Q5>{mnF2Z6w$YVCh%dNC78|-QPaI9uz0B@C?OuFYXYrpEaBvQ5uMV(1jfy` zgq#&38rI7M9xb*6M;j5XK_0ezJ4+DF6wx%~TN|;=651{l(Kw95T`VhZ5!yk1wlj#g zuM*M8$l(@+KF?Y!q7ZKkwl62agzX~w;juA{Xln_Z)`{rMJY$H|vjpdzB6<$_+0t8B z!pH?8+O^ggR+(Btw6Tb`5+UzdA4?dA_02>MG=FPLh@B;(9>|Rrf3=gm5&`BLAa89+XPtH3!>h>tuBa*O;j(9K6iy<)DznF3N@@e>@{y;Rc zS<2Busvq1P{@9t>U@qd%QTH?oXtPEAz`phkJ7|?hgLH?$wXh;Q%Y|dVcnpkuCTFhQ za;R}16PU193A7wVG``6=D0WZ-G%Z{ec{756`uS#~#`A z=S?$68>0?mFJ;rjzGm>`kQ(sk2mT!LpN#i^XTIXce?uDjWv2;by!KGX1Q$zXqyf8_~x z7jIMDfq1HW9pKZ30i zI{IiVQD-VdFcaUEe9jZ4WM$H`vxIuQzC>t0bb} z3Ag`C6@5D83dwnu%r)tR-?5D@lKac!Ii;x*I&@teS$g*r$B%i|CJDWEJeCaH5XN<% zAwgcp^T?MO$rbmOP?_iwaVfpdwLtE4|0h?7yXpfjSqs16Yh5K>2EXM7^_0-dldcf; zVWr$WO9>4hbCE>)eB;X9Bs6bz9GRq{LjIfe;>Yu!ZpVz-Ra7T3l1%ifVs&^(NF=d9 zthPZR=VOP_RW!>lmUM`#Wczih=$fPFaSvF*=oh?0aM(rS@VS&J<9GfJ{V$V+GsNsV z-mS9$+caZJ9Z7XY43qOj`C1lxj`w{V42U7U zzdmIYqhE z?WfFbLKR*8EQW~mGg<2%XtU-VVF$BVD8}us+a+=;`6U~C4|y;yT_JM!Y^Klf?xZeP zNnAlL+n!WOH?O@y5_c3b=bTEqbLB;nn^ek{;D7A{u5qN*#QHk^Zr}ee*YS5de!4HG z+YU?-Y6x;jP@w|nO{)1NUt-yxx-3`V#^gqN^>-*M{V|B<;`y<C9bD z0+*Tt#C9jjBfDS!c-WO(-zBGS^42Aup6X5v5Qi!iCc2OIB0)RkR5P`=P^jxmK5m!O zudk;HCl{U|T8K^BI|$XxLdh7!Ki|3w9~eZCqt0^LD)^YNy>lEnv|CP%#9=~}xNBtn ze&kw=ju6fsiaZWH-_Cj|eB;+8)L%|x!$XC=a6Je)iX51iJ%#$>NOB3Wr1@H5*Q8)l zdrVGWb(tVMv*9?odO}WT59=r#U3G+LV!Kq9WF(SFp2P^T&IRK{cJ3hAg*so(4;y1O z$d#n{$>}O(cfnoJ0W#UV{%&hq!@Hykc_!=bwywi`-;NxR(@hfv-0hYwBp2&j@W`IC zk98#~$j|xu;SsKAf;*|gTtb0Y1h+B8lW>dW^n8n(+|dm_WC!wL9x!>pO?Ey(HqVgb zneta$vreI87V=vTjVRy-wT~crv*c9op^WR4e1(|Lms3BR_Z(->2*2%GAvfl(UUJTM z+I12!9Q~1txs4a2$eIyyI_5+UH{$3iA{&kQj9;H}kx7BX#sqWjR^H}pPWzD~7T6YL z=eQ=m-b4p|u)7?{?MU??Vk~P@J6G;;jT`YUdQ_pJGK_q6$)-c*e!aAWe*c-FM;&TF;xnPhyT0yif2!2U4h;59+> z!jnYBS5Es}trhe%2_uudF9hN;meF`WDd?1?Iu?wF1&o6NYICn7Z(%XrACv@=v#v0zQi8|kwg$8 zr)jY_6Mn1-C-;Knl-poGx?9O9q7{hws;z&FQOyV=syH^UC^-rScMoeYpSQy~u!Trh zFw!lIw7n*$t~H&lborWn&>+ZS;iv)qe{7e=hw0 zef<9v{C|J^f4ltu*MHZ4=f?g~{wM$38~bM()1(FxJ7fx59@V3hyDG2=%9q<@3d8p3 z(dCGv%`$~wUG=Ct;xNNZp`(``&F`Yn(Z^?h%bO$qt=|%HogD|?hW1ze%YL1l?*qSF zzJ0zv-zHzbF+chC`F6y6D`EWgXUuZsWYT0|B{(*H$@+&(ARd;L;QQ<)8*_q^p>r#t zM-uLT80) zv#OxUu2lB)-bgaarV93#r?B8F#>hcg1%1DzvTG$~q+8D_m~MHW^)a4?Jc*SMF!nK< z&~^rCHdG3A|MU$eYm%tR3Y_I6fx7ci)3zpY8>1wUlzNtx4!O%&Wl6yJQ#dow&)`Zv zO5n$fFg9+@OKzox6k1*nWfv3jxG96B5I-fDO@8;DD>RkD*e*d#|B?zBvPfa`XKyLq z4;sWiTPc&T_^i5LFxwnm%^mn50pFh?%y4`$=k-hiBafeATf(1l-$Epyx;T=Jy`ILY z-6)6LSCwr39$zm0sRHxu^Zg$fTn6J-e`DwFd=fmqrofHaX-q#$y&O#Od|hF8nc#t} z3=;A`v(Q%6g4PWK4nVsAES z-(&91c`2+3_GJ1p2{$rH3Pv7>SmO8Q#Ku-p)`;g)(0y`<4O`NLummY6M|rUu%W^oa z04Xf7KEhl}?r>2KQaHWGk7b=W$33=?!t$9X*qoU`oQakc3U!0ofo~ohc`1S2?x$FK zh%?vvqy(x1BU$?KwH&{`sT#6hb#J-sP=mU!7@&~zb#yw&AmjKUHuI?;nW`;=u}!?# zMvY+dR!s)A7T(OUWf)2RDFqjmBP>c3PWX0~cb5Grw>FT$mS`{LI~Kp!43)v^pNClQ zUMGnE5ES2;^zuVE0Id)B+bIORXfAItn_`EAGVWBmTZ?{ED6|L^o+{y5@~LB2o# z$$012g&#wHO!#g3SNj9Mzwu-8Pmd{n%x8XleM+*hrF#(TSSEu5 zpHqdyB2Tg#Vi}~W-4ROE&agO?I~m>(ruRF`;$$)y!(xQDZbh;6wKC{&Gg!E(MKYZZ)o^#iCSlhLr&+IV)iAn~y|9K0Whc5r9nG-TOhY=Zhk!3n=&q3SZSwW`I-&0+5c~CL;!Lv`FvfZBH=f`w`Q=Y` zpR>T%5r-?}jp_4s^4HYszq)!3TwE2nG5ORTRlnjE@c0Tyk1KFva@T-*osUz`gWeSd zZcHvNl)$%b!-bo2W55H~&EL2&`P&}#ZFlR#Vc5+naAWeu+MOSNetYp_%a1ufKK#1# z>&5q(?+@Pxe*dxFSp6%uoJs_7?dn~K@rBg6^08QSl!2DGqil+?bs%7v#V6 ze?ELbZrxYl#_WvyR1J0K87zAwlOj#|pSUqQeEqE8di{eQ`jr3dmg_t@ukHBl%YT-y z&u@2r-{7||zYp;H2LD;UeZJ59dhuhzk0-w^`0dN@1N?r)_eXDheZSSQJ4Ws=R^Sg` zs$u)2rb4PWg$ryi{}addtM9jJPh$vQXUaH*yfJ;g&g9zaUwz&ueGidn*FRf_8Q?I`&^K2q>R^Z0u+77Z` zV}D7{5aD%i1#V0}(WhSLkEI!j6|oB3m^}Se^{;ugi_81bYvl^um^>KQ*}AoI!$@mF zhbeGl^2XYoFXunYZ)<)Z;I|h){`_{~$B-W%e%<-?>aw5&{7DPAkQu{nZBgJUODiBJ zDua#dSiz*b6u2>YRHo$D9{z!yADdXIz>Ue}SL=1suAXDZA1iQU^1yc$5Vbvp9c}W7 zakUEEnB1jjz0E@g9iT5!;Kt-$&FXdHj`RUTTtn;L#p-Zl@(&gj(8(!-DRasYfU)|G zl@5x3#WQ}}U^sJHf%!W8XZboGlj`-UN^juXnR8Yl=VQM9jf8SAT=R-;s`|{VpDA!- z^6f_TZSA)@nRS`}f5-g(&_JKpXZZbxufy*r{64^MUw+&1+l3!0(S0AqU~1F{YWm00 zN8iP;5qVl7dq&a19byP&ec?Ter9E$mVPIcf7-Snq6Ap=?5bvP29Un(!Zer*>tuNfw ziKDjmVp#3p7tZ9w(taB^YIz)ua}k42a9?QpHkQ&=Vt5_X7bZT6r8oS=Fe^qE-mHwH(SL~Hwm=uo zAilan3_Ifcg64x*yeB~n(O-4JZ(T^Ncs?_`K!-zZ(U zi~bx!|G$3Fg&C9MXbi^lOD@KIZXCUg?c1eP7b384B*%zhoCy2Lyg2#=WAY&dFVKUL_@?eth$hVlIQFZtqIVmP%!7rLWAC(wUA^j`&WE!v!n zzKumYYt)Lse&!(XJhz9c=_xS3Kezu`2x-ViR5Z|w>Y;uLav4n@?M^R`E`oC8GMduM zhuZ4PAS^C`dFr&GO(!TY-@e_vb+m|nFmg*uL=6UlSvx(!vJf*eh4wK%GJQ35NFqv`&e z!Bl&N6l#&9DK%S>Cvck4wROQev898E2sccG8)n@>d@M^kjW2KCj@lfiQ2 zwtBWyhXxi&VIbx|UexMAlf$KO1G%kc2IO$+K)FPx9CL_0%Y~U)oR=pT@Be#{`mGxBB zrwHPZ+sfgLBPCOdAlAqb>@=Jk#B(5ivr@Y0%W{t=6Mk$r9jS)74m(&t7eXI+Rl|oQ zXLh%v5p@Ve`Q2@-T-}7a#Z<$Kj4f>Lld<&J!)izad#1c`Je^ci4LNw%%2OXRI&`oc z3OQ?*r)EJrc9%ogCR=uEs5uS6{aZ8bRV=)X8MQ61hRmS#Omb&DoswP+D&HMhx1pxg zJiZ#1z;>2C&bWb{0Q5nP?PK%i&!j{o13!ZRworEg?Tl@)biqY7;Hn+9omBxU9!)^f zVmsZHUIuoLTEm?U`{?O*Ww833CVWtKp&5>)aQl6GxRLEfFPD|T#^6riEA^l!ca*?x zpRRCcgg5=vs|0#{?+$mfeQ0N#V`q-+1-qJC2l^>(Hw!Ye^pUBFNr z)5hi^ew+T)_4lP~>^X#Y4l z6yy#j{SfzbQJ2nGdDumI}a*X2|jDIaHS}R*{2L zb1EUX`_tn4)$s1PEg2O%kml{K1_R{yE&4o|ZqluWVC48szdDRM2go1v){mNO~OKmyaRW@uB>o)CS+z@`fxY_7;Y8Xm2@;M6ToeNBYxa)8z0BxsDg==u*=b zInbqM5vc=9 zCQVH(0#oFAO@E_Hr<^Z_G~{|+p`lL~;vUkmj_dW6A$@SF1iX>!wcz$(I;!>=bTqN2 zBee_3YwhQMVt&0k2fc;o$WPn3T0%TaUO^G^(^|TgkW*h@zyjo_weT!zPEXV9cl=_T<5u2un2i~J%<*O;qgzw^vZT>oL)q- z+CG8!@q6fs&m|3f+no9ox*#8K-lHN?VV?!>)g0;TVTBF!gPLZ*!%r?$ytJBpFn9pd zZEzhJ`Gb6&n+79Jc+-zos#MBSF&D&_?zpKzdl;vK$0{%S=y@~heC8n}PdrE$hkhdK zo@IdS)d6}cT|)T!dU2^RXss_D^oIt$8kq_|H~Z3Yr5g0f=~TG2&6m2UYSJ}fsjy?G zFJ04L6S)CX!E(1RU2CaH-y$|e{A0Z)^*xme4yY6Aqe!`Tq@|T_oYkZnv}be3Qdtq`AJ(XdMGg!b}#UyVFp?>EjbmUr~A_J*PyXZq3*Q!QGMnF=0@ed+LiTJ+w7ROq1ewV-eJKZh*?*V9{SEveV~m*6;h1?|SE(PkT7f!Pi_dS9sxoyT6oL9a!$ zTt|aCRK5YTYAgErzBb)4KO2;-X3=VgPW1fn97uRd@B#i|O70WpJcSoyHs5(H1AlA<0#R{`k3! zcHCP5-;{ok-s4u#Z|f>S_CQ9|)K)f#iH%1&3_jkR?oV1q6DE|wEx9^fX<$cVYD=K6 zM2Bt*T};8-SEyoYwAvmA;VIS`f1OmZTt$sDQgg2?Pp2#w&lZ*j4|}U8zZ{N zF$Z>zw4_OSedwcs+2FllHhn@n(p~{?KpJ6917>Sck?L#M5n@9JX{pl}vtPot_baHC zq!slX^&I>I?CH?t7F7FtCX~$EO4Glp(#w~hz^hif>G=+UDY(ALX^Zk*PNzG?XY zG-V#t_i7v3R=WmV&*+d2!L#YDQaKzg>p_N(oJj?b<>27fk1X9eje6ab!<{jPq}QIw zbbGWMbi9TThwzEC{b@N=#|$O@S>}|#-svZyyv0y5?6U`%aO8hwN3H>TP2BqKCu{{N!?G&YX@-#Cx)*Mfg%ZvS`Im%qBk{S#~Y|Jpu^zYpY( zFaCb=?;5`rf5_le(@m^hj(2k5kIh|@0&`XsP8Kx?7xy0 z?v{dmp^zM`SxzG!R)FroA~L1d3K;^ASW>g`}A2EwCz8Ow5U4CwK*vRvpX}1`pqqz z(qS3&OP@`&4~^hPJIf&EpcPTN*qlqXlR;_3BI2oYU+{9g3^b1{BPMEx1$_VeVq4!4 zEG2u_`3olOl!3Tt5&1Itp5WmT85sG`C!=3{6?kD;DuHuJ?&i*1(+e`Vlrf9kh?v9$ zfea$TXOb4So?H~Z3+z&xO%9jGbBp6;;ILvT$=1|qP{;XgWKh0hCpo$0DmPb(XV0#? zkf_KXoYGw>G#lhe>>hL?YtBj`)$j;WH_#(mcy6a{%26^;G?eh;^ZvCIL~>7Jwzw;i zD$773awTOin~@h?Wnf{nk61o>#U< zJ1v~}S60H~ZI4No%O+xbxDsqFpOg2SH(5=ufv^fV5Lrx)NIgmJjtc0$u$0XD;7eYvt$^$YWkhh)pXfPMz>Bmp;uRfA z4trHV?29t8(Jqv5t`)H8TNydhKaiCBRY2C+QsVR6k4(N&0U>(0_b>D!XDaYphdiIq zHf}_7cqKR|i^!75-NeGa5}vxhCNE5!NSjNQaQ((J64YWd(F>{om#b)J;;9DXnqOc3 z*yqROzZnO9xw0J+nDg@j8GLmm$?q(IfK>^^x7wa`xm*PiMR!QE*_(-X~UEj8EovuVz_lu3!J(>W$WH# z!^rg$pqy(C;xrMI-x>>ZTl{4CPjlev016HoHSGN7cQ7Y+6ihl$%2J2sfvnk3$Q_@{ zG_&*JSXh5>y8E16JzEI*vhI*M;*SPC@O|qi&j>mt@As^RB?IU9#aWV$84C?lc-|-(`ag^Xp%p9uHho5xl|tdYce4*tSOmhcUl?jg~o#iWR{v%&#Bf zI}XN2i=ZyQ-gL1UxUCj}1?H7&cC!F^2N68S{CX`bGl)vghAPajXC)@^aZ@%7!2EjK zreomcND&;v{CX#54!x&~zz*~4Jyb0qa*hbLV}AYJ?iLW@DT2D(`RDu0;fI9?hGI_r zA}tFrG7~`;%(V|tvVhBjMBs`!_}*FOpfytjHy4_~?H(4eZ>k8IV@`c3;`I|mFc|ah zLv<|R3&v*x=FWF%Zvn^WiNFu@|g;A<3un5bL}^Ew17^=B6x&3 z_^sMlK9!Q!z*WoX8y9oJG(b z^WwLDLcCT4r!ZeW<+eF~mlA<7=Gw<&U8?OxP?x_yT^;K?MFb}?hFR$I&B^Ek=H_2S zeA`q637Efc(a8d|(avGaH}7`K94vN-U_9p0&-!8xQ&4BeP7}C*Iy0yUQZVoSd|L}} zLZ8224*S42=HP_o#$s-}9hSQX?FVB{eI(j9L#%{25V1De$;RCFJhbz1jR+=TSy#av zK8_WEcU{gq%5#Va_F*pkR1FKTM*C4{e-GMUjrLv9{xr1TA8lU6ocg0^a}?sYh)*Cc zMLWyUPV>$dAVvFQ(0(A=&qw(Tl($BCGTI-4_P3z@S!n+#+CPT&-QSAfB64Dc$|+7;DCEF0J0aogY~CJ!(JEsSGp`0UVI-0iC4P7t!a4>6*dSU zrG0~Wqp=wNUGqteSvGve+<&*FTCgW78=9>#gGUQmg4?!iIHr!A0Mpxm%Tp;dx!Zx% z9P0$tYb7xD!Y**TLjgF#KIP^tXLZ z)-+LrmeJ)9`12JRq|_P?Ei8xDDI&5!O&t)Zj7wwA#`+;=@J?F7;dWq2P*8EO5#YXg7yex}YUgT19?BrUotoS0h%MXKe* z?`UV3RvP%fRhkF5??mPYHU)ltgulT3RWtZ}1>Z+xwSw&{nnUm-1vYvvgO+J$1aemu7@aMH0gH|ax}Q^q zs62fC(oYnWsQhFB#WMILZ^pG=^pOQ)S%t6f3Jwlv4yUoKVP#Q*<54OwB@y!%tnLej zjA#zdLKzHg5hHNApaKauWROc92uwybhry`RW@e0F%_S9RhjNRp4+P05&%u9-^OnU3 zicwyE9p4RI9tiSLejnv!t6~JrE~`Ku%8lJ02+B~-AG0DI8T5V9iX78z2iwQu`(WT_ zZvW%9uo&NAjkMo#1NXLuNOu_&gx=(Ky=w{E@V#<&g&${8s|vkt$>4RnIb70Hj7b`P z2e{auo3*cDeE9PTKZc?Bu6i@Wifj6&IV2pE!SJjA?)-=r$mt}5@Q=XF8`%oJO_agX z)7e~)v#sGwKN(mJ{KP>-TezemgU6RuNmwUsm{%@^R*N*qC?lN)W9PrwZ~v3AX_;OL zLjo@lyTQnRHNFb6e9jVwW-6eH=gEyNLPA8!)7Vz7;v9;r$?gRhH7}u#gb3(Pr*<0UO;vCF@nrcmw zt|>!yI_AoCA4A4}RDw+y=VL>Gtk6znc9SaLOXd?&rumj-nv{dQAeV&1)v)*lW#F}{ z68Tb8Van-Js1E-?HZIYD4QcpKFz+XM*t$Pl2`hosG9_v$)`#g%B~bXK39U6B0Bv+j zK(}8r>Yg+ZOz@1*sy~|JeP07%2%anZ=+u&iB@F=m3NZ{`-JHI9F%X>byhLtwQ)(AK z5V(jExVXOw-FeLbRG*YU#4;ti@_m1J`LP6IAO9e^5A{H4Oc|UyBqiPkt-*3sImF<1 zgP7Bw*xP9p@S%Su@vh8fS5D->6ipNQJR_WG>{MXB56vbQL8^5Jdh}pVFj-gtNv3`1 zej{zLkI92i-3;j$bL68p%Z2ZiBk0v8rR5d%ei~1uM9~Sa;_%_oD zOW^~yZxs;|y;FGhZ%GHbHZ_7&Z!H4X@qK8!QHRLbeFYHN)sQwlHIJ;#%7bg=Bj_F9 z_T=H_T+n^V(b`erT%QLDJHh?(V8x2jbm_29+|`@;;A=I6w&je;^J9hZ*1R9>JbD+| zjb|fIB6o$IFo4|aS_1R(v}vSn9O2t>GcE(;rOj!=M}_DTgpmDKYBrL~fs|0Mk$T7FC4GERt`O5KM?tGA2MQOIm|ElNi<8YknTF=knll?(!d*JFy?q#D=X6;R*6JEwha0V zZAR~y0@*pS47NXSP9Gwj9p4AL7(CB*>Lzjf>dGB2t%8crm&uliYq`P0B@i*?9Qm+p z1}DS4(;$;b((9oS=Tt0#&2GWOw7VgvwFUPlXgBQKNB4_0!;_p3m&%T4lak_)#p4)cZ65{WF$n_H42gP9h4ie79G-1(oDNHDL zBinYF3i$ps`9lgxhn>itUVDW$SyJdTdJ8dKv-Bbp?Yu1xVfzd+#vmf6mbogZjluE&8^?KqL8Z8WzVD9Je z^~7@bB_Ut`J)SuX!Mke{xl|#)EPqhQCt)70)8HM%@7z6MaH0Z_yQ9G4MN;VW)`849 zpCUBJI0S@mA*b^13MXNI==?8v4~(0}=51uwi8P@k74zwAx0AggX~L7Z2mX!iGZZ?G znDg7kXDjJ^`JS*7zPtU#ht5gC`L;7z)G|%DAKPyGzpy8+Wx5+2h>}W*@IW5M6Y{xW^u`jpVwg3B4aHuqW1KxT+J$QBD(%NBOKr zw)~#(C6@IkMmu#jOVH+IELR%nOj`Fz6N<6i-*_^XyI`^d8I+MMEJ6J`Y>2p3KqV9} z{eyhUElRlYu@Z(Qr4sjnCld=7;n=i8E|z0eiPy}fuqmvqnz>yod4S@(Y=u>q{)|3==`)9ed5-Gbc!zpP*tU&k^M;Djis>f zP7C_<;Q&JMJlhn9R&?VxLvl}E0=HVXrq>4yB8&EwKtQEBHQHxDBKns=m)4r}gyowe!ZMcv4twPIM|*q%xgwFp19lkbXQxNl(uckiS!Gg^?L*A zVf#!dXsf{d*rpp7!AH`I4k+{B-nT0Rn{qvRX!DaXk5&~xtJnJU&9d=Ae*BYz3n0cx zpSmpVDtx`W5L)l-OHJN95X?DT1hqqY(oX)t9KWodwfSKE&49MlYRyg;<%0p@o?8a7 z@XY*QzAbq43+v?82f#m^8d6 zjmSx5xlb#8jh)PkL2N(%!>Sucb(n9nNVOOww(Y6XV=>D-iuoN6G-0SO7d&iCLhevplUQ`&3kq=Qw*x^Eh%|e!`gHx0sACXnyevbZI|GF zSfWBj6Qpc=WC`@@(~NS?6|8DW8T=elO^gfDS(nIius!jPtci(d{P>77%0XY4L(YYr zXIGQT;NzSsGFzO?w%e9MyQWI?jWm~SjV^&jx0=z@*_CX~%o02w-JEWyma$^>5=e?@ zLEGa0i`9?B@N`xyS~coDGee)fs?_MMMeo_}9+*$@Or2(g%Gn0qj4o1N=_x-4#(Id{12G6 zoRP=tkFX1WNMPqpZ*nTYf%&$T!U~+17T2z3Jp@wNg!9sm^>z)~#TMtWXq@aebY|&vP-Q);+irgu#L8&Af?^P=-RBs z4g9n~E`{H6eqGL-s9zH+23xb3{q^f+9iHP>zi!TKKc6jMUB9-*Ub14>w<_=w{BBma z7T3w&U`*=P#E^I^w#QR}M{KHJLr)MZ*2(Xxo(}U!w1|II=A=Lua(DL ztl5pA`Zcr;JFlu=XA}2ZvCXJcx8~O2E?er?#M`b`tU3Btw{AXNX2p~aDR4XdXI-~$ z*6G~dSij~@9%se8P^WG!uEQ>9vu@oS6lBd9?%#f66D+rGoqf8^iaB9?e&c+{`Zbgu zv0@#MC~!F1uUm8HOt4~G&}Q9wcRI|P4M96~Ypdf{E0%zEe&Z~(Q@1`|@U>zK(9UoC z4So3iY%toaTU$kFQypXb+x{TLzvY{-th%-G+bL_-Iz)j7V!3r|Yt9xcb|1_Ajrsi{ z8~ebfb?b@Vt(DAXd;LC;r8zX{OHGa`F0qW4V;2p`Ug8 z;S8@m%o_VfDegae-`>IcdPrd^?mw?*IWfK+-MI>Vez`983jG^)3On9a5(r)6N+#FD zv3&jeXm5^S>fa@xtc&~Mw;^nA8!0$Wa3dzukF$q*QZU8+b6T}GE4Glr>=paS z=0djye)4@FhEf={avzyh?T+2Pmm--$_M?Z_YFf7cxKzqVfd)phXSS>ONa9^-#`U-x(IY5DJHjlI+T zJMW%<*E{k*{SD#2`AvrZo$5dNj?~z9F#h+q#=hPCUEdr3pZaFo{BafB3^`2nbRJb&fZXk zFl8N{=X@}UgatW)2sz~{4sb+ksRN9etthuUNT7cyA#<`EpqH}*=C_1Io~i94ailPYMDzLl5-?1A^Is-Q>rgG3s$54em_H*~!u5c5fHx z@v0m?jJ!kE6u7{KIc2abE}PJ57cj@~+xjm*l6cMq4yuUZWDiw(xMn}_;}eAcn(NMy zh9Wl+KUPMk>*KZ%<$N6j7mPEWBORdQ2?E4T@GR)PB2T!1cCO<&(sSp%z{OJn)A8)6 z&RTEKJ1YTm#2pdOLz^NzM>+#_-ky|z0H2M*XEP9w!E>Y++T-0)ymI+=S|m!KceWNW zf8*Q0ruFAnaIeWsIzM_11W81o`9?s=0XJARCl}rjL&|MG44oqLpxuYQG`iLoe3})& z*RS2^hvvuO>xM!IUf7<}gZ^*{a}y2(x1?q1ftceWhK{|P(EWFV;1Ayt2zw$Uo#q9@ zw}Zv-PTZWT_YDH~m_nF2QJbDr4gf1!0DCmL(q7TWp-3qo#!l%&SF}3{%`$W0(06^> zzNZhAG|8HvA z0w7L7Y+G&vDX4P_Crax8nngR?Ws_-%!@8v zGaLL5rbE_wH~QXd5_F1s0G0a>(4*02U{v<>S1w!k0b?PzY384pU#`US5iGs2osMX3 z3L+!S8*1T56S=W4eBKjis^LiO$ylg4{Rj@;+fL85G=;ahZ+_+a*~d?Y-Cq=#U)IFY z&tX}ni)XO!!wP!8cr5VeQvUqL_ou`4Y>*r>rK=XsMjJW6!ba2NAvTb{Jr7pj?oV5p zZ-yDK^I=qePg*c#JD4^p1j(mPRO`mB26bsZybz|Z>qO0zcEiCQ1@I%g2kq9z8Cs0b z2d!*fdQf#M*yZM8{`)|B^vinKT$TgE-lH++#s*pxWkaRDDRsItyU{VlAA|h)Z6}SnWz?5kYwAUZ= zV87iX@N(Nux#)RN^7bK|nX`|Ex?4fB0cjAu(w!b2yYL^MTi*7rgyBs?$N}d-n2Y~g zYg^qVgVlqfo4gd>%*!TEHv|KJUX9U{Ajhm3Y5nOKcuuW?IgfUdJNx|`%;$e~E#R*; z{66#FTz~(rKKWP2)W0*X`Sba|Gl%>y&!6sqeFl74_iKaURZ$f@UhB7xDKwUxiPJK7{HgnQame`3B(zHe2Y?|yNH1Vu%G?^y-r+gXj@ z{dysvhPdep*lk`3KaWPTC710Xqzu3Lhn-_rM>>KM<{;$yTw^^lx5K@gxCg6EX6nIv z!N3Vzd$GU@>SV~>F@&4+*`z2MBuKv3J22TI0$pH5?)yzk{#D5ca=_XizVKPA+iBLlVCJ4BWnx3#m)=p^HNpv|Et} zA^(TH^Ny-w+4eOCScqc8j2X;1udWs_C(IF8m@uH2v!bGs6+{exA_mMkU|L+eFY4+RPcg{O!-+RX!@4s)%F>BVWS+lCEyQ{0))TWS4;q<)9bJF|P zq>v)(sCI)F^z5xA#Xnz539&D!x^Ee>m4fO1yky!@@FD*+!HYcc-g(OJ)70q~-6(X~Y(8yk!DyeDsc7yu*1noeR~k6rXi=P?4dh z=tj$2R>%2M&3GEWwF$lTK0rqb#na2hO=#TI<9Xs=w01mglA6%b`A0}o=~>oUMpye? zq}?rZSzXtmP4RR&tUmp?d70icO(1$#n|!z4BJ-#O+WD;(O%2D~jO)VU`n5>b#?ZIl z3FL`$iuR4Yk;l(dM$ag^WG#C7@D?q2lt9I#T2y9SERE=&K&#Hyrs9upk#Ibo+G3xG zaqwjtaz243l*V~G+hWO4pFo#vttcugmc|`Qpz*D&sNvyQnzAE-#&or!*2iM$-nj%S zRUK#P?1`nglL=IzH_p#F9!oas5@?FI6&*SeOGEc3(2zi!H3YfyfduM|GjNWdg#NAs z>fgwUVh_YpdFXsyV@0=MbH~~QniOnB{h>c;eFDy7u_6w6+?E7Nyk$ifcf^uYWC9hA zwxXYVW63-qfuxI8^m2DB&PYn2Q-Ri0yLl|RE={23cGh%qVk{M1jPLg?t?A*?SQ-YN z<84i*+E{wxkwDc#t*KG{SUQTfc-69^g|OKnFoEiyw4#piZMSCvrKed@&-Jn75(fEQ zD`MMYX_j9C^~O0!0pMaj2~_bt+P)6PX!}SjE4qQUJH!4FC!8e(`zxTI>|;fN;B#p2Cd5Ah@t=dZxfQaeg)3ue zBy{FkSkn|=v@s%qhK{l#9ei+rojN)zN<-P+YZ9m-&a-NRJ}n5}hJ{+uRQPsC@eT3( zgnV;`onNqH4Lf__PZ<1p4u6c1C!L#M-}J#)8UmXmVKWmp8?R2F2e6}q9Ve7+U)Gw8 zP?p2D72(!2w00~-f%j~%rjgdMWH&AW-=kPl>87wh27QEcnY_xz(qZVlhfXc%sK=)B z>SuJTcMY1j7{`D2cuuc>RiSHs$EZWu7j*S~MH(G;h}KknNkTgd8k4b?YCU*KwTqOb z>tlA4;p!_|+uV%mhVG#GmWkxCvHVkRvOy!_F^Ml{qRB8zMNyzK#-qD0{Vf_21HB{+C3Jo7{oEvJa zqsklJP>@YJKkKrY5`15iZw(Ww^=TVT{qd4!UMWGY9e2}!jxT9NAq$#$Z70!i(g+JA;K?fXLKN?IU|xSLAiMDVd0dCH#B=gQUkYPq`XuCsVX;Wv*T zo;;1t-^M=4SF?GC=2K{4dMf?yGmSqCn@FA(Y2?ytJl|?Rf%Y^^qogPozPIssTHQH~ zZbUlsSzTT6-^Mh$Y=rkJA>-)P+%y_%*_XelGmd;#=km?zX%zNmD8G4T9QpT4qpG$e zx%FjNil~={ZQz-8hXhI!x#LGAB}WW-7T!v-k|}$u#42D$VXZmltU`m5x11 zrMl1O@s!kQB;dW$rf((qvx!~k3Em&&a49jHCyyOXQG;{2<~}?_*fgF`ux?I^gVU%r z*bRIL-@y%8I2CWdo6<1s&yPPoi`O-2Oh$NK@#qikxHgSiE}hE93wd?a>k#!?MO{`M z2X%bZzNvlA&(HkYtM*y#PkwDw+fmo6_D!8Le@C9E^HZJY{}bkof7klqA6eV{PhL-| z*T(d5tilI*n$ssPEWI z1Dmd}+3Q9!b?j?IE+uC(`!sxeQvElNe}M0h@tihv=TAOA-jhZ2N}>2N-}nz}KNh+< zg|3hM$fG+iXTby0X+iJJyvm0CtS;t_mf?~7=ZXES1>SGw$Zz1?<*t2^++CknM=j@t z)5#hC3VEKgk5x=bqha7@;QZvJo4%!}o9R4g%VsvU>|gWc?J3l0!Y3Z`WFwp2HicGi z{=vH!+`#JKUmF2c3Q%o)zx>-HnGD?vQRJJ|EJ#eI!Uc_KS+yXx&?K2s`k7FdJmAf`wMnM_SBz5Q`$TYS>cDw`d`*0D(xGhRde?ga`C zxZhdWz=(oN>4gw{i!^t(5fyoQS*V6KzD8~zjg1q|1|?Gh_%K+zBAKQ`XD0p`nzlNb zR-tU2l6s-l(q!5Ojw+@XN-s~Q_23HTdON7|*XOFfR%{-}LcxA$Kezv@`2{a5#$x{d1m$u9@g z<3c?)|L*aqo;Q;4PC+?$dXDD|K56wE+I3k&!4^I|Vb2@#N;9FrL4kbW?KiXp-zT|! zU&R;UJf&Bjg~`_?gioxIL|X?JqV%U>{Pff$GBPPZcM5Fag|1`I9{<7bQ3U^ty?KN1 zj~?4j8~L)mxpl4Uk}KbnltiNS86VEOS|^cZ z!NT;*Ka>wOyrGsM#?%vglOisI@0!q)%s}4h;2T=NHB|Gc54YX*hUQf@rI+m&b9G&6 ze{9brXZ-`{+x!T=aYu62KY$eGYqJ0Q^P$z3wtg1b9Q2?guQ)$fu4c7<%(t|xe>_Dv zRcPDj**Z7=Sb@d^q-qB&V84ysru?ty-um*w}ANL4xOd#-BW4WD$Y;;o+7F1 zQu|Y2|6AG?`Ir~qTv|V3)mz#QF8e2*H3H{`T~Fr~<}B8$_0{sLFO%uiuuuF;TDaZ} z-+M|SKlm1hD|(j_$&`Wb4p;dXl5heGt>|2cX6&|>+RRI$ioXhzY-}$*>VWsTy-lc% z%N*%di6nBJrXlY}>!r%+Z>SBfkM+xP>A~CVaWQq|6KQ#=Bx;?ip)bN=sjOWRz5a%8 z>?SUkO3h3n-34PjCv%Zf4kytOu`rFAsg;KONTR)c3et@hWhI9p$#meumXmXO%`D zI3F=q@;HjK;P_|0>f&r^5xzUVe(4)8bJttyHaMA#U;N@)?*(SMZ zl4-Mp5pDCAB()C}Y9-U`fksr`O)nj7jq!f-H*ZY4C1-pW95L$`7oEZ-H|&vKkot{Z zpXDP3VqKS!@sXE#Gbvx6A0NqX%eh~p_`(~xym@gleVLibAC_OnJA~)5TE98^u4s27 zdYd|nKRTa8&x-!$4K0`O=#(Uy6!e38-S_6VF=tL#f%D_d{PWnqfwu1o{>-mV^5>(g zB~v%UH$FDVmv{J*M44lL@(t^}c#juJ)aB7HZn|j+Z+#ncazP_{cix?ky_!VbhZ)ff zhZ$V$XF+{3&8%VIkthB0_`Lm2GR^u!{_4wHiXVEFA8g>sTjTsah36LEEBThmW<{=^ zKjT)U(pb!0MVbe5^&G3NOKo3mM_rdXC;#qilX@)tSB`!4yriDH{_c5OeT`6GYo==P zom9IBKIhALUKaa6YHZxZ<*!qCebY1=w>XkFxIB~hdzMPh@3!;mW9M@9wX74KZ$zA0 z$GQ&2Tt?kLD-W#?$Zk1?|?f${0{G2 zoCEkU|H)iyf^XQDE#nnt59d$IrW42h^!;}IxjNq_;JwUrr$}!5eFY!i8sEkD-@uC% z3E;xiG&)f&ly~jt$Db}wBjd<5+`-5vPu}J?*Zm!HlzKk=SLTQO#KgZVTP)QTajxda8<0iCmoF87gqI^DqwGalJQ-BVM9mh zcZW=xv6qC)eME7Kb1sj@|8bQ6u=w(xO)_c}AF*xYZ()xSsKSwY|g# zpEGE5NJk#VJVo;tC>!357d2igs_W|Qnrla0*Z!Xwbl9~U?^t1}=v^$6UX<+2n|)p? zzO9o<4ez$&6Fzy054vVjNbi=s+h#9ua9k$NSN|ehTev)rZ(lNUUGD+9q zm(UdFb+@UVNdr@GzQN9}qFbw6d7ND)jd_RF66EUqtcw4I9cgz*cz`qf6A-tUlxKqc zvz=JHN+uQEW)S+^wG~||WKzN1-vr0@9Yl3q>fBb>RiQ;DX*z!sepTuqeufVp!ZL+U z&UWH-+f1rfT#qVBkG)2j|Fv(sq^_?$y;^KsPjSH zzv_Nh_t(Lj2Kuu9zOeGZcHTcZm!I}Y&zd*Jg;g3p|9Qm!)J_%d#5drK%^X(isLM8Mk*y<(x4F9PonE#J?5bxO|9{!i8{-=~t=&g9{_ay6^rNRc zKG-0vZ?%#8UdP3u?GwL9>p<4s?u~UtoQ~TzU)siml9n0c4_7#M-BiD`3SSC0E=bJt3k-%OP z-ZkTVv-6*yvixGw5qlLBopaFXhxgq|+50Hl09*!V20FuL@`k5Wtyvec?RbKD)Qu+} zpH9>^DTZ~+j3>*P?aApwGMimJfwt)FXx8&owtGVYbzNXXy;IXz;o}LUf6|UppW)no zm7i++zpzJQJ_Tx;s&1nYK%Q1n9POv3z_MQ!$j~MQ@pgfPs3i6TDDXL_CL8L;D5WebjIjCYvG(g-8^im^KS#&Iu`p|`q|P> z)K$ z3~Vg)6BgJ~8f<#a!rqBPHuU&?Iy>c?K-Y2Z-+=B0Rs#G3=OTWyH?S1&V#vpJLt9Wb z3T2BHc+W1uhj94N6Fxjud;@m@+rWq8@ZmOmD2lkPHnOF{*9@#FbnJfGP?rk^b`gE| z6Y`UgUmTx6b>G=g$W{Y;44+HFXXAMWHUvIjUSmu1;j=I5jX=GXQ12VWa2wh?8twfE z-zLGgM(|BNN2%woFT0=8;|ZOpk?$~8L>EuyN9|}qpN=dPb#*K&(&V-cn11LpsxGyr zv|nYJ%Yx_BBc>@uPAZ2b@!iUY5T>`k%f}Z?qyB}~v$0KY@fmkg$^8CCcKp&c{&;OF z%|Knng0J#{j=A-=b=i5@yJ~ln=I^R$L{=^+(3%bYheXnp<)r}*pn)!Xc_{lpe zS|*AO9sGzV;vK4?$Q7ZLncaWuge8Hcz#2zHKJ?x8fB3H*&-9~lWm()t7 z^{aQY#Hd8RsbDJITeXiZYxSB}zlUe_PY$u8_nz?@=ibr8TSwSa^C$f7`FGT|bQHUJ z?g6*I{f=&TKf+#jxXZWwc!&Q`9Avf)Ztso^d*Z}m|jC@PJX*4oC_-Z~;!KEd};b2qcZ4#x!J-)Z!FU<7kNED1|m zq|=&HVXRB|HQ__=bSjAR%S-6v1&g8SG`@BSt6t9_*kK<+u?HcnYv3c172-M8S;J zZ-Ch1gq`B zg}PE2{)@PU9rQaYYzf47ZS}S@)7T?It1)The0LY~?|n>2?Ew8xd)c&$lF+|&8r}3i z#LAqzCj9(~ecDHku-~ciLLtm2Pb)>S{mur#-wglH8h3;xAO9r`Z<$8cqYg5M$3@sf zJSQBtbPs#;D!Yw2{rmrN8*}<`axDYRS!yqt``J-Rn_TXJe?8m#9MzgWtxiwE40J8Z zN*mU=2KLq(=+5MdZ4-D6s<_rbnlr}wlD}%wGyM1Y=N>1UwO8dvqFaDH8r zMF#RXP*4inRgZSe!2b^7DoT$pHl!2dp<~fNTAS2_*5f|6!0xuv?S3ujHSVtuyy`0L zdZDG2@Mo5Ttu$lnS+LN?wizI{2cTRJVUa8tsaE+W~L&0iEiS=`;f! zetu9Ncf*=~&BFcZlEwNl&e;3wZlFSMPMo~48UHd|Xdo{iw>I4qYLG2_tAG1v+ui+Y z&@sq6zn-q$^Q}5f#<_yZKj@cl5$IEQoN1XJBJ9S#@Y*^9MQjTYqDI%JhVXxWrKQ5u z?saGb>b+o?F7)-crpEY3Lu+A#;AoBigL)gN=vu8{H@GIbBR+?>78TlyHAo#>r#S{H zd-$uibwY@X* zv~dK^^vID%J-~SyOFjy%3bv#{8M!U$r}GmZ1$h zaL#IPtuSwD8EU!CK;`aF5~kZ(&_sU&eZ9Ft=(M6Nxy?0@VB?@uv%Ltj}HYl7^vp>+1f#4%1{&V-tFCvooH@BPNB$i%Zd8)tICq` z3Y-&L@QyTk{ZTa(nc59uQpx!QM@{JA84S!cwcGn zl3HZj88O+gT3S`N4(Xa>JSJ|GPS`c1jW~<7>&~qb^J+rhsu*bAwH?yu8_h}GM-gpv z<(~ZvJDv+td3N*1I$fj)ho*|w`xhR#Eter>(htXmm6Rx|rq z*@i=PX$YD=l00vvOmjFr7^j@)_`+9OGwh$3wG3|D9-=Ks##7xh?Ek5ly+SLgFT`%Y8+&NsjJr0V?%>U|69Js$tAy&3BLB#LTfsXS@s9#IQ+t!FCF1e{7RK?mwnK(6MA@m}nACsTRuIlZVZ`vb=@bRTId-<@_&jC?hfO>;4o zpSWBS75SF|*>bhcJg?&HsH>^W&t1%;qsU#HvgK+X0{O5Rrn0BkO;KHTQRGtLxQD6y zphT>gTx+FZKF?IX16~OEnCaQ_H3drv@>El~vhJ#=)>q_i@Kcei^_M?frq7WpoKse< zueLd7FOzcWS_sbZCqFx78vWL%%`ug$thpi1+Bf(=^wnh*d5%rBeYIR&_Ez|3DHCmf z;eJzW?Jr9w7MRK&CvS;2Adj4wEpJxnzO;X)soY3=OSIp*Lpn0oR4!;8BX)81la9_e zmHURoh$RE3OUK+z<+bNy#21Hrq-5x%hR2A76Guv|Vbk()jOgJzS$d1QYFv#Gryg^V zUM)10Pko9JyTv<5E6^^>k1=A+Xb0)sEK|8Zil#HRDbUj8~*uq(w4Lh#SW5iW9 z!zDM=yCXhEG-ksjALtZ(79%d$uak~~O7}4I?Ng4v5XG5;}J$RBRJhsCmlvvBlsU&N+;QXD}c9E(MdC* z(;WP|oKA{`ye0UMxlVF`&8FZ>O?A>ca09Tes!j@oeMR4~gih-82hW1dNN@|tOE8_Z z0zTIUx9FymMnhf=JVe$>HzBVI-l5k?4N;c`_;i#`8jSc91s6K4lk}*|8vH3*C+VQy z47}-#PU;G|0Nx5aNhqt>Yz>_XV8yrc(3uTZeAouQi*^kFw}Z`*;AvoE$WKFO7&r-B z2;39AThRwA_O18oq#~&I1$g>So%8`^Gr>Ji>ZC{TVGB6ZTPGDn|IU6DBgTj7q)8~- z9NbBVI6&X@HR3i+C#9n8ryxJ)q>~ALFu}iH--FAP z*Ga=ruhOoDh^;ADX}d9EavrRVogIjqgf`X%F9O#DE3sV$Zi%+k1D^+fhg^xX4_KM& zly;o}Plg>uz5rYS`igu$_#jxZ6Nd4tvnT3RY{n!0 z7cg)40(S$ShrAUy6>NgGbOi5)z9Zz56o%Xec9bzI9@9xakRJgn{kRcwr5~#zuTsGN zU_JUG9lQwKMbb&H!E3<>)?m&=SzGk)OW1h~`2ooHzH*XIqE9y|u&qffVkw?eM8cNAiK z8LW(j3y{ACE3s1g`ZDyD{+a`}K%XjcRyg7hR>s<1u+oqI;Ok%|{z|{pM*k}M^T1pF z=y#=Tee{bWSMuaL7O$|^chf9TYKZ^{@^`aKTvZD3`7*a8j#EB?EK8-o=; zmw^4iia!D1U0}s#82IQPe7_~yj`%3`POh$#q9IqtehYuhIgl3yYtX-eV5Qy=^y45Yz16;euWjIRy;6!kBNraV>oa0sl}X@&6{0z1mJSm}$S$N{A#;+Ni|b4}9PcUI^X+ zR_Y4ITEYT;D%WLmT$?!L$~>?iEP)j}o7Z8^fldMNXpE88U~}+v#IPQ?4Y)VPloJ1P z-~#9)OURXZwckEn);i}Y_z3jhLZ?4?J~#=i%+*c7%6Qa)qrG%eWyE$q`l9L-om3rs z2|RmLhMUUEA6?9d2k@x!<~*7i+YFXiz^_joop>5O^lqF$_&?#KJ#-e*{P zR2E0#en;WN(>wW2$fL_1&EhYRE1aKxnK_4fhpJeIjN24>(MhaqDo=FS zlcnDl_l7zAS9TQrt3Nby^27~U`j%#<|G_zS?s#qHPs-u`vHUJ^Tu32``M z%)@w3++$|E-yv=-6UrZyGL@IcZ5QjU4COP5VJ$RetJtPaC~sP$S!I^byrIlh^q2dbc$47$ZM1=qSEXxvr7lMEQsr7yS5h*bLq3 zEf&1$!W+xbN%9b@G;!ji2=<$Kh!%I8dE!}(Y@4!3j6X1(n?-BnZKXWKUS`XA#!Zdv zJk>|68@h}~!k;+iBQDN#=B-a@}QNc%ye!q-wg8b7kAMqx13LqwL=J|+)n=a!S&@qON z8+7(S=LU2>HU1<`zp9b%J@F9LF<0a@P?sWab?lQgOpiWVJvEEX_hqwMM{P%~f6(Ko z)cv?do)J4qd{J|mboZ!69_KkxWD{+qvimi1ioaVPn{^i-mA>rK$aA2-r`9sbbEih0 z1bqj4FQF9lTlu(&;Rmh=I_Nlbo`ieM4?@X38u`Vw$zoDwaaIGqUEDr3i)X-Rg$qJ| z|1pg`5c*GBeGo>T(8vkUU-HGARYe=GKk~@psfdHZ`Pr%PR%D0HYvh}KJw=5J-p=Oy z?5OqKe@|umkxQN97v(8CX8I~tDorD&W4xGo`mz=&8u_u+3bE`dZ#E%GBR3lwC|>Th zjPVy5S$kud=+SQ_n~$6~w)YdOI(f5Rk2G?fp8=xQ)0^2rXG`}$(MR-Vcb{tHzGVZ& z5NB_u!}yxqEKr;exgh~LSu{{QI|BdofIQ-LfOu@0H}i_u$amuc#9@x!?Aa@g%$o#? zY0R5BKqt6#pm-Bp`K3m#S1M49XovsjfajP7il63svr(wG`t1O533&4}jT{XgHP4$J zK-u(|05R;PKWh&@{cV{jkMd>}P`2u;0P)6hAI2eX;}9SQIe4=(uaW1d_X_Iz0iEe3 z1I4T0iSVZ!_y_781U{e%6wP7(HtPKz8z2fU-pmjB(JuqU9y7g}DdeZ_2Z-_DWN=4t zGwAn%Z;Rp25O9#910Ddr1dakLHd}&6fIp%w+rfRo?$gm;uqNyb*qG0}ljy z&Gu$f!3Dv`pwk@s)xpcBX8Y+0c0j*Zh0YAHHRK*(Kk&yX+3{Hhjt7T9z8qW?ToZQu z!6PSov!;+gxP=&k1HeNd?*c9kHUiHCw+BZv91h+Mb^)&d9|Dg9`-1O)=Yrk9 ziQvUx9k>+QH5xn{@ox=3HQ+@z1H@b4df?h%E3`!m{sf)A;11w;@PYe2%mVyC2oRma zeb_Jf|E523rkHP5o|Lx^5Qlg4Wj`U`Q#?Stjy^hrK8i&jm9z0?fnay!TQcH#5@TxW zUE~1zGqbKR6xS2W1tx zIdqQw!S~T$CsDQvtnYNq3AGoJjZ$_lP3UuCPdWtsF zw372Bja<^xOFXn8NYY`=VCL#A_SzjSRm56i@fNHlY|^D5tTD1f|fH-@rDKCiJm>A$MdS1RMO~(9x)7)3Q@8By9 z$8}+OJ8!Yjl4{cEyBfKOlb5)&U~_$M_|qrBQ_MIVsI3YvcGXjSHB2j91HUitC7SnM zBMiVAKK^MPXg#)0fqI_A%amE!DmquIz$8u`cC)nfbLX>2(9ea?vx@sg`Miz;j? z|N6B~Y*u^;bHZBp=)?$dyvI^j5bM&xA2x~A*9Nm!gK+OQ;EeeC)G9W@0ry02PK*2P zS1=FUgA6$-i|Y3s`MuZ3?>$A^efxzB+ymAOj`>gDO{m{BiZ!7TE0AEFxK8Nr}Et6sPA9?e2?>AdEfC@_W~=H z?&FQo@8JtV@?HP`yVmFb*?Ki+jhf$jQoa7<+skR6aa?mR<4osWv-QzualQUJSA07E zmfjWX`LX3@Z4^WMwlOT;PD+?hA#y(!}t=UE@B*O@i2 z@A5I`oKt64iK~oHvZdc}FEcSrY>)StH*imP`(U`}f`78jEMzM8nY2N?cX~e?tud9S zG~Jl*ds6j#PxbrI{N8D5or-A*<9dSWIni#&JAIk{c$OG;R=j`SOFGyG&k23bh)!Ft zN_TtW8Q_i6V(Ca@?%oCSfU7Kqn%3fbY)$1JPLkL!R^*%8;926?(Dw{tNf8&hK}NS9LS^J=~{f9*fK~->R=uyJjw7qbiunZ7=Q; z*`|4{MlC$cTDxDYB2Q$|c!scZ+F@~4C1+;c0{8FHN5v*RdoUvb`5Q`v+$<@xX?xc8}$!jg_!@Q6n6Gb51& z#FysQ^`Rp_W9=?j@Q$$GXw74G+N%OLx7NsAHa%e7KU(scwKQ_f*}Lp$Xl?FMLnB|Y zi)9aMHRqGzzh>wyR=4*A{vA3^H$P_|28`z^4YB5ldd+r@9m_3IZ|N<`%&Foip3xNZ zWb!*UuJKUb9zIto`kuKz@5#NFWPxMIfHLwbeZhnt^s@*V&YakgE=KR z@E!2e+|R&%E+56`!iUVw@7Ssit~?aJIn8^+eyp|OQUg2>nUKz2)^5SiAhxmirfhj~ z1Kt3<9p9Rb`fAPXPC@k^);}uo3+OM$i7(ihHfpPhntqiJ+kgTdt%?5pF}>qEqIrW4YT3JEwP?)y2ET+x8NmU-#zIL z8?R}|4}yPb?y-<+wRt3bI3nF=jz(2^U$pU-&tq1qKxJMT{nFd_8QXckGWS9}>%_fc z74=p5n8q5pc&jAVr9d725b@j__Kqb9&3Q%id&s@CJoT3A*n{taKh+ZNFh{3;yd(1S z@b|mS+~B}t;q#z#57@&`!+8_rr*(lRY*V{YJRZIk9r~PoJ~Et7f~a6j|LF1Z@5&{0o*y;onU((yk^j3#_UFbJ7uUwd zuwrM2;`t|X{zohmPK@Lg(Z6kz@3F<7#_@89=irWy|3~EHzmgjdR}SaxF-CsGC$cLp zPW&_4`#UX}?U^uupGH2|R8M8&u6O4W+Wzo)8k@-Kvfz=%^08JcNZ}Wgv)N)}AUoq| zEEn$(ObVBF&1OZXn3J*WUOhNV-x=~8{wq7@$_-)NhZ@U2b*o6>^<%O*KRb%f(*DMB z;mkEz`gexs@?Y5*d8Q+))W=wEHZO#hU+T!*bjGqHSZ(K1ct2JhI^$<&%X4gcZSBWq zK>zcskgT>0bvBmmN`#Pm#}=$VIJs0_n~KkxzS%nJdS4cA&0fR)imKUma&(-bKLh%o zABN?zzrFl$_N||>O!dR)%qB-xc8IaO|4A6lr2(w+U}O1?{W@~&V9zcMGM0NxUq>GG zJF&j7@2gu!?d|N@>~6+#U&y_oe+3)|eNChzyU^WOo(elkfBEz_mUTP?XX*#CIP{k@ z_+E*HY;;f9u?(l^j$Uj?XJa|z!Fu|>-IwXQ7|Yf!>#1d{eBfuaa^k7&>JT+v7z-vh>HJzjFAm?0DXu z&!(U)`>TY}>znggG}@xDQdf?h?|YZBP zSaSyZ4nJ!pgi=J;No;yAWBG0CP-<~<0<%R9ym3W))p1bypvcv+%CY~?=8rl*rzVYO zI{08Nt|#qK7gh`X{-N8tJh{}a+zhr6F=_W?{Xd;o>ReUlhBDUF^GVK}^XK^_XRc6> z@qcz~?k?DZjYTd6CWQT8^+isc^Thv8`TSQo=G18RiNc8{=--8`{pD#V24!ZmA}{m6 zL>_*kEBpP9=?{SKJnPPEh0Xc_4^3qIi+z|wnG5Th-GTPDkLbe=eu&amNj8!D zO&`jfN6K2iw=ONDh*pz$qwPz9kG7WmLEgmnlFA&>4zx%U*rqNn0>>oPPgW0?KY8_$! z_^*!a=#<2^6=jUqfOOL-b7s|rrR)&qAm43A%E1uj!mh*R^J=?p|Ks=Gk8O=UTEhNREUshU8Vh5Xk z&|gM;+%0A@`90T%A%Di!S;RUH>8~I4(L|otbt&t8Z`z42=_c~M&YrArSR;L>Bole` z)}^fDrFD7{eYf@MVrI7FfxaQy(z*G3Hh#ko{VDiqym%U$vCKrWM|&5^uB_WBjr9E~ za%uVq=KZaZ^c=ajB4sFZx$;?W`p86n*SkNf?iQ^tjaa20>B_d3nX4ak4?Mp;Yw7*` zWawQJ**eCC-Klh@wL7@NWE*zAOlR#t=#-en*CihKb^6tbA`Sus~qwMM99oVQZ^93i!&1!XKPMrdUtI%KDr3VW+9V+ZZKbn8& z%gT3(5RSs%L<#6Kq-vCBZ(pCd~FNDtJKux1&4rPe{s{xwxJ#jelK<@kX0Ul(B7`;Q_g46qa3%P^4Ea#z^=LM}(k3Ai^(OFA^>x-@bZwW*H4!1S{}Vn~to0QVXFeIDK44HnL$+;XLxN zlzDd+RIQh=A7%X;*|RA_rV35b_7C5Cv4=;!g%z-W=2?ICv}mBP5^dC%a%9Ci1PQ(v zza1)#WX(GV2shy8+j|q)&)o}zW|&XnM$Tep_xcDXXjcW-xh$<=FQI>2wtbJweT03e zSCN|ypCQx-&kvc+%u;=XYv>E_1Jl^CQ-OkvJRI470!tejB%H>Woz>KZSr1<>c%o0^ z!iO+3!#tq@`g&`dJ}i&TeCiz^T~D|RA1r_MV#D{A5Sk)~6QA~HF6#>lBIbc7%^cZ+ z*}t`IQP&Ckk?f#@MwpJV{PE#L_GD@;;U?l%-+oq}SamdOB>14c?N`la<_@I=EA-vB z@M-K!!@@!h#ANcg3Ctnkx3&TLP8{XJS`9ZA-e5e=IW&az39l~rAkMcM_hCjpLE3?s z1GfZuuxWc`ZF9tJiS@iZd8HoLLw6L_4#RjKW4HAGkMaMaF`g&K{!MwS9vA+iTu2N=sU z-DZ=*gVtqpes&a{Jxh({epeS|>3dLNN*wZw+dpC_ zN9WIWa{5T|M;*7E*#0?gIWd`B)kw0lG?6Ptq;Q3U>*aECRa~PVzs`~i4YS$BORLS% zS6Ho|BUjsL`cbE~g#G0Ky+kfQEsblj z+jp+W8&}U|wT`-Mj(!c_gIZVEe6u`>E3B`d&40FYu#Sn`y7v7n`$ny@`9CYmVW-cb zm@NHbZFBjr>|Bl-qb*+z*Vz@X`I4h!wBr%y&tS!ezp|685wtmdq1IRAIsK)!sq{sT zT;ZIuYJIg$b^P;-v%2kyj=EhrKC69D*Y#(Aa&ktU57llxk}Cf+k*B=h$rPSwhWCbl z@PTi*cUZqQOa5D<$>N~))p(A+!fO2-x!TU8hoyOBDUEFM=qMWpwl9qL9kEB5+D`0_ zioDA&tgDOcVb3;}F3n7U{x9JQbHrIzk7&{2`|eh znrq|&{r0m?+bi<0qSymtwuf2lv*qvboPT?lORRdZEe|h_y**&H4^D|?c$f+HyrrFF z%fFZ7H%&FN_bXzbXI19g5eNUq(QJ3)>O2iLdoMW4!Z+39^HJABy9=y{V@o~=HiIu; zWa>7?CAHw2QE%1L7g_kAhP*6TI)8!Poomh8;raaR4(HjRo0WMfyjQwEJes}iSeBQ? zv;FBB&fenvOOw)gZl7?BeF7&VRt?`C%j18Qg7&-z>eU>-$P5_+_+I$q8Fqm^G0 z#jvlb+Ii-%coe?||Lf0)W)&N{@?vOLsxQwIlir=j^U)S~|8-5zMmvn<9(bqlIY?$L zEJtx$_*Ug`G@I%+l)EYKyw;p&=jPk53>^0tZ3*8feu6}hd*)nzk! z^yNy zW9nbY$$vHnO1BurXCdE)Z#~BRTaMt13LtNcKpe_V;1LEkO$ zC@WvAD%T-TTK1M$%_22Yj3 z?P38_toSJS-&WkiGNx4F-!T>fpC4dL<1F}3+)HlDoR!7BasQaZD{;U1y7Qzg`E%Sq z=5UVw%&WG1JMR6jWaKTop>Pj=3iqDxZw51kOQ2qb$GsWJ^{^j{=lv~8jo_PckGYBk zFkKBN?ulnaGsA<}gvtZ?RFqxbF_=B9IFO%#|EIvup>r4Gu_JW6OOD_f7*l3qK$dSg zbt!GhsVhGp6rHMg*0G~RNLJY?h(iwll^tCf`~T2)2CMb|%1(az<@-(GrEnkJsl6ZT zCAsn~-%aGbvjf?J$7A?Nw6S^EN_L{-NPZi!n%!_U4@iy1wm}t{PElmalTqI zfcd35@NMX?r>V2D=AtL)_ooYIWzA!aQ1&rcnK$mCuM;ay`rqVU$OlEP=;V|glF^61 zfPS5xlh{D8k~0b`I%@qKoB8Q0{i4pXoZM5}RCIFW3jb9ep4jZb?eTo0|5JB%DX;R9FR`V*c7o%PJqr^{?c@ZrdZ7w6~Y=_7St_?I1{eR~z}wk&O^zU3Hg zyEtRH6nI+XG|B8X?tO4}@Tw7Qq^`G&D=|QS<(jeVIk+8J zHh@aaerGD|f=z2`N6|Y53x+BTM`9J>xl~(v z58k=-t0eSVyi_~t1fGR4t48);#}iS2mad+mfaW$tw0`c4!1mq(`d zO7A8@tKE3lkYO&|o%~+=5InnV`K+>?4`r7<`n|mH@VJS*G_;%IfGuSx+JBmNIJhJVy*=!=0Y}LQ*RM_;}Zz7ii=V!nCHE->J119pZsB~@GCx?@s zM={6Nf1x$BI-#!#`E&G z13%BwwtciiUl8r}X%MYVc~kbJ4f?`ux5?TIr)>l*7%u^u+2v(yx3zTfai6D_?O6@5|;d7U+}whCS? zeDrnV)z6v8sV%n%Y-B%ff%yM)KB(Q^Nypt`GkoWHt?QN1+yiyhbN!`FG9S;aPGVhM z&RWRNPqUq_+zn%PQ2T1a*M}}V4mpr?>4Ua5_M4SKzfY`xR=f6iC4LTlTL04k;lT1L z{40EG?CvR;ZLiA5fbR_-e#*im(E4*z$V+|!omSC20s6Zx>s7QyXY zHST^E?@vQF2;Zw!;3uLH!}K7bZ42xRMH^ecTO{P?r+WhnZh`jRj9etVDOrJ!Kzq+! z2on0r)p%XhYrTAfQ2m1~e};Ou{x9m@IX+gm5!tPGap1tk5#yE}jH+1!2I_;8-@^>gp@`8}Wi-miJBS+i>9oSD7W z4A-7Bs?(IRwUIWr;-)+M(ecp5DzqrqVq`E~3f(8~{Ggp*&5vG2UmxG1+{A`WX&Bbe zvhOQ!Gy6u-{@`=Ac`Giad^oj1`^hMC?#iqXdKC2D1B>M2GihcB9R>cU2NdDlO~UCh ztaXV!%(+X5$)$*;%M)jCM{PRNozQor{UmPH+A!+53$m3?;Z}M^()tqkoAu8(F6$c% z8Cc&FH6!U0tTVn<`*R8F!st!dVU2MLcg?yZ?FT!Qa-5Ve{@GkmVq48eEzhhA^=L!z zud~OWYqEr=MWJJZkEWbs_r`QD=G3f_H?(f9HR%!f_bt|pu_tTO$&j=6@j-gyP#w2j zoT|{Zm}{ekRNy`aSkopttb1;CIDPT?S7J{cw|^xb)UoI3SC`(y+%bDIo$JSY&{c@T zw%6z9i<&r(OYx)6@9OyZE51|v=vUV<^&0qB))w_T7BtA0da?L%lC;|v z2h;5Nh<~@;ISjwR++mpg$5z@IR@xa&Y5cZU-BR6);c&!^f))Co`6%>^kD6X-SM$*~ zE^All_3`)$_?Z{T&+#k0UteOBqg7yO&;d7q8>*Px6U@id3y&+j^Ug8 z?J6XuSs0yq9DBgc4y4q^XMI4MbHyhv9?ciBRkuN(TA6@UL9~C zjinBB0=}V7dQ^q`m*Vy)Lj?hFX)u>F%>el129h`m5YRi!hrk1lqx2{GQ| zLL5Z9#Qf0`1vtOv(Fs)#-WoVu_87+^##E*FFfpS=X)`NktyklFy}6Kr`iZ zt$Z{y@7vLo-;AWK)h$SS&q_4@h>>()vlZ#&UxD6+Ppy_zCVRG-(Yf&B<&*H^d=nZ6 zKR!u!%O^vck0~t;KW@J2LdZ^Y+8TZ|Tw+Jg@3NxXq08laHe^W6Dzxtf{I)i$K+4T? zq$!YpMoDv0wMYZX@~eSd%=ntz;_-Gd`ZAJQ(E;l@~`GMkk6S-5dZae)|SuDkHeny zZ0&q9uU+LwV=->mF&#*UBW>s<$TNy-NA7+Lp$5QZ>jslqnNjpMWPUZLC9$pDlNN(6 zlY2DGXNL#Ay=W)I)$a2=x!60JrXa386i;V?{jedLxEsL>^ez72x?sTCh@J0W570Ip>UFi_aqoNb4kP&@)P*=!& zbCVm(6h&SB$5;e*U5RirYQu=iiN_o?;p1qRad)Rj4cC|JX1G zGB4hm?nb-~4spvjAJucgZiFN43msbytn!b={67_w>Nx*9G4oIQLh&!N`LC?!e`g(5 zujjwI2A;~EKpqS?l&&=#C%!+QMc#}uM9qGh=yo8JJQ;!f^Bw8pdSN`-Hq20JwQan3 zU}zd~7-}fh>6szA&PgKngK=&XkSWF@-}K=?LuvixOfj{@5HcHh;I~ZiYDQmjwl``D zN@R(LtBxe2k?(!)ex|s#RXiz<+JW$unWD*{WMUqTvymE^Vz=(&NYfsMQiGKlqGA0E za-o-@v?F1>IAc*3soKv_$}W~Jnl+q2%ETB-S6$P@7w!6yhv5IzXuQ}ws2}l$%na|_ z*N*ItHIycgP83^|j3Og}1Lr4-;}`cME1+Y!&xzvBDI-YJkvLnMog_B&N+6|Rhu>!= zi?hBYk)$Dp(s?08%qfg}00tRKR+m!6_;bnR8OFVQXq@=gJ&}}yJXOl3i}c1w(zlPH zoBrh0 zIOMSxN)n6OMUfL}$mM{JYTecHsBLw8OE{?mnQz@q7q1>~L(25UIa^Y?xV3Tsxe9#K zDP7#uqdEBbhZ^*t9Q41lVNUxKz=&zLwY_9y$z85eGSP!~!;4 zFf~~$alHZ2LEjbKlf<&Gd`V;Idv#l4J|CIZ^CjaUbFP>u*1Fh;BtsWB&m@r?=7}kE z%srnZ_Oj$iXtJS{J}+5Za9c~Z!#HP}-a{PK=!IL%x82NNAeqKhu}& zhJPPEND~JjuEw|cQ8Dhv7i6XV6qqDiE82I>n2B#1jJrIHiqo8_D+jx0K!yoH=mF-fAu z`3zD5KC<#l7RU2hq!4^Jvv!I&r@;iW7czIMlPap`TFW;MBn^HqS2;zzUDAoTflt%l zlEhmJT*zM7bB5igD%(~NY7 z{6~Yvit)h#gaUUfIyT?D`*f!hF@nFY9?ukSdjyhVn6tw>Ws1oqd`LRt{N}n0@pNA; znTR=F`rvqxGp$XWVXKy9#*3FHS0^uE&*>-A#NLOUNyr%3&3Bv_^TLs=gI>SG7ypTQ zt&ZXU&H4M^Fh^KUNVTa(()DB21%_j>-;puP=b4A|fhS8D8A(9XYPPqlq) z4_(*JPr(21s)eaOJE-l}4mK>0c<`k21lQ(Yv}79cz3+{deOIWbk@VqPQ#psN_0T^s zbT=G`|D{_UWM8x&^9P3S%5_KnTVjw*A2sL)E{G4)cT!i3rR(=E^lCn%!r>RI@s!2Y zu~6&>_a)2pF2Q;2%op`q7)b%Sb7gtb+Wmn+|0fNw!beTd?3U6RdpFma`T8>Zl#DWx z?A!)Z7FWH13tdi@?OD4Ma_5$eqb#m^cEEmWTRdgHem?}?;(OJgEUr>ut0_&IQWhKb z{fwm9{ro74tLDA&P2ocQe0Ed!WwI%@)z?=aJ&P-~ofRAAvoqq#D+2X6TSxvSd#dfj z;%abvBS~sML9ZRuc4Kk%pqr7@>0wV=9dT8z7tSONJJEi_wrdMxzjLN(b@IN18#fbs zikQQ$#OYWkPQ;$bOy^AMOc}#X!QO30raf6LWpQP&r#M};GU>B^Cf68ytCJfoNezBJ z7kCceN;Z`v<-@bNF4(J{-&2CjC_axnh5d4Si!a>s?UT6{*dN_|{*as4H)gwS{kfIcADy(nz}cAwawoArvaveF?aFfIe1LiT<6NH|lJ*t$Uyp7c;ntkpuH6Wp zXCd>95J|g;;yVS}BWBd#3`NvFtUu1R59z{P1HMepaC^VRbH+F;-dyu4x7~XpHw))= zE1KqV!%oiP`tQMBvfmrd`PzK0H_q+n1sf2}aL9kaNQw(AMh3dg$Z^-89T5gcLe)Ejd3+{tb_yC334_n>y}SW zeY!MxXYJ(&dgCju=M@$19zy+BNI6p3teEf=^7{srAafpl(}nLfk_4B}T$4VhbvL1V3*U#_29LSA zR?RA_}$4R-$?Y%-U?&Lkk zIoqikojZItXvZ0DM{=ev7_!y4eT9phaY%O(_A#7#pVM}Hp_>O?q6WO?hEFXbOgo7< z++T?7f2tAEPGf!8uOacb3JKQOvzM7>igyh!=vHE%UUah!+1GB7t|?;g)+jqNYC?#v z1!D5Or4woEvMQ%4Vs&SgYUGx4s@Dc!*UEWzZUMb6-oD12Z!T$^O32hYwNvu7Xk%H;6(VcbFJvTk)n;x#ITOMs3aD_f93TPJWn2N9FW zCCMnGOs*s1WNtYFGIo6;*ADR$BfRD=@9f7p?Z)p~^T%9^o&lT|cD}RtE*F~P#Lb61 ztDD~BVyA7>hC&x6!@7q~+-Hod@x94$V>@tXAy4hl`&{gr!Q5{6`uzJR+@9IV+$Y%W ziS(AUTQY&G2U}H+H6rzGGP&BAYmKUxBg^+Ba{icu!`E1n?B)HqRM;)NtPQz+&Yv5O zd0Meg6>{#J16LN~CTH0awG7@uvR4tbr-s^+t+l`8ID_8H5A%9;jE)B%hc6XLxBg3X zg~9*uObfynJ+9k>d420eN#fgduWldw_|?mRObec?TMs!~q`&5hxVF=cg#7a!JmOmC zF3gz-yqqtpIlGZkunO{x`2D>NW7cdENMLn0NmTamD@* z>@I|L;7KWw;c}&a;GRYBdz4X9ZWqetVU|O#&@-&2SK8HlSg!j#@PA`mT4c2ePfH>9 z09YR%ee~=<&oKk!<~^{KYZGGM82*XF-XjmEjk(;uz9@e0{=jM)bzg;^<=8&}&vJK- zMTWIy@-Q1q&Bxu?NYZX9BJ&?xArJq%z8v^Gd6!p1k!k${7sMwRwFxs}=egZWiX~B- z@Bnt61I%P7h!4y2SA3zSXYGo=)I6Clly-)dzG`|kPqqD-3~Cz|WH&~m)=QCDErWWj zpXE_vMja1~rr|w9>F{_*Irb*M`hg$h8cGLT?B#at+dRzrD)bDi>6LcIQ)!p$FTlV2 z8b>)M`+t}hCm{G?AquE^#zr|5Hd0$zs=?~nK!+(;6Tjh3L^E}M@D)bDi>6LcIQ)!py9r*8B ztdncFo;E=ZJFq@J`skVN$Gq_WA>@R-e~fkgfy3PK|HtEq+`gXtz-k(GUxl8jCUs9GJ;a5Fh4W#TP6l6?)dL_)E=``9f)DSm~>#SMyZcpUI%MVL^6dG-|yRnbk6= z$NE_wC1%v|aNZ@92$9%h4(Uu8E*F!ByTx&2MOS=JpVE#p{Cz+kW;7|C@%_DGj7)#E z7tS31zy z{*JC~$Ybz19vx3FHta~OqVa8aLYyqyN}P2VH|a}l;|QsTbEK1nhtfkMy-74^iloF+ z$IK?=8~QG98c)^oFuj7p@J%0m)v_f{X+oAkhO#Z<>DL5rQX&L<k3 zj4MG$hV}8WcJwC%^CfCR7Htfi3B4X=W#!|eY3@QCp-Z59EKM5VN>1R6#qCf6eHGl%W&%H63`DD0s$A?@2|Lz9h|CNyKUGNQhLj$Ewz>2&ar>f{v8vYuB;rnzA*Bm}pz2}9HjyNkj zIx&O3d)I|5g*@ZT&NcL2V3V=nMLZ;8O$ZKsWGF>&UP&7Q<>gC_MkJj}%`sUnu@k z&wcg!@OS35dOrT@9Q-SD;jh|Ov76eSKgXUDSL%59pRC);nyg-{fBqd*e&h80HmQF{ z^!+w5p6cI6^>3^4d#e8J_$$9(EC#acVXrq&C;t|_Xz~N+`s4gLX{y}rh2JTLof8N- zPzUSAQ&Gm|_p>By(Qe`^U^KIn>lium1;Y{rDC*0RP_sSq2 zXX9JOq*-#`a|`qO8duLCPAjmM#?I62Ej*soUWT*o;Iq0g!*L{cG5+UNDJhstPb6Iz z0iUiS-0#+k49P)V*lZWB|L9i4evOe71gw_riB$%9n~n48t`=S^pQMu;=v%zMiMB<% zG!nPONFujmv@Xr?&M(HAc5|0@bE`4rBV^FVe$cjv97GaU;Xg+8^4vI0Z^A+MxoOti z!}^g#0uH!t$Ej^HRSYMUAo8;zuaBZIWvN@tL$b@*?vxrSF@A4lT09_P%nw|X@O z&V{Y|e%axr)_2K~#^fC2F|O{w)e$)230%~~nzP$do3w-c!8v8PJr~_bW$5Kr`KI>0 zi8FCsiuRNYt=fi%cqfts8D_YKYl|nlkPVPcdv={Rpi*@*c`N=q9lWEJYSksV+mQ#} z(S&Q+tTC~HzCIi5xhX?hlMe7vAtw`IYjz7V9XM%28DVDahQtSU9`n&qa6RQkT47wP z2TyhVqif+_Is7jgaZGo)jhk$9v+v0|-xp5g9poPsFXgCp_r`s2Mu;Uh@K@VmSQ95Q zWPy>?}7IG<9?AA?u&yl4w@cU)> zLHBWAQ!)rVJ6eBjcyPEJ6V zYd&9elOBeWP0%s0YH2~OdqwaGoR3qJsh?9vA*L#IaiR3Y8#z#HMaTu6D3L&n>b=z3aaAYj0x&bv8CCh4ut{hBQ zZBeIDt+ncL)%+U`9zw1`U%PJp+BWw_ktdi(FM`aq`wZjB4vclI^I|Wy4k&YZI&c)) zk1o#6w?6#dyCr#y7|8y#Q0oxWlJJPJxxnLHg2?o_xVPc!F>ZxZC%nq{@FvFKv#m^;wz6Xod9)JpqwneK^@%U+R`GMP*1WTp zw1kd1+bp!>A8_Oz)`zvkHD}95A2J8?qI*?$UA!|PYk%S>a*>yuD$=8>*PPRUi~NL z{@aOPWucd!dT>%+$lzzJPs$vQt|DthlWmi5=dT-LtT7e5xQn{ zV-l8*?};&AgxVYH5$_D-SA2OUY(89*&`iwb;JZQ-Qk?`(z&E=W7ln`~F67fhoMl-Y z7a}@3l8*Rq;QxNB;OOE=8e-k+P;H^`-P4&&!kX+od!mq)a%YkXInU3|5?*(ABsbIWy?Dk#!8^f`w1Z z8`X$yBJS|Kcv3jj%bkpiHIUv1rw z3jU3J2@ijjo_t#HHV7eyVUq#xuL`^RMw2SQ>zCd7Kj~}rJaX!mNnXPKuMeLPOe<#) zOW5S&y$3>Or*z^q9=SBF-wDNM;{7<#_(T_`@gec#G5k{Fvk`Sq4kO19^QE}9!oqs} z$$HF%LE3J@NZf7eiQmT-@goJHcM_?N|IaD)GK4-MsbmM@VfV`E!no1tq$6U+b>(tl zV{!&r4EraR5&o;=WVxp|S&X=yZ#!3D`;m@kaCi5Z#`3*<(j`Ob<33)-MhAbi_r*O1 ztex$5>h3}g@XQu69*1^@86P#h!c$GZZGILxd;<5$=QPOIm(h$phwnaqj`c zjm|YAmGJFp^prYsdk@?X(D|UNjB}p+zy!M8#M7sQ8++Z?`|-MFSK|19Xvus%MFej5DVy>nfe{vLE!a6x>+67kj^ z;$iRSMk2!x(U)O;d>D-gn&0gj%k+KFSHT7GsnNL&x$ztB=QnO3GVF0759{N@##LgH zVI^+$@%cHH)G?#P1LLFiwGt0%AN}k{#Ye2K+HQ(%f3}-q2eq6(>!QpfeRHR(c^I+6 z_t}>pa90NEQ-*9dl&)0hB-f|JZ!?sv>x9YmDZ{rIN(P#6xjv=gCgj5xj+EBT%R%o{68-Xmunx6Ko^Ete!Jgx++i{`NUl#Q3M`%ulIv4yK}Vknt>yZZlhE<> z(O|hgWfpYAg%omqN@?hLyi^CdK4l_wY1=YHu1^`c8h58Sh066Q^B_+|PMBPu@*Xm5 z_XwBkQx@&Z8<*9m1cAT1d$?Sm60j9@2Yy}T`jl;u;c2ljxjv=O4#*ZCD%Yo!p{ND$ z?kLx%+`~-}v$nRA>r)P3&5Y5smFrUs_8_*O1k3d)qxYf~V^(XqKBW`J9djlqpYE(a zMUjW)-Yd3Z^(ng{^PR|Wxjtpia@5@{=pxsr^nhMBbHn8Nluj!#uSShozF+CKE(_& zKP%T-u1_fgT}FIqE!U?k+>N@YrfuZ0kTlX9x9T%Xbi_DM1ADA%X-&M}lyvpdQ4 zDQWQUnZV9+eTpB(dfh8bu1`4+`!CwjMXpaN4&0)DxLlud5aVtg-cqhld5U#o-{Y2Y zeaeT!hLX)8Ke;~T=^@1Pc7M4(r*=IM-9=#R&sqxJbZC)Sg>55G95l@ z>)uwbPsxDq0u9>B^(ldn`E22i`Q{p{Pcebtea^R&>r-|>-!;|R$n_}!knQWGAh|xJ zJH{RLDNwFYxr#N=b9I1RpRyZrW`FdP>r-Ap{>Kkm%JnJDj=(74XK4lB$(YEd3BCAh{g*{tp!{qvuyRdl+ z*G_VMiWYi_W*z?{^ZNg<`TO56N7#B^tQPh!XZFbF+npNbVYZ%Y-Efv-_`7`OJYJiJ z8T}MT=WnQrPZ3&B-5<1H`F|$nkDr}2`k)vG36O`Io^V$R{UV5Jq&6Ct=kG+App(nTc^dt>06hSJJjc{ zdP6-%)+f{f|D|JJ(iKK^NK0qj?Uwt5ZcBD2gIuw{YnV$H4XZ}>y5o#1_!b>|#F+%v z#NKM}RoPY^HL#D%x=C;1+vN?=Z;rc9%j1qY>H-_Kc|=>69#0xM;hW~(XS6NelpKPw zntyspC$+>|*!E~gmi6Ev@nk7v`>p7EI`HLCvI8u`$v5C5^WIaZP}F#u-N!(gYOgljt z-t3i!8O+tmDqOmF0Y+MhpgL40hl_aa^3m)s*yXvW=Mq&Q@L0IcRyzH<^ej#xU` z_%8i&J%N;mF4H>YQnPYn$#TTi!21tr*##rW2J{VE^q8JHIgr!_J`$J5N0H%H=n%3N zV+A#OLQU_EBF*7PXV=HHW&3y%Q4P5EL+TNiND5)T4EDWGlXoYPN7Zp=a`m>X;}*=3 zg((+la4DWtN1SXgagE-7?@jh0e(Hzaq5%;;WC!{lH@Zh(yR{%KU>}EBxwO1PFqw+6 zb}V~D8`Chd0y3=hdqUN^GaH7&&I`a_ZHKAOVWb0ex#InV7Jb*2JOe&g<1xLuAb?zf z?oGx$r02X^kf%0?|M|Hz(W(&%sDd+=usihQe4f<8TqxysJ)e)*Sc)z``%#hMen>KBm(UT_Kit@ti#cuFL#uX zJ|;%e4e&XjNg>5bA&2=~X>oDwWD<(LAqR}b;A;sawH&_JoGl?POdCyVf__2!;-cr+ z;UpOAm088ONG$YPcC?sS1!pNXhB$jET0#upmPl9*aE+*v;+x*dB*y^jZRt{? z*@1X^G9a~;3SAQ%S5BevuCi1v-UZein*h;hnpVUG)3k6p5 zRLeGg$OQ5mbmtM4S;n_9KgluBEGymEd2THxdmj+{s1!#iDq{Ti>IdZ#0Tr))OrTu$3ZQKKh{GD_wetn<4=ykRzr(eiXn>{l6sK2 z?oM;D#6m3@3!6)`%tYUnwMZe1TfU*GSY>PtG8pzh`MSJVw{JDVmBhL9@Ur5RaZV%v z@?YLwDxVz~|5(_N@mJgA)@CQN9)6$trIhHu*M;=@hX25ZWySXQ-AMZ{*l*q_Cw>{| zLG~eLs`{FUgFL)Q(g(Ern~7O#8 zmL6d&?%EPfDq_Br7>1gQ?7^fW=Fy{2196*Q94UtX8^c-`7TG;ows>RLbzl*m;UNuv z;E8y@c6=Zv#8EnZC{1w?%y40o!Rht+(RR`aBL@TRk_ zLJ|ISZ&z9zc)`%Zd_<-l4Z=Iin;sS72S!w)*YIBO!hv6jdR(vRm1tW|BfZ%El|+@W zr4@J$>J|&}7Oh-pQE!dp?p&C^MLnrC^qOc}glG5RDDp6@$fHkAHNDd!Q#une%z5*L zBtN&L&+uk(`Kg8Y{{1S`%XqW+P0PZ(?I5Q=?W5*j3GK{QOJL_opm&9AXF%WWr6p|$ znY)9J3-~|K;=Kd#SMye~W-`4p*4?mP)Ud5aYJJ&^ z|F|WZmTRw(Zf~&Q9c`lM-3}V5F!=n|lBXM*YorS&O7OdS^0W))&KY2}42L{>QMbk# zDdbo=KICP0`Wo@(eWDCsqH!dxg19YSy)^$i6#61=ZHj9NF;NNrx1;g>Hrp*Jv($hdO6*csOdHJoNV9x8*4b|-$5IdURm-{JiwSjs z->-+6@r(Q|=n&}DxsL_^fLhZ5h?B{l74nU%=ELUoYuM*;rj^-smsuf~Jm8$~O?@5V<=cHzHIk2zkqK3#zMVr*H8@43O7<^*e`E%U7SHD~F0rNY}0;a69U2_AccZ&fb@Y z*|~(%2ApwObmbTxA?9Irc9FXhXNgmaa}0Z-FT?uyFdDOsxIZU+fJ`4P{lEqBIWu<% zd6t7*zKk6l!wnARVSRiU%_q=%+|8r+1HFRv@fiadJiIT;@|--9hxPGcG@WxWoT@wnU{Sm~?g&+OLY49J|uUILi7-46@5(87SxJo)_HmEg z{tj=XG;&0)FzX;R4e>9IJjTt zsqlAC>c~~ApplCGG!~Oz(RbLC6fOYrxcy-V#U}dN)%IjEt94ZDpih3a?rPa09Q$yy z@aACmYlleN$49-++iIldV;;-c3Hy46H;{f>rJZ4=oza)K&`2};otNpm+W)``J)=?R zSzm>oVKu$d&ghkPedGQWK0ni_ck0?=|2So} z9q+QG19ijx#b=g1KgT_FqY;hbcSJ zkt&R>!LNu7q19tF(i#_c{>|}ldaJKSs#npCXLqFAfKQ<|E}Xt=h+?US@7fPvkpAFBfUTT z_&m`mpA77d^zYHw4_jdw=1sJi8CF&VZ5?Xx?2hyl$ZY9clV^9NZ-*}Dy*%alrNjoiBfT)jS{`o8 zvpdoa;fsmQ?Ra)adNi9~N%lOuBi#lvKQ?yc*&XRcdqVf!PWkj@b6kllw*OUhXLqDO z#reR5GEO|ZBfSRVq;|Xm&+bT{gZL56?0I%axrt$`R1c~E>y-H>0O}X!8rSWEav~Im{iC4--(%j z(ie(aNF~z!O zqcqaF%HA@4QLO*0oyoQeYjP)tIx_w=EDtl;6dHyVK8)TA>wwvSdNTd^kw0)jd|qVZ zH*|zX+IN)y7kV`xr!=eyDNT6OOZbienG4r$EYqKd%&dL86i!c!!#eNUlHaZ6Xm|$R zdX8=`(v!p!?GCjsCK~6dS7T+~A2XZ4A3bn0f29=aCuSv~wczE4)q!_SxQa{Y2C^ z0T1lsO|?VtUWTbBjgF~FpY}sd>tPRC)x(7@?2qr-&E2W*h^q8N4C+sdSEENKR-_#U z;`|}gp5EzbLCX!s9Ym3p=z@i&^c?uCH@2k4x60F2BXE!O?2Ydkt7 z)W-Skj0t#0ruYS+((=clKVV9Wga4VKmULILB|U?Bv?bwHsP9{A%0ZqiOGmnOrXy_< z2feJT(@S=qv=-#A^2~!e<9BBdXpV;&(>HB;(T(G9r>Iv^x*|H7-cCoJNzMl$v_cf! z0eReJJ{Eeoccey;Ik(IeA@-IZ^@A?`Kb^{Ff3;t#Hk7>wdAK8SvMr110F5+=|q07;4R; zOz6vtm1q4z$#Z5ISQJ@{TO3&`a;a>09V>XRZa!#@=BmWUKJZn7-c}PHRD)weFU5AKtu+ zg`GdPt3+o{XhU_Np$qJ(+X`QL6nfQs=|umV=gU78OX@h^YUD?2BTmjg#T#Xj!SpEb z%#-facyC9#4s)dBa#zajh@>}QE9s~mjepmJUPas{T2%P2h{?Yb8<()B(?H+4Hx1}- zT|=n|eIw)F3#)s#p()U}JAEYdIOa>^5!>&!-jQp{?s#D@8CRTV=Q*{T<>4+Pe8_Dr z_8Ji-c!q1?I|9Ru#@ACLPw60yRF118%M%fnhxPGcA+AFx@?xY9u<=RJKE6 za30pjN1xsF@v++3p1f;?y-%(3Jj2 z@x{Nhi6XyRHpX*?6LMOSpqrRWE8dq4L)%*N^toMBl=j)xtv8^ike zF#22I|25@}eE#fN=Lar`k8xlS$#g(IK*tw^;cJ*X4C~|bu}5cO4>>)CJ|GMag=`G} zJ3hRXM%r(ARpyxm*%;QxhmHHWyhi$1@q|q8U*!ibh)?bMy@`u8&QvpQ5Qay&@nQ72ra1r1IxW*{ZGYf`_*{S9gSgsjq)|7Y5{Bby=HY+G zry#%o6+UVj#$U}xi7{pewcnN4Q2R^m3r4TDv*HW2eSWs#7wp$|pY)SsGGNjVoEV3^ zh@#Ep_A}ULG0gZM10M9SwTx|M=3&OOAU=$~IrbO#P5fp0S>UhWg7`4KUSWS1{MDCd z*k?i>*2jnGJ|1$8E!m7`_zGlW_}}qaJX9n3UTYxB^BTG{td9>HH?qG*y4yu7({GOb zfeYfp>^yNe^2BB|;u*e~oQL)CVRoyJvz=}?YRPt<0NEJU$A{4e;H+r|u7_thd-M-n z5FZv}ld-?H-_wF;_;zL<{&#!|^7~)mqo!f})qIrLV0KXZU5O2~ztp~9^lCdRzEInT zjiu;*mx;UDx2tLc??H6KQ!@R9reA-_I8lQy>hlb&Hketmp~4(TPo#oW8+c`gh% z3wa9}J^ zrThBRdij`K4gNF6&Ig9k0LVP((QQu6htVjpq2}2tAdG(5iJFebw>eE@1WiId#_~&7 z<@i_VnVprGRP#}ftG0<+FSYLa##QrVW2whg<`;_}HCAX?+^Vq>SBzebl{ox4#uS>r z5*zGnDylnjt-G|M3~#|6S;4>eK)%7|W^#Mwp?SD(H||e*hSl^1@#*SQks9_zOxEu~ zLx9CD*gL!RplUv;rtb7}H=Mnk45A|s+0*@9@ur4LJ8J*VhE9saeIq5qWO`*RUENBw za172CW^|?@#T;o{?C~%7wxzC84cZg(Z|EIF!xwqd!_jz;%y<+XhVzIL(B-DhNNV6} zORoV>a~(!&JKE4Cz3|@asTiu3ll2`QlGj%)bD^p>w0&pPavq4GnRd1`s}s&o9Eaik zSZ6ALevI`<*;YzlW=};1HBYr{jK-n^?q+G0AouMFJ1DpyJ|`M_{YlTTn!X@DQLy>7 zFx0WW&y?*yEeQ37&oil-Pn|(-bVGaGY4$yVUX|=V5{F_r_p*i_Zt(6^E7@kRm;ixy87kyW%gHO9$wLg)(k}5V(rP)zJe`{@JFuH zkZH8_2WL70^y5u17VN3?Wmu6x%`=~DpxNC5@%Czt+_xO;px}b|kghfVq-R)7Ul5-R zd^hX~`@cDnMcMb7^00sR3t3dn=hj4f>g9`?2)vnB3STrrcrw=ko|0XX|= zG*zZo#u}4jO6MW=UZ0#okKDANZ(-Yv1JmijW!7{KVyV67Eb3=uN7q9a>r1og{LL;@ z3tVZ<9O{X0xS!yo-3{aEf^=)T0lsTIC6T^pVnMH9u2s8`LN6g-cY8Q;UDl;jwfwcv zcNO@vzG_`&eKetw!A4S>ZRxadBMX|=)<}xIl0q}ntZ5j=EjBfg_F=kXohj9>C+%Zs zN+)98ZL=Cc-2yG>bj-)o?!)Q)Y-{=!H2k-?d~&MCT@RY2(AW2C9G%$8f;NF2CZX@V zqNcO~=H^th0kqZxJGvR`Ky*|q8ApOA!)h7&mo%kQ5W@kpBPdC*pwpso$5d~e5ni&U z1olZE(}q^LXiYP*wp1J2hOUXXp!cxm1oaA`HA|S%J2)FZI5#5SSZsYhj&bW3$v-Y@ zkAn=Xo#D&S*Eg-1j9sy=Dp*aU@Uf4qM%g-iep55bFk6Qi*2hO5J(~;48qTn?wyWvY z?F=jH`LC|kzq)3s*G4w3dfijjv|nAXes$eYuMbQH_1stH^{>v^U!5br8t1*V+2EWe}HGGUGUeq7d9Bk7B@Qhq;f`)Aw(Fld?le%y|a_%?BKk^Fw#?)SKZD|CVU zew^nU)Y^ZYN!a^wTVCQDLCRFZ-jB0=f%?0gNrb&0=lmSs7d}iN?ESd5&+uJlbQWRn z#~p&q(-JbtSiCcMu5_N9#&|!@4dY&0l1Uu#ew@J<*^p1p z?|2WfH`+H^Y#`O~9^ypM7n!tG%JoAn~Y`h zdx%vbPf_E=@_UFi4WawA1@e1{OW~tH?JV*P?;%!%Uj}ZNN+#ev#4*r)Qr9 zg-zCdnLyZkh)ZCrLZh~ zH{h>(4JHxx9%3K(^iI*KguRE@=r!Jf4V*#Pdx-Vl;+xdf+46gcH4zUxI?b2gL)?zo zd%1Fn{2pR0$UMS&rTiY^A^7XV^VRZuhzFq8qwQ!=@XTfM8*p!7+o1I;J}MnRr3(W^-_e@QzM?M#Lhcq8vT@*(R-t|ozXzvO&|ughOrNu)I~x-!5i zHCK?TF-vskifN>v?@P%bypcBzzCPiaO@=qwtDAvXy>wzWIT|!qmjF9#Fq=Wl9oy;r zVW06&rxN!o3v;3{ZjY8z$j1Y-y?(>E{@Tg;?4XuMZ8!Fg;Xw4=*nYMAjv<@Z>vyh{ z-!YsG9ZwcpA-`kT7P=4H2ifqBq4@{Y1-xA#zhmeM|27k6%kLOE!-i(IGYEUf@DuDD zV>pelcMOezJv&b!>>a}a@Wq`blk@p&^kXOPcZ|EIDSQ;)fm;E2IvklomaZMlO@)rB z1E&$!Imz5{=w5Eg4C0A*3`=6pIt`qMTGC8TgE>;;$RaWv?-*9b+-aD;j0EBx!%nd6 z2D*Z5$2*2CVgF*iR*~y?$M6m?H){3&nRV~~%6$B9n0NmTvCVQm$IZih91tzAoF&hR zxX*b>w7~M6W+GSNW%go$<*zQpx9>ila|M>a`VRRFZL%i|EPs`K`>yjgNv3}=J&&H{ zuhyA^_3BKL!17mH%|h)=&&dMIUwtzJ@90_26G#-3Vvq;c;RL1Pc?Du-vT>$Tq85A%W$u?g9U&n~Di6 zf7N}Ok>ux9Sz!6AMd5y#}&R?g@?#rW%tCAZHwjh%E+T&?JR%Q2mabw zzqi2t*FBzqT!NXs^U<*URd%0h-1PMV%U{hMhr7WuRtPMAwFUgRY4v=8<*yb-4ufZ_ z$pXt?y$wGaUrWj-1Iu3>GTTUsua_>c{8e_(>gCnb1(v^R1HC*Q76~kW^)z(p+ikVL z@>d^2{+vr21(v^>v>f~Kz3X)>ug?>FrUR>GX8EhNp!<;Lz5>f%?T)_l~uS9`#BB^s3%SpMob__u#wBC!0`QLyLv2hjq{8>|JJ-6P*N>ze*w7!KtMLmcRN5G8aB^S;z8Mt3j{2J92bvKC;+YjTqQmKZFj0&ELOS zD>S*+g^t3wBeyIQ%Af8^ufQ)6C*}&}`}Lsg&j0Oc6NQ_|Umbz@=<_@wpT3MIiz~)c zt@{P!uSOysMhzb)#2|ll3FiCVms16^E>W}$;%8FRY@sXiSN9;U0_Lw2P9uNyH2B2$ zZ^*Z9F#gJ#pdL%D3(H@fj2Q4QGDTqdtB#QKd;R2m^HDt)%#go&20At`J?|fj`F|=V z|EZYyCw-y#m)ZPR*7Lu!4y)JmUtI%PeaeP-=?zZCF;`1}DdG_X= zA-;Rc7&N=^4Q^7E<}!U*M!vr6{dxg8lck4w z^L@;Xy)5vp)8ecb|1Ex{?#>{MloV5s_kZ+FYmV=ae)l=v4Kgf8zV5QlYLEKmvzxjvlTER$zP|eCfA*JR!+dt`e_opl zdlo;-|0R2>?PGiBy4DtT2RUZ7_1Zygw^p#>OvJ-}qegu7=3lhC6ExDHT}}9Phx?Ja z*r&{|wu3PI6gd(KcE(=M%5T2hJ`(@c8Ls;|iIf9=-eaqbqsrxBeS8@G2b>!Wj+iae z`(huY;DY$DZ>A?+f!U9n%N^h}cJx0?UJ1@U3uZ9U5(W-1?% z^FWep@~}QWjJ`DXxjSMP%k<&crzp4}KJ1Morw{lRW|B=99s%1jtd9?)nTMBZq`xeS8>AFysl3$d>7sKpq7b#E1E@Aiw`rKFU}> z^HE~#=lD@#<7dAsKKi@tBy_%2r!61&* z!dhqWl5~v;;vP9*eE?STnd-ktd&~{>J8i#`L3MMq^Qvj2Ydt@btlKZNX3iSP|MnZw zD7-2c=cti-8NHJGD&rO^R++mB{*S7>BBgp7a8HmYHeU0Fq`K_Wde_rPCLSM1oze@n z0mz*zvg#{gYhWA5oR)6DACFni<-%5*UwIlnSAHc-=FyOC?h*su z_RBqOINEz{{z|I(7v*d~AHU)wY3^z-^O^DW9Z}24`c{T7=Ao}z<~ObFxrUJE_{Vp| zYFtrHfSiReZi35w?RUukWPRSaimlW#Fs#@|&HwNET8SCv(?9+G(;QdEWphN0m3jB8 z^W}eH6UCltJFpl~k_sY4}>?}XpJ z_D+1WK!2_akzAoyZ&QyYFa@Vh{bWZJ+cAD>C>2XcYPKks*hDOoN*V{)7!_jU*WHh6|3?0 zC0nj#Z`9u%ap4;eYt6;<(ny~TUHJa%hH-pP+@1B>iNE8O&fS6^pHWACaF?mvnC|!; zALGC`e!P&|8-;i)X~!R(zlvLm8qZFRs_^>k(8Xsp_ZBjYd0Lt8Txtn-1u?!+JN63BVLwo&FT{QCYCxzb@ci@xe2 z&m#doI_+1U|AhHv3?DJvJlRkXV23`PZ1{E43JLpQLmFwtx4QC7w;Xfo;b=>~SQ(ve zB7B{uGvjM*Z>7`17ef}C@D4v_iw5EDN4z!cpK*t75yQ@)1# z1zjufw<>JG-a2zE-lyO97SxO8|2J4uX@7kHDbPaoC{w#ELIzXxlrY? zOTPHoYW!JO7JY{-uELLect_U)F~4MiEx*`Ur#ptVj@+>STQSCd3zT^Hr+ydIzgdYl zi|fW>-ELCTfnT&>n64S-zE7eZA7Qja=Z-b}?xL#vD05MF4K(7!%6!d@^|k%5R$tLN z@m@QE>!o4tzv=6kmz&*3BdxkwSH=%VbRsnqWnRg(qVOz^7?mWYbv8QHOA0I}Ojy0iVw2MrC1%6a;L3|?j_z+vHEt^6d z`N@ZT$ROy|1z62TH@!7+0?oKCdF}rnb?+UYRnfGMBNzx$1q7rcP3cI@eU>i0Hz}d_ z4$`D3E%c7m&YAsYl;>7lMHeu<+y=5ZaGtBs$|_{ zd4e()6FX$obvm(a$1*Ouyr7hu_Lt@8Vx?pm;vc@HQipc1^0AzY78O+fhg(^Ncn%lc zRzS^c-Pk(DvASoU0;k{)++4rz#tzn(yhdkS zT+qos=U5kbx`@ik<9?CHw;kg#89ufKa6CMjC9nFi))cEV??ZB|%By;YO}Bb*OkOrM zpSo9JwzZ7gtUtbh3e7gx8qW2v@SPPC{pMQ1JnrvadrJ*CKHHkha(2j4P<^?1hE<&B zyf$k5ckKk77;BAUU3O+Jq^=$tYaL=;b}>d@rky_`CtE&V zqbFA^{HHcwIXu}a#=g_2USX9mZlZONbqs08&$2uvcs}nq@V08Pv%j^P=icqHMb+zd z23cQo{gxbaX5<}iwP#;mJnt|4^0TLS?(O7f-Lma1INVCbGPL3P!)gz*KH@d^)k}p{ z-yQv}dOQbmjw||SJGf+kJZ@W=_Fs1XxaVis^?p_l$Z#s3ifr4%D#7F4*2^*0HJ5H> z9&UxPO#&9Z{Jg?^Fmu2?H{fgT_+w(!U*nI7E$*1`vcCCC%JSAAo=aQj6#Tcw!r1vw z_W#R#{<}H0>3L84%HuS?tB04VF)6Cs3AZ@sq2K~FXxQ8Klxytc*XO8F8~p8*mzZOj zGgAc}KIR?#9pCklVY)ige!92I89r-NovKnz%J1!Yir2@$DJneWy9rHCrtvkq7^LpT z%?-%MIQ{2AiobjD9A*4ljwvcb)5V@vr_=a8KQu)>T64s+^(=D{XQ!&8^`3gJaQjqu zx+wQ0m8t9wp=UzN``DQoQ*t6(92z6WND%Ih0w?JeQ&3;!Ta zjm*`_DpKCxcX#i0Ri;rxD}~43*ZagyRsL87t9lK8-V#ij>qs4c-v>E;>QUKL z*64=*z8dBBsNFe_d){g4@5}nlUX^%YvFBiOe_yIp`_;2?Wj&o*`ulMNWuTKdl&OKhNdQzuml9eco}nefl+j-@W({wLX1QPj-v#&}ys7dtz9^0@gjx z{b(saS<>J4_HU7bGZ*vsS)DekW}jB~eqPSsxBTsB!9^?i`^x2sRlRO+3^-EN-i5)bKw=b&Y;SF>&iO9qBYl0#`mR9>dw4nKQX+n}!lK*T=gaWf{Og~sgfm_238m8bjxPDh z!o36+3h~~r-DL~+5)3NF_l)g4XW?Fg_#zxzLcg(aFTs7TU@Fn*rqw1s;ZLJD&X_nxtE4?}Zq|M;|X7Vcrl&AeRG z>6a|r!!U(;xnkd3v2YIqzQ@d1@w$b37`|nGFLL=!3->U*$$Bk4eapf=VQ)J>-nnIh7`7uk5@%SSa*lywf{)L-^*W)wi=(yWxtk=&-g!Ww{oP< zXLn4)cUU#`T5qL&%g&XSd4K^v>qr0M_PN)X?^>|eiqBKQ_HzB;eEY2(*Q(k3vhY4L ze!sQm^+xtKE}xoZzcu}nmUc$QS#IvN3QlQfzsAo#d~=UAk#mIR`!hd3jI5^{`0l&Z z>?4&EtSsfb+atMtmksgO%nDuY@vrb*VPC{ph0X`sQJib{aAuTMlJ87z$?_-UkFfGp zZDNmOy}nqz$=aB$uKhOS*VA%NEdOrf8#DcU3qPJr_?^UAGx+ymX|nuI;*{xrzLM_- z$?qg)o5tm5g5-A+1E=`;X0DndzmvFQBL7xkwQ2G@i5EWh^KA{9F29rbbex~Bec%lF zoy5Ik`L`pl&ye3qY&6Etw|D+b`JKe^qy2o@ewiu1)mV-3uc>Dde#`P8<1|NS%5Pcj za@j`L}k7qY5xo@Xk?(*obJ zwpVz%>+NrO4m8Sd4Tu<$puXX6J)Y*adJf)@kn$|@Ncm$|&hy-NGPUpWope@%I{On2 ze8s=H$Qyu*>az%;WYbNsn@NIoJ-l5<@_)*r?r-IDW|dgT{7pj ze&Afn4_U9=0}5EDIhQgs>pNxcTUMz7A6e1-okfk#Q|wPu2U$P$;NQ@xJlS6U@f7P> zZ?;LNF@ie{wm_qM<6KgjxH5dTj1`&|Y1=*xFmcNt*^^&e_Yb z<951z6lCWw+T8ki6X#t0)|&Ig1Fh$q**90_NVvVPi}g5?@A+w%b65MfI$I56_)g|O zas=G+f8SaZ$9Z>s=LQrR($G>{Q~OpvSr>5PLRG5)m*@UtNLo%xMFVE1nnn%^aK|K{C4_4|G9yYBy!JLmtCyYBy! zJNEynJOADHUt!<%{T%*H&qqIcvF{3C+;P!$FZNv_oL`so_j_LKyXtVx?ebwM|D*e$ z-1kuZe|i7aU+u;- z`wWFMm#GizK69CJcRQ#Pk@4@(Yo@-t9h~({ePH)l&y=ISIrpKCY3Hx!L{s104$hUP z{$J0Srrh1mYCe-1JN)&0YU;b&ao0bdkj`_TZCLB8;6I&t-R-!~zsa5T+~;MS>o@Uu z-RCoDnv?ZCW%*oovewFE&x|-rDz-n)lI~|$edh6mW%c)U=d-8#9O|xr{B{G+Oy*cl z#{cOQN!$k}!%pMMLy;hcrt{q`H2&vPuBzi;NhI4|SOZk~0wllW0dFXZpW^1ILA z?)sj)nY?Jf>R;M-pVPs6{BP%a)G;=6_v`!A^3GxV+~qSn>X>l>cJl`2S$AKreq7R9 z{dfLNqMj@M#6P&(8MDpucI5Fb`~IJ~2scOZBAf>5m^tk3cWLp=-a?O z$27zWcbqYG+;Jwkm;hd`Y*B}o`zuE`GXMW@bZ)*bp_Iev{gvNKuAS=dI-DEo8~zPA zxpvkDID8%CadUUcwG+kMDY!ng>E`{CYo}ek|KSPUoZ;WK178SH4#x=W<{SU69n>ja z<$w4|H&^+0?SR|tU)JF^|H^YF*UrJW9bOcDxjEA0+UZyLe>hb)zxsFWz=qr2bof|c zH#hrt?VwI_^W=YP=dXR4cHDCkb=>pB%mLIfIiJibrG)XLW`ec&vdZHNU6G&pf1?7kv?a z5`Fz0w~6u*zy1&ZX=H=UrX1MKk(zRMo2ZkE-^=_RziR5c+W|Lg>I1vESyPVshNndx zBimnjT~puP&VRxc<5@En?tbltDHGDL{Xb^=r&zvb7sh2Ck4w?_;wxjkM(}vK$I(4T z?l#@Boja2)U^Kt0`l-%rwVUzTANidZ<6N;H2N->U{ka@-re!xPU@!CGGgHh~U8g;- zvhW-JKE2W$!FR55t|sH;+C+V0XJAtw*x1nBrvK2i9#alHT65-qt#8^y9U~9$Z7ol7 z?VL&bs^^T>*IoZxE;lxDx0xmUWI!5i2lulmH@0#=`})!QVyhW!tK{tIe%9T-d%WCZ z`XaswzcBK+{R{Ki?F+`Xm}72io_&$|=GND(i(6m!d~lDidmR5dMrIt{xxO!wOZ?Y7 zXLpYD-{tzgNWQT0KUbY+u+WNNXmt9QOJ(D3d)@-OeZ=?$ z>}-6k!&%Z~_=@_nBuiT_Q`O&A&g=|z)TW(foJNs1W z6Je@c{s`5jkxymL8Kx?oV!Xwt0t1q?Y~K%y zREyJxsdQI-YJX&;`tU}W`s(^_RiII%+8ex473{x9mFds@P7POY^LyTtO*g9?YLi;G ze~;?u7p=0c4VPzsC=jg*FWjU``0r6WYi&_WHg8tT;`XR{nW9v^kO=khS9{cf^_x|O zp_^5|k$Y5Tmg_?MjVfL9-D<`3&C0LlCYAP!J!)j1NEOg+qk2?-kDAglQq79mto%>! zQ8&MgRQsQVDgTSR)yh&^)a0+j)vdSosIK-V71no?nl)pOYCk?gHEkHKy0C2PE=8!6 zA4I53OZTXSyCc>3USaBC``zltccRpQ+8fpQuXn5IN4BWyGs0EZk9VtDhayzOwg|Pb z^B$G%-WHXa%YP`bTa|wtrKWxpqPmBARoB=p>g=%)rFMDMgIZClRPYAX{ft+=780p` zuNkU>KeSa;vwp(PaSk<;$m@3b0wm2WHGK~#W zMWei`)Z;BG`}Q!^=B`(*Ra?}R#v4_ZBet5+af{mWTDUrLg_QeQw``vI(W>&D_3E7h zJJj(7F{=NoA?o+kJJs?7F{*yS5Vil-PBrqA7*(cIhzj&1sG?V+)u&-0YIsYpN+=ko z;wOj7v!4~&s%p#$RVym)RIilUsv7PIRd4RzrR-&KDp#&Bb*G?LWvUsY_J6fOg~of; z(wwoX-Qy6IH*kka$R4Av#)YW9mA$IZju=%hONgo%u~RiU9;^112~{7x;#Hq+icvr3 z4^ev_?NCRX#i^Dt8`R3~J5|BX(dx><5cMp=tIE!aQKM9d>h)@Z8ZsqTz58XT%DB#} zh82xbYo4uFm3r(@s~^RvxRD|1?W;S~Yfa)5y~^ze?NB+p#_|}1sR;5ak0(xDt`Vv# z)ZC$}7Tcm0gomhXo~`N&+M@dJ4^cag#;Ll$M5)==Le%-P+f>^}QR=7fLe%V9+f~>4 zThyp2A?h7ZyjpW?i#l_Ey?XvrymH&wZMXc*V%3kW!_*0G^KG_I!>ztGLTCYRc45_1czr<$l&J8{z@t!ll8{Dk3II&A%F|er_JE zZuH-x9*qfA-FHT-oa}>hj&D#8*2bvAfzj%%G8@#A{jm~15J&LrwN5cAf9r5nu4}X! z%Jw-od!u@XpTuYwf8d1bF}I_DqLl&A1!eaF|J$PEfRMT;}m1W zHu&C{NzoG95aYIev_)bYVqA|uq9nE<#&ujCC9w@L?n+3M#5VXUo<(d!jBDS?iEW5+ zzixA48)96VB~cRF5aV*+abg={+?Y3_CAJ~PjSG&F*oGK4H_sM{ZHRFnEr^oXh8XwJ zG$*zp#x3PO5Ze&ro}7=8*oGKaWJ8q1HpIA*$D<^+A;!&17cH?3F)sCDC$=HR6~4Yj zVjE)Iz0^)@LyQXvh!#J9KMXD56+gh7I~ME}KY%}Ms*oUl0DpM=)-Le__(Ncco#F@Z zhpFRtNW6hR1lHLh@dN$<3_rk}-pXyl58w}l;}gUW;12_S+$DYhe@Gd=Q~Ut_Fm~6U zpM{Sa+1%?R`~d#2BHM291Ng&R(LV75_`|$|Bz^#YxE*5uX+4D>z#m%q?G`_PKh!Ad z6F-1IG`nnzAHW}`a~y^rz#n3Z@%qkw0DtIl$QD0m zz#p>R^NAn8ADU;j#Sh>QzB?p-0Dm~}wk>`Df0+EvZt(;7L(crW#Sh>Q8%ypMKY%}M zKIIiZfIke)yIa;1tPL%;#L0SvwV^&^tO;g}uqI$_nA164)#`$utJ8LtUg8{R3g zP1Xdg4XpfVJU9%6M55ur^Hh#>tw1wIP4E zZL%g{Z5VYhPSymh4NX(-kTn5oL&u5nvL;|{@c$uR)#-)(Z%1gs6s3-3sF-{Rgo zAzqq!GQ3T=`gUoITAq8i+E{6m+87_L;(y$&1{B|{F74Z*@{Qf2T9$}VPxeNs(dYK4 zRpld9%&tha#BZkXPQL6OFS&T`UQ^ub_=WCU)u5T7Drd%>%HV-* zKHTh+;8acaz`VXEo;*ktz!FT37hpZIsN6#HBg&)s^#-mv@4 z2J8cDZ`l3#q%C4^*u6K$EZ7@%Pd_V4>o$*1pj=837Qt$STRu3C&QDer0tCPcGRHGu% zN%043F>DN5!_Kfh#sK!mUiA^P%AOH>M|)yS zQeS_Kb?#V=y`J&wZ{~)o5uLZHXF225PeGxoSKqC?{_arG>qFI=hFjIz)Vui3giv+Z zZ>zffL4vy2JWLH*8K<^bulbTRq)#&f8*c4_rpg;6=VAT#av)MY8Sd7={FLtW0@~>5oGDWNEt9Gdj&DW?ZmE)AxFF}3s z(`x0Jx;+UuytFf^PUF%X^YycH+w4wib86LnNqq$$KaeED=Z_91$<{LLP?F4rjvh|Z zrFqvQNjd@>-BHKb1kV~`vOx!>>)Ou5`vuis8*W zcqMlJ6KfWD4(2-uTnBg#-ft7Q4)7ezcM!M^@Epu{5V#KT9L#qRxDN0f%y$sD4t=g6 za2?<|_?#kG$A1FXp<^j2NeF`2-1=$K64I&@4Xa2@Vv-LmPk0Dj2NeX8{7&0iJ`;0tBuDJO`fz2wVqv4n7MIxDN0f%y$sD4)7ej zZzOOX;5nG@AaEVvIhgMta2?<|nC~EP9pE{b?;vm;Zacf}rq@IQ*P+)e0@neagV!tq z*8!e`*DM0p0iJ``ECScze%39U-qRAe4!x%(a2?<|cuz~j2Ne z=M;GsJO}d~1g=BJD+1R6o`d(a1g---2k&VKTnBg#-qRAe4)7ejrzLP5;5m3tOW-=d zbMT&)z;%G<;5{vY>j2Neds+h50iJ{Rv;?jLJO}S-30wzw4&KuexDN0fyr(5_9pE{5 zPfOrBz;p1PmcVs@=iogpf$IRz!FyT)*8!e`&vyi_L!Y4tTnBg#KHm|z4)7d&z9VoQ z;5qnwN8mcZbMX0&z;(Fo?6#ZUGZ45Ay^a&O4)7d&z9VoQ;5qnwN8mcZbMX0&z;(Ev zb<3vDcLcsdpYI4<2Y3!X-x0VD@Em-;BXAwyIrw}>;5sy4D$nZk9f9l6>jhzd1)hV? zcLc5jJO`ie2waCg-x0VDeZC`b9pE|md`I9qz;p2Vj=*(*=iu`lf$IRz!RI>y*8!e` z&vyi_13U+x?+9E6cn&__5x5TU9DKeba2?<|_2-A`HsMKfal=z9f9ir&%x(A z0@tC>BLuEPbGZbrLvxG-zCv@k1g=AKxdg65bGZbrLvy(Vu0wN@@~q}^30#L>cL-dE z=5h&Khvsq#T!-dz30#NfatU0A=5h&Khvsq#T!-dz30#NfatU0A=5h&Khvsq#T!-dz z30#NfatU0A=5h&Khvsq#T!-dz30#NfatU0A=KTmgcT{RHcC7J=)~=O6;tp?N<7*P(eo0@tB=KLXd`e%39UdwtZrAA#%8 zydQz<(7Ydk>(IO(f$MOur<(U8a24Fs-3bKnH7Lv!E+uERa1;5nG@AaEUeFGn~R zYYv>ib!ZNpz;$R2oWONx4xGSsXbzmfb!ZNpz;$R2oWONx4xGSsXbzmfb!ZNpz;$R2 zoWONx4xGSsXbzmfb!ZNpz;$R2oWONx4xGSsB)4yI@15N9MDH^R`%Jz6B^w}Q#jeiSHZXUkuzAm{K?p{aSYd5$J<~0cXhQZ)BOdX7)K3@~g*ZSN| zICs0(IQQP*W!E@kpTEXWcMNyyr8y-Me#7CE2>gcTlnDHW=9CEhhUSzA{D$U~2>eEJ z>!9Y82>gbAZ%E)b^m{`BzoFk768Mee=DgeQ+&Y@M0e-{G8SoosE@A!EXA`lr=9k3& z$*n>9y%>St(C@_v{DyunM&LK}docpPVfy-Od~?TGw_e~jnBySu8{jsW!S)Oo~*Jpgf8DF3M31@$U!3mf; z;0nyM;1Eok;1*0@;2ew$;3AA{;3$mD;4X|V;53Ymz(#k}F*d=o##U(4*bseb-i9E9 z=3WT0Y2Jn)v*v9Gx)=-{O&#cNo`p?Jo3Pb?V=lSp@IU2W|BX0fVkyo_CdU3d@z%W_ z&5qur_En9hP8Ij4J_o|pRoa84Ms`%+R%E#w56Mz1lH4EGZa~#5NfZJdmLHG@D8_aPCzX5K8IS%1Bz-=(c zA^Zlo4dyt6-{7+h@g7b%4R9O077FJ0PrTL&zrit?cr6ru1Kb949KvsKOeW?ygx}zp zOw4fzzu|t?EgSFuiO=4`QGnZEjzjnja2w2V2)_YtgE(S!5oM18{jsW;}CuW+y-+T z!f$}vV2(rh4R9OGaR|QwZi6`v;Wxl-FpnVo2DlC8IE3E-x4|5T@EhPZnBx$B1Kb94 z9Kvt7?d-N2uZhGwh434^W)X87!f$}vV2(rh4R9OGaR|QwZi6`v;WymRx@F^iEb-Y} zI11j!5_25FZ-Cp7eXNtqLCkRozX5K8IS%1Bcs(NC$H=qbHh3Q+{07G>V!suB1Kb94 z9Kvsa+hC4E_ziFy%y9_60d9ji4&gVzZ7|0n{06uU<~W4k0Jp&$hwvNVHkjiOegoVF za~#5NfZJe>L--AF8_aPCzX5K8IS%1Bz-=(cA^Zlo4dyt6-vGD49Eb25;5L}!5Pk#P z26G(3Z}7Q^m`4zP1Kb949Kvsa+hC4E_ziFy%y9_60d9ji4&gW4c6Qs1_YB1QOW`+o z9Vg!Z3BLhugEy{1i0C7R*au9PI!f$}vV2(rh4R9OG zaR|QwZi6`v;WrRJ5Jz+_2QkMX{06TV#PMDD4R9OGaR|QwZi6`v;Wzk9N6c{uzrklZ zVva-j4R9OGaR|QwZi6`v;Wxl-FvlVM2DlC8IE3E-x4|5T@EhPZnBx$B1Kb949Kvsa z+hC4E_ziFy%yE#;(S!5oM18{jsW;}CuWaS<_2=W-BYoX+JS_@2(?AjCMG z%Rz{7I+ueG<8&?uA;#%k4uY@hTn<8v)43dk7^ibN2r*9Qau8yi&gCG)IGxKuh;cfX zgAn6%E(amT>0Ay%jMKRsgczrDIS4UM=W-BYoX+JS#5kSHL5OiWmxB=FbS?)W#_3!R zLX6Y79E2FBb2$k9pmRA0b57@S5d1;sauEDM=W-DILFaN1{6Xh(5d1;sauEDM=W-C{ zw9e%q_=C>nAozpMajzjnj_yPPuzuzSIgU;n3_=C>nAozpMnAozpM znAozpMW=Mh9eJ-#{2r6Q6)=ZD{C<n4V>JXh&?szu5&pE zduyG`LD*aCTn@tCTIX{7?fl1{&iJ5PFUSa4buI@%2c63y@ki%!5c3_vbuiaN%y$Ua zfxY(Mtw-21V(+MPIS6}4oy$SkJL+5x!roEma{O(q!=A;&YPVnW8I8b+fd?}f=QUFY z=QtxL-WM|`Ci3GwGWL>YEpW#T?1^4xEnpsi_jH=XT*Dm~oC9=%3_5>9WYhT@BD2ol5M6ZshUlpC zH$-=xzaci!`5R&@oxdSAL|@Q}`3T`Rpc8b{`5Oe?bp8fGADzD;Sm$p@9i6`+&+7aQ zX;bHKB>9DzGyl%~amU+#%8&l381mnUr6zWP8wa1kyoPWZ;4_%l5KaSp2J;%iX@JjQ zUPCwy@EOc&2&Vx)gLw_%H2$e|YI*a?c9kN(slsR5Q@0Yc1wUTbi^7i17ku!QVbmwX z0>L$c$5X^Dr;a^&Dvh2WB;{9!&88o^4HkU!)&g4EyQ$z}Uo4@oi@Ys(-<4ph_Q_)} z`Z}L;HSZ@@3ZB<&EuFl7DFNkcKU_y+p2P(JXP&W++FhFO0q#0+E#3Lymf*#GS5s_@ zLKe#JHeW$At%ibUwpdErd|2p5d1h#UmB4sjo?XFyHW7{8zOVs?j7l) z<+}wB^R=bZAIuf}UGCO&>scAW6N6h&if7|RuNw`TQ$Ak<(W_qN<}~?@LSD#Uyn71@ z?lE2P_Eedj_i!HI=tLoW;Us|}t(>*wC~s1;At zxP(!34QJBkXRid@n~<{VXX9qlr+Z=(YHdncb=YS!la>pdHBLZhwBl zVlUdf@L(zppBCvwo4qav(XWTU^rFos`z9u<3-m&p(97Na)pB1-n~7bA(c7Qd(&na9 zgJ@*a2yZLyt9+e)RQA?#@BV`+tDduaCTkzq3hirKCH2L2NPx`I|bYb?cSFgZ3x4?))d4yT=X~?PDC>eX&hEXg_zc-mr-W?PqM>pHlSL??LZWe8;bvpp%cQVbUdQYr?5gFOLiEo^cA*A9+!5gS3{>aORt7^FNtObqhH2 zf8~R5bY<{0X@BC}iPSRw8^K@m9f`Sm9}pZ@b1FS8x=COTx!;j7G1yT z1y1vA588V1sNlrZT_{CZsNi~u9jM01p@IW0x24+YUKgD8U>mA7u)Ns6hTWRpJ=|UF zfAVN+dV5+P587<>unp~7K2Gq`a_#7ypv{8Y4-BNfS-%oIa&8wY+TxDjFGlpFFW0?l z;n^xr`%#bAGYH=G`w)t)^15K#8b!SxW)?hm@kcbZaeBem`c8sgf(Bb1w7}{6o=s&`WgrB61$|5*;URmGINdh+roF$ z4=3Lz@4mj?nT_tKu)3|uf7TKzoHCZKtv^L7?IIdjXA4#S>J|iz=bcy@{BSwlN*PaM*)FZi22-nucq;QKnyzIC zrn*aZP@h6u==l8QGG7ZKlbro;ANzy?KKD_=D;ueC zm&Np`Em5Y08!7S35-Rn?OP$7sQ|%JV=tpk?{kCHhwQjkbYHip>yQ)SI)efen_D=dJ zRTRzpJ(yzC?xZSzY@w9{R?zrGJ7{e7SPGiAf*uaoK~>u@k9;hgqVjK2OoolemNO=qByUh>G24)BO#ja zr4OT0c_WmaD@NT}yOGYd+^o|1$Eca_htq8S2BX3>{ubBCJy3X8sB;elYYtq#mDaqp zeD9`n59E6{oqHhPyXo8m`QA;xLsxI@lYC3OLziz$r?rlv&C@ohZOkXf^82gb3x%rt zx#HC5=8^RJGX7?)ZLB(zCz6hQ!S@LaFasA^L`=1=z2 z@7cw+`dztv->ToU%eQa(J-dASrr)#6w{QAAy8>T|ac29?WUMjHJl-h&=jR5*cg#Ey=(9t{mgc<1J&IoIDt39&Z_Ij5Ck7j5WrY z$6Ll4okoc$W#O}%iQr@rTev|lUa#vqRx@JTJd<3_Uk0OVVsdOqy1X(c$4<)Bzv-7nBaUONG0uqN7;B6(;yA_{2Xo459x7vsTk|_-_R zdSISG7wCa`23=k@hPZQCUp9Z$o%dL(Lj?W0B#dJD8=~j4H`9~8{N8HlZsps?>*{;q zlq*{9%Sy_ze386LcMjg`oM%xhRR~?~u~Utj#NYYV<9x!qyVOcPt5u)Qd7ED)$hV9p z-|t0o{BjiM9MNqXD7I3p+7=&0xeIKdwZ-H9WakBkBI%1p(KI8wE$F;Xo zD193hN!QMhy3~u;?cq^Wcc-m9i6P`Y6-B@O?v*?0%(vSw`@J?|j`_})=YqnVz$eh4@c#&A--bcO2-ihY|zO$9QJJwZUPGCOpT#z|| z`M`5Q<^<-0`x{1{3;2%rUw*g9b3tKFU_S6%kU4?*z;i+71m*+Jg`|56U-qs-o(oBL z-0@scm=iia$ehseLFR;x4>Bk4jroh*p{MO5_pNFBC>8fAfw!Sh?R1 zYX#G(j{dtq;!+#VA9Zp;bny|LHEocLFqiC!ON zJ|GriPU!eRh>1Er5MrW^56Fj?``q;UDDy$*z{?$OItO0vaKl=GIiceN@tUD@d>~#k z6z0Rxd#CJd0g=LUemnB2z43g6;0Yf-u;2cCv*3KyQqsM&n*^^-la@j^^Y?M!MSsjl zyX+9b*+R3@@9(b_Jic%aI-kCbZ?~E)813x+ zWV&FqpIB;&VDy`{#w5XzXV#vN1w+pK)yE2k{DpIk77V@Wb^B1T?}Ja1%5x0eo>afX zfH2#%)Bc-fwrPKJfjPG6cgWhwwvne|)emhWXM@dyZ6p7Qg9B`%7s`#ksBi3mc8q<{ zzOftnHTHx&#?Fw_*dOwnae-bdsySm6od2Nx_^LBT(>{y0KfBi?N%4v4!w`-*Q!qV|}iW<&%)$cUQrhd+NRb4*Zj?v?V@{kG6 zc%gph&CYnCorFv?lG@*K%o#8A8=B~h7vxD8Izj3{&a!WOBpC94p4u5Z=ryCw7%6{# z=t@#~=7RT=>VIAP6*BFdIhck_`%ijgAk*)xyRVaxCtK4u$jCXSV-7O%Q-+*m^g_AO z7xj%D(2lVW+BbGXzs8=B$JiNi8v8?jGcI}jPg|#}IR2G!+NV|@?O%PTY`1P4amFrk zLYTE(`&Y!xWma$PUr#E`vBqlu+PiJCm7x9WY_AWkS=zsT`FgNbQ2W=2TLY}sdc08n zruHw?kJbK#b|z{6Li>BQf1%$~)t&KzJn6N6LC%nB&KN=djc+>s1-*`Rb^NRNtgA`o zU(bG!RKH&Rl*+Vo==HS9w7>S(jLP(@qO&R^&&JX@l#w%})tk!5KOucCW%NS1(HHfN z9ng-k585|&L%+tJkjK~=avJ+Xelsr6D^UAav-4LhulBF*74KWqwSPTs@`~DD*72{z z<7w1b?O%lkXHb2$e{FmEy6Ua{OSOAL?W^wiS4i(1>SOI+S90W3L-lx}yodHL)X%T| z3+;^6{)P5OYyU#Oy|sTq9!vWdzwD&Bg3+&Er#XTlPwJtZU&-x2&OZBQ35NWm-ghwc8vd?>Yj;1F zR35+Pa#H;@qpu~kGj{*Yr1p!o`Yoy7LTMf($+K?XBiqQ?bI{`?`G-DxoTL}ZjlQUF z?0|NRebBzK8~Qc&ggnO1kki;7@|$rn>(^(^Qu)mK1#H$YV6%P!oAnFWtY5%p{Q@@Y z7qD5sfX(`4$`SufeXI+>X8i(2`&dVS&H4pw)-PbQegT{H3)rk*z-IjdHtQF#S-*hI z`UPy(FJQBN0h{#;*sNc`X8khdSiekttY5%p{Q@@Y7qD5sfX(^^Y}PMevwi^^{{lAt z1#J8a*!UN)@h@QGU%3EoW+hr?@j)%ABT(gGjczE>8O>2aXhhzHuW;M|9a76A0 z)`>Tqc=+4tM^;-M59232wk#bF_r3l^_8W*}C{O&xiHE5FV*@81qMg1v9-{rU*{($vI_SY?Az=pT{KWg>s`W>Ki+t9b+G~Z|sJCjXfccu`}c}_J{mt zT+Dt0V`ugoz-GSzZ1x+#X1@V!_8Y)vzX5Fa8^C720c`dgrX1_FsgHFW*z7le&3*&e z>^FeTegoL-H-OE41K8|0fX#jb*z7le&3*&e>^FeTegoL-H-OE41K8|0fX#lxlw-eP z>SMnFZ1x+#X1@V!_8Y)vzX5Fa8^C720c`vW*!UN)@h@QGU%s9(36$LjvxmLBESw(RC?KNsrdnLG4 z&o%0Yel-O5sJKRbzv8{5@^6mTPpThqzOi7m(<7?6V6-2dueD(G+c0Na!H_5Gk3`>R|_UBTad)kuB!LnFb* zXEss;5}OO2_f})|N4EC`uUpzg&3V>A@H^+4sSg%+5nSbBOVw#-55cwPys!G#>m&H& zXC2hTclrx%I;4vl*9u#cH-}jQyDhv_Logi%^LKSXLmK9r0NHD6`cL!$!hJBK*68Z4^sK+wiSH0Y#G&Z zZXFp&GZgv)}?(7OJ@m zTMPdE4CAg11%G^Pf!ZHfL-4~q^Hr{|D+z8fb&mS-wbFujRhX%AHz_Lk!FyAcbt=E$ z@KY1j)DyV`hov8_ejc1d@XqIh)ZqhfIQYvR>dgxdzInL4%H(tEyjQKc%G)xx)Oq+} zJ=JGY0l{^=)z$L1iV5yjGeG4_Sw?V7^$N=Vp|ap?=gTtBP*bq+HH=rk@E~=uNE0cK zEg7U{q^d7?N6pFVQ2yG2*Zn$Cg{`Y5c*@A}D&J<0;Ee;vs&ws~_S0S(sR9mFkn)W8 zhN{)Cl^5*)#Q^0k^RD2ui+Za{RUI5Rw42)Wu2bi?IUUt1|B6!Qc!qZBNUYOl{p_vP z)a;g&S2);Q^~hgcaE}U2Rf;G_wnHB_R!^2YGGAHMNWHSx(WPrdBbE4jOR0ZiZDZ9o zcRRtKjclrNCUz8jFK-JKFut4Mn4s2b-^gBq=geuRPJQOghvIK`QXAV2kn+N*yQ`Yn z1_>@+s*fsi+rjVj9;h~7cJQPbAE-(<2TGk<14pUa*_~&5{4!Q$AMCXG%MasK2Y;up z#5X6Yj}p5|{l48NtBb=N*>=lD`wOY9QA!k zH6)X>PNBTc(hf=Ws~qhq814Mjd9Yx#e>}Cr2cqA#6UIw94kEmFX|gRpdDi$v~TQ&evLgLkFhi4H1>!5W?W1>gpT9BE~~!TR8w@E zmZyT+Th`f2G6}RMUiff~WMKp{gA(EZ90R zTWu@u?2Bs5nWvgAt{~-^rYumtFRBVY8?jKWnpaQotw$Ui7qk$Zx!*#SX1cRK8Ip2= zs#C0&lrKLvSM7h>nH%{o%u+k+jgs>G^`@&-^_+J%A%%lf;%J9+o>Agsl{ha*>V%IO zu8yB}<_YG;$=c35@w?hZ4Z7fz|1tl4^+&8zzsl|=D*S-c&h@A|YJELt?xkE@O|?1X z%*g|xRn)ZdL#6%J{uR`|y?q34y--$d*xXt0msQKCfKqJ)U$=tQnX_A|z^{pPzihC& zczG+G2!2Yzp(~Xg5-a5eXH8YR-(F5fzRTz{_|~ONzFogBQ`@-QjZr5r*T0bRdZ81>`1oin<=!Km+k)?m~({kk#gyPq}quks||1V3YDTeHoPCRLVoOTV!P&RufA@WwlFr#zv>MZaCcftEH?mgjLgCe& zeaO5TJ^4-}XMZwnL_Zpw(b>05-ZYq=>+-bQhg0erPW=l*MpL?UPCKP{engehJMFix zFp*B{e$Q^3MC-FU@(egOnJ%?;K1YKhZ*CCQ~o>7K6BCL!SwqQXFs`W zWIt+G(823!_N2qQJZGgYwD-1C|Glvt$S&-(bC2z|ppeu4&`B-nw^L5PBPKVaB6%En z8aHV|Kb>{tEPAgIb^Xzi|8?$b%UWmuP-oR}${Lhi){zM#KBmq^-xR#GT@a-mnOAVY z)amp|lR|>y^3SG8lZy*}m~I{&KIg30jmj^ekvWx=-bJXN&BJ&7_%yFOR6bxNX3~I%1x{p7+KKri8f;p4MSFeR?GxZcPG-XbKm)`@z4 z=Iod3p!PIjlyhDf|8X12GNiZE-=3x=rTMJ8;GR}9`gVykUSF1MLZ_d$m-4TEZbT|i z8^I=a!JdWLM~1SG0M}yQNyR=6+>w2%3HuaqefG5i?Bl?@*a!Eq4+7ug*mZ+_6L=fP zt}E=bz(v`YFR(8IW9%M|cJ^sM{V|;Ep3Xk)yRzfyLIG!8e(wkVwsyI*rdO#ngSLe` z`?Pg;XVa7d&OU9>lX*1gu(MA~S7{;T>gep#@-F^_GA?xXX^H&38~hG?43zI$4^y(Yv?9=GvqY(hx}$-Ogw=NO`HKX@dwz%C14Y;fK40&Ht`ME#64gW z4}ndbH06k&ras~-u!*<8CJqCe_zY~~Hn553z$VTELodXC;P0Dsk@ye1VPqSL|G*Ec zG?w@e9CNX@#DCzu5lZ4eaOD$~B>n@>33^xJKXA=UWhDLsfA_R>(s-d9@!!-({0Bxm zi2uN7AMqa;{UZJYLmtF`V91I14-EMc|AEJ6Ttub&MG1C)vw67OB6?71vy?X+wTvz` z2^0M4P0oY5=H#w4=aR(?oT^-R`r5T%F(qboWN?2&>i*7jQOHV~w$9l@c4!$) zyWZGF(|MnnwUE>Ap^Z<;EkpU^-_b>u2Yb;gOTMKGj8~j~PE$I5L+2S6+x?6_P3K_L z$=AlwrA@o%H0FB;mm8i)ZXMH2ol4_hb@rkLW3PCf-vdnMayQ0aF%8!be8<`A8jL#b zXAMUEE8I>OUEg5TcRy<|>R;yis_7cp8yk%J?q>}~{oThFQVm_-VAOX%YcT469X*$- z>iYXMesV6OZ+ZHKRGrH+Uj849`un*39$J2b(Z0JcgHeCYy=Bx}*EbmT-On0~`XO9@ zrnbMqsPBH(VAMaz@=Vk94Mu(Uvj(I75w5@K;%u>}!Km+k)?n2Ch3y}v>l=*v?q>}~ zeKSwo81>!H8jL!%gXUA>x>X{Ndn}CoQO9jhx2@cEaO>!n-z}TFU$>m@`RSf}?s?^& zGnr~dQ1>y;xp;1eD5`bV!M^U%l;)Q6?%+hjSgI25oZo*>wUtulcitU*HgOxR$yrh2 zLuCARx-rW+@7E5Fr>ucaJlR-y2aOouygOLZY6lHj^`6v6dH*k+cL%6{^!vt1?L64x zto3NWMgiyD0s1}vW?QKPdBS+lgg6N~&o*?<=8%6?w~kT{y~gcv@F(wVN-FPGkbloj z*KZsUn$%9QiG0_xZohr1^-2AXIJTCIJm-F1lO*SuE^CtHpILTIl3pk``l7zE1KKh6 zLHovT=-1d2@)$cqPGf(_Z^mU|i!W)y@p5#!*FCz-IKwgCJMoPZ{-2~q*dVxw%C&4}Xeowy-3l!{@XFaz+ zebi|C?#O5K_~=E-v~RFIwfZwE-1s6LI@`PLsPGx6GMZo~PZDk4V3%W51_)S7HRWy>NjR6j&-asm`cp^tYJp@FdMeI;h); zD{z7KGd`Frk$MDtPkR{;t^b_TtX`phYvPc)Q}~kOn#RPgP!UtM(?;f<-0@R!EPceW6zi9JElV!0 zniz{UF1dExb=+;b`}+UOy%Q1Bmr%cxvGnGst+amG3i^WY{aC_dvHq)1sLy9Ux|?bv z6ZIV)~u5;o%ml*JlOwT(X0Xz8*`S*(>P6z#Zh@GLEvZSwT5QZl_Op+*1Xt zAiqr8sd4cXKKFjF<%|{dRi7Pnmt|`;dI^o>yR1jC%gFTb{&Fi5}nn>28zc z_Q39aW>DGM_AkpR;rWC)RmXOD&#wE~n*qRG?pL?J&0gFC{9&d__A4JO7M$vFQG3pc z+t-Wo*XowB zQWx1OI7MV$Yt{9i1(ys;WAzx8(MFx&SHANUXkAF~s1Me8YD_3ExV^WQr^QFr1b_a; zxPT&0Y70);aBf10uN>U0d_(WD#Hv#M%YzNxuG`)fd^P(8@6&2;30`u|-~Jc9 z%0fHb&o1-_%>5*wKVa_1i~fMQA20d?=6<~B519M$qCa5n$BX`exgRh31Ll5g^asrS z*ysEyyy>@`|+YbVD2XY{Q<*%=nok7 zLw~@qANm7^{m>sU?1%noq`Gg-=gHzw}7Q^>)ML*Gkib!n88H|rCWP&tLuX0F#)CRCZ%Q_4@x&Rsb}*It6V z?hOsdGu$aReL*&Zq3?_IYh=K)rarKd6S()fKyRM-&eCs{(PO=bPW2Vs_v5+VW!r`d zPF-!SH}jbf1>c{v&D*#A2*IgFAM)-Q=G2*)41fUCHh_{WZY@GZeR<+{ZWnC&f@}suwioHw$be@}ePAOeaP7}}+KI=e1fb0)m!b9k)X zuIP_dP`;wFyl=ZsVdm~E<4k_K!KK$4#^}lN0%f2_h{Vvp>wx_LK=HN=HvpHoqyH3Cs z!S|l_v7h?y5q!1SV0(7y6M~t_#Lc~x-2_MUb^=>Jrq z3;y+|I(B4$Q~q8xWe>}oO3F{&t!r;+c}1T6p-^*s)1keBO<%B;!D#bE`ZY4(SyLa_ z$O*i+e-V59wR|E&KRW7;xq4@@(rc@j~2grhctdq@S5gn>>QN>1jpRTZYS<2 zDcJM{*$jrhFVe4(0neKHz(!8sm`73G*~1(;hxLr|PA<_+`W-rclXqhCfr5XY65>77 zd04^c6Y0 zNkHxcLj`A6|Bte_j*IH~{`hH7DG3piMnFl4onaA`P}v2RT^bY=y9>JmCG1x0R&0Sg z$L{VHutmjI6a)R;Is4h~kKZ3Y9`E0Oug5&joqHzFlbN%Z<&tqO>UJq_-jEy_KLyL( zsx8UQ+mlg`2@N4e@6~N=FX=;i99Or!cdrS=_T3<~8E89=%sV$m z37nvA@57r9B*BN({h)al_f4aDd;iOOH9qiXHTGO<{N#FJyJpm(Z7lk>!lWs^GFd%u z3p{OU#`6Fyf2rSy+DvPM`jg6letxT-hdY9+$hNoY`Potb9Jx9`J%<;?J|u&M1hhXo z{ykX-X{gWi(WXbs)$=ENS$*0mSzWH5Z%HL1)%F@2?wdyQ_WsMhuKya%pVioNt*M{u zMoKTb@}(vE({mc7#&c~@e=UxnHZHcP%NxbfW(U;zP;e5JzB9-2OL|@DqkeU9(Qv%Esr07y3f#wRQ@m(_4bg-l%DfJ zU28mr8uc+mt=ce!dae*~|NnI*oBAq~QUB~ah;A=3LY=AVN#Cqph;gBXX%>C9@f4PC zX^=@f4prBwc^CIhqxty$m-lLX;LmF8xz_l}wK3^I@2~nP;dMT+9YiyZ+7PZ=oXw`y z=i8!gdU+yc&Ervz%NkFAJ(-9)ea;wqyXhj-zoW8g|Cw7+-}=*wPW`$Y_4$Z&`YwJS zYNt#keb7>^T@zAh%a!?9{$gD>TECtQwdP&iH;v~0{FnD?eBjS&?77zX$#vr znAX+2{`@U6I=aG+avf9_PVc$8p*DpOdfV0K|D*Y{8hfra_FOl=+kvXAK4V+HT6dut zlXdY~KeHHmd7BApjSv6zy-eywdn-Nh*$0oE>BW(1&TRLj8J(Ztisg&T-RT8GHBUAz z2&A9q)Wh<+Hcrc%QIi#}H0)?2>A&pj`tR1DBON*56XEvv)&|mLBkJL^g=gJqw4E*L zx^;GGYeAjwJ7D?yG4-j%dA07gN1HyI+zQM8jHo3=KYdXvthMQYl~UAo{jA&P|7yF& zhWGjG3+|Mt+ECZ}dD3Q$?Wl)^8+GiOCoPD#q8{mvbkWf~sma9#wEqeRn(--58lJ9C zSKf4@+x7CLyVlnd*A3oOc0W&=*Xa+b9TP|`cZl^^=+I_MJJ9Z`JgM0ZU0RwDLqC82 zfB(kh@2&gy=70ISIOn52^&IC!hg`~&W)&OJb`g$r<@7x1>r`DDI>d#l4(3VMz1F46 zs+?)ZPO#lOK*U8u2kp0p&A3riq-IM@>C#~isQ-4?qf=)(@*%g4ic9p0w?rJZWXo9}-p7hI&lRlOCP^hx8Biq~-~E(gq`I zNtgO{`;gSzEO4 zKJpK#%=AR9^~-|h{dK^1IcNVRo9DHrPp$K$lXw0lF`=z#z_(oKR&y=7dz}ZZD9)7* zko_Txk9pD)YjUO2#XkAt?}yLcivB~+Gfyg8H}(H~<377b)~9R5qX)+Z|{`dAjt0qamI1$dUG5Gf)~;sYB1baiIxEdP-llHl^Q&I#B1P(bB5J z#`MT!wbne#%cn#c(k53N(a+OWwPe^OFSOTaUZ+OuC5QZ9{k&bPOX}0wQx0_A^6Aof z7R_jAr3<|^f2MRuwh8??(gF1*X9GGl-3j&6T3!0>zBAfO7i-gujjd3}9yFtFlN_)Q zFWCMel8#>V?~pOlK83op+}nlbWKNL2T%k?(tZapC%n#M2WqB_2!`z|&=MSIHnzr+H z4Xe_l=j@!ZT|*}5(!>}Sn%}vDv}U9ZwHoY-I@9MbnN!=E@^)Qrr$7fY@^jkrW^x$rN+G3p(>Y=B#sHurNYUSKoGO(;I zws%cVEuk}gu>8eAZTi!C8c5yV6}K zj2n1p&j#*_u=d^S}o86c7Xsy39mgn`;qR+&AmOtB9 zTz7Gee6hVxbF^qpt~=^ALuyH4S6{UGFjAkcIpstRjb}+u_-Rq|E*{u#vbTEFQyjZV zO{Yt*tkR*aLS1Qk%W2YRcWr8^bi;XaH%Es?B)d}gO;e<6=F}3FPPm6;itDTQ6nE4sj%w3IS*@@Sea;xtsVg0+rB=N3(oF+8L(hpu z+Qdj7i)(h3xMoqW)u&e5)q3DEEo$Azou&+sNDId6(Sl*lRMjz8n%v%i&Wv`V9Z%1e zCdcT~d*fYD$A@as7vh-@FAq-BqLx+e)Hiarv}~y^wFz*+erWSrpLU<*MD5SdlD=M| zMcegvr{+i>EBB^(l7mtsCzd@s(L(C>XK?imt{Fp>Nr&z=dDHi$9d50 zKeMI9hJVQNY%khNXQb45m??D>$I)qGywuB8n@&t}qXEmKrN-2dM&5R$`riViMMk~(_&0~ z;ZGO!nHq(^6Mb*9&jO_g4`u1EF#oNo;zIt?5kr=Z?egBOf zZEG*?1JZ2i)js;P>XH+kbabRNYM&Nu=I2gl{TV5B9bZc>R`_7~Qd1-PZIUBxb2wf) zG((?uxZyu|v*Nljx-NSR-}8tp@6ZXKjUEMLU9tjo-8!FcnMryC$71=~)~hJO1qx)FA)T_xtln~Dn?9{mNwXU=WSi#oyvef9DrB3DHZJ6%G8Nh8W^oJh zen&54n{ijoNa^=s$TphuWd2@_=6?Q{Gw`fC=|pl^hHO*wzAs@XWym(IBnlEaR*r0Q zr;&;Pkt5sKTlFI+PsxyN;$C%h`XdcHs^Ev$%fBy$TovoyAwzKBxIYZ&7H`-W$EafhnEL=(mN5^ zX2<6iWNLCRtkZqLXyU$Dj(gFCMWaa%QFFGbaCRbD1?i~M?5C4ESuyCRLAaD;9*ae` zN#5>7rn;-|P?Q$#H}YLNS8ga_^#N$64GV40@+6Of{-sM3S=Ac zzeA7tL%O~hLr7-qt-mj8Q|Ho z9wb@FNyOJgj7?(;#}mu1 za@5DqbtOWH40Y}V6)E>s+rMy*B>PWAhaft z$i?>xWEQm3! zlOiDo^&$f|GWnJtbHXB*GyzQjydg<3O?yzQy)CXnupqLFP}TrI|00`kn~lTuQ)E*5pW%@c{9do;#e)1;~7u=p(J zy1Nm*$)*D`)NLMRkgVM@wAnH#i7fu4EdHLIT>nU7bosT#+H$Y`G{U25V!n-?S~0Npo@RINK~}EhppN$dPScPYolNgJN)= zSeMAi%NjYdjmcq8(sNNfvdsv41<4;TN46OZDa8J+4EK=g_)u~}Twi=`PHNSOY+f0S zeK_q~Pf{heg|p4u+nJ1j+idxoKwcY) zd$Pzj84=xx{GbdO=GeDbvU9SyKZ`uG$328BnjMSU_GbtwPL4&kxj!t965iL*_`_!!b;iyV1o+vG43Ac;Zk zQsPN$m&T*buzn**uP`~Xjp5eOM0=?m+2#~;C9<>0$Tqh(#*;P8<;XU37ABGWk1`yi zOHok-T%(a^@@K@8GcCnF5!uGXIGKzT$CtBBc4jKscTF5?k!>D#YfrY^ib1yVIo^ge zYmk8DFFbk^KXLAHw(%pW#6yhBoNemYQ;?Sv<;XVOBLmfQUZ-QmFZY?Ut$$*XZAO{g6|R`XBR>eG^~C#e1;*k( z3A==SX=%tdu^sjay~0zGTS}%}5InafpkBDY9{VfWbDtl44`l`7Sn#u*TJ7CJx_cV3 z&9Kk~!q9qsu}-?!hne^(k!}3kyxB%=C9;ho-G{|^D3NVm*LGxYHYFh2 zw>=FzuzB7I$Tp+q_GE9Db;mj*&)pFO>v-IY{7&5wd>X|g4@6FiV~-l8qVA(}OknXz z=;w-37uNEN0@>!Cim-mmRccP~4r3GcC7^xZ+dfP?Sj{%&?Tdx+Q7QPY3ynNjjs8sGT-*-z)W z@EnxL41cLMYq4K}K4jP0vLh|kdT@gmg4aeR`q|^811ngq?sNaM<-$Uh3hOU8(Sikv zti{i5>Nj^~1AeQ=F{eYhV9{NLY%}@pPvMeP9LD|1D-BstO)Roa*`7;6VM+qBO8bMi zgtN+c)S72G1B_YuLs;SxhkkZA8NjlCDbYrwIooJ7XB$oZoNY$iKM}&URLCd7V{&8|S3fr!Jfl%yJTOKRo@eEjzMD z%{DiVm@pSz1+vY6m?rFzg96+5@U$5-{1uCAqw$Bwca7%l`e9?p;=>i#uG&GS?EK$Y zU_305=S%znYFtX73K{p@-$`HoDC@6XKN2nz$1 z$TmLrs)Qw$N@N?e6Q-=cxPJM$&A8dk*^N#L)a$Ej1ZVF!jKu@*`?C^p&*Yq=8Asms zp&PCUzBUQSHaj=`5%QlXkZn@qo3hPq6v#FT9SM7ure>R{qoJ(kSv>NLmZb}Gey%`0 zbN*%F168v}?-!?p3sV!Z?YC!s5eCeRLtWtZS9tM2fpNKLvmxs(RbaX7wlCODG-$`FX2h%cXQ3WjJV=3T^TWu6wST6bC$B9H**tOVINO*l zvShVCVv%j$6gFqCIxBFV+;3#X0>wGN&uw1Zr%d;$3fbm)M>9589AAEJ(|M>q%jl-S zJtXR^1G^`#FTOU@I@_{vTLt!Eb$PY$s#~1;+@@QtQ2(<6c}5ki&1}Rq%h_hebzKJI z)%rrJ1ADMUfo$`@uO8drra-oNV5!XnvF)5^Rt+^{zeL}--caDo`rT8PM^1HOr;jU; zZG6j3*i0RDU)jvpVJ{XdkZnTxiheFtAln>FwP#DGE0Ard{wJYkZyd5sqp_cavTbq5 zHrgI8tjkL=PKoC>yI1?OUYFEt)4ttB!D~(evQ4+*<}5Hu{CiD2w;?Tl3awhkA-AN| zYsj{Xdj&tM*|4@bGwGs0z2_NaPoJsK=66!LaHg9I*(PT59bt`aJhDxNb!RqPI|`-q7vW$Y0A9%2lmQ~j~LuAiD*G9G{b zmCvTJ;f(Ri;W5kjlZb4iwYh@XPmv+pY%+VuhRtb*Y?J%Ef}QgXM7Bw8T*(HX_CdB; zcUcR{e7x}7#@XKxP8a$h+eAMy2irS=$Tn9eH-o$=DYA_wPmI4;qq(2|CAZDd`XzG@ z@I|({Wbu?;AJZ1uW=5|nR+{FGY_rnh4V%Kek!@ZYK4pEUv_-a&`&6+>{k)NFP7bVK zJ@yA8KTN3in$?*2V62R{e8>h33q`hxuztwGLfav?Jgq2WFc_1Qu})o-T%RDCC9)%-VmdEXP+rugD-w*ImDPRg^P z9;CW?BipQ&)Pvcle97FODjgg@?>{I7DE-L@Z z!al3-l%q2qv32_bu>MEaKQrTIUdT3UUB0t(cRaEDm+TQccsc;t#>?wDOL6zZxW9Gj zTej2E8`)-Oi*nYvp9EQDMe_=FvtbZw&9j^V##KLKJG=OypAm2WvTzIaos>p%w$W(L zHk$f5+Z=xMi2afTAgi3$DQ6RPIw8YYEiGrYhl5Z*h8JvFH(%8G&tJ2+bKYoQu;(LN zlj4QCLwFgR_l#i7s(=3vJ67w7=Qg8HzhV7zype5kR()h~>EgY+=+CDeRZJ4)jclXw zhsSq~=IxsBsgfBD^}%-eSyr*Z!@QAa67RobXRdjn4)OlUs>N~V?Si=1>{GQjvQ2Ky zd-iRW7ix=pJd@aPL0uIGii=9V5@$o9tep4p}i z?)}x}w%g1g$vhC_`-_MtEYZ{-*=EK3CoJ|(TVxxfpelB#k2ms6X5@eg1&z`fU7krUzJ~sQrX34yeZEV+R!6k1m zJhxeJ+xpNGwV_1Jf$tze_IMOo#$qZ6w*B3sr>yHIKh%4FKWCD| z>U$+g>sKsNyuaXQJDn$2v+b`u@!2u{IxuCf7q)ld*RSl_M^DscV|74hgBRMYc>9ut z-Sa`VF^R#r>hq2TRC*!Xd<^-_Ub&0=uz3G_bK^T^^w100 zrr!i@7?k0KY;$916}z46jcl_bypmnn?}K~D@<(5pqqx5K+SF_Qk@*c)_u;_K&sgbh zKV+L9o1e3duYHkc&WdaHg1BZm+bmr3lD(|)LH&2jS9ZGE6WM0o^;hh+oe#22yE!iy z8R?5W6FjquZBvQ+v&c3t!V}r%&W$(h#58a0hh6qB*=TQHWSh^s zzOrbsetswA?(~(l{41^n@lNXckf-dFq%E?|tLaZ!|JH4hZOk`+W39!0<7|^0`j;8% ztM8-&zLqiXof2f5)={5Xp_>=7jojoplS=)NTV$c1*-5cKIoq6*zGWV*yixa?tPReY zUT6~%`-qJ`5rAxSy;}tvcrp;#CgYqwsGfQw+jw>tIj& z#a_rZ4+g(x%ioH9B67~Q&y{T15FcclNqUtm>5BU9sh!_fruD}Y+2-_LZLpf+g=`b~ z>M1jS>xXP}!?KdqJLiLJGk!u9dz9dfY@=)Ugmr4|k8HDN!&heZ%@f(CZjSdTlR#J- zR3BO5U-{m3V{~2iSo)$VG;goYnVIV74)gA)^KI(ZX(RQ4f=n%}Kc=fU^y{t8)%ot= z5ARq7=Iz`KX$QAA-$A|4tP5B*zmK}EpPIaJ&J6#`UDw!f#^_B$;Nc+~WSfRhf*>Q$ z1lgwh4<9fbrh{zbs`M8BU&dF$^KHD#eZcqXOTzPQYTpLKO2u8m^KB|mbcETn?hu}D zbG=0jw5|7m@O+!7@2QZO|A6p(8%<6)f3HS!KmSV}`-Vk6u*BdM;rTWzc6dXJi|+`} zw|Udv5AKe8N_f7_rAxjreD5>D^KFW^dBec+cZBEL_-_J`?X;NcHXHddf+IK&$k7kxy3BDDj-%(x8o+(d5( z`SKa-F>?%nzHQ10Kc9)$4uYpu53t-?5dx79?+~6pv#p;u_}{J}Ja%h~bJeY;8ui2k zZ}{5$3+l7RK2TNm2K{N!!WXucy+FNqw;zO!eS$i&X)t)5y-RpZ|GQ5P!K>~Qo(FQY zZx@&~^d8}{3svTyMW>Em2)=-=i8;khmWOT1zG*7tPq` zqyMG#{2;x-GxYz-cX3`-KfrRUp>1L8yGMkdtGMU{f>whvoS#RU<_+z9vd9Wc$Fq1+NItpLudJ7@iHkOL(5lbDwtLwdM}tOmhB2AcS~6M7^b#xR*|? zAw1WmY>hX_Zv7&hH!fZGhRlg?QICo8fdPYGqm6;LFBlez7qFtu-pD|RFMWvR*HS~^ z_uV@Ecvx7~Jg~%e~+GK<%8D zWSz|nY35;HaesS;b8L2VUl>>Mf^gq>PMay`(M|eBfD&O7ii1cd2u#FW5DBf#W;R(FazsMsu z$0X_9G;e4%_dDTtUgS*xv~N{Lc&^Tw9^&s%-#;h(KC5Vm5A53Wif|TcDffebjHjqi zYzPEfG0&ct2lNUAr^OEm&(%pV^#keOr#KcS%Y2~G_e#QZbpqc7z#^wI!nx@B-T?SE zsElwf>bJ=U`amUlADttup6vst17DHyYcr)=5_}+`?P~(JW=J=+41hMimA`aKOx7wp^Mo&!gGH5KKFwJ!zaYnb&7PN zWm}MMdW?PRW8njP*c-y{zw%%D!<1>|gmYBI96ty@^#pan1}V&IbQf*5i~Cq{qc4Q# z_N0k>eyzNk@Z6q3ZXMua${oUUdsct;F05{RugfhP9>hVjx~3Xzu5K`MsM< zKLsq+Gej=RJ+6QW^(>K#&Rr zFaGWzAtMF+?yi$?Uh3+S1Wl@f3C}~m9@zu7Pfo$u{bEr998i@?I2WDmoB+S(FbU_P zfY}L9wWCzRxoB;tR0zCVDB)c6Yexo*vn!BrW~<$o0%_@MC7g>cOZ$R{*(mh$_?I|X z5^9h8QvI)S(6pmHGRBp)8L*oaNH`gFaDH`A!nw$CP6~X|U59=ic##0x4T~k5C9eL@H_mdK+Qh+|F1E-abNefRMj4_1 zf6m3h9LvY(L%e+)EZ*H1{crL?3H1xFq0hln;-KxHX6W0;u1Xj=|E`4dQoq$IxE69A z-}`x19Q=|u$2ePWf&vC-86$fv)sBM??LSC3M}0k|gl(%`k(W9&QNq>P4yZNHa=tn` zMF9uQP0-JeLLxltyGO#yxqd2Y&NG^F&QY5BIR^&B#lfT6CK!)A7Ig);d(jxpgy@O9(t|(KI-9HlwkhlriAlY8~rqZ*DEBP0VcIfh8wP1vAoEm56oiYB%D9@RVkq18Ea%S z(}xPMIBtb(=5|p5Gg?$jICljED4|-ok9zQQ1!VR&A^Z;O=d?sfIlouJwPqZ7+Z!)a zg1A7DqwWt?z=eeRgy$ij{}=~XwvR1H~U!#rXy<4c@`;03R z&St-sCc~{Ao3Onl)k>(0y@tB-Rx%Wi+K4tI2PnYsydLtE%TN{UH@S%Y_90sVE&O$m zc{;hoLDyGR63#g{f|PJ(@qJut1wL`G`tutJXPdh}lEC`gRte@I-&DXihp!TTpXD@I z0dCK9aSz!guCIh8*Cc#xzC92J4k=Ht4U;AsmpcyK=?V&9C6-0?P7%b zqd3-O3-nQ+eWV17nClYGHd!+j5NV=?Z1YUCe>Bnv8K%!21uVSqMZ$R|CS3)S$}ggB z>8AqA^_L}_ZF(G5z@LZTupe58^%p-iK(;yYLw<)z`7F#%1T%+y5}t=FR4T!JPAkImkiSwTOz3xC!tb*V zO;SM8d1K@d4~Y`K&bu$+taALb0ifz_+663#R0bK+oBXmey0*Kct!FWw$m z<@@(Eh?%-n!db;%?8Bi0Y9*Xcw8Z&Pv|k(7^7@20D6grMa6Xx}NCACY*P^x&*QS}L z4&nD%)?%Ffo~uXreb((GN@#uOhJ@!KEBhwH{ld)>UcP#b0?x&n6P~LxL$r_Xp+|VG zPRrZkzW4EqgtN`ZuL{tPZG=2iP@#kY>DMLvJ}a?pCKP#jGUN)a1Q4WwsQVVjKr{c& zsGom}0+((>P+PJXI8>OA`q$$`NNBJUb=}{O|CisJYixMTEi@Sd`;%KT&K}t>vY@ck zopJVPVVDFpFZ~#257-e4(`SS;ekOC{j11n~N@e^^#$Eg!>aEgQjI&2Kao&dZS;#nh zC|9OJ*ynYOv&ZPHEO6O(fN}QF{7#&|SED(5{FmRh|Eed4nQ6(4pULc55DnKqL^FOS zW7(Pv#$$V%bgI}_qjI+lcO9iaa3u8RKyY!Sn zbl(id{h9VS2|RE4GQMA}Kb#1$acvpriZfy?$R8epda`IAnU%q~&&!1vNZ*x@ zz}?D^arPK|zb8bvxnrFbz2x9EaysMe5zbY1B?K;h1oIUp6i-8K=0(|z! z0yzwq&S0E9G`?}4J1>g?@#3HH7(K4F9Qw6Q!uQI*MnT@V1=*r+j zW*^4cLnSiIp+4;xkHsxA70~~C2h^Hpd3p6AIc)l^L_c#HM8hcG9JJABUZ+Omz0CjW z=k2O`5d&pQIx)@?UAu}r>DGqvm}~J-0f)rj+jBk5Q4Z@SC80hZCIici?r49xIttD; z9E!T&j1unGQ0&9;m*vnyGLv!kIOisV7HL_Gvq!jSpZ019w$aH-T$^dV7-tVnd-;6U zXx=W{WikkVkdE!TZ7&ZBKTovn?(zrkBJ+EZ&ta1wD?J7)`L7YV<=)<0wRDAdm%#lqp`bFsa9Uq*v# zP%f5dO-g|wE!Hy59)q=FAnSmP@pGZQccS4~j-2sxA-TAIt5bV2&K?8xWpJ|12-NG& z$)U|ICF8u&&s`>7}N_sM}hEYF!teCooE;v6vz0P ziS2kf_@0SpoIQq#YZk;c%XQNiGFZ4f1@&29aedj2VVpgN4U$1&WjDspRa*GS;jc*& z_Yc9p?u%h8Ophb$`^Zhnek{5<4fN;KrQie>yfB&v@L^z|n&&K}*K%fV^sOvc$` zxFGWLnGnX=W4(b4`lOCvoIT3+%V922G0qhU^<=QQus7rEVJzB2hmSy=c`X`>KFmg& zIf__lTOPsqImrb(1%%(}$oM%)cahb@T;?;*9^r{HDD%%`oINb($Y8#rD~{1}v7ZA% z2Qbbal6V<(jL$?}zElSF%F`KV4|+)kP8(AhXN>t`pX~J+%{Y5BZ4?9ES8}oZVe4pU z>aSp&J(iu5f%W-R#@VAmV;Q)7>&ZBKyb|sEhszj0SLq>+QTK*p7-x^V-*`Et9}L4Y zb%ArpzrOcUH%8ZGkApt3P?>iOIb`tD2so7Y9Ch6~O)9)0?YS1#zc|Vbz75tvo%75d zCO@o)`htf&v@f+n-E6lr1gvd=x~`v^@5b=>`>$`;Xl!^)U*0$h+>8u>vrWd)b`W8s z2b^v0i)VNCU$ua<&Bi=;2>z`NoNe4noxpvPK5(`ff7%YL`&s~Jo3&FNpr4T~aJE^s z+Z9GdIRa-J_m>_3gS>#Vjpmy${Jk2@{roTAvAOQ=3?}vUfwRrW9j?$x%-i5>bKS-f zW==2!&NdHbI)c2y065#29dL!M9d&`TjjWX;OwKX{&NfFIdO+b7ZQyKEQt1djJq&>R zll93DE}Ccq-w&@G^Mw=dwScqDk&rg9CR7`B!7E4b?ymk8&<|I8*m~3o%bSBAIEi^G zoNaFJ424t4dRXWA19sqHYz~}lCYRX3=8a~+*~a3a9r*k<1I{*`v+Uvhackggb780> zRJ3Y}zIg`Q!|rC*z}Y4|&lUdsb-+5`H}e4Ni`u|BVM%ijczi({INKZ@;0PHlnxej) z>;=ESXaVnA*)Kcrv@ikAHeNUFAY`Kjmd_A<%WGkd_LuwEL%W;SsC#eqft8Q7@LlQG z?cijvDR8z4d1wbYuS|fmP1YAXAni?nvrTKUo_>?efwRqDUwcUZVujB-iRBZ=n2Yx! zQ~%F5?(?PQZUFf@z!_lJaAz1H=2&q5*FCg{ikJ0J@2_bE^9ps)&x79fkYj9&TF`fg z?yYsO{`Dj6VXScj;B0g0n;k4_ZGz80*W1d%)T~YOQ&emrHuOKw)D&^mFMUI~YB;A=+y+uT!Hr18C~!?Xt*m z1E+2}z}e<&8im{|I>33RnM-ScN!qAa_Hc&ZPxMf0Ep>!@=M2z3{hB>I(5;VJmEs9L z4Yjck7Zlq;wq8TvY_q?MBUJhr0%x1Xx9p+K&wAL#^E!?YxY`gn+i3jZ^I4;LyB;Mu zf#Rt?w(FFSBcvx70%x1Y{T*QGW+T+y&e*|_U8ca>_2;4^G?`%loNW@^9N@Q@v&Hq9 zu~H}zzmdq!uF1;v;*BPmRO$N zz!f^{H~?oGd6!nu@3RhYwka}g1qU1I0%sdv7f0CM+YmV094N2{tz-33SB!Fjp$+ta zvyFpb2Q{4=qSlNfZ@d4*)?nXHTRiVmN#EXchWsgdz}aT^A$y1nst=rPtk2uQo?r{$ zY~$i&4=szVfU}LEu07m+X^h%=cWb!cRa@LEXG?2Tp72Q=7vA=1wyvPRR^1O5FE~R< zz8>1RhdM#KT79(H(!w4Frx|0pcC8&8xo3&(HTSfKYc|HHUFzAxg_c%m)B3U#Wc1eu z&Nfp;A0*F>vELRYJ3+w{ec)`O9%2NXZEW)G;rprjI8Sblc7Xf>Bj9W^@QEFq zX=VwWZBnfq;qFvJ;B3=jqZ8a*sE>Qd7;k%+VPcFr_pLo_JX8<+u=s`xthuZUoNb2x zat7$72b^az#Wg!kT(ewn`Q!xSJL#kT6JQUapBn&Yn_jh!klNV*INK~4=M3{N>j7sQ zCsRilk#C54w%Fb#r;Jf2+t|a4iN?U$CN07dJc10dA0~S_!(KCe;B4a|*1xT~0dThQ zinNEKy$yh~jk32ZBn;67&NhFOT;aoLUEplRHhoI%U|CQ@;A}I!X&cxW zsSTWM+;i>W&4v2F*=9|G3z$0U0cRWeJqNISW(b^Z9_QJ^y3_Sh-xT}vmiSFuZWG(c z9ZXzwfV0gY2MNXwaMAW?1U3Yvc<6$*``ytSf|hcINOAM6@6G|iRG6qU17}z zUEplm5!1byIabJ^Sx;%6BGXPf5zT7myl9pG#;CD0z6J~jZ(Hg&(}_HgT4Heym3 zvc$i>?N&EN*JY1U^=v@3t~EYu6krHbI!jR3tutHxfK~05V)--wi>yK~70kw{u_U{7E3WE;JP zhuM@;DYA|2y0dJmT`;nZ&39lMjYE)aK7G5w{M>_)ADmo{u)%|+7!#u|JYqVH+9BH* zm6Ws76GD(%?6Yn%qr70$<60eI4+lvx&aNL?#I6nQjODol9FY6XMJ|EK9X4U?Mas+rgynB zvdzXBMXbUk8S4x&y~<{I1mj+`+UzP@E^5vO0phc#+r*+CJnk;*Y^V0Kyz72ulhOg% zW?I26mY<>iw&8QbBKCPk7qmapeGl_92uDp$JY*OCsQVWd{S)TJtPt z0GoNISVfB3&+g&7*|d}hwAX0PHX6+tKvO?wo3K3>*?yB?WTAN(CCuz)JJb*6-Dbu&gRu`s?%2&N?}sDXH0gGT z^?fTvwrMxGgdMJEhizOw4OlbZ5M&#TKRmu`G;ddF`cWphO0oZ+S{`BxbwiM6t}PQ- zyO(Nxb=O|zdAK98&C9!ond3Am^33SnrEGtvcBoZhAJ`|CaE#r|>KaQA4n|fvW^tTt z5q;*IW7+l~+tRc>YO`xQ+1#)wYOo_ah-O3JCv(2GXtY1Pf#^U9pcC*#C5vVoe$lJc;>2OujBQ^^&oD!A{&3EjU~`hSn5nke+2kmT43J`Ztlt4Pyg(9 z+uJ$k0MpBDk6Qds7K~i)q_$abjCFexjBL|>;eIyEuLJhm`ff*AtT=X@ZK7)gHsDwY zvW*Z?%nptX#d&h~l)%>C3PH9RAHIu?xD|7&?wU`!+Y|}NQn59h$MYee};1nCxH5j?&do5#!x`iOm zTnsN}WLzj}q2n&r`)(xK^nZSdT@~jlXPbStSDB~yUd}dEOLj7QxeVE6?%BgEF-MAQ z^V9Jtqiv-)MjKrOrnGK{JmV@HW|rcW1819zw4+S7mADUxY;$+yF?QlZFfz=AKL^;0 z;P%KiJAW0i?eU$koOqsLf5f@R*(S8dF(&;YYLRWUcLTfb7=mo0B|Xn(Hw;F$xmJ3B z74~h9Y*Y8!t-Af52(vcyK$iH|cU_DtL(b2i#uU^iZk0nA5=Z=}?cLn9k~YTFieObSkVTme=)D^F3G|7yk84 zT8#~74De{kk_(3*+nllgB$Pktg>2LC;ZZ@Al8S6I)iqyOToR9Lv&hq15dT92vdxi( zg@MIGlaXyaW~>Q%GPy7vdxo4BPF&DBav-1-+JZm)oAYLfB8ObkH_Mt zJ}xSeZF;uoCm0P^A=_LrHxw?EDUoe1G_e#;iMbB^+$M2nKjFtn6|&8>H%5Z&o)Xz+ zwcb3T^mjb+L*b)lLWX#^%Kd5c_oVR9G7Z^Al6*us)GQUbrT@3p!g`vBdg9k+f>N~S zK0AiB2^tusw(-+DDKxB1MYfq!@Kv~Rq&L<%cUVpF>}!e0HeG7ElyojgM79~z*{HxpNw_&3v09LDiiy(KqTrgZ3^$l9J?VI%Uho-D_&ogi1x$R z#0TlNO+(%FTB-1?gP4mW_Q|TUFC}|-Cm`Fbp$$rRPE0_y`Ih2Yy2CC3*~WTT<6@uY zNys+IhWKn%hmt$jk8S?mnlL|qj-$1gFm$sw%iu)o<%mxO<<*! zb5y9Ge48ZL)TqDDT={Ki>8?rf=yUJjSwg1~@mRld){@c%hVjTY?@#!a_OMRC^7Xf7 z2}Tp+k!=hdVuj&4DvbM2;(wHO`z7A}i|01iVpj>VwPGHR80&3MEfD7UsI}%gQ}z)MvWTGAJJTt;FF&^#x_M1$rFjG)G%j1Vjc`Xx2Ya6wX}I+JhF|=HLakdJ;l6Ov3%aNZh}oa z6|zlQmbWlktcSBrn{Wf+s+jx2&u#3kWeaA9RLC~%Ge(yl8XAvmQ};XVarX~GdllcEF#5*bddj;fRdKYAy?JbuPo!8;WHaT|tNe|};WE;oLN66ZHosn&P zYOauZVr~JyllnPa{LRF^WMmu7cis7WHJbbRU%nw9@?{B821g*<$QmsmtBpD#+Z?T0 zMUMRpL$>KSdL?o73rDsYXS9I4G3|tG^KI`cvQH-**(S}ifVf`mqUMLV6(qQCIL5?{ z9cL0FJteZugHtofiF*p<8N+kAMCYIk^_7?vq(rpmJ_jb05QE@IEYC@rNm8%GA=~6^ zpH7ZCWni7sox8}wlyGF5tuKm*hcq17rl?>Sc^w~)Y}2-xKzvR|BHMgueuAj7qR_XU zKTAk$|43w;#*?m)UBwEl^N?Ku*>|rC?nNJ37LX42)n_j@CMQT#S`@N@_3K&0XtnyA z{1JDz5|4dh$TrJn?I-)fBGCUdB9OaRBGEqO>Mo*{p+2{vi8X+|8Q}h=ZB$wqdSizns-J&7o6Hmnk`cQuYs;J=Mc#|^|{c8 zeH%&c%rIn|Fyn2+xHt@bp51>Ac~sjO*{0jRMPz$T1hUQ2wyTN3%`jve8}B@_R?H*e zv3_@HKJj&oLalk0mroe5h(uaMqMuD>?IpX!GZS8}(VT5GnzN0je$F=D{&UHQ>79{J z{B>uLsKOMCP1D}xk;233vx~#IOUT632rM5JzLGql;b=c?+InJ|7lu0j$ZTSEK#u!i z|7m;3->vF%n~}k*$XUy9WSh%_){{cfp8NAIppZQL7=~=4@rTEEjpqKl*(@gpMd8@4 zp!usvykR)qmWh3j$BIIY$8zWpV~x*h`w>oF&M|lMoA}ZZ`YCo#6M4MGr#H*+3-FV z<9p+V^U40{osext4V_Q;->3XeDpFWQinPO#XO>uOB$sA{p?)2?hXKMGYoY^N*+1uFThr^I>!l(#j8?BmEr0I_^WSfr4 zWn^?&IPM`U&TJ;W;`-uibJLr3WTJJVjdKMY_o6iW)i$WJnI(Oro7%}(zhTC+2%$50&?VL zB(ja|<^|-;xkzN2-T7O|PjT${oz&15d&ol;j%?#vl}m~ii@7Y~oz!f%jpT|rm-wAj z#_UC;&`^CQ)9O|sf$}iqnE@@-eaqQqO}_)=>gWh$8;c=xNP}OUk!?(x6p)_fU65_Y zyB{J$Z+AkrF+RA0G)f3Zw&@YOoP1oP-VX;iUrU;9727WIOz^1{get|DCF=2wmy?p6 z;yxgk(e-A^pSyeHQd@k&SY|}M&Gr25|5xoTV11ryUc&Eq%lsb&{nQ zZQ!fUy{YS`=Ks9#`1`N_S);Mxj8QqW3HAIzk!?)-+R$syype5=eY2oO%bk#I*4SE7 zSA%BAHl@F;>60>RWSggb9jNCLF{eVzx5@T&qdV6$M7CM|&W~Q&XN_#LVn`_6w7M~} zjpl#2@b_vo_w&E}-5$ z6-_X=MYdUSz=n=%W`%4M_S1sO<~2ipC^^@N9;sI6hkSLlq?<=MBin?&wxB^DR(cKHG@y`eubOckEdwI!`di^6gD6Y1a%#m&0XL-;#jhI`R@QD?7ehCEP{EdHO6SPRsB7Ftm9+7A7+wQEinr8Gpgaoy}d*A%M% zU(b0vJG%OWI^QN<{68b4T&>FwThOHej`*%^VJ+ykh7FNz-hOIMyErvOwlRxtPA|zD zBHP$Zv7^qV>U z(v|a?BHK*3Z$-0nY%uQsKkU7CKvl`I=xxqoL=2d9%o!C{m07@?2qI=3!ux+PnSs+cww7u7#2Vt~&lD?_DF6Vh|-hPq(9r@Suy z(X)spWV(m}ME?DG{vx(HKBf|czOPR4N%A3McoEW^=BCIq72)@THHmFz8^dKk-TNn_ z8k)eZZIwyhrg?Sf=2VgRxNk+MlvbN;7*ez@Y(G?<_H7=ynZTzWm38mi)UOU7Tq{x? zjWbN3{>w@f+sOKg`CYQ8*J#@+5I@(L^js5c0;3yMrg#P(RfTC?DiLpttOa*ImZ#We z-HR%)<3?qQXEMiCgU2})iI1(R0$UrQ6@D5AXJsr}|EAZVDJ&fw)J* z1`v3#Jjry*FoxUt#uVFh%{K*)NfpR$M{KIVnt8?)+c+Pt3Ju3rqS&U(v+B^aF@Nuo z_qD@kt3t+rN)+3;)~*k&x0k2bCM?AS78k8du}y2EDv*<8Ok>FOdZrM4paSvSv}$l{ zcSW+{ZP&_hp>9=*ZGws!Lo}FBJmby#Y&!3=BDQfnZwyH_bo{xvDU^<^K(S4)uqsf< z$e3cARilmJLRb}wXSUrofj(a=5$9etg%`6b5PNPgg$HgGD7Fc9H-W-kbnhM6Z#4$< z(N!q6=~LPi?uS>P*k<0@8u0uafA@^PZxhh5G7LLjm13Ka&XvLJXjO`BGCr9?!3h;8 zwu!K)3k5^UQ*5*8Kt&k5w-&`VZ!@aH&W05!wz-*H8RiF?P~7r}+w*awiWJ+_Zdw(> zj#nbyQm;Pr;Pw>n+q~jqMK#YF6x*EPbLGsPrWD(R?c(3EFsneZP5GQE&^VZ+GtalXU*W;@}i%W06RIG`2EiO{_|>O_`6z@a%yx#WrWIo509|l_|Cvm{)x0CaXy-Pf{G0ZdC zs28lB8%F7s0xV(Txn0E7?0P}+IxpgxV+X_ena;%hI*x!02Pa}fJ>@suM9g6R>K}hs zPRfWF!)g04*sr}!=cK%Q4uSQ>&d@ojM6=#drBxK2lX`s95|&KfOXs9^zqbUu=tt+I z2DKarNo8H>oRsldJD5G&iOxwK>^>Gk`>ddIQW+1Y!>E9HbWTcsuT7LIS?KvQ-RuK1f6P=SX-e3iNM)}Y=seN4Lj@foPCspja6%01> zrgKs=@-1QPihXnz>A9U1G+XIQ=WBYh-f$r>n$Ag8E!i8aLnG-7)Eh4=sCD@O@feO%n`?iPZrkDq!-+=DbWW;X?ikRFUqN}kePapM zzWY=WC)9jv2|G9Mqq9XD%Q(QdM}HF6bF_wKCl8aJb3*#SqlC3|PHMvBfiN_~h0-51 z=?~e;Dv~cce+Vp%TS>foRxdbtJ)Fua=hqhw3|K?wq{`a#g+h^Q=$sT@>;v`P*3vmC zzvca5-fi7EDP_xGXx`14o}II(KMZ-GJ0~S|6FOH5vIN^vyXc(GoD-b2TdCZyj=kWx z{;XErZI;lf>@L#N>rrng-N2oAM;vdvL3=2F%ins#Vt)@hCsi)44;A+Oq6L)+^c>73Nv=~l3!}>%kQT@mO$rR`dU~)-ogFEos%qK zgwIyuO>R~Yz21l97tZJf-MV=Zhvr)W%REG9D+<5r59=M==$zCf)e8RHqF(oESwV@U%~UU!3s!J@h&P>$iubgJ2M0G07k=Fr zUY}h}=cFc1u!2sleCce|q9@j1ab!L5N$)|hRC|if0nMmv1s695)48W=k1e6gx-G=k zZoR?eraSSWRyI(5^h&C4)k1?HVv-A`FSli}kq{fC? zLV@^gbWW<+rd|-2;YsJD4wM`Sle)UnIjIje{C?}{&U7~F^y)qk@Nq4%{a7n#u7=S0 zoxLxuAmY&>s{5#QmT)mSkoe0HOBfljjbv^#v4TNPn<-tb*$3`NuA}tDYX*VUS7)kk z!HnL}qO$JHRHfuW&?DKIWD38sgek?g&^f7iw?0tr>sqp#7jL^_XExJ0sXEiG;dsT3 zbWUnxelK`j(v$pT?FwtKPu)Q0q@Ld#2us$v&^amFXI3yHe-oXP@-1KmHT?W&4C(i{ zH|(wFPW-5IFX$2LMK+x8WeMI50_mL8v|vjJs^U-Qp%(D|)tL8L5!;k}ZV4+UZy|np zp*OVe?M~;UM)t9S4e`EoPRb+R5(Zz{O6Q^6GpwN8gH6P*ruBgxjn@%pcI*QQZtLir zREX9JVtl;G4oO#e`BbT(>Fb!%wVY!mVEI|IRVjSI=lO0a}EbNA3WDf4%hux7_TIwy6poh`h} zaiVil>SQZ0t>sJSqoRmGEmup=2qjORN(yZXji%oP+ zsyA=PotJmeIjK>}yp8&~(>W=_Z>{#Sp8&OcuZ|Hh$&bFfYB)z5#vay1$HLrKZ72@e zUEy~qzWrpZ$j30x<+mLn_sGr;BK^cpJ6N_h-dyldelNT7*_rN{X?bxN>>0G?Zp)BQ7^(?-H&>&JBe%#J;i;7f~Qiug@x zYpXf1#IwF4&PmB{vx;&h3q614d$O2n192l8TZnT~dsA#-XZ~w*aZYNZuMJof96|Tb zT-s;@uO1Af`)8c4*+RW1`R3xBR9hc@uYWy9x_`zo+#ZVG@iG_Zq*DBBV77@B-CL3} zVY z_s^7@F&f_Q%cT2f7FTfukLMTZ{+WA@lc4STqKe3KNUS{!I^=0C;snNd^)^p)@xDsR z_|b4;NhaOjvSt4;n0R9ceVe{mV>^g16F~RRoa^rZC2q#kT`qI@vn?x!k^G~*jxZ$r z3i0P9!{O7a2GOFdtxL*kkUx_>6& z?JyWr>>}B7YmPnmjf>wdIfXW?gY7Z~YhM0?U zQWouPVS#TYx|_vsmkk8FPo(>2LhlR(qmA9o#av%4&mMXQxDtzJpYvx$`q}QbP_u9a z3!&$=EkogTHQ7dbKP!GeRmyq0FV8rD80w1iIBdkup-V$^{r(G zuXa8(7w4qr7O;bjEz-=zZ&HrD{}vkUNO#V3>}Csx?bi|4>0=8$Ldwy7DJ`cDg((|i zh-Ev9x;G3O3Jn2UFbUmMxN{Y5n_#5t+CCbnQ-dKKM2bG(ED^q(9@_s`5v7zQqG z$#mz;h01pDc@vd+^|08;ysYYFC5@)(1(tq?k7BL!M{%t3&AF(Y@wHzDczki zcQ@DhXeUZfzHJL;7dKP->juN1)PvJ>=S+^)7IvKVAzte+3=(FaC7H9wZQxklHWuQX zRB$CbILdVQ_Nct=Tphte{3g|we_LaW_jI~{<{J0aDJ#}dU%MV@1KYRGr2A(Y?{I)7 zJ5JL5GtYQC22315_s`6awt=FD%`8NJyw3aA!KFULE8f^Zol?$Z!(RM5IZejG@%D1aphJy(kV*?+GwIr^5#1`BRdDHzf&9>PnI( zyd-bBf5v>XEzFGDNcYbi;pt|jznY8Krr`lwX!Guyxi}}a-oy@We%VI%&x{?%zh75B zhVGxKU(x|4YucNO-=q?I@;D@P9o;`uqmwNJR;oyM%arNC>+Z6S?wolT$ZfTFJh9a- z2dET&l4R_v+e3QO1Lopg;uDO2o29C!xpzAHawneOZUta*=h^T-fg7&XZ*i7 zK-8WjO7G@w3u%XoScrFt*J^B_OGH}>@xDzLZs(epM$r8;&Mobr-2S`f;+$01!?rLx zz}rIX+ZcXV{g}f0_4RN?#2Y{Q#=7AgZ5VsB4;c;n*7T)kjruvl+1nn(hIzh9wuV>R zboo~~))g|7Vn}9EVSq`a&k1M9SR>0h11=7iLZNue@YnLt!Hwp8_XVkOn0~5Lxgq*;^}U^JK+GAH>T2^!*NNS zq0faEbm#DU9zzDkexTUqOJG09PAv{1wvpdw7v)M8dK!Kk{YT$+59!_sZf-bEck4Oz z?*cEYYv^vhcU*_KPKk8q@ZzrkRc@VB#Jj}HY`cJ)k%sQpd#nY>Et*Jo4xbs^9j0H5 zRzz&Gy$8bkxDymJgx~A~fqTN}ZoNUly}|Q&m?GjCW4oSE;&LQ0^hDUtPAEd>-RlwV ze0o6X7CZYu)5BqOx8Ar1xEpE`A!;y6X3f#FtcMjVY z=mf>@KB7B^AJy#&`I|CHx43A8nIRA9&S5pt5-PXW-bvnB%SbN4OBDN{Bkbl$cbC@FHnaF`XpmjnNaji+6V0x?L#1~5<{2qK# zC;vf#LDA=k1IJi`&DRLBVNFMXk@s)W9lwRI1MKxVMR)%m`KZ8+o#&{IZT14pS(Qk4 z{7QYq{4QD4%h?Yh**k&iWp)Z+=<`#Gc$e6t7r^*)r-?i9D^nj^UZXpWy;>n$FLP26 z@7omP{(S4z8RDh~ZDHAna7E1N$(o#S>?8KNQZ*&3EHY(k%$98pr+N)K%TW=Wy_*N!S5$_Ve<=-)= z(LI@1+p9BNuc}qVxt>Z>0jww7CYJ3e>OOvF5B_cLC`H6JR}wqH$8K?Sw_Ze^0%aSX zSHv0c2B83pEK=$2;?ipnTHb!3h%?}~xbKY#OCe6X*aIF~M=2t~os# zwsp@3P@mmZ#2N4-M*%kXPE^Dh@SGHcr+4CM45`WUANuAZ@r9xQy=$K%8y@%R47Haq zMZ`8mA9sSL-?WN|ZI1IkyOQ@=!SBm-0^3IM#8-Ge*4m4TI0HW424S)be|M0_Hg-$6 z{FgXIyg%%J2;lvwMB*>J?om@xh)p^B+`B~g23NcS5V`9V*wFcF#LOUae@dJZyF|J-xc{pz(6We1ck4aoHq4E=sEF8R zX2rs4fqv`gw@4Nzyxqh{nl4kW_1;HZK4qn{Z$t?3%!)2brq`kG>8%rve3vhD zEu2{7^IJ$1vB+QBAck0!JG`YzEcD3_(+~?ickW=sLVt^w|39y`xj^X!tXnI0uO}1V zs53$d8grgFIoMhG`t=NPL|$w! zvD~23IcV!CrCFw~UIC9!DE)f`ll-E-TBYo%oy3*CMJT?0I(sJc3|4%e`B8f2qn*mr z!oIrvy>=<*Zfqp>s28G~ueqN1X!%H`(sEDYMfJ+S^;Is!Bls1Qr7uq*Hd{Cj>}%-W z({5Vc8Js?wQhK{$>tWXv{_Q9p(|%R`V8pR0#GSJId3+v9`*?+y_`{eYfOT$y`R2GW=PMe3s{_k$Lj6G_owNgGTDWb<;@QxXv1>Gp~zA)`izm zBkRcPu90=;Hql6%a9e4lt+)*}(uUl&8fjZ@bB(k)Zwpnn1#cr&wo!uDE>*T2Z&USq zoAwM=Wm|I}P^AxW-%zD*aGz17&v0K-r7v+GQ>Bk_-&3XUai3JBPjX*XrLS@yR;3Sf z-&Un>bDvkG&-1>Z%Dy1R2iZpi%f7?=lq&la?`x{;YrGGtvJdjUsmi{|`>ZPaEbsfO z?906GtFn*tzONeeeN~PLLSBv)A|E-1i2UW)BFdFxj?hPrMM6(GMhX4p*!9m^bN$Tv z?pOA%e`as|SAO^ZnfD5Q<(A`p7U_3(ID|YfgRB&~G=t^6h}1`8L6?e6#6iz6td!-@E*o?`i(Z zx59tsTjV~ceHF)x4m7tu4ql~<$3et9n$K2Bl?>YDA17&OXUX(syp+?y`O!qy|23t*`?6yXf-p8yWG`wApIA?JwsCZV#qmLGZ zCr*ti{p-9hO6bS7#J6^Ige~(*5(l1c3IposzQZNrG&xpFp1i1%h*v2VHDnQc7>@0d z^)lb%Tahl}*njY>VV>XR|BHC|dp=S|zrVMC#aMieeWSO&n+KsMI_cLp;5%wX$TrO1xLoMwxS8Lu`A# zy7K0r&Yl^QYbajx11LTGd0XX1|3Km(wU_cTG>F)y-Uwy;+8xBDW=~UWQ+5$=FkY-& zn7)_zz$GUozR!N*#*dtpqx}yO-#p~3Bo9AKY#7%`7H#);V>}+)Q@m&RtY8@*3YPJq zVBtT~PukpVrL?-0O!}O*9j=`H<2>=g>ds1yN@sPv$47~OmPmY!?NN4pNFW}Y5vKH+ zrX|iit5H6W*4epcg%e85$8buI+Hgv#H6fI^qIyzEJ*l%vc&~V+Scg57-hP0pBEBM81i5BeJLa4MZXq# za{pJQ|8u`mrC)J>Q>DLgKUAe3a{pANe{#Q7rQdRYR;534KUbxnbN^SR|MPyK%6<_M ze=v5&iwM$zvxQ{C{>b&D@mA>hzp_t>at&x3|tAD+THHFB&x^c{B-Vm5FXcOsdp6vt&?k*+ne%uG{xb`JJX|e|*${G`UIvs}o z?ITsu)(b--V6EqqSivW!L_n|JB^1H7Nultl_Hp9vFLps-i|QcKht>0joJNC)vmPvm zHV^(JE_ACuynE?Qd^^YlK056tE_*0exzyk=agmB2EmpZlNRE}vWmGA{pVi1`d7c`X zCofAQ%i=m{qz+s+jns|ntdTnNx@crwcpWvej=b&~S$A#|{=E{NO}MQz(pKDt8fimr zTaC0Wx4A~zoVTMY$4SHSoR5d991r<8smgJZkDsa>Kl!+-%5n7{%_G9jKbi};Jni!c z8M)6RSnl%(mis({K969z&m&mw^9YvvJc8vuk6^jaBUtY9 z2$uUig5^Gso@t*)FGKr0g5^GsV7bpDSnl%(mis({K969z z&m&mw^9YvvJc8vuk6^jaBUtXs3FhrZ`*MQizMNn&{>!;rupH}n45P{zhQ~IljBR+# zqso|v$3m)%g^qYkQDuz8$0Ak6PKI-ep-=L$OO<06AJbGhrt!I6m2*9h0aO_S@Yq0= zu>p@6R2efY+~cFlSc1nGs*Evs?4ioogU2MQj7cW-^iWpWhC$fAik*giPPfQu7D*h~ zw`**v13Gqhu~j=<2&eSLCK`3W|6$?@aYZy^>hC8m*`cZC&EoCEJLdP-3}imUtBTLi zSR1V&c02B-8EH0`IGt_MxYV&B_Du=Y81-vS?0tQo2Ah>8J`)UHBwW0lb?l1?>aS7(=#|cR5V@H zXtKJrBR;3ys5yV%j=1DDS4~>PeBz}Gr)pf9t|cxP(nr%T%$K-Nhen!}J$Dc<_ARKn z6~CW&%$i8`TgfBDfmN*4Po*M=Ta_;rJ2N_xIC^Cvr?u396bwS7^`uoB9M?HyaPIQMkO(qgAj9UWR%$lyD}_3y@z;f`@7137KeyszYzJG#!XZYJ`d9nZ*-0=R!V2Xv?}K; zUYyq1*_+>u(6X*hrWL!cJgs$zxtt_E{3^% zoQda$uY)^HCKAsm?gy(5_asglwi62Z)*&9UDg?G4eNA@jF#8D1d$WhQPq7FXSN=C* z2a8DHW5-^hbE|R@&~0CRvYV&R5pea}Mf~QUmUYl|q~=0^}Gwf`8iyrr&>k2%s^P2QyI<2h%;)Xw{Lef&l4H}&jNT_1NF-%xX> z?hbnP_Q777O3}W=?MD2e$#GmuZ072s37WHj__yE<{QI-^#EUZhHK~ba#E+Wo)$D0s zo;a!ZA&qq9>qD&9lUU>@$`kp>c}?)#d4=Gi z?|w?ZbVGr-_-(`?zSH4b7hSt7_VIw$mg6bCV4WavYT1hT{<8ycJRpC8hmgk z*4}LmRrd!Hcj=O=eDgU#+`igW07h<6|RqBgY*A&y(a zzo)GACk{I}MH9VpEphS)cTJ(L6NyW;3e<$JZA<*5`vFbihp$NIf$hRIy#uAkI=JX=WW?M?Ac} zndVkx0CAB&->UApA;c+`OH{j(;l#rCg81Ac@)>2!EDns-@!TVzm}3N`7vTRz=YIjw zPeXn`s+Owyk$7ix3r+FeImFTV%Qfe-Q;B17x90BJ6U6*q4gY^){&x+RBj(R(`18a( zKMl{9#vEP_^*d3PKApxEy}U-G>+>Pj=TEFJmsqb4v0hJNz5c|a?xH+>y%bTNV4;^N zPq5HelqXo!LzE|2)K8QrSkzmTCs^1+lqXo&Nt7p8*iZC3gLJB|ULHicJ|ALz{>1un ziS_yr>-8iS_7mlaeB?MOSU=8Cx_8N*8_2Uwy>&Gi%IZo>J zp>a~M947_KaZ;C$Zk#kor~1lqQl#t0TM#VANx^cQ6fDO{!E&4wEXPT~#dcRmUbnqs z?GwM=c|HS<7z~z{b=g$Fu zo|xyS@O+6yU*_e>bXBH{a-_T{N9H5Sk@<^%Wx3+-QXlc0)Klaq^%vy`pV!w*q|@Gr zULN%I68RA8^C#AqORU!i_4N{Z5{q(#y+pdcUNT+OSIP@J5Q}nz9fiE!Zn9iqPh#k0?jxFaDL~ioZ*J z#B)+lk)PCGlq1_qpHA(imj`{lL_Wm&{E7AD66^IL*6T^E*PraKuNSetzQlSv$b5u- zi1l_O=H&`|5{th}eYl>&{*=!37wtm&A6V_n{){FD9nf}B%p*pUU{f)ihTj& zOhG+Md66zz#+(bXlCb4n{+9c@Bl*c4}7 zT^u<-(bwC3}ixPSH2%xtJgpA;zqXWKd_K#AEA>mlwW?hxVF`OU3z;i6M06*yEz-?bC&11 z|A9N{AX(%iWdzG~p?@aVd9PkxvZ0J%nJ(m|oekMgMzE~AkdZ9x(08O4>#Vm=dOuIr ziSxK;#kALgb^KsuVeO7WI+@|M3TSuS@F1BihrilQ+ECbJC%31YsSo8Nc-KmA)?lhG zeOVn}vcnFZo^#fRi9Cgj)m$GY%KAq(`Hyvx^%d#TuLMh<5iI>du&A$W>x`uJZ1UBu z)b2gbd9zU;e2ER)_kTuS_?WP#p?wVPnVI6nR_6tfP22}>VAa<96UTGk_|jzCclPqx z%0j0U*Cz1v@!aPpb9;X4J{Pd#mYtpP)Jh#d^`QX23FlHfcQ9X$4mA7iA7rnrEDXg z7woWn8~Oa-ZBujfA%7748-ygM|VIQx%&JE)l>*mLroF5g|&9jolm?mWe%XFcGWRV{A z-Vbl+pOq}eXX_YUx{yh_pkpy-b$g;?F_)dn@xds)4zetfzhv?32Ct2HjLQg~li^MB zVqBV7!yBV{`nzStwNMq zn{hpliG|(vSo>l-{doQ(dzL-uhjmlDSr(rQoV_;V^OruvJFfU*QF9+AY&hbR57u$p zOzE?^&8^S+Qu^H>Z_K~rN9l%kZt!k1{@Fk`K3vK7#U+h&oBHZ5@-iXGFjEY~D3iy5-e;oGf^ zOr#4Pp7h>8EOeNB)r(l@@Y2bXSm=;6!h=}oaC)XYvCyG$!a8E1Lq~fZ3mweb>ezQd z>i6_w5s$vh=X$*Op3nIkS>N+tJn7~4a_7}}^Ie~p*WZ2DGiv3B@A@ZH_(--DbrI>p zwt|Jcu&rQ`kFc#^k-xC5U{S8Htze;#u&rRBr?9PHp}(-LU};;y(&mC?TL_kIBv`hc zVA-aEWm^lDJ|I~7hG5xV!e^uof~9VPrOtw7T?ETI3YK*jENvoK+Dfprp-dOPA?1Z{ z2$pRjShkU1*>-|un+ld~Em-=1VCfrzrOybKz9d-sm|*F9f~8LimcA-j`mkW>+k&MH zrEUN1^Z)1gyzC3Ieg8Yh$$$4R59;H8w|||_zoxO&&owq~7d74WbI_w+XEcNLbJK?z zCp6*uIm@)6RuiG0%Vzq-Xx8ZGxVaA_HRY@5=Dv3g!!?`rb7H$CM>R|IbLDRtM>Kc! zbErt~d|Nk03HiExbYqmrCz#J)!e>POtyg*yi*k#O)YVbwQ*4$yr3*bL@%c;03;h@H z`Ae{<*IYh-3GOj2^?Q0$(4+72L5p5|&u7Vrtnc|ZvU&Nv-1^1eeAj13!n^N!{yzP~ zcl~F5`S877B3;&3$V)qje58Fu{?cxuTxn0CkF>MUQ`%qXFWbeiy(EjVQR*OA>Lys~ zELhe>u&kqCS$DzGCW57{1WOwVmbMivZ7x{0g<#o6f@RwYmTf9nwzXjC1A?V*2$nu0 z(}iuNys)ic>3f2uPYRa4Dp>lkVCma}rOyjCw5PPWNSAFPShkU1*>-|un+ld~Em-=1 zVCfrz|5ujvZ{N_xjsFbakmHQ(kJ6V!y7V!@()R?*as^9Y75wjUQn!YZeMHzq_8q~p zPYITNO|a~Pf@R+nEc>ir*I}knCkAHW{C2&t!T!53gB-H(b)#PRwZ!mP+df%Xv{*0n z^4T40i&+?d!5UXZrp9#ZnuTQ=_rlA`jr5PTtt)=|=A!H_mxa#`_rM~Jx+u$j%fkF8mN;U` z6N^?Iv(V>vYsAhIEPC+#3x2akLp{^Re^dTAorz;Fw8ERwg~9YqCb|r1ilYk@fi?BA zu=mLZ_<2tO{!N4|Y%#nxR*T42t}o0&@AlR4e3b`^*Pbj~Fvu8J6gZ`fxsrvJkIQ4! z`rXR#Z&}!|Mp+E^TcI3ll8xO>OX21xEtU1Q+4$;7aV&j2%;Mb2Y~1Kn3VO@-hwZ4~)quh$&owU~K$Pzhdms=c7V^*qx?Q?L5btzo4Cs;l5dk&_#lts@4 zXVhihIe5UO0#<$WSbcvy2Q4dC!C=3)>a5HhY+0=a4v#IUiLRE59lYzHTi+s@tX{d8 z*XuX5eNjmBVL>hy`_K%XJU*!wyK?cxq&E2aQMy{@QZ63Z)&VztNKrq1$;G8p0hgW* zQ}dhW;p81%u*yYG_35xYv?|*Jug>qM8oT9T^IewcH$F4AOhg_o7;TMiDbr$?UCzTH zU#+Q*4|DU#HwroBnj3%1!xs&EVfETGEgBfTMC&ism~k)M;;ZRPVF7eJSx6%|pm;sJ zG^hyitf)rlkzbJb%%~RlX30BM$go>&`PUeq5TF0h5nu9e^@{YW{)mgt?CZ(w?ArGtd zHo<_$H&wsgd06gaC7kSdLLId-4-f1wkI(yus79l>{E@O4ImlC8qvWA~gVN{)qtr-~ zJbYZGBxW1cR;RqpMeX|HIR2_8*7!y)MtBv&F$+4y#>M60;HEl%Q1|7MKjhtZw>amV ziyMX%!zJFOl-yCd7~QHkPH59lsf@XJ)2{@2ZFg15)yTzR%Sz!NrFSY}A98T}-7>g= zf5IW)Mh?D-Er&tfuPBGYbMSD{O89d3GbP0<2X7pxf`2@Gt-PI@gBk0qBgTJIUiHbr z-dk(ojCO^=yGagiI9CtBz6dNYmV;h(8ev|u!r=Kh8y){_hOei7Q^Mo2G4yOJoZ9%c za?3v(Cq8M1bqYOGt}V&N3XvUg$(PH@{9)NRxf|fB@)~7yhiu&H)){Xd-J#5=n2on5 zb;DY#Tomt|ER4R|11rb&Qq=QV_)4`z(|RS8V+XR(uZlGuF z(E>Y0Y1B`1^Uz`i;_DfE)xB%;@XpLGxM`e++HQLu+I;JVyHdugTO#wYc-@|O`Ppyk z<+FLX@&{7<`cVP%AWd4x29P*WN}Y4ZFyPwqjVMq<#far?5Q%U zLl*WN(hfaJy;4g4o`rw(Xo*gi@0H@-S$O|tV=PnSono1gg-5s6$2#|OlnYr|SaCru zJbe0rl2kPtmwHyi+c(ZCigh+Nd|esSFN7*h7i8nCN9D2fClAGScQ)=_Sr%c%U}gNp zY}96!!tm&V%9c;rc(r;-d_Tv`;?Jfz*tu~DtUtS6Y>8nxSh!vZbQ}LJwv}5B&MR0F z7o6#%ZaA8Qx7AWu;Pg5*;(iVu8C({RbvvX+mCeOPVdZhi$TO-FOU_9zK<$ zwEry|52dui9hcuKy9e{RCbubCt$wc<4{*ueFR(-kMVoPA1 z*KO6(b92#=&zrWUOVk#De9Y`z2Cc3HsxfDBv9U=xe7#szi@eUo@*WlcGN=Dc>|yAu z?tL^C&v~4%XOtDD?+i4*&f|nbE3I+-{kJiWU9#}~HEaC0&HuB_4Sm>fzW&j8`0x4j zUvoY+jJN$qKTxv5GV%Vlju<;6S@AlPiA}#*{AK+Acg*~+88iQ@#SH(B0seCg@OS&# z&%|0kGk+PbyA9XBKU#zTcdWaI6mF-C>X?o9pATcz?O$5F=W*TLD-P^^?i`C(AF}X# zGY2Nt!jX5f@Lv8=Ikv_0+RIFg1Sq>~=V_Q}5kf+1g0Djkj z;3_>wumx@Q6F*r#niXPah%Fb7XZChah$~c`%pSFSN8F?1bhi3oL5+B}viRermneM^DtCdl+Z)f6?MIJ0Zy}vr}b0)q`aA%Rx zZtC=!S!jEH9eW(QOC8AfH|lL%%XXS*)df86J!i6p#k9Pp=B&v=lgX>tZ^K@w>`)e7 z^>k(3+P_ubUChFS&CYDc$O4*%d0A+`&WS}YFRW=&DI4b{E@OkT3Md!7)A0E#2Q~s7 zl&J}67wJ#FWsl*~!P20KQw#9C2GOx1K;n?8nR7QCe7bxFsYQ-5csE1xO{CZ?nN z(8;WNMheT>tw(}#6zT7|7j z&G%`zu<$x&k$6NIdnXMqJzm4?N1al(votIlu$tvM-%v(xPea@GtJvU|&y+eYX?P~e zmDO4MN@+AX4I4FZVIP)!Rz~(q!|qF0vZfab!sJ$IIC|-yY~szraH>KY20dHKn)ELM zZ}VT^49i9AX+mMhdH4duU(RPPy`y7Wa{qCh|8>{!dvT$~vVeH1BeroibENtoO z$hM4fQ(Fzn!sGKtu)*8*VHiF+uG(J1rQ~I!4*pj@$go$LAK;>+y9{rUNq^-~JWGuBaOYG;JPdVR*zc z)}YQ?wY6s!`p9%K5Ts*lq3pH! zl2w^^OG)K@&Az!SGbx&&6zrak1&6F+If=WK{F&)EqT?D?@7_u!E-)QOC#_{W_FE{6 z&Zgt=ymf3-^bL!n`RVvuxI63Of6_dlP6pO3?ZJYV&y0;3kb#Br-P!yiMyk=W4D2_> zowW&eR1^1Q;GHGw*nRB=_1fhO^l!YD1w|iK?Z0JU^t{!~CGNaBr9~$0pW()aXdbH7 z95b;=3m2BrBv)m*m2fbI4?bES?vWWR_eXE$QOvh&xma`LkbCkOW(lP3(6C2#+kz#Wt z9rx96VFyC_oy{N8u~JhvcH~yHl2b|ha&xSi^^!>r-Fb~ox^|MSyfhdE zzdOlT&0bT8jq@T|?cbPqNN@y8819B!C*-pm`y$vM zBi#O?zo_HJTaj#2eP=Y=dyTc&70JqWalt7EuCWgmk?huZSDbk88k2Pw^^Lt0$@c%@ zjFa}hVmqfrvX|K|IKEXrTQ$m_O`32D_xzsE>Y3WH&+HWL^vY+cBkb9nkW-l9|JU?( zyKLBldWpDl^w%HSEhE;R)$luo#=O4A-R)VqojjlIf6dd-KD%GsVGfyE2;%bI>37(n zI4!i~+$Qr5d%jT%19#>#L)%XHaEHP1V^DecS7v(s4ojV`LaqJzOdE2C8Ew|W3vM^V zXANZx+xKVm{JU-Uck5-Sb4#Og5LG%kl-~JgNF!VR0gF&qLi9npp%MF>hioLiOj;%Nw z`pK{8X4q#R@j8~h*oJ(&-N|GYbfz8gtq)>HhgwY?enb5Gz;8X z<2w7p?>sws+X5GLxWRIZB(rU=I%4yhH~2ZxWcKELd$hWIo%Mg5%+6)C!=xeC+21YK zKJ+|WdeR*2_FQM9&z)x;aUJoZ+I6%yDYPN6sY??v+FPK zvaCC?FuuzdHX`#b`xqSu&*y((Tivg+4OOb+X)fbdG>MJsWKVpzOC&q_Y!$H*5XACN zZzo>7(T(|H6mj<!gV&Z+ppN)a4a<(y9~$VCESK>wj2d<|3EvFREEw`aA@wgzu5L? z>}fd87>Vz$` zy^x5?ly5A$tPLC3FbR8~{>IL%8N#ZTOu_-2=T^64C1)n$knFGQWT_#n^7BOO$J5JI zwPSM!C*tq>zOrWvZCTvFBrMJI99hqnjT@JUd$Yc>fxN#zJ{CtlaNp@NtF^uf)umP1 zadt0Z2C?J5{p|6)&BR})c(CJD!-x&*{&(&6D=}O0;Ja*iyEt&;_TPUomHl=?3pTu6 zKFmvHnt592#M`TJZVGEttqHYJ{G1f#9NC!K?qJOn7Cf^twQ2OY<1D4d44q6~94qBD zon$WWietttrjv|OoBgay8GfFVmz9}m5&LW>rTAOYTQ!6 zhWk(Llc}s-vslQO{Ee|GciDvx8feGUYs^n&-8-o;A@eJH?2yW;4O5}sp08|ehr4V- z$r$kEKH1nRmEWBb1LxBJ>U)Os&OggmKbj+cG~fNod}KJs8TJdq_WG6n^($kG;rM2# zr{P>|IPVzFM?Bs@u`csYdnwi_#A0scYd4f@H@>Drxu)Z>ABuIKkdZu=Kg(lX6zjM} zoHwQ4!J9SWAd#;fHg3Cw*#mUzDeI1L*ld?>omHlLFh&>Ft-n4`bjS9?bnCKP+4k7f z;}nW#Kij3^6i3}UZcu>~+-R>`-&J1|hnGv})_px@2V>wU-FmRW6nA{7UneGd*kiPQ zE$KP<0q`AaU8dAIk286EE7ox_AJ60Qp!T$mYkevi7bUi%b)1wJ z^*!ov9!s9=fcJO4Vv`moV=ZqpOl_9WW`*2AYkw`gADhqi-?)Qs>{PhO*F?YP-oa&Ea`vyngIlhh_!1+m+NNhdK z71vqjGpqfPxV41~PRM=5Ebc_&nwrkI%IVd2KNLP`=vO~uf5Wz3S@1fZc~b%l@Nx~? zgY~xvy?U;hnb5w2oUm zKMKLqnbvWJ`uxoJ!{dCE>rK8cL%9y+Yd4f@Hy+QUT+GD;4uhzse zOTMtRxp%RcCJxegdI=jF4CHG!vF_`3+746sdd;QV7dCd28)krRedih&ga?y!>%I}) zA~E5KZarA4coN2U)U6YegA)uLh#2e*Igu#wua-a;kZ3^`XFr0>nPS8_qPwhoJonen6G#KZru&XmY*4`4aZ5t zdFn^ws-YczroPdf&(on7bJ5uZz#CjJ}H_ z&2@46(-)~Ys)a6|&zNx+cYe}<8IOm}r`*LmJZ84z?3t8`femA!*dKfyaW@rbEsX*# zkE^2&r(&;wNQmLQW>G3;wpU>?kDqgvq~hDl5pbBNj~J1PONOZM8;_;$TinIDMPgt( zkEKWTO2q;F`2K6y|`^NiVej~zFr>9*JVwP z*yDh9x^=Yo3=f=8O}Bn5cVIt;%-5|eOJp6#-6wVH&4;d+vFt|OIyAkE2U-Ljr94;1 zx?}nFM=8&hPVU$+Ter44VYVNOmfcJ;fhoZl8sSSabv%O6XMt{w<~8v+`qZ33GTUCq z;f3|nN#@|bIK0_Xx7KT#pMte&G$EN23sP`KbYqe^TsH;1XY1CChW$?KG8ilA*Y6n# zL$H>9UEigeEq3N(rtmlaC3d(~zYp-o4SRg0-yit9cKcBbX4v;ljfP;;XNfqR`$kcZ zA-J?e5{~5jth^0=Xpn>soO55<;RC+65X60QVv;SE;(H6d`QE~omG*d$?>|iE>CI}{ zVaSX`9Lo0-3YyyCIKGE4lkXuEUuKJ6`5rfC3$?qpgBt~T~Qi|}8j2;SWKJ{uICKrCfMta6p7SKgDL2=2z^hea(THk4sS?z1B{ zy7URx?y)6ikeWZg!b>s zkE(QteV%WIRjkYMd+I`2-sJXpYgk!rsb_~-(Wf2o<@B=JIi^S1qo+JZbt$Vo-5`wJ zn*_LbOIfWpJ&eWo>WqUz%WB&V3upI?y5WwvvRaF^;mo^uPh54mtoF_9aQ3K{H5Pqd zRvTMBoK2|T2OoVbtL-%^j2*Am9|x5;((YV%lpWYG5RK~_Y5Ut8VQ(V_W5Eta+B12f zZ0t-MY}eOFTg>SY+qBLWQ%4(V>lZr6!m8L|nR!Oqg;61_6d%{Lu0~q_`TNrET?s-u!rs1XMqK0mD3(Rn1Uvj9Uo1 z$mIoJ>$abHcsbE%rbbCra{CqE4@7aM^+N9G9Bki%z`&t(`lz+5pfc(Alyy*Bvtpn4qti1d!cO|$`=OGPzV})*anko*>26N?-rF$By7zj_ zweCGwXWe^K4_WtKiE!)QYk$_d_g*Ag_uiPU4*K4!I^03udo5-==zGs)orAvjo*i<~ z_uip!2Yv57Jnf+Gz4$~2eedU+;&gQLFp=I623bAqX;z0OOYs`h$LmAd_{%1-Cyv#;%RUS2n~(|K9c%TDKI zz&Jadmme3~>AY;%VyE*m&&^Kf#W&hc=cVUGJDr#1H|%s?>OZ#Ac{wuHM(1VZ0vnx| zMVoANUUs?J=)8OrW25tua?wWTrFw>q&P$=kHaag`3fStrO#a+f=OyJETb-A~t!#B( zHuSaCd9h5i)p;57ovqHxuI;uuFYP^SEx+Y+!=4jc1D$2Rw|B!v9b16ynSz!D32u0+ zcT*^sQqU5=!5x?VYJvmz3R*lnd*E+Xo4}Em1ufmCd*Y+78v!`jSXN*3!uXvH;95Dc z4t0HS*RJ{yUf;&@ZB1WXTE9NnwX(5{s_ut(oa@8OZZ?)475%Yf)%wuXMa;K>8@5ks zA$`c$=Z2pSZ6;oD{+X4#>NTv~xwNoy z=g`wukEx!+tua+}mNlkouCc~c`vcaPx)Ext$J7Q9gM7}WCfe#T^}}6TJ*HZ`v(;m& zbTMm8ZK!6AsUBdBDd=vEsi~u_F;!xLHKy8cvc}YlgVva88fd4-)Vt$$dQ6pyv(sa$ z{vA6#rY^p<(_?C$$c@a)xk}bt7ud*}>uPkd<~rLE)?7Dlt~J-eI%}@`>VP%ZxrEy5 zF_rg6dp)M=rP%8+b^ETp&P%md_Ij?n?_fQH3Y52=LFF1+&!D57t!L0Eab__u5i_i3 z(7u({GpN*F>lyTGpo5<4MxAodbKO@74tlODcE>@_b?x6e=(+A;5$hRLuB!D6y3)we zGWO>H%uKHdRJVA92jN<$Z=l-?Crfz05S$TR8_L@{TdGBb;xfOw@Ow#TON)D9SpHpo z$XCtTvg}DXPIMER=ElyJuYQWafjdl4s)Mto|ENg3kDN45 zd|7J{l=649>?`Vl*#if_YKx;~gvbd)s`Z0AmmDpw(_C@O<=)_*;b@sU`v|_O(G%<+ zI9fVyI*iRub%o*Y94)8r9m1}6I>Jg()4F*a!p|GGgHq*19pZNgH;-urcj`J>zRi0W z$M0zd9osrtzVkVZTVI%9VSgvfCp(VdkG_rI)OaUL%V<|@ezrcWo9|>9Q`j9NI@E<> zYn?17JUwtuo!Stw*U1tw&I_L(ss(rboh%ORe9+IcCUiLFWGPnD4^z9=ghD?%SuU^i z$FHZ?graFq`g&4*QY0VuR|X?QRa-*#;ddj#+OZbf3G=8auVSZZ_w%7R$tZ1+ETd0AEL5<&QZR~Y^>-MqN z`CT){UgtMJ#4PjMVvUG#jo(6h?R9>q``hdMx>@XXe(znf*ZB?2u-Exr^T1x`H}##p z&Tru&4m!WnD>>-=HWKm6{3@*+bbhJMVSf9Zw$=IlA;DJXw^FXH&TsZ_wmQG<3fk%X z?k{Pl^Ls+%TjsZqNz^Y!>HMx7YNzuXIo(d@_w6z}o!`^j>~wzjyV~jeJ`A(d z`K^4$PUm+;qMgofXOVlE-)_GOI~u=K3o*ar=h^7|#;>!{`E9&koP8Ru+jOwCeBLccib=HY}NQ}{7%#rTKw)QY^(G8Q$<^y-y#icb$*lD*y{WS^$};B z7Qgw%+Uoo^nQyD}yL-K@&hIdBZZf|keQYh!S&XXVHmx$FC2Ya&~of}2rhrwAI>=2 zSdLW-#*IG=glJJa?U^2k?QLA3Ze1HoYY%^XciaWGw6?Lli1)>{w_TuC9~;Y~lcK(g zc7f0#HkR%p_GjdFl>XFqj>M=jT_sL~2%P5ML*i9mhvR+my)xB!cW;K`i00z^BY`JR z55bbd2f%&d|EE`iuu-8wQ1nVc%f!Ngc+%tohcm_B$#3P4pT@bsFHgmNkJ-NXd8!Mz zjZ{>ZD*fY#~jeS<$-}qa3A9Bn_ z=Y8|fHahQ#H*Iv@4~klv^Y*Myth}EqV&(m9B`fcP8(Dd;)X~a&RZ&;-IY_k@$91V0 z*0^51!W!3ic39)uU)0!~x9uZr^|&5>##WE(RU#*FT$jobb(a>`cV5`)aoy408rKU; zTjTmvEo)q_Yi5n>;oYop9Wl%r*LP=F<-$901%_Ig~u&a~I#I*+)XWqzq^L&-&@b+3ZB+;xp%aKp0^L2bI|kl z$Rr0nZ#T|$(DU}DmkxT~K4ot`m&=#2p3Ax4SkLAA;!J0L>3$>go6+A|cXgg_u57Pr=2 z-6~t_u1XE8b=QJ+*19WrfVJ*&oMf%L;ul-%t|U>jF~4+AlKDOF;iR9-jiR0Ob9vu6 zC;eO=oaChQi=qZ*eha^J(&M+GowLsG`On4uNiBZ&)o|A1_f<1z{apUKr?bxQ?2+PL zqE>gAW{P@PtGfz|dzD;wjoI$3^Sj^ESwELwMmy{0@((|WI$W!}PRCp8YPvu9)a;AH zvs~nT$oZ%Iu|NZj{*SBZzZN8*BTaSn?1fw_@*G@z}-=dVU$(7~1xbInhE7Ps-kuw#Se8T9UJ zAG|hP#g{62p;IRp*?v^0M-d_J~91da;AV&+8sSul;TGcK?a$eFo~^X^?tvf$Wr9uij4}`|+POko{@gCS~eM zO#V!Z_(o##v)L~-B_{tDB-D_Y=CyaeieC*5(A%qz3DWyF?;4`p8S`nFZol4&aDCj8 zF%h~yA^RhBKZ{n4LiRsjzbJiP)Xwvz{=5!khu4Sf^SaTvyq@F_uQU0{>rehOFUI>V zzVAG-!q4jZ)M@XHiyg%Mb5Tq5p5}uco~mp0{SIHDy;t!?JAcgjM;+Ox+~xpWovPxu zO@h#Vk=keA=3sn1rJn3_Gc5#f#HltHH5At);=2#BZ#yv@=S)}c|1@1JY8y9|yWX86 zab|0k(Aw)b>qD-uUv!0NFlnlo#%)q1ySaq9SJtUsqYA=@E-$~-O@Ak-i zMfsoFYaUSd8}%Q2p|R{kcBb{KCo$Pi8dpnV8uwY{>JpPbH$$sP++X;)s7fV?$^T8e zD@aW9YE)RoP1*$N?XERK^!_Dt#P^|^ol!$0b^Cq4i`K^-*5s(}Pm%9pbwAg&Gwc3G ztTXHLqIRAy_2+dUJG?$*pVy7X<@F?gc%8{lUVrkRc`@=>W|=2WcNs1@z17kc15dh0 zeCYK-bn{lfdoAd20H<8;EZZM@?#GGWi0=nQ{WB^403N#9SmN&&9L7^vTjKH^-LcB0 z>Jkr2@x}rERVCgV6rkgz=An9@apHQDKf5_RTDNJFCEm5FjrDkOjP8TW#wgvl;_btA zpHm73>vN$weyj}&>UoCFKF%|QInNO0JVTiC3}MbQ-2U&Z4UBv-{;&Dx<9Sh6=62?h z)`xi{%sdii9tks#-2U%AFZf*ecowK<&42P)@V=U@yttP1D+cl$Oh^vJXJ?y8Jk~1& zn;&l^arLIb_C_0ul47&#Uyl7l0eR)#q6Lr=EK;FZRF*j_Ub7tFt@i%WIN8 zw4UvTO&=%{H$32q_x7sw!2DN7aN17wnlWwH5$tuUjqLMg?h!oxNe77=9Xx{lYj&3S zmXj;K7}ZVUv7#Q{K1aPi^+|IR*Qe@rYr)1I_+wA?diJ2dC-#}7UgysD_riHg)Eb8G zhfsa;pK!fwyzcm)x=;IOxqdNTul-*=lfe7`ukefqKYR99diLh8^i0%W=~=bE(ldnr ziO*^ppDFz_o~?h^`|wo5|DC>P`MZ6O_ILZ9^zZULILGW?`Pl~J_dEZ}^R$1)?}q*p zp5ftZ&%etvR9pl6-JX&AyFCN>cYDV5@AeGyzw4QB?U>M3oW5= zC$h8DiTCLg1_!)4NS*l8HDOS5a$Bhr->@JIX02=`b>dl7!T@(SmpbvM8$zM-F_1d( z6+t2JdsUOviN9PO3}@mSNu79b>mUd!(@^Tfhs6cJ&)4fqo%mD5ANJL#FLmM$p}vqV zG}NRMPpsnuAwmyGI`J;QdBK8d4Wv%oE7=pW4mOm}7;JR)fUqTvrA~ayK6iM1(Ij=^ z-(7HnQOlZ2ow#Q+Hwf9}U4ca%Eu0&m=) z>Vhs(Cq5^|9eOx-mpbu0c|Bpxh@Mg>-m$G094gsc>csa&c*ElUeWXtO)2_Y{X4hBh z#D7WjgK4G3Gg?9?UZH;g>_5^+>cj)L1;Vwny`@f^d7Hn|iT||Q9oEK~q)xoo zB{$eGr>WG5N4Ir@F9x-cI`O#tZqT)NYpD~TZSMxPr?-%F{>c#CeWX=kVSmojC73 z(uwolBb_+!J<^Hu-Xonj?>*9q^WGz!IPX2uiSyngojC73(uwolBb_+!J<^Hu-Xonj z?>*9q^WGz!IPX2uiSs&BjmmqEbmF}CNGHyFk96X^_edwsdyjPDy!S{a&U=q^;=K1r zC(e71bmF}CNGHyFk96X^_edwsdyjPDy!S{a&U=q^;=K1rC(gXk^#$`nI&tQObmGhl z>BN~A(up%Kq!VXeNGHy`kWQR=A)Pq$LOOBgg>>S~3+cp}7t)C{FQgM^UPvd-ypT?u zc_E!R^Fr5#%nRwnnHSQDGcTkQXI@Ar&b*LLoOvOgIP*d}apr||;>-)_#F-b;i8C*x z6K7sXC(gW(PMmomojCJCI&tQObmGhlUDq=&q!VXeNGHy`kWQR=A)Pq$LOOBgg>>S~ z3+cp}7t)C{FQgM^UPvd-ypT?uc_E!R^Flgt=7n_P%nRwnnHSQDw-0jzOZ(39`O;4o zxWhb$Zc-<{Vu=T2&FLX^;w`s$LV-rTq)z3xVQq zhLBEtKwf|F5twx19`F3&=}+SCB?+DQi>CoFs8t^zo%phpKq$Yex73Nh>h2CH+tlY^ z-Aj2uANTIkpZ0d1@Y%GU694*z7hJfbK0|xAy*CuMQ=b)2J>dh@ZuF5l@z2}%L1fjw zQYSt;(I5Jy^pQGozkY#G{AF*c6KC#7-^AQe&A{A|PMoBN~k z(up&7q!VZENGHzRkxrbsBb_*NM>=ulj&$P89qGiGJJN|Wccc^Nn4BN~A(up%Kq!VXeNGHy`kWQR=A)Pq$ zLOOBgg>>S~3+cp}7t)C{FQgM^UPvd-ypT?ud7-)_#F-b;i8C*x6K7sXC(gW(PMmomojCJCI`N9%hCulq z1Ayulo5Eqx=6+wP6K~Te9J;pZEp_6HJ4QgaWj&-$yt-W^G+EMB>cqEi6@P=YXD6u> zf1Mf$$*+W7Tj<0q+=+z#!L6lEJi*=rzRsyFb>an=xIxJl^`uU`ei>I7QnR7diPtD~ z1b#6!kvj3;M<0e=CXhPu%XbdJ&qJF_op@gNL-0kN)>0?#8gdBQG;1$);_Dp_L%ZBg zQYZd4>M-p4wwu(6e;RlMAhD;^i4VN(3e&Ijkvj3EJ>6kzkN#38{^Ys`v}iL>>cl&U zyq6v^Nb1Ckj`snFgDz4h{#|cB*d+APq!Z6+9soh#yGWgQ|58Dad2o=_iFfHA3{!Ru zlsa)U9^X6R&nS5*8r|qOpd_Ynp*t~2hb>h<&N5ZGwn@OGct1A%@cGM(w;!je;q0sO~QYU`I zJq*&u)R#K(1&u-hv+GEmctPJ_aCrKS)QN}w76?<9*OEH%>~aCnVqZcj)<7U#F<~xi8H^X6K8%&C(itmPMrBAojCJLI&tQgbmGh} z>BN~|(up&_q!VX;sm@`3Nhi+yl1`lYC7n3)OFD7pmvrLHFX_aYU($&)zoZjqen}_J z{E|+b`6Zn=^GiB$=9hHh%BN~| z(up&_q!VX;Nhi+yl1`lYC7n3)OFD7pmvrLHFX_aYU($&)zoZjqen}_J{E|+b`6Zn= z^GiB$=9hHh%rEK0nP1Y0Gry!0Z~Pzv@-a&i1i{o6-$0ll{HHGpi<$PW-DUp77OgwWLlw{kaDWP5nmd#LEQ*>ab3f4T0x#YRf*I7X-oM>$N1d{15BO0L(up(gq!VY}Nhi*{lTMs@ zC!IL+PC9Ysopj>NJL$xkchZS7@1zrF-bp9Uypv9xc_*DX^G-T(=ACrn%sc7CnRn8O zb6iuc#c@qKagJ-!iE~_&PMqVKbmAP>q!Z`3CY?CPHR;4Tu1P1(aZNgLj%(71b6k^7 zoa35w;vCnc6X&=lojAue>BKp%Nhi*6O*(OoYto5xT$4_m`K5Y{`6Zn=^GiB$=9hHh z%rEK0nP1Y0Gry!0XMRa1&is;2ocSf4IP*(7apsqF;><7U#F<~xi8H^X6K8%&C(itm zPMrBAojCJLI&tQgbmGh})ojc!>BN~|(up&_q!VX;Nhi+yl1`lYC7n3)OFD7pmvrLH zFX_aYU($&)zoZjqen}_J{E|+b`6Zn=^GiB$=9hHh%rEK0nP1Y0Gry!0XMXAX1?HD@ z;><7U#F<~xi8H^X6K8%&C(itmPMrBAojCJLI&tQgbmGh}>BN~|(up&_q!VX;Nhi+y zl1`lYC7n3)OFD7pmvrLHFX_aYU($&)zx3S@^GiB$=9hHh%rEK0nP1Y0Gry!0XMRa1 z&is;2ocSf4IP*(7apsqF;><7U#F<~xi8H^X6K8%&C(itmPMrBAojCJLI&tQgbmGh} z>BN~|x>uP$#S?<2K7>LRJ=cAu26CI&w*e!LDlFj4he>| zSL$c8$Am(Knsw!8le5C$>;qL(5L+e!231$J052ROA@WD{`TxG&k#Nepx$Mt1Klvl{ zM8H}wp=|`#BMZ$VuufTMAt6oEi3^P+u&!BXZGiR8LTdx8gBDsFV12aE+5l^#gw_UF zCr<6Gv!?#66DK>Y6DRwu6Q^-mCry}!_|>UM;t zRkts+uKKt_1FQQZw6waPLQAXrFSNA!yr`Y$OZ|Br$PTX$+2?hmad|z-A6{qjlh>d8 zXI_l=Ti%&{VD$u5*E|yZz@wr1H)l32_lN%TRXiaw016FL@#3$7;MxVX|I6=#VNI-h z-=>UxDD2Fy{_UD86~f@INxjdrzI-^mD5&258RrxMpNV_gq<0&BG6GUws@nfAl}Pxq zxvGhNJ|YqxbZ9C2)NUOK(;KUQW6)Tq8SioZ(R)qCdTEQ8*ZB5o?X>WoA53Yj;i938F-f>CuT6M$?rgl~TM#0s` zuHe@}tu3!Db%jeC)VX{%z!g5tR_Azejw=K{QvdG3n?zSQnXBr=TQzcnCGP6q3;Lrq z;VYX67$4vIzr`uXtfmu}F-zwK$1GuvS;8E%ggIsjbIcOvm?g|HOPFJpFvl#nvre32 zmfAUH33JR6=9neSF-w?ZmN3UGVai1mvxGTj33JR6=9neSF-w?ZmN3UGVUAhC9J7Qu zX1Sepe;l*a&M`}vW0o+-EMbmW!W^@NIc5oSj%94ni395asSjhJM+Vj-3!O5sPFd)e zf%VHm*9@#{78*KWy|d6k1M8rLJ{njbEp*esx@n=OmidbEKee+?ocgm)ob0epob0ns zoW^CHIQhf+Zt|0L;^e*EUDy6%tAv+I5e zoxAS8(7)^RqIRAy_2+dUJG?$*pVy7X<@F?gc%8{lUVrkRc_F@-$CQG>z&dfExdzsW z3oSOVPF!fTfpy|SyA7<}7MgBgow(3?18cp71{_!?F0|pmI&q;H*Rjx&>wSdAT>q@l zp6fP+CS4y(Xw`Kegoa)BO=#P7pM~aKp9}9>%8i_72y>nx%z1_|=NZDBX9#niA2KN(3CC` z4<8i@eScB4)zzzqz=B`Zzw0t$W-zQwR(00=eH@+F|H^YOjUIZz<(}#@Fq;;6f@^#A z`I*W?J>aB`c>k8LZz<~zUzJdOa4zTuDdFnhADdFn75cnT|IWFHsZxl7fRCw+MYmNiuM<}ddjff<`rP5Pb5u5idv)yRK0UDV0q`6U{+K|Ocq zJyE@${ZG4IHePr9Pu-{evs}Lzuh;&so=M>S|5td%gTIgdD?NMjS9&Juuk@_iU+Edb z|HNlCjn9<+8PC?g>wS2-Hu*b!&+>Qs9_{b;J?Y=&dvK1~zw)yU#_xCjmFH>yjNc9Y zCp^Q$*PefuXQ;Ra_`5wL_jh{+^6&PHD_#5Wc|q^G;%8~-U03`p4ZZ7%pQWL9UGcLt z^sXy@mWJMS#m~~vyRP_I8hY0iKTAXJy5eVP=v`O*EDgQuil3#ScU|$bH1w`3ewK#b zb;Zxp(7UeqS(-ok4D-M1nQ-I1&40)JOuipN&jRuD`Sc!Jem3-z{8=?$q5aYzaLG?* zdUtt4o9p1M;boUoASEI{Qv3G<(%@jTXR^3nf8@)@RnCWLVu??bF&m z6+U~U_IaOuY7e5Z7QVqvkPiL=f8O~mj;@dazJ$Mghflj)hY6lz%;8?I(R}$j>^w5n zyrk6|ta|f0teZC9oKJjqSeJBYdC=2*R`e;pJq5O>CrUh`Vj^4@zES(t!AU}ElOL-d zdxLd%B}1CP`{Li?hs@EqCLiK+CE;7m>GS3K+{w&!vDSl-s0FJ$*|lb#Z350>on-E_)Gjns|?ufK3C!`ZLh=1Q}fL0 zFTF$06B&@d_B^x8ymxqfOa@fGFxTAb*;`C+p8=mn?38`hpGt?EK|5t1hY9KMtn^OV z=V_aCXqGQP_A&jC1_=lJWuMC9(%@1*f7xe}B^8!EIVbzJXjh3C{hH&dWcwR5u1 z>_aJV(mhr7>HcL3MBn_J?1y zw@Ca)d08+i9S+Z(XYSwRDP9_#4y`*bGv6Qa6ia-b1fRdoF~1PluG2MmV=9XIM?S@^ zJ^ukqFW12$0-v*71c%gm*r)AN-1XoB^e{KTCJ&!rtuHS?$MTJE_R=RgT#kUK3Cppp+Y{V9IRcy>tiUg8JjJ@+;c(w& z6?PM2?WyJkWfFGcRDn-d+YNTlJaC)9|H?XJYC4q7nP(1ldy4zg(!tSZo_V3bJ=4=6 zd;C0e8G--kn#77V9MXB2InXr@W5bhS@v2J_Z|@TaKNfXFYQHJg(D70oiG%Z|L+!>B z%wdAxD<#sQXQ4^v^yg2}N$m4ZL#La&^m&T!`92P~pZzb8GK7 z%r`zA@bFx-w|^YInUDs>JBmJHtTx3&4E7yjUf3|N^XKQ*2DZ4Vc(NR zSfg|TwwrYketppZ+g*vru9+9%{QY|PW3PBz)HVt_r!15GD|~efs^^_7adz7?Fv6v` z#PMF?Fk$d2xweIOM8Nr~E0KKLG%FJNyLKx=PxnCMTr~!N-5UUNMu`4m-BwpU23cOyC3YKr5%Tu|iB}a+^E~x2=KS}a3;#+S zaZLT!y;SeiML2Y>p7cNI; z&F*pkv>)Dg-Wksq{w$r*cPFRAg^4cme3|!k20RZRB60N949IjDA@Pp`#M$)qSc$_U zufy+2lO)b_>pHY^o++{MY&D*D#xu+4!~4!Sq0w2EE0+zotRMJmbyJd%yjs z{A}D;KTVu zTqB@!^A%XyFAldfiGU8HS7ITNuekq*o)N~eJ|xCD-nWW##CWEB$XRoy{&w(x>?66-RguGq?T6 z|6DwF>v0|C?3-zRbM_rB9-0ByhRraayZaU|uMxH7xyk14lip!9QSa5*Gs8U5{Vkpx zmkz!?hMQ-J{$4KWFmdZ>^WX{ZFfbw=Zg(AFJ}BDPmdgO8$0&2Wz{d(^z@^M_<`Wa& z;i(ZBaQfM3^Fz^IeQ5^Rrj0Sb6u4C53~(AY!ThNhYxI}tkWh4-`C#^2bc)GD`zk^z3HZy|<_#%M~AQu9o{2kL6}S&&LzYMMV3Y!q=g0 zJVc+aabg&iYFX1;^(xGO(p%QbBqIEXzH_l_!Zrqc`y!yVH%2=BfO^JlFo0cK1 zGw1LR&G}x(B4N*f<>(;Ryra-ZoD5x#Bl^Va=M>rbkhAH1{=BblG}fXs%U*!ylbcBY zmH5-(pV|<;<&dV4VdBnezoKVHLXb*ErrFo`D^@1h# z8THiExTd$-o>NDuP-LIP4pF0(gB{jNO#jo*^jZ3Sis(m}K1ZJ?O!mmGv@gb?@eJ*; zhW-+3cFfeS*_T)wS7I7R^pjZgQ*BrMmspz@x5o-UxPPqhPi@bsLw-vv?9+G>)Bp4{ z`9QxH<4H`P6XQug$)1>(#A5x-hIz?#)aFI~O$IxPHZQU-u{N&6G!D(5`p`J~`ipUx z7j0g$58?WSqm*YS+MBQ4Uu^oKYq-Rfi@!AWF5xe6{lX2E9|8_a?Cv~KIXZuX#PmP? zOrNFSQ$ND=Ir=OGqp*_~nUt-OUnc6k`5^Lj1tob9c=BLD({}OBS;`UhK z2ltN^{z)wCklzvu`!t@!^gsPfKG5%}pXR4oj3@mhdty9^#k|bZisbX4K3coU&|hNB zjzaC4eTlVkCD#0rn8xAtr*UW<>9g9rbbRK-O11x_#-_QrT;lA5k*4`e7D#;NM1Ez! z!!Z)S@~y4}kLoNj{ZBuWP5M3cBTS#8&l4tlm4#ixG!Ap8wZ|IzORU*3Q@dtgVr^WB zHGd@5{FIo+5q2e>R%AsbF&?+aa=YjsEBuq~!VdW@v9M3$NlgFK&*TIBp89Ein(6a| z$(|TbVj9OVFKRa#`b(_YQK((BFR?bR#F{@6Yko>h|Hen8gZF= z%}lQGt7UAC?rt{q_gN}&*}FE%?n+Z6-j=Vnl5?u3#PmP?Oz}>?r+$R#bM$$_WRL6; zrZH)+8ro(4(fUiQ*)dZe&A!CixDsprNUZrOvF5+T#G@FG+hc_v+&@-~C$X?YeoHLu z(|8io|MWBYK)p})kM9fjI8`x0y8O04-KF^xm( zLj7qR=7sp8T-NRD0!Ou+Be9l?B-V12#9Ho>Sj%Y=Yq?Hh&Y5JBVx8;~=A3D0k0q@2 zmsqo7rgqJ~#M-zLYyL>gIg|Qp{>yf4UJ`3Lhx^N%N&U4PCEK;!B{Anr>ccscFy&gx zWrR6rs&=9zUxs!$U#-8yoHMBp=S;$!GgUh>hbx3RXA;)@m+eNr2ve;>dxdKi!deZW zwrjPDh?7cm#!?MIeY9FaVmf1~hM;z?RS0vfLYT)fw8s+G`b(_YF;lx{Ut(=siMdvx zKAN9uyH=}EyEZR6hbmD`LA8a}U)Cywwc3E~%UXrnxmKaia;-w`T&ob~T7@vzDu#9w zVXeQ!njMAOHTx2CtwQZws}SZ|MYe0T3SlE(!aq;SU(~MU8Hu(0Be9m3D92UO@|A4Y z@|eV0ev??sd(vmllVqRAA*{7azO??aWM8vmraqc|iM4Sh*8GvYaGs?8n*Xv7{ml7G z%QLcF%Rg*K=0WPK*+;Qy#M-$p+qHT?Vy#Y)SgRi-*6Iq0wR%Hhu3N}HowsC{FpVkp zP$fgV%tcy%i8VWB>Z940SQ}Sj%^!(1KPA@umspz@x68VPY-;s@Y}e`piM9GcVy;`L zKi4gUsotT_6Xv>wFx4%@o1tCKSL-h^*DchC>lVUXx2Sex9i+Q|MeDWNzAFs{Lv?g3<66QLSFxQ!c|F5pisc!jrjiA@+GQK`uBRrM$ z)yHcDbshfat`R<77tmSpXSpsQU+LPI?yK-MIAOj9m+jg$IAOj9C(PI2gtcpDX@{@D zsh#7CFkgck+U5Nsz6LkgF%#x%aKd~IPMEL33G+3$Z2ud4UqELWT@TZI`MR4hUw0Gc z>u$o@^{?#D*WJ|4*WHBqx|=XxcN3;@#C6Tb`;+SZPq~JC-L0;Vyk9EY`MR6h`MR5M zeXktL)cW4IOiQCmDn93(X=xl;TlS&$#_d#0{r9ANBiqT&fjKHB z`~5#xF^#+FLM_>c{PEnNV)AqIU=@@9(alv%^ZKNritDY+)!S#e+|m0_tbA9u^E~yg zZhzf^d-}M8Uf$FFS=;}d)&yc6fcrKCc^%%j-%0=<6)} zRwgj zvDxICmghaSm_2aAGQpz8;QhQeERLmA?BIFba&v+jchgs0*Y_v2Z_cB}9rYjCQ;n|% z!p^6GYP^vB1tnEX<2Kz>Q~F8%G_I{;@^gDu4c&kD2o=-3;yqNn#`%tg+cT!z)%)*` zx~JO-yMAA{U;V}}`ndH&9_apj+wr09=V0%Ly8kbKe5lWh+IhazpVxux@cNK_UN;(- z*OUC=btXS~{mFmk#mE<9;*_}~%-j)X?g%q?gqb_SwC3a+Vdjo7b4QrD<96bX`xAGB znLEPF9bx83dWXB=TZ;|TK^N0`qzZvS`JCv>h+ z+;Myn=J+Da@kN;9i!jF*VU91t9AAVvz6f)Car?*I`2Uw1DZXe8Kh}`75s&kpAysh(RkEHo0r6Nuj0wL-e&t> zyEirBo{2?FmO4FTdy@lOO{IO>N&IBoHBDyVdLQeI;5zaoB?So~fQ{bI?c z_?#j>FR`$v2)h!CF(r@GM{743`b(_Ykyx{@P#s%|0UMu#qF`e4~a#8v+z%1VaF`SWBX4b zjb~_=^QCck9W*-%_0jB0Oykfzsa^9&V$DyWb{dCy(dH%F2@mlu4CU|imhmVs5_ax? zJ~nf@v&3cEv^V=^*hoCYdz*QG``2db6V=>o-dy#%#PmP?Ozrf0>PMJ9N1rE5_Q)<_ z8i&R(SPyIAMfj+PK4`i1xttIVGL%Wu8hf-A^PQx3Ioa@WF2~uZG=Qp>$btOJe6ezDl#w=Oq^ZE8=H~ z#qSl-Ph#;oMSNajVGo2|ndikga$Yo+)@~xK^;ZaMb|lv9ORSA6vF4A&nx7JD{sY;e z=W%E}!ZbdON0|Jg@d%T@G#+7^2aQLV=11cZrg_tNglRo!Ji@e2G#+7EKUzmayPU7q z-%RbA9f>vj5^Lj1tob9c=BLD(|B@FP=VN`M*9i)(?SFcG@-e>tT=B(xQ4L9F%=wI7 zvYuqj`IFi?uM*bsznL)SVZxlB33J{i%=w%!ohQO>EMd<7hIW&oze1SL5yE`F5Z1<( zefT`0cFj*9tobi7_j>MXMiM4Sh*8GuJ^AqW_w0>llu#vlueEqrj()J|R zDj#b|YmKK+{l>9RSj!=@onn{vx?21F@79nM+cYk5_whPTUZ4JHuHz`5()FEl|4!n% zW{bpS+MG4{W~`N1a4W8B7E2t}ToKn7!z32}i|ZOiV)1)%T~kr<`2#F`z2{L$=7tc@$N=8wdhpAu{SORVOQZQL$$$QJG&OXHD!@|VUV zO!J`ev~k6`rbtZlrtzqq)`P|)OzTAB5vKJs%!}G%4gDq7?3k&Y){oas8&|e#{zy#g zN8?d{vPa_)*5<|SANjJbr$X!VpUf9?SJ|e&&Ld%M-pk@gMs(c(g4 z+P}1Ks9lSrSi)L-Nz8F)Xg3-9ORU*Zs9m!!u{N&6nm-bA+);ncf7wpg-87!oF5`}{ zwx8LKj5})A_P=b`;zDBPk@|4l5$3of%yDOEm-E&7ORU*3QyhIScKT7QW(I}&U573!~zD>2{yr*_Rx*{=C7G3`SdkNRl$&n4FGt4qxH z|26ya{y$;u{=DqN_y4J#@Bb6#`~QUb{=cD}*MYt-keKiPQyf;aF3@Bm3X`uFc5T z!I?3b>vA1Vb~~+192$cYx~aHImlzz=OvU9P2Fuq_aZLH6*lb4zOt|($`SgAaZV`Xm zuBGi$rSYjK{G~;@wDZz03LlBT8%s7PABw^+a?>Q9BJkm875gSfW6$Sl@HpeCk`WP& z`KGA2Vq`Q<#Reu&1_7ggNsVHEz@Q~Z5oVe|K=QTU{ZiqHQp#;Ty=b)QCK z6-O1P-iyZ7-YL?ze0gJV<;WE2^V1!HxVu2Iv{UxmKupe~;xc0c(e7oEZ12+}5Ia9m zaroUpd})&;?Sy&;;*}?f($42AL-1f7?X!bIFs-ACJA5621zqnH}nd{OE!tp=P_se@OWR9i#^GH*ld)F)9(3U>sczk`MV#kS*7Am zCH!zgX_epKJNseDZYsa$X9r;HbafBdZVJHYeJb9yHvl*Oq~aX{+q_coz@h%w&wO3Z zx6%rK^k{QK;_J)(5sKZA^X)a)A4lK5F7fFO0hl=~Q_i& znTLw2cJasZcA0XH?;7}H#qODM?m6LMXumW|+PRe;h8M@FIMyK?o4csEVbgGIq2U#8 z!*J2AThg~HYr-*fhKeWj5652xCSJb(Djb(DQL(doBo+=(?PSG9;-wI6tSgatFh<2e zIgvQ{l#07|jl>|IThh;--$!D?v0Kv5`+Gug`Zu?wpOd^ou;~{no*oq<_M3_$&V}H! z7q`?sFgz63XWW*bZMQ8HlYMSWo5pw?=MjrHmx#XwU+A&2tSsV%aW}y2)&nJSn+0oi zy9rBr-dBwAp7&ua_PKCF+JAo8jK4n@9C=(((n1jTRJaM>{GOp0<8*a{7_2!x9hSR4 zRo-rm!AEz}q3z(O@67|oykU&TI1&3po2AOnes?w+H^!$*o5nm~jCW(+Fvj?=b7Ju1 zR(1ayV?1$jES9(wFXuZY_$WqoOO)%dJv9bj#3#x1d0OEpE_#(9=X>Y!QEWLnLC$x# zVV$4O2|?3{9NFJ?Q!w^U%awM#yn=9Tx4Y85k;kRgf-%lNN3Lhen;`sYW3IFhSA#Hk z${lIn$f{Pi29L9TNU~H;flgewn(0NO$ToYq%T%6Y*7q+}E`OWX` zhtX#Hhdd+6`&bn0t*m)|jh}dDZcxAKosf?g3+7 z{o3q<+p@Cde0Q$(#U~?g%XOGG*bjqKv*h|X7x%-O(dr&3HQpD;c2)O)FK0h4ikSp7bV;TKh=BV|+xmLcIvsyjh_k{Xjn;^B`F!FBP4@d*f*YiA5!c7(VEtHW_?JF zYCOLNeix0GqQrYUM1A{UN)+yY7ccR)c9A$~s*0C8Mc}mpD*mJO;UBG6|7e|TtUsMk zhT+s6@iHg8^b5y6@z-Ro7`!b4%Z|D#W8CP!ab91UBJg^pIGHnl920>rT3?en(^%^o z=VGjNjWzb5@DS{FJW=Mr(ltXdaa5wrjmDbXI7eemZmjt?EDORsqHd?NHMV3h_7(40 zq58*ojbO|b#%qMug?;hOJhcwV+9vW_+XT4|RZ0b5t5S(_eSDhwVdfRJ4w>fdi}x$3 zb%@dC`}!E||Ir-vzO%`AuI;Mjg$0i#OTM;0^1}FUk|dsz>y5`wBuE@s$_Iz0Cdr)n zxO@~&>V6C6l~`n&T_76AuFR77`k81<-JL0MKXHxu)0UeOzdRpvx~sJhOF;)AeX zm)q)G#P#DWe-(G{8;ZNGso3sd7;ZnMVn`3i8;exD)FBf0y;be7|8+9=n-L*ZDxVj`TLyvfvaSp>eCkq9U9Y&6*pio|*8iSS^o&or}3G!{G^4|iV%n9iSz#Iuh?Zj28yo&72TOAn8O%X>mhXXk}sOz}8~?h$6H z{6h$K5IDs?!qlozFisVHM#n{()=dvYww7<3CB}*v zX*LB<^uPA`?Rn~rOS5mni;WP=fHPcE}L4O3B&=nbKud)D<+qT!FXm&F61`6W;$Ia z6#E~^g+%*!Q>}zBoc(<+)XYpU6&VzP&)VjK!-gc&s^23qpKlKQFe$~fU~M#>J&_Gv zhNPJ`WyN5XL$_f;rwr4QXGgKbh+7a{;)W^yAF(*+bte3rebZ!_X~r2tZi0PEmg&kB zGgjMw9ll7vZSu-8qh~@o6idu8tqwM0vqotU<#WgMRbw-D@k)WybMBeGSrUuqzDkA} zt$#7)SuU<6Mb2?8_0UwkZwz+Wk^t>)Ju+2#9EE$=#l!b8PfWG9L}G4y9ISSEW_ouk z9M5+b+|_<=ivKbU^A(AMPl~)SRTvP0N6N=RgL^McTP#7icy=6|asA!Yv|%7_wT*{a z1K*g6pY_ME>*9S~CEuB%X8U2)=Ls-qW*+6c{=T@hNfI3H`-yUXvJb8eNrp$w^D3Xl zdE@A^sZg(IKBfCqZ`>w${QQ&r%IjXVFhhJW7P4Ii-~Gt7EX3IRU0$`dm3&EgHQ- z;^9mDLMas(iRN2zaNYAuWt?pUF6|cwr+1cC?3ae2dx#u?N|sFE*S^UhLlxC zi!&v2TpU#DTTYqLF%T<$5)YB>%PV)1{qcynUy)w5g0e=`2@Mkx;6%ZSO0C(xIJj66 zG{0L>8MoR8^Q=jRFRxWn?k0QV*TqtyMoeWTR`A&QR2rOhucG|k-5VE*9C&43RmEwZ zH=Zke1H8t5rCh%+V)N=vI6k1AY=I+%M_np3Y^dGn2%Q{~xRbu?`+}qo* zv1kqDD@SopFHa6!eOW^p`h6fSyOaajIW?8NHG=WQfLxe&t(Gz?D+Eg&&ILI8jS?*G zRnFWkuHCSFId*;A|kh)6Px6zpAVm37LsHYtGF$O)4-G)}% z>MIEeM{(YoTQFo^1I6V`EV>rRf*~^-D#~m#e%t3JWX)`(>=*Z@ykf6|U;oC+)f_XH zDVhP1&_sD1W5x;MzHxRLlaeTSd~_)V+&@v2>g!|i4J5QNG#dk7M4(!-%(Sl+`XG zui7TU+_bhzb}wIyH6_8>h<1vjh{w&5$jT3Hy$6F3a55;P%e-0#&VyfLzguj zm9U=TK0{OnWRK~jbX($$ciP{82TeOG?|$>fkS8~x?AKkC632YdaZ45?m+7j!_`w%5 z#5q2}she`*wjchZYBoH(*G)N8JpgNemIEm#yDQzI#l7z9InX`0htg?EFpeLa3qQE^ zRMyuB#Rnp}$+=j5~{gvB~kK(M+x4`T?K&d2nyyTb#Zodpru1q$gX~s=(%NnSB zE_lohxega^3{p1TGGm~4x6QC*7o}5#883HBgW1OhE63ZJap1)iSh07AVqO!Azcx+= z@AX5KQQsZKCMOc%{?cK}r!8afvn3)%W(-$WJcz=wYXy(pM<~VCM&jM8aZs+(Nac>G zb4qrLgXPYnlstk*ufigiell7))>G6-6+}Ef7_CG^2VujxanSn07{#tmAU?H^hj-p% zmB5q!=$jc2wrj^Jb!PbCUhzJ~lGDa3@qK);P17W>={-Too#=xTBa)#+vx$oNsyEiI zmfHilgC~+dMZv6Eo%)U5P zIpyPncc*1R`QT|vIbUDwEzZY_Zqt>3U;NOadN#NmnxVuG7563Ti*s$)Oyyu=ARc;< z1GB%KrHq>pjBUo}!l}`-m1)kQI9bGFgYI*burp!kzbzMvw3w?@o)Uqro99BE8uOIu z4pCUsBL_B=p09j2CK@x-vf;tA`AWVYV({DJw_(cd1C<;q``vz-zn#s znlU3f1#HSLRXQz=#d1}W;rY&`N`nJO@wuq|+JCZ4X+Ki%xIY0JEnKE_xEF;9;(R>* ze3>%0SERUh6EQerxpMzlIL>Pu2Wv8yD+Nl2p;9Og*7jbZVWLAKtlYOs327wm;fzfZe63c( zNBH33OUZC<>1rj}?2Qv=rb4e5s}-A(-gu-;I&7G{MhOw;V>fYMZg=_`#e0i4Ufp~H z;`*;u%86^Ah_;!~{i^so$oG7(X+{=&*>#;VGSe5mzPb&s%j>0=Va$w``P0CN=yREbd+0fEqvr?=2Q5-ekHoRN3S(#>v z#WTNU!Dr7mD;|Z#**78+I?UXnTsdsUixD@V^}Q{M>82Trl)Mf-2W?dxZ;1RUz608S zdaLq!hZ#3sN(I*@+msToW3f}|6j&3wP3c=M7K?qK1l_BCuPprXC?4*V2;+8qubg`t zjZc&W*!1RmW$)rBT-GrjqGxVbD#l0Px*c)gb#J?};LC74UOf)%M(t3d7KWmqLmcE> z*`YK{2}Y$}95}Sxsk~_(gufk%gVfNS%Ce9EoFMKY)U2{gsoB9FM+o~_dv+-^^7^6w zm_#V&yjvOV=!+!}B|+qZ-Ab`WK3K0x3iv(VtpvJ?{FyB3oGE*h?E}2A*xqzV%-*96 z9_WqNlUK!!Gb9Qt&d-5|Ck`pYE=S{YanHPB zqr-|#k)ya_>TO8%KdhYkDi$Y}xCLD+9Z^dB5{nHn6JBjSqWrqrjPE`ZwVA!ElAUbE z$-S;a!F8@mz3YPCjpBZFemAA8;JVj?RMI>Dzj-MMcLH$fH}TMLoVSv? z)E|o!Nr19R-bzwKKXk622s^s?DCaBsV&7#+u<*E#vZSpK=7{UH*A0A?K}SUmGba`9 z9Pw4Y74aBcGaXiy@>3l9d*j&OGr(b&pW?U28}H%`_@c1CQbok0rAsDkS>dlFB>P~} z4_UDOxxdmp$rtf6QU6a0P&ySAxxHgHG`|&~RGJfjty|{6QkOvG%K|}ICQmM`NeEO* zuMEa}Q*vQ$+aM*dRVZ$C&4o!PgOnnL!?Dy_(cUUpDg2KJ9A6<9RvZsjn)iyrrOR@_ zzHW%JI9l9`aLa}g?jg$h7cqE!ji_^qg(@2g#p2O=x8VGmP$lB7_-;b{^#+@lp^9aV z8T*yK32UZ=DVqe3v&UbDshMHQdcor+Px1cdf#FK$eP*1PlM0J}4p-6(nXy#+6o_aO zq1@~giyoJf;9g{evbD!ioVqFzs#l6s&K8Kl;@uKJIT)!lUmbxHwtz!GiL3m+wwro!b2uA+^75g?7 z_j&wPd~}Pb&nK#Qz>08uQ%uE6CW>o$SJlq0mXWxrkcu4(h`%u>-0})aHHjVQ^_SU*nhToFL?KjrhReIShYb4G#$3t`o+m;C5joe`xH$5EJf1U{arV1UtLl_np@59dic8}?#UkH}Cp8%Uz z?=vlQ2}ZAmiLn2>1E!88gK(FqqpmJLWJZ)v^m|FQQT&{Z7GzArf#gTa8wU~)7W z1Jg~;U=vNwIR}%$wd! zd%}00yp|R}*RHPauA1rYn(3LjE0dhsYbF0t=Y}KW*ldQ zwRl~;9Q`WXTJr54Rp@lQ%=jkKIyY1Ac{mg=U!{(+(%uVJvq#6vpY#1{&H64>U40TK zOO!uoRsLb08u?wEEM57qHKcx++E(SR46E~-)hKJYN|WV|?9=h6Rc)8P|9dJ{#*a8| zjY<}w&W^byznXT!I+9iIY0+_+Hu02I;$gTdb>zA%KJ$##euBPMGx(bPxZ<3({6d&& zT=uF==5@i^`u9HdNynw&&WqOmm!T?ct;_Q1_89BC{UK_xz8`&J_Z92hfMC@xdyEV^ zc+EPVcCT6*dr2lgf5Y+)2vQ#&Uy=te-m+fmxMZsmBQHhYwqi2x*4GSUWbfN|tz`Fi zsZH}P%e1fKtzYl?tL*yP(U{Not>gLp)ejr5O0SO(t&@xWRK{!9zobx9%8N+Rx=%!6CZBL9}2y)2I{zo+PCGrynk8&-Tc+}dVfXvLT{|? zwe_`Vokx7G_|}@-DnLCP7bjCScyFzlv0FtKkC(qU`^Wm_XrLOfHeR-B^vPOVXpbtT z<1(ap65*P^SLM>z6;=79V%WoA_1zfFBAFG3 zrp{EnD_=H9DFU*GtAGr5WR_N`M7Q1HYWp9tGDD}-;+Q^PHjTR_lXXcWBC*9 z`>tuln)~6ZrMfP^>idP5Gd^6^>wQhW8J14WIUlBWl)5VOjQvuadb>}}&3{F<9h+X{ zcp9o^=zTTgCu9)&Lqk-ug)ws0tgl4Z9>J=4))+Zyo^>I+KVF3{nC5 zd>Om)Ymuv+zFuL)NT0QtMeFptRpjq6Qf|v4GTqswcI)wNfL~VOr{l6^>J`~E;2Y7f zfWMl${;F){mrbnIaT$E`n%uKHyU18YUmFoO$_Xh zD=L@xE5c7H9hXunw`kGJUp1R>NB({=k62fKm&&v9uB`Y+UQwoXfI2lHPS!b_Pn^={ z%b)su>3QZ`vH3)x%BAB{;%t7=N#En>qT^CJrhtfEu~*&H=gZq$1x4Fu!K%GJUxvmP z5}k^Ns)tYG+n43Sv;|y(+CfU%cv66pMBRsV7e_$q98Ui51Otz9VB~`6l0sQ+mEGe>_HdwW=(9 zZ|+i`7G9Rm+f@;b9{Q_dQ?AIjZK{e{`SqG@%T+nFoh6Dd^ivJ=96GhD5Fab~sUZC= z^L~A$n5^T{YsXFbY(O>PqvO&|k7JqpR2R9GpDNSfw*04W4NxqeL_4usMm;H0=iy2RY)g&F4(D@C-+!FeFxE{wA&TlB9TkKN@3&+WTWsOA5R{Gjk ziMz7Q#>V17zHl`t^&MHxyNS3M5UzsszMZB!e-K?hhpQZ8Z|N;2KZ>N8BUFp8Z_4|T zO~tx+Ef2UZCmd@gPK^y$r8`}d56)g3phHhd=b3av9?<;GRzPlLq zt6u;Acv~L)x`)U<&|kfodq>XA*;71dyi3*Hcvo)C*Gpv3aalAzPF~8>TP)S%Sk@x( zGWoZC#J86N)hRu{EG*Vnl$Lwcw6pQ@X!(Akg1$d8OUGqO)&8Q%qhK{b$7O4k0ivLu zUoJk>*QRO=6ph;MQ#14HdnHWV2v^az@u7BDJ1hO6mEf zbN8X5wvJ2Hk+pmgsv)&UpZ2cI~rCYGtqR*H2 zYsZQV`h3}|=lyeQ$B718gH(EbFUD{4c=51Spvt1}d8P9CMa=pqKs7%ZBY*XqAQs2! zV_3&!r}soL?!Lb&KJ$v4=`%^J&grj?_+OQ40w#+dv-G_G>Y6OkVT$NlLGMdxctZ}o zHbwlU=a)MAT5+lNQ$^>Ne(Kpjw`8_!Q^oCreyX3oKG3P_H1TSXUO(tPdn4{n6Ki!` z{@id^UhAdbA)(_kSI;lqv9Ytn*A+t5*7!Kt_VX-Jw#z=XICq?^KYO+a(ASCw z7Q8DvrJo}P>+_|DK3_5}o+H}n^JU1-zj2;8q2sc&$2A#{YrfcbI!xXC?y5|`alRPxNat(W^!2E37l^EvL)GQd zm*uDJ3&cS05cO$lj9gG?p%~IVSnbXdBcEvMoQqR*GRK8r zRUR+3RFs+FrzXC+CN~A@cZlforC@^_vT&JY;!{EG|Lr&B(!gaR{ZIOySISt~pu%zy zf7nl*?|55&6~0{59OAFOU3N!y5G%x{M!Qt!b$4Y}*9!5Xt={9R&zC={trP{8?pAF} z#>>dVD@B#~Kvhd$-&@gml{i#ukNQo=<>HxD;@PUb>MuRNoNcjM+}HEVvEe$$xx8A0 zR|(a7gyQ7wZfnH#?m8~H^cvuS&bvE=sS<_n%Eg1$ih_E6S)k{a;!oEKZylE~5I_A9 zrex8pa>|piYR$m{{4QV_{}#&#ZHfrQDZlWXPtso59{l*zghgXEJ&TzaVh$7vv^|#s)G7_DK}}0_%7LQbx_A;)Q2sihaSh? zExjz;PuMDM-O_uO7GIGMKW`Pszt(fjzN<29`Zlp)x}SQa<5DflLFS+X7kpE2I zF4pOF@*D4)@^C6IF;K^)UAkC#V7`}d>A39aa$C;GxI-M%=S!=_cVzgo9b%h4UvlaB zr9l>N@kQqVHF08`e7DwH3|PHe#g>kjKKXsbnFoQY!M1q0-PcE~sj)}Z({Y(xO6Sh& z^~vH z)`$?JGU$EUXX0i4D-ptXWU%^rwVvO5M2ajYLe!!>@iOz{NHMX$zJ5MWk5QARStAyP zs{&K*$Upkeww{cOP}l0-mOY9uuu>L{R3Z0o$>4}3mRuaEa{Y2s=1IHKTDUJ#J$im! zw&=6gy1PD7-RP&U2`t}eb*dhz#$Uc7^IqO+9b6ru#x=ey3s?5G3g~;v#TUfLoqc?* zG}rb1#-lf6;Hmpo?guV4L$9lGfBD!xm#TO3maNlZr#0AesqPDJ%Z){Rt!iTF>63=3RjckvuSMIf$#X;1xkmb0O5bhP zczx}C@{#*;ebKGfhsJxA@2mUri=S1n=N1eV|$5LOD*T#0O$UPXOsL?ij>#o{7jpyV^ZIzPJcrd^V@7C*K3l0*4&gqUv9Hf zxARkJ3dhR&!@MjXZ$Gsvr{1&ic!yQ1zrVUR?~V*9>1#dJ*X>*Hxhprd^|NMW2~ahf z#>uUR{jGO50#w=PI61OPfc3FVpgKJ`UgjDRXk}g-q+00tF7=u{*4=D-)g8S)+2I>( z#d!rQ*MfLi?nS7zCuOM0l`LMSs}OEoEVWNx3)1Ix(?~0IU7hpRxGP^QQr6;!`n>LO zN4Cti-}_RJqdy+88tOe2f9O3GU$i)C z`PC0sF)y#m0;`W($7YAABS)^tXq_W>oUhj;;g_Xr`zf=3<9*y2>u8D)wZC?ZJXh$v z^?cJ_)#lkHxu9;el~3pIzv(r6iPo2_yvqaizNQ!%w&AkXy!>vpATUNQy>-!)VuJ+$-xzGJo4^Ifvqdi?n* z-b$(GyFtI*lpXx;Tan%T)Q$SFa*581+r9KtXMepded|22tRR1N_lchG$~?1tcI{Gq z-rbe8n!hmqpS<*yB`O4}heP6J+jD;!|9}1Rjq!g_(s#!H)f#;;{?E4Hqw#+kpU=ks zpI#>s?Ef<1Nd@~q&G}@4{og!E3c>y#Rx+hv|EFu6O0fU4jn%oZ+y5^HrxEP`o|DoF z-anIk^B02s|7?Fc!Tvva`b)w7&lQtiu>Wtr&mh?U&2ncH?Eh=UGwEk)Z2#A4{Iy{J z56_TUu>YGB%OcqS%iClX?Em1Y-w5`9Q~zv&{omnqcESFya3qId|9eO06ny;G|0|bZ z|Ch^}NAU6gRpGpXkN+;;xN*VvpZStM*|Hy%*jsIKzQpWgy z>-4h5|9ySR8UIHgD{uVY{Za+v|D$gz8vnnItYrLuF8X`p{~XDy82?u-UDfzMx~*mW zA3I(c|3?gy#{Z?JRx|!TxwX3Sf7rnq#{VnN)inN(yHd;e-|u5>KgxVFICU@ z|BD~%8~=+;4UGS@lx%4H-?4ootajQ{`n{YT^fp)pO3|1-R8 zX8iv?TMOg=%SBrn{}(OW%J~0jtDlVjJB(^={C{s+8{_{Ux3@L^pVYUV@qgQ??T!C8 z1$Hq0|MhA|t_7lqG@;I|7t^e82{&*)YJHXz^q=z z|7HDp8~<-S(Z~3|_?5oK|4ZKWGyXpq)!+DkUCaRE|Jx}C8UH6OH`w@pV}~Ke|2roR zHU6JAVwmy&U(T{=f0v1mpigohBOp*PT7d_&+vivhn|${!@(q@5D_p{?9#ls`3Azk5i5R zdn}x0{NFt5bmRZAYo{CkcPu%>`2TA)!}$Ml?U}~^=`PGP{x4W*mhpeaL$i$kE4H6) z{D0)xY~%l>)8`ofXUjU*_&>#xxyJw1vd=UAU+6o}_=UvBVXAF#g{(b*1rt>#tWC|L0n}%J{!&@zuuv zedez={%@6ijq(4Oz%|DIsq3vZ{*S)0*7(1}z;(v|4eqTo{+}{rz48CqPwS2Ue_yo0 z_&@ZUjmH1i*KIWZ|FzU64i|5VT0`2Ti{xAFh# zem=(kU7q_G|1X{FYy7|Swy*L3sv$d#|07fS8UHt4?`QmH!1({|pxws*`Cjfe{!cbt=bP^JXGG>8od)3PmI>+Cm`E0NXo*Xax)(98v^tIv(`rb

2T3f=kj-T zPE@UXgzz69rhGo$kr)4r5YH;>YrofT%Ta?O#nfMQUcV+*wtg5XGNg-8M=Rf=`Ve(x$=wh%aSx4`2dU0FUuNNXZD7`<;ij_GJgotZ;&*9RIH|3`aq2i_9`&9pL z{XBwSsMtKhrFJ#DCV$MoPmDPpsowfuk?B_N(|a%?w14z{`IKQIM|ikO6@N+go)9M5 z91l}*IrTF>=flMGAYV1I{1w@xgujUS(?=CMcvTi&=P!JJ@lo$bUzcyQ>=H%w{_1bC z+>|%w>=K#!`l#-aw`A+jdf&nkz2B_+ZTV_cfcS2RuX>l_uH5%HK(uP7@4xHklvi}n z`xbN#J3=2nr_Syc1CRKtp3(PY&U%4jWT^l(Tkiq;Eh13V58bU!TMuNT(m^8A=pa>S z#gez5wX=K~ovcaLbXAyoZx>Au{Ydar1kLtn4{>b}e{ zWv@sxEL`2pa8Gvnd#@1d^f49_Cx;IV796|CXgzM|JtP_R9+JC_eZ-~Z!D^?BmYsgn zW5|;|s)df-Z{>Z($09*$O_6B%)XP`w8ldlU={+P}^X(ML^!=Su6)(!KR__#D^s|kd zb6k>HGWv;EW&D(n-b1owrl086Wv9xjulwb`=4WDBeDXFE)8x#RS!^G4#aEFO$fg;`}rjsXlo0z7FUTb1{r_MSP)6o6vOib66 zUvFai_0IJsrh)l3n3#@OxxvJ=MT(6krt`*cG%<~Nw$a3NTF*@;rl~G(GBI_v*lc1t z;lO4S)A1Fyn3#6jv&F>pMDeXAra885H8Cxdb(@Llm`QprcE@zfpDRsFa}3qadXIjoPF&%V#o{4GM8uLv|GwhykV%ngPzK`HOPgm&uete$RNWaj;^vKkO zCZ^*)EHp8#I$)8BY2_P>OiXihTx?=G=fYwW(@Tw)n3z7xrWq!t zm$J_^F|9Fcrip3aw=+#luMD4MVmkNHEECg3J!hMk=Daf7#B^2ZIVPqJc1$)gomhK{ ziD`?dDJG_s%1t#f-R(2g#B@g9X(pz%S4=Z8Es%V=iRp%M(@jj@otbW8nxfed6Vve0 zLrqM(78+(^TI|c8O-ysV``N^_)xF^+rq|AmFfm;nIMT#4&4y7XrrTzWHZgrWc#Mf@ z(zatwOb0d|XJY!a=y(&;2kCz?F%3vN!Nhdl`w1qdMITNyF>QHnl8Nb^?K)?4$F$;- zJ|?C`X7)8Peb=?0iD{#{{Y^~2t2)5MbYZc9CZ?-$4l*$fOgY%Z)H`UfiRr<&olHze zUG8jRn)`GY6Vv$6t|q3JwskWxowlUAiRq_bdYG90+Pk2sCZ>a4_cAe^w5^GW zY58eCn3!G}^P`FBwysT0Oqc)A%*6Cm)#fIqtqZp>G0l{`rHSdZ=PgZ4^IUFaVmkcb zPbQ|n__a1Mjo;YD#I)}(ZB0yjc5i25TC{U}6Vnt;JD8Yml^sn?PZsKAV%q6%eI3Rf z)7^LLn3!(4tgp$q$KDaa^-N3;udZ)m>a(DMiD~Ky4NXil4ryd!TD*N@6Vq=~G%+z1 zKUgNF&r1pu(^dJUiD}og)l5vAzo}+o`p@0!CZ=Q0)G#rv8c@^3^t*MnOib_9uWe%b z_OD_lrn@c{H!*E>qJ)WQ?%DiW+GR~lSC=ej zV)`^oc@xvWK9)Bz?fSBUiRtar6-`WUgj6yy-5T`0iRq-Rl}$`@EvaH+T7PU+6VpqL z^|eiROp8^{Z(^FWQ~?vyr>P2>m{xmS(8M%nCn9e&`#Kd&_uA(NU>)IAG zF%8|E&BV0-0$r-|twjdGcoj;@^B#PoH6JSL{WN%ESQ`aI2RV%lw8 zJ`>a7jZ&GI7Acw-K-|22Tpur zV!Bo8`vvZp*3J6S;&pHF&z~$lPy2RAVqzLrJ*kQ5`U=TROg|JzZep4uYYG$7JV{cT zm}c=$X=2*t-b0IXncsIjws_r}W$9Cka~Yp*&n?bn=2$N+UL(b3eQj|rbLGjO7Uwb@ zeBW4{%haCs*5X_yf$;#_7?+#eR_GWkPJTAa%yTXfpuTxN8? zvlizvvud2TIG6eK{({B1Ozee=7O#=M*%4#$8tKrOD;DQ67aCo&IG6D$d&A;f#_#b> zi*uQ6VX+qHG9?1gcjKm+4VRKTGS*WlCoF)#6;{@sk4<=Q1D99DeZH_GP%sh->fh7{n^TGuFJ}+ zc3FL^xRgupoAQ~k+v=>JIXzrJKcoF!kkxEVggUM7scrhW$LdxkT-_LcN%o2lw(if| zrqXSr(cfFGO>&O7$~|8dS^Es}es6zO@%<^{4J&u6WaVs5x?zv1 z{q!Ws`)t#DDc$nAOT&!*A1xw{oyDh>u`mAIZ|cpt_kd~7*7pb1lAiYUg!6|FsUa=x zYYxj&A6C)r>^qrWVNA6Os$VLR{}+lN27Uig{Y)4keO)6TLZx0v=1ExX0^ z3v%u+^w|&p>U-mrelK6}DtoVfho~@>Prs`TG5WbvxH`Dpj$_bCy|-kLz0dz&@p{zf zy*_H}Jo{M9qMudComB62(R~cfyi+|`ZXeISIrRRYAMER6iO=#UKFgo@EPvv&{E5%< zCqB!c_$+_ov;2wA@+UsapZF|);He#62GNKG?)P9`-)i#62GN z-sZ$T9`=6q#62GNe)a$9dpw-aqd49dL!%yM;@odw7+2 zLzGJ$pLm_v`7XQvmG3q1^T_{M@AG#)oByBvZGyyS{}Z46=V#9opZ&Mry^#3qzy0ou z#ApBQcaJ1K`)|K{B=OmQ``s^z&;Hx*-bsA+-+uQ_;tX@ z=Xv5g&;Os^dG7okcjC9*|Lec)?!3?Y-}U}^=X21W-lulnA5VN={lC_??4|zp@vNn{ zWk|*q*88)5>S)$D;*wwL?-9R`Cw}ys{{E@{Za8$-?cJ;Lm9ja<)KFEU?LCsuzZ<4D zc-dwD(BC*{R!6^MU+cH8vPJD|8ZFmm`CT-$wyB_D=ZJ3vd#PN1pC*o3>Z3~ib&~i& zl%JYB{seLFe7n`^Wq%OkT@aJ&+PpD)sFCN?-?U==lHM+3r|^vZ#(u=d1E$`cpAVV# zv>ty%xyHwk{c1gaQ&p~CC2k$`8@&qxZH9d4#oM-A>p%HEo)~sM^>{!G`+wJbOpJOL zL_Q@(dwx;RiP6qtm0uF0{TcJUB1XT84YnEmWjXx7`tT3if#29Z{K@sg&)lAXs7zP!ZvmF#W^|#zMrsNott!?j)77az0|3^ zXGkY?#U1L(;xnZ4>EI5Prs`SJIpFW3zASKxbmso$qpoZ{MLKVK`l>wLPm|8JGk&U^ z{|VB`nap3^sC1HaynfW*t4eu_bb1%ttv3Jm2kE4&t=~b~<^<_B* zd<*kXCqyzu>=6h`GX#bo#@Q8HapP2HG zNC$qty6h?Gz|W`iKP4UbdGpvOq=R^^U;LbO5U5cfZR zc|kged#zp1Ne9PInkTjnj-QYYFG&Z-PsOP(NC(GTo2swK4*19pTL=8`n5~23neE_s zW;-~Z*$&PNZV%22ZV%22ZV%2c?ibE4?ibE4?ibEe_7Bce_7Bce_7Bc?_H!zIzO$ck zzO$b(Zg9LXFL1mtFL1oNJlkaA{>8Y>isQb#;TFYlKb2;aIezl5+obsT**apg;^Sws z%bv4v9A;{^$sC7|OKv8{aR@tnJi`tj&#=SCGup%F1=_>s1=_>s1+= zz`Rxg^I8SWYZWl!i?s@v*D7FMtAKf}0_L>}nAa*`UaNq4tpet?3d!AT6_#VI!unXN zfO)L~=Cul#*D7FMtAKf}0_L>}82!Rp1yjB78S_RB&6)>+=z`Rxg^IC=E z?zIZbu~uPytX06ycrjzm=H$dR=l}dQXRBOWRp>eWj`3F4MTX?tRnZ*hiCcHtp<;hM zLwqNTuPS``6!C&={_5zklf(~x*sb=iI6;i#b5&!Tb3P6+^3nPmpsfFGL6@-;a4pK% z|Fhx&Q*U7IL#93HXB<{tqhrW^fo?iqNPCUAhMzqTqRo&$^|?)Q=r_6%M+`f!Zs~Wq zYaQ61vgQ#n>OK1M2{GC;?aDJ^v@^Em3u3hYuiP(*(XUK>ZAO1t4nMFy{KIzOH?|Ld za=q{~x96|m&8D5PF`G>L4==RGShN{(?l1J&4?lYEP~&=DlapFJ5vxjjtJM3i5HEk> ztuB_iOg#93kJ^9W5^idpn9XfAN}&? zYq2&qQ0>*+>(Og5?5iMESbvWdJh^I+Dy7Rpr$ca%YWiyomCd8S#T?T!hHNVDJ?eCt z7^-Vv%pR5J!X;|MSBLhhAI%=Vzp<{r7Z3mU^@>!tC*7j9P0gp& ziN3Ma=Fp{4s&v!a)USbQqtuqycZi2JQ0n~DIN}w}TH7EQQ|HWQ)_Q!a#S%2vs zb;UQH>RR1xkD7Ngp4#wwRFJZ|->0^vT^OiZU4KAr_V(Vb<}`goeW{c*Kvnr#fcB)tUdz3ilhj#K)f!FSm{m+&BRl#O=sNSMK z_^bS1+@bcA?&7Z+kGM_koUXs8kn4IZwZG7Gf8|v-mil#Tn!l1+VyV9^^*1ql#or=s zugkV^-6EX{daXFV)-5WV!bg82_^AHwygrXUH1Si}o7!=2{EeULpT~~-`sKdr_wqOF zxM%lK*Bf1@Hh0T=KouDpBZn`J6FJKrP@SILlwMEoi*N5os_KKHrTY7!D7X7pwQ%e` z*(`sY7^xyv(qq^3ciUeGpGBdnXq$7SlfGYsN)h;o%Jyv=q-wM}O*Yrp4OE|sT_pX! zul2Vl=G-S++0r{yMW$ZBKTd%68ltpr&+uOg0z&;;Vcf#*+TIx!YCFs+Xt@ zcbfaE{`DS^&Vy9jRg=RvsO+{J+tt+C@nkb`-uc&>cbxIcr{B?9>gQzYI0+>wyZW8Rd|ZvMdPKEZroU^f zkFmOWe^V77TqSNk(7rap@)5^xlN|aj^2HOw&M!3|5X1huERTs%Z@|o_#Ar|Gl;^}~ z=MQgQ5TpIsuDv8izX}$6MU4Kk9DZQ^_S!#e2YzGw@F&*`KXZHLeA;B%8I@y`;`Z-7 zY3JJL7v$Vu=(8WDWe8ChQtEFrH9aDVSt06{{+82AuXEz}-XZF3oeQ$ehnwPmWsUUL zsBm>?NetP4T_8gJ^8OOpe|ScJ+q%~!vfqAkm^!^rf2T>e;o0DQYW-)sJxl9{s)0jn z9<9HBH04sX{I>aJQN8k-sAV-uRzLIihp2^h)-Jl9Z~xi zlp*=F?{`EsC{vcWS9`Ch=mR#l?=~;$#I5oqpFC|wB~kCfZO&G7anwV9n0g25gMMBTb*zkC*SUp@qoNDjoPW=vs5)tE z&Uj~G)Q1?m-Ume%MvYo!bBCD=qITD_xoNTmQ8^#j?fG@<{HSG9Y~I*sew6jK&A~0_ zM-AFyw+-^mrEP|Og9CQkU}t|jn_<7i2fLl9x2K=YXwQv)Hlv-Zs@RP7r_5zD`js)0 z&8b>1HS(}>%Z&c9B+HGR=dR_({-n+;Ouh4BSD5x>ueH*&)0(i-w7<}jm8M^ibAO@F zet;eJ5A3twP%rxv?O{Koo$Pt@=VYR-nJwEb-UGkks2 zp~^O&`nWDizOj$_8lBcfjoM*zg)3{LZa1*mYwX&ncCq$3GOgO$s3gN}UQ>K+RD~q} zChxt-KEI%!{#%=2XJ)v44#NJ+4mP9S5?|Pi_IMq$&tJ5&^BSAc{*&WvM!#Z)*{rWg z8u^AaTa11{%obxOdf8TEzemMwrrsf8+e~{tX4`JsnXlFMC~kk+zS~W|Am{!>t=?zoB0CC)&e)MmyR6Xg|k=$CE~-v+d{c6U<`^n8y|{k1b#xTfjWFfO%{I^VkCB zu?5Uy3z)|i(s7S1U>;k*Jhp&&YytDw0_L#=%wr3f#}+V;Enps3!8~7pdA!8~SydCUa!n8|XCnXHd76U<{Kn8!>okC|W|Gr>G&f_cmY^Oy-BUJZ6G<%mnk8 z3Fa{q%ws0$xW`N|kC|W|Gr>G&f_cmY^Oy-BUJZ6G<%mnk83Fa{q%wr~)$4r)E%w&CxnP46>!8~Sy zdCUa!m^t)XX6SJ40Os5Q%((-Ya|bZz4q(n5z??gPId=ea z?f~Z8fpq>0uS>8WP%krl!hHvG-@)8>F!vqIeFt;j!Q6K+_Z`fA2Xo&^=f5FuLf@S^ zl(X;5&~Y9coM%DKc@~)SEHLL;V9v9^oM(YK&jNFvMf(3u*X5jk;Qk^m++Q&F7tH+y zbAQ3yUoiI<%>4y(e@XwpFt1Fa|NAw=27!M+{n5@k9k`Y_X7WXA(2iwd=-0`;e$9|u zbSg5Ng@YA5XJ`iQw6 z=(y#UL!a1fM?mhjPwcLj*xept)C0djAN9bGVEpIwBY0=#=8ENDw;xFE_75@Q1OGzD z?N4I2pNa81^q}L8iv>pgunXq;9r8$rKC#=53v#!8Vt2j7?)DIK9HH-SKgr$wB6jze-#Sp)7W!2x{JVm@BzJqwXG>W)R$O6$I(1#fR;{Ra-ze5j< zawrdmJ=g_vJvevVayo9^`Y!0W?GU@|6T9mrcDIMv-A-b6`-$E4u{=`O$NDZ^ADzG2 zj!V}^a&6zG>m$a$_!Gu?Y3Bf86#3^xgFm zyW2yIdf*r6pdR=Oe#8H>ADIzTC%gSX@pb!$81=)y(0BWj*zIRxxBrPzKgvTN^}{Zh z>vzcMTyyKYAa~m#cH1X**Guef53#$Q#P0SJyZgm*iX-g1{X=rM--zA*B<47}+e2{# zyW>JS97o7Gj$n?XLtlV7j$n=>nBxfMID*~nq_P}G$T?p4m*WL?`+<*##Pd%3gyRMO zaJ;}AFNgd;^}OTx#yu}kjCfvitOrQW^BUU5^BS1vHR$ua2071bV6Mj@r*X!uPt5Zg zba-9^^StJ0j|+01*T6ilf$^WNk92rmgUmf&keuf=$a!7^^SlP;c@50-8kpxbFxTUd zQ@nUygPi9zFwbjXp4Y(c_K=@>UW1(HH8B3eIE8bK&oB4+Nb?#vaXjomV<4Yj@Clz^ zwtwt-%^|1p->v_@eLTc*kGlB$0`vI=cCXV&htDs_`TPR&`32_l3(V&in9nbVoaQe+ zzaZ!H3(V&in9nb;yFKJXKEEL6^9zjQ5XZe+PV0X#pI=};zrcKcf%*Ib^Z5nl^9#)9 z7nsj4hn(WY=NIIBeu4S?0`vI==JN~8=NFjIFL36FZgSn~I&$dO)4j4Z>r7lfTW;5m zlC6jHtF*Wx%ijTVU8m9bnzBLdVkem+^IlL<|Q^?M+1LHDUV1XC(tpHSru1(DcC@b2Wr(#6rEL*w+p1mF zirb*0>xA3|h8%T(p^rM)4(b5IKK{Uvp$;%~Q3ebfumy%~)B$$)i{-+hFC2D+!#>r4 zvRX!UfZ+p2JE;!H;WJ0SAm{!&Be4BO6l{k!9n z<0~9-7mnjWIF1uKR&Wex867KN9LtX5jgA$_aqQ2n)y)fxIvvL?^ywJZb;1rY>^P2p zssm*q!*8~oShSNEHc$uTu#MxhZ{;HtI~=!Q9JlBf7;Qwqz&Os)FEEaO{DC3EZ(!)6 z3>Y?G3k=)6L_RMt>O|cvN1Iq5{Q|=d`T&M~_zsLZ(JwISM8CkO6a50CPWTRtW6~if zKe+V~FSdht5u;8=y{LoRL;gou)ahuyy#JwpA;{hFa)D8&!w=L}$WbTy07jkY8yIz> z&tTN)@IT^3a@6UJ*TgPAtK9QWQXdZl4<@eaQ`D95Y!Bixxpue;q-jAsvCB(W?R!;- zix4(e zQ|h1~suocjxXV$|vI z59}*6u)QLXZc3z^L#HiB|7vYST_xidr_qQJ@cAq!ZBL2KMjjO={?JF&hoiNKa zp>7Fc@AXGq4K{p3obTX2F8wE>P5T`^EagVMjRZ3rD?F2kdBF zssjw)INC28-nP6Thc6xdg}z{YhkwuqTdsZS@F&_MZ97NMPGZ>5?I(t9XS~4eOGI-Y ziP0{Ug&aPCO)&XN*9S)b&;~Ha4h(;wK9aj*2ZsMXMZet+hF?(!%TWjGqYg0apbnC| zV+V!|zkxY+VAwz%VAw_-V2+(zPO)?AQ|!R-EBXLNpB(j49gxEZj&@QVki)OfCQSCS z?bxwnxx)`s2irj%V8ji7V8~DhnA-Di{-@YM&anfdUx~5%*NR<-rgfmbvtA#9CMBGQ`@3(zYxd8``$| z^J8>=u&xvGNS31xF!WIe7-cfVL}IrN3Yj&Rr) zj(UZoJyZv5Y8zAs7(R3K3v%u+^ablX{DVG_T-S+ui6PVNkHx!rBQ924md-TJ zqhA>!+7lmNoWr&I*Ji{Et<|n}qiYbyWx3%}9g7nm%auXl592Uo_zetQlmWvAY=L2$ z=QY%+;+@I$M_58xeSbX24gtM-E$cj^9;v}=Q5U~4%SB< zVAw$&Bu`w2kk2uf)os;6>0_`U;#I70Q-yz9_0Hs499);=SIR7QJ#SEnA;WJd3tg0f95!GJa<&adomx)UMZ6_~e z+i3wg^&N7w33Aklwz3`cf$hV0VAP2|gHb1Z0Y;tLmO@$7>5LcnM7a>O1AQb${U{4L z>W57*>PKB*)Q>+fWcUpXU6cXC25f<0J6Xxu+rS(Fk9LD$2mJxVzWyUdo%%Oo z)Cs>p2X(?U74-$qpU(g!ECr!=}qoS7Pk6KmV&^ zhdBmu#5sw%2aFsCc_`RDuMxZFHDdR?M(2@xUL$tTYqs2;*N9>J%-@;4VADOX393uW zF%N=KC-M`pdtS5U_Piz`N4@$tVrq}hWgtg8F)xGNIU2FMUo1x*tWP-+^id~rCAWRl z!SzzU1Uc$-w3G5Bs!P{7vBs!EwjIjRTr5YMz^D^#1;Y;dKyo`rQ()AIK7*+}|K@+> zXe7tHwr}=5IjhVKiGJlzeV6!7zAa+QmdnKX_T-Vdb{r+%H@lDYT@ysSwDbyzKa_mWv* zx(;G@zgX^a=qraE<*=_D^(seul%t)>(SB9CTkrhtenHOtg}!w63wDT6r^9ckm*l7u zeYWlNQ4aqrM_jNTR?tDeu$}~Ct%`Lf7;9CmKfze5VoeXmS`~j_Ugv|Mi!xx?fGsd= zbH8|<&vL9~Ss&|aFzjIM3x<8H!@;Oi|3-}VU=0m9>cn~;j5@LA24jwP$Z4JL)~9to z73o-$9PHJN!m{gB*3D&tTN)@IS5d zA;&sDF<$?=@j~p72l2TE=5q~<;|0e67{@k_doYd{{DC3EZ(!)644BU~FwQm3(NHIj z8Vuj zUPB-EH%wm*ada}~3&=4?VIBcv?!x>6#+-(E2aI_K^AQ+xAm%AB<|)iyV9c4A*T9%# zpR@?y4#pgdI#`Z6SRZwO-SZtW?Bfq|_k2eTUDN?NY@iM>Y@-e^avX;o>l4M|~m-&NUdD(VoeZu{PzJwh5r~?dNI{b!uNe-FA&$I@D zK5RJR^6%GOG>@Py=ojV=v=P1oqwVMy7=FVa7&80@hAzs0VFR|n@EOnJ?s(Ch2szrs z`sf$iK_9@dkA8tsC;A0Oo$v)1b)sKj)QPqDz!aru%)~kq%(I%A(*>>#pKg%6{ zptiCd^Z|^V1HJ>JPV^Z}?a{siqfYn^jP*aRhl4T4;W{}O*U51`9E|JdxE>D1HE&!G z2jf~e{=ksoH!yTj1`Hdp1%~bK_HNt`c3$$;(9n3 zb>ezB7(h00w;j6P4o01hdU2hf+e6pfp#vMZo)1Qy-Qt@U zwC&`fx>@e<1GN=$v>kl_qfh7?7~ZJi3tNIh%J?q4({*qOXs1QYXgwlg=h< zpz7XnKXKL`V^yzg7m4HloT}dRy-8)|`zb27_kEHde>hoXKKFv;506h&zh-_;@@Ja{ zt6^;)kbKLr&g#K$*NMyQY^u74KO!!5tg$N6`z`6e^sBG3#3fVcS6Iv1D*OEObRDnW zjHaspUpYwr@IgD3;ZjkOm#f)bRk~i1QTe0G5O2%WQB91hKsw28wN;a2OA`+p z+)xz{C`vkyo>W!&o988Yhp*rJBh%f%W z&$VXiAkt~@gO}^W^UlO|ORjRQ?QHj@)8DgPtLF3|`N8jpx|$B_MP(0EZtlvoa3ski z*R^qZcbrE2;bBWxk9zY+r?;%`;p=95mNP8mh!G1G|~q|Gm` zT^LR6xqPyyXyMz3WDvD_9XUt&_hhA-JNtk-kc)d6&^d~QShcatRY z+af(k|8<%#W!-iINj|Mp4mn^!KVr2skNh#f?&G6~{IZnGJ_hzi7nWA?R;1JaRess% z8~Zx^1^-;~Zu9R+ezj<3`LcXD;@%B%$nLQvi3e8ACy#b0LR|cxLh{QtWr?XDAh>5FZ+==G)X(T zW1l@Pb>G=nX6lfFY<~UQ7`g7(&!kf(_jnl>`iAVR?lM6hSpAgb*%wTbZI9dIXZ2+x zE_9fmrD{isX1Nd zm}cK^Iv+Yl?(k1S@}8Od$yI+Jw4X~z+g~>5GA&ZCcM9f@>@TOulq8>2cz~?)<@E@R z)yL|MmuaiX2HM%}fZSvGko?4r4)ST*eZ-yP+R7Z;kC4uJzn|poq!&n@uY3zR z^qY9%D_gqA6nQ@oUz;>QrfB$uMEjRb8!0pSW+49U!_V@^f4-LJ%3vu+}PV)QoUy;s&aX-rY15%T`YWW&+-IesjO~zTWbY5HkpE;G}@89Pn`ENbS z%9+iI5I-#}Wc6ni$d0^UM^4^fn|R=`#&T+h`lQqQetr4Py+*|GKh}}2yZuO9)vJcA zv#CDm-+WqD7Wb`2?EP~=S!rK+;?mQz$=OFLlm5OonPmM9lH^%Ge<72}S|l$$DTUmz zr5W*#2kB&$&s~UzB*`R)z8ymPuXkjY?N8?4e)>39gm_IQ z`SGEH#p~z#Sky7yKeU<1vbHzz+z?CLPv4jH$F|HRa#!z1ykN%PR>$J~iFf7<=@q{CwOzLE z`dbkz3yvrI*PfS%%=^i%Ye|*rk**Q_$!7agn<7(q+3l&->}F(@#eGS>{AdQ(iEqac z=UMu#E9${C;xA7LSGMhQiD#bg>RO(AF4=#+YJ@9fp6!!W+o!u`Kb=kTGs70T{Lf4# zp7O_1*XGSbscgaAOI?iuyAnU|Ki}1(bZ6pbOV_zh4(vdDbly%^hkk9T?EMzuuJzq* ze@+ZI<_dW9GwBR2b;A`CI)QYyHT%ouHQMg)yiT87AqB>gPC38is&eEg;!3&FsGd7| zlYaK9sZ{0k_HmNwW>VFwWdqWw*Z7UAdh$A?Gx>T_Rc3s3;wFRBs3qZ5NoU2y3@Wlp zJ(5=zIn{!*_PzC=>K9cD>e@EbdRJ1d{42R7KNQ zBRlu=2o;>V49T;nte{#BEkHc_vR+TF&P_a~L22c;G(my-t zoE=hMg@xrMJ~X1W^6ON9bUItT)$H%{5)aDVPc=@SlXPl59-!Ziot5O5yw1lqN05-6KB=;4#xNRgT}h8&0DE7u`ZGi-rh!C{_;2C zxh49jJxz|2PDJI=s^+v~BzIMqt~RCpmE_s8&QK+%hLU{d;~6UOp+CuA?3=0l(ybh;H&#K9F7sP2n$ z5ifo)LyhUXmFB)bn~zr=UsSA$b3bK+0cyl;FPbZF%K_@Elr1AM{+D^$Uri72jf75$ zcKy}TPDe;ysrWb*)Alv-pZR8}l+|;(px-Fpe3e3$c0vE(fq80G$=W1WZRY7c3HEvq zdbmH1f3Y_J_s5~n_s1c}UIN@7haC6k@dt(szd;B0(oqI-*nlm_*)|w;;yyjgasM6+ zee5Lw!w&BEvwd9$G3wO6(Q$=3bs3VQPTZ?TS=6cPAlBvokJ^`lnBqAXjwzU93Pwzk zAIv#Em~(tE=lEdG@xh$qgE_|sbB+(@93RX%KA3ZSFz5JS&hf#VAIv#Em~(tE=lEdG@xh$qgE_|sbB+(@93RX%KA3ZSFz5JS&hf#V zAIv#Em~(tE=lEdG@xh$qgE_|sbB+(@93RX%KA3ZSFz5JS&hf#VAIv#E zm~(tE=lEdG@xh$qgE_|sbB+(@93RX%KA3ZSFz5JS&hf#VAIv#Em~(tE=lEdG@xh$qgE_|sbB+(@93RX%KA3ZSFz5JS&hf#VAIv#Em~(tE=lEdG@xh$qgE_|s zbB+(@93RX%KA3ZSFz5JS&hf#VAIv#Em~(tE=lEdG@xh$qgE_|sbB+(@ z93RX%KA3ZSFz5JS&hf#VAIv#Em~(tE=lEdG@xh$qgE_|sbB+(@93RX% zKA3ZSFz5JS&hf#VAIv#Em~(tE=lEdG@xh$qgE_|sbB+(@93PAv-}$Zs z$2$-b-%X+Y^FQ(36rNtUapwCd`~P-4czW%~X%l5(KcQpN)9Y7Gn9mQmu%FO4>FG69r%jZF{e;G9 zPp|7bZK5pfCp2GpdTrTh6J=pPp*hRb>)TG7C=2@u&6}QHV|Us_S=di#?)LOLztbkl z!hS;Q2T$)cIBlXV>?gE_@$`O&(#wfqActuw5Ij+{+H7x%EEp^>uOK$!8vWBEbJ$=w)gZtpwlMG!hS;eg{Su-oi3;PM>-Jaf~ciKc**iR_;_jI3t()tbngEC=2@uT^satACc20%ECVHK?48#>yw`DWpdg?S+eim2L=B3*GN6xPvx|Uvap%Z zb=t`u?&)&cL|NER=vuL-`^ua)Q5N_t!aXqAYAC zblu+5J$_D`C=2@u-8=AfpP|zx%EEp^_b)u%>*%zJvap}fJrqy(TRLr`EbJ$AAIH-@ zpH7=73;PM(OY(HzsnaIP!hS;cvpn7V>a>Znu%FO9HBa~7I&GpX>?d?z&(l4?PMatT z`w87!^mHGx(3iKw288?pU^#4PxoUxZK5pfCv>0J(>>u%nog_vbrpqActubl>08X9S!!Q5Nz%EEp^`#?N>X2fX|Wnn*|y(peOx8k&kvap}f zei%=mopIVkS=di#PmZV0?>KFuEbJ$=FUZqph@3W27WNa`o8;+pOir693;PM}kMi_c zDyL19h5dx~XnFcPm(wQ7!hS;g#5{eb%xM#4VLze0YMwsV=Cp~ju%FO=IZvOhbJ|2% z*iUHBo~O_EIc=gW>?gEu(9>rOoi=;?EgPMatT`w8uz^z>Ovr%jZF{e<># zdiuPl(fXX%l5(KcT&>o<8^Lw288?pU{32uIdn&J{Rw_iL$Vt(0+SQpUrpLL|NERXwSc=?+0+&L|NER=(z(= z-%;SSiL$Vt(6bMoz9+$H6J=pPq316=eOH6iCd$HoLeGGB`o0LKO_YWGgq}n3^qmz> zn3cJrHc=M#6M7!U(|30`ZK5pfC-h8^r|%DO+We0^m-HWbX3g0Kr%mTx zDLn6nzWm>wjY|A(4t=NQU-7#+_=XO?f25!3D}-+lTiC#j~yTB z=%aA-T{wJV-K>|A^sQFmVtlTo#D5L<7Jk)i`@1Ht6V_q74TY|(5m`>!ZR^{6wYc!= z4fQekoRuOrjm=);mWj3P|FV5@Wsx}f_D|yI{PV?@yEc2LnI(pIw{byeNf&(lwJ@7{G+@outJ$9SLqJB@kf-RDZPwEI?k;VN^c;}`u# zyvDk7#J(|Ki^q1HJ#BT`SK?K6nl+v9^_SwdyU(0@++XpD2e(ZtJYDgzPySl`@#U)i z;5)u7c3-b*=c|XlC{7t(@dh0}Ek=x}`daae(Zx0GtMQ!k$;hJ9*op^kG_sgHs+!NG zJC7_bJFxl;j2bnnxMJ|H8pA&AS5J%XQ_ackT~Rc7 z{#fM?uM_)v-dyp?-MXhiA5{F|V=d{0gR6EPKY7jcS(~c;KXzF?4S%ZQeNJ69o%~)k zhVxcmCH=JU7`6HFNh_z(6DuCG_sZ$H@ncnf!zC-H)pxDVQTO>*OYaY;c=HzyP1`S2 z&Cf+E9hi6N@-WBh=_Q~nr z$G#)J@r{$x!S4(cmph)AKHs$B=h6x3FF(Gm@&o5SE`2qj;)~`yChf6XRcEd1k4&8o zuG;+korBWrU8=s;zw>}}@h=s3UT^<2>q;M}oz2(SFKv4GaB-hk_f2zbKSKP=xP8++ z8+|DL{%`xGp2t`7Umku?TJ_ygDxd$u%hOL6R{LsRxY4C)&Tdtmxo+y6Hr?}0)j8~? zJJWG3uZj=&;O4aZ{V#}j-S678_Z82Jzu4iLbj25gt2!54o%;Qw;uTx3N?-i&oXXqZ zcx7t;O2s`-z9N0}Ma3(ga(O!E=&JrKf4wZ-`g7I(zn<)!W_{;H9eetqUTLZ4UlOmm zT(8ux%`4)aU$`h;wB>)qTMfD>-L`x+&V9#Tl-kTYMCE_jpjTRS(ok{F_Lrmw52)%- zYV%kp zUG|}LeYcAHZt`IIb;v_1-)G+kQopk*?$iDL)N*RY6BoNL4H;PRnakXpPB^$acHw#M zNssRHsE%FX)jQJ8Js%TaGVb=&cK64{M;?BA8gx@No|}r>Q@hUxsC-J#+tZJ^RlH-L z+tV*sm*QR>??|&O{*<`&+Pl-|tyTM5_Ix3oGh5Zpsv8bYBe$uJ{mT;1rtVMQs`?$< zzmx8N;wJH;iwsHUPrgq4&e6}OKC4!|{BncSBCXe|e7*IaO9vlP@hMwBn+9)Q@v}=j zlb+wd;)j2FDs_3b;;-g@D$Rd+)y@?i2BqW1->7zWU3XyGzs=3!M~=*R67!_@GS&rtP}kE#Cgvr_y1oRee3&Yj|3$ zyg}tR4|+fCzfsj!hq3RbQ}#Vu<%ToOz{~fj!NwZohE+!(09|@OI2LV{!aS* z#Zy&&arJrvkgg8);?E!`H)vr{}ay>-#hNrwC6+Ti*MRvNLudD3&aD44N1GK zaG|*KiLa%@Zn#)HtjAkv_}(XpZ~oI)Y1B8>ct*T9K7D!L87gnL#klmBq1%b~dg8}) z*OA+bua4iY!R{Y(rAEi5P zs_Ngj<>>U*i(9GwK_`q#UEbS9{BZw~>FK9-5?}Z7h_vcDe-rP$(}*+y_a~U{YR#M{`)}j-yZuUeg4n&#aFHV zb6R%89^yqh{*>;Sry5(k@srb)SI(>Q)%R=L{n^Vqh>zKAN;-P2s{D!(-=-rUXs`19 zcKar+bXLV{@A!4<+_&P_dVZBYT)(RS?%H3bUAL*)Ii>6Pbn9L7>DWt;8yEXfbrhfY z?%1?Tx5dQ^A2uc(HF!z!YRimCAOE_vc>dMLq(ctqEdJ9CW74(fEGO>sx3RIm_VVJ9 zKaEZ2zq*2W-51BD?dDrmeE7NFroVkYS^NF2dU3n%Yn<6m<=d~(u6x;g4)NswwC%pd zO4q7R>xfyp|9M2UAM!Kn&eZ+ty>C@{-|;`D=a#Iv`@WOX&}}O|VfTq?yV?7w&ZGk; zq;-b$70#ReqO-b$dYE@lW5S!;T&#UTn{A)4umSC(gyU z>Fs%560d&fx9Nx*Ulp%7(|2jhW8V-jGW@$V$LT}Gt6uhfTK!LNi?=@Phcxh;dm;w>)!F|D=4t>U5QO-c)GbH8}aeiPFL z&zIsemY!G1ChlXdJ9t&`lvgLE6JA(R zyw1B5(@h^QBktd6V*2{d#l$P!J0b0Ub_ekVr%y=7zxbZU_R)X|>4BLCi|_hkLdvf_ zD*p4HaqNM&SG?||wDULDiqG8Q$MoPkSBQ^TY;yY3NtcRGpKD6``I)oC>pa(n&$IgC z^Bm_|%(;%wfSAufd@sa&FAn+fQ}N9U|C&yo<6ZGVf0>w`n01(V#}9uGDJLagYVM9YrG=9=B97cO?$r}{%V_V)5DuSBi=H2p&uR+FEZbE zX@^hm6?Zx4yVPchyTrS;`96K{*lpqqzW+W=*uRhXicS;K5*OVnUhszrsrTv?|2$@5 zx^l~kw>kC~u49>V%5^Nh<6^$!@!c2m-H+>`nCs!pXRRroIP8b??>qk>?tbZ)X{oJO z6n9;7d>Xgj3gUOSAD8C%c{%Z`myAuFmg^$E{k1Xa$xh3Pzu9g~8r^wm@zG0+Nn@{F zLj1}mW754{7ZgvvbZmP3h55xFcN~|_nP)!nmd}q%i(OZZ|Ba#J)7MY7SNYs?f0aHx zui}Tse3fpxrs7_szD_4@*+F%N?J<$xFEPJgacviKZI5fdm}`Fg4vP65yfPmue(v$l z)22)PLp-|u=yc#Ady9{Leq{Qj^Iqbme*7?9-}-m)UfX?`raZd4c!&E&q~kB%O}x#v zBhvWZyNF*bMx@mj`m6ZF3rD1XE>Ml_h22M{yZ^Jb%Fms7RQl#mTZy-LV^sQep=!*Z ze?K~1cEJ`ZKWN>L({mS9{NTc$qz&J%_{OUl z`K^!jkC^q(idSDIo^9N)bneL)Rdpu6o;E%CLh(AUzm|R&bb)xqMPEzDO*&t^?>R%# z$dAqw|2*rEwCD5ZidT5~)%5D%bHty$^J=>A%4$6KZ9gP+c;|GLKYiotY4ppdi61-Q zjWm3jim%w_&2;KR)i@tLHS%9xUhx4hzLkEc%Lm`_cA7Y$D*y8GVQJvLRg7!hIh^&X z+GM>NYdJA%xme?gS>wgJSIoM%%gOhNFYNzJTD9Np;!amRk^1zyO+2Re!1P4fS3Ku8 zIrSdhN8Ia#oaP-=^)+2o=!LPtayu`o=HbvQSth3MV{}86_0%UxpZik z8+Gi^!(Zk;Ma+Fltl`D1;bUztW^Et$J7Vs49=PLK@yCbWn}+rnC?37Wo#~pkRXf}M z`Hpn-5~a$Qcs1@j)~(un`N-STDsv4``Py;ckw1T2+-CFJ({0~9CSLlAC?8YJ^M7`{ zBP~9>pUNLU`R;VtTot!F>z?%bO%JJj@`d-N-A}1_-#6|{n>nwE+dp4X`LV4RrTeyiS=>ABF<0B? zCGpEU_ey&o{i65}>-0{CzA;#QdwFR(q;thx-n%UJHGNLy=ZwERtvmJXm{*x20PG>w@^?O188+b0Ea-K`XJ-e8D_PCc9b1xsyH^e;O z_CrYX`QEsi?4ot-}K`pABg9k zvTqu8;``#Q`tFx*x#d0awGZ!~9)0ay@jZ7RnA+bqOuWbTN2HxQRs6^!N2Tk(e_Q2! zzBnc=wtQ8-%HhYSP421qyO;l!rmR+-qYKtPDLpcx;)gE%cY0)eHJ)|9KAq=LYKP}h z@vKJ7vzmB@Bjy=SJl7KQTRP`_VV6`;i92c@6(9M} zmD8~YjuCGW+-?18-tHZ_a{8$2=PKXk)m74dhkPbpIi4fkF|a-t-PTAQ=Bv)d>brGI zuipQ$>a06Fw5xk6-hbis)Bdwmbq>35!?fE270>_lpV9+cRP9_aTaWbl+*SKs*4ZR| zeq}Yz(^uU(#dFAk{J!%XGM>?ic}5q{?!-L1i|3hQo@buEUo{V}A2X^LI=Y&N9p4^V z^ypd5+k&f)EH>V;nzxsi7+LJN$9Ed@ple1Jucqqr^Uxxri=%sdqw;RYd|bSB>DS`n zyM0#7K3m1>OdebG82P2j|MuNa#msk9++*IE(xB%n?!QU9wBY7nsm=~J&62t-P#ycp zZL_7@pQ?DNr)N)FUs?6F@4z|IS7%OC{SA7|o8tMi;^O&pJew8sY&M?Rig{)m&#}ev ztiI^qt*!Wq%{M5%n=(c1TzAE$#YRU>7XS6lO^as^{!#q&rRNiXYCZ=I!VGb|~78ujcLc_jW0EJE#8aUA#}xVQe*r3$ArWG2s1*FF5?%qTfbzIIJAi}vWoQ%P&?d^zCd8pl zl%Y+CLz^fY*YMo9zU9VsFE@S*a%dAeHnfQx+Jrc?i5%L5IJAiz+Jrc?i5%L5IJAiz z+Jrc?i5%L5IJAiz+Jrc?i5%L5IJAiz+Jrc?i5%L5IJAiz+Jrc?i5%L5IJAiz+Jrc? zi5%L5IJAiz+Jrc?i5%L5IJAk}`0dV(-?iNMy~~X?Kn`s}$A&hMLz@tXHjzV{5QjFA zLz@tXHjzV{5QjFALz@tXHjzV{5QjFALz@tXHjzV{5QjFALz@tXHjzV{5QjFALz@tX zHjzV{5QjFALz@tXHjzV{5QjFALz@tXHjzV{5QjFA8*8@QSkL6fIwv>QemS%W9UIz2 z4sAjl+C&a*LLAye4sD{UbHUX)vp-tq_Cd8plp-tq_Cd8plp-tq_Cd8plp-tq*T0J+` zvAMCn&5bpG4sAlmhBlEyo2YoFemS%WacC1cvtLdS+Skwcphhc=Nzn-GUK zkwcphhc=Nzn-GUKkwcphhc=Nzn-GUKkwcphhc=Nzn-GUKkwcphhc=Nzn-GUKkwcph zhc=Nzn-GUKkwcphhc=Nzn-GUKkwcphhc=Nzn-GUKksHrsa^rbLZal}xjb}SKv z+C&a*LLAye4sD`p|BO#_XcOYlCUR&K;?O2?XcOYlCUR&K;?O2?XcOYlCUR&K;?O2? zXcOYlCUR&K;?O2?XcOYlCUR&K;?O2?XcOYlCUR&K;?O2?XcOYlCUR&K;?O2?<5^s8 zJg3Ty=U2J$OmARl6FN4ui5%L5IJAiz+Jrc?i5%L5IJAiz+Jrc?i5%L5IJAiz+Jrc? zi5%L5IJAiz+Jrc?i5%L5IJAiz+Jrc?i5%L5IJAiz+Jrc?i5%L5IJAiz+Jrc?i5%L5 zIJAiz+Jrc?iQISwJFxM5a$w`R<-o?X+<~D@==o=869Yq=5QjFALz@tXHjzV{5QjFA zLz@tXHjzV{5QjFALz@tXHjzV{5QjFALz@tXHjzV{5QjFALz@tXHjzV{5QjFALz@tX zHjzV{5QjFALz@tXHjzV{5QjFALz@tXHjx|8-Ul|GOAl;3uO8TVhCeX02|eEqZDL?( z6XMV&a%dCc&?a(d6XMV&a%dCc&?a(d6XMV&a%dCc&?a(d6XMV&a%dCc&?a(d6B=h| z6FIaAacC1cvIkX9JXcIZK z32|r>IkX9JXcK&%)mLZ}oNIAt6MP25p-l{IXm$fbn^1XZ6FIaAacC1cvPN1o8Y@I4sBv!L#xf9 zO{hGyi5%L5IJAiz+Jrc?i5%L5IJAiz+Jrc?i5%L5IJAiz+Jrc?i5%L5IJAiz+Jrc? zi5%L5IJAiz+Jrc?i5%L5IJAiz+Jrc?i5%L5IJAiz+Jrc?i5%L5IJAiz+Jrc?34XuC zp-pgY7l$^%HD4Us1iypg&?a(d6XMV&a%dCc&?a(d6XMV&a%dCc&?a(d6XMV&a%dCc z&?a(d6XMV&a%dCc&?a(d6XMV&a%dCc&?a(d6XMV&a%dCc&?a(d6XMV&a%dCc&?a(d z6XMV&a%dCc&?a(d6XMV&Sht8no8UKH9NGlG_2SSbSpSGao5-O}h(nvmp-ohECcmCT zn-GUKkwcphhc=Nzn-GUKkwcphhc=Nzn-GUKkwcphhc=Nzn-GUKkwcphhc=Nzn-GUK zkwcphhc=Nzn-GUKkwcphhc=Nzn-GUKkwcphhc=Nzn-GUK!Fp93+5~GkacC2)@x-A` zup-tq_Cd8plp-tq_Cd8plp-tq_Cd8plp-tq_ zCd8plaGxR$ZGtttIJ61Y_TtbcxZe?nHjzV{5QjFALz@tXHjzV{5QjFALz@tXHjzV{ z5QjFALz@tXHjzV{5QjFALz@tXHjzV{5QjFALz@tXHjzV{5QjFALz@tXHjzV{5QjFA zLz@tXHjzV{5QjFALz@tXHjzV{5QjFw{i!GUs*p-pg4Ck}0b`&@Bo6FIaAacC1c zvp-tq_Cd8pl@LWP1+64FP z;?O3zmluaN!SfAqXcIZK32|r>IkX9JXcIZK32|r>IkX9JXcIZK32|r>IkX9JXcIZK z32|r>IkX9JXcIZK32|r>IkX9JXcIZK32|r>IkX9JXcIZK32|r>IkX9JXcIZK32|r> zIkX9JXcIZK32|r>JdYBGHo>zRacC1f!x4uzksI&a=Fldp@()(ap-qTGo5-O}h(nvm zp-qTGo5-O}h(nvmp-qTGo5-O}h(nvmp-qTGo5-O}i2HV1BZoF24s9ZbHX#meB8N61 z4s9ZbHX#meB8N614s9ZbHX#meB8N614s9ZbHX#meA~)WV<{4dge(OV<;Mtuxw29n! z*SZXCLdS+SQHC}l4sD_gZ9*K{L>bzIIJAi}v+P7w=Ps9w81rq6|Gk9C}0-3 zBg)Vt#Gyx&p+|^Ak0?Wr5QiQ?{(3RqkVgLZlKknM_d3tJxX$w~uJgQ$>pbt`I?ubf z&hxHyBl+CN{keZ1+N|@umvEiuJ;T(e514l71FrMDi|ah^;yTZ}xX$w~CeJ&4aO`38 zx4Vr#;3zNX117gTeZbL>KdzH-UKb4s8DpZ2t~y{|;>b4s8DpZ2t~y{|;>b4s8DpZ2t~y{|;>b4s8DpZ2t~y z{|=1qiGK%16U4s*qZKyhO8y zjZFR>*!~^Z{vFu<9oYUII5aZ(cVPQ>VEcDq`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcDq z`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcDq`*&db zcVPQ>VEcDq`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcDq`*&dbcVPQ> zVEcDq`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcDer}po_p^?eI1KYm?+rOhawSNb;e+RaI z2ey9)wtok zVEcDq`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcDq z`*+~b$mHLF?cagz-+}Glf$iUc?cagz-+}GlfkPvce+RaI2ey9)wtokE!m`*&dbcVPQ>VEcDqKF{c(u>Cu*{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu* z{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4Mz zJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4MzJ22OL z-W7rE-+}Glf$iUc?cagz-+}Glf$iUc?cagz-+}Glf$iUc?cagz-+}Glf$iUc?cagz z-+}Glf$iUc?cagz-+}Glf$iT>o!Y+x+rICu*{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4Mz zJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4MzJFxvb zu>Cu*{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu*{X42(`*&dbcVPQ> zVEcDq`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcDq z`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcDq`*&1c`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcFA z(8%Q9f$iUc?cagz-+}Glf$iUc?cagz-+}Glf$iUc?cagz-+}Glf$iUc?cagz-+}Gl zf$iUc?cagz-+}Glf$iUc?cagz-+}Glf$iUc?cagz-+}Glf$iUc?cagz-+}Glf$iUc z?caezr;vXKwtokCu*{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4MzJFxvb zu>Cu*{X4MzJFxvbu>CtQ+7tdA7%c|>4va>Fe+Nd#!M_9BzXRL91KYm?+rICu*{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu5XcO}9!1nLJ_V2*<@4)u& z!1nLJaSfM$2j(3B{5vr32H@X;d0ztm4s8DpZ2t~y{|;>b4s8DpZ2t~y{|;>b4s8Dp zZ2t~y{|;>b4s8DpZ2t~y{|;>b4s8Dp%=<0)cVOQAz`q0YP6+-TnD=Dx@4)u&!1nLJ z_V2*<@4)u&!1nLJ_V2*<@4)u&!1nLJ_V2*<@4)u&!1nLJ_V2*<@4)u&z`WOle+TBB zAN)Ho?*if9fq6d){|;>b4s8DpZ2ykx)czgV{vFu<9oYUI)v5hEu>Cu*{X4MzJFxvb zu>Cu*{X4MzJFxvbu>CtQ@3Z0GfqB;p{|?MMVEA`n-iyP(1KYnNuKhc({X4MzJFxvb zu>Cu*{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4MzJFxvbFz+$q-+_6@5C0C#yMOq1 zVBUwszXRL91KYm?+rICu*{X4MzJFxvbu>Cu*{X4Mz zJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4MzJ23Apb4s8DpZ2t~y{|;>b4s8DpZ2t~y{|;>b4s8DpZ2t~y{|;>b4s8Dp9M9t9 z-+|*fmHay}?|9?if#aE;{5!DyJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu* z{X4MzJFxvbu>Cu*{X4MzJ8(RMm46539e(^fFz@!`-+|*Cu* z{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu*{X4MzJFxvbu>Cu*{X1|xdzXI)#=FsYUM>F) z<@j9i@4)u&!1nLJ_V2*<@4)u&!1nLJ_V2*<@4)u&!1nLJ_V2*<@4)u&!1nLJ_V2*< z@4)u&!1nLJp-srYW5&M&Ge7uuVEcDq`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcDq`*&db zcVPQ>#I=71wtokb4s8DpZ2t~y{|;>b4s8DpZ2t~y z{|;>b4s8DpZ2t~y{|;>b4s8DpZ2t~y{|;>b4s8DpZ2t~y{|;>b4s8DpZ2t~y{|;>b z4s8DpZ2t~y{|;>b4s8DpZ2t~y{|;>b4s8DpZ2t~y{|;>b4s8DpZ2t~y{|;>b4s8Dp zZ2t~y{|;>b4s8DpZ2t~y{|;>b4s8DpZ2t~y{|;>b4s8DpZ2t~y{|;>b4s8DpZ2t~y z{|;>b4s8DpZ2t~y{|;>b4s8DpZ2t~y{|;>b4s8DpZ2t~y{|;>b4s8F9>ev1q*!~^Z z{vFu<9oYUI*!~^Z{vFu<9oYUI*!~^Z{vFu<9oYUI*!~^Z{vFu<9oYUI*!~^Z{vFu< z9oYUI*!~^Z{vFu<9oYUI*!~^Z{vFu<9hm1@_;*xZ`*&dbcVPQ>VEcDq`*&dbcVPQ> zVEcDq`*&dbcVPQ>VEcDq`*&dbcVPQ>VEcDq`*&cTL*n0o?cagz-+_6aiGK&Se+RaI z2ey9)wtok|rk!X%QJ?nXe=&W=zlrHHjuF#mv?Zp` z=tEq`)Y{omi{e_x)D>aX$KJEPWc_#HK=UHy^*coYGrskeh&3K8C*k^=i z*ThIHJhyMgJH0))n){D6kEK5C{PvlDQ}1XVJ0tB~*4($P880z1Co_V+LyW|Nw$+Sx zdi&Hh_vmXLOMQJ#>V55CbTR6~XoAgSXQci8ntK~IratYXn>UZ0k@moB?*G}0cSd?opy5aUKicoKxz}s+*y+7r(R{b0dF+g|Pi%9K z+-AHp(z`Uo$oHN1h??15C8TZBdknG zk=SR1_m+u~SnB(csqs!P|3cj3s1El>&10!gJHLJ3oBEX3_fu1kossfZ#J#ZM;$6pP zyff0f{lv(5B*tdE)5}p3&rCEYJa1_pJ3UVX^=ZF;J~Q>$87a3*JX=#-JWFiGJ0tmD zh>`PHKQEmc@AUHc#4}jc;rVUz*y;I(s89R#^WLe)&Pe%>;#s}oLYrvDJ0p3-h>`PH z>n~H|onEf1&~#J>J*au?^t^S{r~O(#ntJSvlp`#(KgEUC*^GBa@=+2a=dspvr^Y+I zd~l%=s}A~d^VsS6PpMD)wH`h7*cmC0Uc5`7xOjJ>8SjkbH6}*RWBq=})Oe?tGcn#d zQ61h_X&yU0k2dvbzka`E>ajCYuE}^eNpbNmRx{oi$&XKroX7fov#Ie;FRy64!=^gC z|JFQqdixkqpZ4qb<)$7xBjsa_cO4ZM?{+rhossseAV$t({r>9Ic&C?pmwiike!}~- z&10!gJHOrQgZh-$@83>6c1Frs9PdsmF5VTNCf>-)OzbnlzAnT_EcN^FQ{$aperopi z;d8>?KFwpPPdmTe52v{oQ1jRsDX(`kr+G8p8ENk$V&wd??^840>E&>5=I`O+U&9UKu(sjdoFw(yFV1&H~BkVmGVei2Rdk;p~doaS@gAw)~jIj4$ zguMqN>^&G^@4*Or4@TH~Fv8x05oQm@#+ofPev1oYBzDILJ4VigKno_?uukF5ICiTmzpjtvi# z+V@_*wC}xqVejP&doN$ud-=lN%NO=uzOeW5g}s+A?7e(p@8t`7FJIVu`NH1I7xrGh zu=nzX*~_=_Olg{UiILbHBkUMq#|S${*fGM65q6BQV}u=-tQXre%G+~yN12rHSGPaVefaX`t^R-u=l%$z27y=e%Fm> z)YHUEjKuC3VaEtNM%XdJjuCc@uw#TBBkUMq#|S${*fGM6QT6{1_w;T&XPzcr_I_j@ zytg^b-sTN0L-pw^p2?@iUXiKs3}5xB6S}}O$A$+=?R!sn+V`IDu=j+Ay(c{EJ>g;R z2@iWuc-VWw!`>4f_MY&t_k@SNCp_#u;bHFy4|`8|*n7gm>V66!j2Jk zjId*b9V6@*VaEtNM%XdJjuCc@uw#TBBkUMq#|S${*fGMP(@hgE`(!c?-v1wF|Nn+I zs`@^*v9D%oXo9LwozNMlIW{~{YTtPiXy17gVCPMMoi_oFy@^uf7T2+{H&Ke*;$r7b zppNq=R2cM%hom+%* z=N5sTTLgA)5!ks!VCNQrom&KUZV}kIMPPD^G~UUXCSGDBcE<=iM%XdJjuCc@uw#TB zBkUMq#|S${*fGM65q6BQV}u=0X}rs%`aZU?Uu$Z- zv!wdeiT9wUIW{~{YTx;HXy5sFVCUa~oqq>*{vFu)cVOq=ft`N`cK#jM`FCLF-+`Tf z2X_7)*!g#0=ih;ye+MT2PU9WFY2qbDVt0(NV}u=iBWt`{uKGTf`mpQ6t`En1+S42x9w@!D?L2O@?>ug>^SHsz z;|4pA8|*x8u=BXV&f^9=A?-WYA?#d-Iu{T8n65i`Rn>Q{L&}}& z5O%IZ*trg2=Q@O)>kxLXL)f_v#dWSj*trg2=Q@O)>kuZ_VZ)cC7#%M$!j2JkjId*b z|GVdNZ1|FV%!Bh|7r1Et*gKw;+tg`E!+c0N$p`9NXk1BIOr6m~vP*!e(V=L3bE4-|GjP?&t6@!ct4 zz6;HGiILbHBkUMq#|S${*fGM65q6BQV}u=$k4*Q=?=k~5b!oii79&Rp0zb7AMqg`G1O zcFtVbIdfs>%!QpZ7k18E*g11y=gftjGZ%KwT-Z5tVdu<+$(b9!#fpXBR_4d?&PaKI ziIKSK^~2P7!?%@~2i6!3PdaN7m9w5{9!q`NaebJz3iaW7{WJC0@IZ;3SDL<@R~mL+ zY1nzCVds^GomU!mUTN5QrD5llhMiX$c3x@Nd8J|Jm4=;H8g^c3*mapR05=VZMbli7aik*9%zMOj< zcJ6i9xz}OmUWc7~9d_<@*tyqX=U#`MdmWDaCh3duJv9dBUZ>o-*J0;ghn;&JCii+g zE6}mr`!hd|ml$Ek2s=jDF~W`!c8suNgdHR77-7cuHwi6lqOtXapV9>-+x$f1%(KL1yu?WCjuCc@uw#TBBkUMq#|S${*fGM65q6BQV}u=r%`1*PS?T%xD~>!_smrq!N1m)S z|K(LXktZu1H~vPo6M3@I{%vj+N1m*7efwL)ktZu1vQrgTU@e(7kJ4VabJT28Gva>=D3 z11pYPa_NMFt79XVTzYh$>O4j+xwLc7$J9>bl8bzkkBcLhTpDy!HJ->Nm)d2LV}u=8<>{QGtNM{|G2Qxe)qdn#OtZf8qK=Jxi)pFnUlK>Y#ni9OE8@tv zm@e9~I`5HhG2OO&HO|PlnA*%+%}L~2Op8t$s``;{k#`BiygSj1ml%oNF~W`!c8sc1 z#|S${*fGM6QFZDVVaEtNM%XdJjuCc@uw#TBBkUMq#|YQ&hfIw(-XRh5&Pij>Vct1W zIq$15KR%ZFuO@Y`)al@=&B#fbUhh)%6*)=M z#lKV>IZ4y3D}A7LA}49u^zh;0$Vr;!*nWgKa+0QbHu_K;IZ0E`<3ABcPEy`Y67w!r zGhSjOcE<=iM%XdJjuCc@uw#TBBkUMq#|S${*fGM65q6BQV}u=5h>%+VYM}4?{UvBEL;eirI-rltQ;LpX8w>Ld`#Ao8j z+nfG%P4$_KyuGRQO@ltDIP&(U7Y?r4 ziM+k(vo=-xk+(Muf2!ih+nY{)uNp(-?M*)|JVtFs-rh8NV#SfSH$69gtjZ&AZ(4oV z>a!7fdwJJU<-FV3jF%XR-7&(B5q6BQV}u=M&*&)I(-!P&x|2*Tc@o~t3G3q+d7@_^_MD-+}5eb z{S`-U>$Jkt6-RFC;*T#^^&_`+vHN;eJCWPEIAwUnk=wc$F{0`#a$6VIw6De!xvh&% zV=Io_*2Uye)psXyTNjrdI7R(NZfo8TS6sX+&iqV`H)4bxBkUMq#|S${*fGM65q6BQ zV}u=N*zr-;0s6 zR~-4@i)(iIL3JYkd-2Mo>O4mN_u}S{Dvtc`#gThebt3=>5Ed38H*#frn{)vf)a6^GAjz=vy9 z96qlB?XImjd|s_f?p3uJKCjjd_pka2pI7T`YgS_jpI7VqOI2eFpI7T{&sU$5@Oia1 z;u1SvVuT$d>=V}JB+Qa zE#ZMG2fSZ#c%aIDOI3Bk164l$Y{lV$D(`-vYBM}g$)@4Da@ zeQv`8RW`1%)5J@R#O@ej#|S${*fGM65q6BQV}u=6M}B#YM+)+k{d(g@;$M5uUT!vMJ@Lqs&Mr^tv6A@q>z*w)yM7_@QcwL< z@;}E?#=pVT5g4AL2SLmlx58>oZm{eKy*s5BHlI<4KKirpEZwzc)ChOC1;GWgQpw#q`No zDW}iIyrsr`YVN9bVm$vf|C&3s8FSV=U+_O?URk;Gm|vLwITogW<`LFh#XQ3F&;PK` z9ZX%0QF(ptVA?)w?4SF>K6fr>PF$b4f@z02RC#^wVEQC}SmTL#f$5WT2m9Q?hs}RR z-$uF4U0q-E2-7F$4yMmWzxp@I>9a9Tojb~D`}wWb?NYVVLw&ovF%KH6+aU&+KAAh1 zK8YFDc>Zhtb?zwV^U^$DyKcKg-esksI(NOsEGGWx?DtxpdcC7~p|$^7EMLqn-gVm> zil=A#rlkHQEiV=Ezc|W@_&0IXO>vAk+DOq>EA^x8^!?96mw}^C%3EAcA29Xl1EwAN zfN7uqVaoV7n7SMT(*}LOv`rr{-#cO?_TMt`QqCBO7iR3l3lkIZ!oFci|cm8b^Dn*b-&_z zJmPws;(GkzTQ_;EbM)tO#^L&mPaN$qZgI4qqdzf!@^|{>->FxRGe>`7+Kc|g^fTwM z&V8v?;Oj&QxE1ij)!TFc47MA+%?L} zMtyPJj<{|=Q>X4%T#rXwk5gQaU%YesRk}ofE@vFB&-ldA4&xR_`#Jg(^Cy3&U;dqX z^*D3%C#JpVPfS0YJL=TsMWepBZbw|VpQuy!E3U^QrXSBg{Vhjh`{SvO*5!daD>wd-cc*ONM#r62b-5z=2*67dWt-t5b9dX^hxb9b6k4H>D%p=Fr5Ay{# z&)5B%?bWB_fRXwxH+j>AuWwmkyWuMD+JDjFwm-fp?l@r2qVEk)izgp>aWQncd&T_8 z-}zqi@6>}ij^kn4qg|LjIggF<)<*pjuG1#r-|O+jxc3xuT=XZVz35NlrytH^9T(+_x2|6_+7Z|7i|c;H z^?1be!#r{<{rJ4BwbsL(>uY9FUvv0w7WK7ATwkNa^|eb}U(>|(wT{n*uC*Kw^IfN1 zxN*&NdD*BhuG+y>l*G%HlwTyP^YmwXWHIw#z%`6(%%%XA4 zBrabw8NaWY#N}(I%N1{3U);E6y8TqgMZe<4HPho%c|Cq{^L#z^(lY#}^E+77zxCpJ z4Ir-92I6|nAgeT&;>+y)| zaf<8liyLbd;__OhsMi2)$7>bZ_gbZBtW}D}T7|g0Rv|90Rfx-L6_+dCy1uxvR&o2O zj*EW9jkSu$sq%XK;^z69^|ULvo~Zr$IwP*HKjQkjB(ASl;`%x!Zd@mIedTz@*0@f_ zb#!Fmb61yhopJpVZd@mIJ+7};x*pfpFzl5}^>t6zW3FGc)3{Dj?&~D=eVwEo zUngnb*Gc;Ib&~P;I>|VFog^+@zvzqWWZX}4opd?ZN!R!M(2lrqopiq{Z(JumPL(&V zlST7<#c%qu^;)H9a{arn?|Z!-5ZCJjalL*J*Xs&#W8I?l4##tS;P;kx;l{ef<^1lu zehD|$Em|Md>j$lm>UD+INA-F`>!W%dqJCI6(9X{759v~`TPXLsh5BB%(2mzFwC{Bb z{d(QPc)V_5oL;vueyu0!xV&z0x#DfCTilN3q_J*szbbF6TRcvcH`XmhbKTN7UyMuh z7~^5Qnn$>CzKD;Pe^JUD{f9vnsH0SI0d-Kd^yRptJ8|%#f*7xSkHD|rX)>`!UdjvgK`TZW@ z_j?52YiQkA--G~Cu6ug! zjVW*3gS(vXk?V^a_uysY`}O}=FZliWB8SXc2@M-D26-?hB>oc$*jD<9lZ%%A+7WBGUL!5qi&FzwMUOh3F+&?qk(^~H5N zRe9CExb8Ps?PxsWdYs~V{Ng$;mopC6XMExqFXI+R`(?x<=1=}kU;I1u>T%}iPfUB! zpE%;m@%-mD>eS^$qrSLqrz)@77uWqJ>eu5D(~sw$ewat(hdkLRIorz)@77uWqJ>eCPL!}R0%ryrk}=J|T;yY78^ zKmCK+`SszuTb`WtTk#@`uUPEz^{3+APajiU_tsGH!;?bC-#Cl;lfTm!|4u!a<2W9s zJ=%ro$LFptZ*9~s;kq4h-M+Z)S6q)rT#r*+k6%oT(Vxp(qd(VYeBx+_{>0IK8U2a* zlfT#FiE$rOmB(?>pP2TdKaHP$8gWsscd{!`J#UF ze8st5rpJQ6==C@NGy1cbfzl7^{#C7}Px?gcU9&tTRaXo%9*O}oY!a zv_pU5Xupj9#Qe$M>+!_6PZo1r^e3jh=uhLPA74M~a>ZNMFB-NQUzv6m4V)|ho zIhKByFZh5<4)Ha!sINJEXN&q;B#v`h)Zb;j&sJYEb?xL@Mt%OBdNAMh`dXoDFzr%a zT{CrUae3LOFRt6E%Kz({>3(z7&eUtB$Eosq{NfjnUEkMC;_@|<`o3nycyx_Y{l+zu zxO~kdE?+Z=%hycC?`tM;`I_l+#oM@Mx}B>0zpk0YrQe=9uF~_|xMq6%i8{^m^|x-1 z+)}Sqiu$*n-^8L`1Bh9Ju!f+#UNeXrYZd)F^{CTWs}%gk(k|tVwTjEjMtw2;)N2E+ ziRv|j`^{B5Q`agUr^@T`i#H!Nxif1B>es*Z;(84ruGa?Qdd(nitW}81YZc=1T7~g@ ztwLO0tGL|rKz(sztwLO^g;ZYmo9eh&8;Kih6^~!#&GQA<*Gyf{>hGhjbM^OB*T4EY zsp}%wFZ$w7u3vEDI;rbxeVr_5uf9%3JHP0?1?t!3TxVRrY_ub;+ZWRh*B9zEu9F_8 z${W|oqK?buzD`o#*Gby(b&@!Iom4;ky&g|lUnd!-uak`5*Gb~i?;Z8)a;}rEUo_eg z6Nl%m?pNiF>!io2^2T-2ajE)(BS$LsZgnBQC06MTQ`^@F&vZqdKj zzsp+h)W6q7y*}Z0JmUI6=Mk>U`Q3N@5^k(pv_7iW5AIiW>hXx{af<8li@DC!>lW5c zUbnEG^13C)Gj-iU`(C%uuhtXwcuMNk8DEPF=2e8|xP0qMbtR{MWk0 z{i?hkkGLMExUp_2n(LOv`O^Bx>m2&2&lhoM9;094qd(d#>vb-ddM7&YjolD(7C|_j?50`}}^75NosF?-Bm*?-72#FNpii{~`AU z&F9aJd+@Sx56*LJeeUCaq~zX_dvCaL53YO1`W{@*x$Aq+vT+X{?fkA6)br+haOP9< zNO}ECKy%x;2S>-zJW?lqr=~uutnXX7r{n%I?n8cmKFRaT`o25vU#8x7myP@G`1k++ zo=^VgmAU&KGWz54$n$#@8&A2hWrG7oiNCve@nX;d!^DS-{ztL#dV|G-m%6O@YNrRp z@n;c#7stOBQBNGl6>+>c+N0f8+K+yCp4y&FG*0V8%s%Fym$1FmccyOnmeQ6F2?A%m@9!%oF{=%pbm$M!Djx>z9<* z?TG94#dW{pdOYHKoMPsW{%EIpzW#X5mBbj|xgITb?BaS(#PwW>>p2wHb1U|_qn-L( zsJuQ$t&}sD#0b~rEsgpGT(={x+ZWgUitF)+>v4*G?r7&9#oznTpW3X?9bC_e+tInB zyq-gq``qc+`rN@jcd*YL%>410Y?LcrpF7HZ?qHug*yj%Rxr2S~V4pjz-umS3#f`_#CO+)h^NXvyPbsPM&4_-*0mt%we2*=mfdGcTc38k_~T8+6i2>xn|Mgqmy4PEy(Hdp|J#dq-ups)$*U(6qq@$NIChVx zmMU(0dk*nY`<&jg%jNCGo8I~3fB{?0EAD;t&#hNaoJ;)VJ-e2(JUFxX%=NA=*WBSd zwYlPuC(5=5yeks zPxE_6Et+fAb=Ca8E9csa|ABVm*~_gk^`}=JZHBL)tJ@dX?f>t}Jx=Nrjr#wW@{exo z#28fm<~E}{!_=Q%xnuwBJnVGh=IN*&e=g^kciz^Wci1G2`f;0bBIhe zls6xC-+FycT`66E&tB!J`OJ0Sd1;lj<$ZgXJ=<^B|N6VSrfo;>RrXwP{Q(bcQlt~l z-J=}z@l6BPn)93D^JA7Sx4(AL+XuOP7BfzC@n#_n(Vn zCUq`{-PS4pb(x7px9*+GJNhh^&z$%BVp!*8%kfJsmbY4U{?u~aBIPMtES^8zv}@X8 zjZ|*e;gs^Cmds_-*KJ)lDT6bD<_LdWmSTKLO+8@dRx6aZs*Ru=eqdr-!JoD6y)#!PUv>QnG5GFH%{f%*L>D(yHShe$scW4_MiLhZr2~SSUzLu#^uNFKhtfi4lCw0 zmfA`4^V*_+%%iv2Rr53F7pvrpyTzQu{4BWZTKSWikJS8p*LA&o?Xst9eg=HAVSZq? zt2F0pck7mScx-@py?GYN-=EY^ZBCf0Q+}k!qiS=Hb(YLuFa3DATeP{+k6m(`YX+#z zZ?FGjp6}6CwK=%|T)B63?qFeDY3`?5dImKWINd(G!1X|6m^w>Fv2+vwNk$#?BOYv%KI#D(+ar;hEI z`3$doM7zA}N=u8!tn;7py1&nx`3&#a>-F;T59Z5!hPS`s?Xvu}V`e`4e>ti=dgQ`t z^PcO+m**|mNo|h1G?(i?*)DUgyZ_X`?AE?*Wm4l`xubC0w8m4E!AO=doy z9Djd#+(&IP^VxaZd&(s?pD8n+AI^1W`QUtQGxIt2PZyQfyfR1TvwFyGSC$v=F2SzHn*9e&Yw1l|%38tk~a}`-<|x zG0SH@pBFEDWx33At0?v-UcI8+_0X=0{ijKnlS8g_9HMRN9rVE!J3|mw4xymEUl{Y`Mp4x1AbM5klU%RW#4cBa2PIzQV&FAqi z{M35kp^Ixi*WKd#)~i?Sr1|{Ur=Pc;IR9dr&+$XwZ=L%ui{@8iK3~}GKdpcJW)aQj z_QRfNee2gnG@mzIHe2i3H!P<4Tw&BMt*5NNnC7tWq$^rae`Hbd4#zw(V6(M4<=bzW zrRD4!dkr{y*2QzzQ)X%zar>qN-dTHzeAMF;x@|PL-GD1@TQc{$>a%XM_kFPcqgyYX zZ=CDxZr#hv`(HHEvYO8ePQRu9aoen}*dKZ4xc&!UwU%Q4^^lDp|MM&BXg)U|Fk833 zY|>q^pa1xc-L~I)W5xc;vKzN7^!B!z!ym4i)YAFAt;OH=TDX{f^=dw6UvAN2z2mC+ zT!vpU+-~0D*?Biqn@9GTtLWXWn$L&loU1tI=}wx@U*4U& zSa_wyG@l=D-l2Hwszo%P6K7kn_`3VTn$NT6?o?dA;zF9wH3ltHoO;57n$Px^^(KA-QcvPJR2k@IT~x43xi;(<9A5a0R4enrQw9r8o*`P}ZJLyB#7>5xy1&*#L0 zk1qZ-szd%hKA+oP@vq{BXXnf3$LDj0r%ox(Xwxx25TDP^cb`^FJbr=vWqdyGU;Lut z{Y#h8e17wni;E+V>7x1EV%N*#K5+%j=l;WPC{CGcWyOBwmvW)aK*8 zhZk#&Sz2xWX@^0@-g~#z=d;JUPZZCr&?es+-}gtK7+5Sn+t1|z@qM2-`xC|f$NX3h zi|_mGi#=IvIqQUS*3_=$l}Uq&9&dbG_K5HMBL8}(ICSl=b^ToOnD>e$Vy(&d{U5Ww zS*&;0Xk9Z;?)h>tp!XNzB_A14d~?A&<*hNF|M+rL(d&?5<)Ja3<4^shIIYdFa%9YB z>l|McZ^u$cFOa_a>1X|Rw2oLNZN2kMn!`C}TP3~s!$c0J=Y4Q^HtIZ+p7EfKqJft>T_FpnRblhY5J?i=1vgx*O2C2<;?pQwc{^(`3dEThG zQ?Fld(r@L5ZRbjdzHq&Mk3L;`&h+As*OYByK7TrQjx_q}E6d$uKG)n~j&$m*m+ALt z$k}tGFL&;(-=q6G&zTna>H^K@?uT?pi}w7x=JW8A+NV2?J5qCa(LQshOYS&beC9Lr zrMFMoxjZuF^TDq!s?L zRe4j)=W~xQnx4F8Yt85Xm-SC`O?CGnTc@LbomKPs({Zb%_x3rjm2-5$qid#i|LWDs z@6mj(ubuAv>s77%9(8G#(q79w(8_PzBad#BE*Sh$E5C7jbzdf(cj`&4{2o0va>?}N zACG9=GCrS6pSnc)*M57qe!BYjZbxsjcv|_=ZCW>o`P^;SPU*q7y0#9C>*ozGE|z}0 zVv*MQ3b8O3_ zF`q}pn0Gqnq!xbP>)2Zwv9~m0Z{hc-j=iN3dkeAGb6D{EUeB$#K1T&@)@#(Fu|_SJ z&w7noG}fpEZT=GHy5n727p#|tZ?bTDcK@vk=JVD*3#Mn!+q(EH=JST1I;K8bZC7j< z^Ev#?`P2SK?NB@s^ZD}T^QH5q{H^ZCFobEJK?xx6?x=5v{c=SUw8y{ecu)}KTFIcI8F z;JV_Ln9qIBm@D1+`3=Run9ou1o!ar2n+mN-s_&*^ufLm$z5Z?%%xC@GRP6P4Q?b|I zam``<-A~MIeGO5Y^)*Co*4GftXMGJ(oAotBZC;+fD$YLVJ0VwvsC|fBtA>^ zZ%5<~*sg#5+mZMz)xRBy&r7t>Z+WI_lJBMnr#(pQx)@R%0*;SWOB|<;4_4!Pr9O~VW zQdFOu+t9UhZbR43xee7P=QechoZHZ~bB;uH$hi|S=U`MO=U`MO=U`Ny&!^;IROZB# z9E{4W(mr-&Wco*_KIfd@v9eCwLsXwJ8Hy(TQnD1)=fOE0lZvk^LG@Yg@{FVli;7cy zR;jZ;$y_W(^;u&^R)5CyVxj2o!%n~M_p4Qm>agAQIDg2pqQtTLSNR?96bZ$=Uom{I zzcNSB&|S7Z`+f40zkEW`&}p_lyFK-*->zG+(2BOd4_^0|KYUv8(51FM_1-&vvw|f< zH`w|dUO9s)`gN&L^mop^>DoE>rfcWio9dHuZ@PBQz3JLHho?H^+@6@%2vjDo5vWXF zBT#+v8iC5>H3F5n|I}F1=)?R}pO0@CW3H99-^#P?^S4`LOus?7sXoIpePEid%SH8h zZsUh$_ft7TF&|}XFu@Gkot^5las61=Y<+Hu4w$*CGg5u>+K{fD*M@ZMyf&ozpK0yj1mqc{%4Uh50>Z^{?jf z5!)5!_dW$K*zZ$pR;bT7ebM~dX@kmZ`}+#JW^dbk9nD8o?VA0WN zo7y%0!Y1<++Goc1GX_eGo}&_NeZKZfrofY{XQ`gHJ{u-x3AB!%snXf{oYE#+AiDZY zwZhhCo=36=!k5fc*D-!t&EcC&vsK;0--fVuLD$aO1zkI97c?KSc0qFoYZo+kum(c& z5o;sFtg%p;tg%p;tg%pivc^JXvc^JXwzFDIg#-0fB^%rH21NqD7ptw}Y<>PzvT)$` zYo4lT^Urpb3k6!Ls%oIE&*jq!1{!v&r1seQEYZDSU_kbAs-&&Yb5>vKd$bhQ=O(+B z>eGLZhw&5o(z0HE5<_>oP%IbKt*cA_Pv`%?SLb){^@;^W1E1FNy#|>xd$A|2-q2-% z_wA}XA>}HR43y74-Fth|*^oC5JQVoj$YgKdteqh}{YL_o>&AGi8hshkw`%3Uj{~Mt z-urpjGl6}_rc>T~Xk)cNk@iz5@14~*G%&k!IOV;Mt*#d+y=(yGz3s0z4SeupVGp?( zvk&GnX&u33(mI06q;&+BN$UtMlhzTvY;2wC#P}O*Y_BeSC{VC^tl#(L-67H6mJGbt zXsZA7$G?Qs=~z54toi5u=dEspEJ!RG*c@j3)lD;d?)qzE-tDSrt8%1)2V0A|YqyfE zH>ywX)Hcahqkg{CW>s%&4LWvTt*xrUUr!SM8*4`QyxA_TS2fQ+Pv_clb-kK?^rOPP$QQFDY3KtfG5q@V$fQZzkCIQ{vH6p>zjd6r{I;np1Ia1zKlkaQewX$? zlD*3D#(s%kQer;;U{8O@ODWtf{2RYm?o;Gb_K&aqxALcyQ+518|9Z`2vS)v4reA&Q zVd8x^V*NqIQ_8F`{{#Qrvnl0Vd~cf{aXsZ4yLHTN&W`wl{Esz$(kz(&D{)<~xhXw5 zCAN`Q>Y0w4_mjO?p_k0DI_u~fCtYo1Ug^1k>}`IlZw}YrOuQ_*j#+SiJMk2+jwx|r zH}S&fUo-0VYT`q0w=+L~_6>2JZe2{pP(wVR!FY3dM~Y9rQDaSytO2s;eQ%Vh(a0yB zuw^!(#m4>3uNhOgLEau_{<0K~X))O>J@g&<#MYTQfOU#E|MiZBwwbX>`5yV}ZFE^(n2N1u|ZJRl_`F-LAy*8TDzjY;!JG;*8 ztDV9-tF1O?s&ylK!!^bXJn|m#9JA7N&eNNC;7f9X9{?Jn%`ca$q`^`67FB4Z<@q=0Y zNJjE++2XKiUno2A2ix|Wu4~tmPnDxM#P2rz!HnDYIq`&I7tG;1uMjtxcFIgF z@;dRYkw2TR%{mc3)9$Ew>W|^XNrMiVYz1P7zlpeEIu-6feCW@c=FQ*ZLlE04%jq6Y zNCJ1YKCw@B@WJiuxu)iLmH5bWKbZFqeC}Vf_D0c%%)XmZWPhx}5tHk=(ZuPq9XFF! zbs_eSo-*BYyhe;`nX-F1F|P65wd;vryRpw4|7;KO?fpNQRgn)GoVQfL!^ZpO0pctJ z4x0W~G7%@VI$)YizeWC&GVV8HHeDqCD}0{`ed-u7-xu=d`$f$6k(lo<@mF29nLoF_ zPu%LI<)(MU02=d8pGq>T%k?CCw_gKhu<1^`Ik488Y2B50joD}_<>^L@HaSU;Am+A8 zd?xoIbD`{q#EZHtG1H?zB7Qu_LaQSt5+9rKh57!;IO3%j=bHheqKT_K{DpaTXE^cH zrx%zujVBOu|03poN6h_^nENU5$Y;l!**jMg|NL$jlTR7C#(cMWnWvg1k-hcFfhPU+ zmBa^M4l_r8NU^uK-_|=?B|vr_TZnngA#PdtC6lS%I^x&=sArCC-cOvqVjZ(%=5FGz zYt%7a3-2J_`g>iotnXIhwaprsiH~g}ZeFUfY1wu?F^`kPJbn`MxJu09E%D}Y-}tR^ zpCS&+)zh!i>=0dJ)SOBFt0NDQeao&Xe#@yp66Xt<@9$`Tl=#qu<^GwL$B8SY%n`)3 zQ|1ohb9N4DxjE(7#n)P`TzB{!+2_yyWaYYqlf)G|++Nw~&7X}-@&>+PS2ul^OC z6q+aHTyIp}lyq>!VY2glN6hmeG0%_0JZ};|ym70i-bguDl@G6Y=V$GuYh0f0XD{~5 zKJp2C`-69>_ESk2)sxTdA-?cwPPKmDE@CsJpvu;C zC-M2sp{ic_lyV|(S67o4?j`%XUp}o$yqt1RKYqBP`g2^0f2(U{)T@(I?r-ZEB~*ry zDLiyqW7Xwm%6)lgMt3!SYciGd>*pV+tgTbpNmRXf)pF%FvbRh>Ne$TZ4Y4X8p?bCZ zoUU=~p$V$Ss|(0Jao~7WZ0us`K=RQ^= z-b%4oA2&@+-j?ED!JVe^cdt zN#Rz5uBg>7{zc<$=FZpD6MYsEFTHp}b*tZixbEt+>gt9X#CK{RRvVMrC1Fn7b=|(p zpKl$_HEp^bRSTwHCSLl{G1dL!BILj5@CkK(cO~NWtq!a0`{Gt&UI2f$FRmuIaoxkJ zuxUs0R~dV*jyr33uun=jp?*B{1o824$5o54QpBI^PF7R@dVu)+_9N;<&Es_Jw+V;U zka_coIezlt>mugsCFXiiIM=*w$tvVl0pi#^+f}Jo%PCyr%^f?`fGH)(KDEnkwTSbC zZAbR0_6t({Ki_*u{rG%-^5HcFG2c_-hHq?CYtz*su5EMsDZh0gZgF|DnpLXDe;jfH>f5T8xnInB%EH1Mvqs&=TFHw2mLrsJvi-avd{Z{ocj3am&6%Qk5^qAFCyNs zaH86m_Y2}Xb>h{Kq;16C&;3BHY@L#0Uz^@t9oU*ob{?0A*KQ0|ru+}YKMpRacE7Nb zt})}Bht!C!JIJ1EVmVc8X9|}~s;s_Vu#4=OJJnEIPo%7Icq}D5kFmtOm&u^bxO=gz z{oZ|6s<$vS3q`S|`9Z%fra_y-ZXWTN=vUjWGbNNFj z4q4}8-`ALh*+ciO4EM3`t7n%?p@$l__p$G*@{shQwLfjNeq~`gu8$+=9$en}S=g4W9kK8!j z`2US(+7+IXvbl)KyxZ>AQOacrPo}A@3bk z&fZalI&}8{xaW1_36`I@$Np3M2hx)BxVe+N-@wgzQnOdVjUiYb<>pTAo`kgIQEr@W z{Qt&&3D#_>y}9|DdtJ3!TvLU-+0?d6ymC|RtM*w++kWx!(EV@yMD1#BLh;bYZfvJ^ z6=L^hJeHV5?aJL>!CEmr!}@RcX}EE|^q2ikSEXp`QyT`HR0Dd9r9L$x({WWOdl>bp z(h|WKO%W^7b^g|m}y~|%xITfPUs8IzL zQ#m7Vexus7Tu9{%iZ-g(D_>AurDcDJyU(P4i-$t{OubEYm_H(KXyQkwsSe9*%@~^R z<2_V|?tT*Yylyj3qs%(thg(z|w3 zpXx9+QRzH8sZW)9cDzcA%oK`wbL9C6s&9oXp_n%h?s#A2vbitj%{Jca>Y2y>pmIud zZLY>Ydx6S{eWwFJS-bo0((?S;jnj?)-`Eq_{;}=;^usBA^RDOS&a?PTjZ2vv7jskFZeOLe$-N*i zwe9*1UNhg#e3sf(_Q?%Q#?PuyyXt!U8B=uLBh;?kJ%nl5i|EF=vTr(bD^E7+Q&U$R z^>0>7>6@R9-Rm#?KBaHI{`^jV=ZTcQneciG(`#7{ivRY{Elr0`xhVc?H(Qwvm(x)> z8?wJ#H(O_T)hw>{EA?^Ju%$_^eU|$8&8y8#{Z~#=-%QIMNOvz~;f0ZA{^43w zhXZHl*jlIn2giucUIV3K$T+7YwW|#s&YNRd@=&{q%(~wU?2>`nmAfA`E&E#CI48B4XIc(9O1bE8 z`&{nVx+yvB(^nGAxW;>_Pd&Ol&g{y*oBC95f47Mr^nJ>Dv)=b+RQ3ZDf6K^iX4sO| zR8Gq!8_YL7zM`D=V(oRNQ1yjW&XanL`DO2XD(8)KtIWJlKc~7%%YIsSUv8FqxdX41 z%}aGy=6Hs{k|~*}4o_tK)yymP8?86p{kQIU-FSlS!*P%Or}plqWp9tWN66jl>+bDI z%|2l_hG6@J+&x0>e&Dq17jolt>edljt zQ93r*{w4R=e`+6cTJ}T*+gp{Iy;9!sD`w@a6<&o48_k?`4+OG}+2GYXQ_Z-0WrOXD zcK1=c`(vXXFA(_Z@v&a)UTsEA%N#gSp{F*=9LRTQu($N+0yFvC9TVUG z6Ys#(FHDirxdLOajP}m0?qM!h$`Tl|Dcn=nqRf&vvIe@end|MW+06`IpC^zp0eLaLh+eR2nWIXBzeRv^8}aj;O}*4i(;tzUnh z^uu3;0~0QO>V0witE7Y+$)>^a2(NsHe1Sh-_|sHbFxvZg;4u?AG(+IGHWR#%YhRcK zdmacRWsCNH{G+=WGbV2!|MrRA&|9TUl{zH@vj7s!(S(3c<-|r5(*E)CKn`Xp`4)pxR-KXca zt6*)<-FIDkWs|__!38~NN@>~4?Z#88RKdWeD~Cd$|9sLiM<6+0O?u|?P_ImZgC*L~ zGnWakrw=ro)sddLJP~)tyxpr4J#(pWu23NNv?C$Vizb%x0vV@gqh~{h#*`0K@AX#* zG%hYb3FX5-&$J^+^js;$CkZ}$EImKPHLe+4(8o2p`^-#xe_XCQ}aW6n0^XR!wT>(!B!0;9kC&_I`NRHS6!*|Yr& z`lI_z7|t;a-bMXyzb)g&x%bbE0e^N)1MO?(6SvHms*f6IU(cQX%Pi_!%0RO^Q1pr! z7btF^SvBvKIZ%AZSc?BduB?GQ-9DuF?^L^D;@f;cjT2_mla!#%L<1 zTJjO|arRME4(C)hSt^g#t;{6R6%oBgzGm)6J#&bni=Q z_A0w|<=(rr)LUBW%Ke6qTW@ZC2HR`x9{W#y|0gZ`x7~f`xcg0^wCo9Y<8`kMMCuWbVuTX=07z}UiT zTk0e3_mR@_oh3I;Uf0u@!0UP%6L?)uV*;=1X-r^!gW_j>gW_kMfy!Z>fy!Z>fy!Z> zfy!Zxg6b+Q-*KVP77`1t~r!_OvC>M9N2I^$<0 z0lcfr&sL}o`PmB9AwOH8I&{B{=6++%jVIWVBczU zzwPG65bPZy_q`$aTWx81hscf7jsM^HjvPOerS|5&yX0OMKaZxi&CjE$ZS%8WYFGR$ znA%mYlxM-zuH5g=rRDo|Zk+raocdI`l;_~or}#N|zh15o_DAAsWL=kinz zKbNO+__;jwO@1yyfclO-#y72^ir_4R} zpZZ2$THaH0-*b7djmqKuY*Y^KXQOg>KO2?9d*P_A(((;P_gjv(ez4N3Q#lWq*b-r02D({#Tf znU;4p-8kL&|Bdfk@*ZGnZ|=LI?sf70=altw%Km3++r0OfbR^z;Oxh9eJ*M@t`#ntF zdrVr~fBRicH%{JnO?`^@T~nXpeb>~dc;7YkDc*lh@$>$3il6s^Q#rg3oXX*S;8YIp z1E+G_?~}OSE%|T1=gE884RYEaQue@89r7M{szcrbPj%?tm(;w&>(-Tf@6u9lX{oDV z^`Dw+ck9Y+OQ~slyjP#@^#F*;<6ML1CacPvSEULh5eFOV+&L@Qd*bfg;m&1g znMeNHxg*#dl$!D1oiE(^G&S?DJ72rkKC}G{_1M$5sctLxo}|u3W(uIr-TXW?-xhFl zW;cgVOa7deoH z2Gc)XjnvgnU2QovTC}TOySnHPBi5L<51*udH*EDTlVRim;$Y9Df;|IrpA)&ykKE^L zsd*mfKEHFH4SnZl2|V=MXo~ION;v{;e{D+~?3u5-_aN9eg8r$!0cm+A?(Tg`%{Q9d zeN$_?{A5lP9<6f477M)i*D15V*jV+{{^Ei0-L9Fx27I7O3@b&?7K`l|tDrG*eG>Dt zHsw5{RL(O>WZIDQ(f`1X{syk3skpm{H{GU<+$f{>pwO3%e}wuedj)? zFh_IWBzE`Nrslh9?%r2-FK$})!KP*JYq0&asoBfw?tOLl2B&5(vAg%!tp^^Hscw0! zCcf)kgH(K@&)xs;zK@WWcLCC}|3BC}1*zH3@9zJ1-;YSm`xNf`7j8Z9936`G%yT!f z`@U6bzW3<91LeMxm6rFR(((=z=YF9W|K0bhQu9ue`wo=*j#z5mDRbXJbL)X~PO4kZ zMTy;aPE+%(8}~g>_r27#yc3$1_dtWaTbi2pI^Fj`-S=cu^Iom{9<+T-! z8}57esrhb_`!2luZhl(ci%-kD@WI}%PtCjS?z`};70~ytSzDmFIM}xZ+;0)M^}w0{ z)$QgKt$^75_DE{J!R3Ar#Qi==TD}dEmhXZ1DZd{_xuW}xk<@(O!~GtJ`@NLZd|$== z9*bKKEk@ekUdWw~>bAq|h+m5f1v_AKnMeetZQuFO2 z_ghIEn~&HyWM1Z<}NlRwOeq{>0yLEdCvSU>t|z!6*;qf^i z%Qzc8Y^UqRd88h29;qKLU%{Wx8w%!lh;bgNf1C&P2p{);#n+!WvufVzp-r|uXZD`I z=@oym3h|=_2dS3}RV1#Ocez@-pd|6E+-FtNz#PQ*6Mx6C_;>h$aU6~Zqdb%g#(8k> z9J}xM8!(qc%;gjFc>^isP&~vOCo#uQoT1`}kJ$5x-M4XwKjI^{@#1{MwtQpHM~px5 zcaA3jKaMkC&qs{%?D;5uoCo&~K5VD!#d)M2a2}~2E?>c)&l?Knc!+TxsehaY^#~vL zeziNXYbN?C?6?|t`xA3H2L4<=F`t*1<00lai8+4a;+0F5#aM%KtlhWg6Mx^H zkJy%jxQT7~I3F?o#NTl&{vCc`9B0o*aiTnw3p>tZ`@<|S+daphn9EVHbNR%4USf`i z80SH~z@OtMcJEie$wkUmShj%ruggE5?cohBFrVz(8=UtJJU^4T!m=mSp{O|G2eZ7T z2EQ<)6#&n5lToLElt777?SbV=RN6$1Y+X z)6gF1-+4@+v6jaQg}#n*;p2>%Vn@3bf8&%x%;gjFc>^is{AbLRILXfO6FXxju1m&D z_{*4SoF%P&H;!q$0CP-opT0a&Lz+u=-+uRrW}XoXoWcz<-*6wRm6_A zD*nbPhnUMJ=JN(p%K1;OB5{(P<0o#Ma};tgu}iK3f5}yBJpaj6a9xtCAQzKd1=l6H z3gVPp1@TL+g6oo8MeKCFPOc*5P+d8>ikvr;ugge1JGlz(i{vWy_gepxTdJqCEqH{- zOd8L)KhikI{glQ(j9)09$17rIoTPCS;}?8z9FLO<`#pI@VG?d zF^^YrUW4*+9*jF+XPlJy$-bdMn;rxWy$y*fLY5Zh=VlKyEoaFL}`Mks&53!TCP=18G0ms_w zn#Fkw?2@-2pOU-$nNAV5x=(e)&|1N#9b5oO4uU)d4mw%V}-fZ++7CA&brSlW!)H^$fhriX+ocb(4 z{KTwyliYd^amM*eOs*>9iSLZqVESfhLHzc(?@jt4Ifx%=al~v|5ay%&lGBpS{7X6s{Z6$?w_f zG}&_uj`3SoJw?1>-dBF{EhmUKe!9o6QRo-qg0KDVS1xg!_?=_f%*-E?iSuj}6SI$G#`tG_j?LirGax=2{0671&NZpmZ;@{Iku( z)ou?x6ZtRlXp8 z{DV0L|HBR&{tXOY90NufC<~0TaSkxfiF1Py3t|EzM#Kt6?6?MEdri1DFs>EX3`QNG zF2JZ8)DakUhPnfzE>Wjo)G_KBjJn4?0OOwE-hgqhaL>TFhq#wu+*{mZFzz|-J#o&n zrj5zqa){$Y%*T4LbD6|^E@F;>m}4X6n2GsX6w2XiB<5=;<~kwfx*|rquyvTiDRoQC zbxzFpf|&0SG2c64zNf@|uZg)05Odog<~BpjZHbuM7%{g!Vs4Yf+*XOX4HI+QCgwIz z%zc5F`v@`j9b)cN#N5}2xepR^-z4TfOU!+lnEN;}_kCg>6Nu3+Zs$BJ93pIeLTnq7 zV?EnGh;5mkZ6Cz;T%K(o#5M-cwhv+(n`hexv5ncY?St4}i?Z#5*j}Tu?St4}yRz+r z*w%@%?St6Xm9p)F812Hg4`N%l%Jw~CTj$EQ4`O>Slx-ix_8uwQK8WqTQ?`8&+k2{P z`yjUWTG{qNY}Hu{CM%|!}z^F6S9T;_qIt8PSQP*J9J?;S*_XPI_jC+N92F5+a zy#(Xl+V(+=dyab#JKBP6A1)`6J;jHZkM*50iTPZ_90M`OM$9o2^R*b1!`Dd6*G|lJ zLdnC~?)w*g{q8^qjZh`B8ha~mV(wnxlu zl9<~nF}Go2ZrjA%=83s45OW_P=DtJBeTta-8Zq}lV(y#7+-HfoFB5YgCq}!#+<>~} zF@YHE!nO}#j3MIlpM1m3uQDu+^CCYyOgYJp`21>f`Mty!AAe0fu>V`)fiF)~r*ADv zvCsNU?W-O~Z0dfamiK#~_>=KF)SC4biBI1?sA>+}OnFpt(`3~<-A>A{o_hJHx_0PU z%Deu^cR;Q9{tEHXbz4+&xw;0q*3WB~t0h-Q62CC@WA(6^PMq_4n5vp%Iq`tD^;OT1 zEyPozuX~-%equAXsW+|iQQ|{$j;ON}8v2>`ob!cIS0kP|qAK;SMfOKuI-Ndb ze;!ef^nda$cKyNP4-V$f{WJ;Z6^6g`JJ^L`m)P!&^Ys3MYFp>k6pt|cpB-^fC090N z5A_eK>W7vSXBc=$Jr=q2E_VIF;tvkyFR|Slr;G`(3!@x~4R&GJug>19=B&tRU>Alx zeb>Ee_oVD(pR;zadZSl1;x4h@tDRS}+{LaxSp31k{3W(~HKFE;^;QpRoJ{|?qb&;EdJnN{u0~0amrW4;FuLFn@{d-Z*8P zhh138zh9hHCoWaRnvbD)gyDbi^Q9_>{jMg;32(McO=&)gcutG2Rjs38cd_da7JqOs ze~InhIAsokT^Qv^Y_JQ%zTBU!(zl7Hc!XhJcxARqXc$NKK1=7Qy?tVdpIrNys$Al3 zcKyNP4-V!pvE3V|%#W}Oqa2A1c463UEXtmPViShl#;a@`WVhF$?DY`aYgP96yV&&y zi$6G+zr=QLoHBRAE{t*{HrRz>w{1b$dra{N!*1J)vh9HEwjC+ko``K*Q}+Jd#jZbC z{K3KeCANFxl)M6VVU#1W!7dED?TgCxF^WeRcH3W-?T2Ky{aD$)O>Fzn-`MpBi$6G+ zzr=QLoRagvE{t*{HrRz>w_~BQV;sdM47(jKl^qAkZpTq&$5UcE)+#%G-NmjySp31k z{3W(~i%ounVIci4AsP*ljN0**Tu#5r*C73!cpb$Zqop&*l@vHrMd%{CyX@{$TM3 z2lJQM?u}FOSlES8j>HDLFzhxL^K6bq@d(3i^EJ=rVPv;?oM-bnVw>xEHkZ1KU4O9n zgM;}?Z1=_~IX3LVC`V$0T^RNgU)NpvP}XFMM;P{(cZ9EKKIkafE!PmXJ~bVGV%MLU z{JH%5`b%v0#%b-8|Fiu+YXON3c43r{+}Wv5V%U*8OPwQkmV05Z-FNO6vFi^Oe{eAW zU~$^}LRu)|6h=A0;zaK3v}a=YBX^cIkK9@Mf^B=g(_e^Pf3Wz2gZWEr_r_`a1?jY~ z3!|K1aUyqi#uH-rBX^cD2f4G1MYiuFC#H5K?D~VnA1pqIM;LaA?cO-;xI{WB?85L5 z7AJCNXFMl{KXPXo^N~BtTwupuYuhj@()1VmtRCC#Lv?U4O9ngT)8&2*WP1-5aN!mr3u2T^Rns;zaK33GDoS5PlcKyNP4;CN9BMiI5c5j?EFCtAJc47DjixauClTQ-EAGx#S zoXDLe7qz(`a$<^K*!2gCKUjPak1*^K+r4qxyp*08%cyO^E)2WG2D>oq=!@uAunWVE{wix;^kZ2IgVC4Z zFYNk*#b5Y-{u0~0aoTk;^=;UNQI5oRZ=4tlF|NTb41bK5qB&q36)gf|EygnV3%mYc z@dt~~z5Ws#?85N3x&)1_unWU3vB543JLV$HE3ga0j`>P7AIxK-1!1nkTmpY#*B>nY zVDY)vUt)t@82(llqPY!rVb~=$*o9$7E`T{6c463&FNo%bJVLZM5z&jrLh_TI&=KUn<1 z!TcpQ#3KxUo(rgaVb~=$_zT0%b13->iyb-?{CO@W=6UcgcKyNP4-V!pv7vln`18C> z0iSJ_9A1wahVEz&t z;t__w?F*jGN2z>a*d;dj3&U>52W4|p@)w5Pjv;vFMRq$D;aM25?fc5+#CNgl4;FuL zFn@^+@d(4;jz!Amqg1{y>=GONg<-ejv$FXp`3u8t$8bDzB)gpp@GO$pj=gwZc^A9> zVDSeB^Ox8Vk1+i0TtNFIVHbv7VuM{6cI2csAEkJNVMp#Pb~_j2Supw7xlh@g_%3$+ z!Qu}N<}b0`8>gL%mCZ+~d|{L$vB6&$cAK9ln~##eFzhym!83QV+gu3G;)!kUp=?fk z7rXvo@dpRAm6VuM{6cC-cDW7vgZM|(j#fF11!?Fo#whWqET>kk%x za4>&~4dn>KA8jA)33g%FB{tZFVMkv?AA?;OcJx>DL)g)eWi1Rw{}DUb^#_Z;@csNH zHk2a_f4de|=-aRh!!EJGE(|-yLX2^+3&W1_65}B37)LRlf-%-&{Bqg#2a7*An7_n^ za)jZJu^;0p?82~1Y_JQ%j=2bP4D7=GO7!muM3z#I>|Fzm<|kO#nyJOcRy7`X=KZoq$inY;9&j|8_E%eztu$* zay!_CVVBro7lz%~<`tF&&(m_k&z*K{OB?dp}JBc01S6oCi+LJ4&whA{r5ny`Sa-yPaF{Kg|)T zc~8pKrbI(SIrr1VV7GH0`Cr&PR0DbML}Y;%5w=BDUD(ji#&pIbD>!rl3PZA?{!}y5uQ}doI>y6~kIwUdjEa}(KGlZcPVSGgS zsd-nI^+57xosgLIMq<|Yh><&Ed_?)Fd0!Y>8pde&vyMm1dLS|DZ^Sls=v~CAd1smR zH1cPijhOX1V%EoqZQVnUB2LYF)2w%qKkHz`tfvvPenrgMOA4pF7f&4Q-EDi{pkI*> z7-KZ*iuEpH)|ZHF+lQV*oSOH?SuY}g){%%=k0NIMhuHRA=q;2BrRE)W)^q4s)_I6o zFCu1rhS-ih&_k&F)VxQ}dJFlp4nxd(4l(N|#H>-I`dxn3L+Du6Nr+i*A!dDpn8#;@ zd&KXO6Z2R~%wsIE`)rHHOtSM>O3Y*I-;PbqHz?d^PdsK)IXspU^B7Ca<1=w;zF*-! z8{#pOj^(kGn8#RR9-oO*^X&`w*$t1GbS#gh#5~3l^Y~1hn(t=t*hv07W)kyQO3Y&{ zF^|v0srlxH`|N|qOgfgwQeqxsiFte`PR;i^+-DO!X40`dmJ;(AOU&alacaKx;XXT% zXB=qT_j_gmJCDy)ermoG;%fWy3|?ns1x9+O=rxDCd5fIqW<>d*IZ37sb_H*6b3l@DCoSHotoO{#r2+@aeEa&QE zcViHJ7(Sv8gGC<(a}H0(^4ft|^kMk$T7&Fv45AOiNAzK^=)+)MgV3?O_8}I17(TpK zBD))d=)>?4eHbkIFqqd+bS$skh(#ZU53lve?#3YcFnmNG28%un<~1N4%WF?!(TCx~ zYgMwlF^E14AJK=wyjCTDUc(ae+L>7NVTvK;yJ}>2V-S59KB5nUMIQ$98k~;hwLh`w z!|-9Pfb4Dzy!I!%=)>?AeHhFd0{O6ZK`i<(d|2xsyBmY(!|)M(7%ciQm^BbOmbDjR z(TCx~S`FFV7(^e2kLbf-(TBmT;n1b9|p4q zNXN4FNac$@3?J4i$?nD=`Y?P%9|ns)3}y|Jjum|vcF~8yq7Q@J7(^e2UG!nF=)+*v zVBPXlzQe=%FnsVmB zJ`Co%rSe4|hF$bwup5Ku!?24!3>JMDEc!5*+ou7GJ`5Ip80^L%`Y`OG4}(P?28%un z=C)1ci#`my=)+()2GNIM7kwBk`Y>4ZVKDbiDqr+r*hL>EcHX%YeHeDphr!&JsT}U( z#5}eTi#`m0(TBlq45AOiF8VN7^kJ~*!(bj8seI9gVHbTE?8d-jBl(Ly3?I>l!J-d? zd2Ab9|ns)4Cc9s$`^eYcF~8yZVaLi!!G(TSoC4A=)+*1 zTd91}hhZ0e80^Ntb1V7toJ%bFF#JUy26JveKB5o9F8VOojY0Hb*hL=(i#`k%eHhHS z4V5qYFzliagWVWJABJ7@VX)}KV9|%coSRYkq7TC^`Y_myLG)qRMIQ!>J`5Ip7|gjP zl`r}*?4l2Y-55k4hF$bwu;{~J(TBmD8&mnB55vy6G}+x4L?4Ea=)=tS{f35(jr3vo zh&~KvtwYMkK4fCihv6goFj(|qu;{~JTeqYSgGC<(v(`anx-p183?I>l!J-d?MIQ#+ zwn6$ZSoC2qYaLX+8-wV>@DY6&Ec!55^kJ}V+oTVJMIQ#U)b z9|qgLN%}BY^kFb-9aO#>gXqKX5q%iUS_k>F210Dd7Se~|Bl<8{zU2sZV-S59cF~8y zq7Q>b9|qg8k@R7(=)+*vI{p@e=)>?4eHbkIFj(|qupQe;9|ns)3}&r^%6DTBeHcEX z4}(P?28%unwsRBd!(h>e!K`&q`ECrN55q_FVX)}KV9|%ctUpjW@@-GpMIQ#cG1$44 z^kLY+7^A_W4}(P?2DAP^KB5o9&RR#xdHMUIu!}wn7JV2j`Y>4ZVX)0@NFN4^J`859 zgUWYf5PcXvq7Q>b9|ns)47Rx$>BC^rhrz6MP+sT8Ao?(TL>~r=J`5Ip7%ciQ*yf!0 zPORjj_@E3g;Ec!55^kFcM&kD?ACNYnt#5}$ci#`m0(TBmJ4}(P?2D`_K zJ`6jLrBo)5Z^WVx!$STb=)>?4eHbkIFj(|quzRfN z!?5#MN@eo+MlAX;d_*4xi#`k%eHiQ>EBY|(JeE?KJiZZ&J`5ioGs!OcFzliagWY3A zABLUBQaYB$SYpwK;UoGmSoC4A=)++5SkZ@J=dqN^s;l*;7sjac+y_=r9X7JV4ZW9;9K6@3^! zJeHCVkFlf=h&~J-(TBmJ4}*D(rDO3<8**0Ig`pcaA9Pe9e}$cyzGcBa^1TZjOW%1p-|Hln-z|k*e$NyvzjF$f-#-P*@1la`_fo;~ zJE~y(zG{zr8D}|m&+#Ybaun=bJ~5w{SbpynKJvSwVEMgKu>Bp*^Uo%8q z`)ZU2F8%KN>hh(X#PRPv=DpE+q&nGmif;2*f;T&Ppc>I>iY~nAfR|-{cU86J6y4|g z1FFK1Hmc{dQ}pagkE%6io>Otvrs&$awA%FPGwSGLQ*`+!S|~51sG41Lihln2PAbQ9 z*Swb5r|6M>Z&m!H?=`%hs88P=psm{sQS8m#p zs9%3)q$+c+tpAgrsOx<+NPSv8#(#KWqQ2GYeKoMoF8}h!iTaa0Z>h@_vY17YiMre~ zP1GlC9xf1T~2zk4Fn5kbjQ5RVE>dG+>j565@ChD(WFXZoBG}2_r zoT$G#5aH)6I@rv*oS?(c?DVg6ecv?wB|+zSGmF``^exl(`vl$n^24Uq*d}Jch6KGX z)H8jfs+rj<67<6q0^YZc6ZE*1gN^^r1n)#> zf_~;^4|6nnv-i`J3A)hjcBbI)3@YiN1byQ0i)PSYrPTV|3Hp~y)y?!{HPzd9;`N^G zCCub8%~Xzy@w#{UbSA!K2UR9HUN>0!t^eoEo+{6-cztoeSbti_A?nd}@w#8Z?Ecyl zBh{13;`Qna@2n`4bCk+ACtmljo!KjX-QKgfcs*s<2cD@jL~R-quTNgzRM*Gjb?f0hRG!mYy-~&D^__i#)tKnReoX)Z_Bkf{iKbhc%2G0 z_MVB;`p!s|Azdc_i$ihx?e#-cjrdXiob7SCX=E?;!r?Xk=2da}e36c7T>LG6?czAy zZQx5P=eXkL*o-*6^G=BRWk)qLJ~B>^u31`j`}qY^engyJ_d`bYag}!Fi5_vfUFU6H zWXB%ndfPbNx>2~7+wslV@)d~$W zwI7Ysr>YF~qhB3r&K8K%=WeX_ubEzET&6hvaQfT+BR4vjv6o}@Q>}}esZ(Dv&z*?X zKM$*FPBm1f{DD~gOH^Ys>(Mf%-IiGWuJ^WZbbJKff)UG}L^!c%R)7(Mk zr&H1X3sYnD_NbAj!K@PgsqwM8d6rS;iBG1lOdb@g_tXkARd$~YN$eV{yRRK;V!HS9 zy0(ecFX!!JJ}RB$ebF>lXD#!#IacORZ)5FPJtEV~X3c{|)Q!rqx@S6VUS9l+TKG_` z-ZG_(dALer)hKtYz8aR*h#6Q`dq;{|NY8?)PiG^b>54Q z`$rp%RDbTBtT(kUlr-_rFjZp1WZmudh7hk`n0o!|$-3zq-MpTyhp7kWOx9g~UExh_ z(nrmWovcI0{OOf`;B6H%X0o1gt*|orUsg5yP1b*ne_E9+P)q&Rd9v<$sgXMMdO20+ z^~rkRXK$!HFXT|Y8&B5XrR%OD=N|G_c$4+Bbu-9a0Y#$S)oQx^|YmBZimtDKL~&yMP==C=LPpKvrrH!bmw z$~)(RziDTTJ~#3ebz@=yQ(#Su9{5LXReyA4vukmTuKQa#^+%sZ=A9WadQO=fs^FS8 z%yW@3`lqiCc|&h?GlxdR=qx{f2j zS}%wgZbn4D;$<8ftsg($&pbPIp4ajHXuUAgyXLQAr@ZxTqxH~VTbakw^YbLM*4YW7!WmPP6FFP!q8yV^x9pB<$?&6ii@JJw2-jf>J72UJv_#MD<&A4KW0 zlk2HLQ=U+l21eXysY`YBRRSlmE8khOv-xGPfE8B$68zNN1DVs)fm z(KMfGm7|sEu{ctL(!4?O7AzkVYP;vVWT5;^ovVE zqGQ8M?tYQ_Nbg!nUCxA=DQ`#W^+Rg8 z+p0$DwUct0n5wN!=|>~=w%5y>^7R{@qM*T@7a~jx@?j9#`Kn^$gYB>{q+bP z(zLVrF>uMhd^SQatKHXR`0guz-=PRS=E^XW?TdDP_pK2++{W_lOG}c<`w_a+=`b^` zO5Kot^CNWi+#^k^TGhNSr$y+DJqDUlnWuVLA|iCpncYpB(+9k-MnvdW&zY$!9#z%bMd%!hpE3)QYpEU0B6R%&1a4a_j?hCx zmibF>_EFbMN9fPr?&j}*eVA&TKSE#nW_Qxc4q+-|<_KM@z~!1(ZT>OuO1Li6^D(cf z&4uDmgzL%W6TE&l7plB3T+3cb+Bdk3D*bi1F7f1}>P?#qJ^NX> z{@mt5ui0EEJTY94wYiX~Sya6|Aza7XTq;BJI{g{oV;UCvm_V>c|i#8V;|7%%4vSPR{Y;&QFHDdf-CByY9 zn+qk>-Q~~99j=?&Txi(iS?B>iO(FkVn+tv2Z<0RuLxi7PWUy)R_9XrF*`59}n+x4)IZ4ObTxhh- zg~~LTq)*sf=*XBRrd;(&`U&lsY&I8qx%?!ZesME1Ew+TITWpf9QN4r7YIC7HIVS1L zHW%9a>pH){jfpzO=0dri3iFqqov1TB8fND1zns+O&_rF_#*(#q=bD4JPSmg3Txjj+ z0$y)3QMa|ZP;!?EUhKk&`p+9Z%$=CcUgV64dgHBjW`@m$-i?~5N7-EHn$3m!jGU-@ z*<2|1@tUe&&xyLZ&4n)8T*z-bQJ;P+ojGB1p*_te>at&b>py*~r&?WSqTbqntiR6Y zLf=0#Q9qDByT8rmLPyF@)CHTRob3-!M;LFc`> z$?Iivp`s@y=tDLadfw(jkMEnHTQ4f58rfVZ*TxC@lFfyN*<7f=$_aYA&4q^9T&Uvw z3HpnUZPn=-nbnGE6LgWyFRR113Q?}Uu~Ue;*1bCMijKup!{*J2ix<4;y?&=N@!t1m zdFg-cPkf_DXZ6a5zkAu=o}zR0>1)5I@uk<(=JvUo4p&LdTYKZ{PthY5hpFYYriJWy zW{OU->j-mtaMIV0Owrw%j8N)ELw|PuDLUJ?{nhMlv;8TVr|86;@2YOce)eblY4iEE zucGXFJYjy>m#BL*sGv#@ZeVV%Pt?Wt=2X!OTANnO5_OJVhrO5L zyP2-D6Lp5IA9d}kH6a6^lF%>6HZ<8=auYaPFG9RFT7ODB(`mCDwIpq=bx`? zE(}yAws4}>8Jd{UiI13e4o7k%e{bS6QM|9Y_LHf(~w z>4yY;VuH^&%*-Z($V9rryXR~)}jI{ZD-|t77zj8n5{V_K|=RH2yvdr_w>XB9r=7a^WM^oDr$($`CGqWhMz303U^D;-}bC(CcUgwjn)Zz#S=wM zqiQWwm**37u2p~fk=Ht@(jf^t`-v6)lP~sBTPh^z*2R1H>XBh;Zt(=2bHeVVoE^i| zUpW(W=Y!cp)?N!!WpBmnIx8!Cw=0cQk>}&}Pvxh3#V!p{^L~uiGnyuQubt_t&Tfs@ zA2xhY%`mU4Eq=UixvGMyov(pf@I}0yy}Yj45miZjGTr9b-@mE`ewLo@%?x`xbp}#e*3dt@i*gjmBV2wGO=w)?-%SEVMdtxz4+%z zLqp^B=-R_o)^>0B(<;U5ih25}-p?=cCp{Fedv$$B_2~Dj-yu)DZuH_Ss>uEVre?Z$ zeLa0`b!GfhrvJq_9mxBrTA1#66LmCB*H+n7Ow^ku{f;<2dF>wW($@D(h|S?={SxCX zA2rA%*c|@RZjX3H`i?Z+KaI0`%Z8e#GK@0WW8!qK`lpkW&ApSt;&jPUBmHp&hniD8 zp-}}eio7pEh>NN*MnXm1jl*|osLQl`RFO-=ebar&JrHB6V}8s^ids$c!a zgWgd`TEyykxfc0bi}h2>>c{GXzqIxrZ8%(gRxMWVDmpi5-6vsceYsdYY;OCIW{bb$b z^GYiI)4J+Yo421U*Fe4WSp^lhVzTc1-Rr7p#Rt`Z&nN3~e|1&I^Cf$)Bu>^9ZVXVZ z&V1y>e`w2mYNRSqt+KbI|787w{f)V2wq*+`Zu9o;cJBLj!k(n(U$wb+@nNc6Tn~S0 zqsjVA-9GBG(kuM|A(M5!vz^qazy9<~+q`}4!!6YCMn%nmqBiFbRcigXswS(=+dFJ8 zt@`wM!8~>~Mn95}QB`Q&&MZC^qw{3m;uZa+hspgzjDGIcIIrQ^!RFH~F*<8>E^pTU zk>*7cqkjp1u0|Q#x7U0TqqiJ*z~6Fmq-i-VMlbnhf5^!jO%7T`Qos*e^sD0h1d#i$~|8cY)^41fk%cgqjjqqrl=;bl9dcCIR*<8K&+@JkzN8VMRbdT06E6?`R zf7f5leKT5L8Q#$E-+Y9c-Yi;QI5sfpt6gDgVx4IHX2Xv{>MaUWy`GBJS-x-WA~o{J<#neB^UAH;;(YI|_!WZvM@rl0BpJ(4#}to7=;TPBX ztzVAPbDDNgzde)A9H<|qD;#O6-k(>}^sW-68@8{Z%Jive5+8}ukM}R3E^TOL*5r-S zO?KY$@;=bfbW9(m>*>|r>SMj^J5`aofAQhotr|nk;-4dRp0bxh{;C*e%I%BPIWJFM znKkPu({n?lzB=|Hf9j}_=KQiq{ltrLeuc*dnFnS^>b$29_@ittTW4~l{^~?_Q}5Ip zCacZQe_dP7d^xp|+0-XeCl;-3I`(|Zd};IZz7Z|WLnjNGQ?EwqXG~|at@v+#hDMP( z`D|Y^x7cF8L-k1gM#6BDaHgd{#OCJ@1;WhN&7zXl7l_oy*N2&ptBwm@o+y*Fa+Mky%~%F;4Agb3 zYb{s4Dgae(2Jw=4>&QwW)uG?1Al^8Qv&?*>5lq`1#E0k2EE9aY!29(r$UI~ejnWjRy`!OJ%S&U@zOvo1>qj)H!JN3)Wh0{QydqhZ$O zcw6&|f&BdK;ZSWxXFJOj$nUQj0HtcXi59m4cx-GBnE7d{xO60dzlvxN-a)HG(#8Ou z?t34w+iwc*fB@dky$Ymt$|mEw1n{E69iZjAlCpJ;03QG5F>`!ZMV8ML!2O*!uoy=s zvt9A$`4HHd!wkw!SoGbXq!3QxoLXV`CA{jTW=2k zm^hA&d&%K>)j7QL^{woAg&I(ntD%>x!c-Vp|7pTpl(%nr7-xgq0+1imq>BqZN_ z!QMVh;3Lykg-pBmuz{Bnc=R@a(=`LxmE;6IpkM=No4X{tw>g35I_(ELJ@VN+7A5e5 zzxhJw;-Bo_hb8c?N#5XA+D{all)!&hpG!oaOAu*?Ch!%9Tw%QLNzu1+0&n@GFl2n1 zMxJb(z`t}%4|OgVlvipe@Jmb1v9Tp9NVl>Hy!@1fEYwz8j&VrfdDgXLqu$n)Zs`-a zYt`Mh+tI!<>x+0ka?q~Cg}?jBp1;QP^waW+n2inOf#dP~w;I#M?IWJ@q>Sg=-IGMx zY1L$vmGS)a+b3f8z|wM3Y&`!aI;YIhET?QTE1qXwSz116^+e@ zi&LK?pAa>_xI)>DaePAI1ko+d1Hu->@gnnmgu^*+7^j|D>OFL+ebifDD5;)VI(wwB z&FN=9Xf-&Fx8G2THA&k57JnC~J_ihB2OaIFXU^&4xad#=Ryl2D-#m-u+X~bH;XIbbUQ?e<^zeb# zE7GzhM`QW33=QGCwP`#`*kgH#{JzlY`8E4u^;w4PnHRLH*d9TX(VNI7zGN?x^AGhiQOZQ_j8Q(mXKN@+MWj$3%7Ui*g=E^8$ zzh{$cD#r4c-+Qo*OY2FgKEF5_&mWOG;;% z^!rUwBTRj!@XSrN7wZI@7{ik*d&vb|28s~_VtCr$eWc5oyY}hr6lZEEiv%C2UBD-X z{}%2e<2${#?Q@Ia`CiqLE7%Zr%PEF0DeW%h>$R+wLkzF;%303!yUA*#jp3*4d1cc~ zS)uQf+5B_H*W#Eg0pqUB=9wGs6X&C{Qpf(Spb#m?rxgv_wrXzd3TXUyic?*Z#ORNbc?u0BWTAICO5^MGOM`JxefkF&0I zDnh<*X7eF!zOa#>iog|^&3}){504*Yge;Y2bJxw~plyj?m}jxse8;$&aMf!CbILlK zzpPmo)=ulpn!k?by9W8f!-hv}eQv4G4qp4gvD1qa^QzAy%6w@6UyfxH4|YZKB@Z}w zd5#xFHbnCs5jCKX?-o&KK{U^P&k=5yzb}e~MDv@r+^}+Sc3FR1G~e3ncXs_zDcQMi zG;i*(gZ=1NP3CPA%?l*WWSQD~$~WpWh!M#pSb?Gqq^o;0FLJcB?P{{0`V1wSzjj`1 z|M10E=F6*|clxc7coX6+Yk!X7KW1AXDg@P*tsX`3iHFY$-m`+tdnt-fZkkSh+FwX! zJQT&fuNIW+JEWH^QGIr>pu8;LenEKu6vZ#UswIElvPfi`9i={(_m=Z!Hy5r`)#nHo zedWn*YweAPM)4;X{N%D%S#5bcNAVY38pzwN3bO)DqxhBMp0a-N>8!D56rb{B+=zANzr~dM=3BciLtq_`=({k$lq4cC5|Z zx{yzOzVOSOW$a0TT3{O;$%o0y?DBXQ$lp7XpZPTdG@VueYPOE#lM5Gt-;&Zmp9YaU zbdoDft$B)hyG8QOJv`vsqI1}j(viGG!Fo_R#+zlz70IW#`@xXX5w_~;Gle`W{a}6b zdiH|q`JY7_>cjFqWrg2G^{mcPfG075V&tI+p2oK-1RvZj>TZwVxZDQ>dxU}gVt1X~?gM|S8G!P{?1$5yuU zkyDyR@G)!acw9=`P)0h#3<4+lB$MmTTWq?nxN@==7G4CkJ$D#_}OM+M&%&a>^d$$i73 z#i=#n{OWJ@WT{zh;%0m}51ZsCH{|PYFFGrnPaWVV^L;{U(`#`n=$F-{P`#uXilDS~xE>BD1_%%>mAr2mPiRUq;GepahV7+;YKAh$h)ZS)A^-dpQ~$AGeIr}|u= zgzy9RhgEHv9K!g};%a@b5O1%XHjK}9tp}@{))hN`59RO5*dY4HSdn-ml!xu82#1RP zENYwx#{&x#Xj_Av|kTDLIBc6Nm4I z@YiRm%I&*$3fBuEJbg1yndaq85w4!esXeHHtmj=w%-I;iJ#YKT2XlW*d^KO)|KH^+ zyT09Gs~Zx+d$jVFllp$c(oGEE0}t1hcOJ}Rrv`=a3pXps+||#pavekXjpK#n$GYiY zM#B)EBS$(39}7Wv%@F=ko)(odyTb2|>iL`@^Tdl=wV`3&5I%fhQ{m9d8;Yh4;frr< zvd1U;!X@?W%_!SzkA=VbK^b+QzlfS+K6PmTV~+*%YNKbdA8L8RbbB!0;<1Yr-dq(P zFIUgcEPKXA4k!gJW(V^=iMilQxg1bKJ#SO*r!vrW;Uji^WH9eLxjLNsK9Lpc8O$F{ zme{zFS&=(Fggy?v2j-f&1=*go_- z(I{&$@7cW;3~shm+0((su*n|tf_UF%Ud)fxlU+m9{r}vtwyTbQ^3eoU-sW!i+2$wn z3=HD6#+MU^m)Do=+6VFa5GtO(VzQS{5U)4&s*Um*Dif! z?{GMfkICFnI+U5S?b^0L{_4DsyjkY4ZPci|-H1RQm)1e{U!EDfx&?Cn=B@CIDh|!R3FN+$lSQx9mEj6gp9O@63-4(R zrc_Yn^VbkX($|N1MFM$^+N10ThWf#~EP?z|kHNOFi}LR)}58VRu9~62k}16 z_~-TRkYnL$_HtYRU$D*#?$~=Vmwo~KePv&GQRJtQWxTO?_aT zOfTZA2k`Jwbs*okkz!vNb!O@52J*`W@g+|H|L(mLOe%gyJpSy@bNJ_h)eW=BVvqg# zqDC*+=p!X%wM+gyzWHwUv``{e~V9EvCTu$?-h+L>Y1K z_(a$n9M6Y6TPl9I{5@oikLTVKUWjrZxhHzj*Jm2B#CNu1;3JukM zeqW_Va^OV=_o*OPF4Y^dr`CO;Ls zOC<1l(`?ck^2(L3k>f{KP%eAe1 zG&OO)P<*Y=I|x%nc4AhUzp!$4lmj!!q!~v zTP8K1!$Y##QycVf;I(Bz|VeP2Qq9ODLjfNaQARG_1?+`Vb7kx_lo={HFquVsLFHk9-%;4^})RLaJ4ka~j60 zarahKTv%L=s~yjOnV45T_sJ@csCR7&9d?qwEANP@h2r_^k2PeGIh(}IjPZP8_d3#X z@(*I@i#Q%M%10KS_QihiMjU^gp`q+vCQV|{@i_j{$yYY$bH&zbM;z~1t*&f&sxu2y z@7I*7QA@5WwT$(e7ss!?cadYYOYB2P2EYIljlm&cO8nPW$XU29p zAviE6#!`qhqWKWvvBl}0h@W~xV ziu7aa$UW-$x|8`fi903TWV1mryg=1E;_3@0x%#^p^@%CMIQ)YM>sSY#wNdZI z+|DFIU45XluR6CDk4WtD-VcVVcVXhb9I>72?+e}3b97Czc4Ec9tqXhd%;s*JmowM% zHPy32(Y)WY%gked3v_&}&ZkQX{G-ILhD@N=8AQ0-VW|NU$QNbY=weJ7)N z;>OyLt^It~ab+}rG0R&$N7|DNn)uHo=MB(Ed&AYEG1EC3zL|gUF%a+`^;KQjLa&Pfy z-ebTMws~P`>6$H?i;I#?no~_yeyh%;&1bTa13hJ@dr>@YMM<_cR|9$Cf_f(HZbjSN z9e%R%K~-i?oP9$HKiNXP=MpiYzF6|cTkc&P#aot{BW`u`kY&T8_~BtE#ct^;i~JbH zKj%y%pROt*s|=3fOBUpp4Q^zVbJe*u=h$-6?bt6O|2I)QtY}U7{neGC5k&D-XT0RY zzk|Ls_3& zk$hDZcNv?smc2h6$CbR67Tlm4X_Uf$qp{cFcd_VB; zQ~Eny*~@|TVXu26_v;?U4(wo1%u(@%18mjZ%5W=pB%izNH5)Rq1Z?`Oo7Q_Dk$F7ZtKM6=ZS#TT@flf>6%qXX z7e7e&xueI~*%AEbR=%*g`AK{5^a%butS+RFYA@^~BlxNVwV+k#V)f2I1Yf+TJlGGN z7f!7r_}Og*Vd3=ja*ulcEy^)19NSx17OJA2!JB@H)$i*nlZ!?08z1K~myhZ>(QN8W z4d1XPZN26A_u+hqSEB9RCSN)Ep?b%p%&Ej`kNsq!OW}OyrMx0?Z3DSGIh=PMJxwfl zt>63Cv&&lE3y=^I3?8-CISv~Vs zyMI;b>$h8E?W*2Sxd3w2tfVNQ-bvv{{p36EV)k_|;oL8apZpZH zz*erHI@=bgCy&N^vo9GHSF*{cL{aI{{uA4AI*i|V zm{I0e_nY$X4&!f%UlsQ~Vtxw=kaT zmz#>6;bECDUOjIXIH;aO4$7;pjVcEHMtxxS)fqNt%Szy;p8LA2&aed{ZSbMZY?gQ} zl(TK>zDNDqEdQ}kexRoxY}+--7HJRV<3jvk%K1+A6F-IWoWtuwrsl4qjXJ|N>IIPa zEJ*B}70NF-RfXvKd&Hqpp*+{ll8|A*3$aC=Vdq6;gOc^~$owrsd9|5$*^u#0GDy8+ zlD7S3w*BWCa;rMS7R)%F)p){X=@OxQS;rh~>~9TZM9xsYbHh%LW9pvvmX9I)&E#G7 znX$fd!$b8x$k4XJwymx#a501j=3OcZ4Xq`o9|++;hg}pOtCpAZHmkF3LVD@4w4i*l zIE44#SV%VMnNIeM3gH7BDyaSVIk8}B2)|RJwuCPW#j0T;e0+It+3`VhQJ_l*_de_^ zU7a@Be{2%Mhurj&1L9wJ%(8{>kR=UdqmB94&hjDr`9Lnm1W#r)iiGg{xoXHtjkYoW zEFrwkR7d%9y$5XB>tOy{{@l|4ka}l6U57vh-^MiTUkb3sBE7Y7H8qAZtLTo>I`N8}N!Ti{H&YFK)4+;(l z=Jt_sY{*j&_@SLTpQbs^&W))EUDP`xu5UlF*&#)tr+ct^7u5lNxt$4)I0y4w>&rrh zayMAp{K0(61b1L#*07j#!TfALFWAzdA1nBK5TE(M2WGUpZ5#fJI@@My2t5aF+}`wP z5YMvG2g-)MvfD%uFWkTjcESJ=y()+=I^qtStF9I-AxO=o<>1=gYa-M?i02;R0NE>M zmIX%z@g?^6to-$2a;SPH?I;{(YksXH;oBhY>l@8x9J0y0b%Xe^p}^*jswcmzrk+U) zh_rR9<|j*(4&rk@)U>bN;wPu)3gT|L%Zl8hzAW%DkZ)TRES7nL9P}WNCsf}jRwY!C zl`aJGpN72@**cVzj}8R#jS0DBVXy46lseD;T+UG*ulrDZR_9sY_0{Ezr0rsCbRhpc zn#(>ulSP54fjsnm1G&XLyBIh$kav3PCyyVPlUTBIAZJs2WmJs=w&W&(yx?zj<;>Qt z*i8uJTie!_M?NfIzo^f@(#@xUv3l88x6G}o*{+BGKb^zbBy$Zw}-pg8*3*hQC1xU07v%L8O_{8M;u*lJw z^-CMTb0n%<^QvKc|HPlabM=Ffouci%e(~qN{p-P^rk&4YA{=C+tO0XvQh``U|CJqPinj0nBZ&&Bv89v|(6&}ZUWVJO|+j; zI@=yLg_wywY^yH%^Hb#-!`p(@Snpf@ylIa5u&-t$%cbhjdP!~Q9(|ateXH~vl!ty* zKQZt00eoN20?@#rARNgVz&HH%nI#@`g$9KK_`=&iv&XGGVV$FDOH3R~^k@v3DhKd_ z*S(mJLu+WP;_y0qv@Q5>2bka;z-u)3u;(4r5#~1u-~%1i{g&(kny(=vBKUG zc6L?v(aB2eD)(gMA|ccox@!^3><@uzO+v@1LiV+}tTY*k=Xstu9_N zW6AeyO+)~%S)#dolI0+aofE*T&+jN>+l907%L2G(hhB2qiOQ_?`T(AxLVvllN@ts+ zJwUx@F+gtIH^qKyZvgMtw6EMEJw)WO0KVs7H`&oKR#ZJ7z_TuGD=+Rkp`Hf~;N4#} zl-cK|lVu+S@XZfutG~roOpbpZz#Cn2l4%ZBm-Y_n7bR=bDDi=_hjw-eHcJR^RPo5~0Bv)gkeHk&p^POl!w zj~={cd!*hoYNPJw$TfXf@`n+!a{WO5GI}jbnl?xlXd1}N2i;+-R&)}&J%95tRhDb3*wHJc>x(1HtC)dk(5j{1Cu*LlG5wrvM% zo~Z9JtKtANMm2)q!|}Xd-byg)jt$bRj^}0f*M+;|D}YmYJb$(KmDrct87fqs!y8OK zD)!Z^4KFgy;pghl74B|+(BWnR|1D2TvGZvwc%VMNyXJJ%o}*P~s4+Jo^?AhpoA&j+SHADH@lVCwUMsm}+d zJ|CF+d|>MHfvL|2{(tHDz(w;Oh`HSz=^dzRzMDn5(=~`sogXGv?yf_eq4-04qy2%i`g7xf-ayXT{au>2jL( zOErmHaNkSYqZ(C+N9OyU+5Oaev&!DsYXi&Pp$PHsOK-BRM=}%7E}9v>Z+Kf^nX4xX zL%$-Mi03^h3oQ!$Kx|J}1u|CqWXCe=uU3PfpZRY`9^btRTy6E(hU~jkeXm9K!3_E6 zjUq6!=Q`rBv00$`mm9<<9^7Fy`ey!9>@r@#5*~@^k#EpMW$L^l2Ol-Ds z#f^*h(aBZFzGh?>ar3qd@#)IT#4o*z6Tgo+FPbOhAkLjLt+d~KMt*13bC5|7_Yv}(ly54z3aoQnLq{3BEST73 zXny&i?QY^)Q_{&ZJD(8$`tFkG+9bQg@)KUH5M_H7BOVssNBmgRh4^Li13L^&=_9jG z&3iKc>D={aKKnN3sBQgA!pD9E<5jyz;YOIa;bH-=p8qPsj6_nbKE z%Jj0%@XCPp)O`M*o6kkcHIQl4e`~%>-~5Gl@4`t00S%+fNMj z3d%IDABok!Lj8Zh^6K|Ol_OTy33WZO(i2LT*y+kUC*{wwGs}*Ctn%o`(m_9#KK^U@ z#ot@?!RxGgqMlWM^kcLO?LxN;%M)uIVy#cC{Yu>~tPioSCo%fLcww2=w`MqF9FcW< zt@0QLVjUl19XDd-7vpKw2jfhP*ID&MKUV$C{<8R9us>hX*IRB$PREcxdD&#Q=aY#i zJ*X(p-$^3gwy%i%F8l@Y{1)kD^{sgU%ct#eTEvHzC4TM|Cm`9K`203EQS@mY;?W6y z_F=p06K9&g*p^f%g&Wps$+oNaJW=QBvgNFLWOd@tQ?Ij&HOde#%AFOSwNT%mugVnk zFA0S++@m@ail_=3pROZbxIujv*W;eVzl7C;^lk@jSbp}W`p~%W$3*1Nr(W>u4)vV~ zice3i1y1%b;(~)+U|9EK#LgWYV9S`a63c|_e#PqCE=;^++zuAFyCQM(;*(gyL>uvt z=5K7lo4koP9tWOOO5i0u&s58-*pNUmDK0#sJUt6LE(R|Jn_2t&!P`g-zTr^ zqa6y#4{qc^A~yTZt#OkA83r>UN=>{?@84PpoyM zZWrnkYrn+0KE%47#OMd(h1b6Sag{U15m~p_Dvxm>*6|@mKNv^t7vo8+>Vt76#_KSS zSO)!A^*8$~gB(SD*RjA<{$c0<;!5{OJ?(s)OaCz^o2=&nrsuKL`8j3X`LCLv|BieZ^kKM+=vI+o zj=A0FBUhexWSC=*n{|?N)Rz-rj@@~tzFXyBeug=A>QY~sJ$VI{_m6HO-D7ey%(uv< zon(j33+dWQ*L~FA7R=5t_gL+gvSFrp(sAinPj1Pdm0=#HYuHG(oDoTy$!prk^zt=n zX7H{j_w@}S&CZ#d$PYswl4gSXp11A80!XualDB-j0d8%Amz_u$rsdPzmX_Z29 z$F@(Tsr01MB~8_Cq1sQHN>3_X(p2phs{N#?^rX@yP1SCp+E1EFPbgi$c&c^_)qc`c z{UcOAk)~?5Q0*s8)jvY@6KSe;3)OzoRQ)4VKar+tw@~dTP1Qd_^%H5T91$v4NK^HX zQ2j)jDqn=k8`4z$BUC?;rpg_ma)>ll{|MDjq^a^qsC**L#Xh5))5}q$sq#pud?L+> zUNxQ7d`FrpkA%u6((IAvqLZ5YNK@sJQ29if56VS2t9j6>C$sA5Qr+K4&52e$nN`m| zefl`7`O&H;v+9|r{a9x;S6cOCRy{G_t$1R-TlK_zx8jNUZq*a>-HIpXyH!ujcPpNl z?^eHKzFYCce7E`?^WBOk=DXGJnD16RG2g9z$9%W)6Z75bcg%MyKQZ5}e#d;b@)Psj z>UYd{D?d@s8b_G#R(_(MHI6Xft^7niYaC&|TltB4);Pj;TjL$|tZ{_xw#GZ^S>p)X zZH;%-v&Ip&+ZylKKi0g2?Y71{_K!6$VY{vIj{RfJOW1B}ykq}Z^AhHfH8*1aSo0F* zku^_Z|6o7ic*i`l=1lA#YhJ=UvgS|BcU+foUcx-G=1nD1!Ec?t6f z^C@M#x263L&P%$U0yQz;u{_R8x}E|xG2hW{)Kj1)<~#1AP*c}a=y@LFNt(KzLeKLU zPtw%&6ndV=c#@{Br_l2}#*;L4zmukpCu!<_Cruqs($xJ)=B>ii^4J&s6I zk9X44-L&e7>yZ^tTsN(H;(BDo6W2|vp12-a@x*nLH1+y! z#S_;}($wp_6;E6@NmH-yRy=XtBu%}(lcwH>kS69k?r(H{;y#2lG2d~2qw^E@A*6}< zj{6(TCA|+JP0V-H#c`zfA*6|VxWBHyi8R%C$9)}*cQuZ1zhsSf+}Bz267D}q6WeW#ckCZ)Ucz=; z;~o3QnwPNM)_BMMvF0VrBi!F$+p&Lee}nPFe8+skwqyUOyr($?^BwaE+m8K%`x`xf z;y#(`iMfM&8q~pj!F>$&1?Gs#X)14iw?MHM6Cv_^H!(gqkbA4Y-`e=bcsp{^uqlvm z|BwxN)$Z}|ZqrnTY<@Ss`Th2P=6mu}zc(ZGdo%uy@69mpr&;$L@V-{+eZ~J-_Z7|g z!F+!B&pd~0&Ru`i-{zR{=#-QC%uNo>H*M+XBkkGo_3^|PCY@u0mPHcp%2gaXm7AqF z{jv=U8baa1L&>iG1@-@l)$i5khsBB2b)c>nsHyZo=@KhHw0}124ENKzJh9dR^riI` zPg|<}66^YqmaZq+b^YnuZg);PqCeC@|5y)XtQY!2O{_2a)A|zqA!GZ{A2PNZ{UKvK z&>!kxoX{WEKP7(YoshMi+N;YGYaMCm6Jz|)AKG<&h;==Qb^VFW{<3&ofhpW%9S4ba z9Uo#HH)0)6VjX8<9e-loF9LO}eni%BU1Hc7vMx`obpY*JpV;ch6dlSdvg>*h>-rO0 z{fOmt9IW!xk6MTN5n0ER%2@q~cB>zet$swd`Vl#$AE!APc51uTk7&305n1a?WUC*M zt$swd`VracM_mTWxor_E9a_l6KDC_7slTU;{PVGX%+9>dD{KF}U#@d5#M<>JDff>)D3c~f z+h&cgAh*;zYH2d`h52CB;UAphH{Xtt?Hf#b%k4a$V~~wl6!%0=9QR-=?hXrhW z{@B;#3#_*PBhFvzKz(7>?Vswbul?(C-W*d?vt@(aEALUv)xS*re>Lt-QlDU*kW0@R z#fr44K%Ch6y{*Nl>cr~zU+ac!^w(c9Mtpa=fcxrcDn2J=(7LJ+)2lRb`Au$6VN^RC z+BMsaGSn7*E%85M{+Es;Y&+FQ#{`U65##SME@;=WCDt*gYca-_j+)c{lCfsC7yA=^ z>pBSZjg0wd)lK!UQ2k4G)fT(zUt(Q1iXpPmzyHVM(QL2kBdPkA^i}^#)xX55Po?T# z>Ql|s*SZX~MPEy7=JQ`Tekn#6D;*PwtYby2V@Ql+$QnC3=G2y-GVHg1-uHm^DrMiF z5LNkY;w}T-Wn|im#9_hXW#z#Kh)*n?CwFIGOC0=bqFf&xM!aDCap`fiBXNd-*W}SR zd5QbXyC+X=nMHf5*=Zlj%LN+PaPJg5})n$5G<9Vd`&m47p0z_Ij{Dh-G()Uw%5fxMabH zRA%hTxvbA&w5MNIcBJ|{G9R#f`eo-mdcfsp$A||Vj{yHN+lfo|S_d;-<|>}H)IE1H zzwl$5RQ!%Ph0xldlz(gJCpd}`(*%mml3ba=nqGy?j+v-LsRHK`!sP_@$^tL@dk01 z2JKnJ8TW~;JtS&cdq`w!4~dLp2=_o(2Wt#oz>m2UHF7B=fD@$nc3I8^=&@l)6KkoEjN z;xVm);Qps|DfT7H;asiR#L{~QZ2Msd@xp-PuzP<+;`^U3fybCbH0NAzb{&SNIYIMM zwN}^Q-Q@-}-e2Uq0Nc;LBA&4KFkCO^EpgtswPzb_csrT6X~KLcBj*w4cs~W)vu`6F z-L*apvmGXmk9g1e$n(VVr)F$U)oa9knn`=TZr6#=%4E^H@a2^9eJaU&eUB6W*kzc! zw>*is(vlc?{kvtv=~r!#Io$$?zf3wHM`mhC+}r=GOglb1v17|$*?2Z*<5S>s&(-1ShN1j`hxQhu0t4qT-$LS zLe~2YiH!RTj0N()+RN$v67}z&*=vbL!A_r-2Ges&bGz4PU#0{S%l^CB!V1%gKQGMz z;}S*?mpp)#k&pRnSP`bp*53ODJ9F(>*WL=(E>j2ud zKC$*otm{Lp>q)HZPyA$pmoxf99rTa>kg;Cq4;kx={*bX9=nom&hyIYU-RKV)3Am@saQcxbP~!pA zsqG|?hqb#8-nL%Et=;cI_HmKKy1Wg`e9rL@I>~e{*vPh7S5O(@X*IdScR zw;_4aY2sps@4$hTn}{z5Tn4v;E`U1q+WZ3f1{Ee=eC0ay{Z-wgQ1&#_KF~%AhV}`Lq##mxZkyYO^ z>@#GHJ@x@I_6hb4vdR$~_C2!75r%zQmK6(&{7Cchc%Rl^4>=4b|7u>T8t)(#ip)A*~!!HfiOIDl4sA zQgxA5t}1P5<(~2>t(;VCl2*>EI!Y^tt+N=$T*XFOV@I`BT4O=QKw4u&#aMk$e##hB zF_YGqQn8fQSW|r^F+WgK#a>!tQ}v0o#;oddiTQzLR3A#r4`kK167vIDm!bJV<$}cg zAbSeawc3|3t|iu*#JbMJx(>v;Zp6Cn5_NQ2h;(~;!^AqbiS^ha)?dh-(p-Bi1oTdtk)4@y}l6Z^@~`qN5p!aBG&65v0m4R^?FCF*HdD>J`(G7 zlUT3I#Cn}2*6S~^Uf+rJdQGg?abjEtaLi-d^}0{2_XEVZp5U0rGPpkAm`BES1IIiv zu1h%Pk#U{DF^`Pv4~}_cT;Fia6Q}HFh;bdmF^_g!CvnUpo*}>+1w2?&qR4SwGfol`uXI|qy(spk~ z>|1ea?G5i+64&e2+i7~M_Q-bQTDx(r-MH3nTx*{+z;mg-)|RJ58rbsAi8PPgf5VEj zNMY9+Pg$mqDIDJL9!vVIEcr6Z+l}&eqrBZHZ*xwnum0Xu6Nc>?-nG8$J)k>rTxK8H z!DSS2=dlfC-zn3G7udd$1y1=R+l_1O#z^=!nM-% zv;TN=E|q^cxrqI3p*h4ys%}gye=d%=SKrc!%q@mE+0}9TkIkcqF+WQ-4o9{njf`4i zvEj>R__7(kY=$qJ;mc2aPoI51NBy!w^6?8Qh~Eyok$=xLF%O6m8+Gs7cfuXE|BT_zj8Y=$qJ z;mcR$h_a@MYy8*$rP--jdz$Wjm2!Av{PkL!z&i`xn8KPE(1$++7T7kN-%Vzv~hh z9XN*gR=FkM>oJ_TfcIip={$%yAaNnE_&&s^7R-lIm%0-EuNA8l&6K_)HvJmwg0)ss8Dm|r8}t1CwR+y| zH4B=jQJ;sXSS6fq1H-0lB3^jBAf$h~hj{Y4Fc48e9VjU}D z9Yf;(OXJJRC91=}u}`!6_ef+_GPqOux5a0&kP~%?7bQEgCMA4{|HM9%_MCbh|J(Nu z&L!rH8S@gT&bg!CisVm`#8-EelLPYm6Mq@?jlASFl32zLmA!7zzS`cp%1jw_xDwfo zHQN4n?+uLosd>fyk;BnpV&WJ?PaL*ckdr`%mIDr zz980pM6COcSobNh?rUOWy|x?sgui8P@F(`tc0H!3&U&m7>oJII?rr|ep5JEpvKhW? zrY~b{`ghJO|F_m|o3S?8jJ3&TtW7p!ZL%3_lg(J0Y{uGTGu9@Xu{PO^waI3zO*Ug~ zvKecW%~+c(#&K$uAvV?~OH*PQV{NkPKz3tovg%BBV{Nk9NOogwvSLDZV{NixNOogw z`hRoJ`Jdi%uyU2^Y^+UIZj;?uoBq@LCx19&8fRPE-*Dcv8EccxSetCd+GI1*)$Kb$d*waGgF;+kchi;0c1 zt#ytjyK%O)&fR1;&YM=u0X2=a$?7Ar8*7u*r(`$Qroa3AXsy=*>-mR#NV%VecJscL zRUgbBb3gWXv|kx zZvTtUyyjlf%72Qvaj(M~3uw2-7nL#grPi1wyRoOW8+%%7{F07&@7gH;ulB&^dEsB} zz0LdQ*7{5JG1nmDEb~{b7uNhtz6^b9ZY2AEdRF?wecF_J;JEf#YedRA_>a$G%=P*Y z=gNQM9BN%lYt#R3KX4w0us3C1-<66OS8v)Bdu05#lvjx{6U%a}wXkv_u3P zc!$qaCbgV>O5hJN+VFSCSQf8AMh(L`6;)K@>m z=u`a;QgoIG<%1Y~Dj&q?Q~4myc43K=VYeCOnW4iBeP;M&Mt#7jCm8hyqg`mX+Kc6d zZWkEw0V8hcm&%||Y_o0`Gvd#TezBSTh3}8$8Gc0d-F~Nj51SIVo|Q+iS@nron^1x8 z3t}0iD|+`XMSOHuMu|UYM;rbQ8O!1|$f$u@$f%9a^dqBBWoMRMl_$pXN{1MAls;e? z)K@>m=o8=bOVK%r^(020$_Fv}R6dB6&n1SP8ReOw!wh{e{9^xG^#P-vVAP-bPPYr~ zLbnUc6QfTfKBzBsy8zpUj6Si=DLN;yp2XZTxA2RyK zHX@^cY$G!IM}NrZAKQqG{?Q*Y`o}gRr}W*lrO3MPgk?t`R(bS+j5_E88TIi88EyDG zWGst5kWmADAY=W}2eN7x<)pS#OmundJ4*-qju_iy_@$U*c~zGBg05AuK_AGN7x>-_ zGRD$qFZH!m-iQzC1KO2O>^ow#p^p?D>N{eLCHg=+YMcGFTy!Mg=)cp%Rh)FHW6We%BseV-crC*|KQvHtJPf}&2 zx`tS3NTo%rwAC1#wiJCT|7fT8e$b9S(2nKN2QuoQ4`kHGA7r%Q?~t)9UW1GpsD+H$ z=mQ!5GwjSL&kP-A=!4-GjQW64PcZ5aDPE{uXt&yn<%yL~)FDUZ-A&m>>s>#M@WQJ31pohF_U8`3!v_kNaHsvlxy zlj?U2b3m1q>KbCDA(a-f(w0~kETi%T?E)F?=mQzcqYq05eITPg{ve|beIR35yapLH zPzxEg(Fbz9Zg-X#c4m}kh7L3I!SD-4eZZ(E81<+5Go?PQ&~CLC%M&Y~s6&jgG~x!z zFW|Lk!{4RooWXh$qlT(KF=}J}N0$7^aJ@6R;n?CV*RuRrm&Fao&Shs=MdHU>AF}w9 z-qiQ140P$!9xx_1>_v&sLLal{)<@No80)F(PmJ|f?IOl@DSyN`FBx{bQC=82!q69nUt!co81a`8?r$_DG_G_P`D1Tb8qxNa8tI0m^b2_o?)hM#}s9jh5wyX%*1J@T4 z-+casax7_JVKL3MB9)oe_f4=4asgSkY|YcsrKq z)g-sL*>y6Nc{Fjqy7qV?mKpu~98vP+87kve=dS(Mn7cO2=jO9+scS#ju}rTfVWRcC ztO9kueI9MUl&hE>%WS^?KwaBPU>UbMeZ%G%6s__BQ-c$~_N8`#w>V>9Y(8$9(MmGPOCpsxMuiy3Wa zMj3VO*E%yJhRpD#uKn6}X7mL!>a4E)8bfCEBQx5ruKn5<%*X+o5kqzD*FI%N&e)8; zP}hFV4QBMCD*rW?Y(@?+BWKk4BK7=*XRQAz=Pz>~XzUMD_w9OLZJZ-O!~cX&p_ zJ-1>yqotmmzn;zMd}N(%@!W*0&tJrNHpR0L+A;TWtw+YV;DqrfI~#is+)L5k#&z8m+>ia``z723rRze%<4#`VbrCzsAj|v(ovxPex7J%c0*7UbCpY zD!cei^%=xvZh<&f^+)2~S?uD+dIN|*cx9FuYBwjA*DFi)L#%94{f=0bmFgOGRzC?! zLnH#4@9sdx@1MZ$^gzb%rNHm{K*sm&@jF0}@p~-ryFrlg zJJRr-ePsOJ5d1C?Wc*Gw{EiW1{0=s3BQkym8~U*9=))?HK9ErdeITPg{ve|be}{}^ z(FZbWpbuo!Mjyz!U6!4`?@*U#h7S2aJGRO2OFq!9%90OcjEzx$>N~V!ERFVJc`FX6 z1C|c@K*m_&4>H=&M~Y5y@_~#RM!%@;iB{140EzgRD{dW&&IAC?_`AY*y-fs8un0~z)42N`YnJ7g@2*C3;Y z|6weZo!XAEG~z&g zhhBgWSocb z2ick@k*#?W*_tPjah^2yC&s=dbw8>1d&d6uzhXa$=L_6t;#mOmB!%7Sj9}UEyrB7? z&r{a5|MEO#+;jd@_vEcJ%Ris>jQh`j+2;uV>a6tl+$aCvpXvUpd;8eGc;@}*^XA|2 zc|^CTS46M4s-8F(7%cmJTq>$9az(rP#YS;raSD5O-61|@tVs6mo`=N3{V6=A=_&F4 zbS1K{OLI~5FI|P$&;i2^MtLxFz|aT7FNE%YV;{JQe3>lk|9Crbi@iGeV#m|kooZAg zZvL^n{rQ2EI=txG+a45Dne2NO#@idmq}21`!(_YPtCad1I$+qrC=Z4X82VuNg`vgX zvR7$S;%TtV7n>V4QPCyBl6uvj)7(8@NVc)@rq4)F@Hgv$S zgHav~9WeC4@Cz4Otbu@$#i*VJ%h9Myt3KP$6v>F0G7a=xuz_5c+9t<5Y^uh28_1>iS%wOUO?GFr=hr`o*4yf`A z+GS&VI?v39t`m1+={&u+-y}X+ES=}opYIUQ=$g*6(v|zft=bU#8yRCM(G^?U%?4IMD-V3Y?# z2Mm2M{KEM_XU}ExeNoe7`OT$@o+XCWBwxdtxq3do;ZFQ0xx8oQD=GF1-?@0cY34!p zd8NyF7AxpU98|m4!LkA3fF#JOH2GuR$VM|f5Cd{C|u@$+6)JTss6B!0QKs%Mo^4T%jMFzjHI z2SW!8eK7oj*0Eze4VJpj0_&#riM2kl)+g5b#9E)&(6RiY-Kr0^{UY&N zgQd;~v`gJz#JazTb$=1-{vy`>MQrF;{fKs}e~AqpD<8;i_ywKkWH(sq@r8D4ToCL0 zC)W8-tn;5(=RdKbV~q>6TjPb;(6PoB+4Z<1*7L?cv()ny+NGXPi1mCztmhMAJ)aQk z`GnZevE~`HTk{XGp<~TgWH(MUtx=gIsWn#T96YF)ESg*^(hK{vfqupA^i47fV z-6y-@7xaFH>;_A{k3ze({~^}<9AdrCA=djGV!h8HHgv5058ADL5wW3T?W4%9_gBPv zAN$WN_5K;{Qtxkx_5PMv?{A6q{+3wpZ;1^ZYu}4@Yd=hE=vez_vKxNEHhZuvGu?&k z2Fsg`CrGbfOQBu5Ul}F4EhtSK`|WVqY;76hpjSiW;P;Ni=|2vVw&BjiC8iIOk)O&E z8#-Xv!6*-g4jB4i_=O`*zsTM$*-_JES=8ye+>?}!d=1U~2MjwH<-yPaLmv#kP-I_$qy>X^(fBf0HhJfe zbmH9tVM7NDI~e7`&;dgq48OpG(8#>l}h<0n9B-ZmMv7v9xw`AAz+ds3^^D5e3L)AJs&p7)6Lyhp6(Jz_oY5gR(ze28{yo+LJO zta+8}hF{S08`%w(dR|4l)bk#(p7)6Lyhp6(Jz_oY{V(?31Kh8wSpOG7sM4gj2qu6u zr3qxO?;$7%NJr^X6ahs<6zNTRm#SD0Q9@Bfx{&Pk4dBJAc!2h&<|~aN>!&DtWS7yuMYgO}Kh3MP9w`347fW z_PQtRbx+vqo^axcdWbygq;TSix+;0HTfDwWo^bWLioAN=6ZX0%>~&Ar>z=UJJ>kR? z^$>Z~N#Vp3byf0Yw|JfGb8W)aYbo;Tbx+vqp0L+FVXu3_UiX9(Pt-%?Q745HPt;Y( zlilL$(vl}!eGMFW_4R6DU#}MS^=e^XuNL<8YT?8a>)6O+eOoy3#Co{o$!_uWUda=# zzP60K`Z}<%uLBGFI0}J~)uyEpu^EEA0LVV~4nKEq0<`a(~%7$=@KRC+vNfVvG*hV%z)O!7AAS8((l*!d-QyTa~|aP%Ge*deB1Zh-NIJAEDLmLUd`!AoaH~wjB;V)jdTmAYP9}u2%ht2D9 zyKEzT=VMJBv+uUTe_Ukg`iVI=7hZYcIcsy@`ofo-{#-lq&trx2y(!)MhIF4g_J(8I zdly+r{LA0CUi-WKJDk^x^4e5dQ=0Czqd5;-W5OmM?P9g@gHNur)B_vJ?)o3NaqM63 z-%9v1o4>QUV$Gd|Uwrbg=C-GH6kc(S@y)d-c6jW=w>1aP-rXSR^eJO{tf zocM_igqOJBAI+a`?BbU1mFZqQr2FPxdo5jlxOBG;_S6!qmA}p3<#t{VOzVw9S{uB2 zuKmmUpXkQmcg{M#Jbp+~8*ly0Ic1S=c6supeJ?8SzHbxB|GLVz%ek|>Px$7aU03Q- zT~0o=U%&i$)O#gA>AU@M@<+NcyTe=Bazp=}lHYaC^`*bF*5YDsRPr=87}9-w`HxH} zJIp=5I9L42&E+50%p;uFd((RIkk)=T+V+WZ%n}QUf8V8FD3AZw62jm6(JZ~aHqx48 zx%u1k^p-ogYwt{B-_pBxTdhx)E3aRu_u|r8&n&x)TC6wur`@${+`3TjZI^ZaA2ZMV zz3=M@W_4F?=81mH;4JhpL)I3Hn>*u{s-UHTWf*w!n5AHa_^x9&J)giJ!vm# zNc%qZr_1zK*!iR4|NXk7d)Lpiy>Q8J7xu9)>@`6+pTWrIJ%(}~!)u!Oz19im zb1CWE%aG2fc&!${*YF;>P8+5%#%?u+L$HeQqP{a~|P* zCM}CXt__h$#;d|uR_QzReC*-?M?5syC;3H!5>us=fy`?Hm> zKXVEDvzV|yqY3-7o3KCA3FkeOv_~_f{S<#D6~8~L3a9<4yl*w6JtlwF7Qa7(3;VOV zus^d4`?I{TKjRDgv%m1dN4-!-Y_0R9<; zb;45pCC1JneBED{@83I7XHd&GpIfni%iOa|KL0OP>2JIBEW)3^a@GFKCv-e#U9(dE z{j+!HHXl4_+5YyQd#JmwEitNp((k)9%)G~x_OOPu-*m*Nh5LJa_%hi#VWma;bKKdj zh30+XwC_BmJ>mz}Te-j4CEBwt58b;~|3iCs?-Z?j+PnLYZ*+lt_-M0P|9idjg}?LA z=KcPT=LoO4*OvXa?x{1A<<1AT>c6tv(UQ+G$NTyRZ1|B*XN&dvmu|L+@DX>f)&I!G zYYFE)ue7H&r2Vfu-@ZcsiB12kdFE~puh3t0(|d*UzJEGbFr+g8{p(79m3fX8{|#Gg z*#Gl)_ZB|ni(B=7cFsD&NAI#z|MGV|rup`*2k+E>$7dJGcp~!_*Aez>Tjb6u?6!pS z9$ebv8`6H9$4dMjL*aa`BcCA|${7#Ofl3?K>~cfcb4J*6snh9lOxSZz*mF|Yb5+=L zSlDx0IPVFjJ;x#K5Bk^?zmHkrd~PS53mVcHo*#8JNBmxkguO-yd+q8ITd!%tUh9Ot z1`2y^6!w}a?6p)l?@^{b&>`(t`n^Ct`#nN9pUcW;z=m>0%kOb&i{JZ%{hlbC_d9%# zpb*2@;{f}fg5F^N5nEM!=+ zVn4CQo)kJ<$MxXYlj?Z7J*gz8Himu$$DR~8_N2gWS32&Gu=^?O{tH_k(yoxlej@F{ zp5(p`8I0 zw@Y%{pIU~#vwf@TxPo0@INFOm+6#{Mf}_3QXfN3J)Wj3*MIP-1yPQ3^(3d~aUgXhU zaI_a3?bWrue+rKFf^!?af5q?pE^Iu->Bw=3-a2)m!c?!R!_E39b`v8KJnn)V!Ps=PTdv{Iu^qTJVHO&FyjGWq% z<{LvgZ=B{ZHO+0}T&rxQdDM{3Xr;MXO>?%I=5jU7@oJj;Re$b~KWVO5(;TvDevLr5F56&xu1iW0{^kBR9mKo>gmlhK(GPPI~5z zoRmC0BS#KPo}Q`WOrzxK`F%*|!_%5TO=|`5-hphTb%~nJvexN6L+dq1oM{atYLw(@ z%_M4CkG@N5EKvg`Pirz!GbK-JI8mR)pVo_pbY4BJLDjT2755$akj^#_>5Oz*TZ?<2 z_|sZk+$$wdYj<&Pl{~HW)wBj!)7oH7Yld;=Q`e^T$swJePivkvt%b&WL$a0DUF%TJ zz^Ap`n$~!0TKlbOO}M7D;+ocwYg${bY0bH&wdk7GsN)Q(+LG48hx8qWw8mc3+Izeg zCR^zn2sM4vpr&sf)IU$dw-nOeK}~xKHSIOjvxuXNq?7iQYWj9TP2V)A>01XieFGuh z85B?2tEy=atERoJn)bYE+6${`kF2J>vzqqQYT9e7X%8;W=*ow*-&fOj18Vx7KuzBn zsOkFyalThPX%Dfcy~TL1Q#xrMv!-t;O!qe&(%xuId!{w*rPj2^TGQTZO?$F6?bX(_ zhg;L$ZcTf>@h+|I3u%9ONZ(ILd)77WWykx)vX%DDYx)*JP2VV}>DvW0ebXS`O%_ku zi?3;qzNWqVn)dW-+Uu|B3_wk118O=mP}5n0n$8%+JKgdjooA@&dj&Op$DpR~8`SjO zgLofYJn4)?O=l^>i+1NZ&L_XN{tb zdLBtOW-n9^o(+rd zeuy)jLyKIMe0slKkj}Qnm=aGq3m0Qh@^p4C#;oM&tX+(8$$)9xgGHSl$>8xhlBP35}JL8@rx!-Gq z(;3m~_ch7WdDJ0&#~__?t?BG*d|ybm(mOJ7FP40I-?d3+cVo^Vo^;kX<`|Nvv%xVZ zkvyFxjya6v>FjY$XOiRFQ_@N2pJR?B`SgBQA)TqN>8y2pk4v2CTzAaoz}ddz_(PiNO-&MbL4>t53t`1l5zbkceIA${i|o#C(PY=3+gPPWo} z1VegPF1?!&&qU%+?=r+Ql;r8%hj`|aJiRLs&uEgTcPnao=OW&fmQH%Vqo(ga)bw45 zn!XoN)4Lw=j47V<&PYw~lEi!8(n;^F4C!6S^e#+1gNr}CJ2S<8N38!-17rOk9P9t! zSpNsd`ad|<|G~riQ+nTRaKFamqd0op6i2YdQ*i`aoE1l~?<*B>?AL(#dk^;gT{BzeYg>%F{gpJnh`(;1X!Z2HnEzAqEkn$Dm+WAyRC^{3DYIr@Q3|9ZXu=>CM< zbgmzKx9*?lc-yniU`%*dZg9^o@)`cfXK>^*IPw`B`3%M`df>=su|+kU`}yiSn8dSKKC8ZfEuU3iz-iyPq7JGJr&y=T?^dL>vXa)&ruu$Fx;CE66whf{i_2?b)4Q&ft}SW3tE6?XlGevc z;?LjCEoptYq;=!?hJ*Sdy>}4LAZlaMpJJUkzdMlDx=UIEFKKPOq&4&WE#i3YkgcR2 z&nc28{&*IXe0tZV(|UMG>(wQ#W0$nPT@wEk?-!(fijwv(;@chgmi6P=L_R0|DfT<^ zI|XUarKG)>lJ;my+Pj(J``Af7O?x_dZ)JM-N7A(=?VFUepHk93OG*4wd@m^NYnQa& z9pC3+T`}v&nE|agCjBY)$MYHHv_~IjhQ*oo^y7>%d;L>#lJ3^|TNk7i6sD38>DfZ3tS^BhhKTYT1)3wumHX!fO zPwzf^y0)bK_cAT-EadlM(td79`@HcTA&vK>AJ5bp?@51(ePMsr*0pJGx}-hplJ>Go z+T+ge(bOcLroHdH2R*&}$m!aW_LocAcP?o^x+MOR-x-E8scA_+&T=4+ z7*=rN$!88rI*ST@3#vPv_F({Dy2L{W$L-dE$>VE%Il2&kd&YiY1*VEa{wK zk?-?)Rv?_#X6gh9bKE&`eM9DKDFgGQTjqC0(wWba&Vojr7k@fCn!iaq-DgVk+0N-bpP8;L>D*>X=Q-nkDxVX7 z%!OLwna)p^bgnYyNV+z?_Y`LZ70;wU#W~FU?ov7nI!*5%rEBASplnUcS<`&xb9&Eh zrfXyV#=dY#=R9M+r?@5ln5!#q(>_8;`wKCLmrnW~QJhUe9&>o%#FO_vV%{sBv{w@I zWXaRsN=e@%it|X~Pu~%W^GlNFJ(s-qF}?d2>DqX{kZ)D92gQxxX>HcO>{@zYH7g5rAiTL{?YJ1X;vpVuQ=}&RKB7b8i zo$)B?>_?f}cXHCT(|v{{pXHd|^BC#cGQHn2^7TyRZQA!Q={!KJb4n-a$5}h%aRyH~ z@#M1#C7of2^+Rz^?K@ZboWt~0q6D#Tb zSo|##>7?)Z#MvI?k(0uSC!cLA>C9V6XW>dZBNzD~Tj_f~ah^x~Nk7j2NS^rPjFaTk zdp<3li!15eT8tz4md?4A#2?>r(tIGDA1moxS?FlZCw*5c&X^&Ovu7E@na{kHbQW%! zzVDR2D;4L;w5Bv2XYH8J#2Gx{^zE!TvnP4_)>in8yd-%^=iI`7>7;XUq2F+AIx9HU z?^ES7gsJc1yqxkO@#MM}oHf}J&OYa}c1a%R7|{<~!s(1znU?RlCH=^G@l5RuTdFf< zTE4TF^kYv!HE?QYz0#SbGA-XfO!~10B>t(LiOTcOY56W?(vLNK@lWmSPKi23JpQJy< zJE8gcG`;f}-(ca|Db_TSeymxEe`@bergg&bxd&%@rzX~LBv1OWhJ!qO7Ea&Q2_JNA zdZ#JAu^@R~gH7L=iDz(erti#5@orRFhcDCeosgs-@A0W_Pwid5>HU67(vN4}LVVKq zUgCXB$#x33 zW?B1gVSe&&bof1bV6NkOFnsWKJhSz9pFPRjq+h|#BkcUbZdcg-5q3X?-Tyv3M~*vi zjI~SHE zD~z3pv->Hz`>%eXzs7y?X32Md;rOP1LSJ~?b2FE_e|=qtKRK>^^R`Qb*IDeK^1{XE z2=kMF;}5?dXL?|+<9aZB@Pe@u?Q*%=>-shE2s^*9+ZD!++3RrUr?C4k?ClD9YxY9F zn!OHxa$F4_9*P5Kq=Ji^W|>~@7?tclad8rc1p&MEJHgc>63x!PUZ<#6z5tZ{Ah z9XQ4sn6bzh0LNGZ$5;c$SW9xXH^v%r=PBSAYhbr4d5ksWG1kB_*1);HG9K=`bJRyO za^LOwu~Kim=L_oVvp=h+A>zal*ExRvWqzj40sH*Z_Ea(0@2Kk-Xf z*T3Ad(b$A1g710on)<6d?wSC;(Y|rcy)4Ps0lVD_c1~fpCG0*3yKkY-Ia^`lDdvCZ z6!Tx$t}W)juyGdiU)X#u=Ck~CEdR~tVm`|^^Lel)xLj>%M~t!2=F{u<6t9;tA|> z`n_h1Z=nM=e#Tw+$#@hte#U9|#`yhj{1y|*-5=?L%}?=wgC89F9;?A?EuM_==r3XP zv)uaY|2f`WUt=w5?M58j2l{JzW2-S3`H!u!2tM0t7SM}%)a`t4=6do~ufpT+(yY`?c>t`Wj^U9sz1d^5gcyuxNj&t*y8 zfL&kMc?xpp7k0bC?vJqhDeV3W|NUFfj>aB5*vAhreqj%czt{uQ4(x$xANIhs8+%~l zfjuyB!XB9T#aMHBoAia9ry_TLVYe&n{s_CD!tTHDaDTmV`)k1~e@IT&+veK4jXniO zUxOnDz>yo^$Qf|t64-OH1xN0IBPWx*N&3Q(+sGs5!7&!VF-E{KcEB;F!1rzbwu>2S zE~kbFGgcUD$QeUsPnfY~_JsM#ztQ3M=z+P8>%s6b);gZ!G`CFhHt7pHPetzh!fsdC z{SkIQg|R~%xi2s?lAc41f8 z{Sn4a#2-7+FS);Re&#+M9)mOf7|i|Xc^mycJnm+|aW}j#^TykkiG8$XXPxO{@Zv|z zIVofIh1d^6?)z2+?E6{5zRxA>`(MJbzlMJ7uYqHKt>fwT*OI(V`V}1eYhdS>-0cd- z{u(;&r{wN`ANhn)BelN^!^4MPkyFb#2{Waw7|8ReG`;Y1ikDKs}++Q~TT;|OG_^bN#mFq5VZl3iy z;YF8xd)e_%PY9p+9|xB6e{#R@buV5}c3i(N%uoJJ4)A;Qz+A`mVEEt#V~2THl52dq zensv)!p<-3c7@#^VfRzm{THTgn7xp<=11sPvnOmk)$9oye>Ho;{N&&6Pel*Rb!JZ( zKC>tPv6I?`TZX7h2|^-AglU)9oU9Hi%UE$2*{Ne$} zx@eNG1CI4Kcs%~Kv)irrg1x^a_kNrLXC83yfW3b!IC#L`N8<7Lhh44pxj*!mJL1O8?FaO{Q*b) zN%A)7S8&uH$-DX{x!VCtcno{Q{=W;kV>neG`uQ)A6VtO74CNNBu!3_t)^f^v2@^9#FOVfRPa{S$I70v+Ws8bJF_4_C2MB?-rqR`^_WmdrWT?<|qF~&hOC!a~;=%;e!{9ooJWK z+oUh-Ji^Xj(Q&)N?vJqhDeV3WlZR$6^#EGU(s>9!tRf7 zj5~DPf5~4uYQ-^(2bXKy$yS%o!J~2K{2F&)9~aVzai?o-yfPlZG48-I?vlJo`ob~p zkUM_?GrnmjIL4i>^>GJ|aR;Vd+;6~sUl8{Dg|Od8gsI2eZ_xMqjo zxgT;pIPPm;?4)+-zLxaWUvXbU?)(KD_qC2k_gTr^PvN+)p))+b)>I#Po(m6;uT7L= z!{cjyjhCT}uUrq$TYoOq##46t@T82RP9pdEQ@~Lt!BHo{Q76GsC&5uC!BHo{(T_>q zCVk7?qfUa|Pw7ORMDFbhx$30rYyR&%s*~WTlVFdtu8lg0JnAGk>LfVo zWRf>YUpVR{^5{o!)Jd?l3x5hY>LfVoBzU;Lj!?h6QTi*^A^-oZiRJaQSPz6}8rSi3 z<`aEilbi_lGnrc3oZ8xBtYNy(@D#AG6AJtKp|JZS?0yE;xks+`wZ6EPwM1cGV-(Ko z!ydP>?z7HvgQvDmd*>Z@XdOegd>sQEbqpMJ4D9tpcB76V_xdAw)G_2y$2y*FzL(@J z*!6{-ry`F!26nrWM;${RbqpMJ4E&xC{pM}d7niG!xxVTc*z1OLVq74PItKRoBb}&Y z$fJ&RJl%XR$s4fi3p-Ci9(4@tb|sHGhCJ#RIO-U9c-`rZweFPrYj~_3@rD{}xxezd z{qR0ZzovZWsFXae_(WSoC71z{TSFeHBW=n+o;--+Z#CXs9n)U zw>uas_eb|)_hAa`whHsQjGdphYu;u2!sxILWb1d69=Potte5v}T~FB7`FghQEo|#@ zJzKvMwsnjFTfY#tp9A)9Vf+1n>Gk2U>jvz4VdEPxUSYE{Kp&yw@?O#xb{=8pA3(?L z3cEkT?x(Q(FKl*L{|tE_d$MJI;U5@(vFH4(OA6CI>>;P!*weKZ5A1=76ZXKw@6z)( zST@P~NnhA`gq?p9I>e8EcRcb(nD|Bfi68dR$^DhE)+xOo+2@IVWdA4nk$s`)$KvsX zv(Rq*0DJuL)BdiJc11siJmP@9aO%h4SKQpLu=^vN`Z4^M zJonvje`(xBJO{{=8M(jcyT4D~-12EFjl00xEi`ZM$G_Y}@?Si8dha{uyj%G1lke<3 zu;=Q+d+t5U!1i}8C2T(j?BBxn`vKGI!)ezI*!9B3H(+S5-Pi*Y5A1=76ZXKwkNTP9 z{iHAKJi^XD2_53czdIiJBkX<(yZ^$u@4UUCKippy&l$15mfmpVu8)?OtG9M}ukiho zPwu^a^`7w38{XC{pI$}y&ibZ-)%ICT*nSS!zlH7h1E#0^vFirxdST-m_{9=)37eh4 z@#XR!dFA@T&Liyn1L(M2VfRPa{S-Dk_%F=(!XDRRKjip@J>>X{J?EcPRZ z@AyWJ=c;|)CfVJv^X(dF;^tO z>kB)Nu=5MM-2wF7A7S@X*!>q~tYHs*>|+m%U)Xb=KK8)01AAcFhdnUu z#vYh>U=K{3um>i7cII{2B=0AEVdoKceqpyespFZ1Kf>;(u=_8}_!{o7H)elD-*GQ? ztow50C-TToFyo2*1V?^?BR|2BpWw((aO5YLe8FClYkuYW!jYfoM1F!JKRcc-Kf#fo z;K)yKZX@FZKU`n+1nlEia>g0Z&$Qeb&?qVJLKV`%dRttw%l{iE9L4P-zEI`Gl%ycnX`LF zdvw_ez4;G&tK|FjpYHu&zPW|%=YajY&$agZ0n-z<>jvz4VdEPx-inUd8O%eMvxZk( zU-{-d!p<-3b_Y5h`6KLp3cLTp^>0=K}JFo|)eb@ujZrTqf9@qmD zC+vZVANSEDS9@K*kKB2LonP4PPU?6j;E%BTDeV3Wd%HsZZ`ohOa?SbI(z@$?Pyf9v zvH2Rp%Pw?i?*j|3B)sPQH}t-D#ZtoK=Y6U-@sPQM?dO2~TWi1e`vKDvw(AD$dST-m zFy6|#rP&!=8+Um@?)p8j^9Vb?u-hHzc;t_;`zh@H3p4k@9{SkF9vHu{=RAGvfoTW! zz_bs0VA@Ul!Ndc5VB&;5F!A#}j*zRpuHR2Q!p<-3b|-Z_H{g%3`zh@H3+MiNO@98{ zjJw=M@6(9Ma8AAfa?Ir^EJ%KOk3GLFe z8@{=mdJ_7IgYyWddJ=XgdAp*XgrAaIyTpqQH6;2gbd@Wsc@^%j$DQ$|~Hw*n<;t_U!VYfSgj{76*ehRz) z!i+ngThgw$$I-5sTf!4_OWGB4%bMnvv@7P8_!)Cc_+oBJyJ9aOE6xR9M**-PtT{-pZg?F&!;s#pVstzTGR7sP0yz_J)c&8K2_hj zT>awu!s+=m_$5!zr^ci8w*lIio=erml7Y!cWQFf8pGB!(&a) zaWNKp#BfF%Ys2H~jWxb7?yLfVoB-rbf^rKE9k2(pC zIth+C2_}BNFA(y6(ie_8i9G5gIO=4_)743E)JbsENigwa&kvmT-D=u*t7+e@rajY| z_DpNqGp%XQw5B~%}rajZ}Q*!rTnEt|^w@c>}z`hq5 zJUX9%-1jaePkW~Lqw@*qq&-vo*ZBnGY0os|>Lb?|PJ5=rjq?wal3iin!xc_@rt}N` zOHO|ckFUWzA0URq<4b1}hR2tkHzFT~I=-SFMr~xi6txi?wGkY(5gfG{i59 z@~DmIM{NX0ZR~h9W-oxVks;T7K58TKsEy$0JFwT}N#LlB;HZt@sEy#?yFbG2 zr?C4k%)G$QwbHIQ*GjwMT&wvrc&-)xIM-VJ+^KldIZ4_T=UVYU&b896!RIxXM;y=> zb{=8ppXBX|bFJZz<)%=pUv#aOeP(mHd- z={*j*%`4n~&|&Z}*?RwD4hv{(9nHR$EN?irIH-4|?a^!jH^4zCGnX z|JI`a{x96y@;?|EzXPMoHDEa40>f=N^ENOxO+Gf{rr(6V@d(3X{KD|t|H9a`-<6JM zd}}s@v1vAhv1vAhy?PCHYyB|D}Jx0%N>g$fLdJx8AOj;!{%G zuqz#G(q?a0lj7f`ei@tli#q<{pB$pTv-}aZzSVaGkz1eZduCwEh1T*!I+i1hJ7Hw} z4js!C#;LI78hIiNH*xHEwnE;3k(<6S`o<#+kMS3D;J5#Uv1z{(#-?2(j7{Sb#-_DP z7@JAnBz=ANvGeDiCh_yWo32Hc{Neq$@RRq>!vA9PpE2Gp|+m%ePRX1KJ5WxAA4Zz(?&4%u?NOJ_Q2Sm z^TF|>!Pv(}$gvUn*Z{+W4KV!t4@SoC!02KF3yf{_`qL~!_WU;hdcMzrR@hT zZ;l(!J#gnEKTy8@iJd0U-Uas9q40Cl3m0wQf7lknH*9`hd(;<;+&irV}su>+@sDpWWBKW#Yq=&sF|x)!aVuxD~%G`2~|_ZZG-kL6Yyj z_Im9zmn!%CY`Fi?+wDxRP`(n0#z|@J(Axfb-x#Ez$PYnJAr8RyfP9 z{qk7y^VF-p*lw}U;SW7B!tU+;Fbbbf#2_wCxdCZKchpU!Vb{pCLCtg-GB6CXR| ziLvDKmM1-C*STq&6VbWu$=}(vA8658W8J;lzihX- zbgrG_t_g>q)oamN_}K^S+Eb*n^>Yhmoply|;cL>l^vWwt{uSw5JI59ildZ9n_qj_t zhwZal))||89=q?czm?8=Px^{oJ7}v(ZEuo}T|4M=lVaE;TXyYW+ndxEP4d~U9gJa< z`msrEw`&LcqDeV0HpS4c9qiL4<;>XB7k2GnZZxSMO@A<##-zR-J%jZkXB`n6p_-)QJh;6>t%`rlr z<{O%O;7``KzZq?3?%-Kd^FQ=Eomc0L(CQnOYpo?x23c_&*q{!0-k3 zw#2pe>^Q>y7Jz)VdD`H$#xpoawK?8#n$udlnD1r%!MJ6eJl`|Uh*itq4aAn|Ui`vp zCkQX|SZVKg=TX9Y&OWg{>OCJ9w!i6Te-Cg=;rgpps{Jo)GW&agvk9ASwQKBI{hneR z)wqO>yIy+!_wDa)+*A0Qe%Jsb$42O50}Kx~!0_`w7#Y6rKWlK;WTumMIF8(=uhe_^GlZ1tvH74;}o#FZ@GBOyC3)D{O&jANIh+72m+b1AAcNggrQkA2R+UuGk1U zHjtx_4KO^|KnH&Q2P5Nm=%C9r$l<^S7;bEU?SJ(h`uLLc)pzLNd*WB$AvYN@7Y{MO z26E$2-@)0%Yy^LM-FUjb3psHJeQY3yC&f*Dha4Hd1EY%#FdWzb<9}YWN^4oeYm62j z*8gU-HOArb^~M@sxxc{FPaDG*XUup+PMu+#dW{{v$5~9GP7;%-li;pS{_ox6^86&t zTZZS8KHp38+Zkd$$@2yCOrAkv9?LTY&j=w;xS87XQF^}6Ju{xC(wg&-*5u=vh5K<} zp5xN`^S^8#A+<$u@MlKW;Ty2+3;YY$$^ZE?-M?yW-(pqq+2bZmU;j_+NBs8XZ;iL_ zH(TCp)qiH)-;SO5hta}k)sHmq`~>;5Reza-E^U7Q_W6Xr{mM_8i)Meto{_fd^OJvr z`8|4IuH$+zeDH#?Lz|MEJ?PMH!OkP>{K9Tm*!`*KyPv}Dzp%F}hCc2`tcvSVzaW^?eFU^^0O_*|Kx`o zm+zjjY5%hy?_YG+X&aOyAKI+{(os*1-~aAXj{M3N{deu!j-Pz;YGwR&TWZaV^)EPC zXJh>fY;{HJUtreRSYHG4lYfI*A43n!bzBdIkF_)~{t~MsZ0g zA3W=Q%AY?UI9KzR_PxrV$;Z#$?0M$9l|NV9^tt9^6W$~Ji#{`RGxJ~9Q7)C4PH&Fb zW<6cI;5VKhd%^?uy%5W*Gqyjand^$4c;?*y#Ac6cOyBbG?6vQ1PCZ}^@oaR+(ajTw zuPUAoU2#YA#r0MbÍzgg)1<;3%oAKuoS`RFR*x$Cs=H{V}tMe%IC`p9y7f0TIk zzq>XgFMXSMCY?E={P{;qif8i4*ED~>c`@;5&P+C5&P z`kcOphd!t8yZ+iz;};(KoW6&LdPDxhL!Z<4@KAe@!$a)>Cx2Ras6&#!>Q4&~H3@n0 zr%nE}DL&$Hf7%ou@wh(|Q+&kZ@ez;rmv}rr;_?0xkH@El$NNh>-e2PJ{HdwG#N+u> zQ-6tv9JKtYw9E5HJf6?u@%#~w=d*Y`f5hYYEFRD2+Vz*lmv}s%Yu8^IU*hq6u3dj= ze2K@$mw0@8cznEz$H$j=e7uXt$GdpE&WOjyyLi0jh{wmfc)b3I$Lo)H{C+1M zuRr3kx$bDoMe%t35zqT4d~LMlqImp182+?2HpH{UJ9l}TS{thopVo3wJXSMW%f*OKYq=;Ms~N53V#KGl zTojMhjMj2dJl0>W<)U~jf2!r8c&xu#s~zI8{Hd0U;<5f}t#*iq9JE{%kL6EmxhNhu z;3A(be_G2$@xTEW`E2>qS}u0&GLDqb_6?W6$M~wW4IVh)A`fX3ZG#66xO{w7+Qzt` zO|;F&d$n8?4{f4tKHjV4qIhT%ZS(P7Ef-_FSIb55(C3zmG2W}?qIl?Y%f%S))pAih z^tt7tc<6J>Me*32t5TzA7kzHIC?0YUIqjm)Ef-aP$U)>@4~4xR;!gt)IfxGJa(^0l ztR6~EyWF3~>mmL$DL&$Hf0`5@@wh*#&*WgbUl1Shkb`mmA_wDs;r%5Zaxm@}`!anfQ={+~m>h zpJNOA+*>&2_VC2q9vpLfaLnzKyiNMTF}FwV{1qH?dvMI{b#38WAs_)Zc%pH_Ae9t z8M#nj{MlKUXH%ZNk@IZIvp3kE!G-}~mT=a|W3H&}7a zvWMl*qc4tV9$&I3f5v@jwx&OBJ>}0s>+aWlahoyH|LA^iZZ2AKBjwVEH$JTS;P34G zq+NUJ5%V_7ernUQgXPs%UpS^Y`qb6M^Z3apG)sJXZSfrR$d%34_g_Rj>ui2%bHYCc z#Ph>vZ)n!tZHVs-JX{GPuw8=XGCc+P$PrDm?v77`B}a1n=D zpP#9G`_aY40|#8R>xtWDDJzT{B_257Vtl~?7vqaI(KdMCfQzw4n`j$6aKJ@;XcKLN zhc?kRc!)8vhKDxMHh73Jv4)2>(KdL9F|me+7!zxF=v(?29%4+a;h~@DZ+M6?v4)2} zr|;pR&*^)34ze0U4#Gp9)A#UDZ;-=7pVRm7PTu zo#JU+g}=#p5+cJU-sVW z`b-X{dWb&_Jnm1E;?pF5niQWV`O~EMh{xk29`7&lcznd;{Usick9fSl#N+)X z9?u`~kb`mm^867GIT-gZ&mZx4{)or(xupClw9E6kr2Hvf56S03d_12E@$vB`9?xg- z`1lf!=d*Zxe2K@$mw3p*nE&|r5)U~T^B*5y;vomq{D<)_9&(U-GwmV=x%bd6a*%s7 z?IH)c_s}kKFwMuPKjIG#k?!e6^G~cugvgs`@DY_{bkRwv5%?!zIYZx9?xRn zcoqZ4vl!T)t+a<2&tk~qSqvP{Vo9Ip_23bXXEEgQEC!BeF>pMKf!%-G8{4Y?@4DZb z_u69pg#EZ!Kk+@g;k{8};_D~GB-T&5_`E)Qqj@bQ`p(8g8+`{JUi-R7>s`@z#3cHz zi_hz`_Qm|j=0ZFlw%aVUR&)7+#|W>q^>xkl+a4rr_rCJ-$d3r$eDvGPZue{~%uoK! zwcYPW2y-3RBZm)Ou>D^?cJ{s(B{{Oz^@W|MB6ogaw=3-a2)m!c?!U0NE9CeQ`q&dT zo@(}ljlY^bVSe&&eCU2ZLYV8!p8SN*>x`4;T^hcOa(RU+8dkiJ_*h=4HE;%;2o@=oQZ?ZEc$>odd z3pG}@2$58TD`)HoO^OJwOKlV+E zJtgNlvnM%xW>5aR9edAV#AuhRy{=z8KJW-Te}Uia3cEkT*dZ?HV23!u!@r~NhR0gB zw>l$_HS4R3$$R_RdVUIf-U^c!-S|4L^*oo{^Itf|7d+$z*MrFmc){2?;rH|NzD>y6 zq+h`?zQE2ex!V*RC%4Pb zwUqF^-#@I~;CCHa z2LIO%xM^b89a!f(6T_cRf9SG_;V1HMw+qP@`d?jjL1B27y8A7{@IQIk{KDA1{YUc& z=B4>|1$ecBs5#9@%%;uCg>Tlf?4d|>l`RQU1v#5cWCzp(wD!e80( zP5qO4#|S^S`b_-|?mSa?diCKv{??DQtNq8q;$LEo-P-la!hQIk-s-dM&sXf^&yU%m z-S)nPBwuXRgW4CDTuA!&?7U@r-4_<>L}%-uFTSI__V7;Ug30T(vp+e%c#gVd>GryBcRD*B zwo-e~n-}SLmRPo(ZO4x1?iUwqAG)Ax7dqoE?R2ghId}V`Z91RNyJ?{^oEp(oLuIn#+-v8=O=hBgnPu%@8U2L(n#zKn?wtbgb784ITSB_hB z(C3|JTm01+uGr~dYmPrJCLP+o##NmTeX;XWoen;4xa$(qQ4C+|bm+(SSDim=TifT@ zX-VnO7pp$n>5v0=AKd9EhPQV*^y$-kb~@zDum0pQw7wX5NvA_@EOK7w1O52cr#m0W zrL|7(ILU!suU}m4C1*bO*2OfYEa#gTn>H4j7_(MGni$JAcA6ODHl~^w`!?2^R709n zLz+}W2IV%E2lZ`?j}0Ch`(uOOYQosCYqer*_+vF>Z1{;h#w_|Vmf;y3pdP7)Lg)n;6&VM4hqm*u;3W`p`suz*f{N8`ooFT%!|p2A`wuS$!BA^#NN^uV{PJ zPjsTr;B(YH#n9_8wxV9q_NbrqMbvYAj=HB9dL5=8xfhT#v_0x4eG&DX9N<2Jj$-I_ zm_CjBg4K|Q`;K_5FQT548{A)z(~og4uo}{EKSE9pa32AaGu(HM`{mV~!Rsw|>OI1L zDnA><$PZcNSmbsFb4u*`Wh(laQ`e&Z_s?8eM!xex@vpb>Wu?FPmxOme{rqy>$Ilji z|2e0X3pYQl(>Zs)vf3X`5dQ5U?=H`L`WWF;7n!GQ@~6XvAN%%qnsrw{Son^semC~M z|2iP>#K5N0hK^lZ<67ga!MWbK`_-^zKGg8Re5>J``CP+iYfFu`bAqs#SIp0s)0@~C5b`){*Q|2Hp#kfA&oqmnG&owztSj z3-o{SwU3vVc0Hl@p|wW!Pu}RnvcOfR^bS37rT%jL&zA*HIit7!(M|uz@#D+lSAC&3 z=IpKd&z|_5via{W=$-KV-pZ4d5C0eXJ?D9iw%aqtC9|&aJ>}t+=PuaHar-U8hirXL z)0}s+@Y{d;ljh|MCJ7&V)Ewo)XItUtelfZ{d&!N$KVEliIrskSgn#g+_my?dze;%B z%idq=;@=j2`){`$j5G2R@BPN0{v2ChAPmoyi+oua{;fCsf-rW+ztoL8{Ml%WGbP8* z*|+Cc4Vyk<7uYve81x_{dpXt*tA=kC& zU$V-T_0-$GCi!!#Us|u&?u)`+D}>KG;-tFroTmz3y4y$U%jX?0eB3Wrt?RFJwD9|0 zc((n~j}H}o=-LC@{eE(wFnx6Nkq3ml3AyPvp>I4Tc#OXUzu7He*Ze6~yToIDmhjX3 zFX6x6I}{VEd&TNr-|L>P^}1KA?)AOy6{~xFuY1MnUf=6pV|B0Zb+56y*Y~>DSl#P; z-5YClukUqlqSd{=*S*&2Uf=6pYjv;hb+5I$*Y~R#XLUbVW{ z_qtcD?)AOyRjYe_uY1+%Uf=6pwYt~$y2sd8tRg1=hJBs$nft!lYv0DFCJ1}25cV1( z?6pPMYmTtjB4Mvl!qhse3Bq2}guT`c%B?00>RU|^hR14xF#J{%gt2QiK^T9mCJ5uF z)dXSux0)dAH9X|hiqNNq2zzZ2_L?K?wMf`&l(5$>VXtYzUh9Nk-rxgur;RQWo_oJd z>$9tOwc`8dt!wxAuSmY|+^f_(Z#qx-ob?u|^PX|8@VEnCZjZXZ8?zg(^B?WTB4^>xiH@;uywEzqro40>JEDk|Ew0=oOG+bhd)mRFSo|^ zoLLgybI%LyJ^vGg`N_XKo~`V=q1Ov@9oHj=4_@#IzaP0A_FUeC-1JN6n;rW*2_28| z+jkQ>e*0YC?**fV~`))$#r}5c$6FUFRj_oy!7>_NNH(;}aegQj=u=5MM zU19e}*!>hXJNPer>G|`~u8`B-&?gSU_=`R4dfbF*ANJfI;w(%&!cXI)U*v!E7i)%K z*6Lr2UEluR%glrQ2qv!h0d~8>?vJqhDNJ1P1O4bnaQ}dp?eF5<6LR$~R9YrP-A#1DI5;%Z}Ye3Cawzks73!O@Rkw<{guik`0R@=ZAU5qb0@*xMWW z>PO@rAIUv#!qJcDc$~Xyy&sYPvwo!Cqrbr3?=|IvaP$}Q=r3^em#!Ticiq_O;vgLT zmEtCO^cV8zFU4>w$n~aAH3iRqvlu+doFK6Zu(8=8&3%y<1fK)KTFuP-}Y&p%jK#wt}pC71s&%XcDusvkFfhGYtFe+{%l`=hBZ>*bv9jL(p-oCyo_4-seZ;^J^d-^ z?7GkQ>vv8%iZMHQZRn!|9=pSD>w}MfK{}>i(06%34&H6A+sgs-w8ESH@>}KCi~mgc zrEeZrzV*)Mgb%u6jk4SpGxyN{*eW+Ppa0`*!u!2t{V_-1KS#*hkehxDedDRYWBfJv z&2A05ukmxRUB_H=Mfv3m7s&r3*Ey@~w9N$JZO-1U+{TlklQ-jC&Yw(-h8g{K;deJXai=p*VFZu<2`pf%8*AlnT z3G6!k=y#J>`r3IU_kNc=aEetw<-kAXfz$NW*X9rU$^meSZ9m1fpJLljvF)eW_Rm}Y z_se>0kw1$Vv1g zC*g^lggp#_EaTK)K5^R@YeKmCIfd+lRy7XJAnC-?sL z%Iv}iEp>8lj(J83FZJMwyW3}!p&ve&Z~gGieC~(O)|P&>#oE}9Hd@>J z(RPbTKVo9B>PM_BhW&`4#kL=@wV3xK=GGVe=nL9K+r7PmZM1&u(~rolfBVtD*6;o3 zcgu%<;*L$p`X0_xsD^K3BHdeiO;ZJ-tu))S2Ui z4}NH^GSko368_t1e`_{AU{&FjXFamnEK1&DxEr%mlduc2bu;)Kmd1CtLME;b-UsBGLlrtseOi4LYQqGi= zGbQCrNjXze&XklhCFM*>IrC3_#{b;jG&Xx_Z1&RF?4_~UOJlQ_#%3>#&0ZRty)-s^ zX>9h=*zBdTIT(NZO!X7}sGsme{e(a2Cw8NL;!o61{EYgE|4~0_SJY418}*YoME&fg z`bpeWKP|7O$c=PAqA%ipL?6Zdh`x*a5q%o>Bl|-~^{$Lwl>wl`5CDqK5YGz3_v!t3?Ui`pE#(T{~ z9yJsFsG0CY&4fQ{W=S=3urJKF8Zie)AK`P7PoZx*(HAwfrKYyLF7@Bztb2ju@RPR3 zed_g!Ik63YhpaSz4+>~oS&F)q^m zw5I!MP50B9?x!`~PiwlL)^tCu>3&+%{j{e0X-)T2a$s-{mi)y3m^V%_W|Pma`y3$l zZg{qey&G`s-GF271{`}g;MltX$KDM%_HMwjcLR>Sn~<}26Z-7kfMf3l9D6t5*t-G8 z-VHeRZosj31EyWJ|1M6GYwyPOTlQ|iv3CQGy&G`s-GF271{`}g;MltX$KFlIZT~vj z#lCj5i~Vk4_-!9t7`wJVE{s36Z!T=@Vn1CN|81XLIQLgz_8Ft^z|nW$=sR%q9XR?9 z9DN6lz5_?!furw2KD_UCPk$);Zn^JlZ{uRlijY5^!@{21!k+WOJ{E+1j0pSK5vCtG zBjGuzvm&0W?BNc|IctI3`(4=cLD=&|*z-r&^GewBP1y5Ln09ei#M`B_B4E#L$vx+V zeJlw37!hU+a#qCs)L9WQV=(;pF(@4$n}hlh2Y5Iu!nN>oRs@V)&WeEXhqEGJ{Ipsj z%oyaX2=d%thKJAjSbd1Tqdr96furxh)X&%ZoKNmAo=4JpZ!gx3k%Q@L$LjaMuU)%F zp4NVQY3;X{)_!|w?YEcKetZ9_b#?ZO*vH2o+gH*46xjDi*h}sCzDWi9eu}W~vk3eC zi!l2|T#tV2Pl4_GnB%eMa_vunecvZ|v_FO1_lYEr{VC+JKLuw02YX=OhZ2tcsU+9_ zj_V7@{uDZ~KLvKX1swZRVE0q<*q=hqcg?T|_Vx;U9D;}aJ7JHTaO_WUt;bn%kH7r% zei3GV>+7pC>^cT*VICWP&dBRRdF>+BDDeOFUUOhylCi=$jkHIp{bJ7zVb7V0PK-@( zjLnW`c<-1v#MlJK*i7-!zHp39sj4>;;-#=|xCeNh8Bdmuc6 z)!4y3N9#vnzo!rGIU-N@?$>?a*8Plg3-}!Kkh}-cPiyl1v?kwAYx4cHCf`qM^8K_X z-%o4u{j?_EPiyl1v?kwAYx3+}{To};{r1z^Z$GX5_S4#L|6jH5 z6YKN%neM-|Wro^^&FA{!Y#2Vr*)Xu5S*qYT8wQTEVc<9$1|B}kcLy~p;vgJn!&2NN zkF#OO<7}9&{U>MnkjFcN;Nf>LyLY;W_zq?p?~3w%cf3P7{9b$)+v#~Po;{0nPNpP0 zc$SIv_Bhw%?=R@RzyIs+vawbc@BYNQUA!w4nAk?#atx8b-e<1dw>Sev{|@5hTS@1^ zN;(f#(s{7|i8G4CZP1^D$yJ@%Bc6eYdAxh|fBik9h=b>$-s51*#``$*d&DirFyzdE zL+)7mua$Ez%kxjeS_gBU!1U1+>tjC0?!~ovy>xhe`)tK3)<}s}tdW9ajTHQPt#8NP z1U~qBejn`X{KCHeFYNmQ!qzU{EfuzQ@y@BR?=J|)z7m|VujK7zpJGsdcu%m~kNAJ> z2~KT1hCI%$Gfu%@t_#;&_qe>gYu9EBc)q(XD_2V`r<+eQ~_E3wh)1LSNWvFZ%_0?W*v=_2W5@m$=xA>ja*Z|DFWxSA zgq>g5?Fzd;!tSRqc8C`|%qNH=*xMWW#6cK4#1S2jo3Pm>p2GY-{NXy{h(310{}^}3 zBM-rzx9YpdL*$W%;K)O8((2#!1i=REv( ztdopW@?!QYmb@73{ireM{j0I*{VweJAnbV}?D->1UXaIddcFzA_;R_%7ufSQcr?C{ zd!9=k;|qC=FEDnv9vtHf%=o(e*&mNi@+RpQu=5DV_(JY>C6Doi-2Ie1#uxG!U*H&D zuCMV0j`0QdxP@JfFXS=4z%jnSF}}djU*sovxHc}V8ca-yN%UP8AJuBfqwkPM-+`m= zT+Y29^woFHQ|KFT^c{G5Yh&~m{b>7Ry|`arzTix~Z5Fyg%xpSN$&uTjx?dE{fo z{1e{op4;s24SZABe%jw5xJ}r8Z{G!eOxUg~cD=CiHOAYAhdOEYgs~HH?1Vmcf(JXn z&(E;S@53Li3qRot|FM(Wg&xNr=9Fcn* zf`|ABd)$Q0F7XuR_u-HEN&F>;FZ_>j2mf%LJX7(Bu|`a0usUh|IihFvf4uotydN1~ zjE@*!$_vkD##4+h34X6Bl&cf8o@R!*z1# zb<+BIc-(pZEC0YV^0?!^W@GJb_?hl&n)~>?T5})jJ349puX!u;X5>D<6}IcRUO3JF zsR2BPhCJr~JV!F$4Ia(Q;q?29OP7N+;dd!cWO#4vD_y{3XN@oaX=ND~`xLKGKOfByx|Z$n~r?-$kwjOXEU z;JII7-5}&VQ-^*9JCCsQ3%gz6=r8o$PsyXdkVk)ky}i;Q-oz2P$45B&3wiVxIQk3h z@t1z|SI6^kz4vV&WF3-r(T{3x^jG33;OH-~+m$@}3%UC#x%)31{e_OVS8|U-@FxgN)#bqOSo55p;m2C;FZy(N+-V*14Kwaohm3lX)*(w;hh!h7 zus%rtrgccIyR$xsJgq}&pMmv399e}SF9fTO=U9_{x@9{q*f z{g*uY%jN1XaP*h+sK3C`Uto`?c%r|MM}L9;S%1;j^j(a#jH4gXiGBn}Kc+mX;OIwi z^dmU>5gh#pj(&9c@VK*>L_ZRf=tpq$Blw^7W9r}Gao6pqYb->aBtA33xU-xed|vav zQL6rmzeS3l@wZ69@wZ69@wZ69HU~zpg5z(Ig5z(Ib~>#8Xk7)lt!o_<`uaO;&SUE@ z9Z&o%QsnXX5yAZ4?CIM0`)$bM@3(b4$FX1I>vj73vZ|Buw@4F@`X&ArDf0MRq#e%) z{E<%lEmGv}zvSI|UAG<;e{T<+_sK4AJ;+mk5kKrzMvivQhyxIJUi@Jm677n42=bVRfMXs4_WNc9 z$2%L%=Z)0aH)Rp04%zn6Te3gwuQye(XukPyP*$`GY-S^Amfj59WW&Cu!He z<@u%89RH;~C)K^a z@pc=h$BjQ`wp(kv%0Kvf!Qu*I!J z+z#7tTz&Si@fG8oZC^u!k+$hdt!98+*u!2lkK?C+vZVpZ$IeIxbgx zUB5-gc_erKirnoAyFZG#`zh@HOJ}&h-njj>`+PqgO|CF*Jy(T2hlM@2g+1qmeJlw3 z7-`}0u_NqbN|@XyC(&_vlk|n1N7(rbI&N3k{SkIQh24K)Z&%1Q*5L6RmfUk&*mGVu z#v1xD*4$5xHE@hIF!5vDB)QrfV-0zXHE@hIaEvu@j5TnKHE@hIaPF^+hx=~y8=~*l z*mU_yKR&(JlVi`kWsLB=zuKeu=$ii@d*>Z>S5@t85+DhX&Af38KvCL76cCW|o_%gW5Tr*0=|xHa1qq>xz&D@YnZGmk>oDKv zy;trhW8|+qEaskTt~FPgtDSd@c$Lpw+_&E!<`qwx?}5JKmzhNz|F+`4)vn_Iw?a-F z-?id-s{mH`Lx_7Gkp!xQ@#&QJ>t|a&U{;4J+eofc8b$}G3}82kSBlggRzVJ zQcpkm!IXpiV9G~+Fy*HFF!e!xF!e-!F!dMnjsAX3rmMUu-`~(9PW|G{x82oqG4_bl zPI1~V{`^S`QLgrL8$MNMdBs@|V*3l3tT&}+efE={^(@Z%7pGsYN5=kwGkpy><@*|X z#HnAL`L?=xy8eRGPNk>);t5~wKcD=N$?}S`9>laS>_#T*O>BRWZhyh{7i@pQ)F17z zk*@OEU!tERAHOIeNA32?}SRVdw z>>>2*^d1FynW;DOa=vcc$aq~0d%X;M9SwVZ4SU@U|KZ>T6>Dd@*6As)^*ii!J?!;9 z?0o>(b|&}s3Y?DpmWQo}y0U)KKj?jfr!PEviBo>{dVBQsqdMuFQPr~GRF*4g*pC%)>fb6Z=lSBvA{R{Xa({(mdvy6MxVw&Htn=xc@Ee)LB^TFbzh z-UmlM$hY9sBToI|%vYTDh|^AS+Aq#>IlZ6!(2rf@2V*b!!IXpiV9G~+Fy$scrAK|( zPU?yLNT>dYui#8qd8t40Yv>WDesSh2PJ6^@r$UrrhKQ zQy=69Q%~dvQ-AhXruR4G#i^%Fdg>QvzT&h;oOX)Se(}uy_2KJZ9uJ>;XSws?iEGZ* zX>yJ;N@qNvpCgmwk~qgJagJkRkCVvfxTkc+C;E9;Pj{SzGrg}N--10(D!n@nD?RfS zr#<4dQ=ImTUs(DVOENB_C&wAfYn&uK$0eobcqR5Ynf7R$ls!34!Z{ww{_Z$=#JEPf z%Ik5mp{Ff9-Emm#agub8ld#80IPI4_{u+G9h??|~r`+6k?Ur+ie|-8nt&?A$O+5IJ zlUm!&-}UcDr~b0F<*g6u+xWK?|1FOH-wHW#d{^Roap)_dSN2Cfg}Iu%GF|0O`4;J^ zN1Xb_nXfqQ5vQG{VZRuEkzc0wlOK#-45oc4&*&YEwjKk|cT_OJU|)WgjFHM4(xQ2oo};dZC|iZP@f z{pQrV$sQ+3&+$hxIWDzH&+$r}aljBcUCdWzAbG&lC8Yj~pjgxTtMKT^INvAFw<-!h? z*M4m1X~P~TVULqtJsP(qlXljmdz^%4`s;Po|A)n2v_r*{;k%5x_siR0W39XB@QRd0?Pm7Z}UocT(|aU5zch=FUO4yJ+3#_@8Zl??6?tm$BnS# zMtG*bV!ami@L}}VTVHrueT_Z0CcEE}?tTZm-@#E{?Q6mAcd+}N(sN%6cE5w&?;7da zFU@|c{ZjWk>B)WvXTFkgza!oK4tBqT*`Fl8Ojo~4dG$Nk{SLMtVfQ=O{Z8rAy8BwN z`yEWbV?1f3Yv0)Yj`Y;SKCJbNGhea$9Ww5Bu=^c6(_i<=rymx7{VVUcbN&)-N^KSP z`4Q((KEL>HoOAsvpF`2lRNnu|na)kGFFWq8&Zce7g}-q5e0>X?{5kRU2c6P)=|UTb z@9O-vZ{-Unh_CtWkk$j2E-sFLTk+rG`2Vet)7f-<*NX4Op|2Hs#gUI<74pjTJ~-vY zsYjgpTgYU-;>@uHd&w{Lx5*EteB=jHZt{bv5AuVlC-Q@- zKgP^PdVfP+oO;Bmzl{v_$A5SA$R2UpDW?9&51HoKz0c@L_ZdAr^RC6k^2@)%U5lCh z>%-N*n*NGdXi56^mzQ0tlVgiG#~g8vMdBQz#Ed2MZNAMhtsnN-2d3GtzGfi=x zb&7pviq1S6mHj?5ZKTUbJ~Jgf^|avBFV1|$X^%MV6sP^-N$bsZ0r{aP&m1kUGgH#@ zj8f@&b}9CmY1*SRQ`l#wu+L1pdN?!f`p##j4SAK_XQrh4%oO&SX;+WVaNDrYOktmy z!cE`J>}!j6eVTCy_4BXT*Jk#wUOWF#^e_9Xd7q@o9w)i~;Bm5hcVgz+G%s0d$v-f@TN#|#OvSMesEfy8ed;JQXS58_+y!(19bWUG&74Zh^uh1Da%UWXV zLBG>s%Tq?{A>I06=L^4l_H3OsM!&6kFk{=sC(YJb_G@n|uXPWct#kQJUH zd30JHw#`jOe^bws^Ni@cb^jlv|B|20*_mbIXT_&Y8rFIFfEUE~KRl$fY5B8w|08Gb zJpS!h#nyujPA4zR!`6e0^^@*=;iHZo*?DD~J5>*6?0oBxk)0i{xl?(az0b(by(8`t zPu*%{=bSGOWb{}bwmkgGU5j=0{N`oSZ$|$ouU@Qk)^9G8&dttTtaHs=my3t(vskBp z-GPiA%fpt3ZF7^+-_-NSTw^+qUw5VS-}CzD&eW%`5s&R#xbvk;+T!0ny-?>bf4o7w z-8&;Y+aGg_*m}_KblCE+^}yB-J6|};REMsr$=Dg?uA@8^9Q9F0ImJ-#Nm@V>PT!o+fSM={X z`mH#|fI9mB07j4HsRzrG9%D=$ge<07)$Et^Wqp|>ge-g>p{QMVatQo16x1re5sR| zbLtrDRS#zDjCrY!`9^ugd{xIhB#t?)j`?f=qto)R<>8n!>zF&G-;Dm4SL>KBr6=aw zI_6Pv%*l1kZ37rRmWM45+vX;tzo{qYv^wT6>5RFqjyX&mb6_2Fm^kLfI_5BO%$aq} zVPfk+ztdsM!`1^^KkR(rh@t9;UDU75*cowF9r2U$iukLJxJn!`S{?D(07j4H@tx&K zj~K9y_)qn0Mt{VKb;N(t6Y*mmaiKV3%sOJV0gN8Yqu=tR+h)?u=x^$Y7_E+&OgbZW zt0N{8M@&~oOeT(4ua1~Z95G-WF`3wU$jj-l{buwZ_?gT57J6%f z^so8g)qVH=vCA*a-rqOR?*}q^EDu{Aw#`jOe^bw{vkq-dj53nG*yF3TmOOJ6@vaB# z*gAVmm)E}c*wz`z2gl#znj>Yb2mMZmEl=HA59!vg^vsv^(9=)3nv6YBmVTE#%GmEZ ziMr~i-jFf#t>t0M!{L`UerYn_hA-OoUHGVNpGLj4@jEhRzO_7Td3Z+l`&;xx{j^xZ2$%vz9s+GK2FE$F_?TF`x* zwIJgFGG@NDJbtu1>8u4AXPV5ntOY$5u@>|g6@9-jjv-^_Tg$_ihi7EJzeNvgL5~Bh z1wB5n7WBBmTF~Q()`B_CSPywQ9kx7dJ+Sq|&X+o2Ey%pnWNc$C=(<pyw>sg3N2k zn9*r@*zz!ILFUaS^DS#Z&#kNlJ?F9(WL`$b%(s?@Ef3Gget(M|)`FhbSPOc-V=d@; zkhP%aN7jO#H?4=foDN$awjS8}VdqQTvKAzcBHfH_tOXrwu@-a;##)d#4H+}vS{}AM z`dJGS2a;~)Th@Y(6BoQaH?Z!Hg79=6R*Zhi~17Id7ZwP40?tOXs{u@-c^ z$6C;FVABStlb7WwqxFz({h;%OSqri*Xfn337WCSIwV>A&tOZ$jAYg|(p9FRTT< zuCX5Sayo2z*m_{=hn+7>nb6f_Y@^(i2c|wKCrq7DUrpv)%Tu40Cmo;Qk0$die#0Ly z{=`o(KBw-Q%(s?@Ef3Gg{-z%4j57gQ}@&nj8CW|*m}sz>9FNt>w&Ew zcD~dJeU!e@Wc1UI>7OwDn|=#32GIYTj84nLmWLT*7+;#qw~RxKFEHa1;||Oi##qo~ zzO_7Td3Z+lH}xznhph*;e%SfK#8AX8O-4U) z7V#5I{6$;^6QdEUHJNWMPu*IcbYei_zb5l7aU$^_O#Db(2oqxxt2LQ#Ee~5Bo{{}c zJ*)*4lZAd_H)1mM6Vnls!NhvRWH2!xG1=eR;B@k}JZwF%^~25=W=%jW-emN%ZeTs2 zd}A%hIssums|$MUe{u_67U`-Nt7rY~A>`n1bkzYkz^S{}AMY@3@boee!%Khl}?BhLB} zXZ?t?e#GfV+3$4nvOH`(u=T^v7ta1wHyJy#Z`N@3S#gd71DJ0uPu*Ic^c-iT-;B;2 zTcjt)9C3~V0~kG)hb<4!$o{6D?C;W<{au{>U7Y=0oc&#FJ>=zd*z&OTz}62tUpU8k z)q|OO$hk&&CE{{ob#7B=Pz;2Ut;S)ztdsM!`1^^Kkd!=lAilfohD;v?um8a+$$63p4$NCTg$_i zhjV|gL%wEo#`w+HAw9X*Cyu#-{lfu_9?Qd)hi7DeQ%~-*NoVe}iF2P#ocnCu^zJ^J z*m}q-_x)5?mREXr-%sh*PrCDkGtN|dGgA*4qspflyNWX&9>D0aJZyP5<8A3Tqd#M8 z>B-nzobm7gMvvw3m*rvGjEoumO+6X+N@vEs;*5L68TX1a?iE`P`kfA29=0CX`eEk_ z=Xyu=V8+f|b1AP}i-~i6H-OP&dD!xBt{8pO#ksy4!053&Y_5*!p4T3+MV>ZQhKXxrd;>lY0x|+@l!4 z=&?L(c{uk#q~DDG+yjxG+#3<+e#HPrkL6*@!?wA}=x^%DeF^EzeF<^yONgg-_dUe9 zFCn%b^gA84JZwGGzx9*ud`Zv!DAj`*J9AG=dF5W2IQQHJFgh&{TOQ6mJ?S^2Klk*c zC-?fqx&JnR(PMeo@~~}gGWwf(a-U5)bDvF|`)uOeXA|c>o7j5L?{wJm8oRptek!B& zBjSAF++UT989Q^2S9#^$uQ>OU2QYbA9-WqlbB|j3&FIfPYU#n4md@Na7U#aPIQNakxo<4C9`rjMwmfV-u=T^v7tZqn)q@#3^UOkd?wDiTdIES~{bCIM)_O{czqbj{4yo zTpabo`MB76(C>8mujOIuLB{%F=L^U9!@U&MgBd$x4CL;L@`|yMJ1ycEW4ZS-fYD=l z*z$0U=iIB2elz-G4Cn5R^u*ZCog8tDx7^zq!053&YcNbiF{g7EOL@gy&mAps z#0=cy8o=nWJpQ#j=@FlBPfYsF=#Q9$yJXT6u?lz0#1TJm4{ZRW$MUe{VcXnf^f&cH zoWMOU>5Mpm`(5IQ6S(&!jyQq)VB&}qxF;sI9`rjMwmfV-u=T^v7p6?;YBF|GZps5w zACwcO&Zw^@^R4A!%ft8t-!z$T@f-et@h5(Q@i}$ZWPE3N^jIFAk^N0Q)ERYzPU@06 zf~jNb2&V3-BN(4hN3iu^gVV{^^04*5)(<;hm_AD1Xfpcg$MjE_{!PDy83XA5P3Bw6 z!@d1n; z%Tp(oCq4F^xR);dX7tBi6L;68C-$JY(=LvEA@02oVDwlXwmfW`n~eUZp4k84-newe z{tx%b#j*dxJ#%sF|8W0Y9Q!}qOBY)Y`kfA2p7L4`>DCWBUzoX_Ikm~y$^6f}4igtJ z-@~!D$vcPv%(s?@Ee{i$5Ti61J;X1>B`|Rf@d`}rLk!VmzO_7Td3Z+lH}w!ZC{_sl z#1zB|=qJ`7R)C2?h!tRB6JmwGwZZA+YkAmuVC#pSFU;N;ds0nCf9$1q*cVg2v9HE{ z8611{9roRtj883(9`@mohvQtJ!yaFg`8Li1I_&GgaYoQ#zYmUm`wn|>P3Bw6!L-DGs8FWPYWsLNfy4`9BvJZyQ`HaA&18+x*S zq%-SBob@Bl`VnXSh|`a<-|3Xm^5knhu=T^v7ml{fy+OrYX6)o_kn+IMHrw7S=4_C< zBi)Q1%VUG(Nzc2ES`V7}ma{?p0dqEppJ2`gskjO zF`qS=Z<)uKpJ2{qYck(j9=1Geo15JH7G_Rk4uhHN zn8RS^K;|%*xsf>xX3k^|gKZD`oeo;o5wm)&(_z31TXiTB<6)pmRD6U6t= zeN}tt*A5r|VE%2}FP(Fcc%=i*=-+q8ubKPIA=9!Pee*lTCw+F`(z#|1<+bB-Un`S`ju5Z+_CSIV3>E-aq3)OKasj*E()`Q&D0)WshapF3)! z@~uM_7r**=Uzz&oSn(a_bXw~_v5feHJ$GGl__ND7z3udnuPq;XYU>I8we?57wet;o zYTFZb*0wY3uWf&nt9H4fytT_4^-#MW!WXrD5p`9&uA&ZW*J0Fc?YfORuU+Tii`u>j zAJz6z_^!6^!l$);8osXWYwBUQRgaKg-alnnt9|8>UEh7{=+;6@94Ef$?3-KfZhxwH zu^a!|T4>cDh&MWCWO;Sdi^ShrfBCZMw%xwG(G3&JtWS6Q?E61lr?mFHFZHZnT8BR? zR{EK5boGS%^{37%U!dpoFU}=K|2kXGFDBm=cN-d!LVw%(Bj4KjhCOx9o*O3CwlnOnTWSAAXRlv3%2m6(Q4h82 z0X@C?3H`1&@^yV;kLwvbUH{l`zcj~8^Q!Y*)BaZ;(>%VVof`LGkB6|wN!a5j>~R&2 zu~*}5vc}<*(fAB|+=e}#!ye~h*A?vX7WQ}xd%T4`-ohSlVUM@4$6MIrE$s0YZq|eI zW$bmnu=9nTFYJ6_=LlBJNx|q`Wfd=i=?x8dV0La=rM*m6s~7?02hp*|8rl*RT0|@l$uMsPT=w zNbmgmwVwRCw+-r$j-LMhVPf>JH)tL)`Ht9gK{58cK4p{`JMSK`s2KZqo#Ufo%C*JS zU5@mAr-yvo@}Z|~J)ysC{gH3&e8ZmF_C&dA+Zp!Pwm-_H@h!_$yS&J|9?;|ZLBH#b zd|jW|<9fzU*FW~#FHL_vJLMC=0rO|BQ% zvU{#~#|qcg5C7&js`JaIUtWLzgznkg>ib_@Uw_%JmHvlmKde`n*iGN=yh-(jXYjmcfLb1Z+`2T`V&*TZR0ERf2Tg<==+ua`^^rl$1eV;_`*6*RZJ@aAMcXKDlhJ01+iJ9>;x-&@thjAQ+beGK(I$)gg7d{5=L~c$e{`kkl_y6(Edb@d_ z6o2;q-__gP)qOv8!z&NhCvN_f();Ips-Av9H~q;!K3~^2JfZX>zx;B&#I=u#mznT- z{nig36gw|$a9*(Uf}I!aykO@AJ1^LI!OjbA<~8K7{(8QN_p9v3{rReTl}+yz@9@UY z>aS0lBL3-}7uJJ6(&btH)Qvu z68j|M^e*?w3Dn`G3n8+3hfGx`Y-l%_@%fFguja0 zM)GW^@lb0EJ^WUcX@9>iD zzrzbho9er9>&b1{e}@{cr#sphd1T*cX(m{om|*|KNt4j)rG^h_LnX` zO?jEI*|x#94YqBtZG&wa9P#`T;m>xa%eIu4ZLn>FZ5wRcVB6EQlk}*6{hmMR=Kou| zfAb%C{?4-7iT{qX)A>8jF!KBz1ncMTBQ%-3tP{3Q*gBn#PRpYc#^%4L(|^C4y!`jO zVgLPZ*nhtp_TTS@{r9_*_4m6|Mt{E>_TSNl{r9zD|J`lae~%lcoj2?hW54Z$Z6|Cy zVcQAYPS|!P%g&UMov`hMZ6|CyVcQ8e>(jPnx!QY7K3l%CZKT^a*tWs8E%~2bhm1>Z zR~~c7%VQ2qy4xr6e{URXjwkM?eCvJ+yPv}Dr?C4e{6UN%?vLnqAA#LRVD}NH|Gj>P zZOcBlxqP?D84LEUdGTiAgEl?A@0M9UC0_Qq`}^))a}Dv~hs@EM{>YMI{^h^X&;Lgb z<~zQJ(T84`d^qoIr1v-E#i>V}`rF84zT&h;oOX)SesPw|>HT4c<@>`vap>uf{KTQZ z9r=m*m;WYT{y%bQXFKu}qc8FkN4a#T1DQs=lJtF_* zR~KvTaQ)E29;|u4LC?3pu;x~+qaL44=@;F1Z0qiCbb0%=E^L*PhbaBFqi<-vKG$60 z*&cbQHF?T>;t}7R)*5=r=mFf+30o&@ov?Mn)~WQ{mM9Ou`B1CL*gXI83ztPNzPSa@ za^!sFysdsFeq_Gk<=kJNCSLO0VP*OK_7HFOrD5faxmOmCUwzKQTuK(~$yWt}-`mGbTPS`qO z>x8Wnj`G%xvWrQNved4hC}Zt7&2zkEkpXO)25U%?LmF}#5MPqpKtP{xUBI|+5Jn;iwAB0 zNE!FkH1R$QKU%gs|84P6J3UgqvGSk_Jxi_oQ2EOKvx}$Qbbndy+jEGYp5?b?%nBpK zzgYN=^6cL8il15S<}!Y{1;n-o+nf$t9=0CX`eEk_+aB0Hq=wlAViYWvjoV4Ks^ zX34|W16x1rd|}%I+fLZ_!!8%>^1`kM*fwO_lbxiyUpE<^@=`2{JWEC>#^T6-~aFJ(Ei1q|H-)Ou^K%eKl{ghug*DK za~CNf_SCw5NFwrGECJ6D;zUEBU+wr}^! zMY_w2yz2oyt{?Qf-pJSWi9N1o>~#HOzx@*BD)v{T7pI4Ov3%$$))V@R^+&$N`G!5k z_Jp0qc82}M_D8vj{YARVi@fUrJ@yy+?Jx4Rzp%&t!cO}O`y2i$_E-3^mmdD@$%o&2 zdZIn_^hZ1CNu;pRvfvq2QzOe0qZ6|E|VV4Vbd12QB?D~OSZ?NkV{?idJ zwqJes2-$BYeVK18SU>f0_wLXt*T((fmCvb3|H3ENuNU9*Qt_?d|6={=Rci5F6SuFw z_K~~AXFah~z2Nts6gTU^Oubn@Z2hqH!`2U5KWzQ5ZHA}+VoLkUr@yVT%ys5;=5PzCSqdmi8B~yG?9+s4J(#mWQnewtm?8!nOyt zov`hPT`t(=gZoPr?C4k?0yZqzr!8}V2=;5#|_xy3G8tO z_V@#DK4$68hR=Mhzz;w5@y=&IJ4pP<@8g}?eCzg+zRNQ!bTbccz9>xOZST(-gJ6B^}$)xm)&R4<9-3VzrgNCu=^M6eh0fh!tSTA z`!DQ%4ZFX?9tU8L53t7#xY>8y#z_BX^&__#bh<6UZey_99_%&=yRE`*!?4>n>^2X( zFTn02u-E?ZdYg}^Z@l{VYrxe3!|Ru~Ikq3(<-DQwYwM4dueW^Z-S(&M`9|08`#js; z>7on8-YY=U*KC}#V=jlogK0 zjQm0S|4EFVy`FkTjQ;Y<<6`n1Gvy&M_Plvfx1D3>(v$90I`$v&%PC^Y73V49QCGx$ z&rE;#7gzV>pIyJ*(=&3l8+-aEY^1`kMxM`c2^l0Xi-&%ZIYv^+1znA7rn9b-|;^LUJPEypLe2Roe(TOPI^*!p4T3)>#pcEYwF zcDZ1e7j`|sF(wzserD1mJ}HiWB5o;;iz1#Wj+Y|NDUPEe{wa>HVmvR7yP9P*;}`3P ztsl02*!p4XhpivB&2Y>$#W8KnLB+9d%uU5HaLif7v2o00#W8ctamBH8%zec%cFc*z zv3Jas#W8uzp~bO!%&o;Se9XDUv3<|FHc6+h4H#2;0A~{SLc5z-}jS#D2xGU&Mr! zW5S3PE60ivLspI2)))nh(+dF+KfCc_@9VUOXk$9C9b zKJ2*w_8b9w?tnd~z#iLSkL~dPl1ri&)Dhu$A0_8{#tAAwfgNZ z*#3g;FWCNq?JwB=g6%KZ{(|i^s=LgY7%G=`S-rweMj24z}-L`wq76VEYcX?_m25 zw(p!iv)}#q`rTZs&#AuL9(`#UF>9A6o_%?_aJM;>e#U)Qm816@CVu6@Ys*$6hl+pn zN`LvzzO#$pIk!{pJ*GP*^i7&v#_cgk>2ut1L%DPF_cR6$S>;B}Yxs-w?+t%l>Bx^h zahe!ClQ(-&jQ)T7&hujOy=uar)S1!_BUgTX5 z=yCm^-}Oemu21Z7J!7ZqAN%c>D3|tjsKe-kHS--DeN%f2aP(R2Il$4EwHE=$_^dq& zIL2-5UBK+scsyqh$K$;Bc90?6{R?@|Yv>^kv3}wZn0$#tVC*3dfw7Y~1jc^i5SVfi zhrlsz^wMM8=*h>p(bE&-Mo)i?8`|69+ZZ=`_Qbf+vopqxp8e!Qe1$yeE-&(~2lNn! zAcKD55SV<4LtyM74uP?gI0VLi`=#kGbB>>q$#GTR!uB0(-@*1BY~R859ci2iteBeFxijuzd&HcTRT=VScujVGjgUPIpV8hSjhq2Kcw z`FdW%9?xso>3I$N8}nN2c`fF(t+{L8^?yEJ zd}{mYz7_X8M?Cg`rCWbm_Ehnu?{D7v$*@Dk@oy{sTO9wt6>{SEt`*<+qciliLa#XT z(LLuzdLNwf;?&b3J@tz-Uvb(aPCLbEzc|a~^nUC>Cw7q^jJ@OsQx5XWeB0y)Q*QEu zsSomlsVDM-sXy*-H`4nX^5WFfCY}0oy=A^iPkY2^r`d+Cz*y>ZfgpB&~sJNd!Be-8UzdLzBRAumon;?&V#Ejaay zGhcDqBThTT?q7VH<#M|E7wOqfYLgM=%(bSjL0+Q|A71{j-ckMV*}oiG4qkfkHe42duXX66-w^M0;N3Sr0Pj@ATu=S^xgL(%0W`pH_Q~S!&WZcwoWSEJq9z&%e`Fed8Y-E-sHO+dpRE z5#q0Yc8>OI>&+n^vHMrri|#*2e9qU;X}@&mpSm`D>{spG9=S`r?)p!)FM0J6aeenY z?WY&}j(C}&L+jJVEGK@j8eY#oev-;^>sLn9+rRxED&rpiK4*RE-Y=-^XC69hJ@=nK z-@?xGzVS-?g%i#Y-~Rf2?WeZs7tg!VmF?AUendQJ@8jDmPkBRp!ZKBR>215dnCs=q z{fF+?^^xDxq0{f_;D3>~e!X{yertwperpE%tr_gMW={Wm?=k((6dAv*gZ;J+_S-r* z*3f#N3;S&y?6-9=?LXrFcBcQg-@ry0TQP2`4e%b&Z%F-q5dD5X2>bmYjJ)40|FiDu zM1SesowH8POnqM+-teM*+sDm2OMw@7^4#_c5C2hbd7iyta{Km0r-&aJ|5$smW3Le3 zy5H;VH6J`tJkOxn>d)Qu8L@S;CT+ft_($%;TOJ$2&ffd1&|j=S@{QjM?&cfzv}{k< z*|MEsf6Mkqxmqrlbz+;x5cq#`)@D7}Y{ri>$I=h)SZY6}Pt|wel^;B>J^sGu+wkPa z_iQitomq7M_P|-@YY+eRF!7@stk*y5o5Rh0=8$PwCcbU?+tAsv&b%jC(I(C0^r z{u@2~f8?YyzTFSX^;MzJ= zz7?GIh{?zGPd?NmGEHCSoeH&wf8-sO?zq{l;xyE*q>dxN6E| zd+Xi*`JnG_q@DWB$!zE17s{#ic884Z{ubpfE7kjLG+zA6z4mH9R;^@inRnY|rDB=* zw)k7?q+C%Cz4sR%^gUwU1ld#`Z!hUNB`wb@Sx0$ftY{Gua3HyyF+-REOoOMP#+VWW^?6XeT zXPvOmI$@u6!anPSebx#4tP}QGr_x6yQ3Hz)Q_E{%Px!4ni zebx#4tP}QGC+xFM*k_%v&pKhBb;7Zyt+P(pXPr)GPuTM83Bx|?gniZt`>Yf8StsnX zPS|IiaMNFA&JOH5*uI19JJ`O1?K{}MgY7%mzJu*Mr+YsidGF`jcgWaxuzd&Hcd&g2 z+jp>i2iteBeFxijuzd&Hcd&g2+jp>i2itc}_kKR|-p{x1kg@Mz`wq76VEYcX@8G7t zf@}A?kkOuh`dw!MaOl(-0UUYh>;MiMbfy4@Z8~d!Ia_gii!$nLf^?t7z@)q1A@6>N z9?oKrK|g0PF!^#817isVoXDcxFa~1i2iteBeFxijaMNGGdRvW8{k9tR z+iKWvt6{&bhW)l0_SwRyt%m)!+UdNlwmfgEVZW`0{k9tR+iKWvt6{&bhW)l0 zrd+(OhW)l0_SwRyt%m)!8ur_2*l(+0zpaM-w%X~ut+qUGt6{&bhW)l0_SwRyt%m)!8gBZ_OuTL1!S)?&-@*1BY~R859c(80|5@5`fUU_^3rc6z|ns6TMBTrEB(d-?BAe({Tmdpe}ls5 z?sv$$-=T-!G(ZOZ{H6g+zWk;Ej6M9O0UTx2Z%V*XM*Y?VOu5|eqD}VFqfPeYqfPeo zM4RmCk2cxMH`-*+o@kRjJEKkNHz>#}+9dnS>R+V0-y!dQhaP^@0D1KDn+7oX@|y-Q z_VAkqFn02r1~B&Xn+9;xU*`0$WYX{Y7PjwT`wq76VEYcX?_m25w(p$oerMm2Zr{Q7 z9cuW+isLsR%a-3BB|hV&b;}L2j~37S$5qRGZ*d8ic0P7;_wTw|KlWHZZ2hqH!`2U5KWzQ5 z^~25If;MAA^Eci@zOp@`r?Q=)zq0+2Z{>1@J(bHFc2=&3u)lKsSby3h{b{H4!`2U5 zKWzQ5^~2T=a~?G8>l=1PZF6qD=!0{VRrg&_Jm`jF%E!LdCm#0oTgrDI8!z5<@%PJ8 zLq>_?-zxsQ=G*xHRmh3syDGjHhrTNGiX)$jyH&_%dVy13oO;BmU!3_?$frHxv{Rh+ zi+6Z-$~f{vp8UxV#xC+pJ+d379OMU6KJtSpH~GQT2l>I&6Zyf^-#+utx>O^*Zpe#M zk2v*^rm|^Zm6}ul};Y^-7;`!0OfU@rc0`v1S3fqd)3;7_ z`zJqfeS_D4(>BTEx8l?(&b-8FgE(yyr_JIli#W?D&N>liU5T>}#aXxFtaEYtqK(bz zBXRmpoIVw&uf_Xy+kiORhB(_ySEk#R#M$=5*>1(z_QcsH#o2DvFS0!=J=?jsz1M_l zmqX{2%y!pIsLIXVv1O$fCsZ%~a+uN|d~B8K?gvJQcQ|0>YTM=K7Y|zJ6II{V3yJ67 zaHZAo7XNWzI)V))uE>^FP`-06{`2o`-J#+bFWza=E{lU3lCbc8u`7o z#H%c~QnkZJHx#!Q`9yWjA{&dZ{?y9V!8>m%e&?sFREIvWxp>aiCRBsIu(f#2Cs(W9 zp1iGi$z3N_>%O#$`1{|QSbcBDoy992HnDo`?w!PU>^HGmVXYm-f7o zSe^Ez?Zpc`wR-jOCBH0ge|Poj-qBwYKfdPb)pHwfC*Jp?t5-L-4-oHp^6J$`4&G1v z?mMejYfRWv{GZjT)d?$pOFZaDt5&m~)8*r5olsqTW0#lOZ9=udkGg!`Z4;{3Cv^D_ z<5sKYJ?@+OcJP6#RU?0Ruz2UrYSp3N`iA(f*H^0!|M)@TD~?;adaTuzS>V={s`dBm z%FH!*#cIo2x_rlmAFqD8QCH_De>}c=_}Opk+ea2%zS{HF!^D5RY1!(k1&gxG^Al_^2GS$R&&lMm3v1O`1Pxw)n*I%Z3`IH}uFI#(=YLlnCG9!PwMD>{$ zu2A~FO&nKUKJTUCzU!B&=3D+k@jefYtv>SZFT`(sY>DcvDP11E{}R!ja^1D!7e6<;dS|PC@nKspTs{AVj`;Qq zM^%rUd4u>T6Gv4$&VIA_FAI*UZaV2!@vW^<)p;MeL;UWgqpEX{yj%Re9T%?Vy6Ly# z|JY`9b$tJQ;v-I4q&k0#2gHAvzG$`iQ4fi~f83brgj=5wA5xF07GJo_3q3KW+I8E< zmHw$|W2)WGd`x`&%VVm8Zhut##G_-XL9-=aH>Uc+Mvo}{7e|h%_Wi-b;=islrn-M{ zmvJU9Qg?Roy!8 z^GaV})`hFH*X;72c3rr-<&#~W_s)f@*H-BA7d|$+di#~`x91-Bdh6~KP#OZKC)ode)MVa{!1-To$+$lo+WpjuX^mvE+2gEJk{`fy8QE}M^q=D z)0IDe?cvo!Z+6Ra@#HzH(;w)Tanv4jRClcKf^?4Ccv!W=OMem{z5CGW-)4DPyxE;Y zs*u_JtD<1x<_}{-Wq`JL+PyEuEL#i7;-sRWh zcQjW!=3S-7|1Tk@IAot222~F)G@Cg7t>VAMp|6BqaePl=O7s(P z^qca;bzP4BRH9!gJ^ERR{w9w8SE3(^qhFTjpW^7RCHk#6`ge(bE{=X*qW_CyJSZ_P zh+~{6FFyd@3ah zWr^`l9OGY!aZnuNVu|rl9OGz-@l+h+Zi(?%9OGz-@l+h+Yl(4I9OHM1aa(VxCZX%o`=<4{^*VCFT`z%rhnC8*$7( zCFUV<%u6NaCvnVICFU)0%wr|yGjYssCFVJC%zGu~KXJ^5CFVtO%#$VNOL5GfCFW6a z%&R5lS8>eeCFXT;%>O0g0CCL2CFWys%+Dp}X>rWkCFXB&%;zQMb#ct|CFXl^%>O0g z0CB_xCE^2d#0w?j264nSCE^=##1|#v3~|IACE^cp#6czEA#ubhCE^uv#4jb{7;(fk zCE^=##5*P89&yA$CE_7*#78CKByq$|CE_P>#8V~WDsjYLCE_q~#APMoGjYUgCE_-5 z#Bn9!IdQ~yCE`4B#C;{=KXJr^CE`MH#EB*1MRCNBCE`eN#FZuDOL4@TCE`wT#GxhP zQE|klCE`?Z#H}UbS8>F-CE{H%>$!-J#S!P0h&K9#SjJR3Mx-jBt zF>Aqy%f+k(BmNe%7L2%D%vvzkgksi$5#Nhh3r5^8W-S=&0WoXASSN^C3E%vvzk z6=K$cvEC4~7L0X>n6+T6PsFSRW8Kn~kF{W|XT+=pW1S;rEg0(`F>AqCcZpdG#yU;R zS}@j2V%CDOjuNvLjP;e6wP38f#H z+f1~jw%by)y|&w4wAHrTYP7w!+g`NEw%cU1`Pywh+Hl)#INEmnPFAE$A_mwV=l?)`A|>SPOcrV=d@0khP%4M%IEJGg%9IEM+a| zF_yKU=K|J(9+O!MdaPzG=(&TnpvQLBf*$i(3wkbKE$BIdwV>w?)`Ff>SPOctVJ+x6 zh_#^SEY^aa%UBC~j$y8)`FhvSqnNgU@hoag0-My1J;6$8CVNCCSfh;7=yK-V-MDXj$v2}I#yvV=op5z zpkp4^f{uk)3pz$(E!c~lVlC*HinX9)E!KjL!B`7AHe)U5n2oidV>#A>j`3IvI`(5N z=$MeTpkqbWf{syH3p%D{E$G;iwV-28)`E^jSqnNwWi9B~m9?N_TGoP&by*8K24*ej zSe>}NiM62DP^<;Lwqh;l zH5Y3^ufN*S3_;YhKoZUJFwnUL#XaUOQ8NUQ<)AUTag|UW4NYug&p~*X;PsYkAs> z_Yi1b-gCguUi;&J?+MT@yjMVb@g4&0$a@R4FYh_f?z|U4d-NU!{l%mqLG{U$MtUKl9!T{m*+c^h@v6&|kfWL;v=k5B=VIL5v69 zBVwHJ-Vx)6_mmh{yw}8d<2@+GA@5BwK6%fIam#yIjA!2CVx05d7vrDz#26R7SH?K% zy*0*N@5M2WdT)*K)q8G?-`>+>JoX+P$&yab;dx@G) za*vUD#(R&^g&pwEYiI1sU;#{A75dZp2g!q~`8yVtd;%1mQns^!}9w#n`iMxrvVd8P(a+vs? zI36ahC%%V?_lf%@6Kg@%12F3Y)(J4{2G$QS>j~BsFzXD~8!+n+)*&$K64oa$>lM~5 zFzXoBGcfBL);Tci9@alF>n+w@FzYkcX)x;~)=Mz!C)QCg>nhe)FzYSWT`=n~)?+a1 zGuCM^>o(SJFzY$ib#Ug@2ebZT9oS%<6{c;H$#2D}Q=EB;(*|+cCQh5hSr&1YQJi%m z&bkt39g4GV#aZX#^hFE%(?{a;oj83ePG5^z3;K*W+lJD!&2(kDZAqMMPn>O4oNZ5> zZBm?VzF=FnVWnr=7H1!kO!ftF_7QRRDRK5SarQxR_Dym2S#kDdarSX>_I+`V3E~_p z#5snDb8Hdkm?O@yNStG!ILAzJj$Ps$)5JN}iE|7T=h!IDF;kplsW``2an1$e9FxU4 zR*Q4)5a-w~&M{w{bAdSL2yxCG;+#{&IoF7D4ie{_CC<4_oO7Hw=RR@HiQ=3q#W{zH zb8Z#qoGZ?`Se$dTIOlG0>Tu>%|!xh%=VxayK>*XUrhZm_(d0hB#vnamFy>j8()L z!-zBH5oatU&KOCYv6DDsDsjeI;*7z>8JmeSW)o*DC(am8oUxxcV?uGpisFn>#TnCz zGqx0G%qh-TRGcxYIAhl?cVk*{#=7E+fyEiCi!){xXDltw*j}8mw>V>RamMQ6jN!!@ z+lw>i7w1|)oNEMet|`R1))40!M4W3Aajsd!xt0;<8b_RKA91dU#JN@y=Nd|!Yb$ZC zxx~2^6X)7ZoNGOCuHD4BrW5Cyv0{AAHJ~`xhT>dfigPU~&NZeu*QDZHtBP|CE6%m8 zIM=-5TnmeHjV#W!vpCn(;#_Nsa}6%ewYfOg?BZO@i*pY_oO=%9T>Fc2Pe7b|1>)R8 z5a-^4IQJaHxfdbMJqmH|rHFG+L!5gZ;@o=?=iZ1o_e{jOmm9g2cH;B+k7faqcOJbFWF9dr;!sn-b@qm6)|)j9=p1o}M`O=)}2qC(b=Uaqjhra}Q9QdxqlNOBClGqd4~-#knUb z&b>-;?qP~^Z&RFmp5ojK73UtQIQLG)xu+`5y;gDV@rrX#Se$#a;@q*-?i1RE)oM$xRJkt^9S&ul+fW&z=B+fGoM&+2JhKz$*_k-c)Wmt#CeAZBah}bI z^UO}1XL;g0;}hpuq&Uw6&72jA^XyWbXN%%Ia}?)Uq&Uwg#d&rq&NEGMo^^`z3{;$F zrd^rtS*n=(wy`D@=h>?`&t%1UR@;^Dp5cnacbx5t^UPPAXTf6Dg4`J;9>}v}ah@rQ z^Q>8%XVc<5%NFO^v^dYK#d#(!jyB90w>Zzf#d(G<&a-lHo}r8L%w3#k@#5%%oY9N( z>|UH_`rHHT@-QNQ4!~z7IEHn5$7Ekao&v)=bagG-lY-e9UF1py%Fb~9C6;&5$7Eq zao+6_=bayM-USlp-63(_H4^9DA#vU*66c*Iao#}^=iMZ6-flgwSc|(@;=H3J&bwRUywfGlyI$hF118S9VdA_qCeFKL;=IEq z&O2}7yn80jJ89y)t0vAnY~qMrx!WerJ8$BMb-4>C&O37AyvrxfJ9Xl`YbVaTf8xBG zC(b*2;=Icz&O3hMy!$84JAvZ7D=5x8gyOt&D2}xTcM-*TM^T)27sYv}QJi-j#d!x( zoOdI|d1q3bcPYhr$5NbkFU5H$Q=E4-#j$qdZl^f!f{OEQr#SC?iet^lol>n0^Ny&} zV{ORYQ8D_^%N!AFN$#48V~xojRB^0HE9^if)~eiP6~`KuJFenb+j93+9BW?g#ESE- ztT@)l+@Tf6+L^nx;#gC2=T;nRZSLZVV-3z7U2&| z;7+nQ*8bcL7RR0dcZS8WSHN9jaqJ;*$5x$DRXslEtwX!Chr>>``!sSsZ&Q z+_e_Ro(6ZG#j)4HU1)Lay>K^M9D5_&ofgwS=qHpV&Ih?`-R15bY;o+pa5q~VdotYF z7RO!?v{QTpW8%+(j419u#-f z#j!WV-E}eJ6XO&%vliseC>(oS+<_M}&N1GR9(!WknHR@i8F%T$vA4$EdvWZ=aaUg) zdu!ai7ss9(ck;!tr&lqKqcisCxWg}wy*uvqi(?OvHv;0=>*FneIL-%oBOs1FL*5jK zV=s}n2IAOb5y##yZ$refC(N4>F>wL$0Xkz3nKvfl*z4vkj5zk3d6OcJy=dO5h+}V@w=?3{ zyXI|+IQF!8^CFJDZr;L(V-K7+GUC`9=k1I*_RM)xBaXdv-r9&`kDWI-;@Fet&5k(s z>Uql}jy-(d_=sa~pSM5a*z@O2kT}i)cq=51GXmZaiR0{mw?*POQ{c^!IL;b)izJRS z2;L}(i9?A;sjE1%;7yY_&N6uGB#yHW-bRVzyo2{p;y4H4os@Xyd(ZKjcRnodJ)8b| zantLT9Dc^9I*Wh*{Cf1P!^=mG*id}xQ^%EA_Nc_e&$z9eblM8yyG|Qa_3b`d9RF7F z-{ScHRmj!oiSMfTUL5+W&?}C7^i~&{OfL<2aq1DL{tB7QSDf~U(@t^PFCKfv^l{|J zx8zTLFm_=djJ@QS`a9$YQ$F&8DL47S)Cc*&)D!u^)ZayCufJ3yy>7^hQ;#_HcaWj} z`0uVB*&|Ln#c98|>8~bd+5PQI-$mX2EBo%UjsCC%?S|h$weR3;&q~jBF3$EZrk&Dm zkf;69j$!vZ*!>QsANaRw-R~Om`t8=#BToGlGMTS9?GdM);Q6ziXts9_Xjy)FV#)9pv5bx_Y|(4tBqT(|*Y}{ng}| zz8fun{VV%!=I=s(xPBM6t?7L^M@1DWF(*^sk7wkJ=uIYQ zAM~9%`<;3-Q@73+_FX>Mclof*clk*7T|U@%`C#AWgMF6|{zvYirB8L=%*?mGs|NcH z8*H6$mZcB&Jw4d>^kCo9gMCjA_B}n=_w-=j(}R6ak9zPuJ<@$o5B5Dh*!T2c-_wJ$ zt?F;QHOpxG@r&(;Z9i=LVcQSee%SWIwjZ|ru$V_ptBe!@jEz`wl&* z1a@7)u0z;$3%kzY=DPqh<@%uC2sCXl<7?-O4St&d=RMLI_S*#5Zxdj@O+ZiHQW( z0rtBF*zX!(ziWW~t^xMD2H5W!V83gC{jLG_y9U_r8eqR`fSYw_`zf#OhiyM>`(fJ; z+kV*g!?qu`{jlwaZ9i=LVcQSee%SWIwjXZVZ>EeN^c$Aun;J9i-0xhl!S7#Szl(wW zUIz9%8rbh^V86S8T^87RQFb%=&gfl_#}MSr=<(Yh*x$nc$os+OJ4AEyTkP@ML(={B z5cZos*l+z{zX62(HW2okLD+8z(eF2gr2Fk5>^F(9-zvg>!wCCrBkVViu-`($ej^FH zPRQ3xeOd&I`5;ux*2FGwia!E+g!+!>$w9bp^W)Vb?9}I)|I@D9x1dgML%l zw87lW7xr6D*l#&uzvYDemJ?t2Ehp)I%L)4}Co=!YJH+O@MKgN*RuT3aM%X%G$5+&? zne-XGXY{woo00dM$L6=N-#>MQ^pVa&2RG!vYCASE*SQEVc748VZSei{q9(t?~&nryPpQFb%w zGkOQ@F$8%t@_sAb{FZi=cfvc!=iP5{-U%1yUGV{o9)An_TiD;CKkwmpNY8un;=Cs> z&U^CWyeBWtd-CGECoj%>^5VQFFV1`N{7ty?^Papo@5y)5^EV=}C-2GY+q@?)ZkEeT z{a6O}xA2GMcPH}Qgvyxj7v$4?*C5XK4&r&i75?eD@^I_fX<|Cne7JQv(>kTLv5a zEo_~z^MY*yY}?Rdn@M+B;2GtcZ>eNYzOfQ}455C^=&=m!Z{d8Sp>OjohB)77h?~E2 zWo~{8`&-!G!uc*n?J(c1i1XcwINz;^^WBO#->r!A-HJHht%&p8irRd>TTyzxTM_5G z6>+{>5$C%ValTs-yH2p*Onq7g_P4Ng!p;k}4X|y4Z8Pk$z%C=~vcs+u*mVWF4q?|V z>^g_@?UMXxrd;`+Na^{`NSyDF#Q82sobQ#y`Ho4P@0-N=?n&IV!Q9LjcD}Ilg`F?# zd|~GcJ73uO!ucjnHsl*OalU;M=bN|z%(s?-{Vi;r@Qh-ud~+wA`4&&?Z}Ej0J(hv} zE#pAGaZ@|Yw{PNn6DQ8Ma^ieLC(gHZ;(T)_&bN5#Bl$*8oNxCelW+RO`PNVD-xg3rd^0F^eIjG~DX;B^Z9i=LVcQSee%SWIwjZ|ruPrAa6$AGR<#c?izF6fPB6s5$78darBGc@7$WP&ELZQ7M=bU4j<_^ zW8r*vqw?mv8*#q75$C%balX3|=erwmzPl0UyBl%7yAkKR8*#q75$C%balX3|=eryE zu30WK^>-@?`jJ1^Kaz_tyx&9KV?yNs~Q4!cfZ*A?tKgk86=>l}_Y!`mzQ(Tp$h zJ(SY(os>A=Pl@wgl{nv9iSr$nINB}mv&8vsOWd@<+{_ntzOeI!oiFTsVdo1wU)cG= z`KC`cc`BtmVx~(Y@M|8m@D-=!=&fiI<=pCb0^NXc;bAcC(gHf z;(XI5&bNMQd-(=X>G?KLoNorj`Ib=f-09|w0ekZ8p*Y_pikoG${gmDI!?qu`{jlwa zZ9i=LVcQSee%SWIwjZ|ruIT^87RVW*k&d^;)I@=c}K zeH?i+@|J0S3&+~+|M`3SvF`5uZoj$tEu8PR)ZX$vmpI?SiSwPBINzzM4d**GrRO^} zalTU%=Q}mY=Q}l}=Q}lVzEczDJ2i2>QxoSqHF3UE6X!cMvFoH+M(Wctu)l?^6Lwy( zZGdeXY@1=11$G%>mmPMUz^*IUbqKp|Vb?jFZxz)x%#rDp$T~73W)5aqLOeP5d&Gp7WvKRJ@0$RE=S+b>d{^OwGRHePtBTpt+~QpVXryY z2~!rw*eZR;-iq@q`eD+E4xDFUV(j=X4?EUX>=;%O$ zJ62b6V&FJqAYaG!j^+N{1j^`GV96aLEbiA~?5Di3ACCQS?1y7N9Q)ze566Bu_QSCs zj{R`#m)!Qlu^*28aO{Ws_J^qx$N#EL9TzNiys&uQaU8MO@x@}t9g7{0EOwl-nD|T1 zC$J$*zR`j6ESxmqlJ8o3$ zxKXj=M#YXB6+3QJ?6^_c?6^_MQzzIQraq$s=UF&u!pRGc4RCCOV>6txz$qh~vcstp zICTZ54&l@-T;mh5z%5*TcItPU!j#MLywY);uh{XwV#fuGiNCMDJLWm~&8EH$;eNhw z@`aNxoP6m^$rrifm(@m&YgXGi-dXZGv-rEebL5zGl_gC2j!#!Qj!&O0O?0xpqHe>; z9rLbt(6R91zCB^|qtkyDE?))xjul)!75bei*fHs{$Fb^S$FPeX+b(v@yV$YtV#mmf z9Xl^}Oug8#_F~82iyfOUcFexGUx%@u`icE;?1y7N9Q)ze566Bu_QSCsj{R`#hhsk+ z`{CFR$9_2W!+rb1)W75L)n^>1FLwOC*m3=0$NP(Y4}jSB1BiWZfVj@Gr+(usO#hD# zHso12X~M}1jty{ZgJUykrYy*l7iABlI)`lKIy*!MVT9p!tL#QDt{bbQZ} z9u?>#RaLNLwjBv^hr%t5*-}v1h-@7#~`&|AFptL(ShpA8ByCoZZAD7to zbcua`m)Q4uiGAOf*!O^meLtAkcetsq`c5{n?`jiQn@;`CP8i#w1Ls-4Bl;~K`+;_w&ecv4??%NYaKRW$q;i@bBE)x0rt~Qk`zgvV(ezyqroo~|dU2tOG5hwQD zabn*oC-z-);_9pV-6GQT-E@-s&N^}RdHrq?I=Yey7oY0fckzjn7y7XQj%{#k zhEoof9=GPlaQ|7@cXVjI z!e>s>OVSgo`sVpoV?)J0LL~sHp3|koHD{GJDfU!Q&({65cVA}YNOOS z^73h)`d#KQ_3!&(r0;uU#J*2P?0aU!zJEsSduhbJuSV>9Y{Y#V!u@=y+vE!;UpV=q zpL~%gUpV=~$rmo4VeUAR4ZgET?7NJ_zT;>%Ca>ry9seeBKTSB_2dLXHa^In(G<~;{ zcs6@%8~V}dKMPl^kbbusdwiFX`lRnTQeXAmM`GWJB=%iNV&9=8_T5Ti-?=3AT})!% z(IocWO=92aB=%iTV&4HJPJLo??5BQWKOFnv*bm2kIQGM_ACCQS?1y7N9Q)ze566Bu z_QSCsj{R`o{xIe8{Z49A-}@x?eNbZG6D9WjQDWaKCH8$&V&6k0t~1i9-!u=CZ*<^1 z3nxwbO!9(b1037n*bJvEaPp$;Vbb?qRkF=@Scx-+pdUs*I;5Fr;flQ-vPMV0;){pu zbKr_E9z!lFs zWFG=oJo1qJ37k6VGi8qsoM+*rDIMnp#|AjI!Lb=mS>TirPTAqq37oouQ-^THN~><+ z)Hz)7wnNq#eWqL$7d&JyfxO~^hwLTbiVGgHmw+oSc*tG?uDIYKdkMJWf`{xS;ED?# zvX_7>E_ldZ0`A)o?&k|9UpV=~$rnz(^x@=-Jo&=O7j|DAVT1dj*!@%N_MMG+Hac*g zCEuipJnJjc4P`E7o$z{shjmeMUbz{b$L`bv23HZ7OzKD^}WlKyvpDvHOhJ zeQ88G?qg#2J+b?w*nL&(_eJc!J;FBk`LWLUeG#WV$t(6#-q;VvemM5Su^*28aO{U; zKOFnv*bm2kIQGM_ACCRfvHfuDhx_)2DVO`$Bs%VUV)se0`>NP|SnR$ncAppf9TfXL zosG#iI&hwalO~+J;Mf4iHaIrJDGNMZzT6|u9)|Lo^_x@EjVI9|%{&Wx?runDy89}< z29r*>|16wmVXqq-*lPf>*E3?TXT)C5h`pW>dp#redPeN^jM(cLvDY(VuV=(w&xpOA z5qmw;@a}j$BYEls`@_^vbl^M-Crvnc!Lb33ZE$RcQx-U7gj04nbpofZ;M5_Ux`k8c zu-7DNyD;VQx=8Z5affH$hHyV$>OA=(_j*kA@Aa5CcZZ^ryF+2G$E1_HLy>#TSGlIU z1JiqU>4dQ-_hgbzp6#cJ&U9-n&ldyg+;fe%Z%>$XqC@(57WQ6GeKPlsBKKZZ<@Fv` zI^Nq#?me&AdttHn$YSrE#okkkz1J3d4=(oJTah?A@;+uACCQS z?1y7N9Q)ze566Bu_QSCsj{R`#hhsk+`{DEfxNm=$a(RzD?lW`Yj#=*olzy0Y&poto z?x%%wZ!PTozS<@C+#=8Yw{Y&og;N$dc~SN-a_>iEPygQCj3MZU(T`65S=eW1N@u$J zy?yQ}oiKHtXGtf|!nqq9_8FYY?(;;k&lANyPZaw+QS9?XvCk9LpM9Pv_IaY%=ZVty zd7{|oiDI88O5f*+lKVVS+%H#{`iu^oXW^s?CoecQz_AUE&2Y*Br;KpQ4yR7w)D@gM zgj2V0>Kyi&pxQ1>+s*Ae&-*rn=?}>l&Ry$p?plX)*E*cL*5TZ>4(G0QICrhX{${1} zPIphZeL|!Y=GojO4(C}oX~J1wQMX~_)7>|oXVDL%pF7F>&%*Y#P(QR!h}ga&V*8MY z?OP(Y&xzQ+C}R7li0!)~woi-LzAj?>z=-V|Beu_s*uFI4ejUbs${YLP*bm2kIQGM_ zACCQS?1y7N9Q)ze566Bu_QSCsj{R`#hx_)2X_vWuC%@0))hEN`n|u4=+~?2xn|uC| z=l*}#{x)it{9XX^{Eh&evcSoUvWJn|A3*l>f2Sa02>M~{iBA7n*uH;5^zHvCw*RNt zew(v#|5-TC!g&_958)8DKcv|HkYf8oitP_6wm+oU{*Yq(LyGMWDYieP*#3}W`$LZ9 z{tXxE#QuF{J^%EU9&%*yGzYAkuN0rfjm1zu3P0V*C7y9fKgYFY#&EbQ1NJ?r=~vE$3c z_7j_p`_IC87S6NS?-(fcL&tNeuR5Mf?07EeIG#)FcrLNyxuoxSF3BCwC3ZZQ*zsIq z$8(7t&n0#|m)P-K;?xOc2~(fZf%7b!G~wh0#|AjI!Lb=mS>TirPTAqq37oouQ-^Ts z7EYbRj>%Hng(;Wg!X$TGnAmY)V#kGv9Tz5cT$tE#VPeOHiTgH$`}yjKv15nD zjwx1}jy0A%_1U+d^2UBR_QSCsj{R`#hhsk+`{CFR$9_2W!?7QZ{c!AuV?P}G;naVh z=>v}8RhynTjwu#9=2z@kV6kI_#f}{oJEmCN|IJ6oLP{Pc-{?@cc@|EZaPop<1037n z*bJvEaPp$OVe)l6rtEPnr#NE>`eD+EPXAft_AS)2_RkdCKT~YK%GtR8ESzWIJPX^$ zPyNvTiemdKitTSHw!fv={+43(@2KiFWkjB`!>JSL|2KYj*#3v(vM=|PNzM*Q z(|(U)`#p;7_b9gCqu73rV*5Rc?e{27yOVyH`n12LY)HPylP{cn;p7V^UpV=~$rr{C zg)H_`+~TjvQYY&d8DD3xmH4^3*5t*iU(5KOFnv*bm2kIQGM_U;6)xzx&*` zKTNssTj5+Bd+=xByd1{Qg>!Tm{};~J;p)Q^oV&yL%WxhK<440eJ#1fnv3-4KWAcp- zoM+*r2`4W&Ho&osHj2&2Qxo=Y8 z!?k{EIj4tf-KB5MeJ0I33+Gul&%(7H(0Mal>lvLxQ{Gz7=zJP^t!H#@4cB@`=h<+r zXLQbueywM8{tef9M(5(_)Otqe<;ZJ2qjPk))-yU^N2k^^I(LU_J)`q@xYjc|r-y4j zqw{;XU#>7^j}Dw?;iL&CFE}>9u?>#RaLNLwjBv^hr%vG16`VSRQ@3#H9IiEq&f)q@ z8GWyj+PBt4EobfM)ViqUtR1d(QOj97T ze!jF(@H?FDqc zj!u~Rj1HV<;iL&CFE}>9u?>#RaLNKFufNUL_le0i-$f>#Zaj$&Y35nDzC9{Fmh^pp ztkUuQvEuq}tZ&WegsJm9OFDTL&a-fR&(wJ{T;F4L4h`4$Se;M9^*vVS)^L4~)p<5t z-(z*o4cGTroqxmiJyz%9aD9)}c{yC)V|9)W*Y{YRuVZI@kJY(5T;F4L9*<6akJULn zT;F4Leh>G{6{hUbf%7b!G~wh0#|AjI!Lb=mS>TirPTAqq37oouQ-^Ts7EYbR^?g<6 zaDAqXzL#~}XAb#Q%UL@*zL!<(ds)T4msRY0S;fAWRqT6N#eEyX{d{5H2dgnE`65rg zv{&*)o_yit3nyQ=zF+AaowC$9V9Pl@T<3!==l5`(sp(9&&paC)IM2dK6P|9ZRo}bx zo8qKd-@97Q@8LY#XVQrdoM&O~b>LhX_I=}G-#0GyedA)^H!k*lx#?-&=? z8Dh)1JMubPY&nmI>&&s`oF1;T$d>baxXv)*c+*L&G!usr*7fYIb1#=9p`X;rdUa6ex-`NGK; zPQGyR6+2%z`NGK;t~2+Jb98L*?+}Uo`$XdM3G8a!FdOr1bl^M-Crvo(E7A|smwey8 z-oZMr?>N6lC(rhobfVLL7A{}AuI6L)!}1C2I3q{Dd<8qs$l>xK>^LKb%eS!Oj2teX z!;Uj@(kWlWjx%!P<)hefMh=(nV#gUdTt1B*XXJ4CI(D3q!{r0naYhc8Z)C?AIb1%I z9cScl`BHYAk;AD^IQCQC*bm2kIQGM_ACCQS?1y7N9Q)ze566Bu_QSCsj{R`#hhsn7 zw?9m|{2N2+Gyd%%v44|D?B6O9`!|fl{%s?1t>Ze*>B*~nDLc;Z;qt}mIBV}S`9_B} z&9lgpCY-$B*noa)Lmr#qlm(tH-Bs!#-XW{bw?l{BdS^s{Y zxV|fNoYNyOzx|Hy&VBAb3+Gul&%)C^Ti*{lzB`j<`Tuu(kA~~pL&taOK9f%L;poHV zqu$j%R{h++mnSZN`;PN(bjshp<6ImrfBTN}a=85MJI>MJ^0)6eUx&-zzT?~-E`R%u z^LV)Y?K{rt;qtfdIKQVI%iq4^TpxM)+jpGzBQJmZ4nF|o^(~>pKLAdh_nGoW2hOu_ z(u9*292?-+2FGSNWr0&hIAw=ZCvfTtP94IjTR3$Nm(P61IbWYCmw$Ip@;bxs@F75_ zz7uqu<-_&;pyMnbuI~yRXZdh_Z|FG7hwD2;$5}pH-zPfG^5MP>;eNiR)*PUrg+-zw^MZu@burl|Q$`^Wg*kuPfs;t=5Y-NEs@ zgX4Dx$L|h~-yIykJ2-xKaQyDz_}$Ux<97$g?+%^#-NCHUh~I$c#P@PKpUJ)-Ch3tb zY5p_Cy!3s!=XQ+7biU$!|MR)+_g;Gn?$}g2CQgAiO`HOpI0ZOy3UJ~S;KV7wiBo_R zrvN8T0ZyC(oHzwIaSCwa6yU@uz=>0U=Ok8Tx)_sw+)CnSN%Nm6Mz|mQmRMTGin$Tf zI$dmCKVENc#|hRNgL|m7u1j1eZJM}FIB}iSL*hD-C$1AtTqm5kPB?L$aN;`Q#C5`n z>x2{62`8=-PF$yK=*6YZNo?9t`PBbC1WI+=b$}a@_&qzO8#g9EaYLzGI)oen-TPe;51RZ?VnqzS!@+*zdmB z@4lY(yD#>;FZR1H_Pa0kyD#>;FZR1H_Pa0kyD#>;FB?2Iiaj<;$1&7m$54wMLoI#B zP)qI@YO!Oe#g3sCPj`2d=Ln@ax9_3y9Sh1U_lD74xi^fq&b?u9?hS);Zy20=!{FQ- z2It-|IQNFZxi<{Xy;*aZ#RkWoiyf0LcC5PCG3;W;wu>F}E_N)u*fH{A$Igo#Q!jR`z1T7MV#nr-9kVa? z-c9Vin|Qjr;vF~FQAY0##hefDT^_mjm}2iS#g6Y2d+#jv-dXIubH_N~y|d)rJBz({ z7JKh3eeazm_ug6Ty|dVRXR-IrV(*>B-aCuEcNY8Gg4o{{l&@pN#EuaYJ4Q_Uju8_( zMojD&F>(JlWgO2XxxaOY{f$NJZ!BWRb&4I=DRx|^n6oC%erO}db&4I=DRx|^>}M~? zITQMhBNjW3SnN1rvEzuvjw2R3j#%tCVzJ|hm6zj)C3hUL*m1;TxqnxMzTsG4$sHps z_O~^$zpaTKA1(H`II-h&#E#z)`do=mZ?cX(HFUWUi@^WmQ z*fDov$Kr_{qbGLkp4c&cV#oTaZ#V`}a>oXW9WyBA%z^U&`jTS|C3ozh*fEJ>&UrX{ zz-Gr|iXD$B=A4H!8`5;VfaH!B5IbH#Y~Opa;}^t^Ur;*sW0%}M`C|Lzi|vyywoks; zKKWw%zR&1YJvHfGk_L~*kw^nTbe6juHRbKnaOKv}TvHj%5_LCRa9HHMz zrqA0?Ug_8;UpkH*5Id$o>{tV_V-UoSO%OX~LF`xtrSBLAv11>kI4#oC46x-)eY@b8rYo9~0eGbR+vCpCO?Q(-Yg5PtV#PSaSR2itU#xwqLH;ez{`% zn-)YJ1Q!Tcywb(w` zV*6%`?XxYmFSpXPkGJHtca!f9w%Na3a{ISS-#%KB+eb@s`(H_JAFb>$@eR`+-2PzM zV|JuVUiJ$T+s8?4A1ASWoW%BV65Gc~>D$Lia{D-m?c*f2kCWIwPGb8wiS6SgwvUt8 zK2Bo$`H1aPB(_hH*gi#K`xJ@oQzV=1QzW^4ip2IQl8*g5sJLWUEzHN5QXK;Pn?3mBs`nK6IpTYHQvtvGk>)U3>dkpW{AnP8UwLg;N_6ri*FGy^^AhG>|#P$mk+b>9LzaX)Fki_+GrH zUIw_%o;vPjfa~n3;|>D2&Yn8%CV=bgspHN9+PBW0I_@$+UT04ocO1ZV_SA9r0bFNK z9d{zYb@tS8R{~sTPaStCkWQUFb=<8WodsUdapwYDXLB9^2(fjN3@;z9)9y6T9z;<6nwB@lA!N^DpiDYEI|l>UX~(o%l(@@t=g_R|&`8 z5{@4x9REx>ew%RoIpO$u!twv44*l-ShWLvjj~^-e@h^ovHcCIfn&{6BpGl9&%FAQ5 z*mH!~bA;G)gxGULgKeH8B=;O4_8cMh93l1`A@&?9_8cnq94hu4D)t;I_8cl3Jco)s zhf2qDsN|kQ#hyc@<2h99IaKU9RQjGnCHLAuJSV=RUSlX7uRZi^;)7^+uVEzrXNn1m z-#cYY>hO4}CuNr+a_o`9e+^YuXUNt!Ps=>Ke4gTM}7tUwXvfpRZVxMt~ea0>J z8MoMH;$okni+zSJ_8Gd~cl!oNZr=dO?HeGrZ-8{{8z8oCfY`nP(zkDb3aA?~vHOLt^_5 zN&nXiOinCy{n*E2hxr#8Y_!LQ9nY?D>jr}vU*15x!>-#6j#z!nFS=&G!6D{P>1Q{&a&oZgmp1IM=ay||4W51QIL&we?(D&m2ab7xw=CGK_rUX{bHE-C z3|2jG1Mwx#xqk48701u+yv4%J8Q*`NY&hf0g_>_&HRk=6Sg1Memt)@P+GUzIKl&W$ ztoMf1npYn4Z1Dr1e_FHjtY?W2-f)BFeVdMX<$3!xvqkfTAB_2BTW;Na^NfE{nqR(Phvu1wKT|e;?#Ul*R{YTVl7Ha# zU7MfJ81tvL*|mA^W@G;Ag&%Fsf7_Vv3dK_V}8?;UujM{d>zT3{P5w;hmIKYHS-%HN=yfoYpM7^O(|K6Bi5-;0}V{$s_l zZChW_?7h#5(m(QTKW^@R)0nSW;>XPqJCAw0v#x0Vw8xk?e8x|k<6gVG^gsNI8=4hg zw5<3?d*0gY@|2~;S3cvmX2~;_55O%jWmZbvKQDM{oV)L(NC`T0rudt3KM?cf^y#Z&>`#%_p}W z^Jy18+HA7hn4kWkN1IoCe$00)_;~Zk!}ChN{toNkE$>l1H>~HymEN$@71wjadR|=V z4J%!7=T#0!?IgkX5-_p$0} zSoI~YdL35%N~h|3SoJP>wa>8HN%Cs9;R9P=A+GirRy&ES-Gpd9O`ykuu{TSAJB6+<}!+Nj8^_~sueG}LFH>~$iT<_(u z-cND8ufuw8#r1v<>pd6Odq1rAUtI6^u-&9KHD zag9U68jr*^-VAHp5!X00tno-(udyc5^>H>`0`<*jjXSmUGQ zHI5EzJQdftJFM|nT;u4l##3>PufrN=#WfxeYg``Dhig0@*0?OLaeY|hyST>tVU7D^ zK5)Zfjqln?LR)>S?N#DAMUorX_8-a@AHQn-*BdQ{-s_p+v>q_i88S9MeO6^>=W9~QfBi~TN${f>zJF33*5Ba-`_68l{f z`yCYf-4y$s75g0*``s7&9T)rE7kjJ_dkhhK%n^Gm5_`;%%^r&+_t+)&m?rjEC-xX9 z_SmR&JeErCF;?ucRO~TU>@ivFv0Ci0UF3eLK++)7jbA;G)huCw9*mI58bCB3` zme_Nd*mIWHbD7w4pV)KakUs1=RP4D`>^W5Ixphc?_FOEv=V-}2cT4U$UF^AD?6rZ| zYX-5`24b%n#9m{Fz4j1$ts<^DkTs0hYZbBAFk-KH#9j-Dy+#t(9LU;9>@}6xYcR3b zW-71OV3K=nCiYrR>@}X)YeKQtiej$`m8RE^ zd#x+>8d&T#v)F5CvDe;WugR6Z*WQwQO)mBtUhK8K*lT{V_X1+?5tOF)6q0)nBKDp_ z?7fEAdlRwuCSvb##NPXey~h!I?<4kJN$fq8?D5`8a__mu^6_3wa_`Z^H3v>GpYcxB z95}(e1=k!n!F&eS95|Et&pZp}onrpXv&^f^h3GJU=2_;|q{%$YT!;?yGjk!#yvo4X)m~|O*AG`i!mJ0G3t`rY%!SlH>p|v1m~|p^Av&xpnG0doo6LnU>rm!G^jV)W7b0if z%3KJu&SfryS^qK@!mM+d3wf6HFLNPs*2~O=FzaaMLYQ?ob0N%noVgHY-OXGGvmR$I zgjv5c7s9OTGp4cLXD&p}K7hFpW`Dq32(zEaSjs+wxez@%1P(Pv-6TnMvY zVJ?K(-!K=#?0c9CVfHu7g`~s2hq(|r`y}QAZ!s6b?8BG~Nr!zK zb0Ko}bIgS>`!?o6nEf1cAI?R5Zl<-G8ZCezsp<*vp;4oM2CGdb0Ko}$IOK=`)1}sn0+>LAOYu@Xa3wx}+ zp`V>Z?li@IR{nTSQ*zs&eXDI7@vLnYyDVatQS3SqyAH*!ld;aYuEefevFldsHfqV& zZ6|gcwX}=dPI9-k*nL1c?i-T3&xqZZ#O`}y_ert)p4fd->^>}Z-xm8_5c?ew`&|(G z9TEGT68l{f`yCYf-4y$s75g0*``s7&9T)rE7kjKwop=n9++&W|W0BZnj@V<7*khO2 zW184wo!Dcb*khyEW2tQL7%REQQnANavBzZTd#sk+W4qX6zSv{C*kiufbA;G)huCw9 z*mI58bCB3`mTd4`Cb{P%Za_l6MIc4_F7TwHKEvRMX}eGDvQ^gVy{J|<29<-Yge(? zx?-<^#a`=*y#^M0%`Em>TI{vA*lTjJ*WO~U$;Dp7i@mlNd(AKQUO?^;|5KHiIoy>}CPPp9;~ zcaz+EIx*iwnG1Q>yf@6V>?Nbm{!#3Gr8vHz+*2ARo%o9)j~^*K+kL0KdrG6jyPs!C z=O5kAHuh8Y_zA=D6Ncj_498Cxj-N0bKVdk2!f^bA;rI!|@e_vQCk)3=7>=JX96w<= ze!_6y{xIzlUubmVBMrxQ8jepj9A9fVKG<-4v*Gw`!|~OXop;qT;>-3q zfAq*=i;1`W*W*Xc7ZwzsaP5AhpM3mD;@58crqSNFj`?j5tucE0tc4`sZGp?%b3S;D zc>epZYMc9S5Z`vzb?tXveY?1sd1L#&x85V3ciWrWb?&%dyz?rzwA&o}sCe&p-rRot zdGijjZQV_7Y`6dD0^<8GyslmElZ%M&oagFx^=B<1K4X>3+q-sJTKvlw{IFerz2(Fg zyyd?3#WUvmM=FvzJ}Ac6-wwZyZqG^Q(b~$Tz#@J?#dcTu^-7yLM?8fB&N5```cX?PGsg zLcH~B_H1ujbs2H@rv2M}Pg_p>nKce>4?JlF@#8xm-tJR-a?-qKnPb~Mk6cN7>5oos zH{EZ{U)uJ}_EqPNb!HsewhzB#{H)tu`oC_z)NZrKTH^P-`#J3gH(y`;{SSO#^z-3! z!h>+>G|{PNn><@-Hr1D;UwJjjt88duL)q5Ewz9d2%~h5rWvMbYDPxtrN!hDTn$$_v zRg=1^I&4yhRkuy*w(7h|omX2lX^U#3CT(=sZSQQB|Jvi)Yp-iw zzCkN~?MpXn*4*)A@djriXS}Vs=;^f{G@oX zFP}5`^l={)pLxx3gIf=Ir}+Lqer2%C@~;!`_x=M1+a9#3_&K}mH<LUjYe)zei#Xs5b=)rA=%p+cT(bEU_{_xHbeciFl4jX3iVbDk zD7KZ&qu5+!8Ko>$#!<>xWgn&NRVSm=N!8UTbyamZN*z|+j#9T(=cCklwMCn@s5WZT zM%8w0+OFEPO`BF*w`uF@18w@idk*^Dj2|8GdDX+38$CR6;sfLMebr}o8QgTw!IIx` z#c6{BwmVF`-n@4Vwt40;;_l=Hn+N9oj(FRDUAdX>i?hTRJa66Rfe&6He)?Mf(#+cU zdhs1sJi8fu_O2;;chSRB`kP!fuihilnVei$O!}M7yOfxGm)LQ6G4?!i)yiV*{K*ol ziLrl&MV=z2TyHpY%q5?Uy!1!WuXIL9r_vuK{mQpZzGY7vd#YS*?5uLNvA@dI_R7_! zyy&MMNGJ6}`l&baO?_fd>KQvz|Ja{)dHAvA*LnJ{UO#Hq-lcu@AslOE~9>_Y>Mna{f{--b{RK!QqC>oHc@A9J!3BUDDu)DMZeM+C7nutl=Lg#Hu;u4?UX&|Z`8)l zDpwo(t6UmaU9L9e-MsWu52Q0yKb3y!jeJv|*pqt3&eT8lr(OE(b^nPkQQMu@EY2&Wz4v?H8$gwu|ayB*=QBb;`el2!}N9(H{;j|;1c7)T8aN1FFw?BLJ8a+kI{YZ38w>wTy_Z=of`o8J1t_J+4FEnaJ< zo!g(DyqtKwU%#)t`I;5Quld0C?V=Z~B0hB8ZQA>{TTT4Smu}UreBx8YN3Fbh`-wf) z6enN$aO80G;iLm6eK`5Tu?LQwaO{UuF1Ye-C~u!Bd(}xp{lH~U6FbYECia&-P0CgF zG%0V{)1)5Co+kBE_B5%tvZqOXmOV}CIr-X7$>He3Ne52)aPoy?4;(w;*bk>%@Dcle zxq0`^mufr=Gj8|mXYcp!(7f+}`BYbzEcdSF(>MP``ZM13uIA$hJS^VpE$?Yod+Tq- z2j2OC=AONODPH2nk2W)A{#^Xm`9IwpaKiQC+gIGDdGe!Ii9hn#fz5-jze1dRss9DH z+@ZO3=lRqYk1zPH=BoGorA2<}e(!2lzw;sSowdJv@1DOAAODk`ns@Der}+A;%YLRgWS{HAfBeM0&2#U*Qha~=h30~HT`u0{8;3S8S?5ymFYZ6OdDcc3i(mNB z6PsD5UL-#4!PAQ~Rk)aUU>pVw@$ z-W4tUiBF#0EU^Ej;#s$x+ARN;i^cOjc6@W~DHn;aU-PJD+r7r}e%}bYuj*ZfFF&#y zZFbw!R97{g%vk)c^~5C~L|)HMz59{V2N>JYhm(%`MoZto=CY@aJ!NMbJInqy_E)*u zl&i|yro2@rEpwe3yVd8;6hHptm$kRPcv5`9ty{Lge%pECou9r<`@Zj9D1PIa zJG8scxJ3N6=YOPK`-scL^PTeP_O6957r%77ecPGu9P{Z*f1$nb#2-msc{Ryvg&)>F z{b$EX{`4JIY<8UQtKwaDdT21(=>YL{OMY*#(1$)NK784?41Ray$HdRs^^l2Ow);?c zGF&>N=+v{LJX>jwl4j-ACa$bCsn@S*nap%2;J@QueBoCUsJE)ugVf z4x7|r)oqiyO`rVl_QSP4d`0t{E3Z{O9R2QVniY@unRwROH#9qZ;70L^8{gIp2RDfq zxazLvqmPf}U)c1w%>knuB>&jX4>pJHcD?uw&-_!f)FwX_f9my*HM>6hO7UNRInVH_ zH;>!#n3+otpZSF&B!BtVPaZDxk=KYHcxbKRY9G90M7iF4-HhRyr*1p}?|%Q9!)xC6 zhXMTitydYId(XQYc=J~-G5qfR$BXaY85U;U~0Y0rP8`P0!ii1&Kiea+fu-y**K z-g}z%{E9iLXD1iEqj~VSUx?3t;HKul*WV$2<#j)8w*K*0e%-xSG}|nFyX3EZ_r=Yz z>;GJQ@yE_@?%VK2an``3`Oe?}dvo#U9+Z5)Bll?T_}Xv8m%aM4%?FmdOZ>C#Yn)tv zY{Qm29nd_q_)U^u^WuY=M{m1M{L^#4+B|;YHR5@`b#!yiRac3>eZ}$3d@GFk?SD9> z`N*MT{@m}s*KDxmSbxD!Pd3YJG)||#hTr1@A8TH)!lGKwZ*niUUSLVW1{J2gk% zwzT+V8&$pDu$*}DKfI;+;d@pTpS0X-nm2xOW$_`u+oU;vfmOvz-@9S6%pbHg!^U)uyhh4%^gW)oq))tvYX0=hYT%+M?R1O&e9)wQ0L*(>85dZQZ7=s}Hp4 z1JyU$^o{CEZTeF6u{M3I`d*v9SADWgpRB&xrmt2XZqtXWZ@1~&)#uyv`Fa=HybJY? zba_YW-Rbh~)H~JXovL@O%ez+ZV3&8W-pwxWX1%jr-r0JWyS&Twj<)mhj?$?;m zW=yEDqRm)QV@R7Zq{fyuV@r)WZN{7$i`tAuHAb}=qiQ|8)>^xspz+~%8}BeN>-Wcs zzcjjY;@LYMDXzXZ_|4P5BtH4^*AI?a_*3HgJE(t)>;DI(C$8rP_5397Z>2Y=bj6jA zzK!(c8jGwib~*!eoW9ukifxbBc8YDk*yW0R5<5r}yT}j5Uh;z}2l+W){w=25r>7Q}W$yqjjVVrBT{>ig& zo;BkmEuH?ke;A!PIqT24e_tPtZvfo)Rhtu^wD_m>pM~>mk7vPsAFVL*Iq}Pik5*qF zjvp7?_gf1ipA%oT_^tKz;rO<}ecz`r@;UK$itkfjAC7+%-1i5Y6Th$cfc2k+^DG>n zF}Uwj6h=NLenjyp>g&VtJA(UuR$=6G;#(CztG+%QUo5!qs}n{(C;mC{)#>ZQ@#lg2 z{!4S>rxc&1{R?D8h4E*nUt&)fIX>_7QRMaaKaGj5=M*2^*N3AI zyvi%w*N3AI`+bqV-;1%G<9AK$cW^fDKMUts*zZ~cyASBuFmm?+$=#R4?qjoY zUmuP>?6GS|{fCizjFQ}Am)PUsY~0s}qYwKXmpx(Re#a&ESfMmMhRnu&eK`8C$8hO~ zk$Vi6+;f50bHr@i*N3AId%PVows>6CvmT$t9=B)X{%-B9y~ftFmG6l6mcHusxwy(T6(<<(KMUtsIM2dfgQ;%A$eG`GC&|leIkDGxvvFS^ zjy~-5jP%3Ey@rvz`bNt;NnTzr&BlFwIQp>Hz^cbA?Y*!^WOHk|16wm;XDg7x6?0qHjJG4oW96=$2?D;L#M{xshFea zpdTGLIxuTJ#s!{b4am3vvo_>CCw=dmX5;>|aGr(pEX-PrF@iM1$g4g7ZfqLsKE{r| zKJ2}QHk@$}?vG;`_mC&f8cv)woH%PZvC?p2sNwRZ=boh@oS17k zvDk28wBi1klQ?VSiL-_?7Qy|oC1Vlt#970MvxXCA4JTF__I*~eGqKf@kMFaRJh9lw ziAy7X8San6_J^08*fL_J(aHF1o*Hj6J|j<@HEf@JJ!@Zmabl&>aa@4piLFMSm}@w( z*pfR&8_qZhC(as9oHab%7}y^(6K9Qn;;iAsS;L8yh7&^#C$<_+%r#tnMzPp%VzlA@ ze33Y7gPHZ)tm}@w(*l=RB;r^dC5 zt`o8AO6;|w*lR_x+ogPHZ)tm}@w(*l=RBVUMxOH*wa;6K4&3?;{1~_pEzqcan^8RrQyU-!-=hi6LSqG78_2CHte}f`6kX9dE%^L@28~WIk7|T zIaHiDYvhTuh7)HECsrCx3^knCYB(|1aAL9H#Aw4_GbrE0StC!JHS9HpbiDQud#xf) zoHhE1vxXCA4JTF_P7F1i*lIX2*KlI7;lyaeUYjZ3#91RxoHgvVoOHa#6MIc4PMkIR ziL-_iXALJ-8cqx~oY-nOG1qWnvEjsM!(Ia`-^5uXPn3Gi~_8v!^IBWD1XALLL z8cwVLWVeVLBE`)0g)LqRm zcPud%!ZpU~OcUnbCgwtz`<$2yVSmFH^Bs}75V_9?#N02%T!@@|q?ij~?w4XNgt_C2 zxe%^7LU$~~+-1dF2y>Seb0N%KR?LMkcUdtP!hBz3E`+%si@6Zy-Yn)qnD3Fyg>e1V znIl}!O`S8AExLypc|E6lnBhuK_b|g%Cf%hBSN^(V87{kY_cC1e>P}|3%AvcO;hO7p zhcjGj2A#daRUf*C8LoQLJ`tIlL$zBe-$!ai3LSDWh|X5`gAx`!FAcGEq~aP^%b zb0J*qtUH$BS_|p!Ww`obw%JHJI*UhO0m79%h(t)y##k z&!NQi9!#BA*1M&9n9->;2F@%y6w&b(b<+@00FWhU-1k-OF&TMRg}LT<@js zYKH55)g8{T&j)2gt#x$|GxAyk>mFvf*33H3g?&~ieV;#$?e{&*=+xR<_b|h?Cf7a8 zaP13pmoi*yc-^rK^G%ew5Uw@9?qr5*FQB`c;o2kU4rjRb8ah{nYfmv`E`)2Zp?jEN zpEG99GIeHJdz`5=*4j7e9%l5pPm#G0uDy@$VTNn}rMr~j+AHafWw`cGx_cR}`9yaz z!?owqUCl7xM41cW{`qpvSGtE8Ip0K?3*nqQ_gLr1{j+A z*mJ1Z^Rn1;sMvF>*z>#CbFtWSwAgdE*mJtrbG_JW2C>%$Vy_v*USo*8_7HomBKG=6 z?6r#6YZ$TDQDU!o#9j-Dy+#sy?IiY^O6;|n*lRGc*Jfg`<-}g&iM=Kidz~rvno#Vu zqS)(6vDcYmuRq0Jmx{e!6_+n=d-)~5R9o+T?J@0|tJM0b+WP6Q{(5`dqIZjTn)k?d z{;&K>yzl~twJ$p5*W%}V@X&VU7yVZJ(3`*9?$O*Q{_>Rvw=?&DP`uQw2epST^#}3j zz=Px)Px{Dzywzh<`YY@>kL)3x2bY~sO#15{G{2a9m$~^#V(dBn?ghlydE3e3SYYfw zW}Ss3r(Cai<(RvbzC9&h<*4sW>0f*A=~L-U{OWsC=`XwcSyTDG`rvb>>^XI{$u@Rw zu;ggU{(ZL{O_d9I%8P#Lfpk(oq@Q{t-_$4eq@J-e^^g5&mnv72_9}T3dFeONuXLKE zQ|UKJzw&L8Z`sqtp0cxvon?O$`>R|Hu?(~q^0XKFsRzy{M!u;}>`6UiXX+pO(=PPG#a=kxkL+{xH`^uVAM+wx9@QTIo^d?vsVg1U?z7`~ z|FY#vzS6#F#f3WR{MbJq)P81{1;m@b>Wl3)`_3<3_zjA&MM_lU{&d(W?XjVm4OdE@8q5M$>m2i-2l z{+Dlan^^DH!?%h@tDZb1-{^?brt}ZF_Ip$5JaGKkQ|W*Gfyt?S|Kq4`%AScs&zrJy zk;~7YvVXx1E|@A8@{||-)C1|Hen>y{M!u;}>`6UiXX+pO(=NPUX|Iwuk(YiG{Ys}v zI+cEt^ef*c`IbFR>?u2&*je^BvA@biKOEO{$hI;$0>QW@05PE`&2sBAEwf;elnGB^`9wws$WgnS^aIw{_2NQj90cdj%K-~|}=6-;>H=xbE0d=21oBIS3lZgF^NrV%V2qz{HPD~=4m_#@+iEv^P z;lw1uiAjVLYY8XT5>BiooLEaZv6gURE#bsk!ilwn6UPcCZWK=3D4e)aIB}zJ;zr@b zjlzi=g%dXl6HA*lXW~_nCyo_Pd@G!|S2*#oaN=a)#LvQstA!J93nva2PJAw$xLr7L zzHr4JD!v#_d@-E(VmR@|@Zydyh7(^5C%za?d@-E(Vz}~BTrb|4%mRxOweC3sQ9-aR6mx}qzzsKpUHbM{PIi80}k91*tV9C$&iO5TTBKnoj zAn8>4gQQ=72g$eoe-L}>xk2o#^aioN@)^vx{=RFIm*o?%^~FwSfZXYeov+yTh;661 z^1*&_`3TP-KbMR0MxS~RV=wuk<9ZWQKJr6OxycWvKFANQ^k^4x+Ur&8@4eAS-f`UM z!|yq0#^3TfcYJg7z}DMOBLC)YhmWql<96{8Z~4OLBkx#egnXYHb|2lg)oaE4<=^9U z))}D(^Bm8^q({2&&dbh!EO}c#5qarPM8EPGB%Mlsko4>CAo~sdmoxa%lifxbBc8V(>>=)CHgV(cY9bX;#@%13_4 zDL47S)Cc*&l^*RfvDWH;ZLfUUeWPXfJbwnf{)xXCO+5dENqEnjZy#NG>WmS5&BT?X zD_^#=c*9qnJ-YD9!^HgM-{W+49-$|$=Xf3_J<^4F@5s;ciO4ITLG&x1LDH%82T8yF z4w7&E{~-3%bA#Af=?!9k{az zTrSERed=M%Re$7%j_XZK`N+@qP|srOgL*+;>CrB;wb!p!o~PUE$UlxgddSy~g+FuS zL!%8JJ9!eG^__c0uYCJ@BY2rzt{?4nbXJetn>!4zw#Np=JQ{jL0*rG7g$j|mr&tmF>{E%0Aw2SOd zd)@Nh6}yZlu*Z{0IO7kTaS6_N1$#Uh!5&Y<9#6y`PsFqx<0SfwXT1M#>1$kdIvQ_b zk0;Xccp~&=aZ?O*PWSoIB{=gZR;EY#r#xXeK8*DoVusjpjpCBE#i#YAI&$cUc%(1I){mWxv&*_tJ)&OwU25{C4 zu;=s<>^WVWwFh#~>5|iS%(a$l4Fj{*U~YCgTJyl3(yE*me$J)mKVNF7E_ zK}BRZ}(apg;WiuwQ8!*kT5?WbKPUOnHa~~!3 zcVFx=LChG&^XO;HgfnJZt}zq#Sd?@$W+M04C3(h7g*_S904adB#liGiJgruXJ1wNk?O*(`T-c-1RATJ&Rrc;*6O*oA&CD zpMT3~N90at1g9Ng=PP;Iah%Q*b077Pc7)T8z53By=6VyS9nncU!f8i1?Z_G?>z3Yn z=81LYczvri-v70ACi~WW!_0n`w#z;j&i)t9z8KDa8TP()1ZRH@XWtDoPLiMH>|3M% z#COZ8pL`#ne)8P_&i4e~wd_^l>|x>TZQ<;B;p~Os?2%#bRW(j#PmSDrRmoY0ke}u3 zRippJc|p}xz6nr2`BnhCU1mEkU~itbGe7YyrRwA#;adu8%l=+~^=#J9UVo0z@w!y( z^{UwGSh3f)V%Dv!vw7C*Veu2||Nq|lpZd&qOW5BtwO{jhPO-m#s?PmgRP67i;wQc{ z&;9Sr-go~~e^1~{gl{G}x9W4gtDuwbExogq5uEQcaK78X{(d5zeCI*#?7ui8HLKt9+-Teq8?p*zJ<pPzHN64u^@`Ihe*!hZWkC^)7 zdGym>aN5gqwHNGqNIGgS=0Roc$))c^Xs)^D$Ie|X}(qaM$@BGwBzVr9$M>_e=k38S`;e6+Z^PL~gcmC)7`X!?UA6=|DXxsBzzKeuE zw)aJoKig;($zS`EC1+l^@Y>=ZEcxKXZclrv_=H!!Z}6U7*A@TA=#;@(e_lhp>WRM? zEcEjg#QpUDr_#jEPam*SbLmYNwCCP;>*RZHSgASaz6;u`kN?`NooBAuEWF@F?MA=a zZ(`@`)@df*aY_5b6aO?ZbAzWgAKKv3cKd&w7_9fEr#35ZacTSPXYV#xbNO|fUG}=9 z{nQ%{8@%l!Yd0IMcyYV=hbIRQ-LQHy&y#+rI;p%`@^ZOa>dNI6yB@@@AF=CA?6Qkp zC*sd6apK?um#x{Zz4=A$KF{2Bu-&Tbwr|+)lJ<{(dhTHR_dd0~{PmZ%>wN#NiNlt7 zYWsrKE^R-2+*T9&Z?sPPx`i%j*B;I{>%)Isv%PYgi`u)cK4tQ%Pp{e@e#sBoM<$mV z&G+zf?H+fZ-}duz`zqi6sj}33z7Da>pE|EJ9}AXXXv;4hXQ5UULDu;J>8sfNFJ{yGCJ>6|!0j4_Oz#2&-gPfRjgK1+C!znN6q%BB4ZA89lJM2lDVrSaA>Tp*2!0nsAdFB>- zjq7TG&;EGkUtWKV>h1Q;Z=AX7!Q*=S)DnwNta13Uk}vStS5932{G(N$-+SiT6JPn4 z<0Zf6k+mnj@r|#lZa=leffK8r`wi**_ME3qobbyNq_fvrhfkcb!r{{S-ZPJxSoE%A zr8D1#t4wrX{FZb!UjCYiC*N_DbbfnI`98n)MCm-X-XCTjJkPhKv-qYDP3&>xG18fD z!^0-teA2haIvam|<};T%SvuRT@aKusFE~*;kFB@s#C!*QM>_Mq?3RrtjvnjG|C75W z9{Is3W1WrHn0Vp0PK(Yt(b?nc=S+Nfg)^ix@5{ECxz)v|C$Cw_Yxi4sn%Lyu&Wz5i zDV_EHFe^5n|AOOZzW?{%PhOMBtI9r^vX{=RDV_Cpos7*@hm)zp%4;%tRoN#~_G*jC zv_;uG8JnvPCsT*jj+1G}D*I&0UTra%wx~WZD}A8qa58mRZ917Ytv)j=eWu!CGHp?P zV={fC+Ho@NSbb?$`cn0Q$@GEhGn45vyuZZf_ug@_-+eJ-6!H1!c&re63=uO%5uc9^ zV-)fEu*V{?$EYbe@$Jzk?j816CnkO3(ZqzKIz(xHkd) zetR(v6K9^WclXmzZWw#fAuo@;$31J^vl_kr^y)gl0(0(^ckbBc=I@Y z#;6%vog_J9)Q)GJs(cxvzH{!0k~2mfv&Hvi17p;>&pJgqj8R7}bb@pkqYk?MyV7Bd z+GwGZq{A4s_cq5#hcW7Di=HMO#;BDJJ6<}BQK$dr80j!Z{qWV_mJVaouQxentW#su zia-CRbQq%!e#Y_AVT^jwJH9R*#;Ao~HP&H_dgXfG80*v+wb*7yMdzI8Fh*T@{Sne( zjJj{#Ba_#xlHAcl|#;Bh?c4+dNOkRvpDLZ4-lunINv6(R{b;uZ% zycnZWcE+f*1!GifW{gT5GDf8x8KY8m#;CLfV^sP8V^r#pF)D4!7?nQ57?rkQj7r~N zj7mE)Mx`$?Mx_rhMy1cZeDV3(_SDH@rLuo*Ij+!;GN&ON&IhTy{gVZelK41 zz`sl^x#eHP*WR|?#M6$Nx8d31$#CgRMyH-F-`erBmF6gER$imzRW^*U!R^xY+N()> zmHnz)+doz3)hOQ`s{q0)LZmzoAl8sdj`EegMREpE<4fb z)$^cN&x2k)4|?@H=+*O}SI=*r=K^ye%ti=ZPV+w zO|RcJy?)#D`YoJ(i%$A2&!*p!X8J98rQc#h`Ymmw{y_atSGTl#+AICR?UlYndr60~ z_xlO)%(Q#ySKRlc;v!zM;8$SKx&6VdaCi%u++^t#tkg?8Izx_ya>uw8moHadZlbxEo)>usGJavI* zHJ7h&CHv)3Kh5Zq=E}SMTXWqzE|*SU|Kn>squF7JvHUG}uhZP~-bi3L||4qf&v@s)Qk(k%J0GsUET+I6njS4L!I<(OFGzAJR(i&OzBs-+LWux z+orr#4{hq9>ZeWpRK2ySx2n%J^;z}Y(k}hH;3`*}a#eZTl(*`kO+8fow5gw}w>I@w z_1UIAt4&+ll>Sg9y$qb{`nLd6C=1==91ssP`pxGU(Mw)2ovyeV*-=tLc@i?hzW7tLkmG zG<)?n=+)aG^;Y#TsCPN_AbHA|@{(rsu_1YxH7;2vV-z|Wmv~kjeYY3(XPlv28D}W3 z#+jt)u@3t)jtzR_80FPC=CWv9BCp<1YdW_@AzgV{_5R78GQNo=ZgQj`6+|pxmSzZ2lpAg?G3kz zpZla24R(0rFU2!=y<_6iL+%v6;L}S@ylR%KmV zs;3yIhwqtBn|rG9>7&Nv+ji|~Jngjc`K^tY%*3~Q`cBAaO>FHsp*+?xj@OnbkM}f= zwv3|>#?d$9=(BNbi*anDacsMBjEQlKm2r%rF)>#>#V3roXoWZ{=08;a)3bQX;`zUM z7J4qkS@DF`w_){dSbZB---gwf4m7Z^P=_ zu=+Nvz74By!|L0x;t8v7!|L0x`ZlZ>x_3p1^4Pb1pSN<=_jTNTa`>lb@s`Ev$36@H zK7skZ6Hk5L;df7dru5qJi>&jC1nNAxT8q+J>(n!T_4={N zuV=4fJTjYk->}`6TK$bbcy8uBe_UwX>-MhsaVP!Bc-(-a^TSHhjfcE*LH^0try760 z@S6OChqgAJJ@&S|-LZGh#8$mu+?9X&)$Y^aSZ;kg)-O>W?_(VAZyfC!M}Lf?pT^Pu z)V0evw%0hu!Rp8O80#C#wK1Mn{>mDSd+2-mRGqt$`xewme}3rw;reqLm8!n1o34NI z{o(TudzHq|shb{i!u?^Bk4`B)UbjyA#R2z+<3F3U{9F9WFDJ|#QM1Ip%a=@BKmTTx z7mSx(v{!!ml)H>i7;;v=tj+}EpEaJGA6~PU@vq*$DZgjeRgI51{?2@z&ATRi-y_e2 zW1Sq1*BZxr8b@2k(Ffz`TZJp_HIDuppLY1crE=Q?ZGT|@pV9U}+mBkME^QCA{hVdL zOUi8zwEdUWx0epx;}g4f;**b-HgB}VnDL3mmg=jFTg1fwr+!=S|Eu4s4{IE#@nMXA ziM|n^i?QAt%<06$U(e#(&&A(g?0+xrKK9!wKkHm$X>pvhEFWXjAE@KzG8%{HZv33P z@pG>6GuL`{w!Uxd%{)%y>J{$e%9r2M_kV2tck`nk=;z#Db0zHB+&22Ga>n^8U!lI6 z2N8$w%pYUiY~J_nd%A0h!wT2BI4{4p95mT`>X+@5bf5D5OS*sg-zC{C|NrveFsb-czOE!c%l9kE|FWI(-;b_04O_81fn$B+ zc%KsG@&3lqu5t9oIQnT^wuAr1<#ug~z1S|=tNO&j7=N)xoftP`+J`;LX*c#@;(seoYbd??R6Lz`4`1$G{`4)@IIi$*UK7MV}{IoF*a+rVf-!T85dN9{< zJMFI;|aZGyd6o~XQBKT-YieG=WLe1Ee?{jwdi2bcf9*@Mg1nLW6CKeGpy?UZ=` zyK?KdvA%JAF^(D%NBzuyjJ__mQTiFQi^j1}8pl3q9Q&kk?32c^Pa4NQX&n2c@lU#@ita1+NsCGB zlQBL&PS>PoM<4ba-z{nE+h|jb^&BbJbAS(XunEI4!-ye4R zgy8fE!RZr%(_JXB=Jg?#GcQ(sV~r0f*SHbZcoNn)6E3&Q#-FgprSQdl*1VcH z#&R3S#`=uItvtrZIL6I5#?v^)S$;AOH;&`*q`W4xTnoqgjMqLn?M?1kx~W)SnzR+J z{TI_s`8NJbY3GQ4Iku*6B%YpKobg|Aw)*_mRNr&dwk^MBxzCvPApSN@m!U|#Pxy+w6|F!oC<$BM+ zdjG(BFTr|W!SQ`=bL#j$H(puu^ol=~brs&LYU8&#z9(l={?qqsQ+;<>M>77u{(i;h z=+}|#dri5%<8b^g&xG~ehczC6HBNwIyK*>wmyI>vh~>4mKF06#+xsSZhr4kp@AIJd zIp2=R%fAuyTh)PeZG3NA{W#Auj`L;XIL|VU^DN^y&oYklEaN!OGLG{s<2cV+UjEY> z&hmLyj8Ek}BhN0*v#dPMvyA!X{-ga?uLq#MbOl~x@b9P-;J2W*M7F*Da(}k5&Hq$C zsrvdIX>3C|9Or<`_3D(ndF#J~uKvF}*AV@;eiGZb0xLdl-uk_|SvPN8uHEIHZr++Y zjdbcX(y7x(r%ofCI*s&loiO*5rU*vIsJ;GgX&S$y`-<0^20$!rfSVUD*Sk{3&5Q9( zx_5k*?wz(s_f8w7d#CNvz5ldl9ruW}?@4U6cLrbtbI>-W$sz4Kl47676Kp2 z{lxU@@IRw($M@}W4N`|)>xNa1vGWe4$G2J|todYx%Q+>!lXHM;l~)1YboNG}-{?xd zg^kzVJZyWaodGFr*rj8*u!Ws3DCryl8gF;LprmsL+(-E<;Ia>?d?@>t$~V1NV@#Io zx1|-Q{GajL!3VE_DYqr1EtHqrn5vECwx?>l@>=*D8njpEN@Ck}-h`OgIh6m6t@5>K zX_jkv{@Leo{I~djqxYkYdUo(Xde%Po$o;jPC*=F`Y($@b@HgT$Q9o7_7-OsZGiF%M z|LikFv_CvA6Er=sn)Q^Uz$ zADDjqL{;(hK39i{gO5m8y{TidfA8zUHJ=`zUb-5+q?Tg<$bz3-e zyK(6O`?V|Tb-pK5FB_MB@Ze^}p7)0^VfwhV(Po<#jrMvdgyY7fkDb@HIR4o`h2u{> zF@3x7#>FdNKN+^Uni6;+r+*h3SoVNYDRS%VPd>uUorTzrMUr_0WystEaY1Z@aKV@lE}kLZ64*r$hGY zP;Bw)P2uVGZPR;~Zc*IU<(5#VOUv|~Bep2Ie{*Ztb&Y1}$B(x!u1{_cbLTcmUs^@_kYg@ed{-bvPpEqq=Jb&6_X7|X$HZJRpX{9K z{>@qrO=b7|9fzgzXYla-mixI^?-8l|uk-eZp zfBe^T;kS0?L9L4O_Ie{MD)TpowJKH}`9|=+!T;30>f89A`kwL6cfaXP(%ojZE*`&p zUfAe2txyiu`Z+t)+- zX@j(BpEkv>FL^DrdZu35VBE&VsBK>j`yc#GY1ZVn#SQ5zp+|$immZ$ENwMJ6xuMO4F|th`t+Q3#prWi4(I&pozfxiw=ed8TK)?RB5ssu;h|b79qX zFP1Ldpi6PxhR=j^9-LD;;=<0wrF%XZ4j(zEbnf6z#dhr<3u|vbr}WuQRmIU4|1msz z`<&8|mv$`f$R8~0yC&;-Xl4=qbllw1vh_L^e{VT6T>sE(rTW`;EGB<=cWAi% z8>JI})3I26(H-H+g^Nn-eciG6b;H|2gYoZ|l1r>vj!iG03 zE6rQ8bFodG8^UqR>Za?y)VX-5*LC60)f%QvKiaZ*uHUs5|07n}s`%rqtBn_p+Ojz0 zt*h*JI(x4!MfaJLL$=eF>2|wyDb}7dIW(NwHXXQbm*UtDt_<~0YMvf3d&}aPu2Zf4 z++TJrw%*~YkW}|e=da$ixb~8(!X1AcoUS!^>!Q?iTF9Q>Gkt96R>kO@uMUr$IXr#g zxGu#lzrH50$MV>3wk%Hn>RRK5*L5zg{JK(}-?>ro?Ce*<83!Dep7dm!;@IHo)1S4Jt>_se3PR69Z!cR#*axG&fc_0w|+dV^M`TicEsA%~$io8{j7eu6UfzeFT+Z{g?@8&*TRIjGFTO2odg-z0 z*UwZHUB=xUJ|A^h`lqKm73+<=-h7+$XcbIK5@@#~rT-2X$zhu93AYrtUX6 zTzXln^sKjA6p!C^Ww`p34b$CDYEhiM)6}rW;`P!4zG+@0ZKj32-fWWo>A2>_ac!>& zpPjHy`r3jGi^V%m4}I@!lz!54!=lHz*M}>wSSvl~(hZ6Y-@Y*%Tpp90`(CqR%igzy z1(ViFmy}1EJ6}E{JbQbibo%)9i)HWJ9u^(HPTG3mdc~_7-xVHP&?KFbu2)>x2+y}`n?AX9)8g~nitu^k zcImL!n-qKAb${5qXI1*~XF5fE6PH0kGvUpb5uhDkt!b6%AC$95A*mZ0v z{qk2$isA3f3cJ4AD?Pki|FUCeg-6!tpI$VtNpVv-_rh8q)ugkxYFey&R}ubD9*d5g z*t8gOWC-_8+AY0%y>*NE@6QbDZ@Xvu>XdbhZe8vRpY|A*K9sCi+|=`)@YL1&rY#n% zSDe}YuF&ex;pus2uU|C!>+NCK=_Ar7do(M?Uo|6q^VW!T+`G++fjit1ZaTBf7jIBJ zyyV94hogq4eXBPtw!ZNCu<9-Qrbo`-u=r;1^ssNgVd*u;HZLyQ{F?A#uRYT4bzq;qjaMH4xbXMB3cx?FOFt|zobjfKgi{I8< z5gu9CD}DE_mc_`ilfuKlDWwg{{iJT)N%q@U|M{`s6ml)=`vU8G1ZUT7SzJGMuH|Ds zy693I^4B@WUB^@v7d&)}anI{I7Q4N1yYc$v@5`Cp?lG=z*0FeSdL@_h(Zf3y^UKeU zdtS0yRq^rQM~t6by;IS@-)!SQ4C`FvD4d68~<3}j=8L=cz)h1cI}AM zIuxV!ulWDMF71m?roL?DRn0dqnqOVvuin|Dc;ui;ovWVPxahUGa_v2DZdB~E!91&f zOUKs5ti|(<_bvY(f8OU!;}Z^TTa2Inobk@Lwks|^;ei##8;m`s3}{`no-yCbPd~O* zvHwApF^TR&oh#38QDja2Y;_tu)Vz3g+a<pPgN&;QrIL->A4_t$GFV_beYMmk+RffaL=$ zA7J?a%LiCK!14k1{i-&fk?;TiYU4fPurg!rpY`vzZc$wS%o^4QZa=?eu^?UDxOlHs zarU*V8h1Tr!(x{sD&+@`ZC0#1ay2WTIeNX~mFp{Y7I$r0e6mZ0cllzS;*((&KKF@6 z#YK-)_`SQ=EFSrN<=Ri5Xi&_!p>oeJH>_Xq4{^A${yN2zkF8?-^@R0{Q+j=D{Z@X` zZ{;T}KYyq{>ss!wYhiz_eBeI#g?}*q;x|k?Xb(*LXs2fJEPQ(i)e#8+b z-sV%;2hZ{W-{b=8U33!@}A>e1M~jl9R%}Ubf1|y!1HZMQu3vvz7;!~vZS*W3@J&9z&qp6%`2foYSU$k=0hSN2e1LsSYO}w6``O7B zf5mTHthTMH^*HP=G5(Ju|4Cmi$brjD{*e$Y(lu9L&?f-|MI-@ znotkp-3}NZhWG1k{Ql^(Lhpgyj0d*;O}OL6?TpVod~De7&ie+d2OpJ!~DZD>wAh1aZ?@G z*YWr9tZV5%x)%1=Dkj`>(Y*(T9hY=7yZ2TP4=1$5P3U>e_QqT7SQGAfy|3}lS05Bct~tQk=vhACn|y%f z11uk4`2foYSU$k=0hSN2k4bIzH{vNfqk|PTMh4TTpZCk{C(fP#&vhvB787@d*k!#Y!WW|vX}9pp+&gv&dP7_jXRo# zTOX|S!w)xY7#`?Q;j;$S2?IaMtp3pp{+cgsUMU~dWaIF9pUQ7GY(F5}@NVUIx-y@s z?@JFqT?(5vti++}gFa#OIRh$vFUE(ssSdnCo$u+NKDN4+zT~e}Ot|L(S1!oUyQ=cL zxOeYo@>aj?X+A9b?F0Eo4^)05^Dn(4U);a)8~ObG>+(sBD!-AhUzn0Vxki7hf5_RF z=XbW-!8mlAn4dhX#(2;N6Z07t46C9jH!#2BwHo6q?&+P6nOW&q zAO3CYya<)wSEJQh=evAV`F$NSrd~evz&=)g*FI0q?7n&Bx3=wtzn^(TkKR^Zbxot0 z?XR!=?%HpC*0hUHsPMH_ZS!@0R^b+(Ov!IJr1E=Qna|YsrB`c?%0GFp(#JXv{9V5K zLxZgEDL%wabzon|-^a7ArT^$!*k7yma!>VPSbZ2)ABNS3VfA5HeHd0BhSi5*`3B23 zSiZq4_!j#EJPB`1FZf4t3SZ%53u?JtoJIcZzZg6C9H2HtZyZ( zZzZg6C9H2HtZyZ(_p0&#;Qd*fzfFAbeM8?J%JtoWHGYFNCWkd9hczaLH718OCWkd9 zhczaLH718O)`I=FUSloF{aC9u#{k&!eM940$~C@)HBW>!_lGt2hc)+yHTQ=#_lGt2 zhc)+yHTQ=#r-LAa*@9m_Cn-J{H`U6QjP72nbK4Z-QC+tyMozBqE~{@_{Cvksos0gu zboDgRH zgSjHix(MG7nDr9AH?ZOlvu42e24*dR?+{#@eSrJ>zRfxc-y6zVU*S9S?S3LZDVLwH zZbx&?DQnDq?ielY7C z%n4!EKbR}Rtcx&Cg;_6QZV9W6Flz?P?P1munDfJGJFK?DYCEj9!)iOMw!>;W?Az}9 z59=t5YpKKf3gca3B|l;L3CmB|x68Ax<(|40_SY)@+(+?;6@OUqhZTQV@rMoJx!mPV6Z-iNoVLl17PQyGC zX8nfwC(ODI^HP}g9_Fhs>p;w7X|HU-vIWZ)EL*T_!LkL*7A#w^Y+;vmg>oL2Yhl(K zm}kPQLook@S)X8D3bSs(d=+LrgLy2>ItTMxnDr0ly)f${N0;ZrFzY4EpJBBTX3c>4 zGt627^J-Xaht+miZHLu%SZ#;Zc35qPecOHiVI76}Gj&*BVO~wFgYVfhLBc6rvd z+*8-W{#wPK`zZdf;twnSu;LFZ{;=W?EB>(J4}0G{%Ljau53qcI`Ufb>|@5U?-|EFX&n2iaqPp!v2Pp4K5ra<3&ycu8T)v~er4sczZu8)8>{X3thU2y zJFK?DYCEj9!@ljl|HR*p*^0j@i@E$HZt@eBpRjM2XI+b3T?^}4SoObspOyJs;f5mTHmtr4`@S8=HrC!a<}r?AA>%kkGLB;><2a@=j$9D8&M{Uzd3JG}W94!DW2`t+M{$M~XIOED6=zs+h81U6afTIVIF9AaZXDx%=ef&I zVkkdh-!9MplQydUx9_tupG%x8S=-}WrV@wBJl8nReT?Ir$T-fGjN=^2IL@t%f5mTHmtr4t8c^V+pzE3ajtFc zjq5PRaec-(uG<*L^&I24&SM(J z4=et#;twnSu=mZgd>{_;0hSN2e1PQxEFWO`0LuqhKEQE3)8ZV@7Z}HL2gdO{f^j^j zV0?7t{DN^j*I*paI~d1v5cce3i?+)aEL*T_!LkL*7A#w^Y{9ZcyW+aK`4G=37{~Jq z#_?Q(aXjx}9M3@*$MX@!@!W)Q)an~Y4ZpG4h!62>h?U1PBgSewb<}oPZHLu%yU&k^ zGxdG{iRUlOZakOqoo69GiJ|<2eY-sWqc(D_;twnSu;LFZ{;=W?EB>(J4=et#;tzY@ zJj(}SA|GJ+0LuqhKEUz;mJhIefaL=m_f|4E?ztGpy_ib;D`!%S|mHdR|CoDf<-!9L(7Q4C@_SY)@+(+?;6@OUqhZTQV@rMdcL!{@gg~(v72D-8kyl zjibKZIO^VwMRWsiU^TYCEj98~=znQ{VTWxR+{n;~wjG zo`w7*hVm2k?ehGO+Q_wvKdkt}ia)IQ!-_ww_``}ntoXx}n~X2UpYIgF#m!#HX`jH4#RIBG?VqlUydYD?_d$rf#wEm*c- z*@9&YmMvJeVA+CYi*`kghxrh7=EhNfZX9*##!;_s9Chr*QQvMHb??SeqhcI2Eyiji zK15B6l}D|MvD!`@wH;R5VYMAr+hMgGR@-6UcHe*E*$}fEwJzUz7V?uA%1_w0%kw{K zBiAbau;LFZ{;=W?EB>(J4=et#;twnSu=mZgd>}sZ0hSN2e1PQxEFWO`0LuqhKEP1} zW^s<%FyrZ!vn0k*OJ*E3X2wx_W*jwX#!;(g95rnA>|~3!%N8tKux!Dy1pj=Fc_sD(3*+Bsvj5g(#<&dQ^v&RA`y zj@k~Z?XcPotL?Db4y*03Z@ce5Q9EaLqo(dV&q96@L-`5&c6t6sZRA?jfz@7E?S<7| zSnY+?URdpg)m~Wbh1FhI?S*}N)gLHVe}L5=VD$%B{Q*{gfYl#h^#@q}0amQw?~AS8 zMby!I71nzd)_WD!dllAu71nzd)_WD!dllAu71nzd_U~06L%nmTqjwIhcMhy~4y<<$ ztalEqcMhy~4y<<_{C)3mjd`e}@f)o18?5mgtnr)ij~KgBU*k7e<2Trk-+T-;wxN#3 zHn7Gvu*Np9#x}6VHn7Gvu*Np9##He4jTJSwqK@W?u;z)d=83T8iLmC0u;z)d=83T8 ziLmC0u;z)dpC|elY7Rvm&7ok;p;;66nC|K)JuwRezG1OWOb+lFkYpn*>S`DnV8dz&Ju-0l|t<}I< zBZ9wg?MrLL)X};(taWc#>)x=|y)-weAgT-5b`rH>`DU*spv07-~(JI$9Hk zwI*D-)^wh>{-ZTv%C#m8YfTu|nlP-jX!!fq*tI7`9qq5d+FygUzXof64c7h|to=1u z`)jcF*I@0h!P;Mg{r;MdVQucwVAt=pecxW5_P(jFeSCOKMPp-o>)OYsT>JR2_VHou z)Kc<(^K0f8z$A|qszK>yT?geAl@9AsbpK|T{yE-{6y$~$D5G=hAEWHpc zy$~$D5G=hAEWHpM+itd`7oyzjg?tQSY-ds@#@skQ3*-2V?4I%28OLX89G|tZv^3l^ z_6;kKF)@y@GLC&LP+z)4Sh_@5x_G1VQ^@@ zQ?>D~yX_jj*(){v#e;i>p%WA1#si0kmMwc2KQ`;Yu>ZT=jQ=mjz05~628QJWtg$z& zu{W%-H>|NYtg$z&u{W%-H>|NY9M62&d?%g-GmdA(jN{oc<9MdbIG!~#j%Uz}U{OMVP zvUXqXoIZ8R`T3w*24yo^?V~e;+0@zlq+_<8nD;()V3vNiZ@PB7iTS(}YO;Fgm-A;9 z6Z2o6xMMcIYX5YnBQDSDY_mhw?W+UQXFi*huXn_NjJ%q6&Y7H#x~;$QRkJV5SHGZV zg**2O&yGwo@@if+wR^bx)g&XY=HHig35Sd z^R8u$!=tNb8F@87nzdTk^Y>XsUd;#p`f0v&)#{AAn)|&lKfmRu>WsXa`HaW%wV$od z$g8=u;obRKZF*+p)jVQ{tMj2FD*jxT?ie2FJ|G)Aaa8)7t!qNx4g<120}n_~XfrTu z(qcgN#%Cj!KgUJ~?VmPSR1=2I>zCEta{u(ipVfq~uIrnvGI(UV@NYYY%TDN%y)%1w zT54YtM(nzM_Tcn=(;0Wygh$fe*><1rot`>=V0bj^m905@X!`VdgTl~#dS)B6-z{x@ z{Z8SfORKZdTMS7zd3bQRZE2QOFQ`fHpFJded1RK|x?lhFXVZ5McQ?qgNi%wl3eE9d2II^vAH!MrT{ML93`+g&6r1$)O zP#8G7+X`*m;n*$HM+OZJO1RlU|WedLRQ;nt_SWe1gWs<*#nGTAkG++o_yW{p%LZ z!xL*I+5B?e-NE;-6?VEb$?BGKs;|~|l`y?sDcg9#%cZW>i}NS%C}nNSIn|GD|4e>w zDa|%3=TtxV=6mzs&rGux<(%pt9dmVleWxtjpqx{E%-R$3=g!TtFS|BL-~947d5`&7 zc5OMQ`l0=f%O`DEoxM@csXk}Y!TE0GXTAAAECQm^`sZ z*0_Gh^qR$kL$}dAvZu?rj>kSYBs{r$<(;qZ#sB7AG4LziNIDg>w*^FVYmrgomlQ3`n-r4Xzua+7wZ56t&)hm1W+?Pw6z1=J<=-M;; z@U$08bw)Q11JA9_nvR}R8hc)Yu*RmE?RR=C7aJGdpqh#ifOH{+LhLqgS^0 zrVmQ1rFlMX=ib@Z3qCEKe*5kD!4~)AHkM`enzg z*&yw-_7(Z00|#W!{Ccgl+lb5Zp&#s!EpD_VcPA!$kB)3h>M^6}(jXJ7HTIcwQd9(6+o@cG!?0;&1{!e`u(XO$h?#i1#m1g{n zfH$Vyoi}_m&G;Ju{r8!fH@Pj%_!|L_|MG!+&bevE-w5b-{p@_7k!i-?2pIG1^Ldl@ zX~y3Om^NX4e*4>{jGX@+E_pBSdwD72Zv?z_+~4!MJC!p2M!;JO>xF^K5-Xoqf6Z{w zjfvIo`gxPE+kT1NXX%L>hDGZpcK@^X*(jX(To1Ebb;PD2y|nzUDEqVjIqk#4zvy9p zZhCRYaOQv>=Ksq_bqeQn?P1@JHJWw~W2$;&MIW1NAcnQiW_znPyA7w@l)}~e?6C%3$|2sY}p54d& zuFU_?rgKJq>^AkLJ zFB&%^U-$J+8TqlFzw(}Zm06uK@?&55=&Zce<()F}W7m0dc7Fd+oig%c=chfN@6o4I zMtD=QsQ~?>Mk=jpuC?_PC`(Mtk=^A>It>Xz?Ae(d3AwF>V%+aV)A_L7U6 zhwHxVkdYs|ezRs_P}v{yV?WrqY53FVjv4u}7hcvVTsNg-Mt-jQrT|b^JI#=8CF}{Mct4wmARQ+^UTH*cZ>8mp`yhr;PmA z4^DhOU$A|rjQrR)&!3%-D#xGv*k8|?mA`sfr;PmA!)~}If8qX48Tqjro;4%?+q_O0 z`LX|U#tr$9^7AD>_Br=llh-Lfck*K&vei|2mvVm~KX$`ar{rI^>TK^c^&jSjG5?0m z<6_PnM-$p0&vTNI{zUO^skFD?~r=~NTKU3ijEv}q->T$iT&igZ7n>pz4?Tzp2+8}@a z_CCgYys>dUGU;dhN%gk*$zSw0e)O^J^R|n3Fy65BpnTI$YK(tOTktdH;jwFDejekP zx5qf<^D&NjevD)OALE!8$T;Q;GWLD7)OlLI@u;3weqrm5`LNEtvRP|SO3#_T{e9Ja zwlr3(zU=wi)U)EroZYkPFc$T!I?O>ls}61VtUBetZM*#0!KzdKdy2x|leVZntiB4Xufpo9 zu=*;jz6z_a!s@HA`YNoxiVvP;mvY&KWfzuRSaxCAg=H7^cJ&*_2mQuj{lo*STHxBDJ4(m5g8)XZYEm*c-*@9&YmMvJeVA+DbEya*>#Sm5uVZ{(u3}M9(Rt#aq z5LOIft--?j-og6bS)EEgu8f%YXRT`~*R`;&g|)WKeZ-XO8wYEh8P+;8taWBs>&&p$ znPIIn!&+yCwayHCKlSaVTU^IkKLEWA0hk;=iti{k77(aUW^kU}@gqFDf|UKEyI6qa5TmR=N=UKEyI zls3v1EL*T_!LkL*7A#w^Y{9Yxds~Vj<%%J!7{ZDntQf+IA*>j}iXp5R!qSw&(pAFB zkplbY>si+lD_slgT3EV7?jxpL+DKU1NI2>VOR)0fz{-;YD^CurJUOuP;DdSy;MRSh`u-C|j^>!LkL*7A#w^Y{9Yx%NFcyDTb6QhOlA? zD~7OQ2rGuLVhAgSuwn>HTMJ8H3QJ!K`{(Of*AgpT3;S!O1?4`{g2K{*!qS4m(t^U$ zg2K{*!ec7B-yD_}6qXhgA3Wp3f+3BrrCdJ1@&T3)uzY~!11uk4`2foY*vCX#Wmn(& zzqHDfOREe^s|-u43`?sFNBKZ?tjz zb{ofUx^ev08^|JaUB0!Kk+Od@J&9z@&T3) zuzY~!11uk4`2foY*vBN!gUp{eKQfNR*@9&YmMvJeVA+CY3zjX|+luRE7U#G= zW*pbeelY&JmiXve*k2phLhU|rea|?q`x(deKx6$qW&DimhgKff6^-M1qj6k^G>+?& z)=xak2YizcuzY~!11ukm&ez$*&v zcAvOkU>x@mjN|@-aol$>j{6bDai79C?q3+keGTKd-(m6eEFbVqKEUz;mJhIefaL=$ zA7J?a%LmxUB<}l|KXE_EIPMb}$NeMYxUXa!_nVC4K9q6XpR)GK7SB|+VA+CY3zjWd zwqV(UWefJU;=Z2Qjr(`TabNETE06o97EjOe0pH{UEFWO`0LuqhKEUz;mJhIefPGBjKC<}}_m_?1 zzO!-Mk2a3`)W&iD+BoiO8^`@_Yp-k(2ibyU3zjWdwqV(UWeb)q*xQOa0ka$R0LD=# z@PqN!wZuo)!v5N*k+Azj?SygER2WCCg>lqi7)Nb}anx)WM=ghO)OZ+2or%TMvwXle z`2foYSU$k=0hSN2e1PQxEFWMWlc?V?f1<9#IO;tr&prN)W3G+*5G#+m5#y*QF^)PD zYp-naOl1p}Em*efxkp>DY{9Yx%NFcyMct9vjrt`0HBQsB2+=ZPZ-ZeWDi2 zIBK+vqjt+UYPyW0*2_3*z>K3d%s6VsjH8y!;^|pF;G2Aa_>GgLSd0bv>tx)l45NX%z8!W$FfXz5u&AUjV!3tKU~fd97$r zqrQ~;OGgSzM+&b@4V!d;*j0`)SUJkzm8rdq-&u>l^pp7D^^+@8yCwY_J}5^StQ=*q zkD;`bluJtqOG^n$O9@L$2}?@}OG^n$O9{vEs>MgTLCU>uaAj(i;yQ!*qa0=Uqa0dbX{BIkrC@2L;JBV|@sTcwa_NHLxKC$wR;KFO{Lk8p_nHdjDC7RhQ3kI}4N2TzHobv#Ao$>QAS-hZ zTKo7eCZ=0Zjxx%945Q9rCgswEz|w@k(uBa$guv2-!0}m|Eonk1mlgt+{sH#-hn2ba zs{LzxP>wQKIm%!kLunx>mlgt+76O(Q0+tp6mKFk*76O(Q0+t2<*1kXN_x)Gqo}>0{ z@j-v18P?xuhJ6gB0iawO09YCTSQ-FW8UR=t09YCTSQ-FW+5=eo-LT*9*4hi@T6=-D z_5y3|1=iXNthEj064m0`Nr~Do$=Wn9&JAwIIsr-Im z{)Q^QE118n%I^*4Z?5t?g!x;n{61m+Mk~KtxNg;etNA^{{LNB+=P-ZEly@S$GWR02 zpNri%<_T~d3mN-9CT#$9qz!SuQm!># zSZlnn)_7s9@xof;g|)^DYmFDy8ZWH1W#h`+*`ATsHYxXOo3*{>=6^eJ4Z-}0YYWEO zE5SGImB897fwflxYp(>>UJ0zd5?FgBu=Yw|?a{z~jaqvIl>0q`+FrZ%eIu?RSWM#D zg0c1-@lAVz_keugh-(NI zleo5EyfXK=jQfbG@77Thca}eK>!^u4%b&Qj{E0iupSZL9i95@mxU>8#>j}iXp5R!ajzw#j}$w zShirfyCt#NL)UF z#N`u6+?sac_5~8{3lJ;$3CmAdep;RXTF*~@Y#X)K&3(kg&HLtZ9V9N-LE>^9BrexM z;&L4%F4sZgavdZt*FmB-Vz)M9Zn28_B4F8q^?YGHUs%r<*7Jq+d|^FbSkD($3}M9( zRt#aq5LOIf#Sm5uVZ{*kF_bN0C|j^>!LkL*7A#w^Y{9Yxdt1JrxP79;?Uf{MuOx9f z5Ry2C%($n^fsnWy2#L#qkhmNOiOYeIxEu(H+xtk|{!ya+BVr{#VfhKmPuRE1v#!Nw zT?_kb>PztV^`+X5p?`L6KQVE8YKhxZ zOI(hK#N~)cT#ksu<%mdJj)=tNh)7(Hh{WZHNZcM-;`SL6?K2W9`3cKUSboC3U7mF< z{YTfr{#yCKeY8&pYo89*J{_!mI#~O3u=eR-?bE^9r-R)-UE*0j;G2AaPxWt60E)it1rRoOR)M9{C$0?wqxj@o!fU#+}>;A z_Ffa0LnCoHG!mCXBXK!2lBi3!ZWhiOZpp#QCh%cl*(a_M?fF{DkEvEI(o2 zF3-A_{-bMQf31ArKHATPwVw-XKNr@1F0B1rSo^uK_H$wF=fZA3H}NbV@J&9z@&T3) zuzY~!11uk4`2foY*vF(cpD*o|Em*c-^(9z+307Y+{;%9GCG{oB)tBJ!>r1sAL;viY zJ|S^?^oiS}Ph5_X#N`-CT#k{%|;`!&zJVf7A#w^`Vy?Z1gkH>>PxWt60E)ie_vm!?HKxJ z=X5NI({dzE%aOPoEQ!m(lDHf!iOa!~xEw5r%fXVk94v{;!IC&_M&k4>iS#YRN`Auf z6PBN_ZM5BMe@ zVEF*c2UtG9@&T3)uzY~!1MFi`o6nc_$`&kJu=*0Lz67f;!Rkw}`Vy?Z1b<&&s_hv1 zXXo@ziPQWfPVPcL#p2X$qNnEa;#O3NqT&|wP z-oZZzObGztmg~s`NDd>uwn=+hOlA?D~7OQ2rGuL zVhAgSu#cf^@$6&^mMvJeVA+CY3zjWdwqS3|_YE#laFDP;Of)bZ6 zC~^6M5|=M1aruH0moF%BTCc?E zu%0ih=L_rk!ipiR7{ZDntQf+IA*>j}iXp5R!ajzw#dDD@ShoI|&&&4{r=LumhA?p& z!o=w+lQI9Lt4y4(GI2SM5|`sBaXF3>m*XfwLsZrhkx!|-E?3DD1v_13B3&i1lAo~r zgykpf+vQo;a(`V5`)j332HZu z{9Ra|l%JGK6ASx3=~>ruPhAW9YvX&&?l1i+_mqAWmVOnMeifE}6_$P#mVOnMeie@2 z0(3R{1{uo-%H;zrA7J?a%LiCK!14i>53qcIeN1Ze`O;q5f@KR53qcIeN1Ze`O;q5f@KRGQQGYwsWVN!;WoEX_RZ+vQo;a(`V5 z`)lO`_i?!dwQp{kbC*l7meF;`RLs)$YRz5>meF=`b1&d+Su^78^ z3erbexyy+sJ(ZQaoOse-S-H!JC%u-HyK@TC-dMTLDG+D%E4a3wsqahf?1nTv)(;gQ z;-)&V&Ue86KAv?gZPB%`zg98fK05aV>)aEpb5F3&J;6Hn1nb-rtaDGW&OO0VZ)P#~ zEFbVqKEUz;mJhIefaL=$A7J?a%LmxUq&E8-?UgN9wqWIZgw?lU<$HwHw_)Xbgw?m< zsH3xZMqQ<`J1-`^u9dr-fztO{xyu53qcI$Z4Coxia=m#VW5R_<~t>a2v7yPS$TTVdrcr=recSb037VeHPO z>db`8qu+DMAI>!y`95?LFaqG;{cb53qcI_JO^aYU45H!j+&f;0Q%Q>mDdsgmpPU@_mmB%xH z#xCci&Ujk6JO8dTbXKl@Ma*manfiX^asudFp~W+v%QIFTVyL_Uu)og={9ic-bUxAA z=&w~y0PdrF8nE(dz{;lqE1w3ed>XLwX~4>-0V|&d?DA>o46OMhABeepfaL=$A7J?a z%LiCK!14i>53u41*JgjCy|M+%7OZ@#u=+Nve5$beHmrQAu=+Oa`?kwZlDIr1iOWNh zxI83@%R`d5JS2(BLz1{WB#FyIlC%ArcR^3B4^Hw!D@EUbL9u=35q z$~Oxu-z@CUzk8Nle3M;Rc466tWfzuRSaxA&H&=e$vJbgyZ!Wu(%PuUtu?qw@?XWo^o*~;CScjb1ra(CuE*Ew{2P|jFb zIb&g8M`zV3*I9K~XVqbyRfly}9oAWOSZCE?omGc*j@$UZ&MYg3w)yYQfGa1tmAkXd z%3*Hh?kux%o?E#)%d8yfR_@L+=Q>}EKRT-pyR+&m)X^Da>gWtItTV{4&LG1&gAD5o zGORPmu+AXEacpCL#xbX{&gW9cozGQnf2$McIL7YWsQyNPmAiAJ`kMk)?#_+sZxC2{ z9Jd?m3^G2rGswBGqqC*d(fM3h=W}75&xLh97uNY)Sm$$LozI2i9LoHOb6aDbyQGdg zcd5UTVRhVjK>bY(D|hDs^*1=I+?@y1-|Vn*od?90&QzLj)1M3Fvj7^>gX&Ob#$H%)_FQu=jmXbr-OB#4%T@( zSm){BxF&4=#I<^3os*)DJ13>T*<^Lx`JLRI-^tzi9sNzHl>4~zJNg?^R<83q)X^Cz zSZBdtcNT1gIy&P+9i5YcbxsP_IVo7@q+p$sf^|*`);TFS?md~GaZk`#=U=Gf&cEny zpIIGuE<=AS&C1=m4E=32D|hEI^tafoT<0>drL!%t&iKIYjL!;nbasO}I{yOe{0pq} zFR;$Pz&if|>--C>^Dl7R<2FB|_P|)@8mOal4Y1Sp>u(EMeW&f$-y*bfr|s9@F0^u| z?bqKrv~ua~v8A&cusgf4QvYUj)Y6!5QR8GRy*j>0uMRuSw*E$^)pwe0{Y_6RcbaYe z4Nxn0nr;2fP%D>?8e7uj!%maGQvX(R)a;>mUEy!kN{39j(;?^5;!-{)YOP_XkNyAt z+qK+B8e>>mYuIV6SEwTmEp?r9+0LLx!b8hGSdMBC3tX(w9>1^o@#%)p7b# z{T*s6ce=-a%HM3o2WdxPX=q`mp-tZ=>}ox24U$2Vd(~8=>}ox z24U$2Vd=qOr$^E|+2Y{zV0yP(xzj1>TVUl*r=)L(l{=l1zBN`Zof1As>jf)^E$lRJ zx#sVbYi$J9+6b(*5m;*@u+~Okt&PB18-cYp0&8sq*4hZHwGmkBU9i?hV6At-TJM6j z-UVyD3)XrUto1Hf>s_$cF<`A-z*@V2eGH}bqFj18Sb8~FdO28nIaqo*Sb8~FdO27+ zDA?(6H0H7A>vT{WJ6XBY=V+{D!rI@2wZ92#e-qZe6|B7~*zHwmPHk;*`;wZ2 zTe;hp)STVQ-M*ye_*U-rC3EddV%N7_Ia(>#o;xfZ1*|=HSUL(=Ito}i3RpS{SUL(= zIto}i3RwH&u=d1ZwPTk@OJ@j6X9!DY2uo)OOJ@j6X9!C_20Q(d=A;%| zrytYY*28aY@wY+teM31~DVO#M_C8DdM7i{Au=H%O^lZjI^6&FXr^L0=Cc)As zUBB+L%h#e|twqCHi-xrp4QnkL)><^IwP;vt(XiH{VXZ~OT8oCY77Z(JEv&U@Sov3B ztwqDizY1$D8jj!n4AxpSto*C6)}mppGs9YohP4)b?`lng{5-YPB%FNP#C-IGLD{II znuI#XPt2QLI4Ik1dXw;4GBKZBX0BCz`1{(WIB>1!R&&nE`#xN`=WQ<>nU8&cQ1)Ye z*e-iV-`{M>xr_6W^R^Dt9_yd&wP;a3x~faqxnsYq`oy>L_BT|8EwAsBwf*fI`Orh! zhw}$+pUoKddVbO=n}m7m_s)j*c{Ojmv{mT7Rgb6?Ikd%Ia!(6wjw;b|}Cbw)Q1 z1JA9_nvR~6k3FwJSYy-bto~th@+;4%8!q}Z%ZA_aV!rIXzvX+^tEA*%ZGljL$jUKV)fb5#I zZkW`xUl@AwfUN79OY=|OOT)0g53px?(f$KN*MoXxbK9&FvMDuT%&6Yk6YUy>@l`cp z+_Bqd6CPMI^j)ha)Vr`xHvXfAVe^4C;i!(abe6Ruy>&+hZt^ZmnSAN9zJ zv~~FF;{!wW!-woSGR&0ZZ6<_@dy&u$(Zdd}#Ut-5fFu*=yy zg{DQf>=zrf3MY503GLqMmc6z?z=_yHY4zo9*{4SxQ5e%y3fov ze;#!IPCbtdvfK3KUj_NI-w~$-`Pt|2aY6onQs>m5c2TbOQeSc4K8g?bSKP3xc;b)Z zjGu}>{_DB$?DV|+b6nK76fU}MNElU)KivP%yM)J1PqQ~Z8)<#7JWtLV9khRFu&5>s zo!2j`yXF4j#GloKudeHxtulCISopUc!(}J*$=;bgJe1nkgb}-LpFKEz-!S9un(#>4 zJKOH_y~C;F2Zl$pUfG(nhlZ!m8x)4_(=*$k{cfT4^*e=^E-lA-iy>i?hX;q-mS$P? zf|_vu>>=UHBeU$*{rZQWP2V}(-5|>*&FCF=++&w;;r(g0(YWfc?v1;IBQH<0!`>Vn zu1j|ek8~f9jh#3u{ATN#(6_^Ytk1v$!U=5#hD}-wusT!*z@;U_S6OA!h?VPG+(-Eb@spoW5Rwf%+GH*sycgl-;+W<S7lKFioj_5A*-!qdJ9ix>mkHYc%Z~##Hsl z4&6NqD&KrW-=O-JeNhv1pMyTxIq3e)S`H1ed;X5Yg8Ugge7_(+_v$@jx&L+E9=5e|la$vVX_t#k2dk-%Sif_2P=~f*&bS-$kxM&emtNK? zTr_S*zV7Rtva3(oFg$yRh-Rjlv$c zbjbGZSrzJEym8p%!VX!B%eM-vUE4OyIK4x*U!(0puX>w=rKfbrb{$&^FHLV7E-aVt z`f9Im{ltyKk_jEMN7m>c&Re)qs9V0zS|8Pf;b*l9?>yTf`@`5FVadhK!*ySF$nKrA zTd3cxSr}CIXZ>yW3=cML8vZo8WAB?=@%rJQ1s$_ihYk<> z+*L1}*rqBQcKV2L@LS8u-{q?8o3}=U_d0%@A9F=jcGH<7!WoAx&VMzxD*MAx!^6dM z=j9Kq(WpN47=f; z{Du2FWy8l02@TJhk^gO8r|hIj3`Ki|Pk`iFDwxhAhue(sMf>=h2#>Z-g; zxj#Jon^I`F>XiKJR-IQE|1(F6>vcAF)8BodT$&%N6aVgmpId$3+~M2z{D17-d6b=1 zm9X&^8d^Y*dCGubO9%)dX@-!xHwiK)KoHt6s0b!BN{gVPg2*5W`uQo)3N}Lwgqda# z5Kwc^%Zwcm0b6Fn)Iu{WEh5VJ)wAn7#ZGkvtc}?tUTccOPK)3t_+e0J~oZ``riF{X*FNLfHL6*!@B{f6jG3747b)!tSTS?x(`; zr^4>1!tSTS?x(`;r^5Z^lh3^W6Q8Z}=eUSl_io{#%(?roi0l3~-^_I|_OZ#ds?#$xQo!p6eJ!p6eJ!p6eJ!a0_EP-*u&1+aTfvEM0x-D?`I-zk9I zYl{6&0qkB=T%Y^I|1bBN((YbU?3`lf6g#KbImON?c22Q#ik(yJoMP`K?EYKq{#%^$ zGtf1@5A&GqYiakjIKO|+iF<2_>)u-I-dgP5TI}9h?A}`J-dgP5TI}9h`jBlOXtxj8 zK4ANR?E|(C*gjzUfb9d$Iq`m@-TMuDzhUpUaJ}EK_Z#+p!})$Q7GpOSHWoG(Hdc5c z?``)g^IE@C0J|p{yC)gDCmH*l0@yvtxIVvbVfQ3s_atNYBxCm^W9Jk*r`S2g&M9_I zv2%)@Q|z2#=M;M{VfSfc_i5vtpMkFNeVE5=UrW2M#rgenPTYe{T=!sO_h4i9U}N`S zWA|WV_h4i9U}N`S(}!&PK)Zdw_5s@mY#*?F!1e*#2W%g3&WZOM?cQ(L`we@)VedEW z{f52YaK7J+#n_F7jfIVcjfIVcjfIVcb1e6?)9!Z)VE3+Lzf%CacOCnk0@%Il*zXj; z?p??3UB~WS$L?Ln&M9_Iv2%)@Q|z2#=M+1q*g3_{DfV8%?&rtu=f^oe16||$Fpt^3 zmUdr@^ZVzVxL2RJ?$yUHKRTxA{u@1hF1c5qcK7OI_v&N!>SOonWB2OQhiv;myM4g+ z0ow;`AFzGE_5s@mY#(sWiT4}r-f!6Z4ST;~?>FrIhP~f#zTb?+*o}pag^h)cg^h)c zg^h)CENdTVx5fe2eYr7r);Q4a_ZMJm9I)SCfUR-Bb)Rs&k2MaoTjPMOalp`~3^p?_a>VpWXwsdk3xlnN!9zKA?_1(pAB3$B!Z|+!UE}+3&t&^r+I=nd{jv2p z#L~2zEA00#;Nf4N)O7D}>%xB51NOTf@T_IGZo2o$#WjA{1MPm-1NOTfaPFt~0PWrb z*n0qb4`A;B>^*?J2XMXzjKz43g^h)cg^h)cg^h)cg>x)(NV_@2<`A1hY!0zG#O4s2 zLu?MQ-(P^OnZifbnkj6}6!tp>u-_?w{Z0YwcM9N9_4_HX-wlDSnZnjg;h`M6_bqX) zBg58_;hdj=uJL`iXR>`Q?YgPUMhw@v>tMgD0$U?S zAF{1wquoAW`+)5Owh!1oVEcgW1GW!1=fwLhT_6AVz29i}e#72x*!vB8zu|np87t+X zE9EC_EZU8QjfIVcjfHcpI`5Hlzf*u~tgXX-rvR@1Pvd&OQ-F5AQvlch?{SUaDL{Mu zKN9WM*3oWl9bOdo6>~-^ z_I|_OZ#ds?#$xQo!p6eJ!p6eJ!p6eJ!Z}v`JEYL=cM4!@Fys2qPHxzjfc;JZ>~{)a zzf%DFodVeJ6u|Xwws;?FFlo026FaBaImON?c22Q#ik(yJoMPt`JEz!t3Hx0b*t%4l z^E1#jz7O-5?Q3cGwK%_j&WSar#I@!WTXTx7ImOnTVrx!u{j3pruAf1|^|ML*KgzZb z^vynC`+)5Owh!1oVEcgW1GW!1=fwMscJDXrcUWNWH|+g}z2C6+8_xHevB-(Bu(7bQ zu(7bQu(7bQaE?_!7e}7!XYjDKx?EpBvq!tNy0q8N_|aZJ`-khAK-gMcuCHqd(Qd6S z?bhmI=M+1q*g3_{DRxe=bBdi)?3`lf6nigWzs~|&zl?K!2D--gVIH%6E$zM*`~D~G ze7Ea?<*(PhyK~BFW10(AzoUHn`nx&@owQ+d%I>$7Pw#VA=lGr9-)uJOma^Oj?&`d> z(+16Fzjt%_=@oZ%4nAf5=7*i@%NncP(|LN#`pw9>P5IZ)-`9C{<@K9C4Vzmoyx~`! zcW$zNGy6AJm!&`ONawJxt=}y9_z%k&k3Qa6`StaiFE4$0S?XKQb|##%LG!{VFD*}R z@cYh`DerIgS?=Pp`o*ty<}b5h^LOv~m-6{n7b`2>vte_?6zo3cVB*Hc*eNRntf*X_=8Js()_~?J=dK4 z{McslC1=IG;ro#Pp}Z%peI~B8&)C{$Z0$3)_8D9IjIDjf);{C9ei(W9?S>Gh*}iHFM6mw=BK$Go9amd);Q{@%NT*fAPuA0nd(V z_Py!evg^$M=o~zCbaT}<_mxZk`ti<}&so2Dapn8VZ>K%hnf1F3ns;yfK>5zN$2v1^ zcz<)pvcD?(@BWzU*wN43=8kA?J$-(8e&UEyULD@NeDy;^+&sTf@ALeo!<*~&e4tS8 z^W1tPnkAOMw@~kM_}`Cg{(iAv7V3Sz@`JUSO?SDyQ1A1(F>5y)kG!Q&?{nU~b()J$ zy0K92bMdGDwz=k^Cfcu9dEMrY^?n@JKYq!mX2&zGi1)d7!_m#Q2VN5I|KK;)Z$@=4 zh`9fFA&;B+&N!)9;xv;ZvWxU|J~z}g1>mk@aBm9A1Tz)%)WlDX2&-kC{I80k@D!F zBb$59onMyO;P1;r|7S$=$8{bm-}?EK^7vE3n;Z9dxXgIZR^|Lz!<(y??0IeH%8|{T z^X@Oy*L>-=wVFdtyr)oK^VHw0-7J3pzZL3h&fI&QX4DUFFVxp8J@36uYwWFs`kGrO zysw$@shbP+HPbIyxB2u@*A?n(j$L)V=BZ;l-M_<+EOS3Sx|uTj>Oy_Z+)LMQZhYeM zLVeBacWls%Ir@@9ea*k#{{Cj=qc4oHEPcU-%^9zs8@}ah8#P~j?YtQ8eV-cFjNSgM zGGXF2<)J0VHRt{FS>=Z}?_A!s^Vp_q(%Geb`|jnI=^HmQcR8ora$I+<&F9B7mwx%& zc*t|t>)Hm z|2+D+)Uj(dyZ!q1=>G-VuhkrJ5zW%gBt}WCAojiYq=Hee+ zQ>Y1=xABV2N>??7nxK77U9p*Va4FOTUA^*3%|p-5Ez|@(aOO(Q=3{wk=j|zIE1Rg_@wFpIWt8s0sRU;NP-g_@viTf>@L_MTm+33|HwZ|Sd3`F^1$=&7rQHTxVj zt56fPRQG+d*kZHdGgRF-60UnxdOlknGrD0PDxXK{o|dp@DA8W`z(l)eDA8W`%tX6q zDA8W`*hIT$DADd2N;rS^AF9t;#P$32u;)tU&p5Q_T=jQ7*ZA2j|7|wV-#L87|4aCM z*LUngd7pUB4}GY6$>RR0d(6U~^TRcs^MmVNwYbJ}erT_I+ZtT=yfw^4w)ZOS_5s@m zY#*?F!1e*#2W%g(eZXgKH=-GF*+cQS{a3p`L+#uB8H&Euy^+z+x(_q#`9fS%_iaYI z=L^wZ_jyLU=L^wZ_k~8g=L^wZ_mM`s=L^y9`9j#7U~_`a2{tF#oM3Z;%?UOq*qmVJ z0{fkP*fW=K&d)&C_&(%0+t;twB*gjzU5Uzc|_5s@mY#(sWiT4}r-f!6Z4ST;~?>FrIhP~f# zzTb?+*o}pag^h)cg^h)cg^h)CEOSV^ImG4=n?r04!++*H^4eM>5OeLBRJ7+ascM}< zT;n-iTvO{BqTO@4Xs>k;(e622wAZ?cX!o2h+H0Lfw0lk$?Vi(x-%daCJ(=xmnP10< z^B8j3Jx7lIc#a(Q969Vca=6yW#A|EqOt{w6#Q&pg`#|691GW#?K4ANR z?E|(C*gjzUfOAfqU)r5t?EGTq7dyY$`NhsJ&hu+5a$+oOENm=nENm=nENm>CW0^zR z%^^02*c@VWh|M83hu9oqbBLWgTx-^1emxtIcFzXHo|lMgJzZSyd5N^w`nzcNyhPe- zyPlUM20GSBX8Z5}#kc6A;&0&UkID@r?gR+4h0H*#~SNuzkSx0ow;`AFzGE_5tUd zIKQ+zzu5W3&M$U;vGa?aU!3RHSmeQ2*jU(D*jU(D*jU(DIL9)Fw3|b04zW4J<`A1h zY!0zG#O4q?cevJ2$Nbh>>9A*za!sw{j&{#wrTvOmPKf8<*mGHNtrL&yJ(rdCT2~(J zp36$R=dxnYWyPM$ir-E@9T)SM?Q3awj5v=m_rY^-nYe^TG4UY4?0`?D^!_^U3K$wtb-8K4ANR?E|(C*gjzU zfb9de57>NS=NCJ_*!jiIFLr*h^NXEdoafhAjNMq+SlC$DSlC$DSlC!N$1;bsn?r04 zu{p%%5Sv464zW4J<`6q~xSjzU_kd^4)9#t`*mL-?=kR0C;m4lCk3EMUdk#PL9DeLM z{CKeqwmXNtt=Mz;vFGsPx6@C@#XM&FTG|~Wc8vLKrT;y*_SFA!Zf!mXn7OFAZR4Rl zCwZvOkK*3QXH#bn)j8Glq29M`Y+UU5*x2*2vFBrB&&S4|kBvPa8+$%>_Zi(?={q79 z$#-JX2k$HF`PJBSxv}>f_FQi4x!kz^JZxjn<;I@NjqA_VxW;q2X|F$rquq14Y4==i zTz^N$HJRqf#`Gn92BmfkHVf!#Pyy{ggu)G z*Uw*Zy=N2A?%71RevXT4Ja>zB&)vc~hn~AdyXS6U&)veFyM;Y>3)jDyBbMiG(eAlh zxc==O*LW@#?VgK;>zYH)xaxUIwAXc*X!pz++C6gyd*%%G%o$wQf8w=uT_{}Fi^86# z#Py!1gmVr(PlZJSFUTO4#$1aQ%!Q{qejb+CA?G*R{>K#>=$-y~?o|8kn=j33|$-$nJgFPn) zdrl7aoE+>qIk>JRMt?lVhIY@f!SxwRTvMOdggqmIYwGiz7WRw?>=_Z*Ga|5OL}1T| zz@Eu~J^uuI{t3=G^!yXrJ^uuI{t5Q{6YTjX*z-@Y=bvEDKf(2xMU2<;Noet$JYL1YyYve|Jd4pZ0$d`)*gGV1@>GEoO9^87PNb=1@>GE?70@$b1ksv zT42w$z@BS?J%a*!?gaMS30(KR$GuVa*oUnj=NjwBvGwEF`f+UiIJSNqTR)C#jX=D= z=M~WIc?CG<(DMpt_q+mJYZl^tJgh+MHy77i|4X~| zzv-GzdTrR+I@+zR!?h1_jkR^OTU&?gSmGLM>u9%@4O=>sBKThc&lzX}1;_TMLY> z1;*9_V{3tNo$Kh2wZODnuRl>jAO#fY^FKY&{^h9uQj(h^+_2*6v~J^|1AN*qRz_O%1lr3tQ)f zt@FaxdExpqvtaAIuytP8y*NK*UGSKW!SYc>^c&59SOURgk49%u9ace%CKu? z*tIh3S{Zh&47*l_T`R-sJ1e_fE2G`DGVC5X>^?DE|7M8$!Tp4^yPpudpAfsB5WAlc zyPpud9|^mk5WAlc=X=ckgtS|?g{|Ad)@@&)17W}N@;_{@TKpIKm^jbfjTVxNs-pN(RljbfjTVxNs-pN(Rljbfi0VxL=KpBrMI z8)BblVV`GVpJ!p8XJMabVV`GVpJ!p8XW@Kr_-vGRpN(SoU|{!PVE15P_h4Z6U|{!P zVE15P_h4Z6U|{zrV4sg;_a|WYCt#nOW1pL2pPOT!n`57wW1pL2pPOT!o8x?MxCeuF z_h4Z6m0|alVfU3`_myGym0|alVfU3`_myGymEro?v%&6}#O|5I`Dc`SCTVxiBzDgv zcF!bs&m?xwBzDgvcF!bsev_h}Wn64rY+P(y zY+P(yY+Rh;_I`&WYw~_47rv=8zVpCZlVkmV`$<2YyWGcm>{>n7r2Gu(GXi3nAKc&f zMbhr~Yhb^B5dXQ~>4k2jTgJt zja~1>uJ>Zsz_DxK*fntM8hCgi&hF;=`uiyI?;1Gmu7UTx#x-8rUE{^B@nY9_v1`28 zHD2r*FLsR=yT*%M>&CA4V%K}IYv9;5aO@g5b`2c6298|=$F6~6*TAvsx7ams>>7CA zYh2@{-8Ek98ZUN@7rVxbUE{^B@nY9_v1`28wQlTsFLu2by9SP31IMm`W7oj3Yv9;5 zaO@g5b`2c6ev4fL$F70*y~Z_O+Fj$tuJK~mc(H4|*fn148ZUN@7rVxbUF*iK_hQ$3 zv1{PiHE`@2ICc#jy9SP31IMm`W7oj3>$li7aO@g*-)mgsrQJ1N>>4k2jTgJdi(TWz zuJK~mc(H4|*tKr#dM|dp7rO?IT?5Cifn(Rev1{PiHE`@2ICc#jyMBvZ1IMm`_r1n7 zUfNyb#jf#U*LbmOyx28f>>4k2jTgJdi(Tu+uJ>Zsd$DWaxUP%-kDYnQd$NA}@U&&m z!>)m2*TDN;;~FpRuJK~mc(H4|*fn148ZWM6>0sA*v1`28bL6n=z1a0$?D=xoHE`@2 zICc#jy9SP31IMm`W7oj3>$li7aO@g*-)mgsrQJ1N>>4k2jTgJdi(TWzuJK~mc(H4| z*tKr#dM|dp7rO?IT?5Cifn(Rev1{PiHE`@2ICc#jyMBvZ1IMm`W6v|e`J9u_e|K#2 z(BUUVUF1_=*rd7iu4BXbJzW##wXO+c*MzZa!q_!o?3yrkO&Gf-j9nAPu8m{Yhq3F! z_|HAhir2cvi(SjbuH|Caa@kiqR zx%J&6nwdxU)Z4nxmTO%9#IAp0*FUlApV;+J?D{8m{S&+XiE}<(|D@gZPwW~Xc6}JT zK8#%-#;y-z*N3s|!`Ssz_D}-Stn}UH`z~;5Pwe_9cKs8({)t`x#IAp0*FUlAz}U4=>{=*xeHgnw zj9nkbt`B3^hq3F!*!5xT`Y?8_6}vu+T_47-i(=P5vFo4M^-t{jCwBc4yZ(t?|HQ6; z;(Two{z<#*pE&o~^f2N zlbvIqo)o@$kN0%0+jMex=esYN`{K+VyFSVFu1{juQL*c&*mYFwIx2P@6}yg#T}Q>P zqhi-5@v*xe)|vkAJ$-)qyqTTPyxik$|Ko$@man#=&nI6nt<0FdMfjI{?Or~6)r9cf zFMqV0y?#&o^WWL8O#AKT(e4@}?|<8aGs;W%^|XI--kxR6S>xjx&!giS&zHkDuQ#qa z@xp(KbLS49yGirfeqRgwcNEw7cNF&TDD2-+*uSH&e@9{ej>7&Oh5b7U`*#%f?)``Paw-t7Ns&v}OV-WzC6op;VW%yvIH?d~VX z?kB%&_=o+Qr@irqwk>zB`_0bn*Y4O}_qAQh&yP5Zwz=N@-uU>{r($?(AuHgG=97GBQNdKd;L+T&M03SJEd&hea%)=KVA-9Yie1i`?ZYs?d0G2 zB5t;?rQNy1&K>@9&wiwDc^==+-1$3&*ZMmJ`#S~uI|chY1^YV%`#S~uI|chYg>hwj z|Ilt9uzkSx0ow;`AFzGE_5s@myx7E%%_{GFFwUPm_uq#%n;rUa+|T}wqo4jR!~QPA z{w~A*F2nvV!~QPA{w~A*F2nv_!2T}7{w~Aj1e+6VPOv$_<^-D)Y)-H_!R7=z7uetL z*x&Cs=Vzd6d>`_h?Q3cGwK%_j&WXP(iR$TL1RL{{4gV-#`9MNV|U%V*e(@{!NJe zn-KdqA@*-V?B9ggzX`E_6Jq}+#BZmc`JT-7wal+$#CeRl4}NALuAf=3pINY#dKY#L5W5D5T?53f0b>4a~4HmlwOCPfB1MT(! z+XrkPuzkSx0ow;`AFzGEIVa99?anWDezEh5onP$yV&@m<`85_}Hx@P)HWoG(HWoG( zHWtpY%pvXO5Sv464zW4J<`A1hY!0zG#Liu~?zP6Qt7F&IvCkT?&l<4L8nDkAu+JK> z&l<4L8nDkAu+JK>&l<4L8nDkk@Id`^T+HJFu4AO#*Wx_J+y|c@5zFUC*yl&s=SSG* zN7&~_*yl&s=SSG*NAw}vKG1F-uzkSx0ow;`AFzGE_5s@mY(BB`i=AKW{9@-9JHOcZ z#m+Cz^J^@|ZY*ppY%FXnY%FXnY%H8(nM2ymAvTBD9Aa~b%^^02*c@VWh@Cs^^HA(F zLF_X@>~m7=b5iVcQtWe5>~m7=b5iVcQtWe5>~m7=b5iVcQv7!M>A0B3Y+p;eW5juk zuIn!B_l)p9eqRaBYj?jmbwV@i>vMY6l#UqRY;*OQ;aR(H*8Jqu9ygn9(p=yD{Uf~g zsnO$_4Uaf0{DnyyH-9?loLGbMJ;}quuGub%^=HPC*E8({?XH1i*TAuB;Mg^A>>4%;Er!|v1P3`}(kZ`LKKWaGr~SuJL`C$829qyRXIh{TIb} z`}WiQmb9C5Y|gPc$L1WHb8ODBImhN4*Zg#)_HeyET;C^L-#=XAhHHN&@IJMl;oAQR zX@0w~dseZru(7bQu(7bQu(9x>ik0sf_s7y7_s8P;e=WxD{$bkPKaAZ!jNLzs-9L=o zKaAZ!jNLzs>wO-v+%rsjz2~Fdd8d7#YkVK(G~3tG?rX8{pRdpTq1`-S^MK6*HV@c5 zVDo^@12zxXJmC5}w1wS6j@?6!-9wJuLyp};j@?6!-9wJuL(UkDg^h)cg^h)cg^h)c zg^h)CEOSV^ImG4=n?r04u{p%%5Sv464)LNIm;3PPgZuDt{oAjFty93(DPZdquyqR9 zIt6T<0=7;8Tc?2Q-(3;Q+63C`-(b<6^E1#jz7O|Iwy&k#*J9s4U!VI!yLrIo0hwq%X%OBV7(8vW(r#mg{_Ce)`Q?Yk4t*?-cj8b(geTcZsdL#MWJ6>n^c%m)N>X zY~3Zc?h;#TiLJH7c`gRJ#`j?!vwbb?z82^AUlil*+fVyIyE(_^9Gi1&&apYi<{X=I zY|e4r4;K3^>)x|)-IEsor|Mp{aNWZeu6x_Ubju{7B&_(7B&_( z7B&_(7G6}boG>1TH(5nD_r+?h3meraNQ3UuKUEo zb^lnn?kfvh(@h`h9=~YMb1~30z7O|Fwy&k#*W&#Ci(>t;1hD4`gzI?%xbDG=_o;jH!gbGH%$>2AQ)6LcVPj!q zg=;KqENm>isA4%^^ucoyu;(P;y8kNjQ1@kp>wc|p-NzNK`@6z*-&eTq2MgDIV&S@f zEL``Mh3j6vuxCfmpF9@>UE}*OzuCT)c3+G0`!9;|_U)&ApxvBfbB@h9Hs{!!V{?wp zIX36G?gxu|zV3w!*FAFKx_2&I_tb^!Ub}GJgBPxQ^TKt{Ud*Ghm`7t_V_{=qV_{=q zV_{?AMHS2Wq7Rpre<-QN|i`@X_;KUlc#6ARbb|US-LDm{`?$h&e^2hYO7c`gRJ#`obq$@aCh`&#V#=h~}f_uscH_4t%Bef~D>#Wvcv9Jc9{^4bMk zxBqJAeafSM*rA+u=vM6~=j~m(MolRn+w}wO>(Bp4x$NpG<)+q_?altUXZgyvrk0*ap6woo>L~aXRbG`taIbewI(lxF2$fGBgl`i^VIr#Kehf341SL?q-vIx8R4Qv-PAU9&qgF5foZzwR#zug3d)Z%X){pPkkj z{r&C3xi&U?sOn_NbFP;(F74LmV(W9U^|{#kTx@+VwmuhIpNn&T&YE{pXUXqOiaZQo zVrplCZs(YfUKEoVDTPa_2r1VvPCT z9;lvlFzZd=%+GoH@9%N!?{Vz!aqRDL z?C){x?{Vz!aqRDL?C)0W?^f*Z*1p#a_TNhj^Ys>3rt`%U{3i@6% z*y}$Fvpz=OT>r$be`41^vFo4M^-t{jCwBc4yZ(t?lf9`_pK5e;Rgw8g_pgc7Gane;Uqv{M<7}yL-m^ zUQ=H?m-a#22iW2LYp%lm?UUr1n%lUh<~&^IB3$PvT<0!a=QLdBI$ZC8aJ_%R?oB1G zdsA_~X0Z1g*S$K0xb^>9xWE0_TvPvV#x?c-Y`Fek4%h$V;rf3+Tz@8n>(7dC{TULj zKYzmRfhVqe;Bl_|So(qun=@WNH?IHA+GCq_Px)T>nyofzKJmnH|K&XgyAGo6*@(FH zXM1>{^JM-fYE{TduC=jlh<59SuysS&x*=@c5VmdzTQ`KQ8^V594z_LxTQ`KQtHRb* zVe6`}bye89Dr{X9wyp|WSB0&s!nx+Czd9qX@!THVxpHK4=e+x4Uiv$KhHL8IQE|-* zKN;Q}cF4owum5;N^X!@P!`7*By>)8XIyG#a8n#XiTc?JtQ^VG&Ve8az&Zjkxv|ICt z>*vY_TN8?{3B}fgVrxRNHKEv=P;5;owk8zkdddE3B)O)3_Kf~m4@-&n^|N!le;&KF)m&q3HLjmM<9ch)X}9(qTYHYJJ;&CbV{6ZG{fr#%Y3(`f zbxk$e`>Vy~n)=x@uCeZ(cI)o3b@$l1du-i3w(cHVcaN>R$9e3Y;Xu1*IN!>=_r>GcK@aTwu?*z@Bk|>$97P)!&&9T$BF~dgc=C^|Md>AN0&6+C6g# zd*%}M%q8rZOV~4)aNXMw{i&bn!u_3(#Py!rgFUwgdu|W*+#c+?J=k-5u;=z*&+WnW zb8hs(GpT6zOe$PIo5wYte?q(GpJ2~F!JdDDJ^uuI{t5Q{6YTjXINuwdr9-=C>EPUF z&l;lLvxcx|4Pnn33NPe&P4yXijJ?0JcV3zF_2N1wcAXQu&WT-*#jeL<*JH8kvDo!k z?0PJAJr=vpiCyQ!u5)6~%ER?{SsT~iapC&AFI;~ohU@RjaQz(`uD@Hu^>=Q#{_Y6- z-Rs2iyVtwjO1WyKT(wfJdcPZp>r<|JzZ;15l&jwF2BJOXs`tBrXivFnrChaAu39Nq zt(2=)%2g}ns+DrpO1WyKT(wfJS}9kpl&edh+1) z*!=U_Z0CY@?_2C#VDDS(Tww28>|9{)Tb%orZCv_hTx?uyTx?uyTx?uyT%2=W|K{Od zZPmYp!u4;YaQ)jUT>qvD*T1#G^>46n{o5>D|7Ht2kHi|x`-^+RV zhq3oC_8!LG!`OUc^NGzTHlNshV)Kd3CpMqheBzu>@yu)|0a*P^>6jC{fxXVxg(#q+t@y1``kCT zInQ2CEU)j|2cIj^?sH`9b7bsuWbAWf>~m!7b7bsuWbAV#?6~k?=DBa)j77V1ik(yJ zoMPt`JEzz=#m*^qPO1q+$1@VfUnA z_oQL>q+$1@VfUnApRtn9Y~#{yTx?uyTx?uyTx?uyT>g?C9%<|zY3v?p?6Y|C znQdI!jf;(ojf;(ojf;(ojf)*49_(0oT<()6uKVP%`{c3v4Y2zSu=@?L`whZ%zX7%m z0$T@xt%JbsH^A;U!0tD|_LDivw$HTN=eL?iujf6zKEFR6s`2(6i*ac;&)7U;^Bk^u z#^xEDXKbFadB*P9z}D%E#g|Yg{|Ad?n}Y$OTq3-!R|}J?n}Y$OTq3-!R|}J z?n}Y$OTq3-!S<6m%C^t6+vm5MN3Z8Sy*|G`9;)&79gA^kH_zBSWAlv7Gd9oIJY(~W z%`r|mSd2@%dB)}$n`dmEv3bVk8JlNpp0RttuxA=z&oscEX@EV` z0DGnZ_DlopnFiQBVB|B~xU?G=8y6cF8y6cF8y6cFJ4QU%vGTY)*Mhj7Yk@u20=v%* zyUz`~&keiJ4ZF_`yUz`~&keiJ4ZF_`yUz`~&kfs8<|x}f({7*NY976w_w;(4``|u0 z+TBNo-A9MrM~B@R)U7aJEF7aJEF7aJEF7w5R1vqZb+EMd=C z!tRH}?uW$ghs5rO#O{a0?uW$ghs5rO#O{a0?uW$ghs5@iyk*;G+U;}S+~)CmJ@4uD zIQPN*mbAOy61(3LyWbMK-x9mu61(3LyWbMK-x50(JeYazn>S<8?wn%h6g#KbImON? zc22Q#ip?iBpV)k2^NGzTHlNshV)Kd3C(ijaF8MSrHZC?UHZC?UHZC?UHZIO_J@=1x z&;7%m`-j~(i;t}PX0iKbvHNDR`)0BGX0iKbaozhm0ejXWcHb;^-z>JDv>PF&+m_iYP@~NVqDtIGd9oIJY(~W%`-O7*gRwMyvw&&J1@1*P1lF(`-JQJ zcetj;4cGpJYd^!a|KU1Eos`>f?ay4=-Sdo%i;atoi;atoi;au(y)@Xd@)+wq7GrdO zHT|jgTeQ2sns)bBWA|5M_g7>0S7Y~AWA|5M_gCZkGbCcUznXUUS7ZChoMzi++U+yW zW6bt?-qY*z`{SV+Z{M*Pmv-}v%`-O7*gRwNjLkDP&)7U;_o(CgJEh?IyCz(J2ZihJ zrf~h86|TR_!u5Atxc;6kO*27aJEF7aJEF7aJElMm*TD^0?~XJTYGP;nRou z_fNFD51)4T;bZsVWB1`>_u*sr;bZsVWB1|X`ZsOFavwhJ?!(9Slex~e&$QcToX42$ z^}MIo=l91$HQv5sF)r=q8JlNpp0Rnx<{6u3Y@V@s#?~g_`WYwg|N7Y{Tt5?q>u05K z{R|bZpRL06Ggr8N?u$9iHZFNKE;cSUE;cSUE;cSUE_RG~uw&(MS${!X>o0KqJRW(d z>mlK~P7v(a`*Y&+{UH1#u^}ujlCk)s1 z!*E?!4A=F>a9vZ4xyv>#c{VOKE;cSUE;cSUE;cT9jCinP<#E+D@EC7h2M*Wu;c#7_ z57%}3a9z(2*LD7IUH=c)=K|sSydYfH_QTc!F!s9E9qn}uJZwL?2eR!m?e-bxF=l%` zvAiDpo_MIn+jlI+rQJMZ^Nh_iHqY2RWAlv7Gd9oInhR{r1-9k_TXTV}xxm(3U~4Y0 zH5b^L3-Xz5T-uF`jf;(ojf;(ojf;(o9U~s>Sb1F5l@Qmu5?r5GHrTonY+VVqt^`|G zf~_mT)|FuEO0ab$_?4dXNF$bYCA3>tg6$`Blx?4Bx6f}ik6zDvdVPL>JXGWDI~L>8 zZl1Au#^xEDXKbFadB)}$n`dk-47L^qTML7&g$dVM7+m*PG`Q}&2-p1>VQXQ?XSQ)^ zH!e0VHg34a#m2?P#m2?fA7Sf{u=PjS`Xg-p5w`vaTYrS>{-wA-tv{mO`Xg-p5w`va zn{zzaW6ycE{)o7B4^Q;p{4jUfUQfH%_%B?>iRb((b%t=N&um*m=j! zJ9gf&^NyW&Y)vAzCJ|ech^p-z}px8Q4Y#k`J4isAlime01)`4Q{K(Te8*g8;b&hcQ6J?GgvP~z4-rSbpB z{4ht^UQfH%ztuc?{Xp+e`%vY-?^ujWyYr5nckH}l=N&um*m=j!J9gf&wa?hvXKd{= zw)PoY`;4u9#^?8(DH^|ntbL~4+Gp~aZCu)oi;atoi;atoi;atoi|gM0xM!?4r`>vU zY`r=_H#GZwICERfG^E3*!3S-`M=b9M$g%$6k-U{;lTG>j!#& z+J`FteaB*4+MRdoykqAbJMY+e$Id%;-m&wJKYqr;9iA=WTGJZ#d>Gn29|n6q4EB5& z?D;Ub*4W1T)Y{va(`@6CXX9eyV&h`tV&h`tV&mdkLmhEFlZSTC|Gr)V#3g|vhV*wkN zcH?5>V&h`tV&h`tV&h`RNFTC|OS^Hgaj|i+aj|i+aj|h3d#Z`W($F6_9lA%OF^QvJAROtrbj znr>`OH@2o5ThooL>BiP{V{5u`s;&0ytcaEB^oMrrJ%2w$A5vX^v96zcDb+0Zns)Ps zQ!RXN-e@;(*t}u$hRqu`Z`izH^MDZcdY)v}0CLO1m^xknXUych8 z_Wj_vh~>Dj$|b_-PrnWY<)Mjz8k07 zXU{;3_fK{7y>rU-gFW_q52w2OlIrdk=yR&qE~z%Wq}uS3YQsya4KJxSyrkOjl4`?? z_1fHf+0GH|&JlKwuycf+BkUYu=LkDT*g3+^5q7-T@nXk|9WQpg*zsb=i}QFL7jx~n zu;apx3p+0CxUl2Gjte_3Y%O_QGyi_Rcd+MY?7sK$eS|&t`J8+Cp2D#8*IaM?HMag5 zTYrtMzs9LH*|Y58JyV@~Z=Si{JY(~W%`-O7*gRwNjLkF7dG=nSJ=MkcekT#_xzDMd zy3{rB=zpr+E~$3Aq}uJ0YPUpBkUYu=LkDT*g3+^5q6HSbA+8E z?0B)Y*x2!6$BV7S#*PUnptekEKaqnepf}rO?A*iI`(`Ir@HB4 z-8A<=stN5i?dA=eH*DUpdBf%nn>TFUuzADg4VyP?%`dj*7hCg-t@*{){9o6KY7!RXEk&n%ihkwYSCkQ0~2c+(o-{gqWCM~eMR3=-Em2E#|!j1)vNk5s_@!W8|%-sXiv4V z{tS%vR2%Eh%xJfMllvjtIilS;!p;$Pj<9otog?fVVdn@tN7y;Sju%@Cj2$nw78pBT zY%MT$yg1bY`};BO0mnr?9T#?7*l}UUg&h}mT-b48YiY6dr`Y<_xc;+~8=mc9>rb)u zr`Y;aZ2c*={uHO$Ouxe}-ZRzt_U4)E%`-O7*gRwNjLkDP&)7WUoM-PP+EZO{Np-;s z^f}d&`Zs6vKh>`KH)^z}+ExFijrLT#>fgZ8Zha;9L$-57yK{t{Bb;i4d*_ID=LkDT z*g3+^5q6HSP@-Mb51co<}BkUYu=LkDT z*g3+E7du{TEiHDu*jifbc(Jv#*zw}Jt`g&QT;$(z;la4~Qr)O)ZasZCW^}`IDdN^O zy0G<|(YGhpX?QM$t>47fZ({2=ajI=}Eiqo3>STNK%=P9On`dmEv3bVk8JlNpo^j5z z_Y&=?uGTfi=v(e{s>gJlHm*svpRVghd#e3(9XQ%k?WgO;4Sld4llvjtIikI;i^jcO z*Gt3B5!X0JIMvwp&Jpd-5q6HS$9D|Wm%)w=qOAadfk$b;j; zjte_3?6~mTx%aFU<$CKYvGtYM`bunlCAPj2TVIK-uf*0@;`*#D<}}r@`phWCYo58@ zJY(~W%`-O7*gRwNjLkF7dG=nSJ=MMX%qaSq`<&_%eV!QCq}t5h??>Z3>+`#~Ce>#8 zyf4~QZKltr8}0{d39)m8og?fVVdn@tN7y;S&JlKwuyceRFLu1xT2$<6YBH#xCgAqt5%%E}qfSp6X;5xF*&2xi2pInQ9x|M;Gm>w$Xie(O&oCg;Q-~vA&P{A=_Nh zZceZ{!R7>;6KqbfIl<-xn-gqKu;azna$?7e>%PIb&mAxA)^cLUi}QFL7ddxa*l}UU zg&h}mT-b48$Aujic3jwTVaJ6X7j|6Oabd@W9T(2ya_(ri1{0^6%3=*B?bb75>lv~2 zjM#ccY&|2ko)KHmh^=SDskW}9I#%}#$9;6KqbfIl<-xn-gqKu;ay!7h7wI9WS=l5<6aOttEE6IMrG% za1S^x=EZSg$Aujic3jwTVaJ6X7j|6Oabd@W9T#?7*l}UUg&h~p<8tn3w_Xybn#W>| zB<b@R2yhbO|+-l zKx=TKJ=F$UvlH#suW>(Qn=9JQ2{tF#oM3Z;%?UOq*qmTy$U`M_%z@SFA2y|3k({IkNp?Ro!!J_q@^iPvWPTH1Xr z_8cDGGk=yG=(D_^_jzr$uch7B;&lGi+xq*~zlV8kwtpAV?%&4P^H1o%zbo-Te^>Z- z2(QidwY2+Moc|_qt&H~{Xid*`KVF;dYiakjIGwZS-oIGG8E9?X^>bdE?Yb`Qz7~6a zCVlqV4Ibzjlh2`eZMLta-Phv$e9C8_y#GMYYWvw65YN_qE$``TaemI5pScgT=b^q& z>^I2vwdpwLxg_qPX+YwA44YqNbV z@9%4|`}cTlz2D;f2inV8@56ZiY+uWJ`dXa#!PcKAZDI{n`%r(*w0Ui|uch7B;`*~F z-n0HZ2@kaAy#Abt_s{mVyr-|ldB1x7c@pnGP>oXkITP=n?Q3~YUyJL{qIl2x^CUb_ ztzZ2)6YrnxYk5y!i*ub|{e2Pd-(Srv^I~l{uU)`ze($!wQ=$*n+w$7_`!3$U{$2~$ z-*;i_+Jc^r!9M4YVS(dhuvRCyWcw#*F3dF(|vYK3%l18`yEf%y~o%+ z-q`O`!|ub!^*KVkr{7&jyEQ4et_jDySf53^-xG?h&%%BuFSb?@TN8@?{%dUAF0P;B zBGwJR+ov43;`s2iXLc*2m)auy(!Xt6{`Nn&Xg949<@sBumWiit(SGOWMwj2-v2%H3 zzb)FEtgu;G^?_;SzP+}Hd*%;zkiEDc9+k*Z7f^S}LTyx@u{}k+ye%b$Vg zwiav6T5+2){qXJDxE}pWv@SN*WRrCWS2kpE?nu(1zmpz((cbs?9ae_ec$(~ zpRL+lm2<*>N?0Fa1^DeOGUEuoJE&Aqp7qolc z1@^oP?0FYIUSfrov7SEuiLQO-k1c24vTb{h#~<&SxxtvS%lg~2Cm#0eu2KK8LD}fS zt=emU{gJNe2aGBwPW?dpvb`Sc`qB~Wl=-V{+1`7r2fCJjad;X3uF35ikH5F;Zy#H= zJUnhv`!~nj-Sv){%a^IgPi(I^^RBL=PFSk^&3h-d-+AC&U1uD-SULIk?e^Y3yu0hw zXa3OHbFqo-DO=swby%Zti^dLzCN2T>M=v}sKzy9#=yS{qG6`k4pf1th2XJ75w`lAl=IeeEBaA?i}@Ok5ArrY8khG{GHQUW%SNv#7+}qT)XbJYk6ajR``?G?_Q># zIw8FL)V<5FVexygb<4H;m3^PuJlf46vC{9&R{Fi!^7kg^8l5%oq|TDxnbgL^mzdhw zZ`sM=?M}FF?#R7*>^;vl<_()SY~HYW!{!Z}H*DUpdBf%nn>XywF6`f&*uOdPYU`fb zng6{h(f@mXc3Nlj_qPvUdDraDjLWwT`#Xi}k6(Ri`R-rt+N=YKce{C|1l z4{h7Jd);q#ZohWN_PVd_()#%kCw6wcbjS8(!#})0{@>1AICp)2ZuIxF;;r8QznjxJ z^FG`*A2+0>jv0$ z1MImsxIUka-?^T9L%ZkRV9&k5o_m8m_Xd0J4NjklTIn;9=L5&jDErC1XMeE$!S)B+ zA8dcH{lWGJ+aGLyu>HY)M#Ih*_CCkn=h*ukd!J+PbL@SNz0a}tId;CVbA2tr?GLs;*mIDu{lWGJ+aGLyu>HaI2iqT<`{R7k?tEeI4eY&vy*IG;2KL^--W%9^ z13O>XIl_64a(=S=yFR}s`S<;?*W>=)pLX+)%|AB(*!*MjkIg?e|JeNFoc}x)c~jW)rm*KtVb7bwo;QVkhQfHWjZ3?6 zv2n3+v2n3+v2n3+v17!89V?H^=S0NyIT7|b5%%0C?72_abDyy1K85SKPuMfZu;*D} z&$Gg5ZPxGEiJxPx%`z|c6Wbqbf3W?*_9tBXgY6HtKiK|Y`-5F8#<@Sv7wyg$_TIqW z8`ygTdv9Rx4eY&vy*IG)g`Fdu=P2hVyT9x6dy;?OAA3FS@BL{v|JeLv^N-Dc_|Lo_ z=w}{_acMU$HZC@9`2S5x3Ga;+D^dnHT$s?GLs;*#2PqgY6HtKiK|Y`-ANdwm&%c z$N8e&`NG~C*n0zeZ(#2Y?7e}#H?a2xcD}H4g!3Hb{ABlceSS~!@B3q~$NjxO?dBhw ze{BA-`N!rTn}2NnvH8b2|9LFNrT@mo#>K|P#>K|P#>K|PIj-m3(e8P7*z@kN=L%xa zyThJ$hdu8Od)^&(?;PXJHZJYP#m2?P#m2?P#m2?P#f}jVcC0)u_XiT!{ejs1f!H(d zuxH$1&$z>$afdzQ4tvHO_KZ918Fx7CGijxLCf)fQ({!)HwwM?DiR}-zKiK|Y`-ANd zwm;bZVEcpZ54Jxz_s997-TA`a8`yiJ=e0d&Fk)iB0t8$#=^$J#=^$J#=^$JIhOgP-F#y6iOnZApV)k2^NGzTHlH}> z)3}V?xY)SZxY)SZxY)SZxY)Qj$911G?e3Ar?sLYTF^D~55PQZT_KZR78H3m}2C-)h zV$T@FX|GxHaI2iqTPf3W?*xj)Vq?ami=zOeI! zoiFTsVdo1wU)cG=&KGu$aGs-_pX~mw&+ke8eShrrIKRI+q1|&JaXtHsy@D;zfyABz zi9H7rdk!S_97tTxB8&HNpFi!61v~H9dB@H>cHXh`j-7YxyyHCY#v(t)!p6eJ!p6eJ z!p6eJ!a0`tq}_aC^NGzTHlNshV)Kd3CpMor=hL{1-MHAe*tpoZ*tpoZ*tpoZILEbK zgLZ2@u=N_)^Ca<+^~_J~d6L-kB(dj7V$YMro+pV%)iXbF+V9#*`(0a}`AM$qC$>M> z{$Trq?GLs;*#2PqgY6HtKiK}@+#lzQcIOK_U)cG=&KGvRu=9nTFYJ6_=LH2VepKyKu4%gJU;o6^Y?Ps|5KU~MfK5g&quyIp<=3?Vw<6`4t<6`4t z<6_5%2Rl|CW4*^>jP*ZVD8@A+{3zYwnfN5b|0PPqP`3fKQ@;rf3tT>o!|>;Kts z{l6TxHiUV!pVY=5x*!S)B+A8dcH{lWGJ+aGLyu>HZgKh78J&KLIH zz}_3!djorKVDAm=y@9+^e(XWt)tJ?`)QX*d7a{A2Tv%|AB( z*!*MjkIg^M`Ojl9F8wzyHZC?UHZC?UHZC?U&T;EnO8iWyYb@cq_7bjZGU2*b6RvAG z;kvdHu4_Kwx)v1oe714PgK@EOv2n3+v2n3+v2k%-i;F&F*R{B4uWNK~*-x+MJ-r@V z$BI*}T+3QH+RZZ_?D6K@I$q)q)c=dlpU`~qggG%UTb?$)xv`uXzV4XKntf01@e&7Z z(oA2o=bHOIHLe-EebnK$QcZ3v)#SEPO>Xblsd;hi*ty2eHFmDCbB&#A>|A5#8asCE z*s){B&KVk+EAPQ(u5E)fo z6mga~p}gnW_dK|7e%xQ1yk6Fuwem-=^{n0JTW8lkRdwrp&OW;iJb8+ry~0x`|7O>z zHXr)w)|1Pj32=~cWyEH zj^CdheDdWRPVWA|&B4np-e7W_6>kkb>pOEMpZ3PvgN-xCT;ua|CJ%qzl>ObGn>%^$ zsZ+7-KfS@^^;dl>u5-_Yd*r`*FVL6AnT>NFE#7H-+X~xEp8es|hfiI($9UB}ww~;k zoH3MZ_ZeTk_g0e!?{(&I_0e@t&0$+kUhtNwYsOgJ_`?^CZ-3(klixb)mf<_|pEthw zf6blz!zQ;4yM1-(_&YzCGkNvCw-1lqXovBcC(W6hSmBO{$pf#NGx?|k@A#AB+;SMA zeameKZaELZEf*rV@@>>&A^Tq>=?m$jBle0P*nVOAg4zy9--)7j8Mpah#T`9Nco4gIjKMaLaiPHs%~>w$DAsx#b>* z4=pD-#zlV^NBw~v3)r!M9gE=q;x)i;9T!;N;Ov{@h28Oj9WU7Nf*mi|@q!&M*ztlL zFWB*d^LS-HGtcC6j(KL=Gwz-v>@i`_7xsK%&lmQ5Vb2%#d|}TQ_I%-dzV^%c+AnOs zu>HdJ3)?Sjzp(wn_6z5J+dh=I_S*iG;I?lixb0^NZu?wKvq*t*AX+j|wq zZ+o(W+g`2UwudX&nDg7&KKC5wwwEe=XnU+;T=a*r(;wKefE^3iv49;5*s*{e3)r!M z^#^ubV10wLZ;lss#|w76V8;t~ykN%*cD!K63wFF<#|zHmmHo^-lh2+bHbquXG&Ky3^RLI}KZR8n*5}^ka z*o`^%**^Ci=e9RId}w>dV_fuy@zNjIv6zi(fMYr?u)e|BH^&RR;{`iju;T?gUa;c@ zJ6^Ek1v_4_;|1sO%6?{^$>$vN%(iFTJxADM!k#be`NEzr?D@i;FYNiko-geA!ufpd zm-Dq>*nVOAh3yx%U)X+O`-SZn&iz`C9lQ0|Ve7HO)?n>*qdIXD?!I9c=owmNny|Kd}D5js@&kz>Wp%Sip`2>{!5#1?;#7 zw>sOfzQNfy#|yjT1v_4_;{`iju;T?gUa;c@J6^Ek1?Tbd`oW%gCZ9b=;+)y`IsVb6 z#R2wwVb2%#d|}TQ_IzQ_7xsK%&lk?;o6p65IY;}2?H9IR*nVOAh3yx%UpV(`J$&re z!-uVh4_gl(wjMrgJ$%@D_^|cx;a2}DuKCRNOC0PMwqMwOVf%&c7q(y6e&JSAEBdv@ zK6Y#D!`9e`t+5YVV;{E0K5UJB*c$uratn4jle{0;8v8J{Y{?UXjX6Bq=bqziO@8{d zCO_k%Kd}D5js@&kz>Wp%Sip`2>{!5#1*|`?;{xj&Jk7VS?bee6hu!gl9WU7Nf*mi| z@q!&M*ztn>CIaku!Fjy0pP6U!*>fb$nQfor54)xV|0!!36F*yj^3+qN);R9ne9q)a zznfYc`p>R+n@>W&=99qYlfdS-!REHX=C&n!m)Zxn;{==YA8lG4X1J}Bj$!v7!R|kT z-G2nT7ZP?aB;3{x;yCWh#_qmsxap7uwnhYOjR?4D2+_uRHQ23J1Go48Xk+ax?AFeL z+u!b~zW!JzdB&QY)|MQMkI$O;O!X@DlQ#MZ>nH5_!k#be`NGBxHg2$SgN;9I{9)q{JC3m92s@6j*8}YJ z0DC>aURSW!73^LT*y|HE4?NnmI?S-wd9wGZeX#5J(Wcd5hP_|lW#w8>!#34XAE!F% zW9z7IebM24eYSMuS#JFLvnOQi^>0?kGZ3!N!0w2e#}C(MU`O6CT%Um*`NVL226p5b z!}S?BBL5h!&%hD6r*M4+j>t)cH{1F>XAm#g=Ns(bO4w&F?6Vj4*$eyZg?;wIK6_!G zz3m)(&)2@N+ZSwKuzkVy1=|;FUvTcrzsuN-Cu}@n;|Uv2*m%Om6E>c(@q`^axIXi1 z-R<3DOzYpZj@()7_3uJQ-YPM%J#2f}_Hb@r-wz{Cj^oI*sqc!Bs|VM2#mM1<>$_s) z_QCaCF>?Ok`mPwcfN*_Rj2uC@zAHxVAY9)SBc~9q?+G3E3|!w6I`U%S`kv5{FALZA zgpNE~xV|TJjSJ0us*>002@!(c*4dLHlDEYgpDU`JYnMrJ9coLgG7!aT<2Ml`xtFj*gf)1iHYrD z+rzexHmQBpD15Jj&Pl~Mjj+w=dF<+3D2)zYKR0$jE9sCNKY zEj{WTz*S3+dIxaT(xcu1T($J5cK}x{J?b66RZEY02XK8qiFX3H>Zq}|9IiTQ>@A0@ zrX73B;i_rZ_kgYA`A{|O*jtXhYTB{49Il#n>@A0@rX73BVb3?m3f2c$A7Fie^#Rrg zSRY`0fb{{^2iSPR#uGN4uqV^-xUTC(trNJe>qV^-xUTC(trNJe>qV^- zxUTC(trNJe>qV^-*z?V?g7pE`2Us6qeSq}=)(2Q0V10n~0XCkn@q~>hY&>D(2^&w? zc*4dLcI@DqGf>D$f@{t|Ay)~mc?E?$A!1^C*!HmP;oQFdu8^0&ab()mT%$tX3|w=K z3i&i}%{40I*}yf|s8A0MuDM2qToAbC8WnOx;F@bx$Q^-eu2CVU1g`Ux!dwNewn82f zT-z4%li+%cLf#Twk6p-T3V!yZ3VBX&^`(&i1Xmvmc~Nlny^t>jd%ihVus*>00P6#+ z53oK2Hy>bqfb{{^2iSPR#uGN4ujSJ0us*>00P6#+53oMK`T*+#Y&>D( z2^&w?c*4dLHlDEYgpDWc*uk}4Qz0h+u63LWxdL#lp;YSMn~0C?iI44J+rzni&EGDp z3vwKpHnna{Vci<8^<)a`*>J5hQ&{JQYyFwR`ZrwP9SZB>aIIHUSTBcb9h<`1EnMr{ z6xMX%s#g>=6u8!CD&zscwRTe>KLD;ZooXHZKDgF;D&!MjuQi|wc?NK;4OPfLfNRaD zLS6z~Ye^OI6=2Ud#|qX5SRY`0fb{{^2Us6qeSq}=)(6;l!p0Lep0M$RjVEk8VdDuK zPuQ`8>)wRInl4=TCKT3s;kuWh)c4njiS3Dx?P1%)xqaQARan>II5KVOUai7f7hLyh z71qGux>u{PHU`(dT7@+;xbD>|tfj$quU27=4X%5&3Ttn0-K$ktlY^^9RM6w#y4Rzy zjtkel9)fpLhu+;f*#KiW*$M&%8;oQFJE(Kkl2yo5p&xUAKSyWhjaVJ zT{=!jo2tbYG(@;+u>}ngu3BtCLxigqThI{Us>K#GM7V0P1q~6dT5Lf>gsT=?&=BFO z#TLGCnd}p(eQ-NYa65iao7Qh|^C!6Z8QlC2_I%ShM%?h>_#IX`8+-F@0&YGB>jQRu zfb{{^2Us6qeMlT}HlFFXVK<)GjVEk8VdDuKPdJZb8|ye`y9R>Wwb2nn+rzepZ4cX? zHdJ3mZ?k{q2aDx4$XD?QhMPnAje+J#2f}_8hbQ?T+KLzo)_N?`&}U`y1T;E(f>2 z*TL=YcyRms9^C%!2ejSJ0uc(V+XgnZH#G~^9HxMaKyy+jJ54y+rzni(-sQH zmub`H{snHDKpekm1;I^22yWU!aMK)un-&q=G>YJ+T?98BAh_uR!A&;^ZhAs+(;0%B z{t(=BiQuMJ1be=mV`hE8t`D$2!1@5|1FR3QKEV0_>jP{&VdDuKPuO_E#uGN4uA&vFM^xJf)Wg zHw`nmX`8`K^9=solpY)0bj9GNHwHHyGPvoJ!A-XeZhB^L(>a5i{u%7~62r{;fL$M8 zeSq}=)(2Q0V10n~0oDiDc*4dLHlDEY3~up+jVEk8VdDuqc5u_)V@#VSAKbM1h>7hP zYum%NhjaV3_7TUCY17sw;+SpCBDk$(1h+Mg;I{S=+}1>b+geF*TSEzMYb(KRog%oc zUj(;xjo`N45!}{6g4_B?a9cMCZtE$*o-Z-XtPj}r0oDgtA7Fie^#RrgSRY`0fQ=_? zJYnMr8&BAH!p0Lep0M$R9Xq(K<;9q`HNN1s_7^d+J!5Tq*!FO4-_}y&I5KV8T4x-y zYO$=t2Di1*;I?KO+}2Wq+ZtjSJ0uc( zV+Xg~fEd%3GZ5Tz2_h!8XRK`x+a9(($85P7ah#Sf5!~`9f?Iw?aLc<0ZuuC&El(r3 zFKoZC{lfMO=YCtxM)=TjIf7e`M{vvi2yQtc z!7W!LxaE)px7?E89NWzHOU&&TwqMwOVf%&c7q(y6eqrMYw_Kx$dCNfxZn;U}r|pT4 z?P1%)w&$2F*DH?G@~?thURH3+*9vZVT){2BE4bx-1-E>#;Fc#A-15i5Py59m`-SZn zwqMwOVf%&c7q(y6e&O72%K-}?T5ecy%NYx9xn#jD$1J$zo&~p@wBVMj7Mx?7*?x(+ z{lfMO+b?Xtu>HdJ3)?SjJmHqR7%^`-jlnI~G5oYW@v%K@dpNh3Iez91SJ-FKdym{U zj=#y<#-k@(H^uXwc*^K)hiw=3doTRDw#T>3 zwqYzX+osw_nQc>#(`B|z?YGNp8}h3&+lCzb%(h|gMrPa8xINe&woQ%gG&bh=Z(cN9 z_l9)jk;8RwNXNbiIOU_#rcZ5RzfWs}ej4rF%ZA;(Y%uGGRXd9|?yJS_zFL^I=&FxI z8~6BQcaJ|zUPGN5M;q&nV7J}~T<1hl8w$1-6KpLem}77(xaH>ux4ivee8DH$wEXnQ~CM9?l-|semZL+u=)I{JsQ5p33gvVv}yZI;O5U5 zc7Flv{sOq2SF~}T0(SQ)z%4$}#{CZ1-R}UmI2YJ`6R`Ux;5J^-#{C!A-G2eMagR3c zkrCdTOawC@(4(QkCnlHlX!&hPhI7|%@Z+0XMlscj}Qr{7Mb z-%h08l5@*79KTIIOe7!3x8xd*HtAd@(z%dp$2A;nQcNaNOvtn18jdz8wi79~j3&|;kzc_z9BtBAPo%MCZJld4+N5iyYL8RjY~uLs8s^%YNY~zkds47-4ZEh6 zuHlKc$0~lC?gi~VzfJdo{tVdDJ!QXPPxq#NhCSVz#wYCQ9-m0}xN)AOuk@@ip7Gl@ zUeP8!b0*R=$8nD~>De`ro?Tu)(I!0uC(<*J{C}UNURTjRJxeF@UXS!lo~X}lpUD&H zd5+!Z`Lz87^}3CHKAd|!e(W!TxfZx4;Ob}WQ-Z6Xu}=x+nqmy#dcLvW39jcG`<-B} zO|DV6#x3?u!8LA$Si@Z7T$wnXn0tjWfa^FGVhY!BEW{e-p5xww>vda* zDO|6ILabr#UG8DHURQ;f!u5JC+`}->kM^wQ`Ygm0d%Zpjv4->7akIy@-P#AY;{>mj&ZC&BId32xU_aJ$}uYm7T$gm3kE+qGvk&)cp&t9d@hyI*ZH?OiMVmgl^` z9i`v$_kwGf4j4Lk3Kop-~|yJ6?uaK0CuV`6uX38%T_$aw*F=XbF4JJ|Uh?EDUPeg`|hgPq^O z&hOxS|IT!us-@6gEelr5g4MEMwJcaI3s%d5)v{o7}EjmyVKNI!bz} z_eG&E^-oy+6HdC^w0I_sZj>~-QPSu}NuwJjjc$}Qx>3^TMoFV%p2)jL_?Dl~YWw(> z)*VJ^-C>m09Y$&0VU*S#Mrqw)l-3pB9QwDf85Oj`OVY3ZY+ zrH_)9K1y2pC~4`Vq@|CNmhQ7Fe9M2ETqDD`w0<{A>vyBHem6?%ccZp8d^*A`KNllAqT9X>3HK|crlNzNpsZm;!8l^R3rh8>O5&--jbU`90iR zT>3Ka8a|@sUBl*G!zoXAl=6hBff0Gvv`Klw)WC?mYwY=*-@IS!=KaDcA9Y$hQ*P=g z<))5OZt5uIrjAl>>L}%=j#6&wDCMR)r}+QOL7G1?2TA$%9w+Q6-`;-1p7QPWGwjX( z;FNFg`G(#6d17MzJe=~$r^U0ynY?l1ADnW?9j`ck${}}r!`{X{IOUMfIR9$b^FY68 z--_2^*welhuiLPveJft)VNd&3Mrq%Q_e->K9}4}t4+U=bd$eiyW1LIci{bqnZPH#0 z@At5$y%;_p!k+eG_&f>wOmolnJd8GJ|Ci6Pu&4cBqqP6a=V7!-`@ejChCS{7@_8F} z_j3^w_jAGR??tr9bLX_D$>)ExNqd_7dlB}ur^&xBVNZLS{CgDkndaSX{y2$mZC)AN z=9|H79va-{r@?LB8rs4-d26&!HEl+zrp+kTv>BzEHltM2 zW|V5$j8aXTQL1UU%}l(>_z*L&Bc+nU2yvQ{QKz zjr&F!7x#_A?R_lTWL+igo%H=G+N8aczK?}H?Va@fE$nIUr0;uSPr9q`LSfH3NtCxXrTsyeU!Gqh}Jh;u-gWFs_xXtl{+uT36 zX#&AbD+tcx(&o!y&-zuH%ZI(qwS(InJh;uxgWH@vxXtB*+Z;c*&HaO$CJ@{-gy5zv z1ZTaj&9%ec=HS6?ZXVp`?7?j=AKd2n!ENpz+%$pUrWFL|ahXX2Y;*Z&-{#uEZ4MsX z=H|g|&K}(6^1*G6AKd2t!A%ngZW=;x(-wl;d@wlGLvS7!_EZnSd0*I5Jp|{8VNdlC zMyVcx^UY{ueFN@O>l?srz8r0`W}Ei-JO7R6L)zo-d^zlCkH7Qlu%|u#&c~y#ne^VK zy+@l=k3x+i?5Q4wnnu{0))AcQQK*fCJ=LQaH7zCV`MRA+XKq?Yv~OBOaMLJ)n|2Z0 zG>zbZW>E)(_Y}bhB7UWCF#a9uD>K5+qz+eVzIW->DbH6r=s7aS5G9pdLrr76G^Y0NP6`|(yJ$uUOkcY>S=j^NsG2FR`{H> zXzOT&J!#R_-3oisqOH>v_M}BGGv|pAdAi(Y09Jn_l#Oj`7;xBNm}%*@5xH*(aYSEMSOBRlNLQI`;5~1xH%ya zpQJ_4`rgL07Qf8Bjl?I%GilMYvR^N0(dNU9@gZr^)-wrv(xR<@685A;TQ4Q-NsG3= zO4ySYJ(0BNW$qEiw;a!;MbFB<*OV7wE>QTNwCIPejsfSMv}o(Sgg;4(o)*ufMO#BA z+9xgg|7w4C$_bg4kCe3NiKIna*P`QGk``?pjIbvy`cJA^k#ne$7HyrAIA+qKCz7^r zjg)AUwCF!uorIZkx{?-cU4@>Q%tq~(q@5a*=qqW_*8K>3j%U)Mtr_xXt!I*Qfu`lf zB`w-|0t4}xjT%ZxJN2H5zLFMgy^FBtcqT1+R_X#JEqYpRVbY@ArystxHMQWRMZ4cW z?El$XWJw!bW-T(tD91Bt(LVpfhonXO_af{`i}vqJ*pn9R-=lUe59WYP%g;=j-bB)( zoik42XVRjbV}?Cx(auT3p0sG^uwhSH^nc8!bsxmEyxF8h&w73Jmb(>xCN0|f01?Ba zMZ2#*>`9BZ4nWwG7H!>tuqQ3rIs;)(+Rid-9x^WZdP`cgwIkw~NsG4DMA(xSZEcFM zCoS6dy|5=OdRh)}(mb7OM+}n|?c6-`9AuKYQ4d7VZA`uqQ3rJ?vr6q5kDXQMW6(sh?vo0sQLeqJRl+L|Qs+(=rqHB7>uv}kLdggt4| z&d1|?lNLQ~pF;LIY0=iZh~FkH`v0mna?+yJF5>t}i=MX6B5BdqYKZnpi?+5y*pn7* zEr_ruEn00P>`9A$$eP>ii&RgB%~giYRfcn}vhC~mj%*Lx9=1KdHJ2DRzZW*YH`+{n zTcq$?+rzepZ69q~dw#3_37a1an;#43{8-y_9NWXThi%Vq)em9wOJVa%;hbM;dyZp! z*!HmP`K|gAZ2lo^{vn+64{gtJY!BNWwmrX9pMlNagU#QAbN-&~IgagN+rzf!x9S_P z`ERiKZ*b0kvpvVLJ#2f}_WV|T0Cvs}n?DApIlH+oV~%5c*!HmP`K|M7*f}q3{uP|& zyyhA)&ou`r*!I|MpMKk?V+K2C#Gdn)(tOq&Fy@l>6>NKc>--Kj{|9!?1?T)9+jC6Y z!?uTQ&u^U{!RF7v=Fh-6f5!G4$M&%8VcYXtb2(u1D`4|0;GAD!dyZp!*!HmP`K|9T zu)mi(qqjZBu{~^i*!KL^cSzWL1K50nX!FPK#kiM&=d;hWVB2H&J(k}($AO)L zz|KM7G;i|R8^^Rg$Fx2CQ0;SHw3+SPo}6n`&yo74;dAXbzP*SK>6={S6jAFo+N5uC zkyAvi+pwo^a*0)_fDFpyPqrU zX`cRH&Kctz^RrGLu$#9A>jP}w8mtenS^;d{8f@MgY~C7dJYnavu=82i+$z}lENpHS z?0gnBw+eP{2%AR)n@0ra+$Y;}&)OcgJ^WDZb6>QX?VPAIFLs|=Tn|aFa9>;4lV0II zxUeU^!hLgLPkP0)zq9#ou0C+?=I_D!0Gq!D>jP~59;^?r`FpTFz{V4HUJsjN20O2Z z%`ti4J?TR3Hw=5yh1{PQ_M{6vc;9i3-h;3{z~)K9 z`T(0J3F`xFo+PXfuz8ZOKETEkRv&=PRfE+BU~|=A^#RyiH8|-5&KcwHPQJz-&iuxt z&&+DBAm{Ei466~r`T+a=ELe>Q_WN1EfBc45XTBnKzn=x0uLv7YSd9)gUleZp1Y<1B z7sc-PvtaW@;hZn({0O_u{g~D!M(KM@?z2N%`?KZAC#`Q*@=o*fEwg$f=dKU1-?xI* z8)3h11*L0V;|aUg1N(g|*tH(m?_0sH^}u=Gf%9nWGGp{`?w3hx zMzgYiAjUifr(oBuV81^FyKV*h{VCXWE7{{s=@A?hTS&}H=p@lm6|r+Yw-FBb`Lvt_prn6VTawr4!egP zb`Lw;uJbr%%5zg2kM)IzbMO3Y@AZC&HH#P{`z0pk^}+5jhuvciyT=@Mk2&lfbJ#uR zaQk}^akf?icJpIlYc;^;$HLZXfX$DEtc2Q12&$p^

zy};IcfvxufTki$7-V5B`u_IP(K1JPWb*I8OKAd%UQm+22)QxHL;uy!w?ib+P^#Qha z4Q%Zi*xEI)wQFE&*TB}Uf!mxh`Zb=|t!o5Z*9f+*5o}!}*t$lrb&cRQ=Z)hxeIv%v zx=*yR?h~BrKG~kJwmocn_@UZ!oc!B|vz}Gj^D-;-mvSCO=B5`#Z1sUSSOW^S1{7=! zDA*cMur;7yYe2!)fP#%DY<)1;`e3m2!Gizzy(BfO@YDKWv}qbw+}Gx-V3!%|raeZR z*{<7`_IAxmoiVRl&M~w5%dqPMY^^icT4%7e&R}bu!PYv1t#t-l>kKxYup@}H2ijQE54NTsY)wDdntre~{a|bQ!PfMHjVEk8VdDuKPq?i;g>Tk-#NO7b z!fw4s?B>70?stZ*y$QSD8MgK&?0#q1+MBTZondQl!fm}Zt^xbynz3KleqsBC?H9IR z*nVOAh3yy4{ic1vvr?ln=kjH?U*ceGOxW6(u(dH^Yh%LJ#)Pen30oTzHct|^-Yo1s zeb{=lu>163>&?RM(}%4$3%gGrPW#Z!?TIn9Ut(^*u>HdJ3)?Sjzp(wn_6z5J)Bg8a zsm0oITH=1mY`?_88nCc6U}0;(!q$L=tpN*L0~XFTU~?{OW^4A+-Wmw7H4tEHAi&l@ zfUSW5TLS^M1_GRFAUtgKfos2g%312ISC8F#^>E6!p-p^$q_v4!_pMFT%!lj#i=pms zoP=u~gQ4!l3a-zA`2Gm?x(8vXdql%t_wo<5Hdb(bw#WBJXjAj>hq});>~%l;Q1_e! z*T3WO{Sn&KT+=9!h`EOTYP_nHrV(-n6~@|uJ8Zx{SlaB(+5nS^bOa! zUVMK9#z%aG@tt#k>wG`HKLT^EoHI-ehy`3VrO6scbhC&VHSOWL&vBBN!d0(}?~f!q znvCs(+i`;1@yF4oeSZXQ{)D~x8QlC2Zs!%;&NsNlA-KgSxWz5F#k0^?i*s;`e{dU@ z;5J^tZ5)H!_y)Ie4{p~(aJx=|+w~LNuB+g7y#*6v^gDd>8zQjZ5P|*X2;U*f>~FFA zTiD;i`T*+#tPil~0(&m7=K>oO*qFe^1U9y?v4xE->=?n05$qVjjy3F9!;UrVH3NIi zz+N-3*BGwseQ2bRJ3XL6zn|(dvC(to3QsL z>^%;9kHg;Mu+IwEX9euD0`{2$`^`_8ADb>u?hGSql3s zh5h~r>@ykWxl;EA$8UX}H+!eO9=~G@u-D_q_ebD*{P_L|T>XsikHFQ>`2Gl7{fzIA z!1a9N`y+5Y-}wFrT+cVYKLXdd#rH?x8n^iV2wdY9-yeZ%{Nwv0aE*U_e*~`akMEDb zbsXdSBXAwZ`2Gl7$1%P?0@v#yzCQxj>mj~z0N3lG5No(zSMjX`*ge8BQVbo z#vt0X?~lNKa{+d3CE2^wKDZqxxE(+4k=Ac;^C!6Z8QlC2Zs!%;&NsNlA-KgSxWz5F z#k1gBi*s;`e{dU@;5J^tZ5)H!_y)Ie4{p~(aJx=|+w~LNuB+g7y#=@HFxYPs;HTdZ zf&G3#dv3?KNML^p`&-!G!ukN~1FR3Q=K^~!u;&6B6WEx*#soIDu(5@WE$kS@@>>&A?tWu-6{!wFi6c!Cb?9e+0JPLbRE>=6&CYdm-8T)IQjID%!Mf z`oP{(u=ghHy$O47!rtSs_c-i54*RTteOACeD`1~Fu+JRWXAbPM3-;Ls`|N^!2EslA zVV{Ap&rjIrC!FSk59@b7-J^#O?$LwOT;{=VFJez~nLqpYB{_b+e`mT+)goxG76Ge8 zz-ke&S_G^X0jov8Y7wwn1e~7W*k(%iF8bI(4_J^M8G?9<${Pjk;c z%{_bPp7cA@GfI7rHc5}_lOEM4J*rQ7RG;*yKIu_?(xdvMM|oew`?LEc>DT>|aMD$# z#WQIvebQL^q_Ol#W9gH|(kG3jPZ~>~G#2l>@GU=|)v@s{>8^d!UHhcF_DOf`lkVCl z-L+4;Yp?Fg@$=sT_j_V@zbBlu%4zXTT4kTK%06k8ebOrXq*eAwtL&3j*(a^iXII20 z|7~);2H(>9LZ8+b`n0~#r}c&2?~m|Xzdr(}^@ZN`1?>6npzBK5T~~sWCO<8nNt5rB zCf_GbzE7HbpEUVCY4Uy2l4YW_|bbVT<>(e@2pVsO6v`*Kjb-F&S z)Aebc&cAUnk9I#VF>yaHoYtPE#WSrv^=a*?Pis$oT6^l#+Ebs_p8B-*)Tgy4|Asop z=RG`P<@!FprS<4Otw;B1J-Scp(S2Hv?$dg7pVp&$*P}Upe*bYlGIsYP!)Xn7T0GMl zZlBh0`?QAJr#0L@t>N}*4YyBgxP4l~^*towli$ZuPD^iY34WSe0-IX`n_B{#TLPO~ z0-IX`n_B|scR%-2V|PC_oN^VW#WUq9^eI=NPq_;9-E8XnBOE8?D)cE=p-;IAeacnv zT`uC2-$h$)Vc5-~;`k|dt53OGeahYHQ|?xua<}@FyVa-Mt!eMQ?gytY_k+VJPi9&? zQ_f7Ea%TFJGt;M>nLg#r^eJbiPdPKaIWzP-(|fpiiL^<1bo~+S`y<$``39#vI`+aA z_Ksptd31fsqw7;1-L!Z9wEw+#KRd@sxna}dnR3JWlpEHk+^|07hV>~otWUXNeaa2% zQ*PLda}e`y@h#hH@GVCe;zc>G%`wJ_+d}`xYY#0p7xJB zHxK(vI*hduh+Epr?;JdSoA&ZMXAgVY%kLaN>}fB5?_Pe6pX!11*7v}kwWhRx**SO| zGwok?&K~x(f7v;H*xTGcIPG8V)4plv=Fw&*{mPmH_?h;|I|q;7rakh`*~6ap$UDam zd)g!4r#Ie4^B`)ZxDhdu49b&enQw69i8Ana*B@3e85Ndt7B zK7OXX;m*P1m}zggbM~;Oz2VOB!=Cnr_i1mq8bY+O4gmeSKNn8>Nu9?<`?R0bd0*Jm zep2U&VNd%>d-s!a{H(9K-yFO9&Ed2MbK3JN?ZI^Z8_$ij2h;g-*wY?N=htCRdoZ1k zhtD(Vz1ioqpI40{ew+65s%eDX?~ia^X+N*pNVG}&dHbfNggsxkGwIAt>xlMgPq!LH z*wdbFHI1;RJ>6;`VNZLyd-rtXzx(%L_wVO56xci#*fkVbZ5DP71y;v~%`bw@FM`c4 zg3T|2%`bw@FM`c4g3T|2)vjT+Ygp|XRv&Aoxmy@AcWfz7>v)uLgw zXjm;8R*Qz!qG7dYSS=b>i-y&rVYO&jEgDvfhSj3sJYH(i*wvz8wP;u^8di&j)uLgw zXjm;8R*QyRFN4*hVYO&jEgDvfhSj2BwP;u^8di&j)uLh7=3upGSS=b>i-vPN)uOSh zMZ;>*uv#>%77eRK!)np6S~TohA*>b+t3|_V(Xd)HtQHNcMZ;>*uv#>%77eRK!)np6 zS~RQ{4XZ`NIi70K*wvz8wP;u^8di&j)uLgwXjm;8cAXSfi-y&rVYO&jEgDvfhSj2j zTdq5-77eRK!)np6S~RQ{4XZ`NYSD0xr&=_2wP;u^8di&j)uLgwXjm;8R*QyRBZk$Y zVYO&jEgDvfhSj2BwP;u^8di&j)uLgwXxQ~=SS=b>i-y&r;T%u3XzXgyuv#>%77eRK z!)np6S~RQ{4ZA)LyFL!9MZ;>*uv#>%77eRK!)np6S~RQ{4XZ`NYSFM-G^`d4t3|^( zo@&w9)uLgwXjm;8R*Qz!qG7dYSS=bhHvm?PhSj2BwP;u^8di&j)uLgwXjm;8R*Qz! zqG7dYSS=b>i-y&r;T%u3XzXgyuv#>%77eRK!)np6S~RQ{4VxDMt3|_V(Xd)HtQHNc zMZ;>*uv#>%77eRK!)np6IT)~7G^`d4t3|^(o@&w9)uLgwXjm;8R*Qz!qG7dYSS=b> zi-ye!fz_g6wP^T=rbWYQ(Xd)HtQHNcMZ;>*uv#>nbEwp!v8zSHYSD0xr&=`jIqzOl zc&CKbqG7dYSS=b>i-y&rVYO)3d>FXtu5o;|=+wT4tz7`CMZ>M%XrmU5-P#3k^FP|C zMPpZshSj2BwP;u^8qV=li^i@N4ZGhTR*Qz+?+>d*!)@HdH??T&YSFM-G^`d4t3|`s z=z!ItVQX~2YSFMYI$*VESS=b>i-y&rVYO&jEgH`8REx%LT?<$(8n&(ltQHMh*8*0H zhSj3snQ{x&qG_WR4O@!_R*QzMMFXov!|gdaz-rO3S~RRS2&+ZIYSFM-G@Rq97LC0< z|D!LpXzcCpMcCD%vA4f3VONXB-u@niT`d~BIbg6_G^`d4t3|_V(Xd)HtQHNcMZ;>* zu(ds5wP^T1i-y&rVYO&j zEgH5a6|5EwTayY_i-xU91*=8FYSFM-G^`d4t3|_V(Qv-r)S|Il#|c)8hOOfSt3|`s zae~#N;r6~4*N<8>cJl*awP;u^8g6s&7*n-q>}}2-cC~2iZH^yywP@^369~InH1>Sm zszqZrClFSPhSj2B>&n7v(Xe%8VYO)3y0WlZG^`d4t3|_V(Xd)HtQHMhOA}U$hOMOu zt3|_YjvsMQi^i@N4XZ`Nd0f<@v71W?t3|_V(XjPeVYO)3dabZpG;Fi-xWB z4XZ`NYI?9*G;EDWSS=d1#v`m24O`<8R*Qz4CJ=E`i^iVEMJ*b;`KZBD`(fj^YSGxO zQwpm^!`3N<)uLhRl)`G!uv#>1O*9>jA=Q(XjOZVYO(u&BwzZwP@_-9>dvZwP@_t zmW0)!VQWhUx7w1hS~P5JNmwl!R*Q!7b*mPQ-JEAwEgDvfhOI9Ot3|`s7lqZLVe5;+ zYSFM-G^`d4t3`kA(Q6D@PnO@-tueg$q7%AN^5yxJiz8CJS$>3Hv3b}Gwl@si>2zgjx}{kc1q zN9=LnaOc18IzI7@JCyHVwg1p%suZ}<8OXsaXI)Ydk&jivB&tL`$}1S`_kdktM(lK z?lq9}lg)Z$^SPdt14nvaglT|0Ke&j0(_ z#UDC%&+$QfFDg%6<7vaXH}5&VX}>A{tMm65FS+pPVV56u=TnAfzxP?=H7B25 zUjFzw!<*+X9dG*GrynIw1Rc`3Nd*|}w z-R>WS{dZUYsJr!jU9>MJ-q8Ja&Nz;9*sq7~Ij4`~_=lZzPIu!IOZ5BF%|F!L{`M07 zoc;8pyB%&U;pf7?etq}abru)=zv-@*b?@pH$9e6t-@)C!&#dv>Ziff$53Ib`VEbcN ze$n7@Ccg7GgU8=|$!iAtUGv5_4EpopL*F{+=MJwvYS8~*Jo0UW=Y`$#rM+?BIL3$L z8#nqjp7>*&@zeO@zvGg}k$d4+U*CEB7e8B6CdYG!pI)=uc=1OUl@@KKO-Ih8rsc)#E5Ql3`6@B2)-=Y4ng2i~&v_>8M}F8khfSAXz=EysJ!->ED<{JZ^TA73!u z;=CQo#_ztP-}@DtjX$v4_T|F;ZtdUn)=kE@tg~I&e}|j<)$f}#e#WZXmMh+OWB(W5 zTX%f>HcQG+-u{jLkq56n-tB#h%bEw@&>#8!mBx>G(&Dn>t8VB|dDn8|5B;)~{Xg}M z{{A2Sd-sCn7MG!_yBqvD^Dc&n$PZ_PF5%Tc6Oq ze!JBP-Gak+EBRUXr#|0Kd&0ZB_fIT|`}*zw{PONy_be&pSz8Q?Kk$m~ zQ$JWzRz7Xx;k8@8uKVJxOUjCGdcttuzDIVCy>6=gzyAK{?#Wl}UbcGv&cio0eQ$T| zWxJP6f4|r8)wh12+x>#w%Y}1Z_~5hmw5wh?98rDV?rpo3@vmMqJa*F)x?A43v@HLD z{fB>>tmkt0uI07`FBzV7=tsLp{^c{v(|`Zc;ksX))UAE!E`{gkr*Am9JLsaFgHONe zxNe1iS~A58w;f-9;HbRorLP)JKkXUg&)hsJ*M0DH!*A}}a{P(|yYhE?ziD{G^EVye zac@`t^_U}u{eQgvc;1`G<#GRb)NslDtB=3DLMcD5_t(!Zd-Qmpe<h@ z-S?=)Iw?;m=Es-E4ft%NK>8Pda}7_~>00 zh5t9ccJuME+f4oaeaxB*$44w!R9^YKGH8GD0Xq)1Kk>Iq2aj{eFZLQd{<`b$J=pID zcHM8#pFQ?}@t~jkZg;?g{y*}22RwLQ*gap`8wZYKd^o;wqhI5RKgJn9jX(Z7F8po! zpYd8${yUBrWB2o&PU-$}!-eJ7AKPl!aQRcaN6cMVuGwzEaOf7NcTZhsVcCDJO^4B^ z&+1lQabY=R-p0cXM}53I@V?EK@9agvecXxBXwV=GL-j5$x`RCpIlNXfRPg-?&aL=(%7%#YgUitc_8xMc+wmIYHeQjR(_3E1r8{M+O`1u#iD=%2GU|8|^jmDcC zH?KVLqgxG+K6~Twh3}YGUcB1VhHaPMWPIOS=auIi*$v-3XXEj4)&88Dw;j$qVWaUq zADmad^q8H8_usj}c)5Cbmu?xg1qE3Uil zc=zhhI#1naxP0|B$NzHh{PN31`we%VxZ3#KQ|Fhjp82BT71yjdKIHcKWzH-2A6|IL z^5erdTu}CV#{t93zI%WDTehG)@ZAH3AI|@I_xB%LP(FF|0mHjqb$9oMn--LReC__j z@i*Plec^GNmq%UjqT%urzTVxw{pRIGJMA}|f7?~vK{ftA-gcki4>w%a-F)KaWsQ$N zci8XapY8tb(#^~M$Lu+*{GJQDf4^n(@}~Qj4nKL<$Gbi2`0laB&cm^vJ*#_U9rrKY zx$W?ZtxoT@tk=U8@9c(^A9ZT?hdB%5Z>!f&eph6!=e+4pd2fvN?c0vtb+T7t3o> z%UUPmx3-6E54)}eyRLM|KHrfacS z+v6M4))eyk!b7b=@V9L5pFXjifB9_#n!xt!tY5yo-E9M!#@%mUzx?9LTLv_ZpZ?XH z@`V@NJfLa(=qYo{qgTIiK+|~h^EN2YTkhWmG>y0Y^M>WG_PTaJ)A;)>H!fRkaP@$u zarRZ4lusUa#ek;q$yfhHx%9TluwT6PrscY)d@kDGb^c~$_fsy8N%<$)B=WJg3gH8)SU%TJJ@}6Iv9R9C+)xvVgn?E*iUd#Px zVY&8qCkn{m-fbi;}{=~Z`|nD zc;b(7#!usq|Bg!@FZg>0&M8Y?dB?yt^W2HK<(iM)GW>M$++nzXPWkO;ZW~U1!@S|G z@0nB1`~B_F<|hj`D7$Wa>oET1O2e8vY*^m%;cpLfu3LUs>8Op$K~KGTc*)Bi=r22Y zdAV-2Zx8u8|5L8*M{W9z{v(gyvYfl#b;Gfj-_Rd= z+`{saeZDfh`oJ6d_wBKHdD>=I50BmchW=O2T2TJ(_$!AmUwlLVnvcvcpXx6kp0Lh0 z`+K&WUpAPS9RB67oBI3Lo?m{m{={(J7r))F_|*C36m-_(MJ}PU%dQ+;hqJ*?3XUxyd3!0PY&yS^8WsoRTh@NeB{T6 z!|q>hSnHb$%NMsjcX;KaS02{<*%sw%JDnZzKlBk>l`AhhGx)B9wkWUo?&$+M7_ zS)MU*@_=6PwC8SF9(%*d1A4`7Yi(Ix_oGt=^om2T+M-;y&1up8roY{$Z2ipBhtcAl zhTB%yrkwrZ(}z!8xyP{T9$S}g$r(ercAw$uy|*d{?{(&I_0d(AIBd&u!CTH6&>yaT z=N9E1zdt*8<#QL7Q~oez??1gkx&Eqe4d@SV`pSmobszZVfd24<$821d|JK(B^oLXT z-=u8zscQ%Hhn25-QW12UN@(_^^hq(`j9#0ANIW?o(bMB`9Aue=ibzF_5bzf-U{cVUU;pU=ed86+*tD#5{$~etjJ5W8aykF=69f8&&vWcM9sQ(o?edpL`yZdVNqO1o zUy9=#`L&J9H}3s%9RF|D+_-%G?N>*?uX)u*Wrs`uHT*g4?hVT|$9^^ZToF4)bM?kN#l4=o0#aUZJ1p82XRC z;dx>Ad}(hSIF9k*_{NQXjVJyXXZ$q&`0u!IfBnyReRcTnI9`n1hi+fL%)RlW1Nz1~ z-&ntV<&h^1=o`z|I&$|OangXk@%VSFU#{HsV*~oeW6JvFv=^T|pl`hAdrvIaTyn~Q zzVX~QJ+Zv^S*H!?8!vs}31zh583X#pzZ~|2a@fXa4d@%+zJ0xN_pav*=o`OSvR+yA zzVin3jYB^2__E&jJ~5zgyzhtWmMylsU_jrvr(3t|_0bCl^o?_lS*P6p{fh_mjk$NO zU2fj!k^z0=)bZNoxJ92G&^O+D`da1sd7mH9H?~}Nt+MF*69f9jsVA;kUj4VjfWGmS zt=BBSzG!kl-`MZgHOfAhTsoj{{QTrK$|`?<*?_)L-nd5j@ZFaU=o@#wVvTb6y~3qzi>d`IO+%MmffCt!GOMT)bWomSKRZ70exe~#p{)=k2`Nb-+0Y! z>y-!gIA=iLIO}y!C?`JotO0%F=s!H6ylRs(2K0?f4u4{~YtPdL^o==n9N+NSQwH>n z%f{=MtM@;7K;O8h&I{hX^kW11#t$x8zZ`hvNdx-EO7%KfZn=}c(@q~>hoa5c(@q~>hY&>D(3FmnF{J}1B?&j3N=G4LF)WPP|!RFM# z=G4LF)WPP|!RGkE=3c_)Uc%;H!scGW=3c_)Uc%;H!scGWJ`Xv^%=&;`A7Fie^#Rrg zSRY`0fb{{^2iSPR#uGN4uxrMN~g|NAWu(^e>xrMN~g|NAfusNu(IjFEXsIWPxusNu(IjFEXsIWPx zaQ-`+SsyreeSq}=)(2Q0V10n~0oDgtA7JAN8&BAH!p0Lep0M$RjVEk8;hdAXtUO6# zVtd&3uz8hm&a2FMgAbM0hY#i=@>|=(wuj9FgdeIs$H~7nN0IjCD8l9_!saN#<|xAE zD8l9_!saN#=1juo`oiY=!shzI=K8|s`oiY=!shzI=K8|kcbsEpeZZ~{us*>00P6#+ z53oMK`T*+#Y&>D(2^&w?c*4dLHlDEYgmXN-uCU9TyLrN}dBU)H!mxS5uzA9;dBU)H z!mxS5usOG|Ik&Jmx3D?4usOHEE$0?C=N2~S7B=S=_PXU9GwTC(eSq}=)(2Q0g8!3w zzs8f_8c*1G!p0Lep0M$RjVGMrX&yD_YaTUh9yM$pHEbR=Y#udi9yM$pHEbR=oS!q9 z^#R}X0oDgtA7Fie^#RrgSRY`0fL)V+m{K6&lWHAj4y&3$v6yM4ho9y=;OI_k8D!#xK-qde}SQ-crM=4s`?lc)IE zD?GLQ&8|~zKJ?SA%eLpA9&KDJ$!nVbUDthFQzrg0@o|qQ>>f|pJ)W?8JYn~E!tU{e z-Qx+n#}jr>BJ7?-*gc7`dlF&yB*N}Vgx!+}yC)HLPa^D^HRqUFAF%5KtPik0!1@5| z1FR3QKEV0_8&BAH!p0Lep0M$RjVEk8;T+GLs~~gk*42dF%M81h8Fnu->|SQrz0B~O zslC{d&){BW?C!mV-FpkW_ZD{VE$rS~*uA%~dv9U)-ooy^g>!C0W_=(g`T*+#tPik0 z!1@5|1FR3QKETEkHlDEYgpDU`JYnMr8&5dL(;OA-GUx7|eYomg1)T_X&pzy)eb_zw zuzU7l_w2(}_bTW_u=P%peIm6Fc8@uB_n5=(F^An_4mUsJnsJXg_M8Kg`QhB>Zaj&z z@q~>hY&>D(2^&w?c*4dLHkS#0xav_5Tl-Ruw`)7>)@{IU-3GYbBhkjX4cM*Q09&^Keu%uRj@a5SY`?Jm!uAW>FKoZC z{lfMOoAU;@=lK|J&-vg#cik1v*M4F9h3yx%U)Xvtu=QSG>%G9%dx5R@0=K_|acx+i z1iSS~VC$2>?Qc`Gw>}AW>yyCNCxNX`0=IXJh+Ag+jrh-9RM7Qc`-SZnwqMwOVf%%1 zzvf0_m+{A1L$I}mU~3J*)*6DXH3VC02)5P`Y^@>K+BmSaabRoXz`wn7%Yr5aTN?+q zHV$lU9N5}8u(fgE_I?|2%d8KayFS4B0P6#+53oMK`T*+#tPim9gpDU`JYnMr8&BAH z!p0NM@id1PyUe+_d0&C8sRg%rV#L;(TG*|r1-JQTv}yCuU~6j8rp;T!ZVf2x)_{Vo z0R>wF3bqCmYz-*b8c?t`px~UNn^_+?cYT2M0oDgtA7Fie^#RrgSRY{H2^&w?c*4dL zHlDEYgpDU`JmIFX6nI%R+=z+oVcWyje1n_D7}tR9b6>QvHXUqjI@sEDu(j!eTWvbn z+H|nB>0oQq!A&m;AFQQ@-CAm}wbWp1slnD#gRP|oTT2bLmKxl&xQJn9ec;^n0oDgt zA7Fie^#RrgSRY`0fQ=_?JYnMr8_(eXM6Ey0v1zJtjxzS9e@2|G!HC@&jIcErVQVnL z)?kF29vjDLI&E;%Z-cEFNPBAr!qyCgtr-YgGZ40BAZ*P**qVW`*DdkMtPj}r0oDgt zA7Fie^#RrgSRY`0fQ=_?JYnMr8&BAH!p0Leo^Xz5Tce3_lsWgdo)U3x>ny?68l{c3 zMqz7>!fhQV+FNTByR}B)wjLC1tc{7?+L*AlF=1!1@5|1FR3QKEV0_>jP{&VdDuKPuO_E#uGN4u-ur}6@antmKVE_NJe#$t^Irb{seADMU-y7(spXHwxMa??$7i#S zH$K=GY+tZ7!(nTN!`2Lktr-qmGaR;NIGk#Rcbjefo-@cptM`7FzPa3`+HqaVFQN@K z6Qh0lUNdc|Q5g1GLu{xuI)iHsv7y!z46e^K=HbD$j@D3X=LOd~T6IpiWpMpF!hABg z){+`(eYD_OOKPZf(}L?e19O$&S}$m*HH?C5y`afj+bFocA5QX*^TNje!L;Q!Fvs9n zFvq43m_F$n#ut2o@eyBPeCHfs&WUq_IakgZCI-X;CN{(<+Dv^ zOK=;n;5LrIZG3~jSJ0us*<^3+%bTo(pVDU}FLs6WG|o#uhfVuww)} zMzCW9JJzsc4LjDb*9`161AEQDUVE_D9^9_^G3+%Aw`;qLHdEJpu=hf;^Sv^%v1vlRBZ4f{-neI_@1#I)JFTK9GmuE&qDgzNFg#1yW_A2XJ4^>fS^ zz}3$&F@>w2V`2^0^Bpq=a6R8KF@@{-j)^r~<2Ggt;2O6vF@IfseN!ePH;Q^IND708{GT}Zhi(g|AX6k1-J7JZgB{1 z@d<8m3vTf&^xNVb+~ObH#wECoS8yB0;5NR&ZQO&~^$^^yli+s!1h?xdxLt3-?K%wh z8!q_iH(X%9!Oh>A%>EX;zlHrRtPik0!1@4tF0khUdoHjsfsF}lOkiUR8(Y}e!j2K_ z7{QJa>{!E&HSAc!UNf-Q4D2-nd+otqdvLqvGw zseQ2bRJ3XL6zn|(dvC(to3QsL>^%;9kHg;Mu+IwEX9euD0`{2$`^`_8AEK{Dgge!fAfjrTJZ#zCF~XZx3}X55Mr+^zET8eS4^D`TWr)eS65~ zdDv6k$S!?{s7rI1&iMs>Ilq9NU%<{UVCNUG^9$Jd1?>C+&hv|W&(3t8CjFsH`a_q# zThyiR7Io>nMP2%CQJ213)U}-Xh)Mcxkz*S6RI{Z^-!1CWJbhYhlRnU;?-q6GyG334 zZc&%MTU2XzJ!QXP==CGD$A+EXJ^?C7r5EI#ri+sxIkN-gn_cem<+2 z<7d)%yQJ}UN#pI3#@i*0w@Vstmo(l^jhEx+zXjIM!EXH=IO(F(;+b^OF6p9O(nY(Z zi*`vD?UF9qC0(>jx~R{th)@38l-7y5w3gAOwTv#UWprsRqieaoaZJ~SI7iopVAqD= z{CChbEbOjf!Abw07SE*rcS-;6lK$T%{l824f0y+CF6sYW(*J$_$GPOc%dWBFTUrzB z(wbnG)&#q>CfKDl!7i-{c4dW>m$KwooiY=(>hm|*15X0&ef%L zt}d-}b!nZeOY2-+TIcd_sB?VY!y{Ja65v}}`|i@(cbC?_yR`P*rM2%at$lZC?YndB zo8#yAAL~0|x4sjc){CdbGp!eQX}!2h>&0DKFYeNMahKMMyR=^1rS)RpLn1!;eat)- zd^3*)Hjf21j|Dc51vZZbHjf21j|Dc51)@ z)`hQOL-Ap%8T$_E`FQeMa|dZnC5H2=4-*`Yr*Dg!RBkh=4-*`Yr*Dg z!TG({`dZknuLY-^oN4h)`8l0=L9|c#IbF)n=~8}9m-2JEl%La?pTluxdJi`Tk~S%4 zuRG$8-!1A=&R&;t_PUg_*QK1jF6HcXDQ7R{t-kYHAB=vj4+f_^v}y57d1zhAL+er= zT9@+Bx|E03r98AQ<)L*c4{gRdh`GM_mU2@)PRv14ZmRu;J>{nAXV{zn!RDrNeCPft zCeg?sG^>pbi!2fH%|o8#oUp7q(VTb~V1dCSw{nevvsf1|IIx9t5M_LR5m z^C9dhZ`tQb*wu6JAo+&@y=YJe0<>&kNBJ3$Y-@h+mPx<-&Jqr6w^KSJ(d`tVsoo`NJPy5H6 zpN2i{A9p?*_OyT8`ES_MzV!z+Opec52YNA_*PhzEHSDQ|K$mI=bg70wmud)fsfIw8 zY6x_xhCpWx0s6IG1Z=$sIPJ0WeIVkQzFXw`L)g=Ii+tY*d-`sX?}lV+bNsNUed}rhVNd(zotuY!CLP9F5R7B0UEmx%ew%6+IA;%gs$Jk5KkTV? zL1*m(j&D5^*m@>#)|%3OZRg-|%r-X`M7>|sy) zh@InyJ?$e_69{|SzdUVRX3_wyOMstgFT8W`IA+=l@0>mCX)nBU{II9J@Lk#quZ9q9 ztb0Je?nj2x{#oa7(LU{;b>0{Dw13ulV%XFE+0Om596#%;?ytx0{(3m=b)ELSN_$_OPo_ggxzHSJMc4+QY5}685Hz1iObF->g>vTdyFmp}=at zuxlu=+AQoE3apL|t7F6J*swY_td0$eaA% zHLP9@t5?J7)v$UstQHNcMZ;>*uv#>%77eRK!)np6S~RQ{4ZA)Ct3|_V(Xd)HoX1No z8oOFFtQHNcMZ;>*uv#>%77eRK!>*UXYSFM-G^`d4t3|_V(Xd)HtQHNcMZ;>*uv#>% z77eRK!)np6S~Q&FsTPf0EgDvfhSj2BwP;u^8di&j)uLh73SqTqSS=b>i-y&rVYO&j zEgDvfhSj2BwP;u^8di&j)uLgwXjm;8&hb=>#;z6(t3|_V(Xd)HtQHNcMZ;>*ui-y&rVYO&jEgE)>7*>mh)uLgwXjm;8R*Qz!qG7dYSS=b>i-y&rVb`N!wP;u^ z8di&jb3E0ev8zSHYSFM-G^`d4t3|_V(Xd)H?D{zD`Z%l>4XZ`NYSFM-G^`d4t3|_V z(Xd)HtQHNcMZ;>*uv#>%77gckszqa0i-y&rVYO&jEgDvfhSj2BwP@Jf09Y*=R*Qz! zqG7dYSS=b>i-y&rVYO&jEgDvfhSj2BwP;u^8di&jb3E0ev8zSHYSFM-G^`d4t3|_V z(Xd)HY+eMc77eRK!)np6S~RQ{4XZ`NYSFM-G^`d4t3|_V(Xd)HtQHNcMZ-CsYSGx$ zqG7dYSS=b>i-y&rVYO&jEgDvfhRq3q)uLgwX!wYxMZ;>*uv#>%77eRK!)np6S~Q$< zsMMmdt3|_V(QuBZS~T`KQ*|36&q^&CyIM4?77eRK!)np6S~P4v4BT|rIKEnRYTv`{ zIKgVs*jvA0SBu8p{0w{ZKUgiAHfqtZ-{yeTqG7dYILA{h8oOFFY<&Y*EgDvfhSj3s zHtyk@S~PaGXt>2H+NeciSBr+*bvVFk(QvzN!>$&My*aC?r$Z`Go)x948i z)uOSt=VaK`qOq$*!|iz+ZPcQ%t3|_V(QuBZS~PZR#lULOu(e`fwP?8geTjb6qOrHX zN9|l5IzLk_n)YhZu(eEKwP@H{rm$KxY%Nn*EgH6#DXbO^|A&0q(4w)cMZ;>*uv#>% z77eRK!)np6S~RQ{4XZ`NYSFM-G^`d4t3|`@eIVkg7LC2VKZIQ^8hd-+2)kM|_V#`f zcC~2i=HtO?(Xd)HtQHOD>rE{hdwai%Kx<$u=nQCo)*=;w}2ut35clJ zfS`gsFpALKPgOVAj7^STt-b8a5UU8;gdGMZ;|m9<~{arrcOG zY%CgXd;F+xEShp-(Xg>-IFF05Xv)=6!p5RuW6^NigGXD&qA52P4Y$2~)G-!KdE5I( zxv^->k8)$tl(#*5lpBktyzTL$+*mZ_#-d^G;DwDv!^WavW6^Ni z$Hg;^MN{7PeNk>Kn)0?!jB;bqlpBkN+kP|Z7>lOdSTt-b8qV)4W6_ki{cpTaj73x4 z_RCRjESmDRzm9Ta(UiCSc-UhsnsT+raJJc4H09o<2^))sy-PE=-K7Z|i-wIw!^Wav zW6^M)x5lC=SMv-Ti-wIw!!1S;{W2C!d5dX8xv^-%-RPe~rJv#>8M_Vz4nW{@41j^%-RPe~oXz#vEW{4zMu?{@41j^%-RPf8Afh?s;MNys&#-{@41j^%-Ph|I2-D zJ~P-o7v=7`(*K4I$30qVE6T0U|GGbd-Lt^%Szz}pJjeR5^%-RPfBlYz{SJlw4u$>R=YOpaTOYPQY<>RM^Lp4d4D1>v>OAxNAfAuJ zS(x>CruAXhY5cEic-S>I>>3+(U%>xbAGSVhefZhx=eDThegSsB0J~p+-7moI7hv}b zu=@qr{Q~U%1s-f38RlI0WN3F}*tZ7{?T!rl`QV}5kzt=7JhVG9?Eiy@cDV;IcxX3% zPo%XQzbDe#jotUuxG&pZ!h`tG_NcHIuUZiijB!>-$5*X^+DcGz`0>^=f^{|meSh28(c?tfwT zzp(pX*!?f;{ug%M()Y~TK)E)++5l?z}f(71FQ|O{)F`>tUqD>3F}W-f5Q3` z&i?fML%B@f-Cw}&FJSib+05EN-?ahO23Q+lZGg1_)&^J`U~Pc)C#*kV{R!(& zSbxI$6V{)w{)FA1!tNPi_l&T6Mtov@*!r;bVe9k1?xA4!IB?$MxG&>>tq)rtwm$r9 z^>bU)alZz;UxVGR!S2^!_iM2GHQ4u_?h4G7>_?tZu|i@{s22~ z>0@SXpj;bZZGg1_)`s9`e$%8F1EE|SU~Pc)C#*kV{R!(&SbxI$6V{(__NV(V%4PcQ z*%s{C7VOy;?AaFV*%s{C7VOy;?AaFVSq$u14D4A9>{$%#Sq$u14D4A9>{$%#Sqz-_ zcbT<;zH0-l4X`%A+5l?z}f)oPgsA#`V-clu>OSgC#*l=>`%{aDVOQ{(#$9F z%#n6IbA&x}ggtYFJ#&OTbA&x}ggtYFa~vSE=brRk8(?jKwE@-!SQ}t%fVBbE23UW> zo{7VriNl_W!=8!5o{7T~p7||?;+Z&oG@e5pnR2xX@UX{?-wuG)D!^(LV6_UcS_N3G z0^H8fr^ETKj8?wH^1O1qD6{AL^j#ZZ&-Y=^_hHZXVbAwr&-dZxtB7%VzE8RSOm({S zzrp&Ga{USGPgsA#`V(&Rv%u$>=RVZ(ByMxuM!0J`t_8Eyf>QyLLuL7%AfuALY8DnI-_`!Bz z+l6fxwq4kEVcUgm7jEAdF^=lZC|7R=t2cwyo5AYMVD)COdNWwP8Qi{)3jMWR*mhyt zg>4tMUD$SE+l6fxwp}>4t1gRjby={wELdF@tS$>ymj$cKg4JcgZH*EB%xt^(!FFNW zg>4tMUD$SE+l6zxo+D5$V~-k3SdAsD#u8Rz3BP^pOh3j*jV0x3EMYa4aMKJ#eKmoU zs|keF1j1?pVKsrUnm|}hAgm@3&gT@FwSm5C1FQ|OHo)2dYXhteur|Qj0P9a!f5Q3` z)}OHcg!Lz^KjG|8&zmTh>APBDSS>NEmKat`467xE)e^&MiD9+Gu-aEx?JKPI6;}HS zt9^ylzQSr>VYRQY+E+NAXJys~`mPPIHo)2dYXhteur|Qj0BZxRKVkg|>rYsJ!uk`| zpRoRf^(Wl+Q`}u_Y#~_fI^}BD@rm_eweGO>;b*I#+oFz|d{|9BtR^2;lOO!dUH9%Q zE9GkPVKw=1+Z#q5HRP15A&1qF!)nN3HRP}wa##&HtcDzJ`|j{tW^JJF+5l? zz}f(71FQ|OHo*E5)}OHcg!N}|^CxVM1FS#c?9UcIi9X8o-P{w{+!NT`6WH7n*xVD? z+!NT`6WH7nxW#H>9L<%Wyv0MJ+*}FD&6R-7m4MBafX$VF&6R+ixAZ-;Hc+k&ur|Qj z0BZxR4X`%A+5l?3F}W-f5Q3`)}OHcgtI?eJT}Hrrtjuh!IxfnetfUM=2*ez zSi$C4!RA=O=2*ezSivp!8{=h85as3s!R7?PEgl>7%?YC1oFLeoAlRHBIO`}fYXd&f z23Q+lZGg1_)&^J`U~Pc40oI?e{)F`>tUqD>3F}W-f5O?H?Yua~F|&D>)HjC_Hir>5 zhY>c15jKYrHir>5hY>c15kK1&Y+JBx!L|k47HnIvZNat$+t$!-f7HV#ymHu=j>6vI z0IQpY(|ICwM!4sp)fwSV+E!;|*e?YS`pLLIobo|G8TW_7!+BQR9}W*1!ni*i9yEk; ze>gnMrMN#F9&~hZe>gno=;HoxczAEb{o(MSm5Ter;Xx}E_lLv7cSPJD4i8$dxIY{o zv|e$4I6SO3;{I^>JM$)t{`{~9didrSt}}Z0DPzAsyXX9MMsNP~J^e3ctkd^TO&I|Vf2Wn#_DJ%b+i-KPT2m!_7}FluzrK}8?4`8{SWJZSpUPrSjRZRjw9?i z!p<4k`2Y`dCgwvc4-IxJC*NQcb}qr{Y+-e_u;-qzT2ol9Dcs&U@l5rWl&iOd+xJV< zQBy~`nmV|xC8Ca+K+4qw!fjm|V>gUrP2*S{$6?$nc!|FWLPU>hUtevp^h3zkFe_{Ow>o-`x!TKN8|FHgt9Xr^ugMD|wzPn)G zU9j&i*moD~y9@T+1^e!T^Sdj(pL_2qrOpK}`(XF6`7}bO z7~ePjoNmFHbE16R+dtH8cf%Ne`TK9}PX6f_`}-z5=YRD#O8DRA&uHuM@9j`t^~HDrv-*sfHGW8WigzvX z-yT)}OuOoz;S?kCyEtr4F`_=ji2mDtbKz(3tg(e@@S zPv_Cv6Lr#gwDw22=g~aB&7UY&|4(_!7jV3yj_1hKY3HF!>^JDm(WWhPv|)8DaME4) zd)Be1NV9A2{BP1K_<4`= zq*d_!5amg$;QJ)X&C$jNbF|_1K8!l%L{M%{1e|m-3-vMSWPB&bbCOQRcX*U1os94N zG213~by(L1C!I|H(7a9Rkw3aH%HMIu=Jmc4&J2F!om3J15O{pETQj(rouhv)w1ncAqrcebQ|ANweK2t@wCc1=|+2H#ZN0I!U+R zC*6LZbo+hM?e|Hy-zVLEpLF}Zx_zE+E)Q%j51iun4e>u*3u{iLDwH>0CGX=vU5MtRcEx?hg+q}^R;Tox4=vIB7@wq#gBl$>V>McC=60QGee&>Ll%GuXdE@ z=a`$?a>~_~!%182-Xz{9<}Xvn{AJkuW!U^>*!*SK{AJkuW!U^>cu_IHY;)4?`djeP z-=y8`lXlnNl#e<|yKCGa%9D22-@A|UJZ~2jdu(xlsGs!P{^od;C;hg+Q6A+%5aru` zYHGcqKR@{E@7<~%de#^}@8~V-+_lH*xE|wwU5~-8$6(i-uqp zEyL=TVb^2uw_dYFJ^k{Jhs`I<-?BdaruPTCcA}1JC)l+U?Ai%-?F74af?YeouAN}l zPOxhy_>az3p7jjHwG;JSJHf7s!*G{mx zgs^KT*jz%`wG-^x2{sQMcI^cF9R#~}g3UjIT|2?%AHlAjVDpb)*G{ncN3d%rIFE~K zC(1oj3vPG6z^ZeZ6= zuxlsSyc^iH6YSavb{zt{c7k0y!LFU){N8ZwM7e7x*tHYv+6i{;1iN;ET|2?9onY5a zu;-_6w%N54<>o!XuAN}lPQfkj33lxSoA(5}c7n~fg7ds}?L@ifwy*mxApWeN{<;2swIaki9 zS54U8@4I@`4-a36+xJV9x9^=`*I?9d@9il6=u3AgXRN(r@I{kmm#<75yKS;m$Jc7|AEI38GjCa%VLK|Fu4B zec1H_{A~4eThwuF1G~0?UE9E}ZD7|nuxlIGwGHgr2KGJ*c(6I{!GMQ$$%ym+8CfCD`>6?0N}yy#%{nf?Y4cu9slf zOR(!V*tI(BS{-(+4!c%|U8}>c)nV7_uxoYLc}pKNYXjxl0BZxR4X`%A+5l? z!1@!`pRoRf^(U-9Vf_i~PdNM2_YdVVeRo|4yRL&>*TJsqVApl9>pIwV9qhUecAW{k z{)b)v!^Tcw*Z;8Vf7tau?D`*e{SW&-q>q`kfpTqtwE@-!SQ}t%fVBbE23Q+l{R!(& zSbxI$6V{)w{)F`>tUqDnb?~Crgsx-piS=RY!>%FWXRDvvqK@lZ*!3;!`WAM53%kCB zUEjj4Z(-NBurYsJ!uk`|pRoRf^(UP71&dp&;}h${)`wl&!+C9=*RG3NTe=?R zf2|K&A9gJYKU;nJlK*HI*U7N!WY~2w>^d2CoeaBfhuv?&?l)ogo3Q&$ z*!?E#eiL@T3A^8f{oK*V%-TS?Ho)2dYXhteur|Qj0BZxR4Y2-%^(U-9Vf_i~PgsA# z`V-FnbY4*|(|7l(uzOY5y(;Wp6?U%*yH|zXtHSP8VfTHo`##uxAMCylcHbA=_ItUqD>31@%0m#4q( ztLzVE3WeAXEQe&Y51%{on;-^-r8y zx4-86;B)uhs{YeCV?4Ummi78A#_BvWaf`a~i5Etlch20b{_g0Df^T~NCiQ(!UlK81 z&jO~;*uKAS`7P=te}7^BDYtkwngjuBX`3+x>uuv!<`a|hUS2iS85*mDQi za|hUS2iS85*mDQia|bxb2Qq5|eb)w98(?jKwE@-!SQ}t%fVBbEpRoRf^(U-9Vf_i~ zPgsA#`V)5S;3eHw_M7*t(ylrsSe+8A?h96@1be3ntWF8`P8C?466~ESusS8!J5^wH zO0YU5IQwUDHZy0e4_hC$kFb4&y(fpZWXjdl!QSx#tEq$4)WP2I0;{Qmn0eGBVb*#6ST%-TS?Ho)2dYXhteur|Qj0BZxR4Y2-%^(U-9 zVf_i~PgsA#`V-cluww@=>9(@p)I-v)dPvwiZD8-Tfz?C8-f07Srw#0#Hn4Zvz}{&C zpEP#=&j{?DHn4g~SUn`1{j)fmnKRahtqIdsv%JnU*Z()54>swgg!uB`yG5o(Y$5(%1gZ_l|C#*kV z{R!(&SbxI$6L#$2CEZr`o4RY-ZSyVWQk#dt?Q<8b?wb1Qu3>f8uy_8z-uVN2=MU_i zKX7|*#Pii%Q?BkB&i+}P&1ufWoVPyZ_7To~Z13knTjmA8?Y$c1<^@pR-osIDUI69o zy&dJ|1yJ7J^HHupvB7p>+l6fxwq4kEVcUgm7q(s4cH!Kv<4C#V2s@6j;|M#Bu;U0j zjtUqD>3F}W-f5PT> zz~*ZB&j*`-gbn5&!EIj4tMUD$SE{R!(&SbxI$6V{)w{)F`>tUqD>3F}YTJTkbQU&mOt7(%djYEj2KwP5em zg1u7<_D(I>JGEf%)PlWJ3-(Se*gP`WJTf@@XK^+&j@E~*58FrBKEmcX(w0p5lfT`h z5_5;W;|unVFW5W2VDI>Xz2gh^jxX3dzF>U|>swgg!ul50x3Ip2^)0M#VSNkRU;3C? z8z|QXSQ}t%fVBbE23Q+lZGg1_)}OHcg!Lz^KVkg|>rYsJ!uk_-?BFHcR`#3us%-QE z?IUa-;TCrdEwM~_i;;#tr^Qa=Gu2|M!7bJr++wi7EjAn6Vz$98mK&^ZX-nV2`WDu= zu)c-$Ev#>0eGBVb*#6?r%-TS?Ho)2dYXhteur|Qj0BZxR4Y2-%^(U-9Vf_i~PgsA# z`V-cluww@=>9(@p%!{YpcAgk>sht4@Kl#!XDu2{zXAQya3?kS&->B2hETX)fWdwWY z8+F>*N0hfSkzn)UsbgL|oc*&no0&7#hpi9WN7z2X?K~)KkSX^L2iQC4VDF%Vy@M{e z-9ZPpGo$zndIufl?TjhP^)2Q47S^}0zJ>KItZ!j`3+r20-@^76e`eMO%C!O323Q+l zZGg1_)&^J`U~Pc)C#*kV{R!*O;O0+Qf5Q3`)}OFr2QTTivftYIc+8)6ZXVpu#Dm*; zad10(4Q^+$!QQ!t{p}1l%Dr=s@^Qr^zcque_HDQ{=)QLb+(*SD~~ zh4n40Z()54>swgg!ul4rzxXq=Hc+k&ur|Qj0BZxR4X`%A+5l?3F}W-f5P6W z2rYsJ!uk_-?BFHcR`#3siP5h2iNQ@%8uO~@ zErXkOF}P_OgS}6T|7{w`DEB@w%9~~~%A1xlxM?hdy-$q#-X{iU|18dC=8W}W>%;aD zwvTYmS!nvtnCDFw8r<}v!A(aR-1McvO?MjH^r*p2ry8t3X;**3`V-clu>OSgC#*kV z{R!(&*goRJ%-TS?Ho)2dYXhteur|Qj0BZxR4RFqZU0hCU&ih#9h(r4qJT$w^y=VKn z>?Viy$GvWLdHS;L>T`BIq<`?YJC{!#JFEV9!9jhu(d=^Y9AU1`DG{<|NWQ|9hJv%X}bJ^OVoe?z(RlQZh!ui35N;D%kx)sNLW zWLHfX7n%m!W+w5KV4!R zo3=doB^#d8-E;Qr;5)zlsczzDb_)K=?dNs#uHIpxoSF+3?BAcX`8nOT@7bl6#}DXN z<$sTzU6(t3(BzDs)4lt+o$Gy*5AEM@^ryRJUb|D>`su^^TOU8STl46#+!=Fi@NMR$ zmHW)RvMty=YuG$%*gR|4JZsoIYuG$%*gR|4JnJDhy!cs$eK*3shhg8tu6-3Ys8 zfL(*ZuJ>Tqd$8+0*!3RldJlHJ2fN;bU4y}{Phi(4u;0;e_NU*`l=~eG`yCDY9S!>( z4f`Dp`yCDY9Syq%gI$Bc?oD9#da(OS*nK7JzB2gFxGSFe?)6~zL9qKE*u4Op{pntS za`ytTdjZ(J0PJ1>b}s6_j<4~5ZIU!Z2Sr~egzx9f{kCn#;;)GSFrIb z*q9P*yahJi0vmIHvprvh=_E|84Bzf3hWsf>=_yC*)i-{JnUIK>{&eQSv>4nJnUIK>{&eQ zSv>4nJnT6&>^U{;`6-8U0jt@7)%?I}e&A-$NU9&)o)g@jAKcmvZuSH>JA<43!L47xt-rzQ?r699D$3QN zQJ($T{LEd8`af9x8|CWXVD)dX`Zu_Zd$gtgjdHbxu-Zbn&1dd(a=rz(c^KU0XK)`fz4{q;);P!q9 zZtsoY_C5(#!;C#@m|^o?Ve?*L^Il=|USacIVe?*L^Il=|USacIVe@TabGPAi$6#6e z*XPG?4Nz_#I&AJUZ0<8`?lWxeGi>fNZ0<8`?lWxeGi;taY@R#Z*6`d_wZwnJ-8@#> z%H!glHk5m(4Q!4!Y)&z3PBCmwF>FpTY)&z3PBCmwF>FpT>^%dp_YA;o4Iln7kCJlp zC}Hy`Ve=?q^C)5SDB-qui)XeyU2xm$1?O?`P8cV?a_kU-YvN8>4MEirmeO& zjPkag4{q!2;I-pfe&JS+u|KPSS2yXj@VDnzFr|mVOyzO^_+xj`) zpXQ)ZzwKY5+#EE@%|V0BL4(afgUvyM+kPtA@=hDdz0(HHHk(&Sxp{@Kd4;ffg~5O3 zZ+W-9aM+XQt#{h+Oz*UT+g>&5x4mR=+hYc|y=QRSlLoiFYH-`b2DiO!aNF|+n@3E$ zZSOovEXeN>*zXb8?-AH{X{!^zf7I&4@7=UI@w++j@V+I_C!RmNZ_$PZ5APgwc)`Ov zCw~8k`olYC&{u65<-_L=eOU1Dxr^UFqR#NSi{C$j2j8MAiaLXD`(eC;2j9l;A5mu* z_xSxIc$gdU`$sT!`5%~P@GN-sf0{6Q+%aQ$g&+LKbw+=B{ykAX@|AT*Z(H!M{i%l? z)gS+z^+u05{m%Z@GmhyWdH(vN%l+&3`nS(LzCZt<4MsQm@^|}hpLSBe;(}L>md$VO zU-Pc7hW*6zvk}gmHG3#$2RSc zJfy44pLgxGVgJBSyUP4I=s#ZGPduSi=FeB3TCKlv`C6Gjzr5~w{oa39EA!|2U;Jj| zvFFaH%%20lf8WTJZ<|q>KO_?sUP6*bw)X}%FzJ(nl*fD|~BiONq9c$RJhMhC8a|U+K zz|K9`xd%J&g9YX@b@r^4E`j|_MV zX`gY}&p6!r)x*us;AVfY??CFb{ziH8L$L2s>i8~&eV4+%lVRV?C6~+J_{8sQOJov5RYk2TK+P~nT ztm0G3hq@JC!^1P;H`L(a*%hC{Lz@*}!-FlAF@OgfD?Wt>+bh0?hdx!t03P~U@hLp` zpyF$ocK~A$b&i}_@hLp`xZ-Qr*hMPuQvKleoZ$BS5_QJf4Q}=XH#>uy{lTqY!L7f+ z%@4uNKf%p!!OfqQcAKAroBxB`xCFQH3U1>V+{QP!jeBsL55aAo1h@GU+~!qqn{UBw z9tIEZ+b+FtJKwk7lgxKt<_i~`*`@b5(t*2XohjcZyP*R(dSX>DB7 z+PJ2*aZPLEn%2fOt&OW|W8Z<;Kdk3#TF+P4^S(=|L{qAjsjLk0jr~c)ltCeC}4FIusRA@9R-}qk!{!RUHN8>L_4! z6tFr9SRDndjsjLk0jr~c7xhk7M?oER6tFr9SRDndjsjLk0jr~c)ltCeDB%45S4Tm) zIto}F1)Tk>!0ISqbrkTTzKhjS zP)8jFtd0U!M**v&fYnjJ>L_4!6tFr9IDhY}qo7L{qAjsjLk0jr~c)ltCeC}4FIusRA@ z9R-}%d+I1CS4RP>qkywN)lpEcjsjLk0jr~c)ltCeC}4FIusRBOQR`226x2~i0jr~c z)ltCeC}4FIusRA@9R;k80?un)brh7Vqkz>>z}cVbC@5D)0jr~c)ltCeC}4FIusRA@ z9R<9owYNG7>ZqfDPii^}SRDndjsjLk0jr~c)ltCeDB!%#S4Tm)Ito}F1)TkL_4!6ma&ZItt3wQNZdbV09F*Ito}F1+0z&R!0FFQ-bq;v%L?) zC+$5M+}@wT?HwMR``F&SQQqFk!R=ig+}`2A?cE;S-uc1pyCArIM+E;VdtvX2q+kDC z_fHy!bw_B92^g=S{-WXodC%_s=hXN9bJ+XOVedbOz5g8c z{&U#-&tdOBht;dVd8`)|6Hu>0ef27^dKFl`3anlQR<8o9SAo^5!0J_C^(wG>6*$K| z)T>agUIkXK0;^Yn)vLhjRbcfhuzD3(y$YPiWl^yd^(xd?uL7%Afz_+P>Q!L%DzJJL zSiK6YUIkXK0;^YnbL>dH3gzlmVD&1ndKFl`3anlQR<8o9SAo^5z66HuL7%Afz_+P>Q!L%DzJJLSiK6YUIkXK0;^Yn)vLhj zRp1=!Q?Ej~dKFl`3Y^~+>QyLLuL7%Afz_+P>Q!L%DzJJLSiK6osMuq+S-lGN)vLhj zRbcfh!T*bQar3`<-YzQUsa}Qp>Q!L%DzJJLSiK6YUIkXK0;^Yn)vLhjRbcfhoY5G2 zgpGN^f67^jF;(if@4h%&Y2S&#?YlC#eTN3O@7Cbq$5=61p6cERR$!RB_s=61p6cERR$!Nyc!^DbfYE@AU7Ve>9w^DbfYE@AU7Ve>9w zV~lY7zKH&|?~&m4{S}#W45p{TiBQ_Y|Ium zW(ym$g^k(5#%y8Fj$vcAurXWMm@RC~7B*%J8?%Lt*}}$bVPm$iF-F*!Eo{sdHf9TF ze;Tu;+?XwF%oa9g3mdbAjoHG+Y++-zurXWMb9303Eo{sdHf9SOvxSY>!p3Z2W45p{ zTiBQ_Y>W{$W(ym$g^k(5*`LO2DK};d8?%Lt*}}$bVPm$iF z!p3Z2W45p{TiBQ_Y|IumW(ym$g^e-7#%y6@wy-fE#<~+VPm$iF!s;bpW45p{Tll0FvxSY>!p3Z2W45p{TiBQ_Y|IwUdM9JHlpC{!joHH4 zpT=w{H)abPvxSY>!p3Z2W45p{TiBQ_Y|IvJ@yXC!8M96GM__Z`U}LthF!p1XUW45p{TiBQ_oc(FcmU3gZurXWMm@RC~ z7B*%J8?%Lt*}}$bVPm$iF$Aa7YEx5h+g4_ErxVfl()4|a9fWB=lRyw zQBmI3SHW%F72MWi!EK!u+}3ZwZCw}K)_cK=((4-Y#AajBu(4>^STt-b8a5UU8;gdG zMZ?CTVPny7p0~!LDOaBs^}q01a_>iBW6`j&XxLaZY%Cf!77ZJVhK)tT#-d?k(Xg>- z*qA45EE+Zz4I7JwjYY%8qG4mvu(4>^STt-b8qVWlEShq4eXy};*jO}dEE+Zz4I7Jw zjYY%8qG4mvu(4>^STt-b8aAc}8;gdGMZ?CTVPny-v1r&>G;AyyHWm#Vi-z;K7>lM{ zZDerEorH}=!^WavW6`j&XxLaZY%Cf!77ZJVhK)tT#-d?k(Xg>-*jO}dEE+Zz4I7Jw zjYY%8qG4mvaNBRj=fzkw<;J36W6^MaUm1(0+*mYhEE+Zz4I7JwjYY%8qG4mvu(4=Z z9W0z}HWp2}v1r&>G;Az7xW%I376XaCx7bK-*jO}dEE+Zz4I7JwQ!Lti{5q7Iryrc+$>#M(d5R}{4?vWsc(V5fM0tuQ zmlQ8Gzdq`u*s}TlQJ!MsCB>ObiZhoKXD%tuTvD95q&Ra)apscZ%q7L-OUhFyLtdD9 z3gf=IZq;+g8Na1CxpxSJ{l>|upV|79KU?4bxW0a%TtC420oD(&et`7@tRGS1H`u(5jBSUqg49yV4Fr!#`_KGJvl2-`>4KEn19wvVuVgzY12A7T3l+eg?w z!uAoikFb4&?IUa-VfzT@KBhC8lFn#KI-@D+jHaYBnv%|FN;;z{>5RrZH{vsu&J?_Z zBFfVl%|f;E_Pmb9DBp1i9h=3Y9>TgbMh>63JpSJGMD_&uM@jqIy*7FnLn{ydjp z>%+OeXLFQiwk^sX7ua!u9T(VffgKmvae*Bd*fUnxae+M(ggq04JrjgI6NEhzggq04 zJrjh}nczY`v|r2(`vu!C*nYwG3$|ad{etZmY`CCsJGvAWVd`mj>E$Pg+q%+@=&U{Ncqx4Rj_#CA(-|@MGolDaX>CCsJGvD$1 zV3`luSLw{UJe&R0&z}qHQ=aR4hD&*7+oIfYfgKmvae*Bd*l~d!7ua!u9T(Vffjv8h zJv)XyJBB?whCMrmJv)XyJBHKQ@j^bdUyQZ=g6$VWp0p39rpM|6iC`lVok~W~UeR|YS+JKU@ z0poLtww9(Jk~W|uZNT`w!OVy3tHs$*{rtJGKIOT;p7m3n*|sQGvjICUu$m3naS3jk z4cKvk9T(VffgKlEjRCC209IoFt1*Dp7{F=_U^NDC(ikk{L;JNf=9~SZE&B!AFW7#; z_6xROu>FE_zmkTeBn?SP8j_MUBqeD`O45*&q#-FuLo$AUGVLbKgLj(6XDVq(#^)0C z9bb4!`ypvaO45*w-!IL4$i7M%nDP6cu`_=bGFzYLD&p**u~QSP|FjtlI#z>W*- zxWJAJ?6|;cdtk=}R*M3wMS<0#z-m!owJ5M!6j&_^oU|wl`OtphH~R(KFW7#;_6xRO zu>FGV7i_;^`vu!C*nYwG3$|ad{etZmocoouM&tKvQzvPS#_!ptJZX)_@7bn2X^qD3 z*`_>cjY`tSjNh|OouoAypG%Z4O+O^95qI!#Pfo!G{lk2aDNkCdXSJXD`Ey}?%5#6! z4pE-jwkUtH{q8F4xWH<_V8;bk0|q-Tuo^Jfae*BdSj`fwW(iia1glws)hxkkmS8nY zaMCO-FGV7i_;^`vu!C*nYwG3(oyY znzZrz*r}5=X(egW#_waNPST`}-^WgQ(xi>w$4+_DP>tWmPI=O#jn5^@m!=<*CT;L% z+$9y`rGJ8*kCnmaMI2#5A7ptA7T3l+eg?w!uAoikFb4&?IUa- zVfzT%N7z2X_7S#^uziGcACq>mB<*5J+QpKzizR6nOVTcuq+KjYyEuMtKkX*1op*`H zTus`=g=|}zK1tfelC+CxD=M*U=7vmPlJ;`^cL%a>^IU?h58L1TOj!TJ`XAQ+u>Obj zKdk>@{ST`hh4nwI))7|g2&;93)jGmz9bvVOuv$l0ts|T?mJ9jKKH@9;2-`>4KEn19 zwvVuVgzY12A7T3l+eg?w!uAoikFb4&?IUa-;oQfhaV<&X>OKGHJiY%vIB8t{y?`iB z8rPCEuH(P&z;n!_hm*#2{P!LH*tVtVlcaI=w+y0R`iHq8|0(w8xdhu^IB9x)=16*e z=8kg51wN^1k72dPu;T)&J%$|@*l~e3x_q08#tvp&cK^srE=lF{Q~hAIvXrZph1JT! zYGvVOXY?g$W$kbH)_&nn`vu!C*nYwG3$|ad{etZmoab9BpP%Xn+b_!P7i_;^`vu!C zIQJ`Qq5Z6lP$y}j{cJ{g(n9-Lj`F01_Ol=5Nek_}BFd8%+Bp{GNejJH{gAZKC2663 z=fr%-zFM69%q9B*TOUr^Z{O8DYSdxJ1y-XDJ1%g0 zU&Zs)R8y{|8dg&ctEq<7RKsejVKvoo(o~Q8lR0L;md1RuU$kYvVEYBzFW7#;_6xRO zaPC*q%)9pMsgpGGt`(y^Y35y9MtRcAyB3Y|q?vc^8s$kd@0usdolDr@_`*xt4@om$ zl4jm@X3XvEtHs&R{IM^v_2HBw;NBsguO6N{wgsEZ06Q+QxeT!50-MVKJ1(%f46x$@ zxAk+_p!S|}wfC^vdsyu~to9yOdk?FFGV7i_;^`vvEIr5qFE;bZ-M@5DNsF$bp{6XWVpo^ni#!$*0_ zF)?l*gKoN`QzAxF7$2|JgjA5xAfgKmv+#lF+fzADa9T(W#AJ}n$)zZUi>0!0>uv&UpEj_H39#%^aCoTPW zzwn{`g6$V2dN9t#`KIQrO=BZJh*|sRR@38qquziQkCxY!eY(5ce-(mX>I~K5c zd9ZnTuz7i~d3msTd9ZnTaMR1h`zPh)E#yP{h2QKKY`gHkOpzsLnI$q})a|w^5#Q8`bDWdCF~6 z(;MX}w^0pnl&9QAHMCLQw5Bm1Wb9v5ef!8<%4~hgQ|_et=Xk!kvDC3G*uKN&b;9-? zHm?)5@348DuziQk>x3N(*!*AE{9oAoU)cO#*!*AE{9m}~x1(Pv|98A!_|SgA_6xRO zu>FGV7i_;^`vu!C*nYwG3$|ad{etZmY`9vQJ!+B%}obDM|$cOd|f7&nDe!=z&wqLOQg6$V8=LzC8Ipu)nLwD zl()RRv3dT?-4W*EMV)lF!y-QyKA(A&>wEtR<(YH4_MJN3Qvus|*n28q`wn|g1#I78 z@2P+t3;3|l-ro&pOVMBNd!gL>USRKgfxYhq_P!U``(EI5-^)@RQ~SkyvtO|Ng6$V< zzhL_X+b`ID!MR^cvn}TdHl#aq3css1oPEZeTzmLkwc$)OINh03(w#Xa-I-I;ojE1l znN!l8IVIhhQ_`I|CEb~0ZhN$w?#wY4KIT=nC*84QPJR5ZePsS*wm#*5%JY|Wf3yFG zevJ%g#$o@^?#OUXA3XSZWH`SM9{fBqoa+YB;OF^+ z&LDX3^ZY?ipbw)h{9qqp#}sx%z}f(71FQ{jw!yZr$F^YGf^7@7E!ehT+k$Niwk^iAeU>Yn z?nda--3WcU8=+5kBlPKRgg)Jk(5Jf*`u3iW=eKuq#pkvQ+b(Rou2OCzO7MX9Br4r+b(Rou4tM zUD$Tv+-}?J#pgxF9&^Ltwg(UYn;TBKx#6(6;jp>ku({!|x#4izzsEDp4X51PaM;{% zxWyu(zPaI)n;Q ztUqD>3F}Wd`?JN6V;p7rZcZhfaz*=;D>{C^H+9+>LHIf4iuNg2v`@LBeLEM3`sNby z9CIpRb1GqTDq(XfVRI^Bb1GqTDq-{f=zC^upj;bZZGg1_)&^J`U~Pc40oDdsf5Q3` z)}OGsx50nLed+YE#V}(WWy;Mlhs`mE%`u0~F^A1Dhs`mE%`u0~F^5}RI>yl)bIM!H zJj%^6r`#NK*c@}%9CO$lbJ!en*gROSg zC#*kV{R!(&SbxIVpXQlTF4K2&GhuTxVRJKKb2DLcGhuTxVRJKKb2H&~rd(iiGhuTx zVRJKKb2DLcGhuTxVRJKKb2H(lg(&nfvo=t!4X`%A+5l?z}f(71FSz`{R!(& zSbxI$6V{)w{)DqXn^q+HDAV^RpUHXb%?+g7+(6jeKse<*_T~msZf+oKZXj$<9BghN zY;GWIZXj%KAZ%_RY;GWIZXj%KAl$TJ(Z|f%fKRjm)&^J`U~Pc40oDds8(?jK^(U-9 zVf_i~PgsA#`V-clu>OQoPG6sL)B2Q~)~DRGKINwMDL1W8xoLgMP3u!`T5lc}zO`N0 zc46CvZ5Os(*mhytg>4tMT{yREP8{Xt#KGpo!RExl=ET9~#KGpo!RExlDJO0rwq1N~ zyRhxTwhP-XY`d`S!nO;ioU%UUM)fH-s!zF5eaemMQ*KnBa-;f`8`Y=WsNOsv`fIze z?ZUPT+b(Rou$U2*$J`uvh?!O5S+Kb|u(>&~xjC@8Ik34o@DMXI=crFP zN0yUkWc^@sb0{}A2R1hcHa7=uc9MUg{lVss(D%&PaQ3W~E}^{HMo!SU4X`%A+5l?< ztPQX>z$rgS?oyp#{Ykn0g!Lz^KVkg|XMdXKLb;3|%ngB4&Wm#+{F8ECoJ&!ja$cN! zQJ!*M{ES4oIT5sFZU}5{2yAW$Y;Fi_ZU}5{2yAW$Z2kg$%$)Kv{QRO#9k&7223Q+l zZGg1_)&^J`VEqZ}PuLtHSbxIi5W)HrHirn#{xr{ma+$uHn*gVr3*XgfynTlUr<@Dl z`B9#7F2;X9g8x;M539+C%}s#KO@Pf!fXz*S%}s#KO@Pf!fYr~_$IRM5xi-Ms0BZxR z4X`%A+5l?n3b68;g38x$u*K#orljh&GR*Z$(czmKZ9#$I< ztBr@%#=~mkVYTtFns8WcJghbzRvQnijfd67!)oJUwefIUABO$vx9NLkZJ=BmU~Pc4 z0oDds8(?jKwE@-!IOQ6+rVXF#PwMDTSbxI$6V{(__NRIz%4PhZh6h%|1FPYI)$qV- zcwjX=uo@m%4G*lY23ErZtKosw@W5(#U^P6j8XmaCyGCI(Jg_z}f(7 z1FQ|OHo)2d>rYsJ!uk`|pRoRf^(U-9;p|WIJ}8&zySWmuxe~Cs60o@vu(=Yjxe~Cs z60o@vusH&-xe~Cs60o@vu(=Yjxe~Cs60o@vu(=YjdVcztSsN(V23Q+lZGg1_)&^J` zU~Pc40oI?e{)F`>tUqD>3F}W-f5O?H<{eNj)Ay8vVC*+OQz-|*SaFo690X&_QJ!)T zj73Lzi%|!wpQl~5`mkDkSgn5WGdT#xnd3QX^{Jy)A68FJA2VwM<=Oyi1FQ|OHUvMD zFEDNc<=Oyi1FSz`b2?!C37gXa>rdF64p@J}DW}6TvQf&_H_~^td9d0%SZyAxHV;;t z2dmA4)#kx!^I-LIu-ZIWZ62&P4_2E8tIdPe=D}+7V6}O0(#tKx+Cbm60oDds8(?jK zwE@-!SQ}t%fb}P=KVkg|>rYsJ!uk`|pK$i4IycH?`kpjzo-aO-u z@}zm|ljhAc`lzEejCR$A!D_=`wPCQ@Fj#FEtTqf*8wRUiqK}!AW~|o+>SzP34X`%A z+5l?!1@zbLkR0nSPdbpKVdb5u>ORzKa-|Q-A?#6X_Ll(qYa-VZPNH}w1p2( zTCN*n5b?iBn>79#ZPZEHr19U3YvpQ_s2{p1%9A#U-+&9973E2rggv3lqC9Dn_>H;H zaZ#T1T??^w@QME$zIsOMHQpBG+5l@Ctj(}mFIfE*tUqC5V?*30-huj)a{fSn`aYQ2|Q*OJk?ZUPT+b(Roua{UbJTUg)1ju-4W z!ul50x3Ip2^=<28=;&bEf^7@7E!ehT+k$NiwkrYsJ!uk`|pRoRf zvp;>e&|lvzumOME!1@Q)Kd}CR^$(oqfc~Le|G@eOUXt^K=j$I>|Ku^s_E2v9>`yrN zF|+mm`1!d`=A}640N7(O2*zZT!??>40N7(O2*zZUDV_UFo!L|k47HnIv zZNat$+ZLSL(ub5gw_)ct?A(T(+pu#Rc5cJYZP>XDyB39Ai^8r&Vb`LtYf;#>DC}Ak zb}b6K7KL38!?};9K>xt{2i8BZ{(_!S1Kxt{2i8BZ{(}*0eh|id#(X{t^s?l0eh|id#(X{u7Q7S3$`uTwqVXDJGWuaEMU(pV9zXI&n#fiEMU(pV9zXI z&n#fiEMU({;M_;=XQ15s8G_qyPs2;v=iZ+{Ti&0*9MC_o{(mOME z!1@Q)Kd}CR^$)CnVCN+4oP?c|uyYc2PQuPf*f|M1Ct>{q>z_PElxq*=*3bTgb00HX z|Bs)a>ttS<$$Q;l=u;UIp?y%zyJMOUK4m<9!;|@FSu;UKvA6Wmu`UloO zu>OJd53GM+{R8VCSpUHK2i8BZ{(vQ&GtQ$5~3>%Av zjSsgoxNgu=$N8Z3DYrgseg4;&5^RhJHU<@ST8xPQwLWZp*!oeY)#rbG_rktQVc*rT z?@#{M`mpt3>%-RPfAu-658>=X{mlPbAGSVhec1Xu$2BVKniF5U*>fYWbS zjOQlszt)GX4_hD3xeSdXr@-HuNo_@WduEsZH`w~AtthuX&oS=?_BWy6*7wL+Yd$GF z$NI4KVe7-z=Q-wQ!EKD~Ac>ZSKYM+nfyhtJg0rf1-I|M;PxFF&$m9$ zu|8~l*!siwb^qQkzNI_$(V4ZrVUvEw=|^^7eq?4{@q+dHw{3n*_ll>FWIjFZ*EkvH3GA|NE_dUeSI1b=w5*ddC&hA3J=E?|6Fdv~`CZC+cVZ z=E&6U?)ApXcba+Q^i>ZYtG{5MP3zS8=k?gI)t;NyRc}A9$A(>Av}rx&XP@n{;phdM z)LXZ>py!zn&D*3N`J)T_u;DdZ)YC8jc<>4Hx2#XU>HWdxbWq3NG=cq16WIKnsB`4Z zI-J3e!2W&^Y_3)+?^69>^YtkAck!amBhxD9ZLqnSu)jeG`x}(7`L?jX_X_)auW(xv z#xwnGWy<|+Ww@;~V_f_lbISc4bGYquqfU#V1-IB*aErMGw|IVVi}MG!_GZ(7Wa$G^8jdDSnc)zPv}|BIV< zDKkDjt*-F56Z@avx@&phO=ER@KI8t4Uma48T4QSb?`}WYvrK%!SRL)8j&{P@3EN-T z{=)Vb)^D(WgY_G%|6%

wnmBgdIoNafF=@u=4?SKETc^*m(u}dy6ph^ZwmdxdisN z_W$_2)zyB~ z_jIe56Rtj|JN%3}b>7=nFU!31oNlc%=P+L7zUk+53kJUYMYnanqhQ}rujhyiK|7km>c*!;UH!UNE&>bNBRm z>lw$C-#xZzIr5OMzJ2cT&Clt!ea|knJbpk~b;EPIdybu5mplES^8L|sx_2M9bG>i!q2&!nf4W=dwL8_V zpFXVI`uMrsnn&-*=c|1C=?`?TUNEO_w$~2jjtxKDefPRKb;GB3FSnd{dN=3FIZ-FQ z=SzCem-L=5={;Y3&*!oGQ^tC$`s2>;uSY-naCgW(o0resv_swJp@+J|CvRGIpR|3Q zaomr(jXpoQY;yUmy8Z_r=;j`|Q8|5=*Vn7|ySF?3#0|x<%TIK#NX4ap-_l|Cv!&fW2d~`-#mn~=g zrq+YLd`I`xPk!6&yX=fQd)8guwXb=kyK?r7y7#*GbiWz??!9?N-S_1Wc2_KSTX*jX zGwX57KioaI%(uET_S&XC{0~3to>xY?Q+D6BK7Idhy7ztQOWk=#yuNPm_NTh-4*Wv* zp0j7wS0BDy+3~2)b?=`>w`bl&HdR<_2E@sSoR&p z^xbcsT{qr+wetJT&gmu}w@dxdq?OcZ)Qiiq<=i#4FLO`Wv2L-_W8JTRQp$e6+c7>b zXC1mr+2V+8>Rs!-u+;Nsmy_mgTfe>GD&@4vv&$*RyuP0C^_9wYE6*;=ojI$X_RAH^ zt9O}QZW-CGu6gZ>~)?7!=wH+QFYGx**qJMMRQx6e*9>fzhYDwhA} zin|xVWs|Ml?RuwRthU+U`z zo}+(wzJ8-!{fRyL89Vhq_B$?lyz)5mPVhSy-r?WhSZ;b>sSiAU$oSk_<%mPe3m%$X z=H9b?U3Qa0%WBVhF#0m zkJUQk{@LZ)1-q3e-&*Sz58R==?$X`MH7}_3+^e=NJMZ6dXP50J?pSB-a#%TbyBHZvR6{-Q)Rdm6LA! zUbp&2rQUVd>g981+}C~S-@3Z?H&-na|NbZ4cAxI*Y7eel?tI7Zx@F(c)gxxCJpQ?( z{GJt7DrbFRdeqK{_Bf$Mw6FFCF%(a>_@h)no4bi&Fo2y>im^)9RUP z?pvOE^V(&NKMc=2=z#LqN3B`T-gbID^xT8W9)DP+Z2sZt_2}ykF6Zs^{PM^hV?6PM z=aefq=%UUeAO3asmw(g6|6cPC|K2V0wJx4{=2!3TPW^osZN2Dsw{|bvx`YiAzj0&t zlD{fp+h%XPu3Pi05;m`U_dj)yez`bnldU(TOiD-}~&>y60Rsr9S`RHOpsjysn$@=_z%e9}a8d?=0x9 zecP1!_^~f6Bk%oQx7VyGb-S;uQa(0%Pq+JOQ|f0wvvS#Hw}-n4|2nz8d6?U$ulTEO z(s`5X{pYS+{^}b~b!#0mx!(4rRmy8GUapi^Os)^T^Mz&okrm2D4@{~z-M@Od|Fl)g z!52)b6aQ_^GUvH#l()WVQvKrbFD*N*v{w1i#*^xee?Or-`jMBF$xltJ-`jBg@~Zbt zD1Y%U6YCSJZCGA$&$?x=D<{@{XHG6Foc)Tj!I=~5+MnL6JnxeA%T@22SPxuftFp~< z8Gx_&uxDBt7mZOY~6yrMjM#>D!~=kHKH_Tai@+2J`W|8jOY=tC3A zk8hh;KYsFV<Oxv$K_^DOO zW#><-w_J2UIr8Qe$`SWZsuTX|ptAp0mn+AuH@WWjzJtq~fArL_#-3dN^G64lpG^8y z_qU&!T>s$%2bWWidboSnU6bp_-*!+r`>uPsufK3geeRV9l+P8 z--2%5;Q#;FX7BQc+pp{H{?wGZ`sep7`+fdv-S@AZQV%+9x3c1guIhe!&y;%nQ?tv@ zPyKwi+c3VnuD(P0$k#6JmKnzVn-6YNj@<0RZqs2t-0=RctoYpXyFW}An?KI0|3AI= z{*<+AUjMU?Gu{Oo?}CkYMV&Dna_kMQpWC8N(}G5wrV$Np+R@;qDGhE~)8M8-4Q|@h z;HFs(HqJm>O-~r*O=lR~^oPMsml)jiios3C7~J%Y!A`BL~_oE1O-XgbdMm2B9dGTfJ7Bk1VKa*Q26>^ zcNJUvzPo4l3Hm+Hdv?#^?C-RF&-7H+RbAa(-PJn0ZEQeXw8cGPg$lIZ5`MViq456i z8vd8&CXlnN1L%1r%K3Z&$%@Y%5c7EiVm_xp%;y(~`CJ1rpLZbUa}dNF8&AwJ>ckwo zPRudw#2o8R%rWr992-x}G4sS6OHV9wVg0-K_q_Q3o)=@DB5M?2wYD6pwdGLOll@xp ze|Q~3tv`pd{tW$>XX3rGmICf`Q+IRQms#s42WCBJo;aDsvL1yxf7adUc$aSHzalHK zC-_^nHXEw7*}pqaMExyoT8CYh1hjVa>B+mp=`~ZtM}|KXwmjUBY=T}R`e(9*oMjCV z{P))JP%g3si)_JiFFjc9r3cHs^kBJ{9xV6LgXLa&u-r=zmV4>J{~h)a&k>n}W$gv5 z)~-WYyGAU;G_^LEk*kGysL*A!W_Z=mtwF^$SuFjI`m%lq7W)YG0T|vTz901#ZN#T@e{z}CxFFI0E?dh7C!+j zegath1hBO2AFWa7H5SzWXWxt8n%JCww0^7Cic$Zc*(JPJ_pjEIf20q(&Og#6(LLRs z|LWSctWEtZHV1V?2f*SZfyGAxi;n~r9|O@bOS890T$f= z%U&l~_Bx?6A|J5G2Q2adi+sQ$AF#*=Eb;-1e83_fu*e52@&Su{z#<>8$OkO)0gHUV zA|J5G2Q2adi+sQ$AF#*=Eb;-1d>|_=A7PYB`@zzFux`I*sgLLD`VxPFa?M&+e3pd9 zEIwmG%x6!C`AiBipH(5|Gc3e>wuP9_yb#NGp$&he4rqCT;~BcKGQ+WXFZ7d3_7WsfhK46g# zSmXm1`G7?}V37}4=m}W#1T1<27Wsfh zK9H4`k1)!m{a|T7ShruZ)W`F6eTmaUxn?aZK1)J2fzOx_^Vt((K9fSsXH|=1)z zZ6W3}FU0a)Xu}_=16rP7c^6pp4J`Tw7JUPYzJW#Gz@l$p(KoQj5G*nTiwwacL$JsY zEHVU(48bBpu*eWBF_~aKmqa#!&npp2ei_t}{4&IxUk1!)MyNiYB_ZZBCd3lsg!&Ty z36}Uzu;>!_&y<72T;aVEa|OK;`G7?}V37}4=m}W#1T1<27Cixro`6M9z#<>8$Op30@)1V4v>z<(2kZ80mil}5na*()9yi4LXp;sawu*e52 z@&WT%st_#l0gHUVA|J5G2Q2adi+sQ$AF#*=Eb;-1e83_fu;>X`^aLz=0v0_1i=Kc* zPr#xlV37}4n@=1Xu zpA=Z~Nr5Gw6j<^}f#tivf20m*d4lC#V9__Q=o?t{4J`Tw7JUPYzJW#Gz#>Di$Pg?t z1d9y8B15pq5G*nTiwwacL$I7-0iWVLSzyWQ1eUx`V9DzQmb^}2$?F7`yiQ=r>jaiq zYp|S`0n2$Au;>!_&y<72e&f9o`whJk`G7?}V37}4_7WsfhK48%ku;>X`^aLz=0v0_1i=Kc*Pr#xlV37}4;iFmV9Sm$#({pd}m-@HEVnu z$P+B`1dBYuB2Tc$6D;xsi#)+1Pq4@nEN6@n9 zEV=){a^?#x=a<29ei^LW_GijO&Y+8$OkO) z0gHUVA|J5G2Q2adi+sSMGhopfu;>g}bOtOs0~VbDi_U;WXTTyKu*e6p(((~TxwIcF z?FZ}jYnJ+WzSIY6nMmG7luO=5u;gt7OWsDXO^I(GI+$dP?VF2@;4>;HSH*Nbf zWg_QT(S|qp94mB8_mUG`=kq=np1D3u6i+sSM zGhopfu;>g}bOtOs0~VbDi_U;WXTTyKu*e6p(((~TxwIcF?FZ}jYnJ+WzOK*Dv?$lC zWyLa#QHNzqEcr}P&V518k$k2omwcvR?o+BG`AktR-v$07bwJA#Ebjt~zJW#Gz@l$p z(KoQ@8(8!WEcyo4zekawsvmj+Iz}wIg!+G`9Qe0GZIC-3pjRRvF#qmI4@EvG z7x{oiK46g#SmXm1`G7?}V37}46%0b;fBXb1O zF_8~+OymO=`G7?}V37}4_7Cixro`6M9z@jH$ z(G#%f30U+5EP4VK`GDoV5%iIkk1)!m{a|T7ShruZ)W`F6eO@P_zR;{?CHbK7w~`MU zEcu|pk`Edz`Jlm)4;n1_puxOO@~7&6mM2*B4J`Tw7JUPYzJW#Gz@l$p(KoQ@8(3rr z78!y?hG3B)SY!wm8G=QIV38qMWC-T9IFhF@%6To0e*3&eN38o=v(!f)Nqv1T_}^!N z|9uwtKXDe=sk7uxoh5hbEV)x>$(=e&?$lXwr_Pc)b(Y+zv*b>lC3os9xl?D!ojObI z)LC+;&XPNImfWeccj_#;Q)kJYI!o@MXfaXUUy9 zOYYQJa;MIcJ9U=ask7uxoh5hbEV)x>$(=e&?$lXwr_Pc)b(Y+zv*b>lC3os9xl?D! zojObI)LC+;&XPMhOYZOM3kT1>BGtHQUAo^-G0M|i9@^x%o%BL2)Crp&?d(?dsY-n7 zU2nSXV@nfXb$E|ECo>oEvaPw2Q}uS^&dG3Stuo2d2j&y6`>tw|eNKDgVQq;l*EM7pI+?gwRs?DCP@-@3% z%W=69)ahDafh%~bG;yIa9o@{eRf*@X{Ly|ixfXG|c3sbZ!@m#peYufxUq6)k{yCvM zr_Gw(p*-KeH#+;?b)_R|k8fur?ey)Br2YQ8BKa==y^(ycmqR3S@bZa7K3;B-$j!?$ z6nT0%hazV$|4`)b`^9j-IMrWH^_Nrqv4( zPW6}b@|6B^s=u7-FQ@v;ss2K_^cU(&f8jaOUwFRs7v3xVh4x5)p`FrSXutFqzDxQG z-z)tEIY@s&KGI*1oAejtDg6aGOMgNB(qHHo>MtJmE$##1ao?&tK&-k0#Hu?$thxil zsyjfex&y?jJ3y?u1H`I3K&-k0#Hu?$thxilsyjfOx&y?iJ3ySe1H`F2K%BY*#Hl+# zoVo+VsXIWNx&y?iJ3ySe1H`F2K%BY*#Hl+#oVo+VsXIWNx&y?iJ3ySe1H`F2K%BY* z#Hu?$thxilsyjfex&y?jJ3y?u1H`I3K&-k0#Hu?$thxilsyjfex&y@W9UyMx?g~lf z=i{B%A6M$r3d#C&COChGjLWgKLUORj1n2LNabxGWG6B&fg*9 z`hQ(MS+``e^LNO&o1ZP847`4-^LNO&2hNmBf=bh!zeC1-@N~K4=_)gwzeC1-vAb;Y z%{8-~zeC3T)TC^Z8ZyWEJ7nC$W6C6Dzn<&-9Wrjn_ob7%moISs4jFgAlulZWf6Mth zWZdjQrIO#iUF7^7GA?s($z*%wCC=X=b;rtyk zF6ve+8U4))=kJhldmk&7bT6{f`8#CXsb`8M_k6p;`8#A>M_+&3Q!AXmL&lBVQ7oCa z>>cOtka24-ES{8Dk~n{djJt1a@uX#E=lmTqZfVI9$*zO3^LNO&?Ndr54eO)P)ER_^GvdH;6WZe2x>15Efx17I2#`XNJbkgGL z1XCiO?masCb&*Lhdj`&v$Q{tg+J;rsEKWs{xv8{LYqLh|7~lbpXp#vSNYA?bJR zMCb32ao;Veklgp8zXSMXE$J z;5Ul>f!`?h2Y#d2ANY-8f8aNY{ej;o_6L5W*dO?fVt?Q_iv5A#DE0?_qu3w#jbeY` zH;Vm%-zfG6exukQ_>E$J;5Ul>f!`?h2Y#d2ANY-8f8aNY{ej;o_6L5W*dO?fVt?Q_ ziv5A#DE0?_qu3w#jbeY`H;Vm%-zfG6exukQ_>E$J;5Ul>f!`?h2Y#d2ANY-8f8aNY z{ej;o_6L5W*dO?fVt?Q_iv5A#DE22*_9s;KCsg()RQ4xS_9s;KCsg()RQ4xS_9s;K zCsg()RQ4xS_9s;KCsg()RQ4xS_9s;KCsg()RQ4xS_9s;KCsg*wUnF_f{)Ec@gv$Pe z%Kn7P{)Ec@gv$Pe%Kn7P{)Ec@gv$Pe%Kn7P{)Ec@gv$Pe%Kn7P{)Ec@gv$Pe%Kn7P z{)Ec@gv$Pe%Kn7f{&@X~)c6&t@hei}SER2T{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi- z{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi- z{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi- z{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oi-{=oj6)t{R#t`r?S zxyj*<&DWY&ir%uD9PZfs?DXJ==NFn7daH*WY;M(fZ@4viF@5($;J$h%{LTbauLoSHUAMqx& zZCRcgQR^S)Q=5C;S0h@T%%g8vGpa`P(K++rbV1bU z%$pAP?jBuNJ(?3Na=3SQTY>7)tj&uZ?%jQ?QMIVV{ACXJ>y~JJel$NFJKVcFuj6^q zJG&ApZ`QYJv@yrKRR4z==SGhdeUF~=;>T5@PY=FN&u>?}O7xdrAJTg}cc>gSedi-; z&(v=!Me7D{pmyf#Qz^RntBnrrfBou8(F=<=(Qo9oBjuy{@9uKApZtna6{7bq-{o*W z`8VF4{Iq6=!~Nt(F3E^i-m%@`e)2;XWJbA)e(rET`E$2ajBd%k#o>PPm)@)tUD9f! z!~Nt>)~ga-Sn)%L`^jgmJvW*+VztBld|$R7twP*uTvvx z-eEpHe`o)iQFZ$|z4!6OwW6-`XHa_{nO!@wZKqN@pJ-Dj>VJF^wZHV*I?%E2`IXzC%8a4>s10O7@&X?aBXoooMpunZzHyTsP|d`z&hn*7gme`d3eL zLE~oOuG|fxS)-@9x7XYd7QCT;WSUHO(Z<%{hqqlAJ=ki7`>?Oi&GB@-Xu2FmI zqfq5A3RMoHP~|WRC5I922JDpW!f4Hk8E(W4pPKBOFO2-%A1-ILPtBMz^`h6yZgPX) z{ls({Q70PHdcEs--zR3s4Yi|7tAFSUU-5}KetoT|%cwQ({Y9Uc&SPpuZ`*fWxl*5* z1NCY~730LO5pFfVm8=<^s1Un3tG+OKFRmF)`eCWdf5jft{pFfb?tO2&$$R&ilBa7% z&*xw0@(ns@f-$wCpB`P{4%9kkuD!N)bYJ0luI#+u%#H$eqKnRX!#(|5_OQffb)r?5 zz3v{*l|L;0W8LWEX0zPGt-m&W{?6rVyVE>2p>A}~GRU zcQ-w_-*j$KBU;jIt6PwBpLu>p&FJTn+uY%nUz-U>Yehva-0p@q_}a8xRXf^L=nHDw z&2eV5Zu}1Ca}tHye#?m7Sh~ykoJ8Tc{u$Bjzwahn{oKPD(HC9z{Chm&aqWN8cqIM< z#wO{(Mnd`_Io`TRJsj{|8&L{YdYnC>k zT-pGZHh`rKU}*zb+5na|fTay!X#-en3wX*^nNj9jyXbe_`>BlR{)hMckF+@wvxGK( zJ~)UD^`ty^;eiJmMMV})q4u|JaA|bkq%6KM_r+1WYqIK$JW@ZpZ2mN=BjX7ALY@ic zvyjxkd`6O(&rTBanMz_lYe~#!Fp2qWCNZDcB<8c6#C#T*n9m3k^VwlyK2uE0XN`&Z z3^FmFO(y0u%f#}V(!a<5jbo*bTLaIX9YoIzol3sM<>MMftKAghmAx*F?jM=OxjJ1O z-Bv!Uj`%A7N}L<&{F(81;tS!uYyO&_F_ip_&~xqosJwEa?OQ#S|Xnkpv9-GCWG}d zB4@D387y)Ji=4qCXRyc_EOG{moWUYzu*_w^*&A1kO6A>2ZJYUJMs#Vn-NYhi)R8$0 zxL7(P>i$$#oqo$Rqk~g+Q2jqbR?-*v?a1@N|5^L+pP9?Z+zsy?-XJ4-Is0C+MU8)| z5EYx6#Ud-zkue=CV>(#Ibg+!+U>VcFGNyxNOb5%D4i;YmeW6*}fO2UASlR%VHh`rK zU}*zb+5na|fTa!Kf2KeGnK`nwAK$q3#|qI6le1)dL7j}~_{qPWN2AW)>x)xO`h^|7 zd9JEI7nFc!)v99rSsh}Z&(`=eJj9&yLh4vm$ErHk$Nf{Cw#6ztAB#`ybJ!y1D6zl4 z*LmAP?C;b??owiZ*RJz-D-ip;H=Xwhi2Z$-$bm}i@5w|CRAPT`p7Y;N?C-KeE>&WG z$6ey@oFYC|Hg7`z{CA-Y{|(=Wy7(I~o`Gk9@oc;UjCbPQV6+8o0;7#+D;RCZH-Pa? z_%<-U72gbo3?K_IWaH&%sg9ScmoG77>E%w0ei+rXz%10^a--@K^K*##`61QGdM`1z zhnU+*%c{!Ah=GpHIQ6 zdfEPV}@z6OiVfJJA(qBCI8J+SB= zSac68It&&a28#}Z<+lKq-vXF_gCSUcQ(*Z`QJt*cpaIKoQ z`Hh49+F&AUgWh*al<$;?@8o@hM6G8gYCSVi>zRpK&rH;MW}?@LPEE~oL1%W1p=%XkO&&!;{H`{$Exfqgqk zC&0d)q@!TpPSR1Z|6bB{u>W4tb+G?l(si(x8~tX$UT!2)u$Nl|S%ba&BlH2-mqm~% z*vmhHtiiq?BlH3IANic(m;O&&OaE8q8h`JsAHEm%9y$U3d*_Z(uFpPuU5Mc8sQO|D z@El_QyN=NJR3|H^IkC3`5&9nG-Y!Mxd$6}l5&9nN?OTMt2YdS#q3^-ozD4MJF!vWR z_aia)Z-hGB@5HPR#H=U8tUtu8SH!Gu#H@$Jte?cJx5TW^#Q!Ki&i~}x=>IJL5&Qwk zg#_l`xcCW1`3Xk+1d$2q^KYN(vrQlt*`kif7A&#_OCN!ykHFGLVCieH^fg%e8Z0^k z7M%f$&VWVtz@mF#(LJ!}Fj#aLEIJJ4-<0^7^jknV{|3nq#BXYM%R=I>(r=3D@VzVQ zIaZYu^KX!t+vC*piTO83%-==K?Ih;*6N?SRbNG9yoaI0)wiI>5mV(8Wg2g6-#U_Kr zCWFPcgT=Ok#kPZGi~!3R0hTcWEaMAU#uv=jdSY5<-5T0U10exuzVL- zz6&hh1(xpu%Xfk0yTI~YU>QTf@{M5qjoE8mH3R+`%4O~emboXF)7Z`BGX7`3dt0nvmdOTkxV$1HD^E5AtT9o z-yZjZuhaM8jAZETS!;BD?JmLIV#Sv;!)s1tBCGlH2m^anFrw5bkfA zkzCL=tG>L8*ZLB*)|X(d59QKku(TO0Z3fG?gXP=7^6g-eAy{Mx78!!2FTm0lVCf66 z^eI^S6fAuTu3o?Ybm$CN{5r7sbzDw<9hZ||2NsBVhTB zfaNy=mfsp!ersU)t%2n?3zpw3Sbno$u>;`0w`PlSS=aqn_MM@7|7?vNb;KqkSLS~- zCgERMlNVnO?H4-_7GDl5z8qM_3$XZds@$mh#4>)NTzomI!@e9?#zC-*gJ2m4!7`qL zWjqDTcnan|3c=iW#N4Np?~?nPn00`db%U67hM0AUn01Vpb&r^Jl9+Xsn01)=@8ym} zJ0-s)bmqvq7GdM@sR*$Ohd132?s+IHPkrg_EyJyCvT}Ehe7$AZ_O>jR=R;5aQEpIa zC+bK$!O~8!d@oqO7cAck7P)~%ZeWocSmX~D`GZCNVChG&^dngM5iI%u7JUGVK7d89 zz@k@R@r%IX7lCE2L3P+K0*juj^1r!DipsNemBtJCjreoT&ga}r4}9^m2<&ri#^p9; zvCp{~zx4FwRPJ+b#@BVcg4pNWw0~LDl-TFowD$$gh<(mY``pRq#6IVyt@6#)#6IVy zt@_io#6B0K#l1^-m(TNPao-Tw=Yq7jg9+?&gIe6#1orutE$$%#`~1rm_Yi@7{$-1M zh`_%deBI(6BCyZDY;g|}*ymrixQ7V5{Ekf)_Yi@7{$-1Mh`>BX5c~Yg4)@ET+~;3* zxL*eB^DjHxF9Y`ZmmThx0sH*R4)@D|eg0*K`(?mB|FXmVGGL#7+2MW}u+P8ja2E`5 z?&}=xkpcT$Tov-*yj&*xElrR^M^Xz zjRN-hLmlo$0sH)+4tJw~eg05)&4Gr*Jcbhc{C5ufUZ~^q-#P4ifqnivhkY-w&wuBz z?*;bx?;Q5Mz&`(-kA2H}zR!Q>u)j903fqgzWhy5h5&s*oPCkOU< z>m2svz&>}IL#zOJ_JS!6u>xS9yUih10PJ(OIm8NpeeO2zgViVYx!W9K1yJsDw>iWL zfPL;ZhgbnH`xwMNCznI40Lpz%E{9kFu+Pcm5Gw%oIk_BS1;9QhmqV-o*yrSOh!p_) zoLmmE0$`t$%OO?(j2Jq^3V?l%Du;L-u+OFC5U&IFxwIVOb-+HKltU~I*yodSh{XZ> zd{PdvIAEVo${`j9?DI)E#NvQ`J}HM-9I($PV4o+*VZRFO^8`8USAl(=palC>V4u?`!9E$- z=gmowdjstA`y|M>0rvTQ66E0k`y4k3@_&GRj++E|LBKx8O@e$OV4veAK^_s}HaQdI z7Xka6N(u6gfPGG-1o=q7KBrQGJSAZEQHgz7f_zIT_jMEGVFLSSB*@PM_Rmg!YLmtO zoeA>mpxn15LEas(Z)1XdJYe7U1bKSE{#z5|3Icl>B*=Wc_0{cEmki!Y=`zk?hC$R6s1Ua9;zHbxcf&#M-PwaIe z@j5~5btFOVG1T$8lOQJ<*y~h+TxDRdYYB3gfxQkU$ZZDpx|ty78QAM=f?Q}|uj2{w zv4OqrC&(cO_Bx&*Zyea`eu8{*VEZ{^$cG2^zr_T3 z^1%K#njn83*#CADp35$tV4g8YtPZ!;3)eFS@3l2ATK z&)&u)$P}^$oe3K~mwk<)u zlzSVQAXg~Z+s*_zM8V#sCde%c_O>=b&QY+p!3lDag1v1{kfRjrZFYj(rC@K%6XY}n zW6la63+!!wf*jIdKPDu|Ee-Z#MS`5uU_XW=$VCnIV@rY@)nGs7B*+=TH?nxVn5a;e#|5GV`JjSNMb)`CVuQB_G4+{$5diJ z#wLEOCH7-);>TcOKPD%BY$o<&b>hctVn2o_ek>>Uei8Obac_+CV}9bteq!$nB;F?= z_C7-5eFb9gJ0#wRAoe~*;(ZHZ?`tI9=OFezNaB4FV(*(I-bW$!zD$DL)p(cpaT4Uc z276y7LB4aa_i+;By$1VxP?Ihnw;=8jU!6=`b~&-XH#Pa;m-@v1KGmd9u1sQo&ua2m zj~vAQ{?+8Brt1Sd$KT_cTs-0xVt-$2Qfp=*V$5sDjV(6|b+|lM^@;g8#Qc1VI{aQ@ zZVxfHlbG92%->7QavU&JeTxA!fTo%=U_y?He)MJz}_G5|Jza?frmYDrpV)loL z*-s{B|CyNmYGU@ciP;Y)X8)X+{dQvZ=ZV?RCuaYjnCAt=JYOK@c?2=fFNk^GLCo_J zVxGSc^Sp+b=P$%OuOa4n5HZh>h%q-zVmE0AgMrAm()gVqQ-m=5+>QUVk9=J{|dX`0evL29@)A z1u?H<5c9eRF|UUZ^EwGJub&X}x(YF`w-EC>3^A|I5X;&=+QaKPRL<)>#Jv7P%qx}BzC_IHPQ<)UMa=70#Jo;L%L0!0_+j&w(W_h09|p_w{3`@1GOPbNutIJm0_9%6ol#thC3s z(@Hyi`>nJeJ}i7VybC@od^<3FUif@q`1|mO!0_wgCxPMD!+!$9uZLd+hF=eV3k<&= zei#^jJ^V8;{CfCpVEFa$=fJZ60)}4?{|^km9)2Mhem(p}F#LM>kzn}s@Grse>*05T z;n%|-1;ek0p9;p@1wI@Ya~Jq_V9a&k^MNtXgFghud=7pR81p&!PhiaF;8%e$pM$>z z#(WNb7#Q<8_-A0u=is-2F`t7!2j(?%V$A2@|Dhc7IrxQO%;(@Qf-#?i9|^{M4*n$= z^EvpPV9e*>kAg9ugP#hAsF*`_={kg$NTv_81s1emtf4} z;dg?)%}35QV$9>=r=py5+!JH10=^x}IoCWf=dC8j`VIUf)ZyIO#8|(9UxjkcwN1=9 zxQRJ8H!;?4;J2YZ=kg}zJq}{5-;n?3>u~OPD(9T?#GGrMm~+q*b8dQK&RI{)x$KEK z?=~^#<0j_(*TkGlmzeYR5_3LZV$SnR%=v$bv2F)H4ByE4f{8hgFfr#BCiXra#jT+} z=Sin>&Yw=qdDV%rZl`>_2>vDhmh)v3a~^GC&aX|(xqyi|M=-I({Np)t?h-6#C&6-d z5-evY!E$yIEN3Uda&{6dXD7k5UhCIw!MrC$EawYQj`dpjg-6xSz*wh;Uj@cGJ^U@O zoaqB&ogV%f80+-#+rU_-hd&4Ay*6U3)5HHmIo9dn7lN@)4}TFXXZpZ$rVlJ<`oMCg z4~%ts_^Dv*MZkvxV=n@}9Tlw}C$d#{LZaBrx`8;6H(}KLfuCjQtt-TVU+Z zzz+jse+K>;82dBu+rZeLfjJpzXW4{ z27V_P`!n!I!PuXHp9;nv6nr=^_MqU~fw5-=pAU@vI`~6iKQ>12lfc-QgZ~7^z8w52 zF!tr(Z-KEd2R{sqeL47NVC>7mZv$gr4*nci_B6rRmxKQY#=aco9?-NC8?JiPlcad7V zi`3d(q}J{twRRV&wYx~I-9@bimyxwQl*`&3>dV?4o+E2_cs{k$`*e6OvG?iF9%Ap) zp`FCseq#P!gYRNF5OZG>vkru)!*U~Lc@ndniCO-{+%Lr3U&P#x#N5Bc-0$>W)(2wN z6JpjMV%95S);D6-Lt@rXV%A$?)^mC<>pwC7#)BWAlt%(k7FZ9XyE zNn*C2#B5iI+1?Vf9VTY`Ow4whnC&^S#8lwh+5S^Gj|;>+UJ&y*Ld@d}F^@aMJRTAA zI7Q6k8ZnP|#5|@G^H?9DJv=@V^SDWMcswQMah90JUt%7YiFv#x=5d@@VovZb9`~u7 z{Q+Y36NuS=AZEXUnEef6_Ctu-KOts+hQ5XU9Aft6h}p*@X1|D-{Uu`dqlmFD3f~Ux zXTOV>{V`(p(}>xBBWAyjnEgFs_5+F8KO|H_QQ$UKPP6tomgU)AUF2&shs_PVxAWe^L&Ar=Mls_ zzaZv$2Qkk_hiBIbD$G0&%nd7eeg^Dknaml5-PjhN?g z#5}(v=6N46&j*Qlo=D8|M`E5=67zhMnCGFyJZ~lD`7ANd*@<~BPt5aQVxAWh^L&|@ z=h4JGzb58+H!;u0iFuw*%=33*p4Suee4m)t0f>2hfSA_}h`ZPH>2X;jKsgGoGJg#!I71F#r8N{TQlTD#*nnxm1v& zM{=nkcaP*!K~5jZr4p)KDxu1yg4{roOC?mfR6>$%*AVkQ4l(cV5c9qd zG4B&)@n7RzL*6H%a^628=KUsO-iIRQ{V8JJw<6~KEMng0BIf-sV%`@c=KV5a-bW+m z{WW6VcO&NgIAY$XBj)`(V&2yy=KVfm-XA39eM4g2A0*~|Lt@@%B*yv~<}K(i-j^ii z{Yqlq$0X+cO=8~nBHB|AgA=b+=e}nE}y`1A+Lly5Ds(9B>#k+IG0X!|&T(AC9QQ@c@nFOp_eIR{V8k3hM$B<##2jx%%yDSM9G^zaacjgJ&qmB~ zZp13ymG(t3??Rh7UXGaK=!iMKj+o=_h&djQnB(+_Iew3rPN)kyypMhS(3sybIrs{cz03z#KnG%yE^(9B)a? zahSv$pGnMdo5URFNzCz|#2n{I%<-SZh$G-N^U$wFOT25y@ugIU<4%cHylbf9T|*V` z8dm>nyerO0CA?-XUHB|AgA-~t6KDURM+eysrC+6=ZW;qb^_Y$)lh*@sL zEKg#VGcn7bnEQp8`-_<`oPRlIA+{xg-Uc-K(HyM`*>HDv#s>Z^Fyvv&yK z+f}@4sN!8i74I6Vc-K(HyM`*>HB|Agp^A46RlIA+^BQW8igyipUPI+P42V!iFw{i%=1}dp8pc_yqK8h%fvj7Cg%AyG0(e+c|K0e^K@br?;7&Fp2~T?Pt5B8 z#JoO0%kP!a{y>Z|jpO=4UdNzvUauhLbqr!&_aNr=5Mo{@A?EcHVqRAv z=Jgh0UWXy(^%-In?<(s#RL<)>#Jv7P%qx}BzC_IHPQ<)UMXcgoLtdw% za$diZIuh?1s(9B>#k+6ZoftdFrhC}Q59BIbQ7V&2ap=6x<=-v1)zeKBGc?~30(`G5Fc-e03S zyzfTL`*Fm)Pe;uAcf`D}N6hhOLmv5I$v&6jvrtR+gkYlwL~{86-l z_j!p`yeq~viFd^~NIoCxt9Vz8^%CzIs(4q7^%CzIs(4q7_2h@)IV#>2W4*+?VvUa0 zaZpFayJD=Dcvp<|w2p&1D&7@iJ+0%QT*bR$tfzGxl&g4GjPsHtAXf3N@bMz}ZK$K-UFEJ4Dp&EY@bMz7 z-=V&WcZH89@vb4(?XZ4_Ix5~3K3;_NJ8F+Vrw%_A%yA&ZD&7@-Zv>wYbyU17WER0s zLb-}}g^VNkRVY{SuIQ5pei+JCyes-Jg5QR674Hh)p6;JSxr%p%j!3*K)&L{;i>RaG zU9n~u!M{Ygig(2tV+4N`5u?NEnfpNLhwE7raw-W9(giFd_sOX6Me zo0E7~%;_TX!~8QHB|Agp^A46RlIAc;$1@(?}{}yiFd_XoW#3g zjZWfS&)(sK{!;O-Si_NcSFGVkyermlB;FNkI1=xQH5`d|#Tt&pyJ8JT;$1@(?;5Ij z*HFc~3LCUX#k*qdPU2m$RwnVTSVNO|SFEi`yero3B;FNkaT4!}H9CoRr8|z)+MUF^ zN_|xr%ocJ*09K?<#srp%2m9p_?c9$;$6ir zrE(STD*i2%vky-c{yDRIcJ(Wj;maJkKKL`4_Q@ zca`}Xm8*Eykmq+)uHs!~K1k&}Pb60Ht}?Hraux3?^H3^R@vfnYcMVm%YpCK~L!STA z-}1benCHvHJdY;k`86@myNOl2tIX4>T*bSFJg=v674I6Vc-K(HyM`*>HB|Agp^A46 zRlFp8@{&O^-WKg7H)M9k|&#Jr9~%e&(dhv|i!I%QGjQ{_5Mz3t9aF3bhlC?|Y89fV` zR}aoGTdE9*hYc!i`rJOle({lB6vwp$w^v54pFfHm%H%A8i+GzONGN$Ob zY38mMa|hQBC}OV3Jq2{$EF93_wEk{?3!Zg9$z2qd*Z#|o!h6F zuS*^Z8h4)>Y~MZEG#ZiJjL-K>FsR*R)Asy==7agwg1rYPnU{-}Fc*C=EA?fUNv7@v zWz3f)USB%l*NNuwCS^^oWNx}tkBMgLRi#bz`UUX~IVPH34-_-=3U-UH?mxj4S(?ub zzhr8BPN4~A*yhv0^Tk%j&%HX{+}U_vP-*j?cxkEeW@6qCg4e!35x+ThoOx*Dj9^HP zJhok?=X8(Ynzn`Qwkc!HE!pb@`}P;Nxz8JG;`5iMTHaUEem`rB$?@TlhCeMTZu{04 z*LTHRFC1kC zE_^3`z17Ni`@)gtmliwXl3OOmFE%wdZ8ke#%d}u;?N`kca}LB;KDj!070YinH58WzfAum$n)YW z=DH&bgGWX!4QBj0&^&r*Q!wwA5yAQ=2AWMfzYXgAc305-zyR~r@27%{`~`!#4-7D` zzLe7pUwv=t(e3@swfpm!c7wlLzVycaW_CtiGwQ`J(__~5GZ&T2Wr}B95tnGv&y4N< zd$8$1-?-M2zNXr32ZA*Z&xv=}>}zs$`8cR*KZxs0>0?F?dpoFHVQ*ZjR3CH6)2{}{ zl4J3x0WX`E-)|j^`!Sn+^Y`9nPt!cXMd#(T_de0vTyyXBsVUiW+SyqnbJw` z`2KeLgAQY!G{<*b6QAGg$Ds5ZUCa$*^TtEt<3Zv02{UosfOPB8CxUN3=xloQEqw7g z3yueMa(6b3Pqj&vn|Cyrc10&MGrcXfVg35oVNcput!PhOy)_MfbW;WUak*P#@S(3u z+DE@0Ph4(HKD%YcTH;2}AB#6Xf0+38ksIT6)ALx=ziRBX_?>|zh^x$Q8^2Pn0`Y^J zeo31$6^TE&uiNs=I%E(xoSIHmyP!1jjK`Y?^`9v~+^fvU;NYz%==pbzToq(*_X%y(Djpd4)-J|mpuWnJ^%)kEEEZq9ph5qUyo*(U6UFH z;6}HUF%vEtLj1vHh0MN(9dX@!r-N)o_Yof~wLNgp=P;)}O-Givn=>a{CJ zJbzKSz%I!ozWLlB_56KVoN-RK^sz_EQu*2?7sMlv6(;^L)i0iQ?K#BvW-g5{uh573 z;)POw2|k)XI|vIuVWvHj4kol;6V%(>#SDFXe6Z)Ook8tEPnqPz6Ty9-91iw0>uNHO zpC4Ry->KlmGtZbggXg5aD4or`x4gTlz5DV@-^x54)Oq4LlRP#%{bre;gXn@6%;3wa z#XTR~7o6DH!@QI{6+b_EQ*hrkJx$RGlj2>?76;E(eaWoY^-lbGu@S)ozrSP(N897v z@826t`mC23P~}K`UFTv!p9Q^5hkV&=_nyzEI=%d|`T3)qwqCtC%YSR#$9&r$x4min zU((%c^fm9c$Z2z4ZsKMq`kJw~o{k^u`f|MLgMQ|zj}FB-E`L3~Yh-_O@`2CeJA$?G z0BkTvw$Bg&(^+f#m?*mPPb34UVa^+{&s`So&nPu7C)Zfo~b{?%xoSzEf{w7=J=ylubNwnz8C!R&B8cUa=01!*xuliSBJ)@KO1glDpvW6bbJ4hMC1Z4Oq= z8EY~>_#}wt9}3z&G|n_yyCj%>IJ+rddAzx=>}$csCkmSR+sB*6>)HebFDhZ4967<* zPxA-oR4!v4Z#B{69dK`I+xcb9$O4nh*Ezpl{zb#m=DYVNnO9%fn=bokF>`sZ$!1FJ zrt#s=@|pJ06w|rDfcTB*Oc4A!#oWAaetc%zzTnYCQ_bl1o8nRB*9IdWpJq-rI27MI zc~)?1)#+y2qd9D|yuE@Z+oqcn#|qhw2QCQ?4w_-Q=PhmfmR*}V8qG96JyF5tYk5uT zj+ryfjjb|mj$3DtK5v{C2VeDCLHzLCNx{$)pAt{){X)>8);GkDc4-(4Y;iJv>a!tc z)$v}z4VSDU?r`3QU`Msbh>O0G&2%f&CXG7Zk1S{&&YL3uFMTkd@%fH}xWY-(;L6T% z!?zX$1&;h|etqPXxc-l?1br*~WO{d-9J^DkgK5Q&nr#Ob#&auI3_6ZJYC26?6*unt zVd|NCj+qbZY>7{1Yo2;{-!CTL$-Qx>;=RwydghV1z&1G{C4HH;tjX= zBYyhj_v6hyS`q)+ZEL)IdLiPWqxZ$vL_{k`uPFSm*%jMQn)^D?-=3rJa(e!f&f^0AkJy(5&@H?d{ov(G4EcHa zrcn;L>b8MZ|5Dqyf2nQUztlGF-&pl;tooPUh4=gS5##;-eZ+Xb?_c6h#dFM1AT-;wWMV*I}5lxP*qe{QR(cG2Qst9^<1wguCIpZkp= zzO>)qVAJ<=iJ$NASnyIeOMGo1qE!T~HQ+TGA&w2j&u{=Mx zwJ>qeZ*_1>zhP;VKXPC_=>r&j?aNbA?(5StQ6Jxqa>(4jix}_nZ6HP)eA|f8Hs5Aq zwAp_PF}}rrBQd^FwJlcVv8o@d=fvvyv3hS>wa43vv+|5p`(yQ8Wb62QQ7&>oeQKNk zUi5Xq-+P{tZCc4Zt@;A(r277Q(SBn8z4$I-|Gi{$sy!KVziduj{qwuhN5P}dd`PnO zYYV|ECpJ?#ey9JD`rS9YN6-AFQl9kOi)IktG5*DL_YGIl^M9$-FMZv_wp6~q{sLd; zJSx9q{F(I18`n2Nd){2~VYlKrW7KI;x?Ef%+CX)h zpYFfB^2(EG)cNGQA^vYKr8<`sdq1t}G}_em<`{K4PkqS$?e$cr`RTlA^{&*kCIhI> zw}VRRIw{rW)b2xLsm^0BT<`z(?7LFx+jSlPw`bcNC>iQ^1?t-a)fXw%X8*TmWf-V_ zOsQ}8e|xqs0;K~fB}4zWXZtizI+Id;;s5rmZlqK{`ub;eDW!BEP&)HB_UFIrx1)d8 z^4r81q09ekzxT6tl76T7?Kkk_%pYT;{%T9bu4aA9U(1zE`|q-`-riS|n4bLaL_s5NES@t>WTh98!_{RTsKl5+(?XTm4DyMJH^3#s|A^xO( zmzFKY2-a2V-#^k<{M&c^ReyZj;;c46ug>~N#Q)ts;s5zA9;0Wd^1qqO{1LvNewX?k z{U3JYtWN$Rb2QZ#vC;?6XMY!Q_a;9CULP#{z&%qA5S!;`ro+9viKqN}Zd~)0jl|uX zbd2lvT1q_Zys@$WN9@b|b2<|Hy0QNoV*iZTKMQj`>z@so&j9;(q8z?4mE#>?)WlBGgQB%E;FM{*TV}9`u5kOuMy{c zyH&iW)?ng0`)!EdD&LFvGE>@~uGx;b>A9C%|Bu+0S^wXNeO>GSCcrcOGpv6Wv46J3 zJ5cW5iSihXa=b(8;~ii;2k!vm`S=G$8U7m>b@2``o`Gk9@oc;UjQ&#PfvO*<=g>P) zAK#?jOYcCruS@R$LpG}YBs-Ktmg;*^U*v%27WV#{O@J{WGk87IfA4XIq&I z`*)%ozfCH~JHV)qcYyI6yaSBq;~yAh_-|m;#ovJO47>x3XX71U=$9%_srrF>PN1G2 zsP_h{J%MT`y#vpO%92$H(?G&U>mBl{c<@g{^S7Je7C3BA=~a=*Ixh>@(vb`+m*u13ahg9W`x^E4xv7qs`CR z;p>M}`F8^@r@lu074u%Q*N*)lh5Ff_yB_spl%u{cPfNLfK9%G7{y8zq@f_bCi~4Af ze=n8ey}tcaj`sU@TGU57{r6HizSn;jmE*g-OsE_(@p7PY$U&8-?)v=(Do1~+=LD*L zpx$fL^8?jRquOKCcNx`wqvT-J_tI~Y5sD8wIsocxW zsD4K~4a?0aJqeUP1WK1uN`J`aU|$BZf-M5W{=p7{VS8b_z_7`%X<*n<*flWhH*6pn zb{BRH40{Z_28Nx+JHRqVNIBji_3;ico`ZLQ@qGLPqYVEIjJkLS7|*~vz-T|-0hTd> z%V~_@`ZPv>(RTHGdI!pV8NCAx8K`#BJ5UapsqaF$d@t&Y9OxbL93?k;2g*@~cYx6z zC4U+tP>yF~i~!@Edc4q#Hg)ym3*><3fYEk59}KzS+rW?~-VKHf@NO_f;??JO}Rp<^NBN_0o^%FYe!e z|L(kQLpPxlkO_1aIst|*LnpwH*`N8l)A2$Tze&^YddTiGaotfviBIn@Xq$FxN}Ri0 zX`AcYHMCcLPW=q~@7RD@=Ks&w03VZKz8brq#-BPLR4~c@efGN5+tQQzlrrVRefImK z*T;`fE@&>E^0i$ze^^}jyKE+Zp090_`pe>>v-Sn$pZ?0;^~|=oTDT^dvHweZTjS&L zx~rxHn_GTqkKCNsUVne5pyT4bcJzJ4?YJAu1r5sWwO6z+XTPu5E48`T9=rUyOgsFO zrOV$ww%eZ0ThTUuXji(<1H0|-^D5XXvzy0@*6y-l)zWrH9B^Jk* zytdQkIw!l`pL`a-m~E%M{GxB;T)U6O&vn^h8`NGK&$>O2ZL;GF`}^?eak=TmY_ZF~ zusvSv8b5Hfterk{yM2E}CbJ0bpwLlC3Dygl|Hw154{!SP9KPWedROT;?$O4 zdWnzX%T9l4cRX`6xbpK^@r*}4wJ+VC+XN$Ch!=18#Fp4o)I3$=f;gkWCw69+vSvul zDd|z;w%B<)GtAA?PB*-_z!ux6az(S_o|UOi&;G^Exh})(J=HMyWbene#`R^)?=AZV zXPSL%XVfZUmaLc`ES$U9K3O%VnO5)P;N>!#?ZSqKf;{<-1jhz!vUeWc5RAAvmpOB6 zqwQMqjo{TXMa^w(Hrl~0dj*9L`Ph_qHrR$k>IL^s%rLK3+h8xL|7PkDuMZiCguKJmi%u9HQ~XUpJ$93{{uVanj&_} zp-Y4FT6|!q-CxFD*YKUx_(kvAOIl~x27PukTwCRRo2yDid)-ab($5TEV>f-0VJ}bB zh#nw^D;|xDm-;@g zHg%P4Fmg*g+vKpL3azrgbbBjq(Y3IB?a6oTwrdB(?KYRT3qN0JFT1L7T%$mSeY^2W z`>WZI&RedcEjE9JopJR;%gYqav=3EWVLxf{TB`k?viA0V@7T*WR|&fID`vm?KCxw9 zekQo&;ym`9R*Ai*z>J`2zhm*3*x9>AuMINp_$;1U+u4@Gz72k!{C2!)thJjj$Zl?2 zIVi4^&DyCG3z;{@HH)u&Ft+!mN}Kx|??`W5m$s>N1+(|c1ru< z8_R9~W|?Nu1LcEtC6?Q&ca}5e;m$$7Zp-Yu&5E1q?@kG7?ObXbT$tAke0@#Oq4`p~ z?3-VLF*)}K`IaxSUzOMvJXh=-^V|7LY~vM6g9R%JnpJ}q+maU!3r0*RWp*5S+dlEl zb-_dTS1<)yzir=$zE4&BHPh@~y~yr5^IfBAPiLCKmoBm$`aG6Cxv8AFXv#vH`^Vz( zv!{!jnzi=7ssTz{!&Kc%zf4YrmRj=jNzji+@)< z^zmT>C@g@^)oV!WD7zd*;|@hMkIwZQB!1*!a4g+hJFH&)nbRI*nhqmG`^2&awP<=S-h? z;`dSU#v4o8Qu$}w2OhsOE-~h2 zZtC>x^7fnMGi;$8IfD}Smb4uz&agASXcIh=yMUeEYq}j0j|$pv{XM?+z%)B-jthU9@2Q z{i(^e@1^CEQ0J6YP%#vYAVUeGwGcH{QN9^Q&M>u@gbn+s4}$ z53UL>FPYEmerKG$-N#(qdZf6yqv|-jY}2Db#s}q0i~eJ6ojxUk*PqBVZI6zzt+%&N z{pCca8T8;7d*hw^mUnohg6Z_}Xgj*Zf%Gr0mol>(jZ_Yk7xTVDiyFMeYJ$Pn*I33a`v~*eNy#%47Z~%&$P{^`Pi_-uiAM9E82V|zerEL z`&GMsMFnf}HH#a+H_WzdR@%Pv+@Sc@3x?U53kuo6_rD#_9WvD3)Hu6+^4!njb*F~d z>8rkt=e0f-Z|^X~-t_U>xMSr!cID@T?TgpVh@b3M%uWdh+sehd#WO!EYpYKkWLLL6 zH(pdA(-zG?$iCWjMEVPFD{g=875h=1yBb|pEW^J4-9Y6h)UyE060=cU2jJA2!C?aP>s1N#JnFYj$P-%-STmVbUwdv-7D z?#XHD4ci=SE#Axiu=-GNeUHPzb$wp4lU~~xG%1(Myl|wa{bb!6LC*t4%-6T}v~^1N z4(!G<=IWPT=re8!GXZ-@sz{Bf|Q zN>_V(?nChfXXXc^PCR9Y7tU#K8QC|;v*t;ASA`C&Yty;zxAkgQ4stFkX20HeuWfPk>7aG{JhtbUd+a+mP7k^l{y9GK z_}#Y5(GP-$k9`(zZF!g7knP)`&5euW0X6TmoxVTE+}3+=+~xQkHhYIcrc0x%;>jy+ zw-=QuZH5iqogO!+wQV)4f|>G+UEb;8+w8PF70pe@dZwDSxYZ78m1!0vWrML5Z?Vrl zUCy-K(lMy@?M=31r{X3@?kT}N3vaZSJ)GCvf6kg+wZ|X*hkJ2S+Hi^bNt5mPtx|T5zOl4%xV8P(z0*1FWoO^Im^b<^5W&9 zTBQ|RJ!lMdnP7xxI+?I7%A;w=?bQeiwb-N=j&w5mGUg`#fGw9slAUG}UR&@1hU^61TG)0f(CyjQ^mWe?yl*YgmOK+W>g10TO9s(^$=VdE zo`_4M2hwEY-`IIn5k~qBpw}venBDCU_I2q`BYYmB{E;@Ljp#=y4=!L%cT*ap)0d{I zEkt`yYwD2Ghth|tV|KipuHWfRv95!}-Y?{I>P#;>_PMjLA;FrSI`^cM`6>{0#FU!) z^&q$mZ8MST*-AZhqO7%6=2LT=|41VO?lVNC6~Wc!YK*I@6+}pHOUh z3E$4|MBZ<;ShoEN^z6`)?zoz;1NZeXtEN4zvbAQvch3@4QreM;ublO0(GsFV+mc;{ zoOvcT3bWkW(D*hsEJArY*iC9p{kxkn*KssiEoYOVxj>VpZnL7J8v~*6nK4TrVo7x?)sIXbjg z&zQztlELOS+GIY+iaI2F2%YLRspmjBjoETJ-XlkYj16t+dQz^~ElTPy&affXbtBQ| zKr6CZZBFyzPhj#GHLCikN7o~waHO>EU%gj_ypLsLj~Zo)m{y5(>GildLy21Lc#c0R z)JbE~KfKlII(kl$>hndvas1WY7>Je>we=^uYjnWBe`SFb^p0RJ2XDvw05>^9Ew8sC-3n2dKsID{lR~EE|#CLU;!ydU~NMditYyN z;;cImbUXuJ`m0GZ8|e^b{{~-Aseu9YHQ=f88eRIQL&QflRvz&Za}VBzZVwIE^HI<7 zM!xgLg-2Fl2!pq+h}rJ>l% z)|SSGUlOf4-oV6fGHR*oh@sCyaJ|3u?6`9;Zl4#7Rn|t-;p25&^ED8UUstE~17F~P z^OtdFpL)z_sYIQ{7p2y%EDTRlAq!(aO!*jz?Je{vI_w-;XCB8H-sWV@d~wlH2fSHf zL-TV^*~G1kPEHhO!b(m${GEnVakHPZ__-SiUHSXj}aAD&q5ZVMAW7?FyXJ8CW2 z21BlCkXGxX`0T<}m~^fYmp(a!t0q2!VW)C2*XtlQZLWYtDzW(Ls4M1#D>LKK-q-(aI@yFlac3NCwhC)~wAiXv?J=O~63WK> zgnwggF=^3bTv`7Ce!RBAtck_gx-Y?-F=m+h^)I?upM&0q4RQ4j9Wq=t2fVN8;JkaL zl(0?-e!f-5IeFH!u~QpiTptx2mLaDj!-t7C+<%FeBIGo(mnN3k*NL_pt?7O7B0TN= zSycIFLR~NWVSdI(G5wG>t(c#HanrKJ2fn}Y>%Br8H7!ltd!Z0ZZvDooQN?e6TVy{^y?7;#9T#Uctf3>n^ zt7HqrKeKb=>pbPG(n(cV@+CSxyIRfyHq{9^ny2F14zOW%tENJM@wE66Q_R@%tTW)> zRyBU)3|%&8a6Gu}bBcTAsl;rSyobvBX9kXaUJ7bjEil74dXVOj6xe)IlU>*8Xur5y z5OfGKW@RZ`?Gt{ihh|?ZcC^P8`@wI_!FHjXHOD=%pWAkikgsCPss~oukNEZ?{>3R9 zwzolDXt%XQOs|n@R$Z)x$1>?E)=!TOxZYFPxY`>XLX_FO%;Cb_HnBKzZUuaAJ41MM zD;Mi}KZC^b6~fXxjrd{bRiK!iLRz>6soQLW72ZdMBPB+ZG0YZ5JDw7ZWmdG<%u5Kn z=O^sxCZ`~WQ}L571Pgto^VN1smgpK6CU}?H(C#z`#PKo0We;--Z#a&vwGxCHeSKQ= zCla^ccqWXDSD}GlvM}S_8)11-CFYK)$D8-x2@|bf;MfRt$}uSs_9a|Lr*=lvE2Uca z-FGie4z#3V*CxU6c1KjIlhKsAf5J|iOJa#!s#$GO1EVFK?Kk$5QR+`k*s$S=5G=Ex z50CWV*>-@eQt6r#WDL_>-60`Wl?HFIfDIXUVb{`X6b)r?p=}1V{7S<^``Um{{&z6{ z8;XscIzr>^RxF^68>;>33K8=SnY&R>bbH@Rav@7*+b&Gp>)#K;qh&0t+F?*<3wvmk z?j4n@?+YU?4u*BEGG<}b4?Gq)Kwg*y^Za`l5@0kej5T1YS8hX*{saihQe!`-q(g1= z6qu1;1CLhMfJ2*^ke8JXWg%*8TFPA5KkyEmIc329U04Wrt{wrYfW_wQSO(9x_6OHZ zGB!(C4g0%@!dB_C!yc}K8LnP~JQAg6A=nJ-m);Zy_p@YcTDC#n{qDH$pdq`Ty&F9D z9>k3NR;=fp{V;k}C_bH33lna;f$R1(d~+=WUVJ(Xr>d*)+ajQP{mgk8D<7g^cqjuwcD8i8?SDN<%+@5I%emQ zTd<+m#dy2^a!P)98$QqU6!!GBqD_`}VReZNCaW7$^3i)R*)(n=XR-W@UCv^AtYn{{a4K>#itduh&7c=Qxdj=D3S+S*I>tMi) z7x4L!F?-}42yGsx!PP8H_9ikJ0_5pXxuXS6Pc4PZbKk<0kMALQmJ*8(%mnLK@!;E4 zm+e%^fmPdlz}e1>wQR|QE;J2_+uN|d@83huUX4Pp&(b_zmjcMl))YL>$l1=th0rBn zw#cllS^wBiQ2tjBtG1i4TWw0gZ~qEhld8q~ohpZg!X^Ci{3jHC{R~wxkMN#n0UYgK z1u^0$99~GUc;i=Tw)!tRygvtyZ@$5g5jxcHYc3obRtIJ$OsSWN3Ygz&fT2m&^!iCB z!Ru!eEPpAdOF{M`_W1#a;^Z{jT^%zH|AH|`t!df#h1j9y4@~N4O8W{f;JIE(tXrHm zVZ=kMTcpe$oBqL>GHDj{fC@|QUWCWG{Khsxs%&~?0uGy_O=jt8?6csHCWR*CrmoKZ z^k0IpPEtLJX|OY1TKFzhPJdQvvZo1-VtlTg+Pi5nlQ3&x;}>h1bW59Evid8irJGV_ zfe!1cKO3^H=+GfEJvMpoS+Jb*4|7KAvn5v%T%Q(Wjk5tey5j@%sCtaO+zr{1_dlSQ z?`1T}^F zcGA4$p4Q)l=cg@L#5fx^_r+wmlw!#=T+G-%<1?`0w-uXnRG0npii4nDHf&9*5?k`@ z9ZZ`pV-ZeepmwAg7HpEU@X{0r+pNht1=zB(vLI-;!2^k)ySN!z1@+`KQIQbuh3(I zOFFTHYbUX!NSRGE@4|3X40iim0bZ;t`=y_Y_p_hD?K$08V8=!*whMtVN4m4x?HaTo zd^<#74>nem)`z97!L7C@d!l4TcUGSgrnK(O_S;IwfXSiwMT7e=U8zp6z4cpBdx;%8 z*knUNJ%^)%PhXaE%bXtcIgUCn`mu~yw0tTr*AjC;dbm$+lFSWS(b${d)? z_AU&qk=E9FBU$>Pw@?!B3M0BWvenbR!{3-&_;~s#_H#=s7F6Me9X&>~R=o{bTy!ry zlQ@RG{B6OmYzr5Ue;dneuFIH9X5_%B2IJWbY3=W77A?g0p1_h%$XLKmJL#S_k-0s$ zU<2$AgYSh&EV0;t8GZ?a#I(swFlfbuh}ST+X$sr3>KlB^{|c*(rm zWQ;84vU2@v;-#sUOmECQ*4MNfhTSn_)Al>DF3tyVshK*{iR9Rlw`MJ2f4%j|Y~v7EdvYn;`^lVQ4!jg5 zB`#ybO=a}#@ErT4#mm`HYg<~Rc~1QBZv{K9CB6Igc007_wTgXsYf0Z{?LwWEtC@U@ z5jn2EhGQ=|vlMd;Ixo#uZG5(dZ5-Z!eeyr!*pjvEu|^K2k5wTnt@X@gWHi>^*Q4!& zH?WaTUf6nqG~LUJCur0ry* zrk2CV<@fR7_g(C-oidAhaSF$^-@`7x(`By=CZgs1z3lH@GiGzBQoQQz%HFNBVdE@H z;$O$?V(@tX4YD_q;NJg})E5r%6^!Fk1^l{SUIWmBuVMBLI^7yRl|% zEw)B08C25TSf5`la3-MyN}Ud|fjjacS(;fMQhkU8>=i+?S%;Y%J_{xwB(?rY6nZ#gDqUg%=) z026ju*PR`&ScV~gwAkoSclL7cMcg>?7Z?opV0W}1;jz{qAtc>{Id=Mle@;ArZc9Ab z%9=m;$p1Wew0N=!20FCsoD9#DP8|j6<+i@!9Lu!rl6HQg~`b$*sv5ing6pB z^QL;SHi^=6N0A!tD)VBUFI&^G$ocr|z)3cBf+-!cy?{wJ-fUErHifA^M7580g4Dw+MmP`6CdWKV=5>q*-(#pzRdB(PvJ?uDJ`h?W#?UHLRzK{ z4LWs}HJ~q~XaB?BozF4%1`#yomEZvJ99vPC4~}P(u+P}@?Ah!e@NP-~9xXi2Jo{*| z_+QRwxc35E+{%Q-h8m-}xgQ&!WyNfktr4qk`?1^|a;EH9ZI6OK8{I5t?b54+uWA0Q zexVKP)N2wvUUiWjJ#WUQO*;)YRW3>QP+hj7;64;wy2M_qE3>}6-a$#v%j|Jg8C?0> z1QQ-yW|b$Nzzso@8O#V^7Qt5_f1)v4UlYL8+iiwBi>=sQ&p_sGZ4Fz-$XS~`<4Dd^yp{Ky1u`{fPAzVsS<=50j7 zJlewGKi62VGD~tf5G;Iizs?5c{eSx<{!jWY`2XeZ&;K2^N?GCl?_S5kiFW!5_n&|5 zI5?g+SGfQ3b`DTqWutKa7}HE)m8mV`?k~RcwD<2QXWaeux1JO$4Xqe=|AE!E$TEx= zcYotY+pzk)2IKDEJLM{N-QEb?{eQST!`W+dfxG`S-wN!S7X#e=y&ovk6$@|R?*Dd- z9yz*<1@8WTf1A-ivtog}fBXd-syp(;p1Z$~nk}t(?<#WlPnjzxrF|C2-G7d!6$J)u zK<@tYy^U$=&LHIOuY5+6vfNUTyZ_OQW~@^yL+<__ZQtX;5G95CJ2%8()@oga``aEp zgG~#~6z)Iw;S}^6Vxw^XY?E5i@SB{t``^2!B(^>#C+_|~vla;@zpRM6f3B7xR5+Rt zcmIJqRzb&OTEyL-+Fyo@&Oed6Ke#`J9qAvCyMM{1Vt6FA`f~U0p!*L(s?Q>K|7(YI zn4QubN@tx*%X`yZ~7(+{CuK3 z?~XR3{VG1l-GB5LUHY*y9=ZEx?NK7vBkz&BzvqoojO@~a-2IzOQ*c*|ro#Pw{{&)j zsIkKRd;71)wim4w?jNzv9D^6jiMxNoiCtojvMq71-{pi2arciITq<~$n-O<^ zrvu|awTpCoOYZ;foHraft4!Se-;Ixjq5&1i-9PYkF3i+?hTQ%4rZvL430IN3za?p~ zI&?wq{@!1Wm}|Zqx%;1JXT^4pKOu7WpU_jzv{w7rbNAn4Y|GxWY=OH!E3#qhdyfF_ z{vij=*~<1OfV=+zRee_1ISRP@C*4wErwy`!yZ^$3N^o+n2k!pu>z_mR19gS_ul2bO zcY7Eq+<#5x9sc`?6(H)^}ql|I)KRorKutRRkxcjHx>>0ndw~TT3A8Y?qY%;ZA z-2L_60fxWRXWac~+;+#ksLHteul{ovGlo?IcmK6xGSD$Q4Y>R7`~4l4XM_TG|0J;$ znb#f!?*5Zj8B%n358&?qtgR(=opVdz?k|gz(c?c(aoqj0+SyWW-#C%Gf7~t^g}e4c z?*6VJ7L?WV2y*v75N1G2UfxFT{uiIB(dZrN$lc!%YtYcM2D$rRx|@!5k!lL}@1=7G zcU?44xc@qrBY4HnLgD^H4f-Qh-?2qM%?|E^#~Pu_pl`H z{`akWz~}9T#NFTO_Ce5l-HN#TtNVn)=N`4l-GA8SG|)Scf!zHa^s6Cwa0GJq-*H`) z9sKT&-2K^eeb!?gL+<`Jv@BTJvS%W9|J_|>EUkQCJa_*$GF$ezqrbr2Kl+D^`A2sE z?*2LvmMm=a9^mf(ff=y_)2;(||Hp6C*=F%MaQE-&R}aIyDuKKIfzjEpT*~L-?tgAo z6ol02Dcrw<^9d;0X0C95{l_C9`<;!#{l~4!5tbX-GVcBvniuTX+Q}Jr|Cg;*z+lX=Z-`UdzLtbkz?*7eMS25~WBXIX`e)SY{)$)M5{~*;0Eb)j1?*1?L zD^sWU-oV{I!Ca4a8jc6<{xja2QR%8OfxG{tBQ{hbX4rH0pQ2<-cL(kex%*FCE*V{} z8FKgU5n@IEwAUkd|Ne2t|&#E|Gec5;_*t!pCtEx;GiKcIwdFW{+s*G71o(b zZYa6`?dAG#XuSz>_rG1Z0>Vj)xci@6bqP|#ej;~&*Mdh-u(ANT`{#c61V3U4x%(%1 z{e{DK&LMaIQB!nS&x>=ByT8&|Q`YgWGIIAn@ywd_wd*Ky_t$$RXKwvL;O>7z${89} ztq$D%pB=DfrMDLXcmF;zQ>Lcl2i*N5!?YRYJp}Il%1yr^Ygi$0_jlGTf{oIA2Y3J7 zj}jn#xwgXn59s>C_|GN^_Yclo4AYlbE8IV#vlhG!lj^#X`%~AELbn{LZX>z>;h{2d zNSQU`?*F9Zuh{>oDdX;Mws|&QIjh6C`**u_7GK)`1MdE>Un1@bDF*KTM=pNAD!+-`{a-uUP-u@S$ld?QS~Ke5a0a>iuidRndH3UxyZ=5>i3+OTA$NZ@`!Xr3 zsu{Wa$395G$NMxD?%z`k!ny;-3irR!b0hXWXr*xfABL8wG)qq0{XKdg5S7(!iMzk| zr$_d?18s=A|D&oR!CK3lxch4rkAc5)^@zJaWS)e68Op@n|BrtR4HI zGvw}{KB^IpwhBS+{u2&suoaWGBX|Gh$wutMf!4^~e~N|`OS|>I(P&IsOKWS2j|(f5LKCIOSofaQ~TKIzd&1jB)o@4haz2wYFv4 z{p07D#J3$TW8D3_l_!Zm`&%&X{+0FuPSrGE-2GYkG3?r;%DDUY7G|HII? zIDY3V;O_6d^*b){yan9-vnAi{9Pb9){bK|}s+-aaxcfJ#TGH)XcLeVKmqTUL|69p@ z?*1dC?6M6-(IR*MHXbq>k#C3G{Rbvl(5cmjk-L9wt^pl3yN%raM<}&DBORJa1;;kwothLxO)R|<8m2s_x}<>;+wWo zonLbQ;{7pk4liWH-T%Y8YeLXCOXBX|dRI5-bk&f!`>%X<0KzoXiM#))_cvkR{aWPi zfBnZxXeZA^?*3H=t6<^x2;}a+XN@Ww66=B7{fA!EXJ533Aa{R~S-psl(lb9>%?*2~;jp^jS0Oao9>aQkU zwM$0s{-OCTxam^~a`#uBo{w)kDk$ld>jjSfrg=Y-t-k8Lz%uCr8; zyFWx)v(In3i`@NxK9TArzWoI5{<9uRy@;b)0eAoS^VY15$pYZ+?>NGg$tGR^?*927 zwOMkHhrr$c{*FKJDeR-vJDY?qmy00j$uHpUe_&lA81~jyxc{9O{&4ECiNgJNu3HMx zW33hLzxcH_?7S*x-2K_haf0s$IpgkM7-S}X`f1I$`|msZOH{8iW!(M!vS&($ufw?e z7k~D}%W?mJyT7h2qWQoQ;O>7w^#eAnO9JlxgLeGD{B{Ar-G9RnEvmTa4BY+e^-V~} z(HOY`d5qG{X5LFp%bSkA$NZhZ!^SmFNRk2m3u zl~xM(H@1{jwZg53QbCTOrFg*&jV)>`_wQ*YXU^uE?YaAFTH3PRey;`Y{y$V@>{RVg;O<|WWX={| z@&xYwAD8K~tx5NQyMJ{%RhE>U3EcfF-hY8UbLxP*e-ONc{PF4v_wTEE6Ru_(D%{_{ zejg;PvsAdh%gHXV;k}G;_dn8jMR1pT=(+p5nbpOeoGN47{abt!#TY4*k-PsMzd;x= z(13CG|Jddj2HHs;DY^gIv*Flh-dEu6AEfmbKUuy8?*5Gx-%xdU7;yIwAJvL}>^}tD z{d05;>3eN&;O?JSW3o<$@^g-_ap+y#? z6?_P}``flMr16Wxkh^~bYemQVzeeuk6v@2iq1K5S!4-2GP>RmPb~^&{^7v)zM*r>iW9yZ_ki zE@1oGkhuHX*zX4&2X*4^pV;muL=US&?*0L@U&2$&MDG5q{tHmZJ>>51*i)6o?)F6P z{(sl%vjt&8k-NWdsyTb2{#xYj|65(gRDIUPbNAmS9S`LPeFX0Q`X3Ecg!oiSq8g(1M*KgdCYHEl`-?*6B5Hh|^E&%oV(!2TTQZLOkk|LHHHLDxr5 z;r^d$ykMxExx)Q7{TT%hV{8=euccKWcuKW9?*3ZqBJKN(l{4=CZhH@lE=#Q#cmH93 zt?=3uW5(UTLVYtj4bf!W{g0i!g8mxKz}^4e!6$go{vB}lZ&h4|{VMMRcmE(2WtzR{ zG;sINjMk-h<0b)j|Bh$PsI6wTz}??}fep>-{MDYjf30+VX#D0Za`!*DQ@WOW86$W9 zpV?Nlv&b2_`x|STQ16ie$lbqNe=Vx^NJ8%Z!Ha*O-INmK?tiK>AE&(fhur<`l@OP` z(NVa6$unP^QfsPk|6ZqN;;FyZ3it1)`b)e~ASdqri}#s|D#3E%?mxL^yb$DQP2Bx6 z&2^v@O^CbyyvU{Sx1%<3_a9c}53Uivkh_1XMAsseZa z#o^YhWw#S>_cwMnWo2IHfxG_`V;#2g-~-_9uhjepcAI?!?*6^{e1f|pe*t&@*5;4E z=%?fXlKUU`xCq`CO%(25uCg3n_OVvDf5kRk$nlpm?*675rV96^nm>2{IAsG73~d;9 z{}#s<@r;2P_uX5i+ZI*hyjNCIff>sdX(l zrZ51w`%l--k^qKVsGv+%dsQ;r`7|Hds1TPTc+9vt!~R$$+@~PjtOuKP<(D zxcko^_g+{v$(*?Ruf5?2eWW!PcmEEPyx_}372@vSc2G3DF8z$${m1{whFdME$lZVX zpa!_V>l$+R|7EPf$~W&q?*4-}8nOCk?U1|wuXIax(BYiO-9J)O&ax9`*>m?_DXlXv zjeaR`_g`ZsW8J0?0q*{HO3Ybpjt6k}@9Lw^IvU&q?*82ut1>(LOyKT+!?_ByU)KV6 zf3e^t95qr`xW5tIgqT}~3itnU=m1=sY^iYnnSHv!^)wmd?yoiWns7rhLGJ!#ZV%%k zm&h1*|7eE?VyA5ujJtnw^8kFg!hmu2A3pymzFV)xxcdhc-oZI#UxB;7@!B`2g;EZQ zKTrrcY)Rbx`}ge(nLiAPyZ@|ESLm}xow)m-UwZ>QQ|pksf0yVN@MBIE zD%^jibnloQiQN5jzN@g$LyjYNe^;i@4vrg+-2E@#G-oH~z7@IqPj0kfzZwt4bN4Th zon|4OS|c>F_l#=xSbdJ6Z?jywrU2IdO)?{H}hBn8_j+`pGokq{~M3~={1 z4@|J{JVVa7`|t01P>kPe#kl+To@a^WyNnrk|N5;P(P^6|o zx%=nVN^?jPmxLJ82Vl|294S0qlMwcmK?S z1enpO5V`xOw=IIv^booGTkHOTDPJxicmJEw+AL?~LgeoMpq(ju6rzsY{pqkZyI>@U z-2H#wm$R}NodoXw`7h<{VUsd&_kWmd%{CUz1@8WSCr#OsSLcAc|K`y;?5e~q-2IDo zNak>$0J!`6Cw~IF$3KC)|C~pUAS*>n;r`~MFTp4m6NUSK^Sqj!6lahfxG|DH=1rtnhvB=%O z_cmo3*E$cm`|tTuj-qiBa`)dJ`4qe7X(-%Z`AabFSN$*dU-@|}hV_wp$t3p={U^gU z{p7^mU)|eN%#(W0xcdiA@VAf7u_5mM-nhhfZo+EevgAw(RW_KOA`|o+Qza-j{ z)%yC0-2JP5$yo2T%$~ddUa7u)wc(k--T!na8QUGjfV;n3&4LX#_5kkweIM(yUGpP= zyT9EfRo44r25|S+ZK{G}jsLO4oaQ_QiL*ei~LxuZ)^*9I)c9shFZ_4Nn zXA@+MyZ@<+H-!UIFCusUhYcQaCpJs>Ey?{Cev22U_*yXT{wcHjV~CFd^6Ov-qN5f5nox`xkq6gb^K$h`Ya;MGS-_&~K?mx!h1&~yG;O_q>rxNCCMIm?pUNI^xTloZX_m9)jXR|&_J@k_M zFFGdmmW5@B-2La2*suj1PRDci|0ns^@DC>h?*5~@%b9O`Tj1_rCbwcg|G5Bn|GDKx z%xT?K;O>7SQiG*+cm~}4*Tpu%`NhM4RM&SA8eEa`To;=T8{9oUd&VN&W{{PBt<2khdU3udXW27EljYi`6JOy@2 z?Ctpm8c}^)H0ad~rd=Ayb6GcRwWtD=u%43t?!o@fZ^3_JJ@rnyihUo)LRn!Q?Z`<+ z&z7@L;ZjG(sSvy9EdhVcIvUvAhzoxj!1sV!`emU?r?+ep%KFt(dv#4(I`(b+#uwjd zs=pSst0@!@Fa1t4?r6|)|B=}K$2YQCs6uo7J#p5VZ#4a#G;g-`F3P)oqX_!~TqM04 z#x1#q>YW~=vriQsU06fKDOa#-S7qwl@|8|6*@aUgwP=y=SIU%k#r4Ats7>#$lt1&f zI4ahNmcOhfb>(CIpVb(Wt#dV%%(^2ilk#6CwW_9|*WF;eceK3kX-3cb5j(3iPt%yGsO=v7os4sng}pZ!rhk5W3`6#MZ%G9>?B zwx{%+@Z8P++p<0XbASEkIY|G`z}@}Lv}^Wr$l4nTqH!}h@4N^7H%oPhn@yDa!v|zr zied85CK~Iq99|jM!-?!hTG-JBJSzWy_l8EAbvQsccl5Hze@@uNM!43mGL~iZ@vMqWuV=UcDWolKAe$H^=JU5{;FQWn3M%~z|GVpo z|NPrmxxN~-?sXF_xZ489_S~0dq?%~?-Ue8k-3xGWBbj7>hHdHF;bcq$R9LHAPiNlv!iJac;po~r3Upl$B{M2v!W-%O*1ZSp z>`)I*gKFtV*SA8behc)t_MHxQG7xgRwSbxBcWSdpMJ(A<52KHMBahSkGZGa!v*5Hm2ds=9}pJw4C;? ziNl*-iKq(RI}_Z#-vT1vI&B#Vn`Li-OT zw8Yp|OpItj=gCq}=Gl9Lys8?}G_jbbEIuo&aje14U5d&4j6NKG_6e&`exmMYr^2(e zH~6oihyrBppz)3H!_p#ZTY42{ybZyp*@fiXhCs8c2Ud?Lq&Bv1AfRA6whjA8tA~Ap z>K}$!VDOQ~SA2z!hT?I6j8sXvAzj3COAISZ73+x)aRq&esfz;nOLF=x{@ajoE z#dQA;eO`}*g6{dG5mXB8nHx;?c~8#!vf#z-0Eqtcj=W|)g01K7LzgY@D83*R4h&0! z=E6McRDKcy`+fxFv3WFl(_-*_S_NU@xio*2Er>o1aM~=F+z!VGQ+Bn0>_`snOTBG> z`a(0@YtE+qiA?W@S)^Mu5RbRYgUsGpWV3q*&b*WYrT&?; za*7}3B!@$5-AwZM8i^kd`9gwg1|4Fl=<{YBJTH4o*+1T6>uufPKdWJ*kE zg4O*}2jx6ZqG0J-F|gpA;0#G*T+j%!CmO)|kjFHmOAR!Qng+eJ9@C=0Pta|nJ51R8 zh^j8U0q7yUC$b=sHs2!{u$Z9Bv_#tL83GP7-hh2V0!8M!L%#DTSk^It+Vq$X_f>14 z?TLq!JJb-YUNnMn!vj)DyCAgOX#uwt4`}I|@3BA5WY=31jBRQ``>e zTz<3&9Fybd$fA!Zo{&RzmpHmnR)s^=qlLoL_i6C826TIO-Tv^uSeoP7g3oZMsOJ(( zF5b=fKKrxi^D%}TUe@BU^MlZ2R18h+P=OcP?L@2F(Im^x#jTh8keNl(^d%{HsCN{e zbdRE52g8xJrJ_+wBpDCzMVl`9sJ}Fl7Ij#M>n>Dc`qO*V{XsX>o>Y&uJ?~Ml-D^=M zYr$_9BPgn`mZ)djg75Sr$Yq+Q@Mn5Ge%yPP`aXUo%nz21%aU+PI@%3V2IOP%*l=1` zyB30vrXoe&AzfQvP#PJ9_U-Oa=k?)G8R>_o&)%l|$tlu%8+T&d-!MvfnhVxxgD`PL z7zJ2WK;EcIamdSCbSR}3_Ff()J{)+9#1qZ1!Sb5@$gogy+b8Xxb5TN#WhgC^>ggFX zdSf{Ki*G~arMuqeC*97kQH z=*+@6m)DKb`}TsRTGa*7LbnF)*#^@g4MVip{s}f6xk5qB)3A2g8@NyvL{}2sF=>l5 zUp+U725k$$V-6v3JS~vE1Q3oq<_<@MKyvhWgKm4K!L=&^)YIn^-aBjnE7b$&PwN_N zJNdk@a?@o>&TGWWz0(JME4)Ob?zZ6e{=3A%(=XBFq$aEjRzar+7l~TF;i!S5aB;hf zim z`_KzC#Ap%vs#Rm}Yv)NNLx%pb4cJ@vJbm|w6xqQRtlD#qvc3ex_c_{(YiiC?+xrf} z@|ar8pLdqdPW>X7C{;+ux-ZR{XfMsp=i-u1zEt^gCk*VEg1)DHXhnq|I1diTpDI4I zdP@}asPMs+E@vn&JQY-St;OjdPLspze2}YkL&FiLsU=?OF^)|Whuk_vHcRWF&R$)d zW`2r-+O@#w2|5Bh?oC@PT44Qn4+%rM!>C0kr8%lfxE-(#G*i6DT_Ycg z*7<@#PcPa$F%|M6!r?~13DQ-Lf>O^E_-t^3N>}>9;O1QTv->y=zP$q;4UwL|iahC? z*&rC5Ukk@Zdy@Xk3ZeLHv-IvU59%2_SU9q~1#Wlrpy?W6@n0@T^POki>6vki_$<8& zy8J#yd-QEFVAw}^v-B99Vv8|nN*d%oKPo-%oWw(+_aVssC|NxZ#rux~z~askIy3SS zCd_by0~SYUKadcz*}EoQ{hV?l)oQOWSEzpS^;5;Wu>Hw2ekBQibqtrRcz1 zsNI)Q@UJuzXKQYyt^E&y7?_A>3OCbp&p^=A4aJ8~H_?IFaiG=gCG|>fr1a7>P+qnW zeOxwBWvtW_WGRzuay>0*Ukw*@?umc&*U{Uj4Y2dKfBcQ=HT3gv3wTC43MVq1>Dk_9 z82GYE7!$Ud76sJ8bQJ-*?_5Pu`Q>1=eHTm|xsr-pa)I^pha8I)^sh1*21Z9g`tN0Q zq~#90FHeO{1xu-izYmN)k`Fy1meBr}Yhda7O1QRXF*Q%<3L4w%!Fb#vQW0JXf4a25 z>h=q1$}m+S!mtGdodwi?l)iYdTRl{jI?-A2jre(CCFn)ZqbrTwvFp3{(wy;JN*=c! zJD8-xlc{s)qUeiiiILE`?`&FEAC4(jez4zs7G`F763(8UAc(EaK3 zXlVs@pIR;i9iB#IwYB)|x**gzO{MaHW<1gq5#M3N6k4{u1(i?7idL;B)1+e!sFP}o z*)QJ-o7JgdArTx#;_I~ylVux zduiAw-)qFAxeoMt_C=w0=2zU@Z8%-qX9TU=eZum_p>*77286VvPG#&?+Rz#TVO{?7h0!()?V1!3?pB3CZ+H( zV*g{ckawjMC5-wi_KYis@C_ZwE?z+6k-6|*=s^0myYcSbWN_DSPc8fX@lebixK-bl zY8#@^WP%TvWwoJ4t)FA2?HY)=-kQ2amqQs0<)J+2M!fv0a-(hpXNF^$q3%XSM23ww{C zaTYg>F{g*`o?+3zyQtRHj4E6s@z%c-?5Sr;$6sB*mvi#a>|!bO_2Wacdx(lY>qMrly1hmW9h z_(5zdQzy5~ENHwq0&702kxx-6Tuc8awux1x@Y&yCL#GX5k>pIzzBYmOViSAwP0ExQ z+5%UyE(y+4lqf2=5&Z3q;k(0MJbeEvywaHo8F{~Ob4w9yjrM?=?LTm8aylHIa1G?$ zo3UFg!rplg0Dm^%ALpy!*Xb=>46nmAXO6)Py@T`a&Mk_$v1kd8~|e0-b}haKm5fo{8ZxNZ6?l&LNN;c*T= z)h)yY*R0{Alv&r%*S2!4^ermGp5MC;Oun7rTLw4-Q{|8UmuUQ!&Aj^16r`8?R`x2 z`x*aGr3LraM&n|^R9L56kA1F1;@!whq137pI}MLO>yk<9L=cg~@zKCXcl}+}pQr~9e`WBdWJYKkE>4!nf8sICmfrPkon6ae_ zZjM%v3 zao$15RWE~23GV1o?f{XSzQg=EM{)D)ze4vPP0&vHFuHbID}24t0tGJ*;rjPm~qN{e>ko_b>pd|d=FCtR@l!AvYXnGVCBZbVNtPqf{EFvD&w>ib^9 z3vI5#?l&v(?S%(;dDt=V9zPQEY9)=TT6Ms9+9YR?HEotIUe&m=orlbIzim2#6w4K%#&I zku1=4H42CdN>mU8B#Pvmy78!IYG3Dm-tk?t=F80U%$g6lmh04N`%u-ptD&1+|NUEq zy+Y)ut7<5`{kaSWShirkRR^^EOBXv@)?%yDQXF<|9`+0ShO!B_MQ@46TYsft(m_}3 z+(R2Xl)l24z7n*2J`J~W-Z;oK3Gb^QXCEBWZ2kJP^!BPTq^v@ZV$V=jk+b$})Q=+Yu^mhYj{+e4`S zs7f&J{uLUAkHL%eMMBi<3b2WNCzKq_626P`&YE6LlIYo~g1DLjJf7ZjlRbQ@G)W<=}mIfl&B1Mq;t13HnW*A{>#aHEF^eA7_OGtULXoX&zu z%O3oBCIQ0UR!gRKdx#2NVX)NVy<|$hFK)7T0=GS05;d(D)arN(w8t7q`s#efpHt_9 z+x3}})(PKnXzougX2{0~3zIsuoOFoWbGIh^h>{GqbsR5o=SFC^c*=2ls*5n&yHH!> zb~7#wP{ZN+vveY_S7Z5!jad2dj*hQ*t+~lYQ%w2sOlQsJ6ug%0iIz?&IzO}!dt^k4 z&u4>9?=Mf#;^9X;65W-PR2yN`<7^Qs+)6timaNHK;#!8kd#b6^k@lF#Go+?#35$ z;hA_|cFx_znJt|baq>D^!{An42Hu3dIdxc%#mp^W7wY{BSdDukxIG8kGc3J+|UUt1xcRzI>QC zWdM%WiQ>9DS3zQ*XF`t`@!X6q%`j`Rp~NHlBWG$UhY;5_T-5z+E@*=cqF>Z=Avxc; zw7K;#Jd1~Y7puAWr6r&w&TUtz$+)t>3^3axUXM6a0W^NT26rJ8v|W|peW@QLzJCw( z8l7R{Zc9+%zd~AecPQ(32yAy&fR?{196dT3xY$M*eYPL`Sp1f2KVJ??9S1{dXpN3` zlX#vS8VWTN2MSS{4N%*D6kPSq5LS!7dv!|Cgo){s@Q8XgbaS2r*7B2BI3W)9ubU1x zYHd(0JP7W*7kzAnK!mbKFp-}Hrh#wKZp%3sUp)_kO26P0qv`PRr7mo$D@9>n0k_Fy zITSB%Ku=*JXFhf{+!W_<=7h&deD1A>6Z^!j;f_>@AFvs=&S}E){=;zB*X?j|S|zUW z+>6SAdtmF{T-4k45Z@j@2y-9-kB@wY&l`?{=7BK0a5e@TH=hDwr4vp&`WXd<^S~Xr ziL!OyabogiSbt+4E`1{YjCHyJA^ZLo41371&q&dHowi@dahK!U&Ej=+Ia)f-=bCY& zgAp{WbmQE1Rbx?$F(@AC4OUkRu;1=`5UaikJcp;?mDl&-q?ai~$pnOM4o(Y} z^a88mPvXxGSGecw1FFYg!L>&cFin02YoB|8YD*F_zQe0v|x%0>>i#W@+J(91dxmdoHxm;|;tt`~ZZt%sz}QYf0# zD1?qE0o&6r!Q6ZnI*Qj)=VwO2#^`H!F#0v@o%kAZo=Z$Fogra{hO9*y< z2MgMNK)0g@VVlBxIC1zZCIpWH>mv!UwT!@;HU(_GH1K+AIv4Ws7;z9O&No z4(~1uL`7LHc$^Eurt-HqXG#IsIzGaK{j%_uX_5Fj?JPb~E5mQ~#o(Jf4d3o=Kt;V$ z*k6_>#K+4p$*UZqUyT!NcgpcqW+fDPCF%S#z6qae)QIy9FF8xqN*rTQ2et=?L)gq* zyj0NuC)VwQ{p}M_V_7rofA$dgkzp7p{*LP2k!PTw=!7a!tq>Uy1KBV2akkn|nC$c! z%;M*w>eb)y>GF3NThS``oL1m-ggQvk+9T*Ww&O1jWY>=`(77Mho_BJS!?T1ZoN|UD z-@LCGd`I+w3Z)MGt_9U_HDwc+a2@$AYs71+Wv1YMRGH7NN(O}^PhsQ3PW%ap01MW= z1UK)_ys-EQsK`G;PI4Fi*)k(=4J?8Y?Yi;T99KYQVGW$0*`0UW*9BJaE$~=uEX>5~ zU(Sf0&Cy)=gTDd z_*~i#^2D#_KVlg&68odPm`c$ zuFj9^S&z93XJdSf27mqccf5A^I__y6%1>IEfj#Aq@wdis-uljK+&t?A4i#q*gq?oq z3?IaGuSW7}u@>lO`xU)RNAc5N9>8?h3S9hZG_Te=5>J*l;>OxB{G*kxg|REd&m(G@ zd|pbCWbk(x&Yv)j|2ljqcTIdRZ@GRvFL%r0##oeLq0t0BYrz!Ijn2Z!IFawP`ZNp? z-l1;kB>t1BEoe*)!Y4{o`2FHqte;ms!gIr>@(V}46W7~6i!)b=*K;n;f~bDe@RZ?n zK3=N~ejLvgYF^CX4K6l7UF;aa_v=i)DpdxFc4<1jo3(hmEppJ)f5pK79bSJx6S!%N zfF8>^-ngLx_9^U#Fn!=_I^}|1>qDsV=lPQ#K7d)kGf+&K#p`@~0hJXo@TqJzKSAOM z-I6~;54E}cn!fsA>hc|o7tiCLs?CL^pXy-X)%m>PX*suOlngvQ7w|t|C&#(SA?(#c zzVhxW$=D6eurGfRzipX^&^odj_Ngr9XXo|7-=hjZap4kP<(3{cgeOC%^Go@rCHGMA ziU1Gnm+}3Bo?_uIHz*8R&TCt|L<89!Sp4NLe&~cx__0j9_P@(YK0C7rE4({H#hg`q z-oWqaD>e|9?w|*^k=MNO37gH_aQU81d}Q5A%;_Uw;1xYSUEK?9_a*8mqhbjNvWZ(5&ycIAJ%h(mEU52Z`@LfA8Th_Phb!OJC!1&3*j1 zg^r*!&=3DwxSzMa@d9?Aw?NhX2l%gNKY&Y*1E^trkdJ%)6&B4Ki7|19_*u~vkenJV zp!_hu_NO?9nfFyPcF0lw_F6ey7&3x0oOz7b%awus;2iGf_T&68`v&OrV+!ngc!J+? zq6~}@cfzEjC;5xp@?icTBXD1Eioen46D0V1!z`6Ey!&ARoQ}VR$*E`ghsPYDASf3m z+&|C1Y&`?J(`%tX_aZ+;HVWqL{u^%obBXtT;LGKR>n6RCT;V6=&({hX@*5_exyHXd z>MaEJYlhilZ}1Q1jmBI1ze8)TK5y{yJYKg;f!)h)@jabfFi-adTpeM+N9Dc3%w9II z_m=^$GCLbPzS{*Z8HT*+usU3Ex)&G)+~!YoR*+t~b)7qP=MLYTpd_6U%%4xFM#cF)xZT!-|FJg{w?I6a z?lt98Vx{=q`5VSgzQ=3ZJ7RWlD<1oGkDoUD6b|dqLAo}M(+E-6=F zm-`lcs)IXNEKS9PHJ1Fwo^PO~G#I(wR=n-eLP)oKh`%$ec(0B>AgOXaMmkvYQqPY3 zo)krl*lxoQKiQqPy}CeX)v)EWm-OPFZtB6Af3xLJ3{>Us-mB%ddOzY%@nF zcWrxq;7~_?cYkY0KGTi&&vxYJeAo)zrmOMiY@K-N=PuB0Xg~hg8fU(f=`Jp7RDa&K zs|#POR4mES?#q|IbKxy-6bk*1^y23my7F!l7GiBiXa4wXH~w^2Q+zi29{{-d{`&QY6l)aD$uIY({IQJZtr z<{Y&-M{Ukgn{(9W9JM(|ZO&1fbJXS>wK+%sUpPl>zMl2|;(yW8P=Qy`f6C8{4@b{i z-FeF@Pd;s!DO%j`%NuR>r;bU)Ir`&***>S~n{4R%f5^UPr|>#S2ToG|!EnBuj+vXWqc8&2D^g?`oKH zhTQ{A{1GxJuEPH{9Ecf8OmfE;VuDdxUr9t!6&KcHNzLi`3t6 zy;m$=vvlOQ&G`-*sRbC`$B}pL6bIIotr+O=m_Ly03FeB*(t|_9Z9!jL!(K(2<>tU| zXg?Xgm#9iRj&$I0l!RNoySKE`%br(!U#Hy|qAIMl+9v*Sy0HPH4* zM`_wbJHBDlDQwb}?-YHVJ|p^So3*Ddq}%)Qr1zKX3Z}>&{L{# zQ{ebuE8b+7igaDhBp5QqiZ>QINgs*pr1%9`^4vZJscD)!Q8;+Y@9{^fQ^YmQZ6NW?Jw7G33?}~E4p%Bn`ES4ehQVFB zfuFd>h^2uNZxy?XJCbd}FE3H%4?ZZDgs(N>y$5&VAKfex?Bk93>AgGfs)HAx+FWDa z;mR*askn>d!|w8_-?Ojl+pC=4A`h<*AP@iQ-2LetA8 zd}Mluzw=HH9@i^K1ApD-3l=KF^pQ%^U1x6d%XY2g+}bNiy^9U`%|AK{;SLJYyLyKF z-W!#|qpC*y_1=KbJhT`OEib^Xvkds4NE6h&{|L!E_p zFi_(r|Kwsm?mofeYXyDY)Tkag^E6>x;dOp?pI>Nmpic53_ZpuUsvs@8I*_YxyviT! zryy18`I!?sU*)H7_<{YdOn}iESNP?9>#&4B26JXy=1+tc;-n-i=(y|>-z@q<(9G90B_4}G7V{_8L?liA|S7k=K02xf|c$%N{_f~Ge^9EW2=c$mz{b{}|9})u0 zD=D(_hjzo0fO#d=&i7&YxgzpPI(w~zOCM^-4rerhc_kKUY5a&A;|;WuRDl|1OP zh~vby$eCB-H_cJ9I<|?tlG|H?gg!&6$SavRXE3(&7p-d1EBR!!18uVs$t&5S`~Y_? ziy*IL$3Pzpx#~h*$#lOc)E{9;UdfT#G~EAIm%I|sX~meRtw>(U^5R*lhUdand z3x3@f8Ns}g8R8o43)O7}=9O$HZbnIs3No)`pH>a_sa}K3D`^fX#DluV$h?vrA*ndE zlLs=d8B7E$(i@XxsrFrn6YzTQJ!!jzN@J*<|ypo%a zP0*a`BVk_2=BsiTHhVV5ypoRAGC1GAjALGjM@Btp^4h?>l090bke753m{+1#oe3u| z*aP!QGH<*Q*WnHU=9P4G_lMz|`4D9ZflUFjf|9EIx&`4g% ztJ-8PslS}O5~si}+^S*XxgmNbHt8LO4m%pjD^XEQ5{8D9lUIV8<1k}I4tXWB9FO8; z_jvM32FR?iVP6P&B@37PV^O9(c_k~RzQGN?m&hx*9*~Kn#^{h&qOV+vGZia1=9Q=l z^*DCme2#e~{fuQeVAvB0^GeR%6s?bpV1aohJwuwXMK&0jSEBp750?aF!^CL=JlQSHcSE6{q2bNkT0`p2l5}_{3~R0= zucTno5U73LL|%!*k`Qi{zMQ<0VMXpb8KyGwO3v!c6EdUf$twZtazRVAl)RGF_1c&f znfb3*a_JJrEqFs-$;lXdT)oquypl_6LU6c>HF+f~E#q-!@=@|irp?X4F}uf+SEA)p zjvJY|7MNEOJ5Y{mZzc=OE2&!Ah_Qv^ka;EdEy~ei z$uVSJ$uspF{ISRynOD;7NIWW<`y=y8Iu8%QeaGJ*^GYhr>`^H{lf052|6Ih-@ulRI zbULGr#m0UC_6V_SC$Se7zK1VRVCMT~XqldSSpPTreNAyZYZ3yL7=U0+f;u|~! z%s1wdSJJ0=C!9H!NM6ZDuLpqQX9MPyXnFZSY>6{@B_l^g!=@VswvbnHG31I+Qdvu0iMoO! zj-69XUWvAaE?)VaMqWu{7ek!?GK##C?ENm-YqAe{CA+mEuu)w!oJ6l=!}~<^5O$DP zGT1E-)h~$a2a8_GPqix4{Sd@4uLNE-p;M!i4)aPh3`NUq`a*$uCAV(Lu&jHfz`T<0 zKJ~cSTL+m}Qd(VthC?qS^Gf*pnYg~Y12V6~MfnY`wF*Jzm0TU@k2^lZBlAk8L|fs~ z6FKCSyd8EFgWs2vSJK@_6Z;-(B(G$OEJ64*N={zMkVqw=cW*g)C0u+rE?`C@c_oH_ zr*LT}%gHMVaTpKV>$1r!iEKOu$&=&BD~YzUhOPy{oBk6@+CPO`1pcjUdhmh zO`v;B9hg@#GrAHKtakzPO58Q`;84p0U|z|L8HvzR=>yCw(KQJN*`8=%UWvPtGejAu z1M^CTjWd8UuVV5_cKa@b!YShSAkiyvZr=`$er+MIWS83+PFpn9m{(%q(M~d3(o9}S zk)4BZsj!;7k`Y6DVTD#9c_m-lt;YpwspOS-awcf0CMB=rSH1`C{p?O&Nz&g^tm|q_ zUWr9!DyE%ULtaT~N+EtaszP4L@Z~kQq?ZlHyproR&3HA&Pn&rq&Ek8EYXR2<=9LT$ zYQZCsipabY^-r~^v}iFhuVh@mVyxO>h|DXwk&uQ#0WQeAl5w}9(EefsGOwgvxi>CU zNJ8e73{1I?{t0>Hm2B*?14E}(kyo-rItX{BG?7WvSn^7SY;geNjOXN)^i2eS#cjzV5*>uVh|# zIk;c?$T6>E*--I5YbOBnN}5-QYY@902j-R3#AL&X0&8Gi$@!Kz(CiZc%qx*Q2g8D* zH^97-XN`6cI`<2CCGVbJfRJ;gy>d7k!w))O(ahH)-vT3Xix9FUlyb`Dh zk(|2GL|%!*s&Jvjt&+Tw#E}|k^DCFUlDG4BWA@Jk@=A(z%~84}oV*f;slIq{oilkQ z!7kDGIpY?2B}*|Khc+)DuVimhF%DR)Kwim^<#l+-^CZW-66LZM47$)=!n_hkUpY$p zI10=wnd{q(!*Y5d^GfpGRO6J;^~k)E72OLl@16-VujE&53WkpHMCO%vi`4fLh(zX< zjDFybOS^qU=9MhLyZB9BNM1?7%hlNRpy+0aUdfHX?il~GnY@y1)>cAUkobK=^h(~0 zw24UbXd$oU*0Y=36iF?4C7zd+piA91@=Ahbi(#*Q8hItjL5A@6f++Gzj>=si-QAnK z5+OVS#@@V7UP)i=B>1*jnJR*mG9?D!qeEt)1LuVkpz zFP$YF<>Zwtk5m<+x;Bzm643ZbXdG8gUWsn!iMY!;o4gX|zfR!q$T;#!6eihV>b79= zN*-X3m{($^COR+^XL8Id8RaL# z{9K8Ic_o!6<@h=wLSSBr!?7luou`4!E3q=D!~=D^k$EKtKIY;wTXSSy$-cMZI^36h zk$EKpmBVpePBb#FM5U86hE$~^^GeR$zJ)?#F?l7g=Pke)`|8LmQBnIxxY5``Udef% zV?vI%cy5SZiS5z>I)ffJlUHJF?Zj#LRFhZI?U5>&eJl9aE7`vR9DP#AD{1%D1iWpL zypk2CJRxb3J9#C(mm}fs;k)FO6wUhx30+r{S0Wu&1bv#ikynypPy@&MSPIN5sqNAN zN7b%GFs~#+bYK>(H{h68vd69kQf71j=9Q?s)WTf9CBVFrck$oALGd;)uVn0jH0ZRz z6_{5N(jf}ov_t^&O73m$Sdi( z?l~v9FDI|0S<_6%b)Ss9lD|f;5GL)bC$D7tjap&EtrGG|KEwk)Y0V(7gd21f?`(`E zuViT9VV|NrX>d_-W)?-$>NC>m}3yfF|TBz zS0f&GmFY0AL{~?SSHk-U%q!9SM}|J9(go&~sK^?yEP5g`uOz8cIj)tRK<1SM?$5?6 z*KCk^B`0skVTNM>GOxsDKrlw=y+!7gC~ULCBG)hEl~im#kHe&;eHqPCy&a>D@jgzrQ@`viM*2Br2^M^ujpTkUWuLEP*8iCOI}I7%N|I5 zkU(CEZLvA*e-}nxiE*SaJbvj!UP)HJ82B;y7I`JV)IY=G`}4^wsUGkh5*>aC%qtmn zy$B;|Jt%o#jNhj}F}Pvx+tmkY}gN^G{Qf|JfQ z2`%q+F$&b#@@vi@SWM0WWV@q5&@+)~IH%=bH$*U^J zD+zu#8f^sebCKwkEbH)27(PclA4IRD`FXvhL?#*&qE`|V)SuHS60IlED>1M9%o&!H zkymo|@+8QcnN42FSND_fdRZKKC12ugU}0tuc_j+@0br9@!+ujJ~ICdghh z447B4Z9yf>Sh*LNSK@X#7viQr1m=|t+mrww+dTv3mDm}D!IBLzz`T;K=bXgfNqh$8 zm3)!hgkN*NlUL%GIS=Y>>c}fOKJ+K|qqB^>5|^L@T(yVzxmEN^yz8b&_FZcxuSD&k zt1#_kHF+gIU3;VZ!vgY3w!PbkH)f}hSMvLYDemfrGw=%Yp}LGq0pVbYPaRz9TTNq>FwF zwmk2M%quZIQj0%&Ekov&q+j`lRX(?oc_mwZf5Q57S7ctvmwT_!_M!xtSK^xDg$3D3 z$h?wQ=4R-4IiI|e;J>!wfag`@mGnvLj~7*&$t&rk=PRgM%gHP8an+Z2td@~iVl-qO zC!1bRUP=0y25x~?33(-7r_X}Lb{XWAOgnx}T-W_Ic_muLkHO-tA9*F4vqPay$CA8~ zt|jkbSm{*duQ2ZU2-yn{8CHi$T z*mEe8V_wOuqy{LOJQdOsaX&ym<+EZuSB`aaO}1sm%NgFfA7VO>IvkP6c|3lutj0ymHe~# z8SWnIL|%!LMGQXdb(6f38Mi-U!|-|Jm6RX&j`dzYIOdf+@~^{}FZOcGD{0q9hN*97 zNtjm>{X~u_-JS@{D@i`qjGN!}M&^|$t*yopmo_2uO0FI#z^r6bWM0W@T7i6e4S6LOV!GhX87<_Mm^j`S zR*G%`^GX7{WQLD9(?VX!$|NIBX>~1mC3T0DVa&R3@yb`^ zmGJ6r@XN%DyprwV5;!`?jJ%RLy^_J-aSM4Rh93El-oHP2C4E0s!R0J(fq5ml!<)hE z-B}6qN;*H1!;AqNIp&p|(3L@XWh2MDk`aUJfh(T{%qtn(OPpireI1xrQg$E%u6%k7 z%qzL&{u)9Dy#VHwbTaURbLt;}c_sTQETHGjujG}~s2v2WhZW?NoZUDIYV#Y(D{1Z; z%N<`PC$Hpn{CA!DG8uU#_D|J?L6QdYN``*>BHVmZMqY_d>152#%p$MkYU?TNpYe{o zk|q0WasRp?@=99w2cph}N92`gD8IwfEoaFqnK?NNwa-l>uY?;_h9TqfIOdi39BaT$ z^EEl1dNG041<$GMI;EbKEfuVm0seGD=CPF~62lXJ1(yE^hp zwoGgl3N>Wpl@v>M38!4;zCbkITI&>kglUJf%b5KW>myuUe-Fvg3sZ>v1$+rW|!l%lAy^<>~v+?+h z4Dw3!Bd?>|!Pn%KxD9c{y|ettE0J%1fiE2`$SaB7^Z`#CJn*kq^870XI*lZ+q+3u0 z&UhHZF|VY!p%J@e=Ib!8Bzu({N4pIZm{&5VP=*ORvjygrq`5cXd6y~3yplNmGQ973 z8ktw(5nOBn0BMA4*e}~K~IX?CgN_S?FS28#746a&QMqbI> z$f>x-pn<%S*@0h$x^x+NB^HZE3tjZ&Y!c_sUj??7c`5qTx2 zAN~c$6spK8=}z zvvkL(L10q;3(QY6OE=zj<^q?r<71SYrKeOCN9Imd;6FZUk}jz76M9UNLGQ6mQq#TT zu)|K#cg99(?C+~M6- zv7<&>^u`S}HQPzY$g8CmyD#JF;Lg&W*45IqA)0u6UJvQe$<@-F4Ss@dSTE_mgeqyr zc6VpQ)%29AAFh&q+xVQ@ThdLsvO|^VO^<`+$sMGByH`q2t-cQ3qh&a4ex-EMZBLl< zED!(5uaHjhiUY0WXgqndLdv}?ffj!kG|;G!ez>E+D-1u2J)_H|&-!-dJ9rJl^4;aq z^^K~0Jwp3cNS&3h?{w+)@D3Q*O5PkK3EFnN&CcV7rJ+#fsx6RA9 z&C9pV%eT$Tx6RA9&C9pV%eT$Tx6RA9&C73u1`2a{C6H7+*@;N6u=4t&x+!=6RnzZia)`leAfXy)kf;C zP2xWYd~rGT*EjoUVvc1F_1EX^k6@529$0_f&(I2e-h}|`ua6Z!M~`LVwfbUzefdi) zcK5yvtiQf+AQK1caKQTOiqsMu#aD5xzczhTkBhB!Io4mxFU!!Hx0kT~T19MG(jEs2 ztiLWyXu|o0gQ&kgHK7W}P1-^I_50U(cs&0;_1E2+6LEvgoBHc(MmMr&ag;_e_1DWa7UO};TI#RsZ57cqL~L@!{(86SbsaY7+s=)2ILh7%_+pK}O#8hPcwew(OP_C6C>#v6uyTkgA9?1IZ!$YOe zNz(*be?3$^6`XU|A?vRX%`Jqg)}F}v>*b}@khjc1VEy${X*0Y$`#Xa5*T!Poba~cU zj`i0avs*wzvmN!3t(&2-jGxgW^H%7x*+i>cyCAmIu zb8aH_*P}}wfXlQz>aQ1{+6C6{DyhHTrmGHuRTK5s2De{ut1ru`zrGRgr(D7oX6)L##}auGK;z5&)>A6RXV8L|Gr`fHQwV9YbL z2G(C2^6_YudJI^9{kb(8HO`L*)?ed=a?J2g;aGp2rqhTICUoOie|@2k9Hn|41lC_0 zjg(`_qC|o9*NTT4(LYI(`s>`+<*2B8l=|y}eL1L+YDN8Z_^Wu_Jl3E3>%2Q57_KI^ z_F{jX_RAh8Jj$g0y5ZL)+}K<~{k5i{4%++IQ-5t1T_GGZlu>`3Ww$`sY9Ocn`irKE zP8c>(e?7T>Fc;jtiu&u`j)P&UT^{w#s-E*TRmzR|M8yN4;u+L(}86S%3XR z{9d7zYs<0zS~a&BHm&GE{q_2>HPE8Fmip_RE`>1eq%rl^m3FBB6U4P$a-*cDgQPHX zmz4VJYo;DBe|;+T*TI>_kaM_@`s<++)QK}b2yqkdH}4yj<_hkmZNt9>#y(Z%tOI!2(bRz>w6{6=@`nf{(6>Y6B=Ya z)nWa$-gP;~;T(bW*XPV-nEkm-VEy&{gnFF&NSpfWH6u&WZulkYuLpn5#Iug})L*aL z{RRyuhfse#>6SlA&&N}Ltvb^h2aV04{(9%gV|dK2ocinWk>jw-%0}w1pG-{_1`n1~ ze;qQdv(Q~#Y{*ptrRUam;(o1br2cwZOcJ;4iFjUq^OwFh8V7G?=1_lqto|rGF^Wgl zUw2ct28D$o$olIs$Nix^*dAGbowMqVxYo)gWc~GM;6ya(Q$?*Xj8u5gy(!n?-6`s+m|sc3L@EwKK2qE#UV-R>c- zRpBiCr6G22s~&NzzmEOVj82nNv{`?x8z9FEGcF6Pzh3pa1sk5Ur~XaT6qRB&nvrPN>RtMb=->-;@JGl*S?J zujP_**cz57u>N|`oaSni zEC)a5W7J<8E9XGLF>C6tPp^oFFM!3psJ|{gU=Ooonbcp;^1CQ@HsbY! z1*X#4KH9K2r=I$2m4s5R$VNu}^~5K$xI0(m)L*YtekQ4~Yoh)-PW6Qlmr_an^;H#h zbe@|>{q;kB7iO$Z1lC`>CO<$!pKxIP^?>(27#`yctiQHg7>%#i8vyICPo7N2^NNdr z_1DhU#hA6b9kBj-=EyqSp?;2I{k3^U3))?fMX>%_?kC5VFZKfKuLGi*(fM^x>aW9U zt8ujNI_j^V|5b>;dzw&xoi#BP`$u|EfBkcs6ivQLslUF^>W-Q(Q>nj>oMDVRq=nR9 z$HcEejafC+Utf$@!KJ0m)L+j^wGmE=?=gh%i_&uz5fNN?3-#BRr(EMY=GRhxt-DhZ z{Kpkje?7cH7ycl!4m{`%v)Cb;y|LBjg$AL1Gf zozC^Ju02Qnbx2ML^ty1F`s;#onZQqXp#J)w@>tLc4Wa(}j{G@fm&8+lJ;A{W7T?LC z{#rlb2<*u&r~X>@mnJA*Xr%tSJ(s}!8Y`#%di7jIF0iMZ`s*3GD#ERCjnrS;2&qEZ zj&ka+-I~XvW>z-!*Rjiv<4Co5VEy%D!5WpKf`Rqd#~S_d%>a8~{dM}AH|XB(BC!72 zdW^Vo$}TNn{dM%7QXIdggk$~n_xgIQeadmHzb;hmO13G1)-UXWuui!g!p*DLQf zVb^$d>aQOMRpOzFUDRK@s^y`kx;gdN_xdMdf{HKo*NTV3QSVkX_17ksoKg8n`oI0P zf&pq`G4%l{wf~>z@wATbQnh;rk{Z-KumIS*a>#w^HiUf^scaini zb@i!`*LMxF{`yF<_}-wq3bOus(B>Lgx6WE%{k3;#zUu zZ2^;kO4MIZcv}m3&WowPc2O*b-NuI0UpEG)fkm1N_1BN~M1kL<2%n*KQ%(L194^_1Ein4uYc0ChD(emv17DD6t+3tiOKxcRAWezUNqfooLdC@wy5e>#t`{7N3*3y#&@@$9IH1wXW|>+|fzwgs=9LPW@agyz!Dze;xBoOBj4cPW`oFNtll5 z`6lYGCwGtFmRVL(e{F1_0S2YH)L##9*bT!A6Oi@Sk58Dxi80~G`s>{rd|~!PXJq|# zhnLYX#{U+w{@Nfd9hx66K-OPd6%>PK%0B|@ul+aG!HLl)1lC{2RkuKwU1~b4zmD>e zgIl^I$NKA#C(YoXqe}ht?eJbimY>(lZAI2&q0{q>sI6uAADC-v9k!Vs=)iKPDe z*I{?CAN`T~>m!zTVSV=^>aVl+uZD(mHPl}xtnCg3iY?S%?@zbnHi(^Y$#t`IamCP^;(00d z*D)CpI7;t6u>Sh|x+EN|xE)x3{jOU+ZucArtiRUZU4`#@`g5$mPA+T0kfG)}tiSGJ zCdWHI%LUe7-#skDNzpX|>#vJX)??!dp#Iv(sssz(U7`MZq-rKQd~l%tdf~ZPw9^Wu z{(A4}=V-S1J@wZGKP|B;KZpA3c4rUco52Zk>#x`Qmcr1j-vriQ2dOu})4=Hh>#uJF z${^{pREPD~!N=vW_MU`e{k7}fCa8v?)L(x(QwiQn_E3L4Pnru2k>=E2JNqU;hJ!El z*RM;$z@aso`s>UhC&=mWnfhyC%Pq+4_?`M|lal!me5#K6>(iTlbK_fEsK35G?kHF7 zC8z#+?KBO^b*pCTuTQLV7D61VslUG3sERJh1=L?xMQ*_S2Pwe%Yf~jtRKJM8`fC+y zPqZ8A4y?caXcvi2bMK11=N=rf?IXSjSp}@W9;j7>+a7fT)?a%(tiiLJEI8I*H}z^k z=PP@(S%2M2>@js!4F%R;53p>(e5(%BUw5>u#a5-I)L-`t`-ZX!x2eCr^;a4u9dxDs zx`BE+o`TJiQ;s`s@3D%fMygXO8vPK2;46Ja`iI*Ux2TFnHxj>aUlt%!Uc>Hq>7` z9*l!iF9WE*J}D0Zr3-JVzkV~r4zeP?P=B4Jcpgd;OR2w}G;0Rr&S;?iTAo+P^_0k{ zzjk~vg&TfYPW^S^+Zc((nkMS64=SUey{?k_YrbhH=9%YGf34E82Y;SP0M=hm?e-8A zyuyI>*HiL+ag)6hu>M+2D+aYX-U8NN_tp7~Kc~(I)?c?y_>Mz!e{!t9wlJwf%Sneg z)?Xh{lHsGo#763`eLV}%WTPqd*K0PX z;I(W|>aTxjA@<0Kr2e}1mnUfP@FVrtl4>K2+F3;X^$CSlIK{7q`s=Lhu2`heLjCoP zFXqBC@x1JuyNNSfIxXVlofhh^ms#BAq!(+cziwF75nLX8qyAb?vK0FFPeayUyWPAE z_P(!>_1E)*T%owZ3t4~dyGa81;bzGC>!(pk@YG`~vi^F|zI>QCWdO4Ny1R1~B=&hG zu>N{Rmu8r?*igdyYg0=(gt)HZSbrU~K?cz;>N(b5r_HU0;aNQO*YQhBK&k&V>aWWJ zGr(-mW9qLpe!d2GA(Z;-_oaT2`2Ich*AsVJf(rkY`s=cOhro7c1@+fQkB$Z|wvqbl zAB*2|?dQv>zfKLU(a~-a&yzz#p=RPhAu6+h`s=H{8NzDucdt$fnlLea5*|^{rvBPm zei92O!~yHCZ`9hLT6hq!{`#ImAVS$AVEwge;9IoYat>I39aQ=SuNX}S)?aU`D@9>n z0mu65;^htKDNN*8e|=MIlIDcRNmze+<}`YTlby%>-9J0;nF8{ z)L)0}`&%&VA-4P@4Zwfeej&$QPW|=B94#H^bIsIWH>`By+;&w{f30|=H&|UQp#C~m zeG_;NPeImSpY$??D4Bq)zfK(X6wW_!u(fcL5bTmTNU+2Ys1f^9gk@eT}jEg{5 zqbsuh`q4XatzFY z{<{6aZ!rDSZR)SBia&`zJ6x&1Rz3a-u04`af4%m(m$)`v67|=12hBjuJfHgO(8et= zSXxE>wd_KF2pHH*{q=l%AI{1~PW`n~=w+P;%VpGGZ*yEP^cq`F{dLi#Mj>=W3H8_J z=CjaIKLc2Qy)pV49*lkstiR5A{utMI_yOy$JN+Gs{=F=L_16p9e?YgR2Z8n1Ck}tb zgy2!Y`s*b(D{%FPSdR7AhcX&5BBo4-_1E5u#r5dM4iQ*?9a$yAg`>U*tiKL=-GCNm zlc~Q>3Ms=Pk5klNAF9p5uvxa$Uw3bOhj$kSQh)7nE(n{--%@{V>-Y!{_RFIFdP3k? ze4_ef%@zHWqCq;yo~zm=vU(e+nsXiuZz5rbp9FNME&*Ab}u;2Cj0zWbgS$}=+$TLt-6xUW3`|HSn7|4F9kF39* z?DQGT;^!jkuRmS>4r41?1=e5Z2z8L6wMSt6^~HfQcowukhxOM^ZgO~*@PuRib@RSv z@Ey^I`s-Z_s^MzNChD)ZtSNxmGE?fWv#XLp;mA|!uTMw>Sg`IT_1D7UC!iw#Nd5J* zWk%o{SVaBxHOCc@Sy)5;wcEZfu!3)){@U!T8FxlJFMHkU!EY+`*782uLjCos`*(#G z^J}TUE`6tr3+H^J{yJ1$T$4HI6R`d|aO534H|Z6y{`&I*H+*uy3s`@xogqQ(zGlGs z>%9|_(PiNlVEuKOBp;tk`vL2(J7!g(|3Gh!_1B8yn{jUTaUIrQU$m2B54%kQ>#rBh zlVQ0}lfe4xaXsrXcj0X6udo09j@J%fr~Z1<$_(r&e@y+g^_|zadDaW+uZ5j{=nNmI zzgCO2KtJ2B)L&13c>vR0E2zI#YaNLv%Nwb`ezfwnFm{Fbc|=W<&r2zi4E`>o{`%|i zq1-k92I{ZnZdu$Ii!$o3vldJN-RLapuREA&Jwf2}{D3EVVBP=9UQPyzcC_EUdd(ee%NxFbjA_{k6`w7f@Ld zL;dvxi6eAN{!IP#n!fsA>hf=Y{Zwr(Ed5kR{k7p~Ik#w(jQZ;zu#@9lut+Cgw~PO|Mu5;een0F0_v|-Zs}n|crvj5x@pNhRJ#zFoIV2e z*XinBXuCI=`s=8-_t5EEKK0iJtT$s~OBMCkE86wLsl51mv}xPucQ7tV|WWUH0wL{*D9^E!F`bU{!{F)FN*7+doO*BtiK+&&=Hgd z`XTGDt#7=5-RCWk_19m|egKyq2axsGaj(C^qIn~c_1CkaD#uLG71uQ#GJ<3MwO+0a><8y?tiK*+-vFI{OridI$B8m9O592P^~G&@;5ofKjLpw_ zh_Cf3$zzUfmp*TXeBA-m=iYOuf+0ut&~|i4E}T-mJz~%9N}RT+4t&Km2LIhYP21wX zc}`n&TD*_qh<~^1;Qa$5PIjS#u>RLqs9)3x9(UX=#8=0I-T0+oVtGqAdo3I`C>p?h z)6>G&xToUpP@UnVkG5c_V+;4zN5FjjB+0_#ciGp+|Jv7|$MEOA*nJelKkOK^g94E4 zSAN(Grq-Jw+wbkmt`PaR9~Km=G=WRu>HQDmO)>{@CyTb_{I)|98*D|9MXSkDT-W>+z2I=Ebq&h!#Iz^xZm=Zclty z2<%*Ex3gmpJN=lp6;&j_{<7QIZQ{Qn+y3u-UHtjF6Zgf&(Ua{<{7d^{`xo~|x3gmt zkC|>~$1FY;fgKNfEPoyw+y3J@rE~cI?dwR~9~}eRzqmg-2DX2895 zg*)$X`f(514jmeVU9+TgpU5OzWaInqasKzc9_fMq=du5BF5w^NnD{f`f1P{yU*pBb zkBuW6Pd2XX*w{9^FWdg(`Tc+Vn*H^?A3-e67JokG`O!T1NXz0EiYg9aMX_B_6?^!NY4 z-hBr})kF=02MK~G8OdPI0TVKPRS*>g5e$eqARr@uM?qn_j{y@#j3_}2 zAPNRVG6vjxdF*%jb8Ek?t=+2csiK}!ho0`9zH?{p9qIF%ws$aIHf||le+FYVN7&yD z#%x={J_d1pvV9P?ufdq@n{adC^6Z#g9&<65=fxUbIi@E-}A1>x{-0!%U zYs-zn#atg;UtG-f&5gmuT#b|=c{HRw8qyClqZVkAxxtLoUZfq{*){GmQi@CLA*EEfb zxi#j-pm}Z#+MXMOi@AQdF}RrPpZnorF30_ji@CPk7+lQt!HvPiT;JRnT+F?8hU5p2 zk}jT#nap5ZJZ=`R+)8dR zZu>6J*S#z|7;h^3%9mRsH5mKq8{pE#;)C(e`##trQ(!PI4=%u|mwpV6mDpH`IctoY zKWB}-tS`h|%>EyJo)tP6^X9YP|39@Dj7_2&(A`qy!PwvHD_W5h$LHEVPGf7av-dk( zd|=)R;M&!KgzGae%Lb3p6CI4@FDv0w#$tnU^8O&c(XQcx@mO(19Z4IZ!Fc|KV&0B> z?7zpbkJU+^ZR4u2jhs%n{i&J*kF8Md?KE|s$=l; z*U|U^W`71hm)RWKPvT&nZA;k44CdKB2;0}-^)1^s_r5xw8;e^{ZVWEw^4u6)%(dsn z;I1pUez-BXJl8+>!{xag_d71nwdEee<+(oo8^bM~>zf;c9q$7ByYXC}YtPMPNP9G- zAH?;~wc(!Aka5wF`7qoV+*oWM%#isHo~PVnxwYiR;M%Zba_#9lFx>iZZP+mxZVWDF z$K=KxjJX{5J1)<)<;LJ*t`Dv+F6R1XuaPhpbJtz}E7#}TvEb&(-S2bPbzGn9b>07+ zdyv87&dq1Yb=UvWHQUhZ!2gwNRPH%(|8dv({|{c1)Ah&yEB7G(`+Da8f7dhIwGDSI z`s17z^UU%(`(7Y4e%FTm%-+ClZ0*VM6E;pTVCHVQ!{^!zeP10K4>_0r_j@dRZgTH` z|6hBL{l9X2NBOxjPF=b9OZ*@H<<{eav85-*dvez@&u@;#ckvorcy#k%evyp=(J)>z znBQ}~5?k8L8q7PsUQRL^#th~w+$71xqg{yW^Xor8n9Fnhu=62Y zdu~4LxPy6aTz3A0d2asfJPFsHnSkUUTA zv-x12J$KTF^n-@9M?=PChV+ky%##^1A7;q&VusA08L|${kmt*==V#i#bz_FC57(Zq zGnc39$@M>&XV;DEhps;}UAaJw z%S0v@sBzh(kPFnfH2amjl$eT$`Q))VMTq$pLCyhHuXSYFt`q=KwV>pGf5Z zH7>n$)VOr0y#Um>^uKfgsBt+t^a4=h^3s6|K#fZsg9|{7%a@uLfEt&@ zKhuF4m%*>nff|=fOVWWFm-+$eK#j}1z3D)W%S^p=pvL7IwRE7yrB;6$P~%emMH*1! z@^XF}P~%eDD-Eb|dBq|PUi~vJO_s2a{byV{sH6ckE=#*off|<+s#1X(mtQkeff|=n z+){xWm*aP*0yQpem{g#~13|8kZ4A6M-6+L8gg7jmsy~5`h|*vBHT!jmr^l5`Y?)tI89A8kaWV z2|$g@KZg^58kb(H6M!0*;u8~q8kboE@j#7B@7j2v#^wIY@j#7B`OtWv#-;3mc%a6m z?>jZ3kbIH1Pmr;BkwjZ07eIH1O**xoo;@z1yn(~ARYTuxJu z18Q8Z>W>9#TzWi@1!`P&=fwgwF0XmU0yQoL_rwAsN)VORr8wJ$3JhCwg zsBt+kI|`_A89g!zsBw9*B@(D{`Rzs|P~&n(d?Zlga>|KFpvL9Fb&)`g%YCyVff|=- z;*mg&%l%CeK#j|KhyZF_sz*ftH7@lXB7ho~&rKtM8kd`=MF2G}YlR|!8kc7p!hsr> zyUN3X8kfr>!hsr>Er-K_8kbE*;XsYcH50;t8keR6VL**b!MZS@#^u|~VL**ben=Ql zzN45)Egw>%7}acQd=2GqC|`5g+>xKyhN1!`QHUkn9mT;BEz1!`P|TC;8b8JD$s zp+Jqx7wVxvjmuH}AwZ4GXU{@_8kfuRLVy~VUY;R9jmx4vAwZ4GCAuL%jmrw<5cnVC zvNIT{arxn4Fi_+2L1r*eT)vPD0%}}3dE-s0Ij9T+z0?_T;|0E05vWi>+(cXhr% zjmsaGeSsR6lS6#j&*J}#%gFt{K#fc5<-S0T%Zr-6K#j}1-#$Q%%XhDQfEt%+#Xdld zOL;#ZpvL8PYagJ-rT0gQZlt}RaYFs*<@c?RE-ZAq4YFzefc>pyo&yDf`YFz&M(8&KoYX_y;(-}j$!snFmG)VKt`D^TO|PJ}B^9Ty_C!Tsj2105vW@+PVO(r8#H03sB?IW{e9^XkE4_%UI(wtL8LN<1!}TG*II*T<kQ| z0W~fwRZamlF0-pn0yQqrxts)QTt+N73DmgM_;v!Qaaoyh0;qAhbNdOPwKM~zP5?D7 z6K)&_YFxfNc^s&5Idjf&pvL8b)?+}8%g}^lK#j|TYmWgnE=LO=18Q7WVh5ncCI6TM zP~%c!x&u(-((BDppvL9FkfT72%aI00ff|>d14n=wm*>ik05vY{4jch$Tv}-!0cu=c zdUhD7ahd9U7^rc1R{tYacR2S9;k6?D{l|fxa@my2&i$H=y3?B zajC@|0%~0DY&!_lxU^3>2-LXDGd~E_xD=B<2-LV7arXdFXc08ry{@$3UYjmy?X zJD|p8a*Q2N<1%!E9Z=)4LEH|gak=TrexSys?&1AFjm!5F_5(F8_cYi7t)*!eX$#c2 zT(sI2sBt-eU>{K9(z|#cP~-B9%|4*UrPE{|L71!`OlQ`rmDxSaLK8mMu()Y%%Sap|_e8mMvE)Mf?LxO|gg1=P5l zzs(A$aVaTj#eU!QpK%ElmOzcm)2A$f8khU$S^_mLi(2*oH7=*b?*VFDN}KKhYFu6x z+5^)TZ4B4H7?f~>;`IF&Jx%S)VS0y+Xd9P zRJGd$)VTbiz6+>vDf4V6P~$S+XD3kO(sZ9#Ijmr{`?Ldu75wsnsarx%!HlW63Q1UjQ#^w4=+khIE`ZC*q8kcUBTY(yv zeP^};H7?)J+zQmV^l#h()VNfM+XB?M{JUWbP~-Bg*cPD1Wi{Ch)VQ2szZs};Id$S@ zpvL9!x0`?(mkN=afEt%y4L1QbE-QYU12rz2i_C!wy}V7e}s#um6loi;8tXjmz%S>wp@U)pOSYH7<)jtp!?3 z^Fr)epvL9jHETikpK&QDycVc&`TmM2P~)=om?==>5~i2}H7-NzO@JDgILHL3acQyA z1gLS@FJJ=HxIA@v4N&7U$#xA;;d%G>TXO)VMsnY6Vc^()-tPpvL9vqUAu1 zOVjH;+`cYa&~)VQ1N!omw%#W05vXmt(gJT zxO^)*1E_JCe|0)gF__bG$&36YFxV2P6KLO?hBp<)VN${G!3Y6=^!u-sBu|W zG8H)E(qY7RbZ_re5Hk`-r%ij1pXyWyO7h`lvwt_K|6&SkI=5j#n|Tis2$%w<_q_T3 z%HL7t(kW2-P7GTPYeHpRlVSYy)tIq-hE%gA!{TIjT=Vn_TDWsEoGnVmmcK3_O{K|j zVF4eXPVhw|9#4Warz*@ao6%#}NzmH&mfbf$8f7e)1j!=bu(SeE zGEydjPh1}^lHSIjwrwJWX!YV7Z+rNm(i1`aYdenLuml(1oB-B$nz5yo6MlSR0z4V^ z66f!W!`d?@K<2a?cuHa^#?9j)u{Q^|2j0i73FG09aWFQleT~Vw@o=Zy3h#OH8HWmw zhZjxbafwJ5-c&vgtYokACz$oIHK4{pSaWT;O>HmhUyg(Ou@iXK0Udb7+p%C#SI_&h ztp(?Vj)jPgbCB8TS{%D#EF3pIf`;w6gDrlJfi-_3(7Z>5SfgYNoc>&h-0LH7wcQx- zIeP~k6h4BZ$BcoofwgF+$Qr6Ms69@PY|!4FnCCcjGe}C1Qkf?bj&6J{XnURfm-) z?xPn9xyZ#?9eiC%k-!SpqekjLR>q+OrI*O+yBg%HIHB5?&B!HH4HSfzpp2e&l(JC` zs@XTQxeI#HNC`DCs@THY9ovV(Z>hos!`PZDn=UGXaa|*J?r_Hy){0;>`x!pcpNv1LD#GuuD|qs8 zK7Lv~8upi7z}Y2LxY&O*yf*g5w&UO7!+N9Pk?$rvYy3C7s#5`?S{1O?hHmVgsQ{6? z)A(|UeR$h01+dUHE&npH7uP5$fYZpGyj#!Pv38X_cx>t8Jx^}N>s;g^MNAjTKdr_N z^W{Npuwinm7=Ir)`r1k;?n1Z-f=zE+q%^L>o}! zwDEY}4Os|l|BO5%uJZpJmxUclU1)dL^YYFavapKXW9t?%nOFN!2KGPgMU5L9c%S2C z;MvIz6hCqMDBKyV5@zDUzPG1E!C8S7vCmeyXe+z3*7EQ4BUc8;ddjsfC$`K^A3s3R=}T&L?BY{8~WIo z!q>7E0ReUozP#qVhfCe58 z1K}N(C`tMYdU1Xj)E*g!-c9Rb_v;RW7^N$`RXh7o#%Dn|DpaMj>RvDMP8Wpr!PEH4 zdpc0iRzXm>6gW!& zqU?*X&C&?8vFb1J`hEwS6xbuO@GtTGT8sISvr$OG0J&Jyf_E>f;T;hkAT|{p_=dSU zui@|?V!+mFP_S+(=YRN32G|-76H0FK&DZ~C{W7+;ZN@}=lmCk>bNP(rcJIZH#&elqND3BC#J>vDfTIb0lzW6!?C=GA>9^!{0VWb8-m z&h(M!m_;~o(hvMJrI$3X=;XH<_Ts9Mz2w!s4gBljefZD$9u8Axg%311WK zBD(z$v`#Ep0EPyBA|DBwl#Tx5!5@=_48_~PlhNdiAgXU~&BbR*|(X~hqqj$nI+we_DpFdvxKeqcT?NZ&(Ic9 zZv2aHu(26U=>J4E9M!{14pyV%yFL+#ZRhcr6BWqu{zo#?FdnB&$w3zve zL8vFMnbc}Oz@H2DAYFxKlD?|}^UKGgFK0dwPpvOFDUR@>8k@+H#a;Nm>|LGWwM}F^ zTjOQE-%P&!twthP(TmfJ-|=m=8VNG)z+2AD!^%=Uw_HJ+1ZO1e|=3hZdc)NTiS=!cfTgnHnr(k-|EC^kLtd4-0At>=m30~$3ypW%T~p3(}bQ6}3liMgBT32)2HU{uKM6CCSf8&y7bY zwk-o$Nj@k3Tgy@1g{w%z^%>!pCZQhr=SZ^cDamwqL)v~#h;R0kEWNo3jXC}uW#T8q zYO5&9bn8KfCOjcNnQpw2i)`K6$j4-}?d&rCm>y&{{4rTl5y*d?*M?FLR}uTi5_q9S zBXW58h=g{p!Pi5dB8$b32()w;c~mT8gcYRT87wY>g>FXMCmZ4w=AI%3!3$#0MNp1ycs$^?wJ^qBZ%2p8RIrGs? zT!RfyT_;Zc4k-N8ZLHjQji_lwA&-gz{CmSSV%=4Q-e-j4zqhUuCCf_Wzv&QOG3zQh zVpNA-Po9P4!>^Et?iO@qc{P9dFCdm*I?!JWMSg+}5LLET*m=V)9hZ7S!q^&O`}6Mb z+E)=GSKNup6epvVMVMUI{fy3I8}vtktuHP88dYU;embAzhTlWKC+DHUwsJDTu>@(% zzlru)u=S-?Vv*9Dm*~TTGIIa)8Fa?(BNCm<)|Z~epuZb`AdBeB#CKggPi|)~au>Qx zf}XA61qSw^CnqkEu9sfr(LcM;_vTWf;F!xVa{h`Yn3R%VZL!*{slU=As%G{fyt-*D3NY*ITQivvQs@uo%DB-=KD|2U%$Tjynw zn9rK!_5D3qK{Jc|`DM$~KGKf8d@{)y-2vV-@n)R)J%jkyFGXL(s)ed zUyxf$Ie&g_D)F-DLTl$jxzoy2Vt1eq&2yQ@n@&=QP!W5tu&jyqdr}IK7}J4rKg~yR z0mraYO9OB?Ia(vTQ()@C36yX_tl_!&*q`a*C7 zDnY9IqsgKJd3fIA7*z2(ilp1$#1o&MM$=bDkttHI@UYVet;~-ktAan`1+Ut8IdYNY zM`ajBMWX6(8u^ zhNWkR5nHLZ*kHXsu8#~Q_clJl2hL{VIU=DXv#ty$jk$*FPKA*2u}L`h>~oy*fvqq7 z))kA@HQ`08gNg0-l{g~%JDyt{L}oV%XL^FOk0f7)6XW!_!)Q*t+rWQ2#Pn+-TxMZkB#S4PWB;Ic47D zPBOb!Qc=GA>11z`p4ErG^&a3IjP)X?+j>x8`Cnd@uos!XxgGrq(nl@(J;|rW4@fS{ z8JRrwAfYc`pt30mC~%Pnxpe(HIye3@`c~*p;x=ca8x0T8Ck=OEe>4z1`OtvGz1#>+ z+s)RD`GPKfbtO;zHIaiu7jiXoC3_~6@oEmUuZJ5h#6|zI&YDd2`cvD5m^f}y&v>ZmB)Kc!iIWb>@UFrM zvYo9}dstC`ADDieM6fk%k6gINmpy-s{PpR?F5Xjc%1238X+2(N z5Q;NCA12!4@8KOqd06U!J^9gh5zFM>#Pf;{kubLytfcn}H@P1q8>gJcouwbK^tuB? z|0WOLcmIJusN0ds?cexmM|$zeE?aV{ekK2bS0C1|-$%qRhUt8%>B5?P8}jEw0q^y) zuh`6IFB!H$6^;7v24|RAlg`ZTNL2F?-Y~(67_eVsJfL6C-)ULUa@Wj%Qb@yYm^XCSlZR3riG~c6|yX(nD>ka70({E@^ z_&Or$BZF!SyHUUOS|V{MmbWpd4>=l`lCtGuIvtHY$bY&CY3j7+kJ4>N(*)L#rf31| z0w2)2hpWlz<;$>2`U^BO#)usF<&4GMucPPohD69A0gK6Hqg?Y#B~aFCfcX2f(!yX7Zr(t8|hzgSG%rq$rF3ek8`)*@ni z_ZA+&#W>iXAzr=tI8*8_?m38v+0`&?{<02F)Z-Dx>;SIa){2WHbjVYI8CZX6Cw^M1 zP0F4;;jfVH!_FlONQ8qVf7jGLydiEr>5>-WEjrPObB@m=^>_Thm_;nQ@=(pf82lk)Cb9Z>6Ky+x3Lic@ zgR~reg{(*MaM;S}52P+Qc~^sD)LiFcxMm0|MLIbyKPZ&oqz3l z9@NfOWJ-0H;o5I`kTXh}xuXz_c_Z@SgSZG&tbp;=N%@cx{uL#EWzR#sd~lS1h>kXN zV$sd{aQJc#auyUOQTF+8O4}1foRJ`gUiq*#eFlhx9Ci0K-;Xu6w|LnMtWbvnbxGp;ahYk}Vo`3UUgacb^YiAE`S1bU5@4+}OpaGxL zDq#P{>>?Kbat&)47Jx1Ld7iW|5f9%}0F%eJV2kjhSnzBC)TR8wnw{gZdUydu-4!M} zN7MOR^9$hP6*02&fvtA=odU=@Elw&{X7U!kD}cCuQ6efn0oC>wz-=o*a&X3Blpg!p`@g_6J}O+D2Ohfy zP`OVas4-E68|@ zu*bdX67m}-$-J%0g>C7+>^;F~=3_}NSdLqYI=`qg@d3F|D*v3fS6+kBw9N&6t&dL3 zM0Lh>MJ`Al4dAy*D>IKYb3yy724}M>B>=Lxx*?Xp_l^$zZJ+|g+^XR zdp49usge%&+dBOZvLRGhgILu$@=s-D!>!HgM8HWAx4LG-CLd*zm~;@UZ_kEpfwE-n z$t0}5AR7cj#K;SmTi9JH8$6!%;tt_v{N_s*c#o~a&S?VVP-PbE>ng)9Y(|o4DOsT5 z5rTVmD3Cd4vS9NSQyjfmm6UGCf@--ReChA%6bDY z_AwJ)iA$qT%jJl{wM@`Hu@_DB6eqi*Gl7hcN6#kz#OK&OEXb<@op}5j7qfd}fW5EGfY1gNrY%H+k3%w` z<~e&Ds`Ys0hccibU!9p2CWe#^Gr)hJ3bTCqE_7&I22^*;F$wpgk@K$$u!DYLzcQjq`By{-QdQ+LaD5-ivsr9;-7;o~A=$!#Muh$12RsymYWp7Q`wk@=T;h zI?Nrh8E>|bU{ZIc!vxz19LOI)&N}HZ{WR-JNH?O@^68*3rvXn@u0SW-)8LuoPb`tm zo_F`t;A56J@j7IUveVKaWv3h&=#@m@9n;{YgbI=O+R6*ulm?Ui)ycOuVg9)JY2fxn zo%HiM`AekIV78Vjv146|t1YQeV4y(G4GYD$D^kH=vm5JE96ezSCjZ=21 zlk+$QuKJzgzZBFUf>9|TGrCG=ik~W3b2J4?7k%LQd{iJGR;R$$^M*)h$|&-ALJHJI z1S0ovK@v2O47Em=(7Oena93?IBv!pbW@44t_Hr_ueb|lcR;S_z!R($CGMwqa4)~XC zG6a5;VI1q#@q}f`;5Sa0Ic?;}Kc=1xt7ob+;x?f=_5De3MplEVW2$+ZtCN6vr^+0d zt&hYDlOWA`G-Ey94@r9`!FeG`repF&6mO9PH?oH@!BW-e>7pdqag}vd_I0A|%1JQ3 z^B$@OQRZW3BJ2;nfC^^FFykL3g6;D&Nb!Oavos?S`V1zbvE6FSLFYtpTN}$ep{~Ic zZBK-|nKR4x&sJl0>m@L4Rx z9q%-Whx0j7WcPzye06d>#NH7m1}7fl=wb07joYxaPaD>L8wYU(k8ww_Fp5D$Pia#n)g)l4`;`~>8WbW z!;jkKY92B0L`{RKm>9#`V-W)-{c221$pjR_#DGMh5|d+a1{JdVR$enQ%=vW}(ARI# zQ1L{RIn2L@jF^ajlB^oBM^%dV8 z8_nFC8x4{b`lz~Al{qys8VvWo+mfr0b*nj0ejQRaqNPTWYm}l*vQ^bh$01|&>s%JHm}2Pr>K(9 zXW>v|*~Ry5RVTUm;Q&jA^LGZR6FuK>I6QYV&rV*2G+Kp2uB9Y$Js?M>En(xgRw$o{ zlckE`5U@86-Oc%lH~$C&$A;^u!MXvvJPLzXuivBoO9ZdY4uc#11IR5e0&BU2!3t9e zW@hYWyl8tE2!zWs6AJ`!`hqa>WC^ z@;6#PG89fAXamZ)rsr-#7prUCx^JMzpK;Sf+bY>tz|B^dXHV3?L2jvwg! zMcc}Pq3Qv~r_vgcYFIG1$G*llZ&aXl_Q6oz-;dSy#-pQ#!C>ehPQD4-pn!3~@J(Be zs3uCI$G?JLUZ*nQPqpA#zYKyZS9LNW{dalK#UN;JS0_!a-}!2RY<{^a$(mt`Q*463 zeZK;ku`~o{=>@_5(<4dE_`|CQV z6IIEy9|3Uv%R8Qm_-ImjKLErVSE7Nz;fxh~zx}4gA1rUmFt5*RVv!sEU^-lxxe*`8 zmQD8ui?Qm=0UZyW{8Rp5rJ%v^K0oCxF!Kl94prttupat4(;wPWMl3iCfW}aqwb>~H&N!!Q9t-;l!1%{Wtic{ zesI;&5e0cGG2yH|zz=!vKH2r<6Pd|`%R0WN&_6?tm-!j-J2*y!XVH1?Md z>^s_ycl%_chH4+EJ}*Khm%AXXLLVsQNs|uKSxDd82fBomNN#o>Z^a%Th|f|Z^S?J; zHeKQa%h;Mg2j7+Obya*|jJF!mub+eGc6o#L4Mh@UqlNI0b#y{V%#7=L>GkJo4oe(A+I^Ga;JrCy{kRqF9yGBV}<%1_&=zoC5sXxcxuY1B5=PzhSdm$E%_k=UH zLd@bz-uV1+PgoKw$$TEM7<-v`!qV2!Ok?SNzVQ@K*rlY#d`IibzY2N6Z50j1- zdFKHhqUy{ysqyG2_5iI1N=)&kQz$IV0~+_rFsGu^(Zd5CU?M)8X_dc+3|D%9)R-=` z=}!xKJl+Gs8mp1@reTciUv__rQVBYJV-%B7;|>|q{n5M)qnW&7ci6XUIXYCS%53y= z2PmuMDNAZFH}|^33SPQS$0BuR-ZFQHf8@#kV4%zdsk?((nkrVEB+EdL8|;fcf;B|N zm`{)0z}7SczjEn8OLE-6XYw7~oXCFfO^_2JkEA@ zg>q0P9mn_M<}I#p=dCOW_?v)*=edH&fEY=ga}#Tia)qpV);M_Igq>SmKyZCMemYTr zOuo&T&18u`cAsQvaa>`wVWzBvd#t4N_zRw#9n94aDg>%NAb;~ z)yZga7g!Lyj+Zk-h1_Uz2D2+8(W@{yGU|#ml&!Kv-Rd9vJe%UaK=t63)WgBnAHa zpDIlChO^)l{);dAMV`T;XCb=U3};nJFptX5Kx0c7jxYO*4jniHBQ-D{t=)uPjX%R) z1HZ;yb~n(**Qa6OiGEx^E&*i*pN4~r#mT4GedwM3Y3P)cBNEGH(XQ@Ou(D2>WIVLt zoys`{vrelMcf0T9VeI~t(LL%UD&{M{Tlo}B*rH1Og4bZNM<+opP=N%U55@}TPl9nS z`x+ZwhMne~g!Wzma(_MR5wxCw>GzuPIgMVtD)j`6u)2*O8HkZa^Aq53EEyAXSu$7r z1msuP<9=&p5=M@L>}6%FXrxYd9zG5?TV46h;u>Vl)Z<`SP@>~ftV*Qb9fQ=^2AH`eI-Sr}J0(VJ zl|48FOhE_h)ENEWhrqo%nddb|gGnhp1TG34WdUo|nAryoL0{N4eyJIIO{{qc&O|T7 zh1ycgucrs$%@|LdI7gUy>V6Qy!}GD$mT%}XItWSPPw{)DD)hbc0Ca!)j)nAc(CO?0 zkiSBN^q+G@leQm#mm{TFTW&Tolso`6&5C5|??Rs54Lf)m!@hsFOI=!Y#tyi8a{U2C z{P}b3U}=;Z3Fm3ysUP>V`%M&yc#11t9lakkM5Kw)t{mKNv>yr?5#l?)3VR9chuKfQ z<0VJF;cI+bFm8K-?=!+A#oiXekLTmKB~s+XI9m|>>wz`4Dw2Q~`(V_%g?Q5jHL}8c zAIu$gjeli~26?Hw5BAEmmMPSzk-2>~VD6Q|yR%n`*yh>5s_H37qe_~@?X&?^opVTH zsVJE&V*}U5Wug+@4!rx$UPv&1fbQVu*z5dWU^+h|l2(LoF4zmpX9_WwPW#~7E!Hrw zUy|9LvjjhnwT7^}qnX>HRs3}(*6>?YjS&j9D?ck@4aeBm!$;>(-qfpB>^?PhX83`z zDC4LVNPJRa^d_7{-zHc=dWa08@-_`^d1VPnONTQ(_IHuKza<1`b|IxhEv&C<2@6O7t8W}o@kty5*@7w&*k~yOpb&EY<|7QidQmV>W$?pMi@dlpH2-byo zU;*NG#X4H6)EPy03vfB>#&@t#X5Q*pfbM`YPB)chbieF|PojtM*2Q8>aKdiz3{S=} z!+X(;^}C_S`8IaesYSgbc7sS`GoIIa8TC}`f}~-B#C&Hk+J1Z&JTDnZY7N&Q+sV6N zVz>esEB2Llu5Ks9Y*!^4Cx6pv3f>7n*!PF-@B8?F40nR_N%q|Jm&I~_cfikTWpeV} zJ{(-U17yYI$n0ea_<`jPm^NRWeD%J8HI;Ti%C3Gq$FvEjJlPIGt@YUS(O)d$y&ZG} z*!odVBuF~59hxe`u;~wZQub{d%nCBYK?5ozF?k!z6Z*x^Xiz5^=G$PGlRSS|iaM#2 z+6E?VM!cluDrDL1t?+!b1p0vGNaM+^u%*}n4NM$CMoilZx?f_DW8p8X@@5O%^}dFT zL*B5)@D_M@iFHP#u3$-%Edc(1(3a^@xK(fq-1#(u5qz`_iYiSJjz<&KbOd>P-N*)EUV{A#~7h6YR=YVfs#QMRS*I0@;1?OtXI^ zGHy4A+p-c2yR{OjrJI95?;mtp;SGAV%^YTFy+;MhejzD&bI=@p9m)I@XQtoX2)^E| zl@u$-n4j4QABS0@2U;r3_Zb`E)3K4Pxu(vnYBU4+gKK%08`YW9ab{2^D8)z8s!Yf_ zGw561#}AQGU|fXF;0oG+5C4>4LN9LslPO_XP*s4Lw0{G9wCCeJcbm|uu^T|-Ks~-9 ze-nw-t%tQ8eR$>D1hhYJJ**!tPL6BsM_GF7q2!}1scMx&nw{%FwnCZI*dO9e&RPe{ z?bV6U{Kj%*u@1U_vey!Zt^6Xzbujy&DpBZKjjQgjg>A(OB>PGbu6JAuZLdd?Lz^z+ zg<5N2y0#!$#;?KSKbgXxEg$it=pNjkWD4CQ?%-G{F_La(3f8kzuu*M&KHXcSydW>Q0!V*;Vp#|6E8H3TEYLwk~7dKiP!}^6?=<=y_ zT&H3Tzhs9q9}l0xs~@d~MTcaV&dPB(@ce4{^;n5{U}~r&Gf}Dt9RNd^zDtOiqw^d^ z9W{iEeP7Ussvqd)bVJ~?|Ay%yBg#m;Uj;HG6P0F5GYMgrNEzbOp(b}UkNvR7vKk0Qp}CV z2B5di1J@o9W`bM|An9!$-qidJ?ba~>+5JzjIIco*KUTnm9pABWPY%+_Tmh>k*!T7o zZs^;V6;S$CisXjPVJ+JgaI8|1B$|})y00yVtG;R^we6aA-O1%(%6@h@G5P$@vzLQX zh8jtUnuWhLErTZmibTK810_-X9ksqG6Bl+yQ;KxV0TW{O}dq zmg$32z*D?SK$z@2s1J*#72s9UQe^QMeXzadiS3ahS@&!y`25hpz4~h8x5rZ0XLf^c zrKv$qEM5v@t0l{mo7Kq2ZasKDKarQ_rbK4s=)wHClhN~jX=1ru4>o2wBCRu`lZ+d}eIk7tdtl7^F^J45gPZwUc4`W&u`(i(KABrO*$v7M8 z;h5+p5T7}k@!R~AKf-tkm~^W$zq(z^)rFQo1A8CpH!Fx&PZoozraIGFsfqR-Ud+~u zP-ZrV9!I6)7QLs=o-Vm0z)cYaqzP z^)rxswiNBO7{$EGW1zY?00~HqW}0>~Fd=Rwx{;#FXtK8wv$nqD6^m*xkMANFop@De z@&z>vW#de4?2$?!ds7tG3(=aU|O4md;ELR8&e(} zti6RZpVp#SF&=zd+l(ut%TVDp9niidK>limps@}*@Y`i15&dX_W>3_C)WZto#OCij z_8<3P?J8ArYu8U5-@t|N>W4b{ZM=t{yK*7SbWtbAKT6~0zqO&WO_>B4+2GBE+MuK* zN6vZ1<3I~-kl8Oz9=@%>&lR*`ep5gD?Q|nvTD1VOoL}Q$lfU?i#{w8pfU$Lg1hM5U z03Gje?DJ5bIDMJVekWs&`&v}Uw#511xqg7Z>XkY%HJcA@s;YdOY<1!}YCc>wUd}Vx zu0n?0oCnhmi=*84awPlsJcv-2V-W&AT;MUeq7J)F=@DpHcWbp--OMD z$7A0i19Ao5T0Iw3M*cyjpQCX8-#L(3GJ<(&y#qfgo&zvWp1GbTie0Vd!2dzrUA|?} zMGG8OKrm52x(w_tVAj~(t(e$}`r2I}C>A0pp#p+|poky>v-Th;h^U|_(n^VR*YntC z)|^l0PdJ}mzP;DwHP6J}`?qd(#)$XS;si6JVdC#dQ~vv+-rTaZp9Q+G6Pkn`h%ZG^G@r5w# z#ZQRW8Y0?A=N~>NwBu`E4HosL-h?Upba=DFgT-p^jo@uy#E14DEKV`jgeq54z9oN< zIH9u*=UQgUclRD7cHY=lnAyvipF3}mXw}>#q>s?$r>P7Qo%|MH%fODjO~gQP*A_SY zv%D3bzh$7f`b9LZT2Ty!<^!c!964wb6AvtNfT+4liED5A!oW)d#Gk3sJmgn)@ZZ=0 z;-Kf+Z2c8oD5&c%x&<1t89E2JjC=h>?Mzg+P4(SG6_P3is}_zdd@^%IBeZ_Q?yXW{GOzT(k}5)`B}Rlz=e z#RFl9I3P=dZC=<{Y+d1xCsnoC3$?!Drn0>lJk*fsMfDLM{4>FABTQMWT^~{1<-Cy9 z#f)9I=p*{h^0t1OVa(3t_7-au8Jzil()@at-lAFCNwB%16RR5ETYP-}qV&5|VeOiF zi9Mad;nlu!JQ>_eoUtw)Ci%QUw++3-)1i%!JnSCcH0UKB&Qa%^S|3H7cNXG=Nm_i6 zodwQ6VIh8dYQWdKdkJB~EX2xR(mVck-gDZ2JH;g5v#(055s z(Ns;JAFu5UoJLP^_zO+`@XAo=i#^0)H&yu|H$K7m-95yPEtPO~ay{&p+LO(vlc6EA z4gW5$yXd+10h~F}h2MC!yIAdf8YT=g;IB;TF1CCc0N0+I@WG01;*}eL+^HUBd_ib8 zF{a5m>f&w_-e*fUadmC9Fwb3|-(}oQOjtS+@3?j5om0$3+v|>)6R5_|Ic+Y^>Hi3O z?5Tkcmgb`F+YcDO;sZ>rH4|Gt)*$!jA++2z6GKwfSWX8=h_Epe=Y@A>-A75TVmmW2 z@qs>T?;puMiZK<}9y4M6eoePJe85!to-$*<%7O&HL8jup2otumc_2P1G!a8h4A^KL zd(3v1IuzS3>`naxJT%or%nEJ8bn25a|Ch0tSzL$zY^qTEnXx!VvbQinm6_NXi|6tl zV_2akQ!_IbFP}e$M~w8DUaFCZR{`e?H(?QHjHJD@SHde(Gp5f=O^QXo=%NM_cB9cy zTwHX6v%YP>Y6A_$B9~q;v6mL>zrs+|m3&LXr|K-Qqx5(9J@_}j5yck<;@^Gg(6MVEokVCT?Iyiagf@$`Nd zI98?02d(NVp0S<*CtQsAoX%av{tv%#ZYpN{{zM&d!>4!FpI4jmhfe8;eM6535!Vg* zbt84e>Zf{Gi?;^&GFqYORRJq}o zx`+p>OxeufmBR8VT|~DFrflu_&glNLvlyUZ#70L*rdUX4G1Eqe9eZ;V7p&%38=bN{h=+zhhwqq=$FFt}9WLiX`R3<%bVdhJ z^Wtx4e&B_B{)VT$cNp>K!p8}3^xKPCp{D%h z2y;&5qtuvuGUaE^YXxOz+li^!M*NwnHW0_P6SKm*@-CgOLwaRfG3Q7J{%CIo7yR0a zOIrTI^ztvDXVX@Ey0i%9jQt6RI=2=3Y<~eZSK9I6@fy-RrCSg+ONak{KtsGRbTgQ? zlAcL@HN+z?Is=|Fmp$i!E?dPbAWA4=pA8mAb%~tAS zgX(-7y{02?65d9fbpI;Gd$r;{rQT$>b~LI~6@zHfMvUNdP-jyD>`Ye^=a(z6w~Zgv zoL3V!+-S?DuGk5dqt(Q9*R@&VNPY0HQ5D}_He@Z4$GEe1R7I~9(lb2ib+pqeRq>0e z8M_=n))m4wpH2lZxw@rZMMw)En ziNCDj)dhHwsKPFM`@>#+3X`183Yri z{$M+;O!#BkAf2sOvS}9j{H!_WpjCS%Q`Bnmy8<7>+y4~ouViq>{Q3wVb6c3fnJNgt zI)J$?>|T!)u<&iecNLmhLcbvBw4e*W)U26xn{N--bPV`=4oz&?fk6OIO!(M}M%J}D znA4UFfWIpm+0rk4ql{0R@b}*~u%EY{2}8s6`HjOH*vV(Z(K@a(@8?m^_z!3Bc99yd z_q&eW-v1C?f7gKBmOA#J-v`wE^#KaAYo)#C8hpF%5p11O%hIo_vGR|Opa`yE_Z&O3 z1sNluf9D#OdS0JxZxpzMgVhY}OxR#`Z>zy2Rcx~K>^SIgUkF@U#mZlrFvY?FSoXY< zO#uVeGV3&s?^($-FLq(}@Bnu@SFmg4ZCLo+WYljgXTH1YG3#w59@tdQF2DVRUz}B0 z*vB$Y`H?b%bp#vGay zo%_#(c^7?WU$1y_XQY!48)toIODcQ9&iPvGTWGOl;v9j*N_Fc@a76a=Nr%ebkumXPm=+{3_uF{x#)CI%l&ojcjY{t)~3!pIPj3 zhke54P(yz5#w>PBQy0D8YV-ZyWHNDv9r_ivReN zS#4|2J=IBLDJ7Fg)=*xi(w-{^$*>pn7#Zbs~s=|)Um@{!FyrNjDkyor6K z#-vAjJGS^z93JeE$}Gx%;w6tlRB`{nj)#23)Oml=M&$!@Xe(l{Wd~Ng?LGUc;eov! zx-z}@DJ*jJa;y=JSjdPJHtMhnK6_)zrurqbJuCVOD+E)G)Ee>DkCs5E{}R}T%&z=@bFRV2w0Nc((t)o&jNl0I z%=W-PIJNK#>ejh9;c7=dVNDEsU+jttGh6Zgi6ZN^AqtnA_zp4B=iS$UZ1n5+3dY`N%zC2&y|iz` zy3UMU+0d3b*X)Ad`;g7sA*~x_8$d#qz@qjUvYmtMIlGAh`#jH-d0)fmB@xl=yM`Ha zTADAs>>kZL1C3db$uykc9L4Mn_1M^hmvLEDB%8jw6Wco_0^co+WUjTX+3)fU>=yTo z?QdU(TiP_E-tcE^)SuUQZL0=Ly&1tc+dJ4lREznwiePg(9Yo8Y25jV}r)=BwZs=)j z%BH*zXCA{{g-|^+7CA1QJ^XUQ`uR^|Rv8k;LKmlULYN*)?;6Igy&VVbXKJ$g!%tXk z>kD9`s>)RIL#69B41!%N&}&vGYwYtGhJAmFUt=CK=Gy@E0r%0e?_(CTRh_@v;{;B; z9Kudib>TOJ_rXW?k67kW1HRJQPZ+Y|5pygw;p^V0TdTf%$kL_#>aFu%aO&`owVrOm zkJxJs8~uY>pUL{Xw)0uI+$NYEHS5f4G={(wyC8N|TaC|I^$~hzK45P;OY25M>%eWs z19mVW1&lYg;oTwvnMXkoEVAgr7aImL9eoGzYu4unp1jYF=nnx8e-pl6$vt*$++%Ky z^z7i5-eV4XPerc3V!~@DN;~i~!-dzW`h3-(yR1=X7@n{0%nx$A!!p~R!GWf2cy~nr z^L!qR{^x4p#rgo2?ED_fZ=}MgbbscA)%Z^@1d7M|vzIH>Sfr;DINra_qL+4NaL5v# zw!h6>x9c;U62lGO>&M=#G+_&`r&#SQ^kqw>{pz|&cZ4nreOYm;v{(M5AMQdQ=4NBS zirb#T_hvq9KvWl2;1GyaXKt~sJ=Iz9!*{s1<|b>StjDEeDlu{GO}2Au8orvX%KE3= zU}{sJAWD8fj}bRmd!6$bmaWIedwMhe;}|sQV!~$p^Tsz@lSXY|ldv*0<#lSXpSW`CU9%hw*pe_1Y#JdGtCP zlPI0H9hiZWs;)6Lp$ty!e2N>FUt^;{h5zDw3B_1$au3t!^K8@bS0 z)tNoM`3*TkrF>yEPN z$JC^AOkJ6R9bqN&Rzk3%J=^Sfn0>4BfIm;A|JR~J>{5;>HBSXtF#I43*pLUm#8`CI zIl%DTFIe2`1{QzY$5M3L^U6W%@%*E`?B`=0zN1$M>72(NwrGqI@6bG3aGt%Jt@kzM zCmhn|77Y83UC5W-C0hODF0|XljM^CUE?SFWWcm(v`gd1e<+3{*_pxJD`5pLQZv`l| z+s=MB{)34u7i?#2V~xkY!F;P9aAd$%c13&%0X^IC`M)=_Pse>A@s~FL{?#USX4N*B z{@#$sD;wF$PC9UWzbXH3!v=Ouv7OtiH04)JU(Z}j%A=pJH|E>+SjU3YDuqU0UEZ!{ z4P)vy=_{BtX(bc$S}-!@ zHoVnc!A=Zp%a%Dv*LMCgrkE%_J5CzGy#tsb!;h1nrzDI)`dimUbBP+ zb}(a$+I$gq!D4nCjalx=DR@I;5qlsRccY$O!lVxiSkdiHO#RwZw7)fs^NZPc~uYin(lGKoag8s=@9Kp2O1g@1mEZ7F(s9#kBkmp-Y~0#`48XcCe~D zPUvjP7P-%0&5rKEFzH^=a$q|1JhQ=iNkAR3|GD# z*vw@ny#Gf_$l*8^yFs7#c_HUv(kSh9*aYW%sFRH(i?ikaW4hPZpR zkam6~%a-PUWcF*ro39Z=2+&D7_&HV$P=g`x1kO?r034`G^a zVcZt!*-;%Zn02zXuw3J7!vA&{#I%)<1>IVGzI@?8X0dk&dKh)#4;l|(!zVi637a;2 z_mX~WMB8AzyuSrL{priPSSS7;JMaIy19;u(mOy?=@Qr5Jd_2X9{FGIXm2mcGBu9SA zhGR{zJ$*2cpQ4jq2Kzr80P<6^MrFYmRWBevWpqXY9C;W9)B zv=PWpaZY+G@Wtgoe#$A`ewceT7syZ9@3jq|D3XBu6nzIbe2^FpR^Y6$q|KQa~e#)DddAKA05|W?Nu{jwRD*}=Hlw;eXFz`|= zlAm(R&lfAw(~$g>pR*mXmw7RgpEA>YDsIZGMe zC)b`>U8-zG@>AxmxyEgqT!ZAN=v~!>Gp`Gg{FDLL=ELjcR3tye$K)Jn)Jo@L?*@zA zivwWM$2&-V%GPcS+V*os@>9B*rGn4bg-CwNmT`qp^`i@tpE9$w8uDg%3*@IvXU!0^ z_iq&WDd!$4;qd6a9Qi5gIW1t`uQiaL5;33-hQ6N!ybcyO7zzUaB5sKke|}KC%*fJu?iu@FR>0V*^^*Xmt@>8_GN^_fLcLwrP7WJ)x zmMIH>{1jW?LTMfP9FU(<>6r>J@D7llvik{xQEM2GpK|Q{9hk5v706Es%RC3UTc!Of z$xrDva3Msh)<|o5{$l3XE@1e!8OTpjN%rKFkCZ@u%DU7Nt1<6efc%sL)(3=H+I2vF zitG2*xc+c4ke@QsVKNFcKLhzGi(Tw7!XOUFPx;>LgAJZiXCe71Md^`v(L*{bCiy8* z2c_R~oGp-_;%J+P!bMXcKjr@SN*t^Hlp{Z7^xY=3&%S3(eu~X;CBDY70{JQXTojm- zUM7&AGT~jlbbiDN$xoSYQHq{D4k7s|Ch3{D_of$;pR#am0y+!{NAgn!pAJE`KMBcC z(H`ZF#(i^<{1jUYJGApGNAgn!i2bqsoJJ%+#edj)!Nf#~7PtNa0rcmm~QpFP-{B!l+y%KgF(oJNP>#A^9mC&D^2Yq;MoZrO%EKC=c^O z@>6o>CcvY`hmib~gv3lRO147sQ+y0dA!|yxKz@otLOmS2HBNAr{1oA$0(KhQwI)Bs z{)7_juZMHwr>qZZf=`Q0f&7#YHI?9Y$ri{@Ic%2)zfWEU@>ANJONNPbs@^4>dcAf&3JwsL2r5z7AwR#Z(1^w=F<^%1WbyoNb5_ z`b&Pw)3p4keeauLy5y%Atn?K0JJtaCDGnN4Q2#(7G(Wl_`Y9G*{rXfOKjn7pIefW? z0r@Fb`|se{33q_}lnNh)lg^$4@>3=|r=tDQ1wekvAh$w%a;7topYq4N2D{Jo;K)yj z&uYe7Lq1rMpEBjK5)X_#ERdfv_oXz?!CwW*PhrYhoMJfz$xrcKP>j0@?UDSHO8w9H zeVi|npAw%Ni=*|Tko*+Qg%9v!NHUV2k}>r%PP>qYJ}~LGNeM ztPf2uvCcV6;7==&{FKiXe$hjn6i9wb_s9v{hKPD3Kjqr|3Qnh0DUzRJGus+m?q(wS zDdq1Dfn_hL0haufjip|&b#w@lpR#37I1DUxL-JFyLXtq`@OC6WWx~>2Fjec1|m(fg?XLiNPZmoDWAqR!t*f$fc%t*Q|0i` z#}3F(Ij4~e1$OR0e#-9INstv90_3N3Y#k28=M#YZl;TZZFj|obolmhuF zwYpX?HMbtfPtkl=$`xHx0Qo6{{6}++N2ED0lAp3rBRIOkvkAygNz{%IUVo?r@>7m# znxW6QJRm>i3cm(3<|PC9DSq!Sqr-zpAV0#^l;REEST%8n$&llMP`6;`0ea8K& zlY#scANOL+UfUYTPZ?!VhpWx@apb4CWVE2?0Ywz~DawaRY{~Kx$WM73+l)RhyCC@~ z&uXi&chEv4KjqP^Lj2ps8Ocw{9+Zj(;vFPE<@a!@CH%sW{FDPfq~oqA2!CB0*ipR&(2DvFD2LGn`$4?V`I=hq_n zDN}4!A*6pXPH1!$dsIw;f5mA?e#+jF4j}l(BKawA&ihK|dLAJ8DW{f3K|94IBtPXt zakBIqT8-qVlt0UZQ3fVRe#)wzRp8m-i9mkJ$HXQ$^xHd{{FI+(lyE*wI%6UEDX)(y z!17%sM}CT}PdzMD;eh;<@Z1v6I&c`sPbt`!3H%6eAV1|_c|2G?4F~d59F>nCrz8o; zPZ{Lx22&lSHDSq5Ir(lItjj3}@>3ME`hmuQMj$^$g?q>S=__5AlAkhfoGKUEMG54m zjGUq=obKNU4DtB;z~HAS6FU zb!#NroQ^~CQ=AX^poafvl>L-e_Sg@Lk^Gd&^CqF=m^vgsW%b=wIHsrt$xqqPW4Ev? zSc&APoV%o99si^m$xnH|^aeL1ts2QsxqCtj%zG3f`6(AxEP^}A4@iE>CH#-Q??aL?*^STk^B_nWi_yHp}RnSN?>y{ zR5bWSk)N_pn&)t0;7N}Blz-Bk2WKNSAU|c`t6IqOnF{2m_^KAe+H(#-eoA9l8n~wU z0{JN(>tf-dM--5sQu8Vho*1V9`6(8GmtbpQ9+01MJA4(inkaQNlAp53))CgaascTDM`}YkKj?C1oBhb={4f^kby{k$`8IABbs+0`6|{1nxaXV&NUHzD~cLpnuqGp<%5`6=h@&B4C(E0UjL z=)D$t6u!e2$xpel(*<_+iA3^K)-Dc$F@t=h@9HyRo0vH06LK2KPq9z?49zztBKaw9 z1;udp!#{!il#r!$u(S70f&7%$)h*C|jgB?>DY4QVnA@Lka^$Ck`!|EPwKkBSawf7G zQaUUK@>6yz3t;b4XCOaie*6bGGwUvppVI#s!m;Hdke~8rYXErl{s`o!Y`c0E7Il*5 zfJuHz&c=Dru&)NlPkFbX6BMYn0Qo5!KVRh*hbe*l6b&0^D?gtWAU|c|wbR1DhqXX{ z3d>N#9bdkI?58Z4hHp-$0r@FbIS#nOA{NL`86%y4czP-j$WM8Z5rw^ME&=%|`xmC5 ziRvmKKP9naKCZfJ1mvfjTw8^ST|zkWQ{I;~VR$zeYw}atUsR&wgP8*PDQCATaBy6W zKz>TGv`5*v6OjBAC$|zTNIZh%r&wrbN_%SFNPfzseevjN`4q`dS-<-cUR?GD$xkWx zeHE+nbMb}br?lR?6%$M0l4s!k zBM!(<$t=1Bxoy&c{1jpNX~U%F#w`^nG6-?eFdvtHi~afB6HDpK@O9JenOucrE!U zn(lYevs(a=pYqXD#9QOe0{JODSAN8Z@VP*KijidzuJq^#FG-2}2wqU+n8zetP{c0`#P@9hAr|3WXhKhk_ko=U>v(hkS zvmcV5(x&t|zR-(C@>5oDfoOa_1<6n8tZ@ldtn-oll)Z~qV%EtjBtKr|eQb0ks3Kfc%t%k)Dtpl?CLdWUKCnlH^h#KV|Uf zk??h71CXDh%#-HnMJs^(l$#MlxgJ}UKz>T$s~6F(^P7PDl+79_SS_ps@>BSxZkXrt z706G~Y*~lD_q+r0Q-*cCg01d91M*Xb<_F~`6=S@ zYAoNm1j$bcx?6zGOU_GY)i#LpmwmuvId}1h&5Jx4p?L^t)WYP%84u&Ay~RD$xpd7eR$L^#};X3$~tj| z>luz6l;+<`eoDh!b@09X4arZjiJlGy25Crs%I#BUz$@svG{7DA zMoaJG7m@swd$B2S@6HM&KgD=MJ`5Uah~%eq@~MJk-C%+Il#%V5Vf0joX!29eUsXyo z80K^2r#xA#fVhZyj{KCgarMw6Tbdgv`6)@$OF&IJ!$*EfS!f1aTz3P=Pci>3?M(9z6x4?DV3docElL0Y`pH@yrIi zD-7buPdOE*z_F39qsdR%Da|ka&yfk_r>q#;g!@CfBl#%@hgVALi|dj6lojj0qRq-H zNPfy#c!xVIf|2}`ew&`*fxRz~{1hp+#^Kx3k^B^H(<$lQ;X9I_vgpKkobF$T%w3?M&6 zW%Dw)}~qQQ;A)1DR-sWunSkyuE!hke{-1 z>lb_%)(gl_nRcoI=e>>R$WPgl(TGtm%B;yx37o3L<$X;B@>4`%}2Reo9Js85Z6756Ms2Qk#v>MqfwrQ#v&!;@L@|NPfzleNV8d{1uX)a{Z2$e?nQr{G9*7G=>2efwYCAtPuWzKCnP0Fv(P0!CGL5D;kvC7$xkV|pJM%QKogRm zvb}W-cU8L*$xpeyxd%KO^%coa*|~6obaw6?lAp3M_zLhA&yf6-3)_OBmFg`dKSg}} z0&-$bBKavpZl%M;q;W`o%BREMp>M?xf&7$Qp$lIcTJS;3pHU$xpd;TM5DM z{5kSdnx*;JK|OVW{FF5ltKsN}r9ghl^7&FbrZ^Aer{q+PB0uG#bk28=bX}64vaB%B zGH`nfke@R5(pe#5LM@P=QktlNlg54n@>8Cg&BUrFpMd<7Pzy)gH~2Y_pOQZDHu`V6 z59FsS-aztG+#O%y zve6Mpeu`i#%@u&R*hcbGbmCp{;q@;#UGh^##B9RPeicZ5ip~!U+*RI)Cufl7Se#^rzme{bA4RPko=VFi9=yZT(-2f!ijC??FLgJ z5y?;abpAS+4|{^-r))eM3h8q_ko=TM7Kz}cwin4y`8_ooV)ch3`6)@3W$<&ySAqN# z`-9S1n)p5f`6*SY3P|=$vnD^qbGZ_1PCl1r!B~kW4V&P$c~2le+~JZ(9E0`>M<73?+rUrwv1}HQpOTYV zgcX79fc%uk-!qog^ilAn^|wwyCl)*<;R z={;JwZrR_F{1nX}V<5md1IbT0*yRKSPJfByr}Uq66V!|zBKaxqCn8|&epd{6K0y4k z_bvE#-h||*ynguwCXctk7m}YcI<5lVr^X57r!4s02vhUEM3bL#W`Pn8nD*qzPqF!` z0554iAo(fXy&9nH&!Iqm%IckEp#F2W?5C()&4%=h>$0DseJT+w-h|42%DI|QIBc6J z`zgO#d%)g<*|MLKyL=D4U0x>pDZ<)epm(W3_EV14OP)xULiSTE-&k-57As{x<(G4I zbf$Wf?59}%iWQcBs*wE@_pF|%{^g78r;K>K5m&ms1@cpdPj^N0fCwNzWmjV`j@fw= z$WQs#`z3nsIsxRTy!n@o0k&g-{1lUf?-_qRCGQ zyQ#!BukQ-vr;ME3jG~vG?5FI~sK!%6m&tz0>0kNi=5;~#Q)*7XM{UJD*-tsc3E1_0 zjO?dWN8FZX?0=H|l=1f*vGHG#?5C((&cbs2TG>zOQPmc^Ep0*aQ?3*^3zA18`ze(k zy++NL-y-`d^PJCf`W}DZMY=CYe#-5R zFCqGQgzTpbOAm&>!Ea?h?*{TyUf;{c8$m;X{FI>MWms|`ha*4btiSaB z@V+}oe#)x?1@1hWA5DJB;CV_^Km0-nz`Q%3Z-iCc$d$bL#x;&HrG{=a_8>7X$fu2L`iDc_Da z3;%&a_EWY^S|+G_OYgptpW;4hv$gTaX4y}GQ+hAbhl136*-uH9I=pu? z-y``c2IUu^@<%k1pHe&KK76sejpV0fcX$qE3muXClrne8H99jB$xkWo^9^PWZHwfm z;P6_wvi_Vve#(LkE$~9Q$&&n(E7Eg*j`~H8{FK6pEwJKeJK0a^QeOizt!B%9%E-hb z@G^Fi{gkP?pP}A0q@_-eu|UD1-NBh0OY4Q54VBRVbXI! z@>3RE(go9%&9a{o>mR_)^po~?$958XE}mh1p_@YXQ#M~%Be=h=ll_!cdOw6em%qz? zis6QF*grZQ$WJL-a}rOdz5w!5I%eO*39i9Fe#+~A5g3|r1;|fP`}P)9BQ^l}DYs0% z;=1=efczBSR+Xrg8N-pEa;JL}7XC`LCO;)*r4q}u`w8Ty*rq7(hEAS9e#*}s4XC?y zxa_B_>QjbJ^Y+Sqit+GlytLax_ER28ow&{1C$gW?ep@JB{gf#CDatL^@%QI!*-!bd zx*Iq6mC1g}+J+&R8rdNGDPw+S2}jEmvY*oWvzhR6hP2iu`6)eie780zY?S?!q^6hL z<*OC4pE7c0FZgKxMfOwHw%ZJa-QOblDL1~m!XxttBtIqh_(SNFc>~E$`QrN$g3OL1 z`6(sqGhkxVXe2)+OFDyAsnR5npYqtK9-d5FB9NbwGFbu5o%ULjpJFMUe;@lYkRw0k zOV4IF(aAveQ_9{|L9^>}*-tUOpATobi?W|`sjKvycf2qADPu4ioMt?i{gfv?ZiDaZ zPqLqKq?IGEdEaC|rE}^G*fghB_EXmF*ML>KTVy}wa>*!7THgk z;dn_XPOp*uly;HrvD~Lf_ESpAXJenjk3fD(^iC&iV-*ABr-W?w$JiP7fc%uPp9M@v zI}hZi99R2*-|d$I`6*@V3-H;;u0Vdu=y}q7DGPs&{FI#S%{cPp7;ExVeEgL-?(BMj z{FH~f3T(OZQy@P@H?$5L^v5IlDOOv*;~I@qvY#^UY&w4Kc}wL<1x;;>5WRvWtn5_^6T&tA*6x|N*qWis4 z$bQO;P6N5YHVv|$^2;Tk>#bHM`zcLkBjBJ)HjSU%seoE6jX`LzCSRg;8U7Z39 zY%8tFPZ>5@Dc!RZIPz2er8GjJN^jXusoPxvF_D{PKgDVB7w9+gs_ds6Eq?=>UObfj zltp<@;ZDv=*-uHncmt+f%aHw)-3O0BtC1zLpHeb*G&l~gm;ID1=LW9LJcaD1w3@w; zo8T_3r$~N^M(K&@Lpsf}pYmZ`kWd{`CHpC{uMLnpmJj5o{2IRkhvuaK`6;>QFXG{& z(LjF6qIdUkOST`7pJI6KIW~rz0rFEUe|^GlCNqHi6uU#;a7(m0ke^byr4}!2cI3!U znRucFhkVkHB0r^GT4$Q5BCR(`eu{se77X0eLH1MJq*<5iZq1SXlw${qFfP_f_ERbz zeZ*Cv{<5D^trYRB4$6MYDV2N3!3Wt-sc<-t+LsGtKgI0h65P3?8igA5Rlx&>|3gOU7{d-l)3%lZnEpCT@N2On(KBl#(n2c-4FRo#*NlpW(M z!SpK%xfr@SjDg|&D0 z$$m=sr!2^6=PCOs+1FnIm-a;VQ}n()hOtv$%YMq`lxv_mB1iU9W{2#8?ZsuXpW<_7 zFf{0iAmImmjWexENu zeoEtpEvR_%2FOqGakz@#ZaoF^Q$DtNB)tpV0P<57=*45l_eX*J6sK1ixa&L*Ll*P~rPc_ES8! zO~+XdwX&bG`ga>tz0e~2Dd)-@gdNg#Nq)-m*3+z#3|nMBg*$zPGxn>I{ge@dI!d!g ziex{9&7BJ_hd(0uDPdY?K|~SBPpMV-Lw9x;$xn$|i11_Bc_cq2>%R{$s@oErCiy8w zQ3Wt@l@9)q{FKAztKo8AUxECTZ|9rg;^$t`R^Wb1ldm+XYw7s_dhNBDII#GgO+eh_EXLozkq!&pUHkoY+MlRyzox;Q?``5z}kSX zvY&DyXdRfWt(5(gynt?SW|_3dD)}j$*9u&p?Mm5CS=2w)dO?JA50U(o5Y^#AuK^9R zpK{EpNSGZ{D*GwxE{(*LfGpWhxiWV@PG9*7$WK|m)Dvs`9s~I)7j?sM$mwf9eoED; z*BIY=7m%Nlu`UO7lLrC$DN*X>m~{3tM}Eq?<_63w*5$}g5&kMLZlWTZ{FDG|$y?k0 zS|C4VRbV4F?&~A_Dbt5kpo-R3*-vr)k&DXItFoW6?C=}xHuI6}r>t4|6pI(c%YKTo z$s6ysWXOKXiC#zX`-u|SPsvIHj9XVP`zaf))e3DkC}ck+VexFC@{;t9A^9mcQZ88Y z4NbD2k_L~s^LwQIKgmyNGujB+_sW<3lpD8Kg87~lBtKbY+d3vm^8i(lAm(+RxLPgw-?Ay@$qPZ(h&!( z$WMuv_BjXsb>+xUdE21{LdrVIe#)scHPF~4QFLPrR(I6uxWgN)Dqle z`;Utt{qx9vO5nb`u;Sha*-xn}aE5;c1+t&g@4v-hd%s%tQ|$b;VX${Ike`wee2aS? zsFeMb%vMI$Lz<*_V#!ZwI$|f_Mrqwc@>2|c{}np56w7|f>roT&W$kAmKV{9y)2Nak z2jr)mRrSH;$AW>bmlB`<9Vw8X67o=i-mQuS@>5E?Hek)fQL>-%z`GQ$EBDKOO48me zj0x~W@>6`ey}~y(VX~j{VAW$hDZG~bl<48t(AhOd_EWT$?!*O7YQmd_B#Pf6LK01M`7O@7LS^GcW&9m0{HvZ=5M+O`XzFM=!~KiXEhYi*KOpr}$wMOc)m{`za;AePPP=G}%wde&zsy)!$@4<+jQ+xEWb1 z`zZ#FYM_0mMfOu#XP@F)q;nzUr<6swMcx0?Ec+=Y$K8aOEj6;AqIV06P!7E1i2gz&@oSez@Wc*eVZKEC6J$jWi99jtz=~3Z20s@_EYq-!r^&RyzHk4tG&T-S*Gl# zd`&wH{Oc0gPqEp`!6sM9nUnmKbADCa?t=>1Pr=nwIkmHr87lcHDnTC6TT`24Kjq1& zP{DPibpA~8Qxu`bxbS_R?570%TZK1NQ-J)GF>f#7>7!9Veo9PnAP#=&3$mYbJQkJf z9YC6}!PX_EVbk2HKz_>GuEm)5S{2AoxhTyr{PpEHM}Ers&=z!B5FAB*N}DH2Z2Qw) zAU|bQZ8Ppzqbd6-8MA7z)u#EfpR(msA^uQ5C;KUhIjQ(3H9+=LZvA5z)0xSB%Btc! z*rrRW?5B8)b;b=N3uQm$LB~ai`PH(Y;xs@D7e_VAeoD7cZ^2wTUr2rmu2hNc_O(U! zQwsL%;p~RjA^9m5idHZ_s95$>w)#$jv%p?nvK%Rna#%`n&W|GvrS(l-3rWh!?!8z;xR>`R};!ufYCYmH$4x^bO23 z4F_sWirhk=wKO|`8k1_DOE7a^k=&THyFUjGy{(lS6YVBduz%DdHzpfgPjC~Y-#axX ze_!2=!iHwKFz8&#d(&CepIlmKMAQZnH^q?4qEm|jmcAw&lrBz2dOcs z-6uI|2O^Og6W3NjnB6lOsWGYSNzVW?EI;2QHzsBip9y0R zN^OYLm>9%8j@G)RkQxxpjF)4GjglDE%a$_>b;vghPC&-P- z;(lJ>_dP^zOwJ^S0Sj`M80k5XguaQMyWdGSqhV{&Hs6G7LsN^VRBjWxm6A$f9R^2up6Ue8XJ z8> z4yiF&9iEEA+TKBGOrC#Wk_W+%8WX#aI~ZXt-3z3~WNj;F?6tU1ZcM&8E<~s1YPm7l zc&iIOd)X{ECiNG*gvpPTa$~Z}zagsk=N7p!If(l>HS;>TFKJ|LY`l^c_gXOXb#`DM8=F<+SsANAMBjmh=td2qSRRBlYV zXH-hQ)>DBRlT$aFpgHwHG&Ls6jw+%1m@ynRChG1A*l$qAQDbr^qaOP4RzQu(I?GbX zOF0PCnAlWj!ma~eK#fV}i3B*O84lE#s0V~Vk7Y?fjmhto?(n-yuH2ZMIBEx;XUpZr zq_4pMXqwn4Hzv<(-*YJjO1Uw)722Mg+g-Xgq{ighXLX^?>PERS(Ns+lx`mg^jS2Sa zj~TOb<;G<6&FwfOAW3da3>9wJupwM-OeW0?!Jm?Zi`1Abx6i}wHkXkaldA#AxNPkMq{hUcT@+fE#UeE(Z-)BfydIyC8j}O5_IQ4I zvD}zAXiY)IpIW&wIe1J3UnI21jmavnLxS34rQDdTQ2lK6I=xwLO#0sP;5efixiP5; z>I|{x3+2Y-gYN>^dm>eCOv*gYfyq@SHzuR!-vP%>cjU&z{Un1wkI%`CN#f2_Sdz9t zZcNUfD1@nno#nUL>}a*F`1dv0`ZenfEp9$ zHgz!j%VeO&L}gPk6h}#uSER;d>9EgGX5=fabKMfh{*0B*QA7eYCaMP>z;w4{pvEL( z*JaqgKTmEEu5QsQYkkk-HQUOGtMjI#$>Pccp)>k zUT#dly&d8n%tN)ws*h@F|l%ElC#klwT3*9 z88$S$@d5KxGc~bsWB<7Eg0{onD}ZW-~zXB zq{if^Q3$Snn}pPu42^Tc={s}f#^hD^?HKl^Ty9J{J?Mvec8zjlGF0(S_|!|fPf3l5 zsi-D&?W&X;6E3ME_jqKZ+?Y80`oN{_Dwi9RaPI-IsxC)vOvFYzct0dbZcO6b+@V83 znB18B4@vhO*VFgM0i0CYY0ppg$d^#0`@YD`O7=)rNJb)ii%5}%N=T)xLD`@CKF2B} zBMGIHq)19h+sg0W^ZTzyj}QKEKlhyTKJVx2otS?K-rApG#$-kE1K7S`2Qwxcw2Q=w zsx31n4`+UX7|kz&WK7Og{eXbpydW8qb!Xe)V@JB3WK4GLYzMde>zrgvdIU9#`63n| z8IuwBYN1o;a*&KkoMjofx1I#am<%8O99nBHf@Dl4`Q3yz*LxrtleqIyaQE07kc>&s zfrp?v=@T<1D^e!FM=_s7GA2<9ond{cSPK)4$?^+c+(^;EO2#BOzO#I^yoDK)iioqq z&X0A>nDp+UgEh9|c~dkdrJd*Ec)gd*m?Ut17@|j*G5Px;9#~snC>fK1-goiLj$0@hlg?k0aYCnD zl#GdKUI1QtR>q9Ue6^)`&H5WNCXu(ULK7SBj7;?QCPlWc&~Z z?nTIt{~Hs(Z``&gRm_-7TFSwGm$%HAggw~>i=SsRV@H8lJM?wTn2d@nfs*gy3{%mVsMLOiygg3^$(Yn1Xac{i&Vpo2EW|VBh%9YRGA3g+ z+aYdeJ|`KIsXfHc%pL@iF==u93io0>Kr$xv_us+B@=%bB$+p(VU}xEioOrH1Yj$wb_Gh^~_+zNd6=NU65pC$z&nS7HOle5E8aLt@3 zW=yU`-@}4JZ)QxU;2Z4GGM*WemARkL#Gw;2CbDS_=$_!oNyenBSaZnSt|^y{Nu*ed zkQ+n_k}FvIliI^x9mMjESS>M=U$;hmtY*`#uk^^-n;_m?XbJoGezC zC1cX>WE@V>$VbVTOh#XJ{`G$skV6hW<_k{OdLZ4R*V%xh*$USuAI-{bExW3s+I8s5Yu zGh-s$yafXe1~6k{I5HP17cXJP#H_6h7I!vd#$@8`Z*U;*k{}tArRB|V#3)2A8IyTp zZR*~@shng?+%}56lM3~mWK2T#`~X8e0Lhq?B~-z_ExSQ7CNTrw!t;c)AQ_WC!P)T0 z;2KEAWXGv=upIRSBxCZo_bJeRQo@YMrku6FY1A-d5Asb*L8I8djiWOx*I{`*h6XTdM5xEEWuJvWcq+)D7JX4>^j0x#k0S3()%$VdI67vELLIlZ}d{=9Q z4SKt8Nyg-sSks;`_Yfx;6W54V$Q!N%k}IAW=uGH4k!bCV*s2f)*e&-J~EH6X!p%uylJqNXF!np)Yt%t6;_?%-IP% zqw1M4Id7){-;G$@~IH2WRKpVaDY6i5To{n9Pic+*Xdi%1$t2vN|CbgMTk(#w2vc2OM|O zgc*~zlix7#O)4iDldqjy5Jw%glZ;7QP&-!ioGD1gu@Icor<56!{hsbP z#HofElPizZo z#$?MbD<~WBjv15EI8Vr$`j{D$qMR_8@HUeflTIHl!(pumW=y7?dI+~KZ)L_LC$9+J zmfJ965?}TOTzY;KBxCZ~z7b?2hX|4}aTM>$yWV+VCmECH;vM?8hsa6BWY6SgcsHvj zNXEovd@T&0u@WR>a$(ndcx)3S?irTRp5jcI{LZN$8Iy>kH(>I-`yd$;^{wY&!0ZB$ zj7gFFApEue%#2Ce+p+K?tbrL5j~;)xU#e})m_%o~adq+S%$OuM43)3i+ro^AUQmo+ z?ODf+$whU2j0-Af#>C~(eB3`ej~SDW{r@Ix{BK@_IaM639u$fJu>%QYJovA1plQ+97@!Lf)gHJRj&KBn$x9OVfVn6c zlRJSYFml%iW=yV3UyLT{-%4uT)1F=Mjm-8E>i3t`4Y zy-J+nc7F{sCRwvfL8jG@8IvYYu{Xi*fgl-^H_w~I9a61aGA6|n#2Qzc87CQ&17h!u ztNU9{GA5&P8=+#z5Ri$C|ZWAaV;9he)2gJev8X+H+_UKt=6ld`Z($a?+| zBx6#0|1<>sD`LjPU2!XPQmAIeM1P5V%F~DyBxCYoLkli?q>qv@QJh_ey>~7^$(ZbME63s&{wNuftgd;ueo`Vz#>AvZ zz%e$rQ8Ff`8)EU-`+Ss)$*nC%aa&{sGbRt39g%-i&y30T`)YV_cq=m|evtvf46&zI zGA5a7Z*TVZ5_A4VV=^Q6D5p5{J2NH?Yr8`KIhD+q40t#dvY(2*?4mK*_S**>X53-M zgtxc=fBlk}FCBAD;rI{m#@HAoV`BL98|*4h79?ZxzL(fj z@o0-&GA62GZ{Bc|`J7}-Hco1TueD8_WK4RSi+8DCM}cHa%yp_@qy9dSj7hayA?$v2 z4kTmZ9hU{y%&voEOjHh~!B&f>AQ_WYHNnvBU@0>u^?GaIR8S2wCR^tBh3_Alm@#Ql z&*nU)wliarmGjx|M|B%BCT9{Y1T%RfGbTMMi-d!*)y$aKeHnu9-WD@svghX}G%kF^ zjLGCx;kbHECNm~KS7)Hz_S4Lmbnp5Izc_DU#$?2hVjQ{Eni&(WZ#7;WSjI`l<;M?c-Q8Fgy-bZ538wDsC6SMUP@al=r%$S&a+N05<24+m0 z2mcg4c5h?G7nb6$~8j$c)MTZ1FBjNsSqk_228^ zr0j$s858aCt*~pW*G8J`3PC%*v6m~_+~2Zt9Qm@)CKT?F-CzA
>87j7j(UHFmmu8#5+#`ilfh#UIR=RJyeYuWJ8qOm;_)Mvviz z%$OXY`|!e=EM`nD$Rcs&s5E9w+Lv6%+mXS{nA}_N6gRGM`@b?C9I&Z!;yUFa!D#$?RLHhi}1ogf*L*Kv)wEqW+Q#^mvVY79u& zjFK_Ac(E84W`?6=Ow7(d!kpv`l#EHCb|$)x6X$t|#>8X5X(Y>vnK7}?@It34Vz0Sq zOvK4NIO|X&GbW=mN`;0uZOoViJM6uLGbTBs?sD5JYM3!G-`5)s zG?p@BGHc;#SbO;?GbTAbg5h$OnD;9hlTP`mAU_q!j7hsn7VOE|&y30UssiXQjA6!P z;g!#jD9*N&jEPs7xX#~RB1pz0YG518-ZIZlGA6%73ouM2fs>4hjbjTObTu^Kp=jNps{2IP*FYBxB;>EP!RkZIFz~`r->9b9e=kFBz4Vd)Y7cr=u?%!J_=z%$V%Wynw5ICo*G_I6}bPQOB7viQoSMd43Ty zCSTh>ph1EmGbR_5>d?L{fs>30OlUzjLl-;AnD|GE`83^J1j(3$3~j@#53Pb^OjN%$ z;Q6^@P%FDlV zXlh)lnK22UKMdyW7Hz|%o^<<6FHl(d2qj}O<8L_F+Tk})}c=sI+olm(J8A(JB^ z%D50DV{*xKKNJ^!X2!%oaSSB2HZWsSAc8sT5pB$vOuO&QtvJ`tj7j3u74ku&#H_b{ zX0-5VqHwPL8#5-&ErvL}>H{+-seX&FT+HYk7-33_?j1)o5wA6zOz9ERBwQPOff4Wl#I!lj(Ti(KOH4w;`puty&I39WK5s`)_N$&B5Xw_R>7n%%c#8(3xI=6)xlhZ5W1-LXJ=XUP(h5s9qSQUHF&o5xc#9ZS5gx23@#w7Y$B;3B5 z%8beQ57(h@M-Ve6N{^pHyV`1IOl*|jL&d<}%$S5W)PQgJ9YHcCOO2ahMe}R9WK5=r z#?U9cKPMTJ_4#d3G5Z#lkLYdApFK7kc^2>U^uL~UCfNh7U#{N7Ff-UNhhbFFf_f9854bZF_-YEjTsY% z**&;@j$*&fb#XSz)(ZLQnkKQ|LyNAn%@SV3)-Yr8rmhceI8(}uN&HneR2%b@8Ix&u zf^qiP>&%#(Se%COf6g&uQtzFGH@EC##^k?gh4|TNG&3f)e?DW)-DXZQCO5Ridh^2t zoMcSm?c4BjPY=0dOyWd~y0uHPAQ_WRgIaK2rV&cUD8IT-?LlLCKg*n|uKuUwVa-F}Y@W1mE(N%$S_DoQC>i#f*Xq6}s?M zS1eg4_J5pKp@H$f!glewygE~bKI$E3+kI3kGbYm?p5P8v)-z)=e32UHU9DioU#igqtrdusD zCdFR8pnPC6GbU$^Z*xq) z%xYXQs)&<}iTnLV%vvDhBxB+rT6F`rYPn=gIz+?X=UTQP8I$0*Vzy^eUzCi=ghMr= zA6$cyF&VO<6hCW-86%=GxuWzG`^2Q7WK0zPUBhfDK9`~~*?i?3p4(f9k})~;bT4}K ztYXIG%-K;G-R}o8CZ8uY3H4Lkm@#?#WUg>8teqK?wZC@ST{dfB#zf`NMeaNO#*9hq zdSl24{=kgM-)d)Y{h7;*$#vHgu=Jdq855<8Nub>k!;HzCwReDf>%)wR=f_vDf5%j2 zOwO#Tgf)g;nK8Mv_&WsjJt|1X^`{!>pKBx5o* zryd4Om;sV8x#?d4cTXP$$(U$7&Igqfu^<_fKSsCVbCUp)G3nhe5ten&1Id^yPVR~#LDdgC&aZgW8xD!($1<|8#5+WimQd3xCUlS zJBy%R%h1<32McgQuRy*a4}`nAp1B5bxQ8m@z4~eTFrc zS2AOguv|nC@}A6?_ztbbm`K7&#$?RsW_+rfV<#Dt-mBVi_=&-SWK25WZ^L-UazQdC z;Mj=Hdu&iLCi@$|AUAU>O2*_&O%VoHo<_--7+-scDpxa6GA7ZA8MxH)F-pc{SaTQ# zn!RJjq;r=|X#2XF8Iy${tZ-LhBQqvv?iC8zO>NAW%wJ+ExQuIO#$@2adONoVP0X0& z4SC3gt*Bwf#A?brWbh`p09W(krp(VHipPrn|rlZ=TF(hi{=DV$_X zY}H$!sE-Lq#-t+p8#J6*43aTHw-505$_bE+No!UvoU2a)$(RHzmWy+Q?to-WgzGWT zs{a}!W0HKt2W(GNGGj6>dkXZ}{+$_<)r*xO*{78m6aQo%?wVNtoOn8qELu0@me512 ze|F6yW9|nErRnv|m~6^Z$C0jLHdkRTIn^=)@14qL#)MWM#iC-$j7iGtSbSZUz>G;x z8^rC4{h2Y*n4gE2cg<(U#5ArPlLS3xOxpI;;ifOqoMcRf9B#qOcmA`Jj7g!GjicMi zU6724ky0BDc=Sh*jEU~?2JGlJ4kcqUZHSn$)7cv(W73B&z~`aoQ8Fg?x%;RUcLOD3 z;$E48XFQ*wWK6o~1fgZXduB}1I<3U1vuc?!IsC5&Zl5XUb}r2(XDm=Cc5i3KWL>W; zdAPid8Iys&L%9*Qjm(%-J{B{D^1d)*(rwsq$i^aOO!oiW3Sqk*GGk&sGy;y^zs!t@ zTXQCSObTPh#CVmM8MDxn856H*@1V556*DH`E!A*)Vu2tTlU221oypZmkc^4h?>0C% zwb@QGCZS@6()#pAoMcS&t~9|dqy8WnlY90xa1h-=GA8r7mBNdZ5Ri;XTG$i#(?1;~ zW722eHLw_-4U#drWqJ;b%L+j3j1C)Om@%1Jc?bUu^I^th#gy0hS$hgICReUj;+$wDW=u8)eMeu*!<=MH<_EXp zh;z$sNyfxntbf|r2Mdxhd7&$2x*pd+$(YOusmGFJCzOmyxLpOtf-g$OWd5>zv@(xF z$(Te&Qk=X6Q8Fg(5eXP|JP##fvP;z;b)J_qV{+~BJZy-lW5%SoLl;kmv@m0mvMx%< zOKNAv^;4o zNM@Fuhi=g+%$Vd?+<=Go1DP@5lb*q(Ij+o@1j^sT2!|fbn0(n(3qG-OK{6)CT$^E* zHI+-oWP?XL*c`IqBxBMgQ#>n7sN^JLqTZts(!LA_$(S5S`vMX1+dwiVFOC;M;Jyfu zj7jV0hj7XE3P{Fe=7Gx~KmQmcW3tmZ3~YA4W5(or+D3S3^pzQt$(sj*Wv3=)OkU)? z=A0DTnK8+B*XNQ)h#B$=B8kqZU-I)&P0X0I4#*K6ThuUPGT>!@yk1eljLBa2wfN8F z2{R_q zJ~Jkp0(@ceQp$|U>DA)5Xl4R4CiAW!tdjdNW76$j9)ugtW5(ojOF8_Upv#O&_Vqe= zUmGb%#^lk37MNtDFPDr-f|$)%*XF@V#$} zK{6(%3g5u30Z||slN;iU+5^3Bf@Dl07o|X!INw?_CY!bd!pl$ZnK8lm6|g+0mKl@$ zfbOt$Ycn$@EBoByiZ+YSL)Ia3X#7pP8Oh@Q)AkT?+Gi`EY9liy-S2!7o*etajLE?0 z5hyG!V#dU8#&#Utqb_-qcJ9{ItH$>Sw;LcCWSGbX!ACJWDwi4L}8Em6H1YFAs-%#6w39hbS%3E!A8 zQJ8B6nxD#;F=Gd)(Bnh7IMJB+wzfcaXDzXZ z*qOX=t_M|(Ss)pc>Z*^>ugn)DW74` zgNW`QnK7B~HW$3|>zFZ7_Sb>pj2320)IHB}^HbZIF}XES#jdfUl^K)DrcHvTeFHNl zm1jEPA^M3Klj##DplQMzW=uSOd!y=+d(4=0*&2l^dMV797_7dD|9S;7V=~C#IjXfR zXU615w=!Jt+JYIAYnN+rc=8QSGA7*7X6%@gX(t(zp4-KH@12~$j7fAGnsHTvWK1SD z{lK7kwkR2shE-qCsckz-#>8h}5%x4VgOV{>mm}tL;}w*Q$+5Oen5>$6GcrV{+@|OJP#Cc4kb%w`vK?E!&wfY3|mA8?~c}8IzKp z&$zXvUzstvKh_d-kCiZE^7r04m{XI(jEP6sDHwU{Dl;ao&FSJ8@3YL9tggximxH^Q zF{$4C7Th#BW=!@JSHakdT0t@*G;hC;t4&G-^NW76v7KhVJXq=#rgcF4U-paClN0 zT`;B%pH992x!u!f!(0_I!*vrhx2MvG6}sfyY!m4FDwU4+Fd?-Thq;sKsZ{PLBd6Zn zlq>tE(he01;^0;$tX`c;|E8Ofp2-fVG$xgf>TO6$$DBlUqf}~fK$Ga}UB{$`6spu& zfmGct#GlVn=s25dRQk}2yDp|s>p?k~w5TijdN_stJr$28@j67dB!wP0xC2)<8k6xO zL^pA_2g;0PAx;9IMUbo%et5U(fpSEyg4rD7dv;@c!ts7j`X z7Af-(wjUktCR4rgZu~aO0l4B!GELlK%m)sd>9<8!g!RQn{ATw=>JT*)m;BP^4~OBj=%KyRF?!}ZfH!Qk`+`hBV*Da|_yr;jGk z3sbepg*sb^Tb4lMT#bn1$UB_3T>>4k(41HwEgd;sU;KN-IdP72;)IGI5De>_%DZ3j;xOavU`}vJ*xO?@Cn4W9c&W1ekEF z84qGCT@sN4=FWxKIU<(M46cTjm}@v=ODugkK!KlqF91JHkEO9untbZHNm$b-R?Pl2 z(niH7l$L#y8beb@*NS;xGCqG)3@!Wj)vn)m8Nb9N zhHgB%Uig(~!dEp#Q{^AJxTiyx@0}Y>CyZN%6Z@<3n|HH1;QK^p2)>SF&)^ z!xG3`5>2~rsl>~L0<5r$rUz>OVdL3Qu+ojDKBekpz~Ff>vNnpU{}Sh|+5O_uA4Ji# zE@njct1fpnCW`j>ApSr2I11DEMbXx18A;u%j(-xN!M{8Bc|j||MT=_gd)0&v*FGtoTuYUhYB6y%sAT*k#wD(71xn$O7t+2 zYIacsz2*93TWBOrC|L|^mDR~%k4PGbr@^D>FK%#%q`@f^nl(P6W3Nd1A6Eumb$8LN z;~dRe`5VT&oI|gobCfEp@i${vqVJV+v@%|gH|(Z?Z;qd%zP6@(k-~ouiiOW_7sgd{=iuQHm97W zKh!(%BZ5o7{ODPFD6tY=>->b3u4n1NZ&@%-UzHEx#m`@jg82=)e1s75w-TK^xu|;lRp=;PN1X-WDy`ONCgt z934TQo2!tH=FL#FGlC8psY_0XK3aKp1kImqLjG(%%DMd)K_kYAb3Wrzy)6;b3Btvp%ZvfVZpQeeIHOWcWYj|YSX*y?&0@>QD5T8vu zP2;nwF@0e(&g?J#K0gONdvqmFI-jNo9TRZtE*;XjB%Jop*@cOP#-#W4aGJfU7hYAD zk)?s*G-OAZP$Ir7GS-LFXI+=rP1Z3d(;UL-2A$_zWr-ot>=91q+!zg2zFNfKXBaJ1 z@`snRx{y<^!e|?p2_+7-n06_Q7A$=YZ*M-svB$$`ZoSy&5R{A+tHUVQU75ex`ydV+ z6Gm;Xi*w?hTjDsQFnWHzF|W5jURd-al(y!X^VXVAM;^)zrEA4GagiFgxmhWpv}}nv z4=%Pa)F+gtdl>Pa$B)9OC86}Cvo>F-b_o(jgi^XpkslKL5`wyg()w(1-*@0U45~Xt zqeEYSy@?Xv{`eGq^E4H_Yqa?}v8U)@Lmwb7jQEv%PEm!S!(eHkIlpM$DSFB0Dz`*j zJ7x?$MgP4%X&V-2&d<>}MZJ_S3khvT{G6%~y85@3_zZO8SKkexw^R>fm$gc~{7eX) z{U!x3aSh@fe+Z2fa`Cu(KIqK~p^KF3aKOJypz&V_J*A~c=7syh9>oy4#7vtE4zzh34gjjZkZZPAMZ0J zkGk&1lf8oJhVR`-@aZJX`yE72c_@?N@1CMtVGylJZbXY?HQ0JJh9WIpnRRV zj7)zONO$}U;6~I%H4}P`s)`ZX6Ay(;K(LLJx7TvMi9^nH>+iwZwV_7f6jn zKknXKh;Ix6X>O-#SUg+I`TTK`ZmR9fFYq~ukDs2T3L7=~Eq0SJH~u8GF*4+XgFXlz z`%ltYN#dN(okae4(McNDRove-dvoJQoTS0CWc=mZ#*nUklJ41V!moPm31!s*RDY8$ z-$nTXC}joEvF<9oYv+eB<9q-eB=&xXZT$?Fb_LMBmx`gsYw_JNFM!r~-hwYDHN?5G z0W|MNF!b7Oz&9xe&}%+UU^T;x-&1~qss+|_2I352amp-JwQIBcB+e!te&z&SRk2D? z{A$8K+H!&pn685%{q*>*jwk4jGqE4PYo)4y?cUVxMPn`Y!a>pker~T?piO(?; z&e!5NeO)9YxgRG9J%9Vtjma{iR-lUS3;b!?0#j1AX9W(;@TXoydgSQhvpC+*pN?=+ zBNvtL;-r=S)JgXb_McRaGspPT7YZM+VBlZ0H}$9EPu)h@JvCz8>_;Ea2rT?hpN!A- zqq7v3qMg4fiAwULd1I8ZKrSPmhy3V`eItb-Ph~`XnIHA7?$2$!V@ewB#6Rnz0I5gx z$s%1pI&8c%^aORXy7m|~`z_ulF6zL^50BB$e+X>7@Da^okI{AU?;$JV9@_6eMwgZU zf(qkEoV)NC4a`^N3+z_o`k}{Y`aV7W;7v`urh1I7u`uQT?4B<;fAXbzp)!6@yDInn zo-ZBtMaKKzZQ&Hp`_gGW%=nDXbKu~1Upo9h1AbrlDLCfjOY3`R@EWypa2()Ee@*Me zuWWw@-@5qHz>%NCjPZ8h%a79buxx01uflJ^qx7g}G<wT17?NcNlx6h2%{da^mXH^Nx&kgvbq9Zh4n1&}5 zH2L%^M`)pC5W2f{=I5U{LdWLcz^*w}kiF&z)ty*`5Bwj2%>;42hIK0*x*ZEavLkfE z=dNUw-xi>)K6J09E}0r>4qx(osNqNx(kI)G8^K1@@T648H#4*BeSm`;n^jnQaK6m1TRvzhu}M~6AF)jUl9 zmllOb)4P7Ugo6#!$WlU-5hSsA4Ad*eTZH)7zO`sXp#1vhp6p1Kll{T zg?Po6hcK!B0hj8#KV1KJhT;9dS75 zDtObX6GnX0gCk&n^B@(DY4hjir-SmkgY?;1Mc%PN?BTW$XKKu>hY?Nn(4|Op4a4&w zqfC*{IC+4+^-hC`qykv3P%`Nf9&>5prvLb!o3zxL@qYVSN4HRg5WgZAyC_r@PWl{h7S=#YJMmn;RV zvm4<2r@b`GC>Pf#zk-)hduiwH<$Gw4 zUPk0n$pg;QV-KBSYfkju_p*E2dk?j;upm<|MGEsvchkGy%}IM>UrY|(O+C&UllYx` zv3&e)T5GC9`jjQ&@)prDBq|dR+o!lIbr;<^vFeV-H_(t69NbBl9UX_sU(CpU>z#Dlhu6XlJ?VMaK|B2mkb4b~ktuOI zXusqDZk>?{saUXsRvi=FUa1bTR^35WS8RjP30+Aj*-jrv#KDa47F@P@J6+@W80>@I z;tb2}v~}|rSf+3Twad5B!b_cbU57xN7rKr19Hq%u6->buleW=2%?AAG@(LleeJhoP zn(=XIIdYqftu(BQ1^;m3Ue0FiR_f#;<98Vwfr)G@Jr-obo7!)LBY9iI3|?J6V4CPV z4sD^`qE+}@=Lg_uyM>N!Y=co^jq*>u7j2&O4o-%3;(H}|Q5y?6l(}f|(av6U?6nYB zH{XCySNEck-DkliJMkTKXEPmH_Jey^C*vEoZKla~3fy8p8E;^_H$~#tW zqOwG7bam3>3&J%rZGjnw{? zSSJ{3FMMzEpph9eGQmm(cc*wz3r|z>u3{PXTjD_#{^=3R^Jm1o3=f)jSdFZ9xr1Y~ zHc%S+2kSCF;HW(t=-!AASefz%hg)x;e@EZJ7bnz+Wz~9mVDA|`qohx!pIJ|f&o4vs zEvDq>wDmOmb65PGDI>=^t*0ktV+5mo8M!O0qq6Z#!_3-&$HQlfVU=3M{l=ORY8EL)y6eXx;8kLzn)7VTF;n zF5R8>IIqeFO>%C9kBBCL3{hBo@k_^*q*aK{d=5x++= zK5A1Vmpx()?K#4XAGT%|Jgj!3<7XQ1tKNjb>vL{&!dwl0D4qF}*KoV1FL|Nd0|G{}rE|Gkp-+EOXx)f@0S87t|1bMY-^qshx$ zS5i;+KpYp}nP08Hl3wm{11Bu{0t279(t9ayv2n;_FgoH&UDI2zbf;Lmw{xY>FLfo# zX4}BNb_G3BDW31`Eg(2*1=Te-Aw{g=~vEiJO_?-e}oZW)~*S0J`EZ?H0W8C_NW72i&7 z!oO3OQAg9KI3+`w=>1zt_uomx#l3V$@Rg1uitA=PPLc{T$zEyU`xs(wd{tbM`5she|Y zV`n3BdvFfdZ~a`lp|3glZZ+C&SI@cBSzOQa7M~GR-p!#;{+N^9GyCBBK=J1r#zgtc zZoD{l4(;clLss-n#O_VA>7+7cGV;_D?0<1Kjh8p!;Pqb-TxZjq4F&k_r~=6}noZ3@ zuHt`RG|7vnv*@eSC-A+8At~86i?;TjfV&FJ$jG6yXy;*Xg;;SP)BDRzy3y*KeAsXq z`57~lR?qY2_E?*cgn2Wmd!;!zDT_1Lm1okqxm%#Bq$`;xIMF@tW8scjD{6T<(Wyy~ zAknf2fAn*rIptN*`PvP9@_q(Y-rSk@RS81VkQuZ?O_NvJIt}|xm?6&1G~hQ4s}h`A z9mV-FX8il|0(nuoBenl0Q!Ra*ajSBzrN;Y)ZOs8LWv_tSLaew)38l7484zlNW;!EO1*N`iRP)iMd)xv3X z&9+mpc9;RbRdpI2KxRWlZ!_M5PNjpbS~#m}86UA_Dt%p`!uf^B`0W3t(g9Hm1m4t? zSN}MLR&{7%?RGsrDs&1xb6_>D%TeW@O`1ZNa*_D+$uDUAIhod8zlWLr?_u24$@IGL z5yyTYqBEUL9X&g6+`Di{kxiyQ$E%a(--{qC&w(18&?i=U3J`SIfsV;CB`+TK<5t)? z&{fZ5Br?WMi2N~$9=;_b3yvwHUGgM4`KT#bIc+J{IZvW9`s$PY?;}uCV-g*BOO0U0 zZEU$ak>1z;i}TDs;Jcj@Y4(5R=sVyK)(n|Q=X||`_6yZWUF8H?&7DQP4|+uR^aT2M z_zJwS*p$epOrRkFs#ttcMyxx=(?@qE3i7uyvhLP+s+VfYdDfVcWgExSNRtjuF;Ab2 z?lGQPYAt{_7u3n@SL3MD-Y_s;_z(Xa9Y z7rV(DW&ED*-#Kp^dzvxTj9>KB2~LQXq3c!y{-16LoINv!EoSIBEdC6NN7|r-jHZ`9J%H5BD*W2bqv_|*G0~XvP@v{XI>*OfDKpzcee5jWgch@xYPvu4fIp+-=0P z$s=k1J5SMNhcbEn$CkG5NW#yp-N>R0TRI|pAKo}*OafhP=~Acuh@Z^KYXe)_x-nYV zFV;uKy%<4nchj`fn`lmMA00ubnPqXIqm0NpZUhZ3umg8JZL+_1I2~}y7nUn35|`-V z)Z9YMu&ozomdzV3?sM{?GAb8+HHTC8*$vQfJp~oAZRjsAB|hfMAxznBLzRYf<8NKF z!rcBg^w}RH{=&9PLSBhAHA^(-x4yn&TNY|f=Zbs(eFoRK2h*)-_6c)7YUePx^lunF z^u&lCVdn$6SBBBM7215anp8NvdKl%jm3S`W1z4C4qkGnThwmkIu;}$rn!D{Kl&@9f z|MMS8pVp?sbyscvCqI<>tvw1FTa0*}`XTgzo-IT#H|Jl+4xz91P%d1om+f#KLTgp; zj||H-=d*Q&&?>D2A##>6|NWsAwbmbqsp;K#i(OW9z}kc8YM{(#473t2{F8Cw+aJ*S zVKB{k^$eele+@m)4yL`A*P@MCCOFL;OnbU?A$>pj!DNNOv?EZg|9Osvh1Unsy&nz9 z^@Gp25AK8LSbcNy*k_@gN%ui?jHv}#rV=iYxBt=Os^VTRtrrdo5a(s&8J6a})uU?A0-a81mI z&?MnGmUP160PH^9kX+bfNk?T(#D7_4rn&f zZ3SO$+zb=4X3hY5b&MIP57j026$emD@PavdD#Y+se_GTl7M{np;@u7XY1Y4o5RqMk z;eGnkNwcb8!m69-Q__!i4C~BaeHw)2f&J*YVhui5+Y!Hw6@P!(fHyn*RZwm2ON%#{ z@l%Z|G|S5Yu) ze;?YWrpm8V&4w$(`p}`j+acsmC5)}K9SK(=8gJ~XyBjoK@KN}D=AV192pc0?$2 z*EHa{uD$8v1#=-+%Zwj@y=cw;cFw6n#*f|Hi~4NU7W*$`{ASBuwDa$o!dh!n{#jX1 zdUTNn4vEs^SBLbZ$G@z^_`j-r(1f1!+1_*L>G&H`+j`J+wR`B>y$s4TdeDjeKH}dK z6r$XFP`CQOc<=0K@HFc|r)#T|UEzztFSk2A?k2wfu?x)b?oLb7Oi7H}U{2k(JGFlx zBZmKm2@c;aXpg(%xuaYWTN5m3|MRBA_lgT%UuZ#RP1h%fEg~>q)q+l{RU@fgZe#jw z8C??o7bhJn!(H1&vv9W@?AG7M^P|p^q2*gyNY|_&wQ# z`VUp*<-gbBz{MtXxso1#%tw{AO3M$Cx^_$@pG* zwH!apm^Ljnq-!+Nv1tbuyy& zMVoa&^y&eEA^m#dAtZ4s{6J4bY7~0`N*s0heLW1Ra<9#hzTAW_d1XM4nVN#vWEmfK z%z&Q1?!)D%S@3~l4XB=9ro7WlGk$)XKK-3nD)`wL@=>Y!H1^{poEfgkr!3K@k3I&V zlZ68RPFtU@xpNJ1XEkhlq(>iYEkv!oIk5Af9^Dmku55sYR|tWMXT9I2U7B7h;q78m$Am(X2l;ctGrjbe`0WhPysP z>(R<2^p`d@8PLFKN@pIS26dYGX2cxir9Y0sBYQ<+a$b{quDb+j zV$bN$*_!lp}gSd7mXJ>GGrmE9d=gj%Cf+67bSB;i`G2&yq z4ntUm8ZFiC#^1L|g>fs@Xv9<{URCP_JTX$ElYV@M?3s0-kgrPT>gPk;U`4*#SCtAE zE~d$758eVeVbdOT4EyT&O}@qFP2SED`U@ zwNEis4C0*#0_(BX&S0MfLy3n-dYq-rk>bO&NLut6L?QkAw}0a(T}3b+}^(pz1DT2FBd%o!==S&*Q*oVc=t2( z(z}JbuKpu;o5c5bKrl`-`A3?QHTco#GjR3(4s!K`ShITdO*mfpm*gxo<4c_y)k@)Y0RI7)C+A)?Y+(oGO2I zMHb{N`$f7P{0a7hD#iW$PjXSS6ihSz!RawS3AIER{Xm_6m)K77T0$YHTA%Nv)=q}} zmqfGqM2(!aS^_bre-OF7KDp?s1crYa$k1?8Qld1R+u+_nUQ-$Qwd_CPWAS&g zFd?Sy?+{0CMs-*f(EqQ+991a)5xyJUcB|58Dq56NOWTRgVxlycv zG(tvBpJZga+gEaUqb4`Sz>HkUuO^v$+Bkb-0}?*6nj{p>fg{QquPX9latSn#%Eq%5pULA_qVd#-#?{k5lNG;I_(37- zu`=Tm(R#1TdpPOi3;j=|3o+rBC~X!B4^)y;4;e4cfwpUFs37`(Wc--})m;733R34~ z#-9tB4nrP%B;uq_eo;^mOd0Tz&}t2S&ET8xE3lmWnb?^R3M+z~KOe}!eO2&wS1auG z{6Nt95x6O+@I`OSNV7{U%3H;;o08eA)GP#MeU1Qg%_`EzRDM zOpR;Ur2G|z`xO(@q5}NY{mK8>yQ{b?zAt|Cgn$^BfV7?1ip(0jyX$LrcLypdp(3S( zgrsyR!ZT}c1v>#n5l|6C8bliGGkgDT{^$N&obx(fJ?k~EhthfW?Af!|=M8gzF3hqV_C#O&yf7B9*ZmU-jV~AIz%Jf0Z&YNOLqEck$FXNxb=qYU+h&S z_MK&;q01Yx$Egx0$JAo`^O@vItCyIjs!qacUX$XI8#pweBYC;(H5pZS4sXopM*8C` zGSOooE_^0mpL)I`e>;at1@fLA755C%)D%C)a*H8Zp^`zKA0vYAXb%dcaFkJ>?bbD@aGu=_P3rzro!eQTWH=1zGaD zmH6d|4el#^PKw`l5EnEL$EfMgN&i$`@v>f`bTsxE(YH4gU$?1C8fpBDjF+z+4hN!z zbdgaEuv7rm35KFA zJRmbo9tavH#^T) z5W`_w#4dUwJY0W=BnIe^1-&wbz{ixdtu-Jz2ItN1jG|@1BBBV<@lBXWJS z32y8_NMB7ovTnpt{B;-!JnlqVe-FZkITC4SuR%HnKf&FTC6YhC5r@-KT$ZRHYsP0| z$8=?KzlVYph9+Xtvi4+>Lo!)Va0#EQ>yVXIN#xb<8S?zufV^0oM4tElEKxOM(mnMy z33zxeX6Bhfo~gOGP8mK?M(5>u@@f?5AqlGmUo2A6Mx z$(Le?kI+Tj{hu#H*G7}#W18Z|6>roR-4bt*nQb+(u%e4tq<4diQLM+6+uMkyXT!+tzh2m5;V&3a5=vSU?_%bx zd=Qt1lEZ)Uaca>W==?Z@to-^5vvj?nYH$b{a-$7d@nkIwb_*r}dR<9;YYlL34kB$e$lu@M&j#Qf1>yG%dC8p0m8itNI#o3|T2vmK%}B8?KQb8S29Hfd*t?nhz-) z*dQDlt4(^2^dT$8ErOrs?Z`w=Z?aZ!gWo%p$gDqJB-~R0ea;kN;vU(;hzQe7Ek@ihK?<+q^w;jM9I19c{^Q6kKD&l`dmX?{lO*g1})$qK5iqQnAuW@a|+RMjv-3ntiV-I(#q?-HI=fF@xVp-H+>ti{@S; zqeCZSUSoT4SNuitchvSIWWC<^uU6_gI~J_zWT&orvb;daPI* z3Xj%1k-C@aZd zuWvse@I<KRlfy{6} zM+~>wLdoq`WYM~_RXVT@zro8I|>_XPLUh;TZz3y zTWlsL$^IMi-deAbxXtzi*%_!Sw(L%p9xgdfqK?aR{C1m?3q~9xFXU$qYQ_7 z!J^^&Nr%Oma4bnxbkf{M&S}Ph<2x;JRMsBitgwf)&bp$7-)^GR2rzSqp;)?m7uj;~ zv9Q9(SX?)2C)u-SsJU{Jp?Gr84zf|#NBSGqP0atbjXWRN2d@t8B&I*wN-PzpFf>(N z#LHWV()m!dI#>^XH*Y2eWzVp)eip2nxrsbYEXS`SZ$j&y8%cDi3b{D!0_?6{Po^tr zkr{I)gJ04*vgND}`FbQv=x4i@sN~Dz_bhjF^$lytw9dw4Ri_Kmlqsu;&JZIqF2x9+ zYp)_}d+U+nfWxSrzmjaM=|sxL2jQjg6(sAf1~L8p7`;v}CpL1H_Hffu9J_uQ`ID24 zYh9GdK3GZ=%Wq>+@Akw;V+pAUa>kKG+T>}*B4T)L7Unt{5G&t>gd8oBE-D+7cgGfx zG2hb_%QndO#;fL&%X%k-yle9Fjv@2Nh6OrsJ*qQV(=vzrJ+lXTDO!_*_hysE8h`K| zF7MlSpG9IdAA;ok9-EHNB&ohdARSbow0H*bJ*Fg{=-`Ga-KUe{Dec5gMGNs)*;F!R zslzG${& zD+G0#KxS?1A};g223y~cBWI&E#nkrqU`W(hc|7?6Vd{l)Znj87qQ5_aA)65lwE zBHlV659*!9dBIE135ZAcY(4%Ak z`LRu(WbAVgGJp3ci^mudxgVhy>o1Ud3&<5aUy0ckkv@%Zla`pRP>-j6MSs9IJ51;q z5=Va}D~V?^d&BXmade)?Z^#gjKxIiRHI1kTjoJX{d?A+hS1*ElfA7QDVX<;nNd~Mw zQwXK9B~h$)8@wBT!M`KNF3!FcdBrr!~^XUfIl{JJr8eOvFb()N$+|kGxode@ky||+>_T57` z8I`~tjSU*HFhu1kcQjmIxx?NU@42JlZ?OlyEGg%X#?L{faJ+XtcQn2acrAo$$$eFc zvDBt-2O)c43wJcSuTzn}oT}%JhQrh6l2}yE9gTC^1Mq|E2kvMb@!E;;%};?j8oJhQ z82E7T#2k&!FB)*tX9MnN>^H5#fkW1EN8{Q3Pq-)lB6l>} zHNM29%{RECae8Mm-nf{8|LI3l-vEEC$a=#ajURKZv5!d+cQj_3OvkO+-?*budqouk zZZ>g8V?$>PDMij=KD<7PN*?iJE>M!0k6Pcm~f?B$H=6Jrkv%+XMP-vlNDl)0mkIH(4OrBC6GhDJaU z^b)POqp?GtcR!Ev ztEU-*W4QF%Ltu`^)&*Yp?m-MNN5kQ30)Db~2j*y4i%-$*mHfO_b~LiSzekfJ zgJkeMjN;L9d>4};Fh}E!xt!-<+D>4O#!>ASBrDV;=4jaUZo!hNFD2$^sBW*vn6v@h z(a5`Bj;hmkaYv(I^9M9}<;ES2q`OaXW&arNXneB0iAh}^a!2FMZ!a{xn#~=Jy5Glf zSz`%zGzM6kqnCUy`OYMiUP!Hwc3U?ib2M^2CrhiWTDYT;Gr-^cHp=Jatq?l2TY`|# zzKS~==TF|}w5}BhhY3L;wKOh;Iqp@yWINV$2kId1Ko~6LA?^ehh zje^#1;rQ-p$Q%uW=|vEntAfnY=p(NOuGKjyF-IfiZWC-D`E(3(Gy>(Z!YuEKa9DOU zI_JsxJ##y7M`KCeLFjRWxnMz1H_(KziG43n0; z;*Lf_wmp2<@tHds-Axxml4><~G_uEc1ik0-T=8ijRe9+tv_!XXM`Powk}>1bo4BKK z)cmM4r*jQ=G+c_6anp$+?r6-mo{G}!x4;~YrOsBE*ew;9qfy-GhjpIez#NUjtR%c} z^%5{gBl(#8Sx#LC%+au2_X(v7M!+16u;NM_uYOBlj>g!K2DHizHD`{-3X2weg5xFT zXdHHK#`jre5_2>ry{N?rSI2NiV`1-7^z3<@I~s;r*?8!h7k4xkZ+M8-LvM0NV~Ax8 zk|R&KqtSV^I~w%=z#WZsy?5ho&vNc)459#Jx0ObznJnH169CgomR)a7SZz?Jfwkdy34_XlLvWN>gqkb2R$x ziGlJ2FJz9!hxrd7dg*awj>f~s*`WV&3^GTlY0dfvnxjn(?cgmp13 z+|ju8CO`RbdLwr+q9WY)*@`!lz z8Xurww>x(<4$OTDIdL)E(P*c96N(%kaz~?Rs~3!I&gPEB*r;QWIE|aNtau#)`(P8cs6iH<8kLi=}AT8up>=o?Fh@i0SvV%$^8@B+xK2sMyGyKqIU4)+y~QJ{Q-L`ee(pt> zyFnS4qcOU74X!mlEHFpI`CSuw9&Ju$jz&vV3pV9=NzBoRO=(2G`yIKXar@g>IqPvT zcQm5se8xW=9k`>BJNOlLqru$K_%(u{!$-m$jid7V(||j#u>E&eN=Mn_S|WQ7nXdHS z(}id0y`TWFe`EI~pg3ofg#dzi~%n+B#K; z8Cb*}jh+?L;BV0zWRAw6QPv>&ryz4Qo;mtM`*z{T9F23!lR>ljA~HuKqv)ml8Cr|X z(I~(D2}XA_MCNF$=_OlvZQ~{8XuN*h0LOoME10A4L$C}n z1}Pr{=4iP0lLf5xX22Yc)QzP$Xkm%K9F5}ITKpC&2+Ywa@oPrgrZ@$2G&ae7+{!Mu zCFW?%JKun9pBi&V!zaEHw^yv^jz&P2PdLEXnL8Rz-Cp7gtq5d}hU$(aTw$5Y9Sw)$ zey9=n_J59sk`)fXBJOBRT`&c0$JKC0V{M2Mjw@{9j>hJm2c&(nMOX0NiP~S(FnU=zT-Z)&Km7I~vz-t^uXVRou~7vd#bsvt>v4r9B^3|9!)c}g~SG_;IQVr=XKV2(!1S#PwK*XWs} zQQL46yUcL|=4hmvJi|A}JApYG18;sn$-O@?Mf%6 zGs*B^3wJbBOKzJx9%X+6 zNyr?H4ND_n++aUsj)vNuROlCDiOkWkdh-?x8+jp7dzcpKsLe^k!Uw4%Rv1c6uI*WA(A>3SZPw3qXsT&(E(EeoLTa5Z-{UMy-4 z1*%Ql(b)3VRalzP!W|8b6%Jzp{F=C)Z`sj>f%r$=GMbMPQD`k;Q3fsJaH2qai<|!!;rLz#NUU z8)U1wV~oHYjr6hxyxHB^oH-h8F37fX_-u(e8s~R36QAI~r3CKR{2jTinsubRZfptbE2Dje=jUSe5^QI~vM|cHl$9ivKwp zANt{L-+Jz77*BjE%^Kap9gP&PABsCFE!@#qFLV`lE7x;JBPQXEP^4GR9S!}hgQ2a( zd+umh1nvdl`V$-@I~u7=J>WJZV5ID5n4OA+QC6PF9E~mT2x?-EAagVd?Q`Hs-6&*^ z#*&Cq=)UTU#2k%y<2ne98!0hI<4jyLq-7Cv=4d4Bk+TY&6asTJ0yZ_kSLn_ijm(3U zaAU?s?r2OTc~D24xufA1@dDm?M{q~ueu=z(@;#M18rg-u@Ift$I~vk|mXNJp%pDDf zl1Y%TzlJ*+2bTX427Pbhj)uj+UBcI}7Vc;)8eyWaaBJj_#-7D~(oOHL+|f8y-x>YW z3%H|EMVDg!r3_$>hGQ#7G(LvF91Sh^5cKRG1kBNR?Mcyh!g*khMz7VcG4bYnV2*~q zSs|{z+76hb5q!BC4=r~Qn4{6qsR{j0ZXClLjZSi|)U?jl5_2^4T$?c8O^rJm>aO4L zd#jn;(a^p91)EK6xT9e?=MAQ93*e51TIpT9r=#GG#wy_k8aSrmweS0B2aSuUVxG?( zjYCUTW6oK5-{Xe;bU}q4dVFu-j>dfVC~1vz3wJc;jdW1Nu50FwhIYt2Vc&{c?r7LT zjiA_D!W|9oULxpxeuvD_u-|_Q?v8nY%+WB>@qyl^(a0Q)ekX2$d#s$JC_5U0tDNKU zNZwm3I~vaNo`kxd{g62tDdQ@@-%*rtKfn8lUc(GVND<0t1l?r3N=ZNy&(UjTD7hPS(nN@2HwIU2+ABXGHwFEB@= zi`hLiQ?~@>Xy}+{;jiJ7fH@l9P30W9yk7!yG+Z2N&~?amfjJsGTQ%cq^+5{eXf%b$ znPac~CFW?D*fiqI*e=}BpcY@TeD5;uXheh*pu;jp?r1DrnSrO@hj2&ZhZ$mrca%FC zU2_7_9(U|38BamZq4(h;-v~Iq-+(-F^I~pq#Gof3zH^>}~>*s91E8?!4XS9J%iVuLI zx-evpM#OT3JRiS+%+UxC>4d(5l;M?r4<7y@LxIeYm4x z^6NeXNw?r`+8X+-Gzwlmd&V7&!5dsbOZ>I=eydhTfanEpsm znbg7^jn}uT&Brt}b4R0ku)dU%UB?}bQxWf^1@hW!%c)g#@Y^A{)A&7iG~8SE;b&7h zcTaXS&V2L0E=lpg91SO>IE1pRz#I+7xJT&u-(g^mMto@wp0pbY%+Xk0Q;O2&0)aUi zMYHQLL>eqGN8?;-GmcMsqF|23UOC5dzpcCjM0PY*jc>psF+I4Waco4TyuP>z@BLa% zS8d9}6{|0EM`Jv^z&*VqxuY>)>uo%G=pJ`8qm9gr%?_EP@#(>9Xf=NxGDl;g zeIZOUX^YI!xcXRL8(4KoVva`S;3g>4S50P)Mt3z#I*~<4w@mMuR&Vv)6os zE4ybwsLw*Gvh53u%(UT-hFejleC-I}jz;G_cj5F^1$Q(SMTg18Xc~7kJhxqdF3$Pf z(YRIr9~hDfXo)3`15J}^h)L$nVr42}ZkXte%$3u8LD0&_Gbt31c+ zyS4#yH1_WJh%XZQ0CO~EoU6bE&mRcP(b)d39+U5tnKMV@#&p>g?QbM8M}x}ww^RD$ zNX*fQzh8$g7lv|2Bkg7x76$Lh(Hxp;f*74B%XuYZi^r^InbBlvJUHk3c&j>eU1 zS8f-Pq;lg51FH}ckyP}q9W(s$d1OA$jc!1zKzV$aM~FO zN~*rd91R+K58mH7i_Fm&>YD`@o=!mKXk?x!hW-`bCFW>+kZK^qY@@^+jbr-F5E(z& zoH-i4*IOX+MWDbOjYc^qIii;~cQn>d{tBlumUBnrzl8-buGx`08t<#pL1||wcQp1Y zB$&MT4tF%9>4Bit@|rsuk+bX|Ag+)*8mF(#h3wDO+|jtcxed$}o4BKK;o}A2pnP7& zjG07Ne!gLLV^g?9F4f%ws?5RU0{wz z*5vCLxHSxzqcP^40>|iF0On|HGEGPSDgOa;G|CkD7)^A6IU4G@RT!gxLtu`E>YzrP z@P3aub2N_0`PdyimrKmim^!f;%flNa=4cG;Sc`d6#&Ji(;!iQ2-eJKVjUn^iVaFC9 z?r6B%-p7?=@aKWf6AGxD3^3GO#8&JU=jV|ANQr!N5k{K7FcoiuD~3Pvw971-J}YN2f|Nl7}pSSJYnE!@$lJU?I2e`zCkG*-_FmcIA?`aehGlQ#b8Q@|Y! zEz1>Hmy{07(P)_AgsLYcV2(z&_)z@(`?{Q?I)aXIxr0{Cw!j>X?xwPDQ#J>fqwzkw z5G!tI0&_I#e^sONIwyfS8qa1n;p2W?%$TDQAm^7aXyYI;N5g4t6F#$U%^i)FzTYt6 z^=$5FY}EOJU5?vwM`OU5Ol-VxojV$|<_><)mbjzw);J8WY)a>jM#>{6^!<|09gVH- zEAeGh6?Zh|D(m8Kv5`9(9sNQjGoKdjXbe)>sCYM8&eOCQOw-){le3#@xTBHPvq|Wl zTg)8|t?%O?$lx6^N8?z>GjL<(ePoWtz$w?Dm3|a5N5lP0B5XL~f-$nA@$t}e@b9n{ znWORK{zsTPu{SbDV{B>#q`yj)n4_`iSH0{*eN-?g)(WuX4!0CzN0Tyr7o-4*U=bUybOdOwTfj)r}89GqD9m^&Ijm9N5~ zW4YYX`0(FBc>Z4*cQm98!$Id_9d|TN*UGL$PBV8j%%1fYjxKHCj>b=iTt&8e19vpc zex^wOWma%U!#$@Ls(<{*9gUH(TX418b6}3fh?y>E5|jwc(b!iXiR1QO1LkP_?Ry`+ z_niUeXgvFyg+c4a19LPC9~NV3Q2OD5pT<`_H*6($G%SDSqnno#cQmRk)3I}ND0eh$1PQyQ-{FqN*Tm~` z)_Nv)G$w}HV*TGj?r5l+&B1crZ`{%7S=Ac5FK$q4z0heK;~!+)+&IU={m?9jXhnz!XA?li8&fDrx9KbT&7@-My78ITyb6_ zFh^s`pk}z?+bl3gqcXn+dd80Dj>h#{#V}2AhC3QfpJde^!EBF?Vnu+rw{5;!-U}&urZfA8t+36V%5~gU?w{ncY9sM zoTxZpj>glr@u+e83NS~*&Fe8X#2x_VXgmp(J(GxGz#NST3)#;(`d(m;#`!>b{*c~7 zV2;M4f@a)%Dqq1IjUfwKQ2oR`i8&f=8tQSsYj5sosNJlDBi3Ja;f{vs zs^>V;Jc>ISH5(G~$EN$-(HPnD8txeWjyoF3k1gB(W8ec3LrTx&% z9gUq+R!ZvL^4vGL3w0m8&D>yABX=~yriKZ3%d5Df(RYb16uipkj>gM^mGEMAIxoe7_f0=c81cJvP9dq~{T_~H@@LFwt-(Xi|71it14Fv&!VI*eEWrNiaxLS}oq z=%O|lt#0IwMoM6iFgrkgzB|4>?X`54xl{LM?r3atS}(ajso{>s8lCUb?@Ptp(a_sG z0S79wfH@jv>(8R)t9!EJ-j=q@y@r!qB7r#?PyQxi+`G%b9F10Ao}+5wW?+tnuVEf; zOz#QI(ePKQ#7^0F1m(`pLZ-3l4Ed!(c=%UOaG>I~q}K9^;Dn@!Zj9voj7|GaqwDqh-j_I_FyVJ3TUZA=0Fp7G%gj{35(_P(s_syEt~r~Y3b-D?r6-i zy(krBRdYu}GpP-h`xSCWqojN;_WS%An4_WCYlmuM?f`Q%Vzvch%B)aej>h=65Gja8!0Q#xD4ZZF>g_%+Ywis}V)DLNVY` zGj}xZwKo-ptf=FT#!u&bp>L})?r1a^kA!0?x!lpv_;CmpzIuer(U^GWDwy<*L*{5? zy2QgP{VT{Ejic?JK+MYh$Q+H1t=>ahaVRoJ*Fa*9hGtDO zbX!+x&K!;5Q(NRQ`=P)bjlXI2@L8oVcQk4aRKT62ZQRkYTlx_OjB@3U#;NjWu=QRP zcQlrKx&^`S?{i1vQ`OjW*5P(J-;zDjd36!ySzyn!kj(lZ&~d5&d!^j9!|B%+ZL7 zJqHad?jdtDEcf|BYxPKEjz*}}ZSXR`jLgxXi(f#-icQEIjmo3)df}QL$Q+G56Dz?; zW=fc&v2J<;xadDpFh|2ic4lK*4;7fB@rpLX^fsRb=4gzaR0oQzk=)UEQBVpSLJo6B z<7Q?Kyw~*Pjz;d4MNju4=J;p891TBfSN!683z(zvS}j_h3-|zYG#2SRz;@}UfH@j=kKW-vM-iB#q4r-1 zMrzdxcVtIn^z2$(vv7gH9F1=OHRF~7TLp78`n$B?vOAFyb2O?{8nMbsk2@Oam#Z+Z zW)*idMl8%nz4sTmqmgtY4Rbr);EskbDA42KUG8Y8x&&a{5V;R1>K<9X+6J5bzi>yx zbLUK)WBrXg8f$;4p{i38cQowFtff8jdHHKe3i(fY#+aviP2ABCEH4WN0oB~m7&*8d zRLI#(T|Mp)GJifepLmVT(MafY9w<^|j>fm+ag<%rw|x}M(Z~*M0gbae1m5%p zs&h~9f$~0Jj>fxe0|I{Z|mEigwz`qPZ5lbaRH(Fih^ z-K||uB<5(Wxlxbxhx>6yW9HBbROz&XI~oq(KVZu%SMF%6Jn;;>&yMDf#`@K_uxQZ( z?r5|$cw2nH;&y;XSBj*iZ>c(2`Xl(ZQCaG<1=8ne0rE{gqi}D;}R4DOD zb21m}8qhO1guH=h!SSH{{I6{YQ5&ldZTjSMN5kj(YA`vNhRo3zH}E1v{76RTXiQ#t z1FWY9AagXDl~W+NwGA>yLvzy`7?d;vnWM4s@fVmfQ4N`+ao+bE*zU5Dn4{r$wFyc` z9vj0PjR*2`PSZaw0&_H;w{3!$vUc3jIA>E0^-2r4qhZ#&5H4&!&mE1fQ(wc@i9ztE z@ESQ{K|%iK;f}_Q!y&LLG=n=DH3bgvx1fMK8Uyw(g>_+HxudZ=urmztZsd-}!$@D@ z?u{1iXk;ttn-6V}=fod9NyEwA5^j;#J!W{4ZomFW?VF0Yqw!?)WW4|FEigx8{aH&? z$xj95Xq;E|!~af40CO}3sV1S3k25ewL*@PpZ1r;kFh}E7dLG)9n*eh(!p~J=Lt(PO z91ZJT4Y(d8bLMD-?Q6lie@02n(TIs^MsKAei8&gjUF)!V@@Vd8gnO6bm6jvi(Rg|& z2k!)Va!13j`y+g|B7r*^;cH^?tn`FC8j2Af=-~36I~tvq@5O@t<=oLY+;uRXX;aS~ zjf^&Lq+GQY?r6kRbe4if$ou`eULXfY|2EHbujh`&=+dXcIIRlqXsk5t4>>PBa7Ux! z&JOUO@C=!w0VZznNbeRhM`NLLG;E9TM&@X&yYv7aSe!)WXoU33hQ7vt%+Ux6Dv_Tl zRZGm#=yOue-Ie=wnWK@mrx|(^7jx!lI61b!3`LB<9F47?8=$qEMXYIWLrj)b!Kj66 zxTBHs{S(YOb&)$7yCDsn{cmtbBLI_O(u5T5Xq5c&hiO;da7QEewl&=N`h`0h*Hvb~ zwWM#{(dcH|3OWZjaYsWr_ngoq?+Z!1VnNCh-IBw8H*!bA(85i+Bj;uL&N@Z3L)znp zpP#v-(dO0ywCL~}n4>ZO_Id0&o&s|;QXGP?gK3Do@9ikbe1-Dfeg`>w@d&y5J_CQ; zSpv+_xZmb8T90ckuh<=fWJjY>&e|Ol zxd)k}p_lR=6l+Y8IT}T?%i*E(Yl%4;ZA|LnYE1`;IT~5*T40EWvcMdTv!*Q&zWKSp z9F3lq^$=1dpO;S;6RofE9=}~Xxuc=s{{c4bb>oi46ZL1XIWw9&8ag>QlUzp0`_EcUC(UsNxH$b2cQhjYu0bEwG+>U#xaV?z@u_5Bj>es$8#v^a zKX6CGA_ZGESp#!4Ha>lW4fCf1b2OfJEy7PvRDn4f7hZkCpC2s*=4fn+YeKt4k;%-_ zP>XND)<4`O=4h<>)`)x7YjH>8-JEJv+PaWC8rw5J<9Bs??r1!I{|bM<3gV82?_Yv< zIuPz?tSJgcwT`d2qj7b-18yGmnL8Tc?Uo?sf8~yb-JnjmG`W#G8r|c(B@=mnVfnow z1Xrsly5}`2V+9$99w2ix2EXuz zcOT-oks-f=wcBHEWLTH#k(6(f`0`pU7+5YgK6SGmF>voS$I& z_ZnVLS>uPfbCe0|g^3Q|j@>7!^SWzNH#{-7HLtJlx-89Jufgjcn!4s%+f{izDl|b@ z`%K=`Ab+iSKyT>Qw)lVFbKGvZr}HJR*T#D=`=i&>&I$D7glg;-6(X>@bEItF4etr8 zKBiWHy9e#%wO?>LhFf{@dP|#RG|s-w>+|2dacE*1ua|8*fL%7`^LqTvJ{Y~Mg4Y9E zMN2;8s(F3!%f95NKmK=o{{lZ@Sy%x-J~74^US5{-VCA3txN0Xn0|l?QcJhQDtFH0- z_w__L>35jdcK2Sw$6*6_Jw*Bhj;n6*-{13hIYfW19>c!RuQAmyzxIm6>hu|v@a&2% zvbyBcXE1HMf!Fm@GhxsWS6&}1l{5BN$MSmqnjjc_U$(B<*RHhz|J%8|E_Rv(vl2>p z{a3eI=(_4FuOIjABTTmXU%h3gj&!e2DL=0MwL}_ny$Xp3^^L$~Zs%x19f3f&ZtyqC8yAOP3uMwX#Qo z`ZgV2PdPCK{*<)i^^mKV!8!jgu=g03N-!!UpV#bFX`lpgbE2u;`ahs>bcUR*(RACK zwxVj-B)Di9O;>*FBDPxoP;j~yO)HDLiOUa6HuFe|re;6nEWTT*Qi|Lsl{-{d{C``o z*8lmtB~F-vxnHAcWc!ZdV{I1{+QiTzO*Jt=8}V-67#iqN1=p)&Q)*%iwdnd14&~LO z`pOu3AW6=yS8hc-_se}!W^$IxskUU6eGFX~G9JqNbR-4=F?62%jH1u$PDC>~hHe;> zWj^a*N76MThVJ>WQ99kT9T`^|LsL7qK{pjOa{g}&ZF5+D7PGDiYjk6&(l-}*j+uw7 zH?48*P1LMR!C|vv=}xB%3>f2&8k=Hizg}gy(c=&*pN^&P1Aof7kG;^yBbItTZAHuv zg-EMnVrj{p)@0p_oo0&1u{8XoCb>7`hA^femR|d=PSiDfL+ow-ZyLwpKlLOiWV@r2e8C+FkD(~cKz0{QDIue-+66U(2$|9LKjjx4{; zjt9$YX;lgzfz_qajgUW0kH6o^y9$hUZsc|9&Ak8H=l$RKmO%f%I==m%=fM9{W8FWa z>Yq{dxmRQ)rm{ux#OjH-V|)jy-^pHcPCsQPDA{WGfm8CCy`s((h+KcniOQT5NL z`e#)AGpha>RsW2te@4|mqw1eg_0OpKXH@+&s{R>O|BR}CM%6!~>Yq{dxmRQ)rm z{ux#OjH-V|)jy-^pHcPCsQPDA{WGfm8CCy`s{el)RjlWV_1VciScLUlv0CoIBCO|% z)p8FOVLex@mV2;}^<1%9e#Hsfltl+MxqmACHeBebCFZ}6qN_ukl>F#6Fpkbm&9bJ~-M4m!c!-_rp(c`L1kGcZ{Tq+)HslP9kjC5=ot@GP$nn z3~J*e>FXKo$<)I$p{;Ht{qswk{M9ZL!fGO@!qb4%**-G={vv|9wK67K-dji~!XxOz zl}1GAj4qa2N6;0Hdc;3qFB+|hpsSrblZD3vaPsH~s_fdDytR6WwjCm zmEqK($9uF4RwDbJgwq`j$@q4AJ2EgZoEqD?V$)h}GW=9HU3q5#dW|z6iA%z1R+n0- z<2NIcJtUmQhbT!V=Z(nDw&C>0+jYX1pL#^4w>laMZP4euCfVS1 zgOXmpklF7Co|Vlbu)hb#GCpF0Y#x2tUkItK2_7AIgZ6Is7lNxiaDJ;BG{m~CI9zE3 z{+Aa`ynuEr9&hS8ii^8Z8DL}B^9Fd7?UBo1_M4SKV}=*1oS z;?$|@VPDTMn$_4v^n2z7mOn%3%wuiDxwd!VOjaoUa^x2*d7BSs6GCa*Bl&Ri=`T2b zNv^f;!UC^0;(_g&ttN)jt>QWeJFYM0>V?uAOAYvZQ}*Q>La4XHSmA{1 zxQ%}uLjCi4N((de#lg`bbi1B1>IZfeuiAys5p7oD%8hNspmia%_s%QmEd2pX^AI}d zq-$;FX&06ry zBAC8wt53SxuM(VB1k-*OjmX#PR#MMV!PKVGhCj;YWVdW=+${^DvD3B5 zSrs>YbT5cbpV5wd->Sg#*MjKVQ%c0b_B|RM52B7?MVQdP1rIF=qD@^N;)%r8ByMmJ zb^q;;h2fn^rg{(^>b(bh_~?<=1%Whfw+;rbHzMaSklwv;LV72=e#)MKw3AM{dH)Lr zWZt1bnmD#da4gX#MRNk_s&lhIwSRk3(L0dlUU3Fn4`p)s&vlwR`!*DeF2#o2>(oCz z8_-Oc>N_W*jTv$6PI%o0{+1yHfTK-@EQGHAvH&|pg)aci#&(9t1)o>SG5 z-MO3KyD@;?k5Ca^I%L7?u>o}LUD=4)Q4eeM0%))LXOKnJ#gck|y2~vTVof`Vz0&;Y z&Nrt(H?*5LDa@a?Oz#6d8V$w0mj2Xcp^tD(b{^x`_|vC11}k8>mqgj)X;c-XANtYlzhg0TLY18L>_>Oa$i%5xFJX>_A3gJ{ z1~+HQ4%Bi#dS6l_I<=NCcbFfYx2+?&6=Mn;HT~$59^J@*6%oR&FTT_;*^u1(y(-x< z#h1R7?ak~F$m&qa118(u`=-G08*=W#1C z{a6Nisrb^4at2XH$7(dozecacW?)@HE7Aq8(IIW4@q|wYa>V@_-F?^=uY2hd>pj=# z_zt5`JZwmIPrpW8*D54G`Df4Vd5zvIK9}5!8j`JleB|ubaABxvH*zq?hbHNpLfO%d zO&{^zJ&JYGSOhN51ph{1%YGZu#b@sJr=4e zTGrU3Z<99_pJ|DvyG0Dm@TOs!x?=IBC(?lkZ+dcoq4=`IOkrr}OTvu=UQS2n1TNDaaU%lwPSL)&c=@}e)>O}{8)x(5~ zsa+dE+2(D`{KKRdz_TF&;3XbTA&qjDrt$ULpE7w3g(awv` z+V)P)STz=FOFe03YftlC!;Qq%4?XD%6DO&ysh$|??@1rdFv9u2I*B>QJ?ZhmhcP%^ zLsVbnNt-o;@aE4(*g8nA(;j1Xs~pJD@T6l@OYw`tZJ6}sDt&QQne=_{3}y5xy{prn z9Pc=iAz>TnUp?Yct$Nbm9C z79}!!`W3n@Sb;vH+mZI&uh3=F-B2C0iS~C7`g7$X%=lY(yqHdC&tRRtmej>XX7P9yDsR7Fh4;LI#eP>-;ScLo~@GT@QL`o7{sQ`2$zh zx>Jk1RLI+!hgNCsH2dRc_7PJ)y`>e#VYuu@lM^~{= ztTKj-cBdDf=!+wU_mM7lbf@jpj6|zZAeer2qhYs=#A#LP(DKBMJ~^i^7DcUv#er^g zm|<73Ra-CEbjpn;M79x0&K+2})Qu`P{erg>@?qXEH@c&B0qmRc3l_I?qbF1ELdNDc z;^Goldaj)}%r5I9Zb@;afp6Bs;tl$u!poJ$_0xpckw)T)!>*JJm?8{(XC!u6=t^zI z8%pDf^~H9BT zww*H#8@vxkSn84TbypdcZE$j$1Fg;OKy0+-TJOao=V` zGUJgwt%xJis~*P0Akdx`o=r@i^xTk4IAc#g=7tCXv$~NbE9|MsiGk2Js3X}m%${z2 zatrbb>A2v3@G-dtx9iyI@Oca;~7K zWh_3}W=p3DA?9^sjl_{tY^iVBd8uf+o_N{FmKp{dph4fxB5ksvJA4kJv3hHQ3JYZ5g40h+b9rr{st%-YXi(6Zc$Dlh(kulp#Geveo! z$yQi9QsZw$Cu_K4y0$iHIc`O#G%UuCT@1*^T~y|mQJi0Eiq z(a|o8gh*3;a{r4ZU3#Y-WV?4E?eAF9A7)mh{xD&yc=}qG^9i+R*L~Xz#g-omDJpm_b|d>Bv<$A?X}Fzptxku}l@!cb=n= zpf8ra8YDe6K1Y8%G7^j2M+&MrXX&y#M&j6MY7lqnELB|97rS>^1G^`lrBf$&6%FTl zf@qy_b*cNt%CLQ|?pCkV-s?Iwqir(wv^s4j@i;BHBR5r<4us1BI2==aE z@4bPF2#R6>3y1|3QKSfLau);y6}zYi7A#mmMUkQ)=sOdC`KyPB&keBY;BTegXDdwgHbD53arFER zV|+JlJ-q!CMvtfdMT-}%7tYh9)TZY zDGb@iqw~>g_jOQdV#$mLSfFXuYhiGaJ&U`25H zWwrfUXyNV1_Joe426xwhFy9$P0PIB9p;K)p0uY^-aU&?2G_SgM{y^G-lHWt^`jr z;S5z%Ef)4`1!R0mLR-gwqTSBXyQ z!2RX$BitP8v}i_eZ(9y|pY5>2xBbcyJ(ojAYZ;zzv(&A=d>I(nIpcNV_v9`y%b-@< z3Gb`ujUv65K}D7go^otAiZfmYuV$Lyj$## zv=pMyZS;JY9v<;-33SswhfX~)!%q$^fr!dYDBaHv8w^mR8hqn&W)g^S@=ScWoroUkTtvKZEf_oDGVP4VxCi{Mq$oiwtm4t^N0 z2o4^+M7wx@MJZ?zL>WG$Z|v@&Z`N6{oVgCMZdX=pA1Mv*;+K?+s*KU5$?}!sSDDOhse(;6! zuWgxO^maNt+!vg6&DgMMv9xxWFT`VA7UX)5?$Ypu&ce5ngFxR{^ z)%uwe>-K9NOxP7I&z)<>7R1eiAy3*M=X+-C*wlI8=(ZUd_tRso&F4Xe%Q=+P=Lemh zI~Pt&xQ%jYKHartF5t>C#7bl)D=hGbc<7*=NmQo*u0S-Me9d;f(Nh9=sq7GxH!&*`YUf2nTZWN_1u3 zRn)}88z8s=dAC18OEtYA_oETkygP~NB~OH$Ay)WGy$-!TcOslTDy-|5byKczng~(p zGJLtRgZ%OnFM#VZY!a!B7VYtZX_p-EuXR4CTW>G0m~VyO2OmZwzE6N03u7!C#fO~E zOaP6a4QQS9D^xIP0(9!~23_v|8<|>75Y8aGhRo{>ar>L&At>-D+I!RzPgp-5K4{HC zx4SstZym_F<*f{_J2nndHBFVs%n|P&GY)9eutZ5`-h7AFHuD7Ch0m$VDjOLTjfK%ae$m0j zCy?*nvBKH4hHOq9&DNz#`LL`1b2!dF%6IV89X?({_EEhGvX` z>N;U9F|<^9#dZvIUgXHEtA^8id81)cf;GFK+DD&n91Z0!8nMM*DYRFY(a^r9ChMe1r5S?bnk}O(Aua`P%V5%{ivw{J2P$+%;_9W`*gHmwR)q#ef%=Idbm9sr}TiI zK901cw~U!A_JAV1Q@OpdGplIj0V6iXxb?a2$ZowH36q8v$>)x=VGjF8f^W|&7Wriu%n{a^#|GV& zKR-PT7Favsc4HN2me(+dduM|yo(7^7hQpxk0TbNP^a@%CL!tdNZQRu@A01gf6k_Io zMn?B4P$xa+aR#;eLxNAJ#?&MAhekBjgF{^MQ-N?!f<0@ZXf86zIqRY zt%>WoB+&ebmOUkm&1HdlEiA5jj zM8Cf44-fv>GWViw)Z%b|(C=o(QqNzYX+!$Mn^n3@FYGSu_QxF(eZJE>C12=*RCm}E z@{mr`&|y;-xdUl;nGP{CWs0Wmu;BVmx&+y>F^~Ge?g}^h)7^>H@8}2f$7LyJH*sdG z75$*u6O*))@159(>b{Wg8Yw^RZ^t^s_665&tx}p?f;*lRsw)7}Z3EOK&tm^Oq{%gqA&? zcwiMuc2PhxFvoLRo<+5^LC+cAzlp#mGTp7UrwrfN zhG28st;)0w_V{E^1f9L@=!dlySg%wLmCF}XpOpr9>@hivDvY8v!9UTfQF2&Rc%7bm zScr}q$l>eg_w+`1DvHl=gPzwl*xx4mQL`1oxkcL=F})8SsB=p^vIJg&d+$LkIKA6$``kqi(ZqN1&n@1;V+aCBV+2B7>*@XH-5~#EI`V8)Okag{gZs^1 zqd`nXuMh7A4viYnsInvU(%-IdF3AW#oil~rP3Q{XVui1r)}z~JcLnC}fRC8VmCg=b zp*}^1-+Q)_Pt5NE&u`1HszwvF-`xdN*$#N|>xrlqcY*K_D?I(~A!J_O8I}$b_8jsV z%8%|0uUG#;$F{sgtGzozMD`ohHM0(7n|B7UYuC`@>xTGSPA9M#bPNq#VTqmBc7m@F zvr&Yd1CDRk2?jcvpf8~^TvOZ;`k8vkLqExIvxtshI@>@wtfeFN7}XJaRaYsWbhpNX zwK~F%s4=vrLnG{!+yNHPJ3t$}HE{8~4lpG%jZXF{LH12LfX(9~>ZHm>te`z;3*RoD zek>Ao2yPE`4-D9$96z+AcYElVZoy{mvqrDKw}S)c?AcJuRr052+kwR#8H;Opoc4NZ zI|%+OW4^!MEB&n7LB&=_HrQ(zJ#@1z_&l~|Yk%*hC)c-yktV|YeeNo)=-3uIuhe8i zn>?d8O4`8svJX^gQA1--w1HI#xwQQ=eKvP&8_+C^rkk}bSf)-JnDc2ljqPI3Y*Jgp z`M*wdL3bI;@M{fvdv`0JnK`pVEm}k5@Cdi0r;g13c`Nw#^QpYa5*zk zHD+J>wt~yM_Xy)siy2n6gyuUEQO=4|x;eHb44v@=^*?co9+=eu-)P__d&;H?@FwNp`p*EL@q;wFP|sEv)f0IbFk8IXu_;`i;7U&)FvWp)o50jV z0kr6x4j#F+35;wPM_rbcBjcV;z&h_f&GxyE27Pmenuq079(NJdoNfS zsJa8a^2Q0`o$MH~+(rw-oZ!+_Gj^-uJY6%$37*C4GRulPwD`9p6qJ0Yf4#m?i>r>H z5Y7>!*R`3GpCjygb(to-F=0B+ju5hY7hUII%WNJv0Ns!1$Zk$7+229fJIhh#$efui zc7WIxZPVWVaAHR*?P1*8qjI;CcI?|Zdw9FIC30_R&f59dgSBv0r+tzhJJ(3iiD%K@ z(Urm(rgkvcG!L<=$Mng1J9zN46iqTrq`0dcbV}C3Pc-+?F(tN;YHWhXf9gl49=3(4 zJ8f{+*vHE3p|;@l&Jj;;5t?>Q!xsJu`(J&9bNGUlHZZ8Y42Ly$M(q~czf~_m}q77fH@rB7&;O{mRZQARIi%hMc-NkqE16s~_Wv(U6dUV_E@e~P>>S_sJlWgeQXbXJzg9Yq+wU9bqG{9C77LYBRH~r207YZF|0oS@- zr#`+#NTFu|TQf>%?cg*tUu6!5cWAJwZ}y{)OU>ckDB-zd+h|ndVh+znShGXtf5>Z| zn1QOhqY$IemUjy_gVkSTY*_3hrT0KHI1nUb)BBpzusTyXrSHH<@*LXak|`8;S+Whc zj?ppGOhFlC$OZ^!*6y-2g=ur^Xhz$&^zCgE7-{>G&b|MKuJkv7b(0uv?Q6_B^)i9J zLk`gm=d9R((#BAl?M3bK9hm*`#&G9>20i^i*oz(07;0!UWk7-uJ2P$!doC*EaVs3y zwQG&Q=axR|U|_|Tu4n|l+omGVeMW45%SLczaX1Q1tfxB)jbTl)eJMfUqzlQoh+59Mjut)9fzhQuX)CWN zRK8mWW*s$PgM1dDo{(692Kmm@+7Rv|+{16)NZT=4IFm@* znT4Ett88Vd4GRuBG8a08PRi8+^PfWAh1*^_cdZsI?9-TSs!667+iSt^1WooLpn&?l z)r3>)Khl1|)pXJ^P1xgggKj>l&svYxgdt~6(ba|KEKo}mEH|vAhpdHXo@5PZamJaR zZ7pNV7HGhr*TKqx7l zU;|Cw|C?#rnd26wt!S&7I=20Y9rpWhOnGx^9eYvkgahrGxn1eyWaK!YCOgaPjIegO-FA-2QBUJ+3i(q;;N1aU2(!0WtGh8 zYpmR&xikLbQ^_X0Xp`!=)d|Ps{a|&+uPVDF+Tz*Wez46~yHU4mra0B+Y` z*rxtFJGt^A4XrOne)GPw^KI`_li&Bzo5F9x-g7z4n-PcR5B$cS9MWN>4+GH8*m8C@ zz?6-7>WbQ#ma_-DZJBSSQht5)S4RDuSSP)RUY$OCVFQGF$Lhl|%5xLGu+l6i_H%4| z`YHW08;I;!&G4SXGhH>Ol!fFy zqAvoqS;E6lY}J8yT99bM4)yxP7JCFzd7TYQIrfo7cO}%jnG<`a^-+jL-c%MlIVWjp9 zvMQ{kPdC3~zkF{Y`#ZZ zdBdL0w!taC3zT(xUo)GBj@WVBiL{&b#X@|<8S4cF$~P=7W>r0fnAH|1^sL|&D{-^O zZ5Ay@JIO0H%*+DUUWrEX=$EWzsqoyfITxKZddaQ}XTW-YlL>;}y!e@%DJY>}PC)i8YPLv%u|c6)+g;N2A^t;JA(j?A?q=>Mxu(w&UH1GuX2%kGvnCC>uYSU=4bouCPaQxLUp{6*vPNu-Y%E&a?=j15Bjm>X zs+P|=m(Sif3wc%xjO0m{`Rwio8T+6=UfFo(BX&7V#+n>$Ok=)3Wcp1V*cRDrdT0DY zHhPOCYu)G=Z9^Y0mnVj7T<|rz+T{UjQCdfX55J*WVfWd_OE2kzQGckH)_u0!0BCGa zV^*@@9;?$oOj~WYVm9~gvXm*_v>Y7RrS5lGkF{F#>Ma=?6m^F!^J$~>QOX!Izr(0e zFL`#51N*b_Hk<9Dhvsy$VvFDAv7%3tQB<}OyErJ1Rm2}b8@e~pRhMtEP@&+usOZpQd8>N zQ12MV+-Coz;T9*+3{%GT%`#wt<%?1M3d%+;6yipOcIf&uB}-jl&lYvuCiin!vd5!j zEaD(d8=suU-s?NF9TSR`Sm1qVO9?D~+yl8X!G=At zN?-@``XHlWCahxZ74}Ut2zhC1Gp*uy;eVTeVnfSl`0#jE+4?c+`aX}oR9$8)QaB^{ zR1EFe<}y>w*TZLAHc|JGOKj5@GdwG?HI1u?V+HH&@MpIuWoMr_7VyRif4`;YrhWS& zdm`*t&mWyB*FzVX<`5^`eYqQ&9UaSB53t1+fjd!%ZY*2xY>M?OFQI{c7ubFa9b7c| zA!=T5p4~DP;znJ*qXR?Fv(?w{BFEXf_(1YGcKG!L;Vj#}d`rsAeNNaSSJ;6cmZ-e(z!rb$c!pJ4cBQ+& zn&OTJPO}2xe4!39T^#oF6g!e0OQUyvLzy#Au{(kHXz9@hsK=9Nwu649e{C+IlD^R_ z%SVT$9NB>aVotKO38oCK>4}nzPO?y6TSf<}v0Iaz*w{mNdo6ks$tDQ<)!+M{ zR+^2CWF-%Tz49w<>0)|<9q_VaB?epQJ?9gweX1FIz5N{h;(wf3HP>S$7jM($<;R%r zuL?Rr@tNjMKgJf#&!;&fv{}2mN14u`E0p@1FqiH}nUUpgnowxN`W}g3_@RP2nK`kc zf5KV7usg~mduNusFr3}GGbJskk&OL)d4w%d9FzwXL}!HJ&+cD5g1G% zBaF?t*cdlzIgsWz4`cfMZLsag=gP%F2iTr;N8DvcY?|4x{cK4i;aRZP4*AOk`{H|~*vUUq)HF68=UUL$`@qKK2Qv+OGkc0H~_A#1SgP`LF6t`wC z>;LH)YTH~BA9x?a`iG>T8+RMwF(X1){jYr}JjNRPUI}LXmXAO-^BnO>n_w0(qD;P} zR))9w?_tM!e{dVOT$r<}gIMSJ3zhe8+T)yQLG0OlOKMbUfzz(zM9fFJH^pqd6YRdD{Zmw&OCETxm>Oe(`56 zZVqhX&Y5)57=Pv;W68FA9HsGBx3iH(My&o#1}&CtXWRUKQ$y`HwBO!stY`mM^uhfG zdc9#QYjqXq7cFD9XwFtP@5W&oG}(#`4%@<9e)`b$F%E3Z)Xi)|6CGhaC}TZ(Y+{q^ zIw?O~lQ9>EjclZE7y15Z2Uh)kJsYw?N62HcVn5kB_F>c{6#LVN%?((~-hDre8j^&z zJlC+`A`s5VdQD$MmR2 zM&ZUnp2srgsc^vCt4AmUM=WJCBW1YX8VmWDu1i=@v9OlVsFMd7E@lq8j(D&6IOO_d zA=_GSg|$M$(8d#f>`SpR{+*{pAN_n;edS-|&Yq*GLl>~h4e!wCUbSdl`}u4iWT8{d z4RLY(T=r<=36%TW0^iG-!~7>NKtt}?W4doPo7C76ZCokCe`n2N2Y>p?m;aJspCL2Z zUZ>Ku^qG#>z-0!zpz~Q-8EK9E%BL}Qdj!?VZiG*yOl2m`LustFCT<-tg)K@-p`OB7 zr+U*TvoOO#nw6A;`uCs2;8hJxxqA}jS^Ka}9SqpS?ZSV%cq04hF5EjdJD`yBUTl)L zu(!1(Kpwtf0=qdt#=g(Elt!kFXXlKanWydxT6g6Uk8D^*(?M)v``&2XIulm^X#hK?*o~6=XtS#1{_OL@D=6IgGrbq$&Q1j7 zqkzEMblLKL?1uFZ^w;McT{yTe+tFDM4@lfhPnq{&N!QHqobhexoFWB#H^mMw*>g(S z=^|lo^PTXI`e(g%3TF@53wsV7|ET1pzK9K*=!Bym_C!T;Im?)3iw|e*Ks~kGm~wljC2}wX@$){%%)RIOiTJXse5xOz+N2j>MvIKTYxb zcHLOc%k5}-fi0e2*@aC|c0uP42=|Wc&dlUMf_$EE@A!JE6Kg!RMbBxGPPl%1M`rQs zveNpSEiN6~fwfrPnI3j9!>b+Jvu^I&=_W5--0VYJ*4-eMhODeXj~d!AGq+soViN$} zcG!`R9nF-xR6C&Xwk6k_Z|s84sis`FZxIAd7Bu3zV`eaPtu^GjThKnR-C)4=z6A%s zuTG!q&qEIVcm2D0_<#04E+74`o+#rJ|J8rkI_kf6>*3^o{!~^)L$3@OuTvxW6!aa_ zoa+fyr=Zrf?SI#k?sei?w1?@gT#NN&9+h(~*6%Q`H`ijj2J_vy7X5jgGLUQ0&&*as zxEB3?ab_sj;_nJ_n|*Cu%i2QLEXBTFp+>YIf@D;%`^mi|j_n|*Cu%i2QLEXBTFp+>YIfZIf9yo9W+!SjJN0#uo!VYxCu%9LPdjeG0Hq-+ z?!Jq4(Yy}+^Y@`Mxs6%HQ)87ypaK;eUZn>L^i?Ao-A1(wuOX?8(a~)9yZQ)vaYct| z^vMRd(zA#K*U_~a*)ZmB3Tm5BK@Ysh0t?SP)N@xkojy=sm1?Vv^KN`aizn)<{LWM$ z@9t&j#Rh$qoolghW>K-QPSjUD_kDz}-+YLq?Mll^>pa^_UzHsw8qyBZI8!4`HBjaS&+216y4unP9q*>K?OWUmBHn-GA9eHS`~9GwUL&UC1pX2 zW`9tJRzK*12U*~}+5o4|sHcq$vcasiDfViw%Q{ZX2A{r`*z9Iw)_+HY&kDSZ%#BpPTPIe~#A?-sj4Ix!H$sR!|*n;hzD|pGV;Q_zJq;H3MY(BeBS9#RDDH^ne1+t4p1Z zYOwz!oZ(uA?se5wCE4G@D~gNJFkfBOX6M^Nyy+p5wks_wt@Fzn9aXW@E6&Jyt&U2b zRKoR#p*pIjgFoX501j`MPI)ls=k{l$6N zx6x6BY_7sP1ztZo>!^;}f5#e8Wk_l-t;boRuQI=FLPTD6AG4tT^j*&D>aJ^01m&Dp z<##14*k6ZZ1YVtw>8f1zwijPq53fk{2i5qO#Br$Ld+UmPIt zIy5{DvNmdx41w3v{8YHiw28=T^Pa!pf7X?V<7=v}hHAchH&P(*vKy_TGVIocqzJr5 z9nw(kE9gXi2)v~2O3O;?466GBqaXGn;+SeW?+eKuhcfFFld23 zxhL?Nax4|9t96LTtKZC2$my)dwbVvhHsD4IOnGHU+6%mHho-=>E{%vdzTEeuz}K?I zL>ynul2gFl(v*nf>%pW3`1@cW5yw~Gt_`r^zyPvG7+*EG0dAgjCjkPlGs_#G_1eCq zUKn3educsmsx(y5S0-{^FAJ6M-Q0V5AlG=Z>sk5Hk5_pYhSph%u){yrCFUwaILOgyIDHeDQ*zyBX(^e9f+YgbnU1?cq zosj$u25D^KjAoaW!>rmZTyK_@!<#kRIIp%17?=uR{Yg|bz?@h&1B9i zb8R%N`8JhY5_nY`l|dDX;Jlh$Du$!%DCZ@$Y4P$T*iN2CA_ZR4txv)$|LMe4;N?3i z3jEDyk}!dnc}OI5`ZbI65O`%}ya3DoC;0dpzV{{g_B~GYdz7Kub6>$3zhk8F>tYn? zSPcC>A0;CMUeb1@Wu!x@deCA{}$J(p{#jkN5=#N*&FYys!hzQb{7JIOdp-_kRj*Uw?kAbh|X&Z{uu8BCaXn)3>CD1XzlG^xX?gRVZ z0VG7=rTK9$TwAt-=nK3?=i|xHcgejxN~68Ld+UL+YD-Rkf#*Nv{c^w)U1lxuMab5>L z?1o_$dpNH%_jkj<*gc%rad`#|o1e*fZTHN8O*z+yxZc>Fl>ys7WDs$^Q8@b=jMc~> z4Z?gVwU^e@Y)=O0y}8YKbuUg2l`LHkTN=T-E3Ex4aQ!g&R$QlQ1m_iB zcplt!9&=thK3;&`1M^+!3c=T%GLLtF&smH2fDBv~HiT52OLn<3

<52a~%T=e+vO_l4h|j&oi?X1*|N;|b2oZ}}-$)4YiDN;`E5igpxoUU8jI z!{)SSoYy+x-R0(=3pg*Sy|f-vk7!sKQo?x+444nkFP!1L_V@My>-85nud0b7;KjCc zoY&tCN1$iN&zx85c_Gkk{3p&!YO~91IJ91Qj?5Q$xeED@TCwNIF@aZllflr;^gOA& zTtTnY41l?j=Q%I8q}}jgMJeYcD-43e&p(k10c47IGJ1!c;z}-L8JI&&a0nl6pWl$$9d6?V_|ApEvXcEt=~Kj&YrI&1p=>u z@(FO{SS`sHcuCupmX+37A2k9x)z@)Gs;xue^oieGPn4(mII(lRnK`z?WOf-IlI9gD;I7=a?*YlP8ji92jwxUhX zGSur^Bhc5Cn*uLsyVA1KI-lm~K;zlk3UNKZc$+443IC^utf^;Z zdD;qbJ)hQA$!;gBIIoc?oh_fO;*4-2V+FzgwA4mgR<1~94p!-$S72#8dl#I}d0qP( z$9`#Na9)p>Tx7{>GdM5Jlyc^BNk<{B=fBPU&T1CxD8%)=V_GH4@2H~?*YnEUpN#y} zR*36)slBuwMR*}w)ZLKt>QsK5JxIynyn>8Zv(-Ira9&1nLz(BHEFwOCZ7q*wN@T=& znWqIY&o_Ds@%c+?v#a$$W;7^^P=S|xkAm&8$|8-0^+xh7SGH6yi@X-3pG)`RIObOc_~cBN&db*`Sc zfO!h`BCnB^lUUKifBNno5BB|oo5xst=jDp4_4Lw#Y|g9kgsv=cw?60f zS>A(P@YGj`>y4X}2`g`=uMpQ8Q;G+$?+tni@p)NlFRiEQbsfDFW6XIC_r6N?``+Tb zYM)$ImIvSBycTcXB~R*horv*`#KLOjk>|#o*ZAT)a?9WPoR`#Q=K1sT<`1$-knnwl z!jA9cZkw`6VMrZy(zHT-hGdgXLOd$-CPHmHXLDY9WmC|Gb^4rFNrEf7y;EON)2$38 z2ALwWv-*kwFN%>>pU?6pck~r=Z#+cOcBN&db@qL`8x2^Y&v~`FcSd-}?4KTxmVs`} z)aSg6r>sLCWZ6WFM{PMf3Td^==DY&8%|@MC{L@k!Y1x2&`_Var%$ z#+TGyTF>5V2wTql$E$dd9$xk8Cg=4%YZz|w>)-h5)5{O9{gX*93cQN81mnZm|HfA* zt221e5(= z&zrOO`0`ry8lTVxa$4XO`M`p-{-wvqm!FjrIWbU+k1wfBsLoqFdn+Tih51mk(|hdn zoszu*uU|H$cK!Ij^S5Kls3hG|o%IR+D6XO5?mn5G|5x zqvX6av|UMqrv~SB_C_~Sfi*aBHgcRab77J zro?NoL89D0^*Wf#n*@P?$0GB##WPe z0`dkLP zskqGVUvoxwCo7v?=J&6djjrUl{4(cNo4AhTMOX0kp~s@N#3`_XKYtzAx|-y~RS+@W zJ9q9%VyN+hi1#n4y|kXkS9g+>_SJknA8hVU%r0Hwyk@o@N{$C;DVhlDK+~HZB;u#0 z!dcM!W{xAtb2Sw%f=;RNCO;l(DB1~H$}#lfB(nRohGM92z2`$8a*Jvx8VOqZACUex zr2m;N3kMV1crArOurC@qguIW?QfLag?A{=v?4+f5{ai^ymzt5>t}1fTWG8E0=}czy zr{t2LXIM61mp%sE=V!h;BZ6gf0&zX0B;jT~gxzEYz$#~Pe9PaZl zSw4QZJ)8Sn`D7r@9c#>e9{F(!-rC8S`>gk46}Heb<~}FY?Zlf3jkwR!`_cRJK|*eX z5%>Ao!$3UbkrDSl9?(_TMz46nhM%?E~!uJP` zct?`PLVSC~zcfBh_7 zSMSJ*s~xm)Yz#|N2?FCYP?&rEB=Txdp7Ww;}ImR`rC99A?P-*(u>E>!mW_ zKDTOgoUKXC+yZu?~0v`)>c|RLYZVpkoy1bvI&wbM8LFseiV?{5}X`{n^-Z7;o%*8s~=Y9)& z!u&XG?(_aI9a!y?!F^7d`I)WF$>jaKdHN2Cqj@QaA^ z#^3Infpo7W;=ED+V-slE{vzVMu_o9J8u}-5pHFRQ2eQOe?sG!Blkms;J@?u2@(EaH z{_&sB9gcxX)+g?BUQ9S#_ABE)OJh(;#Yf=9moo12i2mW=9aqMEmd3B7aV=@Q%lPX_ z$a`4Aeg3lNB>b{|&wcJV;3ODomT;f%eVq>@FP`N-FR7XYD~w~g&t|*Qp~>Sr+~@lv z0lpUB<34{ip%C)^0rz=RUMhSmdBlB|#yLmZro#TM`P}E9OH<)dw|wriG)5|ool0Y> z2ZVjqZr$#1pWnPp2jqW;`#fxEI@GSe&3$&C6$DKS!?@4U2LfQTbp-d>rc)uD9&?5J zJg|R(@D5)h_gQc36KMAZRPOVUM)~mLcq;c<8i$w0 z=cRG`so90lA|jsqe0Oajtf-FXK5zZ_40Qiq=02N6o`4-AHgliX91e%97CX4lRY$+U zvFV}Q=Vk`wpjUl>``m5u7ckv%i2L0AZW%#>!`!z3zm%)jGaPIT*;4)~xGMxJ? z-RqI=0ZI3U9Id}Y(?k2X&rZ+2L0R2C?(^4{-@w6fANP6djZ1L3auoOZPxJ-oDWAf9 z{&`tL<=uA@_j#?ghHCYl>D=cL-~YgiF>|@kMwc64`U5}ivvg1J+)!aJa`PhY^S2ER zu>IUZ?z411QM%74-G3bVQbXml$D8}yK37BaWsVQ`dD>JBRlgS#xzC3CD8%lSai51y zPlbr0_T1-wrur)F4d&eE*zyS7w)rk-}y?Mu4?M# z7TjltbYUO=c608tbkAD4mo44n{?bujwc&~>_xY5wzUs~)GwyS%SUpwxP*d)+#?@@- z(DeZp*Bj4+GhyoBaxAVl4&F0T9mw2`#kua?aU+!?{SX%CI+J-us--E>Se)zZIvT0& zU$}(DxlWqfu))DdHQh4-i*wzR=0>V>o8z%K*Gcmtr1=ukJc>Urj8sD{cVcm_d-B9c zwXSRz7U#OJ6O2^5igsXeuDfe|3x+Il=RWIJ-++ESw{o8c2i=16xwlWZf4-B|yfRir zelw0)Ae414GFA;TGDo7H#V?FiWOk;!x1g5_Hr2EH$vp)v&82Da%vg0esS^_Y?^9^3 zs(;l4iT+FTa31fv1-mpK%B@Uyu~}n{g}j3Hs6p`U+1fman_VXt`|$GMH)p%;2qb53p@0Z}9Zv|L!tN8-I?ZC~k6FjLUUMyvmM)6q`ccpK^l;uuuKT9^ zqT%ySa~+<|%C+d{lw)aJi~jrhD7hZd%P=PM=szu7m#eP}_DF3n)PvOZ2=ya%{X)A)-LBvd zQu`zPE~NHT_+41-zwo=T{a165 z@=|Lt7fa1f)M|F3R_n|*Cu%i2QLEXBTFp*_n|*Cu%i2QLEXBTFp+>QeL-<`;)@9SBRxBHU|d{B~`mG6LC(EJ_Aah z4Rd9?$l4!Oe4dQnv5S~1tN1)Q`|B>Uc}o?aw<~(@CTFrLNiSg@Si3Js2z6JIQG%{{ zwTGq&NYweLLarlG z=c#@ka_GP7LT==L_Cn6&fAt8tl>gN)fbBctNTH$N8LYS{p!48v0ZguvFMLFuUPa`omVXSFUcz=>bzp{_o}ap{h+oN`$t`m z*l+6k#r{;cE9Iru;(tudPSk34qE@q0Usva;s@aLx)$ByAW+!SjJ5j6IiCWE0)M|F3 zR_n|*Cu%i2QLEXBTFp+>YIdSlvlF$No%*^uPgTuMysl;^YBf7itJ#TK z%}&&6cA{3Z6SereM0TQ9vlF$Nov799M6G5gYBf7iOL_IL8%+jHi{o**CA&Py%Km4G zm^W+kE0nD2^NsJ@+B`Wx;=Y&gxSZ7HLyN)N`A5Rmx5SNR(KY=W7 zbDA6#;&LI`6G_VAQ#>v=cJ(3RCGeoRZ%>SdPzQu zjQbVE<8m{Eys8r)U-G!z-pJ#mu;e9=%O%7gBTL)A;&~DGuN);4Pro8!993#Bt%vM5 zN9G#7=5e`Mla>*-BAUnL27lR1ELtDuy!Ni$LbiW9$oG}r6kQ?n(w}i&dIJ*3r$P5P zFR6|G^)19|)Iky?@ai>vEBUcDj5HE>^*7%}hD048D+FGZ<=aT;_5GYz)Vd^6V}G0T zstHLX^R@1f*1|quoe+zy`F4kN5qNc-oj}|Y?vnWeFKN5dveG(ZSu)xF`xa;P^Y>Na z^!z5*V^AsyO}jzFeZVQR{7KNNP##C!?6;kGjo;519sIbR9Dg6mwbVvhHhg9PIec~> z-&Z;~V+RS=-pAvpp&fRT{TKK0IBMUVouoQqFXt6^f|B&-Ih>byosv|1%i+AdZI#5< zE0@PnPq$AaBP()w993#Bt>>$G4#^41<-9yu5RP| zwi`#>B~x|NIj<{y?vT+DNt~C|X3pR+;w`XQEAZMM6GmwJt)xiUXFuBOAhBArne-KS zB~=|HT>>|9UT6N?C7~^^a9)u;?vmgR3B*U>6?p6pvG0~hW(d5JhTS2N8c8HX;3aKW zT2@+Ty!Cxz{qizr#M(U|r3Wr?9in(h-VKW5c@Zyq9wr*Q*YSP!;OU15*}Z`?dUN{_ zS+ILO*HRm4*;tz+#6D&X-)E1kKSH`Yujb=xrZSwY?6r!IFBgvpVp+D5^KzK*nEb82 zzoc;2i_#(T0YB8u}m)$bj7yzmguW0Bf?xp$iAMo%Cc#PQYm z49UnCN74jd3pSh~v1}|c5O^u9&XS7bqj}zJ?`lAm?|B~o*hy@pWj_|ikj9;db6(!3&XF45p`2H*k>|~Axy}Nzzqq6oNCJVZTs)9A#H4C z@bR_Pu7(`kJd3;*c&)orO{V9~A-Bcxm0C?2{DmA>ftR#hX<2EVRqj8@1D&ayk^7II z#IwSO>$1pSWb1P;&a2a{MAFVw#(7=umq?PAHQ|gd??@z3eVw_M+DOZ0Pe~%-*$$l7 z9i3$2bjOb8i7h{xOnUFM<-Bs7uaXy~Hk_ANbsbS9j^VuQ=GPH6c`WDkEvuG9J@n+f zJlhHJ-HYQnFR8t>o~yI96swjEwAw9G5U>jYljOBm^E z@*InK&faC3ibwq&I4_Osnu?+uPNbQTcXU5dQ(@D*2`LkJm85DaI=pI19tpgp?Mll^ z>(p$mr8sY3%Nfm|siiQyW68DeaVM7n1yMo0$F{w?+@Js@OHsFH- zuLCZbB<92loGkDf2dW!KKFXO2KFKN5dveG(rTIeZW_d3eo&Czn#Q$z=calL=4p5lIS zFc$N~R&C29FVBzRyq0)o5}m)3IHNel@99h~)Khf#+KRQJSx=;b{WiM*sXEpBC#NAvX1CL!-=+2(BWD&nC$Qp`K@%qITc!SZfG-cj*@ zY|?5?otrqm#{26lj7~<&#k{^ZLHY{sK2`Gm!h3KPr-ePwfF{Ua$UB;RLtimATaNY# zc}LQArDdgco(|Ag_-`$66Z6DG?X;~RP1Ie5wscQMD@9(m1GCAvHFas?_zD*EqPkXY zV&1H%<#nynL@l+EmK{GnoA^8mRf^+l_pWTxNcd)f_?}Mf-E6Ypr9Ktk(=ieHZT${g zD!!-VD)iOQ{zIvl*H?R8Ur{jKjf%WhMCmJ1uQ*VV*E=DPjOKk)ioB%u(t5=HPdrgb z#XL+~fl;meI2GU15!uDxvtZ)=>*I$kqEYI~L|!7_J6^+?$SYX*&(yx#$V6UJ8_hLY zWL%;fYa-+wnKa5GHH&KEUAa z7Tnzlgx~~%Bz@n6B)APexa%-TfWc+!-mc=*w`X&AqcE zb^EzdtD<6|vTrRj^BytZ5ZCtlu*N3owO?HGAMegKNw1<~U5z8Brki8M``5W`BB!bP zWHSrpMci^ViWZ$T8l-jS9v>uWLh0((8VMSP0xS+9bWU ziMX`m>3Ea$8Z2T_omzWL(kpX%S7YI~ohIou=wm7)Rl#j0=`~!$mH{!FP0~wmulGao zZF}DfCh0{nFfw+jNqUX2Vk7GnBI0lruVbti#m{v|ezIQwh?qR{Oj;zp^fq7GI$?Rl zar2glhu1D5Y)d$0ZW8Zbm)ap5d~wb^F6M`Sh-XK^;7hF6Z1GI_ImaDIueKLb7$Mm* z;$K3qJ)SPcp%3YBmC$QXV;AG(3^%+a^wQ6(|5oplo>^{ZypZ&wXW7;?K8(wWXXUnP z*^u;_C!V3>Gu~vq=$ZA>?J8>|pJj~oHu`U8<~IS|@3CGxQ<$(U_7Ur~B)ti1%RXbh z_K4^HfRX>OUg<6-H*S8*gQQng@hr}8G&ho7|L#j}cwNegq}M!=V^w&QACg{rd%Yi; zKa?w821zfPV?2mUj-=N`Ywm$`f3+3!oaryTk@9Bc`~>O#nj_{sBf=Xa<<07C`Y(up zdBRgMQs{N!-+l1HEh`QXdW~te4~jg#oXA^`xc(58H0r2A{Om`ne$s~784`p|z6-KQr~-fX4I|3U2N?nrsF z9yvu`RlBZ8c}IGCy&syNpUyvq^`bd^%e7@$ub0-`p7mONBMkcAu8EX4E9d{L*I(kD z;@IJtte4)#zgief?N|#p3cX5C+X90&*2Wq_uVv>#!K_nP98ZV}7w(*zz`ipm> zx1;7*dj0bhCij_*AB0}B_dNsu>9g>o(Cc%D=P>fiOspXE($A~^R_~MEx&D4Wmo<{_ zVwPUwU9V~U0@kaacn2)LrV&!!tbFHUjpVx+W4%ps?YHj-Z-VT%ny_A5l5K)jZq1SM zW~-hJf&UJ*K#GU`#e3^tFIuu*ZdD&by+4+)UehW*gdN8hvtBs-A&kAci1pg>SX($4JQC^obwsQ=c+}j%dR@zL z5e7Ehj(%c(xHYB7Wth7S^Naam^0-TIG21rmDD=|LtN&K-GfJ#!{IhT;Yb4h?821xv zDP0QeL0Uh&Bi2|(29IIAy>lJ)t8q8Ta7b$P{m9>7wdgWRh1wl8D^8KZ^NuOsL)ZaZ9 zX?^2irKvE$dmcU(^ZDmZr$F59d01cQRbH&!bs9RK@2^Q>P4C#D5HQ{Md+oUSO2Zv=Lc)ekTu#W))FUwJ;}JgSgSmo^)&01 z_4P!EIUOUUAY%tyg$u)>FxD?SE2jam~A|*Tust;r_}y7%cS4aAg&I_Pc{K z=zV$HY6y668^eTN`g!%=>V49h{P@6otP!o%PY$@x*k9}guvPk#zwRN5Oq!|Z}!!XW-ut_CVqZ>OK1u?A~x~!>-E&8ki7b4)@z5@ z%V_)N5$koseG!ar@rd<0xqT4~U-S?uZ}!hoi^2W!1Acz#?e%`-{s`+O_fS}`amRMU zk+s(`mzY;%>9Z4-OuUJd6EZ%{cDUaDHd0Q=nGInuzVuzBTnk;tGLN=EP~2UtEskdr z&$4%;?jq$>=+}ULZRpp`-En)MMcV5~IU&xxdmwkS>qt2v*N^XpJJqit<%EnJIUdT2 zZ-SR-1hLGyL9r8Xuva{DexKnOw3>I6IqR{) zv&T{JEq{zTXO21wwI3d3&U&2D+rA8-ch?sGEd z;_b!$hNx9XoOiyQ3(JPhW6pKoJ%V=5^~||T>4)Gct^pe7-GAJN=bJY(=PK*&!dcHS z=Bz)D+PL3^TIa)<^Zk~0Va32O=Bz)<^k}xgpF+BOQjyZQP{}@WNThE-UE_noF z|6IqM+h+@fC3|`@=Y$CxAiDJs=6u}eGt6H%jyWff_z2-YCNk&CwLU=P)+x-n{#B8; z-e@{=*5^F_UEf3F+`-KG{Ob3x;?Q*Ftk0M9d6YiC`g8JUnEPoAa}KZn848>k%bc6d z{sbcnj$zJ^S4BYI(&d@+sMmYoNXi<_d3LFk#;(80G3Qd@E=G~bz?`2Hbum(ws>+EH#s1!z?#kHC9ka;PLZ3k*GXMIkt&(-xgeBM?mjY}EJGUtcYQyPt4 zmu1c)ueuluCzoN)6IR4P?*cB&xy!!@zBfFW^OWjojWhSJnsg7A`jp0~Zay&S+Bmi) zjq%?c@tvN)zc)=|OmF?gq_rl*yx(D_5KK*@Ae^1QO zHmz~fxMb4xe5+wv<4L9~Cf$Q~uB0*gMqM=N9_)SV7~J++Vbb;d+Hn-xhaWWQ9-OjW z5T7HgP60vK2WkzI-^-=P3GLcc{(HV zeKqE+uPx|n4*FWeu5i(3s{2vIdGjujyWRg;6mcFDkj^;L;C>Ww9vpNEwgrbo5$A&u zCt*}Mcjiodl2r@h{5Rq`sz_nZeFZte_qGVF$@y>e_u~6%od34?w42er3hq##5sGU@3Tx-IA>2^Bh}YV z^)*$xt_FPg&YbDG@+|y~Ip;o<+DO1}%$cr-4&euxGhHWly;g9}9^GG_*J}b@8+6~L zDpeKe+MxR}U@`z*&vc*e`Kuhz^{lU@(|vR~V_Bf~dP96WA;y;O$36vIfX2C=6~~yfjBm_2 znTUIPe@tY~6b~1y8^@gW{Thl_^FEDX&J?c-o*B!W^}QZ_4@ln|Ds06`<}BkRbACMW z9h90oojH#b@$G2J8qAsE-XEpQGv^@ddBL3JbA&n5^Tn%72y>Rt9p3CiaJbC%Bq z=B)20>idlP{$p$FdBmLWS zoz`=lIn(n!rCSVhmd{_fD|DpiZ|8Q=%$c6Q)%J-U194p6v)1>r^*wI++-J`6xzC*c z+J6LQ{&AE!%jY$7rssI*l^M)g&VQKmIBQy5WSzWaBWvz!+(XPPgS%fE&>>p5(CzFeN;^PuR* z*Ua|moDa9gyk`D)iq40uQLmZ5o`-X%L_@gr zcn474?5a<~D`@>IpuE|2l^esct~;5J%;7=lGf8<_jAhObW0?!YSmp>ZmbpWWWlj-e znQO#Y<{&Yaxk-#=&Jtsp%fwjbI5C#FPmEM&$Ip#IeGnDRk->BC} z&rlgRke=x>ZXo5&QrsvuF#)x_S?n#2uNHCO()w3Od9yMOAU$)FiGM`?JYQon*O#%( z0cI?7gBi=5Va76-n6b<;W-Rl@8B?yZ$Vp}_bCrJ`7dhC!+KU`)#xm!bG4(I<*crCAIigLEc%ZU`SXm$c`0w7vEW1b z{ER8LT=Asba>ZZfmUA1KbN;Kn$ie>AkI0{AO#O@edB${Jkw4Fv_=x;@#*|ww^5+>- zZn?;xXRPZrz|$p!w4-ZGX-8OTM_6e`SZPOCX-8OTM_6e`SZPOCX{V0U->%xzm=IRl z5mwp}R@xC(+7VXT5mwp}R@%wqtetGn+7VXT5mwp}R@xC(+7VXT5mwp}R@$lKbgioP zq#a@EhqNQCv?HvvBdoL|th6Jnv?HwRHOKl^n%CtLMwNkY6?Y-!&B~m4UYGNW7zuxF zNZ@rjy$zHt4L5S{!d7BkZgK5W5L#mw4j1ckwMvzM8q0U#X^|JPOngiJ)N41d%iR>; zm^U8#me=J*1P_6GpA+z$SeILMZWx4wBw&nKmm5EA1O!Y^K=RMg&#V7d@3WiuhJ6*h z!^*zH}!j8@8)$>`3*a-#mR5m8S8EI-;OL<2>zVAhu2Zx zS1$mCD~0nqYE;_%(BpbIucPi9mJd31+RN*5b-la7kOCihU9RZ?kx#qi1Fy>s%hes? zp8v<|sIISiz}H&;@j9yBUhhYKhwh|(K>58nuge{@ya-sYiGeA=)hCkomE^bQPMQx_ zNLdDMG)?BDeL%gAU97t*MI%>sx_Z^diOi2i(aD{(52&}-`;p(^vtIs|rw8k`&GPzSy;?n3>G-SlVcxf$ zZux<*UI#+2IOexZ#d_&&_RL!DIF|V^4ib8O4PWf&^gafM(LP1P`Hp*^g}0#4Yqs!0 zd7bAl>(xtmr1(QB*6Yt^ryVy6rgHiUz1Dc1cT6jg%6UlWwSN31N8xg*oQs8C`g!%= z>V5XLJXlzxrIt4f;}gRBrMCE9k@ng92v3-NBM&3xMMw`8)<}A@FxK1Xzdbc=tius^ z7%4BJ$A%$}o`quh{z^5kzoX=WSiZl$l<4c&_9K?{`rCVxqw)Y()~omP&5q<{U7fVg ze!JaPNB^&>oV3s0XZlV@>T{`_w9l@$*Za9?`Qfl$Z!OOp*6Y6IrNeriD8arxNPe^P zEx#SsD|Fzuz*}*tos<`$xAB;`Cos*_cnlSJEGuVj2n?+nkIzIN%fx*11JmS*M}LvW za;)9Rz@0hbk^E-+3lE|fT~a&AZ#JgK<-lFtgh#g6x6NASY2f$~shy4Q2>-WH?*jvu zr*^hJc_C0gul`%T&m5M=5o=V=@;+jG=z06VmLpTMUSEXgQs)x!tk*2d$P~^^@?HB<5{o9$2V8(cqN|oN>gom#iPF+VZGj@JzFvB*VL@n ztB)@$&ODi#^$Km8Iq=cC)T~$E=j8&&PEE~v>FxD?)>(d2tk=JmCl%{e%krvXy|y3u z7By>OJd)q+8_Uniy1yE+M;7a)x4BR!h54>vJhl*e-RYgyd>kK#p+c{v4?N7motcGR&x7F%?_3CDMh_ObGEpIW#dK>+> zhg+33ue-*vUM@!~nHxnvl!rNJN)7W!?KswJ_`cd^^(Aqv*O2`)&2IOt`)m4;U~^QY zb$_+kG{s!B-j((GUTK24YlSQ8rMK7n8E5&qv0lNJ=Ns!)OnAXvIB=Bp>OOe8IcP)- zQl1!CesQc<`+cv>;yY8aUV5801$UYgzD45`5f9T1+hgt-6^#*MpZ(SN2y7&`^i;MH5&})qUJM&Jtl+KwVFJfG!H|FL+DV;H= zE(Gf5)qkt^Il%JhV~zf{y!#km7T$o9i@UI1FNJ5|DuSfhHDcOPTDjsDx4 zXOEf}z9Q?jf6^&)=p$sk&c8ovdVE0ED}Sl;W|`tn)~n=^Ot`v`i}n1PpAmDpx$ym! zeO-DSn8Jni^62k|r82p&UV3}IAL+TldIeaXimVrTYYb`@&3bJs;f8fL9b~m@xfS)tXI9xEpfx)&pba&p1TEZS@oIo#M+f;hHkq*bDr3J zw2D z>!r8ZH4!jn*mm44^jdboz;kc5VN0P`|7n%+K#=hK6?$b5Uaz;8Z)Lp(2@lvFUtX|Y zYhel=+3_#F5_)xQG8wP-dx`%Fz0So8Kh4os~V-7BD{*3kN5;q&0)qKW!75!@#dXIg^dd)d86JI=d#(L@P^?sz+ z3hO03Rah_Ssls}F@aTi#qt~!r}3G2ac=OK%f8xDVF4vl>?ky&BHx zEBszoV}Q`>ar%B3UVRnL6naGnFXc}oSF&CwgvWBj+<&uPV;_d#;g5f#yLkWV;T?jr z{=SC3Vt&|T^+t5gzmCm?Uix|U-|BsmhjXf|S6L(J?aX-6^)O7E@-pi+M0iR&Yph_s z$iq3pYb9$Wy`35BZS>#n&N2jjgO{^jsr-kb@o5?BRpZof+_-BQ>(%!A2t2rD8S9lo zcway0c9He!esDXk?RSy&N_%b_MjW}wdgZ^i6@43AV!ibCdOy-4;cyR~c zU&wk@J3j*#Z=J<@NpBg}D_g}FJk%?e_0rqy|7QmN<2nn2g=aHz0(=565i~|hD5Pmc?!(IfP`tRm-I+yjfPv^>5TO@`fnXs z=HiP?(^#*%Y3AYBc2ile&1dG}{0~!DFH`u;x4JQf^;#ml<*&9q#Cn}gG;`I%^O}Bqn;oATHzyU(9#*WokK4)Ky5qecJSL4wly)m!QYrUui5RtbhzkeM* zejW3*-oSdz^SF)^`fbD!LNA}0*Dzpg2#ywd-4f@z)Myi~6ME_A)qkt^DQgh0Ml-G2 z1dON0+`{Ko*Ki(YB~cUM&re=)c|Cb{&rW*qPs#yOds!!y9$t z_vKAb*W=rU9r=B^*~kr;>{SQW>(q|BSWK)9();oU_q+HmVI{9`Y_4?&zfN7n>l+0o z-NwuHS99Kx-d^wLy&KnqV7+cxH6vIr=_AB?E&a3&KTQwf^$qDM#Cp{eH7q)poyvOY zZ3;c!hWmpmi~A_0ImvT7{?pRHsY0&-{kP-68V5J% z@p&&XeaIw4q1T@!UgFER$+%bO)iB*lj9D`UV})M&dG+7weNv5&E}zGao-jsDy8!8@@`@6xOn1nt70nWZ>y z_TjxHCntumUJv6F@b3b{Sg*X<6Y%k~ z;hZ4(8`?Fr;p_JuJ0P95_N(ml*tXCgV7iNq{CeE8BKc$U(TCrZ!M2(oz z7i(}l)Z28Qc>ph7%z!O~UUim;`UMZtVN0P`ztaaW*i4H{g*L{+p_JU+A?#)Sxl9S4Ucp($A~^R_~K)=(PA6Xx(3; zwobzfxf!THDB;|IxeDS)7H*!%tAu1uA-Jxtf-$({`MuxigV5TWbPMw>F3pd ztM^GYs>+>X=lV>wdE^J%5%>0DF(ZgSz>+n(d#e{2wcc|#a%y)Ls!mcz0!!xbR^Q#lWAJ7>~&1RXx6bS50XXi}cD-d^t~t*96Ft*uwGR%r*`&pmNkou zcz7;vYG?7{mCd0vpRbhK+3G ziq?BCiuIdCF>j-2y;pCq_d_0H*@F%K4vxIS>O`jH@8EodPuhj8J5AaTCI7TR2R3m2 z8~LhLj$UHrzX`v!#j!Iu|4rAC{Lt!pP2>DG@9K-*=f>>Ggtf(S@|`=o#2q>RO^Y*n{L$kQ`Q3Hg zm7n*N$?tCb>3qDW+^j?@XYp70kn*y~r>;}YSIn9G>xzrD56a6*D}4VtpYO|@>so$* z%$a-who9-hoXJ11O;B6rtUr&)->>bg*36mw{a$u&!<_YJnf{E^pMB&jIA&Zw=KMvJCRQOvVs9&?sHip*J`FX{8B|7Ctvm;D==v-EFd&Mk*N$Gqj1GiT|$$ehWK zare81%vt(aGUrsn-!kA+1aq!ljeRefGx=d|YP^Rz>+@>qSIL~EUnO(a=j8faU7y2m z5I&i`KOAJvOD&&F=Da=GMciEBAafoj{4L}2Pi4;JdpWJ%IOZ(_FMj61?9Ed-Db__;{=>{!`Vuqe-z-08=A7H|d1lW2 ztFZqwb3SbOLNjN5Eq#vV+svFJE#GG5tgplC>+|}${bb88nmPBe{Gyq2+wMEeJKNJT z=lPb;GjlFr`9Cw~OqOppb1q@|X*1_Xmd`eGE^qm7GiQCjrj+H6&75mn{@Bb}-|Nx$ zfb_kgFw2*lIrp}FxtVjqxO7pW&C)UF0hXUOa~>>wwi}l_#hmwB{^ZQr?JfJ3Gv~&Z zpE+~>X!)EoXMIm_yyZjAoa1m0SH%mT~ zMSi|R%A57Hd?uNXUf;n^O^2k`kC5YLP(DdwbrAHr33lo%*r|`8*W<8LzeBGTqSq)% ztS(7X>z>%Dt)SOpuv5FiPR#|qj*OkUGkT31y|zwb^>mV2ug6Zk2ED$6oq7;<>NvP3 zv0jp1n@O(;l~^69q}G|TQv*V;8DXc!gq_+DdfhHNb-whPVtOsJ#OjwNwLY4ix)ORF z3OjWx?9`jk>&@AzPp8+y(`)c0R(CI{b^Ywrs?cj&*r|nKr-p@IC(%w_MZJcjUOO_e zdXY)3M`@@2ge7bDGpTs&;B>=ruUPt#>-0 z_mRYEcG#)4q1UCgQ^!`XnXA|8O{_j|QtSWPsnem?^{`V1#7_MVy`Hk2`pbH)XT8RB zVs)jHTDRIx?GL?Hh@ILZc4~s?b-?Y^4cBXw>$TAntB0P{dh2%TiRkr5?9?l- zP69T1J{0bXb@J-t-{QeTLm;o%*FdoccdFD7pnOp~HA?iFCU$C|*r{D|UhKjBJYNH7 z-!@3>k&Rwh9Vl=1gX24%SYH(=Z+6q5?^tL=5K!Li&-350L%vEp4&%gL*yPP+fbzg+ ziaoMM7s~VBPJ3r9zXmeykSdw8SJmI(Z!r$OjgmRj{#FtWh;eARB$;#G-^JnWsSAO- z#opH1fZ{;=N_Og==yg);)K#%l52d=;+iK_h!oG!mWl}mTbok_;_5ZA5PioG%_YPYB ze=GK?R%U(Up!NSJwNpBC*L>liy!63hkEzp?zuDLEU$OUe*YA#lt_Rwas<`hFYtA@+<)Pd@3Oaj;WMMX$YLr&f!d z8Y|Vrp3#9?iL$K-=>HA`d?S&>A87!a{2VUK|NnFu^h#u=0Mun*VFd_?d%)c z+3(YHO6}yJ>iMpEo^4{ewMot0wX;{K?=9Ndi?p+csOLi4$(`2owDtV(#B#!unsaVv z|54wsw6niyXJ1m!;kT3XuYX^lf7g)Mw+u=BR>IDnroIPiXV28mUZ?);Nh2HIs_5Uv z=-=Zc_6<%_zwxoNPpa>$+S!M-vwy08GiB!+EB$*e{X4S6z8y>Iw`q3vUiH0NJA1o! z_GI;M{p@@jsDFp3fB%@+H;+mErqa%SuD<_kXTR9aKCk|bs-16I_3vl(?{*XWRyV2N z0^8Xm*7ua{>_OYvJJ!Fgw(~8v{@u6!y?J8am?!lcc02pdUA28`JNw#p_M>%A06QK6 zx?h3rlaQD3K3lj?hH$6HnRVzuMlYR7X`_mQ^aJFR)zUl`DrKB zuiK7atM2b=#}C$ykE`x~ZpSZO_h#2U;S=+L@0&!Qc{?7kx@W8%k6An3u)1%*9iM-_ zrhs0{AhG%dNv)4y$5&SOp|#^%YsYU^uQy?*K80QjL$AS+Slx}J*7dOCRjYg3+VR4* z<6*1UNwHH`MX%wa*N#c7UQAN!(b)07)%|kq`0Lv7#ntQk*r^BfztkSm>Ln#s=P1}C zm9b_2+KS{iMLt?7yoA4vz?Y|Najfp+!gz820`UIhH}q*wKKn1@7RDNQZC+*k zpNA7NG&UKpE_n^QI#w}m^zTb3Ic3MMo2$h+ z==f^k#oD`lAP`>L`7zA;GL3QnDW_oho*j%!Oxp^(i=JgXp~qy%J@_f(DJy=1)`z|@ zp7$->F|D+VLH#sX(=@V;XDY^pU1H3l|D<4y=PO{hWuLkIk80B}?95}v?K17aF&R!X z-n97)`uT5T+}`aecE~w}aoT}j@JFFCjCbU5aXzfHpZQ<&Oyyj#=F%ZL@6T^3oTcJS z{(I-%`;4oql}9?ByZjT(F-LqODX`np)3~pn<&(DN^fvU(d4`Way)p&UYc3wWgaL z?`4W_%B$Iqx3e8jX1zw9otk=j{XV^JU}CiblUj?=j-Rvc|7^!E+K$h&Ufa=5El9oY zq+ahbu^N|2t)XehBU<;Aw&Ou<$2(fDNouEtsa`KtuhW`XZPujLezoH}t@~8l@wK+& zN3GY=wNranuk)+d7f!6Ea8hd)+wrp2y|3+fW!v$%)@wl9sTr-;r(P%O)To-;iPgeR zYOQTM{@A*owjKX%JHFX^?ee)cYMtwK)%AMriPdmVYK?e1KHGNux^=H_xjw^rh6&bp z3P8CK@;e2fTnM?&1LQd=zf%DEUP*qZ0Q9}m=e;B0)P@AkBWloZ1o#Cf0OijtoG=WI z?nvM|<2`x|fwalq0_D#L&td#+sxN!S2Hcs1%12sw7o+l*7T(49Ig>xPq2tO=o7yWs zZR#g>Wkqfyypb_mvr3GGXELVgRn_W0|4h7mpax^%v5c_=YcUqy%c%KjV{m~weEdbN zCBKdf59eR)g}3vseuU@qul|J>^sn;@kLX`~gxB;hp2BPT7k}Y3{p;_dXLK6I!fP7)eo4)k{$6#Q#zD0gUemw& zp>b3F(|D@$>Ut?m^FXB?VWk~mrJXvi{Ir#JbX;jiSZPOCX-Am2k#>ZYc7&C7gz0Z2 z?FcLF2rKOfEA0p??FcLF2rKOfEA0p??FcLF)N$pft+b=#N;|?zJHkpk!b&^BN;|^D zpEM$@v?HvvBdoL|th6Jnv?HvvBdqI1?_5(d%mX@}IqG*uq5HELm)sxk`1FVMzB465 zCTMnSI3GXwv^?|;Xv>)XP5({5rTX$H`M|cXa*N*f1h-}YT_Jh<$ z_Rm=B3yq|1LW2(AqPW{Qw=8{WF&5Wi0tHrt{FaPu2$$L07imgB})jwfR|&Wz>wGnTqIs2`;xVWp#X+$1d9GnV}z9hdzxmgi+G`7l;G zQhUjtk1HMJan_Nr93RyW>qy7tc=B`4ARyq<^I%>!HZ8KOnUv#TE`!b|39vE?5cTxv+%L!dsF(QGnPK;jHSOiW9hrjSo*Ou zmOkx_$?skGw=*4|$NpD);bYHO`o=Sse)5c^&pc!4KhKzWikbq9iNB~d zz_?!dw4tH~fjUmL2~_())n4=yC~6S!anXOEs6oJ3oR?}JFcy3QMGXSR&`9%!^#^ld0Y7j7%&pXEQ zImlQ(9~sN%CS&Wt+)@YiuMU;5Qv%yk)yet_n>^z0M;bFCl3;=Dj}QNn@`&|H_W z;0ZK$B`o-ZHeUjo>(X)Y_x?IA#^G0cF+RWg5##o&e=(lF&MU_G7ayS)(43t56ncT0 z@BL4`7+;_<5%YN(AI3s=8Xv|&cM$JxzmBWxncA!CnRFNLZrp}+7w>M2Nq6z?#+Y;$ z^MA&qyLfkFOuCDAH^$<61~LCx!|w-Wbd4kg>cz8O!UIG5uZQdS)!IbH?)eXDsgv#`1n)Ebk-6 zG9IGTi{CK`|IhoHbzf6lRq==7D!ud4_)uI`@rUB7ia!)rRs5m2s>L6E*QVc6Tvf*@ zuB!GFS5-e0S5^NMSJip-IxODDR_|hj)w>vB^)5zOy^9f6?_z}2yBJ~hE=E|ri)qLCom9Px(Q)-IMp(Uz5mxVF zgw?wkVf8LXSiOr8R_|i+`2RNV)Ts&`fg?SA0;#@0{*&==v8QX`*zlC*z;W?#XT^nz zYv+84@@pColUvWO_*-~F)ZOawP;mH{3T1^CVq*1MJ)XwF?)zmN?k6&sLnp?T;s4iy|Ng%9C0M=W^ycXm+!1DeJ{%Aai= zbX{x0$Jy7ITZS_xymGtB_<3a$E)D&MdER$3!I|orqpjfCFQo|=^F4Aj5Iidu zGNHh!yN;29XJU0)kLKJDx1M_gjc4(bd!b0C96;k4-+mt~kIx1)o@Y`Xz3k5t(U5d(7pjpweZdtqHrPR8kLgv0u>g@I~>!FaLL|x|D zdgB)O(5E&;3*F1t4}%wtYcWqF^JYj`-3X}WOTB)ZVaTM0%*FQs;=dE%} zA=!+P%yXOfGRPV_oO!POwhT(=9L7AmL@tLR<%crQeeV}T$>1?SUZAr(EdiJ@nz`LS zy##vC7{$1Kg+(xQ|3nBCJiFIi1g$+L!U(~0LFgig3YY*l1kaV_7enUZ;~+@zOsocL z(9vn|--@}+vwhdeFmvd9Apg(hU8ca&&GVqR(0y^|sW97R9+02s{G!uf!S=a8exC1M zO@#SJ7BJ6oeJ4T7<_nnH;-`~f_2c=B=Z+W;lU|FO>w;(MBjX`+!^JR@#lVUb!85VCt2---8eX5)G0)B^+QG3F8-RReW6O4c4m;KZ`NZC7+X=dr zSkL3x(X|UqdB2Xwb549KIM9D1^9;D&8lHG;WNv9*wSnmo8yF9m-V}yZ+YD55?e>qR zaCz${SS@(=D$^WVKMjG3g6F!wTEL*fA+S>LOsu}DUdvVbM*-D#oNd*2gWIL2o1tUM z!0L*-_-{EW>au0ayqm||uW1RGyKonfhw7H4rNGPB#be&RerXtzdl!#+E>S~m{OjHP zx5&C_%wN`1W88Q|K6uq}FOWZN_pJFL`}uGP7k`V}qymtsKsa<2e@mwZg<#{9JrE)O z7U|OkcLlctR$VjZSr1acG4Dv`87&G_Wau5qV;+^^i{qhZB#(LS$RCb{PY&^zC-X@T zanBC%n4jPD(h=ek#XM!bFy`iM)e&Rda_BwB8W#leJ)WQPfuq|56HW`B$%{XB_`QjO zxq{~>@8^!11EU~T@GNZA^J1P`t$JR}GwqX=j@_*fGtUT7hpSND!_2exviXkmpJSNk zp@vHwu^(cXXMEIh$9|u~%(I%Pne}4CVUAt0P8M^M^|KgPF5lNN;zulO7d$82>+k3@ zGZvBwFJJE?Lmm5kV&R$Kxg^s#$16Mx&jimmRvjzmdDp6A#XQ$k;yPB$GhO?UflqS8 zGtVhi76fj|8_)Mzlg}Z6{p!R+jJVe_28IVtoDt7FV@0hf{}S;$p5v|hP|PjZsvE_) z|G4QD_x*N+@3k&rVHNY8kB6D!IeWd>!-^Hg#=~`b&L+&sO~==2_RO z-^4r<_J51oxiFr2P8M~S`qhu)>+?+u5A)slIOZ8rDUF%(LL6V8DgH}t{wNyH*XJeA z0P~t}9P@l))kR`%-K}~_jNNwBHk&SquZKnA0=IK?X6N5hu%- zf4auOWAQAQY1J)ap2bDoqVoriGSABcwwnL`1+#FV&AjT7moj1D`cLL1;iXJ^{zJG^6 zp4-PBoir~$LTD^v?8|9K&4=F+1`3`^t&UNXQ)*Nhq=l6IE=5E+3|vJ z1oIp?DjRlrzmK1-*Jk?So754|UGQwy%Nw`UjDW2)2e9hYFi+|8$vh{&bKnYN2lK2U z>dRzYv6Xp#>0KFv>uzJ7MVA}+G2M2a19Tb;cqx24^V}n9!Sq-g#yn;H7v`2=)rDdF zzEwTEHE|2`obFy13k}%S%n(+mm(QzIQcdtJ9l#1{7V5 zg?jd7o{yfd!a5oHF;5Rs^P>2tuFP||Rp)}a$@&+JV@GVj;jcUJ+%Ny__2|>CBdirX zJ7rmqcP4j&GJPt=!1j02GSAcV58$ej>6vHMSqJdtKN*JHq%R}Ol=&}4!qd1pWjV3ih2P?#ZU*${R%IS#@h9_J816LWL7k8 zO}WQGbHBBlqVd?^eGZ!YEfC)RIToyS&>WTg{J-Vg!0#jE^Iv~Q2;*Sk&+oBzzJum| zLpvYF++7wrUI?B!pT=O1_$7`w!88Bl7`%CNh2xUoNuKIo921!*d9C03y%O^*Cj9o> z1bH#f>%u30-`wYcH22G~FAnqP`4LESzuxELFz2u|4x004NE46lg);Fw)WiJIcqP-L zK(!}0d}lQ8U5;!w$x-62$++jhWH5S$Rp0r+zYZw)Vly9~d2b+`>a&RP+cxuINuiO9 zGfoSEVfm{wE`C28R<*VAK>U-La5mEt-k+_#HX3df@r|PM)?JTqyl_X}-~27hei;Aw z72``~!=UrB(m-trcU=mf2lZh*D&GXiS!NF7zn~uc>$-vQn-ZQd$8QhgZrisw+KKrU z{Wd!1^1#D?Ml<#tTG4D@&B-`_+%3~<$^phT3k2YS?%Nn=zSjj8S6jjO?1vc`w{|k) z0{z$GhBD0<-*@c7@Be0F{6^Hvs97|MIqTz@;kgrMMx^1tcjc@@7;!g-acHSs_$ga< zByMN&uEUC1nlS$D_$(|EK9TW++PyL4>Qcu49Vmmb&$ci=KjnitXkY|mug4?J6xoom zuKPk!r@*u6sX)5+s5U_YUJj)9O{!Utx!_&KB}J`)$-U+U(tO@+Wjy{Iwk+_Ln6o9T z9FG;AZw@qPe~B8AEFK&GJP_zF=0a3Epn7E5K)OdRPd|y%lV7MvzOOZBp2V{6Zwn=k;0xdOZTYK7yT^2zrf%#A+@iwU$I;bqe%47kb?dJGD0S+8>G4@uKusJ?+%=)N70;Rx>oI zwNMkQBcRu5)$7LEsTHf&u1%~KZBlFOCRRH@um7vpBeqk6Sg(nkSdHVP)^1L$UVvU# zTCa0$r?$0TYdf*p*-5Plo>+|lywqV73_Z^diO{Dq!2yruC>lKMKr}DAZ z=#b`Aa_x@s#K08b>J!Oz06+Xl1|y#y!p34gzc>32$KL0Mu#R{yo_qYWqojAFs27!;-_^;Yq_&t zb%vE6)*-E#yzuA*RgCqxTl_88vvh#25$n-YyhC+sI}psl8<6I)axI;CRvbPa{NF5Q zo>^Z{gs3A6c+6L&nh2M6EaWjiTYCbGT(OA9JRoX36l}AY$Gp7Q7w9x}KJ#2+t?e^6 zTJvwwd;#O&Bhz5c%DG5ux#{yvgZjJYBJG?IvdCI*B=6SmOA}DoWBJ;c>_CZDlk71tgiY#)cD^r$_Zg@Xc=` z^9&dJEC+)}BJD%Ty%Od&$J#?-JgNQ)81iBW*G3$-YdLsV9g2$t&queGL9P13&`-RR z&P=-uT15}X@$^nQaXmD+GnjeOUeDDx-I-^9u}}2Zil=3E!D>e&$Z?@$Yir`We@T(>@tr`&sDZgNkG@#-64(EoN#zSsP#g~8O0 zwQ!^0S$f(Q7__lA)(||GoeKrCPF-<4A?oGx-LUaOb>>NXXDvltOS(SyRS$< z0b-x7&&J$*eNLYi4!zUlW1i(5;jplA0lq$~i@iBFw?ceLe#~_CRBUl z!8~a%@p4j&spYf(i`;Rm8n}F{3Oxl0knZkr+v5%}efay(G zTlN{(0sKSks}>BtWRmW*H~P};s!6d+?wK+U5&N)JypEZ)miwix6P8CDH*X1^*DfM# zOE_h252oOxXE98vKI^dE4D>;2K*Ze;9It^>GD>@!W}dXyT=H@Y=0FeK&q!|18Y&`V7 zojQtQ>}=7#-9;DU+Uh5z<8!91%tz%^({Y*W#m8k17-N|m##rWzF_yVxj8#rG^`mmC3CkQpZXmN|HgWo{m0nX|`Ob3F(|D@$(l{$VB3JeoPnAV=-==Q%(KL+*dv>b7C3GTv^5{ zr<&TUoNB@{=k`~7q1Uf|#P~3#{>8X4rt^yNWK4X-I5Q@mV*D8sf1wLw`n%Nkp7i&s z<1`McJ&lj*hsI6yPvfc1OXIBg$lPY`pK_ta^~PA{LjO8WIpjS4R_-)osTXL+8B;%$ zQ%%QZKfjKv>sjSgQya;L+en^_C4a{9?_wyxp(ZW+t#nX$ai z8O!URvAi!B%ln0~ypI^GoKNDcay|*GoKM0k=aaC?`6R4zJ_)OwPr@qald#J9B&>2i zwd1_6p>jUyxXSq?ta3gHtDH~5D(921%K0R$ay|*GoKJcDf1B^`#C^dz-t>3LIEjR1 z{A4WS>aXMK{-yRR{!l;aeizpR#cggct`myqjK%dsah|cbt|!vWl><+DsT_F1a^Avi^B=}42cCW_=SzHCew)Tv z&aZy87xP2Laz4gb&eIsn`5R+7uVYL+#W!?}iNE-^jxqgR;+s2loW8|V?W0tC(GSft z`MBtx=AVqkd1+qCSn#3wDr1`WDxQMBDdx9)T+VwL)A2PWLw~gw-`p{#e#HElG4(Iz z)r{%9V!q9o_=tHpW19DhZ|)e=yjOg4$5`Ks)b}X$eMvhtHK>-y|6Oeky_QF}Ch44o zP6tFi5p^)HjW~rTyM2k=F6#Ma9h({!2KpM0L$+eRHff>aYhPo0mMxgcB|V&8mets> zc@t*rmI(&_mdzO0VIwx|?FG%9*$kgL>oLVoA6Qo|yK!*PT5Rc&14gdSZj5}e8pCJh zg_bX~8=f0iVT~4r;e25~V|c_$9NVfmoNnM}l*qmk<42Z(A|3sV=)YIs_zi(@v9+JE z?Zpc8I~W9^l|=hiE3v@F-(hbCKcijFRTx#L9;`W@-KbkZEriH=eB%HLHiV zfF?h)8P^)D!=Mvwz#Ny&h_18&XN>FsRsYRuRO%gqvxjsB|JqrN3&%EN);(Qe&~jg+ zPTeqkS)e;Cx$R>#e7+51|LP8|em+L&rfvH0SG0r3yqjk!BwamB9k zF#D{#QQ<`_zMN7D8eDQWR$Pn43;hBh^u4@Gzhta)9G#=fR1-6dzG@{NU)@kPfSv|arj9;SAWqSs2J>+F1JUJxRq1@o? zADN9tYYyO;!D%2YAd4}za0I%4cZF$hvKYTF3CG(_T%qMbZ==?mUD$cFE2JCaV+8%a z1NG~tioYk^os-3A@!u9)@3ev9`!gF~ z9&W=Ni`zhomtID<6+3aPqct?}_cEGR-h(Uev;cE}r%^0!FTR`G6gD6AFxq9>k7>I% zgwG{BjO$qr;*RlkAniVPWAm{?nAN2Q3~J(TRLT;CFMKM)4|jLt)5j=${k#G!ev`?l z*2}~Pp}#?%x0#FwT}<>FTNGAhaW}p_jlzm63&OY7?nbV!k$Boa57c(L8~H*Gp=UEc z*a#lR*XIZDZ}5e-mpzQ0w<54piY(wh!P8hdV=pd5PdFLqWgJPd2P=>9fV@AwjFoM6 z;-@W=7Y#<5M?P}i>E=5DBBLX8t$P{oASxjLbW32ma=p^6DvBU_=02|e;PLlqM| zJQ|{k2?v+fMimqCovDT@CcHRlpo$5b!^)$I3C|~#LKPG0^$kE36RJ%pfGQ^J`a2h@ zn9yKGHdHa;!Hz7bVnX3I9;jl%-LMR(V#2MRB3Dz!gocCCpo$5jzqz7{30s=DqKXOL zqg_$Ogp6ZSqlyVLTBb!66WaYqhbks`w9kYpCj8dP3sp?0{oV&vOt_ya2dbE`azb8I zF=0@>!l+`x*ha-s#e}~Gmq8U1Mz0A(6%&?41fhxvf3E)>RZOT_yB?~TFmYL9R52lB za0^s1A?L9+sA59*;T=%Lgkys`qlyXt?&^vvCbTNh9aT)2^;dUPF(LJq?xs)RZOTm z*8^2d`1gq?s+e%DS{76>Vdx@XR578W(+^clz>RrO#e{~r3ZaS#W8I3OiU}htltvX3 zrj4$MDkjw1Tp3kNC=px(RZLj(sSc``(BfP}R54+}biV3=QE^!^PeX*mCvXhG%5l!0RWM9)UZ%d84^8{|-hV^rvb+qeH)EJvL4etB%n!{PJsL}tdD`u?n$noE^0OL*rS3KV0jiY{O zfH82RD}EdL&C#S&fN>^1HTEo(5*GUg7z=l$#hq``Ldf|dM(+;k@j;tRA_u;RaprU; ze9$a2bojl9vFd>r9zW*`Ia3!gX3p}(VWuCPKkIKa-kk%lX2=bnSNR)T%H_kehw_5o zV1FaX%^$1m&JWIJ{>Ea@61eP10mxj{-|#J87E5&~2n8JeMv9IOeC<;Z!Ycb4(+5_; z@GJ$OX+wYGX7ifZqIEvF+uPqL_pTnsJjx9&^ZboTrJCSs%mHPi{f${)Tj0GnS>gGA z{>DXUiwzfNfktJD7}xG~z#Wn9ux5A>Bj=^gh=bEX^5`N)!Jl2R%9T{GCslwkuUU7z z`S_>fbG-m#(53F!;^I5UriB4UstMh3(~hT(6;}d`2_3rOkno$1=*&e8pTS*lc#iXq zuMLVC`t@_PM+=-g?X=_UHh*Jh^QJhxLY$+)U4NtPl7?8|ZKUI8h9X9FsEY}Y_Bu|M zEn*Dp_B$4E>~uJr7cuS?se)U)w>on4D`MQ(<-i*ALmll#7cs=#0COJP>?kmyh%t3v z3EX%t)bVX(5##YRe~e4N&9SFv5#xDOKAhNUx8q#xB8D+0CuW*)z+vPmV$^?^6;t($ zag=@SZ=|c{jTv^GbX3^yZ#N%naikn7@Kq0V{q4RZxTL?4+3>)a$d`^Q&kGw_ zVmxqejV}(jkiy1~R$kaS&;{yrC~OS>A>zRMG!UAju#tULR@_q{BX~S4WO#e!#GuWd z&|ps?<3qK47}Llb9!)D`n5q2nNxH1y*{hI|rf3Nai_HedniVoeOfQSqx@CvO^$Qsp zo;q;$n{2SZNg-of)~Z;eS62AhwU9CEbxpkZw>P|*P{@dM)W`QtydX5JkkRQ%V?6Ud zBfPm@$Vk7UIi|Rq7Mgk$HlljB!ebRuf>%?4OSQpjZNE8cE-P#_e%J;ZUVH7hd%Lhv zaAX_IR{NpDncv^&`=J&7nelH&w79Nx?Rs=d55Ho(NK*fYAi+w@Ggj!KK zK*fZn)$)Og2`7B~LB)iJxk`YF33aNK1r-xU_jZ7a2_HsQ0TmM}w5tg!Cd7WM2P!5U zDANQ~Ot|{J1*n)Xtx{W1F(KeV2T(B~;BseBG2z9}uApMVmuB5T#e|ucx`T=dAIEnG z6%$r>=msh#Tpip6R8068-w{+ySlyx>sF-lJaw||V;m*>gpkjj0;0B;#Lfng5pkhK{ z-)f*@!sSc`sF={`MLAG0p+|g4P%+{Do+6-P!kjbtLB)jMO5_3+6P}0|pkl)9f>}Vt zgr$$&LB)jmRWg8z33VE}fr<%L^Q8e56Rw|i1r-xMG;jqK6S{761r-yX#is@p6B_SM z3o0h)*H4I<1yoEh#kZ;|CS;i72P!7yf07$iO!(+5AY!2v6M{b$0TmPG4lW5=OaK)V z9`+ZXy2_X^c~w6%(30 zZUZVNH0|03R7~h|vK6S9kdRNjFUXise|i&8F`-GO2B2cXpgXld#e|)H)j-9BP9FeN zOn9@h9H^Mk)=?5vOo&cX1XN78{ab!eF=6+UoS-og=5NX8x7jvpQ>^ z<#$h-XFBQK^N(SG>iCnbRZ+F?Ho6w7el|Pnqv}7dW)oEB?faoQDn4I#v_i$RWs5eb z_%D9k=GWgv$JO6U?bSF?KWcoae>HA&UNxS?M~yS_RO3(ll`gtogo94IJHNb&#Y11) zW33d~oJGAuu>8)>__<g0#uJ3JuHiJ%)?@|9?q574x{__>R39v zhx2WUSWLCA5~h0Q?!2-(7Tfm-#MzhJo$Ig1(ptfpG4y-r?(7{Fi(_&X#5_ej zoDD7=#)|uLVve;Q&Y44FaO=N5c)g;hvzl0|nVH-ZeLi_QH`g-p-I5GA7QLK-*AC&= z!EShEY-VSx?gwynku>O4CyTRJ{61U}=ZdZUyq%+yhht=QSB!t{?F=ct3lB%S;-4`- z&Nr>MV~BqmoIlOi*==DMR+#OEi>hRGUUPp`xSsf*+I z`hL#gxmRMA1!b^xM?dG`t1Iw89tRF?<>x%}W(D3}RRzN;_&K-yxe~vLcdHV~{G5fG zufiKw>*M3y*`0lst;QPdn_^V0?9PM|YcYMRR=DnTHfNB}dYsj)Eza+o&3SP81|Hk1 z-LvBiF(;vW{MfZ@7~8avLHGFGvRSc0k3t6B@AI|~_fk9!Qv zh%t8y8FY_Vua*`|W-DyaJ>E0e1#h$|Y|uUKbK{G7WL;r{?(yzbUYUPCv5xNxyKnwe z%%9tT8+gUMGRU9%srv1tIc}dn_rGO*jQQrJKcCmR`+(UscM;~}K47=mP|W>^XF8v4 z=CJ>Rz4s2YvdGrHTQZV5K+|NQL1=PPpm#l>0*VNtWKmI322c?lMMXj3kQ51$B}q<# zN>G7*)*c2#5K$Rr6me8Q1rZbCn2_+Ud+oaSJjd6$&dm4DI9})D53l}N)UH~!s%q7$ z@KmW!2>DySu`K*TeMPhx9WO%okk-e2IQkCbqfap%^fjiBKFEC0Hz^PLEagOBru^vR zEEmFAUc{#!kPh{O^r<)GOMOBf>KSrU|B#>cf^xCGz>{u1U&`d>1RJ{am7dL0*~weS8GV;);YnA@0>3;6{;?cZ^#L1JXb|#RH-WGjn4_TR4FHe>sFFU zJ92_=+h<6{i?igrlC^_=eM`#jyVB+58)^sJrs=o39~6`N8?=5uFD&EY1?1(lIzjb^ z3Q5L<6JgEU>jd?#EhJCg{8{*yt#yKP`WBY7BkzaboLe`jeo0Yzpw^q=hPHKs%3l_f z)jw_zAAUgRu-!|^%JCBBtgIXK>X#vRrmqiYzEL+gSu#sfI=9%~th- zK01$UbZADnFwi;j_=}}Zky&9?o#$?SI5ea_LW`F9S^t8suR@S+*c;g{xKZ?`#Pv2 z$8lWSlH+)xZOm~T(YEI}zG$0t9Cx&>I*v!$h8@Q#ZQG9Hm$rGwaZUSz<2a6Rj)REL z@e%28+(h~uPmwRjS;)ij7jkl3hWs3_Q7(?-+V_*;Y7>(2)pjM*QQMVFUu{=1U$tFH zdDM0#4%OSHbg9LLw3U(#_L zZ#4K^J!hC0$GaRV>^P3^9a+e69RIKD3ptMCDP0OXj^m{>i#m?u&6gB&9LFCyTGDYG zulRPl<2YWbYgxx}e8|-m9mnwp^Q!8dLWyy_=Y2ID$MKs7)pH!ji%BCF8OM`ldG7p{ zj^p^}`7U)F#~Tdl=s1pVzM!k)IR3$Ty&T8!!Q*>7j^hKLxyf-HfA#yD9mnzAH}rKJ z$De(_uj4qrqJLkK1<2dGhHjY~#_u=R}jE_FWbkNtB zKKdZ@Mc<@6=(Cg)eVOv3kF#6|XL%8ydO$kV57MXJkT3NKd8lW|N&Q29)(iSI>kG^= zbnWYf9LMqRrxtM>$M+5?<~WXL_bKH#j<2j=+Ho9jzNMVwIDXNIDvsm$g{#{w~zt8*6%@rfd90wF*l#KZeH`j(iv&`7j;i!}Rf& z`QqOx4}M2EksjqoJ~$`x!{Ky|dzJhW`|^f}?B#c0E!QIC=fkajeSE8Tu-A{p@p?1%`ZV@>j@fU0djtD=vGxZ2McOCi z2z~oBJ%FhnF!ko!C(0>c>KW|IW#OzBgtNZD$Om%x_$U|CK|42Qdq5mtE(`bNqMU;I zLL6T%uS0EOW=~MA$+tImeKYb|JwEqi12>}FaN{ENtGPpM zLgT;OQ_3yae9Tz?#`OQKZRo$pG@h~kE~dXX*7RbUuJNR;-!9Vp7#=bl`7l26VLHf% z>Ekc+#lKS?{El)WJ<5-KU^jfZ5FP{j_{KgRW1qgU&(|Tom&e%4X^ecJFT{E5_I^vC zN3bt1<3kU|UO&cOZ^oK0^htT3XJh;hdPJJY2kExBrjwRCQD0ym9)f**V=b4}7s7q| z7Vh(vL^_H30wW*j1?=TFW_|f^t1lnl>I>}kWAVM-j9FiZ!}kG{K0uO8Tyw#TvNBgwjdOa{5v}a?lH)GZpe(Uv2Ijz1B z{!8_hXiI1N8uY-r1GDZD`mw&xzJoSq%(_FIU#qVrJI`jvNb!M86>m%R^nv$9-weqq^Ma;|Y!)>q-0`7aym-%$VGSpPlL zc-HszccK2?SkueXbd866x@@uL$M9T+BOk^`K1>JsFn#=GzW8^_gWpk3q(}LY4}5-K zE`;a#av^>Q_URb=^o@PK#$Fyld@rXl@`1h({^VE7v!O?@FE8Um55`_U#$IpC7y2|- zd7x)w{El)WAEZ0={Llowwjq?SqhfXmbajHNt{INyGBX2Dn987z`xK#h5!MZW88aFv|ZjjgEknx=diUp%y zIAeU`^5Vgi(Io^jd{wo0@MPNx#{CBr3$nvn0y(2h*$__Iz?2P4*}#+yOxeJc4NTd< zlnqSTz?2P4c_4F?H}uFK-2TpkCV$z!$J~LjON{Rx@@H4(@*P%|C^J6NWPC8=ApIy8 z>b=`#9NuMV?w!2T-8E;o@vz`U*Syo4#_cAE8~WuQOQHh=f+i@u78^3p2!HT zEK#Oxke{-FDI1uwfhil9vVkcZn6iN>8;l+Pl*6>MtSY7GQe$HjIhJYM?8%mHbLTAMJ!?9+RTaw_Z_m2cm2Q{d?)?V1XZB4TX*nCXL=KFSh1Q6U(yubqIqO)DR)t=`@E*n+HJdD}k5=QhX;>g>PW zc+k}u!He?;8&|KK8sxMYYP{{~;=%F`!;Sw?zG(1G%Mr$p4KEn1`#KT+P>+mYdf!PF ze(#HggUd&3Fn;RzaregYzZmbR^Q~LCb(!&pMSgVM_N_Kff8{54&B*n}b$gw1!zSbz z*LnJsTe4+~@svNFbc2q(Z2aJy6YlUUyNz$Y@_SdM>D$In*UcAvcX)#F=G0Se!l>EC zzm^`Lf93_I&cW08krf$L1Ihb_;W*vc9cVLzm9BEfB(%xKD zewGXISza*p0H%Jx)Ek)k^ka=+tO2W?7mh({|Ak|djtjyuOUDc0Sf=BMaE#OOML729 zxFZ}BbvzP|l{!ud$50)=gk!6YYr-*C$6|?$<4M+W(B!l_^>TtKCzx`ADJPh6f+;7M za)K!*m~w(CCpapn`Xq7qPBuR-j_`>Ee0^a<4;6Z(qkrwM&X^(_T{CghAV-a154Rl-< z`V2Z=3w;S4$AvzIj_*R>L&trgPon;S&{t7ELFmJ%{~+{j)UOcwJnC-T26-=hA8(4SF1MCj+JeR;`#V5575BJU{$H*GTG0v~$kD^&sRo!`;W9G>KS%` zGJvTQFm(l{4lTadE%>!pi!VWY_Tko^eSB-rVAdU&b!zedR@V|~dlG365@{z%UE#Nk z4`zHYS+wW_2B@4TNY`qGm$t)3dxpV3M_+*MR|HBJp$oZm)DURFd( zwAXKdhqRO1nii5u15$$_!#c=UbMi~YNvXm5idV^`(J4|VObr&c?ILZz`!VePd1_Gd z%Wjgt;_H2S{}$+7iLdM4>mrME;m*T!&~~M z2gfF-$&TB%g@;uSZ|OPY@dsZE3!al66quAI+dA(JJG_z>6djo^17;lvzf^s$N-Zrb zCw>~Xza}kM*C10i6gwXNLG}Of-Yj|X(;vg9v|fsxQ&G+gPm$ZTzP?ycMK(T>Upi_% z_FkGTvBrhuVy)kXCu+*#wngN8t@q}S)s<_gK3|^wA*0Xb1?f3%BAxx;oMy3S#i$Ub)FUHTwdo{ajqfg zJS)!mzRt7aTnEs3R-EetI?sx8-9YDAajqxmJS)z12AyZcx&EN@tT@*tbe<(#AJBQ0 zaQ?3ItT^ZOI?oc$_jR5nTnEs3mT-MQ=UKva1D$6H*AsM}C0u9Fd6xL~2h1f|M$G#t z59WiE6Z1sMkNG3Zg?S~*i}@z?fO#nOgZU}-hB+*Ci@7azjyW&u0`pDk0rSD6oDumk ze`L8ZuVi^K-=rQ~L_e6HQg4{IQlFU5QqRAd9^l7P=V0mwOud1rPcZcirvAaK7clD! z9IZ#DkMZ~Km7O}rZy6sP4X3UU&UA1-@KEXR_3Zd!dAv;{cX{3K<&_x%~0UzaJ-+^H+2mN9T_>*!zgwx2TFM{Zan-LxaXj z&a!OxTEhbI6RpNb=@T_whdTNd$(toE zbmKM`h<7hIO51U+yHmrb*B&JcA8+M)&e8BEM#-P5v~llfI%C?8mLGrL&OO?wfZn<> zMlQU!gG>21fBfKWV`W~MtK8dT^2a}Z^ATy*yqA0LR7(7-np1R6-pf7NHzi&@m?pPO?d6`E zenzHrnjtsNzs7C4@wDvk{)EKSdb);|U)#w-Z6|1x?E7d}WQ4Qrf&bNZ;OA|d_5tCv8(`WKFzpPO_6JP6 z1g4zeH$DtqizSIYvYs_|yC;tSl(%?JPZ#BAoH4iE>gtbPW$QK<^m)*=?en-Gev}yp zW7(f}baQp;x3f4=9-7_7jYz-P!tXua#l3M~YvUjHbaj*7ZYv9ijB|_wu6OezZotCT zA-Ley5$;2I&N#EueeU6ETa4#^dYfzbz#GPOTl8`7bvl#?zp9s;n|ac>eE+WQsu|~6 z`U_TG<=*|Otnqfe8$EMV4dWsOuW}iWH!*pbFUr{Xyz#C|ft{wHtpZ*Y=?@dgwc?Y4wbo&*|jal&xYs_=3)EsNTzh_$SkQxP2`P z7%xlh?J8b+%+mbpPrq}u;_n&{o_3eJ?V*>ApPVqvtuK*hd|$iKy07%CF=hC<%+Y#` zGWS&>0~u|@*Qu=q`8st-Gs@98zRl!D+EonkeO|_lgYak@>;Cj^x1~ZYYkQt^BXKNE z#z*>02h8{pw!Pz73(5rpCRBDP*Y+mmgIn9C8NU%LAN=%6e&bOa%LR?U{yc^_S3jK< z4D7VWIJauqAbwqFyr^=S;ImCjjf<>L4|0E)V!ZmxQo-!$BaO2^E*`8pKFIj(HHTGxNV?`nl$tdG5=f5_^IrQWm)aHyp6=ZSOC0PZv34{N`<|-Q0agjE|05 z=NfPP%(zm@CRcm%7siLyZg!P=ereo!;C8pCaDp2Ye9iS=^tpw%=(xwl8XYxmU16VF zyX~-X*LEMcm+$`2+973w%#;mG*}#+yOxeJc4NTd@5 z{?nt@Lr#m6G2(?}`k$5Fl+3qQ-7qQ7m=`1|XR#IWr2IGj7fh_l!o5B%U$19luYY4-FV+TFUuXkN z-`Yt+&sNuz2jP?xO!>hq7ntP*Qx9P32TZ+zsZTKUtmj~@ty2Gy_<3N~7nt=3X8nR$ z?_jnEFxv^3?FYBJRMt0w7HYBBA(O~9^ zCykfBmmbv4zSB5rhxuFdYyK9@--7vDFn^1D{g`WQBg)=?uyF4u7<>OA7V&M2z0czi z?)?yB@1GcZzs1=5GsbfhevYN%{U2lR7a4nh$=Lf*CJ*yP-|>E$jrHCiGxmO(>5Xwv zcJF&w8}>elvG-Msy$@sTeH&x%^H`eR7c%xflCk%ljJ;1~@=&)w*CBm2gx_}K1b4&J z^+Pc3MDE$5>C#BJm7VcXcE$%Yek9!DN9&iqO|%VwIi8}OM49ms9v#c*N8z^&2UE{K zuNTHgIQ=5<|Kvv@4rKsG%R+r3{FmA)!v8<&D#UMp$!A8mm&fAJP9mKB8qEF?S3_x%GeFt22q zoSPthrUPbtFw;T*y5@n?G2HJCUbXp5tah;(#s{{Z>?r^C4?8=S3*q1Fm}oK}{)|f= zGe$ap`RiC?q(AtFQO3x3-Yx%S40&$qINTU=78oR1!g@m9QDiiXrExV2Qb?SnC%D5b_Hg81G621**?K+w_vts zFxxqp?H|m30cL*zvmb$@{j1j3qhdGBn`rV!`QFFwjm=s6n1z?g9TuCoWW4d6Z;yz5 zJa2;eIgEpGTscI1aDkH@!%My&V|>Z;Rl+(oMjC%`W?$Zr?!%4CrCp!bvgI)2v6U)>BN|hrXNH4C=2ritNbC$qH>0i6X7a<2>DfKA>)9*oq0=aPQOPj zyw1DLWBrPcHvZ=0!m(i02;(1`EX&oK?u~mqzrV#NHw`6kB5RyH#?jw~{H>-LGEL1Z zL|$HI)2-KAlIi;)Jb&XRZcx!1OecJc0^v(5?T+2tYqX`q_(+rS!Hf@%#-~k2IBhSO zHW^G?4UUcl|4iG!Z~s}@qW;w{`MO9m>T5-9&RIJ%-`c}()y`n7SKm@}ecRUD)K3;& z-?q7Vl%sL9t%|O1n}4G9F1o&LWsEZ8_;#E0d9*zXeG+ZwLSKdPy-#BC!O?KWM>x}g ztrTQoFA2b=r`WlzO&r_#dK?Xt4CiYFZD?H!*?v~sOL@+{_vJ{m&={Q68><< zx7$d;;t79vXoFU=rdGlq9{NdhDYb2>rIT8>u?&1O;TyN9Uq>=KB>dr`RjbSNdI|nx zvr4k_zC@fCmt@NO4HCcoab~L2ykW7WGdL)wd!!4ETSy_QhF7&mOk;t3Rk9Usg-_#;fwG$;%HW{Ndet_xd~MB>1(R4Q1NK z1do`}OkSCth_Akxz&D0Hq5gl)>JtilV1%o$DDaKJ>iY?NX0ZBx0$&=eHd)|fgQMxI z?INBd|y)n+UN?nJH za}871CxvU9Q9I1vqF?j3VEz`&--7vDw7!N721nV_lOJ-K#a$wMx;w+C=zOy+rqFjdg8Pbg$OZ z*ELVky;@^k3l-g~HP$s!(Y;!ehxwwebzMtzuh!Pq zMfYm0FY9`v=w7X{u0x9M)f(&ir08C)v94RnzLo`ybv;vbuh!DkbxzT}T4P=R6y2*e z)^$X@YPXX#s{nKZSld3501u< z)-QdVXd3`?JViT+GUFpWI+oFo!fzQ4rk)`~lo=o4(e)zwKM1E^1g5_PrVQX{S*SyV z|597Ea6e}R|0BBM+zs)6X?}-ru5p2*Hk|z$;q32V+5s@_1DJLLeAaIN`|UQ`uy0EO z_H9g{|0qY}__;$K;`=siYu8a`9HbMSYv}sC=s5?QgLux1#IZCPAL%n4Fylwq_KS5d zPtM)DxH|fp?&XQ@1>2sZu0@OP1zQ|lqZZu@HrBOk(Y;_}UDFob3pTr?Yu$pqW~8HQ z;G%oM#=15xx)*G$Yv!6xO=De4PloFndosSRy(iPrHTh)vx>ldeSJ&{9^61)rQchj- zPs*=*0n)R@b5<@Nz6rAV_<3NTjcQD%nnC%42_5)_S0<*n=*$%;MpJ29IaI`(M?og+TmM)a4 zw^y|Kt#xpTto=0G_}1nt*plv znWD!1$8V6FE5Ek(^TLiz(mZ9SalL7wOdmGKc>f`h{71SNmv}BNdC$IWZPJfxR*zBk zK8b~U-^1AZBw@r~GWO$_Al&;l#@^>K_P&s@_mPZs{};ZKrQ>}nWAAGj>;5l%Fk{{S zg>Po^Fkk50kEdn>bxjODp0OWK1^QzV9_sezI;0^2!`($0hbr*Q#sekm`6QxD)@YGaW&G4TIXM#S;*Tl`=0pApB)V{zCw5q{Q| z?#+cBeyg?=?a;5Wo6qCd-mOnXnQ>5-Xt-auxA=ZN-&p;nYMpFg2nf92V=(fGGJYoPh2SL z*OxVZqw6JdU9n8#b$dHVudgzU7rfg|_6|%lu2}VYSvIqz@s$tskvAVMW_-ogzH(ly zh;hk}ekUXL7ckEER$m!0@*Lw}ejmB+!INg|I`+6;&T03Z@zV3U%aj?%On%A+nJF8X zvVkcZn6iN>8 zM`d%=o678{Pc4h1p0$jQ`q#2M){E-IvA$GS4)y5eG}*lTCL5Ttfhil9vVkcZn6iN> z8hZ+i;ew0va#P^Hun3@#wf3@-5L9RYGc2DZS428js1SNvEK(bMtPYI%ByRD z7LM}j8lW-Ct80M9D6g&o8l$|FKU!Yu0p+EBz|le&= z2eUnZ*-pT0KVY^iFxwkA+74M?XsawQn0f$HKVa$&Onri>XE5~-X1#z}UtrcFnDqi}vVeQ&j%Y`*=V+!4cZ9*OaBPRZDxUo!URnoJ(%i+1AA#!yb2kD~lI zH)T3!9O&Gi1+s8|M#$Ko9WwT3ij4K#5zZQsTaf+PB>om>mW=&bCS!lbNp!yoZ=}U> zHz~M6$0qSTpPvlDT{7#$Ym^ycaki|k6mOdLg7K#Ni^Uh0I%-x$1Iy$dT{6LxGR$muy$&UBxe}^Fc+eb6wPqlu=c=SUB zq=|s4r{pzTH}T_wCu*yKm>t zx084xon-%V_?_=B&bK#|gjD`xoSA z|3bOgzZh=ijr1?31D!B^W1lbdsp(jMH}-NGd-;t!Z!F3F#qu&f^k5AAL2h3zL3w<> z>|a)H-@i;B$PaNM{mVuAm-F>#_2uhV5Z~9kv2PE?zMaGo2kjm4z-aIIJvh?8T%>;? zoc#;&*}squ` z5Bpalokafv`*16-kMAPs82j{%*}oF$B>ESa{R_o<(lyMWL3yGraw z*3Y4n|5U$g_g=R7jga9?@2c^y7k*^*_0WlO@kMoSwEDX2NQrp6_ZAyJT>K|lz5GpM z{Kfy{xA=F&1LJr2Js9aBU2w^I>#~ub505ci<2%OJbR5&s^c~aJzmECpzXy~@e-}_r zO)sGQnvacZ$jgVDo$>JDK>L2k=Uc3-9-KK|nW6X_fc z5f6;t;rC#qhjhUOx=&n;{Cs$f;Tk{2_?l0Q>1g_n>FZz155LuaSGg1N=;sC^zy0Lm$Ww3_T$~yhq9U0{d`#bJNE+_URb=^ab%*Ux{=Q^#x{qfmvT* z)|U^r`ttFuzQA5TOyBAY;a;B>?)6MLEkDFzeI?SlHThW8thXgtNZDcLnXMqrQAN+9%^%efe~(zQA5@7KinPaMl-?^#%6zVsf&+P>+9) zef%&|@5Zc0gtH#Otj9!}XZs!WaJJty5wyLt{VriA@un^IHJ}r|bqhZGwsIA-W51=h zm7lqGfW9@Cc>52`H|D^6dk)Mu>A?C%p1oBE<{NfkzHJA_n|1g-m~Y{MAHLP$?LUUw z+j%}d-u|<2O$TrP8S@Q3#Npd~V7}Q0*5BD%eqjIhUmjTVv2iUDo*RiD1N(H0`L-a! zeZCg%<#7o2Z~qzlxBrZH-rEvy|1mrda`^brgR$3-vDX{(wYL<#JkX ze%2S>8H_UHAe_Gi`?`yPecc&ThD17Z&%WEJ`e9pzPS}Pc`uTr)w=t2<-};)a%Ydj-i!T9WBkScBM$x@@xb^Ueh)@^NEfXAZV~eH z;kgXg_%X)UbYe_L(~mKI{fl*H%A@O#33>E)Sl702O%Lm9CcoyB>~}ug+O3ZtgAAGv z(lPew8~c16;&^$Cy`09H59Bv4yRT$* zw+Cb2P6Xk;{TQRY{{pjr`EcuBVBc<;j`c5u`*v>O>|Y4?{la8G`$c{TN4rLT zV6=D4uOs2PU>`pQX8!`Se}R3z4$S@q_HtS{`xnBsT-A^t*q7JX>w)Q5|3VzEHw$O~ zLb%tn$>#NM%>IQqtS|JVzsIac#PR7^Ut>KYob?E1JtopTYbT)x)+3np7}3xFlbu98 z$}>0ExCY+Y?mD@wcLi(1H#F)j1@p}^KKa7M8gIYxYuD7#chE`+;^Qy=KatM<5b?nF zJN-Qv=^xj`C|h zHm)H}A8u{f$2a!r82j`c;`@A!y*$QVPGijn@*7|J!qn=>&zB43W&9BN`Eo%&#$Ip6 zC?E1e9F!aRfuRq}FCjnlXyNQ@h{OH`X8!`Se}UP*!0cb(vv%^|ZzpkH5$#>ueKuIz zh4lxpuiwP?gT8+u+_wiif9TtZG1@!Y2jWD)T^kiDi1EcQr459fXth-2jvoowagtP9zth+=y zW~tDVI8H)H(8|0mK( zo_E6dYrjW0(nGpno+tF-Jnw|~4*B_X9P$He`i|-AUpr5TaQ$~XPYBlE*?B^+=40mx z!CEdmPZ$ZuK0f1Pf1K$U`}B={zCj|L3@&w2a>Em1j@&n_%1M&k$&RsCv z%Io7h#EG1{!1)p9&p$9D&t{{r(o zp%1tI<>Nc_FR-TLn2vAf7S8^KIP70w_AfB|S0bI{d0mF%{3qk%>>1NBX8%IC&o@Y< zlRT4_>|Y3H{{sJ-=i#IFFv_eu)Gu_2Ismioz^pqk>kiDi1GDbHtUK^o+h}Los5k3( zUZ2*dyq=A{{*9xyk@bZ$Nc?sNdwFDkHp$K)`7=v)1_{hFNZ{xhq$vMS=a=x?=yyi^ zo*lju!@>N98s95Lnelyi^7~~C$9?JMi$=e>=J!56U)-^5XS5g};ruoq%y00){5BuV zZ}!1@_fhhlFTM98`JNZ`fH?kb2+NCacv-mrP6|w2f&JMeiyzfQ@@Wp`yH|BLBGqh@3o;5{a(+$;|A+@d=B5Gg7y18hwoCs`rRMyZ#UNO0h8hS zonSJ)w$Wrd`dwi%ef{3hz6VD-`W>Qu4-Urnw)lP)jC#TMjNpIf-Uh^H`v?tCO)$UZ1Zy4HH=baA`w8YZp#wg#g#v7x2!y0dl z@(pXeG0Hcr@y00Mu*Msse8U=VjPea@yfMl*tntPu->}9TqkO{}Z;bK{YrHXf)W2bk zH%9q}HQpHI8`gMZly6w$jZwZ~jW}rSmTXRzG00wM)`&{-WcT@)_7x-Z&>4v(c~M}`o<{Vu*Msse8U=VjPea@yfMl* ztntPu->}9TqkO{}Z;bK{YrHYaH>~l-DBrNg8>4)~8gGp94QsqH$~Ua>#wg#g#v7x2 z!y0dl@(pXeG0Hcr@y2N64Qt1DrP0R7(RK^wJJDdi9}VWa(qO(f4dy%4V7^Zc=DXF= zz5tGfGd{wZ4w&hKnJ<{~fGKCh&$0ETo)=?BVVQuX8K^J4`%vcrVnQNV5Sdd`p7Ht zhOF@YVubVkVsKOj#z#7g4`zHYn42rxO%%T!ncpxSGh{~_VL#bcM!gP+-hh$ z;oHaEYPAu*ecbhlR>HTBdmqRZzI{BS^o7E=k25ZBBz*gL$K<-gw~wF5S4;Tz@t|k3 zg>N4>UR_1__VKRb6(#xh@kd$0w~wVortt0K9a*J?Zy#@bBwhIS@v+Hi!ncp#a%sZ1 zj|)sn6TW?1bY!~l?c-IcrG;-FuWOJgeEaz0y;;JykBgmCQTX=p7YnKg-#+fWG+X%g zal;ceg>N4>f2^+X?c;WB8cF2sMWko8%kBV7@^N<{QLdzCjG;8^mC~K@5(z zXTGhBHq5-h%nQuCz|0HGyui#0%)G$Syy)*Cyz8GP$rBl&`KSzsjiSE?yA)-{*Lk{r zuXOgiC+H!v{$}fN`2U1{Y&{V3_y72JPtp29owDx098YQD!;^Gv$mu&Tb zdG3ylrHlt3?C!pJt-SG~Pxr+ZO{;3$y=1*5kQM1@c*t;#FO0A02-DH@1?fXh<_lIi z1InrL2b5pS6^z)|&SZe_<5GXw>u#O-osHMeuR7%(9=6+f zajTL+)76WN>;0iz5Zm0xxL-=uAn&zr>>ZXWd$NNPb+5HIod;H{794vqZn|Y&kaNrP zneNK_s|4WUliJ4)_s%AVWQ`+?Lw^Z!Mmbu)<40GGA6fIB$#BP%^6^pQt})p*UQjCD zzx90ML!-{f(-*vET)fLZ>Db|0+^i8$)>yJjf~Idv}J`W(x&I66mgn>#1u)VYIORWTu(&M92!b_rHJ zyJz+!;;`?dy#G!+gY={JP1|0uwt9C#xVFh)dD}k5+E#-)`)@baHXOV-f3UH(?I5Sk zP-AWL!SW8njkPZX-?SWItbHU{_jMv%`%duP;RzP5eacN3HQQMGnp?SbnX&dk*KOZw zW9^&nnvv^`wa>a?6Y`9;FS{jMwis(4cY}_+Y^;6X9e!oEvDySzrRm$odN;4rcdzWe z;+{2jJALLd*ckNN$ z-@@DReqG%`9>3mh?APaw{rbGIU!OPDIkLT%ir?xS*u~Om5W+<%Q21JTMG&qSGy?J?bwmu_}bI0T$AM~#_OMG?M|#b zVd;PMZ5#LcpT033S-g#V>-gu!Z+v)>t9sF4<1-UuZq_IJja43f>m(u1n$C^GVz~)> zq8uZ0jt}|ux5D3Qn!+?SFJWFPgHQ&QO(>hnERlb0OW54uX2IBbNnr-BL>*Dsuqtw*|vi5iOY+}r;ILPeCL5; z@lh|FvEMd1a&A1Y!y)5R{foxejd|60uPC zc_{LFu)tLLq;_JA7*KzvY+SnC;(XU|t~_)7F5{B=PRAb_CB};t^;byw!f#smzPFx{ zFLv%RF23e@IXLjo#_cAE4E-_@J}h`qns-XX-#dAy+%+eWPNCkrCF5`+{pcK-dp(dX zdKdRE-MNi8zTa8C(LK=U-H*S8`>y}l`zN_Si!$;~Z18{T-f2H}n4Y;840-$*WZ~Qk zMmYC~!G6rLINJ6c)=UttZPl@@YI|^O586%~+ljUx$M&P`%CTK(dvk1W+72Dtp|(%Q z_NndGvE6EWc5Khu&K=viwtvU=uYEaSU)KH-u)kn!Z~*a zbMF<*xigq^XE5i^V9uQ_zMngTUwgIq63m@_xXqn?e49IiId=wg?rib>+!@TdGnjK{ zFz3!-&Yi)WJA*lQ26OHV=G+;~xigq^XE5i^V6LZuxy}aW`Wu+*a$v64fw_(c=K3C( z^Kmf!4KV!;F#QcM{S7ev4KV!;F#QcM{S7ev4KV!;F#QcM{S7dEBrwwk9E3(PZM zV4e*F^UN5SXUV`kV+Q8gGceDjfq7O9%rk6Yo^1p3%o~_z;TX>HB0lwibf_PsPrV`E z-|9OWJadS0{U`3vN4`803+B8S%y}`G^I|aHfdca#C@|lF0`naxFyDa!^BpKK-+==2 z9Vjs0fdca#C@|;6V7|)${(Emaa9-@w`H#O9#rHQM&u{I0NxrWK*`jY^@~upS^9@Zf z-_`{4%}p@h;so=JPB7o@1oKT#FyHzF^9@ii-v$NqojWk!5(V>(Q83>g1^+wVc!eF) z_jer9_x8lt+ZkhTe~i6dGKL*fdu8nHnDMRcJInoFOgCOV`YL&;$1LMJ7Iu`Wlja(4 zS$DbIIc&ah$G6)^!QzXIhc;*>Yicb?@F&fs)V8I@sdXF6z&Do}x2a!8GCM3cE?Tv^ zOs|*VKQ^l*JMT-xd2vamyx$=4+aG79O3fP_mL;w_E)G#5?S0Gkot7%yoM(*X_Yvw+FZAxJP1*j+)F33ce=&7kzHr zdEj>0Q}|2cLu)rnrJf0{l(I=`PyWKfkB(X=jW>Q~{N`<|W$wNs#@pUsCQlbRWLzR; zkrcS$fU)jX$(KL9Ys__f$guRi^my&;J1sn=Ur~IsWvqK)GP3(tW3JmHKG*HRZ!a$z z-}2#&_T6sw$Hn8Tjt??k{bi~6?CB$oi>yzN=l(Focv0mt@y|9bHO{SCHXgq&G`{-j ztoXoAdyGeIEEjM5_2l_R#yo z7ViCIWA8s3L;sZ1``Z?-cHZ$#aJB!AZ-VQ%;398=JH837<47`G$CqS$9e0xH=y>G# z=D3bij&G6c_@(J2-YC~`&GGGW9q%09G}mzu-(N398}{M${<4p6?=t&zjD7mXKHm_( z_3{{dIgP#i#ySq7T*kh<#$FG`UO&b<4x(JfIu4>-mamS3D3`I0gD97=j)N$d$**sA zyZ)00TDf}nndU~^zoP}@98h|?tJSh?E;z6G3|FG=WaC#}p6T{JAjT`gS#IalkBl1> zn(LPD$`?a?wP~(Fxu=YE4Mg{apEcGun%(*mdB*xiv%Bq~myPv}W>+izuCcz+>?&S* z%vj%OcKccuu=b#DG`pd_5`DS(oKCJy*(w&UZ#27a(&`zj4R_-YJOILZ z9stbq0AQX60P{QmnCAh&JP!coc>pla1AuuR0L=3MV4ep6^E?2U=K(z1c>pla1AuuR z0L=3MV4ep6^E?2U=K;Vx4*=$Q05H!3fO#GO%<}+Xo(BN)I|Zs)0lg0kiqvU0dwCC%zZa7_uatU zcLQ_Z4a|KvF!$ZS+;;y+ZLzbs;K&(WiJaZVnS47-44Hq%zxtjU>U@;`a)f^?!f=*Jx8=RrU{Om2^T## z&a>iRo*_pZo-N03?R>kJEy@4ReKeI5-}+fzVD9CCxyJ|Q-XEBIf?)0yg1LtX=H4Qh zdyY7p!MwoHaK=YC(*ZMmF!Kdd9x&wuN9E@}EW*i?0L#lfr>FwgLSqi1*+2kA2om~rq; zsDASpbT2qc@J(p<7YYO?YL60p6IyOgf#8Z+qXgfC-f>5P;Jgl_1>c1JwPAta%2s0p z--NdND1Y$O9b*OGgccl=KPdY4BZ6;23zg3w47_uk;G5723-blzFBmWQCbVOvd_lX4 z69wOdKK1xH!Kez43%&_$c`7BSR(p!zo6wBDDM5i&(*)myhSSctrdQ7pd=vWT8&13K zJ)aPK6MAiH!qPw)KRow{+c;G579b-#BH>{u-LCRD$f zbrX&*7JL(0T*Gr-UM%<~G)3e0>a$qzP3Rl%fA1Q~BEdJI6Mp}L+w{&t!8f68>ip;m zhYJMXgcc}x!qxiSd}*rRg!Vpp!WH^pp5U9%FN>XY$8zQhz6pJ!-YJ*bdA8u2(Cq6@ zy9vFY5PTDQ&g3(0N{<CbVt2{6WjR#|gd(eQ$l5AV+7xXUZ(ZFOY0rqgyz%suuj_pz6tH1?IfqpDEr2ZZ47OmtnDz_@4#$tV75cV zXL|-m!x@<+b8Z)VEe>f3T&UaOM&eZcPX%a;w}ZY zPu!)z_KCX`*gkQW0^29U`@~%e$@ZytDX@Lw zE(Nwv+@-+wiMtfoK5>@<+b8Z)VEe>f3T&UaOM&eZcPX%a;w}ZYPu!)z_KCX`*gkQW z0^29a>Nf2p4UR0=y@&1K{|{BW*pehQ~5{7 zw&{04u%FAG8XcS1DI#Y{duZ0qke5nJZ(X^3ns?&;P2iE_PVIw}SortY#Ri z+c!Oc{S5Ej7F*XeJ%Ig8Kl)nit(5ct_OoTLy|F5ON?k8o+*Dkaw=TxO!>;`>A)KxLQ?G1K7{k!*g9N4Tt^w z>9wM6wZ@12oZ7yKd-w9x0QR$Ii$d=0{;2`%XURqR-L{FT0qo}k<5S$rd8q;H=aU6a z#J>J4HGuv6Hs^TkyYtcl*w3}kej2;4XIcRJIZ+P8%4&IGKU?3oH+JvNv;g+=u|luM zE>QizeqKL$TkJg58|>%$R$=U!ThasA&zD-Pi#@D*hW&hb`N~*R)j#a#cWW2M?$COH z{Tw@dcInexTNSYxeU*w1=v$Hn?-y~BRam_9bPTiXNd=RK=N z$0leyfjx}0N!&AI-`OFY?G4O!2s_F6;AlAGBb@2LezJYSezJYSezJYSezJYSezJYS zezJYSezJYSezJYSezJYSezJYSezJYSezJYSezJYSezJYSezJYSezJYSezJYSezJYS zezJYSezJYSezJYSezJYSezJYSezJYSezJYSezJYSezJYSezJYSezJYSezJYSekR+e z+E2Dm*iW`k*iW`k*iW`k*iW`k*iW`k*iW`k*iW`k*iW`k*iW`k*iW`k*iW`k*iW`k z*iW`k*iW`k*iW`k*iW`kw4b;8R**+K)(mdH*SYQQl$R}CY6gc_UgGv&P)?fvu4Zt{ zgYDe=k7mjZqiP0A;~m|YPt)a!r)vgVFYD~m?kXvp_ty+=`>va7)4HfMEMF`5X?0K6 z?~(lSZm(KFkM6x(*>_Kb+veAT?Q(rD{xaNqI1#>n#li4sy&Q{w@~*eSw|<{v>0EMh zXZXyX`JSqi=_t<~gEJiE zOnWuWQGT>}mJ8u5FXB@VNQe4C`qUfpr9L4K^$ad{2ab?N4vhS3dc5g(YXo-ScwR>Q^-G_@ z9MH`gTROgf#3~EFsB4+{SF*z5KU+RC{%DD1md^e^XT~Q#ve?qEIjn4a{>2L|-`h%N z#Rs&XZ}MC;Dl4A5Zl1}R{+F!ykkNBZ{+6lb;+MZR2lwx~8r90hTThxJW(RyY`WNG) z-!UEZN2ZT{%6!p(DG&NJGgm*x}AK)EO@CSGY6#N0+0R?}6cR;}(;2lu#2Y3e*`~ltp1%H5dK*1m2 z9Z>KGcn1{h0Plc;KfpVn;1BQ)DEI@s0}B2C?|_0oz&oJe5AY5s_yfs1pwu7W9Z>KG zcn1{x0p0-xe}H#D!5`oqQ1AzM2Ne7P-T?)FfOkN_AK)EO@CSGY6#N0+0R?}6cR;}( z;2lu#2Y3e*>;Uh8f69hI23@{UT(TX{z%biz9-F>mD^m6*5kj!Mj1c}FGYt-PZW^H$zbiFqsU zsKmULcT{5D$~!7CZ{;18n78tdO3Yh%MC43shl8uHOq}{zBP8`{+yu1go>`l@lCNaC29xN51;40{&-z%=LNNc@8dOGjo8z% zc(>ZYBj49{%QIKTDh;e1OuW0HYy0@J*mVyk=jJiY&9$v!o^Jfn9nLL!eOc_J&fiDQ zxx{TP{#0y@&g&oU*UpXT`E2ZUo$uFK*3p%E^o3YZwRTXUfxce7Gu*NjHG?7@%ez$NvMfq5oYklp>*kvBWCX|DX`AI0L;bAnTKGTfad_s0G(AjkB~bwcQze0I$+v8H`?%`ma1{g12}zVy59 zLYwe(w=P1PaP9O?LYvUWT_LmycinQS&?X$HeX-Ccy!%W{A~pg3Ic-9cN3U-nv5&{;p4Z{gf^jckS4SVWj3b?ZNllE z8A6+I-{~?!n^0j+IiXF+%&0813E#EO7TSccV2;ox6sg-lXcO)qdx6jnOAdH@W_K}ZNm9OdI@d9 zZQu2jh)qcDZNX=tO*p&Hb#|ZYpWWxG`QtURe?pm{`?t&Gt+G93LHo?$zJ5#PhKst% z;uD#{=7Ni*>)5O1%O}bP{SPjX#f3Xck*Zn2v7+QT3udz zEGua8#60=)!OGI9LRPS~(tMfFyS&`=c-f%fnFZ2zMW&qjGBe1izgT|%Zic)W%M7;8 zUMhQwrc05bWrC_rR>+5~)1?0MrGpb6JtbF6Op|kmgNf+ObkW>;9pPd9a04JzgsKuumu*mbQ{PWm1EapX5n{ zN7~BCYf^(MKW&nEKeU(2T)g5g@t50$q zZNjIA8n}o}z}h}-LXwAH=^Smslhs!iKbVjy7T1MI9Y&!e3sz+R-LtKhVw5 zCVY2UPe+?DIjfhWO&I$@FGrhDX<9Ewn=mYPjiXJN{ejLSyiNFKVi!l7P_%C+N1L$v z;r5O;pu3{N%s$`IChW?o>Sz*L$&UBxe+S;abZ;Ncj6c=-8RO9p6^t)0 ze83og@&Ac*o)N?Y<9GNy80jHh@W4+VT#WpDc#Pp1-||Da=41JRHGRkQ^>4s@HJ^a; zXg&eu)bs+%ulWS}z3LLAJ()+U3#4`9q0<>LfbI*`3AmRkjL1|Y3$`s#Q8eChOax8m+@J5)Q^RGy%|U94)U<> zsDG0uQg_MvDmSdKo06Lq99q0mvU?SEExyVM9xk(7O64!^cFimoEL^%oO5Re+-PO2! za98g|(rG}3>lQB`lx@F2@|`K`=3iJL*zo%&rAJyNH)L*wV91B+V?S2S_4uMfkiKY+ zwC!HY{i#;P;J)W(%dnpH-L5Mu1`R6AmKTRKb+vD(82n-HEO~fgu6y&EiosK#&60{6 zE^^CSYW$wFrN*L5-MSJLgX=2Kk-YXD+`JtXf-9QOmGZN$cFhM?2#(C3Cu0V8cb(6a z5B?8(?;Y($m9}jf5m6+G2qH$1tTaYW{ZLdCQ9%JEgCrA15D;??NShT=KoC%pAd2x+ zVQy_R+UBg7b8JJ~&c3S7wXOBd>a}L(o%db+&Ga8G?zP?Z?0Y}=bMLBO?W#Jj^tv(K z17E4$7~FP=Os+4J+Jm99t4O{bnTB5AW<)5@y9%uk!%HYyo+-KLeE`!7hp zXgMai=FKLR-k&T=AAEL9Qmc8B%0*Y*n)bP6Op^59q%teHEgf|8=w#8AjVrsne0%!# z6C;zyS8ZH*@z6Wd4Yxfksk`aMm0`Evo%VlpNb>EGjVf2YdvCh)Lj#g89&1?X{6=-U zMaO>0q+J_UexIJD7dG#m)Lz-3a#zFq(`V-Fm)tnGL8bTZ52Qc7xL4A*VS~!Gn}=`q zuBs#tzgNF<>5>Q2=}UJ>ram2>(fI7a^o#R4CB0s#Uzz^OgXyYc+a))DU%#?^{DbLF zXSYmNbZSsJF?}Fy_39SMjTbejoPO8+=|@wVB^&*{L1oP0E7M1pHcl3v(y(&hb7|Uh zNQ0zlgGQB&ez`AQdvV>Q);*0X-+XvadegEx$sUpKDobItPf%|5k~{&#Ou>GAc_bi}E(k_}F4QrTmlC28;Zqf_gr`{N^1>u2B= zho#ofpp`>X>!<0x15)ef@NN2~)=z^5y;JMw?rZl;t)Fe4+AFnwKKpAWwSML=*d?`o zJ~^vXYW*BAwq0ud>~&Vl)cRTa@)oJ})9d19srB>TlE$g^(|S;Y)cSdQLEY5)dE?eP zsrA!)T&P-KNt63Kec{_{BwiU`e`t99tr^|RmiO;YRU-E}ult)J`9+B&s<#vRZ)wSG=NsAFpVJUf2J)cQGfW|!3ZnYLn& z)cQGL_CBfgv*&&Xq}I>b(+*CppSj}?O|736e;JfoKVv2hORb;3j2n?!Kc6ohm0CXo zT8>GrpG%${lUhIP-7+S%e%5|ycsjJhqg6Yd+rF}*&ye)oO{=ReyRCg?>TUzlb=SPT zYV()dSGK#fZ@PHxMOE$o-oCQsk-gGNWp35_4LVdBzuhA}?}?dJ>$L1pnO$eEwCCf~ ztHyTjP&t3CP$vgYt2#C5P-*e@&S}#j*H*RNqeJD3dv-|g`|{eVpbgM zu&nCzx7%0Vd%u3V&a8W?=H1u6QrV+!+JC}BRdX&2xL5c_PK&3jh74<8IeqKe=^ZD$ zQkAu8UpemSTIojJR#*M-al6V}y=tY89r|_Efj76SoOn~M^dA%cQPtlr3o3^W5xpe*X*00x3=04Z9a@4R5)At6|OX^N(TY2iqdg*)pHcp1^)3$QMdyUe^ zp4l{Mv0mHCluI^ECssF4o_o4Y<=|zTr!UprGWq$2HkDg;-X?weo~@JS({1ob;Iq`X&<&sHr}&MWz$`DN;?f}74~M@RMr|^m44NvRkC3BHkAuc?3ONX z+%oCgyG`ZwL-tJ%9k@;McGxf2`MU$s`&Vz7tbJLV$~m3-q%+dZlbu$!sa*2wq3Jtc zH%&hIp-tuaWN_O1>c+`IJGQO7^3Jey$-VWHnUmU9TD&kKO~-GLthusnrPc4F(rz!V zo7}c;yUJz##-y)*@O#zI2ehkm}CD8y`1Hte>DV*R|o#rBEy({rz#66@#GqpA|?=f}z266*urIM9-de~GY%b+SU*qi9{xUTP5r!eZQsQDX)?Z7V*NbyS&zi}X}#%Q ziS_fhdX>cbIq0*U6YJ;jhj&Pfd!L(?8>HOty>GB@4j))DE?yEVg{R24M(LdKHfO%UH8s(hcgaKS9jPryLs&0 z={vg&O`kZuQMT=k_ofFNFfiT!^@iE8H&&+upXryrw_n3->(N>I)pNbmI!`yqK3csp z{o;t8=_5xp$gXepKw5wC-f8E}8f4$D^IOD-|=;2+`sV~&eX21Gi zeqU~nC+laweEDFy;@1vo^Y`m#M=f|TJ#C9t=~itUWW8Q^Al>bb@HZ}IHOQt+xIbO^ zd6V?j-5O?lg=>;2Yc@=q{M0a;-=jMH?wY#k>1m^^%PaS!zmBhyzIgh^*?=*3r8C;r zP8;=XoE`b_9qIIkYNZ34Z<3w5=JNF3y=$cpf3-W zr!eq8YnrY4V19c36Lr&#zigU)6W+61_vr@d-4{2@PO2Z?l{;;d zbnAwjWp&oPF+J~r&C;LG+bkQk`^dDi-n8`9TaIxziU*=E_%(`KaIhxSeH>#4F?QJZ+x;@wnvlM=_UOJ zrL#W6}Y;u92S5GpyB@j!JiEv0i%e4{a+~EI2G(d~@CO=-F*6-5(f| zcDuDvI;vOO%KhKP1)wm80f z`rB{Yq(>aqrgG1)u4$d+Ez@_qx2Zf^)g`UFQ>*mqO1>wXUN)*#+PF)b%56hBrpupd znfBSMP35pxTBRduZJYjSc$-Sg6P>l*f4#3c-zV&SJz2zeQSfXYolj+bfI5xWgfx4!7% z>dmIKubkItWO~6>&s2YLNN8^}I-R@kYt^4^*1j_4#4%~RBR;JD^o@3vU)~*)KDpxC z>W8MctF*m;OnSxjKUYs3*RFC~tBn%ZjZPElB(58MKUgnu-FW%jT8Zn%IYVnDt{ZFg zT`zIn*m#rm6W5Jh=WURKNM$Ni0 zVd}8Nb>rBjBNEq*r~W=Faou=!_?X0XW7(Ty64#9dM~+EcHy-_IRN}g^!?hz4*Nyl4 z4@+D(MjbLJaoyPE=0g(KjnyL#N?bSYp4~HX-Dr5`-ihnR?ajI-t{Z)?*d=k@xP6UI ziR;EC7qm@WH;xJSnO!$7-M>ZRy0Oipn zW8BBR64#B!2k)1-ZcI30uf%oZk?xhmbz|3ByCkj~wZe6X>qg&e+a|6XH&5R-aoyND zJXhno@$uD76W5KV_ivoIZoG7Q{ls-+y-zkwTsKy4R3~xWSnucc64#Bjm)A;MH;&t* zR^qzRbyTgybz{W4W3uMm=2Yem>A12{kI~sWeG9x}^~h}diwgYWJ|nU<-!AapKMv1c z>UUG#KYL+V*6hOqH~M&JHuBQBdHeBQhGtjxn3v;CpBs{`S#N%h_ggX~Tkv{;Y45$@ z=GcGbaku1{IA6A2kYnQSysE&Ad&dCoSI5M0m%esv$X{( zw==IFDh00hz!9;%)8$9S{!8~78{_nR`j{BM-d4xOaTo1)d?ugt_v15pHaqQv$p6>* zC&YQt?tJNQ9*ARph;QB)*L=dqJj2uc!(Uy>dJS7+NOskwOY-@4Z!|a?xc#kp4bQ#z z$gIKS+w%6UubP-$vCkbj{{8B6vWD-k$nkm`OvxJUb!U!`oOng{!Kk9W?M>HZ5AT0_ z-oE+Z8?)K#FU#?sC(h4St|;={`rbv^`p3-A+nd*2mUTJg#vJe3>-OyN8?Gz*k6Dqe zIR1(pAGp_@S*LZTFE3#cKJtxOg_P!%)c)`RR|1#mW?D$)c%<;KXmSjVI7@Xr> z+TEHpsy#TL*Wh)J%=)%lp5x`sCuaTEU6JDfr<{}3S$JpB-e5|0cb&U(+UE=^6$8ZR=aI z*@qW={$6!Rtmg?!`o?wXmg5h}&Tdus^rZC<&H5fy_;mid{j>dM6y9t$Y(Vzi-9?>D zt}`e*_RhkC|EgAhTirK1zk9K6@BHU}*$p=rYxM?m4#@`oSgg-aHtnBX-@eeO@0SCz zSGq09=Z+W5C)j-ct2{HWv9FBD=gz#qoU{JbeE(Ja(Z7w%?jK*|YW4PqWoztM)tam>-}k=^&Ynj&#q028u;ulL$Yrh9h%Q&Oou_)w;vQW^YNGcvlF%*l(&D> z{Lt)&Y)Fo$KH4wqIcs>1_x`SLR&UwJ9Fw=cbBjKAY%o9D`mqA<-F;qmN~fWDpN%h> zo3(hmz)!t*Q}*~1!}9iv4!$Yt{Y4S;j@Rd8Z&ya-?eCs9C)@q@BK}>y=VY7jK00rI zrZOkypZ0rCEIdO0>;8FU-iJ7UA9r+&f6>EZbIiE)K0GGJ@VR%@u{nn4&@+$AG5lA2 zQeftFZr$Va_BH3<9NSMAdrRy;yXAry=i{dr#Q5!pFU%Zw%@-F&J}K{&tOdS^fJ8 zyyJFrv#rk`lGoVbBX7#G>xw!&_ntY~IiC+J>agRSti{BlCfomYc6LLXq9*@2WpBzi#}QudEVV} zapZqXm&I{jv^!t=n+M{UAL5%g#xo_2s%$-ML=19=MLR zPPo3cez@+nuDE`--ndS-4!M4I-J@OK(O=&YN8b_O`e$5y2OoV0Pkje}eaF1?9oL_> zb6skGu2+r2b*%BZzI9x#d*#FRuspd=mOt0e&Wm>EOMmk~9P>kb^TxR56F%k{p5`C^ z>QdGVtnaw~R9~)3)t&2A>w)W7>xAoD>xb)S>x%1V>y7JV>yYbb&tJ6bJNoN8;#lXz z*LRGo@8F~F;HmH6ukV)q`>vZEm3{e6f!|tpY_{?C zv-0*w);>0?)wjTB)jB?VaQ^~d@cRkbq^1SF?45DhwOMiOIx|kn?(S0HK`kd{mt0+p z^_Mymvi|GM$j@aL?K>*x&oxZ@V@G8TcAK8J*M4(U_IiWsbNtO!qqCjgD)7pwW3nOF z-H^ABe&Fz|c2yClbE_k>c@Gx2?uw(b;jL%peeM`GHtTmxftxftHoNAM0xx^@xNOh! z3;fdMCuA25EbvyH$7OTZFYwA0AtW}5NoZhhS_1Q;*igW!7 z1E*()yfz~51Lp?I3VhAjqqClGOvu~sz2V4g_{D`@&wg=u_T?Fq^7cl@j>#^$>*O3? zwaw_PQR`E3{Atrs*;{`-HOF=OkIdG%;`9Q)Ga|e8#4~gJziO?%Q(iebyLrf@Jf9uA zACTboUP?WH*j1@?Yk8XZ5k!Io*rj zfX&97kez?$N%>eU9~_tMa8FT_r>;CHYdNH-$w|E?X7}H29sZH$(e;ka8opW7#>g{{ z&xRd8KF`%HH=md-pLt@A`<*;KJ9a{G?Ns~2ld|J$9hYd1Y3d-d@Gcm4BeS+8-0U%uVy)a;;vg^y;vGdX){QsJ-pt4_{F z{iXO_(BdDHvfYxxj~BI_oDKf4xYsoB<4IY&dBy#uuRfZXT{XG5FHvuYiP=|&75A5} zeRM*$RlnkQYrn-4vh0B3ck8e3PRKg#UHoosdgR3H+s?)B)~<$`&^+ez#8Pb8l z`S{{~=6CHUXR|gf?lb&);K|wc&lkAK(n;B{8;bjx=NvpKd!^=n=90jt*1pB>;y)cd zDeK&#_+9+`Ta&V-Ulw@6H7933-d^0R?0NCz?6on)@8!4dI3=6CR`GkeSKZUHZO$+7 zq^YN8-+WTwGSA1pK0iCZ{nETvj~y{JyT3t!C*OHx_TpPb|0UUV*?lvLv3@;ZR<{3; z;`jUN-R5S`?KC$(cGmD)vhF=*<+$^Wi?T`g6!%X?zOy9zeA$(G`ymaNX15KVn&U0n zFU@Lwc7Bf6=x}Sce)Gbc<$Qks-uc;6-!08^e%FMl*~zaIc;C;i%yzu7$oa92rf1t6 zTd1tK!*iu3+oXWyF5_~6Pse*IUM zX0IPVHOHgATbea~^ZXqD_T{bF%JhsJm+SC?)pN6UTTjm0%UZ8Gab9+Ha!Nk0^0BSL zSSPJME$_c+`&+Z`+ZAi$``0YV-kVj#Ipf{MS-NkrmfqHAady@A#Txrjr$yPbLyNVy z`JM~2UtccPky#4PhK zb1rK!?&Brdz_U-!=W^k>OR`>T73=CJYb?puTUg9-!_kYgxn~sX@FvR_W$Rv2tj`a8 zzA&5lw_@E+nlH>MhZT6k?hCS?cPQ}N$J~-N=uzNfrr(@>G_SxtpPQf6?q0n8KF z-L@^_d){xny4_08`(V%eV9)zt&--A{`(V%eV9)zt&--A{`(V%eV9)zt&--A{`(V%e zV$LHwp4D!p*8pIz0l;1ZfV~C)dkp~g8UXAy0N85)u-5=!uK~bb1Ax5-0DBDp_8I`} zdJccjDYXBqd3jw&AFus5wmjdmcIB9!r#RO06!?Xj^AyPWV9!lp&rM*@gJ7>$!Cs$(y*>wfeGc~e9PITu*z0q!*XLlb z&%s`wgS|cndwmY}`W)=_Ik>D*Sv#-8$(z5Az~9#VJ_7su2<-18u)mMM{yqZx`v~ms zBe1`Z!2Ui0`}+v&?<26kkHB7cF&D2$G~3Sg8lu%SmivIYon$aPHNExeq3$o%{K4qh0L%aQb`So<8L` z-jk<~_vFFelLvcG9_&4Nu=nJ_-jfG=Paa(6=6!fLcpo0@eR#0<;lbXA2YVkL?0tB! z_u;|rd4b*2frEQPw7WM1c5evm-VoTmA#gdL<(#`uM11#&!0r=)-6sOOPXsP&;XV;# zmGyFOh5qhQ(#QQE+TGWq-F-c<`+9kM&AuMkeLb-IdSLhU!0zjT-PZ%VuLpKt5A41k z*nK^)`+8va^}z1yf&Z0W?!z)i_hG^A!-Cz11-lOmb{`h(J}lUMSg`xBVE19c?!)H& zYxZHm?!$uJhXuP23w9qCT-L6vuX}dP-90<7dv;*=?7;5Xf&WzvxVOl-?k$4dTLine z2zGA~Og(cC7VO>!*u4+1dmmu;KEUpMfbXo?`vAN50e0^L?B0j%+{3g#_cp=A;hrbh zy$`T^A7J-B!0vs3-TMGDFYdvD-TMH$_W^eA1MJ=h*u4+1dmmu;KEUpMfZhABoqMqM z=N>HBy$`T^A7J-B!0vs3-TMH$_W>^J1!nJq+HlVi?4BdoJx8#6j$rp3!R|SN-E#!H z=LmMs(RTI@?9ZM8*gZ!u@!5j_yXOdY&k^jNBiKDhF!N&X1MHq7*gZ$EdyZiD9Kr56 zg57fjyXOdY&k^jNqwVZ{*q^-*uzQYR_Z-3QIfC7D1iR-5cFz%9){Ao@&kmuf&klio zb_ndVLtyqGc-AHFAND4A1_tc2LtvjB0{iR`*k^}q=h-3q^GptyI6SKZ_SqpY%V4ocV`|J?dXNU6sHO~%#eRc@UUWPn%V4ocV`|J?dXNSN(JCygYd3Fd~)(gxtduZx2dtjg01N+P#*k|^@>``7F_f|-}+JNF!Ech3>*o+H>jN3eU2VD}us?m2?pa|FBR zXuIb-_Z(?=&k^jNBiKDhuzQYR_Z;*7HG7WWvR+`%ckcD0uY3Jq_xi!^^@H&Rd)8q5 z!d^Dmy?(HJ{b2X{ZTEcVUO(-`VQ(Ewe9w38_0#TNKiIwg{Mg_-_VmHb%k!Ok{j|H+ z4|cB~>|Q_Ey?(HJ{b2X{!S3~g-RrmA^PPMBw7b_2cCR1oUO(8qez1G}VE6jLWxc#l zPP_NX!QLkad!HQaeR8n($-&+y2Ya6!?0s^u_sPNDCkK0<9PGVWu=kd!H}9E)y=M;g zo;lci=3wucgS}@C_MSP|d*)#8nS;G&4)&fo*n8&SGB@vg)9!t5u=l;e-uDK3-y7_G zZ?N~h!QS@(2Yv z-0KE=uN&;WZm{>d!QSfzdruzh{sP#&B(Qr)VE2;1?j?cUO9H!>1a>b8>|PSsy(F-E zNnrPq!0si1%N{A$p?f9d**!b3dv;*=?7;5Xf!(tMyJrV>&kpRK9oRiPuzPl3_w2y# z*@4TsE!RVtb2;b#llSEui{~7?2MG2aAlQ3=VDABfy$1;P9w69zfMD+dg8wJ)jXM_O zdLKUL@c+^tvG;F@S+2={w{=@?@RS?aa|+mV3fOZB*mDZla|+mV3fOZB*mDZla|+mV z3fMIeT(0?l=XFM&aF!?7^$_fO2zEULyB>mF55ca7VAn&i>mk_n5bSygc0B}_^)2%h zvu3*f&|gfuT7dtZ&qwlvzdXU7H^H7a!Jaq4o;SgsH^H7a^Zx&ZJ!11o9M>H3DW=_h z%rd4=d5`jcm;GfqGZ#67-4h49Ck}Q`9PFMr*gbKud*WdC#KG=~gWVGcyC)8IPaN!? zIJlhiGG{UQcVCkJV%p1lWdFPDtICn@2mC_VTrgn0EJJiRnHp*nL>A`> zY)r5*!Nvp|6YOs~;`~CMo zyT8G~{sss88yxI!a4`IRuHN6^wEG(z>~C;68f1-|Ps*YfF1gj%h9l`1dR!6Wpg4GeMj<)~jUdsQodnx~UPrUG*@1f&6-%rPP zzPIi@XZ_`S?%s2@{eSX3arX=GofzNoUOB$Ncf4;7#&^7j4#s!9pAN=%|JghEpWQof z&yJdLj}`15E7(0&uzRdv_gKO1v4Y)W1-r)zc8}F|&v*ZMud{eh);(78;~p#6Jyvj8 zFEQRJV|C2^Rr7u>SRKLY2v$e1I)c>^td3xHwB7TaI@121z4D>?nx>BAL><9C>w>0Y z+I`-McAs|w`@B=${%`yp1D|(-r?@;Xu=4^tue|-=_&F}0abjL#IQzU4?LO}W_IW3; z&pUyA-U+PkWn7L4HYV7ZU}J)f35FZ*ONtkS@8Og&W7!AH`MUg_1fQ$)IY#>U93$B0 z7{NZr2=+Nfu+K4qeU1_AbBy3J2QfSy7wouT#|1ks*m1#*3wB(vDk5q%Cm*#XIcNdpD`}KAMx+}J_z^je20bmsN(1Bf1aT&o>}^LeukEF!GE5;ES|;k*-oC(;(KxI>Hj-Ed#S(v z^UPl1uYc!f_R7z${O1{}iMgl#uRKFlerD$1?KvOcXW{#kUK4_S-vsRYCScz;0sFoQ z*z07l*N0%Q&%s_Rf_)zi?E7e7-$w)cJ{s8f(ZIfs2KIe4u-E@!um8bb|AT#>3+($` zVBhBg`#u-gYksirD}jAq3GDkyVBc2)`@Ry`_m#lDuLSmeC9v-+fqh>o@Bd%;Zlvc# z;`lxS*!K~@zK;O*eT2M!&HD&o-$wxZJ_6YH5x~BWVEcc*Wg4C__`mrrQ?EJ6q1T*X z-`fKF-WJ&Rw!pr(1@^ryu=zIOojy@R}e@Ygvt-x&101KNG>0PK4QVBb5iUA=tofOg+I0Q=qn*!K>= zzIOojy@R~}{|~-(=KTcb>u)`<_ZGl@YXa=ICcu7c0_?XYz^lfx-$4NT4g%PB5Wv2J0QMaOu+&>0@!yDz`lb3_8kPU z?;wDE2LbFm2w<-U1<#svlbb7PO{Fhqgc(g=Z0%l zhFn(Q7WIEkZ2$bgZxj2s*yPj1ICB=fml(gx?r$WH`@{w>C-Ql8=NA%r{_^H?iToEf zdM!hv)IP_=|Eba;$Bf%@gN`|d&sEC{4A0K(w=dcQ{{tr# zn0ZaRyui%YcJg3<@?#wGW_oCZs7IDMc=j9*t!Ls`=ft=E8CPGxN58;RAHiRL zF)w|`d~GKW_9s8aA#cVfpN>nOOjdozQ1FIca z?eg{-?Z9dWRy(lTfz=MIc3}1Ld>7`Kc)q)Tt*$x7vxCoQpJTinyqaS?{z&J#ImY{c zKWvR0vu1Yq{#D8q^#W`l&j_+TVWBAP4nObtaIX9|BS0I;GXQ*aLP zkKJS695e3qb$jF(KDAdA7@i9{?pL%2{trzqF!S2*ssb}#+sT9d$&Yc!oAJq~W5x>WbB^H<*6kdlU0Ba^4Ck=U7wtj2u>R+mIfnB> zj%&^rIVLCeuUVt=c5-O^nl&wNC+G61Sp)NSw3C0$ni<=}c`(QH59h}iC!9BPO#E;@ z%`xMK^K6dc6VAWYA2)sKIC7X z=pui#Loam{tDU-sb7kH~?Pym!u-bvu4y<;0dyRHrwF9diSncxmkSl5ctaf0v1FIca z?Z9dWRy*67yZy-tm^kDLtaf0v1FIca?eg~EJ2V2T9a!zaYL~ayXa`n1u-bvu4y<-y zwF9diwG_C=^8(kRo-epY^*qA0tLGQ4X+7_7t?T)S-w2+kxHk6u#Wl0%HLj&S-|-v4 zcCNkc&o#MmxK=kl*YJ+ZwY_}!jUZ2cBgmiM2%hg~_k2Nr&m+X~{6c)sJB;i32tJ;t z;OY4b{+`#Em*+d?Ydd+cKlw2Zc{4uwbX@W*AM!6xbdkS$p<@}V9qnodRy(lTfz=MI zc3`#3+iSD~s~uSFz-pJb*JuY;JFwb;)efw7V6_9Qo$a3Q)Q)zw1FIca?Z9dWR=d2t zMmw5^IF%=+nLME@daj%A5ASVbGMzG*q>Y(ha4K8 z+&V5fmk(OV6Yb=WcFv3Ts?XNQ`OyE<`M+n(mpDI8`z^=BpO*fbW5%s){Y#GFGvdXc zatzNc-}!rv;s3>c1!i6Yn-rM&+D;zqPkxL;-i%K^9hW@Ihy2SE?c}ds>c||`m$`%0 z4y<-ywF9diSna@S2Ua_<+JV&$taf0v1FIca?Z9dWRy(lTfz{4-=5Bv-0#-Y)+JV&$ ztaf0v1FIca?Z9dWRy(lTfz=MIc3`yws~uSFz-mYBaqbJ(!G(9i^~|?B4a+g-%H4Vm z&oSrFKOJ&djybo!x95l)bIz?-e`JoiRyqBy0&|XT(P>oC9gX zJ{*u^#=W;`f#I|N`2Kl2JQw|RXpZ53`K<+JUi(~KV6IhcClB@~KgJ<%#wVYSOP=LJ z{^iNFiu~0J9m|+L%$;_%1FIca?Z9dWRy(lT>7|(|5oE+oja7>Qzc(^XgG2Rc?OF3pu2-i_n#9^%n*H<}a4GGs> zIc9AMIn6O^j_s^P_GgVU4r`b3S<@VswN5@Y*B&_s*358ClH;0dmDuimc=~&Po;cyR zZr+FZ-p^-T@AJdQ`~UC^*TZ>#_`6@gyux^SJM*=jJlLQ77>B$WpL{wld6p0PmnXW& zU%k+=jMa{IwF9diSna@S2Ua_<+JV&$taf0v1FIca?Z9dWRy(lTfz=MIc3`!$ow?he zoPgC1taf0v1FIca?Z9dWRy(lTfz=MIc3`yws~uSFz-k9pJFt4;5j+^yh5XtHZzcmi z&oQ2T{Gu;&jF;1Ezs@lp-)!8sImY`FHvB%vteFQ7{2|Az6<7B9v1ku#=A)|%%-Z7h z7;C2OtVQ-`jWP~vm+@KC9GA6DKCGGYWX+U6Yo_y}ea*jpl=Gqggt;H&m^f!&^L~zr zzx93Z=9qCG-{PGd!{_to-^wvO7r*&t(H{7pyl;V-*XoT6%$jLCd9XkEF%Ee%KKXQ9 z@+=?nFHdxlzj~o#8LJ)bY6n(3u-bvu4y<-ywaeRUv;(UhSna@Sm$%nw2Ua_<+JV&$ ztaf0v1FN0w%-#Ov1gv&owF9diSna@Sm$%nw2Ua_<+JV(BZ?Dk~taf0v1FIca?Z9dW zRxf;q2fZG{n_j2kS+C#lve$KZ-0MBO?{y$+g4c(v6<#;8hIl>6+TwL4YmV)#MfPWn zG7f8(@mbRxm$gnlteNs;&6GcDrt_lR>ood%{YD(G>xl359^-l)2p_Kx;pufF{JoxJ zUS4N1U)#xp{mGAU$eZ!Wr{j`m`H+8kqKo|13mwZ??Pym!u-bvu4y<-ywF9diSna@S z2Ua_<+JV&$taf0v1FIca?Z9dWRy*6h&Qv?v)efw7V6_9Q9a!zaY6n(3u-bvu4y<-y zwF9diSna@S2Ua_cJBw$-}{8b32RW! zhxp!CWL)nz!pHlN@bvy9{Jn3XW*LH6zEXrkvFEtNwqqud!8u=|AC%rFkFXyuGr(#9wf2 zff;xGi3Ntw8p8?<&mO%C4FA483(UO0!Rz@P=>w(@$AUSQm|$Wu7MQW%0EPqHz;J^z z7|zTE>>R<&k-6JWPV7&vz{DYkVB(WoFyoSQFnrJg3{Nxy!yoOyY6o6$(WKb_f*&Wv zI5UTy9OM7>zLVp)yKFEy*N$UPI$(0H9r%LNCP)51PM@4>NBcW-C&&5HZXW1weu!h< zh;Kd_*F3|={KHdS;9u6OtfTtUN8LHrdLX8C!dTW19IPw2S#NN*4xJ-jV2;);?bb8> zt#jg7|HRi9jH_SZqmSUJzu>R$!k&F>e|FwcvHv$a9~I-g{_K%4{?c(r#&NrCePrab z_Pa+!p5NSdMC5<=RYyeMO}qGrIA7Y$1O3epam*X>%_rlUXZVoS&kT<7PdagM z9Jkh1gCn2E-yRfs-o0#4H>fD zVqWS9R$uz4JI7iN#I#Nr%ld(Xbpk~-pNwms;bZ>csV?v@>s8iKed(j_9BVxg(>h@+>jw_j72K>h zIO{v-i0_!AzN1~=(O=&YN8b@&-!ZPfgO9$0r@n)~z6-w>V*8+*ddL2!?btiU8S`|n z7=O1Ddc|>{+@e?HbLm?LMxLiFJuvd$@QMSY@3y}1z&Kyp%>(_-4{^*J@y#dWnrHZ! ze|V}3{MCzjsUui@>7(u(YdsLtI$pSO2{WC{>N4vhGzrG`mz9YWA zV_ba)AAJW;eFuMir*@3{^LYow{x5%fP>l1%z=LD_rgtA4$Gvd9K9SEOJ^DnRFP+>c z^56H`KGAobX7`EnrQJNx-~15Ayb<4gGOl@skNJnEy1>7zS6N5(rH{IEto1-l>x8ka zA2?W7aI@avtnZv7zGII1j&^-Ve|<+BeMfwK$GG|qKKc%x`VRj3j^`L{-(t?5v46MD zd&W5Jp6V9k|9)JzIPMiKx~`xOk^id8_K3dw==?q6d}%ii^fy1mF>k~- zpNwms;bZ>csV?wWFXp9=VD+Vsx^t}cKuqg|v8*3BSXXef-r%h7oFnzm9Q7UT`i}nk zjyU>``1+1<^&Ncl9X$0N{PmsMF>ZJuH};?L&0aCi?F06X@!!64?>O!OwYo<>Q}*p1 zdCr*BJ@Vi1n(oneKhEkN=S#bJpuhPcj(H=#`D9%43?K6kPj!KRS+BB=>PsJW=UD53 znAQnnSwC>FuHa_9!CBuqM|{T|^&Rc{j{f?NIQowG`i^n+9eng1JoOj+_1%sQc8={I z+_+QhU+Ygh#W-I-v15$?$gw-daSz>m$H=GY8=WK1^_Fyw{I9*VbM)P<=XH+rrQJNx z-~15Ayb<4gGOl@skNJnEy1-w(n3p<&)t5f%&au`5F|8BEvVP!TUBS(IgR{PKj?_PM z)OWP&JNoN8;^;f#>pRBPckt17@YHwk*LP~ixaXd;bL>Cz>z!kqll$)yf&S))IOdJ`=96*FGknZHJkpRBPckt17@YHwk z*LQq}#P&tATF3rR?a(^Lx$Cdn#rPK=vt1mwdGqZepSNCX6?s0js8!@YIha}`lvg{S`WmuP8iGjfrE7gH|q_~ z`p!90|IAU}(XQ|4ukVPX?})GO7+2rHN8iCy-@#wssU73)cXpfDf4i^R#5k2h+s61u z-O)CV`|{fDBA>?H+eMz+O=uVSPrI^R^xfGr+Qs?OZXW1weu!hp$D76Yy~j3-!YC)uxf>l?$6j{##9L z8hy9RIZfkyX*Un_H$TKNZ^SpBjBB3ZWB%c(F7Q_`=B18c^`(!xbFB41OzVWPtRFa7 zS8%i5;H>YQBlXW5^&Rc{j{f?NIQowG`i^n+9eng1JoO#?^_|)=?nY-dkNrRYqIrz7 z_92_c_}kyUc^r4te^U1j8 z89wG8p6UYsvR-8!)t5f%&au`5F|8BEvVP!TUBS(IgR{PKj`)r_>O0!?9sTtkar7PW z^&R8tJNW23c$|XT8ryf8u~F>bzvD(RPPfPE#`qf_T{n(z7(_-4{^*J@y#dWnrHZ!e|V}3{MCzjsUui@>7(u(YdsLt zI$pSO2{WC{>N4vhGzrG`mz9YWAV_ba)AAJW;eFuMir*@3{w=?R+ z{9IG5_#X7x$}i#{SJatQq6f`pX(I{%c3B5yw4d(={TW zp-X?S$aA+|zgOfxpwaK)dt1f+`1!y8v*LVdHxKkTKg2O_#5bReYo6g_{^6-E@K-P9 zrH)|rrH{IEto1-l>x8kaA2?W7aI@avtnZv7_0Jsj9qsy#{`!tM`i}Vej&b!JeDobW z^&R~6o!T+(^wZah{U?34R*duKK5NJL_bppH`fj^5)``9w(`}vTyGbXm6Mgs5rRzlB zt-5ZV=sViY1O3epam*X>%_rlUXZVWR}X6H{T_J6ql#}(sD zyZEDu@w-0zVO}%v9M$o|yq3TpFa99S zcf`?m#MgI>tMA~W@8GHL;IHr0j&ZY}K8^h+|LwCF=jNL}kMaLGcfO4L2X6LNt{w3^Z2wi9FYV@m{^o}`=8gE~lX1;6e9S*Q)dl`#y~;YOFMZUV zW32~bS|^NU{lLMxf}8aQXMN`!sbS`*?`YR|^w)R9(Rakx7mTZ4;G>V=slVW_@51wN zvAs^GXJh|fhddMGY<=O=G5%kldMb|lWxJ;$pYaQyj68eq_hjUM+(u7E-(CO96LG$@ zn+N)vAL5ud;+s##HP7%d|L{~7_^TK5Qb(}*(nsAn)_Nc&V^L#_W&Oaxx`Lba24{We z966Rb>O0!?9sTtkar7PW^&R8tJNW23cpQh$+#WwZ7yGaC{HhqI)9mMC{EG*@ z5XT+!>kE<3JE#9G@?7VwzeWD5H+?bs?wZ+IlNa^^L*xO`z(+A zf8Jnu^j*uJZj1A!-8|6W{1C^y5#M|=u6c%!`G=>vz+b(XmpX#gmpeh)OYaLcWTGDFMM}b?0?y_ zcgHx@Gw+Gv`!ey`hkOW1vl#r&ic+dhFm7hQQy&SJ=0&` z5l7znS~lf%2dHP3H1eRX!^|4XAe(Ra^mHz&@Q zcJn}g^Fti-Mtt+hxaJu?<{zHw0{^mJWgXR*KI+b~)&nuE6UMTB;9yx^U)<*G*#D~o&x&!*|NV>@|8G-H zkK=B>-)WIgtG!Q+Jl{U|l*oVcjZTTaoA}}6IA7Y$1O3epam*X>%_rlUXZV<#yY)vn3e}01t zqwfZ^yfDs}cJn}g^Fti-Mtt+hxaJu?<{zHw0{^mJWgXR*KI+b~)&nuE6UMTB;9yyGP`c?7na0`TZIDME;%E-zWNR>bu?Jd}%ii^fy1mF>k~-pNwms z;bZ>csV?wWFXp9=VD+Vsx^t}cKuqg|v8*3BSXXef-r%h7oFnzm9Q7UT`i}nkjyU>` z`1+1<^&Ncl9X$0N{PmsMG44mN931-(zr1gZb5Hw2V*I1#92&>n^8Nmi&n6!ah&+ca z7#R6)(PB{a-DBMc#re{19_Vj=h-2P}Z$25&`!$RG z*AMSu8t1kjHi_|nKdW&Zx5w@qM?QVJG>SayoYFAz-*26U(RXv+Xb|U1yLq6$`5}&Z zBfj}$T=NVc^AAsTfxmh&FLeZ~FMZUVW32~bS|^NU{lLMxf}8aQXMN`!sek6E?`YR| z^w)R9(RakxcZ{p=;G^&0sqf&g@6?WQe|ur`*nh$$Tf{ieY`0a6f98y>`RSp=ajQ>yAd%0rN3TrexyPqzBLD24)rtFe$1ST) zoGf&S))IOdJ`=96*FGknZHJkcza&5v;!SQFo5D9*Ak3FqZWL2kQ!M)*GDl zopYrAnWMg=UEk4P-w{XO5ntaiuD*khzJsT}gTKC0JH~A}>xI~Vle#a*IFEII?T`4| zzZu7!cKh3r&$;Qlk!PdI`;q^(tykyT5r6fh)p5SGn+N)vAL5ud;>Uc3am_P)%s)KU z1^#8d$~vkqebk*}tp{SpItgQ0KX9MVRx3pW&^taB5WBn69`XY?0 zU*MyU;Hkgh|A+4mitV@mvq$Xz+?IRBIL9rkit!h|u~QuPnHP76e13SaedPJl18pMz z=RVmk`mXc-+r|0PZXW1weu!h~>?ftc0_ zV_83Nu&&@{y}?=EIY;V~IqEyw^&S279dYy>@%0_!>O1)8J9z3l`2XR%LOaHt)4G4` ze@?AoG0y5qqyLEC^XNG4`3D~#`3xH~KJq;6@QIQCIhB*6@3wg3(_-4{^*J z@nb&2xaJu?<{zH=4*q}muFwuIglp-jFMZUVW32~b#ySaOSwC>FuHa_9!CBuqN5*1~ z`i^#eM}K`s9DPT8eYY@-tMA~W@8GHL;IHqh-rl{X?cdFM?_T>~*KO-D;a^=S#bJpuhPcj(H=#`D9%4 z3?K6kPkje}eaF1i5v;!SQFo5D9*Ak3FqZWL2kQ!M)*GDlopYrAnWMg=UEk4P-w{XO z5ntaiuD*khzJsT}gTKCee|}Z29pi@f-Aettl;U(L#qUxYw@ZmnRf%U+iGLN^)y%7^ zG~cRH9;!ns-G^U zy2?4zCuot+1spWW=UBwqCZD_QrFyO^)p=E^{`1_@pK(im=~D7hmy*AB(|2J#No@~) zOzj_hni?ngH`RB+*Qw(Mzo+sE>p&{cus)>vF031=z6gx6X-U z{S#kbFs^=qk3NE@zJtHMQ#-~D=fT)NoF8MHaNhhQ{u?{Ral?5w@(JhP$TOUmBmZ!| z&b1?cIFHBq(rzB;Z+?hl-iROb8OAlw@G<}JR2TS{^(yPAzVuOdj(AIfT$jc; z;d(X3Z?pZIaoliy8~KFm-pDgt4@dstIyw3-TtCP8(rzB;Z+?hl-iU8L8P`0+$Na-n zUEu$RUeA?ud@kxsA9d$g>w%co31eA5aImi6X1&2#-#JI>lR4@;+Vvg%^&N5a9r5)Y zV?M*U<{3WbAD;RS{(tzc&<-zz->^|%`lvg{S`WmGbrQz1 ze&AqT!OePuv%YhVjKv)F9qsy#{`!tM`i}VeF8nr+eu0m^gQvcOzrG9i#4_8%{g%xB z;XX{Jf5ZKm%=qEHP3E}aeoiKzaGxiWXSn~9$v@l|$~@nN`$d`arQJNx-~15Ayb<4g zGOl@skNJnEzJtHMV_xbAR$uz4JI7iN#I#Nr%ld(Xbp(DvkJLYKJ(r!J|-#RCb^-p|#!MOSbKKclr`V0R0E?ld`_OQPY`-gpp z7$@vU#Q0&KB90sOFCw3?uMv5M{f@{#?1Mz#h5eB@U)s$B{mlPsJW=UD53nAQnnSwC>FuHa_9!CBuq zM|{T|^&Rc{j{f?NIQowG`i^n+9eng1JoO#?^<8-8A-0G8^w>Y_v&T4L|2@VJ`|@$z zuwNhfgnj(TGwkn2{$bxg`Yt>V5a&y~d7!`fA&z+?zWHQa^9&#J4^MT0zj`q*bp)#~ zebk*}tp{RSCyZtNz`?qLoAm}~ediphf99y~XxDf2*LTFxcf{9sjH~b9qwnCU@8GZR z)Q)k(b1bocc)lgZ3D3R6_~Ch&IPT{Aofi3o=Vv0%@LWygAD*{~z6;Oc#QD;09_Vj= zh-2P}Z$25lVMl)i2cz!JQ56_jwIN^D-7(YCR7RL?Gr$s*D zxwXhMJkJ*Shv(d)@51wMalW*h2l|^I;+Qw$n@`3y&+sw-@KhK0s~7W9N3ioeC!+Q{sPk28f@(k}yME>D@is-xWo<*E5?dF00=7%`ujriu1am_P) z%s)KU1^#8d$~vkqebk*}tp{RSCyZtNz`?qLoAm}~edioQE_s(E)-CP&j{f?NIQowG z`i^n+9eng1JoO#?^pRBPckt17@YHwk*LP~ixZ%CL*uU2y&%`+4 zJ-!$}yx$kc4e$L$KH+`9$TPer82N|y2cz%8dxdenw3`R|n;+tsH{zR5#x>9IG5_#X z7xYQBgZmF&v&%zJNoN8;^;f#>pRBP zckt17@YHwk*LN+#-{G=7ybl}uhxcS-obdi^j33^sjpK&*Z6lxX9&Y3r-p`Hv!+X2Y zcj0~BIA7Y$1O3epam*X>%_rlUXZV}H5AUbPIN`nZ z7(cwv9>)#uxkok4kx8=Uo>bHsPdQQy(7@93}Zh@pSA;JL2m*#?^Q5(Rc9FcktJDYR9(_-4{^*J@y#dWnrHZ! ze|V}3{L6ZkbyQ#as5{4655%-i7|Z&BgLMTr>kZD

xD{%+b1~-Fl|Kbxs`XpZNNM zarFy)^btJu7yR{I_$F0s58peA{lj;VVw~`Oq!>SZH!1oqd`~I*E_`Px`YwEbDf%va zmnr%#e6K0`j&}1vfAd2e^G1C0$++ejKIR{u>H>fDVqWS9R$uz4JI7iN#I#Nr%ld(X zbp8<4c{?~e8Tt5BG2&Mv&cVu4=vY@_~AQgalW*h2l|^I;+Qw$n@`3y&+sw- z@KhK0m-Q;^sJ`@3caF6lh-sZLmh}S%>k4kx8=Uo>bHsPdQQy(7@93}Zh@<-zR*T3dd{;2?4Bs1!{KIz$ zqwm7^3FCZeHxKkTKg2O_#5bReYo6g_{^6-E@K-P9rH)|rrH{IEto1-l>x8kaA2?W7 zaI@avtnZv7^~oId9qsy#{`!tM`i}Vej&b!JeDobW^&R~6o!T*O_^xK`AHKI4U z#`xj;oN?Un-Ok7-e9trT4Bz>T{KNM@qwm6ZLF0UBHxKkTKg2O_#5bReYo6g_{^6-E z@Gt9C)=_=wqwXAQJrL76VJzzh4%QXitT#C8JLib+n4`X!X;>K~q_i`hj@EzUAGkjk+@(vz+b(XmpX#gmpeh)OYaLcWTGD;XBf?fB3$1j1#^)9pi`Z zQO9w^cd8?w@crt@Gkn)N@(vz`v|l zSx5DykGgZL^*~JPgt4q2I9OM3v)GeMcO9M|^$9xcUx0`VOA@ z4*vQsd}BYhhwrz?{^7gsF;4j2dyF5x10Tl?--nNU!gu2%&+t9@$Ul5%KKd?ve?HEa zcJn}g^Fti-Mtt+hxaJu?<{zHw0)O>lUg`)|U;3y!$661>v`!ey`hkOW1vl#r&ic+d zQvb|R-_fq`=&$dHqwk2X?-*C#!AIZ0Q{TZ~->DtrhQFH-`-i`$5aWcuvk>ElzrPU2 z4S$y*@(F*hA@U4=$070$f8QbcF8tkxIA7Y$1O3epam*X>%_rlUXZV(R-8t5JAf|P~Sk@05tSh)#Z*bOk z&XM|Oj{1&veMf(NM;v`ee0|5b`VKz&4xaiB{`yYs7&rW#px8hB{h$~p{9U0KKm5I+ zIBxhmM3GPU`$Umv_`5}sfB1Vw(RbnR9L4$4ZXW1weu!h;bdBynQ?|j8^!{7gke8S%ai#)^M3yb{2-w}(x3x8iM z&X;!cK!5W?9P>te^U1j889wG8p6UXB^kZEO z&N)*5%u(ObuJ7ot?}(%Ch_CM$SKq-$-@#Mg!C&909pi?-ix>Nczn2%|gukN~ShreqX#|?k)GV%$32Q%^ve;+gQ4}Ui^`Y!xE z%{X7$%>(_-4{^*J@y#dWnrHZ!e|V}3{MCzjsUui@>7(u(YdsLtI$pSO2{WC{>N4vhGzrG`mz9YWAV_ba)AAJW;eFuMir*@1R{tj&HAO1dUj1&HDY>XfN zo@^X9{GHjzC;a`{$TR$1+Q>irz1rxz@ONzEd}%ii^fy1mF>k~-pNwms;bZ>csV?v@ z>s8iKed(j_9BVxg(>h@+>jw_j72K>hIO{v-i0_!AzN1~=(O=&YN8b@&-!ZPfgO9%Z zKe)Qr*zLEiyzAJeT3{FJfs!UbOArNGgrq^r-fKO^#A1tEN>j053awZxCxeBx533s* z4zfjjBMlU=1#39>u&tz~>E3HS)%JzK5W@1%lokXLNx)E=TDNT?;`oeve&_!4yt^_o z?=i1At~utMzj@E!{NY*N;a}d(H?psNzQ26S&v%)xpZQ+%^*`TnzV*)coiCsH?(^mO z)^~l`TfugcePRf*T(XWy}VPtyyK_52jz<=y9f#5=D22fpzgxBR=`|BmbDJ3s%O*Z&W{_no)iPy5hUFP~T5 z`s(HR?yq|F@_+w#yn6HQr@#Bv+g|qKpnUP+r?~N7Jk?vA@hSdzrVIY*rCsR=r>`>U z?zi;^KIp>}OuNJb(KSy>j`#?^|BEdH2RQ zy>i>jUL2G!KKv9n{)?x2i!(mOAJ25b|EXS2bxdDn(%owY{mUsA+cX*a}wegK_e(mMa?wNMMV}GVy@RWb1UGVsM zrd{y(f2LjV)cZ`k;NkO3yWrvZOuOLW|IB$6c-r+$yRvIn<+TguN4sGDwF_3ScER{) z7mTNN!T9Twuy$pizIw|~AHII3Z(sk@=Wo4}3(w*+Ir1!?lRKCH{ z`0!KQ_%EL7EzbB9e>~F#fBmp_!C(GQ|BY?qQ>;9DI>PA)rz4z>a5}>22&W^Qj&M3= z7oWPA)rz4z>a5}>22&W^Qj&M4{=?JGIoQ`lh!s!U7V|F@Lo{n%j!s!U7 zBb<(KI>JwNoVCi;cjm#X`^=BGKg_&&`^n6wxBtvMd;8VQzqh~5ynOrN%-6Sn&OCnm zEqnc0`T99OxS$XYF_S%$o4> zoVDWRKWoU_u31~&_Oh3E%9nTilz04>cj_(g@G0-`Ebs6y@3gC2dl8p+=}7BzgwqjD zM>rkfbcE9pPDeN$vzK@2$exaHI>PA)rz4z>a5}>22&W^Qj&M4{=?JGIoQ`lh!s!U7 zWA^ec9of?nPDeN$;dF%45q_%UJeyyA=eh6dKF@=B*hSKfX#&zrZu z&2#AOhx2@T`{z8j-hRto-YH++@l)RMU*4&=yu+uw!?XOtzr53~?6Vhf%g-Lg^)q`H z*Z=Hk+PA)rz4z>a5}>22&ZHA@-7|O(-BTbI33}1gwqjDM>rkfbcE9p zPDeN$;dF%45l%-q9pQA$Uf!i6dpg4D2&W^Qj&M4{Pj#HV=&SGSb6(wN|MT{T*%!V2 zWcEvM|CxQ%+plJS_4c>fcfI{^_G54VoPFBcZ`sQ`<;y#M$~*qcJN1@#_>^~emS6an zciNSG_TF##*^|G1X0QJGpFR9r@9gbgKC|b4dCq?Um;d}naN9Ni9o+V^mv_pScl?xh z{Fis?E${Ft@9-?|@GtMQtGs&=mv`w%>vV+E5l%-q9pQ9@(-BTbI32T>cj?HUj&M4{ z=?JGIoQ`lh!s!U7Bb<(KI>PA)rz4z>a5}>22&ZHA@-7|O(-BTbI33}1gwqjzs^k3k zdi9pY^SG{>#36=0EPsbN>6j z{O3RM+phVq{I-|9yi>lsa5}>2 z2&W^Qj&M4{>6pE|OGox}gwqjDM>rkfbcE9pPDeN$;dF%45l%-q9pQ9@(-BTbI32T> zcj?HUj&M4{=?JGIoR08Q9p|jk)pyRZT;1n<%k2+y?&bEAIS+ID&zzIF{c6t7-2OJ_ zYHmNA^ES7C&N-ahZ`sQ`<;y#M$~*qcJN1@#_>^~emS6anciNSG&Q{&>bLQ&$nX_2e z|M&dmPrLQb*{#cG&U9U#bJpwfpEF>$U2`_PA)rz4z>a5}>2n7zD9NA`4t(-BTbI33}1gwqjDM>rkf zbcE9pPDeN$;dF%45l%-q9kZ8r>Bydra5}>22&W^Qj_^|*=WOlOcg}5I-GAg$KK}NH zIp=x%$(;YZ{b$aF-hMUbMQ?wbbELN)&iT^YKj+-(?YHdZo$}=!Kjj_&<(+!VJABGJ zJj*Zq%RBALK4*z<`8i{J{mj|p>wnH9-+Je)^5rvUm@m&c+kE-YndjTCISYN;%U<3o zU*7Rk-tk}Fskgktr@X_nyu-h|)2{OFMO@ycBdyaBPDeN$;dF%45l%-q9pQA$Uf!i6 zdpg4D2&W^Qj&M4{=?JGIoQ`lh!s!U7Bb<(KI>PA)rz4z>*~`0hWKTyp9pQ9@(-BTb z_^FQbF3Ht*-cz``&-)9vKg@d#x1Y@W4!8fzdl0u@&HE9zzs-9Sw;#^?6t{oQdlt9f zvX^(tmv{V>cl?)k>Mif^Dev$szwj^bv@83(J9Ep=J2ltOylZp)&pSA`-tYW1AAR}E zJ3E)>yvuX>&pST1UGwhGZ7+Lyr+j(GPkG0Gd8gj;4xjQ4&+-oc@=m+TyBBeJmyWbf zM>rkfbcE9pPDeN$;dF%4F?)HJj_m0Orz4z>a5}>22&W^Qj&M4{=?JGIoQ`lh!s!U7 zBb<(KI%Y5L(vdwK;dF%45l%-q9pR@s&byOW-+3?Z>OSx5-TpA|@!fth@AuvQGw=P~ ze)YwF>rJ=6&3l5kAI|%Ow|~xig}2|bmv_pScl?xh{Fis?E${Ft@9-?Y@GtMQEBm}F zddtr{q}R{9TYCM^JEynac^CEanRiq#&v|$C@}GBFZ@cDQ*V|t9@=p2kj-T?5|ME_~ zPA)r(^c=E*;s^5l%-q9pQ9@ z(-BTbI33}1gwqjDM>rkfbcE9pPDeN$;dIPi-lZdZI>PA)rz4z>a5}ddoX}$~!#EFZ|0p?aDrPBi!^~emUsAPA)rz4z>*~`0hWKTyp9pQ9@(-BTbI33}1gwqjDM>rkfbcE9pPDeN$;dF%4 zF?)HJj_m0Orz4z>a5}>22tUwoSPy7kUoLzmCoL3DY}-9(rF+*x$nHFp`^_Oh3E$`>DgiW~pMQ@zC* zpW=^ay5L{lX;*poA};UJk=E%5rz4z>a5}>22&W^Qj&M3=FYnTkJssh6gwqjDM>rkf zbcE9pPDeN$;dF%45l%-q9pQ9@(-BU`?B!iLvZo`Qj&M4{=?JGI{8Y!e3-0PW_l#ZL zKkIXT^!A6jm+bbFxv%W@pSj2E_N%$y?Dn_0_w4q=xex93&$%b<_FMMyPWkeVpYo3X z@=m?w9X{n9p5+(*<(+nApS$mF`MDGC`kA}(uK&41@76na>s>x`=icQxckx~Rb4TB8 z*WBHA+sj_wDPP|4Q{M4k-l?~|!>7E%v%JHPA)rz4z>a5}>22&W^Qj@iq*bYxFQ zI33}1gwqjDNBF6Za~|~SJNIf{-RHi|+aKm0&f8Dse$Lx}=HAZRujW3_+u!D%&)W~@ z{?FS#=U&j;Z`sQ`<;y#M$~*qcJN1@#_>^~emS6anciNSG?s~oD=MLEGXYPi*{^!ov zTkqT@d-=>AvzO=GJ$w1jowT=Ib64$cFMD~Xe0j%DdB=Zwr{3}opYjgR@(%yrkfbcE9}dwG|R?CA)nBb<(KI>PA)rz4z>a5}>22&W^Q zj&M4{=?JGIoQ`lhW-ss3kv$#ZbcE9pPDeN$;io#zS@x^%+#`K;pZle6f0%oxZ$Fv) zsBiz7d#Z20n)|D7f17))Z$F&-u5bUGd$4c6WiRiPFYov%@Axn8)LY)+Q{LfOe&Ju< zX;=2S+x(WFJI}A5&-l~db^XsB>9^jwJN@#RJJm1GxoiFMpF7xZyXJ28+g|qaPWkeV zpYo3X@=m?w9X{n9p5-0><(+nwcQ4}dE*)u|j&M4{=?JGIoQ`lh!s!U7WA^ec9of?n zPDeN$;dF%45l%-q9pQ9@(-BTbI33}1gwqjDM>rkfbj)7fr6YSf!s!U7Bb<(KI>JwN zoNrrPedoIgSNHjz!tD>=@GF1f_LKSk!tFmF^?SbR_N)0`!|iYL9f#Ww=lc$~f6jLw zZog$O@02g^_$lxBFYnY_-r-Z;;aPs+U*2g~_W72_EkED*xPIo_AJ_jU{{C;c_0G3K zE}!{^$mKcT7P22&W^Qj&M3|nWH0|j@iq*bYxG*Epv2)(-BTbI33}1gwqjDM>rkfbcE9p zPDeN$;dF%45l+YKa5}>22&W_bRL430cJ-a_1YOfS%R7F`JO0Z%^_F+|ly`WRU-*}I z+Le92U3JUPH?6Lp`PS9-Ki|N*_0G4kE}!{k*5x_h(z^WT8(X(s^X;wMUiR`%`SOmR z@{a%VPQB$FKII*r6pE|OGox} zgwqjDM>rkfbcE9pPDeN$;dF%45l%-q9pQ9@(-BTbI32T>cj?HUj&M4{=?JGIoR08Q z9p`_^tM7al@9I9^%e(zyzN2^h$$Ve$_MiFg-tAZOJ-*xD<~x12AI|stZvUL``rUrZ zUfwBR-tkl3@n7Dlx4grryu-8n!oR%JuI%%z##?^A;duSbw;iwl`R3!TcfJLA`OG&W zFVFdQcl?)k>Mif^Dev$s@9;10w5z;(5tn!ANb7Wj z(-BTbI33}1gwqjDM>rj`mv`yNo{n%j!s!U7Bb<(KI>PA)rz4z>a5}>22&W^Qj&M4{ z=?JG|_VO+r+0zkDM>rkfbcE9peyZc_7rm6e^Bvfi(tW-U`%?X3z8m{e{bar;`%?X9 zzBBt${c65H`%?XFzDxU3|KH8`YG3OAyZMgoOZ|VxUfwBR-tkl3@n7Dlx4grryu-8n z!oR%JuI%$|;#+>cS$zG>w~RmF|C4|6);r%mzI^7J$d~7QEBW%DZz$h(&9{|rd)bSF z^2LXr;>Q1t=hR!A@hSdzrVIY%opzOXFXHkp9ci78a5}>22&W^Qj&M4{=?JG|_VO+r z+0zkDM>rkfbcE9pPDeN$;dF%45l%;VzE!PCgy}V0D_H=~P5mql9 z;dF%45&qRWe)iROzI%RkpYNgH{xIK3zy0I~f8tYb|C#Tq-+ndUTfhBnzQca|;e4O{ z_Rsll`|Y>v<(=~79Y5tA|K*)}%R79^J3PxT{6CO)pMCBB<;VYlTmI|*@h`Z3e)b)I zJ%?&WvhcKw#0c;{^|dwHjPdB;zA$A5YE zgHvyLhfjHjXL*PJ2lDQ-pXA-I#^qf)(mEaCbcE9pPDeN$;dF%45l+YK za5}>22&W^Qj$8hpdFTkIBb<(KI&S%+Bb<(KI>PA)rz4z>*~`0hWKTyp9pQ9@(-BTb z_^FO>`Kf>TxBl?sAM@Sst)KkLUwPxb^`D>kyZ`9D^{fB! zGk(MS>ThrT*MIZ-n(zL|_y5-SHQ)XC$9(Mjn(x@lJLStee#$%k%RBX!cleZdc$Rng zmv{gB_rB%hp4dPAN%=QF@$=><{@?th-Zwwt^Oh$(-|~e2Tb{J*El=9}mM3v|%ai!L zX^N}Q=X3O{Lm5RpN_D4oA2B50k&I)lVj` zU#tI2zQ0z#nsMN@`rC{TuhkD{JbA7DIpfJ|^;`D(v-0(Ge(L}Hmlx_SU+^i9@GQUZ zFYmM~`;4Er{EVyD&y2Sp@c$E^dh4C>`SO`@`|_Oe{PLgi|F&z!|Jz>n;-Gx-;itIq zf8#mz7H52lKc4A=e|e`}<=u<8yh}$~rz4z>a5}>22&W^Qj&M4{>6pE|OGox}gwqjD zM>rkfbcEA!%O4%#bcE9pPRA{ObcE9pPDeN$;dF%4F?)HJj_m0Orz1S``05C!Bb<)# zuh#L$uD-MWyt>c2^!A5Yuikz#>)6|WW_^46)vSAOf1CC2?T52|zWsC7&$r*Qmv_pS zcl?xh{Fis?E${Ft@9-?Y@c%&G{n)k7^TI7Z&k@(pJYRgk|3Ccex88XkxqRk1icW%4pdFQs5y}VPtyyK_5PA)rz4z>a5`o$@6wSy9pQ9@(-BTbI33}1gy;Egb%fIqPDeN$Ve!;|;BWQwosyZoRYrcKOV{+~qm@b(jC_@7;FI{@!gbdvQ>{`0!KQ z_%EL7EzbB9e>~F#|ME_|n(to3rkfbcE9pPRH!!T{^O-Bb<(K zI>PA)rz4z>a5}>22&W^Qj&M4{=?JGIoQ`lh!s(d3yh}&+bcE9pPDeN$;dF$b>Nsna ztMB~3aCM*m9d3V^|08Zcng1zn|C#?UZoiuUHEw^K|2u9!oc~8||D69vZog$O@02g^ z_$lxBFYnY_-r-Z;;aPs+U*2g~_W3{PmY@HLuAlk;==z`km2SQBf79hN|3h7#^Z(T4 zKmTXlcFq4;x4rD;o$}=!Kjj_&<(+!VJABGJJj*-$%RB8V?_R{^T{_Y_9pQ9@(-BTb zI33}1gwqjD$L!@@IPA)rz4z>a5}>22&W^Qj&M4{>6pE| zOGox}gwqjDM>rkfbcCPkIOhSbzVm3Ip+axzhy7)lrQi2Dew3%@6=n~;Zxq>S$^SP-f36%Isb6W&$)=}XUPA)rz4z>a5}>22&ZHA@-7|O(-BTbI33}1gwqjDM>rkfbcE9p zPDeN$;dF%45l+V~b998$F?)HJj_m2UWsZ(;I>PA)rz8AS$G`Srf9C2t=f|$@bFS?6 zhtK%a-*x-RoI|_)XU?bHel_RTZhxEeY_}iI`M29Y=lt94x9sJe^5q>rrkfbcE9pPDeN$;dIPi z-lZdZI>PA)rz4z>a5}>22&W^Qj&M4{=?JGIoQ`lh!s!U7Bb<)e%e!=BPe(W%;dF%4 z5l%<=sg85r`|3OArLXRDj{5e8IbVJI$(*~s{b$Z&-+ndcv~Pc#^V_!{&Ux?KKj*yn z?YHdZo$}=!Kjj_&<(+!VJABGJJj*Zq%RBALKIhwS`8oG~{mgmz>wnJ4-+Jf#{N*#} z>MzeZZ-4pE`TX0iIiG*q%U<3oU*7Rk-tk}Fskgktr@X_nyu-h|)2{OFMO@ycBdyaB zPDeN$;dF%45l%-q9pQA$Uf!i6dpg4D2&W^Qj&M4{=?JGIoQ`lh!s!U7Bb<(KI>PA) zrz4z>*~`0hWKTyp9pQ9@(-BTb_^FPwUv%}I_k*tP^WMJZ}Yy=?T7Pz)9s)0e$(x@?B$*EddoX}$~!#EFZ|0p?aDsybKUZv z^*KL!{mlDc*Z;g1cI%z@#V((DkL>cC_scH-c^~bzYu-n@?PV|TlrQi2Dew3%@6=n~ z;Zxq>S>EAa-f35P_aZLu(vjBb2&W^Qj&M4{=?JGIoQ`lhW-ss3kv$#ZbcE9pPDeN$ z;dF%45l%-q9pQ9@(-BTbI33}1gwqjD$L!@@Ilsa5}>22&W^Q zj&M4{>6pE|OGox}gwqjDM>rkfbcE9pPDeN$;dF%45l%-q9pQ9@(-BTbI32T>cj?HU zj&M4{=?JGIoR08Q9q0av=jl85KRi$OxfkMj{bBBlcwRr5dnBIMf98IP=k=?(cj9^d zZSJFZ-v0=5f5r3uN0|F7p7%cjdwHjPdB;zA$A5XJ-trEg@($1P3;*&?yRy%H9k=}4 z<8l4W{T|o<-1~9so%=v8pSdUG=H1*Ma`SHP8@YKm_l?}VV=oTM7ax9#8~?>qy~P=y z;*V##;9uTpS9$j$F7MKj*69eRBb<(KI>PA)rz4z>a5`o$@6wSy9pQ9@(-BTbI33}1 zgwqjDM>rkfbcE9pPDeN$;dF%45l+YKa5}>22&W_bRL8lm>FPW89bMh$ z9;DkJ=6iVC1u5P_^|JCI)_hMb1b6?iwKlf|hcFp}- zx4rD;o$}=!Kjj_&<(+!VJABGJJj*-$%RB8V?_R{^T{_Y_9pQ9@(-BTbI33}1gwqjD z$L!@@IPA)rz4z>a5}>22&W^Qj&M4{>6pE|OGox}gwqjD zM>rkfbcCPkIR8stedm6^tNYyhcl*QK2YCC*+!J{F&v*WskG}nC?iIZKZSEVq{c!Fl zy!~_TC%pZZy}VPtyyK_5JNn?sdHN z&V7%U&)frfdCvWim;c-+dD}JjN#6Fdmv_pScl?xh{Fis?E${Ft@9-?|@GtMQtGs&= zmv`w%>vV+E5l%-q9pQ9@(-BTbI32T>cj?HUj&M4{=?JGIoQ`lh!s!U7Bb<(KI>PA) zrz4z>a5}>22&ZHA@-7|O(-BTbI33}1gwqjzs^i?pd-a|BY_INf&+Y9GbN}t_Cvz|E z?LTv0?(J7|kM8YnbHDEGhjSnA?VocW@9nqj<(=~79Y5tA|K*)}%R79^J3PxT{L4G- z%0BlG-|}-W@%1zJ6<_~zkMXT{?l-=C=HBDWbM8aF{OA7U+pf7k`L>t6yi>lsa5}>22&W^Qj&M4{>6pE|OGox}gwqjD zM>rkfbcE9pPDeN$;dF%45l%-q9pQ9@(-BTbI32T>cj?HUj&M4{=?JGIoR08Q9q0b} ztMA<3es!OF-EV)G``&LqnS0=G|C#&YZ@-#*<8ObP`{Zvwocrf*|D5~hZ@*Bydra5}>22&W^Qj&M4{=?JGIoQ`lh!s!U7Bb<(KI>PA)r(^c= zE*;s^5l%-q9pQ9@(-D5E<9u)B>O0>nxw_AHOm2Ue@0;9yGT%M9{b#<1a{JYMC*}6H z`F_gnhj04U-*x-vd~fCUTlVr!`SOmR@{a%VPQB$FKII*rs{m*x5ZoTvUn#*UtYjb(d_iir#`998V*L)x6wwJxUQ@*_8r@Z68yi;#^hfjHj zXL*Nzd8b|F-HW)qOGjF#Bb<(KI>PA)rz4z>a5}>2n7zD9NA`4t(-BTbI33}1gwqjD zM>rkfbcE9pPDeN$;dF%45l%-q9kZ8r>Bydra5}>22&W^Qj_^|*=lt8%cfQYcb)WBc z-TpA&^Sb?HzVmha&wT&u_N)0W*zIrgy|CL4=lf!}f6n*CZog$O@02g^_$lxBFYnY_ z-r-Z;;aPs+U*2g~_W7RLEkEB`yME^TYuEpLm+jU&-)p;k<~wee=X~Go@}KX)-FD6Q z;BI@_%RA-EJATSL{>wY{mUsA+cX*a}_?LIuRo=ab%e!=>bvnZ72&W^Qj&M4{=?JGI zoQ~PcyL4nvM>rkfbcE9pPDeN$;dF%45l%-q9pQ9@(-BTbI33}1gwrv5d6$mt=?JGI zoQ`lh!s!S<)p5S3dG-Ar@BaL&`+TSJ_J{d?rkfbj)7fr6YSf!s!U7Bb<(KI>PA)rz4z>a5}>2 z2&W^Qj&M4{=?JGIoQ~PcyL4nvM>rkfbcE9pPDl8uj`RKKtM7b&`RYF3WxoAkzSn&F z$$ZE8_MiE_^X*sj-RIli-ukXDyZvy!AAS4hd_Vg3TlVr!`SOmR@{a%VPQB$FKII*r zwY{mUsA+cX*a}_?LIuRo=ab%e!=>bvnZ72&W^Qj&M4{=?JGIoQ~Pc zyL4nvM>rkfbcE9pPDeN$;dF%45l%-q9pQ9@(-BTbI33}1gwrv5d6$mt=?JGIoQ`lh z!s!S<)$#K_;vHAtANa<1T;1RO{&(E|@SUIk&f8CZ_`UDE{pZs@^wrz1UU}=Qx4*sn zt6shR@crNM>g}ID{oSwLe#>6oDPP|4Q{M4k-l?~|!>7E%v;4xpywk4iAN+l9zvX}1 z?|l39^Wks2?fU=uuYB9B_gx?Rw#(<)&%APZ{`Mbwrkfbj)7fr6YSf z!s!U7Bb<(KI>PA)rz4z>a5}>22&W^Qj&M4{=?JGIoQ~PcyL4nvM>rkfbcE9pPDdF3 zkNHb~?)jWKed+z*_SMgx;I+T;&9A*Y_NREueC}WVrI#iSi@*QZ{=JvR&*D$~rN8&m z_+R{2zx?mNH1#h2zE}UjOT%aJKl{t?e`$Cwe*4e;qnC#N;(y_{{PIiFuElTq*FH!b z7SA~aaajC~Z~WS8|DgZm*NNNOKlkJQ32|8bA^-WW7l+0F-QW3OaajCUe)>biVezm0 z*$)+m#sBSZdXqRT{`a4~iN4o9y5I8C9~Sd7{bVu!(|;DLcly<0e5SuG#&i1NV*IDy zF4nH;w~MtmyEs%{eDWi1`4`XX73cVfe>~|D|9|Xf|IlsM4}9n!zU}>zul>U}4*&JP z^6%XEeE(;B;f>oDeB-}+F3zwi~8&;Ru2zVh8I; z#W_CWA5Xf(Uw(bzZ~U6?HGb03y+AO1-4_JY-919E{@{KgSU+*^5Ul^Wj|kSU+*1VW zZ|*gM^+Wd>!TM)*{kHP@bAI&m{OkYKD=*?BU*ai`;xE5G?32E3+jZ=puHIAr&G7NF z`1oIZ>Ro*JyhZuLbMfK7__S;BY473_hs7s8i%;Cv|B2_~6X(Sz{)>+;%m2(@&+$3q zGd?dq@fn{NpK*Kf8P6A= zaena`{}-QmVey$S7N2=!@tI#1pLu8TnU5Z29`n@VGk;xsdMR(6R(@H(!Tej-!Roc% zgYmHrgz>aKgz>kYgtg0h64u`A;!t_<$&a|@Up%W^G}$c=n_V0#FFyGZxBQD|^@?+R#6O;NiT^{dU)Wq`_x_7|mG@o@%#ZhF zVE+HVKlqD_)$9Elc6_{d1LNs^92kG^@4(vS{T*0)vx`IJ#V0@FmVfcAUU80(_{Wnj z@qg&`XbZddU(~C-_hMjvye|Xu?>!n=z22{Z@$udbjHmZ;VEnzm18bM}cVO+!E)JC! zpZthh{>8I;#W_CWA5Xf(-*`CxC%&XEc{lg+EtZdSU*BSRI`{Z3mcQ=lRbF1ty?=}4 z``ib(*f=ov1THo{xF1+~5{Quy(P} zJ&Iee@^io9Vt(e{#l`D??gz$Ay>n0FVtnTQ#>IHfy^f3VcRz6Laz8Mvz1hW~^5T;p zam)Y4^VBQO@e%)c(k1@#t8t!=jsNs*UZ8vPh5pbyqMtOs=s(Rn`c?DMjt^)4(hr-z zc04(D{kHP@bAI&m{OkYKD=*?BU*ai`;xE5y7klHs^34nUG+*%FJfhy_7krv`@N7Q9 zzj;c#n!mI+yEs%{eDWi1`4`XX73cVfe>~|De|k+n++1dN&ys$ky!)46e%#9h^Y6YU zSiSCXg7I;`6O5;OpJ4pm69sFRd!k_N%`Og=7oYryTmHqfdc`?D;vY}C#GhWZi~URI zzAW`B@BSs2ANMlB{JXCSR%=tH1z0Om?_&8?;|AM;T>%~SC=f7LE__qwQ8dH21*{I~}O=HLA=uzKAa z1LNa985mFZ%)t1&mj>1@_tL=Hn_V0#FFyGZxBQD|^@?+R#6O;NiNEo1-cNa^E_pZa zcPy5V^WMi|c{=ZdESA6Xp2%W(J@1b!mhbak$ztQcyl=AD_%QFMEH-Y;`zec!C)tfN zl{fz6$GDV#<5l$<$Kqpri>Glf{>H=F#Xj%jY`x0Qdpe8xnfG@V^FQzPELQKl@3R=6 zc@JnYp7VatV*KZQqQ%-Z?-MQ7-t6K~dGX1QxaD6wt5=-kBmVKEOZ-oMy-cs8zJlyEs%{eDWi1`4`XX73cWSE1vXwx9&ZLjl=FkhKK(%?p(`U*yL; zl7I6{^_q9$V?K(fc`E*A{@S|O-B+w$<=tZp^W%PFn1A;k!|HV(GK`OVl3_gEpA6&g zzGYau+_wyCZ+3C0y!hlt-10A;)ho{N5&wA7CI0ej-a~(;E;`P8+>7Zu?{_bz`@HwP zSbv!J!58Z%^Pc!({pXAS)|(dVSMy%^V*PF2Ltm^P&U@&K_0R13ZRPdn{OITT*Z-?m zUc^Vf#8V!{Uw+jt_IdAq>s5Z<$6w6Pyr;jI|9O9Zv3lpd{>Avr`~HjZoO=Kk<3INX zEY_~MH(;^$W*3Lbi%)*UE&t+Kz2Y1n@sB56;!m%+pX%lGn){s=EB{%a^P`LTnfss? z^FQ}QEmrT`AGH{txmRj2o^#*SV*KZRs>Rwh_fsv_-t6K~dGX1QxaD6wt5=-kBmVKE zOZ@3oyV&PGuB})3xuixJ-uROr<5K>OSJi7Ai;wXwp2ofS8xLz2d-JvO&Exzuzw_U` zuin-J__R*Iv-Jc1tt+&v^@jFl7l+D=PkzKL|KeG_;v66Gk0)K?fAZ_~^2@z&@X>ei z(S7mh4~tJfS$z7>;?u7dpZ>P^^uxuce=a`#cJb-Yi%&maeER?5lNXCmzC6l2@@VnN zuWNTNoOYdjTzvBMQRb1qi%(uJKKZ`*j020$_^|kl8;j3)viOWMi_iG8_>4=7&v>=? zjAM(>__kPn#b18Sy{Qt6; zpZQ;AG5_;_&0_V=|2T{Bng4ed<2nEPEXIHS4_d5U^FPsI?aeL@l^37L9ddU7#8v(8-1|Exb3t9RC= zi}9KD>S8=+9lIF+S>GbaPrAhaJb&%lM&8Xj zf3bX=_5WgdI?n}*e-eU_5;{3SPbDyI`<(`OXx)dL6qsR9<}YBX0SpSM`c> ze8fMVbcz3&zqT%R-)T~>^1j~$^W(ct@cN(cOu_2)9Vi$d--m+n^xY^Jf8Uvcwaa&= zVC~H=4wV<5{D@orH=d_nagLAp$CEDcHy*m@SzYqZ{m-y`bT2e4Pu&*{%U}0M!}8kw z(y)AY?=);2a33{nd~km?Y}{~vHEcY|Zk(yS@h3mVrTiPOs@FIcALCm*jeGGo9@Z{) z_dlywdG|uY{J1X~=HETiuzKAu4ddh9X&6uUQN#GVzZ%vq_gBN(n_V0#FFyGZxBQD| z^@?+R#6O;NiNF0r?|rDtK2_%}?O(n7oWr!QHRpu4jQy@TKfKsJ*qkd~Y=3Od8!xtR zHs_ER+fSSG$&2l?d7njH_TRGGm#e(}y8PJ3%fJ1->b36|ANzsvv`-j+`-ioQz4Lp@ zcdn10&inD-IY9MxJ`kVI4dU5(Li{^ts9l{u)ZXmkP^W9?g&U4>l zeCBy@F`o0BxEO!;DQSy#xlak!-t6K~dGX1QxaD6wt5=-kBmVKEOZ*@Ir+nn*G9BB0 zqi_3ibZ@^-e`p_1KWTqY|7qV(ziK~Fe`}vmKWzU{|IDu6R$hP3kA9wi{l9wUMSSE- zJmpdRAOEL3+Qr`foAT|;@zZ`C|Lxjh zAU>TN#Iy5+_;=1wyE=cUz1hW~^5T;pam&AWRx%eW zZ`3Y!_x-9@dG`Rr{J0+&=HI=+uzKAm4C6EZ?<~gC{lo0|yRR75F839~+M8V*Dlb0y z5x4w{XZ4D6e8fMVbcz3&zn-a!j-6MbZ|7L(-uV{&p>r?#N#|kopU%nXSDl~H-#S;L zA9mhG|IDu6R$hP3kA9wi{l9wUMSSE-JmpdR&-}IRV(+|)@||Phr}HiRckV^Korl4v zb24~#eg^-})o54eZL~MLI8y@6N#5<-0Sm_GTA{%8O5a z#4Z2gS-s*MAMuYTz2blLdRbk^zW9`1eEcjv{uiHm7au;056{Ji|KiiG#izZCPaGDX z_$)qgTYTcV_{4efiT~oG%i^QgwfBGD(Rb}f_r<3_EI$2Y@##N{Prq7x`rG2u4;P>Q zx%l+k#iu_nKK*?0>HmvQUMxQOvY0OMKl_I}SDt;U#b^I&@!8i}eD=E*pM9{!XMb$* z**9B!_R|)heYVAC|84Qvms@=H>lUAVyv1jKZ}HjpTYUBdA7vi2c0{_5hh@4EQx$1Xnmw2ROF z?c%eqyO>_h%k0h9$~TYm)BMhV^S*jp58%@}0ngSC__wamuGSmcn_V0#FFyGZxBSzq zdc`?D;vY}@y78x1?P71fR=#vyNJP z)>n(qx@+-Sk1amyw8dxrw)m{;7N7Or;N$ANt==Kk5HO{ipvK^{f7W)ZhAFQa|kfO8qmtep`9{IY0V&{`LRrl^5}m zFY%N|@t0q{r`x6|4V9D|5s{nc5$e@_~b|2 z@-Lp%E6(u||9H|R{*U#>XRmhVwYfiYvH5Q9)m&^IoclHxn;+*M&c)`5> zTx_15`#cw$f9L+s#pdO?|8ueVI=gwi^5*yanD_HU94SmU+ZG+%`Og= z7oYryTmHqfdc`?D;vY}C#NT*0{qVW;J{_be;18F4ivJ84*M6%`Og=7oYry zTmHqfdc`?D;vY}C#9w}OE`^SrSD|m`Sm@sQ7X6`fFZxO6Vf3HQ$>>*|pV8ksSECFFyS*jA#EB!Xl>b$7- zW*3Lbi%)*UE&t+Kz2Y1n@sB56;!m&I#ol>Kxqo1>d2{Y1 zSZqF>`wAADXXhS+#pd6+-(azMdG0+}Y`)HJ9jC?wdWnOMKjM~u@vL5Pj*s}qlP>XpJbyjj?Ui@) z9{R3n<>S1czF3~ld+Uqk@4U~xSYFS2?u+I7y#Kz~I56+UFE&2R`|^v88}lChV&h46 z<4om^Klw2(<==Q!y~eTl7~kS)+>8I?`Rmax_TFDszW0~;nR^D75C3!jz+&~zy#$N# z`M=-!XBXo+_ZTe3f9^L}tX*^O!D8*rE)JC!pZthh{>8I;#W_CWA5Xf(-+0)2qw=oz zN#$ejnab1NKb608e)zfdiM;N8Rr%g~tj2-fZ#6#j-m7t=_hF4E*^M)mH~!?uxRih6 zRrMOj;$wV^r*SX-#>3jh-utA=_ns*~y?@Go@1?4@_f_%fJytw>zZL)9d)2Pqht=Nf z;!t_<$&a|@Up%W)l=|0Z|i}i>$jEHpYx-i=U@M?UU?B8`4Ufg6o2_uyV&Qs zZ0l8ip4S%hGtY60`JeN{i`6^NeT(s#=fTBz&U4~o{O9>`v3AXK8I;#W_CWA5Xf(|Do5vwE4nb|5Uzy%TN88|N6Ol>;L$a7kHL0_?Ji8Reou2c5$e@ z_~b|2@-Lp%E6(u||9H|R{tvw#?P9NgDqp|lr~b@;{an5Ee|*XdJj)mS%OmY7zqB{I zI8n?s;kMZ9+O}(w(@M&F#XX`!uTL)@a z>qG6$E)JC!pZthh{>8I;#W_CWA5Xf(pI)_#z4evyt-JVXJ;s0QH1)QA!>4r}o~`%r zZyl&ztq-*~yEs%{eDWi1`4`XX73cVfe>~|Df9u0(*XEaX$k-QKpG^71)-B`bk%P0I z8UKr|bEe+K)<45%v31e#Tx`8G{1;nCbw8W+Rd(yH%3F`+$2u+l)^F8oT^Aqgy?9y& z#^3s|cCn9+%R%|kcQHSs`(pm5KP*=7^pnN-O#fMo=k%+^_)mXZtXz_y8wIAIdWgh)u@#!avPybnb`qkpo-xi;K zxcKzX#i!pcKK*&|>F0~Zv-~=FvG$WMi%%XcHXcqsKYlxTH~0E3mXCAa?_zm6_W&=J zzjHtEVtGCH1}~QHbD!|exyFIHXZX&)bN}$2m*-yM#m1BD#+k|+fAV8o%D?fddW~c8 zF}}sqxEFupVeMj{dzhD}@^e4)Vt(e{=EeNaea?&3JNG;<#%Jz-UX1753%wZsxi5OL z@$ijre_-Qbc5$e@_~b|2@-Lp%E6(u||9Bb?<4>>dF=Ow3Gv&MYjGyj9+%%O?pwpZd)TzA``NTNyEs%{eDWi1`4`XX73cVfe>~|De|ps}_U<=RzI)I3 z={_|6yC+S(-Jga}_p0I9eQWr451V#%Kb!Vu7l+D=PkzKL|KeG_;v66Gk0)K?@A>O9 z-}H6c=dJVq{3m?vV(b53`ZvC2vFCzs_?17g*z>~w{7qlI*mJ~3{hqH{?D^uK|5x9& z*mK8Eef=L_?0Mv)KJ0-#r@Z~=UR}HAm+YQvD(`tGKc0i~@A;^DJvYV2^He-NXT{(1 zSM6f|`M>*Uqw?STKYaai;OC8R|Bn{)|B1i<8y2hg*ZqSB#^-C^{_eHo`8|L0f${%_ zf9gM8yLNr<$33w2W*3Lbi%)*UE&t+Kz2Y1n@sB56;!m&c;biZAPUX9|lb`PM!I{Jgo!cZ@p2w*eCC{Ugakr7xOcDx|sjT-^J>kyk3mY z@#=6&_H9>Aw{0-miO@NZqAU9C5?H@i4gUVQQ+Zuu9_>J{hsh<`lk690!@k9M&) zUn}1{&QJ3@|IPdAZ9RZb>jXSoKj7cGLc3aTXm56LsJ!^(N8Iu+p4BVP@e%)c(k1@Z z8-1V1yw>-9%y)hF$2{2gfXt75C&;|n_k+x*eOJgl+xLddzkP?uyxjMR%-7k?%I|l7j-SQH|Kd~c;=^aZD|C1+KKvJ- zb}c^bU3}uO_{3-NiQD==@mzf3y!ga_@zG`Zo4@8>;$4>-C+A+@#m3LM?{~3rb?yOP zY`mTCxi2;jfAdE_uR@?##!zxkzl z%{%ciAH~x=6@T+r?P8yMn73Z#=YHnJ{LH=0i}|1XoENKi?s;B}&)omK7|*#EdNKZQ z`ql^5uDM5g?b@4N94aq9`4PALi)ZzUb9}@3qPH2;lFzo z)Z2L&d}cp$$8bDnpK~$(ovYEV&f92jc5$e@_~b|2@-Lp%E6(u||9H|R{`Bg+4SVNR zl#kzjH6@?K})Vv;Vwp!E^Sd7vtZ#8tv-5jrL|2hsujje#9;R;#s}o93SzI zCtc!yo|m6nZ^*kDCl|}d89x`x(-~J6%ikGq7t8AzhZoED8J`y$2WH$}Y#Z)Gvv=Q}Km^@sO-#RKan^WB!U>p$~7m&N+keCK7c{x;u#S*#z%InYh(a-a*|5vZPh>v`Ur#y;w&tm;*&IK*j-{!o~V*RlDD)rCo z`fcU)=ltmB`PcueS6;+NzQj`=#b18aF81D^Qhv@;Egyd7oYi9f=ls=T_0GAh#rVv5 zt;KlGIj+U{&-t#!+SPrP+M8V*Dlb0y5x4w{XZ4D6e8fMV@+rAWc}7U zv;J)TSwFWft^ZrEmKWBs<%{)gd1T#NepwG^w@$9S^>co#tMhNYUA@-f@v%OSr*(V$ zt>aG9dQ(oX%zTjUTX;=BBz1hW~^5T;pam&AWR@i!jM{>IkDKId>2D?jIR7V|Ubb{6wL z=Xn;Zch31N#%Ip|EXH%r1ue#Z&I>Kpt~p1vSbMXJL*>OMKjM~u@vL5Pj*s}q(|8zv zdiDIp-t&v{J=gHl^A7(#2dTH`BYb*p+Hw1Q9~S?fv$U({FYV2~^TH`FKKT*1{EKJx zigSF#Kb~}nKfQYXI`(~jIpz1c=J;8B{4YNBE_Xzf`YzCqCw*c$%l;|CqlX?PBkK80EV+hM(?};lF!k)Z6_t_;fD~p50f2 zfA`pESNGd!Z+3C0y!hlt-10A;)ho{N5&wA7CH{}+ug4y*bx8ZA)+gnYCY4w zt94HMvDQEB(^?m`e`~$ezOHpt`@Pmz*{!=OZ#|YD>$Ln^zg4ewU3{$f;%OZi|Ht#! zqh0Lnmnz>rDnIS7^54FzdfSi1r+r#H+rP!XeO>KpzgK&+i$mqbCqLqrfAOqdagLAp z$CEDcKkLKI>$477eAXw6&$?ytSzu`B{j>P2ix!{t(&Dp@T71@5i_f}i@mY^8 zKI^o_XZ^PLtm_t^_1>e*V;#8otPiif@kIH?8Gagn_-|ZNZ{rm{jbnH=zTw}vr(KPQ z+M8V*Dlb0y5x4w{XZ4D6e8fMVbcw(G>bqui?0aYQ?K^06@B3)_L*Gr)Px_vk{?m8X z^sBzVroYX8+Qv;k?0aqcXLkLz^7?ar^z;1d|J5rm;v-+;DUaeWziJnI-#b&j@1XJ1 z_tE&D{mJF2-r2WYj8ETL!?W+N;oo=Jw5#v6X>WFMsJ!^(N8Iu+p4BVP@e%)c(k1?n z=jF%uM%nvbr}BNrlb^ot$$#JdRBzt{#i#Ft;@S5@@$b8$+ST_)wKuysR9<}YBX0Q@ z&*~ND_=tZz=@S3P^YWuz?0v6O`M%@HPv7@k|L41(>g{`=`1GAnJo|nq{(V)W;zK+G#nRAcFV(ZVj-(#_L>D>FV*n0Jg&-ZSuW9OcbwOilL{UM93d;8vv z^>B9U+^V8x5wXlzIL&9|AzA2zroMkyRzK)pZi!At9R~c zS&Yxz-?A9bxz}Ye{&U~UV(sdCH`<$B94aq9`4PALi)ZzUb9}@}0Wi{UxZKlNO-otgn#=^+SPuP z_GTA{%8O5a#4Z2gS-s*MAMuYTUE*&%{A(Zfc<)Bu^*)Y#>^&WM+WR~5xA%JFb?^Jg z_ud0C4)lJI@uByIj2pdAWIV}koTr8gHP`P;o18^`1jtBcJ)4y_GTA{%8O5a#4Z2gS-s*MAMuYTUE+WC z4|ktg-hJt3eb!?6IOlT~%hNfxvsnJld7j1cdd~SQmhW@^XR&c$&IK(tKFoQc#m0>} zN3_^@lHE8{dE-xhj7#}9URAGgEI!7!cpCTOZ#x;b&P^>=e$G=Z=4Z}XE#`mD zUoBSeoXc8_&z#p)~bM9-g_GTA{%8O5a#4Z2gS-s*MAMuYTUE(jl zrd{_Qu+~@fZQVup)?@lZ>oonO_1pHJ^F4a~s`Z}!);dr>Y<;MIX4h{kzy106(a-a* z|5vZPh>v`Ur#yXLp zmVVgtm;RYuzpcFfoFDx>|N4LR%8U5Omw3vf_{*=_#oqIa@;%q^)AJ7hJqM|`=OcW2 zZo;$YDg1lR(ypGrv^TprR9<}YBX0Q@&*~ND_=tZz=@S3*{Pn#5EBimfeAoXJ=E45I zFhBOchIzC9JIts353N6#V<&M7#PwMSHXF^Vcaa zKKT*1{EKJxigSF#Kc3bb@qes0KJs;X$-C~`myg}UFHgIlU;cJ)zr5}~fBD`$|Hgst z|2IDLT>#@o-wQCFWH-)K-uROr<5K>OSJi7Ai;wXwp2ofSKh_(McCmNgzVh9}&rkRB z^WVMw>g_&%e7ff!&+h-nzwZKQSKkZJ-t6K~dGX1QxaD6wt5=-kBmVKEOZ?AzYaIWF+Q{3 zvKY^qXBXo?^Y3Eqnt6G#_GTA{%8O5a#4Z0D&r`2B$4C6*X*`U-{OUblI`;lAeS0sM z?!7OpKlC24e$xBJ`p=x#+BK4XHRre%>u|N4LR%8U5O zmw3vf_{*=_#oqhB%J*I{KfN!^fA0~ixA%+jne%nq7Ch(N-D3QEPg%Qqe_4C8i$mqb zCqLqrfAOqdagLAp$CEDcKl>Xy&eO5`RO#D2t90-FRsErRS@o0dYt?_c$5p@Tepmgi zdtdd#?t|4ov+K8&*PrvFpXXoyuU>f(ANdkbc@%&7)qSw+-KVO2_pI{M{j2zT#o%~|IxHlNP=XR )OSJi7Ai;wXwp2ofS8xLz2d*9De{zuODzxe5UTm1JOF7@_(E`0iK z7oL633;(|JrCojhOMA16L*>OMKjM~u@vL5Pj*s}q(|8#FlV7j5o*x|-AAJ`e-4~z! zu=w2HfqKU{qJ=i<|E7oYyT`1JF|r~fZLd9nE9%cIOAj~1W&y7tMt zTYmC!@yXLinMeLEK6$~Czl*c<NP=lR$Ft5;scN4~^U9>rgN z)h_n#D^|XHjQQz)WB$AMSiRkcj8FF@^N}tH}G#CL%Z7F(BAAj&Ybe% zlOJ)*zj#)!ILAl)<4KqJpYd?p#oqpa^6eY&(|*GGKl=>oZT|tE_9gIazXJdEF|@1w z4eiY?4wV<5{D@orH=d_nagLAp$CEDcw?6EicI%MtZ?`__UU%!3?t8bM=^l9NobHFW z{^{O$>!R+H-}TbDf8IK(`{#Fkb?nw%mA4+tk9Au9t>3EGx-LG}d-1dmjKB3^?PBl# zcICU*ouBS|=f8X4)%(Al`{(iL-grE_Pagm7nb)rFpV!{(;!t_<$&a|@Up%WoqNU><1_b1C0mUD+*h_( zyZRoz_GTA{%8O5a#4Z2gS-s*MAMuYTUE)u#+QmNiwk-$c=RUW^{LDRXi}|1X-xjNP z?uA>7&)gTc7|*#!ZZZCIzuaQ&>U;Fsn_V0#FFyGZxBQD|^@?+R#6O;NiNEzm?J}>` zUh`dXFb@_V^J8%{Zx&DUX>m5s7Ju_^x|o;K%Y2>PJYIS8dw$IO`L`aZUh9PTSU<$m zx+4D88?}qQ_9|Z-_$fa87dQ15Pkf3qp2Z*kbkVN#(%$UiP&8vH+K%InYh(a-a*|5vZPh>v`Ur#yNE2Y}(cRY}%V$94aq9`4PAL z?|69X73cVfe>~|G|A$^5xp~b#>&C^(&w6q(KeNtU%>S%E7pr&HrHk>I_3C0gXC1p3 z|5@KI)~>$itG(I9q4MIBA92gScvi1C$4C6*NtgIP^m??5eb)KQLHSw#FXm^S3l{S~ z&kKvyJI@h|@tNm~#dywh$KuVeZ+>9y>U+MMU&k&El^37_|N-mi?yr!^t3m-I8;o@We)fkK^E3O#i}|1ZMIY zJZE2eG5)h(y;!^YzJvB=7l+D=PkzKL|KeG_;v66Gk0)K?Z#=9Y%Deife5~Kf)B3ag zt)I*5`oDZHFN_1_i}9g6GH#S##*^&EnaUe~@?%`ezwxSijbrgKzQxnH7k}en?P9Ng zDqp|lr~b@;{an5Ee|*XdJj)mS%OmY7zqB{II8>7?d`uQ-@Y6_?bq?&KAw8p z-@~VUKRnwH#J_z)?P~u}d$Wr}<;5pI;+B8$tX^@BkNC&)tOK_#o|os|p6!R8%jP>% zi#@N+_oo(nj+^gNE%to(37`Cvi#_+vcdQnB9-Qx6E%ux^-@RJA`-dO@vx_}f&UdmF z@BZPjdk(F<=hOUnZq2{v+3NM28z0ZV@$_6Af6vRci+#Qew)HAM-wRvJ&wNL0@%sOV ze|@of=euKz@tN~|D z|Hpps$#?dtrY_GTA{%8O5a#4Z2g zS-s*MAMuYTUE=@P?|rn3z4Lp@cdn10&inD-IY9MxJ`kVI4dU5(Li{^ts9l{u)ZXmk zPXp>>qyJ>*g;y&N^f< zeP?~LnC`P~S*$L?7VB5DE?TU=&3b9Ee%SpR`e%0iw(|OOe)RMF z>;Kg&FXAI#;wg{f|JXl#w1s`vjmts#Sx+wJXV#gE`JeUYV)f3tbTK}&UR{jmtYa7B zKkM7Y+SUCV+M8V*Dlb0y5x4w{XZ4D6e8fMVbiw~O{IS3Me9kPt^!{)A>Ss^z&TGg1 z6hHg@pZT6G|9Kzrj_1Go_df6kf8X1mf6x~^@NfH_Z-4&5Z-3wqf8%Y>f8b9&@Xvqc z+n)c_^9O#{$G+|P+kWwZpZ&}$&p+s6{;T!*+kfbl=fCs^9{7FV^2+mX`_CTujc|JC2|!2JB)FMMGB-~CMwtlod_&p$9epY%5#7|)-34j&y;GbUFmEAp5m3Kc?e%xD? zfA?8cuY0cIMhRr6n{L^3;*=;-Jk5f zn^Sq;)5(wT?Bw6~cdFNSdE(=HJ@ND%pZNQ}Pwn#EpY&oc4$2oFeu^9a#Z$e-8K2^h zXS(2@UfPx2caAFW`$zflU8MZ`UQ+e?j#7MlUn!oxyA*%lW2#-g(^Pxei-YpTho9oc zfALgramJ_kG>vGd{&1&vd~*y|gR4bBvXDzA-<}J?7te$m(@YGCs~v#?!gV_&aY| zyPU(Uz3jz7`QpP*apS*us<$}fQ~dEv7yQ%9d#2gv|J+-C{^z}Z=KtU8fBqM~_0Ipr zm(ToOTFoZPkP~* zF8HU{oQt^jIWKX`&pC?gXUz(r$m(QHjxIE|l#^pcf zI&Qms7c#xr(@XjE;wQcMPcQYR7e48QXL{kEUjDbu?tjn9`#&^4{wK}9|4*ye|Elrv ze``Gb4;z2~&(;t9Z<}81>7{&n@snQsrE9V0EtNy6$==K31SJ+DYcRU0*Em)QG-|@CEl$tGiPH!3yp@% zsA!phH&9DJ6H&)0iB#5Wef!;K|M9DOs(0_zPd}?~-~M#3PB-?`Q@QDkPx|ATU+~Xg z&h?dUU#|T2yRu^+Ec^DyD%ZYQeC(&i(>`1L?Y~to`*PJ+dOFCTKJ26$`{}9NbjBzB z@ysvy=P>-9Bphoo~#JbC20~9n z#(sJ#H=XfGe?0RG{`t$j#nRpTE5G}I*>O)W`|b}`u6u>?ao;eW?jgqC{lx0!-eUEY zo(}ToFLu(6{q$6BI^&c6c;*-U^Ot&+?w)4(-QUcPd!5;L-?MVv1C5XSq49KYH2&_B zRxkHVtFQEQkUxFcNjLV>Q@QDkPx|ATU+~Xgv;T6_#SJUJcw*TRXDs{Tk5#U?WbqNN zES}<+#b120>Lu=3^_89u@~00w>BfF~DmR_+Nq;=^3;y{_y-FA7t^DG@Wk+1N?28vy zx#GyhM|`<>iaQs7@#w0TICa%mdOFCTKJ26$`{}9NbjBzB@yuWN=dZa(@N((m%9dZe z+3bizn|<+VD_7jw_=sm4PjPPJFaB-y5*N4nN>2y*(}$gOV?RBWo6h*8Kc4vo|NNz1 zrHcbxe(`~`BW`f^#S^Yvafag~{%}0SC62#%#nnq3GPh#&Hw68{myG=-e0)(=Us+d?!4D<`OG^Gm*>3iaQV->54T?P9>lG$ z^mLFveb`Ai_R~|j>5NbMGS>K=AZ8x*Uo(J zxc28e$Srrik6b?U-Q@C|?R;0Hm;CvQo&3dq z{!(uK!Y6;>nZNMQU*9_C6-#$6uKdo+Wyd+X?0f&Ta-F-2kMnr(bWSh+&hIsDIMzrhKoS%%RbCvOT z-m-c*hgp54r-S_I!%n)fpPtH1XMEBh&-{Xa{+e?vH{Cve`R)H_$9IA3`(9AFz9YoP z_l0=+?ht?9BdVA06xCOHI>?_s?4%p}>8adw#wY#p%rE%oFZC+jcbW40UXvZ)akB6G zPUZUU6CdA$;^{k4{Cz*FUcM_;U+L)}fBLYKZtSP0a?=@~^v5%Q;h(=|pY5i9&fMcJ zzkA%-nft2O{@i1|<<9-q%V+MrUY>Iw_VS;5vbSE|U9G;-(?S09VJF?#Pfz8hGd}5$ zXMVvyf2mjL?%kJv?xkKkb6@q^pL?vg+_~R+`OLl7%X99-UjB1W_SVZgx%o?a{*pg` zv6H{p&tJ+-XMEBh&-{gd{+i#FH(ea6@{3QE9dWC&FP>H9igOho@vq`3E>`@-%c>oU zqm{p;=P&v57d!cj{rsie{Dn{YAn$8K3mWGr!=UztpRA=L*X2yg_!H zL%8lWy!^J*V7s#wY#p%rE%A;;+}- zbm!vA@4Q@goTJPB#09Y8E^;KW#=^%glu#;}=r>An$8K3mW zGr!>fioafS)16~1zw?dRaqjWjpEz}u>zrhKoS%%RxO4G$-m-c*hgp54r-S_I!%qHU z|LQsArZYb2k7xeEKYzXWcR%WbN}u?_s?4%p}>8adw#wY#p%wPEDFZFsZ{ac>P|K{iH zy!ko%Z+@=aH$TVcEzj|M%X9qS@?5>%@?3r2@|+HDc}}0VJg3{6pVRZr&*}W;=k$N` zbAI`j{5A9PlhVhJPs%_3eUhE=`;+X?x!fm}JMH92e5U<8iRZMdC-I;5_N01EJA6`o zrKf}Z>BCOCv7esGO=o=4AJ6=PfBsUh(x>0u{L>$=o$05q*#GX2xaCg2zI>*?U!F4# zT>djY+@%|GMkwKL=DwLj<3 zZn-lKUp_NFU!F5=U;Z{ZMWQ+H!q)=PcP4zXD|Pme{a2JUcU8}p1!_!t&pPC3`DcCdG{4WftE9Im;CvQo&3dq{!(uK!Y6;>nZNMQU+Pu*tQ&9sSx;U&v(CKsXZ?B0optHu zGwapMbJnq!|EzCsy=L8e>nlAS zlWy#%r*hL7pZtYqe!)L~saNTVK&e@V|@^5-vh@)!I0OS$Rd6y)ANzY&M=P!2h7yJ23x%ms9{Do)! z!ask_KK4y_4!``)=V!;c{p>r>U%Aft$7lARFVESRzWm)6Xxwm*Ab&~EU-IWKcG8Xg z{H5Idg-`y%Gr!=UztpRA_a@5kK1Fuiv&g>t7nSQ?MttUb!R0yM5iWoCJF1s^ANfmq z{*pg^*hx3`(^I+Wj8FRGnZNMQU$YNz)4jW0e(!N-$2;BGpYJudTh+7 z9v|LspV^_89u@~00w>BfF~DmR_+Nq;=^ z7ykKc&N;kPy0|Ol7mp=7;2y* z(}$gOV?RBWo6h*8Kc4vo|NQ0My3*$y&dopPbFQ5^w{z{!d7kU9Ip=fzHRpe>zvf)f z_1Byiy8iNRUGVkdvGpTCrwzwpUlc;*-U^Vj^Yyy@b2 zlwW+0?1=l3{W&jp%YDpU6^Z|x$Gi0sha`VV&tLNAFLv@5`}s?``3s-? zg=c=jKYyuL>Ef=Gf6gmjJ9Ccl+Mn}{x7<1Rc=^nE$jfuiNnZYQe)85!+?eVsJssrF zU+m;B_R~|j>5NbM&w1c$XU+*<`*VKy zmOJN)FP}MYe0k0}G@0k{KZcGVn2T=H-F)izwpdo_~$Qi1xpu~ zul(ZmWk(#p?9X}cTduf&@evO&p5g@7-oy`VoEKNH{v|zs$)CU2$zSZ}FXiSheDW8b z`33*{rCz0rqga0N6|*DmV)n&jtXy##<0F1!JjHd4zj%+;OB~4RD?J_LPak&j7yId{ z+;qk#{qf8%_~$Qi1xpu~ul(ZmWk(#p?2GSLx#IrCM?AoIiW3MK1R z=dX+AYV)?~a%#OH=*%yzoa>Z$kkNA!86xT8S;yqR` zaUiR&^mLFveb`Ai_R~|j>5NbM2lde^x2DLsG5pTF42U+m{E<>oJZ@)w@@1^@h|UZs1-x%}RD&W?AVv;WQW4t3>v zCptdfkB+BzrQ`3t>FVVj>iU=TbdW!N*hx3`(^I+Wj8FRGnZNMQUvrQCrq4a}oBs{( zc-^%#_tvldxzB#foqO(=&)k2%Jm+5g*)_w>W=!FXziF#g&ntX|qJtiGkwq5Sm8 z4&Aa(&&s89eCQufeu=-hTh&WkyXq_MRyv5gl|JHbrJJ~0=_&43I*YrN{^D-sml@Bl zzr@`tUEHnmi@TK_aksKB?pEcByA>aCx8f=8R{X_Dt6tKpul(u2PWrH)Zpuwhe9{@u z^v6HHs8{|{-_q$&e)?pGZrP`2<b`9++W`jRUP;%1@u{&@KD)tXw+BhyL;8m-y>npZ#Ng z``7Es{5a>wz6IvrIal^(nBV8T*<$Ts&Y>;VPUd{tV(n+nt-VEl?P|`mE!N)VoZDjU zaL&Ii);>$uZp*JdXGc5FzV=_a`bB*7mw4(&@z=lJ`@_C$>vhsU61S881^C!meC#hi zbv;pu=wb+_~^FwkDiN<&Wn%!k30{*EdMiqJ;UdWlZ(&z zx%iB$i_dtw_>9Ag&-lFfjN6OPc)s|I^NY{;zxd1xi_d(q_{<}V&-}9Z%sY$Ee6;w? zQ;X01b@tGeNpLuifnNJs=d3N!ce;1#5dGVRA7oT~2@tNNjpLu`r zSr05e>x9K;{jm6~D;A&mYw;N;7oYKS@flYic^>2K;xi5}KI8M^Gj1lnPc1(4*GmS20$j&`1X z?Z0yMi}>hY@zlTKuYXl9>Eci+SAOxSV0Of zy~NRi)wgsyl%GD?p=!<9-c{r+YUr{_f+z>gApetiGkwq5Sm84&Aa(&&s89eCQufeu@7hZsen0(%nl^ zuKeyR!R)xl1n+n__nTnly7vU*<31FOr+ZQ`{_an~>g8S)tiGkwq5Sm84&Ac9L80{>H=VC0$%2<;pMK5zLM_Nbs&V zCO#6ZTyc|Ne8f|N@f2qX#$Ws;SiQt$g4MTlI+UM2*`ZtZcfE1SrE`4fA5VUXzxDi_ z6Wg|7-RPdCa;+!b--N9*=e*fs>reMRrCXP}2MSxS&bhV4*0Ju5O1HjspA@$4bLuNGYURrB`!&pt@7gf?zIVgQ^&K3>$M7oYaI__W)_r#&w|?R@cR|BFw*SbX}+;?s{7pZ;~zojX;>(;pX~e!BSd-^Hh2 zFFyT!@fimepYdVw88;T6@nrECXBMCFXYm=A7N7BI@fpV!pYd(+8TS_Rm+$QP%Xey6 z{=YikuVHq4*M`~my&G1p@8B>#zK_Fr`fd*6?|V9|UcR%#>RUP;%1@u{&@KD)tXw+B zhyL;8ulVy<^^)#ffpX<{-T-FDIRuz}=M!M%I=2Ah<2(b5r*jT4{?0$Z>g8MntiGkw zq5Sm84&Aa(&&s89eCQuf{))f#hB$S~GOvmA2Al81e}m0~;=*m7S#SK|i5CZ(H^q^I z&8Ona!RA?U=V0@%cyzFNS)4l9d|kSEy!__(?3nknZ#_`C)(P>keu$@aMf|Nds+V+e z`IIZaczrNC;`qVri|+?3SKL1sAMpTTJjDrw@fSZ3Rxfb{Vf8JY4&|p$cIcLU>y65# zbA0F@PkxF2nZI6EmT}TOXxRAael%=cb#EFr-nvf>8;9MqhK*qWktX(;$2WxN6@4?!kbA7P(S-N&xe(gCs z+IjZ1|H{=b;-kOBQ$LEo{#CuCJIAP8`JHcs*>Ua>X5V>8Sh>zg!uU8p3FGNpC5*rG zmauv`hY721>2xSReX>Kh?CW2ZOXv8|Kc4&&fBteVU0Kqd>xSij^_=&H*>Mhh^NfAx z!(rt*HxA?DJUNV~bLKGq&Y#2T+J+lSeAo*!1ObN(RUP;%1@u{&@KD?Rk?JI z5B=lGFY!PAdRbW~eeub^_}F>mdDvfk%3XZ;EIvFJAO4F^y%wMPE zEH~;u|@$viO(;gO|cCz@ipT(zLEk5mS@o9&PPy1Ya+U?@g zo)@2XzL>wJ9WFloV)5xOk35flwD_@q`2A1$%Q)#AK5YDSJ|8x&I=2rSZ=L6djl<6Q z!^UUl|6${{djYWV+u^lVD^7x?q9&lbuR)yusPSba;UL;2~G9lB+o zo|Q}I_|QL|{1X4O-q^CvyteqvcZ<(FxcJPEi_g5d_{^t^&pf;M%)g7zyuA3#*Ne|Q zzWB`Vi_g5j_^byOpLN3Gvwm27))kA-dgG?M2Tf1;-H(RZac>%C-+gLWx$arR__%)! zDjKBNZuzI=24XbbIbSOW4vO~A*)3b8v93T3}lV9S0*7G}88V{X2Rj&T%JSwc8 zI;RSs_2**!+PPNg`n&V4uyMdSSlIaBd@O9-aBdbho|JB!DZlY2JI1B#8?T(3^?!|H z@i898(|8#Fv!37l(w!6bf8}?6I6KZ2!|c!Rg~iHs4p}-r&L_ioI=2kt?>sZCUd}ng z>RUP;%1@u{&@KD)tXw+BhyL;8m-wIg>#fR?E=~?CzxX*YJL2kWp0WQS6K@Art~fj} zKH~Ghc#7KtufHaq53F9|{J`t4lTL^7(|*@qp6p`v61P)+^(~za<)=?}=$3tYRxX|6L;ra4OZ@Fe&AF6k z%Che<=Q7JW#4{L<=RJzkNu^1+INcoId8LNN$>lz{C&4&r|-G!_kCHp zegDO$@4|TYy%_(#Bdb^6m({m)I+UM2*`ZtZ=~=mSjt~9g$uIHOzh<9p>&1_=PqmnT zXa8z3zt6tbV(nq}yB2FFvk$gd`En=RJfWFwvp-#!mJ?f-a79W4z^wz`2zngyizWB6<#iyMtKJ91mX;+I+ds}?k;o{Ri7oT>!__XK6r=2f8 z?SJv<7mH7SS$z7@V*Z+Y_b=zK`CYbH{`tMOn4S3@x0wC;eYaS-^Sf^`KJ$BUF`n}~ zaWVe$`*E>)iR-Q`^(~za<)=?}=$3tYRxX|6L;ra4SN!>_dP$$((Oa(k^ZR-+JM+7H zG5hm-e6e!pclu&{=J)$zJm+`)V*Ka#{$lkKhhM$aw{$v`pFY{4TlVQ$xpa;X{o~1B z@#nAEXM2*r#0`Vx7f%dkN1QR3eeuU&<%&xN<0D=fjHfteF#h73!RjUM8LYmg)1mzI z$qwDJPtVGwbA0F@PkxC%e^oE(;=CzWe(~R6cEp8)*Z#zdgOw|e9E^|naxk9a&cXPL zM+d8yICZf4mQIKA(|^g-Xqh9J;IvvVSpX|^r`}C|_I>(3p@#L5IpZV)0W$|O@ANaR(5&YhH3GJbC6xvDW zE3}`^U1(RG$I#w7r=cBoena~#UAry6_M9EL)|&wSrmjOTp! zS&aXD4_d5V-X&2l^(~za<)=?}=$3tYRxX|6L;ra4OZ<<&p4PwmesuD0`mwY4*k63g zU3~Z~K0Fs6{)pLVtQw712l9WFlYbMa}ni%)xAeA@Zq)BYEqezExUm&KNsjYVq0EdgOWRcP&2qV2jWG*y6Kqw)pI)Ek65fi_iYs;<2DB`-F?n{^3n;zCQbnn|}5o7oYvf#b@7g@!8K@eD*mPpZ(9pXJ2&j*)Lsu z_E8s~{nf>1-*xfsAD;Eb*{9v~vw!=@^Vrv2%wNsR{MCFdfAcsy&F}0t?<=?U06wh~ z@NE5nf9neMYQ3SprPHDO^vMq0vQN*-rE`4fA5Z>@KYvv(>CM;jH;=Q^{LX&!zH(a+ z;L|z*&(;t4x2{mH)*I?uIvvVSpX|^r`}C|_I>(3p@#L5IpY`F+%V!<3_^eMBpLNUP zvz}Re);WvM`e*T37cD;PrNw6*wfL;B7N2$3;%GNi9k}?c z4{!ST@#Y`@Eecs3^(~za<)=?}=$3u`t8(caANt3WU*i8*Z@gxG zXI>M>gP!I)@jYPkptv8f`B6L&*t{uD2y8wTKLj?>s!eae;en%|U-{<$mV&lO4?pSPmnBOCdjT`ejWwG(3bmL6LtDN zD)M)Zg`Li~u>T|Hyp3`@4}(wVWbo|#4E~*~QLoP1sBh_XC_jC&L$~bHvvTPiANt3W zU*d26>N~7)vhTCT&%WClSNop3>zVU?**M(yU*mJ%g^k;NFE*a{9oabF_hsXM>E?y< zn=i6s9?AZ$-%h#ao%ooK;%T0Wzxk_rN$>lt{C&4&r|-G!_nlX{egDO$@4|TYy%_(# zBdb^6m({m)I+UM2*`ZtZ=~=mSjt~9g$uIFY9?rh#%Z-Qa59p8W8|bI)C+NTJGw9dt zKj`o6OBe^*uP{Eek73+sf5UiEx^brb#-HpMm$GlXs$An(e2j1LH15UUcv!upw?80% z`v&Z^pTK_m49ac)0iX6I@NB;V|MoG|tNji2Eu9YKr%!h1mVJ6wE}i2;|9Bb?(3q&+k^{wttRK`|5bM-;RI#@aon6y!w_-hw{@WJ9Nwb z>UqkgbA0F@PkxEN`Agih<}Y!>VB@EFVz6;loH5vVEB+X492S=hHa?421{=460D0WuKmvOXv8|Kc42V_&@fe z9_w4%ZQcfc0zdP{8`T z_bFiGfOjik~&E@0zH>BgDz8-KE6T*|)js&b8E@iD%|)3_J^$9n!zFX`Q{ zl;3+FIIuJKpck|6eGuu&^==4^kM~4iJiRjl&1KqzfK6Ee7xY2z* z<4NhpnerQdvSVDzzVWJZjbrgKzQxnH7k}en^^)FwH~G5<$4>X-*zew)a=TB5PxtKb z?EW48-OE$2?(3;<>2xSReX>Kh?9;Py=^P*W$CF>;uYb+DciRR(&bo0i|IT`HF~83` zbFua?>(9m7$*fBkYd^DIU94TrI(D)4HtXBP+M#zzYM-TRx8>KKv!k77U;D3I{USd4 zOFZ?X`0HQQOZu$yw_N#W{lA!<`CYJ>eeb#8rrh}*u^6BEeX$tN`Q5Qt|C-+;i`C0J zGWD<0=}><9WQT6qr)TBTIX?7{C%?r1;jdq?{Y851Q~ug5JGE!_Yv;2xSReX>Kh?9;Py=^P*W$CF>;|M1tNUeary^4D(JsXen_J6CS)AD{XK zp7j^}>qqKU|5D%5=}><9WQT6qr)TBTIX?7{C%?p>zgkC0Z+#_y>n?U$kFno6O}VY# z@M&F#XX`!uTL-FF>qGS|oet%vPj={*eR@_do#R9Qc=Aj9`Kx+KZ+#_y>n?U$kFno6 zO}VY#@M&F#XX`!uTL-FF>qGS|oet%vPj={*eR@_do#R9Qc=Aj9tq-SO+rO+sCVjE> z$>d*b-7!0DX*t%$VF1B78{)?@nre2G!uS&P>D!=tucC6E~ zzxxlTTo(_NP58R_?Tu#rRD7S&ZkjtHtKYg-8x9nRVRxX|6L;ra4OZ<<&UNZKc^u;It;$!EL=V5>GDR=SV zv-t2_eE2Uu^;&%DyZGp^_~^6v=(hOix%lY3_~^g*_+|0&*G;c|9{+Co@%!S_9u}W= zviP*0#iv~@KJ9JsX@`qX`&@k5?c&p(7oT>%c=w~u@4nM7HvROMN1jJNT5LR={=8Vf z^KK5`>5tyif%Q}G?7;f3_jh3Z+Pgfk{_edV*f`)FAK3WdeIMAk;oTqDcv8A?ru@dA z>=>7_Z@j8p<5+x*Z}Bwl#ou^Xy`+2RNV)QR{|IKsyGStm-b;d&>m4N+AMY!{czSmU z#@~BPuzGo?30B|I=}><9WQT6qr)TBTIX?7{C%?p>zlyUYz4%M=7ng~h;x(~f94F-# z-wB`MKH*tBDEx~PrC!C4Qs2_)P=5Mkhi=)YXXVm4KJ%vs+aWQFUenACU%O~ z#C~y{lv{i!e2V*oXYru$FHV$t6+cRSOQ%Em>60D0WuKmvOXv8|Kc4&&f4{%H} z=X(bew*L1%ChT{CcQawX7rdtl`yKKA^Ufyh_l5U2VZS@P%L)5E;=NAT?-cKN!hXM$ z?srZ3{ocur-$B{;`>1mLZiS@y;pC{?GoD-?>=1 z-bIy;kM~kxJiVg|m5)h);0~@hqMp{>3>|ui_u7Z|QU>KYg-8x9roia_Jl&`p1)B z;?G~zOZw-W_=oZrSCF0J4YEJ)@U9NZEj}SW#Vy3Mc!u~F=TN{}01u606utRLcOy%B%wjp`+R`rVc*|MbVj z>`Xsh%>MM>#mb$2y%?YA?~C!AabPk2Gd?U7FXQ7S-f%cX>rKSv&APj{}#90 zyj(nU^L6Rw@$#GBvt!=RzV$%mS|`NE`XQdy74f&;D4zLA|43v0$^Qa;>?}U^7oTz$ zA3ht0{P0|S_%A;7T72re_~@|s=(G6fw)T∋vEWkN%5~UzWf5%ez|5U*4sHji27D zf{m-*v4V}a-nW8{!`{7ujnCf0f{okW$%2jN-p_)K^WN2hjsK;a7s_wG$c}j=`{tL* zHSfg7d=yXfRQ%0f)l0f}#FQ()_r+j#ygLT7?>#bDx!x&*@$r5cjHh?aVEo^6-aCWU z%R6YW`j$?I^3x|fbjvimZKmQIKA(3Sihcec(MLIM3AjSn-PFE(z>IKS9< zQo3=b{KlW`7?-kdysBK|SbU6c@igwm|NLIwvZT+vwpjj|?-sK&^Wb9kXMS9)+?h8Q z<1_Q=`UTIKXBXo?^Y3Eynt6G#`j$?I^3x|fbjvHI$D zb{1<7bDn3hb~5LD7HdCq{%5gvHRpmBYj1O2Xt8!!JU#8RbnUkM+H-ca^XzN?m8)OG zM}LW@eiVQGt9nWAK9T%$o@)89Gv}-pvp?sr7AtqoWi7^M&TB2kbIx%s#(&OtEmp7M z>8Wq&bSOW4vO~A*)3b8v93T3}lV9R*JzqPtZmfM;Pu6a&Gi%S*pS5%A(%QfEYW>1G zw*F#$TR*byt$$e$mu{V0e(UG#SXXD?db@J1!{cLp9#8A`_*>6cFX^>U`D?fA)SlU| zoh!HYk5Byq&-x4g^&|DFf2nWjbSOW4vO~A*)3b8v93T3}lV9R*Je+-iXZn|ZH|IJQ z>yLBZW3hfZ=Rg+gzjHohv3@=0Mi%SubDm_eabV7wEH*yO`IE)QjX9UH*mzR9ai;vn zpX?ZyvTwYqT;o`LjBoKY?#2J?Z){o8=N!&r`R9DjVs_@-&SLiGJkMg~&N-jO_{{mA z#dyxSpvCyld7;JXHRp&Ht8eLaC_jC&L$~bHvvTPiANt3WU*gYS{r-~P?-%*|UBgbl zci8WDkaGKdgipVlcHBPiN#Wn`EcNR5m-?2z^TNqbpX|^r`}C|_I>(3p@#L5I^H;yW zPWt|SIr;Z@&9Sri*k63gU3~cL@210Z@!`Mt)NApn@8YAw;-k;vqubg)dM-XXFFyJ& zK7P5szotKL+mJr}Zn6B+9~ZMT{d6(=(|;E$clz~We5SuIUY_T@8~kT{*mU*ky&Lr{ zeRVkb>60D0WuKmvOXv8|Kc4&&|FhoMa;48Wxmf-gKNqtz=_iog;bUKuuKG~sL_UT!XIo);IzIA6RJnYCY4wt94HMvDQEB(^?m`e`~$e zzOHpt`@PmzrCWEE-+C-N)@j+deyd#Ty7*Y{#nU=4{*T{Zk9tXOzf}JAQQ2vKmHqZz zmD_$SKJC-u+5Rp5?dz&n`@QO0IvvVSpX|^r`}C|_I>(3p@#L5IpY`GP>$477eAXw6 z&${K2=dqqyeAYRO&-!QaSr;un>!rnK9kuwZuNI$m*W$AtTYT1Oi_iLP@mbd`KI^^3 zXC1istPgK`8prT#e8azSPrVus)wgsyl%GD?p!jfPyHzV`d9Um-g`{)_f8W#z2C(C>`yLF<@VkaKD`5l zXYWJd-@8%j)q7IvTRI)ePoM12E&KGWTsp^x{_*6O_@D17%ab45&*9(pdHB8kAMK%i zA?>97BJHPrB<-sGCGD+!C+)EPDDAU!?Y8{db9S`z>}&s(t6#)Ne~G95760=+W$Puq z{T%t*=V7P)ANJc9Qf~W2__U9NXZuU|x9_B0?MJC^>2xSReX>Kh?9;Py=^P*W$CF>; zZ#_S84_@l`*TfB2Y<)8E1QuJjOq_wm)-w}-V6k=1#3fj4{qyV3`wrGc6USiFt(PXg z!D8#E-gmIRD&4xP{MKXHu};gr^;_jy*Tu(rFP_$c@wYy#Ueb#XAb;@z*qOKx%Z>es z7qM8m6Gvh(J`-PJF`g55Vln;`k7BWU^}d7pmQIKA(|-Z<8M5i z_Oa#acQZ~d)*om5T&$nYxVl*XZJ$BEo^g27_4gT{7aIp=++J*anDKnEaijeW<4Nhp znerQdvSVDzzVWJZjbrgKzQxnH7k}en^^)HHfc)(nu+x45`|UF*xBUlv+Lyqy{R;fs z$55~KH`KRuI+UM2*`ZtZ=~=mSjt~9g$uIFY9)9b4zj61$^tRUP;%1@u{&@KD)tXw+BhyL;8 zm-wIksP&hA_c^bA^T&U-A@Pv;!SV*Pi{hb-2w=iJC*{e8}pEH)0zIg`c4hdF<; z*tjw0QWhIeN;l4w-}sXq<5KpGSCwlVi;wXwp2ofSpZ%yUOZuF{SuFpY&sogQoZDH< z{+#DotlT;0vlyQ_|Fam+ITy4T|2Z$TSiR;P(PH&2oet%vPj={*eR@_do#R9Qc=Aj9 z`Kxu5^wwAMx9(!6^%(oD)0Er#4WHI^c(&fdzjdH`wLVne(&aqwf$A&ZTqgq;r3&V&+XG1x7)upp0}@SoNvF^ z_+Pqtq5S5H?3hQgZ+@v<^G60D0WuKmvOXv8|Kc4&&|Hu6GelJ@e8Yhb{ZTu|mv~jg~ z)W+N5R2zqjUu}FYuC;Nyc-O}B;$R!+i;r#mFWtOQe)C0k%p=)1zf`VyCqCw*c$%l; z|CqlX^^#tEY59vg%}(*C*)LADa*JP$PjRjBEZ#N##lcpu;$y3C>2xSReX>Kh?9;Py z=^P*W$CF>;&tKhZliqzd`MU?lPWR*3@7|npyHAJDoKM&>9M3touo(Y2&#+j%y053c zrPHDO^vMq0vQN*-rE`4fA5VUXKYvv(>D_mezk6`(bU%*$?#(H;`*irsd6MOi=bSTH zjDPp?)T{e?>RUP;%1@u{&@KD)tXw+BhyL;8m-w5%iaTeVEFPWlvp99e)#BF~Z;NYZ z94_9S@wqs7#_i(c8PAKGXPhsdp7FnQ^FsN}7uhk7WZ(Q!x#petn2+LVo{InZ{q@Ya zA-#BX@)xI$o#NNAUtBxo7Vi$9`8~LH@GL$a{>9Bxuj1*cZ|QU>KYg-8x9roia_Jl& z`p1)B;;(>*e()vyNXLtDREad;I=RFQ~ zdjEp`-o;RE?`7cAI~sWQz6SoiyP;ma$DzKZ)1mzI$qwDJPtVGwbA0F@PkxF2>0d9m z-WWeFKK@;N{Qk)EXb+1|J6U|%&*Iar7N7RE__V{tr+qFy?RN2L&x=nxUwqpC;?pk{ zpZ>D=^rOY6f8F%ycQ^m^$Hk|gEu2ydAZG2jX60D0WuKmvOXv9TS3LPE{>NWiFX^p^CJyP)~P?}g?O zzayGo{Jv=3@w=n>$nTNnDZf*izx;kF-S3+6`@NGLzk{;x_fh5g-4q|cr{d{%R{YQJ zudSE##((*n7uadOV83}pxy>*5H1FWqe1w1VlzKIPsc-3YC_jC&L$~bHvvTPiANt3W zU*fNS6(^7%iyz3p#TDfD;tgsK#Ua#AichHh6t_^jDxRVCR-8lau=t1CXX)B)`L*Zl zXy@72{wr6%h>!jfPyHzV`d9UmUi?7$iz~=Z@dnwS^9Ji*x%eWZ&WYo#pjg2 zxSi}2&y)S)d@A?vpZKEq6c-fF;)UX098vWuzNq?^PKWZ-Cp&b@K0Pa!&heptJozR5 z{55fVUNRm^pST>0<)3&Ri`kht9*fzZ_#TUuJ8?f2<1_I<7UMZ_LKfpc@k17?SMQCg zZ|QU>KYg-8x9roia_Jl&`p1)B;?G~zOZvo7Sq}0~e3ixQOx%^l>`y$F#mb#HEsOD) z_$`a^oVYHF@t=4vi`A?5M%A};I+UM2*`ZtZ=~=mSjt~9g$uIFYe^oEzWc4+Erh{=c zeT=v1W*kmW<8wM2x6|Kvo?ndf`OElUx_P1e=8No@N3w5zsa*3;e9TAjG*89f{8hcA zS6}(lft~bWKi!m@p7^9Qp6QQ&eo?RdrM{)pq5Sm84&Aa(&&s89eCQufeu=;SHRWwP z;m7&zyqJIId-P&{pYPO*wTJnBy;wV$@7jyCpZVUs}&s(t6#)Ne~G7l6o37zdP$#i0?SkWIX|$NojF&qnEg3#uvocs4q-7q zb3S1)o^x(tG5&L&VX=C3zfyfmr$hPalO4KcpPrRV=lIY+p8OJj>y3U_n%DZhX};@s zsCls8r{>3gx0*NmJ!?MgcdmK1-@oSHeixgU`@L+wF5Ns{e)D^F%=_859;jUFg!ouL z#M8PW{?;4SOM1UI9l)ui|g0 zZ|QU>KYg-8x9roia_Jl&`p1)B;?G~zOM3AuW{aX60Ll(yyRo%(~@~XY9{< zX0dW-owFF9S^q4?bJj(R@t^h5V)g3%FZC^*4&|p$cIcLUdR8u-<3s;=@=N?5{(96) z`m7t5gZ#6eT+Gg_GZ(Wz>(9l?optGAd}h767|&V9F5dq2l@F|5z5liS>!j16{Pf8V z-LlVLl}qRN&_AC15`XKB;)lIOk3mn;+*q>SFWe`=59z=F>U9 zy6NWGIoG<_{5$7e7n_%hmtwvy-8^1?^Luv8``Nc1s9fuW_*g&0)4C%5)*IDJ`keb+ z4)V`=;Kl6BIpM|Z|LhYlMY(gXc+>Hj^TvzuoO8&F@t^a_i`A=mDe7A~9m-Fi?9eUy z^sHPu$A|v$@i!h;FX^>U`D?fA)SlU|oh!HYk5Byq&-x4g^&|DFf2nWjbSOW4vO~A*)3b8v z93T3}lV9S0=C5b1H`*UKD&dLoyWkxa~kT^`3?0goet%vPj={*eR@_do#R9Q zc=Aj9AM1@r|1z)DKFxQvTk~M;+5A{LH*ePd&8PJX^KAXa{5$VcY}+$0*T2lyrJKjg zZ+_2?c|ZHs1C?u?5FhJ@cv@G)|FPb9)JuBpQ~ug5JGJMvf7-cnYybGvFYv6t;9oyd zulkqzmQIKA(dRhkJe+xLG5^kdx0v5&9$c(F%>1}m zJDGWNvGz0b>0<3_=Gn#C+swaKKv!k77U;D3I{USd4OFZ?X_&@fe z9(9pE>yYIj|Ey0Ivoq_K#q7^|X0dW-owFF9S^q4?bJj(R@t^h5V)g32p8A$fhw{@W zJ9NuFJu8>a@u7b_^{@EPHwWiZw*7zYH~!?OU;Tlfz4+&U$xnLv&Tshq#os*dBFwov+kNpcj_UVUz@0Ty0GgeRk=lA)V#c%rO|Nhgj`+?v0NdJm=d-}P* z_g#Eu9YKr%!h1mVJ6wE}i2;|9J9C z{GHJ&j`Sb=JAd}+4}HWV_VsW2_&+;)u#Z^QANnbO=IMXU-?Z>f8lR^VD0crzvh9z z`~UbOH~lql`olN>r+@kXa_#)vKm7-<{jd9pf8dt;9e?#rm(Lsi)*CO+PxW2Z~eXh?_%xYCx6}#E!Iw6`=0-DvG(&TKJ8yE)~^1CSHI(tKJD!mHU@|%HLaz&kz2!zq1(6Z~C6^d87~jFZ!hqtX|*u;~rT5DxD7Hr%!h1 zmVJ6wE}i2;|9J9C{PnLHH=gM4{5bt?G5=0~T+Hv|*Tvey^xwtW$@J^R+Rya&7unIS zW*k_oz0LTrSUVgY7i*uTYq#asp0lH!XJ7lTT>TzOnzcZ~fuL%6h#A= zKmBy^>A#Clzg~R$`{FYWEI#AI;xle6KI6&aGtMkNn?U?eAztgw@y=T>oec#CeM_f9`RS7#x@G^&FUx_> z@u7b_&pdVN^?o;Qs($yG|NNt0;yeBEC;jbTv{*m=sekRG7VE#i<@;V*tY3fZ`#!M# z{$0Q2>82Y8KH?ou78@Ua@;5!OapUb@`M}1L(v36aH~wVDxRib4RplDT;$wV^r*SX- z#>2U0;&n{`dO$#rVAYpLt+Bzv06_ z;gLT4zwPx8tX}W=RS&GbrPHDO^vMq0vQN*-rE`4fA5VUX|IBaZ<@Md4``cf7e}DbA zAN!^E_t(d~`nQ`0H_u;r*WY%3fBl5-{BQ2>uTOj5*WKS=pZCL`cYl9<+VB6(_xG25 z(P{T<=lj0$*WL8L^7B6H=ASv|+WDZ*__S;P^FHKP-E!aj<)3o-{KBvQ6_@ARzvwlW z|J3Q$OM3lF{@N`&wP*J0U&^ih<5R!Dv;KmA{Ybs)U+P;r9m-Fi?9eUy^sHPu$A|v$ za z@u7b_`6d3Re?2h<9zQNV{#|_hzWB6<#iyMtKJ91M>Ze^TKJ9JsX@`qX`&@k5?IZos zo)@2XzV=W1Uwrz-;?rLipMJFX^sk%VdRYF}$?Q!1HxK)*tCib&`}FtCgJU!<$~EuA$9xn|^HluJ zU)4)`^_4#z*hwGu(@nYQiBCG?ng00a7xl_t>RUP;%1@u{&@KD)tXw+BhyL;8m-x@W zJNLD7C_nzdKl|Xt{QLEP^JgyR_iy??KWMS`@WX%q0~c#2-}&PnSo`_R-~2N+UAy}8 z|Kg`F*53ZeH$1R*_~~E%z}jc&+HLu@=j>?b+1LInSHFml{t{39EB^Xd^^*SXKmTVh zANgPX2|s5sJ0Jg=4}EYR`|o`EVT+afLGSV5i}CrYKl#9TzUo7N?jwEp|FYLTuzG#% zS3I!#mQIKA(YUCzv;m5>7zZQn|6|(+D|%bSLv_4 zT{*`Z?-)LX*Jbq>_JL%8k zmp|H+Nf#2|s*FF2uU--ap`n6y5>>GaX1OMeWf6=qQ z`|N>#;d{LP*=zsl1AoCMzy8^~{Ioy5HsA1DU;pg?`PC2nj{ouX&*t~arvJUKd;PPQ z{_-p7AO0?X;^zOBS3NL0zx=ZwnEf~Wo(ER$2Y%B7q| z{YU?iFTDAG&VTfU*UpcB`)jZLfAaaSz2$!K&v@;#_`LKFzTjCrKlD$1!R7y!ul|Bt zuebl6FSzxUo(}S-4?F3`etIf5o$*P3Jo5|w`D^2y*(}$gOV?RBWo6h*8Kc4vu|NJ#$`c3z~ zXZgMRnH}$eX5agymFxY`_;^<|p57b1{O5hr>g9dXTi;1f2l>;7opfVAJ(Ziz_@qCc z`33*{rCz0b-?RMQ{mhQ{K(p_i(8~3GXnedY8c*+y#@{=n)yw;&)mM5t$e%v!q#OI` zsoZqNC;jovU-;**nagjw`={l1FEu;vt7hLl*2;CiH9qdW#?yV+_`4@tz1*LzzS7e{ z{`6rd-Pli0<)$+}>5pfA!9RbgSLyDbmfyY9?6|L*efL-^*ZtP`%=yX7(|y?ZyC++{ z+@Gz!($hiy^kFC6*iTR8rZYb2k7xeEKYxkKRJwRgAn$8K3mWGr!=Uzvf=mO`m&7H~-vM zx_0Is)3rbMn{K&t@9FZH`%stX+>^Te=l;~Km-o=Cuk>_~KYiFqH}=z0x#^5g`s0~j z@XufBRr=f`yZPsS*|jtG&aVBrk9NzQduo@@++Vvq=U&_8Klj~ky}XB>zoh3c`STY$ z`HTJhrQH05PyWI)f8n3MW}SS~-QOv{dp+54-zWR-0adR1LGf{KD4y;U#os-n+M)YL z`Ad5Kl0Sd3lfT%{U&_s2_~b7<^9%m@OT9{Wf2aKJ^<>9=pX|E_RJra4#mBv&c)Cv% zfA@^4m-|Q6S9&_gpFZrQ8~f?0+;qk#{qf9S_~)?_s?4%p}>8adw#wY#p%rE%oFZC+jdEoLpXPX`8 zZ?o@QZsj_!8z1L*5pgr!ask_Z@-%^ zUQ_wSamtSPPT3dtsdB}GijO!^@f1HQ{^CkiFY%_Tuk>_~KYiFqH}=z0x#^5g`s0~j z@XufBRl0ahLs3b^_89u@~00w>BfF~DmR_+Nq;=^7ykKc_Gn%%-TN2i_bx_uyqA%E?`Tx6_ch|< z-Hmv9k0bux>8M`b@2I}g(?S09VJF?#Pfz8hGd}5$XMVvyf2mjL-oGfncQLZ#y^QR8 zN27ARuMr>bZp71j9P#%~NA>c4NA;DS4)UiDJL$%LdMY=a@kxI?^9%m@Yxd@D`n)4{ z^UwQY*Ur2lWy#%r*hL7 zpY+Ewzu=$0)T{J)_wD9?^{0O4wKMO;UHkKX+%0$BmAicAy}8SC-l4nv=Y6_cuX(rb z)>nG|l0Sd3lfT%{U&_s2_~b7<^B4a4YtDS!^f`xr^UwMGYiG{wU;A^O|CT%F{4bw5 z|9^STy@1Pq?hD*{d7rfQDLsG5pTF42U+m{E<>oJZ@)w@@1^@h|UZu~yiJO1!Q(QZ9 z&*Ivj`xm#|xtDSI%zcf^bMA3m{&TVkdvGpTCrw zzwpUlc;*-U^Ot&+?tXXq-TTgt`{3DkPrP#7ACHfFQ@QDkPx|ATzwpmr^Udt0yI)X#_YSh-K0@~0Q>a|`7vkeyLpMK1R=dX?^eLHXS~$d3C6*>_K&a^HXMN5sdyhIqQ~ z5P$a|s+ao_)mM5t$e%v!q#OI`soZqNC;jovU-;***=M`y;w6@U;)z{56KCw&pZH_9 z+=)we`AodB%X8wGUH%i_?AB}Ip56LNPY3zahn;j|KRuP3&iJH1p7{m;{H0!{f6l~9 zEWdb(*_pU-*Z#zdyX8(Cxyxtb%Uzxmckc3^cyza36Q}OhS9<=EKYy{4zu3=T%FSQ+ zq(7ed3;+BzzbkLLc+}+=r#d_0S7%>b>&g}HIzHlH$5VXl+MBr9wL|f=YoF5dm;CvQ zo&3dq{!(r__~KYiFqH}=z0x#^5g`s10u@Xuefj(Th9?#Gqiy}9hTPnUi7>?+s&yZE@57f<)~ z;_n_`^>V+j`btj+`O}A;bYnj~m7C7^q(7ed1^@h|UZuMqSAO^Avg1D8wLkalD%btH z__&uBPxtlW?;c2y*(}$gOWB=+o<)$+}>5pfA!T%M1z2>I>p`Z1uZ~iZP zx6inCzVCJa#kK#9pZFVYxxe#QeD3A*8NcrHFVEllUw+}`|7B0V=+^6}eD@dK`btj+ z`O}A;bYnj~m7C7^q(7ed1^-w4^_rXhr+(z)Z~nLa)Q`D#e)AuH@fG{u{Smj^@BFTx zclrFQ|LsFB&%gQSKjiX%+dui>Td!Ar(g)xAO3z>N=P!2h7yJ3^8>ig-g-`y%Gk@Wq zzh3;iAN4_{dylpJ-f7K__gk~?UDwL>-fMik0~^mzp7&vEZ{Cfq9ePi;_9;Do$)CU2 z$zSZ}FXiSheDW8b`3wL2^}S#J;s-sK{*lk+f8jYhFFa@eh3CqB;W<7pKF9OL=lH+) zT)kd=uD&lmr^AcS>GR@qy1nq6o-aJ7^9#@E|H5;A`N;e=^YW9@$B$3SKmL7^o$>pV z>`!}mQn}Mkp2TO`&y#pgyLuA;X>U)e*R;bY)mM5t$e%v!q#OI`soZqNC;jovFZky# z^(uY(-OWG!@!FYw`ilKe{0+C<>DQOf^!Lki#(~R!#)n(488>cyrKf}Z>BCOCv48cP za?=@~^v5&5;Qxxh-geVxoV@vG{JeH%T)p-`E$`|?Bzf6@2%I&%eTJL^OyYji=F(%e*T(y`Ra^M{=zeV;h(=|9rd*IS%*9=|Ey1* z=J#2*Jk9>BXP#E>taF~mXVyPY<2mc1r}eK{FFmb)%{uC7{Y!fOl0Sd3lfT%{U&_s2 z_~b7<^B4a4OT9{;b>q!H>&a_p)|uD-tUqtLvo5`SX1#iO&N}w;pY`pn*Q|SQeWj;^ z{OQ9^y0M?0%1vi{(jU+Kf`9&+apR`XI{)Sur#d_0S7%>b>&g}HIzHlH$5VXl{3UL7 z{t{0+e@V|@^5-vh@)!I0OS$b>&g}HIzHlH z$5VXl_=}rey~NY5zS7e{{`6rd-Pli0<)$+}`3ukdg@68XCb;zZ9ewl9@9S%4es^E{ z^LzZ3JHOK}pZWcMdCu?p%YT0F-+GBRRehzWgZ$~kPP(z5p32Q%_@qCc`33*{rCz1a zzQ@f!`ytoP?2}ykvww2Soqd(dXZBkz&)J8${AYjW)=Rvp{3Shq$)CU2$zSZ}FXiSh zeDW8b`33*{^{wyy#+yF-R5$t98Z@hM9AM)Ct{mEPI>|0(wv!8i+ z&OYbmKl`7zUfxg4U()lJ{P~NW{KbC$Qf~gjCx79Yzwpmr?qrrO{!jVE19H~*_Y^*gVf`7U$q&-a>J?tI6&eCGSkN=P!2h7yJ23x%ms9{Do)!!asj~!25jvP4}Kc`MtA{9q%t>-@6Qz z>%E5fc*h~0-gl_IdH11q=sk$~m-PH4fBs@8f3csxl$*cs$zOQp7yR>=dX?@yh4Oo6 zAv@k*$i8Sq#c|654kH0wQ)l2;I>MK1R=dX+AIc=^Q@&yING*%ybra>XZ)kGSRW6wf^V;+$76@z1NT^mLFveb`Ai z_R~|j>5NbMhgZ@F)J*AKXS#KDfI_}KCP^og5YI}}ele@V|@^5-vh z@)!I0OS$<<2?P%V*B7UY>KV^%egA z{m;DhnsczP)OXU;LH_*3PX1y)J(Ziz_@qCc`33*{rCz1ax!;?A&I4aNb58i$pYy}F z+&Nc#`OJCa%X7{lU;cAG`POUBE#LY|&tLNAFLv@5`}s?``3s-?g=c=jKYw|br1Uwb zee-+ABs<?_s?4%p} z>8adw#wUN_nP2eFU*aT`KKCGQ{<$AR5* zPY3zahn;j|KRuP3&iJH1p7{m;{H0!{zv>OY_U51anAgtS)4cZQ{^l)r?sZ;1bKmpw zoO_^`|CfI4e|GCN_eO7hrROjC^A|h$i~ani-28=4{=zeV;h(?ep6^Ycd$KqG+@HO6 z=3ec!|IMHGU*B@)9`5Bc_j51LxwrcY|F8P5ZoTH7?<@74^!z1%{$eM8v7f(`o4@eM zUwGyh{PUN3l|J{HZ~nROeC^CV=xcxON8fVi-t^@&_o*+>PyXWHc=^x$>szn6mwoFi zJ%7oczu3uN?B_4#<}ZBm7oPbG|NJ%g=x_SmL%;dwe)_dD_tvldxzB#foqO(=&)k2% zJm+5gVkdvGpTCrwzwpUlc;*-U^Ot&+K5+wX{x`hib=S_s z8MyW*{=hAF;u2gw6R+U%oVW*<|HM7G^_sW`x4zQzm;CvQo&3dq{!(uK!Y6;>nZNL# zxN*;B5BrJu56|Ie@aO*6ZxxPTt4Hw@VF77v6JaD);;c)T8;o`u<#fOKB8xI#x z9xl#2T>N>sxb$%G>fz$p!?T~X@$KQ_-owSihl`UB7e5~^u0CA6eYiOMaPj%!;`W#B z{8;&&D}#$C4;N=1F8(}RTza^8^>A_QVfAwU4KD6ITs(ZZIQek#^Woy^!^PW&i^C5W zpC9g>1(+XwzkvDIcMX`|eeZy^2j4+p?Zo#HSo`ta1lF#6Pl2^J-&x@K+xH`2?Xz_4 zw*1<2cC_>CYyXw2U&KfMil=@QfBnn%7iCHJ{Q{QXcMX^w-#cLTeFuS+>-z|dkMAZh zp1!BR`1{TR&)>cu0jqE6bSOW4vO~A*)3b8v93T3}lV9S`U(R7FOS8(#!t6ND z3A68(&kUkUErCAjyP;NEG1`6d46-L!2d#!2UCR zx6b9l#$o4mVdJxNys&ZG`Ciy~?%XeIoOd1=HvX4xUMRo$B0J`h?3-UI*Sr%S^H)60 zU-3Wh+-+IXou^f<{Lb0J>^Of5ul+ff3oF-oT^Jwdcws!9?}hPq?iW@s=Ye7MEu9YK zr%!h1mi^W9luPIM&_AC1693*!Qx-ou-vaZmb1yKzI}ZbE56;QJ+KKZsu=e9z4Xj-` zZv$&@&f&n?q4PPg_F1}iTYl|1JKA~ndxy^d)i2_sf5o%+?Bwa4JGl4MVELVU$&T|d zo9DdC1}oS385keuYG6E_w}J6@4hL2*=W}57Eu9YKr%!h1mVJ6UpX2}1IX?7{C%-tK zBTw%V!u)9e2j*YV0`R5!P~!P zKMKa*J{7E9_OD>|Eq(jf$xol`&@KD)tXw+BhyL;8m-zFSb7IPpUjLH6cFRufnf>~g za%=zi)GzR?zu;d#Qm^`#`j$?I^3x|fbjvDG%8!rlk}#gWSHk%FjtQ%m@0+mtmQIKA z(9gU!R(0d1hX&h6RceEpkRE&iGuMIKMKZQTq#(+#G8WEw{$v`pFY{4 zTlVQ$xpa;X{o~0m@#nAVC0)EG<;p+buNSi;zLRwJ#eIU6D;^Y#k2p~2E}yEXfM&sMJA zx$*J)H=ceM$N#Z^_^6k3=aF!b-#I0i9p{%|_MK~jmFv6{jE{3rFrLmw!T38j1<&8i zgAc5}rPHDO^vMq0vQN*-rE`4fA5VUXzy9UBt#bL%_gt8NedmSw-S=Nud+=Qt)=qpc zhP5Bxkzwu1_hndn^W7QN4t2B!#Wk;Nreeql6itFMd-ixO=F#h7h>LuNN3FXRf9|g>g{S`3#_Fcfr zwI2h<$36`hPy07u{O#+2)ysYlSba;UL;2~G9lB+oo|Q}I_|QL|+9m#<_1+JE`M52XLr4_|v-eZJaj>xVC$pD928lO293`}|eq@?-Jg-{Q&d z#s9P3`>B`o>MMUbu#-OQr<-!q6Q6X(GyUl@N9ZXA~1J%rNPaX%r<{>7ie%DuRB7@vz*hw;2Pb{PMQZ->?E;@)BP zEu9YKr%!h1mVJ6wE}i2;|9EPb_-n7~CB5}G`CC6^$Nhxr#lCwBVdc8d5XR>>@18># zPxl|f_`4SozQ3>aL-j444&|p$cIcLUdR8u-<3s;=YM1z%ziuDP*1q`3*5CNg*5&xs z*6aA&*75k^*7x}5*8TYH)&u$T)(QFf)(`pr(#;FyH(zAOJd%C$OXZq(;$uFFr+F&= z=CA4{z4bTwTbE;}^}5-A>v+m-eGi}3{qSr(5dYQ*)vNVG^(~za<)=?}=$8HI`O2kp zeCQuf?Gk_O5n%TJ=*}s?%5{DL#>cq^ z7*FRNVEmnffYrk{q5F2hxJ4E)l1huOP`;4`Ss`Q=;ztj|0~zHh>!6SPva>5&mXQV z>9-C%EdQ+!53_UY#-BWA|JIX-m3!;V!}#3#^Dv(7pO62oR}ZU~`|7K2>2xSReX>Kh z?9;Py=^P*W$5Xq+|Fze5%94KVI4u9Q?=U;p?!)X~e;8Ko^^;+IuKx_$L&)L86JFMIr z*TeYScpt{|{J^mOcK%^lz1$C0dzDUy^3x|fbjv%$t=ou0TF()m zw9X@LY5hk$)4Gs2r}ZN7PwPnHqSlwhORYOyeZJPC#8;(@yUH&f%Z@lL`{K9C71zZ_ zycbV#VEq5s#fQ~Pdh0pzx6Z>(>p$$bE~MPni|}b33D4G-7T>;gC-rJQYVq((r$hPa zlO4KcpPrRV=lIY+p4uh;Z+uYShH(ow@KI3Tkjjylt{Qnz|OMm0^ljk#jhu^p!e&c=k z`GH~lo2Q=NSo-rP!_UtQKmRlQ{L=9ASHsVb4L|=j{QTaqc%yY2^IGdU=DXH;%!94} zm>*jgGHRUP;%1@u{&@KD)tXw+B zhyL-@F7f9N-Rq90ap%5w*m!ggJZzl0A09S--5U=Z*Y1;tjd%CV!~B5z=VAWAz4Y+? zedE4*m_I3k^`}&O2_WK#X?E^Hf+aGAWw{MUiXg?wU&^|+c!~GBH#h;YU&y=74$qv7ieg3d= z`LX!$Z}AjY#GgN`UeepYCx83;*lE8X`|Sf%Zulv-Jx6TgOnZ);H9*bUKuuKG~sL_NV77m(KB_e>}BI{Ee?$XZudy(2nk3g|)AH zSz+z&zE)U&aE~jjpSa%@)_>gl3hP(ygN5}s_r${bq5ETD{j+raw*2~YcJ%Y?>;IK& zT*SwCiKlTCf8(oqNq7IMa^-g~E6k4jT4DCx;|eR+{jM-R?tO*vbRR5?zk6a~^>TkK ztiGkwq5Sm84&Aa(&&s89eCQuf?GpdDzA@ixUh8|)eAjoVd9d$O^JCww=FPrm&8L0m znrFS&hQIl@?_%?E-^=Ff(#_-LH@|1cyq|sXK;?=P;v;^Dr??{iZ+&ANr1!lkf8U|( z^nJ>H->u5+dlsL*bMfr^ck#yiURJNZmltombUKuuKG~sL_UT!bhy3>&`}&kP&a7v~Hc?-&0J^8*(b4f78dFAZP&iKB-3lhXN_ z^7B90;g_<{UsWzY79ajCp8Q_?`NQfZ{o=-zEC0ol!|Ys~In4gWpTo+%xO5nwi&uy7 zyf}6k|BG*j)yw;C`ltGqPKWZ-Cp&b@K0Pa!&heptJhe;w-}l!qDa*J!KRIkXp8p&+ zPS39n8^7)amEX8NKRj%_pMM_a2hMK~^AG3GhxrZnk@~;?yaxt4}G`lC#}co zKdsa1SFPXbZ+$Oc8DHzY`e*6-ZTa=*?C9s&*Z(WmxQLJO5>MkO{x9BGy`=ZOEPv~$ z?6khhe(SEvZ9NvB)@ku<{TBbem({EFUiB@V4&|p$cIcLUdR8u-<3s;=YM1zb;*B4# zUfR+9b=pq*y4McY?(VyT^#}Lh!TO2&@nHSOy?L;HYemr>N{qD_! z@pPXajK6#KVD)nU9<08l)1mzHKhF-`vQN*-rE`4fA5ZNPfAPkZ_pP$bYt9S9<~!$z zVe_E##jyGDx9;3AY~FMp88)9frwp5ConMB{zxRIeuzA^eXX)na(#_-LH@|1cyq|sX zK;?=P;v;^Dr??{i;*IJh-Fac<%I_R8%#QQLF#FCO!^-`C?>sV$k8{c}p3X1B_&e7O ztC#c6u=a@u7b_wM+cp`o_vK?%da;T;tI_POx$6eka)Yb?*~w zT)PhnHs0_1eV89`f0T6o;lB5W@88w|hWV4y`I++bKiT1zvd>>tES%U%)Wb{VCA|G3dYAhQ81qFkAm@cuM~WL)@_E>w{$v`pFY{4 zTlVQ$xpa;X{o|=!;?Eym|4`=QjoaroY&_onw_)S-_Qeewzqem**touZbi>B`?XMf= z2X5cpF#mA-@rL;g@9`;%KPjD`DL?;{9eyeM{8i=hWAWkN;>qvDpFgZ#(r;hl%9a22 zD-N@B`xuAWzx|EF%DsJ$!}#2O$nS8*^Y%#&2xSReX>Kh?9;Py z=^P*W$CE#d|NH)0Y-8LNUm1_ZUB+qgnDJYjW?UD)8Slk)`~G_IA^%Vu$Zr%M@+YP5 z`|IWBf3m|bWuL#QTz)J*{98Qvz4*WHuhmO>@s<3=UF;N(&Hjtilw16UPjTJ8zg~QZ ze{rCC6(6c^>HGeA`RS7#x@CWQzH;dtANt2ryTt#k&#x~@@B2mmzH8X&dx!nLgOuC% z5k7r4;o0{T{(WbuSKnXiTRI)ePoM12E&KGWTsp^x{_)f<@qg>{tC#e?U*zw*hMm55 z*zY??xqTnu({~e|eNW-vcb0nf{iVL8)1mzI$qwDJPtVGwbA0F@Pwf(a{_w{0>Sf&B zyf$n+-h4M~oZdV*Z2aE*IBZl7{p8Lu4eLL5zG+y$x^qv%`rDm{8rBcJ@8`xp(et7@s?jHjL+;Qya$r&aVxt zm-pS&OMOeHL;2~G9lB+oo|Q}I_|QL|+9m#<@%0~8mUg^-Q^VT#_EQaO_uFSRtUvtG zul&bh{p9v#4eLL*Uu#&ux_w;3`rGaA8rBcJC#zoiXX*NF`Ss`Q=;ztj|0~zHh>!6S zPva>5pYipni}c&)wsPga{cpqU+`hPB_HV!3uySu7-7r44zit@M+jlpN|Lw;cRxj_# zs+anfPKWZ-Cp&b@K0Pa!&heptJhe;w#q;?Mabx~OJei*nXXbyzpZO(mY5q#QnjaI# z=HJA(`Ms;pmp>E_mo82&zxX*j;_B>+w<}j19v|^}JjLzt7tdEO>G>1+^E2$^f7s72 zDK~$GPks!~{2TuHJ@v{Ts&DCZC_jC&L$~bHvvTPiANt2ryTo66{m=jT-}^uG4e8!* zg5~$F6U>hHo?!O90|hJB`%o}G-i?CSUiY39jK6oL;QKo}KR2wtrLVnSe)?pGZrP`2 z<|0Vd@8GiPMU%A7N&o9dVcn&}Q!>?Y$ufD@i zhvBEs@Y8MfpPs`{=i#US@N1Xxf9r>vE2Z~)g#7(Z!A`$lu;1?*%I)_KeEJ;(&wd}l zzu!&NtKU=9w{$v`pFY{4TlVQ$xpa;X{o|=!;{VnUS1;-P9wC3fQ?S$T7wq@DhI0G8 z1D}2e!L#2-@Nb`?di8sX`j$?I^3x|fbjv`y9}^6$9oO1_{TdA zu(-(k4zPI1yAQB9%6ky7_^NbqSNX+b*%7B@U;I|N;=1^V_u?rIjQ{6*`BN|H-cwMn z{N7oB+424Y%)WOSVC8zR0mjEW4lthHcYyKt?gOk|-h+VEw{$v`pFY{4TlVQ$xpa;X z{o|=!;{W1}wXbn^^V+cSc=O$`aeDLMu< zYkcu1rSmi8=YO)pFJ+&(3p@zgHy|9pRa)(N#^>u=h(bvf8-!X-?|(-t=F;NI-YV{-@~VMKRjCx#J_by^=kc4eM_f9`RS7#x@Di9l}qRN&_ABq zCH}_O?fd%9Sk{iWZ)#Zk-hQfK?SA{LhV_Tre>JS1+`g<~{pa>;4eM98k84H0^^$(;isK;vtv3#{bL)`9?BDw2uySwRau}am&m6|{);Wjq zzxB^y^=f~w`j$?I^3x|fbjv~@A+OmHvjgW#c%Ze#h;YU&y=74$qv7ieg3L)`LX!$Z}H^!;?E!U{q@rK z{qpkfyXM&$e)fl7xx?V& z|NZ{8ej;u>KRGO(JpVZ?&OE<5EdD%yJ1j0eKRhg6J^%cTHWJ64-yRmG0 zt)sHj`YQXayDGQ!SbSQi#k2KW{9D&muhx6jw{$v`pFY{4TlTeA<u)_c{rbUKuuKG~sL_UT!>M1w+W9#CwsUj*aOdgx=g!&j+nvAT&pVgL&v#yr|1aIV zP=518cFZH$H@{S_c_%*Rqj;L9;{Vn+Ru}0%eCPG#?;IREosVO`b92h=JRLrrv%|CV zcldWMPrW*?r@p1rq5Sm84&Aa(&&s89eCQuf?Gk_O)xC4luN~*R{nEmSy z!^*vWGK|mlpJ6<&Uk&4b{cTvix=&AiOQ%Em>60D0WuKmvOXv8|Kc3np{@Sa0NxyM7 z4)Wi49A@Xn=`i~@eutHN<9ZmM8}Gw-o*x*-|NO(SdUc$f|MF*l{N0tg^^NW~Gv9UZnR&4L(9DnBlV;xR{xtJx_o|s^yKl|>+dXXN z~~L^a=Skb zpYBz|v-{TY?;bYw>V7u$Eu9YKr%!h1mVJ6wE}i2;|9FZw;{U#vH*dc0vSIm~$JuFq zXTN!0xy1wc6er+W{P4aX*ALaJctd@QH|S7)`ecW0*{5ga(m6i#kEeDi-gw{3tBdsJ zYx$eU*=c@fzjhC*WE9fPZm?dKGV|Z|QU>KYg-8x9roia_Jl&`o~kd#9zGO z9U0@xyykrw*nH>R8Q47NJ(`Wdn;*SX1DiL!Ujv&@y=w!TXT5g=n}5B71Dltp zOE-^~-~65(^M3Zl1C=XIh>!Rop5lu5i#Mv5bnnY3SAOr#!0dRB24>$oHL!BMUjyUg zT^krr@7=)odj|(rFYn{P>RUP;%1@u{&@KDojmo8SeCQuf?GpdjUf(P0r4PUS!_Us} zvp@XG9e#Xv3_fu)}M{v`nhpk|2N(n7yLlug@0%q@f(dV{-kt%ru_U*cKD_2^H-J2 zkHv?7izmMqfBvv~Nw0s(U%zFi{>*;;T)Fjsd>R*cHeT>=9I031OMOeHL;2~G9lB+o zo|Q}I_|QL|+9m$l>+YRf+eyEBz=q|&`@x3UxqHKg*}wb5hLwBwj1A*+_m2(ZdH0eH zYb5rPHDO^vMq0vQN*-rE`4fA5ZNPf9+Mhq~E=5D_8!z&uy5UyXS3~ z{k#8dSh;sE+%P_OU)(UBcaPjK{&yeXuzKA+fy3%sIvvVSpX|^r`}C|_I>(3p@zgHy z|FqY?SUe!T^S|KYg-8x9roia_Jl&`o~kd#Q(EC{~1T({Q9T(zkchxp#JQ8p?>Z=qW~?a_j&2G%oOLyx`wBQm@9B`j$?I^3x|fbjvv#LtDNIP!N+hn>#vu-~~J<#yf&pZgyC8eg3c!oPDv>eYE7^(~za z<)=?}=$3tYRxX|6L;rYcm-veh?;QQN#fP`AV_1B0`#pxmEw>M3SUhw4Lx#mUw{K)v z{B!$BhQ&p<&tzD<)fBSQW*|~i?!|dOFo?+$QKA&NHZvW3Pp0_V(82{TZG^}2|@1VY=)1mzI$qwDJ zPtVGwbA0F@Pw`>=`NQHUey- zou4T`|C1elDf|3Y_k;osuP@5P@#tX|TKujDW8VyAeF{o*v`7Qf+BT!&}z9{$CF z>Q#KGzNOQl{Pf8V-Lg;5%B6FB=pRq*5`X^i-pTqppK|X^4I7X5{?xE>dhb#V8^1sQ zhrc&$T;DrZ!^Zo)Z#B#h+`Cu9{KLJ6HOz0^J9NYRN$LDy`T3vh@Jrd}uPT=xix2-6 zPkt}{{9*Nye(!>0<4uwi!Y9kJor|AjvoR_?t!HjK}`M>dS-y;C-f|Gi%}tX}`m zuYIukmQIKA(giZy(OE{I@@6n4R0VGtB<&=NVS+ z?eiJN=l1^$<9YjnhVj4sLc{8H`-q0sw{$v`pFY{4TlVQ$xpa;X{o|=!;{V!fWl6t% zQ^WG#eyU-1ZlBdK`?vpUSh=?^YZ#x~uQiP4?c*B8|MqtctJm%O8dl%Z=}><9WQT6q zr)TBTIX?7{r*?_I`RneTn;+&U@7}gy{_|h|w;#-}-aT(i=Wp-+w_$$x?u8rXpYOi7 zVSfAWksIdEf8~GsV1EAYom)EpU%Gjr{N{`7m`Ad2eyLpZPJGNq@ib4x-~3g*q~ASz zD_8!ze{YzbyO(d6{kyMkSh;tP-!MLRzuz#PckkaY{&yeXuzKCQ6~pRVIvvVSpX|^r z`}C|_I>(3p@zgHy*Iw;Qk=}k4`P;|BPWxNfZ{Le@+Yf`!eP67P;d$R3!}zzaM!ni^ zqrRonq5Sm84&Aa(&&s89eCQuf?Gk_ORlTIQUq$}*v9Qzr7WUisqTKew;B()Ds|%j@ zoj8nt`)bsy{Wj`bIvvVSpX|^r`}C|_I>(3p@zgHy7jJYgv3afgip_W3V{9Jmeq-}v z_a2)!yARoX+C9nU+3rs^|8}pkdAa+R&DW)y$IEYi&yION`{IGh6(__;{18uZMf}AZ z)k}K!70cf}#_V*zG5dG^b_<5Eu9YKr%!h1mVJ6w zE}i2;|9EPb_Jipz2^89)C%=7cz zKhOV{ZeA$A`64^!k?fmaD%ZRdAM;T>%~SFJe1CoFCB6IG($ zquu-7(I5H_(ogz6(trAH(y#iS(%<^d(hvLo(mzYrZ_BSgXGcHJzW!gi#zlOLmv|aS z@i)Gzm-N10k7jeIMb|cN3m{PvPHpmU{L5rM{)pq5Sm84&Aa(&&s89 zeCQuf?Gk_U*WF__Kfq7kJz&H9=iLuB%&*?PVZ;3G-6uB858pjw!~FBzKQ_#7-@RnR z{Q2EiHq6i8J!ZrFf9d9h@|!QRV;;%A`K5BrJMl3e#nU_$fAd%Ml79ELtz7x2xSReX>Kh?9;Py=^P*W z$5Xq+pFixL3gfQ(D~!kPwJ=V*@51=)9t`8U`!S67zxM9m;0L--gMa9r4Su8hH~5p% z`I++bKiT1zvd>>tELtDVE9CE93wFBig8lBnP;U2Q;M2Vscy^x# z{@t^oUfsW;zNOQl{Pf8V-Lg;5%B6FB=pRq*5`W{XdsDUJrGIbE)xMX1Si7H{Vg2Fk z59=pa?y&xIe1`R_<2kIq9sgndu=`;3&(ihV^6Ssp(a*E5|5vVY5g+3vp2ku9jj!q@ z{n~LH{nEmSy!^*vWGK|mlpJ6<&Uk&4b{cTvix(`-;OQ%Em>60D0WuKmv zOXv8|Kc3np{@SZ`0O_p{$ltmFJFO?M-#UYGTYtc(bqPFMufV@`4E1V#Lw!r9L;2~G z9lB+oo|Q}I_|QL|+9m$lt9nUqeL()!4cKWtVfNoTgK}Gcz^8QyJX^28zjX}tYJEd} zOQ%Em>60D0Wq*3Ua_Jl&`o~kd#Qzg-{Qi8ed9CwP=DW^SnFl*>Wq#}&mU*-DS?1Hu zZJB2~&t?AYoR@jI^Izuc(#_-LH@|1cyq|sXK;?=P;v;^Dr??{ipLpX_FX^41lD~6R z>~!9W{mx-2xAR%}bZ!gJ&U4}4IWP6<{FnNcPKWZ-Cp&b@K0Pa!&heptJhe;wUweJW z2fp;-mw))#8GiPMU%A7N&+y|p{P+*QdJVt&4nG}+pFYD+x8bMf@Y8wt=|BA1W%#w% zS99De}+I?icbi!+B`{5kyM(%~1c4!<~d_{F!wFYXZXbUBaK8&^$L4G8+dQt_o8R?^=6(I7ctHOtPSCH4AN0543jMHnL;oyYzb(K1 zoE`l<`}%+78W-^~UgBvS#sB%k)k}KwwfxQF>@>g6{+sueTRebIaRQ#j5BL{Xs8{iZ z`j$?I^3x|fbj$wqeC5(PKJ<^Lc8S0Cx^=cMKiT~-@^^0xJKZP4e)r5MxBF-C>0TN< zyRQcS?y*s??zd6j(&(3p@zh@NfAiNjSLWi4)(7No z-GH6e6WDK^LAk9z;M2MUo~>8l-#UhRwZ5UgrPHDO^vMq0vQN*-rE`4fA5ZNP|2KcF zUea41kiT^Uc3MwhzjX%Xw*G)m>k@djUV(q>80yvfhWeIHhw{@WJ9NuFJu8>a@u7b_ zwO9OKdwq?sOCNsuho7C{XMgyWJN)3e(_#4OGyHTLetHf+orj

FLm9C3H^DD)P0*9V~w~6ye_2IbUnK3FlSxefF8RdsGr7On~>u-*(hTRV_!ZAwL;CH?qMOVqBka(o68qcqlz#tkIdgdR9k`s&-2K)L7=?1K zQ1hMGvX;kj*ZZ9?p2g!hx3>dq#`8GdpW}dc<9Hk|8aQC&M4lTPPHx8cqHOB3x<<9n zpP^fjRy&7kQTz9suo*S${iJP&?b-yxCclVBFW-nJb#jSq{;kJ^Oy;>$*TF9^kL^iI(km5 zNUT+Ny7XLqWySuwMpa_r-|TfYVi6}|e+~AL;`eK!Ni6c-UsID<=&A2ei&*FknOd7z z=%0L#S=2S|H*=!&%$01{x8J4s&;077#IY=OR^kUlx+;0QJeIC6%JfWJ=C0@rSa=Y! ze$O)pmAZsou2=ZWeGqZv{)qT;-$Y)ypF)q^XQ5N>ztAs_i+a2SkKLWGr}?a5lA1eJ zS}%R>uzhKT)o{G^n|$W2S&FP_1;kx!7s7tYUt-Pq^HBG9F>#u7ZWfhQO5C800UG(0 z*B9}vM$ClMyo$u$fitLH+3rwSh3vvVFQFQ-h;w#94Pp_$VyXtQ$UCu3O=6+PqgyRv zq4V}nW}*M*^4eq8l+nts8hikhkdAqgUujn}xBYnT7 zOlP{EJ7oROez+@j3Ai6G@#VgWymCK<9=Xp#r`&&`Umh1xS4o#b>a*6k z4M#0N4cIQ#5H~`gwJFiqa`~RV8{D%)T>hInMv=# z6^M7OnTwsrc)Tinoukwx>`sw9Uc%qHF^`vsvuAyE+E&CLdVJoOjUg0nILBx^!BjU?_6M5x+3O#b4g-*HuLccsN>hThsl*`A!_4_tp zL!ZBN+^bpL60teVPf}MRrX3#}t94(BDz{6>r$O6ADEEMmlMCONz^Wb}Czo5#$L0AI z=s1>NV2soxK4v;>Hl`ZIu~gW5dQ~AG;Xk2(kDnrr&&cXz7x6XM@bOdR-D9aicA=-= zNIsSdou}R~3;olE@Nret)omX0l0SBe-6vtE;@^LoqY|fSgp(3qD`u~fckNUcMbAoy zeTvSo;jW7Q1@^8=UBWKcEBxg?h&Xb8M0~k#BCp&}p-1ks&?)y{=$FSuJzg`OPsXfU zyhb!?%T#=I;I*T{snf8-jMtPjzfH&7ZoJm?DtHFEo?>r)Wev4lR0L$^-Dy06SHeon^}Y3)d?N5x3b!1&xMCBFS@Cibo3wWc?g zv*1$1eD>N*{9aaGU#vTwY%^0jPb;r4)}4N)%s`Y*1%0vZ^e9vt^Q|)|jykWp#+1`q zs9T@cTV9>1j^i8C$$w65O$=(qJbqg(O!&v^OC7T6;B{@b8%?W^wFbbH_@n&*TI}Blq3e$WbRzI z99j(LwX$v>%Hxd>kEze6in!C1S=2RTj5e)#s%uo|6)b#&hW2_IFn`sU{LlTUCVkhE z`H628=zL^$H>`w1SD3GKtpF1j=1pD8;rTG;t=EeaKY!4nIBVkz6MtJWCk*|Qn3mg! z?29e)6Vp~O_c6*#w0`yf>XbFBwJp!B0liI)N$2cO(pWn(H+WnH&9*Z)xl;*$&6tBz zE5N-s^Wb{r(K1_yw$;x4muP&L`Dg#)#FhP+A5{9A`1*Py@~N<_AaU z{wxh{fub%=NdNk#E%D(V$5(4})u@MA5e#)$A+zIn_Si{}F?WOO4Ft^y%7HwuT57umrCDMDr#GL#u z&0CsvhxQGwed~d)=-P#Kp1;uA zaI41J_KY$_niKQ1o<>-7riQ*)^PFFKHeS`x&=+f-r;=u)WU7X~So3uMRu5fAccVDz zgKA=0JLc{2RdMP@SF(@VQvrRuGUvq?B|6RRLUzrN+(eDpor%L5{z&xc+KKq=@QlO> zA36{}oRpT>)2==7kIA1CD>rDT*k47oQT#8BX-zERSQWJ-7V%3TwjdUHcieAIEc84t zYDO${8ZBfN`p;Kj7InS-*pz(q{2D3tu$Ijg|M!#IC~=~TIzWzpq;gltd8be60a?%Z z_+F58qGun-`n$*Wfn1lc%k>I>xep?a+#eBN?wiOf_fzPR`z&aZ!(#;F?k0 zXpTAMYa(Vh^XqO^v9B%j&dcR-dPi6CF+Nk6s1ebH_>cb2M1Akh#K#wYP297f6Y-}R zX^GYqI}&FP{Fvx;pgnPB_YX97V&4?@orl^e{@!g{6N@-w`y~1DagNP&dN5q%=Ci2St6nf-73!QTRg?@Ql z)Z>+_RSO;N&7t{OHLDsfoHHVRF;8}G1UGNy>cg}!d@pl{ z$_-GknE7W$U4(XG&MK&li!WKj-r=<{aU-)@o4T&LF3mCJ-CWYYF1RUv)HWub7}yv= zU76RrH^M1h=4Oss_|buRiBkiFRAH_YUhn^5?yaM`dY-^<6Kw46ZUq$#Ffg&jF3JD| z3|f&+3A-D`K*0jB7&{OHTNK-m-QD`!*+Bh3W_Nby?%wxu z2ew=!Jti+o!q8~q2M$KyW_w~}^Kzelr6*)rt1-`> z|115fW*6sG;QL?cc@hRGo?Yrsdg0QZRHjoil>=hE|FzTqy~^w3-DtCa%LuLC5gkiuVjG1;%~)D6W01Bz!8~SMkH0 zMsVa5afNy%z{sPYYL9GK3^I$*IP^bL7^XxM>&HhQqnbqvLH9uFOOuyHz~MFVd#~a! z)32xMW8+0e;844l;_dB9LG?St1%{V~8i`ia{!eKb?cZDRj60pqBc2gw)oBK+tI|BVS+xnw>p-lZ59hTtaxO28;oW+9;qbxkO8+sVKj{XOh>P_3 znSQY#@qMH3>1kRGW!$S5ar>GcUx|3I+n4ksOS-Cd+%r!pO{|}9AA9A4FQaL``C8_I zJ0*#iKKhydeP?$yZdcBHOF!6!xK`gU>7|Z!Q|$&mpVH0R5yy}Cn0|OuSJjSZ3bcju z(65U*gv}nNSRV`hxK;hp9-a>wCVpn!HxXu^^*WJJ2KCRZVGh#K9d0S#U`}lrp zp=9t(RPqEdo|Rs2CdM;VMm#Z|U(RhO){i-!%a-(`@yGL8Jup_|iRZZbt%>n`S2nFB z#Yj8%HPC9{V!ZG?X!@juVmv2qT|tcJN6!hwc&>ccofyxXZ!L)Ntd!7?_}G(9klEW( z>G^)NBV04ERQ=M&rAm8KD6^KHHGRLCKszmu;TrjEVhoE$P!8Gju_a_wp`25zvk9E} zhw|0ZqHVzWIIXW+UE0C%Oj@ z<>5caTfvSWl*9A*nZo)Pw5FcVZ4Zs}(mKlfy#jPQOJm;lOa&<8O#S_}tPB+MBmO?o z2<}e%-!ak0D{^facy@>MwCQdHY?wwV;X}hj4@iMWSnjcQwJ-*@e-+FkZ_fvtOpee!pK3oW~-_GJY+!?bu}{kUyz zQ5jNBQGeUpRfPsxGQhZp`&9=c16m6or`3cOJ&E(QsSOD$bJxh8I`BC^t*LFV>q6rh z#QInq>Q)&(kE8KlytgVGnohi|Yz;V{NNnA+794y}9MHKAcv;i@k9b!Xnw=zm)UQ6w z?M>@NKR$Z9dKrD}%!=8=2j7yaU#3eP;7%FhuMXp(z!4+WZf-jfPHW%R#=Z{E>iwi;rO9x1tdV*@dH#J{FwRHk z5xre~A3xM@4@bMud9#bN8LTNo=b(E|rjQas=b&-t+d%$jbPlpy-3IdZA-;E`4RlPV zb5MAoDOi;yo)~QgabaXv?}Ogfyi;vq#X~wHZ+>6~rVhmWMwr3xY&tI=Ze|A0HCs5& zKOD@U#34E(-}`I^GfjybJ!%W})5!mff3!T4PUpn^6>mz&sbR}0v@uDNP&7v2Jv79hTGtOY!sNay8Yt}UV7c{(q@oNf&JI}-ofm|WUu z0`*q6P<yG9NKsjADA~3ZVe;O z>pd7g)*@aWJP1x^TPRzr4-bF}{>0BL`a{)H#Cm`9c4H04z)&N~lg$c@0{be&^ZpEn z0cD8W7z_jJFBZzr{&j~y`3&N)3D$5Zf;i#IKzPua*hc#;WBL{9SA16wh|C~A{dRl6 z87I=Ix4ZcBIOuwp{6IKkRHo{cWG*2UErpPunvcngkHLr20Um7~*Byz2JE$ zacYlnaJtf7^+n%Dz1^_&VQ_wVdli?FO(UR~znPLB?H2*ninmp4t$kM{A)eSRCIT*+ zwo~n8`$oX|4B{tu!r|6nvZc4H*FSq|I8<0;rfgN(6At@ov{jsNIUI&*^`0;ipFCkbanWWd8ZE zq8sHjw@LG$1rSGXnF}wpT245ILr>3vlmOx>=VrtEBgBrs*Fy4c%G*C$#KX%W^jy%} zN~yL0x^<#_c>mS{I6su0K|7x;gp@#fcFfnlr<(5=y>m7=yaX!LBmT#C8MtgAoykL1 zfbTHk2i>*rX*3~r?YIW2=CXb~duX!eUj?=25Ep2^1~$$nzNY=Z!>qRrRNQy2+6eo5 zQM=EA4G1O!gBm8L%E^U&#I2y6d2D7V*E0r%ka<@HBy*zea5~!p0B8qkC@9 z?qbn6*jOdN=MluKx~zv+uEcjt*TFm&;=u!w;L$^R{_1_!>(4p66}l~@=l=P=+ra1; zJ;x6uY=cJq=>71i3){f?7V*QZZ7{-(p6_MWX|)J{5_|O8238Su)tEFtkqp6xWOr(n zWcW3cSnrSC?x6+Akoc7LBwZdP!&j~L4bHYXs`0%ZZZ^qM0{&b zGE}pxtK>IVP6q$W#Favmz`>mQ)wzE%^gCEd`DPuL1d|dfDS5r!>I0Kt<73)`ElS&} zeeT`537moLzCfh3+l_i z^(*6^_P@*(%PXIUCT-Eaokg55W-DZ#B=&r@6^fY9?~L6>Cqdgy#BSREANkjz-y&Nc zPlB84iI1iyLF;-nZtW`1hhr(l|EG_7yVJJLgS!SLln?f6V_|V4k~cpV2Syc%|2&xu z5!Hy@4Cg{lJK`yo=fNmfV!bWB&T!jkXk3Ey4;mT+Mj6GGt^T&Lkg5I16IM*hxE)cF+E25yHCJ8J*4e|#YE5Zk$sRKA1y+rrxa6UEHvpvFPpuYmO{VBk=C?t5zA zKPH1Ue6=XMOY2i@^RWaZrhcFwU6t*EOFH&z*?% zeRTb2Ikad?dzk8-weKwyqJ2xu=w+}xgE-E7DOh;YzQynPVmMiHbSEidZyQzya85fwf1oQrxZ+pUmJ*P`mBRzMgMoq_3_R6k_e@S z(lgg1EfFFu>Dk(%aUwti+Mg^Nwi&MeCa&IP6ZAVu`z-3+9al|FbkE?|#R^aev|?rDwzNZp5~2=0I{S;(wbb z4*6r?(oNdun{0~#TTkLxpICTMmALDuI9PU#VjVGXHdwDG&NE~V*oG17<6{3f5h~oH zJ;Ti+Tj29(;!-2Gz_eSme<+Z(1+vByZ*|@ZwZGC{!l<5>mzELhKwyXOpN1s6CK)Xm73k61@jAX&nKvgNXa~hyd>k^xmvhPy`IKCJwq60qt)7 z?>LlB+X>G*(U@FYu?t2QAnrXc1qSEP-X?HvDqJ{0+7!n}2T73=52lABTRv21r`tK^tyXn2c$Ln+li2HX$y zQtfZH#K7WBy%qaUje+8e`YNvFlLbLq-ASB>FPmt!jCav|GYvQcGp%T^yCnG(*e)i1 zci|XZSwcMd&mp+nkNER|bf}QKkJXQZe*F6+oq?@e$d->*CF0FDVvD24VCoOzz)Odq z?snoE1=HbrdE!@&ap3J|t$e;76$>w`6W2Z+17^Dhsdo2fG4R=pIC@_+R8JYG+S^Wz zhR5}ZI}eVAor?#k_Tl5A;b%eOe~VYGoH)4C$Xboh`!aFR@%kXer<`J;g*WlZ+c98R znAplY23+P3R5BM^$3VMs#Gfk1fbYTqs@=L#40J6+tRMe_ZWo}_Q<|$WZWm$E72;7- zFTsyoemdncOnFA_g(hAB_fj-I8GWxpvA)Fft6zi5T8uEJ!>(O}_wR}I@vYVQ0_2ON zSjXF3gr8H11A;EWGJf6yIexR>IXp;tiKqf@vR`4^0JC=dn3*stEmcsP*^gCU`#3fLDDzSOP#gGzBJmt|saG6E?Y|{c5<^I>6MVMgZNLem2jXl&9UOwRzU0X#5Jd^fD1!t ze)h{*4v`m#^VL`m2^KWAk2@`cdrOHocUuZUcZn~wUIG)1hN$t6sJIwvH6ZT)bs_w! zM|@5@FXt^r9D05}e7ft;qF`F zt`o1pi%P~y=2OqB5Z;*BwBZ$KR+~7{=rYvHORS$udq(8Il4A7SU;QWtF03LR(D4@J zYe)OQns&D!@&>U{?^`f?2JHz?{LF!F6=+X5U+eFeEyOmbZi1O{OEv#zJ-q>WHWDBC zCmSvnG*<0d$F4(WKVqBN*Wj2RacaM-FnTuekz}#Y<4Yj@Uu_9>oPq%I7DG z?|^~D=oz7(OGBS5hn?H$xl?=5a+rLepBkUoh06hs(Q{tQR4XcRj{O|m6G{Yd<~phL(it9q_xnaBJptdb#OYhr;=G}odAV=iTicl2ub6J zzct$oU31&3me>LvcT@Y4%Uj`nuATz!$*^H9=`49?8?5U^cJ=H1$>tSMXbC-An~zxm zMk)Q&c&;D40`8xo=UUHA+PZksN3|EVSP7Mi6JM*i3U+s)aof;(HMEJbQZjp@*1*Eo zy%ZlQ8V^;c5;sd(2VKe#J9{KR+|8a!rj6FG*i*z`ifxADx$PCtCBpVx`Qe^h0dn=! z{gMRZ-;kc?y|+QLSh9QJ_i1>2nD)BmM`yxF?d*g3v&@wY`1X>{DJA_*L7Ciluzn*? z!p+rm#_8m90xYi5*(dtuaX9#c&PN*~k3;{8#Mgq3Ljz+vC-ymc9G3Q_vthMiC*Z-< z*2Mi-&3wg#~;`gyBggLg+~z(I5ByV>)TaAOIb2S22ofFsxF%sBhVae&`+uH0Pd zIP5M*oPGEh7}ln#^grFqpV|9+@go93Ho-hD8`hj`ZGJuoVb_~ZUG_;rhTU&L;(eoj2tIu(B0Chk%{ z1qSXVK2c;BjG95b!*C~@t4Ca??hg2!PImt-C-@B74^zEpEeA*LgQUyE4deI1(;Bq) zk0^Ed~RY2oEb^H%Xt_0YW+odn~4KJ;73oF3<()j8ruKIfp( zQ2HID=8SXD<1VqyfOD|lk*T5fnAB2$QqbUY7Q`c(6LbeHoGko((^Z>jSz zD3H!pJGY;Ma;53awXga)faS!o4rd{%9G%hhG1B{~m(kBLw+G|l{uX*J*DGfOXTpe2 z&KwTA$`G&YI|vGlrswtP)IMNmM|*<{_j-VRlR+w87N0G_?F8*TqRMpEesj-#UJU36 zy%*3kA~VebupSV`x3<>4u_@(bl%E|zIUMzbeW&{>sDDoGeK52;&z8=Q=+DdXbY?_9 zJ0;OM5&f^%ff)N`q>TyM+P&RH+ROEF7x_-UzM`j8$pFz`&^=h}4sZ+=e-g99#Lrv% z!^QtXh7r;)Z0G)>JdXqF;qgKJJZ@;0#}obGaYjFR{Lz1oi#}e+M@kG;bLM2$SZMHs z_J_4U4ujZf#5rLDA#^A0KYyk4h6hQsUp=v{J1le=r2e+c$}TYW3+;icuj~jhqv@Hr z>x4P1OQ7dquLjz;rnT5%9>(_mRp_~c@)O3>^9%JX%%Jll>K`+N?gF9R5@qO}1N!4u zg5EQrpX2+}yhZ;{XXn08(E8P4Cvmw?F4DgDg1gA)={#NZ+$k9-`im9~5xf1$hKWBm z3&X|Fg@F;`|LOA-JM0&>bAM5u#{u>5_@I6sH?+&+iT?07qn|wf=s(9rAFrNCC$#$m z_0{}b-~A{UZ6@~kb`U2(o$h(?r#}a zx@q6-98**2jCa@tv(u_8_Ab8*u!a$?1#Ew={qGDi%3n&PckHMqqZ++?NBx)g(0hBd zdo`q-l1G19MwL~Jeuie1QH=gO+Yn>F2Dc@CQTnvBSFt@S@-4M@1+1r1*GrqEcw zpj~Uza!MZk*=bx>G5WcAS{cRYfAOEC6=T0Vt`M(ib6VQn)}Iymk~vwTC-B%M(O;#< zRk1sEz;*FwN>(XY`ZDAN}XJ z=;PJv&mzb;RYc9(e6<(B677G7aV?ymun^u9B(AQ#+rJ%GShaVZut58NDB__F7r^$Q zLaMz&l?5>BgQ4Q*77O6rMB*Ur8&>~RE~>`UV#`7pe7J~WlZOi+dkC>r=LJwHr?6^| zIx!zA4kP~TH6Lo6E~MIvAD$0WM;21|&8+il@(&HweY1ZdV``X0)PQkys=Jj%xm3 zEc^@af}Z1vUmEO$UAei%wD1n7(>+(F{B~$xk@$JwC2*)u^LF~9OJH}Ql+vTOyD@Md zv=68DkhuUaH6Jn!`YmnHPxciB#P}`EY{)sCP)q?n+bC;oiVdAg5 z@51A~Mrs`Nebn0xYIPU7yBVoiY%+NO`xX~d@+;asfKpA1D?VECf%?V*=D>#g?!%q_ zB~*KfHuvGy72@p3d$6!S+0xt9>;K|%ABw~mQ?{D9-`D0$amA_q?nCGnV*fw)z_4)% z)gC?T9wf#SKYV=`hL<2eYt(uN-X9H=556w%;HdVE0-U#c{g)i>!{N0>RlD)d`!IDq z<(5-J9ze(r$|sq<9zxly+u_ z9zpTml#9~*9z*RdhN{0$wC@)F)0j9$s}oV|0*%AA)tWymiPz111;yqOI}d*Yu#FhM z&D(iFex>J(!4K%rxPaoN@EzI%@uBYDVN|bzs(sSBZ}8?6@w4k+VMSZgv-rgq7_W^v z&WGfOpW*a<;`*mP!R2z~Tg0l5P{)Kgaqr)?_z|Md7)hp?oCqAMG2? zal45vqdvlw^TgTHKR}nGH>k@w?MUU4N){{2uirv!9Cb zJJnv*e<{ZASBF&jtr)*+J-@*p#U&QLf+{^fD}Tml-y$CU;InGi`*3sYd+mF_crEYvwJl6H8 z_B|Hj){)QPKoaqj)z9JJHDbf$7qF=DCz9X#60A28|C|4@Ax~h|iciYVQZt{z22bMU zzFMso?R!=j>!I$?!Fw5T*ti!k=$~Af9xvgnHI2gt?LNbqR9bg>pY{5CPg)9w#z{s-ler!(_|53`4T^`u^2klAzn~#35>l@`t`Q-I=y@sz@6hXpG)pv z0OlQthc{XX_4m|gB5D#0h07}~!sQWX; zH!gs4-wLYxGX^^rz`l(I)%_W+ABwqxYlb3o%}^XeWIi8h|F5L#!(ux!)`vxTuBnR5 zHC2(zx2Bq^$XrtunQN*db4^ubuBnR5HC2)S%{Q*EivDnYRpigP^;MC%zA7@;S4HOf zs>obl6`AX+B6BTT^nq*CV!M7!xYjMUbFEusu62vdwQiC1W6t$$Q9swWMRv%oZ;QwVVuk?SL)KU^Ofnd>7XbA4oFu8)k&^^uXeJ~A@bM@Ggz@_QTX zJHLO^j|tb{MtQEmjm$N;k+}vpGS}cn<{I3{T!R~#Yj7iT4Q^zv!Hvu{xRJRAH!|1Y zM%Krd>u%$Ca@}oYuDgxQb+?hZ?lv;l-A3lR+sIsZ8=32FBXiwtWUjl7%yqYsx$ZWy zelGpnnCs_W<%5xM>-A)dDuI;`ay|N=4=NulwmKHf8+lkDAG#O|!#7P+GF8py!RXO5 zRr{UGbHT9v48^A{=YnTfU&TG5=D?E(Z^eHSXT$wcUW(JU#lfC8r1RhOm-woEBkqHr zvh_4-9vIJ?u6WX8tv0BQkK*uhbHT~gOYwZ|PWYNk55=|e&xV9>cg6aC83jbZAAjm& z*>>T=g};SL-#48Kfkx-1sJ}Jc77TSuQ-8Sz{r@>W?-xZt=dx2(zlN*|hYfj&D{Tye z(d~#cc85aU{lteZhCmIi{v(cO`9HysGs|5u*Sp8|Sr&_+Ppdf9KJ)h?So$Yc`J*2b z{rKo^ za}~dwvIyFE%n>d&Xtv1w-~9YgWg$!{v{3nzc5xxJZ?i!0=Lw6Tx7B>bE?44?>1iy*BZ=G+}mU^IFy=A?Ycf1&-I0dr)h5Nbo7D3@%~EYYLquzT@$Ey z=~pi(eLG08$$l^R`Yu>;p)45%!2=5~QVUl{u~fcm@F z2ePBIZ|Q3>IyP9V(Y!HO_-ICm$b>!)RowUb99U|yL~+dcxp4i^5@kz2KKfV$bq#SemsnXvtIT|jMS*CbUR*Z1zSFs|K{woez29SKg zZ?mDwEAs8%{7fA^3+&b{Q$8PB5e?^W67RnkBYdJ}oX9k=o(=66gLU_wE)e{*oF3#|{#|ni~oQTG2Qh^$XMP z$q?(uRzD7U8NENL(KfKX=Mvf*yV-)b$x_8*^V@-8(`AaETG>Ij=F1g->1YSpCMy(Y zJ+KA4Rx1_nGP8yGjaDhX)WrtI8?9DsW;hmF-z8o=XEeN6utv4}2iii{(o5Ah>dQ>G z1B1(2e6?B+_iEb1k$%h6H|k$z*u%PG%hW#qX|_EK__AE_lu&!9+Hj@fYngViuiq-g zbyIDjf!%7w?|az5^Wke0w~8ABmd)1^FB}H-tF2c)bSgFi7Tc{??N_d8HRXNRDbBe) z5^UGTE1q9y#njmrZ0HYz@M${I%9B;NaAAOyH>QtjWa^#`+T;`KZF zLZK>~ReL~JbGX=hm$KV6%K~P%*rnQyHfc3jH||jUvS3H}RDHYR63;qn?^lx*XIN>! zV|GtcyuX?yj4!lRagE{Kpy<~`#qA#TfRR;+Gg7VKgdf?}`=IadnF{7mYt0Vj&yxUi z`2A^{;!H0KcsV**am!B~;rp$viZ8$G46b2Y6dxGV6~>QARJ^-R4_M;1S@CsaD=2=5 z##7(lUg=Ftzg@#Q}BOgH`#x ziqAAG4V!M9Rr-GnC<9&W&i#*!-Uq$>+VGOla>Y6Iw-FmlKqb@jisvjV23Ix^*PmPj zDnB7!-ntO{`9i$$S3xkyCVqD#KU9w*o_8ZJtSyquMe{(1airhy$ItYf#pGuz@9*h> zThAz4i&uP2FTFWaaZT;phQ ztA(4c)x=eQtJTN_tyZpLt#&SGHFOngb$vmrt*cnCN2`UKuGPd6T@fm0)h_4+$@sSoSI zEmVK|mTU+Q*U)%6Y;6Sd@^)73%M6=9-*}2+N)_!pb)H>S``CL;!Nsk+V%veupkPo> z#fP1m!SPjAigOw^1FOA#6zltv`msKw)}%2U{G%aU9%G^U4yPK!`=>O{(61@X-A{Ai zTSzmoK4Gb3ENq*@h#%b)Z@<+XR`=_v`1hCQ+P9Ug6i?pK96}BIDqd8f2P|#lpnRCM zwmX>bwNvf=ms^6BgT3OhA)R1P7;)dJ<`7(+IMA;hq?nL=z&jdsw!HI?u-_ zPON7FjvGfQKIGXFY)gz#>|)*mvf2z){4KmWIGR{1&K}krs#h7HSnsEPtPIXu!sOTF zbGvDsAg9bY<^S2r=5RED+FSn97Tgo;Rr`ZSZ6LO?o#Gv)tst|sjp9--TEd2vqZNmg zZ2@;PM<_0Mq#1nLHB|BL?@eL4tF>akQ%%9X5#eR9WvLvL*|-y z$XxRd`TwQ|ePBJvtOuF(AhRB1)`QITxKTgX<3{Fs+{j#y8=32IBXd1#WY&W^Sr0Pn zL1sP3tOuF(AnWxoqker2ab|1}@7Wnr&y28mysg?n(`_B$(I(;%wX{931@X6}4)A== za3$k3rag2{7^e7syLPZIc&K8t{%xV5@esuewC_ZnPPbNUZfXWES`1R`TG|X&E*>E5 z{eSfn`KeR;Dn>mefA&_4`h&JwDMq{BqIxMte+I1TsTlp-`lg3s^nXY=G4?CWp7`>; zF4Df!t*gkFdeBYu#GCXG{SAlq6uXx?_Y!}+U-ts`^V|q4VEdJNFmmc^ps= zj}PkSaYMU2p6CycGy2KnkN$I9^zmZG{T0U!nPZ2{u|wwAA#?1IId;e#J7kU>GRKbF zvF|L8V}i`FL+02abL@~gcE}t%WR4v&#}1iehs?1<=GY-~?2tKj$Q(OljvX?`4w+-e z?HD_j$Jilr?2tKj$Q(OljvX?`4w++ztdAG(qi_xKJ_?!lQOLZHLgsxGGVi01c^`$$ z`zU1IM!Y!{jBBC}m&wu{Vmk=ZUX+eK!($ol;NGy3!YhrNp4PiDPu z$h?n2=6w`0@1u};ABD{OC}iG8A@e>8nfFo1ypKZWeH5~Otau-V?Yxgd=6w`0@1u}; zABD{OC}iG8A@e>8nfFo1Y!_q4c9GdGGTTLFyU1)8ne8I8U1YY4%yyBBY@G-vR}8g4 zA2uBy52fsg`@VF5Rkw$zcGITz(4hixrP;R7uGC=F{-&~x_I->&idhfpWIf2N2buLC zvmRvDgB)$w1)5fAqxP1}=$l@K8Qb+TAzwPdiz%&?KUH!%Lg(4WipQ4e2**QPD1NrV z0?cfiDb8M`y=!XOL^10@A6O4E>p^Bc$gBsM^&l7fyaS3oOIFXv35|9@-Rs1k9k#=_ zc;b_rw?PA~<`?b(0`hDF>#IqM+fPY`65WU=d`r^evQ@P&SeFEg?{87;=#~Txst^Zh z-|GnKpD67&f;Wr&qyw82qn`G8iBbRi5gS!I+TC_)gJSgOhW1Vm{XstseMR~YxiSW-nwgw=vn?EMfBg9nJRWu-lvK`;a0nW{oE0t-FwXSf9c%a z(l2c1{-QjO1M1=NLH#^#XqU$m{o!#&KY9Goe~ybjUd;IH;MgH^?2tKj$Q(OljvX?` z4w++z%&|k}*l|1do#k;%kU4h996Mx=9WuubnPZ2H{$uQrId;e#J7kU>GRF>?V~5PK zL+02abL@~gcE}t%ZpYZMJjM>0V~5PKL+02abL@~gcE}t%WPQB4zF!CLimz2`xkTG_ z&~?}v#V=OI!?w`XinrB`hlwjzDIR!fE!1DXQt^#VYoTQP3dKV=u7%JQ%N1v7-%I(h zbeZCQ)#BmUnx%@b&yR;HX-gEdU0nNY7n$uMvt4Aii_CVB*)B5MMP|FmY!{j9{9+E| zI={$V=NFml{33ImUu3THi_CR?k-26uGV4cMtRI>6BeQ;F){o5kky$@7>qpktL}u3e zpqIz?p=s|S+2EcU^I?bHfn`17=#y_@Yjxt_i*LZ_!(Anl_UJV@ttXyb=rznVCSK9; z6=biuqhweo+G3r^tP`1aBC}3p)``qIk((zRfEPFDeLge#ua{xQcD+oQ$NOP#wN&NX zyk7eusC$ay16ljv`mkM!w*~Bjr^9zD4jaA?tOo2*+;Q|iINx=<;^VXSfvx#A#SicA zgR`BI6|*h$lWifhEo8QZ%(jr(7BbsHW?RT?3;EgXt+1sE;@|H$k=GW(Cr{v)&h$m~Bd`;W~2BeVa=>_0O5kIeof>&HCbhAl9C zXS|vNLld=cf)!h*c-*?pFvx=V)8b8Vuq*M$xQ)=M2C>=f4RG=T{q4xr2{39Daoq9s zQ1}q#TegL9XIsc@3z=;pvn^z{h0L~)*%mU}Le}S7X6&zCh8f$n_aC4=lhl4jJ41u^ ztWvCtgdF|P(81-n+Y{jTwdzLFkyV^5eG5VuD`xT>~+8#nN`mgOF6l1@% zJ%nQI3@z>28CvAE_aCB1d;cN&wf7%lS9|{<{%G$%fc@0oe*pWhy|0pfVLSI1<#`-X z504M(=W#>3Jf7$ek2CtoGRF>?V~5PKL+02abL@~gcE}t%WR4v&#}1ie z$L$z9mdDs3bL@~gcE}t%WR4v&#}1iehpdkm*Mi42$hF{+xfVP!*MdjpTJXqR3m%#4 zup_fh%mb_wnROzwPGr`J%sP=-C$he_JG0)dULM=^GF%HD+qo7zGS`Af=34N`TniqV z>!c&IPPD~3ky$4)>qKUq$gC5Ybt3C)qcfwel}7*H)@0ZFz^u26%(dW=xfVP!*Mdjp zTJXqR3m%zk!6S1mcw~JaxfVROb1iset_6?GwcwGt7CbW7f=A}M>d34g$CmXYvwmdO zkIed!SwAxCM`r!Ve4htx@qHd-zR!cq_j!={J`XbA=RxNCJji^%1)24uE!L0B`jJ^b zGV4cX{m85zne`*<@3%0c-T$xe)#!a-*4stq`#i{ep9h)m^C0tm9%R1HgUt7Nkoi6j zvc8Xep9kCdJ`XbA=RxNCJji^X2bu5EAhS*!Pu7XdI+0l?GV4TUoye>cS${u=S#MV_ zkL`LHzR!d0e4huI@ADw@eI8`K&x6eOd64-&4>I59QJj092bu5lAoG15WWLXX%=dYa z`92Ra`;2{IpOM*TWcC@EeMV-Vk=bWt_8FOdR{a0c9i;Snv2e<$P)B^{=Bs^QZdEbj ziA!RjeSYH2+V^Z9YyZoPGUnR%JR`rAIQ%3t}YuLep#>Pfs#jQT(9BSyRZ*Ak;YK{3SWXVaO)=>KVVV(izNDa3!= zVx_%QYOKg-eTo%59gO2df5iAWv0Hm~ocNQO6bJ0*+(U7|{y#hsC;h^9?k~#oIG`RL zAJos|hIV;8(H|aX^pnRQ{pYyo~C|&7N)>zt-+%YybO+G8A3gud^whq$$v%&H9|I>gkj!!Io0DuSUwEway~@Z~k-2nG`yY^8pC`q|${6o!j@t(VDH?Sd1+iCq7rw<{OXUm6@>;$2nc&r0>(-#7ZpIO^B5_kTE7s z#_-kUScz$v)<>Q*eTT$JEM{$pmAPTiBu?Vk*Ev?^($q(>G6%}U#LAq(xjnXYLCI0A zjfipWUo1$BIbr7K0+OS)-zUZ#QaFPcbIaf@#F(QzXAxtLa+yesIm*iNZ+nC4f8}fZ z$S*mn(@kR3ADvE&IqIKv#OP1?*~IAQ(Ewu1QMO*h*e_FeVqD|gj%%OgF(7qS1Cqqtw#&izGs9tYIJS38oy z995zQ$zYCJ=0q}>qXH|E4Cbg=Wl08e)WkLFh_kaK{A-5mgOfI%u$(- zNd|Ki%V3ULlAT|2)Ycr5!5qc5Fh>>HM>3eBSO#+x`;0ki^k$O59L2UUM{(aVN3jg% zDE1k16ptb1D7J+;iu;Z^ierH}ihaf$#bby$isOhmiu;Z^ierH}isu04C>}%1Q5;ju zQ9NfbM{z7LNAcXi9K~_O9K~}9a}>`3%uzgNvT8&@`CIu^eu%vu2`{sWXUvO)Sy{yC z10tc#Vd8;hBf)Vial!i$aC9EA^B%2+jwkVvr4i6b_ zSJ_4R>&J;v&)49>Vva&K?3_>KC}gyS>khfp=6q@${a1Oz-&)))NawS=kzmw@ zxYMmjaGp&1(=sB#yCJpbTN?>gZK(az{zy1gk=lJUUb%*RSUoKgo^>OcT6-fQ&5&fO z*hNC4NRp{MED~btk<6^akx=bRUe&Mg%8@YEo@CqyMuJOzlIeC?v-Ol@I=zd4K_(<) zX&(t@5Av#U=<_-fEboxav8NGG<4;~SCi@~HA?5_h>?jchDcL0RGjAkVpCg%5>57&2xtTWKcnqI< zM@bylTg;Nahd+ywSftrT$sD*fY?h2+-t$os(mKcKj;^%bGHN93*RPae9!f z!Pl#TWNkKx36eE?HB760mYbuno!2 zM|E}!k@i6;AtGP$Q;6u9*)ml0pBfh`b{*nE#h;={q2lMogQ4PoofDzbFKp)=h4P%E zP!H!Q)XzBz?Q)Jne>g{>pPZx6f6h_*cp-C+LgpNW%sC2~bJTy8Z=GNBCwIP;dlW45 z)AfF^%&Ujzf@N+u-w-VGu-4&VSr-Y1f@QvCdI!sV?gzoLzIsgvmigIZbnxGGaUxjO z>CPI#GPhR`4VLvaEnBmdo1KYazeIGp{L}W@I3=yBV#)ilk&e|6uwq`vHk-lG_rP<2OQLBrDiqE4yhR7I}n;9Z; zykHqBec$yuL}Kx9e2C0}!ec^Z44YpLk(eIu@psO|4Gxu9WF~~j-00ajRN@%x6e4qJ z=RYAb2Zlt4$egL!ai*O0mL>binZm1vZ1;WHZg$!9n8pU-sIFFxyS zIzLm|Ge`N0e9t@nqNm2t0MVazAVBQCDiJ9DSo94PKQpHVivLpr0;ONr&SyQ8=d&K_ z;jaehMX@J z1p3K&C%V-PIU|f;GegcPMK)-*a?g5y?oF5Tg~5>-a^9(s<0t1Y!wb{pobsWlpPZZS zRhcR0xas+3$a%-e*H6x0c6NVdZoAKrb5r~`KRL%Wik~UA49fY*`D;zcOp!6YK2vqoe98la}#<0Dkzu0Pjz+d`)&Cp+BF|Kfc_?&ag zU&he-=T;QohJK-)xW38zT(@vsj}a|cHT#!Jny4W5AUN;KkuW^F7KnzAKpiypS+Jk z|9KyU{o;L8)=^Jsf8XCr z+j$>_^1P2iJ-m-X{k)GtyS$G=e|R5-e)2vF{pWp@K3>SYk3!~s6f*Clka-{VU*-3{ z_KgXZQ#DA{3%QN@6gNN(^?(TAz zXXvff+Bc{>}?{4{FN!_=q`Jb)2}>aA2o21r`T#<*hBU< zr@TEy#^#Kt_&n>3hwPC?e)SYvSKoR{-wl>|ij3!YFY$RpUN0F#htXbQ%R#Gs%;(%+ zKQvpp`>2>-UgC59i(WE@Gwyjx9N)NkOW#vYcu6eE?edg4V87N|#xQBNm&7#N%Twlz z^Bix9#Y1B+nH#swy(NxL`#fbX?cC`lbKvVwPnk3E=1!8MDknM0TKH1KQP#+el@n#{ ztgAOs)>P3$6J)JjahV`%Fs%6mS({%9O^`Kf{d2smWo+jhh4P%EP!H!Q)XzBz?Q)Jn ze>g{>pPZx6f6h_ZFV0a7&pAnZ-;vHDpK;4s^sF5`N%WiTpCooC7k3eV4)%5tKl@B| z5&z%Lbdi2xJLf2r=NyH4I7gv=&QWNWa}@f+IST#c9EJXKj?%{qnR65}=O|>(QOKO5 z{;PbcZ;mqGE~h)n{0!dhDD!H{Y)6^f1{RJo4_~-D%DQ+r%~9r?#l49#pS!v_%KB;x z6J>syCQg)fQ8vI))@f0bi88kzubL?9D`vfBD>p|4-JKxoBJ$8gS*J^HI7;4#IzK_y zmuC@2S?>;&og_zn&ofch>0EC|$s6}={>s=)n<(qO_E$&AKU>x~iLJ;oj*>TO20Mw& zo~usc^Mk97l7DvPa~508e>h3s?bbVq%=yXA;`5)P&N7AvCOC_&1N)q%@52q8B^Lh} zP7%o|7bwM~*qkTq=_8EOTIxp|i}H(=F}ftY^8_R?ZaF%i79WW8GYvzh{t2+BcnY zf7ff3GFHwkKW)d#SthCWSUKa=_%%k(J~Q5qkuwpt^H~q&`K*U}_^gNe`K*_z+2yky z`om{E^pnqe=s%zJuwQ)E8+gP{+CBQ&i~QRQ_M#`Fr-SIX+2$a27v&u%{ygqDPW*Hq zKTiCwFm0Ul3)}guhw^;ZLp^-fL;ZZ#L%Tel=ntRu&`&<=q5pi=)5i;$&w9vw)}}c8Zq%6^F<(~C6Umh#xi|r{ka^5+7 z&Q{J}JC2T(bIQu!Hgay7Rl-irdbK}kdUAi)+dIit&R>NF|CNcDU?b$aMCOx&z4+W9kG+iH!;$u4 z>tV9J^gZyqW-IqM)?z>H#pkdrdl|zYckCpNQ(YaT@2!v9ODvY`u#-9PV6}scVY4`U ziRnmBJDD@j<1{_FXT9+)?PYG*c5sk5KHFm_bID|fz085>KkQ`A;JoGgQMktW9uBU3 zzMq3Rf$!~LuHgGTm_zuU59SuW|ARS)?*(Bl;`>6FqxgOlw)6cWl;?X#sE6-Ip?%m;X`Z0&FUCb@)59S>96LS&! zk2#9_h3(v5l;?3kJv=_BpT`aD@_3>@JkIDRk3ag)anZ*MneRIx^Zh7fz8{6m_oM!+ zJmx6A>w-Co??+*d;`>pUqxgOl<|w`&g*l4vpUqxh~7<|w`&g*l4v zM`4cQJ4=|OSO#+x-;cr^#rLByN3ku;QG7oNa}>*9j$)rNNAdkA%u#F$a}@U-a}>*9 zj$)rNNAVb9j$&Jwqqy&wqc|3rqu6K6Q9Op2qd1P3qqy&wqc|3rqj(Nrj^Z)I9K|uk z9K~}6a}>t{a}>`F%uyUi%uzg-Fh}tmz#PSM#@g9Ma@3h@?YxtFhjVk^NwP+ooOYJA zGuYZ$))c&OlC>7T)JfK0o6%0PHaE9%k~N#Zk+x6Hy~By^yv9+U*FNguoPhc{SD;Zo3>c%&%&R6c;&R^lKB0s&bo9G!7Q!#N85sC*a`S!ZlB$>}2 zwX*=PuV>GkWqv-n>MZNxgm$Ljb((JDEOUEFrgnD7y~AmKL9>;6hts&2v#g7@FP&wb zS{b-V-e{+tp?H1OH=88uy-ZIR$v<10Im~YXlWr1=S5B@nH=cU9NgUnZy2xBQ@YGf2K)%+lGG}t)y(LEtDW$zP&dpKA;a;*v zQnmMTymoFyYww?P@0s_g>nUr^=%RdCwyPTuYAI?$eC+8^ipK}rRi*wXC6CY`hIOrqt`7M1#&&|EQqJLVA>0)=Y`*iW= z>-Op5XZY3W;(y}@)1_b7&N&L@IY*%$&QYkJa}?U;@kD=koY7CtQRqL%MISF@&QZvm zqmVgAA#;xUukw9tyd_7KsO>HD^FU>9nOBJ)yku^7UgstAuzt3etcxbsy=1=mcK4F` z9H9M1z&XmjwwKJ$sU^H*UG#tGCF``u5>J`iHS=rlU~_ZSi9+78-uHLYen-f?XMUuv zm#ovv9la$-9c|?)>udWIFIn#^1HC0jwVvoH>ohaROY%mQ<9}tAUh|aoK4z@9m_+()Z@Q0@7w!`&(%73OOAS_eW#uGQBHO~()Z?>nfe4vlSG4!^t^u1>rUx`IxEgzW!pNyu<7dCwyPTuYAI?$eC+8^ipK}!Ui*uBBn_y{=@(ULE9@_mJ*0bwtu;~BQBt+~k8yX`1 zbny%kKMf;8#Q#xo+MSu){UNqdK{H@p*2#cAqUb&-dvTEO9g_8X|pvniedvsMIW2 z=0K;qAu@*JS7>z;a{s^SdkJk0=gyg9RkZtixzCF{Zox7){ND#l9FMlt>LcX-U)7VO zV3`Ban$LXJ^O+SPIjU8c2w4lYe}u~#8MiN7*3K9Ia9LAHy~Aa#m8umkYtSiQxU9`} zZ^C5F4ty3SYZ==)N1;6DDAdC_3iWf2Lc5%!&>zk%=qKkW^q+GS_KS1Wfs23J&sK;O z`IwQBqUZC%NYQVp-JNE;x8FsIKj9^##LvEUqQw8zjkLSRxj72kIY*&9=P1;}ISTc2 zjzYVfqtGADQRpYsizqrzofJkJc5b^2j=gyfA$*5R_g?B9mVdLQl^AvtQjOSr7l$@L>7 zZ!B5+)LHIn=PdTCq#%H+HD*XN4EA|(F=z5HtnwEOUU z&b^lYS0=7@r1)H4yI0RSsz7yZUgg><&?{2@n0C_o$T`YT`#%ECQQZqi%G@|QJ5u6kc<%39 zYGM^Bb0ACendc1GYQg`B=K3ti+>Z5nxE-16-JlHD!9nKwILKT#2bt^XAak7^WY&+& zI#EBjBeOg*>p^Dy$ZQvx{Xyp1KzjYi+>SDOyIeO4Ww2%w)@fqK`c24O*9n>HJt1=) zC}h^p@?7JI+tDt|Dt}hcb;a#ym*tUJ4>IdV{-ODP*oQh0OJ* zkXb+a!0pH^kIZ_ISwAw{MP`4H*-vDi&uB}(#6BeQ;F){h)swk8-{d!TFudsK&FRf*@9uLc*p z+*j?h4XeV8e)PS>3jM3Vi|+JY#EEYz!yFU(E@J)Hm7!6U+e)5wqJGwi%sP=-Co=0q zW}V2a6FDkl0#tbXMd^QbZXB46|El=Gc6(U4o48tlExfu;e6815XqrhpuI6Ys7)yMh z>`0hYi}+9L;b0X*I$1y3V*SXhADQ(dvwmdOkIed!SwFJ%)qXG}gJRmvZvZ?GqgZ#y z83-W`GzW^k7zCr5(cHMX&KjDg5D))l4c9v6Rdej|7i$=FmU!EI?R#j$^Qm^$kG5Dp zGV4cX{m85zne`*Heq`26UEL^CE)7`;vs1zVbfLOI@e3X z$ucA#kW&^G1rTSamWNVho~gfOov5F6BC}3p)``qIky$4)>qN$Hyqsy9F^}^`r6{ejZ5W$8eN{N_Gb69f46qCA?rz2ILa|%H01-hH zY-~Xt+tFbeqce8L*xfA_Cg1bii|6^?*XKWYzhCd4UXR(Yeb-uhuX_&nUe7&O&3aH9 z>w#Gh%z9wf1G65O^}wtLW<4LZ@_%P$cj1MzD%=mEr zp6z6KXJ@m|&h^{Nm0Rks=i5u#zNyW4?DzJP|ATt(Kken`lr(1iVj1hV|D4hq&#BW+ z9?w=EOwv{w{!}wQaxp&4_%P$cj1MzD%=j?l!xhu?kPl~bR!|pv zTuBP=$z{er6s{tF)l@S+axp&4_%P$cj1MzD%=j?l!xz_=kwPmLi{X zk|VT~8Q-4CL%t?gFKpr=rN)&sLX-n6itsb@4K}N+#a~|!$b)j~Zr0z~ahI!^`OZC?$&G$$=0aZPf|(0uE||Gs=7O0EW-gey;3UbX zNm4hh=ScUdvNT9tzv>imf27{zKS{P1(=}GvJVAzaRgc&^PTVG|2kjao*#p!O)^{IX z%ur9*JyK5fS2Gv#G8fETFmu7o1v3}STrhLN%moJx_miwEE1JE{zSmFo<*j7A_L85p zTdVf@+fQZ{t8B&}2KvdpXmx)#KXEEr#f;BfGgHnkQ8OmuGbYTKFk`}u2{R_lm~iOt zAu_VOKF`k%50RKd>W)c6WN95e7KRL5Af-h;H!4_O7S>~@?TPuabFzBanIMThtgd-r zo@{=jW_;vge3=GWxoxj`jN*l{Tn{tl2D+3h3)7_oJKT#v1isF`K1aA$_gVYTjlUxK_OAK|<@UT(W{tJ`gvt$Pb=#t$^7~XLGoCePsC2UKmx%Z8 zFFZr#z4h-tFykW^Lae$MM}VWN${3tI)e$Qumj-aOOqxsaE+VCI6E z3uZ2uxnSlpa}sjF%mpVMc|)F$%V6rCxca&T{iFUP=9=V5qV?1{_OJE3u44>LZ@_%P$cj1MzDeE3!s zX)(8zsb}!3sxmrGJ#$wzIXkSi8TWAal+mx%W4d@s@1bqXca)GNi2; zznQd}?0u}x^}UL`Xw%M&GZ*qQ7tCBRbHU67GZ)NUFmu7o1wYwTL+;kr*JO|#TW$iNc>b(Wzb5aj8XX~4SQhdCc@sW%1VaA6UA7*@*@nOb? z86U=H2nt@3m%pcJcc>H9pgLQ7K_9)@Ltc zKk3@>8A$rS)%a}W%|2BCm_6`^?THYf`Aw zug@q^7c@?pm+7VLT=j#VE;6Ky`a_mF`{Au0TmykxT2pk;_dMR8=2$DkgpE zsu>gU853qqm@#3-gc%cNOn6Mo{W9FQk*RaqtbMZilDcT*AMz}3V>5nq?OsXULESK7 zkIWsf&g8#aM)<4u`RtM*6Vzw=?vzs<)jJ04kg=}nZqv8R_p2Je%-(I%Z=Cv{wA-Xb z8a3-dZL9}oJuvHmSr5#5VAcb(9+>sOtOsU2FzbQyk2xn(U5c4~I56bARDY)LeFBDD zkg&_@PQx$C_XIy1c1eak*Kw!5m>8KK6K%E0U&(Iwa3kxwKf_?&?*Eja4%j@-i39 zTrhLN%mp(S%v>;Y!OR5*KHet5fm&zAJ=^6)b@kPyJEU_mb)yA4rS(mHpExCWmz@7w z-6(Xov^%QqAG$~0UsXrV-79WC)mcXVA=xTu9Ogn^=7O0EW-gey%y>dBn7Lr)f|(0m z{A!a7>r>M7tH+Z~lJ%Z`26e+ZNkx@7)S{m0#WT)k@iNr>vPX;k)&laog35k6eroGd|4tFyq6F4>LZ@_;Amp z0dnz%ehyYZ#UsIF)bc>#MuHXGzLIYUV;-=7O0EW-geyVCI6E z3uZ2ux#0Xat^3Ru)7P}Izs(b`e_NV09_t?{rAMp(vF{W!;A&W9NXW_*}=Vb%lpcC8_oPJ3&eF4pVk7Cnr=H>)8fFR7Q^t09M4_B7)S z57m_T@0n`klevX3mH04W(jBHS?kdj>DV} zGY-u7F!RE!2WFix>xZ2a)&;wl8X|w>>tpKisW41_rdH>28zG4wYHjP|edNS?b*qh| zq`1$Jl6~{{M9O~Iu#){7}-Jj?A$4UMiYUV`^9EUj{W*jpo zAwJB!FzbO?C(Qa`t_#lId5)a!*w(Cf_r%$FPfZkFUR4s3G-pbG2;pGVdjNd56n7Y z)(?BTw3EW^+nf4pW^N-Xs;P&kZzcbhQx8bnLjI|#j?C6fru9^p@oFM97O6w$G?GI% z)oqeDly)8+Ow6nM>&u&kYUV;-j>DV}GY-u7F!RE!2WFix>xV;&zL3D}8B7iI6YIB2 zw&i~=PnTpc_sV{s<(ULVsNG$j%8V`QvKgL8!>j5k1s==Aj2X>*_a={IL6845&P$95 zGbYTKFk`}u3GWQJE9Hk~GVy7Q`(C*tSx@Tt6VE&HqfBNqXUFl|(q+AR^Vr)mIDZy1 z{&(}+QZ`ckwb^Z1;+oZrHywRjrma?=J9=Br<<4ftX~$eJbHU67GZ)NUFmu7o1;=N& zC0AA!F#Atq{|m0VDXB9RG&O8%eN#5iS5GW;Q~q=*WX6Yj+?0F^)T6ps$=_Lo!FKbi5jg=UH0;?Kt4GtHI{ zrM?(5K8{(A!<-K@4qPcAKFqvkJfR+#b;3Raf@RpB`rFgTy3LntdDoe|zxoGB%vN>% z`POe_^j&Yp6I~0GpVjp@ul*VX%ANB1TiB_r-<61{vB}ICxh+6?bkN_AW_;x0IL!Gl zJzT_%QRrtOxFYrGtE&JIus?_r0TB>@&jn z@!3vNYtTsJ_6<7Awm@Iw>%BY6q5WfwR~G0je>@&%JlVgKeEvDXm@yHb<1pvLi~}=1 z%)Bt`fp^Wd?w3_xe;+)S+tf9BmDW$(N{>95%u9aD8#?L+I zF5YGJcgc5D>@Fe2mYea5HM>b~mlehpQ+Abdch!sLcb1o-E6q6bqNmIYGcU}%F!RF9 z3o|dwyfE{^%nOg+F-~56*X#5uG#V#qGrl+V)bJZC?Q+H%*BvlMa;E=aJpPxjGZq&p%x&yDm&I^)$)2PWqjjWZbX!I@x?rpFg>7t&`Om#+&iUqu0y2A!CjI zD!oAx#g8`bo^+#ZJFCyh0qe=UjD0R2MylKTypYim>Y2S>O3OzHbLzd4)2%+6`nzO#Eu9~z858jt z6J|`9F=56ua}r|0j0vCrbwb`8($6J&JUb~{ob@w}c6(0AAAQwHd!3e97u6e|pO$=$ z^*WsS_0CAyGwNbv&PcJg`foJ(#-EXTch%jRpOO9j^mBs@ai`_z3w7k^({jAGe$KGs z>?s*|QO$Z#8|#5t56pUC)&sL1nDxM{2WCAm>w#Gh%zEJc`K!s8b*`otOQuzoHT&`z zFDhMC-tW(299^=i?Ao2n_~C@AGH_20Jn?7u~o12 zZ_r-G);h$BYizAgtbE4Sy2Yx)*xC=V>NB?XNvyh!t^E^gJ;v6)inUH-=0y$63o|dw zyfE{^%nLIw%)Bu3!psZ*@hqA6c+@kW|D64pM9w5u-z}6_4jrg##*etf$D|mjc5eJ5 z=0bAyeV1=BdluF)bDW37#YARTw;u8(=I~xJ0zevC;ecsON7$?I&==1qc=dV(CrasU8BEHJ@ z2DQ!ns!6^{((-kUi`Duj{?+Om<9*7xmJN-W3wfCfW-geyVCI6E3uZ2uxnSmkTX~F; zVdDbKZ_uATK3dL{Qh%&JTD;%PHRIcM_)6~m>bYrsWm%|tR#)pD;1kvH8%9djQR=a= zKK8h8EgyS+^W`J#IH{dR*zrAP4Y%`d&NJMuC+fm5Npf22nYwzIBrORA~wOpZ-f zV?5xx8uJ4^=9xK&lXs>X@eiL>BX22}ATtN`46m(5ov{PdsNa8@8tWP}M~(Gz9Q(le z*dNBhzA--blXs4$Q~GjLC8A z73X8GVAck+W|(V%xki|4hq)&(_X_47!rWV!dk(V~Fna{EcQAVjv)3@6102U*aX$76 z=5q<=a}4Hl59V_c=5rP1a~S4x8|HH!=CJ_t7=d~0z&xg4$9|1Ns^3bW()+Z|@-Ei^66u4iqhFsb!SYjCL@CUt7eG&SU@8YU^1sxf}*lN$3+H}x}f z5U2YpHR30JsYc$RZvJKt>e=31jXKNtt5N^4J?>aTs%W>=j=VN~u2m8kO*iYug zKC_;$?h$sKK@B48`lqyru-Aogt{3yU503q!(NoTW`B<1SIgY*JeC!p>+F;fUb1g8} z2y^W)_XOr%!Q4Zbdkb^VVfF%Mk6`u=W=~=E8s>9=7GNGDFpnLW#}w??FJ5be&xm+k7R+({P2@Q2c)b&i`LkC2CeQEa zH9Y0(x=8OUYR7AJXvg_5=fiwWMf2Jxj-v(`_go^RB# zzG-FRg!*Q@c$kaybZub#d*uw0=Z-pA`;3xzQ$rnplu z(I&k!*%`j_*Su@OQkl>VWoaE0x+MCzmH|8gkAG7t^MZOkwoR1!HKFs+r z=fjTIQ_+Ys`)PieIH!}@!(~GX$~YsJ{p|Ver}Z~RoLhem zFh+dWYXgm^Sb6=<3^GPNAqxi^qt0qYhUgrt{hgZ;?eX&^HrVqsp4?!^ zDc@nE9slXYjdtFl6*k%R{555hu+Hesn}qeB`g4=LE{t=%n9qGc9PSU|bKj7c`-ytE zDkNVjc$9~cH_eAy%X76D3&df>Z9n9Xr>>bSB!R#H(-f>bSBnK=o)gV{Tny@T01n7uP|5_$)-cQAVgvv)9i2eWq^NAEZvy@T01n7xD9JD9zL z**h~Qp?9!jzk1y7BbDMJ&GR;DR&Qyaa<#EkqRAYR`Z2dPr%+KSl|Hg+n z-e=T^Kcln$dmr+azp6$(F_rb-{!nN78EVx3^>;PamHnVPYt?@Cc$2yP?fDmu4zS~7 zy+6>7KjG>iJMZk}gY9}e+=tk8CY?LPuD{mCA@;g3&h=tG_W^OZKZwtLLtgGD>ft`4 zPVPVIXI~uqMWd(e9n9Xr?46mD&^wsDgV{Tny@T01n7!jTddK>bSB!R#H( z-kCWGy@T01n7xD9JD9yQa}s(7vv)9i2eWrDdk3?397pdsAH9RwJD9zL**loMgV{SX zC!u$+W4|2#J(tGc&_t70$%SPd^|ir*NclH;2jdcdt(G-s+Zm5`S}QB#+Zs3PyiWSB zP|w-EUY2iBKTNz){w<;NX~+0*orL%>ntS;7ivP_t#&YR4-XY671Ul*rJwj3H~>HKN( zC^R8{`RTIDP4oVC(E8os+iI6$Go;&^D3hz=@EPJaHrm)PWQHthx7nEcfHiV0SQpm< zb1g8}0&^`e*8+1bFxLWeEil&tb1iU#gtfq23(U2^Tno&#z+4N=?~r0${Jt&Bam?X3 z%zG?g4(~w$a~yLx4m;lGfyVsLhpWoxko@}IB*0UAx)d;eoz+YJEK|rhb5Bpn=TyXa z<*=&q;cQXk^vx^D=W)f29q*YyJI04^CB%mrA7*@*@nOb?dG7+4_k3_1#~L{fJKjry z#{5N}dr9rPo~GvFF9%7>pK8Z@2+)r6Va|v7U4EGNH*g$B4IGCZ?;${Ae%{wJWp;E0 zQ%^&gDSfwzt?+D=|b5#MW16K6&6X7BgM>kibIPfYa#Wcu@N#TN}rQk+ANi^?bHwI zE|*9*^|HNdO^W(_cFfcag1*zsNp9LIBpG!X%Y;2SjUB&VPdh#q=3`+#7Unf+xOS1(+QA&h z9FD_N&OMZPU%j^#?-A!XjSJ%7%Hyk#%=qU1&m{fT z$HpsnKa)~Vo*4JJ^i2B3KQ%6R_?bjxe{S4k$}?GALhqNAH2pIPao783)g1j)p5@ki zZ3XOkA}3#~2V8wDm6yCWk8O49kyOc}^*gSGb)sh03A0X^b;7I@W}PtWgjpxdI$_oc zvrd?G!mJZ!op82VFJ;Yw!sfbJ8n5MIhQ5>FP5I3Di-&I{ORfCI?h9T^&9CbBQ(noB z6Ru|b$ljMSd8=N3>*4iMhOa7U#+PJyDS0Cb88as0a~$S;m~mjnhnW{I46&p)28nSDUej1x%~&(JTbQ! zkIMBy%6!db9Pvl26q%@=UNTlLIH{ecyqEH;bDB9cp7X2?W^FKQgIOEQ+F;fOvo@Hu z!K@8tZ7^$t9qXa7Z!1TK>!dSJ(x6OO-?dk6Gd^h}@LO1diQ z>Yv|A_nms}`lnOYx=N{AjCm{5w*F@NGUuDM#)|4k9p1=*Q+i$fvPG{Y?@;yeKVHec z{OSsSzmy8k^qTzof4z|GNB+~;Th<1%Hkh@+tPN&uFl&QZ8_e2Z)&{dSn6<%-!u97TH`E9{ahX`Q9r)=T>dPV;0Z4zW6P`lGh@yf4uJfG8!Yk|2Im}`N#7MN>+xfYmffw>l#Yk|2Im}@ak zSPRUxz+4N=wZQzY8Jyd@t+>C^?{<0A>>(RG^t)jEu9o9`yq4fN%=s|m!0B?%k$M~S zJAE|99l!Gx5j9SRx%V*to;CI8cuCsa+jvR;i85wFcjK{vlO^4s-Hg2!OqJk_>g;K! zO9}t3X1vR`8RDH?z0|t@*uAq|%=pe)v&4U+nt8Dnj>DV}GY-u7F!RE!2WFix>xa26 zm}`e?Rh=un*Xf>2Y8N0|=c;S>4wQH8)f2kRlkMr$dnyKr>vsLVWRJH&lA)IR>!kT| z`DiEe_oB+(`BL0dT`_&I6#l)V86WQwEUEIUQ{J90g%{{|xO$GCFOo_4%F{_ z?eqwedU@0{+Rl^uhufJrtRKDOIL!GlVT4QZo+Xa~$S;m~mjnhnW}V_wQhSAJ%ak^>7^K_e?Q|#<=76XEWcd zE@$KQ_$pklhOBz5#~|n6u^fjvALg~hh{=0Cz#PYGV~)d)*FV#kf4B2-IZ&;tdEZp= z#XoX=aTVhaJO7r$S1TI_9X=}ZtCI1?>_=sHX7#m0Mow1O04r~$2G!SBg{3zTqDdi!dxTFHNspY z%r(MXBg{3zTqDdi!dxTFHNspY%r(LblHHKEC-r^{mA2fFGuCGa7*FAL)B66by2ALI z;?zX%;m|+)rgXZg-Zj(up5UNTX8!i-Hzmy%wa=*=@@jl(Gd{xYhMbI5PwahN(sy<@ z<8voolV#h~^Tz)xci*XN_q{4FvwN61pXy%`zvAi&MK4Q9SG8j=SU;YVtRH6mFzbg| zKg{}J)(^9OnDxV~A7=e9>xWrC%=%&053_!l_W=2Sd%1~)QUMhaK0z>qi(0%Ay`T9-0{K#r4*3o|dwyfE{^%nLIw%)GGU{Xl4p zPhPWBTC~-3;HVEvq)s_KHwOKRkTyy5{ONKkT&nC>U-MopHQMVrw$zC*>2XCpHQhq# z<)P={g4IIgMSr#9y*OycyfE{^%nLIw%)Bu3!psXZFU)&oz`U=B<2arJ9ETn6-9cl1 zs=zstAu8FO`2I^g9Sw9xs)euKJyY<{6jC+HLCi zG|S}A8vKsKQYm*goh0uPS?j4aJgFWb_rld1>x9eHyXy1h z7E50jy@#HEwndV^h`L$aLit%pea8CSIB^>FjI$x~>AF7FagD4WYhnE`>xWrCoc5~L z53_!l^~0k{6te-}|+CE((+ke+<(pC@kR;4k2{gi!D#V>>D-Sl9QR~ynB z*SURI9v4ySPNH5GbyD6{SC@QoR%+c;JKlqoc8m`*KFs(q5o~1PAU+j5b4y{UU*66YQz6@XEY<#TE1DU=pmGQ|24<*w%C*!RCkK|Bt zb+4pPWI(5sX54T0Q^|BOh4JzE&*i{yb%U8NrB-FN_srK)y`(zBH0$%srs}bS-pgN$ z|I?1O!K@8tZ7^$tSsTpSVAck+Hkh@+tPN&uFuns-BQ&Xby}G65H%XU6@2A=-(Kl(j zT-_q&BvxV$s<~H=wV}VP4Q6dHYlB&vnV(P_%-Ueq2D3JpwZW_nW^FKQ zgRyU`awjtNJMJOJIR|?Sj>G(o9?aoy6~P?G9FD`d-k85N1M@e1ILJo%q%*ZyX=|R^kSf zG5+n>8(G-0^nchfCd`;HW5SFHGbW5{+i?9h{=ER#BH}t>7}xmW`e7K?{^7b}Gsn6X z5!V~TxKl#ejCQM zh`4?mMm@NG8%CYDe%s8k>c{olFxG|Zw_#k1$Z=fb$N9MSk8yBKAmig&LFUCZgscbG zBC<|gi^%$MEh5*2ajqBhxetiL{Xu;08}f2LQ4jYSb#nhvKl|d?FS^prOlFOk1M{&k zW12Y$xnR}+vo@GD!(0o@HF6wl=X~r5%)NrShcNdR=AOgsg_)DkBbdE|@tj2OVD=j3 zbHL0=cy7RWPNH`(pGz>GV=$k4FrSkgNAEZvy@UDOhWVU_@tj2OU>+kdj~z27;h2IQ z`-N*AXZWu$-;YZfGgH!dsINFplj>!coAEOFCdj3QON}>OA0^#;Mi}26I!wN8US#|^ zmGxYj6Kb62jCH+q`e5Uk7y8KYuKFF=MTPr_mCqix^4asPe8z}l~&$B>&1NT1LAOh5TE;oyxdRJ!+l1b+<(;1zWg_Q7xI78cUS)#zBB&6={x?`H|gcp zo1x~s;WF7@;wPyyRra%;>gx=9&W2;trPvugFICt&O$uflVIEt1_f&ba)5rMWg+OV) zLC4d@Es&2N^!)a0_5$%(FwV>w_#{}GbsJ;smpNGa5B4<<$u(bAo*ZeMKWUJx_0yOW ze}zeSyq;G- zMRK*sd^6st%p&QTA;>tOcd-0>aIx_&>t3netM#0JaOqq*dqchdUV!bt^Ubs86loPC zmCNd!@Imt>COF*0acMA93e;0itvy*T=hZsTvn9(6`Egafw!&zskVF5D?EXGZ4!DjtkM#&1D@9M}K5y?gMp8viGUHcf zkGAe(ImI|U&Q~(to@!iXzpuo-*S|qd=X_E*zV@<2y&V61~cvXRz73IvGVD-72nEdjJ#GpW7K2KGe(^;&wCo9ek-mq)@9|> zaqIcXajPzSzE!Us$6ALS-&&uY*IKt-kF_7dI<0*YE1!vP?Vr6aGoG+s%;!EJ4)+J~ zxo^nJ{X{+7XVl64xAxEO3)Y3#GuT7Eo`Ly#2IlJ-n6GDGzMg^kdIsj}8JMqUV7{K= zI9?BMK3*rld_4p6^$g6{GcaGzz|IXlUKWn# zaffjpcQB7Tn8zK=;|}I=2lKdtdECJ~?l_L)j`MNc!94C@9(OR0JDA5E%;OH`aR>9b zgL&M+Jnmo~cQE@1^SFa~+`&BVU>ftNBrEgw+Y@Ytz z#M7grd8|+0F7jl#)_G}TCn?rh^B%0)QRa5h&lyG*>maK`z0LepH4bvlaA>*>a|+&aiqnPq%t zZwCnq4K)7zxRac0yudhoT{o$IB+U5jjb3u?T7+@G?gORu(B;PallVxX0jrGL1dbQa zovV!}-I*q9tFAR}y3t<}e^I+m4UngI)wyd0OOh{Z%$&rh7K%%4eQd?A;Szm*r5QiI zWtn{1zRbAxnU#|2SGciXjn&fj{6gaapVr8!`oYGH?yi+Y{sG2)zN{7Zt^UR-Jl9H< zN7IZ$cCQw<#kz-G2d|P9X>_mJ`7F17D^q(h>vn|Xe4w9oj5{7CzeQ_*`?p*mi=XRr zpie}gjN7NrlfFl0$?M|ksvo9Hrds-(`EU5#hM&dZ^PKH^`jnxn4hw;9)pN8y^0=#h~NFXKL3%|_v=y<2lb4azQP!FuJhL85%o{; zi!|d{SMFzOD~~;H<+0~mdF(h=9y`93$IffzvFow&*mYWY?E0-d_PQ|6^%gv2W5nZ#dggf_>CyA28ISfID$V=; zGEV6~P_iD2H?EkkpTx%`^1@>`cIz$A{zzCk2C-)!qvo9epGs?-*dAv$q%ypo!YdQ&Ur2af9mAEfa=Pr<3 zisZ^`=8P+wSOQL~TQ2<`6TdE>884UZbIh~I{Kn&*Vq;eP;cC1;;B8FQ{Q}0#cfW~A zo~e*M?p?32J%8}9BF2d0>R;3t@l#JPW{kX3Iu|!aJr7g68Kce{^VF!{=e8Q_su8FD zwJWPVUaDg*dw$AY`Rq8+YYN)&C!{JW%Hju>MICO9|J7ajqBh zxetiL{Xu;08}f2LQ4jYSb#nhvKl_5`VaYCOy^h9O_kNr=T3S?7r%g3NcHT~7#xLF+ zBo%6_ol5nSIU`b=@k|AKNgC@nj`7$Yx4TP3?Nr7CMs}4(aVd>I#dQ{U>-q=GnK`br zc^<+Tzj+|3J^ygmB*uv2lQFR|;wL&A?}_=yo8rVzW7M;`&<|tOx$WIIW7I#otQzY& z@ZqZ&@AGAd9%$DyXy!a&o$G1_+4Xmu7G$pr z<6JN1a~}|g`-Ax0H{|7hq8{!u>g4{Te)fgu4eSZeCuVOG&NDF2KQPZrFwa*o&tovo zhd6J*I3MD?0rPywahx|eALk92=T(^JTbSoznCEAh=WUqha~SKwc^>BZ1m<}L=J^Na zc?stE3g&qX=J^fgc@O6KkmFo0&z~4a9GvH2o^N5Ehhd(dVV<{Pp3h;=w8NyBkBhkm zfX2T;^S8+1nAx-B_MkRE<@6;rVkSEyudm)z8L#QI%nkC3Fs$2WyY{p*R1=Qdp+?iCXmXTKdRYgWd4 zqW*f;?*pDZ{mT>e`(_W8h@QVZQNPoL`O+%xr@6*}M$L}DDdTJXMq$ z58EATuM6W`FXnR}5QqDN_}n+-<$j_b?lbD-{-b{Og}pzp48b9wjsLe=^TKkGejRxa}wN+*{pzgewquq-H}<{TV5QwR2zx^3e;aqREN(@Vx4i}S>>e>Y=KXLjnD3BFNZJvGQK^cjRbzzV`uNt*7CW3Vsq^8DA3xvS5IPd z?7zR(N;YLrVvhZ-A+5x(eG+qiqfvkUp6z6KXJ9yP0oD;ex?;tmvQ=4X;f7U0@G?z0UD3;7u%3V|UOEOgakAF7fU553OH!b3f-6r>tX??yKr|H^7GJO7F z{J3lf+4LsfI8%YPl5JUHFU0hz)mmnENopLvs+D;TbA0C46lNUrKkjofMx4FfoQ)Ab z>CM!}$lJI;T4U6+uw*)8)Oq5)8uh;);9|zHuKpqFG%?fc@mJOS?D;kMI^SKX*!~H>g?i=!QKT!|&8Fh01 zQ9t{Fb^UbvYW6uxgVAzesCuCFKKgq(?MsGCgJkR2?`BT5l6@tS`%h!%*d7wmRD0BC zMmL#$FOk`+cRp4|~?%pBAiR8{+k`ZupoV_j(vsWa!8W{6*V#42e7pX<4d>hI!Z_E9`P>J@;r<{#_YHZupQwlXj5@jhsGoho z`>7IjOL`@4n(Kh)vTV|#ka}IdJhJnj5@!5f(*jbyggWYb5t-e|&5W-|Uc&kf@#4lU zo0OJ_62*)g?(vXD_lp>dds%UxTG+VMwzB5^6mntw#)bm+{6qCzjSzhoTpXN+T&C9q_pSPnUlnh^KsAj7{*Vt z=0gnguFL#7hV|^N`7DNYo@??rhV{R0`pCTh#kw%g^w=KFe>@9SZ{uZQ`*9_IUcnD6UhzORS*zMkWFU(EScLdicSkUoksE8koO*^>%!ZS-(_0H#{z;+8*`E-#^8y zyRVK)_aSC}u7+m*(i87uJo>2X$G(YayH6dz=ylAHERD>ZmVdp9SvO9-WBjX_xV!)V zc$0dK%^b|1u}O_MOH(wl;~(s#M&2H4)TpP)9X0CQovNvskNO)GRAXIUCDjL0Cl-#c z2u~uM|1(W8VVt0@$%XMVPfa1rdvH)nVLiRFI|=LDKf_5_|C|j@!gXPs>&1NT1LAOh z5TE;oyxdRJ!+l1b+<(;1zBu-aeqvq6%ih849n9Xr>>bSB!R#H(-ofl0%-(SvYv+9I z3C!NXh>tyl**loMgV{Tny@T01n7xD9JD9zL**loMgV{Tny@T01n7!jTddK>bSB!R#H(-ofl0?AWimz2oG|{mkZhyJGPddGSJB`od?Knq2SE6rbg@Ja<>`9r{Tw z4^of3{ZU5mQm^RuQI;g!$LVzXkFvdw-p48O<_CFxT)pqa2k|VO&E&#(aF`nNkH@JI z=U&_FW)9*fi&7)+x>z;p2`;JkeL|gIJE&3r{E=#`YsN(NEBCMVc;_!)?fC)Qzu9pv zb^LC}&-(Jao%faZ54)ZNdwft`4 zPVPVIXI~uqMVnqH^bTh4VD=7X?_l;0X76D34rcFQ_KxG|9p|HWFnb5HcQAVgvv)9i z2eWrDdk3?3Fnb5HcQAVgvv)9i2eWrDdk3?397pdsAH9RwJD9zL**loMgV{Tny@MV5 zwJ~RL34W5#yoc>Hy{LFQ=Qp1Csj%!FrOq|2kaTu+HRFNq1tod90>;+=iuK>d*8eZo zJY(x|Vm;p2iYHcFV=IqX`Rws8yWH&gS8A3tMx1hcN*N>m-znUUk+(@P4`bBxIa3*9 z)Vbs@HR^v~qO2Lmx(>BaTY2npD~~>bSB!H)gHG05W%=N$GI=OXqU=O{iOaPH#s1m`q9e{inj^9tuo zKHqT8%zJB+h;Fnb5HcQAVg zvv)9i2Rrs_tJiEPbFaI3U01)|Ea~z>{ce=M%yaTK#YQ&%J zruXzi-k+1ysOQlkHR^PaRipkM>Gi&USXV#}b!O``C5{hvnrqL$d2_BE=i`z9JN}F6 z)@M@*dH4SvXxG!S=sdg5oxSJT^*fE5XRiz6TrcKx9}tK8gZSJx>bSB!R#H(-ofl0 z%-+H59n9Xr>>bSB!R#H(-ofl0%-+H59mml-&PVTH_6}z6VD=7X?_l;0X76Cfel>fy zOrF%zdlf!SxlGbGRRsv@k+^@2WGt4VQNw9nA4kdqB8MOt>#% zbc%2(_g%*uom?z;2X!=aKJ8vCzui+~yk475W*qZl6Yjx?IGal8y%`a|LXaAHx8GBv zp6~*CUq{sWsEr!+XCA4>x~fl7@4mL&9#6A>g*|`5yp?vGuqLbQ_yO-%*?BvSiL~o^ ze?8K!vvro$cKsWRueR5PajqBhxetiL{Xu;08}f2LQ4jYSb#nhvKl|d?FB&~%?_l;0 zX76D34rcFQ_6}z6VD=7X?>LU$aXxwnvv)9i2eWrDdk3?3Fnb5HcQAVgvv)9i2eWrD zdk3?3Fnb5HcQAX$arBP!(L0#EgV{Tny@T01n7xD9JJ_*b<aC@R3C9Qpc^e?(vecw0Uf?ybmR^uX;hu1L<&H?LPH^B&+Fe z=G+|gKq~E4V|-9C4>OMWS(m60=WNn4W*qT5_fjM8)!k~;BXMffnW}hMGavO=X`sfs zdbd(94SHse#}0dL&+k$Dg&k)?l9zV;5gT6Gd25t>W!LlX{8x6Jl~2F2>kqp3%3c@7 zxn9iYJ|GVF2l2UY$jkjiJ=|y1$^A$D?2BW+X!Ml5gV{Tny@T01n7xD9JD9zL**loM z<2ZW9`RE>bSB!R#H(-ofl0%-+H59n9Xr>>bSB!R#H!(L2sZ z?_l;0X76D34rcFQ_6}z6V8?zXeNa@|Pw#4;x8*Zf{}vXgp4F_7?1)lFZ73kWZmLHY zbCoA~x|#U_ck@Y)5$ac$^2(d@YDt$@)>YBhtKY)%NQ-E7iy?VrW?p?=it)XnYRvDI zOkbBGPL82!#NTj6jl8b;5?-TP^*HxZqt12<)u`WphZ^hJ9;3dnqqsdj#kYh#ziX~i zcAVfPrS13=AGzCkbG-Ag>uI#Rj9q7%Qf2M>_p~c(uM6W`FXnR}5QqDN_}n+-<$j_b z?lbD-{-b{O#j#&Bddl9x>>bSB!R#H(-ofl0%-+H59n9Ww9KGXw^bTh4VD=7X?_kt} z-ofl0%-+H59n9Xr>>bSB!R#H(-ofl0%-+H59n9Ww9KGXw^bTh4VD=7X?_l;0X76D3 z4tDI<;1R)6BdPvfNIqx23{0!ux*f1}SrJMS3l z-jA%urE{3D&f$x#-*!)^|L^E9dtDgkdNH5-fH>SA#OJ;tFZUDmaGy~p_aF7MFOL19 z(Np#gX76D34rcFQ_6}z6VD=7X?_lvy7Y zEZof&DJxGT{2O<&NV(*x|CWvM6g$+Izr(eenU6RF0@aBB`K20pM|d?ib5KvmX=>ED zc841EUpcSFx)R+~H!8Bh9*=a|XwOf7Yoi^f*wRgQ{Jb@y?7VOPjCk2C-)!qvoDVQqR~_K4rcFQ_6}z6VD=7X z?_l;0X7Av+3BBVuddK>bSB!R#H(-ofl0%-+H59n9Xr>>bSB!R#H(-ofl0 z%-+H59mml-&PVTH_6}z6VD=7X?_l;0X76CfetD&TE!hX8GSBCKi@cKBBh^#ty_8W4 z)EP#;kVAi|zwCT28ft`4PVPVIXI~uqMWd(e9n9Xr>>bSB!R#H(-ofl0%-+H59mlbD&PVTH z_6|mT>>>bSB!R#H(-ofl0%-+H59mml-&PVTH_6}z6 zVD=7X?_l;0X76Cfe!c2@PEvl**NT3V&x*%Sb*bfNq-Rcjt$6UnY1!IDz25n>gw0oP z>vKxdKTzMhds3Fy)Yp&=C!Lfw(dwr)PD-L&`noZs#7QX|tj2i1WcpeW^MCVIBhJY? zYQ%5vrLPr{_hPUb_3XQ(MxDu%S2o8Z>aS2hjdgjKRJU$^-X4!~zhKYLp6sF>r_7Oy zcKo9KFWGs&yuM`DGrz@UyUurkm+kuNMqakpg>kMI^SKX*!~H>g?i=!QKT!|&8Fh01 zQ9t|Q*e@DAW$$424rcFQ_6}z6VD=7X?_l;0X74zT-f=#92eWrDdk3?3Fnb5HcQAVg zvv)9i2eWrDdk3?3Fnb5HcQAVgvv)9i$8q$I^U*t)y@T01n7xD9JD9zL**n;=Uk^@x zmh_)p&GUA`gHKX5k^bId!Ni|rP#*Q3k{@MnbM>;JA7o{Sdi{x5$?;hIZ|zuFU#Fmn zQ~myX>9$pUXYG6IH<${U@j1co#WPfm@!=`;HzF}V*H|^;T)MADeD9h?%wv)FW~dtV z9J#7Soi0vA?fR=1R%2ZQ-PH|uei4pGE{wD1yY&BR$0=6in;k#z>2G%4H!Z*0_4x1l zZrAzr-FLhGYRRqZ#1htpajqBhxetiL{Xu;08}f2LQ4jYSb#nhvKl|d?FB&~%?_l;0 zX76D34rcFQ_6}z6VD=7X?>LU$aXxwnvv)9i2eWrDdk3?3FzQE-VD=7X?_l;0X76D3 z4rcFQ_6}z6VD=7X?>LU$aXxwnvv)9i2eWrDdk3?3Fnb3(_N!%s6_TQtn|a>8=)PP$ zhNwd(FOwbt>VnZrWlN0O`PC8$i&tl=zeLivDq$X5_i%(P+pgZy&H8Z;JInk`NnS=Q4wyKf$LL&V)2-LH$wi%utKi}~CK#NqxRKKBiIxu2+q`;0od|EQmRaqJh3p0al^dk3?3Fnb5HcQAVgvv)9i z2eWq^$J#j`y@T01n7xD9JD9zL**loMgV{Tny@T01n7xD9JD9zL**loMgV{Tnz2i7~ z$NA_T%-+H59n9Xr>>bSB!R#IE*e`fqu`(up^ZhHOTXwZe{zz%|T>o7rdcIv0?mrDYH-el6>iU^ZY~&7%x{} z*M<3)Lra(%5Xb+en=#_|Ypq7!tmliHanuvqM~ynOWmThor>Dit9IWfwRduVY%k1$G z>-TOr|8t%tcAR~0!tMCkpDniYX8dijT~E%@i|jhTXI^C2zwA?(y)KM%y_nB^KpgH5 z;&b1Sm-~r&xX-AQ`;YqBm;Z+67 z;~M7i4)Z(!^ZWqwyaDrk!f~7@IUnaqnCB&!=PQ`|4D zp8xMxiBH@wIB-}avL|BkP0 z2mU7=U+fppjgIF@n8zc`;}quc3-h>!dA!3s55PP>z&vljJfCnJ=Sj}Tc@pM%3Fi3< z=03wbzrj53!8{+rJWs+rf5JSk!aU!?JP*S>Kf^q4!#tnEJkP^C|8pGYNzTW466W6# zn15ej{@sE3_Xy_SDVTr1V0=~?w6BW!8}Z`WdFi%E9aa6JG#jU`7ko)B6<5zVbXl4o zs%+*LICe$itEt_VU6uQ5E1B{9mH(B{ANpBwt%!f6Y(sVAKFij>3*he>#>@SypSxoI zgo?vMEWAC@)qkvE&S8ucvvr0*+HXZ8(h)bBJ#jdfk`tA6wGj6Gg5=(Ih5 zf#)eZPMfqR?fAP>oUrq5@i=bRvuEKkyUs=Bj@k8B%yi6N7sk0>%;!EJ4)+J~xo^nJ z{X{+7XVl64NB!)}f5T_y|J(kJ-#DHgN`rui|0ni^CZmU5$16U^Z12%T*Exx zVV(zIo*!VIH(;JmIF9oq=i@vH^SlJ}dV$p7&s$4`H4sVV*x>o>yU>Z(*K? zVV<91p0{D1&tabDVV?gvj`Jkv<2(uT?+DDlFEIb^!2Ejz^Y0YQzh5x^?R!<}^yY6z zwdrqUL|*leXK%&(t&15Cul!yfuTozb5Gy?@sC|cjkPJK1nK_f{ev}V6)FU5!lyyFO zjlsfNpQP?Vy$&JP`mIk~XM(?L7_Z+{{~aImpF}v@al+rHGDiII9o5KN{Hl`~M?LEY zsZpm}ZZ+!9`8uVUgLS>UrLMl>r9D2S;tPBJ!za(|IP3R3wd1GQ_QcK`f8(*R9w)EI zcAd{|KeFqeBaiHLVVvv5eD1^l$KF{#RJA?tU+lo{PHYjo5EVPH6&vitLd8Hu2@y;z zOi)n~!NT?o#=UlTcOW6CfPkQU_p`=X*YBTj-=F)_ecf@+tY^)vHT&$d*Et}L0JztrXb!WoSJwKFsS?Jwgw?7wJ#Nxh^u{@EwNvLC^+Pr4fGZ_6JeG)AF94vhvEd5{X=#%1)J_(lV2w1K!V7cyq<$45`>l9e7UtpZ2tTVQk zx)!`SxQBlAXWmhKFU3`5wiy>f(;xR#KJ)zdQJfQVsen)li0+~6m1cyITW{u)1@}|^ zknYOfY}$Uh``u2l|LXnfd@rtRu;2ISrtI*aai^<}Q?&*&;^$c1McFa#@x08?(_m+3 zWrxlaeVL&@xC%4oHM5YH(NwDlku|e0#Yq0Ehu=D}2^arr?4Y2eRv7=9lKl&tC`Vv_B6kC+}J7BpUf#o^{mg^T7-_5yng+EK2@Xq+#OedLZc3DG9mNH-5w3f_UFlV{8j=XR4 z=Z!n>tf!`S%=>n4pi)PFf8N;EpRSuTpWo?E69@8Vj}`y+SKk-Ibq#i>NdCNWyWyX= zAv5Bf@#W7O5r2CEf0l@Gdrf7Ao*UVip|kgKKF0$6ZI&=&UWHtkoibKvdzk-n?O(9d zG9BlBabF$3VL=}~ZXN5TT2JEuZ>_UfD{rm;csXx9FW6$>{GDpU$E?Ju>({sxx52bO*amOcrV{t1@83YLBgmOc!Y{tTAB z4VHcmmOc-b{x5d)N%2RY1j}^7DOz74txc zX5{{uzk~0zq?!8t0bJK$_Z-9DTZg|z_%P*~(^Fgr88!(Q|IVCA3VmxZ=_Syk5l-B(u7aqe4|)A83;EThNubSb6v__r*nb=uD_ zq4jUHE}`cIyUZ8uTt4`AsVVCg4fN1qgb^hvPvC9w1>u;dvm z{S7RA4=nu!SgtQ% zx$c1FdIXm16j-ibVElHF-%Gw%YEUAIM&4vjSP)IUw=u806+@4DFkjDzr9L0{erjU& zILb1D+4)%#FMx{2zB>MjW3& z{$2p$Ps+)Ram#q}_X42DzZ5fcmc7p35rBU4EzFqL3t#5O4L@r8tQ+sO|5Mj@I?mQ^ zZ*}~i?ceBelcv7bdNS_4(mG!{ztZ{__A%J_{V~i7c9}2yB@c)r`9XZi8^)DuTt z4`AsVVCg4fN1qgb^hvPvC9w1>u;dvm{S7RA4=nu!SgtQ%x$c1FdIXm16j-ibVEh)PQ!c(gvKz6DY*P9D zDDRa3s&j>TZ%N~Kd*(8KG`{m_S%BHI=T3ULjPH+@TLjVBM7}@rI3GmQyDIuk6s{+@2XaQ@;08 zcIf|fks0$kag4d=g3a2#s`w`DpLo$<$2q=!gN|Q()p|W{{?qHUo|5H^zw7;5X9}&= z`ZsP}tLFu~%oqNW2gH&5Aim@c<4QiENAe7vl7Hxzy8K`GP1OIj-?05}f0c;%H|;N} zm-NOz`y^QQBUtt+SoSYi_BB}cJ6QSvSo#B4`UY6~iP+I6#UK3#EPV+q{R%9321|bf zOWy-aKLksk1WW$}OJ4;`zXeMl21|biOWy`dKL<;n2TT7KJNl&fqfdh6Is%sK3s|l@ zV7VTFlYZmZGLk17j8T~5G+`)M6GdFCs^8c`H z1=Xy{{MmUWnfvkQmhTI!qKGK|tTLycso&ejbq#ihzxlID_-7PgMw~t5O(KiX6K_buw7;}rj} zSjTrU{^qZYJ0;g5t!K_8H?4DkxtrGi?a@L#FW6^9eq;#(I>&um%!4mz>;UM^f$2dJ+Smcu=Gi=^iQz#Rj~A1u=HWD^k=a2ZLsun zu=IJb^nbCVPl`YKBv`H^V7b14<+=lw>k(M4Q((D%ffLNk=*`gg#y6*o-~0NIh1^>* zPYusbBVN2y_Tav`Xku&TN=Nh1sEKcteZ={^^!KPYildk%3&lhC6r|dDo@=}1#;4kUa{VWY5$EokM~V@D-JyqyF>X@G1I5tu`N4g~(3#wn z8TubSzNhS%*X$F_pIfAx#2y>?-6a0=hkZ3k9Ph2MCW)WR{gX+?jkf$?50Jztjcu@@mgHKX*4X)vL!m zWnEUfoyhsOv(8RU{g~ZO<)HEA%#*U_BImKMRDN<7$V~%-xkk+&6fW^$%QM z%W8>~z=Nt_#gi6)7k^y{lh#yt@kZxTHNhsK#i=lzMFO`_ke z)Ms5U*k!)(mpmYj0JztrWw{l$Cp-?YD^A4={1?2};Gk6_uS zVA;Q5+1Fs%?_lWzVCfHF=^J3_Ct^pR5r6a_u=FLc^eeFB87%z`EPW3w{Sb^fqECXQ ze}bj2f~DVrr4NIpKZB)jgVFy*C;GqWm;MhQxh{x5`lQ4`p9IVG1uWMcuw0M8a-9Op z^$R?(cru;6@zxsGwZXfL-;M0?PVpw2M50^o761DDjr`k2Dn3VF>DY#7#g&eKp~i>f z6qkA%Pc@wr6jyE^PaBV>D9-XBjyCoDr8wyCIO<}aS@k{GJABEi82*-ei&e(G`kyZzF7Rz&^MIuCTt(E9UD$k6kGUFHja$phj@eh^>shH)jI&?9+yi^`#ht5^6n4!PV0Io0Q_0x^{Y(}!S7k`tY{k@K)>No+;KXm+cCDQb` zqqe1KJ?WX!wa%d})3yG?z0&o(V3+yAU-E!Bk{`sEykT6)C-g|3p;Ph?{Zg0z_80Hd zf7AYwekiq*K8bz;mOcZP{sWf21eSgUmOciS{sxx52bO*amOd$V^b_$%KLJa>1xp_W zOMeDS-v&!R2TPv^|2aqLGq6kl0ZU&3OTPk39|KE&154inOFsllpArY9)-lWjk! zU^V7ByV7WSg>TC4HrM!jyI;O2b}9aoHU`8i-eC0b$4%oDf8X$vo?eXA_UCr;!EBz zuH+MXB+t+(`G1D@a`eF-f6 z3M_dBOMe4P-vdiO1Y?fqlVIteVCk!1>9=6%!(i#pVCman^ncNb{xABa|HDVF3*wJH zDRIyz!E${8%XJ4V*CVi8r@(Uk0#~qcr8-0M+Wh^kRK(2Xv#6&vbKYFjDEx)Fvfq6+ zks7yU&S^Q8mQKr~>_w`KB=ae`6%T*mKpWfUQas*yD0NB6p*SgJFj;NLuGnMFV9H)A zo3=lT$fEtv4b7|=ai$kCQ;hhTZf3NEHjJD7%1_166KavJ7&;Gr`Jov4XEk8Pydn}( zm3?%wo3?K}>8|~o^z_nk%Ixvh@r#A}=y9j^Sf=$%^jJ=!b61-cB>IOfTA}9!yUZ8< zk_W_*{2;#M4dY5ap-1uzosxg(m%98}FX7lG#Z(EcpRT-oTPiu;dvm`3Iwp zm@gQ0#C*Y0N3mnR;*a@)Wj%mpoq%QifMs2QWxauA9fJRyqvQd0$q!ia29|t+CC^~V zKUnGlmU@Auj$)VjO5I_X^#GQ20+#gymURV|^#+!82##FlO+zYdZ}}y)WW?A`9(3t! zpyHAiZuBK6K=DAY+2rzItKyJF(`c&WX2quI6Df6ozv2VlV`%%swQP?XK}Qo;Db9D; zk;dLxruf4*2QtR{$KJ_9`y1maMjT^2wj1${@f2fRV?4#sWB4hCPE*tf#n5kzrx^1x z#$)@PW!i4&(*A~C9mkl5j&ICQk88|Z>oM{{qSMF|8RMz=M*j4?l>PU7;V*eW9LW#j zOWrW9WKM*B@bZ94_NXBmVAOyN8}kS`B!$Mj+if4 z)zO$QSn8~+x`3r#V5y_F|DG@WB@eP5;Dh**H(5Wh%en$XC)Otz`msL2PH#uin~=WhS)N7F zVRX%d`J$^m9WKngrCTq`I=GMWxpJf{IXd=MeEW3=8eXfH;+EfS$>~B5#omQm(}-rj zzgOPFhPtfb@6lg9){;_Qbx}T*4Eyfdowff8uZ}v7$B*`k5r5^{c8W3XYKOLpp(l2f ztzzhG71~BI^joxG#=P`DOg~Ej-PG%B0X-8vF;>#_CEF? z(fRz8r`De{hnJog>@r{YOCAtM@`L!2H;gO!gdWK=bV~lAU+VH_y@YG{6*vAiDAx`w zwF67-z*0M~)DA4Q1553|s1fD@mfDFOwG)5j1dKSy6eG}trqC5_FYRz$`&+r((s4?*y{qFF3%jq!b=dJx z>p4~UF^SI4NsmeNm$ZGN=LNgW7ygn5#F6|UzT^$#Nh4kJ^Eyc3`O;SZW8B+JU8ZV5uGW&wAnW*u8~s ztIv3GO&1nB{KXCyJMImIVV^ZHm43XqZ4J)ilSUUB-&2fx)vI|PDemu_LCsq|SNzy3 zQ^fY*w~9N|F^ecyEL!o$J!TQHcHb0dN-*pN(i9ud@gndn5AlVeLB<8kxL_FG5(m6!;Pc*RXG4yT=kCn$dF+KmdkvVBNQ6MFx1 ztg>$ntwQ~RMl0Uct1y*bG(vHsp;_t4zF~@!7Je~JZ8J#m%#fF+sw4X;?sWE^DY#Kj z#m1U7;e8Zz3S*9<87!K?q8Tij!J-)~n!%zOESkZh87!K?q8Tij!J-)qoyNXWpU?cM zS?qt#MfgvDFzn%tADDVYI4geP^4?UpqrKvVjz3LzR$D8cv>`vGI#p3@{FjXXS8V({ z8GdSi8LuPb^@@#nWW-hc=iV2Fei;`m90hZ?x;6LXm&yQf2=SN_9egu~1M__q=1eWJVV0nH7mgh%c zd442zJUZF;+zwdI?SSRn4p`3ZfaTl{ zSkCQ$<=hS!bHuqFu$&L2Q24yz;bQ}Ea!H>a&AZLIJYDIIJX0q zb30%;w*!`QJ777t1D10;U^%w~#(BU0&JUM}_&1#&mU>C;q>eZ*4VLrLU^y=hmh;kJ znJ-w*OM~USG+53{gXO$5Sk6m}9p|ORALpgPa$XuN=cU1NUK%XtrNMGu8Z76f!GF$C z&bPxZ=i9+@z8x&*+re_a9W3YD!E(MGEa%(7a=u;cI3F(lI5!TK^X*_c-wu}Z?O-|I z4wm!nU^(9o_KPV*FW;82F|#WZ5!pO1oyuHR@xo&{$bL9;yQP`wK^k-7u{6`-8|9Rb z`OXAW#;x*-cNP6?nx0lc@$ojFOlLb(Qhcl12h-C%l@))sdvD5C#6sJx+^TB-E^n$S zMx2ecYbZwiJOgSf#<<>tYAJ@EMzw1zhR*Pd%+TM{qK>j-UbWl*|BU+u@d3+g!4eZJ zV}V5jShRsLM`#9Pj+hHr<|uZ|UHp*~u;dCXIRr~?!IE>Z)B-Fu0!!_{Ew_|VwFB>} zP)^kj{MxRvsvS5ats0?r;BDDz6KV(U)vYd}cHqv(>XGOqs|FV2q2}fuRSr14Acj2Znys4lK3%ld(R<2Q04zOH8ng1;!j@{fIW$MKf6D z0+u<7UDmDS1a`?4SaJxK+=37cj4fgilOISo?42b^XYPC=%45}h3jT9W9W?`o;mB<2OX z%oqNW2gH&5Aim@c<4QiENAe7vl7Hxzy8Kx$;XmsLmO6r^j$o-HSn3FtI)bH+V5uWm z>IjxPiXC|nf8+-&bp%Tt!BR)C)DbLo1WO&kQb(}V5iE5COC7;dN3hfpEOi7+9l=sZ zu+&lPsH6C!j$o-HSn3FtI)bH+V5uWm>IlYpiS^6VTmBecCgR8p7pnIcv&Ze}GM=^9h3u1J<#W;9P1|2SSgifKX7SW<%BFeg_}TV*>v6B=^U-=v7xE?18GXoC>-UWG)$@W~ z<_mwx1L8=25MT0!aV4M7BYB2S$v^ZFwQ%P4_ICcmY84}3oIJIq75vX!7>-H z%u(#9o%kasV96C&atM~(f+go*sRdYS1eV%?rKVu1HCWaFSk?wu)(lwI5*TYzbjsR; zUDhO6)~fiUc3@fCU|I8E*$ZIVBVgG(VA)gPKkGH<**h}sUDb1z=P~c8&NSw%Ngv4C zmCxAkjsHk}>itkYxgSK*E{}A@N!vbAA6PXKG<^q<*+TJ%kw2+L zgPMxlN2SmU3rocpdMD7Rll2sPc5F>Yt_@K0ZM@%xKI~y0P_ZSgXvv%!+Jd52at_B0 zX-=(!`YZo8&6?54Mg0^v>E4v8*XyfzO<)tcV(P8fx^WYVsoP8Oq(V(-%laPL-uT&P3?xgk1it9w8^TvSAB>K0ycGmNPUFHja$phj@eh^>s zhH)jI&?9+B0=+scUxOtzluh|hw>)(VZ9_tiJ)k-tF4Gtx@?t8WU$)aHGKjHKq#fa0~ zj2ZF24cM*h7o}WY z!gc(Yu1EB^;opvEJ)WJ9lIT3R;3$cH|5ZozykM94!e8=$IFcX4m%L$I$tUzko}p9n z5B*XXW4#;S`#7rRYpfSC##3ypBQnNQY^--O##3ypcQVFPY^--O##3ypcQVFPY^--O z##3ypcQVFPY^--O@~G{``q2JH-W4N`Q4ht4Z`4UK#x?4v7)D6$5`(=zOml*xW;qSILKB>Ij1q~`^@%oqNW2gH&5 zAim@c<4QiENAe7vl7Hxzy0jlL}i3#A$fUQZeFR$Zn+=<94f2Pcig-FH&DIbZ$D&4EugWvSgTZR zADo=3{e2Jp&~fe!Ow;j;#~5cIMB$FU(8oWsIZk#yHyF7)Qr3#?kSO zarC&xI9iV}j@D_6qxBo(=y|~|^@6|D3vr}gh%fcRxKc0Zk$OR=)C>BhURa08Z;Gn- z9$25z(ac!4ZrO?{JJxfQ6*JcP{fW$2|Fe!TV_$5_SzP&JzZ@FPjQtgLnHl@5W!)0W z2liF#nBjjpg&A>P_baJ<5I<`OGsfNZjTw4Y)hVTXpfhyhkveFVkVaPHOHQ4yT!RZ)W!KPcc~^W4?MI$+YVYb4b1f)5i6@ock9qq`M}?OFEiq7&fZPOKQo9K;||}+ z3_aamGDGLlTz1MI`nyzN#=LCmFrUd|Mq=OQpP9t}r+HSAI4g!`BZ*(sEj!7$XC~$# z(KE7SP7afdv;V*eW9LW#jOWrW9`$&6xG0!U< zNnW*>%T)M8KR^GDpC^jmZ({yn+&iCc_?zcNlV3!2rD0D}G<|EqyrgvuT|QV%+1n0^ zA)AWKC2V78=jy7gxmXO9-^lkb^=x8jYG4&*|Lb@RE!baK@z;g1lzyd>Vyo4ksZA>1 z`$WHsqhhwqrpaGu)!quqr=#&5+d1~kzUg1dI;p&}ANBi2PM*vUGbd0=Zstr~5~$G9 za>}Rgm;|bvg}JDG0)@KrJy%GX1gf7}M)_yHsv*chL^*g|Qsr24BTKtszSjp%(viRNW0;a{&P#f-n z^Df8J>j>_jMUvtvUvuVG-{Z+4yoee%>6+nh$=uT=o)+ydtn5pF7%`hLzaJ1snXU3il6x3)gMuHa^F!u^l|RtkLOiZjxA(MqICHq~D{3^E=Q8ub zODcYq`D4qMlwP0be)#eW8nT-?boL9HRFQLap~nkqu$?)z`wQAsiF0c=>jf>^!F=oQ z7j(-w-;RB1k@k|BXW<%!ZhS>SKe&$jx4fb@DZB=XXMIH#zVMoHz4wBgAM)DEDEOQn z1n^p|68Mbr6yY^|u+K9JUCHcf`HW8I=XE~0-ZQGOnt8?$!(M>*g6IBcG}D)Pr^R!! z|HT{^@tih|;k`5b&1mu|I843A3t2LXuGD3o*>ogrUdsIC=WuFQ#({m_I8v{7%pGGL z=;&idWp8fbKxv7?6|eFeMs9USDn8S67#&?OO0iq1VKnjaXl<`lf2{VmUo=iJ;ygb+ zUNPcVdOSgKh%v6`jfsk($8YT<#n5S8&53;s{dpHLV_w|?n2WaJ|Kq8FqJXzBh+|Iji6I>_!~N8_bCBKA7+EF>a%W%+OFBl$sm$s5L% zd_s@p89F8Z&@Xiv^mv!vUkhvP(sg|A9;EBLh*Br#SXnrI?mmp*UvYr z9eQ2m%4+!h-e1v)+x0qxUDhZ3W!)l<>@UQZ{e^L5e?gDzFX)v01^u$WFfZ9(jXZa2 z`|a9$w11(idvu&e1A=w@$h*OM+{umiYCY!{?$tW?h3?h*ubtkj=LNgW7yh!p5J&bG z;>-TRxU#>XNA?$V%Kn0W*xIcAm-yaU24f5#KC^8RJf_<)wU}=a2(4 zbk_G`hW<-inK7^9yO=Rwu_F)SkNij+^O@Y<9w9;;Nh86_7t;E-kG#z4fB$rGbo2EbH*NL zDn5gG_P6QUKGSx(_V2NEnvRnv=QJI^-jb<$+|Y7UwVseWQz-Lw*5kHg3T3IXOz8>m zn?jcsFvITqgc<(J>Md73h*RE!8S&5EWX8Cb`Bx|(=$YD<89Kj>XNG>SMa-C&%Ti{{ zSM11x_#;0O2YHkD$ft~pJd2)w3tY6$1z|2)zazQmdBHC8g}>y%WvLfk%AZrcM{3Z< zi?*6GS4#6V-Y+qaJn2av6LKh@a?;~c!PdLepak~dHLywy;Gj!H=WrqGM)0r`^ zfGNzU@BCxGUVMr6_Z_%I$N9c?iH>i3d5IqP#n&ZTk7ogI5}n;Ddz0wjR>ND*3wD_= z{3Q>FBl$sm$s5L%d_s@p89F8Z&@XkV|JhB~D?Z3g+g}WG)Bfely6HHh|5~Wy-x{(| zkL#anq1Mys`U0)<^zH>(f3Zyq^t@n~`NCiFfH+bw#Fu(uT&WlINWGv_>IMB$FU(8o zHLKAgZTFtHNc(r7MLN#mltnuJ&svN1xEuQ|)_U5^SgdvCSh85_AGCb2o)_#=FZfHn z5J&2T_);&7EA@gNsTXugy`W#}^=$hrU9Y|cXK8yq&zai)h}ldX=ef^}f8tk}p~uaC z$64!%SmUg9)}QRG^)DZ8e5dL6{(@cV1%Ig*;z+$Z81bcE7+2~AJyI{|lzKtG)C=>H zdX22_qU~N0F4{kf?Q9+A>517o{IHwP z7vf005MSzraiw0+BlUt#sTcH1y?T$IsOxp@@dRxT?lwXD*Sa!Z$LZ61ypB&XV=kFR9m) z)QQ^u({qycpOeeDKl2b?9pRDyvaha@jrf-?7^>5!hS9@#)MdN%I4br$v&vPe(6JQzm^rz;@f&EySu(uGo4aKUH9E_@ z!(t4L-N&5g%xF5ln)&|3(PTb@*~4-))#<~WoO3i)v10C>K8iA%|6_k0X{O@C|Iy#f zh?BCD8S!nsm@)3wNzBl5%bpoJ=XGL+{t~U2F|W85%++s<)Anuy$7}z~&&TUHfqjf? z!SDD@PEF9`PR=_~>xt+xQS0nFbs~xWFRl~yykM94!e8=$IFcX4m%L$I$tUzko}p9n z5B*Y?PW5N#dY#?wtnFKiI&1$5e$#cF&ZVd8_=k^7)8oz?K27VXRb`six$W0ftv~ha zR6Q@)Wxnv2dLfR~3-P617+3NMJyI{|lzKtG)C=>Hdfhs2yhr+7$8X(dYX2#BXX-c| zI~(t{e%I^8fmwRoB3WFtp3$vcw9c=iU9|r7(~bM1-|G-|sTcgEUWg<0LVT$g#+74zJ`=IMPmv*J9xA5*u^)%&z!wYhr#`kbAk_jMnqIeNcmv6`d% zz^vSJbbq+>bGGgquuDIIzw{Zzk^Y1D(w8u<^egC*J_eoA-=JUm9_A(eaL-LwZNEBb zzV`34)%_euy~I4-sGb zA;y({2tCpdp;P)H^h-ZXud-P0uM^J~={oLNzev~jQ{P3p?(<77((9q#M>oAr)|=e) z`ia}>rq@+9UpKwp9(cIvbqKrcFZj#;LLAv&h%fsKGMa(AsKPpG@rc_+eM>#uylUC#@4**>II!rFX)$gnJkv+emMJuuikfKHu&oO7~IcS?^EkizIy+D{ph3jbwBda z`#o%%kM0AJzCOA?to8KKeFJvshwztvh&a*@5nuWt#+7~uJ<<=MQ~DwFOFzWCq#tHD zEz|abN0w>-TS?1woEG(#>-b)ymg{jVtyr%0Tn$~Wb*?(IT#VY!|c?9vb6FZ~d4 zq#q)_^h1m*{SbPjA3~?}L+F=&h~jAFf4Toc9J&8Oe7XO^xN`pmJ#ya!opS#L{c`_>dCC13<|}sO zLHv;)iG#dJeB@KcMV>_u@-I437txP;$-H2f`NCiFfH;yL#FxBbT*)W&NS>in@(=w| zmx8rEkaN+h>htP>0}fI^OMXUtB{G!yM~_$b6Lw)V_9{OM4t^d+r*Dr|_KK_blYg#J ziqDQYKzZCoC?4e*N>OS2EO=)6KFSmAr0fNI?xPKRrzkG#5kf9j(-ha+x|g2JoUYhC zFqphs?{Cahd~5R_Dlmt?N8pqYL|td{bCX8#L6rWKpEXd+Alg!Y zrSfm}ZU+SqU!yo9GLZbcZ&18p+72@94pf|b`*zCmBtUVegg~nCd7I*GlLE;sYOCU* z1p+Dg?iR&2UkA{qLz@+sd1d^)?`4}5_sJ7T!zXT3JZMxPb?xh~_)XiLbkCljFR%Q$ zk5V5nZ%7WI!DDwQpW`p~Qsi~!CdY#*Ez3@2KkU1QEb}nG8?l?Zzh$3U?RL=wALiRl zg6MKK<_G=5=wb6L?&HornAsmknKitlbdN!6ovE6)A?Bw0=3=hS7QPST4c zeg^#}IAJE!e^?7uRTF&R(z(~^|IlUYrlGJJjK$^rmqxlfANi$Tz#$h z*X6HtDVDka;V(4i1M|m#cv^Xc`Syl58ZemoN5E$~_l)DL8Ja*_!r4CfWddd2!Tgs) zBHdiaJg$5i&FK9^jTMqDjhZZZs<_I@A2dDunc~D2Kj`_*=ZaUXPNnU4UMLQZNTE$f zUMennC7C>?@wi)!zj;wD3&+2)I*D9I|1;LDUY(VHfj3Fiw0{f5SyR8${#w?GZPSyf z&;b6fO^Np@wBw$QvM&uurPXU&E1ucq2X$O&tJrkr2ZbGLr?`KPH1baGpm_YOM5LZ2m+$n=^m89z{_jn8znaQ)C>oW1(2O|CC>ARqQkMtWZt8_IBE5T7Im$ z;=B|`EB$IJ-q$ytX78!3c)_jp6cdt3eJ)Yu=R0y~8n5hyvPP2Q%D0LuypJU7Den~L zGxS`Y_FnPY%2Bj- zS`nkTP?1kG)IV17pq7zTZ_#JPy=^~IFWWf9&1!z2nh%*jRoFr^7jPfAKXxrSOym7n zZ}B=ho|}32-t~0mF7Mfs4>nNDRc5CQf0~lOe6HLkYSoqfTh-o7g>L_jlXDFX%)#;N zY+p?WeV8vaSVh^>n8TxdXk5DxrENnMU&@<@_jT5_zSQ$IpI15Fa2ds2=RS~bwww|l zbAPy>w4A*1Fqh7?l6Fl9QgO^48oy(I;EUorCyeKMuagxQ4f7(u#?0T&c~apK-<7?= zFAusqE=jT5SP#n5JCW^~J?N-Kg5nl;+-aThcT(`VR?TI``^H_VitprIPA-qr6nCq$ zlFm%{r8sKcI(mDK*F%wkYw0^NSF5y!+6FL}`>~qB#xO65T15|wGPg@vN!5mBs5lV| zrql93&WT^D;8cbtn9alW**g(2G?1W;shW1pT*h$5u-1^dj4b0W{^`g_S zm?vEBP9I~Le-3R+rMjAw|Bp}Y$ZXYV#Z7m2pq&Y)6t`H`iTcf9-nXg?9j?sm9o&tU zCvu!q&q`Cj#5>AA=h_nV;@V@yW)(|Nd;dp@7ZfW&BOM+pzA~c(<*fNYv30YO6r1V3 zV!L6b$SL-&;&Zi2((rmu6`M~hNkg}C@BQIWk{;*ge!IL%c{)Awo$^`Gt1L~~^;Yqr ztEDOHp*M=FZ7xNF1GwK#zE+ZI&E}r$IJ_iXXv@7iNBjQtt7eMwALwt?WfgOr<0wif zo2u;3%|=k!In4W)Inc5IX1~Hismdzm`@w_AzAJOTVa9iA?s1$=PsY>5eY`IQw|1gW zvAi$BE=;9>e$2_O=Fx}zyr&vnn@eLm@?O{)H-|i@ep4D&9Gp!di+R5^E9F9;X7WB7 z+QfLK*_QX$XXA6cgYTKo^z)#$zrVjWDAbt_-Q??g%Q7>`vLtidU$dyLC-;HD8)j2f zG3Lfg=hC7(+!K2Hy3)5}%(+)CptMWOk8Rzka#r@AYi0Z``0>oUb1kNGNz9g)7n6Mu zj}&!_t(334pjc#dNub+wT94`0&5hT zZ68Sc&G@}y#XbY5{7oNaZ`FAK9bWFG*w1|+?HjOIajCSyRAhy#;ylF$(e^Eq6~{OX zrg;aaDz4XU2xU&3uDH?tA@rgDOvP0ahfwS#7sW;Q4Waps<}%kENT+T1{kH4W0o3El zL}d?nZciDlCn#PT*q*FUI4TY-)rnl|FxT4Ig{~K3cCTtjY2%n{tnNWhb%rZ{hugiV z?w}EhkKOG-ca`X_zdoAkI*xiFT{tPQ}$TvXoMC-bAt5HA2sh*ZJ zwtjELkNaCvxzarpPd;c#?m4?`P;zP5SnU z-_MX;ZCZ7zHOF6Ehk9SIRov3Sk_M!;Q+(jLC2h0osQ6d1B{_t4R$Qf370O$P$4aBh z)aqSxW$$EDnKm6{&OW3dg$(8R+m96@*X2BJLf<0fpTgSGYZs%xgE@|UgA!C`H@|k# z;8OJbdovZYs(%@36Tm#R*`a zHLG(DYFN6Dvco^c<+9?m9)+om;|;~`a|=?|W;Yeb4$n{SADNSi=A}I&Zz=o7J-O+8 zD0AkTIcfhH=4=PD(W}kO>pN#5M_cBT#&;a<9pyNF=D$n>e(+fFtA3cK6=gmZk!*UD z_qvK-V_%Y~Q_NMxk4Gn(?2cVgyr4>R>RjxE;N^ztT^LqOUm1duV4Kyv?R;! zN0hx~mzGq={;1;K?$$J_?=i)9XSATHt@&D(e@{y)x|^??vDs`WsoVkOlP}7K4($q4 ze7Upn_YT@~e>hdvmPX~|zER%39py>k-qP$t2O3z0`SOv@bYUL%pPdK0QO?rLt;`3| zdPjbbRMx_tN{r<9HUqx(qw>GMW1D?mU#exnz3#@P-Zbbb^NF`TX~87!Z>bNvQ}Qq^r}btV6`y-N zoNiazq}c8HaN65pv*OO9hg0h4EsBG7InuE?TNStUbD%QwwkeLRH;kT-3{YHbqboi6 zK3MUf)^lmVZr(IObEsXVR>j%!$9IQ$l;@t*56_qk;U|oWYYRGT$H-=lqbx zbY{^&#kE&?(Z^2QA3oglp*DS(FJxLtYXjNmYu+_9y9UP`{AxWddgY*AYg03jet5Dy z#UX%VYjQ8@X}g&&U1V-heiIG9$DHufpHBSl zdm}z>pp(z}wJXfFlk*kUKl;aZ@*T+9a^%}dOw736jM=|y7^M&Bulzr>4W;Sb*zQ`}_#7sNxte(heYWEG@1ufgbQ$Ir6C$an zZBg}F{N9DJ|JCmjtTg{XUxy?r_HOi%%)OHo+jftn^~P^{;JtB;9-nBS`47cC>qSxj z4nGxdj*Ft59+_0k_(jpQersmMeIldD`&CxOdCJ7ltL8Zrhm?z<{sFlZmy3@!{`PAg z#RrVe(QouuGWx8t8@-K;9;evo zd1UlHrPJtzWb{PEMsFsgM=KwrcaqUV6&pR3jNYo)=(S|@T*XEYCZiWCHhMD|JzBBR zv&rb)ij7`QMo(94^msCQz2Zw=EvV%c3&m$rThOgZ)fFdXx2BYmwG>zA(3;LRYOMI; zAscFL-%zoQb4xnkqQ2rKYpiL_x4MeIm9VA;%jzih$~2T7#q?IZe}nNHye6-K&$C9+ z*GOI`??;cI2mP3HPIaVRE_^+09%y{;pm$&OTKhBO=)h!tZQ8>LR5A;%nNN2o(e3xl z)6Uw{q*}Svz3|<$189JWx%=ROl(T;xWuNLhka8QpUxYPtx5q%bvD#d5osa=^zGhy< z-2&`s!71kVjr-G6>wL=ovwT0gf1J;t4xP}4VlDZ+=!3nzDRv{D75VhGH}%TQ=Q>&! z=}V#0`20YZ3*9NO`cE~Nms@+%qcrA1)q7L+#9zwpHlPogW#fCXp;i0Rn@!BeeEU-O zCVVzvt7l*O>jCrapyD*t`ICC>)1$d)ze}Xzf%(m;c}3>V^Yc-cUmumdT3i8oo}caZ zJqy#+e$2ssMJfLc=GNnK(wjrfTZ-f$zqia;Oxb92E*=Zltht#Z~S5UdquS3G9`bRPV9|R+^UEfjf&%#WBX>I9wYvVZ{4A| z%6Zk6d1%a2{+`r{&pD}7H1plf*{S4PX21SfY5jTT^R+XR!!qXCwKLI!*37OK(oOH* z@b}=R9!oWSpT>N$RkG=RASzrP>1yKo_@8^&?+d?`WOFEfwb zQJ&Ij@%Og2_o_>Kv$4JG`a1M#7IXKtwJ78sv-#i}G_)l9U;9zjxTY|d_pCyd2QarV zuSBDbzpsJyiO<|xui-O1*RrQki<-Qy{OJcZC+0Klf6$;#y!IySNTv8o%u$b0Xme9O zZ@fMxnMN6Z4-PTI-hHPlZ}~%$LE2io-pHc!osFBWyj}- zk0a6*<8wvZr@Tk-dE@--8OlD>=Nt7n#A7wP@P$@aVRkJQPoMfGE1!I8jlXr<@w?*4 zzL8Y$NuuJRlRg>W2V`!z#P~jGD0AetXo`5qoFgoT*40d6|9!F4dpGkgYk#_SgliFf z*pKoZ<2;N?_oGjxnX}JXLydem|BWryQtjX8$9|-(rJbv|UgeV4(T}>!j`=rG`Uj3# zXNMp4h~_v$SNhS&a-8$|bN#4&Z)Ueu>*#$c?p>k&YpLuB?r-ldtf5P7m|K)vLw2Wg zsamht?MHsqnR|`!qr1zwce(cQBky>Q`RGCzRjlBQjsc{Orj?suIMU`NRXdx{JBm#`~1Cin*D`J*qN>Ipydp`gkJ0 z(zd7mTROR(uNRw}y`_S+`5JM)z+1|Dmbv=LH}tYQUoY}CdPC3eGe2JPn$~vbIOS@- zCC@!v$F|OIsl;in-Pb(tXvkx(*TMLAl$4G6Vet=?w+q+q*u0NaDTHemS>O}BugUCt zEsD%<^ZMDpErx8jFz;~vOy;YZ$J@sf?PnfX+c-ZkzX|t*L!NYUV`IfRJUxx?2scu^ zZ;vN={@qaVwh~_S^;HA5-}j;-IhhweTtfNU)>rn+#g@{H_4O1x8=qCy%E262dl|Lc zXr=7^Vwcmi9?bJ+uAvm$I?8TUcMT=KWZrnhkM>UI-;(N+%a4wxGLNsnnkr7MtNbk+ zucGO9ne&!eNq?2)m>r(4p?X7WE1#n)){>ojEyboK>&WGFO~swhuBX9ym>1Xer|&K` zls*0GMw*?CIq#CqRPK0nWiM;Ll`5@d&T1JzyH_xe{S`=IN0}e4*h5RdR8#(kw(h1= zo!IWOW*044#+)%Li0YqW-q2$wt+@UBwN-Xdu3OA~dW6!4cNQwn&2IZC|6dgqpAOnj zHS8)WzI1y(jepMk?$&-9;8a=J3-8!ZGt!xzJME{=UR9Lc(%9pRa&XM4rNii_EA!hz zVdQd~zh9gqe5}MCRQ$N7H@_=15E9JZCD8>lZYEK7C|%DeFYL!l6+kB(0^8eo1ioC3u9S_%~;2oCA-psQu`DbOm{a0Q3G^UQS_n%~C{Ovj3 zr?GSD(J33|dztNM#s+KUv%KpNIy=oqv3>4AWV4W&F4c zmCqy31~h9m^PThc$T@*ItCAyfsbh(OdDk9xdtCRpw`PZD?-KKFaQR%7z-hU`~p$p)F2*m3{nQHe~gS`FI-} za`x?~?3pICq||~Of2#4Deo@Xnm3_+DYZa<03KaQs4pbI|9<9H**T zZmQaf*Tc8|=Jfq6^U*H(Xz`#yztvkQ>LI^D&~rU8Kzu?m^;qMM5ZM@l|AsN86D2a zJiA>MYUbZV*(VpvM%K-kFWxYxGg*26c3hoEDXu=`hceAX^Q*6`0%3iWW zS#q4hZ2h}ZNd2iz!?=t4Y6Fn$>JoCb3p0s`_ z^B&`Q`pL1(wTTk6?w<}&d;Ql^uczR8q4CQHQhTr zRB@9P*3_*Wv)O)Ys<3p3vWM4hNtKhi7I|~nP|-=uS^C(}&q5B$=j$;Wa*bkMz0QU@ zoO4w62VFYT(L*-)v-;mZDDp$#4A%e>ppi8_0XR(7Wb!)eYs=57}K=*REh?DaV~m(En+ zI2nWHQutwJrx4?Nl&yGN+nuv%?qAGBy1CHo7OZn#*i3Q?Vt#CVxAbHhbFmB4sAel3 z%YN+?D&)jm&T1ZQ@4(ucHE|{D8Jv^eXXewj{hX_ih=tTRjcd`q$RbJ@%6wziVv2dn zwJ7_`og8N}&kgjXM|GJO_E|#a=FCIQm(rWu%*QVq=US(5-TRzbL606WcVDrR!u$MQ zS9Mp>%2&+sTUSw27hZc)9F=d)tUmO#HDR&*d&d!_~OevZ9dYu-shfZE&&e*e?YAojK zd*#WyXiG(Y4=^QL5dGZ6T)|}rMdji9_pvtu>F=J*t=es-;GvDxSj&72KG#TbU+|u~W-$T~%qU11+zu~DjB^GI~Vip+UL)D-2`eQEmXPRbr1;!ErI@cWbbQ;oA~ z>-c?0$v_`!KbzlUd>*@;X3gXG5|6x>QEWNpN>_ZT$zgskF};p2eQ(0-bJB;(h4Xuf zrc-_BV^!wXeSGN9dVViqKhlTNv;F1~tLe+zK1$EwR$It#8rv`L*+N5d^J_Og*+LKY zGVi*#g&KF|vC6F9LcvkY4=Qb;Np7sI{rt_8o||Ki2-!qdp3DmmZY0MT=F%JdX-;## zrU#ALK;@<~TUTFC;Xce$KCGpQOPQngtf5|$n62jcQQL;hk-?iO=LXJ|<&e#kKb+sc z?Hs(B-dy8+cHFa>Zb$NazdS9sP|3W^4@+#Nqis0X^lxbHuC+n3Z!djd9GQfLY8rjydNnh&iBw0mXz7!zpvl z5mC$uK_!R@L4EsMMfE*1_kHfVcdh&UUjF*5T6L;w*Y4ikyXmf~v{3x^Fy3{)SzqGm z{rV^^J}g`%)lteFL|;d2@HQOEJZ!RhwWwNk<*9fRqoP5dtGah2xgmSa9or_0o#pPWa#yI-M?M}<2! zzDns!$oY6O{WZFr9<7=g4|b)}Q$g z&(iTkS);bjIZG|`35QNSOJ!VSJ^b_hSz6Ux*1*E<=jg?-svKMQisvcq<|@q98(g6E z?_`brZRthY-&}Zkj?1*+iVN$E47oxP1BDBYzD5`9h<>Xj*P3G8AJLo#!daU=qQ&Fo+Ho!^oc_ow*ACzD z;q)~~xa)<7RKvxYW1IK(0j1a~eCk!0@qLZ>y>aF~U2Y-Vb#W-2nIL?i#Xah@Sa^uT zT}m}ec<_r}bSjJ7d!N72g~~+8IauP8J1rb896qx(&DbmF_>cX~=*3Q16VB~!NXrJc z;dtt;t4CeF$~seIof|FaB1+{46|I86gH3YR!|oNg{F&AFO9=@?zOTZ%dB^21d6 zrX%yn9ET`uaY<&E3#$$cdt_jN01>TjQu zpBZ+--sNS6{f%StFvD-#>baQ_&t8{Y%!qT_@SMzuKXXzJW{hj(UE#IWE}8Pdo35Jr z*}`v_cBY)UZQ3u`=$`4fORM{4JVS4Uk;b{@=mRtUhZ!E4}Y;qU-JgP znoq=|c}AR?f5flz(x%CJ8nQ^%mVo{1=;#FDx)s(^*~Y?oj;*FPadJNXHDndtnkbyB zl~IT7gPh~J`mCUv$Sw7R#DYzs+)*e_7Uz@Jh?6N(y1fA61jJ1^PRN%lZR5 z%a2sxoWp+AoWk(Cd`5YeBc5DYg%PLQ5xG}K{5xj~V_e@x2>*Jt!IXRT_BZtx+zT-6 zv@EgNw7;m{7Sr#d@>|V#Ttl~-adxW{XvTlON1!<_$aTEX*F3V~*lQ72B)K|EhLq${WSm<|Ce_WD_Y3Jwis;2#kcdMIzCvB~1 z#uH||pQdpZy;<9gKPHc>IWEX`ywKM?z>ekz_BC(ttNBDcnrFnR`A7UZFT365(wdBY zdAuotjCU`;^u4hj*SzNoQnE=Xgz_ z2nXT1-jnH2W0}+8O(s*fNiwI9r{6Dg3jNS%nMc?;Rb3eNyZgwT!tcox!icBtLYZI0 z*}u9l;txwHjBz=}%3OE8GtZQt=w$pqG+96L%0ko5&U}ka`%yK#O~3Do`IzynzG{5$ zlN_h5+7dH<#|}%(aY3%*g}&wib~Hb*uX%%C%_ri~JR?rcKjPPUX&JkYS`L;mZZ!5^ zYdQ(L-C0fP%LwP}xr$tF$=KWESxI|43+FK2pUH7ej`QqUmQ!$P;a)wK(b^$$Y}ZX# zN&|vA@-Yy0Zz<(`)`1yvTW(?K&u`<&a@ZNQ+JhPPbH%$e!|&fcg%QuEXt}3FoP}2l zBmRZGgfXtLw!%p>*PHTgnKzpH^CtP5cA8%fFzqjh++_M)aC@^EPp!#DecVmJep_3srg6zIxjEXwo;ZWZ8#^@f;LmfBf@uz zZ=#Dcg}3eXr#L6!*T(n4!;i{yfWU?u=yrMGt)17?u$gi{pAhUvovzCL{JqA0R6f1% zU`Ic?W0k!*h9mI2>x$FfH=aVn8k4F5> zPYYvQtAd4>+zB-0pE_+f^^05$GVMIix6`y=tmZD$Z?WRL&3LX~-EGDhS8b0Oe}@ix z%yB`kqiS!qE#a(d|sadj?;m%9G^YW6#VBbSqTuJyJe6Pqre$PlleS1s&zyV|4TL zRK-W`Js^K{t{VG={*IKwu(P76+oU0qWc@#H@%_y35q{t#irA6!cq;v%X)f8Gq2pSaV#E>v*BBd4L_w z5A18+;8*jBcr?$5Q}d7bbzWXv{z7Am$zG;v_0M!Ri}3ATM$e9ivVRG*exy#x`9%A@|KliP5p6xai$&D zsE?-o@fkjue#d|OL>f=o^`Ff+o2UC?#=pP(7js;Y>v*BBd4L_w5A18+;8*jBcr?$5 zQ}d7bbzbT<{7kK%%X`;LgX8Hf3A>d2NaxxKr#&1?dAG|u+kXst%X6jG8 zonYFjQ#8@EKiMtG^gFrC4>O*McYc_0wzB**;}7X(oIAxXntT{^9H|~ zPsF2nMx2^|#IN%bpE4x{l#)C+?M<|~{wBQH`?D?YYRN<5^%z_K4>I=HwNbYIsf9lm zd1EX8`Z?z(e*6nt-&N0;Emxn~tYx1v?=JJi7QW#zbJjJFZ516Jnexe_ADa4wqQjVB z=i{XN%&`BvODHq^#%90AjCf*=m-+DA7;)C0bcY%77s(}zafQU*W_ha$sY&IzEa^z~ z`xnYcYA5<&CQ|!@K4l^GJNSGy(s(Ww&OsVy*4P}R@jtDelXP5=>v*BBd4L_w5A18+ z;8*jBcr?$5Q}d7bbzaa@xLUnjJgyznKU1IY^37V4@9|W$tZ)(IJBu?n<(sum);K!z zGb`&CDiTW#Pi7Xb7DFdX%lC0Z=0(%MM(J7pXR&D7S}hIp%cKv~ER%e52YL88`7RIo zZ8yuedxZ=;+g`@;w{NiT7yOGF|Rih7Gvi`Eo#&;{pc0A&eO#92T{WSfqNcd^S(_qUlGtR2%QXJR#Bl4v%dnH4z z$o#JQ3ffd>vB~Ra zdYd}i&-yUCdoL%4FH4xi-Y=txS(h?r`L={U#ZO>9am#p5J8(F2@l=ax^Q;lfzQ()y z8!nGzo|W5&`VAVzJm8HFwd^{E`R&{#fc1{ z_cQ9`M;0B%I@d?epv?7#GJlymlWqpfZ^M_*q5&g>Tko7r_2vj4OdLnYON?jz&DBR! z^#U`QFPt;p{eC#zWas76Or28gr!vRo8bh-iPiB7KVJvOVHIaF0gUNKasN^JTlbKYq zk<3@7dNYjg*JK`pn@y)TeT63tm_|cSui)SQy=5x(`LUci;nx(ZQdrn0aWdU6E%T-Q z)0;ZwJ+8gB!P-k5ti9C1+Djd*z0|?lOC7Ae)WOR|1q4%S}kVC|(2)?Vsh?WL}a|9OG6mpWK`se^kY_fiLIFLki?PX}xN zbg*Y}>7NeP{^?-tpAOdk>0s@j4%YtZVC|m{*8b@#NB?ovM_+QV_D=_E|8%hSPX}xN zbTHyX|8%hSPX}xNbg=eM2W$Uyu=Y;}YyWhx_D=_E|8%hSPX}xNbg=eMS2_Bpt3LXt zgSCG;So^1gwSPKT`=^7oe>zzEr-QYBI#~OsgSCG;So^1gwSPJo{msz_9E`r_=noFo z{^?-tpAOdk=_*J6an(m(axmxcU(LWum{nNqPKOL<7)4_-z{nNqPKOL<7)4|$5 z9jyJ+!A5^0s@j4%YtZDo6ix)kptyu=Y;}YyWgG{I)gv(Sx;r zI#~OsgSCG;8298=Q+{OqZI!;zQ=`@v z*?>rv!|(cYZn5jWg}1 zG5VRR-|EL>&3M*#iY1NHS~S*-|82%tb6k+?c%iR(fE~>b>}%fOSM!N@G|z}r^N;v- zUa*E&`aQ;i9Da2ALer-TuWj*}(v65^dByRcjJgeR%sG$6Q$Ws7%!TvB)A+zI%q@IA z(z8to%!iDgs%zttnA^q0(L~o2oX=m6;`rVbz97%{I2FsGe||$6X4u)(C>=BGhn`K( z48NzdWMoD>UIiSO5vR{nVZ{HJXC{_oTtB7?pZxXJl;?eJ^ovi{pM4;~w6kI4chmmz ze2J#tUh5Ohc#={inQ?ZpCYkZ?Ym;P-3vwMV^feE#qxpe-%^Un`J`s=R8F6a<5x>q0 z_E57MKIbu>y8RouxCjqjo|iEvYYNWF*5u#;lQ17_HNvpb9#eq%ET zBc9?j@3S0n&MPjA_{+WyWjV%m=ce$VJ$~9$9{uRMP4%mIf3>NdYrdasYX9@kIGg%C z91&yFcsg{6wrQMq2Y#?={8I~j;5{$K1-XtF`kDvW(fq)^<_&%|pNL2Ej5sy_h+pRg z|0DL8-i7Z~s%0-j(-#WQX<3T)1qlZQmZYEI!lTQTpf^Rjvi^dn#mH;8@cTPODf*@` zWhqKqYIkFu@5_r&>m93Jej3{lII&@LR(8MgYG> zJQ;fmBTn~a!iayi@$CR~Fs{8e;amI4oAN26Dw_IT3OSi}eAfJK+MoE!+4Nf=*2Rpc z*}=+YoSB@enDHNSuVRi1avd-9H4m_(`GI}S8~kcM5s&5>acce%zs?K#!uz}_#>XW3 z#dptGoEd%OL;e;d?FsrGvd_zBYvG1JhRQ;KLa0=_shJe1|x;1Gf@GKx-~7XG?F zlD4JE$oeU>MjCZOge%W`OM60u*OY!seTzG=POYd2%Hb>g>Rtptv&Hcb`MB|!SO@y0 z-U-9bqjs51`~43H!|$uKSy+yEt~3=!oOve*BmO3h^19ruj zc4iKWHSLej9!Ki8>B=}Wp63a1W}Nk_e>CG?+3ce^F35Gf(APY`j^+pUHE-~%`9wUL zXT+)bNBlZ3_@79&FC{n+6JC5K*Ayk09aDa$fklK5Rr*9Bt%TPZwNp0u3U9sikqW#P zzTe;@ZT-WMe_Q8y9Ch6-{A6<+Whh#T<@0>v_Jtcb*Hwe)oE1 zSO~h-T&2;`!D-u>SyhjVA?5H=DTUX=+*D0 z-{>}pW<0YGB$CD%5u0enZ%LD6jtg=fFZ4AJu%r2bea##EYCaK<<{5En{t>^<3*Jeq zo2m+rH_be68jx9dci>`LTS2(a-9;49S-4d0MRa|G@bAMGQqzyZ-J=#zXq&2R=i;0N zwCI>{-#-^nt%}uHo}ejsu*F|_i0&!b>KInzcAwY_)-{g zy5+9PI*5O06=95PwN?0z@ve@_%e(rT`m3`nHSO%Xw$!x0ZNxIu@0f4P%y_bPT2310 zu$4xC;pF(w?O1M(3vwMV^feE#qxpe-%^Un`J`s=R8F6a<5x>q0{->WVUUEKb@^y0g zA?)OL&8X!fIX`jfD(!AAyfx!hTJ9|z-1`b;dm;Sn>1Fb(C-c&D(q(G5LpY-DWlB*< z^6y*mGXGB>^96a|)RJ@P=Nu&rJC~mb!@h@`=4%7dJ5nfm!t-!|=3Hr@eN`(^vxG5vo1aL0_tyY*c&&e(-_&G;Mo-!;bt zxsDh5ng`g?{J_5E4SqGBh)45`I5q!>U*`qy=%(#ifyW!w&5v9L3;Rx9M_vnr9e1py zT}F)vN}HMIPfaIVH{C|lc#EN^&fHLcq#ysPVKYFDrl%bS;2O}`chf6cs_-_eB~ z$ou^5#5&N=@md&mF17rf<*@I*TNr+CrEq3B;yKbl7;&Z^C5-s1EfvPNy88(qcHUsh zv*y@n>Q8#T(X_L2v%hJ7QPTj^Z|55UW;~x|q88tU{ayr6 zHS3?OA7~ArU~l2D5P!172-j_Iyu;?%oOPb&^QR4$gy*OB=XabiUy!HW*MfDRzpq3~ zX4vV!P#E^Vyc34s;cl&12k~^6CX6^Y?-NG+_ihSfTq(kZo0SPP<^JinnflotZ8PnZ zTf5z~U$kzJ={M$FkQvYHvOCN;-}c&J#%~?B!yFgnI$r2&9$-iF1N)jc_|<$O9?di2 z)chlUofo|GS^1glj~W~Aa(9jrj{SQ!ElMx@qiO!L=s_*velKRy$%(=vtTV~=hVZ74 z8FbM}_DT-zXVBDD!a@0FP=yS#4{Dcs2EX%(`GVXxPUO&c>(P_v0(L%M5r+Ng6?(B8 zet%37Mm(=h3L{SEkHU!GD_d{Y$G8?05YAm@o+%%ce!i(69zNf+^J&cj(|%N)g{I%5 z=N6jrv?;sDjB~%ygGS>|KW>pZF35Gf(APY`j^+pUHE-~%`9wULXT+)bNBlZ3#=gPa ze;NA*^FH6$H<YXVowExf&1lzZxg@#Tq~M%Q`N|b-d8mJiw0T2lh2@@T>VmJep_3 zsrg6zIxjC?{j}}#ZNg)3v@g-Nb*=FHRo`ruL&BH$e70?QE*z94-sWAXDeJGj6l-(o zE!_BHw5|OS;a@90*aqj3>s_1E?`>Pg3GW;K-iB}PupUC*ypde*pg&`~Fzl>NE7v>N zKhaSbe!VscBcA3@lCOzIoCh<=brA74a}>t7+$ss5a7aliU%%=%QvDy9Qj^+Q+$9aE z{oGU2lKMR{Fdb<;J@cn0jq~V?^rZ363rx@75@KAC>v*BBd4L_w5A18+;8*jBcr?$5 zQ}d7bbzble{G0k7oWqE8>nK|bVV}}#sop^0;(x87MeBsqFI!Ecj2ah+El12Migod1 zZqR=fOm28RuVl0?hcgl@Bn-1-XtF`kDvW(fq)^<_&%|pNL2Ej5sy_h+pRg@8~+@ zlY8lF^oFXH5FY*LHT9`0oG!y_+BaM{y6G!geL(oz=9iQ!-S3>Yaz$T~e;?r`wio1i zQ`mXx3rby2?yJKGzTkIsF<+1mEa$?%g?`>O!mx8aRb`gLey5(o@Edwi81c|IVZ@oC zyzChff9)p17+0^h!fO}5HRT_NMw6h*R^A_;p^oXLYC29&*0a%iWIBT7-vX zYfJa53ir?4n$Fh~_RrUnru7i6?ADy>t`J^2uNj>T7jBoPDY++~ccDicQ}i-9*KSX$ zOC?IlIg)Wm9g18joO_2GWzQw&!k1cZ)PIHW(!y@Erl9;^V7t2;)!Zn2{G}T`C?@|4 z=vAUF-MK3FsHKg%;u~Mf{cY~>I&}S)=w!@Vmxi~N`_;sjb*a)F;dRf9I^=ES9<}Mo zdi3j}aG$sJDY}~6qb_Lk2i;ySyyIg-`s0mo`%{gnekr*xjo;gpYP1n9+`YX~vt8Jw zo)-nW$UUmF(_lJWOn5}~q4dK+xKM@Rl=7wMZ~ZlbE^QTVyX|iZ^Aw&^U^JCT6u*&1 zZK7Y^!q01rrNRY-=iVDjBi2d$k;TVR@dCnG3eKZOfs)Vt_2Lxk zp3#00H9qCe>qCCyeYUF|+A|-VIG6nL3Qt%#hejJU2e8gqj9v^gE(>Q}Jc~x360Wjv zCe67j{L*IzjeM6Z513A43yYnIbJM7&mvDx#F647sVu-oi+gRI$y$%ni+rh$jhmE3K z$>-qLa}&vHu*CT*`y;xyp(MxSxG|g@ayc>w{}oOxerfirCT|+v*y?{Dz`~^>-Og~;FECK z;1~4n_wuY$|H4ap^_TFTW7T@02u8+3d}ZpQZxn4^64-_fQeG8WsASn}Ck zjO9@;qbX1Q;>^xVK2W^`;kYU9Dd|!PmY)fEN0WC;Ze85o(Xfq@&oz18QPI_s!^Xz@ z2ID-$=7OX+vV1Pezdh*tkp|Ba4*e~jzGW0n(JY>F%qzk=?fS%1$yCC*J>qHS#KJ5O zDr9`?kx+4noziKA)(1zBgq@EGdiCVPkcQPET?dGAngdo)cq z>dYe#bAqFd+ROQvOQ(pTp;P7lKX7>r*&55e{eI*B7sGxDPq-LE&yMG2{al}8C`)bO zI$vU_+x}cE|9r*p>m=NIObkuios;GBz8f*r5PszuP5rOrVEMWgAE@XM;fsgg(~;uB z)z7`7>Tk2NPUF*2l>dzI(y~#saIf&1PEqtAMEJhZFJnIm2N#c|h&94-d5pe+tA(Aj zMi}+jg{v6f4K)oFo>KBP-OeF?otwX+C0@e&7d)kELu4$Y?meNrmxbS0pHNa|8T-DA zkE!!k;hke2)1cy#^K-2pQx$*VgqDwKO$o_)i_wp1T7dA4vybUUVafl*JCA8(s2p#3 zQ$M9*v2tweUiXyheUoEg=jx}l`Mb<-sl+Ene_NTCbt_sK@4X!4|6>~O(2?KpHJF~g4Wju$iR8}EKG!>{p97&GEA-W6j;oW?t6%!uE3=ZqQS zGTu33Hr}B#<;FX7rhZwMcBY*p)7qQ%>uz>8{YH6vnDH#OdXmQZI?$6e{sUJ$&2d4l zhD>`8U23djEN zqUDo>gN*(}1)mEye&3C*b=t)GwM%uQ*hpa?U!!-)9C>%{M9r>r&1nnkOfArrwuK8r zK4Y%Dj|crC&Vi<#?$?B2e@3TmEQjA}p~8sAR%<)U5ofj;!iYa%k1)oS|AcT}*S@B_ z`TTyS{;jk9O*?s?4>0Xd2pwqpo$EJekz z_BC(ttNBDcnrFnR`A7UZFCD{-Z=$nz<*`qxu!S!DF8pf7W?DN>IN;4D`lC=c(ed0w zZC(mrdmKOq!@9G)@%R8r{N%;_(K&#o{@#;0Lux~3axdnnPyRG8thXsIQMs?F?=h_( zGweJ%)}I;nON0$zo?`f&b!{Ls;_+QJh#7HO$_y4ABmT_OgfXt>8-%OP+G@&gRtz-t zb6gHI?NsyJX4;Rqz0LGHr22LQMjtg=fFZ4AJu%r2bea##E zYCaK<<{5En{t>^!SRAMzP1`TcFg-*uy0-!ZPAlZDqk&u7Y; zY%gN!`{#Bv?Tk(;OKN{xjY_0`TWobEjc0$QDx`5%I$D)9{@^;*NXG@aju-lx2iVd4 zz`o`Uel?$nNArw0HUEfT=SAxSy3l8-Z)t6jf1t`I9ThAgSFl`SnG|0wca>b>y3l8-Z)rmjDxktI9O|pgSEyuSZj=f zwZ=GDYm9@n#yD8(zJj&xD_HBkg0=1|SnIxmweBleYsrGO1}s=>z=E{~ELdy6g0%)L zSZlz7wFWF$YrujBC)a=lYYkYi)_?_T4Op<&fCXy}Sg_WB1#1mhu-1SDYYkYi)_?_T z4Op<&fCXy}Sg_WBWlpXE3)UL2V66cQ)*7&2tpN+x8n9rk0Snd|uwbnL3)UL2V66cQ z)*7&2tpN+x8n9rk0Snd|uwbnL3)UL2V66cQ)*7&2tpN+x8n9rk0Snd|uwbnL3)UL2 zV66cQ)*7&2tpN+x8n9rk0Snd|uwbnL3)UL2V66cQ)*7&2tpN+x8n9rk0Snd|uwbnL z3)UL2V66cQ)*7&2tpN+x8n9rk0Snd|uwbnL3)UL2V66cQ)*7&2tpN+x8n9rk0Snd| zuwbnL3)UL2V66cQ)*7&2tpN+x8n9rk0Snd|uwbnL3)UL2V66cQ)*7&2tpN+x8n9rk z0Snd|uwbnL%lgSRV8L1g7OXYc!CDU%to2~QS`QYi^lk35PwH_>3>%oGxRyYsG`LRyYsG`LRy^w`*NO*gt$483iU(`0c(B%r2Wzc(u-1wP zYpr;&)`|yft$483iU(`0c(B%r2Wzc(=Hy!OV67Do)>`pktrZW}TJd156%W>0@nEeL z57t`oV67Do)>`pktrZW}TJd156%W>0@nEeL57t`oV67Do)>`pktrZW}TJd156%W>0 z@nEe>4A#2DV696G*1E)CtxF8ny2N0uOAOY!#9*yU4A#2DDo0&n)kj@ou+}98Yh7Zn z)+GjOU1G4-B?fCk@;tE-_f^5`(oaF<9#o zgS9R(SnCplwJtGO>k@;tE-_f^6000_iB%tUiNRWz7_4=P!CIFXtaXXOT9+8Cb&0_v z`uot(WAe=NLRW9fS5%&J{_MBdsLLVT*n1I`=_AiPQ-m#~A9dt8=d30R=}9$twwdAe z0$N>Ho?DI#UO--+LHw-j^tzc8bS74wo2{BjYoEwBxi!zuB&RR(4R279S=8#cPpngO z%PewB6#n_wY`XH`Gs|O2&7oNEd+q*et#__nAQxhDkiLp3R_6?POj$R-Q@Yo9^JTTqavx$p2sRzvx1-Jq~fq zbv}2ZzN15!2Oa7_7rP#2o?6v|vgJ9#TwrQDn!HlD%#Jp6?5Xg8i!JHRd*L5l8c=~h zZLI(O?H`oV=NNO%t&M0?{847tg-xjaIN=>W&1hdq;knzI)1pse=V*9AYX9jL>!)9q zj~-uwR-Q@ezOMmC1^yTldzNJ=vdY|GhbBnG8Xz=^n%%>{m zCoh+W%$bJgr!Ic-ZS41M`6(=;d`r8?u_zrI^^$caw<%0Rx4dB9d$}N`-us-n%-RCf zX@h*9JLF1!sxVf*&+YD&pUyRq?{m{Nbf=%?zp;Mq++LKhD1q7iYFApiQ8;O4XL6h+ zJfuZOqgIdbo+_S{`l9^y^OsKK^DB{md;O3Hox1ar`SI{}v@kIRuU*<#9p~WYiLL4H zs2{9zKdue6yej%T3;so`FaBcrrH_BnqCxUo?Vpa{YX5X_hpf^+9jyJ+!P-9^to_r$ z+CLqv{nNqPKOL<7)4_OVh5qSa?Vk?T{^?-tpAOdk>0s@j4%YtZVC|m{hJEx;2W$Uy zu=Y;}YyWhx_D=_E|8%hSPX}xNbg=eM2W$Uyu=Y;}YyWhx_D=_E|8%hSPX}xNbg=eM z2W$Uyu=Y;}YyWhx_D=_E|8(%H>hAQ=l7;h7b$kcfyu^X|=*$k3-!T(&hbkSY+(F@7 zb3MteUS^h;n&UyQ&I!P*BFtbJg?yOMi(gSD48SbKScwU;-` z?@BLku=er>YcFrG_VNa6FK@8+@&;=!Z?N|A25T>Gu=er>YcFrG_VNa6FK@8+@&;=! zZ?N|A25T>Gu=er>YcFrG_VNa6FK@8+@&;=!Z?N|A25T>Gu=er>YcFrG_VNaYCin6N zYcFrG_VNa6FK@8+@&;=!Z?N|A25T>Gu=er>YcFrG_VNa6FK@8+@&;=!Z?N|A25T>G zu=er>YcFrG_VQ+(QP$WiJI{FA?8c`;8S{YSguon zm0!@26>=S1Tk8d7uPAeLI@=4%d{VgVk>~WJrCbxURC`X3?h1#^c}B}xik%|mU(l>T znXd*TUr@edGDmR^FR62w%u8_0OZuEfI5h8T%G^xm`p|?oR3a!H=PDxGTY6Pqc)^uO z%5*a=%XhDTNA=eU2Tc4xnU)Cm_lP0dEnKvC9F6`Y+|Q_YT6bwG{_T~tiR4;7HS;R^ zPPIw+M8ogYu}K=14+u!0mVG8H;=+h$V_~^RJ=5(IMSPX};cH7iQ_Zq+pX?X%g%-^h&VA`C zIT!lQ_mkU>f1?5qgcmPKpqw_jfBxk9ox+YMv5w=B?^OSx+$RU6Nu)_><=%LdQDd{! zUh!4yTr4ed6rNZhhTgW5J#v<1AE;ns**izHi=gbu``<2u-Wu=n$sV@q9OGTkox&08 zqv&|3aJpUZXnA?rQ+L_%p4x5|-eUBBymCPDA9-LY<#m_b<}!LT#6Fe$7puISZj2R< zD!PK|loVcCY9)1fF26l9b}6~|3SZprON}3-SUL%tEH)|vf92mvi$s8H9FyOkO1Y69`>td8?(hxtvfEnb=M6T| z9S@1k`^OGSxF@{wYY=tnEAfOp-cAu$g=>Utqr_A)#(fI{$;m|Z@jJE-ruLnLZ#~#cf!&3#b>2@!whJG^ZYN*^{H;Jp35{s^7kCC@j) z@*JVj0rLDLhwU)M&XngTRecVVcV~Hi;K=|g$X!7hN{C&d*Iu$N`tc_(-iG8e@6MO$(zHYQ>%D>I_+*nK9U71rSe4*VHEX?(jzETcPD|5bA-zeaY z8}q!N1X{AJF7v2n->I>8eP-K<@3iaCAI$FQ5@~KyBj*02KarzbZDyac@pN`iP3GJw zKhpF=)tQH;kE77;Rhg+_EImHq!t8rIhMv4}V$NRSHI2+&n)z$JH}o=3Ddtc8BdF3C zN9J_KnzO04aO~AcitHiW|7#RQL<@J%@t*EJl;1k%`9Q6UmEqssO#DEL4wYrjOwr`+ zTb_AGyBHc9SdqDdXE1HBdNE&$*h%hD{h1H9*hPIW_hsJpXcry3*_*lelHIf_Loeo& zMz2zbsXdr`&Du$ki36EOCG8-GsKLzHTkoKi+lMk2o*6`AoQE^J_-&^Lqed{#*tm`Q zj2Our?z)+r%1>tgv3N60eK3LfMD{IIcjq`}?~_|-!`?B>J63F^0bfTkyDko-J@fu% zjvF07&tgRGmuDkQ^c=$SBIW#O&Jr0{>XWN!`xzO#TltOjeO71IN!M-zeXrA%xqIjJ zGov9*OyTn(i7UBavW+(k*A?yUd1!A=^{T;vlg8hL&v zTqaWxeQ*~0uOhcm??S?^10tw({oMT9j^QuKcz(pS5WO?Krnt^hJ8^EcHMeE1^qsl2OC-5B`oX+5I+8ZcOu;r|rbW>Tzu%buiio1QPg65H6naNb zYo}ulD)NrpH)LQg5))W7djdL)&^?Pf4!Wb@|625ScoF7$8){MMRfU)zeW^v$Iu&3pw6!*QRLRGDcAG0DRm{V@>YIh)+vQ@O zxX6wC4@t}yX1kL0lAMnx5?txVAUOx)(;EFu^H*T~V#fDzC#%U?ael8G)%K9J!fm9L zPP`sPW!@&7LejFwvb3t(W6DX^{slC@07K+uu6S&B#uy<8iAaRfv&e z`0)GA)U~l3S3Mhbqv#*vcizT^WH~H$Vy`!*3^j#&WNb#Svk3QU*qkm|g~yF(NvqEY zk2iX=R`io|=k<`bT-=EE#Bt%&fH3AJc{ zWwAN=Xmx6RQO44!epMt#8qo`R7+B>b6s^WsY?mDRU0-l}IJ2&P%!O z7{@Xh$2993=K&e#1G8}ql5s3D8^jP5$T%lW{cmF~GAFjmN%gv4 zW1cZSJEg95o%y|2R+{lf_;c>e6xj0y%ijcMq|-Zve=DD!cApSVvnLHbT`RnzX)5Yo zU-*det@@pVV#hbrPn+j=@fG9q-8MY8@X_O6ZTB-@W&7oJe6}@tcbPe?_a|G6LzkE* zJJzPAc@8r-xM9@d{(T?wuQ)4ZuCt%n{hXDYS{`7wHnUPCkAuu@XIQ9LyF<*k|8}Ke zbwil523jfiR=H1mpT>XlyZ6^nZOK@Q)x zvretoji^H*;fn{F(zyw8pSdZxIi)WsTqlz!t>`ZI%!NyNP`;j<`L~`Q+f>TbR>M zXh#)F$^GiJ3vH?6L*c_OTGQk~fvl4d+LCI73EvI%q=2yjEDwL&fx2zv`P(orYV~yu^UxVyRH*Da=FrRC=|~INJ2)QbMrFFMXZgoQ zT`9_A19P>Z{b&J zVEf;K^|xUCE!e32Ys2xcjB`gBa>N52$idFJ3(&O{VgF$0Zwo0vC38Mxd8-r!spE=p z=F-sxs9eFv|6qH4urz{_NA)Zzm_xXsYaGOuG;`%?? zULUOb;D#9{QnBeBt@-NYHW~8Cvpdq49}`%9#^ymO&rfHLTi98t z8n%(T4qwfD?Nb1CEWMmL=-_5bJ=upje#;gLU$cNYZ`AtDj`sU=#{Oqhd#Xg?T zeB`J*?VU24dHW9!DqU$hv)aLNGHFUTYLH`<_3Rwu`S!T(l=jXlYtjJY|6Ikq=v0f< zRbLxnxf_r1c7v5vWp-B{qcXaI8y1PpF)~+7Z#LnSfooMqQ zIq%Mo=|IjMI+Zul?K8#rC~f-v4}i+L^f@ z^W3h+efYrv%s+d3P-yMJ%sLi~E8~tnM$d@$JoYA;`_scW!q>YDq;v};S3A82)1jG? zPu0gUP-$*&idos-+Hs*#YjH>~+8Nm1nrou*Klg4uDfXhlJ&o@pe0xx?==Rn@&5ZxI z+U+U++k1yB2ijBI(7x8KUU`o{e$k#jAMahFKBy-l#%1glN3+61djaQ75xT{GS-||Q2SGStjQ`5xw+hw z+q3GYF#eQbM|B_vs~zZo|E;gT{kQyoXXoEG?d>bu>!?lp7>qFxY?o(K-`4 zj*l5^v6Cx9ZiAg1v;(+T)Wf9jrdK^wUnz#9B#~<#l~*+pZla*KvuK zBMp3Pok|_2mUX^cb~N&_Sr-wxE&pa|-_*zUAp_B`IbSUPfBM)4Y_QR+GM_AyTlm^RGlmOi#8#cXu-aJ1#%zhbbDneGxbTbA9L{#J;sPd`W(zNNFa{t{wqRPX>Ld`@Lun-pT}n`1wPI{dO& zQy#WC58Fq7toUrnmHM#lh4C-hT=`R5>y7fWT@F7+_rIsK`cC$<#YfwyU6+j3zJWou znbnSxZ|5JDFSGn?$77Dr)K=-N_YMTv`jkFG6*7Ic9GLHCd$Bl#&Mx}RI_X4^?OVD- zw6jQprQP`;+ohEkIiEK-hWy9e9$I*j^PDB0kFCw7P@anyULm$DhpsaBPvc{Iy5%b8 zYOldJMqT9`&Q0rMYggtf=k{$nAKOja70&s&3_iB0wXX17>*0Ty=jd1#A6xE( zOFVbGvisN$HoU}hdMlTY%{~VEnD-6}&$hnNEzWcO=0P^glgm7JZCw3qr(a*^ zd5LllvMqXZh3C$*R}kkD$2{`+pK^;lLkD@za3hrY^@(!y^QCb0imjM&j)3j$fYpA? z1>p)g3LF2Q52ZmR*IU4_35HGk-@?Ay{BP&keojY+$uYU>&sNlJm&|XlF|M)>p*+8Z zoLW)S-|q4J4t8!u*Vf4V`c`R08=uPjj;zs&YCnpOf>mWDRWFwG}-HmbIdl5p%A;WDR*a zp%s1VBx{TBxK=dmjI23>N4Fxs$+8wL9MOt?n<{HmmLaVu{b5piv;-lr%TRpl&Jh9e1rIHz)43_5XU3`FZ>O zw#FS!FuQj=Wc&7lm_tS!HTp%%{Z-j1Cv0a{A7gnh&vUk|VMm#xZ(gzW=pj7p&~4k| z+QN~ajul+xMucB zNmc8d=XfAr{_O%Y^g~u$Vuqb`ndO*){gSQaIDubRcR5ZFk7r&vP7vq1MZ$=G*g;{8 zOXV1^>LU+o2l-L^$ea2_J~bZXS>r_hHGa$st|^$)Rk{c+=TkwPL#=DNjy|K%~L`%W<5BZ*L*xu~c!c`vfeN>Y@*{w9? z0pDM_?8)~Rjo^Zi@!*6h|asqXWA z-Fd^;=i8xtzgOd5G1$jEWquf6N48u^v=pus%J*0EDAAJd^BunLY95?u*&i?0>-L)y zEpuz$oDjE;e;bvJ~zY!Mr;( zyY+)d1m|j!!H>&Ca1NvIWw-Wt@P>1n+Tf={-f+&(-^p(EdH0&I9Ol&8OeDb-_XIDcKQd-Vbx=)t?RZ#@Vt1}b+8sre8+j-dMLGZ){@secb#iH zSnIEe<(Y5;9cdWClW_gn< z#ih5tb$-fnV?D9%@Bf(DSWm2NgTtAP^~CC&;~}%Lo>-o*4P!Re6U$l8`^?6AV%gbN z&O2j0v3M_$Yk{$zSpF<1Y^*1iG4XO;FxC@OZmcJ!zOkN|c8vAJv~R2@re9+{v1mNT zdScNyjrGK$@f+)jMaN~V|CYkvo^hOzPu}~28TuPry<&!)m~*e0VLwv_$tV0eW_`KFOcc#vm}6ZzNpF)xmL;@EGC z<`rDQSl__*=NA~U;aszq+w1?gkAM4fZPO-MD-w258^5Q#>%|~B?;dt8@7im-oOdOElymJiT+Tb|(sHgpa=zj7u6v1c zuJ*?~82Q2RZ+~9cufz7SeQh1iYufQ*WnAsoH2bmG%kB05+v~Y~%=Y8TJyF*D)e9Y6 zn-{sx>)8DuN7o8vZtyx*>ye}D*2Qw|a4TBM^>)+SypBB{UdpxlpLcm3TXw6ItLqH8 z290+u?dtbTu1y|0OS{^y)%NSm|Kz&;f9iT|e=lKwPT8M>wiU5_u3hc+%c7h%pPY|+ z4yqhF_UGe&%B`-|Sf9ao{s4v@@V|Yj9DeO%vp?Ve+vnYXI*&wXxY(~U)&@iFu>5Z?M{A{}cbTsiDsF9>bdPyivm#c% z_4k=iq$p$^Irsr{{x$`ywvOS1M`UR_B zu=)k7U$FWG!>?1&YcmG0$`PAAYn*yM?i`uP8goO=&F$;6SVQLsUp}18S~!RB{=GS@ zo+F~ze%A51tlf7-GXF}I$6EQ)Tju!<@>=O?1ap#8KI^U%ZjKQAmbxhW^3u~Y~|NDHj%RkwTo$PW#cDW+E z9Fkpb$u8$)Hy30#M;tTe(a0g$%{BW?9y|L@&I$Vk8@Xb?U?Yd@7i{E~{eq30vtO_= z7wi{o%#nSrj9T*MG0zMgBhUYc$37=dn(X1@!M6k1z|gm6Jd;r!dxp+QH~DR@1;=cM ziV1JNe8jdrW;fe>Uh1$d&o1HR+Yi~&bP{giblZDkO~a;;*fe2b>qRy9(pHu#XLX5u5r2t6#AC z1*>1M`UR_Bu=)k7U$FWGC$9q>bMiT8#$X?heNK!ukoECfV{KuEO=HbrhA(3+Vnz(c z8pVv*jJ1myF&k?dGsa@9b<7x}u?8|@?8Z94jM(5;V}@TH3;crBFIfG8)h}56g4Hir z{esmmSp6oinONI327Bh%l6CB3#^FHV>=$f|k^O?zFIfG8)h}56g4Hir{eq2Sz-l~2<9Li* zF+&cvkH>Bvtw}$xu|9s=Ag`=lu-U1bFnr~@CyW>#{w-?}V!K^S)*Qr~qKKSF7|W;v za;{;Fv&zW%Xw2h3VuN3e8Gdyv@C#PIVD$@DzhLzXR=;5N3s%2i6yUCc?%V zYdI5kh2_TDYbn`V*tmB5BR2R&{OT91e!=P&tbW1j7p#84>KCkj!R+_*9!kC*S&|G^ zIbySCdmZI<{e$_puzC1_FnmSU-^+5ukmN6n*s^>QM$8+l%l|GhmR)^?F~*Qt!WjEK zZ(*J#>1HEGe8jSpT?u+IlAVh^2pq4%YIKXRN0u9ktwC z@xR!6_pn{ZYW<%@;oF8Htq`J8NH%3RpBu?8R@AbPO{AjTQpzS_**3$>B!tL5LiVLF z=e&tfHm%f>C7TMR(n=+fmX+`Gx#sg3&i7sK`~4lq?~e}0H2*t~ah%T>=NQ*@jd8!v zdq4O6o^FRHZtVW;_L+mP-@9FR{%>yTZaKam%({Qu?&6s@cX!`#-QfIlx9Jwz{kz?H zTih^sVx52Kj(zC6-2tzjQU|J;3i)$esjF8;m2Jpc2q?%kVzulvGEw+;U5?OQeb z$s7Fp;O=SfZ2WV(9}ZUh*%r;u{x7<7@ZdW)Z~iy^;$4H)9@?zM-S)=22TOfz)28Q~ zY4;3XfAJAm_ZuAaK-Y3#;O(Co{AxzmYVv~n_aAJvS=VZH!2bU>SatfK z)o|M3hYZ#|c1o-5m%ee>;C0)s+iJf1VCrD+->%)(V#@zHa8OrgQ0A&lr5}oE4k?rA|I`@Vhs!*w*f~_nkS|cA*v9 z+G(dI@~M@6sG?aT|i`NFpj__03tw{FC>p6Id8=(PT2=rv}cQ+BkP==G>VJ=gu6ln>&1Kf*)&ze``owYl|Lhj!xGC z{jL#t&53Kb&L&^4KDp$_zftFL-sxA?IbH44Z`S!eX!^J6Tpzy6RdwEfzR=ax2X;T= z>go?0-+6WQjW;}cb@dbM_8Iv0AN<&t@Nd5&u6+zW_BV9e_t0-YBrp5qwo6}8_D?=@ zS@GZY*rny?@xNVC{vTcWl8Sr$VHcO47r)@*(z){07nS~ZoN-a*h21_0-#&>S`y~GD zlf<=8qQ^doPWvSK?UT7)VEZJwd)BClXN_8U)~KOpjoNzFsJUm2weYO5MxHg+&a;Ny zvj*R@h9A!w{yl5N^{k=CvxZL38u~qJ~%66uVdjPPEKO4b>S!Wv*{BoN6fV`SZ(0+ub=V$@xx~)%O&+M^2j+gFCKf@xz(5M zUiG}{R|~H9)#_v0tag6&w;krYp!(ibmt0W&uv_WE>XS?DcVYFU&U^}g>N6mkNp|{_HE+Y&(UL_N2mQC z{mupQa$bYv&gmzt}GwNNK(q<+@Uys(=ueCvQ8>w|ymMqKNO9_x%w z>yLidCD$wQ+_jrMFP_V5ckn$IRPP1blh1nUv@zKJ49ETqCvkET+yCJw_Os~|EJsYw z2dfR7{`E87zw=_UTvGq9rk_yr;?{3|vHH?wcb-`N>Sqs}RDEpaAD>+PZME~iRDJK5 zcb`)IaIqhpQhoCAB~PvXdDmM{t-gxgc>&*ffgk4u{+$=ZbzY#yd4W#n1^S&AG%XvZW+Np_rYNa1)sDEl}TxzZ! z)! zPyY1j)5l=@GaUOfoW#jVZ2yO!*w3a}S&_SdN%FfYk<0|N0s4-#Sc|OX|ONwa?bvJbU}8)t^7N z-{-1te{1Ry)z9bq%#qdS7u@2g>i@g_`KX!;zx~v-niscSH?8K#r9YWg^98$e6TWj3 zKh913J2#2z+(eIa6P?aY^gB1n%ei^)LWh_AiAN4C{>}FvQhpx0^WgITt5pxGxU1ZE zVCh-zfdfkC2R1#R^q;=y0hJea=O%pTCVrfo_;+p+*SU!v=O#Lxo9K6L=6Zpho8)eP zrY81nYGpsChW2@CYyYR_&IQ)OdBGYvM_4=O3wGxYeCH8KhCF_rBFnu-hl$+b8j3pTxg?lDPIs^w=lSX`e*DeUiNF zle_Ksp|YR)>fMUJ?tC98KW8nqYxzHMzg;Tsear7$dhU3`drRlbj@_yBZ?WS}l^1sV zBz*fMe(aO@w@(t+K8YUtBs%Sr=(kVidV%ee%SUdX(cKZx``wxEXOZc~65!XJ39{U?Q?R)6AACi}SlH9dZ6ZzCiKh#kF)YiDv zTs^FXI$0z2vv%f%-F)F&2mDwc{98BTT2J&?XLMSB^t&#(UWwHt<7IQ{EqynpL3SuUyn?#DK-xq14A z@2vj(;X}5nzWu#Z-(CIu{fBN{eSVMEZBzaK_4{vIb7A#;wySyZ$CtjR=EzkWzNh93 zcIPI1=O%ufoA`Hb64$wj9_J=Hotx-)ZjzUCbJ4GCR`$(y+obrv-h89-v*iajEdOu+ z_68Mq+Q-%}JqPW%Ug^Byqo0c<$QGo}16*wcBmUwX64n?aAkFzw8)ne}-d!hLbosiS7UJ6Z_fp z36>*fUVzmGPXGED@85YbSuUynbL*~L^J0r>t5jcF{ClfbzuNb~)vJ#!a?4w)zb(1P zn$`F2yne0fhd-aScJ;|Kw_T_D=Wf&1slJNcc>&*ffgk4u{+$=ZbzY#yd4W#n1^S&A z*uzpnf|ebMse|BnkSS8><=#Zp5{o=&{b|wEpOKU2?q=&t1FO^WwR@c5gZC zCDkXN`r*QL9&cRu<#kS9yW(PXey?3*@jBPHT=~j6?}sh)s_FyB%)dnShj*T_MD>kD zf3!sP6YTa$`1VQs*eCICpCqn*5ECAcc`7gL_DT5mN&MI+@o%3bu6+_c_DOWw zC(&=8%=H4>C&}IONKHJa)XMWq4L#S?*7Huy?E|cZ{ed;IZ?Jau6YTaG`1T+C*q88c zzap-E3_bQYblUgOZ$Bh2`y{z*rzY~Lm42w9{;92TskwSs3w5$a>SyiD3%mKkw+{HR zKKQq8#I>I2vCinU{^)mIa=jAIUAx(R^0~Zri+D$#O~kH=c0+z~Ad_wZ?-3`|~d@eRyEsKKG$V2KMv2 zFMo7kpMUf(e;nBV-*?XA1LwkLzVyVvdGX|JPY#?Thp+LMfxp+o?%ag$+{BM_3jfYc z;yO3c)Io zOXu-Bey8-m@bMceFYM+E-#XyO`rzNX5!ZU6$2z0a`lH`<$@Ky|H_6@pOik?D)XIKN z4ej&P*8We;oeQjm^MW;Uj<9yl7wpa*_|7BzIH&OM{35P%4L!~~bUFvo?|dXL=O(#p zrzY~Lm42w9{;92TskwSs3w5$a>SyiD3%mKkw+{HRKKQq8#I>I2vCinU{^)mIa=jAI zUAx(H^SQisKmEm3)qBCtix2F2u-``PpfmLq0vg4G62|N0s4 z-+3`vE~)=D%b!*A;-VYQt-iFudKXr|nrE*|s*k;8gDa}PZGPmH)%Rwtc2)JmAFpst z^~tSwoKgMrXE)5KzKY#>0pEFnALj-BofpJ)UZBT$fllWI`kfc#<-9oQ@GqBr-UUxC z{@ecJ`113T7am*wpX@(hai=bJRO$KGrH?3`k3KTB^uPb`sg)OY=LLM{1%8|t_;+3q z*Li^+=LI^Q7wC6h}HcP@~Z^Mc&9Qxo~rNgB#bpSoqv6t1qqn%2gZ^8%gD3-miL$jf>0i`NaxK68~dia+J170b_mthjvn|LUnrRoojkeP!u6 zZpTGS=NBJer1byW>lUfJusbi{J1_9#yuiQng1F8L^f)ij>AXO{^CH&^?7Sd%`w}&= zUr{Uj7&WxNQCs^SHMbwK7WPTj$o|RN*;lbwza8@J!}zg3CkC?DOcf|D)fz zKwi!Za@S5xv**QgdF>u}^V_EQJ@!zxX1icr+7~H_|Frkcz)M=@p)4`*C((1 z^(mhBoqsfIihbaQuiZGs{xEaDTc+4I9$EahDSi)w-98E5K8YXuB>wG_#I;YN$3BTp z`y~49ljLQeJbI0#%Kn2({;;n6@9%oay83y=t9M;j|EIj=59=8B9hbjo9rbiq|MY5g zo;Cfm*Qo!LJw|ymMqKNO9_x%w>yLidCD#jVpCotBBQ^1yQY+6d zHS}ClThBW+w-2xu_6OF;zQNkrPq5o(;M;%jV_(9*{ffBuG4$Bq&}rX8zx|NB?33iK zotns}R{Eia`lq(WrRM5kE!4>xsh_noFYM+E-#XyO`rzNX5!ZU6$2z0a`lH`<$@NM+ zckO2P$>;Lg{pyVCrg)7C_S*Hn12X_i)91$!>p~sh&N%r)H}2BQN^fO!c2~ z;WIPM3%mKkw+{HRKKQq8#I>I2vCinU{^)mIa=pOLO>(zCQxp3(wX&a6L;F0nwf|Fd z=K^ctykL!-BdneC1-o+xzViq_&MEvmzliHxLyz+goz6k@J0Ho*xk>KYsfm1Qr5|dj ze`;%7YOWsELY=IU`dK^k!fw9stpk3n5B{wiajhqMtTQ^TKl)vlT(87)*KYRQd@iru z$@^|R%RYJ7T7y}h$L%**W0vRiCwHwl%k#VEVEI{|>y0j6YL@5yecQismVMyOdn`K3 z{;>KBUpC9WvBX-7%(9Yv&gmzt}GwNNK(q<+@U zys(=ueCvQ8>w|ymMqKNO9_x%w>yLidCD$wQ+_jtCC!fn}x743rG0W>ru-Bi9{&nv$ zI5}cCVm|BjE%wA-8)NsndNTj{S$vNFEZ5cJImSx9nCoh=d4VU=y!uCvEIU~KCBM6B z4ED3hhm&^oU{7o=*sa54{`0fM8vj}9FrH(q4nAr!2y?)pZVT#Mfrc#aaUH{&#!w` z={a}RYf9&GADmJ8FTHI><%Qk33E#PiALl0iotwmUZlcGziB9Jx`kkA(USQ`Yx!a$q ziG7<|+0Ut=eV*Fd|Ealifwgd6utv@i*3S8Y-MItbd4wP56#kuG#C5Kr$9acN=OFr> zkL2atBzNu9L_W3B4>i<3wKXm^R}X8UPS!~MtetsbH(&VH0YBCU|JIGT))PI}8J*T2 z{jN){SK_&AH+ybAm)Guu)9$Z6xzPXIUFUJ{L+`9}dgVXeQRnxNgKw{M{n52L@>?UV5B zllZYu;@>_=T>B(??33uUPom#Gnd=3%Pm;Umk(zi;sg>uK8hWm&t>>MZ+Xq++`vYra z-(cl|2zhJEt-5dY4`dTdt$GRv3p%Tng9GOvBrOv>+10wV{Aa1dc#g4>FQyJ)^8!z#`Lxfyr1yKd zyViVBZ-0LAQw#R??Tdf? z>t3;V`Cs*#S61BLyyR7-=ZOWED4pLtXNl5(z+FpJUf9hSzIDKl^})Y&Bd+yCk99_; z^+&(!lIsO_Zj!tGnVQ(Qsg?bl8rtWnt^J>xI~Q0B=LKuz9AWL8FW8+s@SR8aaZcgi z`9)mk8hV^}=yVRE-}y*h&P{UHPEF)fEB#PI{Zm`xQgijN7V2b;)X&Yrfy>g~&{JqFujlMg5D_HFEm z?fKZ97nAwV&k}3=XPFn{ImSx9n0Wyq}Np+ z`{3ovSAX07#miOSJL{@ts~?^)YnkekcP_U~_0O07e(CC~*qs;fofr6VUf|z(L0snr zdYl*NbY7s}c|l&zi*FpWO4Dlc1wM*v$ zJFZjuzkkd+l^1sB1$^fPew-KhcU}X^E|8b=g50%J z6ZzCiKh#kF)YiDvTs^FXI$0z2vv%f%-F)F&2mDwc{98BTT2J&?XLMSB^t&#(UWwkX!%4e+8+&4VK6dBDWd8HB#2Wuu=EZo9v63%l zUVzODJdx)0pWM9W#s24SR(RnrHRDJAQAKtL~+eJ5SP<`*QPpn`4@Rxh9 zSAFvJ_jc7k-*1MCKh6vMJ1>aqyg-lh0-eqa^gA!e%X#sFP2XAeAAEMJ z;=lRKcbA`ArfyyS?|kDn6?ghU+m@bFKeJuw+TKleNW|u-FX4ud4V721^%5E z#C2Yv$9aKH=LPzm7r9Q1x&4r}uurl^_D|N%zKY#` z3*SDBANw=@?c2n)pQFbjkz?lDp@T zns`pBmFJfldakLh=bf6{2UrXH18Zd8VD0QD*zGg$?LYXjFX7*QMO^zBdhBoLwC|zc zen?*SNpjatP2^K6{ZK>wQ(NOwbM>$m>ST@7&)S(6cJqaA9q?m)@NeCSYdz6pozZFi z(eJwCdL^E_cC-8Bb9wE)@$c`g>rAlMpL>2`pE1~L(d5HPyVtka6MJop-RtVf{O4zh zHU6_)SC8iyEBRustHI_4o=EfjM;usou>4(LJ8ca1v&n~(cJ*LSY%bWX!({&Rv&0(z zS?VyJW31$hsRP)&z!PbHY>m&>++6s@hgW}I@pp$--~Q{*4yk^=!%q&bKELH#532ru z;?EDPxp34k52$%@>lO#p9GU+g52*Qq-MI$GM44=O+4{o8;x( zymQB?WxrHORE(@OsX_fD(4usb*5 zJ2&y;+{C|gleo@J^f))s>D)xWb2HZq?A#=G`!hAMZ&NG#IW@G;Q(OB#HFqws7S0RS z$T`B=IbX0lci=mZ@Z+4qzw?W@&NcKn@6hQSM8ETqyqufluAQ35r&ju*hWe+r#---! zVJ+0j8mXVPGcWAs3*S26$NJ#kx)IlUqQ^R;)B2;|b;!Yim zV7E`gw@>27K8b((BysJN=&?_t(>{rQ`y_eUC;#WFFP8nmyG|_r%YSiF`Pt<^PcHwv zUHGMnd;Qj@l%CCgcuMJ9Vd+y#|NmM0)XEFHeGrAlMpVJOGWeoOOH2HAS?)5G9#9kX? z_quvA|M^*BjsGmy)#EwFO1_xuYOr~MC(?Z9f1g%%u>5b_cflC!XWG|ZFE-anz+W*4R zzs46Yth}&0H{m-s@#EaYzjKqg&Q0_R(=^RAA^O3xqo8+#Yn#iYC z`k{vUr?$qW=IUWB)X5sDpS3eD?B)yKI^f6p;NQ9t*LtGII-}G2qu+JO^-4TXy?24IVaB{?O5|8?M^CN~c>i^B2c(Pb&mp@r7{SW8D82#kp zXUFHLHaUFu{pVcYjm~C&@c!TKMrX4>b;s+v(b?=jy5+Uq=xp|{-m&jSXS09hQM0_7F_8Qth?Hv8yoHvZ^rHb0}Y+5C^rW{W#I zn@!K?Y&M;vv)S~I&SuMN)Jyw~ZoQ$?zT$7b)5+iAi5olpod27fI{jZf^XAUD3+?{h zPCdsy^xaOKA7Ax*o%-Ls`S&U>?B)yKI^f6p;NQ9t*LtGII-}G2qu+ITKCBlxj%IyZ zM=^C6T@UosXLOy=Q@7FeLr*yw`K8eO;atmEi@?`9v( z{l*{7{pM#h_nZIG+;4G5bHC{s&HbixH22#+9L@cf*XTa>wr{m_?&Nds^uxK+Kj+T4 zoICY!?$pV-Q$Odw|ymMqKNO9_x%w>rdZsU2=cUN#~B|O4*;|`BXjF zSrE^j>JujiY#)Xr9`Dm0KG|on!=Z@)8Ac*b2H z&$#R38Fzg=&Yg9@kM-f)SvTT3FF1GB8J*4x^t&$EPv)d^7w-h`!Oo6&$9E65 z-zGopVEZr}F?Rbl_QaFLO1u2YV(FirpZdqgO8sh+!)I5#=p*&_#cn%(sIFsAef4g2 zeY@^_AE@izvzFSmu7~42_5FRz?_Af+gtRUe1f(|Mg>Kzh>=^7k`PZ_bfkGuJft#f8G6iRowkn z->39^_D%bi&bNPe-_pO(fA3p)VRv4@_wNh*I4|(;-xtJnUZBUnFVN|{K)-)qJRjDJ z9Gw@5se^rq`q;0in|+LW+TWN13V}0;% z-H2;F(PN#_Y5mdfy5#%2ev`^UD9_J{brWLro333mGo>uCRBKiHR8NBb3V?PIK? z{SBS=J@nfT$;&>;I%<#KC$@8^pZGmvJ9oy7-#@lR|#SgAjC`q_9UY9G%;?cGf`Vy=Vm+;wdr(j#xqg-cn)eG&q3|u8Mb{q!?urS*!J-Z+diIQ+s89(`*?bZ*8oY+GLTr8#xISUcxtV(MUjj^{JCb+n(y z^PJl{+W+JE&utx@7xBF4wvNsh?9NTr(RqX)=O*ju{35P%lXZ07q0_mEe&-{3IX78H z?eTo(cJA~O&vS0)&baaX=XUPY8PAJu=gz#aJ2yFZ)&W1xP0pQlBd&9kb7!5=>D)xW z>q1`c&pGMb#XG@!u>CgP@!f;%x5-aC*ggzLjJ-&~_o|&h< zhgov>dFuO_ZC0PBzPG{dynyfbQTTCQ;NS0~i0iySkKae3(|Lh@zmFm>zmIzAhYOee z#)V&A{MW9ySoyhjk;TjZEmyv>;vTlpt4hx?^Dj|4-+9IorGL>MEm3)4cV58v`zZW4 zFYxd8QN(p#pvUi{(CNHDzu!kaAJ&T;ofnCzgMEqm*srLYeT;hA->9>FkNVpWSr_{x z>t+9B9qp^wofq)!!}xJt;NQMYT;~OP?DOb!UZCH(Kwi!Z_N{jIvwZfse%Sx|=Uf<< z^P(QkkvchF>gU{<7k2Z7ZyoSseeiGHh-*F3W1Z1y{n78b;Ca90!1U0*TGJX@({MaYsH$g3~eKLL%)O6Y><2ONl z{0^v(-vRaU8?HWn!_~)cxcc}FS0BIO>f<+Def);2kKb@LyL~c#!`1xQC*wC`Sbp{ffBuG1k%khEDq)`t670WuIgnwa4!h+qu(E{GPF$JLAUhAKST8 zXZ&8WojdcwZlC1bSqJ>sCpmZ4jkxwn&Yg8er+pIrt_yj&Kj)-#7r*oE!CuqGZ-;xZ z*VV~SJJ@S!IAZKx-(pWZS**0npDdRCxi(Jy<71_MwaMYL@s8j=-Vxl#JA(UoM{pnS z2=3!OvwgfHxQ}-P_wkP4KHd@B?9PjLM{x7wyoh%Mx46!Wct>#4>AZ+{1h>4ru8#Kt z_wi2WKHllv$2*<-c&Bq8?{x0toz8u{)47j#IybxX0>0PP@lNOF-|Omlr*qTeb#=Vc zxsP``KQGpcJ?XqiOdae?)W?1m?=f%dXn%|Mp0{0u&I|Uf_IO`;J9qkt_nWtKXWV!ndOLUOjQ6LvbLYIk zZoZs5=LLSO59iK#L0s#}xpQ8i)B2;|b;*7*C!M=}e!cg=UJABXAN0U0#^B_L;Uu;X z<3|j~o{v58WUiuD%EO{W@Q$ z?+4D=S=$Y&h|a(Z$D&R?31jQ{gZXHuVQyzz_$oF8zjY(7 z^+b<#MyK^hzw46wb51&U+a7dEeJ2mLSAY8S>0_|{Hu-S0gPjp@#Mtfm*b`3{EA8?p zi=}^he(E0|OP#4r4xfF~a?>gouo_N3?7%TtKgoxq9c=D!#MsRRd*aDrrCt7HvGi{) zes+8;b*45seD>PaK3jA1-h~dY{`|xvhgRRd`Tj$ypFeiz!PVz~wdz6D|5v&1z?uuo zJ#awHiw|siK+TcU7d@cn3wGxweCH;9oSXP}ZW7nIi5}-BI-Q&7cW#oGbMx%&rYZe?)K-SO3!aUHLY~scHOknf9X%ARbJSgoA8~R_;GIH z-?>R#=O%ibo9J|IqTjjsd{{4XbZ#c54)$m2W8bE3_H*iKpQq0Df9mgCU|pOSte10y zb#%U9ckaM<9^uD1g@5N4ah+@Eao(ZRIf#DeBY8PD*|*x+&+^&l`eFa;pL1bc&Wn0D zN9yE!sh@LaUf9hSzIDKl^})Y&Bd+yCk99_;^+&(!lKXQ`I(MI2cjfAn*FW;cI*(6W zyh5GRla7B~o!_S~TE5Qp9~W4z&imTmSho7W%2zK_{b7%#m#MyS{v%6QKf!LFgm0h3 zk9`vV_DSN}C(%=Va;VcjiGKSedD$non6^sU7ysU>#ozbA)yvN!x4fnNFS*B>75C2T z*D5_fpS5=BJagN1O8;)t)~UR(+b7}MC-GyS#J_!#xb{i(*eB6xpG3cX^7*h{s5-8{e4({oLoJ@3@tKES%zA6PH@2J2`)!ET>{Z~wuMeF^{eE8^P6&|`l? zr+p9o_CxZrPqJ^dbMEA`&-KIp*FWdNxSSXDaE{c;`BFdU&b+XjFMR8OAM1mE>qcDb zi5}~WPV0|;*CqGooOJGXTXOBXHU@iLdj9syj=^4+CLfM=u-DRX#Mr$y#-4bxSZS9( zSuFi?ZJheY$5Ll%lf!4@eRB<~A>LuvgY}dAw1dq(-e=c7YcALmPZlff@+XUh9gey9 z+3~Sbf9mwJ@h-DI-euOuyUhA{msub0GV9}gSbe<9tdDn@_34?9R=2ms#`U z+>CdbwYbjBc$Znz>D-KWnf3AhvOeBl*2lZ&`gr$TAMc*)jm2b7$R%>)hnrS!Z-wfAqU9 zmyCM2`H$)%rhUnwn5PiHGqK|h& zG`oE=-VM?G*eB!N5G}5KGTsf*blNB5-4HD=_u-tnUaXycGBI`VJjQ!Z+B$lE<2@;D z9X;>yUX`|v_J?>6OIt_#33mG=>uCSMkA0GLv|ka|KFK=T-_U8FM8ExzyzG;#qxN|3 zNjrD?iT9+mb7$OmuSz?2>WufWv~y=(*zJ>?JL`ZS`y}Vix)Ikt$+@%6=(JCw-*q7` z_vf5+?&5tAJ=p8gc*jH!_PR9rX$O0~3P+6HYh&z*CySMK`IE)cKiAc%e|)UeuQoY+ z_NxEbw*FQEtKq4atv?3qC;4!+gY^$bjNM$YC!Q=;+T~9cOaJELXUE47&Q0|Dy&QS@z1-;=zO(EfK4h!n zfA7?Hm!J0^x^?;A<8|9q+}H2FZRuHkpY2NLA7A>O(tp*4@2R}7J2&C`y&Qg=oA~#8 zIpR7u(c|}W=yYzP-|yv~59>va&dtQs!TwBr?Az4Meoj5@^VHe?PyL+>tc&x4^>U7| zj?NeC&Q18vBm6iw@$dX1u5%MT&O3BEH_`8WBroSC`&K*qSw8z*KkR?~b1sa_c~KAN zNS&N7^>gmb3%mKkw+{HRKKQq8#I>I2vCinU{^)mIa(~WA=kBM!xT@~;0^4stuCgqaI}M+5pcxV?fKXfPZlff@+XU>e|moEA0JDdsZ9=_ea-S`4ZJQo>F_TP>`U`5 zc=Eu0^|t>weqbMa$qSDi*x#P)KR>YVO>I3iVe#kL>yq;GmJO~b|C=9q zWyPJf+Eu0J$17Y@I=9|&M(O|A4Kpe)?B)yKd4V76gMaHrTx@q8kABzX`LJH( z=)6cw9qdcg$9_fK>|@l^{zjecd(_{4$hz1kSugu1>u6uaZoh?ZAI6XU8UOZe;@Z#A zW1mN-{U80#1@dxUuy3`qpXIa9^~3(xKj*@@oEPw|ym zMqKNO9_x%w>yLidCHLo?bne#K)!U*rFFgc_}?z6>%d1> zzND@Xk3a0kiyZBfiK&CC)n*X@a;eNu`l7@ennjS7<%k)=(O*l-+oA5_DS}wcJ{M; z&YgbP|N7@#7?<;+9?p?EIbZ7M+?f}4^M!96@MC@OZ{3J%J<(&G(P{nB@4DpvoRiMo z1#4bi-=%=ProCmGi^pKEOOp>rJJ@S!IAZKx8)HvAS**0npDdRCxi(Jy<725awaMYL z@$R99)e!Fz>cRR+e%it24o8gLT(BpeELPg(PZmr6=Hh3^$4dQblf!4@-86l?o2HL< z)AaFfnm*o5)5rTw`gk`@AMd8=f>EP&Fbu_ zjCTn&ozBg8m(cTKz1Wk^&BWBf{v7YgYU^k}kN0Y|b+rG-d$`&kd$`)UQ)j%l ztDQUZ!tUJU+*t?wI5#p;n?%BC!Q=;+T~9cOaJuz)IUC!I#Zh*K6}Dx_t*2mmL5Df%j@~CU-j@T z`_*3m^~fx*|IfeX(OLGle%{As`S-$`FM52I{cy9hpP1#}7dPMeva&Wps{ryyK1Mz5Z`9eoNB!-Gtc!h;^|F7mj`mgT&I|bVVf;8R@NeHH zuJZyt_IY$VFVOE?ATQ?y`&K*qSw8z*KkR?~b1sa_c~KANNS&N7^>gmb3%mKkw+{HR zKKQq8#I>I2vCinU{^)mIa(~WA=kA37nTJ7ir9OJ=O#9gH&iKhp z``aehJv`IC_mbWIIMaT(XZO@h`{YMn^tYMz&r>dZW~TE3yYm9R^8!E43;a7Ti0iyS zkMjbZ&I|NAFUZSzvCqYam3`v_cP;)#cdcK3zVffHDgS?5X@QD+}UDxbN#UY_0PF5F6Tu(oFjE|zSPgTGcWAs3*S26$NJ#kx)IlUqQ^R;)B2;| zb;i?B*oO*Np zA9ImoZ>;}s9>3#v>i?cEeEf#`e<*hQ41D_!e(X#5w@(t+K8YUtBs%Sr=(kUjmwj@p zH6AScFD`w!_~$wG_#I;YN$3BTp`y~49lh23sB1ijVV(Q>|q&}Wg>gM^So}O#!?0KjD_5s$# z{=j`VB!UlG?nh93JHI_-Ptw;z(1eUg2vo&7AIeXbw&zy3KF z#^t=IhjXM(&X@W*cjkrNeBoOM{8%6STQ}lbPxM%4bXtG(yDqsu=cIFY*fxKzdwalM z-!AZ@o5orJJ@S!IAZKx8)HvAS**0npDdRCxi(Jy<725awaMYLzhCLBSzcG~ zf7`kB_x{40URd7){NR8~>idED-f=~JZ}6()uB`79KELi&^*zJ6t6o#zKP>mb8TGxy zrMJzf?<=r7FW@^b@Z-F|zw?5)&I|N7FVN|{K)>^Xyqp)i9sT99-?7Na#b4yUa&%rKrVjQc>SMp6ZuT+iX@8^6_C4xvKV)6(ldPBhlXbMOVz=MIw-4jT z{)~V7HgWCe=&{eE)BcZs=K^^-FW9%*+0XLX=lWs)>z{LBT+WMnI7jN_e5s#vXI|LN z7ru4CkM+U7btA6zM2~ewr}am_>yrC(PC9q1fAq-u?j3BezT|gTjluTY<#o8Y}zU*7Sd34L^ zrSql#FunAz^y{N5FYM+E-#XyO`rzNX5!ZU6$2z0a`lH`}UDxbN#UY_0PF5F6Tu(oFjE|zSPgTGcWAs3*S26$NJ#kx)IlUqQ^R;)B2;| zb;C&YWKN{DAG%(+)Xh47T4UAC7jgGXjnnyFDL!;>lvAUH)XT^iR)E{o`Y) zGquU#v%4<7e&qsI!_s$eI|l0~`Eay@%^i*yySZRbJXx%?%bzTk{>{bDj*q3z)Fy|| zuK(obH8)?d={u`G|KPJ*Ro{N|neVQCe#_LYtIyy0#%-$qPd{kenhU3XX1kgf+b{Z_ znj_0>`ktCE*qxj3otyY^ZsOm$NnGb9dYqf+bZ(;Gxk+Bm&Hc~ctn8P6WRv2*YpadQ z&$m9jVfnx4#tka&W1m>R^!#$~^-AaK@9j$e`_AtwFYL}u_|8rII5+X{+$64Z6FtsN zbUHWD@7#PotQR>tHxp9_`!n^iZ&Nq>IrX&9Q)l}>^>;3?F3tbYXxiBv0MLnD&b#lJc&$%-% z?B)yKI^f6p;NQ9t*LtGII-}G2qu+JO{W&L{yMyn!ptF~P?YCz=b=nx595I~4&ItU7 z;n?%BC!Q=;+T~9cOaJuz)IUC!I#Zh*KD)>x=hW{|-gLv+oqcJuubkD{um16*Gdug( zZRecP+23xutx6*~B zbE*9_ABaU zAETc3H|lKPqyF|o*2O-_df7i&NBb&v`z?I?Fn;XM__uEp*M5#3`#d`B|LAuvkeBm< zeXE`QET4U@ANIfgITyy|yr_qBq)yJ4`Z;&zh24DNTL=7DAN*T4;#yDiSZ8!vfAqU9 zxj*Nmb9dlzU+b27!wG|@|MvY^;Fo^v`wgGF;g`qYi8%0oc;B6aO)tJ_7W~Bef%EI1 z9Mw1(3%)+V$+`O2od#PyvPBR79}ap+!*CKO=knu^9lYp(9U5Od{KRrTe8H67SYS20 za+4j#;N+MKd~<}KI63-+uN{8k`E?{-SNjwn;zB$5A>}NMP=FnN@0#@6Zw_H00Cr6#|%@Ka$ zR2{uRgiIbzx{49Jq84HfNfYk{n@kAW> z<_JHrpS^pdFIT?;tL?HAzBUG%FC2A(%@Ka$jqHT%G7`~Dfv&SkLq!ciyK9N{ERjz06V@a1GIIOYOYC!E9+ap0RH{KS6tj&EOE z{R*tMPfk5_3^rdl>I9o3{KU!8XMPsGoQws>T)^stlXxNyd~<}K*w0@6wjFBiz-pW4 z+$m$Q`NB~r*c{;}PL4kFv+(6)EI8%@Rwtaq6LH|1BmBgE_L}$YQ0Et{wvYU6zcJW+ z;iwaAj_?yFN1ypw_;NB99CHDy6HelZIPlF8equj+#3!Dv{tQ;zUO!%{@&%hO9Cd=t z5l-Ud=rcbHUrxq?V=iEI!bv<42fjJNPwZ!RK59zsXRz8X{q0g?u=&DKC)ga}Cr*w& z^Rw{fWGp!50#+xS#1nDgny^(Pw@ZzMPB&$6Ubb zgp+t84t#TjpV-f?{H{Z59)Z<%>KhjvgUuI?I>F`$KXG#OnV*F(Cu6}e7qB|vB%X)^ z-yGp5_OmZ~)n}>~fz`J2z0dw_2sU3h>I9o3oW#k|XMPsGoQws>T)^stlXxNyd~<}K z*w4QBhfCF71*`3v-Jkti32eS_)Co36IEj;^&-^TWIT;I%xq#IPC-Foa_~r;dv7g=J z!e$TVt6@c9jaI6W~I>1Ss9DU|z;mgTbaLf^GUT_jm#DQ;K z@DuylmtD6&?QO8yu7Bv>DT&P&jyl2S2tRRh^pl^3FDGNcaSwo9cQ}cYWA5 zIPk3r{KS5C@jpC!Z3Z@%o2Ebe-5}Wdz%ehdHGz{jIr_}c!k3e=;Ft?oop2IQ#DQ;) z@DuylfB5Tu)f2#K`{$jW{o4d=zHrnDHb*##lcUf4EPOc`3y!&f)d?r@L>&0$2tTo( zz3ip;PB9m-+V*;4%lhsJoE&w+H%B;$lcP`g+TkZoj=8{BC;Y?{ap0RH{KS6t-{0|U z&j%a#iN8Mk-2&Kr;iwaAj&KquN1ypw_;NB99CHDy6HelZIPlF8equj6@7eXe&|s?v zF7f;}Jkm3OlX#SS<0KyC)%c11EdCRZ>eKj%N4a$H6OS}^=$Qz^*A5=#+xUq`y|MXE zJnEl~FOKiE24Hpa-Be=pf@4j<)&YLvi8vVxzCQD_aLf^GUT_j8#~S8m;mZNbiT^tc zz~;#R4ic*kj=6x%5q{!{I2jARKJ&A1)Co36IEj;!xoC%{U??a_sw>3KW!KH*>-XNZ5Q|Dc5%OM7x(dYaer?Y_x*NpKX9{;{-4|UqyOhN zKcoNWHvgml=eD?`|K~P6qyOhNoumKfHvOaj=XP;jmi?OjKUe(U9C1YXS@VD+%m3h=M^)S}J$Y2=S!SPU zrSossPxJo0?ty!!RbJTL|M1=a_;LT^-~CTq_dj~v|LAo8qu>1>-vbZ8?s>k;P3&HU zoY$K$9)TS&%;Ta9QSs97QP&?9Nz6Rx;L+j_q=rRo|=Z;&-hI2 zp2ufmIq{yOF5Z9C#e0#ucwbT%?@{XF{YqWDcd1+J+4nJZ@t&rR_i&Bw=V^BLKYaIp zya%fJcmKzGqnaM~f4pa^>39Ffd#Sp3|4|q3Me5>xNnN~0sf+h3b@AS%F5bt~#e14M z-kWA#@m{CKcmKzGpqhX8f4n!U>2d$Zd#0Lx_kY}HG61{he(eAFcmK!ze(e8o-*}5_ z|Bw63n@;X7^KcR;$Gx4O zg)avzXW^Zft^N;o-`>8=+GPi8$7f>qJU$c4`Q3Ue*Y(dEe*earvpZk0Le1a5o%Fhz z%OAXa`I^_;zj(Qt<7Zv9Y|Zx*W-U{5|IX!>sq2B4{(kA|li1z=@a_NjasT7r{ZCx4 zf6(LpN2k|6=y(5I?CyW~_J91i|M74CC$9S+J@$Wey8qE{|BwF*55Vqu{QZtKo>Ob`Fp(8c?&8+JeAGqHOf zpNZwf`*6E>Pi`0Q&+X#9x?Q|)w~P1icJY4RF5cVQ#ru3a-q-APLcIUC@!kLNzToEH z{U7faZhGAR@jl|F-~Au&FYe+!xm~@qXc^$NeAgBX0WL|8d{i0PLRU-m}E+RXFZ#uzMbU;)ysJ3%)+{ zvvAzEVD~(n#L01Q=V#%|0n3T!19$O!;Ev}E`*%S+bGXB&dmHSY$7fK zu`RCsKb|YwblU&pIka8ehdcng=i}byLEN|8IPPuu?s+(gC*owR^qHT9=E}oy$?C$?~-cIx5{*UMLw7Bm7c%Dzw>Hd%B|8((x z_5s-a&;QC3+pFQYx54gt_=zXtWGwjl%+JDc--6xqa1tlSy`7(hF9$4VsXx7<`aIZu zyXar{E<0E|J`=m=@tIi8$@^~XbC$Zp)*ASnrEdET*6=w?-B0dX(dR66dk&WOIZNF} z7cb>=mb&+C|4N^;)V+C+MQ1tpSAXHle9lt0#9E8^oTU!C`yam7KlpL~pKCAwQ2GDu1|P4u|9-+=rDvW)K3zJW ze)uz`f3a`vUwL77|HHQq_;LT^-|HXZy8qGR^$$AT|LFJnCw`|e0K4bow-1B(T|?uz zx8b|z;Uu1jld;lgein}V7VMsflQ=oQyz4HWcir*aY_EUf8QL8_-P>UI zJU$c4iRbrr@m$|7p7-0ubAY>eK5!S$4esK3!d*OPxQpixckx`}W_SO`bBvoG_kTS1 zxW#q<$8(aKPWOL2SGkMlEqC!;-{J3Z>v_LjJO{Xo=L2`~+~6*rC)~wzhP!zFa2L-d zZg%&7Jjb~CasS72k6T>#e>^9->2&|cbCtWe?_vOU|Hr)?gSbzlaopSR-Scn~PsGVs z=`%kI$9)TS&%;Ta9QSs97QP&?oL`-B-4ypZ*nNB7ft#(Z9jqOniQV(~Of2VtH@|Jl z==Z$cnk(-<#Xhsg{8Oh`|2_Wm#3}Zr^p6Id8=(PUmcU`#8&Fc`b`=5K^5+}#K4c|QvKk-DIj0Inx`B^ybTd;c` zPU7UaxAU{`<$#mpUWM--hLc!M+;=?yTNCb`PHZl4%pGh^;3uAlld<6IGd~N*yuj83 zPU7U4dwv$a9I%}D-O~VUj{J5hvD)C63)mdtC!UCtvEb`7KMO~lU~`0%I60Y%cKC_q z#P3oEU~`P$x(?!Ztc_zX@XZlU;)ysJD}Cl?;iwaAj&KquCv(vbKe3#+&wKzjU+xu8 z>{`Gv7qB_PPdpJPW5L&Fein{8!R81jadI*j?eG)JiQfSYz~;zrc@nD)j=6x%5q{!{ zI2jARKJ&A1)Co36IEj;!xoC%w~~PsGVs@b#IWg`-Ze zIl@VtoXkZ#{KRtNKH&k_9J$vwvD)C63)mdtC!UCtvEb`7KMO~lU~`0%I60Y%cKC_q z#P7TYU~}ZRT8Y&L$6UbX2tV;eoQwrupZQrh>I9o3oW#k=T(rYaEGK^FH2|9 z<_IToaxxd~@Dt04``!m&bL8Ij#A<_ME?{$npLilp#)7ZU{45-Gg3S?5;^bs5+Tkab zgMF0OEc}bHbB)cjfUt}CyHXB+dy28k@o!Q-OP`cOzZGMbk6p}t3v#%(L5y9F_dMXA zzYFB>_ktL^eC!k9i8%bOO*@$HQT54ptzzu@^gCGe@cT76{7y}bT|Rbk{@x8dT9+O? zTHnI@AMK?UYqZB29_^no8Zxe!yuhQsr|Nfn`d6DeS?pr&#g)VT zx?=2dypI`yHJcc_eC%TWwvxl&XkzSgu#4%9a_F&Q z>~gS+`Mri5e$yewE(g1q|4qx`f7W8`a{RwG`SM+^9KPcfW0&vu!0`FoN)CUciLuMa zF6MuQa`=Cu7`q(*&xn71yCH|)Ux=~G_jeiaxff9m_bZCA%lAG;_{?HC%ycn!`Pjwu z>YOiP?DUYK&o;}%tfL&(QH))Vvz5;hR}OK-*yVfe0iSaxhjS;!F5hc2_?$aAoI5dg z`ChxiXLiV8c8Iad_u3vl=RywWLX2I$fBV4aT+88Hi?Pf1Z$tR>JvsC}F?RX>?F^rN zD2IJ0#xCFQ7T|ME<#0~L*ya1(3w-*d9QvdfyL{|o=A9g7r5L*$>|$oU9A>>3yBzFd z&S`Om=U0qf4(C_QY?Z@o6=Ro!UCcR^!#NdWmxEnQpOHhK5o4EwT}DN|7rIU>DQp zi!u2z&XSUCd`efnZHB9@hrQavR z_j(xYbut(|!)I4^U;XW+4gc=2>j&U}UH*(g;w#?0ZE?Wg-{IDd&x+wE=Cg7p!sGoL z3!mT{&;EY%Kg6@ZBYxpwtX>ZIvU4wL`o$wX&F*LA;B!2dGd|Wx&#YM|{h?|2@4qb3 zgSTAi1q1LNJN>TVQ}%dG!}tNe`7if0{zP^@t6iLYu=dMedsp-GrNvh2!PpZodjD4c z%Z>)^VEDT}@}u@y>Z2bx*x_i8&-UUWr{NK&N5kl|4Pzf_Zk$o>%|6Pp?8939f7*w& zZTwN48-G-1{dB?U!e_IiZOCtS^ba+R;h=L=+b%T!FDz$Rs}^@y!w!sHjDPWX`>;O6 z7mw;W#vZlp!1x)~6WqZUYmc?VPveaIkHPS@hqlHUX&!^+#NMMOjWeoY2M3%S_P=#b zew-2NU!TPef3!yR*-st#)5aNWHRw0_!fgDvqt@+LxNSC``lGe`%~$$a5wmZ~o!8wS2)(-?w4Q7yON-H){EUFI;}( zmM{1Z4{hA?1%G|}OKly@*OTJ+AkS`dWf=74ZtfrI>As@Q?l;!Uedu~|)>tq1Eq3=aeD^ti z-2eFZToBjuf*#KiIz3SlgB(cv$n6BY3zL zEl2QhjarUibJXr0hVS0Sk9!{fo(1B1M$qHgL8oU5{c+aHKHRItAMWAuGu+$df4Ju> z?(nRYp5Ym3Yk}tB*=cJ89-g(zYk1ZwU+i(#sy_IMvsU#aZk)BMKRV;AjajeUpRTVt zaz@M%Y>r@a1e+t+9Kq(;IHMfF=BVBM4Bvfjj*T;{q36OJv7^UxWRBR;KU}*WJnWOK zUBj&DaIG6=t%rM{VfMgqZ#2x_819*d*)zkv)G&K#xW^i1j}6aP!=pXfFne-%9?L$= ztN6pb8ph9X?Hb1aFt3J*J6yYl(KF1eVRR1Hu3_{K*Q;UjB1iVmcuc<7N9)+|XdN3K ztz*NZb!>RFjt!62vEk7=&gRTs$A(AiSa$MtZ<8;0w2remv)8fV(K)0^* z$=4jI19;S18XonQhDW`n;ZbjCc+^`O9`%-nN4=$C*Af4t-cokf9s8)aG(74p4Uc+D z!=v8P@Tj*mJnAhCk9te3qw7n)t~+&bKTsd{33YS-uwL#f>g;}Fz1)YR-qK>RUhZ4$ z?q~S!bNsmf@$b1HuIB|ko+EU6zR-Wthkx5*aa|3jZeaeV0PptaE$Z(G@eibQ+W8qy`u8P9=)RKgCF*W{@F8N;VPuJHRIV0u>Hb<~Ig3S?Z zj$m^Hn%5LHayfrzioJ^lYZOqP(S^)Vfy^=JT^Scx30~Y3tWd2cQi*D z9?g-m59`)2{9)Z1#?NqXG>rdY-5MtDaBnn>p5fkT7@fnt(J=al`=Q~{bxyRoeZ%IsN2KlFN-KI!bU-;Vmm z-*u)$KV(*RXrK>AKV()mJAFI)A+xgCM|m|o%B$f~UJZ}tNW-H!Qg-_c{OE_w%ErOJ z{c1EvnjJm%x6vGFcJxO-WFI#BXdgB_y0&R}bZyh{=-Q^?(X~y(qidUnN7pv9Ie+Kx z$C!`I%F%Ui(*Pbf6B}oAy)8dyXyR_XPyCOrvFkfzIC0I~d~z*KT=>k^(2)Kc9%%;m ziP>+XS>J<4ei}!g`scfPaeP1Di-+I0_wk*1AK!ts$upI`wBbz zin$49zp)R&>_he^nElDV1+)Lz&tUd*eE-I|Zg%!R*9mYq7sEbKe6B0>!}$W^pK}K$ zF6R-99?mHkot$4V`Z?EN^3u-!m(Tv!5Bp#L?0@63|JB3(S10>l{ln{l%8P4z^Tlo* z;9DR3SU3DzPvTl<^jLp%a(>AL{p0r!cGfihKgAyCvGaei;ofMNy&)d{zlQ(EHT(Ge z#@`N6w}wakuwm*vtXspQe%LVUGOSy}qkh=1eIB3odGO!+x|-`K^Wr)R>|6$q`eCz= z`eDPPe%SD+A2vMdhYgSV;cU+6Z#{haw;q`Nz`O&)XAXk#W8LsS+=tChTGvyZN;8~%HIKNI_*U01Uf!+p-*3r)jtpY!)Z!^3^f-wO>7_c?zr zG(6nr{Qc7KaG&${Lc_y--ueB;=q;#z0)Sbuc7F6d`Y zkqc`lW=&%jjQPLnaBnoe|EuM*{69BlO`EOQ*<&#;s9XE&a34~)hKKvJ{hbAWxNoUj zvk&((b!&LIC(?1$)+)NMBB@BBS^%nRz-G*D0H1$7?QzuBq3^MZ95u2-|OUd{{F z(Rso8Ixj~1q4E8@m|9`C4)CoHeykh*ttWAv7wED6=yYAs&%H5Rw~YG380?zHHB4LU z(RB#eYm$cL$Lwf5NB`c>LoDy}0egQAnEPQy{5FFUkNo%1(;ANJqISJE^n<b1ks4vzEN$NBBG!_f|o{?JE%Xur>5P2p$g%n{jIm}!O;$m z{@F+WY`+~-k9PRcpZn;~y>>X-!O{Qw=>NTTINHH6U;3CYy>>X-!7;!3m|yL;UFz2k zKjvc}^Rd?sM>{y?Zy)ow*A7QJIOcmF^S##&M?2VS1J=uH2C#NG+QD&s(#Q2luN{td za9scNasAV4Z~jNWw*`Ccgoe1j>b1ks4vrq!+xPgab~xI>`Fp^8|DAR?+V$_f@%Z%K zc(C`zgS|Ii%)Rko?~Mn0Z#>w0Y} z!yMahnlhI8!ZBa!uN|Cr^+Q4c9t4)kHu-Z6B`Ue|VJF&pV0vii#EU>Y} z!~$n5^TlqyoOkWuw5tcZI>l%Ms|~C+u-d?C6Qd2RHu{YI!N%22EU>Y_#sV7)Y%DRc zz!}SYv70Y_Qad>9>cOr~G1|at1FH?JHn7^nXalQ_{;YqnakaPoFti&ByRpE=0vk)* z_QTMgvCJ2a`7&R$gVU}a?CKPw4Xie>+Q4c9t4)kHu-cew`Ue|VJF&pV0vii#EU>Y} z!~$n5^Tlqy%w_H1w5tcZI>l%Ms|~C+u-d?C6Qd2RHm(Qs4>qoLVu6hXHWt`eU}K4i z1+Q4cPqYbP!u0Qn;Hm-JJfsF+=7T8!|V~L3c z&RFJ)-F&%z)(%d)da$cgj5e^^z-j}l4XidX+Q4e#x?TTZ<7y`s*jQj=fsF+=mY7)J zjAg#q&6mGBw1d;G9_;EAqYbP!u-d?C1FKDpHn7_Gdq@9Z<7y`s*jQj=fsF+=mY7)J zjAg#q&6mH|w1d;G9_;EAqYbP!u-d?C1FKDpHn7_GJ5m2&<7y`s*jQj=fsF+=mY7)J zjAg#q&6mG_wS&{H9_;EAqwW8)_nuLAR@L5q5TqP>krE&@A@mk{_Ch+Lg(kfTf=U(X zO{9e;HFQkqy@yV+cThxnCxjwJx^zLL2%7(Wt-Y_w^cne|G2Rd7ykFiAj&U(vd(OGm zZ_c}}`w47ru(`qJ2Ai8qZm_v=f31JmxY~&Y8w)lTY%JJVGO^$s%lTq=zC0h$4rjah zU^h>h++cHq%?&m;*xY1tgUyZS68eXYtDRV|v0!7t#)6F{6AR9OUu zv)z2Ko2N`}u(`qJ2AdmfZZf&S=Eid{{lmu9PAu41u(4oc!N!t_1?O1K7rXQ2Ii7Yn z+sy~NdCKGln;UFyu(`qJCX*X%ZahEKKWtp>#Da|l8w)lTY%G~raE|4Cu{&R$e`<%b z-F&c{r%Z0JxxwZJn;UFyGP%L##&cKw!^YK4EZA7Ev0!7t#*&Ez=UC1cyYuC_v35Ay z%?G=A%H#%{8*FZ{xxwZplN)SqJg?S2Y+UWcf{g_m3pN&PESXqvj^%u@J71o+YlpMl ze6X9ROm48b!R7{=8*FYexxwbfbAJ89#??+N*jTW!U}M3?l8FW9Sk4!_^W{B-b~xM3 z2fKO7bQv9KEpHWq9wxvqI*&#{~@W1KJV!L`HL zZa&z}Qzkdq++cHq%?&m;ncQG=<9&*LVEz1e?}^NZG3Lo{GdqU&6#9qt&pQ=>R~>Ic>j&s4R;+3s(#>yzJRb_~x0^#kjNXO-IFZ1=a=^~rBDJBH_M`hoSsGeGTd zw)nvlQ)cw(B3eIpZg@WBm8Ih$WK`;~A5g zb;hT^l^K)&{Vy4xJZCUZ*gSa#q8-k5{bM(0ew*1b{`-2wlF5hh<}Z^!KK-rC`26qp z$@t{?fO*2^$+HXXaJK6oyE*gQ%#PvT%7lp}lMmyuXC{Aq`dgVX`QP7^@yUI?dBWz& zGY9Q(w(B3eIrH1hj`82OC6-J+j5mLo{PF2;Wya@!KUc;l_v7XXnC*3GWp}v-^z^7|9-uUPws!s6E;uo&9%eXu7B+2%x^P0X21(u#`??T!+7(T$seEo zR%ZOpv;HW?%jC~}t9ioa$vw4pINSA)-JJPtX22GDm-}b}~ zF zI%4nLhgR<8Q@NLCau`8*FZzLyaX93pN&PEZA7Ev1DSw#)5M!=ZM{P;C!9gG1$#bCO6pJU~_}b4K_EK z++cHq&5e65W68vVjRhMEHWq9wnOLx~;2g_2Vt4M`-(_|Tc5{=-4K_E}++cHq%}pjZ z*xX=q zH`v_R$8HXJPdjWra2~H8?8L&q+?<2zzj0$e*v%6*f0#KkFP_ynUs=23)3cyDUjNvg zuS`C$dBWxoJ1^L|r@e6Xdkx26H#eEwU~_|=BW!N4xyj@Pn;UFyT&EdJCKhZg*jTW! zU}MR|f{g{|Sk4i<>%cW(X2)PRH<{dEbA!zdHaFPZWO9Se4K_EPO&Loj7HlloSg^5R zW68vVjRoge&JnwFPkX@X_e74tZf-KU!R7{=8*FZ{xyj@Pn;UFyJfk+2Of1+~u(4oc z!N!t_1se;_v794z*CFktuiy1J2D`b*P`iX2)PRH<{dEbA!zdHaFPZWO9Se4K_EPOBhQg7Hllo zSg^5RW68vVjRoge&JnwF=NU+5$6z-%ncQG=gUt;#H`v@{a)ZqcHaFf?8A~P>Y%JJV zu(4oc$;5(<1?O1K5xa9w-&WM`F&%^5++=ct%?&m;*xX=qlgSM>H`v^GXJjmySg^5R zW5LFPjU^KcHWr*?IY;cSL)t@LzpHf&c5{=-4K_E}++cHq%}pjZ*xX=qOm48b!R7{=8*FYexxwZJn_Jrd@E_mZ zV>cFTEZA7Ev1DSw#)5M!=ZM{PNP9fmuw!7?L1rCbbA!zdHaFPZWO9Se4K_F4Ul>a! z7HlloSg^5RW68vVjRoge&Jnxoz`K&nj=^qjGP%L#2AdmfZm_w@au`8*Fa8yEm3h zEZA7Ev0!7t#*&Ez8w<{{oFjJUp1wJ%e^05L^4 z3pN&PEZA7Ev1DSw#)5M!=ZM|8^G-0cW3Zc>Om48b!R7{=8*FYexxwZJn;U!2j3pBb zHWq9w*jTW!WMaX_f^#hAh~2rTZ~5!r$8ZdGbCbypHaFPZU~_}bO(r+k++cI#eTwnTm zjvwtj+xNGyK6&1r*)iDl17|{AlMnp1+0l$+NZ0j=`=U zIQ!9#AMHFJ^S7`*d1jT_G1&D3XFuBUqn+nY{ub6J&w?^L2D^UX>_ZM`hl|_?fB8o{j$G>^~pVKX2)RH51jpI$B%aIL;WqRPwovfI|jRc z;Os{`ezbFc=Wk(sa?h37G1&D3XFuBUqn-OEe+%oAdzs9R!LA=T`_Yac?c9&}TUejm zBV=|AcKyKFk9PcM=Q`it!usUeJF{c3>j%z$wBtuR*U$bI)+g7rnH_^&KXCS=9Y5N+ zF7>ytKDk!R>=^9&fwLd&_|eYwp1+0l$u(GJ$6(hFoc(CWkM`fZbWK_9{Eu5Z9W=Oe z$=4%-vG=_WD+bW zHRZ6W$F<(rX#GxE?AmfgdAhaeYa4XtI^^1N-fB;@UO0K9&V)0sEoUtDXzRl@H?H;* zXML#E?_ZnL@rTdR{GF9+HmiQF+~B^}7c2j``hVfRds|muu|X_%9zgVMV{@35XTE}^P_RAl2obTHQtlDuM7W#APxIRC*x^%1u?5-!{U1$8b z{`glH;;I+rejb!ahlBfW4Qp`zNUf zj+1H)TMvDYy^cwHI6HHmaaPpBO1~H$aW`M@%*bbf))|rK_#vl9{!blrTFmQ!$4-s; zemwNlScmDpcWSK9Vt+j))(yM$z_Qe_r_C?b`Dr?jJV4Ao3aV^aYXUzyTLV{{OYog)uMe)&t|M2mDwM z__rR2Ydw&U^+2B11NmDIe0N|C@GXPv_XyMj=Vi5qt%ttnddH-1B08Tec1hdg!)~Yi zu5H|>W;m~HJ~O;LyltK@Pj`CT{2zGWw{7S3ltOxAY1LLg+{8$h8w;qUV zJ&=#}K%UkE`CAXn%X(Pl^B2N?`A`1&eK9ZW&X@771Abf|{JU<%bv?<)btX^OpZwK@@4~DBzBQBmUX0@d_Z{jB zTMvEjWgL^fS?gT9=s9DohXZdoW{h#yK4RxF=CjuLAB{23%lDdZjQM}M*c4-&*ZseL zbF}kaai{x7yAGQV95veYIp?P9Mq3Zqtp~w!G22lBTbn3whN z$Te4oeXjHFiScvo@ksdj=%N?H|2p@+6LF{A?b9*lvv2u&jCt-p^}olM{{`1h7~{OK zJ731T4)}3>@b9`2*YzYH*O@$BfAUuszVosM_;yV8`!DK&`&_k#t%tt%&W=gnpmoj~ z@k*R8rux?laa=m!=y7qpx_!f^;y8BHZyt-|+a4=E9LK${PJJMbhp(M?e;g-w-t~`h z{Cw`)`{KBY-SuR=>x>`QAOF?^ajggPu^!0NdLV!6fq7XE16pr{{noqQiShe?_bWBz`ylCTG?l>Z@uYSDNh`8>;ZapyGdccqMfPd?O zxYh&tSP$fBJ&?ckz`U%7g=V=T>{AcAGR6;H?W*u|;-IU;|7qX9CgQ$-^EHvrua>wr z^4#RGYa{}~^?-ltfwH3qu^>ED!cNdQd4{vcpFm^TN zIbLS#q3^Rn$KXd^d7WG1`NN$1+*XV`$*H#&^I7J?JBoQ8dFq|T{Eyw~uHwA@GS%J1 z`Tp#LyNm0v_PD!?>$C93cNdSV*sTY~TMziL9`J8H5Z8JjAM1fUtq1bA9+;Q)u;qYJ zVgJ>Hn`8XypWPIGKL7WP;s4{sZ;ZIZkGUc8ndbX9M4pS^eSPG=-bL5Pys$f8#=8#q zaeeUbx)Im)Bp=tAJY9eCSC?1cx+|_Bf4cLD!PwQ5=f;_>hrZ9E9fKcvz6CCc>&ffy zyCSYzR$KMjmihGC|Hin^S#Gsaas9LYiMPjfQG1!Y;(F=1f%n99)aKibj_a$}?i(G~ zUD&M$##;~gu^#YmJrLJ=ARp_2Jgo=vw;q_6^>FU7zYF^$Q=S*&SATYR_?dR{)5HIl zo!>^>VY8eR`Rp~|gvj&b_lHIPyBs?#=7rsQV7&E!AL{}C)&p^)9-4ft2l90N$=`ao z>)9>inDF(CKMKaKro5-fY(4aS_u&})$S-`hejFc0uCYVMe-w~D^_bh@phU+!9C>*yow)&t|M2mDwM__rR2Ydw&U^+2B1 z1NmDI%*%S1`SKxQAF|szG5)XXuN8iV?z%?!U-S2?MckA3{88j{w)ps1AeRr{96yiwI0aFdLU2hf&8rpzMJ-Z!ME75-&1ov$$K&Ng{_Ca@7f%b zzUl6qdGqdZ{qWdMKkpd#d-LzsF`vt(_-V&Hr<`x+j`@Fk#7-UOwbsHrcAW2uOYG2b z9S%8b`;O~#>rUHuJYQh99vE*u;KzEvzx6;|>w$c%2lBKY$lrQkUe?1_6ZQ=Id}W^) zfAm)ShMzfC-7owv^v3=X_q7!cjC?*==Ag*)`bQ6n{C_p!pqLkS=gWB40Y9z}{#`fX zx}N0YI+LgCPyXt{-(j!@_}dP$f1iPR;61Eb!`4IJce{>Be%XQb;OnS6j8(y6}@|@|b$s+$LemrT+Yv_bYV!o?SHc70*F?;lj^=YrrFV+pa^}u-R0YBCQ z{;db%S`Xx7J&>pMK>pSP^Rgax9zT897n^0K82{TPX9+(G{$SSdzw|w`McntMog?!3 zV#@xJ=N*^zkNgiG-#_Ms-FjfW^?)Di0sqzmajggPu^!0NdLV!6VYfL~D%QZ&+sqq` zU441)pV@loyO+Q*_>qraW$`#)Y;f|D#kjLRv~)3_gWg!SnCA=+FIUWe&b?PC&THHs zRxHlu~XwD;L*ix06>c9v`q<4~(}S@MAsT-+Caf^*}z>19@5xw1!p>r9@mKl!W667!!NH8Ap+BZ9H3Df>(^TMvErt~dri^4MjLi+Z?p zn_&_6_(P75eC`}}LgYE=p(jTEQ*Lll%xkxQoD}o@V84@N9Ui^+{i9?21Fswvem)!boACec(nm(z zC0{-w@|pkj!z0h1u6uaoKXT^7V_w*;2gX|u_^}@FZ#@v#dLW;uhbB+!f&8t9Eswk) zYT)3Jrv_tJQ}#7wwjTQKm2wPz6`HbH1)X4Lt38zHHpdwaY#S$9>jL&m9`~ zUk6=rSlpLkw;mX8J>bWBz`ylCT=h>gn5c&Ul!5Ly+*sTY~TMziL9`J8H5Z8JjAM1fU zU4Qbo9{9UPUO(`+l4Sqh5!aLK+f-lJdg!|s)G_IAE_FT|bX;6dPCw1D9pf(g(a|0A z`R8j#bPUy{N;#_^F8V9!#l3SBO4svaeXG6{qT<057?~-##;~g zu^#YmJrLJ=ARp_2Jfj|({H+J(Wj&1BZdlmwIqdit|K15Fgr5}-KQa8bHaaQdp8w@Z zkyQj@a?n3 zaqpO^=7{6rX_NJj~XfAW!Ro{H+J( zWj*|I*{Q>R<>ynz__be}Jp5eu_sPQl#T!o=ao_ppB$3Zc6Z%D-bN;Mfw!F7fAY5;_`8uF6Zl({vVTvK;{$u$)fcuN*bkrCG3jqw zcFsF!?RcMc%!;kHakp7*P}_W79KUGWJojxa&^G_IZkVg>yneFHY;EVe)ZR0|K6k-5j_rEO0&#rXW}5lqxOd52^TzS;toA%{oE$g*JaPP-?vnv=T*YoZFy4B= zkM)3m>w&n|1Nm4Fw)ps1AeRr{96yiwI0aFdLU2NpZu+dsZKdC&Ji0t zvO_R-_2s*v%+^ESZ;>2>A9>O1caQVMC;!|tj!XBfv`;ag{+sU`$FbX2-Y<@C_r9`! z9QO`c_P{tE9=F6nahzQ9!Gq%XIn_4@#c>t8^}u-R0YBCQ{;db%S`Xx7J&>pMK>pSP z^Rgax+wSLKzi{r|V*DzT{xtktGS|-G|C~d1inuQ?uw&%&)WSPNo->}ledNEvcH76i zuv-s|w;u3gJ>cJZAg=X5KGp+yy8h&EJ@9v)JtpwCqhj6L31OBZC;#v>nV?B_k^+5jC1M{*TP8l>;*q^-d zZ>u=|@ttp6ML$27d*@a3f5CEpTiLkl-7@vc=2Px|^=|XLw|ySjkvBS`MA#H>H3qux;#Dn!8j&-Hfl^TcJ<|3$jsIQ-%Dn841VNYF8f0q zAJ%&0zNo`R-}__K=eA$mA9Z{6dw+_0zG2J*QRh?r?7^u2)8BkB`eL7@ABuk2bp3~- zkFdL*jCY;!cJZAg=X5KGp+yS`XxJJ!GvX zRs(#)i0tj@Q$KLNR-f24JpQ?E*T0PaeBCbNQ$KLNH=Ni# zBmTKh)W3}Xe4i-eQ$KKi7BR7B6!_=4g#Kmx=jReKKJ^3VXI~S0CWe2WgXv$!e|`=o z<5NFye%3m%XR!F^xvTzV{O9McGCuVK=V$v9d*+XSp7ZNp#(#d!FXK}`aDJCGv3E@P z=e?5tW&G#&N-{q61Lt>_6MLtLf8Jy2U&eoak169*KX86mKCyS`_~*U3{$>2<_vSJ_ z^#kX<857&Hfq(XC=wHTv-lrksQ$KLt3pBAkLilH2kp5--=Y2skKJ^3Vy=N2KlZJox zq3K`7f8K{C<5NFy-s?EAJ&^ck-=qFz{O5g-GCuVK=e@NP+jEP5_Sx!R#(&;tE8|l? zaNf&3u|3{3|K@vA{j)qWqj%fPJ4h0b=$i?D%Nx3r~ZBZUJn29xBBUw z-t}<(H|88;{qx(jZ?>fUv?cAcEouL4N&9k3+OJ#EKHie{_m;Hpx1{~R)!w^qtmAvv zjnz-@y0QB2T{qUaz3axBPw%?1=GnV$toiq@8|%D!_kAVpr!8rpZAtrYOWK!P(th2N z_VJdqzqh1)za{MluJ+z_ejVSt&aZxY*ZI|d?>fK6?Oo^Be0taUHP7C4e$BskonO*B zxRTz@RlEA8YmEQ+ch$L8u^!TOOZDS#(|fCu-e;Bco~xwyUnRX4E9re%N$=50dcRiE zd$*F_$5p%aklx=_Kh{Hf-&f;W59$42&C_~F?-NUU&sfs?tdibymGu6rr1xSay)P^2 zJz7cc*GhWtR?_>pYPTNJ`@8DLdPwj4YTT%Y@7@pAJgtZHKCz@dz$NVsu68v|=k${H z02i(etcP@+Q2qGZv~RYg{j??Rvn^@=ZAtrbOWLnn(mvjj_V<>w@3*A=z}0R&r2WIy zkM)rD8`rqjL)xEQ^Ryn)e&&+)IhVAbwxoTwh5f)DXVSjhlJ@JCw2!x>{kid zaJ5?xY5#EbV?Ct(#wG1TuK9R;Nc)y+{vIFFH-;sBdssZbbIecI0F|u)t|c;C16~jC z+w@&tN#E<0^c`PG-}jaD-Cs%H1D5oiU`gK(mh@d=N#7e*yY-O1Ppp2dhx9#TjcYxm z?;mTP)HEi;r^ko%y<|!6WJ`KiTkYzb?x{<9CtJ8Tw;s}cdiCRP(|gR4-fx!l z-m|3lp(VX1E$RJfN$*uldf!^od)SiR&sMwjklyE3Kh{Hf|6Ai)59xhz&C_~F@0Uw@ z?_ARR&63`Gmh?Wfr1zvHy+1AKy=qDCTT6NmThja4YPTNJ``qfsdPwhoYh3Fgy)UkL zS`X>{a!GqWOWF%s?P{9t!AsinS-6+C9@2e%_2X~TKFN~yPnNW=vZVc%CGEp3X@6!( z`!-A3&soww&yx0kR=f3(_KQ|O)lJ-@WwBNF% zeV8Tf&n#)*W=Z=wOWNmI(*DnCw;s}d(dx%~Nc&4`Tmhy5QuDMP()TYVy^}5JU2V0iX?jLo(mUD0 zvu^7lJ@>AD{B3%VSlHPlk^ggtt_oOAgKP~CKYDw=~OL`Am()-zJw;s~_-0H`A zNbi4ZTIhnDo7w50c^CB0WI>3wTS?_o=NKU?kA zLwcWE{a6p_{cnwHJ*4-=HBajyynZ__^N zlJ-}ZwC}p4{n#b#(=KWMc1ioXOWN;U(mwE#_J>!y^^o?HS3lN6+J9c-S`TTzdd<^% zNc-DM+V@`4{_4X1aL1?p*d^`LE@}UEN&C7>+V5S`KJb$EhgZAxkoJ>TKh{Iqe_rES z4{5)8&C_~F``b&}6JB_a;PWWoFK~~L-a%Bh26&f|*&6VD1iwxDs7u;kUDCemlJ;Yl zv`@RF{o5t&>n>@(cS-xeOWGe^?bbuuPhS044{85-jcYxm{pvMO^-cTR>%6?bNc*cx z+IL;je(aL=X_vHryQF>HCGGcat}SC9cuD)itKE7?`^l>x>mltwuW_x1v|qjEX+5O< z?Irz9ypsM_UbU-ldgfWu-^45FZ{<~Xyw5+WhxB*k3V$EZ`&|A$p84?i@w_kQ@8g+2 ze;?21Z2WyZ=gZ&6^SK;q`xOn(%%^<>F*CT_Zsnc2}=5V1=Vgnq`z-a z{a6p_?;+H<)pLnr2R!TPwOG= zM=EKbQc3$^O4=t=(*Bu}_SKZM-=?H}I3?}RDQVwMN&9)K-Fis-f2tqrA?+8cajl26 zzo_PEJ*53e|E=z5+Pp7osdZ**!+krMn|Ea46ZSnaWBMLv^zX3+|1#r!@0>aNgnduP zn7-#V{rgT3|1#tAc}>nf;s5SBO8@Q&!M}|Ed>ticpRoHhYW}@_9hvdzwR&d8xUVB~ z_6fUBi7|ce6V2ayL;TB(cVAQH>=SmM17rF=m(ah@BJeLW-hC07vrpK4CXDI(98CW{ z`@+A>c=x4b&OTxHDKVz+b65TQtQG$<^>;Q^nH)1f8Sl=UuL}frZQ)r@PGH-T>tJl!M}{p{N7y7 zKH*glyS1~|0vEL&{`JP4TYfmc@*7KR-1+F>uD!kO2Ax-j++6MF9$*%1V?XRNxjj1f({&6vk00D+=JNNoyUZNr8}^^3^Ubl(*YRUMnZ0ww zKI1DdaqsM%y>@=C^0!OQ-uZIZag|SAbGFXIM?G74!lbiyo*wf|<>?Qbr8CW3UA}G9 zOr6cI>c)EH?io6(?AYaNFPg5iJ=hpkZ zAF+ON<9n6KVcCcOTAAEBkG)%&oNv7MoyyE5#VRR>lE#$u+md{i6sx2hO3JOIoJ*QZ znXGizt(kB6_TP`!e46=|HD~MU-psdbw^Ns!`IcFp>vA*S^3nla-J7*7&#c_lx0!G0 zH=w(o&3wy&{kv=4%(o01*wv+(Z^UY}ZoT?>H*Qk{t#RYK+|)+v!7IDm)J$vnpLV&a zrPcy7cDbps)(p2kR&#D@ul3rHE;lvV`r`|aR(n&ctp#@La#O>tZ~t*~r&rId5xaML zjWKt>*kykE-WuJ$!{@h`c9~eyecokqxMYQHzmwaIKkqU*-!-hu%;mY$yUZNr=9o}k zdHn90!SAK8G^~-JF@AB72 z4k;h)c3ZVybmux{xxaN|-QHQN%ymtd&%S((a?jO|)-lBT!`n|+CWpfw?=oX{9@b@k zd(HG+#^;;Ae5#Ho)(6);S(zL<4?Izs+=e{zcx7^4sqq}{HrIS*y>FkZeD?YS%E*hJuY7O6xyt@~zgT&W zP5YPjwtuet`yq3bL$`XRGBw=vPH@vxm8s{Z<||XrO)pfYo|_)2Og%TfQ<-{hda5$@ z-1J&y>bdE`%G7hyo0X|&V=eLNl%;*{->UtwohG#8Z@%hZ_TK)ZYQJFb`N~pXy%g+u zt?{d{)M%Ospn{ zYA2s2x8Nq{%H*85lg4z?Z#fUv@r}>mCRQiq(7FH8ZqGLP1UEUiZ@%LCPA~sp#-zF9 zvyQst$BU;omwJp;}uzdvEN3eYa+eff{1lvcjeFW1Z^e;^B$n-VG6YLyYIG(^B zPhgKHu*VbF;|c8X1on6Wdpvv60(R>K}Y9mDYx_V@{V{DeJz!X7_ikDsu| zPnfxIUVuF>z@8Ui&kL~U1=#Zf?0Et9ya0P%faxR7M{uu~gE4IdC3?$&K?MOwODKVdld57iNx$>v_L7rk?kEzpdwexba!f`*0JhlX9r%ee6wc z^}G*z-iJBwbFPQE-rzb%<~qkQT<5_2mg^iCpIqm_&3x;14onVQ=fLE~bq?Ijw_fMK z&3rptU%}0MgPU5a*L&E#-h-POsMmXNQycYq4{mCvUhlz8E!FEixT&#vy$3h7SFiWr zrY7t49?bO~*O@S}xMqgQf$LkxaD5B&Tdr?md~$sY6N~Fxm>jsig~^TUTbP`=zJ-~K zvA8~8aObZ7rpG(w+AcS}-}z!dx0jn^LZ>~p%gwQ(bNjKQs-NZ<(s`pf@8h#Mwsf}K z^|s2*F{ktMU)^50ITm%^KK_o%&GD*}j#nMdmHd`5oI_!L%ehsboO5AfaW00*fpauW zZk)Sea^{>4GZ)UkFmsffb8&}rC3fnKb12-LLpz*X;pW`h;hYOM=iCnGVz@aMcQ{AG z%{jWmxf^cI-5t*9aC1)YaIS}&b3L_PnOK}Fu~YM$Lt*Nfb1O_ebIygSXU@ei^~^aM zrk*)>!_+h9beMYP{0mdhiR*d4H>RHVd%vyceVAiHidE11*g1xz-0FEBJIAXumwLT{ zo#Rzn+j{+j-RmFN>mS(bAK2?3*y|tI>mS(bAK2?3nCl<)^}4S9ws&0zdtC>6T?aR{ zRIlq`uj^p1>tL_zV9u?ltunf<^E%JI*gk)!F5iChU)t9_-sPjVeYbt}(PQeEUta!E z`_O~hm8aU_@9pKU>{Nbxhp*a0zkhG#XO3?Ejp$Q;U-_l$CbVx@`o79DzTU4h>Dzy- zy!Q5!bdDbRr^=_UIZ5aCjUKE#;=F#HpS|}`<&mTR-TwQok5ry!@Hg$t?s&BFvk!mK z{`Bc?ug!A8r|suPb$ji#^FL^RJG9$t{TF?^{rMGL9=iLh?M+5?d5aUCZ{N9pm%qB> zsrFkRb$@%xLXWgBTcFFwPI-U(>i%8-^PD)gz3)ri9F}+3t(PrTU8 z`EQHd)}C{z2de$LUyW){IQag`$G&n)`;l9^bARfHQSIHo?5@e{Tin)Ocbo27ZMp58 z?XTYGuHjw#jc)(>;_lim{F{5*f4rc(=DTkFr}kAZbhY^SsYlzp?9%0Z?|i0x@ZY=r z+i2H1diHK#KmWxut+S5r^3)qX);eRA@im{hCw-u`%TnFrz%lFnzBORS7pncLA!AxA zj_n>RM*r}x);()?k0GPJxvh21doR~9yT3K6_2I}@D}V3fTUvW;`IpN3%`>Vsa`HDS zZ+`Htt)Z8_S^47+Zg0IjclTKFn?3Jt{dS-3vEuHR+pU*Q?j9=+p69;S*gd+(iW{bV zsP*;~-DAbCj(DQ=$_`yF<+;|%dvtlld0uW^ym*(-`r8|=$FJ)Cw%<|jwSN0@*XNWM zebPGP*>0@82K=M7%~{a8o}uH@K;*nls$gTb&Es)M1??+|*}_xx-D}wpbImspl4J1vhmb^J?n9 zHTPG43HywmLO{$G!eX#G$1ILB)0)?;Aq zSKIYi4STGHJyydWt6`7Tu*YhcV>RblnDZ>haJZ?}dTfWATCK-?xT)28E`Xa_t>*~1 zsny7*sny7{snrhW8pbrW+HqdZv8A)zj~)p7IbS_knelg>`*3CaOfl`FmGQs8CXZDn z?%*vSuS`B$&-O%R@*Ht$m&t$MJG#ugv@>7Fvkv-Uee}<|8JG1mAJ*ACIaiuL=TPT` zUjLit+5dNqG@|uCb&d4NgX3#mEjH8Ko#%J#o}2#svw1r2F48?`O*(M?&J@c$TgP0s z+Jc?ohdony--{RSEIW0VcUofcdQU|Cb5Dd%oe9B!UP^K7}sg8xtZG52!LA^S|v;XCR1eDLJ6FE*HG2pkj6UTM)_o-L&J z3-y@>V|=Co`%DA&nFj1L4cKQIu+KDLpJ~86(^ziCJ6FAS=BHY}oN3Kf;eWpJRO=_7 zu3q_1D?Hok|Ke(uADR03*1XUBsPZa5dbzdlTdP*S^qMzXYtGi?0kgi}dT!rR?H_LR zS!?+(T9pUP@J(yZ>$|-EG~X*vpV{T(&X~MtANlEj6~`Yp?es-IYu-Oo^PaHl|BJ7F zP>g%i@Y##`Ec5IB#XQfucFtn{_f9ugabDPeJ!q|(599y1!P=Ga)7fmD%J|=VwRI~K z_rht1R3@J(Z|^dBUbEzSU3-)NeTR0Lc};Uxmzl42*1_?tkA7G;{j;9NWu483^*2v+ zF@N=%_E)!ucCgyPY6q(wtah;4!DtwX61?cCgyPY6q)bwfD4x)ecrWSnXi7gVhdJJNxe1nKxl8sf_;z z4?U?eahH7a^vdLO(X8iGCeO=1IKOLe^8e*pzpKo=IOj2U=Bu4`a6IdyAJ$F(tfz5V zXY*nG%@gg+AMKczI?9Y;?&{8(z-kAp9jtb++QDj9?LF;awS(0TR=aBNX$Pwvtah;4 z!DtwS(2J z+jpCkucu$69>bqLWRvp2#{(;`c;%+$%JB6W?tu=(PieVopo?L>!TmmP5-Q? zaam{cVg1b$UCh7fvpTP?j^DA`VOKj??O?To)ecrWSnaC4ryZZr?rCvhV0k`;MNq@91Uwjvlw~=zaT+W2Sw_vBJLN7-HXXY_ab+W@_hHdcCgx2drv!9 z?O?To)vnrm+QDiEs~xO%u-d_D2dkZS`%dk!s~xO%u-d_D2diDR_q2o64puu@?W(<} z9jtb++QDiEs~xO%u-bXP^FD~)^!|vR^}dN-_I`>U_dbi>_x_7xruStWE4*Lh7~*{# z#}@DJIA&_+Smbz)QTpN7rGJiT#^qRNJ{&X6lVhg&bIf#J*u6huy!TD`@qP;b-e(cl z`!DkGzKlG*Un76-)?3SM?b8a{#j4svd-qi`kN=Zm_Nr%=GE2lJ61dF zY6q(wtah;4!DJ(~PT(|K|R&GI5*x%F5)^+;5Iy zeaN%953Nl8&HZU*=G7d_Ds#-#&N?`r_0bROrhnGcxU94Ju>R(WF6Q66M`(9-toM4A z)egJb!DdcCgyPYDXZI_e-r}@0{_NQM~Hr?hQl{XoA zMHxQyi^?xQepUI?TV4Ko`fJNJvwd0Zvu$>L*e^fk#u$Iz88?TYFZLW2{x_NYwurm< z=C?;adk?uI^1S5LJ0kxk*O(XfNyfcf<1+rh%ipeypQF!tvoikYAN_h|;yyIbUn-N& zhtIrPnLMw5<(10hf5^IBW?pa2(q-nWopo?L>!TmmP5-Q?aam{cVg1b$UCdv-&@r>x zVOKj??O?To)ecrWSnXi7gVhdJJ6P>twS(0TRy$bjV6}tQ4puwu%-!*<39NRo+QDiE zs~xO%u-d_D2df>dcCgyPY6q(wtah;4!DlkC!WyK@9%p8wCr_0P;J8R;2)=EFDq5fH0 zuf%(zj>mI`J)~4Qb$?s)SWef z)ecrWSnXi7gVhdJJ6P>twS(0TRy$bjV6}tQ4puu@?O?Uj&fFc(n!suYs~xO%u-d_D z2df>dcCgyPY6q(wtah;4!DapSiPkOWO6!?(sCCY{)%xe0YhQ4! zV!v>XwvRY>+h3g1?K`ejv~vyMc&-if!!?8cxt1_4*BIu*wTgLitz!OMt2i(0)-B_$ zXZ%>___zLvYhRF${X(Ah5&7F+%*(!GzS>y_$Fn~AVcqo4dK#B?HXqjCJkiDc)e9Xn zs~vW=gVhdJJ6P>twS(2J+I!l;Y6q(wtajDj(+*ZUSnXi7gVhdJJ6P?s+jnY*UF~4C zgVhdJJ6P?iy{8?lcCgyPYFF(&?O?To)ecrWSnXi7gVoEvYwnfmwG(50KJ>WC{Py!B zkFSi+cTYL7GO^bA#mSY);gav2QW@=z*!a}SRe?djEycG_7J z$Fo-YVGZ@q+8UQNHy^YxPqZ_Cv~ynAw>kSaH7?^<8+3SO{51F8mGOV!Pxh}&+;NtwX61?cCgyPY6q)bwfD4x)ecrWSnXi7gVhdJJMGNf z@vI4~cCgyPY6q(wtajDj(+*ZUSnXi7tM;CDu-d_D2df>dcCgyPYG>ay>t1VyG2Y+t zTkr4i$-W!L6U+NMa`65R?YzGuXYcQri}!cT(fd2J)6SYWp0&~sYp8$L*0`*>`JkP7 zqMiApo%6!({So86Z^DoFQ~38ji@4r@k&pLfy_$Fn~AVcqo4 zdK#B?HXqjCJkiDc(T;hkqpWu7&YHk#2df>db}+fI=CImTdrv!9?O?To)vnrm+QDiE zs~xO%u-d_D2dkZS@9)$OyV}8O2df>dcCgx2drv!9?O?To)vnrm+QDiEs~xO%u-d_D z2dmxY>)*t+G{@MnLpJX6H76cCw%?9jKK_e?$4+%nmq+e!$k=Pn?efE;4;lN~*e@$oaOl|PTD#i+a`~ZSSAF<9`;z@`iShRg z>N0*d-lfaw_QH4ganuab0Kf zasA0tUC2M{1vmE#RlCfL$F7dBI>PD*t0SzAusXu(2&*Hkj@nrt$Fpv*I>PD*t0SzA zusXu(2&*Hkj<7ny>IkbNtd6ic!s-aCBdm_v(b4hf2&*Hkj<7ny>IkbNoONujkwV{n zPS_)K-|!!ML_O@X{hm=Lr`@w>)X%q5?G<&k$_9Hyy={2-UQvhb^Y@DSyy~*OqHeKU z&y2Uu@nhfN-@YTReMdg_9eLVcWEz(VReMn5mrZ79pS7a&mYux(D6Hj?lXSAL)62-?RJbh z`SIO5M*aL@%AKOFCakwp)Z2`Q?etw8p0`uf=bo4D^j+OHcKeR;_8orgJN(;s#I^6p z$G#&^`-}YTJLaYR?8~>0@pmr2efYWLiS5Gw0l(TV;!Zx_c9G9RuWcK7-gWb~k^efw zw~cvif8w?=U+nfBIkbN ztd6ic!bkUXgw;{IeW#At)e%-lSRG+?gw+vNM_3(Ub%fOsR!3MJVReMn5mrZ79bt9U zZr`aRc6Ef+5mrZ79bt8ZvyRPs^U(L}<2DK1pZ{!=sE3cX*)-~8j=MIE`Z-~W&7!XE zAF^50+xSB^i#lBQ+|8msm$_uKs9Wsz9pmjg{MdK+x9^B+-;s}fN1pZ<`P+BQOZ&E$ zZ5-o|SZ?F+v)kiC!~e?r4vn~v&NDRfIqlVrBF`gk+9>j$=FE*^Uh|)@QOp;+eaCqF z4nOuC{_Q*B+IQq*-;t+%NB;I5^Rn;yvVEtHXswR0I>PD*t0SzAusXu(2&IkbNtd6ic!s-aCBdm_FI>PFx-M&*t?CJ=sBdm_FI>PD* zXC0e;N1^Z7W7iDbM|`?w)WfY?uN8Ij+8t{}{cJe-+EG_0ue)~C+lYhL{;m$sSv%_U zi;LF&u5KHFlE>^t(b z@5tZ2V_x=MU$*bm5v|n`R!3MJVReMn5mrZdnx2lZI%>D?)DgQn!s-aCBdm_FI>PD* zt0SzAusXu(2&*Hkj<7ny>IkbNtd834J9Wgaj<7ny>IkbNtd4Njak&{+2z`$|W`)pw zm%ptL^>D~mD@L7Mar=rK40w$9Ve= zKlUB|?K|SycjRN=k*EDd{`MX7(*E|v%g6Z1mt8*m{OytD!vFnyFBfsQoO`**XO5Q# zMV?dKFevgr_q0JVuN#jW6!XPy-!b04!;gK3fBTNO_8s}ycjRf`k-vS%yzINaY~QIP zTB{?hj<7ny>IkbNtd6ic!s@8qzEel+>IkbNtd6ic!s-aCBdm_FI>PD*t0SzAusXu( z2&*Hkj<7mvx9`*uyE?+^2&*Hkj<7nyS;uC7d+58~(Tjxc13y_L>Y;48Xw=E>w=Ej= z^ZcZXMP2=1?Zu+r1|GOr)Zux<7mNBldcPrhno{wF(P~^Y;sSCxt_B(c= zm@jtwj`8*#e(XE^+jqpZ@5sl#BTxH|{OvpDW#9E>`%WFvS{-3^gw+vNM_3(Ub%fOs zR!8mjojPJyM_3(Ub%fOsR!3MJVReMn5mrZ79bt8Z)e%-lSRG+?gw;{IeW#At)e%-l zSRG+?gw+wwIyUc1Lf`3*nk#hw@T0k+9wyyl?x>TcZk;>oXXN(=L|whK=76ZT5BDGN zT^*h|AnJ3S-wpV#ZX3IO$9Ve=KlUB|?K|SycjRN=k*EDd{`MX7(*DblbH?~Hmzp#D z9R5)M@W1h%{Uh${{rg8gSG+h!IU@i0PMIU-wc;^z#C);acZ|31@MGWM-@YTR zeMdg_9eLV!PD*t0TO9Pe)iCwcB^y-)yk87` z#~nF+=zi;m(?>l#wD}BCC!gOkL)6bMlgt=(b;%ktM!k*NZ^o#@`Ola!>T{Y4XNoVwYh zQ75Bso;2!bV86+tu6A2}vZ%L%e>K^6b$HrjQJ+trKiPM6+t}?p#@l!JvG4G2-x1fo zBOm*YJnb*?x9^yj_J3YDNsOOsiAloGIkbNtd6ic!s-aCBdm_FI>PD*t0SzAusXu( z2&*Hkj@s=zb;PcYusXu(2&*Hkj&RnIy+-QW`Re_Sx*t03gO2rZ)ny-ctdoB?|9*n? z^U}XQin`k3sE?!G4*ko=QHR^i`AO905=(s&b&K74X1sleANvmf_8oEUJMyvb$kYBJ zfBTMkY5&cj_hS4XxB6@NIq#%*!~d#Jz7uhOy5u{N&tI>9JMz4LgSR99H)nV|<~75= z-irBRx9=El-{Hq~!@uiET-TX=Tz~RZ7xK67n3sLmm+d=sL~C_~)e%-lSRG+?gw+vN zM_3)T+jr`ST^(U{gw+vNM_3(Ub%fOsR!3MJVReMn5mrZ79bt8Z)e%-l?e?8IVpm64 z9bt8Z)e%-lIP2K#8w-7heDPH1KG`!*M?EZa$um(WCvE#|)X#3;JR5cOmtT*IdYkOk zaZ!hFHGf;$^TOSWKNoe2-M(YIeTN_W4*&KYaqT%zU#~OojRhmI>PD*t0SzAusXu(2&*Hkj@s=zb;PcYusXu( z2&*Hkj<7ny>IkbNtd6ic!s-aCBdm_FI>PD*tD|=NP93qUBdm_FI>PD*t0SCsZ1!k| zzR&*s&d~kzC+~`S7&G$jsFPW?z9;JEldtZHy4v&b(NS-w{dsiM;V)+$6ZN^~qGO_N zvDrqBcj}1N>IkbNtd6ic!s-aCBdm_FI%>D?)DgQn!s-aCBdm_FI>PD*t0SzAusXu( z2&*Hkj<7ny>IkbNtd834J9Wgaj<7ny>IkbNtd4NjvH9=NcgIghgzo(x9~t$q&hIXY zI=Og@i=%!H`{LrLtA8AFNz~gMFJ2OL_|KUyjrx3I;H6Qw*zG&U+jsb}@9=Nm5!b#W zAN!6x?Jx4T@0geNc^Cg(jNf&W3&YQf$6OHpUwiQUh&$=P^CO=VuQ)IA+;y$B-@apB_FZ4L@6@sR|6A$^t0SzA zusXu(2&*Hkj<7mvx9`*uyE?+^2&*Hkj<7ny>IgUgt2)B!2&*Hkj<7ny>IkbNtd6ic z!s@8qzEel+>IkbNtd6ic!s-ZT9r=b!ec$`|n9%*oM~;npc>4U~qD~gwd|1@a_dg#N zb#>H1$49+gG5+|d!(lU?5cRqBf+s}XVz=)YZ{Oj^zQezLM_l`keC#{&w7%zU#~OojRhmI>PD*t0SzAusXu(2&*Hkj@s=z zb;PcYusXu(2&*Hkj<7ny>IkbNtd6ic!s-am-O~|PM_3)}n4XTXI%>D?)DgQn)-gRD zVReMn5mrYy>)7mn3w_^xVbjokr!zK>dboS>Euv0#zjVu}pLyThD(Y(1ziu7%w&OM1 zL>K40w$9Ve=KlUB|?K|SycjRN=k*EDd{`MX7(!S@=p)vmN=WZB& zF8t^E;s3p1>qXpU*BTP}w0^X1qP#8rdlWFb;|2&$9%EdcZ|31@MGWM-@YTR zeMdg_9eLV!PD*t0SzAusUkD@6-{yI>PD*t0SzA zusXu(2&*Hkj<7ny>IkbNtd6ic!s-aCBdm_v?K^eEu8y!e!s-aCBdm^a*0Fgn8T$U~ z*||ga1AjYD)WZ`4=ZiY|&4~GmTE%8a{jYx#b_ThW`mi{UG8F`Oz$q z&t|L49C`lNVKYVk>rFOO%t`x9=El-{Hr;!@qq;T>FlE>^t(b@5tZ2V_x=M zU$*bm5v|n`R!3MJVReMn5mrZ79bt9UZr`aRc6Ef+5mrZ79bt8Z)e%-lSRG+?gw+vN zM_3(Ub%fOsR!3MJwcB^uu)pX505!=PvwK+vk~Y9sE|?_g~oUJI330__6Qs zZ{HEuz9S#|jy&xz^0)7pm-Z!2dMw75{tt(rQ(phmcmBV+FXE0l;P;WwlY5MfJXd?a z9r<_uJtpS0&&^|EzSvy{#=AcFaozAA>)FJ0oyo`bCr@=DfBTMk*>`=}zEelER!3MJ zVReMn5mrZ79bt8Z)ls{Br;gaw5mrZ79bt8Z)e%-lSRG+?gw+vNM|hE*j<7ny>IkbN ztd6icYPavy5xY9V>If4T9bt8Z)e-(r9XAPmFI{-6(EXUncZ_;?>)>6ZPOe>lkEowv zoBlHDYRBF7k9s@eX9qUh8sTT3n+JdA|K;T)?i0@~9r^s@4~s{hQ)SRG+?gw+vNM_3(U zb%fPXyM3pQ*wqnMM_3(Ub%fOsR>wNN`TMTu3#%inj<7n`@jV@3b%fOsR!3MJVRh7Q z->D;Zb%fOsR!3MJVReMFjx!zG?+W$(`$ccuqwd3(*lD!&@Zx-zkG4)G-1YQm>*wW< zzaDK}J+scVW30CgH<)9L=eu36o_CDryBFtMV2tNG?Diew?K}L~clfvOh-=@Gk9|j; z_8s}#cl-Zh#w(J2m6Xrml;_}-|KK#Q!D+sO(>e@J>oYj5+bU^2 zS4r!WJ3r2&*Hkj<7ny>IkbNtd6icYPavy5xY9V>IkbN ztd6ic!s-aCW6xf7?2WHF!i}G*Bi#6}I>Jrdsw3RwQ+0%!JgbgyGq0*6+{~-$sNKF} zJUU{>4?4p5M@N{rp6|#99kDm_syf2Wyh6w3zO|*kO+U8Oz3J1I_0aTh%Q|WLx<%aP zy$b!_vaXurK+Ae-jt?#CusNQztk33n(z0%`ThENQ&hcaYdsXKFx7E@@$Uhk$-dik9jr6|Cld!*Mae_4}M%X z{KtAWab0KfasA0tUC7_QV_x=MU$*bm5v|n`R!3MJVReMn5mrZ79bt9UZr`aRc6Ef+ z5mrZ79bt8Z)v=E6=?JSMtd6ic*6}?ZVReMn5mrZ79bt9UZr`aRc6Ef+5pK@oRYzDI zVReN6Q^%)5-{$%=bZ@RpqaK>;)u@x^IyUO3xxS6MYOZ^u-kR&-sKe&^IqI{yevZ1u zZr?H9zQd1whkyHyxb_|S*mvYBmeLE?y1yw|H<~9 zI-<2Y!s-aCBdm_FI>PD*t0SzA+U+}a#IBC8I>PD*t0SzAusXuc{aw`&R!3MJVReLA zPwEF&M_3(Ub%fOsR!8mjojPJyM_3(Ub%fOsR!2DN*gP*P>f1bTDeB%lhbbP1o98pd zI%%HU6zivXo>Q!=<~dKX-kRq>#q(YByr_7-Yn~Ss&v)4EJI330__6QsZ{HEuz9S#| zjy&x<^0)7pm-goQSd4F;n}wg|d0O~yp0h>V=J{LX(>#}pJe%irk$>}iFXq)e-;4QT zcO4k-`ryZP!@uiET-TX=Tz~RZ7xK67n3w0fzHHyABU-B?td6ic!s-aCBdm_FI>PFx z-M&*t?CJ=sBdm_FI>PD*t0SzAusXu(2&*Hkj<7ny>IkbNtd6icYPavy5xY9V>IkbN ztd6ic!db`WS|#*t-Y7ke-U-nyw`|&YuqVn3wkEeNc>V-V=qN=KWFlZ{90K+~$2# zWEz(VReMn5mrZ79pS8FvmYSzZQiGc?#+AlsE6kLd(=tuUOwt) z?)8p{x@z9zN4+)g_oEJ*{TorA&3=HWTkQ57PMUpaQ9sT8w5Y3Q-&)jLv!5;Mu-X3>_1Wxyi@L>b z-!b04!;gK3fBTNO_8s}ycjRe*k-vS%ytFs_{bGEx4>0^R`vb#&vu`lsHv0)9pJtz7 z$jQpGZiZQQdzhcZ6yM4!a`wl<$9scb*;@WrQW8aadeMkQG9rLp9`m%kej?Mqi z{=n)VR!3MJVReMn5mrZ79bt9UZr`aRc6Ef+5mrZ79bt8Z)e&y~S9OHd5mrZ79bt8Z z)e%-lSRG+?gw;{IeW#At)e%-lSRG+?gw+wwIyTQGL*Hhazo$M|O7d-!Sg!-xN7pM1n^_RmK?&A$4`v)OMS`8WIXV_wbv{FpCx`;PJU9e(UP z{M&cLweQHsz9Ucjj{NOA=4IdYW&2JY(OMm0b%fOsR!3MJVReMn5mra-_MJLnS4UVK zVReMn5mrZ79bt8Z)e%-lSRG+?gw+vNM_3(Ub%fPXyM3pQ*wqnMM_3(Ub%fOs&N?>F zi$dS#`=HQ$=oU{zJv84FMV&O?8Abgx-ycO?HQyygy*1w}MIAQZH${Cm-#10wVz=)Y zZ{Oj^zQezLM_l`keC#{&w7XTFe)_eaCqF4nOuC{_Q*B+IQq*-;t+%_y4hXf3e$c+gaBUGy>fq zpg>4yg%E)j8b}C2*M8S)JSYg1rUt8EtRNC8e+<&@{@Jz~k+i8bm=tIbrD)RKKOi(p zFoeC=T7VppkfvLMu>z(cYC=tfpjJ6Rygtu*zT^G%4X4In_Suz@`HXqZam{hx_jBKK zj){MHXI$mo+qk?-M_Q*NoQ`lh!s!U7Bb<(KI>PCgy}V0D_H=~P5l%-q9pQ9@(-BTb zI33}1gwqjDM>rkfbcE9pPDeN$vzK@2$exaHI>PA)rz4z>@Jk&(=coMO>AU@~r~CHF z-h9~p*_$WZS9|kk`)zMtZ6EHBB z9Y5tA|K**2%R79^J3Pxf{L4GzD(~LLrkfbcE9pPRH!!T{^O- zBb<(KI>PA)rz4z>a5}>22&W^Qj&M4{=?JGIoQ`lh!s(d3yh}&+bcE9pPDeN$;dF#w z>bUw9uhVz+A6}>X>O#D3KCE8E>*mSoNW5+cl?)k`YrG9Dev$szwj^bj4S)v*ny$m_m?tlr4$zK^Wl$m_nFu$On*7ax9#8~?>qzr`7!;*V##;9uSuS9$j~F7MKj z*69eRBb<(KI>PA)rz4z>a5`o$@6wSy9pQ9@(-BTbI33}1gwqjDM>rkfbcE9pPDeN$ z;dF%45l+YKa5}>22&W_bQpeS6I(=8~=yYElq?-?`k96~7b(3!Xte(=% ztJPV$`L_B?Z|31Qf8^%p>NUNYx3f2&wQrvD)BNYZywh)ahfjHjXZeMHd1qYNSD)(I zuWr@(Sv{-szdBdf@9JM2pVh@Wo~xI2{8wM=#<(+YrcW>kJE*)u|j&M4{=?JGIoQ`lh!mGRW7%!ZT*~`0hWKTyp9pQ9@(-BTb zI33}1gwqjDM>rkfbcE9pPDeN$;dF%4F?)HJj_m0Orz4z>a5}>22*1>E-z87q)%QEy zSNHGc!|DOvJXxK^~emS6ancgB@{^%$@H>NK98)o(oitLu3Ee%p`yoa3`PkjHcNA&>v+N#3|tPx8jg zUfyY6-tkl3@n7EQx4grryu-7+!@s;UuJZ0}T;8Q4trkfbcE9pPDeN$;dIPi z-lZdZI>PA)rz4z>a5}>22&W^Qj&M4{=?JGIoQ`lh!s!U7Bb<)e%e!=BPe(W%;dF%4 z5l%<=rH-q|d-|@P?diTcw>KYF|Mup|>f+w~S-sqwSF59Y^KJEY-^|0`^RsV$t{(53 zc{_V~r+sPA)rz4z>a5}>22&W^Qj&M4{=?JGIoQ`lh z!s!U7WA^ec9of?nPDeN$;dF%45q_!T>d&9PtKWXQude&eht+$(d9ph2H-A+Lw3ylz04>cls^w@G0-`EWhwC?~E(^>g`|q)!{!s ztIvP_SGWKAT|NKfvpWCBbM^m^|IQ1zaqYZ-8!vl#r+srkfbcE9pPDeN$;dF%4F?)HJj_m0Orz4z>a5}>22&W^Qj&M4{ z=?JGIoQ`lh!s!U7Bb<(KI%Y5L(vdwK;dF%45l%-q9pRTc?!1-LcjuLy?mNfi=EKf6 zxp}g4Pj3F~Jd~SPJ16Dl+s;q9dARddZhr2(m7BNh<(>BB9Y5tA|K**2%R79^J3PxT z{L4Gz%D(euuKmuPIX^p(=KSxRn(KGx*BqanYjZqz-p%p<$hUssjce!Q+<4i`JMGIm ze#$%k%RBv+cleZdc$Rngmv_ch-o1^>yL6;=I>PA)rz4z>a5}>22&W^Qj@iq*bYxFQ zI33}1gwqjDM>rkfbcE9pPDeN$;dF%45l%-q9pQ9@(=mH_myYb|2&W^Qj&M4{=?K5n zaqHhs-<{8Oy6@bsn-4qB>*mSM`MUYD^S^Fh?Od>%Z#ysS%{=^;Uw!j)=Zn3Wx3iab z+Lw3ylz04>cls^w@G0-`EWhwC?~E(^&QrVgJ7?|u?EJO!zjN8H-<{WXe0Gl8@!a`t z$A9O+-MDrh+>MvLywkqCa5}>2 z2&W^Qj_}TjdyE%O$L!@@IPA)rz4z>a5}>22&W^Qj&M4{ z>6pE|OGox}gwqjDM>rkfbcA2(xbrkm-FIn-4p`^5)6TwY>SW^Db{*?HtUT zZ#y6J=HbrMy!pBFG;iLrmv`Eicl?xh{Fit7E${Ft@9-?Y@GtL-EBi0{#xJ|}J6H7l z?7Y$QzjH{h-@!WZ)$A9Oa-ne%D>5Z4YywkqCa5}>22&W^Qj&M4{>6pE|OGox}gwqjDM>rkfbcE9pPDeN$ z;dF%45l%-q9pQ9@(-BTbI32T>cj?HUj&M4{=?JGIoR08I9d~~8>AUlnPxqb6eDh)F zHQzk>p0D`wn?F0>`R3KmeZKj&^Pu0%!{7ItZ+`Cl=r{9r_VP~q@{XVKj{ovbzvUf1 zvV+E5l%-q9pQ9@(-Gb|;E(ab z>6pE|OGox}gwqjDM>rkfbcE9pPDeN$;dF%45l%-q9pQ9@(-BTbI32T>cj?HUj&M4{ z=?JGIoR08I9e>?V{hHJF$9(5kpYA{JmwxrlhoAiEuey2i*T3?sZvK4T&-$vHSFiut z$8Ns;{6F!rn}?tJ{U5ve`RQ-|*v(t^@=p8mj-T?5|ME`1}${eU-;zLUcbNOvp#-&KK4Z)Kc3(C^&da}KlBGbe&hOqZ~yp> zm%Y5xzP#h7yyL&T({Fi)PkD!Dd53>_XI$mo+qk?-M_Q*NoQ`lh!s!U7Bb<(KI>PCg zy}V0D_H=~P5l%-q9pQ9@(-BTbI33}1gwqjDM>rkfbcE9pPDeN$vzK@2$exaHI>PA) zrz4z>F#hJ}r@!UBcQ>vN%ujgs56owH?LRQj;raQ%{DTpw810dHI%Sl5x=xN2{H!u*(@F#qN!tY7mJ#>f1G@igCH{LM+&xUx^jYd?L@ z&vZZkn-ACT=E(=~+5Gt+o|{+4fAjFhwRw2sWiJle7ax9#8~?>qzr`7!;*V##;QvxD z_;>uIKmQoxORPP6I>PA)rz4z>a5}>22&W^Qj&M3=7oXaT8=Q`CI>PA)rz4z>a5}>2 z2&W^Qj&M4{=?JGIoQ`lh!s!U7V|F^$o{n%j!s!U7Bb<(KI>Ik?+Ba_#p#bAI-mbN=`IbN%kQ==kh;>3Hrr>iF-u>&CU`t{X3Vd8d7O$4`03 ze|e|h@(!Q!4$txq|MJeb%C)y~d6$l~PDeN$;dF%45l%-q9pQ9@(=mH_myYb|2&W^Q zj&M4{=?JGIoQ`lh!s!U7Bb<(KI>PA)rz4z>a5`o$@6wSy9pQ9@(-BTbI33}aI_`h# z>AU}Zr~Cd7-h9~q#G5Dk|9JCf|0{1^?f>S@xBU-&GY|j3ufO@Z|E+K4?d;{9_T?Qv zcls^w@G0-`Ebs6y?~JRwdmEQ`=}7BzgwqjDM>rkfbcE9p z-us8gc;R%+Uf!i6dpg4D2&W^Qj&M4{=?JGIoQ`lh!s!U7Bb<(KI>PA)rz4z>*~`0h zWKTyp9pQ9@(-BTb_@$0}PkZ|AJ?H7Z_n$W(_FnYn$=;XV{Mmcdn^$|kdh>1XU2h)l zJ?+iUy{El-%U<4TU*7Rk-tk}F>9@SYr@X_n{KCJyGp_7=FMaLzzWV&^J@)zE`|ay@ z@4b)D-iII0y(d5Zd#`@u+I#gIFMD~XeR;=EdB=Zwr{D4ppYjgR@(%y<&bZ3Ew{dxw zjrkfbcE9}dwG|R?CA)nBb<(KI>PA)rz4z>a5}>22&W^Qj&M4{ z=?JGIoQ`lhW-ss3kv$#ZbcE9pPDeN$;g>q@yX5J+?|P^EzW3dH*muC2C;L8l^Jm`; zZ(i+t;?1{xXM8gczx4}me(t;En|V8Xd8d7O$4`03e|e|h@(!Q!4$txn|MJebvhO?W zwcq#I^Rw@^=YQXGuit&=JwE&Xdp!4D`1tQT@{McXk#D^0<(>BB9Y5tA|K**2%R79^ zJ3Pxf{L4GzD(~LLrkfbcFYP`7vHN9kZ8r>Bydra5}>22&W^Q zj&M4{=?JGIoQ`lh!s!U7Bb<(KI>PA)r(^c=E*;s^5l%-q9pQ9@(-D5Dz$70)_XI$mo+qk?-M_Q*NoQ`lh!s!U7Bb<(KI>PCg zy}V0D_H=~P5l%-q9pQ9@(-BTbI33}1gwqjDM>rkfbcE9pPDeN$vzK@2$exaHI>PA) zrz4z>@Jk)H?)3ECy3Nyl>p5>eY@O%Lldb=}`LlJQH?Ou{^yb^vk={Jqy3?DVTX%Z% zmc6{wzP#h7yyL&T({Fi)PkD!D`GtRZXI$C0&i2~>#b5Yy&(GH7p8u`ay?(cj_xNmm z@A2Ha-{Ze^!Z)t16Tb1Xmv`Eicl?xh{Fit7E${Ft@9-?|@GtL-tGs&~mv`w%>vV+E z5l%-q9pQ9@(-BTbI32T>cj?HUj&M4{=?JGIoQ`lh!s!U7Bb<(KI>PA)rz4z>a5}>2 z2&ZHA@-7|O(-BTbI33}1gwqjzspIxpoW9$qaJp~*!p(>6Yq)u`{SG&Owh!Xw)%Hi+ zeA~W>H}mjYKIi7=_F24{x3iab+Lw3ylz04>cls^w@G0-`EWhwC?~E(^_LW@w?Ke3; z+lO-gw?F0j-M*FMv;8c`bNgJ5|Mtb)xVA6m#>-ybX7E%v%JH< zyfd!y?rmJ&r6aA=5l%-q9pQ9@(-BTbc>84@PA)rz4z> za5}>22&W^Qj&M4{=?JGIoQ`lhW-ss3kv$#ZbcE9pPDeN$;g>pYU*YMyeR-$*_Uqkz z*gn3SC)?k5^Jn}1ZeDFa;LW$~6TEr2eT6qax3BQ#Eqi&VeR;=EdB=Zwr{D4ppYjgR z@(cg+&bYE~ALX^*{>t;SeV6Bd`!TQI?bAFyzvaLC$no61&f~v*pf|4V1HJLGmv`Ei zcl?xh{Fit7E${Ft@9-?|@GtL-tGs&~mv`w%>vV+E5l%-q9pQ9@(-BTbI32T>cj?HU zj&M4{=?JGIoQ`lh!s!U7Bb<(KI>PA)rz4z>a5}>22&ZHA@-7|O(-BTbI33}1gwqjz zspIz1pT66Ne!6de`pt*!Tfcd-{p>e?w$J_M)%L&NeA~YGH}mj6_y=!(ZXf-dc{_V~ zr+sIU*7Rk-tk}F>9@SYr@X_nyu-h|Gp_RPZCu`^BdyaB zPDeN$;dF%45l%;V^$_lUmyX%XyL8MC9pQ9@(-BTbI33}1gwqjDM>rkfbcE9pPDeN$ z;dF%45l+YKa5}>22&W_bQpeSec|Uzucjf(bUpTK ztgg$=tJQnC`L;SRHxE}g=H}<>#@xJRZ$4{Z-tkl3@n7EQx4grryu-8n!oR#TuI#Im zbM03@=lra$&iP-xo$GgXc#hBN^Bm9B?K%Fd^K;``ou3;odwHjQdB;zA$A9tEZ*j(_ z_~V%__?LIaRo=ag%e!=>bvnZ72&W^Qj&M4{=?JGIoQ~PcyL4nvM>rkfbcE9pPDeN$ z;dF%45l%-q9pQ9@(-BTbI33}1gwrv5d6$mt=?JGIoQ`lh!s!UV)NysvPT$oTJKa}* z?B>JjlHEL6y|SA>t7CTaYW2--zOC-r&BN76yZN~~X*X}#%RBAMJATSL{>wZ4mUsA+ zcX*ax_?LIam3?*LuKgE(>Gz(W)sZ{@t1ox`uI}9NSv|VrxjJ>ne|7C{T&rt$<7F@J zv@h@YDew3%@AO;V;Zxq>S>EAa-WgYU_cku?(vjBb2&W^Qj&M4{=?JGIoQ`lhW-ss3 zkv$#ZbcE9pPDeN$;dF%45l%-q9pQ9@(-BTbI33}1gwqjD$L!@@I za5}>22&W^Qj&M3=FYnTkJssh6gwqjDM>rkfbcE9pPDeN$;dF%45l%-q9pQ9@(-BU` z?B!iLvZo`Qj&M4{=?JGI{8GoQlRkY{NBVSMed(JIt2=%3Wc8?T{;W>*&8yX~zWKJg z);AAV2m9vd>R{izWiRivFYov%@Axn8^jqHHQ{LfOe&Ju<8CUkz{l50A2Y!B5C;a@c ze)#pfy5h%Y^~R6q>X0A*)h)kqt#0{^m%Y5xzP#h7yyL&T({Fi)PkD!Dd53>_XI$mo z+qk?-M_Q*NoQ`lh!s!U7Bb<(KI>PCgy}V0D_H=~P5l%-q9pQ9@(-BTbI33}1gwqjD zM>rkfbcE9pPDeN$vzK@2$exaHI>PA)rz4z>@Jk(c?!)Q3a}!SYou_c~VdpH|Jo&s| z^9?tDb}qxstDVvz|?!(Pn_VP~q@{XVKj{ovbzvUf1-ybX7E%v%JHPA)rz4z>a5}>2_-OOg5l+YKiE3+r+)eI z+&NRnf9F!&xOOhpjhDT=)4sgpr@Z68ywh)ahfjHjXL*Nzd1qYZ-P^dlOGjF#Bb<(K zI>PA)rz4z>a5}>2n7zD9NA`4t(-BTbI33}1gwqjDM>rkfbcE9pPDeN$;dF%45l%-q z9kZ8r>Bydra5}>22&W^Qj_^wz_g(Vz-MM(D`_9X|`LJ{JZl3IXy_-Kfckkxa&f~lJ zwsZP!9`0Pfo1Z(^@8&Igd8d7O$4`03e|e|h@(!Q!4$txn|MJebvhN(jYrpdi&(F?1 zJpVfn@%r64iN|N>Cmzq8t9bl(4&#k$=P=%Q*~>fa%R7F`JO0Z%{g!w5ly`WRcleig z##P?Ejmx`qq;)#N=?JGIoQ`lh!s!U7Bb<)e%e!=BPe(W%;dF%45l%-q9pQ9@(-BTb zI33}1gwqjDM>rkfbcE9}dwG|R?CA)nBb<(KI>PA)ztnN>i{4A$odf$`y6=40_nHqo zH}<{e$-y^L)?G&iQ@g|Nr{0uHT&te0+9Z@bTO^!pDE-4&S(T z?(mJ5y*OxJeE2DD{9ioRZ*j(__~V%__?LIaRo=ag%e!=>bvnZ72&W^Qj&M4{=?JGI zoQ~PcyL4nvM>rkfbcE9pPDeN$;dF%45l%-q9pRnh{Lm3jM>rkfbcE9pPRH!!T{^O- zBb<(~e(4COBb<)#57+TaPT!q-e!A~G^qUVmC;jHh&QHJjvvbvNUhTZ~n{PXZ{pR7$ zZNK@sbK7s;vX^(-mv{V>cl?)k`YrG9Dev$szwm#PcVBY$ol}49cYgi(*}3*_{Qs3- zeEoj!U;2f|=l}R~KmU0Cw}19?kN@}m^`CR&`bEF$=iGSN%RBAMJATSL{>!^RvVO}u ze9AjK%RBtvbvnZ72&W^Qj&M4{=?JGIoQ~PcyL4nvM>rkfbcE9p zPDeN$AMO9q4|Rmo5l%-q9UtwVI>PA)rz4z>a5}>2n7zD9NA`4t(-BTbI33}1gkS3T zlYaM)_(b~tZ-4l&{poc7y`TTvV+E5l%-q9pQ9@(-BTbI32T>cj?HU zj&M4{=?JGIoQ`lh!s+<5KXiPyf9MF$&qGIe{vSHR>-V7}JU$N{;qiRv2ya{u9pR1Z zp=0*)PJ24C^Fv3Ne>%eY?S6+39oaXohmP>Zbvo{U>#Ou#KE6u#<>{;D!}9l4^JIDb zs`;~gf7QI&b>LO=ZP$la&BI+!UNt{=J$co(GP?s|Uwcm2O{?fQS?WiJle7ax9#8~+#2 z^;?|rDgJn-3;yMuag}#(PA)rz4z>a5}>22&ZHA@-7|O(-BTbI33}1 zgwqjD$4C38j&M4{=?JIeqy1AyI33}1gwqjDM>rj`mv`yNo{n%j!n=<@bcE9pPDl8M z>-c@A@18$T_dS>1eAx5q&67RH-u&6~?aiw__uhQl^YG2XJwM<4-1GCzTlVr!`|^&T z@{a%VPQT?HKII*rh-(-Bgbd|Q;z5Uza0Pl z-??$^|IUqrkfbcE9pPRH!!T{^O-Bb<(KI>PA)rz4z>@c!RDbcE9pPDeN$VevG7;B z^KSEM?|I&BzU}?byWQ{hzUbZVcY9y-ZudL(@=p8mj-T?5|ME`1rkfbj)7fr6YSf!s!U7Bb<(K zI>PA)rz4z>a5}>22&W^Qj&M4{=?JGIoQ~PcyL4nvM>rkfbcE9pPDl8qj(b))efNFg zbl-P}n-BXQar0!~DQ^Dk`^C+xeb>18w(lJ`5BGiK=I6eT+`MHk@3b%P_$lxBFYokQ z-r-Z;;aPs+U)~v4_I(e!_WMqBe)j$7{O`Nc^}Fv)$7kQ6j_1Bl9shmLx^eA$){U3F zywkqCa5}>22&W^Qj&M4{>6pE| zOGox}gwqjDM>rkfbcE9pPDeN$;dF%45l%-q9pQ9@(-BTbI32T>cj?HUj&M4{=?JGI zoR08I9k(9f^xgOL(|zCBZ$9k%`^}Smm%sV5^#C`o_8tG`+rIDLJly(?o1a?`aPyYE zywkqC9G|VbIG$UN zas0P_rkfbcE9pPDeN$;dF%45l%-q9pQ9@(-BTb zI32T>cj?HUj&M4{=?JGIoR08I9skUa|3jzm){mX;TUU1TVe8Fqo@^c3&7ZALyLq*B zYd7Dvp6%x0*1z5S-1@hhx9sJe_T?Qvj2Ns zFZ+-G@cG}m!RvSH36Ia#86MBAKRo_huXy9ydc_+rdwHjQdB;zA$A5XJ-|`Nh@($1P z4*&AbxXQb?ae0@Hv`$Aj9pQ9@(-BTbI33}1gwrv5d6$mt=?JGIoQ`lh!s!U7Bb<(K zI>PA)rz4z>a5}>22&W^Qj&M3=FYnTkJssh6gwqjDM>rkfmpX2}_vyR!(x>~@QQv&n z`s$k}TX%i)XX~+VUTvNB&9|-JzInLy-ZwwD-uvb)dwHjQdB;zA$A5XJ-|`Nh@($1P z3;*)YxUz43`?cS?_w%#$@aKQ)+^5C?B$*Ie#<+2$~!#EJN(N#<0|jo#^qf)(mEaCbcE9pPDeN$;dF%45l+YK za5}>22&W^Qj&M4{=?JGIoQ`lh!s!U7Bb<(KI>PCgy}V0D_H=~P5l%-q9pQ9@U+TE` zMW^rf2c7O;{H5P}^I`jmZk}wP(aoRjKe~CfeMvXpwqNPy;r2J({M`Pgo44%co%ZD& zKjj_&<(+=ZJABGJJj*Zq%RA%BzWrR+e*3)6&-QBydra5}>22&W^Qj&M4{=?JGIoQ`lh!s!U7Bb<(KI>PA)r(^c=E*;s^ z5l%-q9pQ9@(-D5D_XI$mo+qk?- zM_Q*NoQ`lh!s!U7Bb<(KI>PCgy}V0D_H=~P5l%-q9pQ9@(-BTbI33}1gwqjDM>rkf zbcE9pPDeN$vzK@2$exaHI>PA)rz4z>@Jk(6zv6ZJuKvU8bYESF*Ug93i+J5USsjVj z&7akmc-_2O-HDrTt4DG3aP=#0ey)DS&0F^JPW$qXpYo3X@=m|y9X{n9p5+(*<(+Y5 zU%ifNzd9c0XZ1bK|LT6cuHV%Ic^#kC8+jei)em{ycaYT^dENJs)f;);cN6yVPW$4+ zPjTbFcPA)rz4z>a5}>2n7zD9NA`4t(-BTbI33}1gkS2o zdQGSA>K&c#tAlj&VfB%2o~&-t&7aj%x_PxaOE=$Ef9cIU{N|6`{9L`JH}iJ(=Ck(A zbAFot{Fit7E${Ft@9-?Y@GtL-EBoqGUHjFoIzOvtb^cf9>iS*%tK+k}SjThqvX1}i zYu&h3U+c!pUfyY6-tkl3@n7EQx4grryu-7+!@s;UuJZ0}T;8Q4trkfbcE9p zPDglkw;tn#(=mH_myYb|2&W^Qj&M4{=?JGIoQ`lh!s!U7Bb<(KI>PA)rz4z>a5`o$ z@6wSy9pQ9@(-BTbI33}aI_|sV>AU)Vr~B&u-F#R*z?&zl6L|Ay^#gBSed7Cn+ReAs z8@zeA`h+(>SD*0aEqi&VeR;=EdB=Zwr{D4ppYjgR@(cg+&bYF#9^wZ4mUsA+cX*a}_?LIa zRo=ag%e!=>bvnZ72&W^Qj&M4{=?JGIoQ~PcyL4nvM>rkfbcE9pPDeN$;dF%45l%-q z9pQ9@(-BTbI33}1gwrv5d6$mt=?JGIoQ`lh!s!UV)N%EAPv6zEJ>6I5_U6Ot-`+e~ zUEG^LtCxH8YISsPzOBCQn|b(qe)i4J)#H6LZ)Y#>v@h@YDew3%@AO;V;Zxq>S$^SP z-WgZ+)gQk0t4n--RPA)rz4z>@aif*#tWxo_VO+r+0zkD zM>rkfbcE9pPDeN$;dF%45l%-q9pQ9@(-BTbI33}1%wFE5BYQf+=?JGIoQ`lh!Y_4P z{rS^(_1jPP)pfu5uzK$|PgV#1=FjTG-@IDg_?vI5Cx7#B_2+MXuKxVZTlVr!`|^&T z@{a%VPQT?HKII*rh@p1tLJ}wR_FhCuKxe=-+2Ky zuALWf<7F@Jv@h@YDew3%@AO;V;Zxq>S>EAa-WgYU_cku?(vjBb2&W^Qj&M4{=?JGI zoQ`lhW-ss3kv$#ZbcE9pPDeN$;dF%45l%-q9pQ9@(-BTbI33}1gwqjD$L!@@I}Fowcoij=V#~9od2CubN%l8 zn&Y!`ZI0*8yE*rkfbcE9pPDeN$;dF%4F?)HJj_m0Orz4z>a5}>22&W^Qj&M4{=?JGIoQ`lh z!s!U7Bb<(KI%Y5L(vdwK;dF%45l%-q9pRTcZvEToyYsnD_nq5y^I_+C-8|VjUpIet z{@2Z`oeOsJZRdr(nTOxo;%;|`0qTp8`sW*yYaG@ciNYC{FHb6mv{Ot z@9-(_@GS4}FYk=2yn7p$cj-v$bcE9pPDeN$;dF%45#Bj*kMY9kn7zD9NA`4t(-BTb zI33}1gwqjDM>rkfbcE9pPDeN$;dF%45l%-q9kZ8r>Bydra5}>22&W^Qj_^wzcb?|y zyYnbd_nlLD^I_*#-aOg4mN$QP-sR1!or8JvZRca&JluJjH$Qit=FMC7@=p8mj-T?5 z|ME`1^cMj?GyYoqp&(1A9o;%O<`0xDF z8`sW1z45Y_ciNYC{FHb6mv{Ot@9-(_@GS4}FYk=2yn7p$cj-v$bcE9pPDeN$;dF%4 z5l%-q9kZ8r>Bydra5}>22&W^Qj&M4{=?JGIoQ`lh!s!U7Bb<(KI>PA)r(^c=E*;s^ z5l%-q9pQ9@(-D5DArKBZ$9k2=9?$q^A%ry^JnKf-@Mwn&o|$89`u`e z`1^kI&Ci`5{bt_IUfyY6-tkl3@n7EQx4grryu-8n!oR#TuIxK6``Ygu?enwqwa@>~ z-M)Tz9{2ItIo-$ei@xr+AOD^AedF4B-#1?N@=p8mj-T?5|ME`1I{#{4riQ9kZ8r>Bydra5}>22&W^Qj&M4{=?JGI zoQ`lh!s!U7Bb<(KI>PA)r(^c=E*;s^5l%-q9pQ9@(-D5Dh)jy*v+?}|0h0n^YBx@|6?~lKmE-gyLroA z-f3Un@l)RMU*74ryu+uw!?XOtzq~W9?BD%OUvurh@rS-U#@ z*2j;}$G+&}$MYM%{^Q60hyLKlZ(Kj{?H|AKvX^(-mv{V>cl?)k`YrG9Dev$s@9;10 zjH|qR8<%(KNb7Wj(-BTbI33}1gwqjDM>rj`mv`yNo{n%j!s!U7Bb<(KI>PA)rz4z> za5}>22&W^Qj&M4{=?JG|_VO+r+0zkDM>rkfbcE9p#{Xyj=YRC|r@!UBcYo*){9CVo z-0%F8e=q#Oi#8v;)V=wTzWk&woW5}S!s!dAFPy$``oig({WE#`-svkQ=?kYX{4!77 zFVd^~pf=qH;qHTQ_d&S(Al!Wr?mh^2AB4LPW>2r~gY4Z0;qHTQ_d&S(Al!Wr?mh^2 zAB4LP!rceq?t^gmLAd)M+`q{}i+_J{}biZ;DhfqSn4_g)3=y$alW6}a~*aPL*%-m7F!uimS$_g)3=y$alW z6}a~*aPL*%-mAd9SAl!40{318?!5}!dlk6%Dsb;r;NGjiy;p&IuaZ5zdauIXdlk6% zDsb;r;NGjiy;p%>zE|;{HobcPtWEEq;od*Py?=&#{|xv38Secv-1}#^_s`kWtM||B zy?=&#{|xv38Secv-1}#^_s?+epW)s=!@Ylod;bjg{u%E5Gu-=UxcAR+@1Nn`KW9&` z-aoVV{u%E5Gu-=UxcAR+@1Nn9@1K3oO0T}tY14N)xbJju-|67K)4_eGgZoYg_ni*z zJ6-nl>N_2K-|67K)4_eGgZoYg_ni*zJ00A2I=Jt2aNp_RzSF^<`1|C0tMC5l)p`c} z|KexXr97UoThAaSt!IE+&j7ccA$$4NdIt8^Gr+B9fLqT1x1IrRJp=r5J%ja8>D9U~ zZCdvQx9$sW-51=tFSvDIaO=L{)_uXP`^sK^weE|(bzgAnzTnnopxOHD}>%QRDeZj5!f?M|mx9$sW-51=tuk7j7x-a(DeZj5!f?M|mx9$sW-530F z-IsNw>DBsJZCW1-w>}nbeJtGiSopVmW}WjRAOGK8=WM-wdbN*0{M$zWw~qjB9|7Dx z0=RtyaQg`0_7TACBgkHUwU2E@s!R@z#+iwN8-zs~0wcm=p{Z?@Mt>E@s!R@z#+iwN8-wJNO72JL+ zxcyde`>o*iTfyzOg4=Hex8DkGzZKkmtL*93ek=C&TfyzOg4=Hex8DkGzZLv)zm@%) z>D9heZNB(3`->mfxAvuqN&8aa_NBt@OU<5M?Mr2EUn<_NBrv_odqB zo?h+W*QWjZaQpY+_V2^(--p}354V3GZvQ^q{{8IbSNr$b+rJODe;;oDKHUC&xc&QZ z`}g7Y@5Alihugmow|^gQ|32LQeYpMmaQpY+_V2^(-_M?2?cZl_|32LQeYpMmaQpY+ z_V2?l_wTC*l3vw0(WW{laCJ`L>YTvUIf1Kl0$1k*uFeTuos;b8Rh<*|>YTvUIf1Kl z0$1k*uFeTuofEh^CvbI6;Od;f>WcK;r#dI>)j5Hya{^cA1g_2rT%D8b=~bN*_UfF# z)j5Hya{}YjcbV#(u)nNxqHa=pRS!y=>OsNZ@R_<^k85M~pdK;#|ER9l-m{%v)y>1F zx_NMQ^Wf^{!PU)!tD6T`HxI6E9$ekL?B!Q=^VqAK2Uj-_u5KP&-8{Iud2n^}VB_k$ zXLa+~tD6T`HxI6E9$ei#xVm|8b@Slr=E2p?%U*s}H;=u#d2n^};OgeV)y;#en+LzF zo45a!r&skwwW+=+Tzyfv`l4|4Md9j;!qpdrt1k*yUo?AqRbQ07`l4|4Md9j;!qpdr zt1k*yUlca3^s2rnd-X-(>WjkF7lo@Y3RhnguD&Q-eNnjjqS@1{`l9UB7lo@Y3Rhng zuD&Q-eNp&_*BAXvJ#8_m4l`UGX1F@caCMmB>M+CAVa}dj)nR6@4l`UGX1F@caCMmB z>M+AE>oD)Sadozf!3u!_}*Yt5*+KuO6;mJzTwdxO(;3%dhIyvsbSku3kM{ zy?VHM^>Fp-;p){t+W-Ib+=0)W&+cdiHAxgK!mdSoxZI@g1} zb3NeB^?*Cq1MXZ8xN|+=x6bu=ujj*^JMdo5lRJ;#z1IKioPzgS7u5Mj{OnwV_gY7^ z^A6sN=gvWRuX-Jwf24iqAHnS9m-el*;-__1{P(=w`A2?>PwTAk>^_Bm>#TO&IQ#PM z+Akm9YrWR;^o{?&Z_cs$%z1z2z|JYSd9w2hZvO0CgPT`7@8G@a$#hPf-*!$M%-+1! zzWK~g>*Dxt{_D5A*!c*TFFPOM@@VHHyx01uJx9G?e(gEr{qk$iC-3KH&n@rgf6p`T z*YBQl-jC0of8LMho{QcuzxEvUesyv>Pt&;A%P;NAFMi4|{>v}@mKXSxUwD>Z_?KVC zm3_~R*M85F=V#BE=YP+i*YBQ7kI$Z0kLR9a-%qbS_ujZVPt&;Ai-Y#Xho9ocfAQ3B zamJ_kv(@Xo}!%uqg zpI-V+FMQGq&vd~*y^JgS-YZ`Fy>C1}dk=a3_kQyF-FwU9v-g?DbMHBi|K5w<{w+NT#k>BWC~={LRbNiRIp3;*=md+f9CJ@B>P`{DDm_r~Xc?~||Jy=Oi?d;feq z_g?z=?>+X7YwxjdyzJ?veR}beUi_z*e$xw|^ujY;@J}z}%D(sZ*M9Hw&(GfTpZ~r8 zzkc^!;P~u&!SUR8gyX;O4mYlScewGgrv!LAj?cdD9M66CIsW@jbmQ80q8l%JdTF0t{G=EE>80QF!Y94( zOc(sq%eb=dyWX|`;xGN)^RxP{=YMryuiw>!JwB@wdpuV^_V};f?2T*nW^cUg>7{*o z@snQsr{I z-njN1_QuPeUfQP@Kk3DPdg(X4@JTN`(*^(ZGOq0V?tJa{J^K9YJN5bB_v`C--?fj= zzIPwbeFs1O`)+>Y+IRCCFME1vpI-c=7ys#{-}J&Kz3@yg{L^de96rdtbpjvMe(MK5 z$j{ale31XGH~64_w+`Wh_-uW`2l3pxg%5h3-#Uj6dY<1phYxxlW=}8e(~F<<;y=Cg zn_l>&7oO>Ye|i~L_O0u<_FM09ezp$e{BM28^}BT=$7kzFPOq&qIlZonEVtcY3XE z-s!dVLZ{d2?44fh>7{*o@snQsr%Pv<)_tA-t^2xu zx9;osY~9!KT%E(?zq*JwuGK}n@v^6v_UXk>dhwrL`b{r<(hJY@!au$Czw+!`=XUM4 z{_Xs1UEKNKdb#WO+kWKd9G|VPJDyv2cl@_b@5Z%tdN*G7^wK`P_(?DR(@VeUg-?3n znJ)OJmvLp^y2NY0^@`_b>ln}f);C_iTlaW;wjT0$Zk^=u-@3{h*Va|uc-hlS`}E=` zz4%Wr{iYW_>4j%{;h$bx-+T70Bfa)pUwVGF?)3a`J?izlb*jf_>sOEG*0mo0t%JRB zZ5`~5mp#3-PcMGbi~sb}Z+hXAUU;Sp{^@00*|%=_+Hc+R`B~kw^S^p%*YE129iP=t zJD#hncKla|?Z&k_Y&Tx^^wK`P_(?DR(@VeUg-?3nnO^v(*VdVzee2Ax{nnYEpRF@L z|66B%{jOfq@mU?Gn4EFYVKdpY-BCz4V)2_@oz}>4JZH8CUkL ztH1VJZ-0Ka4*&dbeg5^kb^FI>>-mr8*7+a*?F+bZZC}8Rmp#3-PcMGbi~sb}Z+hXA zUU;S#{^_-S9B1D?h-<(75$9+7CeHu%Q(V8>XK{SC|KfOVU&is@K8_pL_Ho>J+0#q= z^x`MI_)jnWrWZcxg=f0ppI*k5efw6f{r0n*pY3xw|J(m^{cc~(@!5Wv4krK?LFJsx6kO>Z~xKx*}kOnzx_(r@Afer zpY3ltp4<0y{I^f)#OTX!bPkP~*F8HUHab@4Wuxr2lV&`Z3 z$j<-vmtDWxcXoWXAMJQf>1ABmx9{@WZ$IYw**?wlzx|un@Ah>bpY8WNp4$g{{I_rP#OTX!bPkP~*Uihci_W7QD`(&^E_RpT5?W;Zi+i!dQZXfRP+5X()xqZ9G zfBSrIT-)b+<7H1T?bC~&^x{9g^qXGzq!*s)f`57$SN82|zV_Sie15hM`uuNy^!2-a z)5mA~sgLLOSs(xH%f4}KU-pfcJ-xI~FMiUC|Mb#tdf}5^c%~Qr>9sluXWu^bYrp;J z=V$xY&;RNbT)(ShaC}zZ;CQa?!SP?6gd5lDB;0t}(@XpG;wQcMPcQwZ7e48QXS(2@ zUdEMubq}un>K>e*)jc@>t9x+$uI|C{S>1!OY7ltp0;I!|FeXKdk-( zU10Se=mo3);JpW2{Rde62k%L;i$m?j0p>>>VE)Ac)~`6g_=p3Hr#Qg)o42rWWmi9; z_L~pqN4TkqHU5H2zGd{&1PxF(1 z{LNdqItj4)3AI;OAwTLZMi779ftZnO^v(S9KEftA0Z5)m6xkdJFkihoOGeXNZrw4e?aZA^z2W;9vcR z^kOd#+7};wiW~pMQ@_O-pW=^ay5OH)#+6OVAI_Tr#@@!_Yq@n1akTb%JJ{&=Pr{^_;nMi77 z9ftZMG<%y@mX%!%)BKGsH*ThIp#y5dZ2w@UQ+u<7F=n+7};wiW~pMQ@_O-pW=^ay5OH) z#+6NdnvJ%{*L|ABw?9~v)vanQc_ z@KfCQFP{1>&iE96JktgL^fIpO>Oa(8{fGRh|B(Mrto}p&s-qqs_0{94?t1*I({5bq zv^QS%;-G!;;itIqUp)0&obf6Cc%~Qr>D9Rp`c?m-_J48pAM)e;i2OTOqJEt>5g+GJ z#MAi{@$Wnf{+(yhc-f1C_Qi*v;>LgR)NgUdr}*QUF8HTcbuIL(enRclRmhKe3;9=v zp?=k8h>yAr@l?+t{?&irU;T&1%U&F`FFyPfH~x#Kev30c#UIb~!au$Co#O23C)8eD zh5V?ukbiX;>Q{Y+_^8_uPxTz)U;PK;QvadxvKI&Kiw{4=jsN1Q-{Oo<@y9d0@J}z} z%C3Gw?bTJtk9rIF-}jyCci(-EkGc)#))qgN9^&c89dvVad`0!KQ_%ELNEzbB9 ze>~F*|Mcn{G5xClP-wDv`;U7 z(u@D%so&y^Pw~eyUGPt@>RRa6`C_$q?pS`DN0xu*l+~~E%i`l)vv@l1EdHI3#=rB? z8ZUcs(7yQaQ{4D3p874$_!NIU(+mIfs!oD_)laCsx(fMGZz2EcFx0R54DnI7A)e|v z#J~Cv{Hy=ac-f1C_Qi*v;>LgR)NgUdr}*QUUihb%ab;IOq4w%3OUBl`VWnly*OxJeE2DD{1;FC7H52lKc4A@e|l9XLBHxJ)LvbM{HV8( ze{~q@SAB-~sM`=v^&H|~{RjTle`vhy#XVW?mA8RDaELp;@Uh=27Tj7$B8#>-wDv@bsV6gU2hr+$kwKE)r;^uj;A zI=@@L>Oa)}i&y_4Kh6Qqzw^QC*SX>Gah`ZQoiiT)&L!vHx#W$Py*OxJeE2DD{1;FC z7H52lKc4A=e|lBdLci)K)LvbM{HV8(e{~q@SAB-~sM`=v^&H|~{RjTle`vhy#X1ABm)laCsx(fMGZz2EcFx0R54Ds1|*WnO^v(*VZ|oUHydGtE-S7^%nB44nzH_ z&k!GV8{(;+L;S1%U|i}yq!)X7X4JZH8CQ1o6Kb!nLVmUm z{QRrKP`~Ok#AoZtkEePL@vr`aajE~%c-f1C_Qi*v;>LgR)NgUdr}*QUUihb%`VZOF zf2h6s5BX95A^%&?fBk;;ulV}ov-SVSbNd30|Mm;K+k1fRBe?OhrH)od3`JHQ#XkZePan*?x`Vss2NHZGXp&Yx_QK zyzJ?veR}beUi=qN{T63@ia(y|f`5ALJ=@vUPpG}R3i(lQA^++y)UWys@lm%Sp6WR? z->Uy0Zt6cYUiS3TKE3!!FaFa@zv+cfdf}N~_@|d~Wmi9;_UbC+N4NCVg z-G+Fo=MewuKNy$#4~>_-IA~vd_$hAu7f<~bXMBo3p6P{udhLJZ+0{>|y}AndQEwst z>M+!=`V8?=w;`VDImEyE55}ebL*r#H4%!zVeu^9a#Z$k<8K2^hXS(2@UdEMO{e;@9 ztB@b{7V@tSL;b4H5Fd3L;;EiP{Hy<9Tp`?YDpPRerXw^Hu)0-}6=dZXf8Y_-udZt9WkT=&Sf|Kk2KkhudfRs`0WH z2knawKgEsz;;G-_j8E~$GhOgcFXPItenRclRmhKe3+MkA{MGAMeTMj`+YnFn9O7U7 z2YRXh(0JL4gZ9OTpW?><#dG}@XMBo3p6P=B8@;~d?CK}fUR{O!sJD=Rbr|YbeTMj` z+YnFn9O7U72jf!zq4Ba82knawKk3DP@zif|#;5q>nJ)Oh(d)yy7LUCCx&Oko-+uP< zvwiMw{Qt_|di`!+{PEd-`Qy2L^v8eu>u(-z-~El3y*OxJeE2DD{9ioRZ*j(__~V&g z+joC@ssE6Dbq4-)?N@)`llfU)f=}ju^$I>&zpG>L$@r|k!KdQ6x(A<1uhmKTRQa_! z37<+Y_Vm&|z4%El{?kjp>4i^v;hA3er`K10`A_`B3;P$mX#dU&KkvNo|IUkk-+963 zqc3=V^acNqz8Kd>UyS#oFXHgg7xDS%i@3e>BA)NOi1Rxy;{VPIUB2K&e!Z7n{e;@9 ztB@b{7V@tSL;b4H5Fd3L;;EiP{Hy<9o~!@Rc-f1C_Qi*v;>LgR)NgUdr}*QUF8HU{ zo;S|Eyu0@5KjcUKhx5Ps5B0meK0eF$#es*0w|Esri{q8z^e0F_4p1W=z|6R{-T)WQSc-hlS z`}E?cxba^+^;?|rNiRIp3;#EIeOTARJW)TP_UbC+N4Ob(W{zLPVJ-xI~FMiUC|MXJ-A-(WPFFex=|Mc2()ce`hPpG}R3i(lQA^++y)UWys z@lm%Sp6WTozxofxrT#qzr`7!;*V!~;h$c{m0kUW+N-OOAN3aU zuMR`~s?QJ~bsOTTof>9y;|+0{>| zy}AndQEwst>M+!=`V8?=w;`VDImEyE55}ebL*r#H4%!zVeu^9a#Z$k<8K2^hXS(2@ zUdEMO{e;@9tB@b{7V@tSL;b4H5Fd3L;;EiP{Hy<9Ts74oCrLjL!E{Q6a&AwKFh#8W+o_*egdfAt?4FMDy&zWDG{ z-1sk^`Yq1*6n{L^1^@IiuI%b3)LvbM{Omo+`QQ7K>v!)}j*q$x@l?+t{?&glF7+Q8 zFMDy&zWDHyUi=qN{T63@ia(y|g@1benIHdQodo@=pHO>s74oz9TIXLKhWb^XAwKFh z#8W+o_*egdfAt?4FMDy&KE3!!FaFa@zr`7!;*V##;GbT`m0kUW+N-OOAN3aUuMR`~ zs?QJ~bsOTToMG<% zy@mX%!%)BKGsI`_pO5F>OCSI0KNy$#4~>_-IA~vd_$hAu7f<~bXMBo3p6P;rdKp)C z^%H8Zu0np)TgbmU4E3u%LwxqV;CSvk!tt;EgK??MG<%y@mX%!%)BKGsH*ThIp#y5Px+ZdhS*KA-&ksOZ(!(PjTbF zcnO^v(*XKOzB~F#|MW7h?CK}fUR{O!sJD=Rbr|YbeTMj` z+YnFn9O7U72XRyXq4Ba82knawKgEsz;;G-_j8E~$GrjOnuj(Y|SN(+AtE-S7^%nB4 z4nzH_&k!GV8{(;+L;S1%z`yzrjhDSRXkUEzDQ^51PyH5We2PDw>4JZH8CQ1o6Kb!n zLVna+$iF%a^{YNZeAI1-r+N#))qmh${fEZOUL3S9KKv9n{)?x6i!(mO zAJ25bKfR1AyZQ;WS63lF>Mi779ftZH2zGd{&1&-B7Sz4pKI?CK}fUR{O!sJD>+t(Uugzissy;-hXuJk@iEfAt@XOZ|t& z%bs4^7ax9#8~?>qzr`7!;*V##;GbT`m0kUW+N-OOAN3aUuMR`~s?QJ~bsOTTo&iE96JktyR^r}vRe$`K?y}AndQEwst>M+!=`V8?= zw;`VDImEyE5B#hD(0JL4gZ9OTpW?=U@zif|#;5q>nJ)OJmvLoRKcV(p4}5;qTgbmU z4E3u%LwwY2h^KlE@vr`aajE~%c-f1C_Qi*v;>LgR)NgUdr}*QUUihb1brSTeenRcl zRmhKe3;ExA@9S56hWM!45Kr|S;$Qs-{?&hIyzIq6`{Kh-apS*u>NmacDgJn-3;yY4 zT-nu6sJ*%h`B85n|LQQ*ulfw}QMVzU>N&)}`VYpX{zKzsFAmxlAAZt{|Kh3N;*3x6 z$1}a~Pp|4E=vV!O+N-OOAN3aUuMR`~s?QJ~bsOTToBzxof2m%TV>Uwrr} zZu}Qd{T63@ia(y|f`57$S9bLiYOk(Be$-pYzd8){t3E?~)NP2TdJgfg{)2I;|Im2Z zi-Y#Xho9ocfAQ3BamJ_kf>1ABm)laCsx(fMGZz2EcFx0R54DnI7 zA)e|v#J~Cv#-;v4<7F=n+7};wiW~pMQ@_O-pW=^adf}g5)k)Cr_VHbNbrtfX-a`J> zVW?mA8RDaELp;@Uh=27T_*eg-@v;{O?TZgT#f|^sso&y^Pw~eyUGPsY#))qgN9^&c89dvVad`0!KQ_%ELNEzbC)7oO>be|l9X zLBHxJ)LvbM{HV8(e{~q@SAB-~sM`?FFIqi^_*egdfAt?4FMDy&zWDG{-1sk^`Yq1* z6n{L^1^@IiuI%b3)LvbM{HV8(|L<8HhWb^XAwKFh#8W+o_*ehIxYU1WyzIq6`{Kh- zapS*u>bE%KQ~dEvFZ|Q1Itlt!KcV*DxVj4YQEwst>M+!=`V8?=w;`VDImEyE5B#hD z(0JL4gZ9OTpW?=U@zif|#;5q>nJ)OJmvLoRKcV*OD&$AKh5W0-P`~Ok#7EtRc&g_R z|LQ*&m--Klm%TV>Uwrr}Zu}Qd{T63@ia(y|Rs9F`pVfbOSqtI?e$;<>wt3+H<%hog zU3C()`QXQX;$8I<;Q!M+1R?Js=CyXrH*U-7%Y z^Idft;6MD&e%HI|KfwRu=YRLR>Oa7L`ycru@2dX*|A&9;kDUEWzxR(````74{-rx9}ugr7!Pydd;^~(H*zw_h&`zv_?|6_mWhhE7S_^bct zzx_%c!9V98|2wbb7yOZ5{v+^z;Jr^Wt_S|6PyeX1|A>F@A2P0o{n!2z|FCgA@Q?kE zezb8t@Spq3KgPHo_)q=7k2S6b{=5I_XBpQ6|Jk4N5#xH`-~9R`^g4UsP+O_{bv|Px%GoFYjREl8>_V-i^G5MPyZ_ypYQr*zwzSsFMrd&dhz@Tf9E${oWJ}J{%aTiANZ0l zKV5eJIlca+zx>AN#@C`L|CT*025JFh2H`!+6?n4&!ehI&56_r^CjZT^wpJKKT*1{EKJ( zigSF#Kb~}nKfM|kyZznz)!x2um>>JWVgBtChxKd!IE;^dj||KA zy{~>?*8%&N*rW zVf|`vA2H02{lzf<_8r6ewI3PA$3A5kPy3f){OxOojmv&#*m$#xL+!;UKjM~u@vL8Q zj*s}qlP>Y6*S_1nr!RKv{b22_1BCgpJ`m>rbGL2~*01%1Fh159!gyML2;*;EB5YjN zE5gQ`T^wpJKKT*1{EKJ(igSF#Kb~}nKfM|kyY+th)!sTlm>=r{;fMdN8-(?1Jt2&b zb%rpW)*r(7TbBqMm-ULU@n#o?+KW$q#4Z1ics~0T=lFvq zS3X(?2+LFJ17Z1V-5@NlttW)#yLE=J>wxu#uS?5XRH`Ll}SS z5@F-AUJ*9l?BY;+@yU<4VcrrC{SyZwfZv?BY;+@yU<4*4jYW8 z`fM=%>bAkgrJfsXyxGN}_TrNtam&AW)~`6nNBrYSm-zd?+_?NNYrOui6$k(0ijV(y z#m)b|;_3fjarQs4`1}8uF8)`hm;amD{SU3Z|EKx!zcv5<&(^R1x$*J;H=h14$KU_u z#>L)vwJ#3*6d(SJn|_NYKE)Z&;*Wp27*~23Z+3C0z4+uu-10A;^()Tt5&wA7CH|f_ z8khT8<8{9)4(@}+$NjOmxo;Lv_tWC+K3n|Vf78W%IlbJkv%8Pi-u*p4?)&-oJW#)$ z6XN6fA)cNq;_rE*aj`dE?TZ6H#fSgmrr+X;PjSYx_~V~0#+6>in_V1gFFyGZxBQD| z{fcvZ#6O;NiU0Hd^|)8cJL}cuwS2UW9hRrox5M(+x_4M!TMrM*ckAR~*8%J2Vb=%i z>S5On>+NCJlkBcDwRio=kLyzYU9albbu2!vZ}D{9i~sZf_2`TJw{5+;ezmub9p=aS zc9?(b-eLV(4-eyGoji=E_46?P*44wtWxYLYyxGN}_TrNtam&AW)~`6nNBrYSm-xFL z{>Gp1?|g^8#kw*%6e?re6vm)HV>`ehRx6H=56iG z=lq!G`8WUTS6;+NzQj`=#b16kE_Umm^{c&g(J(*OOT&-njjf}G^=o}KjE{BKFrL<9 z!}wdL4I7vB+pzIw7l+!5PkzKL|BvU5XTRbcAMuYTUE)u#@{7IsseSX7pXM|F&2#-W z|M4j=@GM{OFOQ6?{4(C`;!u0>$&a|@Up(tqoZ}<@@uW-q=~aF`?T`8SZ2y?IPd^X* z^#8!mejoVB=aCmro)7%w|G>|2J@9k95B!Y713%;Qz|Xin{6FLQz|S~8@H74o{M6;a z-}P|!%g3{*yi`q=Q}d1-aCVb=}y zwBg6|)zj`eQ+wB+{J1XV-}S0~UB}|%`W8>uz4*HxHZFGcsP(J8I@K^g>Q}@3t7{GG zci+Ju7$0@8*&o-#)yIbMS2r6rF7>ow>uO*;t+#>kw+;t3F6(n(s-7X4~(-3!c*^)N91*2%#7wSET1$GRFAPwQ=9{H?=*jm!ER z*m$#xL+!;UKjM~u@vL8Qj*s}qlP>XpJ|8~beaSofyY(v{?fZu1sr}%v{IyRUme=-= z!}8s}a@cjieskFM!9H}@b;JI2*!3j4>rCxkfAZtHlz-Q&`gI+PkLz1JUH9VedN{ov zeX-l$tzYf!`-b_k9~^%8-#&3zzxI#A_}Ett<7vM+jK6*8uyNU+4jXTFaj3ocEw)W<8 ze$4ayoB#DIFXAI#;wg{fFTd2&))%{a)UfvIRKxtJUk&sBiPg1+^{d`BjE_3lFrMmT z!}zP44I7tw+OY9v7l+!5PkzKL|KeG{;v66Gk0)K?FTeT@OUJ&?(zoxnbnknv`OtS> z^Q7;;=1<>+&8xl_n{RzbHV^y0Y<^}pZ)N_vHtE-mf3{c^`k^ z=l%VGpZEO-em)O8@bfw0fuGM05Bz+tc;M&r#@Tzn{d_)o*q_fW5Bz+ddEn=B&I3Q6 ze;)YxT=c-t=cNaJK1V(9^ZDw5pU+(n{CpmJ;OBGN13#bN9{BlO_rTBRy$60i2R`tJ z&l?|puatLv?~{*x2b8CMAC$kJ`}|%hult@T-}}z!I?(sW$Mx{}z0!4~@0E}1;nVIq zQ+wB+{J1XV-}S0~UB}|%`W8>uz4(9lyz$|<*!$k6ecu83>HFZr|MR<{e*2z?Pv05w z?E54BeU~(@zE>J=c5$e^_~b|2^8bkEvtMzJkNC%vF7coHZJuaVB^g$4z(Ab{D@or z#j}3JIX>baPrAgPUc1h}t1tFlCm&e*T|Xa~pIuiUnEzdGA6UP;4nHtHyFNcKp1W>8 zF#fxqKd^DBAKQ4di$m?jCqLqrfAOqeagLAp$CEDcr&r@*-+k@TulBp&JupAJ4?Zye zyFWg#es|w|V0?BzePBFypM79@?f(0~#-)C2dSw@f+KW$q#4Z2gS-;{OAMuYTUE=>- zzwzkHeN8=T{kq?M@#<8=?t|)A!|spjTEp&}>RrR`r|MwC?z8G+!|uQ8X2b5w>S@F7 z*V*02Yw!M^ANT$IdmgA?&k6DI{18vi74d(r-+1)Jt{%01wO6Ma=12W%n16MxVg0Ii z4dbH@HjJnG*f9R;X2Zs%o;GZ}*~Ovu;*%e7%fEQmuQIWZvxv#1B zu3z^%b>Lz5LG|Hb_eXW(VfRh-?CBS@q{(_g{7CVfSVA>S6cm?C#^WcYn{1 z`+ojC57e*cg!p)Vh^Oa`_<#65>cerdtM{&7?bU&Y`B5Jp=Kud*-FR5P>dC|Ss51}a zss22Szq<6Waj91i8*g@TsJ-~)N8Iu+p7krv@e%)c(k1@%>OD4l@3*z@y*EF-59h!4 zsOrPBmVKEOZ-2) zfBp2w+;E-TI-Cb~{oMMT2XuT?^jG*|FgR<)ZYCfKkg&>cYmp0_nr8-AH~ysD*hkdzdjrn`_@f8`qh5xsUDc0 zt+RSy{f%Us}Sr3fQ)@wa5o?FND!1!-{*8>}udcVeHyxGN}_TrNtam&AW)~`6n zNBrYSm-s)Q=U?fIeb0>#to@!RADEv#XFf3h>h5Z<-#wQ;Fg|-;ePBHI9Q(ld@A>wD zjZ3}X^vW&{wHKfKh+F=}vwp=nKH?uwy2StaJpbs6eb4z1to@$aG|JB{a zO~3me@xb`(|HT92x&IvxOs}n2njHh};F#hTk z!N#S25p2BK#i91%lOJ)*zj)TKILAl)<4KqJKc5dDbHj5;^V9Q5^VV}q^V#!E^W1Yz z^WXDNdEvRJeDS7##Me9Z+3C0z4+uu-17g3=d)jNj*s}qlP>Z1 zywN&y_qEoayWh1g-F>k2>W}A*=lXf~&DOWOpSJGZeYW-R?!T>*cVBM(y!&-__wm}h zzvst&KmU*Cjc31}6XN6fA)cNq;_rE*ak01lT>I9g^V52D{#(bc-`2O|)4F#&TMv(a z>*S5A_4CG?T^wpJKKT*1{EKJ(igSF#Kb~}n|A+5;KfEu~vHLZByN}bo`@8wjecwFk zdBFVXIl;W@`N4eaxxzf`dBgn7Zr;}3e9n(~o`3Vde&t1cv`Ur#yi_6hdv$?ee$)$s`Bz5>*01_PFh1%I!FZ}i z1mmwx5o}!Q7s1AxT^wpJKKT*1{EKJ(igSF#Kb~}nzx?Wd3LX3ZLf`(^(7pdV=0pF3 z%#;2fnLqt+GOzkSWxn-4%RKD=m-(69ysf?YoFDT%|K@-F%8U5Omw3vf_{*=x#oqrH z?fYNDPycuL?|+bf`+tN_|C{ja{}lfH&oZw5e;IFfaj3ocWex@0%w*512naCzw|~KbUVlSD1%AZzbA@sBykWfA z#i91%lOJ)*|0ABye#JRH;vY}C#NYG0x=eD}bEA4qu;)p2oM6wH>N~-nKleTKfjyV1 z2gUArRh=lP^9(hqHT5uD$2y{CKX;zvu1x^&B1_&*$;<+#Y|= z^NovLy(ax?uZ|PUkNQq9|LQ)$`c)4K#z&nf7*F-1;K%>3)s=#cOT8)h@&D^-7l+!5 zPkzKL|KeG{;v66Gk0)K?|KaV{I6em5g+*yPk9vo58p?9I4<_at9^0cr}*$+-1J*K@hQ%D7XL?n zJ#{gz^m^pi(=HCR7oYryTmHqfe#JRH;vY}C#GhX4@3pzX?mSjld*`&m{5ZcA=HI!l zuzsEQ3ghD(SQt;|!@~GGHx@Q7=gGpxn_V1gFFyGZxBQD|{fcvZ#6O;Ni9fv>7rXOV z^{c&eT48>i-wN~ZTvu4X&U=ONaSkkur}JT9{GA&M8<+EBVdKp%4z(Ab{D@or#j}3J zIX>baPrAh4^>E+y9x;@6`!4qXaCP@V|8G@U$CVn#5{gPglSm|UQ1Bs!2>tzjX*Q@q zC(=?+VxrlTWSO8qfQlJIOo@a|OQ%Em>60D0WuKn;rE`4f zA5ZlX|I@$j!ezf@XubXu5Z|iU`8x+>r}IJfJ2&LF^F(|) zXT-DfNBldNRIbh|mA7;{l%GD?p2xSReX>Kh?9(&9bdC@Gx(P2=9|ix4!UhIc(kGJ#*N4#5?D(b&B`TVe6ODt!v6} zy^|g5pzK>8<=46?KGsw5w9bmZ^;hMR?)`9n<@c^Q%#QcQVfMX44)g1Mau^@)mcw{@ z&m6|zJLj-+dH)<%-qPt%e)?pGZrQi~$}gScL;rZHm-wr%X&>9yq72_UClns zV(o4AXBKORvv0Fl`z&3%Ex-1h9ql~(+W+j^?EmT)@zG!6sUOAv>_=^W>9bF@SpM0+ zy0J6+T34R2Kl@#a`JH{R#rVwr*kU|q-)u4dv!AwDxn`ejvGSHqhw{@WJ9NuFJ@ZTF z_|QL|>Lvc_t9B^8_9=humYv!&`?Yg^YybGvFYv6t;9oyduKJhqmQIKA(oL9m-Fi?9eUy z^vo}v<3s;=s+ahm`r5Htdf!jU-*;8)^t~1PeTT(w-)G^|cUyS&Js19c=cQbI|E0X8 z)1mzI$qwDJPtW|)IX?7{r+SJ1sjq8pn)JS(lE3e&*y(#K_WKTt-@ebnr|-7#?0YW! z`_460D0WuKn;rE`4fA5ZlXfAuwS)b?fR-3ODudt&T#e~kU^mGRqs zGkm&-hG+NF@bBK5a&@0gc}u55`RS7#x@Di9`K5Dw=pRq@6@T?rxuka=O#bePvD5uA z_9y;a9r*3O89v=Z!?XKo_;+tjxw_A$yrt8j{Pf8V-Lg;5{L(o-^pB@{iNE^ty9wq> z>3&ZEmf!Cz!0h<_1(Rr{8yg@%OtAuyXl52v~Vbr$hPalO4Kc zpPu=pbA0F@PxTUi^;Nl~`#lAI<)8QW7PI5`7o@ZAcNt)Q{ayo%kKb{C@$~x+F#dk` z0ah-*2LUT@>2xSReX>Kh?9(&9bdC@G6u?T$A|v$R4?(r&Qq?~N!(a`C7vwq z5@!~Vi9d_e#HGb=;??3hacuFP__jDu+*^Do9xh#+Tz>I$cEr`$7jNfR93CI>c|67K z@fXj}dF768(u=R;FYaQec#QqxG=7WU@F}jtvv?2x;y~ppK2+Y)=}><9WQT6qr)PfY z93T3}Q@zAr|LWXaJ$9b1emiGZ@14JE51q?vC!N=8Kb_-iSDo+g_;Bt6XouYg*zx3~ zYq#asp0lH!XJ7lzuYM69{Ux6IQT+9<$|b$?boo1HXQ%Ub_B)s7xAS^@I>*Pe^L_j~ z_gAj&11N9lbSOW4vO~A*(=)$xjt~9gsb1oL?e|`L*Y>FzPwZbc&e+##{ITEFxMUx! z@yh;K+lf_=bPuo^mxFDsSm@C_jC&L$~bHGrx3>5B=k*UgB>& ztR3oiwNL%AcB`M(p7r0_xqe;y*Wc?G#)0~a@u7P)#*O-y@uYO)O!qp8}|5D!4=}><9WQT6q zr)PfY93T3}Q@zCh+MmDnZPa7yP4(M4RK2%8)gD^6YA3B{wV&3x+Ewdc?X7jOcG!AZ z`z&3%Ex-1h9ql~(+JAoai}>g-@zjsvf9=m-<&xfdQ~uVW?6f{*zjZ6Wt!MFRor`Dd zU;JAaD_84fh$y?9vu;$(J; zpV=?2=C^nopW<*li_dp_IPtu470>T@a?Ji}9KJtBdiRd##J{pZl(hmCNs4TBj&)>2xSR zeX>Kh?9(&9bdC@GC?Ld%}y^_q&t0@jLg57vnScjThrN z_mCIkKlhUtE0^E9^uNkmIvvVSpX|^r`}E8&o#R9Qc&eB9t1rKU#+P)zj|R){chg{Y z{GJ-jzTa7c`Sts2Fg|{l4aU>&wZZs5cz(wXRxZEq1}ksrbSOW4vO~A*(=)$xjt~9g zsb1o*zABe=zmLYR{C+nLX25d zKg3g95r6SU<&s|el)rY%PVJff+Bv_qe|+i}c-CL=uOBH_{Y!aEr$hPalO4KcpPu=p zbA0F@PxTUiF)n4_c$Ht{SbU6c@igwm-*{NLq_@8(oX`{ew#e~wT4>Ug%_ zzT^3MpG~>ipWpHSq|>4N^vMq0vQN+a(m6i#kEeQxzxtZ~e8<=;z4rs5{E}buPJGNq@ib4x|Jv`p$|b$~mhyKGlb!BovfsT;e!I_!Pxn0W z?EWYI-3wK&?u#mK>2xSReX>Kh?9(&9bdC@GGLk)V)^I2#Kr8)JBo|f{%`;M#r)2@i;MA@_ZS!Nc=!ju zWHJ8pe&b^0ns*%+D{tvL9-jR4$qwDJzj_|ObdC@G+L9udFA+xQfR<5_%;e{s8V70)Yg>2xSReX>Kh z>~DN{{L(o-^pB@{iNE@)T+)k&GRw7`}p)-Kc0Q>kALp~ zC|BC_jC&L$~bHGrx3>5B=k*UgCf4A715>-uLzL_uV}^eUHz6-|6$)_xt$t zT|b_E?~i})04P`Q11N9lbSOW4vO~A*(=)$xjt~9gsb1oL#fR7Z4dZ0@AB>;fi!iQs zU&46XJqqJ+_bZIg-McVucOS!e-aQTDeD^nu|D~H3%5T2Nj(H^e=9m1Mcj99{il=!h z{#Sf>l}mc}ALQ>|1UucAV8445{C2+rpYC1Y*?kQByQiUC-QQ5&(&~Mo{MA?GlHUDT`MWpEPWNfq@18Bc-M_`Bd%1XaUl;%G@hVsM zdzH6zI+UM2*`ZtZ>6u?T$A|v$RA2EI&$llsZfw6)JlQ^~IJ5m#@n`$4;?nkG#jEYp zieuZq72me6EADN-S3F$0IJx}d=j@29voGGxuQ)tD;`4Zl+v6{uuUyjGFO|Q2RCd~5 zWxst_e%p`5r+r#H+rQm-{_OWESNpvi&!2QUl%GD?pS-N&xe(gCs+IjZ1 z|NQC~@zG!6sUOAvis!F#N$>j(`TOpJoxTTQzwbo&?fVgY`mO}ezBj?Y?@*Mh?^Bew zbUKuuKG~sL_UV~lI>(3p@l-GI7jM)K&1E`kBo8Plz-p{^xAiv^-_=q3kDXxgWc%yPjuYJm2yJe^L%zo{h-`YPu z^$R@fFZg$EqFnVa~Mo{IB)b!*@KC z-up1}_ihY3y(hzd@67Pq`!o3TE)AZ&SA&1=*eF-;+bD18bSOW4vO~A*(=)$xjt~9g zsb1oLt-r2vN$-6a`Fl5po!*mSzjtQ%?fn^idY1;z-mAgCcWjia_idE7bUKuuKG~sL z_UV~lI>(3p@l-GI7jMiv75CcjHLtaPG2gYWF%P!hF+a8rGHppVW;&D`>licZGD7K z>n1!~PvPG>OSxKqDR1d?C_jC&L$~bHGrx3>5B=k*UgEF5dZ$8q?;*(FI|=OceggZw ztH5vXE#T8T40!fF1OC0+pj^G@puDBiq5Sm84&Aa(&-~IkKJ<^LdWpaKs$9~04?+Ik zNnoe<6WH%v1%7*P0iWJsz_a%m@SoqO*maO{^`3+BmQIKA(b0e4h7q z78|$c9iGL;^Ld|Vv2niN3o!ndZeA$A`64^!k?fma@@w9SkNGH`=BfCf{iyXTecmZr zEdRV;w3wZF*J$zDKkxSQJMSQEIzID0(qcU4-K53%&wEOXm8;(iP~Ot%P=5Mkhi=(l zJ&#{H$A|v$R4?(@zvf=$&H2~dOI)me=f2`%^*;9)7i$l5zj3j4GWQ-AYd>=za>?rE9n4*PgSZoo8SB&#!(FAN?hs`ceG#ugWET?vbuv`R9J= zVs_@<>0d{eU-&$zh&dhvk$ZQ?9VJd`!~ucJe&>e#cAkh&=ZtuE z{)m6)lFHS2rSg_ehw{@WJ9NuFJ@ZTF_|QL|>Lvch!9P2Ym4>AneP_sr!x;O z)_-SyT&!Quyt!C^pZRpLabV`z#XBCJ-;*+K^m|e}9-egLO!qY(-?Ll$=XdV-?f38S>38w)?Dz8U?|1Z+tKZjC-qPt%e)?pGZrNWwk6${+hyL+Y zFY!O~*S)R3W?i;e{#marW@pxMi`k#`-C}-c-M1K@Sr0D8bJmHA@t^hMV&$535B=k*zT$uS*RATS`wypnH~rN6 z;?o`$pLVkNw4cSNT`fNCZSiS`i%XqB-LJr>dlz`lIIwx}@1BNob$>&7OQ%Em>60D0WqyfOQtI}V%IW?yl!`EK?b7n=uXA9AtzarP${n>T0Qa4=-kC z_Kg>_Kl{mx`JH{{#rVwr^I|+_UwSeAvtPYfxq2U4c}u55`RS7#x@Di9`K5Dw=pRq@ z5`X<`+Q)tMues;8SpClZx5esx?!_(E9_GH>V(nz^(Jj_~=6>B`?dmDdyRh~)_whDe zJDhuZi?z?vwcGM*&)Lz=v#)o(he_w>;o(oH)_Pwgk2wX5{k-l`Yvu=>(IOV@78uRUi+JI}uMpI`kVKKe^M z^`rRfUzJOG<&{4j*hwGu(~aNs#3!BcOn>~V7v-wHl(%#`l%GD?prVY^(ifllU3}_&@o5i>PdizB+Rx(Ct`?v6w)nKe#ixBPKJ9k#Y0ryKJ70X- z|Kigx7N7od<+=LN;?uuw(x)D8@=yIPKK=B{bM@cFr(Z8V{eAHn2Ns|4VX<;`zxRwM zn|{Wb#b^9ke8#24XS`Z`#<9g`d|Rx4#b5uLeYQ-nSbLlOw8h%t?6WP_K1tB^i`s^#NU-@UhaWOly54o8A*`Hj@@9bMH#%K037vnkmoQv_F{m;e9HT$BAmA7;{ zl%GD?p<9 zWQT6qr)PfY93T3}Q@zChI-xDTx!8Jt?oTeZ576%~+aD<1zCrozCuGMyL-y@I_N0uk*^Q zEYjy5>2i>N?w2lRXYQRYW`DjfTg>m=Q(cVD++SUc=iF;ujQ`wsU94RF{<89xPKWZ- zCp&b@K0WhG=lIY+p6Vt3`q$gv_p|P6{(9VtF06ik#m`^M&z$ z(#tNaTu*!Pg_XB-I+UM2*`ZtZ>6u?T$A|v$)W71dzUDirJJr{GXS7)U`Tl4zJM&%A zV)o~IrN#WtcT9`%neUqx<2m0wEyjP|D_g8w^PSXUVSXTC>UjOTo(wiy5Uer>UG&3A2! zmA7;{l%GD?ppa4I*ExlGu=5M^W9J&?&CWZ_r=5eC zXFDG;|8{O-UhX`_d|kSEy!__(?3nknFCNIRI3Ygbhj@xB;xFE)T+%y_kiT;Zb~?Xc zzjF3E2;KJ;@`m>(1dD#CaZ@e(SPk5i_ZaO~Cddh|Ie9`kSjQ;~)cVXrFv3oA8 zyrt8j{Pf8V-Lg;5{L(o-^pB@{iNE@)T+)BZYrkZ9%KzcN`NHhH-~C^_>FodHGcU~V z^B#3!eD1vMS(^vX$9&6$@qg3HFRWbmzvRNoTRI)ePoM12E&KG$FP-B<|9GmG_!|#9 zchK)TkI)}Gr_fJ3ztDd>*U+y!@6g{n2QdzGK4N^B`wVxq2jfQPDaMo1jWgvp{$$6v zlzrn>evM=CF}}sqxEFupVdawEd4&9(Q?S$d1^b60D0WuKn; zrE`4fA5ZlX|0|w<_{OEuJCBgRa|(7kzhJ*}4SqZCz^8K%JUbu3zjG7i>O4hxOQ%Em z>60D0WuKn;rE`4fA5ZlX|0|xq$|b$?2>CmwV5jp7_B+?$xAP8sItRhC^AY?zH&L$6 zQ6u?T$A|v$R4?&A^|ft7dh@mX&ExDezq8-G&u{SnKE(-m7C+!$ zT%laW8_HWc9m-Fi?9eUy^vo}v<3s;=s+ahm`r2|yZ@!kld7Pc*clMk2`7Iv6r#J!6 z;s^YTE0n8vLwQT5L;2~G9lB+op82J7eCQuf^%8&eHF57v|C)ED7Rx{HO)X|;-l1B| z{=84MnBRG~YB4_Zp4DPJ=bfv?_|N-SiLvc_t8z(ie_Q_cz1e9$oc;F6`ECCk zpZ3-9Y`-1<_TiPQ{dwgroet%vPj={*eR}4X&heptJk?A5#fP8!&@cbS*2_Qh4R8B) zSbXxb$A0!3VR6e_9(m7V@yxrw?f%8$oVUL7e=QdO{NR%w@+SGkMNfJ12P_sZecm^H z&|-1aTORqS#p0{d#a-nWk7Y-kmVNPCe#Le15%0xQ92kG`;V*maS8TaX`V(<9WQT6qr)PfY93T3}Q@zAr zeN`^$#aHqdcd=7E#(r@czr}C(6xZQdyoY~rpmG%-DsSm@C_jC&L$~bHGrx3>5B=k* zUgGaJIr|--|NWysaO>7*T)#u~kABk+-TK}azjMdrfBHWE`qrEO!hc)*F~8-lw?6QT zetPj=e%;${eer{TcJbJ_^}Fu=AB%tLcl`9Nm)-TimHyD5yY-LWeqrOr-4FYpoBoww z{a&|AfAxR=rMJsJXZW|X^9kSmD{p82fp@*%?fkysW$%AGJ|F#pUvoR2ul#Etcsu^H zw=v`4^;=8Q-}8sB-yxF!i|@I9SBRY#zT(H15Bned#(%$<-|zi(KX&mPK0oz?|8_B+ zum8~>z0!yOb3XCH%Jug5z3?NZyrt8j{Pf8V-Lg;5{L(o-^pB@{iNE^l+(G&uy6ZYO zk^g7E^g0t^=O_N`iZ^1*lwW;ihi=)YXMX7%ANt2ry~JOARW9jwzx>PAulyhPxa)j`o#}&{&i>aw z{h5pT{fQ6%!i(qd`N)@j!D2lB#y36VN+14Ddfw+RR<7w|i`7@@bSOW4vO~A*(=)$x zjt~9gsb1o*zS_r@{?m`Y_TJ@x;$7EXIy=Ad_dI=L687KrTR&$pzrXyUpSu{J7kul5 z@qENb|Nbj|_&?$K7gnwpzT(2_t8_Y)UwvhVZrP`2e(4+^`o~kf#9w_?F6saBXRiHr z`Cs~PuDx`2Uh%_sFHiRW!+-pY#r%Hz2V5ARCqMJkHyzKv{;p43jQ>~v%?m5nlU{yd z^;J3@%1@u{&@KD)%rBkeL;rZHm-u^Aq;h@g$G_^Pyf6CKue#CUd%o}0H~QT30e|U6 zx1awzues6lX)paNH#$G{)qnLy|F{10*WT2NeYWcBVW0B)oAi6W;&0yMf8|$y^NpPc zp7FPD>_7Fr{?3ix$9(GFz2Wl(pY-=`c)sS}{=FOi-nOY+(krk0>A+6 zjA#1eU%l*p@2M~4Eu9YKr%!h1mVJ8Wm(KB_e>~Mo{MFag{q|+)jsNmDFR;^m!G7}y zzs)cBH1FWqe1w1VlyWtHDR1d?C_jC&L$~bHGrx3>5B=k*UgEF5Dwp)efBBmi*lE6C zzj=h;<`;aLckpaJ!oPV+xthO}w{$v`pFY{4TlVRhUpmK!{_#{V@i!jMy7JB9RsHVe zzy5O<>yPhx-7^>Kr!yBU)_=d}xqoJ{e*F@i!h;F6rO#pgZeV{?Gi<$1G-N z@-1fnyC3(E#r*!yr@zNyd>;F=?|2h^@O=N*ymc}D@3{3tiinoet%vPj={* zeR}4X&heptJk?A5r%X5ZQtp4wQ*S^0zhC!fp74#o>-MjC%XK&AjW7Mw+aL6UzvT|j zU-altyZwc4zq9y5e&5}T_;C{()PI-~Kg!;PwZ;{=ys2 zf6ayO{`x<5lm10N_eD4PXTH6$^ZwueCvWWkvj=_Yjo;sT*O%Y$`BR_p!W*97`j!{o z@Spm;DVOvYJnp(nBmZ|j`MMj!&b^=Vq>J;||ALSE#Kru6{X;%!F+T78cQ1_R>ptR> zuk_*n51)Hs<$Ca+zp(O_PKWZ-Cp&b@K0WhG=lIY+p6Vt3`qz9%zZ}%#JKp)Bi`DNp z{;S`xSiQggUwp`7?cwMC{jXoFoqYfMURe8i`X77LrfXN<`7n^MvKJBF! z);>$uZp*JdXGc5FzV@GA{USd4OFZ?X`0HPlOZt0%^oK1U`S1GV4`0mACq4Bsi`jqI z?Z+Ng$Kd-`Y(>872er}mT1+Ew~%Z`F%-SbgbVrE9n4*PgSZoo8SF z%CCMAAN?hs`ceG#ugWF8^2(nM?4%F->Bet*;*-vJra%7Gi*i+8%3C@e%1@u{&@KD) z%rBkeL;rZHm-wIg>sIsEjFXGc___FutBcQgyZDU5i_iG{vFx02d+{017oTx{@frUY zpLyX*zvhd@XC7JmXMS0H=AFf7K3aU{sl{jhx=EjT?I!=scZ=DXdR@%^%#Vxtoq2Qd znNJtvIrHq5e$Bs&m22kZ#mYPL@?tuapFT4$Z#vzwPtW|)IX?7{=ZP!!f7Ms_Dy27n z$>03NPV*Q0&0qXBf8o>og=g~@{>@*?b^n>a)K}?rC_jC&L$~bHGrx3>kNS$I`ij5$ zs$9|=|K)F9V5j+l{pJyVn_uv0-odl^2><3OGtdRJ@;4^pL;Be&pnpK=N`-AbB|^5xyQ2j++$g+T=pB;KlfM`pL;Be&pnpK=N`-A zbB|^5xyQ2j++$gM?y)R(PBCNpeSA5mm~t(4PBHtFi=9)vrMcsi$uzjLL^ zC4Kgd*RTAupS+lz*=JtN{_H<5=6Cj`7vnSg)r;|*eeA{f&;It}9cSi#j&dn)>2xSR zeX>Kh?C&|<@k{6U&_AB)CH`mMdwrdK@5N`|d-2)#zVclA-iyz^_u{kfz4+{VFFyO; zi_PQJ*V*^p^t121`0RTxKKtH_&%XEKv+uq5?0YXh``(MsImJzS1_?%NLKIasR&pE~7b53#Pxy~sT z>t7S=ELM;1)AFl+-Lr+&yZg7W_TXMFtev>83u`~_@xt1b`@Qg<1J1o)SUYqd7~XTh zldj#CUwh7ucAkChKfn4#eDs%i>PPX{zbcn>_i6c+-#uHH9rtfx_T9^c`E_3x#>YKg z7*F?mVf@|ug_X;FU|4xer$hPalO4KcpPu=pbA0F@PxTUi^Vh^e_wr?&bYC4de!9mF z8&}?j#bblVk-@STRx!kvh zmA7;{l%GD?pGLk% z`jvm)>s!puyyLf+{dwPSF~9Tf-(q~`J;23y&O3pN@t^kt7c1AiE4WyBOQ%Em>60D0 zWuKn;rE`4fA5ZlXfAiPGxa-UO<$GauXZ-XXF>GA@`1#%$Hs1Q~7&Z?39vL=1|B?CL z88&YFei=5N&wG!Hjq|>DmTvqn-MmnK^F?;dBiT2<&0q01e^oB&z8B_K ze%}$p?D)PIX5V+mFu%S>hVk*8GK{D1mtp*U*9~Mo{LNprL*r!a)A(7tHLlj4jkmRP<8bZY_*}m*Zr5Lo=k+7weErM#U%Gjr{N{`7 zm`Ad2e#x(SCqCw*c$%l;Z~m%W(rcgc*KXOVJ+ogs=ePEcPyGVV`V0Q`Bju`pDR1d? zC_jC&L$~bHGrx3>5B=k*UgEER%^Lg7+J<`cz80*0y}Jdgckgj+o@oz{p7+6E?Zo?C zu=e9!FIcKKv!k77U;EFmei0x2C7$|G{PnNOCEfd4 z{L1g$EtnnealvbU-syt*^?nzOk9WObJiYe?6p1}ksrbSOW4vO~A*>tByP ze(4+^`o~kf#Q%yn9=>y>angNSevO~**}}$E_ith2t$Vq!aoBxb*!b)oFKpa)zZW*1 zyY~wl=iLW}jsK;a7s_wG$c}j=`{tMYns?%3K8mM#D*jizag|HD`?UPZ@18Bpj{CPT z`|jn!{JO6TaPFFrL2ug7NoV7_3~r7lW0zbUKuuKG~sL z_UV~lI>(3p@l-GIS6`J&y6>&{mEU(*Fgw1_g4y@o7R;~jxnO*J=LO^G`!5)O--W@- z<$Ez$c}u55`RS7#x@Di9`K5Dw=pRq@5`XnI>y-5+ed7GZ@=yG~n4MV{EM|Y!3yb-k zb;M$PW___3&sldY#(&l$i(3p@l-GIS6`J&`mD>= zul%!KTg=X^;})|&>$}DL&bn_gKC>QNjOVNq7vulJS6*1TW?i}I%3C@e%1@u{&@KD) z%rBkeL;rZHm-wIc^7=aKvc+e;w)m{$7N7Oq;&nGvy}9_T zLl>X*>Eg3)U3}KFi_bcD@mc>aKI`JeXT5xrUU}tD2X@kj{dD6uJ@H9rJkuZl>P5M# zFXb(r4&|p$cIcLUdghnT@u7b_)l2-v8?{68TJ6((SGzS2)}GCewR7`k?caP_zcA0% zU(CPtBlB|o%Y0qBdA$7Q_w1PWvo9XVuQ(w-;)i&OE8;KSs9e%3ul(u2PWrH)Zv3Vv zKIx2S`r}`{C|C8Ryrt8j{Pf8V-Lg;5{L(o-^pB@{iT|0ucCOU#d|zN3)*pR$0PCl| zM}YNT-zmWQweJ^T{oQvBuyMfm4zTgTcMz~~!}k%e@uYO)O!r47G=KBbK<@enI%#QC7VD^2d0Q2kn1sEUSHNbfK-T}tncM!00`91P zuYb*%*|rV!IKTV0SpClL!7Wzr^E+{iwTJorxW(GZ{I1+$?Pq>(Zn1VXzeBfJdz;^< zTdW<<@768WK1tB^i`utAc`jvlvzi%-+^SgeF zH{STC-?EtB`5nN;_{{GEF2-|yH*hij^Lv7em1}-yaIx~1PKWZ-Cp&b@{>B@}FP-B< z|9GmG_^Yq_m-O1F{Iy$lYR~M~&iSqV<5R!Dv;KmA{Ybg$U&>oL9m-Fi?9eUy^vo}v z<3s;=s+ahyulm^n$DevN=!{VdQ;-lNz zKYA`cIxjx@FFy6M{Edfm$6(ure&_ukeP4g{E)cArdM^mpf4w6F>(|~Fg7tUr4#CC& z?-9Yq2k#WY#trWm!N!x)jWgvp{$$6vlzrn>evM=CF}}sqxEFupVdawU{U3hi_bw33 zj`xCK_Prwn^ZRS({UR72?+(FudXEUk-#bOHa(TZ9R^HO-P=5Mkhi=)YXMX7%ANt2r zy~JOA&ARdyU(&rt3d`?zT48qlek;tr-*tug^?R={K7I!l#&h1eU5vlqjg_ukeoq!w z-qPt%e)?pGZrP`2e(4+^`o~kf#9w_?F6rJQe7qwH z~4TRI)ePoM12E&KG$ zFP-B<|9GmG_^YqVCEfdV{L1hBJ(!*Ou5&T_^S$R{e*e$>zP3F0%=e*-@tp5Q7vn$Q zlP*>+@9)X4yrt8j{Pf8V-Lg;5{L(o-^pB@{iT~+e_wglt_B|HMKl>qz*_nNk#q7`i z$zpzIUu7{qv){6K``2?WjQ{M5B=k*UgCfH z*ZPt^`&5hNpZ%-F?99H_V)kdhYcapG54ISe*&kcH{p$@E#((zHHeI>=etq>-`u4Ar zpFY{4TlVRhUpmK!{_#{V@fUB*xbbGb%xm5chs}4>9~YYkr=Ko1KYE8;9`ok(>&52N z>F2xSReX>Kh?6023 zFP-B<|9GmG_+RHKPu;oFI=c0y^>yn|>+aU4*5j>PtwXSddYrWsP*gin( zW%~oA+czk`{e!h>c-qH^|8<^nl}mc-P5E1gveWvM{noAgww}eO zbuON*fAMc!tX!>^mA7;{l%GD?p6y;;80qxV-~_3K?$SiO6%b@NPn@Qy32op|3B z)_%PE3Ts#1gN3y>@5I8|q4#59?Xz_4w*1<2cC_>CYybJxFXE%W#8W?tzy4LZqUM=5XVbSOW4 zvO~A*(=)$xjt~9gsb1o*zABgW?ib15y(4zIkF@o5?nm+4{Uv<5*Mw*Ho$&7-lyY@H zN_k7CL;2~G9lB+I>+ATXbA0F@PxTW26CZBdIC0406Q3+Tam(Tp&n!N1&f*jQEIx73 zV)0?;k|&PZ^b=n#K5^IL6OS!EaoXY&zb!s--QpAPEk1GJ;u9ak@vapvL^ ze=a_8>EaWwE5{E}buPJGNq@ib4x|B4TMYyaG%;J5n~_;l|A&+cR3-#rcG z>i&lEmQIKA(m z`%Cz@@1$JqM=5XVbSOW4vO~A*(=)$xjt~9gsb1o*zABgW_H*QKpNF0Hf7owdh~M^$ z@M#|j&-Rz_Z{JC|+K*D+(&knNJtvIrHpd{Ad1MtXwlMFIL{t z=}><9WQT6qr)PfY93T3}Q@zChT7Uh(`ZBNi{daX|zVo~AuzAq$#lz-DzatNuH~qdm zY(Dk7^RRi=@6p5NU%yiio0t85J#4-%-8^1?^Luv8``H%{&w}(Zl%roqAZg{C+*Gyrt8j{Pf8V z-Lg;5{L(o-^pB@{iT|~K_@CF8dF{&{_mhjwci;8t|7o##@Rfh&Cl;F@@BEAZxY)e; z`#<8s=F|W5`v0)$=GpIl@`cU6KmO1Qo0lK@^Kaig=IheU5d zKg3hK5&vud@G6(|d*5|o`Jem4?^q7(y!NmB)MEC3;c5S6F~2|Z^B2bF_k8&~HyzLC z{@8`_zxxCK>!vH$V?Xl3%3C@e%1@u{&@KD)%rBkeL;rZHm-wr%&h?~s-Y0+Ofb4WW z$bRRB{C1v*Pv?wycK(Qe=aS0Rd8P7}PKWZ-Cp&b@K0WhG=lIY+p6Vt3>Z@`|@4Qd` z&H>r!e31R$ea;Q}?K}~m&KdFS{1N}oC6%l5O64t`4&|p$cIcLUdghnT@u7b_)l2-Z z`Rn1^PK=XtFLAN)bM7lHHm=S+#>K|lx!<_hI6U_r7aO1FKICHK_S} ze!t$hVf-)Myik7gMRv?1**CxB*Sr%S^HDs_Q}Ms%ud7_r=N{?$m4EJ+E@o%$oi1j7 z?xQZ|ckZb!#%J!YF2-~2wJyeg?z=8lF27%|T*_NI9m-Fi?9eUy^vo}v<3s;=s+ahm zc>We&(kE_QEdRuli`khtb20mKe|Ry!6PGT=XX4excupL<82^cH7c1Aqy^EE%bUKuu zKG~sL_UV~lI>(3p@l-GIKk@wfl0I?%V)-ZjU(C*|3l^{akNnZa{LVUJF+Q`tSd8ba zI~LMQ;yKHRn;4yk>LPinW~mfEv;rgkpQsr`$8>KEdo`ipp}ek6{n ze~GV37k8CkJeD1CTK2_n`4!j2N4ytLabWyUe7NP3Ui*~4cFRufdF`Ke&Ts7>pZW!! z^%wl>N6JB@}uQ(w-;)i&OE8;KS zs9e(feoFqnt750`t=R87EPnew3!lE*!n5zW@b5b>0>-fLb~kImQWw|QK>H@|BS&HLI(@qqSIoSKF0RU*f4B#sAvxy~-uM`C9(wadw*D*>B$Gw|D@b;siX4AMh`(P_E() z6v3j3()E8?H^S=6G z?c~)Ddc?b+1LK_t6#)Ne~G7l6o37za!GIfB7f@|c3SVS-#Uoj z)<^iXZo;$m6#lKVl&kfZ@|I4A^3x|fbjv1S~KEU>6apRmjFBVVEdGum&=A2V67Jtt9^14L_&Gb`>gAU_q>2xSReX>Kh?9(&9bdC@G8bssvv!sK+FSLa9adl3XX)B)`L*ZlXy@72{`0F} z#7BRLr+yUwYd`8Lm-Naje>$*}KJ2F(zv+ojI^&uC+rLh|C|C8h{p+ODq5Sm84&Aa( z&-~IkKJ<^LdWpaK8h>{h5C8Yqzvp84AO6@2v-4j6_&qkA{U7cYzPr{Dbxn@4#|r$hPalO4KcpPu=pbA0F@PxTUi^;Nl~f87hN zGRpt#cU+jAKldrWXv@X^8^8I&{C?Glf{>H<~ zC4J5@*RT9@zPXs4Irm)5{+x#{=6B9X7vnSMr;G8NbJfN8&w1-&<(hNY#mZYc9m-Fi z?9eUy^vo}v<3s;=s+ahm{&ipdYwB_Fso%w?-WQ+tu=uo-#i#u&KJ9ApX>W^9J6wF) z=i<|D7oYaL__XuIr~NNJ{bKRyFN;qbz2UOQ%Em>60D0WuKn;rE`4LS3K2M{7-zi<&xfc zpZuKzveWq>`<)x|+j$~BoipOu`6K?FODb3AmC9Q>9m-Fi?9eUy^vo}v<3s;=s;~H4 zf6ZH&TkqohITu?j{-5)*#nuILj&|jl^}?L5Ew+xBbGOCT7jquB*t%oR=@wg$%=z77 z>y$ayTWtMOx^+$Yt#`6x9h80Rqx@Po#m9Oop4M6MxBjYJ(&rp={mMV*n~T|*bI--> z&w1!#e&?KYF+OvCx){$nS6z(%oVPAkt~rNYth}Yuq5Sm84&AbE{gq!j$A|v$R4?&Y zU(-Ie-$`#glz-;CO=oB3!7I<$pZReyzcX(x#%Jc!#dyv>Z^1*l%GD?p^W)t2UTof+d*F-Br*l7iv3YjxjW0I;&VBO5=Hh^ z$gemdKH`UXiYwxOou^#ol0Nt9*RT9@-+nPWa}R$p`*S~kF~4(fe=$CDpMNo)bI*S< z{&W9-v2x9K0gIKlbUKuuKG~sL_UV~lI>(3p@l-GIKl@SZOFhoM$71z6`yq?f`|Oik zd8R$g{>ftPWcF1SYd^E!vRJ#CeVD~(e`fL7w^@Ala~7X{p2ga8cC_>CYybJxFXE%W z#8W?t|JjdPo6={WYO(yYf3=vM+1Fak{_J-x=6CkN7UMJfV~g>eeY3^*&wkos<(hrA z#mZYc9m-Fi?9eUyXMb=1m(KB_e>~Mo{MFZdPqg`^*FNR1-Lg}AX1{jMZ|xtS`URf# z7yRo-%2oeT-qPt%e)?pGZrP`2e(4+^`o~kf#9w_?F6p&T`D?fA)SlU|o%37!$ESXQ zXZ;2L`jK+gzm&IhI+UM2*`ZtZ>6u?T$A|v$R4?&A^|fQQ^uBkKzwhAK>H9eL`)-ck zzNf>d@9glLcazp8{(YCHTz#*nyrt8j{Pf8V-Lg;5{L(o-^pB@{iT|munU&PbSOW4vO~A*(=)$xjt~9gsb1o* zz9x>k>0jLklfQdn>~w#O{qB|V+kG>9x`&2m_tWt2-kNfCpG|p7r$hPalO4KcpPu=p zbA0F@PxTUi^;Nl~cOOjt?uoI}{W12tSH^Gm&G6|S8lK%x!@qlL%GG@~{1 zp7T!QV*Ka*#>L7t?>a74-qPt%e)?pGZrP`2e(4+^`o~kf#9w_?F6r}*<@%L>-nU%L z&b)iMnEiPVb1}d3PUd2K=KajYc+R_;i}9cLHWw?`yu-Ozc}u55`RS7#x@BK|<(JO! zp?^HpSNzpi`!>?s&yl}<9(LOQVZVJLe%mj?r+p+m+h4-JeJAB=KT3H^r$hPalO4Kc zpPu=pbA0F@PxTUi^;Nl~x1S?_`#kKl|HFR!Lj1O0girfOc(%WUfBR0#)qa%nmQIKA z(pT%k7(&9JqYH^)7w)jwd zJLh*h-imwYTyL>>xO8!H`NhxK5m#qlyq#Zhcznd?@f5em|2j{($|b${O8(+5c8bT? zFFxeA_zj=pIy{T_@GlNjuHr-GEu9YKr%!h1mVJ8Wm(KB_e>~Mo{PnNS&DCS)>FT$0 zcJOO$-mQIKA(3j7epma{A8WVzY3*76t)1)F zwSWD+eqkJ_zZf67S7Y3$e;H3oH_nvb_>&#uQud8k`8AHk$M_ac<6iuYhm}iu?Nk2R zEjzVm_G{<-*8cISU*K7P!M}c_T=g&IEu9YKr%!h1mVJ8Wm(KB_e>~Mo{IC7_YrU)< zTW_l0)}iXX^{MvIx>Y-AJ*)k+&eg73|7vfoi?zen%i3q@+HLu@=j>?b+1LK_t6#)N ze~G7l6#r{~{wkOB)|>LT4rQnHDf_Kk`E5OmPwQMfTmRzUx>&hdFDq~9bSOW4vO~A* z(=)$xjt~9gsb1o*e--zt$Kql2Tb!)ki=VZJ;%e=rcw74^4%e=V&$YMWcI~iuUi&Ov zyDh)=oE_~v``Ukg^^5rEFY(lm;;(;IF6qU?@)swwQ~b<+aW%ii+xQfR<5_&ZLvc_Ywp4B+Clo2+%H|s&fGg)%>LX* zUCi&?Q(cVD++SUc=iF;ujQ`wsU94Pl4|cKgmQIKA(sS7{54@P2xhK4s{rUZf#r)2_;>GyPedEP=&OPMC_|N_1#mY7JmKQ5;>2xSR zeX>Kh?9(&9bdC@G<9WQT6qr)PfY93T3}Q@zAreN`^$^Df8wm4Dvr zSj^76Q&z6NUsm4I=}><9WQT6qr)PfY93T3}Q#>Dk@kZ^?yjJ@(-_>r-gSBV# zW9{6$S^GDi)-TMn^%wJR{m8sr|1w{fZXPec`8_-4{p^be@+(e=kN6>;;)?i-H!7F( z+Nb=rTXt&C?AOlut^MOuzreHpf`9!;x$0laTRI)ePoM12E&KG$FP-B<|9GmG_!|%B z++q8&e%JoC{@A{^e%gMx{@Xsee%=1L{@%X2aiINn<3s!K#*OypjVGlWXUcE<$&PU; z`^KyM8pq;ee2b@XFaE~E$|b%1ZTZ{xW~cpd_S+}txBYW`+E>T3{q`Nt&wF~x)&BgB z|0kUe<)=?}=$3tY=9kX#p?^HpOZ?T>^yfRBFZbS~{JjIoPVYmq|AzBkCBMBViBIoL z;@SI?`1dZQa`j%N@|I4A^3x|fbjvF+ zP=5Mkhi=)YXMX7%ANt2ry~O{Fhx@&QdhGpM_1n9+>b>`JwTIr()lPa}SNrMR-5n3l z`@Py*@APViz2B>SmcHZR$*(<9WQT6qr)PfY93T3}Q@zArea&}L8_!GcJVO4?DcI@!g8j}l`0cy{pUy$>?0f|O z&P|l7^AzPRoet%vPj={*eR}4X&heptJk?A5)mP<`-g$)lol~&W`33u(Yw+872R@yH z;Mw^I{+*jBSLZ3pTRI)ePoM12E&KG$FP-B<|9GmG_^Yq)IPXVEZ~Y>F>l$`i@37xG zh~L&n__S`qv-K4It+SM?^_TLNPKWZ-Cp&b@K0WhG=lIY+p6Vt3>Z@`|Z~Y>F>l$`i z@37xGh~L&n__S`qv-K4It+SM?^_TLNPKWZ-Cp&b@K0WhG=lIY+p6Vt3>TAAhySMw; zy@w!w?Lvc_t8z*2Jp}oCCxM;bPhh`y75MGF1$=sk0ngrNz`u7Jl&kj~l(%#`l%GD?p(3p@l;>&S6|bg*RS;MpUdC9bauM0&VKjU`R#r? zKHYoAv-|M)cTZlqx<9YHrPHDO^vMq0vQN+a(m6i#kEeQxzxt|N(z|~yfA`Ya>ApJq z-DBss`|bF2?;X$X!{gsQdFATLvcx%bhz|mvtUt zz1BH}bzJ8c)_0w2Sod|_VLjM6h;?G;Bi4_dn^;$No?^XOx^-yztxvOK-I{&t+5B4P z#>e_Mp4P?jw_dJX(mRikzjF$9I=^7Qa}9nw@4%;X5Ij2{+4b@{Pf@PUQ+B<4(&}&t|)i2_szr<5NivP74A_3vp5XMZ8o$5=Yg)#8;(@yUH&f%Z@lL`{K9!itFMd-ixO= zF#h7h$|b$_DSz#jo!T?|wR3)J|M=7|@T|Y!-?^l6)xVUtbUKuuKG~sL_UV~lI>(3p z@l-GIKk?zl^Xjqv0rlIyfqHL0L3?PQK|5*xLHlW6Lc40eLVIf;LpyALL;EaUyDh)= zoE_~v``Ukg^^5rEFY(lm;(y}9EtmB62jp+xfSvXe*l(YK-}WEyX<9WQT6qr)PfY93T3}Q@zAr|LUHDdhGs#`t4qXdhfo3_Ru{F?WFq^+E4c` zw5#r8Xm8!q&@adf{JbS+j|K9aduHO4n-qPt%e)?pGZrP`2e(4+^`o~kf z#Q)mgxXLBH_p;>g9W8cxUyJ?T-Qu_RxbW$nEa!GH0K>qd(*l9n3{q`C7ZT|tE_9gIa zzXJdEF_f$Q4dpGJ4&|p$cIcLUdghnT@u7b_)l2-6u?T$A|v$R4?&YUzJOG@59L7yD{wa zo(%iFGsAE1&*0O$G|1UucAV8445{C2+rpYC1Y*?kQByQiUC-QQ5&(&D_;jzk3nvbYFt~?osgD{R(`#cY$a3G4Su6hH`a(LwQT5L;2~G9lB+o zp82J7eCQuf^%DQH-}~nFd*>an#m3KhA8fI4b>0nIY`lH+`TZ2*@Vqm&>Bi@Ie{8XF zd)_5mY&@U$$`%{v`~4K-f9d9h@|!QRV;;%A`6a*Ro%ooK;%T0W|Jm}}!@xSWp`aMMH{hpxw{mvje{r({P{VpND{aztH{f;4?{k|do{qCW1^?QiQ zTRI)ePoM12E&KG$FP-B<|9GmG_+RyPl}mcRCn$fvGssTAKe+bK?-KIc?-kOar$hPalO4Kc-*}i`I>(3p@l-GIKl{Dw%et)lD%NY=W3i6w zev9>8_g<{~x({PL*gYBR#O}{nKX$Liy0ZH=)|;hUhnC;^G&|O<*|(m}uXS#GtbgNa zT^#?j-@E0K-hCDMyT`&#_gmQS-V49ohry?NGI(}>2LJBWC|CDwl(%#`l%GD?p=;H>!cfJ%5VJ1j&Ujb#;g1q$Kqpri>Glf{>H<~C4J(?(3p@l-GI zzt&&ZIIrI|{_Bs;3;JpEh5p+-qF*<^==>7_ zZ@kK{aV$Q@w|E-&;(x8bu5w9l{FlFZft}`ywSVRjew$zLY2LxJ`3V2!DdlSZQr^<( zP=5Mkhi=(lJ&#{H$A|v$R4?(@zb5Y8cA_39Zd|N>C!Soa-Y3pntUXNpxmY`yxOB1h zGx6$T?P}uK#oF7%w~MvIes5I!EM2=TzxJFR?L7P1e}46g_~#md$1jVf>HbSOW4vO~A*(=)$x zjt~9gsb1oL;*H%GRgbgpu~_}ie#m0=KKmqBp6Oq+f3jFRnSGVT+RyB_EY_}OA7-)k zHv2P+wZqxBS*(4QuHBYjd(Mt_o_*~=o}yV$Meinn@4;&=S17D#UXRfvRHgF=P!%J zEpsljSUfZ5HH*bLbB?oE{4?h}i^WBA?z4E~rI%b-9M$h}YtEA8?yG;zz52!KckbISR_}8U|H?D{ zYwqVS)=uW${$lNC?(;9!uAcI|3u|w4|9{i9!}%^?vG!TIc3Xb!IXl{U_O<`~>KF0R zzv8KX#b5ubT+-(|i1jP~d>^rxo%wEJG5hm9#bSQvJB!8m%=Z_I@tp567UMtPYb;i- z`Ho|;@|I4A^3x|fbj!Z}m0vo?hyL-@zv6$LS6=m^9xJc?b+1LK_t6#)Ne~G7l6#whI@+z0~$}4|5u#-OQryIZN ziBCG?nf~}!FUnPYDR1d?C_jC&L$~bHGrx3>5B=k*UgCfH*PZ&;q%S`8yZF@mmFH>? zi%&aQeA>_A)2qC#<9g` ze7o{Y|BAoCYybJxFXE%W#8W?tzy4LZq!$m%U!2TN@iY6y)%+H3<5L`tXYo1y#qG*fJg>Z^ z)1mzI$qwDJPtW|)IX?7{r+SIM{x$DnZ7gb>oOe_ftKWHFWwCmncUP`F(;hzTQ~&g0 z?PT6*S*-oc`z?#Lt9jRDvGz9ay)4!a`@L-KvvlpY{MvJNwDat1|M}G~;-i1XQ~!#; z{#Ci8&$~CvLH>CUXE8hTPR?TX=lz_;{LZ^Ni}9KFb{69~@9-?ff8OU=tX%zGw(^!v zhw{@WJ9Nvw{*_-k$A|v$R4?(jUY_p))~|Kh+^b(~y*Bsl7hA{8J^aPicXK~~v31|v z+h1%wIQRJ%TPMyv|HamibN_#_b>(~)u-JODbnDRaTc2jfx;6XOv-!2ojgR$jJgtl4 zZ@pZ(q|bK{>sS8yK4LLD^WDVaT`zyn*DmIFzOz`2&wPKe7|;1GV=?~oy~bkYn(sIk zD{tv^C_jC&L$~bjdinUJbA0F@PxTUi{i}P+>aqLG>bHB&>b?8V+C%rEwUh2kYd_ti z)~>o=z4O<(kF6bcAA9Goldj#CUwh7ucAkChKfn4#eDs%i>PPX{zbcpX?la5ZJ!f{h z|IB{(qWSHGGxw?<7yrt8j{Pf8V-Lg;5{L(o-^pB@{iNE@q@3L>^ zwfV03X1<&6ofoq+-$7q_#{PUCy_nzmZhA33^F8%qJm)*>#rV(rsEd_rzRO;$yrt8j z{Pf8V-Lg;5{L(o-^pB@{iNE@)T+-(|^z|$Me4oCUo%wEkG5hm9`(l3QJNL!-%=hn$ z@tp7C7vn$Q%P&^0`Hp_E@|I4A^3x|fbj!Z_$}gScqrT#)zT&UG=HA!(l0NsQ7R&#A zA9Z1N=APA+XY9}YtHu1zy{yIf%zdrJc+Nep#rV(tuEokV_r4Y@Z|QU>KYg-8x9rn1 zzjTfd{o|=#;;+6cm-M;kwtnTG`)`ZcnR{`I*`NDzi}{^49Iit9!^GESg=aS;6&MU=NrHi}DFCNQ|I4%3)xBQCh;v?RRr#LYF;={@%z4Jc# zI|pQ^^Fj7IH{`eTM0`4D#Iy59{5zLauFfl!w{$v`pFY{4TlVRhUpmK!{_#{V@mF7W zKkV7}S$|1?-HR_Q|BD{DFgvgQtmkYV_W#KnFU;=~-sicSj?c56a$!7Q^!y9s|G?K> zSh;@eo(n5)>2xSReX>Kh?9(&9bdC@G39_^t;ac^vBKt_0!G=_2147_3O?P_4m#hjRT!O8Xx9<*B$M_xY2o~@uYO) zO!~ucJe&>e#cAkh&=ZtuE{)m6) zlFHS2rSg_ehw{@WJ9NuFJ@ZTF_|QL|>Lvc-`Dur%r?_$Iaj|%E>UXg?bLxGu_;cFB zVsYuTlf~lIX+Mj_vD2;=i*KjBEf)7qJ6tRtE?t~le(`g5#MRjsZ|7GW9v|^}JjLzt z7tdEN>C^Alul&;=7qc_{bTRwWe;4yR{dzGz)87~4Ipe@${AYYvtXwm0ELPsq=}><9 zWQT6qr)PfY93T3}Q@zChT7Nx!*ACJ5B=k*UgCf1YukqO=4<(z$JuFqXTN!$-{Jv$ ziWBfGe!#!DLb-}Jl(%#`l%GD?p^JZ8 zTRebIaRQ#j5BL{XC|B`@@|I4A^3x|fbjvZ@`|f5u&RtzY@){n*9q%)7FS*`N1j7xO#s&@RSj-ltuR=e%3H82@?C zcCm8JJGYCKw{$v`pFY{4TlVRhUpmK!{_#{_@mF6nU*0DkkluNO{GC&<)AzX$C|Bnx%3C@e%1@u{&@KD)%rBkeL;rZHm-wr%$|b$?2>CmwV5jp7 z_B+?$xAP8sItRhC^AY?zH&L$6Q6u?T$A|v$R4?%tAAasbzx*3J zPx+Z|c-yzb;**y>_Osszi(B6E$a@xxXWsp7_b(Rby!D;`Yq9v}2cPtiH_0z9ddibO zV6k}V^SE3S)=crTvf!1#*~f7xTdV#{^X zpNQMZ|1t2fv-sFweEcpxd_GqG!*lWBzxb4E@hR`(qr>8(&*G!o+CO?OJ~}Tx`d@h_ zKAdtbfAv)yC2lOflE1i%o#HX}i_`cme#57@4$tB}{EGvXtN2iPOQ%Em>60D0WuKn; zrE`4fA5ZlXfAv+lq!(YwU);q`@fiEXY5W$y;Zt0PXYn5X#evFIe5kyo)1mzI$qwDJ zPtW|)IX?7{r+UGE)_Hek5Bt^wuYAFM@E`w`-*r2D(l^gZU#xy--(d5zGxOkL_Gf-v z%PWH`5`87|)$NUvf^IH7P zca=-J-&5dMe!sH-v*Y&{VD{%cZZW@puR%IKe#ZgE)9*XL`1{=lSh@Tj1gyNJ)1mzI z$qwDJPtW|)IX?7{r+SJ1*>BvoarU(qpZ%`IXCG|w*&kbc_RSWb{j|krpKbBke_K4| zx#?eLzi!jdKHlQ9zqk18`z=2Efs4;R;o`G@xcKZVEH|e!c`D?fA)SlU|o%37! z$ESXQXZ;2L`jK+gzm&IhI+UM2*`ZtZ>6u?T$A|v$R4?&A@&C3B^*C|nV)g5H7PJ}l z?)Mj9?ZNLdz}ku5Yk;*MzvBRFSAO3C*53T?1FRkTJqTF)EM2=TzxJFR?L7P1e}46g z_~i$B%|JJ;&gGDrDq1iwdd?;=h@f(D_6hBAN?gi^{@Qb zzp9sX&*Ljs{yVQ3v*Y=F>Fj&1A1l}M{+K`B1AzJI{Q!95!+rMw-@m<20B<~b>Ecj+ z@yU+3WnVliSDf=l{PUA8`A;wJAyJle?qk`|>H@sg3t8eMzP=4{rj<{uCJS$h6^GE#ilP>vBuj(b;`$?25zxS44cD&C7 zv+q48Sh?PRg8B1X?|TrKpWc^(`R_d{`2OwvDp-9>7l-nTPjcS-IkzKjNRCbjknEdj7{Z_F6Z3pQm!I zC%xwrTW5OzC$|3dUQldZ>V2WudewVGv30EXi(>0r?;XX~z1~NPt%pmuPASiQWD6svFP;!u9^$&R>XUpy;UobyNg^OG+5Z@p1FG_Tb@&3Cn1^I+}S{8&3T zZ`S_Jr}Yc-Z2iUjTR$={*T2lyrJKjgZ+_2?c|ZHs1C?u?kU!QB`DtB||JEDTOM2~7 z{@N`&wP*Hg=gO`9^QV5n&-x4h>qqKU|5D%5#i9J-lO1u(zIaxyIOmV}=OCgvw-ze-(SG`ukSKo{o3~$u>S5l4%j&0`wrN6=(`X2{<+68HlCDj zoGHKYCp*Ta>>IBt*Ep6x#<%=5?&ZJnuzE@NJq13h^a9p7KT?E5YQR<7?gVE){F zp)o&w-$DAu^ZV`tzJKl=jW_&j@iH8Gsnuk-#N$px!*s>{Jh^q$NazFOULTvdl2laZ|UMte(}kUxMg2F zD_5NJNBr}XF8NQd>LuO%XXVQ8{x)XkerF!D?;f>u<^I+0`fX$W-0#(6e%|lcWB%Xo z+vEEizk83>w{&qRzxZTF+_Ep8l`GEqBmVhGulzTEU4LF##!1h2^V#_6xo>P-^*lH> z-g-_P8;3nVj*ZWrE62ud&zoc8x#!Taao+Rk*!W+%d7=E~i|m+3vTuH=T=P!;n2++) zJeB|Euj(b;^WDmo-*exX9nXVf_B|(#mFxL&%pcE{V}5$x9P{6E=vcixpN`eHba5!Z z_+&@ivM-*ME6({N{`pCl{D0%&z5DFbzdYZE>3h%Hj_H2S;f}Qj&-clro!oP~W9{dj z=N)f6yze{6qrKhpzvKJ=eGfvq_F4MI!`h&=lJmb+w*-`eM{eX`0|TScEm0F zi{~p>obyNg^HcxI|Ic~Z&wfi;<~8pd#O6EiA;jiE?U%>49E(2Ds?=@il_>KeSr|&yp{`>9&RxjU! z!0KDNIFw&}vLkNU7thKS=ll`>{G?0%)2n((_dNyW%I`Z1m>u6=!0h`j16Ho@HDLbu zjsxbW?>k`r`|bl)FW-Z}>RY-vlwW+ZBW~Fj&&n0&{1N~Bq)YzO>&{wMmh|>7^0%*H zr~MB5?Squt{)j*AoA}v&ivR7i)T{lM`j##ZvvS2bf5bmO>5~8Ss$SCD zzsTRdhMo31?6(h6Zu=wtv~S{P`zijn&r+}UU+P=BIFw&}vLkNU7thKS=ll`>{G?0% z)607WwGHXsH;Co;9zx8H_Y-3Fy|)l6*ZT}Hf4t`q^V9neG5@_65v!N?C1Uk0T^!0U zKG_ks?2BjRigW&me}2*>|LIk|qa^?3PLd=f$6Jqwgw-77W`wTIEyyp<})B6uG z|GgIxtC#mBV)ZRu9Lg^~*%7zwi)ZDEbN+~be$plXKkNCQ{f4s4Yd21g&389`j?IHN zu8z%*H{OoTn>P-R&8Ig$kIl0;Zja5sH=d8LjC~J6S?24~&Ew@azh}q1pMC3r%C%0& zAM1zww64hi&wBn-FX=b0%?J5!z8kZ1^Wd2Mn;*x@y?JxYpPNs|{JeQ~%>SEz$Li&K z5bCAArHe!P#V0%BmVNQ8Tyf4H@y}1X1HONI{s^mY>Ecj+@yU+3WnVliSDf=l{PUA8`A@IvCEfEo%9Y=9 zJ(wNO`(XAx2ZWXD`5??6&kbRIdY%aL-*ZOz{_XiAtiGj-L;1xgJK~mo@vK~N&L8p5 zPrBqky{Y4+#6LgjlK=FoUea%0wsPga{o0tF+sBRBzx~}g9V7@~Cg=;!u9^$&R>XUpy;UobyNg^OG+5Z@=8RgMC@&5%z1H zQ`pCKeqn#txrTjT=N<#yh|pUy$}+4;!!%kMlzy}YlUUfVCfba5!Z z_+&@ivM-*ME6({N{`pCl{QvBi|LixEMaP@h#`L}UZcO)^2glmO&5vX4_H*;; zSi8D;cC5YK{5#eTeGfue+Gpw7ZTYq5>}coN*ZwP4zsMi`B|r6}{QvBiKlPG+>yVWz z|E*8P?A*F#%>J!s#>%~Q&X_;9{u%T0){G?0%TOZaAtwU;`)+e=F>z3NH^-S&DI;Zw;{ZqfNE~>v+FV&B%qv~JQSEXBb zmEU?SJJxC0w|=W!>$?20-pfzx!2Gv9tX|SKFN=zvQQWl>cvixOz$N z_W}9)-GH5bPhh{_8I;@a5B%wO34Zo_1^@dUL%sTaLw!pZhw_V0cEm0F;#s-koIm29 zpLEH8{i}NpbnN~EeY+Py_wGw*58b2CPP$*A{dDg_yXroM_SQWO?XdeB+Gpw7ZTYq5 z>}coN*ZwP4zsMi`B|r6}{MWy#m-OyG$ltvPcDgUYe)lMp+x-gubnk+n-N)d+?>=bf z>g9V7Sba+uhw_V0cEm0F;#s-koIm29pLEIp&+i-Gv$0qDJ?Ao(|DJytvvbeIjM?{H z2EHlxo}(G_=bo<_^Yfm&8T0?1#~G`a??L!m^(|c-$}c|I5x4A%XXT1>{)m5m(k1^t zzi)i%CH%)Eruny_>0qc`~H?VH$_XO*ierK@G>GucgpMICH zF6#FR>!p6ju#W2Y4eP7Yt-H!^J(eBowCr2IRjzei{#ftjr*&ZdTOU?0>HR(+f4>{B z)9(rF_dA1f`~87G{Vu`Jey`wvzhkIZzi+5->Ecj+@yU+3WnVliSDf=l{PUA8`A@HV z&UAfQ`aP#Pmj9mL9J6!Jb$;@k{h#<_A6D)?2fB3r-1DJhe%^DVWB%Xsq+|8+JqYbk zeM=XI@{3P)#4Y>cS-IkzKjNRCbjg2uRWIrHT|--E#FTe>)uUwpD7ZrP_-<%)Cuh<|?4CI9KwJqPLCe~`a> z5$tqdg8lAMD7X6+{OR5WKf8~?|L$q1SNAv6w{&qRzxZTF+_Ep8l`GEqBmVhGm;9$! z^^)HG2l=}f!A|!j*zX>Na=Tx_pYC1ov-=qQ@1BNwb$>&BOBaXoi%)jME&JkGx#FBZ z;-8;%$^Z9z?@wwQ#!25(z{XGCS-{3s-(SGS+wZ&YL15#s?=@iKv+p=y5~5+ zy?*n`lJ0%f%9a1lH^=PUx#yUD@3odkxpz)F=Fgp)u zUwpD7ZrK;l$`$AQ5&!(8Oa6cK`qWFh_facXe($Nq?0A1Qp8b2THCC?oU1R=u4>snf z_hV!Jdv7*YFYnXF^eSB($}c|I5x49wp08YS&L8p5PrBs4@z8rnl%?O@z522Kc=zqc z`sv-n|Kz#;d-wCl`t{x0AM5Wwao>Yr$2f5J{Kv+JyZ=8nZg}2V9^*;r#+mXPf3jm- z%D(Zca*bp8V|>d`<6iz75384S&kHM8e$NqOc06B<+4tNrR_-78dEYzckLQ%7^V9Ro znE#$@#_HvHXRN-Zi$nRvCp+SnedA%}igW&me}2*>|KIPuE6cvD`zrQp-D9zj>wb&< zUH4w>`??QfKiEAP`^4_g*gtl!=IZn1zK#86>Gq-Jw?EB}eQWmZXDin}H-GGZ^V7aK z|KIPutC#fdtH|Fy7IwPd!hZK&l-qq6{&Y`)uUwpD7ZrK;l z$`$AQ5&!(8Oa2=Vy@y2G(C@sT1nZC9TY~jd?=!*rulJl_{o4Cau>S77DA+jQeJObJ z*S%i_8#laP1#kX(>BgDz8-KE6T*|)js&b8E`D1*`Pvc(x8xO0ObnhoouKeCxg4yvt z6U_dtKgY`T{uAl^@m>_nPwz{?{P!LetX|%)g4MTlaVWp|WJlbxFP@bv&iNz$`AL`j z|Lng$_|v?@&*mfkH&3Zo^OyRT zE)L}vpX`WR_7~4rt~lq9_~$2G@?ZbDb?@2+9dF$@rthsM$8^7S=2&~U_2*bSxpnDS z`?>Y%Si8D)>{xrd_3ctDAY8LOA~$JW0}7l-nTPjPPwi)*CBJy7$Q_SAOrA!R&bd3})YZ zX|Qs=uLkqSdu%X2z264&-+OPcdU+oXR^QUaq5R^L9dXP4_Fu1Dan2v{&riDK{~Hf~ zP+70vjbDEpzkd43V?2EKMPI*O`s?rGHx7*7_%MFs#`ujV<2TNX-}p0r-Z=C#+|HjWTJ2$S5XaC*XRPK$#OXtsx&trbxxIO0ojpt+a@;!+3 zDqS4PFFx53x9q?9Wq&Kq`6K@MNtgV$KD=|H^=0djJ7*bNpWOM&*t+G;WyaPscV08L z&bf1(vGvcL?~JXB?%Zd*_0oO!L0#_Oz6XJ~zIy4_UFEkP%Z_zg_O0J4*Sao$toQQM zIxzpO5385-I~SV|^51#cn4LRE8?%4sYh&f!x!agOcOEz9=bh7y`G4nkWA*Yq2=!9m z(#4_t;*%Y5%f5J4t~lq9_~$2G@?ZbD_VI0H(b4;4Fnzse2Gia9XO`#sm-o_O?c}fC z_aLzL<2^Q5yZWK~9t76Ey!Qrchu(*Swa?PE+wyDA+0o9kul-l9evv==SAObW`LBOf zFX`SVqg?sDX9lz5{WF;Td!AyfT<@!q&L8iw!Tj`o8_a+2y}|0`eK=TsOBaXoi%)jM zE&KXc<%)Cuh<|?4CI3I?l^)r#Nd@#b0|%m#fbgy|mBL zwcGM*&)Lz=v#|6l+5rnd2P96x=>PxnurPkR`@b~1kLXZ+gL z__eq3Ylq|4KF6=!j$eBozji);?SK6G#rXA?@#{z9*T24`pN?PhpT6VQPsgwSj$gkX zzy3acs~sx9;R>W zWV*M0)*f0{YbUL@wV&4E+Ewdw?X7jYcG!Ae`z&3%Ex-1h9ql~(+JEKh7x|;Vs4b+vL^Z}X>hI6qsT^S^bwdbOTc-_pgQ{Nj@xam&7VR<1bb zkND>&UGiW5^4)~`m+vWH`uffSrn~PiEYG!vUwPkyz}kuLHDK+>cO0;G<@*j;d-L4~ ztR4Cu1lB%F*KW(NJ!eNd&%X9wx%x%^=wJD%f91daRlTJ9o`Q1a_nigIj_)sE_I;ND zEBD^3Gv<%)I7sKG?>k`r`|bl)FW-Z}>RY-vlwW+ZBW~H(zbaRp^GE#i)3}%a_RIHN zz{;{OyL0<$h%r0&+{AeM<@+uJ z-;{gLS&aE}&tHuBdCz5x`G3!AjMdBcApEWRmM#wE7oY5iTlTkKe&vdD{)m5m(k1`( zukJ0=vHQ&Q?VdB;yZ@{`bT3*v>Atk~(>-eKs{7TOzutXp?a=oi)NAwCOV@78uRUi+ zJI}uMU%C24{^&3HsUPLP{#CuCcb{4Q?m4s5{b%;O7p>gxOY^6D)covzHUGPJtzNzd zp z{)m5m(kuVzb@#qjmh`(fHJ1NR-}fN+z|P&X`s6wLcmHav+`E@G=Fi>N8uRn+agF)! zyARdN_aLzPmM#wE7oY5iTlU4Xa>Y4+#6LgjlK=FoUefQL+sc*y?!S%MxqESA_V2#j zSh;tPZp@#%UpMCG-Mbs}|L)_B>E(M6=~cQolwW+ZBW~HJSLKRx{)m5m(k1_`4?EYh z4(Ytl`lNF}>z2+3t!Fwnw9e@~(fa2n-g%{UQRk1=OPxzzeZHJmT3?lJ-Bo_;vFuo< zW#9U(a;@v~$9gY6tpoGl`mlOQ@4Qd`&H>r!e31Rl4VBw@B7Zt(+y*jT{ z-_pgQ{Nj@xam&7VR<1bbkND>&UGkq^_ukHLYa7zRY-v zlwW+ZBW~Fj&&n0&{1N~Bq)YxA4?EY>?>g_(A3F!sPdgvfe>*qSuRBlF-#ceC4s`x# zJoMcMbun&qUTHij-8fTz<4<;sOW8MGRjzR?e~fSWY23?y<6-rZ-g%$=oddGd`5^n9 z8!ET+ME-Qn$j{Cn`QN#udUal@zNL#p`NbzY;+B2!tXy%%WwUh z9qa1sTW?pcb$I?*pXaA_d;VL`S1;+kFIWESkMn^Y@7LuI``){YmFs=Hm_Odri}~sO zy_o+uK8)4N`+lXXZ|UMte(}kUxMg2FD_5NJNBr}XF8Tl2e|^vP4$?b6lD~5$b~_c^3aW=TfiEztp#MaVWp|WJlbxFP@bv&iNz$`AL`j|Lng$^^)HC zk^G%2vD0}I`<;I&xAQ6fbZ*7Z&a?R6IhT5M{-wU9i$nRvCp+SneetYZan2v{&riDK z|I=%2LwfVI{LSO+G{3XoyszBW1N>>7z|YnX{BK>MUfqvU-_pgQ{Nj@xam&7VR<1bb zkND>&UGo3wwR%Z!zLvjvoSo)(_M7*W+j@XMtrPg!`howgE7Ys?hWeH+4&@i0?1)?T z#j|q7Ie)}IKk1VH^tye@m;U8@3i`GDzO#VY@%;tNzV9+%<@#O&=8x|&z4D)4H(!2R zS<*X?kiT;Zb~?XczjF=ccHY6C&O!Lu`3V0zH&L(7ztp#MaVWp|WJlbxFP@bv&iNz$ z`AL`jr&slo-g$)lol~&W`33u(Ybdw#4*qlw!q3h}_}{sSdUc+nzNL#p`NbzY;+B2! ztXy%J7T;f3o?FlOE(5mC@x2CY{o^|h*t*E~ z9kBJ1?>=DbDBpv?)>oxlca`6IEIZa|*|&bHT%jcCKJ+~ZWxe!&2*3P4 zfS;Z5vp;_2j-NljR{rPb`1wD6^%}qWj$a(cFFxZJx7oKoyn2maoX0QzpFAI3=0Ck! zN71YGmHe%{*l9h+e(N;lwtnMJ>pFh6-s6AkK=o>UsJ^9(L;1xgJK~mo@vK~N&L8p5 zPrBqky{eb=)>rbk?qa9)82hc$l-v4^KdtNd*?N!vtpnAo^`ZKfE)L}vpX`WR_QkVu z#W{b(KR@Y`|8Kv%dHL2Du8 ze*4q$+qaJ2es=u!x#PG09lw3?`0ba!q*vd!zh3&=caPtGeEjz5Hgz@{GVf=o77{A{o#_#uv@%tTPZ2r1-_-*~&IC=FN8$VCqv2pcu z9~*D4J&cXR*G|U9=W9P>DTY(gZ$SY$Lw4`9kYM^cdXp&*JJ)%e;@Pn#(^>aZ+sZ5SHEwlZ|UMt ze(}kUxMhFqjaRNX=a2a3CtdRYjfX4u^}F%wkK@-*KY2d=cl`SG`1SYk8wbX3d>FrR zWBkUG@f&BxZ~Pg*acTUH&YHx7^A_&k2& z_V|tG<2TNa-}pa%^TPPe7vndNjNkk+e)G=w%}1X+pLuGme|1ho$Ig%F+qn|mJ8#k+ zI)~CuI-k;hI=9lUI?vjA>78?Fhn;_Ief83{+wyDA+0o9kul-l9evv==OMdD{`LBOf zFX^2h$=|sWJDoSN-#L_WJD=iD=T`jeJd6LGbE#M7U+P=BIFw&}vLkNU7thKS=ll`> z{G?0%o4-1THBNRuYy9lo*0|bvuJN{WUgL1*zsBdzg^k;t7aPwzM>fuPzHIz2-MmnK z^F?;dBiT2D4)r^v;ju?_7zU&YRfp97?&J zPw}U7D}HvK#sAK^)T{F^^(|c-$}c|I5x4A%XXT1>{)m5m(k1`tRlTHlek6bAO6+vr z#D3>c%I$oLKb>3gv-2$ech03=oqwrs>Ecj+@yU+3WnVliSDf=l{PUA8`EUN}9<2GR z`?1E)?#&ukyH9Jp?Vhc1xcj%p=imD7_ZqjmuWLNN_q}}c>a_jWy$5D&{4d?SP=518 zcFZH$H@{S_c_)9&NBL>~%761$^^)HGSoym*%TD)c+3%jMa=U-apYG-Iv-`UI?;fxD ztNXp`Te>)uUwpD7ZrK;l$`$AQ5&!(8Oa7a`YKO+j+Nbfec57U%JsWRp=f>gMzwx<# zVcf327|-iR#`*e}@xOHQLix=X*)fk~-~3X!=AHa8ALXZcD*w%2)k}KqQ~ug5JGE!_ zYv;rS-IiZ_&W?7TeeJ(; z^^5$`U-DBw%76Ww-@XXhjQ@7zSaI!{sG(#4_t;*%Y5%f5J4t~lq9_~$2G@}FMaBa+_z zBKf;_#7_5-*zcZ_a=X98pYApBv-?i`?;ezTbw5gdOBaXoi%)jME&JkGx#FBZ;-8;% z$$xrPFX`PclD~UL>~tTA{q89#xBE-{>0T2*yYIyR?m?+n_oLLeba5!Z_+&@ivM-*M zE6({N{`pCl{HNFLQ?>?>e(U_P{I~uevvd1`G5fb)7%TVo5o7+`{$k9}+jorlfBTWK zdfh%{tiGj-L;1xgJK~mo@vK~N&L8p5PrBqky{eb=+n23e`ES2AX6N>CWA<-cS-IkzKjNRC zbjg3~joP7kt@dfYtKFIhYtQD#+PQhN_HRC|Uzlg>FXrF+k$JiPWxg)mJYIhDdv?tG z*|#33Tx%rh-l$&EtFQdUft}*ResNQ7@#If&=4bKef4ZnwdZ};e;!u9^ z$&R>XUpy;UobyNg^OG+5|K_jl>-D?NXZ6RcMBzHB@x-8fTz<4<;sOW8MGRjzR?e~fSWY23^IH-D{O(tq@wFU#M#Ejyj(vfnwc zay$R!Pv^q??7W!&og=GP=gaC_x;T_ye6k~M*%!~s73cgB|NNv&{u>WFuhj24@6#VU z2h>kHAJl(4H`K2?Pt@N#XEY9U{%CyYT++DFd8P5BbmL6%P-5rtf{fV@&t^uE$t=xbJ<8wUhe}$XNTi?}LoBtNU)q zSbMwgiHx>UTW|bNe{`(e`)D>y1~g zIOmV}=coRa|MaSVNw0m%U%O?e_RN0mT)DM>{?sq{S%2Yw{Ybs)U+P=BIFw&}vLkNU z7thKS=ll`>{G?0%)2sgV($_v;{dea9~j;}@Ut zi`(qKc#dD3$1nclr_1~|9`;8Cv(r~mfcoPOQ&bozVG*%=3V{?7Q& zb9u&%p4T&;ly00UzwswK#-;2VuPWC#mOsX~{50<6zwxkoN$+_#`FjqIot}?lzvt$Z z+w*k%={Y-o_WT|HdoEACdR|X`OBaXoi%)jME&JkGx#FBZ;-8;%$$xs?zH;w>kbdvI z8Owj~!x^)4@5vdn-}^U|d+*g*I)CncJ7a#{dw9nDzxVTu)$88dGgjZy#i9J-lO1u( zzIaxyIOmV}=OG0+&!x?`+w+tzf!q( zFKg-ix%*mUe%?K@BE)L}vpX`WR_QkVu#W{b(KR@Y`|MaR}(tF-q z{+>5y=kCSLH}-q(Te)|SZt48F`*mY}-o3jq|L;EDSiSmwrTUgG4&@i0?1)?T#j|q7 zIe)}IKk1VHuYY~}#^BxGxZgd-^55?vV|MO$k}>=D`^i|j_q)oNKlgjfc>U{lewhFF z`^?hStM9|AZ|Un_FTeO?N8GY6o|P-k`6K@MNtgV8{cGh)zu&3G^55@QV|MO$tug!e zd)HXG_dD2_Kll6Cc>U{rAC~|3d)m^~tM9|AZ|Un_FTeO?N8GY6o|P-k`6K@MNw563 z-nen&C+THgyM8w|-(7zkn+LC-j?Is~C(XQh{d(!<)9deJ^X!cSWApEg4`cIk?`Jb# zmu?;}zxh2o=Kbtj4^*yoLjG7kG>?}r{}h`tDfi5-g?eU zJM8%{?Xz_4w*1<2cC_>CYyXw2U*wPelArof{(tsg-~UbHhV-7FlE3Gw*y(vI_J88N zuTr@^pT(b^+u~=>bMe3Dywt1bztp#MaVWp|WJlbxFP@bv&iNz$`AL`j*S~tN2pxOh z2z`4G3Eg`?iT2QYOSF^TXQKV|o)hh=_n&BQy%$A0?0qTPXX)B)`L*ZlXy@72{wr6% z$RGVBKlP*h*T1Tl^xiijfA1k-r}vYv-+N1x+xtxT(|b<%+51oU|MTDb57n#prKoS| z;!u9^$&R>XUpy;UobyNg^OG+5Pp|GrN$-A<{M|cZr~63kcTY*V-CyEQ_nP?GeJB2R z4@$kdAEmyfi$nRvCp+SneetYZan2v{&riDKKfS7#^zIkQ-@PMtx{oxy-u)=$c7KUK z-D~1!_nr9PJt+0+ew6x_E)L}vpX`WR_NUh?SDf=l{PUA8`Ty338#mrMWc=1A5Y$8TLae(TloTgQ&y`gZ)*z2mnY9=~<+_^qGEZ(Tip>+SJdhmYU- zd`y@8|Ev!`_cx4_-G4BCb}z!X+IvvS2bf5bmO z>5~8Sx^ey+SLXI#H%^Y_zwvX-&W)>M_WN$Na&H`7I)83_9`p0Y?J@svJRhr9-^*6t z(#4_t;*%Y5%f5J4t~lq9_~$2G@}FMSOZv@g^FjWb@5b!hJUC|m=Et#eZ{8g9=jPKf zKX0BL^Z(}Gv3m8rZ1pW&9Lg^~*%7zwi)ZDEbN+~be$p%dKl`uGw;j!EegDyX*LNY! zgMBa3{MdIS&6|B+(tO%?C(W~ckJ9|xcPh=xeZSItUAlR^{O0%UnD?`9Jy5yU3Hf9F zke}8S`TyB}ed;B>??1}lcOlv7dy(w-9ZBW(eM$cG-AR7-Jxc!fol5oU`<3cjx;T_y ze6k~M*%!~s73cgB|NNv&{(pWy{CrE=yw>-o&3Ao=+C13zsm+glx7xhf_pHsQedpRd z+xM@{zkL_mynNpcT$?msmu?;}zxh2o=Kbtj4^*yoLjG7k;x?=8+Z<@P;m{`8$|e)j!q{`XyM_3C@s>RY-vlwW+ZBW~Fj&&n0&{1N~B zq)YzOt8+c+o%hM#IUqZo53=96p>jJ<)uUwpD7ZrK;l z$`$AQ5&!(8Oa9ZVdP(oRPyWsU+39?c{eSA68!ET+ME-Qn$j{Cn`QN#udUal@zNL#p z`NbzY;+B2!tXy%($Hv>c-#9i7-@V7N z@%ipUj*Z)QPjYNLzx$J8<9y#kH2#-vUMRo$B0J`h?3-UI*SwQI=A-;HPv!q-{`%BQ z`rRX)5Axsr(lI-C?{v)m-A5fO_wK2V`E&PI$Nao|tz-V*eb=#i^*u!OEnOVSFFx53 zx9p2&<%)Cuh<|?4CI8=g{s*tjtv7DnIF|p`lVf&nojGRz`~J$G8Y}nKrDOiwdUedt zTgQ(1f9u<^dfmErtiGj-L;1xgJK~mo@vK~N&L8p5PrBs)ThFg7>9@`w%YWlQ^7maxcKTi<`+Y}JxqV-fKYe$SpM8&#|9z)Yz50Ho z`j##ZvvS2bf5bmO>6QO)eYmz^9a8(WKB?VWx741kXKLrxIkkW5pZbM$ zQT@ewseWV~RsXWSD&4xP{MKXHu};gr^;_jy*X57(UVd5!=KotCu3pk>pYqpk*{MCx z{%hyTt^M<-e!Q(=4<*kkJG*RU3+NW*G^gwXg{qJw5!$+ z+FR=i?XdNR_F1}iTYl|1JKA~nwg1Z1FY-r!$xr<#|3AO?e(EK?`C9(wadw*D*>B!g zZtDU5v`*k>>j(a~u28Sm8|quSIFw&}vLkNU7thKS=ll`>{G?0%>tFXC&TpH)=y>my z8q@dQH#MgFy@zV7J>2`L#@fjr_<7$u)_(4NR%7kz-g7n9-tPTZW9{(Xi#66hOV@78 zuRUi+JI}uMU%C24{^&3HsUPLP{#CuC-+RDTuKf3YurWLL-mo$I_dc<)a_>E3WB%Ox z$Hx4;_mYkIfA1?BtJl59Y^=Vei$nRvCp+SneetYZan2v{&riDKzy8%eg^ulC=-a-A z?(KK9hxS3*N&6%1r+t%l)qYBQYoDbZw*S&TOV@78uRUi+JI}uMU%C24{^&3HsUPLP z{#CuCw||kpeGNP9ci3+qq}=vL{Au6B&-PRNZ=a=J?Z4Ewba5!Z_+&@ivM-*ME6({N z{`pCl{MWzkImFG&bZow+Z}T|ao8PsE=6&s?^?>%%IzhW?{h+T<{^q2h9kMdvts$SBYujOwZXQ%mn_TRj(+|~p9X`R5&)(`w|U7=pB zH`KRuaVWp|WJlbxzj(fK#W{b(KR@Y`|JL(&A7Fjiy7A7P$JUc~9zC|symRWY_2->m zkF87ZTzhQ2dgt9^>)1O7A6wtv`S{qnx9^)<50`G8Tz>24>{wT4-+H@pt;6%j`aD0a z+w#rG1vJ-IiZ_&W?7TeeJ(;^^5$`U-DBw%Ky*rQJ;EAufFmZ2X=}N`^8PU#gjk9 znV-df{p;zXUg@>|_0q+m{Nj@xam&7VR<1bbkND>&UGkq^SKc>UZ}dG}`TI^TJAFTw z{l2TK+`hNVpT5J(&%V#g|GwL+UccwBeP_SnsBh`wP=4{rj<{uCJS$h6^GE#ilP>vB zuj(be@8QbdcXHY3`?>7*U0vn&yYPTyHVd@9tb|tUum)*;qflbF{Jkd*^Fo{rb+`#`^o6$Bm5xcTP7p zKHT};*tl`$dSl~B>BgDz8-KE6T*|)js&b8E`D1*`Pvc(x8xO0O^gG8~x$@un=9ry3 z_Z+i-=b>Ze-Z|-*KX-mQ=I5QOj`@G*tz-4NbJ(%^mM#wE7oY5iTlU4Xa>Y4+#6Lgj zlK-!NZA^YTj-S5cr~CM|hw*DCr49eyD#~#KaO8N9l!oNe*Jp<`un$xKW`iuzwu%G#*OhCPsVSY8Ncyo z{Klo(f8*8ojbr0CzK!XU|8ITxjmE>y`{eH&ke$v4+3(y?xt%BSr*lSrcK*o!&L!2W z^GfwCT^!0UKG_ks?2BjRigW(ZD?jO#|8IS`dP(oRPyWsU+39?c{mu=Q+j$~?I%ni( z=a2mFTvEL{uT&UGkq^ z)k}KgiTsU+?A*F#{;+@RnXz(joipaot$)7gb?c%pdfj^Ii(a>m`l46q;!u9^$&R>X zpI((K&iNz$`AL`j|D31%=5H7e&1*mUn|{;Se0TS^$L7Ji*F82r-hJ<}dGqdpkIkod zKYVPSy?f(h^Y7g!ADfr&p842(UAlR^{O0%UnD?`9Jy5yU3Hf9Fke}8S`Tsdj`P57L z-K$@@^51>?F*|n;f6V^f&mSxI?(L8HbNBhj{JeYqWB%X$|FL@Aa{*)ZEnOVSFFx53 zx9p2&<%)Cuh<|?4CI8>=Q7em%_q)fKzV~~`nC|yG$tTaXhx`3xtexENDr4>Ees39T zSNA*2`29XJe!ts{-|so&_dCy6d(Mt_o_+1Va`lV+(O>dYKg$32d(>=7zu&3G^55@Q zV|MO$tug!ed)HXG_dD2_Kll6Cn4kB%*_i+Ld)ipN?svAa`j##ZFFBUQc~X7l-nTPj-eRA-Fp$o^56Rs$L!pD6hC>+{=HvutlWF=;+Q}8KE^RW?>&uU{@?o> z$Le+ObsVd2>Ecj+@yU+3WnVliSDf=l{PUA8`A@IvCH>xGxpL*d_gjwHx%Xa<*}wN; zj+J}w$sF_N-k&+<=e<{R%>R4e=2*S%J)C3pEnOVSFFx53x9roaa>Y4+#6LgjmH+hW zcN^*bo+E$1^RUzJKkWCrkaGLIh(G;~#Ls?T;(xz8saL;8sc-4xP=4{rj<{uCJS$h6 z^GE#ilP>vBuj(be-*e>ecOG{7{fGU27gBD&7xAaxk@(r~OZ@M5C-v(0DD^E}9Lg^~ z*%7zwi)ZDEbN+~be$plX|HhrCeAZ6ZjjgY&CtG(}XSN=*{%oCQUE2E1dbM?(b!_WH z>)SiO+jwi;d*^y%>*3O^lgn@YoE_`x>|1YFu620+SfA&ob$kAQ&Qm`1lHU4C{?=XW zv>s!>^`UZGzwxJa9Y0&|@xOJTdbK`O-_pgQ{Nj@xam&7VR<1bbkND>&UHE_Juiva* zxccJafQt_D+TparX@}DeryWi^oOU?vaN6OtE1h=b*M@Q0;k3hPhtm$H9Zox(b~x>D+Tpar zX@}DeryWi^oOU?v=xF?RUj-Zg-DAPVfA?Fk@!!1{Z2Wg01{?p~lflM+_h+#2-@O{V z`TFkRVB^1gIC%5*OE>0H^!R)yA zg4uT;1}oP+8O$H|XD~nAtHJzt-v+CfdpKBqOBaXoi%)jME&JkGx#FBZ;-8;%$^Z1C zD+TparX@}DeryWi^oOU?vaN6OtTb`#KPP@|8z5HT=({6d5 zb~x>D+TparX@}DeryWi^oOU?vaN6Ot!)b@p4yTuPf~~u-Jl12_-&&_(Hm%>VvaIVc zAFTH<->d^MpREtEx>z@2b+n$u>R!5-lwYi}BZk?hUFC{-{?INzTMx6}IvKYf!}43F zVRo$FmgnqS*J0&a?_vH}2V#C&A7cJnH)8d&p2X@~x;T_ye6k~M*%!~s73cgB|NNwj z^(6c0m5#JaU)tfc!)b@p4yPSXJDhen?Qq)Rw8LqK(+;N{PCJ}-IPI3_`d$8~UFqsx zelfvmw>(cfoOU?vaN6Ot!)b@p4yPSXJDhen?Qq)Rw8LqK(~gdx^W2Z7&Ijvv&IfDH z&IfDf&IfD%&Ijuk&Iju+&Ijv9&IjvX&Ijvv&Ie0(K3IO|gV}LDn0@DimFs*kf1D5I zr}M%5|D3;n>LtB)D}U{oo!UA3wSVQ-FZfe`;b;Ab|Mf5Rs^6(^>Ecj+@yU+3WnVli zSDf=l{PUA8`JY~N{F>8FdfMT%!)b@p4yPSXJDhen?Qq)Rw8LqK(+;N{PCJ}-IPGxS zm0rI~JLzeM(+;N{PCJ}-IPGxS;k3hPhtm$H9Zox(b~x>D+TrwS{PepJ);IlLg!Ng! zBVm2n?@L%8_q!9;_x&D)jR}6I!o~`}Utwd2-?gx@#qV9%m{Yp3sQkvL>=?VUZ_KP* zV_p6jGxO8DmjA}g>LuOpMaq@m??{*(zb|3-{qBU7>-Q+kAHP#!e)|0i^WX1USiSt- zh1IuoaVWp|WJlbxFP@bv&iNz$`AL`jH)g6A9lz$Zlb&`s?Qq)Rw8LqK(+;N{PCJ}- zIPGxS;k3hPhtm$H-SRx`aN3ow?&TK~oOa9ew8LqK(+;N{PCJ}-IPGxS;k3hPhtm$H z9Zox(b~wGX6MMb(LH2;{kL(TGH`z0`pR$*1pJk8P{>$F8eVILJ`!#!2&r>MN9=83R zy>03CyydqS&W=5D_U)Z3*Pc3m?9KDj-aP;9&8wI6_DAx!Z(^tY6#MP7l-vG`Kkdu- z*?x`x?c>y|{hj)jE)L}vpX`WR_QkVu#W{b(KR@Y`|LH}?uQ~0cryWi^oOU?vaN6Ot z!)b@p4yPSXJDhen?Qq)Rw8LqK(+;Oy>Fw{*PI}tmw8LqK(+;N{PCJ}-IPGxS;k3hP zhtm$H9Zox(b~wHC1%1%D71lSMXJLKTITzNKoqu6{+_@Om_nntvV}f%uY^-p;hK(W4 z-LSF6c^o$8lx{34zcDI1#;)ueGb`6vmp{hL{4}rSzcI6VNq3&5T=|`IVRoEvvS2bf5bmO>5~8HMaQo> z?WCt2PCJ}-IPGxS;k3hPhtm$H9Zox(b~x>D+TparX}3I2JDhfD+TparX@}DeryWi&?ZleXeGF_Z`lEM`3tOYQzk#h?-Rr>C zwC;OgYhCw1ur;vzA=uj3y%B89>^=#$mUhnsTVt1Q?OlFr^6XfvXWtsWa;@$2$C^Js z?Gf_-b6@vUFX`@SC|7>>H!wTybzt`0_rS_^4+Qha{SeGg_eL=P-6z57<(>&v-_pgQ z{Nj@xam&7VR<1bbkND>&UGhJ@==e3Ko%FQBX@}DeryWi^oOU?vaN6Ot!)b@p4yPSX zJDhen?Qq)Rv@2cR%P%H4?Qq)Rw8LqK(+;N{PCJ}-IPGxS;k3hPhtm$H9Zox(UfPL1 zc>QkcKz-AF8|nJ2dpKBMc0UK}QXecyc^Y)o*^2OBHg|G~x(_kyso#eE@c%qiVi zRDNSrc8p!wH)d9@u`Yj%nfYm6%YS2L^^)$sjdJC84+pd3ehy~ey&bGv_jxdX-1EWw zbpHqQ-@PELUhWHF^(|c-$}c|I5x4A%XXT1>{)m5m(k1`Xi;iD&+DT74oOU?vaN6Ot z!)b@p4yPSXJDhen?Qq)Rw8LqK({6d5b~x=ySNHOZ2~NA^dD`K$!)b@p4yPSXJDhen z?Qq)Rw8LqK(+;N{PCJ}l+KDx1zdu-u_Pc~NYQI-lyY@SVHEq9dSnKw?hc$4&hgci; zJBc-Ozn@r3_q&QUcInpM<+mo!jG)z+CG1*`Sa5rA^+_Ws+aVBmyo~TE7<9G z4EFndL%IF#!JmE);b*^-Y>)GPS5dEiSJ|HErHe!P#V0%BmVNQ8Tyf4H@y}1Xy>1l`44yPSXJDhen?Qq)Rw8LqK(+;N{PCJ}-IPGxS;k3hPS9-szq@DD%!)b@p z4yPSXJDhen?Qq)Rw8LqK(+;N{PCJ}-IPGwH>36RWZjGdGwocP$Tfgbct?Tsh)_eMX z>p){d>qBEj>qcWp>q%ov>r7)#>Bge+8>6yg?8?3|vvQ4f`D4t?PxD&-zcF+5lHNK^ z{?>2ow60^n^`3HD2lA)&AwOF;^1t<@dbQ3}-_pgQ{Nj@xam&7VR<1bbkND>&UGhJ@ z==e3Ko%FQBX@}DeryWi^oOU?vaN6Ot!)b@p4yPSXJDhen?Uv_hhtsa~)|qK1J?)m~ zX@}DeryWi^oOU?vaN6Ot!)b@p4yPSXJDhen?QnWE-`)F*wnox7@BKexefHi9G}f2z zeL-V={N5up*7xuILStjXy?1DAtho0Pjg2Aqo}#g_<=$U3Hs+LWEGoY-Dm%um>>JZ6 z*I1W7#=!hEX6C;!vwBIt_cg6t`R_eWV|MQSPGk0e(T{vsx%WP(rSs?B6E)`Ny+3Nq z|9h|0SiSCjQ)BflT^!0UKG_ks?2BjRigW&me}2*>|BadIMaQo>?WCt2PCJ}-IPGxS z;k3hPhtm$H9Zox(b~x>D+TparX@}Der(NmlUVbsbX@}DeryWi^oOU?vaN6Ot!)b@p z4yPSXJDhen?Qq)R^lHAl|9+Y8+((tJ&$_3I^=0>0u|DozE7tejcg4m8_h7NH!u?om z3~_H38(Z9`#m1b{jYZ`*MrFs?m3?DoD+TparX@}Der`_^A?Qq(a-u=w9 zlb&|V^R&Zhhtm$H9Zox(b~x>D+TparX@}DeryWi^oOU?9v=e>szR$9;THn0yn~e3@ z`|inDU%v05jP>#RPRdx{zwf7vjS2T%m9eqnzPBiF*84nnfY(btX|UZdo(Lo{`*eNn4SB6&6xfBuFY7v_r04jf9^Xt zV}9QEamM_=@8*ov>%ONmR^QUaq5R^L9dXOPcvh}B=a2a3CtdPCz3BKgr=9e)!)b@p z4yPSXJDhen?Qq)Rw8LqK(+;N{PCJ}-IPGxS;j}AV-ODc~IPGxS;k3hPhtm$H9Zox( zb~x>D+TparX@}DeryWi^oL=?2&JpDK(RYsEZ`(Jq*?vk{?X&pM{)=zz%lO=WO9(v@hdl z`!)Wzk5jMqcj{ZZIFw&}vLkNU7thKS=ll`>{G?0%(@wq8F;2U57ZaRzIPGxS;k3hP zhtm$H9Zox(b~x>D+TparX@}DeryWka(%avqo%FQBX@}DeryWi^oOU?vaN6Ot!)b@p z4yPSXJDhen?Qq)ZcjmtT?r;9_t&z-$z8fOlT$@b_T4i=vSZDVeQTADSg8AcnC77SSV}kkb`zBbueD?&aZ|UMte(}kUxMg2FD_5NJ zNBr}XF8QBcbo`prPI}tmw8LqK(+;N{PCJ}-IPGxS;k3hPhtm$H9Zox(cFXg$!)aH# zx|d%}aM~@;(+;N{PCJ}-IPGxS;k3hPhtm$H9Zox(b~x>D+TrxlPVk)_ZjB_5_q|B> zx84JT+4O!GtSs-1!F=#O8O%5DnZbPa{u!(;-b;hk(few!x|c2{?)g7lDPCJ}-IPGxS;k3hPhtm$H9Zox( zb~x>D+TparX}3I2JDhfD+TparX@}De zryWi^?Zg>+`yglQ?T?(fw{LP5-+sy&efunD_wB!&>9;R)*57{39f0<6?gq5Kb7!D* zcL~bxjzMD+Tpar zX@}DeryWi^oL>5!K6v*SH&*MLcNcD~&)!|QvA%rw2FLpNcYgRUjrIMzXE-({-2KC` zvEuF}j*TIAUvX?~@jgA}8goiF7M0%^l^tVO_Klg9Yply3V`hGu*Ye+(S-qs+z0H*? z|J~;tvvc=6$L!zz&#`jvUg(%VcVBeO&$~xD=KtL<9jll3={4V#E)L}vpX`WR_QkVu z#W{b(KR@Y`|LH}?uQ~0cryWi^oOU?vaN6Ot!)b@p4yPSXJDhen?Qq)Rw8Lq)JWo5E zcBQL(`NagM-SRx`aN6Ot!)b@p4yPSfU)tfc!)b@p4yPSXJDhen?QnW&CvUH}HI+SJ z_pIyNEyk+W~_ zT)Fnt`D3r0pZ4bY|Mupqm-Oyg$>04ecDk3ve)qMM+dVG+bia$A-TUHy_rcVwdt&Na zx;T_ye6k~M*%!~s73cgB|NNv&{-+lmzvi@)o_09xaN6Ot!)b@p4yPSXJDhen?Qq)R zw8LqK(+;N{PCJ}-rFTy(?WCt2PCJ}-IPGxS;k3hPhtm$H9Zox(b~x>D+TparX@}EG zzccsUcN4yW&57QZi_MkZql?X<-miD+TparX@}DeryWi^oOU?vaN6OtD_z~oFD5wcaN6Ot!)b@p z4yPSXJDhen?Qq)Rw8LqK(+;N{PCJ}l+KE1RbL}^=zWGx>@mt6G>|g%=59`bS`%nE# zOV`K$(7*a&eg7Z%r5`pX{B?ifUtAtz#b5p-A2x>kuK)DI#+Kjzdp~TD+TparX@}DeryWi^oOU?vN>}&tiwRCUoOU?v zaN6Ot!)b@p4yPSXJDhen?Qq)Rw8LqK(+;PXzNQaepZ_-2H~T$MpY3--eYxKc_3?gJ z)c5D+TparX@}DeryWi^oOU?vaN6OtE4|+{ z(@uKY;k3hPhtm$H9Zox(b~x>D+TparX@}DeryWi^oOU?9^fi0ED|=(RJ>b=GY;SnF zkL?++J&f%oubqtTF|YlM?LDtuZLMWbdhKoeew!WJ!}`vSa_w!eeU9yU%Wp579ed>L z+nZOeJ$3%ro9E{{FPJ~?x9G9->yKmkub+D z+TparX@}DeryWi^oOU?vaM~@;X{7Dpv@2cR%P%H4?Uv_hhtm$H9Zox(b~x>D+Tpar zX@}DeryWi^oOU?vaC&Jc=Dyx1W=`zAK<3Kc7i13YJwoQz-Y;a%?Y%?h;@(GOj_y50 z=I-8KWKQqBM&|m`tpUn!ZIB&nhU{BQRIW8f{#dKzr?pD{TdPzr>Ae?7{@xeFPVW(7 z|5v{Ei7B`D4)Le=5%IJ46!E|J7pYh8HB#Tw#i9J-lO1u(zIaxyIOmV}=OD+TpY-z4scWo%FQBX@}De zryWi^oOU?vaN6Ot!)b@p4yPSXJDhen?QnY4@9wVA4`O-#=y!ho*x&xyzv~|zv-x9x z_}7k=_22yTuNm{<&-~B-z?g48_a}eVn9u*qpZLD9y8PMy>z9w!@gMw+A6EC$#iaaV zl^rq6zSvf-nCA~I@{@M?PrK?R{SW?%e`Y?&|GWQ&-!f+BXMV>&H=g}}{71&h{XPH0 zzdYv8Z~5o{wJ|^c?SJ9l81w&kf8%$K)$5o1^oP~Aba5!Z_+&@ivcGt~a>Y4+#6Lgj zlK-?*uXK#lF5SfhryWi^oOU?vaN6Ot!)b@p4yPSXJDhen?Qq)Rw8LqK)2?)NFTa@J zw8LqK(+;N{PCJ}-IPGxS;k3hPhtm$H9Zox(b~x>D+UaX=&ABzwTZ@k08g=~EuH(0+ z9ly2i_^pArZhULw@mn*G-&%V7*4X2>_8z}A`S`8XXaB9?$8T*verx{m+sBRH9^p%R z>$JD0So+&*jNcw){Prf}w`Uo@z0COSamH`&Gk$xb@!Knn-yUlG_EzJ!=NiAg*!bD+TparX@}DeryWi^oOU?vaN6Ot!|7GO^F3cIkMG7}f9rd)m`&fA z#me&iSWNY%5pH^M@AsNxS@~ zUGD+TparX@}Der=524 z;m>nw^7Qu}tzgT5Q46`q` zl`H1?L%aN>UH*Tx`_xN%&#%efb8YPOyc_#H2dCVgkK<3z&GED6>G{G?0%r`P|d|4WEuC;ys*dyepJwpE5BUCTx%@^`FkFeAH!hZ9Pa+{C%(>%q`<}dy?uc=q_ zo%)t84&@i0?1)?T#j|q7Ie)}IKk1VH=|#t{IqjsU9Zox(b~x>D+TparX@}DeryWi^ zoOU?vaN6Ot!)b@p4yRq|&39=hJ?(JX;k3hPhtm$H9Zox(b~x>D+TparX@}DeryWi^ zoL%`SzI4zwT#$a;z@j`pzF8tK*OT;SZ~O>0(lTvC57ZW?yV8SIqN=7WqlL{HI;@ zlK#v7i$6CXIw9&%gJRe__neU-*r`IOhNF z`xQSkRD+TparY4=sX`xchx?!t}z?cIeNvw8Oh$I80LWTrtld+T|zh^8abKvZUX=&9VGGf%DsD`WB%NI(J?>o9_g6>cfWM3UU%D+TparX@}DeryWi^oOU?vaN6Ot!)b@p4yPSXyVBLY{9=OB z4yPSXJDhen?Qq)Rw8LqK(+;N{PCJ}-IPGxS;k3hPr>{9fzyGeyI9tCx?AV$6?d!+R z;%~n{c1C}{1B{*B-|qusXZrWM!Pr^<{hly(2jG5Z7`q#AzdwxK87SRdg7Uj#kR5jq zvhU7A<+`hoKkhu_r+X>+@6JQ@l77FptX%o;H-|Ah_xsG4{rlZ!tlaxOXUw1booCF? z`~7Fk|NC8NtX}tf(O7*;7l-nTPjD+TpZYo~Ip7yVBLY{9=OBZh4+|IPGxS;k3hPhtm$H z9Zox(b~x>D+TparX@}Der;e0}fW2Yg9k6HYdj$59eW$=4v+oz!d-h!e zd(yslV6WPD5bR<5K7ze%>Gr(kw-?TiJ#zN#oh#R#I)Ci7^V8lu|Lx7Im-N0bAb;N- zV5jd9u>YO+eFWw9{Q~~D+TparX@}EGzccss-5hgb-_tQy_MIJbXy4y4 zxAt8gb8g@3F&Fn8A9Hly_c3?(-5+y$-vct&mu?MEertp5STkhbTB35TG4jV+B|oiI z^50sedP(nlI`a3O9d`Qu4*PwVN4b5khd+JCho61lhyQ)|N4@$UkouM`4&@i0?1)?T z#j|q7Ie)}IKk1VH=|#t{IqjsU9Zox(b~x>D+TparX@}DeryWi^oOU?vaN6Ot!)b@p z4yRq|eGe$@q^BKDJDhen?Qq)Rw8LqK(+;N{PCJ}-IPGxS;k3hPhto^HGxuHl{025B z{;uEfi^t~5@A^;v_OUtikNn(skIk)r?ce>|#^&5#{}2D7vAOu4{DEIMHb?(W|K{I1 zHh2Gqzy8DK^gsC1f6LO%^`%<_l;7GQJJt-@w^pfKYmEG{R>@E6$^5rgsb13mpFj6^ zu3Y*5_5bjfjM@1!zx?kWv;Xh>_%9tR_xt~kzh}&!U-cLN-Z4La`+xPz#{B;^f5+c9 zRD z+TparX@}DeryWi^oOU?vmgi}Q)2?)NFTa@Jv|FC19Zox(b~x>D+TparX@}DeryWi^ zoOU?vaN6Ot!|ByJ^ZNYmT9^~>PR`g|+4D8#(4M<7xAr`aIk)F@%*8#wV~*~*9&>lk z`gSo?|C2f>Nz0wEnOVSFFx53x9p2&<%)Cuh<|?4CI78e)QgT^bJ|Hy zJDhen?Qq)Rw8LqK(+;N{PCJ}-IPGxS;k3hPhtm$H9ZtK_)xG>;g3}JC9Zox(b~x>D z+TparX@}DeryWi^oOU?vaN6Ot!|ByJ^WOXYO>9oQcVdstmG@5Uu{reKA3ip>-h0Kz z=G=SV_}E;0?;#(XqwoFXV{`Ytw|s0)zxSDs&Gn^Q1C-y|AUoC!*|(OcTx*Q{vG&MM zYnA-BR;gan@BQs7SN?mi`ugGy6+vByZa7;Ilb>A znCnZo1}ML^L3XSevTv(cfoOU?vaN6Ot z!)b@p4yPSXJDhen?Qq)Rw8LqK)2n{h`LaBnJNw(tquK17T3MZ6^PzKXzIEQs=gz^^ zrSoxh?A%=4OBa*!i&b{SF#EKtTrtld+U2MImH)J>UeY^vmcR38b~>k?{daz?+|IT6 z(|I>PI|t`~=i}s)llb&|VqitLaaoXXu!)b@p z4yPSXJDhen?Qq)Rw8LqK(+;N{PA~n=n)7tr?*rDNy%)$Dwf6;CyY?O-Yuer~WUbqK zhpd5nACa|j?D+TparX;-?s zmtRb9+TparX@}DeryWi^oOU?vaN6Ot!)b@p4yPSXJDheny}s&q-@-4?`2Fqp*&M&J z#?OcG^KJZm9>2PbUmeGj$a!dzqUPoZGQav!ua)(@#{O|*Qdr$yKjA^<2dcU z(tYV^Cq3*2%!|~fQj^AE#{PvjRxAz>s zJ?Z%ERmX1+JAQlH@!Ru`-(Gn9_Q>P6cOJhz_4xfxGJe0GjNjh;OM3gGx0he~+vAVl z-hcdl6BxhW3dZj@gz@`rVf=n`7{A{l#_u?>CU~`)y?Welr=T z7ahOmw3D88IPGxS;k3hPhtm$H9Zox(b~x>D+TparX@}DeryWi^oOY$Rze_vmX@}De zryWi^oOU?vaN6Ot!)b@p4yPSXJDhen?Qq)R^!jSP+x=dBv;C1i+rCL(Za<}ux6jh| z+kY7o+LswC+OHWy+Q%7N+TR&-N;ejj-x!r0V^{W#X_afN%O7K4ei}3L|Bacem-O~W z^0#kdr~TCIzkQZ++kf$=eHlO7ukpWqoO-ptQ{U3Xq5R^L9dXP4;`z!I=ll`>{G?0% zzcF)rnXftR=$m#p?Qq)Rw8LqK(+;N{PCJ}-IPGxS;k3hPhtm$H9Zox(cBQw!OFQXl zhtm$H9Zox(b~x>D+TparX@}DeryWi^oOU?vaN6PYs^4|KEKldo{n;zJCA0k zb87ZGzgBMN+WhIfo1dM7^S|?P_3GSQeM=XI@{3P)#4Y>cS-IkzKjNRCbjg3(saHD2 zX_xL|g3}JC9Zox(b~x>D+TparX@}DeryWi^oOU?vaN6Ot!)aG~=jLfAJ?(JX;k3hP zhyP!y?mhUw?XK&4gbbCIqGGi=rChXQjDTWOYDvyHEmj~v8bAvOhA>0Lf-q1)E*5A7 z3W!swP$lX_hg+@S6dY{vb~tKv+EOAU2v{lN4MniPSd|fqN#Bq6XFXTG{Bh>@JZskX zyitk#Yc3oqn$F)Z~U8|(uwMzX`?%VYGtNt6_`@!OT>$ksT%f(jsJ!TMXdJXBwPiX(5um(SXj=k&;b zI$f)z-?fT<@$o6EqwmV|4(A=tJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhx4v- zeXqWp;Jm|mhw~2S9nL$PcR25G-r>B%d57~3=N-;FoOd|yaDH{(&A3jnE53Zzt~{ql z{?o~q^z%-?@-fc4e3uiPcR25G-r>B%d57~3=N-;FoOd|yaNgm(!+D4E4(A=tyUKeX zA@7vu9nL$PcR25G-r>B%d57~3=N-;FoOd|yaNgm(!+D4EZaiD=dQ6?J)BJ7MZ(?>` zr>(B{Xy`hSwyqCp?z&N5x}Ma>t~2$$ayhBKTop$Si!ZmeE9dFqMLKzxe%{qDdQ}YwOt@dXL86_I{0+y?3Ln-p8S# z_jG9M{T-TnuSZ{c-$x&N4@loDmy_ztRdM97_;Opja-JSuq?32)=Ux3$-g`9a_kN8y zy>}!2o6mbd+U-3ZdU}6{&fe>xzxRFgtM`EPw{m%?zWfwN-ij}uwJXo*k^gk^CH=h9 zuY8R2F5l$@=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{MDXyu*2i^RDvV1Ijz)d57~3 z=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{MDXymQ{2XXtyK>DhYkYkTJIon>`Ai|_qz z&**#a+q3)L2lq_B_ryKx@BMLW0D7<7+JN3Sw`QPnYYD1vjX`m&Jt)3454CHpLVB!W zNT+ov=|5{8R=@I|->Khw+~V|pxA?vHt=--Sr>FPC>FoV+`g^Zjzk1(Xe=C=V>dQ}Y zB%d57~3=N-;FoOd|yaNgm(!+D4E4(A=t zyRCD)!+BSE&+qb1dERZE;~maBoOd|yaNgm(!+D4E4(A=tJDhho?{MDXyu zq|d8a(@aNgm(!+D4E4(A=tJDhho?{MDXyu*37 zb&hv9?<#M-O5Q2YyRCD)!+D4E4(A=tJDhho?{MDXyu*2i^A6`7&O4lUIKMjY+V4)C z_QCVF?T;sB`{rq@{q$&PpFP^ze~;$&<(j^f@zeLp<)r#@RUA1iKJRK*&eOw- zbeh-F&%64iynXQ0Z+|>-+BZ-9_S4gD`|Q!v{(E$`FCYEw*Qa0YB%d57~3=N-;FoOd|yaNgm(!+GbtdpuKk z{f?!cHM9?&XAtd==h;O2=6Pn(etMo|w9lSr9PPj7*+={Gc_z|+eV&!HkDq5Km3y{Q zea~Eq<5^7cJ)@~z&u-G=nNB)A14{qn8PKC&%G(D|{r1Nbr+xFpZ$CZlw$C0t?Y~E7 z`|{D>etr7YK7RUJxja-~eu^V+#h1_8mFM)xe>(Y+{`}(OQ_ef(d57~3=N-;FoOd|y zaNgm(!+D4E4(A=tJDhho?{MDXyu*1{dHeX~o$|cHd57~3=N-;FoOd|yaNgm(!+D4E z4(A=tJDhho?{I!K-+kIU{m1)!%DMT%7d_ZH`}%+KVCV9;{N~@Vb)4gW`+s?`bN^Lu z_x@XMO!&PY_+Vqj>p%O!#*laTgAX>g{Nx{dura4{V^Q^uQN=NK72lXyyT-co7z5L3 zUQ53*vwkV}ZF>Dx|NUO}U~%5#4ez(*;=konAFSQ4c$Wv$^PB$Gf3$Vze82zc!SuiB zzk9HL{qPq*Sbr;*hw95uapbM|@>#p`oF4g4CtuQU%+xPFKIObqo_9F!aNgm(!+D4E z4(A=tJDhho?{MDXyu*2i^A6|T);ZqcysKQ_t1l-w@3zkI4(A=tJDhho?{MDXyu*2i z^A6`7&O4lUIPY-Y;rwd8o9|V98+LBaH;W5s-bYS|bv-=$hMw#@gcmW?@;8;h!Mj4FB%d57~3=N-;FoOd|yaNgm(!+D4E z4(A=tJDhho?<&{#>dOhvJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2Smvha% z&3RwudF-C&tc6>4FLc%iF1trM>jszIJALV|`CH5Gsm?mXW%pWV{o%5Eu(K|4*}d6W zuej`31)>ekq@Io7=AXvz~KV zoLT3&yz&3V|GKQ*Sr@uY&#V_+rgPSjF4I5jOPBR))}1cvZ{_k(efcSlycK`*dD@ld z^vHiY`I7$p;^R}!JLP$Y^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%c~`l< zS6@zW-r>B%d57~3=N-;FoOd|yaNgm(!+D4E4(A=tJDhhoznbqlKAoE#x6av)XXkRq zxpTbZ-?`s;VNB?JF;;XQ8ACe1j4hpa#+=HHMb$S(701|Bd}CVe8tc+y%uJ^-GyTTQ z`lY<%R{f4=aXQX7{yF}&+j&7x=L?;kNA!1o=~w5S{#Gsz)t8^*$XoF@pQl}UPLKSj zlP~EvX6hFopK{(Q&pVuVIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d57~3=N-B%d57~3=N-;FoOd|yaNgm( zt6bl!FDE$faNgm(!+D4E4(A=tJDhho?{MDXyu*2i^A6`7&O4l6&NaXFX5G;qV}1k9 zUWLnk8_xcX%YHM?zK+X&OU{0e%YI|dK9I|Pd(Qrl%YKv2zLCp*tImFs%YMVoK9kFS z+g9#3Z}t5aE{@;G#rNC1cKxPKkKg9$bpIs%ew)`X<+HEmwyXZ^x4A6N?8CV%{_M}W ztldBQHt(`b&+O;9Oy}(LxlI4;|GBJRvoGkf{#Gsz)t8^*$XoH{vv%bB%d581st>@kA_nv?{bI*3!-_CvPWijXe z_OiC-zV|W>b3c5Uwz*HfO!M47U)GnoufD90bH9CA-z%4s>dRGet6e!y5AV|H z{7V1ByGLJ?&+~MGqcb;D?(=*RCmg$`59n193bC6~In&%_S z`dhg?R9}9IBX7l*&)Sve^vHiY`I7#Jcdy@j3r{)k@?B1F-r>B%d57~3=N-;FoOd|y zaNgm(!+D4E4(A=tyRCD)!+BS^zE@vPaNcd5;~maBoOd|yaNgm(!+D4E4(A=tJDhho z?{MDXyujw)pt!^9M|f_cMV^=uIBc%UvPwdez z<$Y&a{n>AGHH$O*a4w5K`*SX9clPaErf2r^T&8pO`CO)d_WxYguh|!LS$`{+hw95u zapbM|@>#p`oF4g4CtuQ^UwnMZd8a(@aNgm(!+D4E4(A=tJDhho?{MDXyu*2i^A6`7 z&O4lUIPWUg_v*_D&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d57~3=a+NDHRr5( z*ki`E=&TJ`c8xmgC6-;g&N_-^*R->~V%fFsth-ot4Ls{HmR%dqI*n!5%(H%D*|qen z>sWS;UAb%T>boW{j%)SeyN0h_*Y@f08zG&3Bc$JNg!-j?*0F56>d#t^WpQTR%d+^h z9%fm)vrcB2o>@P$Oy{htS*Cy1+brwXtixH>-^%5o`tnm8c`Lqr)~-CKNB+~vm-Ocs zAD?pGDbG8ccR25G-r>B%d57~3=N-;FoOd|yaNgm(!+D4E4(A=tyUO*w`f`Hv4(A=t zJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k?87)qL0S>D=tNbUTVg z({V0-$G>(vFX-ufp|kUd{?0G`>b%q6%H^T@@>3jnE53Zzt~{ql{?o~q^cyqvi;qt^ z@08~q&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d57~3=UwHUcX_8g?{MDXyu*2i z^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PU(P$%oZs*ZKWv{pxfcDJU-?nXu2H}6?Owa= z+VzJ%`?oH;ru~Kw{_V@Ib-(z-KW*7H@M}NeGnQQ&f8KBVtYz2CU-<0jEW4I|*B^MW zYwXHhdsp8zd2w8;7vFD$+I4N89={RN>33ZE{YI!?%D?5!uUrl4zwzCE{jxZp`pvIc z-uOT8KFiwu&hLHi<^9d_m)~=l&hPt6FI}epjX&~|W&L{Dhdfw+E0>4r?{BCRN8XCR z`8@5)b9&@IoqS1ue(~`s=biGr!+D4E4(A=tJDhho?{MDXyu*2i^A6`7&O4lUIPbR3 z@eb!*<@#QIIl+0ibsQU$L!5Uw?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhx6;ndG~Et zogeP0M2b+4ua2Wo>=Z*L>tM4e$2%KWdq_U;K}L^D@n^{SzO(tS|5S zE+4b3kN^AoKUm)@my_ztRdM97_`IuKIZqGo(&_w4|M70yRsPAZe)Y2Y|MaU~wJgpb z`RNaS)S37{^2HyttlfY2H@tG0o@f5U4_v16pZ!-KuuT8U-u}V*_22&8_uq2;ty~_e zFF(bRx8loZ?aFg{B% zd57~3=N-B%d57~3=N-;FoOd|yaNgm( z!+F36MCzmzv$sNXyyPV>vgKl6@un~&)E=VzXxv-yku<~99l zzSG~z<)QlWQyh6K{^s+vE6?eX|8(*t{jOE?i;qt^@08~q&O4lUIPY-Y;k?6nhw~2S z9nL$PcR25G-r>B%d57~3=UwH^cX_8g?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2S z9nL$PU(I*(oNLEw=jOaqzwDfyeFm1D%d`K$vU7a)C0KUu&wd5V#)R3&VA)tP`x`79 zLuTKDWn;_ihp=qSsoYppePdK{j9tYyX4bB;E(Y+eq*M7@$o6=o$|cHd57~3=N-;FoOd|yaNgm(!+D4E4(A=tJDhho@3zkI4(DCv z`d)oG!FjiJj(0fkaNgm(!+D4E4(A=tJDhho?{MDXyu*2i^A6{i^Ugh%89!gZ?!C;~ zfMxe&W^KT-do{C;V%a^MSzod2-p;JMSa#26)?+NY7c}cMmfa(o^&89X9nHFqW%raS zcdx1X?m-pDy{Y26XH~oIWu?bGv2?m8mj1KmVcSwZYdMzHpY<)v;>^02W$|Y{%(8Z8 zoy;;lvwmio&RJKpO#iI6S=O&vhqJ7|mCHl*<)=9ER($!aU3pHA{HK#I>CZ1dKIObq zo_9F!aNgm(!+D4E4(A=tJDhho?{MDXyu*2i^A6`7&O4lUmFs);B%d580>`EJg;XRvc~=JaLf>|Ez8JD2DBXW2PEzhRf1 z`*XdtY)qKzsAXftTwg64L*}|`+1N7IW6Q>z%8f? z=QqN(rF^bGm(`!^(q(bxdi7C9{15)^%i5jm+huy@x_6n*xgK7of3B04^=q!5m-V-D zd8oep6i42Qzxh1v%5!?;Kb?F@|M`vZ3?H9z-YL&JoOd|yaNgm(!+D4E4(A=tJDhho z?{MDXyu*2i^KR=L?{MB#uJ6^C6P$Nj=Xi(n4(A=tJDhho?{MDXyu*2i^A6`7&O4lU zIPY+NHQ!C!&o$qD*Vlj2vUB#I{QD1fF8|-(^@&^V9RH?If3S1^{eIbljR|l2cmMOP zW32cmf9k=;kT3Y}A8c%S-IqPsm{Ym2sQSjJ;uyP%Z%nIQV_kZTndvlUrr(%Zzm$LK zmp=Na{;U4^gT?vy*L?D77XQot+=I3IGjIPXTTai*Kjgu5zUp%yO#kzL=)wB+$G`T$ z`dhg?R9}9IBX7l*&)Sve^vHiYjhX2;X6hFopRzjot~~E>-r>B%d57~3=N-;FoOd|y zaNgm(!+D4E4(A=tJDhho?<&{#>dOhvJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6n zhw~2SmvhZ;y}r-rH{k3=zsH;3hJDY`Z^pj!=(l9wfAkx(??U?RIp25NzxA86?@0Qs z+V>^>hV8qPe%n^=H*fX*7A}t8$i?^Dxpw`gPLJQ(>Gaz?{eGL*FXer=QT@K>C{Evb z6u<93YPat~($n`M>Fhg_^!I&9{p!1u`dhg?R9}9IBX7l*&)Sve^vHiY`I7$p;^R}! zJLP$Y^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%c~`lB%d57~3 z=N-;FoOd|yaNgm(!+D4E4(A=tJDhhoznpjGz8ODXz~;mmTb9k0Gqx<7LuVXbHn-0B zyll>$aeLWZJmdMYIeNzVWpnq8|I5>kd12XHU%6|5>bo{5j%$YEyH=@P*BI$>t&&dH zlj(P@QooeXT(Iq`Kl9_VI5Tf9i$C+}vUX>lU8ZN|-(@;yUS6hu=Idqsnt6O#e=C=V z>dQ}YB%d57~3=N-;FoOd|yaNgm(!+D4E z4(A=tyRCD)!+BS^zE@vPaNcd5;~maBoOd|yaNgm(!+D4E4(A=tJDhho?{MDXyuAW-MRBkM)zA>se#;)QU z(`wgPmmXtgI*pm>H)hr^=;?f+v-61l&M*Dyywl&x<)QlW zQyh6KzI@iMJf}zg)5(|g8#DEbk54)8l;<7JJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y z;k?6nhw~2SUFDs3d8a(@aNgm(!+D4E4(A=tJDhho?{MDXyu*2i^A6`7&O4l6op&Gq z^MCjMfYte@f9&u5IqYx0^1VLp&tozF=DUC0vbNsxXWq0-!w>xUPc75--5>C;{{{8e zyAS!L%lh(L|HpS**2lm3?!SCl-z#75PJOv5jvN+WZfjT0)5D8&@-F?nd&l?s!tK{7 ze_z^8{g>ktXZgfmKJ6|aJ+Dyz=v+SfmruWzPk)zB9+ppjmQUU`{>kU^$@B8b|MKx= z_4AHj`55P2zRL;DJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2S-IMb7eNzAB zIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d57~3=N-;FoOh0;Gxt4*&z!h?=E~(Whc2JF zb@|M>%V#cLK6CW)nY)+IoW6YK`sH&Cuzao!md`cA^0^LNKGzt_=eqGx=W#u`e6Ce) z`OJg2{>+cd=bGnH=W!joe6Ep}&$ZL?xu#k^*ILW^)qRz7ZMNm-nr-=9%PpU4yybK4 zw|uS%m(R80^0|gw&M!Vb<-Aj#cR25G-r>B%d57~3=N-;FoOd|yaNgm(!+D4E4(Hw0 zIo{#CtDJY$=N-3jnE53Zzt~{ql{?o~q^ye2JpK{(Q&pVuVIPY-Y;k?6nhw~2S9nL$P zcR25G-r>B%d57~3=N-D9mEz>;v*DdSI>}$8I zkF($1vc6X?C)Jm$;>cm~<+gU^JUzTfC-2hFyZWVk_V?R%)t`O;mc^O<0GGv|eFB%Y zJNpMN(=+=DF4H;t4KC9^`w%Yc*X&QYtiP4ZL-pmSIPz9}`K(=ePLKSjlP~G#oqpwG zoOk&yCphnL-r>B%d57~3=N-;FoOd|yaNgm(!+D4E4(A=tJDhiw>wER(1m_*jJDhho z?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhx5*P=b1vk?>uYh_mO81{ciGXqTf@VS@b*0 zvy6U!dB)N2vVHb(ey@2Z((gFWO8R~08A|2*Y~|GV%%wP<#T4H&n%ed3COw`3rPDK@ z^m_)>@4HjJzmHD+{oQopET8zxr`_eFXMdL+oy$l6^6A&|>F@H%!}7_`^2yuAKlxlf zd0syGUp~I9{`}(OQ_ef(d57~3=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{MDXyu*3- zq4r%TICSt@!d;yYieK`A;Wb(w|>^e9C#JJnwMc;k?6nhw~2S9nL$PcR25G-r>B% zd57~3=N-xzxRFgtM`EPw{m%?zWfwN-ij}uwJXo*k^gkMR!P5W75(DlQ&vacmFFGKJDhho z?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2SUFG^-{oVu0JLP$Y^A6`7&O4lUIPY-Y z;k?6nhw~2S9nL$PcR25Ges!Js7vJ%*|BpGbeSyrC?H6PYZ66_XYx@hCbK7^wT-<&{ z=IHh*GIzIskvYA6jm-6xy9TJfYlGsrW+=XEiQ09Iksj9`>2$4bE0>4r%TICSt@!d;yYieK`A;Wb((hVD zzxeo+^GB%d57~3=N-;FoOd|yaNbqkzD9YcJnwMc z;k?6nhw~2S9nL$PcR25G-r>B%d57~3=N-;FoL^mM{?Nbiv3pOzocIU6?lsHi%5Qz2 z2b)8``a6HimYZ9D=kIv1Irr_}{lVtq|Ko3e%+@hS|Cw)ou(|sKzVgB5^w<2J2b=3F zcMVW|*9OIL%}{*TDz)nxBR#G?(&>6K{jOE&m-3f=$)k_z|AK$^U~yjZTVA`G#s5$L z?1Q!Ymw)cZZ8<$}`Je~W`3wHb2h;xruY0h5ee%~lSbr;*hw95uapbM|@>#p`oF4g4 zCtuR}WbdEVi?!+D4E4(A=tJDhho?{MDXyu*2i^A6`7&O4lUTjzL(^R9Az zufCk%yxTg*JDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhx6;ndG`W7b(YWHE}xjo zr>*6qVfkoVKAM+LUzSfFmrvi9PfnIku9i;@m(O{zd~&{g&Z9@2$N9BB%d580E>m2WJ-c`=K z>hlig-PSqY;k?6nhw~2S9nL$PcR25G-r>B%d57~3=N-;FoOfMkHZPbHn=j0j%_HW} z<`;8o^Nu;U`N&+{JY|k<{xWwrubI=E@67d;y9TJfYlGsrW+=XEiQ09Iksj9`>2$4< ze%C7XOL_B!`pqNaG{1=7yrbRbBYK*r=xqL?zj;l+n(y?ta(Sq}{1ivtiZ7qFE6?eX z|8(*t{jOD-@1Anr@i*^q-r>B%d57~3=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?<#M; z%RA+Hhw~2S9nL$PcR25G-r>B%d57~3=N-;FoOd|yaNgnkYQCG_>CZLa+3OoSXWReW zx!k_!&hhq3ckZ{3x-p^s)r}SHyKW3=KXzkF`?MQ#DmNBY-xyUKV^{HwnYC-IOOG)# zovtU-Z_KP;%G>8${q{c>r+v}IZ@+ZywvReJ?XON}`>xa9e(d_yKJEHjxja-~eu^V+ z#h1_8mFM)xe>#ns={IKT7ayOpI{L0W?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2S z9nQP0bG*ZOSGm4dUrun|ZJpyC&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%`Q`j_ zkEMCRy_e<-_hgz!+^cDRaSx|?$Gx5ABlmoor`!u_{&J6~dCk3}<~#S4DtE7``tCs$ z$GxfIyJuCq?q#LNJ+XAUCzgKq#Ojyw<_q2KxoP<{C+j=U9LK5JK=(B%d57~3=UwH^cX_8g?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$P zU!8Z&3+gmq_}k_YF`Hks)x1MP^AT;$Q#3b!=}YsPJ~rR!d*yOceYq-*92Q@0Ygf+G z!;5tCF8$|T^v>PNn=jOF9ucScMf~O+?KU6L(>z6I^B4WiYx>oEr@xiUL-pmSIPz9} z`K(=ePLKSjlP~G#UGv>j&bxe<6P$NA?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2S z9nQPToA2^YdEVi?!+D4E4(A=tJDhho?{MDXyu*2i^A6`7&O4lUIKMjY`hJHxeb>X^ z_Pq}=`wob<`aTE^eK&-*z9&L+-x<-DzCWUmeV0VvE0>e%%T;mYu=sLYyKE~VjQr>qx)bD#A;`AL5@%uiAcKdD!J$+Av&b~83f8QU`uf9v7zm>~F_2s8H@>YEL ztX+9dkNl^TFX`uB%d57~3=N-;F zoOhM?U6Q<0o_9F!aNgm(!+D4E4(A=tJDhho?{MDXyu*2i^A6`7&bue)-Fx zeY(VK|1NE{uNMvN_eER#fYIFkVEWR&Vfxs9V)|aWoK#<~iX(@`m)qKv^Yri{oxDr` z@oxL2y#2V;Z=Wu4+P_Qu_Vv>4E6;vn^t2Bco$U`sfBS~%SNnB% zd57~3=UwIPCzf~0^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%dDnUO(f{UW z?>%aD{>1Nju)qD1pM0>GfAnKNXX|L|+yDH7Y4~;j+V9$O+J5J&9!&F>eBOigdCJzFZYY4vR0hwJYc8;YB)mmww*WFXeCl$3JUzs{bDU!Gp#5MQ{4d zEf@bsKI6gK{oG&vV0xbWd%tt*(D|O<@?iS^!XJ3Be!c1UK3IP%mxt=hPjTd}`0`o1 z@|+&|PbXi}&pZ9f$2jluT~2V`;k?6nhw~2S9nL$PcR25G-r>B%d57~3=N-;FoOd|y zD%bbw%L&dqoOd|yaNgm(!+D4E4(A=tJDhho?{MDXyu*2i^A6{o^X_qv_v)TfdQ}Y-!z*^j!~s+xI@i>^mUZ>iZxx^xY8J`kn~QeP?97JKqD+ z$G%Il-koweslHqlM-Ge6yV{lW^zb5`&ad?Iu6`-+yB_NIy$^Bv4v6@DA4I!-H-w(P zCqif68KJ-LkLXw5CDGr?<)QlWQyh6KzI@iMJf}zg)5(|g^RDlbJmtL0cR9g%hw~2S z9nL$PcR25G-r>B%d57~3=N-;FoOd|yw$AYm=UwG}mn83$=iSyh-r>B%d57~3=N-;F zoOd|yaNgm(!+D4E4(A=tJDgw6JJ0gwTID(H8Q;w5%bxwsoWAUt;9UPKdsaBtMa!Nc z&h^r=XNz+kwd|SWTwg7F7CF~l%bror_1Lm!mz8^_S$)qsi{lw+@jV-@UC&I@<5_At zJ$p^RXRq~3`CNZ)yXwz1*s?fty}B&^T*oeJcdl=j>6z=^Wjg12c$xmWPF~ipxqe>O z-^%5o`tnm8c`Lqr)~-CKNB+~vm-OcsAD?pGDbG8ccR25G-r>B%d57~3=N-;FoOd|y zaNgm(!+D4E4(A=tyUO*w`f`Hv4(A=tJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k?87 z)qK}}ch1fB!E?^GKb~{Bee;~-?WgD5Z=XG5!Y7@5{EQXt%V!K}zdmD2`}i4iDmNBY z-xyUKV^{HwnYC-IOOG)yo#wUl8#C*d^7g?~zy0yVY2Q5Y+fPrs?XyQu`|r`&zI^nz zU!Q)pkDvZlE)Uh0pW?_{@#V92B%d57~3=N-;F zoOd|yaNgm(!+D4E4(A=tyRCD)!+BSE`}pOZ^1RzR$2**NIPY-Y;k?6nhw~2S9nL$P zcR25G-r>B%d580>`OZDD=DY3(I%m62=v?mpp>w?Ziq8G+HyRVV4{5CE{-iOa`Bs_Z79<{YHAa z4@qbDC+Y9LrG9lkQ-3R$hw95uapbM|@>#p`oF4g4r!h1A#?0fpP6^O&O4lU zIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d57~3=UwI9&&)gJd57~3=N-;FoOd|yaNgm( z!+D4E4(A=tJDhho?{MDX{Bo|j$MRD@@1=W<zhukZ z!}+pLd9Zss@BGdWcF*SrzyDWk9ruFX@Qn|4kLWeO@4@aJefk$Y*gd7n-D|48dr-x3 zZ>sq2S=Fw4S?O_4ES>I&rQbcV`lbAXzTnYE^(+}3}-+0^i z*m8P)(fdD`&X;`VgXw?WS3X$3zTou_*5AtIq5ASu9C<6geAcc!r$_$N$(Qu!7ayN; z-YL&JoOd|yaNgm(!+D4E4(A=tJDhho?{MDXyu*2i^A6`7&b!L>z4~&3^A6`7&O4lU zIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%`SoPJ+hfeR*>h*-Y|o>e%RQ%dj`#f9x!-eb zV?xinjTJoyH-_|l+}P4{b7M~B#-i#Qql#nfD!wtTc8zuEF$Sj7n3?`FW^TWf_uN_i zo=1z*b87K>ey!b}Ytz&7ZaRAoPJhqG^{eOR`dhg?R9}9IBX7l*&)Sve^vHiY`I7!K zX6~`~l=F_id57~3=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{MDXyu*1{dC$%BPI=zp zyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PcR0VA?|MJfx!HT8&e`54buRawsdK#d zPo4X{mugJteN|&c@39&~dcW1!(tEGQoXU+w)i*{J$JkYTV_NMR>(XP)Os6q3{l?7t zrM&k>)$e^$aeB{G{N6v+Zttbi)BCD)_8u$!z2B-|z4xlWmCHl*<)=9ER($!aU3pHA z{HK#I={IKf-s@A&JO1V!&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d57~3=UwH! z_nLRg^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%`PF;3NUyY@+N&bEJo zbGdyLoa61c;M{K?24h0|GZ-t{x4{_Feh$W#_IWVoRBkM)zA>se#;)QU(`wgPmmXta zI*pm>H)hr^<)3`^c~HOo6U1p>1@YT&LA&k4Ku`NK(AmBX^tYdbeznho{#Gsz)t8^* z$XoH{vv%bsu^SEsps*Y&0S*!8h}+V#D1IjO!}6-N$> zFSoTT=jq{HI(e6V-qkPV?Q^bv`=5)`zUbn&U%GbNN1dMbSEsXm*XeIRcKvFfcKxkf z9;z=t#gVt-%V+J%b9&@IoqS0@@ANAlBfynWj9PI=zpyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PcR25y zYwm4YYlPkNY@L;Rq4TU{%iSYwU6y;Nt=Do-wRK$XwYI*?J=oTLxi{N-usKHVIx+Wh zD|e5#`tJP}$35ZVyBA%%?jfhgz2$UzUXXtGqU)FP)>*0F`YUl-mnDAdwY1whE_zzu zMQ7{2=x;rkezi_ae=C=V>dQ}YB%d57~3 z=N-;FoOd|yaNgm(!+D4E4(A=tyRCD)!+BS^zE@vPaNcd5;~maBoOd|yaNgm(!+D4E z4(A=tJDhho?{MDXyua_o)zinSiG25?FTkT^>L;G9O*1nfCzv}FVsW0u5 zsgLcSsqdA`N%iHbIC5Bg-qo(0r-ygxbbh6uckQ2f%6I?CQ-AlRJaLv!{N>Z`^3k*V zULKvxNB{Ea*YfG_^2x*U$B% zd57~3=N-;FoOd|yaNgm(!+D4E4(Hw0Io{#Cds4ppXXc&qyxTgDW8>vG?{MDXyu*2i z^A6`7&O4lUIPY-Y;k?6nhw~2Sm-Eit*Sug(Y`!p8HjkJ?n_tYW%{%7Y<|A`)^OQNd z`ODnhyk<^sU9`Era@PRWcWqD{*9^sXEm6C!G1BAOBb}~Q((hWOekpIhP``OZoaPtt zn|HL^d_+(46rIgq^f#~RSM#0zRxS_Km!IOuTk++ycI7!e@}Ew=q(8s-_>}WbdEVi? z!+D4E4(A=tJDhho?{MDXyu*2i^A6`7&O4lUIPY-YRo;A;cgph)=N-;FoOd|yaNgm( z!+D4E4(A=tJDhho?{MDXyuNGJ;uN}J~#fko?JfHDz|*j z$7S{BJY5!N&fiC!i9hG{vUcZuU#4fqfn_>pd|0M`#*JnDYMq$=RxS_Km!IOuTk++y zcI7!e@}Ew=r2ky2JjchUoOjCe4(A=tJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k?^A zkKY2@ue_^V->WYtIPbR3@eb!5&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r@Xm-nqBg zdFP&I=bd|@9nbEOcAUF++VSt6YUhP}t(`CK!FC?GH{1E;o^9uyd%2an$6I~(ev9Lt zaPi$Mu3h(#)8pQ9I^By-zkAX3OL@nw`W?^WbexOd@vq&^3wkB%d580^^3J=wQ=WG??{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2S9nP<5 z^SOBz^vqAb?(=utj-Qmj;M_drFZ`wt{-$Ne^D95}!H)A6z4pP5|F{3F2RkqR#8*Ao z`SQ14c(C*6Gk@&C&aW4}`!{b)=iN_y)PtRmulxNEcAh@>?Qbpr)i3%}xBj1d*@MOT z(2swx_+RpSAFSPf=TAPEp7;7I52o`UzUjgAfB*MASidUgb@d(p#c^H~-}zFz&ZG1= zztZWvOTY86emPI;uk!Mse)$onyop~vwOgL)DgSil3;p>uWBM(hdxN+B+%LUx=056; zKlfK}yK~?5>Y4koSLfWPz53_=?d_NE*VkX=C6}U^Gm-f z_pPq#`&L(R=DzohKlj6LyFWAEuTRh1KfgNXzWUWa_uFs3d}l4cl;@ZF`6W(%iJxEE z%`bZLi_ZL_Kfmk?RJr|vs&5~m;@DrP`1T#DUHcKG$38{rw0}|h?Q7I=XuqTUQl4Mx zmmhKROZ@!OZh5As{L`5)^yim;Rc_Cm>f1-CIQADRzI}&k*M3Clu}@Jt?O&9B`x@0R z`yJI^<>f*B@*_@p6Tf_Fw>;BR{^`sY`t!@aE0x=4ruz0;DUN+~OdhBnL zPW#@Z-+nmt%RV{vS9y6*zx;?(-o!7T+AYuYlz%$&h5r1~ugdMUQhoc+6vw_a#kXHg z?b^pCJ@&Urr+shIZ$F&+WuKh-tGqm@Uw*_XZ{n9v?UrYH%0Hd?LVtewmQ&@vV^w|M zaw?ARUKQW>uxi(LveM)GS?Tm$t@QieR{ioFuKKIIJg8rO#3^s$mrw1MXL`y%o%uq4 ze(6``zU5SX-*PIB?_L$(_poZ$ce2vs`&sGqU9I%{-d6qc9j^MTygaC1e#9wn;+IeD zmS=j(Kb`qPe|~xYu5#}iR^K~!#qoY(@x8ZLyWVF^kM|tY>HWv_f7QGfS--q5S$~z6 z2ldO3IOR?J@~PeOOi%fzGhgV>Fa4_AJ9pLh9%6C4pIH2_|DS)|ZP)vZ>G7UpI=%mx ze(y!rFYim%U*+XN{qiGDc@w{UYPUSoQ~v497y9$dI^oK#AFlozX8m(KY|xpu8jPLFlV>9n3X{nk0xFYBM{uk!Mse)$onyop~vwOgL)DgSil3;p>u?;YH7 z>rSh0J!)~RQ!T#rtF>!gYkI7AO{aCR>9;<%epxqLf0dU9^~;Yqf*B@*_@p6Tf_F zw>;BR{^`sw`t!^CS(SSqt@_?mD~|WqitoL)+V#F$dOm61r%R{zbJsUHw&F9@H;C;*>Y>%cpkBGd<;>&U~Rizvf={E&u61@^fzecYd#*bK|_-|MsFA z|NB4jMYr8g`6Vy9dOr4>-tufZ-}lvTc{csO`4_(B+4}XxZ+Y{x^;da$P`~_$Q{Kcc zpV}?Y^pt-(^M(HW(yz+@@aMnHt^e8o_-$^S-}f8e_QwD7-~6`Mua~^&#n-P-c)u54 zzdrkSy!iU{!(aa5>(`t9(2K8M%FBcL`6W(%iJxEE%`bZLi_ZL_Kfm7P7ysz9mH*c- z`;lj>|5rZhA3a-~*L~R!KU@6gzUv=8Tf6_+ul|S6rsp61$$xPD`l}!E53XN-|L6aM z>(|f!mp^pQ;^)Xy(*@=N^u(r$jylV5b^3;p?}UzNY|C*OGM zzxcb~bmRQmum0{E|I0q+uith*;s5*VSI^)1{O`FsU;KmLbM^nwFZtfvuRr^q-+TM3 zJipY>FLClq{QS~xe$kU(bmkZR`8D?xZ~1)d`PQHBU*91)ef7`xxNpDaJKeXx%JWP8{1PX>#LqA7<`+HrMQ6UypI`b_`FxlB)}QZ{-#GIf z^BaG@Z+_dI@19>h^F8#dbH0;)_0RXyZ@=cd>bJkj^Gp5w5+}dJ&oAxf7d`n!XMWM2 zUvvNWmd{%HTYug!xN+vagByR|N4V|IdkR<2yuWaD&U+14|Ge*T`!(-D-2N)hFZJ_F zoct0$zqFfQ^yC+v`9gnw=~w0R-p8#!?}OYp^Pb3!Kktv+cIUm4t7qOfxjN@Pl&gQ< zPr3b?_f~FymFJiG`6W(%iJxEE%`bZLi_ZL_KfmVtq_=#&ae3>{cRz2O`5x$vKi>(x z?f%;z^m$j$d{^}9obQcZ{qr5t+pqaP>Fuxb{8B%^#K|x5^Gmz=MNfXwnJ@I`mwr_~ z-($V?=R2)8&V0Z1#-H!H-gf7EuUF4}2lncm@55gG^WE6nulb(r?XU9uQa``M$uIHq zOS}0+PkzyvU-akK+-JMxvu6I*pEdJ0&b(i6U)s$tdh(0T ze4#(T^sDmObKusWeHd<>*`MLYpM4u{yR)Ce)ie7%T%EK3!_`0gLfn4Mei667%JWP8 z{1PX>#LqA7<`+HrMQ47|pI>tw^-Sfnr`$8upMCb8DbDP__e}9;Pq}AmclPUhCOxx{ z-!ti){r#Tl_t)(E_e{UPW(2{L*fI(UV_v<_rD#rC*iL{)e~z z?2CBg%zlY)jsI)@)@^t8SG;;=-^HtQ_G7&IXP?H~ui3xx_E&j%P`~_$Q{KeC`J8sk zGd<;>&U~T&t$uyjE&rA`zw*|9-7y94o*N5Hmulbc9b?blO z+r9S2`JvDLt#6J0!N2{s`^6vrX;;r{KjAa3&d>X8pLO+r;j^D}`}M9r@Hw}?%JWP8 z{1PX>#Lus9n0E7vp8TRSzv$1eclx3ieSPKDS6AN}-FZ%QAGd}SbeEpO1_kB|TnPxQRviOyF%(f^7k{d&cd{=VW#9$xVzKd*R_x0gT3=gXhu`Q=aY|MDlkyl;NZ zy!?FSy=a+s}KIh%7Kj-6(Gw11B+;-=@zIx_-zdC0excX;& zxc!=O!#DbyZL25-u$vpZ+LfpWgbbygaC1e#9wn;@^BuyXBdl@=s@e(Vt&) z9rbOM+qy=huuIx7@qf)%SjSalE%)eDAZ@uJ_#2;BR{^`sY`twV_DxcqFx4w6=i{riZ;(MRHcD?7G9`C=W z(|hsh_r84n@*aKtRbC#{FF)dxH}T7-cFQw8<)6;{qCdapKEN%X-_f`J{Jy?%=6Cmv zKflLsyYoB!>Y3l~SLgh$zxwC*{_WS?2e|!JULMphKjM@(@yn-n%QHRsMQ6UypI`b_ z`P}!o_2+)bjWhR2Zv44_a@(EzDp$|kZ@D_>KFrlW_h)Xu=DyACuk!p-KflDuFY)tB zyZJ>=e$km<^yk-Ke8<<{a{H@P-@YrwnfqEdzI|G1*ZwW(v9C)y?f260W*?Z2L;J&Y zd@9c`_47-d{1QLEw3}b_P;@hXCcJ1Gi9{aka(|#}M zw+~GHvOi4yRbC#{FF)dxH}UgJyXBdl@=s@e(Vt&)AN!Wiec)Sv?hoHMbKm&JpZm$T z-MP= ze$km<^yk;y2e{?)oaNS^=Px(TJeRrg=XuR-cb?;1J@b6$>YV33SN}W@y8W8xM7O`n z^Gp5w5+}dJ&oAxf7d`n!XTH#%U;0(~JQut5U;Po^dE?A;v>Sh(uibX%x!ct<&*QGn zc}{or&-1(6uX(O_`>Q;^)Xy(*@=N^u(r$jylV5b^7ybG5F2DFkZ}~jOy!Ge#=8ZGY zJ#YMZ9(voI=cHH9JU_iU=eg?DKhIllzvemY?XU9uQa``M$uIHqOS}0+PkzyvFZAb^ zepNotop1el9)07?bLty^o?qW~=ehRPGtaxP&Up@g_0RM1+pl?Ue*3FDztqn!aq>(2 z{L*fI(UV_v<`@0>HR~K+sC?E5yiomFKk!0vW?jJx#h>*CFVya=LwF%Qvp(U4bk4ek z7aGrJJ;Mu)^Rv$3g~os7`K5k-iIZRA=a+W#i=OFa4@~)^*(av)<#znROsH z{;UtV?asQ9t7q1eT)$?W$@Od2pIpCYUCQ-Kd3jL3{D@QD#4n%PEzk6ne>(Gp{`{JC zM7Mm_;oSPOKIg`nbvrlytmnCY%{rg!*R21!e$Bd|>({Iox_-?%qU)FP{8B%^#K|x5 z^Gmz=MNfXwnJ@I`mwr_~>!xn~SxFLClq{QS~xe$kU(bmkZR`8B^QZ~3fqyY*-N+l@2p;%@v|FL&Ghqi^#r zSI?}kyErQX{S&w?#opq{L&#Yg)I%i$$)j#W9Z@*?8?Cr1e{8B%^ z#K|x5^Gmz=MNfXwnJ@I`mwr_~>wa(jSr2^U%sSy4f7TD*c4uAj)idjjug+PAeD%-z zFLClq{QS~xe$kU(bmkZR`8DgzZ~3g#zV&DQ_Kh>^x^Mhh?|s{y zb>LUetPj6BXWjVKKkLbFzh<5J?XU9uQa``M$uIHqOS}0+PkzyvFZAb^epNo}>Tms7 zZ-3*=I{X`d*5}`LXWjnQGwb=U&ROSw_0RhM+pl>q;PzK}eyN{d;^de3`K8_bq9?!T z%rE-$Yu@9y-p{~i9|``>=edmOjF z%JWP8{1PX>#LqA7<`+HrMQ6UypI`b_`MkGs>(BcvH_p80a^uhYFSp%!FXrl*_hqim zd5`AmpZ9BSzvjK0+h67RrG9>ilV9TJmv-}up8TRSzv$1exzBdX=RKoaf8Ia3apt|G z8-Lzcy6w(;Ojpmm-*k1(drw#YybpEzHSbB?{wmKe_47-d{1QLEw3}b_5VB~E^c zpI_R|FM9He&itZ3zvex}TmG^y`Pf^3-tW6{=Doigf8GbY?aq6GSI@jZcy-Qug;)Q) zZ+QDP?;+m)D$g(V^Glrk5U)s$tdh(0T{Gva<<~`qAZokUv z+q1Da_O~p)eJ^Ww-ow3m?30bXd?Dv=bHv9dhJipY>FLClq{QS~xe$kU( zbmj~F`K4c#+q1Fy_OUFE{Vj|CO`raWw_W>TrpG>+>9l`l`t7S(zwEc!?@i_9LH+y^ zr@V<@KDAq(=_&to<`@0>HSf{i@_7&a*8h^(r?EKm-ujI{@3Y@_=RNnUXWoCmI_JIk ztAE~?zx}drRsB_79@H;C;^de3>F_F&wc_o&g?UA|2#z%JWP8{1PX>#LqA7mS=kMi_ZL_-#!nY_D+B0 z+4g^kpX~qev-X8}_doTG{(tw2z;F7B=l5^zDe;u6^CZsC+DGC^yIX$Rec?&``|!KcBV!9NX)oa(jSO-`*g_v1dr}?IlvX_83Wzy+_h% zuaflt+}USl+S#_0TfePc^{wm1;#lvE#kUR|YuEa4OwZhJU#4^J!!Ofsow+*tW&JtU z-^%5o`tnm8c`Lqr)~-CKNB+}kuaflJBgpS)ZP`1>?`v#NA-}t^y@vcA$MzudJ007b z$nSS-&mzC;vAvA^-pBShavuQCcK6+V%S#)8ltNrql0zOuzd8SijsK!1`OcJXBwP ziX(5um(SXj=k&;bI{A`*ep#ojE#=m4WA&};#^TI#!)5WU16QuydCs^@k9Fh9>9n34 z({G(Q)-UVNvHn&r57n2S;>cU^<+FC>IX&{9PQIj{U-e75_1oH2-@0xrj`iMH{CWPn ztX=EFmD6M0IHuEja!kK<=2*Y1Kgar8xja-~eu^V+#h1_8mFM)xe>(Y+etX~5FMHzE zUwh@12Ycw1AA9SSH+$}tPkZr|XM6OOe|z`k%iM3ie%b4d z_83f$y$922ufp`(tFV44ufOV-2XV@e_~lKz<&&QBOlSG0KVS4Kzx20qd8oep6i42Q zFQ2t5&*_o>bn+$r&M)_=92s zeKzbkbpH)IJ}Yy7%QyzyWC<^^$@FT`&i(Qfk#J;bO;$_j9r1$9ucjapiqp z?0EB@FLoSy{}($xD|g&h-|<`=$9eG`|F!G9NRRU+ozA25JHP6ea_`S-SAFl*VsX50 zi^caIF4nI1b1^;M+r@NxpBK~bJzuO}-v7n=Te&<`Uw(=sZ^f6-+Lh<@$bUNdl792o z+^5>MjFYoYY}xqfy(AiptKL__yEp8-$Apc;-fzOjXYV~>L&v=AHDIkJ4$LO27H5eku3S{oa$p`sMv8tiP4ZL-pmSIPz9}`K(=ePLKSjlP~Faez~uxEk3&6i23V2 zB<8#Oli2a#z9n{?xSxp~Kkjp4$Cdk^*zxARD0UpWUy2={l{;>$?|3eb}dRlk%sU#s6dE>82i_|5y; z?RtQot`q3&`eEnabG@NoU2p7seahvb`tnm8c`Lqr)~-CKNB+~vm-L_WYtLmqHlFae zafa`WKaL0Qbvl+DCyiH*pT;rARpXoEt#QwB*m&sptlV*1eaCZg9OuP%{MWAYB0bKR zbUKgHf6lMfsl4$-{l*z_8h^xZT+(ji6+Mk(bT+=x-?*n=jfeVMxja-~eu^V+#h1_8 zmFM)xe>(Y+e&?5U9rDjd>pd`ktpmY)w>|_r9;_R|juY!iu;a%%6YRLM{scSTtV_X; zL+e$rr616)}LVdtxLiBWxWd4-^%5o`tnm8c`Lqr)~-CKNB+~vm-IWork#6!b^ndO z-IwEg_v;)F-N$pBbbrtB(|te3RrdoOZ`~(!9CrWE@maa!w)&3e;yBKW@A$7>=S6y) zFX?n1rQi8gzm#|XP5ti6iPQZ$@w<$CC>34p4?(Ep$qvz3>zn)WLzI%R+9S@#sW5SsPa7?G? zS9#;V`ppaCG+&6{Jfhv^7kZj^=xjcszj;c(n!oh7a(Sq}{1ivtiZ7qFE6?eX|8(*t z{rsw5${YXHZ(b0m`9l2W5$!g=(9^s_XY&#L%~Sf-{H4E@%R}|$r#SLfeEF_K4 z+^|0kHl9>&oT9pSqrr$m=SikHKgY~y^d8oep6i42QFQ2t5&*_o>bQ%xS&#(Etx975Q z>w&eazIDP_9P5X%_|_F;?OJb)>9GzO(`kJ&rr)|{tY6kMWBsjM9;z=t#gVt-%V+J% zb9&@IoqS0@zv`EA>w&eazIDP_9P5X%_|_F;?OJb)>9GzO(`kJ&rr)|{tY6kMWBsjM z9;z=t#gVt-%V+J%b9&@IoqS2Z`x}k(en&U{`+eQK;CFZPh2P`NBYvkhzxe&$yyJI$ z^O4{C%~S3JG=I52P`UdC)ptLkIPNnP-~ET$bzdSq?pLJKeT?+Gzfr%GH~y>NydX~V zh4{@Q+HHQJr+J6Y<|F!>r}V4&OMfeuhw95uapbM|@>#p`oF4g4CtuR<{PG@zV}p<0 zkHGx(-UQ~m_bIUB;mxo4v1P}J_b-$?e!Q1~9arAhz>YWXabU-x_dBrTvvS96^&QW} zahw<5@n5^ni}W~O(&;=(zw@hpDffPacGdUZ1Qy5p6j*%kSzzsY{{qwFy$npJ_cbv6 z-s8af<^2w~F_2s8H@>YELtX+9dkNl^TFX=zm8+-1X*Seo$zUw}Zd9eFG=Ev>} znK!#%WIpXal6kiKOXlD1JDHceA7#F-+&o@=^Lug3`^9%XP`j=Z(&PFeovtg=f37#S zU&_0mqki{!#OeNz_}v%MZug7m={^#j-Cv@=`%e1R{V4sdTpp?~KgE%^;>&04%5!?; zKb?F@|Kon|8=rM-IPdJ2h@FqGo_!Rt^VI%|*!gSUMeMw`A0u|Y+ous52khU7jSu#9 z#KsN#J!0cY<;I!n8-I#pTq?fts&BfM-hu-e?=_5 zeHXEI?Z=4eu}>qW)BcT^e)~FN{j%R9*5AtIq5ASu9C<6geAcc!r$_$N$(Qsyzvg^? zPFsBR{SM4u-}S(J_q`A7c=)FI4hVLf_&x}B{P=DNc3kr&IooK`u+%Zd{*wb zt-j;AIF9q;JN|3ed66FHOFErL>34qBFXg`9p5>0*@+JL`^#G6SKt6VT#ow;G z_}=xHztPim9i3h8(cg8Tesz7Qzm>~F_2s8H@>YEL ztX+9dkNl^TFX=zm^LuQZ>&E4CJ-K|YGndcx=kmEOT|U>VJ0_g#*yVG5yKG*zzqI4< zTn{gw>*VEg{k(jxt2h3+-d;Y};mhax{88s|-M)OT=WqG=c%R}|$r#SLfeEFQ?aQ{}G()BH14I}cv!!bw_Zj4*0G4w`WEqj)ma~<-PXg<(>fVCTR%g8>uU6?^)~uj zxja-~eu^V+#h1_8mFM)xe>(Y+{&Ri!jAKK&{oJtn_IbnN*#8ZSZ(lg9UHiphdh8>I z>9oHbrr*AESikH?hxNB|d8oep6i42QFQ2t5&*_o>bn+$r=lXElQf@yt?W%8|H!P0* z-|)ttec`Zn?H7mXv5y?4)BbXpe*4a0{jwh&*5AtIq5ASu9C<7L=JT{G&*_o>bn+$r zXa3sr@r;wpXZ&0~d3O2CzsqM{UOw~n@|nk% z&-}i8=KbY!J+OSP6PC~Q!}7VVSmu}a_#7L`z2Aq`_ud~C$NPX-eD4Wj?RtL@)8oBD zOsDq^G5y{{#QNp^M6AD+%R}|$r#SLfeEFwp#P2zjc6&ZWPtUFB?0FXbJ?GM|o`30YK{ z`6-UP6<7`HoLjOU$4 z#`(@Kq_gq7}J@25W=OA?Ue1!g zbn+$r{IU5>0*@+JNJs$a_O&#Ybb?c0pSv7a;E__NP5)~@}ZF+KK$#&p^* z8q;qdX{=xNm&W>Axja-~eu^V+#ov6McI7!e@}Ew=r2qK!ZQ4?9zbUM~eW9;Qy)-U^IVg0RK9;z=t#gVt-%V+J%b9&@IoqS3E@oU>s zZoet*sz3J|m&LI^m2&azTZOf2KPya+eXcN__P@gP+ZPM#m;JJ^{#Gsz)t8^*$XoH{ zvv%b~F_2s8H@>YEL ztX+9dkNl^TFX?~W@BPtdwPjvw{ki$Bb?N58)~lNzTgPtRY<;`=v~}<1+1A6Ge_JPS zUT*!o`MPrRc=gTi#WC*}-}ON4x=u)s>xXo@u1Npme($4S%3FV~e(Tc3X}!AmZ$9hi zwcGl3dRq5RXY1kVZ=Jk;wSHcIE0>4r%TICSt@!d;yYieK`A;Wb(*L;Lc)UmHyzBiA z=VR}EI8S>Y#QEEMBF^jHA923-UWsv__f3osy@z7l==~JqN#(|w>KlKGV_Yh}@v3%> zW9c!zrPH{V{>SykqhHE`dhg? zR9}9IBX7l*&)Sve^vHiY`I3I);ksQYA zL9p}PcSEpo!1qM3@xgaSuyMopN3ijva^p<(jX%XPE*0N+RlCNq^cdgLY1~V{@vwd= z_x%p-s_(lVSRCK`z~cK32-dFegJ61mHw4q^dm@;A-xdQ}Yy5D8z zcAm~U;brIVtRG%>UeCJXW#{{>H(oXl%sS*{&04%5!?;Kb?F@zwxkj=FYp;pF1C0m+m}m zy}I+ab?naT*0(#~Tla1pXg$2~p>^`cjn>Z_PbxRgRNweh9OF{)jaRj697~V!EuF@_ z^cxTBm-5!1tKYhGaayk~e(Tt^+xm8T=JsRaN^|x|)sJ{FZN8XAr zpS3H`>5>0*@+JNJ>UX8`es8MZ?@)32eJXyxTeaKoS$g`NOJ~1->F;;3e)W4dQ}Y*Z*#t%^5s*1`NUa1@t04#%SX@h(Ybu|FQ0xbpZ+eNJS?C5ET6nBpL{N#JTIU8 zFCSl)k6*XE`vb?{EkC|5pW|Wq94E`?_*p*3)$%#smd|mxe2&lMbKEYU<9YcU=ga5# zUq0u>@;P6Y&v~?bt~YjkKJ(i0neUd*Jh*)3$K^9`E}!{y`OLG+XZ~G2^YZeUub0m} zzI^8Q!sy$9kqO}ua?hs*Ydd@TRzum%jf!S`CQj6pX2bcK)A^PDbAD~V zlsEpX-@G7B^TozL^N4nvU+8Jxp|kmj{^lwDYW~vS%H^T@@>3jnEB@y5v@6f)k^gk^ zCH?&Bcct=vZ>rz#P;vTwDt^CPwcGDmditG9XTN{x?{~3&^?O-=E0>4r%TICSt@!d; zyYieK`A;Wb($BB@rM%yp>i0WToPM8*-|trK_Is9|e&^EJ?_c`=f2Qs|`v0!1>%8M~ zxjf;h;d!#~Fb*SV4vQS&{@q#@K^l@~hTtKa)|jLjVxA9Fi_~$%2xZ0r2SW{GQY-U# zbDO87CZUMt(!n!orDCZOlc{q(uFw0q`Tp@;>$R@6zt?_U*K6vjr zc(cnx<>e%6x9*g0&}Dg@0}Aj z4s?Fp_|Um><3{JrjVIZSGnF^~ukG$ny zKC4%r<0Jp^q)Yti)wsdlc%ppc3_p!O{5LMCxA6*}#xXn_-|%nT6IbJ*c(cnx<>eXJ{Pg{T|GsOex9=VJ^c@7xzK`JFcN1~- zJw?3P<)QNOlOK7@zkF7&JjX}=<4KqJ)2q1H`yQcu-zoU%`vw1f*HCZYJMif{2%dc( z!N2b&;_7>fc(cnx<>e+8PTT6gz7*Lu9~ zyw>S`|FwSayRdbA-;1sH`;P2AK;M_WAIR>#LFK(q$dC67`S<>zdcBv3kM|Yv^d2Mr z*ZYl)i@o)i@_o1Er|-G^_nlY0egDO$@4|TYy%_(#Ba5r=%i_&050#gn{K#AW<+FO_ zIX?0qPrAha(#u%C=kKBWz{<8S$M~mszzAyIngDKxWF@D-V#((?D)Z2bDeAFE6?$f|9I+0@uydDv9}*g`SywN)BZ93+gGOE z_M73;J~TYrpN4#v|93T0QCtc!yTYufo&YS1AAI$u} zePY%H?H{vVXkVFiMElLGFWQG@-O>Iu>yh@YS*Nt0&H5#~bxq~1ck*K$lz;1^>a}i) zkM&eMt+V2PTYuf+VsAf~^6eAjr~PC6x35gS?Ki`xeQ0>LKMnu(t%50#gn z{K#AW<+FO_IX?0qPrAfk|LR;e9Xqd0-_CK+f! zJM6r<_L*I~t-SV}AMHH<+JE)x7xB?w;;A3SU;ipD_Rec7-#Ko6I^WHI=f2h3d2oC> zCyr<5$MNr6xwtxSF5c|&PukG$nyKC4%r<0Jp^q)YtuuQ_+~(%$#Zxs}EAo%1Y< z=|1ON7Hbc4{$;UtGUs9zYd>>dX0diP=V%sdZ*#t8v3BV9aMh)KX4h^juRZ5SJI}xN zU%mQ8eDs%i>PPX{zlw`}&KYgJ%Fp?u#r({ukG$nyKC4%r<0Jp^)W70yK0n`y9#EHgfuNIqU z&U>xJ=ARFr-&I%Myma1!EjC}B_hXCAW9PluV)NU1pSIY%*YCOeU-RMY=E;>ef6kA2 zb^gt_tJgd{KIZ4~G;fc;`FwG)&wItKSNVD0xR{@L54m{#&+n?^rrvpPxfq{$pSc*% zdC$2R|9StpSX_S3-T#U=yF650e)1!4`QLnA^~!U6n|jM9KIIwD@{fPIh%3Fsn_V6%FF*N_xBPEDuX^PXqmC$bUTP5`XiJd2h3I zd9KYqx5b`!v;S?e=iuy%TkQEb`{fpUZq7cs#h$0LzizST?CiT+?D;$U@fLe7&py4y zp4Ztu$1Csoo*&Qs{F@I{uX#dz%pc-uUJ-xujpAaTeTiGI^0QxYF+a19aWVh1zj3j8 zU+{+SvKXJ)54jl6*(bRe|JgseSX{HOa0*3lzPcFCna3{1f9AJ~#pU5ad{(bK$4CC-NtgKF=7+cQ^2W*8=eF&{_&NLE z78_S*U)*Bj?d+FZY#g3_bc>D8v%l^h&c^N8cemJhKKt<&8|S+p!1$ltbD{E{7y0oV z$-n1I^?L5a$MYzjo>TF^%@1#Jv3DL;`Oe+*(|LUUJEyPS&hO*Xxqdu5?~i}?0Enym z0mPeK9x5+C`H{E$%V+hH&U$>Y zad_70i;d5-eqU_do^}1=ogaSb4IAg@J;2&`et6kE7b@?0ksr^I{CmDsujfvDJdfh( zITe4;ui|2#_a0lX^7B4qF+cO3WHJBq{$#Ow=e^2eeCB=2Vm#+P%wqiK{mf!<&3l{0 z;>|7(m6xCV$Xov9vwGz@KJp(=y2M}qDlR$}FMZ1c-OG>mP~NnY@~QolXYH!|@BHx6 zMLSHdogZFy?Y8pTbAGh*{A>T!t6#)Ne~G7l6o37zxY&zV`SQR|`Qg93skeOMQ=aiG z|M;hixYA3!+2x_~@{=EV%fEb9uRO;`{^LoP_@${UEzvowRvClmZTd(qS|HEQ_=3a=!>;F}cUaa1^M`H0lPrv&Si}9R$ zCl=#B_faes*W6RFSiITgq4N8Dzx>Es{x_djz49C%`Hv@E;(zJ&QqLXsxp#E2@^c^Q zVt(eH(#8DG{iTc5JNKF{#%Jz3U5w}4gSr_1xgT}0xaQu}#p2B_50#gn{K#AW<+FO_ zIX?0qPrAha(rfEtf7%nDxLEnQKXx%cbFb{J%=n-CW*4h>?x9_b&)iSD7|*%4b}{~Q zpY39C%{{k^#hYCoDlb3zk+=NIXZ6Z+eB?i#bcz3My?pCm`d#f)f2`f=r?qGOw|1^y z*Z%eQ`h{_z{$hNn9~n35U&fQ{#+k|+fAV8o%D?fddW~c8F}}sqxEFupVf~A}_NjdB zmY>@5`oG$_dTamq%>6Cfckryg;9oxySN%)8+2x_~@{=EV%m3!{s#l)lBmeQFOZ>0( z*R~Bh&Ufd<^qud~i|Ib!sTXSx^Zk0Ub~4|!7i&NBy?e2CHQ&J(Yj5*?e6e;o-^~|m zpV_tB%4^U0(a!U)e^sx35g+{}p88Szul3i~#XkE47Arsd2Nv@)`wDJl#{cX$SghXJ zhp-r**`Kf&&)K)I82{PNuvlEP&tb86v&%!}{Ku0n@xR`0JZL<; z*3pZv_4VRw-M#o)k1xK~>5H%R`{HX|zxZ13FTUObEWX|kEWX|wEWX|+EWX||EWX}9 zEWX}LEWX}XEWX}jEWX}v9DDaYD&IYj{B%Dg|J@s@-tLpcr+X&x?EXpoyO&a2-B&5z z?D9}~`N@yGv#i#G73nDlb3zk+=MBKCgP^ zIX?0qPyH+Y`q$KVfBmcb9_iaXkaX{UNbR9}Bej$6lhl5?XHvWB{z>hvdnvWU?yJ;3 zvun4N*PipEo#$WsuU`EkKKe^M^{@ErU&Y1VeUHj_4;@T ze#muSCH~z@DX#9T6mNEUsJ#5-N8a);pVceR@sa;{>R<6U-{@SM=UV68JnuRO=Q-H< zIM2t<&3SHip3d`h&Nr>@p0l05^Ze~xp67Ds^*pb$dyZG$^F2SF`}sE?s9y7g_?SP$ z)4U@7<{QPu-g!6WI|s*4=i~VA+?;wlPlr$E?C|XT9sZrm6IbW;#G73nDlb3zk+=NI zXZ6Z+eB?i#bcw(5aN6OH^ZMQBxLAK2eHZJeqx)k0ciO{Z{d(HTV*P#E&tl`iw5!F& zhiPw%jT?T?U0*hyWH-)K-uROr<5K>Oht+F5jF0gxp2ofS8xM<%efr(jtNirG#r#Y^ zUCjUV-^J>ke!Uo<>FSvg@<8|Uqdk;2?WBBaKjm4wD*xJBx@d>#rF~}CZY!@n=SMrwzxH3f`bB*7 zmw4(&@z=kKi@kW2FAw~bAO6dmddnw1Te{QtqXzGAU@U-g>*Z!tbU z_PB?9r}C@U2fyQD{QsAK^hXzq>!%*}Zi~g6ef7G^%TIpfE&uXaz49C%`Hv@E;!m%) zeB|HWxGwwq<93yQ41D=neEDB|)w}rO^H}9Co{KO3i?6sAU-2%!^04^I&*Cd@>;KB< z;w#UKulz5*bXoq_cz8cPSHD|)^~c3mKV5wF-^EwIUVQcU#n(8n_!=J;U*pE&Ydl$e zjWdg{@n`WhE-k*stHswiw)h&~Ze?!c-r{RKJof2#r~LHC#n-rcD{~uf7hmJ>;%j_f ze2v?Sukn1bxSDTV$U8B0l;{ zJoTga>tDsi-gyD#J4e7z=L`7n+<|&KkAP3-6!7f)0{)$A5Lf3N#G73nDlb3zk+=NI zXZ6Z+eB?i#bcsK`X5ZIp$3FX}7ArsdsTT7y`>Ymk|NZ0}R`2Y~T01_oUu!X*vyW>r z{a%)YqA z{Lg;5#p<1Xbc^ws{dJ4+oPBqT@t^&8i^Vnj^cIUZyF650e)1!4`Ipb?mFM`#e>~|D zf9tQFU*`FZ|K|Ta7px0m9I=k*`C@(1b7$8b*Yn7Fr00}%O3yFrm+ZT)xyoDb z#2BJXT{(8tLN8c-|_z{zt4rs&*IDf;;Y`p7oUCZTs#+F{1;zw zExzJieC1*Bm7m2|-q!z>&&5}s7hm~beCcwYU+vQ~PPTu~_}RWb<7)f;jJNFrG!C~v z(D>ZGLF0D&361CNGc?Y(|IqlK-E*Pxo)`J?9Lc}uSM_@C#K-e1p62cG_xvg@_V({7 z-@ZP6+V97I`vBG3{y==%H;8BZ3Gr{Ap}5+ADBkSyPukG$nyKC4%r<0Jp^q)Ysb zhw~o$Jiq!Lp+EMWLO<>Mh5p-j4gI?B9r}CUL5u@^A2B}k-Nd-j_Y~tvcH>OtjX(J@ zF6G~NRlUZs_!!^fY21sy@vykqpLTsuQNHgK{Pg{T|GsOex9=VJ^c@7xzK`JFcN1~- zJw?3P<)QNOlOK7@zkF7&JjX}=<7qsMzwz+9-tx9DMZasmivHL>7X7sSE&6Z!Ui9ns z!|3nrlQ9mof5!OGz8d33`)!OT*^M)mH~!?uxRih6RrMOj;$wV^r*SX-#>3)bZ@-H2 z?PKAm{Vn{r??t`shry?PGI+Ls2LJZeh^zfJ;>|7(m6xCV$Xov9vwGz@KJp(=y2Rgn z{?!lt=zUh|ch7y%Qy1%x-}2}i)=yvf@~5m_|9!^aykY(NjURTy`uh+5+(&I0om!HL#|HW6mi!VNlFP@7p{)?};7GLo$ zzVfj6%Fp5}Z;P*dF23@-_{#sS%uScYmtMy{I-c^Q@8V1MTbWyXSbVjU#aH`Te6_2^ zS9@E0wZp|%`&@jr+r?LVUVOFl#aH`ZeD#aPSASW2^`phc!`h*KSNqf-Yq$Do?OFe= zo$J@NfBn6FVH~Kx7$53K#*O-y@g%!(rt-$0{1}(=Z@j8r<5+x*Z}Bwl#ou^XTqe9x5+C`H{E$%V+h=)|Fv`V*8cIS zU*K7P!M}bauKJgFv&%!}{Ku0n@xSKt+rQXrpUT&6`KdkgUprTC z?H`}|1)lX6{Od>Js(*<$yF650e)1!4`Ipb?mFM`#e>~|D|7$+Kak1Avm9O3MQ+wvW zcCOyqKR)#fJnJv`*N?Q!KQH*`&)72j|Il~buzKI` z%|CPP_&no7ZWzyJea;Qz|JwiahQ;;sFS=pzW|xP`%TIpfE&uXaz49C%`Hv@E;!m&Q zVt>=G`&-LX`S<#tZukG$nyKC4%r<0Jp^q)Ys7^TXSDSo4t1Cz_vhZqdA@^Ni**55LaC zn&))>(fp@#k>*96mo#7M9Hn_w=PS*xvYU5R-h3=S=4tsif2&^ey7-vy#nU`6{buNIt^8(6uj)0%e7x3S?1NC+u0iVt(;Mw_w)$2OfAg<0ktX`L09x5+C z`H{E$%V+hXqmC$bUTP5`XLE88_~?{<1Ecez(|qZTjP4>$vHsi>>db|1P%f zn|{66dT{#tV(Y{i2NqjD&iJs{x^l*i#nzkItwSqseVQNZ*8E$~R*eBNpK)^QRer|L#r({;x|shNZx^d~#^J^I%=o+*&l$HD<3Hp1VsXtlzgWE4<)QNO zlOK7@zkF7&JjX}=<4KqJ>tF5rqGS8P=-WOqy0?E!duU&ocG7+`?dPvu``NUs_NQrY z?OW3h+s~$bX4h^juRZ5SJI}xNU%mQ8eDs%i>PPX{zlw{!{b0(sPmG`TkMZBWGWE9K z44?L);o1H){M)xCuJ*HuH@iGkUVic;Z~2$c>XqmC$bUTP693!#`TuU`QFLs6Mc?LK zbZb+{3wj**s+Kv0Q9^^0Gg6!{#k>@8#OfXXZZ4#pXG4Pv&CtpSeGCv3b$l ztGU>GY3|!xY#ufDa4t5#%5L6OdGoRSn5X66{H=P;>*8a+7fUe9x>&t)ujyiZ=DyR#c+Neji}9cPQ5TDA?oC}R-t6*FdHKnYyyag$ zt5=@mBmeQFOZ>0?wRO?4^(K8=htj?EsrJyiRXb@ttNpaj)vj9qYHzKJwZqoS+Glp{ zw({C@ezf!aYyZ`&U&Kd$iKl)P|Eqs(T)ho~Ok^gwoCH}Yd^6h&i9sAx#-@XIVz3+qCL*EUxlfEZv zKYeG^uKNC{z4cvEJM4R<_L*I~t-SV}AMHH<+JE)x7xB?w;;A3S|F&Mf#l_zDKIQuk z$WPw~`R}`-di$P;Pv05w?E54BeU}th-z&wNT^=egKlzcj{L5$c%5!|=Kb~}nzy8&C zb2|1toxXi%r+eSuwTHgTYbSlL*M9nruU++hUwiAjzjoMu0PQooc3XMvIX~KY{#v|93T0QCtc!Cui|2FKeO`fbLOZ0&-}M9TD|R;#;1MM zc(%V9|Mp#rtNqyG%`Oj>m!JH|TmI#H{Y&a^YHkXpU2a@ zJ^tqN#l_zH9OZk@!%y#j`0u@tdV61lPw$cN?EMn{y>}8<@1w+|7(m6xCV$Xov9v;HN|@sa;{(k1@ac)0W4tKTiY z`s3oOpDw=o@8YXpFTVQw;%gjOe2ou_uW@7XHJ&WK#+k*}__O#Lmlj{+)#7U$TYQag zw=%bJZ}BxA9{cEc%8$N_`5E1BWp3l`V)aftS&YxLpT&4iyIPF@w713L>V1@Wv&%!} zPO2Ht+5Iq4{uj^W@5#Kj+81I{)U|)oUIeAM^8gnzzT_e17`Z*2`YJ z%9jUz$`AkLO}*t4pYn`n`Nuz9#Fbv+%`Oj>m!JH|TmI#!OG?``ho|Fy4s+k4gf4fDIT@p<3ReW!czeBRf;^S$`bx8<21-r{2a zZ+`q&w_fEx?M1)5n4f2U`7bTz|6RZ17Z$7c2mi>=FUIHBf9z)${Ku0n@uydDu|N5_pTG4g|ACMC?8W>{A6(4;SAN{5E>`cazSpNL z#^-&W^GS>G{D1z@({A?R|G3Zo#Kq#8F>x`yvdcr|{Ku0n@u%19 zBYM#Ki~YAA{V|J`fBz?b>|%cYr;qr!#r*%`pZv><)%)MR)yFT!=X1a1hVgut_x&q3 z`|y9i&$(f7J@d5ad{(bK$4CC-NtgK3tGL*I;~`#at+J|Fz4AGvls|MBbo;$r;2?4R7QxE}Z18>Uxwd8oYn z|7(m6xCV$Xov9vwGz@KJp(=y2PJe#l_zEuYAu1etKT;-*ZI0JzwzYxr1lV zBm8?#iL2+Ac(cnx<>e~88V{fQ?jOHce|+7GZ};Qr zr}HdWyZ-wFpZP_L_3QWkrDreJ-@oeZzI?H9;6=aof86XdKKzY8^?xlkZcO`FY&^+s zoTz2W^^ukug%yxaX<{7kvE^Z$L1ddOn+ z{^yT-gB#D`^T^-%weOT4Jm2AkuUd@%uif{`#p0SgE;b%!mxs#BPk!Vr|MFSA@*E%e zkEii4{u9$VH~Natc+$O(`;WKtt?&1>fBxP({nYL3>UTW*!|(mkANzp&aen&4|Khz* zdG-B^-{WJReD8za{)XpSaqlNS<=)zV_>cYNdyjtYeT!fH_y6j>cYetY@A~WS-|&;a z@{^DK>A(B*Q+}Se$Im;w{Iib#AAZBnJN5p_Cw{@<^LIYznTO}M{M0iK|Izcr#s0aE zx}9}Z{(C?8c6ODYmwwpeZk)&eCw<_bS*+f#e8}S$>~Qw{MGdf60%$ z$J(`r-~EMmU#y+H{Gm6j{e0XfzuVfitAF|1@48rf`??q3uy**=XWy{)nO(cBy#AFR z?L7b5fA#7Y@zG!6sUO8(|0*u_H+kRNw@Brm_=MZHMSdRtq(>}I{$F?Rk&D&)9&i5M zi}Cpf|MZ6OeAFY}=Vl-Nf9}(7SX|HhvKtm}c6q40{NzX8@-Ls&E6?$f|9H|R{`yyO z(Xn{xTOR0Mezb@3rk#{e?Wa6zSLI)OOBd}hz4Wi_+HK{v=lp2r`PaXySHFml{t{39 zDE|6aaj_S#^5ub_^22|5Q*Zgir#$0X{_#&2aiy1dv&%!}{Ku0n z@xPv5_x1dmadPoBelEVo)y3C%yZ9Q17hmJ^WBIwp?Zwx4zW5sF7hmK5;_JC^v)`T< zi?8R%`oEqpi?8R-;_G>|_1&2xFNc;~siSRN`bKl5B(yS(LJKC4%r<0Jp^)W70SukJly@A;*C&o6#@ ze(~S)OT9h6@ag%5XU{MEdwz-Q71#5NUfJcL^74}(dCR|iRXqmC$bUTPg8$4z z@BbTb^S$?8`@GM6P`?P@vF})Y+3)}9fAdXSX2yv7f8`Z7?0wxMzxRf{$9wme+_3k1 z&-&sU_TKM9KmLZj5B&B=-LUtB@BIch?ET^WKlF|3-+RTGM=$oi@i#y6_4YS-*bOWH zX}|FeTZW&Xd+>(&fALq`uzKJ0Z{09HZ}2fUjOXJ&^oH^O@IQOQ;>zxQUFE&U%a8Ya z`S;$hdc6;fkN1S}^!_mZ-YXWD_l?ENULKS$Km3$8{>!I&%QHUZAJ25bKfPwWKKA+U zdCJfC(Bo&mlOF%`{q)p3-&GHv`QCbX&Ue_uf4u)s<%Aj zQ~vQx7yQ#pT-n`URC)IoMhUslz%+a3;*<*IpwiCA6I$j=JMk_UH+Z3t6t~t z;^SOiJe}8zzjJ)W<$Pc9vX=+t%MU;0jsNng-tvr3`NuO|@J}ysWp_TV^3KiW$9cN^ zJ7-tD&fmqyxx9EfuNQyk_=?Nd63FGCz2oMNAmwQ-~4{3Ugu5X;~Yvnoll9sb1UiP zJWKJimj~s`4?pFN|MIEc@{CXU$1`2b1W*KK5P5 z(|+vu+oxSz_HP$2dwEd4{P2@r{FhJlmS=p*Kc4A=e|m{4yZz6Vw=X(B_DkpAKI-bV zzdAnlUB}aY?D*TKU0n8W7cYBxP`>=|Q{MP5pXx2o_>_M<(*^(ZnzhZb+y7j7`=aw> zzjXfXqpn{2tK(zebv*6Ij=z1{#by6?@v@f(<;xF0<&FRHsowI8Px;3)UGPsYab>sv zx$^c!=f{5O{M$!ez4lkf$G+=$+K(N7`?QP8{_WyrFAvI>AAZUk|K(G?!I&%QHUZAJ25bKfT12-T9r$JJ*vR=Y8_;98mQ-9~2+whT`cwQT&}VDlX@bikH1S zC|`c~DR2CzmwL-HKII?J^uj;AW<7uGejly!em5;Yeorm`erK(E{r*~f{4QHO{a#!A z{f=94`F*$IWiJoPmmhx08~^1~z2zC7@{eb_;GbUN%I^2kD(`pG^5gf^^6z)ns@LzY z#mDcm#nbP##ozC^6_?+4D_-{UpnUn^r@ZlBKGj>E@hSg!rWgL{HSbpLW&iv~{kwaW z|K5-MxA*e%yf6CId-=crM}FmA_5PLj{*`<2`L{3m<)hd4eef?Iy?*Jfe);J2R=@Y^ zqZfO5P`>=|Q{MP5pXx2o_>_M<(*^(Z5?A(@zV6?j@}K$Rzjpk5-9P;GkyID9_h3tn@0e&)}==J0>=JOAd1>yhvCnOTFoZ zPkP~*UihciylXu6xd-@^pZkH2pSd^q_@DcPPrY-`@ZmG}4PrU5urF?qvlV1F%mwM9+pY*~rz3@*jdp@$yxujEm&MO^1bB^iw zpYu(p-Z}Sl_{@2z!*k9_9sYBE>clnYs!qJ@>7{&n@snQsrm|O@R{>#hv%GYJN)Oo+lgz=!JT;7(@XjE;wQcMPcQYR z7e48QXS(2@UcLoppL=Cb`MGcQ_?dfXkN>%!_SE}_pYS<{&)jEwc+NeyhyUDvd*YgV zaZkML>7{&n@snQsrBUca@tP;_v(hJXY!9Tsk zm3_|ro$_-Y@c5Z?g2(@yA3XKWxx&L|&Kn+{a}M$FpYw?)t~s}O;$=@S<P;_v(hJXY!9Trxlg>W(80NE!Y94(Oc(sqOI+FKUZYcf?mIeu<{qTi`+uLGIrYxHNr%ter*wGEJxhoG+`n|< zntPc}yzJ#c`SQb0dE@`&bLuV6_>_M<(*^(6>-D5#_j`7g_d9p_@%wlA_j`QR>-X~F z<9GDp>G$>0%kS=`m*3+{FZT3OKE3!!FaFa@z3GKddf}Na_`hDSCmp-rv#Y${xyz5= zzdQctck!y%@8!kE@94$T@9V|i@9q_s-{UJ@_VS>7`QfL$@qh9;^_FLR%0Hgzg@1az z&EI*0ugUH_W96N5%#ZVr`FAd|dYzYyk8_mqbiOkF&RrIl^O(iUULKS$Km3$8{>!I& z%QHUZAJ6o{KfONn6W;o3?%3b|PWi{&@$;BF{vUIv-pAbG^VmB)AA5)YWADWE*gNq) z_D&uidnZ4Sy_2`c+{x!-?&SF~ck=(3JG#7odd+kBf$XE>1C<|rAIQ(>{y_fy4sZ2N zJ9!{J(|#U^=d`N_;y>-}f#UM}zs1X59+WRX{FFET%cpwFGd|@X&vd~*y~LG$`rRo% z{qgvje)@X<^E4krK%{=O*+1=MvdG|Qw$Nf(Eckfg6x(_No?um-0 z`=jFTUa8`8-&FCkmj~s`4?pFN|MIEc@{CXU$1}a~PcLz0cVAQG-Q$!W_dDg^y-(FU z^U}k|JyG#=e^mV4D^*f={4iVvAdt7@-zQG ze%xo0fA^eJulrBp<6e|_x-TXE?olZ&_p1~ydwEbkz4$3_{FhJlmS=p*Kc4A=e|m{4 zyZcEh@7|L9xX&d2?m4Mm_n*Yay(sZ?UrPMlqf%V%S1Dfh@}PYA;itUuUq02FUig%M zJktyR^qTho$L{xlD(`oK^5ge|@;~eGQ?K6}ijUtRil^Tviof42DlWfgRJ`ovLHY8- zPkH0Ne5$uR<5T|eOc(sqOI+Fg9#G}|PEdaQeo+4B{mH3!-m4rweupTYexE4*ez&N& z{GL(qvX=+t%MU;4#eex!Z+XV2{NtHk_@~!*z2)HetryH~2X+&5Lc?BzlE^x`MI_%EO8EzkIre>~F#|MU`9cK0<^-aStFalcdk z-TPF%?t_Ytd!pj${;2r7SE{(&H&wjs>7{)6;itUupI+)M&-j#oJktyR^qTkB$L{wB zEAMv+^W*ml^Y3>ItJm)v#%JC?AD;7G`tbKViN)pj6N{IMhUslz%+a3;*<*_W;K}-&s!i`TlbJ%y*gNf4E^~f1`+Ubd z<>&k6@iX5&kN^1|dg`6;q=(OZKRrC>yXxUT-&;>y^BwlY%bs4!rx!oz#eaIKH@)yl zFFex)|MU`9_WAC7%Fp-c<7d88AOG|H`qVq$wGW^9-hFt^cksi1zK@@{=DYccmp#3d zPcMGbi~saeZ+hXAUU;Sp{^>RQ93IR*`ve}W{OliiFh8@e;KBUQeuD?AclIGX7@ygn z@L)V=-@=2953`@)!N!f*=kQ?TA$xi$pI-c=7ys#{-t@vJz3@yI{L@QZ*=JwJDL?x? zj-S~Fa{SN!kW=sM8##PtKgrQ+_L&^LX8+02Yxboaz1Yix^5uu0^2UGpRBw64r~KoY zF8HU{>?1n%*@tt=&;Fd_XZGzJ|FfUx=r#L%j$X6>=jb*2f{tFZU+CyH`-qNS?CGU^ zdhwH9{HK?C(+i*U!ZTg)PcLz0pM6uO{OqSXerBK5@jv^oPQ9})>+qTVT8HQC<2w9j zf7gj?_I;gr+0#q;^x`MI_)jnOrWZcxg=c!`Of5 zXTRd{Gy52i|JmPo>YaU$htKSXJUnNg13)8l{kqn>(apX%W=`&SRo+1Gmb&wkev*X)Bm@v^6v z^6AA-dhwrL>P;_v(hJXY!9Tskm3{X8p7OIF`1qN9!pHyYA3pWYzT(4Y_8T9bvk&?3 zpZ&=vuGzPI;$=@S<8XR%s%|%fA;5}dS~DM;WPXB56{`>fB4V-{}b1o3pnwzr7{&n@snQsrl++@R{>6hv%H5 zIsE5*&53Ky-JE#Y(@XjE;wQcMPcQYR7e48QXL{kEUh|&q*yo(lDL?0rj-NS~bo|eG zrBm;mV>*21eAD4M=bjG#IS+N>nsZVoUiS1-KE3!!FaFa@z3GKddf}Na_@|e+vd_7& zQ-02i9Y1r9?D(JaWvAXbcXs&9d9=fG&Z!;#bAIi_HRsw+yzJ?ve0uSdUi_z*deaM^ z^ujZ}@K3Kfhj{Fdn%|SH{G9JQe&*cY@jvGQPrY+a@bH=QgNNswD?I$?yy1y!&LN(7 z+0#q;^x`MI_)jnOrWZcxg=f0ppI+k1KIbk^`8khy{LDGcBUca@t-btogepC=ij~7 z)$6|N__zl&7oO>Ye|m{4yZfjs z@1E-XxW798-|+NLIQ6>kIzH~fj;H&vrM9ZpnUn^r@ZlBKGj>E@hSg! zrWgL{HRtG$ea@ku^3R(4wDU9P){p-=&wlEibMA-FoPR$&=Un{ZKj-C7T<-fVUiR{! zeEH!gz4$Mm>MhUslz%+a1^@ICSN6F#;FO>H1dgA%XW;ms`v*?Fb1%W+Gxrr7o^y}E z;qPAG^m5;CdaMhUsq!*s)g}-|q-em4swQm`A&#L{*uzObRbB5is zYX39ro>lvzVfU=sFAckAb>3$#cF*d(=UnWbRr{`$nZJAXW5e!Q&F-Gn%DZPZKkix0 zzk61z*FCH8anEWz-Lo2h_u>{8yZy}SRo*^lm>>I}VgBulhSh7oG>p%@e_o8|yq8{# zzkS!r%-=oxv0?FMmxs#BPk!Vr|MFSA@*E%ek0)K?pI#69rhk02gVPR9J2>s&w1d+Q zPCGd5;IxCqNIN*~;IxC&4o*8b?clV7(+*BMIPJ2Fz4CGbryZPjaN5CX2d5pJc5vFk zX$PkroOW>9!D$Dl9h`P>+QDh3ow$$M`vKT}@7^20?yvSf0d^m?_Y7NR?xXhp0d^m? z_Y$!CsJ*X%-AC;`2JAj+?>FFi&iH+q#qOid?mp_uyN^0Q?xW7X`>3neebn)BA9Xz4 zM;(9nhZh&S_Xap9?|lNykM|5P|K2~q>h)d%#>e{#7*FppVEnz`fW_s#2Q1#~@=$sC z$&b9{-~Hj$E6?$f|9H|R{^>=>yEyIG(+*BMSY2`mryZPjaN5CX2d5pJc5vFkX$Pkr zoOW>9!D$Dl9h`RA#a?+ifzu97J2>s&w1d+QPCGd5;IxC&4o*8b?clV7(+*C%EpurH zrm+nD5|=adWPL9cSkqV6iv{0gKW32w3dd z<)rd*l^;3GzuZ=@oX3ZD@uXe+X;)nA&KIaxdFKvbew;^u`Jep>i`DD=0y{p=HNbc} z?*QZP90V*b=ObY8W|xP`%TIpfE&sHuUU`m>{Ku0n@lUUG6l3~|9Zowq?Y7LN9h`P> z+QDfDryZPjaN5CX2d5pJc5vFkX$PkroOW>9Wfyzps&w1d+Q zPCGd5;IxC&4o*8b?Y7LN9h`RBiQmhpefqtO+O6Nqs6G3=jM};1%c%YPy^Q*W-^-}K z_`Qt!k>AUxf6aHT)9?IVMs~lKQF*_YksrU8k$=CJQN4aIBR+mFBc6UQBmREhq`25? zx60R^`Kg`rU;9^Y{Q{r*3!e2O{Oe!hs^5t>yF650e)1!4`Ipb?mFM`#e>~|D|Ma5c zU7U98X$PkroOW>9!D$Dl9h`P>+QDfDryZPjaN5CX2d5pJc5vFkX_vizmv-!F2d5pJ zc5vFkX$PkroOW>9!D$Dl9h`P>+QDfDryZPjaC+%?`k?O`uyNJ*4p^V{9R${weIMB} zGiLg30_*#}r@+Pp-&tT|h3_x0F~oNn*x2HG4Q$NGZY-+2F)BaCuKXL*s@GT-A7f@b zjhXQ`W)>H_?;Yw@-ggj~AKyn{{(U!r)$4l-jF0auFrL1@!1((v1B=V|8d$v9<)QNO zlOK7@zcI6V9!D$Dl9h`P>+QDhJWiIXD z^wLhO^;!p61GYZ0Hf-Hw&DeU%TC#PPHD>ECYtPnY)}*c1tW{gbO?_v5XKkC^nz!=S z!uhdA&cC&D^;%QM$J#ue*5>iQ{eI|eeahbYNcq-H{Is6pzjc;+TYurxx(v_OYxuX0 z6Ibgy@n)BY%F9oF(*w1d+QPCGd5;IxC&4o*8b z?clV7(+*BMIPKuHgVPR9J2>sKx4ug|_Oyf34o*8b?clV7(+*BMIPKuHgVPR9J2>s& zw1d+QPCGcgrq1nyvkz_8CdN$npRnt*?nQz1W%s4P`nY>kV13{HDzGuZy(_S>!hI~T zF~mJBu(8GcEwC{syRoS9#;E)lyYg>Lt6pPWe2kg#G-k%%m|0xx?mtnl^6o`}`Eg$g z%>VDtJu0wz-LC@U#v|93T0QCtc!i z%oGs&w1d+QPP^=4ue_YV zX$PkroOW>9!D$Dl9h`P>+QDfDryZPjaN5CX2dCYZxwM1ROFJ>=obSckX3RyOHunIq zo1?lP05*4ZZvbpg>plV4T-QAVusN{%2Viq!_Y%P7%s&w1d+QPCGd5;IxC&4o+QDfDryZPjaN5CX2d5pJ zc5vFkX$PkroOW<}X(#%ieHySa)BX)upS7<8)|c(~*fKLd+Xn*c`}T*x#svFDU}J^- zB(O2WJ`>p3V*d$j%*k#ns=P5OKgO>78`G-SSQj5-W;~6V@i%4`7rXr%>Q&yp4wxVN zJz)Or1A*0Re+Z0^eIqcQ_LIQ)+h+oc%l;EsyxHZU^74}(dCR{svwGz@KJp(=y2L-d z=y(^W9edirX$PxI4&k(e(+*BMIPKuHgVPR9J2>s&w1d+QPCGd5;IxC&F1y$(FDG!? z!D$Dl9h`P>+QDfDryZPjaN5CX2d5pJc5vFkX}4uA?cns%PRu!b|6nfKdkJ&Y-dC8r z_8!BWw)Y$6y1n->2kw1{xpD7F%$a+CGWDJJD(2YP&AlscPM#lg_57Q|SFgE!e9Zad zX^jwnYlPxr@4bZby|3V>_Za;5enY*z_rRz3A$azlWY;*?dlhl@US-!rmt7tzFF*N_ zxBSaz^~!U6s&w1d+Q zPCGd5;Izx$dzG|fPdhm6;IxC&4o*8b?clV7(+*BMIPKuHgVPR9J2>s&w1d-Y>Z}j$ z9LbpZv}>NJ&o+P4mz&q=AL7}(5&!0s;%c5L-t6*F zdHKnYyyag$t5=@mBmeQFOZ=}fbLU!jaoW*0?clV7(+*BMIPKuHgVPR9J2>s&w1d+Q zPCGd5;IxC&4o*8b?Xow|Ogr|pgVPR9J2>s&w1d+QPCGd5;IxC&4o*8b?clV7({9UL z+QI3i-|2(SAHn*jb4jp1>%0=IFFVHs>*LNh!TP>)Pp~n;c_`Re;hYp~3~_!6p1*s} zRl&xb?8c(X8>8}L?8?6}t$K}h@i7L*)0i25V`g!&JC~$h<(*f8`Eia3=HK}ySiR0Y z!T2~21>@)ho~Ok^gwoCI0C}$GbS~*wYS9 zJ2>s&w1d+QPCGd5U@_7TPCGd5;IxC&4o*8b?clV7(+*C%>|(FHoWN-ZryZPjaN5CX z2d5pJc5vFkX$PkroOW>9!D$Dl9h`P>dTA&6VEY)2neA`XXWRFvFSj33A8((ezTf^y zV?z5XjTP;;G={Vf)7aAfOk+-VV^QUeQTZ`;<=>cAy~euu7z5*J%#6P=v$)vX->7{1 z9{FiMB>(M`RB!ty@o8Trp6$29zkQhEYJaA9v&%!}{Ku0n@lP*0 z-o+QDfDryZPjaN5CX2d5pJc5vFkX$PkroOapUpP6>-X$Pkr zoOW>9!D$Dl9h`P>+QDfDryZPjaN5CX2dCYZxwM1ROTW_xomYbOP3M?keb)IVSYLMT z3D(D*hl2He=cHg`g7Z_bvBJ43*ckE_bKVM`zkAMM!N#2I#-hp_qw-_y%D*wKdX07Q zF=ocom>GX#W^u7Q$E056oo|BqaqbD`-+3rlz0OI&_&7fW=>yEyIG(+*BMIPKuHgVPR9J2>rNG13lBJ2>s& zw1d+QPCGd5;IxC&4o+QDfDryZPjaN5CX2d5pJc5vFkX$Pkr zoOW<}X(w>++m(6RwZ8Met(*94J*BSJSva)*!mV`~&aKzP(mGCzt?$I1T}~=5SNV~{ z{L5|i%6WWf7f;&7pLWH?-ug)S)=m7hp5niCmU>%%;nTVd&(>@Bw~iB6>pSsgmxs#B zPk!Vr|MFSA@*E%ek0)K?pI+%G#`G0CoOW>9!D$Dl9h`P>+QDfDryZPjaN5CX2d5pJ zc5vFkX$PkroOan;-=!UU+QDfDryZPjaN5CX2d5pJc5vFkX$PkroOW>9!D$Dl9h`Pk z=RW(s>n)#u-mADLpWU<4{rRwGsC)Hc&sO*C!=AbB;fFno-OmquM!UBk_Uv|_KkS+A zo`2Z0KD#+U<;@N9W6qF&bBXFT$B2))M?B3{;%}}}T03@pqp;EH3x_!{W^@50#gn{K#AW<+FO_IX?0qPjkrlo2!V6j(4## zVrNe~IPKuHgVPR9J2>s&w1d+QPCGd5;IxC&4o*8b?clV7(+*C%>|(FHoWN-ZryZPj zaN5CX2d5pJc5vFkX$PkroOW>9!D$Dl-IlqugVRepf#=)dgD~yf&jb5k_x8Yiy3c3J zOgnMU4~&ERe_-6)3k2irz93jE?h%5;=zbws?Ahg{@^Y0QIn2M@Rp6&~R@pq39EH3v8!Q#y>50#gn{K#AW zX;;1S93T0QCtc#7Ug;>t^c6dtc5vElnM*r3?clV7(+*BMIPKuHgVPR9J2>s&w1d+Q zPCGd5;Izvw_R7l%oOW>9!D$Dl9h`P>+QDfDryZPjaN5CX2d5pJc5vElnM*r3?X(l$ z&|3%jw%+>4H}}>}zQwnm@{PWAmT&j1zkJhgUFKVV>ot1-TF2QN(E84vf$a7YRNfwg z{MdVte|r+D*ItGA*z*uidmiF%&qHysw?0z7brV0Wr}%H3rQX(G__Qv=v-KMOt>eVi z`cAyr<)QNOlOK7@zkF7&JjX}=<4KqJrxzXX;s&w1d+QPCGd5;IxC&4o*8b z?clV7(+*BMIPKuHgVPR9yX>v+(vCgt;IxC&4o*8b?clV7(+*BMIPKuHgVPR9J2>s& zw1d+QPA~mVA9PP3Y+QAJAgs^2R}j{h-8Z;pX3YHkr~bxbec%0r?8XH57Q)5~_Zh;* z5ceFy#uoPGX#W^u8*KTy5OyH^nA$9;n^ z|L!4#)$4vj7$5f*!g#vR5XRp9!D$Dl9h`P>+QDfDryZPjaN5CX2d5pJc5vEd7klO91Wr3R z?clV7(+*BMIPKuHgVPR9J2>s&w1d+QPCGd5w#=m+oL<_=wbt7?l{H}dtgH>&e`U?s zzAS6W_G?*VwvWr&v;AGxr0x5%R&77n)OYrYS=(l}=B>Q7aDJ?j^Kb23z1Gz6vDS{K zwR!xnwfV-y-aaek+keGR`?C0Nzm|I2$AwS(yYOt^7yj)B6Ic7h#G73nDlb3zk+=NI zXZ6Z+eB?i#bcug@(eW-$JNC4L(+*BMIPKuHgVPR9J2>s&w1d+QPCGd5;IxC&4o*8b z?clV_-afIkV^2Fc?clV7(+*BMIPKuHgVPR9J2>s&w1d+QPCGd5;IxC&YwEoAYX0aw z*fY`Zd%~WTPn_TVggrz39w_YD>UTn6&s@JB3VRm&T~XLG+V73Rp51s&w1d+QPCGd5;IxC&4o*8b?Xru#@^S*F9h`P> z+QDfDryZPjaN5CX2d5pJc5vFkX$PkroOW>9!Re))=!5gD)$g}&&iz!2_1U?%YO%gN z_gO90$G_p}H>~f^{a0%@Cd|E9i;Wd?U)Ew{$lRl~cs&w1d+QPP^=4ue_YVX$PkroOW>9!D$Dl9h`P> z+QDfDryZPjaN5CX2d5pJc5r%4o!bYe&p!z3o4pUzXM0bmFZcdXAMd@QzTf*sV?ysC zjTOD0G=}uv(%91bOk+-VV^QUeQTZ`;<=>cAy~euu7&GH(%#6P=v$)uMAEV2kov&%!}{Ku0n@i%6Qi;j13 z+Oek{oOW>9!D$Dl9h`P>+QDfDryZPjaN5CX2d5pJc5vFkX$PlW_TFcv9edirX$Pkr zoOW>9!D$Dl9h`P>+QDfDryZPjaN5CX2d5pJUizA~-qgKg_4U4bv9;mozSx>^+QY5P ztj(vLEVjm+_Osa9bK2F;wX8{}y)Cv@op!j`8g|;}Vr$#%*1VOs7S4|~a{jHItJj)3 zKGx>(v^F1&me2JrdNKR-$HmG|KV8hv^xwt&PrqKQ-s$g)@tJX8F`hF%EXIGvjm6@c z@no@hv&%!}XqmC$bUTP694p~<6WF~>}dz59jq=ngwqaAJ2>s&w1d+Q zPCGd5;IxC&4o*8b?clV7(+*C%>|(FHoWN-ZryZPjaN5CX2d5pJc5vFkX$PkroOW>9 z!D$Dl-IlqugVRgD^X%*XAJ4?@1@f%yz97%g?h*2A?S3K8-0mInEbcxc&*<(c^6c*Z zqN(rPYvfs<-5j9u<_7sOXUM;~MD?0u#K&AEp5`j?H&-bx_U;8zzWajs=^i2e|Htb- zG4*!u5I)^UglG2@;otp5;_6-_@n)BY%F9oF(* zw1d+QPCGd5;IxC&4o*8b?clV7(+*BMIPKuHgVPR9J2>sKcdt>}v8NrJc5vFkX$Pkr zoOW>9!D$Dl9h`P>+QDfDryZPjaN5D?HFYkYy+-%J%FOSjF805Ef0><6zsn4(%kMSA zIQSiB7&pJ~4CCx~pJB21J!p9T?)jZ)SnS#5r1El=A34mw+*Yrg$A=d2q+R@JS6u9V zXIZ_<`~78@AHT~CumAbIW>~#`#~H@Q?>obI`rT(3f4>I}&)+@26Ags&w1d+Q zPCGd5;IxC&F1y$(FDG!?!D$Dl9h`P>+QDfDryZPjaN5CX2d5pJc5vFkX$PkroOasD zHRn`+bJ4}u9Ch(EcU^qVX%}B}-Nn}&c;}GU+<5UdXI^~Gr59gw?8VpId+{|VUwqBg z*Z(z#UwqB&7hiM!#n(D+@wG-c_U38VnquwOT4V9G23dTqO%`8kmc`dvX7RPgS$wU1 z7GGs&w1d+QPCGd5;IxC&4os&w1d+QPCGd5 z;IxC&4o*8b?clV7(+*Cr`d#0bmFc^)|LuD;pM9rR*Y7{|_N^R;zH8&w_imi~4lb6y zkBhPI=3>t-CzY40{K#Sc<+gg|JU+CDC+*@-yW(Q+yR-6rkLIWE)cp7TTD^VO#;5Py zc=jC}|GtlltMBIG%`Oj>m!JH|TmI#9 z!D$Dl9h`P>+QDfDryZPjaN5CX2d5pJc5vEd@4I>0v8NrJc5vFkX$PkroOW>9!D$Dl z9h`P>+QDfDryZPjaN5CXSHJT+Q$6qe{uJzg{Vo;Er{AlB)#Z1rU>y9u6^xtTy@GM} zdswho{7x1uM!%m0i#@xXR9>#~BZv8y+v=6`_|PJrw2MFOii_RvPpMaVze@%4tX{uw1>@s)uV6g=9u|zh-^qf-<@d8-@n)BY%F9oF9!D$Dl9h`P>+GQ7e<>drU zJ2>s&w1d+QPCGd5;IxC&4o*8b?clV7(+*BMIPKuHgVRnsx#8Pyb|}-iQUBX{Qa(Fp zs;s&w1d+QPCGd5;IxC&E_>%* z(~dpu;IxC&4o*8b?clV7(+*BMIPKuHgVPR9J2>s&w1d+QPCNb1TCeAVHDJ#RYr~!+ z){H%0tR;KySY!4)vi9sbWlh@i%UZSP+SGTRchA^VYxCk_?|Gqo&k=rlzVP33N4-6d@aZ{)XU{MEd#;JA=bd=7%R}YmCqMF*fBCFl zd5(|#$CEDcPcJ&&#c9W$c5vFkX$PkroOW>9!D$Dl9h`P>+QDfDryZPjaN5CX2d5pJ zcG-L0r5$_P!D$Dl9h`P>+QDfDryZPjaN5CX2d5pJc5vFkX$PkroL*Ds_QB4n>6@Kj z(`P%^rZ0EiO&{+ZoW9@rIAcQR=8P4cr!$6h&d%7<`8#7yc4JZHjZyhAcIDrgR=vi$ z_!tA@Y0QkjF|)YXJHMuU=i2z`yc_?WgHvzkeJii?hSaoVw`9h`P>+QDfDryZPjaN5CX2d5pJc5vFkX$Pkr zoOW>9!D$DlUG~o3r5$_P!D$Dl9h`P>+QDfDryZPjaN5CX2d5pJc5vFkX$PkroL=?2 z+3&aSz?FIA7rkt;|GoE4KeU+7FZqSs&w1d+QPCGd5 z;IxC&4o*8b?clV_F80dH37mFt+QDfDryZPjaN5CX2d5pJc5vFkX$PkroOW>9!D$Dl z-JO2-QdpVUgSy!N&K}goe9nH|#p;@Uyo+&|{k@BEn|;5Fai0Cai^Veggcpl(_75)> zdv-agyj9!D$Dl9h`P>+QDfDr(JfjS6)uww1d+QPCGd5 z;IxC&4o*8b?clV7(+*BMIPKuHgVPR9J2>t1HG5a)-mPsj_8QF^cCo!Kv#wuk56rCh zZ)Ik$(Yyy(Y|qTRA6RTJ&Ac~QY>&;nPgrd4&Aew=Y){U-e^_j@|v~y+-l3*QmJI=Y7l8tNgrkSj^A7pIOZRyti4b-g%$17@v91vl!2L z|FanXc`vkBT=TwYv3Rq~L*?ZsKk}A;dyT4Bp5r6`@uW-q(~FLGaoVw`9h`Qsy5tZ} zJ2>s&w1d+QPCGd5;IxC&4o*8b?clV7(+*BMIPJ2Fz4CGbryZPjaN5CX2d5pJc5vFk zX$PkroOW>9!D$Dl9h`Ps=F$#MFa6G1Z@vNDgRKGQTghT;!})%+*qU*^D=oH`obOGG ztug02)M9JT`98JSnsmNfEw)yj?^%ndj`O=D*0$NLc`I)%oF8lC{98L$uQhdithM85 zZ61GX^WtKk?|REY`T4fBn4kF$xS0R>KDb!D^WAVUKJz_sF`o0CaWVe${c*9l`dt$7 zW|xP`%TIpfE&uXaz49C%`Hv@E;-6l0yo=M0J?-GMgVPR9J2>s&w1d+QPCGd5;IxC& z4o*8b?clV7(+*BMIPJ2Fz4CGbryZPjaN5CX2d5pJc5vFkX$PkroOW>9!D$Dl9h`P> z+QI2HbzW<|+wWC*CiXj4o|XN+m1k(bd*#{M?_qi7_B&ag#r=MkXLP@-<=NfuZF#2m zJIkK++06keZ*GtubB6qzOH{8pMtsaw;%TlDe{+?7UyQxqu~NR@x8kSYz2d*$!%}a* zlZ8*epM__?tA&5Rw9!D$Dl9h`P>+QDfDryZPjaN5CX2d7>3eupdV*wYS9J2>s&w1d+Q zPCGd5;IxC&4o*8b?clV7(+*BMIPKu{((m-aS3mTlAB6SIM?LF?_1U-nog3Dd-}5OS zvt{)0zwm80tnYvKn|$orjR}A7gc~+iy!B_@urcJB&%0q`%hSI4hK)JdjYX9=M&-xY zm49Pe^&0EqW6X@FF*E+g%;I8y?u(wfJeB{JN8d0%FMRn^*3SPk{^kv<_l+NR!}$E* z&wbRE!Sh?c@rLn#+;eVNTu=SN8y0VNd8oYns&w1d+QPCGd5;IxC&F1y$(FDG!?!D$Dl9h`P> z+QDfDryZPjaN5CX2d5pJc5vFkX$PkroL*Ds&N*lN-1(9+QDfDryZPjaN5CX2d5pJ zc5vFkX_sB>m6sDZ?clV7(+*BMIPKuHgVPR9J2>s&w1d+QPCGd5;I!K^mv(S^>390z zJZpD6*EeSm>SBGi^Q8K6=S=nS&Y$Z0ol7+)bY9h1(K%LQNatIPEuDKc=43Y(Ro)nt zA7fYkjcL_utc#B^GoHrG_!~2ei@kHB%6FcWpU#=`-}zJZb}kj4&a2|tIad5T-zu)o zy^1%xJXBtO@*{8gm(S{z=lIBfJn0hu^rGWkoObMK2d5pJc5vFkX$PkroOW>9!D$Dl z9h`P>+QDfDryZPjaN5CXm%VeZX~&*+aN5CX2d5pJc5vFkX$PkroOW>9!D$Dl9h`P> z+QDfDr`OcEbI$qw4)yO`bbbS3u{rAe2E<}>*ZIAS#pbm0I~t44b?5gr7Mlal?`|wM zH=f_)SZvNbztgeUTzY=LW3f4Qc60B_o0I3qTs{Bh@YQQ>A0Ko6cv>UG-x{H~*ys03 zwqE7ucT5)ZGrw=LnE(0Rlf~+t-$Pl9&-_lxVm#;fQx@YtzpJuXT=Sb9i^ZE=9x5+C z`H{E$%V+h9!D$Dl z9h`P>+QDfDryZPj*~MOYIf2s-PCGd5;IxC&4o*8b?clV7(+*BMIPKuHgVPR9J2>s& z^wQTn`}*A+bCrHi$Fs8E+3^hR_jf#7`&}N-+^GeLTDS-5<~NehukG$nyKC4%r<0Jp^q)YtMi;j13+Oek{oOW>9 z!D$Dl9h`P>+QDfDryZPjaN5CX2d5pJc5vFkX$PlWcClApPT;hI(+*BMIPKuHgVPR9 zJ2>s&w1d+QPCGd5;IxC&Zp&QS!Rb}MYhMTL+VA0i+XupD`$N>#z7ZVSPl8+fOmJ@h ziCEf~BF6Tsh&{WUR9>#~BZv8y+v=6`_|Pt%w2MFOii^Gd9?G{5grD|@tp97@hs& zw1d+QPCGd5;IxC&4o*8b?clWAGM9F6dg*uOoTKBuA21i~9z1i@?#DBC?cO|d+V0ac z*X^D?bKvgZGdJ#DK6B>o>zn${J$~lc+0DHxZ%&>cbM^e2!&k4leSFOM<7tf$e`|!| zV(%V2<=q7*c7D1ykN@t|Q*Za|;nV$lcy=!z{@vFnuI}*@Z+3a8y!_-x-tsS>)ho~O zk^gwoCI0C}$GbS~*wYS9J2>s&w1d+QPCGd5;IxC&4o*8b?clV7(+*BMIPKuHgVQd% z*efq5aN5CX2d5pJc5vFkX$PkroOW>9!D$Dl9h`P>+QDfDryZPL+TMj<3SVUwU;n%K z^11k`Yw^Wl@x^WN#d+}+%i=4>#aHZ$ubeEta<%x%;o>W|i?5t7zWUMPtA8!Nv^)0p zSzTJM{b~b?ueP!HYBP(kwzT+aV~el0w^&^56T8~#+OIae_-fmWuQtE<>I;jnKC<}g zJBzPAwK%=*==jn*`Yuj8_Oyf34o*8b?clV7(+*BMIPKuHgVPR9J2>s&w1d+QPCGd5 zvbRqx?by=}PCGd5;IxC&4o*8b?clV7(+*BMIPKuHgVPR9J2>s&w3|9x>pcixYrw_V z+Hmo;W?X!&B^O_7%*EH*bMdt%U3{%o7hh}G#n;+)@wMh%e658SUu)#W*V=jUwWeNt zy(d|Gy+2uet<8_U_0hGKU;DMjUwp0o7hmrL7GLiQ7GLiW7GLic7GLii7GLio7GLiu z7GLi!7GLi)7GLi=7GLi`7GLj17GLj77GG=gUE|!vX-D6*gVPR9J2>s&w1d+QPCGd5 z;IxC&4o*8b?clV7(+*BMIPKuH%ij7f?by=}PCGd5;IxC&4o*8b?clV7(+*BMIPKuH zgVPR9J2>s&^wQU^KDhhp_085t`fTeaeYy3NKHfS@-*5e8OlVzZtZ2Pv3~3!_Y-xRG z%*k#ns=P5OKgO>78`G-SSQj5-U_6bP@xR8*jf=hYk@BsZ_-Q@0{;ze`|IgmJ!0$HI ziTjKiT_#F}M7fkif(tUFkD zuj9jveDGnsdEz|`^mBz%^4bWl#4zR!fd?%ch+UxgTa{|T}AUKC>X zeJPB^_oy&N-><^hEhi_|Cs(#Z4sD;@+Aldb9$XkF?u;LIj*D{NPeOg)TS7a&&xH1U z&k6nd{uAQyy(q-#`%;MC_oy%~-><@WEhi7wCqK4B-fW+I+An!F9`bLTcrkw5F)lsI zy3;#3fprJ#4%Qv4J6LzH?qJ=)x`TBG>kif(tUFkDuj z9jrT8cd+hY-NCwpbqDJX)*Y-nSa-1QVBJNZ$v)RX9iR8$vpxqxn?4^xUp_ZN3_edn zY(8f~%szj@SbQ#pG5Wj;W4D}~Sf5kif(tUFkDu)d(;`o zUFYn)PS#;fyYEGXS?gZ+uywPXHSmgC7G`Zc>yW~%nNNFnVb;>eo?e(Ww&kq7tUftoe{^2v9mT^-5%g-!KJDj9jrT8cd+hY-NCwpbqDJX)*Y-nSa-1QENAT2CnvD(VBNvG zgLMb%4%Qv4J6LzH?qJ=)x`TBG>kif(tUFj=?stAqjXHjRjnDeMHrn+2ZuI5%;E2KR z#}S*~nkif(tUJs7{+;e9 z*Bz`oSa-1QVBNvGgLMb%4%Qv4J6LzH?qJ=)x`TBG>(2eo^%!+rr}0_WZ?x&Uj=o&) z5rgYMVsm{+%&r?5i|a|o=sJ_JTTV`_Pp)i-9NIp)wO?{>Jh(7U+!;Ua92e!T)2Q$I zjdonu(Z1_F`gI*hJgyIk({&^9yPjlRt}_|0<>bNokif(tUJqHXX=h}-NCwp zbqDJX)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzHzTEHP+&tDUWu58wM)|DYC#6llXG&jw z|CAW~UMjKqeN|%id#sGb@3%6>xc-oRF?P$ziS@~q?T|y;C%5)X&W#5b#)&)Q$DQM% z-0zK2pYKjGUfS_{rnG-&{oX76`n^=*@%yU8>GxQP-|x3FF2DE6cr7On)+axkif(tUFkDuj z9jrT8ca}4D>yr~$cd+hY-NCwpbqDJX)*Y-nSa-1QVBNvGgLMb%4%Qv4JGQ<0?8j9jrT8cd+hY-NCwpbqDJX)*Y-nSa+6t-&}W;>kif(tUFkDuj9jrT8cd+hY-DREX4%Sz*-{t&Y{U+DXCf7DgowA)I*BFv(Y{@m|zKW z_T-wAkif(tUFkDuj9jrT8cb5B{nC>Xo9jrT8cd+hY-NCwpbqDJX)*Y-n zSa-1QVBNvG%R1E^tS|RF-|vb$-}}mEeIG1s`kq+&^8K;I;Cp3>&G*d`v+tp0EWV$X zG5Vf%#%?(|u|B!79dc;<*9r9-TckihP<-WI8ca-Z6)*Y-nSa-1QVBNvG zgLMb%4%Qv4J6LzH?qJ zy|Ucn@O`t~`|v%q+!OKrw9#K&pLt*Q#XS_uxwm3{?zz|w_hM|Hdo=dTy&L1C4S#e%eZ`RE#tMEJXoLn z*baHKee!9)kif(tUFkDuj z9jrT8cd+g(_r0~cqg;2e?qJ=)x`TBG>kif(tUFkDuj9jveDGxx#Q zKK}W6e~LMCd|YAn+0%bsn0@&ZFWaKjiTU~47Z+yVpS$dqSNhp_Ho-NCwpbqDJX)*Y-nSa-1QVBNvG zgLMb%4%VIJjNSU=1lAp_J6LzH?qJ=)x`TBG>kif(tUFkDuZ2aD6GW&A;4rwy`c>F$TGW&k~ZfP=eLj0a-GIK@z&S^4pNc{e3 zGILA(E^0D!j^)fn)@P2g9p*0EXHK(U<~rkH4m3{YOyg(HbX=6j@4#li)Q{hXO{Sgr z-PmN>kKdC`rr-FT*<|90-=9q;&iGy0Wa5wCt4(HHZ}|QjlNqn&kif(tUFkDuj9jrT8cd+hY-NE{bKJ(gUd{6Cim}{Q# z3~DmhLgTsIWUi6M^Sa4gJDvTE8Sp$@Ck~Vyq1#(>ysbbA#b*y`K=UO!5!eh(2qg;2e?qJ=)x`TBG>kif(tUFkDuj9jrT8ca}4D z>yr~$cd+hY-NCwpbqDJX)*Y-nSa-1QVBNvGgLMb%4%Qv4FZMO|LAOu#O}AV2S+{5Q zWw&$oakqc=efJCI1os!_3il)C5ce9{C&yQRL{GwryYXZv;gr(gFA;&Fc=PWL0?cmHBs?stsWa`Iq(@?$&X&Gs{& zwO{gVJmlXv@nZb?!eh(2qg;2e?qJ=)x`TBG>kif(tUFkDuj9jrT8 zcb2=~>5g*U!McNW2kQ>j9jrT8cd+hY-NCwpbqDJX)*Y-nSa-0#qR+Yy?vQge`)2%> zbTa#F{FZbw`*Qs5b~5|;`7hWnnSDQgr#qQBA%4F*nYki<*E^XxB!2HZnYkr?2RxZM z$8zQ(>oZ5$4s)07GpE@vbDi-pXBsDSrtz0Kvy6-K_}%mDm-_MB-^sKSzmuMv?O(r9 zGX2KyswWdq{N8#pamMekCli1CK6^6bir@ZDX1tb@2kVm`+aYhZpZTo)l4s)~|Hg?I z<1cgO4$bkdukif(tUFkDuj9jrUc8N2n# z39LI-?86ko!vh8qGUdM#D;}w z^Kbrb`z)ugO;g|`sB)X$f50% zTl*#F#)CWK#GUb1cNq`mx4&hFWa?k{i^80IeaXsq;g&D8q>8{o%Kej{OY@dAEFL^c|@^75DGydvs)Obv$4rA9lIe~Qt z>kif(tUFkDuj9jrT8cd+hY-NCxEoUvPvIjtcDOcW`&_fK zU#?{t57)$ulWSte&owc}MR~lxJ^Q78yw^RMcH({S$+REuflsF2GnRR3GV#QFkg(b zatP}V)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzH?qJkif(tUFkD zuj9jv>oQ{BP(TCm@pp4Z}V7xzk%`E1-jN~X=YuT<)UySU$!Obl@! zDw){g{!}tC$9=10#uE3lk{M&%=SpVmmXj0flPlXHhqg~{?U$Sz5AKW;cgA1bm9bDB z_w}-0>c{=QWZH@QfXTEU_Xm^dH|`rI6HnYvOeW5_&zMa7asM%yam9VfWX5Ybd9XhD zu^sYe`?#}T@@zch-#GDN{Kehrc}=fn-RYg2z`DzApt^%~2kQ>j9jrT8cd+hY-NCwp zbqDJX)*Y-nSa-1QENAT2CnvD(VBNvGgLMb%4%Qv4J6LzH?qJ=)x`TBG>kigk)~W7b zeX-wht{2DJoU1tpjCb=Ub8Z;#D^BK|G2UaG%(-N|-#D3b%y{o{GUuN0KIA#H$vJ7f zCpnpO)p&n$a{L?bRZiyI)^g5yt5P;5@qX!K+KKm0C)0ksk2;xt<2}{M#1rqYPA1NHuXQr<$NR368CSdqJDKrXP9CgJ zer$)l**^KSU-E1`kif(tUFkDmNRzilM`5Xuj9jrT8cd+hY-NCwpbqDJX)*Y;`=ri}h zxDT7#40C4OqfBO>jeC^I?8|XKx73L_Gw$;yv+u|K-(=>5xG$W{ToLz+lbJ)}K5{a1 zOWa>hX3nvkxybs=QMSX}W&6x&_RCynJj|KK$((8Y%$bgh^0=R#{Zc>fvnSI|+<#Bb zIrHMe^c(lOvX6=_e8xQ$6 zPP`aDb0*`$W6QduTz9bUVEQ75uj9jrT8cd+hY-NCwpbqDJX)}7^y z-TLGN)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzH?qJ=)y30D%9jq_*JI?ju8Nb|SI0uYp z;gUHwjOPQBIcJRL29r6LjOPiHIme9W43jzcjOP!NIVX+h5|cSsjpr4UIfsqs7?U}- zwVZQa>vJw_JDeliKIhK%%Q?02aBgm#oSPdz=jM)!@_24D`=x$7yO>Nn@tkKe?Z@+< z$@Ck~g(eeEJTIC|obeoKGV#arrOAvdo;yuuyq1#(>ysbbA#b)%KJAx08xQ$6PP`bu zzVO(x?kLwCtUFkDuj9jrT8cd+hY-NCwpbqDJX)}7^y-TLGN)*Y-n zSa-1QVBNvGgLMb%4%Qv4J6LzH?qJ=)x`TBG>x=!4W1rh6$3(YVj+JiD97EmCIkvj} zbIf(W;8^Vb!ZF(Yh-0_=7sqt>JC601vj(s}YXjS1&0zbiCG3|qhViggF;3Ph#?M;C zaZ&DeOMSOz+HpIleYb!5b-y4U_ZQ-HKO%njFUIA5$9OF#57s9?wnN@*pM2Ucc{U#M zZ=85BetqGwW!+J(J6LzH?qJ=)x`TBG>kif(tUFkDuj9jrUc-S2cq zx$a=y!McNW2kQ>j9jrT8cd+hY-NCwpbqDJX)*Y-nSYOd+9{bLJLb=byTE+Wc94oyq z#xd0UWgJ_*kH#_A`)eGFz3;{`+WT=FyS-1xG2Q!j9P2G-4PbrN2DZbR!S-28*e`1g z<6*60oUB!hpS6nPqTKsm)c3v^?RdW|+pqW0=-2ye#N&N8;`DwT@q3?+ae4oa@mfwE ztWSPyhrHQ-=Ck%oo{fk68z)|jpS23(!eh(2qg;2e?qJ=)x`TBG>kif(tUFkDuj9jrT8cb0qqPIr{+4%Qv4J6LzH?qJ=)x`TBG>kif(tUFkDupIN&4+RKgKxYzna}R^&YhBJ^Iz6`X{i(Y-M(k-oJTb!5@rzp)X6%-e6YG;J+aZUxPj2m(oEr}=j1zapU)^QDl)rlW?USj0+xzAw z)6U=j_65nb|HI?AO{U)sw%8__csA{}PA1M@9<^06@jv@fg&EgL-`z6H8L#E!!TRLK zcF3FUcS9g=^nXwNh>rU_F1lC<{1Jxa@J6LzH?qJ=)x`TBG>kif( ztUFkDuj9jrT8cd+hY-NCwpbqDJX)*Y-nSa-1QvQBje z>yCYmHK*4fSc`gHf;FnwD_FaF9fLKk*Ed+}dfkIHu-8La8+)CEHM7@GSWA0dg*CS2 zti7$zn%s6+tJ^+nc>85-Z#x`TBG z>kif(tUFkDuj9jrT8cd+hY-C6E+72Q#;J6LzH?qJ=)x`TBG>kif( ztUFkDuj7yBJ+PS<0sMO~+{Ms@wh+SPR(Yg*TPtaV)nvIcg2$lBO- zBWq^YlhNN~oyi*8a@O9~XH9N9tkrFwHN5?@wl^Nu{Km;Sg7I^X;J7Gvoko4vZ?xmO zF59o`J^FPWNIb3&iPLo>@w=X6T&^=2ujS;y`sBxU$eZnFK5M_^*?7pmapJ}J^@Ycl zbw|1GVBNvGgLMb%4%Qv4J6LzH?qJ=)x`TBG>kif(tUFkDu!O1!%%nPX+V&nlT?XuRjD z)QPo9y#FehV{W_`E16?)ye})6V|2VnE16?=yk9GsV|u)IE16@x<*Wg$&)UFtSToo@ zYYF>hjbS{jRg9Chit)2naa@$gd&aU~>c_jbl4&R2OO{Og@xHQT`i=LPB@<7)-z=Fp zkif(tUJpYyYj9jrT8cd+hY-NCwpb(eLjJ6K=rcO3iTxG;t}CdRXH$s8-=S-515q4C^cGRM|< zo-mnXZain0%&|D0KTPHr{q@5NbL@`i6|ra6_*ttsF3RKC#q5{*@$6zU?Zk7Q$+REOekif(tUFkDuj9jrT8cd+hY-NCwp zbqDJX)*Y-nSa-0#Jl@6jxhc$?8OQWw_SsnHB(pEa`lr;1IrIGMH%eyTkM&YAb3&}6 zl9?-FeU;1{66>yH=9XBGB{Sz(&Rk@D<|x}??y`O6H2Y<)Galwl<7Cb>{(5eneNi6k z&t&Syx-^+~V!fK2?Z05ZWcrQuZ8Gu1x;L3PV?CTq{IO0>W?XTdHkt8SP9CgJer$)l z**j9jrT8 zcd+hY-NCwpbqDLta>j0basulP)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzH?qJ zkYnFdn7QS&6ALrvSk7EzedZ|JVeYbh<}~|dt}`CyOygwEG=Anx$3^*T-de^;{ki{B zn08*d`>Qi%+JDETh3WT>N9~{G#Pi%27ADTQZz@dum%qO-{%{ z_Q|LHl4s)~|HjFjY5dHYj0=w~Q-`rrt~*$Fuj9jrT8cd+hY-NCwp zbqDJX)*Y-n%Ne`%$qB4GSa-1QVBNvGgLMb%4%Qv4J6LzH?qJ=)x`TBG>kifz`x@tZ z{7ya0Ibi(OSTg5^@mtc#oHNGnZYOgt8NbJ!%sFQKPIofrp7HzL$()nM?|LV5t{T7h zog97eJK)Kj+gi>!uk|?>wjIuqZJ%>z`{kV4csSQKPR`AZpL27^MLEAs&lsuCZ_~rH z6Tg$5O#AWs>B;mPzpI{1Jn?($$;27I!=6n1@%!w_j4OV(J(=-ZP9CgJer$)l**^KS zU-E1`kif(tUFkD zmNRzilM`5Xuj9jrT8cd+hY-NCwpbqDJX)*Y-bw!OOM%yka?rt38J zS=Vpu%dYF#$6fES@4F6UPH=t5T;aNrImGoObBpUt<{ZnJi>%KaWjoAWw$Geqzsz;U z!<=cH%$det&k=H5l)Fx&zUw#Iab1_~*YzI#x(*~B*N4REx{>%@PckmonT*$R@?d@P zV>{%{_A{TgU-E1`kif(tUFkDmb=c>9p$=%bqDJX)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzH?qGef-?8S5 zb;}s$93hVB$*fW1n4ZkqHP%0+PMnX#x+s~o?j4WXKbbXftfP`y8^`)8nKg5)yON_H z)?>-6u`OrqZGG0{w!>Q8_F2Q*FKc__;T*v@IY%&l&Ji3J<*^3KeyJbp(q!6+^=dNh z$2vBdeq()`OgypfO(xD*4<{3Utdo-&SFE3t8L#E!!TRLKcF3FUbBkif(tUFkDux_pv z&^Vbhjh{KwaZ&F3xTx=Yx@gDuchSD@^`c+j_eDIu2aGsbNo zj9jrT8cd+hY-NCwpbqDJX z)*Y-nSYOd+@+%*A%(*aiZaee8E`|B*yVu|AQ!s7*=bC3H)7M>>T%Ak|*Z=hPWMcb| zt(Lot`swb4t0Xg)zdmn`DL~@jQ?EHO}N3e{vmHavg7S%|mj{Pjby$wqNs^T=Se< z^PgP3Wc;|pmmX!^>7AUwx`TBG>kif(tUFkDa2?}iuj9jrT8cd+i7 z@=coh&xLgd>kif(tUFkDuj9jrT8cd+hY-NCwJTdHeL`p@&bm|K$T z8a27DT}z#EK9XG5y2*77oLtw&$#u<~T-Vacb&Z`|*WSr>O`crW>dAEtpIq1W$@P3K zxt_-**K>qPc^n5P_2c-MT+cO<>p4hrJvT|N=Pb$fTqe1m<0LaK?<3T6qAaiHO3C#c zD!HCpCD(JVyaT+adXTA%KyqdT~sk7OO)QLZ~!cd+hY-NCwp zbqDJX)*Y-nSa-1QVBNvGvmAHU#~rLYSa-1QVBNvGgLMb%4%Qv4J6LzH?qJ=)x`TC> zb*ej9U+in_gZ?fm`=-B_%0BDwsIo8n`>O2Y{_ZOKzQ4!HoZ#=YGFSNft;`|*t}Ank zzxT?VV>xq?^_in=hq=r4nbYi-xz2c)GmVou)A*S)9T(;PUMltd9aY-#_f=`%-(96& ze~*=T{GC?f^!Hnd-`{m*T>joG1*?7pmapJ}J^@Yclbw|1G zVBNvGgLMb%4%Qv4J6LzH?qJ=)x`TBG>kif(tUFkDuj z9jrT8cd+hY-NCwpbqDJX)*Y-nSYOd+vd`^P$LIO^tk3z=rqBP=m){E@2EQ*rY<`b` znEieMWAS?jjM48SFm}tyiS@~q?T|y;C%5)X&W#5b#)&)Q$DQM%+~@hJ?{ogN*9r9-TckihP<$fPQca-Z6)*Y-n zSa-1QVBNvGgLMb%4%Qv4J6LzH?qJ=)x`TBWedaY5&+oYQ;`tHRWIS);T8-yZT*L7^ zi)%Zce{s#n^D?dl&8_EaTqE*4j%!Dr-*HXJa;`O5pKDOI!?h{f=bDxMaxKevxW;9i zToW^Xu8DbmSIhJKsMgQ(rrJ(&Z9lp8n_T0`^RgOea*aQ^jw`v2H@W5^x#lOi<}KT= z`An{PPOkY+u3j>Ju8Db0*Rt;Lt2j9jrT8cd+hY-NCwpbqDJX z)*Y<7raaH@bVs@FVBNvGgLMb%4%Qv4J6LzH?qJ=)x`TBG>kif(tUFj=?02j=z243_ zg4f|$qk4UwwX4_dS<`wwpS7;n`B?*d{hzh5_XSupd%u9SwD%EMV_VMJ+xo1@ZHKkG z?X!lrU)J`vewO@%le;dS8I}yj9jrT8cd+hY-NCwpbqDJX)*Y-nSa-1Q zvQBje>x=!4V_!TMo!?>MnCSPlIac~TZjPaTznf#L-}~m6>-WJq7W+MMj?sR9oMX4& zE9aQ*_su!hTh1E5`m7CXhc$!kvzD-5))>aa+QT?ms~A6P6~{&StLyj8sqgo=X~*w( z)4t#PreD7gPCR~3oH+gdIPv?va>nKN%^9!dj9jrT8cd+hY-NCwpbqDJX)*Y-nSa-0#qR%|`^~;y{yK+qQy{{ZAeIG2xP~Q{F zvDNp-a?JI;vK)(j-z>*y-$To>+xOFQO!vLD9P2G-4PbrN2DZbR!S-28*e`1g<6-S# zoUB!hpS6nPqTKhsQs4K%(vI(mrG4KYOTWHXmUw*MEOGiCTH^Qpw2aI5)-qnp$%FOD zkL{2*+b5s)OP-B~{2M1;jGwg%j9jrT8cd+hY-NCwp zbqDJX)*Y-nSa+8D-df#Jt~*$Fuj9jrT8cd+hY-NCwpbqDJX)))I7 z$G)4NxCi@v-bZ-v*}Ermto-Cgg*k?P;NM?f>cqO}-~$VD%w2ZP!W@gQ`1WpDhhy|5 z7Z&E&z16!5b4=g;ZG}13Th1E5`m7CXhc$!kvzD-5))>aa+QT?ms~A6P6~{&Svri~v zr2Y!OEKEDIUcP6>O#3hSm%{Y>nMdxG<-~K>wuOmvg~JOI|FNePW?Zj6t1#oWoIF^c z{MZh8vwhYo_Di0Phx{8SYe?hQ7am)t4r8ZWcd+hY`XYz0?qJ=)x`TBG>kif(tUFkD zujo#l+(`s4)G9jrT8cd+hY-NCwpbqDJX)*Y-nSa-1QVBNvG%R1E^ ztgmLj8@u1d7?bN~lWUu$PT5Y9YYfRXw&WUfave)@9b;9Eo-A&44o1D~-{WQ651IcyUNUqyVa^04a>o%5Lx4q=LO(xfEHMwrX$#vUK zuG@Ta-4~MUK9XGbol>XlQ_0ocxbc`=_swM8QAc;V4ODlq?qJ=)x`TBG>kif(tUFkD zujo#nW*KJH-M!McNW2kQ>j9jrT8cd+hY-NCwpbqDJX)*Y<7tW({= zx?^AC*ynM9W1`0kj+GuqIEH$B;n?bNhhwhCBaX!$r#MD?{NmW{agAfT$2*Soma_)1 zK5GNpVa;IstR?K1HHPu9_ApM?D#p)R#c@&Y@q+puM`*|63+;Q{pkif( ztUFkDuj9jrT8cb0p+(;elygLMb%4%Qv4J6LzH?qJ=)x`TBG>kif( ztUFkDu`(>^(9_CErWX?2x=1j*$xxZsYeShDIcKqEd z+V}Uc=-1!LA|8J~i#X$b6ge*9_xH9Km%qcscr7On)+axj9jrT8cd+hY-NCwpbqDJX)*Y-nSa-1QVBNvGgLP*)W4Asz zfprJ#4%Qv4J6LzH?qJ=)x`TBG>kif(tUFkDubqDK~@s9CYP9CgJ zer$)l**^KSU-E1`kif(tUFkDmV3O@9p$=%bqDJX)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzH?qGdIpScg- z{@B?$hcjn>_{^szv(J9{nT6SxKY8V>QYYr;6ZbF7zQ5XPg_#p>{N~K8!(8#@4;N+* z+5P0g%q_1!t}t_s<;+FaXO6NR<}TZ3PP1R;I^$u^G*0GB<7duvT$FEnY#Af-&kif(tUJpYyYj9jrT8cd+hY-NCwpb(eLjJ6K=rckF|% z$JjSrr?Jnveq&#DUB^D|dXIhIbs%$s>qF)W*Nw~}t|ysWTxT-pSk7EzedZ|JVeYbh z<}~|dt}`CyK;vZ2H2!)IDEA%8U8hms^&9QDuA_a|d-Ur%ka%1l5~u4%;&(mCxLjv4 zUdzdY^~sOzkT=^WpY}_hjfeajCti$SUwCX;ca-Z6)*Y-nSa-1QVBNvGgLMb%4%Qv4 zJ6LzH?qJ=)x`TBG>&|l5nYyD~cd+hY-NCwpbqDJX)*Y-nSa-1QVBNvGgLMb%4%Qv4 zujn(`-$kX4zn98q{T)@>^!HWi%imok27iy0*v_fH_e#wEek)_~cU>8yzxT@6Ehi_| zCs(#Z4sD;@+Aldb9$XkF?u;LIj*D`CFO~ZKjwM3>@2=9XzsE{E{!S}#`unZK z@9(-YE`RTp@mfwEtWSPyhrHQ7`Ltj1Y&_)OIPqfqxMN&;ly#?fasulP)*Y-nSa-1Q zVBNvGgLMb%4%Qv4J6LzH?qJ=)x`TCRxxe?SJIZwj>kif(tUFkDuj z9jrT8cd+hY-NCwxKIO^tD!%uX&-y-C+VnlK^yT|wiNW{E5}WUvC1&44%UFCrEo1b( zwT#_za$mA}_^Z1d7v;Y9mHNI9mUetkEbaULSo-z7vc%*2 zW{K1H&=SAzr)6Bex0dl*P9CgJer$)l**^KSU-E1`j9jrT8cd+hY-NCwpbqDLta^G94JIZwj>kif(tUFkDuj9jrT8cd+hY-NE{bK9hG{`Oq;;oe#aOFrPi)SA}Wwj6Dv^I`nnrrwS9p z#((z4EGM>u=N2aB6OJg%Sbp_)g&E^_&MwT@Ehi_|Cs(#Z4sD;@+Aldb9$XkF?u;LI zj*Id~&3i+}N&R*IyfE#oc=aJ!PWwMRs4)G$Y3;(qGy1QCvkq~t_ld&9f7yErGp?)u zwlL$hoIF^c{MZh8vwiYuzvS6?$iH#o#rSc@xb!INPVeLd)*Y-nSa-1QVBNvGgLMb% z4%Qv4J6LzH?qJ=)x`TBG>&|kkif(tUFkDuj9jrT8cd+hY z-NCwpbr*fsYnxxa9Om47#+lb7b8fiOa@Qqu&iKVGzggp#U=4qe!b~5Ll z$6fy2WX?&SFz2RZ&Q;&{w40MThrRjG!kpV$&N;93ITyAa&XH}Ob7%YIoZ5IeH#bhs z&5gfYi!S4$eEk!@oH0;;&Xcc9rk#_%`-S9e|2Lmarr*mB{&X_&d}Y6JGI4J9qsxkif( ztUFkDujUDm1YV12pY`TLBx^LHEhtiR_-oBqxtefj&3#Nh8j5}Usl zNzDF^WV)-r_sSUk-N|%U%gKrL$(8MpL)#~}_Djx<2Y1GaJLAWllN%io=3yq1#(>ysbbA#b)%KJAx08xQ$6PP`aD z?iiOIW!>qWoWQz+bqDJX)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzH?qJ zx`TBG>kif(tUFkDuj9jv>oQ{BP3W544by4Tyex9)X#?zww?o_q0L zx91+c*Ymk|?{$9e>3jX3d;Q)Q;28k#7w~L=_Yrtzz;d1?us+Wi*bdJg*gnrB*e}m2 z7!S`d7$?s>7(dTEI4;V)4o`ir&(n_A?P=fZ`Sj~`e&X@^KXH0rfcU*%z_`4Rz<4bu z57s9?wnN@*pM2Ucc{U#MZ=85BetqGwW!+J(J6LzH?qJ=)x`TBG>kif(tUFkDuj9jrUcy^o+f%5?|p4%Qv4J6LzH?qJ=)x`TBG>kif(tUFkDu125d1W&3 z#QA12amIOQGV#axX)@!A^VVd>YdLwaKKZd7@@D(w(|*ab@sNMx#GUcuj&bQxrVeA* zJ2`=M2kQ>j9jrT8cd+hY-NCwpbqDJX)*Y-nSa-1QVBNvGvz)P8pPazDgLMb%4%Qv4 zJ6LzH?qJ=)x`TBG>kif(tUFkDu+LD>wDTcM*H4%j@`bGonyN1Y3EpPIcosxvo^3D)(p1KTEc!=V;B!>594I5V*IRC z92e!j=bZY!|D1MwFFNh}zI6KaJ?g~c`_+ll_pTGa?_+0NzNek>T23CUPkwBNyxBha zv|sXUJmlXv@nZa}RTvi@Th<-rx`TBG>kif(tUFkDuj9jrT8cd+hY z-NCxE-1oHWj&j|>x`TBG>kif(tUFkDuj9jv>oQ{BP(@^}~bfbx1f z`=;07*=M~z&%W$+d-id!=d;KFZ-WOmF@qPhwi}w+jb1Y{rvOaT^?J#%Q zK69G=GS?XobEa`JXBt0qrsJaA>+sa~`aJD;-JbTno=?AC=O-So{}ZS81&H7K1&qu4 z2#nWq@?d@PV>{%{_Q|LHl4s)~|Hg?I<7dufTzG6*ca-Z6)*Y-nSa-1QVBNvGgLMb% z4%Qv4J6LzH?qJ=)x`TBG>&|lTBj}ED-NCwpbqDJX)*Y-nSa-1QVBNvGgLMb%4%Qv4 zJ6LzHzS!@$w&{5g*E~Hx;##QZOj9jrT8cd+hY-NCwpbqDJX)*Y-n%RRr-9p$=%bqDJX)*Y-nSa-1Q zVBNvGgLMb%4%Qv4J6LzH?qGdIpYDTsZox_pv&^Vbhjla&BIWEe5-h=u+ z2SPhOA42;+H$uNYPeMFCXF{Ale?t5|m%_MwUWM^mP9CgJer$)l**^KSU-E1`kif(tUFkDuj9jrT8cd+hY-NCwpbqDJX)))I7`=IYbVBhpT3GB1JKY@MO z_bRZD`@RMCec!{toZ$Nzm@9m519OP)b6{@qJrB$|mNOSwpE=5Qn7eGBIn92V>x_pv z&^Vbhjh{KwaZ&Dj5~%O{6KKcxD$u^~TcBUx!$3T~pMf}iZv*lBJ_p9-dmb3C<>bNo zkif(tUFkD zuiKvgLMb%4%Qv4J6LzH?qJ=)x`TBG>kif(tUFkDuysbbA#b)%KJAx08xQ$6PUcMGXU=3?cx;(EjGc1b!McNW z2kQ>j9jrT8cd+hY-NCwpbqDJX)*Y-nSa-1QVBJ~H*sbq-jdVx3?qJ=)x`TBG>kif( ztUFkDuj9jq_+yZD~k7^Y5q*D0CL#`nLHX*0eTmP}vqeX(R>i0_dl z6I*=0ESZ?&duPdvCBBcA%oyW)YRQbIrkMHXx(@uPkFPZk^`+dpu8{hj&CZ6~{U@~#W_XLxPKfXVh%(&uv^vR6Za`Iq( z@?$&X&GyNs{gP+nA^*mS7vskrkif(tUJpYyYj9jrT8cd+hY-NCwpbqDJX)}8xZ zTuaSuhC2S94xjaRc4*Vz-=VK})Zf1&hCAx--w~U?<3r5;z7J#ZcYhe8zkkQrEhi_| zCs(#Z4sD;@+Aldb9^4rx?u;LIj*D`CPlx*c&JOMP`#ZFMLH+$Z`t|pEh{xaYAx?ka zC%3)&`*)1X-vi2RwU(0y>ysbbA#b)%KJAx08xQ$6PP`aD?iiOIW!>qWoWQz+bqDJX z)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzH?qJx`TBG>kif(tUFkDuj9jrT8cd+i*@3^NB_g-_q;~tRD6>|?F?onnr_a=M}nR^yKpUk}spIhc0 zhtD%}@5ASuxhLZD&#{e6o{Q!lisjr}u|D@)Y=?U>w$D8p`{mw^@o-PaIJpO8{M-X_ zT$J-{E#sv=&(^}U<8#Qg@AJv@>vPM*2uD+@AJ=$%jcpQujS;y`sBxU$eZnx zPx~d$#zX#%6EDWEFFdxaJIZwj>kif(tUFkDuj9jrT8cd+hY-NCwp zb!Rzaw>~+6bqDJX)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzH?y^pG2kXoI&iAzA&i9=2 zS>Jz7o4yyFzIkigk)~W7beX-wh z?DM$5G121%$4ZYQ978?6aBTIs!!g(65yxVWQyil`esS#fxW+Nv?*VbFx12SA^;sL( z4r>P6XDwmBtTBv-wTE%CRxy6oDvpbCj~CSUI6^xfUufUs4*hyOA|8)Z#Od*i_&u&M zE{}JN*K+b;eez>FapCh=gXOio&GMRljwue%utc#M__hb7>W=@FhDw(+=wzp*Fkk}5BnOl55 zlR3w7<|6AeN7)W@m+dpB#rB!)FxMFmb6{+rS0z)KTW2c*ng90 zKlbZn`i=cPnRsFzNG8shACieb=8a^=<@1@0*K+b;eez>Fkif(tUFkDuj9jrUcac6yU z0_zUe9jrT8cd+hY-NCwpbqDJX)*Y-nSa-1QVBKY%INlk*zS!5er{I3ay#}{i?m@Uc zb8o`!oO>2-|J=)Pzu+E+`wRCz+>f{?;{Fx=P4+wPp;*qn73*`)#df$CWBc5rv0v`p z7!UV!jFWpn#?L(<$3?mO9rfLwX~*rH_TB#J*ZqQc++T>({fPM8zZjSM9pkl}JXoLn z*baHKee!9)kif(tUFkDuj z9jrT8cd+g(ce~Xc<+_7)2kQ>j9jrT8cd+hY-NCwpbqDJX)*Y-nSa-1QV0~@ytdnO< zn|4e$E&g2l)n|=%U+swGEuM1W=o6>BE;;_GyY8Yrk}o@XdUxciTO{*e{y(3s|DMd} z_&nvbN4qfneDQ?u&4gO?=3J6`HLUfRhxqaWH&=D+-Z zJ{y0CCz;RDABD6>yYS3;SI=|2Z64bEM72rY+I+ToZu8%IX?>BuGdA7sJo>HWBe>R2 zuI+S`*Y=ZZzsd1W#FJd(Os?@;C#p@h&&hb(JVb>_e%idX`K- zYvQ-Ild;wIlWV`mOgzao&gAMVd9y!xY5%op%lE|7@^An9x&5zy^z z%o{y%l~TXk?Y7ZIo0fLgyJ5BNv=_Y~>mPsZ^SX6@zJBt5%ztUO*UgVfe&_f1?XF$r ztC_3oKX+)i@zuxNgO}!*>pakr=ax6#V)po;!^>Rvl%LHTpT5lNv(Ag>{c^nFf4w64 z!mmE1zu{fmCZGSSP5Uojyk7D}Kis+Ba+NH1gou4=)`Si_? z?mu?tKg^-uYkz%I|I&*tnGbLL;Y0gxpL%TO@Hr>#+i!5e)yeHP(DKq2=Ls9{(f!re z%Y4=HE2qD2AL1 zlo2_(;wyW1mmYdU@=vaRarfeXczot|ufN*3JMzp8?!k+rug|~kW!;A^eq{F5@~2K3 zb$k8KI$3`1+||3)_TDCWg|&Y@`tGyKcCyQ*9~y0Y(Scch(3UoIl|>F7zH3;&{<} zyolpS?{OrKFTKZ?IPQ!+?!@tE?C~g$Q)7=)as0Z><5wKlMjqGVcsKHR7stVo$H6#0 zb{-$&7}R;(T-Y|SG{@X-11-mVGIl+Ci2*!0hr zKCL_Zt(zsU_>n*DZhOgY$y*&YfApgNI3T&-)8Lu?$uap1!<*W4j{O{c4SvPLdzvofUOpbA}-o6Jv*yFEj z$jozHTPD{vXRfvCS~S;Sb&Wd4QC+(x*EMZVd0p!!*EMi*T^lFYHFI)ZqbBot&ZEkI zr%ldDm$o?Tb&rg*<+^^$^17}|uIs(zx(-aPYq{jQ*188jkT#jWnRm!%%gpi2^^`OB za}0nvCU9(kIaYAYfH{UR@5Al>+wuczGuzD=vWo@V0R7!dc{!)Ab-VIk{`cO?7q)J25t_hRtS~0nphmmF|PL*7srm? zV;|diYzOC%=awJr@yEQ;J8#5%(mS8TJkvYR#Qf7c|HK^9J1@mP)i-n3gda$ov`4#S zx#ha<&GNb)POj_ZCJN{&~)UGai0afBvC&=G=J8pB&O}xBq*`MDq08|GIzr?Kj_pmxkELS*)w$UIl*^ z@Z!F%UXNLs+m;u1zYBA5+(p~>(;vBVPZoYNZ-aidmv5Z>+|yU+pZAU(lV5q)H^$$) zai8QbT>Q52-~aO)l4rl_Kjv?I?or7zZaHqwPYx~Dz<1r^)uaEM`Nk~2aM~9~>wf#y z$rtVOsP2b%?UMYPL)Yy_E0=ZD>*jCMz5T|gX88qszoOe~zhC7x^Qx;3>^`_*Sx0TS z{}J8I?^`F!TVL?@XP%JvL>`P|S(ulFl{4O7yy)!7`QUwX*}nPT^5>p&MO)t9XKDHO z-D}(D(zVa0jrN{St)ISXJL$K*H`LxUijPn3CAIgM+IwyF`b@SnbKbiq=QvASY;BxN z;-27D*Q{awC-;08c2BV0AM5b7G{^Qp?p;3XY3**gE|^ z+&A^_lgVA=kb3pc@8_DItl#p(Zr-y0yM5Nm@|&)DTK}HIHcLME8IS09_?ummSG@Ie z<2{etKly?aUNxS!LpgRl;TOlxzwn@POnJ`yE9M;V`EsoJ>2Yrv{b;L0v;NN8Uo+b4 z>H8*sbCcz}XMO7>$+z6~^lq zcOQLa$EUihR_V9-P`Rde=?DJ2f91~4%JRowxMTnE{Z~kS>o)uJrycpN5%u44^CA85 zuYX7Kx@#TP-}hxaF5GdJ_R$sVum|MeXgC%4;7%S&6F zkT_Zp+E!xZ+-L2=KSS3Wv*W3@q3PTzNO6JH~p#~?XuGW z+0Lq0|7myLoZXVwxMNng_WI@8;I$`h+5N-SLw=uNOiM7v|+7u$75d%y2|B<6_Wxy0uA)yU`M zxmNO5olT4UPo9IV=P8-nc8(?2?t_E7EplG1=O)SR_W%2iK}+hH($-zrK?-f_$v=FDNv9Ole?{${vWTc4Ax$BUdNhdFbLoF|9# zyW#wTt^U#Xj z??l8geR!XFBqpx0lbg&>ocm1PdtaX|%yRy{)*G%x57(k&a~Qs_M-qnP-SAz@Va_bi zcg1?8eh+Um&CQ} zd+WE2Vc~pC@9$I8YgYN3&*Hcj6ERMHTM#FItbPwXWi8(u+}{_+yFlYzt!3K^kAIMN zQU1Q`gy!Ur)oFmByL^EZ3)I?1!<9XdYn^Q$G__VA0x z&;7`wlfU@MTgLq5v!(3fWa{!6%4vhPVA|gL{coHB^Eb-pSRVC9aOv~nWZH@LlW9Nx zcGRKI__t)@iO(d{XY`R=`%K>Pv8T^#%I7roM@>7Uru|XVZ?rLqr)%Qun)tg7zjDV+ zVvE0&J6`IW2ii%d&n9nO$z6_%cxWU3UOXzf*oa(?8ZVhM>MZ-wFP>BTe8{?6_M=GM=yX@rYef&-4_p75Q zncpss&*bla^81JUCMNay%}M@S{v1Pj{{AH8^g%iG<3CxCcIbn0+OK_NzxDT#`KP{q zW*TkSM`?S(eAJYWn);)rovvxWYx?czgN~wZ*TmU1@porzT7I*dTsGsSzImV>{$@K( z-sm^WDWebS#GfwWOs0*9Ke@DhjCH2%wfaBJ^E$F zpK^Y~v8O!y2&O)LWNgt6eZaKOUpUL+-(c$U8JIRoAIJ2xO&^rgV^e-^Q~z9It?kTf z+Mn0-JFkgnUK8iMCjNQf`Q3@jmv;V%a>q-3^FTZEGM>m~lQ;U!@+@1B=XnulmeWSW zpG?~ebJxr>9Q)EK^LKNM;MkYt%-_v1BIj$i0p{=K7%}A-M;@K8n_~p^Jx0)u$A~=6 zQJ>>ObBrLKsF%kGj(y3r(HtZ4_(L7~Y|1(IS%1p0rfHvJU&c_zI*F%i;+%4fyJqzj z&a2~^a!hRU(6z_VCT|@3;@>96zT|rBOQwy+%bXZa-|VZ&@jI@ujg<05<=t1iBj?s@ zzxwg{pE%`b$y+?-8S&p6l4Cm?AGzx1lP^2@oH2jtmookhrf&Jn9x-S9Y)o5})Aq^B zed*j9XUw-BpJRE{AHmd*c9Lo55oi2k@@g}$7{B2B%aZ?X^$W(Ye9JY-Q?`+8H(NkD7i*O*}D= zPU0N>?{d#8@oe|g(Oa*-DaZAl_uf8Q`7x^`e|np{;LHOYb&{zQpB*#yaeTJP;i$>& zsL6TsGjS2ej)|j~lPB)(b$f^$@aG=e358Ew^A{PzGTqG4Q~va-6 z^0)8s^(l2udd2_dSk7GMHw&%5`|7hZ53|>}YoVWA_9NTH*!JjFf8CEpZC~wYcY5VV zv(7#*yL{C4+kW<0GrpU3UUA_;qlJBT{Wsr{b&h!ZhvqEovrV1(ZNE+VoTjgF!=t87 z``K|*KIOAb3~ik$pKZp{_BC!l+vH^2#5`_4+vIkkpKZ2*g?_f#HpXqg?PuG*+WKvs zww!G-_JN$A2YxW*VZqw3SraanwK{XR+eEY0U94;Mne(om_fTA`M=n_-cO{?vZ`syZ zCp6>5WA2NbXT;p>emUjbr#Uy_-?I*Nn{$&X=T>*~7{|PFF4mlz&_+i&?KI~m^qb}M z$+3bu@rQG+WcqBkL&wN?n{v*%te?k$(#*6e=RQrp)Xn_YYD2K<1$Z+d~AC zW2xg?6wYzf`uCF`$hfE37yrG#+>>?uHsf6+j`cok`>tMZOy+#3o^$1SMm^_>f6MEQ zS*JPYs@Kf&x?ID? zoGat0=TI4EJ-3>i57BevVW zrM#YVF|O>xcIX4-pm*1eN^c5$t8a?g%?lzB~a?%cJx zC!g0P`CM~vaopTn95?qCVec(c$9s!>He-u>i(G@u_21mNXU}NvfzEI4flj%X+S~)3 za__ad2O4co;^cm1#vJ!5xnG%F%5F%eZj3#d`@J#tWbOkuIh=Aov>D5k`=`y=r`&IC za>Y48=98mcjCahsEbaw!&o?>l5p&NsIqn^E&o?>lDRa*^Iqo%c&o?>lK~HJ3ZU4Tw zIBosjJ2&^jrralO%bR;@Q|dJL;D-CK;hOuu&HdIX_fnhk;XZ8SD(>}`OG>l%ExtF z)K8|*CO@>_*Ky_8;Ouijo{2N-&?mX04t?quU;2gh3x9pyO8wgFZr^=x=XcM4 z<+A+iPy6k7#pO=U^5tK#Y(H=A*T=N;vFEMYe|pOmviuplKB2$v3&&^qYxa0%zxLj< z&Y}HPKD%;1^QMdEQ-AaBdDI_KPW>pKV|lcn<+LB|j3}p_h$qX5C;H8D`i=OrocJTo zj{3wIkYJ7E#cjD}8-bT%K z!nm?L@-}L=r8&*^!YU@)+WRcceFxg;s6#tk6Nl-ux$iJJ4~u`g&u4Y&GgsLTeKz-rM$t!> zM>|vQYc&1x?^%bsO`KEio5c4cW<|aDvm~C?DZc76S3SM9%>N%ePVT3qySnWxl^&Ob zFZw8d@;+wH(QG5l_RMxdKw+J2iLbC%=1#EZ=6;C!F)xhi{!c>)Y=<=Z<|hPLBJb=ggV2R`LmJJ@Q=s zay+Gse}k#ZXJFc(Ex5EzkH_@%ALY|6kNU~fk9Lx2C)%Gu9omn-$@CfjmQ0`VnPmEm zK9cD(`beh7rhIx+e|po-^rrn8O}{gmcxE(l&S>JFarsrVm#gEV-0@OBnLeBR(Ehn~ zTr(IOOrMOov~vw{Cevr*W%{D{J^sI6mD|AQww^xaJ3-6;&!=-6SnEk|oByM3&#ZIZ z6=zNP4$*5{9ZyZ%O5XO%}hiF*%u zUxsJdR(jI=vd&gFy=lz9vHek(e`C9(F8{`OO5GoisY9RjdA$5C6@5^LK8ck p6^ z%kK*lD|LvSF;j;e)aU(r?gcPr>W~Ar3F`3w;dVcvjDL%EMol~Uo!i>Z9NUR_vQCYM z=j)7TM4gh$A7`C9uB^kegfXtH!?+?p9evgOWSyFytV4d{-?C24Gtb~%dJr zQ@+F1v@@rPhwnQZ&!~xK)QrpL6?>jnY{oTe^5gT3qxW*jBpu4&AJ}9d_S%;u$mR zc1SyJ&p!WYJ8sX!lXb{tvtJMoZL=LlT$BBaagFJVXFr?$i~RI;J0w3@hx>`meoCIR z4!Lahck-NlkxRDqGOi!{ysN&l4!LBXp$@sM&&RS)<2~z;%Vr*9`-wKnI|G_|jPHNN zp9SX$1DA{pc^LBWhuH=e>|2Zb+-;wIHknbZExB`nhw3?ae}z3avz@=-py5>8JIjb5$99GySWy;@5^^t=d&L5nreNfV|cF`+e*EL z+;I)LUR&b&{I(5!!=dXc>{0!T`1KS45F*lyW9p23q ziTwY$p1)+@=~R5R@8fED@VG^;@s@s%?6t*Z-G6f}JMfT`VHbXI{)Zp{70TuA}-#zu>?zeAZQm^>6!8`L51S*F2#A&#ji}Dc^Cg-TUjG zxMuPizuBt4dB;tYcX-wM{f6(`Df#bKeO$lFL3<}3`I{TZ*B*Fq@~>8U|M&wd99ild z_vGaj9W2e31Q+uyb%3pKmlSV%~zSKY9)YC>^d2?y!=u2)K?RG|Kf0Y#;*S&p* z((euXt>3-#(IuWYOxwCUb(0e3?0t6cF8f-EfA-7+x<7ed8Q0%_>9FpEt;={nd*@Nz zC!bmJ@ZsZ*?wb5`P2RdDpIwvZuE~Gbco{XmMvceF{epe7>1&FkrmrbZo4)#{uPNI` z(^oiLur1vi*YVx@J!3nmM6s z=7g@96S`(j=$bj9YvzQmnG;6MoG@zUgi$jmJhzz>#?72CZsvq>Gbi-ToX|IOLf^~@ zeKRNY&79CTb3)(D2{At{*k>2_{=)n6@Jyf0@rZW|;7vXriB=(o(e5dphJDx@^`Thm@ng%!S7R!Cf=DrVOOkb>18h1F+-IO&+T{0Fzrpc`Z8DiQ8ZXiIf_<&! zwod!mw#~LL`lF*-mQ39?=5RC_%O7VQyCn9z$#1hRvHgy@fq@^b} zv3*XNE802ak8wUiOoOinkFR!Ln>lZV^DcbSkvZ?Jdeti9)ek#3`S72fHvYmJ_D-UFrYbKxmwXOP}pR!EypKZ8%KjX`v$vN}Kx9#5_ z_UVI?H#+CA{){94AA4T{ul2OOpJ+{BC|%=j#5yeLi)b_SxTOuf5jV zYpuQC{l4!!?j>JXKiZ#m>p<=$XWTf(e|%Co2R~{&eH8Yd#Mpbv-ijD|QmIQl`e3gr zdn;n>VWo~G#@<%yTVm{aWp71{y|C27#MmQC%pv})S+(h^9d&Z-Zxj#eWVQ=G>SSUW z7kfQokq32hloNZyD8HR@$fca)G}$x$G;$W_et_&HKN~aHU@pBD54Sg$&**BWS_AFa zo*5lJaY8R!x=BX2Kd$L$`}EJ~{QIu^+Q(;RY%%)hinjLU85`Nz@0d$2$=L3VmA9EU zt7dGvq)JUw=7=#CW1V-~9Wwrwys6~$N=~oj^h!>z$5;{0=!nA^ z9dS6LBMxVD#NmvNIGoYNI3sQH-S1m`G>dT`0)OGT%Nka(w=d~RTr%$+`E2n_yy%yn zXdc=;l%IP0?xw@D(gR8(1Y!d-qOVP z|G*H}&g<;U++B}2zd|3s)6DM}<4&47*mtjaKk;t;F7@-TY)Y)<)a|;z=F$9mTrH25 zQ_HXCrRS^lp!K8mCUWBa9h}#%a8}RNN9<+OwT@+@Pen@(90={913iUH8{KnqS7u?sc_1T23v$p4YGD zp4AEFk@=jm5+%frHriM0XrtZ5jyC#(*wIEm5j)!GKVnB4{Yva8pMx`idJ{XE=!as* zRP;}=V>v`$gd)$+2bMO=Y-*x9% z$Y0z~Up;MD4xYpFmk<51A^1?UubbJaTqcH$Mf)`DCD1PY^QAw}KZHj<8!hwQ0K%Uy z{CLd-;}*zI>`|=9Q-FO5#uGUUWE|{KjL45W9NbgNys+Q%cwI)dJJsJQ95dz1OBKtj2rdom7cxQzf*Q`(O#%eG_F3ZMh?zQ zQO7RneN~R+7=t?Ym)b4|XRL_l&z<#o4qhifoIhu6`COdIBK|*8xo$4bYLOQzKh`7{ zuM;3&EIOxouH+JnJfiq*%WIl9#F?zTMq|@;#!kbTth`2JTi(?qA7`@i8jY>pe|$d9 zWaTv)+p*2ue4NS3Yc%$_7gp!vOjcf_v2QdkRe&>Dd5y--y0dBl&Sd2^8e99T1_d~i zmDgxY-#3~S;7nFtqcInM(Yyd>vbSGe)07hX;!IXvqd9cl56ug3CM&PexZ6K!R)8~E zd5y-k`nf>?&Sd2^8n^J?ss%WcmDgzeevL{M;7nFtqw&uatxlWgF_jOuv-r{TTZi_SD;#;RU zr#D><=Y(Bi9sQe<-=zNDksYP;$2sJuv1> zIOoGgsvWsL_IHZMDSp%paa`0AQ6AJ7QO>P$-$max&&A$b&iBk~|7@0vy|*4;?=9zh_FB;)_TF;7XRj;sVGj1*a=vHtr_Rm6-doQ1?9?(>=V0$G z=X-Y3$<1=G_m=ZLyX#Hk8e;D)=Xc{s z;*3>s#;Q1DRh+RZ&R7*^tco*M#TldGj8SpMs5q0-YgVsiy~g$0*D*oI3LQgYY{9vc zYTqgrDIV0l+1RDV-73~8Ik#HB!k^ubsJa@lE4zOY{_MU+__O;RRabAdKN5Ro_f0Wh z{Qt2A|2y}^h?&Z!TkWBg4{WvPQa*!x8hvT2y_@nqqxQdE?SH-6|9Z9m^=kj?)&AG3 z{jXR1U$6GRPVIl4+W$JW|9x8Re~sGz8nyp5YX581{@1GguT}eBtM|5~;G z-D;hx`XA>l@f-=~E%6*_t8)*19-_}l^!bV2zx--n6VH*hI-k+!Hu^kApY!PRAAK&Q z_hm7@tvdPPLe-9aclO*#@oaTYrN$NgY&q9b=SW-C`FBp+W#YxRw!!`s?eQE5=VS34 z2|V!}X{+-$b&iDdv8ZR9k463Cd@Osu7h@gPOT_A2s4t^E`L*)iVT z+1_@**HvH{n0p?th;30g}NeH zcTz7T`7Wt5QFmtQtfbC_9*SdMkgU68-6iWTM4e*Xj~Cavi!+OR*UbMj=MD)@^pN;K z;sc2fBtDS%K;i?54INjnvh=p^xn z#0L@|NPHmify4(AA4q&4@qxq#5+6u>An}332NECntNXxMd-HgFCIbE>IMGAm1BnkL zKCtaRfS!N#7@wI5+5jTAK-Y&eKtB?a+Z-dKgegaWoi!j{^VdJ5T@6cdg(9c)XUpOL zkVk*Uxc=;M{h8z#Q$CwL`A&kGWKu z{C)cDTBC{2+`F}_wB!=vxkHAywKIkjH!gdNYxl`T#CLrDkURak3y7O-TIf1oHh}ot zXJ2>cp5C9h$#);Q%bz-fc;-Q0x+*XCB_6x~_wI>xrx9Or#}96=R0coM@_RSy;|zY! ze(9FKnCbue&TCw^*%_W|UVPmx>YL$T`rSfzV;Hyd#}B#Hi!<^ZviWAW@Y9T(qt6`T z7T=$dzjmG0u6>x-!u!5Y9~S1j=)K|TbysHep!K71unT1lb|DUSAr5vS)@v}>h3$IH z>a`5tm-vG30+BykFzf?6p%wOloq%B<*a;Z+ft`S1AJ_>P_JN&%VISBD81{jkfMFll z2^jW)oq%B<*a;Z+ft`S1AJ_>P_JN&%VISBD81{jkfMFll2^jW)oq%B<*a;Z+ft`S1 zAJ_>P_JN&%VISBDSnEgQVzyWIyEDW_R@ulZ8(C!|t88SIjjXbfRW`E9MpoI#DjQj4 zBdcs=m5r>jkySRb%0^b%$SNCIWh1L>WR;DqvXNCb%IZgKl*QXSk7ysz_|iLmFfq=Y zcEI=M;t+opAN-|R@{dfMY5K!QX2IM{oVoL**Ugb3&dk_tkr^^76W=QD@vvz;KNDwu zIQ$lq^L{4I^lEmInS6I9&fLEDq2{onO#Cd7^JD7t%9*%2Ve#lx^~*AG=78>-+xCC& zw=t)~yTenThFG*|*7vEeYG$5oct~qgX>o?L`SnB0q0=*Cm92h@dHv&z40B67Y>rx( zk?q=Yi_F78=C4=0ZYH0WiJ4_~Sz|hdSbBb&FU?LbW#;~E^Y4vYn~A->e%WLu_RnCg z!{W3fYz3QPwZm4h88B=Gn*qaCuo*CH1)BlGRF?f;Ek`4U9F7wGE6ljkOJoHI20mj5Uq54U9F7 zwGE6ljkOJoHI20mj5Uq54U9F7wGE6ljkOIN;vw}D;vsQ}hr}Ts5{Gz59O5Byh=;@> z9ukLmNF3rJafpY+As!Nkct|XDPe+NGqI64#75!}8;L_~Bo48W zIK)Qc5F3d@Y$Oh`kyy(X_9<)+`xIhPHTFKlvfeHBC(u8B;{U+m_rwx6u(zU(Larp% zu~%d9E35pf_r;hu1B0-p^x2Z=6BTdNmB>g?ltcx-mTxIcK(%3Gy2cWk^ObM?yq??zaCf1qvh1{ z>v`$70gHHg%2jLUI@J;vxFnkt10SsS;PXNQm;S<2{efR`0)&zV4 z7;6PS0gN>Sp8(b}Ypna|XEmoDOUs~T(=zM1=sD`SYn^CaX&plDs9PPwHI}(#eMaVD z<9uZ|G+{$(yU+C}DKqrGGv`$qP5H>rm_V|A4dcN@^-A^&#~jwU(9okh+x`%u0PoEVY@H`jEB=m^KQ14D1q~B@Ubx z?Z3MoGvl(4epYkpv9t_YHZ8NBOBk2)`m-={yTpB-pTl?HADAP23jP5MUxR-D!w2CX z!0=7@2QYjV{s9bMhJOIV$KfBq@O}6PFxCY80~l)s{sD|N1pffW+Jb)oYdLkh?yq?? zzaCf1qvh1{>v`$1lxJZI&3V&SvG zn?@f!mTuSmHIL@k<7#=doLYVv&&D}wT>7EKIru;13H^x!4{_ip4&xFBc?_NnauNsm ziNm~7=(D73ujz5D^OiQZlO}w?_O}~1vp38?js2?~xwn0?S3dES3-_=Umc2$Sx`NF) zF52)raH21s0R{)SfWeJ1fVH0g0M^g`uUPaN{myHQu@^m4H5WhON73%^qv#JAKg#$C z{3!Yle&YXl7JiiJ*MiUCd9;HMyqP{*#?tK=C-&DonqQBr<LJ2zv9;Pr@3Z&xExjzeAqL#v=L=o<}?U2)vm-TgKAuVQv0~NAv4( zwLDr*Eq{o&A{X-;=l5$FLVwyl@I*fmS!NN3afyRGmoI-SMng&`=B?keU#2ICh{QrD;;hngO*Lptmgu~#W`vm`XC<0`8wdhNgU=&to%00CO>~a zNB^E3)EbGpB2Snvu^vmypk)j5rEGdGdX6e?L|?G@{l93Z48JG8ZvT}Xk+aCJVz_WI zXR%%8g`7ooF32417<2T$ns4-5=!(y3PCb^E zLCdCP)^pKwgr1eX|0QnLzM?POryKj#sd%8T@=+_|DGR&!9>-KCZgK4yzS0Ak*N)3R zbCKVDuUmOm@c1XAe8H(DGx*ste(!WMo-_37Fw$2Ta}xK__WFVTu4RsR)6PBpFZ-4D zkngJI?fiW;_aUzPW_>@XaVO&b=}qqEk*5(qGI^$}b6V!i=ZL-bb(_2X_RMF`S3Bdr zG5hc6bCEfkI7gYgiE|g7n5Yxcm5sU*9oncv(XEZT6`k9tbFqbuws`#6F*e#rY-gkG z#HKddRBUadt;Gjy^a1e=8+}9cY@^R;tk2(e#JODRUNP&AImg03*M2hAjGI4<_-_** zN*!KhOvLGkrH_k!*8D6%n*CAUF&T}nG19gOABoVu^>yS+r5eWe%f<97h~-A92Wu9(_WtB-TE!G5YMs?>xryB~vEqh}^V1i-l{sTSt6)-U z_=%Z#@?O;oO*@yl2YdXh&zliPoX2qwzPy~h`pA=rU+vV)e$_KY+_&@J?5X?JCB9@% zADeghx3qh+&j;J-eWnv%IrLIH?Wui;VOx3MjlBN{f5zH3AMMo`NbBb>Dl^|Vr09kC zxqU9SFIB#V`18xpwYPO$_8a^Mp5=NBoWx-)V$B2m=A%b*orZC@`PsjU{Ezp&y%BV{ zt@4lhqO9C)!k@ABKaVqVP#pe~sZ}!n|1H+BbX&02$@>Qmw~u}{lJ@E@(k`z z17_Y2eGJC`JwN;tI4Q$lK^~odca)k?*SCAVx?7dsgY8#Mv~ge#M(*f6BBDH z?Hd}4zHxWrFDbK*8{7N6u|W^Nc@JiB${?}G$6P7-&c_@oxyi@e`fEA+)$ASf-5+{3 zaK`+Iv512VzrlLkfAOq=&bC$l3Fn*<^WA@3e#}vFsN7e^pMQK;K?C;6;f8yL09sWCgbR63j9PG+H%eG+Q#Qv21!`kl z-*5lz9w_wXn7_tLpMO=(pEA!BNBuK;)T2D_3h#|&F3_J@5#Gzp`G)s06NmRQM?K)Z z%*6V$GJ^bUfAWd9vhN8BXG*cZ!FU-xZ28=na5lyEaArju&a#NZ85d;^XJ5q7-{}jR z%j<|GO8lqJ#1cDZ{9#A2V`8rz%U=5YS>wcxJC+?2d+k{E(rZoQ#Ev_b9TR))SoYFu zP2v{3@Ecx%he0}f_^v$rx*9XH`Hn#qLJ9_*pIg&m~kAKi6iEcBx zOZ1TFA@PC42NEAhd?4|G#0L@|NPHmify4(AA4q&4@qxq#5+6u>An}332NEAhd|-$7 zfo*u*<&VAh>-S&3NqE9~Npwy{B>s^2L*fI845=ZA9GUrggoGozq7L6rG_zui|zQ1vM^5kEi~#uDM|`FqFg_1b zeh}mHAMw2*XvgO{;xitB@wt-tnfWso?eX&((VsYc{v-Q=2VM=X8wY<=zJ$I_2q{{?Y}I{VAdw~58i z+^AZMi04hrcle8O(T3jvqi^P!-V!suaNt5axF_!ZLP3yI;_YLp*e?AIF!~D*F?h<{ zeGhT%ye00)`{xlatM{<$H||wp*Ww2EQNbGGl6j}P^X~nIIPa6a+%7pk6JI@LGCuE~ zu}r>OB1g5SRDYv*jN&(HT%+Vc+#|opX@1Dun>U$iv`3a!1xi5|gvG`yc%Q>rDRq#!t{#W$&*jLrI%w z>Xceayj$vSquXED`3IZ1t>~iyq7AXO&KzlG*8Jm2Q9cS>*%2`>gT}r^nUL>alcx z-AA{>7iA4FCnR`B(8HG6Pt}CmrB+Amjy|Dk-R)Yd=M^q5{BNw)_4iywo#H3z1T|mS zk!unA42jKgU2e7aQF{~oo_)|)?M=4YTm8z8lJhcqF|{`VhebPh)ZPT+vK?b0SD=sl z!Jdm4V`@K?Si*M9SG8l$75g&}WN1okwf9luqA&YnOeN=5d#lA)ek3(N{&3GFbxh_n z{*@lU;n5Brr8kVrc8rNRqmTT-o{Jb`D!Wi;ac-HenR#v>{O`n}?0hi~&LzxmTd>7^ zLjOOA{~dj7v9$~z$HmWW!9K{0zJCZ~pMbyN%!(NMp-}U4pAq%~@;jb4vJdtpVef!_ zgAaQOi~Ug8Ygp`W!k)`w-y`RZ1z|k2V_(Gfu$N)~u*V?}#y}tNXU1s3v%0Y7qC8;_ zMLEOXD!U)Tv*El^Kk+xQ-HvBFtkAn}332mVq%z}h+^(bxo25s4lWe@J{F@qxq#b^ssXIa-i2!Bj+Y z29@~3pXCG4WO1H>Pt4iguUW_)qj+zm*j}^1`vbQ3YZh|nM((I*?4@zsZ{Z%$_SUVu zZXxdlpbW*R+ugUjZZmV@yo%xVpg3Cby{0Cx#mAx zXGTjV>kgXutJ^VJt9Wv2@zp~A|J9k%lEqOYC3X~TBR*Sb9kr$WB@Qv081<&QD~Q@P z`@WlKt&s1w^ZQn^_QKwu`2}^fu7P!Jtn-epr7>s79p*)u!J%t%weGf>uhxT5Wc8!< zru8Xfun)#mcP9VG_ZfwJ$Ntc<>i?&`&q(d*qFf@{SgZD2Tj>G&3hBVlzQ7!Sp*O8h zt!J%&Z5M4X#Axt@I+Hleml!%$Jh+3(cIa4*YlVXC(6N%!Dm%)&vU^yxN59?beOST+ zu0QSWE8fesz4z&mH|jCL8GlOjkm%vh^#QQ4{x6oihS7AK)bUfr!>#sHDjp&h#(22Z znUac!{5{4&>`?J=tNbp%jPY=*df=~|*El8qGnTSreoLP}fv+L7{cO1JQvQ6#{!=d> z;H!SVkodrVcJr%RS785nR~+Em_is&n{?9x4854RDcc{16%~^RK@e%1O-PfBgCO-Dd zGH(66QMPlfJ>`AnV|~q=x)wBg_XgsMyL2j$_c;*%bj~3KS2ids=cr?SD%GGs{t`=D zf&7kG`sT|s#KMs;T*ShiFLNNq)Kq(p>Yt-{auk2A8aG$TldI&+Rr1R?_(Q#+JwMC~ z{fRLqWJNp1#2muBaxphxjEOk|V@&7*7-K?5z!)=Qo3XxV={~!wcIYAY&sRM8iXZx9 zAG9fXp#Lamfs$YPX6Hq`J^kUba(QX+Pd@iN)1dnJH2kf?xAV=eH$R((zdc#0yzRE6 zgoD2|y{)BvcK;d<{@WYkmHbOm$J#FCKPUghQpcKF z-R>j*b@%kPRX;zR{N*0G-_-bW2KhHu>2HVK@DTZLA2i6WYJDB~XP>muwD12E`479X zzMV1QE%M*D+1S=IYB)`Z8_C~!^@(=Ydi!3NQI(93#9Q`j>Hx@RDD~v7#69i=I-#OMV&0ieAVs zdNRUGei_FKFZpF0D|#Wn=*fs)$S-;_q8IXuo{ZR){9@;n=!N{ECnI(xzu4J`UdS(c zGNKpqi=K?w)x*AGXCrnczu4J`UCA$YHsW*S7avTCUCA$YHsXKe7k^BNUCA$YHey%u zi=B=5CHciqQ{tE87e6)Pm*f{eH4;O~kJTi8Nq+HDBk`2{XcxaEzxb&Uza+o-sgXEK ze)N$zOMYO9v*ZU>@~0){k{|6#{Q}R2d|Fn|dDg9$zMftI= zqWn(j-zoh&rGKaVC$04Fl>a!Tf2Z{Cl>a#8KTi3NQ~vLi|2XCUPWg{h{^OMYJLUgQ z`M+1|7wd}p$2wE%7wd}p!8%j^@74NsYW;e(ekBKI8P_$m228-KitKUh~>zp%54pI*gJuVTAX@zbj~?^OKsDt>wu z|GkR;Ud4Y8KMuLcsrb+KP`5Z0|GkR;>=Wu4;!w{Jhk6F`r$TOGJsWBp$e#*%itVA! z;j^L6f&8hEzaYN}`3v%!kiVdR@?)JLE`kM%X{8(p*%iza4LtKXZSZ9dK;Kw>cUJ3aN z{zHDOGvpQUW1S%`gCFY*aT)wrXUHqy$2vn^0YBCm@(TE|&X5kN4v@?)K$E&)H*8R`=7 zW1XQc0YBCmY9{bwouMuPKh_!QC-7sPp)LVG)*0#&@ME2!t^z;S8R{zVW1XR{0zcLn z_5k1?QeX>FSAiev4Eq7_udH%+A?hmdW1XR{0zcLn_6guGQU1e1>=VF$dVZDZ*e8I$ z-9HYPuH;W)&j9{@RZ`QH{3+}oz(2J_$LZKVfdBgQj+(CINB)iSBmYMEQ9nferL2w()IaKnsDGpU2lWHx$2wE~W0d|;KScc-?=YW*7J|ENEyAB>~?AN3pgvCh=`Mg1Aq zFX~V7W1Xq^gZh*D!8j`Zp#G%%7)PyN)Xy>gpni_=2laD|KdAp>{6zg6;}7b8$`3oM z_=Ea6#vhBi5dH}}tN4lfKgLh1;y>#D7(cCw|ET|C{6zg9R5z zRh-8@g*@;_q`B98Gvo2@7(E?|09JhEdW;@p695kHiS)7B0vp%cNB&|A= zv^WP1XNFdtNeWN)Owy_|NuJ||GfB=ZoJpcRo=KvAJd*@ZJd*@}Jd?z@@k|o(6ev04 znIz_0 zyYA-EXUX`McIBvph`()L$6j9INaCZO_|W8+JCpdB_79u$=Vb1>cK!Zbb7IpGY`<^f z`c&_~jV1<{%oCXZM=VmW3vczhcId|^cF7sV{#Q?_E}sE@5pmupx5{UOpG90U?;ZKf z@Dqq#i%R~;``ZvNtGAyob9X)B+IgMvlUT;Js@lNfqd?a)u`?-h?%{LnM|K+j4Z$_p7`A2r8czdluLes$9N(kb|GiKDG+IqUB! z`0&riJ>{m4eCs=hT7zej^U|Di{mM~KWH<-c z^0}?QBF|;-RCAY?SW5nrzu3<&pMEZR-l#Xp<(K=2{Cl0!(SJSnA#xt~#+&ZMrklt) z)Z4{f_~DP_9KNBB|KiK5$yx2^F|Ni-6)g17e~*Lw zI{P9ytBp&$`8{h{%>B!k+WRS!cD9)N%%iIUjkxmKVLSzvwBwvgI1`*ZB4>H(+{8@}E6&A1^xMv!XM1O_wSh>x))P z-P)4-^VtuspOF^b@mbNO`(RBT$36X))h_p%`}ypwqZ+z-gKP0w(W`4|Qk0=`>79JX zU4P`WyFWkJiB9>f=-7!LkYD^FedD`bD9OYx0Qho%jdG5`S^M ze`!IU^N)PQiLY4rjQEZd8<0nA;(j{i7(UzfndhAN4LQY++*zahu+L4cRyy&aj1Kpm z;KZjXkN9|6e2CAAPdV{#jw}A27XRj0;_qqkA@Yb%Iq`M!i|?n!*U2fq?7k!RzbAGei!Kz_8pxaZU4x$3k&Daj4w zNBe;bGIAbJyD%lWft+Z+=h6eoIe+KZQ>~`7CgmayGuUtf^GL6y-ehupIM#zl+IP_S!0Dz__O5Tz=09M)^!?k1~gmvtE-yM)`?( z;O(B|e7e+CM)_w-`H8up#vt+^wfZKb{L?7kFlsHNlz$rK8%C`Qqx{n--!N)j80DYl zqGeU6pZ;?qLspAI%^jhNKn74-iLYdm3;e;Tz$>^)<4r4E1e zYm8b8wyLX19qzMoCkr_cPas$NqW!7Eds^>lF&^S4#>W^~3m9|5yM{WPwNHHuUc?ZL z11`i3aI5%fz=c=@ZWTX`ik}8th)dvB@l$G)Y|OMO&P%`N*n##C!{VVvVYN#P(2|vA%#lu|`!sVjt)eYZU7$)M=12 z4Nk-ow1=7va;8JBgq&$`B9@>}sNW!G8k~qFh#etsLZ9SByhQ8>c@z3{A#XyT4xEUE zh#etsLZ1$th<~C_aw6s-A3#p5Kg2k2BIY3nfD>yDu^yaQTZnPsM9f2cC#S@F$(!Vn zylD{AAv4yHa3A8SSOCOIWLlP4>uH;R` zLq02c6LE>pVm(PrpbU~Xt;9n zaCUn8);#Q&!1+y|ck@sqf)i^Ldna%nv8G}p$(!Vnyjg^O6!_bIwRa=Qo8*zanZ}+9 z{PXWQq>M{KUS4oX|12;7j0E z@zblAiTzQG^Vn;|n2G%nPRt2mE+ zT+Bz<$B`3jROKM-(PFOg1NyEsOLy*XM?Sn^+H=qSgLqZ`m#Nxk%p)Gqw}*LZ;|k)H zzl=>?xacL~pX>aR@?S3?zH3n%bKsK4iH9s1V%klaLR@{{Nv7?(D~XS9cE14^#sc^B zgYP2#X5KBj-KqXg@i@ir)VNN`lU8!3|@lk@E^9rf7H0}H@3sy zl$=J%pHlNm>G>)dq@6N&*d>hR)mR=r9LDl$EDxU#V|lEFFqX#}31fNDZGM=Gtg{|* zjvhWAWbjyPy1(Lywg7*$1;&lGfIQI_kTco>@<&@>UeOkiA?hFF!vCQ|$g@@d;D=uP zHu|9#e-^(Ql!N||H~1mjgCDX#=7~NSSN9LT=f&sYhwx!y=sm+p*@!c~v65JPzoF&~ z@qu#;@qu#>@qs!C@qxMu@qs!N-I5c29@c)CduFUDkafF;v4^-4=gS$mmhVQ zU}$2jP4tlH;m`1aWv9KEdVB6@f5QV!4Dk4Rmw4NL2J!U+FYs3k+(>-F7pMA4%j;V7 z>5bB@2;`U`Hn#N3;b1*S};{T8Vzehh{Jcs9j!3SPo zjDzujF+St~hFnjIe87+wasy)?m=7@Khj{{H-k3iy^Z~s9Lr>5bF!TpK0#EAOduohV zHR>P8J1S@Py2Kt(F>^2Fp1TIx&nGzEJ*YUghaGfxS&#mY4m!-<`)DKLFNamO$4oz- zxb7W~n%$4Q0PkazI5^h!U%PK^yyw%qXAbVku>HvSRd9c%0Dbmq^b6jbNqqm8OL5m}wc?~`O;#sue zcfjb2XMn*0E?{sURk~yfzS{9P>kjHZCIw$DdUKx3*<(%$zIxOnrTv)M@1@|YdmW$a zr{(N!;H#%TbgbXJ|5!fTtLY)`t6%CH`0e@+2l)J_eWYs3%Je+)oUw8rcjr@6$W!g5e*Tv3tqkNDwy4leX)=yH4H|y# zo;!3Zc^WR-!*_k*1@c^QYAgT6PhXPfnYqt=GYAq+v*EM(c^-tQ_VqTRV&+%&>uVkQ;>yO>Z^;=%mVqW*W-NxUy=XK;c`SVe( z+q@UZv#Qc;_xv6|kmr$+@469t)FDsDQ_K6Cy5^8)<*1j^BbpvWo`>ty_g%W*N1jjo zk?x6;KPJzn-Z#2gKkaUzpO*(c?yl?IoIJJj-gCG9?I7~Jbmh(I3x*y=o;45u;{Lg- z$R+w&yrQxjG3Y1q>|F0S_x}2t4ul>6hN*S-y6T z`*Pt^&7`_q#SC}m-<8=8NeKJLWy#Z~-nT{71~wwk`4{Y!9(Mfk3Z?Z|WfD-X5p zwC;TJe0JkW=~g|`n3_kPHxIfs)vDWZSKdRG-6VH*S6;V-Qq`JJ=m(Nx^HQ$_4wHo;=kGs*luyX-< zKA&LBD@#-4>Gk4lv*4cfg_h_mP`Y^Qw2{v%4Spg;~3xEII4%xxl=( z@ka9e^vy-4#ImO3IrYV_P5)z-ljnzfA2Fj_?Mfc}Y&*0BpZ#Id8|I?#4=3k&<#)56 z%)632_&NL3y~(re>@xP_gPtJ|enJkcJIH17KI59g&oO(nBG2%PYFfwvpNCw%zo|kV z{Dd6vTgU~yfCqYl99UD3Yo~SlkOx0M7rlT7dV(BS`;ZHI0T1*9JAnswgD$`W-9Qe+ z1jq$Dfd_VjUcduA!A{_T-QX*fM|=mmz_ZW|Yz9u)5Pkz5_z~;`9@q_j10MJh`~&^r zFYseh64Y@`ytXdj%$bJ;A5J2_MJ$L4T~LWlKwwb4YD#;M3rQkB>fi9C_X?m}jt-@GREWElbkOFSRC= zwpc&tkM;D**K3(;2Iu73%a7ZG{mWc*EYDUjU#Y1~%a8Nef84YIY=@juU-7&Ya!P&0 zcE~366*0z@`U-NU!2>ywXECnST97jh9>^)OrNIN)M4mKwf;ao~YG zqJJ0lFFJQo=b~E|bt^g~4|FI#MjrT>=#4zkoA?!Z;8)^Hw-L37vldO^Me1&^A7sKS`2w9o+l61pFB?< ztT}n!V_sNi@;rI4o@74c!5Wh1$%Azx^C1t`jm(EUSSvCg@?cHKe8_`!Ao?W_{9Wcl z9{9WXH+e$b_RuqYTzr>2@MY02dEm2RZ}PxTMZe^MpNhT713wjelLx*j_9hSfQS40~ z_#&vP2<<&G4X#f1|ZO335q-LUAAZ1(#QWM9SiV<3J;jQ0h^K6qb1d{(+-Iq_LiaV&i1UX(%0re(%w zRmHjd4|AM~F+=}p7&Gup!`qs)u# z(4)+Y{e{PhuE+yD%Dl)AJ<7Z|F7zlmr##T3*n)E6v-@OTlplN3gqP5H>rm@f>s;GH+vu}qhcr^QgHJ}=!6&2b;FHmI@X2U9 z_++#l)=RV<)={(_d@|b3kE!+GH48te%kR{P?J}=yfB0GCf&WGRKkAdMN7U5w+U`Di z*uJ)$d|!R8wxhPMw!8KR?I+rQv|nj|JNxX`dC@1O9rlWTxLsn%X+KYvwYK|otnK2m zotz_K-7%ibzp|<6_*mKe-TGbXyVtzmY*6mBW z+9|{CZMdvq75nurEo}3uiyGo5{(ns44;te4=-2m+O%3t>Dm;H}n^HO81MlR;yXIgV zjQ7Q$ayb|ua;$1rCI@mszBScL#h57&7 z;L3*32lVoEvqKs}Pte!1FFw@(`h)GZ*s(+j(Qg4_49-ix+V>S=oI`$g)-q!Geg5j( zpC!h5>A0Qe5#v0w@y3UUabDWvjVZ)9FMXu;b;LLqz3YbI#5gaFXQpWXzU2Pd{)hD3 zjTk%_5AuM2{4uu?W86cUcO=H|FWUTp#For^DW5*&Xky6UWPKMoOU}H0_QiKUP6+eL ziS0OtjQxctC-UIjGVH;fzg z33;NPA!pP-&P$_RBqn6-1>EYpF?K-BD~s|jZ0x#?yp;I5yh69R)`i56ZCLGII`B;5 zIRkh1m-RT2c--7PU$1q0;xjHv`Negc5%1dhINznup2RnO)Ym_k{=$HN?r!J%!*-oR z{Mwbn{rS5MCBFZ_(f;zwzeu6a*WZruUCX^V5BQlENBN%Xc5%QrxM9BGlVgdStRCoh z{-KDtbKgGx>XSDTZyI>4pZR@NkN&S7)y7{iY(L`9{+8ocb?!hsV?jCJvf4?+lMjB! zO`Cic@#c}!+#xqyNPOn#qurM;jU=u)ep$NfgQJOqu82ifMs!6ix-z0GV$qcmT@j0} ztmukZbY(?X#G)%Jx*`@`S3E4m^UU0Kl;vFOT*u82ifMs!6ix-z0GV$qen zFJUCH=qe?;BG!JTaND3a^l2OPMjZ4;9P~yU^hO-?MjZ4;9Q1~HwGDbB4tgUFdV`O( z6(57%;A3sY$DlU{EItOk5eK~y2fYyoy?OK(AA{bAgWiaP-iU+Vh=bmUgWiaP-iVct zwFQ>-oGbB%uS3cDB@S_w7;#0`J8_7s#38N{hqy`{;wo{7tHdF$X4@q$W&2CKA`Wpi z2l9ltN*v-UG31eWD77d*4>VumByotV4bYBxNn9-#=7qS*_7GRuA8{=5gt!{VMO-Bg zag{j4)hIvWDshOb*>;Jm#38N{hqy`{;wo{7tHh8e>N&(!wuiV%tnCFXag{a=ag{j4 zRpJm=i9=i^4sn$@#8u)DSBXPhrB8;qN*v-Uafqvk74Uh)Rm2MTJmRVeK99Ic9O5c* zh^xdQuG--9h^xdQt`dj1N*v-UafqwLA+8dKxJs<`20uysoa<|c@pD7BO>>aRI zL0uzz4V(+`vpdAT_&zg!b_e!c*sEZjVK0Wg3f39+Xwr|LO@X}|_9|Fs!pHqT)>(`l z@R!i;;4h)SLtG3z9&sq}d&H+OF5^~^$0MEvIX&WHkl!ONVhoIjxQM+H#zQ;g!g%N} z9W2HJ59WdK5En5&jE8YCZ|O&Qpbv}(IiV+v2l=5toIT*PJ3_m`d_#ZgA@EQ?fuDK{ z<5HhN9_l&BN&N@;X&31ue=_#cILtk<-40~Ci*Nn3F>E>D`TXgNfBcwueCGx;p6T>9 zaXB+^M!~Wdi1!*ZdB#~)pCsN?G;7A?Z`?}Udg!tlt2dlO-0kysX7t%qm$>J&bu;QT zoze*W<;-U@unvIH{`A=oVDE0x|B>5rX8?oez=;IF2jwG>-C!oQczQkqR zeT6qY(uDY%%kD4SeBt}7NlvTxU?E~N#zK2)(kkq8J^G(~%Vn^s2hXaLHxPsW#BPlX z(T;JiTW~xv}!jl(ygg-Cx%eZ-Q zT#+X)$|G{-ML9+OyePlSD^JZUFU}YJqaMH$^#lH>H;fzg33;NPA!pRT%qutAMcWHl z&SpIR0z*$3AKHS8BVTZ6`KLJZMRDW^$%BpXeF4a~7;k&#_h`pv!+%VD)}c9V+Nf}t zX;-re@z=Y|GJ_Y@CSE*ytvU38a>Vk}%Ksgnm)~3IM=Z}-d7fDKtnjA87pETU={isd zvh|^^8+ClhjIt$$NM1nvg7SnMK^$@fO_;{1e*aJ|erH z!Z^}_{x5!;-G5=f64#6T9`eL}M0Ovit35F-&Y*^Zwfw%8Ce5l<|h z3$ewj*vMxjW)`4NXh&>`{SiYV4{_ip4&!?CQ87Hq$@U;WF%%|!V|$D_=#QAmcEtD) zqc9J|Ot#}E{vYI#Hs%7z>G3?;L(HW77)N5}bk&Yn8v7ey6?<*qXL}geqEC>AILJvH zVkR->m8nfK@g%{C9ugn;bA13Y7dq8BUFUjPg4r5C*9N*~(6z+>c19%kMe-lM`bBE3;I@gGt*&L*E6ZBVHHNWT& z`JeVeY>ZgG7nQYx*bzB;yVsV#vg3BEE%khhqxO)yMTI3-r?1ua)ppnZp#4Pqj~FHE zS2!z$f8(_pU3JpEuvAA&h_j4F$Z=3OQ;V;z- z@OqBD@4Z)XK8d(&(O$07&&258`u!sc(GH#o=Zqr;|G=43i81asi;IXM&rchd6GKjS z)BD7b|K+_uC5E5KxngY3jqTDuFZLInyvQT`d68en&5PrTJb6(bkuxvKDe~t<`DI=> zpN#X$i}OYQs0Z*w{eVB}4dX_ALY}B+$Qku7^U95O!MviqfV<1<&VO%y1@8~sdDA8S zz$q!d&*HSt&iDPUf1LP+-m>4kxr9akrUN?oGxp6PK5TieZ(Htg;s*wm^b0y=z9Y5z zq}lGtrsuPLx7|9r`KRuV;@cd|E8P`@k_=>iNUf9@NDEEkdIOvMDQ{`?< z&Ds~*j|9IccVpJcJ)+kHFOj=3cgQ`WX9Z7|yD=^09?>kpBjs+)Kjj`#q2LB`H|A8i zM|7*;2jyI_EmvT4eTDeDbw&2BbH|8F>M|6_l${WYn{&L5o zv*35-j>oxj$D@_thvbe&bGhTuSa3(V8&gB>5!DcUy4;N^lzT+G3f^PTv9?I=5&a-K zTqk!t#>pLzPoU2ubL>}gk7$+PxpFtAtK1`cLGa^pH^#|5qIrV%xMZ5?CijRQ5IkD$ z##H#nNPm~$=5jY?klZ7>UNH0)Z6vyKqAP!!w2Q8s=*mARSajt?S3WIRbmc`?{zbu} zD=)h8ZwVG%`M2aA(R#t6D=)h8KMEFIdC`^IP39uH@}etOQ?TgDi>_P~!J;cKx=J4^ zSajt@S8e_#Sajt@SLS5FqAM@DGUo^uU3t-!87^3K~n%eS59^>tVKEc|MHzyx+T+obXW^5-uuOUQm!i3$afXqbXU%4NZe=L{cheD&pND;ZktQE zIY;cpbuo8VHFy5)o6}e$t>3!F-81`KuASPi4|E&HPav*e?^$<4%Z^-w2jBCJn{`<$ z;yO3(;*a^E6W8gu!WFLHitfbI8{FVt8u%v1`l0HBZpK*yxUOxf_uTUKeTgfsd)SqH ze}Bq0~xoS2>q5cNlP++q836%5d>f z{oTTw*Kw?~dR^&ePHIKY)XfdtY`G`LIIyapYqz`>d2UJX=MI=Zj53Vr`Dl7{w*$#p ze{gg6`QG1>=k>xoXF3m{3~xTSDc$de2guW5K@E3riJlzyfZ zpXu{c2hAD8aYarO<(%ywOPyhRaa@tjMA?SUy*rf}bU4Qq*-Vt}$lNPZAO4U-8ALV{ zWve^vxYX{??L>K=e(+v1>a0N=S7c5_nOEPwN2>DlS(NjEwzr#;d!J5uWG<;Vms?BS z)3(%ZM^OI7eJ7fepF57S$sAL0j$O}KWkyZwNB-&`k2FU$Jd|?E+*5Jxojbp5=H>Pv z{~rH1!Q9oL4rRXcrXS5w@0`qMTQr?-RuAYz{vYnlGY=m89c^^lXP=v4OOEBUCCAM) zr+#w)`RBJ>mwJ6?`TjkL|2Ou2+jO2~`RuT-t~ZuKI5`~TjQ{U6Es z$$W6nUX*9#_50fo#y2Eqvwyy3t~hox*ZA-s_O|6e*o!>x4w`OmD7S<%-1W{;cK(@r zlC$2^740+cmm<&Cz0Wm$ce<7`JT$1iEjy_^Ior?t%4{h20Xf^X-kd5e-@Sl1@bT#f z*$t2HME)`FJ7ZsZjQnB~E4FdS(Z}pt&z{|MjYBT3J^2c=>Vx6r7n@kIjYIC;{itZh(G>v149gNt6JbR2D zVo&(_Qu04}ZA+Wlll05RY#D&cg#t{ z|My#ezU_CIp9dLa?OMbm#G>gBTXRd}PUIiftG69L^wD{cLDsH8oWip!UK?ST_FJC< zfAjM?*h?neH4ie#+BJw@@RK$j2H7hIzn=pCpqF#)cl(Z;2N{lAaf-dE#LFpi4k~F& ze|79UjQer>i|k9UUtqvlx6GzEUiEmm?2`EUHCzOCcx8t~V9u!9-7*VApmFS*4^jv@cp&Oe*-MVrVkxy4G3 zA?F^YPPG;8TF3+B|VqpO3pEod&skE(+>8ioN^Yr zn%aF2d*L^Ca@_WF+S!9iYMYhI5)4=&JvueeCEXD_H0`cTyQUl`%CK(OUbgDEpZM&+ zzpXHRo8L(V`eD>Ckx0tc1I z?9uD@He+}Hko-;euVgEJ--t3uePX0O;j`UK>}K;GIgb2N^BAdlENm_HjFEbV&q{q_ zr9L6Q)JR5ZB+4K)jFB3KoKhDVsf#$S)F(#j6LL!JWTbW?r_@45Y9Wp*b&iobhn!M_ z8L7c6{6}gkBQ=$QeWhM9QZJETY9S-F5c%Po@KM-Q>K`NZ5Ba73F;f4KAHE46g-xaY zF;f4KU+SNf)Ia2hZ^B1m7pZ@Y)Ia2hZ^B2R2dRII)Ia2eKf*5|XQ(SEgVaAMsedvu zi$B6I;gg}ppbYRw_$B-y)EFEWJ_ujLd_#@FaYHS^u|hq}u|oY|!H;&?-;qDm3>i74 zUG{q9m%1n|brGKpH3P@Ov$6-|Sa$mSwA4%FLA&e+;~Y`r@mZ;z(o#E-6MbZ#NEt$n z$7iLEN=qF@PV|xeW1KJQJw7WnRa$DQ?7U=O8Rw4LkIzbdm6rO7{8C>zsjnzQs0sP3 z)K_V#ugEX;m6Q64GK5-@&q{q&B=r^frM_}fUr~loL-JXvubk9ZMP2Ce2%;hpOpH_Nqt3rGT5@ENJEywq2eN9wDz)K}z3K1W`Me@cDjrM{v(QeSzgugJ-KE_ofkD)p6<`ik;M zedVRTBB#_>PURs4E>MJkx75SyU@={-MT-3R&cf}S` zUwNso$S?Jkm->q1V&8)}1wBZ8<)ywNztmSw>MM?mJrLp)^dR+>m->qQQeQc#uP6id zLx@?>gVa}E>MQa~edVOS;#{ydLi~bGq`q=eUy)zxD=+m`8_0mY5#kzjBK4J%`iePP z>MJkxRU62Fy%Ay@d{yczC-oKirM~h~U$ub@*c&09)gk3Bs2rM_}fUy&bsckJQ8DfN|? z`if&oedVOSB0u)=lF!H~^_7?UiepKA<)pq!gCF~N?B}5qsjs}$R~!rbcMM`ANPXp{zT&u&(;W8p;F0>uOMT@r7pbqj)K?r=>MJkx6`z&*%1eDkeyOjV)K?r= z>MJkx6`z&*%1eDkeyOjV)K?BNNPXp{zVgt6)K^~WEAmTy<)pr%3{qctsjv8~)K^aG zEAmTy<)yx&3{qb?sjv8~)K^aGEAmTy<)yx&3{qb?sjv8~)K^aGEAmTy<)yx&3{q2h zsj0|`JQ&Y}6P!64PxO%J;m`B|yk3OYhV|>k`gLR(EBpGge%)EW9<5)e)~{dd*R^FF zFR!oX$bF1*p*_Bik9!V(>U)v!Stu9}u_N41h<6ALw&PB#_)&4jyu+S z%3wqIC@h!YL=TA%{MkP6D%Tg@5A)yj{^(sw?z9`?2Hx-b-}*TKjoR$%&N=o{#>VgF z&2;be7);!M!zOpsz|)8i-B{nRtJI13+~eB$vEMZ&?z4AKzuzyVi0_#`(3k6$`3&>Q z-A4M8dv zI|f$n7!-v&23GDE6ooqmR_+)Sg*ygT?idt>I|fGX7!-v&21f1}6ooqmM(!9Cg*yf* zxnoci?ikFII|fDJj)9Xq21VhHfs;E1Md6NtlRE}Q;f{fmI|fDJj)9ju21VhHftNc5 zMd6NtmpcYU;f{fqI|fDJj)9ju21VhHftNc5Md6NtmpcYU;f{fqI|fl#)LXc_;(w4n z;qHo;yDQKY?yh*by8>O|?uwVYE6^40u6Vh-0$t(miZ2u#?yh*by8>O|?uxroaJakT zh6xULSDf5kfv#|OC4G|MaCfDR++BgLaCgPX-4*BxcUO$uU4gD}cg4uv73d0gSIn-0 z!`&4tcUPb*++DG9cLln_-4!c$SD-80U9oa^1-ioB6)SgFpex*6v2u5%DBNAKa(4x~ z!rc`scUP#Z;_~Mvhg5N2|KoP9mx9`@U5DY<6VF&aFWvXX%3M?B``wy;zG7|SGcSMH zopR^iTs!Sk-?^WT-;=n_xQAWo_GP%fE?isRn}wEZ=bHu9{VLhZV@-|!u7~@)@%vnl z2ameSRV(!h@$xb2UG<|6;Tp_sS>A7|-iY{;%>&YpEos1UPoH;$7 z{*5?Po7bH_Xe#v;l9Y z+|sxElRrJ+j`RyXET6sb=T7dO&O^!hWZom`eq~PPv-Mtc>C-P7!2Vr!dOkg*(g^nX z>X+4R-+8AAWqxpWpVS%sXHd2YBl1%>T)B}l{P^apsq~_{l>e>|`=l;e)sX$m*ZVnj z?c*tqyR7i-)JLQ48$nS>3(KybH};oQidNkb~U%y>f}7U z{T-<tn2zRIrCEs%;v6#bF4d_cqjGY6T6WAn0FsDb@wSv&XM=NYDT`;jbpt( z>J(#_{+;}?UUTYDPyU_Ce`(J9M+@>l`Pob6jypFx zC(CtqVK-PwWs1AA1k?T_Dy zbJ^76Mf2vG>&dyW)Ly1hn}^8LbI9KI;fMC%Twc3lXWORdQ{-&%)+F=Yye8y%ea-&% z!I$cBE2`lE9n>B|BmqUq>DKT4SN|zM?uAd`)9;>no@HNp`c!vUS65fR9ro>-IN_(a_EkgoA0zp1 zjs9wS@_War+&#`-u-d)v=k4suv8%i?NK7*SwQHx@-#JI+zB+tdHDZxH_3b5V z%$G%ygsn0>#&Ium1qvTI=-==Azqh?cn zi=nEKKUuvKU7bJ8{^{|)y(NE>slJ_lIb)~tTWnP=@$j;pwB@j44on+Ay|D6FoRuEC zqN9^KJa_X#)w_TG=?au(F;`mTj;T87-}%M)K$AST6l^=anjC-n-O@^xiuYRFq|NOJ#FRMV;>(x^a4XtF0>J z+uV|Dj*-k?KQ>#{b$!3eI%blc)2i?9RUzNzmSl5`WFGdDA60K{*ioUATh`n!y+8g? z$+x*B*&HL8v(NT;^~>Y;QCT*hB%4gpYx2K^yqBYt6cM86}}8T&wBiw)yaFGCiw$Pr*z6I_o-a-VHLiNy8V2g z3DaHYjhFoSHrXIedBZcRgZZ!uUxps;dUUQd@7BMU{AKppDvkcjUsVV5XBB=8J>PW8 zVrlzxK9GF#VF_P`Zr!g|)Mte=S4@jmQzdj|J}lwO(5?Gb)#u3&spu(+tQxJdFX7OE^3l6-6v8$}Nm|5O(L zNWR5C$>JZ$$2PH1`o-d(%Hki%xA-Sn{3H3;CN@gHSo~92{3H3;CN@f)E&l1X_(x?~ z{8L%{Bl*}SHi{lB{^_;&M`c<3Q(62Y`Pe2lO21hA(`)gM%Ch)p1&eb1B?GRcGgLMIj@RTd+uT#J!_t7GJ3>i?0SPzLI>4uWF00B;Vqz+Ttt8xA>~I_)79EzN#(0l6;G=1}(ml zOpC8-i?39c#aFe(SCVh>Rc-N=4_Ra<H_)0P@ zzN#(0Qd#B)YJ3xYZShrY@s(s+d{tX~rLxQq)c7X)+TyF);w#Cwv0vkl=wFMkYKyPr z11-MF7GFueuW=;P;;Y)?E0tyORkrv_@_o%BnHFEw7GJ3>U;9Xo#aFe(SCVh>Rc-N= z%JsF9Ae3dP}l8?3csl#&6O5kWs9#Q)8Z?e;~$eui?3>nuT-wZS2nM|q`AZ5tJ>l# z$+!3_TYRN*ExyVYUuo{J_^P(}O7bnf$`)U#T#K)2i?0-8SbSAme5JYG;;U@&mCCjF zsoXHzN#(08bm()*0gso z)s6qL_^P(}Y7m(gU)2_04N^~duLbu1dN;nv;;U@&m10PXuWF00BnLk1FW*_a8^2`n zRkrwQkg_bksx7{fOpC9w#aDxr#oC=UJn}8R$`)VM)Y;;zZ1L3~WwCZ=4NpBSzRDI~ z)yTB?DqDP2Qx7GKpCU#TqC>#W<6WARmO@s;FTe3dP}Qn{?xS+`S9i?3>n zuO#2%t8DR=%4Lm+FGCL&U)2_0NxsEb+2Sje%Nh}1M%^sF$`)TqzQtGB;w#mGH6p$Y zJy?8|ExwX`i?6c9SE>W+Mf@5%vG^)md?op;5%Fc{!ToAYeJsAp7GGuB$Qlt}h92Cn zsy-H9Ws9#eZDhTOUn9T!Rn>SrCS_n-KG-X1CGmY=shl;7kCQ>Mum zrcC?8dmbv+ekV+sR)#QT@2mPd=H@$5_9?A@Q<}DfIq5mrMi^?Q@(#vie%isL@ zzuI?`UbcGY7u|O^u5;1RloL=QZq)@^D_m zl7u<0Vc+OpE9W6NBSC)7W$<_FNB@qD_De{o4ARMOe<>ewD1&t5dl@R%&xG)+?BA%K zr3~s{_P@y#(sf3IH0l`Sq#&QSI!d|8vX=U!P*1%ViyV`!_hP~5GPIZcYP;(aSwpN$ zy#)fcGAUQ-=#t-&Za>MtQ9UVx#Fp$MN}eIS6;|45uolBUrXt{iN(8N z-X8<=h8FLJfq7etcf-KExy8F-VBYlN-7qk3bn$K&n76yA3z#>(D5IpS49`y)q$7ti zz{uwhSZVe zow-kPm{Wor=Ds4oq6{xLh5DpW&yUP;4-B1wcf9zX^!A)c8Kk##+13wpUzyXH`>c%i z+$W4KgZ`QOl#Xm`j?S&oF8dL-cWcZ>J|CXA<30J-8aQ6%TA>8%Cto5Jz{wzFU z*S7TzM?WB3FLg@2*2Omp|7Pgr^OHTD z>32cG-M<70Zp^F5dZj<@x3n`&Xa#?ZV%ES9uOQVO;O0eH-!&#&Sb?Zz!t{xC(jV zw{=MW$hV;mG0#W74Q+{K)$!Y)lRDJ7j^75|e(JZu20r!MU>kKTH+~z-iuq%nn2s&l zc#yAd@PC6IK8yoHeE5aL?fC9u6Rp^~6;p?J7`u_}m>>DK#O<83{=XQvm$TI^ee&Oy ztr0(j_R^2iCpt!_p8q53ps-H)i2h^0#QyqNKid4)?nhxSGm-B7D9qX@tW!QRkA-!L z{=E^tZI#)wPud&oll7NmvNmGQA;0~6WF5p>h(s?_n7n*LIx<>oq1O6~e@Bya(&$nb3$te6kMmc;tc^VW*P6rEU-mn3 zkIKUu#n%zepJ{!eH-mlMkyz{adPHvz8~3Pplv!_32IaCg@^y{!`+7%md>thDzCIFf z=j$fbhcb|Z3}0up*G8l}_ozJ7CFC#bFXWWo3Xh^;cUqa-4fqnN8nm?fhTWcZ}E1=F2{dziaX|`fP0A zqc+f*e~tSgw$yw|d=z3ZVoRmlcOQxILJY=SsyxI4AqF!Z=|gVc{%vgdFZ=oOxc#5~ z^ocKgjj-d*OW41!rFMNJ<_vm3H$^}H7H+@ACARu5;-(*0!4}yA`bZ3KNlM3-W6U4d z0$*-FQp;BVfg0S>LZgR95C4C$0rT6Pt=>K&70eu5d=hhT@l`$t%ZI^v6n+9fSNI8& z#XgGiF!vOGf;qVG6Q6d^_lqufl|OwwuX1-sqP-ChZrG7;S$7qs-}l`Q>Q^3a#TvI> zaCyC9e~SmY@Q;htcXqX6li6?De7Uzj7^VC_IC+Wcotawc2kmi1wd#?r{A&yyl5V}Q zCFhQ@9ckF)E%|ROxJp|6&{iFu8oy1t*51scKKGu!Pr7K*7H_ocJcp&ZuW!XH*kS3H zi2sx8{Av9=xKU?ajcuK;II4S0eeA$~vXfi4d8K}JogIXS_RpEWG2uGGqfh=?-hG?J zgl{-&A{Ee5^XP;|G zUgnVe(yp6J&+C76uYAxCZxnvv<*o9{6Hk=L6YU}5|KvJTZ?g&M|1@>e&AOpUsHW;o4r-f;~rS2`oRN-2>e7CE3H85A2uM zA9j)O##bDcA78mc7@Zm4+g=CE^uRd9&i{$^Z1pSu{ji_$qh(Ele=RY-``tut{Bc~b>cE?@Z5=10rc9wYxjb(0>vZl49Kjj=7Cjz6^F zXwRRHWvfL#b}RhozVqjwUAmg^lMht+?|lmj-?!^#dG<}F6yEl<9Z4{cit$K7O~c>fir_x_w$aKjYn9^|&9l;`!@NA6rlK?N&Vh!j^xl&$@Mc z`GGqho+~do$J)Z%J+fSW?t?{y7k_+{{Mgr~ZKW@=Ti$fN2js6_SnZ(v@=-?%?|I9} zy!7Dh^3_-DKPu1k>i6WUhiq_gzWkV7<)61bYL7h2D>n;o@U1QK0gFzS=&#d9teF3J zXOHmNy9~<{J+rE?{i@yX5&w6#<$uZlf6BXUU$k%kANU9B;?EUx{8QVAc2aO_OxXXK z{1OXV`-#P6yEgA)+x#hKRD_Ak`9r$-i;v8a{>`V}5ooPhTJ4D#S(MG+_^BX=vnxus zU$r?J{1j!ApE%Y262>2f`nNeC`qj!COMd!*GC-tTeqrJaOX5#CyCRHyFGGBI@ww#n zZ$9BTPT{G_f zr~Z@C(2TqP*`2s%+%@B_8F#Jtia8Zu(#&@so;_~j%vPKq;^8(&&z#f5ng70ZK{M`} zap!YUS#P%Yz*zf+^=UKiY@TAx&6=M%i?uj^z@&Yi^>{PxnsL{RyM|XG)(iY$!)M}5 z8$L6mgfEJJZurdB`l1OYU@1Mv=`1(4|{Td<(cgl z_HXmNwUh87Z#`4LaQ+6uhi*G_K7Q?GgkQaOiBByz=84}%nX#-`hf+7{`dRS#XSZUf z*Ipl*=fO363~abso{3>a+gQx<_>E180ptb*{seKHtbW zs_Um{wf&~YF8B!kcgc@(J}*A}(N?>@efS5~mKL|X%l=o?ogcK?^|Kw8thfE3)vn(U zJ>|wFcWCwLghwq@edX(|e-HBTr7x*oe|=lE_nOn+sh*p>buVJ{a>LRiOLr@M$RjJI z5xY+$yxvt?rK|V4PBwY@1bcs~O~yR&+bA=Z73&b|7V8|_65ANt9(5A+iPfw;@xf`A z6ZTZy_j_!Qbm|(v6n=WhR_WqXCRY3GYag2y`g>RHYTa+0YvIYNgMWFr+BM1O<*F;L zJybZ>^YiA9-+mSx<$o4z{)O|Zy5GlnM9z-V7n~n0^Q7;4Wzt#S7G4eiUgA^x75ih# z!@fRi8S=w%mN>Nard!MJQcg*yoRZ%@X`l0@oFbpUOSxW-ODdU|_>X)hdtx2vs(sGq2}sL!Zp`@XIJ*e|ia?0kmZ0d4nVyMJ8|nL5}H`Vn@$ z3A;Xpz1_mD|C$fIUxbVPJiWbN9rY0P6ZIDLY2UZ?9Q7ajL=NDy&>Ob}idM*9+v3|tQs4rr_o1C^iL_3N0 z6YVP6o5^e2VKeTA6#H+-`%#}!&r$!)xNFUiuAgjwi{rumz;1`aZim8dhs95}{XBNq z%y;r9?RX&SE$Y+lQ~ESj;|GM@K84*rg`4@VneUo$*N$77IP*jQobc8E$@5)Y<9`+$ z*Vmr~zpw&p$JQF>Gh(~5-da0Y{{K%*-j-Z6-C(rP=;6cnh#K2y?4hxN#s(T2Xl$Ud zfyM?J8)$5xv4O@08XIVAps|6*1{xdqKVbvO`q8*TwWYz09vT~HY@o4$#s(T2Xl$Ud zfyM?J8)$5xv4O@08XIVAps|6*1{xdque5>IIYL!E+|#o2ZaQb#q&IqKY@o4$#s(T2 zXl$UdfyM?J8)$5xv4O@08XIVA;8SftcbHv24VEHW_YWJLGzd3nQCu*Q_cG%ljmP~tFQG2Vr#rc9Ocj5 zwML%oyrC-VH$xZ6YhAp&aJ|&@d55Dn7M`%{$@))yI}3Nca7MlR1qTQpcmC}4#2tqV zyUawLy)EjakG~IU|Bg!^c|NV}t+$C=ec|#Y)5{h1`UrbHg}wg5-Y(&2CzhV9y(NFL z_6nPvWbG9;`IWU-*vhS}y~0+X%GxXZuh=c^Z~c5KPpLARJpUQ`iGI&*Ak#N)8^Ufg z!fs2#W|P>Mu-l%n+obTnVoP6yZGS;ykhUiD_OJK{_cPMlzsq+;-xzW1_kY(M`tRy% zpQEMEX1;6v`xe+%>*q_2QPl@t?iYfiulQH+?b{z~b8kyG{|b&{@ZW%?Gnex}!v8Ma zyKYMz`1^l^TlL|;{~7aFQ=k9UzQ{rU4VE&#RR8>?>OA~Am1)k?Ht1Yqu9@`jo=i9K z>Yd$Bog)11Zp(C9Y$4p+JFN4VVUx2~PyEgQgZVxAzn{$T9hSMZW#rSIV{D_m%qCcYURvCaJ-@Ka5q9}~yuB}dk~x4_|+n#>3 z~6B|W7wuy}*AKS!6k&kU+qsTAg4f$aFGV;OrW#ohL%g6`g zmnGjYei`|sS#xHyQR|xg*4fXF0_3sV!uR{H+Q2#2_Ut`Sm-y8Jb8}wfV{Z~Q% zRnUJG^j`)2S4ID3KfS?zs$f4=u%9Z}PZjK^3ieY4`>BfknEm$#`>%riSHb?PVEs1hI|`a zsrY}J%QPO4Z(~ci<$vB4Zuy^K8b8Rlu_cUr8(YH2x3MLRd>dQB*uU3*g;4)qkK3iYp$@A~fz`j>ngTj;++zKt#PUj_Y3zUyD|UH_8r`j>pS zAIW$7si?n=E$m0~ZERsbl5b-R`;mMbTiB1}+t|W>B;Ups_9OXj|B~T7m0#=QQ_zoq`nzoq`n zzoq`nzoq`nzoq`nzoq`nzoq`nzeWGV4@LjP4@LjP4@LjP4@LjP4@LjP4@LjP4@Lhq zV~qNH{3H4J=3qa>Ka!7c4)#O*Bl-B|U_Zn^l8)wv)&Z84B5;3$T~f)-|hF=@+rT4 z$G_31I!7L$tZOOJ(`&Hj7j`+w`j^fL@O>#SuCHAWl5ZK%k8oV4$Mw6nTX|gns%PW@ zivB1Oo91u)BQ^)dKjL%2_(yy$82^Y*1mhp^iD3LAHUY*zGG@T|#}>~rWQg%DAK`f- z{{v4}c%jG_MII^gOObbiCo6oE^K#;yC_nI5ZC)$#U6BWi{8;48BA*s{w#dKz6JD+Z z9eaLZmm}=*JIUka3VVHoy`I9(%L$L%vj<+Tq_=rU*MrhsKf$%hu{R?}) z2uEJ-%e0eocOH>mUt&?4mlmzo-G0wB_1Dj7G2gq@-OsI@&KogB zg-sqX$)4%-<1SVHbFS$~2XFRVFZQ|9kvpUpem_>pwoGR&|E^?iKJ}{AU2jj>i#`8ifqBv+_v}<5 z|AM?hx@F40N&Xr8zERyfbjb?&_ddU3dhn(vCI7|MF00mC^qbBomBmB+C3#7*_46K(G5C6{`l4AsFpf!h}Im)rVR9hZqO0(kxd!s z2i>3}T!~T#@-_pm(#|E)Q=OC-AI1#w>0A03`Pe2l zihT0mbCHj2Vx!0>9si4bY!e$rKI!;kuYX)Q-RnPC>Tmk5i~gOWZOZ~Cu`{>^^sVn0^@!BT(I ze_ix%_EQ)8G5yy?|7JgRu^-d_V9~$XPhITC>^~R#H~kM5{hR&N#eU5GbFqK3pSswO z*?%tfZ}w9c`!V~ki~XDIT*j~2&tS11v;Vr-zsb&J{F?pO#r{opF5}nizb^J~vU3@~ zrkh;+kJ*1+?B8VPGJZ`rx%eNGU6=7|y2-`=nC!ZYU(-!4{>S<@7oTae>oR^#H<>Yp z{aD}T;y+C{b@4yex4HOF(@kCckM(V4jA5T|Ka%hEU!xx%zZw0w|B-wjzmo6%NAi9AO1}Fa$#?%L`96Ln-~Er|yZ@AY z_dk;F{!{YZ|46=#E&QkC+t|YYOTPOb$#?%L`8Kxj|B~kFw8~R@XGypGoh84?>7qRHoBXaK-~R3@<=XGNN`36Ru2N5v*H!9o<#bUVay*^2 zD(xb_u*k>rL48 zDeS)&cKxfK-Y>$X97_B$?Ii3EX5Zh0AI@QaFo*rY9QOM%`xwp@XWx6(x9n*+Z=AzE zVD>#w#l`GbIH#S%9$)soQS-TLXdlD5?i}|1a@aS_VIMGuJw)wSI47UO9$yZ7i`vI< zu0DsozZ~`rbJz#WVGpqmdxAOa@#V0$sC^9IYsg{mk25LS+hZ(;eZU;{5Vc?7dxADk z>x=<=D4bhiZylbs4ts^>PuhEb+S8y6AKmy~ zPY!#3=8M|i)nQLC zmoX#1`r+PU9rg;92cN5T;fMQ%O2_}=d&3@LjZAzoe%R00NdIAPQF-vu_-D=q_}-sn z;;+%a)xYcmDjnaA-?sXfJwfze_V|#20_EYu&(SO-P#D2=2AokB0Ey?$@NyUE3ULp3+ z*)8cm>>FbLoa2)IIp0z2C+rC_e#;&o_EYv2vH!AH$oMULf7rjq82S(UfY`sr82Y!d zRrUn&KNjn0j}QCT7(@S@qbcJz?EN9T>>J{LEY{OG1Y~QBA)oU;#sApYDtml7cUH!4 z*ek?;mc2jxkH#4F5Bq@lpR$KY-(3cW z{D0Y7B+gbI#+TQB5cxK?l#YJ9{+z=kE>b%B_xf`tlQ|3h4%R{5H_q$lMgKMO-F_tB>u;P_TmO>p_ES@T*T3Yu{Ybv+U-I34B;V~{@?HOu z@Af14ZvT?+_9OXj|B~PDQ}TWMO1{ls_#er4|0((I ze;oN5N|B@fha2EeB`96P1zWYzfcmFT> z9gH!z|B5k2 z{XPD4|D&^2lJD`GZSF`A?6Zi~lU=FiZSg{3r3h z&0;y=q-&9XL;e2@Pn-`6Sf{~rHKzOPy2|2^iHOkcC8&SrzGQzXaNCi>Rw ztDMi&7%6MBxHgPyMjICGwPajl`r0-zZsM9Wu2th2Hm+^)#eB!yt1)kw@y|FXoiR_} zfEnlX0hsYjzk(UV*dmy5TgE)&v&9kUY(`$`rf%af_&Flqzhr0EU#5J1EO@gq^K_kh z#J9vLUB3DZT`S!*ApF*mL%O!Q_+erDyVL%^pZxawPRl23-*wve!X~f7Zo zmUPM~`6;K!p`0S0ze~CNzSM{BNfb7--7eBO+d#X>FMh`52)le?FSpCvMSX<5 zp2C!azR2_aM_)UsrN<+(x3}a+55le=Vb`0mm5V-0ebBQo-<5h&PN{$FFUqEc{Ct@< z6FHg4)wrFjPLbP*oR3wt%>_k{C~`+?khjgb7s+()rL-CDMcBEQQtm%}KgYQjjR)sm z+T(ks2YLo5GjcMKtBD*=;g+>O;~cW~WSlqFK8$n4IqV7M zun(BS-e2}TO8DU%_7>TnXAc*Snmu{;ZQ-T0kK|l;4ts(*>;vYo_m_Q-Rr15$BKz~~ zK}&wvH)J2)=2da^IqV7Mun(BS-d_%TeC*q^x2`ou*h8$tz9IYY?3HT`VS5VfiEFJ8 z_5pL)`^#aEPqHZk{f9loI_w+PVXsiKDFeS6_5pL)`^#aEk9~X2Hb{QhLo~mwa|>Dz zg}p-a+d7jV`C%W>{I<>>us30TTW1X5dfB(Q z?EPgwBO&==Z?O)0h;`UEtixU*`|V{lf7u^2`#CJlyjjPLLe4^ju#`J@M%lbWTte6iyZWLyGdHpM&zqC(}eBbx1 zkni=ckni>9OlGM+=P*nCdy((;@Adf${Y$>@;Z{C>p?}GD{Y$>s9zYSylDrYjw_?3Jgzmo6cSMvRA zgXE(dbkwq+_PNdCee9nu} z$H?c57=29ty8o1X_n(sQ{$KLl|4Y96f5~_MFZrAo!$y(M88OBf^4-}*~=0?NWRBE#eU?Y-G0is zP3)(f)hzLkiXz_xMfv@%T;k_xMfvAvR=;(Z3$Q75gt|FH8KU z`g{B-`5u2tzQ>=E@9}3DzZzr6_xMxtJ^obvJ^qw@=61#y_T%w$@jvC$~^;DkdH~zQY!-;(drcL~q9x{3de-ZxE{IqytkABE}1nI4$@OYxuQt*~x4<$1fl;P~I~X8Kyp= zql|^^E<4&d>(*G<;G_dO%2?>%aPy8b7PdWVsg5!h?ETb^G8T?s;HKeaEPS(LmEonF z1L||8D7v-uF-7N=e@y8MlQXvTk;xxh`p(L=K5zA@)n{z!YpdtjVgpwHv0eT5iQC3T zut98*bjz=|p~!D?@D&+3CSPX)k#FT@{-1LBJ^83lv0>_oJmgY;Yge{D8|d3{hZ8-$ zqP?EKLJuy-^gIoELw-VUUT#94UY~@Xy`BmEd;Qff)}Fqi$B1K|_-&LK%Zhb~b&GY5 zZJ~{~9rLHI%NBWWs@V3Zlc=kxLoYXb-?eof`y%$yOJ7+=agp~O{<-vBMS0$L8rR-; zdb{5HPTafq9b>5Uo&2r$o!%w$zLV_-n=E}t{?d2IDSe0h(sz_w`i}aPzN4O{?=-(K zrc8$Yw8mQbJCrM1;yd*6?;HzebK1}O^2Wk615@8M*Z=9UU@=7B<>&2o{1-hIe)iL? z`x$#*)>yC@V&LHy*Q4(kBVW>3_;6fMCS`wdbC3oh;}E~@KMigvqR~U6hsFjP8)$5x zv4O@08XIVAps|6*1{xb^Y@o4$#s(T2Xl$UdfyM?J8)$5xv4O@08XIVAps|6*1{xb^ zY@o4$#s(T2Xl$UdfyM?J8)$5xv4O@08XIVAps|6*1{xb^Y@o4$#s(T2Xl$UdfyM?J z8~CrZ0q%hMPwQ@W>wg;D=%KNJ#s(T2Xl$UdfyM?J8)$5xv4O@08XIVAps|6*1{xb^ zY@o4$#s(T2Xl$UdfyM?J8)$5xv4O@08XIVAps|6*1{xb^Y@o4$#s(T2Xl$UdfyM?J z8)$5xv4O@08XIVAps|6*1{xb^Y@o4$#s(T2_;0X*gXTWHI%di5=&soQuMDZa{rcg; zk1YDa3d{Uyl<-`mSFc`}^-$q6j(ntA^W9y92WOl&&9v>B!f!3Gc6#ZixrAq3X0No$ zkvCSffB)x3ruSYO-wR%1rIBgM!Iy=n`t7JRc>Iimq|f)_ercK0FVw$Vy61!6NYnjt z>P-5M$1j@J-gG(P-a{r#&#kz%@Jer8SPgq@KjC4UURUij>E6O)PkgsJ<;rb8foFdD zimGRieU!da_Yu`oj~*nv_Eh&(*Ic=q@H`95lYTt&TEg?axLSI?V}9XZ-mq)BbIpfT zw_nbAcp7#39Kyf5_3$+RZIh~vD}HZedi{yV)vgtGI4Es%-BC(^>d`IJ#P>~{Xv>(+ z#nTb@EGzudr4yvdZrED*`5n)#Uc7mK;nlx!Tkj*cj}-pe4bxY{_GcHdm>l!pB7 z+4}Y&M|a<`&ezkU-|ftcefNUyjW(P!9l7#4In8!r_p+NlTs^zeuDKdJXZJ?eyjU%; z@{W0-yD#m2f45oFHC^lHLzn3|x8V7A9&^r4=R8xLGyS*ng&k*hZ~N%A)f)5eosYWo z=Urnbn=p+zdh0xFvu(P!{PhxP+|tYBpR99!_g&X)mj3qm6nWtv{jmF~CHGI$KJ?@I z$d}jbe&C)_=~t7?GkD0#w{@Ml%ZN1YM+a5&J-AoreGea;e!kpxYU5@H?3M0Y;|Ad? zN3WIUKWy%_?>(ztu*PO{rBe=FJN@lPi;tOl?R%?p9^WlZyzud3R~ox!_0YSAr0J&I zqHn61_Z|P-o1@a=OHJH=`mwLBu-YF-r8}OSvA^`uSFMk>TJ*TyyZ2~~quZ~%eej33 zwEFk#zv)O_-@0~ zQPZuOHl1wJt`XaBoSxlv`ZV?9Pj=nC^8Tsgh#yyr_MF$fPVc_ytj#W|_SovQ?rXnu zXd3%Ls_t6gYu(e{Ju(fw_}0N2&-`)Mx_9oK_Fns^^&9tG(YfE~P132Or_I$p?+!nE znZ?rguKrraR^NJm;`G|!mckF8JZ)P4qD}JTw=dqk*Tr8+uT9XK-@EO-Hh$Oew#!eI z&U;|f{PU-8=(@6cvHHU|cht9&Jv&Dld)hj}Z!fx9`rVYn^8U{rG;E?fzm?X%{P*>8 z9rJfie8C~D!nz&nY{x)oV5GA=l4!O7;|;C%lo6drDu>4(a6YzFhtEH(lK;-m^>^vFH-%yDRS8_23UDN++DPReIso6+16GZ*;Zc z)CZ)Yk1sQP=2x!h9Y0M=|6|UbpnmqRtueLL-^UG}KVK_7_R&!eIjO*jJst+J4Iaz=l(&j(Il~ zp6CxNr4<(H7T)?dyQc5I`Jn7==lOR|Q>^*4@USBfNPGS4OySwgrsn?M$Q3B}$qh%O zjs7;G24B4Vj%kOxUlcy=&tFg1{<1$6;m#F9TKO2@7>|0g% zxNkgIo%ZUk!ZW?MYPH2et+6oVsNatN{_`#U-*n7=_4e0|P@aRAT&+I8ruJ zSAXrdho#Hb{zuoe>s(ZC@avZTA9?cLy6=YF^z9LU9aX>n)Iq|x-?RGo`QB;CpMQz1 ztEVSy_3u6}{khujQ1fN>v;C_Jr*A#5yzsu?-YWI|ej?!u=i59jz2p?ayB+-P)PKZp z)W(@!I6S?#?}Wk=-f(!@biv7M@-f84M*9kv0?>Ev`4^ERwpMKLN(%ly?BYfUE z%cYBdxTx?PJ8hI^esqRU;GIrbCT;VbC6qqvs-0>2BU}CZt5d$7MlR8*^y^pqR(k8E zKdP*Ghaa3q9<{shB>xzd{`TW@WlQ~6ACPX@|BQ+{Tr|n1Y4L-mPT+}l+9I8}_+-L+ zuD^1c@X{{fnNON3opyf9h97?D{A%2`E&IRcyW@IqpTDKUH&&Xa-v6Z5SeSZ=E9JF1}=Sdg8acLtvT_Jmt0%F*|oRw zOflE{gJ(_B8ei{T{!s6_qg(i{^{=iLf2)<}7x&MWo}PC-+0#N z$ImDH(8z7l*sX>L|M({((lwjyFFkDdw^8YjyIeLNJ)CyyL22q+j*#A_zj()Vch?KT z8{M{QI_~&knLIn(u}Rh;;pUzo#>%W z(wtwPR_QnYXrJ`_JD2O*>lPT99(e8_8dEpib$EJtmR4MG>iBP`S=aq_MY(Uix=Q-d z3Bwb3>OZcL-oAWZ;Vt)EBrUUj%T|A~=AWvm{?xMJvoBk(TJgq~ZO^{WKgK`yhgN_6 z`Y(sqb5772Q-?kOOg-0ot^5z~bZ`B;hg#z$_R)*EuHQd(PnETD$0T{xfh~nkdti>d z+J)-~?>p0r^$dILC_Kp|`_!vF*^|D$V%)69*Q(aou#|7PF_}XWTaM*Y383^Q-5cPhx>nbp+CgV-V%8^jjD z*dVqD#s;xPFgA!Sg0Vqt5sVFDi(qUJTLfc+*diDk#1_HWAhrm`2C+pjHi#{Pu|aGR zj16LoU~CXu1mh>L#gAir2EK!Id{q1~Vr!H-njznVZ4P$;{1Q=49q(Fmp0Za5ObkUV1tx|fmI4z)5lexIp@^lx#8AXiU}7j@DKIeVqRijFflK&FPNB@*cVL9OY93K<|Xz86Y~=Lf{A&FeZj=M#J*r+USeM` zF)y(%n3$K?7aaSD^$P12(pjUhRspj{VXXpYjlx<5%o>HY3YawtYZWkS6xJ$W)+nr1 zz^qYNtAJUfuvP)HMq#Z2W{tvH1~3twgj`LWNis%P0894%$kz5C73lOYfCU|O4gQO)|9L* z!K^7+TY_0rvbF@XretjiW=+Z363m*CwI!G}C2LEihdzQ2fD0fU4gf9y3dY0mIqA z-GJe2;BLThHgGp!I2*VdFq{qC4H(Ww+>Jpv8@L;i;cVb;z;HHjH()p$xEpZnBltFW zH`3wQ;M%}&Y;bL0I5xO8FdQ3P8yJoat_=*w2G<6LV}ol0!?D4&f#KNT+Q4vZaBW~X zHn=u092;C47>*6D4GhNy*9L}TgKGoBvB9;0;X&crK91o;;YLY^6NMWE!->L;g5gBr zM!|5RaHC*2QMgesoG9EV7)}&!6bvT{HwuOmg&PIKiNcM7;Y8s^!EmB*qhL5uxKS{i zDBLI*P84nw9Q)|VJ$KJ5&VGl|e|FP|Jm2s36+Yph!}H}=O((qnU-r)%?tG5$#Jg^p zUp!$F$)9tVrSpszd{y|blTDm=+juMCQ{OqdethXxUyNPqq7}OT-m3psUpw>0bv|g} z!FOh@uKjAOA20mJZ>u9VZ}s&-_YO~2U*C!+AHQ#%^u%c`KfJ;ryQO8`Z`sW8I~|fP z>HLQ3Gw&S-rR&GF?8@4bN?RhfcBRm+6xx+SyHaRZ3hhdvT~%n;_|UH9L%ZtGt~#_U zhj!)At{mExL%VWlSG$kQCUdb#v%?(hFb6x#!47k%(_>fkp9gWsrw z-^jslx%YQ%kCj&MwC+6k3C%Rz3=H-fcd4hws7_fP{mw9>XGk)7|^K#9+e9qZN z^x3>zhk3aU^KuUJat`xy4)byj^KuUJa%Nucy?OGk*hdyqHl|vkrLmZVu z9F;>Hl|vkrLmX9yII0eDR2|}|-VjGsA&yERj!GepN+FI)A&yEV*0s2|jV*Ct>k#+WA@0o~?#&_Y%^~j1A@0o~?#&_YZTFF_Su$&u zou8Ym%hoBGb;@6#o~hf`DVcT3sQnh`wslHooigz%6Lr}-C9_UBr%X8K z0)4hl$*fbJn&*Q)Tc>2!DGT;I(QoUNnsv&Ie;+qs>y(;x%6xz67-#F0nsv%UGj@-& zb;@|wDHFUl^Eg|lRIF20dF8y*Sg<)(W#?z44D zVx2PV(TxUdosuTBwd7g{Y(ICwKi=f&xolmTSXZ92;A8!^u1u^er~KxhFS2!IVqN*n z-JSimu1u^ehi^aMfUPSl)|HRnamj$KD|=a2zA?+B<7{17v#wnFnPKB>U0JiP{Od1= zkF#}U&AM{KWzQY3b!BE+5&wvvp-=U3t=c!}@Gp znc?VP`u+hOwyw;qE8iaelP+6VX4aKs-<+&F_K|S{xo`r;1LVL1uzysvK1LVL1 zuzysvK1LVL1)PV=60}oII9-s<5KngrS3OqmxJU}X3jd22PY`jehyiE$cO$xkC z6?mH}@HXQEZ&L@}CI{Xo2i_(J-X;g$CI{Xo2i_(J-X;g$CI{Z8-ABf`<-)lc&z1wv zmIKe01J9NN&z1wvmIKe01J9NN&z1wvmIKdL2cB((z_V3>XR89wmIBX~0?$?zF4Q=; zHa1=~1zt1-UNi+>vC&_7tMhe&4Cxqffvnz7tMhe&4Cxqffvnz7tMhe zZTFG!*ctwpINx~e437;q9y`NhgN?_|@YqU!azuv51{;r^;jzKSV`q45u<_U#9vf^t zc813W8;_mgvBAb;XLxL|@z{0Xu?GW>T?HPy3OsfSJa!5^c2)KotW9lfZAxL^A%%U1 zD(pK{Vc%i-uM-R3(WjK1UwJF2VgRM;&jvj1n z%5d~xYg2}!2V0vm96dPpk=bJ|dq!r1IqVbVuuqi3K2Z+)L^xH97Kjt$A z!@gb}_Vseu*UMpFFNb}-9QO5c*w@QpUoVG!y&U%Sa@g0)VPCJ^N9ONy*^@ONpTj@GM9-EUh9Q`pr`*XL=$r+A*#K~)S+nk)?=)XVw)()GKGaUUw&y5~tb8-&* z<~i(}=df>{!@hYA`{p_9o45PO;;9V(OB*eQ%HfCf|4(C#GIG2*cxs)8vrDQmIbZaqh4(C#GIG2*cxs)8vrQ~ofrQJui zUdeFu$h0*|hNB1D8l?{Bh;lebl;P;fV{4QQM-R3&N`|8c+ZrXq(SvP`lHusVwnoWt z^k7?~WH@@Ttx+-@J=oSL8IB%oYm^#}9&Brr!ElbK3g?J=!#SeCa@Nb%lx=Kl%HDA9 zs|x47RtV?5YB+kzvNdH5M-R3&Wrm{%+nO@N(SvPGnc?Wcwx-N*^k7?4W;lAVttm4c zJ=oTi8IB%oYsw5q54JUB4(GmdIQNy|=*biN$oPN^|4X`Y05u#v*f@Y1jvj0rK!&3S z8wZf#=)uMTWH@@TaR3>P9&8*yhNA}?2aw_D!NvjPa856Wb9xz$o;=0@WH@@TaR43Hrji;&M=s%8)vl$OZPr7k7y>Rqk<7@`u=)uO>)Nu4* z<7_ew<7_eu_$l4(FD0 zIJca`x#b+rE$47&E@5w1CXcsE*xM!S?GpBO3CBKiJ5;*cp|ElD z*rBj-^Vp%Var4-ruyOO)p|ElD*rBj-^Vp&4Y1}+^DBoz@Ja#B-+&p$DzhT@wb|^g< zH;)}A+GX54b|`GzJa#B-+&p$DY}`C{DD1xC6WINR(v6$PZwMPVkKYhBZXUlOY}`D4 zL)f@^{D$gg+&q3m*tmK8hT3S{Jbpv%GHxEfp>*Ts@f(@87&njK5H@ZezaebgJbpvi zxOx1BuyOPF4dK{F?(_5P2b|jPem*bx(s{$(&*u}L7|Qv1{Cr-2nln4y&*wKfe%TKLReqPwPdHj5RPRE&?pU2M+{_4n)oS(p%eG>pTIsZE8XYibkJ9S z!ufgT<#h8}M{s_gc{z>z(`B5WXI@U{U3(tq=b4wQ``6!q^YhHhz5Va&{5GN`4{4c-j^m#e2bMX0N zeO}H}&HDA>v5!2CQa^eeC2ZV0ag?xe^TbiY#?2E)340tR>~WN^$5Fx_N2&fEM+tiz zCG2sO#+t`b75eu$DuF$Y5;kt0I7-;KdEzKxkE1?;J?>Sy$GyVF%@g+u8#hnfE9`Nv z>fmv&u*ba`M;`a8{vP)Vd)zDRac`#n9`_1++$-#Huds3R#J$4C%@g;wa4Xgo_H|0W zXri^|^mU5Tjhknkl9wGfqTjfA)+za}m%iI?+&t@)eEBS2?=o(lbxPi1;rF_Xn`fPp zXFOo;ZsX=zr(`>d({0>5>y&!$L$B;MZk}~YZTx(Xar3NGYUAg7jGJejGT!+49$%+a z#?N;fH_tkyGJd|>xOvto@bg{9&9hE{pYJqoo^?t>C%%^a1om~M(v6#ET?s!w%(!{h zmGJXj#?7;?grDy=Zk}~zW&C`%ar3MzdySv(F>ao9Wo`U?k8$&?D{JHDdyJcBU0HAa zWM8*&^Q^y+5^8mum0|+}0AnZJVu=4=I z&I1TL4HxJL2_g-m^PUqS3 z6Kf6`Yur3MTR#2IlaDcO9-d7yjhlyO6EoS+&ny6LRZGk!?OuH7pgoFJ1?p{#?8Zv3L7^MFDh)@JiMsBHEteWRQ}nx zd3e#9vW%OD7Zo;c9$qw)ZrnV)sIYPK@S?)T&BKf4VUJ&Rp>gx@qIrjHe>cXsd3e#h zO4n7xjhlxT%`Xm4+GX54ylC#4bB1o?=HW&2cgM`%8T-h2Y{_>XTiCdHcx++g=Hao0 zjhlzZ7B+4k9$VPBd3bDLUd2C_lv84y+u{B3Hk1ZWKk1gyxc0yOq zV+%WvtvnI?zJv1kzJsvuJ19SGqHW0ZeFw$ozVA?z?)whHzVDDp_k9Op-**u9eFtIV z=Gk`;Hg2AM2Vvvp*>?~&Zk~MyVdLi6cMy(!jUpY!F-g`!)M@ zV}sb@cB^mMg$-hhvz~GI05*s%K7Gm*arg{;$KfmeVgR3k@925-=ze?#zT?!{zuJw@ zz<0d8(mvhz415RW#y;|WSf%?utS~+vUr&B~JiZ=`kH^<5-F!U09*mF2*Msr#_afz z4#IxUL1QFhKbN9BelA7W&!q_axfI!kpG&Ec@8?ofH$Rsm?B`O1{alK$pGy%Y<|Xz; zj-N{r_H!x1elA7W&!q_axfJ2pM}Ce->3)t#*tmJl5vk6sQCO=`E^8FlDq!R0IY%UH z+&t%qgpHf$9Feeb^PD3RHg2ACM8d|+bB;*ZxOvVI2^%-hIU-@><~c{CIv6+4IU?zk zH41AL>cAR>wF=nJdMQuDe(pU;{hXfi_&GgcKc^?`=k$dAoL(z`>ztl28~|JZb$|na3jo6b zzy*Mfo9CRKuyOO8(^DOco9CRKuyOO8)03W!o9CR~c)s;>ddd^ApQ}_JKUb-~gR_CV z;alV8IajG~jhp9OrRreZJm)Hfjhp9Or7)Zg+zsEt*}&a^;cVb;z<#b$*w0l8`?*SC zKUXR2=PFePKUXOn`^eA1D&5b)3d6C%wJr2s--U2&aBb&qbM06-Hn_IE-x$#c#|GDS z;3L=d!Lh-$)ywwx!Lh-$J$~enJ~%eGwq>sv+X2T0*Oq=h;V?KhxVEh}9XlT!8(iC? z-&=G(I5xPp>3-ZZ9F7gHZRgF8?SNy0Yn$_%TX({-!L{vq`V?JoY;bLF?$_PnXO&g| zi2dAh{nD`MI^jg&Mqe7SN*A0c-00I=UegID3O9P_b}x6piNcLO_Qr39!->L;o;d!l z`Qb$2Mwfi8b6z-6xY2#4oOKwSDBS29vybk86NMZ7)p{?EffI!ry?EyD^}&h4jjq1N z_&zvMxY6AfIHwOz6mIm6XNLE|iNcNE@$_V4;Y8s^>G#-2e$HI!e$HIjxOvW*3mZ4j zIdfs-<~e6BdoXUEbLPUv&2!FN*tmJlnF|{?&pC5pU$_VZX;A?Dsf?{T_#~-{TPWdmO@kk3-n+ zai|V{k3*P!JUDvl9I@ZKQM%u|5%zmG!hY{Y^8Mb8u;058_Io$Ne(y%u@7)Nqr-$F5 z4u0=O*zes4`@I`szjvcL_`MtXXTNu&^w>x2$HM<2pFLPOdN6yiaP(lmCsq7B_oS5H z?@6g#zb7T^_oRgVo|LfPlM*&R&pjz&_F&=YDT_T=ar6e+gN36fnLSuIdN6yiaP(mI zVBzS&?32UMe;l)C4o6SA-)j?Q&m4}PboR{Q=)vrn!_kA;Gl!!Gvu6%R5B7U)!Zt5+ zuT9wRwF%q2%)K^Yzt<-0_u5nkzt<+ro_Uy;xz|?a<#r!&-T{uDI`}(~tj7*6-0k-e^QtG!-R<`f^VaVSc5%jmIO-QKAJggg z5LIW+ID|Ngdx%Q+dx*k*4^i0fAqx9FL}9;&sP}C+hXO~>`!)shzK!1-&Ae~p_eP~3 zzc(s5es8oTvvqG&*zb)B`@K`Lj*?;<_r-WJ(x2@aP(l#5W&%dZJokBUtz!JE6f=p zIC}DMh6s)x%o!p$dN5~*;ON1e^P14kdwm@Hy=K0qX%>53yvPlnJ+kc zFlWBt=)s)%f};m><_nG<%$YAZdN60c;ON1AFI$*1UvTuKbLI<<9;`E8#?ga0^94r_ z=FAryJvjD}->Fx+-=nXtx?t9B&gj7dJayo2JN+JgwbiJrhWR~u$@hEoD%bDP3;R8K z)zk0M3;R8KVZTQ&?Dyz}{T{ur-=i1yd-TG7k6zgC(F=2q5{{lWM(pn%DBa&Z5cYQu zg#F!vR(k8*17UynK-k|s5cYQug#FzEVSo2P*xx-6_ID4YAAk2iHt+8qR10tY{dxV} zgX-bE_v`R?52~Myf4(dB5$9pye`%w?Qz7i{R3y^DGh3~b=pcuPd-oLMf|-xX21 zzbhi_?}`ZfyCTB=u86R|Dl=gr}N=@-tJ!_k8|V-80T=8QQUz0zCnzz7?U%{wrK$L1ZFnmn8_ zhocAkJ20xhzXK!e@4yKAJ21lj4vetB10(G3zzF+0Fv9*0jIgzXw|YK-xf1|KPkp!( z5cVB-w@2yR2?+ZRyxXI6?gWH=2j1;bI(Gu#=#j~t062OucLLz(!Q2UeqX%;*0FEBa zod7s`Fn0pr=)v3xfTIUQ{1@;`+B^KCH-^fChY6+E>@!4*hk!#g8wC*J5q4;VD3o4 z(QovJiMzQY1xJ6?3%7T3M+%O9x>2+Ca7T)L*tOPMw1+!VaP)7Swr~%3q~Pceo@0g{ z?nuGWZ+!fiZsX>8$1G2A!#6oU&pT%Mpz%ND{5o_Eahj1#WN`FY+k%Wn=@vWGiTaP$uiJ-MHIY;g3O+;kS_=Y{vUXT~AiX@jHR zZPfdnHYfA$Tt4xR`Fo6;=iRw{+}+D_ex7&d^3ijz#QAyNoy)7Ox-94Cd3P>PJbWI` z&-3nFK74_vIX}<4b2*=|A?N3LcP@|3mv?ig4UT@_L*D7;P8%HkS35gA{;%KJBV=fVD2Eo(Sx~z2uBa*4k8>q*xv~h<_;np zJ?Y#*grf)hJAuO7L4>0xnLCK#oC9w;D&1n4d+tYePrvE1piAO?)bvdgSq1iM-Mh`o_9Efx#Jto5%CVE%H@tP96kAs zo97))`D*U?!qJn?9bY(lFn4_6=)v6ag`)>^#}|$s%pG4idN6l<;poBK@eSvQ2E#cb z-bz&-?qnCtooqOIzU5AKIQPZ7sY>Tgb~yLNyQxa&PBt7p-*P7#jvj1l$^=Ib=1w*o zJ=oTiyqhX)Yf9ctl?`(z8;+hl+{uQc2XiMIjvmaN>~QXjcT<%f`^fkJ-n>m4|LLY~ z;{bT)Htjp?qVmpdTKzYVcXNjxj{cde7w+K>Jsf@4xg&bGLk~y)))Z&;aEBg_{*-Ai z?%@tS9Q|~MUEJgE+}3a0aYB!A0K9Ws_it787&p&5xAlFCE#1Q%dN}&)_L#4SJM?h$ zo2@%R4|nL{=&!ot#%}J=!_kkvZ<}u80LH`7-*x}UF5>`r=Qc0>+^@Qfr{OK)+&Rm3 z-4XNV0UZ5~6I|KFn+I_8Yi{1#Y1};T66Yz-o}$}0n+lG8*lp)@^X35@{W@Ryb2o1u zz|n7d^~^oIc>qVh)WnPS@a6#={ZgY-4{sj8(T`d22R+8wBslsvpS`GuHxJy|4GhW`Phc^%4=tn*?We;y2z|r3@`#I%ZV)YU4 zRlxt!zr0ZaM?b@P6ZG*$1swf#lPulO8x?T$Q|*6YA8%B^(U0H%wz0fX0Y|^c>hF!= zjS4vWv5U_>mNzQk=${%g#aP~`fTREBmZx{{Mg<)Gt2b`n!5bBD^nV#Pwu3h+;ON)C z?Zgh=sDPtCeEmNS=Zy+D`X^@Hb{KC|gmbXH;T$aQNN4JAJScB{e**KS2pm0mcvB>t zTjt$wrSql;9R1nHy*3|jions|{^nl8c~b^v6s;+t}Dg#%EXXzqExnVBqM%ya5A859SRRIC?N|z`)Ui zc>@NH9?TmsaP(l_fPte2^9BqYJ(xFO;ON1;0Ru-5Hf}z_(Svyd296%g8!&M6VBUa% zqX+W_3>-a}H(=oC!QPfnU~iYwyJnQa!z0iub%-H&O?0m)h>_ z683f_@_4(1yA=(pBqip!EBXHlBH+LxnfkY*d=-(bGPGW1jf! z&5zle5PSYe^@(`aAAcvExZWvBKY8l|)A9?QAlxz2L22@dkNE_SdE&RT{r%hNjt%cp z{)o@~VE1&*&c9On5tHnhW;^gE;kzc@E6sGo_)p-NCw@EmY}=+q2Hscxh`+JxcBym7 z+e+W*r{7HTZ}gh*!f$S$RypslpTIFs{Pz95*Gt>)G@JT8;zuUfAZ@qYEJ}aoqz%(o zr=Cf8)|od>FFrc`CveOYzujuF71A9iEv)ncqvRj`Sl|EX)jJ3u z^`d+CUpZyPS~zvGEV`7z&J)8&8RXPM88B_39aqPxlVy2Uo*Dhb^asz3oPOe&!Sp5l zcy*jQS(dS4%+OEFcrs?l8E3`}j4faXSI4Q7WwAAE4*kT~BQ}Q|JH_U}*fMr}b(}g` zmbt>5K|e9`i8+IudB&UpGZ&eMSI4Q7Wm!vDQ_xS$dc&H6oOOsb1B6Bgk2MSYN=bJ*+`j$ElNLOMf}^7r6A78)xY+x4Nng%h8?%PMs`U&pX8P zE^s~X(E6mFcW8Z8eK#~6%>|udZC(D+-4PkE! zT=q6Jn=E@9nyr=%4`I&>oH|*y=F1TCWr1tH3~f%;d>PtYt2sEtd|cqv$+9)y$C&R6 zT=RWwYeLQUv8@%ghK#YEEO6>%*;=p0Sg#hi)~m6tX|-OBZLO;{aE$eEfm0{TmhKqq z?E)9y$U2CfS3M)^Be>c!#(KWMsgq^vS;u%^EO7P5$T|pT_0!1u2(G>y<9)Qisgq@E ztj2iXEpUzJ$T|pTjq}L*2rgR~<9)iosgq^P*2Z{WFL2r8$T|pT+3Cpo2rgS5V?VIK zsgq@Eu8gtYSm2sZBkLfXHP1%YM{v!>G4?YHoH|*y=K2`>u?4R6U}PPHv(|}`^$}ca z$r$^+1x}qTTWi%A`?m$I^=xDvgtOMUk@XQ=YvCCCw*^j}ENlJcC@XAzVe1RKJ!|3A z$+CXl0sh2(UdjEu!tT$taOz}PkC*fld%Ps~cnRAc*21ZiWo>WLPi%XW-1a7HdtM8t zPL}n2k$z&&7s)+eggqbE!l{#GJ>N(AKe6Y#PL}oiPWp-czLVVV zJ7K?1*TSijW&OUEeqz6`CHMPU*!zLCaOz}P?>D5M*!vC1z26Y_er7G4I$75HCFv*j zeo1ogmxR3^TMMU7mi2y5`iZ^Ylid3~Veco`!l{#Gy|Gltds<=EY1T*PAZs~m z=+$xRu$H&7-fv4kG4B)BL3nu2us(u$7qNz39j8u~_4k7G6Z1Y~9fXJXBSS5= zs;rynCoVqD1SGF|I4cllFU%T>e&W>0vh1~4H_=aA{lS@r#%O3pSbLiGbPE(PC085=39z26#c}h zlV$lr#3ZkI##xy#--4{6=qFB{EX%hh>n8e%Ydzr1Q1V(QI7<}fTb4Bx z{lux0W%*WS-9$fet!JDcN?vOf=ZC_4i?fEJpEz~0EP8j@`Q$U|)VQDVf2V$!#+xy3 zWB(uH4f-#f|LAd_laDN0StmS({yN|jv?jR?>wq_av#<7STV>V-_o2Ton0Zm$Q@dvT z-=`n`<9YC(oj0@o+@G@z{7-CP9oG2&>^ouBcR$a4tB#oMVYY|a24)*rFE-Fm{mTE( z?|0kS+$ZXY*&b$lm~CLTf!PLT8<=fiwt?9OW*eAoV77tT24)+WZD6*6*#>4Cm~CLT zf!PLT8<=fiwt?9OW*eAoV77tT24)+WZD6*6*#>4Cm~CLTf!PLT8<=fiwt?9OW*eAo zV77tT24)+WZD6*6*#>4Cm~CLTf!PLT8<=fiwt?9OW*eAoV77tT24)+WZD6*6*#>4C zm~CLTf!PLT8<=fiwt?9OW*eAoV77tT24)+WZD6*6*#>4Cm~CLTf!PLT8<=fiwt?9O zW*b;9Inw9fp^#zCee3!4-`O7K-1yU6nEPSwhxK6t|DD&C`Pt|9>}&(G4a_z$+rVrC zvklBPFx$Xv1G5dxHZa@3Yy-0m%r-FFz-$Av4a_z$+rVrCvklBPFx$Xv1G5dxHZa@3 zYy-0m%r-FFz-$Av4a_z$+rVrCvklBPFx$Xv1G5dxHZa@3Yy-0m%r-FFz-$Av4a_z$ z+rVrCvklBPFx$Xv1G5dxHZa@3Yy-0m%r-FFz-$Av4a_z$+rVrCvklBPFx$Xv1G5dx zHZa@3Yy-0m%r-FFz-$Av4a_z$+rVrCvklBPFx$Xv1G5dxHt>Jf26|OLwPD6{Kg>4p zUuy&N`Zo3Fe~W(j!ugNpIrXgTg4Hz}tov_66=xs(>x$9az-9kK?Dj}!U9g|AagJ5y zKg1I!|3ClU+|(CyKg|6w+rVrC|7AA78tnhp{k<|3nDys=m~G&HW&?M4>#Nq>{pZJP zZ*%z%ZrfetoKO1nqxzq3eLdmJ4|sfk@d4lKc!m`Ze@cJkMIRMT{gkJE z@?5yX@%;miK6444jh=CAf2$|mR6M`?=jZkx{oB2Tx4y^G{VBhGfpF@lJoS_3{udwB zpZbN9RQCLP9MK-*@a9MD(|_i)Tj;q`Kjo>PJX?Km@BR)4ZLYF! z>+aWo^HUV$s0m7&L`6s&zfBa!0LIdFm%m z@@Ku-o*JXEja`k=*v7QRXl!F$V>&h)Nd1(je)5!!jm`GT#>QroWn*Kr)w0R4*>LKo zJoS^O=E&IQPR)_A&8eCrW1DL=r^Yr1Q$OXYpFB0k$2RwCj*o3ks5w5iwW8L9v8^Gg zpYqgCo?5%cwx-qEHMX^`)~=zgfwguGZEdWzYiMg`t%0lBTADm5PyOUc{;c=IC+)NJ zXXi}w=t29Rv~=OqC;aZmp0#wyiV5HMkdH0>;M3E*OZ}9me)6n3{f$fSyXVBSlQw(dW$-}FxT^aZ>3?|A<7PI>WF2llsn?X|U@Bu~myKY5Zr>)mw!L;Fon z{Fc_?w{3q!zsJSX`utB1KeE5;XHS>>;}<`tzv}sq5l;P-r+)Ih<4ec&yX|_R-Y?^R z&+QL>?Ed2U%A=pz?|A7M!e86`u>Pm_y-YauQ=ab)mqFq$>tABg{@yY|X z7JlwGA2t5nRg?Yv;{Jz?zd8O=*;VSNJoS_3y5Bu){KRMeO=VZy_^IQ^_E{tRw1+)w zJa_9i3V-)qM~_z?c%pFXr#$tOXOFWUIqv$i>#NOwb<|$tHy*u(@c8AW@h{#x?SFpq z>pPA=yL?y4Q$OXYpFDT|i>=4&oH&i|#rx9-0NmXcK3ecUyA?K zSDx6t;O*1C>r0!xxZCFJqa;uLl&603?0DJn-F>f^cy95mle*2Wn0RjT&6<+ydf@zT`Kr+jAj{+Pq2 zHGkE{2lcCtnb!Q})lcoey3Gezj45>TEkO6<*A=MkNEea`WK&b(!lO?&l8{9fAzZi37@%iY`^D^ zHx>TI4Ug|1_L_Gtqm%k6PyOWi{1MOY@AbM@sGVOt?-~6@pL(nC`<`$_f8}dO;cvg< z@P7Es=Y&%~<*A=M_kGS&`&ZrRgDQKgJr3^gx$*CXH@^1+`}6K`TiL+Q-?~%(?%z-A z&&xl2^Zw2s*;n$%e)a3!6~8}pvXgz^*q!j8X9*|gjv-I|yhwr~;vf<=RdFm%m@@Ku-p1=Rt7l+M`JWS7Z;Y)u!yz;k)2;ceZ z8;%=p_~*j6+GXSMvXiFwZ|bK!^^@mOH@n%m;SV1sp1*p>?Z;=nVt3&!e!nzc^vY@d zJmbClj3;)}_i5^m|<7W;TuXm3tWlM*hfB5*d zCr$R5`YBKSY@UKk&?9^S!3E>+%1(<#7Egr#1gE=e>T_Wj~$lL*X~XT9ef^6~CnpZE)L9{a*icVFtK@9tZ@@pIi>&Yt#No1Al5 z_t6a|n@RnYr+)HWdy`AL3$FDf@qc2QOS=aiJn_8tc3*w{~`r`eBlPBe=pFGK*_5RC>pLF4$4Xn?ppYqiI6P|q!>(Af+QkDJii;w7k{Ov*biC=wY|F)06N%*Y&kM8%l z@e7164E>a+e)9a&BaiDJedf2-=FgmSO#jf=Y}?V!eU5l;f9wel7e4*hV9lTYuta zch~q{di3V~{k54w00$D%2Pjil0WOs_S7TyzW3$v|CjitJ8sn9=05@~{(4#yk~8J0pFGK*^=5mPZ+g;j@(-sy*e*|c!*I~kr+4T@Pk8U}+e4qG_OJT& zCx=gddTM{_r#$tO=Qn?O$#Cp{>i(J-`Q;! z$x}b&sh>QT|NGs>Kip}uhxZ=WkGKEk4&r&<(;hg!?6+GAf8os!8xK2f`aVtll&603 z-1w+1#*Gi%OFW<7_y*&bU;Rko>mT}~;X!*nPWX4%`RC!VXH08m>Zd&QljkPaIdd5I zpT_si_ug_i?HALU|MR=NdDRN9`ET9%zTE+LpX}k_TfD!!;mGdXGQ(W4GvE_K4}5G4)fP z`pL7?*KXRc*?2#3Zg7iR^q;=%)aO$T#^^@mgzudZi z+fAl5|E7P~z2A7}Y0W?NE(i68b<>)E(Z`?KuXydW=09=8^ZFh4p4R;Ht~|cK<*w(f zVuB}6%2Pjil0WPH{Tq(&Z~IRNYn}hZtB>u^*!M;Q{I~nmbNaXa`Z2=i?{#Fq>V~fo zPW_ape)4?jBm4AU+3^-5oTnUkK>xwrHxmB(c8BzzJol&KJYmbj`)mF53&N?N^3+eB z@2@$$KXCWYsq9@&eOCX)<6kel`E8!pzklcZ3qR~`$M-jQL*X~XT8~;51qVif9w`}s;+gxKf3%5{rINo{OX~bZ`_~! z+G+oM#NYl~_n==-d!8%$Q@Rr$@oaJa<0&`m9{0rQ{OYxzdfA5#{=@Vx_?M$@J#2aN zNuHc3PyOUc{;W6KbG_>Lm(>v%_-@Wnh^5dquUa~Gb`Q z`YBKSZd&Qljrhx-)7k6x6_(`()-R@ zb;M7maevBq-|lgDocjNxk9>dk`AepLd(KwZ?pNJ+TJt}<>FxV}-fTLfOP-Xce)1%L z*87Kt-LYTuoZa+{_gb-Yf7Pe%DSXwB@7h1;meV_Wvv=;&f8h~Rf2MxQQ$KkqhaPhr zKJ>uUgC3ar;RUCD%2Pji=ntNsvh)+r52pWkelY#Y^MmPco*&FO(2wBcNqOogPx5EI z*ada~C-#CJfUzU&0E~TMH{jGydFm$*c8wiV7JJ8z!OR2f7_9kG^8}pwDNp_6VO}y1 zDa(9i9)g+2%tJ8qn|TXP{gkJE^02P3j!>5MhIItYI>b5xW_@Da0jGY-Q$KlFvstex zyDpe_2=5H^dAIP+0Q1h_odM=u#5)7bJBoJ(n0FWN3^4CB-b3I&;S71|Cr|Qcz1g0f zetGuNJ#RPhpRv!zOTYcM3E%LT{ntG1stLd1X@9x=$de|V`YBKSSzFe_{UtW?#d81)TaRPyOU!KgIruvh1_i zKY`hQv3~-yFJr$2PW_ape)6zSWM4>G_K)lf!R#y97lPSuvM&U)4`p8nW`D~55}Z6K zPyOUc{;Ze%GW%mV*+;WK25Wy^`)n}#ZuZmQ)K7WpClC95_V<+KJAnN?nC}Dj_h7yo z^gU28^;4eu$-{RH-!0JaeZzMPnC~9GTflq|@!bOEJBjZWFyBvn|A3Px<*A=M$)EM| zJ;(POoP6i;{RZaykMB1y--Uedfm1)_sh>Q2kMjLVS-w;G{si;=%J(Oj?^?cB!Kt6} z)K4D1r}=)SEZ^CDKZE)H=KC4UcRAnN;M7lf>L(B90et^cmU9BW|G}Ie@cj?wT!Hff zaO$T#^^<2^eC$()vmefSsEacp&U(O{6>-)B<_w9m9x!K1ob`Y?bK> z@EW!8bv7POdD*n?t-0fg!+94>ZAkr;r+)Hqj>x$oZR32Ab3-uaj+`5UIgjL=5uExd zPyOWK9F%iU%5px+xhI%&Q_elXoTqY53Qql$r+)HqzRP(oWjXidJQvJ)Fz2~o&WSnC z1#^DPc`lf9WzL1c$&>QbPoCt@dO7FjTpLc#zd6?ib1u%gHkk8r&cVT{pYqgC9?t1G zm!~Y}_ngavIoIc09?W?^=lI~%PkHJm5BCq;H&B*)3GN%f+*fel0OlTp`vx%g8{9X5 zx%c4S0-QW4PyOUc{;ZdK817x*9|8UW;M7lf>L(BW3-~Kg7QY7k6~OpA;I9D24+8%NaO$T# z^^*s`4E!)Ci@yeb7-0N3@WTM(-|@=w^8n-bfgc7Ke-QjRz{!*H)K8w|&wBAs!5;-q z{8sQs0prhtKMEK>7yMVish{%HPagbh@TZ|HemD5jfbqw{p9YMd4*oab)K7WpCl7u@ z_z6)Ke+u-w2#MDNp_6N&c)C|0(>X;KZ*AezZV#PG5o#2_>tis22TByr+)I_zlOgWW$|mn zUrjva?}on`7(Y1t+rX)xa{S|(e)8adhrbw@vM#J3WCd@%8?1ml~DZzUL?O?)fC_;TV~3C710-%2pPpZIHnlQZS1pFGK* z^=5nUOT`Zre*9JOLj~iL<@l4t>wk1Fki#tFQU?6{|M+)`ZtQaHHk!vI*b+1>^EXUzzw*Kjo>PJop{s zXH47hN5;<>jGr=o#$f!H@k<7$e#%ondGM#kf10xRS>rzq#{U}sX)u1-_)mlJ*T#Pu zj2}0C*x=+zdFm%m@@KvHmE%VaC;sO6k%RF=$B!J0e>#5W;M7lf>L(9=@%X`07JqsC z;KBIO;|CAMzaGDNaO$T#^^*sGfBgF?OB?|H{b1q)@b3o`H-LXXn0NyG`@zH+5GMdm zo|LD4@+5!OOWXr-4sa3=L7W4aI0@n$z{F1w7XeQFl&6035Vt{`24#uoAWj2JoCk3l zVB$ZB>j0;I%2Pjih&v(9gtEk=5N84=PK7uVF!3wIrGQgE<*A=M#LW;VLs{Z!h?4;m zXG5F}nD`swYQU+V^3+crVv=tC^!vSyvg?A)*`sYvVRH(*4Z^9P^3+cr_le57PlVkk z!tO)i)K7WpCy&QeWj&_C9#di4fN<)kJoS^uHmS0X`EvYu#=`}~#YmTtjDB;vkdFm&R*G!f5nknox zQ`l>)aO$T#^^?c%09^y%!Zu&XlKq@+5!Oo9*!) zTm0*Sy@&6yVejFEy@wa}o?kfiQ=a@x~spJ@oEe#%on zd3^SwvOaqe_Swrw-}>xD*k>=oKEn}Co|LD4@+5!O>oX{E`V30gXHddEvl34Il&603 z_zX>DeTF9NGc;kJxe2F!%2PjidL*X~XT8}TpJ|JKU9iv0 zJM7tK=E6QR?~(hAT{!hqp89{nGu;KKtk3*~edaIhI|5Zd&QlgD?~ zD(gFIVc%H``;J>U^;4eu$>TeBmGzywu<*A=M_Q6wG```)N2T#~Od%~%o^3+cr`xdIK zeG7%{TPSSbLSg$B3fo6fIC)Z@`pJ|0S?_Hp-%D}Y$8zGId^LsblPR3~DYsANT0Hg< zmE1m}!uAmrwoj>W>Zd&QlgB=;Dr+BCVf(lW+b32y^;4eu$zvZ~m9>wquzhre?b9oq z`YBKSVraKgGxhJLW~$F*3rbpYqgq z?2Pms%OmVq9%0Aw2s@TX*s(mqjtLS@o|LD4@+5!O>zF2SI;Kh3F-^jbff7#rl&603 zI3`PF9g`*Om@Hw(a83MEY}Z=y)K4DAlu6$)Wx|dr6Lt)maO$T#^^?ajaVqPWIAO=c z2|I>PIQ3JW`pM(CKb3XdpRnWpgdO)M?6^N+$NdRAmQXl3Q=a+?n z{~aqm&}PR<3p-X?W9nFGVaHqxCr`>#KY5Zr>vhbyI2|)C?3i(3$CwMJe#%onc^vbu zvW|HdcFeo5W8{TXKjo>PJdWj8S;z7VJCQ_ zpY>*YoYO}9&S@j;oHoMFfg^v0)K7WpCy#UTbgY@q$s_EXJi^Z5Bb@pvPyOU^PN9is z%0Z-c-Z_QTX6GOhPW_apJ~29Vekva4N*ZXtb0rBoSCYogxsrsPD@oWnmxPli<*A=M z$)EK)XOuXdGfLPwqlBGfN;vgXp8Cn-oL4IAoL9omc_r)|S;DEG^3+cr=kiin=kgME zE-zu{@)C9~FJb2d6HcC#r+)Gzf7a`qX5w^CGhyd66LtL-tLvdLzglTFw; z*~IA_Zo;Xb^3+cr=af@f=adt6PB~%cpc790l&603I47RUIwzj6bK(g*hn{fir#$tO z$9ex$)_MPgo%c`JdH;l+_fOb)|Ad`OP&heLp8Cm?{8?|d$2k(kzb@E$8l~?%jl#~; zDC|6q!p_qu>^zOK6X$*uPR^94e)1%L)|>5dPD}ASr=_rSS_(S{rf}+~JoS^uIXShK zIwxnxTI!sf!p`9-ocbwG{p4{@QLXLHDXMllr>L-VkP4@M%2PjioGVpjohwyiD$&>QbPoCt@dY#i)oX%-1?3~8J z&VekP`YBKS&^B!r@i={ z(_Yv)?PXWafiIl;DNp_6aZY}fbxwX^=j0c54u7rTsh{%HPaglKfO!0y0>b`H0b&0J zfpF@lJoS^uzm=dq@oyyv`?nH={aXpb{;dRI|K@^l@}xZVlPCGJUjJrW+`g#Eie!v5VKVgHtpaB`+R^^+(0v)*hEd)A6a692m3s+Zqy zYVG8AorJ4ie(y=R>g9K!gsWbDA4<6D<#(fm>sk0cDdFTydFm%m@@Ku(4~zEH81Y+I z;;%8{H?V|jjQDLV;TltZGfO!2Q=aQxcJUi}D<(=dQ+tfDVxNR-k1PJhg`$D<(>1YY#bA?2~ZqA;*e|(pc1L*X_lgEm8QrX%kj}@~dT>Ip)Vwr?%pFCEKlW^^mhl+g?u6^=QF;T*`_Z})% zN;o-Fp8Cm?{8?|dr@kqMiklMuy5Rb*8S3|#q+j1P%k_Iq!u4IVRKLe0T;DZa{T`EW zeb;pLdrZRhUDMa^F$veVQeVHvB%GWnPyOUc{;W6KQ{RAn#cqkez5)A+(Gsq2z`kO) zgzKBJub3|3)K7WpCr^FD_7%IOvh@wySB#c$eZ%$@yCq!TynV%V$*xjA<*A=M^$p%v z?3T*bH+Ww$TEg`W-dF6FaDB7)71Jf0`YBKSP`Hquv&mde)INLMje!gV&%RV~&pL&a{1v(AWyiqR6TGoqnlw}k6VX{eYk;nYug>L*W~aSau_rLuL# zHB^k2aGh}t6}u%|XJSLebP1<^%2Pji>g;Z)7%i2pv%8^Uu7vCCZfs|Ob#^yajF#ke zb~je+mT;W`juq1-J4v3Dr+)Gzf7V-Pm}A9miL=fy$BNMst~1QBVz-3r%yX=mF0J9I zpYqgCo;rgaD|V~n{ZePJW5s9**BR_sv0K7*W;<3)m)<+6pYqgCp346;R_vC_R$i#F zVzkuG$`>_O?3UVJd8EdQ=@L%;l&603)EV_yv0ExzXVhcGXbIOD^;of6!gZ!SR!o<0 z>Zd&Qlc&z%$BN5R**b?GE4E6w&f&+3xzf1TIs90$Si*Gs6}u%|XZu6N zbO|SC%2Pjil0WOs_SBulQ1M;jUl&~WCPV$+ll1G}WT@YJ60Uob<@&uR;kq|js^5DO zu6vWNe(y=R?oGP-y(i(ii|M}qnrV(CXUbDQd6GZt&GytCQ&%x&s;lmpx{4(et~;i_ zV$6i=PO7iiGvU-vdFm%m-I4VbW2UloN7h#?nQ+~a^%Y|#Tz6`H#iR+Re#%ondFqa@ zuNX6xtvkNHV#$Q-j<2s6Gucwz3HB9xCY<^yPyOVnJIcOd%*0uDlzqjL3D+HEUomFF zb*I@^?3r-tr#$tOr|w?6iX~Iox_j*^HcYtgUb~7J6Rx}0H5E%HTz9WS#h3}#9qv%E zXTr&o^3+eBQ_pY@gx##k|69qWJjV2l;(CH%y%K69)XFyZpq z7%MhRIQ3JW`pHvyTgQq4Q`ySrI##TgaOHU&D+X*8^;Z7Zv0}sYUP%3vr+)I3kIGmv zU@BWaDr3cZ4RDr^%2+XA!sXL4R&1DX>Zd&Qlc)S}#)|J!+492~D@IGW{BXvK-4ZT8 zoUvlMG+yP0GghpZaQWek6$2(*zCA<5h6yKU%2Pjil0WOs_S7Sf;lK31#N{_N*6%&3 zJ>@qw)bBkBm*3P-zxO0uepAc!dr!jUH?>s1_at0?Q(gVulW_TBb@h8s!pWKP)K8w| z&w8^xTEG~x0w>nc`FxO~#OieVE@{gkJE@|5pfSFvg;TRw7q#iR+B zk6d4|Y7_qCUHgh*6Hfi|&0EM*KY7Z>udi4&l`S8?zGBjZ%g3*;ST*7D3G6F|O*r*a zp8CmCK8k(Cs;O-GDE1YTCR{#>UB#*imrr9?F>J!ApYqgCp7OoyDke>3%lERY7&GDW zysUX_M|!MSHR1B99xH}TIQ3JW`pHv1-ebk8^>CJt_gFD$!sX*V zR;-#h%O`xS7&hV5PkHJmPx+{i6|1JQ<)c1UOqy`{sE-w^CR{%4W5uxP8B;&ysh>Rc zdlX~Es;O-KPQ_R;X?kbX?^lc!tETr({jSAWF>J!ApYqgCp7Qe_E4EEzT7Ldx#gYy5 zRr&dk6=Nn`e*R;{o(Y$q|5!0;vXk=jA1k&^xMBy!ift24&XlKq@+5!Oo9(HXh_T|? z#J?`M;xfkiJt^r|T*g?xCna2Q8AJV^lyJpm4E1|b!WEY>)bB|NS6s$!^?Opn73t{9fCV(Nq|=B2AxJK@w%dFm%m#o%-m zQ>U^OgVR;)oN&e9bQM!4TroR+#o7s{e#%onc`CN3ub4WOtr()dV&{Y_hN!QYI^l{@ z>MPbxIQ3JW`pHu>kW~VxE9gKjo>PJj`R}EoGVC%v&(?o_PyqJz$=LQ$OXYpFFHptWA_<4P$Kr zv$nA|fm!odo4~AvtW99nNY*AWYbWa+I5|_E`pJ|0S#P$7wVZVv{&m5;TX>hC&pU^A z37B^g?-DTYDBdMt-d(&)z`WCVmw&^D?9_GCZKksMWyI|hi zym!I8&v{RSQ$OXYpFHd%*f&s?{RR65F#8Vn4Pf>o>@&crpYqgC9`-@(dnn8Ph~%vTtQS z3T8jceiY0;m;ET1{V)4bF#BTmwczAQdFm%m@@Kv5)7h89$^M;vIavGp+TVlO@3W5w zr+&&)KY94h;Jbpde1Gs=0p`1e?+P&AEBX#8nEEMC{p8`hjqfyQ_@3iC4a|2Q-)UgJ z|M;#0r+&&)KY94>-=K*}@gE=SQJ0HyX0p|kX)K7WpCl6;EoMlj!GY`%( zz?_9}mI3CBgtH7VXD6IxfH_m)ECbA03+E%?Zd&Qlc#cmbrtibvc$Aq_(8Y-)3;o%m^aBQhuCt(!U?B- z$}5N1LO*#pZ{~cNws8*4`7)UEY0j6yoLh6g4CXwW^JOsS+?-Q`lPBe=pFGK*^>Xgc zIXj%3$8*jO=A52$b};AnoXdk#Kjo>PJlq>_Pe57j6SyY;bI-s%0hs#-?iIkPpYqgC z9`0edccCozGu*p?xwqlo1aLr#$t!Cu}_2RdP2;S?(~on*?*W$=xKFJ5TN=!Q6#%HwosBl)FhVccQ_pY>*YxXa}p7yfm@+%0pLj6QeH+$Dp#i{>sF%pEm%$zblTxl0D$v+lIHO9pe- z&HXeuIa8kc$&>t9Z?=bfc<$Zd=YF1hcQE(%+`EIh&*z>VocbwG{p7)q0KWms;$MK@ z02sdm{06}IBj9HMPW_ape)8Z4f!_mV@sGgo0gT@Seh*;$De#j3r+&&)KY8%uz;A=H z_;=v90mknGzYQ?{AozKJQ$OXYpFH@d;EzIC{8sQs0prhtKMEK>7yMDc_`l$f0>&=} zzZP)vq&)SLC;78p{B-ckffN57{Bpqf_28ES#@`1&9&qZXJoS?YKO_8#D2x9QennvX zlJF}6x`>cFX=a{Tg|e)8b= zho2v1@dw1u4~(B6etuy52k{F8r+&&)KY8$N#Fvq>_&nmv2*wu@Uq&!KlK3)$@twq% z5sXhIzKmdeE%A>8Cuho2KY5Zr>&^Dy`-$Ht{Of}8MaB0NeSB2$Jq6>titi~HpH_TN z!T7r3dkV$}7T;4azOneTf|E1lsh>Q_pY>*Y@Y}^t7k>PC@zVw4=Zl{%82?}Vdcmom z^3+cr{EqQ6rY!!*_!)!oQ^wC2jQ=uz$>7vadFm$*e$)6#Qx<<}{G`G7S$CIB82@Yh zs*$ID%2Pji@cYKko3i+W=PaHpQF#hBCg@aQ+<*A=M__O1`PFeii@m~ky|BnAU z7{7S@*TMM9WrZd&QlZQAD;yNfx{0DIzVB$iE>i`ok zLL3M<^;4eu$wQn9aVeA~eucOcFmWx!rGSZdA&v!{`YBKSQyF_pEA z3ERemZIi;OpYqgC9?ub#^&AoQ91-@M5>EY;r+)Hyj;pNaxUlEAu-63P)K7WpCy&=C z*@@REVXslbUeknAKjo>PJYHi})@!V=*H~e%$-=3h^3+crzdJM^{q7L^*~U>Zd&Q zlgE1)mGvG**n1dZ?|Fn%Kjo>PJl=z;toLBT-h&By&nBGuDNp_6@jg>!z0VZ(K2zBH zOkwXcWhdTe3VZJ=oSZ37{p3mhtT)@^J-PVT1^c@|`u;A^eDQa|GPdpSf&uLB0%3m_ zjL7}1A)K5kPyOUc{;W6K<8LVO`x{Ew-%!H-<`Pc*l&603_#04V{S7GWZ$M#xGYY4E z%2Pji{0*zJ{)QFyH>|L~d4*Fy<*A=M{svcBe}fDA8(i4m?82#^^3+crpCQOje1;(G zGX!CuIS8kI%2PjidPP zV^mq6F$(*PQP^ja!l|F~)K4Ctk*ciENQHeyD(o{=;nYug>L-uSfmPP$z`{NU7WO%? zu+M>oeGV-9@!7I)a;7}>lPCGJ-fWN0%*DSh*yr}r_qn~W&+WCg``lh@yU*6|9f$aR$06)Hj*<5GPDD8MQ=a;N!ZY37sI2d3gndUN>^mJ{ z-|4I+PyOWa9h3BZ$0Y1KCSl)638#L_Q$KlpN2apABNO%=nXvEFgi}A|sh>Q)L-tV094jK0K)bG5Vp^NaO$T#^^?aw3@U3M24VX!2;1jDIQ3JW`pIKIjfsEq>kzh| zhOqrKgzcvxY(EWQ`+mr-k~8J0pFGK*_1bSl{Pt;CXKcS3>D#Ynnmdz!jED5K6%2Pji>_erp_MsYi zF8fdk+viF+^;4eu$zvZdm9-C;uzkRU?K38v`YBKSRdAyirW5DMFeP}n|)!l|F~)K4D!MyjlRBZci7 zDQw?JVf#i3+s9Hkc~YMG$&>t9?`L>Joa&w+&-?t z_Hh-qPpok2r#$tO$3D6$Yad-<`{)YWr&l=jQ=aMDqZYOwwXprDh3%U?$tU0JwdIo^xa7%`{8?|d$3EvOyDr#%@6xy5 zyRiMX|d5KjG+ zr+)G{#zAEr;~?x92VuuVj684Zr#$tO$1xfz>lh7T$7l#Urb9UOQ=aSKGiGPX-5_XJ_uw#ORQ$OXY z?^q$}J9bIfu}i{^T@rTelCWc!gdGDVoIEK{{p3mhtk*GI;&cp`uw%G{9rGoe`YBKS zg!j5wkcI>2Za;7}>lPCGJ-fWL!LdCx> z*m0@ScU-El<5Gnkm)bFx9hWNXxKv@sx+*3&Ia8kc$&>t9Z??xVy!u9P46iV;MD^ZP z+^%DOwdSXO%2Pji9D}T~jzQMC=NM#R$1Dq{e#%onc^pHnvW}q^b`14M-#X@6IQ3JW z`pM%MaB(^YT-Y(-!j2i&Gp2sZQ$Kke+ph6-YL-tLXsE1nXb3xp zhOl#P2&aC^Q$Kl}14Lz=14P(4K!lw$WYU>(hO8w|{p4{D6X`pLiLi5+2s`JAaO$T# z^^?bWT2$6~T7;daMc8>-gq^2F*m+uno%=;NIa8kc$&>t9Z?>nVJUMN|zb@E$b)@gS zI>OGYBka67!p^Is^~8B~gq^ELI5|_E`pJ|0S#P$-If%sX97Mv-K_u*)MSAa~e#%on zd7MK@Wt~Gw?=0s~8dyu6b4fV$Q=ab>l{$R&H*LtoKeE5pYqgC9_O~|Xs2^q z2|Kry#?HB|gx@jc)Dm`%EaBuydFm%m@@Kuy@g+{@_!4%GFJb2d6HfhQ_pY=Kioj9F? zPS`oQ;t^c&r{#ISS3&WZd&QlgBx1)lTQIRr{U8R@gajg;PJ}sh>Q~&8xD`%_|#lZeC&M z<`s5sUSa3>6;7U%r+)Gzf7a_9#o~01Vqxbf7A6*|{CI>@Kjo>PJkGJKvd*zA>>SI& z&dDsC`YBKS+%=g<~*4sBuQ z+!jv#l&603I0v}w$2q`-odaChIm3lhKjo>PJkDXRvd&?yb~=Z-uydXZr+&&)KY5&k zU1gnvUD!F;g`KlqIQ3JW`pM%w^D65+^TN(EFYG+?!p<`<>^$?r#AcO$q;PVkJoS?& z`Lo_^k8|>ie_gPD7eM;{T>xSKE`YFq7eLs*3n1*@1rYXc4G1S^%2Pjil0WOs_V_mx z#P8ow5cY2<$gcdG3&N?N^3+cr{|1E0`Zpki{TmR%{>=!j;i;eU)K4D&hK0)dH!O4( zL~K_1N$b7i-@Fh`{gkJE^7uD6)K32fhp>NxL)gFBA)NXtPyOWaZ;PnU{o5kK{%sLq z|F(#*e_KS@zfmHbJSk88G{$G_Vgz{gkJE@{mui?oQM; z^32s;h%ou*>W)Mt9FZomJtW9kouWFs0 zsb2D})|r|xd06YLO>H1QYn{QV4diXDvpM19NqOogPx5EIQ$KljMz!?q&)SLC;78pey@q&u7i``apJe=!2B)~zflL~cc1v} zIxxQn#c$ey`JJfi)NkN{lPBe=pFGK*^}1{ir^^bvY=_)sg4OhJ}+S z<*A=M$)ELlZmM3-O<~VXwZU^!^?Gg!dydO~k|*Vt?Pr288=_F6>A9~`lu(8Com*|Pz zLSB1`o)|4~?In6*x4@~B^3<>I>mEOT^b^;&c8{+=^7_{9@#zQGw|0-OKR9(#p89ou z+v8V?e&RaI?eRTDUT3*IKBnM0%kA+!1*cBRQ@`#vd;E~lPh5AMJ-$lFA9vO9Jw8d` zy6f!mRRX6@%2U65a{89{GI9Cm^pRJykGz_F4HT#xVGkMByXCW_to`rt- z`7C(K|7XEpenE?R%NMk7`P>qhUuYls;`+!J*GIm%KJvx&kuR?2j)cBSp7Ix6$jgs( zpZ0C?LFikaqQn)C&_^DmKJp;-kq4=dJV<@yLF!u`q~xhMg@wH0 z7Z&;z*RbHJc!vdl#X&6U<=c*LIi5Xn#liKF-=mNG9)0BZ=p(;JANf7{mfs_JDn4!@ zueiB|e#O%*cq-0r!C&!ri+U^Ox^Hpii7WoPkGS~ zI(62b|1y99yFZe6&dr_}>wDu-;n>A0(ueoV{^}qRr%`YDF3nx#?Q$KlQmpu-+KUTU+)OKtXeshu7#VUL$MlPBe=pFGK*_1ezGpV)Is?X>+1+y2#N+rQdu z`xlSxUpRSEp8Cm?{8_Kp4RI#+8r9REUQg6cuP4G@Pt<0wCu+0T6LBU_%2Pjil0WP9 zIxNn_Uh~yXug}6>pVdyU&%$1xg}pw@&og;ap8Cm?{8_KxS?Y(xe)p-b{4NvryG;9m z)Jb{j`<<(PNbGmFIQ=dbr{BfWPo0#fzV{4je`4=F)NkHP2zxJ~dQ&Imsqa0H_!E2Y zBp&aDv>)(ZNcyRh^3*4{#$9$kc{}VjXV#5`8)0OzY9~2^2p(X7fd~0Jm4MMgDfAw))zL< zh}`_bu2;DJiS`J)ox*Ov@KLAkwt{|y$IsjJ7rz--|3v>t?tT+?e+v8Gh28&Zr^iLO z)k9t2Hg+jb{p3mhtT)?Jq>FZX9MztDuB!8lR$ul*_D}IF`Yro2`?=cFQ(yh>PsSz3 ztLo{uKkF4|p<{U$`oiXctBs?u>lLnlqCLWHr?A^E{Q6aUGmcHp@5wfO#!U$U ze&^L~-hr9l*bUh8y9ax{5^n1W@}kgs0&eRGxUDDFDYX++w#_^1Ydx`!<{h}LC*Zc8 zfZKWk_B>KM+j@e$%>%IIL+A^eXGCs(;Wl0q&oo|OuMg5` z-s8gVPht17u=`)_^tcGqe{H;Odf@YfpVQx`yYZ$|Zq7?ruIax1vHc}~@jf@~pSb0& z!teRVJM}00ZZqKre&`|nj-UCW*4@uN7CF_E3jyd0fBKkM6{{ z)_*7TKe*4z)&FqV&vpb~^|0+$-}7Bh-wAxPM{mA*ryrdsyx~7ycXhw=tHSl?x%Kyz z=+wWTTYAD(?%XObTzuyguQ0V#eNDb&lT%OAr=G?`J&m6~TfO{yYY*jGJK<~XpXymW z7xHubT zG5zZx#)rYCEqzkoY(vM9sBVO$BFYvU){LB^(!9I!Fhw%f2w=axtn%yzWcDl zx?ex@t>WBob)B0X_#1IP^-d4zZ@lRb#reKJ+^hfk$38F4t?#%^&65v`^Sd9}u;$6B z;(Xb0%iWHjIZ&Lh+2ax2EAIUZasK2byZ2vw`8GYze%>Lw^bfxNt$LpQloxK>udd(7 z;MtEm<;MNE$B)GMnumX@`^^>~5$6_fIJ>*_%$JJuj5Ahsk9^Q=JDwdrc;SQ(UO3@{ z7f$%#r9a_=muH6$UY;F3c;V!^dH!jA_+iKMPwT_yJDz`9A3oUe{L}hyYRB_W>%)N^ z&p)jXzgXh=;beRmCpZ}&#tBZwhjCInYkU|dI2j+t2~Ng`ae|ZaVVvN^j<6>xT(k8pxn zAKlI&+Brl!hiK;z?Ocv_E=N0;TRW>ihv?5C`g4f>9HKvm=+7bgbGh|rjr$PeKE${W zG44Z*`w-(k#JDfFaWDHE!#>Bb&oS(C2>TquK8LW+q1k8gjWLhLm`7vGqcP^u5c6n= zc{H?nRL?!ed>>=Jk1^lJnD1lE_aWx{(B^xM&lu~{80*p)>(UtO(irQ~5bM&=)}^we zG1kv9*3U84&oS1|G1ku^*3Y4>pJneO_Bze?Dd+k$-}je%n(w;`PxE~<;c32qaiHup z-;WZ;=H1Q#&a!vfIlx)=PCExU%id|{0B6}d?OcYl?45Ql!&&xDJD1^fe~Pp0o&FSO z**pCy&a!v}BuR=g6~{y51C=by&?^UQZ~^4vWCH14M|-^Xd(4`jZJ zljr97;q%2IRyVXz5s&!tR@A-@K&Z>1@oS%8heb1_OzO|G0QER8{-tCm#yPdp`T040kwRZA8 zYVG8G)cTY6X6sMho2@^2Z?^vAz1jMc_h#!)-kYsId2fo-?{{&s&c(R%eitX}T#P&K zcX6`L#kli+7pM0j;`Ba5?esomYUi{MQ9Hd4Y4*uJMD6rGM4Y@guzSxV_DkaAy%F7;^h6-<~#3U>>f_u z!?7;0|7`0L`_Hy6$?maF-ovpjvH#Q>Qg$S}hm-w6te@l!i68W?&{T>Pu~&z$=~(; zQvZ$~m~xZ{!v`;zcfwSkF?C^tDc=2Px0^6`0LM=t={_gm90HhZe?p{@vUs_ zuX#I$s&DbUO`m=croGe$ zr~6Hq=c7Kihkh2OKd28m{X~6Jd;U0HWe0k_C{k zX{~+2>`iO!6J~E(-|E8CxBGPdM=!SX5O6yu0k`uLu+Keua64}S*MB;P0r=cQI_=yB z`SjmpBR=<#PCNgxg3g7&?Ys!=a}VkJ+(WpXJE7xqj}A;fPJb@s>brJM!oRii6L33M z0lVH2T>t4D2GGuD!0p@y{D15IV!hkOgZtr;-@ooMw)eYzKQQd_-sdl4d+)o;^~bYc z^xl;gWX_m%V?30nYb)XT$Lqr*#9IKiz4&@r%!S`T*w}_qfmawkMq| z&Nm%%z<9rX-yqH>p75ml{r9(t^WOKmeXYSC5$8YulD*+7aem^#SJry@5^-K<*Ujtw zbDlWAbG^IPJMGiryzFTY7(e%nZ;5l)yF7Bd;Fw>D^TwJG;;-|Vya zWcQ3w@pUnex|m0@d&a2vWcQ3w*}Lo>&f@FaJgVoG-NRYW-Nk(GV!qdVaWUWPy||d~ z^{~ zC*ML~&7-NEOVQ3HILqE?=TfwDDcadZJ8OTuXlLz@wa(L@;&gv@aF)H(pI!847yT(t z_oq1BpW^hmi__yS&a!vLU7Tg_jJr6?-Whjsmc29X;w*b-+{J186sPS|oMrFWr#Q>r zu}^W@K6{?s_Sy67w$Gkt_dM$8&$4&skvQRlmuH6$UY@=DRp~Zk~S{_ir)Z)lQz9=Z|$soMrE>kdG zKDfp9*ggGu|I1I^9=peue)iZeZ_l?ioNK;!qZQaa{rUYh+pWOvdG?>Z^j<5ld;0S| zyWD>TcJFrbK5Fgcebm~?`>3^(_fcyn@1xdE-bbySypLLc^4@Iy$$PW)C-2SHpS(9) zfAZdJ{mFZ?^(XJmHtxLN#mPDs3xXW>3vAE zPxc|=^gcxG^gcwK-iN52yf?6W#)$U@cF!2`-iUcL#yn!bBu?*_#L0UDyJw7ezhU=q z)^oG36DRMtnD6ZC+I(kU*XBF>x;Ee0*R^$t{iirh^?H4L zzm#8D`DHBpK=9icsmtGS!u40a?}XcZH#+_vl-&O=?C-|`9e-B}Q&0JoHGd@hTl5aI zzOZ@v;1~YSes9)y8U8IQdrf|CQfC{xR=@jU;a}%*Y|l#@+w(5`^z!?cfA{xl`wm^} zxvI`<*iY%R|Ihg;{q=+P?6y1f&1bxQ_viJudg#5oGaq@qW$+D-yk~dFeP1ZN>+g5y z{`x^572f9H&AN*o^;_ZkbE*D5pkM#KRC>ZyZmG%(7vECx3Lm-ONoQ1jO}^aZ)YJ5- zr}0ov-e;i{MZZ0(_+g(=tCNjUtMp{VcSP(ZpCY{BSMD+Fc=(HjU%K_(hDTiMb;AGj?K=$*xyw6*U%cCn!;gMA z3jbh>?T5$i_*vn{p1k$2)n!)*pZ>~Q57+s{mBO#O%Poc-F4zED9bf&_jfY2Vc|GB6 z9(>*54Y$9E@Gsx^yX6O5vZ?R`e*c5zE4H|e@L9{3FW=)g+X#Q}+yAnB@KaX^@Bfky zEx-F2I|(2E&bKXp@mf0zKm5?smOr`0-Gy&-{tK4>agFBAc>jkze)+Lq-A(c{&RVs6 z+~0J<8y>sq@`2~?E`0MZU%KY64!V!<19pDtn#)hzL-?tu{rE#?Zl}39e)Wj0cYDhH zCj8~Y9i1zJ7P+J8mev`m&pL4}JEvg+KJP zTXxs|_^&laXTE;R?sdQYj__WOyIuFaSO2^4XFqWJ?%S{bC*imL{mSk;TU{Xh;!W<- zy>`W!!q2_QF5R_0e2VZTueewDu^%5V+?~Fvd(C?e5I%qFzT46{@gMgSPR<*gl!wbwi#jD zlCW(|*tREZn-sRK3fqQ-ZQH`Od1225Vb2j^&mCdUDPhkwVb4Kf&rM;^Sz*s*Vb5`4 z&wXL93Bq10guR9cdukKjIrMsYag|( z_Z!IBUp4)<-++hxnB=kFpx(CM82NYf+|IV&7-PS|b9J?k+72Dd)j!^!2%AUP{KBqR z5^dN6Xv(u=PXZY5T+0Z<4z|TYK96u=T&>9v5NiX=BGX8s97Y z=Wn<5_KjBGEX2aB^)0i$?gY0#Yw^v(x7fflu8(hO$HJ%|sb_tEQ^)rvF-B`lZq#-ytRKCS9p!po99A#UXg1|#;cw8^%td^q&u_HW*(Qbmv*$dw-0YV%Zqu5Xc<#?_|9AWI8a@B~ z#6MrGdAGjbt#A6u#dXel&AnUOd#9djy}n!XygISZc=gUpU!9tg3m+cOHRc$)yL!_*%P(={PySwgH1hB0fhk9M zFnsWWd4{Pz$#-n>(%-4+7tc-ODZf5b9oT;fEl9U-av~ zZy<&cTz-j_e_>j;_DzV=9;j1)EDL#cD=%GkFeV*?DjXEQoH8Xf1Zi|*1K)|(O+e> zUk&%IWB99#_N(E(b+lg%_pPJ-YPfIJy}j>S2mAkUhdYM9${7ACqy2xl7ar~ZBhK(w z(Y?Lzg@^E08N**?41bj|{8h&AR~f@!Mfdi;zaGM0Wek6nG5l4=@K?cqQ2r%6d-$si z;jf~5dw6;F@K+hbUq$!!_6N|tJ-l#+zseB)D!R9~-$Jbq3xAbb9~S;9y0^FAg6{3@ zx1f7_`z_S^u<%#Wy}kV_#_(6sy}kV_bZ>9}3f?QH%kw6poE(4Wm;h5l^*D)eXbSD`wXY*HK{cQd!te?$ah4r)ftFV4He--Sg`K#1(FX9x~56E`CACOIZKOoHd zS@tf>7?r&X)1Ua^GH2KixSh+aOKvCr=dGRipSO16f8N?T!0C1lUgw+tdFxMcx<3av z-Jb)T?$5#NyzCxM_oq1Bp9AgmxQo-{E>4fTI6dy-^th{?9(Qqi+{J186sPS|oVHJK z+CIf;`y6Sf?Q;zK9BHTL(cpEy`JcCWBu>wxk!SZj5@-0Iw|OK^&v$WpzN?*{@8a}) z7pLdDI6dFhPS1C7hW~k6m&ECHX=IGT|GceB;tc=uwl0Y?{LkC^DNe7S;tc=uwtk8; z{LkC^DbDgsJPW(0Kg%!iEbJazD!;_D?0-I%U*g%d&gbo-r!F#Ivz`#;E)f z&&KW6z|Gd37TYonH^Y-2pr~N!ze>VT~ z_TChy{ZZSvH~;hYesAO6{LkC_U7YykVfWK~*ZW0A5q^Uf_j;VO4-l@~6)bBb4(`m4Ss-?7Q5r|DBqg`JT7C}L`saepBTPL!4|3PL8tnE6yPd++Q@p~Pd})JC zr+z$P^z$}-`a!sO=pSL~p&!LR^=E4j{VYs5`Vk%Kfp==pAIFQo^Mw4jzU?Hx!2R($JC(kH28=$`F-~V`~k!Kxw29jqZd1jJlDb;WNCKo^8 z8o9HGyby}xcU-gL_#M|gMqY?9@fjXMqY?9@jw zg{U=lkr$%Y*hO9l@}Q8fMx2osVu-vD%G=>Q24m!f7$Yyl72-?~5LeS2Z7lL-Syb!dr<%OV~EiZ)f%0z#*yb$zf%L_q&w!9GZXUhvg zf4003^k>Tpq5L;7?kz6_@>!+5X_^N z7lQfT@gi__ySPLI1dJ?`T4xQo-{E>7EL&$HV;d!F6)+4JnS zPjT8l#cBH#r|q-j**%ZM>3Jkh&m(bq9`*F6=aD!)kHqPDBu?jn5vTLOh|}|3oSyIE z^n9;x81~YOJa28ji<5j;j1$jZ>%8)z@a$ffrgr`@&s$rU#OZZO?ew}NPOqQh^!llG zdi@lq*H5+6>!&!qeu~rUr#M-+v3uGHu616V;9BR!39fZsoM7ypX9w3hFHUf+^R1mN z&s%#RwRXzx8F%L?YVB-!-rD=9wX@}UYwyk0pIS%UpIS%YtaZNSd28>@)}JlUTYGP+ zoqoTI)9?2-?pp8Q^!vSyd&~3I-tTIs-|ymNUxVG#pWcUv)BBKV+^76h;`BbG*(dp_ z#OZyAIC*bi_nt>B&s*CsiPQU~Hji4Kx3*srr}s>f_?Ghz2|djBa-??3hI-hYbI`%iItpWN2ZmgfyS zYI)w;K3SaJC%5&p<#}uSWN{vM>^m3!LjI=cv0r~v2-jb^Cl&TLg|NRVg#GWr{-)^Q z@i&Dq-xOE#kp$#0hYmT`MV`19K*zllEn!f#ak*)?}>`-7eC(Y}?|YusY> z-y)7LvA+}5|Nedyt}f!cQrO>{!u}2wu74ltQ~HzdNct3y_&%;qbec)LUY2fp#wpbz<@h@HeYzQq_e zpYtW;|5ZN!kK5{-JZ~31^TPI}7yhsG`M>^YkJ{ePwO+^ZnjWvaAM|BnLf89vJ?wvM z+hRgnjKlgIFJey=!@KuO_85M3*^5@yGxlMV{r&!KX}H5Z_QEFnh)L<6_RXD#SAIva zV13wX|F56ede~^C;sJZdR;cXr{^bTk{f}qqBW|TH-Q_AHIrE#C5Oj)rx#|#R4PY%m zUTs;fHVH>;OJ8kYQ_moI&Fk%K^L^s78RCdr*%trO$6V-RF3?Wml%?-AN6+H8mDVRM z{)K+KTDhwkCob$y?8H3F z?%VbrWZqG)R|O`Om%oH}jp36P_oN zcUD$cty)rD)%Et?Hh(g<`I)iJ|BP*MVH{bdz5P8bdp+9q?eApS>zC!WxHG0P;n*0P zbJaFKu-u%tI4+t`SZ>Z?^aIU5cK_Jl=d#aNc7OiNZS*tEZ!EXXdyFwIG#_$YaBcaw zzI#=$#@=X*Vy;HUAxBDz8@_3tevlY zpZKusoh|k}+2L1au6^&1@?y3Ar@~jsKn3C%5r95C7A1fVtvyPWvYgx&3^ZW*d`{P%A@Xa4VVr!lPm zOiq6_)F68gy4h{{SM_W3PyhY@UMri| zcz?(G%I=eYRll~_@ErSJ!-fz4j`KdFw!FmO#XJ2Kc^#DVRENen*q<@QJ1LI;HoVg$ zeh%g`=4+B4lKk*b&jI_sobt>5tl+PD?*Qjxd_Tb}iJ#+LT+p+d|JV0K(2qa)Ic99T zuO-D1{Y&qs;NDr;{A_=p1>arx&)@g?JGnZ>x`ZN@^gac7A;}N_e2&Wh6#s|X9_)wuI&r>W(3t&({73(n`rYqFzvJ`tq;>@9U^}pE zS_Q`St5<^GGge_7;k8^F7jEFEYa@bZ=cvr`T9FQN%9S#V>*nn(U)6SGJaWoL>98v& z<1U*n$%@TVFcv%zSfM()h(yIGriJC zzu=zAs`b~cZiGL4uA&O0TCOwBR7H*WT0#=ekh7vX^v;WMwi2b(r}qAg<3|-%=QiA6 zJi#@)3ThF>xRZYhbvQDeqHBH9zLE>a=3%_l@s#W_s~F?jb=Jt??iJbo;3~!7g}>p4 zMPppFqc;D{>a|?2IkP8~+H)@_pY05XiK=Lyjf_ha^i)HOe`f3y)K5uczuE8w@eNZ>Z3Kh@am# zgwJ%GKLrTZsqSA&q+MB*v7dJXak+N__nWbFR}peMfN{j*p<;8+`izfN8!yhrMZ1wb za3cM*HZk@4uo_3`(A#5eaAqs_>x>0s81QQZEwnR8%m!T`oo3S5HXnY%E~ zH8zD9oTDM*C!dRmXM>E-Ma}X@P0@CC4wgGkX(cvXde7s%eYmH%=D3HkqdrXJpV@)& zvDV|n@=dES1{O=lhLZ)|M+s9bFy9#4@{O@A-x%BSjj=7?7~ArVu`S=&54L<`Y|A%} zmo4Ae9$UUKw&fdRTfQl>&6aPBZTZI7mT!!0`Nr6mZ;WmE#&}<5pKYd^0#i+asiweG zQ^HhJ!cTo%74zA920<%f}J-fWPehv51Q&ugUj3-XJeD8prrR+23W^#giDH?s-T5F|jw} zkxySh8r{&pvS2Ojjy3kh^JM|pkT{ujVvBVPdT_{)@847m_Ygn#HGW+-8SAKqtDL}b z?H_{f$#n*9fd?)<8P5*>2!(DpWt`=4KC!MqMaBg$|0Zgv%#0mwwiWp+-v+w2ev|%U zyz3ms={AoNu^S%oe$a3HB(Xh57v5V{+B{jfcy!^t%$tnkMEznq(HK9u%ojBy`Ido;%XaG(7} z| zqQ>crbOtA$77hoGC50G|UcUzpzbnnyXW$TMJC4scMPSHh?uYbGpIE-t-0#q_d0794 z<0&X~mCrXt$cE3b;QmwYYma{hap>Ve#;2|o5RHFKVSG2Tq{v$~FXL+ODvAYH`D{_t zY?faZILK#2=RhhCKCDT`#(<0JlFbxT1Kqemdi; zLraQNdyg>g8J}MS*L=a)|3G^2n|Eq%)BnrIKaFdD?&fsPD>f{uB5HKaDhUs7UrB8D z8^kzGjxwU!kxh)hd@U*tX1d6@VwGIt)SeHFpXE;@mV5IVsJQp}BScTmsi>W0j+Y@< z20n`yE-kmht&F8v-oN}9_@jSC#yfjELivn*{w_*+FW2hgSsquiTW(R_xs3pj=z{% zO`ds`apT=N)T6w7ek}^jDy-fwox$?%*mk=}H^$9Xd3AW$UG~q)@0Hd3$Om*rENVWj zqF$wK&$&BrRuwhoTM8g~+^0&a=#DmwJ5?;FB2O$}T(+~bYSSu!alg3*)%As;hR*YB zs#$?AjNN=vsXfqx@F|^VmB~&!^mn&0svFK}pr`dJe{$N>oxI^FxV~Akx05 zqTcjA!LfMI$3@*w(@ByX0?I0wyOr^~xFTxQsk@9XuFaxq-Ab-V=X93@Yl``t;c zc~TB;r)H*WaPF*yaf)FHFm)SqA;i%d*+n|Pb!^Y2ua5YM&W#v*elI6_^jObhiT>as zzFHN_Q|?6WzyL?aIk7%QC;D)Xbxu=7#jINiG!|Fq;;Pn{7{;B)B~!!F6%{03*M6&X zEosDeL4|Aj+xtd7cpXZGdu8MK39bKAHZh)`Y&}{|uCHtC$Kzf6Dr9S+8JEtY&SgVn>4Z5ThBJx=-g`&~PX6#@ItF!pvDB&t43BS_w%ZAUR9cNxanhJg4op%LR36$*>ewYxJ8 z`w|81j~TJp?Xw-8^fO{qJH9lwXT*-Up8qFIeGqq-e$%@<^gb_PdNg})fnJI3_hG0Ev2O?sb;Fnyl4!QG|*^CG#l%c&2-q>sPohu%e|_8C+A zwm!ID`WxxsKV`dy?W8_PXtZrSSHaIi-)55k{0?Wb(bNucY57_jlc`@peNdaID@=C& z{Qd;;nf-le@~dgQq;K~FwL?GLj>&J-FUv_reUJ|R6DI!y^+7^vyH^e5MR^D%V|GCG zNh#FaC{PaTZozWrXOi%|LGiF8;27f;iJ64MuDOgqpUf}TkE+Nxa9?rJ{(!rFJb7o; zV{A&{mus8bLl~mUWDbHGdCO>bQjS+c+t-6PsXn_MI6g_;K5|?;)Gax`V?H|120wUM zjq$Ls#eUt&^4MspATD8lyq{6}o^!(Wo0Mt|J@-)zy}IZka%?e9D)K{AfAZgrl$D5o>YYo%V}T)tmJ#=p0i z@9eSKlkrMdPv>GI=Q9q8Zs6RZ_!`ECbLVuPI&3RrJx+Hjl-b|VznRA=+4Y?KT_-*A zrrlbtZZ^iTE~)$ix(_}?eI;vrri$Nzqd@iLUu?WS%cq2(`rY>EslF&|AIlH^XVKcFEhngPV!vB@-=%sKdg@Y_F@IA9yTPHKi?-blE$Hz@!`ONGE)z)Et8rk{S|FGPj zA~(xlODFZX=v0>Ho^n(+aDJz;{ryYecl-MBys`<>JJZI?26Wm!$StZfl?A+pvANXV+NXI`M$aw8>3!JFSbUlO-&Y z+G&z;pS-oOKg&Dng;m@oN0xia?b7q`QkLJ%pBL?LWqHn8o8^W09W0+(J-Zr^z7xyy z9$hI5e>~0dHH*`!f%k^7{KoW!ve%q@EMHh7nR>8vI?L;HpDu;ZCzh|S@kx>%*+bWn z9@$CPwT)QG@@~sI%C|?-vAn>v(~|5k{NpOg4#Ph?WPwN9Sw6Orqg+}eFUt#yrIN-; z`ZR7DC+X9;r)EFM@*|h7>iK&YWBJU@u9Eyn`s7#gBk5z@^xl;MS)Q+pv;N{!NtQc( z_R%R$q)&4Z#fkI@k56yN@0Ip-ebE+xh_O0&)ILn+Z}jgd=514{{0?tv-yM6oT8IVanN1i%7s^+$5*AAQAg8VCA{XQ#LP*KlRN_WZKd zdbed=887mlr?0#-mGR1uKXf^6DdS0b8|%}qZ)Du_Sw4NkqMeMBdEN;A-D@A?`JwHC z4^OJBkv-IAhRR>v2*(C)(+5Y5W<2HmUft1uX)%(MjVKQ$Omfs`O#1jYZm0aSdd0AP z#?(Ic%b5B_dl-{FXeVQ`6YXbA_T#u1)3{8wX(qX5($`GwXr}fxQ@?H|d)%;1-8Np$ zWWQz_mxl4!Y#T4h?S3GA#yH+T#nI$XH;O#UZ3xnCSF+0PiqOXFgUr@JR={EoVe8%(Ybf3K!Xxr zN8f%Z^Bq0PI1TK_-wzp6UyavBGA`MGHelcMoli9H z;a+J!kC)^|A6DG=e4=)Mbf_KbgD|yEKZFh0Pv7F6?i0(Y4Qh*YsBP+lFn-6Fvq`R- z^d8ET=Zme#X=`j*H`HvFvs%*D99fdiqmZ0r`Qk`;{6%eb~kYn0t&d_W*N`G3Fkm zpZ}HPa%9DiKg9*}4X@{X1I#zZm~XI1ZDSnV;{>eu{T$=%>o?->pFV_uda*1I`+iD` zN=#(jZF`oQ1@C`j-1R^velBI->%FhX&;3-{F|m5BeEi%`mGB!aho9zWhWIS(kgVyS zj`xP=4!@H4L(i-f%II&5QJ1b^jBQX`^t?-9+bSS$@~wpFhx)L~sSm=WPkj)kcBl`+ z)V|S2RhH4;NKU%OHC5S8>VxF=wh7OIWqu~PX3_^!J78)bO#KRzJ;G$Cu=hbe3oV>= zn_*8?lH12i`gT81JB+bUVe*^6e(`TSF0zL)>7t#CsSWDGHZFd4NEm(Thrd~F#+Z*5 zlYUYh(N~6#f9BPHi#X!^!|P3o*I)fCFAx^~;!KXb)r3rE5rs z+CcjmQ``1EmiX%PaGoDlZcYZ!*U$;=alAfy=-wpELnL}ld*FQd2N&e0_k9BK) z(XG&T1LuD-)9qZmfg6UWax?2JJ2{b`r@bhZ8p>WXKFi3j*%>WpmZ5(?%^1zBQ}g_I z*1uZtH}IZnaJt4#EeV~<810O_pBw(9(`h8@A1%HF`iG2WJaw2C%=tE!@sna!@HXkR z8g6j^W>wk=YpxmZw6?FY88Q?cVd%T82D8rR=Y3gTH~&MJbz}hJn!PW>A=e>{&wB)c zS;wiyIG`vrhf8c|?}qTQP2VDu*!ZR2}*o%Lh-YDDwIV#z&5o66e<$ z?}4V)9fetk^r%Kj7BRzxaky7CK|drXnOTSIAUX9(Z4sunsSm=`r&))_Npcz!*-Dsf zr!f$wF`0G9k0d9bkuM07Z^%c4$!BIAiWA8xCgf|v$%VTy@ahw^~r6myCtVTvuq zm@viMtV4N5a>}VEm@9-ScPNJlQ%;$6D33`_IZL@nm~xYHlrZJ2S%>O`x3!y zsRjsBO_+744oOZmN3}$lYKv-&Fx8w{2XQdTNgr#KG1V^BEy)R+b+9iLJeVKJ|EUZuCMVlFu%{UguG#0ZC`pVEjf1*zqlTXlBjLBDK9gGFbDPHJv#^iI1 z1!IbZSqEdya>@scDPxK$#+ot3+N^`Q#B$0v%o)a%Gnh+^DVNMTn5&9>Livn2$(V8y zbCogWs#ynXf#p;$nDdM&=dl(TQ!SWvu+~^k^@ugam}&}ZjWN}lSqJr4PBn@(%b02w ze;898n|06*mQ#&lTa2lWu@A;n$7UTIC(Efu(N@M($2bPYRL5o=^drluM$s3HsgBV{ zjH!;zIv6LGQ;njp8B-l&3>Z@#n{_Y`SWY#Hv1Ckjj4@_Rb!^tbx@9@lDCP=ds$`geO(|2YDYK5LmX)bym8q7MS;sV2DASyvOml@Y>zL*uWtwx8X)aP`9n)N= zOmmtt&2`GGW135qY0gxpxm1~TOmnp|&B@9%S1YrQ>0Y2rbG|a&3zS*MbgxmSdx|pM zYm`~XbT3n;dzLcY%amEibg#tsq<-ELmFZro%sN!(bibe)HQjRw+waAs|5JzN5z?m` zHQm#xFZ;co?D?rf^Azb*jhfaBG!~Xq9h-G%9wdFLQPY})e8qCAW3vv;v!qXTY+CbB zELcu;Y}TQ9ob;(iO=~KOHOr}v%{p|SAbqM))0&NPiRDzsW*xc@kv`R^X-!DE%5th> zvku+oNS|udwC1E*U^&&XS%>bUq)#gpPIYY7K|5GZ zHA?q#>Wk_a=L*JD$7UTIC(EfuX{|u|RL8W2AWU^^)I#kEB1|m##Y}Ua%U^&$&t))nZ>X_D8gsG0rI+$lHry8ZT8tG6S(;AL2 z)v;Lz^O)sSqqG)eeOw#T8ju~`S}gymGDwALgYs$*J%5~eyf>tG$SoN5&BiHxa^ zO?y?{tYhC7Q(LrFrr%V%roAw~w@S~d=sj!OGe+hm*|}M~h`4c{BP%O{cM|bQtdwHYv@)L z+jAx_c|FQ_w|7Q{g~9#_1}-EaxQFdM-!n=Ey~6kQ>6*;FD(L;o893RrdHVRF#`~dT zos~ZDqVeAD(zy}(ycCAq<>W1Wv8#deMqSj0rZsf7Jx?a@H#2a%%rSZeZv&@n`9UA5 zjQ5CryB3g6uEu-xnSHCu%oEG84NG^okPk~5?;K5cIMbCd>C-wp;}1P<$i#9v7?+H^CTE?^ z%sBs#`!d_^EQ~9xyesoB&dPW~mD{pMaC*ioonFY|(~bA^%ccG#s~1kr^3|)NC6+W} z{H^>lI54gg5ic|6=FdDA1&_x{)Z=`^>lFS!WBj{9J;r#Q!gd*BKMMO}jQuOLk1^V- za6F80dh@##vz=Fvh%4m>-NWUlisOW6Upw`NtUZ zQDHtY#{5#4XN)oL6y_^q%wL6h$r$rgVZJiP{8gCWj4|I8<~?Jq1BG>B;Ix$$))n(F zvCb6M31h4qh4sT2>q%i9GRC@8SZ|E6{uI_BW2{Ssb;}s*SYbUg#`;!R|NLG&&IfAf zK&KM6IYMFmyAsCvK;gW=Iyg^|KHmdKpXLkFAvw(#c72*J2vhqsUl68#X}%y#cG7%7 zn8ro(1!1z2<_p4PKg}0}asHt3vYf_C^99Mt4>Vt}4*HGe3&P}2nlA{G|7pG;O!1=m zf-w1?<_p3U7n&~!Q+#Q@AWU(j`GPRTm*xw?ln*pt5T-n#`GPRz70nlfDGzDBAWV5h z^95nbH<~X9Q{K{iL74KB<_p45JUTD4`O!YAWV5d z`9YZSh4P6o51x)b;Qyjq*UohnZnDPWnc?G6C1XEstDc``9w_wUoFy$?n@*GV0 z52ktnQ+`6hM!)iWK^Wt}^95my8_ySnF%CRm5XSiMd_frF%<~0dj3>_*gfY%MUl7K; z;Q4|u<_pgkgfYK(z95YG$nynZ%rBlV2xH#yd_frVm*)$@n5R5n5XSuF`GPR!JI@z{ zY29tQ&+>dha;!6+F9>7Z@O(iS>xt(J!dRC)Ul7LnLOtA9%hX8O{@=Z(pB~+`bMWef#=^+Slyuo7OpGC(FrB(>jXmWI5Ss zS}&0wfZCz`ifMgCeqep_gK3>c{$zdfr)j-M@nSi}%e3C3xUih!Vp>m999d3rG_5Bo zA6QQLU|N?_Ua_3=%CzpKyka@!m1%uTdCPLjThn@&@|NY4x2AP9>esZ7pmhVwasHrn2ImF+HtjoTeqbG%A4rel zMc2{)6Q;k@d_kD5!+D7@^+WxUocgEvf-u=j;~`Arqxpg`*-Lg4rg6}GL74nO<0MSu zrul*}`GfpLnEXfc1!3|l`JFJuf#wUs6gToaVTuFI7lbK36j#C&XPPevQ#>iIgelH6 zUl69ep!^_A`9kvrVahMcKf;ucG+z*={GvP~OnFE11!2lx%1gqOr!-#>ru?P+CQSKG z^95n51F93kR5vtV5T-h#Iw4GTL-Pe;swb*L!c>#x9c zf3mm#7h~fcmh(Mk(`OxVU;kWevD;6-|7xskexrW=3XIJfKB9j92Fzoy^_7GTpC|bt z$q)am91uor(SQHex=!lX$l)YEB>5pJ2Y%5Uz`e4fq0yc>&)8gy_53Zx@ZqoMoY>-! zx3?HqeLdshV?0HdibWVZ-JKvxe2F|lIy5hj-f!h=3#G7#nH>zSY}4>OB5+@AmbdF& zLS*>Vfbp$DMa9}iWf;G!4Pu-}dd3G2br5;0hj9BDpLhs4Zo1J|qtW6`j~t9!Hk&A% zt}bJ4_PI8bMbQ1TGWLQ@nFmFE0kdg*97c*C=OObKPPK_a#tDF`odGWPp(G&nEk=9Rdtkkp1O+~Dc{2O!iDAX zH|}CV=_t51>#Oec(Os->6${0)@6>(2xQh$f6Jc?t)bjmjchP8bH0ZTj=r!WqMbqUL z;os@ITM>&@PS_R`nzB3alzP1adaCsxOV6L4!Mm zz^$oOy}$bvnm$~vEp2C2*XJg{e(V0A`Yo)g_ip^Gtqyy22fX&`{&>iAsgxXy*PhQD z2@$Qw$j!~Hs@&*s2zs_bhIFthuUQvhr>idap}f%8J&^g~Ejb+Z8{YATdrjZUSi~7( zTfy-5KjeVsR@J6aYS^?aQQpUEJ9QnPEuU*qweec@`=#J>4P#|>)SunuiQX#UyAF z0~GpUQMLy%D8&xw+19FBSWe2*=g&g5CRR0k;TC!O&SQvdU{w_cPLdxMe}U2{|KMI$ zK06WvBU_?R#48=g2(~fmI7VR`qZ^J9Y-7}Lj9?oh;26O+M!+$GZH$0p1lt$^#|XAD z0*(=EV+0(dW*Z~m7=vwN6gWoRHb%fPO4}F#$0%)M1RSHZjS+B+(l$oGF-qGQ0mmq9 zV+0(dw2e_qiX-Q0QXG@&F{vJt=GCNmHR=ACbbmC~a!Ko)f8+IPsTKI0A{fVB)&1ON zH;jXkxK6&g3#1#aH%b<`1@WKu$XbZU9tnmc!%xW+ z*l)cV+u-}4? zi*j|fsuz)K+@i?+RPh-gXK4{-qZ6vVc|HEmB(FHOHd*J6cui zd8M_MYhq-xJh=Y98>Mv$`yhLyvZ~Ne^`PFwhjMAOySm+E2Dm*tE8j%AtBJ4`Hv8_A z_rAHSOjmlL zXAx_2-*TJt(Oq?Nau7YP-qR|7cUPzP#6euYy71&V?n&2vghLJIfY)Pp)y4BZSg!j+ zL6q;Dass|II}ewzU+bhTQ2NjlIEnk&gQ>ls)rLsei0vmFDi48?3Gf52-S#>_tJ}pv z{Px;i7d(DjPE6JU_PuadkGj5>%f>`%-q_dU6|wU5iY!{+ zXYT5Hb_Z47(^Vhx)m@c1VNsXzB$p|_xT`lMV`Pn!zsssm-BnicR(|QQM4rWKW2WAe zv;R0C8^3Z_n|cSzDP6A0&av3$wlz{@c_EwP9>4DFL9$8l@A4kn85WjTerse=<pQ4w@7>j!qEpUX1C$*wf&VW`=BoxTt&x1!nvvZ=p_`RiEK})(iS3ytcx-c&Plr zGq?}7S-rJ`xKLw;b`Nu-ep!oX>757qp$%n9e~03m2LhmNn@7HY6?b`7cr z1VRBE%g0Oy;QXjCSc7BquCf%g*f%g7$9{ZiNARf_16Q%H9cNQO%ZC<`A8qI`%}v`I zYY|sJFDzn6`RYQ+wQ?q?Oa>^vF=>MK}nSN&VD`k-DHdU zhWhV%_0T*n{E!lBWM0pVFge+4SsvTZ(WVDDEVv=dV81uKec<}*!!j+_+SzZ1VfdpJ zvK-c6x`NlCTl!wI8_LU#c?H!kWR`VMzs>d^5W2L#o($V5jPv4=PgmVKVEb!II*95K zceG(xgTv0p!RpC%AUXOi_|ix4emondpq*U~-iHli{2?CwyeQ-ZXsOP_BCNqYx3)mp zQBU9pj(5=rF9;bC3CFPgVH+#Ju}2B;0j~`?e^86>>>x6u-?~rS=_+<4!Un9t)L|?1 z&5OT5KlHQ9K}Xpw^)pz6c3%B5LSDh|KAeqlnNVnhTs(d+l*D-DOeJOB&;<~Vam+pL zw*3CG1%#oUgUY^_>pFbX7GYnP#>L9Q&2ngs(9V#|4(iZ{>UtH-lXdw0a%r5BNeyc- zs$qgDQ`=$tP%ApMcYF*>i@Rhc&o+!b3!npoeDgzo!5VQImH|4|crEK=`yRu)!`84H zvIzE@yNnOabvq&-p*_J{4uf-zmGU*(`Qkwcc)jZ-=b`OuUc)&nXt$4r^<$ z247-)JrAC9Z4#IW?pTAP3i;?GkA8#Ym=9&n6qP4yKZEsXXP!JG~X1 zLiWOU%&Q?sb=kyqAr!%Ud*X6iHn`FfexRMlquu&?n}eD}eUM=OnX9!T$? z=6F=mqcNZ3E?HEGN)B=)=J}bvG13~_UJk&#%HsD{9`ar+kK(nK5um z4eH}|EiPWJ#cLCtj%yRMe37@Y&DLkD!MzucWB~T{eC0IA7I;QZLmLi7`$4j5+vRq& zt*pms$nnriv!NKwH)o*riK5R2x3kR|H^c1ZN z`lOkwMI7?a1sBj)YyS8S8(w%oFSPC5^B0iVay9s)%|TbM!L)3FpwQ>r4j+JT&qJXw z#=_TO8C+QO22Nm%+&g!Mjh~|75%x7{ODb4+!y;Z`OkaJet7$15M0bpJ$GPeBxhGSs*f^-Vrxr9qzpX6! z3C?Dk&HfCl`T$y;+X)K&95eVNz?gH87yaL5hA%Ao{uugTT;4aI0tE|4!W*>n`-n=A z@?Ziy#8{M`byO>iH7GH@O+G$zEp;go@?qR3_FtxFdi)JeVLrs%EFvSvKZD(9XMW97 z-aUL7dZL}Xy04e5oc6&P%qyP(y6muJA#}%l8~y&4^ayAL1u+lroqZ>VWQ*1)KR=3C zIq^__EhE}FF13U5e_ByLj`>{sx$wOqqZ-J4Zi&vBFK3!?8Tg@)?Tly{gkZ;{!D94z z*K`M=?z&LuiLvYh zJvABC)f_7e?*hGd6z033V>ObboyxA2vqMaot?~$V~Z-gC~ zV-1I0lvmuxf-}zl)7C`DRntqr2eh;8v#+wO@YR~5oy`{|N{3A4gJxq6pTim)-FBP) z5p!ElnXk5In<7U{Db{KJpPIcQJr#6vLP?Mm4b?M&?+0;Tr!kq?~SRrUmkJHEf{O?QY8m*s6ePzn$`(9;=$#NfPv_@ zfDWIagx@S)S2P>-0D27B2^-PRUco2fOT}~W2-hLu4}8I8%mWyT*eBmCIN0t3B*SYL zE@=z}H{FFsn1}Hb=D~>X$FWv1b{Tg;!@<5Fu-`#D&w;h;G(I(i$8>8>X%J z1X=Su&Yisz3x+vk^^ zQLcMNLBn!gWEs46SomvL5;{-5&uvw=Kiz>%Zhq1~pH&6-JOhzwbonqVo+aPi3(0C; zmzgqI)w513z;jrH9FWo zt+Q1P96nGcl)WiyRk^68L-|ZHSC$ zFXM#yXNOCU2o>li#FRQ8PA4q58sbDLHtWty77kV9D23VtAt8JH8?ta$&$=RDC9 z8$!g|aM+E{a0cHR4K8c9==f|z%q^b?DOYTAo$}RPtZV2XW}H2&xkR~(W8?5y#lG_3 z?O+ujD&X2}%LGW7!zv0ohC?~aCa7H8Dhf}(0Npel#uT)Qe0}#qv+Y+Q9pc$jR>Sg> z4*{R;h>EwTLD@qepqP_YL|f~^(IGK#qJmZY@c622XoPF{>iB(3(}gzetVPra1^n(}6;U1f%9ATYp%qxg_@_(c*kd}p zce9Fqwf0C$nyoOanpNz6bw)PLIS0b3SVfhZ_vE<~?O-$ZHE-V=8UHXFc;dCwpGCSGBs)S+6Lp;&LX7+CT4;{y;-KCPubvQ$r4}WffDs zKFJL$M#@PItRh#72w7*v3hCR@DjIyhCVLIoC-XG7iU|XPWDA$G@?t})7}MHUJ}Zgu z{MNUMHowo6y&t}!XJ}&SrY5QAs z@dcja)3aYX#}{~xPiLcajxX>WpU$}H9ADr$KAmyXIljPid^+Q%b9{m4_;kii=lBB8 z@###B&hZ7F8o#P8U$EP!HI>#4yj!$RYbdE3Z9G}j(=^S6+IX<1m&^f-qb9_4E zrgMCO=lFESP3QOm&++Muo6hkCp5xOQH=X0-v{sg$;nO+3z;k>$jaTVws zpTW&)o#WFOiK{^8_%uf1D$qGTjghztbdFDBB(4IT zh6& zJKV=z-U={w`$9W)=Fi zdGKTSTd0}ND&AV#fq$WB$b-0D_cRbN$RawYw2CIxx@x1VJBTvh+;J>Z-TG(_0-xuI z4&zS-Pd`645IF`S7@wyWy|qn4j)7=AFcDHUDh0?f5V?H5LWIM3K#qaf?i2xmBXJ-7 z-Cgv1djTr#Qp7P3aA!B9`goT(1|n|PJh(jV191#QvQv%Vb5`7gVZZCjywFl+aS+Hc z5CuzFv@9nr0yzd^>D3ncs>RX7F%Yjhr;|?;wtW=(OaNJiYoX zaSTN0$E{MXeM}q!VeL6p4qy0%I0j-!?kaMSmOvZ>k#bs~u39)KG9ki?!?nqa<<+#KG=`;I~iDBytRd*VSQgIQtdi7>Lu>b&xD{KXDAik*`7Ur0*h$ z90O4~>=wM~(Uv#{;(pC{FzkAqjvNEgNyWgh!liZO7>NA$E#l-2M-4d!B6A`>pV$_s zA;&=Yq>6?49&G?Q24ZpVcd%fB{p z0?08CkyTw}>xqv6IR+xS;8fZ8<5}Vui0b9G%2@?=630MHOL0oRtv`!62Eu*+0~z-L zh+`n`;WLWl9j|N1F%YtJyd3x_zzsPDVsI4)^`zox9XSS~-voI3!FfpDoD0U5KGCXRt9+2Jc> zoxfE_j)54HKM^|A`y7ZI1JMX;(DD0L4LJs4-=su1?_Ls+V<4jCSD5BJ4v=FYD)fqg zIR!TXaty@riWk8XAG0FIK(wo{2d?hAOB@4{ImdjM+x7!-48-dljbTGnEO89Pv|O*W z9QfHL$T1L=jwaV`oU;hz7>Ex!o9aCSqKRW5_76%UZF+oF)f#}}Y zq8=Uh2}X{ASkc5mRqhv}Bga7K-tjV1PE8`mKm@$_B**QVDP1s6Mh8ET?H+6=j)5rt z;FNsT{48+{MBb);a#h#I5;+Fq<>jfeWbZG;F%VJ7s>*345{P3U77h>Avp088$T1M- z0~-hTEoD*2F%T2O7HX9iM@i%uh}t6xLe(0C5b& ziY-Bq@$w?#7>KBax4@}EJK`9K9BJOc!($0Laty?8n_^&-UpXB)1|r2Ri)df4u!bB1 zF*&(|Xn7$8$}d2I9qvcW@!uB0!FTShwpIl=R$390T#nQ3t=6%fvAd zb<(bfn){y-$3PtM`~zAhiz1GJC=^o|yzV6u$3TSLT%s-S$eqM75CsmOl)LxvS%Ani z{DCZgM-azAM7H@PZ`KRdkYgYmvc=1M=>px5V;~k(a!}7ldg{nA5WS}1Gsa2TBytSI zoH{?`qcwdbaty@nu$QvXvy~D#2BJxi5c&1q5#kt#Ybg)Qz%G2oAzTJ8m$^2)CXRvF zeWI&8UpksN2IA=YbaL?$i$acpm{a9pQm>vaty@2GV{O^aGW>>qV-ffkLbObI0j-hzKfJ+#suORh&)l@u-Hx^LY@*K)B|8DO+F7NgM;Qclb-U90Sp;`ZVcR;|p;NM2inqr8R2;aSX)wZc=ZCXP3w^5Z%jk z3|^0CD9AAoMWej6Y)7Ibaty@bSp^`v&vS_!15q*CP*}3+3ULg?WB;`aT*((Q?3AadP&3u#(gh+`lgO^pG^a+UNmXmePIMO5pbUqg<82u+RW z0&joN8LsG5Cl*d_Xa&eI5Du5#!K2j+0XYVuO5`o@D723_2IAu|9d7QsOdJC-p#OTP zG5Q&C3`ArLPk49#8*vQ8$k#>S(uG9g7>F|SmuaPOzDACLxZ)iVbnZ|BaSVi0_oMm- z$4Eeqfq2oQk_?V}49GDMIqOf6=_Z{cj)C}XlCPY9btiEQ#Ik-TW#im@CN7p#d?3r7 zs6`wDakKa*IkD1B4LJrPb#$CuTIGZratwq|c?Xp*XsC`H15pQ`ua{VyRU*egZ0Yku z77pqykz*iIWPBy3&Rr>yV<4_=3Xwx+A0du`sMhhY?2|K;I0m9t$a1;K<27*%#Es3} zq;J}2;uwf-i_^>c$QeM6fmk2VS>J|S0^}HoTyBrut}QZZFw@ltZGWzh5;+E9M_hfl zRpOpRj)5q2axNT=KTaG2F{kVJyUQpsY=-vDw9#KVT2<>R-ZfE)wSB6_JzlQ)n! z2IA)41M=DLtBGSE?w-FU5B%^Tj)CYJ{zA4>xrk#Rb`Sk755JnCA;&=MuW3%>$$m;)nv%Xs;?uB$|jfoNIhvut~7hD45m=vwQc{9JxJaSTN9p{M1A180b1 zAo4qGlPAKNdn4v_7E;uAAdZ2k-#Z4r1XR(HV<5aQSwx=$xi#b%h;+Et*qV{KOyWtm zSXdL-5|CpcBI4h{waNyP*4w;i>KV<09)eUvc; zZ)?ag5FwA_WSI558*&W9^fC@=s%4Ol90QSJu|>_>l0_oNKunqaLzcVOOCrZWMAv&I z?^awXkz*i=Muf<#Rgu+$IX`IUVfo_f4dNJxVlF=Nhs$f?7>Fa&y36{neh|k%Je!t5 zKAB-r$T1K?iIx+?A?y9J#4!->?nOe@F8(@l48)Bm39!g( zX%KP@L%QLym!%d?XS2uXY0D7zno--yr$Y(SRHSF(KbmSdwESAjd$gPrL|I z2T9@>h!HM(q0n>YE{YC~ykY!__rx&}&8*Ep+Y(D01Cj35doAv`MIgsO^jYAlHUCzn zr2T#HWhad9^LjgZg4mpFJCHnY=x{N!>UYMM%6Av>zZVuH&uwiaW)%j;7lxD(0r!mW zZYa7rt(f*>Aj{onpM^0UjPFNSm%BeSonm}9L8|4GH1IRNcW*(S8~W$HqgcPk?b))t zPd~6$e&exxZ&kA?jsfEW+A}3lEI<>+=P9 zh_n|cvdwLij}bLS?BsE+FECkDoZ!df%~xWwsGW8K`{7;TG2)s-2;-M;Jw%s#83m0o zJYRdUK4%5SsZZAwlf8`Z`v_^3U(8(HljW1De}L+vJQm|fo2;LI80)`Zv0t|Gvoao(+oGzu7~dh14~i-G(%sPY%Nu%UDXuH{W`g*kH=aw?s6rYI@hBgwCabBs8?=rKx5JA5qb*LY~6DP913=1{O-53BGwZaf6h`y`0gpp zICGvx;!wIDY}>QQZX)xe?Tnx78ZHh#F3q@z#{?0y@j@Wk`7Uv?_*S+A5Y`t>5TPlz zF@BgZTx1v!#rRC$?xIaXAwfC~d>aYJa~k9IA!Wqi)kX~-OO;L>xoFhj{2u2ZqNY)U zAs;;;?^q*t9v!A>yY?G3=(+l;KJJ=PgHY z=PIj++PMuI=Cn}zou9L9m*4kRqb4k4JTh^Fat*dHPWNM?>XxSn$L`&g$tvT#R+8+W zyLp_dCXDaA%U*AYnmWa(!3^oTsC@~}igbFVsiQKjHfnHaR59g?TpN;4e1aV3Ge!-5 z>UBVd3^r;o%(s@D`@x8vPaZwkxt~#ke@x5@)lV5U*s%XvxRkyZw=-wvJJ^%58RG++ z@`+OCj2iq=pr)AUZ`5G!h3&-9gV)*Skhvb>wj($F(9We!pShX3o`1 z6(@@}jmPoWYrBmR^NU_%yt&{2acP)QgO(oc#fbCe1&yUv23PUF*n11`s*de#9Cvru z1b3I5J-9o8LPBwO3xNO$El`TPyCk?vp>X!##fucDrC6~RrxYpt*Lr7m?r?uk|KEX> ze!qLabDyWTZ-?1yubJiVISCbADhBth$S7jARx!9B^+T&>0~Ld33NEx(mr^ml`Fc zjJggyWLgI~q=1US294{>_5mseU#%%F^Ym6RIJ#6y*{+a^!HD~p?IwLx3?7&{#-2Y; z#o(6h7u^pgDLXc7+0%7tjEcc$W7}I@{8bE=J+b*R{1F{Z1?DNm|X9!XY(1m ze;Xo8xBC{jaIc=SS2`7gAvFVKfdwiCYX?@6&l{^4{H&IbY){`6-j^of#Ms#6Tq1pbQKvBsu--gtcjQtred&6gYx3U^IEv`Yq2wlYQ8E4 zCp>*XKV?X z_olzKmt0UWI3Os8JR727aFty_PD>gGd+MeQkT-1`dKRD3LnbWP4ES}q5cxER3+GDr zZJ2C!;3>|Vu287_<@h9<&)95SkZii{8gTR@^mkOAPK|qWPpdCqMOQKSb(|9NN^TW{ zh3BV~vtM__p3S?j*o_*h7+e)H)(#I@vkM7$uRSZ@+(9u+}^_PCf(v;aqDGx15T>Qlh5llR?Gc z{0Rlboy;l*Lk=Yn_qwYXjFs`Q6+gO)!H_*Ytf^g841T?CjO)rl6@%qpeCO_zEEu-1 z(tTy0FQH;^%!KoHiNh)ek5@}BTc0b9Jz4S;lUb9c1D^l5uCy+w7(70#y)5Q819}$T z*a-n?h6o2p_k{8oA~bEJyF_MOX$GQCs`mPqI?hPOKdJ*VdF zB1$j)0(jtxV6n3MHk>Q;b*OlLXD)p8bj2`HV(kEn&zNAqKvDg(?-1}OoV&8 zd9#UFQdGs@u36>9w<}Z(KIxK4Ouw)Gp1ASH9$E3@s2Gg>c#+jHm5RZWoRIyJahFH<_+tu*TbU_V#8f2EW+zr#(1tHN5xx6glLPV=4yk45%PK@2_I8 z%*E!i_Hqe5ySM8hzl<3G9GpEwZl6{e=Mr1PWX;zPao!Prq0;B-M4QjpeSMI8cHw8> z>Tf&91N~JD-acPneiyEOXV;{5C1m#N4RHTQ-ldd398xj3Y1)r=KoJ##?zZFX;NB_* zs~o%LF1SG1@zJ(ct~+iOgZtvOv65|8F<2D!lnzrXtX5Vt37BgUP{jQdzS^0!sCTbO8q>p^{mH^iRdzMmijdyXv(wAYMR>)FrsagREn;&g4hL$0phs5m`Y zeY-eMK|VXx!!?-ZA;KmVSz+S^hA2exh?WRa^l?~o21MQPUr;PSr) ziNXo*z@~4Shl-*>jbZC~E5bx<>vNnv?XyAj_YUs??vSX5SXn(T-dnM0bCIT7Uf_lI zg=oJ-`Pk^t>|*gr<$GN+zOlyLRz5kd^jfP!tRdK+_qXC!;Wz4xb1xL}YxtX5UsgDa zUDDkbdm2Y9u|r3wSh!yIiCs2@ijiUkGRu^`3S!U7I)238Cj^cc&{W3Wb`*NH`LU}E zd)ycJrws$;(JRw%uJA@-@`SYu=bd~nRNm}0+~&L5)h$?V$$A#JRf%+=9_&uIw*IA`<&WhLZ?TOcv4{wTi z=~p=IV941vt-5tBv&vnAE^o7%_^F)s{EHYOeNbiW@oVfW`fc$A-kPJb7=9}TaGB^W zMB|;`K+hLXdWv_WY64e$8zNTaiG_1r`!P&Rs};{;{eRm&RP=~F3wT2R{$gSKJHS;l zwHJN%svJJJM_sXcY8k=%U$!eMrq^r?d|_-dadEP$1@B&;weHqczPGmi2rJE1<&&$^ z?smNlRCb(jVv@VvG3Dpc3-+<6BvSr=>GBbK%mNh`*~cf85erqkoJdtr=KNB{QRVMz z%I|$td@ZTfMy8my6na*i-d8qym=*Y&%R^+1wrTKpv%2W-TYmbosLeW$%P>TK*njAe%<%coH^U61An`3?0>bP>{Rh3V&6y9ssx~TF@ zqin70KNc(7ecm+C-KV33Wt}<*R~?$6N7dsXR8i)lXK+4JyBVRxOn%R7b_& zJa-APExyW!JA4|@_bpVOOq9Q)sF+FR&#Om+M8?_oVY|C^LPgDTwc)EZ*VFF|>=uZ# zA50t~o($Rze5_0lvF>M;x696GE_TLOG1$Ih1<@x^#bEf^?4sff6@$(0zOfRyRSee1 zxsE{)ioteg zGRdkZR1ALqth_ALLe;f^v`uBc3CEykhjm@$h28yugQpFY@t)4Yx!%+WlV2^_j`L=J z9x5A6_|j%O&KMmmce;K6e*2=c?7cH7Y&7M3V|nk0s>`)=m6gwbse|<`1JcXPt5gi` z$Z^k}nqS4>{`0f#>T^{LPTiEyu60Y<@$lulel-iL7)-Oas`awEiouOFM`J02Hx7Zy|~mx#h|smu81jA4BpyVR6LHZVzAk> zWFl>A6@$mmoU@h{Rxwzl=t%4QX%&MDGwpY6Xs_%z`0hA&o7*Y|Pxt6$4{&PGpNH+E zH&hIE$dOQ1xUXWc+TH?k%y|`qq2p@Ggwa%=**s|***8?xzJ)#dO1}tI6RRE>B5nUC zsFfw(hRK8P3ghg1iVTr!daBx5tZW~7f__Gk&wis)EBTXDwfK}@b!iC|gVPJUoxJ4HGBAo5Nm{a)pT1^Hq=Zc?XKY0V)QMoNq4jtj#0%yi2B35TB=2G59o3 z4v{86#o$)@x#Rj%R1DruvfdhbNyXsf@ujWhx|fT1+saDk-vdD7P(>`4uEE_ggz3%n=U1WjgDh4xU@Rz<{s2E(>y{xP} zU&Y{^3+ZLPJ}L&cyt`-LkE>#^=Z-mc*jN>VX+jd)ckU=VwhX@L*SwmF!B=N1Tf6$G z7!1m>)ta$Y#o*8_(M9IWs^>pC)<@jzpki>y*h-?~S`~vQM+b^tqt)!NWOh$+q-kCF z+ofY6;>GJ^IM;)7VWPm^Sg_sAa})MWyIqZdJ2X!&<`z;h*kR>)YqT>frTxk(tY@h1g$}uvc2_ajt@3Dhofw1gY|}M8 z>{>m#0as0b*dCW#^=V)4NFW0XyRg1KxPY8pI16x>>NVxmA5{$IJJVX;X{TnuY1R75 zQmxc%IDY#O`Az4|h{4$J!sPR0YL+ZrZHO#BNzIt^TKAFZwyW85(2!O#I6%eVfC<$l zQQVS!b%JW?^(FI@?d9L%cZP{CZ+`|m?zBQgcDLdRCQRueo+eN+=$j!xOlhWK zaORZ?!tV#gIh+c~AzYbM491-P);iNk#o(S7>#Y(8RSaIKS=M@}IgM0fhWX{nrDE__ zhjeznqACU#++S#apRX-!wBe_RcF=tlgP*0$B!`bzF<7Z`dHH!3#j%W^*+kx|sJNF` z^}5R2BNQjIqS-(hFn1BomA_P&jPqj}H;(Tup6*I~yj&ADp{-W#kTNc0T zTf4njyCJP${JeBM(PgxX!A`-&MCCy$21k9HT%3N>347{^2Kj3?3?W$X?S~#b9Iq1oB*e6@$(5QyrYBV(`b; zHDnC>-5RXVgqf}7H&r5l(`V}|ulx7{XNedhub*p&7@SKnc&0=FoA)mX7$QSADXw+Z zs6MjQEycl>`lgjE^*k%?ZROSK^7IlFgYGN&>MN}bbJAyOqMNF+&EhtzItMJm^hrPDb9YT zX^5D9(G8qocMmaQq2kixwg?b8YJ`Dm$f#g`p5M)X&qGx3hwA_S{=Cljh)9>HU?<04SpKiN_c55Y8zz*F zABOoJ`3Y^8kH&^Atf*jhhL1Z7|6L&bypGwA#{4|X(K+O!G0XT^yHK1$e;uC&zj!K<1pN+~{j67yV1xKa-F`tdfS&ZITL7r*oGg94ZBBaR`NvWzuIH?GymOT$X6U&ABv55&AAVk1xTT!6EXj1R`1==@iEjCvuWf{pscbAeOKJ{bR% zo}R5&U-7SfQNdB^E6itE8|S}243jO;EAm}N1sk^b;J(6q_Fwm^(1)CheVU)rG4j#a zh>&M(&DIj}eu#P#ux{ysjx9jg9&er5+AS?E5YKiB!F;1BH+{%U_z&O&~Uvv8e{3jWYO;ji{bAx+G5BhUS`+(^=NzVh5JV|n0yodj( zK5G!aPwI6yW4+&ItmOb}`M~wHiAJ|(B5DDnLpyic#=yn4T7$N|>!f%*RUzm**5 z1FZD~*7^g-S^M2G+WSAS*N*Ie|2cN#nALWKAFPn$(QrL^*YXL#GNAtccSG3 z8*%6819?W=Ir?Lr?$4Ls!~dArYe&T0e~cZqy(HO@s-TKaZ^Ah+C~c;z8+yxXW#<6PJ*4bZFT$Mx}&~f)( zJu>3%z4~Ruo#3-kpNV{J#GSLB{haFpy%T=!$j7=7cO)k=?i@W?wxd6=SquJK&!~H8 z=j>e5fsNck{~g)8I<)|MbnH8Kj(vQGW{qZfIyd4O>ZRE~otndvp)O=W_aIK9|!!^SPolw;FsV?vdY1 z_kerU_k(+6%zZlFBV+wu!C319tn~!e`U6vq124t3u;ahw$xl8blzi0D zneUvq`y?|0@hVQ-;XTgmV8k8yab(;HBkr8J(k9<_=1pK7N5Cvk=MBVz!Dl*g$LDh5 z&XL2h=Ew&&;?B{B^Z)AbH}I8SrF=KaR(?9@9xBjzv?eP$M55HmdEd7ygzIY=3~9i^$zQXKTET|82-=aimXQl&+}gW;(K!R=Xa33 z96poRojT5OhdVLs?#Rcw5$}#Z^lyC57+IHD9>0&*>Hfm`-~5l)c7M-j%KsN_C&-S7 z1MQ!P1MScBXOVu+b%Em!`;EBZe2#rAN5>tCO%eBl{yz56uvuH>U%xQ~#0&qkag z|B*eg{&&`Q;@(krjr{XT>id6d9p`hsZXG)>f5&rM%^l0FfSAB(29;VdW%Vom8BqDU z^~e?HW8DUR9K3pkZ}Vfo^zRk)-@x?eD`+1uJ-33M2PSzdNp5Z>C-zEyA7j0ap9|Of zSMa))1FYo(>-Pd{eSo!|z*>KLhx*PboeP-X&+p@P){EcAnDyoNG3Imd`xx{2_{Ni#(YowKE`~1gRh*OWUS-7dVd~X*K&Zhd|>@vV66|Z))QFkpO@wE?K$>h zTsKiK+wZr5SWivAt~L4_1?F8mZqO85E#a=_dqW;=5a&044!m=`j~JS<3NZa! z(0>Edp9|UtOwS2=9`7M}^!H7v-*-vx;XU}DUbpx^^nPG12m7>qVEta_dDaJ5>j|v& zclMBE^*(+-zmMO=dhz=h)BmI+htI+9<3&CnzmGBfxukyq^L_C9c%AQw-^ZBmZ@yn$ z@`uQEo3Y*xtmUvQM?SEAFEITP>jSLy1lIaHd;WHR_##0r*Q~DH;A1(`eeFu}d^db7 z{Z<)&0r*(b zs@l3MWY$ge&^11GeaKAxu(Fk4{YuEZRCa>3?X%x)j)gn#)>)Uwr-jVe2M<~^d8&(bOG9S08-uMh>1IIYob%hP?6)sMX2i>%t?fzT zK<0_j@2qE4(n03E3n|6)VnrZxPNQsMbus~&B+nwbkV*0^k_(w6&my^yN%92AwK--< zo*=n4$1KScBo{JCo*=o9N$0lc{BF(zbZ(2z51Djsi_Q<3bZ$ZChfF%Rpz}i}otyrC zgr2?-MfheL|+TJ7j9RL#DPnWNN!ZrnWm| zYP&IoI zI1+rHI*uSy#}Q=ec!x|K?~tkE9Wr&iL#B>*$kg!;nL6GfQ|Bef)OiUqbzTx|Bb}EZ zQ|Bef)OiUqbzXu@oj)N{=TFGg`4cjA{)9}OKOs}+Psr5y6EfMa+3(p#jM?wmml(6( zv!0Bp?n5SH_Itih#_acOBgX9aY$J|K_IsAeamjwqGC3|eK3OKmCC4Y*h~tvulVx&T zvfr~zj!X7?mdW{p^9al2{K0_IsAed5-;F`=`x*&oVh5v){8!&d2Qc zER*vw`@Qy0oBf_;az19iXPKOj+3#5<*A4c2mdSO4{hnoV-C)0GnOry6?^!0-4fcDM z$#sMMo@H{~V83UXT;JI5Sti#v_IsAe^^N_WWpaIEzh{|T-`MY2Cf7IidzQ)djs2cw zavf&BXPI1w+3#5<*J1X1mdSOP{hnoV9cI60nOuk2?^!0-VfK5L$^8QRJSSI(m(GuOv z#WK0iZBZvtZkEY??vlW)xmhOnxjj0T$;~pk&)xjIdTv8cx1py~kKp%)o=!c2-y3?` zhMu-@pOC5V(>CtYHty3l?$b8z6EgLELZ-GmWNN!ZrnWm|YP&giP(9kg5Gs^4Yb2NNtW-9Y>I<<4E$^xvycle0Cj2 zkg4McGIhK|rjB>W)bS3PI^H2u$2(-|c!x|K?~tkU5@hPU1erQ7NwyL9HSG7Sr_M`| zsq+$K>bwM*I)6f@&YzH}^Cx8L{0W&le?q3tpOC5ZCuDMdHs%zbzXY$Ca}E7xh-;1-0zIS7M`5C%sfEX8T? z>`!tcISpr>XMblu&+m>LU@ae5zZY2R1FZD~*8218k2C7oUl^PKpNlySM-Fouzy`O# z=VDF+>joFWdNQYhbvhSw8qlBLL!3r3ey?7~dG-Dk`dkh-;>gFkelM`*G=R09z*>Li zWSnzF;=kJm*sq-TnDeqZN7IJL`P!Vj^}H`xf;p#~^E>-B%jG@v9_(eL*Wr(PKd_dA zbDMmEelOPP@kstb>xp%(Kd{kT3Zu8=S&C3;@MnK9^+YxXLCXMmS-uR%?0If z%jhk6=HuDiq8u)a9++o7p3NcC=z)3Wq9Qzr!o6jd~V&d31dbR#*8NT+`4BI#*8M68I3s!p3S)zvh-}u{gp6gNny;A z!k8t6F-r<#mSpaPXLHCjW?o^;yh6|B+_MQin{&@5^lZ*On=ocx=6HBEhfI!Rjsw=y zn9a%Vk+V6SJ90J`#%xY@kDSfP?vb;(rS;@q$kCH~Hb+n95F9I<;|MZ!9C6*$kcfWGId^pOr4jwzhW-R;S8O; z1erQ7L8i`2kg4-0Wa|70nL2+$rp}+xQ|C{})cF%Kb^e4*_II9D*hY+bR$*Ua%(DvX z$(UyqzE8$HtMJ(w^Q^))V$8D&+sNoGInVQK?&!(0xuYk~=8m2`n>%{)Z0_iZnTll^ zJuv5ap3R;6$1;sxo#Gv{Ib<5WI_Ei_%^kb*Yz~=5 zug-ZMGphDaXQmLwOu>1cXLH9tc{YbkW2RvL#4OGCY0MOy=P|43IO5qHdK$A2=XuQh zY$Nt}mdiFWW*?3tp3Pw+V@BgV&$BsX8Z#Q_dCBKznZ}I9d7freaIl=`c{X?Q5;zpr z)0ibWFM&hRc?q)$%ha>Elb67u@Y#)7lJh6H9+s(Rb0>c~GcV^)a6K$j&*qS+XLBci z@@x)0+23h4k6@X4HjiMRXMd;JJc9Mqv-xtCsb}-$D&8@hFK0dVY`&cBZg2>Wp3EU| zo_9C|M^C37IUEA#d51&bJnwJ_oaY^`!?{mO=Xrp4#rH z#oF$WsqJp@*|ps*!|sr&?QZeewcR08`=@32CuC~>giP(9kg5F>GPQpSmT7QDs2fJV zm|jw4~jJM`4?4n1|eL#B>*q3j;X#c`f@xHu=?Ayeli z$kcfWGWBdO_&)V)4w*VH3AT}*&7r5B%^_3gPsr5y6EgK|4w-s3hfF=2L#Ce1A(Q=G zbDLJNqT_vync|br=HGpFD;L)UnkgbbGyN2^d9k92!<`w%JR`r`IPWL_%#_~k!*4Wa zD|6;DXEAd|GiNt?JaVQpXFYQU%oTAe!Z|OkM{*Pm(NZ|pJc zV%m%Ek3I{gIXcpg&TPn^i953)%i(|cvta%V9az5?nEzbA?>#O^>+kHLZEChQ&uiWT zZHT-d^WMz+H1FBGf732}fB$AL=UkDWiEBB|xgtM9*Y9<7W_^IQp1@jvXAh~(|NGaR z?ZxUwy!YU}hrh=M-pd>RBOd9NBjePJU!6Cw-;8&iH;@x_-T-D@|1EFWY(X>6nEA)d zOJ=^(`bd7(%x`Ai`)|$jW{oy6-v!+-Y+>e4Gq2JHuN~&61514a}Sr^QDL9+it`{DoT7v7v-1^s}Yp@8*l0sOxq=bQD~#ALhw8a_eAEC2uh z^ilO^-gWOiczqyhKA^Y|oi~u*sIGmIpV6Q^wTyMuyq3fB{O$Y|&1=MWD!=$AYS};a zGa7V%Ccheq^%))8@z0?E(^da%JqdBh#C1k;s*dgcc8-pEt$&mo|2Lm>I0W`dV6*O< z{Qz+Ykw33Q*CI66;BczAe>0}|?#L${yQu$s@4wAI^I~;D-h1%g!^ir7dd`eNZ(Z{d z>`yvZ0c*Y#`TXDc)&CoH&Gh&G)>>fJ@&BgUt!&5t@9oL8A0x)R*y|5}hYuV%eC8kR zjYEfSpcx}_Ui)Od@s`b3cwR$q{7>Y=cKeDs-=m29S$ne%n)T8AT+;l!lCCB4^DoT< zBi6P4z-ImO+Ai`tF#P)vU~7H1!1~UCwJqRp|NdQ({~NYbvCIGevAwAGS??Wsec-Qs zK*iPlc^Si<8Dy(SAMWJjpmHg~ot%7VUz~6!CvWcZV40JX0}~%&ZV@^8{=B)%oSdBb zrvEZ0C;wRB!cxWe3==CO@{gf)d{#p1IrVHPXg_~++I@~7dk6N88Vsb7zm$Pp3y54W|el16`94%k6e1~7+_iBA4>*LI@ ztf$srvi@pTqkA0wGLb$nuP@d2Ao(8j{jeP8-X!0flZW{}^*ysb&i%8Vj$K%P>Iv}O zn{c+*zhinwG_M`i?=Sk_Zb$Y@winybi@o>Y^?|?F2Pm$%MsPm-%Oqkef$EfvP|D+w+FWFuke_rgp z2d@wOy*?15dKl{3`~$Pye}P@S@2fpMiy!wh@GfJ&xo4NL$B(t;TBiQ(#ol}H`heF5 zyguOd0k02ueZcDjULWxKfY%4SKH&8MuMc>A!0Q8EAMpBs*9W{l;PnBo4|sjR>jPdN z@cMw)2fRMu^#QLBczwX@1708S`oJgl0el}wy~F#np5A-#`heF5yguOd0k02ueZcDj zULWxKfY%4SKH&8MuMc>A!0Q8EAMpBs*9W{l;PnBo4|sjR>jPdN@cMw)2fRMu^#QLB zczwX@1708af5!*9M4yD;bKGfFkTmhlKl5O{!_Xme)ySN?CS>B}t{ zAETfAtwI^ARffAu15OW?Ija3xzTb$lOA@{flLe#KwAal$<`X0KU|G26F?)6Qj=oFx zc9l7&r!v6^bet9R^<-r)=clR&a ziDwLu$*X4aoiKT{{n$TD7D~OsC;87)-S=k=kzXzPDd(1sxvY5K^_Eu)MdXO{>sqVI zz1Fh8skGUafBnpwwWbn&-%oClOZ;BZ7kJC?%3^z`*uXhL1H{HRf7pE!rS{#ip_OFJF0fv8d|oNKR|U@aGKXw(supndl9{9@dm3HMWwE`U zOdTRk-2LSQtUo##B*%Y!5qOW?NpAk_32L`WdeL2u=;(-&@`p>`ha#=Y;@a#|5 zn_B_j4gmHW_q8=9tQ+u-eTS@|*)@QFPncDl6Ux4WA7>KXq6K2T`{Y<6ZY8z9^^L<; zg&c#hUT{h`tH&MnuAEyh`yHG)80!H=Tz0=p>WrenNqbM+nph7WmPM|4oDFzps_OFk z!OXy4&#oyOTzQK7kDI=Y{AtZ};2fv=%M4vZ+-!?3Bg16Ug)d>d)@eg!+j?UxUSB$R zfIK(iH{f=M+sgCj(hFWcxuA}$?q3@C_1a=GPa6yPhHriuF);;j%3BTP#O{0XY|=B` z<@#L1f%^sp%QLR$Hp_Xiz4d!I-jIV>&-l8V%-iT3aE#E-a{k?0!1s5xm!9lNS1=`X zI69!AG;!%<`LVvFza`ycwV%()F5{G{uk`m%Ba<~~1H3NTQ@c&KLBL7YceKAfJ`niV zG=1zxMS25I&#}?YJ4fx${pVx5bL*N|KbSO&{OVU9;G;(?%hCrQT72F*Mcc|T_Aua@ z2ZLqM^sVK2{Vmm(*~LG{8CO3WBA4tzb)Ai3qicfdca=_YMEndJT7=4veS$FhJk zj?XXqWeNZ;9yg9mct-hB&T`+`8v~Tj3@KL0ZgNZc($h6}cQuTr;^}O@lV)K2Dbu!wd3V`ILF@ZSpVJLYx_o1KHTPH z5Bu;vrNi*trR-Exk6Hhx$I82ZbgMn1W$XTV^AI5#L9U45+b{}!80*}vqj2bp09)5>+je1R9$t1QQE{u%eyEpA8oz zJkp^q@Zn?WqpfV-8xZTHzK8IF^{X0f%@_P3^WAMBGmi-RAi*;j6&;B3xknQj;ZM#TJwgc9- z1Jq&N+hj=$r$r za}Kc1IlwyS0PCCstaA>q&N;w3=K$-R1FUln@VAt6DCa{Tt_vonI)ZhsBUB@Rxkga! z0Os1^$sVfjc$cpAk(g?|m^&$EE?w(Iwgd@$b*&d)N0iQ~YrPoN=xJ76>+!6v^}xE; z1M6B3tZO~6uJypW)&uKW53FlFu&(vMy4C~hT932qS`VyiJ>o^zdNMn)Sh4d^fKL}+6y$M z9@TcmIJZ>ysP@?~5w3ewyTI&p;krka2~$p8rh8O*bkF3)x<`dRx<>`pJu0y7QE?XC zqXO$56=&Bys>Ns2Ju0y7Q3bE-9u-*ksKB~M1=c+(u)8-k&xXKyHpJcP*$`OIhS;NLLts4{0_)ijSkH#QdNu^s zvmvma4T1G+2&`vAU_BcG>)8`vz2-EagXT1BmZLchV9jX&Yfb}La~i;!(?I^$oQB16 zG^YWqISt&8<}`pcrva=v4Peb_0BcSISaTY{n$rN*oCdJwG=Mdyq4q0I16Xq!&`on1 zSl65eu;w&?nbX+RY5?%dRAX%uU+^7*^`b9}*d@LU0Z#Y4kzIGX>h0@p?r(dtr|SSU zM}()dgo#JaS98b0+zrJE_jTx;XH*AK~1lbMAz?(zws}uyME2xLax5tu*dd8h0y=yOqY> zO5<*&aktXATWQ>_H15_m?$$Q$cBgT-e#YHe#@$-R-3sGwg>kpSxLaY|tuXFZ7dpz5l}E)PReN(@w6hOZe1VBX%_LcqI8^_%+tDvrxms4H20;PW)n{<%DkNH zOF7LZo>r8zrub4$vx%n_U##2XLpeIO5$n7sj4Z%DW^%|X`vhCG)X+I zcs|m95#=;VJgwNAB^~p$l6YFNsPNupl+$dk#c}FR8cVepn9s@Uj&@!sUl6YFtd!iLi zwOA5QD~|k}CY)-qB%W4;w2b3RwOA5QE2fC)zEq2C;%UW;{=`p0X-=xe7V)&WXR5^(@wC8Hiv{ttz*LI`@wCv5YOx@m7MN zf_Pf{M7l%Ss0S9r)4IDoXquCHU_m^s74YhFAL@Yx@wC>xmCt>s2NuNBifQvY`%(`q zh^H0P({=Zy9#{}hD_X=&?n^zeAf8q%OnB0VdSHuqTCwJ*nLgA5Tg20fUq&YLp&r;p zJgr!9cHvU$f!)N@iblV$T}C~yO+2l*FlE3p>Va+IX~j45Pc5b%SQ1YQf1n;%5>E?E zJ+MtYEim=KHu1E;)B`g&3rw>cbGDI~XE(k#n%&&Q(*o1%W)n{fOtYI!JS{NIZZ`3> zz%;u_;%R|tc9X=@icL9}FQM5@5>G46rTuyt&2BdFv|{zS@MSc+*~HU|liw6rO0(N8 z;%UW&jGcXGcC(1571!Q;<3qEXMLey@_E`*Hn%xBPwBpT_p1w4@3F2wR*{?hL((ERP zr?obxPvT3nn;@RnDw21x56y0Zcv@G<64!Fl>?Vk(b=PXOJ_pTif_Pdxb?aQ&Xm%6C z)7r(VjLbo^n;@Q6w!YiOhh{fHJgvMmVz@8OZi0APxo_0595lNL;%Oz{56y0Zcv|=y z&2EBtT40*pgfVNshmHAK7<0EUX6^UzU+p(I6JcV5GZDnoLQmpM1o5=M#F+@fr;xA#M9#5i0c!?(*hIMCy1v7CazBqPm8=wT%RDG*5$8Zb1tzY~BAynQxIT+`T43V(EaGW_ ziR%-@(*hIMCk&qUJxtuJ!^aAPr{z7+pZMGN@L%mWICi!j-b9+W~9a0c+a9+W~9a0c+aud+IGUQ9k8|? zu(lnrwjHpx9k8|?u(lnrwjD6r&iFj&J#2h7#5qUFR5=G&=Nw?2bAWZu0oFMOSmzvI zopXS7&H>gr2lt?J4zSKSm<@@i<(y;l{pg$ntaA>q&N-6z=$r$ra}Kc1IlwyS0PCCs ztaA>q&N;w3=K$-R1FUlnFy|cOb3M-g(2clRt`We*%?jglJ+3KOCtmkG{8#&_zT;iG z)<k%)y)+2A|T5qv^b*%^1wO;VLuJypW)&uKW53FlFp4GJ;m}|Z9{ekze z@m&J$QL$h5sKB~Mg?!zk0_z?XSof&Fx<>`pJu2kr9u-*ks5rasQEfh>?ooktk1Bax z_o%?SM+MeBDzNTRfpw1xtb0^o-J=5Q9u-*ksKB~M1=c+(u)8-k&xXKyHiSNUHU!qQA+Vke z;WK(RwD|0LHU!qQA+Vkef%R;NxYM(t&Cl{|Xnf!7J#2jUj5!U|ed1}E(|``d(=w+4 z`NY#Qrva=v4Peb_0BcSISaTZ4|HRWWr(v@`#M3gT0jxO<+>hoofHkK9tT_!}&1nE@ zP6JqT8o-*<0M?uau;w&?HK(EWD^3Gga~jZ1a~fFJoCdJwG=Q1YAbts$_*mwbA~A7L zz{JfmHw8@GEOS=C#OuC?|7t&RiP%p(Epv&Hn7Bk>;%S*ngwDj%GM5NUJS}sHz{Jxs zmx%tKcv|KXVQb=PnM=eT;%S*n1SX!AxkO;%X_-sJyNIV{E)ke`TILdgiKk^Q5tw*d z<`RL4r)4e?n0Q*|5`l@QWiAnzcv|KXfr+POE)ke`TILdgiKk^Q5&95M%UmKb@wCh( z!sm&nWiAnzcv|KXv4?nC<`RL4r)4e?GKr^U-WynR;E~w4Tjs#=tmeRhH3tr?IdJE0 znFDw3mN{_j(HuCi=D>k92afk@4jfo>;J}i6=ou;##lH3tr?IdEXjfdgv}99VPU zz?uVxKAHmu)*QHVx6FY%cgq|&_Gk_qSaaZz$sD-h=luBv*7>sxBNq7c3#{|!7e?&7 zhyQAS`_s+wY>%)wGSGnA z#x(Z?2pBO*xZBWfCm^^5j~wSBU!l&z(V)WYZW$upZ-9S(!V1S>QDn zib!+6xo++^<*aX~zLWOTcTeoag*!n`_g^mC@j9u`b2kR>x5vimgY|F6tg+4g=DNAx zlw<6%j6IgI$1-GE=6-YC+;7S;&M1sC3ge8zxD#RSH`mSmrX0gY!myDrY$Obu3Uj}? zZtgeb7(ONp9}|X;3BxCax!+tj_nUHz7!gK{2qQ*>5mUn4Z?2pBO*ux43nRvb5#z$h z3BufOuABQ!Ing!^mF)kO)5W(_tsD%z-!5+ly;Ze->90NPE1MN3b9(ng+uU!ioBK^U z#vaSqV;OraL#Ac!H`mSmrkqZlrXuH5%^M`L$Jq}&E3~_aQ9;eQ18%n$C363X^)(|} zidxGvuI$;vSc5$t?Dj55;<`LXX_*;#37b-!G?J-Z2SqdAGkTcJ(gg4A|LD zy63C@WbvqO($K-g!dy3WlZI~6&`lb;Nkcbj=;ktX6NYZW&`lV+iIWL)L;tjYRutR6 zEerg-P!X~Clse;|Lvx73IqP9P&9Ss%deXMQm8w3nzWrSJz@Fj*t!oKdV7=Pe7_wyS z8@PurgF49WRw3YuRffm}McN_fXPz4-GnW|Y$9~oHMVKr*HoC=lz~iCP)W=*;dHo0M z|LJa+9DS%PgINp!_WNBjB&owv{P@`$M-1&u7~G2B{kT z`tvbXiv`WF-m*tLk+gqx;Ch3ziAuf716OWYNEkW@LkD5#APgOZp@T4V5QYwxp@VJc zAPpU)p@VrR=3SY#lZNf2VLNHqP8zne4cpmwiAZ!#NMm1#Gh$nMf`d) zK=f{M#cCRyAfkBcPU44C-&%80CW;u{yr&r1WU-YrBvC}`=Y2)3uVILSA zEbB##4uACfm-g*kedUv+GklU~jj75NHRs36tL}c@dtp>jd}V>_cRL>rwc^CPl5EkEfK~ zd}2imh}}?p`LnNk%dV6Wt|MV$ku}(=+B9jzz5)Y<>&;ec*!6@Fy=(Lm?lb4DDnBKN zIN;M+q-@tnuy2pQlwAC{xDxQT+PTD>>ZO3=?=CJ{3@@P8eO#hV#-zY!D*KBB&DJ9> z-j3)k%9mH)v9CS6v#8Qk`R%l;@x&>A?ayt-S{t{kxnq4`PHXQwm9P5#w#D`Qp_)ym zR@}PF)W=+ZS3>PsoMN%7SXPzu>t{)C-EgbkwR=cC>&O`O8BM7&>#bUK{Ux8PN#dlU zZ~PjFwbsc8i(5I|&^h#G4>6}v7M$gJ{+eP?zY@TIOfM;#MXw0lvrrzfX5?Vtm>Vo> zbszQlNb4^rTRRu`!upMzTdZxP)Mq7)#c?Zjiso2cuhpp4OM_QU(PB1sMHjAQu;(9_nub3^Y{E=iOh#eRX27JvGyd8l@`Vd-=5<$k@<9bdErV(c*`YqMD*aoa%7gOX~uRgCro{K zy@_7Gbv&a?nWSI%v23-)!e0}~ESE}zx82@EB<>bn9z4}!>AIg=h>IJg-TlD$MYY=W z5Y^r#fesgk4i&F5r-%Nv^VSvlllKN5ablyDv$r}|lSQLk^Xao`KI65qHQleXg{t%B zd*SZ$ZEfK1Vr7&*bpwFUeiK`6s;<6U^>X2TJ83cX*;W$kj9o1K0PHy!YrOsHoR;}Z zGI!N@epoNPqo62XYbfq&Xu^S_K%dO0FO%u>_eHTXL+9sz3=uE#bO65e#UQc$=?dVq zEBgpjA9MZa<(}B%`)Hu(R3SI;!-+#g_Uv>)>2`(gc@foL{4-+MCj{}WmGRUD`(;pj?8zAOw*A%2K;Tg`V#Uq9 z*Vcs^;$&tU@&|6}A!a1|3b;@5U{QWX72x0f28+GVR^VK7vV{p#A9Fq0@p9PTXv<*n zWs)y|ukQ>N2hz?3e)2~@@qDcM{4rJXj$(h1`k9>>g{z3r`^q089_)10*`i{q(b?bZ zydzbt9UNRtPW?7J^dH%$n!K4>efKZzsD{$eK^i(pLkDT-APpU)p@U={4i)xaNIJM# z2fv?wSV}rrti$UvFPD)Hf^`VYQYV~r5UfLnB*T}H4!DyoM;nhM8<}?n+d1oOyM2C5 zmXYlQ+iv%j65(V!!M5vvHeWc|PO$A(joY}4Y$w=u-^AItlx$}iwzCb}NyB#1u$?q) zCk-E#h7U`_ho#}e((qwv_^>p5*fxCFW%#gV_^@U8uo+WktVtu*gc19~h<(e5eanb_ z%ZPoK5&P1JeQCtLG-6*Gu`f9Xa-33bl$-+@Qx24z0~u2el$-+@Qx24z0~u2eltvDe zMh=ul4z!IN=r(eo%gBK)BPUy?KIXbnJ1nDixQyCS-l!e6Q9Ep-c1WXkNUj}x7OEYR zYX@Vh9g=GYW2zm}sG+t|Lv5pmN~4BKqlQYOhDxJ`N~4BKqlVf>4YiFLY8y4(HuW*r zjo!mHdJo&^J#3@*kVfwzjow2Vy@xb<4{7us(&#;GqX+XddN8-qgV{z8W*a@2ZS-K$ z=)t7XgGr+YlSU6FjUG%IJ)t!9G1raWRT{mkGnCm?Igq19rgJvJevrpQM$8yr_BYF0Dab~{{%|4Q6pI@I$@}b#B z^6V39`IV(K`$(RBLgy#t*+=s1Gj8?3WiC?r>1Xymz;q{&Pxr%j^?$@96FH6K3r{fnMYL$2?)Q7d7^?cZs<(f!J;D8c z`UUp&3u`Yt!6Xy@L-H+8@U?kr=DORWjPL}fpRVMe9`%dm3BH|5aZp))EFwL@M;`tH zdtDA`FFnDZ!d|(b>A5w|1ltoF)OI{{-kWfM^aS^NpyXdJIKlP=lT7#k$rqmBvu~CB z#=FMbp5T{1DEZZ22MJFw$%K!Qe9IG@=$(>Z>Uogx1h1^4c!_&sH&~uv*Dj^cz)=%z zPw*nLEBj5BXF<{v{3(3wQ_GBTQ2D^{DibYFaO(#HkxLuB>}h#|w>?pJ9*}H;oTUr|-KVyP0;Rz<0h!K+S z@&tF9qx5e;dU=BBP9UG|$K?s0-FB0keePG%%M<*m{qs&$b^m_l=D0k;HMY!#{`sqi z2~RM|#Ql(bw?b?WUjBGqak+1cmXtR;elGaEzmA9|OD0m>W9{S_ZPzW;Yb9Dz$||)} zeXhN1=0)r8l5;P-1Kyjy;&satyndnTqfUJOi{cTG82+6}U{_ z8X{|H_47OH=;v}qj*Sob8P*LIS$>?1oIkmFm}r%|9qd?a;UMuTWVUVi7343A7c7Ph zO#xf%dE8JmnV@_r>$pr}SE|Z z2(~@JZ`Ui`R(JWr?)6n$`RtwFimSsP*x5Q)gPe2+v&-S9U*n8^w_3`D(e~qR3!Vv; z*~YiC_FUMXx6|xF^6!!}IN1o;F|cW{eE#+saEc?X<+aWE1>alFYcAQcR5Rem$>Ylo zBUHb7Fy>@C%UabN^mnu1moV`ULS5n<=IMss^_PFTb|%c+0|#4k7sqW7Ccp-(VWh`!_{%Z z5a=_wLvA})hO)qm&li!gs;SS9iX;e@QF*p=xemCKi^B%V%AwJ4=X<+;F0DF!fE&eJ zZF{n3(U4d8OgZpcm<+q3KJ%@&Fg|2>Yd1$F|L@arU!Pk3nbLz{%OdZpSf1d6t*apJ zri#JR6WpM*>VX%;uWEaO_vU#F`G1~nBR#>ZDk%9QYgMs5!NY%#F8EG&O=uxJ!FA$Q zMI5!Eb9jP3g}nyq@7S+=d$qhL_*nh>=$-1*cOpE&^R)be{%6a3f=MR615fg$C%BxJ zU+v+e@}A(Py$?hFK6=g*Ofq3plE2dvyz1Z$$nQq-J;AdIDfy>nEOmQ=S2k@9ePUFP zD?Gsg9lnFT4%0b2!Jop%KDErRRyIeT`D#xb=?T6+s}=U=Y4p&LkBvh5)6p5VNbHX(19`>mIJ?Y|N^GsUbvGR@kahy}}c zhizhWkNNDQ%Qdn8W}nQm$h*yuxoAZ%kMNpsrSt71TWn8o{@hz2Kl9>V(i41cK`;1Z z&Ei`uPjLUZThu))?(BQVyNdO2iPd)VhaZ0<3iZQU#l_8%@g zRK#7?1Tx#iNGwifS7*$+q?boH^)h9nR%y4`o?wy>ok_m*1W#-4#{M4Xdq_L0;ynuH zy<(3_rTX4cerqffn|sV>T~F1_(y?)LEBY+e@8-Jpnany%`M}GjTP#noj%(c4e-nPz zOMRa_X3kl*C-{1kS+GmI&i#cact?=>{^zfM&a^zii)SiMCh6eowkLS!R5iyPJ=WjK zk~##jw&hlUz4WHyY0v#~;XRxzh1wIAIneI6Tq!+lY|U*2Kb#amF>T z`wDa2+<%VvEcSzVMN{ltUq{_ZaF_nV6MSR2%B!PB_mQ<%C>%uiZodrBKQK=nxoNt} z8+l4ZlkK*sd2`pkvOx6wRCxJ`d!9r^M%e{X9d6MB!7GCpZWB#3&3|D|B#7s&(*!6RrjA%= z6{Kf7(6hYpA%m z;ipqte+2atd|&IUEwFlj*%~-^?BA_Q3331rDpE~M$q)!%DogpM`8M@)Jpp?{-^2IH z1Yu8#@dHJ~jD&c$`K+cQBxO_Jv~3fKZDA^Z&UMeUOdV!dRPnxc@dKA9xF3E0YUqop zxo>1lVVCIKPZl1vU{&q83+%P=TFVWqv#*{hU)aJYraa@fVfDq!fpS6oFWo(d{k(cF z{cipwTN_xlVqRYzuqZ@sfAz@PQRn;B)vmUYan7_93q}U4ewN~m9rtLcDEu=2svJuW zy8Y}>(cV=&->i*CTqZs-HcZ@a_`^#7VQ3cJRrYZKZ2MF6n>qF8cyzds=7__SH|(Xgp; zTPb{+V1M;viRJUhzheL4hi&DCQ~p>_Q6q_b(?YG!Pt#8Rwo9#N>Xbx&Q(CRp%hpal z8!z#B?$)0}WwGWe2cGDE+fJKZ#l_tmFWe?J_n6P_o25RlY1+P}Y-OouYYctp_5^?X zOzqEhaJzfx52}AVoByJ9d0QHrW2btlp~A%G9`o72+3LH;#U3^hdEAP(zjHEFtkORt z;2-O@b@sW6&7;wyzlY5|=CgbAKEd4b0NjRAmZb zefN~|^3Eakz4s+8ddMGwl`SH7xcn>xI$q4X*JWR}YlJauhX*Qw4+mN%OgCKg;$pXEJyK0w6DtUmMVn68z0 zlD-DsRc%dHQF&W$;6pXmS#@HlcO8nm#bshksQGAWfo+!mXN|F61}77Xwqa#p>ti=QeTs>}pTeo9Qg`*->$n%*nq63iDm_YAe4gcX6iM6P*08su77Q zf9Fn}UG)HU>n^gpud4-}C%4Tcd&k&~+!DQE4>`1XNB8et7A~(jE9^aN?lGS=Wt#8W zR$>l(>^Xg}#}ho0zQ@CN*lW~mmnWF_dUK$5)+6CBc3&C6AykF|z890DK9{6}Vc z!iKuQsXC{Vi;u?z4v*1Xh9#Z@`5ANee-B@(ksN!De%DC$YS|2U)#-ThX^`p}YKx!U z=DX4l8;yG&GHZZ%a``Rz-q^(VuG?Tke&Xpp#G^9m`y`d-_=?ZE^n=X$(-v4J&Uc_3 z);pytEE*MBfMs0`;_NVCzN=hIWv|+?r&ylgyMfAHjT;6DPjH+9io2`& zM;|e{NL#@k`1_%U*8cGWfbSd|ZJXHKV?H}>xyoY;clo29hbNjCeID53z_*gr<47&EB}cf5abb7 z5%&L1fAwNTIPUpSxxT^^-0Qir)o+#Z{dV-&wSKo)3?3Z17g5&(C z^jUR0w%ZfD?FXe#-QsXLn8W>_}q30^)#-DhB>zQPl{wWF%b&15Fw2`+M9 z)lJ#+gr6t)+K33)H)ZO+!V{d}kLrk>o#(O&Pw->SF`lWpzMLoce{+1vyULfw3^=>X z6Fjlp9^{<;zlF&TElc9wnyfA%J0DYWo`mLbo7miAKKuW%_Z?tX6-nD9$x#WCbIv)< zJq<`^$T{a69GD@@FoC3iihxKE0YNe%l11U3B8UV*qJn?~0hJ7rll;}y-FIu3y}QG& z1H-q?^X&54^zBgncB-zb6aKxj+nIExqkHjuDVi@?QisEx(dViBn!iRx3;%RA3Wj7` zRj^y1jR8gKSB4D5>l8dSsu+yhU(h=yY2W;dcSQXY=6U#UmtW}TRv)&gz_}Emkos^q zq))!EVARSS?jP6=IerC3{1Oly{Hp6EU2ET~QKCXnN&4;iu@%HeJ5@O&yB6?p%=7Ty zhICN(oq+dyI)TTOFaLz`7)xRFc`6^}6D>SAVRz9YYEHqV-<)&a`FX!Hy<)0@*S_v8 zcJHm?nOC-d{|u-*k|2D3$QmrnRUqlDN_D!Japd zs`n;%vfAOen7#|l>lN(bzwLZE2aWZL1K|)Iyz@6Dw*;$B21Ez1_~-aY9IZtu^5e?{9J6jiYQG4uyAd&n!{LukMQP zCK~TlTdMA*Ba$3-s=wZg%HcRB>T2F>pjhz3GLjp|xrc;{gr60p^cr|aotEh;-B(8+ z7%o~it>8%6CQcnB79L(jI4Es<@&2pImNDVLH$;k7d4JTP#6K7(IWdomVX<*k=gjTgsXE&9YWxq?a` zk#>kPGD^L}?fr4Lvm`}d8oQ2Dl8Rhal#MbxEG$yY^-y{-Z*6h%q|&8MNZm4%ds3wGZxXod@j#u77T-5`-FHhc}y^Dy*!&RUuT{*KOYN@|2VnYGwBsI zE}J`zapu+=N;2p3h+}{G`MMDujC~Po&GcbhSA|(ualOT-NwwbMIxNgOjO(*7>ocy~ zj#;;HJ$KA{j%%-D)_H$>K}^(zeHUyk^V~Vb*P2dxcrg zajXSf^L_ZQl!;^NvNh9(ab0!Ix{B+q*Q~d=4tvZxjO(*w)@NL|9kXuZdM?a*j%%+l z>%2di#6(^G#v0d5*Q}Yimbzvw#WmJ7Yb>t4VAft-lfkUXxK@K%t8onnvxei^4rXn~ zH6P5Hk83ZOy#Ut)VEcs+$F}z1x(a4p#q}1exXyUkUf{zqQI|hC`%90`n#}X~Td#0^7G{0Mbz7Kq+uxk^m!Ho^T!&q=4&!?3 zHS05%=dv=?b0mp~;mvq`?QEvd%vwq>Mo~YgwQC8x}n)Z}`nz>0vq<*JO-irRtggsqGcq?I>ro7~~o`V+2rJ^_5Zw+-RV)ANHfrYd3Np1gNFg=3=3 zlGEBlgVJ%Ru6{G$gl%<|-Sd##!{O|#nlz3<=p$Dx{{zy$j9L=`GcP43PJXi_1Rk%M zM)=T^ZZPAdvK7mbw;>eimmcJ}a~uF|XC;ts|ZgX5}clF9^@w?fw&XnKW@>VaTYy$Y)dNDSP*FZ*+nlm+sIwaxOhph6D-kS*PJ&Um3%V-?+9!FU3HH7`i|3$UO-?^@9 zx6bg!_CKi2yK@G@wD3&S$FwO*!KCZu318m!8jMKZnDDU&XWi))x)Yw1>|^(r2g-)v z$oVX8{s(G3YfVgs8|9+AIIERpk5N67hkr=P#;W&iNBfiomapJVN#{)4>|h2fyPX@%dtHVNCS|gm2vG3qMT! z_NlS{yULOE$+b`Y9Uc5^=Z#bN)<1Y(yp6JCj?*L#hwo;Vrg1scF9`abPq0$iIfF6|r~K&x<9LpqQfJ7@*%P~6zK)>upvKeO%U^~NZawOpdn|o-!dyNa z$3$KHtjMu`YXHd?{RTl;zfBOldk10t4nkPJSrFFx`KNG9)a6gk{?a)Qql5Vz z$q^J!{93ae^{eJIuQPV9(huw%+SQpeGnCT%eDIzpsJogYTn>L%IdW{CW&h=C@~R0@ z@OZ!awqi)lNLbta3fX7#b>>;~%eLTr%VXMQu+*^`otV_I8C{vyv4PAlb!uzNEm$)>X96yM?(FQWAsa? zBk~x%6W-HZrknENzfvZie;lTN^I^R2c#Mt??_XY{yTkjJYjk>e|8kA45AR=KbbxsO z0;3zm`xh9UA>O~h=o0b%1xCk+_b)KIN6nK3a_l&MQSCt;grwF63!+Q$a@cDFlJ{%KuNzS0|%ji#{ffdh)ZuEao zpB2@=sdPRr(ZPIvp+3!H^l7L!+i3J`d|p3met-N#J)1CkHq^ffqkr=^7XI?%T}j&f z&>4nf)Q?HKAWGNvLbTp$J0il`zKF24J0h&@kqB$sA;MhF9LGdm{_g2|?+~(ny{8by z|CD-=TE99|@U9?^A^J{zX{tYlQWF zM_BJog#E1*F;N%iLv%3jJIAOm5=LKydL&`=NT^>DM!$r5Ct>tX{>JWE%aO8{>zexe zzhl0qaE$soF#0;wA2VDx^d4|I(_5cPzv(G#Nn&};OEs8{qDy`sPM zC#LIFa(N~_TQtrv|2Xr^PB_s0@_S`-$Z?9jGrezVood+;D?NpiEB)%o>BF7e`Bnav zMfNzexAmd1J2Nw>2&}AZ6pus}7Rl2%lz!@bEfIVrJK-1aWq+GA;*W~D_x6=sIW?u zKE8HJ(OJi;@P2sEY2Hf3(a3gmlyfvn**WaY<$7+NQ*Wl#0zdTLX{z;LEeE=XcMYR* zqVDZ<>xA?roabB;n6R=X;X7js!~Vn$;nCr>VNi+egxlTi2qpi#OLD_CLE2V5g=1Sg z6Q6ohbUv|~IKc5}=SiW}iK@LR%tmlHSMbt1%#Bk8DLIr{~R!lUO9zO%WDh`Ug| z`|xq$I3~)Rv$v$UP_zQc|I=?@6H}8mChT2s&Z(JF=`D{BnB^4Q8cgXQm&obd{XU%V zu7evY-_~&+IsPkUY8@0vesb(N_NyB>q8p`u-sEF<$~E<__s;4J?k`0mD1Gmek^%Yf zZH#{VNl_nPXAn%e3gI97YQ2{-zL3N#}$L2$*&V#+5UNxdVmvol5pK}jbY=s*Qj6RN|%Fm zhfAwID&6~2I40_voO7rM`{*rd564q`MT&Uw&Qbg8?1~aMTjZyHji@|axZI1s+nf}%d{Z2~t>i5$CDQEqz>PoENTM6rTSi<^!mgKD8 zQVHufsi$yE)Wzi!9qdmI{?hqeiw=%X8+abRM{}HF!Y1#s3+mnT`0>`Bfca|v7ED>! z8GSd5Wc%I9<<7<@>dlMKS&pBz9KKd_Tmj=(&um(q#y#>}l=z|9mH)V>`^(Sg2*(3< zM2dwwchG$K1NGt`w0w`|i}&6z(Kv8`BY9Z*^S-#${Ph2n1(Su^KlP>jtl7`JK{xzF8lR!|NbrRsU!S7@4sm zVSn>9Ch9uTq8>CHtIk&(cfZgXwj91r{i+)_2-cKdKzQeja7fxGA7Oc)m~;Ns0fmdb-O`}6-rljut`HGR8-kg zmJBEh3-*?wb}s)cJ>0s}fN;F+zq_mBt3CbZpgHdL0cuarJ|Ks?`bV{QOIiHmp0(L$ zs}s}pCYbVxvtFn(563}n7H7pnHK$J0%DU+x>J(%P!}FAI^A}g?Z~wByeSNu_gL})| zcDrv>bMuQ4S)s@NI+TBCxd13MwkYAb7n?)FxyhfxF;N%iB*)R^OqWcJm&pD;4}LyN zT?;x?6K~ASM>6C%;?2CGMEf@=-5Z!dTr1d?@UoA=+1_2fSC$;n)ybpZD^JEB<5@dY zjp?l>TfI$=syoi~t0UZ`n}^bGIsUuK=ejtK&pyiQ)R?X2!iC-Qow)C5``&8ToldE{ zfEryfqS=ifXr3NBGDI|4KbG(xQzAw1 zi2C#$hibUrgJ%S{4%zgx1VFa z)~&xX2$qeWM{*nEbb$sRUL(xc-e=AK|1$?Cq^O7M;Q#j=q_KltWIL_q@0=>8M- zu^;_+ymrb^5mj{*@r2`duSbdtWxu9*mkGZIxpbrYcH^TDhlxHLLTIiHNYYpIxVW3} zgZM4Q{Od_cZpYJj#49t35KenBtGE}T_LPJBZ#naSRC~>=l#89#kJTQOxLZLdTd0zc zKOOIjYEP8}fiQi3CXkZkIMuLXAX-+Y^dy^;LC=U5gvE|sZtB{~zZmlMa|dS(rS$h6 z4e`P_b$57p|C}dNcXg*IvuvVM=*z*B=fI&e&YsQ6Hux6uF&pwy)_dV%d2#X8QiNM? zYAVK_RcmIkTKKkm`XG(n?cauq(2%I7aBOR*zwy;)Dk1x;&sv1_8H}(#n-SJ$Hp2QW zM_8Zn6erc$kFZ|%p29I*Z_posqJ7VdAp6Df;R@YEn_KEEI(B1-xLr~C`&4-xA=+k$ zL*uv=W7&+UUWN9%8$XANb9*{a`%BI0CsGXEMmST;R-)?3#MJlDB_1*44|V_A+9s>G ze?`r^{NG-8>R#zgd5*35#A#Ydog2q~_nNa;$D96q(wR;9e^cuc$FZ%QKMgGmZ8A92 z7mjlsstsAUWux@2<2u2c*KU)1e!V;pcK28D?}A2$L&5&ax9%IXgB>}dIN1U2tQ`&m zeke*Z=Qt+H9B_9aoG!7L>e}6)GxSJzlkgn3E=;bU1td@EoGb=M?p7lFeXo?Td!w?c zKKffF#Y zKjFzAClECsw0R20hPH9}M+b8bOs`xAK6Mla))edv8|El~$%&H&!IdxO6Ce0G@K=5- zWs3W(P=Eh-%=eBG74f@$tJK|p_SRIe=3rAAi}Ck=blbO7;~TVboO@u6iZ}9b$Z_x7 zx7GMInAg>_VW!$g(kAWT?EGDg@0JCwGidtLsV}S58n$?WbY_CzoOpnmcP|sh{rCi34Bj~*8Fq# zM?vB*Gn33Y9v&11UsrEN<=^^Qq6XnBYpRNQo$^10V{@BvJrSsPBHnV0`X7OMCrZaNi9o#* zVLYn{)H?|&XFS6Q)H@NzvyDK#6Jb2_IH-3bjAtPS^-hHGtm2^FiLk$O)QhS&rq5A) z-R3x^>uoeKk6V7Zk~zoc3e0x{7Z0MbIQr!^H*;APS9krLOps@LJxbqwry{&}O|4z` zk~D+l15;6Ya8xh2RPRUP!>Bz&z?*m+;S!S~;rr!BX>I&*Y82c{-kav{+dqcF(Z(HJ z$(f3w{UK*%6&HT{fi}?oWCD=ss1pFxFFl1{mUg0^3Q!M5?MFQrpdO4c>cL#pgAqnO zn2UNa!l(!Hq8^Me>cKpy2P2HSF9-EtPvO6-d_0o~JS)<8aa=icpqQFK*#q1;*-?lV z_bAVo7>o6nAF>NMMpFkB5?kU5!ufJ07InXGML5~rZO(>~{hq>qrOYYyzVJk*Qu5(A z+eeX3syj+Pm+J0w!qO@`lN;YB7dO6Z4zitZXDcQ`msKYGXjxs6u%|kg_Fvvv{JG%< z@$lP`gT$~z3kVll7cQ=^&P})|`mFcvxqxDkartl@8`{9z!!e)Z`AW=n&*oKYZ-+t` z-F!>bdE@(18KBXJYOS6-vn=c$pw{q36B@#y)0Ti>1NveG;`7@U`oC z*2Oun>Z4$1>Y`yZz6no%<1}mBk8u5YuZZhy)V*N&{Ji332{j-2zWjHU!_Opto(zNJ zH|r69#x#BthU{5KILnasu(D4aYFp{;H6Ysr6*KU?lLeq@&nlFj=B-5VxOi*A4NGr# z?+VqI63zR$>(Z;W;__>gymQ;Dxlp9RCQrAEPp=iRtv&oK@#94NKHOS$e|a~5XR&gT zy4Q3qUq{@3L)~|>4=gPDW_5&|zlT>P7R7^~URz?KOj+Nv+=Kk>Q~uKVxt-$|r4RIX z?uu>gNmMGoJ9d&fx6Hq}z+K;3omI}CzTs|~r*uKt3S@y{$LkVjjuop6-R2h~99q0N z^w_BGUrmShh62eBI&zd#4j&55AB`g1=~yJBU9^SHD)YKT!MY<8=&Zu=^K3&%-SO`2 zPt<*xkzcX0uI`RRnR}IQUii&yvAUWKg8zs_?X-D$8 z6&fm9t?o{8dvv9*=>E0xALlr>wKMhWZJgfkwC zg2lCyQGb_Dh=943Q;&t7x4(7o-&4BuOK)^{>yJ?Dc@(tqhJC8WQ6#+Sxm7}qFUPU1opSy>%R0%| zI*xOnjTG%&mpIn6U6e?x9A+!-!?B@lXpi@A{o>IUS{Pesw2>CZMjCCWg|VGRn`&Wfs?pZk zF}Bu~TMl%L4K~_ldyH*1+H8A`%{JO{yT+CqZMq?+F z-&GDjKcL+;7`tngcW1eMG#$Fxm#=+RJ^YuKowWmVUzM{yKU9>)MeB!+pqW+R(Lf#tQ z>r+`Y?W*qP1;5TDa@|z#3&VfA==2?`bdpZDj~v$%Lix)rOXwW@HiB^Ij=bLbyQ2t) zHEreoRw0b=q3)aAGXebxCmfmxph9cHRlh6*UB6L!q};#PhH*=jeral+&M;NbRO{?HLidzkiVP9yhQCK+ z`gvFnQQ)VOgcsdxC<-)C`r(b$N{b^~%L&;Yj$>OpQ8)f?ZDR^783?KGFCjTx>)8qR zc2}`v^T(|NKaR^ra*OwR5$O50hj81WNufX!b+50Nez%*kyt>yP=^5$KU45e~{3mtT72Ps`m#R4hC-CvciW_$DEV&B+Gln3`9 z=|lPyj?HcEv8#b|@GCVpIj)zepr`0gHGdKv{;I@J?Z--3`?nI-ey?;+)4r=D6YX#H6#gq^`fI1Z zbbm7Um(JHZ_ovCu+HT6Gbj00Ljwss$Bxl}CnpR9Z)`;+woMlA$-^vnB(!HUGn>Ib+ z?=p556NV_==8a_`;>1E_m$>@#2oXL#3CT^M-`VwUS4nO?#c)x-oARUNa*J*4;d5&4 zz*3$aThyHTwZ|22>6&Uzt&Duv-O^}?kh02?{;1nDT`$6Ir=^1R*P9X^6j~fak4g%k zs|z7nvJmEb;`6MFpBdh&+D?=WjYsVX7*a?4aWgAnzP~(ce(vkRF~;_EOl(h#`RSOL zpBM|&F|j}~MyN0`LNRuzFtI~1rl>G6MKRW>FtJ847N{^WNHMORU~x))IHv1;b^j1? z{_0rbImi3oi4@`D8141dW<`ln=R4D0U-faQ$Ty=Mtra1M`ipVHly1CrP+M`}NPLoi z_J(hW3?uRq9*`!Vn0crg;UdEmh%+hL65epkb!NY(&SN)6bac)g3Z?XZd-{8ZOjcY? z(&VuB#2m#{j$=dHdiPuHIgn7bljHTt7J82qQt9ij4R_zoIgI+XCFeeOTGl>ba^31>Qjc62`|o1CvwSA}o06ablL)3ThNQmoND@KZh}$+30KWg%zeK`IAQ(HNSMa}k8SPb;}RV#W$`TjDV$4JY!KP)}?y)v}#Xy8n<@7lU6>HWgQf28qu;`GWde@s)7#*)bLW zc^$63NoKrZY~%l}z0=Fm{!!}=d4HX&)=Z8MCmip#TdMZ@Q}upwAMH`+=hq<(WE!H* z&%xVEK{t;&KX2I606sad>^9pa?+(3|pL66`6h9vVZx)nnb2)PrF@Q-_=;A-U@ z#Gj8RhQar@8o_tMsQm?k~?Ya0gF8+8D+uDie&wtB@d!G#yRn9J+S5b$>f)s0T&b3X7fs#mtj*k)aJ)}Loc7by9fL02dE1^f zzdt_sOZPV}{?heY4YHja<2@S8JsR)VVD8s=?{>|-8}H+;xsT&L-D~dYcz^ep`#aw2 z9dob8`@UoD`=|#HMh}4c0b%q5s5cNsZ-Dv)Ve|=jXBS4#p!-5|hvV4XX1o^&rZ@9p z)U64lTSJ|jFgiEX#R;Q}Lmi!Cbabe@bByi|b$TA7(?eaKYjl0619XiJ5OssD(G8-` z5RA?cb%|hfiKx2+qhrK-0WdwJ568B4;#~%q-pq$lw+2SHhB`MeIycnCfzidGjt-2D z4s~~6ba$xJ1EbSJT^|@-AL;SuhDnmJ=$eDF&~Z%ZPRZ(w8wF*-{mP?zt@wVM8D(H+NIz33F|j{ z!h9X(_^*`7$22;a*Bc$|Z+#nduC6e;5!9IoqccHWiZHqq)Uh~5$AY>S$LL;AC*v_X z8PwHyjjqNYA7Y{|KBgR_z6*@L3-w@N^kAqT1EU{9y%`w28S2x(=+jWo21d_@`ZqB8 zH`L34(aWK}&Nccv)Z@8EkLPbac~R~0w+^G;35?ze^-*B-QU3N9fBDho9GEYd52L>r z7=JPJBXf-(8TyyG#=i{x&RpYnhW=<9jXxUtsX4|^4gJ>~_}ZWGS&i}E9TQT4{O9~sJ4#;2lv zf#aC2SH}XPb3Vs9b`YiOm_megtRceadnIEK5!SJZ2M^6|ZJ@nlZ#&-{W`h@Z6 zLtj6~`1+x5onw3e(U-?zeu6$6+uDg|0QsIvJmeVtw!rvpp+6TGe=hX%0^{d}{$F7H zztArXj9(b~i-GYMLq9Sweq`uh<{JMp^!aj)-x>N4d6{pT4?oW~pwFGleC~W0{qn&0 z<)ObG7=JzV;{)TzhyHzF{QJ;H4~*X*mnX+DQ6?{+W4?xSj6P_>_@JS0nlQd;=(8q_ z&l>u&3FFI#K5oMJxS{WxV|?GxC(bcGasD_T6Lt9;FZ6W+@3&B&MLEPqHAJmVXQ5$iM53>xI88X7slpt zOl&TU+2xp+T^P$tm{?vIJ4=`tUl>P4usC2o9NXH-*L;p&)VVsQ>%|x^0W5Bn4`XaA z*TlBMm{+ced4;jCToVfmV`PDek%h6dz{JkNm|9?BYGJG`FtN5U1{atZTo{`ROl&TU z*##zM7sm1e6Uz%@XMu_Fh4EW}#R2o-*w#*r4FxPVln-P4DA&Y~!njhdi7SQiro1NJ z6vm{B|>>XqA^Re$yFh&aX}w zzxC`Ui?8fq@Eg$XzBS6e1;54Yj?MeDeblkmSAB8UUsQYW+rgfCNtLYv$M~IP@8k+9 z9lyWqj*L>a4ftJVcS#Cm^MK!LhFn#YEd+kY8B)wuHWK)KXE=FM*-qfMm?7i*|NQNt zn5YZCH7wZo&3zcZfiBE9(DB>o!h9PYznLz~H`DQ3>cV_W9lxf5Ve!VZ#dJ-M%Z+-KZj`6?+en*4K=NRLb3;d1-t#$Za z41wR#AdKH55cnMp!cyPRV9u}kWxI5`BeBj;SeHXsmrrwqZ!kg$%0NOI73L&AFRehSBQy?pFAj;?I`wOVApHzCKD#w(`A z@mcD^*!6;av%`n+yB@-P*8{)zA5(s<~tYo{R=SPzrgQefcY*4elG*e_cHK18eqPo zf#25v^L-8c?gp6eZs7Mgz~9?XrTd#N_&o?=z6XKdeGuk55qury_`l=_$y>h8;CDKN`A!FZzeAYsclcWm{pIIn zava@t?6pJV%r`q?d>wn1y7(OD7{8t2G2hO>Z)$8Z-_*cwZMf!J8~)a%==@fWli_)E zFzQnN?Yk=4(u1+3M;m)EHuh+H561Q$ZSuj`GkGB0_Z2QsX-!(S> z=nLQ)UjXzG*l2tN(09Nwz60n};258RDqHiV`-%Rw`1mm-bzMNouInl?{H9nr` z`{^3rPt-xV#wXO@nijokEAd@lIS}rjPE4+R0`u$iN2P? z_*#aX4Hm`+6MY_q@y$e=WEtCm&gUGzEbT=9R$=^G(eG6lzgP5!b&NkO`pG)RPZoV$ zJ;r|)eH*>Z$JU4cN}2xVslRl8^9%hkJ;oms{WLcjKTUsa_Ltw^dWHU&VEi%BPZNxv zroTDmFF)r@bg;GGP;of@*^^)#PQhaT`Y^@^7A8J0#tjxGZZO6Z7ABrB#u*kS&M?Lw z7AF2M#w8XeE-}U{c1*ltjAQJWIK~)T*fH^q{f*J{Yy-ww1s2!WhcWgqnApD<6BtZP zV2l+ECRQ-U5C#)N7-I{Ai7kvVhrz@g##qE)Vi9AEVlXj^F?O+QVi#jfW7otq##qN* z6YCgb3wulqWQ^(RusF#+9NXH7v3$KOuCEVc>|c+G{fjYy9TO86V+A`VRxrj87AA%; z#ugSPwlKyV7AEE}#v&Fb7BR*s7A8h9#x52nb}_~@7AB@K#yS=z)-lEw7A6KV#;_GE zPO=Zjwsz|Eoc7J=V9sZZEes~MFvc7P6LT2j34@76%-`kz%5V94g0X*viT#T)frW_) zjPZVji51M{|5tv?`G)b015A8ljAQJWxW|0%JZpY^rXu+t-e1ybmqqytSI_!|vwC8X z85eP6O?$!{C*%76;y-b(o$#Nx@?+d$kHC-r?PA9#(&QDmE z12T^;pRlf%F#eNl4`JO-!n*y0kF{Rmdwa!n7wa?mU968VmIJ07EFZ8wN|%4j|CVjg z|4vx`4(p?K%JO8nGLO{944GDMu|zuEkyz&^tjiHHU6)T-*Gm}xNw$ZutVha4=GW~v zc`#+fQ`nB9;={``jw3*ht@;xkEOV-H=X~Hi!3;kBa9(k~aUODha^6ZlBcJlf8adB7 z|M|S&^M%V_w}<+v+ew(u$9#(p`1JOeF4rHEU#>q!M!xxu<;(Sl((!M({t(vlhOnGB zY@W*X$IMePJD|Rqr@nPb=Qs0IV7ul2%=$xE*GpLbJDaDzbyByV^6>d6%d%sK@g!fu zvE$>&#~1nK8+ROBA0IeRG(U+CnlFSo-;nP<9!ieb{n74^W_{DV0=arZ0v_XZJgMU+}#Ly^wcXyWiRU&hB^0CPd#= z?b|D}Kf!B=eAh7darxdsSg#v|?Yp_pHp#vLAz}19auNQMZI#sJTbqY}w&TL{kI%jf z^9bL>?{|2%v}>kaGp)^owRymGK%Nok zzG-b9tlz7=V@Y2osejNuO@#43eZF$sht8feZG080&-BHxdf~Bg_+5|BO+IJ&T;_9} z&wafw(A?Mi0@;+>_$tb$MxUQaKKyRQ=K{*vXG@9l_r=-3aq-39z&!ZpX*)4Hj=nc^ zpFN?LGf0W?`-^^GHny4|^y7*Erhodb!4n z&oz$iIKEutXvgd28ZSQAIJV>Xa*d-Mua|4Q_*~=Ij^oQUj&{6WuJPh?jbl5GFV{HQ z@p`$&i_bNV?Kr+%;}0#p|%H*dVgd8M)*I)SHbV!VSRDp zyr_C*-KM|M!y^Q8dV$Q#ZB4lis($;RzVo**{q{lW_;dM2Oqkog>NjFa=Q5FPd{Ol( zxyb*2+749x8&9WvApf7gck_2}{3qZ0IDZe~??n9lNXypPPyUk)vyq9c58L-b>*a0m zk4J#vypDTM{o*#F*mv0v>WiLJg!Nn_EdO2Sliv#T+3M&yOL`0ZsS6Z!XxsaHuN zdfeeWvRHFS7ztV#8cA4gSZ-JjSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobY zSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobY zSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobY zSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobY zSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobYSPobY zSPobYSPobYSPobYSPobYSPuM8a{$!%%l{u?F$u%UL2<&$!OFpMz;eKHz;eKHz;eKH zz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKH zz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKH zz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKH zz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKH zz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHz;eKHAUYhVmLOF0e7Cz7c}1a%)d(-{T}||vkdN@mSKEl)=@SwT zYTr*BUHFY7%SrR&Fp+9P5aHa#qC}Z*=6huNGEbC9G;_9B;ulpf?|XD`)dZ=aSJP%7 z+srZlZTi4|qQw1gNVeUEw-#5DC8GRqrmQM@W-mba?M1o8^b^$yAAcpDSoKyr!mp(J z+6j&vK=|iRTR6oVg%LhkyMgD&vgkxKK zxU8asIUhLYza28OBsd)_P=6O3ZUEbkr6(N!KzI0V@)?r*6bx*;PvJ(=wu2Z$NFT`ijeE$5`=%bn*m0~ zZ$S89vU6_7GTjLmsyW%68a9~l^4` zuN>qRVdRyAydsRe@*uAWBd@&3E5a{(`{Ts<$G+VzOE?_fUy@|IdSVb%&-w-7BWv2r zz6vSNh|JYt<% z^_cSI-=<#u?^KTbooS~m&$M6GlW)<1e6r0toj9QL6V~N`%%jUEtm`F=|0LT(Shtg~ ztOv^_JUgI%ej`WSUz1!YvlTqanKPgY!pT(;OAA?w5c#ld>y*qJ`c zu`_)XJ$rt&Q0CEN=dk>Qbvd#uGj@b^y@c_fWP1qfb`r*VeBApNPP(!_S*DhQDM!kO zu$CKPEl`Tay1 z;h^SOA=@8y2p>*f0$w{_k?`rCs=ya*)!DfH;)YOcLpn-d-=iJ0suYj#xLSQ+UDxkj z*{=or21AQ@6A8CT7Xb%yW+EJ3B??-H%%c5Q%E!oRXFvo@Oq8DTG;K8)ZWZ}}@b$^P zVD`fw2v7XH1tb`fjOrR4Cg7Kg1qpBbs0ak6_Nep%>0n99Mugw{<)ORwbO*vk`t5VG zr07Gq&Cz-8oKu4cpL^2Fy;?hz@QC-)xU+gh5T5pJxHtW1CEFo|8U*Zrpm6RJpLzzD zQ20cF6i(CkRsP1`J5InDCG)!3x;sNgsWSJ+i*jmQQ)4Zzk8wIzP?+~!&ui+Vp4Wu+ zyr%Z(c}-Z)Yr-gMIj;%pc}-Z)Yr@ZaO)gb31@7N5zb607di8wQG zwA&sbao9Hn#pGFnaN(SJM3*7z%#-t2Ch_yJdX&DlN-D9SkUDRFn>L;}7v7H2_ar#) z)VkA+@Pz_foPc!w3GX{O!&%ZKgmA5oTRXY)hY|kuz#UJMTG$8s z4kOFdCj8;j3Q(wiNy3%G8bF^G83@1rdS}>j>ZT+6-g-igiV!u8w0t}kDqw(VF{7ef1GAq-!agNJoX6Rui22V|IC zi*S`Ri6H$j)!zipkM818y(oRcg9YyRR)YvfuJ7#%CzSB=WC`6gdm;!=ZW-Sjcv8vv z=AE&gK5r_VJ8?c|-z+8b+#NP>iJ@mtQ2c%2D{ zu1+j=3~EJq@$s}`d5uPdBf_(Zvq|d^o*kK2bZYbl;ZsKoipX~a;id%&i+dd$!u;N3 zv08_%9IPBH2P_9H2mbGIKW-o3jDr~6l$~$hHt&Z^AE9=TT?)20-#DSHsyYh}(Ex~=K=et+DQa{nT#WE*2 z;#05G3#7eU#3}G358iP`hzoC=%D3&o;e|Tg#dMF(?_z$BF2}`kJi2_q@*Q0-V7;SJ*Ef-#90E zf4LmEe7M}WJh_~?{Q0=pd1vPx=MU!<=NsoC=K0rk(#|`(-;>vtZ$I*cz?#^^D`b&yB}JMUlz< zT)x+H{BPD+q0ipFGXv(aXHmQh=($E`<`;Gr4ap|Y*kp%Rvcp4f^;|>6Z0PIG%p2-X z88=Ye@7cqRsUur9Mec0Gta{pDxceb8*C$gG*UlfL)Uau&A znq0z-|5{b3JSMk*hnd}hVAAMoM$ zVGs%f+^?XkXW+UZ$nf4$clf4xp7q;%z@4c_+%AjvdM;IN3rDBKfu9=O_EgSX7n&b= z9k%RA<5X=`78Y$Q4qqGlT2ExuR8^ug2$tSF?LyR80kK4hto)6v02d{aK-02I;^KNlBiVdFjYX`%J2i|q3c6!URG;7OWo*2S%55Qs*z~P5VbMtWG%Hc`MB%Z?eX{ z;6%9tPX8%8yyLR9hSOK#i{on^ddttR3E!s6D)Ro6&ix~INeKJ4wD3e0b~jvq9eS*) zC8|X_Zke5r+_)23iDXk6xKq5_+!Yynh|5uJ-OD4#x~Xypi7T&mcXu96<3@%J5g%ml z>)tE>f%n7C!$kS({p4NSckbet-)Hqb!k))s@p%mGBYbN`XwD2yp1MOs@QprhhBu}< zB})$wzgO(){tjp-$Yj z{k`jch!Ev##&rtJzq2Xf<0$ddFBt;HolU**(=m~vc+wxeM~dzVICwZz#BJ5uUDd3i zXGq^cB74fY?vNETJdxk@689SHbK`H_?g{DEUL;8Mz&$nos^^E+fnxUKbg(#WDrefn z^5V(|Md8qtyv~Pha)}}1s=&6T<(-?MsYLtA4IuNz>dt3HUlCiEHG`Qa>pEL%{pqa8 z)e1f-+Q6Ci$0H|jWGgs5wt+KpV_Z>Zc?%e}Gtk+bKcP6Bt{IGPRG0KuQjaCqTsapk zwsNo>upF=)upIcm$$@{^eMnuj-1F2Qi>(|i2P_9H2P_Bv5(nrWrDbR_2}0TTTbWon zSPobYSPuLZ4oK-q9~Pg#gU|m?+R#Xw9hpPg(BNNmzmYaHWIKZi@^AUyG7tXwuYMf6 zcQr-7BDEiK{G8i>z8$I!(tbkP6UoL)y9(K7iSdv05hE<$gH0dhJF)4zd_Tr~lt;dG z8Cl7JZG&n{oH*|{4HqHDics6i_Z}z)cU(re=;V&#a{v2; z-)T@woL!oO`t^R(f}%^DDug4#6N)m2TN7UV0XWlo_9r}}b!%r`A?5RR;*GMN??Cw$ z%}x-oRtM+ zyLmd#&&%QE^LlxEcsqIfdB1pnxg5BBxZJorc{>XqN)N@3seXtQ5^bglO~uZ>bZU->^zA#PM?PU!`D zmk@(SS0udhaD7pu{Og2|C+{x$E;~o#IHSX0@k2c2gO)rnQk*z^3GF%K#OW|8N_=r| z0Qslv${8w>%1 z^Ye0e`Mh4<9^Ovge%>$MUoHnOA1*g8PcCOJe?BgJy!bdOPD+W$KmUEr)$$=(Y2Fgn zyd|u8OIY)ku;wjc&0E5nw}drs32WXG*1RRGc}ruec}rOHmatlvCXl}yZ!=Hl`FT0K zd|oea4{s-LKkpasFP8(C50@L4r{*5WQPJEZthq;6bI+A|H1`N=?$Nx^+@pD+xkvKR z+#{^HN3zx2BdobcSaXlC<{n|qJ;IuMD!*D22y5;U*4!h^$A$Nor}O;09L;Sihu6#7 z!`sQ*&-=yu%jLl3!{x^1$>q%D&&P$27avD`PN4Shf`U%l&5;>Y~twTnCN$YAmQOH zqC|MvDa3(C$0Eh&gSHSiayA(%vX>a+%KUY1^b&>J9wyu{TQhOHNh*-(U-qjgl8r1u zn2*uw&R@xx2~;mn=lOX#ynJ3SZx3%LZ$IxB?=P1Fmk*a4mnWCA?3-zSbTIZ2aE~xD z0V5OaBN$m>AHm2F`v^w1*herj$3B7?3+yA9F~UBA89VGFm@&mZf*EV%@ z?4xTqgMD-jmpI3G`*}Lg&&%QE^LlxEcsqIfdB1pnxg5BBxZJorkxM=~>-H1hzSva} zie)cB_|LT{|3N7UXPVI)iiI8^&UZdO6u!zlf^f|YQE)kEIq_d(;=j&AoY%i4tjnaa z)^!o)GUV;y={!F#hnLUmbgAq_;~SgUv?tDk`zdi-?4cB`Lt?hbGapZok_Y}f&<$&dY<$&dY<$&dY<-q?R2js8hyRCX3(QmtSw%2dI zg!Nmnkh%36F=737Oc?*k7k5;@HB-8NgC@-Njq(jy)+fu9Z_BbiiSdtoXD6)R-wDe% zYFVGmpx>?u%QtOVpG=o;-LgK3<$3y8>lG$$aE!kD51CeZu{po%{(@|QmIGn@&%f=> zU6!r>*s+sx(A*$7Yt9&%OD>tQ__y(p?bz9Qr`H?e$$zqS(UT7Uvh&W)JGlCcY0sH@4;6Y}kanbm<=^toAk*=Wy(6Fyp68m`HKG6v*i?n&|5Lg`(59J+N1gVY zV$dRWWlAq!t{f~qpyF?zy&xb(|ALeroUk5LxSpAC=|wG|)yQOo6W;0!CzoHRd)AY@ z{oundwiBK-Ed-tvoKCp-(J(kaERgV)m634fm+$GF=;4znSarQgB}s;NH%7vm@!!## zQPyi=uw`vsSEk4FhCsa%(+Fqk+z%>!sJ;bur$!ejHtZUu*GSS52K}zylA`+6gLr*2 zgZ%A->Q!LTE9$!gYa+@)*72n&{q~(=u=#W)!nI2kf>f0S;dvJez=n2J2oFVBwcn)h zcbN-8nuaRR#@)prd(z63XL#{)5PnpZd3K9{CNouCHNL6~Bb#NRJPj(efS(H{Cp zGi;vz2erBRtiI4EU?<@w8A2detC@tW2Zura)XfOj92^O~f=-i6`aOz*vjqxolKsl_ zI1+9iT}LuZGIBV0(+EeVw_iLM@}!?c_~S+WA#-b&aJ*Ap;k{-T2%r0<6*P{MSjhb0 zz3an)9j_Cf?WqReY*yc%YwT2jIh#sS`ntdpFnmr$!bk5Hf(_$T-16Jm3&N42ic6^* zc;G>E^?p}AZ*~~)R&9{wzrOmun=i5>;dLLca03=AoAdm4JnoS9hg15T+~02!m!h7+ zf2GWQ-J_sP&-X|^SI$R5|9xJPVY}@^VafIpu58=H(tV(ztG<76ofJO3SKYA ze^;6NMr484rq`wZ_C9yTZMm`w;cwsj*lqG_FyTIT61#cVD0}kyt@3)N?pE?i(z%V( zK8vzHU*2u2v*K_+%HR2DVsWrdE5bMqLbhA>k>h{r%X4f4azRK=$o3!?gye+8$OR!e zAu)16NKQzMTo95I|B88Ep0!Nmf>(~8EEBolk(`hix!_1nNQ_)?Bqto4iK|;Zy?+xq^&4>Aij|4d)HSL_1otsytP&?k@L?QgnQ(F45R<~ZTxA2)-~K1vBPKc6og|CKViJaONTah<1(%O(3F+idXjZiA{{wc)?v zziUoC>-xagoY>F?KEI-aIX|O=|E|64uk7`)p$*ZI70;vitJc8i;OLAU&+~W5gtz(c zD)X<5H9zC=wmoZ^C@a9<(;js5P%StTKL_EuJvzXJ$&YF8`zrEHaDQG)IBZoI-00Jg z@cl2NVC_ReXTq_ABB6TuGjt{_aA61(t1y<<|MvCJR{Z;egdbgP4xfLd&h5O-9LI+C z$g>0P!L(<|vjd(X2+Okro*@X!vjd(X2+Okro*@X!vjd(X2+Okro*@X!vjd(X2+Okr zo*@X!vjd(X2+Okro*_t9^6Y?T2*UF0fM*E8=DhHaxw4b|9Jvf*d;874Iq2RCQdBgE6F|7)*yJMf!{&q^-~HY> zn6D4v)^A5TZ`>V9_^X~PJ#QwDB3wGrJa6W*3Xe%P)GZz~jM8hr`JKD&vij}F3rS&G z;+B-odC0Mp|I5(+r+FeJDF6KXwKg`aX|bUVd>+LF=3I&n)?)_hZyG;~Nf;xn9IPDv zk8|K3dkx;T1>Uu3f5f}Cz`HhKylV@*YZJ!1w!pi#khH+HOW^wQ6z2O^%Epnx6Q;g3 z`CCY+NS3q*l{0X`K+!1WQo_^Y_Y~rj6NI}gXe|!yN=Rka?;9wpXU_Cg`Qy5_5bJ+a zdhG6B_ZGKL?Wf<)TOK0L&74N~v-sg6^l@pz&Z9`NuHbq)L-Mxq_Ve^-l>_%#c%JV9 ze4piQDDmcSPwz46tT;PcBInjtb%tD&sf82TQt2T}O#RSV|4_xdxO2mGZj4p2GL~e% z;7q#G73BCr;v}L}fYMK{?wdt)UaZcmKh-HFoKcl2Pn>p+m|M6o;rR;##kRc}35(?I z#nc>e37@&zSL9j$tt-p?_~H;TwWvC`*ZwL(q^OdZ(s%WZ5*L>isRawy0BC=`iOOD=E%= zTY=I?1imgFep8?Dq{L603=i8AZj^Ap^V`MVgiqaF;QZN2eZM%_pW#mH)Waw}LHAP5 zfpp4;WksW-p5Bv{PO{p)x}JzHl+5{9@V@Z$nC1!Rw#84cQ86tOKJGDr`MGY!sJhVL z<19kXkrI=;z@KfdIud`iBNz$>&LW&)UIesCl8kW915r@pY$lph7i)&WI}KaXJmUE8 zDxb?)-uvBxYGC1aKd)6|gY@`lX@>a@5zV}Eh zWh38vB$l#~?>!Pr*~s@EiTRjv{CAZpWg~UdvMwnb`5q>*l#P53lUT||zK2OHWg~Ud z|B89rp0&&e_5Yp(s_5D1tv-j((CD&GsjM;{^F z8=Ar^r&J7(SJzjB~fy_T?<~8?3fO^xs*JQq1ajx3?9!KSMyM3zm zJHCI-IiFI#E75ObL)&7*T!;;A;BzoKm~%2ZI5y0w*w6;f`HD@WAaeGHG#>*yM?tcI z@6$T=Px~pGztPIibmq|+M>7}YT#hMhbdp=}8&SKjAD})~@`gdpu?=XQ$=@IE6J=)* z9{EFG7+!1#;V&PxgMyXSUEt83THsBdgVv2!`-;MWo0SPCYo88o|K5;r;vMmz)obkt zzd8J*+i-FZ!nbO#caKzjlknBY6Wors2NT}Vs=m8rkGj{yyBp8lb6(wdN*9apelbd& z$!m5Wzp+2sElKHoUa*X3%4UV%pSsvnF^|HXB_5q{-#Cuq6i7U9hA*MYDfvQoW8R~CUi4+98)lqMN0 zyQ*vzhCAQ6)$b}BhA&1Bb_b7Bca8RwKlU!JrrNfw$Og}lJE}dk*N=4WFI4sq9LI*X z@iu%KcE__Yw`z0aN&7vuKU28ejwzl(%~ih=or&iee^TK;&V9J4=xv2--<;!ZTuI?3 zN7K4@Ybp8n8r8`ivOSb!_;Z38?t&0?hkZ0-vpb@cy2Exp@w>b6vAV;4bSx2!eb9>X z7s#6lj&=jE`r1 zkDRCSjE`r1M`C%#$2UI0@{EsXeIe7i95}``(`QfhJlmt^BehM>S;BfQ6V`K_u%7#b z^_oCfuN8##8bVmFEhGoM<`C9v5n(ME;$=*u&iCfctOh@fKU&>>lSkI4@Q7{;3~sXVu{T2^HE(7G zgt;j_!zfShpVqrIvnid*!J?O3(Y-6B7hahhN}X0ZlAo*PfWGsTKIWHnB_QfxMana& zcL1ztSd{RL_iMn=eYpt#xvL&Dzn+Qk;eidIX}t7=OYCd}UGk(QoEy(@#XF=U{PWg8 z_-Ro_!aH)+f^4UA5T3W*fw|unBAlsAX()D}9N`7E@<4?a)d{DWl?GbA--K|l8F$1C zO76~`96|XTfAX%IGft-ijO(`%GKI;A!;kZTLgzE3DC;WB1E--trvNO${zA@BZ{~E~NZ4VW&;gYgp zf46IKI38As(r*RlhG_|F5FR`=JLD}=oAA(b*&u$kI{yv}lfJIeZD+@tPL!u>pT$nZ zm4Sr6+g8xYsAD*7FB8wF1Hg3Gq+@>9APeUHf5QkB2HcuDc&_6pSZT%&S| zp`X+wT;)~@@o5s(&h$}Nob$W8Q2K+t8=ODA0|@6%6zTMNqI92?O2l_=o>lX4-1^a; zro+_y<#Lnbq5kM~kp9Es*ea92!1=!Q)}Aq{gB+)q=8VDSmL13TGyqs9Ksx-BK@U#Zvbny&?7nScKDz8v}cqxwtiG>qBr+u?xpD?lE>t=-CsTd`i zz3~a1Pg<>x67ROCMdy~@O~OUR+eK)vObdfWf{=-XgTCn}Hm%u8xO~Pg;z^F{gh$tI zB96p)RY*#uJ1<1!pn`-mCn+wr?5jk$;O1PS%*X0{b+CJOk-mv~Z_#H4%ER&G{y9al zm1?gUSEP_ARz*;rpiAXM{fuhAt`x7P*iudHS?PB+7kdsTr#uInbrJW)HEP?2sQ%(a zCLlbjL4??xH!a~mFGPwpL7S-W87mJGITtT)exXqLrqlwiPw0Z_?EQX~hJ-Dv|D zQA7nn444xJken8CAea+oKtx65H6bwDWzGq6&N*i>@^$y@dWL&G|98Fjjpyz@kLUfJ zrlz{Os=8;Ud#2~Z0Aa4HrR7UJy05TqQ(C1KEdJVy$=|4K2~IU{Ao`1ovqs*%&!{*p;ECHFYFXjrg>adJo!oZVfQ@doma=J8-F*2dC@iJ;G$u(ls;5(WNK=QHlMXC&zC zInB7KVIQ!sr318$@qz7uziQ4{n&J#eu`L*rJ_yP_xIEwmUN%pN5gwI=9S%hZ@)=EV zyZl7P+pmplO0Ef&<(#sd$a6}0qK8xJp>-?ee}R8IS1i6i7vHxl?n4pPskjekthf(n zO#bv^UO+rwAU?;F`+f2J!XN(5ly$Bi`G&!d`*0Q~@qN4aeqMYI7LV!V@E`L6iu-UD z5Ai%gLG8dlb)TrCN6sqW1yje41V|mbAM->U?YA`N)%{L*Kb^ROj!Uf1D#k0uigApw zVtiw)828v%p%@Pt(|dDuzx%OApVEhP?>@%rF;m^|#Pjd!e%A!iaab|-Fjic9aI{>p zX26(Uv#GCDn6Idxn6K2=nZo%?eVr++--y@1NRIqi8&jNjlsWUud&#Q%ox0yCuMgGt zcPXqNDaIVe>V79&-~ReN0zJzM{-mU4!3%0XsQsYM0d)?jbKpNM2Y&TjN82x~Z3v$D zISbF$3x8M4YXUvykDG7k$>!Jp==Bisb1Y&O&)q88$gagmlYgwSDCRO*x%ggLah<}- z6?2)&`3CxorEKst#fI0`%IiSt~bq=U= zK%E2X98l+gItSD_pw0nx4ybcLodfC|_&=QkAjF^k@6VqKst#fI0`%IiSt~bq=U= zK%E2X98l+gItSD_pw0nx4ybeBpPB>A?!V+)8{%)K(0yT)-x>d-_a+l^RrO~B#diJ~ zd+`YSr3v|@W-`Uiz6b>RU~yU4L|rSm&1JDs%GBi1`XhSMr@E z)~+9WA&U1%ROAlLpa0c&u7vUE-(#wdoj2>3|C9du7sig+{Ac8+F#i1U`APbn_#3Q$ z_;=Vy?Ea+vD$~int^a<`QOC|(Ii~&c_c8vu*wIn=-^Wl|sxBA2p!S2>5C6*?VCOc$ zi~l}us>{_rQRl#~=fJtRTGH`>$3+$nm5tIx#2!H+|XyCB-_TfgYdawGVru5Mx&qn4Kwa zbK4!Iu5v>shYyg4-f}~et=y3pc9cKOa6>`E+|jr9HRL_Q+|ZZ|cO+SNpPw4&hVJcm zN5d)=@p1NUD6YN-Dta-SA9vpsr54nY7WgMa;?*0{YiB=8_tcC5cds#A_kw9$aZo56 zT6mJP&3Vlw?>7g@AY)W@jxk#Kr~tbMxufKIcIazL5B%G$7N~5IBYO7YgS>U2Cu;8I zipF(cDsOYj9T{(SL-h^%%frvQp#&FqWO&a(UNVW;5aEtGjjAC}3w1-SGu=_uFZcL! zo!wB+)9&cx=3Ts&xf}8|^*}+-XY&bHT+ycHZ6w+sWXQ9$2d@e%a+Y25s9AjtrOp9$ z4ybcLodfC|Q0IU;2h=&B&H;4}sB=J_1L_=5=YTo~)H$He0d)?jbKw7G4y1oPBGG*& zLmf@hi&f!eSOVd??QC@4+QZM-VT%ks@jl958sj8ag)O(XMEE{hSE+>)sKV}8g0AYe zTbDp=P=%KtOyg*N8(Ku8wOYZ9{T<^`kE2%^`*{pUqej+c^X0qC{ZYnJTgJz;TO+EU z9!u(~z&UY7tbFc$6@=h_T+1v1pd57SM7RpAhtPkqzSyQ`#VTllF`=4J{CVw?E@E7r$_xjlvn{ z8Rc_Rknp@<<$MQHr?6&oC3v&7s2q#ru}BXV=?780AhHKUc7n)$5VZ?L?FEq^K;$0~ z`HjVnwwK0nv|R9W&^vp0#2X`8-g`|asB-rm^Wo;wP{=Od!+7xHFgUwch-tP(G+h1? z#LAC3#zU~dU@1M;b(stvZ7-Emp0+L-UM)?=lq-FR0blohjQ6b%gUsAY%!eTF3pJaX zGG08fBlMfwlJVp|PLL4PopH}S^&z_EV8%^So?*U+;Qx&`HsEKs;#qms6J4;^3>o82 zQ)A=u2EIpIN^0}(ek5ppX2b_vs){#B|KVzy}nSVcH< zoGF(aIP8bp$>X5ef)YvIl>xZ-saTNDE0P?%J`R7HkO*td_exUCY_U5ez{D=QB@R7W z;Ip6NA%6sxY>nxNX$;%GttF4sGbl7W?~L-STR=qRGdmxK%_q;LrT{c_Fcq^{-jv91 zAoAmhd{J2xlIYk;kNBr?@9svSx-NFoc6ZXa<0qofl2AKoaY8z`cSRJMv)@iy=U@hx zaVrXWwX~C7|CGiJIvR!K!|kO0^V2z#?NP{ak)5>AK7)(yHJb}A%iuc|MZpbcfqUU7 zc(6|3Mw_Cbb>CDb)22%_NUUUxci)MDlVQUdTLs2J{yaa%UTfoF;*K7SgA?N6s9_KLJ0~+3OtYE(??R8yd&W`1^9bw}FC&ufI9UwRkG1fP4&c-cjgD@Wa z_v6FQ#toVer2n)0`BnBfRRi$}H@K+z9_XjMKMJ+FpX;@^^K8!JC#=f&BbFh3yO4}6 z8MOVXaOmeS<=6$P@Od4B!lhM1={N)D>KhbxYi_!ca;j^fWIh>-n!T4*&~re$2OFI?m?e;SoxlpEKBW0 z&N(SCI8YPDdNgDX@8qp_|nWM z96kBl;fakBJrEIL|C7(Z*wi9uU03*)W4dpx?gOBjcn zCB!4K|9|Emu@9SW5Ntb`ABBno1%9_H3jHj9R4JG2Bj>NDxn6Ppv#}~1aul<<_N|sXqW|n;zsTu-pL@F?o7@;oxpkwa;#eh&}~|! zb<{Rmr=o7!E-KH_a-q&0jA@;;4YZurN!v!5)=Aq;nbs-z!kzhs`iPb*>!eJ4+2pVA z=l(qn*8b7{JU%x%SMbB1=g-P(wbqIJEEV~m=9@AuoG4zLD2_B{%J|ZlDdSFKMstzn zIUR=;?IPFJ|KdNo-b-uSlXt~ZQ0S^<7HU@eL7fA?Zw?$ia+X~4&>y+JJ?+fqH|Tqr z^xa=tO5YzQ|6%tQWG;ce-@}-`KTQ8o8CpjFMw$FTaSVO8mcIMN$_3rRJxX#?ft9G7 z6UlQTJxHV&&5Vmjz#iVq=))VssG3OQi`^+ za_R$-oir}YW}+LE@8{Easbi;(9nBS*d*r9?cf<*FocW{sow^VHbH~rrovpcbqqdrV z3`;<=;cYqJ_S?-Va+K`O4$Ri|s%QRM>Dw83yqiUHVD_rJ1l)i2={cH$$NSB zTH#*r%z|+2`@xvWJUm^1zZceE+(dpCdz^cL>9H}oRiREVIb**rji6<}X^cA=*n&*g zK#-~C42jy0cq+f|rW+jGUBa%_&nCITOWi<@mfw7C4+h#fj0c9AgRJ8v#@m|eL3JBV zYAdpt`3XM{)n`0*<`I0OofYG=yXND2105Nk?&ONwjCW&v=KOGZW+#E|^e0JczI0&a z4V$&%Y-coKeE0n#ZtuVbjK9Vo=MF!u#5l6ySMJ;B^UQ|bE$X6@i>n!@+FPI~&W~}M zh~}s?XA^77vYoEzjEF-TJZI%Q=ewYpMOsY$@LOk8V_`kU&03H-Y_MiL*v1Ln-r~i$ z!FdO?BWp0@fQ!vggL>l_>)&XK?k2}Go^;U;ZMUDw_*_q0gl*?B-oD%lUEi>Z@yTcl zwCiC$<1y7u(VWXgjB5rrM!KU8G0tpYfWiiyVC-AB0kWEZma+A{x+pUGD&s0;wNdWd zyNsW%se$V5f6F-bf;M{UQpQ;0h$cF};49tW7#m{$(h;joYos|L;Go|aj&@(<@yxw|H|jBP!qaogA0FsoUa$9Rb{TMyezszI{uBoQA1Wp z>x>fetw&~sIqs{4_e2SH<|dls)+vJhCo@`O|4GeRU5|!!!+}HW8C%}$ zi_e{-^FHqAY~ncFtxWKV(d~&i<*m>c#+od|4Yyb_nWW52oZinuV7=A&Rk#`Bg<0$H z{W`{s4Zm!|`K=l+)mV9A*i#%* zr3&MVrmyj_9YP;32r0vJ@0YV&@~Ei+X~nM?Pj;&U*x?!D2hP>td)h6uuD1Ee#)qW7F3`OP&p15673%6uWIWT?4Vt0KjO$)-1N%O6B{X(@ zKe)lLoo&1*r;+g+U7aF~t7UEw1cq{29=+cUs-~=Bto76t2FMB-kD2WXuTxJko^9<4 zqwBwB+%4G!j9u$vdh9btX9(w<8JkUZgxg=cGIpNT9NrBa#kkC;8I19o!Z>8IEo^=? zi?K^n8@PUBF5|EHR$y@=ld*ZWC1@n)FwSga4sDO@WUSrB2u^+~VO)7fBUoUuhq1F! zL+I4@FypEx^&$J*S;ncy>q340Cgc6xYe96|r;O3!YH)ba2gcR2v|#@$4WMm#)aW}l z3D;y?>v{*7Z{JxsEfYqoMfDMxjs5y>j2}AR}4@y zw2kq?_QvQ-*(SzU!30fOoyWMZqZx{+yM}R@u>~>=UcmT+sTJzGM!42mSIriM_YY^~ z5gVGKNWB2Yu9e7nK#7?X6x6VU_Ped*-_q7s*?5KT zx}iC_L!`9aKhmwj^^*A7seD0ArZeq?8w$%bV)mHxPU!Q-8H{VLwn6Kg0OLy~4Nglt00f2HCc?duDQbsO-s6uEWM|7Tv0iMh+!4km-|o7VjXg$u+%&3Lk~%T1L!(kI7QHlbTuPq)wo9kan#mbpow}v}+Bi6KEZzU0I|~pmmUTWsy38)I2WeLp^(C!?v@47HlGZ`ml|_9?>mcn~LwzZZ*UwlT$G?9Z zbv7N!q2mns_ouB7D%R;}ooo&2k66zl>yK87cG307A516Gl;z4bOS;A-T0bRr{a9E1 zUDkQ&dgvd$E;*fB@Tad!o;B6`Q`aT`taydAE&0RO)zOl8QA&U-Vab&A(tlBA zR>#qs9mjuG9M$pqXT?k0*Tk%j<3A;i^v;w1{=Db0$^1$a<@^qv z?-9-W{cg`=3*S0n?fTQ^#1!+HY|iA*n41#MQ_(pc+S)&(-_d%6-=CK=_0Ast!{<@! zo$dIi&yW2X@e=2WXddYgo%dGHXa4^4;p#a4e(M+Ne)mtgJ`v7q;%iGWtK<03ilaJS z|Eze4`z{z?WXtw(&LdxWAnV?u!Ybdc^9pT2PX?1 z>GM%&O1EHmw|zC^d#k&F!KHhQ58RW2mZct@b3-MIZQ#k0W{iyo)&PepZ5T@$UBQ)4 zbZ4Afb0Mx4*@v;KkAd>JP2~G@leMUv6UlQTJ)B5C64i@D_8^g+NMt_}wF`;bi$s1v zBL5(f-;l_kV*W??HvenbKhn3?%N@|TNi2MK||A5GEKg$P|;v&u;QQ!aDj+rzTf9Ek% z)Q^7Je_dBLW_>v}r4#HuYry*Wy~W;eyuKdm`|_(^(DTJ}j`sJ@1_NQ9#UqZ6109!# zfc2T{933D0ulU3D+!ah_oPGrGrI_e|z!*Di2xqcxM67u6c3F1KJZgARDX{Xva^*0o@aD_pPT!(=+Tn}bH% z)=cJe2V<}+^kgz$I_rb&#(qpDJNh#&^$ub(C4JxF8+qNBjMv1+*zoW;CeyjuMttJc zNG5ZmJQrU|9l&IIEm(#3Uyo-pH42;K;60H{W_N-e4!u2+$$WTgj=wEQW->HCyAF+I zGL)Z%jA1gAMS3`q9!{i(6WPOw?BPWAaH4i`qIPkjc5x#AAd!EN$UjKrXC(4768Ra4 z;)O)K91VFOaBT zAW{E9qW*CE3&`B`C8Q83g>r`e~`#;V&7I^ zv5fdwk#GOY!2B49aC@&}tv%Zdf})=LU9A zdsuI7_mmc(RoVN%4YaWIwDfm1j#Lc1oaBYw&t%L*czC>+MN7$xq1yQXc)> z4xVn|xV-T#A-|dh+^V#VOE~8QuM!%-h`kzUfVm~?U9ANceoat2z7FI+x``dl+o9pX z@9=ly0vs987hQDTjoVF*#!{DY$ZXOyY`aw(XV@p8RS)#=@?O*ABaSAchl}Tt??=#I z3d@h*i}Nl_!FRl8T95>sh71sVBV`Gtxr9q)8{CmYkt>^d6bG1L!{#56HItSD_pw0nx4*b7! zV3zk}c8%0@cnplIVuRmK^MO0VjNweT2F>X8UxBV}vyf$%aqr^cFg+>7qxp{cc&>32 zG#cmNv8HPSoZBu5;`|HT&vZY7m)*IE>z(q2Gf}Ux>}eb5XZ{ec4jPa5U2X%h)r??f z3$m}EO&{2PG6ySlP9r-1Q~5yBG+d*boR4`GjYjrwhpU`&hfxX5QH>+jnQzlh)ZAFs z@C9y0_T&5bu>n&0VJh*7(zoM@Z`dRcs$8|6Hk-&!~ly{lCXT`QQ)_p}c} zE8jIi)mzRX{bWrot@2hi0cWBQUrSp zi9LoQR@T+7?mLg%L*wAhr`h}w(``8Vi=Zb}W&(W2IX}{X%BXypl*bKd=zL zT$|3X`!p6(${yk8DXILer-LCdz9E#Xoyq54@&%*0tstTOOnxlq2(Ie`VD{aa{Gm5B z;Q0EH(AzAPzx(Ah{(L_MW;{*fmwZgdG4GRLPe2A=kXF$3lq&B;}H{6`60Il!;Gm7p^Vtj@w6{&ncWKFhz)O$Bb2WSfL+9fB8{3* zylN!eBsM&u@)4w9DWJ%yLJzlZ{z_Ik~4( z1y<_cMf6{MkpOu_f8XbBT=BdKP)77y1gzk6b`6FeME{08kGXD}+r!bV>3q*nbF|OL z4*Jf?;JcS2^!khe(;ry3n@X%o9~aB~(Rp=8k%wkv+~)7?;v7&qZ@FbG+OVV&O39hU z>z4FI9;+-6j+x01*x-XUA8w5f1rZ)-i=I#GgL>4O#Yc3|MhUmW(ATc1yyV>;ZqcMT zq+dOq_Z&NfD_x#UzSo(-FMC<~W2}zetp8)I)+*316x(o0w}^`+Hq2c&7CGftLXU|J z3%2w{qw_4#Jz~T0EFU!MU~6=c*l=dBE&7tw2c;1ki~_Y$`%7VHZnsq4(R?qrBqR=J`C-F|h=zr`-Xx&81sVMMMQ%7ge+-)Gm%&fb!Fa1#5Go~o zA;-KL*jP%C&(;ine0p;za4}-@HYEo;S77DXlOg!NB6<_)SR~@0K|VLY`NLK>18w?@J)Kyl)EUo6X>hQaBh=t0TPF zFr5$1H-%B|p^$Dqga7vN18#qHJOsqefBt)vTDcqZTZMIfxv zXa*McGx+Fe4swV+FNr->i9J`Fhr%9W&zO22@r*O$;VZG{LewVwp<_JUC-#hw48*d< z$>hA4&gU*TD|aIH=%;7!zAHTC|C@fgThRxbkUqFV(XQ`9hLt?2mJFj7W$@2rpQSNc z(cqn)&iCt<&bhe_gUD8C{EbsLxdGDxperIdZ&MS^b9aJ+r)Ki&*R@2c+qA&B#!O!O zb{`~by%BffX7bsd}{*d4KvB$>n}?BVMC3> z!%9x*CPQsv!(i>tQmq=%&@YXQw++)dy|%+(a?3RS)S{c*j70&ko=fG6Yt=*^ZJb~` zv0?f0mT2>DTF{KxU~{JrN-^Gu?@MR$m!#q7O{oo@HgXm}DkTwZY$q@ABsO#Rna6fJYy1ud&dP!_ppV|v~5F7M~ z4ef~yUL89j17gE06B88FZy>rxY)IMhhHLmF9L*;-d~dyuJD!n%&XRgP4W!(mCNk88 zaQ>w1ALE#+{aQH=41cFzxKck6MRiN(M@Bf~IWxzjCkIGARM~<9iU%WyUZf9}JjTXD zeURI|>HNaC7O*SX2o>f`=L6F_!{MzDxy_OpygwQOO}4J)uDi|T_vlQ3KA)>{gEdq6 zr1eR_S2C9yJEil>_sO72TYcPjLI%IoDG9nBo502jpQW)CSZQ0>YyH9vdWp!&FP*=6 z#~HtF9D!o0rt(KDa&gs+eyGx&8N8*V1{4pFqF_9ocX79ePL=DU7dxl(z0Y@t4hjkRZ-SJ9l;F-#|a!Lktwv9Z~H=RG5FM}=ehBzZJgEz08 z1SH>>Z6x1RVr74Sd82{npbm+!;avvbs(N!SG%_68mS^xf_tul|T!etU=4@VLk0yG@ zyMo>441Sfw1AXz;fxOHN{?h$mbjz^_N1ROOlUI*L!^RllLFVcFr+0~HwBr)V=8Say z;S(8>Z_?$?6CZ}pO+tYqM{#uAOSX%vz)E`#U2EVuf!MQ=*t4~2b8f+eaPTJfq(55E zH5eZPdxZ5?8P#_JnaBi1*fkOk&UTC&6fzc@geQ>}j7p7MYAU!o!F?H;6qS zCoYy05_>8=CEq|_q03z&_GryZLY;Mmepl!lqY^7)t!mzmnl8*6bnG7ks_?Js@6}Sc z&Yw%J^HpJ`pH;n&=*-!&^LvK}ts%vuD%#&PgKxPb2=X&8aE&XG>xw}m;A8V(j`oq4 z7V%)#wSFOuFRe#6{9i2A)fsZsBT{^{ioxZrU*|I|4VdbL`KFP5kA2gXc*Yu=g=u{Vu3 zmWRM%O(*DcC!Ozjp(Xek|LfRwTO9Bra_m6&L>Obb5+5hWT1HHOrM{Xlk{p|~D+Ge- zI)NKGw(H@Rkld>~J74oV>Z`=R>gUC0dNMzk7t}_oa33G?{c_^xqp@B{6(;sD{i^0| zrOu8_zUkCfpbGbF;mquTEiF)DkO4H_OwPGs-B3}7`}oi#k|$S&ptlnv@nD?68)U?y z%C+lyD)I!yTm6f7dJ1|13R<8?Jq^H+=)vQHp9Zd%QKbHz|WZGcWhOQ2Z+wM0}{~w=Yq~fO(KxAr537AbUHT;K{tb)P(z}#hq z^_C3&`n$EbdiM|%=S${2K5K%@N(mZimBAmc(j0~bG(_eJF|FR!Puk zQr8vj=3v}MsO!^9U%0scJVRpI#~oDRU$wueqX)~MEd{Pf6;{sq({&K#Jino6Z6%7#|7)~fzK*WN zWKL~iDrV&x0hJLSE7m!itnc`|&*1II`cCmyD_n1Jd)R7a1TCL<(&wyTQ1|Axo!eZH zk0vrf8Odb*po?@4VUM*kSUt~=3nAC5lC|;R`%;h74E6xWSB_wmA42x}PJw+#CfnRv z6GiqmPk|E?>)IxaTg~=aj_r5Q=5tbIDXnW~Z*#CHm?o!;HkyHWy{Tr^oA`>=1wJxx z82CT02T5<{^Cow?L+$!*(EI}MeplTg&aDf48#9~Vk=+>Fj}3r!$ABN+vkYsI`Ay55 zG~RV;AwIM!4hBYV<|ow|gq?zuA#?)I?;U%W-TUwOMCK*PoP3s5DbBuo6=yhhgK5)V zm;OjoL_YrcP<(ZdoSKAlux^gZQ2iq{0)su zTF<$H^HYYyp0U2gJ(gd^Zf%Cc?C&wf=d-Tj&1g6*-(Oaw)K6oL?gYZ&Cb}S9@ZIC7 z!#kX^?J|D$+#Bwc8$kMOeehmb19}zJgxn?#;ZXPbFzlo`r2bYP-ui1oc$cQ|x?4Rk zS@srZ?stY-Z}ecm$y<2h3r}dhst$a`r*Ljh4rWHyhV%D|@!5&(pggk{B-C7oBae23 z%`P=ze8^lpve*|;*BbDlQUcb0w>)056_y{18y$Sg~{Elu*lW&K-PYLKkp8R1La(y@uEJXbE48-r&Rr-q1_qCa!w3Dtz6D zpk~fteEIDyyzS#qn0t1L$NJbn@IRyr^&fumpnW-pTyL+k-?{7RyQ^5Q(Qxq7FO;0Q zdmRU44Fi`Pxumh>4cu$RFo-@dNpfH#d43NKgKGQYB(t8}#KT=l`6(pXxc4^RuzM&x zJmDfS*m)iM?H)$fXC`#SD)@@2y|p z3C|ticHKJ2yMGeQ?@6v9`|EKD3!~uN?&bW+R&%&M??=Fzj7+|Y-Z^encyI9G=kse_ zs-vn`-xSds?P+=$H~MmcFD)64WK#;T zpLY@8Ofnw%>HPH_5CO=#C+Cg(WY2SR7mf-`+raD5|M!`Lmg z!Kuw}9MbWEJtcMEQ|PCc-Wf5gSRTSJrL`mnFZ7j9RG z37o8=4<|lpqq+w5!Kcswt|rt*&IP*g@k~QVnb`oHZlMF;*EfPXs~Vy`E8gQ(X2$Sf zvKgw?=?*p+eHA;&JE7xM-{IXG0b8%`f;tkP({YdbTzbC+esIzq&bc_C(qUO_EbUNp zsjaRB+fLz( z-(A{(buY#hNxy!55|X1xuTPPjT!HZ?1F|}{><$EXgUBz+7~l!I&LgV-!+~J|^NCZw3>k3R9BuFZ!%3*+XTfh9t>V$M1%9mDnB0%+7xrN6oe&T4 z7XlbR?jB#^{@Rt?*Hb<8zJ3L{ucz!z?&}|oxsEC89U2BrF4kic2ImZ5{IR?Y4<^qx(PKRZ72;9L1Ye!rF$g~zkj%>KtQPLOsf=dW_FaYp zl34j&Z$0jQMik>`QFFLDA4V{)s(+627%a^F_UT+59beOimG>TIgPK&fWxT0T8??W9 zb;cP{z0n%kMP|Qm^ATvb{}#qm62>F(eU?ADR;M<6BiHI7Icdtl*+Vocn@XRd(ogMGEt_vEXhYj6fXfNQ}Ewe?>h@L$2$=uQ_&gdyAKc=hA zDQz>oy}n3&ZT6pcZKjT?I;QFz_-k`OImW(n$!$e95kV^+$m>mM#?BG8mcwxM z!=~&UVO+c(pI=drog)VID#fFs1wH*2z2j8jU(K0cUDFrKUx^ZI%Ut{ptHShHPja2l zA)~?*mNGQ|-8|kfKU*4JBtiOQP4LlUd(^Tl0F~%0;upu%K*3u_qTB9E`9sG}bMuDA zpvmD&_?teHIjxT5dEBmx$TI`>+$eHveRAw8a;#soKonSa5x>^12D17-61DJJ%A3TT z;)?QP(8T^r_?Na5xq7#gQ0c7&e5^-hj@r|T*t1KkZXwzC2GM=t;`9uDa5UkIU7NG= zayJP)dEANdcN1fntTmAF;FPzx-`8-)nx?r}GbE95)i7HuK2}^VmKW<0>mOVe%=D~z zuMG*#(Tt-#QY+{b>sN($b`#p-;wC}A7mNMou4sGca9a)(J~?ER%hl5seC3z?mdk!3 z_^`H#F;X6zK>RE&7t4$Fi1nXP_{7OAm8nM)&3SCVfdU9xds$sn|e-PedO>yU`nklbE-*B+m?jX*N*rM&gAwfNx0foQeg5`O1{SGezs z?kJ{o0e|vpJ)rh1A$mGk%_$`9^rSgV{rW%PLdCH_{q-v>ZrA?>HglWJ<}oyI6pH9A z@ReOr74}M66l2L^o%z8VEp)8HI3YL~8IiG!=78z;ktj-$4^5xjqf!vwRoP+~jlRHD zCR5maILaDSmmS-^%paYbD?A_Dc|~h};X@ z^5-ac87j!!;GhE3+>9>J`xr>2<>guCm1$G3w{Xs=nc=q=Cd{2gAE-_Ezdinwbm^ly7HNw%5i|^ z-LtaN?R4Je%ZC_yak(jxUr*%2|BJj>=J#UJ9;6laZBwQE(sBu!{JNI>#5H@68uUV6 z7dDXl)~*ea4~8Ml*M@R4pKJI)P9)=)MGNtFtt2MX0vTYX{cGnfSVx)a`P{C!#lF}? z^rD)++_HrgULF^L(p(zK?;B?0{lkTiI8hrb?87GV1Ny2P$n5tvu7QSJAIa=@9C(U*l^VnBzokEs z^VyTc?4RARGAHtL1)V=DSGF-IaHDOT7vwx%e=R?2B`2BlMTRb|!6n%SRuYm^sJ=O$ z;hf&ojv}X4T?t6J43LxbrhfO)ro}d4= zcdi!M>yqr*TcM5bNIrNiY9Mdb+JO1|{3}B_$rI-D?}SPIFrR-A@(OLb5{LW(Qtf0_ z25^)I%L1e$(t;Sfb~z zle;zen{-=vXLROJyQWQkGeY#(#oc1K6-~A=8PA#Bxh?i9nat_$4Y=u+hD>I~i!5$n z&>SY?KD-}yy3R!j)uWj`mkYzynap+hZqC!cGe^sBoI1rx<~?CH%nClswI6Vr>5P4+ zfr_-Zl6|;S(9yF_WX~@R4P}fdD`P}i86(Qd82wik^w_GbN101h56z`nD>2>sTSLet zjPy^?Jf*L+ z>)<@4ucE?^&0WDdNt`6*-A%xgt-P9z_nbaz&1@az&oA zaz%c!^6kwdXA`3Y1;kQ;Wp?A$k8U zW3Nj~%Gz%;_%|;P7m01&U=xT|>Mi0u9BZJPpGP8NaxZp!>M5?*h8Waoz!JW@*F>)9 zW)h0Ovw&Y1TA33cd*fRGGON0X|30<`^5sXOLXV}q>#EaS#JCt#d)yL!;Fn3<1;0ep zxZ@%|r6t^UMH4aK#!beY@f~PD_Lat5= z`FXdhI{F0Z#np* zwA%~#=#+Y}sjrj#{2T+h?;_bxnVc7XX>ZH6cU-VfokaE=r7C>7?HH8aaX0-=h6d#f z1uvg62pymGf|c*@M6MOtOVXfxR*%&1hHpH$K4#YP0R}0Sov;Jmu|nCjL#4ooL;eShiHgp z#N}dng@2fTRpDQa#URtZtnFPF%TQe%fd>)Z`z(Z&#}dAMR^SZ6oJgLw`B&@v>*arK zA5^-Z>GSA<3~IM3OyquPA5@~#ljyHSk5h$z-RFO_J-_VFUu^HM>8Ek}m3?k$OsB{G zE5837|4;P)!TIy6_W#ZD^RFL6qHoxP>+=lBt9@i&=$|mz&m71#q=f8k4yv#&*$@0_ zdV$R{vLCoAyuP#tdmr7Yc^m#`e8%5ivWi?EBsqxR znGEu7>t;92NRo*8XY%5@{tj$hG68G{>16NCT+WG^>pC9#ZPd!%J)?j#iwOhmlFHdl zo9^evv?BYz%+<(_kG@!ee>htqKW8(d!rCW1enVgEvH0;GfC=9oqPJw!wSbNiOqB4~y^aqmY=7oVd*y zR32f`aqm#nXWBdN<^DvA`%gmA=uw)ecKQs9m%oKn;GfC=-P+!7lN6;F9kHnMycrU6 z-ePYwb4IC!-zQ77!M+Px`Sp^;DBKv$80nAZ)xBl$9@VSBKa>BvwO8ML0%|i)({lIO zRh*c+caBD>qqHq;@>99r-o>K#RjXJ&ojsPT=bC_ygjKcF4fUzOKa>Bvwbyq`GTJ{~ z*Rn^zDY=-x4@*MM<<%`=q8{E`kbwMKRkz&P&Bw|3j8zq zzgv4XJcGC?4RkERTg8KzgDyC5M_Sx8-y%(fi+0-Fw)?-C%g!c&#q^!h@jg?`UA`n& z;GfC=-P&7ukw3P0zkkij1@Rze>-F)t%>2z7caK;&v~DiG6Hz$Kd zct%vSGNNQ@3O}FKi3TS~x(>-n+8e z&GV|jKa>Bv`SZcvR^T!IVAdIZM`%&Y3+fy=m=$!;0lpkj7y>>)g@A#7;A zCd>7zFC5gb0vof^vhpH>!LUdN;##F;;myJDbwoorUt>*HtJl8J`$1C}x?+2lMJR;QsADXI>^j>)-Otb8scR zJEb?g+h}Hb!l62}@A!y)v(1?7KXhr2JF_SBWdgKwjbc1HJr>UPdO)5H($Fw?K;E}% z{u`6;RJ|gL+v152((l4+6dWb{4f|^|`3~1*aI1fR*gf%r>C=thaO-OmApVNK`ORa? zaNpkUtSv*gx_B4O5=UglReW#ZAbJXv|#dl$HTC>geDuQp$sdq^(5 z))Br8u4=TT&;&|%goAPG^6V=c^0-EMQE;g7wrmrY_;QnDUyQc9br(< zT1FGsn1J80nJgAz z>-fjQ>6RlHC-jPgPh;Fzdk629!Trt=%x^j+v5@&Lkom3eXBiAkOkm|#Y-8cmg=CP7 zTWS7&-(LBZi^-50xYE2u{9buUa5$6MbR-u1Y?I-h@$#(CKJTR?A~CDWa?KccZ+3?H z(;_z+8pO9@^=UE-4|5#3q&>FjvmMYcWjj)%1ItIX#{_QnT$4+O48 zLo@w%Z}0%JKNCH+=d1uYv@Z@SNtc=TTOEqa=3QZWYLb1XZeC7=lczSDmm8bmkK;eG z@}VZ7P_3YZ@$Keg;Y*by2(7opJW|#e&)hl^9IUsSnQ4~dO$(Ya{Q=*kFoxJ?v5hyK zt~ayfEGL5<EiLgb)zlm6^|5io}@6GSA=J__vHosOja4}4m z@ziaBP`i%|OsCb$(#)MJJ=4R3*>Ltz0(6_zipd!Dbc9!$H5fPY4}{x|T^T=l8T!n3M+A1H&pUnEcWA&hR{%e9M{q=I6DC+@uApt`6mqV367#YSvubsQEH; z7_!2U$!N~(3RmMpApqaXDK-1R$%e^bRQXi%-UexM-`Egv?l8}E;ZaREJK+)2Gt6)Z zbeNUH^3BSg>~*|h0n5WiJ!KHLa2iMJ4K0s`QjHjJ)tPMmaMm=u`hFB>YD_S{GAaXK zzTm;??cv}GQ|vVun`HKbWz$B(q}+368Ci$%;Q%{US7BUYg&fd%B_n%G-8O4_dpmDZ zG8Co`h%$TisJy4rxMGUJ!cvx1NePr{aT-lu~MCVOlS1AFsSoI2DPK6 zn4Qz_#GmUggN+;NWZ9<9mTvSL4^zgQn$Joo!1*>q;c)NaW|z2oxZ_GcIPUh@_~8Bq zP=2YD=~+5yB=o6@SY2Co$si%%GAl1RIvheTS7YV3uE=23jv#3Kw5{ogj#a^~t6;;$ zoG^Gf)F0XmX=hU3ryd;9uwwS_DsBgl_LVa|4hQ;yWg|;g{;|6cSVgU6IuF{(!1J>k zE8kq(9j3Ppgm%W2O(l(LfOd?~zt&D04!4fgW-_CW_k^gxv2c5K74wYS#n{AfI0Vc~ zGjr&44Sx+B2(jM{%_@I*nCahBw=>9=`#{jSg$);D3)tS>9|BhWe{}r^P!!Me z28;`$L{Tw-B;oFmAW1P1ZdwEZ0R@QyA|N^E98N(nAqEr$MYvnQoD~$k9We(mD~Kp2 z3}D2Z-@Vz-?=8On`oC0B^;Fk0eLX#4dwOPfKpR3w;cn#x_sCY* z()CAK9~!nW-^;&~j0d+!Q@KBP(3`&}PW zDMkLEV;^{8y9ZB2=Z+1>nbn?n&&H>s_ajDN^QA#p&Fq6{`i>v8M?*B;`udmXgyl_o zWtci{EK213ws3_^JrA5;kj1gLP=Wm+IT*<-;Y0;^BVNe@TzFwEb+ud$KPS=HG!#|d-E?ZeY6b_$s!86v|)aee^fE&y^yY071MWa7V z0SQOqe+g%H?<~ABua~;@RS$Z;kH?ozUE?%$Il`MqGx12V1?Q!=0Sq!p$7PSVa5l{= zN1>zgF?ZK;k)O9ZJ@2O!K7HZ`wWM?*j%-h*@4r*3yC%xQb|F*f(tFBvQ~%{M-;z5^ z+f5u=*T>8cO7FkX^G|)GN`D3Y4<1+-$HzkY?JoH`*GDP%8FQwF`Ceq*75@l4_*4PD z9BV9^8+KJ}n8B<)hH7v=m_6p-HAuwA%`GU7sFA)LmxhlykEDX9Z=u(P7vPYqS{%ds z&-wpklCZ3_DK%-tVY>Kb3a%Qlo%3|35RDm@g&hy}iO{5c`cI)14vtde^!S^>L2Wy% zY02l9ozR1F{V04eyOy)(Vmne8orP2ReInkuJi2|_ExO!Irmi498V{GU!58jpbB45- zK+Pg9UKMhg@N5oW;*YNa#3&?mwkmr*tb9-)#)Q>BVIntHpz1cl~tybL4r-%YQN+%=E;F1X>^0k*}h%E4EJ`J4j_JdpNmCY}=w5`9@yCD!lo#mQRhDeVS%Y%(|(7b<6P zTJ+|i_5W<~>LrcTdpUjFI6D)I*RJQhDqV((ObsFBBbb1i;5`!~;xKU1PuG4CBV{p!QAt%N88oFwfjQiHs za(3c9Xkgi0zXf>FJb})?g?ctuw<}=t;7`=W8NT@c3;&;fM@GNL_-wq!X9ef**;u4; zFCK4g5OJo)iqQu>0oJTk6b*UTAnxi^#~K%GIBuOTut7B)pD$CQK6jPVjfZ`3-GXvz zY=R=b{U`)iKitBJ`TYTPjT?cF{CY<%-t38eP9)@qUwB?7!u(sJU%6Jz+@_c2S;4ZA&>oub&r&e{P7Qnzz5C z?_}%ak(C`3Z@Vp))6B%i9Y00!XNu`}GC_EdYawO0_!qrdMg!{yZs$}qyTHukBz(bH z$eDib01}QXz?(PuhuD*vqK>` z`LhN+DrR_H?%;e}FP)E{w7YQB6*N&_Wj?;rXvII*;OR2(VduuCPK$ zQ{1=R3s=tFOuZ;q#+oMwN?2EN6yr^rew36R@Mu4BXtQA^bHy5{V%E9(Yv?yON zpH95P?72)hNqN*8;raJ^=;Au5x^pdIxUbX}FP_*$HLuafVcp$yZ=Q6Wrga295y|+$ zq(GDrKa#$ZZi!p!&QL{}=J?U1TwFQpu&6p~Hm&U!fgc`QOkE1?rhR4I@S8*-rN3z` zzF-@UO=P2}mv^7h?g3wDgH3;_rw1kPPbJ`9rzw>0mL_`L@jM)mv`*B$h)d^wvBg{0 zHd6JY_3`OKKYZ`n8fw%aS^WN#0CRt>)Lmz5$ya3d`&#S`g>U5Uoce1oz#I1u5?O4m z5-TukUheu}k$k%pO)1!6<@ZOaOE>gz=&3BsoA_9?d`b$f>cxD+#o((@%-<-UT$g~i z+fJiKc%Gn_H(O!*-qY0S@n%>nlaD8k6H^@q#`tehGWI{jqe3t4qOiiTsw{ z5dVES3&(PgQGy?Oc=^`Zc=q3e)H%$-4POheMz}QRpT=?iab*Eceg8wZqWl0~TGJBu zYn`R`-!;d_l$dYa?)pG^{qVx&JyF<5MaU^GyMvmq%)_Ve3n~9sWAQjgK4zP=K|dRT!E^PIU#<)l+C}bNWFR> zce3hJB;9=kan~(i-Ulj@!S4F?+}CmeFkQh73*>p+DeK3AbU;2XW#)gAYbx}EM8KL| zTd8MX4RQFmp;$5gHDx!_9}m>?kvjsf>gIEot@8vq-dEbk@)PH0b})=P(nPD}f7UJi zoB$HehW|L1v>(zPA7*gI^+dpmBTMO^;tq~?19NX$T08Auv6p+tDhgH)nS~#HbL9S& z(uX6@GVrut9vqqA~&~3p3!reihtyZi~KEd zy6gjy(MEIp!Os=vL|orGXRq0@ljnTjraTw=N2;e^!(=h zs*(cJTxL9KJL)d?DCCcm<>Rhp-rP3I7zX?2;hRy?oFF@6v|8r^y@=Yw^;C|7!v`PI zk%@b`nr9*)#lislPb=pB_&pOGyz_7dEzJoyY>b+|BK(ftMtv?Y!iol0=)+2TxpORH zp~qkqJ*)8ur)Nn9w6+A{?d@iiGyYEhGFy!QKIBoxSKrgkoM3#DV@lbFe5217F?TRL z+e3XUw7|662z);7In|KjiKqXv#?m$-%J-rPj`dT<4HMg_u@}6sLbVOn5czO-sG7jV z3LE_Hun#v|+XQ|Tj=-{0n6hr3_?+V?e66yIs~9#Pw^ysqVjXlUXw`r_|}IKt6}QnHr9QuFzEPHPQ?J&dtXHxQ?atf|kx z2H}CWUCVdFLoai{S{hdOkLa7G6!nFFv)3yzGzA_7)DfSYX3# zAIgE1@-f)y&=JnOyzA&KGwx1ES8BiaI%}1uYK#wWSi*f$!iV*tmRJ!5ad)mVhk<2f zuSMZGsm+|NU+$oN#y;30-JcR#E8+iNJo!JlM8EyuN^PO{S*xUNE_ll-6RxST20WV@ zL+{z?#XUbQ8+M$YjL)q|;;PJ=4x7u9@w62yIV%!&p~*k;aaQ6P-GeZ{=REu@T2a&-qeWL- z5a5;12J6;EPvlGN`ODPTiLpn5bs5{z8N9AM8&^=KoE4u!QBf#!w*HE*u58L0zCCky z)SL)?Vf~+Z;xZhG=awr{y2bZtaep3e4t=M)r%nr1bQR!#i9%sf-)ZqrsaQH$T8Deq zC>x%=nvM%6gmR_FOolmE)9^C2c#it*O~}qM6KlyAGtZ`FH20AiKFw{SY-O#OJrM=m zHLRVIcJjq5Oq{V+a|typ?GH|9P1#7n?7KelmvAD%>3mO1zf zPmhy7cLDMhr(*Gu9ikVd+vv|j9k999TI#nA2iJW|!|GjIMKT9B(m!9=;nun3luav- zi9s^3=N^B~;KtQxhea|TdJ&7d*6g8AmSyA7uT44QoWhVklgkc^zgv5>Y>0SQa1Nd- zH%C;G;7!M#7vP)Lio%EqCgKGdF8J{1Wt8S34g9k~fXi#Ry2oR^`9E_rams8LPRN%+ z)T@_{&DEN4%$60D za@-c|MdwY^u~k46=i01t6jGCp^|LmKR=cjF^}BL0Us;i(6EhtZT}i@m@?{)x$3E11 zSb#sLs_C|Eb>ItbB;$or&7!K2JL!8Gsd&oCeIoVvTKWu=W17;KtGh0vp5HMu6*ra$ zINGH($YotR?oq4|jX$!EHfQ32T+u4gv#l%Wn6*Jz@yi>IP1+BXIXW2YYxQ#8Zv2Km z$R^{rAuXc*!o4&Vwg4|Z>P~fDlEZga7-GA+BCg*}03DYcEO_QDGLrJ81LjBL6I2tY z?#M0F_m#-b2YG=rvtXqx8YWI>%#pg z8|-H4%T0GTfiKNJ{*g{m8fD%23C2vTC`BGl8&i! z#C1yx`Uzg*v;rdt`f?~W&D*MsHg)jnpt*l6i`e{$uIQTM^kxg)qT z3zVRV*^k(xxk>a|X&oJF9gO$C`Yt*q`wi(24aVh%zKa?!eM8H5F*vMLii(lGj>=}I zV9lLFsNU#$bhIoB7hpLmSvwv5+nI$Yw8~KqDXA!CehQY`KZFY8)uVk% z(bNmJNRmJ44a$Wn;(sL9B>yiTf?C-;nD|T}7=>hz9LrjT)hJjdjo@?FtLSYo20M`7HM8Y_SvRxS%ltXNccHb{g%Di9>8Ecevw0ye4Otw@ z%nuSySjQf^Eh3v>%fAu-FScUvz`Fddiy<7(6Rq^d-gJWNoXTkK0zSd7oQ=UXc?`i3 zoo?{?St!BNZC|7HnhOaoY?21QZ=(r*G|3&x&MhW*&gQr1?mOnaP3F(7G6wd@coX^2 zU&G*i!a=eJ)cQdHZtvfax^H?efES(>gul8e4TgR3BK+~Alwnv~D#3k5+vuZhUZiaH zPXTCbA5DCy?wk*g{}m8U*VCh7od^NJC9_J!Xe5hccJ3G7$B9JlQFMepc8~R2V%AU` z9GybsS)1$V?oA5_ZqJd!H?CbJ_6+KXfm>o0AAAr44&T_awRS`ClH%EfV>2li$Z<9 z-chpK<|&g8mBX&(=L=GIPf-}G-^%VoX@28_XJa(s8~5Kp>t@yxjwv@4Ts7I8f8YK%@ElM!V38r= zKlln@b~umVl;2$X|8VL6ERhe?zx?tSqW|oMVE9k~NK&tk+*~LrK1AeuwUgkjHJf`6 zXfT5_AN+}ahdnZ&$;1N^enH_fG$$y7@Vj%ez;8F}2eY5@w0&qW;k0IaMHXr-|HPwW zG+|yik&mo?riKn2Mp7k<~o~7kO@I+4~TrrQ`U$fKkf#Xc>TjGb*2c8h}nzd7)@D>>dvVHi&0dEv( zZa_G-|7OB$3)Vm7va0mJJ|O#!-Af(2I~gv;PA2?g8>fT16>CFWY!2eiX8Y3RcXqVr zNOq1LR!~KYf%QY)nQihW|v)mMj3(q8YOH3A=H`OLOhckD&ZuVpM1f%v&gH2oJ z5%~{eRWM=BLQCrMPyQjF)5G@jHQvkVPeWNb@7y2$;lJ!$H%q*R4&G=__~;K8uGp|P z#DA{l4?54b-9Ks^By-~lNA1~ZG&Yg-$;cot6gQl0#{lP3=$mR)&}S8WoX$l4&lshWp?k3%n1&|mQX*D9kXud&6&H% zW)Zpfp9yg6B&%olH(3;w$Ud6{UL#=f_8Ek8Yr!O#w3@X+?Z6APeJooqbYL$(u8H+S z>#bIPE0bfA_^LMG3)*{uPq5C-iE#N0tN$=p7CmO-0SPCuO%?es8Aot)w<`n(s1y9! z$`uYfu=*=rRPuk%XZf2hjG}{@DoNYzGf#tnWvt&UT0KxVbLWvnrvnc_Nj-|-`%)b! zBbnvQnCyk3+41y+ee66_vN{ZqEjthI`5FVA-y=!cdFwjpk6G;4`C+916@F}g z=qpqOuhU6{qdRgxGGp@9lHXNnkOvNPu0?|LO2)zAfY}637{-O!eAfP`pJPzgT6Vne z4k@I!Eob}Qc6RSrnR}Ssls*WvV4~Rg) z70%nKW4B=kM6|0b3~HN*rE!ZW>IxqY9k9l+mA6DM)J)+9&lwBvKM~Cttp!0*&UlB; zQ<3C;y1kdI@%x+(nz)sh+UrZH7>K`u~EU29;oNFS}M_#u|Es0z28ajgy%YyCzkDSz;bq+d z@HxZsTcQ@g)?BtNjHpNamGkZqen&wRbbpltiT%Zn3m|&}`z+Wrz5!{Zvi*5j^8qxw zhmH3hRPI2z%h~!KbI#(cA7Sfz=$jmE`VZ@%ywaoWdg4pN6%dzi~ejz(f<-dBMo8|29ew-Q0FHd6a zl#8!JnSXbYvTixa;90`P12LCwqS+1Xm_7I5K6=aKLnZc$%1HVT35P3p_0Ajz)CvuxC71%w3wdY>y8&nx#M>va*3E+Wr4K2~>=9|jI zfu5zpZ?jC$je3;I}_L~QkwRK_Vz}>cKU|hn^C)0NpqW{Cw24IQ& z|MV*``g@~y5F7R|caq;2!jAFbvpwK)?K1Mai5UX$3^`A1TR1HaekrMtx{RLb0fo#y zj>NWg>bf8`$%3@S1*JT=cb0wbM0l=6YaXf-j(vv<++E7@OB-~d+>AYIVFR=Or@jMi zb8-Daes@h(5S+(aM9;XIIWYIo6oOM1OoflnV+nTaxqxS|f>36EO~R>2P=wuY*#74I+s|*ycVdaBn4nv#IJt1XRoePK8T-FBdqn}XJ z1h(xo>x1A?)Fe{&TiFa4Z|+9$(7>_KVrD^b%H3&DP{sPW;HwRKKS7ts^IkiE=<#c! zU+rWl{J6)Cud8=uV98cH!nvxa2R~(35KeV#2E?A*O>l^BGDMfKW45I&4tDKl*Stm9 zk+Ai4kh^HeLtA5)I!QCYs7HKSQO-;EjygYL8Oz~wr52&@Vv`Wv=n!@~=a1RDipLvsl0 zH@)lq$TWrR8>iQ=LV~VWq#ghI6u`1L)^EGz$1-=rZY5=Vo}|Jo4Fh6>l8P;KPGdRP zb1Ya0S%1bx+Mq$}9K@17@aeDs<}WuTbBGf&53ghHLY2q|PuXzl{&qH2ujumz+4Fyh z{zl(Lux%w9?_UhWin0`%Wkif>EE@Gd7M^;jmb30nuq;D-Yhx9+O0W zZYd8r*yjT7R|ZSyKq4 zx%bnn)~*({6)|}2W%{XQtVqTy7LHlh(0dE`qQUc0VVGqA$n4hV9<-2wsz80%u{e*r zs?inr;m=_BIhG2Ai?-QJg_bg zMn&V7oduNj+1tn})(?LvSWETm$wK6fJ=R6a_T!m-QP|e)hk{1)IkDUvSSc!^w{58v zN-^I;wqNf=4?DhASf!8)gN+s<-G{*O7@Py2Zsya;H?|9JN@u~yvfIc&a}f8<_-M#e z9Zk>TCkf@;^5MlZTiE%tl&fT@4~o+)AuwVUH>TMfZmk;(rAMc5`>O(A)Xq_K!G%Pj znrA+g8V2IhY4^7VzZ(Qo(q_W-i>2I0*9~B~sy77rZ{>t{4+H-MYkcqT)LNS$Q)qZI z9S7bGtkoVl8M=C`a96u^?UIkCV6GF&oUL73WisOpT5~8JM;;c}Zn?1*Jz5xq^_#V; zGz@>D34R$kdF39Fx7}*=W6vFwWG2P!d=v#YPu)QWK#D8#Jlm5BIz!*vyxg)@XB?9U%iaB)?zLMl zY*z}0U4ku0es~q9I3x`c+DBs1MiBDDJz)Q`CZv9*m6P!&0g|m{aQDnaVbGKS=vy!z z-+H1X^jqizCCu5EnU|WY&6#`NxAFcWf#pPQjLjlAZutl5JN_Fn#}xjS{2yBENX@FsDtjiKDkGwxd?A z)e0`3F_E_a=o7mV&VMI}~BoLrkc z*!n7$zgvl;`>}}0QR`n9Q)*ViC(L_wE6CuJrHO={fWR=zLhKHXcr$U*^fB31CE zrF@~fln1=9_rqhZ&8l7zDhvM_)x}rJYiq4%MpBJUJ_XjQ4S3@$kM{yA8}Y+J!)Oxt9v3b0r zvua(on}KfrD!Q#nBpj8V0S-@#_@2j%bbn+D;H^!lczwguT9vKLck9oN#4_C=gj5fB zS}rTjH!rJI?GnJ1=)v@(wShv_r}+?mt%d)gs93k>egXXJ{ApeIcIeO}|P+|9xd}ue4;Xm%I(RuukS;?imRk;^skeQyhKob(Qe(h-{c>WMSRobyd5Cd0v$N@l*+|t_bPbKkJ2WpQJ#g^nSW3pkDa-OcG@3JD_!4dYoB?xiIgOEm|{1 zmm?0$h1(x?($Q`8!b&E$@O0;4`pEG*VeP9#$Upm-U%R(PS2wKy){d>9AC0XSemR{6 zU-bv!HBNcL)7t`JPm>2$sVv-X6Fd@A{Oj6uVR>@_T)K0bw#*R<{U^jj z`YHo@oll`~MqwVPBsJ069h5LuDiP-ID5gg_3WbNqXTpx!66Ez;!0G&x0asJ}@zQx; zwmIhvfl7q}5@U?){LMdnAd=vHm+m9y#S;m>YJ?!fQHR8S*V+VdbI2GhiAjp|-9hPr zGr_wJH2+6WZ&nB?`#q~4rD(Kd6ANrfbdv*5~fpZ5NXJ%?n0`r4xZ0|5k52|c5 zv4ns4sx#1k1{1v6FW`Uhz`CS$v3Y*?ws;l_8Cb4z+2bk$5G@}I$Z@G%ugS?7L32#;AsdvKl=IGZ}{^WiM;Z zh2_m`UM}N07e;om_8-YJgvn1?d?wuxoRrwI_pj+e5fwyi&@=vl&aPzFjFV<$L3jKh zqSHPt5Q@gKxvanE93kBH3bE&&Ni3Z3Wcy6 zS6rJ3M>=j1{KqL8G&idf{VmS(K;X&B6(XbmU)wqu+pb5eu39 zlwP90b7$!PU;KcP%M8#zY^xb5Tj5{@>fhNh<poj%2W8?nIH`h~!N8 zq+&$Yo>|P=Gyfx7FNal9Xswq$v9op#4~Cesx!katSQs@?hv@OYp9c=L6R<>2zTYf3 zsvt|Sex4sps$us&sM$L3YK{)kb9SpEcrkfx3I8I`8A>CJhz%$q558vKVe7lS0Oo8Q zOgN9W1OR6q`(DgLZutMSqx~rt!U>VqfUdrGM2}qTVo>s2N%R!P2|yw9JF)ZO-5~h# zl-;LJo#_taza|lR<8|gc2WT$Q^KQ^MaMWYl#i~LUN=lW9{2}E9vNdmr{+J=5u>VmF z!Oj*;J}`Se(W6^F}l{Lv2CurbAt zU_Zkg=G)UuzJvM8sLF*8B{vBkvMCzAa4iX^|6(p=t}`I`+tNHJiXKJmbatH&qgSdB zyzBLRIP0H6IK!K>KHpeG*!`mtS6?VIW&57^sTZ^~vd`uAMG0WkrA5k?f5?OA&$`4m&sh$jcYQk1v!*>4 z-a4qjUDZm?B~=gb7OKFuyh_fAj`=Y5_Fn|*%Q(pji{OWTJ8GP^kh9%2in%*=ACf9H z<#=96f<+4Z(9j(woZat}U{23H)cq!aqqHyzuB-e*b^K+V3Eu-j1EpRT6FWW5#zXuIb`PcCd=6Z#`b6wJYZUT7dIFqTJyyY6_)^Td z5Q$G5{~bNm@{oPzoN%#v?3jPNV ztjprkDpFQ?cp3~fXLHWcQjG1)9;c)(Cay;C)O!)Z$yfg%o9l`M3sQZ+QhFT0fBADk zr9^rK46_o zIQ|FiQFRRCk@ot$c!XJ4opRQe0Or8bq-vrDzY1y2- z)?ERV1#Ktt)1L%T62(53lW%5%%UkySyVXY`01aJC^j99phE-H_%mdnwW1xGfV- z`p+l!G%)LteQ(&h&+WT#>S#+B8G{Ce1yD3?5Yc1*J0G4D^9Zimn+J={8p->xf0%X6 zS2us6(^V@6#0~3-+@Dz!4YciJCEK_EB;7=XhIYixq`i8O6n~QF{9}~>n}ktBzM|a2d$T28BvVf#kJkvvqa&&E{wofF{oZFOQ#MYju7=QNSJg#Sx`&1Gz# zG}j%53Y>nNlC)#P69LE%X6NwV4j#a{dYtfA(+QAn#6FL1O;`W}?HP!5c&6mH9O|uM ztJH9UCwY6pce~d_&&+3`;E=nIw0qiU=Khu{Hs09n?+A}o?-Gvrg(&9C3|p_R$Z~qW z2|I7(rkA4Uv#p8FgR4xTsAL)8Z(#0qIpe#5me~JsemWEi6$yT{mHGCl9~(FR+!_jb z+e1m&w{E?tm&t2O_#?_bBDu}%_!T*NgKgz@qH|?bDpVA+>kc`!Q9%1nB5kz#jNpIz zK*YpsqQ~T04BBfshhP<3ZRn0UNc1#&Btco_5mL5jFq1Px>>NApS`MV_ok2JWZMkrh zSuaWKxoHxDW)`#Ua>!U2QH=|T{ECAdEQw`f*RI*)!SmxpB44tL4{4qYh@Mw7a+o{! z^k|8mZOnPa?1(5Le=kVtoU5D%Td3)zZ2H2}GGz+Uzp7#?l-yJXD`xMb5p%9@Xihf_zq31`nIC3wqoA-M381|%A=WA^AiJxB>)*Sx*U%;1q*GAZkL zg^9r^J;Fb3ZU@18S$^wCJxH%qAo6K8zK~fmlkn{mbK#|*JHcx8Ip9?=l5n1jJRrFd z5q$505y&h_BAm{9Sx_I%#sjX*oH?j9fNY0I?9FyZm_E~(;D;f6IFQW7d)PYy9;dM! zbq6Q-#hh7@l&wBs4LdHg&)G}X7NDjeAa!YbmkC+7HHiMx%>L1$9JcSJHpoF3pXG;M zv4FepSU>9x@rCNmVMOPh{1@o-4YrNa&Sb&7F#!;)*~fXFAOkQj04f9fI7K65py=2< zIQ6fK6E#E?)XvTXYDydDY`Ou=@S6l3_fK*LZJz>1aj)m>nw&ZtZ>hy8^r&xkl)n1_gGS34^9kmnQoyZMm`?=?~$x!?} zfYeb>HV3MfR+IL6!Nev5^(1~vB4tN)@1@HMBMDx(qLVf~>qBs(mm(g>2{B~nke-@P zbd#(D;V3ib^AGL_B3MuB2fbI9wI_MaPVwLpwoS)19Ytr?iHJS7PNzWe(?8_-Sp1lI zmaUW_wjE&dgvWQV^Fuu|KfDXxMEK2JY5#)<*5!Cu4_{LE%FqJ19hy$~ajTf~c+4KB zL_T-dRy38#ok{TN&sX_t``LPJR8)i&vsjx|mj6V*F0q`yb1w2%+Od6L;vYG97{SUL z@}7$qWrY(xJAOPxAD{aZe2$jE_uN>Y6p#Ew`xdct+K}Plbo(-vZ+7u1s?hW!w#hKh z$&?`rN!jQ}(pc{zJHI*H(#8|+wG+-XUKDWUo)9eV4~OG3?-N{kJreK+1A@DmHApSz zBYA#RJrlq$u_KY|j>(1AL~Y{F&({Q?@6Fn882DPO=JlT+8eWSBFMdtRM)U|^hZUQ1 zYu;5)N3KyOwmC5C%Kq8xm|ato3fWWd5&hejMS+~Z9>M)o9$3s~`%Lxf2lR+$HXa!4 z6bQZ*GDJ_(AAi8id3uTetHv?$WPKYc88JehUSkL@R{FcRwzB61i$^04db_rARJR$PjF`TuqApnZg!%l4bLDr)_D#6HeZW&W0b5TN-pVhE;pUPDt%RSDj|c^*tXw3O(lnD` zk@Z_>O9JxwZ_G~nycS&+v1{Hds=LtpxtgS`5A6&JjS&RDdHN8g^{{3<01MbJD*?VETYf%7!f@ust_#S zpF{8u$_?E!Wc|4<5W(S1Z2UY*Y7}HRv;KVR$=s>RtaBuGQWGP@^Ih5BwLa4)EXWCLCFIeXU>+4HMUCfw0pblTQ?=96Eg{rr)d<{5?t_HJye$}T4aFn&P@2NfC zJc{+`H(=IgG{+?eOuA&b27i6fXr22g zn3u#u?UC5UzzmAMOym|Fw!(jIMuYEU70M>#293;~v-Zd*xgb@)9JO#=JOE`-E zaTZO`gw3*^yqjIlIJ2V%-F{oivtquhV6$@^D6QJTz18B1EtUp@chewhul!dUtrx(A zlRt(3B6Q5)dZKSDQ_Z{nfl5wK9I1+BmTkvE6g&(+;L0(Pc%^SYS% zVe@T$2%{2s0q(X0C;o>A)Z2b)1O%02atxA=HGT+3Mq;@}q|cQt7|E@L4?@L!1L z=t$$vduPzFLk+wc;y7s8Vhyd^YB|-DOtD21b6&Y%AGc?=95lZ*f>|}Dyoz!J`-_#p zFe9Ef{?fq4>(z>4nGgfw!zw zbnK`ct%?(2?6cY2z~x6!oJuTo-c_NRPG6y0^MXOaXd{;%_Z9Vw4TG64<*5_dujq)| zk+5WKHaE}wJ__ygg{yi8xgVFy!$;=4i^|~HJjXST5OvB8MhbmJKdZ*zFADy!@82y^ zJ$EQhC<_Iv<8qW!Sud^jARCM}c8G=y3ZgeM@AWOZI7oPTea0#6yc}4z`3YxRlqah2 znF8Lg)OouOPX$5lF*Iw`bKaBSMCe?(2iezO;4PYx%-q{%0sD7q@LH6o!S^S2up(!V zuGuXf?lkU1lhz0Gbhkv}WpRf`v%NVc) zWY5_tuHp)T^Y3%z)~kbGwE)^J`gM(V1@q@QrU7+DkL#jeiT1AUM7QdTco&vN;?=zi zV5Zk)k>+PvY^|vWhdx{JHc)oZu__j(9}3|%lwCp}79~Qp&qzvKe2kvQw|&Z2^yPX!R4-jA+O}y3ox4W>*6=_W|JhC4U$hw3>|ew6TJsM5dtCr}FYQHk zNvFhnGE*Sn-(;?-T^;g{^MR)L!y?O0MXaL`2?mzKsji|fns+uIwtQP9`lTjI=jNM2 zmxexXvWGSNR#Jm=3w(I*Kh1?>GXBtHvWt7oWGJls;0{HdDWbH#Q8;#(J+$eIbPKlg zaF|mDc=rAi9Xhd^o|}~il?Ho6*_noP4HJ8p^xvy-s9tn(BX<$lpV-O`&;5%&e;W^< z@6P6BK6C_ogJ96N+{B$U_Zt!hXu&rR7oN-8Iba;h2$lXTKMu ze4<2+W0mpU>5LB#REmC-j-|Dj^NZsht_VG^g1Asa07sWk=WrhF=FepM^OxO&g&Y6m zo*MHq9qfF@aod=4j9q^dK=jF(8=l{UC~G@-Gy5lZ)Mh>K&E>=Cg>t+}JY)EGJsM;> zr9Il7r;`7 z1d-OR9&vSy7dVw~7hQa!jCE~8AnMq9?hvO>=sdHo>zZAtTN?AhMye_wDofUis@oOm ziHGuF_^<<DKKI3Q)9hKITM`*Bbkx{Fm?+Q zIn_N7AJY$k=Aj$7V;Vl8G@VdrIk}oUVfq`i;9>z7M!SnDuU`~{CG$>#XSOJ|62{%)j)GdaVD#=kfpe#f9qOwQ%5P>x$NOn|b+GjUYQ9g(hqKizJd z3vDxRa-t{OBd@E`@aJ0`S8d}BB)xS4oVqlfC$(r6RM&?>&l@?)a!N0~&T}D*wCoWz z`%B|S#qX$5yqs74DF_ZOp9WgP`Z!+-EbwUNtku_5|8%7|@qA;ZKljJ+YQrk(PF{JN z4!*kMxQUa?(6;3Q5bPepF*3~JZ*a;46Rt9MQ|2SZ<%Qdtn8!n&yfI5{MxhMrm?_T9V){=K`#UD5L! zeOzh|Zc?gx4`VH1pq}qi?7Kg&U&Y~|*m9zCp8<3Jv`&ZM;yZbGAm`v3Hcu#fFAJ~L z01~eXj|=d*g<*uhW=%F$9nP-1w;XoCow00;>M**G*0~Y`*Xo_Q$CX=AWQH9?;^L zDz8U_`{@wqP+Gy=mGBV(vxh2)dwGUZ*e{Gva30?n*BWHPH052@Gs27MJvk{bddI`6 zv`KaJ%zrk76Ta6Nzba(j0l1J-y-Ix*ePa;2zEGR!jy0dg6V78(F}=qTNPV*lao!OWCf+_9X$sHL0D&!mpZ#R_GG#D_<71o+vB zG*HYCazyqOXtHqzjQ?KDc_t`D?w^@GnBUttpU-bZ?)QB`!(Nf+%DfA3N81vv39j)@ z-ZBRzsfF;w={5Iyk2EOfOowAW272bpC&TY0qlwK6OWc`rzAQeu+8ytjV+l^4ZM=?p zb9g%JGO_u1Vl38+%4eRli*%2Kj6^}ZqhVQa0C&6oO|&n{7qZ)i@#cFefNn+_OlxZ3 z%=@(&RW4xHH8C`|^hNgmM z_&Ls-zFPD`DiD^ue#CW|ECtuKQlT#Q496&>7D;TI^Pg=~FR^`_zQ)I!y4jqAa?DU% z&5To7_4pbqgDmllX+7me~vZvdMV-nVHo# zAI$SXb4H4;wu35KYs&7wG#zrpEBx6!&oa(fywo!X(poofe-!3JkAKVNvK);9@i!s6 zHcYni#AO4@!p6D8hFN85xS$~c@UAgjE5{Q^f=@Hp`aewnCzt3?V)Q>|^gFzmK+1+` z&B8zS?k8hhoq4zZAT3AaBVrd|odfLJ)?al9_7Eq-fzH#F*9ALi%LW0+@Iq>QJ$%HG zH`%;*A&S86pOT=oub(6TbuSvJkq!m6*S1|aUrw*yCV;KG!)pS{L&QtJWWv$|pQ}#^ z3uuWwDU3bcj6D*Z{2w-Th$1$evumeM>oWIlG}>3oTrQ1}Z8j zFf$Yt6%iDX*+E4_R1{Gxs0auOilRs_gB5%4iWC{J_b!uV@4aF{#on=(WBZfrne)Zx ze%{Nudd{c+op~Od*GzU+NwTuCQueGuF|If~q8nsf4`AiT_jr$65m_V;>RMd)^po%0 z)D_jfSYP%sq$*m{+L5fA+FB(ZbV3IQg`)Bk)1nEqbA~y#Lj!$>|9cy?6mX6vW_f&+0(V4-kD+KzA%01R_jgQw1LKjVyrUh zY;QQbz8lNmIKC3(kbS^|#t9k23~H;oEf|a@=pw1m`LLi^-4A^4Mr)>S<-BS$AYtw0S#s@dK|NMwXRz^@YlEvF_>)zJzO(PD1kbIvK?lj%;~rOqOJ1?)aktIsOG3wDzZh|iV`ZuPILDm$A#1WNHu$xDpJvg+ zV2OO`S#dpg$I!j_)kraaCvunn(KKSKcN|H7zIZfN=%k?WYZ_QK>;F~m6rX}@FX&p< z>3TyROX5=pLLM%eGGi7t>@C`SgT*>9h^%c`rp>T8vN>Home`6;ciLJcw2G5kVlfUG zm1qmKMu>694XbTn+D5X5H?OT_k$!n0wKh2~H>HfU#*z)fy1O4)-JQMB53Z87w6A_@ zol}|RTOR4+&1Aeg%>-Na@u<1*&4ODyh1h*pluAE+aTP$6wkndYC0L4F_C-scK zCycr(w!QOtQV8}I$7S2`kMZ${STtb3?)1L>$6$rv$jY34)CtPED^R19DHfMYEtVJM zwnBaH7f5ytvw>~>$UJ>C}H?lN$Z&F`0W*cR5swXB;TqGR2|Y8wHt6>;$=_+EINw&QH4{3;fl{{ z7S~;5qJYC+#B~Sds3=%8Nt984I?2~#Qc_S zb6ho8LNG7O{NrL=@tJ=oVF=k{N1xrha<+U1Swp4x^PSEx{E4`RvM(?krmhgz;C4n^ z!d`RHpE;D#5Jp`-F3|k%(!-%#own@RqMlOdda@Hs-*qqnZeJ2(+93^^L*9^ZChydy z@o?ahxL?cmQX(WswlH7Cj@)5`_lfx{q2}OB&K1-0AB;L7Uw$W$J*(Id56w$&WO%-Q zB%HMn^W-_cQ%#N$^>Ft@WgJjWOqYdyR=sT?rdu5|5xSHYrA{r#JHqi0C0&0`FEiGr~uF1HF z^izt%iaxvK8H#k%%bE%jSCN)|_2;S&yTtYAh#Sdp&PA+?M~!=8e?g1`&)FP?Ge|6z zmeV79Jg$nxXB)v$Rp}@Zr&TMGAKNP8bGj!~8r}vH-daazF#hMeN5Q7PqF-Si<_nE2 z#lG3o@d@7fa2d;UV*CiWlqbq{>yPF5b%MC}qpoKx95^e+ej{5R!WGwv{G2YFfTuf; zX3rMQiG?|RL?6a0r7w8g5^Y!2!!;md{&iNT`^fqJ{#V8I)^^7dfq(YPXwe3)`PdH@ zZxr<=FV#+^!7Vt92Jl_fQ08-9`@mbr1X ztI*}TC`)peGIH-FVxA3&JA{PcJ6JhhONT-u5;v#Mwl|G{^_|83yVg_+_D94qVsrXw zY=2OkcN9SY#Euoqbnc(1;_J~}QHqswiP*pt@*)IUrm(UnbUY%iO*h|AgtN#QCz^hA z!leB0V`97QKl-5j#sbl%U5uN7Qz{j+y3lbW_omOO$neDi1=#K>V&w-N2!Vl7i%o$3XCzxFYc>r|UysIajtOJCom zHy8zoeb#=EFMKo>=e*a~b^rr&v7Du)R^yo`?OFa4k`~~ywKBt|q^6xHLg_UZ5VBpwI*rT?% zXW(e(LEu?I+$UgmZ6IvgD3-tH@O0cPR@B2mx3Q`l?)zBX4ZV;8Z>x)IOiu2nu+yr~ zOx|h%{h-Ed(PtiZuNK^RF6uVw@hPlO?_+Fz>5%J~MWUVgBP|v@oW0ny1KuP+O1Nkz zgK?bAEyz>*=LvU>b<{_fLx3952bX2e7M~-a@Ysj7$T3>ei+`!h#oZ83wAGE zfb!h)P9snizQuaG_bz_#(I2EbmsAZhI%F2kO@a0?b5fzm^j+e6I55oqN|51CVX z7Cv@Qfu0#S%HA}-ozItZuA_JsW6F|H_*AIN%Kv(%H#q8AGQ6m4JK*!QUt5KxmvZnW zcYiixc>5=EcdnZ;!ygCvK=ot+S1a2-v-*TY*pfR+cp0NUnDp0F4rl3dtx-GSG4`oICh**Ye~&OFhUvIv?BI7AonUkbDRUfvKPT@w*(y z%(G<^AY$(ZLHAL-WRP(rRK8c6$$R2V2N*S2)X9bbUr4Bui`#ddn^C3S2*{keL3rgK zFR`l=2|FcGDDaVo%%@EzPO+}Vo-LMi0_W!r3}+cPhfDMP(UsmtvQ_iTK={+1sN!Km zSz56^;Ku$aF}13!ZW~=Fw><_O-PuW|lRg0ldnnNB=^bUZ`ioQtlSZQEOWVuFoSu*E zhbvI%f|@c%%QV%ez<$_ui$mt!+wmYB-w)@{cgVa|6b~E7ylM8nj7pv-pT*76) zI4vD641)Ms?nt3~N;>|l6tb&^qjrZJWP5s?!g0khD6O`)Oy3|4ryBM_b-EkNrk*Vg zDLu2+%p2!7T9>FmER4c}dx-1qK*%;U~WP2O07byz=?IHabm zDD5-;awiJeM0v_;&s~h4x%WdEb!y5^=zYN&-b@H@Rf|rmp3iNciB_h-A9I@v!SU&q zwpSA2$w+flt6Ye*s)r}&*<)4J=B+bN+)05KAued(^7YaK@r_|yYYY6?s(WU5K@z-q z)Ciq#Ia~Vau?rj=*A`thJ}a$%MFN30Ww`4X-^@qLli+5^WqHQs%9h)wroeu`ufmmW zy3!?g`og+~OYnQ!of%7xM*$p)#PNqEnd8pJv1fhM&(0sUN1jml+Tzre6zD!-0NQ12 zEsNNB4{Pucg1d3)`$+khN%`rd{B4~}W8-e!GaEimhKwm~E-_5#SO58&U$% zG#7JOV(?4+&f$tM)G%MNe%?Tcm~MfBT*IW-g4;nG=chu9Zjoe2VGxs-@+^)nd(9=b*(2f9zMDdj^I^&GGNIsUPywYlNTi{!{J^?OSG33Ti}bdS5gc8&T^KcL zyyU{Zp^)398hU0SNOv#q0$T=&a$SgN3=NIr@yFVxnb0{7=2s6Drg+@3l#e9u3M2cD zmbb~4-Yx3{x(4wmZLp7Qcl`+bpn3#KUf)8t#A*+Iw~359ee24`qPD84^V_QYdX&!G zyh#DMj=HMqhg2CP77ks`-WFsvPfAv{4uL0D4N$MylcW}b0(h6+BJYrQ!y=8$JNlFl zMjh5mWJS}TV7?7BjF^pU`d`Z!NMhF&_f{3!dGxVdHy|0(%F2*?VT?3psyiGq8id+3 zZX~O2S%9Bh9f7v=^pH(_mW9`TY>nD|J|gXV%L<}g7T}neBN^W0eJ^F-0B)65K4ZIY z1PokITW)^7wuSc@1su6sL#SJKkmUr&WH>o}iLmaXyW~bbc_-d-IXU08LmK_E0n{2h z3>DfSncJStSns+E`uKK(^u~uqFl$vLO5D&&c5=*G>^V0HUhjPccVyA9q9v;o-o66 z2VxvYi(i9k(xAPgOGNm9pX09YA~7ZUbVlekokg^7_a=-h$z(y>DuL!+-|XwhAN zsiPCQLpm->9(-V&h4~Z(c=RbN`2OK$dFf0tj9$`Q=r%gt^4jG@@aja~HDdMD(#JX; z!aKA;H`3QgOXb+Z;7D@+c)?(aTLp5rah#)&C0}US;7cMrba*7V9=#%Yr3{9mwXM+I z*9WArp*GOBEJCLrtE7{L)`x3;SA{usv1F^yKv-0-tB_;6-}26s1ZW@G0v#*8R@x!i z9{P@HhW6X$O8v()h1pjkUArarGJj0wakJMgat#QYX6{4QL25K_gGO&VDjmMW3Qpt& zq4DP}WyQMBu;u1#>^d_mdk#G+}Zg- zl6oQlh7N6j_Bu_LUN#qCy5A7g`BQV*{e$~4F?ra{sas~n4M|`%JpfO^O)_hpi-#*+ z$laZ9ePvfax5go|ox-u16C_cIL*e57#e#0BHj@5@Q4pS98Fd)dSo-WS@%PC2ivxou zN#3~(g{L3q3Ega*C2P`0!eMWP;FMHO67(n*s$6V_R+P?@nm29=o(qSfN2YR_eDV%l zeYvIlv$@pb`Ek-;>W>nlx>k@h-yRD#DGvqQ`?93>`Cyn>Fi=G*J@Xm4hc(Ty1?my7 zMyiu<5A*lsxZc@+%>utvK>5$}TvwtC7T1a1^y03{?FTHdOdp>D7t4DHzC+(zZm*vR zZ^Nev?Y$aEmXPt{seqvWq-~VuKHsi=~Nh(D#bG;(_^=lP0A=gU7=m zz${OCJT?y>`q%+t9R^DGudNNIYU#kF(n?8jPG5j$iGs}kROTW}vOZEljxLRf&2F7x z2L-o7QS8U8WxBFL%$Kv%uMIS--y^kdtQFi1>Z1e}c&(zvena;@Sgx|8-p-mvox;O6n zXs+cn^8`3O^DG|QroZG%&oJm)qqDr?b(2i{)e5+n+&(`ix}kZ6k7S;^>>QR14wBR{ z4TFAFY~`xMpE6DzR=|j26KLK3sbpt)ZN|jrBw&K#eE+1 zg3-6eNzeJ~!GKCvc`;GHs7B@;$jY>iRC{c&>SZ=RSvy`~+k=otVVR!)^# zIRAlHKZ}4{p>w3mi}Ue`YR0IE&BUxLX+BW-RweYjFe)n|yc^t#G(v@|#%E3b!w2du zZi}|P%E)fETLMP|0#WHUJ(l@he2I(V-B9ml6SG5)*uu4>Ae8g+_%fH}&oD&PgtSl3 zB>t;ALF4F}(6UCcq#(Bw__Yp1?JD~%o7(0TZg<%YAg_b8Umsg&4MoDGab>bDlX+#x z$_D85lPcL;9?Bv1v@zKeH6<&%j1P%-d7y5I+1VTFN+5AlR|xGJC-n}k3JoTI5%3%9 ztjgy7;K|mv!raxhvvPg%+6GT2go; zKvM@Zkhl6I*>cVc9&^vmGGB&$o>Y_+E*}9FS1eJ_1sAf8^zdM~7l(Tge3Yc$BjwLf zmtW1GET~3qlsInd4I_3AhpYz6rCu|ZZgSTdV8tMf#YprvQm@z3s zpX9$~J4UeaJd9y+QT7Ang^;6*E;i~d0 z;ny<~E-Ii$-@3x|6RR`R9w$L`ur9i}&n2t5nLoTV>Zp3r#LZ&KS_N38cnJ$~_GDgv zkpOlphLiXHcH!UrKDZQwueV~ZLr=sh2?xt@~*J>Z9+r4o0*Hh4u#kO z9nc{;WRHzDg%93MP^DdV*_ZO1q4eAVD5v#-Weq3X!*6Ha!*9~YNhZx202fK@+jnn* zWLi)t`0F*4FWOQnbJPI^tiF&goElk>*?B?~)Tx<^Q9mQeZkrJ>xuZF<8+IVeKGgG@ zHc+#Y4Op%=lA3>P1^1>*#?RfZTB^Kb;Ly>@!q*SyGT*n20ryI_=%b=kwtt;g;P=cG zJy{i#eGl6~%g%*DznVH(DVIZ`#w%NB6JJB>)!hxQIyuAEfacPm15IGW2#oVuyGSOG zchss3C*nz;&s$Df9s`A+uc^9BduGvt+*SNac~Y=7D9(K591arV}3EA#C<^3LS=r9%ATg3PTEq@91RE)?&~%aoBjZg(ASj3$6AJIT}q z^1Jkqn^dloIY6m^$WnFi`}VGu)juRb;j;t6$chg#am^vHYU@a0+LaTTHRr~Gakb6Z zBGp#1DQ6fAm_8Ff-2KQ>H7pwTmmYzOJFK$|Cw=zG00Gab5M${wF%hO*-7C~Ce=pN5 ze+X1{TBNGvvdH31TLpNTMdMz3Hd}r4f$*l^ zSz*GumzmK6!eBt#eXbGH7G?xKRlve!J+NoL*_H!ZCqS66Pbl5)UgoX5ArKU~OQ`X- zC^L-s1BZGY!TE09lGK2~;2C%bcbw=YIe2t1!Av;rF4Zj8*^S!E}ec7f@w4B^_SLz3gRez0*>O*ntHSQ4Dl2@db|K_*QeXK&qY z1iKd?)efts7HzgGpi`%tD#Hq|EcQmHz}V7`LM6xTnZwH@!IbHas_J`eEIRB~K(&^y zRh@h3Tl(6ifP-0me8{A$W#I56DAh4vm>qa4vnIKVdcCV73N({v_df0fahWPyaLQSt zI2HkV`ZjoKVMj~vSxIo=aDY77Pm)=8sRG^yKfLAHw@Sdu1aS3>Ht9;4wE$v#+m-f|J{V@#s4RS?}k?!|BTvu+gE& ztf%C@-Y+r(e7;;n)}7_V*R>7CPdo~;BpLBgwP`xeu`|nFkR1h^E0cG+)fg|W>by=K z)+Qd5@+CQ)`-Ne*hMl3yk-Ex{{cAwL+3@MO{kTMkkRHgf-7etl90jy!9=2?oQ%@DmLwy^Xr|aHi z=y1|CXIT?{oH7_0lRz9Z3YtBWZ<{(&^h+y$yYvtUB_25KNJ~rKU zFK5V$2nbx%54xCCQeL?739D{C#lu1jl$|yN!Js+{cs#p)&QRNxs`=#3YDb-ZIT0hu zVZCwW-Fdy9=6qan7|%6&hO-k4l+HOpaJ1b?VZ@>jvNhy=jImErzp+LdeOwD|F6K4QNo z{or+GMPS&3A`4bhR{B+UuCW`Y1EdEiF|#WqE-MxnrtYeBT_G(MgcrtrPglER=<} zYeK1ATk==LzsbHq_H`(?_(7jXCd!#%6`-(qt*TSGN6QkbC}3na2YFic5z=dW6rkI) z2e`I0QKF#+u=rDb*b{G~l#ds{@x@a7Rqs$vlipEaGBgb8hrZ2e;&>J(*$2YlrUuH) zaj!7{Y^+m5@VsE7TrtWO8U&0NV*9O^?bnNCIF7@bbiRBKMOPSD&P;h}LsgKQDZqJ7 zsC4>*mGV8~Lty-c(#lAiry}8Lu_a2a z(pmPUtp`N6_kfLVGUeLGmT-W?zOw_Zl-;UYK@IPGyvyQV&bmrNp~C7*sPKu$ja^FBGFs=i&+e(!-R$kzi zvjt~++{m%%H4LmfmRSV>^-TAX0eW{N5)ah`VfEM+~$^$onxcyYupHQ|8Rj3`)!nOt~LS} zuIGA>ZygM)YdCur3$MAz=XH<=^SIB9ZmjcZ?*ukic zHp;>ta%j*g7q2LPDkrz@2spd!yvlY*#hhd5DG+41Qt*6rNp>xEIHbGwfZDxGlouBm zz}kud5EfZcS*OiMyrsAds=LF`>T{q!#N4}!YZdD$x2guf3bRu1agLF4Ql-AIWkxhk z+MAw}mlg;8$sMQHgY=Yzh9M9{_O-mSuckCQ><_+a6(PjdR9U%ecW|rOP!;YJwrnKv z?e7iVA{hDHmR%(8`m5pB94$b9h!A?)}Lyaw#jk}{@<3Cv~M$``wKU%ESgSHL)tTu3Yt1IgDepb5 zhDlLoEYH?CUNFkBSfKf5bPR&eDN7md5)=jAo<z)kW+wbPnJi;{vJiP9ODL!#4 z0fb3A7~Vf^C=95r3p8En>JLFPY#1J#+zNE-crff~Bmu*#{TS9c`4OL~GMwR;)mP)S zPDu!CjZxsyp+FYt0mo9Mm1+E-{D<5%m5yubW_(UB4h?5I(@*++Th|>?b5C2cS z@w(;p`AvSl9KL*>F3%6oC(l1G7cVcb2VOtC-Zc6=VztehOaDgyTsfF4|C@T``1z*Z zIsU(CC!D2(n}#ReLhKF&{M>t2o}uyuxC4w zv+_~r{287`a1fWi_lcMuN79Y-#QZ@7^Zf9b=l^@@yzC{(!|U*`=I85$=Z)uqFQ3oP zwGI4N^K05qy|8z-B`KfJ&(Y=kDRAk3_IFx7m(J%$TzZM}b9|x_@bitW;Pk`O{e~aD zd_F%{FNo9scgyGVbM4_T=l>oLe3{>)#ph9vL24h3{x4OFnNqZR_!Zj5;|J-gn-!Oi zyYEWg303)!{OzNIWj7p2L6sE~1xd_Ay)1G*CfBe~@X{^Ri+mW0!d_HEIZvzU*J;*; zoaJqXww`UK-?DL2p@}JtQ_fxV2~D6hCOb6MCp3Z52;Esl zpU?zK4I)<> zp$U`*kt>bR1WJR*l}2a+r9tFMBQ!CkLF7s!G%=+?XOnR za-~sSQW`|AG^$HVgUFRebxCOuxzeaEDGegmc&bZEgUB_W>XNT79-F1b;93h~#t)2( zLkCwJ!|gU68(;orI9k!N0!%>_(jw0Jp)V)xAndGN+R_`YXk&JJn5t}_X1A*j`uw;* zI6mv2)^+r2p|bu6m{o2>n%Bi#VNPNa^h`=h^QcGfbfobE@H?;*Z^_>|{*(VuD08e6zPi2B_m^ZvSU*t83(QLBr7lN!}g(uSs}@!F>P zFS|EGBg+|~TwNpm7HztsAXy}KKkSJlB&j{&L2QN@H~_qek0|Z zdL(+)r}{N%Hz!q#wR+IDfuGw3cst4WLB4PDeU|Ubd>`lgK5r9vTfy59-nQ^Ihqpz% zjpA(=Z_{{N$J;>OHu5%;x23#|2t^ERK_D)N`+`QeO=*R9rn_N|Q>po^l zEM{~5bQ59Y^hk!?>#P$lZR*P~sS}iJ>dx@4sWL?V7$#|m{KhcJi^wyW)*mSYk+K*j zWh0-~!>nmK>0>mV%(ZlMXgZ}qG0jiD=${TPhti;!manFvL(}MQG@X2q`WYQs1}%#w zie-!ILKmCNq;hG}F_#~6u927KXPD5W<NcsVJDOjk2U-Tu9JCxxZl@iMwP$ZVR}$3IxD6Q-Gp_PP3PI;M#> znbIUQSUHp?p}{bvNoX)kX%ZR?Q<{VZ!;~hW!7!ysXfWO=O+tfVN|Vsou9gc34MJN- zhtec87^XA{4TdRALIcq}lqR9UFr`UoFidF@8VpmKga*SR%~XadO{zOu4y8$TM=_;I zbw@F!Np(jtrAc*1F{Md$M=_;Ibw@F!De8`tLum5##p6mvqKrzC$3P}N8$+I5Q(7#u z8@%A zp-0Q{zZN2w&537t*u!AKVDu1%N4?o6eB9lWVZUbO(DfSv!)XiZqbCc^8J=hBiS}i` zV|*&B^heE&RxrGG*>EI@Zou#{qCdXwwBz0HH81WlF@%jxZ#Lf=uf?gL)q}P@{LD5$ z{RGml(w3HWX7lc>UD0WDUP9*%qheCh=-h$MDJsP%(ulccbB(bZseFYssBT1vF=DMle(n;iXSchwe=v{llnEBbE(bxJMBqE z6@%P=+MaAS4W)9y-)a9tj4kv2Y5Tv~^q!LRGd31z>&_kiw`2Ezs_wKtzt-p1wt>H| z4NxDXf4R4lh(D>M_P=YhSCgo3OMTX8orjaC&rAJMr>&PJk@1=N|CO)9Bb z_9W^%liy%oBgG_=m#tZJY~e78`t#Ih4c`P4>6l4roG({z0=37K#*FIo%F}d8V_?6! z1~fmVQUBHu16mHHvAWhG16n@)TWq|;fTq#ko<*EBpn2&tBZBW5&@yOQYx}=2pk-4U zL@t9ZFYIk-I+2T}Gyk8+Me{TNpU6eaVg5gniZ3e_CH;E=AVCv~~CU)*azo>;F?Fkk9Wh_Yv($=~;7GJmK%OCzQrN zZBM!`>P^?U|5p3|{`r)=f7<>R*E~hnxY<~stvh%4-;Uk?xw>Qaf%*mNPpTF(O=$HX zHVCaAw0h9C0c{)5wgGJ$(6#|>8_>1^Z5z8_>1^Z5z8_>1^Z5#N%(*|~5sIZK#f8RMa+CqzeeLdv3q_-sZy`nqO6Z7|}@hyTk zc+O<$v)WC{w`)6&;oNeQ^E(BPV7T0l$@z2piMSrYvi>5jOYrtU5gQY%H$cQ?c1(5! z^|NIOw($_loL_FTYq*z4E4tkz*XDAOpDoc7U5#8te3alBYP^Tw+iJXv;J<2H=pEnm z&SY}WH~cKzcGe=*o{$s>Shrk$_P{$AOx}&K+d+Sq{R}%aw%SD16(3hK3Bm5FS)?6B3o4bOdmX`lQXo9m7y1*OY!o=reHk04tnwM9QHWV0D|{b zMNUV`!$Ko-Kr2e2u<&|dlv)vP94{354|j*CiZ8KUrA>VqrCBzWZ2hmpXz(EFMVK#xLdSd<~V=23(POHgQicXx#sV8ML!EqeMjDe^h5!kb*H*~4`bv0s!=W> z@Y4AfHhOSQO81W$S#-6kx%Vu?>t$W7OqQHsxP85@R?89xY@>OSdf(d~>EV!n|4Ryt zzOqU6@vHd0^}WqJc53i~N*+6F-$`V9Ossb`qx&rxHmqkt%lIF0CnFuQ_f$t`(C1{- zYR?yTw)#uy6japrGs9ELrJz@zKQgRaDFwacaM)fk{|A!4Nq;f_Xp-NhOG6yrI|4aM zR|&hD>~vW}`1ZZpd{-lg&cA+Df&5pzbnUZ5M>Q%?fy#bKmM=?hqrx*%P_gYEdG_?V zs#4iW=;c~tq1g@{^tDAxq+<3R6Dg50Up8*q3IwcwaI+S}Nke z-N_);E5p(&sgmLB95Hr!^>S@vRMs=XOQ=~dHI_#Y~9uy8Xgw&%rEEy4PISfJQNQc z1eFTDGVC$4FGRc%)5A#mC!b?1ee$7j&^0;1@aqBLu=M3ghW$TMXN;?9Z; z7xzy_ecQBQ_>?RW&FmV_@DfQJ8sa;j;eMeb(Y;6!p9~!NO<$|nOonKgMfUFK+0$|i zKdsXf)gO0}J=@M>&^P%{pIpMyPfmzJF*TntJSRE`HMBKj&z4`|MQm6q77+nS#isLd(1H$;;zJ!JUR@=}PmMJ<<~Wa-^@86uN<)iYlvEGg0aO2A|xn+aXxZ|WS81B_U zJ~?(M%O6*^$+k6;P+WW_4oY8}DlblatO_qmhAoZ5<>UKQAmf>ij(lk{__n*s#-O%o zDe&BQJsY!D21SBNOl3C4P1oy2-t#6f+|{B1Ofn8)xNo!PxKdCY!(q>2zZoAJ8;Ru~ z%}fTTJAtgs@f*n99$$=D{wwo+zr01bd&?VK_goJ!FwLrc>TtHfamz^~F0( zPWMM}>!=M&f7GKDSWK{DxQi!!zx2Px;_5yLEWPS1KiqI!7{h5N&frG=-V8&k2^`rv z991|IpsLzAS2$=j0xerPRMjPNnNWZ62vp`$ifXBMrm&@E6gqA@LDlE-62bUOBr>sX zt6KeLrEt8(aMWvXCsm`Q6+*Yz;b@b$pXy3+p7628aJ00UxvGc$DnZ{f3i%xFqk8ae ziD2gIfqGBMp#X%71a1?(;3BsM#gW*W= zVtkIg+cDRkwA&(cT)~r_DbktUQwHC|QPGjC%@6QyuNxREq`8aN3E#s;t4uMm z8}Q7bJ}h_+DvHC3?O@RLS}fhPQ+@anTbto<@_yK=?&17)v-2|R@+7GZS5EMGrHw#N3M~k z*|GHelzO(+vb!?;S=rKd#$v?s6r>Jclba}IIDYepH4h?AF+P2cZ5Lu(+yu(!7`F!K z#NH&v=e34`sD5`9%OfqdQ)nLDnB~a|Ahvo-D9bY-F9^*rU&Zn)sl7{RIkzs$6F;CK zYCEnA%Mx__jwJmcL}!VIq`OmD|S z8l%)+rYuj7tWY$iS}%Ceu9Cc4s6H}nJq%u&ymHk|+#)#mBtS2tnZ3yiLTd2+k4)uyl{<@et(Fj^UN2iQrSAKEoy>$QgPr&(NDjFm{Cx za`&z5I`hyqyx@H(s($})OWR2b-1J^7Dqq^KW#gR5`3WTEQ}#;F7Fo7&U{_!w@3b^d zkm%Hc;n&^ehD9CG)Ha4fweU9b7hcKe=!zOG&yf79FQmDS+b~@2wIdXH?7u3QJ_q@Q zCeFyYo;|7-@LE27?o;9Mrv7AZUVYa|l0WKonrri@Q@d6XJiFZu=S=WvdTmpqdQZmxOXt>)vOJEBo9ToLyidk8;9Y(HA2yeBPzk7 z_zb?SYKByPRnh&Xqw$Nfp(wN7HsNcPDcJpe2wGNVz3{Zra~w9Q8M+)?7KH>X#c%J1 zAb*=o!FYdJP((IE@p;8U!TDSqR}_NwMa&l*`)tKs37*h(tYCe@3evKhA=!rs!iJ*v zczfX^A$PEVjFfsH8S_YZ5ZxTzesBc0e-(n}ul5iQ^{oPB93Kf)bnQ`#%vvz^#Y5pn zbzAhx?mRwOIuu2OR1@m&ZwGD>4+W|1RiRtWp5T@EP_XMaL(sHs;!AJ)tJtgYX4Yor zWeh{DF0N)+_d_HywtL3#`1Bxjte}A5$M*-K)QbBUez#%BH+hcZD=d9e^gyI3#(${hM4Zl3z@rA@6*7cm+q*=k>ogWD9 z*}8(mOqh-r0N_ttAxHM|w>H6RgLh23$obK0j`dLadMO$&887_SfIn)gCAKW8+X zTV*HqQ4B>bcKJ7RoF>P8W+$RaS8h0^MJXWYX?xW=cYFC?#Rm!uq2Idh(4qfc*OK6) zN6xXkA*i{bXKU#>VT$RQTlHCF`d@l3m!;D)y7U|}O{8ac$^RLqXL?Bz!}P2#J&R29 z(DQVpT!u;8fRyC*gx;U&tj^T=8CI7=%hHt3u$nHz+$!h$5*;eY~Db=Vd3E}44;rz zgS$%deo68vZG9cD`4Y`=kZLM^5}d+tcBi|ldke(90TwGm&gA=`swB@-OSn(m0J0Z&4F^reeHg=S1{az+~dA`d;^9n zko(CUnoN~Ze&}54fa6{gBNg%Q!atqcQjSSqu_E#?Oyt8vPKJrxn8?pC(FZ1aVVLL% zh`tym`U9dzhKXK*=oiy6iN1m8oncZBKba`)ozQ-hsQ(^2 zmJ2;X#d?Xdr0wos^`*hqxo50@R{4B;CiGa{5&DSm!7$+q5&jq^{360Pt9K#?BJway zSGh6!Ka;Gb1KFR!cAhS7TXpcNv243o5P=<@uO}?*g0|O^;I|3sYpXTw;DxcafT0XTO)UHuX?Hsjt6jS?0?I6X}E>inQF}0V} zZc;4TQL$YS`}b!Yv}4C*xj(CXz73QF6PrWg%=D8ACBb~VDhcN0qPCb)qPCgZXo{)L z=Ie{cC3%*}$jYIz{x1F@Klc4D{L}V9>r3k&{=NP!Y4c3av>*Iz|8P>+Ynz`{KHrA5 z{-KTzwLg4c{vOu!Biffrf=l8P@_8s9v}8(O>mUAo{w+WDY5l{$&%gay{u}RC@c3ty z&-*Gr+drhf;?F9dw+|)3CGiRQJbb?>3FhU}`iE>x_$HP}?YP>W|I+@gW-QbChrh3X zsEr?LV#;m?VG@?)RYKh*k%yr1*4{lkF+ThMhM<|h!}_J`t=CGiRQJiPB$63q9D zl3-pgt$(QX54G#dY(40^>*J)q{B7|=<8$S-@k7!Dwd>2;_2nO3ALqwDt$(QX4|zXF z>mO1-hkpLG2jhE~*PGTq6m`b0&HXO%!%t!2`TggQ*Wn{W`!OG;*2vHJftv@z)^9E0 z+!R}ei`TkAgtZ>SsC;j5(A&-S#-J_{F!5L)h6n!<4|}I|VtZ+ZtWiMR-Dhl%%_6rH zn3^!1?I*Fo(a_5E2E!YJLg7%5xX{MGnOc91YVOsnjH=B;sKxbHMu)a-gM zhCPPpAurEi@)egU;(1NcqIsSS&#Y|z-F=BAd6w_j zCBb~VJ^6=Nr_a+0@Qe%Me(;KuzkauVOY$t4`)l_x{(}23`EgV0XKMXS-e3CJex`Pv z`rq$C<#ql&ACBa7^ZEI$KT7(m&s%PtSEnmls{X_pE>1YK71_bsoguxIi_#UpZ?V{ zHF~4|A&>d9xBQu0{;V#4hL`jmrXPAnjn@y4f22&_-~JKIpRJ~2Ds2PwEGd5$n?Iw? zpWWuqbn|Du`89g}Y&d^roIgv>pD`ykoas$GOZqQgov({unPR zf42aC=Ky~f0e?pUe|G_YrvZQ00e=Sqe>Va>J4$(=XG!@v=J(pqugo*GJ5(0hpLk4d z6HTYKil1wfd@P;X9v*)$KWT3)KP{^yxFma@_&h}CKue~&FA3(ycOHxVL_BlNpT*|S zX!B>c`7_=8S#SOfIDa;rKQqpsCFjqW^JmXVyJB+DKKebmen+19GuO2L(7L1ji9e&w zpWWuqbn|Du`7_}B*>L{MIDeL$KV#0HJ?DMh@3qfgnP?$2g`F?R|{9Vm@#5d=}|7w{U-O|`5kNGp*{8?}Q3^;!_ocE=9`@`cODO2kovbzG% z_xwYCEdCLnle7V5-?aYWzwYY!mHfj4j-_q2{vo@|MbP?(TL18O^tFCRo_}RuOXIgt zpOweIGS9qE$m5^oAM(E9kCds=r`A9Gz2k?*=O$?83)=W0u@ZFdPGb|)V*GdbSN65O z=d1t9JoEDu9+NRq8$TrX=lv|7mLF4i{JnS}KTqfJ_wsAT1=@c~g8A5BN$~e#Yu`)f z$2%VXj=t9K$n&r4YkjYM{>nV_eU`^R;>+>&xOfogY~f=ld*=f5eyL zeZt^$(5^45=eYbDG=Dyn$NYIi{v0BI#*oL~%TMZ*t;14V%VYk0C4cUcKU2x$ z@8##quVx+RH8mLv~<)|)>A&YunE&y4eD$@w$p{MmE*${GU-_I%%VX(3#cw3-fyt}g$M|dRW2E(>jYIxi zU+a7Gf?wIE{oeTUy|^MDd*t!=@@vKgZ5&b?hot@ESN65O*H(XJp1;?Bf5eyLeZv21 z=Um)Mbw?L;DzQ0p17{c1b7f?MexqCe! zDnUH2TjzPMu%z?|mhO}LT5!D8pW$_<>!8A!?HOM2))gJ!V#n~NhkmGStqKg6dlilh zyB@=|%!%XT(3g$T3@>S=K&Kn=sioPLBllI_ns|w29r($8?o!>JGc6${42K^#4?E(S7zA#O(-V1A@bzMYf=Q@$x}@w+7WujKvKKJd1JmvN!JFZivm!t{1C zJp^_H-eUUM(LV|r99hcn^d?Er_Gx2=f8<%doshO9Xxb8KV}hoQ5iKB1+aqlfY1$j0h8Oj%urJPd?A=by7W^-354o0{e@e0V_;7=&9hOxxztyRDbg zmZ?t16sz+ytS*OPb@{Ab{tf=y=uQkAiKZ(SFrNM6g3-0xj~K4CrUUY>AM`3QPBXI1f+F z9Ley)u!nf*WzjddGo&`GY$*B+s<@U=wOb>Wr%!<&7&=z?FZfsHd7ZZcoTtuXZEplzeVw3c8cZ^Up$su?)X_hNYA z$d}k8A&}uAeU*59J8^t(pJ{{NO#bi3l>Zbzw69T_#LxeX`F_e{zOJ{=2}NEJ;@v2% zPWhq@hr}_fBze?)Fddcz^Lk6_p@5qQX0dvl_9Y(1rHXf3@9sYg8YXRF_1J4$09?QG zp5cGfe;M7MP$tvqxh|dIN#hy}7g_tlI4q7q-|H{D?fTxc{Ftlt=l}V+2|u=K{rMlC zgLJPP0D}CZK>PZ(>cioN(`tsdHb{b|QT7Zk`>Ft|tX?f?9BaB?zuov567PBE@qdaR68E6@ z>@eQw{ua%BSai>f=AJBi$Cu{*EPBV6=3Xs&hXcLOgX)KGpFI9q<@37YF<*W_jvL%v zV9WSfYA=KMFmcWmeV`2VPxNQ$e>Fc}FP%F_!sz7ntZnS*nFxY^YleCMpT{M6mba@V z!Bp4OcND)%j1kRA>;@)r0ES5%0FyWX!z2!XNgRM-5(fYh2Vj`Q0f58-7$$K5AaMYO zNgM!39DvDA;s8M601T5j0FXEU^KD2R07x8wjfo@<03;58DGwwL03;5;Fp(EXj0k8t zkLmw4{=u)zv(5DuFuS}x<9~pEEg1N*Bg59`9^e`}0~q#pT!7m|jAZyuUp?IGNHW8n zdzN##G)vY&6-@L;XElYD_c*1=T)T^E)!%e#f zpk((ym_F}!8jjw5Sjli!$0YP2u_41$m;8K96N}_^{=3LR`Y*kw578DvW3!t3dgy&Y zntOcc9YmV@edrxTntOlf9YmVDdq^yY-W$luA@^O9I|)Vnv&!dnPHAfHKcc*7?nR6@g_VojeVeHm-| zGU?+gO&=$HU(ob@ViN?7O(3>H(AWxMLy*RXkp74?wuRISjis~x&g0)*7IjRR*(i0a zm|=AcnT;Ll*fJYa)G=p)wk35enqhT}n)MNN?3!V9Oq*eKteatV44h%LFU>G-6RdNq zl9;8~c6puuYCQA(O6`v^S=4?S!)pJHVYOe!u-e~anDm`*?pxH@*q>ECDeupHlhnu5 z*f;89YV02MF*Wv(`j{F!NqtO>{p8y`#aDU_W%tSctn$C72flo|??_{F$oHT3SC%9X zug{WTzU`F+Q=N$A(trPFO#D@(S@R-mVMwzUM%KuXW{r%jogvNI8Cg?9nl&}D)`m1| zZDb7&Y1ZJ#+MJ+Snf@aN*tmV0C*7C?2AJ(k#k+napS^Fbvf>^UANY)BLvsOrA z4xm{>BzmBJBWt%j{@rC!`^LdfodO{*+#YRjcHA*eR77?zB+3MY9F3q zwQtX`+UI9jJr`hD?Qb*8&*Q9f&rlzUrSm%f)p#azLqRjYCi8BjnRk=y)*h--YMjWiCwG z={NIw%~?lY=f9aOWKOQ5qh4!fW1o5rnql?YG;8zfHEV{|YuOBw$LSh3!|JtfhSh80 z46AL|f5B>f{v$l_eW7Idug#j(wkLUAO*sr3l zQxL!DzyG~2PU`5-{cdK=W&Txr$kY12yibPT>%!xb>}e@U9_sUOV^oQ-W-aNj?vdm9=P~8se_JL$ z4*p-*_sG|&c0b;a?;+&v@c&QyHvg)ReI_Kn^l$easnppL6}n`_l-YAl5zo_kYIf@rylE5=_g~#GSPJ!Q7bM{>i;9Br7>Di()vB1LGm+nMvvi2E@d^Hlc_S z(KDc)o^mSp$8?JM_*Yf;8wzlDXWiLh9{26qolS<-7M zaXDwDZG>}!?!J*so`KZog>cTz<%Kag=N9FqCC)uLKXl9W1!R@*ZFC@&o8BB zr!BUWJ+F+MHS*(&@JVBqh4$StB7@_y<1yy%X_>!^udjY#ZSCl;7vBGj?t0;~Z_!;Z zr2FJuFML)my6c6{(9z$d9zHV{-Sxs}?xMS1_$=PE{QHF?%olEhZOPBM4aQuae(}E? zu7}%T%=P;=a`;(vE|30X{Ac(MB)+Rg%DcK9N0vSGULEzE?@5v}ETgK2?^TlL+$Ytp z4M4sNSE7V*fCyqguUWrFZkWg5kKK~@H;=|%XrGUfEurnw@|)O z9(fD=4t@u}%lv$S=MQQgQ7-d4+6S4>?PPL(N9)|>KEJ!AZRZ^@znisS%lvK&X6?d` zIlK-~>UsK(up`DhjCUCCGC$tI@8EavJNO;X>(zQb_7Nz5#6CiDpJ=Dq55jnd@ebo1 z#ygC6?t74UEnlsZ&_4Wh?3>fsgq`L51I9aycNp(5-eJ7Mc<0XI?cC@6Fy3Lj!+3}B z4&xohJB)Y9bMm~NFY|g{04d^&nZ)2)R^>*2E&=;yk;IuFlvC+k<^?C*Ggjm^V9uKkj6s^wfwTmI|T1AP6a zsOQ_9S&iP^+v;5a`fSwqt#S;Vd$8Vp8~je9VA3DIlPK8dY*88dp3^O7WwkDJd0mgL zU$?7lVYHmec3Zv65Vgf|L$y^de4~59AQ(g1LX% zujw=Locl-e3wE4!_TD-V*%BMM4b@+aYorg)BhjIc8%eupd+msL=_m zOl3I#7fd|a>YNY%jqBjDif`--(nscw_Cd!X;Yhjq{{M>KDPJp>*s{%-71?yF+)Q!6 zGC!CPWr;2C_F1w}#hh~CG%PsonA!A=&u&+mAqOV`DZ&xsVBzXsims6g5`338H z)i{^n_P8z1F}OX(^kaN`5{tP#e#rfc;>-=X`m= zz8<6M7tH$O_V_vdusnjjoPxdlf=PdTpU8IDeH?c5`n0T%Y_=op<>ujWu~$)kr+riV zEZH~d%i701C&hntOwh4H#}M{)%AslPFd18-n3;@4I!0;EYu$Qz#4mIV)UlEB<~kgs zxh;-uDrP3<2K1+7?4|m7EQoxK#{$755C0a-u~x-Q9t%W%ZijN{C}t+d2wy&mnOujV ze=;B7{xJ6K3a0;Mc?5GitVb^6<&VnH6Bir#ZxPmI^k=C+vQFI=_cfBi_fhKCGPBO8 zUXh>si198NhecPcKjx^ILHUU1q&#Q+u@7*WqWsQ%-q{p(Y;Rc~+V^!#V4qMvxI^+5 z*bC#G=cM?x=cL3*jCXFGU5_bxtkGi-`B8Fg(qop6f!fzJ)@Af(b)C8`ErXT~nd(dhNzOvU6E(HJI8$v7Ojcx z@O=b~cNp(5zr*~_&mU#{@?*MS9`pTLz*c*y81LMAHP%&fg(rT^L9kzQkTDM9o!kG? zI?=j<-(mkw$5Ox6w_WVjF(_u&#pqB=h+R{0@Exzk}cT_f6#N9Gxpj-lc%~Lh{ZBzR$;SUP<$y ze!SCRA@H?!lB=6EJ)qRYZ z-(h}-_?h|m3BQBi!SCRASXaTi%KyT7Ka6)6?=aqByu)~h@ebo1?$4w+z-N5q9S7X6 zg725{e2{Zrlqc~0ErR{MSb~W!d{?1he~*^nqRxrwoD+Ead!L{a=mZ=92fzVv02}}Z zzyWXo8~_Kv0dN2u00+PUZ~zL0|%ztO_Og~;BA!+IC|fUL@E#cxt^9!-Q^)K z>O>p?2fzVv02}}ZzyWXo8~_Kv0dN2u00+PUZ~zzBe9-s$s02}}ZzyWXo8~_Kv0dN2u00+PUZ~z3ir@^TumU1OER9uO4aIAGTERTMzZ)GEy$TW_$C*tX#qToB!W`-uQAk{5k$SKj-?m zUdGLu&dSZnnI1h4qvupUjLK6n8`VSg+o*o}ZKHPS@0Q9*J@h#n$w~FuNPcR^)>*iw z4!7%{hm3uB!M+}@E63L_*taW~{>1VK_HqiQc36JFx3ulNh}+|Oe1D_ztOvpLC)ST( zuQ$QmKW>jdOMf@?OEBw$+vDe~CvJ~1>yPxf;J2`QmMkCe|ND9b`}(;J?l0^}df1V6 zWIOPWw=eAF{9X7@YJuO85_~)npGEvkPyA$`;~)5)8+S0?$+(NW#pg4ePnAdB;=B%i z7v+2KJNR8D<_oJ|SX(<2h&tN|2bz0erM^b@VObo1UJ}sT)5!s ziGmluIKMFen1To=B1~n1s0@8Jh(1eony5}{%S3IF3?`C6^KBc~${K+d{Cnkzj8-!DL^yX@uF3|y5@AmpH@obFt5v|W`mQ%~DG50y*Ln>JFBt^`=D10Mc6?xWWK#i~K zar+tAt4)rlMdd2lCMV@uVU%l84i-i^ShKG-hEZ-tIh&1gHp=B}l*>_$XQLdCaz7j8 zev}j1C?}*`(MGu<<&ZYYAt|@CQEo{&r;Tz>Z+Ee&#yVHYW|?D@1F()o&oPqOL^2aM zG*0$KbEYWFv7j`0OI+e`Hp_{8FTFWxw&hXTobP#mmspny_Hl#bOEh0D3G?5hG9}_{ z_ER5Mr7zhmXIai3FMIDkS}#fO8G~&&ljK0Q$yr?7cy;vN(LANZb)%{dQHTyg6{=~~Co9Md|?ayi+@#nwg1ulrII_A!U+@;`1YbN{nF)@>CR zH?U5!-MbRW^_&tJ{T0bMMK;S^wt4h39EYX9>GChqA#*|M)cVXeIdOin z>}NjNPoi-=6}$~MG*61c%%knNq}(+`rgWMhR2NPPA9=-Ik)e}5vj+IQ-ZTi&f>o6PSWSJt_Qo&mO6ftvTJI-kSXdD;cjHAprx0cCsYs+`Q zdkR!&&5z5L_dCLQcimX7YmCwQWnBAG{Q4fwvG}+rv4Yn9=#J0y?u!*S zZtDA;BAjU%`qwyH?rUY9myFp9oPHRUgnbO*xUv^>E=hXdrn;4?wNl~~|amM?m#2K<7DP zpvEqDv+NnTA1s-#(*Ay__uY1coavg67w1Q>jy^cje~IsFd(MbWGo5>vMo#RTr+436 z`*Jauc_G};JShtMcxByh{%`SfC4J5$6MiwTL!*0Gs#MlwbRV->&a#~Q%BwYx;)EMt z(v=5p!=)sDvQ19fH|IOzVab0E`Zg9U1|Gk*!{P(C#sc>2Nwyf{{ zoS#d(+3XkPA!l)U9nNhg&+%I3t@hbWj9)Y#ru%UDXUq5PW?lyOeKe&VL!HdO@3VR= z);RLfNGI;M)6Z{X`J33z{k{17q?owGbx3^BWioAx0W}i8H_uPrtDFhmmPXEspPX#w z4LVwM`|;{}=K6^z3LblGWz%h7AHfHG`Al%mjNyWpTroJv={8C50pDDnSUSe#$t?<3 z6^?jznmqqv#%1A#4ig0T?y@#KxA73c@3z{`a-8OXm(Ch|M- zM-%xY`KgKgl>FC3{!4ysBEKeo4(EJ`KjY*U6~iRIdh z+mFD$-q!nidS5%6&whAYi+$rFGmUHZ_kNds%{hPJaZUQ0uDImKT&Yv*Gt1>PkzW@j zzwS#>nBzieaunYdw~g=fO7nM+6_>Z;e#jlWu8aJHJ)VDdOn!p%v_ZYxNM$~X%sU`Ik#=cLoweUNiK4_FXL0is>~C%tPm<>}(v?3Hw~z4Z=r*)I`@7C>$3jjWD>UXlmvh{()Byi0(>-i8 z=iD2U_4D-0SsZV%|5fz*6868=$-J*TzT@7Hx#HIvv!6%fdn(w+qNpB2pD79R-=$1h z=BG91JQkC9l72ahiziKI?M3-nYU5y8@<6@kJATfT-*Nv#=H)~@*=gem#~nUrQsjHb z_`d0_^K+d;;{DmOzdx(b+GS$CgMDH4c>Zx~)J0*R+emy!1?zDwUF#dg#ii1$=X?1j zcgkitW3*Sux)gn8v&_Zidze3NJ%99ZK>R%w?8iajK#DlY8SRfnVT=n)W&Pa06DpYJ zm!%oMke`%2Kk@t&zbI}zdUbT|XdSi0?}IDL{9XG+-L4h+OhV*?{5xyp^f5$aO9g8^ zr--?)(qAfHBG!6Cp4s$w#gnqEd*t0Uhu59NUg^pYx8X^W1KB2LHoq$rm-m}ei6Oeo zHr%i(RuqMk{7EIA`1-l7IGyohd9z;T;_~(#@jW9O8-7ps8N1l!xgk2tHaXK3SBuMY za&iud*2zoEbF`0Se%}52aFZZLgcg|$9oMjpJ z7w+GX?y*a6ep0+2ITlfy6icSlKG4>8S;VO?v|@7upazE}2q zFRt+f=XkfCHz9BTeR;d)e_7V3m%Vo%t@EXKy?vXpo5ye&$Fo6BNfUg3Q^CG3GTxo_JM;dl4Vt^Dt6Ry7C$Cn^LFdOt#5c-27!n?C)#e(K^fq zIa7%hx{S7aDp>bDGv^2LVzR$eqMRm*1DZ3%VD?M#O{|AtJ!JcH-Cx&ZKThR5Mp^P1 z9}}3n*vIktVK(eH`M43;g@31v%fg3ceeaG(9-byS^}G-FHLa6#;B-%dxqS5RzOTtD zu9k>7?nHTSDp<#>;{5d0(UmEm&g?p5QQs+<4RY?Nc#>D^VV>7W>`GTYsX3tgRhGDy zE;)5PN!L8CxOqou-v83N%0f9gR`9frG zcGk$r_K5s96|DP`ZD*GB+%_)fthCHHw~&@|3+!9l`I`2-ZLm@0Q^Cpl%MxeS4_U@} zxX78!aVA}IrV?9p8N?aq3-sOS=7Hh+GcR-KyV1>n-c1G5ccYt*i}M82ccTa9z5#;$ zJ+y-Te8-h(I%|Fu=hKy^6_@ws`PL_nNDqkXIyGC&!73^b| z$WWaA@jc^3@Bd;QAT8?v%t7H{S>|QS`rgXppwyGDxTJkV`)roTnbez>tr%=0J#W*m z-+Z1*4AEtDoyEnITh}kAyC*We-g3oneivu9$r;CZlCGSSY+?92jXXCD`>^L1?yez4 z_;bG!-~4%C!HZvWx-;InSGGC(s+i2# z(<5h5aiFN@W#Kc{zS6SxWmF7F1t()p+5BR8O#CAKau%2W;B4F0@8%R0H;Q^*mUxnx z@v+1+V@dzgeaZYdUZR|-#0p&|*{`z1jhb_0@0jb#N!NUY^c)L0i;Ek0r!UC|wq>+m zoHFLml+T(f&YbwTDn85e#r`$Urn}Na-z8!?laSFnubMU8o7!`-ML5$kxc1BcoM+x$ zHPuw%$OgI(zlHS}oeI|DIOZ=qcK(7h_L)0l-*i?(iZ$gQ)3krJ zdGXiZ@!d(8ku#N8u}vABqo#s+yp=JxEcy2OAuD1sPfw4WF76k*55&2{Jfj>NO_2Lze~p64x;lEG1ncHFBK*`7x^7w z_zqv;f5`WrvemRLaOXzZ@7&1r9PQQ72j9(hOl4l9Z5TAzc%J3_&I%dy!~?Brb5R4yIkcg!Id2c*&FlSnI$?8 zY3V$q_#K^xv~(U)FrA0AbRJSLoretRJfvVc4;gk^J6f=xqX{P4CGQt1>b;(9mN{MP zrN!kr^Ex!5JFszwc)vqhX{VR)jqcAy3+-Jwz;uA_wCk#kE?!~UHw)~!E;yk zw;Rs-T5_a{Lr2?3uAeV>@eNaL)mQ2W=Ke-}V?2J&y>wo7>-k7L`<0sgw%D8X@W1n& z6q)ov(lMRmP5j>ZQAYE?lH}yRFtglG$(Z7UrLyvwRIsm?KjVLjk4I$3+7X8{6VG?- zeyG-AarqwBm$uLMqBu|S-$e1B#sw3N3p8GsXuP0t#6;r=jV~q|UufJh(YQn7Q4ozs zG)@K4I7Q=EA{xJFTq}&mH5%{2XuP9wFpS1Q8Xs*mKGL{pqj8hQ9UG0O+U^>&KkkhE z(tXs}1%={cf-a*!o6TzxarsV3(kI9AD4v%Jmt}sDSL@}NtQ(|9&dld0)nk&M6fdXu zec@*+*vALUWmCa=pAP3$cIT4xCTDT$)i^i1^}f81 z2@+3I!9L~)2U5Yh&f@ZUe23T8`MmeF$S(XlWsLphwCpcucwM6Sala@&WLqBPV}fus z73|}K<+7<@ou8y@zo59dv=hDG$~KAgoC@Z$QXc1Kac_Athb*Zdhj~qT$eGRe zY0!E+-TmYIRP!O*WcI$#e2wyrVlkJC_?8OR^%s{{V7`;S`A%8ZU2)gFJD=?Dgp~N~ z?}`-c?~oMi@0Jwo@0=7&XD>~3_Oguk#vAf6{2f1vC)qaQhzqcndyD@S4X$`z55XvJr9tAoHpWTapN8K z>wj~+W8Fouu2{_FB7aN;d;gL;$u7m*zn7Ws7}E2sqV8SK2049P%n7j+--xmwHEq@M5u-1Rs z;>lw%i6?23(~>I17G8(NV%B>p=QYXti_07F9p%57H%7ML-zj743u9l{-_O9l$3Of& zqhSA@qhLQS3#PvtDkr%3{Jg~dYpx@zGZk!9`BZSSPV85feZP`)Pd{$`Cl#DJPcYx~ z=kb`+IXaI`*E(Bq<7o=}dPzU>v4Q_T8|7sEi4HyYO2XWas7#5N`&>TxOzmjhuf*>> zDoehq*Uam7t;lo7~? zaJ7wwDwEX*t*O{}?vWMQ2@0IXp*JZ!Y+cd3vf9F5bEcqRynV367_g%0q zHHIB?a>^19Gi^uMD_-`}zNRtk7%w}*Uh%S*_BD-R$9UNh_KKIiw6AFlJI2e7uvfh7 zrF~6f*fCyqguUWrFYRj@!;bN?BkUC~dud5mcUkuD z^cfPp_mt^&d9Tv_xV^;Uu-@0sy!Wj#*%sNN6nhI> z-z%kg&hnvQekbThiE8zARm)9Lmx3uj{?_-w# z`>dotet%l{tTDG8J%=6Ji>>{+1Ht~CZ^6agO_C`)!d~gQ<1=-XQ!d~&R zm-aP{VaIsc5%!9gy|k}s3_Hflj<8p}?4^B8W7siXc7(m+WiRb(8pDq9vLoyjFMDZU z(-?M)mmOiRc-c$)n#QnWyzB^j#mipW*EEJ5<7G$KD_-`}zNRtk7%w}*Uh%S*_BD-R z$9UNh_KKIiw6AFlJI2e7uvfh7rF~6f*fCyqguUWrFYRj@!;bN?BkUC~dud=iG2X=-XQ!d~&Rm-aP{VaIsc5%!9gy|k}s3_Hfl zj?P~EU-w<$-hT2u(7@0MH~A<24=)rLUdVn6l0dN2u00+PUZ~zxT9N0iFfV2Z-Nit12_NR%ymrx38b( z{;|@~N5>!N0eS!jzyWXo8~_Kv0dN2u00+PUZ~zD~+YdEY~)nm1l+8Zv(H>XD}XVM_(S^-w?7i+nb}W_$C* ztX#qL+tB|DroS61Czw7L(B}nHeF4?$%j}r8bRXNVKgqU#CD(8t3%lpqXFInSyynu) z;g@eoKXX>zz9j6vaHKrHN-;eAM(_ht$*5FAo%Lp&4Ql~aL*?UUmBczi7Vgn zh#a%>4p+|$^K;G7Rb2hwH)wB8nc~|0$BKSt`G=bWmf^MQN18h;EfqZYu&L(I$C?U` zqnui1&9TBBwZmY(0CR)9f3!eq6|PUUF}N?X|IMg0VeevfViN zOwni8<`>xsH#{MD!xv}UcDq(ITqZ7ZvaFH+rh>ICQo-yau3l*;6-+j{ebE+KBD^II zJU9E{pjE$%sa#IZRcrHttJh8z{I89x>2rov;6o+kM6(X+$LJ{c$Y#{6~R zl^q8Oeqi|iw(8Ozf(P_&Y9G73rQnW>^Q>82U9h=tfNl2GM&U!JwWDpqD>~ z??j(|92Cs@nAhPc(o0&#$E=h`>#787Sr7EHt)745`Sj=+6)zbV6{G0G%v-7Jol!^G zWq<1+_=B~9{m+61g4YZ_!ya<_9)i!gZm7L!pO-@xvih47?5TOv1>dx8n!PS~O2&vg zCKlMm*UXSHqV3{I_QXF95L>UidW5}hbtw44{IhMfr`;HlZ8B(in4g)--v&K)ME%H? zK5mH4eLNAIjq+@4ctTy~1Ird+%{SzM>CIQQZi~Wfi&N%aCF5FZcuO20LndQF(RjKU zKj-G8-M8S9$H5yGeO-@bV#X9b4sIEv%Qn7buRLD2q6eKPSAC^UxcCN_&p&eg{IKFs zm(OoF>+5jt%Kj1uR=-u#9#{P|!RNl++J3gVvEZibPPgy2+Q&U_JjC|yvR2~rh7J?# z7c(vsJmT4DwngD8iPcNT6xaj4xm;p(PPa*R$rXboKA$sVxIO60X9RZ}*vF1Nwz6S+ zT|e}t6%6TYg?Jr=evED)G2R$j-S&eIrmolNzMtq4Gn9Y z?ZTX3%r<1MFlHOl-vrbDTF)(+A2R2-jI*J$7ym!&(fxK~BV+EX;5N#k=CF5d{n!!}PdVp6+xW)|1ULTilkn&d#t1(6$(zHEzH#S#_POJ*P}ifM>+-rDUB7NO zl8s|=D)`oU?mW_Wn`+tF7r66C-~2Jh_Ws~vk+bH94~Dx;pCWi-T@%jz*1d!G$F*}; zTw60=o*y}_dhpopu3t~Rd;3;6UG?jFN{jQ~as3*aznS{t-n|(#W@%V^v+LKg0mp^s z_;(9GI^voqjvL_YQenn1LBo?qNgwlD+#77#bdKPMum3sttV##LH?=<6yxpR%;GDPr zU?vW8?=5tB;B52YMUMz4m+W%!R-DxGYp&|@x*lD>Zdc2r<<#=)e(C;dJ!t(fYufEP z$qbq~Le3A4es{RJw&T-+Kg>DX+~1R z!L=F}nB$(kOU^CdlPEBiZ@NX!Gi%v2-cj-ld3j;tM)nAHiO4g1tTk z)87rZNB_2ZN8Z~-WM+Hu-`&p^tjl=YMSV=xsoT;rP+dvcw9MXiBF~?O>`L#uB>Tv= zljm9|R8LY@T8CP<>3`XFg1zko!|&XC23|i_ z=}oZq1^AtNmjZs5eCM5gNc_n2L@@l$#e9r+$=HJNjvU438v(~ypN9zMTm^ZiTXQ1S zMB@(Uv4Z(G=SHkI`blz0=Tyiu%P-F?YK~vjb3La{1#f6Oi{1~ME@MZEnC4_I$ENZn zVlM0IW%>ZK7N7^_9P|Lc00+PUZ~zyw_h$rwp%ZWb8~_Kv z0dN2u00+PUZ~z~9vj0okM_0q%<2&g`oF)19jlD6&mKA;$ob2D;hmR{x6K+1 z3wE>rYWw|$iMGR-5kbe1oq{{-jI|9u9UPp0_@lv-XAic07xfG39a_;e`KXtDqEcRP z+WB=%Rg0bo573syjWOuX%CY-Zg2D2SCzuYZf|LRENE!{G%GhWtE-!82b^NsewqlI zeYG*@IIXW)+p9;|_2@f;KQ|w4-t68#T-Po)C|o_xd_G}l$ai!`_aL=-F;OqVTF-np zSpVMlgk$pWOz_=c2Y%l$thYIr?k=8gs^tz}bkIrt>-gsZJumd-11ewW>j}tqg?ta+ zjr$#G*4%$c$oKH&JRO+C56ANzr{EV!-;2`qw01K_qg{^JNv8l=AZAk z3GaHMjh&NM-+WqdR5<+6UiRVxcQ=L4R0t<-9Af)*Sse`e<;lViUYTG!ZJHEx9DPyY zrN2zG{c1drSn&1Y6%Vv8u=`#*r*QLiSGU!C(^%^;+ho&nYRvv0**X=h`H%|!)1dRr zrAxjH?OmTFmL^7 zsn{mi|H5X4H;$sa$eZ0Cv^#Kd;St^Xn%w!n2KL*p3qQTBomuegQRew>HNtyyYnf~Q zWlYa~PY7@R>#srU9%q`L&gv2lJpaC6cITm{^`+;AKkU*ZxT5Pgb6$n5dA@M}tL};V zp3QP*8<(<;=a=6y)PCLm`S7J`VPfOMz3kzK>~8`~7R2yVT1w{Z18$J_m83=0}QP&;wZ zYZL7qeMSUVc0MC8W5(D$+71qWzSstre0!n2r(56Pp;s!I>mTT8|MgX;pw~C`&4$*k z?W~1OgR^ROG?#X*XA%kUkPrSU89 z*$E%4)=rSUHC@TGrk9t#&=8Odm#5?J{?#Z-}xR3aG`jYT;{whuU2k(%bDb1QSxh@7lnPSkob@a)?*pPlQ7DM zDV~H;o=ov1jPhrSCpOBfDW2FU-==tCqdc7AiH-7eiYGS8+bN#dD4(ZzVxv5t;)#v& ze~KqIniqIIh)-!87n#>p?qI)pyEN7T3Lzie%r^=uZLZ7bUkj_7GW8`vqB zcg@PM=@SF(s@i7&Ka8}OeK0Wi@V-}r$$vfHRz0#$FloSE=A^dW?78zh1ben@WWG7;1e^a^<6z>X zPUe%_tJ})6sunpGYu#qE%-NPdw|Ox?IZxC%KsLzfeLwl#KvAAw)N?I=Dp+$S75vV< zW5R0hk1{ttdSUqZv8%(T&tG6FCC&;r6zpMhM|3yGJ%390#-R=E?Y&!?>)t*#+)$yD zy}Ee~^W`B2gd~rpIaEM%s6vg)Qs?Ry)+Xos=^A&6%O5uX?cN2Qp1mu#yvOBb552cA z${GB+f#el_Jwfsf;sCERNFL(XA0$8V=-XQ!d~&Rm-aP{VaIsc5%!9gy|k}s3_Hflj<8p}?4^B8W7siXc7(m+WiRb(8pDq9 zvLoyjFMDZU(-?M)mmOiRc-c$)n#QnWyzB^j#mipW*EEJ5<7G$KD_-`}zNRtk7%w}* zUh%S*_BD-R$9UNh_KKIiw6AFlJI2e7uvfh7rF~6f*fCyqguUWrFYRj@!;bN?BkUC~ zdud%L@ChL*=xuM^$xkqRa`?MoH9EXcjQeYxK~qV=G0CS~BZBKD+$ z^?fogtsZ4xzWJ`8P1U~^b{;;}cH3AxxUl2lgdH@H& z0dN2u00+PUZ~zejsxhGO zpvR_~neQJSY?yg);g^jHOwaRfOWa#!?uwk8>E`ic>o+*>f}`$cyu3xd25*c%^6peV zyZVK-3+Nn^wLG58`W*|VeN(fx%AhU7d`lTL_fZM(VK5q^y%dhJ$pGt|6YEv zOS7hXC+(#%>=-XQ!d~&Rm-aP{VaIsc5%!9gy|k}s3_Hflj<8p}?4^B8W7siXc7(m+ zWiRb(8pDq9vLoyjFMDZU(-?M)mmOiRc-c$)n#QnWyzB^j#mipW*EEJ5<7G$KD_-`} zzNRtk7%w}*Uh%S*_BD-R$9UNh_KKIiw6AFlJI2e7uvfh7rF~6f*fCyqguUWrFYRj@ z!;bN?BkUC~dudC`PZ{Oq;U&CP@MFr6yz8V)>lsCnk$Rl)7!ZDCRJWKss*R%!9! zM?DvYw+u87?0$Cm;L1vN^YWgi>ZVR%r}}m6gY(*&^FD7L*1z~9d(~S_dgOH=krLtaL$e*yVi+>vb-$3#(qAsGj%d6$1_{ zus2+>pzy+f-O`qHW$8YUknRIXXgPP33|gL4a8AyX$$L2n*NyJz(4T#veSzKg(m92j zue-YKrN2zG{c1drSn&1Y6(77Z!FJj-Dd;%*qQZ$AhuD5yRtJNAd9rZ$qrL3K2kveP zpQ#Yu^+X#xC$GNwwBV?4k9!Zbv%hL@{`r2JaKsbegg=~kwmGV9_pre=3&PXy8fMz9 zIxlSWX5Fy)!f|HbUPHrdkb&+1$%%B53Z|G`J1Vd5KhgK1P(6HqOLWf(-`^75bHewx zME9KV{VmZwCwzZPbk7Oj-xA$(VqdDzrFQP+?dR{PcKHq&){FZo88>S>D|ugv*H5|L zZxiW<<&1DZIHOj1-(6F*JeibXy6JZFZS}rBaqc3% zx2GhGJSQ19a6c06xysl*S3Xum_jmEVWYPUyd@osae^=VZHHv|`6a(+__mV~TcO~yJ z)AyU{d(ZTJXe2Ys6W!mHygyBkJ9QSW;rvHpvcA_#-}goJn5Z6oKbXEZOy4J_?-|oE zoa5WMcb&56!;wK9|6Im#eUF*G-%Q_ortd@Z@<{%m?@#mci(P1pOXeXO>oWSYx=!7e zmO;y=W!8P+KGHb5fO3*t-FK}Mtt+iVty`^gZ3}Iqcl#`{Tj3F zk~tXlE18>7zmho{^(&dnQNNNo9`!5fBh;^??@+&zK1F4cIVZ+DjCY<(azCNxnA}_F zxhMA-dQM85yUN($(nBQT3hx00W|6T9P>-~C)6(yd@!FY%94&z;Ne;Mah-1p() zyb65>G0tZu&kvXT8C0C>E8Dp~y@shV)-$o5iSwCmeAjD(dJd)YADqt|vfX#V<9!6D z6F;BA`OK?F7P+Uq+sBRSw)wF3!t#DcMvrkCW4yz7hw%>MogdTXjH@5hv> znBQT3r}I6X2kQJ#=Z$_`llNQsoluN-xrI93VqH47aT>#p@vM>4Z*fCyqM4XIQoYZ5S#;{|& z?1(rSuQ;j4IE`V)c-awgGG1{~k8v8qj`6Z1;$*zyq#olmh8^Q&N5si^#YsKJX$(8Y z%Z_ZXK{H1L^u4wQ7C!Ld%eoXIl*Cu)8eeF~*z0(ALW=^&*2sfHPHPH-TKT7bF-UVjr@z)o! zt$%rUnz?WEQwhdL^_XCeXmVM=xYO5z%`s=cA-L<|r}&Y>Bg0#nJuhh@_@;T) z&C4(4ZHILk{aIb7ZcEFcWz#b2zUV&czH6OmU1=R^-D;h4-y;2|f~oH|>O1wn7O8YEBp2;ot)MeFp4G}dMGXLX&rEiHqVP0OtNqWh@(4*jeFf1Izu zzy8PKkIx|`4*T&%upeIp`|(AvA72Ff@kOv7Uj+N{MPj%gUj+N{MdG<1UxaUdd=Ve? zu7Ob)|Kvb*pvGedD~={Vo|( z-#M3ybiz5FVCpaDeuAmLoD+%;slS{n3a0*Y4k6?xXIz z)``}Y)**2zsavgcjbDARwfU*;v6l6AT*Kbx?6!Le{)S_URKm++ecc_f9%K@uGD$x@Fg# z@U36-<@qarzaf0;>#>5L8n`~(<%0_Z-?{W)`&i53ZKTWS&+0mLTUrJ!o0eJkMfXwn zUF$^aO6ySTwzSxD(z3649t!q66zq8@*z-`Z=b>QFLs#DUj$qG2!JdbLJr4zY9)>J~ z=b>QFL-A|RL-A|RL*a?%p^Ushb6BwFuwc(&!Jfl{J%^Ur$c}ruMtnX>8%jnPQI(1uG1}&SGS@%WvQTJWzMC(fHaEoqJ&oh{trS(yi zcUprUpa*aO8~_Kv0dN2u00$xt@b4`-sNdU_Ig#J<73}wd4VU(N#De|av0(ZW?6;E|}`!eRjcq|6MTeQFD7N1O44{dyIKco7-c|d)?d~W9pZ! zvv5rvM*exo*q0aV>*2b%U%z|b|CY9$7jb)BkMFPG^4oLYe!c@c=ETm9%oqNF-{p$! zyuS-3wUl_?27c$(^Z9HJ;-`!YhIzw2#rj~qF!uf>7;!Rwaq_p;_h85P*^zybe=y!* zydxT5zCcPS@A<;{`St8YD^BEbG3T9w8rZW=H-Zm*wz2KKUmL+Ev}j@PUejFg$DbR! z_lWv}$5cAaw*0E5;N}Z^+cPiOQ*fnk``Zux_Eo@jZmvDt-mr9~;A`fLwVUhTDEQd7 zC)@QC^8`P2|1|s2KVOkOxSux{*ayDq(V9Oy^NDHpp{rh$eY(TGoNS+3c52AaD-@2k zr!|=)xJLisw)G9q3f^?`0NZ%tmx52;{R}($Gk0FMVEAda!myf_Kl@Yr6Yav?>I;4- zzlA;Qs^)^f+tk=T`C)6p9h)_<`?fKH@7Pe!KHB$0!4pVV{Z=^qV$BA2|E{jg6RR8B zBlc(`Wu_e4!cKkL)%o#L#`d_$wRQ4ir`k(SKUB(eY1!MpU*DZQxNBs8`{a$^h|InI zI?N7jyGn46gU8yV&%8-+`!SPk-Th7%++o}_J9y-WqLbmj6xfgJ9kYV_mHX>7`=7TT z79H+>$rM|-zX|wxzeVG0ZnbL!-@I^yt=T6OT;U(*+drTFx!_O!d8X~2Q^j!ksY5#3 zHP5><47ViO*=L`uBhR}BE$yu<+!=$1^P1Qxx4N?pZ~xf9KKjQ%%6xZ3efw4;$EE$c zB!EgPkw;g=%o+5*8 zSL1Zm`RepT?EyEQDs2t7{R0F)_vf3#9{(C6c<81oVeNreLyzVY#`F8gJE?49Y-UFw6;-hqz#v6O4%q zhB?8QxL}wQjEM_|Ik7F)eJO37#Dzk(AJ<7-NH8ZD6Bh#J1Y_btz?@)ATrkWD#=2dN z(^Y4eTBn*;)ee)k9^c&Gte^gs=wbN@W6a8DZWH`ar+jnR-3JQ(zt0QI^S8dymSwwr z*D2=jRXPQX7lap?zpj2%aF4NPo8#A1H2nPK<$o}p`_&cv^eIQ1qyBrc;0x>i5+q(e zNATXg{}z0|uR9yI?`MsJ4Q;nS8+PmZa~4N=w$?*7%TMysdpB-33;-aBs}%X-uPqH$U3%=DTky^m9y`{HDFIMXt?_MHqR z;dJ>_Y2!mtF=t1~qx~xttofM=PS;qLuCabc$&-q%bQ#Cr=@K(j!Kv6zmr0i%w9M(M zGhMdUvX!<@(v_vpi~j$!_7wY8#Ulludf_?t^J{;VvG1{I7u)dtWr8O^Fxh@Rw5#AB zA1ScQem0U5UO9T2ZGXZ?k`vbZe7tSk@=A&S{Z6BIonCoe@GoEVviHq%dApWb<7|+J za|arOWz6E-fpQ4JoI6ksA((Rq${_@E?m#(&V9p&VhY-xU1LY8cId`BOLNMnJltT#S z+<|fk!JIo#4k5bY+<|fk!JIo#4k4KHg=qX`+~&oV_1JH;4zpi=H*Su;VygKzw_d>V zf7x`jS@PZj!GAclzd63ne*}Nh{#5h*hC>aPdGo18rb|v+!L6>`%hdeYoeBT-`&WY3 z>$o%FeXf`mob>$!Df8H%`x6)MRUo)|N}fNS z-`gzz)UAgPe0+%c?jNs7yLbF;toh`oIfC!4IMq!0wYlKnmucqV`pZQ>S{{9$K$DB7 zB!*n(^0ZqHuN-{)w9DTX*61BfI>W62Hu=j9!SbKSTK26?Ux&fhSB?<8xaQ}aK#H8#PeZKO<2-@x2{%rS!RT99X+dAYh^vsXX!mm_x( z{LvS~Oz!gMLT>Bk4dcyU8o8Xg<74?|?-Q%Y^B0B{n9mnqC3&^$*Y;9^-i?9>ewqu;!qtf|qoAJ2B*1w-(y&hf@>zOC8^|-iqQpo^KzQ%0nm2EA~0} zlYXr8y1AF0YP;NgsI=GQ+5z^zXMGWHyN^9T#@5gKtKft0$hT+izNg@$))d&2KdvF% z-q2yP{ZrR7gwGnMtA4Fpp7+!IU*zO@Kh6II^Sqzt|AKkmPxF7lJnyIZzhIvC)BImB z&--cq?=a2#Y5p&m=lwMQ7p&#ict^=YYmy0?Z-{KXuSI(qf_Yzy_A&(Xz839e2-_oKZY!MyKBdp&}A-;efsWG_QwEn8{pWZm$( zE%TOj!}~pqSvS1j!{MVT@TfydTDxb;J8% zj9E9lHoYy@vX!>ZpJ@N^m0o8_-{&kSu-_kehUn*P+H1aQsM~Aqc*A(x_SUOHZg=nr zgYDEAZwVe^d)nRpv9IOlRhPH2>zcd!4Hm7gVQ>A{Y4ZGn*y?sS z2K`!4JG|gdH}2^1rEb>)cwb3An+>vMn=kArd9)9vf;A^o!P(|hJ4znS`Bps(?6g~M z5P!_;UtsqfHCy7C9#1t+<+G{SPM3*%k$t?paI`PkeDYM=>eTuYTW;B9wEf3-3kC1? z;d%CqCEp6JIlGgc{HEI|6zeq7-8{Wa$P?r7Px3{NebW>J#o)|&rx|lup)juwA{gV#Q{>!37t6YbV?fF6C!Kuy` zo8SK_F|n${1(hlUS8Q~3-Z^Z$xug~U}KIQ-2g zH>_y%ox>gfb8BJu)(-c0`@rz~Q(T>cFFh|DzjBhu_WrJO!}(*~-1(QePlnT*xw&)y z_dW}s_|?sw=e=9mUis6RQodg88usn;^8`<*d5pbsXdrmgO|9*KKO8Ig-S_kCyO+AT zbDa~;u@z7Fuh^ycal`HAp(_R7w0OMjxR)DSuR0^&{@myQd42@>{&kCQ5L;^wd{lX2 zFyTDM=e6OB!Nhfr=MVq9hgthe@n=+0`K*rBrOhSEB|lN;mpI3#Twip{IX>n3qASkv zDc2XwIX>n3f;q>hTwip^IX>n33FaZ^_>}7hj5)`rJwCyl<5RA0__@}D#uOWq=czI& zkB>_tn~znL!9JD>_AyrU;A5{~ACm=Z9x`5eTvge>%LduB z47De;2#)=9iuCKJcV0{MrZpF~X;J)4<+GXtsbI~MRIv8VecqfBw5{cQ{M0)Ng8kQT zKQ?)pE%z&x&vH4kndqVXv1^Cc^Z5Q_X|ufEL(0p$OV*gFopQauncf#&$ed^0mG?R& z+v%3Jd((TP<^Mhe>5txn^}Luqg6_)Mo+JJL`)lDIm7EW)Ycx6hB{5NKI(4^4!nY4{ z>noMs{dYLO<@xgbz&3l^YcF%_CGG!xq+MCvtcRkyc-~WUT zwrK@dPsPp&d(;`O{^iFuwSQmPQa*e1rAOHbw{;MF;CbT%*R&3YFvh7Y^ zf26(k@KXf8)4HC$V$+F&AFSBi{w3!G!3};e_8)!SIq_v#4YDoX!7nmf&^Y<=aZT>>~IGIs?8U(M-<9HXAj~&brZ!Z=>FuXou7qDKYzm&o8nS zzIa6NykY0rv1e`)-0X_Z_SicPFyPeHT9e(0P{YKY!?=Fn{AH!7n~jKdkQW z;coNd-ZXwVpQ7hM^qk5EQF*E-i0YyGO{80mHHX)~uvc*Vwa!M}Z<`q$mFL#;R-N`r z@N%A81N$|1q*_|rF88 z23{_Bmqr(x_J3Y3`0)w@%q`>GIp12&}0#8Pe7)>DtI}zvj+9*-UuV`Q3kC zIL-9>%K76Pqq>@&6{<;@Cab!c0lCh9Ykk($9DB||^8Ed$^UOO7s|$Yq=u^z$A08?A zj^(rm^;`qNHI8d;8n0;~c>XE5re*K;g7^RH{^pF?Jp>P)yD8ZHtn&oFe$_KU_qoFb zZ`gNcFyuVPfwPZ2Ea?2b8;=hA?3TpmZ6p8XUhvQMu@BF)RVPj^Tcc~UsdqFmkuPYp4Zo_bAigG0_T4fm;JnO>87cQ7l~9VIw1y{XBc*ivwZ$~8>C z$$rho0PJ+8#@6C#7r1=m$x~aHw^uZm=g(H?Y-VsuQrhxzwdm&5Gx z$S6~J{$lCl+9#)&d0{KTxt|o6tKR%VY9 zqio~*U9SGeh7D}v6OB9{`R^9Cb9I-mwyw~@KGn|U9@SR$vM;@{my~(^^a1uq^QGut z*GU|(5eFXc)xtjffa}Y+IbH0B#~v*GT6n?$+h&P-mvo=EN7@Cm?i2Z24V`Qsef)I6 ze`-}=Pe184vFVu)7TB4+Pm#V1=|OAQ-!+tW547X#u4AtjJo4G$cEv+a3qGOx0K56f zuLRHN*u%b+S4V{KE2V z^KkwSAnBXGXG5^Rw@La_mV2V6<=>y2qh@04U-r;@8M!Cw{AZeF_@1cbyI^!Ce+z~k z%XZ&artJuO#mipW*EEJ5<7G$KD_-`}zNRtk7%w}*Uh%S*_BD-R$9UNh_KKIiw6AFl zJI2Y5vKAw2CVnjjSQO#*51UVg!p+wp#g$6Na7bzt~+CiY3(J#unhaVI;6$=}~m{^u~c4aHABH!C*v z=Vk>{f#mld=28+%3jb;<8b@%0FQeEoubyMnzu zg1wxAHQ(TO<$L~l8#_jECTVxg2h9`BAI&SxH*ZHvf6vMM`DgfDS^O><6WDgZP7BZj z^Z*Wk1KcGUqgAvEa(Ax00+PUZ~zAR(<9=-!B z(us|9qVLMlcUSp4u;hL#e+QOelFK@o_`h3lHprmm*%p(0bl+R~-?O&*g`Rw0p6Ezp zewHa2xSx>>sbDRq_XUyP`$%N(i=A{&(5A`=(ti*4XJOGcq_`IR0ja3$9nZ1P-;t+tNS#~ioKxqb zo}ba!oXlNyPOJTE8+!%p=gbqG=hOct^MBtjDdTe(!9Ir(>~ola>(OyT^H5`5Mt@e< zsoT;rXxX&P)W>9Bw&^3^bsP0Drm@f>s;G{>f<|zrN7iKOLvz>cQKdi z-Ne}tTfFU}_-UADtW0k^%h=mau(zFH`cpDD_O_Gf-gbiN`wb~hC*xo|1qnx;Fadn@b(KY5WLUgIpNLsj1_#q=!)U%AGz0ohbOHYNwb-zc^Cx+L7m)l^^{m zI-GjeDD%OC_XvKy>r^wpX(PexJ36*&%=+dZ_*Aaw)BCbuQVaXIVCE_NFzd?4L&2H$ zDQ=&CynO@4-tK}u9|U`z7%t=aBiQpwu;-g#&qKkUpMpJa1$#aV_B2b>Yqxg&WNAW4|kAl5FiVu2!6yNmz7$|=f?EO)E-20YU7kA-S{4AuA;s`1gP@zJXB(W>#$s`1gP@zJXB(T<;UvwV*N*^!@1 zzsQbUUNG5_>k&+L^`-S!w?MK?bwBJ#G?XrjZE@YYg zbLopOFWA>3*w-(8^z91v@(A{F3ik2~_Wcs<`zzS%L9o}4V6Qj9I=*>-l;_?bMK{mY>&Bp;*ON(xp6da;W=|O zpP?eWUn^xeHu1cNKgY3&ehKE-6wS{$Hu1cN%P=pgZRs;}m)nS*a~q7gJpJN-GPmb8 z7<2u;4O#Q@@sIyx{AXk>iQC|ZuI}lAnLp}zaxI2sRP`kHT)9uGUCV87ovZ^TXL2ou zbw=|!T0h{Q>B+Siey;Su_3%HbN9m2*mFN77+u$k&?u(_NYU{*z1G5lrzs zAnpjJcpeaU1XDZ@h&zHQo@@S?v8U9K=ihb8GhLqiLTq%|_yOjJ<#!4m_V{RX!~3~{ zE8jiUEPLp^r0wXr*o&W2dBI$s>JiNKQ2mBG!u4~^V@$j?luHWc`5onwf_Z*Nxujs8 z-%&0pnCEwtOA6-s9p#dOd45N8JHb4^qg+xj&+jOg6wLEG)vi_YSS6=b@>|s}vgzJQ zn<_nUdC>{=m+KKs{pI?t@9$Ras{UHl-%#~8RQ)Yf{Y|L;2CBb->aS7#-Ad1@zgyWw z^_T4{_F_BMS-5|4Tv7eqiVv#4Tk%K5C8Oe!QE@3yaVb!7iQ4ykX5}f&{=-k$mz6K1 zEf&!@wt(wLEXox2l&W?;#TnbfO3RPSRRa|0!5gB+~(|)A*ww2#0ep>oY z!icw9`LE*nR{pO1LfT~eGYdGjM&ks>?Py$~Kc#KW-py;cHU4q!UYz$;VfQvJ-aWO; zCxvqcJN(*_PZs|4fy00M{PMyl$GA9H^Wv(7HUI9guBY`8Eee}h_k789cN9L++~IT2 zd%dvx0$0zB$3H8aa)!hDvzhJtmhb7Kep~9ltP@bbE%je8_1jYa1yjE*^h`<-NS7pJ_9BnEif2`0NH_lvx( z<+jMcrFRn{nhPi?Cmb~c)JVsb{FjJF4)^$u(!KlZ+F4o?t;DD1?zS* z*>|l6jhXM%|3da7<~#LYF!P=IFPQmG{TIx9r~V6OzEl4NGvEK8y|;kNs@e9(!N3j- z3~WJEFc1_Ko*BEl6%e}%5tFbB3%gtFZsnP=#lpZ2jMv8QK>V+@W$$6Nt1`o+;9cE32f#=Xf` zxDFy8$7}I7{$J_&ukY>X{d}|St74XX)8={7qs{Y#wRxVfHqR5*=6S+;o!UH4?bWJ3Z?zmYFge1Amyr+u4mqHr z{D03W(T;xye;Z>o<`p9cj2tj>;Qt~A^xsFpcZt95Piyy0EZq0k{cQbrX!`Hg^xwJZ zzl+mbeTQB~f304p zzAwEEdfT)ylKt8k3IBsJ(s#&upXhz1_o3dmnmrPJ<9P_YhecQ)BRCHM_sdk>Ks(;2 zu*mU$J`E`#*8zZ%Y4}aa$0pI?**8@Js&q)S+ z`Rm>g`0Up`Bg_}L2MOQv{u-ktb|_C+(<4zv(@$9ImoR+v%jcS%)UJ<_QFs6R=cxW} zZn4DfpMGD!sJmaW!#w9$3r5|k`N3H4)EPlzy{kcWp{)gk^=p=XEz_@YdaRexU#r)d zT;MeLqCgm;bpY?^4- zT$FR^&m;29VbSX=i@=}&UgXFVmb5&dnE$a3AGIY9zp?SXd4ZoBpM0S*Z?PrH{CIqN z9#pdxpIfDbx$Wl|w!y16_gweBc=w3DtXisJeDrmP5*B=8;{cJi)KK25;0*Io(Ot~# zFqB^t+e|m}wH3n$59A>$1~cCxHAUjAZhT;mlgz83n@F3gC7)A24gXLni)d1w@x0Sq z_+Ea;yl8I`-gjGd9zTDs*|TCwUf$N1_aBzqT<`lKHsWO;u=5{}{r}Y-5|sjN7GSgd z`f$681>?9*+#6$l#KR?y*SI2&z0TY%SIpnUMQ_`m-S6pBacgj_7#p}ZDq_5Y zWyI^A4A15q|JhTfsTjauK9Eb+ww4w5HDqvaRN5S2()6V~!*f>ivKEpTx8L7^*6c<(;PXE#y&r;`cS+Mk;?I@dk6YPHtRpxvy=GmtmqIWEw{ zK#y6|&q2S?`sL6socr|(QgQkc4 zqvs(eT;afDdg=<*Zm&XS*4cb5G8mFN2W z*Vl!}SkJgi%`lTGRN^7^|=dU`|^jPxqS6yrUTJrPPJfNQ+^z#OuPUoZMP($^Q(UBIf^YwrzU^bRXaJ?iUJ(_@)We$}-;Pc(Zh^U1II zK|gQc84^pp^w@~wuXO?EPs)>jbHhyyi*$8mGrb9FtcZjd?P8&6D~yPLGW^Ca*Xe^JMaxC-rNb9vg8? zUU4+$$>cRp>eo0uHsYAP;%Lm1$!ng}uW@>8#4&lr(U>Qb*F33T9G;V zI3}++8uMiGnkV&ZoE{r-OkQy`=E>wWPwLk=JvQQ)yy9rglgVqI)UR=RY{W5n#nG52 zlh-_{U*q)Hh-31KqcKk=uX$3x#_6#U$K(}9W1dW2^Q3-_(_z{mk32aFsr za=^#|BL|XY4$$9y)?#O1aD?UWUmHGAe-qsBgW(4w2aFsra=^#|BL|EeFmk}i0V4;D z958ag$N?hz{mk32aFsra^PPx2ZpT~Dn0G`ikQ5eOx9o{j{ll*G~!~!#mE68 z2aFsra=^#|BL|EeFmk}i0V4;D958ag$N?hz{mk32aFsra^Szn0ps01;2`52 zN5=b|j2tj>z{mk32aFsra=^#|BL|EeFmk}i0V4;D958ag$N?hz{mk32a-z; z;5+-lR)OFD|FbbXJHX*N0tU|!n61H+Ge;B$8zlPf&%oB$@NX#d-+I;q{PS-mZ(}o3 zHjQv7ad}aeb$=Gd+DlmMxW+GEh`fBko$cm%*6f%*K-S2=l?7MMw&vPSe+eQy=BVA8 zP{$hb;8Z8Rv*)YT@LR(Fxo@VJ)$q9lIi9e1(Q3F(!1X-;!xpPSp8&o5j@$KB@HbXK zZX{nH!hSUUPWW5v*9kw@>~Y5HG&`M9pJu-^_ERh>vKWlZ z(k@_J7I^{Va@O=n7?-oAU&6R7{Yn^@#U2Uca?~}TTgMLPPEdED3Epb8n*I+;3$2AzQzsGQ`5l59L z|MGFfyu^563=M4f!N`GsZVo_Q(cgkXziR8kpEm!)d<^TvND1p&`oCiShjlFq#${O- z{#vL><|W1p^Txo2AB-IM z=jH&eGpG^$3hUZ$wqLtw?ALyaefRGdN2oVrzh>-JjU4!sa)9<3YF+yc_iGo8{hIoo z_MiH_>tDa`{{7-;@biBzKR5ho_*0()mi-!f1@~+C8^0sO`)i2t9+7t62mg!r)2JQq z3E>YmYHfs37O%l})PcGXTXZAFKJoiHMA(k^tq^N{a>S?y@24R~{qRE=`-IO3!$%VD zub~X~3AzZYKGpZD_?fPq?&E3lOs9wL<6%4Ysp}W@kxrD=*-7{DP~M^&F>(amcv0Ts z2h<@^0`=e+5aXCM-%-Et8MVVlT<3qh4@vFHXKH_q*S8Y{xeI z4Dsnx&Efklb&Ve9o!Nxi>o{g#oh4Om!Y+4btWNCdMfmioxYZ_85yIn(q+NqQs0Z8d zGsGy1*C0k6s0*>ujlGYQ*eA5p_s`f4@`O-u%p+2gFU(^+S~bM)yFnY3|XyJfs6PZ;~u`3Lo{ z(Z=PBV?&I6;+U15IJA>6_Nja~QevOh#CKdm56Xd~wVlMv8s#Vl+=hNPXa0DIa-c}= ziRS0LJ;_{)Ss|+AElDyiQA0$*0{ckjik+R99@l_m+K+i50*~b*nfIx7i}YL9lT6On z)y20`PKoJ3jt49BBnUkH@JKCus! z!9KAMl)*mHR+K^8(N>f}+tF5(LECZ6D1$!0F{2Fn0LP3n=mX3Nl)?WaMj8A;jBWTC z=wUiNCY>IWMGx3RGMYUMWi)#j$|zsHAQ^33B%_UsWN=*IAC7%#{vjF7KO}?xfzL=r z^E1c3G(VFJ`V#se87*EUqs5D4(3fB<$!KvW87=N4gT4gck&KoN@2 zKMZ_FGTeQ zXUQK9zO&>Ht#252=$pqCw0A*!;D=w&v7{Ky^d;sf>e2j6GU!Xpbv3RR7%!61 z;zcs(ORO1`L0@9cpdR$4s+m4m(@ZyyVg8T|`cgNKnQ*==bTfW3&iA+`Udel~D6Y4- zRytR&i05C3tDN0B9@Z7bRXP;gjOS&Ds}yJ#i|2H(_T|w!&+wcMah142Kb%kp>iW7W z73qe(+nTdm?VPbsJ;q$OwBvegkwII1T(}MqhkpVqz8R!(T_g0^ou^V*n>WWagm)`yvTm^Y0Hn- zrr^0Gt^H4nBiQ_x#_Lp*<{7ic#YFwt@yZ@o$K@}K7v_*nrC|$Q=6frS9cEWX97`Wa z?L~q%iOYxE6W-f6QA9kiNqBWY5t*Zk3*odEs>%`TQxYyQ#aEu}x{v0>!k7BV2@Z7# z@6S3yu6upP2m9KV5H7de%t`BaAPbd+yDlf}l0QiHcX~_M`Eo}&plg1K@==fK%HwlQ zgukVBlj}X&5U${mPA&*iYkvvvVYkvPYPIdm> z;|RI>+s6^-nty{hVy^z?^XgR0Raz@y?f6~i)qjIHW{S#WR&iYMx(FMQE{I}U;r4Pi z)2TDz#x5_I&ESTF6Zhoi9uegTyA1Z?hq7lUJa1xC9=HE4@i9}4Zv5o@S%j|_4(5-0 zrXf7=P$(ZYF`jtc#V6r>Rx2iOK6o-|1g~nlg>bo}19+)yRSD1RF@jealN$K3jZLXL z;rwaMB;YPKHZM|z@wL^ak6f z(H4dH&1UTgkJ^%&yHDy#c+J6!?8~P?gadcYW~ciopV&?+$XYtUkscfawqu{#eJHx8r`>O&K9w)ZQ=gzqqP*o^9OC#EHC%MQ~R=Pso9~&o`gF&T=Y5fz=JS5 zx5B*rQ)$Av_f--{n-(Kn=-D(;tXf{e&jQV&Q;7_OV%&ly)z+x z8(fZmXrICdajF#MdDniINIp*<51!{oYtmWqq#K{mK*g?Ifp4bZwQ9VTM+UMKZ}O9! z0Z+EEeXbb^J2^aJNvYn@wfV-S;oGVlCmeG+7q7K=HsM=Yoq6HWCc-Osm*x-i&!T=k zb9(X~YdP80X_+U_-#-IG+m^0y=jq;@C;8lEa_|o3?}R(&PQhPp%u4-wFS@}hJ}XE# zY5jUOvVtq&2@bu9BcmSpk%{;3kp7eR%gO62+L8Vrk#2H8@<;G`59X#ISuIS!8KVheAJH@lD#R>OqJw`0(S(fnJCPl=?9-f5VH}o~9 z+NN;kT4hWXn!8i`j!E`xP@t;);JZO=w5bra@9njY6|%`rxP8qyHY96G!n5~%WkFN! zlRcRhWa7==?<2fzi6b9hY%1ZK+lz4rXGS=3LutNdy`b?<3-sU%_QdW-``^M(l$#`< zcj)iIYe^r0?H7-f<}2JH2xrab!VfInLb%n;0>nE|27crO$KIqr8~C_;`*_0RZe*6Z zB65+PQM%i zOC@&PC?V1ILfwapdpFfR@nU;-i7$RsYjR4)Ct}N?1RSq)@0d=uO?`my`}&UZ@rTib zGaoH3uhz;+cxPvKc`WU&Xq2Dv%2UpXJBc>Sb#*=D;32*Yar#kivaWv=;qViM@J3%1OBA$Fr>4Xv}C(3;tJ(R-Bh za&XBa+_bwfwFmSp#ho@)q_J$yaZ@Jb9~Gxv1arDct$a zJv2wjbR%8)%p(h^{n`DZd}NNnq;mr+$>)wsOZe<@cYgFjH0f;q!jrc-yOVTwS?a+L zm#ItFR(x2B&#S+Kg}!(zxc;e8rC6%T0Jx{9(54rW0Y;DRbD8 zouvrZJX4=dFGh2?{1|cG^a#d;<6?cMSFTuIwQuu1Yd*3`$*(EiK-dmadX_evC!TN0 zrSva8E=o*GLwL%Y*P_b~T0^D%=Jayxsc5q8KyY4pzTp(Yk#~#9QR~VQo;9V6e12{M z`7^qrr#yPH6peTAc25~$&dboAfU9L?r-@?}jw&vD$L=9Kn&*=~?;a_9F@rpREe%Kc z-F07!SMBl;&hC3iWPM$XaEeq@#NeVdkI6T-E+TlT%C|A&tC-U`DBS4IOjCy*D))9i zsmdBe6{TzU%Y|&(NtJswo19_uv)WO6sT%Lui_}lZhP?q9_=#)L%Fe*NJUn(5VLR^3 zuZ&wJ(6-0nMPwRJm3uMseu~+Lib!nt3SBA+Z%{s8du^L}q@$|w{d;q=mA;N7^ZLSm zb}Hf->6zO!J@GKO7VOw9W{oP2GJIr>vBF_QS;EZ=78U_x)OwvNu#H)VO*$E-yVi29 z26eK@6O>MeVq?Xs31ko79Fj?#`>J#n$`ck{t`XVHbH|=AoeQNr;d56tVv*aN$%eVH zk>~@^SDqg`JZBAZFT}`YbbRk`c%zQ*Aupoq6<7KX{;A`8$cr#%h!@qKKkOGT((@%f zkJ9riJ@3-)%eufxjb^f=Uqx+>BW$ZSeT&-kP>;OyE zUfWqW-am!kCVE}AjQ4Nis~a!a@@u>j$A-3{k9Fhyo4nGE_aE*@aJ;(w#5j_#v^WyR zK6Uyrj+TDm^I!JR-T>`E9lHF48p!F4?f9dQFZ3ZS@}P&X7DvL^Cyotev^WyRKA{i7 zXs0eNy6-$Q(fKO;&dhSA3$f))7h?GLzdDz$&PAh|zwTT*oK>SUbJ#25-e1(&m1^F@ zd^X-!_@2jCpQ8sA-g2k1Nsle(aQ^?U)yr5g_J?Q5@HhDLPkDX;&*7nd>=R>#2>ZmC zA;$A=@Qe5>o`b`4c-W5Tlc+UU7_51>y%cHYosOQhh6ZL*D?BTD=6YOonSCs>8 z&UTJ2^Fzy%_*~Hqek!~KsC_VdQs&hTQQNJwdX|Svke>}^L@Y0+n zKIL?A!uN(&;nv9XKmS#rr#=J+a6NYWo{scfTG5(s+mxE{=jQGB{wB7B^Strn*2qN0 zr6>7A4z0N!yLHS(?QI4&;+w0evw3NHHs!7Cvrzl|dM&s$GLur&Ci$Of3UfVfV`@U} z4WH!TEtxtKc+55rUtY2vwV%tFpIaj{^^($aJZBEB$J?v7B|SsCrr|dxwjw-uO9tLy zUvt6%&$4i9WK!C>ll-LsuV? z_ij;&>v8K2wWxi~`NF(Pq3VR&>~-cN&T_)7rj_8<$W;DxoAT$}t8QG6?`Qf#?Wx`e z@YwvX3E%MV#FyrLO!(IJF5DWKDwQP3FC5mF>+xRaTh#9B-<`{Zi-bFe_2f$y#}K|d zp*Oci#$~TMzq&X}5ZB`QAbN3G9*2r|8K8obCZXCk@ z2FEU?_PYT=ykGt~gi}5l#QXb45DsoRn0K~9rs%QiB=1#w1lQvmmBXohL&6ZgJ-j#J z)=3Xe*1;e0xrGDi7cZ^F5iGA5KqJs|%JLtoz5j{Sm8AH=8=`XU+Z%NiLN zBgvy5^cZ|a?dUh~31RdJ_=+(4${HDn5kuP^K^*lMVomKBcZexrj48yLFvi*%8OSk` z$2`~`yoH=3j5!IpN*Ht18X2e&lE*sw8$5j!wPW2uO%cYLf?6YtwFdS0U&=s@ zlMK!SdJJ;~wd1@2a{^(U6JV|&jB|xGGB8JxJkDc!409c|DUGBauAvC_M(QMeWGDfKw4hP6b?x zFmf$xWPsz5Jn}$22ChhXg1iwpA;};o1g=OJxuP{Pz)?vad8{4-*QIvky})S+Bc}zf zOBlJXH8Q}lNgjE)9s^gWcI55A$q6GT2d+*Sxw5jvqmQGx*l|`%c3hxkEi{i`rYvS4J+Z(g=9=mp0Goq-3a$P z8_%qfY4E8Z$^Tftm+A4xZ0hWv`^h*~x^QojsT^{eZO_%0@b!F$nKd#c8x11)k>BSt zJ6?K$c*2r&S$QAQO~5uErzRp z2ix2=75J`jp=oH+y*82TcN{en)ys1y1kjD1-n zb1`=X@@K!-9#W5;>|Lq-To985E|ezhklI@g2`xu>%os0ejZBDBRg%wUS6u3G)pM%f zd=)+9%x0BIruDQkGWT&4;rL6g(i)ktoB2t;^yIoyk9W?tr}qA{nn{m?ISH3t(^xLN zl!vg*$_COJnE_2pl6;ebT!HO6Cl0PAt&v$)tSiZ9 zss2#tarzJb)Sj>KPw{R*2f`m~d=izesb^rnHhw9rk?9+x^fc>lBlWm{ua=~9TBl6% zN2xZ1OB75e#jSRPU!O}Qt&z#nvp&g>>hCD^`1M&8_f6GZ-EE_Xr=$&`nw+ zliK$z$xqzhOX~5%%-g7aUgrUF#f<%gedhO*>wX>~d~sJFX^qSfSM}^n~Hck~`A zuZNE#oYr}Wv__`HssNJzc5#^0<1{CWQhVE7A+mO?7vXu=M#!Wi^$GXCKU`WPlkt2( zl25uFBK7#urV}*JKRz8Mk2t(0e4mHOYP&L!e5FO9(i)jXFBM-Z6MaJH@s0UvUdliC zftYf(JLSB&;SCZ0RPnJvSuO}`WV#$yd?~2MI-$pjP5O||&G(N9&q|8RjT?MWbW1mY z+JnDr7uLvpUZnU^{_c~69*@hZI9t8ZQKJ5~Akvv7ez6EE7fjf;m7s zf9rq2TjZat_?Y>ui?Bv!nv3F2T^dK3^|-(g)$ew57V)%@;#40?e>P{|uJD3Wv1V&z z=6+QAJ7k<0t;cV@ReR{8Yz*VRnc?)n7 z!pKR0s}M%6VvP)N43bA4qQ}5hs2zC=a1z4ENr0;mMy_Iw3~&sRM;@Zbz*VRnc?)n7 z!pKR0s}M%6VvP)N43bA4qQ}5hs2zC=a1z4ENr0;mMy_Iw3~&sRM;@Zbz*VRnc?)n7 z!pKR0s}M%6VvP)N43bA4qQ}5hs2zC=a1z4ENr0;mMy_Iw3~&sRM;@Zbz*VRnc?)n7 z!pKR0s}M%6VvP)N43bA4qQ}5hs2zC=a1z4ENr0;mMy_Iw3~&sRM;@Zbz*VRnc?)n7 z!pKR0s}M%6VvP)N3})dWdJJ5J^dN5mPC_!sNr0;mMy_Iw3~&sRM;@Zbz*VRnc?)n7 z!pKR0s}M%6VvP)N43bA4qQ}5hs2zC=a1z4ENr0;mMy_Iw3~&sRM;@Zbz*VRnc?)n7 z!pKR0s}M%6VvP)N43bA4qQ}5hs2zC=a1z4ENr0;mMy_Iw3~&sRM;@Zbz*VRnc?)n7 z!pKR0s}M%6VvP)N3=`%L@(?`+u0nc{w*V(0jGP3x3dti^u|@_s2IV305IqL2LhZ;~ zfRhkLP6AwoFme@ZWPoFkJn|4d2ChQw$XkGu5JpY{T!k=l6>DUGV~{-Z5IqL2LhZ;~ zfRhkLP6AwoFme@ZWPoFkJn|4d2ChQw$XkGu5JpY{T!k=l6>DUGV~{-Z5IqL2LhZ;~ zfRhkLP6AwoFme@ZWPoFkJn|4d2ChQw$XkGu5JpY{T!k=l6>DUGV~{-Z5IqL2LhZ;~ zfRhkLP6AwoFme@ZWZ(=Q$!q8Fe&O=ZReS0xaX#0R6dr3n;tl7rNCwYt>GA(d{;xcj zWt`Ld=e=hb&tY0(r^h%~{@Lg2j5z-9;|OPy=^Qe~OLq?WPdOhB&p%qurvGK8#IXkPJl)b)`Z(&;o@*nF&oJraEzgmm z9?SDksNeEDl=ckPFMBM{L!q4 zeszAfJP(EAvOEv<%V*e^_FNnGX~a%F8k{j;qzAT>#xK# zA8P&ng?J?O71MDdy{jF^{?}j|%NX(ZUx_7-5!V;^^;cr(PWc-9|DR&rv!${@>+7_4 zc#&96vI#wC@6e^6tMtpG-hJ_XPXU>$Z9KKly_H%19Fdad;H+1_2-olSg#B_{#ph=U z;~cE5M;zB9ZGOh*TjBFx&#TfJgL65~&D#9TajnzV9gecgLo&hd^885LeGzr$6|P^r zQkJxm-#kcop2#a3R-Z_??QR$8m8Ll1SJ}(TvKyDsv);qrddM!p?QrctUGl{7Vo*}$_Mo#IPa|z+Yxr)j+eOeNB`Q|2bUcE*-{eG6iwUcZEJMsB< z!tne%gXiA~!}IS9o_{9{&%gV?^Y4V=`FArs|4ta5e;4rlyTY-Ne=~M%4W;!^TXQYz zA<4tqq<<$8atUfjf5UrzEYG%ch%ea;@#PR-8VkgiLwpHCd^yCIFvOQbd`S<)mqC09 zLwqgkIQ)M%)A@nx{KIvA<2rwGou9eR|EN={xa?*SYr+s~2C)`etU1J*FvOZetO-M` zImDVU#F|5_DTg7}@E)femgm7Kw@{D9H%MM_oL_l}{-t(}Z;&4J_y4B8jBEe*bClsj z!-rZ9(E4iNk%k{A2@F3NwP56ckpo5!7&-8Nn*(Xcg-6W%i~9Y6F*oxO>kae}RDrp}f) zwe7*Kk5*?J&Zi1B9a*W)X=ErCXU?`$ol&`bXridFP@T_7>2y=H{;JN!EgqOnUcRr+ zVdgLDA$PuWpuXIWHj=Il9+GXoPF>~2h*^Zs6b+X5PyC>BL{II)WTVr?==}4VQ{nP$ z_htgeyKK^M>0daS@c3N)&m=uh0KIU+-bo#oV`GH?h-xukEfx8+t?1}Df?`saoNG& za7gFBmd1O|DV!H~31K)Ey8=UbnGfd)zk1b^dtJ!Hv3*71mi$u5GK8JBRp#p_)h8TV z!;yEGr_O2)t^SI=3|422-q%{nPSjH8a1MXT!P2}}alD+gGCJ*Ib)IL(6(7;kQJsUD zJ8!!vzk$A2ve}x|Mjk1v&P>`@Eh_D{xlmsf`d5|D8>J>(Yic_=JdJuz|LwEB@>2a4 zWV7Rd;d1ZLQZz1)3|k|Rt`Su&ISFur!M%+v1=!jpWv%Bpi6B#v>iU1Qm8 zZUw?g{XJxX9Zd<3zn)Fb?5fVIr$~8Am}d^A_B!h)i7E5K2=^L!)m(0}iesq}!KT=L z!>IjqP&anoS)EHCvh6sVTtGb+Gtw&^e>a$s%&JVTyv&w@g!|;K!>6QE?@{sk5Wttj zts^^kZVBZ4LrKC_dxY>AsqN?;7kA)Y6T7OoFtk5mdI+E6u$J(b?{LcaZxd%CT|N&B~-?{7oynRJ{K+zPi-R5{%$LW%bk@E68==9pKKqd zYVchKUpXPOs=-6ws>(f!R1FUNP*fH#rE0MBQyaPLxT?W{U3QAifvN@zx2Ph@zEZK< z`AtM;=&fqdoYkH^Jfv#y{b#%YC#O?A($MjZtUOeKLCU?_AYj`8AIGN(WVgqqDtcx0|RMY*ca?%kQab(B`cJ zYonb{o3VFR^n`7y26qB9hYA|<$pQ6@CRfAXW6_KS=6sOq5yHu4| zcB&ej*SMYZeW7ZwU36a=T)q|ApT5;_d8exR^P9Vp4`+ZUpk zx}B=ckH)JS%(y>*Pu{(r>?}MXkgwk2Mz~)~sKJ_}sRlJzeD6u5-xF&$kB20&7wb?*BAYUKy2#V)qH2v51h31m=H>1H)yt z76%AB4(unRv#T0x)WBDMI#7&!IKNsoxxb~VLGLXi* z)!>3+)x=8pJEN%oL&dYvULmRmCzi^>7C%-s_<8ao)|IImym2&voo=RT@UVAY?&npO zu9Z6~@k@4D2ybrMg3ld)iR>Kj+mrk48A-V9$sycyYzK|&R_bt`o-dWcpQ^$5D_h0uqU}j%@!?70+eKA_ zk)cIoi8iVR-`}nxmpj;z%;#+FWcKrdY<@qjul!oD4dJcc!{w{3-ZZWf@P5aN;qPg@ zPG!R6z7sRZ58bB*%OTtE6E>adDj!|SDREr6XE&CwZB-4N6O7aSUss>Ai)aGmVd?nlNg#_^93pWrJ?F0FqPNfNNtro%^)|;sYpTK$8 zd+pS@^!@unc-N+D7>>nUcOc&z`+;zUYaMt#XH|nyjqCE^g;WjNOmyShimDnME7SAW zy;Th^DtL+|{#0k1^ThRK<9n*u_1iVs6mUY-V7h`a=J#2KP%Nf9ju*!~R1KDzbxpWm zP&K&0$6ijmw+%4>Cs2W_Ix`ufERK>1bpBvHBrl=a+;hTxo%s7bje_gVWl^vpL zu=CUBEOL&j!J>cU;XxBr4KD3giMQ*gYVb^k7W_)LII{Cn@t%Cz@==5@t{cMBCGDnh z9Y_r0HQO$tTrFEYoWD%0$8d~86NdAhTUQZYFk>L^Hrujx^}H3+j@rVyb<3^ zo_RBn@Uv}0<%UnQX?DzQ|_`7>w<`JGTco2Wr=_%nI`MPj^ zBsWKy<$W9Si*qUxj_&Br@78Zlc;v*a{6wUx@#cwF*yH-D_V>0Q%Ld+6b3)P=X|ivp z;@ELbq*wsyn*6tmfnQz&z=?&m$V|hd0GbfZJZC`V`WRpvhdD&w4q!~UD?g^ zJ=xZ`R!3r61ez48UcE_2;5?&#lua<$`@aNd2pFGKs^ryI@# z`W+(d?A@2YyP(#@uglu zkk9RxmS;XNr=b4Zb8Gs9+J+L&Up${MJyJEeXwM2!G+NbQ-LSVJeQQ;NGve~eJm*vm zKK$q{7y7Da=nm#;B^S?B&yMxo+)L&@KZtCeH*2VD++aS9YjVAC>9ThpjrY-qFqtoO zH2L9H#1LsRT_)`KrHAZ)R?VyF&Ni1R52^WfXW2?J?5diFH%-YS=WkXuSUTr((X@=J zLEA$M#E$tIr}~jWba<@dm_OSiA8$8RgXI%yvV}EO4VK8Thq;eXHMlNU3cl-_s=6l_c@ZD#?|R2#BPlpL*ITs z5z4>jRyF9pU=Tk#^$E4dH|xTm`>Gn8xxXP#TUFKIx&7|^NJdqI3m#_W6$4ZaMqazh zKD(+K9MoVOTM?&fu;i_yroA0i95Yv)X0H59)nJCk{l)q!ss;}~J0;fLS2eiZIfMLg zLDgWYyKZvkeN}_2#@3a`GAaJBJVQs>Veo3QGpXM|`N!bGgiD+ak)t|2B_7f)DO{d< zR7T(!|8NhHdxvZ!JkKjoUZ3!daMNl5a&NTaIljEMe8yA_ekfH^#@=j0{;ZHGt?aQ~ z)nNIoM@4n1YH-7w4r0?H6}!UIJDK|oQZ?wc<({c&8O6s^^qRsZoKiJ-I`R%ne6MP7 z_T%jQVzjEkb`3oFlisQZYsWX{#h<7ejQ!S?*ZQGqFvZ4T{%O)1id~P&VLZUL2IcCD zUEzGj)3!ABS4D>NVY4LRKHdBBeZ5o-y4`Kdvqu-F+LYM-^xbZR5f^Ynit!yJ=65Fb!VRf*;Ea#9Gq8#Wl+32%Z25_^hwp=l+|xU z7$8Pp@h)Y28AxZ<4CP)SEMjanDp7hfTfe6R2^pEI+EVs{>RGdb#Xo1NW#JwA*RR z^AuKGF5?6z-lVIl!EX`O`1(z%2CGi?<&mQmC;YOoA79e2p};(Bc5XOt^j2}m3s=H< z&Mk^tPPrD!dsS4N^XS1r-1ng3qIo8E;rBi%j>=Ot;w>M0Q5;w2D#u@*QJnTxHG9rV zsT!=Y^%`rFQPp693gcP%ld1+E-#lrWq;cl^J0_dGQVkp z_SVtq<(`5j!dEA{$;lN85dKiLt}OOY)nJE<9psV@irYKY9w_fB4UN6LFI1k^a_JAR?`tn?9R1J>J*N&&s_KZ31RN+0YslDWf!9{rP{Hg}i z&P-yvdZ-%w@NO&ndQ{b5{o$3^MQyL@H*}QG-6E<6-$dsYZ_BD0{QP2>7*M7Y#i-J` z*W&JLRf7vN<&zcrsv2z7(ObF|PUWD!bVF z_o@b0)wAU*JF6O8=;g#49#b_qyK*&NEFu%>AK$no_bpq9Y<9j8!iRgQcRmLW4dQ`; zPpREDPZyqhm;=e19UJq#K0QUL+WtK4e(^yeXWn~2b(H-vk6e_r+cB++#0 zQ4#6o&*ho5qW9GGq6&w8A08H^H%u16-u^tczzq?U)JPmH>(5#C7a~JMDiPu8&zrb? z6<=y}Fb{U~hxgjTclZgbeI|JL^IJ!3WUi_wOwB$0x!co3v39fv>*(Uo_Z)jG+LRAt z8w>gKa^d&H>mAG4Pr&m0DN*yGnT;>*&wYn&5jSgJW9}vVd6xH6#l>nb;O|fS^KpwC zi!-&pv6I>Td3~oJX8$EN{7Vjh9+sz+`PyO|zN>&gKfADyX^7J|HX^q_-|3xXif@#_ zGNqF29v{udruFBE<+riHMOLwg+5CCGTrq6w=&`J627kU} z%N^D^M-6r@(T~4#dd&vjOUa@?`tbc6y&S%s>MpJ=juneR=eoHIL{qyR z!o7(W8v)}Q-200dy2F=E2l-w%o{Fq}X0sH~S8M-E;>hIPOoIIZ zefEg+B`&f~&HZ`K8*{|QrcYUgdj8!0n7`QM{Dr-TT4>iGoj9AzhL?o)liWG8iM%#>ildOdBJEF*0q8493W`F)|pVNgE@BF`Be7 zau}mo8zYA?3T=!G#wfHgG8m)K#>ildLK`E4F$!&r48|z5F)|pV(8kDMj8Yq;3C1Y3 zF&;GHNV#gn(WpnG9*ud`m{*PU@!xKJ+&b1q<^cYdF8HR;rp-1o5AdIfRh}I<(bq=q zY39$je|;a_dCzz81Gs&G%r{MkO1&1HfvbNT$l2JlH-+%==a)WDU{SM=h$F!Hmpod> zQu(eInO*#O{_rEr#3Dq~JpQ~`{Tpmq>n38iJ#abi7i`#R8&L%KaL!cUShmZa=HkGg zo363p^&N-%?0E0TgS>5dow%i@pnHCN;fbHjWAQ3;V3Hr7T>2*)8#C;H=W{_0c7g-{>kj>lwi3Z_;H81AJ_xi5p2?HKfccS0Xq=9f|dL1$Gaz-V(yzHyY~pb z*T24**}cBOM&9+~iJKzW*)gwJerQi|v<`b~pUBPt4`1T?*pxb}Ek6Q(iy(gq8&lRJ zHhekgpB3B4ydd%``vTWKZI@15e*cVBdgjObzVQ>)?Bm#d;PZD}=ZNgZ_p{0gethSK zU81Vz0yY}#{IL9j81LVmExzx^+rr=DzMYVr`Mv@>Z+;fz`wug%{Nl%FH?fhc9G6CK zd+f(o)v=Yl)+O^)=qqdR4>90}NpyP%dxU*&gm111q95!L$`8LSo|aoLQojS8Gmna6 z3r~phfB5mZ*K34Wd{>-+YyCTo7J<{>iMmhyU=QLc`k0bLyYGHH^_T-@*~nJbf8obJ z*7lChTG&S31UsMah%{yI{YjJpJ9l*`z$(3YC@Q@4<0E4Suszw&3CC}K{Fwg|mLhJu znEb?#@BMI)-Rm|(tcAYHUB1emcWf>WfDN}QzhDC{CYtj=OxwzDY(T-1=4OB$Z`tr8 zmx`FKf=rg5Hax}JMAHhmcCOubHl=4X))jO{c6q_3^_szMe)Z#*yIy7IPi|w~!G>*@ zqgm4$=NJRqUanulG9)}?r@>~=`GIUm@lPxtjAcpsf-G&qPqqlgn5$r<=}{Y79tdMk zJt1>+>B&hf7W$e{AljVf>^tTNHoPzIA)1EXWwCGl_}BcSMcvnMUJ!iiRceixkZ%JU z3qBu{>ZnMlIe|@vYyGz07KyJIn*uSqIr5E2+2*3DGsI4m{2_YB@9>!lG41PVEAN#Z zV%`RJc87C%#rk9ygV4@`UqsK4ZXy%p#=yl-#Aee1;q(LIUg&~oUuvJ|47pTc=Wg+2 zMVzn&`ETjwh?bY1iHVSVb?^C$t@Xc(sgRRzHl`CN=G(}$pZxg#-ObJ6Znn|{IXuGl zmCxdKi6R{AtQqmxw0id|A)vkW>DsL5vK!(f$QPIs!E$vwBm~q*s_UCr#xyHMY0&@m z(kXUt(+J@T{d$ypz%peoDbhi$6>s%{*-u$xE(J9>)bS^4Rpae}0BElRHCW{H8dEip z-xl_h#rPFxDNv92z{V6C&RT)~GMyi=N%>c>0Z@a7%ARIHev+jGzqNq-Be9!quu))V zmK;;qx{@Pv6-LsKGG~Pfa;8+VU?jUiW<|O_xsE@cp3wRnGe6PCLG` zS8(n2K550J63S1MJM!_JSzo z(}PWfxIAp~M3lIbgB6E(Ro?qqRC^p^x({*eP}fGrADSC|8SI=_&sLV}e!)Bg`Z7=b zAu{JQi8^5Cj>m7r@J-`|2jt0+=-Z;j?RCNgHRyEvsCe4&glGbJm8X7`SkV5ikZ|pj zv!g}vF7HGU$iq)5%8M~BNg@yA=k&m6bM}U|ayaB|%z?Vm-AdTV=U`{(<>@B($WOu% z?5sK{KP&J0NZ3LC4|>y|nOmI`zEFcVQY~S(U3Q3VP%raV9b}o#&JdfRuTRsjGUr+? z#4@lUN7@(c&i*9xJ+Q6Pif?R1R4H==)L^QsHoRs2f~NN%6Q0tRH$L^vv>2|Pzws~ z7`<=yMqH^8XL5$v*=GA8@}@uFa|mKO&D~Z$3Jx+K13Np9v60)uvWf0s=cH<1MEs(z z;vVGiwaZULfrs-&52(R<9WRIvH}{GukW1%N?-2*!`}qtY@6mUTa9H+C1VZj@KHOf! zl>92%Ku+#knqEZCw2?KSrY3o|Hm@jSE89b@^;!DZCoVWqgn^ygH$61fdHhN&f%e&d z)M9i0xFPm|{5IDJX0zjvcn3Aobo3@xyUR*Z6Z9{faEj#~7a|Hlzqvo%XOT9pA|C8% zSn312GGeXy8Q57O?N65Fbh(2OVE+N|t84DnrbZxtEAl7n7wE!X!gyCa`M{pl8^(%& z{_y1wSncD>*%qk5C&8!Lyo{1LgWoER-@nFNncTR zRUGq!8eAPPTRe@~&*nfrOiQ^--2AkFEd@K%*iLvI{&{yfGA7YZ5k0=RtF3s^)45>O^e1&`- zmvmcf9=A>eL!O(RkBMhCCqysEEBB}ReUGDLvA;ERbKepCy8rN zN1p?Pxj}tfxdCdhgKL}UrS3NJ8`xR+(^ONoy`MySuyfCZeC%u2N8&2Tl+D(k&0KI! zEQV|EZd}a9hwKp7K&NlBgDk6iq}Ty{O|O5IIhAZF#()hDR}xs-rZ!?7*cLzf8!J-E z-FzHuzI?%kSLoqr$_itNOJmE&C44c>hiltb`_7ImYr^t^PTMmtSp352%olv(`Ti>F zSzsGG1-^Pcz|5{}JIgwQZM}LdWfg}!WE;We_l<(si(4O=1fK^#E5y#6`pF7HEL^9| zHkE|=`Y^=k+|&mLPwq})@z9rZhkfQ{Mc%Wg5YxvU-9>cbUDg3&owMdBkv{AsD*!oA zDQvZv61#yN20LeWKO*Ypn#jh%wKL1!7H)^Du$mB~D^71jsQVSu6UebNUlYYF&%-|N zp$6xcwv~Ag_BY=EJF88$kuH(;q8-?|s_Pd~@L(6Q3vxJBrl(@`2avCFVUAeQ^O;uzwhu0zm+Se!6WLI5oiV?UD9+}Mc{Wv6CK+hz%O|0eN zmBJ77JNTSpY5YS)PU!dS{`>6dOINWI?5UjU0~^_Uy*Uc(T>K%49emd3;9jub9%_(P zT50kH`7^73vajQcv1>5ij9EXj?EQzb*WiZ*cOI}0eU`Hq;Gf$EPP0YPg4F@Py}rGL z-E_G@{*1mqg>`!Ol1cD$<{|Z2P5GVW0skLJNH9HyIl3#vrN`y;Cfhh0{v7P=xTd<9 zzyHeaKrC|3uoFe+JZA#pd#83gaW^53<%PI6`Z`Ob&2xYqg?zZOb*FgPdLi2kcHW3N zFLr+E$vT0Z?e9MpEu;fG4tce?|7Wr1=_peN$hYm4ZREL36QlD(9+n24Xt(~X8S}G? z_#y6A_ZFGJ&c@Z=iso0xi9?Xj?W^1oZ%eNen{gfNe@vX(d0dQx{CBinD-Pd}r@END zVvI=0_)c5~oxwLMi0|Kih`CTltkEHJ@4B|~Ce+uy1>K?#RI-s7z_zQorkM8K{v^JF z%{dl1vhm9wi71fS?a_~wzkN>JforcdTg-l5*ddZYXG+_H?D?EXu^;SAvb)NjWNIaP zfDM1FNMNaI+KK^STg@)t*t;E`<|MFr>KPk;zT+q#T<Sk{g)P0&#SD88xdHAQ zEY5Y+2lgPct+Orf7<2lacp2?jO_aO3l@o%Eyk=D2ek@h@6ylXWR_aO4y=qqC4z@4}Ukt@0!5Tkr!aStNz zu3aQ}*2e<&AhPOz9isMYM2az@1YDOfa2iUONup9z?#*ypzQYzKnYiIn{F(Gkt%~ zU=Jb>&1%Eumi>l%5V`(DD%SXp4Tn95Y&FKmv=#CU_8>CjYI}3-N#Ah~BH8@c<_@!8 z;vPiKE89?PSbH7!ATls&s)#Eha1SDnjovDnA6>>^4`?WPCJZy5P4w2M&Y&LrbzS2PkMZwBwi1E4dtBBRf|W>fD@#65`g z-F1sC8@dtqAacfq!^~tCgL@E}`|2v@HuxTcJ&2q!Xe7HZ=sklyh#auI4BH={gnJNq zA!e892du4Gz;7KwH+b{)KXDHt(_EfsUK#lj_aM?^R}m4A<{|DuWbC^^;#`rlxCfCT z1(u1(5nFK&B6Hdaktc2%gFT4MHT;_R{G<_sJ&5e%_EIcq_0a@-5P4?!cTuoG4ioG_ z36^qGx0)(iI_^8V(>?EbcexCfEl#-C?{I~~A1h`iouCmT}w zGVVd7+oD;l(23^^_8`)ENL#i)>o?qkNXOl&*^g`R9R%2rRJn>Ng^ewTJ%}8iE35c4)WGuVU3FPNLBhMQJROyPbVwpTNI0g~`_Vfy z*G$9*3Adm7P1JLjqpQRR38OA6iO0`|W_;C2v%ZE85;{N9E_tx` z+weg`%a$XPcaMGoK1jGV+?bsH^fdS&;n-PK$$%c0M&g5nH@04o^nLP=k@z6t{%=1@ zF56~NPJEDXn&iDsDruP$A0*tp%5vd?;oDS+4-$TOT+X*!Ee9VYJaYJV$t(go>5^p3HyYN%$b4<-Rv04_*IGB0flXey3xTsW1K~ z5g#P%duQvUg`9=N2MKedaaC8z8A*H)+2aoD`HvrdgbxxHm))Nmz2+D2LBg(&c8^|q zmuIc;&b4PpEoMIgA0*89c2e}a?o;4{gw2LO9IgKPxyi#K^YT4jjh-FSBM~1Y{3ZH4 zYW6hGc;T2iKSp0oI)9G%AfeeVau#~{%$)cjVNj2fc*bq(!UqZ0pRg#p>D}S*LBdDx zyc;e4<8|;s!r!0zM|5_J+3-QaoVsz;p#zhC zoAb;ZhP^m0+32AJK1f*j{GCbrk$;WE2MN7q%ujwO9~FrY5^nz2n@Rh>w2#CG2@kLO zbrKD`B_}>e*kR)0WS=dL{JZ!dVWWMP3#B_wtr8z3bpOv!$@rH#!v_ght@Kqga^PtA zAmQF*Ve-&@x4;Jp(GK&H%NE@aA0&+3`u3#%#xEt}gM|C$Uzj}D;?qQYkT7bEzR8W3 zq;qiPuiva1F20HQAmOLyU!OBid=~LR!VAOq&F!=5x9~y2gwd-+KOXaM_#k1-Wd}wZ zwSE>pNZ4xb)ltVw?}ZN%&f0Zm^wj0oCgOvHOK*5OI`+v!6Y)X9$d%uZ$}5^D;)8_w z2Y(a2xbpE;;)8^HE+~n6-gJLY@j=4#TZmnoKA#gGB((Vchp5|~z2Jj{Ydd}xJ-Rx5 zy6{}LSE9j>-3lKhe0R))Q8el?_#k1wb1S0D7QG&c4-!7!`OIj;wqHi#gM>vRw~AJ{ z=O_3eq0@P@a&2V}iVqS7eEN2eO&?zjA0&)E@~W!UU;i3DNcisgjgl`z-f02MO(8?iTG^_Bwo!Fma2s zqb*l@6h26pd*h^N&bTS?LBa!VAC9^V7@LR>654#?OIo+!viY`AKtskp~^!X$y6`J=)_DhZ)|4Q<~xeH{1WYWKr)Uk~uAghT+e?o6O&HljN4x zL&NKHze+Z)`k-p9(xG8~=kJr-PZ(F#eT$*t{=*h0dmKHx$B>POhFiXoIkDxWTxa3G z)6}1m<0{)mE!qwZP51sfxqs;JXkv$KAPNZXoy~WI=SP*yQ8za3=M6+ zo0VMO?}_NxO^1e^hfYYoEm;`tDY)CGrzM?M`8;YNG^ft%p0xYd_tBf%4GnLMc(Ll~ zF(q-I+|cmi=vAv$xKQ>g;n`%nHFA?T_#yhN>(Fq()-U8fT>N=-qLgpjX{+e|C*O?j z?Kw33buimu0 ztbjbRk*6<8{vqY7jaV(}KlT0Oe4!t6#{SV!&pn$wDR|{Qu80LB1LIAioQ_PeJp$koy!gzYDofLG!zi`xG?43%O50^ShAy6g0mJ zxlcj!yO8@7G`|bEPeJp$koy!gzYDofLG!zi`xG?43%O50^ShAy6g0mJxlcj!yO8@7 zG`|bEPeJp$koy!gzY95Rw3X(tK}Y0wA%_h*A}zvq4jXhteiw4s zpd<3Tki!NYkxzmgHt2}_F66L5N91=QhYdO+zbjH5k>74jXhteiw4spd<3T zki!NYk>7E3Kw?ghEi`Lmn}yDz-2=hIi0#Oumg=udMlpEGju z6Nx;t5ME#T#^}MpGmzJDWH_wy)u zRPel6pGF7VT#{6_8yZfRc=84xom+KTr=j8aTNg*q_4?P}%exN^e|)|qe(s~4a}(qY z{M7m-@yBbvk$ZE;p<&uy-$xG}&?)-9_t5ZY(=VfwZyXkFCFPILc`rI-_+82G#Xq`x z`KsuEl|r(W$o6obJEQbHy8`bLKd0%LWkujpyk}qP zR!ZGk;TI1)EZ(`r=eOLw|655RxCq(udJWoS&+yKn?{7Tg$<;z3xVE}@df^|twra$6 z(M#+WoDFNlUe4O$Uh!qod*elu!t+i(aRU92x$2+Y1$6u5fKs2=;Q;7C+qg$!PD*hn21~_NY(@u8Uq< zAALsXcu_^gCX3(96@qK4i>L3i;k0PAH;*orZ~BBna9#Amce2j<^Nfn;p57`d1baDa zi`##_T-7=kk1bv9^)aCkTo=8rKX0FK-oDK$dwsKFTnMhME}mX=$vM4h#C6f@<4FgF znP2{{@|-6>j|#zF&f4NOkGG4i+4=0!C+40W3c+>JYjEjt;k;+wt(bq`%%~7tTU|VT za{Gh1i%vebG+uBd} z(d&^JW5P;jURlxmogH$8;M(fq>4%mtAJ2QGSLu@#`-MVqUG%zt(U@@8@Utq0e0%1c zLa>*!w)llk&Estk+M;ySE4zh4a9#9zW2-UYtUC^_cyi}kstUoi)y31_7PpDJZ?Jyp zW83!+h2XmA_1U4L!=$@=ReV3Yc~S`Wa@H0Po8BqDW8)^JljlXD5L_3%p19)F@Z8F6 zD;CV!H7NwwRu@md(TUyTv(|lalUJ_XIuwHIqSyY(pTp>zzMt6pxbu@ju$Qy8_^DC7 z;|pGyw8>W$9YP_vE_z-0;h)05J!elGdD7&h5L{bbJpHQo4vdG7KV*|!)7GI7To=8D zw>>&M@X^SLEB)h zczW^u6L$|#Bd&{HD@@%otp7}DPldRTkyUJ_tIWR5+dtDj=i!UJW^vwGO zHR3{atd3^w)n7^e`c==$uI-PA3&C~KSA2os{DK;Bbut%He$jv=S#VIV%5$e46BmN( zqL=sr!TAL>;zH!Fj^@P&Z%Q`ZWyi`_wmmT}1lL6`@dbkO3u?sG$y`YJsPW~=l{0s$ zJpJ*L<3ey<^b%hnIKQAqT!{SD(X9P=@8r5``&Hg~;AwFoxGs8$FA$txP$RBR=0eIx z-n?A0^A~@py#KS&aUr-adKD7S@-&6WUmeZiZ=YG!@4^0+tDin5E(F&_uk<_CjT6T# zDcOF?-75{y?^oB1>!O#$vtk$9su5S$7lo7;aaONY4A|$Fr;_75Bq`Zi;deM4GJS%pwtr~G5@>fSwgl|=}UJ}oWU2LmHT%F8?lot`( zDq1gzXT>hIRUcVY^z3Goy>)l7jf5Av|bX=id}50MqG&e z)zK7jH(0b@63>cVY^z3Goy>)l7vbXtVbu>lz_(kg_@vPXzwra%H z$y`Wz5x#lRdPzJhcCoD*aUt?oM^l7vUbJ2k&x&1at43U%%!QN};hPt&m&CJT7u%{4 z7b1UkG)4I4Me8N;tk}i2YQ)vaTu6BlzIoAlNjxidv8@_$A@Wy8Q-p6`v|bX=id}50 zMqHiDg_IYPKjUeHXVH2|JS%pwtr~G5@>fSwNWPP&sf%6`&x&1at43U%%!QN}lK<&x z>Y|s#vtk$9su33=e|0p4tVbu@+K-Fce2=p}Ke z$i<{;#MQ}MNO>W7cb=v$dPy8AaxtkIaUt?oM^i}Nou{dbUJ{3jTuiD)T%F8?loyhB z=V|Jqm&BnW7n7Tox5{JsUm{g6pI++V8FXGv*qR;b1#H1>UeU7id=L+MJlJq&my7X5e z`39b*kbbF-rieSDqWi0md;?EYoy>)l7jZ{av|fee{CJu|X8BYPU*S+rh-lfR1~dOA^Gs0raGAmDK8>tsc5|ld49pu6e53hG)3er6|Gkx&zpFf z>SQjYyoj8NqV+1|`5;eIi2T*j6p>R=v|fcg7w>7Rlev)cB653*)~k@`;yq0v@>fSw zL@rj*dKL2gxTmR3=0eJgh#?lOS0T^)dzwPzua2gO7-G?S74rTQPg9-Dg_IW&Lo8aa zLf%*7X$q0QI+`M4h(+sF$oo$`O?5ICQeH$1v1q*td0&mEDMbG2Xo`p-7Ohty@15{8 z)yZ5)c@Z(hqV+1|`EgHEi2T*j6cGz3TCYN$_xCi_$y`Wz5wV-1^(x{WWfjHVV;2z% zC|a*Vp7-}Oh4f2xG)2U2iq@-;_n&y0>SQjYyogwK(Rvl~z8X(ci2T*j6p?#Sv|fe0 z|HRW&Cvzd?MZ~g;)~k^B)p(jht%!F71e}NN9{x!M?y2z3fc;jRTVd}5{qTnCEAV`c)Q>lOdk?&; zF2Oz2tDF66V%M!M7P|6y>ZHyW>O1UEz6o-olwR~Gi4p%3KBZ_!`Iq9iwp*IU2Psb( z>Y={KS%!90{xY=Fe$qeNi(Xcqh+amYfL{3o(W^}P2hq#g4WgIH6CjVu8APvAl|MlK z2|ai2Ks%oO?W(FT$|tHFKyUT|AF~_yS4g|CC)%x0J3}6`KjgH2f&6$TFo+#1(O*Bu zSwH@I`Z4W4^jNu!b@XM1GdpBspuWZc*JCj!_+|SV_m^y6OV1VA`9#in4Rt<|`6g#C zu48i6$uQQT%nsRjsIM`A^CGMXe(LWum|r7)hWJ0_LHxC5jp5gbzcxwqYViG9{I$un z*OoJTdAPlNT;)C!_9TAr>_aPWJbNthydhbi{m0j}HMB)qA?OV3p+E)-?+OE9p z%H#y%b+^B!?1%5V5g*)Za@pEPEu=gXM@}nyZgNYHD9xP}`k5u(lh3rq}wN+lam({_sQZ5Z($Kca zwWQyxf6p+Z-5N2<|Mc(%GPY)rzHOUX$@43&NZjGs>B*TFmXha;)@z2pwS1X%FW9hE zcz=g&V(@P^ZECX4r#q5<(D&CT-;^Cg8j&RtnaKaAVIL%e7d4F`v*-bRST1cQ(l+^A zf7j?_-#xEp-El2PCnMfIg!Ezq*n;$;QzE*NUfN8gZOYbSX7A*g5nGUc%BUY}VlUE*PKoG7Ip4qSpH=hb&tcswpWLA8$NRTo-FH`O72SW>aMFv-s>F7r|76zG zIphd#I?>07PTGX8G! zZf1wb>;T(CPV~#0oga_hd3GJrx0%s7K5Wv)qHF4c(Yh_i6YmsX5)DhnrgmuEIzD^SY|=wN=&9o{ z#yAB3&EA?EjaX>_>7gI=1kLdqjfk(h;t7sPp^Gsmbgaf0tEdZ|pc~2ueZ6&j&lNY2 zUh7u5wi3|DKk`9c^aI8)@T&73jJln&DaW(&VcqxJ4U6YAy@qws=jeOT3*QLxxVlx~ z-~OV`@fTf>NYF0&4dd0dMV{y%>8F75qwcsb8XbSfy67v6UDVZnguDTLB7H+X=o5@l z&}hFy7Wo^;3F);T$sc_peM9-R-$_4rooP|4d-o$f<|yVWOxeh49zpGbi9^KSrChMZFu)aV}op)^a*|yC)KtIrSe<>!MGj zZ%D86n)Gj6ylv89gF7f2{th~{i$0OQVO?D($rEMPU$DLO0qg3zN-T2$YcJ_xd-OZ( z09xxWT~|r})c1#ns}3AUdR>P}pW1#$VqI5BGj`sVp=xq#mh0L}eCWO*S$OJ{D%j7? z13(SE*IRrYZ8gSTkNCRkg}6KS%HP6XkN7(DLf?6umSz2jvlMLcYdEt(&W4_MXv5CF zjWO@i_VQ=%-^{#A^(v3&&)dBWSk~$o`wy_}1u^ymU@42RjswH)-Co$G?ClM@!xxL^ zbnjL6;Y-trkG!s9S+~w5@Ymv(TQ@CBj%r6-dgP;}E!y-T?lSS<(uu$>PDpWpi(+Xde0ySKjk+#i)T@h+lu8Rpq$K=EU!f>Q;I1u$S2G)Vu#s zIVnDmc+o|>RX*P3-ieSw@g~4ZQwpqgiIry=%C#+Gm4R4gBUYJ-RTpB_kyv#nR+|v3 zt=O*GkhnJXM;~F&*E3$M`(T9rGJgj&=8pjDeo7kMXCw5f`Aw*6{toEPH$l1Xq&Qr};aO)A>-b`6Hk=zXSB<@1$cj z?@z_%?||NX6VU6q3*$Y~^BA%DQ=l<_2X&oq5}BWcy5>Wv{N|6u=I@|f&y%#j`8%lV ze5ly`5zy;-mGpX!H95_nip}2vz4J|Qrl!B6cA%dHZ2lDVGJgkk%})W1p3m8q^P%D^ z)!zZV`6j^TYoM9fG`|D%=I?;sd@GcjzXSfxA3>Y+cR+7`7O?qKsB8WX>N?*x-vOTH@1QN`L)p4Yz03yzz4<$!cm9;EtE4wS z1@z|cfZqHpVDqOyWBv}x&9?$JzX^L5`YZj(a6Q{0m}SMz8KyCovO_lZQkzs`hmw*B zJM@q5?$(BX_xQB;H;env?aA^DzF8%HZto$)hurd1G;6z~h{yeHO!W0zClk+@HZzxe zcLwopuZ^$zbmuX|?{qsp+2iF=#JBG9STf_O5yZ#cuyUAQzW0COhHm%a^P4Bh;iCi0 z;_;DBjtR3q*eJ*HW@m(U|M-D-HSb+`QkcHrGWr|mop*Tndg5!u*B!oV*r?B1BDlnPDtnb>8)O^T2!8{16OvwAn9H4XVT=3 zS&&@b^GM>azh5I%-L^aNX~%6Djv2ij@jtg26plM&ed7HuJve-E&?h{Ld)(0Ns*b_w zORO?*?yHa|h!}LbUl8khPOR%Z zv9ABbx-SsxenG7J2*&>-mRR&qc&~ULw|W6tSMKi1pk>tmh))#%rs(d6AW;W22-*&dvej0RQi?oSg&u z4CQim4(Ll@IXegRF|eGS1Nt6V&dvd20$9$@0b>PN&dvd22w2X}0b>hT&dvej;ODqu z+s)Po*t_~W4e7_jN5|MFK;^Oc7FAfsQ7*nk4r@KI_!bfN0ATSgBJ2&o;#my!}WI|rO8LFKWWodeE%D3`Ny zz*!Jj&dvd6L|{2P2b>*&SkBG?XHZ}{I|rOif#vL+;2imL+_3Ft z>jUilf2|MjrQCSPWB5AOU+{sfAK@EW|H5aoeupn*;{iUFjT87@Hh$of*|>tQX5+2# z+RD}k9S@v`|Bbmv1h-%0G46_NJ;xoAt@F5Bvh^Q#PPQ-LF3R=`+)>#+g1al*UvQ^o z`ws59Y(Mh2VcX5t2OR@(`WyfCHsKjEcIU}F#$BnM_i%@5=Rn-8+W8Q7u6Az3U96oa zaYt+COx)et`4e}#b}q$Tubo#LudQr-(D6|1`XFN=z^?$E$I@2;XML1Q9|rgsz|yw~ zd<mTT zR{@r@X9QmbSk9yod=+3htH$tEfaMGu!&d>8vuzAt1z66!F?^MuDtmB7R#}%=TH)0)!#5z8Sb^H)FUR(7wAAhTS@_Sam zc+mZeSoarV-FJv}KO)wBidgqAV%^uchUk7rEWQr*LGFpVXK_#TxMACEh&lCJ;+a3w z#uyKJz9rW4C$XMOiS@intmjx_J>L@RxtCba!^C<{Cf0K-apSf1Tb1&m~s>mvdkJV$OZ_mm~00Kbly5-WcT`H*CAVrMcV?y5#T2 z*hk3Q!k&RX(mN~mm)>ioeV5*M5$in|vEGjn>%AGV-lq}kJsbJ!Jy;{RRbTVyH_M0p zg#K^%vui_)=Z5B)k2%_WK`he7Gvb598aE`?c%sb<#2JY-{z$BGNn(vx661~mXDsvv z?jCTi`Z>m(K|{8yG53IWJ;vP?_H~qN+?@JqJe?SKU^qj7M&s|?FElQnpj_ki#2UwE zTey3}83Hto*Vb=#Uek`SW!>&N7-L0Djs2yuHe!u`5o=tGeXa2_jscCMMUX<{Ys4CN z<5<#o9I?jfh&876U$|l0ZRqvn*Ump5b7#M6{GAwgPPi99Uu)c)SmWu$8fPcg_&djg z#^s4MUeEEPaeR&|+?nAH0{k1VtzUb8W%6UZWM`Yy3d^7!f=O1leJb0>Q#)pM$n4<9 zKuJlfQDZ{$XV2yy>am}1?|e2UJox&wIk4UMhsK11pYK9?PvhU!=HKDw-|gn#`R3mR zCv5ZYh_mmtpe?-527H0_y*kADeh*^*ZaN{$zq8K27sbEhPUMM&j&=Qea-^O7`*W}k z;yuV{SIc?!PBIgKQ!I1i1pR{_Ki~a2Fyyqu;);*oWIuZRRmq-l-{n?kfA9F-zVT7gI&0{WlfoRy1hdO~N=z)pr?S4WdC z_w?vPlhb4Lx#@-eG?~%Qri-WX<(^)61lR?#c`R)P=#O&Y7oan+v=d+pU{B-AJ-yNd zM^CJ6B`DXr#9H^iXneV+R~pabOe7&e0rD2F{D6EN%q zS%E!`FZc91W=Q`tjIqIT9S?>vPK@5uP^bUWMdKU+@g^ z&0n4#KYsCsw7;hZh93B7=>1n@z}nY2U>yU*p2qjJr}1??O*S4%*^jk7KR5Pxu(|K&wV&^P9q{Wz^1!j->e;h6 ze%dcSBs}xN`^4)$GbGH;rO)&YJfL3~GJYej5uV~Ur#41CAxu7x=dwO5)={+B@O#(Xb5!)o70~Xr^&;g5W0{8-ZdSCA8 zJs;=|JyBO|lY?%Gs|>?_M&s#yIqYimo)7xXWJ72|Tk6{a7Pw&e;z2~DeG3qJ}vC>42C$Xp3wpi}zJs;JPJXJ?x)sa|j zLhR{%xu^Ghpf_ZKoUjMl28Nv=6EN%tS%E#hFZcAGkB$e{{TarXVY!YC!x&>m?`iVo zOX$l3WJ-TBT;FzB@(qRZ?E4fw@U4#WkbR%xc+O23Yxz40f5)YFYozgaV*akopV|J$ zS&r+o(i1Bm&UJrxr|sGr0C|Z0nbx0mv+q-6->0zmwaPmZ6ZdXayoW#gK84uC-jyov zy3D>$k$s;c`#weXeF_{a>us-h_g(q;+HYa6clR6F_bFt+{F={f81NdGq;IbGvBY}D zst46S`vzPid;<?$GANigPY1Bc5@t%)oCFsE|xi_M7J zUiD?=%d_7l&o8UinAGLl+ljk<+h)?|y@wE=^+@|k*R;C40&OWqj!RIQGGMJstUQUe zt@fZ%8HiOjVwIU#bs<(AiB)&bI+4sBqmGZlCm?QQ* zJIo#TjlAsp-TJ-t?EBq)V(huaGxo3NjE!-h#YdXMugt#R-Q?Ox&Mn#ZyWc*9--tGU2R6yR-#wdS z1MwfkfnbyD``xGUJJ;FwySwol+1dBIXK*}Z-|vQplb)x6ex;cAp(=ld(|)WsJ1n`w z&*CEz)5+o^8%~Rm>zU5C`t!AwpFJB+U-h?;QwqHbiFtuW^7aGvX5bIv1Hyv2HzS89 zeB7sNkbH$4%6FMOBrsFWiIK)`m?5)Ysh?NG|7>hehI+--bZ!{vl>WU{gCgEdXoa4$fw^KIdcve2F>(29- zBWSk@^r8dr9bH}Ix`g%@b&kL2dPD*pv-rqN+8lj_^#wMOKF{JKVh3G&X`eqmyn&3% z841SHx{^cJH;a#y)b&}>EIyLIpXWMNU(X|C@sae|VSSE+K9D}&L9BKr&f+8a_Y}nv zKjV2@pLa34#jqpxb)E0T^1sXEGul~vq*dj($}B!&{*LU|S$rgmk3?-|bdC?3v~e0I zYTY_Mdr}r3F`o-_M9#Dk&b08EoIe%IxmRq)b8jqvk8t*df0jKzl083i=)NIYcxv|i z2+l_7&$1jtfrP1ijgd2@25InnT(vvTq@q{;o#Hsl;%u*S;2CZ^!v@Qv|F!r8&;e^M z?yi6(7Bfluaw+^#vwv4SvrYPZ$>rsTRqi!$L(=qqU~=W1{hAZ+H+4bfw`Z0R<2U{v zeDHVB0iz!31A`y<0;g@F^?W&>J5hS%;}{=e8(-T~Lm8U`Jr+W&No4ZR}IrrOLfMvFx=`y61KakIj5P!aj?B*ZnpE);*aR z^-v$>diTluQM9A&Svl`Ml^%Pz@gcVT9Oc?>09JX3RZe2NF9eOX1B|;@+#>=DeS&y| z@=4M=H1bcRJ(lCQv}f{2*$iUTLw(c*Kk!ZYFlT$RE2q9nAE7*LX9ltICq_HaGvzY_ z@(`<>#40~A^h)EN<*^%|u^YEB=8cZS*p2hpjsIBZ7sg(UaiQZd#<7oW@n(F8l|Qkzi!o;M5UZTTDnBt=N!z1dHa?-3ja%@+{35*@=gRK@oAmx(#K$CsU;h0!CI|RyIq&wA-tPGzEB-B&SFY`{9DmpL zOiq^jy&LtdJ>C0AqkEt6!QMxVdmQM4TDtcU>)uGL_hFRN=LN%-={xuG&*bs0Na=}{ zPjLK+wOwNQTYfM0d$ixXQU8DSom+Fb=IPoZbCqjmkUoyx+LiZFP_Anx){|K3p+2#$ znOIve=V=4{c5A88V+}Dr#8^wv9?G>{@^EXo$;on+f2np**R45}3-X~HYoV@D;BRXe z^a|FlTk9Za5WOgmu9;XH!ONa=fnK(j8hrv9+YhFz}x9`yQXTEecF@EF!+4u5y(g`2bLw%Hk zANT^N?WAKx%dr+2Ju%u5K9f+c{E4+)VwHzjq$_akb95U&Rz?untQC_Bcfu30Tv{${rpIF-^R(Xig zj@cjWz+RNc^%r!+SiwJF`@3S!4Zr^A`pI&k$*)&_9nsUR=om#`}N1KOY*1udga$KT|ZgZuX}zy)b*3{dt3T-)vvdH9ro+9U$<2r+Q_f- ze*K3&){ky(Vr^)U^O&{g)|}whqIx}#rRxySnTS`%&=YH(u9-4+>+k$*&jz9$*b!}^ z9oP}r?J0IXXSwbLoJVeNGC5f;{1|TsAK1^vz3)fgzd}%N`#77E|M>Cg$E_dFew_R9 zukuiKKVSSjO4~`#U{c=T=dScS2#tI0f{s|Pt^cGyF(zZTcf@W_iQQfkW6jn*B6fRI z?Dni!_de_kG1hF|BZLq3Sp4M6u`d`svGTz>Z~Te1U1F7oSmh*E`H9g=+May(Wy#(F zy=+f`UX#!s+H!jk+O@q2dSUM)jqZJv)9rE43ws~@ap-G%BJ{Go()dhLy=-r_c3H0S z5UZTTDnGI6mB-e1x@NK;buGuFLsZavahzE_T$l#rDJo$xD4~>^tqz zXL?p?uro>5tyZg)am{tr>xi~7-tphY*dwHExgTrzJwkGTF#o9UZ*`B*{-Tb4uN3pv z+u8DG{S~3_8tQBb-qvRsPRDL$hs+N3HwGGSJ(P7r?rHP;nynk~wTZpY?tOXh<4g6t z?~i)2?$|zsGe2>f>)CkwS7Y5(iv9BYweSDN*vl>)zV_tC=sP)+__G#btn5?W%ZNpe zdh<{1{RR!~pZ<5>!J64R1}kKCNUf0Bp+4=B5z8+$592*!f z=BEqWy#Ma~dhhT1djQ?nINo$$BbIRy|E#|f$n5t)zd!nY)9zaRO1Y8mj?*sqWs`)c|-!nJ+^h$NN6sC-S~hZTIf~e`2HA+Ew?pE3;u{!|KMsk~@Blo!gpK@ArdgALRYR ze4dB*PlP7#xA-;Dua$lc^=s?T@0G02{khzq*Zn!(pYOF@p8HiEV(%yTd!;mQB!50Y zu7lCT?=?Q~dx>=)C6;#c_jLMqmZP4u$Gb4?7h=0d#rfWH9`G&>yn_$=B41Yikq6$( zfp^cPb|{b6zhZFNA6l;^ccbO;8cq6@b$IVBXt7%VX8o=wSz9wGXk{jTr6V z|G`J(ft^jxGLsYSnEbWrQ}nxgU#sPX<2{*?y$=>N@-EE;@AJplK>jxJxIts@i3Lrw zX;bArE<0Mjwd8WoAdS5z7Bu<}L(9YF^Mv4|??UJIqwzi%ycY&-+4F~>X|+V8hOts-myqN@{Z3ce4hYqS^hm}^j(ys!3aSa zXn^q>{|^kE@K3+tWqkOIkn({YN#nnZt$Fa|gZG}AJg}eBi_heP58ktzzBBY_dmj$l z(r13iN9+@uee}ILq_KQ=@WJ0fr~M`UlkYE?^ZEXgzkh^zkACNO9H6u1(}NG>h1{UA z?>m4-pINf;WAAaz+Y2=K2iv83rSEQae3;X3&pv_1zb{DTNt`?~=JN6+PA}5f^8=u9 z?_ABlcL;p!c>~a>eFFIS_YT>!RiIHjlSccCZQ1h-pwa#!jrKcf?D+@KXup$2#}8@j zc?rMkmp}(PiQY?q_JnjK+|US2 z$VcZFX>@*(kIpaB=sYEj&QsFpJSC0JchZQRG2hu=V&?!l?Jp_Yku=g@ST{(c>jwK2 z@=X4@x$khp%?VVe8!lQHB|Sq#)xHR-wT7q>v~p6eetaC!~z_< zzov7h-J_)MGfDf3-BPg%H`%b{$ zy_W=h@ctB*tFOWHk@_IS>YH%ySD%Gg*9T(Zk&o@ccY&`3zCIS1wv+jQbzN6s z$3prPG`fdI=yQE`l<&sZJs0OaoT>BQj4&SoV?+1u2sGvkfRFC=a#lJznC}1@JsaSh zi09ksBY?(y2hivlgEV^fh(Tk%18DTDLK;28kVelolt<4zq%j`>eDsV&8uJApkNF6o zG2a1g!In}+KEOiDwt(gD#s_B+(&!nFH0C>ikDdul9==~d<%w|iRlRtYg*Lr2(3p<^8uJ}MBmd92p6ZqQ2%wR_as6<7a1Jy+{N{r4;ddES9@3~h;BE3G;A6f3 z_?V9X8r6$5<_mzvd<4*_eMqBrmVQ|B{xZ;*?~v+6-;FfdUja0*Upnsd{Z1P55kLd` zVg7)R`2uLmd<4*#?*JO}1wdmy0%**4P(GZ`%7;FJ@}chl8uJA}qw|6?>%5>m<_myE z=a=aP-`wm2pWW=k_phNX^BvHZ&Uez7j{q9;9YABg0NOGi0W@hlJF+cZf2`jrH)wSI zA&vP0;G^r9jURlorV9Hh=4|?t;mi)%7^vSd0B%e2N*elJUHlK+m2yt&8IoAfmNwVx z?Or{7E~nw|7SiW98t)7&c9i?)wC_Al%kt0h@*IRSyTu*qD?XC-WBy%=G5mknUGD*i z)y~9ff1a6iehJRjv2?6vcF63|5MuyV&Gt1|p)Pkj*}m4WasS`m`DDqQ^Ybsmn2Gqw z?33A{E@NQnF_ighr95NTHfE9SYuUb5OMi{yEL*$kvUX*4v++~y7zn9txW8qX#;8BP z_>9qaNghXP+s%jGUYR_24ewzmZ2s5E-DR zL40Yu^0F(F6NuN{{+hBMzUxMOaIeW_Yag|c@=P2#t?aqUEj_M)Y)V6{bt_S>Jc+d} zVwHhdWg}LZiB%V3)sa|rCsvyftF4IDhLmTCZBzT=zlf0`)&-o#~kBqc2 zsOpMNY0iev>#*Dp%%}Hn`)Ad>`E!`JaOIO5RQ-7WHmv*ZYOSLC4;xOsEDr?qpUj#% z=iJIP-^1r}tk(a7+-bLTWnIxXLjD2d(O5tEOdmfwH+bI%sMq1Mo5Y7cxFhL(E{D(e z(A)sZ_GahDqj#QNhxG27v&@}A?gC`fd;{8lhkx%EwcYF%*4=Hy^6|iLzhS#4P8krt z^4gcAv0M?<-6_5#8kUSr?V#VWh0QhBf^{v&1N57{H8~ow(g4z1P6+6a-)Ka9)fG=L zUr6Y9#)TbxPKf1=pnTBRTgUfYaRceKE^|Dztpqgkk9^Rs<&yxfI`6@#+bNskUGT<- zb=`MntzG5-hoa~QPWrLUO3gmJ>W2+iRM;BWaSkWKrY^mEsl7PY!}Khpa=6U#+GUF~<; zZG+{;Mz?O-k##M%1T;P`#qvo|e)THNqnnz{WL?WYft)(;*sjkx@p&maPuZ5wEzx;L zy|7+`AN10BO8O@*e>K_TKZD8N=c4GmOCX!hQ`Y_As;SBRPujAs*qr$%pt0N);5RPb zHtDdz9qdz|f1Q6Q84Ec`VRN*HzL#_5I=Dssjg-zplg7 z#d2C8r>?7{89Q&wP&K(VX)LD&H1<7Q*birv^moI@pd}`Y^9bjjeC}%wU$hXTJPRp`>#9bR~A-@s(w(*T;Jc)I@5&!bfR5pBnrQ@RU=A9dd z`R`3OM2<&e&pWeYZJw9Jde`lRUCQ3xpgY&TIo*4eefZLJ;v=u?Sk|p`3H-JA<Jh`UTYxb))YgNSb*x$P$XPEDV6eQC9(6_+edpMfo#dqYL@(1$dY z_k3J2YG4=Q*B@wAIj*uf@q44XRUSO-CAK^D?mtvciq9inbkS~=k9WCuB4kj!39!v2z-h303>pm{$vn9{E0-HYt8uNEh*ZC$qyWy-4 zdh?+`{2i2=-vOTH@1U;ppu4j z&EEmN^G%q;jl*%-=zo`A{e~f5+8@Z(?on*+$TT59*rF1#G^RRCy5{eouJcW7oWKV$yW)HvIe!ZCh2JpKy7^~p&EEmN^Py~>QZMs6 zAcOfkpf}$N<>v2zzxgI8H-AU@W8P6m^QS;#{toIo-^AuM>CJ}%jq^ufXUoaAbrQY? z`U`glw1e}ZY+a>Z=7WIV{2j>Y{3%;kNpF4%=*`~&z4=+d=1+mf{2i2=Zv||A6ZS03 zgY+lE^=t>8rEc{{&^?zL2o_?XtMZ779TNx0pr2W?HEhuFJR0#A0)B! zJm}TGB|wZ_<82ye4A= zYxHW_e)JpTh)0ZDq5Z68j}s5s=EbtpXD%jQ&|yN^r0#3;eVzl(*}ClAiS3Bn4{lz% z(^(yeJG6PR;+%`p_kzwiU{q!4g4Qgr_`{sa!7nx=ZhO_2l`qeJmps3$T4Pd|Z*M2= z_HCO9+}hEnf@kgymDAuH`|2M(@>e&d;77 z$(|p{o*$8XDxDYjz6oO@mhXhQV>wQkQ=h~r z^xbghhWj<>h&wm@14bGC28`cXd?bsHWbu)7Uf475m?M_Eg?XdTt!MAoO5dx7vwE=S z&9R2KXTxP}S@PXCdj=f#bkDQ%ximbVrgganfu}uh4tnl9+4o1X_y~M@d*^_@Gn;FVKEJ~_huj6>xgKJS8>~yXOT>K{Fz(Rs4;W?m z8!&!n@sTV(lEp`|_(=ACtvQVQ*!y^~HoAA`X5Sx??}A{@&^;&y*1d@sdlcSriE{Y~ z_6|(RZAg$`jza8Fmh+H3cThji9r$mKcno{vN6!ZAyM}n?H|xjx>BqFU8os~McCz@0 zu2%u}DE5qvd;aYCk>-qdWZxgTHWJ?|`~HZ0&ry8M?E52=Hcsu3eSd`a-g3_n?>=G;vF|Nn%w*pm!AT{HkH89c$NB#&&f+6kd?d?l z>r*G+4flJ9gJi7~fxNjg@UV02$;p~Pp9BgIZD+Im!9-@8sne>+X1bTh$ zmHe~sk7VCx*Jn@ojdlB8A;y^dwjjRO6X6?~D7SA2V!XNUA>uttG9H;%lYM{W?L**4 zWY3Q@$(|oU97gUp8FSG%4DtWq+=Hh+RY~@Jb}>YD#;)5LJByF-o9|hC zq+a!yRWZ!4+2H!CIKD)e6SbUl6`|S7b$9sOcAIQGXF5{uYv(u9^FHB=(+4tFT z68+W0JLq4fXXnCX{^;yIrx^V?JMA{*;9b_941LE={KJ%MR=a|D;rqXz^3mDP6Mu5) zCR1ibO{GqGjNkZwVEi3)z^I4%z~BeIz-T9JkL4Y#Tu7Qczm6uqwA0b)h4K!NLFtK=53%x>I@Am8601DKDkm}cp*_%d-MsUfX?uBn zjUIL&R{IdE-H4$d^aLO1jrLSd*q<17GWnPE7qnaQ+>6h>_c{4KSKsFs`Me`xggi<5 zT$(3Ita*~eYD+7}JEM#~LVM}om-uV&`^}HjdjQhtJpi%Z1MnFDu9@HKmQGM|86VqPw6+uNw4}6`+QMpE}uuLb|a12lUVIXtoEmz z+AqYuzdTl&1bStCm(Sf@M*FTjym;53Dd;Qo;X_yTpAv7r`efj{_U<)hK$CIAC->QE z%8PeBL444Y8%&vS#qv_8Jm5F}9~gfJ9Wd&lJ}~%!FECn3+hchLD;N3>MlXCi7$4!^ z(fG^nj@GXHy`#w^^*WlI!mp#rFYR#E5&OTARb*Sg-+ z@z0kJBh7;MuIbpk$uhf7jbi?s)e<|45AA_d1-tL2j+gVGZ# zAE7G`%AZ)m!f-e^zdg#9Te z?1c7EzNEj{XIx)_8hT$)Te7{z+!q>pFOdC?c7=Yr4|1I9{zxo;!rDt*U;DW9C2fgz zv%V`e+u~UjvpLQf#CrB1*0D$Y%k*7&+$^f>h<-yK4*UBp9fw_fSO?$_`d;7hFKfO@ zT(SP89h*gELRTK2-f48lk;m>qjNkZwl;iK914cd62L?az1x71rdn})9PceC<-V~El_)RhSrJX5gk20j?m>bXw^u)?X=%^R?6KlJ~Di5*B zNi6L^e&VN2Ip?ypy}Z6g4?7U6eTbn4^wD-cILu{wf#;44?NvcHOQ@qxbc z_ha(EdB4y5gE}uruk(f2$JcDU;TcanAM)@6S62e#n+bSU1lZpB4{YC42A1!cC^it(-Y0C>Qz&?J1wg_~`f3S&r|hTf6q$ z0qCV3+XI$%Vv`^LzuOu&OmgKpM;`$zA7bTCtnJ325xpP}vC2uTIWxrD{NsoADQ!2l z4>|Dv_MDFL;WIwKYB$oTJx!i~_CTZdC)R$U{PMT3;vJ7wq&%0#SwC`o!oJINKib}d zIi2Cu3d^`1xQ3>Z)|*d}@uWdBduHPb7Fgm(HNyF-RNCYGQ@?u74+%b7MaDO#6lMqraRlW4tZK-H>PFtnZ`~ z>!P^{b@)2kR!l?^M2< z{I2~0#0Q`AY?5@ljCjD*zb8+&y_0yQ2{$Dhw4X~XV_JT{O5A6|F7j^J&xoIUdV1CV z8~i{lF+f>k)B6P}&sn+9OU`pjFMJ~7Bm5)dFYQLwuE-OaJR)aga*F(s$uD|ErkAvd zJ*5 z8}@zGjh(*vKk4^xyJ>FIjTZl(byvJ?=cw)RACShkwwa1pVvV{U3EnQ(aw^!PEG5S+2VHwupUQ zwF%2r=Krdzw*5cr>KOPx>+0Abjc?c2^=)~2Ph;gW4>(RSZW{sT&y~_vhEtnocF63I zje%?oWMg2N9|I6@$$n{ZHaadxF&yt6WYX=wCws$I$X2m=DAs$O??^3}3ySO&mvA8zk=Mmb| zb}g=*f1e)8U0fUTTU;A;;`5@b5ZAVH#D$F>aZlqz?Bd$iZVVcghuFonp%>!vEPu9b z^A18wjJUd$ySO&^SX>+Ykq@2!$pGDJgwX`3R`4qp}_t;2$Dt%T?<{h2^Y{)zZiAkkvg!l0qDn~`v zKl!y}UCP#$U+>zYeaAZuf7jvfKz<$1P%Igber#sgW^CQ;lYPr3`<9Krqw{xnGQw~M z{;#{fVsZs-v^Mmy<1D~9@Fo$Jj62sXyp4X0pFPe{vbXe zESP&U?{oBiGKcbACJzbw-}oqLfQ`I<=Y&Ie4B&!X8Mgb((l#3XPD7$ z4c-gs-DU)OeU~Y*zT=cUXS7~3{H^87tb4(Rt-|{|Y{PHFG@CXxk?+coe$e;VC*PDE zLmH8V-w1(@KMngJ8N8?|zcnLzKp(r0;(Z|6&Aw%me$z+3xf4kr(B^M;emr{T*>z~Q zHZwZMho#@C%-_wXV`j%l`hfP|;otj3Z8y7xb$1)Fd_3^mZ`c=#So9tUQ zn5z#ZT_@x^VC>-E)vGj*ZfY_!!92Bi1ZeadQgRpHE$H1o>9LkzO#zL*BR%_;P5RD! z+T^M44-Z!zIFRtq6K?~aCT$Ija_R84Npa(j<7XzUxB>0Y?x+}6-%b&U&i zA8(AkKKqtUKE6-?tG;}$tRM65X3W1our|*-H}<^K_8M*8rS0Y4ch_KdQ@_L+Tm1ca z{=D7!eh67hd47VvvflFC2`u{;&rHCe@AkqjWp8iL9rtMQobJ8KK7469@sZbcEbG>} zMBaH-9>3hWX<2eqJL1wKA1!UsrU!ACi3gWn+X)L>?O84_3l4ZPKwVXUUboJm5+D1cOqm^ zya}+rq7o8JK%%M(DKn%{(S^LIdRz6r|B-vPb(R>0;@fyVqD)OEf|WPTRt&4&Vw z`?h9m{tn9R8=By0`46b;d?@>dIL2d)?gU40h@C%zHkk(n z`c^BojHM2Ijp*>%P2xiz+%cf;2Fs0&Zr!va>pI^A^F`{;oaobJmRu0K1ZdvfYau7AZ~?BC%Jt=B4Dqe(yF4zFKU`or*TiSb-tF1Io9*o{{% z!#~iYEPdv$Jb)H;P!1m81)TDx-13gl-BDg)-uUxog>x&^L+I0GYp1Pw=XCLq{ zQ@tvkJu9Je%I8_gNsKmKzf}1C0xk5z5AFc)8+X=-*8wBe>+?(C>!2KY;rIuvWyGLG z9h8FycmW%4V6=%l03ej(z8_fIjDf)ixxK*PFaLaq{uHDRG1?Sf#A%yL=DRDG zXGin&k>i8!i+8cZt$PxRc-U&88LKw<)BB2Z~O3~IXe%mA|CyC z)2cm3-bp<8PyMS79(*0~hNqudg@34vGW-n~w5S6N9^eHG-e?0DZAy7hD;N5l(F-49 z@DcvR;4lA((Wd;37;Q=$#As96AV!lT^ z7`LYf`6K?>S%nz;x!cp1%E$Hlvfr<5oy0quTshWB@`Q~3Y~c7Wb(V1QEOqw4nE-Oa zX6gHx@P9n3S%oy<;rc~*r~Q@Ynr3|myZ$=+4x?eo zSu?}12Yxb}WOk^JF|cHv^y{ZzSN(d6wHS8Cp62#7l(8JNemzh9#&rEp?=(=m@qE=Z zU;VeQquaY1#0UR)vqgNTIo2K5r%Rn-+!zRMY%Fyaa$~8W`xA^6j2QgGaa-KvR=}+UGC()k2KiR3(6;bc~PU0ACcK%1v5vv?R{L+3K#%(|D zPkh6Q+sDtm)`fV^>ciq&r!L~z_u)5Bj#qwU46(bP`Ayx!xciyk)V*1K_4}F&FXi~z z`Rf6>HlMxE@w42(irkBf*5~-C`pZkX4Y%Hw<7e0I%SC%k-k;;=KYwi<-QE8J*8TGJ z$8yu!jO18ay!mF)E`44jpQcZ=i;jP7E%Ldf-(Jy#r?w!U%g3A%U47ARTg6XUO13^%AV;Fy?6T%@_G2pMbRZ&%^;ukn_V0IY2D8w%!`i(&X1a&xjOlr(EihC zuZf+>=kyiUj8PwR3jBJ$og<&KhO~`QAM*?RP#=825A`v>zz_8?zrYXrfDiOTeatoR zgFfH`{h$x{KtJdMKF|;PfDiP8eZdFzhCbi}{a|14fxTg0@PWNyU+{swVPEipz0t?u zgFc6S!3Xw6e}fPDAN>tJ=zsJ#_@MvM-{6D(#~K7a7=!3<@In8h9DJ}20fP_LAz<*q zIs^P;3*$%XlaG#P^3m}eU>_aN1nj7J%Ne-{E-i^j6d=LcJfro_#+>bJ9(;P zKA1dJG9OHyMCOCZlQ{cSIe8LipG4-T*(Z_lXZA^C{F!|c*I$XVPvZJ3k?}`9vVJ5o z{>VrAE0OU>KGI)_8$XHbuf&a?M8=X zL4Axv@I!qa&%w>F#Es|R=2rrJFb<&~^Z_5}2YtW?`nma@xcL>_d{1Qjkq_)GHOM|<uAicIPEXaFY?j( zMLrmh*l)lG;}Pq7+Fy$>-^mB#(Vc%V-^mB#5&I4F!gzFNuqx~~;Dhn#&SO}AC=bRX z_G9RU@reBxd@vr}8I0ox{uahp`jg>h*$$eQ5<^DKSBa4eqj@Yba$z*TMe?xoc|mwOu*%vOFU8m$dmm=b5{IXplQG^kVwcxOZaiz6kd! zw1LLy)E7U+?4h1?|YK`s_C+H~z&4jAOI95BdPr8!ZM-*Uj9 z7s`xhOHdnW*_H%#qPN7Us@qev9O+ z%&hS z7k=D6-XL+GERU#R@`$pWq9wWFzn+{T%(x|UFT=10elnY6cBqdrkow?qhfvwjew@6s zO`a{nPviOB_uTyo@?*JoH`H?khdk7^gX-02&+=$~6#X`jvwrNuzAoneq>=lv(aw|U z*v!v6-f?5D%iR;P=8SVJNuC#Sz=&~1aOZ?t<)x!Fx1RhK^N468%_kw&JR)MvBO=y3 zB4W)WqTMx*i1@d9UxB+G+q9<5zjVRA2qBF)YSZHEzW?s>ZE?i(4^{ zs&T6XaVw3ZF|MmIEXGkaj>fpI#?b=ex*A7gTvy|03F2rP*JGSn<7kZQYFv+TW{v9w zjhiEm#yB(bHYARgXxtoeJ;uE?uE#jD#u*v+);MEuamL`{jETn0$p>+GjWaUtt#MDp zEiLXDT--Bg+??_t4zF=o#4RoE$vC{mVG*~qIBaln*x=%@%nQ)Ca6q1d#$lNkpmE`V zJOzyl2aTH}o*P_Tn0X2srw+)Q(6})36f{m9kT;=m>VUinjZ+5~r)J&+<`V3TJPwUh zBZkR2CUIEluaCHsPArN01XU)6d_|ZHN8_(pU<2k@SI-Udc(ztn&_7~&k z$dloC*1Qy(U&u?b`9(f1FNO0<^JF;RH7|wwX`YPDckAL%dV+30$Ryh`#x9*65MWBEK`-n-7=Jq7W6dMN`op{p%nR&4nn#572YHpY{xEL?e2~Y1 z@drNG4=49NYLc#pkz0RatZBL)M!@O(%I8&LJtR%qU(BmSo+sr2y{?Cl2YEy$5Aukx z9zveT$rG78Zohy$$lGC#iQ6w=p9p-^KIEhJAs_6|ZvTRP$Orau`xp9)e6+vFNBfI> z&|jKI#PQ?yFXa6o--dZW7=Mrl`?HK6@m1;~9B79MA5&VR_3~4=r!m<`?;<#ls^cIUCkoxxAB-9UXaBLun(j^OXjnm+ZnE#eUANb5clT2o;fxAQdrvNIRNc%zTEEd@kcZZ zcOJ4?wD6Fpql#CL46pUNH8*7L>d9w^jtUwpgEnoX89dAzNDDZH%NWLcBv zm+BYa?y_c+WlbJ$t6vH)Yc^TdZ}y`vIqg);g$h?!)4bmmwd4OabeVpe@WIjamPgLA2wa%hEAeu z^5K=gy9;&a?f?9ph1Q+>=jp5qKF6=N^Qz!e2(GPff^j1J$DvOO#j8Fre=6wvtZ+d5 zWcN>!I}Ygmb9i*r0l9}y?LfO7@!ZOrg8ycdC;hF^ zx?N9f%eqZ=`rW3r)$7UfS$D!0dwb6KJ9bk%M({o-ZX9*J>Gb%TSxs`&Cf*)By#Mj> z_*E{>Jyy~zzWCui+W*?ssZ@c{XIcJ|fvTCQXW8x!{eseZj@yj`1 zEgTb{Kkm`LulC%$?G`T{6QA^U#qT{Xr0%u+rpFb1znYH~=xH@|10{x|5IA03D@fKU}vnl%V=I>69 zU!L76di&Y|(GeRR6kk`hFdFpnw$ZD{b&C7`vq$_zv`Tbe?*-BQJ&uT*ygDt{|IoWT zV~j1h^omZ8tbD{)9B=pc+!Euw<0*TS=N*erj^FFrDrz!eKy=&o2gQ2~UKl;_yWdAY zUfC&bHLXYd=lxfSwi~%1D(`Yc+;_#ha;SUe;CHvRF*fJhd!_+DIDBOM%1?(S>rU$z zt+U3d@#@#!RQ2A#LD9of{&y)~Ps-O?^VE3wmN!-1J7`d}{2imhlqoADH+LGCtaaPT zq0g)Bl6UtSkeoO8*s#geo07}#-XZy{Vn|s1geKwR{ktUBO#3i7{)dCY+>7t8+Hi5- zs)MGD30qyY@tphH^sQR&t})@QSK7_-JfFG!C&s;fhnf zsTw@vq;SK`os<7m{UJH<#uLKbubr7ZvTa}Vd%WMS@3x2CD%u_y@BZBb$$b^MXyrYh ziyrv&h_KfwcjQJ7+Lmie$ph~vQ z4L3b-^~2-qzJEO0^{XCHzZRq7%I(&Rw!M8obiq$sbp_33Bbsk@`X-0RJ6-#DbomNB zqY2GM#TCt3MqgD9h%Ri=H$HIn4dV};+@1s9I5+q0F=OJ>?%%g(^z`k~F?$>z|Jdc?+^f;;(RIfiA8&i# zxLnsxYesMHH9C$i`>^N1cdZ}qc~1ZMtOtL{owxHE(JI46$G3O*pyy^y*N?AhIv^e} z{dlajDzJ!6tjP2B7@yz6@{f-UypLuoFeUmzb z-G)bD*Kbx%TCR9lIQrqIlOs0hk-XIJfzJD z=gkQ{?<#v@X7c@E$A+@KudX`wj1D2bBnpQwSUGw1<3mH!t^b+auyT)NO7D}yy-hbu z9$9Wca`9%ThS6(XS@qo^scg6G-f|LTTY1r_aN6u|a;=XTm<*bBWLVfCL@n2kl27h0 z4c%Aj9rwL%#iUosjmcr(oDhG#&Y4w@?$C_=d))^MJC1L2E9d^WA1=iB2`&1rPoBL# z8x@9+{w{afK?9R6K*qvV#Q>~%O)gyu5x1h=h@{|Yfc{( z|FhEy(dU~F#QcqA{zfu?qYZc7rz6J6P3Ldb;owLA7A?Qkaq$bQUy_ja=Q|#V{vUf^0bb>?{2km~iX;Sx;|UHqyTRSvEl6=E1VU1@xJ&T@5!^jz z2X~4VYms8brKM2(+nIOwu)Y1am)^Bho^5X0iy!Me)wXMFK7M3dS)RRNDmFiP7oM=k9(H%C zjcwi>!e4)pn8o^AGAvgzG+8%*hi0$MZf~#3@^(tWOBZO&GYr3G8$3M;t${z4zvP#9 zVFt42*N-0-LHTvvl&c2t?|Rl|?YC5A7dNoO34?HcL7lMErL`?Jc=rj}(vI~tSD;R=l=WG@EAv^A;eBU* zy5efPoU<@6VmFg>R*bFRqcqZ_yIHPO@Q^cNq(>J%=HM#(Qui((*90cl1aWk85N!X( zgLmlTMz%UE?Md`c#KunsLdcy;qG{S{qH3cWu;oS;DB|ud4oz5q?ZTq15zBAC^WT8@ zn{FA_P8lJO1Sd|3QEochkx?i&6 z`hs&1+jL^59-KDdv;n6L{QYeJ*K6fF(O&Zrn1>C$OTH+^CKqIEa!bZ0U1V%BTg4_< zWNcDN#wI_?*kp%_O_Ipir1y?!+Lya0ADgdfGAlOO4pwY3CFhsK^FN7AYBen8@O9VL znMv_)y9A8(#Pwx!E-zol#`bj@0{K?tu|+lkJ-$ zt$8v3`yxk@5^V3t!8~N>N&Br!HQ0gKo@L%jKR+rYX=$HN7<<}s2!z(kX-o3+0XD{^ z8+4qs#O6^nD=(O|7Q}S_$+q%kYo0dbo@k!G1WPb(Ft2~%D|?}<1GiGTX76K#dq!Q~B)e!w7dO_mMbHufk6~vTUHaPdx2M)#L5HoWx6?wAu zh1``#*;~ojXIq;j()avj>{I$!Klwe82xwQRiucFFKG7FHfoHpFKyvq=?b&4P^Ye~c z;*gAeq+RjO!$$sYymRqUZS+?mXL>(B?^Ra3(^17cyYH^1x*r?wj5gvOWy5UN!tThQ zr>s}*|I2u%f1(fZPQ?>eypuZp9Ex}D4+{BH@lLa=R=ksXQQ$gH74LY;c&CSqcYczO|RRRk18>e75}*s zGt194=*#E0jbzteRbtOw3YU>_J^$oYTIr|bkM&N48T*S1TiDf+ z{8#ZsbroL}S!l%ibB>YI2AnqFv;n6LIBmdb1Mz7CrZ4?5I8EbmbYEq*l8^Z#`+0 z);4h3O1hV@Re=fe8PF@rb=vd(G28soc_@!prEQ7WOOGJRA5-p?D?41W8NN5miw^Q< zZ`OCC{4w^)LF|0OLHHg&>;F|XhOw%=pMc(L{cp94GN4{?Og{ZA z0sF3W0;m(ED?nW-9m+HNV_LU>x>Y&{)On`Q>QKJjX=D66Ol3 zLp&ct9SW&ix{pBWR>;0%t{T)io^^nHFFI0=oiKG3pY5Uy%6>?me}|{G@TYt2y4_AM zJ_g6RHc*CMYh>^?J*2y;bWl?&ErW=D0qqb(`b5t=4mn>$zIz zIj-}n?;O{Exjxff)^aafX5zSRSMFKfc$O&lFRzcmrfkKpU!%H1c5KDHEFOHJ58v^@ zyQy$4#z(u#ewehMf9ng$JqzzI1-XB*kHO_uGvb-;R6dALjQ6T;TOI)7_8rV|&3|g@ z4`JCe(A~7xzVL%7pM(((+wTU~hOH;O*)uI9C~%GN`ohlzY)?#kb?pwX#AA_=@Pg6r z#DbkJgxAze0H@l#CHjinia_RTu7qbz^@C2mE&i?^?r?CzDk}eMaRxY+@;qVG;m9;8 z9Czsc6?oy3yUVbz`0tP6q^qlV>bmPAuGlwTvF@pD@@)%|aBu#=Lq3KGqz>l*n~lpM3S2Bg_~gkkV)8MIXVVZNDnHFm0_O-^&cW1O1*)2EK?Revocvd();p{&pg4|!fAf2>2kQLfBJ4AR& zYcI%MZaU%gjS54KjKv7|XkQH4wCGEEQJnBw39GgUD;cPdN;bk%ESU+b zz7SS@B&_;QSm}hY(iLH4tAv#e6IQlOc;D_UIR6MM`y{OFmawvC!phDGn|1e$KaF#T z%Ks?FdVj^-H~FY_iODh^TPG8^c0Nrw&yhS(z5NoxKejIbL!PuGoa<+W$t|VNuW`6koldgm(O$&guwI2S8Kgx`I z5Ay$5tYyP{!1cZ3cyGAA&s)wFz_CQ0c+a@L{~Lend&kYO#(MhRapb4(7dOWjW&3Zm zt8^p#Q=Iltl;iiXDYNX0P4@-wF4uiD=Lp_iu62TUmup>F>y4#DSXxThg||R3tn@?J zT*u@-D5P%y*p}QMh4c*w%Y8Fe`UZsMerl7x0b#k%GU*!-misT0z5!vmFEi;I5SIHj zm%ah%MDF8U`UZsM{?4UuKv?ekT>1utr9Z%>Z$Nrem~^FR7|N#V5>`A3tF{O$8934_ z*$69{39G&kR(&L_`c7Esgs{>TVP&g?l?@YCwoTadZKF1MtoRdF?aI$kKaQ9~ z%Sq)*e!@o167-F9+$nJtFN+6_qxL~GAIaOnpYWgU@6MV_NWV%Can|4eRr{3Vf#d1$ zoeVu<4j;5Lv=7R4qwI$A+~BxjxnVbwkHc=L9@a-1!)|adb(}NEa`d-}#+c{G$8lC5 z`8)Cy8S@PQ_F*Ngq8jYt8pRuu?_8${43V+l%mJ^;2g)l z@i;oi>(9mM&UxotKb0TzQS0ab>OSuDGwDpi>1X~;;~?}y@Sk(P`{(X=&awOFjh%D9 z`{$mkILGdvJ9cWV#8@BCBlL4c^iTBjM)}!?^FwvcLG;Es1fKg59r97<9O&o%;@lGd zmgfO@2B*vQIT-mvSZEKF3(f&yp6Cr=g{+muHD1oS_P?=aI_I5p-Z_1h`1e)NN5X$< z{&B;9az6L@8$b7v`<{N^;TO;Hoa6Y=);o=DDY==Qt0=b3Z)4#Ir5@C!e3=dt& zTmSxjQ1!hPtnVBHwV=_ z59F^HeiJ?KMgI-`7{kxvhW~}{(d#wl7w`2ezYo_TJRe2B3;jFEhrS1d{;V!Xe-O`2 zwV$Z@Ff3R639ELIhn9!1;h%CPKb5QZGYKodPt!Z%PQx$8e&Kg>i3We;-`JM&`v^-p zQ7?oIf1K(_KU072f#gvAB0U;>1Y*UXuxb~u-0(xG9j$*QKhdb~{`?9%$C3Q3f6O>K z$LpUpUe0;v_};@mdi`|HyMOMybB^6VckIx=IeBd{tC24+`7R%WXADTf{pUO*f6K&X z-OA6-vX;RaiRYt;1pMu@H{@4kxRRNRm&XY=P2$OY^M64&)!0HjZ@M7DDcy>3`-Umx zn?9XWj6Yah$?`{E$~zYJ`7xBacN=fsY563=Nit;Pr#tT>{CAMS)XB$Sbx#P#ewo;; z8+qdjn--atXmY_S)<26o;krA!vBtjn33pBS*w%ZjwIBSMx-T|g(cfd|AA@CEVAz8L zn|+b8*|ls^W}#)4eG$4ZvX4Ud@z2!#EqQ*cT-uBzZA{u8Xxj^VDenYR zHYsftw5>`T25rOAwn5vrw0Y1rFXsa2xgh5V=s6F56{SI@KnZTXL4 z^^B3~Vr(UO;ByEa+tKqCjK#1V<3AM(;#oGuZdi_GR%~d!?~Jh_mScQ~ybvqigtzP+ z<874N4SL5j6^yf042t}P(XN!$ArG~I{4qW>7oBIQaisGMHNI$5dfa8ZoAom`v_YZl z1jmi`CX~@*TuhWvZd3My^x6)QkK+sj+cesx&yWw=tUkj)9)|q*UX)`!Ht~O>zsIHy zjPw2~o569{_Vdvg>lpR)b4;3NI4_lsas7~V*4&k2PwNKO!|~U19mijYvJGzlbmL$A8kU@jXDodd*NY z|1)E!&*9aW#@W~vupgvn`2WjeSNusQv=^@W80Yg&-JkP6H}9k#9q(b7IKJkfa~vJt z?ZkbD*1tcpe*Tf1063;jdP@sVJvjC7=WM{mrH4I`H+oipeAGf$>hjh}G7~n-TOX~! zlRfmL@@Jn_=N|K2O?r-_kUV<;e|xheVXwf9yqbG`!tNt)uuP3R{tCA~Qk<`2#i;!A zV_EpxIduq|?ZyTEEqVT`a&tURe>D_%u{;9x)2)3!I3yMl_Q)6v!4vKfF599GOw5xN zkY?$L;?TBqF~VtbWrK#_*CL#*$0N~uLVLn3!eRv2`w$NASWZj}9zwYKl?wJ`o5Klr zdA8Hmf)`~qPMMniRu~I-Zo)G(`Up&mbH67!dU_zvx|)^ z{TvB#ElJa#Cbr=Q%2HdhC4faLm%98oSEL^kZQkmPt#l@6=#Jg!MQRxB1 z|6S&nwqe#!kUnrZYHdD8HF73#sVIU`w* z9I5!69yLL{UdJv4CE>-cR)Hg1FR^b2yfsgoAsL+b{xo$X7&o38?R(Dfs>Nxh51@cza4 zljOB+cibrs<3Bfxp_t5+2YqhT7y8{9VvF)*ndaFZm6v%?k{981Dt^KeyeSSnvgYF% z?zLnW3zdXpZ}RYK{*&3ci>08p_=Mj&u$pCjRR&(wO~nf(KEfi#+F;1ESL|5CbvCg> z5M*BcElbqmIcwXk0wfBsv#{?I@|Z=Hp;3|fY*Bb}e%qxw{K)#TOHWhrK9g#JDchgH zZxiQZd8E$M*R2QpGP<*TS<>(Y-_?UL+uT@(Oli2skM&?fR4%q4a~huQ`+BhPXFrxz z(r=aYn0rmy73l?YvdLU;ge$tO#awTMrOM#^##V%PPV~fFZ-nJ<%=JcCeh!k3Fy@Gp z^~o+UcO2#lM7^W^9vpp(Y*v*EELHS`6(8i~qWBY5?GlzBp*)0@oP?G9gfYLLp8N6L z$0LUuNS(U4#C0DpHCq#<`-nQm_OM;lJ?a#({NY+xI98}rEW|NHog$W>bNP!fjydWS z%OyX|^GFzNWZ2fEI&ed2rD@WEBQ5zB(rQ1d1)LUeU!E$ zbB{Ut9;bbL9_r?>Q74W7)Vos;PCfiJHt_591MN$%B~I+rkJASJj15?G>B!+T+ShUT z3Z@TX`WB|oVfrGHlfy?beHU}T9~QPwwqvc0=#v<}4&@}a#`1$-h`x>C>rhT&q>=LA zK0|vA`bdVaLpg~pJ`sSq8xboXPWu54zgF=fe+ApY{vf?-m$3X3{Zzu(4(bJIl>CG{ z>IKr}u!)H=@qjIHB!m1s@O8+FY^5F<$JD4jJWk9UQ&MY_SO+F@n zvt3gj$PPZ%=*`rpsb^FFQclOXnByhe0q>{`GMBYu90g)U zPgwB*ELZ#qt9A*?k5C@MN>0M29j;5)7{^hU$C)p#;u?6zscPzSOYbyT^^73BuDiQX+&3MGre1xlx zZOA=0r6qj3cqe}H*;TUHJ0tq>(@z!; zEdKXqiEfLnvz&z9SH!KzPE;<6r-$|<8xTJ3UI?l$FH6|fyDB7G;7-`IFO&a)jCEme z-Yi5j?{W})+QgUefZ9di^!(C<%Pz_VLmpQpoH})C_^L)@!q=DG6oF~2Gtn}|my0C} ztaGE9y_$(Je%5(Rn{5~E3ny4-Hgmto4#$txq`D@awe^OmUCrV%^86I>aGZ7C)23Yp z;oHUPyD77YKc+6)jh>@%kN?ab1UIY!F+XTF*6ZT;rnPpdnP=d-BTI#ZRqg2S;XQVb6lXs64dfLe?k5dUoJZ z{2{Ylv7Q|yJeY&GzgvT7)-5Q*hp@tg8`Ap(yO)zD;WqY*$69{39G&kR(&L_`c7Esgs^PlgWpm! zA>?Y=60qGHmy<)|CQS)%%##U@4Xa1ER_ol*etZ?eyB8G(pYml0*S^Eyd`~~Zxysaq zQ};6yZZ*6OBwYHE^iXpgW%-RQG|Qi!XVxAEQCX9g~P-2vq@LzD``74 zvFnJTkYj)^(Vx!S7p@kIB0R^Z9eft`BjLo!t3%z=ZY0CBjs>A>qd>xClBb4RwHp)u zas6>Iw`W(v?|KXo`}{%(hm~4x|K8oQ4Uv4gtz&Kr?{7SW1?IPCUPm2g3Hw-eOC(Co zXVkNJ=4)4whcvU=YLd7*PsuD9gl9XRa=j(nwcLGqu^>xk_u)hNjtN#@a6i@lb~kyh zI`V|&$2^ceej-=vth~vlR=m=?_YB9VscS{PWr7t`B$({UyXC0Jv3zF&7k*)bHAj}^ zS<7xuvV5$%-}tlJIfoKW(WP9@Z)}KJu5ShP6T1-4YZH4zB_B)9b~%TF>-U!YAI8pV5685(lH=Gdf0jeZ zm&AK5yRhDBZ$Kg!-aNb2UX>}HeEoQ?h|IbTZ?9E}d=Obk<{*~2UsO*bA zqs2ZN7`6xGCf%jEI23l5UPw5jobQqS?+`AMEf|sy$x8icn4=D4NM=0``Z{58xa4L% zt1B`vE8NKuOf)Y)y(1nB?nk&)p@rhjMN7ZwbLJLiyBN3O*kJ5|aSvjQG2}0*i@qer zNm!0C2F6c_F~*Re5te@f##>m9F$TtAh%v^{W9j0uE6ON$#E00X!3WRyHGgiji)B=f zw1%7*w`=)LeM;I0{w&F`67zpPP4<*6dFecQd`pg*>8;1NdZpw(dVKr%`}pYbeR#N_ zj~?GwvrG8s@!jz*tB)RE2tMJh$G1WKx!yRw^87Dy!GewyC#KKq8W|Ilgf%)5#w)mG zi+nULu8i6ds*ud-T9$*$uXwo*e@TiVf=oU2W1aN{$xwNHiW0Fcqj1d zdVQGhfnL1Sj@;p3VFcl zoNL0@)bwC4TD@fL&$Qszn=Z4>t@(~Mw6)^?7dx;*N!HjNe;Gn}sQ+i|d8R&ucRxGL z4hOX75A$AOt%~Pnv%ESGu5w@jTW@d5lgxAHYbK4i?Fg}!{?el=uK<^A zHv`;w%4MDSp1V10RU2KV@r>%`CG}#>%a6fkY_4^VHmG%uSnC|I{2`qqFzcG-CcVkW zJT<%XmPS0)LNa9WUx2s2;IYOP`gdMdqRzK zI|N9=3Fl7O3p#Y) zO1RtJP7t{AGU3guTEd*Y38-IF8rOytV?H5#WJgJuBHu?x{)zHsff;G)5;n);?}h_A z%@YG3Sbq3tH{C?g6YIJ4x>XD93Cb$J-8v_<`e@*0MV5%CC;L*lty+W__VpmbD{s{l zOHPLp_S=_9WUO!b{28Yov}ZkJy%QBNs;B+P6pMfNMUP_r<(SF6L#_d|j)B}$y!84Y z_Zly~Zpb~zORp#RY^uZFALy(P{f$i9Hh61)<65`FUfSPCR{BeC?Qi_pXr-6-H_l%V z_tySKvS%S)+TZxfHo+VHjr-Ey==^T9cL(WjypaCJg;Kk{=1G48*YV~32jl*`4e^@n zT}q^hfNe=9Bxl*0y=FT*wS=WJMzhuak670ZP2tLu{p|DDi|l9V+YjC9BHx(-79f55 zOdhU0_TXZ6sX`g(d7~KbP&k62Zx1W0^DYHB+juWCoRS4fbMWs<)AnOEI-rQ2WF z7D?a!)zg8zL+Nz3mIp?O$kJiF;EZB{a~@|AfwjW<6xUK^1Jcg6;~uB>GC-{MIKpc0 z1Ki`(zD8K>cYu4G+SdrH{SJ&h4vamH=EacAh4_(;WjWgaPo*32#VgYgURS0UkEpnX zVR?@8L-^ARB?+VMdSkKi6mUFYdcc2eMj_55i6gPF#4wGmtr~kpq5|i;!?#soL@Q?MQdHuSD`$*Xf2{qx~00E zl2qgUM&u&g%DoM*oY;Cl(ECy^KJod6U(u^^BziTDM5D%$u-RY44+}J*bAH5KPnVe@o2Wcy~{^>Dgh}BpVRyM$~T-gR;Wiy23M-D$w*%*~8+aqkf6BVJ$9q|p?l#Y8O zA5iW6;yD`HrjBEj%@QB9Wo!>+LmSs|j2w56??%PTduG-Y6jTY5eGZ;YLK7V|4vOc_nt%|5AlKy_8$2&;KO>!O+m zgmE5N^X`}P!<;wfd@|>mYL}y4<&R@tn)6lZl4#^}R`iJot9d{e=ch5h9qRtngva|mNQ@_8$*_o|%wtLO{9usM(A znVp)BLb@0<|P#d>B{a`=0Z^MbXG4Qd|-JKtxZHLwQ@ zgZ$rQAza|ZP-v6i`cBfhOI>nD1a1jOU!1WztjX_2<$cdLhs0keCcL6$7g%`x z9LX?lP*3PlY6oFgum13ri#0|^lMIH{eR@#&;X^~A=}~Lk+Z2$`-})`1SPl0yD^A26 z@&isH&$rerT|zWT&JBeE;du7o;!+?i6s9(8K=|m~K`=hmaKgLub%ULCju8GLxEahZ zl8og1WV$ea}1GdCxUd~q*##vs;nA-S)TUhp^iVwQgXo_?$) z+lR5UY{)uSQ9dX`nz-;a|0R~h^9_z|#g(s#yzwWlea&&7CYC;}7OfNA5?@|xz}-LFE{f#1CLYAp=V{j_gIU8pMQxu( z{L2Q{L{TWAZoSHMV4c_VZJTQq$`2B({s9X^$vTxK&erZ~AjF zH_X4>K0a#qGzCFplK)8{v6ueq{HE_&f ze|R&V!>r?{ZJQ7Iz|S3@i%sWyid%J?!s0yT;PSNVwjaOrf|D(Z!S;slcCKGh9JbzZ zgXJgQ+gm=Z3|m=RXi~bg_)63P*HqXW;<2ajY=(X))iP zC4Ff~)i@ulZ0ILWw@zW>T1l8S))SIlixJ%u`NOQy9?II+XDGX0D ztrE6D-r!cfBxKJ#T=dEA1I4^;Q03G7A|liWdbS9H)V0^ygBSWh*syXi>Ao%CT0189 z*@LzO_5DDX7rmHhecM((@cnxZZ8smcf40&a#+)k))qbihzK`;P#ifda$IB^Vz+g|v znYaM-Tofzv4k!)4*~#J(_f zrKoe174}X$%R;*w0pM4nMC@ldN!ey|6m^GXG02c_cnKo2-@8`0OD*u=eLq#e^xPc#H6SaK5#-*wnTRPn^CWWXtr_eyd~|-ovd3 zv@JEmUg1h9uKV@W-E~8O>G>h5_fdPAYJqgHmmy@Xi*T_De0-UANR94=D2mEkiB zz;9e!i_hZaB62v9xD*{_a$6SaKsNjGdT~A6lCSTAs-S zRr@67ExyYO-?nmxymjufyG1?W#bQ4w_GUkO*VYS0Zw`QI*%z`=&Anmd>CzB=w-d|a z?gL3@Ft|K09ZMVL16Owh$y*+$+Xi3{M!>jl1dRJh@Er`ISI@OMj+BYzeI`gxF0dRkjHl@Nm%O8c8+UYY=M+Z0V=wQYj9n83+Bha{`L+t%%_$_^!^2>WvxN(mPH||m4 z#yu+BxJQK>_o#5=9u;QXqr!}PRG4v(ip{u3#ctfAB8+=fgmI6GFz!(S;~o{z_o!fB z^eXZ(*t7?EkB2bs@vs~Bc-V}4JeYBh2Q%*R;Kn^3+_=Ys8~1o{;~o!g+~dLV9uG_I z|66`jPI+I7Fz!nc#(gPejr&rVabF5E?n`0DeJR|yFNGWTrEufE6mHy?!j1bIsk`30KB!G94sJlu4?$45- zs8e{S2dx|N@f>YIV6Aw0j%JE~$p&Vl2cBTnB>L0!r_XY_Y@9q&4;XN9!Rna>=} zXOZ$e#qo?%+JWQQrFqU|j*<0Vkz?%Q{2hmXu}M1PG0%I^=4 zCUZ{dIbi*E-qE3L_piC9!l_TEK7VNgS|8>dH0P!{XU(~6&T(_@n`?qT1J-l;U)B&> z4;8&$8*y!*{YddAtlA~4LS__U9b$(JJ49=A8052rFMi&&7|3b@84|t3A`tGyOj)5XP38KfcqV z+r>Sbu<}z0n|`Nx&VqZi^dIBpeSUc!g6}Z{YE$+r&d(;K|4nE0s7n)L`}pG=M^74y zKkD1X_c&UkNSPdGU(!!>d>7gDv(z&bqBpU+>ypaVJ(GmhJ(Gmh zJ(GmhJ(Cu_b3w)p9uuoOC#|-uJ0}UNJ0}UN zJ0}UNJ0}UNJ0}S%Uzo7EXOi$d>z+x%>Yho$>Yho$>Yho$>Yho$>Yho$>Yho$>Yho$ zW?xLK?wlkVb#EkLb?2nT$GUTp@E@gDHcEBl9y`~BzhX_Wc;Np|eLD5&w1NMBY{2TN zocHmxUSoUCwv>H2bxw+K+Jn;`oHpRJfxprQoIZ@QCvN@5|D8H<>g2DofnVCwSf63M z{b1|P`E5r+_@t_R=ow|f8ohbK8P=Wip#dFv&rH^x^PO`wb`FTI?c4^wyG7tWK3`-NNIDF|tm zo2Qvz-GM)EVPPI9@5w~Fx^bKHe!Z>Pao^P_XOF4A=}`r9Lw!F>-^%oGxBdL zm!E^ABP{DV^oa6FzEm#Tk$tq*Lwr_<>jCn_b89>UM~vs$`dtV4r{jAAc>az5kVd`# zKp1JU4wfSiI9O|rJ%j3A8QSxxy&nS8SVjShWX7~<747RWCdl$xi@4~q6T^RSh zgC$D@@7%d`+6xUD(YS1%H7`n!OSW`nqCbpFZ~0z_H7;w< z>(udJ(CVdVAn%zU+hUn*e9d>FuDoY{%(orboM)%Se0iTd;tu|wiG%W7uQH9b92>l6p2ixnyoZ^_8nOIQWBp6~AMyd@qWBY5 z?Gje<5LWlh{0b|1sQhF2e9YbQCJpuSFF5Ik8g@P8)FAfYSy(-UiHj#!M{l zF5o&3h|J}|buJH?%0!-k&R)jL&Z0jBtZa zC)wv;TlqecC7i?#J+tzFROpkQ#rC#*ev{AN0n0l9n9c(tb8v8-gG1)#;5s*l%-O+p z&JLN&gX>%#GRFtkIX-0W53X~6$ebWt=LC_tLb%QqB6EmvokK+C7U4R#h$(~1>|FfS zPu4w*#ST{E11DH_Db`5Tn!msQPWtmME;EBW^TNr#A)NM2FWxRl-9_Je5TATz1eH(y zG?ZsO*pP6cTk<}N_qhlU${fzCgs!HTsM+ms-rD~b<^GuRB%D7vvYv8+TyGZ6H*TLw zF;p(UVLT+gb?)(`+feSmARj{+SU@PB`BhWG3ug}GQ8UI8c0JRFPfZv@c*@eQ{30A9 zob+HjKDp6T!fn$v;!EyZah!M7YP@LATx36{9{yWc`DWxJnYd@Aw5ylq{i4jrUS`yzIs|{_uspusqXP z{bV37Q7fJO%M+u-rBY!W_7{uYl{l+7Q8S#^98+rN)v~kgMtlKA+(B5yBY<&-iZuwU z7=-ffs#t@tib24LJHUuL1kN3qV*-raA7JGE03-JY7`Z>>ou_GZYz;MQdeC=9o2f*Fmiu@ zk^2LT+#imSm~DNWnK>)Bf>JT2aXZRBlCLT7@1>AG%}wE=zJnFR|x1_ zAu@*u=o}(4w+QImBG|5x`@@NGkbYYy@|{k++dl5Uvmnp2qIs6^d4>H#n({D2O z6VuPa{YS<-%djnTUo!VAb00JJH*?=p^3Yyq?vv*J`TxV6DyT=)DgJNzp3bqeo+(OO zLK`7FQEQm?i5$-qaSi)#-1CNG<{UeUs~pdR<$QNM4|a~76`MNOOh+t^wn1y1{Eaq4 zSWY6Y_6(ilg39H3=(wLi?m04+v)0KEzdy`BM9y+c3r;;a_29Gtrw#m$4Uj)&X~;Ua za$=_*oHpRJ0jCW(ZQ!431J1m+zn}Nksh_`(epJ3x^240Cd%Wmj#@juDZ~k>#D!(ns zpz_-iR{3oSs~oNtGvmCRo-O6DsM7j zl{cBN%9~7Bq{tDHP38Y3Tr<~DxVg;w?utu-aOfMhiQaeH z0^x9|U2(z~XIby4;LiC0=a%`1%T8EEG#w5Mg^J1Y63?D4gJIs$9)u6N_lKEz=Mt_k zpeN+0xP!3DgG@Lqx)#*!pN-^9By(ivyJUUOsoH|PaA#{JDld^V89W_ky-K$As0nKgs+%&n_K(G~?d5enw?I3$uJibzaF)hpNAXReuSq z{u2IA&dQB@Vja(LP5qd9Gxcfe+0?%|F6Mcw^*qHfj*fSt%yE}|9QI(^iD^HkU77aw zug?@EFZxmAOLnjNMOgLgS9&w`DH)($5sj&Tb6oyqys%%I-tj#!$p`yI<*Hx0U3`~} zu<93K)i07$+ndTe%rNh;$|KB-Ji-j~2&-Jf408>uoW%@t7OOnM%*a#Bj6B5*^AxMR z!wmBdt6akja}BH9#0+y28+>%$VP@nY{#~qc2iq}su*xrN$Na)7H!(AE6Eh<>vCYU$ z9E-V$RX$>d`G{2x;<82#Vw;hJm|+fLl?RqjkokNyW-^Db%1vxHaudfIxruE?ZenKS zCT2!%VrJwfW=3veX5=R3Ms8wmw zBL^|ryB-&uu)l>>4qqGQ@Kt$!ZAPA7ZsaEBMs8wmJ^0|b-hH{pZ$5$J%wO@odqJzPCve?q%X`GaYa;F<;JrN%nj*F zq=J>-q~%#Z$p)T3=Y;}$UXz?JHeXq$<@|S8$)4crT5lf!) zU-lqAKW5Gb+{J@8-SC>_l=`{mpNf~2@+T|r3uS9uVL3Lt@fybqL9<8mS^Wckym8~A zFzyRaw*9R?U%sTN7&o;uA1LiajW5UXRpZWa+}C~jqj(fpmESM?6}vp_yeRKikH_vm z%)0n(7fo!Up`C@o*in4;rF|6@3A}BlM|H$AKHh< z78}Ph-mf5T1`OaE7q(#eOO+S7w-4fF%H?A>ua*-FS`6kXAH21Fy{EjWoGX+Mf40wd zz^9^kzA}{OYdh99MpP1wU50SGXExit>6JxH-XZ+ls6%Dv&#fdj<`}{koj4I2)~BMF zaxRpw-yUrD>sUb~Y!k{aHCbhU)1kZw-a42s8hz7#W?wn6YIX?!#6OEzIjfwA$ufvX z-I*6(wOjnO zvyoVJswKbo{JvN>w3UFgoq6rKf<2!YEMBB&&71DOA--MPTpYdHm9IXtQlxFsScGrw z&8v1AD^5RcAnt$KkDva&n{e$^Ph`G7fLDkP64Cc+2~jYFZ@7?7bh%$cT=X5xpXR-1 zFFm@Nh)Nd9`yX0sf0(I?NN_rom)%|7?%JucXzMnFr@lWj_U)$1Vv58sBFYCo8B#^W zUJvC@y*zD!tE!5w{X+SvbYpE1{?$do3xjzf54-Kw?HVF`_Q8B!vq!cvthUJVcn}Y8 z$;x((sVmwH8_0c!7iZ`9HV{wR_2+&+Alf%d0;W1vY*yRV7z%x5!s^AR=J3nL(tK@(RHM@$i zPwVn;mLvz!d8zo$R)x>$nG$+_eq3BwP?m39lo}E*`cX{TSCHF^q=N*fQ$kz28$VDc zBOKhC9SU|!#dqJz0uPUN6xpxUUie~WxVI+-+#Kc3y=r8D!vRl4 zjiAE3Q|GjBJlRoEQGQRbXR_4rIQf_2$one%i{vTs4hmR0XOchu#(%?IJqXu%;RSnF zKW5doWrt@+3&N!zqSR}s5z{}pnUNC!+dab$$r-ASzc-j{Sn>nzr#u%f%2%f1h$3s z*^~=w@ORoCMPXqLcaf-A034LZIHM)vvpVoy_a@>_|2(%3~ zj)3FX^5?}OGEr5ym@FmiNqkh)5P{$=$7^xWQ?b2FVF>P$76Oi?0FR;Wkfv4!xO6ic zlyHnHJQ=Up1E*II zKlBTQVw;xQQ!K40mV6%yeFJOTOP{SIYUCaQjZ-d(JwLOuNaj8S`lqWHxOQeGarb2? z%oyxtTb90}7#JA}Q%+8>_1jfmv~~-HZB_Q$zP(*eobEUnzOMJ$mglKlV+(~q;5c_S z=52Z5zHlHE4k^c$bgn3hwdfBGc7Mw17q2XuE$t1i-%e(WN>mjuZgz)vm7 z4j&AOhn%%tcCRKDRt|;B=fALRjH)8eo(YA?OH0^>@2V`yYeA<3JK`jxwGz1F%kVq^H zsUz;x7z8c*dWsG9dgA`#0dU`~vUup)P=uB32Z?s}6!lj&7AYF_hUPzv7a^jVC?3!q z%I{nzvL9!1 zvc+jv5H9oGoTX*U;{81l(5-v0XN`Po2p@?`=r!rtQo`f1R`x2Lc^cu#c_O@~i@t=j zmYMDK=2daR?SrDdGI#xsLX#*cfv|1gq5xcD;<(NA9VX+oXopY%zX&II*TJ3bp}fq`AR+May)}2Y@Ufp0>@dId4{IW42fQyfe|*(;*cMnsZlek z9mJ}f`l;v%D?WfUia%l1E@Al*%0pPmN%+5gCiyXAiZr9{cY(cCJQ?D9yfvIZ^d-es z4=V;hfsofWEUz8i7+NkoKs1xj)P&X}9uQ4Xj(p$~HHe{|r2T1^$eZnR8`{sEYM$Vp zcn;AwsTK&E^Q7Zg-e;ey^gA{ay?d^0;_IYI3HzK`FFqURNjx{_Ob;8feM5D}x@Ctu z<%@CTpK|STk>zm(qObXSp7`0T2hm7bgp`T+ziWF>)P0eHqs+1&*dHpFZ3@{o@tL_GHV2dE38mwghlZ$vNK6tZoSE#nrs*LEvJ^x;=)+Nb5~PV`bw zcBwC-mwghlZzSiPm8a~7kHk{l>Bn8|Z+8`=y0_D0XS+InO7v1^cBwm}f3$6R?5N1S zBpZ%{mOo9kd$u7<0;n$PUiTMuujO1nE6i56`EIJ)X-8rnyr%-uXHS-mzba^*383z^ z9#HovCyvYY{72cXGg*i}*XI1ZV^m)1*TF4!Secb6wH_Gi0mq{J-4@Kfz!Iukzgr?+ z4eBLs-^qvj|t>lUQ3Z+R{VLoP0#o4x-2YVLz1}az1rK(PRIxpGea?cQ-y`+A*?8Nyl+sqWq|Pv{kH&eZszBdCi}S@=ep`6TPZyH`)?N zBmWT}tc&A-HjFs+;XSPQU_Y{F#fR$N$xiX? z3TP)JPrw4350>G-nW-|cMTxgiT^uW1UsPRMgRoy`+%wSq3`mdTfNKiUsCi2CYF?9^ zYTgllv<0L^K5Cv4{jsT+MZ@QHiC)cXqF3{d`laS6)qOK#xj6F3o$BJ4$gv@MHLr>O z+QgE=$8|NyhMyxHwu@sT$A;>vb&_~unI13Hy&MCotJYP*axUQ7OY~};q_&V&kC$3k ziT#=d z8FQ5-TzF}F&xsjo5?Lxbqs|xMm)lG zyo2RB?m(V8-a$Ey7>et71nG6$f%H1wv24{5PjMaZAia)FkY4#+Xzxtu9B1D9jt4_P+Z3&NU!`=qSx_`l2gZ1T*o^| zZ^S0(Q&YTy^g7N$tm7$^LB~5-SH~$xqx^HygAqgV=_=kqdL5e}*0BcG)o~N@*YOV0 z=okbs(%}k%G&?x)_`2wlJo^b%`S%tc&q3`tFEzY-RAFx<)*r+r^j# z*E9zo9a~{t9q-`hIBqI7(QTp6$#o2Ze2jPs=L^{`(&)GYdFprv>5Ujlk2~>Hb|R2o z$2&-`V=FAz@ecAg;t^~U<6=O19cLld@f6n8@ebBCViRpA7$azX2&`+wQxu!x`l9M$ zyiaoKcn9f?7)sAm>X(i?PzD|EAia*Quw2JG$X~}MSgzw8#h>CV#5$fr8XfOoT_ZNp z^O|&`V<@CC;t|v{#XDH8;|}Dh;~i|vh@telO8wF?2-53#2kDJ?O0TO#uj3S?*YOV0 z>o^Osj;D}D$2(ZAV=KfuZo)ka=YjR(#DA?GklU|fN%D=)It8-&b<7m%3cQwyrC4u9d*7PmSb6xYi*E|O{&xcLBG0&6Db7sYd%Qp47 zF=5p%VI>b?^L$&$Pvz=eR>G>kn*J|+=M&}pFkbW?xb(Sx`Aix=&oQm8SJj-E(C>nD ziK}?|T%AJr&8H>3@n<59=dFe#jRwwrTluRK84? zOZsJ+Uh-L{`AGhen!o%VsoRyGM{0Rwy+|#msyAGU|>V!yFHB`4~iFzN~0!*cBp z%QX=2pB_i$-_p6FUO(}3z4jv3>o#J&wj);lB=OUG3YP2r2(fNQmDBkiVo8ra8`ahO zESBp%8nNEr5o;d+vGRp*uheI}B)|Nd=7CXeGw9Lx(|iak{)AP#9BH(Fh*-%<xGkJjaM&add{8G+(M&leCYy%D|ArJ)}|kC#=TB@qG-`BmSs!fH+$-)%hEZ zTYRjU)}2_6XKm!m{x7VVQjcENh{fN2=N!8~_Zj|BQ?F`6RG(~{*ju${2is+m7hmxd1SpPEvMucrRA6HM5(@Fzpxzl2<#Wq zMtVU! zt2kmzEH``=X#@1EU+%RZ;$Osuuj23>RJrz5FkaTa3i6>d0mUEBg@~u&tDrp89?}@T zisPIF%kiJ?Bl;BRTNw1{186>k4POQOMdwi#AM4pYV#8MTy zmfQ}#5sl%iXg!lWhOeT>Mfxhvc-fkdPCYpF5EnLpTK&K`uFn~yA4L8Rwi+Mj4Bk;w zy|Jyhj&bDqNj%>JZ+%xC$4=^0`Y`z897oi`pE=))zj6E!!^v?Y-wtJWVoM87JvjC7 zCvAW~7}3br(qaT3S*gBn``Vdtjpn15R`s2oW*Xt|?v(O%k0yKgZeuAZ2d(_= zEB_`eKlhPzgk?P+S)Z`v=Og(N#&%?Tx;$E!V>_B2+tGZm9nBwq>vr*TEf3byaw0!1 zzts-5Nd3ZcAJs3UC#?7oR{VXDMzu>=$wOGlNf_HfeIflf{avS6dW_(zznUKPKv?OA zu+kf0*)Hmnu#^Y&tmQ=g6UKJ5{2#{4>Kp!V{rqZQ(`S{Ad=2LF6!STY`TRxlay*wY zpVydYlBzu&YscrE9)NOS`!d#cy8m_cih!?!L&p%NF#sy%D)NA&wV5v zVOh^d)+a3a`AEKmu|?UoE|1pb*p8;hb~GPsNAt(ux?TKS%Y*f_oXAhhZ?$9fQI-3s zejz4&h=8)0k*|HgKu zJg8?aC+eRtwu5|;W=8avG1x1_R{|Er44m4Q%Flm4J0^qgWx{3OkB^xVorieVTRA9Z zqX1@geAXd$(Jy;BHPpDKDr#+(e&7k=7a5M{`gzBi=S(G zu%4C^`DyvBb{ze}@@VX%q9?5Q#9+DNPgu1}Sjj_J$w?U7L49G}3wOGwxAYhRs=t~Z z^*~tZhp^HcVc9O~ldzNr^-LJ+p&pHKA^c&ytiIv@*3XA{K*gCMIkuzeu^r6^+tK{-w{90d*YaRJEhqBR@>}g# zeN^SR{$Rh5p0MH*qxyyX39EJqD|rYjISFGsk}u(F`TC}}bQ-}`e>FYofw0mKVQdHW zXy}u$ln3=p80%>{u^r@#y^(d~_fXQ%*;ic8JM~Tt$5!KGo%D{%Anh&g{pWS*8q0R# zZ=ICy6zQ`{=h(^d{WG!Ze{t;OnX{FLRL;9Ny<^jQ$1MKrQ_eeDTjF{>kz*&@iNAPU z&O0w$Pq0lBJIB%SynxpBKYFebf8+QeCeZ7(8c*`KoY<)!rw#lm8=(2Gbm+vSh!5xP zdarWo$ElP5#0I`?T!YsclauzUj(6Mf-DjWBIZE}=zIR%u;Nei_W!_f*6!kajd-2Ksj1yTB?5WAF$D>)jd0_gPF5p)yx32y%*vlVuT9uLusC0Kycprr_3Q9_1+x;K zS3Q_FUh_ST@2iFVczCr1gcCd-%3CDP^(!2oGW;j@S$pAViWTD9KL1F&vmZsUl)DCT z9J^=r_t@%R7)JO?qLKDZgDiXVkLVyg=MJXw74tys@7RN|y=G!~?AL;DST8Rq(y9XC zWv$CYg}GLK5EI9BTN%G<4*hQ?CKp+Yl~3BOE->cBSvQ{4jkO z^qYE~?wh%EejwD}GKOrd){HLD@afltzw>JdXUnAn)X&+xW#HMa!i0kh=Y+Rk)F527 z{1eeOeS5-pk1Q1lCiEqI4EQ>6OE~#zq9p5c6XdyQD~g_S>N+H8MuUFIc1{^r~?aeT_qw|rLURG|(>c`j5g4$t=#BfNZF z9jLZ43t`{0!H{y|ErvAT`}BtlkG~)sR5c7HpUh17+n3>Ruxi^_q$!nuD2y6bgmh)% zxM)jW9L{6=T6vW2w{hVuhFb551g+e}_~*Sy{(POQu)f)c5YAH5#dhJUWp8EOlZ*B{ z!l=A=y;4ZkTaW$j4Vl-a~_-LCpx7N9=cx%jg&UY5<&Z@h+`*l5|(l?U%w zszj}crtN(XUU{iydrA9L;AxtAQF-sot@xyj2?!@o-m%bo53)!pkD_3%H)Em6c&(kcn z5pFX*CC?kwgz)imM_5dnZiFK;4`iQ(hY;Q#wa7NLlw}*)3$C}Lf1OHTi!G zHf{1_uxYosdne?#E4QS+SDs~OV~$(?)$u_c*h1xZb)7cB*1O}c^Jzg5>os5Q z1zhh1a*yD8kC1x@*L#QDQ@Gw!q&!^jH71Tv8Ki!=UaRFA&h;8D*LJSgcDd$rz2?ik zfa|?L?h#z?5pwU~dhd{S$n~CL;<#>0uG>tn+j2c;dOerxJk#sET>tHQ{g?ZK(EEbi zFNEGN|F`Gj>Y%)muNwXHp!Mf`%=XFOi5*5LZoD;RI+AwweLmy zf~3$U3T?X2v`J}?QYtNIUu+>-{^xsU&f6*7yf@zK-hOjGAACLcd1lU>`OcY{Gc#v2 z*5yh^zSQ=u*j}>9R%|laYAd#yY`7I0PPW~OZ6}*=#pY9AV5KjhKEg^LL48LoeFya^ zvGgg_*TmA-XdbRS{RcX);^q#yK{m2K39-*)w=>0VlRb~co|B!A#mVr618{)Ob(jt7XtQyY^GJL9&@fY$n-5BeqoAB8^k|R_llQj!fx0s85Nd zPocghmcEAiAS->4ZeJSjN}9Tzrh+x+PnlFU>hi7|cfEVlwCLP(oPVjo#;>9;w)C;k z{q!Y=nA<;h{-r0nH86$dI{#9WA?-|sy_|n(YrnpxM^oots=Z*Cd3W)Y7~g7~?tH23 zB2J_1NlEMZX+J*XafQY?DT8k#tmi&`d)X5gZ(zK%Tx)ylxRP9VC5qIwlhz%}_`4U1 z+lhrcFkZQBb$naHevBvWe^>nZHdpT})|QGZZ`*P1wqX95f3=Ni%lEcM2iPICIvMcC z99Y|a{$3--b1SyCLq?WlJYqp_`}p$jBfN8FxncI6R?`{JBH0i5pcLb>zhu~v_3H9` z?dM|SY`=Hvvdmg<8mBwoPQQ8KmyE6+Mm%+GJwZ{@y7jk%e^Ni@ZZ$|R- ze$C&E_C0tYS7EIAsd4U*4YfJZ;P2+|SB_^~<@_WSZkici5)I|&x7ZEwxBYrCzG6-( zn=!m4v29WZ{E&U}$}^PfA& z-m4VwAM&thUMD-j*8QHp{YR|p`u{$;GxPLjj(an%e>!pHj}!RY2Jp_fZJ;>5}5Mx>ova}w=nAU?Vtp_ot^&m^@L0m>!53;l# z#F+e_mezxIz&R`f)}%x>tW`1gYgml^+Ln|NYhH}~S{P%$M#k8$oiX-nYK(Q?-MaO? z=;Qdg_XFpM4ByW`!QRuevW1RM9$en8`RF9ZXRrMw?s=Q@ecgEdoOtyL=M&3!THSc; zA+C>p^sQ?a4IqCmzMc3~)#%C*?)ig*ABY;>G=!gDe8|tyRS)!Fd`Vo^e4RLj@u+6U zo5lsJGCs9#H*@pqy&126>3q}fiOd*jjvYM4Jl(7lq z8JBVK+ucm}RRtI~8hySg*Vu9yFMn^edA~ys#_!#dVYU`Nhs#@g(ggFy!|x}clZ#)w z&}8m&WduAd<81S7tM?dh-M5n|Jmdg_=Sw#?GS~iCi}B-|OPUIcTQPqBi65gQ8uVto zrpmoh>)EbfYkvdXYx=Nj*Ba+$nQ5IOru9vW^3wWdCarHWruEGPt#2}>_05RZHyP9V zW<=|ojA?z-(E280THiFZzR6gZSL1Z#wf~kE;wLY1@q8uq;pm%HVbB)uHehq5t=M1>7G32ba zaGYKD*ikX?OBW5bqYAmb9OpmW%l`J{dVc=PgDq{r0d9PFdFh&V^n-5Pxc-g8cKxev zJo#C*{%krh+wpQo-8hn+JxOH}-Y? z&PQkWH5-m`edVm{+L>h^x;3NecQ!Cf2f2Rdjk<@L_BXpe_pEB)M3wIE!a8j++79-URKEb zTI+NRj$ON|is?Auc*gY>pJYm3SDtaH3%i?n1M@Myw8I7F!q*lu_kLS7#uVPzim~o5 zG|mmO>Hh2Cdn?+FwVf?$bI;y(UAJyru7aPw7&PYnZc3WriGW&pk3SsEa!~ZbFK+qxC_DA`p)vBDcK1O0e)#6j_Q~=^xW39YIL=O<SzNJDhbI+r$-jDjKxw-Ow z$A=T1sAl@S=y+0aWFcc4o^GJ4W&NIwK5OFEzs7Xz8hzPt3_l;eq++7Y(hSDOJXkP( z=cVzCqrP{()V>X4<;;m4lKX`V51KU3w@E{yXZ zR^1G^Ji)l~|FtmhU0Is(j{|y|*ZXZ|ZdbW~h$;5-{fw#aGc?}V0p~^er~R5?`aZHh z`{)k-b)2bpr}N#lJ7bvX`pq=v&v#w>m{HxoW!#}x8}sTrhZ)q-Cxz;oJAXQsaj^mi znUhaGm2sETKZ=@_7{IvIn(L$d%SSLC|NQ2}_2nnH=Y^_f)_B=*zW*z2<9D8NZ9!wL z=iDIYKA&7*dwuj6>*10iW9@Zaj%Pe>eTJ=j?!!%>lWU^!cKwQjW8iY<4YNmIGL7-( zXM5ZKoB2Is%@d7xSNb}g0cNai)3+JRY1U-eb$x$eIUk!d-j2I%UzTV6gTw7dGjC=5 z>f!zDbr-H-yl=mD_Ww$_^@W?t)wjof*}$S)7wlKU-nz0qL#sH z_LvIR+)f44I^h4*zPNo)U7q-8n&Z!TubrQH;bh03jT3vsYnF}X`g(F@98bO0jTx$s zEnq(@at1#ibYLZW=dz}Z%d|Vu9y+liN%H+0x!mp!krQ6SB z+;mEYy?AXe9@o8f^#nW4tmJXsL2q4X*Z$!432U6&;&^tsVa<1t{|V=yUqtSCo#w@>9L6I-jexa z%#f%Z;|U*Sm~C$sWc_rTJl?$Uc45}x@YTaiJnb&V+e-E^4O)N4n0Rhz3}YaV#(72N zozH9JiTZ=?HNLiyjbe!=<5EiJysa@P&A;SYmeX8{w2C*=~?_vt2wlv_Ce=k&&n^9 z*UK{L>@&)sbdKg}Cyz^lQZK9M+eiBK zZnr)(#2&x;e#V-68t*B2bRDIFwalqtU9QVow2#)$baOF#(vi`i&2CLZb4KG-zV++Q zPS0+i5@WxAiR;4eYhvv8J2CeApcwo8QH=e*DaLvYQR8&yd*w|hnbEH}AMC^V&N5|w z`Yi@mTh$tD#vkqWz>l6X*0g%92|xewrwlV>@(n!K?p|uVseI1itcQ~;3^PA8n!W?x zUFlEU_x-rpVP{*&c1@wH;-(K=$arzn4>D_CKY?+*4TBPWCpjCwY+Uc?v-?N$^Ruph zF1jY4TQkbnp`h94$J6=w;|;5rK3knHTFa?%y7Tq>*$m3%_mndBdrcYpJ*bTR-c-hZ z&njcTmzA;K5GWPpd8T);$ zjQxIB#(p0xW4~u|2ds6Hj(m0csbI~?R50|C9lyG^Gm|eJW}g4fty|sRX_y&N{BGt? zR&6|$Z*@C*w&$hs^j6O2xnb2~nUnT*Z8odANab5yUb3q(?MF3uM)o$Q{iuw|4#%_~ zl`+|8OZ!n7lijwoAC)oLb4&YC8Pk4LOZ!o|>{Lce`%!nm>CTsQZpE&Wy|rR*$qrkw z!(^YW*k`iaR_r#}b1U|oIAg`mYn+bs$*x+lt7LDj*juv0vDjg<&#~BNvfG(rx5=I- z#GaF#kHpRs2O_cm8tby8BVTHpINQZG$DjFP?9YO+E%j%_m>d4=7-N5?jJf2`nlbig z&=~u(X^j1uHOBrd8)H2l&^R~9Mr{`7zbx8;KNrT>pBH27&yg|q=gS!Tb7zeGc{IlU zycp|Qmr>(Am9LgTV{Hdg!Mfd%jkRK9$@W^Yy;<3uRKC^vAsd?z8%wq~65FfWk;bWf ztJ_^Fcxu5R@e^;jHLN19-F%z=(PB$=XxQu&pGw3_@*C+@$;)6J2d{h`gq2#-(ROmB{~Cu_lMqHBP!X-`GubUcxLo$ouT}E zz`}LWv+H~9fYXuJX`KeyGrxP9dHd~oW9+6YIx#-WX4p?ZZjgYS?^T*$pPc;@`(%1N zGQytv#SP5=dnWa_(S%iuTOQNFF1oTf%Y00|W9-7^^;{X1ezg4Q&UbRTk!H*tm$7WO zoISzh&%cJ{Z}Cco*?3xIF4x4yV@=rwZXNK%m4i+1i{^0I>#Xi+=FZr}SaVO~bfiD+ z^*ZM38VwC}KI5h0=9c|BFwVShO>}ZmcP{?JK~tit&%5#GUA4uX=?k{YvvexcBl3c_%`xgIy--Dakf9p z;_-IEorPEr4-Ot~hn2pa@uHf2ZShiHF&=P18~dR>jAd@~er=&$a!( zS;{*6<>pa#;FH4{mpmoIKCtKx*7-H-CfKhVJk52nfcAf7&^|CoqA~uzr)4t*H)d|C z?b>FB?Uoob!?n$CPwW@9ndtnhH7Fyg3^Tj={;aE-lgF6M6&+ZI z1wK6ATz#tB4^Zr|ZsxS21zG1B=VqDj>78K~uDFitz30jaro^o0xQs=|jx?QrxtPn? zapXCs%Kq;#9$l-m>A$E5mvLpy#-{JRZl7f7Dy7V*58b)NwV$q!p1H@JXS{dgebM8m z59Rj@)vX*|G0E{+`wjFNr9CCjFW;YQ`#tT>$88!t+ID@cAD8#1=^3`frDw8E+SZ?7 z8&%xEx_T=bVP9EsV+<~hDA3Oqea-FfIxAmWTmF|rnOC(xt8Mo>(AnG7mlUvuYy znPH30p2RX7wR(c>9>-ko+8%10-E_1~DAD`aCTq95dVe8NEV^;1o9pSi);N`Ky|0G( z>HWrxy+4`x=Kai$d(QvN*!!g!dw(@!@5g4W;~r?7?tC?u{5?Dd&-6WY^xx!tXgdD7 zzVFW8!^7X|`|)&~e&R3PDS`Wi@uM;SpTAAF4Bk$%&MA&TBykKVzCk4M4JhtGBykTY z9)gj02oxv5NSp+UpI{_@0>xD@5?6u7_DO%T#yOcU&9jWeF`#*tk@yBQ&oUDCfaY07 z;vvvH%SfCAnr9h_pFs00BXJdIOlu_Gg2uXx>Bv{}gkls}iBUkY3#`O0pqK_$Vj57a z11qr(CF%~HHLPBCM&^h!-Vlrr)8)T#N z=0@TbP#gmzaSSNFfsyzI6!*YL+yjb-U?d&_#Yu=HP6EYGh$Maj#Z`zTu7Vy{Xq@hR zp<9ZFAa`Phxg65dUIVpqJ8{5fLu;v5BMlcc^fnp{YiJ3sL6pX}D zpco5AVk~HTqVcYzNj`ro{(o8*u(B>d>jhTU3uqm|$~pqAFIZV$pmhf;>khOYVP!pn z)+wy4Q_%WFEbAAvt`W<+2Ca8w%6bQ_gCt}fgnSo~tdD4%+vN0Zfyacj7GPv8fYu0% ztP#-KfswTXT2nBxra)^Ak*qb)8bl;(5VSUtkhKX~v&fV+3tG#FWi5l&IAU4jptTPx zYag^GVr5N){9QPE#qC<-+$=NsvSL{~pf!b9))Z*1A(piUT7!5-)*xtYB9gTUTC<2` z&4Si4B3a8I{~qEBa@*86-FeYEf{}FuT3;}-zCh~^M%Eo@J;KO(1g%pTS*M`&3nS|n zw60-fU4#5%M%Ftt*5yh^zM4O@zF=j2fz}Q zYX`KZ5X+hZtu;oqY0EeDdV0x8kcOAHEeIKKb^o`1Z-?Z^h@Y?T^N}K{m~QS~oGWZbIuRM%Ghk zoyEvH3$4ExS%0B*86)d5v|eLmy@u9tjI876zC+`5=d1gvRIv5~_=_c(b^ufB_tesAbKexJTG@Ymo&ecvPIK<<7<{N@jwlQN7SmoF;1Z9HVncU-^f zncpvVYvPMXb&ikhIfkF#`0X?C*dN{b!A5Hf*t=fu#?PO`gR}$QUFm!M zaQrvSRF&-JyTo17ycfh$p zHm(0Uw|2K}>*ZrP&%5&i`$EeFtdk3m8f#ZiIhpa`&oXS&%GyJ8G9cuWAFQA?0v$Fy|0+D z_aQU(zU2tD;C;@Fy)T+E>Sw@!MiRR@C@0BX*eVvl07DcH4;E zCVOtgo|Bz7V&}>J8?pbo9yLyPzS^#Of3-y&c|SH|@84$Z{oahdKb*1mlQZ`Ib8gpU zL*Q560jE1(aOq$8y;**g{|{U7_gL3aDp+%vYCAXzIWtaY$s;*S zPG`&`Ib%*|&yActr!(nB&ZN^>bt7lh=?uG(GwgJ>-N@N?I`eMi%sZWhH*yx9&ch;h z6WbPz^I}=(9B!tZ>87*Zv7Gg$GvKkD0jIO!R?ddgnQ<#;#_24%m9yk@#@xyob2@u& z zbbj2(`Efc|PVpEM2G)Sin;SWAPUp}gIfqW?(<3>bPUqGWa&Dc@vuDbAb~-~H%Q<(A z_mn)kj_3?{EN8&!YJ7Ar(wMq*1+%t<3LCn*-Ckyw-zqtZx>N{U@+Bz7gmtuhkRQsdk#GjSMk zT6p|JaRsf!6{L8BR^km(96~E`2q`|HmH31dx6n%5LW*Y?OFTo0a~MmULyCWxDe(^} zE@DFBB2v7>Na7_@9K}fDC{lbyBk>g}?xK;ni{x`gEFlkh*>~&TVpPc_{u~ zLgMdHT)s?+%SZA0Vu{yBar|P5<45uRti<=DxPMmS{!u(YEAareebzYL`D)umF%=_; zsYtOFBZ;+0F&K@+V5HcLMq)Ek%tj+I8!48fkywrty04_zhDKr=Qp`gmF%NZLpm8eS>UNz9)@>veOmV=B#Mz_xdq(2#QCvPF zarr1-pOJWd6vxj<96yThXC%HK#r-o9_mAQM8i@x;aRQCR38eUek;D(&II%}0aRn*f zU_#;zQmnH~i9@JyZj)2{2mTlC&7^pA35loo`2I69CC(nj--{*w9>wL0B`zPu>$4KC zkK*iEiQ`8c{@cAh=}4bqAzF!rNHG$v#7LyriB@7KQcOiFF%>D+qLo;S6ob)93`UC0 zXeBly#cZ?^vyoysT8ZUIF&<-y@kp^BV~PDpF(G4#38^`wvDQg$lUd7_3dR^^XTB-@ zj;?o#h1f)5AySOQOo@@G?SRIqe5>sS#X>X^3z1?Z8i|oe@elv@UfNW?^=09CcQ|*p zpp9S45^`F1L>8CG8+R?)^cnn|j6uNKj({~u3{!B-E#p(li{_^!V$J%cWs>^uO z%tLJH?QI#qz3j92wP*V=uK(Z-akVF0{OavLugNUg&z)(y_LmD2_DXl=#a22m8gck& ze%~y4B`Vh3o!#5_+5OFc@u%_g14h*}rb}bS#}{aAZo9YS4mdZR zwRrq`2e-#y<@~$jj>oz4_?2H;7q|T0ott~U+mZI?@7=l1(f23pg&W*i*OFbj+7njo zW6)mfPC3sO8TkUwq1Jyq+OB!+EXL12kwN#q9nWW%j{kMMJ>$@PTz6M28g74TZTga*58lw)b{}v!>r><0EHjM>llKL@NOtd{iM2Q`>)=bqnX2bkVLg2D-4L_% z{Mn5AT-noH@Z(R6%P(tgj(njs>+pk-N1JYkMmyl$mHy7oE@e zgb#bfE8cLNKlSB7nb-I@fmIGzo>+9ZYa^S+T^>D=e^N9$=|tngKwN&)GS@( z&Jwm*Rnx54avZ-iEpBNhw{d4$m$vO?`XB7>%^b94i21bkY_4lvE{*ewoLXj$HCNv( zT8!L{u6^|>H6`x(rfXjxKL2ezJ96>Xww+PZ4nMB7K|9JEew-~l(A{e`tZ8SvVwyYO z+A;q?yJCvFXLHh#qip}0@uNx)}HQ&#@ zm&-E0YA^HTG@Zx>HV z+bE4w`BwA%x%=XH=xwe&me}vC_~ox$du)48pUfxkbbZtI3qMRuzudLQ!Hcep-k$Hy z;a>Igdr|i;u02kD{s1%oosQfFYd5NG3Ow3~aaR3QPRc;{Qdzm*knTOSa_=GChiK(K zM7k%@$~}p6f1;K96EBI&TDez|?puuIzD2r+F_wE6>3+so?q{TX8ym~LjdY)5B=3%~a_Z!l^heqx_r27Yr+=uA< zIJVUq=LUJ`zDOhYMQ&cz!^l07bibsL`z7h#Nh9}8(tVUh?xUpp+9J89Qe$1lT}fZB zfzn-^R_@}YJ36i0(fQzAHkP|P=}ymB?)0R)J~QR6Pr3s%A$Ne%y?&A04XSZE@}j#G zW4Sw(?o^HCPF1>VHI}py({c7dz zSGp6{%AK%uSFDx0V(AW9D|g7!-Lh8hmeu9eI4{bq<=0sEJ9Ouxl{+8lE=VhPLDC(O zR_=(TyCbdK9Z7deQfzz|$D8h&v~t%Z-9Z`49h7u8Wh{47(w&u=a%UyoWtot>EH%e8 z&JD6@`$Km}Msjx~-6;NO=?+RGcTnp7UE^IzQ*)2*CynKPQo6S^mU~O- zK2t0AnbJL{R_-~a`%kUhe@geFTDcdM?n||DUn=$Qe|v{`4&H=ORlG;$9n-H&PH zeoVSI)5yJ>496z9{yWk=S1p6U<0VFp3psBvu&35Hk`(jADx!i7iGk z$Be`rqgZ4{Vv)V`)}}~elu_)mNMe_fZ#j~fW;#BD#<@W@npYa}i7ju~*NCr-d}u~| zXyjWn;#(u18^sN9J~#5k8S%xDkIsmXj(m4Ue0Sv2Gvd=DU!M_QANc?y@d1)=FcRM& z`3xiR8InKY8Sy1*oSS9VHsOC^zCboDxgUxAZ&v(oqP7IT-OnYMk5TB!8?Ge=PZF zt@vrle{02mOMYD|eqHkSTJiUiAJ~c?SeHxVbf>TL(pcLx@);WO8Imv2h%b?Rj7EHn z-B$%`z`9p@64Ter0xHfTOS;GOcPt}iW>ZU`Zt|zyXl2@ z!0FESqtja1c2~GqH~qfuWuIHVj(t`w#|*Xe>)prr<=e;E{RUQI4Bby#d+PltuYb<^ z_wO_I=`i-`TfF}_n9G~Se6y8)<5#E7-V^1@PQK*pFm%p{%SHY%L;f+wNpFXf4%hH z=>M*D_aHQHx-RNjtT#XJTk8n(>m98aFE4+b+4O8J#-CN~WR{=c_A|7(`E1i^{kzP! zl`AeZr#^lK;|;Wbe%Ry{yvEny<_uF|`9NO#`{?b_=A@ZDBINt!u=CBN&X(~(Z*()m z*Ay^#uFI}*UYB2&MPqFTX3%~RLvv~9q3^|~+AebrWSo_aO66PqPO9y_?X=4)Lx!BT zGug>k_d$<;Kh!>W$vw=yOQYVl?aeSYoYH4E9Wk z!A^0B6B3(UGW#Z`_awl>Aw&Xkzj6pK3{vA8KlcO)^oDRy@xvAZdzw~?6M6zkha ztZ#||ZX^ac#RfML8=PW>8;KcCvBZtU5~mpBMq-Rp>~SNp$0???k(lHf=VqCG8)rLD z@!n&J_fB!(V~GP#@!?~M4^MI9t;CI|c=A@_$y1zpD{8vc{==tL-_(Q8yAto#Lw-iLXv^*Nwzo*F4uayXh=_Wf{e{aQlwZ9itol+l2A+ zIG#qjW34Qh|IsYzPjez3SDzQ^@?6Hp>EiLNkKe`E$Mxd&?&EzirWi7a1ICzmi1=WP zecUj{UVg@YZoUH!_1N8_9eaH;{x@;ea;hG|O^V@`BW-~=Q&HN2#yKfN;Ah_AXRtHQ zPm-?qjX7m!Lc0s?&d03dF@uj~$JocX z^mlAeEX_}3o?^idrystDi*Z)5L&JR5`Qg2Oxc?&E?Y8^NLVp+fJB)|W9(By#(C$LJ z^W#9~hWF1g_WnKY6DJJ?5=?4E2?_>PxpZjYB==t$GagmAC3kw>6DJJ?5=?4E2?_>PxpZjYB==t$Gag zmAC3kw>6DJJ?5=?4E2?_>PxpZjYB==t$GagmAC3kw>6DJJ?5=?4E2?_>PxpZjYB== zt$GagmAC3kw>6DJJ?5=?4E2?_>PxpZjYB==t$GagmAC3kw>6DJJ?5=?4E2?_>PxpZ zjYB==t$GagmAC3kw>6DJJ?5=?4E2?_>PxpZjYB==t$GagmAC3kw>6DJJ?5=?4E2?_ z>PxpZjYB==t$GagmAC3kw>6DJJ?5=?4E2?_>PxpZjYB==t$GagmAC3kw>6DJJ?5=? z4E2?_>PxpZjYB==t$GagmAC3kw>6DJJ?5=?4E2?_>PxpZjYB==t$GagmAC3kw>6DJ zJ?5=?4E2?_>PxpZjYB==t$GagmAC3kw>6DJJ?5=?4E2?_>PxpZjYB==t$GagmAC3k zw>6DJJ?5=?lzT7TJv$TmE`oo;b?aQ0jL)AF_uU$e_=9iVvxSWDF22EYq=B@6 zk@hLKkFE%eKlD5y&*}XL*yXv9G18&*86$oAWAG00q~9@yJoF7?MmctKWx*PrN$Yw)8%i~ zi66URFym%N&W%^h@6MQhWyc@UjPauDDp>l%n4Ves9b@bkK*E~r>2zK5|H^KHd^#cpBTqfGTm7p=U6 z@yjQ7uS9C95;&r#MiFWwhDAe~t(59w0r4f*nOe)fl+XDR*9B>DLrq@7jWDLaF{kLwinTlEp> z`}jHRx9TIQ%JQy&LCioI5S1m2fE0_jK}!TlWGNB^Mu2*^Y4aUX%ck1^6v zeFXPEcn5i^=ji+7{Xg|JDt+{QEQ2d+QXZq^{8JydtjvM4eYyVBCn`M{-G?f@q3@&L zCHp?czVBm6!gHj3U6EI3dO6A7KAMo{^nL`4_bDC5 zNT<-$yBU|N^m5$tfklj8FY`#;`_g5M;|7!BwKKn9oWIgp@wwACF|PE@A#s5UzcRjR z+U=R72exH(>s(hsJx{3jBb831(vMWWk&=gOYEsT8$oeXDdBDcwd&=af&fE~xKF))Cp{WZnHOA3zNH*?}i` zSfbnpmLb2X6dk$uQpWoyrbhbts|Bv*=hw7hZS-yW}nX0UZs%3xA z^4o$BwV|?gH)RHY6Y0G4w;g-W;dcgfeJ0ZR>Tl~*{EXk}Id@o;)weY+{)OKecg_8Y ztiDz6Wa@m?^MuMPRyb1c=x<~7{7>I18T31U`c{=i=N0R3l}=(MbF9Bry3O)i#epop zRosYmzWQ68mwsQrqo0F|)CSl-2b>r5@Wg^WNVYkQ8B}>ukK7h9&mh|@?eb4^A2m0@@A)0PtL7$unp^#)9;weu&bb)- zJPn>B9W^&WzWf|{qOZU^^n*DUW8|rMC}l)>)pOLNywClBOD5l+<~}N4yvy$+Pt1St zKGM*0t0kAOr7=H#c+M3AAy1_Tq+#(K=_tJ+Uw)1}QD(eDKbUhdMxLr(IDaXdd-YFs zY1}jXy*r-oiXBRp7vo+&V_P89!^8exi}4^rPBuX{ziTt>Mrlq z9oj3|Np80R2R#H1>~0RYzIf>?%P_V?Uzj$3{)F-K;PaxNob%@|nEz4Q=LmgXsGH;d zeCI!Ob*FKt$7bADV63jk@I*R(j!xu_y2%{ z9`-B;;Nxh$q>|0wuqpg4(F0KhJFA(2A0`_9WGQ?3MaRHCnPV;}W|!8j!hV%sFa14! zW=RS5s}wlDj3Q)qI_YSAdew=*snrz z8j_R!DkQ%l`3?FWDwm;h5&ol$;F~IMtjZg!@>*41tIBItd95n1Rpqs+ymrQxWA8hy z$!Yh&52MP9_oci@N6L%zrM$>j$_sgaoPay(_=F;E2lpIoGd$pX*)o!KcqW@%b`;ygbY+%{R@%zo{=NS5go3 zPEtSUTSag1kBL4>o}`}PA5-N@)(ggef2l7iSF(P6I?QvQzLYD;6EBaHE6FSL>B2XZ z3)}=30}gr!9N4`a&^BM&6K!Wm=jcbcooc(J?UlA;+P-PK7y7kiKc2L!+TLnAtnD-D zKWVqAUXu3Q+sV+cDg9`@X?A9HqxsXfJ=6Ux)b`=_Jhc!aO%{AZreUel7HC zzTaX0r|*w~AJX}agC8>Vp}|+22RRV>wa~AHe$DxZ!}?nAr;!N{bK(EMnlJYAsr?4Y zeF%CThpIZczO$?A7uWpMZ|37`FXMAYvcE$6@w9(W`~7^rvflvm{NuVj_GK#nRV3^6 z+TTUxO8UXHe@y$$v_I{i)(xNj_N!Sn?k+T2@2~Lh%l;4=_a*m-?3Vp7q3(9ins2B( z_8Vhg%`WeU3GL49=?XS;=X(f4y9@13?T3uien|A!yxyeue}?`p^ml%IDE{Q+J|!A= z{b~Pa7-#Ojeb=Ggg?1O(U6|j6xq0&J#!km7*h@@v0RNK`=JNyYgH+Dovj2_dY?U}4 z+LI74DKF?D@F8#@a3F9Xa3FAC&vL+zWl|moQGL-GN!EJ{kzRNw=qGR>a3F9Xa3F9X za3Ci+;Kws5`)MdXq{Sb6C-}0K?=H4|JKid3`Xy|W8F}|V2lBh%3 zLwCTbe2ee!J@UKuvx>ITkCPZ*^lB~p)%@y=OW$1I9`S1nzBA|kL+jf{-EZW(5$x$T z?Tb$}jqz=Z%Z{?eTiwOD*0;s&VUNDWn2Lh(uxxmS-{F0{i*JCD2GRmX+Q|lnRC}UVQH05py2JeDL;1e+T1+D;R_x-H$ zMNC&8E0*u0@-bNXZVw+T)*^PRkJ-xq`dF@1uM3m+bKpB4`<2r}y2z96G(t?;9dNqy zMV_1Oh-BWW;4KSRRTf!yhO;UczLz@9i8AI?UK9_v0+r36d>Vs0R8D^GIl$O+gE6?{ zY|$8p1#i=X@QGOxTI7<>IN_IhKixvFux^F?`2y4fV_cW3zebB>GFep3@N z8;uvA`Au}h&-?Q88;`P4&1Vj0{C(yP(VC+wG0yHghs}Q~x~}gL{B4`fmqcGos=|17 zlY^t*%GF`qW%0%)Uwl}f@wVe1%e?NsdW_4pY#R^1voz(r@6E`KcpU3UUJoCcfsN|D;FO*qe=0)$9E^VRnJBqE2X8c;1 z@#k|3nG^2&5$(ksyy`sUJG_rh4qte;-b z)T%lkd^UwosbL-%-ys72zs=>$mdEa4ydvL0W=(eBPX#AAdFAT|*)QK-#`^!^-Ey{3y%~(VKVIE- zU*45*$IA8WHND>CdK~pzeS6x=Cp?3Ce6&_w+q3@fT-RF8-IZpM&R@o#NBeWVFM4ht z+rRGjEKkE@N?Ln+CgZx3E8E4Ju4KG;WNmxF>E#%ApHts%{-qAfeA>bF?d0M&v7ArM zuW36^OT>`B(wqvmUZ-0be{j+vw(`nX7{C9?UiPf~TNyvP?!)-ZR}Qdve^v7b<85&n z#x3ff9iKbmXvPP3{xE?Jl%CKdz8|*9AoNYM|CHJpBSW!w_lU1)cq-MKsVU~6(} zzCd}&x(4P9xfb^vbdY`O{pB%q(`4%b_UjQJGA=l@i0$yhXN*7Gu%Df=Kl`iACnxM< z3wHg1pPzb8L0fR*2FArF6tLyyZDx$}(s~EhbWHiBb?vg-Kj-(`8OLeJtW zMqUAv4xon@Gft?4fANRzndEvWUK!yP)wPkjCJq?k0CB?zH;6w*`1AeG1S07r~%shE5;~t}mnkrpBVf@++#muI)A223v7~uwS#t3JKOGdav95ceP zoUBK+-edxHd;v$m71RT457{8busvjh7{m6E4Pp%2LpI1^vOQ#j7=t_D5YnMJBXbZK z`~uH_!8`B|7<>dT|N1_70e;{)_yXPlgGb;KF!%+Y0q0~rlFt@CJd1oa_B!O}zFdrb zc^P{>F!s7)jCMxtjWOC8wKv9SXVl&pqn%NEV~lo2?TxY517oir#$IoXy*?SMeHSKR zSC3(Q9>(Wke4g{;b82^3k7T=)U5xc}tfRvYV_hBV>%drV$GST(*5R=p4~+GBtkVNy z-5%@r{G8VFv98bW(>g!a-GQ->0PFFxFm+>xWoJu^tJG^+~K#0;eNQtrP51zzHQTx)3+LvzBzI3DZr5m*`o%>R<@5~3a zFWsnp=|=5KH)>zHQTx)3+LvzBzI3DZrT`Us}GUeB? z9k{yK(e|J>&*S!9;j_~Al#DryZ);W5npd1ZRiU3IH38E%C{(^?14$QK6O26oRczS zcYY1osQqGp9`j*m7@S4f@V>_26u5=w;2Jmw3=V>ez~Cl03JlJIyTITwI1LPrgX_TH zKI#lubLOb4?@#VEN_W0WAF|)cKpwvjiZS*px&1~Bcpnqi?eNa7%EAWhzDmE3j%7#(uW~l8KlXL|eRQm=bnRmi z-I9Gsaw#YCMV)46Jf?WV^{w0X-(hX{G}c^7_ukH&%uAP1t>te^gb8p=GeCH!NvDfnWi94L{XxyW}$H!E5XNxZGdXQaN;@t>3*>YSt zyZ7z)G0s=My8W$0PsWeDT-P@J{PP|BJSbO#b^Uqo^`4R;-F3I8+KA3q@88f^>wMws zedCMcqq)DjWAOv=n$OBGExXSHr-L}R>1?;E?HglamTKZ5st}UO1H+8P7XtxZy zk)QYLU(2@Ks~+QwzV+>kZw}^qFHN}ZVMBOMaZi)@EZIE2H(MZV6+3Y2Vk@hv=e@x+6~$dFxnH^6)@Tv z+8Z$1AKD=>+9ld2Fxo5HEil?K+B2}$zs9*uPU3TNkC4W??GXPH!hdQPk+chHFOjqt zYDdIX*N%4O+j?JZ%v?9f^@*ET430ZIUd=$C^ZU<>w-ztWcuAYp@wPRE86Wm;A^Tao zA0xbTZOM}Mfer4Q;JxcA+ux78f}fwazP4TP>S2s;Tv^|anzM!14NtzIp8fdBC%BCq zcz6vvY-LBTyX$6`vu}MngYkYh9B7Llw}NqW?Y6k%L;0BlV_#evf3f*s#>*<*65qAn ztp(gX?wI)C8jedPA0CmpzPsZX;e=p%Cz5yQ+ep5pG$Toq@`@xclEH`!B%2Z0NM<84 zQ(26Zh0188j8t|bWhb2&(Fy6wh^|P7Ms!HJjYPMk^GI|~brDHjP#qHXYcA?})}YM&=+i#^JFJbVy?y z9_s+p7>CC?z%<5*WR62)oJi(AG{%W!PDEpzNajkK4;mw_oRUG?y=yPukU8o?*MH4B z{DS!6k6r(D)1heVBtb6|@anu8$z^n&S_*1s-{pakWO3?KRV{ zX53^{ZQHVgJLjHQRNroIbyNcHpSil8%{TKNZjX;`u3;zFYR>KM(6UF_t2Rtw{PmpT zw(nVQGhTT>KHK6`H-@}&_S^AKH*uURbJ~eh<9iBooGbI)ht1mPI<$0a*~NN48)bGqocqKMh1N%H4sv@i-Wybe z_T;#I?`_T~ZHo4v%kn((Mm6*E^A|8ie}cXr<58;5>We4AW-j@#EM zbM=mEjyBV342U3q?~BTsz5`}6o`3U!=7nl27#C{xTQuP#=ig|0?6Rot-o<%bv8>3w z(Y9&MA7a*Yk9xLqev;x-K220x?%LXuztlI+bnV9Dx?#$59K4yU8B@25Cl z-+wXo{TgH6PqF+YxBdN@Vu;1WHnVM!QjGsaI;QMi53}zDY3&UAxdY3fv7c+OoPG|% z*w0NE`#B4j-Opth`#BC{^n2+4Ad8<9G4^vM#(oav-gk2=#(pltSnF2f+$QHWOKM7- zGpsqLJ(hy>L9AbYekUho(46u90p^DH8!-0%1jgRaz}WjAxPHA~g0c5kF!p{7#^i@i z@_J9@n~I-bzf*Rv>PeYX!Kg>^w`+Vx)5bZ*D?PtXH-~e&FD~ z(<$I=tqbUKX{@<1LwUwF3&*z!MIWewNwl_JSO?STDws3hbN`^pZlKo_t5QC%K4`3UHL6HGv)7vC%(t&DuWx3J z>dZKmceD<{DR2w;#L$-K19*BIOcM&7Y*ExzioPM!hYVMI^$`H(zb7t7L4be`BQxHyq=7I89F=8_uUZ2FTPeaescIY z#yYQF%|_d&+ML7bm)UrpJ>ae97~A>X>~ja~&F>$*y{X;$c}2!&_NrvhyrC)MC(bTt z&;Imu#!VN!9^Y`@K*k#`o*dsYWCY_|3sj0XO>y~tG3HK#-MY^lB(<6rzA-_nou@1fpfe2<4n59tEyysoS>&VK!U zEl$7G>cO^g`#Fr?7OpT^Z38>ClJ{Nw-FHOFB2AbJRuKX_t#0 zk{qa8rwDOjqVak_-7)rc%9wtKx@PP-z}RzxvF8F~&!q@ydX6#Hd66D6Ne}!!=^-XP zFeW|3qzA^NhnV!hnDk&t4~#uG7<ziZZM`Ir(_Q$FJDKTzOOsRzD^nYy5{sf2N;umFk~MXlYNNDJ}@Tx5RrXgO!grn z`@op&LxSuBV{fAps3VQFPP|Ry_r0xS>}?=pZyOnVo5|SQQpVoKa#_6XWvuhsU3~Di zl=JmAma(_JoUgaZjL|2c{Lq8OXfI+XVb`GxyaRjBx*&*t0J^|q^bgPlF!~MX0vP=X zbODTh2D$)7{{vkB>%3qapbI>OZ9v-qhHXIG0ETTq+W>}bK-&O@Z9v-qMt=fb0HdFQ zE`ZVhKo`L1m!Jz^ErZ6oj=XI*cst$p0d@;*19`!op=|)e&Y^7p!~UUd0Q<5tMxTkc zf#>Km(Kdk5XQFKYqt8U!0H!u!(KdjKFMD}5$`70y`pw%5D6mX?klPjV8z`8AHo#bSHfj$#s2*`sz6JrQq^qCk#0He>u7y=l5 zCdLrJUMGybt{8hAGWNP<>~+pqmlv4E^E`$mo0$;%Nj5DKn?|-S5?e<$(1;Br+i1i# zlFc+?Gs%`3v87~Vjo4VSy+&-W&WmhUB({reS|m1&Y@HEXM>f!i4cuLPIP}MHrb+(N z%oB~v=+W3h&rfVDY!}S$%(!d$H{;<)x^er(O~=RE_jfk`gE0?gUR%obJJ+A` zVB+8-9lojR_~@o0?wy+sc{4hotoyd>4~30+!lilJz?$ZjJ}$4v4{BwO|MUpXYswM5 z&Gtjrv26Q%KGb~t$~}y=Y`vQvVuzmCj^7_JY*W1dIycVDH+w-`b^fQb$|gYl&!s+jgK z9MAZYZl{=i?kdZ8OWmHPcO}<zwiEMup?)w~lB0VU+2z0KSoeqj80{nn;ypOVZ6^FVEL z?#Yc9KbTR>eAA&L;~Awth;CUifN|T&*F>e;UdUMIwY&P?ldr98YFvK;r{Ce_eayDL zuFbCe^7UwOZ#R!?IODRYPuY?Djvjjq81NK)T>KomfnHE{$P2lFQ4W*`80AAbfl+Rh z9~k<8UVxz|=nEM7gC2pQSLhd5=LNYSAD%;A$PJ8gpgh1RAIb^5yXLJ(%l)|W2ORW} z*ErDRtxKZs&T{QqnB`x*s;^zpdoA0s>yIC9 zyPSFl5q0j19~v{1@xlR>;?Hh(z6I)M(YNyR)~%14C0OexuapJ45cyNVy6iVU zSv|_%+3BRPc`*8M&=A(i+T(wY7ESHJxaF7cm9^5 z9nLqk^FPaVRHD=v)3kp##+{zYFh3l69M|dP`%Ey^dN@v2D>A~YEq8MSdCL{frH&Tn%vrtM`0ec;??#U=Je!|uyQ=Yjsf^Ht`w3%! zpohH40gQvtK2d*YyJ*9}Xwzuhz-a4e^T4nHum!-d4X_cwuo_u_wl$!0ApC<8F+Q2#{dkH>$VnCtznw^ckNv-}L#hrY3-XFTb- z(fp3axlJA|TPj%lR|jplHS^gvuDqSDIwanDtXp%@?@XJ%GV|iA+!&+%z9r&o+qrj+ zzvj63tS82@exOJ9lUkk1+o^IOyblfhRkwfrzi27z=d{m<=KM6yq`hz0(*T@~eP1*V zqBV0ThsJo8Q!*TM;;^I)sbJ_rWKQ>fFue~=0DI-G*|T-t@YBnY)LX z+nP`1cKuq*zUH<$UozgOV>|O{^+VWJ4`|ZB40^r3>-!!$#Js)P%`rPI{wkWfS6_Z! zW7xFlnL)!CpE;;(H19pPE~eYE#yKfNDs5T6qq&^!eSKs$NK%>#aY#F*3YR8vk%AbU5}wVzo(tC-|KGi-0y*B zoZa&g+83=c+DJ~xfHELI_wUZJmebon{?^+@#@=Q!{@B@4#@@y<_O_R?x5=zqZ>t%5 z`?&+oNg0%0Ou)>K9MD7dY_1Epz%#1$z#&Ey;;Axy!pWQyGKh8|Ln>J0O!xUC zeeOwPt*dm)p!AUg{fp!l?1R(9?$d+bvrTjE7~?tQL38dH<2+!Rb6br6fN9QcF)jqA zIk&}l5t!!O7UM`@nsZx>FM(;!Z87cy*8BvPGv+xhgOkO{lM0r0{l753@O^=WUQ)qI zf6N2-|J}#W+?W1D)4KJ&?0+T>C(qnrjRor#kQeI@Scd?{x&+oIfb~0AbHLgIo?|Tn zYZAa%qrh4Puzo+g80$Y+2SPen7sC1wFxHE(ZUl^VB&;U^V|@whOu$%o!uk_1)}yd4 z1&nnntXBbJ{R-Cx#j;JmAcRK^VYoyM;gsY30?qQvRG#T4tolVC4`Yfcz+Qz0^hS2u& zZrcxamsje}jf-=_hbD9UbkChD&3Zd|_9rL$k*Q7EP~4gH??EE{p;J7 z=WU|Nsd{wvg}=j`RC71rz=z$(fnX2wiapeQnZ}w6VSLhz=fysDC1W4clCj_O%zk6< zQ(}xhCiH8;uIjcFa9-v^=+{EOR)Ob$sl;t2`=4A}5A$xPH_so|A=$zdVm>>I8Rlz2 z4}k;e;y~!vLcbRJwJ=|UeaXw?^B}+U5TPFb;6m_UHDfs7 z{`_HgG#N}iE#&H8HNA<3EvG*rcof%!(-rZABxB7g(M7 z1yScxX8w~c`F;IuPV7~d^UJ8;;>)h&xL)UX>}ZCKFUImry{fg=db`WtW`%VbH6|STx*rZOXZ-_-#q{CQrNV<(hxB6Si zBIjaAPP#YE$w~5Ck)O(CrCd~AE9KSSrh9!Hd5vB?N6ri9C>H(b@?P^)XZ!It?hd$$ z-wm)&y!3vAIxJa#ggvp$O^my?7;m3@tOVm-dB59j1MQM6uW>q)r;M^C62lo^(39?O zU3NX6M;pL_x)@=cH1@;Byg1v#=0frqS+szpE33dw4^|$G^8(PmA!-m0@ zK^oXL*f?O=JlH;9*h1JuV930A%#n1)GIjjHyw=J01$!MDq~dkL*y}37bFV|jUbl?( zx6~JrEp+2;FDIwt0QT-Gcca<>;MIeO{=WBX>g4dB9|Sg}Uo*(dKtGenqIeeEEEAdDbVz zY_z0P(XGY*oo&r${d@VE9XU6qJ4pDsw;PN@yBlnjt{6j?h=YmeUbl=>jprY1ChN_h zokNGdy)&l&?lhi%u$iu%dR5idbGlR|aTtQzDfh*vZk7>g= zw7bymLVs6>V~HT{MX;H{W(J#?FJG7=ggHVOXV&5PNQf~M=67L!N9}>G=86nS8cAx$`;8YTQ~!zI?Q9WMCWcRQsp&ctW=s z?<E@91?e z)PWldC!h0}z`xJfr(;z5jD5b0>35KavF|?^Ya8n3o=MvpL61mN`)=sJNnfhh8^7cA z$=K(^*z2F=^!36RcEI_5ki*2?UU%DzEQ;bbgDg_N;-fy%r#Fvgd}!f263;ewFqEh3RD*3t#!)>K+Ze_f7W`CQ%(kjNiFYRdK z2E|y1EgxuXUoTUWaiOVYY^h4k8GG3nXH}<-M&C*CoKvq;O5aHOl&_I|NggBekeo*3 zB>9cVPvtUFu0QHGM{S7cg;e9p41K2ubHZo~mXT{0{}N9$FZbGq*M=eMzsG;HO_C|u zPX7f4=S7#hfG1iiOJ%2@UBQ2}K}rkqh@P{7)6IvFzOQHD4gEJa=mb(tv|@X8->Umu z&nf1W?xS_zO$jCWruzupcj!Jv_cgi?(tQ)9X@t+dKNT6Wz1}9{ALw1M?{i~l!S}_C zef!=aFD-+X&5r^2{V*0v`sPq~2D;syV<8zA>Hbvrv%3G){j%<_bwBRwk>%85IbV;pSm`T~R z{s>1Mj=Eo!x@JQ9V!kKp~^DheoBJoU70?L&=FeM#-7<$wFtc&jsy4l^5@e z9*_?Hpj=3wG1B*W@R(ca*(m)deU~n6S6_OsnZ}_Wn{jkg86zqZ?Pko!6(+gS?$e8TC6TFX>a}D=FYV=l9R@rN6w3+a8~+-&AmJ ztKY2;9Y$Ps{7D7lU9;>Fsjr=4N;9dSR50{I>61)c&pW}{tzZ4V%R$QS^ZQ3TmJOTh z(@C{miY%_ofBa9&`*-;7o@JFrcHYe@jqp76y4h7-NluPK7}v`j1#IRkSNa|RjPVqW6rK~7d$GvfQF{qy9!MCK?y9fP-h`iyA(pV4pr?pD$zjRdP=0<>cqkAJWCQ{yt85pPq!e%X@W~T|0@I|5tW?2c96M z?5E}O)?=#Og-I6UWMa8?g0u6kr24P)wi7v0kyXEw6LSAkIn$s2)`xCaW4zskvp23w zb?hh1*g5yItGDdFpD!Pc_YB5-kSP`HWdEnSmeRR*vOk{0_o=6!y?2wcWutv%U#F?d zl-;z$`>qD}lpgZsd%op?cFaqsa(nr@XB|7`)`pCKd7!o3w&ZZe2T$v5*H`_4$6dXi zA8LnPF@y0jv&Pv;ff=oV^)WdHZ}*^wLb0`I$ju%tQS;G5+q24AXXe z=}hGK<16FM39Sn{nFkFwTdLj8_>%m6&CFN6V*K%Mt{FHw37dM&dmJo zgSWTqpR2dtxt|aBx$`^o%$YN1&YYR=@_T5|aK*Q*E}IV9Z=B#QjRWcz2LHRCLeo1VIP2q{ll5I)=T`4GtL3yEyAJG26Ljv9!bARTH z1G8Zl*ksJ{S=q1`Y~}l;{r6>||BzMeZKyKX+Xvg>H~w}UdbXh$^}-l<-F^At$-CSC z&;a(VGyI;UTBBh(uyd#K>ylSqn3n_lU$QtSmoUh;ij?|l=oM;C+fb-2JBgH0%OB+X~yPnqCfD8QJowtYBWQOvC z18srd?%qSo!JqqTHL=wa<#)elC_lK-2Kb>5?Bd3yp_~;#k78<{rzgFv{NP3#;D-*b z|8vs=jxA$gN7%&avPAh|SJ)xg#M$~t)dzZmAKWO1eb7Jj3;eJNYzO`EIobffv&}oo zk1>P|!H;plm_dJVqtD=nKKL8_7(@IGesH4=@WUpM2S0Q`zu*t>7yJ!=aH9?IJKHo= ze%J(D;D?ST{eVl2Ufv4RfZK|2^T z)P;?~gSxN>${`Qk;WvDTe*!GsPG$*a^ZIU)T>Az9IKaXy0I4#^^U> zwuKJ!yT2*196#Icei+xDwrT1=z2FeoH`p5X4Yn4Et#n3PtXOudeKPA*QTp&Thu@mj zqr!)}K3@Fohgn}=b+ckwW3#c=!p^&1y&$V<&o^}a&B>`;bzRLmZQMt80LpYcn+df**ZB?8BTAd#FC}DT%idzZzmLVZ9I^ zbL$24MEv#fR&{{i$>+Kzfgf$bR^W#nT>Kr2*sC@HzpM{7tQRN`>mB-qF#^BXOxGmv z%UYzd8~jc;w_d}BSOcKHjFqlQ;1_OPr=dUEf<8XBry;M9^+DGp@I&6M)0$(b4le#2 zo`xJo#vE<<*xnF&AReinunG8KL+AtjWo_~Kisl;@;{yHBU)Tiv;v?EG=nQ%I1~}0d zj0-qr3{`*V2_4`M;1S=^H3@aW1K&ekl*5N1Fa9Di)a5Ypnf$o52naSqU0~=7d0^-z zzwqx5U2}2qae{qv@r0}graY+g_x9Ib%$j@96vaIkf17noPFuxIUidg``PX>vaDtWJ z+48r}ahcayGOrcSc`nHs{qbcw-w(LD^~|Q__Q5m!R@ONw!w>rA;y?ZhaS?r#{=t{^ zI+pZLvHbam)*#_6()HZuLWu7n&p|(A%ru|DTB_xk1CW8gz;EC)KJQX__zV07KI7)r z*IE}mn4hQ%-+>RoCh%psr{G)g6ZkUb4>-l!H>2OQ^1dM_&WG87cnQn@8<3j&rp8YLF}UZkbzCWk9-#TK!21YCW0URl71>bVmxdD{e6Be zaZuxx%uB@d%zj7t5lb*G;1_NKn}8o}NuQM;eaG4Z`yijixPTw>qPOy+U(f;kusPN_ z*hjbx`~m!kZeOPS$c2SVVqa!|r2ObFYyy6Y^Mz?Ap~mm&&*^6_Jp6?fT$i7UWP0o5(Nx+iLe4 z`)ALT6L{O|fS%~{p%T}MK0f>VjLB)n zn1FZ?;uvCHhzTy}dZ^04P3!issTte&*@z(uz>jk*c2KozqLVS~W>+@7yFOc7={@@Pl zozD-I-{-fgzthF7cd!TS0Djmc#9rtV)(dc>9QJ{2!g}rVTlE8c9@aZ&8@FEj{f_cu zT*7(*ZnOcvfIj#e{1`+04gbKng!K+KfjoT6jgQMQ;4k<)_ygL2kGi$Ut=F&#xWEs6 zU_S0$o$671bb8eHCglK-YsVk6KvO_^6|yh<>UG7Fn%0F|So&&U2b9Z?8TodlIc4(%wG`UX5G z7hVH?VBd~n`4jCZMm^MrjOdMaG8koOH*kA>^mFJLxS>DVg1nR=Rw{0O;Cf-&;BqS_p}ocMHtzKDN`ZQUNt<*^eI z^d0#a>VRMTHghg5b5U&W_Om|MQhxBEUD#0OqKvsae})d?>j`|umASpS&k2=Z=1b;W zTILk;Th$*rxcqXi?)%XO_`oj*W1AeF164f6%Kv(Dw+rU<^54a%@`@jyc7wiKY zpugb9=V$}=k@;$nUpk+MZQNNjxX}jqvFC=J!4Dnq8Ti4CHo))qM9L34pf32qjW)m! z9nfFc-;G5><@b9r<%f;I3x3GLM&O4Iuru_BozO1$(HGbV{LV+*Sv2~Jy3il?haTXB z{uozqV%(t{c)*RZ1P^QpPSi!eQ66jve{!~xPbF@+II=OuJP9(QuhxZxpH~)GbkTN! zrG3>6SblydhB%>u*oD7c94pFpT@LHoVl4gCxCP%38!5&Zi6rb7_6~|+fAkyWuz6wP zOo*B89Abjj1upt_p`~jNV+q@$1b%=q1(u&oAJCuBH}n%@3IX`K{89|N1RKF#p$}pF zAdjD-97pg^`*;t%9{R)0)AKH9@qw<1Qx|`cw{Pn^6w4Z$hqV@Z-TMBtysz8myEV5> z`-8h&P)FCzrME51+UMoIn&)TV(JuSAK;7LVlIuEQle#vB58V)( z&@YKsdOqTOYDOAj7upT$h0hO_-{)N#e^3{(7z%}PU6a6%{<`%**E@~l;748= z)(fYzTd!q3(X$)y!_HU_pg-D$4zQ2dSl1-*qwiRg;3udHJAhxf(T3Uw{e=#0juxCb zW9+adfgd`<4&ayZ(KSi!Lub)w7h?f_v5oe{#f*ZpXw-#2K!5ZR_6H|&XXp=3=!S6z zkNAV-~= zMs)xu<|NvNFTIz6_s6Ur-J|gU&J*GFRN*7QPIhMjzqJh$-NQ zFJn$RTNIo*qg})l@MA7wPJ-X(UCQs~@e=Jj;v)9>;K!UmOa#BrZzZl}@CiAO~%glnOLSi=JfjGaVGT7<_KgAcsG=v7$zfQzzU;16vU{4R*= z_!K@D{LlMs#z%v{;+NPl&gO!69DxoJZr8i+?WO`us}yeSRC_t;7fyZ+)(%{NM}gh0hN) z9{RjX`CSZl>jj@VBNm4B4)zJ_1#}4U7Tjn9HpJO5n#dj1k%Zzt3-d%!6&*dJXQd-eGK!L&K+_13m*kxX}iD(C>+qA9g@p z@MA4P8}LmxKJF~qjYUKFZP<&2d?R!I4BNm);D-+IGw2UHpNjK1R^Fv@s+giTQn4(<#05ueZR{?n{bhPHz&>IDuF%W$Ke(5AD! z(}iOk>IL1w7y1<13BQlL{OddUbFRmH+zz+Tda=ITkL*_4$vFppCS>$Ln?XO{$E{-9 z*KSyxJ!9FgCmHp${uQFaOBwTN*s8_?f!~WOcgkM8#z@zT zdB?wSfR06*J@fL0RP3c#?(NA7_x2PfK4VUVJPq>z^8q&F*vm1NV=3lE$Wbw;LN4m! znaepjR&z||*vm1NV=2dcj_n-75ry;`%;(t7F&zDZ zewcF{lR5T6hY)W$#v*qB7v>koc8=j3w>ef9E<(pkKi9BYUU+be#_O~CJ~fwVx%|$Szn#q4A7+c3VyTxc^%V=>A$Udwb06!CQwe!2{<$C65eR+sacZlc zm-;wq(1wqnisetld&NH9D)w<$vA3OKAGZ_mKxg4q?EN7je@Gzf{UHH|_Xiyp?+-d& z-XFjp)@vPK_?N^i9e3}~%J2PI`Mp0YzxQY5_x`N>-k+7<`?K*l?@7E*c_v;b-(E9aA`TcsN z{1{X5(eV5f);{HjO=Rr#{$anK>N%}nPnF-Vr^@fwQ|0&Tsq$k!xa(wYPW$<0QSRrP zV)=8c)XVi#>eQ5);+ZA=3n8@ zz_-;NLGJO(3itS}xn+IU%%kS$S~XYUe|6^qtx5r0a$`3PV>@LSIervzLFY8g}3?F)8&4B*k z#F_#7V6A|yU?0?_{MI18Lw||MnKN^-rGX8>FY8g}3?F^Rng@QjCd^QNaAM5^zi=D0 z1^WxPLBGH+HZzF(&|kO>#tZxyBdpo55A5mkfWdy9ac4xrVK6S>2d7&Lksmgc`Qpyf zWgIeR<}&801NdcZ6XYD=hfR=kK!4a1ZNWb1JNgBF=m{G_e{f=rg#I$Nssr?wwZp&< z!4E${&IEob)3(45o1kCdhdq%ufFFIw8V`Qx3Eu!eIN^ujN3I0jz|S#6+Aty;a!bXK zmo^lGN7_&fe)*>u?aF70p^wzb#5!q1G4$uyIHc0`d3jUY=^Q-Z;q7Ntt9P8vP1zUE zl6|q_Hm2pQ5BIF8a~Z$!H|A{1X<4%#JlQ?Z^7-34&idqzN3~p@Wy=fCvY{WYy$R4w zehOkG`sw<<_17TJ9r`bJ-n#eid4CA`3H%}CC-8@mpTHkNegc0;$RD6v@CWhHj6X>I zj6a9`3jQ4OEBJFl{+y6ME5G+=<@f%q{NA6H-_J+o_w!NWU}iolzn_oF@8_fP`}wH+ zem*L{pO4D#hZ67HHB+heaKZlQ7dXN1mNATD8y!SB~oKOPw*qIf)o7EE$r{y^)ZoM$qBHVal|j8Q9`F+yC*>i;V)jo&Rm?m>iY!mN)E=+t5aYJIJ+z*PMf_tGc2VGp<`gxaYOWU)X;-YNV zoujyR8E>n#$>+El^MH%KUG1y3hp`NC6>DdRw<00Ah>OEmYeRgN-;y`D^%${6YKXdA4X)c(zEMIhqxo zIg7zHf#wy0K=BvKKK*%({k7n|4``56hjtu zP!0}o0fQTRN32P}*r!rHmLKvllw(bT4EB*BH^W{QYZ5rIrwndz7@ICmo_?_+( z;QO*C&~p&@I5@E;p)Shd!;r_>8+<;@gK!U6QQ!Z}xw^Csy>t$WPKy2fHYmrO4Y3gY zm48}}KFVi`MQn@Ce!+`&Lrg)tzD<0D+*soU+V$}Ram1ia2>5mtOFiV?DawT}vu@*W z*p=GI#4Y&VR z_m$c%d_m%s*7Z4z>fra<%H#LE$^$=wKcWAqEB>jRelMKigr7lYpC2l}-ygojBwOkgGV2NIg|&?P5!NA;h0h@y)*)~NK5%d8 zyg*z*4vlssCL_1e>pMP&(d#c*i%V1N`{jHNlcIgBMIm1K90uzwa+y@t zB;~=itZ>c9=QdI&^L(84)#q2r>2n^bAKvreu5J1JO8Jq)Bfp29Sc{+^Y~yn+<;Plt zc4137R~Fm3=S_UxrTnhUU7O>3@W72Wzz_R`Yj!?ARDN)W^-j)OR1P-r`JwVVz1(^S z9iS`h1KYqx;0HI_fc~%p>;?P4u3^2#=V$}`us_BI_7Oi7|A_ZL!yOx7v7c*-{agz&m}`n*bNQ#(&p*X}4N5==9}_Oc7}LM{`=5QE3~T}ndpR58 zuL;_JUl#fgS;b-(d>-s&g6;4-*c6|8xo}^H%EN|XY{dVI^!yq5v&+Tf`=61o!=L>= z0%M@p+$HXajWX|-!x)8oB=me9V}yMI{2yoXIJ<|>pk6qC7Jm`$`2J_V57K!A-;;Qy z_Vjx+wHxe->ltCLNsg7d2h7h6D`ODmjAB2R6#F@*7;{bjR_y1RVi~L7oY#^!N_+Sz zxW{bU>EPlD^2!hcU!D%1G4Ddm#heli!}wthQj9go zuR~k>Tnu{bekT0w-v7+^vCDTQWQXrcknd2)4&R|5->r}xzFR?lXNT`xkoQAphwoyL z?`X&l-_ao7-H;u=yP>GhpM6fKvDfD_@O#aj5mzzhJ}1<8>+>9)%g93!f1QtLPN?zR z=dsF(x*@h8uasO?`H`cBdoX-XtNbVr_eCI24)yxqt4hR_4~lIkgTclL4nGQDo@_ZkWGM_Xb$M-1&A< zpFjItQF6Wb{%6Dm__N^90OS#0Vd+4Cc9yR|fOk$19oB z?hFLEBAw3|#1tQ|GWQQ7mb(~@xmR!>FJfUhTR`k|aaQA%>Hz%_JHr_fVqw8KL%~@z z)*`GEn9Im%!#NUSxr==ouQK-rqrX_&z>oNienDr*BVHpGNISUCQ_q^P=0Jbg0Xkrf zfgP~6V2wdt@L+8~U6f-jbaAraeqhNX<(^#p=>2t&4cD*~`WLHG^={0`quAm3S#7rwJVzRMsle3t<~2aQo=KMKBu@}gXGi;^3<`&_8V&Yyj* zsIeDuH^c|Tyb!N^eyH&lXM_cDqu~7;K0nlW&gaa0F70zIjXyp=bn%eRocS!;=Z6}{ ze15C^e9jDgLVV-1XvE8~Uikc6^@k22-tzggi~a7*8F3eOz}UhjA@)Ka=qP-^ zr=QD;5kDlJWY)rfi@sfG;`#{m`&jR<)c0w^9-^P>4|{}ud3yvqm|zF|4)&3TOt2g3 z1$%-o*jd%d=++I-+$g92E@;L3k1AvG%e7KGWXP(dc-dZxM;|>c88UL1;xmq@lvI7w zjUCqoAI`DR4nBt*FzTT`F!;a=jCRl-aL}c&c$4eQ=%Ynl-*?6GCv2kF+e$HPCVwmT zHdE|vo`T1Zg<|d(WBv|p-xuZaeblU!ctq}FEM}nPreoRo4>dBEZC!o-(~h|e!r8z zwne}9L@Q3uqHp*2>`|Z#P{GfZ%t_RW^3Hbu?RNP0@sr~Q_QCK=^heg3t$sGOE!*;A zqJ8;ecw5GbZQGW!3;r)$tO#dZ96z^ZuCguL@;(#Jd0?aeh*>wrs29#)x5b&ywrtDU z2><_Q+c>!b-`>(Q(%(93U9o<=+3$u0Ip9C`@?7&+%b|)}e3)xi_4~E~$_pdI{>*sr zC%NXXr5`Cz|Jk{w)qSTZ|BYwlnyx=iQM_iKTr=gadle6Uf4sS?l~r8w`SGT1hbI*u zA>|MCa^+Wv{3Xvh`4fcaqXVx}nTEo@-$#zWpS0WUQ`au*!}yQd5VmnYg`4|98ahM_ z3q(6OKZtgSc8EUkpMAi6Dly|f<`ACae^6$ExvXEW>|n!?XY#eeKXRRMOY8DF%lPgM zvhMe3{TTGT_t#u=K%W;Bmt3D~);BM|5ao;uQ@1cO%*nVgby>#eMXIOIm-3;r&yhC6 zza<~8ElbtRb>{zs(T4jeT%7RNrcotxZNHEh*JDF|@|*a*z88k)UTk47^%tCBe*Px* zeGPK*XPo!{LpBNihjEWs2mbGF2iL#l%U+%t&d+d`7VbsDSsKTsaPJcCCBgkUFpg2<2!481nK9|H8X^6oWt9w}N&#j`=!z=7%;= z*KxbJ^}zja=TSNCu~Hf6NIbYFOUuzGv;iI|GxAF@Y(RSAp0A+4>AAR;+?R!)37LDr zU`w(Cc<@i(_d|Be+zW;>v;i6Uk^9p#&k|$8r2?jN|0P^c?`j z9{aSU?R@M&^|AUxA5ZUmag^eBW_L}G9yVU_?Iqur{Kok+oP+CfdADoEsr=N@yQOtI zk5GJd)}(aExU&=|gPs+ibv%-%R=vKyn=j*cI6PUh%Mg{RJnWw2l|@|?Kh$bnGHG>V z#WT8AHl-V8E8gjalw^Lkg@)>4n?}v3R9Q4v4^H9qUiklxg+SI#Zh2~|8E*+ow z9tg}4)wTXcWar;CM9Y^f8EKpJTBBn<`S9`b zoO0$pq#NNd?r4w31#6AAg)ygb+$iSLxI4Dj9 zUW~Y7a{BN@H(wT)*hA{Mv4C!`Om#Lt_Pnh0q7g$4%GRDVBklHRFU60n`8XB3DTdv+ zZrJ~!uViQFnSjUlRqH~38ZY!$%h6Yi8RX>$&+;fnU&$X*ZmZMsuW}&VAZNU-a_}H+ z>)>BT+GDS{PjOE3!S=SBS1K;ss+XOYzq@j-sd<|H?2)R9_d4(dd(oi!iudSxn7!?y zCW?pmu4KXOehTcw{oWKm_0dsUr+t;WrZD*8gPjk&)O%j?TbSD*I~2*h=+mcO$W@9w zF2Pq|+pN47vx<6N+|r;$$W@BmKf`#5E%9D0^(EvnW9@yFZdE+! zkYV<;N}nlS*te%`v;Y2TpDCZUuy-!2tN5w6~ER=w!6%&eHCZkncT8RcP)Rs#COTp zA2n0_Lb>v$*3E}2KELs?X8uQeD!%-&Q_PcP-c&sYyxGTe`gF45iWNqf+ZKGM@o;SQ z@n+?7m2_^7dN$XLOHWGB-wS^kZJyu%e#K9`e74#5*>#GWPU~V;?pet|rrGi)=BGJ1 z4u5v2X@6lm#oZU|Y9@cxPjR1bo=?gRbL&f|V=hQWt#Ip0|5LXYK4){-U)Fk+m$g2X zwO+BT^{K4&ie;@&Wvy2%YrU1VUa_q8R@QpOvesK!>s3!#>#eNyie;_0ves)KWv#c+ zJ+vKh#_yv|oHIl_{9!v3_*7g6-FGf;X?_^j!D7YYIvCf%OeiYI&tiPe7^NW2#(X9i z<-f@$1-is_Fs_4fKUl0-+z%p76~u*z{~P0W9HTHQTgN{O{5`INaUG27U|a`Xd?|irGuMfih z@%msv>(eV{=1qFx8%elYXQj;>#EKlsE^LC z+T^cmleiAb*!`jREd3ex$!xq1?lmL6PbS_k>S9pAe2)8+5S61%qHp}34-|Y})aRmc zKUh@z!3mY)IvCf%80!jRSc-`^I`tRNQg5O*JP)^x1 z-20guA9+>&Az7nTrey2>DSzL=+g07W+{f+tcG~HD_ul6FUbu53nW|Hqo(swkHk0>r zdOq@E7jwa0PS0nSH8DGWpQHRsZa&l;^Fuqu-L~J=BxgH4cbNNZvgjSB=P5f+NNTTk zdLGtgVNRtpot{gMpPb*erPK4GJNl+SEFYje>;LhD*rveui#nHxd+MUvQ@ig-z+Aw) z{OLXX`0f~ka``dz-UEC;g_ip=#gL`<|KoiT2`a)b;@HKp6aUb-0binLnen|pTJHSC zJ^TE3&EYq`rW5BK;sf4k{a1LebsW3Q{QZkxOO5j`&byeazz4AQQqG2TIOKAF=sTOj zz97cT7&GG@VcUNfRh)Nm-o<$r=bb;x(fu{fXK0^=^BgV5Sx(%W>-UiI`#JU83OQ0d z6FXS_#QRI|rQiHc(m(%R*|@)h-^O#5%y-eovuN=Lf97i78;JLa`@opjK37nm!8(C* z`T5Q7FXx&UNT) zC&o-njBOq>wNY(1An5R)@$Y?(+EK>YFxny7A^Je{f#?I#2ci!|ABa8>eIWWk^nvID z(FdXrL?4Jg5Pcx}K=gs=1JMVf5ByOd==;sFruxT+>Gg}h6aMR6PuXH$*6YH4{0o7L z6|3;_DD%k`UG?295l1^jABa8>eIWWk^nvID(FdXrL?4Jg5Pcx}K=gs=1JMVf4@4h` zJ`jB%`atx7=mXIQq7Q6+AK2n+UYX~tE%=iXZ8)HeneqXZdhlt=5sdSKSoL_Y_K*(;d(2hWFg#{W#(M_fjYG?maxS=ijl0 zcQR$()#u;GqOyB&F~oiy)o#qTyKXCJ)sWW@{Hf1UQ-rHA4lSKN`FeCbfd({|5Fuf5rQ&%<9x zPb1^5`inh{*i*6C(}+FQCSp$`_EaqPG-6M+q1e-iJ=L~iPb2nBygiNBQ?c07h&_$B zrxAN97JC}8r(&^ZBKA})_DsZ{ip8FZ*i*6lK2$d!7>k|%68ihOU||QDM~TcM#WIf) znMaCc9wjo56w5p^GLIB<9~u9DIi+4zj5&N1@#fCtV4K&-;9Zx=@Q2IWiRaZtyQc2h zd)ei+4$*h$t-o+Xx^QV}eTUxmeP2tTpYs#m3n#YEOG_N{M2h%#Q}tfyxD^+sh}m=J zuFTI~xr6x31helY*XDJoJSWeW=SaDJ|BlEfBCp@SBRq-lB#4*7p9p_~cq#2B(ysCP z7|}=HBP4nn(No{OCi)xEU%r25_nC-cuo3qWHmClk)Zdi)YpK7M`fI7b5+gJHwbWlr z{k6CMaP*9J4cg7XS}5hAzmO081yATN_(OluZs;%c3H^nhp}){y`zzlclNb8y$5G4u zII29`jqS;H_T#Af_;FM{dAu-=r5BXUe)WNJ**v~H?(7eqU;V_ltN!ElQNLn;V?X>i z;}!aqv4hBD>?8acyGgqldx}08JBywf`}4S9joDFYNGMmQ9IPctgr1L$_yUh9? z*E`8`*dI7P$9d=S$++HS^6E@JAR#v9nUd%Gyd~zDE-#IFrrU3Z{Z2yr9qdmv4~hFb zXNS1IbNgk#FAMwDKYf3PJr{ClS@&jQF9wYLA7UM_jGN{R!1AMKDFE2NB4+@`{!)G^ zM*lF@D93&jxjHcRukK6~f9ZQN<(wt+o=nA%mm>TN--DnS{JxFwJqTJ3Szkx>L>s6J z{m}-nJO3}}W9TnFqyB1aM;UZSjsz?}IQLhKzEXctrsa^O{_5EdDuP>VD(CU|nSk=p zU&x34g2O@rJg_M++NAzwu0zO2|FhrE3%k(xV!YH=e!LXJK5RF(r+k*NGuxlXWs~tr ze487MFWNx4A1}pzycEMn*ndP%Er*`$Z@~}ayeqH|+YL5_oncS>1NLQ#Aq$(L95$vn z6X%`SMC`Lsd?tHZvh(kLj|}V^=UrUy#0}!Sb9qZx7c9jeOZJKLPK*)Py9qj9#1t{l z6dNEH!#~(V)*}2?jCD$UCFH}{FDS;E^JjctA@qyuU1q%0hy8dd_Tv@uE{s)Eh zo9pDyuvzeP~vVZ&$>KWCzEs3D?1M1P1r5Pcx}z_#}R zv{?B43ZB)#z5b{bakNA9f#?I#2ci!|ABaBi-{1qtOSbTQ=6~SaDxOhpxnFFlA4Pd* z<7kIyhv);*2ci#b9Uo9T>UoRf`_E@Jl7kt%V*;`fM>|9xh&~W~Ao@V`f#?H&whye? zzK+GeC5x_|`9-5ziffGgCBNYT)fH#wotq9>QeN?z?H8oS-o1R!jaL(ke-J0H?^N%mj&JAAId|2As_4j9>r*r>}H(pv|rE% z9P)2L;%rd|woGVT)Mk*`;ohY)e4BsUvD@L^CRK}i>>g`=`=2s)e0`UmS1pp~!QCDO z|8KkJ!O>b#Ki@&mt!(sMDm^cTJ(}**@GK@j-->4gpd-rg8L<4|xd6q#^;{K%x>md= zFPvv%&SM^;{JZn+)bd*8&#t;-dYfW1`m?IV_PSPa*NQc=&RcPT;(wmlIZOU2ma;7Q zOtHvjNu8PC7mh69QY_qAXanWaKFamox+vE+ygb@a-Gm2i0D~X@fVE6Mb38S&&;~F# zTpJTCxX}j6(IS=4B>9=p)$`;Le;&1)NBZQEo_VBy-h1mW-NW(RgYwW{$Ok)sCr|Ye zTaw+-u9jzr}jUB}qtbIDBh~KnEVC~a##BW+7G+x685Wi`S*l3M| z9YegPH3ITsjQ~$rBXpgEJk|$VBcPAS=^BBxPcb-XjnMT6GH8>^vGxV|jn*3C$J(bl zxV~oeF{I~4Yuw8fOU?5A+GtHAI~ZO=$!=KtsxyI!ny> zIt3TX!F~DePtOE~UQ(VD%0)f_hP?172G5SSOjle!>z`?}J0Da0Y{fZgj|*Q`oYt9= zemwIN#U--3r2TLGPI1=iGU@gQuUCBOwCnNSU5#aUzXFx#kbFWs3GpY?ZbJIVGiMn+ zlV5hP@APT$WpeS`A8NneyXL24zun3ze!S@hV6_9V$S8)4)J@U%RO*rqA*4@ z)uq00TPfEio1~<3%5}-Mzgd@j;5X}%Z=~EV*X6cYo@KZkz9@4*<8#D+1v?a+?-zBh zPVdIq=oxK#))juEz9VsDqi4P8Sy#lr;9r)W@x=SLwcI`b?QD;CMN@f^JQMn77u|4UTV#umIWO-cpnfgt}QPw=SAHu!@*te;=`EgW? zHfe9N(K<$Z6Mc_5c>FkOUG$gy6XU4mXj9ryELHGKv|{Xicu$1SzzJE>bECZ#J$sJw z6!K`3>;Mjna`2Gd{vXd`gJq-fQ~gl7^~;@acy86d@Ho?7)C+wtEH-EdJ|Mrg5dRU| zWZFWTq20n_>ve|w7GcTvk=q-8-l!P+A;0I+eTLt2$!B`rs4}$Y@@HmxE@x=ZWw5{T z=W+)79yxEE>Dxm&_C;Fm_cAK)_gu>3_dd$+_e6SD=l5KykKaS7o_=qY*$;u=pEp`y z=tA;g&jlWwH>wQwL)5Oefx55(=^5I9{y1;UgG^`xzftb@TKGu!?^Y47Xt;Nfiyv9gvxpBxJ-I<{qJH~Mw z8);tW_Xvu;jTQSng699QG4BPo?Kr|4-1q@S?5q&&5bf}H^?_r$UY9(#V7SJi!r+qI zjWjPkH%?;}W3F4W=E|gN|6a;@)r|ek+zVPL-oHsbbLs3O6xW=5s(E$p9*Sq*+0Q&z z{YB+u9xi8j=3#zrmw6b^ozu;B>A67WltJ~AoC5k^8zN6jy*ba)z z{rGr#XvKkwdp*@LeWlE3#b>@>JHOQ9xr#rYRXmye^*F`M&*d!7Jj~DSvOcV*^d*(? zGMJH!PrIR-S^R|2@-uJS!JL`jLGkAkZSq~efr=-MZ=d|5?r6nV-+5S0uO+#PhYc)| z)>}PJG4pUa%QFx2bGxitVKCc`G1tB4+Yi$HNB34e&wQ!0J*jzX#qC?ywr@RLNAXFO zTiJaFmr;Dmb-nDj=YNvGRy7VBZWq_MQStL_$JteL_fcH)hg>`8tceRDv*@QWw$xj- z)i;WrGsI3Sf0ts`fy-H*d6=KuWqnvr)}Q;u{YCtdGfB-=k$Z(40r^5WFZ8*ZMPHC# zg!4k=9rCx9%SX7bsTjGS)K@Hgc-OmP{vKGg6Uxy}kQbiJxj5Ph{P-Q(_3bDp>IFT) z7xb5YS;-aUY#BcVedKuS`>W&S`>WXZ*Py2FuVUX{#qtsQtJwEfvG1>9cfRcM9^c;} zkNzqap3M2N@2{5o{wntURqXq#diwqtn&g7}5 zei^jo`=xl3@q*uKIghVY$&9=2m&*8lDfazR?E9rUv%ksQ-=g*LpbD)`>(cvL=**aT zmd^h$$!*qKWoAy;*K~TmmEwJB*D*_9t*w~lxt!&hXVTgxX2qLsEo00&j6SD@x$mL< zm48xxGxL4R@`_o8%US-*8|#`L{f{!}7h`T~`VL)9wNAgNKdfpw*v!wpPw~t%#+Zi= zJYMnW4|B~acYdSsw(UR1nKff~P@7lV{~WW|oBvRJ?`~(B;?v$!ykzG#X8F>6v|VnC z%UPazn4jBaeOOP{|KuUdb9T1lwOz(bJFQM?-qcg=mRtV-v#zcCzW1M=I@XNd+kJ<1 z_jgV+!ynj9Wy(EpmicbjGurp2b4QvXyAD&_?#x`XPxZ;T&!pH+v&NgMZ@q|nFpB*! zVuZQ-?8~(8-S_EZN_BqQ;jdboGG915Tzy|{Q?r9x@9J0I$2>Q(jp~^*XGL<$s6L8Y z&$uKh`OpZ(tTUIhJo7MrcWRgQVLe%Y?icr$?ZEb7yRkhVEio^7uC9x{jCm}s-m!ji z%j z&hpH|{M@ea{M$Gw`J|P+)WWwVKeUpUDwe!4mAq83d6=Ku-Rrzjc23>i+IPlRey}EOw_kT{tMsDswo~tBiie(E-|pGvFvWdqo@UQa zcURoHML&DRlP{&{SKlV*+C~#DRNN)g_^Dmi zhxKHB#-;7L?{>5_?-#c}T9aAeuam_Dt?UB1!T~m&kIL_`+Y7gb#dGK&Mw(|9gnV-v9 zo_Uy`+hu)NPnZ8p$(*^uFYv>C>^r@sompi+gYqM$)UwTo9Ig1P3rg9N)7vU8{@fes zkku}R-+a*}Y2(LSOzV69i}{meoj~2wCta9x(+C%f%1r8?++BH;manU@G+F;ff5o+i z?QE|9@pQ#~CLC(+*fUYQ&*G-0|LX@TUfZvm8PMf>wa+I{4>5bxn63EQ0b|XVmseNJ z`g1wUGY|7~yQ~lE$@+7@xW8-%wh!Bl?a6i?c=*C3Ej`G>Zj3QrVc&5=)3K)S`!!R@ z%x^Hn{Mhks#RCuTY7TnZ`QANwCz?j14pN?X+8<(0f4iaLHrXXj-eY~UQOUYGd_fy^8d~jtlw5dCj;knH6T+Z^$!!h%S=DD`@O;a_#eRpiG zeQ4e^jeAR4jIw*&+gEKkWY$3Y`KhVmb0&AP-G45w`kdPRL_6p?XHTA+%+KX4&pgb} z?Xo_sC&$LZVD|sQ;EUdGls2j7;wodQYb5Te9j0|?WtLVcqjvbmDYZ@B0(XD;zL%Fa z>A2Qf{`14{C%u-sJwo~3*CZQCoTKHvTknuOv&^lDt8ZGr@VfV0+-80*XL;sfer}ib zVLh3j@#%v*nik_r8qA$LpBQMKd?r5u{=DsI^Vr$#6hHK&YRv6FH#t~7ktbl@${ZfoAXF8%ek;cCylcKax8 zRomHl)s6ewa~8V2*gujw_PD3rUhIZ)t?jTfZcn#lY;XJ4$`6$Ptrv&esI>*;(}-RowLK zGwk(mZl^p~R6pLXea*esi+Q-5<(Y^1xm}611~CQgGL}92j1a#h)+UH?kdauMAoc-E ztW6LTfhE=ba^wFWU1SYoX~Yz5xu6s(b%lsMXl353)x2$q`GS7XM=W>>39?`)_yiz+eE@uEw6lb8~f|gZtvf+ zO&vS(;o54qX{+|JlfG@O_^i%vr_JTO0As#(^kr%Hb6no|P2HFBSIl&IWB#p^axUoO z^2W>N4^19?V5G|5V4g`P*s~PBJ#{y8*w?2i?!5LelYDTj;)zE$H*a-4K=FbLdYX40 zTCKXhcIa?Z>9rdav(8-3^322h+%D_Gdb0l9FYYhff$hU~V|(sWzMjo{^#}{QF<$f3 zH_3goyK8y9t7j(nByJy6y?FKH!l7>5_wF&d{+S!x`g>dZgVHX~y7IOCZcBgp#>qeS z$rtHkb9*SyX?q@EPaf{hi1oyxqN!VcHYJlCH1$a#u)-yzqYHh;e6bt|%R?E}~3>H5MvT+Z^$!~EPX`wZhf zyPj^F_1r~u+wsc&_UF<6RDFKjZIrF?(*VWuN95W{6E0NUuDE5qJ@&y@RJR8&9${7ut1QpuEYCdbCxyZ61BJnCpTc0C3w!O6YbU=jSAC}9 z(YdzmvA3!(9eCbI+wbRdbc|Xa(BD?RdAS=q@=4}lA7gpuVSaA+j9J4?mHg|JpYe>{ zcQG5T_51etIv4%6*F88a~EcRjQ%l z$)Dz$d-}cB05Yqlk2BvMx~sOu{9MlR%)|WLF6+~W^sJln$-?rVxY)>;`#7LMZ!`3> z4^^MCOIw*rlUm?TOCc>BD5+aOac1EWb9ntAk7sXx4&9oqY3?c-UkkF~c>an}x>IN?+~s+^0-wWs&BA1``U+hTq$ zXL;sfer}ibVLhw=>v*$sNw*hZ%zZ4Lj<+3_xU)U z{NBg=rE9CZGxkqjn$ck4w=QpKabd%x>)B&eX7$MXlcyJ*t@!9=#mte$UFRKJ{a|y$ zphjBG`g1wUGY|7~yQ~lE$@+7@xW8-%wh!Bl?a6lLx%0`$TNe&o!wqWG%b1@qju{t^+0p)+NO#*R@MPpPr?;eXarpZwy2A@<3ocPg%bLpS^GytRr4FFwgOy{dxpTz7L# zyP$Fd#n*hWn=Ni#KHUAI7t+3u^wV>39_HtESs&Ju`5Cuudu6&|@i`WAZPD7d z)74*|skn8|y>0RB+bTALYuPSSj#hl`vKDsmiSC;3*av&sYrp+8Mcv+a46_vvyG8Mm zgU8tiF56!*^K&`NGY|7~yQ~lE+3$lv)f;xpqqXJ{qH# zpUYXEd6=KuWqnvr=4ae0e?wAwX=fdaqo>YG&MY@r@jsU}NT%NG&Ivo$zofy}-@CcI zqHei#$u4d!d+Vax()M4twS#%MoaLE^`MF&=^GxJAmw^v3ex=DV_VM{gYI)TI%G&H2 z?iym-rJtp_IX$)f)hg4|&)T^7e8(;2(>3ed8P2KC?cJcudKaHBdE~I<%fyv0dUaOv z;ff(zm-)Gz<(Y^1xn0(W^;~&Dt|_@@jE*&9?&EhQ4>T3}o}~Ibb#spCwBb<2A3lG& z+2{V970-IFznS^dQ|h0kaz>e(m-kc5JY3H5%)|WLE}yqE#+l7u<$6TWlXdoeQ5*Ve zABz3855@l4hhl&2Lv8D?eJJ+VJ`^)2m$N+cFh94;`fSPB80HB3(lvLCGRLpzp}Osw zGtd<8{kY;rcXTwbRCi~R^V%M7YR`6g)P^q(Hdib^LHql9z3t2o&z<4>uGgd#Ge7s2 z<(Y^1xn0(W^<*D=vEIu`$)nu$pj{S!n%wt9Pm4ZsY+-pWXL;t~HTRU6OVY`m2WY=4 zO(|}_S>8$U=e-WJ=Tva>j^hB=<#Lv19_HsYu`rnDZ(%UU@WNnT%PyLoYu}i1ipHY7 zn~k@-cK%$~qqkl-$FBeBiWD{5$%Tt>-nG+vReWXCCI~c3B_RllA9*NuJq2_IEnIj3vjjvY*v?A^RpP z`#Z(5pR%&QQ+e5ES=rwymi?EN{heajm!-15Q!M+nRQ7j@WgnNy{!TITb2-a15A$=o ztPktS{EQ{nwXz?#7(3bLTG@{)mi@1l{kUS;7hBnn>zK-Z*~)%gvFxL*?8g<${@TiZ zT+fJP-)&_-uJ&PmE@ye>VSa9x^c6(Z`M|2rvy-KlxbkPOo{=1SmXl|G zE@ye>VSa9x^Siq4nNxXF6rM{pq5k z`kNJ1m+M%(`PxWRX~JN|%){j@&pgb}?T)=|s6FT8JJbglpL9h9v-HW6Ed1*7`@T+g zUE^}#iaSqFnzkFJ<%?>UN*48VIpO_fisi3)*X4@KPHLTgIdiniyi+wlUHRca#oyN7 z!4_NBL2>`LtJ(G!8^tYpG__~9si^qH54zdCW_+jmunt_#^322h+%D_Gdb0l9FYYhv zzyis!Z)AmSnoA0*Hn0;tH#x-7mqUkTGC7VvgpVG=8SWnRJ>rr z>1MmWJ8OTZU7Ta?DN{o+b8w*Zs@d?Z0v{jbjn>a5>8}5A$=o z7r)fdmhE+j+K}#Z!4o`Jf`#tHS&v7^@gXMJNv z9a&xRXOCAj=kDB8@w~1-B-N^PQ{1}B?4s*^R{aPKD zJxa(KW`zedp1fXWq^)rM*aZAl^Utyan?0lWsuri)-0{0;yZfJ%*clDoo^i=(m2A${ zO|*R8@O5d&hq@?ceYl+EnTPqgUDk*7Wc|5c++Vf>k1yk^*OoG;wQj3AcR2beQ|!6A ziudZ?%H)qu-sXnmK2SU4_B_YD_5M|gXJn5zgNCkEyD<-!vpn-KKev0}>Eq4Q zFR#*ZVf=3Ail$$CcMe(oiNvIjR9D^lKHAi{4dAOYAnTPqgUFKnYf2Sd~UEW>V?%8{Hwe@Pb>oR9lJkcIrv9jt}_4sVt z@VVm@-+ShEw#EZ)Klo$LL+K8?x^wLI0~)2z_xKf81JWOfM`>pHBx zBYEvYmtQR^wl=wTSvQqu9k`t3nTPqgUDk*7Wc|5c++QBMo=@kR_xC?o?SIRWW8~hp z#%iCrGY6X!X3SAMp-(r{y^p&GHTTVCW={3;+Lxx|k1!q1uBVuNjQP2o<(Y^1xn0(W z_2l_m7|cFU7|e69FqmUqj|bMKldpGUeQ?eJ*0yo$+KP5{?N#^59G0I_SG2UJ*WXX^ z16_L9D-ZZe?aaQxoLtWG%)|WLF6;B`>tEzt-e|mq4vgg*u95p#Qk0t|ZOrs^Zb`amT5{GqM81H(}-O0}?9OH722aj!A z|1O`C9KGz2^oCqlK6S_0X@i%X{HGs&pEhpnavSF1a+YTv=I3@#D3)tiTeqe&W}PqH zF|pk*JyiQr_sY|4gZB-yge&>b8H!e)h}BFR2duU45>7yv6y7=YKQae*MBDs?S4> za&7O2Z`2sO;*ycJ>9}(e_{>vZoMk(n<*vgnd%2x0SKsY(Yb(*(vf|zKhi?&*d!7 zJS<-rjJX}!Dh%c|t}vM6TVb%=(`DrTNdsLNOKxLj|EqCnV%gDl&ucp-kePqoKs$DJ zs(9@A9qrU^?z+imJ&&`y<-2=>AOF0v9Xg`1avuKahIHVgofW_Q@%*&$J1$Rt>%HUB z+q$?s`QR6pEZp}CHx{3FES2=^>+<9qXWo=_`oLYUJg)WXq|Y>WCeX2ASu<_V7Rt$b zayiR05A$=otPktS`g6ayzibD#58JKbaSiN-O7H`!UtsE zXJx;sSoVWf_M3`jpJ-*jsqsPfk5=}Zie+DEWxuKYVjeDMdFEk$Zg>61XP9K4?X+FS z?87@XJ;jv2VlM-o7k|*ltoZT`wPF44BTU&{CMmwV`*?H57ayyi?>{Hkoc?fg)${S3 z(I)?=(^dad>I^dVFMCWe^K&`NGY|7~yQ~lE$>Yel&FN#!73bGb9iAUI#9X=hPQ|x9 z(bcqE=;Hr@vznO2_1(3Ms&7>@qc1UPpS_RS(R|mngW_uEEK2Sx>CTy-|Dto!arG!I zKW$XAoDb&aDt@8Scln3aaC?C=4_uX=e3r}MOC9k+TJEmiDpR6D8GBI|x6ZCyQP&<; z-R%Y5>(SP}wxX2El=-}m{o$!MR8Q8Q%UPazn4jBaeOOP{pZmrAWjnBa*lui3wlhDw zeNMx(>m%y) zVSa9x^(=c@0?bd z@7Bi(AO6r_{rhg+e7x?7$$5vk^|bM>4yqR6%4YgH`>vGL~bNZ^UE_!E_Y4k!D zwcGM52bxcor;1P9(9yK|$M(uO^v>hWYsY6PKDSm?^URbJ6f-}Uvpn-KKex;Ju%67% zxLLcalWJ|xG3f8*b3RBuzpS_7`;3-3DphD({xGyVdEa_^r#T z*(;xSYt7&To7$Oq6}6mo;BuB{9_HtESs&Ju_2+(Zf9qHHG^zH5%NrT9t@f%u)ZV&F zp8DS4`^VZT?^IDdWPPqJ`O02;59$|Rjj=Z^sFT2+d9w%GPygZ0Kl_jFVw02CYx%>g z8{2_h-C6O6_h#F@hPboh&u`n_4*0&KLETnU9!o3L9;Eo>A6lm?Zyv4qwPc_C8Lzsz zoOPx=Pxi2zwy9y> zY2&W3vOlvtm$N+cNIsBx@8bEpo@-8QFj0N1@(v@+4VPZ7nAang=W>>39$q5~gE^)Z z24l}EXRPu4b?$wAI^X&IWBgt+eqWimQ06^m{C+e4J~#DevFpL%On~2$#_vxPp3HmI z_!G{^R{wvG-@i@ja7nf5dT{<2m~e`xU=uGS0g=@BBKVbIPwHao)N25*x7x z-gArh)+&}iGkH;*cXKuW_j#IPi6`;B%HkwGk5!xa{8s0b&)*csdFS@U+cGbW>s?&$ z;=GIVPC_)!B{qx09G^LEb3BjhUHl$_zsfmGT<_v~7uUPE-o^E{rG*vFa+JV!1pu6`#A@zpLqKymi09Az18eL>{qxS1ox%E zuyNkSdFTBEai^H~AI0)#=6<0#@7(>s-VSlzxphkY#K)6x{%jDJ;YW-?sP@@OM)76z}+ZEe21w6yXwW<7sgbWl=lnH%ff z9-W@FtmmH9YCUCjvhwntTDRk({mk4$TPiNrzpg2NvwIGA>BNuaJL+8@xt!&hhxxf( z)~zsjMTbF|cIAE~d}rKdecW35u%4_x_lx_>?G|Q?HkR?W)WQPHedK$pv8Lf#h~wBg z_egMC{_I89O@GZrG2d(9uhFOuTe`OmI4@K-_K8Ou8}t-J@-K!P!3MDMC7KW?9K z_Qm!G=zKh=%W&J{+UpfxvCo0X*c5I$|Uh?QekF|S0e7JHl50|q%^DsZR z%eoZ?%QI`HOV72c8)L5f&&6M-pMBxpy>nTu>FEWn+&e3>A1swt=whk3)>LuN3D&%+nyIwNXnFmrP0c~mDsE<5E@ye> zVSa9x^upj`@77`L)r3io1O;@BHsOS>L7Hxc?aQ>6`8y z%eM|Z+Z=Vwf)qZ}seLCit!)VleB{F8&HFXnv%qc7sA9G&*I3JYH2F0dS*wfUPg>1M zetN*oyXu{5CDqHg_}O`U?fQ@V_gQhw=f3>+>gnE10~^RZP(O$`+9CQt^nvID(FdXr zL?4Jg5Pcx}K=gs=1JMVf4@4h`J`jB%`atx7=mXIQq7OtLh&~W~Ao@V`f#?I#2ci!| zABa8>eIWWk^nvID(FdXrL?4Jg5Pcx}K=gs=1JMVf4@4h`J`jB%`atx7=mXIQq7OtL zh&~W~Ao@V`f#?JObv~faz58*ASPk*--%-KutBBZnOteF^L-c{@1JMVf4@4h`J`jB% z`atx7=mXIQq7OtLh&~W~Ao@V`f#?I#2ci!|ABa8>eIWWk^nvID(FdXrL?4Jg5Pcx} zK=gs=1JMVf4@4h`J`jB%`atx7=mXIQq7OtLh&~W~Ao@V`f#?I#2ci!|ABa8>eIWWk z^nq>V1I3D+c0)D0_z9!Wg)_c-Z7F+N>$Y0ns`LSN(%|NbumAoaJE`G`idlxsS$=7! z)k)2pda69*Hm8p@SDar%zr%g+2Zx%KFWj#9npQo{mFIn?c*=P#P2cAGY27=Q*EZEn z9mU<3mN8F#&{8q;a5>8}5A$=o@;&diOV731Zeg(4%81c2_6W+Mc83?_K+P zQst<=iicI(&0KR#JH;%+xa?GSyS2z@~3qvwxU4e?+1{*pK@aa^Jg{55>Q zzJ7ma>*8s#Lf{E@@>M%lb@GM5${BnC{J)0{$rJ)_Y3wTo&d}fA#kEfyVJa+}l%T(i z|Ml$%Q|+6HT0Z!ObItqvp0D_$dLzwKgGO(LS%&LQo;J{&a$c(PjQ5^2$ei%XBU-*- z$l2zW$_o?^YCG7BA8_Ahm}R)`fKEM3oho0cJmb0(dz$PytF^r6UA;_;qdrmm**|-m zCG+3k46_W^J#+f0=CFV4p<~Lp)^_d8s?ob?`GW4Jn`&KmQM~HW_NI8loi@WP!*#d6 zqLF!L`-4@U@n_j5nukkQ*77eGHZfOMs-$?k7AKjJha9*WW*M&A?zCFw{JV};dB$&5 zs%^epS;z6qZ~P4(fGp%T#gGj$To<}PC&)8~zR(Hf=m&HHMqkm-O)<-GUDy&fg*;=} z8#YBb#sM}3##mvTHpMK%b>R!}3CJ^szrZI@4nKlV0K?bdXPaV{;kxi;_%!4h!{6c4 zD91d2PXlAFV4iG>S%&LkE@DnXo-yVt<|N87k1;2KG1oEAH^nT&b+b<_l^oP>oXRu4 z`j~Rb{kypGL$a$TJLHX3nY&6Io|Lb@Ic6EId;IoZ?R~p7zd>|!%$Y7S?y5ess`CA5yzoo$^#oyB4 ztK!2c`Ev%d4A+(UlG1$1V3{vzm{T%e(lFO#4yH68Gni$#uFQ8!^F4!QzS|HJWWL)F zD0Id11-hF3}zXwEAiG+yv<;Vx0d3q4Y68e zEyeQ;7TJsp*A-nXtrrkJluv52$a6hE?vzrf;amhyoNW*M$4zHBMq$YAkzi#Q8T znFki}7g*+srFWX7a5Ky@T-T46$}{%krR9FS6nlTz46_W^ z_5P;vjJ>~Ux%W54-k&$aEW>sEd{KGEe!ghApD&92eB2DP4A=GZ-NOEi{e0JQKi?Jm zc(NI08LsQ&mC7^r@k+~myi)Ar;bxd+xUP@4D$m%*TgUHWwPGL7H^V+AYdP2T>xGsx z_Una~`}IPxUynA!EW>sEdZ+S?{d%Y6e!Wxd*VD}~%Wz%4UaLG~zg}y(U#}JWd|)%o zGF;c^8!FG(=Nnq?^9{v5pVf{CXTgI!0`V6ZxdvkNrkG{8uHSE}JY(cLh_m299)$P{j9dvZdQ;3Y zT-WcHRh}{OHN;u)Adf@*1xBui7`-WG8LsR1`zp^E`6l8lc#wx8{sJRcMU37Qvkceu z=M^f?82K{dEO_KM&N>t$*G7y+Ib)XLy2#}bmm$ws^u?KsmPX_bE&;D^rZU8e%l$ z8M6%6#a<9`8S;$9-*Kj=;?DY|&H^nT&btM)W#AV1cmUw9pXHhP( z&>;Q-eIWWk^nvID(FdXrL?4Jg5Pcx}K=gs=1JMVf4@4h` zJ`jB%`atx7=mXIQq7OtLh&~W~Ao@V`f#?I#2ci!|ABa8>eIWWk^nvID(FdXrL?4Jg z5Pcx}K=gs=1JMVf4{V7K_-C$jP=~R9hFZ)0v(<|I^VgeUmf^Zi7yLg#pUHQBNBnoU zL-!dClJ?Wa=yULl8<#AeGv;0Qe!>;6P0HV`kHcT=)NJAQzc_qbvnO);zcF6x9)ITS z?tgLyfd<(_-Z@ij( zcSB#rw>bA?3x#pmrgY%)=*Y!u4 zH{a=}{d)X?(I)TER*HwOINN;r-F(G$JGJ~j_TB?p&!TGkkAxz<_Yw%nIVV79N|QYI z(0fM&k={gUB1JkukPcD==`G1Q0R#l3CeI8AN-rV;QbYtP(u*KXzWuwNJ%nSK z?|Q%gVJ+lxGS8lJ@7c3wUwbBL^TX#%)PG^ih0^Aw^SCsnLQTfaFZH- zYh5#K+WP3uJFb8J-DS<7%{uGih~K}_+GK^!oF95YyM5U69enX?`?v2qwln|D3%{B8 z=T|1he`%JTPT$=5#QfJKI&Yu;Y}EGoqnkV5t9j(5_V+jK$b4`6LCs%3=)7xs z#En-qJMGhXyER`rQ<{I7P1VoyUtT?ZYn!3MLk8`h7TM{y8q4*oeJ@?~@)Tv1ficdv)sNDqe?2mTw|!^3wEvFp2)}U9N@>MAdo;I4y){?5cJ0pE zTB%j@4U~m&5N_98{g`DyS4Tn zk-DExs?dTa3G z!l&%_{q*(I?h_t1*%oQ3ou*FIS#!%p(q3~W;VTBe)Li{`=e^vnr}k`SdZY6`?XNfA zeAMP2biUD?e_AWwK4s^-+&Zc!@As3=`nvht!TG>HcjiChyYD?Y@9}8o?=ZP|u96oW z-FYMTv}MNT_YeG`+CAX>ZSt9a?tIgap1XY1X>WGg`uKwbnpHRM^kKO(-);siw!P{v z`PA3aql+vneCxNiOIwb8SK~VFy{*#V)xM(g%@)`*J@d~ADj$0DVd?4*?vZZ4{?|j& zpe1}s4)45!l-}q`cW=Iu$|s&SD*burNa0tk&lASHt9Jjf=>F+| zBTf{)>G{J`>&Ry((uWhT{!zMZ>mwTQ+wX0ezI);13B1mp+oV72_p!=v*nh25mK&n- z7x$h$z5B-vgA}u-nR)FA?VVrkte4+zbyoiSF8iwf$3Hwa zKi2N7ukTI0M;ML8XLi2xob$hTYo7M2oo~0x-PkU#%BEfho(D+?c6(I zDf<)^o=mx-hQrG(#hYuuZO2%xA>U zoUm$IXZhh}!OhR^eqf%Z(`wHySGF7Tjjpv97?rlWcw{-?#RJE#J!bv%(SdW7t^c-M z?bUwPaMH>{cWn*HGP{Hb?$^;~#&9zXYP zX^-*4x}RHXLSAf@&Uatv^-J?t4(-_Ci2we=oB6Q|JL~AFM`kGR?EOvY!1gyyR`#2B zE8$<>@o+x+vCiK$w8JAQUunJzbM^GRv$cl(p|dt0y!e#n(bGEXdd3;2NpqahdDHu? zdsa@rTdiC5msquxUfI60M~vKdvvk5f)2n>SC-+I~-q+bv9=Z7NbmyVp(c0YMR|lty z@A-z-!n(`tmbRPyZsFn2Z+KPjjz*VjKCV-*s?0 zV9*K;c>X`^ltvx*SK+zO`$k&Kd?U(#wR}pieSHz($3GaF9{B$1!VkQ9U$g)A-xt1Q z--Vi$?(NvgKhAh@d&*@xb9mByKhL8M?X1BSFa03DwfwfKfB4L=WGd{)%W_*kj%=j25nDH@AFymvKV8+Kd!Hkb_f*Bv<1T#Ly31)nZ z6U_J?vvGnMAL9fwKE?@Ve2f!}o}#0l$LJ~gN;!IpzJk$H^c9SrqOV}|bbHfRFnWr< zg3(j-6^x#uuVC~PeFdYZ=qngKMPI?_Df$XVPtjK}dWyb+(NpvljGm&eVDuDy1!Hfp zHJ``W8|)6{*c?H!=D4=$KlU`@#FC4!1!_ab71^9{5dfGIDYwv4d*<$ z;%n}o>ty_K{PO1JU-#jUMKaO9%#pP#oOdww|QD$ZA@U3Om==PJ%uA0B#EH|HwOSEn9+Qa9(S>+O7X*s05ObFSii z_3=@?U7V{pU#&CqJ;OOyalZP=qTRzdS8=|Yu;?NeaIWHfHOHw>jOAR#`D*iRFYM!d z%-NWJM$Gw`b28J;vHb(9K<`o#5ss}fQfSu?*J3$Al?Bc&Oy8b zOq_#w2beeq@eVL?4&ohP;vB>~z{EL-cYuj=5bppJ=OEqzCSFCXs_UJ}`|(3lOfiUf z6>+PXPCsfK@hak0)F)m=+zL#*intY+colIgF!3tlR$$^)#I3-@tB6~HiB}P~0u!$y zZUrV@McfKZyo$J$u*Iv0TY-sJ5w`*puOe;*CSFC{3QW9;xD}YVBQeL%W8#j)A1Np9 zNc<5@+>!Vrn7AYHM=)_m;*VhBj>I3q#2tx0f{8m4e*_bEB>o5{?nwL*Ox%(9Bbc}& z@kcOmN8*oQ;*P{0!NeVjKZ1!n5`P2}cO?FJ;6v|>d+z4#%D83!uJVY_e&Pq^y#udM z`JL+@P>xypK;b?2*te|kwX=k0`qTHzlh@oM{F@inEeqc@kJ|d~2E)q98+H8K>wBKc zH~wW8mEU|9W=h{AS#^jy&%p%9G zoo0Hf<1^g6$b4zPKdz(xobr>Kn*(<3?0t8wcX?||^NpDE_6^UpZuvoHjI&*}MEjSw zb;>Wh=%T#otetiG^PXwTolk#D^$)&zg|h4tow)SMgSINeUg)gBw@3f5Y%yJDykEO< zuQKcx*Q#%4Z?t#_5EW8bp-!Dly9O+U@p+uz%=TxY(^;ay9PS>e^?$}ux7o!%X>;3enJJ7sx( z#x2u!ug`GtP2-QrH~w+|^uvdyx%lcoUOwt)<~N*u?c+nnZ8u@UYyUhv{rt(NFF4?W zIhrMwJ2d4T9$#?ZQyyy8`}X(J13OQ>(8f5z3 zU-7zOHpavlcl_{*VK&CZ7&n=Amti)>#2BA^ZJJ>=#^hsM*v6QAj6-dV$;Y^mjj{1D zE@Wez=wrOl#<-%7aRD1+_Ay>$W6VCri*1a>$9S=gvG^D-u`w3Lxb_z3ji+@misT`fUZ`?2Y23A$Q>u9l#yCFp7ix>|y+mY}OS=xRIYYCGs^E9hzy zbTtKCO+i;v(A5-lHC0_TJClOV>BnYsQm{EG*qjt>P6{?B1)GzC&1r(oX@bqk!REAs z&B?*$lwfm8usJ2zoDytK2{xxxn`3)N342FBw!Nc-y`zM^qlCSqguSDLy`zM^qlCR9 zhrJ_*y(5RcqaF5+ChQ$e*gI0#J5ty?QrJ5Zdj~ene1L=x@Of-LK*9&0+x)qjiF ze7O>Qxe|Q25`4K5e7O>Qxe|Q25`4K5e7PKaxg31C9DKP}@a3A|%cbDUrQpk@;LD}z z%b6dZf=}L$%_mR6Cr`mAPr)Zo!6#3_CvSpJ-UOe#9enZ}eDWN8@*I5f5`6L!eDV@} z@)CUV5`6MfeR4Zb70y%WWW;v1Dx9q-x3g6VXR8vnI`CQ9`Vvgjh!ov5pdA z9XZ50+BMc;oK+KI9ZiUJBw`&8-nGdB7VAjFI{rT9rePNANW?lG>N~O9Vpb`{topIV ztP(M+Sx&yJ+hSIUnAJ+ddb%uTm55pG_N`flTg)mEv+BO^n1wB7)r6Q;6Jl1QLd+_M zm{kces~lohCB&>sh*^~ovnnBGRYJ_FgqT&SF)NEbmJoaF#}<1mA@*28?6HK{V+pax z5@L@f#2!nCJ(duAEFtz-LhLbz*ki7-N8_woA@=_ELvTRwPYxN$lSoX%=je6!0qofe!aDf*@3!$3xT|aCpQYQzSKzMR zUgnR(ZF~jpYQ400uZ^$3U5)Eqr`N_;;I8hyXT@xVc=pIpeHaftzar zH`fGiuBqId>1hLZb=v_;jgQ#$v@h5 zt_GjK=Qz{T0(Z6H@eA~to));P$7bEE*Yvc&U5&fw*m0((1@3Cclg4+Mo));P$^Wrl zx9MqtyLxo=54ufHOXXP2-ju+V_hYj+1?~!cFnd$ruE1t*3fz_OnDqWBWz}cLlb6qk+2u+rH6)y8_$3 zk>Reuwr^y(E3oYw1?~!L`$mDg0^7b(;I6>7ZxpyIu2dRV{q!MzFO2|PfAqT019Hatw#dk43u7n(<5^|7A$U!PK2g&^L0$Uf{0a zt;`=Ua98kF=8qS+D|jpO#|zvQyp{Rm1?~#o%KY&HcLi@{{&@K$!NDsWfuR(7r`a98kFcCIRLSMXMLt}1X> z@K$!NDsWfuR(7r`a98kFcCIRLSMXMLt}1X>@K$y{E+MzGAKUr3gxt;?ayxU#?JOa; zvxMBv5^_6B$n7j4x3h%Y&JuDvOUUgka91B}^2|bZJ}z)qYcGA|FgqV-xT{A;?l#=c z$8ET)A8dNia62Ej;I57u^Ts$kAGhGH{_*?!#u;bThP!(Bke{7nF%RLN=DE(XI7bWa zYT9Q<^je&wfxB8@&56Ah=V-xQ-Ld~7y%y&f1$XteGTm5cvT6x z*8SMxRXOBZ=a6fiL#}lWxz+{l3Y%c@suFUoOUSh@A=kQuT?3qy56-RVCzF zmym0nL#}lWxz-cmuIPistJ*c!+TxBmJMxD9s&w)k;|y8;^zkm0UAkBtY& za95NY5736Y0viv|hPwhA50J%O88jXs!(CBqJV1fF0viud;I6>N0~EL`u<-x|?h0%? zK!Ljg8xK(6uE53v6u2v}@c;$x3T!+;fx7}54^ZH)z{Ue)xGR!(DwI z8=sTmt|&J?C&OKVjnBz&S776FGTar|_?!ZF1vWmXz+Hij&na+MVB>QN+!fgPoC0?R zHa@4oU4f0yDR5U{<8un!71;Qk0(S*AKBvH4fsN0}a93dCb28i&*!Y|bcLnw_PJ(@m zD)%u8`xu3NjKV%fVIQNgk5Smis6P7`74!5lu1J4;jG6}@qp**$P{+q8>|+%6F$((_ zg`P}A|+qd6# zVYfNu)V~bv^1VafF=F34RBoIVdxx-bR_q>a|!S+RFW z_l&b*?+`Z5ioHYFI4kxJ*&O4n*gG2L-#9Dw4q@Z0*gF#C##ym<2pea`-XUz96?=!U z`v8+*_W@LHoE1KRuyI!S0K&#u;R6U8XN3^^|7aaQ;M>YH&^_yDq>##!M5Xk5lw z;R6U8XN3^?wYEXG;k0|*;ug%2QXoE1KRuyI!S0K)DA2)q9_33gvjDM*3A-;R?7p0^aaQekG8)tg^jbqCohb}eR5&<$%Wk~7j~aq*nM(gKTnnK z9JgFg#D2CaOWZI=kDsl|cDD`fG0uv!Rq0-2(;nljI9rwBQy<-9oE2xQvclga<7cZp`BRtn_}MByJL2pfKU=N%t?&G} z$In*H$no3s_}QviZ-y0n{A`sDe0b^}KU<}9=03UG&sJ&GtDo!gb8*_}M^pAxyrE$~ zBd3{mSf|_1$myXqMs)ibIjwl!f!%&aP9yjHZMUD1)5rG>@9{Hov)R(?_xKsPnYU-} z9zP@Jw_ZEB$Ir<5&Aoro<7ec2f7c&+{ES?l8~w)~KO>hDc6g-6&&cJ$AK%yGXXNtY zbL}4EtT-c=uMEAY$2cp_$Yt7dx9>5|iZgOK_l0?SJl3Ia8nMSZI^TV+LaamBI4fcu z!p2z<>ku~1idcuRaaP1SgpIQz)*)=16|oLs_S!McToE0&v0yfTyn3c+nvm$1ta^tLsSqU3wMa)Xr zI4fdS!p2z#JvLyEJqmm5F;VWZM`4d4Pl7#$ta6Vb3wsQ? zgF7)~VUHoJEsr4!dkk6n<}u_0RhAeEH6)|LCk0A?t3|ZJ? z$ig1~p9DJ>pmO7^-~xn=vw{l{HqHtzK-f4dxBy|}tl$EKjkAIa5H`*VEqMk&IKgq&A9+!=X6vjV&`;J$2coE9bxBmgq_n7 zc1}lfoYRqBIj56p*EtVZJxdLzH++2aTa&E4`TRAsZ z;H{jSQ(Ml>2|G8ZIbnQ^lR060a93dG<{B{LW1L{d$2h^xu{Q8l5j)4KI_N3-N`3Sc zeFdYZ=qngKg}VYf$11%-PtjM((Npvl>>R7GbF2m4$~o2oZ{-|ofwyvwwZL0B$6Da6 zoMSEUR?e}Cw{nhE@|`Q61Upx*a^tMv%7u-yf-4s`&I+zv*f=Y=a$)1F;L3%Kvw|xZ zHqHvJT-Z1(xN>3Rtl-LpjkAI)7dFlcu3YnDoE2QTF!l!Sin(>ytxj6x$jk6->LD)Deavr2V##xc`kg0E+6*&*W##xc`p#B?Y zMb3k;aaQC!2peZb&V#UVR^&Vg8)rq%gRpT{Yuc*Vh zit`nia~0<+u;&B{drqMG={bSIo)akSIf25S6DaICfx?~>DC{|b!k!Z->^XtLo)akS zxt)_>&+Sw>=VQ*v^q=!F=VUPFW6sH7&c~dS!JLmdCxba3b4~_xKIWVZ=6uXK8O-^Z zb26CoG3R73=VQ*vVB@UF?G!f7irh~1!8j{&JGD<4XGLzO=G-_dayx~|%Z0l_j_2qK zdycN^7-vO}ZbKd8tjN(-xp7wH=<2&0XGM;#+BMFK99?1KtjN(--;A>&M^~6Q2k{PM z66YY^0Vd8tyaP;}gLns+I0x|#FmVpz9bn=d#5=&mIf!?FiE|L|0DG?WB-nGU)lbj0 z7A9Ur+=|~4uOeFOBk@NtaYy2hVB(I%AHl>O zi9dpgI}(2c6L%#32qx}G{1Hstk@zFn?>&WgJa!p2!~ z_d#tLXT{wIVdJd0`ygzb6?Y$mjkDtJgRpT{+kS4vVmHR@`Ax9pkLH z!y;^)6?a(F2ji@`!y;^)6?a&KjkDqoi?DH4++h(m&WbxM!p2!~heg;pEAFre8)wBG z7GdM8xWgiBoE3Li)CYI~_yGFscabK+eiupQeiupD?;;8NT_j<@i=?*vE|Rd{MH2SA zNWy*>N!afq3Hx0nVZVzc?01ob{VtNQ-$ha%{4SEP-$fGkJ7tq#zf-1izf&gccglqQ zPMNUZDO0>@01Dqoibs+Qzq~{mz2frIA>~{l&{cfPJ-whP@yMe-f zH&EE`1`7M#Kw-ZdDC~Cw)d#;DDD3w-C&7NlQ{{fgQ`ql#3i};TVZY<4w)~E#u;1|% z_B)=!e#cYT?|63VU#2^r!hXk77@j=X9PW6k-0yg*4}Ql}^Y3>&RZhMGd==j`V)7l} zt|+&?gS)ydF!>H)@8GVk>iAt<$??0ooql%i>I&Q5!ChTpzpE?kcXfrycL;k2cXd_n zcXfsRuCB1()fM);y6S`9)fM(T*Qyh--?>&D@>bxk7^C007A9{c_yF9wmK?uxE$nx$ zh5gR8u-~~B_B+?Ye&<@)?_76q=gzgT-?>&F{LZy7c`I;N^waNLYyQbUg1e$TV!u1D zZ|8UC8|wJod6oO!`RdDYcV2Dz-FacZJFmX^-FacZJ1^{a=Y{?5ys+P$7xugJ!hUyN z*ze8@``vkAzdJAN?;cEo{S5?_`x^-AGkIjeC+7_W)$unFg#8T!VSfWb*xx`9_BRlO z{S5?Re*;0--#`%dHxPvV4FvVa-$2ke@;4AP|NaJoF!_M>JQcCOWzq2M{4EP%f6GGH z-?ES#f6GGc`db#l{+5OMMm`|i6*B!T3t@lDLfGH35can$g#9fGVSmd)*x#}c_O~pA z{VfY&e}`le>~E5&+}|V-_BTm{$?Jr>qR;*&iLk#(BJ6LH2>Y8P!u}?Su)j$n>~E3? zlh+A%g?xXLMDylvk_g)wIl)~~hrCX>E3m&wBJ6L=OoIJw8I}9nGQ$40jIh5gBkXU> zs4ah6CexO`EhFr2%c#%(wv4d9EhFr2%XG%od0R%9Hv&VfgSTZ=?r+Nolb;KBMYH7R z!d-#=ji5=ezY(Nz@~q*ms860X+!dHSYq%>gdDd`OV1FY>*xv{eCeJ#=tau|x<^D#H zFnQJ?X2lypD)%>nG*|vckg&fIr1j!&1U2-*-v|=+x1J`!{??Pq{jDcqf9pxu-+B`E zx1Q9Nzx9-9%inqu_P3tYXMgKS*xz~*_P3sd{jDcq-Utk_N8Wl;xxe)!>~B2@`&&=K z{$|%C*x&3@xxd*Z>~D4n`~D4n`}tUNW|y$P*(J>V6}YRZ?%MF=idS8D__F4w}+iU7S_gCPqDChnP+!fg0UK94W*M$A;HDP~y zP1xUF6ZW^)g#GO`VShJo66|m2shoRAa60tC-_R5GH}r(LhXi*;9e+bl*x%3-_BZr| z{S7@~e?w20dq{9s$l)Fm+!fg0&=ck!65JK#+(Ux90&@>3a5}u9*92I9qyCCU4gkz26qMKJ{jB3sH5rPZqd2-a=Hl>1l?qqOFLz7YKJnIrjns$I6?Q zD(7Bc-a95wl-0y_DqMZAka93dNcfwr>kI~zt!e(z0+!f_! zZ+M$jnERb@SCn(V6YdJk{Z67QdE3k1^qXJjX+oUSz zeka@&b-3RNcLmlxUAwRQdCWasxGT!JryFt}cw<)O+|z}-q7L_T;jX~k(}lYNb59rU z3d}uSxGOOCbm6YR##!;ktT6X<;jSp>o-W)K*!GPCcLlb6gEwY1huqVJyP}+Xy0(8L zF!yxfuE5;4=HB(^G54+Et|;feb;w=etzeaN-#X;3@K&(e;=XmrUE!@@olUrJ9dcKA zE4Uz^`_>_MC57A--U?P7?puf472XO~IrptY?h0=OtDO7RHFt%3^Ke(R6*2eb;jSq6 zH=l*MHy?74c=K81+?x+MNWA&1a^0IZ?g}~Fn-4iiy!ote#J%~DgOoxJ5^p|B&$%}b zcZD4D<9PE~n0xaf2Z=YI6Lq*ZUvrQwe~h=gRUR?#AHZEvpZ5>ouE4y10CxrE{R6lw zFz+A0U4eQ30PYHGxn#WEEzJ7|a95P`{sG(-nD-ChuE4y10CxrE{R6lwFz+A0U4eQ3 z0PYIR8-Z|FVBSA~y8`q60o)asHv-|Vz;?#!$Gl?!cSSkxSioI@dB+0o3d}nea93d7 zv4Fb*^Nt1F6_|G{;I6>DV*z&s<{b;TD=_a^z+DM<-e4EDoIu`SSDrcVSioIThj%RC zuE4xw0e1!F9SgWCFz;BvU4eOz1nw#?Ke#7i-Xnp#YOirdFYl4SUH$IGNBZo1%v<^? z&vten?~%Y=joM+kKHejNySjSR#=X2p0(bT9HS>()JrcO9k01K|CA>!hclGwY(=5Py zByd+(ee>*Lyhj3eb-gYcY?0%)2shSMUAozOlS3 z19vs`dSke6)rPzJ^~!miaaR1D2xa%4t-37E!QY8czV-E0x_MUy?rQ1%&hF-28Mv$6 zZ@;3OcV*zNZkzp>Zr+uFyP9X{16{l;19$c4(%%`zyE1TB8;p8uA>NgNyV_}spIpSd zGH_S#-MZ*l-j#v7+U%-3#__HU+|@KY-PX&yGH_S>4nDSzcV*zNt~~CFal8)%cf}YZ z=6xWzE6RBvDCAo6cU!2O_klvLHGj8-%6T6M?uy^?K2XTD=I^$U{pWq4kZYYnuC=`n zdX03|II9GAg&f`o3c1$&-4-h6eW03a?SHq0%6T6M?uy@9+>yVdWD?9fPjFY%;hiVA zD=_aoS^QDh;*R_sCBnS(6msVIJ4#f}J5M2Jp1-3+{pX#hkTcKUQKE9*c?vo6{2e7) zcf9iya^_RWndk2)N%W0(o~E(eT>3BMqwYLu#ZvL$0+P$6!tNy&pt-^cs|B@ zr;IUb9(;_#KE_0!eT>3BMqwYLu#ZvLb#)T#x~g*5RbkgvVb@h**HvNHRbkgvVb@jl z*>zPq>AEWHx+=YOUDcept`^4Vx+?6tD(t%2Devg2u-lnQu-hD!yUh`Hnj#k+Z_HUB*x`7N7!wSu-hDAw>iRYbA@6=)iyu4Cugs4h-nPfDR1kz<>@6=)iyu4Cugs4h-nPfDR1k zz<>@6=)iyu4Cugs4h-nPfDR1kz<>@6=)iyu4Cugs4h-nPfDR1kz<>@6=)iyu4Cugs z4h-nPfDR1kz<>@6=)iyu4Cugs4h-nPfDR1kz<>@6=)iyu4Cugs4h-nPfDZiUbl}tZ z+G@T-%EJ#XrTfv>{PYK9wfV0Se)QU{x!bJ!&WFysTA6UtFk$;|vHve@e_pJfu>CIE z?}bfXHo3y7T1O zhjDJLKZ*9}zqP}+t7GKb)iI{^)>}A!yC&2Zb~(tZ-%i-u6}CU3Kf>NmVeh~2=XA1P zSA8C;9Og&Z=S|q>Q`r8z&>sEq`By*vy9n3$qfW%JPW)|@8QY3|FhTu&i+%QQr~WLx z)JbElJ>fX^I435jf3D&j`nS_>eGcjv|9`jcY#z;i@z3Z|@fW@B?!If&;Z;}s+ZB4? z-%i;6FW*kszn$=ZW!*jg?JH$lY+U`e)Ys|1b=~cM=DOI-#8{%PMjf_4>eub4^KmW2 zH4@iOTvK)aXbWs>zST(68)e3}VjoOUf8S!C<5>LL)iHkI`<;EeI<9_O>fbIi za$mob=tk5TtJbeeQOBb0?SJNqU+R8G-#h<&`t9O3{i4^P?-81}I1h1ttbhIU7U%Q7 zvIb}U{a5=K?-#uW-EXP-`K9cAv%GTEmGygpecffSue$>FbtmlWPS~b}btmlWPT1F7 ztz*?j*K+x3$gJNBY!&pq!1a51yZD*lY63y+? z?5*;l`~0GL_||QNZ`kmo=7hhkEu3UD;IfFR?h~qi;L<%CC;tLD>F#rTu?l`|~TUp0NGy3j4jV$-Bbj3R@$Cti4)3vX;|M ztxr2u4((L={I|BtpV$8IyV_6W_4i-x(4xjg`4v7c>I=J^D}7wZ7xs3Ay+6X|aN zr`RK%e%voq|J>__r2{vAvBkRE>4+WD-<}z(-|lwlSJEOcT;F01-m=NY>D_J5lAQC; zx~{o| z;k#E~*xa%6@(um}{dseyzP!KHrvajC|&XIYK_) zmT!!F^b0*hK6AqyA)jx{H%2~shyEd-Z_77EK01glBA;)|H%31Ch+ZP!bbJtd2J-o~ zd}HLJo9HO=sl#4^d~_2XMLy;1E67JT(NW}6&K~3a&$a*PCOV3I>ah2C|8wm>1x{&Ssw)1O@R z$NJx{{kQqgb^c9%a@8N3|6J$a^e0#SvH5S;`8WN^RewzXOVxjy|8|{!)1O@R$MnBc z{Wtx|RewzXOVxkVpIr6F^gmbqH`%4GU(=s<)gROUT=m~%m%4sU|8v!UlU?fiHT}<3 z|4nwO>(}O{RQqH4pR4|x>{8dS%}uHH$7JWaer;|_wLd01*Y#_2Q>y*3Z(FL(G}*bX zUz?l48bg2V+m>oSZEkY4KlW`)wVyUOx!NE5wuLo@ewuEUYQt@Aa1L@m-_}+^FIivqZF9AsrkkbOe_LCs!}>DaEY<$o+EO{| z%XBkW`)_MY<)Qx>`KFt>+J9SHs>A$v|8vLw3|2Yo%ln@@_UA^O&sbmH|BQT}f62GC zr8=xH?|(bYzvO%W+sOC%mwfMk8~Hx}lJEKx``<>s&woa~>yPC7{Ac95{z$&hzvR3A zNWSZT3G*-cu0N9R`d^qI*B{Au{V&Xq>rbZtuK$wn>sRt!e;9YMvp2HF z_`dAztTE)f|0enDjjS=ZKU!nRXK!SUx&6UMl>K3EWQ}1T*xOlSZa?u6C7->KHOBX4 zZ)c4mAK!#E=Jp34QS$LkSYvK~@DU~7zAZkYn_E}f%;^)={>|DE3Pv<<#fBFBMQ~7i1f%zT32O|%;^(@zka#s~nTRc$IJeUA(qyf4+F_kNs}(+E0_WcQ%gz@`LzvWBd>zf`6!tJ>(~&=-f45vM-WMkiPPQ&V2QV9Jb6uDh)LJs5}2WoLuIX@jM9 zD|7#4xSa=XY}Q=qM`fEG7dO9ut>&8t49m~`aIZG9>c%5Rq|IH+Ss1|gyfI>{RU;B zhhCHX2lx1PxoM^kCI7Zrr_A$D_Kf6TKF?8k|7*6E`~}y#HQ&1UC6d3%Z~l?LnIDw= zIS!bu3>)#je!qoGIP|iIj?2rsAF?J%*+w;`L=vxnT}@{N(tx8)lnpKr@IMn2z`Z;X7t zE#DaVd|SRT^3hFn6#3{TI*NRB6CFi9x`~b=AKgSpk&kYoqsT`$(NW~1o9HO=S@Wzn z!G(mrwpg&E}pQh@M z>3=Kee-re-3Hsjz{cnQ)r=b5@W6Zzlf2#U#vbDzez9zc~>$eH(w+ZW4YmDz}vbDze zzP7fs#*lBaQ(eC{H(F!Jx4CJ8{b_>zv31Gq`e-rG#))?|l zH?_u)Z@Q^9hJ4datuf@=+Dg^_<3qC^kdLnn?%1D?ggf@96Ej6VzB_f0k3S7YK0Y)U z`S`(L^xykGD)hgFd|O-ezlD5TTlBvb`rm~9+u5MM|8^ee@4xx|+P|3pR+xXux3$Im zH^{fO#r!v6{w3e%U-EtaCEw>?@?C!<-}R@V|F*W!AIZ11h5ksstu6FN@@;LQKay{2 z3;mINTU+RlnT}@{N&i`xo|8@@@aZeoDUW zU)WE{x3#4;hJ4$X>8YYY1?`RFD(ihOhv9YwzFU)X=ixBUzIFZs5AVgDuH)|S>7 z^2cmET^DPN`JZa#2|Dn!5{zILA{D(UK_z!jdGi!|gyZ=Ab|L zKa!7auKMHto8-IyrvAJCCi(8aRsF|*lYIBz)PMKiB;Wlv^`E_wHOBX4Z)A<}ec2ns z`o;gO>$imUi~lM4?te-?dn0R%`C)HojUnIW2LD;|+1rEt!GD%~_V!?Z@Sm&w!GEsy z2miU+PyBz$$2Vb((SLlCU_VQ+pZNdPe&YXE`-%Tw?I-@f-B}_(pdhXV4UD(g; z!uCg;*@gYgF6?J^;a|=;hvg!5Vg&Kb8_&Wfr~ix`&(85o9naeF3?9$s#6<4C>-WmB z9GK64Pd?}QqfYu#a>;J{%L3#CCiE?0|Gx6!{JRUgKB&IyiLmRBuzlCaq1Wl? zrsan$UgK9_Ukl`lEbcl^KFQ*~7KD8*2wPi%IoX?0=V`W zT*m^gV+7Z+gX^4t>s*2BT!wP;&1!w&x~3?vYYkl2AlUm;z;(@n>st0Yj7xQVytTgW z0(c$S3b4iB#L`#cN#{Hve-U4&`J8YA~eIaix6 zBFwqkd=X*J)n@aw(|k6Q z)1T*7LjGIvyfVI<`qgP~H03pqj`}sf4mmaN4*4}7k9KRG9{s8Ld-SvB_0j*D@5i{V zWIky($u=hvU`zajq;_A3+dCjA%^HAlG2Po|GChYSm?DO2I z-^l}1KmEH1$M5xJ>Pg5+5HISv2jW6K-$4AQ=NOcbBaxk#C$Fr8yol_)Jb7g$>pcc`4+)WY6m;Auk2lHLoUzypA%(r+F#Ju6Z@&ywtoDWY@eJa$ag)3OO$| zuZEnLnioXQOU+9m=cVS=kn>XWf{m(bdRJ7@lF{ld#P%s)AI%n|)}US9H<8|H}lcV1rdotKw< zvzf}>M85O#lJC5{FlJC5{`tQ7ai~jR%J+G`dFE9Dd z%d7v+%S*oV^0Lq9X0`dOEp}Y`?;O44J4Y}3&)T96^W%KI>_2OZa^}amd&y^QQI39w zyaMch%`3+LQ61(# z#dVa|p}ocPQtJFme#q<4-r{*Fvd!3N`XBOAWSg1Bp$crw_Psj_>-pC#q>`y^|LS9X^KZWm0&Zg%z)%Ba1 zf44u9@Ak6<`y=@wuSt75dpz@F`&Z3ts`g*~4|ze=eoDUEf5~_IDfw>y)ql62lJE9k z{bwEE^D+PAY0-zWbl*zx!{J@BXLkTgYpz{+r~x|5@#i z<_P_9|5Ngr8_z4N{-@--|6J{-d_?rq{ZGkv|5@_g|CfCWd9Bs|x0vZi)qj?J_x~l| z&mgkT?mt)i$r_Vc^RIO7BOi*qD9)iFPpo+UmC9K=)}Ao=U)El& zU-Qt4$*K8i$gg>8v|IDp=ugdaqo3qo>5PdyQ`qNO*ymq;_U|GbznAH&VsF@1 z(;H!IsOgF@cGL7jJ_feZbV3-LXu2hg9W;9fiv{HvJ&zN#2I>CK@NElCFDgE=j9b^gfk@f2>Br| zqJ+GN67nL%8G2qs4tX8Ld3nV$otKw<=jA2edHKwma$X+)y*MwA&o0go?vOPV@={93 zODWFFOTP2+lJC5{C4LNJ@ z@`}YeFRxf^$O|%?BVJzeotKw?$%ixayr$y3 zyyQDCFZs^POTP2+lJC5{d#9=e`;Q$?OFYKiMD6;=Ov;)H7^m)x#lIpIm63W{b7x1ew>%D z`d{-Zi}UiDf9K_^{@1)p^uOj+qW`Qh$#-5}@|~A&^L?F{*Zey#FZtxG(FWhw)-Sw# zUB7CB@9Vt0}So()wiwo(|P%7|7%_`_P^#8WB;Y2^xy11yu9R_ z{g;j+-+6i2Pjs`|f7TZ3f&R0$!0z)1yU(NbgM8K&b=>C>Mm}qca`$lH z71aKdS5W&;URmvbgM9D5#kTtU-yq-nPhLTtfAS*g{FAp(=f6R|&wqn_+rMgF1p8Ob zi>UK2`K&E$9P&e62m6(_OF_kQuV)~ z{~<4>xc*DN>%ZoQy~XoVs{SYDC*-9do4n|T`3ZS7b^U67eEmv3Ys>R$>iSL0f5@xJ zA+M&|AIW$7qyD@7k$ks5siQx#KdGZX{dqyv{;2=#?VcA@?Wg3s{giySpOWwPQ}S6` zp4U|Er~2=C(UR}>GX?uE`ELIu-}bMXmsRb*Q$v9!N*?7!r@{g-^V|B`QcWxe=| z%)jN8^>VJ@`&wREFXsyM)AGvtI9D(~mRHutxdQo?SJub5g88?+vOdlgd|%5e>*HME z{jYg(>|Zr6u7tce1I{#jd|S62N`$#?%#^4sPs(eBY24 z%KA`%>Wt^R+tpX5bX`&sjH zv7h+=lJEY%><{18^UA9KU+pJ((XyX@ej%@{o?j&2&o9;fC(kRZ=a*{#Ilol~YPa}NC^)F`r z<+q)(>x8MxZzx9wvcSk*^Q;4hgZbCWTeaNkH{ed2*9jxX`$@KG0ivwtbC76&$oDoBTdHv&`=jE&Q9o-N9oe0D62A}Sk`v~w|J`58XoEWTPx9aBE+%bI*pWTD z))}gZxJx=fa^$?l>J%B_9MEkAd3pt{H9vhrc(wVLu>U?KYM_c7C(9*^Dmm&iiTh_UcwGxB3m3`X)yhIa8f~q40cN zcjk32ogjSQkSp^JNBv$nFLO%%>$vBIC+pfK?{?8U!d-uxBTqi;W8vd2IE!3V*)q%B z9~R16p?(wOG(mn7+HFFAn$XYY!|7M-^k@Conq!`PR^$5f&)#q5oNjL6Th{snta$)i z9bxL&Z!=@h_S-OrO_JB>QS^Vi|4)6eIpCj3^n}9M7J5s4m@IWQ z^G|WN@U*S-n^=C&onvCe`{h}@wc1qaE0o8cZ-QlY&ZUPso~G4&URPr)BLO7j{NaQs&mK*<6Hmgx1mlu zwj0V@p{*Qn6Y9j@=1~5b--bTKI-mJ%7)xv`$KQrI$)V3V{x;0*zx-{`fq(hipc^^1 z8-E+yiuGfiSdK2*8jyV+!2cWO;Zxr)_=I1Gua51mI`L)s>h||o^nTI4`UV#q{iXZr zojYuwe!IHn@Dsv#`HotPoHNWe*LC@svrjmi@aL*S-EcPf%-QO5-_iEG{xg@bx0xtM zPB@#;uF7eXy@ERS4`(i6+KhT=<5D@}4dtA>tit!n7H_i`uVa>s0;Bw@jTf{`cQe z{@<}f{o`dE8jFwbKY}$5um7LK|DACUs%`P#|12)dI^Q>p_dkTq-^aI49&Z%pJmhCC zoiqH*Wq+o4qw0h+m&eQ$mrLQyl{nvcTrP3$v3TP+Z;x`$MJo5RjOzQDOLF||Bl&(N zQmoF;THt0X`#$M{w zHux{)e&%9aYNN`b4KU{|KXWlI`Xd?P%q1Dfin75TZ&dlfxBK7s?O3m7C$(+|@W4C_ z=)k{Q2ReH(?+XMU>U%#(~ zak-ryUF=Okoy$kPdO%r!y1lfAZ*%1CW%k!^6JF|xZS&%7jDHTJz3o{NU&^&uJTt>wfwa;Tb1i zbDYH;gg^S;a^sF3`qkmoX|;xqvwwxHY@Gd>u+<%FzY#VWV@;N@$sX(PA{NFM%7=ye z!-AY)LH_X2?(oo`;h~?yL;tN!{?WWqKGw%YePP<9uawg!WAJeeXKY~FWXxdNWG=w8 z$sB=cv-536mx*_em_C#<54HZ-AZKil&wQ#5WuZUJf9>bE(0{AjKQ7@fQXh_(rmKzo zv%bGuGjy(F+vwX2f4`-f`e(msqi?^OX}a{yI|pU-ZPA}En|`yz+!=j)Wyx=+iARmm zZ*RDGyXG6eTR5Y8`>ncb`ook{X54LKdXwa@eCmQ}{P9mp{>A@n(hB3} z&WwGIAHe^>I?dUmt)%7l+4|Dg7F(m9V_FZm0- z@Wq zQmyplTniWGXUMjzB$F%o)=pz`3-fR7G$vQ_t(|1^BKbB?Et4zx)=si{k$jt{#^g%A zwUbP)K_dFX%J?62fgZuVF5!J+@{(El9zpTqpOL;rJ_ zf7Vs)KkKUYKZp6xVg7TN{~YwE9p*m={mEhebC~}e^d|@X$w7Z|(El9tCkOq{L4R`4 zpB(f*2mQ}M|4UfEtSikw>nyBa)|KXmbr$r$g!P-l`YmDo+8*3*e{xvAwjcM~pB&b2 z3G3JP>3;i@gZ;66y5IhkU_Wio?zcZB*iYNP`|VE&_J?()^~-k-_Ok^0S%PiP!G4xt z=X0>1CD_jr?0*UNzXbcQJ>K`G9PGc!-EYak{+D3?Rmc4qVfSZ*-JhZVE#I5u&$@3z z|69IKsoeb>{nq^)`rq>Xi~cvhf6@QO_b=vO@>yrt1>e7z|Hk((`rr8eMgJS$zhu{Z z|6=|npLK>^Lq6*ayG;LCXV^95v(B)~$Y-5l*O1RT!>%Epb%tF=KI;s-O#fMD*k$Ci z&e&Ic|3ZHxpLNE*f_&B)b{YAsGwd?*S!e7k$Y-6guOOdw#=e4l)*1UE@>yr>E53gr zSMphB>?_D;ow2VVpLNE*hx_LJ`K&Yi66CYa*w>NII>RqPKI@Eq9r>&?_I3KtI>RqPKI;s> z1o^Bp{1W7|&hVL#&pN{|K|bpY{|Wi5GyD?dv(E5Kkk2~9uR=cS48IEbtTX&7WC*KI@Eg0`dn<_gpXM1my2HcD6pw3CLgR zfhGGw|680HkiWxht-jFz7Uu`#UovQoKF$xw|LJb)_J#hl|JMGq|JMHFKh*heh5q9| z)cJ2h|Ji?Q|M4H{{Nq2=`Nw~#^WOyh!GBQyS!Y3inlS(P4|V>Vpg;IOlJEYH&A;_@8zC z;(tm$>nzwG{7=mf?F9RS|Ed1dPFTPA&(;3mKUe#M|6J`4{(rTf_|Mh;;Qy=teCJ?) z@Sm&wN%)26C*L{PPyGLCKU1*(`2W>@reOc^|EvAP|F8Bl1^dtWMg2!lgZ)pz=BHri zIj2Yt`iQS)XF&h&0M>Nqe+K5HGZzE%@ZX#Vtu5zIzD!)`x3~Kx;!f=Jx<{`YPHc%j zd^vbf9b>X4zf4SfHP`n`#GQ3{-J{D8dsDk#4ra9cJu#csm}DXj>ao5QVv;GuBolE^ zj~S*AljQH4sWHhEVv>sEdQ4Jd^Oz*%H6}^@8k0m$jY%TE#w2OC#w6*_xX{lUlcfJO zCds%cAI2Cdr%zzwp!5}t9L4}fK4SyZE@KAMALar~o6HfI{xf%Ai?yB<%9)2+zs8U? zKS4e*Ue%#2^k;bJC*P&^-|Bw)y+AWAdw1ql% z9=mLM?9i_X|9zGD(~*PL5nlJ&=bEw8>@2*&Dpxjp-O%BOH~Po-o6QzIP~{h&^h#^% zwL5>mF|ur&lEre|c?9@xpyKG)+&LIu@{KubeU!J^iP=lNc z9{y#1_vcN6oL{{(Sy^tDkqx@N$`1RLIe)regUkt+^_0Cw9xs_s{jOCGOuv@Ql~?G= z`~BiP$vplWo0lg>j*`r~-n%3px6uibdG~s6=6UzNOfnA{_WknMq1Sd~?mcfAzQS9Q zbHtzK%tsEoTk^mC#^U97eczXyM~9rA$4>KC$)DppYm~Qdyh1WJe)Nxdvqj&R%zf_K zy!_;$rzLah&892A+i8Y|xmtb57+r4+5y3BX* zxsrL#WZ%pyK5u{LsL8zQu6c{ii|X4vwI5sddC8yq@8{*+`<9jb?;bRw*c|D%HfQ;S z^=DICZ!CXzesQuT^xMDubbQ<9PQSIe%zt^lOYQD>#M2sm9oavAL_T$-?ewPIn{4%jB*%0ro32Z~ z>3-XET{2Dgv)OvdWDT3HOQz|5HoGsGl$+g`Ot9&?WSZ`0+XEz%@)>7aNpjvj_k~fm zA4ops_s)8=g_|}(XIisNwX$RmS!B;9=t*<=Q(H>r%~KrH1pRCUJ!yV0_nwl!?z5*gK|h!Jzz+3b7YY?_~4Z+yQMbfyVwqzU@jY}|c{=52wO z_in-(X#LHhs0xvy=4el}r^qzez9T66eedA??_WU{B~*d*3BA zhZn9eYoa~uC+*V)Yk@Xjd%DpaUN>UFgj{S0?H~)gf$U&E8)RWOkR9x26YOV$EbJ1p zgZ(rgrQc?zVCT(W>9?6F*!d>d`4sGD3U)pPJDT_Pu3;2!}m)1*+wR|ggWlO z(a$zAu_f3J-#3|0$;4h_JCKPj!4CSq$$VyHVhgbyzHc(08JXBWn@`Ea=CL2pPu3qc z4w=|I_5ftE=CJk1WNl&NkcrL1zDuUrd)qf9$M($zn@*ouL$+^9j_sT1faJ4QY~Pej z+c(W;eP1$J6Si+krtO=__RUP+Y~O5b-;_+-HI&$e$S+czcC_RYrj z%|btI-%Pe|7W!%XCbmK{ZQpF!zFFv}?VHK$gJjyi+1S1*nYM2-FRIV_F#90+wr@7J zZ%V%Ho6M1Z%UUs;ptfw^#0KiOwr^sW^jp@D*#xy~`zH2KzqNf6yQJT;p3Ekw54LY6 zvxoYv?VH#o{g!ox|HS;T&dgS*KelfsvyGBt`zCfta#(-(ReV#{pV>yqv3;|_$Kw04 z7V%v=diXxJQNOi)v%%kD4q2CG169ZN%?95~b7;O8z99W!jpBRpU09>|g|y2W#V@2S z)+oLgZLvo25s}Xt#YaRYYm_q*G9S8m-Y$GZWU@v%FClZyr_Su+yoAhmwtKn@9}$_X zQO-`tT>beOyKUc;9NRZ1a*jg&sJ9mCwtZ7_Y~O5irb7NL7cSRr`=(^tzS-tXh0Lpe zy=J%Vo04h!X502n$+Ug5ZTqHV+P>MgeN!@R-)!5yDVer!X4^L<)Ar45`=(^tzL{;` zluX+<@wFrqU(5DQ$+UeF|4K6PuWa9xOxrhe(9d?zlWhB@NY`eX~6czfR-AW`s3TY(JAs+uw3n3&r*}$+5kz&<}Kpe%aopIkdg5&>p%(`?P^B z(WdQfYRmSzf?RZoc94bsAUoL4j4bpA*};Bt?vPC87+L5NvV;9B!Dezks&<~UMzxuo zkJL{;A4w)_H`q_kN7c@AKB{)Ug#9Q7J72$C|qb@0t#}^0hI){p|z7kB@z`HQ!DXgm>S5i{_?x{~-L>C!4YFtp*?nI>Pxze)XTgOOQ2l+X)n?rxvp`YzKuAfXf&A2d@9LCrVeaNwI2d#B~i+(OT{GsN)>*gB=M&4$F zXH%c={^mW+pVmE7b)KH{56w@eJbrksW94ly5Iu%9ps1d9O~yFC)>9f z>+&hD?NYz?C-(m{^}|?lXxHjLrv5xJ*|o!L-h}P@wrxIz?fbTEo`voEGXKK%efciJ z_I>$Y!uEaXgRqS;^KYlmTV$JOVf)t1zp&|;eWU*R=tHg3gx{h+Do1}pyXc$B(YMgg zCiK4*#?^}B4Sle3^`Y=xysZ-2D(JAcRYF?@o%gm1Yr)$ptPyXk*xZiwvDiA>qK>hk z^WKNTT8s6Aocb-0U%v(I)^9<7>bIbu^;^*Y`Yjk&{TB40&Ohy<|I8u%`AmJ+!(w_{ z^{|*en_lfXjQaG~^-$%mhpNvwsYAQ5zUy8woktJRVPWRIBU617?&!v2!lwHRN11LP zG)A`%8oS#E&57Fw&6V2+&7sY$WTNN3_I>P~w(h&`ys@E9wRQTwK_>bjIp{;^1Nx(K z^ymMucOGC`6j|FwMMYLbK*d0kFqkl)7=Y;BJN*T}J^-c!}5?mBf&b#=egXNMbk9M=%{^pnJS4G>t2%l5fyzoD;zvnx= zk1QG49e#WdK8liMhu@b0-(!eIUwqHQm{hqNMRpJyzm0)8RrRM8Hk1rYRHm|n?C|ek z;IRSo%3r&4d^qR2^%BUZwj2}EZLe|p?7>6ANrS&~d9Q{2!^%&!NKvPES@$sJ@8vGv zI&0nV(Tsgv?sU@fq0K&nV)+;MXP@pf(&hc{Iw-J7^Cw z+DAViqhGgL{~)8k=r?3s2d)P)t`FA<8P|>LhYWkbE|6g-*b6f32RlNZbYQ=$3V*dm zt4;ij%AtM7q#HMk=TfFzHaPv{^vus5G_35M9(8%WfciHbwM}}(P4Rp8K0U5cy6e?@ zdU=aWZb};T7=q^*%@06E5Ti)SR$#yc+Gx;T#nuHu=Y%Cz2FXO+$)oze06(s`r{&sq`Zf?Vg8 z^VTb!NBZQwZl&``H#FIQdeP7OW*kvEk2J5#Q2QKyD$}t;N0iPZp}aWfgZjn!ALuF0 z1wnstUI^_L=aJB#;(QVMS)4mU|BLfT`E|8JySUz>KI~BFfqe@7uv^hC>{;{&b}sq} z`xobtFfPS){X54UI>8nA>iF_#XY7)XH_m$WJ=*2*=u69sM0^%cl|B0&wgr^fZLD$_UAC|?(bdCl$T~^-;CKT zfu0vWs}pWLtzQB?mv?UwT9lpPdRBdIhj4QBEZ1|$i|b~W-Zk0vG=2P_aDJ~X6ZGe} z*;U!(^-gp>t=oK(J=FOs*VATpstAiw&A^7R!(4(vv*r6JLsuZ zQ(V`S*Sdr&o1Eo(_WNX9w)d<@UC+xa-=00v_&e8g$Y$>MzU%q6-^A>;MGaEe=gFgP$XY#hL zXM@gHW>;=f?s}%)y+QS)pZd9;r{>?0efq#%u4kW%udSZ6@vzt0CSMM>ljq7Q= z?W$SV0X<#MQx#pZ74F-{^-NfO!+U0LcckmN=FNSwj!EWv<}du~Jx3f?&-HX^`Q<%L z2e)@UM-N%8`nWy!bUjtycddTv`K?{g(NE9l+Wmv0UC+l8_pRQtceU$jc>Q|ir`)%^ z>p9_`VdXQgDsw$AZF)iZmV58vdQQLbp7L&Uj`Gho>+(YRNvq%CpZ)5`r^_epu#A6p zLieW0`h7O{wkBpLmcQD1ZP#=CO7Iwv;_>f!po-R_9w z_DRjX{!>RBnhbnlL)WwD&}+&+eD^SK_sseyB|Wdd&hh!Lsvg1`E32K zd|WPHV{mdz!*%?#8#lbayyv_F{j*K`PfPl&+SK(oI&ot1=rYq?&nKrR$U{-#y{UWaGmwje1V%n;d!6 z=B{VgtDjCjdhT`ClQf&09CytsuBX@NZ_8(`zPo?6L63#W{QK*<&Q?wCPoDj1qU%}o z#jvE#W9z$~{_{Rh4&U`D*Yn*KHzwn^T*39=->$>!_-DVH^g=T1o9$fZpcVg=E|_() z>%qUb_g~xfJT`Fo^!-imb3OPM{lL6Kzml?#eNN%uipE>Io{_`WOwkW8kAC(0Vinhe zf6)(ci+;f_&;vW6ADC0<*HRy>>w56-CuSGuft}C~%zg9=c7Yz)3F8Dk7&q7gdSDy$ z13m%$!Z<+>#tn9X9@q)v1U(oxu;TqOc3=y97Pi5dK_|u#+&~XF!Z<+>#tqy+4>$rJ zs1IJiF?51!j2U!d48bwUpTLk}2#<(*#s*^5SXPQVI23wFRa^n-WIALzk+ z!u-K!F`vLRbb@irAJoTudTj1;u5)O!Gy&7l3C73occSZgWBRNFa|xft+&cf^YF}U0 zI(@km^9S`YpPv4FzOOaMv~8E3ut#IBzx=S>d~XHUYcW-_`TJ#F|HP?(_Hy*o;w#@T zML#XR@^bXe;wzWYuEkgAXEpSopIB$nuEkpDXEpSopVqf(=t1ACKh@Ba_a}oM^vCS) zdSHL+PX;~ckJ&#f>~A*D3Y(j4v%xM_do)h|LSvgLz^62V58Ux6fy=59XqA9&laY z+&=GmF#qiHt_O3@J|A#hm}mBR*Ms?F*W-FHhwSsN2lK|R$Ms;|*!8#`%oV#H*Mm7> z*W-FH56r%<2fW+$xE}Cse7m09ZwJ^Jj2pYI2P~U?T@RSG@pe7n)a>hez^RS5>j9@W z-mV91+IYJj@Mz=hdcY%Mdf4ZkMor3Wyj>4?M0}5NfA*g9$`Ie9KMx%ALK)(F*k{$p z>b6IG4?Evl)xJITry8+7?ELQE>}dVs{!~+cs;NKK)Sry(Q%(KJ$Ud3P`NBRK*(W3W zWHesYWS@-2E2HtsXuL8SuZ;Mqrt!*%pN#m)h@Xu33B+?o`~>1TBc3zjIS|i*=2u2M z2by0Q&998+SD^V7XufAOzXHwojOKfw`5tJ#2l77|&G$h5CnNt8$o~Z6ukb&Cd`__Z zCM@;o>ML~2-&^?XW%stmyO;2Or#o&eZ&SSQZcf$dZOrBQ`|diWx3s}~=j=DEGx*sy z`Mc=C{bdW=QbNhi03 z?}jM)fb;!D-?-0sS5|HCz2g*Nm0Q_*IwXDZsv^-o2cdAn0lmiK2W>gN5N1|50- zr=d-}n-RGq+O+b-uHDOFN4qYsZ+cR*mFqG6soBu=!;W@c-Y)ED*X8|z9c?VUpRl7{ zm-iobd|>z2&nVu_SX^&jzZg5{DaH=^i?Kty#n_=g#n_>r#n_?$K6b`OyJEap&acty zEyfN^7Gnn{i?IX$#n^$#V(h?VF?N_o#n^$#V(dc2TGyZPz}qeGUd>Xu zU010-I4kskze4}7Wpb-gYw~q1aVEFvkk+^Nj{En^EJ-E@4&17&U^1VB1&2$-hYa}P zBAaUs?7icazuVZ^J`(1g`;&W5UO(C4=6ciqbkNw)Yt3tuzrVipw0*BSCM@;WuamoG zel~U5N(cC}PH#N+;#55Ib@Z& z4yvBu&tVO|YDgPAhjsD8yQh^AuR5B&eG>%83te@DFoU--5S zp0C2^&+M{nTj+z{i{`A*7VV(Dg-6wIi}ulvmp53xE&7H2y|;Ruw&*YVJ!#&8Hnyz8S9A{*_=*ODwa$e>#>QXfjyCOYE?c!<_>QMauY>gmc7)FOv$&kb(PJ3= zJ-^AKmYQby)W-~ z!xDdI?}!V!6ysQfTN+2$2EPTLE@KR79KolTqb|=Q8W*#x#tZf#9%{^Y`&(+iZfD{O z<5KVz{x8N0eJaKd5|1g5H8a3$&|Cu}&I#%=V>H*~GtEfw6J)m zj=Ul-%DCRHCJNHF-4(Bprb;{TNqxMPuanD5K_(vE=%(&=7AxVx_kR4^websTU7BXMH@vq+JKDuXah3zpbf~-AKU2UW%wJ) zQ8#|36WYws2FeTFkmpStQAOqDR6ij-3F%L$-IV&1Qa{t84cKhy>2Atu-uRKVO$qtk-!QQd(2dF3R)u-RtM;zU#^30oR|$ z3EplVKX`xgxWfAhUC>#?IFKz4DdI_#7x5(O7x5(Y6!E0TdepAB0X?t*^|NRL{ZI2a z#OjvfNiQcmcpHVDJPz?#GLJ*NU9xi#PkKMm2J41wwrq!g@r$u5WR!D#8pk4D^}cYs z+@CyNDy|pt62`@C2N}BayrAe4@`B=ev!XtYqmLQN(I$;!4g1qLB7P32pR?n#9(i(h~K;p+9dr&JejxY@npeg(a(^xg8qj*FTi!7++%l?(>Pi?9#0m0x_!_lt_^(# zJ2Z~Scf1_zz;^j{Sv-lK#c_$`Xc5^#cKCNNfO&>_3~T1|&gXhQA2Fwkc^Y!R;q@_p zbAO0AjlW@z2l$xW5BR=E;hW$eZdqfQ-+iBi);0H4xj*zi=Kj$8p8LaqYr?hRTB5Hi z<<}`}fpXX;_lE&Cqx>4>MShL?Zj)%sl6`y)EA;37(A&-Zq4$UE|3B`Nm@TVJhmQqh z8au4rUXJ!zC$~joXLT3%jr+{kLVH{_uAOZHK5$)VlWoYhWt&?+?OJ`Wqgcy)j8KMO zTFX$rMD|8#kE_%+SS34HUrP4zaYEm4O=Qm+bA;?)tYzMR`<&T2&b4Ch+W7?DC&7M# z$0^9u|6RE@og4q%&R3UJHS%YR;8&JZu6v}dwJ_Pgx4rs=RJ z+Qi-yB(w=uAm{A3F9$n(#v|XC@pC)8*I}RW`q%@(z6|uleVVwJaO=!hasIz3Un2Wm z2S3oU7{?{P-<8k76xW&i%oKhupR?|>bDwE*)$<+9S@+qw&rIXIcb|axw(#@+6#wVz zoqrzw3wqFI?lZl9?lWCa?lWC~?lZmJ+-G`!a-ZpK!cReG;inW+==#RCBYbf2*@v)$>gKn=w_jE9JVA9LcN7D0~a&XGsybbg%XA-eW z!KBNuCD|?KKF$TQ^S{i&G1uac@;KQ+3@ix-3LgU9>|4l()bK^@qu6(`Ph(%lKG62g zromUB&EL!a=Xo63EPSKOxo>nCew}}*6`J2|02gJ{BFQ!^Zm(^Ok=l1{J*VhrTtL8cD4!Zh`#;1{Qq(@ z=1jvH1D&vIv|}f?E3G5HX}vyU&J9I;5NPZIGt6w$*!{29>wlcb6#p-gJnr-(>bB3@ z{N3_6K0lAPm-IF2zHsTeOV3eokDczb<5_htx1so#&u+*2!g0NYOnDsgQ_t!Co%g=~ z;XFohufN8*bo3h><@xDvxJGEfkM4QP4q{*lGEn#%%r(hwXxSm>O+5TBdBAg|#oC3v z++uCUUT(2Ao9fa#O|X|+?BU|yVsAI!%MIuTK3D7oLtn8+jCSx&EY!)%eQnO`yPWIs z@yzwRoVQzyGy3Cl-cOhF{=01Z#Z`r$z&^6ISJX$$;j(q36vvqUQhb9r2mgJwbC>h6a37eDk;`D@|6=UGL8C|ZOHVp$Iqx6KubgmLy3Wkk6Vy5Px#8*A zFP-J`7CVnmH(cqXa+LSKrXt7j>)~>)&w5xt zw|iv0mR%Pts_=fY%zb{O^VVt7XkD)}ce}OI)t}zMKG`QME3a@ND;T%Yx@er|W)!>g-XzCYe|vi#9|J<_ggH1qNyUvx;vKGntLx0&EY&U(0<>$4u#&+U%6e^eNH#{oV@ zEOVbHHW`CWeQTHJF0*~u>$o;94_>ct zSoeyhUB2*dgToQ6tGzAO&*fa7^{{?!m;1y0T)xHptm}q{q~McfjES}F+|KWFTzLJx z6B5*U`Q^hyW%aWz51F@Dc>d9b{@MK=-qOBrbQ701nz(vsa&AwTSr3QUj%RStBU-+f#~_^i%}K2KRcmvepA!}_^h?hp5KTEnsF$b}uxmj{g6KHcnt)-G?;uYY>! z%|E#QovMeVU$1?G%dDTvxjyS*{oF41hx^I;S$^`(@nOM=lFwNe)-c&vkjjg>hcAX z8)aV}I?iQoi_5t_>tX%eF87D~$^GB((Q)DAvgO>iEMIuq+%ETreHzQm|BDaR3-b?+^XsOs)(NfljPtAAqHf`|$~eFFFY6nYyE@LV=I;y+ z&#W8g7wh42uFrZ{Kex*))kfwywc$r2(k87>@i7{D=h5jCf1T+vuen^G%eg-5;jvz> z59fY6$?bFHPltxV z&%Eh!mrr*OBNsIB`L)@w&BFudZtC)jTQ&{vp1rHf+&3=g`mBfbbGzIh?kD%3uZypj z?ZEcoxTQ8SufMgCd2OnV%&{5E9Jjo;_9p47&urD~M7;qtWy|1GI(aj45L zd~jKE=nX?%J~(TW%)B+8cVj(V&h=Rj>*scdHW(9<-aBUSKP*=~wPp3z)iKt(<>p@5 zA-j$CKD3>BPxjIegI#Xlzit@RvX9G+A1VtCx7ya_`4`wb*}sc^W73a(!?#;3<>jsR zI69pE_-)=6>*sQ=&w5xtx6A$Ee)inuyKL#b2Bf$ymiZc2pH~qk|IpgwfeGc~!_&8Z z;`4g?pb=r?dr$Xyaq}sMo1cH)<()p*JKWcHCD+-0#jatQ+d8uq z+%ETr`^oxQzW1YD(;M$vEkz%;>U3y&SiQgbSX^3vc=~w9^IU%UyK(8h2iI}=oChn? z2A^!;WBNkB(dm$>`(*em>)~>)&w5xtw~LtC{I$2mGGc1;3*Jw})E48qjF{SDUzZV6 zTTJXSVrq+(T}Di8F|^C9hs(J>>tX%eF6&_#F}1DP-haf@7PET0h^Z}>br~_W#kf(n znA&1rml0E2OzbjZYKxU!Moeunw9BlY%eg-5LCjw0=XSY2+)uVS%RIi9OzxG|oA4*^ z&)T>5OPhT2lV2~_;c~9ezJg`Gt_#oDH@wrlzU#lZQxbORwZ6+YKHf5n{IUB#*@4Ts zKI`GR{C0;ItKXOybLZpwT~a-1`#1;LXL5Zm=lZON{ZegYW~MeW&)M3@*DbwjI(yyS z1Lh{nXTSY<(yQr#Zo`{@Y@R+bcqf+!oKv1I-(Ulmf4q0!^zgYWxZLyULFqN+b9{VH z>^LgzKK@9TM^#p&od#C8KOb<`_;lG$FS$=x?cfpVr;AR{(C(L84NSki`xTd)AHPRB zutk%A^1jb^N-yfTnakWCF6a8JhxK#2+#l{I_n)teub1uc+DV6J4R(+7j^)wcRfHMU zdv`_uzk7d7xcJb`-3}Ap8xoq9&u}?xHy~tx`Of91$8--@AJfWhxbNocg=4o!T|RT0 zdf}71db@nc8V_azwvXQj$NIUP>$4u#&+T%5xSy<_<+Ij5K3n6?<9sZp_k1dQ^~xh$ z9{+rUFtqtTF3)MPQ5Z6-v&-wBzjL^w(^@XKJm#SA(6fK{@txRcXxQVrD_rig)VMHd z{bnw+elF+wtcUe;yWAh{=ja2 z{QZ@qA6PJA9@fw8 za(}p=JTF+jahLKiZr?ahPuR3Y*r!{Zzk61EnKiijfE0Yb_}tam8!sQ@@+E7npIvy^ zSeM`UY{A{{{uI}d>ap#UqbJ1jtJbJW##%+<=lZON^>e%2AMPj5sa7vlXPev` z*Sl8dEEPVT8`r_VZM$}O=II^&sXzQ#?kCr0J*=OZuZ_$$uZ_$+)JA4jm)~~z@W6ii z1&m$mHgmImH;emnJa@Q0mvepA^W{TB(xX3$eu-sUJA%cr?xVW3+dsVY&9ZLi+ulh- zgJJ8s{J_U8!<2X9I=kQCud>$;ja=Pz-Slkt&XJSK?^-;msyA9D z{qfo8iyAh#BROQ1m|uK#aku2*u4BA@=k@;D_0>yPz1 z+)pm&`mBfbbGzIh?kD%3uZypj?ZEb7yD<+eFZJ*$;r6{^oYSF0r*QMDF|K&{{N2Nz zgI4itoVoR3;h=}#aC>fd{_xOu;yEr4Yd=0bKmJRPTi&|6A}rUWtH(1(cN-n1j@viE z7_ojX=lZON^>e%2AMWQC_a7Hte67;kVwqVwZFKXn$#XmTwQP1n*RZf|2bYh!saLr8 zm_NDv)gwoSkqzhhb#)j#GQ8d8IF}b~RS~AGI>oPXWSxp|@Qhpi8d*P=bA8ss`ng^1 z5BHO=W#`tmSGM~#-tLKC+xNpiafkP(?RLk7RjxSE`#Cl}JX9UtX%eF87D~$&A%T=6O^bneAU2`Sp!PhLakMNx&q_-@dpo z+hKn6KU14G3#Yx)!)^80U%G^3rwv`6o$V7AzP+N$H?4kTcz25@+|KJSH8R}!;W(GK zSgj(g^xXA6E+4n62y1*&<>STrxt!~>9@fw8a(}p=te@qFFZe!L{j2`o=eaMOk_wKrNzbb3~SoCkKhs(J>>tX%euC3|8 z@~IT|XZedK28U*+$9zFzJe zAIFUkI4n%w;SHD14!eibHeSW`uW>-9Fy-3KTxR`T&h=Rj>*sd4KitowKFN}yr^XnJ zWxmEc&wevocjd#pKR-TqPS*a6;Vxgb!xz=7+{}+_D^*+r4_fJ=Q zH16jwSZ{}PrABc*UHgjm>7udQ1dM5;4eF-T%j0^wRdKkMgmuFrZ{Kex;M z;eJB@z=3z!c|iOuzLxwN-G+I)F6ZsKoVV+8-mc4eyUtbKuFHA5F0+0v=lZON^>e%2 zAMPivC0wA;-qnxVF906Z|bATac>>zGS6kM&*fa7^)TDn9aknRz8mA% zChwn+yp``IvQ4-?mvepA!@jFFGS7?J$n5j$e>y&#SpRPKC;J{-5h~6<+5OBVH;oD- zzlitZ*>CV?xt!~>9@cO7dV-zX@v&t2_4>6Za-)5jLip!1}EL?GV9@TuFrZ{KewCnR=i7~#2)v#`Oq|M z`FYH7rVnlzUfp>|ueVk2FSEOEjycZzXH3iX9TeHv^seUF!cSw4(|FpsT`Rwg{_VBr zw@I1}h&j&eM{i52_J}#ok5?_7hIL|&^U?USbmb8-$7y)P_USi^;<9@fw8a(}p=+<(3ZdtKTi z-E~Z}03WsUb{nR9pW4OcRkm!9PB=O4n_WHY$>jL^<9^!LhaR7dzA5gr9li72<-075 z`%YUge?j$v-C_*0Li=N~d*_XGJ$D@Pa5j5V+y_`^;0j@zI=#KT+xzQ8HdEfY2xSZ>=9@fw8a(}p=+<(3U{X>`U+WJ>DDd924dq)j7fV{-w<^VdDJjT)ybo z1H$LYS1z+oF6a8JhxK#2+#jC%wUL?O+Q?lleJSaG_dw@|WxHpQ+I?!juGikINPCQ5 z|K`HXnLq82^wQhkbNRkKc1_Ql(A0HS{JCSg%z0b5yz=Bm z>6d5j=`!o*a<0#Mb|(GYF87D~$@*Eo^sB#@@4t17QCC0r^knU0N2KWgv_;P)GbbMI z@(U}klur6;ZNwZ~u&zL(<19Z+2U;elF+w ztcUe;yWAh{XVZ6|%UWC*`^oZAQ^tikTm8xVuz!zX;gu#AyWFMiAz{Dm=evCL6+OeV zDkob z(f(JQ{rBqEwu$31Y3Fw3m(PuB>yPtyOtxGuuC2>GbaPVOc!=v9eEWAv(rJLpuiVoj zUG>GdcC&si=lZON^>e%2AMWSa>elJumv0}y49icwdRW?Lo7ddV;oITq1mvepA!}_^h?hp5KwSy;T`yUg}y|B#J*uCthcT)*aRyIOWZ=eWnndbphHvmVyZ?H+xL?L}$Z(+ z|MtwN@LlBq=j!;W ze-6|3dcfsPPwX9Dzo1?UmgcXRguy4o`{S+awg{&m5$^}>e(Pu1=ZDApyq|7&Rd(HD zF{WkxT+a1b59{Z4xj)=bX6eQ$ld{KK#d~d^K5}aI_{}5S{%l*W&*fa7^>F`dBeQMG z|9)9^(~O~Rw?X&M&-&Co#O0lLZ5lSJjA!s3>AiWl?d3;#tS$)3C>_53JF6a8JhxK#2+#l{|jsE|PzvcDl(4|gD4jvuP$$T_*PICP{ zgZ#R-Z(TQ?uw5UQ&v|t1^tyw0aG5{Ld37njeS zUy)v4{}s*sd4Kip65KVMgk>%Dqd z+NSyf?|&bXAAWL~bkeZMz}-8RrAJPSx#|iXx}{HyZ0kI%eqG%`dj zt|!h+=C+Fd>f}GYUp}Q@%-2{ymvepA!}_^h?hp6#q{oJ)KeWHhZOHPR^5xPuzuV8p zV%AaXq{$;&yZphT?bBqZxVO-F_5SHOQ{(;9eya^hhuNA9o|hUmCcWtH)a8dhsYu`N zal6O%TlN{3{`uj?-WKcUa<0#MSUluCve1R+ts{mY1sY zN%iJ=+}`ckp5>d(i1Fds-}OzNwpa?+_27EXT0IoD@Bte@NE{%}9J|9oA1y=;fKj<_(p@yua9E-bSRlRgz;aF9+=twmqPM>*=vk=Wy@Lja+UsevNSOTk#o|L6^?Y zc3mm1-K?L>xjyS*{oF41hx^I;Ya_ESx@Ez~<=wkQ9@cGrPIAfg7z;JK@y(>NUgU?z zkw44jT%Yx@ezy7O*KW+N{Bz8kZhd`Dw&hK6-RC*N^|_quvmW+)wUK#_*G6Vvx8dRA z(mM}ms^woa?h5*3a#7f4HAD`u|-;YUc($X0UTdCE3pKBzEr3`)udg z5<7S2vYm5F?cANqcK$83b9XM=xwzEM-MMV%m+c&5YUd9@fw8a(}p=yY9_#1wiSusBet0YH|6jDiw%K3%j`8w)n?7>S*7*sQ=&w5xtx6A$EezJa+k8L(S%-!o7U+<>OstAo%?&AJ= z*)2zh*AMRPEY-VfaQI9kofW_x{;SCi|T$C&NN?98NFo46LQJ>%W-^A3u>_kef$ zR99RX*W!=54am|LBDWvkc5gOigTdYw>*sQ=&w5xtx6A$Ees29uMOgFuG42Og=4(u@ zUMDJetLFommfH#f9T!p2cIvWj~f!M9v|QNU7n2zw|upgm$M!&=lZON z^>e%2w+Yu(gwe0>=4`yPqV0{B-{dlnHP`2IuFraSPCYj5yJX|eaZm55(IGkX&oP!` z-^KO0oa?h5_C>?H+>sprr=z1iAN(r$OV0ybuJh9B>CC=8UFLD;&vH4}|CaQye)dbX zk$JpoBlDcCjXZ4WBf~bAJ>m10Wy_rt+fVju|LD%YBwwF!oXb~DxuLvQqc}%adhwR( zsmn%rQFcPM<$4!pTR+z5Qn&-86jDCC<&ChVCBjyJQvDIq|*2 zLe=W8IiGz-jtCDO8e`X~w^)q5>*LPS^}Q-Wi&m4|=S&(fGHklqNbfWElgqh2>tX%e zF87D~$^GZ+;_GEQuzlEW+)tJprQ_2Vd&cM8COuk_J~yw8U+)L?$E2&B5uXQKajhX~ zi;Hh|`+T+afb{w^gl#YTp?cEtasR*n7u%GNy*=i4b^G>DI{z)^cO727KRNZDKfBJ& z2i8l=uj=jcX$P#I4%i@Zx#ylcrT47e!sXNZ9GI^8Uc6s?-JE07=LcTpEX{2)E`6@Y znl5wyxt!~>9@fw8a(}p=+<(3{w=g4&Bf8wHC&_?CJ#- z>9kdz@_3u;a5>j!d)7wAGko^Elg|Z~?VTklp1B1-_Rf+N?+}4(?<`62ZV|}#&XN@G z9D!`_EJ^V$63F(>k`(VKfy{cioa?h5*3a$QJ4+Hg&kvm}bD!;l;T|> zknNo%Dc&Ih+1^=_;@u*U?VTkl-Z=u<-dU33T_lk0oh1q0Q39Fub2-;%J*=PGwRfnL z`osM^aON@T<9A-;c4L{xZi4xk1I*W;Kh=+H6>~KD~R|d_XIgKYe{bx<{{XywBWEF6a8JhxK#2+#l{I_n)teub1t> z_F=nmKUtn~#YSnbZ8`_o_S9_~q*E*6S&`kwKbCwnDxP!e_r|c~f^*}3(SvQzF28#~ zT#K)`=85X^8)8g5vgzqruM=Xd+jEOovjdyO7e%2AMPjjpRbFrm+ipzVY{(C+0Hx`wUK%5v&?q*OP5vCdP_x{H{5Sw zvSV`%tvjY*>4(#IOOJnJRhJL>>7caj z?H~DgaeXf5`mBfjPi^EchaX-(;DR{ES++f*VD}xo52K$sB;0@YyDs;bxobGKUQ_Sq z%(pv+7g}xM@(t}8hYvQ~)8*$Ld^xK>Y@o}}c0ME9fB$%9V243(RKGSd#tf{V%eg-5 zVg1}L_lNt*`dMD#zPe%JJNpONyyY_O!?|_0b@`{6-NJ4!v~l^dW%`8`Hd@N%eRn)M z+`s6y4E66?YD{>1+nro~aDbXFaT++vWanKX2|_k$y05vimER z`5Ig7*DSsLwisi4FuzOM=9L&@9NxKCdQDl3F)o{UWZJlK+>73_-^ld+E-@crJzUQ9 zSr6;ycGn*_E*#&up)bw=RCMmz_?`H7bYLA6n#kl_LGy9#tilH6Navo%>K(b zmnVL>QuXRD#&zMsXZFtCKYX;8H=Gr+qXxuSqT%Jsho#q!dnpr=^}}~P60fuJjGe-Q z8O>d8vgp7t<*bF?pXo;p4Yv=S>@xR<%eg-5Vg1}L_lNt*{paiA>t#D|e^@?ZxkJ;g zv*SA}_UJG?9lc9@_fEHV$9$(Mpm(1^{{?!m;1wW>e%x}r~6;L zM*>zCJ$g(!Vf`3SvaPs2mvepA!(&<-nb(^8H>s|^KYusK=*@;_y(f%J(YFUWJdo{i zUCbY!y>*$;=cGPfUiG)uVeN5oFPHri>*R8-&w5xtx6A$EwWBsN`@9fO;dvf^^>zzGkU5YdD zJscT)RKAY8obwe>p0DFB=hx-3{R!*1%lSI)GRG$tXa26=XHYypZoZ{-jgWC2`1u{; zmbOKEJRfzu=hiJVk?W-)2 zyg=)n);q+VScB{baj(mocba#ckK|l98+pFtxj>%p6nTN|)8c#N@T2?=R$#laJ(b_Z z`SlNZf$}?JhB;w=H1FbmEcQ9HuTtV9g`dg&iOcrCrTr_;uX(>q^Df3Y?1we);{C+j z&v+iH{mgh@Ece4czj97A@8b842lyY|M=0eBIM?w{ewh6;^TS+e-YwDlt-SxNIMe2= z);q0tyuP#lVZX%wiv8GsTAXR`C`;}Ab$<4kWqX%MYVVox^U0I1t4J??WH*<;w(kcy zXw%dD`$4!4mvepASsR&k)<(8xWKw&M*!NOc=C<}PADe#lT72*NKHm;Y-<}rVr^j`; zoa?jB+Q|0ZwfETfJNx?1GJkfDz4u8!JfVTtdFYDHX~!-bxqR<6Yo@*G?Bep6s*jRU z%N*?T89gsg_L>~e*w?SuB>ABCI4@_NT+a1b59{Z4xj)?J+Q`NIbHp<&^JiNf(mlIq zjWOQmQ`WjO8~SE^cYWtGmkGCA-p9+&Uax()`0Z_6Zt?2&VT)s0yZq<7`iDaXFY@tS zxZE+}j8m_7`HIeC!@JEka+%xWa<0#MSUgNwn-+1C#x7)`}k4x`;^CXwKZ(PpxSr6;ycDX;?Pwqco7hf;iVX=KG zz2C5hji+SUK@5liF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_S zAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5Ccn&f#9m6 ze#x?f7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_S zAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm29^*5pV#da@H_jy z^QV8@t)t5ujQqZO>owPNxqa1f*)g-5x%_$E+p^Br)pvQ$?ejDI;f`W)lVSDHg9todQ88|&~Lvf>Yz>go6G2rea2<9X>GWix9Rep z4KJ&r@^Y%5ke-C}C)BR#DD@|$ex}s_bh9TGm7#C;i}K=nQNOSQ^tg;R$!=-1onIIF z10D8zTM}*23ARjVT-;`;v)qh1)ABa|YsYT68Qt40>9L!&%T@m;W5?f(Yu~}1VtPOO z;>@MT`*X`G3d@sBG&1HOFyM4yL8yMf?Zn|8?_q#)P z{Ha8F1{vjO12XE{KVA=d&<4t(KX0QB%JT1o$Dcy}nL5x>v=MbzmfEB8gz6`xCnfzU zwVR?1G-P#C>Ss#*PcQG<^J>(AE$Mnuzpw-J;Met#-O#R=qYQ1Jj{T(8PnV&?`tNeo zU0KwrGoa=5Rrs!Id;oJE^APeE$6xE^9h)89Zu#s=m($T7wyU%9`7RG=xk1_SFQ4G@ z!#ngVvtO63tjzxAvehlK&rFAY(@|!+TsGZhXanWeKFaO;wkre5y^Xv++VH-a9<%`& z`tb|d%j|EEQ5S7MhK|^VeV4cCMjI$ci&Q?H>Q6^sb3Ik0zlz$eqW)A-KdY$!Rd4=q z+DcK+^(Zf{7xfD}Ku?wT$81SLYKQW-^l)b&1K^( z8@JYMmuF3wmf;ueq6~k7jJokN{mf@9%%BV9&^@8Sqto+#n!mldyePN&31rkaJuXAf z@|RC>xmnr6S&wUHx%^nm8?u8=e8%Oh(>d9@)8BJ>>9YRWpew#`xop8|S>3ijxP02= zi>l2I?#nuEGNCP%ms9`AMkNMG3Ka=kpbcy}x`S;|MSKsmLdh@(*lcp=K z;qtvZ{sh_W0NLuej5_w&4A-97XUT>M*)}1YTRWw(u(hK!M&^@CWA{Ju05I(5pEyC` zDrzB41vLNBM__KQ*G{fr*?0rwd?eb?gY4?`bIpD^j$O!l$)SkFGrhLD^SONkaM|=HkrfX8gac;j-0Eg@9RKRQ>RAmL+zrj*GHSke^4Jf zIJcT}^1EeGkLO$&WVA_kfR2E2=pnnIT`xzQxMtL`ALLvvqfHtYZ@;*HTFDmgBeqZT{YICO z59K+R=NWm{)T$i^|=s_Ehk#FTW7p@EaaUGO%xen-J-H`MBMlaXc{qe>Q z^VR&M&s)i|gBbXCGZ5F}xsNKwzH-|%w8ejM}jeVN~P9O230_~kwgacKUd@@NRzL3a3WVPNsP&3gsB zhmhye81fo>4!_oq*?p901vk70!h0iV19jjJ;VU6y|AzK({GJTT?FV}uUMJt{aGCEf zmsLGgwxr_+yKmk;cIWroV>Da(z1-Mt+zW$@YuDJtvleEKf+g%L7W;45S9BS?|KE)r zMr-lhlMH*{M>dfi{%s8S{Lk$v*$wgE61U)DbS?jPY)9KGukRKx2LJhaeH<^|lVMro z_(vH>&=$uMlH_Ow*+F&?17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xS zfEW-1Vn7Ut0Wt7j&p;@y(8gM_8$))8OvnzhgBTD4Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn#chF(3xSfEW-1Vn7Ut0Wly3#DEwO17bi7hygJm z2E>3E5CdXB42S_SAO^&M7!U(uKn(mhG7zt+<0ccP_iZ*dV2q!Aa+BevtXbUEkK z<(yBK%c`C#qj?8^Qq+e(aoP0LnAbG#0@^@BumReD4BNyuqTjf@YtLfdp}d%Ps9(%G z=)rH{Ph5sA$)4~hUXHqCfA|wGkGkW$!~BB(f=>KU9rzY6M}J9YjXAEd)7TNusUd`4 z&AY{ONAu2jfX|W7tWyVTf_$cYrhKN)1;r}SH(ESc>FcKA%u?*CIMdirj!@cHQGRDU zAaIuw~BdT|Nh7OOr0<4=3|6$ zqp?F-F?KcfT@e#te34V?oLHRqbT2QE-LMzoHq6%um#qx@w=P>vo z0qYOe8^~CHXs)F?TN`~5)@j&B`CTbK(Vm#`fcTevEc@PkJ<}P##W_OInfB;o4IPi? z;d?1Bz&h^bD8t|2bL>aYBSbrBU&ZWzwTPI(x>T^Fy=dpepHnOCOHe)zI~BIlyfb6u z`wU>n&*T?*ft~{@`CgnGab`5{lp`RArd$d0#^(;=KJbBgq#Qvx0yyCP7Uc-KZ?1in zc&^N*hJ2>-J7+*~rsB*zzAk)%_M-FHL2;(X4B8Vj9%AfJDW7Tgsc2tRxw)|cdyuct z{X4Tso^KUvigI(aiT&t4LbQW&bF+i?GqsRh2Aw^S&osj*H!t1qQ*NHe682A#dnz|KV<^s4oT;-$i=XGp*Hk}$rTxs9 zf5~T>1>$!H__G-Dnev(Pnev(D6p&|mJc-=4pT_^IH z<`Zxq9M34iKOmme^LKjw&hkx<84L-%FWQWt_eGa@kk2$8`Gd7`z+TOrkh*ao(Xg(|AyvsW=n+`n0z% zpK0?V?pMiYBDSJ6R6bKa6VG-Pd%21;jR(b6U> zwbNz!%+lFoyv6WsfYo@48B$(j<8>s^F4l-v2I}fzr)=YCkhyAMKxjwG!*5a&uTh_ki3A_8<97`Aqpt?PpS+h4a`&{-yUtn~&7{qDyBd zl$#q5*sGAwl+TpU^gV}+Vn{nbQt7#de5QP69!C_pr+j9fZ_(NT+Z6UuZf?e~ADz#P zc2I6^cEElWt+SXbDa@mLKoh3H4tfr#t@}^i11f!2h0Yq;tk82nZQW1i_eJG1^&F7< zN!~7AbT0$3 zwtS|(|ITwRmJVoxjz0 zIhj53I6^*CK2ttZXKS4Sovkgco5-`=H{vV+_G+<)$Y++$=j;3Lj0eS;rTL;b6Ar?D z6ldzWS9;!4?~ArMk)InbE&_2I> zrhKN}NtMqF`=`h~m7AL}^nR7nJy7{f<3aCN(R=*#440na!X6|&qk;WM-;>n)Rfc%{ zfc-9g!HV#!_xLS7i>^2m zK-iDsOvRbxD->tioXGEm%4aIhbOsb>D$dMvufiuN&dg&6T03By!alkOWX7-`#hK9# ziZjg)xG##m8<<4*fJ)DS>K*&WgYE&9Vhs6AI0*YuZZ4lm@s)COn-j{-bq^@s3$65A zL%Dfr-PAoG^AEZQREn#056F1HzK!mi>pgz-{DR&|mCpt_iS&|!hS08-W5O3 zuQ*e2CieB|{*K-kZ8HQm!J6vR#d1^Hx6yrbGYZxg@*%o!ZZ^?<^U{3Lee>LLkYCmF z=4KP~qlm?doCWs<^v+?ubGV4lvCg`Tm>vE!pGLvf8?gc)vjJ z9M+zge5T$7M{A|tIc#eL=7i!*L{gQ=**)I2yae~zi`YB0KjPQVEMZNBj6Dz9_t1MD z%qBYHSIY6VCzj6_C#Gjf4N*N_=Suz{0*}G=-#UtLEkA;;sJZY1t+@qYHT2W*S%NWdzH`By;t3P z)fqpXi}tkuF@nbliZhj)Yd^EZfbN@{V=$kf{meXf(0-=Q8tEQTe8&aO(Ac!l^LLB) z9+!Nk-~U2fTC5}TndT?$NB7Om2)b{s`{s%> zb=C+BAP<3KMC?HEgU%Y6O=28T>A8k{rhKM+rhKM+ruH*+-@L?t?webjU_L?jfXoiq zgVcR<-8a`>wDzJYm&84qBF987<+6OH-t`Rz=pLx-Z>oOXZcL|Or3df z2J}2aG()^^0U7Is-W3pI2{VVUp^7tg<^c@Q9=^_r+2p|4YQ>rInRNdG_qF6RE%&nX zG1JTz_M_Y!R#0xP+#DRxxd_FX`Mj`yRkbJrc~c= zZgV2vqms|m`&FC)J&&MsVwPhfjxKzHo=3=I2U;txDgY(SBwr*U)pX`Fv5F8S^c&gZ49x4fs*p zn{dBs|Et{GjDR2I=E}{f^g+ihEvq zkDpltY~*|>&eVRU_A|Agsr^iSr;MMI!FdQ@HtkFqJu|NF;WDEjjxd|}o(ytO+Mm&W zrr8JfP;RdMOx*+0cNf||t@}y&%x=D(Vounv%gW7_o9A(a&k?Mf@|p6P@|m7_U~fu3 z^XwtmxAgBh#XV1*HPTrl<>v9dOnCneJcZsDUD~UW&omyeUnQUE`w!TM@wG#7W@(OS zKT|$a?~67D5J!-Ikk2%mAon7hAihv;u6sa=GcAswyhCxOIR?dPF%l4-l{+auL zzu~i}i_bvL_l{hK?zxZb)ehz6&uX0az}!Y@-ew9pUl&}?V`-Q3`&=$tHQeWN8Eul! zv^Jy9e0jecs;C@$eMNovlR^*n`dl{sHJ*d8HoP2lsh>6W(nnm-rFhQ+%8TnoeV6k# zLw;Q~p25lEq2e6~UI%UFwkXyDFGmas+d)tK`Da<<_{SSZns?fZHn5c=EcPKosn=Ajg;U`;PLsj=ponY=t-(@SeKuict=ns*!@a@@%AWD#d- z-f7+$FS-ZhiHW|O9%fLivN+e4&(u92?5z~@!v1wxK6An}*aUGz+~3i2Koqy@tdWtC z@B8_DQJkqbQ$ABZ6AWPg3oD1>OvRbtK=%>!y(E0kQTv&td&=%7N`W70i46+ zvzp4y6=#yKP@HMbGC$)ipDCXypBbOCNNrl+2hUl!tlWI@GZfm-l+UDjq3@o-!q1@c&gmUvz{-rq6cu<^K zS~nGE8V`yyOV4QInXlp*QpK6Z2JVaMzPWrRF(98QpBZTXRzA~sz+R^IGvoWFihJdX zGZkm%bE4R<(|)G;3hYrS&Xmujy-LeDDt(T~XUb>FXZ9@K!KgSh&o$_Lvf@m$Nz6aw zGZ9B9H;=J|VWBuPzK_@UFcoLEO^pfV=JYOT#hLz2e)-INUdU&{L-;$)7T4Df<>sY1BA+RriSLpw z)=>FO`Aob+pop>MGmQuAQPCWc&y>%U&ol-wCn%;;oM|?}eNnOr_A>G7?;OB>H)Px& z%AnR0n&!HkX_Y!y^zI`fdv|2=XXM}KW73(MV zt89-(=QHD(JNZocO!-WmX?F%}UoJHlS@;C`Ofv@ZEm}KZo5DW2Z*Io0ALZuJ4$95V z4meAq++1;{e5T*$!g*}0sd{!&&ra&u$;IakF(-;RN^zzcLvdzX_ml9K@|p1+lKMWN z_*@(I@34m2kM=Xo2-?pq?cXXlHy-3O$9gOg_w_4X);%Ek%sh^89^^CSGr<7uO)1W_ zwL?C$bQV|dHOgZN`$s-g-#eKa2YMIW;&&72yDf|dtQYjmmwcw#L~*9RLoJ^Z@|hMp z(DRS-nev&)vpk+e?uGLKW)k^KeOIra#WfV_@P-%Fz0ycA>T{VH&j_9LIE z_p2z*)Vl)o441y|mG-FhJc6x_I$K*hE2ZzqHXigmLg_4}o<}eqbhfs{gPuo-{vpu$ zQu$2zOq~-m26W~@XC8Fsq4chp)b908vuR;J`tCwl0c_-a_`8m=PmOZ>QJiT;P@Gxf zL2;(>fP0&YGkwoi&u|$JIBzSTsW?+-9%3wEQzErroq154=?v(31k46~r;J;{{-ZMw zI`g124?6RpGY>lRpfeA?Dr#TF%%FXh(s>W+D%w|3j!?=Ub^k7|3)+j$*GK!u_n&p< zLHjB?^H5?yXCBNkV6Rd8D%w}kzKZr$w69_g(eAk*pM-!pVZSct_h*VYN}_wRK7j(ml3bDI--9-*{nr85u4gK~4_=87|Wwnw~R@0P?n z;)=7xiZjh3U?b!G+K{*0^fpP@p z2+9$ZBPd5uj-VU?E244)7(qFLas=fF$`RlTlp`odP>!G+K{pPas=fF$`O!G+K{as=fF$`O!G+K{K{!G+K{hnhhiJF>*Z+E{^qh(3-%e8(I&5h)`pkA zyx$E~RGv`%g!H7OKc#k|!}Xvp^)sdZrz0-t(jI+An{>UX@7JEU8Bhay$ZlxY%h9I& z&1I{W=C*+S6W9o!jcvy9!v7az$Fjz;#K|9G95r5ltnuQx#uvw9v*&e9j^at<+IeGYJW&^2FWRrep` z^5zF#lXX2Zt_y=7T+jMg>E+;%<^Qdo(Jk*SEA;%b9A`mMm*>R)EXQ^E;ae_-{uFg; zBX``SfyEB7K4i0}e-`6q*XVL?E0=Ryxt!a|W!UQ9^;y>QYh`21`;#-~@edd?K3&e^ zx03v8>;IgdI41aSvl6H6Pv#-8*Hd!S^nSZsm+{zvL7CvCc2GU#goHQtkU*d_wx8C1eNLK@5liF(3xS zfEW-1zY_zVd*p3Nc0>G{`~V+Neeoj(#DEwO17bi7h=KnM2L5;BF!zyX+VQy*KCi;( zSonMkpL?-u_c%H~SL1u;I48sBXU31asW>lG9284iTYFHTvKc#o_9Lav3^kTufga-~9fm*U{K@OJOwF(0*Oc?dme@ zN{nHQ64ZxXHFkc+7z|FT@t?{(w<{bK)X zS+CGr{9D`Wu1%j8*Xg>}x}`nd+Q`NH%CFPxRs8&1|NhnA|M7G2{}+D!z4fa$a!G$J z?HaGW!z~+^#`l-xZY$hl_3%>}Y9oJMw^P9H?EB82{&BaCE^jdM`|7RNT+ik9RmWw= z%x>oL=XGz(I$u}cDwtcuFZseVFw64IYgyQZVmpOpHU zQvcJ)|dzS%Fzi|a-G!Vb{mGTJ1&rO|eNUFZ*V*zavgv_&V_GNEyCo1xBfGv-Xo z+tk=CX5$Ytb~Zo#{?H3EU(04qnC9}hwPt7djX4?0UUM0BZ#jFR%iWr9WcO9Y0r*pC% z*UobJv6eSv%U?dl<^RXtdq7pSYx~21prRC&DyX1REhu({JtvA41Vuza5tJ@c6f0P; z_ue}eEGXE!>;$lP6cH@5D=V2vs@NQ7 zJb&m3%yv=E><0d~$aePc4S_i=vt3|jJ6j9*A~3UE!TnNXFUWKTnJpl*k>g_9IgP-~ zUjD4$$?WCd)54$ZUo~d0;Lq$;Fna}N_5!n4U}i5cdj)3p0<%|OW-l;%1!ne^;3?<- z&#)9zd3^tOY*_u3qz~FaRjrc(mshL+dHE^L>7smE=SwAMruY6V;=Z!hhd-qEx3Cw! zvbX&HhtHPY>;XI$7X2TCT$cP<@1Qh66YiT1a=G$n9j$K*n%-Ln!XG_bcdS$gMoinN z_@ifKG)lQ#S-Cf0mc=-#F&9{27ip56+8Y&O7b-i?tkcnXFtU7e0Jj z!@Ba(#`JruMrb&;z4eB{9q6_I2JPh;b*R=py4uQae?Ca z@^}@;m*e92a(rpMF|AqK6YqDMtBk*|E3mR7)RQ;CPB zttgN0yp;2jbmH{D%Q-zOR}_~s{-T`oXMBK{b3RNTQO@;Y zaz#0p%k&rJTz{q~a(b>OvllskZZES-lyke7PeeKQ3G;&}=YEitE4m~(i}Eh3yRDb; z0U15W7ZEu|H837tW{H|0s(i z$l`^vxN|*ek>5a8PqzjN%SCsQLN&Y<{@%iWHw%M#d|I5#9TjA{S+t*c@FMrG{$}#tg zDvly2^G~mj|2yLNJK|N;R@gtkFQ1{vF40bTTmKdL3^KcZTRsDq889x28a+S6=Bw1y zisxE6=4Jdhj-?zDsc)5Iv$>u5d>n0WZjh|6*-l{Fo3oR@^ld6I%a=%2C~62iu}0Z- z{4b~HW&AgeIW2#NW6p!~;#lI%rH|%kWb$&W;&MhWFsEmH1m=7ge``*|`Ln+QbD8Wn zfw@ffjKEwblOZsd$z%x3CCbXJWb{@tK2|dR)-t))GJULNdRoi$w@yE4uUljnFE6&2 z(+kXH%KXFmuPd_4n%l-Pm&t9G_~dXs1?Dnkak2WD_)d5dA?m=Pc2<0SLCnwdIexvj z8KMr+`mP&eS#*pbZIgxr=y?=7*|+gJ*C{%6hUM3+?9N) z+gQ+4E@N7>rXsC(7@IB>G;Qw=C;T^F|2VB|9f9)SxIGeWA>lM!rfl7TJ?AQDxJ<4q zr{TKG)+s30mGj}cbDKF0_knC(gL0cW4fg@B6P$+spJRDD;br_c#s_44eysa2K8j*K zOdmm0q>otl;l5=00H=|BStw|V>=HD5&4k${Xt-U>KgeYj`A5+3H5TR{LBsvSeiJlB zenze{_a*yH&~RTe8G@!LUV?`ElF1M>+?PyOK~ofWK~ofWLBoB?d?#p%>W`o)sy~9J z$d`hq$bW){V`hh-;aJ9puLl+LQLq>k^HIq3;p<1m`T+A?u|6QPtHk=3%r21mhp$fw zK736~<{yyxnXhLR`x#|^W-@=oi}Co!I+`qAAd7p6^)*@CK~{fCth>qTkN6(pac6Y} zb1W*_7S%(%Y`DUvs2*}Y#r3(wI-RUObA1F2_ob{|psZbRy95pQrL29i82)Hq+&{Fa z9+p_|leJUsXF z+@q@4{r7x#OR*E}pm;8cw+R*IE>ZbGctPcdA~*ca>w}BB56xB6L&e)jYdOAn*h`eJ zd~E;+?b-|6XxALrJG7a=F6y~(v35;?4?Hf5?61JA4B2ml^JKKho)MVwK*md8#v5CG zBI`K~lgZ10V_wc>aLnnsjAA}qhM-~mxeShZ8JEE^r{&LZ%z1EL9CO}W2FHrGkCWy2 z?_^`xd^cg^v*d9g$0pu&MER$%Pawzq|J*0MOpf{UyqxnWft%L1=H=Xf&*V6H9Ffug zz>KHBMf`tY_J7Lhi}d+{nLL4u^#6hX5wA#D?0y;xKCEtAF+M+ok?U4v`fU4Rxu&`^ z?Wb1mBFb+&>yTYTItc9SJ(ZOAaT3@(>m*T_*a&mgR7&98-H%`Nz6_`KEcnZvUGFg<M$H-WisOlN_)&de5pxh=&$>Gd%pr5M-H&P=cnSkjA#2w}Rpue=&$}R+oo^4p(qCQcdctTkMHrz_Y0dCzqc-~TXHP3k)IzT z=2(l?_r&)TU!Rw)-SfS}qMVn>*6#o5SuSinhuYJshlq6x zUSDK;qAB~4|NYC(P`c{pz+)$P7Ojm6%zer89=I&_r^KFXp7+2Di+m|C_oYnF5^JFH zw#J`RealE*`0wz8G#~go`YyJI_qWdnHjg*^<$YJ50keL4PEL6E{vUUvaQv&=xT;V7 z>-uEg*4ST`7s3CG#-GG2_dw87M*mN75iLspis$}M{Fbdhzhrv{%cixn`WgI_I{&bd z@x&tj$v=btto}da6FJSF<^MOP7xkiOEbve9pBYmfX>@1fUp1y;{{Nxd@6nAal z>WbJW_fN6hF4_3D#MpjEpO3}w7he9Cj2oFPKXm(@I!L}zeMkTI`=NN;s4M^G<++!l zUj3Ed7f#QVSfd%5V$;r~C`$i|XVe=LoU{s{BdrRul27gTyDM?u}4g^BZk%EM7aj8XJ=8g6~`7(UoHRqfPy0xkA2Z^FkHX7+Z3~ z-^369u687s`;Rsy`Yut|iq?V!E}E+;u7f4!Oyq0pEHHwG&x6Y6UgZ7KKV<#;+OND_ z%XH)G?4tiHdiNIF@-OZEm-+d3j14Gn9RKtEEA?Mexon<_=P(F*W;c<~_p&)LQO?)- zWo!MsOq6q4{tTDJc`zReEb;#Lya$VIEP6NnSXbiXKdvVq5AyLJ$9z1<$A292@gN`n zam>eqeEi2T9}n{JAIE$=$j5&i^YI`b|8dO6gM9qQaq)PtSPx$IpM{I#@^jx2>(lst zWXXn~!Ns)FztVFmtn$PETOIgwbv65CUp7Z6e2qVYi)cl=Rbk23DnI-ce)#c?@KbZ< zKhv+uY5ucg^yh51#^YpyuQZg7Q}d|Xl_AZHumGXh<=oh`DJ6p68WOCvE@I#qsL~wm+h|}qssFP<>PaC zo~kU4CB9{ty~6)R_6q#3tRw%AIR28nV!6GtIF=a0%i>sK%rE~Ikj0V8za8Z9DjxH) zJ7<4+&Y?VZvUsW59SbJ^E|23-hBtmwn@x=>Pxm4&r&H z#s2*DSl-_M({ORW$Mj<3lt1_V@~_dez!k~k=syID_hOMgDlElCgc;7`|qUp}T1F_FfVzhX?w4VL%{(^Xh#kknWS!)K$t&z= zt6Do124iipm75D)Sx_6A)+>kY>v&T)n*><3>;lA|=}k?mt%h2m)8P2=2wM6Sf!CjO zVE?m7%H)z&pKOzvjp#79fIRfQsJJ^W2&aF3N!nj+lFGXB+&Ss7dkFH3*MY;DBItdLn%@teW7Cjk|py zL$*dhu!AqgUw%S#^fX}Lo!)5w@D5q5h)H(s5+dLzWXLLvR9n;|D*sJ74TnNr?VhmpHS!Cq7DD>(w-PyePcH+M>7R`5! zRWco5@#8{kUjP3>OrDwNuj78^HvUS?;>g-&f6Dp+U~vQ%N6O;Zg2fS794U(m>6& zfoL@Bi~E9R6V@k?GP^>t)X^b?^$Fxrr{0(|+k>z^fplE#hj&}nB&<)M_Mu*wF!QOB z^$D~`LOYyWb)}N^3AF261?DYjrDS~q-Q?RCmwfG(&iVv8%BnUx)jNBD^$GOM3|pLj z?pZqP6KJik_0UJTU&;CeTGg^8Zr*J}Sf4<GUEL z$^6Z{Pax?Ak$C!L2JaJy`Q1o-fA%!*6O?9UB1N4nm2sN)!zFNb#RH`4Fe{Q@7>VuM zFC^(YYe?afFf6q4C;p~SiG_tfCV>_?JKvP%=DFd@?e@wG7ELHDZivJ4sw?trI#TWG zW>_%yo}zzFPufgJ4VOM_4g*}m>5hgPS=|SPd>!b2{XFFAH_=^ zqjh)Fc^^W;Uqxblx}5hdMAI|^yNw(`cwJpSF%b2p)+D?RI}Y-~qZVt${n^8s1A3d8 zJMlWdp_2{f??_efwlLhI99rAhi8i8nEEk@f9W2_;*sXKm>Gwp+2Q0hnjvSCBODG=-d&3h z#^}*3M93QO?janWE#=+yU%dj}J&^M5&YZ6X3r_`Y=2E%b_UTf2rbbP;^g-GulIpS= zR_g={K0fTcf6H+m0(V(wit$Db1+M?R2_BzdDDca%opDo{`(llI*4q&5mby&f4z~y5 z^ubjHp8H1HUs5br`d8B7cjAhRO~hUsvz$ci(Q_|w*&$l7cxahAa$M!GKUOp3*_5x3QR}G`e_zC>&NEw{8EmYvIMt2~!Nvy#0{PsXaiy;CZzBV0Z z-AWL+&P8{KGffousd}oSYqo@^Hmss7MdL-e$=lu}JYKr1(_-sYQn!M%wI1EGx3j=QzZuY``@#gyzjA{FYfJjPj+;TQg^v>D%EtGU)fP!QcqE4_ zmd=!P@OKM==kZa3W@VMbkha%XV5>G|G4&D%oV}(NYRM(bJB~Y5tS3ye;c?k=oImuXRZI z@dGHYOO=nM5Y2mm0&BMZK!RSj6Ik!21#Rb7OJHwPr0ZXn5!krUm-Y{n?j~B56h$AL z2qK)%*yMORa%3N|FKp%VL>k)Wp{T>B{YTNz`ZI-Zjh+prqo(Bx96KY7UiUOa{;bxf z&Qz{vHFpD1zO|1Recbh`px-t#oOYZ#N#F-JhESX6EWuyn@+ewvev*)z(JYakET2d? z&+X5K(xU~Z1P-_mNvm0D3;i$G@}Tn(c~x1`qgm&vZPnz$~?jw&+C z(?r|SIK{L)&3#}?`&QLN=W!Rw@N-CE_*ZZkHiK-v)rIc!DTKGXwTL3AH!a^h7q-`2 zZds#0!HQESvZm)#u13hWx zxp9hp+V${^VG9b1rRiJVwM7Tb>a_9ObIOl5{Lt)fDVn0&f(&dEjtj3HC5pY{NaCd! z{Q6`xnP|9yH0#|TJ3h@<)^2f>q+RZZSx<}=1p&8+Rj)p{|3h;)d*u!BbM(T{tYmPV zr%q2Qo$y3p0r(8kqDC{S<2ii;EdO4M4sBlw2Q+uU%BH2LcK9J^^R+daUi?VDE*}E* zk9WgBgC`_!#|Op24t>N}dalWbwZ-FVIXY>oxl z91EMzc|q753$i&DC7WZRY>oxl9E+08u~0V0f^3dO!RA;fn`1#X#{z7Qg|ayoU~??M z=2$43V<|C~&dtvh<*u$n(x+M76!cnM8<3f6-U8?2U$}w1>8gR8|K#~E$+bIL$mO1T zRhjw(YO$QE7vyqu6B=|@jpaTjlRLdUX!#8<_#6=#RUtrp12VhT^Y6Z2J$J#Vs<$*yTn`*vkRDA?2PQr$m{}U7v*zP%r0PdQ9ftI>_TQ2%k6ss%r0bhv0T7p zV0Iz1i^m0+T_TQY6`c-?O*ml>S-cA1uPt09lq;3SgwL25O)Ef&9 z>td*B{y3PPxf&)+=}$ASmWE+934GWVO>6sfby|J&65O&6qdD!>$Z3Zs(9o<0)!QkCZ!1CXwSUV)5keK_n90Nu|Dhv7GrnGPIQ@S*sU_XM$gmae@7m-6A@p_X`91 zN^g*}_B90_-&&i#RBlsPJ+wuw&qymaw}8B|`Z#uaXZqk+5LD^&5bihaMJs=v4g2<` zf_ZKzeRn<$^hX82^!AZ7Wp5_f)c>M*bv=@*`p;k2f2w?|@~!F}`uF_yQN2S;zC(94 zenv*Jd%eET4n&VfpGob36Ci6{SA5RyJ&Ny7p<0c$IBTvJ%}#y?^%RY;iAibd^U4q_ zwYR_?0h)BbejSY2QU+ZIs?jJH7o^9ofm8Myvct&>%Pmg^lhk{pIt{>_SRXK<*(7aF z1O~QESHuMDCni&4aOd3Ibd!fGNh;fqc)yMT>9>Cj$yyMDCo{*B4Job3>6H=K=&X{Y zrD%}F#{%$B(rdDTBq&$5_QItrE76&0N1ax9xnSH|mPhenfud`JIyi8&GYwy)2V)u; zVW(Fe>BhUA;M0KjP(`B$Rl7YAHuz_N%iv)8V)|N`Yc&y8Rqso0yD1@moFUYB6-m8r z9*21^wkhmlRqt88kLa(QuT#BSRsNLM0oDAiYW`L=fBWa=Z(GfnCguTD^S7$LRNj}W z@ZY08sNRXHccSW@_~+h-#f8PV3^oX#B}^C_DxG(Q29aShrhZGG`~I+xmO*GMw2U5qWVk*iXEqbqxRE1jH!>C2FwX;%=R6R3 z_(^j^uwJ!=0-vCR@Wwt3flogiiREh55;^%%#}aYef^H%Y|3T*jli9?)9CHn~fc*Jeojg=WUt61iPNhf2QfZ!(TN^O9uw51B?* zMGq4EKRGTYZpQ`)JfrPK0)~>FN9$&i!CQkx`E%XJ#3#*1;J~jsbcl9qfg7#0qO~45 z2%Pe?1=Sm9EU=|zC#rekt?=i=xxMKl>-_@1O^u<8r;Zo6blaiy-l^|m-^AH(BWb`H z4H2Vx`H6H;zANE%=6RdpH16;Yfk)kqrL^HkfkRgZ(mF9_l+)~}(~(}--$3B>_D$(- zOKA_q8XvTgWJ_c!|%DXrgB>?WcIU<%4q0 z7ikY#`-8UW8hfSkoY$un#^KWb3-Y!r)M_zMJbP|e5`;$d6?lZl1#q;H_HJ0dQN#EY zPf>o$$ON~$Hxrm{al|M4%muz(-yN0ZCA+4i24bbgdxeb$bz)K9G+bcM(0H^mq{2Tn z?u^2QQw)UP;&T(xZ)y$TeyE-~0vnl66*znB5Y#R&-8E2ZUVq#JCq%hhXg@q$`I5kD z)7aj_Ytnv}=P}_W+QP!3{dYqKM>r`5N&9r%PTP}BNzy)@<@PD0f3~zwXa3X=WbagI zpHB5aOZsGty|8O=9#X^kr3GGd#E+hsND0^TbKhv{c+gj1_l5~{_tN^pF1Omu52sy6;3Al6#7ej z$f{Zw$fhPl$Qqp%ja~Azgg$xAd!UihPT;ihE;#I=R8>VA^jq2eidLFI?Pn;(kLC5o`0I#zmTsdpWzSW`}VuU*aiqS(J= zxM<7IODkCWDyEOJFUBkHhuJs2BfaCY-7E-XNO!KCO;}DGK8J{B9bVoeYmB`FUa;GM z1|N|6hxJa5^v%*LqC9`B8?CV7lW4>K&Ve*5dyl|REn?{;s{nyJKa8h+vge9EHl%wZ zb-TDs^ii6v5@|=BP{N~=I4+((f3#g-6P^Ba%fp8P>pF+fZhLeor^##JL-(Jy7T8$N zm0rnq64>%>T^i9v+JmgDYfOV~NqtT=uMeb-O|+odoSQ+KydENO^0SFVr@=^pee6ug zrdx>uzw`K--pfeBGpy4Tm)=V6rnq`;kdY$2o3@l*0T%w!yXob)3!v%bFP?Q6uYsQi zbrd*S&kXxCZy~ULN#KW;Hr8ZuuiYW0?$ruggMF%0uNhU6_-Izf#Yjw;+i>9|6g|D zd2kycjdRxIECPdz!v&4Pycw)`C)K?-)%G#Hr259|*qUP#g$`3c48aK-GKJ3mS4UyB zF)M^E4;6`6RdWR4x}oJT41As~@asK&QR})M<>ez{x}vVGqriF(n_-l;GzPf-+yvje z3lZf;8u!7#ez3s1BIdzuYiW#O{_w40Pl^;%4T~Kq=o4-pCa+5S z3cSW&oAwJ*2)qpI(6BmH1+G}hjc(fVLg+T_bszflMUud7^#{_VZ-xTTYCDqduYbXr z>m2YNM^ zcuRvXWSpKfo~$2`N~SwYZFb%Z2eRa*IL}=zGdK;XdT&9${_=Zh9wWuk{##Y_-B(wX z8)!RY;e1_zwLAD=m(4jspAMC!*cQi(>!rey7gT;w`Qi7~f#P>`ggw8rfqR~xe_nKF zgBrh^g5P0K6p?@FPPcP$4>wADMwd7zTz-By`<-%{qI(krF1j~C;6Hm_J-_GcAHJ+3 z8;3;N$3K_s?e(E5*}qa6hg5K1K{{QM&b4ST;x^H)?IUbA$kL_vi_U6DVP`ey`r3=~ zeqWGA*VPwzL({I*fZiAV+tOnp^rYq{fg8jRpqA%-1vYPxKyN;5Sw)^Xhq{D7Z7P#`(AvBC;3Owmu6t$W4Uf>GGz3IVR=^T=W9Xit`O6mLo z-^&W>>+B+YHB8^0R;k)W;5Jx^K4{TLVAH_Yr0L*jfpt1jvMfy+pEwsxCLK>p-$!Ex zRwoP6rT5ob(p+gDD&faFrYpv*A1gL5Tw6iomS-kfGRPNYAluy~O zg~?1mZdc_?hPczXjldIo*Tm72nhCt7za!rJAe{>_Zwg@UgDMhzdpBG%S$Y?bTHh6K zk9jL>@3Fo&zO8s%V83B~u0*_*zghVFJUfGA z(Hsxp`dmJdfY#emCH%cV`jx&X@WIBR*qKQ87vH_)gLl?gBd1Stbj2oxP6E%)tBVIh zrMV+r17kF<4Kss6w(DlOwgemG>k0JU33mIW@lXIbE)dzK03Q*_U=z(w~g3qKUyvn>2jbkDM|x9FZ_ zfs5{0M$V_`o@IfH?pYSN=$>VPi|$z#xagi`fu(zvIhW%8MTNNsq(3U3sQmEP)`9l* z%23}GZ>*w1{pkAKQnX4lJrXp{mzFv7mTcD=M=ED`qhtDCBiRRcl35l$G{j{sG$Ayb?2_h0#iS4<8gpP-9^j9Wnnh`KC5F{p9m-s$(9Ju0JH!IqFp+ zo%MYq^t*e>xyGyk^oB{U=+oLQAB7yBc{5eYY~ADxcHNgF;v%9`mmQOyI<)36#Ie3EZ_#lHiVF>%7jWh>Y{Nq4}qsotU= zoA_BD{dRld<4tA2>zW>}Y19#01djuoz2&i^UTbV=nhyKT%HXb!EpYeoLMW4>j_t44 zL&JmR@aDbukg8P!J=-@9<#&j_a-@8+_U+ z2TY8{sUatc#fHwxH76obcjpCCG1fx)&8#ox-M>WAZMLUtyGP&~waaAn-6rW7MoiB) zuauf+t|%TJ7=a!p`lxgD2xMeCp})fyaJg{{bbVd$Pz6hzU2_X)oNtIZ<1T}H6Lln; zTrl&|F(B&iq5XmOcx_x+{66CeOipi%uWp%P=Y(_6bVxmX{rwTl_)r>SgPLNug>}$1 zd=E5OWsO&EJCjOTrb>h8;aIb20MxK|f_n*r(PCgDFzHbN&1ZO`?zI#}vkp4A!N>zA3r5vTVe@2dTQc?zTL6;2v0Z_TL(*PH^Ird zI~CU|O@T+N2BSgjEVw?tJ3g*m2>U|)LGMii+%wk!ZIX^E9oDZPjostWv~@5HZQcZ* zE~a&&R0p zv(GYeC?gJg^oW43o0{P$c82Wfyrz(2R{_@~dSXQXbBc&|i=c+%KrHn%06&bH1KY#T zz`Z5jINTu*veGELJBMXniUe9Yfo}M7JE^G=noUQaH_li+Rv$J6mHMZ2<;$8d%}04-Pu-4fZG5nI>ym z;+YBKK~KLvPED}GEBBYf@G}6pl~3n7aA>G3Iki6ftd|M z(dvLDoBxpJz1WzCa-F0VT>asOrGa*8!Kuo?>iMRcVZJ+=-nt z%l%ko$$Kz7*hAo5rL^$2x-?gL=esWc3{CMk<>ZMRYuVkb;v96&zi95acq~)mu3q^a zzKm4R@Ht!gT(0a6S!8$1vUynkN6h_-xh6i}%w_P>qWNZFOVQk~!2imfx$JIP8`+$; zIQNdr;yQ8}9J4>P=srt+7b?HgwpcD@zX{A}OWYMJze6_oPy<`Rg^l@S_KI^@d3n+O zx11NB)Ba2D%q^PJ7Chxx701>hUjHp|{2lRXnQ6P8*F9Ccvl8uvwRPU!1?KgHw@JxA zYX9`E>fhbgRI&Rtedh0IcdGZ@uZi97ZiA{g{&jIwwY&eW@rk^x$+0Sq{~dAsqx&QL z%1F5!E1Y&HJ?l%k2WI8!lWL=fim{OXrLm+*Mufm$9dk)mBX5CSH&vh~Ml}`Kdu#(5 z8ZF(+qp<2!0$)ER@eCVPoh%EI@>f?YSCTH@gT=E}mkJ2gkn(2Zml@NuFB*w*qR39-9Zgg*R^A^F`y@;iy-cNNL+F#31NEgHj$ zasJO>`Fw&L%l-M`gN67u?{;kj*3?)jaOE)rakx!^z{Yh#aF4sRS7?iKC+wNi2)XQ$ zO&a50#YeZCG2uM7JCCGx*H;R>s@Fj3)99JNJ(dMg-*9OUj(e;-UG6F6W_KOqKra;d zh&bx4)uB#SECDxGJSec1M+^?N(?njLjXiN$IVoS)@>@$B-$2UO zeF-&j&k<=JLpSR?*i@48a$B6(UINS4${#)-Cgfh7n21-pgbG=4iSbz0f{cb047dLi)q3vf%$o$AfmfD)A36bEM8uQtWE_RiK6~ zrI;S|%Oi%zrTn)$c9RLuZQycwZi7)nDJRXh1=2*9_M-gBa0}XSXm5e-9o~^4HR1$* z*JM2jBT~QD{A>+!;j`q2Q{|dFPtTI_$^i3M} zz9za{lJfSyXt`pvLPOBs3-QMn+ja{ZNw?S%SnmIuQzg0Aj}B5eu80@UE^!NnFQ28H z^R3C5p!dyBlrL{q8lPIX6gX1Tj-An6Q{dqqZE)vqHG!wQ^+LH%`j4;?<&MKz(K+v= zXM+rEY2`1zqTJ|m8M;L^-|d!9qx#+fm@J4=UrZ&oepdeYHHG+pugK)r7T`QzVB4A`|tX`Q^oGTx6f3??r#x0(9}3+&GuS} zeWO2tN$~cwV*ZoQh5j?l^B4KNEB_HQ_=RLIvZWjVbia+{eNVt$zC5%WAku2)g6 zvcNo#Se9GJ?f{q8eR#gJJlC49ZSZGp)}QCO$^vtlGJ2k?EXo;KiQGk*T>iVD;k2?G z>=HT2E1W$xa9LcYJcn79gUxv$r{H|J4ICHcObX0pvfl(|Kk=MNfw@dsT-dz06ffq> zb;Vdstv=stN;yv+^V`}n0{0F}C(g~JIr#+{NyKidv}U9}bu2mfIYH1k9q2$VO_A0$ zR;TC^y9UxaR~yGQY%N0a;f$x#nr-_etwj#owMVgci1h5Ev)&M4D4lolzD_1AEibJL zyT8=MbN6fo|L~SA@$$zrVm|*uKqSr?@Ib6_oCzF-749N%oehQ#N28k3x<<8_P^{Y9 z6nXjJJsy}B)Ii|S6;09hlB>YYZ&_jbI%(~x{{bV+pXw*dzrHGsb!YSuct+h2GFaA^&W=b+&Valu>HMYYy*EPEp25&*nwMXfX3mvjcRHpiRU2e0XdKqIWOoFc3;e2-JMEsTC6#yWL7xSk7Cy<|8%YnI zo*?jAv!Qf;L3x4uEg4BKwRIA{8hS919<^AM&h@|YCXr?ab`$l=VSOSEj9ew~h9-$L zt-Mm;h6ST&sY*u$K7M)>Rd0Gi;HO!msN4_o@`qZyGGI6lhWCw zQ`q{phFLFRqtUx~`fmLifz6b0w40N3cFJ_SP}<3@lJHfuQ5R}>qPDf-At+jH?u2Hu48eVS7E8| zQ~5#V2gh&qMcZlnwi*3;9R=Pv+@8)4@({T4c~iP(i1ZFxXi$dkFC8Mvt@js@L7$@p zcH59iQdOt{o$?JriO8{UM9 zaxb;pME-2kh5DlW>D{OZ`IcTHdtaQ8~(=^)B0;zWuH#a8G3qYNNa-o^>c2N|)YO3cO1hU4rL#&xKHa z;~-obup`}a^FkQQ^0vM_An9|W32jMZRlj%`0i=f=#LD=+iPI}h)MQ}HG5Qfle z>5CdJhVI^j&~nl3^lx((!ztH6XkmLlefE>Zkl1(-J73{J`c+s0+wBJ7A@BR?wo{kD zI(BB&(a*Qjhn`vjYYhisLB#d+d&X0s(SRX%OTVUq=c3$veb1KXqS$R8f$I#c;M4Z= zE$kKy#3>V2z;xHQEh@u#Y)7cj7aqw6R{Qjwz)3yhV zuvd-7c!Ob?A<>VChS_$c+hTA%_oE(>R z1yFP6Lfg|UC#U`rV?5A*i)}<%myc+z zcyszR^!ALTH_Dw?cwhVsu04BE2R1I!ns&y?w^s}JmJ*9kCpJ?S4&MR$Kla5P*`<{| z49|&kA$qlSvEk=J$j_1RObo?F%gq7IbHTR%K`7LWLBGuw3jHgEkYv~gzk5DX1jkm! zf>CYo=C&Si`auJ{UBeDf=*5?fq`#*xBvS#4Qq!gm{tZu{%H`C=zGS^dO_+c0xj@NPO7com{@Q z3oyiOPBO)7CFrO?KJ(4W2xCHsi z06aT;0;w8&o!x=#kLhh^kPr3l!tNYjeEMhs`99_`sMlm?rHoD@^SoZcnf%UpQ+E?d znDq%hymiNdnY&5bIqG=Tw=KT+0g_Qr46uxMMWBAVvHZ3SHiY_mFSJh?DrQ2c&V@w?YF!VcF8wFuZNZB zIM#OsO|Oiu#+9hYiSqb#b2U8Ep#m*?tPHwzvclZsx>Pel1C3wR#_4;sDc1c6^=mi6 zOCvPt^x$W(b-NR09sWu_PPz{Z&a}j_JzkTII@dwNt3CQ|eLxcG=R$Qo5A=1uPW&sL zgWKJ`@c7pAqJl|b74UU^hr#Z61PQUiTqWbDA=}sUNnA zFO75Ck5itj?}k?HRd8nG0m>>LI^d3aX1KuZqw?g+MrhTgAR?;^W@U|E98Z$jmbEeZTQ%H~c%HbNt%-(bYhkkUA@a4O1@5ZU z92e|eLXxd&;_Z=*FsMTk=~~4W4g1%_WuEKEys3@R_}&$mRiIDvQX8Uook!rnjCUKFMm_)ZE%IG_iTV^Z7SlXyj$c&9~1n%BNME> zn$TrwhPZZHHcSd_L~qZohy#r7z`RsPI?i1SE3dr(*<+Euq#Ag}@h)r_>r5X_P{W6( zU&6xp<}~T$X9)IF$I-(Z(?zfEf@9nZcv{<)J}|fqQ9ZswkNZenSFeD1)ok%eJx3aJ zdJeD&R9L(jK2J^8s4^Pg=P0wq(+OAU`AuWH!DqOqH-0~Z0&*- zcNkKitOw9A!WT2H&L#8K-h=*ix?^UA6{Nz;`_SM}cZ|8bh}KB|jPhZ{_;cjbtySQS zXCTkRpJvq?4ObWMgECrSbk(JGFlcr&w9KtS_f2!fvWu$W65r;exsEHQl&yx@yV?`a zXjeSxSPfUNa3RYw`e6H{d*EH$94^(Xi?cmUu;$BKgs+06LX@NV;ZWF=>0WuQTuPOqp2~C(`NPjKsE%- zenxg=tc0Mx`k0j5n%?*jkJT18gI-%-DVM#qMr)I|P=CG&&5LzI?^h?m@BA~eX$_-4 zq=%hrwxJEXCScYbN7!ipTsd`u4Tc|l1=SvzP^%Mem_Pgk1m1i`c&?+gayX8ZRo?sG^bq-cE0Zp@)t@cTWv$62scC`4))Iy$+VOdg7goIbhe6LWf47 zNGA`2_uZDjfXT5KT@k@0cLD@89E5gnjNw$-nULWVhrO!UL1dj7khmxgXX;tQ>!=x! zFewhzH(A5F)EO{oXdEtRV*~1sXMlD@97f)-fd(~a!VteWtQTzy6}rs?pN?@@>xC`U z89fu6TgGAgK6cP|`AitwoYC*JgZ^nVVNjzu{P@%k8tj}2UmWAm(!d^qQfI=d25}f; zZVzP1OsLW%4hNUBhh7OYVXboy*233v zv1qDh1LqaFP9O~E$&*H42$zx zV*dyo%uL!1E|)uDw&`6M-XjZgYW2dbsHJdr#963bJroCRv4k-+SBx2U1RS#cpW_Gl zSYpenFx2gEQ?bQ75Bi)A!o0=Z;mzV4SYy=-oi;9o3z27GZRc({;?g0AseK%F26n_s zpI^c(V+t3?DNt>I0b0!14y_ap_#(p&M{HjU1y?Mw(7qX7TfPVmbuz*+3taJr>kL>p ztUQ8aM|?YaJeX7|g#jnKU^C|gP?Y@u)1P$5l(W&$#`+n2ZP^oVHwlHKYwp7Mr2!ac z;}6qLUV#ZS`{3Mz-cTy*JWS0C#y5{ULR<_AFP>3OxiL zQ^N7^Nf*#!b84O~B5>VZfOq>S>|GRros$%Bn-U1S6oGrvo#8kVuzeqa-&;6ChZY2` ze2l z|2pBgYH3S2GV3_>3kt)bm0Ck#lhY8~FBCslYzG-*vq8}^1V1FZLCrC_(DQl__PF8+ z&wJj0Zu5I1o#q3E+67R>qZis92>`{*H(;XYhwJnrA+3c5#*FvIki$cv^3?LUkhRGx z4&&k07GrGZ-wJgdXM*jEnz;OSBh;<46q*ffh?7dyz^m;x!s7aEu*>e!=rw2`tatK8 zm$5l;-}49z+!BDp=gfj5XV0;->qAhZzz$9g%!PLK!ciwbRbj9)Pt>Ia;jKhn;{8MH zx=I^(|8V5I7b=xyp#L^Kth%Bj*4#J_QgzGYryH&D(YK(e#kn>>6V|}?glN=Q&;guq9V|HgB}S=c=wcj ziy97uTaj6?H6#R&PELSnp2r~OLJ*dIJsK*vJ_QA1`=I)>ao`$#7KZijjTJjjggG_O zL+R0hnAvMGjD{RIlo^2eAE&^Vg%@FSn*eN8b{cdr%mq*50Mr^f4cyZ%!k(r9=!4V1 zI4B2vQv&c#@2Swu^*k&N4n*UJli4@SS(x3eH|jr~2;c2af&G9!xOw(?xH$S4M6V6P zJI}_zptY>d-wZ}W*HKVq8-*f5y=u7UFHqw!Q|M+iKy3X;x5V=vRu|cg$rWXf^z-DSdIU|bbzSM_ex9_d7(wml=POs` zXA}9l`TxXADyQ)|OcH%9oN8D4m|ivUGMO41PVYrUE4$=eCao`r(dh*nltOly4SFr><2aZ4O)|g#{thD!vR^^z|y)xj%$Dj4e;j zT3#cwH;2%?$2z21jcX)I8A8`xFHbIMTq9nEA+-F+vPARPRZ_7*C=J#xMcjs7C08be z($|~bD-Tz>N=82nrEOo{S2|~0A=&O>v~T6}O8Y77SzOqPx*;t4!(Qp{q$-bp>s@Ac{ti*-3G#}N7cTsh`@rI*&|V|9h?l|IJy zO24gr&gMk}_HCZsmo_?dJNZIFHaxfQN1A8QVS_1_^mt>W$-RR}&XXo|f=3NnX22pc%fXH6)>fwxi+7OM zZawIk`a6i%kYl8kRS4a|K2==Oa>yyQaJohPuyV3po`~I%+{XOd=MU@oM~!fL=kXC` zol<$^Li-SU$`{DeRykx$KyPY$U=r~>dxj`3^rX2-H>H2=CfZ9j4gIX}1^tx=;aefcbfxLG;y6JS7X->xPv-CEKwnU(0u!ZoCA zbSv60sRB*0Sx3~yw5Ey-9XfpDMlyI#JDQbWng;hvBU9J7(*+J+iDlqUvT=Q9+WO1` zGB4l&`54iS?i+l9v@*#er4#+BPvKf}^vemdqh1ibH!70ct9zd83=d;{(R=0gh)d-4 z;&9poMkv4JOFrap8ScXd`@(3h*Ini7xJzWwkr3K?O+%uem_tnK1W~6={YlH==ZIQo zKk8H_ovhrDMOL-&qu-p@W$s+LJ1JrV@<N!N&Dq;AUqs(iha-0gXS#I6XWo!`wOUlUG|4-b0N z8>`0?wZt>TxNb+fF>=51R+=eY)uje~)BS6D+UYi!cgvkxxSP_fhxy7mwjJqcJ5%Zz zbWs^q#*^NAXiP_#&Quy-uTK*OHlw3H4^sB*7fW|e+C=m&zExx|i=h)LtRyMct)RVe zADU3Omkg`73NAnJpo;qMNkYJONYH9b9UN-Vqi0va$DMw3Tk|TU-a|Fq8&HQ%X|j>T z%(BPnwwAP0>Pd3fv<}vYt3W$xc+-~qTPmhQW$Jpwg2D_n3|eSGrCrd)v_kG`&Fk?tNl90+$F*7J-Z{u@MqHK|(>=7kG3581juh;vY&!H{g`+D8;`AjuEKlv=D=RL`F*|V>^&(^4~j!#af3ubGs z+cp{yc&c7z9dja&UgzATIPYP2{VKZJdv7=+n*HS7`||Vd*dELlNgTRHnln4#BhZ7ec9f&eZHY|K+Ssf?tOoX&)2&S z54>4YIk~FH=c{dAS2mN%P~Q6+4~5@7?zC3kcX>GLmpSJT4UqN&)H>&l!QS5_I9>I$ zlkN%cyXkWjxm~?5vWc|G-oB>l-QW9L2%A!NQGH%MA)nb!(_o}JvbU%3Gd;(s^~t}K z@2V(R??H9%#E~-pI$g#N>XYg}3-_*7LDgRCeW%H~N7JY_PqkDW0Rw6AIoZz!2$v~x zr*qT$-gl#{tPvHsxY7Iml&SmL2T#oLxa@n2gB3G+d@iFC==HY8h38jydUf)?hvm6p z&pFxfd2nvu<{Md)Rp*&J7#fI+EK-Xf34d^?ZoGRsrgg$N2m&~j1w-2&(6P+FK!i= z-?n6sTDN(D)Wbsj-I_{~-rtQlGA^Lb=PIt)rv9>YR&ijtz6W#Z74VN~hTFr9jy+1_wWc|C`cg}ik4sJ~s z+_u|Ww@d7cfwL7o?qu0d|S?)&F^Gwr{-l$rg@IiZ)vD%Kc7Q*{+x>H z$(Ch=J6>{BwPD`hYf1C-z3TRatg?K{$PQ}kdlzJz4L=;A?s|HxaJd7q>XvEA>sI??QJi$k$!hemHZZbRs=tJU#g`Fe^)^G)?v4)m(F?LH+1KqMNYnSUTyr^?r303 zOYeJ^9;v=6IQpc=EgL-JZf@p%XVdF}&F;W+y=6PukN@a4sM%4t+py$%ea*JQCC6=W z-*i#xG~S9_0Jd?RZ@J*WlGkEeVjtG{i_8!s(tOw$?^vG^--U_v{Cq`g~QbPv`-7iAC6T|oH-@mkrb#gS_O*M za=7laay`_RPxlJ9$9HLr|GK=Kqet$(Lv5bgK)7|jcb&8Kz3=d<-SJFdCjKr8*DVk@ z6g<-3=W>)+k>)h(Wud? zX!kk}xARrH-fGdHkA(A|uBQ&p%p>P3x_KJ4ZjtxAu|53`Ctr$Q-g)d0WK5?6|<)XTJAs(Xtde;n6nIesjy>dTaxH9vD9j##PsaXBHA3^u&F7L3C!} zHJIa`Zg&RZlaE%@55H4bIB)AHJ!!i4-DkWH^B&CY*nA^v!sj(Ut5Fl1k2i@?%{Scc zEytL!xxpFvuC(&sj8XTuUoADzY-X%#bEdQK=yzjPwFcz_+>SdfT4nq&O4ePut(Q7K zdYf?W9F0_5xg4T@;o14rmX>vezwEitnLf?Cr)0VHUZ>I8QL;R~#`s{3k=}E{$Tjiq z415-z+kfT2O}h0tudd#8%IIEiR+Qzt3O3bmmAy^)rZb)N^Gi<2ey6nRs|UZePPoPW z1N6+`O5sCJC;h;EXN1p=YNVSi$u8^ixt`DT+?UNavL+cCwo`eQM~EgichvpWjt|}v z4X3Xkp`KVVR=D-r7&Yg%n}prg(MpvqE}ZVu;p*K@j|oSe@2f_>xkh;7nue<00`MTCaY(*OOZITj!P$x_FL9g_kyt*3-+E5Pof9jIPr% zgK+0phwG~69~aJq?^?R0&Q@XQpe;?pd?Rau>qS}DPMG0|6@4Jj9Xzq3HzvaqD|%xx zJh7rTCc_gedSfy?v7$F7!xJldV=_FkLvKumCwAzK$?(KMdSfy?u}g1Eh9`FEjmhxD zn%>5a+o#G2li3{R}-jfFdn*7U|?jH}uj zW5awSYl8c)vhKxUh9_3^fz%D2SkW7k;fWQ!F&Um%(HoQDi50yu8J<|t8Ook_}LT^llCwA$L$?(K3y)hY{SkoJm;fXc9F&Um%(;JiFi8Z}38J<|v8vWO!mlZ%l?KcIb`C@Wc+iF&UmXKyOTjCwA$L$?(LQ-k1ze ztm%!(@Wh(lm<&&>>5a+o#G2li3{R}-jmhxDn%>5a+oeVX1l#34U;BWnT;94jjbGd!_FA4sj>i5+@lGCZ-OHzvaqJM_kThpfmC zPwdbef01)e0eE7E-uTVrlOy4YtI``M)SFZgp4g=~e){Qi1>uQZdgHnKZ;yf}*7U}4 zISv+tC)V`FwKA=_6P{Sp8@Kqm@E!2Pn%azwC)V`FWO!mtZ%l?K z*7U|?cw$X&Ook`c^u}a(Voh&M#&x6VjYAyDmu_TDFs25r>@m#n!~yz1Y6Va1&>NHC zi5+@lGCZ+EZ%l?KcIb`C@WcV}#z1&tm)@9*;fY;(V=_FkrZ*xbcuW%=|mn%azwC)V`F zWO!mtZ%l?KcIl1D@Wd{?F&UmXNN-GrCl1gXli`U2^u}a(;vl^-8J^h1`(j};#$LuZ zvL@zUtf-aE@Wh%vkjvqTHN7zzo>8{V?^h8J<|v2XZ+)v8FdB z!xL+IV=_FkrZ*!Z(cw$X& ze7I4LD0pH`Z@lO0aZ&KZF1>Njj5DL)iG$*ePd^_8PaL2(R`GqJ;E5f2uXh4Gu|sd1dd05^@WhJV_{`vY6X1y*dgG4g`^3Q$JM_lv4?Hn_pRnvWO!mlZ%l?KcIb`C@WjlNgiWR-d?RbZ@s(pM^|2YASknh`IXtnZHzvaq zYkFfcJh7%XCc_hJdSfy?v8FdB!xL+IV=_FkrZ*STo>_z;E6T8F&Um%(;JiFi8Z}38J<|v8Qw;fbr#8=#9zn#ERaS3{R}+jmhxDir$zEPps&T$?(LA z-k8jsfZq6zd?RbZJc)jon%K-a)bxQ|&Na!* z9BO)FGUrg!85a*p zLrrf?<{WBzV>0JZ(;JgHhnn7)%sJHb#$?W+rZ*;Y4mG_onRBS=jmextO>azwCsy>v zWWL9sHx6;=`Rzv5gzvblXZtY26KncFYQ;I!^u}b)p{6$`a}G7VF`09y>5a*pLrrf? z<{WBzV>0JZ(;JgHhnn7)%sJHb#$?W+rZ*a!*9BO)F zGUrg!85a*pLrrf?<{WBz zV>0JZi#G;x4mG_o7jq6Zy)l_{sOgQ#oI_1-Oy(SFdSf!@P}3XBa?GKoHzsoqHN7#J zbExT!$(%z?Z%pPKYI5a*p zLrrf?<{WBzV>0JZ(;JgHhnn7)%sJHb#$?W+rZ*;Y4mG_onRBS=jmextO>a!*9BO)F zGUrg!85a*pLrrf?<{WBzV>0JZ z(;JgHhnn7)%sJHb#$?W+rZ*;Y4mG_onRBS=jmextO>a!*9BO)FGUrg!8M3(=TOrdlR1Z)-k8ie)bz$=&Y`9^CUXuoy)oJ7a2emonot+-XRHnp zMsS}+3||MoHvAg!YrwAozXtpo@N2-Y0lxe@Rrdr>i$ZZWbTm7iCNd{3;%bl%mFfe^I3%OHSz1guK~XX{2K6Uz^?(n2K*ZE zYrwAozXtpo@N2-Y0lxCweaAr6?xoj+C-)w##yuS; zJo}p=>eE3pg_GL8{jU2}W+$V3Pt4SjE!4$IX@xuA)LIQI;{E-XDdXCz-RYCd@}#zJ zzPFV6`eyI@HV52SPIX=BeJ3jZRrvq1P5fS=op4gyqhAXBlXcNwg?qZHBaBZH6>VYJ1jZ=-jb3L+6yW z89LXj%}@;_wLNPyRC}z=P)+jRP_6R!p&CwVd-f}I?XbV0Yl_Day4HAnp=&Uy?Wt?% z+Na*3F@fhHG*`T~e zQ#h&Z&9Te&jV8iID`BIFa8lcwbEnv6b54cLxfV9(R5+>aP3_6LrY40=tqPl(6i#Y; zbM45w=9&^V*P5`ori7E)-dy{#t{D@A%~&C9#suM{wl`y!tZT+JVKdeVn=wr|sqL{Y z$KKF3IVKC6u{yL(j^V;dZI5H;y+hVD_Y`4suMvhOyax#oCY;pv4I9o&;5_9m=MP4{`)DyYUFT?Z`{wF3| z7{_J&-GEVV#<4BeX}WY%9Jj%3ohY#@j@#xwUVZ979QVn6mz{Gkj(uUDcHF-=j(ucb zKic(C9Q)2=s2JnM@tAmQFY5VmJXRj_qqQc+Q3Gl*B)(M~wV_5`XJ(G0X4G!h>SyOs z%e!jKDHgmv-L1B^JbxjbcWf);w9OT*KAW^ZvR3ZJ&a%k^)#E+3N1}n+xxAg)vE#kS zRg)rB%pJ8yh9?lWT?Qy$L)|^#<`@y~oJ~%E@ zID0NXZoqp&p6Y6jsC|)C43x({b4%? zx!lG6WI5Wq*q^k=b~N@U+rjoV_9xrtzx@B)FMrQ=><`!D`s^pS$L+HJ+|TT)jpmPS zyJDhQF2`%yiw3_L;DJAZZr(-D}0WO zhM|3h&#BQcw6Aat*!wctUe($tTV_(^w+H*2a|UvNoV!e5f{TW_`}7Gw0Pg z+0soZxI0?6DV@)`^!~&GgB~2BN8LTgX`D7)WU?Gx^`JpVono~cMh5R_th0~Is>)S; zIMR%73gcTOmTCM>J(cW@NVIjaj(U2?hDdC~#kN%PA3u%6wq5K)1heFX?=4#?%(h&I%ef71i_C4;eQspI(EhMI5L%A*PN+ThA<{)K%za`X!e*bsO*73(u$Bj`_Kvk3$J)MQ?HAh!_eWX%R9630 z`Hy~yGRMW`q2p!ykPh6AF!yQcrabNBxY!@F-$QMKoiZ)UT}%KO0=H=PvbY zbqikYbGNGD-2chB=jBT@x`57zE6#PG2&V7*C9{)%?ZioBea&F)3BZABLJ1)nMHtR?~L;GO= zIc|APe%m+uVzqay?eJMo+VhyK{VMK*+d*4CcZB-MXFXwR#%CgLUt_u4A#=H<1GmHf zWINmk8T;gZg}IFT;Bx#Z^i!DI;I_EX+xFN{n}`m17tuRt{tnloj5Fl3;}**DvbhEn z#9z-9R-=v=jJRdGaEH9bqsHwSFT9~nyD0o8jAc>yoiN%)VIAIQHMS9jZ3$!BQQQZY zWB*)Ukj&+>57VCekiKC%+y|N4=YM2bhToCdmir)c8{R&~YHpkR;BxNKS{`q;k7r-a zb`q@ZCs_MUu=$IJF19k`tY=?}EDbmM+yxh(rl=LAdt zc=TV|aNAcpch)$=d!L+Bj^EZjg7-dI&hgv2M_|kj-y^hjkKny8e2=4!<{t68d!luZ z;C4dy2)WO(J?{_JJ%ar~J9*?1>lYbYcWhf4TsHZXaIM^>@b7+M)R`M|$2#Fvlj2&p@WQN^f}h@fYsiyw&PgacdY$7 zR(~+2hWqLKoS}->pGMz0kL^1w$8~Vp1t(kj9K!F`yF?Zp$Y>+XHdxo?vAbB;($KNA zbu7)XpYXZBy(4^%FeZo3-JjM2G~mx=b;5<2^PiSJBv(;R?o^wE(*=ujlzr7NzR`qf4_wstD-z;7ITU-r7qI=?1udbC{a z*!#8DEmQCdY147>5a&wkmU!qFX%jtRLEuX3T5W>%ey!yJYhSL#j@8Cq*R_`aZe6Pn zcAMX=YaNTdFV|kz(!{m;?Aq&E+Fo&8s|K#Pu2mbZydtY{YyN$h^wTNp##%G`Z z3p)Jv>}Nd_UX^Ec=9i(Gu%30V>a#ks%mf^l)FYpDua{?aXvyc((DOq0nrqmwfPK6? zk8_ebWE1J-1UGtd0uGmPiL?<8-OHkRiy znVEPBML%S`hN8bQ9z@aiAa9H}`wMw4S#G?Hv^Snhwqv}HY~Oey$?A;flKyZX+$OhS zyj9o_akGl(Mr8USwwRm=Epmi-v9C0*TJs=zXtpo@N2-Y0lx#oq%9#5cMxaMsR z`M+zSt@*qGU48PYbxRoB+57yj?Hc)uLl+qKgWwc+3IAp8H%yIp7(ntSkv`<;It zIc8hq^S}DJC3Lo~<=Ew4ceUi6?q7Fd|HAq6p?T(f?h@uR`}OJ)D2d4Bd!I1w)m%^Wq;gLFC2YPAO4xiKl(6|eDB*u#U1jw_*q##{`tB*V z34JFOIrLpszJ&U*^>C(JQ6^gT&txg4))FKo7>xUSj0u-UILe#QO>n|=y&Kh%rs zLO*0fmycQI*hA~`J|~P-{Bs8p{$1zJA17JMyl%XI|Lq*=r9V#k<79-4s~lf>?_p(_ zdzr9*kMs2TXYO(TmGQyvXJ~}<{`JR6f1LEk$!q5Y{PD+(JO1;e|4b6{dcN#D>L!ONq?O5zHiU>ZsAPKA1D2BQZkL-vgM?XlisM3v^>xAh-N&J z{r}(0-zH_9q#Q$1+Dbp<-f8;lvj}l5HT0AZ)r0@;qn6a5|K7^aW6gW6t8`CK>NOs| zPLnW3CS{BdZ(oHdG$wfe|IfCSlw(LrTkg?sZ*)(>`Ti$$^Y$L90sp?>-xvJ%bl%*X zt9xJg{dH%?fFz8`G6wkVMYun^XZ^4B8LKhBQ9hGq-f6h(k*O(Rd!Cg29BRJ@!z$tV zR%U*a+$S(jhv#QuUS)XhF7K!Ri~auQgT22O7@B)!`W&j$@LVl>4wwDj+n)1fUw`&{ zA^RBrSNr9;4Ba!6z;fM}&l8HLGoLxVjQM-E zV;{I4*C%s(+%B2>;r__p&*eUzK9ZRve{bhf<}*LCF8pKo`{v*)`MK24Hp8FeG4pq1 zxt(z)-NTu#`kuoG;a_K-5I2Sn=6csWW-|^5oAJTrax-oSoAE^09%pQ}^DA?0$~Mh4 zD~!#C=i-@bT$Y<_U)YQZ!e*?H{hBdE*xr{Jf26$`mxRrDC2YnqVf)y5oFy-G)g>={ zDcj9^9Ae1oy>i!-c=>btqW3 z{}|!MO*#h-&x{q$_EATt(3+9LmHMr58sF4UxYpCD)y4I#gd^W5tkynRP57<5>!_~D z?i4OnyS+M*>R0KT&Ht4?Zyh{Ptz6}OZgktG(Q3k173EkK{uHYojcl@-`X4?Vt+MCK z>yXdS8mt<2pC`O{U?(+g#_7x0*5U7LzjM3R`rg^86!%+VWj|f(7FYJwsKF?`|6+6D z;_G5{?Vn5XZ^1{LI~SuTxDhUS-I<|!;>Kyh_PMb6pW1%b3GY|^{zRv;oY;7y?2++TerL{|8??xdgzeM!kzba)8l%4 zA;(xa^DzC~nW>lY)!y&Hx&zgZ@k?aCc{aCGjTT=LuDrjNdN00!^z-SvqttE7YX~QE zldF~4+X~M+^@j6ljse2yi`H@OEHYZy?z7F;a$oj-ZMOUH%$`1KWY+a^yj8#Mu6AeH zFMOq%Pt3Y@y`4VWRp(Com25Nfp?*3|si5$c&UIqewXeIxuzf8ghV5vLvcd~5#j1VLO;>UGH*KR;yGzC7xU$q6q(02~s_=o#9n_Q}KMMyN)={r~ zonLBW-z$aGk|EWFU&xwLO{?EVxKpLKostXt3*R~W9;eL3QJ3+*t#3c1%n_*ei8m&! zEBQ;XMusuc=hzvO-6L-g6Mnt_KDT719>QBT-KsD4Ybu;`W*Plr`-;N1eb!J{os>g( z+xpIW?~^A*x7G&+>(jem7Vf+(T2DS#Kp6LXP3^rOVflOAwr>B+zIo3D5fO{0MCD){B=U(I8NBWKst}=IRu<;J>UjO;a69QvfN`0MExLWDXs_>@oWA!sH@09!0x)Y=If}ih_W8c(k zpiXttdmdi-VLQEH;U!sq&)iyi@`(bXp{;|>S9`zqwNq&Ar&Sjp^X@Nwe$4FdtK&U$ zw#oaFJHN1(`^-r5y*qVpC&hF3aIf6@!9({5H(3zSFP|=Uo!t*Be)gyyz zMIW25_I_>M9xKsRZ_DT9Uxg<0)H!l|c3FSyz9nW|)-c95%-!J6U$cF@iDA1262sW0 zi)R?k-kg}RYjw6`-Zh@3W@cw#qZnCUVa|)r!N3sVIXzD~rBZhm&T~s{m7#Eb;iC-$ zO0_61yzg8K)oSR?!ny19Rn^nKFLk>xZltQRzO(SY1+l7Sp=Lquw|k*6s>MS;h;N!x zY?#{E!t)n+4pi{kqPflg=04+`hVQ?)UufJf^_R~U z6}I&u-@ZMK+()j5<4Vf&l3g>2VOyWXFrL9QGAPk}NwR_ZraPAjcWp9Szj?Zb@cTz% z^>_6TS7rV5o*Sc=9!l$y_fH+FM^>33jD3Z3Hk<#c?V|>ycDP?W|0_KIOW*MPukidY zjOTxa=YL^5|0_KI%Q|@eS9tyx#`C|z^S>~j{~bL43*-6U!SlZ`p8o@Q{ujpce-O|A z!g&67@%%50=YJQ^|H63w*LeOH#`C|%^S>~j|23Zfg>4;d{;waGeXcRiXpA$O=LqAB z#yBI4aYkdD5ym*p=w^IvDjjaHq0b!7SO`+7+Xmw#om`~3k==X=r&b8mgxtN-Hf%?NI9;9VCLH@kt0hrD~@xQK_H=$0eo zyu3YYhtvF!m)qPtFO$l1w3#gb@^opHHNwknnl)~ue*7l8EH8Vqi^`hYtAU4#4pmQl z{=DdO=9w6!=cO0UcQ{rJD0D`~ijiqYtFNclb9jv`FE&8socf0FXEWQX+6R*#?|-%_^TWo&DEHTHXJ^$l*znVxt1 zWW&um`Foys`{dCc%}^>n|3o_D+Jo{oCfr=E8^Ja>>Tlg-P=O5Gc+KWI@x z>g1VAvHH0Q{i^U7kIjnKi&I5OjTLnU>oU{hg@eUA>FB9vga>_bkN&iGZq4>ZlaN6)%NW7?!&XZEUx&@^!kwxJpXc~nn}#Mc3mZg zKij_ADRb7#nJ1i0rH&SAE$8LC*dnUJZY4bJm%1v$$9aXHAJ*3th;f0bA3mZbiyB;?5$h(-Yj*s=kW)1y_jLbZ`O*{ z-QIdZGR$S)kI|>Ly)D^hwr57@cN;w<^_jhOFa7PrPlQ{&e!u=AI-_W1^M9rP_Bl-q z+vok8-pzHled*-bUzzlPZdxM4WjffJBxYS(x5TiWec>H+5bwvO4|qQw!25AwydQV) zeq0#u#~r*M7smT>h43*-H`!uxSK*LXj!@P1qv@5dG1j|l~Xnseq_g1XMV}v!edI0an}9fv=1@?6K`x%t;uXTb4h5Hda4U<9YF$KQ$VyZ?9C-rOx+6 z4$$Ad{f6+9JKE^6rBi4wfB1BDoh^Hz%lO~WH*e0lm%T22Ho~oZAx3nl5E<*{J?Yhh z-A|hnv+n10$LRiNPslj@?c!K{Td(>u4iCvaN|$WZTC{5YW zqNnGi<4?GwpYSp+`+BiCG3&CP>}%|=*w!I2%_RQnPvt;t>;gxNzb;*NXJzVKJ`a9d?@ow6oftgI9a*IQ6sd(f+v$|6Lx@KdIka;h($k z-y8bJz8Ay4?&R-Jacqr}fJonH04`C4f*edCl^+(owU z49TXlb-P#iSe6Q^g2w)=TC_Um6G z5#D+EPhKPb_{Ndpzc{|x*LY$W-&wR8-!~<-x-)rtXZ&+9!abjS)+xGpsBr0Ghn-w~ zy9qZrlUco6{yyREL&~f4&)y|Gp;lw{d9|#<(^qs=@25Q?^9Src{IB+9@Apc~`vB$% zV7^5}#7mW<^;fw{N&io!9;7EczDT(5+wFDNe%|N4^X#jw?;hlR?t604Li+hb-siq6 zPfVeg&2A$)Ja)%h?vR81h4Xc->pqubw6NWW|K)yptlrOG-w*Lw8wdX>wr@FVUf_$8 zvBERTy&jCY&EqN0#JC4idu?h@-Rfotc=P=}=#XAt%IwV{JQG(!|B}<2TR5{!ef@EY z+_IhYs*`@Fu{RfSXYs*$&`;hR#lnw7>z`|Sa~Ex`{>}Zd`*tP9+bnRv9vFdgUMRnGK%n%DGB8^Km_p)BXIaQz73V z;ahtC?9@)tLHOpi`PGZP>j;;~Q(ZO7P*^y}zSgSM7H=+Ar9gjmd*@Yh9o@fll=`G! zW8u|%W7X{{jm+`;b$X0i-@yAUUaIehsG0Z7bhzJV%Xd-n$BqkE+uuN4{4A&9^0%HV zsXnS$MR;qq^s0Ulug2_Syb+GeKE^-izrMbCZBbM2$7f#$zXtpo@N2-Y0lxaz&peK(n}iLZlS1AYzoHQ?8PUju#(_%-0yfL{ZC4fr+S z*MMIGehv6F;Mag(1AYzoHQ?8PUju#(_%-0yfL{ZC4fr+S*MMIGehv6F;Mag(1J{2I zY)I8w;cpi@o9^H2`0VT8*T6qp1ARN~a!#EaU3gQ9o_hJ?Z#&OsE97+ernlafe!8=2 zQk=8+weC9C?Jb>UlTSIX^>3qBo%=NqcsZx~^x=E-rQ6d7cGs<_Vn&zI8E@_#O!vTj zYF38Kx^IoFuFlX|-CgZVck`frZqB29)%s!2ySY}*aq+ii)B`CpyPtl(MwZvCIlStG z$OFRYkV>;ZyZTj7owr8d z`=sNXL+u)=bn{QS?Ejcs+AAEF+pj{K1voB+{sKs6pkx^{%9PR!f`n`E{)@Ia9j?KOXIj492fK%sBv5lj!Tx~xK`u1 zq&<$y#c?^@4vx#kaVc&e$K~R<6!(kc(l{=~{@}PYj!UthI4+Ij;(2j#T$<-=UP4bf zU*y9dyp_OncRioS^4~QqbiJKNe;oT~$1z_|Ur)aV{2K6Uz^?(n2L65x@cH?%wd44l zdEGrfKel!XeZh6-cP6hNFXxNrZq@$Rugi0{YQKA3pF50Q8hMwCyvz03*WsV40gefs zob*Mn$MJl2os6$skK=i>@!t93xtsIK*F~);2p%>DljEzjOa7`aQmb_MS_(zb)_F zuVo+XeIEA1_Mh&o5^NcOU>+8CE@9<=mg)(kjZ}Y64x#QFD zIFn^nAKs^~yK`4*c^5ucTzBt`>~mLidRn>ekUP1^om}Kj3b~Vu+{s1mq>wwg$emo| zP71k`i`+>gcT&img2~gHan%}d#HV1-mF#@ORf2Ss>0cVYD(Xfn(wWK zoeZe9pZ?0{3MaZ!6IErxw|w4k654lA_I?w?7^9rL@4Q)%&t_MH(T616f0Noism~h` z5lQ`i>FdrDD+UVZIe*Sc zd!d7H&GZFTx}`OR?-;Apv@eSYKc1(N>QX$1a4>lb_0;LKmvI(Lx4SLf#z40>jczL~ z-9EN-Yh>y6g{50(=$75+RvWtQGP=b;w+xnU6)fF~TDlFgbi4Sfr`vw$R^I5=4Z1Zn zx=n{}BaCjfq1!g2+aBn4-00R2x;<%h%ausox*FYzRc;hq@|ss0HowxniJN`KD9v-X zH~KyI&5!zed?AHC)TWJayWMGZ^4nVom%8n^+qG{O;UAX2RYzeMeK1MiO z>+^xuxjZiX@oUbZ%>!lmlDJ#cw2IAy^S@JF4QW+Kc-qvqs=>F(g!PWWYI2UbQhR;V z#H#kYmj>Cl^zV*QoAPc7ko!&@q2g*jB(>N140P*abh}{bmi))xbW3UJR>0EjHR$%N(Jdcz8)|fW2D;sA zbPGba=ZtQBpj))1+Y+N&Kj=2c=+*_g%{IC{2Hnyb-I_tSyNzz=pxY-#wm6#MG{KN4vs?-Oo zqz<2qk5z*Uw2(S{u;GKMU)_;X8($pjqdwpAf$+wdc4}z52*vGu`h9;@e$AV*{PT*@ zs%h;~!gqcht8&GEA>-=2XJggRMSIHjV^fV$jr0E+<|c-F{U5sRFuEm&Zuc48(nGg0 zMz;>ot%A|*Dd^V3==P(fTZ6g3=@xJ4RvNlpG`ekoZe5IS0qB;+=r$3$?KHYofNqs7 z-RfDo)i%0~gl^r9Zik@TKBLYG&Qm>g^Mb4wmTT0xc zi{6(H8<9mUYh! zyjwr^bXnmqpGv2@&2BE7zSk1>mS*1g_VDWU!D;Kgaj)kC1)S4wMN6AvM_+L=G#Mm( zi4;6^nBYn8EeW)t%!gS#m=8aMNzx+gM zBmLr7b?%V{QiqS-9IeuiD(CRH+Wru$>bx*j>T1xX(JFo0^0Mx#F9xeuHoq)fra~X} zNX|{d9X{)#Y7RdZ=30h7{DW?_EZv^6bjxUT`xd&TG`jVJZcUAD7ogiCMzA^M$fUUb{dTvOo76*2mS_tLlr zc2#_lpSbm=%#Cb2p`l)RDu*8O=(vJkWG<*bSXfgJUHVPIb>;TEw;k-RzdWBk>QIep z?%2Vj^|OmpM17S$)9P^-WA*egne)&3s-ZLQ6Yu_>`mtS3%Ab2kjSa1yMXmd#vG6Np z%B#9N?-JfRs-aq%+8cYLYIRp7-#Osb#_XZ$*u`gsQQ+dcU`K9sSa= zoytBrLbmh4)AiIhS-o*J^@z%9PLEQu9M`6@uG276w^h)swb5-hbo;{S_UY?WtL8Vl z{b=dd4!Rxx;)T4gLAQ6I+W_b`8oC9bTL8MXgKo>A+W_cx7`nX=-3CIpP0;OD=yn*o zePwi;0o^{ykZJW;==KqGdlI_E8Qm^Dy30vzbQ=WSJ}|n?hi>(aZXZIo<(6(`E!|ES z-BLrhVMezp(Cytn(QQ3+JN75K;l7})`$CvsJrJwM#Yf0EFg3?0ooiZahvUEt-}l$O z-}CM}C%@^Vzuw^8n?C9|R9ATTIcc+|X^bAe^mgI7jbe4VOV7&Kl4jpfJ*JyC=A2H~ zUhmxUtDNinUscd<-f~{e6iuO1?ed-vzrT068^3XYEYCPItK0Z)&yQq?Tprk(5_ONC zH>*DBHE6)z))w zn42u^r=Ka{O3i%QtflUIIE~`@{pybD`g`+ySZG-lt+IO0-akFnKz|mvL)skd-ANaH z?X;}BwC!+Rt>^^dtZ}ir=-!r6!yi_T)cI!3tp7&yRz7XtF%d5Tm6&40g9?Yntozd5v})q5p2z8UFjA%dtfnk)bRmVR*w(A_wntubGH&qh^|6mOa(Zp@#??B( zQ-Op^-hCh5DiHEng)D9g-KPABZbzWoDWhAIrP~GQw$tc#0J@bhx-EfjwJqK5vvk{M zbh`z*rTY`zMnJc41yN5bkAjrB|M zS=4}JWfSH++eg=LvB7D5Z|#I(7f0)UkC%7qywxn>87Eest};9LW%f1+yEhHeIm#|@ z^JHtCu>Pa=x=)^8;FH@Ww4AB*zW0mhblaSSW9x3yyL1!X;oZCmr7wQs2CMbb-M-G5 z@W|Rn-5eK&>p-C#2``nu5KNw9j2>O=Kzzy!&jcb{#p)O5>?&A(MHi<8GMp9r+ePI( zy4YFLd!TN)@~%72ovrD7X7Y-btqZQ&e95cZIp?#u%>ywyG`2w-eCqGw9Y4x>bN~tBr0? z8r>9hd&B7V7fCoUl)AEc{ORxA6tg?Y@&iL=y7j*qqPne!iflbIubbvTw3_kA@W>9CE(O;m z8>7Z%DioP&dkf41NW=lOer1!`P~)vGS{uBvXEn7?LBw9b^Qi2KT{ zv2#=A>90petafW0E-^3tf+qUNk=yj*L0jhSJz7?OlJjo8C#qQ7s*ShnZfTn6;XB&I z4Q_MPotdYrexz%Mxan;sx*f|5*INtbjJtT@*I>@%WAx;6ZR2(v-&y$>>Z)?ax8jb? z&g*{rd9+Sm{Q0;;&6c>Qn-A0}FCCco(2_Im;Ye>>eV}c6T`ik;k2YG#*x1X{P}tV( zpwX=}bn9SrdltI2Ho8Sax3tjhUg)+Ox~+w7&l=s@K(~I-Z3%SS4BeiGZV~gxMK*zM zd!XA`quXBS_Oj9KG<53--D*L%WYFzJ=$0C~4Tf%aLAQ+1?J#spfNuMt+cxO-8FULm zw=U3aD0CYE-Clrhk3qNRpj!v%_Azw3`6o}e$DrHG-+8)Kfo=z(+jr0{6?FT;=#~k( zjr)Uc)s1fE+LXGo8F{aZyjPYZ?+qaD6-M6cAnz4M-s>Rm6-M6cAnz4M-n$xkuQ2jn z7kRHR@?IBtuQ2jnjl5SFd9Oy^D~!BXBkz^_FY;cEyjK``uSVXxnqvs^UX8q0?!U-; zHS%6zesuVx$My&8G1F!ElFyjK``uZz4_7}%TmToc74SBC(-`=ov+ivMr!P4z>=(fP<)(N^H@0E3HK{w>R z!pM7dMx)yS=ytc!?Fr~s%F?a6(QP7h`}tK*H{`v#tkJDIbZcOAdltG4H@ek5^UXO9VM&2uoyjLOb z6-M6cAnz4M-s>Rm6-M40K;A2iyf=uvR~UJ(i@aADd9Oy^D~!BXBkvVP-m8)K3M22; z$a|eWEi=D_yjLUd4Yb*E_dMji8hLN9*jqi~koRijz3$?p+2WD+YUI6c!(PwCBk$G7 zd-X3r{2GtES0nG$x15_3kGxkS@6}tgKONsRS9OiNSASXJ<9Ot~8hNk#!)IONk@srk zy;9G}do}W2Ve{M@X5_uX$a}-OA@2?AhP+oH@0DY*bwl3kAn%ps$a}-OA@2?AhP*ed z8}i<;ZpeEz@?KdNd9Oy^D~!BXBkvVP-m8)KIw_$W@?MR+H{clEkoN|&LO0~S8hNi9 z58aUWYUI6c9q5LesullHIvIOM48hNj?{qc$M$a^*NUT4wI z+2fJ-YUI6vn=2HEN8YQE_Xe}4o*a+7S0nFrdsax3fV@{D?{)KDTpo|SS0nG$`#(N5 z4|%Uf-s@&qcxOEFUX8rhZPzSA0`gvsym$40-XF&!@72hA1Nl3YOEA7ZQ0e&|!pM6A z6~V}RMYqBB-m7XuH{`t0JaiuNUX8rh>3P?|xyXAp@?NLS@?}-UKe?9bCCB6Bk!$>yjK``uZz4_7>v4k@tpmL*82zd9N%--s>Xo6-M6cBJUMO-m8)K3M22;$a{s6_iE(5!qg3Uuk?Ys zA@3DN-m8)K3M22;$a{rt-H`Wc$DTV~{mbVJ^&koSrX)D3yB zFm*%TD~!BXA@3DN-m8%J3R5@ay`mfPUWL5Zp>D`~74lwT>4SBDFyjPYZ z?+xpQyf>^H^4_p+$a`Jnz0w|euSVW0jJ#JP?-fSgtC9B#Q#a(j(g)@5QxTLl}9lgS=N5d9Q=KR~UJ3 z0C}%4^4{QyydER(b&>bVa^$@(@?K%&y&8G1F!ElFyjK``uSVW0jJ(%H-Ybl}*G1kd zjJ!99yjR%Fr4dHn%Q-f}$a@v?UO8S{H{`tvd9UViA@2?AhP+oH@0I1qdlm9tSr>V) zLf$J(-H`W&bwl1OS|RUM$a{rt-H`Vx5^USZ_D4)R`MXo6-M40)(v@YST{3|OH&7%ky|R{ zy|Ns6uR`7{jJ(%D-Ybl}*FoMZjJ#JN?-fSgtC05!BkxtndxeqrD&)PQA@W{@yjK`` zuR`7{*D~^6g}hfZMBb~A_X;ELRmgi4`-!|)A@3DN-s>Rm6-M6cAnz4M-Wx#PD~!B1 zh`d)Ad9RDSR~UJ(i@aADd9RDSR~UJ3mCcvD_Q-o3<{u@g}hf7d9Q=KR~UJ3SU2RoVcn4ThIK>U8`ceZuZz4_)S&qEdLEfuP-s>Rm)h6!^An(;%2V`O1>mcvd zcjtSGd9Q=KSHF2|HuGMEyjO4S@gVbFg}hhacIbBIy=vEU5qf2VNd=JiD&)Ox$uB>? z6M3&%eX;lIj9GL(I4)R|0-N*^d zdmZGx_};Dc%q<<{y`nAhUWL3@*k~n;yq6jZ+qxm|72QnUE4rDyS9IG9-H`V>$b0o& z&<%O7gS=P21>KPMD&)QT6X=G#S0V4!S)m*9UWL3@zhiVm-s@I0x*_jfT@kt=?^Vcq zoovtzd9Om=>ja@2@?M3!SLK3k$a@v?UX>BLA@5bld(|T7hP>B7-mBh(ZpeEbM~Bux+x}gR$uh~R@QCXrh|$p`IGRA$=j;Jhm%VmI*)IuiazJP zpS3wL>u$_lTooP{knQx(SxAjNRb6<;h5YJBppNk2)w$HHp7k%|#H^cp*BWQ!_kCsE zsa;k&y}EhNMGZb$;0#?nNS2SxJ z7;5te{>ydIH#gKb^w|yd8OP#=js^X6L&s=yV%CMWI;1T$*CEYuE_CQzKxZ8~M>Z#B zUDSgP)dp%thiV43q(ilYI?%x37hR)#%5pt=ep*2rH#=<*l4A>U!%iioS1dZ`I2?bITbeNTG*V&%Q!LXntGFU zO-%}$S`{{Rco`>VU30z2y12f0O@)}(ny|SB|BQLvh1&n=y5`!KHfBr^He-b_`pGfm zGEU68X6%x6&6p-^#yVl>%rWpXPRzPyyp?s$m@I6@YN;jE3CHluI5F#*dxxxR?kU3N zUL$PoBf@`dzvE};|7_3t_I}1nzkT*~@N2-Y0lx$)@KpJ*TJg^Uk6_YzXtpo@N2-Y z0lxpD9Ct>an<*4EbCJ{R^m!hZCM<@=(rz0kRH$)>%q*^cINvwdN+Ut#8Cj_!qhKxt&v0L(LZI|0VLI7mNVbfLp_znOv0U&lrXzw%40PSv`geAm{Z<)iiKJ(cBp z-?M*!UUq1iaMsV->U=TD{CJwz-EC{U zdt#%-rQIw=yn8739U8A}w%ge2+S|1EW%t4Eo84#oSnOl8kKNY9*2>n<))wO*?;~=I zHrsV>*FTOid|lYri+vs0*Oz_W+1H~t-ZsO&`NOf-W4n#LuDwlrUv?j`p>W^qKHJA) z_GR6#`3!`6S(6wwbnER>KZPF{rpncLM!5W4J=KMYJ1=9qjlJ#%J%_41O}y{dvU%R_ z7?r+%N~yhu>ta>L4@=7T%v8uZN<}~3TDIRdbwBm_pf$oj9dD_&e}9u=-(KkAsA2_* z2|rySkNU3qJ;JG$opz@5>LlFe{g<5$hXxC`&6(Y~SlIiHoxE$@)m6Urz9Zs|EOp)J z+@qyUlL~LS_w4O2Y+rXa+imQ1?QPoovio57&F-^(EcP+l$8Kw4Yh`O_YkTxmw0dEC zZqc^vud!-;`7^7i+sfD&HF8r%(X-z8VX9fWDZ*Der*<2AU3;7MzU)4*uDDO{=dan; zIWatA^Aic!hvxPZ!)#l&%%nKeAN_v$hveD&)t967oGArGs}8dV>#w`a6MnWrXYDNe zPWa=!4fGega>~9I6ez6+zF$dr&xTBT#MWlQYwPcHC)esJ+@sYK?!no^g^w0J5Y!{b z2tW3Dt3c&>-uEGVkfn_iecLEme&O6|C)LS*!Z>z?@&7Wm+t};c+qCy(_rdO)-Dmq) z>|?Z#-PXj`%8ZSQdfIHBU1d4O9Qr0KN$L}0 zAbpeYAJ1dxoZ4;db?t51`?C9B_s#CJeJocxFSvIo+?Uz!2;5T??#sfs*C^bVrG9V^ zQn)V*y2k zpIJ?KD!f_f8<&)&p*OuEKxiv^ZX-ho_~b#D?a}So97>4 z^ZX-hUkf(dZR~aJZQA>?`(XFY?z4H8lm6RdW>mtIaBXkYMci7$ylZx1_xWz2Z@urx zYSZ8cH?Xp!cP!=d=tpaL&pf3&26Uzx#bx<(ja%pzqtgn%e@`D>TW^$om0R$?gl}ch$8GgARUz!6jV@9Q4|sR5d2Vt|2)r~dowQ(SpKpL!DoNJBv0<%cg{I; zo|!Xe=G^qlLnhUQ>}B;XR7DI^qJ~8GJU3c?o6Mlo>S9js^{ADnQ9K0K2yyN(`TwVWBN=r zmrS3j=9uZTsJUnQENV`gK8u>GkJp&e^AkeO=>qU)Sn>H@N~|*LdC6HDX`ah<#n- z8WD38@OyRcBI0;Y{A`pN+lqZKg*JVQeU4)>Js=)Sn1hIYJ>qp=kBEIe;+p8|5wWjF zTpxWs;`-?85y$K65wWjF)QPW0#J(O8`+7v|>k+Z9N5pZCB98aO&qkTCt=Nayx7g=6 zmN>>Z_NbGntEj`MTc7Jb%Ok}(jrhd_{#ahO(_RVlzT5@pln?x~dS~+Qmwu_|56e&D z^}E;Kwd0&`RXLw6Chb>D-0~=1UuJ=Oiz~-g?~Q-x$&aOZ_N(6M`shDbNlQPmF7H|S zj!|i`&c%p_Zo5}H|M)+WCzro`cG2G) z$1}tp&k%b&L+tSkvBxvyhQ~9+9?wwc9?wwc9?wwc9?uYaJd@BLk7tNYCx{{6gyTK& zvr%SjEA}DwE%rH%C5|zUJ?bRtD(W!m*7(qpud~>UxjWDEP*=8&G_`eGN1#{y`H$+Y z_&nOK{+)q6ZsB#0Tk3ldw-DQ!)zk-VEqhnz0nCna$g4Nl^6I(Hy<1*A*E#u_=_lS3 zKRYu%nC%zAe-^=ib_D;~6Z~fx{AU^bXAb@|2mhIa|IERE=HNeb@Si#O&m8<`gUx?7 z_n7}|K5PE7k!k+3Y0La)(+BgPP2bFaHhnh#*^I^fXER3gpUv3Ke>OTX|Jmp&>d<^z z(@*ntIrz^U{AUjSvzhD20rQ{DJ?1}~&qkTCt(nd5%&vn!BVT#Q@(vZp-w8+G*cV&enyy~M@`JbH&&n?ZI(f@XV#fpB}HyJUlqp z;Nte{syYJZ(zwTa?0Q*WxBJWbev?zya!meP+FHCPem2UqhMKdcu@A9tvCnZVy~J`^CCS5b#iw=w3AIPTrzo-T4S;&@N| zY}_M6{6XGB&1_ENJ}d6O;=U~I*Wx}d?(gEhFYX89J~8ee^ zF3xqt@t*kEC^NP-GhNN>dh~U@!L>htf9M_NeOzk>47gQwZBvK&lcwfw{-mkJn?Gr4 z^yW{R+P(RcrlxQHq^b3rKWWYYm_KRG2ADr-&J5VRV|}DQk2s#Sh-Wb3*^GE*BcA1m zXFTHBk9Z~|o)w8_NaER&c;>{o^p++j$yeED(%8YHrKE%GoKF6`dJz8&Y zb?}?v{GGkk@ z53z5t&v7hqjB)HyCs9}bZG4V-m|yO2HR4lDh@08UBLpJu2tDf}LQ_!Ye zFYWqNT(|p6yMHR~H#ynlbV82F&nCYU^6gKyc019g{VrR7a5gg8XR`IP6K$HTZ2j*< zo7RTOv2Tp$&kP*ziJy%!V_UHgv2U@@aV&2bV>9-s6ZE^*Rn#HIS?d<#uXPT+)N=uS z)pJzOU3=F^S#^u~q1P~8 z)*F59Ag7)?*7|(zSOfIAV{OpqE(iVd*sW`LpnTj(N zXSUcvw2=^RD6itaH16e1S9N{{F<70qQC_9W<0-GAd?tKLZ5OQXDW9o)X3c@fjgUu0 z{=dnM$GuG4~DJFl(ByTFS)FIb8C1oYMvQQ_w$T2LXWDfxx;meqbuL=Z zBdCsWOsAelXwE#e)OJ-zP#q!Ubz7db343$Z5vskp@|ntKDxax*rt+Ddo6>oeDpwhw zb&WXe&6UqoK2!NjTOyx6`&&2ua`W+oDXSCwk zt$3y@)&inU)$xhRvmd=*#gx$ElS58Sb|<@&-T6DCLad_a5$yd`daqFv$6`Hdo?$V6 zs^@^-{LVC;i`KblomVmE5M$98qsG`Z#Yy>j&#;{jP7F6Vo{{ z?eD65sp3qS)Sm>id9jX1J*t#hi9L zLl`*|YOgIEi`>)q0ad;z>MH6m>Ne^;&V}WU>hHGDd)oD$_7)!=eY@HF`n#s;5>vmDJ?sW-e^vU%rZ$VIoD2?@FAmOYoXQGd@M&Mszs z@1(wWvi>g1us3h1WyBgs;9E9+);!evRrGzY`hEmI3tc};qI1zY7wv0$^WD(FXX-ue zmCtNhYvLLdVilZStYa0`5mZNLiD_f38)6m2(y}`{+ZFVn^D2HO0e;!P$4BR)buPN4 z#uRhlF-K>1)YPiN-aM<0pgKZ`Rg_mzKC=vbfNyEOdnm*zEo*UHqr)Ddzw;_~mR0W_ ziFMCeaV@Cx54Lvc4C*X&237ObGsCjGUE7Sqvs^4KyOZ5v%?Ee&tkaa1x?YS+ zgMQwVoUQCmb|<^rY{)9BZZSV%hq&*P-SHg-swuxkO<8fK;>_S5a89f~hohQuAJ&v* zcd|R#UH`uWL3Ss*likVgEMH*HO3c=Vvm2oJmF5%c=jd_% zr~a-bJ-5}*&yOgtqP&XYlm3rSWOuSV*`4eT-??G+qxxNBh<|i0+MeBir+0)ZucEw) z{Ad6BPuZR9PIf1|Q$ADqOyx6`&on=Pcaqop7rghT{+^=`#JiMrK2zs2bv{$)GnH4- z^LO$4ZR7XeB9^VcKLUH3r)Ht|46BZyI)e7&{l6cV-O27`cd|Rx@0xR58M%P^`)5_Z zo785xkWz7G^}X=sD|Oz_zW4I|&X1{nr~RGcmi~`hWOuSV*`4f8b#v9tRX1<;iFn_y z_5~k+eSz|s%4aG*>Hqjdb|<@&-O27$M`+?e)e+V_rmel}p>~~DIkXdJOG8~r`-Qu% z9gNzV>Il?>o|nA8cjx*PXDZHAoT)fdapt>?Gf}yllJR%-BP>0L1LA-mZ!t!W zJ?bRtD(W!m*87v}-vMzh;vBViJ=7KEt_X8iSbO}eeLPuv#F#57wDA4Z;0r2mJu{`|G)bjEw6ppV-?awqKz?#ApY4!To3ldIUC(wAFJLal9vf z);`k6jBUj}_!uca_BoCPy1e^@r%k8L80)!fbP{zHbr^N){YjAH{UrAO6U*+Zc{dd` zwro0tZ{Zx_U;H0BbiNRSFQ!xS4ScD2D7%y08C4ozC%cTZ=f}6F(be#Tlzc#rIEFk{Zhr5IBw&QzQk*PysIMcaus6>Tlzcu)Lnlo{L7 zdZ+a+`l9Hgw7*kc#r%otcji3JXQD>Q+_l>UvD*u=_IFL~wW)=fexRFLZ`$9PGJIW5 z22o!|&X!np^QQKyy18+~{0Z!+&PAi9T-ShfUd8m|zJ<2qaV)XNx5RcEa!16nyD8c9 z(Q>8*`~uH#-F{?urUcnt%UL-3oTwAoU6T`QY{%nd+EF|k7IC~scGu*@ptA($6FFuv zk=DC6=tOoWyVLp1CRS-`g34z$dj!;!>pg<%cjiAm_UHPde5Uf59)pn&9)l4ZRj~IV z_FUhaI1{;Kv5L-Tn$lwJGU_DiN_Ho^ligLZtLg|%tfKv$_IFK9&DY;-|JKi@5yzZK z%%wye?@?Ywc@@tcmEe+|ziVo*c&?T<71tnBP?PhIwi9hC+FHc%p7_})Gq$C=d9ycH z{mw{Ydj#+?*`NBEdSdVtT)}nwL7s=$IEFK*#Kt|<%}qJ7JFRzG@2cnS-A`mVjkwmt zHOPLY_0E)_I)ds5F-I43cQL1@=gq5pMbwq@naXGS-lvXBaSnvo*B4@6cZefrB9~-$ zdasdjL+7H+aJ0Xhl1&XdpE=`QaIg#dPxG134YB!5or^YQ_`Xl)GsCkv;D~djB{vdt zl`)4IalA))71^EgD$1+G7~Xvg*C6)~#Bnd6yo&NF+TT^rf$F_R0}!*;wJl=vC(XNL z?N_L6@w)GQh|QnqJ$|N~=wt1_i0hL5TR)3Uth`F|&S9MWuFpK^ebL4f|SJ88?zMkf=&Jx@Il~*w(Xn&{uo%VN%Gkx8pZ&aMAI8$+^;>_q1 zJeKBuTy+H15mZOe_ai8uIiil2nrD$bmgaRo3s?J0UF)Xx|aYk#Nx zo%VOy-^DZeZ}ILC#wRgmi)%_;YvLLd*QU5;>6}>gy$P~A*`4gJdbf=GmICpK`<6OZ zX`ZEW-@@zeTZrAa5W8<7*7uS$XC9g}Fdpw^=sE5&JwD`h6KyKi4kC{C#Lq^Vu`R84dXHc9 zMT#?|_ABJrll_Zlxb!@N>A~%Yv9ZpHHG2ebgt1>-YvLMYzi(o~ zxMsz*EUs}8$9v*uqs-V=?1T1qEzig(pIN=T=}kTj{H=Xm^nuYgDzBovN{pRiOr`yu z_IGg&ifdC`v*KD7*SLt|J@Kh@?;au6_uuLJ@1l(uNAMlQ zv>oG!-qUW%@feJL)&7ffS;TSg?|UC!_umuC?)3e4F{fdi(f1>m5xH-njp&?M6RW_t zWK&Q59T3FIt2D7nwtezc=qKjheeYA}#GtcUZ+iaDl;LZ7g5G3z&AV}$XBkW_vO80P z+flto$YGBlyEFZ`Z>AmjnojI%I_;77y8e*myCN%|2^-Cv2l!<-{Rd(vO9gxatiA;vFuKE=kYB0VE#mP z1T&IYLy0U;)$hz*G%=y)95Q@} z=lY28f5d#%zcX;WCw|uMXk;qRRNXxKoal?9kJ5Tqty$5gDtnXNnI4eqV{8*+p~#uY zrO2_!J*{_I@8a4N*DTqc-WTn@g>jDi7Gn1;#O_;IFLvKT4BvA12|BN0dQ;upoQ(Sx zu37F|h;?42*_&fcr%lQ3nmvN*=4LzQWARRG))bs0v>o>?#J;a2_BEYYcBi^|dyg*CxI6iY1al9vfHpPv@d_KGV5UKd+?qu6lm$O+GgI-sqEM zch&oR+_%&@u{Zh_?&+d0iasjpFzPnyT>Cri?;W@$X}!~X{LE(}cf?rH=+T^2@ca+2`~H+z=QEoc5b_w=bf)+C z>HR7?7j5r%c%v=Y{~H_ey$|m(f1>xRm~x_zwf{E0H~M7wX8a$zHGhMDiESO%^9ZI4 zi(#5~Iz^pCT}2&6-9ndsU&~x*y=&eT(7Y4Lbk*3h>9Bd1i|@Z^*S;PSE6!}bBO7+g zc-y%~{WvFyos-1QNn-a8#IZ&Y_jD1*d*WxK%-B}!L+qQ|QN2fieG%)N*Z|H&qlf==tN1qQ)UNn5OArR=-$<@f=$nD7a zXbaw-3^~zuqD@6xi#XmBKO1GnwqhS*-(sKRSY&syJL3}8U)qBE7Gn5ja0R^8`OIc- z4&Opsmfh*RirGhVMh7=FkoG<7)x2 zuLZ>TeH~YL494pogVp!gZByQa<2~`SQD$r__Ca>1{hixyGQQNlh1l(#*nS1yLhSy5 z*!>2v>UYf^p|NGzU9(4Ma_P#eGMXrx|3DXaBL;b|PRgC@c zd%q7gAl2_oA#v{z_Z0Rk*_|mtcGvO_bJ|+W4a)9DaKGTbh1h)yv9IaGs^2wxbNH5Q zI@9+7%{W`z)UdGMvb?aq52)e@ZO7MiVqepVWp`CBT6F}~@8Vh<*J!VgbM1Z$-@?3v z-%spvWOx6??^i*d3hQ(A^WNhZ);y-OZbP`zuk;{2hy&t)I3Ny)1LA-)0R5RX{un)3QHzC>)l%8!0`XX2YrADkyH zF@o6s&Gvs{`+c_ii0yOPK3_nl$;&2}81I=FHuUtV;d%+|_Y=Du$Qt1CiM?H7`xW{_ z?ENJ6{@3@|ZIwPDtH$x3_*uK5kr~^HeTaRFefBZ3|8Fryjy>um>MH6m>el;{(DOJK zagN%%9_q68cn@?O=B}{zc-=mptUY4Pm9;Hw5yyMtXQRy6R_sIUTkLZj3&wc& z2~V3&n=#gN*XShbD(W!m*87tn$NNd_{U-)b@cZiLy~p?6JH21+deX#et-Z$HYi_^~ z)ZD;$IcC!v{01@p#s4ck%&np0^L{_Hi|~;QS#s-YY&t zKdiZ{{KJ20%bGj-cGwE-MRr%MiO~+M2J+vb%mbGcUW7-O26-4A8k~or`umU<|BtV%51g z&!Opg1U*YayU^KMovqawKb`UO^|7=x37+x9UXA-T=LWH#3nj+y6=y2WtU2KI>zXsF z-)^llvaOug4gXZ&==Pk9yPRg_mzUd8uKbv*+6DPrZK^-e0^JMf%?&OB5xgM6lZ zrhI0Ve^V}6xoG90m5bJMKza_y)&iYZvE-`qD$1*9kDxt*_6XV|sPlg11V3w`Gwu3Lnfh4pgn^22-+iPkDxt*_6XJ4X7h&yVk7L8^xYQv zZVR^y@xP73Ecw zSMmK3>+jklXpf*hg7yg7BWRDHJ%aWK+9PO>pgn^22-+i5-3a&kTg=ZaWt`hloT)fdai-!-KeI>wpj@uAgzxb3oNIFFK#8+NIkYMsE(jIg6asWBdCs`I)ds5sw1e5pgMw{N2vCOsv`{GGb!35Xpf*hg7yg7 zBWRDHJ%aWK+9PO>pgn^22<8Xye5&>c_U!(oiP|G*kDxt*_6XV|Xpf*hg7yg7BWRDH zJ%aWK)mc-#-%EQ0es_T0Yh;^ddrqyyIc$Ri{7gQve5QP+e5QP+a{&1@eBX+Ers+XG za|-#OXSimqXSiU))lW5l!qS5{AP$HF;($0H4u}KdfH)uyhy&t)I3Ny)1LA-VJbs(widDGaaNf}c+$#;0tr`IkRGImS(yXFhMqpSnnA{vP0Sf$FvL)d zqY!6>7_23x4KWyEOWqF|AqF$qmH${|`aIp?I%3QEe#Dl<)@DnL7urpsKP|Chj3Mv4 zcN>fI@G~X-H;l0wYc<~9;c6~kxoJDwTl5CkQmg$z^}n~n)$dF`;%&^?fVao*PQL9= z>iO-rJ<)&xxAys-C~!6MHhoyfThDsU!Rr4NAKx1HhD-6Dx`nrs8Sm+hEyR1`XM2mQ z{#AGP3fDf-KGNH9^tLa!PckcQ{Ws~M;@!wswrc$I+v9i3r%IP5vsqu>9yjv2R``6p z4Ss98>Fb=;%>48F)ozS=Ld*ue(PvmZ^}u6tdD z821KlwA4^Wjk>(nZHlD2QU+va?sOIdg zV~^H*sykb+z1`>j|6)(%(&0PMnsbcUIYw;1de3qxHXh3C|91OYpYK|Jsz1@YIj-;S z?L5!mO0WgQ0BqOh7xm@356Hz4BTp7=EnBO+ZuhpVFVP={Sj+Bz|J#jym^pse`h+h0 z=bh&u>cn)_FL_be)ce(Ltr^pIFZJ}6Jn54)F6gA+&Iz=4J=7ljYM;d37Y*O6yV86A zo$D}NHgO=@4!%WmXZk>lZU4{)+-K7E5tBzhpt<8dB?Vo*CwT_hU9+YmW`lkQU_B3O zI=ko zp%462vAD4GAP$HF;($0H4u}KdfH)uyhy&t4#ew(htX*uk-mBpZUaY6YI!nxHggRGC z-q_}pxnks#L!AqC*aGui)#s~m&w2V6?HpY1@f-TqSGDh{Gk96`4eeSzskt7;(o)L{ zV{fVb1zq922X!tT?>!)fo`TM)rx|^yP_3u8y8ec~u~rCqeOWg|KVrMqzg+jUn&ZAZ z+g7(_{K2^hw%Z$wnqcT#pPUbQgH5q-Xg6LDwO!Z<=Lnggl6!+|9pWrg#MWo~KjrlK8J^fym?PLY#|s;QUaJ1QcV{DG zyEgU&`8HqC2lk1diEZ`0KdHtwa{BPb-}VMqx~@L!dWp{+H~t)RgWvmHQHRc9V&^b% zZ*$`|2Tfb>WsncMu{Mao`QS@i>XosMX&>YL=uhlt(0PXJ>Su-ztL@;euE)MbTz>|3 z6gb=`ekQin*Z#zHKs^f2u!q`)r4#977U00U_H)&k@OSV0qVAWj!~t#NR~q-Pp7j=Ak$6bgk>w$GEJ^(0oZledSyKj7^v_AztYuB>}fAtp~^DYst1;#|+@rZOeO7vHxb%UWyE^W58|}~h>-!WhW2AlO zlTTh`_2R}!*LQsJBjeM&XMeTh#>Wm!Fa7cMB3#eMUUd!cnd6|bdBSV26AwCPbiQ-s z;Dpa!vEYXJN8i|xc>Sr%<;z|lO?>7lua#GPZ!Gaki(Xwmv*LK-uiyEZ@>_FFCdTN( z^&;F~1UW^JpF+DS^e2UW#<7%-y!z1s<2v)+AC`kp97%lQN3SZMI(7>2b&H)}e&M(0 z6F)g*a(RE}RmAfhxN&*c>NgWVc>UbvZlAeG&!aYU!Y>ac>^LT9BcIUSBMLafc zzH>Wndiu!p_wk1p$6P<40G@aH=wi25S0!F{$90Mkk8ex-kC#7IeC6|BB3^ryt2+ih zIg$9)!~Zfo;9J5yJ>j!ukXeSd%Fu_>;`6eO+b!-Tw)hzx^auNhx}Q1pKN~lC z>V1dBz@^9Ph>eLYR!7WCY_U3GX=01j5n~futX^2`O>D7xVH_Z~SiQqyb>e^SbyHWk z-V^Re%wNmFUVs>TfzU3v%InxWgnpKx|K*v>591iuU1EI880~t2xxn?=E*sMU{N#C) zfO~4(Uwf{j|MhTZU+lR;|5F$*aIKRR#tU5QAq76P;0;&$`Yq7U0soqm_WRKS)ZyUc zC#0|KcOLP<*BqAi=zNNJ{Tug6AOFT83HPt}$`)zv?qS61zP3hMdG*bRA3f+(X_a&L zApZ6z{#<-=y+est+W+F>Cl6Hn(}fNl2>$arbT#kt)%C0A8d~o9?P@>!@$IfIpZY_! z&prIf*UD|iR{P(-{Cv55+DEH>@uMR)%+GFJ?U$$DIXZ7N{c85}*0aavIX+hL;gluE z=ijVy{JQA#xn^^l&HkAZ_~_Nf=SP0|9pdM29h;v!_%-6E=H5ADkBxg^bDJ+-+4Z2| zW^+?3yWaB7*UN<`R(5*O7T1*jw@_u*qZVAP9Pf7ht5xQ_`4>fX{mFl?QjB@Dy8q-| zzEeE3{LYmBg@66KXuG45f65`trK`qNcK!Y5H%JdJF@X1+a@^>2(vK^<-fEw*Epr#= zG}!)o?xRL5y6}*`@KM38v1ZZsEr;-)`=vu){b`^3C0mPo!g}2k*6SK$y{_*mY^~|> z^$u%L>FXWVCSqIfN?WstZM`dPEhDz|uE*9mVq5QS33zz8rz3n8YiKPKYb!C<*3gGK zACl_G#$r5SDnojxI3Ybq58{A0AP$HF;($0H4u}KdfH)uyhy&t)I3Ny)1LA-<@ImFk zj592Kea_0xJoV#yw<>)vGJT#QeSNmd&L9nOe&gL}Jf{R*hBHez$5fwX`j6fRRi802 zT{h3(p>54w^PM=X&-i<`h~MsgL7Kbfd&Fv8{fFjp-1^in zy+3WuI8Scl?$__>j_+LrhddtXlk@ZE4!?akE}lO; z=bt=Dyuobyk#BECJpD_H<~ugnllb4)KU)s{)M3Qy zoqS1o!mX8E?EH;ECa;Ql8DEJFW_Fs>quHw8VUpq~`46x0Gd|=N!fo$NOO(W8?pAP8)1`C}EE_r_fJ@yAFfih;2@x&y0I)PN8RF zo6~IiC$>4wHZR0Br=`sovCU~|^GIxS+7oa`xTgr8ErLw&ho1$1LLb1lx^LiN-Dk{Q zg^izKj4e3a^Pw7V?N6|__I2JS#KSq_{_I283-sHwhp>Tqj6nU_hY&0FW3H?mI?1PQ7v7^4;+s+sl{Z+!qVMqPh2WzW&SO0_OEKNS|^rs1V z-YYMxVv-*mmS5cP55&W|_R1rM{10vXv<0_p!S7a%eV*erdCBAwTRX+%A5{AeYrn95 z@VfP@n4zl~d5=+}E^mLga?l?1jQ*oN>fFYK_JFPZT(vh~0Q3;Y)!wymJMIBL->n>c z2A{O~?Sx!lw1f75(LVGGjDDeiz-TApcPppX8)OB2mO;;D(0>{9nInF;a;)F%KV$^{ zq`<2b_=a3%ZSO7kKamsW5$)FVi~iK}p29q~;Mkwu$O&_l!#qOI_57A$-pe?TH6Ar; zxvu{YISF%%pWvU1P=CR9uhjSGJKs%D$a%-LJG@f@*U1gUZt*)u>|@j+>JRZdO8mVQ z_4oVKddBzr5F;)K^MZNjb@MC6_cvqB_2n1tA4NXGfT7iePs z_iygd%lE>5B?lU)exy(7q2@rf*M>gAeyxoAbn^@J4|dCc^qr(JXBhJgeOV*;Z+UNO z?IYi?#$g`0_Cd$*)xPEp^VqBreViAHb?`pPC)|C)({&yjHE8BiU=x9#umkE7HWBuN z$RF~$UBmaG6WhJ`K6GN}CdMB1eAzwyS`Y2Nc=Dn4zV;_N_pWpA!PaK_-SM@pd5){L zP1&9K9{4c$Ecl_`?geCbvOC#bmH#o{Lfg@EUNd5z7z@Q1$y^M5FJh+{Q^i=ze00B` zGtt~>?%>bj{w2i8S?itFyLZ3dA)=~tEW*%0^&_1~58{A0AP$HF;($0H4u}KdfH*K~ zaUeW@(ek{{9aEoT-EgO$?41{Q;A_Ootan5{>u0a`V2-l+&0t;*MQ5%=U-au4VfjvE7^PGsGsNG+D$Z zyR1opY+{Q6vT-hHkM+~adi>~o!P z-RGLv=bG5(n%L)>*yozq=bG5(n%L)>*yoxUeg80xrJhT(*|y$cXuNm69Cubfx?g$_ z2YSbW8Gg2}&vCusJR$us&dP-vakf6=&j8e6LQT2l`K)(Sqxmm77s~a*blm6XC*Sbg zNIgzbkz?2u72dNqz7@}z2kt^HPdCwdG)ZK!arr`8ony5zb)tC!+Rlc zo% zn-AvPp=a`A(1P?(X+e5;FZG~x&9phouWR)hr~TRpu4RZ#LVSX2^%~cbAHd!Z)`Y#F z_G?;a!3C`^l@?}gJ!oCCS)Aq9HSO28bWcACrSNfFU1$fO*Y+2aJ318DPk$ z+L)3d8*Sh^+6>n_!~LD;tIO#M^1DL2U7j84Q z*dNnn&>Pz2bzYmH=Pv6fuS16QpBS>^d`+5b)#CimR%ea}9d=c5$GnGdyx-sA)#8!c zb|Id+>!5V%pEn|&=fU;UC)OK6yuxWarSVtHK|Ju`G3oBTf55u+O$&`rCw_7y@qxEb zN}pcvUOt0leNWZ=wVZkDllR}&?V!z2Pj9JB*gfpKpX(#`bA7}(>u0|swtL_0`)~W? z{B{^uKb+s5F<<@3le>3biJUxP@Qb$`^2inBB9{o~x7(FS91)?{fC>4ox5Po>GFd}}A0UMS!6lx;34-{!V7xs-41WYY`fo1U`GYX|(5 z&2wpbDd3AtPub>`@@<|=(@O!rWO~Xruas}|oQ+$(%mTmMVQNB?10kPrRCt{@-% zhh0HF^bfm&eDDW$1^MVd>z^))4`iEUXKKKK>f_(5F zb_My+KkN$f!5`QaKIR#`gnaN6 zb_Myk2fT!Q@Dz3h`M3^VLOys3yMlaN5B(nwUP3;23cG@Q+!OlW0lT7nyB_-A0lR{H z+#mYi5%k{yyMlb&6Z&5S{da`^7eW6;=zkIPUj+Vig#H&n|3%xqUj+UXf&WF|PZ9WE1pX9(|3$FhBJigO{4aw27J>gM*l!W|pMw1s!T%J2|0&pS z3jU`E_M3wLDT4i`;D1u^pGC0W6#P#L{<8@FCk6jm1pkwQ|4hOE7s3Ce;6GFF|3&bh zDfs^)_|Fvle*zaP|Fdcl{AUXOpZ8S$=c*$3e_pTr&#Oi7|GZxLpF!wFC-lEwe|f#~KV#7Udi{m|>-d59RQ_i?`d>i4*%|at`G^z4`V0LR z=)c(+`d_cV(0_sco1LW)|DgZ%`V0M2zS$Z0Q$RmvXV5>_ce69_hw{zNpnu9YI|F|x z-|Q@f_zn7}e6us~hw{zNQi$KcAIdj71OF-C>UJ0X5cX20w|+A;q_`Os5{-xB0P|7Zt#sra)J>^EV4(GK)d@n-_; zH(`F!4)jv-=d!~5C*@12hE4`esGOB02qY*;EXu_#q(w1d0~7XG_TvQ{-g7jkX`+7A5B}r`NzI|J`U~m z^%+Yal>Ni!pi6JFEf0_4BgSWeUDdMxH?A>{&au58~%hWhu{mGLH_Zi21>dV7cEjHWz zVB1ezRet>7A;rjO$ib9<_Q_WjdmXa}<^TDqsl}~Z zZ$E{@yh)0BVepYJRld~_ko z|HOLT#RVVxJ>`$T;<#ep>n^7JyZ2tZm}BJ1lz-wU@9DU4?e!`D;emtFvR!La{`P-c zJZ&{~MarMN>Vj$dg`cAQ?y;{GA6aGq<$rFDM~feS|6a=f>jqa8H?4m<<)5>_!Nn~b zFGl%mTr{9Cxs-41B$G?|)=o0HlyB`Mlgs^ywUbOP_aW9!GP#s*?Gz@L@~xf1)xG|Z+fz|sGIUlPqr2vNBO2FizC*ieAAP~ zBlp<8cYHQI6*jMwZ}XgNUMb(^IoZ5YzRh#8d8K@t=VbFr`8LnV=9Thoo(r4T9`MKJ zxv+Vqe4FROcuD!j(`3A)eB)^{UQ)jCG#M``-*}pgmp$O8@iZAPd%z##X)<0?zVWm$ zUQ)jCw16M+{bU06eIv2&6^VU+NbLJSV&D4_`+koyeP4(E+kRu!()(XPzW2X?eD8k& z`QHDI(0}eNz5m=#djBnM8=ujC*cIfv{wd$}Px-EY%6I)2knj30(0|uI<-7hVANq$~ z1^!UJ^M~@CKa}tMp?v2L&1O7uU5)|0&=7Kjp*!+ge8Xuq}&uC?D8j9?A!{n1}L#E#{$o zV2gPuAJ}3Z$_KWXhw_0#|7lmge$lRc{VHKszJ8VP3z%Q{3D}kQzXx{Z>sJr#3jBee z2>LH!SC9`s2fKoN_&L}WO4t?T!%xGmARm4j zb_MzH)37V_-}qC)t{@+N8g^CrpS4Ta739ND2mWW+735=`fn7m9)*0B9^S^{$IsZ%8 z735=`fn7m9)*09pkdJi|b_MxZCt+8Rk987u1^HMfVONlkbrN<3`B*1m zSCEf&GWeeiyMlbI^RO$($2t$Yf_$v=uq(*NIuE;oe5~`ZE6B$>54(bVtn&Vmh8{->$q8h@HPuJNa-nDIo59WufOPjPw0P7-Tx3jK>w8Q`lo!?Kjpjr z%b@=<=%4ak|CA5?hxiBlp?v2LZEe79f9 zhy8~5nRW&F?tduX{SW24|Dk;MKa}tOhw>38LN676?t%Yg|1r;)SIBq&N%`(SDc|f2 z{*&?%C&I4KfA^o1@BWkW;Xlp)Q$Bba_Aj(6=pS(+><;(f{c~so7}wDTFz!biwH&ko4Egv2jB98E8292c zz>rb3F(pBE^^Ut{T)YQ;3HJ{Uas~(aZK2(^(4V%@&$iJ2wlFSSug8n~iLFh@A%-r4 z-rB5P`#i_hhTr+P&`)B>2=g*H&X@Z|&RxapLx{l(#2@Gvc!Br>7dNaxIo~;d^zhUm3s0Psq!CsLp|eyj-80+p+gu45>8Ozvp)PlP6wVWDUe? zh^%#Z-H`PSuNAVUVfkTl((}U=C#(E0IqCUftktYVcx{n25U(M!*5P$S);GLX$eM=N z1X;WAI$%N`+iQQUQFx7ywFs{*T1NzlA!{056J+he>wpP$1h4(EM&UI+)Z!o) zX9E&yAYMact;6evtZ#U&kTngj39@$Kb-;vrh1dRAqwpFZYKhPb<)a4THN=Ekht~~R z-|$)?YZ_h?WbMN1fC=>qul=z`;Wa+!sje+1)Ihw3m{9BRx?w_n!)t{JH4U!`Ce$vx z4wz7{@Y)~dIeCq*KwZLXiwQLluOTMXI=pU}P~Y%cVM0yAYk~=N46g$w)G@sF$2x}B z_*ln)efyq}KGgSw#J(pa_B|o}ukQ(oeNRa2dqQI06V|oGy8o#0)%{1^uF*$!w zW2*T>`KXV1t+3_~<)ilHb-xQ-eqh|EGM^5WQ|#`+v$uO&fNF{)hS??5wU2vPSLoLHd7N%PePCy?4@L9?FN! zSzh0y5c-d^N$fw)P$93X6A|=ZpTne|^V%!VI0XIIXFKVqy#|f-t3J1h z^{YOsiS?^KlZo}KK8FcAE4_A%^{ez6G1f1f4P*bY&Ug(S>sNhl6a25wYVu4<;D3D% z6YE#@+BeUb1pc#T@9S56h7;>o8SJ<8T0hpWGT1Nc>u$fhSVvAr74Bw+ory%f(O!2e{}75szgDF^?Pga0i33e!$MMpYeeI&#(bsze-?VzleSPBKGx*_gDU>spA@ds_#qj^^5oT`i1`E zY-ip79$&xEf1KN_`;W7lb^puI|I*hl^uP4=3;nm87uPT7pYaLe#1KC~|D~^A(0}Rc z7xYj0u7ApR{Zl^T#1KE^5dVNbrLSM$59K?5DBt-*`OY88cm7bm^N0OMoEYLa@SpOX z|CEn7F~o1+KjkA%4DlQIpMCwxA%5eTQRv_8m-5|yDc|jv{YN_?{;bbo*7i&JXeY#< zJo8%d=bD}nKg0h}zWbl->lgeFMA zSCEf+#=L?*m}kr@KIMa_VgG_N`IL`1(fmK< zBTn?Qi?#o!eDDvdkPGw1bzV_J~QYO`Nldghkn+1IpiCO zkqeCT)t@}^`XK7?b$zfv9RqcD#KfK-wpecv&k=aNkLMb^R>(62Ui&MMyY{*v&lh+d zus|N$YlsOsWUEzBCUV+dwpF7AYMaEs6lv5kY{JS#)n!u zYxa`{NlOuNx-RH@ptW^FCffOsJuFO)#OR<2AklwFs{*Ce&6;FR0}u z)Ox)3$1_S^H%zGecpZ@EmArias>j8XebsBL+zFrlV_dwjoF*9{Zu8@TR! zzw9-{gjxr#`#uo;#~B;;-)oDht}Xihu&({F|M;x$6;a1T9gY3Rb>BCl|EPJf|6b#x z{&A1*C((b@3fX_J{Zap3H)Q`|SCEf7pw|%Df7+Gn-)ns259|u^(SOvCARqeo+8_CY zdQz=_*cIfX4hXwK|Dk`_75WeUc#V(zhh5eBhh5eD@!B8x54(bV@CSAU`QSh73i81p z)aoD~H9@cO(SA|0hkWn{H9W`%|GoA{`$atu^1*+|g?zLFyMlc1A95j|?Nn#v=zm~W zkPrStF65&f)I=-(yinH-X}{15!83;AdVdVzfC$!mP{nUD+lXa{x$`OuTs{^&oU zmx@2fvAz!Zm}lq(@}Vc#735={y~al$?zP1PJ$bE={?luJ^zB|Zr2m9nK|Xkjd4+t; zv)2Ua^KCt{eM=R$z^>4L%(K@D>HjUBp?<($uN%_;TWmx5xb8JX`hSaa*neCP{V%+> zNdIr~5A}n4LjSP`wY_u|3x)n;Kh6H*{?LEg75Wc9XYmsIk9$J@JA(d;(EkqDmFvF< z{qG3+r(IS4=hfK%j-Y?qmGh@Qw+a2zuAD#h8BXZGBk+fI1^HNKg8n-Ke`r^}e$lR+ zKeQ{z$2t@EQw09gt{@+0VFG_T0{>}OkZ*QIyMlbIGr@joSI++;*l!B{hj!)sFM|E1 z;D2aWkdJjT_#fI8AM~H=JNh5u z2k?jT5hsTD0sJYTAH<0vegJM%;3@2?;?F(spX@*88FmHv;Ax2e5m!+@cnZ6Me9W`? zf650>F_(~uxea?3oXbXO|`#M)<{IEO#e)=z0*4}kiS6}DK-pB8NBd?&*z8<5^ z-Bh##zTjCwAn+yRMX|2o55IFQ*db4Ltc-WT-+`ONpupO`M0 zOUArKta)tWmK6LOc%7je`0U^h;s5Cy;hXz;?PGu7KZDPN-SIm52p^3;+Yjn`#28Z; z7q0O-?hWH=@&8q=0b=^&d#HO4r@JoZT))7n$q@*l@7n5h}@iZJwnAL>5C_BoaX=gp2gCt! zKpYSU!~t07{Em*>Hl3VLpZq!A^OF~j&hsC2Gw}^;kI6qgVj(_%_r2}6$(z4!@3Oa_ zZI4(n|KTTl6Q6e3Q{~TI^7m?QyHxqWv6FfI#rY@poPPDu#HU}rMe&d4b|=2*_P-T_ zt{zG}a@5-CjL$#Ewsw1Lk92q2g~U((^sqGVRuz8XuEWyArGCNdzj$=tblTY2`Pq(5 zMz`R#7n{y|_E~rTv{lFP#5-?!WV&Sd#l%l+c38UkfL{`ydh)($`bR!NIlp>h%e2O$ z)wtHWY{m5Tjy-t&CtrWQSY?^2|A(x+V=?_B)wl-SeSOb-zZuVa4qI`p^7vQwAwKBd z$IGR@TFH6j#TD~@`&aJ`_~n;(&MS2t#&#d>9G9QD@>J^lfPE+DVY{D3{KVdq^HJZ~ zg!laYf5zuHcjXg5<@JB>bwEC6+iwuhx8C7-nJpG1o@e~T{QE~YCO&o9@%irAE+yV@ zj>GbwPkOOf_J?1;;QUp0&(}S*e46X{uU&lBUhC!Wwr`#0zWT~bCJz00UgxGm((kWY z;LKCRsQSCi8V-3wlF=Wplf`RnPE(^tCpTlT>-59#>D`G=-2+_1pFJ11RUoOkC| z>Ew@md)e>Z^6_-ir|tVbcYk*2d3GI@{`TYzYk+>^c6{o1sKVDCI6i%H zYBd*s8h%&`<7)70dmWI%7*iNy3S&%RjLFBigpD!z7?-gzCLiOnHpb**9B5-Ke2mN5 z7(0B7m)ID4e2kac7)u}HB{s(FWBitlF^4hcFvc9ln8O%z7-J5+&4H^qa5V?6=D^h) zxS9i3bKq(jxLO9Tb_A{#fvZK}Y6@IUfvYKSH3hDwz||DE+Jb}6Nx|o&;B!*&IVt#@ z6nst!J|_jAQv{z=1fSCpd`=mBP8obo4n8LbpOb^n$-(Ee%-yJuE=hY|<;BnC{eM3v z@nZMynD>9WB375A3jF>r@!u-SJ-+U-ZSBv?ej%TuSC4>l#aZ`oLdt=wa3Tv zpXWB4v7gm8|9*MkZ>snBp82obQ;e(p&w%TK-{!zH{goH#TQ*;LQu@q>+x0;H*v`pmgU7ZdzNBk%x@GHc@}BQ( zG&wE3SM{F1lh&Hhf{(msGVfV*%H*{7Y!C3WJ6}5~eRiu3;+JoloYq(o4I3nRuB+PAz`fQ~A|7 zUSFp;WXa0kK6U)Jd;WIc7~V7YsXr(W`Nqb?r<^=6ue9vK#1H&#>)d(I&)8P?Mf>Hy zyinm4&)F{zy>V{dv)RHsC+#{U?>lgh^xR(a z4QZSGZ{@Swj!S`)i8-Bn9e9Dd8>^t-vX=3Lx& zMJsOq`54|a=}ePz>h9$(f0%dK6K*^ztvGVU^4nJo8GORn32D27R_WP%$CU=3e#hi= z>g@9r-@Em)&h2lWm}cAMyTw<(_=~Pb?i!o+>0T)9-Z`cFrZu-o*Do_7b^hV5?(d&8 zIPEy>p!EG0?(070@H>k^n;o8B-e&IZ#b^IU@!CU^(`nnD*LnY8i*<}&X`qt~1E;MCRg*$~|6K9Y?q_Zvn&%kzg|zbe^G^H4PZ!AB{qLCcqocn# z?Q7-t%O~fYl$QU>8Pi@F`C8AFYfMa6UwiSi)$jgfG3|tX(siFcZ`xVizb+OUu~Rx@ zr;Vl^IB?E%~AIpq%z-D=1YuOFUX+wz?9!qpb(`q*4Yq_KyrP)=B4a`#uqO-Q?J z`qiH625r?ob@$0>SHoS7KR;>Ba-FHybwB=x@oCF;`%dzw(vV4u9+Fnx?X2?Nj?IVM z^5rAafD78o?YI5E_B+m-kZ$<%=Z61b?!`J^`RC;H`(wXU>~q(;-B6e$vCm+2s@e&&h&)b}}7V!pShvf%GjUv8!!^QLK1NR~xwD~jTCYy{S9{A0p z$}`PoU?XQ8Joe__KUDddZ$EWnvG~E2|2%NBdDHnlRar_-Eijh z^e4+cH#Ys?q?Kq>Kf7~s`slbX)9$uAYFyg<$oq-c+VFsM^JW#^b<_dr&VQWA>z_X1 zh;;02>k|*&ZF~!Udh@UI`r~IFo|d2UY2q)vyjS|##2*u1_@@KX`18&np6`c8q(!fI zg7!P-@fk$?Bc4S4^z zUTMoexTX5+y|XQmuiCeI2go_c4ahr;tG>%%=Zmf>cl-B5-oO1K1IqJ@YE4{V%<~;T zc;p~nKWeWZ6+5n4eLvyt8!VUR*mw6;7xvpD~uvzI<}&s|gJ&)4C&rY!uK^pQ~& zS8rZn>2%hQ59IaZcfPw=XX{EotFQ3qjt8EtVuqDo{#-fW*lI6x<2ipVXTSAxy#J2R zFPVSy(+c0U&XRfVkL{d}efoEUuNpL4j&p}`f>#(f#s-YBVr;+|E5-(lv0`k%7%RpG zjIm;Dz!)pW28^*{Y`_>R#s-YBVr;+|E5-(lv0`k%7%RtS7-PlQa2;dC*Z?tBj13rL z#n^x`R`3!SV~rRb#dUBN90dkv!BJpv790fzXTecma26Z|24}%hU~m>31qNrqQDATu z90dkv!BJpv790fzXTecma26Z|24}%hU~m>31qNrqQDAU3&K>*?uEP((*8s!!z}Eo7 z_rTWx!}q|~0K@md*8s!!z}Eo7_rTWx!}q|~0K@md*8s!!z}Eo7_rTWx!}q|~0K@md z*8s!!z}Eo7_v~uE1{l5vz6Kb+2fhXvz6a|BFnmwMSTk@PYY5g1V5}inGk~#%V9fx= z8iF+g7;6aD3}CDwSTlgJhG5MA#u|b(0~l)v)(l{*Ay_kjv4&vH0LB`EH3JxH2-XZ> ztRYx4fU$;P%>c$4f;9seYe<|s!~x&57yxkr*8YR$dc7U70M>rok63_fzhT4zSo?7u zu>jWopA9|dBE$k%`*%C>uFDY%VC_G9xAQs?3t;VEVxLR85DQ@Kzj&32-G~LS_TPN! zVcm!Yu=d}!;`3dI1+ey?vh=E5hy}3r55H^eF2n*@`%nGryxoWeu=d~f-NU*O3t;Wv z?VzW-5es1Le`(-_-G~Jcw;lA@uCpT+0N(Dg-wXgo47bDvcXlJDLkzd=4%c)erb7(3 z$-H7QB!|iha)m@0`5W_A0sgHFbrb7(3*i)bBLQIDk?%yMx=|W70 z7;cHBj_XEDhZyd>r}yecOotfm>XF@Di0Kf+t#R4eorviW!!5q=1D7GDLktJiBBnzO z2aK2wG2FN2J83XtI>d07cE8+?m@dv8;&R-NI32M#Fk*AW;=qW_5sL#OHb*QDjMyBp zI51*!#Nxn+%@K=txhu<$6C-zJ`Eg?8t}H)JjNFyw$BB`cO z?#lAxv_a&qEI(eNZ^&I)ew-M&E6a~(Tu1K8^5ewFU0Hsd7`ZFUj}s$zW%+Sp-`#FiiDb>tu|KTeDsq~*tnk%P4SI5BdNmLDfZ4$|`D#K=Kfew_V84$|`D#LPk7 zeLcs89HiyP3-lj3NXw5CBL`{u@r3KhL0W#C7&%DGj}s#YY58$tkvm3zkV{7H7#O)^|-SMF|z+YMvlwJ$np9ZsRtipLLYpL z#6Cu1A0x4kk=Vyb>|-Rx7*W@OOz;-99AM`vv2&H!xk~I@C3db7J6G9f=PI#tm1A_S za_r7kV&`f`ADpYi&Q)UPDzS5w*ttsVTqTB|K}`-a-RBUy&mnf7L+n0>*nJMM`y68T zImGUB*njsq#O`xAUiUc#`rtl?*nLjIb@w^M?sJIU=McNkA$FfbjJdP5gBa_GtsTU^ zc2u}pJBWSlAojI`*w+qXUpv@OUpvT2UpvZ4KYD(kuN~#wuZ(K*wId((wdrlXcI1Cu zF}23_$EL05RsyVmV^Obr#DJ zdn`xnu^h3-a>O3X5qm7hzIiN1?6KS}=%>eWC9ubG#2(9KT=!Ux*kd_jkL8FxmLv99 zj@V;4VvpsB5rVvos*F?Y7NVxHXhR?L(8-imp0-&-+H?t3fd$$f9d zJh|_!3gpRsZ`FZ3x$mt?mc@A2eIcmh&|Uq?70r|%5xpWp6mE5IOe$y za?*1h8P`46LF~B>V$XFDd#;1na~;H<>mc@A2eIcmh&|Uqj69X)JsNB|D`L-C5qr*x z*mG9Ip0gtMoE5R>tcX2lMeI2%V$WF-d(Mh_@SGL(<2ftp&2v@>`th6sV$VJDvz~h-_S_?Vi02+l^v!dR8Q61=#GZR3 z_S_?}=N^eY_ekuyM`F)C5_|5E*mIA>$QxT8vcZ-^CiWaMvFDJ9J%>!}Ib>qbArpHJ znb>p4#GXSY_8c;?=a8uf&mmJkocVnA@-UMvDb8ny{1F#H63EF=@5HOhuCX6 z)PvV_h`px6_{VEH1@z-JodoPP9b&KP@E)(}5M%Dl?+_#BYQBcpYjeb2nKQ6ML}MW`{mcXP<7XZ!y;Wx(I2V5Ap@2U9%mcBXc_8*P z56#?JTuwe9=W4MyuOnY>u{iJdvnv&@&aUttKf6+*EkC}OZlXFt0_>}OYq{p<>{ zpIssLvn#}Yc7@o_t`Pg#6=FZTLhNT(@(BZncKX?sy!ViCOCm>Zae3Z%$p0+?Y}>}Sb%5Ax-}LXr{Y)USp9%bb?7atgRmJxAPf0*} zhfo6~IVbeqb7l~bj&!66NC)Y?g&-hEl_H3ANJyj?slu6|NpA{BQ$zvjRX_xRcYW8M zlRJ6u>;LsWKjr@KeGku*>*r2pPhES>n(v;y!)(q3GMh7jT(3D3$YX2H1oD`hGl9(J zOd#hmX9D?J%pGY}%+Op(t73*;PFfZFOz7pLRq?gZ%So%^JkZNYt73*;PFfYW4SG3g zRm{-KNvmRpUQSvSGxT!Os+ggdlUBtHy_~cvX6WUlRWU;^C#{O>f?iHq6*Kg5(yExD zmy=e-485GRD!vvPxy__GavtdAq&YG}FDK2B8G1Qsj?B=@Nps|KpqG>8$PB%lG)HFW z<)k?>LoX-Ik(thu&`@nh3yARCf-3Mm#?gO{My!*gx-hE&;?>;b_cORI| zyARCf-3Mm#?gO)V_kr2G`@r>@cOQJVigzD;wu*NjIFEVvff*XPWw&^Th11PDEIyxu zcUZU_^9~E=G4HT2n|D~aJ?0%2X7dgUvw4SwnS2i3VPQ7!urQl%iI(o#KQWdO6mP;op=xEwAFHwL_CW?)fBWQ5dZqn)Gqc7BxGJ)(%bjxcBElx!kmNXsr9|n>KJmBexkb zK%w5r+|bKOANOP%QZ1HZ08RS1=kxc!52F}BlRoY(<;mlw7(kOgt{#n_<)#=wlRmCW zT)*I^7(kOgu3KJ66HYOJCVgBtnouyDVgOD0IQeByIK=>p^l@EpNwsi_0Tk)udT}04 zIK==S(#Q3%Z0>N10R-ve`oPeX;S>W%(#Lhw%d2ka<)n|R<7p4NDF%?FkE`rC54b4? zkfe|63~iRUDF#R|cZlT>7eOyaEC+^OPWm{{JH>L6^l?t7SWc2Y&P=hKBz>HjVmV3r zI5Wj^g7k4_isc09Ep~4%W2ZbxeXM{Y0}4i zv79D-T%es4%W2ZbnJJdjq>p=$PO+S}Vz~rt#pK$G$u;TYTn?RK(WH-aITVv?(#N?C z6q9Sx$C)W6*QAegJ1HjDq>nRGOs+{EXQr53kv`5$F}WgroS9;BFX`jV6q5_m$C)W6 zm!yv~Q%o*NA7`eRT#`P{Ofk76eVmzMa%s<X-SA7`e$l_Gtdnf6wi^l@g|TWQkAd8}w} zrAZ%Wrn5+z^l=_r+FNPT#|7q#_Ewtoac0_EY0}4;X>X;ieX%BeoUesmZtamZ>EoQA z_Q;y_ac0^hYtqM=X^*T)ANTE%HRj0D1AxR%+Capt~KF&;9ha`QRnY0c;`ZzOb9fI_6X3{z;kv`5$T8AQi zoSC!^P5L-9X&svMac0swH0k5c_}uBONgwy34WxBw(#LshN$b$0k290jp-CTSCapu0 zKF&;9hqiR81Z-(mn)GqbPnwk`eVmyzD^2=1Gig?u^l`QU(yTP;_UOq!J-eVmyzD@pn|Gig>5 znic9I%}SC!&PwCB#!9)+bnO47$UKWUGW^l@g=9wq7H%%nX^(#M%edlaOPGn4ix zNFQe=?a@p6I5TOFiu7@2(jGPGnR`_NYl8=P@MhQIkH-V@ukj zCVgC@U!*;1(#M%ed(@Rq>uBpq#^FS&}}^Od7HzeVmyzWNFWx^(;VG&jJMchW4PZ=o=V)Mc=^aEBXdT zUr8TlMqkl4q@%Cs8yI~>-@xcA`UXZ{(Kj&qioSu-SMD1z`ij0G9eqXLfaojw21Z}e zH!%8YJ;zDF)-xRq8%2KDENm1En}v;nVY9GNFl-h!3Wm+XM!~RI*eDn_3mXN)W?`dX z*eq-m44Z|Gf?>0;Q7~*4HVTH#!bZWcS=cBTHVYdC!)EQdv!2Zf>)D)uuR(tJ9{3tC zd=GpL7`_L-1`OW=Ujv5kfv*9>_rTYH;d|g~!0pmVgaoEV8jAg`x{@&;zBHdwSR2IL~g_aSo?FH|Im$C0Be7@3P;_D1+exh#?(#B_+^&|k!Kh~dD9=@7$#5z`@t10$wG3g%@KkN{{o(lP~$HJb9ucbW}_Ecc(v9PBC zV~>SB6&QOg?5V)mV_{DP#vTiMs@Z2Y#$bSB+DJr&;7#U2ZL zD!i+UJr?QXdS39oeAr`QPc^pO`cUk#u&3(%?En|{SlClFZnq^r_E`4ZS!c8GBx<-7@7w(4lpzi zXdGZ@9?&?z&^(}VfT4Ln;{ZeRu;|%8@2!BLmqT*|LobKs2!>t`%@GW}9GW8-dO0*lF!XYKZv_m!ob+*KXpqnxkq!;g zo;&N@wX)7yD`>~a4=owmF&KI|v|}*za%jh3=;hFk!F1MILpui3S!)gL7))oaHMCM%zpu znN1&=O&^&}ADK-bnN1&=(MLSjL7C9Y@hk@nz1({D0k+EN##Wh)tuh;1Wj40TZ8o;b zY;2YLXl#}HZfup=*s4SujIA;oTV*!3%4}?v+1M(xu~lYhjnC0YH$I2i_#9^AbC`|KVKzR8 z8FPo{tSAS1Ii9V8p_g0lB4O>|bhCCao3(@4tR2i|?cjErwS#TatR37(vvx3>wL_v_ zvvx3>wS(EL9n5C!U^Z(9vspWs&Dy~XjU3NeQ9c;Y$idLdt#`^018};D0hmn;z-(dw zW)lN2n;3xE!~onc69X`t7=XvY!~hCyFfo7zLodfOaxnCAJR=927=YQt0L&%^V8-0x ztOLHg0?id?9dIr5a-4O*cUMd-r}5nt=;b);fbXuDSWe@+D<+mx`0k2{O0U|x#%1F~9hx#M)a;Q}2UW~v z_Q<;L@|3(K?uo*1>GF4rZfuFdMCd*=QZi z(93Zy5cPtsZy-Rk;&h`~F&oW_*=SbGMzdlzniaFrteA~v#cVVyW}{j0I2g@}$H!<^ zJZ?s_(rBmAteA~v#cVVyW}{g#WA3bPS!nB97SJ9!kI^2PjrPcFv`21((H@zN_Q>nI z(H^<|MthWKr_mmnjrPcFv`1#6Ju(~Zk=baE%tm`;HrgYz(H@zhm*bo+>IGZhB!Py^ z=|)3lHX1Us(U6&qhRkdD0IY&2wzHX99@ z*=WejMnmTO(95ZB%+OqMRvyHqUgJ%`+Wl^Gt`?Jkwz|&vbYk%rhNk^Gt{1AM;E{p*`lA zjs}}&I?U#o4(Bn?beJ)BwGHo8vZ^XLD?0=GmOU zwdUCz_r*M$V>Zv`n9Z{}X7g;0**u$LHqYjm&9gaX^K6dUJey-S&*q%`^jwwvPCVls zB(x2BIo?46n`f-d<{2xqdB)0Yp0P5UXROTT87s4S#>#A-u`-)ytjy*aD~}KKa=e3t zHkfCuJhtW;E3@v^F<(BksxXiP1S?>IC zw|Q1BZ&pqeZl0CPZ>s+2HqXlC>TkQa&9idZEdM~4c~&mxwNDXdo|W_Xm}lk8=2Lz=^QR|=0UD&_l3)xc@WX(es!5M52AkUnJ#nY z!Tb0`&scNjK|MZwFxH%TP)U-{i!o;&c#h1OhxoapSe)$vnk(Mzgl#}Cr&yfxLodg> zok%xlS2&M3yCRTo&aN<9NpU zX>aUF>)yD`oF(J@<}4XA^m4pwjq=S|GH!!8OU7)@l5snsm*ZV)*r%hz%vmz=OQj4hbCyhOY@gO;&XRGN(93CW z%nZHUX1p_x_Lwt)qDqD8E^{VO)V!10WzGc3WJwl%71)b0$z8c=vvYITI*z zPsy6!oC%Z#_qWJt&IEG#=1d^7ITOfi&IB@>Gl4vA=1d@utvM6OV{Xm_GMh7jp1~o> zV$GSr__=%hY8aQ9q;oB0^NLAMtlqwaQ17O5^pK5DN~%Jtw{>5K`=uW5&Es)+_BRU>u${-g7IQ+86ZgT-{&DczfZqoEHsH4b zzYX|pz;6S78}QqJ-v<0P;I{$44ft)qZv%cC@Y{gj2K+YQw*kKm_-(*%1AZIu+koE& z{5IgX0ly9SZNP5>ejD)HfZqoEHsH4bzYX|pz;6S78}QqJ-v<0P;I{$44ft)qZv%cC z@Y{gj241HPSno`EY_{Hk@>uUid93%R60n`ezSer5OW16^&n2w)xrFtOSOT{5*wiW3^Z0E7Bom2H)E64EyfY~F|IaatdWj!#T64E$kTiVb?ap){zdo#ytRrUE@9h<6g1Z&SPIo?`?8^ z+?O`fdz+k&`;y+}&B}DEe#i$1~mwMLNpFd!b;|h4(_irakd&=drKFd#cE9`Ww%9mlf$46TIUJ z##rG!Sg;w-c((J{*U}tu9y4F@O!LKzIi>kx#$1yPFdKV_XFHF5E!i07G4>YEWN*x{ zNwPO)*ecmDv$5xRw)5E6(mkTlUvt02GuL;`D=kaXkv9G0Zuer z$G(>Afb*F3E}qF&nBl9)hM3{Q$j+F}dK%Am9{XCdW6opN>v$$xXNIq$dw>}}jP4U= z6A#3*oyWeG?nBN4-)1x2tDFvBMfWf>d>Gy5%}{zLYgz%Cd(9Z0E7Bwd_sVY}uQ#>`htroPg~-_O;giqHVVB7j4}y z+PWVTu${-g*1F%d&DQ;{t@~YD{v-k0dF*Q~f2D1<{FS!+mA3q00=Dzm*INEo+idw; zZTVYm`SS#9=drJ~)(dU3wO(jzz0lTrlz{C#_O;e}r){>@J8i9Z+FDN&u${-g)>^N% z&DMIYt@T=4@jwE$^Vru~@rJh9iZ`?sZ)hu?Nx*g<`&uhr(l%T1lD6U{ZN*~=*v?~L zYsGlT??Eg9KL=k4hOdGT1;dBI&w}CGY_{{**TRn@KYW|b@byTCufiGth7ZF!0fwKm z+0J8MYsJ`@FTNIj4r>+4fv>_E28IvAItPZIv)RsLUu*3VU~haa{2bO=lmlOdH5d#Z zhIJYYKWDR@$G+Cuu&r3NZv2J`8aN7=F%XJCA*>wMWDK&ey`vA=W`T z@KuO`!0=&+lfdwEHrsjZYpp#d{1smdKZjTi<-k|b4>Noi{f-%a&SpE0eJ$chlmp*p zGqsh|;j5?*%++Y7MjDz2oI&=O1 z(l~Hm&wRmg`k&x`)xRe4m5KlU8J3s=Y7g@M33i^(ulY9lGGDCm|IP7bqHJIJf5^WC zl+pOvyKC06JJm`u7asE5TRBHTW_Rph)pu_$=3fFfsfsI8GVkAfUEv4UI%%7jkr&q> z9c7>_Fv_kmXJ{B0Ka}qArBi+ZcIw>3jB==aW|U7q5_wQ3{f-&!p=+2?C)L4h>SS(| zZhowl?y>RrZi2zV}?JWYglWdGBlONOl2dF`8Nvb z3jYV`r~{1r^dHWLa!?1-QNF1o5z>s$!mqTsCK1Z;)!~#qD!x7|U0C^rRgSdEmsY(J zb)X{3E3I})tNn68M7=oV!B|@TMSkBnpd9>gIo7zLUQS0E>Oda)C#jvxD1+M1?36vq zmnTu%;8n4{eHrd~+=saM(Fe;py=1Q5Vae4JW;yIuSfcc^nA-*yc71Su4D*5N@4D!R znbKVJJ7&u3qHEymHI?C_vY4rC7wSMd)sOTrFw(gWlOJ_(+o&AW0Y>@w0dpGt4vf60 z1B^19I!0-fjXIEy8m;tYR{mvZt0^beDnHh$H`Z!Ttkup~tNpQ;UQ9^ql(P!yzWyS= zZyZogEVqZo(i%6^%julLpYx#XKbkws&tUE2IfehW)(EV9oDTnOtr6_6 zVFU2r)*6vujl($l{I#`4Air;oKsmlOg4a3Z$NFHc5oizP<23?nA2Z6Z)(BpIkOy^I z=~(-G`4g-)R{2=_xD8HU`d1yZE(_*{prc zD8rf;JZFFp^4*8bB}=3s8*$SAEVs_}JNwpCC)Rs6e0-m|TJB=>-|v~p&QxU1z0BLE z#3=lrUZml7VB~eKd6#^~eTA}+jy9k3J86{JYnG+FO38HvXUjHgj(qy zE5ESH5mx!as#jR;AwL@5PVqcVC8s_0?uzl>UFLpW`s6o}Ep>M0oi$&9c^tr$hZ%Y3 zT7|wVy4D&)VU4Y@#+>Sjp9@+$;^&Bba{S!=AMJt00RR5UPLP;6-$QOg66q4T0}nB$ z@+=T``r&}doIa_+w+Zr0Zugw~vasOOKg{1cxB!nsfxNH&@Y-Z6>rvm{mBD>(3cD`* z+Q#iybDl2EcL=*)``Qv=KXRUSYx|2oy0*yZ-#O2SNuPWE=vpg}*RIz}_gHl)i-ncP zzE)Z339hx;VCPA2t<@L1E@fY9jft|_tn6#8vHinqEgSg5Yc1PQcD?qsc3pOUJCB_X zTcmq{{j;C{6UN~mv7Z$a{w=XOe7DagtXTJNjn!STU&sD8#_BYdh>?BqLi|04IKk>K z=8^A3>@&zW`|isGdmn3Wg5Pr<DU)>y4lNcezWJ|a?IX`%Qt%>*6Pfj zi`!%NP~1+lw~F5np?sq^YB1Vj<@fEmP!9A)&V&7sRWH|pYcU2^JAHMa{m>g@k;hjD z{)=?8=R&`@4qrK_1C0Ha*>j;^Xb+cR?YX!Nlx3FG>PK`0j7tBXrnP^0n*vj%Mi0oz4DvtOi@ebDsn;JSA~DY}ta`|NI7-$smc@qkjiNP97`Di_UBL*4;>MPl0 zbu`vs)K@4|s%WZ5XFR(q`RYB>^P6<_wEmP3lV6>>{2;`XqqBVM4mIWLYndB{ntFBT z$^)SJLF=LVJ_KDpkZH4-U@>z4C zexY9W)(3c`RDOn^0EJO|M^$X;~(93Q`UU`TJJlm@3q`_C)1>Ot@qvFGClvT_nm(p|C;;m zub4*@v&j#trCMfUIq_ocvlw6O7f|60?m68$>6w^^4MK`($y{ zFJHQ#e)(cWLH+W@kdpcp;*0&LU(vqUkNQR9^N-li=eww1h{-utr+&q(F7&<|^-;f; zA@)Q&s9(z{Kga6SulVy_)URb`+$8mDnHf(>{la-Gif0q?eANqXp)+iLCh}&iFY?W( zqsykhC7vESB=VjvtFPrgDHa?~FEdrotNUlzCbnNHF2}x^Qs0bOB)$o*Dckhisq&U= zBc3hoERVH&OU2x{?8*1ZP`RZ1pt$nsGjUrtwMib=CvPl02OTBHOeEmQS8MRsc<$?CR#H!wtAR{d8hYq z?8q~xnTuUs99!tzFUfAamzh~CpT=!mn$XxuhRL}kNL}?e=liOR>{V;MVbK$3@+zY2 z?fxe7hR?>kJjEI^-%tNC?4vU+nbEKGL2Z}^HY*tGOJ84kL98!-vCEfYedW|ok}l3y zzUo*Y&R6f>VGrFueP0Jhtz;Vuz1&(qI<%N=Y(o3$dS8*+j97XTJa(q+t{n02kB0sMY)_`3pP_<{XCEDEz!s>`te&KT;|E^_4SqLj9liL zH_PfbCMV)Dla0A%&HpAv&`u@%1A+Uc>|8{EN+j+RmvgzN~ zt%g*K!M$)TcVnHS*eB7r7y4(Ypf66T9EyA4W=yaimHtKu%FJ8xqH0`YV<^fr?Nlf; z=0*n<_;61s?hDgSg)&V$70NX2R4CK5(`&WUi!#j^a+#)`UX*FZlgl*Y$z_`HV*IcF*N{ni~W^Z4vXDt*LJF4I$Xh01$!Dwm1!P%g@B`Dsyg zAu6Ln-%%dQMVTlM<)TcKhjKBVC=ccG98q~F*O~Wc3jIf!C=cbLO!9vU{dea5q(c9l zdEchce`nqoDfHi&_cjXsN10^f3iIU5`(-csk21;L73K+LlD#X;6UroeSC}W1N%pQV zPbib@U16S3CfU1!J)umpcQ57%Ws%_pEsr*1QYfypw%OpM7Et^vyfjr?l)-TJ|X{`xKUa z3ZH#adD3?uk$tk=V?3!mwtLJGl_#zHi0vM8MCA$VJ`%qBi26r1_DsdyFT| z58FN3N%O;Y4_l)75wLsM64?>kJ<6o{VY^2=$&T3WQ6|~Dgx#Y|vLm*8lu35Pc8@a2 zjs)x;Ws<$i>hC9sLz!epZ1*UW>|GvP|4S^&Bzu>W9-WVM=DmW9O0_u_Ws<$iB^T$% zqD-=PG4pz@SgV}^Ws<#%^mVo@v)bufkI+tGwNqH_^sPr|C$C3lJh@EMP7lf?d&hWk znPxn>Of#NbrWsFRji*36&AfA&W<0q}Gw)ocnRhOe?49i%?Ie50ymOgm-nmR;pVFFl zF4Nej#CRI}l;}IzJM5F&Y3!5BBzuQ_a+&5n;xdhW3iRFFM_eY^JMJSc6Xl^?w3F-| z_Ys$g@=&fb?|i>=ndUy?GR^(YWg^Z+|DAc~`<=@~ztMkZ-rL}Q=Q537;xf(s&Se_E z#APC`!91Z%#5I^Fv=ea+<_TpYu7Ta7orr5-_ZUy(m$*#CHL!b(C+rAzk1`S0!0u5d z;u_dJ%7h)k?onp>=bhZJdz5MXCzqM=^X6{YJ<1H*C)}`mlzB5_0XO-1F0=Kuv~Jiv z$~-N0x?uOFomh{!%y+9)a>4E~M`k_pwG-=+ubo(reC@<~yd9f zv2Oat6YHjLJh5*2#uMwNZ#=PXa+&aRuzNF}SU0&$v%Yhg@N?F@V}0i`;peP*$NJ7? znmB~Zgr9@IGxmu%gv&H>2)EP3AzY@3Lwxp$IE2f@x&gaKJ53zIWn$fc-JAOe@e-Gb zb;G)k5HI=eBg9KwriqcboF4Br7r8oaSBH{zm8G*z65s4v#!UYe^#7UZ_k!{#Hr0eEvF>_3*(5uTj%OtLg;%w-KkoIF6OI0SlY@FaXb^n>}K`B`tF#q;_b6H zVwxV0)SrJID7M!+3QZ(lLn9m3WW$PVIEHLklMO4f;TW=EO*X8^hNH=bHQBHx8_q{I ztjUHo*>DKiuqGSUWW%Aj?{WXreXZdS;1|H~6Yv*c_z(CIF!={X{(+hNgChUnK|1*d zb$Dv6FfjQ6MSg(O?Q6+zDDoS8EuNL)nKSz2Xa6|(ZQ%9TfVtll?o)F=GMoF9+1$Ta z$N9eQ5HvLgyzR+pb@tULPVcw(n0k@>6|??jx0=7V5?@>5zy{U-K!4`S3m2-OA~TsI zZj4in3NL5w_GDcc;t7;FtmZLKp|Ee5;bVNhhWjND7rvN^#ymb|gHQIwZ1Bmxm@UDzR?OyWKhKL@ju~f#HoTmji~Rms zW-~s_lpkvW^RpazRLvd-nGej_>7DcF8|Hqk6MH|}cgDvaA5$KWFArTSeAn7>;A`gi zvpsm$f!GMossDa<&R4>pLF=db61^V&$MYl8N2>dy1TpI0l#b_dbbc%nb-hM*&ZN`W z=0^-cbz_|WcE`Ali~OlkQ{Y57cP`Ali~OlkRK zDnI@{mDc?$>AsFJ_chYtSAA`Z-vb&y$?3*_GJiO!H~gwE9sZWt_+e)Hef%EK@}JW3 zjlR91K;NmIK7WpJ5VUr{uVNeotsTrX4uaMW&QIeYXzgI8aS*h2Fw-~)T08!!Ow&hB zKYnlld>XSE6JLJ#G-hi}k=B|bUC-YN@m*`JDbiX~d}Ge#n0aS5_P}iBi2H@HToRlM zYYN847eC8$*Y~U1^TRm*{ls6Z$fTDz|G4qrs&^i~$Nb*5F>30Hm7FJi;?ETQFjJbM z-!a41akddY#?St7@Y{gj2K+YQw*kKm_-(*%1AZGwd1+Ym{emfJPc};W`9EtMj{X!B zx9M3>9OiEN-r{l53!lbLK&ZBiZ8K)LHo4VCt$*Vgr{HVSXO9 zDYkc^%FKFNo7fu1>M}?FHhWoBcVp&H$IlE)66kQ)=dE4SyE=KkX}!_a@%tA?`ZQTW15%wA zL5sV{b6c~8uB|mrtV=Oip4p!zwDj?9o-GeX%Kf#{g)S|!(z`lGlnn115URYRRg*D; z<+{*YA-T7FtG0ITDg&zQ3n`Q(qwZL-ku2L{UI^8rQD5dh?}Si28ui_+dO1JUqfuYv ztH69zk4AmXtM6V)^=Q=R-B2T%>d~lgc+e-&RF6h|F=uo%)uU10jNMnGsUD5`3bsfR zL-lCXNBxSSdNk^ze#KBd3iVOHVyGU4`lw$qRF4<+QNLoS9uMlHe#KBd0`*b9qNyH% z`lw&gRF6b`)URlaAL^riMPvL>AN6Y~#t-#Tzm{P9P#^UxKgJLBQNKbkeyET76@u|Y zeblcIj34TweuZHCP#^Ux)SfSU9$Um^ma{%R#&epdX{cOy@>AxRfMW99tL2#ww=XTj zvh>3@r{$@)O3Q2=#_%_E7OyEP+u!ggq^~>>A`=&#%e?)1CYf^U31-*})yL0zQ4iI} zjC!a(X4FIVF{2);j~Vq)eaxtb>SIPdR39_yq57Cn57o!@q8_S`8TC+o%&3RzV@5qx zANK|IP<`A-)I;?N(=Sc+F{2);j~Vq~9FYh0U>w1y2jd7vJs3wY>cKdIQ4huujCwGR zVAO+g1fw2|qsimzJKEywJKEywySDnSt-fok@7n6SPLgGYO1mUXQ~COPL+ve?i z0po}IFxQxK%q!Twr(h$v2apciL49D@6zT)R)=(c9Hi-Jbuuaqlw&&}Q*v@a4W0!B& zYq!U4r`>+LUv_`(aj?h79yfbD?QzC<_{QI!7wf)AFpu{9+VgJPgKa0a{h%J$F~-og zH`@+v`?T%WwrAVUZTq+H3;TYt?<4#EvgQu=yKjDRzx(DL_q)#?v^8JanlEk5m$v3h zTk{2<>a$PyRG$xrPxbk5_*9<{hfnqSaQIZ856AfV=Ibx>W7d43Up^m>e);AL{qp$- z^b39y^T=xj#u04I7y9M%;pmsohx1y2aYTM=zPKKYBhsz;;(9QSNVn(fkJy^u1m#%v zkf2`6eiF3PZol0x%RUo~gFQa>xY^@rkF#~ZBv@ap`wRW`t;HCJ_;t#n*>RLV?)}e-d+oWiV`DpJwqt2K#Lx_*n0|luVL>&?7a#05WYQ&y_d1~IQHJh-V@n-C3_EL z@2%`T7wW+{VlRe06UGsHH0-4?j@Y|lkA-o>o(_92j3f4X*pp!#u?NIn4daNtA@*<> zN9-Bxd&-_Ko73gbEKeV7ASXS`96EB)ccNjME^^GKY@wIKCyJ}12FYH(W(oa0-*L|` zYe&ifN7IEq7>jrFE3d**P$D-OYh2+vp+k>)^W~*9#p}CmMH`A-xWT6p2ftZ$vbe zv-d6zc{5dUJ?*;+vf}oRA@fB&-6?T)d9`TbkaHb7>O`BxOO)R5Wo2)sdK071|1?zV0c}*o(9O{i>w4&)v+Pk})xM7| zGN!p6Ip+->FyTe?<6k^F-J(J|tYE5`6o+%`nzL)^?gKN$)OqqiC7S=9-r6NwOtsQW z)YWJGbhXP_W72fUrY;nV)W6=!5cBSVoe}5nMCm$lZ^Tsjp}HuVcew7c`AKxeD_cbN zTfKDn*;CPd1|^khMJwIyi&fF%bGT*q`)}&jcSlCI`}!?eZ)ASG=RvOM0$;R|BgXu$ z-fz@mX_kP#a>SffYQ)4E`G2l3Le4BwOf_8+#NUBw5)vFsdRvG+7xsMF^JvenJ@2+X z*mh#uk8M}Bz1enX+ox@}wmsW+Zri_oU)c8x^(+29vhOeZzO(N~`#!brU;Dnc?|0h| z*#5!x8@4~O{fzB@Y``2*n}=T-Ay*Cx77OpkhV+=#U&f4GAcnL#67pm7 zjxx=lYhvH=+aZAy>&vs3vdD)!l7?dLNq5C_dF^NaIQVVg-(my)XCI_{lkNG(!9Nav zxeeHRZPG{uX{5Y=Cyi8)M#@YYsUVG%nKV*K8Y$}uq>)O}NSR3^m86j}+xyDgzfKp+ z;+!(S-n>h+xD&+X==^uY*aL4c*IAN6J}P*NuMJP!?Wx-`;dmnx2 zmr^q5xl?9}i>2l7&F}0$IX`+!$ovIUaQ@oM3d)^x`ZAx{5iEadu!8w!l?<{+^0WU` zW{q!8iyIj-YLwGC{UWh)etzaXrE7{tPl_rgCW60x1W2k8ic|2(hHI1P#W2k8inQ06)jUh9Q zp{6lpwlx+SLrr7IWzraG8p8-PhMLBZ^V1k=8bf9pLrr7IOk=2N4F9Q28bd{6D9sou z8bf9pLq%iAOk?P!F=VDOjG!@OrZM!;7&6;-ZfiugcJyboufHk=u;bF#$##tWI@#VM zyiTUEjo;(EPPX@GuaoUP=Idmf*?0aq?@9a_PWCLlPW7@8zgO{}$XzG(6jcJ~TNd=s z&;P!0$hB!9e-9b&1pH4J=lpXFys#4I{J;2Uo0^@?E!y7fE>EPMg};R<)~@a>b7g8y z-)FloR`+TpxBvRm>sgXRo*r9EzRHx^d#*-#89BU!Oq-&+Csor1a(N24)^UTa$N5r_YeGx-W5Bmn%(}M>l$%+lxR1!mt5OwoEUwokode|C;3=?Bf1S= zFT9yXyJeNymF2?gg;cp>DP_&Vjb&}uFtvEz zH=_5^b}}f>5>>F%Byr$CSDEZE#Xiqci*0wi<9!yf_?esE0W3P>y13T-l;`r8_ImR3 z2cqUTB}BQR@9N;w&qe#RABwTto9G);6U%1TR*O`RYU|EL0%Va@r^U6tQa6eVl&9PM zCfjRR=NqZ{DYHRMO;{kzkY%iCbcRP*FQZSkP ztypTg^|?zwj|!0T;RVs9w@3HwkXRnvu~IDlu#PU%?5P;EwyWq+w7DL7_LfMUHi_u} zQ#)PY+D~HE;}1Q}E_Kv)-@!#rW-3f`t!XKIPnODipt}&ir6-76Vz+B?auG_#QGEY#DfuS^vL#!q2<~W$^wR;_A`zx@F2_vgnst<&Egvy7QEz^23-C@>piJuD#my=2$T}M)sRyIai~IdL%4ub@s)luTi^$_WWWz?2cjT9n0I!2hoH*!BJyhV4BWwt(lT#N@Bw6TI)N>8{<4x4YJa6I7B? z-SpP>(**ehm3(6-opj$IK|Vp;kH8LpUP@6r<5LkCZG3=tFBIw zFNeN9$yU02>O^|(wF;_lbvyC4XeDk7lzkMsl#01e2)a|Kdo*Z8_4(0=(W?;omWvD-)s#3s-n$@ z4mPIqoA@_M*Lx=~|BarxXGZ8}trs#k@7G_4#9n8fk*cG9F()gRGbNzDKIAULoaLv| zdbp_1T(MSGU9Wsc=Dts^slC(sGxu4tKt1`{`MW|#zs{rf>~3GkS8vT7PWrASA?n+w z{W$-s%1hLe)E$_cj=8P!j;Y7oXjzaRnxzzT@q1+| znD<_otUkUpjJfcsI;vk#6!V?LtGrE4I6SdbE>BWDl+&|4ZYR17?ZOGHwyN^dB`4Q#>)+u2fxfD%Wdtb=pubri*v(RHqHCYj;%lhW6k*3v=yNtG6^~4t?tlz3N-Rd}3)q9WW!9`Et>k zdd#Q4@_6pd)J~^Lvz&QFOkaI*NFnB>?MEbN=T=>VuMNtbSKdEYnR!90aB27D|IcjS z%V`=p_tEqhg+;2deI;fk`~Kx3;7VKOfND=g`v*0c)BX@FYqTiH+&D<^^+cS@j87d5r>}jlp}g7TJm+6GwTrAfaXj9D3d(Blc8h&e1HN zobd+#-H=3=T#4l;i+VZvyKfVNR}Ev{bGW`(v}`2vjGEtg>^A?ad?2tT|6LM%2g1*5 zm46)k_V8EQfE{0z_)V$7<9g~2yP8(?ynkMG9NAI#Tb@N+YjIzFyS}MT-fE`Uku#C* zIqFRvR^Y7Icq~9K>k+O!yHd$0cQQR8D3w0_vs-q{9iSt|oKnM&ODTrGP(_DKQEM+X zl3SbJR*yFYD$k;JGF64sYJJG35sf!=mD9f5s*VN}68o-pmtAIjs*-hIBw7{fA{Q6w zq$bt5Dhkb`Z*cU?qP|$4Q6}#Hw%m1mjCX5_V)AI_ic)yyMyz>KT^0?q;h$hilYBpUF7Tw`-Er97!mbtFZtruC^0T`oG9O}kF0y=qNh;BePZ?5_vP+e zS-scWToR%0z9+Xmt)Pybdn8(vXec}Fj!{)-CYFc1mE^&;*HzO2filaKeDZj@Ogh!C zfpT!oq_S^?qB?s}QkkO59`V+TYC7oDZ{o%LL8AD9X1Z;rTjI=yr=Hoh-s4z$Mz*KX zzPQ@v?P=%nUV}6iK^lu9jYX5jB1mIVq_JqySV+&guSjFjq_KENW6`9sXwq0bq_Jqy zSTt!YUeZ`JX)KyF7DXD1CXGdr#-d1L(WJ2?h^0?o+{Nits}72o6#4__4{TCWOkMg| zp`6yYV;^<=8J z`_PEg$nbK`fcFvvw^Qu ze=n|AxE9g>NaqCiJ2VHs-~Q_~|JUuegJxgnb++HmZQ^b+m+E_~yUsmjmKZT1S{2*h zSs(qfh1l-Cr%rBerH7nMEWSFDT{lQqTVKu<ORmI_r})6Nw{5Z>dr_TI#fGMu|+1pQ$~nmOisaiN{xx=oH<{=-|6g zMa%7hdgAEZIw&NY?0zp$pBR-yzj3;#%rh#f&T#&q>X4Y7C^6S_iRnO15d!IG#L}y7(D%ke8z;3e0wTGf$`wAk%#MU}Pk;F16({k}~ z*}D2!OH_T?L#DmmY{%jsmx-4>`pBzOZg@6i8!rx2 z>@5#%8X&sMIwE7YZZc)gtzvMM01=(GtvuS{p%~NleNVHl4P@i{ndHN?19qgi;E@N` z7LpIV>%5`Y+%oXFlo=`nt21w;lcOg$kU#HluX4S2O?n%cT`mB@LzlYH{^ zYL#we8!@?Nce#AaF6AozyXWC|-KF1u{(b(_Keqm{^{=7-oqHeu8k%qo-B{+Xi2Nm! zcr~r9u6N_PDAfN$v3pq)eeYBfIkb-!dGc4+AI}JsCt{w6VxH2vY_?>w>BG!2W6faQ zvQ2>8maeeuwI;c)+CP!(QMt0z`!A?UCmx9nl^V*F^J7%DRaZnl-A115-Be}MC&cRM zU1i(qJG{NxY!lfg_L5)BI31Dg+Cs64{(ke-!kNVT+ddGxXZ4bYc8wKr%d3ea3+Zno z9P^6R%ae#X``gGpi+&MtYM5tXwT5!;!i;k2>V4Z6G^{N9J*IOMPiJ|Xlq@X!kBX38 zK257WD4j*te^^(3e!0GS*7sMDD@jY4=*Mv?uJuk)d0+>5e{!^%5jsvR&eu);Slg>E zj>#=0E?^+XaJ{RA3cK+*U|2X(<;IFiS3f~RZ zD6eRiQQ}-K=e>!XZB}^7r*?S6@O9o3E1W!ar+=VM7VXCQo76q279?rHd~0|*9kZ)E zbJo%&bc)hJ%$d*B(=pS3=5zRqW^~lW^2}yFs0Zlpw;VZZJ&SZHpQA9p@jEqKj^tBO8}rF7|EhSzdxUQN!}O{-CPN#~Oy|Drub|8~WLs?Ku6?y(g+;e&?N(ba}p0JInOs^rs)~R4WJdW6oGBMnzt7-ZAMp zc)Y6J+j-}uOsgj9R&XTeDU>R^dU4Nr_hd`wFTH!8IpgLHs=uReHHTfN=Xx$o8NvCd z_HzrnUxNobW7{X&7;(3uQ&;Ojlf>el133S)5_3fD{e79IRR3Iv%uYM^71<>QuI<3- z_tM-HO;UY#a0A zRlVe#iDQ|QRUa&`9Dc>`O&og}Dcc-P!gDn9Vw4Q$pX`nv?m*;&rq) zmD8^YtJ>;}Wwvl1x2Nu{(*<>5e!J699hzD5_~id-q%Jif6OY@_(^0y`#QX~5kZ;!r zT{`DP<`bg_=@hBfGAEtcM{gDfnQM1?U+>NSEpwtt^zPvW=Y5uYy}Bg07iOFH?*_bUvB*RBV~(yr+||ZC-ing96;IfoG)5{7EwA zrC+s>2ghlFc0TXcQ{TG>@S0uWA2U zo)Wg&`|V?AZR%I7w%WPeS)0}*TcCnlJ8RQ}G2f_wO0D_YqGOZjX9Mao_e`5ZzgM9m zbGqflbm&&6%`=0m>QkYw5!8mSLW@sSq4l`=*S2`WAEFxAV)?huSc& zDfzn?lh%nRi?>-NCPz5;?9BT`#b-bC;XJ!KtX4X4JLcH4zp4tooOvwpGPiENwFswY zN)e%Nf0BkdMXjc~(aMwDo?6+Rx%IC*m=XN@zxiH&9v&wCAOBc6WARsvgX1&lyA)xq zb2<0;sS_pmTR5l#XY%Opy7T=@|5r!mtj4^3N+`X{7|LwYn2{IP;97i72W5d#_P1w? z)Az9PZxqr62D5aMsgHPfP1=-bS2${1oNHsu?DA|O$U*BQ!!^cZ_Om>!xlI@<1<^FmHM#&W)Hxejk!uVlwLEbgY zWKHHJ%RTtST$!3)+Hm%A#uZOIC zWsVwpW3o5Z+WzwXfJimtNITE*rGsVL-%6`1qvnh2qkGHl6JB@=sATf%7Vq#k3dXGd zjGtZ7vszX9^1K50Ucv3F<5lrG7e!FJ)-vSh?W$es>7w?@_Ojb2C)9$^^N9IfI?L~~ zon~KGWBy1D9({k33+!E4$6M>SxvslwqI6DIeO0#e_sddj8m0$%zED+${SbEJNN+tp z?wOjtbh4{Qg|_TNmBuTG!IavsKbRy^%ir){dh3ja7}=kBobsPPf?9P~TjU zTr|9pRxd4GS6A#XM!2@5(sk2T({Bdt5ZiJj*Bk3r)SC|67Ri?<)-}H?rZaC(DSx=~ zt6CM9U%y>FuS{R|hH5k`la`H3O1b8|3VWVJuXVdh^X6)TcKZ%Fyqf3`CiyC2x_4CK|^yN8Uh)pxUSLHryqSM#dC4&2GQe%>~(j_||5>0>p zSna*oRxb-VAuAt zo9{iniWLw~9uL#0l3(_u8d*o^nnQKs)^|M1uJsay3k=q!1LMTj@f~*5dfHcydB-c_ zn%404rSF?e?0857$2IUSJ=k5R`QjUqp?9$NWsYw8%++tj4%hk}De839j}n~~OD>n) zu`>&4(T^T_0*;>ZT>El_u9q#HPJR9>vGYVF-MZ-Ss`B@jM4IN6^`7*3^|X*RBFWdK z^vN-2Rh_bl>F@4T*1K-(S1R$ZqUM)1^@TBS=vPy2iH~-a(GM@>&<%zi7v%=g-#vYG zLrr;_O!jVHPB)ufnBFbkEJ`j8)8~GS5E*v|c{BAKu0zVTQTYp05?6)|)WQ8rt86XP z%bZi*)@d#*_m;1fTE=B*s+U}lo_psydDb?F(lht;SEF*&kPq%;)`vE{^!~OdrF?I9 z6Md=QB$cL36S-y1Z)(V*l4`=4V7cIC75&4*A3Q}5EK|2<_0jqI)$n#6Use3}Y?!XD z@~RE30_2C?-q96CysZxRE-aI!D62m@{e|~J#tGua;(*H-o6b{vcJ|XPTXt11R+N_`N4xcr zGv(CD@bq$N)Z4mipX1)HH9i&jOZ3-C@3hfRM@|>(yBt+lK5MLp7d<0(uh#1Em(}&+ z%E{%*wChx^^A)sfOD=h#&tf$yRY9Hj+Y&NQ%PFdl&Y`FEqWdEIAhq-4Gu2>2OBwg5 zgj%%ym^yW%i(I=tiJFusR#kt|M}82ly|CRIb@qnAe`LGeS-<%7uxCU1GpgF*4!T6A z8e&}SlL~oqbSM;#JYSwVqpGa$D2t5>R++++==3j|$^l zTu&SpF3(+^ug-o}MPL6ZwQPKPopQBppxe&7EG7)o>dPMQ>MXP8ivCrOs;Q+q>Ci9p ziVD3>tI9XuX1|f!n^oIfpT6UU`!3gKzpBjJTQYA<8mNCv+?4sJS84R0$>WP_N|uYeHYfb*Zgx=jprBZz`yDn|NV34 zU+-||U>)(Vcg{Lxt;_I}KL4-%>)l@$pZMcUf1GKaCrJ1o_#Xd#$IqDlmVLn=eV@5S zaz|HRP-%nb?c&ZesT?Vbi#($oT|M2mqea=BU3rdPlsGMRmu}2lbwzr4aAY~=#-mHh zPCc_SdqV3c;O`DQWp*B!Pt0rYoDW&zT__s8>cII!zr8MW5=WmOIxnj{cE2>IXU$$F z!8fu0sQq@jy|1*{&SQUL-~RT#{Y`%RTmAMo{Oxc1+u!`R{}zD#Hv;}$^-??<|2GT% z4BL8w&Gr~ReHzUByJi#p@#?W%zdsnHRs?Up6i6JbP+6uf1&E#d(fXr*|DW|Lsa_OHDo~D!;kj zlsRp5YFTNZ^So*E%%kF2n<1ROFL;QMZ#wtFPoeWYg>O2~n9{$u!&|Pkb1zK3GDhV( z=G+UFAD>e7mpk{u_*dz4qVeUq99Q2GdVirH=3?L1qjNjX8Lce?JL(6nPr1!0J{_PN z1SVsyaU@c|C?CYn+P?fIN@q*kP+{D*%p0aZ&#;|2uwE}cI6Ocj{e*0#=cRPc!{mMW zrXE|;IS=zdgy_v*IeJB!-LI4@qqDwLJh(mq+xqskdqcS1^W&oQx&Ou9dq7pSGzr^e z11Km#R1{RA0R0I}c+l`=T5D&|iqd>2LoNM`R0fo58J}8~6$G#9J%GdA@?2 zTMnF#cGra1u(>lTuzSxjz_%;GPL&>36J%KP%8V}d7y6TtrfxLS@&S|80D~~P?eS8^ z@48H-lJ?NTB!{IB+CBxowS2|+OiVC5a_Gp)|El5wBX0}k`*kt{nbaSsvRgOYCGWtl@x8Azs}qtnIwllcBa*Ls*`$rXJL` zN{Ea5uINCcMRF|tNr(?^IBDs^j zB)0uIo~36GR-&&B>=;KX7;|S}_F$asGL#-VBExv8lP{H&N!(0BmTorP9#%C9zYS71 zf{x$4Si0t|7LcbX_+;z8T_i@kg!kxYPWo@Ml`Qk0;Z6hlQr>1#^Q>V1aA(HVS)HM* zK9I5g`3B-OKc4ZV`fa3Q+f2sRz6ONrlNodOyc9|DD^f6vm#5Hj#JNh4S+*>k-LvBz-;q40liw{N3Ifow4z>U`uk- zx8kNrfxx#nc=vmZNgu&@*V8Wa$njo`&)gBw#cx|O?m5znZW?`>*+y|p6kVnh#MpD+ z3>w?y!F*f&cBavWaUa;bU)(p94hvn4eEF~45^3Xs$BaKXh0@qQ9Vnkp*1OVfod+{k zduaBX4@B{-b!mST69(g5}*6$QzVq0?lvO%1`jDOZE z&R@1w%bKyL*py1jL~f)oe)#CPiL=`v;PX2a*JHtIA*S@lvyOE7_I@n=i<2d7|5253 zr$P^U{Y(|%^N$XWpyO^YVEpX*)ZgwV>r?Rmb-y0(=c}qP+m-6>|L#6V$#>*maVEc1cYob;xuv?3>h6E?Jtorc-Cy?(8maE2y8Dmro|cYP zg6Mzs-B14;-n-0lv$ z%=S(E6HI~&%h~!TzZUu*F&}Hlue)-7NXa-`KE9Eq^Rc25aYuYyF-zy;$RuLP_%xRO zN1Om#L*~nnjANAaGfKwoNX8X#-wWIey@);5VFp_^9~URN=QT$~`bbBbw!D>U|P7C<{JZ=XY)B)h9+Q zJ>1TY-uiNdt><6&i=?Y2KVv?QEB>ie?J+PrQJle*< z@AguxE)&io=oYXO%Z?@rzb#mSPOWAzZnB6*+vCZM4W?V+S*KLS2YT0wH>?)?Q|DJj zasCtG-QjidajD>A8oJPkcE$|McEzP3yc~2t+9nGu_DHg`}Kz7 zkj72`}VC-gh z#?Rlihkf3HoZsqc!HK>jS$gltPVn)CBjfRPy72OVJ>w2mhEViW@C~iG*9T6n7Ib$x zW)R3E7_mI2+w8de@;WnqFYgTF3KWI(F%#fT&}Al*ier&be0d(@ZJnmU+B#*%ld@8v zYM3?iTTLrYgR{DsHhleSKBmD*e@|vtrg>@LAGw)vzC{}BRTeYuUzZBoLo z2VG$Nx-1nWf|c%?yuw;SW8J!x>cZz-!!ln`|PxvkWq!U8F5YW>D>Rz-4{x^w12vgTUv)uXM7|K zd*Mvhv^k7rgCn6=l@l2@>rBI54gCixora>E<1&| zIai|y{Gj^te1iAyq0;>cuseJuu^spveJVZSs?kQ$&w;z6UTHK8vdbqY-haUk<3>Vm z;bCH>B1bFt4TX}>Q$%TS3;MiS1m_0aAZuJy=&6wd!T$bZlGmagZF{O0xP16Xx<1vQ zn%doAREZq8Rcg^$TRVdxv;?iw9q7nFE$H8(4J0h;K&Pgu!#zhea0=F<*46EyuYP-2 z6rw?MG&LZtzCDB&x1-~qXu+qV_AvChDjjan5#;-~2fgiQ@n_69IFL|EX51}B=bPS8 z__UBbb1FfjIsVY{@ix-%{WylW2SN6gO!9I3F)S$yhG5xML_hK0oVF~I4`@s~li>&lXrHhXa7R~N>Q~c>r9PQD2 zpm=<30S>Z_q-XZD5u24=VS7t`huIqPdrSF!rgdHSGj>f2r311%6YdgRoOUS-w`n9m zUBn$5qqt(MSBQb}dvwLBHTAejBM_QhUxY4e1ibvroIdPs3>Vt2!m*+e zR4HE`I;`H0Bhr0N%;^YbnAvq*|ki39Gn0lwALoG|9TwfkpOy`4{d&~T920; z5oIL$0-O$cW^-tJkeT&113*}2dX{9 ze2i9Y+*2byUdy;}Cf%W~PrepjD>7a;g)W+xLzX&lR|coN?vgBW@@YFw>>3J*(TKen=bf8-XKHA8qi@HMsT6>B6)dB zmzF*n1ll?|WO$f9J?LT%YA?2t13D)3P3zv^IA#y&6V;zac;6+3HtnFDwi(^K?=9(m zQUyd+1L^T6N+A2`4Kd!NNEdPA=y@g)C7pMv(vo5ic)U?gTwvoxZ+hM(jyYR!MO$~O zzFraXr_Url`vU0=r)us@UvDy4JCa_XaG4C5w@CDON)%O4Dj;~(hD53)(5KJll0^z# zN!40^x;gAVsod^MVC)!r>f=2UYjB8k5W7>AF|Ua0?ER!n-HnI{x^m7^9hPN3g;A4XT+LA{>d@ThbZ8V{m4Vn8U+h10RgGYcm#jD=|Kb7WgN4}Qp`hjl{@QTF9B zY!wj?k#`NzyvK5!IzAryMjN4;=W-l7G9G$17-8>O%hARz9)<@RT8`h%;z3W{1cM5e<7V@Ci0N#Cn6(^rEaD-twF&wrEyry(@v!Nh zF)nvmj)BACK_$Z&U-Vv%TU_E{imx%Y^4o?#TE~L6j3HhVRbu^ttK#ZAarGRN&;MBWQcejaFzsCdm`Z@J3Hx zS{Ai|l+P^3Zrws@!ahBcPAgfzcmK?3qhEa>KQ{RHyl-KZrNadj|! zd^r+_IbTAn4WY1Zsw1x1eHO=G4}*s*98fXz6n@zi4yP~Lq9V8U;c68DJ025kJWlag zW(17dB*KRjF{~;Aj+WTqc|bI3ihyP-8ysPUSo4J&pLDiC+5Lzs?nMCgw?XYq6brXU zz>Ah5?5=te=Qu^cW*vfe)>~Z0 z;7OtIt(_y5&aOa_T?l;M?u0$kE7AK-5KO3X#kbyf(Q|D8&?RG0qg5U1xcGAG3VtYh z_Ypg^9S=L&M&e#8IT|z9142$u!;XuUX@>bos4<<35B6zMM<07=W40WP8hX&|hXbHZ z?+rM3T7SAgzB}A@+==V^4W*-xD1m#zam=&!ptiGbkf*L^aLPVEn!IWSIa7X>J8v_D z%GDW@OH(S*v2Qq4xmO@k&#h**v@YD9*%IGBG{0$=&-V{!uDMgOxCMzj(3W<|8A*HW zoI?uQDATWZhtL;KN{HJwMT(28DTcoxH!XgmRjL`SR#kyw-3EN5sZV`EyTd7myI9n$ zNjC)!guA{MF#U)k-R7M|vw#miO88P6r!5%+pZboO#7_hoJ6lu~{ zEKG_9xpgDZ8g^jT=_r_A?}7tDcVdrslVDKgX!NV!gS&r5g55|j%)GH5(_c-5j;?-a zt92NQjz+-T>mj&k*KyPc42NCkC*g!7F*d#q1sRPg_#mZBjs`?3hXXWYa+ zL;b+M)$Ux@Rj zmE%g!08o8BADfLYp~>Vx*t2pj-kfy~qqhaYqc`c8u#L0%`@x{$kcv77D3)~&g*PeF z@l0tkR=9>i`k{EVdT|V=P6>yJGSRqw&|w@tKLSE#gk$W{186&MBD63KLY3&f=*QiM zTxH^mdjoc(%aBPBoalw=Yx8l0LKMu>8iTD`@4#34qo7c26fQcs6_tla!==!X=wGxM zH(iMaU#$`7_8}MZ?P9>V`!Ku_nS&ZTVqnWc2lUa+M*2AhLPpr3tLjFK5XC~<5WrTJ z8}Rs)SZ>@U!pIF-7@QpoTejO^s96>&9OwGy^VWFr`+9tLHWo7Mt#RZx?hK_1v9Mg- z8e8|u!WN~mAZKZfAxpBbV0SERIB1OpIvdbxQ7p7fx53W$HlWx$7M5-m;mMU7(a)lwc1jgHPbx-755!j4galFF}`GEvby<5SVr2C~BH3($@J%(Ss36kPo(HfbIUmp-GUm=k}wSD@}slGWmu< zUoH}5Za-S(8QmQ>a?^?AzBx(e_b_hg9;jc#?O{B}?P2`X>#AXcIXAznm#mz9>&Nnv%0Brdl=_fJs>TA9^d*_Ka75U zvXsnld}vV0?P28iOo8au2c}YmjW0!Vi3>z}r786JZaI=Z|Ac78 zt(i1)z9#8)tVY!1Vlq{)8bq|CABw{4lc@gKD6+O-uSiXQI$gGA2iaUVxTK|3JT+gW z2j>R@-5wA`ZoIO9c`n^)i^-W}g{c#?=_N}e)*mDvoF>4Peh1Ng>N#Ss9|8xhxjF0J z8|0EqIP8->Ena9`P5AhLGnE7R@iSxojr;ffMJ^m3y*wlCEniKp4-bJ$UIaJT-yrFJ z0bo?L0A0(k5YcsSsNAp{#|NGxG1}um^W!;G%`PQB=Z}Un<_~bpj}zpirz?0p`GAcN z50P(MoZ#La?(D;qedJoABXsZHlD>Phi#XpI0^uK2=t8$VQvbjnMn|d9S4Xyy-D~V1 zXia;%%W5mR(!vhX{nV+^r!C~2lO23N*`DUsZzaQ`?V#8Bt2}fwA@5 z@a*>sm)y*che4(LWATUh zDw2671cq$wkE&@mh<5KFu-+YqcF9+X%&75T-J%3@^UKI)tMTyDrUW%^lyR~e4`IiO zQ2$dI+1`Bu__`d!Q%R>t@zV*AzUd%d2s=%JZhM2sy8z{i&Jfk_J^)j;r5+ zh(Bz=$KDr6Y>q#SYFvRok}i?Y&jR4?mboaCc7@otivW|g_r#m;Rgl7);n3+`w0M$k zHCcTjoNL#7v5vTk{Gj0=7q?D)#j%P^IS~%$^R|i4h%3poW8rZ9&H?esE|ug+Q8>&f zE*9q{-6W1>;h?_$wAi@j28k*U2d86f6)hfp;}#jht=TWF z%NIAg)sQFs!XSZGi1*#EA&<9)g5kl};z*y{M0s#1EZ!!ALyK;c`nnL%pV0y{f7~XA zPK1EzY-KFht0gP<(&ljZ_*t)HE0=EH(HG|Lh{9doPf5c15ZL3@28{!1$>!1B;p4a;C3`Oq zrPU9dLDyNEmOZ~GT4gj6W*KW!*PxrCs1~m9Uns%pW%Qxef zL*wCqr4IIeE<=y`^@c?jJ27U330-QW2W|xy@v(Mq+C5$k+~ho{-3dGKQqmC|&gfFI zOoj$!=)#iLgK5vW9NcqW7CIGd!fGyl!zET3DhfU6^2xWY+URIOk2byO+y&2ZzP%>+ zUa_V5a@iO$LJrJ7?!ydwC;DoIG8lC5q&_aO;^o6NAf>)5Jxy9r-funC$(q`h9mQ!L zUy19MESz<~olYLt8g_+^qk-AgCwO~1WF@cstKXBdV0%(INaY~40jUj0Z9r-RQX7!k zfYb)0Ht-+Wz>kTv zMG68|vHVLHD}ZIe5Am%dUeLYlD;a7Zh3{>~vAtz~wU`+p%1OFkQYr_j4M=T3Y6DUm zklMh1w+(QyKDhp6J%2tDf5-8EiY3mU#I)jBKNCwOUcH0e|q1?Lj8P_pfOyi~>1V!jUi8B=77=TpWz9+wc?1zH&X zJ`(!TY;vt&Eh=b7fM?2NawF&==lL3_TCqd$&)h4T9AixFR|1%S=|nbeQKN1<+@R}ZAJVhB9-sB{f%|gH z$oeIR@zuK!=sIE-sg;|8m$-8ZHZCe7lf@szqRL2+tdFD&C1ooqb4guD>PS*|k~)>t zwWJM5K3B?d^xxYmClm6={S?2wU($4TX9x1{m*3o&U3@=t|K(d^VBd`lTj&SV#>&9B zFS%sbNmq!{RD`V8b>xb+C3I`61YV#8mo>XW=_Yw7HaCNwyJW#E{s)<&GYnQaUL+~Y z-;l?yZh0uLT{AY;2r9jo$b|(zJowH@7%l{Aar0>-IGN zHLKh5Rt^>r}$ZUFIH(MY(y4jhl}A!WT}f$Qs_ z{jtX+y<7pfz78CyGR!hj0F)t$2bvQ$Z6HsgL$+JeN0!uK1!z%hzht?$0~Z zoH99jUDtvh?ACb((8k>gMR8s1>40a3@Xl_&C}XE7m7Qn>^A9VMjgi{)@OvldX*i5* zo7s$KxHmoMSUP#7b`hU<3<6cBT+%CQ72fxXfOya2WbCWn*!wXz4vD`?EZ&V0Pu@2X z-jc^ecI9HxdKv;XlRl8xLJ>LF(+3_NZ6>CRvq%f|QSho!9`O7%a(tI9tZ!0;pmFkW zwvQ&cjw`y;bo-JJeb<+Y{eM+MdZQj2-@LH zF%IvbLrUL8(jl?eae1MN$j4$L1$>Iu*#+X$Wx>=e_!EjETv4=l0`0m&hL&&Kf_FN( z(h`3KnipGxjfBwq>PocssS+JIp%-1dU6FQr-IdC5XDx14m#2x72GFxn-|$=2ckI>5 zk$w$2hk>bY(K5-CYWG@+Z#?ednzSHl=+Xy^axS2LT_n|!^AmHjLQYnclhto_C23>j zM@n&>Ni=J&uWH!|9}grjWtHgR0hXlNI2_)uK8H(_=aK0uvGDOn5_ZenO)5;| zVCPIK&U|PKFTdJpvmc~3KFS+xbbRs5@qFG-^!~tjMGw3*JwwH%6|Nc;*_>*X; zDM9&nO&IRc6};3HA+)HDg!Z(A1`ip?ex6Gd&bmTa-CL4v+Kt>?&cp(IT$-89FAKC6Q7^YFvQ6h9y+QL?T;FCN=FxPo9HX5 zA7W0c2MmH;2`$Afwm4D0!8(8rpTsKOzO>)@FXWoo4G+DZNI&;EOm-|7DK# zq}t*TI)=v5oZbPVjJj*++#`Zsx40mVJ^d0bq9@R%#8jNo@dsvaA4bpSp2r+>1v8B-D+a2QmB}e++9!sNn6j8G)EbNrsUaSd(wP!bzt9nZjizA@>d@-5kt&X+tBEitOoJ7Bf7Gv#1xTbQK@G_ZlISeMe zeNXQ0uq1YKeV|=mS!n3Bix~DB35!D&;fUQkl4fcFG7XBLo7xc$wdxG1gXAH8OMh4u z^n!ICcv$cRNXMDt|`ctxv`TWd~|r=O$X(h@(LPxp6_ zw$X90Df@+ZO~ZVWZV?OBu8Fv_(1}EOO$5J;2#}>g!qIuvBsd??G z(Iea9uf6Ty!8ap%wC_T3xwk2hJyvu{mOS?D)e$nMIng%M7N<7ILLeDO^=p!F)#q!Z z^YZ}OFLOQWkIo^MKH>EFyh6O>>p~P)MbcIQr?6V>m8kP&j{n3?HhemSGwbY#< zy7z#bP!ELp+9Kk8xRJEz>IU2fO7bvM4(@-mfWWsON!xdd5EH^jY4P^Ul17dFG2hwk=bX*~|fq#t+NcOQgJ>L+MTy-)d(;u9# zeIria=8~;+3@km*onLzbNsQ+(7`;>x#?^izE9Vb@sU5ksj8IW#CdXfO`5JlKkT%+1c71mb&jC>mNKJsyTiTde)OHZ>k`QDG|{21d7tvpWx;L zF`#(10z*4D@iFi_`Un5}&;h@HkwIw(aD}_8LF9;PwG8 zT}>8Mc({Ycg7(yO@af_gp0+UUtuftTnIV=j?hWl1+0e(&+oFC4P3XnVE8|9w!eyFG zbY&7BLP}1?$ z|DN%cw2%GQ^s!PoOXV!N?k8PamaZ*J*OvbpYs;jfPP(=%UF(*v^Z!k4K>A&l`h2B6 z-@l&E*Qv!Nwq7Ci`AX+j()sn@&juvF%Rgr)piWve{rq$_xgKDEUV$N0RfRj(NOimT z?&Ps_@-1cXZ85=GyS*LF>tqb&a|%Uo&l=Iu8n#e;s~7Pb*qW-DctG~@B(l`zI!?O7 z-N!I_3u!*M7!@ibpd{raxj*}-_|84<&a>=0WJjxOHhJ}7aG~>i5?*6Yx@-G_!f_c$ zN#91Ix46KZPKr=G=>-XUJs8euD?wqQ26URE3!Vk?komYDjA|(d%@@9r{58WNKdFq= zRlFcRM&2;s!8DTh=o(pM5CM}vo)?YUc$mak#zJBJQ1O!!tI2}_ad4&2Fg#^3flO^T z3GTeujpHI)ks}TM@G0;OI!qlS8qnDdmOj>`MTT_zpyF2bCcBJ$HRgqlUz(y=faijX5cjKzjkI;Wm06pV83^UWtW31IAY7{<9%(WM}_EN6Be;N~2 zdG92Pw{dWoTCzm{K8wRq9Al2lw|+uCKF6m%A3u(fqkP=X!nN^6h5MSP{Zyxe zj)$@Q_iFB9aI2||Kg2J?+Hm1sa`C_?;;xx#EZt>$xM;)j8H|0LLde@0!u_+kI;Y9r zV_qy>e<*i9Llt3Mv9%{Ctkz}x*mO9|$!ucx_mrv!fO4B%jCXIJ4ELt@V!SnICYYNo z)Bj^%-)}syWfr^hdL?%scf0i+*ge;sZluB07V)h7hHH5k5-r@5UX;`m4NnSn{^-?T zOsoX%`z=@0sVs@*k27{9>T{+rZv2!(%55SU2d*tAi#Pf+E*;M88!#Hf_~sB*sB#|8 zcyF{W1Wg{mxXt>3u==A8<2aEM_&tBg+A?KYFgUfH%{X?$G!WXv|5v#8{#P6SmFe7l znyeoDeVUF%GZ{}C(1YZ)nIhEh)MgSJ7R=bvImP4Tirw8OJOeK*&$Ql=G<1#w*vl63Mpz zXIb)n@1>ze`Sv<&^q~5o!kzMCjz!Xl?+M7KUtT$#YP%g`_BmF8yT5eg5)q$n6_G}V zd<z#ytFVE`_BxFHpiiYh#_QOZ+1qE(l$1c$-rVdo8anhj zlfz~1&fCy_%aNCZ=9@&Cy5t_?*kxh#j;jXc(-n7*`mMjxv`c4soQ_O`sxC)aIsV^M zq1BZfR(@|$8qC>0l|A=a;&ce8y2RM0DiV%+E3Uj$ zwXb0RRkw3d^Q-VK?|xZ_RzHPzdH)tI+To4xE??<9kcLJJ@0Up5jY^g&nJ$@MvK-0s zC7&x<`O-Q_%CB{Ufo6x7pK^`$P5c;}+{U1md zMJLwRDT}&*M^GQe;a)ayNkN72l2M+ZwC4)zOLgNSVQD}zw8V~(s*Wl zGS6HdrR#dJ^rhcLG>D$}1rcLW6GCnr@8rFAW_*|Ay2xCF}a*2jPnbpE+Wr*#ISO9KPo0GqJ(j8t9M_>jn9IPKFaEV zomzjE$N8fL47Sx~+^*aO)@nDhwsc7efL70sF<$X92E0~BGp>=J0grcGW_I%SSSs9e z)MT=ndNU0YRtz9~+x34WL&U{Q#wSt|Ku3^W?%S;k%g}xsfEzPiE;qatTp>mde=ejF_vt@UHRp=A$FX^Jaw^+tAJ$orf?kUZ&5jjp;M~BaJbim;Vi)ncLe>`LcNC%XZCumd`V9`&>Gc37^j8 zXUym4{t@^bd^ueCjQR4pzl`~3a{tDd%f_wM#WCie$(6gisKhtRX#v=AD2zr}JBl}n&pFa0xGM(v; zh0{A{+EG4FdPMExoF|Lrd+rf2Y(RyXP5O| zu!MUyUycu6vbOR|VQiP!p3JNh@~ev$kePweEd9{|O3sc9V7%>oBdL7g#&|-6CTLH! zVXR``2STER?{)n=d$?!UmZeu!j)AqkU$FYyyatJ>K5jS4LR#&&uHD#68*@v-(>vm^;4kT7z0g`lsd*|DP3 zgjAOQ)6NItO$LI#8ul*5*!#k|Wwgaz%u;h_dGt`7b{Z$F)8-!>Kr51kwFTwHqv(~)e}*fF^f0djx8c-vwX>8dxgKnK8taYr7xBE$GaJ%7*n~&~n`A1)w-p?8PgT~K2j0o)r?pjt^n0IACPgG1uqKgcgMS5dQ@cFX@>Unt@>G072 z{ntm)CX0i__O%|4pB+S-c0MGJ?{>mnOU6+*Wkv3eRSld@z;l#h`wq1(72uNankC0R;{A~X=K)OG?_E3WS&z9ZQOegUmlJv z8J!YF{lC@VtwgPo4k?@*tx|DQtdIBnzyyY zkpl|J;C+*5eBL0;x_*lcA014Sr!B*gwPNun2 zzw~dYr?}Cm`*%M&XlOZRCS)3cYb3Q++=NN4D~w)wPN6F1X_#_pfsu9nH2NsM12r!+ zfzq!pvFm_#G}hMwF#85>acM*MbP$1w-dQwDYDIOF9AH(-2{dS-NW0mL0GrS~_&9^R zzdFkW-aOfim1n=>5N~(*7@3KVEt}9jZ44ClUV$~`@32SjaS-r&0qS;rjVaONp;uu# zHhr$chLPUT`O9>a33!S(uKR%F&Nv+D{s`5S{J<_H62D)#kFQ_(LEOSHR6BDQofrDU zlzSm4wz`8y@A^YvRw(Z6R*P$2`$O^72z(oJ8($vthtiA~jMBP|6;}S>&|(@cYIPfX zPxXT~O6izkeH%?D`NF7!3-D6bZOkP;kh^+0zS6A4i$5oThwnPfI#!FvSB{5Gx!L$4 z{SMZD90&WYw&RZ(cX4oUPiUuEfY*22LsN?}FtF2M9IN~QkF*~R0fS1gi}NFtd+!SK z+MmPc5l?YlYiBSUbORULyg>23VeroWK8D|UjpV8w#G1dtDc&DY%hv|1zBXdOxi2W| zYyqR~Ww}@y8QN-DUl@H`iS9bZoiC(r3vi(8x==^l7{A zj;n(ez-F>KjV|s+ zA3bdWr5n_!!8JYFG_VbvnV~}0kJP38bJgMdf);dGz7B2er2}{KW#|NBE~dt`2NdZv zqFN82=GHZ2XfJs>HD5$C#yurf-DGGdkv*-hsVAo|zr@j3MYKFf9`Z(W=NMhKqI+Jq z2JP=R@pX(pU73EB%p9@=mrMzy3c8h~XhS$owNHljvu@=dG8jTO)l37?_imVzH;nB6 z76YH2XQGF?D;cN~3=3Jgemd{Fj z+or+%-e-xIrY&~U35WY|ogCHrDL%xV^SPj;iWHt%EKaB4Fwiy*;`(gL-*fcXZVVd^W%|nbpQq@8<(S@JJ0d%8mzxNVd{c(8Bh~VfJUwA|_X>i^<~!Cu znFwyObBO-MFIz*Cra{nvi=xBP$G2Xjsi30q&ia0PpY2vZ(}46I1{P=6y(#0C`uCo4gCr<2$+Cr4`hlT7`G!J43yqH?(!n!eYx?M1_l4@-^FxhlaSo zg0WA?%+NKc_Q{Kv6`EMQ=g+cZ{dwsXS3{mJm_8;4dej*Vp2W?Q)E6<60U;gD2b&Yp1rxf*~{MPN!km>gYc4&;Ci=xn3*r zY?^8-mIl%d7`9HJx zbhb9dr%U*)_%$v5FYmYF%V*4&FX6WW3BMH=i~SG36_M~;ab?e9zdd~Dj-f<4?~h~Y zd>tjq`OPmT@mwlVpWpmz67{FSr_7D`I`iLtiT3jOkx%_YmV8;i{BewVS@M7R^gsM@ zjJf~i{c()>GPwFP7Rna%^@qQkrAx9@k3-;>JpU)_kso{W_2kFi!%~Det3%puw64n_ zR{uj!&8hv;(TvqMwWF%C!uq^k^ev2eFqNfOPg{UvQSd>Z*mY5y8z`*Ln~hv9+Hqz& z%hNY|GKuRX__7ylyhuiz68t_($0$RihYibP7~Ticm+CNXz1#_wa(fy0x=sER2-gC) zFdq9M9ww@GX6&ev0+RLb>Z8GayMFU1dU9fa#tX77sLdA_##a=z>4*R!-b~K!6&}_U z{OQA2Z^rY7g|%tlk{)>LkC?joo7)zbR0-{RQe7tE=cjyq`1z@19o!#gvHG;{nE+{< z9x>j&JQQk`)LH)RtK4Civl(N>J%eFhgfnA{xXw^i8o-!z`$YQR6#4|^ZF^Z6{Ih=b zAOA5+`%g|r(*BbZ!XMu#%G-?eJNR$$D*v6|!GFc~&hDg99(A4v$DoVC_p;w4y7GWB`<^B*@T3#^3GoK6v#jZ>^};vz za=*^hrmZjr=$%rJmmUaXfXMwDQM_7+ZxQcO!9}&g7^X3|rATYH5XZ9riyN^uh+*Yd z)E1Kiy9J;4_O9Gr3YTqJdeo%fed4DL1)unQUw=3ezMIvvEPOJ|_wL2`VKBF^WaBUv ze{zT$cbLu)`YTJlnV>diFY@i3^e7HWZ+~YTw!sf7Q@b-cG*k?QWfgXelfeiqrh79k zx+o71j>Is2-gKO-`y%Wo`uJo7S@&F6D?FEd-$qh~l4F~yH$vM(l8SBSiUgUQ`JjoO z_JXWr=4`_1VM2`Jt%SE|eBKF|UhH&e@Dw3lw{W-(-L5C-;`I|xx;5(pYj2hNBsvs? zan7lm2Z(HEfA-t6>fcDtP$51cB~cfwxpi#5%sg%#d%_Q)oba)p5NKS%%JFzS5tb{> zVSISTG-&L9k;O$^=GL*haO>FoZ~1j>eodZdeobDo?K37NGx-!$+LAk-!W_qI%mHHZ z(T}C?$oWR}jyp15X{ZNRNH4~vP6Q$yTQmL?Hx7>bU1EB1;?5q=DV)Lh%FyW`xfi4G zvako|)aFQ#-P?-&w(Q0@@LX@gc-tv}E`dWCXDaph?YD>Wgjih1F%u!Tg(}OV?>+`D zeiiETYP0CK-%6JA&oJ*x<>kZsQV(@J!Z>tFEPcE}jy+3bfDcXGA;b|WjJ2odj|ugR z%jr&MRtvJ~BmW(B9VWB<=PmXi@0;e!k19*XJ=*o7Up0&vn}4#Sx4Nk_KA7rG6H>piI)CE)q?(+clrM7_ z=O>-tauee~&QEIEH;r*5=O>kHujJg}pW#2-uM{3`xr2W$|6Tr9?ic%i_1r&`!=I%~ z?$eQE$^3V?J$SqX!&1B9#vq}e*&@!x(al0%tzT7#R8EMOp0QDjmNyJw`L#L@8Zwz4Nr&tVxqt054_u05XvSA&wVXfXF&_gblamVy2@cFYYW6#=|zt!jerW|hn zKELh;-2HC<)IDyz4^(8L#(bdv%CmR=73V_4$0zXZ`rDlgQ4yW-k2}RAS*pkXx_d?c z73X_M_4U`%m*l%9$x=Q3we%>}*I!FtlJA-%OZE8I(xX&ge=U7UzH5>!)#G1FkE2HY zJ?D2v4*xypcbOUgHouc(sUD^8-G6kC?Z0AOMf%?T_uoe>)#Lx~b5l`4uJ|8!(Elfy z1Q(Y7V{Pp}Vt&p0mtRxLf`3;khyR^&Xra-9`8#~3j;G77X)_iDxlrAif}eEl9iZY* zgIW5KAN{C%n+MGI(a<-HIv;t<_}suCs;Sw`IJL?5w>)wCg|iwOW{svl8~d_y=vzyg zY$Es^hqdkU8yCGIERX$?o^;SoAwD+#X%AWzy%foe$)LO+Nc4n**wr%JPZ#AgSMhDnbw45Y>8SPu45A(0&kt^PgG?U6f9|8DU97M^`xk1^(1($8C? z>_9Ki?n0W>x`D}N8=5vUlib?V89Ijcr$g+kNOYY#EGRanp~DqnBex&VUEGDPi|hnC z`LbYMs!H#*?gxfjUy+sPWNGaxJ5YaogLvM2f?fUG;nKPjWXHua44&@~$698SwKLCP zrb!r#P#;5lo8KZmF&-?v6Nt@hRoYbN2%a66k@m%g)a*?^C=cIEy0y2a4(VDjXj>ss ze&IwHoo*zt11NFYGJ#I_+D&$!zD&$QLg={O{mCfnO43IwoE~|4L{zo9`nNVt9wwZ- zn0a^_Y}t4nUw9riIOjPLR?4f=5z4c6-1is*i(B-jlN$T!O;{)TEe1fgzBfKPXy2op zJ7bcM4aj*~Yw&;AdlPsctM%_+5|Mdsz{cJrqR13`T_i)9g_J3C=6N1NQA&kSD8n9P zDkO>TTF4ZI%yT3mQJoAG<+(oBz3zRk?C1CYpWo{_r|0!N&-c7uzu$SEW!>w0uXSH* zt!rJMwbsVofC}HNjf`2dxN526qo_>9^O5o{KK^9ZQM9kr-S&YziSbuzji5ajTiX&P za~bpSU}{#khFja& zV9yunPN%c?GKe}~vbVk4jsK>1Z*#p{l07=U z8=dOi$K2a9$+qj)jaIze*UWx8$?omajXFQy&s-{zWWVjyje6bQ-)z2+Xn*V8jk-1L zZ>G*lv~7lVqd_hEoAhN9?TfE>ql2;i&AXo@*yomXqeUO~GcVRiu+MDoMnwwtGjDHM zVE??(jUMgX*Yuq7ik-BqFV#C;&HOn16&v}mFV$I8&D2PG#nxZmmyY(UW=gGp#g^do zJE)pz^X)6P=F+}2FMBmJFy|yYV_{!vb)L+zCnnk0`F&~Xb~3YHo@8%-r!VDNMP|(I zN%q+{`qC5clPOr>Rr}0~eW`genW1%(?CsfVQ=0=B>8^(J?Dmp|E>_4#RhqqPA9<`I zovRT;2`|jDb32ux%p*%smIvRq1Gg5Zs;@ju({s(R`xh6YyX#e^xy|0PpFNU~de5px zFPEKW$1KcBUsS10Z>O1NYv0UBufFsoy*Xr>t=c*rMILBCv*y2Lr@oqozHQlv8V;Xf zU-{&^S^R!u>Ywi&+x>xG%?;Cp`m~#4%XGeK?!3PVy-{_Z&C}|td8c<{>iTk`{p7$k zQ~CZz^n7Hoy})~0F0Zdo?K7>k7hM`!{LGUS^ZPoRZTuaS_tN9EX6+6;W?&YI468zS zc0Fn@G|NlNww0l4yU*L#yA-6k^NUjdb60Ir)i@eFFCR^7cANWb#RD{_T4uU3HoYry zrZi>TdmGKFl+k7Q;UU^lA&9*TY?FTy=(AG+ynlyKxwL4ZdqNH_e%*tO+*k(tY(3)S@nA}4T*leqs(%A`X z&AIn>+06Tz(eZ-T)X2TvcJJPtns(V>=3m@oYc6O`<5q4qz2nx~7K58pp4>ak7ay&) z#ZNV(6K{WIu1sBR(;jY0`5GTKxyG)r)mJy6N5-Bpg~l(lZ^ksDKUe;2?mo82#_y>| z%d6Zpy_!*t&+8k|@)8kK z_LU#(QzaWvjxyH#dHsU@wO0em^=ZUpzJu%dbA8(Tx;6i3bkUCARiAEdvSvw_i}us4 z^{MH0YuYrpXmcE@Pjwe?y>9$q3*OOy7T2<7$Iw&ugRKpy-m-0G;o&p3WO{C^ueO*| zOHSL&ts7AM`K@N!_j~QR_6?}vz(eM_qdV=HZ4IeVnnPyz{d=tavH?|_cF3FjwOXhXI^r%ix*M7?s ze~{dU&$E$j@v(XDP+_-ocX|5lwRa8eF6buSs6^We^Ei3*UN`*LDpY#w+oncB8NMr^ z6n*w$MY`0!l#jD}>0vF!%jOND#XrZ4*3Yfp~PLk9}i zqw6#C*=bd>)1A2+QJM6)?cCe%qGB7LqB>91bZh&iryE~NYjpVPXz!F~3|Y z=$<%JiLT_FZ7ReTcbl)4p;Z^>n^q6SxzB5qr6womnjNw3MFo7R6>gbIE9i(URlZfgGd{S=e# zto?FtF8ZuYX?l77E?d7=R@%F*GVRQ>-In^D?RsJrs$6!ny}Bz4)wo=hGAAy!KU}zj zUYcHq>h6En4%&SijW}AL;y#&Tr!T#39(%C~T{y!&)sJcDy($s&(eS!%MYhZ4_4xH> zQSOV84)H&j^$)hA&5wK^>1ocI_s6%V!9DA_F1vp=%W^m~VRU`Bt>s12Fxz@F;i(3$ z#s2eV{l4|4#?c0D*Tl0Xce4$q-xJTex34CcRg?Fa=-TA}&9zDNyGOr!)CQt9plzV* z&t0g-iwD+yQ}dAJ^*G_*aL383KXjq$-T$$!R{SCR{n;)wWqA6?hKCQ?+rRBXGd|B5 z8ByerZGNf?-8fz#@@dvX_UV&dDDA9bk@deGw4X8OY5id2{Zj{R|8Kfb*Rj+E!OK6YonEp}p`j#Rp27aLz-n{E18M_RV1r7eEqb6crsC(50tfn6EdVNbr& ziE@3!_i!bDX+Qa)6KyS5#=g^jm+e=tGc|Js?Qa>r`b+!hw#vhIUuTS&A4#Zs&_)(_ zq9siWSjx1|p3K#O){X99E5z@z_nc@;dD^~dA8q-$E&OCFdcE;dd*2TmZN;}*&1d&h?rQNwo9jevy72CuE_?SR+jL7E zYB?^wd-%JB_QI=AQq6g3-Ssz@*o}|Wr&XhWvnN|Fx6gmlh-%+=-gdcvwOx8!Gospi z?LW3f*uQ>;%9dPh@BMC*ZF{&4{d{?x8 zf7w?0jK5xb#LHM8wTZz@P{+qM}h7$rDMm$OfQ z!EuELO1NvQUbXWF)S)RO?{HmaF12^JZ9!Dt*{1F@`|GUsbo~AfwsPCAZ1U93l&!*r z$ju1{Ym7{BVz?@Z>$GTWGq?OelCKbt>Wjr-Rx-bC zvX8}9b(81E(d*@Q+4a5R-2O&wDSzL1TWj@MJMBQ`ZG|#jDE3DG$o<<6 z+poUpLeCBReO<8mo6a z9k;)q>qKwIEss33{g@q6p)+l6ydX05;bXSq_|BB?lWCC&ZyvQ7zU)lD{`g{K`n4mr zNX{UBJ9-}|@=U0<6al6c!;`^Awi zG%?@Sbz@f@vUx6dp>&ystgHOOA-nBn7b?8!`r5u-|Jo)4PxPXVqvzWr)gLsAK59$Z zcU-bBEXZt1^?Q)|FRAS6-~W4LV)BEudu(NQ@!enfyv`UIOJPIm&IH+$jx;{UiMt@e zJb$^9L7lb7ze^r}23CA`>}ywdCj8~^H>o=l{&IH&m*eoeCFQ_`Ue=V(~ec@Y{VX8Wm$Lv&Ci~Rm|yM)V)(^c95NHAz2q73#*gNOZ(9nl z%X2$r`K_sNOqQ&)`i1(!m6G#Q=W)T=tIWrXP?4OEO8UG#WoUhwQo;xN#MA89{KCV( zsZSe*1v*IeBduv)t2I*Jdh>hH{%$#hzv?oQ%$al2J|~)wqT}698MH&ABb{i?r$PH? z+4um*XL}OTKi=v1p26Y5hdR|T)%T1Nu3Uc;ml1q-*uc8VL3+Q{KSc_y8YX$V$2PQk zTLt$;)Gsl~9;p!AIecpPV%z&v56LsE*hYIj{RrV|E6e?bhkY6RZtumF?4o-E?(=AE z``YoLlK z-)$P4GrGGM$JI^*Hb11>O?$9GEh#78nZoYL2_=L--b3#0C+`%V{80;6@zNG)x9q38 zyNB-XBb@E{5EqwernK$-b@^{?6!<8DHq4rKw0mvSNNNA2w-0gebPoO&Nx{+G+|lZH zIppcOtGSz3Ecm7|L*w1ud@edDYGtV{(>~l=Up(dtZ@N75tf%&ae4=KOu^JKNVkCZmWllf@2V8o{L>YSQmr>?%d_QM#L&(< zLHSGHzL%yv)JW3r|1CG=$=qDHb9xh}lv=R5kn9Xa}W$>ZuCu!l|uePrc58|{h(!I)p+gJt&m z`ruq%xk0mSo*F@4&j0l!`+bEW^6bqy!|X2~3>8kFroH`oebD#2Rcl~#4h{P318c}` zJRR_ojTOXqTKVYhcZGgblmp)>+78inh}uBZ2BJ0)wSlM&L~S5y15q1@+Q9#s4Q#vP zS&4sbZ@R-o`2!Pehp0V7Z6Im`Q5%TbK-31JHW0Oes0~DIAZi0q8;IJ#|CbH0#3+CJ zWZV1+3D{49eIW13pPZZU-fMp(U{AoVL5WD0{UT4#PDFm}ccEo#=JLO% zaoAt7|MK(%?5n|^nyqh7Ou)Vx>_=(yP>%$^uZA_nY6;l0g5P`a_bdt6%Yxs#Ui*Uu z{5$Sk?}8J*jJY!3r`t@8j}-CwZRu?bi~4fhdlxgs`tsda6Cdk;*R|c%HP*k6<9fyV z_jFvZSpWWx>lK?ml9u@t{2LeeL`F>{I2XD;(EpU zeKn5j6^r)3?{U3i(SGOld)4hSjKBBa*YEiEV*ieQSG@LK{@VwCU%%_WsMr72 zei!|Yt=+$4{QP%+$N#F|y|!%O-`el^_x_fCw>L}1zjeMFT)yZ3)_xcLj{ly1_wV?Q zq3`#?<98=|U(PHjaaUsK`^{PSGy0rsb^F1DN0T;(KB4V1e`@F}+BYA6H1r|emI|*g z2z|dI7al1Z`hG>1$He~6e7`GSewyO@<*Rot_QyLKzk=Ue*g8X8==(Jvk~hwe32sK3 z!uY#_;`_ajP%JL={mNA;9vAw453Mc|7y5o&uei|n<9gxm9*XbB_2Ty#L&c_kp2YPE zeL}%$$g*jp4n5V4z=mI-o}(|V}76C znRY%`(NtR;B{{X)$;xmjyH&FF*;Vb@rmc-id5+)b;-J8NZhp8X|Z_r>*Ay0!g?V+{riv0 z`y>CZyT%BkoUpA>{-u~zl8)a!c51sY-ly1vW5U}id{A`Kg!95T3g%5XKk{c`)T>FU z%fiD8#w3R6xn66T80K%V@a4p?ocE8;PYlbSKKqlz@OS?c_RwuccUNfiVzIH<)2-a) z?Q_M(UT$B@P3`)I*jW6z2VKdBMv9G9OqbVP>+-DF*y;OiH+U-ZjkE~TUyGw z_CRyH`MX(SZ)rw#aaU>mWsO-KS z^i(YR!uJV<+_;MwV^L;I*%P*PgV$nFrhiY1G84{su!ZOR5Q~1{-_xQ@|DG0Q`uDUb z)4yj#y=Mev`Zkm@{d-1Grf*Lv)3>LT>DyDv^zCU;rf*M+GX1xfGJShWnSLCQGW|Fp zW%_YI%Jk!alX6vxoi4mo4x9nQf7RGMK)&dWGNHnp|6Xl^?l*!|tMg4>CzSpAu!FOL{QUBn(zh_bZ;Jdf6s6WbN z8@KpQ!FN9$LH$uC+q=bgLYZvu7T*bFvb|e;CzQ$dZtF;dsV)rPM>n(PVGTGjV=l!t1qyAxk=ke}6 z=|@~|!}Gp;cm6(N_pl|dH;;Fx!*NOM9%b_PA=o|IlfRGHJ>HYQkJvqIiNBA5-NTmH zj>PU!CVwBXd%P#xk=Q-TWP2yrJ<4P|61zv4Y)4}ED3k5T!0u5d+dE}AyekQ1vK@)t zqfEAUifOSS31zaqQ|@fjlY;MFnI^89kc2YX-f2YK^GPU^?cGcsc5jk;PlGbq-p%Tt zdnBs&4Cf=fr%~@|)O&{W5#CegBj277I0w7;?TL9)%JlQQl!m$H&ICAO95D^4VSaa|PngBzC5>#ZK6^n{&l=pF4nx zeLvlfY?eMQUF=AD`Q7|>=k^P-PV;ezSf6g%G|NqzWKNqPgYtVmnEx-NXz3!2_>(VE$6;J#nU3tgD638tg8O8*lQD zN}Jeh*GRW;;T>jk-Lr^6q{P@B+4Bhd#nKJfCgY zq3^H_7iAlE=u>RNvFOL>&)mlyj~kZ94PhQPERP$)JZ@MXH-vfIusm)E^SEJo+=$1s zJZ@MXH-vF^wESz$5|Pg1gXQr-(lI_^oI*N}Czi((Vd$yQrBS~qN82H41Ao5__;J9h zzA5bctg!FPnCqSHQ0aUI^TZDb2`telxI0T5~kyCreg0*@Xr4n>$v<#SU$=Q$0hI2 z$asZ!3CA&%hu=dvC{NylSwFjHL!x;k?=BDR%8v@m zv`ANe7q@wekB6~3^zoeX@tpGUobvIU^6@ZMhd$n4%Jgk6zx(#rb$D)&^F8<$Xe&wA zcH-Ms(tVo?f08r--y%%MHxl;WPFVYje>11-1@iuz=-U5z9wYZKU~J=g?r-FO`l!B+ zgneRv1B*U|y=44be-;UqOGzIt%_1 z#z|6RCaE!#)R;+X%p^5tk{Xl$@>{CU@|xjvQQsd)^>O4+Su?7>OsX%_n}t^nQ2I?!vxJ!u%HRhu`&e5%zTy-oH7iFxNdy59bv5JKTOw3EN!qD4!N}4}IP68%e#; zmbF^efN%VlJcrM1wNK8DlX8B#?JGO-_LGwTCBDD!>3_5nZntKfoxEtV9+m`=N znA0r(n=ou0dm%B#L^;|HQ5%TbK-31JHW0Oes0~DIAZi0x4+Z}T)<#i|wnNkg{v$RZ zF&^KxQI>`X;$G1LCBW#Ki9t zj_dyd|98K4aBjuF56Tbg{y*hDeFoEzdgJ8oY0V=u4xwpXM@o90IYTJ%kpaRLN)Dx` zfA5xxbsqg}!QH*7Ua6ImUvrlEeW=bS%Ow57UVW)YwMD{rROm;0HYKKFoku_W`pHhz zu}N^>z2;}nccye%j!QY&FLt4A8xILDz3@D3>%T7*>pc3|>YqMCBa+g~_tM<*+OyPt zZaPU%DAS7C%t$Mor$cKRJ}FHq)_L@^C5G3foloB@`8B_Iz8=--f48K!d8z@mpOjB{ z*(VLD*xWp+Sm)8tcBxf`ioQ}>@@pRXO;tL&qm-m~A7*Gv#*)JK^S#1N*qdgQhi8zE-@!9rybIprR@Qm+v#2ZTjQpC>9;h?Y(N3r{7;TAmyp?qx{Vcu} zz8Ugs#`nZGLpr`Qz8M&{06VyqbsqgJYz;Pt{C{D#N7x+FVW+S;Fl-rid@Jibu;uVs z^cD0O@eN zEZ5Ph`lc|~*M@Dv^|fJJaT{9Io++&J=x6zRS@peAn7@||zbSt&8-8oH0jumGg>@eN zEZdt^_LjnIZ#J|^wl^EvD%-GC_ME~xkA9Z>i&gz4g}J}juupM+v0;DVK4?{c{3okC z`dRMpPWAT`=Kk)&F@gKL3&#o`L!25TX)OeM`JYKnQOylv&g<~C$fliHw zDXjD8XL-DJYP?Nh9&cSZCi8gf!m*miaHq!e6xMn4vz*td`67k6Jcn@{;{gAT!}t#7 zcX4VyN@1NxKg)G>YQ9ThZV!iX9A$DlIgIaMZcC@;(-hWu^t1e}oSLswn7^mPIF2&; zJ3EZ;V73LP{DBnKdGxbvYfkwaDa`ihLZ5`~)M0!_`E1Kh`7{Vb1F z4&y$a)y(6W!#Iv~9_Jj!cQB8I4&(lpc2d|Ggx?X8*k; z-G47(Zx5+h=h4r4dz1W{y}e1gw>M#LJF(a-w+BKbA@{vzqVzX<#On2L2C{jBfr z4(+em_jgJ6{ax6PC#hKH(a-wvO7d&=R)y(a-w%TJmf5 z^R=Y=`C8cf1F2Z&(a(B+L-PNH1Ajx(y}u#s{h3s(^LT$o@_2tK6?=b4(!IYV?ESG+ ztn=t+y}u{tn=t+{d!IEYsP$zaUA7fp2zqOhA)6Q;8xao^s|1wDfudSB8t!ym*rj`HCr zVtfa~m&6=!E9*S^Ss$;E{F>p~@N+S~gW(Hf4!D(d9{sG3w@7}?@W(NZqa66@ z7~jG0WLtOYR#AirjvM?Z_TCdPf_ z*UbI~Vv>^1c8XY~FxIk|1CU>{&ZD2jS{ZWy@@wY)gqW(Nb3a3@RTyh=%mK)+S?AHu zVy%yHANe)&cz~F&r1Lm|Sg|l-377+rU$f4mpXITNFzzG2W**N7<2cfJoFk0yV8lW& z2i(d!kA9ZNTEe)G{F-?@CXC}q=dqSBzJn3V!5nZa>pc2d|2_u!HT(CGbpJlWzK*F_ z=h4ri+~7a|T^%5rKiY0l8;IIK)CQt95Ve7*4Mc4qY6DRlh}uBZ2BJ0)wSlM&L~S5y z15q1@+CbC>qBanqBanZ$qF3EAS;`}_Uo z=V}pg3Blcc&!wLdU+$TJckN3sm)it)Bu;%RBdz@AX({LXrz%t4Sq}+Mzpp*j&Ha;{ z%U*nAAT`c`|&B7JtLdgW5#Xe=wqrN zTw-8W8o#osaAMn&=JdV6eH4FO&P>NwG?R4AvpVcEt$%!8(hIIyWb!^6+==mCi8FlP zV@FB<^xOOCY`frohS*OVQ?@U2O8U(&d(p$gKauxoaDd*7b9A0>G-w2RqwD&f3)0`p+|@i(XQ({8 z^~JO1Ow*3SX<~}g$_v$l^yYhvA${GuMQHWMHHF8OOHXBQ3-0mgTe&ceJW@;2 zHE$o6hF|t|oPZ!B^V(^{hX0#AK{^O&x>$~7yi?a8&rM$VW%kSR5Vi5J% zI#D=sb2L4cv2qo>!@O3*sKlqu40zW&{is0y1;RNBJw@j~&rV3sK01#6Y*<4$SHDZ9 z;H37#1M0kKXxKpEdRMl`cZvk~zSFK^ zc^bUu5r;g@f4GM-d|6lc`Jc+s(R@Ll()`oRJajS=+=Vjri?oy_dvFKKkW2-rPpK#6 z*_hIGY23Pdh08VXMwtuml;6F#!U#GszKrmlD@IYtQ9I>5YhCD1D|^l|c!%6QyVCMX zdxY1VuR*_VizTF&o1B9#&S)Zh-|6+HPtl-{RR5ux>DVpkBSThCe)KATZ{)8^ne5Hv zpgrxeeUU74f_B!N+W?*+*`lla$g?fywznsef@GY`PfQE?l;#@o zB`9O=V2r97$w#Y82Y1(;z55~hU}t4{cF^Ew=&_s`goiZjPrJ*$C%;>*-e`Ji+6;N0 zjz0~fVY8l;_naKlonl6B7d~>cHQl)Or*NCE%F<^KS0udK}hjl4%&8(t#4o6I!vC`e7WjMoA%4#zTDPxj@eA< zf;)RFu9|0uoara|7k)iH^25O3yR^Rkuo-br(7%q=+-2U*(@pXWxmtvJ_Npm7y>J~` zF~5-Tr@5b@Pd>~b-23Q2dSLlvsn>VcM$^Z;$5chVN^KZM6CQ0~!FL|)PNw));hkxl z(da+3IHZ625z)i%2lw#Iysatq7#Z{_%}-aWLJ4mKW7HQFOH$Ux!JR*)23My8NyVj{ zq=lX6X8CWV{I7o+N~MRi7QX(&Xe!lmv%F94O#`TO+UW+rTP){u)Nsx<;Rd}MQS*7Z zr7p$O#L(FTwS_Z1v%|djbI=Z7H>hqFb_)8)hfTj;JIs$!TbI_d^NIxNZ8s&^Vwr-r z-TCqiYbOklax_2N{*+BT7TlBEw|hF*Azw?$Gi}mtTjk5H!kudsv(?@SzQx%$X2(~k z7JQ>q?dO`83iOveukX!D4-RN5OfOcX4~CZ&Zno}8n%L+*;X=!L(re|c)UoB$qp103 z=VYwd`1UAjb7;TV>cv3=sN~h4@02~;j&48xleF8ct_|tKEO{N;YGdYh^mfLePifvX zur8fwbFbv7k~yAAzZ=|@H27L0djC`|NuR%sPpwA!QEbrO)XcHP+Du=xP$z#=sTHG%@B;hV<`FeBV&l}D*aa)6Sxb)uI_|88B z{opg1pIcsY4($>K|dPPb-x|8@_Bi7h23IvU+kWW?^>4LO(%R~G zyXjf$2fx+!4?AT*8{zTQ$J?C^gR$;|mdn>A{1kkbtLNI9oI8X5c-Optn4-PfN&fz^ zaWsE+Fb@{!^C(^IRYubHRp>zJP6hMMh8n}D@heYD-4ofS+HKvl7HwW&-7q>mJLo$J z@AjZ_-9M8yEL^BH#izN=ArI<-`rOK>2kL`#)C2VaqaL4geZZ&(>H|hSKIHmXS1^rDWI_Yzyg{ zVPCK_q{F^oXJFVD>28Mmz%XS8aeZkJaurJsd82ui7{#Hi6NB>7U`aSwT_)+fn=>K5!d-Q)W`aSwT z82ujoAB=vF{trgKNB;+--=qJ7Cv(3?{|7(K{T}@vjDC;)4@SR7{|BSrqyK}^@6rFk z7>_X)-^v(|F)kw=<1xl%Fveqy%iuqGJjS>T#(0czS(wLTjLX729%EbvV?4&V490kj zaT$#97~?V+<1xl%FvjB(JT8MV9VJc;=d zjCm6CB^dK0=1VZ@!-IrwDk?2wTTzY_i>7=9)EOECOO z_?KY#mBrb=1jDaf$NnW4ekJ@%F#JmRmtgpn@GrseE8$G1dA_k-c@!|w;f--q81hQANL9}IsVem@xgKKy<#{C)WSVEFs+`@!({KViQg ze2M-2vh4SR`?9|ezaI>LAAUa={(eXH`@!({;rD~F4ttK*VoG9aVOWoWu@1v}42*Rc)?;9-!>}F$V;zR|7#Qm?tjEB)cpZlI82D9QhhaSi z#ySk^F)-F)SdW3R4#Rp3jCB~+V_>Y0u{OSyu|CE+8R=LbW1S4f`WWkEFxJOdCxfv* z#yS~{^)c4T;0C-t#yS~{^)c4T;DWq9#yT1NJ+F_kP6lIrjCC>?>tn2w!B`(-oeakM z80%y(*2h>UgAunt%;Hu?+ye0nq$6&D_yrho3&bzLh+80j0Y=;c@e8oTEjWGwM%-d6 z$1lK$TOfV`M%)7N3-BWxw?O;?jJO5j7huFKmU8?8jJO5j7huFK5WfH;Zh`m(81W>; zl5S>?j5r_SePG1-7IVB0e1PM8i1&dJ=R>>? zj5r_SePG1-5bpyc&WCs(7;!$t`@ro-w0D^n1vaVqOr?G<%}0rnr{3ft?vL1k!Z)(? zb`wjl7G9pVkt;$xfGkE&Wk-Y2HpK&rYb z=u?_&uN_Il(*<|<4_`N$GJR7yKEtY*`Q4h1piWy#nHzOpPIxe;EB*57UbE=>;KavT zJwaLX6r^n59!ShFqX7M2pP=<4t|eZdxzYUec@L^`IFdMUYh}}Y{cxJNuXf^%<*&p~ z>N=V>kNk5%?(d$mBL@znnk$RP&aC{st&-4zb_~xRJ8MZ%H}T-(v|vS}qGkWA=IiN}7ub-Bt35c>tv%RH(pR@0=~|7;DLnDi zAoo@83Brlgzt_!KUkg5x*x{#_1eeut_P*|69@l%beOMF6|Osk%5-7pLmt!n&|sIb~xh%r@qfjXBsD`WM@ngN=dN#vE+yvqDqmvW+>| zSVE2N3)sdSY%H$uQweNi7B)8GOmf12t(7fotYYGn1h%mVZ0vITvd&KB>M> zs_&EP`-Hx~uH9JleL~;AwCb^b zZ_)SHA0L!ZXTj$deZS`Zq=X|i3%Rk}_fPh$pTK?Jq3`#YF@6E}eTTlkuK7pvxbHjk zeY_|4eHZq99+RCKlT(<-WT(btr^aNb#$>0)WT(btr^aNf#$>C;WE+mjti8mmG1;gw znbep}YD^|ICQ~>j^IS=4u1sN`D@o0jq~=Oeb0w*{lGI#j)La=K&XugaMATeq)m&-S zTC{~5)LiM*T#X*Asv-aZDTFj}nn1cp` zJiHcj;aZH>#SUv^q-*9ivQukhr`E_$t&trx7(B~sWCslf%xh$)*2qq+k)2v2Tda|h zpS2f@H8PmBmw2p^!K}R)tdYUIMmAU@gL#ciSR;dZjZ9c0gE@9VDt3{=9J?UIE|7;~ z7lhaam}3`&*aetl7lhaam}3_Pu?sM3FY$<7fH`(y5xW3$?7|{;0cP#Rs@R27u?weS z7f!`4oQhpI6}xa@?1E!TPQ{c`m}5###gv?iDLEBWaw?|eR7}aKn37X5C8uIaPQ{dL z7*k^HWu1yC85L79DyBp#rbJ;(iDP}FVtpyhu|861& z)@N0$&#G9TQ?Wj$Vtr1<`W!SEd`FJ;IcP9oj`cYe>vLhOk7KY-#b8sIW3W!eU|kr4 zW$neO7_3tuP+m}-sUkbB*Ii>MA zrSUnX@j0dOIi>MArSUnX@j0dOIi>MArSaKN<74e55^8*`y~Hbx&nS)0gc=|Bd!w}1 z6y|uP`;`tF4D=WFD;+c#=r8P7 zI%qJ^U)Zm7&|sjyuwUt*!9aguf8VJ+S1HW?zEgXyoZ55c)SfG+_FOr&=gO%)S5ED@ za%#_&3-?^H_Ts`lSFF7_XfXIL?C)D>FktrgZMf%(wU?NN*m_b77QBBJ(=rZC4X;-SHye2!ZfwRg0t+B<61 z-chUejykn>)TzCrPVF6aYVW9n27}+?xP?=DN1fU`>eSv*r}mDzaPKI`lbqVqo5CDV zvT9GSReO5*Z&G)3_+5@CIkl(PsXe_;?df%DPp^XpgJ(IO9uN4Zv+|)%H%koReP;dnB#mAXfVjbalUx9*E*v1T3fZ(+Nr(PPVKdJYOl3Zd##B}aGM>lGFn%)Dm~B(h#%p}{;l;m1VQ zD=ajaQmcMQWWB;cgK6^UiA2_395k4u#575)S2$=eug48fV!gsagUR$;rexMD95k3R z`G+L4Ug4m@BwT(one_?>4d%)Ir;}K(aL`~*H9MBbdWC}q^W^hS7Gb@@L4&E5bVnlV z6&4yyLb-#9tXEiQFq_MpVywNOE>!32#IRn%zAiMeW{I#a)T8#zurBmL+l)!RE)loC_SQmG!eb+>9SMpsndmEE}^cg_xDun`@W?6zAx7H?^`hXJ~S9GYcCEO4A}R5Vc++Kecu=MeP7s* z$*I_n$&&8JWMS4`FeVGL_JT24n6(#-$-=C?U`!Tf?FD19yeDff7?T4YJ_2L1Fl#Rk z8VugwkI4qi+6%^H0<-plFr~Dh`G`s4{I-&D}`Bm!CWcK z+6(4NVb)$SR|CQYUf{zBv-ScXMwqo1_%K0w^=9y4gjsum z4!mPc(hasf1_5vS9n6(%9Fv8xqOvT=}lyuf! z;9Cl__5$Bhn6(%9mcp#Pz_*m&W$gvNr7&wR4jK&J!TXjL%-V~C1_Op~2@MA9eM@21 zUf^2_v-SetQkbvewVcuti^;`d%;>v-jlT#ti>$e zhqV{1#e`XV!CK5AowXMS4F-(07&I8LUyBK|_JXyTFl#SZiwXO6aVqv}WJzc31#4ts z)?Tni7G~`QYh+>8Ua&?MX6*%QWMS4`utpYU?FDOOVb)%-MwYr@jSLM2?~FAvG#FuC zBSV7$`!%w#Un3LJ{Tf-=$1YN_k6lQ*k6j4+*oCl|;uj&e{uNO2VwY zAf_bD+6!VzL7wXmBc>$G+6!Vz!mPa@rXCVTCvG#%(EMT8y<9#Kzr&b;}lK?FF%M`4(QYNX1^WkaVwE2($JA%|e*97ibp3 zti3?95N7QKnuRcHFVHN6S$lzIA!4Eutefni^;GcfE6b_Rxh!Op<2FW4Cv_60iw!@gi=VAvNl7%=P$8VuNL zeA0%nFW4EcCFE!A1=_2mv-Se*RT%vq{U3SI@6rFk((k$dgVFEN z|H0_@=>K5WUZA}Sv-Se*RhYFGXs^QP_vrt~kA9E-4@SR7{|9?bJQaIQT+%TfV_Zgl zjK>(4!K}SN6BlOf1)6xkfhHa>kH;97kssqR#$_(4!5EJ*E`u>1LxTZh zJcb4X#(0cz8I185<1*OqRY=8tuY#mwp2U2K{Fo;(UxG1DV!i}pp5(m>7L0ik^CcMb zB<4#n=1I(#V9b-4FTt26F<*jNd%<1>Vb)%-S3wx_B<4%x!90oi5{!8g^Cj5tAxXu4 z4~gh6eh-Q0FMbb+=r4W`iRdqW4~g^VU$BS7`SUN>L*o4T7wjQ%{`?E}kjU?{_JTbm z!th_<$Kc&qd%+$OVfZibV~`I21%3<|{tNsVu;0%U@6W$rpO576dwV1g{7U$j$Pd2~ z{v{ZGB{Uc?{7PsrV86FV7=9)EOQgfEgntQ!UkU%xpMSyL9_P=$U~iA}=U=e5$NBRw z*xTd$`4{Z%5&gyQ?GgRO@41rlHTykRk`8|#em~v;{yzMEF#LV^{b2a}@cY5=_u==0 z;qSxm2gBco-w%er55FG_e;*nQn6(!N4F=5G3-(+|o3QqRJy*i;_o2ZckKc1;z}Wu= z4JKr)&A?cPL4yJNy>P-X2>oBaxz*vW2JqE@)4C^s4)?rwW zfmwUOUN~XaUa%KVn6($|g%id)4C^uE$2tt_F)-F)SdW4I9>rAb_b5s_*2h>UBR|&1 zSSN$AKE^s3jP)_r$zZIHu}%iF_JTc%!mPbukD@SZFW93f%-Rd~CPxXxCP=DV8ksD zzX1C^y{Xvm>6LdwJPC0naV6wIJc;-83L~C`xDwJ4PeNP?jCc~_N?^p35LW{Gz1EVh+3&TMJgmK7 zueE$5#Q6~K!?TFIc@oDcCnFyefO_kj`TL%a`+I3MDDV8r=&ueC61FW74>%-Rd~ zS_>o2hj<_IBhH6-9~f~y#QVUA^C8{`_WRybvEKtP>8!nA5481n;_||z2Izud<%azLDK!%1Yv(RL4MbtO%V2H6NFiN!Px|1e>OpwwHKUC5cX#i zg#FnBVShG3*q=?1-(~FuXA^{>S3q|`J81T2MkJlJ7n~UpX6*%MMub^=!I=>$A9@8e z7%3-fMw}TDX6*%MMub^=!I=?Z)?RRCM3}V~oEZ^j?FDB>gjsvRnUR3^G{cz@Vb)%7 zW<=hBwHKTj5r&Qg4aV06=X!*pBSC{fxG$Dgqh_Ghf*cl{YF zVd$>VV31$4Kl>)>{_LBuKl>)^&%R0d{_LADYcDwaChX6?3A6Tsvv0!w?3*xaFF5-q z%-Rb)^&%Oym4~GVWXEpmXiSjL=hpRCeXA;9P8D|pZS$`%` ze%GH#6!vElh5eaCVSgr37_4AT7>UIX@LctanCln;Y5yi&eD!z=HA{Udz-McAL=74~O% zg>mSJM3%USWTRSJQwB{R!h1+TP^SD&sIyiKU*#A&sGcj zv(>`5drbM3I9o00xO*)0Ephjl@-1<;TJrd_)$+UkY_+gITP^MH&sIyDW4~4C=WE7( zD`+tI7T9kE4F>Gbyvwux%)6BD&%6u!Gw<>~{>;0uKl3i^&%6uc?y=D4$K7Mf=f|0M z$>Yzw3;Q$g!v4&=F!sSggTZ@h_ID9Ty1$D+*xyAU?C&BF_ID8o`@0B){apmY{w@Mx ze;0u;_Q64e!8_pYF=#Mg+&!k&Vz`Sy+KSg=1Pumxun!Iz3>fW?L z?C*#W_IE@G`#U0p{oNg@*x%hD>Hh8xVSjgru)n)Qm}3{XyF(avk0Ew}ckp+22>ZJ` zgmL$nie2FD4oTpl#J5_|SpI60{aHoo-Ux# zgt5;W8Vue+v%l*`(y`B4#rkm9jilr5F%|2>T{n`ByT_oxpiJzuRq;La|2XMbmxu)niQ75rUj+>YjPq5{V8A$E z1q}v_^HtDbz^uLCjytgpoUeiggLIs)f(8R-?S-JhfN{PG8VnfctDwPvarYQB7%=W0 zg9Zb}`6_5IV4SZCH9nksg9d|i&D`%TG#I4g+#56)FwVU}g8_5D$K8X%IQIq(2I)BW z1`P)6?;aG!xi@GqNauc!y9b4F?hP6Y(z)LgG#D`Vd)z%J?Spe~&|r{`b8paKz&Q5? z4F-(!h|pkeWt>NZ27`2*M^u_P?u3+doJWKPgFHMQ<4#CnoJZvIFYAzw^N30l$DNQC z={S$5G;!Ps>5z`|h@mFV+6(T4lyuxZrZjQf2`T9~j|dIsqr5AMXi1uIZ?G&0e5v0^5C3kxK{z^ccH-`T{F(_LWA+=UvP)2+&_l%yU<|# z`4`-wD)*1!{4O*YfBuE|{7bw)|3Wy&>(9U74pr;VzYw2)k#EHQ3+_;rdg1&o`!T}o zzu*p4VVvJpdq{AHs-)xmZn%ep{Yu-_l_VSoMwciT#SoU2xQdvLd{q~q?faBmOp z9#eaJaJQ}G!MSR+w};f;9)bqr&%Y3#f3g1j3-S4vcz^zd`236U=U;HQt?}nyaJQ}8 zKZbMF&|v)e7u-2a_%1m69x~3mLxVv&&bzBUSGaRn(sABh?YY98!(tCO@2>V-;m+a6 ziB%8G!FhLRFt7ElvH<7Zp~1X$yi_vo9)kvRsNcL~+&u;jX5Y58$?WeNXfRXj%}r*1 zA9oJB7j`#H#@%DkV8%Z1c@oaMhkLGY_ZT#ot_?=aO`AwN5+(Q5jX5Orl$+(9A8qE1mW+&qw0%$OgoLQTUdkCPxygTsSWZXjl4JN~( zM#;E`02<8jkJBgM9s+1El_={hUWXAh7`y|o!*Cb0Fzz8xd*N^ww6rJgAqe-v;eH5c zFnCro?uUQ|gLK>vq4p@^j&4cE{Sa!8BJSvx-^Kk9YL6m8gF!jGKE@s07L5BLpuvE7 zeN50`z`Q=j9o@pXA42U>#2wv|j{70h9!1>IE$JM$z}@Mo825HSgF*SYw*wjs825Il zy`#80UD9!HhuS-eyVHa8;O=x`+}ok{j^gfgsSEDyfChu|Ic|Zw)1^&tZ-?4Dio4SZ zd2nxs+B=H7(A2@c?X||=8jyF!JvVBvHU8Fsq~o3&XfXIK zj`QJf4M;oSo*T8-n$%uv{H*~(e%x~t?zQIltAPfCbj`SbNHiEu$NfXlV2}s*4?%+g zuP|#q&xEBf<44BU*5HuJt?uCK| z1IE2j&|tuqlGnTPwjpuvo*l6^kz>*Dh-ZgZnw=d)g6puxm-n!f<|bwPtU`EC6IO7q@cOxCCDpcWrRi1YZ|-xM-;bxO)s|d0wtkaK5jLEBpGa zd8i9Cn2s~o&hvGNOgvX-9_j)O=KTI8F{leP7_LiUUl+Dy^WbtE8j}=HfD0PPn+m%EPjD2pWtoGUMW~K&fA#1d3Qpbw=wtLv88d|#@stq zUx@QI=EgO;E6&@Pw7>7~Zp7BH#WefAFL`|5ci%mHUlHH;U7GA;V}0Lu+0(a<^L^j- z$gm_1eIFXkjKTBceBZYpjm{T`z7Gwi^&f>6_`YwR$+{!~eIFXk{z|hFarYQBnAaZs zI??xidZf|bMBn!*a{tss-}ec35Bk0@Z4TQC{xe42JIc{^h}uBZ2BJ0)wSlM&L~S5y z15q1@+CbC>qBanqBanLG_(1sJ%GNl`D(72A-ut*) z`&z6p|F`4+EzJM!IG->-XZd+yF3)ng!u9GcNaUM~!gLd+<9EXR_?@sE{7zUt{yY3# z|L;-`o(ta-<%RE$-zk>#RWY=MPq$#7U)Y!9knYPD_P;C4|AhAu_U|c--{EqF=Txm< zoPRG&M}5QmXa`{~2kj&5+fA5%7wswR|6Lf*p&jvVC=cxj#_w=DCf&+9kA7B{seenq z1DBQZZurgco&C3y_u2Z=8UD?bI;PZJw+WY%(pI_+b=&g$5PlEu&%c9j7uFHqF03Qf zt5;NiJEQUo`*KiL`0a%K?+Wuj;eCYtdkXt+Cwz-d;@gG!Q*4;aLHkI$Z#QAzp2Ga^ z4!_6$hkB*-9sgbAox}D+9?d$BepZ*Me@nju7nJgD{@ckr_-`j%_TkqO`1ited^=&? zCR|QRTj@6R-%j%THW2pTPU?m7(59#re&_$ze#h;|W?#{@V#}|NN=A&{n+NhWRmO3UfL5cEbMK3Hxs+?7y9`|90}8{@V%T z+Z}mknT##^o9b`v%OPK{lrdS`jDH`=qixK;zoZYEUKeAgu&-~J|3BXExX*`U3&vH0 zy7+G=?Aub_=YOT&`EM82@ju@0_}hi`N*PP_x7IeGZA06P|8@>-;=i4+w!J~qtNg9= z9o{AQkIa2i$FNTz{Xg9Y{Tz|19d!HfYy8{#V6MG)Ci{A&jH~~NKIr|H&_4f`xi9Ar zA1n*M7ufeZ3-V`MWr0;7AC$ud> zxvK^DR^GY0It_pSc1bVsYD?PMDY#3l@Sa{YA#WWSlh$M(P9?K_F86G8|7;X}cR|_$ z^`w=wbXkQC10Do_*D!I}x+OmeS9x~kvhOaGDUI|opS`r~&Jyi~`M;O({}$$dU&i@_ z`MIV1yfBxyl*<)HYx3`f=?{kK_?<96ekUvkzY~^^{|%o(ta-<)ys8{0@Fm z>V@>BzFx>L?8{l^>xJ@#{qG9<_YwB*DU9Did*RuEXD8(i+Hnl|`iA+@4#K{Dgz-CQ zNB_HMPhox^v~!R@Xn%Q6{7%aItM7&9QNzF6X1v`RWzWLi&I#$>{)NLi9qIhK=r5A) z`;oAp7lctK)D8K4e+=`>obJm(|CMy#uZ4Yo7v_I=T#&FIALKp#xFI~d^ANgPwv0hv ztKY6Cpsx+MqbE&$d5PqowJMf|K7B48{jTE+ z?dkhd3G!_B_iv*I&VC$^KDfR~W4hXQrj#>h<|?y2_n3I}$KQXiOjp`XkTMhcJWDgH z+>kO`WUgs;{GKTu{q%B)0(59sM}zX`x<<4q)6Y`=^uE{3?m~|kl)w9YHQKk~gp_}w z)>6};<_#%-T<4NB>HE!6{>PQ7)1Jab=zp+xCGb90Tl<)&497e>oXL31^ZCE8%yTFq zC4`iDh|FY4nGPY649AoyB;ow`CPN~HiYS$#%psISzWqG!-pB6V?|z@|#l5=k`Tg!a zPp|zxd+oK?T6^ui*Z=%6#_lO%o!Z~LO#ZzGGpX3InEYXjD!DB$=5{gmH`1MO1}z;) z{-*Io-C-p&y3oV3tKV`y>{!Wx{GZLv;V$m+JNdzlKER)>ZV6{>_MPNUQ6R*vpX?y{ z!Hqt^zkB^h&X3iXk{{gY1N<8vp5VNep&R+ZjXt1r=mt6he?skCPWd-O9Owt!=mYwJ zZlELZgByK7KhOYx0qw_!vLmgk6Fk z-hwp){FqzJG5BGduu<@%4b~Fy!!}`~;Ky^UE8vH1!bZW5=U8L3{KCi&+k}mRA8oMq zX!(VaAJ4H4Y59ebAJ4HSY59ebU+G^M{i6-mDlLD|$glJ-jQ*AUK_kD?zcBh&@&}Fl zO8>&>U)hf^_M_wv8u^v}h0(vVA7SiA>0cQAEBg_~ew6-$M*qrwgs~rG|I*mM(tptC zU)hf^_M_}y8v9rFBaHnh`C!q~s!md1aTZlsAn%KnA1f5k10|0>-`6Mq!9F#fA_BTf8K+`{;;(v39n zN6oD?F;j61m_^E7DnwYPAOTsSUUutfJiJ!_grHTK_x7Y^$ zrEF80_^*76&*5LnHie1*%D4F3l3##d*`_e@U-=f>KtEc3;l-b1d=CH8@(VBiywCkN z{7cI(z_0aBe&t(i1OL+U2QB@RU&|i^zt%tbwfsTwYyFd7+m9`O5d2#I0{q&3$glM; zz_0Cx{96Cy*Y-nxZU55JKl!!&kYC%sgnqRBkYC%sgnqRB2*|JPpZwZ?$*=8){M!D> zul<+&+WyI}{g?dO{>iWXS3>_f{*YhWzkq(U|4Qgb#~<=*|0TbUKjhc`OMV@H$gkrk z`L+L&U&kNv>-b529e>EL<0tub{2{;cEyPdqE8jx=C%=wA;y?NE96kp9 z>-CrXI{uR%ZQx_jzg~aIkLPOrBEMdL$&cr1{W9`n{WbbW{y=`Tfsg6+3+u1ZKk^47 zKh|IJ>-@pUkM-B+ANd3Mb^c@I$NFpZkNkoBI{z{HNB&^!2l->lOI)5|z zNB%&5#Af&y^rQ1P^6UJE{5pRlzs`Tiuk$zZV{L?wVSaV~Lw=pVksoU#d<^re^EdKi zZG?|ues%sveyok~G0ZR4cK8_hb^bAGry94Dutlf{%e8xe0ts$A9FA$rwGSQD-rGlaSNqfSdLR99tJha{()-r@YG2!-u(zMZZ~Qm* za`<<&1IBxJ9~gY#1%~f<{qcDT^IWwrVcIL67{jCZV+_Cg9b@`c{~lxHQSZeVITc@w zkze%_gZ|L3e$KNF-JV$UsCL6$%}=cRCD!r~YdMKkKaig|I?aUaUVn+>HSM7XVyz!y ztv6zf5B)&~j2ry{Lm%i*%a3^>w&zRP6W4m|4V2vwV-KKgg&29ivTx=R$n}*S6Cqo-~{o8a4ZCV6*QAHv4g4vrh*$`*&dV!+kw~K9_TW z%{c(D_mg<$f6vduO^@ch4*zY=@qlp-p?-1v=G+g@&3PcO`r$btfH^+|*5@94_uq9M zen0Kx!>5XiF%g#&V3WN*Un(X}?h%Adb{%+4T&T7x2%9W)s(>sKcQgo_eE1tjUYL_o zz$P11XemR6$LY(N`BMAP4hvtg| z=gyM<$(-lK<1>m2@PG1JPI)Z6jR61t0u^MNsiVlhpmAe)y2Nzyr|;5M{`BMm^1pGe zi!2meM*c}tbEr7Iiu|v%oTlP&aRK>5UplN}@L=-KpYxDf_vVvdeu?~I3;C-Sa@3mt z75Phi)>szY|0DVLc55X!WcrQ#TeGAT`H~(b|FYbpM87ppkw2{N7O^E}KKYw%za}0N zd&!^u#jG--$gku-9#dGhD3D%4KVyEXAisDimxO+{K3Yw_*RG(1e!z`BpdWCf56BO0 z^a1^V8+|}O;6@+NKe*8c_`!`nzz=Tp0efO=KLt2BQNIsCZHqmV{S3W;K$rzj=_()#TeuWX2!H?&N%isq_T-Nf(TJi@h`2&{x0ZV?zlHal9 zcP#noV_N?KOaB2&|Bj`9$I`!J>EE&R?^ybGjQ*AV1T6b;EcxuD4t?P;LN3H9L@y9js zN6jsL4E$o1R{W%o!9La8(#Igbnp^r9_lRgH1Wt;Rd@GIYPP5eg=4SxVXa%EsI{@ft;;*WP`3V!77Xaj!a z)4Fwjc6q`*9$@@-5g8`IT?Me#ozU3-&{P zThe&_}| z^6Y0m;*aau&lbcV@WXf5?y6Y}pU; zAMztMTlRzehx~}m#(s4EMt+^YQGT7jkzeO;#{QANkzeO;lwap>%d<^_bH^`sKkG0*3KggfSkG0*3 zKggd={6YR~;t%p?6F-svlOMSWd<^m-l94r{|qm+XLHcJ0aHg zL#*wJSlb)1wnN>t179FEW6}MxRuiF zV|*6RjW6pq7#G{<@tXFi+acEaA=Y{$*7_vYdM4KTr<{6Th|!PYLhVzGT1$wruU4_1 z82f6Kix6X9t#T1!?5kBSLX3U2%0-B=uU4^`F%SD{wN?>hU#-qJz3<*s=bb;?J~x(D zy_vM?(4m^aGh^*0>PO&uNDoBBHNn7TXgn|eI- zYwGkMkE!2-oTjc1@|$`;jB6$IiGHnmGt+(ro?G>4hF`ri-1JMVFORx1Y1KsteJ>w?-RgUJ2X=1NbqK4jKw5PX(yHq~&5NmvkXBuX zu<9bDRo8)<7gLuathxwk)pele#nh#s=0)hb4%EDux)jvB2wm49t-2I&o4Oid)pf`e zx9d{CZR%=J^J3~!z-{VkQ1fEyQc&|^>S|E)V(NlW^J3~!Q1fEyYEbiH>Vm*+>S|E) zV(NmxZR%>IzL!_~=R&A?F?CJgHgz>B{v_4~q2|TZH9!Vy{(~#pl=;LO=Rmp8Qr_7TaLI2>aLf@`?9X*gL}h^}T%JT^90a z*gyP9-OC&Oo4P*6a_m14&r!33dr$wT^wtUaCZy&^}W22 z-_*si=1BP%`Sra#`B8I(yIaVQnknUDg9Eb#QIbbt#O^h|!SWs!L&PMvR91R$U6$My!$0k5$)U?4R;mbv4HR z$#2!w82cx`Raax;5BaUS6s%vUiaM`C_av#INvjQ-Z_H_(OiHu8C_q)_CYgtzV|D$;5xkZ`B2v_(^^p|H-f8C;4^!r~Ep8l3&Mv z$`3z4&IkRYW>eQSnfOnBw85SM@}p)`*JVjO$Ns^J|K!JW>?NQdz5bFPHJiFFi|=BO z0sZUsm;87a`wi${ufOESbL>5!AHDt>{Ud)MKiXhV0{vTcaVCE-@|(IilRp^wOFwjbm_M*qkkD8J5s$glG^qkmJ^XYwEFN9S+k*ZGgJ zf98nLzs`Tiuk$zZ>->}aI{%^kI)5X-&Ogbo^EdMA{FCzQ{EhrN|73i#>RL_yMt+@t zn)pKG?&-iB5wVM22otfS+`7`-- z{!f0r2Vs2H`Ll_i@G|f{n)RjrS zPhp(bdlSZXy$50YPS!r!s>_mAy_U4j4WHs@Wy<{S+8UpoT?Lt6iTEOPK3)q~40h{wNU~_H;tbYFA zvv;rAaEagMybjo$;{mImyLR^O(RrVj0KOk~qVMHVS0=5x0;%uiQCBAQy*%p5B<>7# zU75t4p{^^FR$T$_40T4FOU3P>U(+Q?7TC?-64F+s!NepU5eEA^5oa|^5oa| z^5nPbQlwRvBCNU;-WlTV5c=2m@|0iS%adQ<%adQ<%VRIXJ40PpgPJwm%kwN&-^=qX z)~X9qF^Bi^yBaeXo;d5Be5tD(jhQt1Wv2H^@z*wuHe_*WnupeOLp|BrdAwC;m#BH@U7vt&>AEtN10~ia!hTF$qFS>O>k`$Pl~|Vu`!RKixN|mjiMVsdy}Yp> z_!#x0@8ymCo4QJ=@8zj~eJ^k9-_%vY{!Lva>>oZxetj=betj<=#Qf@edFo%^%ab29 zYv=>>tNa)D^2UGJ2j*Ab%adQ<%adQ<%adQ<%adQ<%ab3z1s#E3-^-i$Lmlb(Lmlb( zW9nKFKRL&cU*F3IVW0Y5p8S|wD}Lf$p8S|w)NX=b#ZOb0%egi2Q{T&*_;2cp5&unH zG2%aM6!NS1k9&FYtN2eF1;4(RXZ(b1n)najfzApEF#0DydN=#hAM#su9az6$Ka?N7 zrRzHATe_|T>zAoZG4}63eyc7;YWpX@wtwmeYm2T+G4}65KUQ4|xKS7FKtEPpjqzXV zNBb}N;aj?{#`v!b{abZ4!m6t=@rV36{!o4$f5@-nkL%eF_(^{Fmac0u@sslFx@hw2_~}~lpZq%hlV7c0rY_6GfAYh(kYjOu z@!~)Eb^Is4j{oFWb!CgNuYmqlUD+b+D=@#Ru51zZ6|hfLSGE}Y3g}1Gl`Y1;0{p73 zY%%r~(7&oHTa0}L=2z8~Eylh=%Wvx9uzs1kIBC_zv1Uitm9b{WlHb(Dv1Uitm0|sI zbX^&1j&xm_$sdgVOV#yNUU=>O$eaE^kGk)s*3+l?u z{)PN{|6=05tLw_l{>8+9>|ad$cXeHv*}stg`PIeayJTs#0Q*}XKUjL0*lYKqLvtO} z&$;2nQ!L&-z9{jVOTrefXc9`?xn;%0>)M@Ee{)ZLzVg+&iw8t6B;LO9(Zy5FRwbS| zx#i+6YYV8lIQ3b=A0A(v>B+b7wodXwt`JiH{s!vZ(B>n#8S})mU^crU~(+#({U9y2E+@sXcOM|Zw?obrr_ ztPx#o>pbEr%^OGmT&O&8vSN=$|2{c6$MW!qrqOlIpX3;icc>Tr)BcwhVO$~Eszw(P z9}=GniH`2oEZJf_|9o5e=(C^XCr(!XyQueumM7kkaZc0|t7{XNNGK7Nc#*!Yxlv0-Ws%3 zRC}W<@cgYU(#UjaTcXW^PTPyij;CVr?t-Yx_2uJf@`7`L>PMnK)mOagN20%ab+g8+ zekA%UnlU0?^&`>WxkEAWsvn8|WlW2o}RDZs{R6cTvGMt z=y6Ht5g7eIkHF{$dIUy4&?7MVfgXX;5A+C(exOHS^aDKtqaWx|w=rXfEN1MG#f%-Y zn6X0^Gj?f>U0P$8;~sh=IQ2SpDAQzYAfDM$LaM%GT*tX$Pu)VqFI?FtX1|z)czxa* zqU@O@#MkPm&t(XpSEvo(zaFGhHcxnZC>@0=nJ-w*uG=?6l?@O0DFM# zpg&;P6#4^(t)V|)*dY1?hHauhVCc`x*FVB`dz;7RxBIo_vE{Vox5s6V*VcorA6sv> zK5aciA4dQ7yx8+)&!goRf0%dM9&9_Y?Faq9j-f-_-fTOx?GttcJ)*sB&$gZ0_HX-z z?Ju?;+5TnC9sAMq3x7BB4u3cHAg%e5)_h58zN9r@(wZ-6&6l+1OIq`Vm}+7;VycPZ zh^Z!qLw{zz?phqP<_qI8F&yJE^M!Gl_<(VlxPft*c!F`6`NFtN49B=k4Ch(_J*qin zKhPtvHDBxpdc<>UzU(;p53$|en)g5OTXymXd2Bgt`R#Gp&MoctxsFemcPK> zs4tAy@-K`raXqs9@elKE+kc5ZLy{PteJ-Xqw12YXLp?=|c_h`l$l z_bm2a#@^%DdmnpGWbc*iJ(Rt-viDrr8$plQA7Re~Jz{@^y%h9_{So$9&?ELo*n2^b z*dJj}20dbbguNQ{i2V`vaL^<6N7&mzkJumC^JU{C1>SIW|I)|Jn{{va@{wtrHY0baPw%@a+7KLsQA9a;@B1 z-O4YReYB|TJI8V7Zk)EDXpwp{!{hng#Wg=((6U=Qd2_)}&e*j#7WBQ+TV`oJ&v|55 z=J+Qo4Us#CW_KnWEEGTT%rJRz%f5s~DP!X6{5(*;6;)rPNLns_%82eVWr~gB#2e+} z-#z<;oU=B$T>5Fr_=&r!$tv9n%d{Uv#%KE>OkT}bM_!ZJ<5zUJCaxZSTGoqA7T;#_ zVsYk&Uh?hN4=$M6CtPe?KUkivJ%7RDJDSGMyFN^=tGVOeSHorVXMMlc z>9(SWlt1JvRO@&WH}k9~<;X7K;X5uxx^X{Nm(K(ygm+3?%Wd5wT$UWaExd%=#=V&P zcX9gq)$q!n_H^fq6=GqkOc8^N4|YeiD^v!JN%Vgyvew^CD z?KS=fXU@Db5g`{Jabq9N=4LrxETUS?3T}_BWnG!EV8rs0Io-yG8@Xp1W{!YOsB_nF zWh2tZz8-uV__x@AfA^u*C}n%T9(+CAbsMnv^6HEefxC01vot~w*d`OhEDVcvLUR-oApk28K&#U$sg22sTC z{w|yaALb$+u=b4Oe4d6l?X=Wx)0yZ0j&t0^NcTkNDSUq7tCDWil48Ved^vY)vZ^?{ zmS2=D=dSEB4(Idot#KvYXAhPV!0w{LZi;auiS2!~y)U-+%l1Cn-e24MZky*?@yu?G z@n4X?W~uAW696hWNnd@bjpuo&XlpAHAAT`WUvpB2oi zklFpNm&ZA2d5D`~;qT;cJ^D*0Y1UA-@A%c*&X+R^5O3Pt+e!6mQR04W(mIz`mL|5( zF_aFa(jj@24yDo|vC^SbI;7r|4yDo|^{I3yl@1-PL#cE~Y@e~59~&vRjqy0I&5V)H zTN}qhL^eL1+ zU9C@{^hvDrDU?2ml|F^iC$Z9JQ0bG{wsZT8$UZx=&y=jQ%0HZa-K`wJ&R6dzwsY_M ziS50^{lrSQiT9iL6We>Y`-$zn=l#U`^A75m0{}6xId6cR_z|U}bC)gSQ3OBgWt}UwDqs znc=fw!1(;x&>`=rnkoDY$8*%z@HzSbMtk)O|KsP<&<8O1bsy~4j$`^A%85SE-sAS- z*1K!JUSvJT-@alS$Y}B4ySw=uW3u{n6&;^L2bP?P-&qQsJ+rlps>#BSs`a`(UbHuQ z01y7h&kn3PS5%?Jh!nwj}Oc|O3a=2J|J<77_ay5_x^M2 zO0T?=M1Oj`>|2l5$bs<^>+urn@e=Ft66^7D&D7&1#(1L^?Nj=__n%`|-!qN+YN^MS zIKTG1tA9(h2is26xDxG0kDEMdT#5Fk#+7J?e=}d0Uz0Cj-idAf*m|?|spLu2v#o!7 zUjAmj5_1YYF6v*8i&&3~SdWWXkBeB3%gh(Xl{jC2^EZF**|?P7dA0XSc=QkbDro-h z0P$TMm-02_UHE|ydVkm0*bAQ8ero%#o=1r`dLD`OJQAyaN{kPB9{F6)BeCi;-t?!( z%jbF?4bNS(Pvv(?zxO_#{5!ti-5Qqww*A!hU)!&3e^;+0>e<%6JuiPVU-xibxE=fL zxZ-2XEPj0b_v2el4!zXBh= z6Wq0BR1x?(Y{KMUv27qj)IyWrZLfQ6p~?G_^$uBN z^1+wC4B?q1c$Y7|4x5uH-ilf}D)~8_!Ezrkvh0C{y1nz{cN+|k+wSBH!|yJc*WUE& zu8+%Lio!6a=MVLHGjVoTuFV(o>KkXfzIA2{`rcA_o?DF2uUCR43cNy;U z+-14%a|d65f5I2;1e^RCetIX^a9*rCK9T=H#di|N>^5qgk??!y;7;&gNmrO-*oYdF zdnee|+nwNlA}9P)Ifjyf`~Ew%b6cKn=VwN=E)^ys4-J;(-y0M$u;Lui>%~6uXq!Mp zuU@A_l3X3+JDaYA=Nyn-2J<{34|HrAj@l*sugT&W^YIM-Hf_e*1!#+R=6B5>4-Rl0 zh36qn>%NKC>$fXw9go-Rx_j~bcS`@>Ior#d4<@d!r<3o*I)r`wAMz!;UptSo z+uJ-gzum7bk1eMyzdbJ1@1M$ZAX{MCD*DB~-=>>2)g9BKJI08!Zg=p2XpEgX!RR#W z7nq#jt(O|kH#xz3t44*JoZ$0586!+iaII|12$K^S*~T5+A8Ge%KeyZ4JT|}GuPu)) zr!BudF4I@FhfmE@dNZ;KrB5TXPa;<@WD?Kgpbp%7Jw! zn=@0MpByOhGjeMBBG%OV-LIOLKXsmCw=b7wbfh^G*p%XhNOLCe%EeZZ=1gG1kjjzf zOyH3LStHGvz$3E`Mwl~!AAcGiVa@~&4V)cr&IF!)=aU8h+nK?-k$UfEUR8NISA_#kS%TxD1AP23r{%C5{^f~)Mx+%fQM%J|y9 zyWcz2kA1%JuVCX#(6f&xMEo;)xSwYWCMM%d!^ZacgMBVxpI6xD820&weePkOhuG&N z_85V&KEPgVY@Y$zXM^^cp?#KUpE25JkM^0QeO76oVcLFbaLP&B7T9gw#>oYW^=fpEZ8{6k>_W7HAE@z+D+2?rn`JR35XOG1mqtP?Yb#1I{ zFEKvbXQcMosePtupS9X&u=d%keP)aCA}%U>`@?y!-Nt^`=Cu2=Ww2$lWwys++xEYL zjSk^6_X6Xt*Z8B4y}0xj(?jAt8t!O~FZkGt2@kp+{%lMzc^bxjC)mVl*v*|_aH`J@ zMuH!AD%kVhtJ)YP5AulnRvUxQjHq$l^V*p6#VbZbkI=cktGuW6FtDNj%^v)D{MTxn z?&mzJJ?h_mmcX2esNeX(eQ;tM?-Bn0&T4G+`4e8?y)uCMxf9I&v)A0)OaE{9PX0E6 z-NqUV_|3TfA@=&bTc1_)c^)u*;_Oua+?l*_8d@$*#3H_!(63jW_o@ID`C=?6M9dQ1Eau+nGZXM>?*dp$zU8uSSc zYJ2VvL(kr;txo=|)_&_hzwl-vHtxOP&@L`*`2wJwL_Kpotj` z8!kxvTqtnc*M_kDjDZh{3QzSTo)Yz{=r!bdVyF8aVfSTt(6{=&G`7Ka2deK2B*u3K zs_zRV#&-v*?+YZxcL%EPlOx7=2deMeBgS_Js_&EI=V0;Of$JN$B5qi0pj&z3;Q;#C zGH$4g+!+}C+Zg*EJcS?Ot`8XZcIp@T;dk&!JcmDOpTyrwaq(|>u73XCzbk@9s$X?K zf}i2;k|ikwQ1efRxIc~@MSP}qe>dBOt;B6cb_KUY8}zg5U>@Rfxf<~A+2OgmH*(c~ z^SSzW$V06D$yM(YD?Uf@603e3)gQ6yUyaqXZE)Gxvj4=-}xW=(14;@y+eLgk*3m52xSEiGSNm5ccCgobir>Z?lDkdPNXY%9+U z^X59+p6+tZ+r9XF+qM^Foeq~d*W*hLmAgKARPCAZGhDXm^(=Y9_8k`aqdoiVw_v<@ ze~f3hTa#u`at&u2B^S>h@g^{21%~X}CKw+uHau59ynh0K4xkHQts7$K%(5%)v(W}R zw&gVXN57xX@ZwLE5m91vzupq@x9Rao?2jh=Q_Tp78u{T&hNoh7~czx z?|H>@eCIm8#}pXf3$4~2Vzur_weHXd)w&~facT_Daj~r=2yf;Nw`P}l3#P3BN6Ngv!CGI(Vf4$O_6e{K-*#NW$1$zJi+*#ZlfI&WrZ$LE`qUU4p-s875%PhPjo z?2^PU)vDsIIgycg!lp;v?b#1e&aQ`^b)P&vp1451e(t<=R~UN-7ai)J{3MKHAFyYb zJ4DnI7|W>N2D+c-Tuc1HXFc3(du|ZdozuoWnK4YFP5oVU++SA)Jbbp8+j7+7#O>Cl zbH`tJj`-P2pE`N^cx%~{l}0)P4tr}^m&cMTS-iCjz6riNjT2s5zrC*q-v;j725$Qr z@)*3Q){A?REBfo;-TRx3-u!xV2aNBl#&3Te^w&Yyf%kJ~`L${7ud_xIzTW=(?8jdR z)tvuJXCVH5(BBXG`$2#0`0ragFyg<;y!-2*zYhB6qW-z)Un!>fV}S;|pTEjFh0)y0 zv3TpCy01j-@n7y-^xd^j`uBs%g6`)1pt2QH6C(Zl!H|%9eLo1_^kdq+jDhz$#`^r8 z{r)HG!CMDaeIVA0zuY?L*U8-dIvHgvs`idH?XQDM4flE-gl}qnyWVf=-p5pizdri5 zaW`z>ue~4i*TK8L4*L7S`&%#S?+5*L-&^Z^J={Az`0Jq3tzRdjlyIk?oAB2`e;xGV z(cQ?y!Q}J!`uum>fVU3%pC7ErbEbdhGqe4sH}F3{=zo6D|NNjA%>8xE*TVy71Ap!P z;QgtS`R`f>{r#Z7AM`@~zdMJA6uu1pT-*&C_-n6&{~h;(Ve$9#bM*c?=&yr*?7bVY z*I&myJNi%1gTD@{S$M$j2mN&rp7dA!yJ~)&%zr|h^ksksyq~{f4&beW{^urY{tNem z|L(spdVkkJ|8o=fcR%QVZUWKwuNZs%ae3?Nzh4jb_XXJa>qzf!xev+swRrL+@9!AD zvv;W|95sOJMT#a}#3Scws=oys60*6{AUEIY)x@*2_jD5;yFuJ}a~pSYE~x z(s4n%-^j^czw7e$bjRoL`rWXvjXN@v*YC$4)p1k(93bbm*~Q#SzdTOdHhDVN>EZR8 za@8JZ%Mq{NN7D><%AN80jcJn*2F*hequEPmO=?+ggJIrRfoAK~w* zl^HzXdusZk#Q$Ue<$sp;pZlJLf5+b#^ylkA&f$H(g9g;k0~bGizw`a>PQQo9|J(9+ z?{CZde&_q0?|1kA?9ul--|u|C^Zm~M4!HmO`&+&3%y6Ei*w~Ms4_5s2=j*|mFWc8_ z?9bzaHIM#$Jy`Q)`v#~#q57s>T^YviOm+fmd_UG}znn!=W z9<2GYea*)HJU&?S=+D=KHD9)`+1Q`Q2WuYv`FgPC%l0)J`}6pq%%eAJras!9!+(s2 z|J}XOKW>YE@!R|Q@om7j0pA9E8}Mzww*lVim>z_$V427DXvZNRqy-v)de@NK}i z0pA9E8}Mzww}F4&20CA=;uifrhW8VHCH&ysq5SE;iS;M%ltM!CeKx@TVdB&LJ4QbC z_2AopZv(y!_%`6%fNul74fr(~e@|1Y|K@Y` z?^69Uv3gIc_j&(@?_yBA#JH;*I^-SIUr304uD*XGBt*9-);!<}(fq`^Ut;x7kcU{y zNv!23es}HHi_G09`ZwPR0lCm0_|=bVcrXt1hllt(q391-{kyAv5knv756__|^al+6 zJ+rmUVj%t80oLt_H4nH9Ke6tYSp5^^A=YvdYx#-Glun;GU;f;AHsH^l?{~i6c`?e5 znckZ9k7A}-6A*{Znt--uO+ef=YXai2SrZUr%$k7pLH(Nq2jaC^6A|oL0|?L22Qb>JUySSEK_7Sye%%Mw+r%{iZS^}L-~boed)&i`qZaLpvYscd;gHd+ zE$WrTH5_BI`jzMdoX~+KXW|;JxaFI%jiS*8y0pfN_5x3}F2O|}^Z^WA;(x$+hCYDR zkJRsAT*yKA+~XcjtaOQW@9!{Pw%YsisPv(A>_RvHLGws?AQSw-`~81n&b8OhoA>_* zCvx6v`_J;(sVF1M{j>kuc^~@z>y8nlyQBI3v-aV)hiZM@QVVxc4~cQ-4&$2N-m^nr z5BFUU=8Zij!+)wCq!vv5^7B+r7rq{RJ@_`@+rZtnfxFFz z8S*%H$+YTh*2}r>1qOHDedQyyP236olk1AdY{sMe`I8*?PQSi9|Eg|>OJzU2E5{t) z0sfPFHs5~!TYN{=45&Ed*(1)Y&3y^(TFkwRvWCR_7~IX6dm8*U_c!{!hA{^3nfo5_ znR9UTqrNYkc5C-*KeyZ4JT|}GuPu))r!BuduK%SkbKjPDr=|O%&*;90bzjDppc7)< z7qRY(Sl>(O_V(C$U-ftGZ5}-qwz2!Q<+0_|x-$2OiFa~pytr$OfJa9j8tk?%6~=qG zUN81>2UeUzoFrEVw^y%I#KAm|xH$)8muP=Ed3jg;k61l()xQy|wvKv-SaCRti&$|x zst@A7ncqYi?B_~X_qg^3qwv;o-It3eO3%0pBv${Kc!#R=oOrjY^qhF-s^^*Q@gCj> z5AIpO3vBDz{I~gS^l!Jfd2D{WUt1o!*n-;j_mYnK*13JrEk*7`Z2?X(!;XU6spo|_g${AKOc!8K!Y5obJkJXm{A zDq{S`f8$;JJK6!`J-iPLKJWsgpKeWNhg#2Lt@Z(6%|opDiFLn@$3uCDwVcFSeqzj` z>Ms#LervT;Ahj2N*KSMdZp!*3ZS?hIWnA%VMdCvj>$=0=%ujqS*|YB9H@{|_{cZUG zw@115i81%wx;b%$$6rhM{OB;Z;(|GGN4mclY&mwAo4?DPxbZO?gYzy9byudJ6L&Cd zv^ZG0zuT?a%($vM4~pK=o!w^VC&evKompnC(ahcZ#7l9fkCc^RMJu=`ziAg&p+ggS z{GF`s@~0}rW!ctAzO>|sGpb9PxIT~dlW`qhb*dd$K6&$7L*@DOp9kvqPd53HXNSqL z@4p&s?X1WcSooq`xvGztnPo<%nd6_Aw+inOrQ83W>G;^@GE;^0vU`q_p(o2%kz#pC zd3t}V(2N~($)Z;p%2i=QL*sIv68TGZkg@$Igm#UaF0!xeE1RvJ5&B$-B%=3~A@cEF zZ-)N-bd^AXgkkdFt8+rz+i^fxlx;f$p}=D4UE`K45G$pnQW^`AR_9I)sd{grW@viPycs!Jc82uRE z*Yfju-wk~NKeky#KdP2tZD8Gj5c*L)c{vdFOiB9Dskk)G_Frq!kIoj(?*!g>hJMuJ zLQ&_Fn=jChJ_x%Qm=w2|Jcphu<-AqlX9xZ`BC4k|Wm+_OD!nq+`Kf4tJbgcV!?`f9 z6?xV@x5UZ&P#5ylTU^p9zJC^Zj-(sm%pY`|JVTbPa*lqHn>>9R>~PNRh#^npug9G+ z7wVFy;WIxwuN7@Yo}3xmJK08zBhMFE7CFD9*+rh=S&unSk4i(Hv1M*K&sE7oo+@iH zyCMC`kmsFO^Se#Ht45w7-;Z&sRPRilhsy78zMS_qdDfpw>3&q_l!G|4t!_@YK(1uu znUtlZTlD?xYGd_qs=1alW5Yl{{;TN4Yy&3?t9X zsa4%3`6iQR&Y~7>)>RA1^GoP+ZcOM}2XSvlgAg}q|6Kvh(XE9s?u<{;@ZEY5wcOGZ z^YGn|7q)ks9Vo+hU%k@TeXj1qd^c4>Qg>)yCl>GS`lYmcVcv*X=wa;fx^D8vro=-2 zH?DMYXI5Df3;Dax9^gK*RZSt?-nb3&3Ud!q`jPJe9Qau-KM+qx*ttl!gnv;DCM54C-`plfeqY)+Ya;H?@qUN z-|l&i@8;OH$N9L&Jifa-{X=eG>sNetK#u(G^-S0J?#|8S-2<;@kdV1pkDBhde7PlL zu9|C=bGX(Ae7Dww;{cF7H z6l{Bh@8)7{R`*qY(@F*Hz|I02E9^)@6P`zx%*r5M`d@_Z{`KHoo_B( z;=8lTj&*jeh~T>o-+bL^d%QB=4fb8-tXtQd@1B_(bk1Ds#D33hI~rK}^es>3Wx1U9 z_Lbnf18emUWNNTV!1fNmP{LVSt|oa}EL|7Kw=+ayUXpgL<2*8@9XUHR_$5&Nk&=9O z>(~~~o?U&&-*ZYjr{(cle78uyFsJW`XV|`0*AmX9qc5;cVETyI@V%?q*Ei3K*i`eA zlE1~wB!Lc}mnJ7-yUGFBrb+$Gfw)a|$%*GGA7K05B?||Z?dU{)JXg5^->tp9d|>DE z1K1ayt2`m`U6m&!wpV!q+YFpvHrROTJM3%TwUNOZ8+wcFOjCgbFRkk1d?O1W(<0mQ4 z>~VcW{W{Tnx7492V(I+ul;_Pp8#n;4P*H2F7moF{%>mYwC}oYiDYLQk#p^~mqg29 z$N27wHpfKr@omWeda^a5aM9f4IdpNS$d)38Jm->~6e}{-<-5NvS30QNlI??!G#7yp z6UqPNd$Yxb_WQ_r@Ubt%qEQ(<{d{s!O#L>DJh7j55VM|mneAWcnpXC^T#1}}^DYr} zTJ7Y!Kh4S}uOF{N{`U@@5J#R$O`cbZB$3z8=OWK@L$k_He<{Ux(+vre)oQqGf9u5& z;*kb@$^U(<5YG-+OU|5wlgQ|%R~Szk70E1PPoyCaWPwcZwV`PW%eb-m$q88?6MXIA z+2!TN=EcYlSs)W)3uJ*zh%Jx>G9fNO7RZFSbiV&4$Y15H3*yx4P05))SGa7ybRv0P%3VpOOEZr=uw~dZ zer9Po zwn=sJ+7Tw9iuQ#Dc9IQ>4GvN9ry&MYtWXd@}o~Ze95aUH$ z+>)1uC0C=>n_^#Fu-|f--Mft_vPXgfA`XP_jj{_d9 z9|t^IKMvYwt-VZy9o$0B#!G$^Ejwp$AWw<<#pKqn9(Ewl##Rr@E}uO?p6m76$gNWc zkw@DS-<{#~lu0g+C8xF}@@V@ZkG3E3X!{|LwjaKm&}XigoG(q)9e?=lk^%$8{H8<5`QeuJ;{Dtk$rB%WU94_# zlRVR7(#r-nGLYx@M+(V3?IXyeV>RDx*R`a~^mb`->R3%49iLsyyN=J~(ear)IzIE= zhFKbj9A&1Evr_44qUxsy$Wu7yZZW-lX7W5%?R!x%Z6tXz?Mx;`FhCx?mhs)Z-7?4~ zp^aR`K)sfcN3UPx(d!p^^!h~}y?#-iw^L^q`=6gj&MUp26nl%GCr`D9ri)eG3zDbT z(@RB_$`#0SMoYV{ObL!Tzk4+lnwk=c9kUBpP` z|KvnmRQ~V6PZ0~1&yxqSQ29K05DS&hljmrkB*8`1y)z%gMdknGY**e1X076#|6K1k zB6y;9Y4VH-pAtNn$2w-<=UnJ+H z&zC2>`J>0vJjd3AqK7=5I`zLxSaZsIw^rw$5++Xi`*S4wEW$pc_`}(Sb*5pTb=YSh z_SuMiW@4YE*k>&E*^7N9W1rR7XE^rRj(z51p9R@xME2Q{eWqleHQ8rS_SuwuW@Vpc z*=Jn#*_VALW}lVWXK41>ntkSGpT*f{boSYueWquh_1R~D*caI6Nb~m&a$oLLiT589 zJN9t*wqHk_GWlcffdLsMTAxbdy3hA6N_=U4R<}rZl@qC-Zw_vECgtl&tk0t)&UN%T zlC;h|CC+v9Ig+%_NTqdlDy=hBsn2F{jwJQjEY6V>56@=ftmimKGVO6*WO#@*Ke6r? zXGBIGVl5}JmY;aU>YEGEAKF{zOBk0qcLER2$JoX?r^2{!K4#=G=UR}{oOfYd<{S*; z!ugmPmpL~x?E`vT=A6y&^SSQV(c?1bbw*A;*YXo%?#z4v-whjR)2X=AHrI=^rK8`6 zJLQjbp)FmG3U%@xZ$ewTuq~<6x>PJ}DQ@)cK%ZWjX-i4_j13Gu_W^Aw?^jEmHoqv|^2&!;2L<9$*%-KuRQPjJ{Z=UmFx zNuu9)KVtDA&8XJczPrL!$3PoI+o+_qz@ zlV^SMobIR#mB=$^UP^b?&T#Vl{Mt{>wFz0sQ(}99Q+46@4t%6XjX}=mU%XD9a|ax^ zK>Y~v#CI$2rYx10JY83WxrdvjCC{`incUp5zdG=>y7iAbBY)aLo;??)Ioq;~AkU)Scg9RxHNlTy@;?IbV&1ezMQZ z>P{NiG8R0WcWrkjX3i7~p5(~~xFfe`6X2t^nzcaM=LN>p)o?$}A5 z0)fKrwxjQoC+cicckh<*RR!cplfSn6T8}&u9wio;kI{+;yLoCXcw3 z-n}q5A9>1taLc)MG`+;Q3Z?we>9_A|@~r7Q%K8546!N&)Q@Z0Ko0I3nPrp0!=hr9C z&5w>c170Xgo}th0b}FtYNS<%%&v8C_>o@X*uW9D=?YEdbUsaRNE0;Tyr`7&-&g_0q zk!N! z?YBHfp86>&Iw?~;LY}uz#W=NY_Gg=w$0D5g5mm@Jyl#{;^n)&JU+9q#r*5H8@^7k< z#p%7f3Eyq@(c6JGFd6xpsWqByW)}QCxM0r!_El%*rQp>;-N;|- zmoI`{n>91~5k^0&wr&pA8Wb@45k@~hg-j1#?VZKwM;QHxrFDW2*VtzCBP{&{E&T+I zej4O?P2^nJlkyDPGhWR2v;*at(Q$xC8egCCIIG%j@8*3TKFJmE`T5+Os%l4oh7**1jm-ER)o z5-lEI#`d|6XP4b()gyn|-Wg@}r7k(kX8m1s2^Jwwwv#8snzK2{6MCee-0?#-w$C57 zMpV3Yp1wBoXfE0BnTmY3YR+zAeTO;Zzfvc){PMX%gCuD(4h+V@^O%kEo#*!bhKqka7$O4%Ve;^BFg8f4l$b@)UEp0QI<78U$Pgz+< z4o#n&oW~EAlD~d`nsN2lrUm4V_xFsBJQuF~B5Gb=Ku*jR<_z-8O|eisQR4~n zW3Dh~kOy;xIfFcyE6f?>!CYa^AWz8pPO{@CACbTDNY#Q>wmSNM72eu5G zhCGX2>np!p+k^ZkM|GB~jy^+9ajubUvacR_3XQHTkMAo_9{9bAk8Jzl!Rg5f zzgO{*@9rB@O2dv*}g}WL2_4*aY2lC+kx(K z?UI**7~|y8kIH1-pXIuIeUc-)4Qs-6S>>d1VSIR$0j{L{7xTZ708*jCYT; z+b-r`J(z&;A}%)mp>!PdgIGAI#iMc14`N}SN+aT+AH>2m?We?{eR#ita=`Sx0q{rV z?JmO_?FfLg!FSE%kvXdZ;K}w|KwhgjCjg!<2eQbtPCw=?T2~I<)%tPpZv2Pa#Mq~4 z&l@Q+$_+;fIvAI>CBD11jSye=IY>@zOXSh^Lmq8E}B9D$gF6K+eAM)tK&rR3I=iR#{){|2R`cB+NnRBxcaA5gj@9JR@tHh2 zK9fhsXY%Oy%y&mE%qa7J)|i~BCa0FE=hh_8HxRFp4r zg*o z@|0hpOYYTz*MB8r_FHdaWnVPd8o^uNQfiJX2qKQWW0MkUTe+)E23FRw7TY8M#H&n2hAf zw0%$T<1~`*B1S6zCnw^f@_+Im7Al`74`QM6dGa6@DxW7$oAC9)HQNXBUBpG@|Kx0v zXJzoCXS`gL@Lvob`CR^xlxr@vO&F`H{&9UE{oWduFSaFk!RTUj0ox)Vizs zqWn{CpBLqya{C-9|CHP3OMk?6dxc}YdNZ~Ocr|8!#IM#G<5WxA-#r?gYs$>?hn(b# zpLN&1nQ=;sAz9pJPE)t=h9pz^zgpf+H?*9a_v3HlF63ZCF8$(r{#(TlXF1O3nvsi!ki6*1P z(uR?tzkL0yJ3rMSacTUR&<w8A2?{RY9mY=^{z1Q zDo$xQRbSHdrDTvs1|^#`vMHIRky(vJnz5)cN;5_^c4@}0bRvyTl&+-FmC~U!I#jxq zMz>1m!suMhg)npRkLK5Ye*3&J*Oc4mkQt}kKA%iF<@UMdQL9$)eXCY*oK-7WJnr_n z=t!$putcWY=cqYCZ=bIY4ZVHty2`2*JY>}h{%+L@rq6u)TsKGN+vmOcGT%N2&Y$`A z`Ec&cx6h3;XTE)&oHFz6bLO*Ft>9LxR&csiD_A%5_BnQfRV(=Hq}%7-SFKvXXX0+3 zlh3zm1wXZF1+QAQf@!DRK8MdX<@Wh}-YKf49-qi%Wi5bN0qp$ddS}4 zYl-J%87Q+PX-!gVUB{p8T3*7u>76rc#G9W)5-Vj;A9Yd}WwhC~hY8Z-2Jp z&$d_ZCVtM##Auid@>hByrwt1>~8Ob&2a8P9j^s<<*S$dglX?e|uLx@BZN+kt^aw;vWlt6J`Mgv;iIcMY{2ui3V*Tc1o3Ev4~{Ih5zphNmJ~xSY-L?^&uOK^!U+S3oqUlekB^B4YW}=EPg; z6%*SwS0L{CO{BrW#-F)Y8B`^g;QUB~i> zbqAIZuS=Orw7j*3cx#I6;?{`-;^$AlCxh*~rDU6|^S=wm6i!1tq;KpSnsa5f zWPwFmo?5SD4wUcX$?4n(S81Ck|2wTK1co;8##M7o{Xn&&MJPjbt+s)BB|JTxtkEwJ z=6L!kdTw;!%Lq?zZ{?pH=y9ze+t2SfGcfS80>tZw%?tG2mydWu?InTLX}o!PcEyT7 zz6suZZEX5ZpzI!Re$`wD%v>uQ2pAjq_1)cpc{#ng-qA_~c4-?>HWM&5qiiW)Y)RQ( zz}TL$Nype^tF1|$$F%Jg>3Th||K@et;Zyn3IO#Te_FQ#hI_J~)!+ici%?!@;ai0-? zl{VBV^Yw1xGs&_#rNXunw@shJsXA=~aqkqlozvr25oh@%uM^v8A#vR%1)N{2n!*{x&RqP(S@d6T@@HE&ue zXaDnFOj9w?*`s5iijB@89UE~kJ!@Dn5;otqT4|^7Shp(hYlTWXuWUL-eDiQAXHkzD zv3UM_^HR(`O^Ez)8 zTtuAbwJ>LNrRl_}_JupuMvWz2IyJYGYx)Y}9DQ>-SuVXx9Oh(q29!=9u3a^?bL87& z#FM5!47xbkHr@y@Z&2X-`!CQjYsi9m`ag^81l|1Gw5 zfA2F&EyHpJvgItn=NlSV3gj+XjJSWu53%Wg^xDM5d>ETb*#ySEZvBGTo;gYpzn*Sz zY?G-TenUpbcK*e~6;{ludabAd@acZ0VE zdGj@9*rwpR7rc4wlX7dY<3ry3ZacCoc;T5)j{Q*2&w`5@Wgvd#xvzubtF**jx_%$L zQP}$|*x0ZigQ7(;KL4rG&%uj%Z_)ND54ah;bm|x4MqecnL!Y`tJiB{xF>&o#;+*|b zijEmQd#>C&mFOr>@VW8@VSGXPh%i1<@$pcRIfds7Yo|XXE?xJ0MER63KBat37++Jq zDU5F_pB2Vu^Y056pO5r>GxfAEF{zyAvpFA*7C$}Ig)*e?Usyc9^GV|Mr;3R5jq4M4 z8c%ODUh)!R&8XbO6KlnYSCb|s&Q+zPD46ab_lyY?AX zmBTJTTt>fE9g(Z+p!i(ZK@nT^NUpAfqE7VZ`-pWN6tS*@q8|Pb|8LhvVO*we3ga^M zRE9qY*{u32rK`lcEF-6|K5bZS|MV@Yv3kF#1X zVVk30#W+Q~pH2YJ`GOY%PPe4w`K8M9u?LoUxmMV@Ex}uzv-0_O%c4bu+ljJaTzc+I z-517tPwKnWe1+@zx-a#3dc8Jvde9HXB~Vuftn2!S|CM^YcMD`#q{ao^-j{kjy?0}6 zp25g%_ISCCv~n0}&Q(8Hvv~o^q<($&WIi;0zN-JlUR?aM~99vqs zy0mg~Y31b7%HgGz!%HjYm)2fJT6-30?OCL?XOY&PMOu3nY3*60wP%smo<&-F7HRES zq_t;})}BRLdlqT!S){e+lGdI}T6;8Lv)7Z>o(|aT>7=y>l-3>)Ix%}j=*sMcrM2gk z)}B{ddtPbnd8M`ImDZkDT6y9Xc4_U|VKZir z4_h*41+W=&CIDM9X9ChXLy*=P0({DxIl$M&!%2XC~4* zGm+MriL}m4q;+N@tuqs8ota4M%tTseCek|dk=B_HVvac@LM$?8O^7+>ObM~boGD4` z3`$yOP|`ZHLTnUIymv~oyk<)YHcIi;0zN-IZ|R*ovIoK{-7 zy0mg~Y31b7%E_gblgs~M?@i!-sJ|bAu?4+ zC}l{K5(>{}FO^hOG^kV>g_2N)O7dUtb@qN*-RC~{oA3AA_jdokr`PLVZ^u6CtiATy z@3Yq0`+T;F$w|fJq+)VXF*&K2oK#FsDkditlaq?cNyX%(atcy81*sf_R4zj*XCald zkjimL^v<#eQSI#M|usho~fPDd)IBbC#U%IQeubfj`RQaK%|oQ_mZ zM=B>Jm6O6IA%}&nLM{xOgq#<)3OO&S9GO&(44(-(HGC=53P{xiNYw;L)dWb@1W45c zNYw;L)dWb@1gO^UH33pJ0a7&qQZ)fmH33pJ0a7&$QZ)_CsZayKTnn`n%&AZ_!CVV9 z6H+x6QZ*LvOsL67%$6E&|6WHTRYxLKM8+4ZwelHYehTB%oBW0;R|f1lXV2=>~*nS{n(%g?He_@*p@wbM*`Tbs%Z~> z7&+i4->qQloqj-YzHEi<*nT?%j~sE@EN+sC(57|u?Pkuf!h-8OG~XPlR8jEEZ|j?u zU)B_y>!nfA^lL5-I1w%zS((*>FQEEk@|I#AGob)%pg>r6ps?hA#!a33l3 zk^4@e?`#taHep*)uoc^of(_ZWF4&fB?t;yEEL<219-~AUqic3gj_#=&kJqsmCq*Bd z7*AY&N0k5aRGbKS%2$!g!M27CFD|yg&3ZE)(inI#_6TQ{9{i8Aq+em8KtYtuCz(+}RA@183bkLj)&4cxZf@tEFIdUPVU zA5+Frz}&`!HhixM_p(eAWb(62coyqmgAS~l4Z5+;Ht5WKv7s;AM;rRceYc_SY!e%7 z!nU%(R%}BXY{<4X!M1F36Ku|7VZvDO*d@Z)@t7vUnDV}w)csL<-;~}@rT5-wtoLQ< z_Ie+e-V>ttiv0e~Chs9h{buvnANHK+y(qtbv)OaD-n;VqH=Dg@>b)+%f3w;A4|`*N z|7P=L^}AaK)bDZS_`}{Cy(dTS)zN!+^xmG|zu7#e;P2mT{`QAGLVE9z-czLa8vXvw zW{v!MZ_@AIY*zonUZ&r_*?d9$PTCjh_tUccVXu_lL#4+wJ*@X=>AhQePnX{7rT2j8 zyAiD$Po3Utr}yCLy?J`ip5Du+ z_xS0(e|k@#-Ycm05bC{!de5QWi>UV~>b;9RUa9jJu?F@|hJ9BVINpDjVTb>>?XV`Y(+OI1wlg0tnjN!Fmn_=@kJ!~lWRxP$%EIV!GGr7 z%*Q*?J71h-F}|(N?@EK0Wf5%acBl1E{9J)4oG#@SnMtb+bV?*4YM~xi2>K zh4r+dk7wGRb+bV?*4YM~xi2>Kh4r+dk7wGxN{dbAna1&6%BH*5@He^fUdnentTZ%l zh}de}^NURFdxi-<)AoF?3-_{27i99YTzD4CbU_D=|IEF5|EDPxajyfBhw=;4cUFwcE~rNBH^3zTx(h&NBqJyLF5` z`g}gY_%^7+q(ZV+`SBd%?7)$$Wp6)^DSqeQVJ>L=pQ69^0gWG6dcsu5AMcH?e{Lz; zxUKokm}9qo)xy5hyOdnt@k9^XbmI{jqn^iy+5uNC5qx~aXxnpMRl!^Lj#(nSfMQPJ{Z`}7?&socN5NOwhe`Q!Do(FGa~dgrOU2BA6gY6f(i1LlBXe5nJ5l5G+Uq`Q%rz4kmuNX?g2%yWvuoZ`7dVXpCf!B|<$WsTEopWb}GpnNvF;Ib|< z?i+HvXlj)lAb3LEerEBdx2M7BwNFp}Bj;tZwU&#nnM!}S$}AiZf4ld{OP8DaHAjj3 zf`zV)_B|TUqc;z%O?=Paj-p>x=JsMj(oc8ZDOksN8vm#0 zpFdA)DtUP^>959@ce;TN)IKDA%vW_Njmy9MU-tK3wEw5^63etfCf{qrvseeK^hw3( zwbwD2#yK7sY=8ddY0-K7*Vox6+n*L3UER#S^GI3gZ{_D}+I}S)2wpv^pw0Z_Rf0E< z-)laf8*|$2gB~^g9~>&zcQmSRHgAZ1FZaIlqi$wPsPj$E^q?ReF|Km`>1hx z?J=LZrdkm3cm~d}LxvB;J}|jO>D3U z_uU3tu??-VXDUvwJ^1LN7Zdy&BKYsW#$G<5wZ>itx$d7O?AkgbPIc6pmW$8gT914Gw5U3OM||L zJvOjO*n0z8g*`d2Vc4q!+lD>a}RhP^{p?KQG$50X`T zldRgaWYu0KtM)iqwfD)YJyBNem9lCNl~sGItlD#B)m|*C_GnqPcgw0hU6%KKg}q+D zVGkJEguP+7H|!aMOyl=`;aOpi8FUDH&!Ah_lLno`UN!V3>|sM6!`?RZJ?wddO~PI{ z*edLigAK#pIoLMrse{eKUOS9M*n?-|c`I}GKNQFDXxxwgH7xw+W&UqroVP3IEH8a! zwEehPdEwr^NyF@dyblX*HK?aOmg9in&yTmZnQ|5N&zAFowr~MzC zV){RNzTh`=Y%=YK7Zd#O<|AfNB8T7$YUZ^^3woau^l>ZL<;trPFPyY*1R~k>^uGPoT_%-;0b~sxV40BIc&Y)vCVVY zOMf{actGL3X6Vbg3HLVHy4t+oyOiLu18y-XH}da)^YxKMe~NZ?tSz`q<{2w+&0kN1 z>)hUj_AJK*IV|4=`TSf8&t-im=)-za(3AD2pg;GELch4b6#C0{pkN2K4+ZR}2*k^|H{lQHb7W+(fg5VkzFzqq^qfAa z3fT+q6kKmfar&};ieOtNCzV|Bz2H*CzjAN>oJV}%@|vq$qF-sj!}Ilb=ax$nyq~{+ zU$ZgxnVCP7O&*yk_L+T?bC^P(){-{!ejRIu_OB|q>$lIF(%+R3{OgC`nkJib2_AVv zZrkYeUU_cY3rg8dvz`yy?RQx4Npfy|c;BvhN!F5V*_N_YD62*PNLS$?@~B z#*63SimvnXUy&2Zbzi>{jI}}jyI@^cXFUn)ppe7z@Vi)o!9Tc$|NM1%|N8cVy&P%h zxw^>u^ zrSm_VCHU9Abt>^5aluhkzS3Rgb8%O5BlJ~peN)7{p080iQ}!mUeWgp?FD-|g1!7ozF&B* zV6Ts0ucu%$jk6>>%!FUe-j_0yIuyfF}QqU96fn2oF zaE$Z0HO*0$#UX#^@?H8Ng zj^KOMM}J^8oSYZI_ujo@sHu}DDT43aRja>kedr01dHwqC{C&hDBD2stE$n;W%n_M6 z_tdnsc&y0m`{g;d`0O?YGS6Q0rdjf25d)d4d-pa!4}DBzwtwnco4@l(kvZ^!Ha2gO z??vXi)Aj70SKb$yWowq>d9p!de*01uo+oof=FG7PleE3F$b8_kYs~CM$3^B3(;C{3 zW|gz(`>Gz7+ADGuv*`OA-p}>aIcHn+ee9gPmM%LaG9S2lpE+6LC6QTT@e1?tvgsmo z>C$A=v1Mt4zC#}5LMG%vE@VO;gPj1R_1^yKluI6)@H z2jc{p7$1xiWMX_UPLK&dfTagiK)YBV+=DA0ZPM{OI*`N>8WsbV^UB^h_u{6H3oS(39=y zls%oYr&IQH%AQWy(zi#@(rLcWT_78h5A0JrTy8{gae`lJZYd{^^u| zI^~~E`KJs1$?{0eBU1B-)I1_JkDQuEPR%11<`MUs)O;s3-$~7PQuCeEe0OTTyD;B* zd`R&U*V9sYi4-r9;w4hN@U zif zCLojj9eO4pll>ifCLq(>Q)IHg!=56O{T=ocne6Ydr^sY~hdmu+vcJQg4l>!_VNa3i z$6aKyzhm4*Ci^?aU1YMqW86h1`#Z*6WU{|w+(jn)JH}mPdjBN!o&6pDN$5NKJN%Q- zclLMqr^sY~hkuGp_ILQF$Yg(qe>(Kt&m)lud5{a4kO#St33-qUdqN)MqVJFgx#&CO zK`vza`7SciZ}dMN_xCa1MJD=<{>S4!7xSIsap&_%xc~9EAIE$bnVy$KCdLQj1eq8g zjFafezrIi_EJosJ?=EUSux3q{s^9d67A`*bmE@=SAk4 zn^!Goo)?+h`(M7Cc|Pcg_fgPO{NC#+e(&|f`zYv%_fgOj@1vk6-bcZncy9)K;=LK{ ziT7r(C*GUEo_KEtd*Zzr?1}fL$n@`bkqMqtc$OO-+amV{zWP<0^xa0jUGJPB( zGJPB(dippd)-#SnL{A@w1ph=FB6|8bL}cQ<0l)Y22=S80#Ct={Bk_BTJKh^=9wA;5 znRsu6d4%^H{2ns#epB-uab1}2i0i_9M_d=?JK{Q#iT7KW?|2Wx?;#WKVZ}>`KLalz z{tUb%eh>e|dsy)j;!oia_9O9o$V9xL_!Dum$V9xL_*48IG7&E*{zRNCGP{>~ayht~ zBNjS3Vde7LB?m17KFcjxZbu#voGJhP%e$AU&h5t2gpcl6{#w)P1mjQq9oOaGxg9X> z!~MXJ2f4s_O8h*zUMXDX_LV|=mQxweLwlBAImqWfD~IRuzgG_W@O_noo-D6&(4U`E z8P9_pe;v6G`i1s_y&P^Q{epbK{<(s^K7zfTg84bnU-0Lrrsj>Gm)hUZ9(EAy?IRfd zK!5ymVNb!{&Vpf&peO8v=b^nGFZcm^2+jhh0E4r@DZtN)Z**YyNlXVCQrU6){Ssr3q7$I$f+JQMxH|Lb~)u9NUTrPfb$ zT?O?IRri1lk)!J~x^5GmgJ=2cVmsenu&=L(Exdfe{<(s^K7zfTg1!ENN6c-2dQP~G zdQNDMdX8Y01N#W}b`$LFDcJwJU~hlX)7NtZhv%SQf4Og5VNJ*HazyaGQ&+7wm#&={ z!S~kH&Sh6jc`<_T6)aK1PP^b}1mC-CUMpK}em(==TYa#n9sg2U=FN{>t97^7gY&C1 zZ;o(xPr200|LjhYx%jI4``#lm zmyEvFHoa=G$m}(~uU+}`N|D*9UKMk@eMw}#egd&}vdG+e#St^L?KF{@y?#-SO=iOf$1HMcv5>=T*wYj?EIkN!zy-tuN))8~bsMdnrK&oZSC3=x^pkey~| zvFAi)mK8Z{-Jib@ne(nIZ3lgsjo%sPQsyga*?g}QM$ODs>ul_;>&u{K<{%GpVNb|| zT=X6CAQydyJjg}gArEpP6Y?MzG9eFgArt*Z|6_hgHt2uM57P|#AM?X1gZ{_-@RmXU zV}96Y(EpepelqAkWMX_UPLPT5!8k!C#s}jBnHV386J%n1Fiwz(@xeGjCdLQj1ex%o zOzcmP2|t2AK_>hN{sfuuBlr_!!jIrjkO@D6KS3t^2>t|_VGckhF!&KNfx(ZE2@HOO zOknUMWCDX9Arlz<==Dq}JrhdLgwivi^mIy3r}PxR_x4OEdpc!Lr|jvJJ)N?rQ}%Sh zo;>aeHSSK0yHn%t)VMn}?oN%n3**lInNa@elz%$qpHBHFDgP9|hdtRpDflPL6Tin8 zu{@{dkyG{2nrSe4OGX@q73ZkB|60^yKjozlWYYKH~S#lgEbwFR>qq-$N$* zkyHFBeh-=KN8g^SsD~ zOh1oArl0R3ll>j@U1Xx)=zl!!t1#b1Ci;#3$K$>a^Ih~rztMliOCpo~9lRtmF+Lb4 z$Yh=eFNsX%dGM0RWS$2viA?r)@q5T*o(F%5O!jy1r^tjK!Ji>JGMVSWpCXfa z9{edX+26(QA@iLLC6>eQVb5l}=Prle!d-VP2 z^m;4c_ps-hOPj5L-+MjrJ_>r`eH8S>`zYv%_fgOj@1vk6-bX=CypMuC@!kyf#CtQ? z6YtGnPrNsSJ@MWQ_QZQL*c0!~Fz$H2i%jsG8h5Fz!AM z5t%*?5j}kz68sZ!h{*JDi0J9#5RvKQ5YZFw4fs9A2=5K}J;n&{4K@-5^)!LsK1;hW=VL7lQ1>-PG(#?t1TBE{(F1-zGw|I@h7tj_dmi}(z$ zF?|M5^%-Q)rthb>)7Z`31ov7vjQcwP@i)Bx$Ir5%UyJGwv>gU*l)k*ZZKTb6b8Ep>_KdT`Uin_W zMSZpF7~5e{LDBz2^I`U$&JPK`?^q9;eMS5Y+ADio*wZ~rNx!%+f2n-`EQ_)5I*86* zH^E+K!M-nYc9`#@=MrV;{M66mY^K$MQv&8TiO@#l7s_{b zFP9lMko7PRw? zQnvKUmuDAD=|Pjn9x-d4zkhba%ERbLjfYLQg-vH)(`F3KuU6Ppeg64bYxa(#`SZR? zxuV!T`KEk4l8V;3!r4nt<-e}|K)UA01~+e8?*hl3>P$_GWvALPOfTsS3Rw zyGR*W@gCG+$-=$$O1y z#l1%gEG>PxJ<_29-8y+|fs-w}*(FC#xp{*Y6RNcN zuSc<*#RYtwO7!&gE770(MX%oV_40aIey?kBzh?RNhWj;d}dYS)j(<+m5zxRjgs|T=o8}6l@tFvFvQ`N394egR{-_Nd6GKZa&ud|(f;aPLmEOO?P`2*|)tqaXr zo4cc#*>a@)GO5HIJx?!Ra3i%DwpX}9<0m`aLRY>pU#{Ob5x-}ZSMY*^*BIk_)4=UygC|mJ;T&>|^A*#(!s>SzlsZ z#fBPxz`vbVWno>h=e`o7sqx40-n>GShtNlBSBeck9dJF>Y5jPF)_EBY5A@F;t>VX2G{_A4j<#C?)UNYu1jWo624(_CNd0fmCUH{F@;c59~@S zYsA03wuo!>_xZh-+oxBiq<)RXZa>_Yjhg?~S@1`toExz^{#`O#aH`v~VuW0O?tzMK z+Y@p9T;sp9&cgz2&zDfZMj-y22g>Rxe-J+?|+s{d{r_by!2j((X`K-yn%Pj7ms zb6kTQd(8-{dEGRz`JlmLY3^HJNIc^fkE03&x{LiMavc83OK}{2y2}76_(mL`e|URm zB7gSov6mZB!8YfMJ)i%$0=0jpiQs*`&Y>B-uMzC^OoRW z=4Kkt91YCeOyFo>&u=ncH2yp5?B65OUyYfYQ^0rV7jv@%M*}lAJ8(2GbF%|S12Z=h zI2xF_nZVJ&%*_Oj24-$1a5OM;Gl8RlnVSh54b0rkc78(a$=pofXk2G*CU7*ce_yA; ze`lRNzlj|*9{=p4uGOrevE6zeb_>tCLGb+@N>I_!tpwNM^OvjkjO)CM-PLsejd|tz zYh`%?C8+dUqKMJNx%Y8vJ+G8Sx}^$A29UjI-5Ny(xKd_ov3$*^66? zP0BYNXKR*UAeiT=h2NvS#%C(W$FaP>B2|uzg@2aV-|HaQ>n8EfpJ|hx{IlvMxw9Ya zoIIfWXqzaQI{7*tL0`Poi1_enm&m9mvCI9*Efyc{;eJ;yW z#dWwSui&}Ms<^{lvk2bwdS!Q@UPZx0`c`%uO*O$k9jxRw%&#T*vQCv;pVIXOf48!t z>u~pFf~)PT;9B0%TJZZtD!9>4bQIhoD(@az)M9KJsZ9 z*Takwyxf*?v)y>Xb@r8ZuMVCl_=ClzUF+?42%cECxEtMgp5UonOS)mTWB<%Qy_8$` z$rQPMd~h-M^-T)|U$d;Jt2Jqn;74|z=dO78VZk%*Dd+~(cusK7_Y1o>Mm{09UAuGL zq`J!m=Q~`$y;gm#;B!kAa4By-FZjW8^Sk+(HVR(#Szb5kStoefxO3dPO)m*PFLNH( zDaWgV%MUr*4Ze1p;N81(x}-VV1^;@@S+36XcLn#_pWPj*9Q*c9k7RShntdeKkI&5N z8t(o?@aCVgxS5xIDtOD7EUxyAp9vnd;CNzo(jmd`@Oh@MeYQ{Vf@dsc4|0L;EwwkXz2IrNe)+6#6Ak#xXk1^gV0WTP!>rP#OTCX1 zg>5#$=d}1R(REmM!Ap0(mstE>4#8`V??{}uCa2)$Z@!V(xi6RCK4V`?tR9(LaF1G> z6Q@t-5q!frn-W=W&MWxSx+#gbpUEe9%=<4S4!o9M@K?XBO)Pu5fZ%%vuSvA27IOv0 z6XOa!G0qro;5GeLCYlc@B6#j?PbZ=ig#^Pd;2&rMe}Ufs!@uBX!0DrYDB) zDk=Ebq}hqu^GgWc_vnN~$pSHVot!i#(Qa9cj}IAnP2OJXMvet8-QnlnO_@#XMvetlfkpV%&*DdSzzYZWbiC7 z^K0@N=2>98_k#Z1ujJ4#=GSEKEZQ)?CWB{z*$&CU4s4&~U>~+;aPlfthO!I2V|?)_`+? znQIL=7nr%$fOCPFYYjLTn7P(~bAg#_4LBE=xz>PlfqC3ac!%^mmBquJL?c&D=un((e?t~KCX+{;{Rz`4N8wFaCE%v@{0xxmb|2Am7b zTx-C&z|6G&Yrwg{%q0e#3(Op2LM+FeWJ2u6TxGzyXv17Pl(T2I!fOCPp9Rz#(2=?|A z?Cl((J#(!A=K?d=8gMQ!bFBgA0yEbda4s-&tpVo(GuIk$E--Vg0p|iU*BWpxFmtT| z=K?d=8gMQ!bFBgA0yEbda4s-&tpVo(GuIk$E--Vg0p|jHKNsx%Uodm60q3F(bFBgA z0{i(Q*v})ue%=Z8^HDIzw1#6^!5q^Xj%fumzZ&o?WHP@R@GLO%s{zjfGrt<}EHLw{ z0nY+6zZ&o?F!QSc&jK^Q8t^PI^Q!^R0yDoF@GLO%s{zjfGrt<}EHLw{0nY+^J{0VE zQZVyt1fE43=2rur1@^ou*z>Jm&(DHAZyU5{evQDhz|5}^cvfUC*d2jqftg<;@GLO% zYXqJJW`2#pv%t)+5qK7u`85L10yDox;8|ei*9bfd%={XGXMvetBk(LR^J@g21!jJY zz_Y;2uMv0_*uNhI`}e6}|DF}>-=~88dseW2FAMhXYr+2gF4({K1vA%1;9NYHxi$jl z0yEb};9Owl+6bHr%v>9Ra|Kr)7=d$vnQJ3(E--U#1kMF!u8qLCz|6G~I2V|?HUj4Y zGuKAoTwvzf2%HPdTpNLNfthO~a4xWqy9E1qOfYk81kObp=Gq9H3+&@J!9K1N?BhVe zK0b`wADxv9&c(gVwaMUIVAK!5xxlC&fOCOSKLFJ^#gD& zFzN^3Twv4>z`4MvAAoa#Q9l6Z0;7Jw@vUIg4>-OR?BjF6K5iF``T;l>_o99P&IR^y zzF@qIz`3~Y^98{^j}VOd0XP?JP(J|Y0;7Ha&ILyO0Gtbq`T;l>81(~iE->l`;9OwT z55T#=s2_lHfl)sI=K`aC0L}$Q{Q#T`jQRmM7Z~*ea4sfOCOSKLFIdLlVAK!5xxlC&fOCOSKLF81(~iE->l`;9OwT55T#=s2_lHfl)sI=K`aC0L}$Q{Q#T`jQRmM z7Z~*ea4s-%5pXUr@)+!(+WoYfMZ(0$a}!EXoGwRJPVBc2|Npoyb3%EjQRn1 z78vyd@GLOu2jE#?)DOV3z^EU9XMs^a;Fwl0>IdLiTu1!?JPVBa0eBV|^#kxMFzN^3 zSzy!;z_Y-pAAo0pQ9l6B0;7Hao&`o;3!Vi=z6+iOM*RRh3(WlLz_Y-}kHNFR$eY2l zz{s<~v%tu|!Lz`qA8<@781)12>_4`7vPD(%$iw^P`jG?WOo7X9l4m{eMG>><%@u+l zz9YN&s%-2(KivOi)VD-t@!Kj3o{O6FkKd;ke>yfg=Z=^k9;lu#%6U3|FZ6%)qXrW_ zSFf77I_2RjV{Y8vrd6VRp_ro@Cmu|cDqc)vR=E1j#N%t@_x{7Deo7Qr^_}Q2d1GF; zx)cc>!ef2Hk9C8=mEG32s>*fLrBUzaKGIcHs+t!UeUE<8_&(*#hEx5}hHAW6*mT(} z@f*E*Usm(V+Y&Dk{>0zW2LFzBz_<_h14AC<0=K;_s(|PD>nY(nw@-xjEGH43@j z&wsk`T>f_#^x^wl(39o4pg%vyz5e+0N_dvPo&xOKCxE>i!Ct;#|6GSQULV0;Pr>{g z=r4Hxnq15AJhb=y4eenE!QMWCz1;+(e|VnP2X+<=d*FGv4m;s_u|8Nwh?f2%R(Toi z<5=ME7m|Nb)|->en&Ogw(bXIatV&4!MdR7Ortgsai?XjvGOu4N`4_F)lw^J_kQcca zsr-&qen%=FB$Zc^${$JPkEHTVQu!vS{FGF#O)94*l~a?-sY&J3q;hIfIW?)Anp93r zDyJruQT@i~ZKRih(Sqa#(LBUPg#Rih(Sqa#(LBUPg#Rih(Sqa#(LBUPg# zRih(SZzNT3Bvo%DpEpTgd>$m&=SPBl-XvJnKMA?GuYZ!yo1~4;K?JKBFR2X>g43}CTZhy5W#9KfYe$5skH!7YXPLz0!Xa|kXj2MwH82XEr8To0I9VAQfmRE z)&fYaUyxeAAfGph{yq;9?DHeRK5r7N)>BBWr;yK^q>ax(1gkY8Lj4jkANXIb8If8u zBDH2jYR!n$nh~irBT{Qdq}Gf`tr?M8Ga|KSL~5Oj)H)aWyh-%*d5~bA9|`t(lVG*( zMrz%SeBLB&d=4U*bAqt8NNR17)Y>AcwM9~Ei=@^TNv$oCT3aNwwn(URBR7D})!HJd zwM9~Ei=@^=Nv(&1W5fC>xHqiBlFyF<_lEUWQtPv%)@SkF3G2CdA0Y>kd(|2=sWoU) zYtW?Dph>MklUjo&wFXUU4Vu&%G^sUcQfttp)}TqPL6cfHC$(;lcX3!}$2&T#*W+Cr z*5&bz4(sxy*6|7aiaZ?S;`1iKJ_ix3_9~Ftt3Yb60;#mVz#g!1F;(cw zp-Am%A+@K4)Sebnds;~CX(6?zh18xFQhQoR?P(#kr-js>7E*g!2y3mVN%@#I7euMBpO>neXlOdIk|#IzybL`)m<)8I1^WU8DRF>T1H5z~g88Zm9isS(qL zoEkB0$f*(2hMXEPZOEw+(}tWHF>T1H5z~g88Zm9isS(qLoEkB0r~@FT4RwGpUqpXZ ze+ctMuB$o&V%kubKujCz5`jacy{gF|rVX_h#I&LIf|xecUJ%oU+6!XZPR>5Af^qq7sRxo_JWu;)LszNhT02a+E9BzOdIM&h-pK;DDbNEMb)WD)uRI6 zN*h(bLQEU#SBPn`zs0~e{5wdns?i~)4K+H%w4p|am^Ret5YvVl9b(#0qeDy^YIKNc zLyZnGZK%;9rVTYZ#I&JChnP0h=n&H;e2tD&U6E8>5pgW`w}}3#o=K{1Nvdv1s?Lcx zHq<#0$6|kr$Wb+3Qng&fv7wfWI5yOB5yysFF5=iw%S9X;YPpDGLoF9^Y^dcTjt#Y3 z#Id24i#RsaauLUdS}x+)P|HOe8|u%9V?+HJaV++?NMC&XCRo+CN!7PW)x#0ThI%;S zSnO|+dwonRSk?Ry$A+3e;@D90M;se!{)l5k%^z`WsQDv~4K;tnv7zRVI5yP$5yys_ zKjPR>^G6&TYW|30L(Ly?Y*?p292?dt5XUB?b^xFEalT+5&kOc(zF@U(f;cv;n;?$G z{uXKDb05KKZ3uB}SQ|nd8`g#p$A+~b#Ia#*2ytv!8$ui#)`k$rhP5HYv0-fpaco!{ zLL3{`h7iYwwIRf@VQmO;Y*^1i92?fN5XWMFi|Ft3LBT%n6YTRr!D@XifC;95ixC8TSQD7))o=dhP6e+v|()#F>P2|L`)mj77^2iwME3VkzZRx zOdHk~5z~gXMZ~mWZ4ohTSX)F)8`eV+(}wlXP&W`RRqL?eSnOkw>%N{KSgp?@rVZ<} zp_U?Te2qo0T7yPR8`hu^(}p!@#I#`z8Zm8HgGNjn)}Rs7hBau!v|$YzF>P3bMob&l zpb^uCHE6`NVGSBFZCHawOdHnC5z~fs^H5(B{e9g@u&*x(R_pSJX~Q}`V%o5dA8KyW z-q+#;tGx<{X~SLx#I#|r0%F>*R{=3?*sFk;HtbbEOdIwpAf^p_6%f;gy$XnF!(Ii% zv|+CTV%o4*0WodZtALm`?5{vf8}?U(I;6yDzCIaZHtb^&?CX<))qW4ev|+yoVp{BP zkv6DRhuU}vN-`@yu8KV;eC}(Kx$Dj4f(Ja1WJbRIgWwutlg!RbO31x$_ee6&d|5~E z%dL{kBfVM)_Iu#vyHWi;ss7GXe}AgKOV!`2vR?B0Z2o&#`Q0}EJ*@nm8@_vu&(9gp z-_^?Zuny1j-^0oo#Qu9&eCHd!hb27Ee-BG|p8p;e-)hMBx%#_Z|DCV#-^0?PkcU=r3`< z{_wrCw-5R6m*qSH$oKY?=XyJfKHmP}`(-(gfcus1H`@9;ZvB0?{_b0U53aux*WZup z@5=S}=K4Ey{e8OrZe4%RuD^5F-@ohc;`R6P`a634eZBtfUVo3Tzth*>@9XdS_4oez zcL4P71L)rk(3tz1`a1*q_XqU%&Km1)qV>1Z`WtHfZMFX9T7QeJztPs;ZtHo ztp6qna}Ku2ut|m;GJGJz2Qqvh!v`{aAj1bTd?3RIGJGJz2hP+7a`rpN<((e?{)xsL zm;97yTw*Nh1(~kB?)^lT`7!R3YfYkgmiRY4G_KJ8aLTr?;_Hl)1Lii7YM+W(W)x)d zv!d`U*1;%!Qn8kk-o3hw)ReQ- z&P%oG9965%SGDTgRjbZpwd$N!tIlt=>ReZ=&U>}$99YZe#)k7@`Rwnz&&T`uq8(R-KD#)p@B_oug{i`Knf(yK2>WtX7@VYSsCzR-Nl=)p@U0odavt`LI@< z8*9~hvR0ilYt{L)R-H?0)p@m6onvd&`Leh#ly=j2*-ey&yL>RNT)u2tvo zT6I3JRp<6vb)IjiZ}9I0ju#F>4K)Kx9W28R{7%a7hm3iV;R6{ykl_OvK9J!989tEV z0~tP$;RAop2PV|7P185mksK>i(Ti#I;Y$SbpTvI`%>Pc@E)D)O_x{-O2D<8|L$Y^g z{P>>Kdh@q}Pp!I5&xNcF)!g~xEJ#kJ_?L^ z3?Bu?{DzMLpJ{uxtA)?uUbeS|j{@^JSokO~kB^0q0-tGnf3Ly4UZ!CGEWuu;;4^LS z`!4r-n+W!{66|dv_)OdTv9r+MkEvik)`I;w3O>{J-uL8Q?~{VPuL|})Dfmp=`?(|c z`Z*=o&o#k*P6AQK#z2LG9RAvgXneqU$c3_E1_z+d76GC#d- zGq4!q_usY;`$#kFlVOwpt`FcG8$KIG;t-98&+I^Lm*$o^cUjBU^wN={f*aPpj4C`* zDGg4qy_Tsl&dK4kXG9Lp$>H;I1mm0>J}*Zw&dK5Pas=a?96m2cFwV*0^Kt~^oE$zc zM=;LG;q!6?H;I;_G})4xg7J80X~hc{ze{P7a@!BbfEH$|kA!@2oSA zi&f*2ic1`AXGi8NApNSju8X~@XV!n&$Mo9s8BN4zmWZEd{Np9J(iK@I$@PX4hSEJ} zFBN>}yZxzCzn9YB^xA8g8sl6PK5Ine;9Qi3Jr4`UxhQ--iu48NqVV}Bf^jYipN}FK z=c4fWD1vb=3ZIW680Vt!`6z;ME()KIA{ghQ@cAf$aV`poy;W_N+53d!SHGX(|342?aR&u>xmnyd8M-9{TOZWF*v?pbgRNQQT zS-PNPGm*LXmqPTw*KLCir1VL}>9xoCX8%k+&NsVxYb+DzoAEhkA|L0Q@i}LLalRR! zb0!$)o87)W9(SB?#^;>Lb)0X;=bQ<~`DT31nP8l6wury&0?*=nGd|}`FwQsQbIt_g zd^0}hO#Bn)oAEhkg4v&~nmeiZ@2oS=U#sSCDsDM+xV>=fZ0T3cnYY`h;f?>YkLk6? zxr^$2y;S^O=I7nCbK^7k?(a6=J=N@dOI_*_RmJ4`Unb>y?d1mj#sK08b>&UNIo z!^A!~*OAW-6O3~m`Rp(`0|@6j^4Vef93lrF^XCu={yXc8a~+{8bk=xJ^LB~*R>t;x zxl5DeRwrZ3XD&rJ>j>>NPOrU|sWHxt{{4$h6-S0c{kac(4^O%}`Nb0hg|GQl`E zlFud+jB_LTY%;+(H0B%e(t zV}x@f`D`-5@N4)V`l#{WS!c{G%rWS!anGxV*bX}%m+N&0-)!&6{d$^y={}~{9{dL$ zgnW$=J8(=O*AY8#3?UfY0}euajniwdWonGrf#1g>2eAXk5P}gqa10?Bu>;2tf)P7# z3?Ue?1IG{sIv{r77(y^&2aX}c9}qim3?cr2*nwjRu@7Pgjv)jicHkI-AP2Dn#}Ie<#*ERk->x_3b#|@&h#)us_CXnlh9XN(a(=Xk}^x7ltM*Iz%XpCHha}2qTT!eEH z!H9Vg`=Y(Z>9yA~k$-SZFZUw<;5L>t@=Umi2GaGuP2riIZt<}X|Ej7K=9G(h3uXYS84ec zGE=q}wex$%Hu<<_UHj-8u}y|AYiAdYjBRq!{k?7Tda+HmcNt;FUKrctq5H-!a0UqM=ruSiPj+vPOrW9C5vZij2M$+N4bs|lVeT6-dEG$^xA8g8Y9N! zxJ~3B#^hL2`imHoV@<(`F*(*0j2M$+P4NxHm>g?5=!_VXV@<(`F*(*GTt|$_v8G_e zm>g>gMvTd^reMUF9BT?jjLEU4V9$GL@ZVWy&+VeK#)vUFc9iRgF*(*u(=XlM^xEt5 z95qJlfU`njbHolf-xL_J1I{-EM(lv|O@R?R;CxeH#11&$6d17s&Nl@{?11x4fe}04 zd{bb=4mjTw7_kG+Hw8xQfb&g(5j)^~Q(zyvron$_oqc>RI%|yBfnx%>j@W@?h&27u z{Y|gEk1-7FqcL&?&H>~)as|#A1p62!4NkAUmZ>pv1)SZB=OS0YdBecS6>#1#FmeT) zHw=ti0p|?^BUiwA!@$TDIA@T)BUiwA!?=!I0p|?^BUiwA!@$TDaNaO5as`|>42)a> z=M4kufngdOAP;IY?^-Q{-)R7=h|X(jS*vV>?qd} zV{)u1*yp)vaC+^vOpOs^;!IqO3t~);H3cKa#5umWju;c?_yQxw#5umeh%s@FFEC#JBFk(!c;|q)!6X*B>BgVuzzQBkv`5l%9|DAP4jLGk8 z(OF}}m>fIGb;Ot)Yo_U!?r(bSeT`SfNMpp996O3k#F!jw3ikEYG&sHXTBgQ`H*w}V z#s%>v&WQ&`yvcE=V8oj^Cmz=kZ{nPIV8oj^CmtB_CeDcmM!bo0;(-xw;+%M3#G5!L zUaoVziF4wC5pUw0cwoevI42&M^~730ut_TZJL~M%BSe3V5o2=fDAy5Va;*6;`+o^ZWPve{*}v1^ z^x89L8jgDi_iD`bmWb;!a{c8lO;Wf%BbYfk!S$ImIKB4#o+Wt;&`!qPc_GpWHAYWs=^Z8va*YVEhcfVlh0zJ@P~A{f4)crO*F*FHV@$Wb`%7n#UW zI9Cyj9EEcg!N^fKR}qXHg>x0b$Wb^~5sVy#a}~kJQ8-r-j2wk?6~V|+I9Cyj9EEcg z!N^fKS8=cvaum*01Y9zN~YH_c|uszloa2>YCngp=t>NGgL_I@tQ*l7%oL~R-}!I8|B z!U>)$gcCGQuf69Y(MMx&Bx89hrQ2>2{6A^0@9i_IGrig(uFEZ|Kae^M+9)=8d)r9Ldvj~SRrZXdVXu5Ix!$W? z$54kw1x1Gw&4-?1K)eMP)B{a47$*>l;kjA|{~H?8 zm(@4qiN@`U^vd<^&r!fw{s2uF$%jX?x~08+dX|p8>Y|jCft6FRyou-5jrX^jbL1 zW>55xcjdv6W9=93eJbzAEfYrAh2`%SZrQo7w@uphq2L7t+S_Tn^NUYToKe?y>|0B) z*6rW*Tz=Qs@UG!^kPYu3emB|hZsPZd4ezY~Nqc?o-j_G06!rTMR%}1dY)gvg_|XrS zm^(ikD)w1+;s>*%Ll438`}AF_{-~PZz873;Pfa>Y@LwUbKs46w*?CCD z_uT`-ZMKFpWK7>V)ywvJ{u9CP?z+mp^iV<3;o1Uq>^(o!7QCtJd3NsbHiGY|zR!%g z`9{H=`#fNZMYjm-yCNb)G4d6*g@;&v2LSrn)berggD3d zU9h)_U~enI-iCs`Z3TOq3-)8-Ak&YLV6EHV;kjA|KNmz#@59m;@7sdC&kOc*L9m}A zg8keP{8z~Ib6@0pP7v(5LiE?qJ=6A{14X9iM!}vl1$!=)XL*hl?73I`&2zH&o9Ai+ zfAAbG*mJDK^?%oM{kuu}<=yK4uf_V>!V-#uMygKf!;I%zyg3cH9@_ zDKd^e#tyn6_7?18a=|`U7wlvB7{{@_;J-p9`vCGak?(UK!9FJv>~kf-K8F(Qb1T6< z=MwC5F~L4Z6Rh?BcRiQqCUQ^F$LFMieXc54>vpE?eNJt`Q5ySPUgY~6Tztdl=7N3B zF4*VtQp52%zJW}i`wRXnWb(TJwF}X~*E9tCT8HSbpZh;)ukYn|Ycj`^BA?%hj^jze z{H}ByPYULDsN;B2Fuz-g<4M8%&Lxf~1@pU@IGz;zSIFd;ggBm*cNWJg#POuqhhrGx zcv3LOHpKCy=)f@#aXcxQV; z!Cq&}_Qr)7wz6@1w*3e~0I49lWoKp5Di#FW&bAd!H2SeO0jc zVZq+F1^*Q?VbhG?CmB!a+adlp{5$Vhk#=W*W!!xGGsP62(~~LFFc_^mZRnC=W2blo?3tG^Q>L#o@KBJU$?4XR`tuOep%HotNLYBzl`cv>Tmh# zXK}w$uXDdr+jGBC<#4}J<#WGMpUeG9)rb3)s;AZ;{qgh2W?=bE)PJzUc=%f z{L`3J`!mA-2mbs|=Z>CJ+W+;u(DOylBR#+LywmgXulMKQ=c#^{o>SWY^}NvYMb9HW zzx2G*^HGiSpZ1X)zvQRfzqOP0e>LtiZGdU)zopE;@tX9%+YbGEd}!u>`(352S^L;C z#Uo=L_wwz3~IeeYHx77*r^Z7R< zvVL`?-L$^29nrr~^fuM8*Jr71m(D&CU4F8pegDU1_WqAAGozo%WShL((Jtsa$^2U3 zWpj3sp7x=$mzxu-$D3xu``WoDdA;|O%;w!M`-#r$Cr^JO=wG{EjGvpb-poDkeAE5g zes)Km`_0CCmYP*h^|B=kb>egV4x6V2cCi~z{1!z^irbxca?QR_o@iIIx^~Q{S~hR4 zeu>=Iw6zP*DQx>UKG)GXH`qE2_n2)%2Dsw;``cHCKVWp<*=}yfh>g&JfY;yjwcur6 zrMQNZ&vm_j=tmdQLihHQ_ql9E`%s55L)^RlKXME2>P~s@uHa7HbPmNV%%F6WV>L;VyJ9eN^t1 zReirOJ&@FzvhBY%v2jXm`uX^!G;T_yoNbc>bl<1EA6w)gwegHvB} zLlQqGqMiLn>!WR`ZL4jr$3l;h9y>jzdaSh%=;vnOw7$wVN#&CaJlKL)wH+|Oy4^W& zC3xnuZx6Xjjmw#)Q@YWu*JPrOKQA^bUu;ADi)5z<4(>N^7Oh9+^5&pU_FVf$kEb$1&o znk73i=a>cS>(Soxau9Ql-O-~At?13VO{s0$pPh*=ocyz6&auPWzu<1%vDY!@*n6k< zbl<+T!!hUBw+5#qe(JT}G3VGHo4uE;bu0&b_n&smv3Abq@4539Wh3TZ`^lbMv^FURF(=zgk5;1D{j(8swHbaeqOLoC z1BaW@^{%1@)4m6{o8{fQ3+I2gcCqvwc4&X?-H&68%9Y;WnCt94cf63irqVl(xy~;9 za$6#2-@T5x&JNjqz3VpfxMQxf&DK5PUP{VL%yqWl^Iy3MZ)GFqI(r%ArtwvC5ObY< zzH$Y6I5|5p*O|GAIt*O`iyJ5sU4x8S-cF}#Q9_I-&@mxXuJ zUy0fN|MVTiVhd~v=Fi#fTlW>E^7~5IMK5Ks@07WeR+l?rmR9`Pd{FrcdUn}5 z)BT(MX7IaR=(?wem@PHlGea8oriRh=}8f%3In?2`J=cAs_XLqj{f;I27P-BtgJUri?O(cnH0gr{?)0R=w)u#P=J1J8?&1Oi?Zz*s znY_t{xuCbLaplYAo9}-~6y1HDt-1JwxpHg2#G&qOZIM%jY}YdRlTXdGcGp`~?cfRz zM0=l2vMmoJ+g1Ue^ddJLoHc!;`(!SQZuT6u6PbN0M)YI1LdCWw8+PLVc z&bIW-O!ln@m$*-gx3MYRv)Sc?cDdum*v|^(upfV&gRbbDWba#=-4;JsnzC#tVjnJ) z)egV;V%pOGq&fNiuO=y1Gy3I*S51$xhfKYZ9jIv1Ec1Q)PtCpKZlKDoYnTm-UN;r@ zbIg*ZTg0|9Y%5}0{lTxakG-{alexd@0LnA1X!5`&yUn}#dXn2-+1xbeM>BR>J39NB zhfIxenQg(s$&_vQKGS`Ac6;s>Wobvp!uGazv)jx+pLUrxUubV@m&KMT{el}_tGT`T z^5bS%=?-q~@oR1O!=IZzJ31yVy7wkqyx}Wm%^TEYhNpMR!XB7v;W&>V&LbS> z5svc+;yi+5mBWtn2;w{rV z)U9qwa+e*8@^rb5E`050_jck+^W4F{^iz#BZrRkCX5#5V^hx>l?t@F8GtF)qM2o6l zpP0MiuUck+3dBKe&lkTj%?i@Pnm3oX1Y~ZwX?Tn{mv|FlhsY$cD>DY=euTq zy?x1dW$*h3oHO@9voCjUH>1JzwsHH@W^(s=F3-HS_PxE?>=X0%xZZQ>+p>jo*xCJx z(EeSe?Uhxs+9yw3MBh#S)#R%6i&^qoOB&N~qq**J&~1&Z+`8uTEWN4Mov*q2 zr*}v9U($sZG|No=*XNB6Wo|`@H6`eHpK^%{H(p9_XTFF|Ro<7l>-Ex9^7*E;XJoSb zX+>7*I;aDE`^I?p*~{D9)?Gd5zAX>C?PaGsx3LeEzboNx?NZ2ne54;$uJV=}@XdgP z`?xQ?ooBa$O@_VEi#i|r!R=mF&osKTD;2mPGaXJ^X)0fM1>Jp9c3Ru$h#6P&Qp$8V zJCzw*%s!W^1dXkem4+_4$j-julsl{CuddZc&Ft7WHoH>hpqo6flb!bSWY=QqE?4B+ z8*Qfn`Q3;2zUaRGslVMety{{m&z8Bo0|wiN7Jd`md-yIl;nG3&gEqs>W6!p9{X6xw z-R8bvzFCyj75kx^J@2a@%vn80CMMad?AYZ6?fG9eZ179f31#WHlEg6|?hhZE4S;hGxX!%(jQ=Xe;g-X=eZQwkfgidVAr#`KDsKMW$ZY-ge)l zXU(?jTAS>%``KLAzid9pe;_LH2IF-6WWllL%;^1%Oucpe><_tSnq0G=F<f%D?_Icf@ z)!Qds%aeDSN9byr{#q7lz22FD9hy?R>Dj5{$H&a9yDp{?#kkgSUt#;uqB69$Pd3_0 zNp@7OoOI`%nP}T-YYR>I#Em+2)IE0gRd)JS%iR3W_qcqEy4jnybZ|3H>~Pt~^s#x@ zyTpX~>p347XtTfeMsm*b54rnh4z@2|P|!SnY=V1e(Lh_F&7J19vX{HAPxY~1^-h?E z1+u!OySmxeul&($+de9>qy1I3@Z^HFX5GyVzUk1=-g>BtT~Kdsl&MN}{$w@Tezh;J zsd!!yo5XqL;C5}zJw;BKHAOnxqUTLETaJ>i?biO7lPl&Ui0m_`qN11G?^)QCrTaEoao0|1)aKX2<@F z+Hyv%JEPA3|5G2xcrRzH`DU#7{^zavwmfT_)GIR9eE+(fB_kiquI@4YOb}uRda>#B>rRTWNv(EfXIm7&u@+XuD^aWShz2_&QlAWb4h#N zUmPp{mIqyRVzy;^2;<#(MEt0gEHtT|7*ozfq=!6V{a-W|N6O?ETeg&fa$_n9zxDaV z{CjnveL*Af<5(_VHM=#e8gYO>KKq3GSLqJ*Zx82bchB)j_5&dN{ZW1U#oPJdCSkDU zc}v~>J+t`j`a|GUO?P&%VK*LCA_T5KS<5;H7vei!_k^6@FPU4EufBeHZ z>GpkZ4E^Q(KLLB5>gH9i2=(n+ft^z;)+6aVGYRhk)?X&ErGxjf?@juFCWaS9%W%oLqwGzcb(i`Cbw6}?fuJpqAuOsPxsrnxkb55vAae0;h6Y3vFXV<4DZkJ zf4+*n_ca2%Z)f71H!S}uf97f&hvRbZn!$0%61G!!FJc8V=47pwOoPyjgF1L&0^9ypjxZEy*&o#*H;&QtL zKJOs6OUUgK_#A}XE+Mx|;PVl3yM){>yx)n*?V|gj7Q9|f*Q)A$?CSmP>V5C({qX92 z^6LHb>V5U<{r2j8`09T8-*v1o{I20V^?zFo9Iw)Vo&&VFTOa->aLwW#)SnBrtl;+E zR>U@ytzq{WSK{_TRsXV|CGWMTI>W!4L!;gOiEm!L!TJ`8B7PS!jb#UE?#_^X&fRDW58Lwv(7?VXx-EeneEml>6xO|B-4XKC+ryjQEW z7&HGPy|-YWc`s3<*c#%sDdFN~bamq7K5^psv5xc%H$La8a)W{k=^Z39-Y1F@3oPl~ z4CO8)iZcZw=(k>n2F1tt%)~;RuX-}>k}7S&_K+3Ux9dt zPTuSGNc%QynZ9 zIM2ZqJgk3T;wFyIxShN9j*vb}Ek$C>`c%H`U<2W3QkwWkn726X@t9*fS+@Pe=Pk>K zNB4^q7suKVFFx_tbK0)6HPu;kB~EvQ|Bsjb=&`5R`>VnrL^}ix-ISq zc7Z1uZoBWUU>NXqDDlY|(NM;F8^vcQ<3z}AJB8lS(sV!~w0N(*>-zTC7+BF#d$&!H zTPPH%qPqMb7<*Rx{=hh>0(Gx%mZt;ordDDv6^j0Nk z)m3|+O~*0-X>YW5LX>{q1%~uLNOQMh`5<_BtPk<%lo*JQ*WPEjOupMPu;n8fhm-yZ z5Lich-=W3JVURH8CXH3twEl42s}$fEnyhXA%kj#h*(j>xv17QnY^A+RzUS8jQRviC z8qXTKL@{Pl6#eeQVbP-3E)!D^a1O z_Wqu%oOgVtz4l(8t9EJJW12QT%|=$?_kQj#PuRPrf7PGDf6<@b|KR?peY<#6>oXj; zVOM%+@qhW+GG_5b+n3iqeaxDE*Y@R2Nu|N^rM54hD&GJCL$&=&XXg!Sn`*gQUu{Qi zU;SORKRCDeY`^yZ1~!a?AqM_yV?cX%5WZ)}zk+rgxOlcMJ}XSeaC~Ow%C;WF@^?l2 z&u>tq%kNR(zu1?bWyDw){|3vk4QvY;+g5!{ma{+0WqsnGzX@25?a20tv3>b3G5)6f zZ^W{iyv`m%jK3*=gIN1b?U>QF?aDNz9G{{5vp!SW0i}Jp4)M3&#ky1<>ni;OrT?(m z%&!Xe8IM!S_G0}%#{t_ASOeQp#tna$%JDble&F_}@shny$!{cW_EImK)8(H5E?9<I~}Qf$FLFN@l#9U%xdvsN3j!hUbfUHh;J9QZ+n`{ z?=6jarhPN;g8UZ5s7glU1J7?J3aBubxI~9U@&3aL;<7CgM6I+Ma*X76PCCU2>%f7; zMs6|UXh;(AhBpx+;o%+P1{s0kZ38R7`YQ{2h;j8A5zjp1Bu1Rj-s`{Ht&H5(e;f1o zp4xX>#*OX7&dX;W@NY|doMoNMX+CKZTN=t$t3%}-MH6^ds5r4Mxg#9!cZFm932Xq2 zm^Fd;@bxH&i8)H!-aJ!!&eBD+EuUJ*Zy?tnN&U3R8V);y&k%PUHf=eNOkF2TjLPVmHMtdf@jViWfd?6>xhfeqteh=KpQ7|@PU3*Bcpp6#I>hhxA0p*M}zuIZYs zG~?Dj+OezUOh0+-`M3Ii^6?8Z9NqS7buKpcVnaV_*LS?mDpv7pKY@J>eQ}@Nvh^cg z5`>6ABY{`no|JMx>%1(#{>7QK@%2zDRaPRGEJ zqr+g`LGAsc`?7{X#QFAAety{q(6uok9)3O^HV=%X<7CaLiO?hagERKW?t3DPTD+Hz znSEX*Kyb~549mwpjfH5RnZ!?`hk?(mYsB?O2Ep~r5`cAr!#lvof=;}H=lNo9SPNrZ$-9DW{uxzj?r#`70ZynjqUjJ6X{I@w0Gw>8&;CXJ=W@* z>n8BH-l0_I?q9#j3fo9WRDC7}J>Cy&=D=mVA@OZEV)%93d{bE<{v#s~w}WJOaeUl6cO`lV{nhcB0k~ZBC0_Z7RY?xKa7j zw)Uc$dnaPHu$ZV6Ie@s=sLTA=h@r$jH|FyJPMRA$yjq)|Dyqfg;FggTM!ty^xd&DZMM=u)xqDvE@*Hvw;BWYy}B#+V7Ko%?<1V!a@IJjNGH@d*CC~eK8#CHaL zOSGo)A3H0-JfmL3OD}z7SC?q}=GG=_*s5OIIFDLYon>zbr8>9kbKbgXH{!*YO@zZZ zSK=udRfUbG4YA!xcX9OY7m9%+ReOq3-`5eZuM{p?_|+l)QbTK7&KY3;w0{h27zaZP z{Jk-7Wl$W7jy>Qo`{E1Mexfh5`&OvRyd9?S zt-Kp-n^wI_j|_V_Q?EA6Tr;P^j#W*;WatQ(WdB2F?d!-MJsb*tCxjG5|ZDEgF>|`6t1;DJw$J}`I8d3Gb81uGKJA1p6lW~;&$>0ZnXg6ETO zG50#&(7Ng|CO+S1TW5H}w>9Tjod`>4x7884e16KJt`>(Uc^g3||MP63Q(@Trt{I%T zn9f39=7SDvJz$5?YIg4XHj@OlT|ExpZ@`y^}!z+zYJsgs&`mqL;#E$H-Ob`c$1YM*b@$#2C@ep*O_y6PcR)F z$VB;UcHwzXSoLNA%bI$P^*Y)Utm}rdeYLN#@xyvT-%gRtvA{L<{(S(Pw2x(Pi(F$y z?E}D~;ApnW=^DE~wFi8=H=f;#y2g&C_`?FvsjP6;HMVztcc@i!7Q5${&DI8XgBei^ z*sk~4?1O1nC{b!T^WT1*+0W?=jozfPQ44Rd#W|fIHFrHbx9TQyuICGB_S;!4zuT;C zst*`v>e;ifyR7YgFSxPw2pbk<}}~jx%4`)#UQ9 z<;uX$vbKALQ33~q&M!jIm~afGt94U1RonbV(01xK&y2p<^3-6nA!B+ z5FT}jz2Di7t+}7UuCk_JXHg2?ocqdLn>oVHg~g%6;w*NrJZHn_cLYacGjKn7o-Oui z4ED>4L4${TneSGBR}Mwtsqq??a;*hat63PvpPtK_l=J}CngyZm%yDd-vllp&DFD+0 zV%eA)?IHh16FBoZgiSN)08!0jg6zBJ99Z^|7kavsg+9nHOX zgQ9)KKzR?-_fp;X^9p`qW{DrXt3xm^Ik}}M=42t33>(d3J2w#78Fpet!W?ezP)fw> z>&o}rW%KLVPx;{0XZcb)579X9ZNBX27;ZJwUql_t=AJ=yc-F^0BKF8tZanC|{_3+p zG3ay_ulzkxf8ReyY>dm|jrZo&J6sK-dtJsA%2x%SSH)*nE%KPAA@jQHb!*RjPI+UQ zD8};Hx=p)gxP0?S6cM4ex)T%AUEI>86UMwu|1qYqONB3q!nr`2-lyQhj2@(&2^p99mdwfeQ6fk*a2+C6&#+sy?#yOBu|iMLVMkV) zpJ^_?AityM-6JvWQ)DI4#J7exSSL4ijkiwh$Sop5KU7H_;pZpT+MeYPGuzrOxIa*M z=N-c*?5|-LIAXZyQ~$VL*S^5Y<03&6E%he7*Q*gJO}{4!R>NI1JiLH!d|@iQuXGfh zBd737y>fZ|d|tvRd=2Lvzw&EVg~aoNGx_!Lp5nPlcVX(Ykf%4v;zi|sL_O-R;M-cX z6B9b!=W&6vdGVYsVvcti*0Rl3R`K;9XjvJCS#hu4R^X9QG)-{crDiySV$|Dm*6t>45m2bY)GID{HE_ zR{WMzUE_blI`SV}Lng*HWdDh^G1lB|`?e(xO8Gxz9{V12 z`g3jkmt4RYjR_h+cf8&rqaE~u7@OQVB@rK7%jWmAX1kI;* zAU0oK0?hJi*W=cqS#0p_C@Q})d;;sl6NvY$Ij&pQTe}{w+jhD>H8YyZYcC1sL&|C2 zP@1s#IB#=MTj!bTTSR>5=t6ZIf@+FUQ!5Y`p6(&0%6l5IKjHFwyyto+5qEkQAqJY2 zCvH_VUa0-A=wFKdcEO7Fuzz4Z;t5L{g3D*^TSli$%0L_W4PtE5NPdTSyM>mIZar%S zJGx!F7VVKynPvUVt&d+}>YQ;|+phap4(Rcmh<}UcM70k-cNS8AN>&>x5|`g4PMIDk zvh$l${gjzLVvT2AVv}`^#kc{U#0`g(7kl?<*WJt}hu6EP9Ycz&+`#|d`)~}$Px&2e zd5kw4KmV391&mcZhbYJSU(SPuiXNey-~XZBGOgGN z+%7s^{iF7;_OBgR{oF3l9D;KC|4={CzQ?1viec_r(EOtJ{k?Aa-!*p)+YF}j?2Av) z(6P~R;yiUiV8&+c{<_!+e$cIsmS1?W&>5aB(9XFh>y!rzZfgz@ylFAh z&(iW)`ZYz_q-@P$J}fJ!FTGaFTW$L6&0XyW(^#F&PUoA~YHQ#r73DjXPikx6gF=2? z13%=Tt$~m4(NpXRT1)*r5EL%Pcdt%-r?0%fbg?_-o3=^ss1>7Kr!=vS6UBWuFx)Rf z?hXW%a^v) z@)7aFDhX$K?Tl@v$!q6s-?VmuI{As-RnJm89q$bk)ANrZ-X1ete5iMv@*pSWwX>DH zcE-QOYiC>sK*n_db=zY?Vgbw7UvlNw{j_VDF20+&qg(^S^3XxTJC8>X8T{*Ie$H>Q~rBH7!sr1yV8AY85n%650!6od%@A3Zc`rW@8hrcRU@2yo?t$$tKH;*IOKf#7A?xP(OlJv`1hacK;)$a0R zCXBRumSPr{hSRU>Q~lCq8_0a6c5K1>{QooU^gBJ2;^aJ^%RTdjXq^89U*fCnzYouR z*J3UJiZ*=h%u?~-EpDkUZpQvoKjJWKm zNb%`YC1StqxL^A7pJ_)vb4RZE@4q?nSLL`ys&gz(Yo!0o=jHzy&vHgY48`sGU-vBM z+0c1^`woc8hI#z2`xe+gml@0S~*zf+MZ_oWR)>RDq-9P>t zf`)ng|NX8rW^9!HxBChIPUd~Loc`O|+JD5j=8bs+?f(sI7>ECRW1v8(0+jFYkLn83 z&y^w8^=Su{;tYr0~QuPh!Z~c_@&N} zP1`rSVhUTfux` z1Ruui*}|AlW=WHl#ywTK&>9Bsuu7Pk?OD_kJ4?R=KCuDmE4SPxn>zsy1(n~MqQ zRUxpo2`qk5Sor9zU~X_ZsIV%paN1`EHw)JRhva8`#*w^`J+m2@-@Cy5F5YJq1AO4b z+&w(?_yN{;d{5X_a0#Cim&xWk_J=m+zP!heS4`~b3Qf8X#f*Gr(5A@9)LR{W#pD7t zAml?G>uz&(zvS!lKCi(ZZEarpw0tiV=JA(4$hOBke#5)zx{-U@ zy4$7+;$n@mteQotF2_AioPW`SIaW7ktnP5p$8mW0DXteU?0=Y z@V0(F(0uxJmUqNKKI%tvu$W#L;(P4m;c*S%uv;bAR(364`Pd$Au5yCp@=Nf$YEZ9C zOYqN~!pBYj$fiE)4EK(N@t5x}u%fs7z_(kzeDlXu3~~lRY3F8q*YhM+ban`&Iu7EO zHYc+b{}A{iJe03ExRO1w4S{>b2lKVYsm%3xFiiR!%8ja}v7n4#h|37&>pG^fyvu^& zn?o4S4Nha(V}s#N*brVmG>!F+2!^eb!ugWUY3xE!F!Ub~!CyM2vHO9+FgRZ%&wQ53 zK8FNDuy-V%y*QNx!~{cB_eh@KDV2@;BN(pOMe=34Q&_L{!LW971Rv*?!nz(02HT1e zeBt4h?EAA|XxcxVht8VJrfdv{w)b55t9g@|esegqUhB%;(k8QZTf!kb!j;$9H<>xg zauaan0rw}fmK(w$skkd2R&olPzd9WJp8&t!W(u=Q4u{#tfiIafh2>im4(2<6k32ht zb(;|mZPoy5}9TyIMtANL}PGkAZT0y|&LZXOw5<6a_`=GnOs-QGoQ~ct*ZoO+cps^I?ZJV>svzDVplQAX$~8? z+7wPYw-O8U%wes56oRSaJ;coDIn1SpG3cv#iN(ot+3cx#;C}b^!aH_8o4h-hty|+G zA}trOkZPaUSJpuc>AjTI?*D-mtlB}$a7kho{vX()Fds2+QYzbh`6FvmwY?aiU&o#; z&1LWRwG({`Z(}b+9$44aLs);wU}j_G_rG7Z5PQ;3u#v-xfqsOuC^#^iJ?m5&HXf}l zKAwHT{s^iFE0QaV$j2X8nu|RQPqGwqI^~6fTdToR*PJ2)?_x#8QYj3vz zqXGMQW4TRX$*o|#_iT1jTj&bu{OHIRY|{xZIMR48&r|jh zJF%lZq-E^k+dkc7ow7T?o=mY=NpDt@dMwW z{XF@_A=YxGAB@?S$;0gTu`a{?z@pR%esX&{t8%9k++28$=gi*4jIR2ErO#DvK6)!_ zwyOiwAN_z=8oQCrv~CaIx4q$Iudijg^KD^^^A8?2el;6y>j6FI7>hQx^}u%K6{Z*F z!gp46sB`igt305XSknF(d$Z3Awm9m!)8yx@V|6bmQJeGcxzE_A!Cqj#SI>)@$ZdSn z4lew``P=p{*w{1e;Kw1(*9W~|dyljO-{YJIc)egHvf6>?O1WKMpRo%Q!v(H>r)dvb)&c`Cmt+{X*Nhh_0z*{9iqqux*{ zPZp1@dYi{Bi2mPNaJ!-9}3{0CUt6$&8Ud{G`_Rk*k!smCf zwD+D+_4y}$`{7PDB(*JU==hO0t-Fmmx_Uy7$=`YKxUH=BcTbqT;w$goY!kbhB+uE4 z^NLs1OT)WC&7gCuxx7kEfc?kJfOpx+muK0)>9Y;s^R#6g&Q^qpUmL?w8+n|}E)TJv zoT1i{h1@NrHaq^k1{@sMNWAP*gAG~b2)3u23X{WjEUcalH2kBvh%R8wdJioRHiKG; zlS9h0+hZ-@vQ1l&yTFpoaV`!8OSKoZ^Os^P@)ZGx106-{HZ37NB0qdRxtj;y@r6U) zCz$o+!~EULiqPgkW5_AFgg3OS0-4f3cDzXD{&nO%Np4Qi;r0rCBA+cx+|mHP4_d|t z?5PU9^VNdKnJN6oYnYJ43TF(!%Wfy^ch6$;HsrGA<2s0E52RDQ$^*-t^?ZA*Cu}u)&;HQu<7-R3(Dl_l zXZvdQ7Mb;*>O$Egwq|S}F+8*_1f6}uHkJ^4LSj2O+WiIdHrvN1bo7EQm!7bF7x!_u zY%e%7@ewQ4X+Mu>(+w7WNMSpspXb{3iQ#(9Fb;+oFvNf%2L5l3fx5+;h{0V_xc$ls zQ16udM)i?1yx_xXushEHkrMSXy+{8n_O4bBaaG@f4{iOD$!m7uKkS-=yk;lHu|rOK z7$o|Q-=0x;b{4BVKS<0uSwp|2;#C%67bKqn9;Uzf@+#|))L*=HUa0qdaE)!L)n7c@ zy;1)zGn-An94M+?$1xy9MhLs ze1pZr1d5FnGWAwdZm{@Ofx>NdhTgjQ4ff@6pjc?XMPKLmbr#*QzsU4ish?fHDjP5{Nc2sq zrf=KtDqFrYNaUs$(5L3T%1&Mj5)&(5=M(1^!q+tVFx8!^r)#{bLR?+yc;A28r9Q(IdX;h zJO~m+Ml{l|Sbv4pc@iWxZEC82H{%M+eI_}Ni@w`P$uH$|`-fcg`-fa%uN?b{b|EA9 zhzSQ-J(GT7{*gGIIOHH(_qwkLgm@mi<{*oF(O0;iiRGnhA7WNt`-;<%(R}FFL#$8r ze!}AO5Pmx1Fq=4}pQu$mi0iD5GT(#!#KyJVd6k>TSmVlpqLhUf-=;soZch#r=Gz%B zzv>j*{X9?{saKmX>T`xgwCyiCiHiJlfpfpa5{}!Sab*!0Bnnw4>r-6h^~1VAvEJ8; zL*a|;ws~KXk=U0v)SY4FZuS%wJ!kT!-H$OF4}bB8&jw!M`2p5wZWl2>E|WWjXRtFl zzT(Q`t9)?RoeXCAh_%t;Rz3_x{Gbd+etvH3;gX-y}WkmDx9kC z;^iM6Vm+@0h&S(N^R=Jl_h$yl_l~g++}!m%o4&ulSbFNZe%7wbe>qm_vnr$QqeWDJ zE#KeXl^^{YCMv>0-m^eME-v>ICAVJUqrzirTN^g%&y3L>6eVzxH8X;;?9TUbIK3)`X+z5ctHQ;&_iz0qaZi?*c+M@ ze#1Kri{b@5xRNqk`w~NZ#w!No5%Zbkv|5^Wk&3kZuayt6@p^M;^+9|0{;RA?@VYFc^4y`-!Fy&s;+4Z1Lhs3T#O*4!fWko~ zi3jHG0N1W-&+_XY^@g}pOK7fhwnjpob$95wt>;4$phmnk&2QPuaS*oQE^)mnfv~(w z9l(B8o81H~qk9q`KJuBF?vEzk|0ta8nxH+`*05N#u3ZO>4;jtXf2*ZEi{w_d4u4-= zs~_eW%U?E#q`zH!dO6>x*WRPp?SY=ZGr@O}3nUmuXYXM%R_WxiJg`!iM`uS z>>r`!KAK(YAujswq3vy(JXl-`E2Vd z6H(nm1(xqTE%+(VSmLZeH{R@g0&$aehh!VtK8x?K$Y`RKN9=m7tF&VT)d{ilW*7Xm z_c^q4oWia()ZPJjCw3hRyEBODjBq%>a`VR#yKbxZ3y(OZ{chO0#%yhQjfXUC#iree zq56+61Tfn-+V>z%KS*H39EVZ)^#QY4csK30%5PiC(m!aw)t~QY$DOqJ>@)ugTjr}h zTU2(iTuZyDy%!}q_y@b<3M%&58il8Fh{2N5#|M zZoX>9yS3Nib7Y|yZXKchZLrwHKi3#UbzG)r^84e1h;xTs3;sP%vEn~I{RzdMzWzGx#R zJZVAveqLo^8?5n#+IGM2nZ{bocWzW!xX)-s^&51t7N=Wl?Qd9EUd*b~p319!E+s6A z`VsdCEh;?5`4dmhZzQIS*R~~U%uBxXqPC6gs$b>T+G^WAHs{bUV`3h!ji+fK@W`jy zc-oks<Q!8_xpCV})@%|6{@9&+sy=P_oo1z6tJp5Z#;*Z{H` zSWtNxllCw}caP?MMo=JBv6x3(WB*XFdS8fm+S+*7Qs!0$wzEY(Qyc%?l_QTG7zTkP+txH+kw34446I%I7{7FTL~YxbF#W;7!ah4u*Iz#DF0N3^8Dc0YeNJ zV!#jsh8Qr!fFTA9F<^*+|F0O>UniCOgclGOp0x(oI)b;HbB-UX&?LIsM8^*y9 z1BMtd#DF0N3^8Dc0YeNJV!#jsh8Qr!fFTA9F<^)RLkt*Vzz_q57%;?uAqEUFV2A-j z3>ad-5Ceu7FvNf%1`ILqFCPP-%_07;_RguFb80B3fiR4TAs!4dV2A-j3>ad-5Ceu7 zFvNf%1`IJ^hyg1BMtd#DF0N3^8Dc0YeNJV!#jsh8Qr!fFTA9F<^)RLkt*V zzz_rflVf1f$vFBR%1CqhZ5@T1Kggi+jMt&iq1$8P`xX0vU6msAy^`Ix{h(gnI>Z(a zo4}=^0mL^0zOhI7I}vyNR18{N(Y^;XP-g>^W;dkr#}V~lrE6*8oh`f}@uBu@;F~Q6 zLPl+W`mMbAM!@pfU7d04Qhp>t*0A9WdDg&au*m&L-1t*ZNc71iUQwtg+^=00u+Fpc z?cjRRro;`iYJ+>np2Xcfzc7za5yT(dl31a>+PA3shE-=DFKX|R_%N`P?rDlv-nzLx z&$$vt^}UU@@#33$6WeWi!>0s#5wD1_6lcF_->dRonZcK~(Au#(xJW;GbOP0Rw(7cW z(~v0QzDp)EmCH`hzK@gdQ!zIGr1rN*8`$bL9M{;lp1po#j`kg*@X>>L%FC|QPO?va zA@XV8=s6Ppnvc7o^>f7it^C7h?OQzkFW2YWa~zl1Ez!!o&$+O|Uqh&!dBYF0 zQIXoWfiCqf4>f%%QTeDot)Yf{UgDM?{9(>K6XL|)-JsO?oiyfkYK6i6v7_iaO=sg0 z;n4G?QO@2;uc(wo+-)Rp1l zU|KP|uP!6mj{O70r1<5P8;Y}RRF1bec;<-hOiv3Kv7v@&{wCSR?Yj#c8~>eu*jduX z$2tJoG@r&N#Wu0&T|5e``pwR0-S}0demRL?IlM;3yP_*91$<3}+*_}8!@3nnvTc$8 zfkCs_$@C^kOT34{>x)M4<^G2irHc4N;d0er#zvbJ@^grA+pZ-n*)Vxouyf_r2P0OweNX7T(^NusnV1Fw&tTREV^xTxc>I! zvZ0$CVEDdru->Pg;z=3K)rQ+FfBHQU z?irnRsZ+4mid*vgSA!ed^1x*kZ9)#kLA8i`Jm!5xn+e?lVNG&Haq@_}&Ee;*!KyA3 ziP3dzTXwGw#Z5Yi^Kg{o{kg-fuf9cbRj5^$3d*=bxF|l?(3Ae8$I%GqVfW zH8C}1tF|VJJ4tIQKYrt`YwQv)HjKYthLkaeaThPJRr{?jM<;T&B7w?tA6?L& z;~GC1eO%{Mcqo;dty{$O?%Mb1AR`Yvb81ZGgOApQYajCwTlVM<%R3qoAL{H62_>~- z%hN_7khe%Ejl<(2F%VO<1HCh7>6b)Uz08Z@c$#F409}=>#C!4#fgcB75#O!b2MU$5 z1*|i(vO9DO)4t2rCC3)VC1}U+d-)4M#qPmWXH((RZ1o21yKgaXD?=ag?(Vq<$~0Xsec#ns91-1{P8AG#X~!n zEpT|p!YgV0nYp|GGz!%Exjb)W$Y*Cy_46!s1FMNf#G4!Y!_2E|sQr^8!{I=~JjBhv z#>0^A`8aOx^t+M|q!Tx*HW=cTj$%y zgI8<&g0JIKzPH3+`rAz`gZDY0wUa)(t{xg|F>|^68(qR1H+V-b0I-2aD^1 z{Fmy;GLZF%W!+!+ujmVh|#&EV-cfsNyj2a=aP;^jLsz;ix{0tIu!v!tNb3fHb&r(@B z7L}uONyj2a=aP;^V~fru9g7&9OFEV_x)wT@bSyo(7CP6`o7Nm%3!O_k7Dv}Y=aP=a z(Y4UIq+^k5p>s*cBG*Fal8zCD66dxuj#!HllM$$D-{*=aP;^jLsz;i((j^OF9CD66dxujzWbS-o)=~(1i=v>mV$hFY9q+^k5p>s*c;^P zx)wT@bS#dph0Y}%OOLLF&Ltg-qidmaNynmXLFbZ=MPr4|rR*2#{=$`gfh+q6SN4lv z_^;|K$26g`bS&x*I+t`TnhSI;=~xsS=v>mV7#^3B^`?xol80vF*=uYEMjyn=~%?*T+*?q zZ|Gdov53*Rq+`+iqH{^dVmQC(T+*?K(Yd5!5umV zh|#&EV-cfsNyj2a=aP;^jLsz;i`qx$l8!};&Ltfy9e)d*OF9-uM(2`_MU2iR9g7&9 zOFEXoI_O-|v53*Rq+=1Ib4kY{M(2`_MU2iR9ZM^h&Ltg-7@bQx7BM=PbSz?YF6mgr z=v>mVv^vtcq+@Ayq;pBfB1Y#@uKT#k(y^!xI+t`TVstL)Sj6aD(y@rqxujzeqjO2e zB1Y$ujzx^lB^`?xol80vF*=uYEMjyn=~%?*T+*?K(Yd5!5umVh|#&EV-cfsNyj2a=aP;^jLsz;ix{0tIusrLmVh|#&EV-cfsNyj2a z=aP;^jLsz;ix{0tIunSUY}q&x|p)wEAW~G%hA7n zrw(32Vtw>1m8D}*IXahgEMjyn=~%?*T+*?K(Yd5!5umVh|#&EV-cfsNyj2a=aP;^jLsz;i?$t|OF9-YI+t`TnqPD- z=~x`M7oAHw7BM=PbSz?YF6meT>!5Q<$0A1Ol8!};&Ltg-7@bQx7BM=PbSz?YF6mg* zCOQ|ciC~-PTq;Y)qH=UD=~%>aT}w#EqIS@^q+=1Ib4kY{M(2`_MU2iR9g7&9OF9;@ zT-OrPv53*Rq+?P0=v>mVh|#&EV=?R-I+tA6B1Y$ujzx^lB^`?xol80vV10Bh=~%?* zT+*?K(Yd5!5umVh|#&EV-cfs z;rbNz2c1i0T*Jb0bSU{RF*+Bne_=T~m&$)tU(OlTN6%6jbBEXtIv3^+kI;(YY{ph>XsKxkF@hF3cSw zqjO2eB1Y%J+#!~ub7Aff8J!Drhsfw$m^(y9=fd0}GCCLL4w2EhFn5TI&V{){WOOdf z9U`N1VeSwaoeOh^$mm>{J48n3!rUP;Iv3^+kI;(YY{ph>XsK zxkF@hF3cSwqjO>I5E-2dbBD<2T$npVM(4uZAu>7_<_?k3xiEK#jLwC*Lu7O=%pD@5 zb7Aff8J!Drhsfw$m^(y9=fd0}GCCLL4w2Eho~1J84zV3{F3cSwqjO>I(BAxIMRYFA9qzu<*%qA(bBDdx##Kh=!rbBM z_nqy~xt7Y@;rhcZaa{{AcUZyS9M`n~bBD%TX5hLOVD9k7iY>P2T$np7)pnr`Iv3^+ zPxWxcbuEUu!`!EFxUR)8ceu1nWovXU%pG>uUBh)P7t9?tn$Z~7we*-fT--b!*R?q2 z4$J#iO+x3Ajs>Tp{Bd1NVD9jI89lCR3CtaC96otvGF!pZXN^~yF z9lmrmNx%pKymp>ru?`wL_45bL0GVeSwa zoeOh^$mm>{JM=i`nvBkcxx+Q1V^*SbVeW9HU)~gSF3cU~ZymT2oeOh^0aKEa(77;o z81!K7GITD?9TrY6vK*ZYbBAXp9l~`jfw{wa$)UKe#W8m{x{wd9YjMmSx>fhbb**&F z9Uj&%z;&$*%pFc@(*@VH80HSWmighj7Q@`(g%@5n=v;1(-YRQn9lgIv3^+SLS@QMd!lYVZggS70|gb zcZlPI&ZX=Z>i&Xjyi^B0OW8+oy_d?-%T)fW`glw$m|4mJJxgWG9kw|-#{r!SbB9g| zi4N#om^(DOR?Y#P3v-8I&+CNr-=vIo&Iz?g=fd1!&78va=v>mVVC0n#$>>~|JN#PreF{1k<_>2p z>6nVng}KAG$hR%h#Lq4!}8akJBEEr$G zEDfCtbBFOqXQZNYVearsz|>T9E<8tfW|dOWvyglIWXv5Jw`rD2&Lwk)*0)ZiqH|&H zaKeq0RCF%P9WHu&F%_K)bB7swoYK&_Fn73QZr(I>F3cSUH+qmt&Lwk)kv9*dqH|&H za7@F+spwpoJA9DVCKa6vbBAfR^Hb2dFn9Q(&>}l@F3cUKO!v1(=fd1!nNM@=(YY{p zXl^sx9-Rwwha=q&*rRh{?y%Y7@Al|im^+MGRLlXL3v-7j%2+s{b7AiAx{IX)Iv3^+ zrx!AFKg<4-NSL>_o-U#imZ82y=W(zTtl_QKUY34-h}QGDxWP)pE7I+Rls#6#&OSd!~m78{t6w zIHtMqGt$-!jULErkg}T7uFt9?)cR_BvQ{Udy=FKB-c~b2l;z19ydBGs<+Ih?H zLwrj9a4O$Bc|BL_tL18awH>7nQ|d6K4pZ7>YJIg_t*^GDY$GV!2+B5sGA5wbSIgD< zYCFmtfig#+%n>Ma3Tl0|T&=IRqr?~}F$PMEffAFT)>q5b`f5AMJ_5=<0?IxD%02~Z zeYISzuePJ?Lz)pqi1jTadIZeKcOy-lYeC2a_ z56?Dj&FcKVKe$?7Em!NS?I?AaQimyZn9?Rw>#OBzeYKsSpxGSz+0tQ~Y3uUJ1e06bP%(RRVsHgI-T8{*{cR&dZcfw*U_*ZPh5TM}Q1tSnab zHzjt~`wFL9Pqa4E`wIQiqr^!QLWI%>l|e06`X-dV38imB>6=jcCX~MEl)iz|H&FTp zO5fmYkt)=G%WutK_ueMNIkoCQ(m8D#zs1|avC3XlUizdZ%r)yn+`Q#$wzr2C1N-Ym zvpa?TsoedNk!WCYkG6gEus|`0)go@zB2E;p)0d9AO6!<>oT0&0QM2T=L|N*_S!11Nm} zr4OL=fhm39N*{#M2ch&q9TRn|)VUMN+zDmwgfe$RnLDn`9arWKl(_?C?m(G4Q05K} z+%kr5md0t%&vt_$ovt&#;f2%cSp>nwb9>n$^P*{!x($Ym8wwID_-Os_%=09U3m{-Z<&uj`7*Uz zxsp6HcDV3Lo0R(c!)X4>yO#QiEg^rsmnXnWw%e6 zix4~Gv?voF7=7Dbzdge|O(*XiTESvjOFy%;gEgW-_f_5(d$&m1kk(y z+mWI6M=k$RU#pW;GD+uDNjv6yS1il!=|@nTgGP9<&L|s=iAKKx^V5f zve)RDEImnEFS=KGJKH%SnCf(dQ_P}dSK@cu3&4tJ+8XBb;*DXky|$*kL|$+CeJCdI zw^+eW;J3L2@wV*B@Ts|Wf8C6-MWM?6o>abc|0f1kgNS=v&17nS)ba-JwcNUSzxS-# zy3SO8=JP@@wnTg4@pcxlr9xxkh+B2R`(Od$a)r8rQ+jV2lPlX|;J$;lE;RDG6NC-x z1K7_2hhDNqJG6CO@7&!ianDdHui0uI+fgls__0w4&p8`U>@?hjub8T>p|Lj+`c-m0 z0oy6}<6L^fky@QP8Kx{LNL!B$nPc%) zSpK}IsCcb@YM<5aO|?x3J1XwC(D&VuEhzW{vMmX`|1zPSCcu+DCo(UQgm9#^r@wyKcmncA1E+ zt+X}s&&!{2Gbe4W*pyx1PGz;6%VFbb{LAH^Z9XinZ&}cV{pZ@&H$QU+6@$m<-+(q&<+w}6CaT0Eq^OxLyDuI*DDF1_H6;uC-dHM-S(g5IClqKI;F_D1Dv~k*XyUsxdWWLp_i(q%DDrayR}od zq{z7goV#85x2%+N$CSC_%G?QM?u0UTLYX_E#IR6eSST?plo%FD3=1WOg%ZPDiD8`* z!%T@`ro^ziPpSKwQ1&%Y_I*(HeWvXDOxgFDvhVAZeP1a1zEJjkq3ruY+4lt=193l< z$3}t2KxBCg6nG3omd8MW$3SFx3>0__M3%=up&SE+atsv8F_0_AK)rGd)G5b6opMZO zYJb#n<=nxPbB9hjcQ`BO4z8R#xN`0g%DF?}xdXRFo;w7dJCNnML*TgsS)MzDat`In zIg~5sP@$Ydg>nuR$~jah=TM=XLxpk<<;ppfE9X$IoYT45AGKU@53aZeSKNau?jaQS z5Q=*U#XW@L9zt;sp|}TE9Lz;=FumenTyZe2I2czPOehW}6bBQEg9*jKgyLXAaYCW? zM=e*}RVeN%6n7Phy9&i!h2pM4aaWomxt4a);RQPU>E$DArNaxnroecX*EmA$k6Mn`K8Xz)*ve}kf!98k zTTWJ%*FFNTeLh||WGAnE1YY|*e>=lYUi%2V_Ay>{eWkqi5qRyBu+$8%eFR?nOkEe9 zBCmZoUi-{DzRFHs`!Kxr*+1i^oxJv8c4Wt?02|jE3N%t*{|PWIVRM;93LF3 z|B&C-EcEl377xF}7#IJ@cgQDsX=}e(Icxdv@R}=YY5c!*42R$04c_4bx8Uuowd{A; zcv3kU!`@}u!te0!w5irf@Y3#)PO)z(eup=$UQ6@U#y?#A4&%1|SI<|OO(SSb@+|b` zzr$@0c+(u^tRDft!xy)XpgGEF@6CRP!}4~c`quUGi{Ih#Z?v_$HePv!`zLJ;p<`() z_E+U4O2kn6jkgbCJKi|aw#+k&gTE@j9jra4kn0%_D&PC0t+}ncR0&kR)Xa+7@0-^H z_%h9%{15p5!uQKfqj@h-Ito7&@!4$?Wx@}^R&l3rj}b)u1R$!&vF5kC(r*s>|F<# z6h+fM5D<}^bGSV+C_yqiEl3hXkStk(AUP@FfIB598Ab6^6ofm1B1y8a(?k`-0Ez^` zNDu)LQ4|w@z17o4oq90$D=51AJPq&l*1TO^U0vNh(>vXo^K0CkPDy?< z=Ot@95~qwe{piu9Ba|Q9>R#j9cQ!BMWd6$Zsi$`|bjLSoqG8*$<#Xy26H+r)546<{ zQ+MPxO@Csz{xjE3d%|I!ERRO(Ob?hnv^&~&*JlO~XZs({d%x>PX2>lqSUzKoOnP^% zk&NGX=oYtqjJc<=zv4tE`=0ik|J|4r%8yKWbuY^=?{lN_gVkqExGs$skI;TF?D|*7 z+kXP*ln2edqiPw(h5XgY;59zFI=wDyA+cQi4lR{lv&<+M#WhI~6Crz-Eg zpJxs2vF$b>C36<}a+F$ME|TNMtF*`M&s_WY;)cvK{mck8>8C7g!*X{uQ%7&_%DBp_ zC!Lzljb_|7-`-%FH74fIe?H*;nQI4}h-S{lbt}7m@a~C5K6r=YcF16U@ZnTjhLfr2aG4Mh(7;c}DCXq2KRvj`5Ld_vwf&^%Q*K zh1NxMntVeUf4F0u`%J9y^AYu9f`8`PG%r@-b{YM3wDN=BzuEZzlsU^ogI1Y2SjD|r z)y=tUGtUn+=KGOZb>WbaKYhPSyU5(1pY_d1)gxC`uH(rg1CbeMr^#CYpJMK2pi?gZp$bojiqkpxOAZe^ZrO&Qcumt1I`{l({;;QEnS+wfJ6QBA%ct*1TSS;HT`dh0v3 z-_?wzDCfV#zkmJ$wrP({gOnd!Fa02Hi&X0txPI`o5ewKK4&)r9{ooqEE@63h>j3@I z(30%WV?R+kTYK|dwRM`e-3#>G6s=VA%Z3{l*D`zKb38i7`7_s6%50t)-8y%H;|KqE zo4MD~XZ&KPWIFSkf()DJS;vHLSpObF?o+MajOB5#{^%Gr{?XZN=RUm$t3Pus>iu8x z&y(Ygf3D9yNcq8c^&HIpx$fE7?ty0qGA>;AMJMO16>R@yc?T#zGP`D#;A{8JyuGSAkRl&0Ua#P?^;McG!leq>&*cL&G7=+*T5^yf`K zdL#27Uzqx)f~QbFb^PE(gUr3twly+4esKRCnb@8y9~!0o;5P@D`7_8~Jku*SQkkxY@{0-*S(Z z_>(h6zRR0yU5RgLyO8@uQL>XCyzEQkhk>u&t+}9@nJ3SQ2CM>a;&Mji*OFYFGa1X+2U~bjp?!%DmLXp zj5^ppQlHVsOYA*WS2d^no4ou$he+LY)A16|P=2TBy><5UMM}Onw%-`%Cy=I5uB)DlbiwVwQs%a6I|57c1!h9}EvKNv9!wxYPD{9wrb)$#Mc zz?tbTvtAzCVXW&1H!AuN`*4lrlihVMo?;)Ko3g7ORxXC)L(5Y`wI7+oADVl)bq1%< z?Ke&3Sd`&>j6U|{SmueZGt?JO)!69YvDH}D4}SA5!++P^L$x0~x&Bc0+lnz`9X~kb z__1u0xOzjCADlPcG?pLp_Jiuc_pQ}S^>&x+IOHa^_?K~FEu*S1@D-NdnkGgC zJ~Q_^R_17__RLt%*FOJrKNY*b5nt;Z&Z~YcG>qlvKN_Pt-JX*3i*;?U%D%9h<=ahr zK=oMIl=CMw%dTo2pULtE8`C=*GyK3ZWzKa{Pn7$Jaof22)!R+Y82$0oTXIjJkc5L*4(sBj(yH-Bo#t zm-w|G+_|uMc6?+-Z)dKe-wV-a-D?l(r1CfKG4u0cWpf85Ui|JczIN>+-L%A;Cbl+y zRVbalyF@hO9o6f(GQZWiLY!an)B0NGH=bn5n%rVYXvi`%&qDeteVh`E+Gk>Z66)u}p^!sdS;4=GtdYeGqEC*v$RX-qu_{ ze55(cbX=54=X}%1JoNl)p*!2&%lYMM-Kd|VJ&3S#J=&Al^tMclQ&eoBPY!CsSiO=~ z*Ii+*E&1x(p+-CCIZ@Wn!SZnydS-vYYeUp*N^?q~xTvH>nZFoA}t=Uj6tIRE99Y2`% zTClvg@8XJ>_FAydc>6A{h-t5dg5A7*7gxlz*MeodeHT~6EomP)_}|E0!0G1Us@Zto z1?OWw2JOK}z)en7aGTz?x72&I*W&oG3hoNRnKO@6w`Lixmh?DSGWbd#hxTBo=DiM< z#NLdw7ann(?H5XojvlIR|M3y058;-CCp}kPtq6QpYNfhWRV180>a$W=ZogIaq2K=Z zXz_EY9rWA(;iXqO?|*Z#)ZH)iS0&1>axN17Wln#U|GQdhS+D)2vgatS#uCm&_}T2m z)%w%gamGZHuF$ftdiacX?jgLlMPGGj!yPL9n|n+3zZj(&Y`jDD+_|^ZSHDK7&U?2w z!{06z>guj~EN3Cv9N0s~T{ZenVj#7a;>!`=ReZN#)!mD%l;r4Bqm-km_*g2N= zSI}OI1T1A%&x+#wEt%>liN9GpnDd7(ea?CAlo=lj{(8!h`TuKMm1P>tDX%2%w%**I zFFWHgN8+*X*JSxZAC^%P=jmzu|Bgvx9ErD`3>x`GrIo}ho-pzi?|j6OxG=r*6!oo5 z?~0JP?(;@|$qx@Z64TxZww1S!;)CD7<>CD7<>CDt|&u$Cs@YYM{z|=dnZ^= zZy&`K@%1<_^`rC5>}JfJ*KbM44{qPY$nU*lX6T7x=Kku^wz-|Jj+y6KUqAV+)1p8s zw*RB`+Nrur_wjsb`i#-)&s^KF;DgLFX=04(a%dH|*N>z7tGey$D)`=m=>zJ+Spym0 zr(Sfb-8Y(X-VDcrf9Bd@8Dp3y&EjQ2Ke%H{BmedC8Nt|)>8C@FM7mQ?m~rHIyA=BU z7rtZtk3Qd7A1YJXh5nPijMi(*w%5SVKbum2*v^dC(;ht@x*D8&o95)QzOULu`|*?i zf{e~!+HS|`WkEmq+i|CZXfIuNw600d!+_7e8yl2Z$~3HM<})93Y~xm5P>$uB+*wUm zKVg1rxp4j~ZmJRHx!cnf3u!5H+p7^Q|5g1Cy2*xU#yKiicO~bkf#zLm!#3vDM+4>_ zZ<$r++(k7~vwW&&+UjXEcY&UbzNz5OU19FK#(aF*4Yf(b`FDJIufBb@S%XwM`>?yE zyt$wJ_W9!arnz^sOs^uj^!PkxuJzr`Y4rRD2C^NpO^wk*S{PiMaNDmuAO7yuki^d| zFmwCa_13%7J$#7p#m_rx=yv>rpWHUX$}rx1OHh|@Yv$WydpFmsJzR?LK~JV3$<(Fa zCg9rE@4nZS4F>j*6?(@ zXQ6x8!?_86+R9~~3=8|}8}BuE&Vs)B)vS&A+VVB?=({tUb#d3v^XXY0{`Iqb`h$}d zS*BzD$~sLpBmZWNJi65>lmAJ+$~trIK`awHc!68M!xah7eP)r&Hjc;3I} zvXCFV`o8x#4*xut;_C!+?XdL^g_6pD|C5od+qS-iobrziVSH@-(~is!&Z))u(}opS zfw&@!pBq~*5tcHuhxcZg*pJ_EBp!R=9j>E3{eY6V2))+;?K|(O6pqB%KQ#NF&-_?O zNxUwqJIk+Zc*K!-V!eaRpY4erO5)*Vji2kU&IKhN_|g5$^LX{c&i_W4cUesRvVf9U z${gKq_R{SB?tUflUhmx(<4b-Wl(_kE!+B@d0;*1f9$eOn(H}ZV<$pHPJRh0#_WerY zPRi(CyxN(d#97XoF*I}9SA+Lgis5!&O#79R${#cGK?OS(s`j`e@$lp3y*jH7?sq2c zYs)epzMo1-+$L8^&hK66cC|mNiB})3XqyO2nU{Yu_juyPymBddpGBL31ePbPoBl4Md9DN^4brtyOjxCrc{#-^Saqngo zIe*Z~%1YulI~o3^JH|K?7j5#S0~a z`kpa5wv6c)-xlnlXFXU~!#>+iN9s{!&ArwZjb^w%Z!@vz{Eo80KXdJyPa2-i<$4AE z;7qNJeDUv|2=+_chjp7<^EF5JGGoe`r>dyiK6#Pj#=Mw;^bUky`8itOPh!-cx%R&> zACq-_^^oz;MdWvW@CABb0Q{u%j{Kn!c{{0W@3t*5KgUnb>)mDt>6Mw&R@I16eq_Eb zZT4`kX>gzFv(Rw<@L7wH9~@g}8$UBDcREH_U7}c@msgb3OYSy2w@sZH@+0$j+IzV# zd>t2~{ouVX7@ti2V*8*Ue0EJMjtTjjj8J}Xzvkw?U)}p#IezfoT`ie^Zo3i656;-(qAN^agA3u~bMOzx5zqiE*Z`rcJINE zAN%Akc`+)Z z_JfZXGxnUdWSH`U%RFU#`*g;1$`Agyg;~F>8*n1%2RpAm$nBeR+%V+_x9;DP{keF% z49X8y=Z!v(s&zp>_@5k;tAA_eDvj#S+UN)GIcnscM~`pJw50;uZRPD%^bd>g;JHxq zpJKEhnYMGx9H8+VP2HMz*Wmtg&(df;vDC}VGyZIhFPu65X_lWv?-j4Ut(r!^J`+_= zzwVuPmg3OeHT}q>EYqKTrsc_Dx~h(5o^GF3bB~iA;Out%#hQNbXGe{EgIdRH-nP6v zUwdc6sw%}sRTDg8eu`0kWJca)<|nDP_H-U@rC7IZqoNhrhk3|8zVNP5MR?tJ^II`$ z)Z1MZbV&Qu2`8!iJk`uOF9Yu$tmfv($MVlFX_N?OtU7@6zxipovyk@lf%EW9-8Lqb zAN^)=Zr{=qM`}N~+&N>zWy9N?l905{5@6ezY}_X3gc2zf{FpiU?Q{HPPkM!Bey z)kg_EmC#>3U$gN-N;gw^$hY-{ytM;(kYFG1Bf)Mc7YX)+jjf$wduxA(^tbIo2VeX+h zO;@gt)o?-U$On5R&B0PNd5x!UU0og|4Oz*ela-Tk!N@e!&Ou};t zoMrj*WE+V)yk++5UYwLdNj&AYZ&^NHiu;trsE7IZvj_P}H7iekqJhaz6!{6`6pzh( zmHgz2GUO*LPk!Q%Z!ji5Q4*7Ha6b8oBQg02=aZi(@)O47CyIQ7G5LujG5HDSlbUI@68@ zpG#FqQwmU0nNv@$O6fWJUXff?N{pq9y%x6fgSVs#7Nax~vW>pl>Qah)Y)l{h1C>iD zaEAV$LVr^VRHW}MXPY!57i1l9UlmHTkXM(!qZB!jWQ9H&e^UzJdwH$V&+2IZy4)Cn zxDXq+;K9x%NIyj>4*HUQic%c(CH)*q^Pq3Wy>FDDG}$YYugyaGk}ir;9Q1)rDaAow z`rDy25BmPmwMIju!{u;+K7mD)(o?yL^m8c9gTAC6QXKRp{gC3IFXT|KX;G^eg%e}UV6evALL{V1vUz;=FOYlcO4k_{=vjXJZ{jU(Gq zin}9qC4KnxR)^BOIphPeQ`(lGl*oTF`ShRPUz=1L{64>O`{E@iq1Wft< zB|E<1TC1U{tNrV8`u^woV^aO}I?2yGKO!RYP1L>=SFVir>>sTu1>6!_g4we^q$vgZ zSDxaGIonNB3LMCF)H!+cU7Av0*fV+6v(?IIN`X&%1Xb#3X*8w4mN)KIdl#&8DMe1- z-cRlPpoU8+^1Fr6itcyEQ%VbcWLYv_%1a)}FUytsNIj+g{{7qZft@>=7o{`-*KOHe z-=!4kW{=i6C>B$S>`3w8V6}`$f$|@=Ks>N9LE~>q0elZRN&#Gl>nR1mXY`2;P`&40 z%d*G^=y^kCu9rV-#{CNAGZZD=6{R@nPj#ZRd;7$pUQ|~_DGv1|J19y#SE0WZr8wAw zPYID=Q)1QMvZ>+xdsdpLw!sX-dV7TDqWWAXaV)H-@x&{~a2e-ijFs_F#z`4JWn7iol& zpJm*ZWyyRgFL@-tELZ9y^_2RP-_qR7ey)sVoI(7ebWP&9(bL3v#5+nH{}Bf%@wkBa zNQuV_IgTKnQsVIiah4K~J5qmtFfSCs~*pMuBV#$^8<)okHcnRmgPrY_m&fSKr~^J%1&8f(dD|w}K4E!d z&#)c-lXl=r(?7oB+f|LXJBAI>lmeB$eAQxT24Q1imi&%l~6e9-bHdC+9`UUWbPL@+_msB;Db4+W-uFZQhbR>RCK;Dfq$i(%r3~SOYyHp5%{*T4D~Sca68w;{ z`X|CtMqX>;rzy)PzN-B~)=^@qv#iV2uCL%nTU*=02NK#;=mwbtACOqe$ZM1952lTh zbwBE=uJ5ep`1BpRmu5eH*Qd#q565|9vFpVS3GFL=<1#qe_h1wJU;Mrazt>Cn9i04q zoc!IK{5>6MNj&CvcH%cOiGG(i@qtvuDNRD3mcQeZzwaXs)D6EwO!Rv|DmUSGg7lsJ z9U^qpl<+%5{9e!g4iV31i3iVdG9>kTy{l43dX8p)YkAG;NWZl#ChCsgAzGW@H>B29 zu%ERderJiqzws0{PxPBm(MDSQ)-uuWoj#t1}bzVU_g!xTdgzXTvgC8H@ z@x|-2KCqEAecccC6%#m4dO9Rv5lh2k+;ud@p&i3*$GbgZKaNzT#ooA~Muv2cx zr1+u-Mye52W;=x%jE^5UY_J+Q@C&EXtmya@dAh0G!*i@-^Z8%xRX?kH@}d z{9Wy*qVf11a>Xh}#N#?#e{$T?IPigY?@LL1d+ZqBH-Q`740jlOrju01qr zQHjnRm&txnh|#xf?po2}q~vcsdA5?3k$85a@7a8@fBSNUU5W`&)OU4smDw)E zgs1_-2J68Czi=rgL{VSYd4}iI#fEf?+L*72{+538l6pz~sBh?hm;SE$Q_-kg^nFT_ zi>eqA)sL>Dn4pi1TN-$X_`v(-E9C;ss2u1ksyepFqA3|08|k$p;nu&*G%y;eS-$ zc=S0x_{UvkLqBda?^pGMQ=gAf_x@nc-cBw~-@l@2@pNUc?`FU~zTe^LA8mF@d~MF{ zkn#m8_g0_e-AVS2h>+zTnNYQ=<+qez!xap3IMXku(l7&XvE8zQMz-Urw*r ze%6xncf9|EdxtXTmq>X(IL9aLLXXTf?}=FXbS<}d7xO;iMR&)$>mM}dNZqvch`TzC zdGABo=*&8M%jR6}gd?SO?$yEH=_$*dw4j(S(4scW%-N7iA3SE>gHV6G>rQ>XFXs>c zzPEdL#tg6@gb}y zEO0IRnwXCue%d&LxXSoy#7Vp70X0RLBCcN7aguE5?Rh}Wu6~>hx7}Yi#+kN5tA*nv ztZ;qU!OTyf?bV)>g!|fG-PgixM{axFtp&ny64B;*8zaJf?fUI&;kLVu+b+C!2;q|N zBk{ZDy!BB6*7RNAqa0h7mwjZUrW6=Csf3fg$RJHAkWwvh$``#)QwnrmcFrk~x}l~N zxH(urHSbbZQwsEGQ&YW}D!rx@nAEhDO0)Pamr`V*0ln1Z&e1NV$l0ZasrH3l3{fgl zvTzJ=kkVXW`re^54>EL}LunqaB|fA$a8fx)aVU$*M~Z_Eq!&^gbR&Hgr8wwJ^-z@J zP!}^+@H?rBVvb6Q_ljU$O^NrA;9eXh+LvSQdD8tPKHCWQ?kMq@NBE8spM`{beUxxk z6yNitH8jqOQsTW^yq2eYoE61ud6LIjQQ#n(|0TcCATIysWLY~<+4RBqiTz}k#o@kl zdHW<~LuwcMxiof=y_3pkp8Ay@S@AFKgH-p#F^A@{=#L4%IikLS`{4XrB-}Tr1pnk` z0n{J=UuT@XKK|$eO6g#G>WkOtjI#{$y=UuuX6@NZz15O@J1GuDMD*=fQJsCdGW$WX zLz|riU-w}QTUh@{OM3%aeL9t|y_ufZSMsjiN!LE*UHkaq%})D2xK@_y2X7sJajh*E z&rU3s*G4oPp>pPI&H5jwx_o5yY1mw4pO~5Tm%8BJ6+Zw{{78GuQ{NNBf)Tmt?$S9|+4_zxI*7x^HS-_cgEIbvd-zeb(!b zH@u%-KkLN-iVxbxuB?rk>%|jH+-Ov}w@#ba^!Ixjj?gtSn>ax6LDT*y_J4_GxzyiX z+utb;xHb+@e9$&NP~6ZqZcseYHl9$N(KgOd{Lwc4$g=!k>BAJ0T^o~SeJO@(8^a}M z!Gcw**m#@VYw0?gtJ-@Y*A)N5=7gpNF4+QqTf6)bMxTp~t1^Bv_PZru@&0N}->svR zA3PFE8GEgI>Rs%eWuD7n!J{M=oZztf;H;ShoLDBIzVyBQK-PYKi_JX0`-&?rNB@+4?><qli#3Jj;SJgg4m-n@B{9~tON z$*bQ#8nbOHk?+_#0#n;*N_=*Ps4slL+6TWiNRYAD8ta<&@`D$z%u)j9>re_*pffsf z?hYkBC#WI)O^MGBs!;I!B1(MjM&wOhs!-x{H0qEHr6kV@!uM9Uy5~~-f6mdMHjIs{ zEczYrcl7%TN^#gzot4g5qQw19Vktu$%;VYQintoJ0VQxMiK#qADGuD0lg@BT=y$-0 zWfJ_I`{zv<2LZ8~yy<2fgc&CKEk`LhQ7sycx6e@L&e86Cw$0E*)!TC+r zpA&J)vaAIShyCl1V~JM|w{_PQ)vMCq37F!Fq7;YNLVfBF`T&T1P{t* z9k#{gDDFqb*3evM|N5=Z$b4g4aMLxKQUI9zRZ|MUH)X7rSjyOIz4|iG6>x%YpiD|s zPkjC^Y)Uuv@Pkde{L}n|&T=bxB|m|Tt>GoRBgeMEA7SGgf6e$F8=yH1{l3m{UJg@T zs!~dFe5blB@*_iK{R4c=j}EqFF4q=P=2D-v_C)*3zA5{x#8Spyd%3pwBbiR0r%sp; z;C#S8nh#8%`NGojSxZuy0*(O92PpZP56H0qW!ah=UF=`5f&Kgzn|_LU5M4tt#>~lS z?7)18&(ldNo=X{fttrLuTn=ZWah(#+2P77p(1rEE_Y(g`=DP4(VZ%SQ?r=}$n@)zrn)E0hsh@EDDiw)Vku*M&> zQPE;UO8AlaA$y8ql-M8qU~B)&wIkLNl(-!w{xj`}v4j%GF^LneS&ToxcdVYkiDeS} zlYG#AaGm}97Mp%u;HEBkZovKV>+Jm#&WofqM3U!4;*3v9SbM78_4-wzgt10dqw$GS zp?3+bIYoimoYUo@_uk^-0oRVV}6ow-Y(5g63*eJdle3) zc{D#!bY}01lrn&u;`3Tc`GDbPlyELEe8$ch{_q@Llx4L_hK_7!^etg$HDz4;l9VuC zg8lr+TrYn6SLw+%IWuO`x`)VzDFp^n`%H_fRDx2Xb7uX>T(0j}`$J~k4>6ijpv>(< zHYOJj?9p3O3dG&E!=3(8MNKKNy?tf9xAYd5Qe>-7`shvFkCdPU{q_A7J655@^W<5j zwz!lcXOc`!x|UKPSBJ{FHE~i3^KK`ZhIB2ZxcqeO z1mdI=H-b22S;@sz2Kqys*IvHyxw@x{#Ze!o6t{!Ud2T@WqbbGBCZ8EgXJ}HI*MPn+ zv3=J9O8gwZnC`Ha62}2~mbVyB6XHN^Gj^~(D9h-Fe}6l!*>4i(d*hKVa%ef;1%t8a zvbe{u>u&Mn)Pzi<6R^GZmr5;`^xj#4d1g%fEO@v?8OGB$b#ihwEW&tI`*>&epsb8D zzV$wyyECT$75&Zk*XVmia*XLZMb|SXK1IAClt<+#Tkgl>p1r2!%6iGVNd2YGEvvOC zYjypg@g*$kqJ_K`b=QKEVo!ptv?$jVwsnPWu4oIk8FX0VPQ2CXl6I1F>$TKD)=}0= z)yeE-YVFO^RmW$Q-rSHvXCK1A zWB4un82R`ge*@!t$N}RzTn`LB>&GZ(L;k;~Tv;z!7pcG0nRK^xjF4E=B_!nGpSJF< z;H3NQ3ASPz!6x)Q+XxtbEp*eOEp&}E>z6_X>6SdB6Y#avLDo^$OV}`x{-i70f#NNE z(+@`dl!(ul#m`TD1~D1DYKn=~jJ-atJRe3ZRnXmwGs^Q}&PP4GIK#e-_JF+S!;C#2 zX6*SeW7|HE_xcp)15?=vGE{cLwP<6=gHx6zb)d2nbdx$$*$H(?s*dtn$uD&%emBQt zMSAG7RWD(|iFUMQ!9N*8cfpT7&vn87qAVMq+1{dD8=n)#G}wWzMW3=f5yEchQ=AW7 zgx%1mI3K!59i(njXIU3nN69ZaC6ByzRh5~D&kD&8K09n{g5UocY|Biufa=_>pxE>gMo_}*ciVbqC=IbSvGV)sZ zx8;;&NgYr&Wbi%82F7)=E=koj<^vV`5x*H};JCUq8eLtkSV_`9$P z`mb&GL_G3ZYc~9T z<&{gVttGbiN%78FyyF@&^p0!1=aw#lLn}Bsp(!~>WDzk1KRCe}8$GQe-On&2+cI%Unv4h3PlbrBXy71xnLzrpHW;LJI698=R&0 zjZzBGE9Z6ERUME5tu9`4*U>eU0!8Wlg7**?rN9Tf%eyF#67N%bGcvoT6ll7msXqVo z5tmZrLs`1($41U_DMg<6Vz8dnsenrPd{M(?v<{Od)B(!A=_R~qME=1`jVG4+)_@052a&Fe{hMV3YVLs5!DANitbMMWv@ zt5uct+zX8rrMNoe=SK!~Rg~ghi#X{XL9<@#O@BW_ZPLri;|;wGiIVwo#A+bC{QiaSIxuq(w)N^w6? zY`mDK4pQ7B6f=jK6n7KZ=_~qr8wl_J4$ho#Wj@XfdgEWSO>BXY~*|2ov|JMO}yVD zoFBHywe$g6YtZk9+2;D6fUjlU|4n7RaI|dDo;NXA;Gd7~ael6A&Zp?Vr>c4)vOLA9 zh=^(v`>N-Une!|VgK&1Tu}7?`mnF0kxF5+s>B-ZXBSCTg$Q3c(Gmm%7gNM#NQR3Va zCC)u@#JMMqIQJxI&tZ`~bRJ4VKAq3vi1S$-aXyP9&Sz2Ld=@3nXGzda^83NZ7pGSd zpSR?C-TD3#PAl)M8SnlD=Qqw@M{S*K>Mrvi@3P++cY`_0#(NLLM%bq}y`N!d9&;wn z1N|%N3p34}G~LIW-AvvYI+91?qx61>Xzwf@$(dYCXN3gC`9W924{a_ROzE9VGG;~D zU=}_b56+$usl^$QTAUH7#Tk)WoDr$T z8Ik(Z8IiHN{G^K+?RjTgdcQIw?~ikD!Mpgy`IxRaA5)9-F|{}!Q;YL4>1?Bf^D(tJ zA5)9-F%cu}S(8`9-g$iU#Cd#|#nb3~xJJ3hMAlrFL1l{lABiE{~+J(uvdmmgd9ca#g8*>e40^1q;W9-sDu z$^U{4=)6Mspv2^VYTogFQSh(MfzE1ozqC=O$RE)bnGal?N;+{|XiDb~)+c|I^5m~- z56Q!SrF=iiU)3*d{95wIW5oZ=@qY2Qkw20TS)Iu*VwF9kusO+}B>8-uzIVov{9%$G z_#1ieTAa6Nc`l1R8?x^H@HKsB6#Xv5-e(Gzi}oRV{7p77rC(|f)&=8$_p$ASKf~A< zC00Kn&Jzp?eDUZW_a|?CH(*ayE!KBhtnU(?Iau%4jdp#fXIxs}CF^`iS}WmPF>bd% zbFQW2k>_1rjq^8USxI49-)XVFbCX!#=_J;7u2|nCoUcmjJ0;e4O04f3AL~0M)^`b< zw7yFg##xYJeRoAXgU+3_>$`0$%7)T=>pOW)CHkisLrq_`nAUf?khi{TO6OX--uiCJ zr+eIAF0JqEIh9JBQ~9sOWTEi-?mx1=EA?*8<=#9F>mkgmF)!l%Mc(?3_Z@lbJKm4v zt?ziBlDEF&{Y&2Z4$sY%x4y%3bLFk?cpsFvzQc2K<*n~{et7KLaZgV9b@TUm^E zP^BTtw#{C6v zeWxVG{RMA*r)a&Vz4e-dw(!<>e1E}P-&OP@PwPAFt?yh~-)V1sr*V(Ku1Ue~t?w%P zk(bx{!JZ8{j`_oX*ZLw{F4~9uA-uk$K4EOZ_V`C*`Fu@2ccXSp^lZ*PLy^z#L0ZRM@mb#E8~c<;e1sQle!D8(Ma5V?kCQx46X$c@+BT`@eQD_Z z@R`p{<>z-92*0q&VEH@_b3a>_#PYeGeBLLY177Xtck+3keC{Tn$I0h(zx6{p(}dq; zBA@q3PGIl(9oBUJdQ7f04K|{=BaM+^{9m!d)0dv*X^F+NJl-QM)_V3?9`BJBYd!lc zkM~H6wVr*J$9ts3TF*Yq!I zexK{n_>!>B70>UmzO&Eou)ed;@36kJ&+o9lv(N9azO&Eou)ed;@36kJ&+o9lv(N9a zu2I9XMNC6~uX*WN9@d!l8R9k7LAJXeoZRPJZK;i`pPL*-KBy95_}{^PQRH6={#UD8 z+NjsacVM3$)gz{vd0VVXS+vx&o$uv-k^PnA$$t~%$$weiuH$g6#p{SOvRm5tDde-g zsI2t|`^8TnUxxpYKJny(8vbW-Qu2PDT}m0xhT(PJ-?pCmyVh~ZE|>N`o0vuahcP-% z*bY2~h3ydT7hxX=`#{(S!afl8fv^vReIV=uVITObeSp^+-h4ZZVFB~8cE(>}9JWc= z2f{vZHGSZEzxS2AI9aXk-UT+U`oYQfz2vr4^7Oa5CtokW<@l9LZax3M^09hTx+w3w zxT}GaTi>gp!=K?yzW)9D%%wiS*Xb+axQ){j`imb7|9s&@i1%9f!Nf_jW`BzxoP7T` z^)&VMgOl49emJGf|BF8v^W^0AGpU;&{QuHlgV}tpw8!oL#h(oOK#MEsAZ4z$KL51# z3hQJ2^pD3K_Kjrt+ts$`KTV&jUEk}yKmOC&>z}62Kh1ysS^6}%usdPC!Ue-`oZ4sB3WMIsDs7al24lRej3k-chmPA#4>q$pLOeOzK?Otr}^~eER7hy_gQuA zetQe!u18zwr%PpId|Q3yoU$ybgVasx zEbD^ulJ=F~&mDhb6Gzy@5jJszO_Z>S5;jr7CQ8^u37aTulfSE6DnBIr=Ze^CyAZ7U z!H^jJTDNiBrgwB4uE#vygWGz^%YAgI;#(P)Tyw9^yCeNt~*pJ!T9Y!K>yI7 zF5@&mM(E9v9T?YnbB+6B;r@*OuCipgNnzCAe17jk;ry^o!afl8fv^vReIV=uVITO5 zeLx#N{G04`;J^0T1E*WKkMtP9_49-2_wz-q{Upx%Kv`#CW1RaG5%Jmamz=!!3}oE3 z^p8&U_MI3H%v(gwI#-YJ-l4avjc=A~KX4ova=FU~r4NBw(tGw)LgDXln;qvR2>U?T2f{uO_JQll2l&3EX|wQs;qvR2>U?T2f{uO_JObugnc0F1J}w2XdkjTzw#0;F))YQy7nl(e?M*C z47Y3U2N~zzb-?|6X%EKtP0FAd z=e)Q1m1zT1odU}k?_0^g=i_VTS)VxToc`u~va2FF#&n%S*E7bM>BQ^FT)VP%?szZ3 z{-~4H0d=yvk}wK-+wuBp$8dXHU+pFPn#AFDyuR8I>kX{C%>RCHtfn=2 zl##!Lr4M-PEavpqUzYzbStnl0vXW;TYsEkMz3e4hUG23kbhd4D^~++PQMTq->s}sT zx_1Ftd(XuCy*Xcdwb$dAsc{_q7r*-TPAZ-WS~ybL>4a zx>x4ddu4R*%dz*+Oq>0_tmN`YeOhQqUl~7iyp9_9 zOn_~&J>&0noGlZgIsdV||nyWNz1w;R3l zP1$$8(YxT3eHR?PBTm_O#L>Islzn#`y<-jU!Q*$zUCXj$xyi-Jjdk8TK-kZd!V3;P zpgPujmt_`D9iYC5H1}6$W`9V17d3_RlPgoY=1`UPee({+1=B~Xk`wpy`}(T99HXXY zXu>u>`{)Su?W4`OPes(}uV!Rh!}#-J9o519rmroXRbQoSSeX05kXy^ByaR)bcTGvJ zcAhuS9i(p8vfO@y?$mGnP(UGWNL;;KX?>`*!}&M8b)!yo!@Z0jTfWI%SGF(XTT-@h z8wE!&F8fm9(Db)r7?=7qt#fGQD8^$>JnJ-y7{d5Y_morTmoALwh4QI8%9{6KK0mOg zI#sVM=hu#HtscKM9pjtw_E9Uo*v@VD%?rcT+_YU8*IW{#s_bmcZ80wMXjP;APuvzI z_YG0K$34aNKT*G%`eEI1#;<*Pmzpywk47DD-u>>=se3X$(|L;fmMRB`39oYukd_$hB=mZ5Og_M{OFkZAxwJ z*tRAgaI6oIZz$^<$M&0X)M+WbAUq+XgkOFyUHz5Wt1*6Cnt|&tyFR{G#;8!uaL6;3R5f=wkkJkHl)Nz3K)$Fe; zR$Ie3N0autahH@FdskpB@<~w>hf_uAic{+_{`AfWU1);2Z+5l$X`Q0%no(j}*En`v zL+c&Ku6Jl1w=e5RZP$0S?$dVNN9#dt*Mqc9)OMXn>ql+ZkF>7Tc3ny9O>Nhkv=-BL9ZKtn zg!f2GTshZj_wZoze(A@%taLAIH(0j2#6P@u-dS{~Spyc_Ki^qf!K@7@?<(ZvI&9XA zOU{qqnD2YDmb~$%TJ8-Gm^J3ZYgW6U6IyX1u-aNWHjx8OFWIR=1p-Py_O7eu~x|mfgm_*R|gO z{qcKdz3|1d4*K0R5$td8HmRc>);+Ku-UH@%NX}hMSj9wCzL68681WwOi?a4mi^d*nkW$DR^Kv%b&2<$;;z>$O=6Z_Bw&v++T%urc5AUn%~l1GRBGQAniln zYDjqXW$e|Lu~%QlkQMEius6-CFU$O<9TWD`dG)nCiTp&gqZ0Zg@;6h4@k3c((T<7i zLpd2jly;W(m+d0k%i8qy@kfh^eE27G!j^(3k)KHa5&9(ZH=)0VzVJ=+e;9}D z5cYw;-UryGh@aPFTtjITH@HuuOc_5BbG`Z@ZZJkH6!8#woDW$Uw}t+egGB#bxZQC~AD!cjIqRkThb{EMYUUiE4dcq`+C8iBwf%odp%+bT z&$v#Z*WI=Ido!*Z8t+X5@X7nPv0>n*?78!F>%Bb7h~d%r#di3okV_=kdG2PQG&my zD7UE4r>M}gsL-Fv!H4aJ{CKZkkY|iCp)2xHChFkTt0?LQj51MYV3Y}40HaLU2pDCW zwu#jncb3c`@?i%nA1`>~1wZV`GRPD9!2VXx`9gn^O{f>+tLYC9rz;i$|NnaRb|P~> z7J|QJ{BDzT)05jn@V8Z&)2kM5M7Z#`(oa`b+i%U|!rxAnyH{--8^_nKo!i-|zB}N; z_a3~Xr`nq)jSHSa1=l%uPA=`j4|`S{tWE^Wx$wi>pAJ{g&8Y2yKg)vD>hyw9%>Qn+ zThzr5XEOgA!6vG4`ZLTwC3O=gUyHfSKXpzAmE+7E%%5)Ai%y=ii_MU3!^d-#y zOuv5WV6~~tzozwhr*_Zv%wOyA!fMgPL(D(-S4UM_l*dKga~7)NtlfW-`M0aPRK3rm znLlUlna;Tj=b693=PlK#4Zkq|h)_HA?7lV3U*z}!=i|0tG5>}eGpf^DGHBRm-`Nt1 zc$uHdae6+JOT#|5FTPC?FY{A5&Y?{OHSF_w`Jg(KJD_2oLY-WWwJY;eJ3C|-<|jKjWEbWqJ2}*@8tqH%>`=QhKee+%?aKVr&JOt; z^OFw-sa=_$+SwuhV}A0-Ahj#=Q#(7}PaX10<|jXOD26gW zdK392^OK)C6i=BS`Q(?(Pk!oO#?zvGQx z(BJXKFW8^?(a#VUyzvY6cf9cn`a9nE1^pdw{NlLgjbE@o^P`_3u7Mx@3~?Fyqn{zJ zfgk-0aT)yRXNYUyM?XVc13&s1;xhQr&k&cPKl&NsGWgNYFs^vx7yO6$(a$ihfFJz~ zaT)yRXNb$-M?b^30)F%}j4R+rKf|~Je)Kbpi{M8;!?@y&U*Kha^fQbr;732hxB`Ck zGmMMiM?b^32!8Z4jEmq$Kf|~Ve)Kbpi{M8;!?+Ip(a$h0g5T@E%#VJCaUJ~VXBgMP zkA8-69sKBLn3sSb{S4ze_|eZWF9ARL8OC++qn}}1hyLhin3sSb{S5OG@S~q$UIKpf zGt8O5kA8-E3HZ^^FnsTD)6J9VO|A(^fRmhz(07t zT7Y>K_|ea>9svLT?9VU2ybAp2XP8%kAN>sL1n@_sKe7Pp1n_r_&%O}r1n}SfPPv6b z{~*>3;O~+>xKQXH#QFjJ^CIdk#QFjJ(|R{rDD=npYxT$YYxT$c!P-A4^vC?c+TRiS zWBj%HWBy?6kNJbOKjshC{*Le;%pX{P^fTc7nBSZKFhBa4@P9}6 zk0bma^B?O!nEx<8`kC;5%-@*bo4+wX`kCmzj_`lXKiNJgNBBSHZ_JN=Ci*YtpSJ&E z{>l94XCnS!{>k=1IU@dG{>l2I9MOLFn_l32lIa$KQVu{@dxvN)*tOG z;t%G}HvTBg3*nz=XAwU!|F`i|iTIECzm10etUvrz#D67X zz7laB>lEgJKVpodHK6x@7_&L}pRi4gEy8yAlXl>~<=rp5mRLh?uiR^h%`=eI`&Jjl zy(Q>yZE(W9R@m6q_gY|-!OyDbziWt1zg)eq67Icmxz`4xw)|TZdrwl~KB#xEPlxGgRW9B>ko(;hv-t_ayl~u6Iw8>*n2)M83Tz33+=@5vB>3$;NtA2v zNkX6bLQi{768hVFlEl*-`BA7N@}Uzj?t?;CVDO+0z~D#SfKe{$3=Dl>3t*H98v#Rq z?;f(Ed#zJMKJLw0d3z6;?IZYckC$bTC-f;Q^hCQ@{YmyxdjVx`8?A<`+PtpJn4_Qi zuU3;n1f34XU(Da91 zPRr86Ie+eyQ^5{*n%}5^i|UMg{_gV6L0FEjNEJ1T0Q2;*X3&UBB?zn^i+ zVjsC(#x`f{R?4g!zF33tTZL}XH$Gp8asFZr@IPZJSBZQjwS*CBlvQ+*xMlQGp7`ZK2b zqF#)tzWARp>@4zOA1ki~j~4u}Gt0ovLLb%_I-(s#9TPnV$G6wYuUel<6GT}NcPY2> z>PLd`;a~1q?=F07a}Ykfrov77V4Dj;`0&=P<#c3|^bUOZv#;vu|9w1`ubuc+`scxJ!9+&%xa_p}~ zygR6et1Zk~t6B;7!Iz(7&WY7q>krG;WX>Jm&vPdg(|8~74)j*RN1_m5g> zI0xp_MXP<>z5ce&)XRl?9el7 zMSVi;V$NJ+L++-w`4sAY_U+nw_KX`8>i$ycZ{2O93p3~U`wxb`&6ZukwgbE0r1MA5 zV$Nq%ws314E6$wDcI4A!7nUbGh4xoI#{7A{d(Q2%url-a7*SG_jrdx!nLDX*b}sAd zsyp2;Qr^nfel~4Uh-}B#k}ciOjuqo_yFT@~TXfQkeC_H+0e8c|e0(k0)vfFVS%)lX zQs{a&{lwR1*fG#0oAR|}W0(AZ`N=OrkAK{l^;y&Mfmp)%`B{ zkg;Lei7xpx>q9;sA|K*w$){ZMZ!VYoJw*P^Ws$#!$cLDRe99$XXMXbi5cxWDlJC0| z>zNaMlzg2z$@g7~`^<@aiu=q7Ouo*X;8^bsdGa4-A+pgb!b;h&D^ zBWg~}O>D!T^f5>D1(n0i%Qh^zKZSxGh$ql1G~`yc;hbvO6v{*VMENKKeF0^D^|8Y? zTwSuT0xx0+$^jSR2DnB1bijpJ1a1*O9T7hra3L;%Tf|SAqa?&kCE`5IR}x~T5^>%U zabAh|sYIMtBF-x@?l>aOD=`K+VhmCu&MPqt83HF_31WvgZo;0-iFk?F z;fxH0qR%1LgA;uV zF%F!Fd5G`KN%5Y>P3EC-(?Lv!&gerlZZZ#zoA3eVM_-|FlR0VJq&e#a=0u;Mag#Y| z+*CAfy3mcrO^3!!=A>~`(YVQ+G;TUHZffXEqFzFqS(khG;Sg;F%SA5=2d7@^goJ?%tPa*gEY_;flV1d7br7%&E9s z%&A1bz`Tz2M86ll;fj8Nc^zMi7(n9_*M-KbknkDIEtv;%OW~g`jaytt8pklVWFE{d zX$)iCXiUSrj_ZY(A^M1>@r*fXd~-!#&@{F&4~=yidcc>U7maOfLmKNe%7ZVVe3SuS zLYXwSaalChY4F0AP!71@Kj0Se(*+m&2izilV%@=8+2L6Ma|2Pppq@oX7ge#(6EqBUi+EEyg3P-RyXzMV!Yv&W=Y|$1x}Rs2GE= zMzdp$?sMOMXXgz))rh5E#l800JB$y;pAF{kwt;b<``S3`&+lct|6*)#(6+Z3|5D&$ zP@mhv__=L0obqqH!g%l-gPq%F&t{yv>+n!rPu>{OyLPWWFop zUBTlDepi(13VlLC&ycOxxHReJi@La?jv=9gD|H*u;O!vvEM0Vu^VaJ8^MS$F@`miJ z^UfA;Iv+Kf$ub}3+Utxztj~ujS4NTD7*qR($exU;eM4kt#?-#BKVxcNvv8J*j>WM{_I*04Wg@-b?o1bO&_m2t$i@E^{H|A=zoZ=4T*6M8yA|DdQ> zP}W!IK>4hLM!R@rX;GGj4|`>4QI>|!du3_#1+OfPKH`<7$+q!cU8tY6v31n&c~1w8 zz9!`bk8KO^+qOWtwk@EKZ42mW+XDLAwm`jXTR;bEf0PUVhYg`mB6-gbHTkXeLrwln ze$_7u^3d1wL(cd7kmXTN$e>&)@A;l4pNAj9hZz$W%ae}>yuQi0p*>7lZJ=8Mrxzc% zj$VA=x_j|~ZQ{iTwv`tj*oI_V=7FDkec!9Q(c!Jt&&3NF8|%1z1t)Ah%ys){AKd?Wqcf9+} zSk};rs{!C3v$GY`@soX~g%7;dX;<*@y3u<2;!+OqV}+u%s=bKuw7vuMxW4BZH~+e$&b+&zf=ruY^>y@D zLB^{#l+>q|v}Rms+>JWWvbV|qc8hzqu^0V_`nN{a!?*H%7-4n z&}$Xx2Mm3oH!$jf`T(PTs3$P$jrs$_9;!uO!+x+M@QnL9%(L+-PvP>sN2PoF zXjLwg*_SfsxxVVmM3?s-WQuL0`aPdkLwfm&n|Z|G#r56 zF;X0iRXx8bTh#9J>CiR``(!x3;il}^KQkXPIg4M!Z!;Occy=fD+c56&&{XWhVf<*W zT=qATDrB=z?PQreq zrPsfD9S~Btvu{td0-#Q54+iNVNa_M>}>Uf{q24vw2Q6RU)k>9gkQnG zDjXcaKKAVCa&E)+{TYuAE_EmTuRY_#>wa}VFMJ2%!5ab^3D+VI-vL7w*8qb9T)^ON zlqO{mzFO}dE8QQWZ*#!2@0$p{YC;DGJkQrJs0$XG#5_6n z*3;ud8vwfN8iyxkJOSF55d0w2o*DaK9H}jm!dxI|A z`UZu1Wqu_}AA2RU1Di~1lEUq>JBLEO<{Yk}=VqJAJola%<+j-HCi5K3yvE&;^+)De zHsWJi=+~NIxW}X`g z-Q#|GDlhXCYZL3XoL!rF%2c20&MhBgp14=bgl1gqz&yLZSnHnMx}JGjKJ#K|M!D1q z?KQo^xzIf$1I&}Pb`G~@r^d{)JEn$v)8<;tGbQ&e8@Juji+L7(($cNqxXkm#*Dq~+ z;QqACQ=`y#8*}w7&OH4G}Ubn}hOGiKwE;L3T$nCC#nnZc?p?qQyZ%Qgn1>v4B%@K9tC=6QK}HRrYrD_MSXtCUW?&Jip>{8)8oY43*2f8mY? zoHa8Fu>9`-WA8k`t17m>AA0Y-lS1e{q2}xXDFV`)^e(+a0t8Z|w}c`hg7l6cNH6E? zks?h%s-Pe$MX7>t2-hZA)v)I{ZX7*aYSu<^XhjGJ2ga z!{xkqYmMvn^`2bs^t2O$$)xXF>;~@4!l2PUF?5jXUQqb2&!-MaGCV z*}0t7;ZI$AayRAAW@vEVxUnxamsvR5KI818SzOMGhrO zXhc>?!{yNLkWe4~?6Y^y8^fQ};xhZCPbY5enaJhP@9mv@xt!y@Qi&fb?&WgmH?@QM z9kt5{yvu!xen(}k!sUz{o>x#ih zL%;7Sy-+!%Cu#@veQFo!g~}m4k)5a#3NC6_rYzc7etDw7zGY&)LI`DW!FgZdJEmipGahdn&L;-nbmno8pSgA+8ilTn@3MnBj7W8N~^g zL!79-!{t!lQ9N)t#DnTDTn_aY)knA->LaROa5>a36#tT*i}+WcH%UL#7ZvA{o{KnF zpXYL@|EbS&In?LW=OsNC^)vN(E{FP)dLAx^`jGlOmqYzVJr9>d{YE_xmqUF;Jr9>d zeL_7CmqYzP>6gnP-qrJPImEl-o6E8Nwj@0h;YW6ZUemt7JOpPB?5) zjb~HiS!z5>t$&#s&r<7Orq;hqt$#_ae@U&sn_B;pT7NgS{w}rtF17wHHUDF3{atGQ z$JG3f)clWB{5k$dYCcD*_(mrADR-I*_PK>;KlsFt_O{dcPCGWb{Api5?V&%kYO23- zd3@eou-NQRXTs6>PQ?bC^|#NWllubi``hmVm}MFy4Y1z@Fegt-O=lvqFI90BzmGxw z(~;@D0OuZhFTnY%x+Shmy)HUq%4vh%HoeVsR+aNC|HCsbqdM*Tms6c~Im@X|yZq%; zr(N%I`&=t(&vLrgZs!Ur!*2fys*}!Uq}Y+_Bt5F<;_IYG^;~?vszW&CsPcu)OD-tT(^a8qr0Ul7u9S>OggqBCLP0HgY>*~4U?kCQia`f``dWlzur9Wb_>ZrW>b0s>HHA{=M^nJ{_ z9d-NacGr2(Innvixzc&-)vIct!=$=S_HsB(6d%(0)!I*=^iOYb{pxptkHGXhF?R)rOA2xyLn>xJ*)xC2K&={SnnThDi)1c;(y#fyLga1 zSX9Vyz@L88zZ)03;!l64`?{Wg>QC=i(dVaEPZ2=nQMvODr3s*VsJ{CH(*{ue)Q+!8 zr3#>SQTx8n?Gr%lrFOq_?3O=02R+Y;11J3H`RF-oUtjM}?|9Mkzx12vPx>Ie>@HQ= zpY%lf`t;Z?KhhuB&avasBl}m z9#m94mvfz-*SVkc;FLr9ampvXIrWl0DF@EyEK_^zc9Q;=+U+O1EbZRyEA9tVf2f-p zwu9}^@6hkyGkI)Ekk6zsNcq_n&KT4o|BK}`ZqOLCdB**?IOzPAuX*lDV^BoC195TC zo|qMJagZu2E)J?)pzLxggUUL4@?#nYWYe&DE1HJoo*!T zQ;a}ksTy}yP>euhtQwCFP>jH5)T{PTjKF8qt9DXcLu0j2?f0iTRT(r+1&nNWdX;va z$2$9dKBL|)hsQd*d>-rUdZ`SjJv`Rg?G#%3#lg9aiXNPMJRQ}kJulsF+IpaJr20GQ zhssya#(JZA)w8iad91VbEHwSoSS@Y4@LWZewPIA#nMG82s?7K@>=?(%-`$QPZI?Q} zG)E$C5+F-;&r-54**yU=F&9APCpQ0YO}ZKQ)}%hKl>fbFvJ(IQ1<&Y1^ILjO`hg5R z{GAyHAm3z}$Op2e2YNqHz49abwp6yjGq- zStKB*8g~!)`OoG@x3AhWKsgzq_6$s>^%}~LYkNF+?}YNVyw0TNxbgN{(0Yx%7b4!? z3|gep#~ht`u4YwySZP#5jTaQ2zdehlYXc)yDMjJ%J9 z)~e{=+CCGNFNxb{Li;hCeI~RY!?%04aNa*N^@oG0^?LQ|w$Ax}S|cOfQ8~8GxqQ7| zy*&wB-xuAx<)t;vWktRmBiffMY|PEGdD)PW!$f%HMaFxPA1+Ihr-v9aoUQrT3;gmqnM zFG?I&>e=JkpkF6D+q@;x-kaa^u6A9#PlnjE_3Z5PAw9?2Z=>|gYm?eOAKss%KF4dB z+CCrN&!a!1vYnRa{QcSKS;^jswf{$NgIyQ(BWJG>?@gjLSJgh=vt&Ob?`5KXO#jyQ z8mU+|Zm$vf0cWof`G>!Seg8j};Jg0geAn;&=)a`@I_pKMi^i=TK~@^DexMWR;cvl! zvj;($BW^zeWD8E{0ebkGFyQ0!*}h@oPTvpsedGknQr)liOsb!b-Q|`>w^{ypSwp$; zR309mzX~oVOK+{pa?bBE%Iy8rcZ;f@AN{ z%Z+|4C?9R&?{D(CP(a9>ElTk9_up$P!!D;}Im@g8a`FM|o&AwR!exdEE!n=!zKD|f zGiP;Cz3t~l$Objjn5XwKWZk2x!%0ICF zm46V*Kd`L)gHZl~W#u0Xt+{A$L4^sID zlVs%|r1B3e|F=D_ZtH}|x_)$7|E%&4Quzl-x>f!`D*wQ;@()t^2bPt8FqMB`S@{Q3 z`3IJje{d`Rz_RiWhVlAq5OkE@_*8^(DNX+wzL2}Ko8!v4__d2N)gtIyH; z9bZ?^&g&6$UAKiUCw9H`jCI`~#Xax8mZ`P>m|wG>g>>OOBg^Wa^z1C#I$_z?70dSD zS+;e{a}E31S=Mc#%ZXnvJ<&ftFJ1lP>-;ytxA6b|6?3>Bx&i}W01SWuFaQR?02lxR zU;qq&0WbgtzyKHk17H9QfPsI?0O!yx9sSvyHSUMrzyKHk17H9QfB`T72EYIq00UqE z41fVJ00zJS7ytucAX>KB@Uht>m$i>wmy1=7kfj#q5pH&CVjpw!t%=G0kUFjZI-{Q?;{IMvED&Q?D9+Q zU2d+5vEHfG`+S&3Asmo7a^bbMGPhW-gWxE zyiMx86d#|&eve@5mP`D7dG>ShnO!6&*1II#_g5%N<*Vo7^Rh^`-#uaW>~~TmUH`wm z*Te72a5?sS87#w&f6Y5VugZ?Fmv`Aq?`ygYJ9?KLVK48pm)_TO8Fut8JHlSxWiP$2 z=`!r-U3P@MyvtsCU(;pS(Yx#jdwG|=^uDIcu%ma`@x+pe#<`baoD)b$2JZznXxjJn(dE(9coEw}}beJp`xP;}z&L``+ab5QI z=hF42%ZdG5iCw<_ED4bZ21be*`+ni`@KSUL6@{|TX09^7^Okrg<_gQ77)`{bdO4ZT z)JZFf;G~sVe!eb?NIAYa%ZJ-uFlMFb&GOy~lZ@|gT79a=fy1uW2dr~pJ3gQ3nbY3t z3)348GaG+soeTTm-OtRH*Q|44A74x-EA(s48@#zskC3{o{|% zDf-8?T-7$|@T|+auGF)b&an3JJ<{p9}S$$wyrv`ml$&SE0zm2XeQ?M&&IZE_cTaM%N)$|p=Q~H zPse5~`!D~>2pQ9h<>6%~8>J3e{rA?TgRZ7Wt^WJNck?_&>RbIcO{Q@3j(Ic_}%VYXHFmhF~&Q<-o;A&&)vmtyvvCFUh*>>Yu;X#6W_sdSn#HTyk zvz)nmQE~cX>ul-F9qNj!XMOp4uJ)b9(6Y}Ay1(7xA)-&owJiUrCzq>-&omMfbBUYIPbV#?9)*@)yIS#K9gD_)PA^E?<9^gve@a5zcvu zmA;M=+lHiIU;3SD^X$$OSpK7O67pHPhjeEB{A+pDr9Prl-IJ`hx!J?SF99(uryCm~ z0w-r=S+7@@6Y|+(G3mw8N3ED`UDiKaGGv5EeRe$8wQ6RhC_eQ9+phBZC=r{X3G3vi zN#Ww*q~<0+SM5RKoow4#z8cs`d^PA-mOonXx=7lfFxNG_Y$=gPV{S=Yd!_2uy= z1=t4F%9WIt-ZWTFb3Bzyo~$j)lQ(^0?kqikWk$>tyl_Z}xKp<@%dbVhDQ1;T%W|5${l&*O zK4snhykwMEnz}p7AseDZ<)e*Q&l567is~Jnv!08eA1?Y$c$f8g^YtF$$<7~GKKNZj zu{a`+B>h)uQ&zk^p&HA&O?COdO%E$KKQhiV@4`CQWnB+9I+T&)2Uq8NS|!gU+qJOH zu>ZL21@pZWz4`jRE-~h_bYU!KJ@MSLFQavaeR#ptuHzRiHd_1EG%oZS&G*#XyTOnr zto>B4vMx2}r1N{Z4S9~2FmCo4!}5&YYmCl&hp?>cL6;Nq*@XHprwyun)6u_bgXy$E zwas+erq`>>3Hhwjt#JCaE-RY~&89-LsiE1_&}{0`Z0gZ$YHBt$9h>TH)8)jjSM_D- z_-)nSrPJS)ACQh8Q2s$W{z3T->G%!hPo(2dl%J7~pHcotI{rubCF%Gj<*%gUuaqB? zjvrJ0O*;Nf`90I|d&(c0jz3g>(scZ!@}Dlpe=5IfIDS?6Tf_0U$`1?24=evH9RIA_ zRG0tT^q|H{>C6XoS&h+B8>6K*MoVpsmf9FCwJ}<1W3<%9Xz7g6x}J48vFla-Lw$d4 z3*Pgo<~-7w^QgIybml_39&|Y&pQU>&Uq=7`*Rq~Ry0kA+mJd0?`Yh}9 z>T*IptKX9l`Oo@c`z&|%|7yQ(qVH=}wp06q>4(otXZcmP!K&YCLqcSy&Ht{wxVo+q zyA75;{x$c+G2N@iWo1K4eii$@6)Wm{h3SXSu4nmGx8Yx(As_$Dd8f^Zy+_^F3-{&t z^6$F(_qBm-_CK@@*DYH?56}Y`00UqE41fVJ00zJS7ytuc01SWuFaQR?02lxRU;qq& z0WbgtzyKHk17H9QfB`T72EYIq00UqE41fVJ00zJS7ytuc01SWuFaQR?02lxRU;qq& z0WbgtzyKHk17H9QfB`V@momU-gIGFE_*o*jAG!hqU;qq&0WbgtzyKHk17H9QfB`T7 z2EYIq00UqE41fVJ00zJS7ytuc01SWuFaQR?02lxRU;qq&0WbgtzyKHk17H9QfB`T7 z2EYIq00UqE41fVJ00zJS7ytuc01SWuFaQR?z+c4xX);<^`h*NUfB`T72EYIq00UqE z41fVJ00zJS7ytuc01SWuFaQR?02lxRU;qq&0WbgtzyKHk17H9QfB`T72EYIq00UqE z41fVJ00zJS7ytuc01SWuFaQR?02lxRU;qq&0WbgtzyKHk17H9QfB`T72EYIq00UqE z41fVJ00zJS7ytuc01SWuFaQR?02lxRU;qq&0WbgtzyKHk17H9QfB`T72EYIq00UqE z41fVJ00zJS7ytuc01SWuFaQR?02lxRU;qq&0WbgtzyKHk17H9QfB`T72EYIq00UqE z41fVJ00zJS7ytuc01SWuFaQR?02lxRU;qq&0WbgtzyKHk17H9QfB`T72EYIq00UqE z41fVJ00zJS7ytuc01SWuFaQR?02lxRU;qq&0WbgtzyKHk17H9QfB`V@4-806Cy-eg z(a;0*00zJS7ytuc01SWuFaQR?02lxRU;qq&0WbgtzyKHk17H9QfB`T72EYIq00UqE z41fVJ00zJS7ytuc01SWuFaQR?02lxRU;qq&0WbgtzyKHk17H9QfB`T72EYIq00UqE z41fVJ00zJS7ytuc01SWuFaQR?02lxRU;qq&0WbgtzyKHk17H9QfB`T72EYIq00UqE z41fVJ00zJS7ytuc01SWuFaQR?02lxRU;qq&0WbgtzyKHk17H9QfB`T72EYIq00UqE z41fVJ00zJS7ytuc01SWuFaQR?02lxRU;qq&0WbgtzyKHk17H9QfB`T72EYIq00UqE z41fVJ00zJS7ytuc01SWuFaQR?02lxRU;qq&0WbgtzyKHk17H9QfB`T72EYIq00UqE z41fVJ@L$eAvQtYR zs+}vTPF0pv?O#cCsyb9T-Bxbhaw$-|Zff_NS~*fHUuyLd8%}$q)=sIlUv}SLVf9bn z7l@%cwdbY#9X(Jvj((_oM{iWGqfbfCZ0lK)E^Pgqq$ArdCh3msRiS(aWe?bn?Bk`j zV?I^;eKbC)-^KB)@fnYQjn8=fMdLGG|Ef?vW<~RXqoxus8lUm{sm5o#ey#CI{m$W& z`klik^*e`8>UYd%;Hp#9@0{z@@0|Oo-#O*P<6rL=T6^O4Bdz^%VMwE*_38&_P<6)Z zkD4Ch^b_U+*Vtc_YRw3D(;>}~9Nl8BqGBI= zu7dH-dt(IH&ULruX_x*v@-xhw%>M9mcy?pNodi z^j@C{+j+0;Fy3Lj!+3}BE{*|}i^hHxwUV@tm68 z-{FGotQf(G{k`d35;abBqjyO0{+;zcZ@l+XwLSLn-VMR~2zVbs%k|NFK+e0^34M1G zKGS=BCT!=uw!?U5+0J=K4C9@B=7t*6v!wTHy}$o2_OxTX!+58BFY=klXIj2j^DQ_l;D0_V06x=ueI{(@y|z>16yiI5 zzNh)>c=JPj-l)$f|BZY6U^~Qj%J(9^)BB^|PxU>zdcW5DJK{T>ucCb)v7vZyzK=NG z{$#~Z+`eUPKL)LvV~?NuZe&dliM7WM;~mC3jCZg83`V7MoQeM@%AliV?jJ0 zsOP@^jo(cVpXt3m6SnhS+rejAw(~}x3EO$E?cg)L*Jr|Z-fKJfOz-uXu$}kX4nEU+ zeI{(@y|#nT^j@C{+j+0;;4{6~XTo;gYdiQ%@Aa9mo%h-fKGS=BCT!=uwu8^~UY`lu zd9Ur@GriYm!gk(kJNQiR^_j4p_u39V(|dg;Z0EhUgU|F{p9$M}ukGM7z1L^LcHV0{ z_)PEhnXsMr+73R`dwnKs=e@Rr&-7lO3EO$E?cg)L*Jr|Z-fKJfOz-uXu$}kX4nEU+ zeI{(@y|#nT^j@C{+j+0;;4{6~XTo;gYdiQ%@Aa9mo%h-fKGS=BCT!=uwu8^~UY`lu zd9Ur@GriYm!gk(kJNQiR^_j4p_u39V(|dg;Z0EhUgU|F{p9$M}ukGM7z1L^LcHV0{ z_)PEhnXsMr+73R`dwnKs=e@Rr&-7lO3EO$E?cg)L*Jr|Z-fKJfOz-uXu$}kX4nEU+ zeI{(@y|#nT^j@C{+j+0;;4{6~XTo;gYdiQ%@Aa9motN6~=#eukeSD&&kNP=#vb@2vgXx=!U$xg=9PkrA7U zkYrysNVe~1*)B)Wb-R3)?Rr^Of1>uVY`2qTyZtP0-EwJ_s?WJ@sQR4y4OJh@svO~z zqskYmKE6)B>EF}_`|m8%=Tv>%PAX5;$1>H^eSd|bbiaMwB-y^7WxE_n*X{CIw(DhC z{fXMcGSx$Rq5G*G(ih1U%4dkP7i?!S0NeR68^jCx9r~T)yVP&;)q?zn`hm|>N`TLV z&$P!__)KdKgSm<|k7YjzpNV;esGtea!c1J>`berLzj>=Ur(!5Sm%m;!r^u;+pM1@?(ykDt9p!#u!eV*So$ zKv0qa>vz~&Yws&&9`&DcPq@81@b0kXapp_ZFIa}pL@wH9 zK-hC>_)PdreBY~L06r7n)obtlF#=))#0ZEHuwTVyfY)3QBOpdVjDQ#cF#=))#0ZEH5F;Q)K#YJG z0Wkv33c&d)IA6uyx6HW$#0ZEH5F;Q)K#YJG0Wkt%1jGo45fCFFMnH^!GZ^tcg7ux_ zwExP{Vm*(axA?Qh%WF(bfse>Yw-yHKhc+ z!-aRaus;*~GqFDt`!nsBlE+6o*2eb%%@{0b-azvQ~sI{JzOyXlKKN@j&NQy z=g@G@1I~F+c>`jBd9de=`0he{cOm;poUw1sA(2->UIlp-lU^KB`?{qe10fC_YmAlm+z%lGWLg zqWgY)ccK06v$OX=()p649lZC7J?&U~#o8-;rZrw5uY$Y^@+!!yAg_YF3i2w55s+6w zUIlp-x!x0Wu2d+A`it3|ssD5e($gD8RbCPMRj^+L zd;GA+5AOk4^CH9uh!GGYAVxrpfEWQW0`|1q>+E=E*?P~N*Hu;6h<7KI60DzS-m_}kiIcI;`#o_6eM$9@&;SHU_0Vg#%sU>yPL z2v|qJIs(=a)L1~@@4$I8#0ZEH5F;Q)K#YJG0Wkt%1jGo45fCFFMnH^!Gl%g$0^Uc! z`v?KfyE)ivr1lpfMnH^!7y&T?Vg$qph!GGYAVxrpfEWQWf_hj}J^Cgz!#XJY*h>vvec!}=Z8@34M{^*bxag7v%F948`1 zK#YJG0Wkt%1jGo45fCFFMnH^!7y&T?)?R(E_Nva8rFkK(FC#`kjDQ#cF#=))#0ZEH z5F;Q)K#YJG0WpFa3lJly_(-jzNtzo`tYpuTSXTeUdqAWV{(;Yg&xFr}&-8Kj9>8ZR zzlgjF@+$V6fpgCGT!LlwJ~j0fmhm1Ca?zM)4(7f9p9!A{pNU*Fa?!{|BNvUl3i2w5 z5s+6wUPX-s2JKa%bTeWE#0ZEH5F;Q)K#YJG0Wkt%1jGo45fCFFMu?_0MJGOD+13fm z>QBO6cci^c^qskUUHuj`pQg{^tZ$t4jkCV3exbSp_V|%g;Gbwgzf|tUq_LJ{d+yD$ z`X}j%WyI!)%@La;Hb-m@pNV;<508o1^E|uC5)dOGMnH^!7=a=L#0b2mjPFNKB&cyg(maW%u-8~wracH1 z%EM>EXToPv-+<4A&r}cyA^|=VXML-2LDIf7;=$gZ#l z@+!!yAg_YF3i2w*t01qU21M-fQ%XRLfEWQW0%8P;5D+6^zlwr@*A%c{1^ZR7Uj=6{ z;tWQd!H5_EF#=))#0VTBU>$+>?&3Wl1p{IP#0ZEH5F;Q)K#YJG0Wkt%1jGo45iAA} zBVZi?dyTNy2z!mN*GP?t*lT3viv+#jPICm?H?mCo4i<*s9WK1X^}lJ&UsSYYr-5dAa zXsQgUwO@AMU!f@7Lpd+)dFg(BcDi5vk^bXyG`&&1e4VaQ9dwWSk@jckxlGM2s=R2v zr$YG*N|%-l+tn7NG}56L*^b*x?WX=<{r+dNbBASf>tFv&PDq*Y?qROLl2@_>+bN$3 zA8w7C+PH)9S2;?Izi~cIXmcLSofI1w@8a0-rnytxc<0Q4X+EsallA$tKCjm2+xk3Q zp}=L@^ZdAZyFQ;kdZfilXWpgH|F!sq$`Eu9m7~u^^|49ogEY_Q`|Wu?%T}G%+$?Za zmepGPLUEaMKgDG%Q=MA*LaUel&iBy0T07&#Uz;+ucH)44^gHxBn;nO%c=0m&U0goI(GT@&meKE!=b`aO_p!R~)qS$g zjPApA->&sFfgD}j*zNQ+^Zw2 zozOg7pP$oMPS@!g{f%VxgV_j>g@0@>cNX+mW9Som0)cOV|L=Bt_>$X~M0BtNRf(f`MI z(CU>={ABl0;avU4>z04E@8kCTGdUz*@wh!U36cMdulT){-rLhXH4jGI^{aQ|7^PwdcSpF>CNTTTExGWYo~F?tyv^Q zK07L-YjEpGS^whKuD7Z@a{1RDA?IJ|YrJ-JypbtWSNUM;F{9wiAC0+d{bl(<`9g?(AZIBpOBv@28%X)6d28lL3gT>2V(tDcs4-x}ngGI>d>+T7ygT%E1!J=o9UG7n( zg2bromBg+eXSfGluPCN%%IwC3?pQ4^#MlHO%sjXZMw)q@18J< zt@z1^Jm4!sx)l(qXBH5PZfr7x+XRcqY{kWk=;r3f-&PS%=9U$AethJqv7@pm9aK>a zYWlvX=I6npz(+wMd#+BNA!mZb=nBCi_q8&fJ!4fHh6aoJebalUcL@?T<_C+^&#$@9 zHV6_eP6mq;AMJD}_YD#a3sn+r?#^(J{;HzbP`YMFibqkR@~P(Tgvb^>31uO%Sws0w zAA?=MBp3h#U;qq&0WbgtzyKHk17H9QfB`T72EYIq00Xa*ftbffLekxd67>qk>`sWh zzzmT?($y-O?m;Q}M{=2sQQ}tZqwWg>%6SqZ`){r)%lNy>7q{mYW%<$gn!*!Mm*x4n{e=5!Czem2e{NLH zJA~ym`PUoch4tQj()DFjoz{BOS8YEE)UKP_{iarqsg*CadZpGLskKvT?U&kfN$q*1 zrU$9%M{0Uw+tKrq9s7AKJ-2ySO5Si65On>`rS)a1s}EU+AD!wVm;bhx!`DA68!p@C>h7Y?R$LGzZ)`o~A$j8JNO}MLNR#9wk4DIb!TVX>zqY@e zzbXmqPf>*i)h9=>Tz|p{PuKF6d^&2GEA!=1eBFJtlW}*=AeP^Kxy4BFX&06wv;1P5 z9n*;A&o<;1$IDe>Iq-Z%5!Nan%MZr9AsSzK#_hjVtg|>&VK>VwM-CK6WIvW;3yl&> zU%L6(JKTsAb^5)=I`P{cC0?(S!XQ1oe>#GBPHpw01j*C~%I&VOTJ;I}M>3V|@b^bD z?G;delS^(S-H{Oa;LjOd*)K$ikdte+CPX&245?PJ%oicEZ$^oP$mxpbs$8S;2N`Ld zCL!{4t$ZKZx?0jqW=QKFqeT9w)*(}VZ5&ecmnbf0NR>M!oH9#{p5{w(^|nUH!S$6x zLLWyd9Yo9Yb;lQ_Iuj!A_#j*^E4e0Q+U+K0#Jq4>yrUANo^x^OWwSdNx&zwt>(ndVi@Gf%_i`rc;9 z<`MNwvf*nFGI~a3$+e^Kx$FMo1^nYhHwN>URQ%INf`wOZ2*QxsltNV97 z2^AqJi@T0An{GV38Y;3@DDJ9tWx8?fc&M1yrMPSN=on+)!cZ~uKyg>*gRw^Jx1pkX z)#9$NpH4Tr9Ss$pUd3I_-ia{^ZVeS>=N5PEC>3jjwVYwJeG==gzbjN;E^o;#%~1LM zYD><$Ayn4rFpcl2`9_!wDH6ro0}M;crYcNT1`%gvkT7s~R&Z8uH!80rIz+Wdli{BSsWl-SXDO;v{Fem+ZsIyFTLU zm#cYJ58ge4i^8opOq_po?f^|Up7MDsU-eTJ`gIZU0+pwUxOJ&r9Y4p z;(zpeRNvmAd`m1nb3)`U&-y#QOD04t9;JlHlC0{KQ}R&DW=~p?g?oU(A@YXceqRz;|{6Owyja1TDTm( z*BvtV=hnve?ZV}vU)&)JrnOXKPPFWC{#oF?qPZ&XZWkfXt=r)V47~2Dsmgq}ttVvf zlO~3t{8)v2;{yj7yF$X1uZvW^uGIY|M(NrSa$LXVp5P--)j0O&e5USC{FM(`rF=-J z@*#i3kDt0{wYq2c|L2!1cK>(W>Yp9(p5-52tOytPzt3V6QT^`mcV)$*O-E=ij(qdk zPpdw9I(7}ob-(DpwoUakt4MCqIMwQn<(~6Bo06tpy{pkQgZe`GGGXHM>s5{Es_%Dw z93UokvV7E!4Z=j^5X&!p+iH~fs<`E^hF=*WWaf%oZ?<1bi;n&LSl<1#jCe6?xcL5N z30L_3cg@Uxq2fmM60UdB&o-lCL&fV`i@So$&M-eyzPDt_;;#3aPB+J14inQJ6m@03 zI>B5tCrp%USIiama+2Bf^)Qipe=%35qEpQaQ$j_V-Nju#O=g&bs)UMKg-f`mhs`oi zULP)^CzNn?S@@2buZ87f$LtCf6S`UcZOEliv2T{;_hvr}72khi`N>JS!^9KYe|}UX zT;!i``N>l^M~b5vE&rK*<_NL*OUvJSnud#OJ1sw4a&)-R_5Vlu(REm2oz=F3>qEuv z)|UKmXQ=oieiCv$WWO4}Zm+67s@V)PA#(c@>BVm4y9&*zB>zZGx#9Jd50VE9`mfZ; z=N|ffw{`_lbkzuxZE5Tnd-E35zM+F9np2CPLh=_1O6TQJg_&%%EZ>^u~}iO zEIqtBeI{L*e6^-$m!^N>&9RH2*~`%ENH%lqOEz=tPBtSJnRD{7_H$8e5ho{hy%$#2 z4N(4BbXmN>4>I%s2L4(G)Vn2ddylnu%;TN&pt?K97JtVlpaSF6*8&<>iVT$MR_k>YlE(TbGMYtm0|_UUAy?o zsCpMz-cllqOj|S=wN(_I^3=TBB`3=RryMaa*DAvDnVs*L*SeNv`DFcyX3fDtET2Bt z%QL^eB^S>*)|KI28NQyUWHqDM;-^xDB6F z$tw1oU&8XVQhp-TXu@*Mp{2#C6&v_j7HqF5PHS@e9C!Kp_IE0XDZ7&M{f8fv7wO;4 z#&XFjDu*otS?*r6ocL~Ib(V9SD&|kk^Cd-&Y=c0E# zKHH+0FpJG*dFuy7#MkQ8y+fM@d z`lGYcjH?BUv0SY3L}Tm9;w&$mH^vBgT9V}tQgt&L6}8y-VqzWRbeeK}z0;;*#*@Y6 zS>81>ow4j!D?hN}#d%lisEU03N!T9O;GZoyw8uhM=Drqh&FA-b^*w0GW&7rIRZ{#C z!`%;$-SgH{>w1OuZ@Z^`XUT2fy5jD#&XS+~8sxd0(~?^)nC;nF#wtJ0q2r$OPptMF zYna^J8)~(4)fiv1Mzq!b6R|bSW@AfpT{n6*He2^7#j^i59n7<5Den_3&WsskHhyC1 zB>#7Bo6!%fzA&)hyJnt^{(Miw{P|`~M?Xu>vc$YUq%h0xE?aG0&s>1z+|Rd|>#OBq z`Ln&Bn9qH!e)LVyar3>ynfdzN#$TGt&RKR3zH!~GGa(IMAJhM~**;Y&md_XZ$^2}a z)yFrre`3zM{u{GYDT9xkzWYAQsnD+d;oG0&E=T=1H&Jp1+nmg|o6m%EqE zVYzpvBC_7nX)NzaR#diJ@HWevQxuo)Uuw_t%aNsIc(bM~ujyD?ZeLfMsLktbgd zVtHY+vNFrn+$&KrLq=DWS+l&&@|1=_vZP4La@H?`WT|$u zLdbR<9tFvs+iO-QdAjo7;^KJAuRaNqZDei_T@O1DBvVH(W;yxoin4Rm4weVZs3?D$ z_BqQl0xQaX*?(fWabyKqpkj8DK6|HZc{#)=&vM~$W#xA-8nIk{YH9hfYhRY1)F~+k zR3FcB`*FqOM>nRjT%kl!`Ss;lEWcP^MEV_{&$91wf9Vssg5~)&edTLMwzHg~W`23% z=^mDoZp$m@`0Zu6eEvML{%eO>PJJS$Tz>Wp%hQf!mD%0juza9tMj7_nZI;D*Y2@K< zk62E-EV(>z-$&B3+{pW@S#U@)mNVXcViruElI0IOKQK$wPQ&u+$?uqhcUj}wj9pjF z{pqst^~V8c%qd5*vz$KoggHGjC(A#SJ7P}yJU7c1v+pyfkFav24Kr>xKh9p5uWwGV z*6h*WpXCEv7MSHD0$FZQFxG4|vN+2FA|uT;TdZ+5@X=s%(Vdcf{pFHw=C-#=vt07~ zCg$GDWmpa`RNZ_~r##CIre!sYT(V@jDWzGZr!{u_ME&CVEK5bcXZN!+p3fgya$o-s zJbe}h@%3zP*YvFU#gaccF~{BWH%lJSpkheF&6ZsAMk!a}p_aU$b5Ga3yq27{-7MGT zX;zs_I_`8u9J1=ITJWl??3d-Z{G3zs8fQye^0MZEM()tEe7#cs3dX#S*0anV`Ojs+Fv>kGC`HI4-buzauGJmcgBOSiM!tBgu73-a|wxi=U; z2Uzoyl-sr#p{w%p_4UQw#s>#;u{@#Cr$*fiSy=8p>Ti!Vfo#<1;q0w8(6+5 z3yQHz*09{6Y+*4X>r$4V6z~(d+syc#5CuIk~U z>&=D-#hWkbbEn_tWZ*KV9}g1!=jZ44_`1u9XCF>xIm42oVr_tA`NEz&Vr23AEI$~Y zN>nP5fo-&T=@sL%Di#~Vu52`J@3;Ebc-LU#*&vJ6{yQGH4$b<-71H(%-;zZmg)ZN` z)MiiX`LmX+_$^A@Or6iQeck**X-`Foavv>q-M)OeaA-w!JpuPD5`$dVJ{wy&|I8@S zqi=s>T<8_wVL3*LC%29ouYcIsuW_1wqRgK3qR_3`eh)9S62ZI6iZ4>__N!RDnrPRp zk(d~H(XaQZ+~V%B9^!iaM}C*qUN?@_3Kjd0CHEh*eYSC}ZlsvsFRlOT%6DB<$0z5~ z`KvlTR7a3c8h=%%Np<)nN$RiaG^viF1%C8XbxNwE$cvMHs!mCD%zAr+pQ=+*9o_bh z_fvIBs>A=MvVN*gNp;-Hu*_H0DX9+iTuW4)lIl>;wN%w9sSfpA%T%3`>QK+MOw}o= z4)t8iRGpIQP|vkY)hVeC^<2wTohH?xo@=?P)1*4ob1heOdZ-TdT+2z9REK)5<)llh zLp|4W(k0cQo@*KDlIl>;wTyI0b*SfBM!KXr)N?H(T~ZzDxt5VGsSfpAOG%fyz5Yms z9smAzOu6CE3i31RzgMzoxBE>80%ST{jrGsT(lk;CsW4Qx$dl4(i)exeyZ9P zx32n^tn<=(XkxERPBP}a@^#5Gg|fWTb;(y{ulBF)N%VDj;?Vlx^$Xs2N^1++*+;Yv z>#WQCCFf2zY`9!sm!b6wE}!b8wI91d@y=G#&s@^l6L0-UUsnoTb;?a_RAQguQ<=abI*q>J`7r#+;9r=9W6=U2K@`~B!A zTIjNN-ebJasvG0V)a%mQptntLv;HhpAJuwj;`K!T4z-32{dLbdwjUDH|88B@>2_gK6{v;6-tnJ8<8)L!d{bZON~-y@;5CsFFHP(H?4%Zta7&X{VK zYSUl0&b291&O~3MTo@ALd{+ha@mIo0uAGl~?;hz&mtn`+%n$WD&CgKZa=4=Y>-e;I zKKb8aN7&1|?4|cLU4|XK%Z{*@ciBttYq|_OdY2txFYmIK-q&;)cJwYg!d~8GFTJnn zGVJIrcBIIheqP;vY?WUL&~jyz&*Yd_#k-WxWLY)n|MXoFDxc}({a#tF!_H??4DUnv zMJ50KL$VPEq*eZ`=&m|=`!r-U3P@MyvtsCU(;pS(Yx#jdwG|=^uDIcu%ma` z5%%&fd+B{mmtjZmvLo!}UG~!Znl8hR-eJdM!~KQIO^J^W<&gKrreb-@h_Z56xzA}Y zjo6;Fwro*v3d>nPZ!T-}eo1G9ikSo2OXKN5I;&QUU)WKe*in}9Z(@Aow({ZDB`jZC z(pcuYaE;|pueoG$|16Xf5PRM$DsRmz$#Q|N>1CNzHCYbH`<0pWIG>>^R%LkCOf$S4 zU$0mvm$PqEyw>J=pmyER?l-h@46S^j)ho322(6t$YroK*OK8t4G(8ASKSI-+(DbRx zUZLCdFZz3>ZomGmj2LuG8spll_rUxri!QrI7)?$VmE*Tn7b&uR;kxHjN*-Ji!e>H` zy--SOHj@8`&kF6cLaSG3^$M+CorgdDS-l)r*Zlk}$s!tviMj9b`F^=7bQ8n+FJk#Z zonfLv<*Y3GR*4XU7G8JL8GudAC{gB61C!+8pN5O6!*{WKY3M+4KW%bJ*M0oki^F4z zvV6E_O>sU&U6xz?<}03k(uw71o1Pns9u8*tRFd^ZncQPoJ}|S4q0Y5qS@m-t?YgPm zZ))Y3TKQ6|S8DB%T05oIeyKf|)Sg#rdXSoaq^7q&;vqqH(fQH({@>PTk}dwuK2z&Q zf7pL3F3QJ!d1Q2bx$jIa?&H_qt1XXZ&%%A*bFsQ?@#9^C`unq7UFB@Q8wUA-dLOix zfv3MV$Uijus+s(H)k3~!P|l&!{rUTR&%Sc~W$?4vd{6M^uJT-T7QUzHi_vn#FB$lr zTNgs*-c_mio{4w*%8XIh+*DWFs7UGm<7GG1Rlng#*)QceH`SG*_5fM;Xnm9J*))BW z{QjHTCfze;>$`^9DI(u@5`)J9D&9-}o^F5!8E^c=D zt`Fby=z*{Ka$Y3gLwq)RYb4)8@}2er_#TqAaty5;Lo3J7+GA+#F|_s=+H)D&a~axm z8Jd2CrXQi{M`(H$nx2KGXQA0kX!a7Cy@Y0Wq1jz%b{85yLgPnh{0NOhp>ZfQ4u!_E z(0CRa&qC`LLhBbo>lZ@nUqb6&LhD~b>!(8Nr$Xze`j{Bc59|I}_uINZ*ZsWi|MhV} zA20NAL?2)DaYrAI^l?fbznpRH%EVJ^wCnN4L9HA^D?i?Nsfrt3DItly)5R@3djea^6dO^cP9ZvS?32C*YV(An>e?vxV$Z8ClL2Ki(9o|8Y4 z>F>^aTz@zD%k7r!Jj!-|l{|LV+iL$qwCJAPvm*Jmo1RNe$B2~1Z=RMDdzy1P4H4^S zjW*M`*O;eAbrx;?cbZGuerfg(d|hNOf7iVDRT8;0S8)-$ErZO}Fq^zpBBkhS7M8z7 z6_(ZZo5tn9va&&r;xbduH;qrmSCPq2m6VUV+;X*xt}aWe^RV7XIwNH0_7Hh0dH1!{ zh8@?&uPvpnD?USpsq0~Pi_6;^4P(vVs&aiAKlyEvEyn1x<>dX*Ib`pBKBBX)zudPZ zx%6uiAZocY%k?+DG0Xba6200!G=D9y$sFFQgE(LQ6SLO1Fw<3GkSIKMqFHQn3NyCU zXtDVFEanF-Cwh7xjTAq;H(Pyw1pP!aAAgm+=8N&>mD*DRPgNfw6CzXnf95+fRGEe< zf0ZgaAU+|^*=I&l{Qbcs6(%arKXB7yQc?XrLw6swUb5*SfIjY&F;L}Y{n+vXdV`lrj zp*$V>lNoiprtIkZgSn*5U~~VMHRZ@O`Q?-<>RiF1?c~-ID@>=%iK@*1RQc10iDvr7 z9`}g*VWLl`T4t)xgJs{*rA7K9X<4_^k7xMsNuD3glIlFZ$B%OeM-LN}P8{71R=Ra` zo>S@ks61(g-)JW*KVEM9Jm8Tzq|Pk!QPY;<#<;6yk6p#&z?S*M_U{LnehXfcjg@>e zYCL~uSs~X5ac}oYqi^{c?#(;;h=&=|h)bJhxLcHJBNjaj5NWH_jdIWchjU1H&lDZm2D$# z+z$|0RC`YEt|d~Q4-t!0dukmiC0cfFCMu}*Yz@gKj-2l%s;Tx|@V#qH&Nf6$SM9l% zV!iQZ?a^YKYEQ<}wTvmMJ=0Ws?k@kmJqexL{}45v`-Re*Oo*(WmtzxEe&s(S7yJ6B zN+(Val4YOGa3{OA+3fkOo?N(Lru%wyL76Wov&?p8hWqtVEo9zkt3A0@dva^CQ&+95 z4=b%YG)VsZbcXv#p)F?EbE}+bQ3a*DUS_%f^bB`UzZNp}k7N0{77rbfAlb2FLiN^h ztX2N`=n*m@veW*A>TP|siQN8fNk+(o$bYtcW$U>9k`Q^$FYj`DX73p;&vo5l-dh>t zUj1~SjDB*%yc<2u{q61UvUPYKxo71R_xcMBW&T;!msu?n6JP zm&exjk#82B=Dzy;r1|Xn2s!!oboac+k>-eBBIMpyvF=UFfAieGX))Hl-a@w{cT=+7 zhRxAC%=W8d+?sD>kJo1TZL%ov?<;EG+tdw@I0xITB7yjv{R-K6?L1P%$3WsAqU zJ5LQ3#l{uj{&He({dlrd{!Uf?`5#BiHLCm$cY}=Gvxmtis(imz3yqXJyUXUP{B?V8 z8jU}yE01oDakuE=EB4nZE<4PObvOM@h@Vd9;__Q(ZJZ!EA$?rGC$YJ@Vsltn`EB>L zokkfEQ1+(gQ&FFPnaX7xI3?_BR)D@LmXP_s~2$cK$qC z%-R&|UOP9)3|~J$OlcD99-q=QHy3UrPN}}I!Z(d9>K`KNY>ssgjwvlSRmjhIn>_~` z#FHK0)v!;V9kD-+7IRdY3pNFrzpWb}CaW^C_2iH1Cb`?LFC_a0cabr^lie>L zKQilH94uRnn&PfoXM;JpakwlrWSaYp^sUX%_ao(+s2I2F9Ov>$CW(W z)OTJ|&Mi;12Gt!ouafolJpB5Y8S0+y9z46RER-ajOm0qbH~6u&TdhqU;g|Xqw~a8vXM~C7tJ7M2bYrvKcC`WySl2Fwk5eNpMHuv#dqyQ zRE-bK`om`8)_1D=`RFlX+W4b;JhhbXRo`V?yI4A-XTex^_PG&pZAgE( z=bq!~B4sAkhVChzxss<3lO3lkf14-9$nsiGIj-t-_vdrJF(%J#CD$6$+`BVo5S40{ zlUr3AKKP)j_~_&0vZQK5(JSplbb$}e>#iy83$7vJ=Tk+^iG8NJ`$mruAJ+2hsjS-2 zNVQ=>zjQ{hYQuqdB1GXE*7)dGc0_{Y0@2p}YThDZ%Y9+oS{>{DJiNCUzA&S>TUYhR z=`BT}z|tZ|$yj&$u_2;E{rV!0>W_H~6ckT8brqLa#=3`Z{MqP#dx)5QE!N$v>S|-m zjM3uci&*#4)Gi}gktk7L$&>mmce$@x`P(X^_qq?-@{8Jg-Fh1)1zBylKB~9)dQnDk zPqks~w3echYC}%dhPtW^)$7$4xl|jb7Az>*bnGfFsWwD!``O5IYlwJ9wc*zqtBqr^ zqs19jZ{=Jr<4{19ctgqS$1acaV+rlojvwgtFz1d%Imd|5#xd?bL(7{prwkUiK2WH9glicq<@RK_u^NSrTCb?V3G?0fk|6qI+GTGfs^pF9Y zml$6MO>yr{IZU>DmfGl^Y??b_ZG?0u@%0oa7vuh5f0Ru1T28aWuvqu|cZJ|mvVPL+;>Yci+;5(1Dj)T}VC?TZ+3oYBmyF6i$H+cliaNtOR6f{t-<7NK zG6za!#(idel-%gaW5$k&b^B(Dkcu~Mo8m1&veV!1UCvRt+v{WGx`(mu zYH3RwU4{>lul*M5PI+yu`kssS(vx9^+h=bw@z7mS7JnA&UK~Qu_I#+?vpIEXW6rQ4vbJhZ%#F21j=}BaKGmMD4kQ!4dn(Fe zsy+RUO2S<`rJS$YbN5zTG1YgM*+I3Z?(%`6;NbjbPt~5wsy&b2elKK)YEP2e>O0UE zrZX<6_9UMjAsVE!`rVF(BN8M#woWLweJ5FYgL<7t$b`s$w)~b=t$F?|HP26o?C3e6 zaYO^77?1C-e_umJS4u4ol!$d#-PT5~pZ|rCFNvC0bn7i2mu_oNAGzljE(mue@IL-$R07x1)~ z?ZtE8S9(4=vbso!tlGon zCzRVH4a)NUB_>pp36Wb=DbMYZ8>@&hZF0$cAE`07e`B%h_3P%Lv5J$gdWZ*a4>!A; zvF=>4BSq3oSu5L|i0~r6%iAkk<+R#VMcinSOXgPPn1dRNH)~xt536#fT3ff+xpva_q^Yydv?#hXTNv;dQP3^R#(-nzI{VaHR@fQjH75hH}cbw6Ib6N=CClsA`yq^z39%50wJp<{<&7AeS7DC#J!^L~_N9b73|K%P_H zebeA~@SobFFU33uttO|z@8JK0e)9aH^&?vU{}cbI{#%C@P@hLGt@^ByhJFXr`bq!( z?tQI3dL-eyRS!e!ye6QKmCJ=mM>WyPhCn2LBVRc4Xcr}QFBUE8NzZ@o*Hdd*SxAl^ zpA8+qLKuNUzVIobW(-eplY5iT$ zMRneeMFq5e^sb(IuakugX#I_9W2o{oxo82cKd0c|^sm1xu&+3ljWnOp&ubYyJf5A1 z-tH_A-fpkN3R415hAX}A@kJVjZ*oA91_i>?a;6aOH3;ct(R0!Fu5f9MG#YZIK{EfcWvH^P7Q7;jFq_4G4stPZe9Dvg4Yu)-L4PVO~ zP&9q58$C=x%b&T{=QdY(v|bt+(${*tBmk1$G1sbi82(%MPxEB$f>Y!^>bez$eg{YY zSeGrHoNxa-IFrY`L!#qv4Znl`)c%HXHY9&`?y^L`gMaS%i_bxR?(?fjoUNqL`~Om- zHf|Q5#gr@JQ%GZ*N-mVIa-#z1`Km)@Cb+h#P||)jVE)D&G`9uNwZ7-T z;S=)>@A6XU8b@>B%-p_4S#jm0&T@L-F~cu8-8tfG)%oZFYu7@N7^50pkUVedCEto~ z7+e)5dxwMjtA3F4u1KhTe+u;JZw01TLFjhV8ZxXV!uQ!Lg!=>}@`f5Wm_b8N1ZUB?p|BH&QV!+O!eo7iwn z1Z=C;Xc|>`18eo(iLD$XU`1zI;}!l*yaPqR#v`8^e(D$ZHM;K&&H9SK zS>0*#!mJ(7*>fGgeB}(D4ZWaBe-Ip>(jUUl>cO(z{o%d4G$c$khPRXZf%b;?xa7z% z=>1Lwg3jK>b6<~uQDw^T4WGkR9uzD|?gLjIHsVWjouI3vH)QqNjFV4}gB` zu;$`^(NwNC$h9ay?T{SNJQW|fxkUkb=D!lYKJx+34VeNP>9MPHVKn{i z0H3$Jg0Csx$0w2|!m#5#VdA%2xN@p3eARr1vj@;|l4`~Bt@7}#20^ciW_A@GpXBuv;8JkQI7yO)q01E4{l>GemD%T5IJbD z?_kf;a7aBm&*5kd{mvc=hn|Ns9F{(B#SxaY{2X$qIdl(K9|(gdXNEfrth^JwhB91MCF9N=^-+zS8;NGp84n2r26DS649V z)*F&bBB)b%JempCc6e zniVu3R{_HjEmU_uGf-9T2ZJ-8Qkm9+LBFv-9G?1>+8>||XXRAk%;z4c@4)`xQa=!G zX7xeCb}7Qgi-Ta!k^$)aNLlFIst(F!gV4d!4qT?I1&`%=kVJQ|4~pS6a|!_Clza6TD7$M#xpWFnh7LOfnAUQ;x3>0>S# zyK40}8C7&j6V8#WQls7PRH%!-Hemh69F1D*M(v|@c2#5|lMrTXG^ymG*|yA>nOKmE z2F)lIiTQ@L!_n}gy*XlhKE)FK^X|d_{oR9q;`2{@{>g!Va^RmF_$LSc$$|fUIpEdd zOZFvR8)QPBYA8p%uVS^53&JfIL}FZ3nhVMWxn#Yc`Z5g;nH(m#u{;K}c-=tEnYnKo zB(Ze}R?Qp-CzjX}Eahnd%2SxV>$ax;5G)f)VO1ou8Z5j*5E zXVY8er-{-H8JwBI=fqylARN^L)2TycaRirl?4h{AV1oO|bx_(VlL(IAtcH3S+Yo&G zoFzKzra^FB@!%XzoRtZgSG@>+HYM|yHMJ$ZmKW<0 zujNbWwY(Tx(`)&svu|TDRyiIH`Yrv4%{$&r0hdFT1c!{UfjrBJ1glhPKxjn}!5_Om z;ZXX0CUIMv8TB}70~4$B`)1&$LAgY(T+Xbu#T@CFz5CUIa)|tavkLX7Acf$UDTS2s zhgk&6t6rvTLYe(u{|O4{G|!R9eZmcqes?2+x2rp%Bc=)j7o_+g9=C=9dO@C za9&nCl3ZuG({pvP4d3axdH_9F7vrJyT-}SFtBbLCu72V=6F1?MOmu!f6Hn8uOk`1Z zpKx+Rb3x@EbFFICS#bIegNF^Ag{U2aEj)rBH|`+!@+$oRbSu?+rD!i>*0?D=@& z`axuTc6A1PB7zyuC)Ty&BlnnRgyM}3Y{MT;o)NyKk463RhLUH55jz|!H0zLOgjVBL ze5JG>c}C3eynv%p89mdB+o|8df0{FYdX6v2zmdY&R~=_hUO=%6Slg{ zr)0*_@8C`Zkc3Cz+_Tzsg7UxVcoilHy=hx@2%SOZK zd>b2VfJ@dVqDgeVMGhC>X$~{cb~@j_MYmxc6L<89&bOeven8hKLE?3;xMoQ_jeTis zPU8>nxF{iag;2p&Q}}6YHsaB_UHQNSpEpWGT<7(|!KW(mv6c{2?zT=?_xKH-_Ie6R zyRce#_GUj2+p~_=GuEK6p7wKuIETe?{ZHWfA8kP#uRp<(e*OP|b*)yAeGDm_f)afg zd}DvgFZGd%)7Yf1OFlTGHRf^zXZiUdO?oU7=YY=MNR;v;AB@1P&L|+9h+8QrVC8axd0$e{TFmIVrIrepRxtAG zUs9kgnBi}`l>#kO7@N;Gr2LYTck8tno7atpu$%2f=gj6{*!B4!!53R&e&L&WF?!5s zJ?+hmUnP4ZVT~E%ue!e#k!y4fH?17 ze!8$%yl?aMLz;=CT!-dwrTGc}jxWjiufh^_M}Mi+_B--x8y(R6x4lJYZkYgQpeOpa zW`M}GPajBr9FC;ls)=-6ZsDU9$pohrufd%%IfOG34a7g~uUxfyvlxr@d~s?Vc{n{A zz3!t2*pWr)q zgW=EXR*Y%fFJT)cVKXJ+3nk&>FSXYs;()#>dK3GdwUp4z+mXb6^N@4Yn`LRl{=2Gk zDVKve#Qqh7x>FKy{zd0s$$$Fj>s@2y_?mu>_pcN#-9$MQe&wQTJlrH0Xy8ES6zZ=h zEEu-jc!(GeAJ)rY`=oSbuX8zQ%a$ILa!j?+^D$}Y_53`laojee>GNaIfVRWb#D3e1 zetd5Z#rRI%B2fnwCDHHldJgJ=9&2Os?@O@d#B-eGSuPY+7lD+YxO3*JUL$h%NByXEZw3>2QLs9-ZqX?s-(Z9!x9;4sZ^D~#kdc?W3bQ2cW`<7yI zi6Z!SI1+gR5;^c6YQ6r*fnUa%pT5|bT-qX$OIRYuute_BwZ@rzcIlU1_%l{tGxlxy z8LJ-3c+1aNrNo@rBIe8Kur_}jWwQ0BFUJ?uY!UlA_j#4@sn$rL*x#j5r<$tm^@QSk z{71f#aqLGPl5y-ueqxEd#o|2tkpn_8{*f~xG5(QbB5_{*=yxLjk&{>~|B)v|&yO4? z@*g=y^ zee@s32l2Rp>G9!bUoRM~SM?JI?L2Pi^__kNu|fvvrN5zY#~8GBuPox!?xJS*_CVM5 zWzn#Y{#4^GKU8;H8l9eSi}SOsI9LA!UyZUJ{F5)n;(YsI+h69JL>wez1$Fwq#O4t% z6tQLSWMVV7U@7h_9z|@%$)~ZDx+Sss`Qq>Ruk`$tTs+qm&z;0R{wbEIe+d7J@PAod zM~RsH?R3h}{r-gh&t1Wx;kIJj<9&hfU0ZX5q|Mca-e{9bvCzg`3AKKSL|XJ(?B0TN zlxKAs8XvSyIK_T0)zF%QGViYzt_ki=Nw&T7-3#f;7YjRMm5{4264l$R7h0B`rxN4R zP@lMU!jP}?sH<+-NMl^FuwtkQrDMcJ(_X9+8h_>e>;I%LJJi|YoGhjHBA$<<=T7wh z6l|qe2nS}2Ys{e6cjp$b5RO=8B$T)=h^~1de%Bh|{LMrZ@Y0v7bzGmc(+_J}mVwe;H4p7!^~Fah4i znSq+=wWn-E8@_Aij`HuV7N*YW2ivDvh^`b46uB02{}R*Bg+HoiIr{!^?4q1a-lO~- ze17z7w0ztF@wYLg#JJ!G-k3K7onHEy$PfF6BdNevf-kp4B7-;Q2rj2Nq8}WwT>pn$ z%>O=(;hQH0ku&9})m&KT%iy^*?uHn=mc};>7`&avo)Y{sv_0#_9iYUvN#Y;25%~f7 zT8e?K1Ye|Wuy{kh7a}Fek(5jFf5eBx_jmB0_QedHX~g$QYq_YeEQ4pz_|VG$B2TCB zy-N%(pfM%E7yJCD*ZZI6|5@!*aShW~sk;iqcK;5hd4E*&wW7?OI&1T0?_IJ`Mb z*Mj~FOxG|6dJgG8*E5IT!HRSZ@E6N>8E&9!fd3BOdSNR054we^qwufrMRya2GJ1ZH zV-f9;cDF?o(<2)dxAdWgCkJ6%9*^Pz7gF8Ls_-4H>8R++0V=1y1%HxvK?&dvTYL@M;zdeKAreY)zHTO3I{CGmkP ziURSN`tZ~|-GA^uarh?({#$c^Eq*T2_gXm}=l^j$Xlx(^mcQcjnxsGyCxy-c*}3oe z#qw=V6CPkFq$DNI8?Hc zlEl=ccnGYK5gb^&i_%StfgVlW1;)llsM&UO&6kx@g3Q#GU+`b?{|-J%+OXyv1$Ixa z@Nu;<5MH7_@ULwzu>>({~dh% zJKNyA=PXrnV=AlDItoeR6KC#G1G~>+jXM;E{1>)UZAY?MkDdpk=qPE_XZd1Q+wOp0 z@L%!&ZoUU@=b+^cCs@j_h9XJ4Wvw$>viJha?K2xyn@mKTzFlKQVGXo6(jBepdzaOL z`u&3civM@>SJgTRIj)jsAGlOTN#ZFJQqi)g9&E#H%c$M$>8L|qj{RaqEY;643!R9O zXDbG~{DS|A|9A7(b!RR*vPh9V)$5!{5_g8@pkZAKY?!Np5ADiA?sf|7xvi`7cV`KoU>3(uUfIDt?{Qcv$K`7!nuk z))d)tHZ(PMnyV`lL6q%mE4 zbT7ZDmaZGTa1d0R^7xiFUE!Fj9Mtgh`CF3xK&?R*GVJpCc!wW+n>7foDDn7qZ(YIX zu`z^|?&aH*P#~io3_QoH6_@6Gq|y_zVBvIqLA>uMs&6d)ol{Y{o<*W3emtr-In&6# z>IskTJ!}&10!DOl;apWAIVaIrmGX<8?=?A)eDAT;)e}7_v!NOA$#J%z zB{lFd{eLUd-Go10;a4o_%Lsf-{4IE?T_@=p!|pu@f9!28+?_rh4$Qr(^P=WE9(5}T zGH-?X^MEoi3&Ubxme0)q z^UidFmEF_fyzMN4vph54^K2{PZ|DIoJerV5;wIaa4khj0ByQ8ba3Lf+i^y*nrNif| zx!@4DNw4GZA<>PNTv+D4NpEE4AyJcG0^w{wkq&M~x$sbHBmav_2WM6?Cf8!~WD~;`R>%PMk_3U`klFP2&dZ3r$~p;FyKf;l=x74y zEN&q9!TMP6^mJo5wVB|hwcB3ouOc0jyu>L)eqN9XLJ8YmI%h(De3{QAF!o7oB7C3&atu24;)-=ZrUc1qyg5?E6I-GVGQ^JR-( z&?^qE2nmME{--J$vOiE~PI19w=}5iMM7C&TNiYnXqonJ+qXSD{aU{06*%?Ahj3U7c z_IN`de=g`O?8ld`TFJRM)rQz`>1h^BUTQ};njYrxMp}trb$4&Lr(sF(^QSf-X^$jM z_H&1{p^n-Yy!(Ng+(^Pd*)a@WrPAMTrhi3S#z0lhYI3cyUCA(T*%;{6YpuHJ20fTr zszx}{OD4h1%wX`scPlRFexSJFT!`vgpyx9%U*wt|0K>+v(phs-8ZIS0C3?cuX2RH| z6(rvbOt_G-W+5fMR&ZA;?5ti*a#G!c3m2r)z*2U;-jk&ZarvVZkd{i)yAf4@uV1wx z*PUu+33(<`1Z$TB!iI&>Ft6&eZUMg;H+u~s*Q(FR{v`)w-*D*~Q}=X@@9h<8H-*81 zpcLIV&+lOuMAzV=e}PTDa4!23vEiadE`Zw?a$l>`V=PDZFwvR1CkB+ia-mO3p6+GU z@xsf~xlmKB%r{!Lf>Yxb4|(xAdP}o*;cbRt(CibTdyRUC$8B*V?(C3t3**iM;7#1O#92N#u8LaG`9UFKE0Ntut$!JPet{*w9iD18rgM z;5gGsyT406I3Z;~?BCz$1Wyll5j|!{1A(p1Ci0I{T)-fulIT1(gbO3SSP}V-KGv{k zv^O|ub=PrFSArgC%>7llFaqwL>O(kDr#&FWI~MM(kkc!;*NC;%BEV}^zOLE$TlkxI z2&8wa>30A44tG2550y1}I;wAE;CA|LV#B<1;Sg3b0otN>XwJ*lg!1|j;Ox=SHCXW$ z517i>z^bZP^PLNp zTY}1$4j<@{slvo<@uxtrjf{fZz6W$uPoBYdUFY=5P2THh;!bt0G~;v#59?}rb13`I?LIzFWM2336#tn)~o<8N`Ij*%saM1aH>ciZqK`fU+BwJ zq_HAFpCgCmulA{Ub1(-a^|Unl!RNeX1xqSrQEk&i7`f7+LQh%)ou~h^+j23V-~Wvj z5_81y7js;mkA@}L&jlAh7@$X=bf8&ymQ{aiEP8oo6sU+SSx>x-kd$c(6x?0MS~Izb z3hkEz?5&IVeqQQ$@|SLKpy9J%PX08AXi37?Un^Cd<)?#Fh!xJi+PlKKD~qlrcNjYj zm92O|j}J<1AF;detswtv&@Wihm$7$w_|?{)6|Q#@;Q{?l4P7I$;-r5#NDFh}M6?Ni z(#%t$A*uA*Lso?^j z@gUdTOfXEj7B6^`2qns!SogQ^r~$pwVeGCKd}>$@{yxtRf@i6*9{HQ2UD{5dY0F`m zHyEHI!&$H^qnuT9yoFNepAJc!7kvFA*|^2#A}(^1smPrj34OXbz_IJvtR4qVQQ34h zEDbrq8ms1lOfLT>zvkC}7#mkVe&&BjAh5QGuubaFEvT!qbDl3as7- z!nl_Wc$=kMMcBevh|?GZT53-O7DFdN)69wRYRz=k&=d{S@M0(=ti2>yvx5VPBh5i+ z?>T|Lzz$4LSwjQ&xZp0w3ii7XfWo}zf`M=8vAq5azIRuqV(RQDh*_EmCwV!noxW2k zZ5Mjp#+TxEEH4omUh{zjt(5}ps-9pfodxrHr?L(jjHgz1Il{6zb%Hi|L#T5}1JR0= ztf%>T)B-bCc<)gqI25f8z8h>{ZTvC8hbT*MYI=-A=69>mSv(WeCPhK!Cmt(t!ddE+ zaRR(pQO?=|HPqUVsnGx2D%PsA3#qN&xG;S(SGQ}Lfx`~dEbw1f%Wpj6f{*oxg0#sV3W-cYx0sDs8a2bSB7iD;@$1}yhp%&I*cO|24~#qoz_DpG8tU`hK>7`^ihe^t&&xOhN}uNr8*M~_hhl$I^3wTx52PeHCs?TyB!an6Au%64;5@o+=*9C zo(W%8#RwWVJ;9eV3_)f6HG%#nN08S{1CwiC__Gf!z^`S3K+1KVV91QGc&&^E7zS=) z6*o>qqY~ob*aRMH#F3qp?dG?*H*^WicZa~4W$qyTaihSjPd}*ao&)z539geVJMV+9szagx*rq7JbW%=n>%0=Isv*G={0zP$&t}T4T87S9ULGxiY)NpcP z(A7zNjqPos69cD#(xSzJ0_YBN&&R@He?H49c0Z;6JRNElFJWCkanx`Q7eaHT`93F0 zMVd|0(3bN_P&_vPo}a&jThwJLK$-qVR)8(cYd$2HSY!c5bfe+5FQ3KEJxLXHhJbpn z^(@;3Zzy&8JnPJ~<9a4aOE}LDapC^N6+GK>7NXN@GQl|>^K-cFIPNliRx-FrFtySc z+^;^u3o5!*962}>UgSH%jG^^{#^r`Ev$YjJ&+cBKX&(*^5p)bqbNQ*WRWNT*F05VS z&DU4@EK1;whfyo51;>S2aPR#XP`bB6psub5Zw$Dgxn7aq<8_s2Nk$CB?&7l+YagLB zuFi%HReY9pw1`?UkFJHZ=sZu&Ek{&bM&JL(SMg(x7~oX{Q{ZTUlA!%o5xz4l3)YXW z<(HuSBB!na7E8mkDmmuSM}8xI8i3nzfm@&Pb#%5y>dF}jwg zoEyB1;|UDcsKS184cKGwNFZ825%TWLhO`5Af{sxleC;F`misK=J#Nz%74FZ5fcQdw z>vT5W*k?4Xm{lj3_+cU=U9qS^Zd+|LHEXoCy5bnX%y0T#qX3%97N70h zB>Gszh4&M8@TB9tMA|;C5ZI?mAZw!zC2Emy_>!lbX#P$ z*{@w04ZF9F6}*dW#_OfrU|$wb5VJ`YVl+B%($-GFltaPrR3;7XuV2Nw7PF8tEls57 zoSRsE!vvJ`oHcl9vqHtYmSk|hH5Zq0s-x6y04 zFi+O(dHR&$rJLAIQM$s$DgxFF;DX)`MZp>6?Hp4jF5qfKK`3_@=P2#hjf;wcW9vals2-y|e*@ z^-2PdcXL=vkCap4%7O5m_l1=)s2loHMz85E4AFa08OS-0azXCyUcGS|ZJbp{rqSQ^ z`NsNM(hZqqabdOgSiMD4=Wzzfao|>-7yFFB1WEg6!-ZMhSwT)F)H2;;c)Fm5?a@01 z)$Y2DBjUEPH4lZOL`x&^w^_jc{B0B(-uW^=4;io1)M2ltIplZtLa&N5=Mpv+GOPiZk7j{FHbYr`^mi$k>HtFHD9I zR;FNot15K8v4$mgw+U(oTEPqVAeeS;n80$%7aU~NfenvsWjEtsJ@$8HFRIE-R61NE_4+{~izjAs6d+mR_&T^Ezx7zi}e0TWZQSGtoc~ ztfO$v7Ekt3n+&x1z;HOSIG){i^a!-JC;@EfXZ_;Xt<><(IglQANUv(G6eUORYn>j~ zo9}9=i@9D}&^mY}yWhLbhR1{4d-Sc~6>Qu9OU_wrBr=*cB6=Qz{f zni?N&$gBK5SyTWKFsVpUpts;U7QM@c#?aS#H5FP^@vU6wisSL-zc?WJ(k&V%bk}7c zHqJl~o{oTdgG1Tf2MkB!PbEX1+H98kr8Sh(*fh}UxqyB)Gt5UXFcHRSsFq;X+%ulOA^$ zm$N)E6FRfT^7&exxYb}5>{P_8&a*Al-S<9lwsNXqLuOBq?8kG-=HPiNoxL&24w+Za z2A!%hmfcuPeYDGl_V-%+z5~qhnlg8YHjfp2e%BW!JT_JH~~JQ1AM)! zHF(`7Q&Af?1MPB$|Q;~1#M5yhbC(xX(0bl56eNh=(Z-2BG=Sx-^B)Uvwg>=lL zo*Sfqg?b6UDW?dpD$Rk?_3wCXaf+CFF%zhr=U7iI9#LIcF)-DtidED12vtbmvjw^N zEH~e6)KRk(unU;QIy<_E3Moqg!}K-$Wv+$T@KzRZdMmPYqef8kPsT$`&jOa{+IH%B zEf?C8)b!457{lS7Pk?FN8u=wETkutlB(Q4Q&R3sZjt|lMQ&x3ZdWET#oNJ?!pl%_T zrJY|!O)N}-M~cOKojrxvf_|oF@t5)+Y*>t=Rs?}!$4iz&@@Fcoe=rzoJ!idI{gHYj zmjJIq4)Wj4+lB=*ePQn2DS{i#@^E?a5OAuP&-S~3knY4x;69kZH}2+x1KcB_K~T@C z*mIF`nVtzfIpg`$HhAF|ALu>t{+_y9Ll!%X3Z4jIqw@rESsLKxF$U}m9oVI>OW0o>o z##af|(`OkqnrryalnQaQeK72J`iZ|!?jvO=8w^FeKk@6DKT>)6Q7|*Vn;@$DIjX=V z5j3~-5Im2pr1lo1LoUb*60}pOt}W>>__VxWOkxrh<(>%gJ9-EL^((2W0a0)+uN&?A zIm-H&BPHH@c^;I7tVCU8pQ>k94hlNW?4gMc1tQ~+RI)#_LSY#dER#&|k#i-u($a(A zhc(I|sps-MX5V}B<193`$5x^^WPS zjgC*rA@ZT0xM-Px+4E#)N1#0EG32`Djx1!}N}m(czX@#Wf=4($qgHB8BY0kYcjWi6Kf!l~O+f`mW)M7n?JMfaYx+N*^v`X56snQ& zBJ#aod!e@2UF7`e^cya6YkNt2U-OWQ9(xoM{<8XH)T_gj@OAq2M!n7?5&XhpD_SehR>$fGWj@J-&GrwT`v6OI`>3At)A=LIiz#2^oe zwgJR)uCgXllJDj2=VMU>dDYgt)n;ey>nzD+wG zy|QQa?E|XJ(V;i~ME{r?8KgY=AtX%RIM6>hG;YQMPTnY)V9m9L|*ECMPF438?qGDB@T7f-F>K2*ggqoY}}~2y-@9DP@G(t}$^FSnE;` zJz|KSx=Tl}`l@t-M?Xo%qqV#V9_pb4#gmz{IVW9jw4dHL7sny#rUwdn#@NYKctx26 zGCBNarxz7rVMI9PU89hTB@>?_xq(qyuBa?DkTQ)KRAIx&(tz0(&;$s69A9sm3ueQ3>*-V)`)s7%)LdT~TJnTh{&< z{7`2m;fHxYr3#bB61+WA7qz`(;`V7;H_GG=W5a|^1yo)hi*Q^{(erLL+isDJ0`i!+S)QIswbI{966+kJ zkC2l3EP}6hyGErZFr1OYJ*h}}CZ6Cj8z0-wj57CC4D| zIE?+Xz6_w!S1|W`b;vxtaS@YyI^D;kn>QH#!9*7F3uNLPJ@X0WG*5x(F_`FsTJ~Zfgt*t5hQPjCUX_ZG@RZK7jt^IDdNjN#)l{SH*!9C zFg7m|jiw~Aq%Q{a8M(Oax#b`1v)3|uHs~r*HmA;z>-LF^LYrSQ?}r?&&P1~h=n{UQ z!&s#MydS}7Z>OM!@=1iRav~GyTw`)z!J%=;tK$iIpJZAm7wO%QC;U1;U*tOG2Jx4* zDgwFi4-qWa9D_!6d?0he6MDJG`w+uFILjAp$YT1!Sa654Wb#$Qzm_`-wSJICV*3}2 z^+g$jnPU$V}cYl<}j`aSjSWl!^ z6UUye{Vv9{{QBZNN`uU!`h4di)fHLqWw%_PudE)c1sZRTzI0| zMj6gy?$e$hrcxJ*nCreB70oG%XY7=pT|uRFZY6EqG82%;LS{Y?)qH_+sbcQgBX6!# zuhud1$%SFhseVtH`ONXT8z^NFWAn2zJw{J+k&@wXN^Dz! zS~j}1Jd@~rJt7_LQ{6-G;LCAHF}IW8i>&D=-YJk=>%~DS`o9azy?i!Gow_h2fXLfi zWzd4^+h9E+&we%r@$Wt(`qi33(dVno{dMY!44SjSiEvIC7@#k5 ziwURnbSjEIQcZA(PXdZu$lS9B&%~guJD4@^{EP^+;gcU}o9ZZwmL|y(+;rU!xhowc zZF_6XMvASB4aYpjps9|`9LD+G2ddY&>4g8_>v!r?pa#LosS}aIC*~cVBZH$*S%1dP z*ZpLX)OBV)aH66o3M>gF`m5GupxehH2sRGLK#d_x+zigWqs$VS+&HjuDaF0@l=Ne# zcP`3{Vd7TZQ;}^I(Y+)zTEmFgpw!n9-LPRe;Gv2vc}zT`BOEBH!Z9Lo4!p1B zBKJjRWDFTckHdxZw^PM(X{%Mj>zkOldhrV{BzN>X(O>5?9c^5~%=hAAhoP7s?V>X{GyOZbC2GBFGtcGs zcW0vUg-o2=i^iZOw>1bSkgic@{ec|<_iTwavWxbE zj@%W3cLs7O;(U$${NBzw^f@Qm*y=|G_2;mn*_mhwe?H#0uAJA6uA}U{avbipe+92Z zAqzXyHv0v&$qU?eF@n}vwPu?vDJ$~Sb zwtUHFD-AJ3iZ-?=FnlRHs?h>nER;t1d#%{-N&-;7E&Xuru{fTZM-Iv#5(xP=*Ea;e zmO@s^qtLnI`RqIAjL@QiUMR?a11qex7xIs_hpU~|+?mhVo1h+0wky7McjJJW)|uu;22W5^e3uwN=9EUDpp zIW40;*IcIJ&AYL0+?j9DbP-wkutf2T~lA-H^Bx!gXh-&F)`OZPq$}Iz@MPTz-9hyJ zSXT8z{M>0JuSF>gZRM_`diE({EeJ_Qu`MdVUyXR2u&HQAUOlCL=rk+!dn`(@mx0z% zal9a_0QACF2QJ=I;`vP*hpyK)P-#WyS*usZq8a!j@q>GiM3MO$-9aoxpA-tyuk zv{Ap4;@S>nM>$MK`)zMiu1k8dEANE=()RYI=N#drEqaTl4j>k^Q|OMkTboE=+KD}(ISUsIFv)!8=u8K`@x$iZw=ux>V8 zo6wGj@U1ENJe$lcbTsiP?%!U(t5%zdrX}=2`R69F5B2m!8>c(L+I<(w&doMJN={Mu z>(~-rmo;6FaM%-E+_Zu>C2A&e+_MA+&EfO>R;D6JdnEDsuzFFJ!w}w{Pr0Z(Djg5s zUdnUzPe)W)9iHF4f;VGG9O~E09OiG_TrPjw4xMOXVIG^y(}!&IKI9Z`Y$@ffZHq!m z7yQwaJSBEPs|>oSa*uNK@5P?>CJecq%oi$msFhEpYlivK?^K71ym{C5cq3_-2=M)& zTRJQMCKZ3l1IA9Cx@qCTKFD`@8kFBy%s-Vdj|$D6N9h+Pv)Pj` zPrchz^w`-C2AmyTx;Ru0b=9ehP8OAy+h5?K(OR02tu}~v=>c7Hw4qMaA~NC$zT~3y z-FM)UfJ$Ebp?IXAEd}8b*}NQnAiBS$7Vp_#!7G0nhdTLFA!~KsCi7esG>Vspb>5Wo zzKu>puN*=}E3598_uW9R?;fhaqcFsan>H2km0IzPIjebgvEk_1H#KU!!wbC>-5hje z9FMbNfRA3P6&J}}caPHnH)4h9}UXMgC#Oe!qJoO%FD7I1^dRJ=mZgzJ?Ns$9#;ZY`OW< zkan6BTyxLjJ&6rOIfw6Z%D0v2=_Ti)6{^Mfj%p>Z<3KX{U?>I4$7S;lYz#y-^;4nm z`gxlif>ltwX9KnB)j8HHK`a_O@(Ojkt{eL(o`u|YMMFdJ;!Wf39H*Y2H^82~=JNWL zWut(WQ=+eDNAQXob5Zl<1K2i`$MYXN8>K8Y!iC=Rcq8Z0wUF=Bi!|2^;dy_|MYWb@ zqL~kB%l97PqCv&Iz*)(S=Qz#_?Nsvy^MhYY4g8f*gq10EBUpj8hpyrGdY7F@a~3Xt z*hJ5@HZQ>a#`1WzI%#Ng`9jL`8<%zCdn&4pRECHP&b(K_9%#KnE}18&-1x?+-5Ejf z_U7xXC{&w~Z7hUKv0L1f(`G!-F(#;73R~u>mqUU*f2xh6d{f~ z`jUL>|FHKSKv6YO{wN?x5CaBO;sgW}B7!0?_W&Xi3TtVH_r1;K>b;5pzE^jm z{K=1e;o+`JRBw@YG`tn-QG1RBjs@ON9;Kf-o&&wCLn+Q^$b<`DIG#%?W8rpLe@g!r zk^^s3fR^=m*B2sV=2QCKjCAN@lt$@ZJ6A9j-ME;%v){tF%<`smKmD#yQqJ+~C6co) zYq+{_l8uAmS*eug!@Uxweo79-j}MdeAKU_qaf1hG_~j2z*soo%e9#~ zSB^3^8`e|$lKK?5q|Ln-Bkr6Ak0WMMy7rO`*nRyH#XsGm!JtHs%0J{W7R0_BU2AIe zf7o`N*mkC=AGIxZ8=23XZ(-y<-l>m*?4{PUoqHS^zY&D!w)Pkf8eRTbpxtQ$nju5z`5-e0&r zynB+CD4vId+ByF+bo zEQx~JB%u6RIoYto+>^$^e>)i;mUO3d8>d`or(lmFeo`o)mF0a|NVd8{5?PlDm(P82zgO3Hxuy8Y<-aRymG=Dy|pa-FZtEE(@Y?JRc}f|>=F zkBumcg|7WgsGNWsIpA8}2jy~dCpp6&Ee(pzawfsxGH(B(a-<17bvL1Mj;tF6<4JB> z&VNGa0Slx0Q5%?q9Qc%Zh4Xhq9=I2`qda$32LgXA_g+kkAo8zzbZPXYJfSN3aJ%gl zm7^IO1|59oQ8_c?#GsY&h1%J2bqajE&+Rp*IC_Ecr$kDxYa-t{V8&26uatVhC{wOp z>{e+&;lhrT-cmUpG|FC3`7vtYul)qV(Lz zY-o$&#yZ1}Gd8lu3c?ii(42;-pC+m@BNKNsY{tmv-PPLI*v&~2VB#T%b_!;yew%G0TS1}I;>PjP%fBz(^CqCEW< zcY}wMZc=~K=I23PUu8CZ1@ z0568C-`OLRLA`$?rI&V30Df3MRxT%jw11;~ZV#w%v_CAi;M$(-{&+Z4$32&ugA<_N zZ9`gi#hV<6{=lQQ`8vCTY11$&XHj!DymZxtt9onrC-r<_LWM4@&soDiaNQevT>iyC z@7eq$tzh_S*38rmoy^}bdK$Sqbt|L1(1P!KI+4uZwleB91Noa?CxZKCB#o8RY45a_<wj9EpVts;&`wz^c7 z@+h71+xr%=2H&}P*NMe-vI|w*v)-b^MrLB?p_E7Y%Mb{?afG&w>dSdBwB``CXU6w9 z2z9+nF%uF6XTEWLGl7f`y&r$0{1bKa{=$mBge_c4%XaLP3hI_z-Z)yB*iQB-<-QCY z-4E_h2&Opc%umLlNtGX$^n>rkP&kcyE+<{g0MD1) z`*#a=M**WAM&+;Bo(b~@aeY&?DH7({aQ5e}Uc-3Va`?|&3f`E~0vpdrAU+EY!=^K5;=`97xYc;lW!w`m_V zpP2`rzEyTnrZwZ55fMrk^wk5Adh7&I4C z`rfyx5Tn6A zXqIsOS2Ah>IIY=0WzL(H0;}e5>kiGHU4iu=;aoOcBeC|%Go2Ub@Oqh-@3TfxK;!zoYx@oZ4D=IUMtoC_dE>ly0v5Fy38KrLSqOwPKGx4!INZbDu4be8z{WW&8tHPX2MB_L$s`Amw0I0 zJ%RFUe%}FJ3Oy;Fc~T#yn{$13&sI}N4&>In&u0&UJL8gQ*-@v-9IVom^6$4C0U=vB z{ zb}$#WtCAG3do+&9u@CDGep}j6oH9QUw%z4;b`++7{S7XjS$A?FW)e5f+>z{MB%`@; z*j;T6bE>tPmD}GIUD*xf6NW z((U$8bBcS;p0pnVJ+;KtmvgT&V8&&AD*qta0}9UK+FnYvCPauh{_xX7;OZ+b&ZcVq zP+Af}WnRgB%pAPH)lur<88EhcAcPpS@gF9r0*noWH9>9sS)Em3*50wu`1>}0nwlQ; zJmLtI*5~*~(#*kj(qOoLqk*rq!4@{P9}MFB2EONWTX?p~k=(U(jvu$o94yX^g@B$d z{DvnzU_+)8)vH=%hVk!XDV|?`oc%?f2XY^c5?&q1j^x_8?|Lhk^DvP5XsVF~YYR$g zeLW^~6Gb`GKPS?%UGHvT7tfqZ@#MKTS&Jin6xWT{Mn#^`zT6n{sO&wvPs5e+bR=i& zchpRw*wpYVyM@QuleDN-)~=AN(_Z`bFh`b3s6CesCc~WjKk4&v&OP!ho2N=`+fMR? z`)j!IK}yDlS0O7YfBo&$zp$b&`y(ESlI_9^A`F&o!0HYD#R z#|J;05iNPg`Bki~4Rf72n{|u6G2c&eJipveh~|yp+CcxGn$Qx((W`SF%7SM^QaLqW z?=x>722gyIRmE%LxR}i8@}Bjd#f@odog&%h*&P3%6Ze@_29v05s^mGDtTvgJjlQFT zrYE@Z&GnKI_PN$fd4>w7fk3mBV%fV$*zb6Q;x$cE0hgOoe3z_2%K2~U^K0z`F?^Se zqI6#OY&bjJh{p57c`=wx;Oy@k^i0-s{GT{fKa;f!dq&GfJrYBW9hY;f-za6LF6u~a zb0zD_cO$uex~MD#GHtF=`5R_W1I++air-b{z>tw#n<-szi|t&`%?H}K1%dx6RVpX( zX8<5M6EBbd+FoQnDLqHaMkK|6PR=-rSMSIo>yGmjtBj9<_6oM0`qQ?p1ZMWJskvgtt}WB>tAX{=?le9VC%&_`-;;i zK=DeBXWRH_*%I$R?;XlLw$Zt>NH$7!*SJ)fRqY;#F-Z&Qi011wS|*o3o49h&JxIGxud2Tlarg7s;{h(9KTIETUe{_=u_=!eQJRD6x-}p1FyD!!u@a`Np z-!LtC#`v^z5C?+YqPT-`NmoMOa!9<*$XsUZYfaWQ!}fq}P6xbf$co-x=gT~1}rc29#F zo49duaF#Z_*pooZUih(}$^XvTkblS%3U=61`n!>XVbNl)t=5N{F%56IxP>1|VEq2{ z*`XhnFsCHkn)kHcM&|Vx16tOP^#HB9D2iX)Z(&j&acx*5ZZR{YFK5GB#}07cft#Nn zH}ZjZMcpaC!Rc{OL2^v;7%l@fSiYSb^XJ}Q&#V-1@;}}2fbA*9lt+i;xuJQ z_afB}9DbJfLo{VH7q|DRzHocIjK*Q{&3K4@!j0!A_`&S4NByXr18W&5+LlG}*UE9s zwZ2?D*9S4MYb7^-?yB4s(ml9%zVsz`s*-h%+|J7WQ8Mq*oL>9GZL)E=W#qK)-RaZYEdX8To_AqBcxHvy;(+1eX+1YmAMPxaRi(&Uo z9-yw02TvTd1YLgr64iFfgPyKh0?p#@qNO9UAgozK(7ec>k(Q={YqYAM&yQ7%3pvj; z>)mg@hxQ@z4T?B8eCRhns`(Iec6lnf=T%h@=v>0MduGAF+ZqD%Uw%wClN(HkFj2@f zPeo7jK``rMf5EI>cKGvRH27QTRyw3#U>VCqux)h~OzN|f$$PE`6=ixqjocM z-}jjCibWDA%CY)p3!TePR_c7U#4sH*cyyyiAp1_<7c10;&QaAutx7+X^JxF!3GQP6 zB^tiMi?=;6{F`T(*6_6EE7YYhHn+W zH4|jtehz@?&ka>UP%N@MLeF9OPzaG?`^%uHjj)ft|y24kxgMu~M-k4kUl8HDg5%xM1 zhPEnB@Ge1Fm@v>BdU(6QBa=^p<70#nJI4tIB`OIcSDC>8YaQ6sGfv1Sd%N8t4m0uX zYJ}&m#6f?yE9~e!MYyc9H#jJ7l@no$3;A2^p;2v@COVB4Gy&^J9^ zX#8UW=*K#O-%1rBbJHBwm-m6lThRjRNzQm{%{Wlrb5`*5baybY@_{R5M+Dt@y0C$q ziC^QeOHfpx1p_@q;LmCbAz%P}nA9CM-U<{BY#Rsu*&;YNSyMPzH~{3fb^K%76J89w zh}5kVb!=iM@683_?1hrOdo)=+oDMx6j1&YF?PlV1W8vmi-O7CjPqSxpLO`ouv4HLM ziFwo`0vw;TuRM_Xl#RMP74ny43UVxOFyU?faK?0p;B8TRNLU;WcKbCe-4;J*HS@CI zf_0N*q>C?Wl#>O8C9V9@X}-*~#&OW4!e8=jZFl^r6#!d*Uy?`#>Zn+@=dDcWSA1Qf zrZk0J$X`$7&yJf4n-6uW-1z7wdvm}|X7I8QA#e3m ztbI2glHXTK>UwlUt7o~eaao}xXpss#Q(p{wiiYv|cQ%P`|4IPKdk;Zm?mp&A>j;>e zwV5~Qk`Rx)wS|E*x(Hj82gBCSxo~0IJpRrTN{kbbeFbNCLE(Tp=52Hi%pO?B4>{Y9 zk=rxpkH7z5xoySdy~N-XN)@M;r8nNq&IRlDtNCujIx$npd9vccI)VjdvluVk(GcW) zL!h~=H%uxOL-UY#ynY))L}N##Lgi^wfv4FTX3K(`%q8h8;qij0xZwFja2$V1V(>u& zd#Z`S(%)XPxBYI}`d;LHGs#>*r|D0bmWgU$r-95ISy(QlB2e?Nf&Q)dnVq`atCHc@mA5E|}_=1HQ+%OD3$cVC^=< zLl>j*f>$$1-^#Us+xligD<6CK(V-_Co#-cg{eBGWRSkfB12+oJ4^)SFZ@ggE&16Yx zTUU(Lae;GY5?iPhG@i3v6t1}$EmIGt@Z{~Z)nUEvTVz`}grQ&CvyDT^@1a3JM3!1Gz zF%g#&A*+B9%&ytWv|}^i)1Y^fe!ueB?z_p}=f--;?k9HaO44VWau-T?+cepMd@)qS zTT0?5*UETKp)hUlGJ%@gd*&Efo82BcleaMDjf3*qTv$`ML{i$U&Gz4!1D$lX^JjJ! zGG99eLgpc6v`Wy3kg zi~MLS7iRpKX!!X#PSCUX0;9674>X<}CR7e~hEi!bJbIy7Io$d=yVQ3wbQ%6gQXim# zb=qH;I$4ph^!*g*ww&a$=l|v@^W#MWNPBn}CoGRxRn>6%Wg7VNdI_dmEoRmii9x(c zjo+{D4AFT~zc&khmUlds+&H;_%t=0~Nit{U$sRuogQd|61+z3?GGU*1@T$y7xX;lQ z%%-Np+6TWRJ@3tDa~6rA^V44y?b;{Hf)C|DN%&U&gxP$?dTj!@bkwcPD?Gs7^9lv+ zS<3_)b>1^(?b2Yes)nF@L@{ghAQfaE)CFq8RL3dwmK|i|> zvRfoiardFNVBZi`nGeYwt31*ce5&}?SZA3B55{W?ynDQtS20zpxTl%p9~3TQ`J!NOOui)O!T-e^y36HQQo3fN*5a8ohI_Ka_~1Y)Xs1{3 zB`&KNs{!d?{ACXRfp{U~^?~f8{8-QbaIBc|y5SG{F51G;)mwGehY1y!;<2l|mWk*I#@}cTK^LgEG>NBnCDPRzJl>efw zoO!Gq1o_YI2t2Knp~)}>sa@*Yh*k*H*YuoI35w5(;@E;Bqyy`8}|}Hw#kFmTb5a;l~=kE z70N>K7;1y_;+~jSodCG8yTESL0Y;7w5^Vnmvw!Gv`H4jSJtE)raUWVX!q6GNZrMir zcyIEK`wmu<(mTgaM3e2@`ZPdK4Si%uu>I!2HBI7Lc6hZIRE42s{yu)PsTaB2^-LxT zz1}Cn!nSw(_Mf&eUG&o+&*}X7C`6V?`b-w_Hy6JEP8}RQ1$Cb|E>hHZ0MojA_SbpLk}1Z>)g-etmi^#^o(sZZIi+JeJ*=Lgi=re_@@7FZ`!Q zCU@NYMD@FUp!cI=f&V`<*-^#+ucyzb+k9|F&{8!@I zsD;Zn=3ENEOFPC>{y~`?v5K6doi>Llo37PcHhy(1%vA*eGwviK-VzMo4bBUGto^|p zV{^$FVke$(y#`}a$DO|lH=K;uJnqr{_0c2>`>f#38rA(0AU}Enl|Ls!2Zzt%_Fjiw zyU4cRkq3HXpO{4HH;Mcc!XeMLLLkvReV8+>fpFo(hY)<_iY--(s3QGN5hzp3?PEvsu4%Zl7Y4@)Neon9M`AN=$ZpZxjvo z5yQs(^s<7ED`j?iT>fXB^|LGz!Rv$Q3`exlsR;-i+aIsV7x`z(vg1o zhE3(|?N51)r9M7dtcT_~nXtVgbVHAYk?aq`)3|)2!OXR`c3RFPr%k?F^=9=gM#qmE zXH=GtLStuc9M;|Kh3CUZgZU;}&t>z%Huh|M21G<0EDZ{o#flkgDs#zc8&q=>qU3uoeYFD&kuaJk?n9LIWOhl_?zG0 zaF<=YJPNXse)FBv@35b427=m@5Bx^ccGx9u9E^&1!uQbXfhME5Go?&ZEZ+3qLUXfg z^~8Ac7q@pHEl9z&^En?iQeUxfg3EoCH=htq*u=G;1y)BGMLGV5KhwPlwfkaJnx)Lj zV|CzdF1C5hrg-7l44kCEW87mnr5B&f#-CR86tA6;fKA~eDSlv;je$1YnTH0mOx*vT z%a7fG}m^gAyPG0u#rWK;4WFJ(He?AqG(ioF7B!4ac+aK{J<^j_f}SYvN+4zl(-s;<0A# z%$0d_HfHhn(z(h2@+}$m2*=+MhM_HazgI5*X~8*B?ZZ%7R=hJ4hpFtMxI`lnFPU&W zHP)YH3(~nbJUZ8joubLnh0#A{pZarj(=&RES9>nU>zuuX$sf+~Seqtv%B@%^)D8yNjXjJ?UaQf_B`!veOI^iw&GZvAOj z(}B}ls;1BI9XMT<-QUQ*HgJ2&@pp6avK?0!&j(Fp0~s!tTf8TlEhG6*xg38V3X`$9hV$$Gw_5f?7I%Kb$SnhpUE=b$iS{R0o$Z`G7h2}BOKfM-vaQ7#SUj1V z!+7Kcq3eBa?CNr|2bPuGp>=wMyk{SBi`z3DbtW4X%l?|lje%Rg2jjY3T--#;qh$Z! z;R+ZCR+K+qlUq~F8kUAxcE?$HtXehW@Y|}c)VBS;x!76Sg~rfmt`DwRZbz|)#~}14 zxehtMQQ}ipDX2ZQQ*cX+BRn}9p8qP5y|~Sd;ljaY=zM~Uo5Rj$tbGOdJnE}r{FlFq zw%Ny+Q~3kVIpStpZftxNBgC3yKT4l_K^s$IxcwK^Hb*u#lbdf?F15zW$&)EhxTgx9 zzj2KEWo8(MN0Tk7Uk&|paDz&3%5yh&G**)wl-!s6ynXD8GEU~MnGTHC9nP0ruXdub z>p7mC*$0@cqytor$A$#7Ah~aOS$F+-+%b;pzuWW$XnBfzM(ioQz*-*X)*Y=l1v6%I zGHpY$Ws3FaB37nyn#mZL7obV)VKz;~(Wkim}3Wo zSaEwR#jR!RVv_fk>+;?eFPh!Twe30EYuM5Nj{a`yGSMhYBg%8n)g9X}=4^;Ryp(-3 ziL1NBTaLK;i7(}8s_cZrUT`sqRJy>jZWAbd@=6^HdCAG_?s>$ax0TqyHk8~_Bi}*$;p4TelsimGar~bdpGOao7?w4J#HGhX>)u12Dhi; z?p>VxLnoK8Lo>KI9Cw^8yX$g<)?LEYJp9z1+b6PdX<}_Q|D^tQn-Yw7-*E9vX=`G8 ztl;L)(;xRj@t?DZ&dnzrX07GMnQuiI=xXah%SL?6!n_!6oD659n1Sj;sr?=**7(_v zYY*YQ0gWTM`QDL18aVpTUVP&0A-I*CYmxgt;D{rdn;KJ`ImZoOlXueO^x-wT*x)~V zOm_7yB8`Rjsota&kyv$zQ3;KoF5KmB#sbbQ#Ai(yyCEv#4R4d&+D z9DeJ8skr0nb>`5{Y`*mARJ2>A1ZfLa@S7(Gp?`Q+FxXwguO#<8Od;o`42$de4O>Rw z(nwRd__Cf~5;+1x3c3PZuHk3ddt++468J^0;CoCD!U6B>P;T?YhZZPn`NXOpJiP9U zYX}OInq~dVJj+{F=AnDK5zHMODmc-}9n+sB!=_YMp-pK8d*-niUTIkiKMs1(s3_<1 zXzqQAh3lj6M~fD_`;r&Y=|V|3SWC>)4gz@6)`o zdoIIvQ*$rxJ~tcpRu?cI96IpZ)n=gg%W2@=$5OZ|?g~3anhRb>eTC)=wb(i1#n9GK zPdKk*vCL*o8vO8^Ae@`Nl-*Mo3tsx6LZgExD4zHSEBdnFcP8vq>me*jm`uLAo(M~t z&I%*GZ)J<623PVuo9`nYFdbFT@xMk!;-Vjc?B^=$@=I!27=L&tqxw9PKdoybc6!{K z`g`u8Cl#_~lwnfHO2`~ilESkF&^(C4l~?-Au}UY}mH z>}&oQw0&bmaYff**t{wbZU*QIH_=!Y>#*0V{Luq) zr&D1t+gM^%e!n#ncan9}iX)?iJwL6J^^I(1)qdG*NMfd8=5iMht2PM=e+y93B?d;F zuo52fZ({R1Oa{XVU4@G-so;#)=}^>rtWZO%h|Qa*M(s~13P7FGu`oC4t>8`{Jq&;4 z2}(zw2x1QQ#^X+|U_9fBK<^_D`$Pvrc3e+kYtc{k*TWPrOK}tSUb&8a(Y8b_GYDfIc&+{RE{CRB--iy2;D!b8%w|`L{9`*ap+}x)sSpP5xw+~#;elf2vTYokM@kAn2geaSUV(mu$iG44mlFB=#;LGf z$4@99*p`cB3%NdC?KKFW*3M_=4*gyBA|V|;cZirv@1(p#%d&B~$8qLq`C5LyS{&}z z=Yi9tSi$mlu4t8fkPYmhQ8vXc9(U%2!eTpPVRraC_OsPZCZR(kf5)n+7{9~>!W^On zx5G!_2-}xTx@s#wt|g56E4N4PuiW>4@Vz^$nDWQN_~w#SY&vp}39~)PPihy1Zd%%q zXT=vpz4yaDoqgbt+b_WbZ(TgSeLquBP{_Y}Bmt|vy1^?GMsTp!3-?ar{JNSx2nTk} zWWV>;FUN5+u%vqwv(WV+Pn1gT`yywDYDY)}kJM~XRVx#UV!ee2`^B?QyT?QBj^V=f zria+iyUBAW$VfOFM#{RBjFkELtCa8AEyikVRay5FvNDnjN3Tl{7-7%z{7uf0_`QJI+htQp?po(?7iN^} zWZw3OTr5%(f=f%fAbpVwp3t2JBL-OryYsHIFK#8n-ifZld9NziZQq??)X!6bp!=qn zVz-)2Pd`;QmfYE*_7Pd9qV{F`edBTJ>fR#bE4@v|UKHc0M?DxLqiMXk*133o$$Dn{ zH5dNfMslxRt%$s%bwH5zu0QsgJsn!iK7|v#_wIlM9m+@Ur?Kh)_pZd-cnCs9X$!#BKt!v ze}Q0*8H4Z0H%bIxD0r$j5tq8f!GznxggvxK25R9`CLy_*Z>SrArn-ep)}d~EyDk|x zFVPMzAKM|AoiGS3ejC8rM}Y!s8}eP}87ZRhV{=T57mCq!vKr(2&5_r9F&Ag9AI6NI zS<1V8BO5)`G(FL~a5GBL(;INUAWDp0Pn#Mngg9q{Y1d`E5ajo}&AOoeC-um7)X zd}j5WaX5XG|6Ur7t=pX7(T8J#j3_eXXrTSAUp(et}^AeGzJfo)KmD zYRA)Q%)`Dbzc3H$zw-0XO~HhO{&3i4f#8NQgG>D4VBC*k!Y9X%vSi3(9c{*!>+H-y z(CE&~NtC;a-w*0N7sd#d%n6b&x`xWNy&5{~n(PnD5M zFMmb8hgxJk9Q>zj6(}`YV#$#zhlfXRo3QW1*#74#hfQ$Rg9h+#A5TNIwXV!-t*^Xwf^0nQdsC!y ztb{jzejfI3OTsAzHG;DlHSCG+o|s`ZRd94$Z*1zNg!5IT{MS`Mh_A94VPI4FS{~US z(H24TtPF{B*#Nx$APO?RS5&GBTUbRo^?oC8Xg~jaqYP7g6zYSUT*LTIx4Yn4ZSsw4 z-3bEq>Zh!nM?R;L^PJQrcbT=k=D+Nrj$39;$IF&$1^Gwzu<^SBQ9Wv|V0CmmeB9Ip zFFw4^PmA%vU+w#_Cx>|Q8rJ9FxmA6^yjer?`zWAR#U!u`(66*>Qpec(P-s1OzOs(o zSCaO_8IHT}s7z@!MZY==7+tZsa)6;d#qNKwqA!tO#(+uk#mYD8J+W+=EtsD3tLz;$ z7>oJ@us+XM@)jFs;e}?a*mI;{xle%;j_jt{}UOfi=oI_z$C%?)?Bi^&4Za5;=cnX3io1-(fGR{HRnI2d2lePUK_>0MFn9fBis9y3`xG%8e9N1$7o9^@@rUx6-Tv15OL>#t`?oL%~1 zScD$T%UxITYx-Dfo7*4TM&J3x);U)4?KFbXwtX_&(|0>h4QJpU@-F19(HF{}T*yGZ zQ{UJFA4>U3mgKI6OUIaVU!RokGm68>N!qxz!!iEK9e((HZVmZP*3EM3r%5lc zoLa>NgGhWH+X0uToaAfj_~FmkQnpB<#-Fw(1)sIQEL#3{PPs{C9=6Z#hp#Gn3GgF> zL#zx?pVzx0p% zZdz(6OWnn{-WPz$^+{OKzgFO}w3a=&On~flZNcT2E;vvrj@`PemdEO6;?b2`8^`Zn zZR}3=t%B#wX3nq|%MZ9_;DHERJb8MU;8^istlnb)?ZfLTek6Ec&tBUd;+M`Z(;)o! z&1W%YZWqhV(=sruI$zYfYH0cLJTX2c_AL8j&l3fFVfP2w`E44!S^e_x`^he%n=yCF zvaX5IKgft#a&Aj`QCkkCg{#87BX$+T3Dw~5g-&x2WAb*TK#+bkTg zF^Sy2QzdYDU(0@NHN+1Cl?6Vt-SK(N2v+^Fm{;OP?g7i(#|#{BuYBF_1k8x=gcBl^ z%udrMciIewjtv7O%{8{DvN8gyoR3uwocoylwCpkav1kr|{_+UCMsnZ2hqL&L!=f-y zeV}OVUgh$FV`AKLwUlW}y3POn>vj1n+ZdeNVJJ-eJWA5?eF&cGeuA-Vd0M{j zW-R(nv4xmMKgpD}gK^$-3wBOW0I$g*2RmrBFdxqTF7Na_3Oj{-lsz-oBVzKCGhV(oOE-MnmEcCd_aui!;EXJIsRgi#swxcq)i9EK$}Fg-rCmPeEMz==tx*ha^( z{QN1g=oWf{9X-#3fBbYT)_iDTMl4gRIKDFq7u6WS(Pf7!o;`KL1KI=8;+c`)dyNAQ z5S1}4r>>VDACrRK$I4la3@yHkP6}S;?-AWuolvf%B1Xq08<_I)>*f7oQqbbTATS)Ba%^(A+vO{S0!uc;baR<|IXS9j_ zrI;nG`;C{Z22-Vc3%-7 zFfNN1xsm>JtH!IU@BEK4tJ48^cSu+1)#s}CdQ%6SyrH+W>cIqje{&5pcjIwk*Z!#( z^Su+CYScE>-{MQ|dohG%9rcBUJP(ZWZehk54y^imJqiyi)i9Z^F;dy@B#N{CU`1a# z)&5{!rdLT$*9PO@=LeY&8#+ss`0==m?1Q#HVj|V_9*eK^0QWxVBRw#wAJ$LU&t`SH zUuAcd+&BH>D(mg_yXyF|X}BpHaNWs1(v{Ep;{nr$=f@$LtKlX@+8KThXs7!F-dfgnT>NS}C|HK3S7hpF{4^oAk2k`^J;(O5Ini zBuh(bTNQ?jgBg^ITM9vF*0JY%V)k{<3z zF+f!nfz+nL1MSE+rn+SYRoTtV!P4<#&{t?8ZFxY>`!(!s+?e@Ma+jRzknZ)v$ey_L5#%MmT%<3%0)bUoLqVCCp+lR!cI?*2;?DeFOpoQyx^ut4$W>QfhgVt|1 zu)oz$R1FSDLA``%>=*T^YOwVsHpem)V~1!-%jdjj70YJW3`Do9X3~uX4%mN6A(Iij zLwHm@gW?$q_#e8Wd{?m#PSrG!Ht+0$A_Fnn7Dow|tllI#R2YecS5>5mc%PkTt55D% zuuChqm#*TGMVXkzn5H8(J z);QM3Sts2$RhC+Dxb-8SHAwcWYHG~E#?)Qx#Sgct#=o2Xm%oa(CHS<%xpv*8t_K6r zW(Km;{hn2|#l@q|v^gwmwW(^jc?N2&{3X(i86e!=E)Rn|pRgGVHKaSkBXE`b6m~({ z(yAZVGI6De7;kJ^BG~k)Ry5lx40Tp%N=pyDW(PmiMX{HW^zBA(EJ^W`9-HE z8~8}>BJ5-StE#r}CVTaT0R31~X(x#b);o7$qklk^Q#8q~eO$?`_B||AKAwsTH=kt! zUB3u_*2G|x#bbwCJOhErW3nb%K8@rqzgA8CdX=>(NyLpQSE@`tY-3+m4Z~gi&80m8 zt?>N|J~qdjO5M^&;@X2sIAolz)W#(U?+HR0^tY8%Y#@1Ndz*S@$ipYXeq`U@`+QlW z^UG#Q(R*?ZA^afIe;s+-S`?43=XXT?llsz^RpT)uywxH6UQfZ`Ct}o&Y=?u~x=H)& z4a8ASi`mzc_f%E2rJ>62D>BIkovL-~^RPB|9$WZqTh(Q9N6>*28<{m*nuV{){g9ic z>|?idX{}nSIvxEFYGL2-UQ%;`KUSRG-MH%RJISy&=sAX3wmf=U?R2OH5PY<-EY)5+q3cusf(c**0SeaQz|Eu`M~8p z_9&?`lLmFQK-F({n0(Ys`tg<45_xSzx9cvvmu>(0Q%7s(xVX>Y1# zzBt1^J#$eu=#F-keN7$?^&Ef&yUe65{vzx@rkdT@zNxC(C>bwRUXhs}(5X68nulQ> zHZgARn}xSClCadlAA3*IlU`e`h1+zdV05C6)NsUicJJ$UV055^>CezWOn>}{?e$t+ zS|^LZjRwm2y;xT|zhe;YU7E(`94@V@DVl*Hn;x=v!qlZL9U?J|oNIY+*-ff@G7x=> zbTHCfU)srM0y_2_D2uU)u1qC!`^T|+8C~xO!fWKty&itU@Wx+IJQUOCKiMq?`8_7&jcBJVhjLKQYDR zS!~MTtppEJpeqAMFCp~R6FFQ!Fk?KKmK{UhcTc$-NbzEV!xZR;UvTspgs!X3@rMzt zXpbURwEsV&EBgLl;Zcm?f0tjeUKDLpv_Vn6BELf0VE?=P|FoaJ(Vxx#EAkcj74$0h zQ&gb;M}L>gSD-8Mg981(#IIl{{1@!`YphU+kD}hc>`|1j$gfZ@pb-E6RK6m=LVNgc z^Z#cyD9ZfLbSd)uc?SKNqsjl5|1YLN`8N*#H?)nmr=_xcIveIZaUgdybvhyX^!&Km z&Qp2NNj#6?r_WQbAn(UicW7ZeR9n;&pG86R+ipkK`6MuSC^X?W@zjt-@cOTSl}SmAUZ{I9m3Oj8bqf| zuH)XCbPb}DmFq}si_#!ES-FlTTQ3cw6XiM$zxQ8OCpuBC zquM~MPIRJN2k}dd=tQ{=;@2Fa6XiOHUxh>`%5@OG3W-jX>mYs=5uGU4LHsHrI#I5J z_*F!7qFe{@tBB}ikEL7(@vBH4OSul>SCKrHavj94 zB6%$3I*4CI@>t4s5WkA#v6Sl|eih1NDc3>#DwM}kvAz_sK~Xx}YfXCL)EP72_{KBr zs9k3Y+uw_UjrQ8O5VVWpFZ;o-^8+yY(tx53cO77t#2pt&-HQe^7{brC5VU?3Qsgu9 z1Jg+(8JBA&7kON(W{R_OaAHnQk!xT1cNyjVHNR+rwSU$85jl9!Ij89JSPNFSUlPtX zPb%7fWHUQYeF~0Hol=xB`8%5x;))A{T#K@rc&Piv3|G7`D=Ho4gvVE_;)P<>qR-z0 z(C=71ySK5v@JC<*wmUP1y|sT#;bZcCL0}&x+06aFXSdxYIhLA^%*q2D)!*lnJLF5& zGk40?tM6?{!BDrCOo`V^b(?Z96)hypg3nxoJ%OqF%;(>igS{G$F%?1G3|dhp7NE-zw5RC8`f+8+VH>C4mmwc zYJQ)|201imbLGNdX4jHLid_u1GtIk$C?<6Rx%w^?H!KnY`K6f9fc%YO!V9DfE3ZEy z1Bfh&iEQw8p58}JCw)v#Cu=PwB{^NLLyqPAu0zg4e(+BjxnC@?pVB$m`4qqKvLibGAFRluSXNP{ zqAo=nVHHY@tl^Rs8QoJX!x(Ram|kUxT)LoP=#hKjKzf1^BvP3|Mbe|)6) zkB=0OoI0#Vq3+~u@*jSAo1|E-Q$hY;ZASh#@+-IJuQsM&Kh#{vHk0%GX_Nodot*!l zILKw7oI@^0A#QTLlrHy`{EcG5CU27z%VVQZFU&vnCGTql|GO6cHxKY{8~9&n10>&M zEAPMZKK_5$dk?56o^4-vFpHofA}WXpW(YCgqlghj1r@{q7(p;#&Jt7x zGl~&mc9|oBsHh}!!UQM^DB;`Pc+TUjx9<1d`_BEJ`_B4sEnUA=?%sLts_Lok-hvhV z*|Nn_wxMxFjrZT=#fl5drFu6%r(zvKO{MzvGwID%Hm#`few$2L(5Z?VuUIjy26i!w=u#7C4#G9)a@BpDJGWs(dDi!w=ughiPoL&Bm=k|F6P z$|M;Q7G;u*3xDk5B!gtjWTH%xAz@J_$&j!plVmWFMwCf1BrM7#84?y{k_-upGD(Jn zD`YN{uqadXoybR&Df&*tqD;|uA{J$ez7w%1Q}msPMVX@SL@de_eJ5g3W`*yF56P?? zugbXo%L*H#iALMB;#yz2_IR}lo`d65>~vU#th8pm*?r>*9Te+K*}gLsx{W9;2c3-- zI*&Aph53Kh2KSPs*h#uQ3EnEN;a*|m^k6G=`15YNVf4(Z&cz>lQS3Q|5;da{=@ll(nO79scp)>QhUEgX% zKWHWg@K=}Cqlnv;`S9%)703TC&f(T1t4kd4G0wf1#vjbVE1RtCs17lhu5@|_T5nlKEdL?MBFQES>I)V7?zqpLYX8~euyEDT+7BL&%2OZ25EgY2p$j*BwL zu9_mfD1+=;E%Fg%kX=C{fAKHb6(o*{|3`L-ewOy#WS8iFY2QtDiE*Jhts-7}{;$mb zhO1)t?-)CZGR0E-x8hF~{=eG~75&7riJe;PS$}0eiD;;;{#W;tGe*-yyZB$(|EKD= zj`>&j|1(DKqN&cLxu7a`z4`y?-2FclyQ(#R)tbL52mZPo5Z54Xb$*7@dNNw<|1P%Q zL&deNxMuZ{<%EiBUU6M&bM8qf&Ck;MzriyeDz1^mHS3bj`$NUGGyNam-XSoQXr=O0ouMT=C$gVn~ zFGU$-muRoF{wKRcKZtxd*(Lf%TK|(>qTi(TKiMVvQ(FI%U80|*^*`Aq`d?cAlU-t5 zr1ifTFWO7d?_gE2`}d6!*n&&5va58}Gu&!1&gSn@=bA1V@}$`4h3 zsLFw=9H`2HsvM}wfvOy+%7LmJsLFw=9H`2HsvM}wfvOy+%7LmJsLFw=9H`2HsvM}w zfvOy+%7LmJ`2SB1TuQ5VK>Ypt&D|BPs__5)emH2q&w<|e%HH^dBwqc4UlBglf0H!6 zxnF2vyFRNWtgf>*ameI(60Q@!HgVg83T#2x)U5)W5WX;}0_zj5HKhVqk6-J^|6E&> zu%d4T&mDEvI?fzeA?>j_bB>4q#whM>2X5G41a#L{Z-9>WPA9Bc5I~2*+kbkN1jN&+F4rRtK(i<9X&q; za^JG3#C-iXf=}R5-t&EtCS>F=h;~@OU-WdxfzDguNT2E4CMybinjko5kK(--r{L^f z^gX+=PF&xp7*|!R&X%-N@MlH!x$gu$rW2>leGZ!N=U(kyj-cfqT#b>jQ70KOvQ zwB~nt#rM{)*!I2nH@vfc-;2%PERoKb$P;YE^Oh3Uu`m>Q{D0yhjbwE8R3@8I>d$&y zE|Z?EE~^&6UaCqZysl0F`(FB6!Zqp#uy2*H$CV2DVxsTtRzbgl=KmDh0yC_F?<6C_}|7kn+pTYmt+W%M5A6ItLq-`|R45n|e z{zv#mq$4MLH7lOB0mPm~Zz(tk3-w_|#=B6!lzmlfG-vshWgyulnmiHOT+uy37+3|EZxB8wY z>5w~p2Cx6LT*7@fsrc+472_T>UgCUL8ee;JCa+<5Pr?OLX7ccF$r2u4;=xb(Kag-j zXAiD^qA%eZ7XG~c-c=GF*L)%0HS>^!HQT-UmOeTX{xI902Q;rO;ndy!{7RG#i1l)A zraue0s4L-IH-Dz;)l0%Drc2l+mqilZ+s2Q1j@TjL3DXv^cU~1ZdD4P^s5M<%Qzr6! z*{L`C`lXJ9zqA<3ELT64uI<-%#y`;CPu?qyC$E{$e4Boi@Kzsp*52G$y0-4&fz-p6 zah<-a6!k0&r9AyBv3bk;AoiTxPC6{~NsffSAJSr#dy&JTWNCb4f(|pZxF_MR{dC#& zPj@B!B3_pT?z$u4AJ+BR+us`{yzh|-E7*2I!VkI_vQ90-Bpl|{k{#1tFJX)GE!k)u zD&fuDS~1!6+k&W1)RlH@KuK3=d_kl+>z+AP!isEDR?_>jM6)!f9ShI8B;lc-+OgSl zE5?!L!Mz6#64ox9BhmZS?0o)sn`xMv>c^{Ptrv2aeA3K(>Cex0oGAn;>(P8BlL_Je zd_=!YX%6ZW9KiGRPfByv5qB?c=-WV=A_pAF_ZA{{^Iwg|JPh>;JjEG*V{ZA+pqSJaPYlU z>@a?)g!wWC?#;%{8lvg2^e~KE=*>IY)%;%hKY@Y3$p1~!e4-Vr7Ap>H>`EYPe`>A=W#OS$Xe zG>w^7Z`iJ+@00Hxi{@UVU>fE2T;Dy|@>2)<61ui5X-E9sh6_QR>(0Hb@8EB?7~UM4 z#c${C!H4v1M|CI4+m|h|UVrJCBH5O)ru;v`^L@OeoS!n(>ij>0kNH)+6KUI?Son`{ zqoYPheS?3sw&XkWxJJYtx$XFjXU(K>qal{OY+-W=&!q2DuhXlbKj~n}hYOa{xakNB zp0k3sBXq6I$(-LjHc-Op`U-yR;vfl+ESGbyTZ1Kh`lFmTdOSqJg=uo$bB;p7Ujr@p z)5S6ghwZiE&mH0kBN1niJO0XgKUIQHgY!GVvNu@^r~QJ zV#lg?=){h0kU>z_`>^NGbXIx(`p?W+R^cPyWPmLj7-q%R9b2dnW%b!Tz`WDW@sixS z&ApDd4Q?lmCk9xUH{S0e;nHXa^No9$MDui+_i^=-wh~@+X5R4+vr{BJo$p=%UwbDI z^<3#>#qM2MD(RWkeiE}BrIBdbYF&hGJ{={RsEO38&rXwQro_0jjV+H#G<%yTfWtNu ziDuE1_N>q9;S$ZnvdL`pgl!T{Qm;g4?Wrx%yjs|SeXC|G(X5y;mDTtaAkhT%*1*Pr zpC!K~P3_2*jWd#H#zakH>l%;aANti7Moz2EjC#)H-weMy)>v{DteqG0agCB3J+(){ zg$qsimh*DK>Bvy#8leLhOX>?ZXr0jiv@XQGt}k?-qHx#2Mrip`Uzk)Bz((7=#i?&C1l^-kq~7+oJ}CCi|85)^I)*RXMBkR4c^;IL zv(P%(lEp5{}VT-uCeLo2wFsd7Gx`jIrIL%>8(~ zr-s6ia6f1xYsS5w^%itq4rc3n=|JO|y@dRM{_M`-CJw1Ye=IH7arG&0VPO0;*7sT_ z80B#xt+O4ov*^ScPb?6^wtaz5r`>38Zjg{n^z#dX9lOm>NjOS)o_v|3-=3CpxGoit2e{5X; z3v5mw$F}S^iS6oiV{=a$F|URp=v!kG=w6w{#@Y75kHR#j_Ph<_O^H zib&AER+9&M*|J43x$yLn8vR~QWmjkKfUe4O=t6jn%PNrHGvmSgZJBBD8aVZ`2rp!R z1obRnjiPJuHY-2E2cK^2^@rOy;QLgz<5*v~scOipcl`(rYjk4WBb)J6`8n|1z?^+= z_Xv}#O=GjCHU`UU{kYTY9B6Bv2_u`1P$;h#kAOv+dJa7mEpx z?OD%y6A#0BXMC8!6$@LvnLTjalqJl}z zh8NK}a1QI9Fy6N71_6~@max!_=QhFf1G)Q`0h-v}orM1?zW!8)Plz4G2f1Bw{LkR< zTIKL8Q_0Q+#0eAajo69716jeAvqJpPuB;>d74i5H16eUMl4vT^S01m7OZ;ZBBh9YD z=eb8$>>2D~h^`_L8kA+92Y} z*H)&lJYJc;G9S{Ji}FPN6caASM%0aB!o}E#xH8Ym^p(d&e~AAl@*y5viQ?XT(m*Npm@DVQ<sFb*@;LGQd;R_un0)#7+W%)T z`TOs+|Igsce)xC9m1FnM;L3UR&)~{A`B&gu+FtDRirM&exO8CA>dltK~lY~$7Z^zV=I!pNYonGuq z9YYCM=4lo;g*9uEDDl^CKbIvnTO#3cesfvi7GDWFU75@7)SD;a%GdrCeyGf|a&P=+ zaOEEO&tR&fzt1&)1s3B^c_76|j6dapgvI!i-z6-@pYlM$V*Du&BrL|C@<763{3#D4 zEXJSmK*D1DDGwxEnWq?k$^&U!j6dapgvIz%9!OY>Kjp#ycCFj{<@C&a6Y>2btO{58 zp(+Rd-*e!v=o^)J(p>rX_4Yr5X|DYH`v0H7)X)FYb(h%lsP{2(P853{^*#xUJ&$^y zgvB07y;8zr|D!%AVX>!D9|ZAQvHwvYl(5+Us1Hh5?0?h;B`o$o>Vpy%`!w}y35$K2 z`n7~B^A!6u_3Qsl7S#y#%O>KxMtBwe_woZAyaPv$M_@ur6|?)YAN0d+;Vvx|i#xCq zs%?0NOA3^1@lR7oF#Ul~zAD+oPYZ=U&N7}~tYrOvElY?q)#5$ss+eWnR~o<9ztOm{ ziaExN#Z#v~;+iAm&Oc!F@e}c>zKTWn{f%2ceAR5#RxaQPvC36t8`1Ur-9reB`+0{Pf zc=nK5h#;QJ(+cq}>O(Ba8Z-JHIJxe@n|)Lal*d7J1MzD|75jK<6@2fVjmJ$?Y3f-?GSb(pY(0}0u4V0qAT$qZ&rW{!{r#+ zTE(6@$+%%tU(K?bD&~4m#xK6L7Cgw$A&g}K*i&_IzUqOJPdJA@kS$8 z!or2w=-5}q?~hT#&q3F4^9U7Bd3+tlhaAM_E-LPqo(;oISKtO$6?ZktgXGqB=rKXX zS^W~&-Y!Y=LrLcfHp$q&q5g?mMyvS9lrpIGaHBAAsEV%~`vac1Hiw$yReZSTTUdL0 zI@Y`eTn8tP!Eju{0f^%|6dzIuwimK z>~K`^AzH`rctZ|xok`F1+qk|_B)ld+80~+KZw>^&S&{`8^YG%+uCSZ*IrF;|L)yj) z-d$AOu(KAQ5*C-RNK3{0EH1;{<)<`XYN~kaa|PI{b{p*4NyX1qe~aT@cwoDUDn9MX zJshUojmG0t{LzG1yzihvXsO~`jlytRjVG8|SH<`GkH*1=K4NVeANQ&Oj&~@;O?_1S z;xCn^$>DO0r#QOKY$hBYE#sR8t9Z2CFTpIe7)SI}@ePIpV5r^~%{g#nfnjuy zIewaoI|ZGAYILu<5z#EP-2(QF9zrzvvvW-qZ1ea4&xVn2JL$p(&qCNuIcEBPm7v?A z93GOa&!_e#_79e^LlnC2m^chzx|@nmsac8*71snmilZ_8=DfV$ z8pr$^DqgRJjMwyAt!Y9vwf*x?Ok$03etXK91Ml$KJ=BhTpKhVVdRw>D+I9%9M2>4thR_0v!2Nin_Bc$r{6vK)p{&5k&5IMI>fIGAGE zXyRi{(azs+iQ+i$PEVZT^c60V4yiXov7U1}EVd-M*2gf&;1Vort>RwnCf-`VQjnv*UTdl#Y)+4U%Ekj6wy#wU|qlS+()6+>jaG5N$i_><6L z{VzO2JoB^rQhj{E-Q<(#m!ZJ+JjHU--)!dzSX@to&xpPa-Ui=I5jd54LJN!M;NB|` zFHctSQ7j*_13TlzspKo8QutkPR&#;s$oz8ovQa1S`POBQ@VDulA~g(LJky{V>Gtu>IGEEl z2TUjy-4t~ps$~%v3{>%kPD6xf9U1c?TQpDWX_}3dv3Sa#y1n0P8moW7zOhsodp=cGB4)t59c#`dLyfuVF&E}M!{chvMPmyqd>h#C!XE<)!GSJYqmSwq^ zvcL{x?kYaMb{Wp4BPP=#yyI$XoF;qKK7sO)1k3{@VeZcwFdUT!o1fQ9!xVPzOeAoXYo)c8O zC+J}Jb%m%RTjHJ%(Cn=x<8=uSF>EfZ8z|!~slGyZk#O;NG5(}@`E(orWA1;(LK^or z41uE;)A0l0*TPYFZ*&O{k`DuZ--P#xQTUYRod*TaV0~5~z99dfHOL1YXKUO*HD&bm zHyrMstO=wTCGVB7z~q^Ujugjz)K@PkcL=ix7X}u)XYfVP#FL*(@XE1#L4r%=bTGQM&Bw-z%nf(+7>#KN| zJxB1^?aMHh{D0^A4Qys`5ZYR+_^=PpuuND60hE)`C%>WTGfNmuKFo?Q!z4wFu-Jew z)nj6AJBPazN3BWaXn1D3W@}>=U$pB73J02FdLNoc-o8OqrKcbXnqI^QohW}4o3Nc$8tQgd@l!AgH&6PAI&`h4i3~jz#TY?-*ywyG%}y&BHzOT> z#_9`ZgJnF7#&34{EM!dlh5N}@iQW1^a)&QyPPq5V5ZLXTjvvVn-3A=~f1^n+p^foE{6h2E-n!o)&A2@pQyh0LErqyVCo~5s)*-PnHg9#qu5G9X zIu@3KL&Ip{Eb%mK^&Qf~6)>OtW7YO0n0fob1BzX*9=9l-QLvnP>FR#RAjXix9MakB z#u_lu&45l+gV)>lfRWd}LK0K)piR$&-+{kj3DCT@<%Xl)Mj2C3ZLYHzud%sV4v)x| zt`~JNrGFtbrkcvPnT0b>y@l0ARQq>!qxQ38;MFNl`k%*fXU@Xiru2T|3&|J}vI~}w zpBrYqLDL@|pfiJV^?o64chLn~>XQ*cGCrd3a3Pbfol;$kU%Z=~Xk1gpqw1An@`4*0 zU#hPx%)^#~4R#Z2IV%%iM6Jd^vgN7kWt`aU2tK0q)s6iJ@r%<9jH24FKX*0W9hrqz zWXs9+0@fOni;F35zump5iJVq~SIBS95rYzYY?JW~WLMUkAmL_l8CsIBO!hW{vq3*` z1mT5pHwan#9#0a@rA^zwX+|o>QV)!aKMQY7&tV$z>9XrS^y;}Ck5Mljy!s7v5oX~< zveC%q2RN^2jz%;-sC_wHHD0NiNj-e@IvHDc;D+N+^8b*JzhTtP`+^qbPtu`0IK99I zCXigip3h;uOCYFduH4$|CV0l|hjCOpecm4i3%kp3m*ft4x*9z5GC`mk>>JSsmKJ=0 zQacrY|Lud2E&B}*yV1P7`KM#6WimE~Xg+P6sM&h59DWj?yHD%k`|v_g5TAN2+|f|y z1Jr9mYj3_4+qyjjC{gl;olj#}dOV~zqV>T3Bn%y}7iLf`Jna4&e^_}ze-9O(b+-V! zy0ijY@^hVQ<(T#?Ot7SVfqio=Zdqe;;;}j^zNcj=rrf=vxkmM+b0Z&lct_IJx*Y2yYV9-x*oJw)rnfDz!Om2fKsW)zo zDFx$@qnb>LSEo}l=G=FR!#RqhmvJdsENmw} zZFIHxhwJur*vI`3C=3sw)G9HKldQ2 zXpY_+d;~uhT*4@d9SaG@X&D*VN9-rF0DsoY#dy-$bkq|~{-NJeZ5q|dNqj$<);Yw} z!ECHBAhsOOP_G`6TL+FlDMWEC{ma7@I==saJ;{gZK3hQx9$*Uf(#FT*U}=+hoI`Q3 zT5}KP&)SV;6vtx+Uc>V9bFd%TXgjo0|2t9~!yjkZ>k*$@ zz008BV}uY!F&(W_0Cg|7g)5}9#^^Of&7TL3G_M7P-UfI3NH|C~?shs3mRk`lXr0hr zZw;)Yb0~UkRJ?mmfB0DT1+Lbjoc~fA`VJ|Esalk8w!MWR0Wx+`pZ0E{)|&8{GS;?( zil2|HiH+=v;Z6(Mf7KX*cdmbdYw1ef%wRPhz4{Dx#VYx=vk|BjnFQ>xlH-i?sBd!~ zc3n~Of)fcyXAJ>fDtYb0>F5}-7CwJd@{($Kcr_JZG}WVDuQHriGeLM$sN@0HwD>La zUWvEWO0Mr;hF=dQYkEg1d6T$&Y@gH}N0HomTG<%VeKqzmqB-=F279~3;^1N>xBI#S zn=g2PrKCeqTX%eSI0r)xDS4+A^-)e|dX{G^`6;a)nn$5B-lqYr{fx&6CqroeNY|Fe zH3qYcLNtA+&FuEV%%Xc(ooJ3kT!OHH$M6BItEUglhR35<m|Y5;muNKUIyCQe)?%}-aC`S^w4T{e3cg+L3cJX5UXlyvUjekJ zM=@%a3DK%GP}Ypz@!pxkWzXZVl4@b*$UX3IaWY(>Yg>1p1YY+)Kw+Me-}+St=2#U& zu#DER=j?^+5i%A)eJs%((uU>4tgt`rn!+gR|d^7Piu7ULLO5S)_9_rN=U`Tz^|3w*28+A%J{87nk-qqr% zmnSANiiLJ)8P-ck(!?KB@{6nTQD$V1+bOYpj6;ic62@2v!e{!z`+c_RDv}`L-!wPuCW|ng}PG=0FVjEu?iFc;ZqF$+X5B zl;TJYUHmnx2qsfphFN-|PqTN>p5!L2rrK$i1eU2v z9=QGzjusl78 zXi$V(NjLlVGvN8XcNjwPvJBk^?0FKZs75SZufVuvM=<%Pk{c+pfxE57bjtafMR|~I z)E(U^&pQ;A!uSyvH7}_i3v9GlLPVTH6kVI;R0{6p_XU-hld?Q8TSqN~VrMim6Qb&@ zf$dFI{I(~;D&+~tqPf88{x0|!n*v?v+Qow>LT|eqcuKlGimU^@hZjQx)$i)%c7ow) z8EaNf@e1#u3D_fJ+O(Fl&1iu4TNlAZ!XZ9$utU^a(EdRFOpL&lEt0_HhLY$1yo71l z$Dn$OlAFKIMDLADX7LWC@OYFLjdL!-4 zpVq#s=}Y;)_-h{Sd+C51s1MkeW?<5?HMooV*d_Yy_4n0N=<=HM)Y*mM_Nl0ImHfQh z9mBqSz_XCVetEd=(Q z2{qi_p%eL}TW~l$Zk~i;gr{G+0)2Fj;1P<;w&X0ho4Fb%lK)F|^TBkX9m>eJtIf;c zfYUk678;*!r^T*B${b6G=T6H~m=c;Q#FFiY<#|wkRRBw(VaA!@HFpi{q;;CxOAYj@ z77I-&UIqhp!QN)~A(?cGbeRZay3-j*ii@>rT^Q$F4EBTvAG8rpaGGn#u9F#kG*7q7 zSQ*vMzJ(33yhagdQ|&ApH5c92y@jFAs8`!WqIKR~h`Xrdx-%~00H0%U?v9dAX_$rA zHw8m|lJy}b4C+6Bn&sn!3@%;dB@s# zYHl$Wl5fB5GSKL}knsVOW2@9-gu8()Qi6NDT5KRGnxSM?EwcZ zcCVX`V+_$B7+4DWCLxeby~|*L24fxkUg;0%pf^Rb~JQDO40x3Vge~d)eZFk|)2_wqmVSAdZwYvc zd^oKx#bsnDcBg#1(k&75sE@6CqvU%J??j6Zsc7;<$&-!UP|+m^tI?d|SX2`~Z7RmL z~S&7qrN@8w}mj|xs0u$c%{4*up;8FNUKA&Tng_%u*VJpe~x;zi(T(*aa zbl+*x%W||<(!C3=Bw~xRr|{}~B_B3uCw}UmiuGx2(Banv>^3e3$B@n~3~HifY%wmNxSVcdtO^i=F7bLt(f#(#L$44i? zlr1@sL$Mf$HK4WaFIY!?px%VGLcPy27V?$W0IDIHjjLqrCS7ZT^>JROBDhYr#6O;o zE`@KP4XuB+Oy7@h&fkG*dzF0q$Sc^*<0uqUA3O6f6B~I4gC*t0`qz1wGrKz+re5^0 ztQ>14MGJ=$l)U;?ExyWsU?Rj&&8C*3&7x$D{X-@1Sei?}xiG9lKHTD;js`2%Vt1;$ zO?wkCuxT9j`%LS-t2^+>%2f2GwLw@(}k%spK zU5d-xUAa)BT@UC({C~brhx}uq5Jq-g>!g9`x3Q2$&YpY;plaJs< zvA9vYI?P@73l==48gyzc7=DwnjbwZEe*HD|=svuRY9!-CLu^u12-8W218;orP4F8C zrQW4|Wk23?zXQ+1Y5y|t3Z@P?3LVL}wa#Q>_S#^`rCu8OFdx@N+Q31I?*<(iZ#HMY zpo>cGbXbcojUJtN^sJJ*?k>eceN!|YU(o%EFS&Tgo?!&#m}UEPT%xxQohj!Jk4?Z| zz2fi_)dfcGz=%bum`-a0<>CqWbZ8E?rhF50Y9b~SqhpzppWbsj@sXAmwC=3l4b+Iw$EFmQ8BU=Pt<1n{RsP&wMlG9aXhXngZBm(1Y4R@KAC=lraoQa0_Dbzy_sO4 zvj%j@|HEn~LYVv%93<>yyAjSGdLl@r1Q%sI74Rx+$LYC$9}pv14 zw^83{J3_^Bz3vI_<|XiOxQcz-YX^@#@*s|`wP?N)tW&Zf!;XG`AEbtZ&#ysK8x@ne zT!Vuz)HHvnSkuFqaA|fB3?=&J8DHVUB?ec9sF+K`5;&RkNXT|ju~m<04zclfoYFzX z_IQ;;+gPLdAY1yn)2P*;vv=^^a!*DxH70o%v{KK|X8GCurToBJcta$qywyb$0i02=!e)<55_D%rt{DUv8 z6F-dH1>*UK8G4EEZTTtqbN&J7`~!&RALK3zAolrd`1C``&MRGUi8o4n8(UBfpAP_2 zu3(E@hrxu-8+UAN>W=pa0PxNPqmJKal?TM}Hvw@sIvM`r{w{f%L~e`UB~YfAnXhzvhqrjPw`& z=nten{LvpsfB2(6kpA#T|G)d6^as)({^(!j|BC#n@_$wSSM{HY{#n(3s``J`{9Cbp zsG5JP)<0G2&x-Z)f6Mx_&o(a@llcZ#QC=N6T?5vvFNS^fRjj4c3&;EqGB%*0ig{^m z&{))!u@OZ|raeW0K?wzLllBfTo~*#qTF=3W&I~sSi^a)48W>A^5WJLv+0AyrD>|S2 z&GJ3YDxC&n=}h$(pCTNxvH|p^bJ3pfWV|%0v0zuCWJ5D$e7U@?rWN)1ug8k;enuUf zXh!?5SMTt6`>D8*&OCo_oq|J;?83%!6|3?3B;G!sfKjF@W>~Zy-5j2vrj)%sfiQgiZHvcicPuIMPp|s;}b@ySo>FI!Yew9HEp1ZWwa;}N)8rdd!o75 zpbu=w{DSmbIXjoW5)$fV<6zp~ZH(THHaG5}7wuJL?`LDY!yB|5s$zjLEpg+f0{lcg zA9!uhvi(+x2F`CuT64+KyvYqTp+plM=p?D%^$gp(QQAIYtu%7bdVZQ&)! z^=|$Q5|1s1`y_Yws2h+|aDaYySFs?^BT)AC5;P;ZU4DgtVo*9XCcH6w00f==3=Tx& z*!Z>Z;_)wNqg1iZst1k_r^r|^@r*Ka(`>k04x+4x8@jlBP9f-!4ux;VqZ~iLPV&k6 zgPXD0(uc5f80CrX8JuwDJe(pQR*qeV^f`F0n>aBpT;q49W7Ju?#NiJ;(Q?|KKGDp#8}k zxPb00Sh^)ZPP>yBM7CGOv?``mby`)YRlT=j-mL1qRr6`pd|I_es#+set$VBXGXGwC znQa4P+_Xh2%?#QHoysY~$V4stKzpmXRv*#bXe2(HLce=vrs0C(4LD$oirFtrz=%;N zF@*M6Wg$_fu4p2@Z(HLV?U{&Whm zQV$+tsvqNj${*j>@Z-Dd8O2<^bVQSC6v%h)HHk^6aYVS;B9Py?(IUowtUqkk_T!FW zO=Ct!rocL_nfz`21~Kt-blF7rQG8~wR?MX89hpg*Jmv71iol%sJ`}j4qu;n9$#nqs+-f<`rb{o__NeQ>ZS*J^PQjC^6YvK z)lUW~_^azZ_~M+O>Svp3a5LF>u9&GE^Jx4vO!f5STS6PhG#Wn{d+c4r3*Q;VC`R|! zY&sRlKPQ>QWS#ykSTqRWUZ0F(;`eTVY0rFk%ld{f>9HB$uxL8}>82Z#+*Xebd+EZJ z$>r+1M%HZjt8RQ}t!(w6gduF(xTd`Bqcdt7mnm$*#`kEvJxCqcn%>hsFcOFD>!LPk z@6YUy8RAKctFJ{eN3;?@d4dt)y&t*2|r(tDtZ~3u(6PRO4 z2`pF}E#KtPkBwQ=ij6Etmfx#y$@aN2=328r?z^K7d$e*ad-=VN;>3?@kUH3tF~7!& zTXPmdwV8fwdQT(8lSw;-3xfmMnG+_8_tq(z#Ml64IID%C#r#lQ>g&sLeGL`s-an>$ zax>VYpSlXS{QBI)Z6s4amnmBI>B#5ruxHN$UdT=F5908lIUA~fL0;RJXtZ7Vc$z#|$dIn$rT{mWyNdtDH$4H)kR~9qVup=9D#hyPq`$BC{GLW4w zHR8AD$E!b@y0ec3x#<34t=gE+VmF^WuusXrRPX7mzEW55g*D=bj9pl-lrp(iOKaZs zc{jGVTDIIYb}%=&+>9;Tdrn?hYYMl%@Bvm050zL4Q3~sa4YiuU)BFWgt#I$CjqA;62Sd{Z}RT$fj~8Os-5uM-m)aTQaxc=C6Vjbo12nuN8G>aoZu zCU_@ks>cWNg~=u{`sFW$D{}+r>k=(ug1)W;cVl0kWM>%jXQ=s1nv3)6|Y;cLKr z9}nZVvwo}h4eH9)Yi#)Uei`bw--fWs^_%kT3(lyW*Gysl7vJHy20`i;^?aCb$F2Bn zo~hc^Ab?$J^GkC=XIk{|$APSVqejB6K~`q1<}G0t20DRzqk8h+RFB6Lry;YMw>&vc z$-2jDv8&q-%k?JoV)N&ivD9aeV4%yn4;8> zpPO(-J$J&*zUnleg|Caik`vZy9eaN^!?_6tE!rI2>wO?wp!d?T$Lc0# z_dYLX8(s|rpIv(LfttCjc;jh!yW3mdE_ec)Wl{=96Qbn{Qv0y30d3d;msI&e7dbQB zOYgYMDU>%GU5yPHtzM5S|OMpo|=diTx28#V5t{`u|n7y|!R_t2uDjeJ&$Y$O) zQB3rIuaPMO*b_wy#XysF*xcTi^&4WSm=}?SYpYLZP4#sZ{;wNwx5N=_w2w^jJgGB} z>R`uQXJpI!jTy$PE1Ixo+Hvx$t)}sVgI<76wH0!w`ab+j^Q}-Y)>K~efKuC|bm1Jy;Lhe*18nHij|WCkp~}r}N{@bYt!; z(PuN6GoN#^RNXDCE1SI7hL`52tM|PbPT#Q6=e`4D)zN3BGN+oaP~LQ34MRP6#y)VvANQ*Q*a2B)nAnU#at&l-zaM;#?ZS{cia9`IxtE>|IF{tEfE zCSw`)s>?ht$I0JUb7H55TdGClJt=QZ~{n$f?QhD1!^c>Hti7d9SuEKrMA@D|T z7PQe&k^Hp{G|?<&PC+dc^#?U_cuak~&1Dk>W?Nvj1xs1p86(9&i=()*k2mZ8SzqBQ z`;7}*O=L4()mD6M(~?7Qf3|4mH~GO72R`R#dv<>GeYwq?(R|#KdMu;ppd1#?;*lS3 z!R=ks^OsjVYi*A0@X%8Y`1`Pn>Wn4!e5rd!Zjt>$J??l5zT)@*Uc*Wjvp?<| zPWPC^1*`fo7Zya~w&wG><;bQnIr9v#Ur&Gj@Mepc=IWu2w|@ol)FUP_1@Rpq2bS`e z>y2VMna9A_B5xi&wQ)?}cLk7i-;KX1trL^x(Sq5%8o)bS7O34mIx>f=?dX}UWVLDh zNOr}uK0Rwf>#mC)Z1Btb*nOXuy2dy^W*X>+E0)z#w|AlMyfxgWnH_QeV609ca~*zC zNZz>3tiaWewRH1?H@n-*dv%<}uG!xKqvJvHVGd(h)^2S!*!_&0-xpZpph!CM8OK$d%wEmWR@_oH=TEy2W(PVI%Euq* zPS5;wVm${xl+O$q$-kYh&w_Uzk{{kVoo~0yfS|!k<=fBsa-WzrU|pk$Tqiw%UoyBN zgbr$D*3Ti3$88MP9NQimJwMZrzv|+J(Ob;bM>=`(%}cN2*c&U=7rKq($NXyZrCUy_ z>s(;mC)$E53eweu-mUqbV|{tRl@j%hhrjXVn+ZHTPABHx>$7MuWG>&^p-D`W1-)@U zEaB6x8po`>wlVSAk3jyE`s&h;Euco;QvR`_am;KM4)TTbxv7Ui%=Ps-Fz)_jzT~HN z%%tCj?2BwDukT;1j%;biW@L5d;m&DlgG3jWHcpRwem|aSPoDDTwDCAG3da_ym*Py%Q zN_pYkaV#yQ7HjPtEAQW<2mAI$!91Tlk+(nGhP67;hgod-E%&vQv7vkDH|qR)ik@C^ zVDWt}d%3QO!qH+lM8qs+YZe$Q&b`(ahGzt_dk;($o9pSJ{VabLHrrV7>tZ-+PoB>f zj5kmWvj2#>2Pd=P>Dr3C7lz!k@le)pd$BySTQ{z}Yt34$d@TR&>%yOD^qB3uWAb?` zrt{P_8PN9XQu(26zT9mqJpgG3-B>Y;-*>x%ldc7+m!yv2TTj;INBW#rYa$qbd&z>^8T>!&y#;tw$<{861ovQp zga9Gw4sOBeDm1vm;1V2yg&+wKf(g63uASNQ z{r`8r^WSse+%q?M9-b^J)o(4Y+Iy|N`?B-=!rZc|t)^@}=96>lk1xf5+Z|-aU(>l< zpO%Xvt}xkibaq#d*Fj?Fo1rpCzFe+ZKQ`VyN5$iUW4^9pJ-yk_DWhb+d_Jz?pO>)p zNyFvBoLOD#PsXtp&JgK6A(iW>Jtw~sQdhR@{MwnGmE#^8i^;0z&N{~qSNjReC<{(n z=?v-IojdkkQ18Qva8~Oyh_8GAHlGe4p`Bss#OkbJVFPm#su7;xQ@*(ol03X-qUp(C3{u(WBo$+-I@1KcH>=q^W z_f&p+;Cq%h`2acMXjWJDWe-@(w4G%l-!!hnA5-#xsx9QEu1Q@6wt7Y;(Hz?VbtX9- zww~3#R>Rig>QFhLa~alQ%dUXkkD}$$)u$>BYCU3E?ITfgUHjxB)w&b0CEg8?g@2eO z3dPiMdbH}S-b;L6to(MKbMcY7@|Q(9{ai;m~CEHf2C)d_a zf_2rJiIiM(oN8UJ))i`9r&^b*b%k0tR;|m`y1Ui7`P8~xt;^K90R3pe;OEF`nU8Ild_3iLLy(jQmsfCj91}WcEKA z{K^_#>dHf!X0mT!du z@)3L0yFUN4UE*QeM4r!mWSu10TmAO~?xGua*;*P!+E$=AXoynS&ZLS_A zOEmIv?ODBqHO&+*Z|2MD%24t*HYRT;*?Dwo*UIx=yh!_c^75)T&Wp}6JXgySGELlh zXX=V|`Hhx2WmLOu&IFq#*fb$d6XG->_Zs_VLheo2PZRdjgfmjY87bl1n{X}jpLH$s z_F1&dmVe9cH;+=ruI5AKfp*ozsoCkA<5^$XsMuC9?DPQVb$1)t$(dMQ7{09}cg>r>ugR0k@?M5|`o6BaD4@&NGUS8N+9{o;;ZfT;O{l#E;;oS)FHoBzq-u)=K zb4wDjB=Bf#oT~A?IJb7^#D>dbtk=;8jyZVrv4V2IjN{JWjrsWLGu33-m?zFht>W0c z10izh;#95$1*fqxF$1Ody=<;2OLMSdIiuv@Vm_`uYv;O?)Qy${*7~|OZ<{Dq*Bm65 zdgXLg4ml(a9SxP+3ukfhHR1fj?+Zo$o<*JA>J8(6^e8MwRb3bR@T&U0P>eM9rxc6I5)r_9{RdK4dG%ebfsADby7Z|kwkcCK{^UMi*xAAk6ftz+w) z{C@emJak=R)r*se8}g*J2TyddpYMn9Gp_9RE~C@4Qlp~ywtKnkzN5c$=j;{Duch&| zM|PMj(xe^4Clt4^|6YEXEv`&IIrGDM)@f2r+lo$6a@e&@Eb8f`fKCgd<&c{l-MN~zjs3iAuxx)| zq{tK* zP4Uka|6K8p`xWu}zqa1V6#rcDpP>H){U`W;LjFm}KmQlyf3<%l-eeDaNfUxuRZqRQTGJ*aNc@QF8hZu^ThfN19)i4 zZ1!1yJQwYohj7O?sqFQ(`pL%2s&n`Hr?&aWYsdp>^6;7qgzen>5IJG$@9cKvNj9IB z1LW8(^H}j*1#GHTD|^>_>gd_1c|eUz+2oG%^?A2x?`&S~(sEAClDtyBi?+OL8p)XJ zo_ylXHMWsYyUHQ2ud-xkqiuVi43uk1OksX6eQdiN|(jJGw_7 zpJU72DNMc_xssg?tz;YUZkSAW&4)c$`hCDD)l)Qh>iykbyHG-2NqX1$O^z%w`KgAodN&W(#2+t; zKE=Ar<2gNDy^jnLg@Phvr2uc&*x6z3hm)h_*?qpQAAV27LS9A5LcjR9e#-Yfo0ofl ze03$O>)y}5v*C|Je>N(9%e;w*S!81FqakErJVL#+3WXg+Du=ZXzq$bN zS?#BDzZAQYhwwUiQ`vj<$|F;ZsKL`_kF#CMSVdlWY2zik9kRt8Q{Qc{`ZKF|Y_=`z zaG3m!FIVpbci7hXsJeEC9Bf*xIRW1&yBu;p-2J$4j@XhxLuB~M7Gg}coKDXrq4G?D z!=gyfZ=FYuHkF+lrSU1F47KEp0Kp0n^7 zAu?4|DwnfdUf%d}u*M*LxtWcCF^&a!X(d+=#4PkV!jLzq|D z2;RZ&ZBMi!+EHdiG(RYP?QwMyiMj8ic$up{_Vd#giSU`>yyvj2_Bqingl~xue#nu^ z-lKRP*?V0L9@sR_RyMSXoHNnJv)w#s^C;U+ekl2gefR4uTZI>4vT!XIn;cTnRx)#x zEU&&hZ{mo#0h@0|%Lvc6yLZ3L6+7!~r2Oe}8*yf(kF!^)P?_ELsF=QBtn>A^O=XrH z>19aA9nQKV%SaJjLY`l6$C>J0X4(E_L;3SC4_C?2=S2Po-Q|@rp02E(;o|06^?X4$ zZ`U`qLfk(ujFyiMsea}~9~=|X43~=^__)fITfmmQ2$!$jSzT%Ny(A?50GzuJm74&zAewCzF%p3iaAcNQDHpj%nH$YDtCtGi{gvd zc!^#;XU9%G6U}dr^m3G|Sv26uuaUgq@pf#}ueofwWGL@4?+{y%@mpId?`HhhOX+yO zCfjY@H3J>TonJ&?PD)=YO$EzKAh)lnbrO#@P!yvD}?8(m&%@QcOH3{ z*Wm5<|884aq^j)Z4B!Fo1Ga0s+R1&LKQONyGi|?R?l0#}bh0bq6>M!%M9C#ny;<%g z^8>c1-jjP#9_}u;{9^r1M9LfY+l!wj`Z_bF3YFf!DZAtt=bX2psZ1G>UiQws!`X06 z85!QVgzVbojW4h&>l*K!i217fYu$eJaZN6}h;98bT;>^@)wO5tAFRWY4$}8pO4oy2e!N?rV0pdK zGiUK6Rr%J-0rJ4-1J0oz+VY)A)pvPxnC%?*FpO6p=@PeG6`hqDNAYqpv*=fSYV6Wu z(Y(sme2xueO9%8&d2D-7J9Z&j*(EBJd!0PYR-O3P7BZ_TU$`tiZ(MVSO$L|d5B8Mg zJ9FK$v4Ng^RRX)na`!Xf-p`Be6?9rDUUJA?T#uitI&w^x;y zlLYW9zwNjEeyyE6{@^|PrRPlBs(WGb$aEK*ySt+8zE_lNzdr{%dSFgK-?Py&N6PH( z3hj!-&L0~o^IzyJF3rm8tg@@8^lI|6@cv_*Gx5%*GBPy1Eb6ht+1ICxEOozxEa-LD zIis(q9Q3}CoZ^+t6%}+^40rXA_7|S60ZsaeiI*be{NdiNHU;{)b5D5p;HsH zCUH@+@;M*Z&4Y_sj*xKa*D9;4`Nmi5LE{dx&Z?BI1zG%fl0elL+xnT)|4kJ>?p}aA zoBp8lW8HTA`$r!|(7IX9EBX8L^J$!7?b-6qU2UUyqS2mW;I7HBgHEa5H1(ZxN%|EJ zXmufyKWW;Y)hh05OXMBOAI>|<*54azyY#LJ?=&t0-`i%V?bg*&JaM5Q-eK`QTW6KW zYF%u^1Cl1QH@k9{g{1Gn?|<)U&-f{fZITgubw6)=P49Y+!)u~>)}MXt1qP)OXV*sY zv_JaTYn)poz8fFT-w()Y5AXa^c)#qxGi6O>f1ce>)(8mZ_7=}<4}+@7o_+nfZ}I)M zz7N~Un0@bArzSIPA*aG*Ezjj_TU&>%W1%Q{MP_FKRb~ZTKNc;Mf0NIh{bQ-v!+j!U z!2w;x#+iQ3^w)aI`x}pmfSKc*oi{dB-{+BDe#o@LnRaGr*)6=J{9(^s=f@41WTEKB zGOBAb*EfAm33;}Mj7gi>b>wWAsQy!g%+TN4RU)X1yW#w3`ANmgw^fp}%15JQj;%f} zXQm(7(nR5MyjNCNyNj<`&LkaV-9af`W8?Djb=899;t|iBuliQy^;-tWKUy7dCb`*8 z-AjBg%66UU%sZq%Um6r6-i|5jJlrjcp9{?-V%krNy?QR17oL~JaqLQ=03R92JHF_^ z1{BL}%X(0CBp+w^;-czM4dzHG)l+oH9eJnUp6KH`&y z{npwutWV<}Jl{{A_THcSuq00-_`>hJ?Kwu*boAa3&F?6?RBVw#q}m(Blde;J;MEt4 zfI;DWQ1`6%q}gAIiBTPR)k7)m4_^C8NAK!9OXySE@6KxS{k?oVbo4%(ywXl)fBBxh z4V!5@nW?}0b*_^+Mpv*6Zxtm6UG-!S3rq=^y(e1cu?4v!x>kz4-!f88zS>QU3Crh{ z8A7G+@uOmK@^Q}0{hG=Zm(t6}-|cX2zg9}x3j|5~!h6o2{>UibCTb$9ZA#`EpZJt` z{kVsmlQXkx+wlJ4+O`NepqIDn>g+b|yGx?w+rz%D)7et7bQ`1Om}NdLzUW6b@L_*> zIAvDXfRC@3gLRPZMJZkFZsg?~8wbl(GoCq*+^x!;$NiS1 zd*)%UMN{t%{NmV@_9u<=$=7+S^L(kF+LjNlCS!8@^C`#n*%obUCl7{yU^9N2X^XDV zUml5xWl@dG+m;TBlAVubU>93V2$;SrTDJGA;NHKZTI`I_NV#WKSMgwrpR>ws6))c( z6NAT$b4FckBB$=kATuo7>1^g(N=|tkBtysCceb9MQJ$*aM83U}%r$iDDY1NC57{B9 zdakf~Khf!OgiIIh?Rv7fmV3(jXt_!C+n?B%j{P=1O6D4)`X}8>S(6?8rPqTjF59=S zSd;c0WWP-*UD;HB-wM^|cOvIAXPvRtxNmxY$+qlsuHN3B``&mXVn{32ky&^q%t_vqvjp5(f zR?cX`kLJn9Z)e+OI~!PQ9ml~MNe)r%BwxW1XzPU$Ty`F-M2*X>`ov1;o(1uZ=d$(<N{4MWP< z?k$dzm1?D7{=3Emcy5W7(I>0AJ#y5JZ8$hmvKw8*va){8`YU?Mv9UjkQTFjpTjwV7 zedmmFNsnF5YUhLGoS;(D`|5q?@LL&WQ2Hh^`>tfJO`T4Q#|wL?_ojQgesnhxKMo!u z>$LW9$)5Xno&6Lo+o^N%$usH+w&_D;aPyq5%q@>H5g00~oz39dmpmCSyQ7u*4uoW` zu%g9zj)P@oj{?`62aYu6AF5}P)h@4c{-XM&dqk=4bWRoGEcwS!-ltM2^}WM8Vz0$T z^B#FtRy-1&ETGWdA$(T(`t02D%(hicLV4!tM_8lkV{PlZHRgBEX5w3IZrh!mglOI} z(AUm>8zzQjir{HydD%FmSimy|C&wm4pRl#;HqK{DmkWNy$k_Y{+j z8~6y&Z=&pSbK~!buFyD#JTYhw(fwV?W#U(HM32pUL$ofEUSXAzPpYpLbxY?aI`M_B z;?0bLM7Q61)jdP)@0jy)Z?lRSKL!!)w=N|+zOOjZ>Untfu}OZSqwa5GuYdC?Uh zti_8|M6XPqhTE^+r**^j`*6iS(e)nY=i}UwM9=Un!7KYFA^KgCQoQE=^SiL_pqLW8 z#)F3>?}?NJd6&T64C8rv_;T-{bwn5UPscZ`zeRMT!Oz&%eJRu$rR0z$Zg#O`PNGwn zAIlp01`>VpP*S)Ax)+s{|*dN+vZ&}u)qvvn*+DNRn%Lq@3@obtuyn>r7fd~zMZawTsvNG@NMeopko&96lz4-bj? zgG*$PK9RrDc%3J{QZ!yebhX$5GU@yl3O1BWfjr+a;BFjf^QJ*TJeWC{Mv(Le^>LMm_Hyp(O15oE`Hw? zKy-~of#Ox_VniQUUC;f8dcFvl^=5`SB0CxM^?8L@f#XGKyx7gjtn36E(WTG-#A?m( zBHDTAIeT9-IniZnr{h-}8TMUw#FytdzlQjkf2;t{d9N?gJEBVPXGP;kmP;O`_<^DO z%46MF^_*J2G%rZciCPrkt=*&ofK4NTEmc!TZ?J*TLxaTf6{Q2C>#lmx!AI+J!;)&J$RmK&Grny)Mw8?(Gxu61nV)PBuKUvE9cTGKd=8&4|G8fv@PIo!$+SSMqttq zT$Y}MN&#ALT*>89>q4Jg$z?vvz?EFf@i}~6$+aAKz*TZ7J&)kyyUw>Oxy*5)$9q&-RNHO$6De|Tn%ThxSKgI(Mb;S6*Vgc5)J;E#1peKp>Ewkre0U9`qSC1tc_z~|n5sh_EX1_u-`00829ns+PC$Cg1@mcWi zUpXVukgM2APog2OISxIT^PwLT2YNH{p-*#N=-K4w-H`k%O+MQ!E4I?)zkAw}D^0mD zZpw@KrXKzg`@Sn&iswk-CE)|*SEc5Mwi-Dto7Wr`e0wPQfciUE^JtFxJ5%#0FR8yX zHIL>fKVoVQKC_iG#pJ>j-!#}b|ydBN4I|s8$IgQ+SK6!GM+jl$7*;m7# zefzjO%_$V|-tnZGku&|g#yisgv4`e-n)|y8z6qWm`*vE69EN|FH_u**{F79Oy3a{!2T4 zu(^tXlPXt`*P)(^*8&>#E^ z{6K&3GvH`F(;Vmz{)#!!AN&<_w7qB!^k?KX$W;~gqB+{`Gza=qd=n1zr}(Bh+J9&c z^r!SlbD%#ZKh5zQ?7v*CNptqR9tA(7ISp?wh988Yy|>Ek&G$R?o-0dk{|)_h=ueaDUnFsWbDi_w(*KMd#|8L(RXaB8?e|sem~V^USGD8%GWq_OcC6YmCC?qE?r~qO#Xknc zv8rv3iU-$g@#o!+vKQs!M2Rc4_{y+FEMu#b^0uO9g*0c?pJ$d=)cg@!E<4ty^_I&O z9lG=6HqkGaJg?}@2QRyar}maU-GYGRv)Md_tc^B6ahWa)KK7?s8NFmyHu! z)Og|IaiU@OqawK)Pt_u&92LGu+{3t9C!kAnv0l+at;5`x-9r@JJ}j3U`1Dy&3q_|& z=PlnTJ~}A+nVR3MOLLZ6(Mm3<_0$vfYk~1!dwG=J!%^4^r|2=S@g+ zvFCYa4*b4bF1usWdULG1Wb~ObEBfW);Ahdn%Z{$jv%TcD}Vvsji@i!t#iBC%fem)bms=^+11%~ zh~Cv;3A_Dv2+^x;lUc_tGl>44>;fM~qH7gs*%ZguyuFLbV$<#890S7F|3 zykVzfbr`L6yZ;}%HhmvKJWTJN-JPb+Y~k22fM2*U&OK@08gVD6ABWsZev$=pEBT3r z+)93;A-9sBXvnSPCpyK*Z^iK0-3h1C^1kAQXKBKR+)9307ji54-H_c@t-k0OaNG?( z*Warn8u~ch;2&};`Q4B`Qpvr#c~>`NKeno_D6*wK(U4ooPjkYvw-T)3@4KP51^2p$ zusmIML!Xda$zL98L2e~~1?azh(b?kuB`*i;l4AK9F=gs_2kZs8mHZBEccJ8G+U`Qh zPc-CK@)HfYmHb32y9;G^rtL12-I=z#Q1UZvcej$CX}i0X-I=z#TiKmyyStVAOxxY9 z?9Q~^-OBDnLvAHM%~5vWt?bUU-FGXyGi~?sN`6`kax3|X2W5AMvOCjucPP6vZFdL! z9`ZtN_&sRI4ZjBsx#9PqAvgRUw6Z%>b|)NVcc$!4_>dcZ57{9%{9fCgDZ4wg-I=nx zL))Ff@3q~Tvb#guohiE$4Y}d>n4|2@l-(<8yEA3?irVfBey{D$;P=|@OxfM7?aq|l z-LTj5z0bt$ft^LVYpr;j*T0JkeZH^w_Dl$0JAJ;``*E2FN!69x$2<_~+bY=9cP;s- zQ**?kIV;>Jw}nq0?KD%qN-BGZEhw4LW#jpPKz2ne{xdQVQ z?N&4ct>(DZ9F95avrK(f;Ij&oDNKfS)mlug<-mN!15-Q*@Su2OiZ`00cxH;{-T17M zg(+DWFs=JeN|leRsl1F_t$s80f1;7Uk;gHsFoCDmbA!e@7asU6w~RYL>-h|{#vxkc z6Rp=JTJys(U-L;c)=}#bo&8c*$YqX0UUNS5K(y8m(OPfjy3i-liXZInMB{VNqvoIV z2pa1YX@AmX87F!5e1UO|L-eq6HF#K>dm{a^8!Y}DsO~XZY4hxtaKDkRLFj(tH@w*Y zQTH3Ib{tf$7+-%avxH66Z?67Nw6Zf(^N99svxr?T*n;TkM{=`0lR6TeYH{YkuryuG zabb?D`NEtJe=%{ej){-o=DPU1=~wt1J`a9?r`97H>ugMO#AO+0p!IyBH4f1lpKH0W zF43AFqBWmHV;!{~(M!^vu&edVaqwZz$9hC-{SdA7Ml{yJ|FN#(2k~O^$)QKhKZhPc zW1WhxJ3B4o0yNe!_3(3!p)7OZzWnLvF)VuKAl5R%ppT~M&no?7(3?i}W`|Svqd9vn zY-g=ocOm*w@N4!g;2WarhkEh4+o}-#een|NTC*V0TSZa+@vBC#*Z-i+>wnPd2iMy)$GrZ>pjwx%|3T}&(;R(0 zFEFmJ^NGefHs@*FmoUc}Xg!~3jYINle4@?kf6P}ubo~#)y#5DmUjKt$RIwiA4n0n_ z3ee{DKWOy>{h0Wu@tEsUtpXGD-)UUypZGMd|1k&lQhLO*tN)djC5oqu#i-W97nAqs zktS*#!*9&{9a#5E$qQ`!d};rj(8ELBr}-NGX{=#Ll|U!xA;Aa!wLSo}KXv-0^P$Se zF<&zus(lUjrN4MSRQuXj%7=!%lpbmSO0Zob361Pw%86Ry|3==EBH9hDFNXIyvxd5=Wp@OZl=(8xmgNzh4x9{w30ARnSL zFQ|m;HGk5@|KIzo|DH2{g6)(B$X@?}*J}xT8QeEv{~|3U=s~ODU*->g^{s^KHGj%C z|DpA@_*|J_$N$sq_|Ke06FzHX!2~@d=;6Qf0ovE-%nRyEU$3dU{8#R;NN4s}d^H&p zYKZ@uo*!!s(WJlhey#dpl)o7F^>tqm`OUw+ugO?L=cRbxG}lfTPtZ?-5B%@@!2Z3n z1Mn;*o`2NOP!p}6xhC5B45{^5QR_3I##Dn59{uye;fBdu3SSRS@2d9>c^axtdXP`9>(HfsBoeMPIvfn{2bH9UJ=6(l$)LeR(2>3MjJFfUQ_dBlmkjh>z z@T12`UQ0ePaY!c`pJ>Z|r*Pumxnc4NY?FVYmHy0p!V_#q``v$}?bKO?&V3g9O3+`* zKh-(Yj63-47xPbb&W!g@9gpO(aYu0iTIV0i8~>_&qRyFgUI4z8POu~G zcmMRh@U`rC^vGE}w?y|%zU+M(Waklbc+`5jkNBnUk8a*{RXyis+^hW>&trAkS3*4( z@HP5R@jRPhuLRruYkE=tO}4}RQ984H4gXYer~Ky2`=^RKypQRtlsILF+XoXyBlS5j5~|9srFs^?3mQu` zd8#teLsul_`6sm|`cRkcEbo~lkLbjl<0yPjyOX14JW$tUVHrYua!O%6hPy@ zrG6OGd|57{r;q3oyS7FqqATxp#l9Vxi0IZUF2>>??2j@04K(KBGoXP1EYJovBp<=C zrW(h)ZD?H0r!zC=D;%PMqwt9azWQgwe5|SdMl{w`pCKA+sx^qlnraQAv7%+%-!ebI zf)ilD53sCjv+!fH@M*K~Z;Omdo?gp^aZ_H*H}wDD+<5<&T z7yqy6CkwkqkWaoUQIypS=}kWA+1t*Bv~Nv5xnoC8cH%)5^2tRJsn~)o{^XO9%^x^I zS0pB%EO39TW6``V<-Iv(6(s68@u`F>FucMuh*W z{XF*WT{*)4BV-(VnLiid|8lZ3n-lh$!RJrq4q}gk*ARaF>K`0^l2s)9;A`U@G5uN* z{=5nw*b>>0@b{;VW2YWgBK&iEud&fx3ljdsM+excix~+&OC=Xukme5I4_z^ub=&X* z;UDT!mL;uOnDEDCJM7q6wld+L$?M1SILi`#i{EqdMll5lKe}iJes*DY!guxk#FFJs zMEJFnUS!9%9U=UuRaUSal_wMatn|Iv?%*7RUusbz23+I>tOH!+1gryG5P@S!K@1^Cbt^a6b733>rO^aQ;C zA9{jbfDb*vuE2+#VOQY8&af-+VQ1JC_^>nV3VhfZb_G7{47&m!c7|Pn4?Dvzfe$~0 zUjiR~3cmzC{1ko(eE2E+68P{__$Bb+r|?VQ!%yLtz=xkAcK{zT2O9Xu&7gsg+zcA{ z$jzXEkK7Cz_{hzmfsfn_8u-Y~ihp6@Us(7T7XF2Wf47Byw}pSVg@3onztTV9YyA_x z)<5BE{S&^{zp&_ESoBZ$TK|L({VV?=eC zO6W(&FX8L>C43#fgpW8=dLewBe+XaaAHvu9hwyd&A$*;G2w&$P!q@qS@DXRqu7t1i zC*kY-N%%T{5C&i{n3^FQJ1{7?8g|4aCf z&i{n3^FQGu&Qx3xK4L<}72$(caYgu`Ra_B1Xcbq44_d_);e%FjMfjjqToFEK3;#mp z1(ScF@`A~~PdLdBJ-f1%>a)W1-1W$Is8 z^e{9mZJB7EilLd6x~EB_ZNt_WZG zzff^S_{#riCtwMSNi$;3B@T4shW=SO>Vs4_F7dI(~&E|48Ts_|Oyd z0(|HRdI3K41ib(sdQx#k_|OydqVtb{UVslhS@Ne;ab@ODsp87apHjsY;ls`#g&==rHU&v|4S8DX8so{ zt_UA~8dj#ZOYdKD1FP(Ueh_CbXP0n6KZvt6t9)J158~`$*5oee2XS`T`>YfCr#L&W zzBAR>zeLX-d7RJ>;>@!Df`0~l%|8Ra=AQvy^Kb6I;NRST!M_9eh%?Ln3;omnjySWN zAE1B2N1P$A0blE%fq$)kruQ%CpYRc9mh%Jrhwu?+mh%t%hw!!k5We;w!q@&o_}YJ% z#eW>8|5(m%@PBUce{S)A!q@&!_}c#oU;97dYyW4a|6^Z-eGzAt^C#k$@OAuh=tsvd zhkkVY626XK!q@Rj_=q#?>xTb)K>i{Ab^alIoqq^l=O4n?`G@ckXO{Cb@(v2kN9)F+CSpY_0n>#mpIo$Z|Yu)#61_#iWh18CYr7XKw0huCETM^`uIoh z(Lr~{&zHYP_ci_GP}@S}lVkl~><&A(f_!qyw7%|ML*9^2KC86O?e`!z`DFg-H{F%5 zG4jc0i<65wrCS(28SN#SM)(uXo&J5@^^1p+f9ALqAa0X3!oQWToj8-bG~u_KIYun2U!U+F7M>%f&dg5u!;`Obrwi>s_|Mxc z6BAm@CVao}LSn&hp@i?}UL`V(x=i@n8VnOl7pEosnD$GB{KZcADNpSc75o_C=bv;% z?8}^-@N*@(=`MV>KH=v*^Hi+LIfn2DZEPz}^=?V{J2Ji(d1~$@{Jlk%ipB@t2*hkt zaY|&1$U^x3`QM7$MFI)GdG2%)xQKnMGxm9D!aqMMhXgM20M^;pq!Qt84aqBki=2RU zfD3%A16m4 z5%};;*cJG&GyD?x@Kg9D@ZqQMOW?y#6Dhw0KKvB13w*>D{1W)^Q;Y*&os$Io68P{_ zj00co*#b21)t*h`z*lD)qJgi@eBi&L$v@@;U!Bjuzr*Ao!0wUf8{@f5C2j6Cw%B%`40pC z@E@gr!iWBq{}8_RAHvuEL-^W%2p|5V{GagQ|H^*|AO55KpYY-T%6|wS{-gY#@U{OF zzV?5@*Z$9;ANaq*WzY}eO!+^De&GKKm+%p1%Ktg^1OHdJgs-#ai;V__=q!wOZbR0r5D22`G*_+L-~jBb^alI#F>gK!bhAby%0X)Oxcz2 z5oby-gpW8=aYgt#e-ggVpM~#YUm$6uHuUD5oh}PkH%G85kBG!XJPm!=Ho03{eafjf<)_UL82}E zSJc;qbmp<}PuD=OFK{gUJ5*jU`FE(iVDisYUNHG*7X3Rc{4RNUw;X_Z*3-F;Q=mq%DlO=zuyd0l@ zxFvt8yd0l@xFvrw6<350JFB=NeArpVm6<=eCI2%^{^XYY&n)?qTk=0sab@OzuHuUD z;ioFD2p@jBtWjDU;tO$R$^Se>@wdwtf;=#y2|9u_Tvj5V2y?=p! zbN{7ry?=p!bN>bZ=Kc%*h2FowztH;^^zYXD7x*{#U+ACk5oebD7y1`^|APL7-oK!K z!q@sIe8idM`~&?HKH|)B{(=5!e@C2I&Oh)U!q@&o_}YI6AO2%GzrlY9A8}?mzrlY9 zA8}?mzrp_rA8}?mzrp{d>HpXl_5S6soZskN2>T+=u&?O-i_V4658@2_BJ_he!@j8Z zFT^k5BhIj|8~(G-fqfD7MVw(@H~gm%?Tf%ioMB%#{AU>Qk2L&;@(JtA903#-SD6H$e)CdI8$*&_=q!{OTa(k4CfN)2XSV(PN|4<3HV2xS*}?e zIF|q)ab~%GLH;Lv#F^##1^J)w5oeZb7CQd{2l1q9`VxDJuIWqE+jUJ}qTa4+`V#ea zUDKDSx9gg|M7>?t^d;);x~4BtZ`U<_Y1G@X$_Rx+y$Y!5)3~nb(|ldiCmdbVCwyJg zr*(BrpZL)=ed1Hs^of70VcsLKjH6e9#=)Zn2fYe34w)?Lnmq>K$Lu`-pJq=2_(!h- z?zccLvxkAkEqX9}9tg*xH}optz6#_rdnX_ldKG9K7+3>ypi8U0O!=Ty<@@T4TU3Bn z{;1BitBF=VuFkUYXMAZn3o3G4%3S`i1_|k7VsrQXi-J=;g8W3;m_v32PWX)CWa*8TWN8{X$&*9skTeD5B9T zWa$@*|E?palugQCv@%X04seNZ$G9<6;x7W}{TDPav@KnE5+|I+V-zZ*Yv zkA>_5U0U=Y)!*^Y?1Lg2_i*qJ&hGE#!xm`X<#ebbXNO7`i?vQOD5rL8@cu`k=7XXN9FcOLYugA4DAq{Vf81 zZmG{oOMOPw7K$U(F?4-U<#g(Ap*XVCmsL)u{uaWw)R$Err~Vd-Bh;65 zeGqj#^tTYcr9Lh!^>Nhk(BDG(vDC*=$3uS$#i^w}E>R!X^+AC;hOQ3^OMPEh>ieie zQr!Z1K&^xR7UJJh-w{AFx1c^Kb$<)$gA#QNT_2RFV<1MMADl%%BM;+z02+B1 zXAaQdA7>8G&_B)upn;Dw0chak8~_@57<;y^4+_mc>Vqc#sIQs)t23XU$v^6YCjY1p zn*5`FXY!A0OX6SG2TlDGzV2@!eBIwd_*(y{ubKKseah57;cNX9zV2^9ebDqD!q@#R zgs=UF@U{OCzV;u&*Z!liVFWe+Xaa zAHvu9hwyd&A$*;Gh<}}b2w&$P!bkqm^+7X#628u#gs<}_;j1_^`vcAVN%%T{628u# zgs=NsNI$y2h46L$Cw!g%318=b;$P=~y4R@tTL@qGw-7$^zj4NoKj#oW;=?%0$DeZu zALEEC=pQuV3jPTiaRvVYjkq$;Il8_{eFVC`iT%s0Z({#4>zmX^pzE8|N1*GQ)JLG} zo76|3>zmlW%=#?!Z`NnAf0^}J>|bVmmii!ceU|zlbbXfkAas2e`O(jiN6QC!vKY{vy5Ldvr^e15dQhAyBGqHcE>tpKAME+6N#MGaO{fpuX z{NtR0xB~w;ry#D7e=PkK*uN;QbpE7siO!#9e+Bk0v%doSm)ReJ{BQP$ApfJk#mxV7 zuG0A*ere`^vp)p+-|P=T{x|zWkpI!&Vh8^?Gpha;JNU=-gz9gx>-`J;Eq36m{R{mq zcJQy_4E-%O@UP-b=088vruQ%Ox7hUlMR5gu&A$M?=3nUji{i?{Kl*d9e^FckU-NJ7 zzh-|9@ozalnEgej{s~{}UjSe0Us&`nEcz#Wt$#Q8hyD>);9vU>@vr@d@O6I+;cNdP zeC`0yXg`OWO_!v1CUcVYjcxB~y${|R6FKjCZtCw%SyLhoM`SKuG( zSk9kjf0`M;68JiPCG?~FTL@prFX8L>C49s$^kVoA?^oj-|xoD(hQf3rW(%%8-+&Yy&j{0YAV|L7yL zT)!ay6TZ&>gs=NsNIy6y!Y|=J=p(aSznJ}vl>gOr8J+F0@BCe_H+8QI?X60e47mjI zDqAt+641(44EH8LD_>LB4AqHNzQ&PDFs^jTkxM|USmC%g0b2Po$Gr*Ac>V_WCP3@H z8i}44-B%;2=f&u&k?48ReKit2FS@TrqUS~T)kxhhg#I6io)_I$BaNOHtTIC3P`?m* zX=q&c)zEz1S3@|uuZHk-Uk$CR`b@G{U-#9J?3VFZ%Y5_;(S0HCZoxPE zd9be8=L3Gs{vYsZ_631|^b6rx8^~q$5z#n$eY76Tz9Yi1=*{d?f?Q6lVc--(zYx*7 zUx;YkFGMsn`89n*@x`$wek}J%{^Rdo>AE5H7wB3c^%Us(AoUUG`k=JbH>r;Rbr*^+ zqrZjX6m<+;AEZ74T_2=A2wfjU9p0?ZQXho6zfJLLsn1d$gsu-#AB3(Cs@zKbEfmYB zW9a&z+9#;Lh2k1@3|${oIhXod2p@F}T_03Am-<_Xf7F+CeGqkcv%akIJN36v&OseR z*9TRur~VeoKbHEqwA9C?r9Mu5D7rp~Iz0MYh=0^EbbSzYc(Xo^I=ormM;#vhEe!e1 zQs0-B`o7ftEx5Kp9UlEHgpWFgt`DLP4_wlZ?r$OfQOD5rL5Vtst`AD3C$$$*eNd|U z4*FXNU-!2#sM1O4Mn0~+`^(}1S4s@k)4eUSLaIP`<_nXV5K{}=~8&QiKQX!4Kxpvgb# zYbO7wuMz*cJ}9AoT^}U=b$yWZkGL}V*Y!bD|EPaSt$)JT`X_woU)Kl8e{_A2^snoK z-r%1kFF1r|Lgi7`H!v-n*LAt+W!e( z`@cHtB_;pY^+8%k*9Q@2gbVv(9bF$poDnY04?2DcU&k+9i|F_zeAFRzeUS8|>x0xs zrt5>0e}D`9V;x-|H1m%-tHOWc`|Hg7L-@!)x;{vKWV${``A63WDSztvAmtxjA2jnP z;p_ZK{G$%6>w}a(b$yWhRM!U)XXtOC>ofSNt`8#4(BGoY+U?BzPxw0j6Ta?mA^uUv zMqHWaG+iqsKQ+$p#+eOq1^vKJ&1*r#1mX(%0gbq_oZk$5HE!V_{Vmcw%USrRdw9SH zj)i}-zKQ+ItZ!ofGV7a^CoK9$e+%IwPgwMi{uYyevpx&`oAp^~sn1fLv*;iFEuTfaq2mLLCkA24CKj?2EeC#t8|3QBX z;alqC*uTvBIQB2IK92p%tnX7FnZ^Ij`aa^!tdG+^V~Jn0zK{LOtnXw0GVA+@Uv9}i zsJoN?)jHggf0!kHxh4NFOa9^5*P$Qm^N1_t2lOXc@+Y(8AJpB^UxEC|EcwUmuR#7Z z`zw$?QFk}Ks5pcF5We;w!iWD@&TsG^^ZY}7 zC(sZ4-*Wz;z7yc1kIZs@GyA(t|L1!D;+FF#`diHN8wW1%5xD6XFW`!8(@nGvb%dhgb)CG5m+}4>$aW@(})wdoBe@i{v>>zKM7y=w-CPWZy|j6DeMaVaZW^B0Uv$}yTZOWCt9vw z%>G6*{}aB>|AepmTL=@r3I78Q&V%rIT$38V6X*mzB>2F;)(4E(!uK3m?yI1GhGI_l z&zSM|mp&FtUl9IIb9Da}ykDdb>c7~LWQ6Zn>pxU+r|#$D=j+M)HT?6(8)sEbf#mv2UbW_1^;goZ&YwghKkFQAzBiA? zG1sF1|IdEWuVJr4WAEBXtgmRV|LT*7d4q?))GNQpKB#o6-d~5GueT4{oTrgzBv#dN zM>O^#>;7WhcP#ra=F)u3weDZmeDd#l|Di>$FS6hL7kkm!208o7#2qa3r!OYZ&)Ni!c}Um#kYDX>22 z7W;+eIuX~!G>*LmXB5My|L6DI{&l~m?@YiNiS+q|=r1L&I-i*5uCFHV-_SozTPv&m zBXJz>KlmJdR{P6;M@#sFp7RgTBWMmj13xx?|F7sj&p&FGiI3m^9nFCT|5v~MN4ot^ z51O;^ek*RJLo;4v#|O2sc{c9OFSy51e4V*4h;KjtJ<)xW4&b-5pCo#J?wnLZtpoM#-r3(_w}%FKBCm=n7i#4i?y%n^Cv$~i%GXSo4m?$@*-zOEemg0S2k?0 zpJmCOW=Uw@UUFr@?(D^{eSfUqEK>g5;IPA1ZO*cT2ZqZVTYh&O_=b$-*k!F~2_Vn8CxArBHT$eL^puAyJor zi%0jdQ@f&gQSU(i(Jxc5BjbkhvM)z1Yd@Nah(?jb!^qy<#m4#Fh%RBfEWYbso|h=x zDqp8wMWx3tpIE7U%>z=TY9}uaAIE+f`yn9W`XD)O?HR}Mumb`0V}{F9H*W17E^EgA zdM{cw-kE6kwc>r9?>Ef@6m5ui_e8YX3Zp%7UQ?xV23 zx$|Y_ahrM*9iC0F7XzY*7Vk2!kEMqby}4hUd)i?m?%eGziN`5B(fG{izloD2jA!BI zvV3yatCTdputp1cyz6+f-8eZ&mMJ=}BJ7pO}>2YN%WeQQL>2db+XHEk;7H} zeuBs`H~-R(0|v?PxktqICUaxzHx88-O79Vi3N>(b4el*lbZkmCeb{HnU+BM+jLp*a zBE2OqaFAK)1Cxy0xGm}}tN6JF&DnW8H?NSPKGE;*XXoyYh7V+(l!&()(U-<^oZrm6 zt{X8}>R?jl+24r4W-V^IlkPCS%VNX*?ILlc5qHjqelm2J>RC}glTs9v_qt^xx_n>* zxkxS|+ufQNE`!R>p%{GsGFq;$+=uMa;cbLmRQwRpznlw|i-#wcz$tycjeJ<>9gQDv z-CkD9yPW8Q$HV?Y|D9xf{JpV%#rFA*S?R>RjNG_qm}I~9Z$-K-JR}(}A8FWk>%O&A1e!Mie|E2lig%HSGqoOc$FwRpDY*^E$8>{MYgDtHB$B{ z`;6!_-*l9Bb9s}!8oTPqb}fR4zO%lR4BuRg=v@`c$!k;65uLtXvv@k4qW?}ZHhpfy zPPeA6idOo~0mHsm_a$fB4-Me(^B#|8v&d0~eaq}0#eDJ`a|&knV)I`cIM<4d-hH&7 z5rc{94;8ga8T)4bZO_Ec-zpGJl8c2UtM;1gwYxwE*{kjyqHFtik>$S`PISw6gJtWf zqbLS942hQSw{0TZz2DMTK2DjL>{4P{BbgzzB+-=?l$K96)FOJLE0^>b7ff`~C3$6B zA>(GkRw;pj(?d{b+jtPsP7@#xb{Y(@7JVe9rp z@sA4wY(IBQ!BRhs=J%^z2-tc=R&3KZivO^vdBDB78AXcbeR$nI1N~#J?G*33HsZ6DH#iGLw^DXMJj$e|8-^>$4;Aoy_1^EJM* z*srbS>mDg%68R;So@HB-9law`$gF|tnFsY#r%S=V(0?ZxcLo{P;7eQd6ju6nVZ*+e z&%SUM-DSjD-sKe>z4SF;!^XEOY*}H<$&lu>``LXX$7ZiQP9)pYfkST>^Zg;J)^QM> zu4N&4>jUxny1J#2Du@zz8qspKJ#PwPqafvm@ceOPy*OSifpM&)Zvbe7Vd(n|lG zWPEVf*uSE-Z4_4eZmS61FJz~`Z%BlwUNo9-@C>u1YqHE8TVgn`9aG-6a@KQq#gIr| z^wy(*I_B@2SqBs}hmzroD-h?y$>5-x=3U-aT57Y|-#%hrDvR z8PPSjrH5a!Qy#-<37xgnj6IWrtN6Xl9L}r+ET_oxMyJz z*>0F|-?d_rZ)A#JetupLezR(VlF28Xf z#xvV*BFpN!G^hB19MbhmKB8}ItR{#0+$7uWd(uT#?^%QB+Bt^G?Z15_+cio)Tuy13 zpKLcJa+v&P>29JEf9fq|yL=LMEaX*PE}Lh>;C7#M@~6E0X*^v8r)W9Mu-&a}`NhBZK?XLW8c6F~qI*3mVsZM?C#^l2M%jICQ1Y0P%Fo^u{&9?}1t6aoL5&Z(h79 zY7{l>n{C1ik#?rx165{clJ+BIXwKeJCFFs7sffP5wz=%QDVA)Ps9b+}?9o)ppC8&r z%Lfgj$X#3}epC&HnBsFNPECuIrM;YxRoBW zy#kGQ%uqz$J=~1w>1Wf*jRA&zTcyk@@2xa^V8_`4vSOk+M{At{)Of`9{e-)yajk3voXAS$lk1H(S>@j>`bcf2a)rMp= z$EQ&%IrHidWV@v$!=?0GLNPeHOtchD%aXnNpB^fQq&4EM&xj6kNPQ0p9&QD;mT&46 zB|6{K^72)92clnEE#BMGadwiCM+EUNmxV zY^tTWzd<O; z;`W5t=DDiLgT>SHOIdF&n{%V744r(2jsFz${ri?Zi1;F3F!yOoW--rS|#%MziH4wmfGbj!wyZbcf3?n-m6z#zFhyv{!6ZW^0QALIV&Pn z;Id@9MY+IeS&N^rUrpz9XDByJHho{!{#&J@Y}Mj0*JUc>3=oqq>JoI@kA*sV7Igyja>uzFBEp z13oL(TqZtZ+=nTftc%Rrbq>wnvw47AH)0&cVAp=pa!~7H0-xPeXqbFF<^s|6`*)Y$ ze=I`!9DljI^m3IZI#K(QvPyB|-2{nprjlDcB51t#<|yGWjTr1!w6wz}jBASPfpgei zA7kHK)AJ7Vsn(R{zs#9|SIgL(=taM#=IZ`G(Yh88Pyd}{R5cyazpm-T(?NBNYlLjC z`^(r*PiZ`J*N)Ow>Q|!0^{(>Rj1@#zm>edv$)ZHhEICXDv=65kEHf!u#%-7*V8^U0 z2FMJPQjiXRDA-aiN>QEYt^M=KsT=AL9iGu!9$nRq=vtR9i5y9d^T~pppWGAb8RybH zT?;e+ZarvD+9qe%rH_W~o+eAr(=M+>;~QrM^4YJd61`@JKUeiQqFWoaIigXg`#Z^~ z>Z%kwy2ct$AE+2ib}1D&RHkpUndpLZ`^s8#4f}>a>Mx(RZ%*SWgNMjF8#sNo*!E}{ zJftGouF;aA@~87>h<4TLAwxIjB^?%s2$lt38S#>2a4NatTSL!R8YGg5qr+)Vx(tiO z8+C07A83<&SotP5jTk&yWi~q-(u&5@%t^*mkFHF#|9m?yoTLEJ=euw&4iqMO$akFmHE_tA=FLwhF;8wk)RgW~ zl=I}-Gt}h1*_4m1v-Az~ZlA-<8H z;=gdcNtSkk)J3i_Uuf8Y^kbaI(UQgTW)F?soLXN%QX7t zP*d>0i|o6_vxnk4LrZX;G$RL_L4Pb_4ldo#Z0wtcZB>0vEA!duO3XF#Mw$j)+c6(c zepe6ZV$Zu~s)p`f-kx{6ljqj0hFCw|uQAL!=TdLZfAeyTI#Zz@bCt1$Vb}4z%!g++ zg4z8qaJ`$ebb>OK?Q^UjjKk+%w`}C}VcYtUo|E%C+Rj*hocj3TkiFdBXZLnDl8Y33 zpVJ%N>TiHTn|`ZKJJ9;8SKAT34^itz*TD_BK8cCwZ~fcRQ(e`lWbYsM=DMZs z&bQ~_gSM5RO6otju5W6$g%_5sVP2lQFO1LKi8*i7K=|OutIQ?)zYd~barklSqli@_ z88y0W2h<@O)FCsY4%wg%nHhD+26f2Hs6#fWLuOx~4%wg%nHhD+26f2Hs6*DMLuN)D zvPK;;GwP7Ns6%E(9kLg7$jqoiR;WW}MjbMs4w)Hs$bdRzt`~L4fI4Jm)FA`vka?^? z9WtN}nHhD+AjX_H{5bWIt{uZ?&J4k8hmnjLUA7zQkPYgPb%*wiNr!Auhpf9cPC`0l zgF0lhJzWUtkPYgPO+^3Vq(e5SLpBTY9t}nvvOyg(uE8nNA#2njo5i^@kPca+4%w`& z(VBF~3U$a_7wV7|>X4aHhpbSCY#bdjpbl9(I%Gf{vUYUHfI4JfuUo7`2Gk)}n^DR` zI%Gf{a0NnI%JJHWMX1#o!*2wk z4q2fN*?hNncPQ$R73z>p^YGiDs6z(SA)9pBHiV)M8Bm9;LoXE%MIADr4q1;cR5k>4 z$bdTJYWEhNTZlSjKpnEm*XONh)FA`vkX3NDREtoD45&l){ZJ%t2+qlY=I4hUew_L! z?yZbu)abI!QHN|$hs=yRWP>_nX4D}Y)FCsY4%wg%nHhD+26f2Hs6*DMLuN)DvPK;; zGwP7Ns6%E(9kN0lGBfIs73z?gQHKnuLuN)DGN2BbV+nQ0fI4KJccBg$P=~DO{6ZZv zpbnWCb;y7^WMGW=0*dK^-zP>X0?+keN}3tWk%|j5_2P)FCsY4q2fNnHhD+fI4Jm)FA`vkeN}3 z45&k9-=Pi}P>0NnI%Gf{GW!K}$oRgjaqKVDAp`1=nNf!fs6%E(9WsbDt2q2P^--)n zYRRb4WqYCyS)&e_8Fk18b;!)9LpG>GW=0*dK^-zP>X0?+keN}3tWk%|j5=g5>X4aH zhpbSC%#1o@KpiqO>W~3-$jqoi2Gk+5?@)&fs6*y+5Ov6aI%M_{>W~3-$jqoi2Gk(~ zop-212Gk*QI_i)?tRctY$ElBEFF;F1jV{|0b;ufZ$jqoiHmE~pMjf(79WpcOkTvR% znNf$VQHRWoI^->=LuN)DvO*m)GwP5P>X4aHhYYAgW=0({pbnXRhdN|H9WpcOkO6hb zd=8=x8BmAJK0+Nbpbij5=g5>X4aHhpbSC%#1o@KpiqO>W~3- z$jqoi2Gk+5?@)&fs6*y^2h<@0>X6xYs6z(SAv2>68Bm7|6S)mS@8Fk1Cb;!)9Lk83#v%gS>45&k9MjbMs4w)Hs$bdRzJ_k{U45&k9 z-=Pi}P=^fUJJcZq>X4aHhYYAgW=0({pbnWCb;#h?IiLl^`9mMjf(AGNxMy>X2hlhitm{8XAH+WQ96p z6I7vD2X1#bU#|zF4jE8~Z1&G=7>qh(KpnC!`BH`;)FA`vkoDWq14xGqs6*B# zQr{;XGN2Aw{Z#h}(jf!tkX6^$=aCK>P=^frJH0?UWI!D5u_+$ngBy;-o_c z)FHDUQHKmdgA|7!r#=cTnUaheUG^jDkiDowW=0*d4|T}Qs6*a@I%HAv2>68BmAJj5=gM9WtMHs6z(SAv2>68BQf#TAAVpb;y7^WIhK`hYYAg z21-XAGN2Bb8Fk2jI%H0NnI%Fj@fgt&D>LY58QO}ts7`2^BGHP^9 zx5~+aQHQKhhir=Wd6jg?UeqC*?7J1|kiDowHr?}GAsw)4q4w-$2I%Gf{GBfIs0d>gi z7t|pG>X4aHhYYAgW=0*dLLD+Q>W~%ckeN}3tWbx{j2hiI{FwF8G%xW%h||YdMvbny zW;%wT4q2fN+59y8rC`({E7T#I$v@-@K^?L}9kTf@WxWv8AuH4&n?JfV4nZBVLLIWH zc0Oka>W~3-$maXGGlEfv45&laZ@&6T5bBTtb;z4*hn*;lI%Gf{vbW2w_di4(GN2Aw z-D*^LA?lC;b;uB&rS&4zAp`1=;l&9Vqfv(ps6&P<$DfHt9kN0lGK?G3E*f>n3U$b^ zW_gup)FCU>Aw%IdtV33)Lx!iU4w+&V98I!%ocbu9cc3xH(Ab5VWI&BBGwP5P>X4aH zhpbSC%#1o@g*s$r)FCU>Av2>68BmAJj5=gM9WtMHs6z(SAv2>68BmAJa~RYi1L~0Z zyh9x_pbnWCb;y7^WT5t-4jE8~%#1o@KpiqO>W~%ckeN}3tWbx{j5=g5>X4aHhwK&4 zt0NnI%I`9WM9WtN}nf--2WI!DW~3-$jqoi2Gk)lqYfERhs=yRWI!D&J0BzGN2AwRmia?6m`geI%IgUjwcj#$bdRz=-XC>pbi;O zhYT-goEU^UWQ96pn78R(VbmdeQHKoFPShd$P>0NnI%JJHWMX4aHhYYAgW=0*dLLD+Q>W~%ckeN}3 z>_Z(gGwP5v>X4aHhpbVD%#1o@THjzs9daCgocbu9ou@S`wm)i;0X4ej#I%Gf{GBfIs0d>gCs6z(SAv2>6S)mS@8Fk2B z)FCsY4q2lPnHhD+8gAxP5jDy9 zJ(Q!&s6z(SAsaehP=^etLuN)DGN2Bb^PmnHP>0NnI%Gf{GM|H}Lk83#D>@c+$bdRz zX4D}A>X6yas6z(SAv2>68Bm98IbT{p9WpcOkQM5XnNf%ALme_R>X0?+keN}3tWk%| zj5=h4I%HVN!@fXGGN4A68Fk2jI%H6S)&e_8Fk18b;!)9LpG>GW=0*d!TmU9)FIQ}95e0H zJx+ZT?{}g-Rz8ntzZEsQ>=)D_1L}~OQHKnuLuN)DGN2Bb8Fk2jI%GZ;b;y7^WJSJ1 z9WtN}nHhD+fI4KhA?lC;b;!)9Lk83#Goua}P>0NnI%I`9WMX4aH zhip)X%#1o@gF0kp)FB(xAv2>6nfAw-QHLCd|4DsB9rEAmqj=vMX&(4IBK-qublESc zLk83#v%gS>45&k9MjbMs4w>_y4jE8~%*Ub*8BmAJzC#@{pbnXBh&p6I9WpcOkO6hb z%&0?Fs6%E(9kN0lGBfIs73z?gQHQKihs=yRWQ{sxX4D}Y)FCsY4%wg%nHhD+26f2H zs6!^b3bUhKiRH(skMu4?I(HlmQY@oJm;Hh|WI!D<`wMl*fI4Jm)FA`vkU0gCs6z(SA+z03hYYAgW=0({pbnWCb;t^J$jqoiR;WW}Mjf&jb;!)9L)NH6 zW=0*dK^-zP>W~fUkeN}3Y*2^H^`Z{hpbnWCb;zV2<2;U*ES4XqKGM5M$&aW*CQV>0 zqehn*b;y7^WPT?Y>W~3-$m~1RAp`1=IS=ZP0d>gCs6z(SA+xPehYYAgW=0({pbnWC zb;t^J$jqoiR;WW}Mjf(39WpcOkbS5_W=0*dMjbLU>W~fUkeN}3Y*2^H^`Z{hpbnWC zb;t&F$jqoiCOs$TM;&q;ew_M<8eQ%$>X1pJ8_THCWkww`pbnWCb;y7^WMW~3-$jqoiR;WW}Mjf&jb;!)9L#~E8WMw)4eF4YQHN|$hs=yRWP>_nX4D}Y(XTlCIQ4O58EeC+-xhc! zAL(qobp5U#0AScy1uW*?XmNvjytEv;XwIQ ze`4=zrrbNJB!8X6Uf<6xJ*qybY4^xBw>YHM54P9w3fK0<;XwJX`|P@L>C+iNa+lV2 z9yqo~Iv9T0-iw7_NDWnn*z1d@JHG2raG?BGJKH@z-;@xLJgG@-J}59Rk^mg0}*M;M7p!|7%xBE~B=6XSLSSfp7xololXx!XtGYY*|8G84#=Oaw26o&)l zKXoh{x3kU4<{&w$PEJnGc&91UTbi4BNwp@hGfh5bHLy_}4wV1(Blell)-QDg$%nFB z=W*c6bRFP~_YU)vx$WSUj&=;$SgLIt4wV1fitG5;u(>aRBCuNJ*Ax-#j<|H#-gR-YbGmqc*Y8(!f zzxLo`eEp3Y`X)%OcjG#zk1qKp+>K1dWq!IF_bAWWG5>{5aXC=_DO)G9?k*g!^^$*1 z=G#K^g!A~mF663y#ymVXaPr4;p#0b#O~*RziDhgvGqoAp=A%5+7wjXm)8AMQlppQM z5sp#J&Uh8ef%4;c$a$RcFqU!5WTr6_$3|uvOL2^4 zcE;OS4wN6qaL(h5=dp}qJ~NH^IJPs>wE(XX%+B>9mILL->k;R1u1B$q*DPkbX5qDo znXYAcjbnDMcd;BOKVDBck8?eZWxVDx(=`{bt;}>S#%naQbG?q`K>2Y#zPQDmtr{{`F-M8 zpD5EOj`fN5#Nj~sMSrzqVG}L-u7y40aG?CcUs|&8sTRJ|A|B#!p!_15XZWh9F+&4{tfi19EE z2g)zTTO(PF$wrL5MvUiiI8c6Zy)cr+HN}W)hY{DKI2{@7$}i>{MzWZb7%}%SVm=dx1LYU=U&Y}-`Ne#d?8#-~T#IbZjPola=C0%;PRIFG z91fIU%(p2X_*k54QOq#o{K|;AH^msI8grO&er3eH8;wz% zj`OQH94NoI-=y)7kHxtbjhW0izcS+9lg3z1$N5zp4wPTqBhz@!$KqUz#(Z1Xh15pe zJJU6S({X+khXdso_xp4`;$v~HMb|85oL^~i?@!k_PRIFG91fIUtXI(Wl#j)^7F~0h zaek%6+67&sIUVO$aX3(ZvF1bb6FwH_HZ=EO#(5FVPndBoMDrGAoD0P(k66#4`34`0 zb2*xmFys79i?tn^!*Dvz-{Nqf{1or;`>xnq#^!bNyLND6z>NVn2HY5MW5A68HwN4o zaAUxY0XGKR7;t02jR7|X+!%0Uz>NVn2HY5MW5A68HwN4oaAUxY0XGKR7;t02jR7|X z+!%0Uz>NVn2HY5MW5A68HwN4oaAUxY0XGKR7;t02jR7|X+!#o(7~p4PtbN~dnGNCE z!Howu2HY5MW5A68HwN4oaAUxY0XGKR7;t02jR7|X+!%0Uz>NVn2HY5MW5A68HwN4o zaAUxY0XGKR7;t02jR7|X+!%0Uz>NVn2HY5MW5A68HwN4oaAUxY0XGKR7;t02jR7|X z+!%0Uz>NVn1|CrixZmhuL;v6TR#9X`#$fz@6FIudhO)C{%73G zp^sl+-ZC-B49Rc5U5&pD{+rYB?*>iBjK>)~p1-4pwFx+Zq= zGdtx_SxKDonVou>@lVtqW~ZIZPWzcdqO&gcf0v5tr~0T&Y8TZ_PQWI@yWpBPRQ;&ioA47n`n#o&3yBIaHRvd}gO!X8aSihuLW-v(tX& z-CrDt^_S~A8v}{dcZ(ineBybB^(B0K;&~TJ=L6N{oR9u^PLS~g&pWIy;l~p^?_&Lh z=Ups6im}D@-QT+wNZ(Pc*#B&dy6oD)je!J-0ppx#`0M}9eA{_(SRb{!)Iw9jF{;s#DkvtnIj8 z)E+7Wf7UB&iwa~*CH%rRqdcire7?}B)Aik-v5{zehu1Jo_vVK_KBl)!T*y2m|4vOm zly1|GF;m{Pldmw>E?5rNRPHk$+`Gny;{mN*fO8L_{AJ$DSe02fzNAMVJ>{kJ6VvYK z+!^vRZ>{%$*hlHan1`A2;IUjj9gF4j8bV~m#Gn*GzjK*m=g#u=jJnPo@=Gp#X3<&Z zWFc*J$F~nK>k9Aa21~Xu?rTXtN*dAhcW zQL@>ng>;~Xp6AoIjI zR`f;IrRA~0CR(&v%VULY10E}4AmFhgHngl)9xLmT`DGrNPUj4sle|8YF#LDse|F6k zW0dC7JfHpx%zbk5|3&^g_DJHdi+=xAHsk|3Cq;kb#cO)~pmUDx%JqfkKg8VflbOD^ zs_$WbvU^Tlr=*X0O|RB^S&PNYle$dM^h3u|8vTu!^3pNHR0fqrOl7aQd}RSK)rsj| ze>&z@{`^=DGnIqoGgJBa!%TJJ-{A#5$O%POO7@*`V&xBHb(UD^ZRT&nlP)H9e4Hc)j4ouhciIuNQ>WmD>hmy{69FDPhIszOhWP5}yBA zPH*{1ZnR-z<|n&PN85Utsh(vmLYXIZ$zbS*%Aqv+8!_eOW00u~DvQ#oY^-k~G1ZUh z%Abz;nJGW{$X^bY55!bH{xEZ$CB4j4CmzF0bz&XNR43NKyll{U^mS}H+Auah+BUWv zw0Ug#AnK*K^tT5@J3+J`wiYNC>hz1!wbL)k&rEd+`%wAD=@<8nnCtx0&eTrMLv;$j zD8GNnUw;1*`~6G&U34x}Jgf8c>z;D@v#QnC|tbWBHs;${WK=c=u_g@_1*bRhzD8F{>M(KWgg76EK}B_ zzoBN)o;=SVXy4kuckQHcI_356T~irU79B`sg4$al|%cj zluqT-UO6$<>C9c|pN96n38+rmD<`&f+WA#T^uB13j`xhQ`T2f=^5cKBC+{yG?=xfT zr8G{bIz>BaPu|~t_@G*2-W#MjuIO*<9==njp^B&+VYgT<0M$u-rabr`IJRIN0ojNW zZJlp1qb-B|=b2>6C-S>~M0+^C1+vXQ&5zWkg!UKJVgGw{=N;9T(C3}gDg5>5&O55J z?TB6`=j9zduKCwmDV@^jZ^U*l-JYwG^G$8Wd;0bAXJ42(MP265AKzJczk4NS+(TaI z^%i3uRV>XS`l0ij(&%r*l$VYnrZT83Vp}%V&iW@x5AvsDerC##s5e-&Cs?#IShPPlW_QVqPQNJK z-(SklOmzzTQ2C3Teg#wCh^bEMvn}TUwUe3Z6n+VckAFx0+KppiN8KRWU*Pq5TI0`j zV=Ko%u{>jZzd&2gb7(BFXzjmnp^cp9+f=Fa!l zTPY8`)(qBc#cMX$5?>_g|mh_aR`TV zd=TQqA(i8g=Q#UxBA%%|oQG^F&I=Id1@(*bkS)deg+7cuzsNquiNiSied0VNJ98eg zrQ8R!=Ws8MS&DVruM2VZ2PxKVziKHuXDAQZQj9<3cg{n$6ysQ&{X{X2;eHDJXRl>0 zyLND6;9mSEyP1(N=i+`eZXTF!E^;=q#ru_8Vzn<&-ozv+!I-c@SdH!`_w5xe@$m(E` z&i5!zerBf}pgd0b%uc<`_@~%)aHpM|?zEqI-N#3x{eGmiV{8Yf(>gZR=P!rWotbG3 z+F2{*HB&L|9N17wGE4&=% zWU+H6o);y|9BJYsozvRAKQMRVDux+`I#Ty9KOvXox_Jj zH|O{y-(^2A#?R()?XTUN=ePww%ljI6za#I1ockA`BjtS){xkM|O5SJ5`>#fg7GUhy zbtg=Z)h%Iuy5Hn7v7FfZJGxI2_hody$$4aq$=Gx5H#rXJe8e#a>!bhvSruo*nQ1ou5h(S9ZwL^DSOcQEZ&U1KhovVlqOEyy-(*|Ci2+Nv7!mnkxs@y(uL zPPJ^0F5I^V^Mv+;^xRUfGq)+c#8Lh+QE$hHwN4oaAV-_#en~r3HKdbe?Dsf4xlFA z|7=K{X93)IaJlbK`>XFy!#O=Y^Nj2G?mM{14(>a+{@jbfYZ~v%*nRl_%;G&rao&+7 z)5ZIg;^YzUUvl5Ug>gvl{u1xnit`>Vk?y{O3vGq(dD9}sv@;jueXE4wzcbfK!fPwe ze&%0g?vvaLjX(dLHKQc{dg=FHWkWuou@!&)C8qZU(R-ihc=4{M1bGM7r{QyhoOe|{ zvUhL|JrVg>zJm*Gxyb*Hru@HuyU72JrfG|kNBiH=)cNPE(f)UEeHvaUmaVT7_8nYU zU$FD8sz>$?uAwK^y6@m}-bp3ip_Jh7;3~TBNRaa`Dfb;*Xn%aS7`X4?`a9Qe_gEUE z|Nr-b{&zoQD1x`|J_v!sv$*Q6EOXnJF(FL+Mlol|@WtyU+h7 z%=5qQJGiVC8^bL288Xr-`n8IVei0}RY2HiPNMh1Ek~WfQL>cd0pb^SP5y=N;8y z|8w8LMRuTgaKW@?7oAGzqLW{bn?GThu<4TvE{rQ%7}MEaUObqk9fC_`wlLAcb5AOF83W= z^d2%XF1zpG!t;XmD&2Q*{dv#x|9{^^k>!>{R&ecLt?>VEhd<-Uy$4Th?{RW{htZ$t z?z`=p36EX8E@02#w_IjJxOQ;k;r~tyxbLz^T<@}w?;(-w`Z00&5&eblqO;=+t;5qA zJdL}wK2K}&b`1XWod&d?@2utf-{Ho2XiXpUGShMX^?fSOzrIiP;Jfeey(9_${u6xn z9lc}0P+hd9@1N7tz8LL^Q9AxdT0UmlNAs^o({K7WWpMt^OvlmjluqSQxx`ctzWZ)5 zk(17A9!`E{ryQU>PWjAEz0CNh*mpiS?c{W){mgi-#rjLK>&L|9M~Vac-~XL!yxU*b z*Z+kWFwTjFzy4e&aM^Da*CtL(x^cpWh<`lz_uA<@DgN(;(DzXMdmHrK6aOA6?T`Au zUqZkA-#ekd`@fGu$N9gfLgo3tze4paD{^=N?fE9{W~W|er#;M0 zJDHvKGe7@Ik!Y;XpC0=i9r{)Z*2n2sj>7twvHaNY-(bCp{_V6!Q9fcij*fTQudqID zKh@*^4h`*-`TOhS*P{T!z14K!`HI; zCT_!;)qV9lbKhf@>BCYl)Zabz%)jNSa>b{ccHYY0kqVT5XRRIj+rCNJhO&HlZ0kNB z>*u-`RAfV0mps-R`i?&E@!Omy(6M2|tLWLymvf##$A0wSE#KXm+c=M`S00Oby#740 zUU@9$SN^*Gmt&Q`&4G@^HYk7J|E1p8W3eyFZ$nwHJQi)D{Jy|8|BuI_ZI$1TfsREV zDSr&edgZa`Yp*|MWWDm(K>1}JS&ocz=N#7*56-#I?2HM_&RD_xPadO+yxiO!qtK7i zzwsHDWF9%T$T38w%W*^Ikz+-m{Bo=abgUdJWL@%DIabJe<*{waq?B46yvCAE!?0GH6H#wh?W8?oa7joxO_8vU;J`t}+iT+-%`mH+)Y20wvqwM#^ z|LS@a+Ar8YFOv6h@nLyvd|1wZxz1Oqa(f?&l$-UQm4Da>u+;I2xtd5=aWA475 zt23APm~y>c&S(DR9y4}NP|jxp9V_QEu7>lUqv3p9=TTDE6rZ`1%p;GD54-aycOE6j zH@RLU$HqYSZh?*slwX!F?-^wbKML)EyJr6Pv$5} zJC$K)(DH@O`@H`nch8i{{88_kru>qroK!37ayhA=kA$itZ}}+C(=V5T-6#5U{=p*( z!p?4MnNM9!4>zLDFz+0FL5)qHmf!EZs{Ce^MdfGS@ZxZF<9G??#cyU*V@F3YPi^u} zwJA3}%m>dL@RiM0p1JG3jymdG81v9!OZAVd3NtU6eq1NnnTa{Ev@_L;&x5F~WJAfN zU%%(QSUZx_>7BOK^Oa(z?{eb1pPA`$2kM{SM|Q@)+sa?&x>$5@tim47XlIaTKij>)5QiktaAzsKCO zVi{BAxfaZ`GL<*&7a!!<{yWFYHb_Qa7{4#jNBrJm`n&y}ru7~Al-_mDe#GC}?`w-SXANH4H zH)hA4%uavVk5q?0<`dcuqt&!%tPh-iCHT2~pm5eus*C(jb|iMreZPIME$f+`v4WZ6 zi|k1Gow0@48FQE^PRU-B2kjT@Tgk2;AI_NksQl>qD{=Wto@?0%a5+V5|_W^xhC25W8(6o>#xM+FL|y>cKw*R{OI~CarsN0Ym!|*CN4j^{z_c_ zlINOa*N=(IkFLKGm%rq>CfW64;_{>Guf*jqd9F!z{g}A?==v*h`AeQ_l3hP0E<AXREE$5t)S^d&0g41Qa z539^Ns|uP=_pD*pVd6l_$uD<5=VC^ zWzI|MSDB!EzkBW7JkZG z>~s4}hqSZgK>24q6>dt!6z4ulmi;=DtE3rHW0)rUG~X3&Hu&;0H=X4%87kCa+YWfy zW2T+$!uI?-$I3odzY(U&9kOw?HqB&pw}Fkfw~FsnnM3n%-=`h8rn-KUlKE7pOweik zkKC6hFBgKr4OcMV$`uBi-|oenc4Q=sJ9wGfiTwfpGadh}dRJ#1tLu#qHDudWYqsb! zyYn$`{N%h&16DsjFlkzobKV8EIeeMdWV@!B_kI&%md~2NJkVFp?3!7IIkFA<<=U(4 zm-~}E=G3Sr++XQm$&a!PWOH%N_>VkzOexd+m_3&z%Qo+dG!SyO{HC{ng7nQGG?Z(jD&l)er7wL+8hRD@4U$6A9=P2G)VOk^Nzh) zAgJ>9%x~wpr+(|2jNA5V_ODggw>g*}YQvw z`b%;`)TPsxgXn=zaJ`Z%ycYzy7SG`HE-iDyg@s=+7hjqbhDP0Ie(A-7YRar^+?U)> z%v0B=7Gsvakoy<2R(x6f=y||!#4)KQ(EA;6f3vqkKW;vn9l(Wwv zZU{?dTBWhiQO=&2$DBE}oy&Y!19pBIsd0ooqgH++quWv z1sZtoy=yt;vjx>hYiyo`C?_h(2)%2oZO@$EdG*qBwk~g*AYYx$whemtJKlu_EkAXz zlA4pt&J%X`o1(Vt4CeOF=&?f$?P%u-H)dW@XKSVA^wpQs!;X*ayiT_NQP%sj=dk`G zA}hCN|ICFtMb)Cry;rr;wKkPzPF8ZK@B8QM94}jw&DHK+u>H-JB#Ua;)y}1*PbELB z@Z=qvn74JjsWQ$_!7S}8IX=gl*P3n_>^$cv zS@x^RxW&5e>$VMZn{?LOKMv!1kBs=$mwb+$5C7HtvX5ocELZpI6y`Dy)crvn?~#Rh zgh>iB2HaP4PN^5NL+u*-nTt#>3dcPQn5$$j4V8AcXP!4Z5*FV2mFHjyT|UmO=o_ot z&eB=F)fHQ3V;*^Bp?)sN#@PAU9ke%@jj`w@Kl@6qwziUXmi%|h%<{d_Q6uag~rZR~ZOkQwykqip}Wa|*-3-AkG4bqRxgXS@BIU!;%z32l=$j}J@R zzR`J%?z+<2cI&>py2>eQ+Yj1YjcIq(+B0YM7_S~=$ClmOpH-iIY2yK}DGIN-Y|n%! z^TQ`SX2XCHJZB!NJ*I7RVLmT{+D4drA7^2|+^JZ~yx;v*=DRNyHmUnAWB$2TRz9|bm?^k91tegj;^f+!q!6_cd{!t_L zMeX0pL5q5&G>vI#Uk-ut&rV|gu4NvmH){v;{@+u=xZZZoS>mT3)t5Ewe6RSl6{_D6 zJKsxrv6s4<(av4l)wtr_I^53dn(aaG~hMP}z1~K0p=`qQke1?7D?ddT;uItG@T5_YDnew2d zqB3P%Nq&@VD6n%#>~s3@VLVS`-@~x1!G$7QRql|9ryU=QbNPO@Ea$nC&L} z@^_B?scQi!PdDo7C+kW-Hs^4`r^7}7s%fs3S+qpdhcb10gMOtwi zGBqj+e>}C2xkJ6I@X75%|JJsLRpz(@XH=2n>G`@)@0rvvv(FVpZR`DV9=Kn12lL@? zf+279Da;=hEC2+~zJg4?R3~F|+iAlPvrGO|wfX)st!17k#GPR5!=jIZu4@$i962VI+Lt{TJ>_>x*HKXI4jUfATCv z;S4Nd&eb>@`sG_@JRfPjj?dGFRn8Zae7bJseB75FM@H)&yY0N?&esKWrA>C;vZa15 z-^kDGyk$h!Mc!54+IdUGHT6`Ri)HxOBU9$6rj?2_=X-sxdh$VbW@$so30<$WReboJ zAFivQXHy!AH_5V{CkKqwW1qD5#Vgii)3<8bd%%7ZSI6|aZ0(b@@7LZ{Vb(qwx^+-3 zQrUUk;OO0L=AFbe52g7N z@qepcsvGC}{2sqL&qSJv?QeT2ZARNtCgobY$J(lOL8I@i<#=nfJiVFM=qz)|^}p(3 zUF_cUt2sC6aqs2_I(EvPxAeTAlFU!%N~im+wc}p>LLFlY-?!u5m_bLq>(1GAj113p zRaZvawVGkna*p`=zhH!nrfep{eaOr>40zG0nAU&P^=) z^>>b?a!#kO7<&)!pLoIMLXbMcN^XzjX6wqrd(*w__qR@$hZQY9l4i)ev6@c z>dlORGBq;rv1>w0!4uhDV}4l2R;}QHsyD}Qy-A08;Fqqg*;f6hmxJK^;au0v8Nslv z=2Yf4zR3lby}OuOE>8|SUb@X3_UiZQ$fhi8W7)QZD1Y+2^f02QJzv%qDhMZbf2_z> zZ)PtA&s}+qIbWej&_$9mr^R_}mYDrjDbI=JkzIqu`HrNbcesGi(@=@-cfQJ1t; zd|0+2J}k?ecz=-^{9_UJ%SX$eSEmM-WnkXZtQ$_T`B#`+S!RTDvXT)1z9Sd)998$s^kwxpSC4@_PyPb@=*C z`eG-0o&C7f1--DmeXs1=1L@8A3upLzY5H6O2@$KxfFw?qaCq;k1y0D0eIUdct;_0mB;=x1A?=8NsS41ZT z%2U1KUfnlW4(1)N&(%w}6=Sa0rMcc$&)#!o%Cybbva7ZKFI{F-d+LU@zx0>ne?r@+ z4gcwyCG))2GDi7k+xt_=1*X+iN0Zw9hzdQ2t98fhxj7(Nl&aCe+Ul?7DbVl(wJn{! zhaFdazj_PzmZ&ZDrzC-(qkpiE$~DXZC+2;_oHnL7M0a|R`Gc3s!jz6RnAa5WK(DXg zVZX~ZBt-c*Hfp@~aXYUySftBjw0lg)*0j>uoPErZIk)*Doj7UXIZ&@JJSQ#GuP$oZ`8$d(Cclx-u_CB5V+!* ztjX7Hzt0WZvwzCmzEDcI|FqRtq>VhLer=rDP@Z3YSfZ*PwfC5HpYNm;p4*hZKhyW# z{&(zpJ5+uqCiU<3x_0|QD&63FJ67+TJ6IQ4WUp(pC$HDf%qhUfHd^?zzFaUpbLDr^ znx9(y%54~fW8tt3o0uP`zNGJg`%rUxu`iaj@|g4^2J-n56Xk{>MW?90^Ore8ZyN`HOMUUPHb z8LwOa7Q%iUmJD@qpV_^MzTS)aYK+~RNVhee2^wklCZvBQKdkbr+$&=yT&c^pk}U00 z{wI&A)8GWJIn3G|X{s+g!@h`59%+-kYo77F;@n418B<)(cs88v(Bjikx?eJTeb=)$ z>L)ka>wBJ@XLZ;P8}oQSXmFiGliw4fOj-V$E%TaP{kC#lb8Cj0v;D>~_Zt*$Qsphm zJaCK0e2}&{$7j0JZSU^cHf~SV8Rcu{wLD{61zokWjo}Q3rs#Dmo&BJ+pXz-_b94Fs zt-55rfw;tmAlO)XhNAe947d-H<0ZQfGOQi$eT*EyvEA`$54>?=5c{{xgR+qRiOTHv z6eEM+-Q+Ww*Hp*}Bkx(g;!|%Yh18esb9&lz2UYD&+1MuM_Rdvhms`DJvLp4?zC&d= zeSD)RZ<%xU9%tRca=wpNSv&V!8KS$Du)ZiXD#g`FiQmi8AL5Ueg#2?w(O zb7v-~1;%Q{$EMq%st>aou+KiYrq29qwc@uv$OQRs9cO>FZCw~zY_%GLn6Y87u~t`3 zzrQ~cQXM|Q{`w(F1=y80AFoSvP96#SyCr8|48Bql8oo4;IVgES$QHJa`NZt>P;cN_ z=0Gv?Pj0h};T?0z!pO@?k!^1$@xZ%fXR}R;84pyxScqfz+5O>AIkkN*VBAwBpg_ry z-1p-{@HhGkFNt?%qWjo`;%iHHLeLC9t`O;-c%+Y8&Z=W(` zzy74IozKso^no65*WM%42&$)t-?H~pwLhKfn|0CNPi0(E);njlhvPX=I}@TV*~cNU zMGd%U$Mb6Y-&Sio+iU2X&2p-%MeKa?RNb@HnxC*^%jW!>e0#^(F(*xfmO4+69gB*l zo3AUMup07&F27Lv#k%`!t6!2VZ8iH`Qj@%h)$g4|9cGfqtZe7_mb$kIA;G0iSC{_m?xL>z3wouXJ6uS?7J-bX0M+)sQWF z_1iyZXI_;qiHZ8m%S`@vAmIcGZ^F9%Ny4dXn0-t)kLTDAYpr_#Uwgtp}?bxhrBmYMr5 zS^De3g17VqPf5;GFL`=>Hrm>A`|*)6@7}id?4IeMw@+4U&oo;)sF4rCIRCm=mZ^@yWlqr4PEKfllyxzueXo+IJS~0e5@0NbgJNFu2#>&L?xD-sbZOzp$_I zoR59>@Soha&%W5DZ$(*sb;+eO_3F0P4k@-isiC;F&-Kq&`Xbj_yB&_+RW0bewdWgG z)2Mg0+8CJs)+;J$Bl{e|=b2ZkIhzWx-DE6DPUw2c{;0R`YZLz?%l5>FrGK4gPI;_$ zo<-F(<~z@*GCR+%GCR+-8p`85>&omr1Iz3@8_VoGyUP6Es`u@@5vJO)oZS8-r#$A9 zHOKf~sYSo?X5JvpF<*3lX;bs%XBG9UfBB+j!1{&E)h=W)UtK=TeDM5jy{Ml(rvlkI zA?kYhn^S7W>I`f{$!{;*ptd)(Yotx;j8r?C*g5cpl||Lbe&PRSf9Z?(9NQ&Dd2{27 z?>IIj%RUzWCc?b9JvH0*i++)2N%?D>KR$V6UyjY&pb9m%eW_n1jkfqF-e+n~6igsd__LQ6ub;&a0!|hUqs`AC{HR$sp zlhm$mc8+wp&ZlbYuG~Q9$kiG*RlPMSn9u!@8D4zRUSD!V6@k}(v-@`yP6p@qLVG>zC;fQgAU$q%=LFhLT_`5`_(*I1=y117VC0fL!HAXd6IG) z{#*5iZz!*Cw6=3y$?u--?Q7f3UI#mVJXv_?6ZpfGVfMb z%G>Mg#@TmNiNbaaESM%MR9Amm&sO))HEN%F%g zU;1d)#^Ju5b**2*S2XZG=RDu~S?6H2qpCeOU%E0@O?ts#ba1WAFC2SC#^i$<6JwbF zs1piXUl_-{?ru3qvfMsj)2+7$3Z(17@i~2j2XfSI<)fHfT`e4be>#}sGxFn5INx{- z^P{Y*iF+O?bep?oPSX`BDBKa(835sZ| zB`CVw1EZ>yXPdk;G#qyAE%I+Rk@kttu_cNZHghJ}F~8=a%;xE@>@{v+vAg=}v1A-q zqsM)%e_ED<`IYM*=&w)OwbSqNw$z`7+8932ez(t~Y~M?L99gaJ1KW3LE6E96ue4#E zKgz?;x9ysF&OILJQzjGJFoQP&DpbnOHmvw!NyzxrQ0Aci1)=wRt1sH}aYpD||0Jg$ z&2&Q*1Uvu1xv|3gGDGqCDC?4Tix10o#)l(wq&KU#{LKB`x2AyU_T+kIwX3A57Bq!CHwgF(W&az0K1QQ zx_yMY{+8X}{BS`#@9a11yt?gkqkMUtJt$^vA+4|+sv67}pl{eTIt5Zjsb?NQCSgvHKW#68J{c?B% zzM!YA)uCmo6lOAK>B;3MM471lQ>d$CTS;D=?X)*)yVb^Q{b5wqQrJK0W4-PNe1me> zJ&P`7p4J&2*kg+x`9S~nbFqK3zx2i5DHFAt26en_H`MVO)bTQ-j@O`$ml<`u26ep5 zsN*%LUa(6csb5d$7@i>tNztr(sv0_m$WVFSG}lTWm}k0-&3a;EbAS`KKjIzhRiS6dHV#ao|j$GwM6*f~km&+XLeV7oS+bi^XH>kqp&o@M`c>ZSErIe)h% zNugnz-`Nhb&5|Eh`Gc0E0Mo+mg-K4aFE_kd=2LFN69Yrw=kQ6)S0cmV=DlF%p6fi& zZbd2f%a9}Z4Ai~_?2BnD%fQ*pjWqTB?KZ_=P0lE0=?lpTQCIyR=BePGcK#z-+HLp7 zZ@t6Q+PTn>BhRYCUs%7yCy%rhgye!^PwZx!98MYp#jDI_9(}e99LrpvIm^uQFktR_ zwp9((t)I!ag2#MwJ_0hllalT8Fn_;AYi!%W1hUD!UajS4pHCr)L)nxc>yIcGJqY`^6A z94p%}t8ymz{pOFF&ZBKzuc}%DQt|ko<@s%@Z91!0y!FXA)zoA4V@-pLs3v2>InU9b z^LShCwAYtsXD#t%`^;W<61x0n4!x&8iL!gyYkTd{J2Kh%*!HD&_3AmvxNYUvW-;T& zeb4>6+^~q*QT`)ly*bRBy89yYn6;6nmFH(3PcC5p7u~DN?<0M6exx~B-|h`bdrE$k zZE$q^+%L%sz8m1p-p<;8`Z8~f?~i}?h4f3H{P;dSjqf=GiUG;8k1?nj=;LSx`d3V1 zE=+yEHq2Q)hnZ@=Vea}CD5o;|**Ob4^`tOv963<$IHYzVXS%!no%I?s|YJI|OfJI|i5{VAXSS(txX zdt}@2eVzv2=gDz`@AEYHK2MGTe4nSm_jxko`#cT4&yyM7=c)01ob`#d$i&yyM7 z=c)01p3E|~B`0*fRQ_Li&PD8nn$oY|^IfcM@0CKMU(?m|SzXh$6zlcNJMI3_=Nr!H zD$CMwJkW3YH`QtXZto50I69uvsXQu|n11~6;H0z7o&0QDryORdd}gO!wyo11W~ZIZ zPWzcht7*|#pFiD;_4)HFtdAMXQCJ@{manirX8KM4ruN#uuV<#?us&ug59{OhQ#}U? zXAPzNPCED3$*)B@%ue~tPQ8ZmIPGDkddM!6PW6zzh|zwr&)`aS{g}A?7&gxXHI4ws zkL0>3pZ2{x+OA=?n%dvHyS?SCqsypa+U_51y)Z##({_KY^>m}Q&$8O8)PpXn3iHzd z#mUK-bg*KAjo}IP^F#ZLn>lVP-3^6jE{$Ric{3aqoG-%sPpCI@rFXnD3)%i&Yf?)! zZ)$ZWt6R=do;r41&Dm_fy76pw?qi7uNnqvg_P+9o+c_ZfN;}WLJTM5pEkBd{RX<}n z@OFHHIe!NaeDq9zw)rsBtS!twjL*~jd&|P@J5@E=Em^K0SbJ&~^Z33w;Eu=6H}*W6 z1THnT^AOta!h2UfAEn(AWBc>vebJlZ6>IZ6WlE{@S8a@q7&Bg-OJn!Hk`2}>=!%W8 zK1(mCckkO6JN8OCh^cU%ZF{LuerWT)jj=grLSg$;qd7h4>*4U^(?ywOoJ)R`ZIHf; z4<9*QMKAx!#$kBHZ+*Yv+6~3Y`S(7L>Eq~~Wcww@=UCYWS}VeJ9F8kmE5bD+W?C!4 zH6vzPE5bD+W?C!4H6vzPE5bD+W?C!4H6vzPE5fx2=0{oA!9C^8mQjoO{3?CKW7eO) zQH|_YvO|Q?uV>+S$o^_c6FTEf<`sy zb)l%-%U@*7EZddIc4zU%*FgP2p!vzevu-tbN7 zWPO)sKo=c}_u%vJZ{B7{|KqK}9Jmdrb1KxdHsB-XBt9)5beE8M29d(|oc7OlW(!IXtirVpQ^Ze*)pZ#X93pLwjRehh10BV1=&)!y< zyOm&W@KcNm?PGNji=Voze&3&()3Y_s2)+jP{B8MhAy^w?_m##!8wS~?b!R)QKO6}e z*Zs)X;!3!#wrz1sUO$Xl7Xh!GPs{c!o~I<-uQH7JQ1|@M>BCLTq`SvG_P4+q zr;}S#F z{jNRtAJ=|K|B_Y(H7kbfLs}KotT2;S1vM+oq*X!93NvX{P_x2JS{2l+Fq2jVH7m@d zRY6S#^P{Y*d!|(IN4;x``mz?^A-s9k4(38#LtxTKyXW%qnR3uDeHf>k@i-5Era6xT zH7a}HyASQ!UDYdPp-0{-91mB%4T8H-)0t;S&-h|6VQE#rJ~qPJk0> zLUqRC|L$w)_rFu7v{igq_646CQuy2u_Yt2PQuy2uGd?%u#pi}>OeP)X!{>&W@wp+5 z&kZr-b3+=R8)C-ihBQ7m#7yHo#xe7wtn1}9xy`IecHi)H?Ubf|vKt(?OP@QgUpSHp zD9+QQTdoH?-wP;yue;vX#9mK(p8UnvdY&C`3v|y}b%V1Wl`Z#m@8#Y$J$>gss@_FA z4&TbPQZ4wzj>AR5PpF*5ZTW%h|4(R}^hhN{8^Olc~ z>pB~)9X^U$t~VC6`*h`&_0*e6T00-Ed)aq?w6$l3Usi6q>e%_KOBcNn_}*Uf(aw}T z)s;#%|BjZ+)x=0!&bB_sRfz+({JB+9!h$^3zwgY>4Mz`Izb`!y3=7Ln;r6^RvK-vW z7r}h6hX3hfcR^U4UDNaJa@8o^jSr1t?&!cWOwCf=+zBFBxJ!zkTN}1y;_1oJyIsY^7 z-B-m|BxSz&SvDwi`hcQxs{DXDf$UZbJv)6_NRy#1rVnpJY4y zxV;=Ss$PceBhL%TiLo!J&)4|8gCUzphNyA6N@Y7g`7T`RcB$>0C(Wq~I{)c3oWJ|_ zbY{>{8&@|*<~R9j*|=(q&*FSo&&JjA&%;fpFY>e9#%}hQHrf6?u4IfQbiL9?@nLBb zd>%yO^B~-Jd>%yO^B~OlJc!2UL74G*5QEQyaDVZ65QEQyFyr$e2A>CE#%BQxJ`cii zmC)tWng`y8bG>x0PnvS_HQnozrkt4W^+{7sO!xY%DMzMzebSUuI^FA&rkt4W^+{7s z9LRDSmj7xpbpK4IyAO3>d-Xm(3nw& zrcsB+j5;)pIy7d~p&8Vnv7P1GNJ5k;%cnJ6T-)V(X-yZ`cA05S7uR;#p0uWmYr9p+ zhP0-OYrAYuTGPd~UA7^u>EhZhv-FYVgsxYXA0PhZ>H{@CRT8$p-R2_k#uSxp?1XyN1v{iw6qNn8x;5-k>Z*OsU0oyWYPz{PFJl%qNa!hxy;z^}vKK zbNldeP^Y$?`!#Fhfv1nX%04xONk#Ge!K02 zJdiSUB9AA#o0Nyk%RXa!zI?qjT-oq6+bSkoF<1&8GS9i14Q}^1z%1iR@;{+%_>7ps z=LFezl81K)RbLjg^P+_h@~Lh6ElXcZ4wV15PLc54Is2V!$+GWJeXgqy#-s%DMedcE z;J}{a?3bM3h2eCY<;?l(g~8Q&J(ycYMMBB7R+Bah@1-VOslfW=geX(m1fR?E;&XY{ zRx29#@VPu@d@fJpb9v18T%N|~@|f|tJdMxgG0S_0gea5N9O@C7y{m6B^;IUDUb@vF)pv(|Z-#n) zg9_?kH4I-*J+GpgSS`w-)9IjG8M}{P>$?I_^7D1vhU@s=@20=n^QgfSk&yD^-+3(h z9Q~Cl>+h^Bl<^=rG4@6JH$E);7$25p@>*<}Uo`ob)?#r@mYLRKaZQ$))?#r@mYLRK zaZQ%TD_V=iHCgrrt;OP+tfF#gEf&}2m>*?bwAP60W!z3$lcRU~P#4Y|%KfGFR9si({?d9XuB&pt9#%Q7E-P{AvZSU?vg^mhFE(R3JU3qyGfbV> z?6i~FX+N{0YxSr5b)l?Fb@ZYjbfm0frTVCRp*yAaP(E&h(5X`U*3wT1; zRI6jZod>;-e(G!2f^{ztS@k*HU}b5J!@e6A>eZ1&nZ@_SL2_d6m-u!(i0{jT`0hN2 z@6m(!PCbb4*T=Dmw9msTU&fO7{wav>qJsEdDv0l>g7_9Hi0`+?iO+{srtGie^qn)Q zRD*5o6)X@{4X$}Ou7;o9~6d$F<#=xV#!~&|8s3YC zna}jsD~9m;39OqDshjrZy;t~EpYk=_Y3Fanyf6DMcCzP=d9CS|!B`%ZDa$XNA0zGV;MTlOHnWe?(8 z_Ho)Q>wQ?|i*JR4WLduWHa&=M(?fjnh;Md-_y#(NZ=i$t20Dmupo91ZI*4zegZKtI zh;N|BX}|2tqijQ}6`%9>Eh*l_H_btO(;UP%%|W(J@?R}Sd~Y4%!<&XJQUxB^Ye(Ms zhgH3__FP+YA{lHhaF@r%b>HL!c;ZWDGcyRjUo(UGw{OZq&-+!GKP%^fC_Rp^9R;U& zAp1v+c)YFsTRCV^uaqV`q6JH~W zPg|k-9Vx_|@?tM_H6v@kpeR*}2Q{g`gDZ~L$@AIvFZnoFM^v)yzf!8EZ|xl0{+Msad%Kpl+-O)8)$Ba$bKuhq)76`| zSbGCqj_gvo-_ON;f1~~_HMU|3=B^VmgPwd;QB2mIQy32JW?cc)>ki3s<|we&!<6i^6fw0_G~& zOGBmI?U|+hB_~8(t1qXA9Uq7E&9+`W{2lMYf|j2;SV_&v zW#=us`%O_>cJebyFr&u~HMCdt!6u15r zZCJHti$1fP_uXLQC+BqckeeLX8EiM%maPp%&wWN zbA!k>9+TnPtK5eBlRW0ss3u(R;4!64^JDzp82EqeodtLm$@1vY00}O^Jvbx~g6DMM z5FCO8mjFRSAi+XNaCc2`5AIIRG`h&*vbeju+v}>H!>xV$crUyq+2#Iozi;pUb~2~B zy1J*QyQaH}Gq=M56(TEOi?&17XHSjB;}Vb^zPw5-6X(83Wo>_#S(Z4kmiX`d_QT}I z*3=XAyXnk?*2c#;w9f=GOUZ?W#i<0|^QzVKHMTfj5PI~5wsI)@c z&}r)`G4q7B?S>?NBI|+tRL5+qKUq=>-N)8Nq;}69yBJ;X^69K~;TL_~r&|jnUq#*b zzNhEEK{pleLZ}!oq(5h_Td^5V;22KlfS|o+8hEtmFxe{S^4JhE?-Oyiwx`9!(3B)6 zZOOUf)g(F_3qMN^j+J|NrCE&sRxv<8#Q>qPNW}mF6$6BHP%%J2#Q-5zF+f1Y03lW} zK!l0`Lb|CKAVS3eAyzR!go*+3m%4L1M0L3+U#%xG#{oo!&DiyHubE$f*vvaXY~~{% zHuDq^oB0a_mSg5MAU5+I5Sw`rXl%#(Y&J(OXx&e7I-*mDG!v7F2VJx;jx*Q6_3RQ$ z>*IQkk)!ZUOOE~eT^yNvRIV#S9}UD8|R-TpUa61&o1sJR}36M&q&WjZnDU+($uEihZL4^`(>lH zF8n-?gp9+99dcxpaVKskUfI!JuBoSe_1`P2@|w(Y-;s3&_6zSZ`DO2QdJa(4$5oE6 zNqd~&p8D1{%`O=Cw?JrJS7|N&o^)8!I={REyQhOsW%dxCJC+O5mz_vFU*(!C+pz?3yKHXY zzhpe=uwKoJYdYp89S+?n3O2v4mGqq1 zcgh>_W|W?{N9LY`Edvs(;+?AeSb8QQDU2(OYiV-v=04E_xZs-i!E!; z=;yBZx~ihtV~Q097bngVwM*nAJu~zbP7~-K_nh%VJ#> zWo9I$`iAwegC3n?H2LG!Kj$r2FLVM};A7j`VbW#WfY1vA}Kejh|^( z6sEV|Mg3u(${#V_sVVh`i-Fm|cR)CCfmz95W&2CS|4nsKIc-7Z`6ZiN_&q&jd2SGQ zc#;QF<tr5W@MitZL-19E81?a zM<;`O6SUoUf8ZRQI`Fb0!>S*D+rv<~p*pY8>K%-Sx+G~0|(ll8aPiSGv(bDi|J*9MOEMvwKn|9fO<6Or|ke%?p) zyJXpTPrq9eH}(cxg`3Rk?&qBB+>7TysVU3v$y`8o@2L-&+OPs;CCbBj~kK;{GNo|Vo6pDerH1Fx^ezl^0}PIu%lOg==dRk+R+%7 z6{n8>N^E``9Uo>{{gqS%jNPT!z%Ba zEeAcY9Q43)(8F*4$w3b+2R*PH^uTh^1Is}VEC)TX9Q43)&;!ds4=e}$cc0CFv(8+% z$neD!(pbAo`&f339AmsXseLS?Qx-DT?$bV&g3kWdx++EkzH98BdRn%Q(EL65EGIay zeD1*VxdY4R4lJKLuzc>o^0~v^o^~=zTfKH`+U%(jc1(W*S~}nl!{<~A(oN;00F@s^ zpq?XMWQ19#w-9gXoEKJZ7(!e*LgiqZo{4zT8kJXQnG4O;xjn<8(_h47G2F#mR zulK_o^24*reGHU2`IQr_NRbCQMc}a*>UJ_7wNr+Wm z5>R38alA=4Grl*m8TXsmj0a9^#tA1j9%T=bh^Ol|kZWH93qw|VP*JB@vzbC)WMrTmrZ3No3jEXT+=FJFtW@8U@g9koM zs4V}fE|4o@VUqJ^S}xdCeiCuuF-Lf6IY8{WGA``t_KrAZiK4LhNQ*Cj=@jOSApA)GP+84`<@^d2flFiDE<={W&xftT8I@jZN>=Tt2 z)#rNDJ~uo+M9&m&yI!}ST2`Cu&F53PhzV)*H~Iq&SBWBz^mpVNp;yK97W(`0yg%Z@ zwmmPYpCoWj2Un8lZ{_#uK zg>Wjb-|2qyPg?S&)9=2SJ7-0FH21)#c$my+YQEF2zZ-0{o1ow66YGgZCj% zjJAanlKe#v63Ymq5M1tE*i5^)}UIlgbrXWpAbktjizQ zipV}S?F?kQ?)l`+--C${JkKceoZUiP{ZJx#_Rs_3jrMnq9nBr6U3_P3Fvb+jOq^;) zPh*RR_SNL|d~bbUNBabLJ1W1&w{Nh~(N}GLzo_o3F=x=UzdEYMoS1g}c2-f~bNZua z2~!UqVGUK^s`0ml8@d_m>gain-^cOBWJm4mTWHyBOxm4}?)kjosqu7a0%EmZu;ph2 z&MYq>u)K%B@*V=qdk8G=A+WrM!15kK=ukW1az)RD23Me6BOgV+$;gEwDVc!1CBayZ_{|1(wGaRE{%SuH--2Br4?dvVN3V z9%o>AoPp(W2A0PeSRQ9!d7OdeaR!#V`A>F;>asAVor+lo_&joExwe7j+WwQCT<7oI z&tQob{>tN(ODKR_eWX9)dv+&q?kd$KuxeIV5@#jxl7Irx+R}m8 zL!EEyDsNI9>&7VtJCeVp?_#}`&uvS(*isf=MYr9N~(KQ%U7|X3>A-ybmKhvR#$6_ z4%!#j=4f9_1uxCB9?1@gXGI-J&epK^B5&5X#F-POfKrRk zQN0%A&JI)VE+X!{p&;CO@Aa4Z^14T-4!rIv?v_=>-O@H$Rn4N}ZV{`vTSCR%B35y? zgo?XGtm1A76?cnR#WE5q1`u&n$mH^WlvNxjz}WgYKBzcOfU)(FRU9Y4*!svSjuT*P zePk8K2{5)kvWnvb7+W7%#c=|Rt&gl?4FSejN9OuOby;)HIKzc-eJ+plolI_!&6q$s zXIK88VeUmq=LsR|8^Q5xf6z9(g7MVfsonv|JAv(+A<^Cu)xHL(;4ba~x zZ?!5SUJcOei}?#%TEYVLyuC%^Vb=8K_ss@%-Hp|E^$JQn$?_$Sx$N2I-JTp zU3?DK_mt~eK@_Q}f17Z6xMjM^tAui@z|)8hmvvdyuOu~|_SEZ$o1I%3k1}W>*>g}&>SHNXZu#doR*|2x$F8FC`0?c= zlk4!KoNxJbV{Hp3K%L|5tYkn=XX01;S6f}zYd_VwB?sJ{be=B=e34L0*r~rgEf~;K z#IBK_?%$tmwV1Un3vq`0m&M0A$%wf=QC$|scvCUUs9esE77j2Tx#>N4RpUAsca~`V zcV8JAG5MVy=Q}1nZShT^>zi;#Yccd|0g|(^=Q5G%t=@yj>&5wJ$>%y_j5-yojn zbt+aJF~+Dg@Vii{(R9t;x6;~frTzz5{S07YdeR?ib%yUq2_4TvE-qAlxW{sW0jDWbh zjX2l-;%F4G*L`g5;A;`tZ|FAa&{A4P`074(aDkU7w_W>$3(s9FM!wa);@?wU5QBr0 zQ+p*z6%Q&;eM|M~D$+v6C%+Ll|C9@I1WX|IzTyHULnv-A_^P zb))wR^QUv)`uEsYFZ28nJqzZ!Bm?D{=aq=fb41^Gpyi zw`X*g+x^&0F>P&P(t-1kMVrO$>iWH3tMX8>N99gH9UraEF0S_|{1^RsT_W>aUe@Kg zn?;tIx-1X(p+eTtWpx;zU91k!Wp&=>X?Z(B&s)TDZ|j7fn$6h?hkU zowb%YcAhk{T<#-(;UE3&iVSgO?uGiB;L*_+jhj#PT6teq8yxaj)ia@45v2G-?i^=xua(WS(O$}fNOLtEkz z>s_Un+g<7pkJPu{#UHECxwc*lT;+8SJw9{$bB<0ORDOgVDi;RXob#crXDovfneVBK zjl{Wwe{Cb)Uf;W4osBird0~>znb$F5$8p2=ZYr{^fALuI(WI|r!!%`6%Slr2$MCt4 zQ}*4dpM_ydoMq2eg6^4G+D*|heiwvVaKeC^V z%Tzf>0P{&>-&Q$C0P{&BtDGZ%`J|Cm&JnSFGhBsTX_5}SK0 z$tJ4oZ+(*Uzd^Tt%i@8o_eP+7ILAAY7J>`yqw6L6=7zh4#}PksEevly<|6LA(G6Oz z%1`~F|3!7q@x(%^@08Vr;7+m{2Fe`LOyx35Gmn_}0nSlTR-@2m)|9_#e-~$N^M!u| zSW>mrbI7SHED=`oyLn{p;kJU@j*z3I-q&<4wiDzm9Y*#Uey0#zPUbG@~vT-ijek$N6}>25lU=U#1FZhy{EQ5KgO8CLt{ zFop-!%iL#0%wuTt*xEeiHjl+^#`-2(nX$f!`F<)ahwXLz76aV8U*Pk?V}_gZ>AG1i z;60{3#C#tS-zTQ_I?{e&ykA|%J)E}t1;*eu<$Q~+&G*TevA%8kV0pwmb~nmHxmu3$ z1^;KSBkirk>*oCiGLIQ<%BSmQxsvHatm=h&5}W!H^O$~|W7<*29Q#$;F{ZtKt@h&2 z8t0gH{I%LKroDcx_TtYP=a_cIIgo7g(-dU^!m@ z#8FX}^3~XK+5%^mTNYSOTVOeDf#tLXmeUsc|0ky{u$;EQa@zi>UcA0hT`tS}jNb%p zdB%a;mgR#6mWLWx9%^8DsDb6729}2!SRQI%d8nhcEZ(LpH!iT;xWIDb0?UmHEH^It zb|~*M&gY{-ruq(UVBR>C&vM5D%N-9acRaA%@xXG&|EW!R`~EEX+zydpUT$QV%Var% z(O+lF5sdyiTaIA#*V%Feqrc9UBN+X4wj9Ceue0R{Mt_|xr}LlMG^)!|`zr+I&%^dr zdpQK=9Yj`pIRxe%L{@t_ESPr?S?%SpV%|YywU@)dyo1PUFNcA72a(lY4g>QJB7e`e zQC%*}VGW#FUTk1_v0>tW@?rzaiw!I<_Mh5_x7Xj1iTe{VCnDO4Gq;b*izqNZBHp9& zA_~lph^+D=S};E%vdW8S#r%lKDleje`4Qkhue_ljt7=I9$4;pV7cRg<&FoI zJ04i>c-;SPsAmjN=jbd8_rqcz#d2}~DdiJYjQdY9pD13({im2u6dCuQVm?u1+<%Js zM3Hg-DdrPJ#{H+5PZXKADd(szm)kQk%=L*3bD1v|&oJ7q)Zc5)ZUf`qIK2mE>hTfQ zRq7ly+9A(*Z%c!on%B&A6K|^PJz#CSO%=}9^*)*SsSk_iL-anGhBH2ioU3BfZ{Pfu z60+PnMLx087nFZHl|FY6=HLto6IY?@`Qy96hv(DDKbAbq4MK-hBH#Gc-7Zk0td1SJ zAv_mcc{7pP`d8P#SBo}Ax)*xy-_7O6t&OwmZ@b$UEOGzsxwdop7Ab^Z1HHe?{kI_^ zSqHrbtlEtTk;hl>2@kLTRD3?EW1FO`nFOrWZje1aH)MhJxmOd9Zd3qLPU%Rz>6|Mh z*?5)gTta>S-xcmje)V}9i$L%DI$nLwbot;@>49YDvmG;n_xx?d-|JVuVqLngODjXi z>F+h1-Mr#Uaqbn_YR85vM&+$ZsShumx6;^}S?{TES<%_pmQT0cxhhYspN4B+apDK7 zx4lr$3O+A~pFFk{8LzMJjo(>3E1~b-zV>0VR06T;HM zrL$VM<)?DNBIk*8z4=fVc%PvN@##(~{!IKX)Q*Q#tevB$d(iU|(#ZuL?RGU#2mZWp z{%@*dZA-XlGA5hE`f}!dvf15>*0B$DTR4qK>;5U0Zlf*>Vu|B9^>x>(0U~t=?dPvL zZ>_i$SMM7op@XCDd%m6GLcxzZ{>j2b7lhX!-S_zO#rfZ$8`mK+ zeDPLkW91EJ>L-PZpRqnydo{4#@6XsD;cK2j$dJCRC7wCw;rye&O;;$txc@@Wmj;g* zE$$`MXS?DA8N%tA-ZSsJ{E?XaDIw`_xu-ou6uVFT@JW`8&}`;*;#s%z!0!6PiDUOE z43!#WCoVA84a!{vYHO}%be4Nsot4=!ES$!-f*0N7ru(ny{7AmmMWoRuIq8|IS3a3% zS}^gd8kyyRd^+ygW7j0|<7ho^Ntx}X@g|!c*QE(q18eu;dY;DFYm&d^P%C{s#qdI6prPA+=c6$qrJ>JCG?^;J?oi$C3Hm)2#TMvx zzaC)^tH#_T`;76(2(6Onb}#WE4>Wu-jIQSnE({CrXCvnA&N(`DP-kPMItxttaOQ2% z=!TnoaQZ6s2k#|C0SLv|nm?@22-d9%&Q{p48U+B-PqPpuY+4|JC*9 zelvBxTdFhTRCje|T&gqU#OlnrRA!VtEETUnpuYyoRk0B)=o>;-u@NHBH-xNWBN*r#LRPU64D<~ltJnwz`i78IYy<;+ zL&z#Nf<)gC^7m{T)#Y+~a^~d*#@cH^-yiDfU#VII`V)~0et2y~e=ap&TNWa-BB zh(nVWm94^0)4S&H{Fdv$+1!6fa{$~=hx_W(-+$UZL)Espf0CYc&QV=1*0FcS(zZ7H zf3k|PX{flPq~~kjWya-q+Gpk4y_2!HqF#4D?fK4nq=8;v_bBQT5&l)r%?1}eVrgDP zucvyHDJ5Qh(et#F14fG#_ImB};@v{g+dDhS@9h~OtYO-p$;*9NZLv`(iN5FZIxi#T zHhpelXqsJCS063Ep4%z+oOg7&Bd4Smr}Arm>6$V_#pOEMU&>`hh8;S&$<1@RP#;_2 zu1R?{jrc7 z^Gy5CIdl0%)!e&swQDpV3*GK2%P!J!8Y6R$%Ksu&9v=hyYp`c}d7#Hm;yLB>$U8ko z5%=g&E$K$>(w+!}*W2vs^U4wH;sA(Av|? zt1@v!PGef5!t|c1w{MuyBaVLe8DU$EN?Y|iFG7~=sg$GE$#c!Mw93Id+xwEDu3&5`g^XQ<+1T1A|c&lztdhi z4ZTNg7Zozssdy<}j_P+Yb?5JJk6}zwA6$|@r>$ z?qj#a`l^WmZTS0JJ6Ka*`@qk;rc?W_v>)>Lid<0S)zP(Y0NE~imr1Vev}(cc9SXBRHN}Z`$-pht4cwE`j`2XOYSyfK6Gf3Rz3{&lnZ*q@=bhUQrqe*K5C-IX_1`;JFYh z&YzIkITZEZn+$zEq?k0%gU~(f9ExP;P^3BEGf<8>AH%k$->A77uF-7Qv0k?OQD>VR zVs;M2RxW5cqz^GWhho#8uAA|GiP@Z==An2##FS$@hl272o)5w6<~b3YKI+;gV*H&s zk461$=TM~j4V=oFA`kx7yiWBs?>F!|JBMPEPuJNw6eVX9>VxuZdJ>!Z6D#}S-19FS z(~h(+_m^qMnD+X$+AHR{qxGq6Tmn4?(RfAttBjv9&t1%O7c+06^RqaIh_-o4%()a4O^Tj!)9e=HMjA^f5tG)QM#yO@Pf30?mX|G?az4)`nIi?+dt#(}FQ${>GuYJfr z%E@DgiTufQ4D&ooj|q>escDX^){LP3Ay(Hw{SAG0pza0r8)8)^sPc$;xj#!LmT%Jm z%eU!<<=b?|@@;ib?HgpBRbPM4Qf#p?*NyYflF#iB8Rq3ihPlj%*NZ|urv>P1h0(X% z;L!AQ^nEt@iKcokSid}?tDX!Ge0VpT4-FZwZn%U3o7 zv?E?O8U59^d+4`jA0RgS#{WsCL|dD3B(?`*lCR3edknme?P=>**v_{8_C5QUza{y~ zCQ{jiAk-wl^}iKlTG;w4W-QII89Ivdm|Y$~B)&n-2KQ5}WNPP*1ac ziN9y7pCzBmi6q;`PwJ=UxPfdNPpF@w-l{ItPtEa%`l&fC(O9MGPWRxyZLD;NQu(|r z&b-{nF#j!k1|@qorP+4)yhyZ@Iab&hpF!I_*w%lt$u z2W|FO{nPed!?v@%@32k3wF~E;CEv6a*&&krtzKM*{|i$cOgm8BkWD*t`{VOy>#M}< z`9&GFG2~Be$DY~0B~!Hn;6J8r*hZwA*>*PjVBLw?dk6a!*!tM_?C`VXb2~(adAX5c zE|ZPn_`b4@?fAa3jrsV#vb_uNePw$`;QPwTj=xqrs`qKk`%b;G5b|w_N&C~bBO+Z4l&PN%ySp> z+{HY1=Dv6G0h;^a$)97c6N$}!LagQ$hWc;vU6}jriT|hVZ;zR0(z+mKo~fP(^sUAC zRiekQ67$@}Ja;kkmgt|i#Q4E}Ek79dVRDXX$6u=*W7_N2YA^n*agJ%nU#lI>c_yxH z@%%KNHz#K6T=n1I&UXV_7Xw=_16xO9zCSvbh%(u_o7T_DALqob(_TCCeq3MJZ|l7Hg(gibt5))Bb)HD zxJ-VX-*4LFFYpb&s^^rtUFpI%E6T>VoZ~>_Yb|w%C~K#%1#B{C+Nn z%je~CeYniXFzSnCqy14wESoX)G4md>Gu9Q$#(U5PST-@U5108T9oYR`4wrB0K;?3M zxXj3~X)8e8Oj{9~wjwrl)2wwPHgzML@Upl}ex2WM+T<_tdAVF4rNg&zU`D)jko7}N z`t2FZQ{mm94RON^%S59E-HB(n6e4hBKjJ}o(pw6i3?W`n^S1SocQ7&6lgsDV`TblD zm(R=P`fxp!%x}+cBpIKPzv#(zlCiv25C>Tc5Z*_5!lxcVTF?vDzYet*=JGZyJFcH7%x@=kI$D(n0o zsbxlwI>ZN0TrqkEwI?1hbgZ$>u9wzl=M`)ereCjB2l1__l--ty{W7hrNWHX6$6N04o_%Y-rS!! zwO1NTm(#l44`!_=I*iqQbxh|7aWSDU-4mWaKD1icggC0@??}-bx+fh*Hndy_hM;x3 z$j&~MLSTKj8D#&gb^1V&Bz+C+GuH}rf~4n;5|^mb0G3TpBJujZ;-%r#3KwFfGbo!A zN40!j)@bVkAqIInv>{ zBbI$4n>&5=lW8`tBwk!HNcODeLL4jB0O?v}>>_N7=q!tuTgwQNVka*vSnsV#xbb$AGhr7y+O-c~ADV<6NbgfH#JJU5IcR@XV)=e?RSdpwJ zU0*pUq2aJaKSzx=oOZu=Uq43;<5socWmDlYl7f-IVS@-XX+l%aMTjw zq=Bu#n)3~DRLfWP5z77&bx`&f%KpU4{t?Rl#LE7LvOlr1zoG0;tn4q9{fU+RrLsS< z(pf6|6GydtUY4@IRQ4ykDf>%hf8v1K{iL!#v9iBZ_K(2&D*H=ie}Sy*FO~g?mHnl% zKXFvcf4ZikbiS06Y&9^fxtvmn&S1ydmeEfJPF+VjuUyqn=4@7mc-Q+7+19NM>F;ta zNEQmtN_yVv-9ug}w}|*klGbuy{8z+LEuWY5vU7F0wR1*5dlpwQkng4}Mf}Vmr94u$ z9`V7}SB)8s_1M+8(p2N=H9ZGtnIV~R%Y63BZw+#Hd#9iMWwo8fpbA0s+vqIo*1d^_ ze;YlnzRZ=-$h%#SOQi;Hc8_?fb(>tOm>Be0kE@I3g^P5z^xCB0^k?Gm`_`m$w=3x( zW0;;_rQcQpYE^cn>t}P+g&K=e5l3fPyxgk^+r!jV*QlRNw(AK!Yfd3{a!*L? zbT0%hCb~@ht=Eu#5PVP=*uJG!_`$ZJtBIpRX76HM#I$sJ&fjA2K{2DDUgNwAb^s&1 zA=%A4yEB{!FGFm%s5+F&q5IyXyxwp>?IY6v@@IcI{%!`bbc#K3RLh^7JJ|5~ ztk+^`u57giywdBM7Ins3yjtr1Q|Des;aNu4(KFQ^v3G43s!ObNc91otIlpzw14qv5 zbzfA-+{NUtEmHyFP0vL-^d8j&hIqy&zBr)^JY2Ph>{jP$A2{%`8}ZtFA+WOlVww*p z_6UKxk3wlayuiILd_K|9zGSk_a(=t205!8ptc$2x2-^F(6OaCo1iHs> zKpdTA@p8qwW8(1Vj-nHb!m%gkat?kkS-jg#Dv|sTKVpY`Z^Vo~tu%XQf~2df z5l3fPXL84p?me1Oxu1?l7`tC}CEhZ;wIMg_F>2Av;nwcmbY1+rZ?^b-)OFlfypI^w zybs;qe#U;W*3e^hrkn}jbC> zKKA^5U&wp98S&AnA#gW!M;bSp&ku&_6HifJjS88{$7LuVm&Cq(XZwER*p|-3Z@uj0 zx^|6-UYC(YeZ8uhH=93+R9EG&>$zVcJ+g_XoZ z!duAED?btY9IqsULi9S0`zoWeEIzks8{7`6UcW)Q?XMXCA3y6cs&TRYaPF8RUH_`q zcjME=qWRK*X+h9(er^Nn_&Ak6B$%z+CF?qG@K5l7uGc(L3r^m0q;`zXvJTBE0~HH7 z1L}6OQGE#etbK#8p7}t|_2;NA8=v%q3&b?h{=A6&ZO zPIXBO-C;mY-R^3x4r&cT*Q2v6UhcCT9`L4l7P4*P4h3LFEqR`E&|cB4 zR~O=!fo;U+rTQ7%Z}GCsTBP5hAJ0CuCbH;vXjIELeKn+y>BAv5eLKXa&xhFb1reJ* zB4X2bL~Qz$h)rJ;wTtP4A~tpZ`0?|lX@~<@)Usm_CSYH(s`)%W2aR)JP(Yk zPS^XkdSMI*(d(~7MVA_D4(WB7F{h|;D}i21UXYU_f?n%)S6VasmyX~0zIGkqsB|)H0XA5 z^j~azuF!+-d6*`*A!g}%b*SN4X4zL=--KZWMbn1*dXh;?h0}K3j>U?;5yyM#`BJlC zSs+7P50W!}ss-vKC`kNo(+AgZYTh8R-{Klet+j}8jiuIF#JI*%Yb|12W2v7)E4hVqjTD?f=;eiCBk zCy~leLah8GQu#@Um7hc^KMCoq{3KHONr;u7L@GZCaa7A!V^JA3zL7p^d^6PeMy$p+ zLyd35YJ4-)_(rV8H>t)qVl}==HNFw6@l7g!8gW#}cX4;0919w^m3kXX$FrJ4s4t9hVQ^FY9RqO&aJ!>j&q=KOoKpEYslLk3DV3j->ZSagQu#TFqe5n!s=@N> zgGV%0Jlq>1zuYK9V@25ufzq>14Jvm?csJ=7eBiew|(wti4R z9$sT1c0cPNtNLmmX}#gcjY3B|()BKRh8Wd6dlUat<>sq4-_pZPzuy}#_Y*Zv_aS|J z>+cguN@@RR^L2JGe1rBIq-vZ8{I_fWr`_=iFyO9Uzelue3IQ+m`n^#1u8`JSl1+wA z=nE(Ewk1yH7XsUt4JUj4Q{|$MANvjVe_T7_*nx~|M;tqlaqWm>2Qsc5aqK|GwIhxl z$hdaIu>%>`jyQH8-8ON|)beU!uU0aWP{x1F^%_=?aovw07 z1QgW%(pzioAxoh~q+9Kd1)-UC~Z%l~cCNaOm{UJ`AXGW4P$ z%KH$9g{G3}3+VAYS?Xf)kJoN=eS3wvaz)Qn#1rcK$g|Zh8u;5L^Lt6(vLlJP&QUG@ zl8hx6R%{Na!^;ZWjO^jQ#7{nW8E0Jri4Xa8u(qA1`(*DHhb=d@YJdLfPXmRVrRNDR z)*TTud^^$oPR{mFaG>s=X|v@AQ61>I*PTkRr>*wW{!`_u{k?R~59>R2siQ3YUi(1$ zm%ne!zp49-%dok|iE`R!()CzQBhE(cTUfPW(he`v=kT-SOuL>=)^4cxFel!3&sY<; zE!nD6$uJ|_-1m5BqrLHIVSl=QBqFXQ-4)#yD;8H5k8bET+EII}X!D0|J1&!7=l63t zTs|+C>*KF{OO7M1??Ah4o~!)TyK+%qt>WYl4@+r(_0`|J!MgrFU0-&m7C7wI{%U0_ z+_Nq5w?9ixr9Hl|Zv9q)GMk(Wgy}u?9Js}$5J;LN0gWNKSM-N*HxiLP1M4e4{7Jq3 zI*_p~jB0<6uD|P96YRF6Bi*=6ex2XX<#74DT&_=?!8u^ikxJBdq8-55IQfaIO=|>& zlh_m24ekWxI~}3AtXR?;-mD!+{98mYJj(q$)g|wg5O{OF6OEH2^8~_!$&E?>*P*`f zV9Yk+7loU{>g#%6&_7k~fZzp|wng;(=jyTP)(zD)`&IHWR<+S{A@@+jconAoKb1zr zk)b7zvzVbbGGnljXOn z9Q60}e6mx8TrzM_1+rnAUFBqwx_O8jhcuRB<0l}leXq0hJo6j%nQbHbNUxBd#Enyg z$T@RXQy(kXI7Bv2G>Picy+vQyahwm;@t-O;rDJw*dRv+FAD<&Oq;qIa+`dbMSeww7 zI8nd0;>2j($BJy8YFSoC_q}}|=UGb@)6BnbMukl7TNYg!!Jb?-M%+WoIaS^<#wiy(0S%5;^#i~Vdw3nRNtxR zOMy?)!o&#+Wq`ZQ_4+8^;74L*V!iJBx9Q`uFQI(h-ive|w=l1Cm|2$ia<_`|eO~Q5 zZ4}&84%r!(t`8~ORbKVnNp)XZwXYl%uOo4%8X@xOpy_0*Ik`im--;zomF?MpY*k8-_fAJ z*3!ZM1?j)ATTMAyrUR@CpKnBkO#Y6>GO=td7j;3MkWoj}6&ZEMIv``6ux`j$SJV$V zDr91NV!NVzY-en5WNd%z2gukjuzw(9f5Co(jQt4v6EgNM>}SZ>@38+NV}HbciH!Xe z`wj9xRWAR=x@Vo*hivCWedGS69&+Zr`NZ9Jw~=k&!efib_+3g8 z%PlEn;ePdqFIg@bCo=dD=W90J7{9wGadegy^x=Xr-AAvLPL@j{7ap!BQRgX8M9$e< zl6dO;8Zz&x^u&|bwUHaHJ~r^4O{(t4@6RW0u_Z|M3(86SM(rCp*kLT~8(B0jNbX&p zi)?akO%ECW%>v?os@$fPSBiZp^>@jV)n1B`Wm}WYV>iwK8{BIUpXy%%>I`-z9;48X0oxeP3fn zG&b_))oYOatqNFY|EAX_FEhm#4^Q={`)^MO6{lMS5dV?vfp}+rgN_QBO1`1wOYA4@ z7i5rm;_G+fuqkC^f#S||9j-N$SMxX!r{B<7<~Xt6!2AEsZ%cm3VG%>$b!V@1>SA-RlsGt*)|iwGzZ7I@XX0vt%Hi<=tB5J@A6`nO>l~EVx7O zlZk5iYQ7EXJR_hTiVbKC1>+?kp3}c8)XAlN=63A@VN9k5)c3BOQa zIy#Wf&X@e5{^6O#Nl&zau|E2l?HRi|Y<-iF>R2&nA!s$po%o+Bm;1idxC&}qC7so{ z3Tj*>R^uwDag|t&tDweJ(pinGpvF~VHLijhSBcfQD%7}2tj1NL##Q3zEKBWw19kqF z${p+z5B8?l@3_u?>=1Qw`_lE$e4fHDM8CVMoXKG+a#+7BU2erOeC}xfysytx!+KGF zcbJyZL4*K zxrf<%=m2Bm5$&Jf0Y?r0+MTHG6+9he*1Zjhd0nEqtd~zafPL%J0-vw0&w8n|UBihR zObCVp^Uu+9RAF`qgzjoZbHz%@1EIKRN_{U$QeUW2SNpeP-DwJ?Qt7#Ip5zt5GE>i) zd0nEjEUXXC8}R>6A1`7w%cRG^ika6K>&NT4qWY6OyFstlc8qnB{WI#h7XBOm8-Hv5 zofv!Z6X#xXVhKLCC`Vlv zsyy5MLX}6X{scBTNPMxd}6a)V)ZA~hZxI2yWst%{>18RtMd2j_QJo}*tJNK#jL*Aj(~sV_EG=&&2HSD z+|FkC^jj>S)fd~*R^M-DY*jhm+Sk0_R$tVYbT;J^o8=Ol`VgCX6035)^+R4?ZU=53 zCFh&nxIMX@x&3*&@b*Ic?H_hq^_y?)NcA=ECpP5(-ebxqHp?YefBM$1Og-tkslV+W zb(?NSUSDnpbpy7SRR4~}?Z)kC{+;gO_UG+_<=DPc+sPaN~y#XNWa=I4&@>y8ZbebJozXIo|IoJP-EK4u;kQR1!1Y!5l#PyW68@!5R5 zZ2*14jSTbkFXw&gd*z4x`g`Tey2a$lE&6+9lcjZK?>i|ajv+yNePkBD^E5t}`O-^X zpFNED*!5uf*+u&;OBW51P4>;F`An*3y=B!m!8BG(s@+je*m08h*-lUS+ofdmyl1#q zLY_#Y*Sse~9p$QcwdwlKdDo3bN7@l{9|h-sv(DV-Fxs(`oKo%>)jdPsmNMVo_r!d! z_>bPt_hxfGm^H0v;i}i&%@%};49)bqo9|KQ{Js0tzM606jw8eT>;`Aw4GrN#7ro#6 zeAmvf#8Lae&pP*oO%a{Q4w=Sjb%y!f%McGr-_x;xNZcW=BJ0^O&?A{(ZD5eTpQRwLWy`REIqCTt--Ql}ZT zYZ-@hi_^CP%&wJ-I9={sAZAt|jwlib4tH)wytL33kvnNO;#bQ&#F$Uo&*L%TgS*#t z?dMr_&%x*vru$pcnPEnbV!FQ-dU?;d_tu+!%j?3w|27*I1gZ1nrMkfG9$*=e; z8)*Mj?>FZ6U+NzMfw2Zs9lIav50w|kr+Ph3(GNO&sX~0FTp!r+tS|AhX94i_@)Y8+ zGuuJ#&NqmYxYU8FA5)WV%iN1Wp(Ad@-u==*u2Xva`F-e3v8;g}f2KK16AO3idS#zb zQ#?GV?Xcq58%xt1!Svf&f!!@}RX@hQ%J&IyPV(%L;i2k=_r%Y&z&LZV2l0Usxs4&y z^?RTDLn6a-6WPf(8JdtB&VCUQ#+i58NB1b8w((}I*7@A(_Yq^wwsU!(LTqTG+wM`D zxgxZR-t(~Y>of86vi46NSd$rMuJ9oFWpfHx+Nl8XzH45vF>XTQhzwofR+3$0+xf); zA>ITp;&q2Zpm*XN)Lu_Fs`lEI(7?I}eDMdz*Ln~6lb3BE%?;hw-s!5t#dCl45pjRf zuU;?SMnkjjG`3XJZDifu+^|0COZH4Ts=jq|xb92)9^AKN@zi~+(EYKZ#XIe*ui53Y z7=GKxx(Qj^*wo~r_A6zj<`>+{_@kYWW;=p^LKt5nK{`1evfT!b;~VCo|@+( zuFOO;!?W2V@%t{_=mY4(tLg; zj&j_8Vm|M5UH$2spOgDPO}`@D!~LZwD`w0j-{~*s+vocMIG>;y?6$LIRQJ1#my=?|re)5fU|w_j%@&bO^K zbQ<}b-dPpe^?(g)77_FP5}f}Hy77GxKgx%l)5DHTdJp+Q$5N2%VqvmF$YoF1us#{_ z^SvFQZss#&ha)9>L&nELh=-k2dyI?kr8SyMvk*A6d4d(6`gbS#z=h*}26E*#o#A+m zgT&p{o<{##_7bnB54J#_>;;L-)XoAUojr&P2fh{oOIs1=8xbxV-s?_$=3b#4Pk#12i+Fs-C!~3nbcX)YQ))#KNB-jwIP1GXPyX2qWAo) z>X%+D%c$FNPT=&2!>{xjw$^cBIH@zkXwQQ4*Bi+mbR)KJ6H8|6*PM9q?>XfrYenJ; zqszY%}8X_-*W})Y9 z@9rQusdWx|?s$B7&fmMA$K{I*^SHHyCP|4G8s6WzC&F@ks;TF&3QKQiA|_&q!xDd&#y4~RHRI|Gg_8FSdf%@O+i-Pwi( zp>j$BlDQ9oTF0*9^;gA@e)g|<8$cw@`+|R0Zv*A?7_FQm^IP@K`gYDYGR*h0 zMTU9qk00ed<@SqiC-k#Z@b91c+*e%n~&Won4A?%huqtSkP z4`?!cA@zp}w}T+f=Pbl-A3~thlg9Mytd;$s)>%CU&adwWgInpbad6@maP@Z`hx~Jw zN>J=w4vBW=_2qT>H|xoDjtuiXik!2n^N(pZ>GO{X97Ev4ot5-X+?*f;re@GNyk_+4 zt!y=j`eeZJ4sdJ28RB(uJ>l^4-M$2f84 zyq;tGt-oQZ*fp50uWQ%G+IqO2vpH_-Y`o0cm#(KQe$dG2)0vp>Bjx<7=wGU85VX2c zi0sC>UPcFKd9NX0KYad2LGU`~PP}fv2b>wL`+u%%ts(wy{qC4vx(8%jzL@&_?Abvu z@RdGu5u(mXhb|dF=Y^wMX3rM|AaJREPCr+z3T3-zC7oZlY6<-_d?4K>%=LqJ`}7&B z;uHJ9ksTJgKI%~jESR&O;`w+@=?@+HB_^AAg$6)img&U1-P%C~`&-2Fcx~7koQC?q z`j2klmbBPknAi8;rd!erouKKy->L5LWFPQI)PwkLhY;}nJc^#RtV@C+L5`C&{x=Bf z1%4i*sO}zleZV9BCE_HR>cah1si^KzEpu(LKG1$$An7?cMF>^b^jxFQbVQ8wf^_5b8Ll0x0Mf6^M>=0PoE>JjsZ6}T#aB`5hF*W! z2W%AKlk~c*$y^VS`g0)N!$*hd9v;6XGW@+b zFg#w0=k~60=o>4wQD?ut@<5~Z#FcA>$mQFnQ9G_L93mUqKK`_Gc| zy|^xsxt=*g4mmJqWx%m<@~02R@a!##r;FuA+-}{8pZ=cL2nx}AIR?-8QpV1V$vM1F zNpb90Kf1?l`#SL?wcbN+{~{K2%+s8%*U6U)hKK5XIB&aD1iyk#blu@dbC|vKE7{?Y z$`_Nrmfk}iWFG{9ZHvc+=&&b*GlN?mv?GQT~J#xWH`8SCinl*F3) zyq??hm|Z`5|Al$etOILlIh>u#thAgAiT7mhX=S-gxB44+r^&M6q1gQOZU_n*A>J`gW9WDSYMbi!JC-JALAUII`F!8 zd-=Pi)OPKM56du0+!@r1^ly{;vY2*P?>Sk!IW?qeRfn!0?phowg%u^^-LAw3xbN&?Ul{*MzXv<2d0O5Qqv`#4_&_jx@!C(%j)!Y+7@c`2JumOicYsE_P7{Mu zeJEHh8MSr%1*PC))xyMw6K8;8y=oBicoCfco9f8h?&6qKhGTu*c4L-4biaN}x81!d zHN{GEZ>Rsh9b#EN9ZzZT`1oLLr}tR)E0YgqrqTO;{ZChcl5w+9J8tRL3IaUdPje)X&C&+8Hy<}sW(tNEkAc_i9I%^wBMBazko(Sq|xWHo=Z;ye;r%^wY%M3%*f1*`8_;NGUwM0dkydY`nyK4AUoOmbYs#v{lGl({B-?Yqq4jDuF+n9*YJDZ zRNBST{iIBMUwN^=J|F55J5Z{9-qe@&Obd~<6Lz5SfybBT9M$FW7|Wb5?agHPe$?-y z?5XA$je`BDzIV6WH^%JK@1r4W)5=sOYti+u3yRAE-bIN+@70kj-srVw_A~8d+=17r zzWuHS$g8!c67$&9oTIwj$h_nDJv`PiXMBgN_b$~1-{IHy(-7aR)gE4t zy-Ie-k+T;xm1Br2Obdp@H~ygaW>=pOn6!K}Jr_+U^np2Xdm5G((>&)xkJ9%y4<+!8bXiT z4kTym;7%~9?h$IER;BvD=U&>+lPGrxG`gi@I+aVW<~*BLPC)Qs74#e0jMCx2P;R7@<@hGaUhJY}4JmVEVY{h{w)IVKuL>zQ3iH_rYe8yKZq z>N7I_yRuk!AJuitTQ7mI?9z3t>JlcBR1Tou4lMORlv||t(G_>g06|_lhEL)HrJ;Tb z7rH0gtp?z_JTY+^`U4`}^|=o{F9?qA(C89-wFy*2K27Z?>! z@84^=raIJ1m67f_l&KAjN~QA!ES}f{0+;FUYa8YSLCOpI`vUGox5Y00H|vIa;&`e5 z7df`o%Z$}bW1Shpnb?f&Ol-z{mMGth1x;+mh$c2;M-!VdrHRd$&&1rG(OE8!!N~c1 zuGmm8k@m??3XBjp)EpPT|LYpYmxb zU&a1F{h!Ck;{2m>c>HtDyIwrB%&xA-v@VOYi2f-7H{l4J*z59Q39B4JR zH%#uXzj1T!dY}WOORB$jZ!F{q6E^Da-C-?DK(hs|WS=Z9j?kfQZQ{NKu8Xt}+7a`Z zRGj~gOs-qPh>kGt+;M6bk6jHQ^VP&u?z^1sP;zD=;ujM#!-hQ`#2Ht;79(f0BCc;N z6Vrz3eZpT?xQbON_1bW5}ai9LT zcBHX_#~m`;k@}T7$Mh{e7>{41l>Zjjh{rqP{gBs}pKs#!QF6YWhvMg?`1vV*u8Ng+K+u9cA`ZV9?aX)x0 z7yP@qR>7FP-(nP-YajY8kMSGRc6z=1ch`OYMB8Cs(f|9OJ^t9N5VJnDSt6!C#5@-< zeITX}#PorfJ`mFfV){T#ABgD#|6P4xqDKl@bALTrk8@UgX2js#dOtu|rR*a6QN3m# zz1b*p>x5Xf1s3gn&A~5Kyuz%t{PR_=$HUpPRbdp#fWe}x+ja>PEnyw zSK<_9j*7rKorr@@UKB0de27|>>KN?&o-0{WHs%^*)@r zJzPbJG?}nXQ+ZUWqi1*M(G}pstpUIS$A~%y@w>6`DC3lH|=VJy^oZne@ zgJBy^5f1lh1xmWy3d!Qkt?Xmy z$}6cB_r*D}cSF6@9=An&vKqFk>pO_pPJ5S;MeY>2D7c_BTRXib-3uCevfitU6F&5z zJ?r@99kuPlhe+mRzldDZWfraslF7@y#|;jBQ}^@N`c z_h-w$rej#%;Yw}xI#Wr)+1fj>X9epKZt?Aln$I(k@T#RN)RQMgznk6IRqgB|awPkB zd+!Q0^@w=4Zox=5wcM_F!1@b>O-faa-(rfe+o@i^8Aj!2GM-bnw-RSi&rZLgW;-T$ zRo>&V>SQP4DdUK<&Do6k`RLlGo2sz^o)rmCxKW6;@D)6lZBDuRF^6T@$!1q!e^w(k zJz>Y^?OE+Y?0`wF&_E#d?)vq9xH=7p4cJ`V@*m1m`RdMV| z{8_s&iG{y8L3sbCM0T>Cg^K<?2Rqq z+1%e@*6+#Y@;(Q4d3#+d_qtq!xn1xgY*)&fRq_+()9`xn=YQ8c_1!CNZ|Zv_wESv3 z*EpbY;C~|rempDu@w=1qxkR4xALkY2bByx&M)};Md>#^?J>t1WBX6|dVdR03&u7Zd z@AyCcIL|3RtCi1x%HN&-9#i}qV=O)A)qcB{$He$N88ANb^Jw`wHLh>|r+>Rv%UxZ{ zk$g5l%bhl68aY6kOB*u-sE-)uWx~dBgYf@rzdNjrncA4Ctuw_OVO-nL8e1DPMZe%n zKGZDQn2C$u|NktgrV)5Fv~{NT+jH8O=}2RvaX*JJ?;6^eiNhuR>BsOdZJnvDGqrW* ze`cMj?QM$l0DRcNec>r4ydem>>yPg!Sb{Z8w5e7wQ+4y}2#`A(bf zjC}Y$j^TG~2y1#loaNKzyFY7vBF}L$*7Epg3=XXR1L*PoRyxv$As%j2JwM=f7} zR=(uECSxs+e^wr~eEnJZlKYyBwLJb=c@+7=|B7>da{e@|#YE%4@8E!_<3DkR_W$@@ z9tHDfJjX&f2ma0hZ9M!_#zT27ld;IDmd8IOkALrj+PI{} zMB~8k<$yLG{wd?3JeSE>@IlMtpOVMl+kdt3P>ZL=fxmM=8xQ}K@lc-2WGr&359PT`#v-R$9{-d){=E-suIsf~|@4(96QJ+uVXPP1f&Vqefv}cGM}{%^x8)Jr^uIA*`A=o#{ou#=uk|~T z=s#}!{NI|#g9lD6koc)e^8(IyG*?|M zo-)pN)J}O`!~2Bns#pr!Z!9N&<@r$_Z;kacv^UykHK-x$)qEmNaL{_`iGp;^X{}cFOp_`@ZO7 z#_0op`1^muV<+oavn=IkZjy2PgRNMGmbs|hzC#x_Jnto%6BoXTW~I_55gzB3$f5$R z3CppS@vqh+x4|6D?*&{#&d0e}#3s?%+v2yZO$LcMl6n6Pa}8@A$ZL&B!~`Zu>3W4oZ&s~>UxzhRm4GX77j<^C%^ z{P*8iFc7)_9clP`B(#`_NN91;;-GOr>f3XDmo%XsmtJJk)BfkG;J3F^7 zfbh1_jx4cgUBdV`{y*l@`0s@AI=mjsu|BL9G2SOBakUd7W4VIZXiwN!4`8{me!|B4 z66XJe?ICPzCt+jz39nywc_F{w_i}~b@4LOi??;%|1K;c6^#i{jmE+&||JVlOzZ1sm z`2DDzSRcP1VZ2Ysu8O75-dL_8Hrf+5*2A#eSU+LoeF^h_!uAlx`(Rwq9`A$kLR_(e z<&S)6xf2}Fa%Vx@K)z`GPV0By$1eUij@5wU2LGdtnLG&En5m7K#yM6SGsPN4TdRn5 zERB=en5nHZjcf1k^X4C|5oqS;x(oj{>LbFqPW-Mf_&?#=fXa>hC(PFlzpU>nRv0}W z?}d8hyFN0mOGzsk?*nLKte^0&_Pde`Py9#q-7JqL{~>)hn(JecFO1Q5tmRIuV~yIG zIK#Pwe-q{$GpWtB-2K>}p;&4C?!Ves`LFw(aleJ)X6%E6jpHX_&cPqrN*>4LILqUn zJRZv9B=+_HWBmNSHv6ILjrA}b8I1K4md9;ld#GF<=jAbk-{;3TgX8q~{UzhvN7wRt zaPIqFKkkna=6~b<7-3@{By8-1)Mj2E?vD}1{jq&R?(p&Y$Nm`21#+J?)&po`te-Hy z&yRgM{!c&VVq-hW#@K$s^>+1yHETCh{W9L>y;X@4*xG{mKr6yDuur8Y*6di(PPMl^?qh4xj1E?v2kuxI*df z%+T&2wV~|2zN}tkIN>q9^ei!chz@d0x zmpuS&nq}^)#`(n(F4jIJZG8oimwXS$=yX8>I}8j|EN==MxgLiVS=c-4Hgs)l-CV5D z=~jeS_sPeS-Zm#3mt@UO7xX4P!>t#)zG?xrZH?N2EnV@1@WWS4SbEDsWb@9aGV@$l zh48uq(X8*4$z*e^d<=V1elX$FP5ZKoC1MFj2F9{(W4inezx)=+E<}A&(Z>hH!`aM3 z8wnRmAIBQi^e61!SU@;S zQUv!3DL$$$B#!JuThvk$I>i&tanVJc+#rGQaSLxKG25E(;IWmVK%C%zm+=Ll$u4gy zKb(9=sd8MjZE%wr%C|z%R6e_kwUXaGk#LjIkUIF2;D7l8En(hq5vyIpTZ848tYkCp zMqBXPEn@r9H2_xLu%L1oU%U_tVBMbbyCP5z<&wuzj%roZ!{SmYl)DK&v0zoIE9KPc zVGr1!IgK#pO#JBw-w}?B8pa4{aS%Mv;-JMrk?w5opsY@bKKs<6b$T-A4;dW4*4m~f zR_nmB9LwTxe&sWD_Kmu%E`V<>b0;WsPF3Rc;@KMv~=&2AamOxhINKb zx^XRIVZi60lu-@4DhFpoK##-e=G3{qQekJsZ)jL_O;bXW#qVS6Y#pMc-HK5F@U(a@phxsu++CjW%B*z#Wf4`W-R zWI@Wslvz#Lks5gk$DU}xCRGr>8}sIZFI$%*6O~un*!CxE&b3E3?@e2t`$B>32a_1$ z2rGftH`1%IXNov2co@SzWICjdTG_xUE<<Ed@!abv!8EEJ|;hEz>-s|5nf%pB1^0qNVuij zS9Nbc!QnLbPHLVLg0~~T7SV;=?@cy){l+K@_KM%+X+HLea@npKmG{e207{(pAUx_) zIZ%>B{Wk|x1joz5M#*Xg*-i$Njc>UZNi5b%Mp?04{6^5_9c~Jb zDcSJ2>SV0N*23bS#+GxPV#~SDcpo6l`vl{CgD~$ajQ1JBydV68&AFD3WyC!`wlNtm zNy$y+`THia)6M&&B3Gxq*RyT2mlKB%TI<=X)@~}657-mWtcGkS>|3=5>oM{$;jb%0 z*_-ewggw?pv$-~@bnUB$No;4xHXUAD@JSL|Pl>(AJoI|#CX1NN2;3bh4@XXk<-$t`63g@rk{he@;RleuwQdV`S8k<@QF)y z@FkZc;c^@*$+7`q?^HYRIw5lOO349y4yJNG4=Xa(VryaXPh;EoqsX=W&0^}fU1BUM zKhRB0*Cvi)p7X1ZdVgzQ!j~KO`U#tJ?WXA>*XOp@V=^94Ee;r$l&FCEpV=UGf zGEF$5PKG4tSz~F+Dd%Tt{om{1s^wg}1*c*>My8K}@GKvTS4tY99DLatmdB4P{`zhf zsFeLL=yUq9ZHqK_@V0qJ?To1s1nSmlguPlvgGJ6#gbPndfNX0jQ$MY=T@N{;gXy=+ z4u8yH%&q74~UrPkRN*6Jw54hL@q>wb)u% z{L|PgX;>ys5AK5moVxKt}6(W z&Umzsu0@@}bp`c()EQh?Q2nSgxUNvJPShFF{QDEuV#|L-^dH7nS|fq9b^>Wl1=4!y zCv48O(z-WI##~nr$8asobp>J68C+KoMxDWR1!2?~TvrfAoxyblVbmF1R}e;>!F2^; z)EQh?5JsKBbp>J68C+KoMxDWR1!2?~TvtGcWtHcl&fvNNvfPhafI5Tg3S~&d)&;0D zxUNuUyxFh-bq3cJX}RaOS%5l&>k4)B`{DCZXK-Di)^IC6A9V)T70j@({Q}e(TvsrM z#d8;+&fsfbcB4zK1*kK)u3(*JcAk$qgX;?QaxPl~>I|+cRD0KV(@|$|U7I|+c2&2y6x`Ht346Z8(qt4*Ef-vd~ zt}6(m&fvO&FzO7hD+r^`;JSjwVbmF1R}e;>!F2^;)EQh?sOSsojPNyQ2&2y6x`JUj z>I|+c2&2y6x`Ht346Z8(qt4)KU&5#}xUL|KI)m#9!l*O2t{{v$gX;>ys57{(AdET# z_xJF=I1kHMi>-ylKaDNd6_j^eD{);x7}ro-R}jXv71tGnaor?ibFSsO0x);D7M3yB z6;zIEVXiBn_JkQlQD<;n0TXi9DuFtK>k2q#GtnM(2G)iRcXdRa!F2`1l<4S)I)m#9fU>n5QD<;n0hW(4I-<_tx&o>k9^-&IgX;>VYx=wP zs57{((DiSBpakj+t}9ZzJ$IXjI)m#9wZ@ik1L_Q}E7+kz>E@%(;JShx4yZgIbq3cJ z>|r{e`KU9vu3)3qww{kVgX;=5A@HjKbq3cJ?C}Fv1L_RE_GPPz&zOojgX;?7IqD3q zD+r^`;JSh^>I|+c2&2y6x`Ht34Ag8=Y=2-aw*Ne~sHHKs$a&P*h_NrA_C}0-1T{Hg z>^m|x=UUt=!E23U+7HZi1zJ68C+K|EJvNe zbp>J68C+KoMxDWR1!2?~TvrfAoxyblVbmF1R}e;>!PmZoQD<;nK^S!g*A=3i>kO_d z2&2y6x`Ht346Z8(qt3uRK5UzDF8+bF*z%zK!`R~9E5;VJ0`AEoMxB9swTMw?;2thw z)EP21=UUub$7_vi;2)Ul3gRcOg}JU!oXXEDhB|}m3gv2#5PQ@aTvx#Od;1(vXK-Bs z#hT`ELY={N1-$<_%L#P`*A+1RK!OwLj4@A@ONpZ$P-k#mq1^BoP#kpz*A;YM)EQh? z5a&^6a9u$dbq3cJI|+c2&2y6x`Ht346Z8( zqt4*Ef-vd~t}6(m&fvO&FzO7hD+r^`;JSh^>I|+c2&2y6x`Ht33?5U$s4Zly#g?95 z{G-@%u2XDLE8sIcE2tdT!dzF-xQ#l4 z>k8s9>I|+c6l??P46Z8(qt4*Ef-vd~t}6(m&fvO&u0@@}bwwIpi#mhr3KcQx46Z8( zqt4*Eg8V|A!F2^;)EQh?5JsKBbp>J68C+KoMxDWRg|O#3gX;>ys57{(AdEVL>k7iC zGq|px`=ZX^YhS{sGq|oG8`K$GR}e;>!F2^;)EQh?5JsKBbp>J68GH^VjM_rRT5Re0 z#XpKIUmHE2tdT!dzDnPf%xY zT|pRi2Gk3wVashmP0bEzGzq+O3^9zOR3Ksp2;qwa}*A;AYBgf*X zGq|o`*B*^1fjWch3U;nR>k_ClxUOL9d|KI~&fvO2y{$$%pw8gBLcQ11+7WdI*A?oV z&0QQ(XK-DSR<3urBkByUD^fE*YVL?SgX;>_WsajG>I|+c)Xm!uIiSwqxqsb@mv&Q)ERg#3Nh*oJQsx+bq1b`LX0{C&qX0doq^|~5Tnk(b5V#I^&=g&1`Po{K_EI)k6xL5w;B&qX07ox#sVAx52n=b{j!&cJg~h*4+Y zxhTY_Go<xhTvpu7&Yj z6k^mFcrFSt>I^&=g&1`Po{K_^Is?x|Ax51+=b|`9oq^|~u$(`?Q1Dz7Lev>}E^0;p zS$3#1@LW{Ot=UpgXW+T0?Bn(sP-oz|sCD@t&qtks=b~nK*T?4<49`W~d3sI^&= z^I^&=g&1`Po{K_^Is?x|Ax52n z=b{j!&cJg~h*4+YxhTY_Gw@s#V$>OUE($T~4F3FrFzO6E7lq}hGw@s#V$>OUE($T~ z3_KTw7I^&=h2^L-@LUvP)ERg#3Nh*oJQsx+bq1Y_;uv)Xo{PeA)ERg#3L)wYJiCJ!bq1b` zLX0{C&qX0doq^|~5Tnk(b5V#4bHKmp7h<-H^&nRSB%M|&K)H3elt1`TC*!b0(FeV5+d~yUAm39H(%P2Nb-FC@7>g`v0r%tRzMeI_luPNvS>^TJ z&MQGH#8{DY$`mE{#AMQ66>92XPx7Nw%*CzSdaxWI_WTRni-F#o786%zuZx6`8hdE0 z>vSv$mfvemZEiCz4$`%KMYz64FbpqaAY5TlFZgC9*0*=>SA$b7OQ@bFvm@cvq{oD_ zXAOacA9@g8`K7N}HnQ)szj7SR@m=;yZl~c@egI zT?Bee)l+^O_S3`gP5u<;!JlHGTya0j!N@H67mBqhA!a;m45btDW5TtvPcaMVL! zx-@EM^ZQBAYhY6q+ZmP?2W>OYAbStTXz=NOneevkU7+We=7g(^jRU8bo#|e+?q619 zEMF_P%~UY>AK!H2&xM??P)cZf6nf|H<1bbG3E=IL1I)Y+2SaJ!2SG``)CaJeov@FDYX;*9T- zJ|NFo5l1UhdC9y9&~H@;+3&G@s5EkFLfFrtFzClkAe-2Rz2W)5(}cg=>k5@T>k>Xy zGae>A>O}TkoNg#BbFHKDO=rU4ZQ*Iu&h%b-uzOgZY@U2_gQ2CxS`He&Q!-w0qH=eO zI%e6Js$Xt{Ic=7GlzlfRR&s3Rn46PRIgfIFP381gc?H#~QaooJuLNF`#rbWUfyJQO zUxH(g3$;-!G77y}*`g9(7YV+#s5x7yTH1&BR%wwQR>g>S9Cmexh9(tSQBDU$#zEez zJt?O#!J1cnT@{#Hv+^#*0ExnO& z`kLXeGv`3UH~YrGjAk9le#4Y|%ACido~6F&;PC$DRBp35ANb5DOW5tb4i4W5Bs}!^ zCuL935`>4ntPiIvtfD$!kBoq@Gv_EiIVUDTwbkMr{&|<4@afiVvWfrN5iECz^Ok+9 zA67h#vWwB2b3>h2w6 z6aFR)Les?fyxF%9ob304%6o4MhHV+dwJGm>A)B`karov)OIYhI-V-e78VK*J=ArV@ z16xAgWHBbst5*Xe_vWYaP1&16f$@T$>eRbR$zj#0{B?K*cvwV?8@ujT{0Yl8^0lVw zm)jt>O>VR7i|nK9yQ%odF_dE~$GlHf;n$Ac6<|iovlPP>iCurfvd!jKi&dQ83oeNS z8AomvYt(%ii!#S1VoW=;DHB`kDdy7;a~`R=D|Vw8=2A|n6$|$vyf@=$_2XHwPPlP5 zPg=dKVhvesiwn3nN~HEA=I9IMB5i2A9e+#@b2Hjd8{WK6fOn-k5x&?z7XA%ws8&v_ z0j8F_t;+bMS1xL2nL&vl8gxJEEDmueK$<06%a~s=v_G$WE|ol?lt+* zE!A#Y9;&}c&qQbsy(zZ&Pft*5Jn2FB(c4rtv$t3$cOHFB4Zk6@f2}cr>T~{V9&l%D}`N)&BdSc)m3qeVTDEo;F0E~39TZDa@A z=M<%Tm9Far=Ge%-%l^u7FvoYlqznu$V>Vr+`)rAW z&LE&mxay+^AbM)pap~kiS|4Q>!O^= zBmAA6ZIbFTy%*UWO)x0AHw&BCh+y?(4&h6kk)P9cZWMcBL*3jU)4n&THN&q#0UFrArSUb z@Zn?>z}l`tSFW>)2H%#A$R^9{I9UF{kM7$qG8@G87W+1hHuh2GKeVUv@_p-pJZH`I z&rRj~3bum9(*>8{WJg`VTESuOGr{t<=pY?6);osq1}K#O-doD~dTbrs|j5 zU{0H5A7$UoiIp5%Ip*f%RL-NEUsE~#RbCC7F1Q!(yCm+dmQ(HsP|$o(FQq}bbc&(7 zXj|dAt(4%#t?Al|&$2?1+M;dl`lq@zUxbbG#D+?^omfl%RkkoR8dRC=YYnafg$9ZC zdH(Zt>~b%9X4__qEm^Q>L61Hnz8S>e?3;Yw2_m zJRVns*0Z#$4jC(0(7gsu4S;Slg=W7KS_$5)u1Dpm3+!Ri7vW=v^Ep#1e--h6@Vtk* zrIx5a{q(20Q(J}29w!f7hel#uQPyF*vdlh!>M8fp0+MY!2@kqk9Aq20T(+0*E8k0Q zgM44vFWDE_N7*lPVr5Ru<=n|Rm2+(>r!qIp;gZZfnX5AYP4QOlFLED|`;^>YDXYJ6t6=PJhJ zu=qVnjm-X3UieCS7`0CD^XS2Px?~nX<%J5YRI23=c zk$seXHx(Z_hH`A>n8!^Oz9hU{spRNWlYHEBq%_D_wpkStOg2~dy;Nj8GP796ZXK~) z$=XH4b4|={WnOu4o+RwMKzN_o9!U=my zth?j@?`!+AH~wSo#}&>ArFOJuhj#Y2pS9z?@^5HEl@dayct78!$oOrgR?NS!rhV&rgr!B<3;xhYAFyKpGHuFY@;-?z5_z7RjFYa}|QmS%xWGj{_hp)Zw z>Rj+{aa-b8Y>7;evAfXAv&-L7N|h6HgtB?N@@!Nyve_QPzhm~i6yXKcYJvM*!Qr7z zN`udhWh&H~V0+jx5@yZ1qI#|Lw_C&4r(f=sQJ=2cUTk7i0#tgnByHHokfLvG^w6y3 zXZ2l+V|K^32SVG61=x*)1B-7Q;|&vcH)7)wzLYpuuNe5cxv=dwikB#oa`#r|ro z$OvfrZBd%f(tx7&4tlsXI$k%p$c?Fu2I*ne8h3U0`wTX#`F^T7HnQ)szj7SR@m=;y zZl~g~u1jJ}m|kzE;?z{ED>~1;rz~yXkaD*vk1cdB zzK8nq{W@Xb8stso>x)>!_z)nxC8IMGs`r*`9z+B|zQt?R`4P)(_udZ&mamDL=H_bS zb36|6552Ft4j5sVl)ob^E_)&^W$E^!jg}dxH)SkxKg5dmT!P}NoGeRxrLsV|~6bfBF3a$>kk{@iNYLPF4mX(6p z?laRS=&Kd&TSpJ~S}su^8HU@|o)!tGhkR7~zuadxy>@%(RI&i`soAf1xjfCF>%@C$ zwGV$Ty1HEwyn1xb*2bOmRl$iOip0<&4bFaeUtmb%*1+oywF9g7dxh+*k5#5_@G+ z?%G1mW3KF_u6l{q_HMAqOZ1mDt+RmDKCxD5`@|Y9&Q_=%=Nry&=i>&owA~ilwGG0d zO8o7#q3WxmH#;Xmt*z-;a@l8gmDc)0>4k-u`?(3l`wwUW?fR7=9zKmpfGelPJJ*2^ zf??JRYxQB|kYWWZC;l{NMQ!h+u5w#wb0NAf-0v)OM9d&h_@apCR%yQNp?-r5s_I;+ zSh-t?;H?($=-OJDR)??md&P883*75xdMy*ZQKIm;A7cG>VUcv?6!0Y zfr$BzYPCx%i?v&p02eIpr9L`(r0|nFdg$Dtzxuks9-9}dW1vb$yW@$$BVW-a#E+a%r)otqBksC!UR_EvOG$stMh}GBks=?=w(6 zll|Ml+HbSzUZ?z`pkHVqD&MuT2_y|3MCBXm$3W@9W70CkTNkwp=KH0GW~oE(dD}i1 z9tDqDR7`6h6jbEO4n4R`sH#i6A2{u*s)veC%27Sxoj`rSH73r2Km0S zU$QT)gdwS4e`y$+pCSRu2+jo;s?xP1Z^pyfmg0P1J-!Y}z2iycrSiu^xd)=}^!KU{*N=;LsGUmnfNUAWJ7p&y z{)}ZC`C3!;%WaU`CbwDkMfOql-Bf(!7|OAgV?O^aBY!)#>;ZN9`FMm*={YT&>o^(9 zHalN0rhV)g#q}WL&c)v%!`zJ?))|i4TyW^T^tw7Wycay35^Ts8HD6hnY71pbwlgT_ z8^CcJRnb+>koFO7yN_04 zl~=Qa^Y#H5$9x2E%uv>`Zrd_U#@8z*!t(3s9m?e^s6Mz^1V(*qYN&A93uJsWj{{iD zRvcHfuE&<-9Hopu6FNKDqYvoH*M?mor5*d9D9OT}RD_M~syq5yS7U{rIYNt^wH)Uj zsKaJ1XaY;K6?VMTrx5$Ps5?}tsXFw_v|ru4ydCt}m(I~XDg!&bzY$zcm~QZ|Sq$3f z++abav4$OMU7^PN4zTd>SVQuO$IAUYVbHQ-e?twcy-K4i<>1V+{)S;EJs_!ILD;jX zw!v$0Q$FW@QVM3eky86>AOt*Jrd+KteqOA7Bs}8J4z>rrDbZMOm1bWi44QuHXP7j1 zk22zF3=}y~%}_T(KPCKp5V#hfV5oNRwPKEq?7Qr*90zlJm;I94Df@0JKEE0VQ+ce? zv<|e(Sjw?ne<${Jf)liSS<|sF)M4+|RED#At2!R^tHLIXX$76?=5nmFJQq7uS`Ta2 zjI^J9W_jbJpznS$}XW_swBNd^)zLe>@a&D(z4+J*d^jHGn;rrWxiG zv;&K^f$*38B*TQEpOwJRmEmgck%nQGRiKzH|4xMEU_-FoF(vS%Gc3=OWGJ>=flE~j zK!v^@hQN%?p!3AnO24$jDQ)frLF+4vl#_pj&zo=|63+kC84Tk`8jj_?uC%Hj1&ho1 z8&X2&D7}5!LUH%0hMG$=K|q^$$W*Va!^bAI)xCRaLD^fS9p8DCViDJppzrh)`|}@I znp(LD6j@c+ac-`{%tdJjYbK?4EMGPwE4DWba<M+leRbW}Ws*W>mRc6zi zI~R_q2khL2icptD3=Ot`(o`yPb0VvbC}%PXe4?QOtpzuc-Q! z>;#pwj5buNds~s`tiA4Spz6t~hH|~KKw9%~sIhCQgV&)A>Z*M4aDI-fL-}W(>bmA# zz~{nn!vo(-%G1B1Va^L5L*Jd#m2#uo!JNb?hQo_8K-K;|pw|5L4n6ZT)!U&b)Uk~< zEWNW$3H{~@O;-*v6n$MC>O9s%29E_LE@eHC>USd&4nCjhFkWaoc=1WEXL?T*RP?yXJTa9!YlDm=VEb( z`VFh88&bXD(ES3AV`mg##S`=}x_BG=v6uR%mE9Ns^G<(qc=_&|dg^X{C|Glvp}KPk zI5&r%!`?L1V8_lVDairgn`yGaxwHigdRhrAUkx{GDO?pgOb!9>++z(5qaG@~_#STk zfNq9Hx0We~C;GvG3DXQ#d9%a2E(y@3c>#w)pPbd1HW4tY-a?0lBiE?G_Pt?=`%nk> z$rDw(j&U%#sm`Ili;vpfD-rVcxRFvi&Pus`AQlF__H;R=b2KD=3Rd=|^@JR*eGJyeHY>BYhrsa*V+^*39w?TldP3IzD;z9>H>>+!M8Op6 zu?|P;&Qwcu<$E7}n>y6L*I9kY_X?*sUuO4q;>oSqHu1AD7pFLsJ(Qx>SjfNMZtI-V zqPedwQ&10BzAVAuw3#X2JiK9Dff)u*FKbwGC>#zPiZGO{yH0W0(Fa~#sb#p`c9?== zZ_}ZN9GvT%R)^H{f=n^R9N*6>%IY>!a0XwhW2OADu?zbz|8EgQ|u0vP@?(!tp(@gb%@ANO0E4k0_M&RHTc@BP(rWA zflJ%U4tdXcskcYY5r!;Gc6#%Gy59b$#aagtEyi9U{AL zQM>x`zECK}eyeU`TJ|`uwQjbx_q;LSCoJ2@*P5zdZiC!5xy`aKvX8Rwrs5;VP>!t} z^WA}Z2;ClGUwp#YG|TvCIDfpQVeX}=ii~BO^q%5b^Q=A7(;^-T+_Tb=R0(@XHaZEL zW$#p}nu>eTi>}6ljKj;kr1uT|Z|UK|=M*{zSi+UR+chvF*}piS2Q==KQ1iVTrg`zMaJXWSpmlL%iLxlzxUKp?5jt|20-cHQ)E-rxf@KM zxrBIi%~lVQHu8g z1`-Zy`bF`K4kLWC+HR$N<5Ket?z$`hQuV7k|8 zYENoTJ=hn|2k7sfiY;Kz;tJ$T$rsDjoTr$NUQ=E}`BJ<~0IV1D)#5%!wUk^7( zd@G(&uFc~K)BA|$N;XG2z}1t2dr3WZD*E1HPI;5L6|l_Th$pi?1wd&16NKXo-QZoX z%9QK4DOKRWIKhX}2mRq){bp2t{(==W%HE!^gZC%p=si90WbpMEDF134adlxkJv{E6 zjchKz_4{eg^5|wm<*RQtgciF8(0%(1h=G<{#P6dOeVhbSArslmp3)ZndUuHG*BuLm z$~OyBdA%u(VRX~}Vg zg-@HZko~!|M6+y6)i1ZfoHolo%D$TuD>=4u%+1N^PkEH`YbvL|%B$TT?iA;wZF-1( zIh{B#nV)IjF?-C$Y1DwMAp?<&Kn8R-e{bn%De z+17;nSa^f$15d(D9@s(k_Bjdr7x0BM?XFNBWBHl!lIQKH{Qg@{c$=|5wc%8v9-6WQ zx>swfzK|mq5U$GiI}fIuC7VK1liWYs*0NL#d^;=NF|pl2~f-HIpHss9Uzx|S@LT}M+NGH-lp=T_d>pmGDnJj@zHFp= z+7=9l*Uj4ywksQFmW_O0`Cf7xP5!bqwjDd&F)(Ubg);$qI z^Ufukm(EcT$$Alfysj@C3S30o!|!Hnyc$g9XV%2RqCw*M-LiBs@U(1ZvN>~E4?|y; zBs_wDS4PINjeM=C`sFsrZIjz9`y%@&`)(>eat!6z$}vAN#FBiudR`9??GKXgA(gxT zgk>9ic8T%i&rj(&=65VTV`cn<;$+ieeLNeGt3TnJ+hW+Bf-?!fd>_T$jJ!_RDsN}D zySF%xG^Ko9mh>oz#)^ecx1}{+-+^$8Gf$Kcu>qZf2wQZ2 ztH{{5v$$9OGd1S6L(2Ijb>*^StcMwr>z;652fp zWCv#aMfKmP>dqEc6Y&fRZ_b(>?MvkzmXV5Up-93RN-tOb8X)#Simp!7Eq*TW=(=lC zduQU1zbZE4#k(-^6AHo1WU)SsY2gNe&&B!SQ+aQw^`41(8W-7; zs>CMHwRwWesGa$K2XahzGeu{PjqJPZuN((+e3$)_+bR2QDn7p&2UB@0P~|G+t8PkX z_F?r{!Y&(ovu|@Z61FT8&U%*2O7Zz{ur;$@CU`O`;thX~Rjj2gp9ZkYR^mKWTCrxV zq@URHVUO~%)lbE{8|QN975!n+?*^CItK0XnC)K%Z!Y1Vy-zUfTpV(!yt=-ISgja^1 zPzo5oeKEx^9h9#i-c=vGxhPD?QJ!pi9jO6N`2IFtn=(CzZUsN%i+HT%iL|Vz#Cuga zs%KInFE^+1^vU_y#g{@S?px4>oyy;y${V?SQmw*1lD|b7wP#0%3cWe{VRN?4_-&kh zO&+IywT&hF+6THTy-Rc_{3Pz6GHjsWVb!uNohLm%e)T4t$+cJH< zqXCi95%v%U#pFNHr-Ws5Uf zlRbad%3j9{&X0aGK=J=7_~~@@p1Vy>!ENt5rxYtcf3iQ&Dm^?~)Q7ND-r=gZbt}S$ z19P(je2)+LoavjZPM)(IMhaf}4YE|aFRns1_kt?3me~Z)yY0`$CsyM+Cwp{{B0Se#p4_F{+fLMPteskHQxy68#` zvakE`FXq6%l|%J^*r}RhW2%0+4d%32_EGlToLI@Rm1AyBPUSqx`8Ac(U*%P|79kYR z*?k_V#iCmhp3x)^8~;RbETeM(>w8G7Rct|~ofTQ^lUjsd*py;6dA$j59BR!XlLUuDYK%}jHmphIDHdf|y-s3YPB>DC zO|ug3SRLN)sYb36_dS}~D=m$GBaGS*-$7@)vNGX0?W(Z6oH^_dcpXefrlG_l{xyF`ndnOAU4cP_)_s}Y4+t}C8{UAOI3Ectax9$fbDg)+KDJC ze~>3x9eh-*D|Wb-P-PprT(+0*E8k0QgM44vFWDE_N7*lPVr5Ru<=n|Rm2+(>r!qIp z;gZZfQ(Tq%g3MdFzsP+=?o)Dqk^6|;cjW#e_stH2MW3=dbxGIT_#NPN{knK;4;Fne z-L`@1t?i=kY`K<`9cwK3*1Gl7v~9hc5l>o9vtrY~iM}wQb!D|{7jbROxPj{RVGYRU zT5&s8Yo_4sQ|spH`z^hxJoD7C>Z9&rO#bWsMRiYXG?ibuHB~*_K=d8I?N!*0y}?vI z*7t>4J5`JuZ#O>q3ClL}wWjKq+aR}1ZnNx*?4#_vsrbk-lw&K$-1)2UYxj`nYI*)l z8OMze)1IfvShkVgIaOsWy}PPP@2INMyQ``>Hg6i_Vc3QSF)cyHMLvr?x=*V*L&4*( zRkS&KHV8Tn%tZF?J=%gfHp}~WA^W1EE~+x#c`YOP{`h!Xi0~2L*sN5b3!FZ&mBy~& zZF<6BpLv9X-t>Yt(<%_YV4DCpZ;mECKCA&#U~4Icoo|Oj-`e87lkdi=Tl?#%{ME#G2y-1l_?*5E z6!}ZM$5C)w1k~U3K!+T-+%gFsZv8; zo%HPjv)5jr^0lLqz+lFjV**06DS9O3GnTPQv|M1J3II-nc(P~>#vpcAQiLPf4iysD`lw`oQ8 zYg*=p)k_t^Z%#SG%*R25bMx2{%3i`Fp;1JXm_4q4F_Xx`Nx3XXHyd zB?;Qzm_ht(_*xGGRyLw~dUq%Wk6Z;;{rNW&!nX+?8Y%}X>B2-iZ7pxT;e(rG=oL^fo63&$t@4FRg83Q^do-4KG=Q_9F65Knkf1bL$ZYAQ+ z-5d$9Y{m)V%#}q+koS0Q;{SQRuk(7n;QYeRo0Tulf)8&k3V`2n!R;yenkcib2+oX| zv|U%It{rjXURVQYK4&FyW75J1I1uVXVaQwNFYnKDr4_u!BoAlzj zRo5Q9;C@OAvT2%>7alJ2ARLj!1)d&kPq_Q+_eyB4JalcX=tOAPvjLU2t8E8?%f&cv z?;fQr$o__GZtV?%y3J}4p4urM4phoa_F2-k1#@gn)i1ZfoHolo%D$TuD>=4u%+1NE zoJTporgHkLyjs-l4#hUhm5$)pZ#m(JtdZb9{0MQZ_=Y4{6?luv+qLfm-A+x~jN`3^ zML)3098S5|>$geyc17@QZYC?pbSQwz=db#vbX+FJ+dHHBD@VQks61nQcBo<@&NAiT z-*rxD7eeJER_-ryACdc%++XB=A@>)#AN|xf^N4x8 z2K%b0Rhv_;3l7T<_qvxLJbX=kI9hW(@x&`R914et{&g+D3F4DesQi-J3sweJAp0HD zs>7!QaqS{QeNej$Cz~5H`#{l5<;Z62R2>|eR*dk7L5-lmJ~1Zu8|hoS@^^RTZvwMJmwHm2PS5+YE;UOLel|9N z^|ZT1V*=}*#Im2yP2=#yb9z?gwm6S;*`^PRY1tldtXS6Qqxzz+p0I7`K-~+7AYAms zYUM-kjsj=6rwp0ej_}Ya8U7V*h)T02f3sFiWHKIPBlh~ z+gXxdt-^hnm5qqQYtN-R86R~K_X>1RWFhCpGs>+|H%qf z)9kK>Q+b^mYt@Eh#XeGSi;L>6FTy5Ebe7ceE5yD^%TLF2FE7NB{Yb0!ivMP@=O6WS zr($U6Nadqi)n!AXMLm0VT~zCb`B3@(_LeN6Yb4?6Axl+rY<`#TvR`sLW#3K3=U3xk zDvw8ty`?;MzsY}txOz6q&7K``?COz>BDR;>vi?022)7GzRy&^WMR-Go6!j#3w+Q*rAlWBv?<}!T zezW}v^|0|7YsHlg?qK{5WUjEAy0Ew6`Fqx=p8TD4@l4a^!CvL0XAi39WclrCWX3?k zU+;ZY9eea9{9x{Q)yi75=T4(`Z1A$BNr+#b;muOn#1_~V)>AUsV#R29!Ju-9!XZmg)XD|pSVRb8OztoZ8KGm?91~>g7;=Ez8p3TZwfO6zpKasho3houF)=P1;%toAVdP&cU zj=V^ie*>6(UDtx_`L}`Dq|Ji!LjoOCkLjV5cjsq^RSV-Y)=m$;xfg39I1@7Rk?ult zJ+fK#)SkTx&qBDgt_{msQamTxcW#?1&slvlh-X+ulSiw?%Wa|iZeP}uWx14|uI-)0 zpY?Ab#=wB=d(_W^{i)nPQ+n2gMT>hCpQ0{4zlyFM*du~1EhEPEvsG`aJNS1xFeZ5} zzfavUu_WQ@9c#0rR{O~Q$;Iw0n144GZS=lw%p4n2^~-HAr_HjDvhU`^N{+1@b8~Vk z=TXkDshs{Quj2OGQ9OHOXu#&jWhUJEOdGao=2ha@hIsy4y|-+sy#5xh`#-dzTs-U? z$6PK8zOB1ur{=d3V`Gjj2i2WJ#F*o8ZI(KAi^ysB%eu7Boy6QaDrkcm=O&(0wCVUt zZFf=ds>uAIYIN~zbT4O@)~sJA@$D4lTn~0C=pxg&g-SuyTucrpE_1-$q&RB)Y2WR5nSjZ>F?Tdr2 ztJeN;RNip6k2)uhcz&HO`muUtuOF3H-I0w27=H`Q-7%V#ew{)wukNa6!>x!;l>ae5V6sl)Wv@@$d#+Pulg*kq*k;`R!`M&bK{Q=wEABuHvxIbHZ zttH|9t8z1s+Tz-hTZ*%NFCP=fCOqrF?ym4A8=F-H*g4NSgjWr7V%6@5F}bmAZB{8t zJonFdqBJ`+asyp^Fd&?{xY&?=pS+D&;e%q_n02JVPgu5*uQgS_+y=RAa+_seWFKYU zO~pr!p&VN|=9VLbUj+^{WSKIGdF|Ns^gm(QM*0m?CS&QhP?_|br%d`SRA!D%$CGUs z&VxPlnL)-o-Re+zqv=lITHlLsp;<*C<8iUa`-p#6%^aKKIZDyB1;5l{GIkr8j&j}S zMIz+Cd79R=SNS(Khwpbw!}g3$)${Mr91xhVPcyxYQL+3?a9{8%CHBFF73=`{Vxp=3 zns25mQL%jpe+n3(`p<4nIIu@nmOEPP`!$U(&T5CdQ+b`hzu3Q_4I6feJ;P_?Y*>$x z3FL1x{{2Q7%Qj64w5K@S=Xz1bBj<~K#c9EnAia%vrg?MoL{-MF$C9Z2y#4t%dpd~w zUdn09{y+BK0=%kY>mSD5T@sRzlR$#I)i|a{Rq!e$F>;*0E zUbKbcR-jmm{%5V3le_Zvp6@$(Z|S|0XRzu7_0=1NN%=4e=@xJE~(Ol^6Nrrrr2)1mQ*< zyv>_6Rh`~z*usdZq3gGM3v>9JK}545aJhNFyF20Iw#(+r45~l*tVtF~l~wWiePv0b z@M;wgS(7a`%u-73vRTXRxegblXAh*VBrd4IC_b zwcAfL9S`>wfqRA$&4SGX@y-Oo%a`uhxjfBq!rNxnHii5?1IAu}$3ipaqSAkO?fS<1 z`U9yv)BDxNlC{eA=><;Mi@Z%vLGa#eCqRRP8eCgia2oP6DqHGEQhE$HXGq&W91zP8=Dih^-C+h?4&m&@(qws0G{UGDhG z9iQ{M<8{jG+EtzM*l;J7c3JSRDE(?d57e^7VWA0V8vHP z*mM=2^{TZH8Fs6+SoJ?_Vrgd8Z$x+VjfXi6f7TU$t^?PN>&$K8Hgelt`G@J#dA>*O zZ?>N)VrtZF| zA@2m@xLmye1L+G68v*&g9Z1i1TKSd9abSHVt5@chaQ~Fz|I@9U_ON<;$)67^_JLk& z9ulq%o#4kHH9vV9+zOi9QD+kTHV%UNtvAw~Em_Ja@SNC%=(9`-hso7deyQA?OmL!Z zN7BLH_SEdOt1RJ4HA=x--vWfI-l+l`-}fMVC+`_^UZoJi`PMEqe~|Z5qAfQL-riYM zo@)3PisrS#h^$xb56t?gw{l z=XP;Dx$Um}M;_K_3p?uP*MDx@h z2I(gCG0?ZmvxY;->}oFEuxSWXSk#7SJkt(?;^kG&C-1Wexxdqle7o(l^l!xj-rp{K|k)-n|IV$adV!`Q-M<-5<@d{0GSfd*bzSt_ zik&mom7wyg^~%HA*Et9;-T4WO`=To0lP&yV>HgPt)cI0|NSGVCkMs@6Dh}tqIcw&5F^J0j zK3#5>*6${G@k0>UUu2?kN1`V1d#pjYpBV_JCM}`1(6UlgJj|cvy1C-RZTYM8=f2{; z<@N5$&k2nsSMlR2W_XjC!&cDK^A6Q}*P>k@$xD4!YC;&)xU6Dt zboX**$naf66IovFG5M)n$__^ew9egv%Fomp26L)5r@9WzlMdFbEKIn3N;?c$t71Fp z7e~z5b=Cf6XqNfriHbK2jL)wNc7@-=(-R&!B?7j!DMimVTwONan3e6fYE+&IY%uZ|0(kSw0lC4AFkHo17@7@>zn+q>8(a(F1gusTh zkyP&Weh4f))0E0D^cV)~VpY7AXqy(2PbfllH@|EU>}jj|oK*pZp!gxx-|pLd(_D5! z?LT%bUmA*4@gVxZ19c()L$x5!ddJ+2x7kt=;EPSzccf~?gyQVxIk<0vr3 zoTYfXx*!r-_+KabhJCxj)4A1&ruOS72+9CNQ~H-k7;rra$r_v_7)pHQLpW+=O-MFf z=`(D2X&98E9m$H3=XsVE-ACu%kG_k7hrt_&&%V@AP@w-}l67-l2;>aPLou2AZ4^We zQ{Ol5{k|Wx8mIO>$K|gM=UaM_te(NOVP?+sgwrl+1_NJxLik!t4rndk1%`f>?*fD1 z_N&RaK|Ke;^e#2X7DL+7f9?RHxja1zstub)Iy6re20I&`B7D7jPx!iYTH^Wi$L8^9 zcsZx%a=9$71DDI~;)KVF^4M@EmU!&BidEhgc-->#!rKUM zQ@p+KcEQ^VZ%4dsw%e}SRLJ*%@bIN-YgLX_f;EA6DF(LP?F>EI4_^QLygEL`1W%ev6I&)jNjofxu{^364zU4ko)oBRXa;(=-xc_}t@=uxcpT@(ShP}fSIA-rc1@_KU zVDCZ&cW4sHJ{tRtYPn>e&G6+-Du-}t*9;@{-B6-g`Jk_nZPjqXd(29PJ2c(9&oPmI zjet;afrU?sJw!7vQr@vy`6l78+g(KI0&fYg9otUS{nC@LluR zd_;1S*6#$*tK=p6vs3Dc*-ujuURk%K0eP`^m;B;MOvg|J+n_$NjlRzVsr;L%hS-+VPI%s|!lGdIK7?Pq-)sC{ zr7L0Yv)9e_+0=Q4eLWVKqt-U3^5`LHA!_0(ivkizrs(u^Z3o~y|Q0>|;*QMCLtp^fK$xW-x{kwY;J~m~){0?j$ z!W$me6CD~UeL6jyXH>pbkjiIvs4SlSUXgIFD@8@+b1G&W_sf~Ldv~XDL*AJ%<%x>J zl=rfNy_ul$3)upp<72gVmTOd7^LAMkV;dSRi)~_8d#^K=FE#Ibt39c5`!flS`LkR% zSA4iFf0h2+SKPO}-d*`Qp|RvDeq6;2j}sn035^*ZpR;|QQp}I8*HOHmt75*-{N^Gy ziOP+SOI%L$U+G8n>tCW8O#f7kDYoZz#J#PBsJzQhb|HTW-`!eB)DKg6@>7X#o0pTT z*gpTdjalnq1EP7CJr|7Y8$`H6y&`aQjEa*v=|?on)yhgD@#!s1498UeVk9qZsY8NF!eu!=7J&5T2tHqdO zLz)tvd?tgKIYjMk<(m{>4*N{S=W35kP%?$$bH7(#V{$+nqVL)unb>$twTqK8%Ny>{ zxZ=-sa7SluBe&fhUvb}ZpSx41ydHV|x~kKJ##NfLYP>siXo7L@tm;2&wg29@lCv=R zeA0Nkcraek{P=c~aj}XT`_|VkBuZpb@s@1v9rMcfs=ijQ?_lQarTUzWGnSYQFE=AT z*|w&G&tEG(H8+em&&Nhk`8j#7^N`tUK9DMOvw12}KPva0yVK~?vnAo$yHklF{W}nD zQ}>1O!?~V>k9Ig=c+2k;;g~z^+-Up#^6d#XS@p`O@U=ScbY|>Xqw6b0Q>=RPokMr3 zcuW5-zu7gLit}Ty#+juCsBxkGnY7}~(00V9R-?B@&u6OdZM^clapzOjroI{7+_*F% zm}t&sOCpk8P&}uW@;0jFQ+Qi+3DfJj(zEILl8Sh69;=UY|#s+9exeZwlnbB(QW zET`e+oSw_&vbYXhF1L%@!foVsx#KH$e9r5R*D0@SS9Qu`!<|^-vF9pQd0XId%i9ZY zBfL%V_QKl;Z#%rb@V1#ms5Vvqi>2nXWvZ=(rRr=>U8Cy#o2w1&h1;vPlWEI#W8#-8 z-X7IYV}5Z&?UQy&dc;_CMbVpUlf|xDtMKn5Ke2BOQuC#n_pTcg^m%}RpN8*PSzFQE z%PH>&_fm4b_)gpY{g@rG9CMnr%w(PLMqdY|S z9ON_T=MvEHhm_FfWlrxrsarwG9UTqi|Kp}`xZz)pWR1LB68eXBBHUxouV%R|{RlUF z{hb-LZ7|^?wLUjdho0N!B>s2mu)29)(kJ8=m?JwkgYt{(J#frvHjb-E^vPNl zgFhmIVDItiKEo>%iHF~&A8D?;8tYl$$`Ii60~$7imW}G=uQ??>44b9oMtyIZM@m(M zz1hb2yjoWbW*@8#Gd!;Qls%pgW<6^HXA73iziMViNbFq%Zq)SlY5!Re{89XOGjXix zRqt+l@ZOLc7X38O+kZ!W_^D(H((Q}Hts!eW55m_s)P){dc2XS;%hM0WJ5(MitG8?) z-vtoOk}n0c+hHfX=t?2@^|aax=-=&%c~!nU2kUoRn`}_^dPeh1&z>F!LnB~NVa3P0 zWGGa7lY{tgC=~%?2ks&KX^%c`(QwX5Y9p+!k3CDX+_imHx6Bs^Yj`?M%cRs^66y{b*O?6?*CGQaa;t2UU zWNj~)WAmZ%Zue_KjkGFHo^(|RMDHy`<(W>}VZXiy@~v+mEWF;B%7=JohW@*{6YetV zf;sv-b=Ovs6$4;%yB5Shw>!RPlB@V}6*D|ec>E+ZW_Wx~ZQTS~jwzl$ zbx0;?bG9ZF*m25dukeAjb$y}EjmzFg3)X-G{hLr-|JEcE6zfqQX6Fs{DLktL1YQe- z`68>&#U%!`dYA)hb)Mv%ZT~0Gb5|Oo_wa22lfPO{^*;CZAPC&A_E`7d3W6zVDickr z+5u2uO>ukjU%Sss`a=}>E}v#L?w2|rBng9t9-HXdJg57|8?$=9`foj?UahZo50a;=biRcc)HyJ@Wc>Ri_D!tEe0P=EzUCdhD1p0+t+} zVfKv7oUhi#Q1~(`5H|Z|_R0CefLvV*nUfRk^9b)e0-A;9fRy*gdxz(12s)kbDwoUaaeXTPr>2=gR;qT!U6xj=wK94aQq#d2_tHgsKy5)t~ zJH^iCy)`WomO0Lt`$EckO}yFz^7n2Y`-#_zJbp1z&>*ea_pFvH4DK&h->daL(H1Hd z7)i2jTo?j<(-tH=dcp|UAm0Vn|LkM04D*5^f70TxVP{F7DmN-X{rQK?u*+Gz?&s+Z z+k@|$!+xCY<=Lt;rD7bTBf@u!9@A>>x81$VV zLNp6vhC;yc`DSF{pnSg;9t=lcrlsGB=us53I@e<&FMe zoVr4Ltb-#X;g@UAf|A%~&)X{R6%oynm?Os)^GI|*0t)nL8kFO1-+7TTPgAJwJ#*8F z8D76Hm1p5zl`@Z?zvXcv=?G|htB~33^nQ<5ZR2B3!=H7Q`cs>$|PO?PP6cS8C1L-}`C#dq5)0IqkQ7cDN9pR7UnZA5-?&{yrt2Y+WhbGie^y(cPJgM7S1w=R>3f2m$kaC@oBuMV64+z8ID@{Q5Iq!;y4*CpN7mh%*T z7gbJm!LBpLq53KhANgrDqh@K9+fQ;l+BkPb?O9BGUlokOndsT?S~UUhE~-v{OX3UH z8#Si#ea|vO-ZO~_zh5E0{~mpkboQR!6a0>+B%Dd+i7Ql5-;=dh8w}eEsr>4hLB-95 zgB733yEB8$uPgCMR_BJ9eMD8lH-`9wJ2c#OZZG$PJGOJXxSrg0SN?J32W~s}iK}{C zJE$YsUTo%X#<8iY?s8A}5P=~oM+e8#icjXKy`Ik7Ok?v6l_$KKE2%keoyu3oW;XP>3G;j^gl1(n!d7xeh%WJJ1tuc4|xb*px)@ z^ya;ZmTs)#_V(r%#?`tiC%Mb-LF^|}RIConb!RPlB@V}6*D|ec>E+ZW_WzQ zTd!h1sJ(~Se?-Ony&7pnh2K@okAj^>+lw=(e!bR*LilCXUMePkV#x2NQk~u`f83DY zStb0i_EN)VhY#UQ18c(B)M`9x@F*ulO;F#7OR=#X+-;z~_wn#)FL-=L?Po<~*<^OQ zsA4tvhcvN{o~rLHRoe^rnAN69dE$RKrUd-{M)hxgi#?3-df)2B$tF7ogw-ROcWv{+ z^UJFLKmO>oIi+JIDo@n6C@d_Zp1o14xUssM>cd5k^pNuF6hu>IYb$uZLdELkDnaHi zDO7vuci^o(qg*>-8}E~Opy>{cEB;&ucXZ}9a@*bU756RoxjS{r>yg*5t2#|+Ty4p# z`qiGpa+?$Mz0(Gl@*Xkt`J5No%&Xxl-j)|#Vq{9E;!V7-3Hcf~ zAewTwbHREqgYbfWgOlvHZd19Q?fGK@7ld-SL$>KIe7E>y+2Et2*Ve;Z7{^ z*yFLv^7g{p2yauoz3_Iy+Y4_;ylrm#UXSBv3xWTO`V>DsI^~9g7t~&A9^*Un z;tmz7gP~&VfK{!CX7%nA&_tet$F?vrTeh9G+jk?}y6(^B<&)~!!ri|!AMH^z6)qRC z*Bq+mR}WL1GE2W#?Q8p{wPyYqs!zTl?~q*4N6ouxjdhq=zELr0t79`3f2P_jG*4$P zuBY&igR{lQjD|n!ia*zZ>&A8Fws0G{?XLX8eaL;wecpbYvLz@WgPEdrd-7q`Qm^7+ zPLs8BV}U-Ob}=(>{QQyf^PDPMg5H-_czKrPu_e6}|AzT;o7ZDiKhtN}C+4Ba%Kv4{ ze`D5dp!$|(=`+Hh)U|1D&>{11xS2oJKv|JD`oe<7`AF_Bh3Y_fNNK{qe^v%sCayxb zU(tf_pP<9yFcmW!mIjy{r#W1L^z2r=JaFvurHZ#Z0V_?89iMms+CHvJZ8%$CANk>M zx<2vn7Xy^6TSWs+-=LDj|Hb#^VC@Vw-@ZO}mAN9hnpZrCjxhaGDEiBLOPOOYt8p;N z_QU4#0jk}V%9aOmf30HRyVQS}TQ{X7xv%9KFxOI*;~lzpDAY<>jMfV_*|t7Umze4+ z;&}v&EVh8?V?75$zYE6*&o0snHi#so+qBNXFzdV@;bh6GLGEWM$;N5-T0-mONr=yk zhY@fn@g%|-SBF8bB}eHyFRkxKxkbZm=k{_xxMMrFi|fg4cjcdi`oUE_{_VVKE|wYPOZDAjJRg{PRvaH%(tj93`(!+cXhAhX36R8sC-NE zx8|C>1qkYv?k(0O3Q6szBw5>YeHHgQH+}zs4rg)Rga~`R2wc z%Ky}s@1pTFl|FxTsv^&2sJPwTBo^37~z&{`Bn7dqZKyAcMYp zwN1{y#G|?-w`T^Ac$h!Sb#ujs+wxcG&wa&x%j?~hpA#BOuHwg4%-Ie0Kc`&gj#Y2`qMnI0Q_ET)1*&hi9ldhoh4(A8KjzVV%NAKZmSuj+x725;YqjT zif3eNs5z|);l|SnKplB+Eb0(dp`%+guK05u+|ila$ZdDWSKPPU=kC;Lyn1By>#9x@ z8dpUwq$A&!+S?4~F7_krRkj*j>#JhSr_3qy;F0uHe%H4djNPE(EoHJqkR-yJ>MQTL z5%7Hmlj^s|)O0r|u{DW@H4+ZFGk0y0#<| z4(ALYnnoi=z=PEz37lEV%w=FXy9t|(&^jt2N#dY9vxm{d;ZWp)L9bdWQb6$76 zPI+Css#6{t?!*$0Jszt({$0f_Z!f%!@HWNU3vU;^z3_I#+h$0*3N((#$~Kj@<~EAk znolF)(6+5q@1NTGL;6AaDK`3FssSq#m8J5@4~9eG*#T6Z^Pqq}!PBYy+uNbAdZv1| zP~rY?wOlEp8F92MJPlUgRZq1y1U@UQ?iDF|wU0c9ruyVz@_g6%z(d66o07d@=X@2P z{p)+fnuQsOkH^C%kmZi*Hz0Gfc$m}hXI=5Hh` zG%L}ECI1vgU-hGSwjYXuWyWv=$BrKg4+Z<1ErbWu?hmo2)w!&_wjS`Gpu?zN)SNBN z!6<{{TS?SA4kG6c0FIknQn|+>&3D^5o}WhL6@8{WF#A3JhSr0>$UQNRXWmz`dId!p zGXvL?PsX(y0Jr^>Z)eVkv1e(oe7ovMA>;WNwJsiaB-D5+-@$|a^vRYlsBZso!X0{d zGxNMr`jjfWHMU>hnH0}c<$Z+v(%vB4sdQHe-;<2!hhJ+Ay%VePx{92)-no5?>dU)b zB-Bq_oz_-cWWVG%aF52jhYcg4KnHa$bmXE?=-*f6Kt8*Y0W!T(JfG}p4YTg3{_0kE z4H)v^63H!5w7Xk0+;(m+_k%mOa~rvy+z;G8|B4@6)nofQs*c(noM-p`R@L3z$%BlI z`&6Aye(z)KJf&#bmdO=+Zc%Hhm(FF9!%gXTtlx_z?^YbJSJmnBUI$_qOzuwQRk~d? zBO_JLVavQQ2)e2EAAQpGgl>tv$>(VB^8 z+&Nux17(GsiGT&8<`Q1_ZZMRKRo~HG^Qa@#d6AvuP8`+{ruwSyvquf>12=CfeL}CD zH)rHlI%l7^#$LQZFwu|dnglNDJ*jNL4T3IaP&CCSd=opqMGB%xa=#TEO+JToejx8m z=;-l?^gJRWq1yQq6o+f1o; z@t$S6x#GiZ`K$EjzT&>+_3p~g35_LJ@#89Hc%1O~NodUQ`1F=}H;k);j)BI=t19NR zg?Sn252zTZUoIea?DbR>ZwEHXyL4Kq@+(JY+0X0vUvVPi4*8B%;LG!9??B-CWZq z@A^T%m96687L6VNhdHuSo(}c#=;w3G}pT!cTfj%2m z47_}D#q6tNtap=1J7!dBNi@4tr-qU9RJfMUT=9~3u-ZgpOS7z8vwNBrY?}Yg(cRAv-?QThUIa1}`jdTvPT}qW>eDd^=IrOl~ z)npo48J?U;L-bd&w*ZmzHp#sP65{`$TL{!|q}Bx!!kR(G>0YEm z+LE;)THoJ3x^{iDr_70CY)@@|H0WWJvZYHFhuL(a((O=-QRWICHLpnXNk-T{Lao_X z=PwM~8mc|+UI%Idr{U$Cp3CL3xDH${w~O1tZRB>j<12T3&g+iXDX(i+b;@JIomk?r z=PFitTi|ia+Y4_ayiM`;!rKLJFT5S`wi*6VjpMd}UNB?J9~4(bBicjT9i=H|dVf*| zrd;hpctx9==7LnJedS--1a{q1{qxx&XUxyjs(ja?4b@=Z8uje+wq;;JR<*}ky39^< z>g+(`Q|_h#9%5%8X(;xlISXftUSwVyk!L`vDu zt9~QXuc_i;PQ#yd#h>fIb>lj7Teywfc31x4KIFdTK9BWNc8&NfC2TL4n{2P{(;yz^ zG}w;iJE)1y!j>Pb7_ef%iUBJItQfFjz={DY2CNvcV!(<4D+a6>uwuZ90V@Wq7_ef% ziUBJItQfFjz={DY2CNvcV!(<4D+a6>uwvl9Fb0IO3I82wVRDA$2Ne^RA1psuF<`}j z6$4fbSTSJ5fE5E)3|KK>#efw9Rt#7%V8wtH16B-JF<`}j6$4fbSTSJ5fE5E)3|KK> z#efw9Rt$W+F>vW;)^&Zo4 z0Yl-(f$ILmX4Ru$-_-?nw8fdLPFWSym- zh3p5MG5r6FrHvr_0fGLJZ69RYCoJ1O$hJ@ISGIkSZJ)4g`ykss@t18MWZS3ul5HPk z+b1mBKFGFDShjtTZJ&HA+djy)Pgu5nkZqr^Z2P8c`-ElNH)Y!=EZcspZ2N>|+qcWM zPgu5nL$-awvh5qP?Gu)5U&yvkShjs3+dg60_JwTwgk{?ovh6FK1BMFO_6f_jFJ#+~ zB|k79TK;k0KipTYFpp2!j)ZLc2KrpKeIeUEVcGVDZ2JPsW!o3B?Gu)5U&yvkShjsb zwtd2~?HjV~6P9h?kZqr^Z2LQ9+b1mBzA4*2VcGUg+4c#`wr|R|Pgu5nkZqqZ*Z*VG z8GWaIKHfQvrN32o|A%4#bc2G`eF5wgbNRS z9a}k1AmIWrL(GADJP1Ecw#BTtCJo{JTkn|oi_faEErgL4pTTnEfxHkS?^^T1{Sf1? zEVnz$CB1=I$=pI1`AGhRk-z*ENP{xvXM|B7`3zx{DP<7WG6^@%xG08|+ZnyV_!x}8 z!Q@IFary|Rr(pVv(#PNUqi*sS%boTjz0(iKhcL=yeiO=fWEbj#Jml{dL;0c%`qE(a zLOw&96kqRmXqo@Db(iAnT7Dn8?sn8)@o%X+{{5a{j}bICKXamlxp9V?zgPGC#{6+p zTPl}*1VrSmPI$*O8^~Y6vJB*Bge5J=XK0-vd4S|aSn@_1{WB8FP5cj*qYT7IFaHo7 z@CxXWrMaB276XL3{8(RNH@s`WgtfW_=}jzuC^^Bc;g zaw_|WpJSN+qow{tgS=hU9qVUs?4vrx{+o>vIQCIF_TOxbp#BLclBjKHyvF!Eqy1dTsPgECn;j(tx0cw-IYk7FO{ zplprPM=(9(jd7>FGJmP=QKL|dCGQZ*2CqIiD`v~i?k1+CJ^@6!M?1P-`kZ{Qo z>1B+la(8jC#~bQf&z#s0yK%;2!qq*C$-h?!%Q!P5^6nwLW17RnUzCew_!(lPRnN4Q zea2%Gd0{#7o|gV_wANGhw;Sxva!GF>MtaGIF!D*ccqw5I{{v>-RXYeD^;&0k8he_s zS!SkrGx`?cB>wHp-pig5_P>|IOlEsac+!%2nB$|qtYnF4HdbzD^akT&F#ZOUYcPFe zKN_c}@j87arB8!jjR}{plU-Nm{$b=ymz(ge+V2sQ9}r6#!bl^ZHPLocKFfS)Fy9)? z=Tc5wUC6N`u8w4%99MV$G#;c6@aIo)f`!?9ej^={2!F#f`60q-?TZawemL1wDxcEm zTs)eo9bS_yO9Fp)NgwPLKz<1De(&)7M1Pz2#1W%jM6O z@ViDd9li-MTs>Q4^c$iXG36_}t7jQaESJm5?M#-*u)%2fvnDH#_bk(a)5Lq0*}`R+ z{8{D`lj&^oXPIwZKFeaj<+Cg{OfHu{%VlwTPQ%MF7G)ct{@KDGgCG7e_hWOy4>DKB zzS|iSY_9u3=j#43Cu9B_=jzgzI7fEQ7vkC+&J&ouSdY{eah)OiW@o#MxAtLc6a1WL zke01Y;;pUzM?K0hFK*36Sj!Yxj(phK1m#jW%EYk(Y2**Cxd@|79*0gF(Oy=LYc3}} zjRT5JqIhc`CKqXm9%bVC2kDUqUt8@Te^bu+@rTx2CL)x{{D3?F%aITB8_K0}l!-PY zjr_qi7h#mi>V@PxZBwN2>QbmO{P(XY|5y5mlT?^NoNQbz$_* zH5c;1d?V4|dWgv-8Tc&vfa&R!f%;>ophJMKYXxPzGXLZ|OA`+J*WM z54Pqa9>|OHMy&IVRBqMX$5(gQUS&T??bgDUAFLSot7AZo#fJ`_#t%cBGYK- z3%Dlvt8mW@Dd1i0r?f`mnDY;Mal+hpDl5rNvhTh5hesm9T~}s>v?EU9o|!mN$QQof zy@>GgG(}-v?plPKJ}w0#-z}!~=e`Z4;ao@&JjWph)F}=xhucW*j352smyoH1D=yCk z?PItTk67a|jA`jDBfVdGv{)MzZ$-L_g~0CL>!;PxY*E%SgU4E#WJP zQ;VWY9*{o&2|93}dVi;Hq1B+o`F$^q*f%!Zh{!i1# zm7d&(?qF7@z%l2~;vZQ21B-uP@eeHifyFfGZUWkYiW`B^`;;!H>#ErZHFJEGY-o-6c%CW+nQK@cZ9c?HuOuv z;~r%cd!}9@?BD%`kz`piK$=O+YDoES%1O{w*?r#{85bX=u3vZ;}L# z{uFsTy)av^pgIz(_oRm(@?E26cjxtlLT5J-UVXVBd@*1&;lGLxvt4k^>QS&b6f6z} zi$lTUP_Q@@EDi;WL&4%uus9Sf4h4%t!QxP`ICNPTAB+C&ntH+9b8Dzh@6Pdu=uOiI zFX&zvI&Tdo%;Se+cb?^S>JAh1#{BxMG43DofLb#RB6I*^3}GN`ds0QeG3>FJ&RNM z$Eb6%Ghf?pZYf3jb6l)KRbxvhWxHeQT%$ua<&%l?_87Gj=OX&>0*{Szp(zQ6c%~I$ z(YMLBuIl|?;mLJt@pCRC__6Z&?(waRmR}Vn9eDgCl>Xa7ZN#BE$tVxVafNT|i2KVt zseFCQG9u%K(u70W#qVVWlMZ&+`PY;DMHY0qx{VB6r7v&!hF~%%ANclFh_4l!r&MTkqA2rS1 zp>q_`pV;5WxScVa@W-z6{5id0bk_sq+rX0{P$Bao!i8RiL-rHFf5M!GKg<2#>e=4c zJ^}l|9DsG#VO~c#p7b~3Z=@dpTd!{*T=uu}&^598e)Qh0UN9?jZKCh=EG4wR*OKtl zpDvs2o^|^Z9{GDl$hocwm3x;j3Y%wFB0M*uHsmShMYwUXcF?KuJCZf?SU;#T^gF_+ zllrl8k(M8<82G;$1M&QC@|l=EB^{>A^}v-)$w z_?&aE1^GGmT4a6~4jpVF&$y|xWzIc9O>Zzh0#Sj#0WKZ-kNruC$9tv}(5t=8dp zD4gYZPK&Ulk2_~3`QW)OD#v{zDUUGz#s8xY`g6j#H;T_=Ir4Mrk8;93uT+4QQy;78 z32Q!pG@3tQEtjzTDDIq@)|1LnjgZwMlRqmJb^cvhx zJgKvt@)9qP4HMx-8mJt_)hO|L!n+`hn}wqzM82UJC>POSe~38ziOPGQd(lb!c23<9 zT5WngvDe5;^P&xvii$2XR6e=ImrSj{~#@nY4 zj3S&i)4AA`^VJ=pWy(!4ue1)M@{dtxSN{L2%6-4j3O}U(l>GDLQfYWlMBRh&!=Xm7 z%R3vDSNpyjq+fr9>h1@hF!=4jRKiDxM#9_vKhs^Q?I%aU==z~}$3UXhpM=9#i+fNE zRDaqV>M!3%_{N16^6XSpYbw>;t8NVT^(w8vAkZTXI5 zI9{It@gRvTrF>;J3O3dnmzu;DArSbA2p)qJ7Y`1 zc2s`+SbmXzMh(J`c2^O-8WkYSW1HiDmp)j>>c`6MTYj)&z={DY2CNvcV!(<4D+XN0 zfbxyrZ>4$NhuZI$+%wzXvR^E}BZ_y*fU+6?RW|B<5VDc)n@fA+z5^_YwSM(cc6T^?@!+W*5$N*(e#9Q9-imtwOptEs1ISSCtE+_A=dl;gwdCB-=Dq%tji5XPgwIoUe0}g!dfn2 z`4Q?vSnElc$KgMzFF>B$5Awfp{^5S({?z`XXSx4*z5J8nrX%>O5}$D!cf1v(YxEjj|r&+M}*tvR&6ZVM+X# z#V0#&6L(%k+8cL{MaLc0i;jQ735`$L?&Lj7as4NrBO*S$-lbg_pHBX9cM9aa5%?tshcCAG@Sl_i3RF|b2^+u$U34sqi~*tSo3t7hSMh$%lVi?`dJJ% z^QO^05$F@`D}laRaYk^*!?RJ~O-<9%=EudVP;Py_-zmBM*3gzP?8u@Vaq>YqPX74UDOY{2^ugzxdLlok{wPP@!B6jW)a7(n zn5H*T2hE4D=1*A5l{Tq&a7sGDT2I0#NAe}yrRihmyCcyqwAV==_ii@rA1asp@f~u6 z@h|>g>m$q5yVj(htGKH(45 zcj!0vC3FAkYy;-acs`AFg`@7=(Q_y;Dlhx9QzfIA6zdHb19%I{shvzj5<yCv-WEt!S5X zzKwQ)o`<7d&iT1huKWzg71D>W){`)f)yNlV4kz z({oyEDLy}ndc?j{_Qmo?^`jQH{9wg^6$AfQW5AmK z)4sq*IfrzPVb)rJ&N9(CfsbV^V0-8(W(}_c4@#|b+$m5;#I(od^vlrUqQxs=)?1$@`qQ;h;?9Fl>}iswkDlHvR7@7Ljp_|kMmJ2=Rx~M)SmZhJ z)bXW%d6EBY3DMf;u;WAX=d#?v#Rgq9+vV&AY32^Gam=4RR;j6|ULd0g$$QV?`BP7E zP@FJoy-5_^pzBc4Vfzqc!uwRw!5yN+@XOQfeizb3znvE;l4m^^TfBF=XpuckwD6v0 zzWpv`w3H)IMxkSG9kF>Eid^A2pupf84)l$b2VMbt94JT1gPM01J5Y|42MxA%b)Xz6 z52`FrF|nxva+xxgF;-y)l-YZU^5cpW^twLNVdBq9VMkz1xv}P;=4a zWLn5R^?~DM=s=M_=W4Tk;pEXrcSMSGp@(BTN2ZG|Bk!o`IwphB?_}EO56z#;atB{b z)d}Xddu%Ri`iG5U{%qa{QDWGcgF7qur;qj-G+ZpNTUov{CQY60**EHW7oBnttH2k`i@2`o+n)O=_ zfy;|B+uC`bHV>5V2}geEVLMkV1DrqE6iz%@WV;kt4Dzn82ouZiwtd#T9;}^^7sl7S zYU8%>a!$|raQ<8_*N5xL_2+hRd$}LDf4JYcKe?Z||9KrH6fejx02&0soU^BFQ`%&P z+uIw%=H|<6brx?mzYpjS1N+yp#n=;>Y2HLY$CSOkcc%5*!py*+}nt_9+J&dWJH=fnAPxm+KvC)c0b#qH&O;Qrx$)!EZ1(J*KRhs zrUSjE^OI{m&}%)}-iL!;1NzCeA?UTCpIkG7UNhR{S`YMEGG1(a2>x7_9HT*x(Kb1D zgC4tWd`wIz{p=E9P`ve2WATBMevOYu!Ob5%?JaYp_j_?=7_>`S-wX{-<2Ne0J0yR0 z!E7<^z3rX77W6Q^;mW>Cw&_uM;ZSfrs5yR(E%WiCX4xLSphWV{HojN;q4{%J3Ba@u zuIV|(edG`Jy@{~TcND<=5dD1$+BetxA7X!>*M-|y$DY90(=jP9CUvX|j8z@O2F9?CZ3AOl z$9yctypB~9+X9b`55b?y%GPTz?5sV{?0PhX-{%p7prW_K+!LGJkB^B7rPuv{kohi~ z?z@D{ciD8GX2^V(v#&E`zRTGM#>#w`pY9t?neXz`eHzGom$R<}neTG;fgg;&?%PS0 zJ6MlvLgu?19P?+l>}m`?O)^8x@H@6r>$*eg;}^_F)8E@}wF`r#d8U|)uch>x);AKa zF8(F9Qj>Ik%U47})mg3W8{ek$JN`TzUgT?Q^uC+|Qj@ZLWEU4)3uJ8k8&LbHwVmZ4%^kdK4g z!pk{5=fnAPxm+KvC)c0b#qH&O;Qrx$^jq8fdd?|i z9?Urx6*3RzoTCbv2eaw9tB`pxn{Ho*%!B!H9XFjhvu)> zM@0`yr#f;~cf4HZe}v4fIrBn7=GGiKUnFF1&7t#1Lgv<1>im+B zxiw#%cM>wU=A0V~nOnnrEas6&pAW%b&%;TUo}UYuTeInTyO6oHc;n{(f*$jP$lsy! zhiIci=M~ZRl{(*uKJnFgNc5F6KZ!oH>AWKP7JY*GYV-;E>VxvykMvY!|+m>yo)GY!~@4 zhllcHyI3i6Q-;i~VY_gkZ=^hI7Y>wz?NGK02g$DL@s?}Ou!b3X{jDd#>Bj$aPFe}vXMnOj?~ z^K6KH`1qJmdO6nPejLt2qV+x<&QF~CcQ|ix?(5-v#-aE7aGvAP`+zwAS)upua9-pq z=QFtfi}PWe=X_B9T$Vdn&SP=k9Ow2pr;Wq>SvkKo^}N?6=eMzXK8*8ZyPhYnkn>wZ z&!1Py`K_Vn)ebqo6?(qykn>xi=iv@HzZH6Z?vV3aq37)mIlmQpJ|8XTw?fbJqviZo z==p!NoZkw)E{K-%TcOtr(Ql>GpmyTEm5v_6l4>(gj`P6OAi z&OIqyZ^nz655Zrqo$;&)$uwuZ90V@Wq7_ef%iUBJItQc@N26T>>zSAN1mxVq<5-s&&m(YpUX-B#`9n+H9g0qbI-ul#_T}@ zh3Do-8AcJb+u!ov9Ggk#5#%|)^@X+_yL z4;(4K?Ik94J7U}oNgTbn`cN@$Pq;DiVXEk?zEL7Y@~`ZzzD?)Ev4}N|i8T6I6Q9*Q z0eNa!K(dq$fI4X10Cm$k1M1BEz{@$kwuSh_xgWTH;`xpF zllz(b|DV(mudn}4tYZ?-E;?fs&onw?7|%L7bZp}pNQaJjJR2FU+X9}Mbha-%OBv1e z`4Ieddm&l6jpG@TXx;YlY>Bgt)4ozd>1DrT-R=Al-^=a1zZCC3!Z8HjgTULnzAK5| zi6E2Ead%1SyOQv|1I|0i@eHclcb?Nl(yuwuZ90V@Wq7_ef% ziUBJItQfFjz={DY2L3O`fW9M{?q1e+Qxn$jcOd*%-qkGM??CUu(RVn1u)DQWd|m5r zy<2-n{T28woDY7tw!Z6{>V@O~)_Qc_S&qKdcZ>_fAL@>D`F@ALr5>GklS^CZj&^Jh zh;_RotlJ%7c_;e6^iHV%*7vIXUGL*ycg#EA8%FiQ?(?_mE`jg!`ghcw$^laznD#Bz z|J5F*g)KjPoG~y`px(}XTg1+NTg38*_H7Y3_iYjDeN}o^@3#`x`>+Pm=>1v3I6v;* zy#l>c+_`UyG|qin#Lj(N#Lj(N#9FSi&7nSowVs5XXCaUt--#{dIm=Bc&q;6M-9tzt zfAEeY!url4!url4!uoT<_#EDOgbyM=DUUG9k?+R-l9iLanx3%cBalY(C#>ZXmLH)$ zgi#Lq1?f=^`U|o2AKLXNjGsBnt$M5u=#Bs6dPM!ykJV>>41Q>lqq6L`RJ(HrYn!N@ z^1hV!pSrCRO+xAUvkAqz@1=f8W9r8=A8I?CX9DQ?vuAshq)%~;67W_*%q4ZM!xMvfJrT^o`8jb%nrf{AKpcfc-`dPQJ_6gDRaSG3Z zIok;5=?=Y$fBe_#50x)0KYaXt`1|J7vhCT>U%IcR{v79z*gmmbwnuEQfY_Q>|9M`` z`!4j6vmfLAJYQe%aY_=$tw;FS#Qn_u&+CQP7s~t}^+^4^rg!%FSdY~AYW{?^T*6u( z!dg$ld|klpk;0E>v=Wtwcl~4Pkly$i!cKR+Vib zjI{U+mLm`3g&2A3vwlt)c-D`~@r;v`9?v)-Mm~7P2{H1QzXCDJl%EkseWVP+DARdn zO3S2jd0s4rmD?G;!T7|Tr9zoZuH+G?51uh|>WOF1ocarWMhv8WbS4e;M48MF$j8KT zl!-PVMw^uH$S%|edC1=_2J^pxzQb~-OvLj1kwek`_tu>}v+4Jt>rS83MF0M+b?00M z;KTvfT=*CBUbwbGjQKF<8czNfaBYR<*vH`73Nelk@(*F0JLB34%W>|E>kGs#8f6f zLyWX212OVYGDZUOMj2R+5?OgPqmM>iHJ=#9KZePTVfw@{J!6>uF<0MC%AokH#d4>; zNbmFm@`)jRq%WD@P%f2I*+2Xo!~7pD^(PwS?W*orKZ9c*)hYJhY>dFMkIJ$CW@Cix zJL1L&U}HpFe~tY&`q9~6^D&W)5y;0mM$kBi^f*4SF#`3GbTmfb*hd(7urY$hTW3tN zavb}d^zp_T#vjMNxUq@pBbc7?`pMH?nZML_VR_t`$owFfe{k$Gv|Tv%$Yl~q-z$V=oS6}M_YmGO z&0*p%_7PZypCLwC^-NpYXFN8M7nURMY3UC~>pn&Hw;Sxva!GF>MtaGIF!D*ccqw5I z{{v>-RXYeD^;&0k8he_sS!SkrGx`?cB>wHp-pig5_P>|IOlEsac+!%2vC%i{E$hL>Y3$~Hh_ zf`vaCKL}MfQ(Q`lf8Rb2QhRyx-+MVWp0_SCV&LeQ1rRPHQ z{XhL(D|{ZyaehYSdQL_3dagx$^c;-%>$w@_4D{TO^wD!U(o@gz;^t+@U*|mlG3vtT zopV3rgLx04!Fd^zOEU0T^a0b;DFgM#yhjYuIA!2pEN6Zo8BRVZ12N9~^xTi;gUrv) zxgYV+b3f7_pTl3B_aJQ5-N#pV*j}x%PkF)egXM?6J_gkId+6Y4x=Ry1j5#xw*E02Z zi63EpkH%Td`LX;Mj-^zN^8uDm!~CIKzp30_WW;)0d&{4{FR!?H)8&{ComcGqLrMDX zm$d6|%PXqfg{nJ_t$M6Z^E!-8j8Tj>ck{!4Z#_~wpf-aDV@Lh9u;m9U2LAhE;2-Uq z?Gt^FaTfEr%71^~I4jR%e(-Vj-?4uued+f<`eqtaaLi@%3am#e$30S=6TvFL`4W}u z`4VAWMp)06WPU$xAC@rk{vY)iH;>};EBTnfXORz|kMVh${ETQM8ScXpMm>2PI&DOI zS-H%m$I(-67-h+yc>AGDF7p0=?0p4XRok{cprVLHh=C0oK|lc!i#3Nq*{G-(Ad20s z*xlXTScE7B3VTkE-C{R(cenoM7<+Bb^1bW-dYj{kw?yPWxk}#sm@e=!m1rW9o0Tzm6x#m zD1ARd^^@etW2_sT*Ba{#%W0HL{q#DMb}&Xp`{{Kic`>FWS3f5#{Y1*k~qCb)CF1^0AIHMl_obQMEyXw)<&Emhq zAp>W`AtML=vK*i}iXpy+`DF&qh(ksW{8|n;$Th+qxn{B3+1mS9UlZ8SU7i7J2Nmbu z@&vQY72w0jc;9b%o5D-Ktl;D4qWJsv2G2u_*^Gic6|22NVNs8<%Cd@cl#ibVLUy5rQUd!^l6Z?r@$~UomEs>b7r2hvE@K${kS@hk6Vvt$!Kj=?~ZlC?L1yk=~j7I z@7K-Ou~k!8Ynm0Rv8TSN(|SW>p2aMBjhB*YF$_+18>I|(?4}GUF$jA2R^ZzY&sHuJ z?f?ygPV;R;H!FkoyBSnVxg z@_PU$ZIAu~?ms*`-@rmXTeboo1%~`0Nv-biI zPdhj>dn}K%^8=m83l2f!dCwAl;C;6otlrmGSuwCI)Tjiouh14&s!JZ2FvuMSa91el zxsW}4m<5`Hpx7oIvV^uPv^1w-mABCL&n?e(Q#e$p$7ZG-*Q;n`tJfw8?b zsU8R~TY>eZt-JOYBA{-vudWb7*sNex#dQD}{iy7=|dWx0ZWDWsOe4u^hg^FoT zdDgZsA|vOJfW$)pOr{`QT%ljk}5$nzS{w2k-H9qeC1F_rSsfZKF?(KPvAn4u>NnnlPWDzv=rIh=Tad zC)tdLm3h8>ZNNOm8tiV@fHqem*|}VW;H0TJFW?jepBEQ})t@KqM9kV0g!;`~;f*eh z-7k8YeW;L~-;Qnv#XGx0>B|S0*^;6#)3p%1zmtifezRLw*n%929(A@Jw}mYivjFNS zH>_a$q!Fak@7)!)*0#KYI_9B|Sl4^SNvGtYaMrml=&#R?f}x(K(6V1L={IeDnx!1c z#!!EN^!57Zy*p5+>c+F|y7Lp#xiN4TyL2jyblhKtGkq;z1$ADyL^G@Dvq|2oYB2lo zEQ#bL7L8=?iHRh4>t2DCIFW^+e)8D-tXYr?;q3C>&PjRSDqr4FiQyf_@bN3Uh`mWu z*+`3-zJ10t6>smEL)PVUS;YL3!mOGXX!G{d*~z?Xo_?aq*m&O>Yc2F|Rt^*TKo{lo zgT}1*g(wkMw5QT+{S9Vi(N^sDouiy`(!tBV)kOan>lAI?{wTNC6|c*;OzR`s$#xp~ zymIAgPooIGyw;Evt!j{89CJ|7t!pO+Vjr^O7#nvml61=VpTREHZ$WZV&K6Fx8YK5< z`H)>_K_q`*S{YcXj^u~j*0R+FDhli?e(PHZnl*4G9h>XV+57PhB)58(5At$z!p8hJ zjIV~i7u$kQo=2?s%v$jN@L@JSZX>Jcm>*oqRf2ih6y~#a6-#>1720}6y2tO{>yCLl zHQ`QNu7?5fh<~YFXxdl#%2wc)vXJ_aic2lQxpX|?`^~bzwA5YH2B&6kRr=ieLvjDV zw)4UEeW{~vi5pPo>GkTRXN0{b{lv`;N?#jvo$!_jV5^#C=h*J@SJ=rOFB?nkF2}pw ztWTxhgyX}4ShIH@sBI=3JIt6(D9Imm4rX(5r;$9XsfhrYhnsD-ZEu{(L_FLSCZgBP zN(yZ^mPa)0B3`eZ#?G9W?%QHSQ*r01Ib`lRmkpU*QrI`~f~$A3z^%%HpDyYLC0a{- zc^4Npeo#MhAsfG5Cr(!_3nL=NE3e))5Ccu~K&M9oc$MN^#FfMaY`pA0{mR-3XE_$1 z)7OJVk8Q*&ITja_?P8zwCw2M4a&68{=HW8W-;a*>JsV@8e=YO8yuXXm{eELsLFV~j z`<}|2bvIZInde{SSl?6TdA)wsgy++BO7ypH{H3(>-s57qU2S{t=sg3(jNV6lP4ts} zLlTFHfld{btp|p)aenm}lrq!*)PRsd9{mjlV`6Gx)$JXPyY@FZ2@{emR zWPSv%qg_%z5>la_nOV*e+*|`LmPFr2RXTDvIIS)cX3AyenFhPE6i&to_l) z9DT?eQjQfrZs6_KYM1Z6xdxqG_eZkT0~5)9NXIEki6sX6c{@e3MM1Mko_*YHrG%qD z**tq9KWk#{Lb%7E{&A1$pQC#JGwMR-UiKcYUE>x<9wVE^IzqY3M~-=^_In)jQtkIR z<|XCiuP-l^@ekto zgXC_|Y1~J}pLy`$N&^YEtK?Y8+H)xB930`vR*x7+*S;DR&$h9=n{98oHtf6UE!YKHsPc)ukR_gCw~V> ze7RfE@*djMSai7mjt%cRjBVRmQ*5?+$Obk!!BQ(#6yt85Wy@l7K*yaW#Fx9t%;%~* ztWV7<+MHg@+?&*dgdV5(sjt1*jgVF_chWT8cbAUs_2~r@MqBZ*S=TAC;|7Cw&Vg|o z4iAmRep_31~}Iz4tWiMSF3GU zkEVM4lscWEhUH%Ny74o8+VLtdaii=F)!ueEh_jp!R`sOu>GaCwZA&& z3kR);{am?{8|HjgpMvgYR+}mR|4tvYT(Tb$*dJkAko}XuehS-y?6<^F*?(bMko}qP zlWhRo!o%cl0{c5`3mtN`5T3Fh#I~^Kw`!ua>>sf$)LP;o)_7JI*cN2F=E#TrTfql+oNo!9Qz3DA7uOG*mq#RA=@>_J_XygZ0{WV8f@>fAK=&rVLu@I z2abIc_7Ae(;8=gyZ~WEuxS(wyuf8A)4@nyU-l2LvKlXV_&*ZMKvtKr`>GEjB_e~S1 zS(o$1L1Q@P@Wf{BqTRB5OgE+i)ZCp_6g}+5i*62qNxSsC`REtC>8aZAI-!}V@6|E*Sb7llISv)f7)*79x}k)pUL*tbj`<0qVI4d6SjPpH~uIIXvfi+x05KaqqxXk_yTjyolR_b zSW95LoB61v$h19)V}I5Beg*L&Pd-s{Z4%qykyqSr*Nw&pG;=~MT(1iy%d3cLaBNU1wWNll<(=!TGVqDlc$##s9&mHSphHQcRI+vOPhys zEEPDW;&>{@Qh{SCj;C@g6*#8icq+$IfnzF;r*bS6IHuxwD#ucRV=9iPax4`%rs8-i z$5Me~DvqaeEEPDW{@3wT>%%{4gE+@9wn3a@U>n3a1kN$A4dUDa=NNLXL2VGRoP!9Q zi=d92n+Tkv;I(qjB5<5Tn>ZggoHLjnZ8~^6EB37$^vMzzee7-syV-sqR6DpYx>9&! zrOcXP&@lF5bQYU)`Y-c`LZJ8k=%=Gb)4X_8<`>b2Ae9$R>j(qyyo&DM)lw8rYz*f6 zo=59yy9zyHaAn)Q=eJ!unAFZES z|Fz}PmRHLwV<7Oe0e54fWefyfvu^v;Xc+^6wz_0*5iMgNkYh-tywP%PAdq|ipgF5$ z3`>$E;-Mf`*vMDwl?P>w{TSeamF~7E%hNQ=-d=`TCHa`ovooor7Ey6Z7&-zv=kIv?Euj;FEL$B z1qudaf$Uiyvs>+JLzU|L+2W4x*r)1^;m)v8tYopz?0RT3NFM0Pto?Ve28+7Vd^^Vj zQ^?h~IpO8I9KdX3b;5Q1szUiTPK4XVHiek$nF$|g*aa$X5wtE~DFdLaTPwonXAFgJ zFM2CD#^sM20xOoC)FaMm+Yd%O8bkLswfE0Gw{BscH#@-R91(1Fw^;T_iGcIx6Ih?a z%h{W|4WW4Fe7XPOX%haaK;TrEDB>eN)>`whw3n;yAMk`nHg$X zHin~JaM1ro8#y7dF}eb zf|HgkPjq8_Fbsj!Bm7}R@JjCPlM^QQsSnwc<9UY%kJZo)wwe3I>+m z%kzAg!umdH3n6Jo`PjXcSoLikVP8Z7$GV8v9|5|R>p9lNlaLVk^!jq%UfRihtvZ;W zn#Hj$dS~ki^V~*}{_;&8@Gf)=$9lPw+8*8o52kBRWwnRe-#T)vqYa;$flt$JWM_k8 zU+DM&=-Q*EHNpH^bFw+8{cWP8#tsP#b-&>0BG6pm>$b$+qfc(bFd3$N1Qe%){o^C``PYcBip&z2eD!sZu>)%ewt3X#e@8%CNNZB0a`! zX#-yRzfS2PLRJOkmGF?QNiIU8umYEaG)n2>v>cc$W>$%Q{re?TcJZwqIu}-G?j4 z73fs~nhPg}WeL9A2HKULNxWYd7l-6J)(p#%#Um7U+f8KH)>d_%$y!^KRFJF1p!Seu ze=^x$*)>WzHzSV76D~I*O^)B)%%hmZHan)TB4(I1>A^Vp1%EFUVZHc#P-3Bmr z{st=7xC@10YIF_ay<25ETQPSeam_cW2G7EmkbToPVNlEa4)Kn*vSyVlXI8LWrebEVjRDx&ub`kHX^|@I6Dn7)uHS`oST~UhcZ_ZT*DmD8^_QxGB2_7}#$cOkX zRiW<%zVpHCEUIKHvY$x=LQWGq@?oQA zaky}FFWLN@aERRq2qxYY_Elg_^*l7DwCI)--p9m}&Eiqzz&$VQ$~nw4RF z-KnF%wT~spW^DVCP_yeN;`O)A!sd3GK)m(%Z!Gu3E@VGBkK8X4g~)zNrhE`_;wJep z<+Cefv9=}qLk13Jhl&;?`wxa?h6N@E$cM1CMWEljY&5RLt^KBW&=D@HHEat<78`nCrJHbnWKCw^^RH z&&hs^FE^C~UG|XvwGd0F5K@o)Op~MZ&9$q^=6w@$SlBL*eB0#uh3#tLOa9ziT#GH9 z*_doLo%Dds+U-vMY;rrUZ1cZJHrK_SVohZ{v8{PsOk(rKS-??h!^@bFJ1Y{tMp|*R%eM zSgXQr#8tn;cvf51AGYP3Pe!q{Hy$LPd!-T^pLU$MwhV92HdnVNosA=3DVqsw!$9Fl`{u0M8FLi*(<9KFvT&gOW@ zU0vmz>zy+k>1ZbGn&yNVjl6-aw-EU~pRl@*6xek;m#EJ;v)tw{S**oI->Gb1Of4vP z%|^HstIRISeUKG$9|Y%G*Pj-2Pr3Mo?xpmeb6<%JPtmunG6V{*ZpY4CsKCb*>#=M`!bJvcI;N~H7aM^K+hxTAlyieHLDa~6t<2;AiZ+5$OsV3d8 zs1$S0t?M9f!u+0v`@yt=gw^>Z`Jm401dbi*yiQ;psq;Fanb!%-Np)T)u-?^qoxr+K z=XF9eujAM!tMfXpnb&d6yiSkvx^r$7;CVX_@~5W05R7rFL3l!z&rFvTM!3IOB-;{a zPh9-cTh`94DfxVDusz#R?JRMX?ev6oN((0ciDYFWi5%0ISBkcKB zGvab;=M6ayxe=GkaCeyR?nGP#MowY}b0rejx$_RNwYEYm;A+l30G8-&kVMe^sFSjeh^FO8>Tim}gq%u3Q|2pIuD_Z#u$9nY3<_T#x za+3YdEgay{V>7Zj;>ju&ZnlJcI3H#MYkeMb%mLrNjo9m6waJIkwM`+p$_cX5L3csP zYkq>b;)-r!D_>8cYa?RXi>bb6X?@YVS)|zg{y6WKJ%TOk)?9?I-orPaN?@~c28(T{ z5_!+;Pg$R?RYhMpr!7?92HIRKBUT)lz=xc4gC#N-`eceEuHyb#L{1Y=K08Nau-bEx zAHMTVpEas2bdHJUU0kB|J3@QH(dOZN$)Pg(R%@bQ)1#~U&6a&rQe^H`+&ndQK=Klr z+e_cT=-a)94I%GuxhVH6+sU&-h074GGov6px=@qw_S(;wPx)4a3p=c0MOO4AyrhAS zO;|gKaHjp`Vwai^Gs?M9F7>%lU)teDJJP-|+Lye-$SeI3Mt@}7Kod96#0@lY15MmO z6F1PrO^(ayabudeF-_cTT-G{u987}*ruF*4M5139Sye;$e*rX0`2oD`S zA+|?x59;6cydM-RdbT0#c(Yk-+LeifOO^GAZJvDv;pt%?Vp^X{B<%cfWX#1zy9sA9 z$)j6%<_O{QPbRq@UVnnHd%Ik2Cqs`B?pd^nTZILC3AepF)vaLNt%N--65LkLTSnOB z@G-Xm2S*WJZE?@7_60w}ef1yRj%0s9KKnIqAg*pV7nqZqgKLUmGfV~M#i}XO zDfg_eGGR90HRWgd+!clCp^~Iu-mZW+7d?b>@_bznp`5-!dF%bzQ&_evPIiv9J1_G+ zH^=-8wJa)zZ#zOZOFSqkw)y54nDY+H3W~QLeq__Mbqk(!t0Cp>myIX+?QQOK?TQJO zB4Foc;xeu z|BNT=niJR6_Vu~Lpg7WhS4{Bt$NLz#M!n$&=cf^u>wHr&w7Vm54PAVfm)O^UxB^Z* z;ENjB3T&Gfr(WdW&IOSD@oQG`+?l(O{fgHZ-!t$v*}vkrj$iFHpX}!@ag3L8H1vV} z-W}xGpu>ymvRU)R_* z(1Yync==I(SgAzz-#;zRP7F2p95ShRZ1Xj(iL1_xi+bOS0c2md$(A?nd5-Kyx?a&c zv~wW)%1`ab!!f@3DJD%%`_E$$rbT=adN}4gPO_GKPH%3n2f^yWe0v zN`;X994mUV$uA7?FW4?0G)V{``yFD>Fk9y!ijU2h;xP}_wI=(!i_cQh-WvR`|Ft2@ z_RSFgR(mF!Olw}58>-elkDnYD6e zy}|!eWvtk_?B@;f8MKJq3bCg6gdY0BT90!g`}fwC28;KOWPi)E+bl~(JF=hpwJzK^ zZAtcR_Bq0=74~HR=9lS8+Ac%WhxWpHUi>3ZnS5llu^P#%&?{Zyr5o z<)+=D_Pb$-JDiVvNc~b8YX$>v9HcS#(C|Xgp~q?JA3EHw1FJ{s$!6XN3-&I^n{00U zwwgV=u!wA4scQlAM(iM)`#j{bC)Y-@S!0GP#5`O=cAoBcWDQr@)3v2+QrOLWL+RSE zv3Ag6@QrSmXxA6&6V|vNXF2yPq_f`lEUOS@Pk86uI&A-FJ?R9$3SqqZBEqEx zG-Z3I3?p3aXh$(J`3TJ`hP9Pv;=B*=5vk4C>Gom5HK*Va&tllNFZIR9sfoN)lY4Av zcy*D*E}9Pv%ME8wc#3g0v$@YoXK1#fu$Yx;1TRw*pi_yg;>+Ps-eGzJ81H+PCv|t{ zfxBBnm&@yT%}l2J-l*=d;$|ezR(ZXCX}mmp8+At?SyrcC(z>*ESbj1sHawyim22dTTd}taY$ANI$>rF$<(?3} zYq~FXM&rDspVNGKY(t;2ghMwq7lS@OrFwaEx}osxc9-hKXIYR~pj@JQ=^b22xW*l( zdYM|*MNH0}MD;RoXqr<>!<_mXxb1Koib<12Gx#Ad`F*uh8$j^-uDs}}WBjaW4X=-R^VHdkdE$ufaK`18 z{@I)cyldP5DF3Fn-a6p4K0@{_$BJdqxokZu_a}#opTWlcI}?-T>HC}iKm7Z?r}N~W z!O}iHe<=4&m*ZaHKgGZAAueD2Gr0ZqiL$K46^L_UO`hAe=nZ-t|~k+D=C`3pPKS$mjkTX;YZjvrzw243?po@d@Bp6*PU?V#z8DR z(;&jn`hD|tJU5JRY^Vj_6+MKo(rq4}KB5odSr&Ksw)JfYw{guUT284;xSD%;k#N9^ z@Cla&VuHOj;kd~5BJ|27j{ZFM?dNHnkJeo$8StXMH(wPVpvODl%BOuCOIsc|lvz zIq)X=_Qt6S#N>A&`J!M3;V!O(e*<%P_M|D{O{@E}uoeUUn|#j45&G*r4Zi(IXVq^z z_?J=L=-QvrcRo-|*p~_<{Xcqbt?7+~k}oG+`>(R|M}7Di{U7OQ3|pwgYPv3p^#BcHwEbrKD^x-I7>t}E4pbcQrq#Ma*KO?YPH40ft>U&7&c zd+~s^hFl5^_ffKJHQ33J|7+tAx~xCsTR4JYzhol!PYY)~PIy7dCXj7yc0l>gB@FtX zE=4#ZxHx1@4j?RZhRNI`+^WzZXdE6u*A~b*5c=tx5pH#B0QAk$ov>Cvc83GR3qQJc z&5mj?sF)Ms*S0O-K!O?J{<*uuo2T38+Dp1f$ouXQ;Tj(+z^I2Fq>~~4*Tw<1oZ(+n z%ZjXTY{Y`c%lNi(S;ba|nj&OML*D)NW?tiMMp^mCk^>nE)k zBHDkRpbV|^LP5OfjUDTHa||0R$F}kIt`dHe$^Bk?eW501+egkIz5G z_>FR6`wJT}r))0RRj`0KbH_#$e&+zCN0^E-k8DKISKhEDEtNlhZX-6zXAKj2G~qsX zZA86o!O+O8pnjmVKjL0p=(G2(a_pUraL*P5Hv)UII?rsxrcz~Lti^fuMC!kKXAKj& z+d}zoHsTF?%|7oL!zP_-EM|{0fpG;Jvu~#xi#|JYfnp|D;w43VZEOzPQmj~kON~X; zayw|AC7K1ES42f8bGFgz3t#uPx%jelkJ4bHiD>bvxi~kigVMyyOe}rgTvQ2~sQ7&? zD4J)gB~}mhNM7>VUhFrkC03p9t^ZucUIb^YC91uAz(Os?@nTU;e`*f@GxPimou6M5 z{U^i<=OEa><9P8i`1iHOa`}vzaozD_T)k;g`MqRGxGobvgMVLV{oK0mXKZS9er0W# zaqX|KuQOu!Zy!V1){8}BdzW>cfivQekpq8G4*Vy~Pcq7wF<<>x<-qUr+n>9aj`vjX zew;d&{-^l&xvq(3kK_M~)%*NEx99Rd_h-25vyIPo{TTmI`#;jhn90us#_eY?>i&^6 z%a8Q=$M)iL=mn~;U%_ZYUQhS6eg>ni)T1@mui#z%H!HE94flk91)~jly&mKLGZ=NH z9+mf3@XyrsU!;?M{}b~F^HR;dzZCx{5C5qAkNS+|!#MtIzw{%0%`=typTY83VEq0I zJa41_8LZhuNBhR->wk!U#->*1Pt2u1lqVVMpp5lkMh;};Kt>K^@#Ej#LJO<=u0?+hVj)1oWN^Cwd`4S+?>uSS=cx?Eq!XBfOVbS}E@ z`E|W8CyJ?qDw_8b69YVC-AJnj%%(Wo={l~@(cJuKjCiBOoiYkc&lJf$Em z6kx!HM$vC420-IQ#o=ge+vxl^!(e2~Z_M0l>FU%$-9h(c3wz-9Y32WB-~LtiLo#?X z?!{%~Kt>K^pt z{ojD4|Nrp2vVSDMZCzaSP4Wl)ewa2kHsV^7V8RoIe&$JY!U&&#w2`-t=uY@tPKB>r zG>~xSxOFKp?}ri|+0TaE2pvq=;`1UFd%PFn{%;?!kBeIq-nl0~bSzh!aK9E63zPwK8dZ1JrA2AdYgSd~#73Fo2L+-(3|`y=_KU{knu-0+=>T79iN#94uEIb6xkkK|e% z?K8i=MSkNsvv&~~!$11`ulBj-i48i6q`Sv(&qW!3zJoZDCzY^o^A2K1#Z!dq<;^52 z?ruh0Jr|Y`FZ=lsp3|0z%rS=Ni(^hV601LDCwakA`9zDhbqJd^2oxsyiW2^rdjeXW zAMGpsQTc#dR=|TB(4L*6X=x~wRGDy@4FOQJZE?aCTQ!HpS2GcQmC_m7bw5D+t#7M$ zhV5$)5xyUj3l5JAA)V>VUBU5=LimNHKU@iOApEv{Gq^S&3*lBmJ_mlVA>n%`^T6Po z2Hc{XKU}?Ag5<5=3=@vkrzhiHTlU}~V#-}>;+k8auZWm9i*V)P?M1i9ON7l++ls** zZV+D5s-1XheT{JZi+19E@)g1z9t;zE5|*c+%{xPfh{)YJN&Ypdk7#c`m$2QlVPbxr zZlq)TYM97h!JhEp+fic6f-urKJ|u}B-rbG-bh6sU4_53>xaO)vUUs7aSMlD&vpe)4 zd9`&Ld2(k1K4u@!4<#D#&8e}x>?Z@By(Nx!-EY9=m*RPy83ye0Z6iO^+<>QU*vbRz z80>F6yO}RPYrr!00_y+7oCOZH}t%DW=b>KzLnHZLy?6LBfUXTZ^D)&p7J%`1TT)TSpT%^BXK~hq@DP za%Zq``B0c}rA>o{b3q5fy$1~zHkF(S%NPiZ1==aIyo|`|U5Rk@)LLThc>`D70jLcE5mbz zljiLUFs@_d+>$V^d*s}b zu$)^m;~GKEEt#BKl3dO$nVee^mUBy{S!*!OT7wza8gg#Q?W2^UzKw3MhJh^WT2>8VoQo;*T(wXvxkZEe!EiaKAu(dV}^={ zF$Yo>M2%*v%Jvs$oDZiw^Gs#8j&vlscUwz%y|OXs=d11tGdvmDIr|_0c3BlC`#+lN z_Dt}A;8OC<0v$G`96FE(%q$y<-OG8(o1ja~VQ_oV`}zKqY>`vg!?%4!WU<33p^>kY ztM)_1Wc!0D(`-xWgXDKORC%^5W$vmve0kD9apdrplpM)h`GJ7$!uRW{6d8wqdiL^1 zI$ED)oB-p6v668Dj2FgA#tAT97%Lekz<6P-WSjuwg|U)x0*n{RWt;%xh59m1fbl{* zGERW;Li;~z3*8PChkhXefaS983h?=c3t)MN%5wpsxh(+Wa3G*FJneXhVSKhW9{^t2 z`!kH2x#ckMJ+NNEc&>FG2JP-F)nlB`Bn|*)eNT?@*Oph_>!9y7%H}pd=jLfWz_0K| z{xo~g>K26tQ(J#*vQM7#9}ZSSTFYl=^F*t1)~jg6XjPv*S=s`>^9SufgHBP=_)f>< zDUNU^cw998#s9xPF-7iI7|&WvkCr?PuSdD;QyAHm`p0YKn1p<2$I#ad2DFcUp+53T zJNOP4$(IN13$%}Z%D)2n(0}7SoGOjZOp(_K!sohs+j zzE0KWk{7@CNg$u}N2l5svRpcqS4jVLsy|Y1x=!_z2T(7 zwIAWh!Ldq{!b6Q%Z^TlE8+GKh+<2|DDU3EHmoRckAB52d?e|)1zsp)H*M66^R!7Ry zzsvf+=%jy_wN^*_UDn#~yVlBo<{j(WcUx<}OaEuSLtgv6_wt@RGv1R|G2ngmW@+Y- zqgN>5xW+E9D1i~a{y6}8j3`Pt?R_{boc4~P{*^^NphTYagoE1-0=p5egynaBL(wlW zF{q=;DF;-2!m1s@s(pd_DlcKxAHu5t+~&JfKM$mk-JQcu6|rKsLPy0{(Qgb z+Ic#_PQ_oOu#>tHo4>GvVd3Ivsmr?Oz2ex_D?P-rX=ysJ_F%8d3>FO=Ue=x5+7rKj zRLq%r66GA_Hz)mu`W*Fx_r;(cj&>ehpN{qg+8^H}5_tvkt|?gr{SoNTi_ezz5jIo<@r)3hury9NIZDx46yBQn}n;h+0&KaUURe`GY z!lL(14S@A?i^GCm_R+(Ow}iOQA6dg<8&)^-=?SqzW7z3x)mNGY z_D)KSd+*FTRnA>3f^@1rUv+n+PPN1Nhb21IzF>W}=u}>j6u(cW`XeqopVX;-3fC#; z{t^Du{h$5H)%nl#UprU4Am5K3JkC+zT1ox|`G3OdJeF_|yN#^=Si|?T-8tmR##Rtab1?ThVLJfa&DAMeQwm(u3wPHXdnL?d8I$NzN38sybiBNf6yM} z8DdqRuxf{}YM<6$DlcKxAHu4igjN3y@^{78Nm^6zKQppmMrJqD3ae_*h(2Q(@>A)s^8Ez=wNu3b9=2xd|n;H_xnALy2PIh zH0;Gxy=W!QG%@T+;^f?XgwtBJ5#dhv$p02K`-l&z^9jEnKSVrP zo`bOC)nVd7!VO>ad9lwR;Sl7<5MSEbUF;o}NchjH)AIL@IRBk>+T1c>EtUmy$C$&I zJO8XsWgI}p!5Ax$v7$K0c!G>4VHtCfF$c6S>xIdBAuQ`ok#$E{)-RX!OIYTBkU2nD z=82GbLRcGTZCz;VOIxSfde`QLHh;7^rp-fbJ!;#m+Qz9|*v7M+{Ti#rExqll`Vx0_=kPlj)wPo>rzUXi5pKUBU{Vn}-sLS8mKPM(l`Q`rkNA>$Na@kHn z_J@@7+WtYdS&;oFov)DnYI*aVsa&12&+dh}$3(2*8j_e179FIt@?SHgo(fY5IYyJO`jlwYx_9glv+rgkj*6`R^|@KObVt-t zCyHlUg?y@<8|CPiQ6K#^+L88!(Z2jEjJ)!5fqZC3UMG+bv9u?U53%GC>u(=*(#W|+ zpRj6&uxekRj>=0|^@p(PCt-{q@}Yi*#@*H;A7ZtPUe@mTu@9F-h*J;H9gTUR>kLoD6^AH#~JqN@3 zDjC=YLM-nQF4xWrdbTbPC=ZK}?-Op>p73So8_G0!-W%nakF@0HfC2+Q|SfP4=H%@5^!C_ui4g0OrK z1<3bM5SH(u0QnvYBgS`95Ds70Mm)-OmvGbjbwrwFewx>Ht>`Hd;wupL=$>1+e>0p( zK9J=!KVR0chdwF)2wpv*Kj~N>jnmJvFw7w(R*YEcFr$vVmKm>=Ho<69a)FUc`T#~B zq;FvKO?}q}`Ki8ZgRuIp4Z_Nbb|Ta=jc}FX!J^X_Tk@@3&$7a2oDbpNovp;NRff6o z8QnQvc}NG6-?JOVeYzUTVl^Q_pVQ1x7Ks%jmO9L+Bd=w~Yo$#v+LT;i$1l?4&8U<|Un<(U&^RX!G9o zKX$G30gQfX?OgkVc4QerQ}%yobKuXF>z~@``2#yY<;hfJ_DAPQ7q+ z!+Y3`N_g;|RW~YLmF2!o@-n{XXftN>wF?|6a*|)`9Ls8WG=(nx-|~U8?y(-;Rlv*4 zLJaJY6I#x3fRD-6A}mJ<@b$?8+wT<+-tWEOWa<6P+`ov(<;K7%Y80DpR!n$Ys0PXX zJ(>2o9$%BO>!Rm(k>8y?9BNLT087%Thha&%C-(ZehDS z5iYU5quYnn8HD%buj+PiWGvx{mO0%bU@zg%X^UOIoIg+4Eb^>NV~@Lpv!0$FU(2B zzBiW2*t$1B!R0S04lPSmf+_QyNMF7;7UX+lsq6_CJ)l9+>lB|0nahG-#bRWqY5R{X zPp^8ElMBWd1%LO$Wb?>PXP90xA7E_zdlrH!FRGEv_WJGYX4cmV=JU?}E!e984JcM) z-dTcwt4+kU!n6>~Ty6r1uiY(e1>#I-9bi4{H} z&yh&3{88&!;ONuD)wz~@|7op8#O1r#i&fa)m$)|Hc4mGq`55Nj#EUCfyZL#DD|+D+ z7N6ChxEddHWjR`PAuds<7h7UCkGLEM4r3z4lek)j%kyKS9ut>i?h@?Gw{YUJW9@xM z?296<-8*u!Z8trLYms9Fvwv=QuYI+|ysX^UI>c41eYkJ=iam&Hb3uiryjVwE`s`WR z!c!HAYkhEeR>|rcadkZIP+mE;gwz;Y_IP6bc!EYWb`Lj7txhkYq z^}W)hK5?~gk%#NYbS17?FU(j+uWiKj=xk}NQ26N)- z@&2ZMQ&J`3DtGT=-}5G}{9f7gQFakze^;jk-1)jS*?&~+Gw*6& zlI-``{9L~+Qxe%6A>aEtliQKar7s5ZA?!KjK-`_l`Yhd>ke%Uc4)DHJGn1Y66Ta~1 zZl_>7PXWM|mrllpV_gUC+h$6NWn`v*zx<=>HC z9J`RNoff^9uOG9MdbZw9RlexL?7?RsK*YtKiQK!_C{&`)*}z$S0-Z{A-$x z2oS+y?z~d^Wyftq!rpq~-0LKz${rix8CpYBSR27Q9JUcFgA}nww~3iuu@NHzxu{_b>UpTiHZEbZ-L_~yV-Tq)B*nA@lFZkgB(pSBl9_ z_`tUN9Dnh8gKR5d)WvI1jyBL1VzeDNKT2ohlXAr_GmRalvClNT(nh*Jpz#wl{)6|4&rWK&P;M+Q z>Ko&Lb_gSpD^mn5Am1mXyS&v zBu5!?ppN_j^%^V}oef8!!S-;Yj!Da+vAEV0_?c{j)XyM(Jz_n{y$W^LW#uaf!@x&6 zlRR?>w=C-BG~&`I!UqGwoa8TIDRYva5th16@)~*8e7KM{oTM$n(zX+Fpj`5!T%Ow= zE>KP!sy=d%Z_*BOAV&N6iPB#{L=& z?;4FiYczhY(fGgS`j-j040d8sZY(eA8{>d>){s9kmYTRBFUd*vdz{y3;vX&jCmpo? zqq@`dGdT89onrs386$A)BRTfpnlVE5+3911(2Nl{_N9+;7)N7&tr;Uw-#A8~9pe~5 z;~eVa_@Egh&>yLXV>XR_gwcj(jG*xcb&yjd$Fa|-|J_)lv5#XP`Cuq(x<8=t^Sd$b zbWy9dYPr4}6E$%FO?+_dV`{l@?316Rk9~wuR}+66`$&$ll*Lh>zrd0iu$N~}nInG; zTja;eV{qrS9580}mvNxJ%*%6%qeiZ1^qIyE)7WPkUZ(L!_M_>3vQIfH z8~myBl#RP`i^_F<_6L?PM*+gSg1#Z9I3Sifgi%Lc%c(5#T1^a@CbmoybIFrl7jo=K zuOrzfr`O#-%m+*i`SaiM1ckQ6Uy=`I;KT}NIZW76S;DmPBbg_Yd{Xea?{p?de4?@} zE%p9~`YnpOP#j!}ef#0H<}r0-*}|Y`kB3alrMp0SBADY6nyxMC$bvH;SVqlp3*YaxQiiV48Fw^L0ujLx~ch_os(CU15t)?tmF0Q>+6BDlS znQO1r#P)~RYI5L**J^TuYk9TTYPq!fS{Yp?4|AjdGKKH|UC)OFxbv1KE zj&0gdm%lbw$G+Q`6Uc%1ub!(rtvR_yGl&1TnXAiK;vCsnFEWybT*Enoro32>)E03) zBS(_j)$&pi=SK55j=Ap5S zSYC}B>yhl>T1I2%yS0yo7j=#Pe7A-&tbYt^t^;H5$T>g$(3;DbpWm&~N8&Vhp?RQ<9r^}dsc*TJ*3Y0X`P|2x#VYbzmaq_YcBPk z8Lhbh*F)-B18{w#uDJl$J@S5Iw91EaTo;jCUCWR@a-baTsB0gxuda#cUY)w;B7f91 z6#1#Ht?jM$*CckcO8yRDX-ftv%M&142t2=D3Ki8N2On;Z5lM&C1 z9QZy53}f-(L#OGxO7JtB4{GLMf7%*h=#T`w=OusszWe!G60iK_YlO%>UVr=je8c@i zL)~d{Mm_q`ybkB;+Bv*Ty7c*;X6^IczRcfSkJJuu9;*Hr>eBF^44e^%j2!rP$^p3+ z5%~M>dgdYHyvpzUo9Y^w*5&FNSr}yL`;tOk%V(T5`h6c6*Z#DJi|cz$+~~drwjI15 zpx)DvZRzLE8p*jP&0ld}PP1qC-9D*i&rZ&J)A#J?`$+L#AnuXMzKHH=s&g&6FNxP_ z_7=HjZ;@;E77-iw7E#Bzw}{u0Z@kV^ydR1876I?S%DqCeukP~_R`+=cW0~ZhBVl!) zm$16eOIZ4bdz3~w?ok@`<=?A>r5$;%^*LeOIhiYPuzHy8L`lj7i)zsa0cCe~o(qKZB`E z|0#P1c0pIU_vLm}=BP&(2{%n#pg;WV1mT%s`FQ+FLD()RjK3PWo^XQiRF1!REz0mS z#HfqcAVwQ#3o+X6ZTET=V&s%^#VD8h%&0Hz5Jo%FK4G*ke+eU}{ERSiN)E!vDLDuu zr{o|!pnSPC8o8p;XBs<9W1newnZ_Tc@snx%XGPj?a#G8Ma$|W>pR46UJA{!_6F1}~ zIdWo|4R*qqCjLxQFN(3gWGo#oR<#!O?HhmyDXx2I>m^>^FAt--`{^pqt|4NM6$a5P zTqk+OvmGYT+pbSK#`X~Ps42;tCKiw}tVeie*gP3qAdEb(M!FDA@XaOg7ww=7KSPYV zcnxB-fwmB%ZOOM9G4e|}Gs>ktVbsSuLOI%z_5m^4m%oIOQ+`GmIpsBkkyCOIMo!5= zctH8BvaZwRGKT5;GPdbH<50%JXF_zi`xPX}yu#O>iN3tv8!^k?^A=e;I$5uMW;l@&!-7aGQ$LNS@p? zoA@y9B1b!)W)>E$M%s|vWNBVeXc@_DPQRr5%QHv?Ki?Ir<}cNsheIf0CpB(oaBr^i!4>&_0$|mW$+AE*TS&V@zZm zNRDyP$d%Fkf#i>`HeI8!!!-I#!^<@GnZ{41@rP;31seZB69>?g7m~AXa8lz2n)skT zSL23qV?04qFKEXYf6&w;)6^Ge>K*+QYTTG6Pq17hmvLj7Tv9aogL7K>^DELiVs4w+wl|WW4#{Xy3WBT(f#{9v*gmF!-$v50Lq1?k9`B&8A-%(%4Vfdl_N@IEd z(sqY@e|5W43nl;jeeDi8!$)-yd7tg!h>iEd5u*%0Lwxv9Lwa`Rzv6;3gGnA_Z?igg z=0L(FuT5Y5xnp_4a^G{cqLd&!wnVmQ{KfGUW%wCl)WvHMqYbo$*kBtOhYRGFaz~?F z>JvtNX@@Y{k@j_{gZAYwVdRvb5k^jV4PoSz9E6cmau7yFjoeYA@2IiksIjlp@ai=F z=rn%nH2&*S4!h)3%Y|}dc~PG*a%$p(_M_Eu>9A~wkrT^ouyY#yB#fMzdU5=j`W^GA z1LeS;K*#T%{mJ!a7v(^S{NwcxA)Iv1A6$XY$ZF>4sxQesDr+1@9m?nXa{}AGNTU0Kt0zd@GKsd8FerQm=maj|3|ECCn&?u zq#dTQlm4uhw4)g9NPkF2^@pBa!dOaw80r{e`IvOna*+<+Uzg<~9W0lO4hEN!T89}NJovcypNwAXVSq~N)FOd>x*XFqYC+(oyT3bkuq$9gL-n9qFj~ zLpm5s89UNZV@Wz{{746}EC=Zz*4X*(SuKqnMdOe0oFUdNld&`U!!+f>y$NHvn5JAz z6CdL_M%v4eu_HSeOHG_{@52~p(8O8lrq`F`Nq=@vmNmV;n5N$8OeEF?p2O7CJJaM3 zo%KW=JUgk$9~$eh-es=P_^;+6T(Di@q~;;oG3K-JoTt%_F`v;N(!p42+6DT9wlNQ} zT%?1s)U+=w7wKRuHSHAR!_gl+6NLqsy-kP(MJCkK9S zTmO!0H}&}@>VI*)r8$$S?%z@#{nB$W|BAKSf5N)^-@EQG@BYet$qf6{vgx0UI2&T| z|Jb_@xToRfQBPg}A0S19c-em*Tdm!(9c{006%jL404t_oLvZWaibmAvo@GmrFA6oU=?YH7uF*^F4m3HW-dM3aep!{jyrrpK& zw{*^}f$dZl?Q1DGQ9rR}DAGjN*L6r)eMX&SNE2P(#qS4MUsv3QG*m9_D`+ex4V6p# z3VO|y^^v}ssdIFFg$|l&`=8|6`U+b#(}z?p?JInunXwQ$f3UCct!BnCy1pVtnwbMs zF6}E~Z839(%B6jyqo*{K56yF9jO&mO#@I(})C9yvtw3zl5X7oR$^9KwqhuYUwL;Y> zSsSCPGpa_}o`bd;_`gu2T%TNuQ1dAHzQ&wu#boY8X=rVs^Bmev=Qfl^)hJn))I3Vg zrRf|gzR#n|zjzf6^E6nym}@1q)|2n2W3tv0{&O;G4xIzX1k=7T!L%09`a|1Qjgo83 z=;lJIMyVS0zqTJmYfDV(5~ZPiV}fZdQZ?#>>owaxn5t27Pg3NJ+K&=*Fk^pABl~8E zjr}ylYR~-lvw7yci>~8hf>n)@d-Wfg3#l3<-(}eL+f|K{@7-cjqtt$ss!`Fsn^W)g zfA98^hkMcz&yM=JFgn`bV8JSLe*>8dIz*ZD-W!zR;i6 zm>)bV9$jBL7gFcU<>%W~jgt3Y2tUAQXRsEDbNKL?8pLWpO6^C{TA^yx|K>S!wboN> zJ+;=8`)U97c~rO7XEpI(YeRwAM1=XFl3@ z(&-}lv4XpihRULSAB~-?S1vveX{cPph5po zxwNk#O9#JExgY3@G|}}nbf7d;F18!CP+5p+U&ANZZs`1%zJ_l<+SkZ|kM=ck18JyS z+Ly|r^pu9S4_whboaDT1EYLAR#||A+bga=aNXI4}vmobPzhi|Uc1AnqgF&wuW5-s1 zXk9YoB8{OBVna{F##lxS@42A90MAdw16SO4H2Z!kh8hXu9OMe!pl%=*I@@ZvQ8%#N zs2hld4{gr^qi$fkQ8&<6pjXrCXG|a3>WM+G8$PtvA6l0TxkzK^gV@j$v7tX=QJ-|k z72qlAlMXoqn6``hq(jdAnMTwn9dh(z^rAlLFvdRCSJWpR#v9O3S+uXHPdbb}prLYU zUs0cQs24yJU0+e3tWYn2Cc3^*!%P|~m-dBPXv(5;|I}AAb&jqt)MnH6==ws9H+@Lu z(!TJlFk=C=+>}fE!gI!qV|0Dt8D-``bbaBOX66i)OZ!q;l%CSicKALy^KM4C2h+HV z5bs(v?k>bT6^-xB!n+fVyAkn@MB^?+{2p=R?nV55apSH=_t~;pPZzX-$xGjQ^N0X52HyBcVHTK zZUTS!ZgQl7pQc>-cln*`&=2|pAK(Y~HJUQScauAlcKptDgC6dh1iJ)p`JL+qe{478 za>)nvL2T%W80467F}{x++bLFY#Jf}fHF3O@EE)eX&m+twil=FI{JSCVv3-j3V}16d zqzv;a>s39=o78{7e?yOXlIe6(o@V?b%(o&_v+;rlwc? z4kxuU(=#Hr&az`E_Pj&?6rGWYo%rq;;`pXde2!gw$RCIs#1F;-#ha=;(t13XV-|kG z??6LiO>uPe@xjLUoCDP7FrHvsfuCWV!FU4<;}6CmU>KJ$J^{mcg>efQ#xaa%z%agH zoCAh&591#&)PsAXE+7_l0_p`|sNXPd0mnCe#Iu4!{6IH~Xkr2C#T`Y498ZES_B& zJf8rIXO{(@TL!k87@lt?4LtYEzVJLWdBStjltumaCv3C#AJi>A=)gae1OK2;KB!N8 z&ZU3KSE*+FZ1Fya_s%nli=?}{WphIOu5s4?yEoQS@@{&T%f6S+SK(duY~0-y`qkh( zIKK8yxUBoVO@p{|+NAtl)h9Uiql#za<=^i>{I;YsAJ%>X;+vbqJo8u)#32K`c=D00 zaGrUfz8Ckb5sWqYXpN#gV6vA6|7f-vq zJ^H6*V=rD{^MH@~CqC##bLrbL9+pGPWgX64Z%fqryApdQU2p9+)f0X4sr0blDDndP z#spJYF~Pul=e8`cC&DNezI8O^#`Zo*T*?AFlP>oK+rVBM?$)(98$9+Y=H9a(U0A0S zy)Y-6WXQv^^<0IxkC+SPttRIfb}b)h-4DyT(ChTN=9wV}#;8@z5nA?}1rcwrnO$pl zyBOls2Y>TEboQ_LKw}h_IzViVd;&kj1he*Tr@~FY{T+T##)-4*-)cZlF~~CWZJ))H z&+5M)$9TC%Mfl*Lsz@J08fNmDIjlIFyXgVOu6TA=cCSk}jF;=vJZwmr<%s>drDeDK z{*3t0-6z_wJCa~rZdcimNc0m&QaHNOUL(%+1BEBjmo{zI%oEe)}QVo+`BmFL)s<;$yqKc&q&O7_Wdt zUi@)dMMgeX`ee=+0q;Bo#^JsHV^p@@zSWw%(dxZ#GCHfu`K!CAs+g} zaVotZV zt~oXbpA;5_xbf3u{6g{vh*ORKMbBP54THX&+ON=aF35v;(fiJNi(0OThc&%y?R`q_ z+pj9?=N7?mKX7(_igoAM`UjN@ck+4vlMdQHQZ;cck>rAH?sMs(MpVx zx$%0?5N*)8LfE%c3!IgRg^;_r0$xt_ge zV)QM=)St^QC*<36y~bF(wtc5N9Flu?F`5n|_O>G=DQ3y5hfDE_DPp>d@6OXVTWZHm7Xf0z>iU+_7_)SqkLrQp+Q z%lLNOkdrT+E#rGOVPWpMM8?-=kOy~6pBCeL^N|<7oh}mNyHxY!fj)9A@HoJYcP!K# z<5+B~17F%V67i^@^n6v$^N6>Xe5rfvNrd_&?X*`9+m;pa{u`6^hyW+VH+vS>H}oiq zxM9*x)`ViN2Kw(VILMN}w!}#qmDZA`l{D2>Ox125cSM^1s$FrEdl;iHm3uUwMegZl z9*Sqa4l*F7;+e0*a~-gF=3C);Z(xgwVP0U;z0S;{--!Ld`12CrTG8J zKeQ%%abLwotmDY%D*vMyYt;V~f2sVWIZyGI;;-_*qz-k}@F!yG=h%*EY}ACfj4AaG z#a}8vKM)HVFRV+Svqp|fU&ThO1A(sKZ;?OT{9Ka!oYp#getpj8r-X0JGf!A6o3e~W2uQykl8 zv}i0Sj%~SXUgoparI=vh6F8%Ubu6}Z13BiH`lsZA4xf@g>T`4duFuWUyrNje@!u84 zWsllw`;WR}U7~nX=LTAb*KXK8bf1sbB)vTAwLW8MZD>Y$riOr zzDoGK0NdAXh6ZuzHMa=Md8Y>Av5h=gmz6s)j=AkhFu!&M@g4fG@x@uTboVi)kJ7ub z(l=Tm|JdO9YZ^~h_25aAMRC%qZfq!PfpXhla9|x$MsMTsI$3lSPEK7ygGG2H4Iaw=jlJVM8G_PKCdNJg4 zpy^2c+g0-1HH{a=@jhvL|fMPpq$%9R!RwH@k^p>$r>nk_@z z<(D*!pSX-T*EbI}*P6*NM%iCmwF=qfIQmk2sEskfC*2QdH;&7EqxhTSyR|T1c~*9K z*X`QtHS$b2)tTbx=v`h^)(3dVeYuhy=2=_bk!SYOJkDdu!{y$cqkSIjVPr7|IdC<@ zNUb$5hXXw&rfACwJ7Mg$w)W6&43f{IKF;+m zfg|M@JaK%IwR3ifr!1JNYlt z&oQBya;%hoAgi>C;w?G6^_z#JEt%Vt*BgE#F}0E6=;%d^ZEJ+kRmHjUjGI`u2W)rc zDdx7*AO|LPa^QV-%QI{f@1^Gz?w-Z=SKZ&}RkVa?`;}3L^<2y3zV4cOvvp4&x!=3k zy@p?K>bE>e9(>h{M!fL>hns;eB1GQkG}P~{0zm? zh0pcN-z3I7Y*IfRZ<+5R)|SLUdHH=Gd1iZfLsy>W`_9ZBB(*UvWr5sk z3BSU-Ut)qEt>*fO3E9!c>tT=dE%e6+bmL~Ab%d^*&HMYiVSN@_y2efza zqvCw%s`F@XrZ--^c#$6XyqNTZ2mj$ukAaj~A0&&pgVyr^q9Eb;= z_F_|(C%`(nX|^YOTXHStc6`twS+5NGKx2(S@gIDfwyY@z3|XnE(FuIM44J=*4;!YJ)zZ{-HQJ`ZVpHY1i%LXW#q=?bW(%k~MbJ z_tUg>v*g^{CviosT?hHR>-y_LOTi0r?!9A@owdptX&1Gf;xEOY+TP(tahCGQPiU`Y zt1G*{QO-H9ZOzM8R#>8o`pVL>bZk^(`COnnd?`MZXAH3}{LDbN1cLdaV=kJ@5UTepc6U@_F6HGRDH(|B8j&|2IzoT@S=kqVcAN;nbgFW8)786_|swn?zncR1xnCc_= zh$|NQlm>p)e)QxaiB@8aVnPFb%s3`&U7Vfh`5b+CbEFIV?reY#e=ofuH=Fw7kBC=R zPtA_)k)KgLIPspQf0vvCP3qZOwBE<$n$**MsP<%--1F(YKZAC)wtUWJv~KWTa8K5~ zhH3U$-73p^SSG8#ey^q6yK69Gk>0eA1MZ%@o8=X#Dh9Nb~gi#C*Z zAbi`%nWsKH9^3y*wuE%b$nV}diFQ>A&(G^Wnu|Ee(;{52Ulnma@fp@1zMg^c(r0+_ zS=TFL+-aUr{5d?SpDCt1H{Q<9M~%}_w`-FfcrnLCh+{%yyeovb!#WS%8zLs}p5R?2 z+}Vija3`XCXIX-ayAXAFX9<0bcb6cS8}Bp`8}B+18}A~)Z`eoVKg`Mgfa5~0F@Ht5 ze~16>@1TElG;v{zh?)7m5aNfJ>J!^KP+8=D6;AF~;pBc5PVQIX^TWwKKb+k2!^u5AoZR!n z$vr=u-1Ec9JwKe>^YaHkQ=i8N-C!JksGh`SO^ZueG&jh-J)GRz!^zz&f5@en(0{D1 z(J^mgDk~;fybCtZ)rh+FJEn0YXID5mGh;qqG@vDCX3XaigLdONh1ht0AvWrvLGydg z#I`J&8x*&#@+2z5PdGQ@z0&r!2Dg?tIv++yPtGRsm|${7j>iNGpE9Ah`K+;F8av@z zxcAufxp{9hC-*i(jLdtRA$EBGFT~5ZZy94MVr|~r%z+>91)8{&6`j3?J~)Rl^u)Q1 zp+927F2v-%XwwhkX9+z21vw4a@Ec-tJV86fu`L(uCG!3j6I#&UyoWs2=89(S2|t+U z=whWNOnF@s&TBCe7sTXDqllC39`eu1XOMFuZ-#;(E4Je+{AZhMQ>@~M=WzZtas02w zYlJpMjXU{Vh?TW=T-DG2Y8=(L`*+nz`i!Gk#qr-2$N%a%VIwDDZYkaasPFUvKajN{ zd{>dVHZ;GB2iAu0*%@UFb#3n(OLM*L-p1S>#4m`=Y1D*SsrYa?`o-@ z6vqeMsL%6+m(||gkY_S`+?cNI@{@N)ZGLk|YjZI(+MDg=TkTeY1c;xO%ET6l`&hvz z<+BxFxiZZ`Jm1lsja*g*af=jQZ10cL(C2X}OPufJ;@mjuKr!`sMRC9GfP?m^o46&7 zPt248>0KJR@)6&4M*OMtW45N(2KjrSe<;>hhH6WD%lk;z z#d&PR;ygAN=dlrs^VnRR$3`s9V{>sH8_(g0^VnRR$3{Pk^VnRR$JT%kjSI!GA&bVM zaIT?R@TfxQ^ZWO=Xnq^zS>g#E_qCOE;HA0~?L1IkcYejiZL;T~-Fj5IpfSm{G?V2yUWL~g{}mh{sydEnkG%hlqYWuTWl z$2da^E62nd9r(vLeW=eVzCR|3_UKo64&;^nXv=O78Ea|_#nI8jy2;LN5bg_~JnEr0 z&lQZga_*J->Ipp&3j%&-jX&Zo;~aTN&dP|zPcD8(EdI^~9b(asi~bsL7W}y2i&)6v z#XZJ3l6D=iL66wr1H9}E{)i2^h{c~kAH;^9hze1Mn9AF&}9vG^0{ zgV@j$v7tX=;XfxcUKCRr+L!XAvJ4xMC)JJWOl<*~dxl?k2K}k+)F;$e)Q8l!hCUql z&{)tI757LJL1G6vY0^VZA{O0kIRLRDv4fmM8leyTL=62%>>wx2*!?*t&Dhy;*x#D4(btP&uG-K;?kS0hI$P z2UHHI98fu+azN#P$^n%FDhE^!s2unwa$us*812W#{W!>8-R+8Hf3Hx)-S)P!TIPfy zK0Udme(m@G#1p!2)pM5n8gbz}N%+ztO%acNRgkwSS^;sgzEybt`}q;aHvizEMc9MV z-Y9Fv?lde}p$3RgB|fE%-QNlE?qZ{~5eub_oetl$oNFp=%zC1PwF8$n_E}j|_uD%V z>0^WE++2>@l~r;N{NPCFE}$nj^k_!I{@^ zu88=+B+2gCdG zhO_%>fWH)Eea52xh<6qI);g~8t0I_UP|Qg>Fiz(&OW>zlDeZ4+^5e_o&>n}5j} z@wprMnO{&9#J7*W)#}!7fjF$|3hmWO`HrmbMNchz5?MEj2d^!c@V%@X@l79E^K(x0 z=f^DaogH7$gAd5F7X9$jJ&2E3Qw6c_wJ@Hz{C)J>`S~F{&y$oI_$MH+4?p#II^sv+ z?fAW_HxS1*|7_{Q__Rzbal9W8IOO;W9PdNt1@dt>2cr(ZJn6)D*FK4OXiz=AwPJb( zI-fgTiq9`t9C5(Otel;zh4|5_U-aUG+arF_c9QPauPd991 zDv9`LaX*&yd1k~jB0I2b1umfvNBZ<*M|O`vTw-=8E0g;a`aCXW!8>a6JVVghV7`4v z0n{h_W&kg=cs}Cv=iBhyRqjchpVi>rZL^~-_4a#kdymqHgHmPWc`HcUJ7&J9Prcaz z+aI=?sJEFd_ONb-}DjlH(ksRQ8zI^w2Jv5 zVlh9oi1{I6F+bGA{1CC2A8KNLh*-=InV26U7V|?U=7)&ISY~2=h&Z9>Jk%m39+b4Ow=XBvCY5E^ZKkzhP0^j zfwEoL&^d=u&!30%XBjTZInU76VQg)q@i=yT7KE}f)lXm@J6EkAYqfX`>UnQw2R5$W zCB$E)^kcK#vv9DhWED@=acfD$EemE~=P%VoJh;m#tL zYggX{pl&NuWzjPGgdl#U-H6I{Lq03}M%C0K_6)@KspX>dMj5*!Ztx@tUsR|m;xEPL zyV4npOSo3ARTrs>;&6&VzEBWN=|k8#Ba%8YE>E?>0gF zrTC;+mX0OWBDC@!9fvux>X;=2B?MV|uDZQXiL2Y52wta_tr@?uVPzu^h@hwz?Ysxw%|-=V2GbXZJSZx%3o> zzb?_0XU?-9^?Vr6pBMePAL1&7!g#e5kvL`zjAPlL(O{e!eGwZx8MGU+5F0vBjB?|f zKJnC7)Su|Le;{`8GG6gHf1Y-8=TlqDS^+=dcNiBi79r36j6XupOnNbP8Q2Vc#n@$# z2Y|)c)nFU~7Gqa~@d;RrT?>p`16xfDo4zC@egxhO`gj!NO8_+=yR6H%<4q>F&Kl9 z1-+Q(6?tb$8^79YWU;K+KKOY%b|ukue1>iq-iLLcDEAq1PY+=oT~lLwGO?f2EYC^Y zmx$;Q#HNIn*MVnGpPuaC@>Pf%Z*IW~bomYO_KLo2&_-Ej{-9?()`$A)`Aiq~<3$bq z13%$+uorv@bbrRt(L=1jexL_`fL{QEpTJ*$!GGXKz~EQ#FJSOD_#H6B0pbA|;sbF4 z3~___0fu-&TmeIzA>M$g&hc3vsvG1xbI}{6!r05(^AJx=7|OQ%^zJV>I(quKh7kwcwBq&U`FZy`OSGu2z0j7dOj!j64c!~el?BEWLLhFh5^HvhOrG8 z#yX67z)%CA761m__V24FJ|iSPgA>nmp!y`rSI0VhiS$WQuT9?NA4p8!olzVeJ$=6x z6HMO~QY`$&Z$>UF4StKv8_L%Vet~t5z5}H=I(qt^l;R6ZoA7Pcq#XF)&C-@HXn9u$ zTt(~3uRh)P7aScujc=yP!E97TckElttrt7JVJTwwR4v(?>TeJSbn;71kV;HW`!R&#r9tJ#rwp1a_{b^BDJ&=+XiBLxw{E0Nq?4Or;bZnz2Pvq2l%%B zY`ymG-bhm`$vr*lb{oXo+UMj$dR9kVZ)-XJJgHnWMt$FqZyl8i+o`?(C0pn_Q;OZ~ z*J^pfdoYOgl=^SA9f7jukIU=8xK%!vCrq_4zhrJmlg6(h8=E9G;sif-X0K8l)1dFS z-hnL9v7w0RI~|H+Ll%8!MDg)+$+cW-<$Utei;`NCD{{_B-?dR39X)*?NAbOgFrILE zLmY#*TLkgv=PRJ?ztj%k&5J}JrtdK+j!9qo-ZLhcp0}Ym`9*JS)vO@QZAJ-KxNeL~;YQyd*V)T_by$BWO$!oR=AbdQ(f zQ3;3XcS^{8=JY8>>VXI4J~rLcrZ_r!y6;W#%4y>JXCBJ^>b(O}u#QjV9ueKcr#L!# zy3bGXknrBDM8P>ac%ff#TlVzCZN#~Y)nunKXUEu0Z{oos=9ETUZBu#{=py&|yR|;6 z?N21%-E8hZO8aJpw0%^^3zpNvW!xv)b+NvfB5US`ysh;)Q3H_A52v>3ZqD+27kxiM zaeUB?zOSM9^37@5uJ8MxEp;c3)y@}|w$pc56h}u--*Zu1@^VMEZg#`oEN`-Ti0L~-ioXPB^@woq9VYYt!WwypD^K5cuq<|D?*_f|<0^ya?l=A$jeDu(ci zeX}4=ek+V$7{Z$eM?Yk?N=f5P8Yvd!v z9eB+Z@)_;8;JMzsQ7feJ?H8d3R0=@cFg%aWZ^`xAFw3{zU7pD}dfuq0y{{vmiRpH& z*9zyCbAYoo60tcunql9mRSL4I2jsi^LZyA!1v~lfp5p%ndk240knNf({ZQdtA{N|3 z`ltJZjat_I-O*RM?)Yj~GfIE@wchQ$_pbEwrnL5Y0#7*)X;FH3EsBzcMu7AOlhW4dAsVu4k)s5;*ZJ{>O_(rGC&a7p)>xE*dXNoJH zJY~U>h=&h#=L@Ts`wNZ(*!RK7HhfcKdG@B$wBCGd=o}mi4_k)tt5q^0 zKJ%+MyOsD9*4q*Jf_T!MK01t%q%J-9^;zo?ziir^m#CGHLwhc*5-&8x32_VY{nGt& zSN;p8G_)_}No7$TsBTneY74cI`YJko1{bWv53MkCF4dej8ZB*^khlk5)l$~R3Q2=_ z-CI@B-t^bQ_`S2Y(I?|VLimCjgtuJq<7md!%^ra@bNqSGD3KJ{zx17&ic&xd|f zl<#a_7IC+AX?TEV1H{R<9?^%s?u>X`(_npD4tb{ZMfz}Siy|`5i(A%NF29q{3;QNR zv>6lSIWe~4gf=gm?E7_CI%ct}k9;Wpui6-u=Y-~5M%r#EG*}zCQTin4%5qDKOww-x zTTLuzbdyH()y=-bSDg6GhA9p0OL>N$#dG0LK2iP`KB4(W^N?an^96HK`Cs|p_8k12`bO&> zt%tNuQvNiDX>QY;r3bCt@axlMDPVoF2%Ql3;6)q(1!@?YhDY~&KnF`9cc zCuy$I9H#ovoTr%5(7u!>l|^-+x~cq+|M_30eP=el*>SATrS1o^Vwu7aUl9AsewP>G z^J~_}R5ZB|dc#Hs#>*Nr-$ z|8}Db;?nI?^RF{BL|pBaE>eDE)kO*nTa0-mb`} z?7oz&TW)#2!ZFB=dAV7zeOZ^U*s6qi5O+P$iY0#i6mvj(*^9ZkEkb-EFqmB)QW!Bk z$3-!vp?xV&DvRnsb)z~{Td0lHcIp%AE9yh)Tbfs(|B$Gxcz!a5n2Yn4wsSQmt`Qu< zi@C~oLucOh<;8c5(;)xpJ8p{Y+l2C6N3P>|+-pCO|F*U%($6m3n-9zWJ!0rD|Hb^= zv!YkNQaPY;gVR1T;dP&uG-;6IWBc&5#;MPYQrAms<;2bBXV2UHHI98fu+ za^Qb72jo2Hl_0zgIN4Y#ZfpRKEx5?B>$=P zweo|?f!N6bRS*A-&ov_#)U)hgI44oDlk-wF?(A^y)+!;B*pdN_1G`x>MEPld!3dG`1 z>V1JMnBxC~aDJ%X5y;#y)?b(>BA4JN;`s26fWGUI;Zw0w`zm%ge$~E;e5Y)T(^z}Q zs>Yp~XR3LonrEtcX3Wo}sG6y2rmC5$W~!R0YUcmKIZXAuQ_nl~yi?CR^}JKhJN3L% zpBWK#K)px6Ns;=z54b^{@ssmI%Hdkx&_`Eh(_jUYx@6}iHOf}C`^Gr3*RP#(V&s6hFHP4LC^Gr2YQF9eF zS5b2nHCIt{6*X5;a}_mLQJ;gV zR1T;dP&uG-K;?kS0hI$P2UHHI98fu+azN#P$^n%FDhE^!s2or^pmIRvfXV@t11bkp z4yYVZIiPYt<$%fol>;gVR1T;dP&uG-K;?kS0hI$P2UHHI98fu+azN#P$^n%FDhE^! zs2or^pmIRvfXV@t11bkp4yYVZIS`L>fJt58|AQ1pXDC0&oKSvHeo#4}azN#P$^n%F zDhE^!s2or^pmIRvfXV@t11bkp4yYVZIiPYt<$%fol>;gVR1T;dP&uG-K;?kS0hI$P z2UHHI98fu+azN#P$^n%FDhE^!s2or^pmIRvfXV@t11bkp4yYVZIiPYt<$%fol>;gV zR1T;dP&uG-K;?kS0hI$P2UHHI98fu+azN$4|7s2_OOVLPyq72@7-)-ojB_;o^*e?Z znMWs&dT7ma1>;>um2db1&(-y^=&x-E+;dk69UpKG!T zg|cDatS+9+?m|h#6YgbVsUG+t4!(6o+qk9uU-%!Y8_Y7?bwfT{hhD69&n1W>Mz>@Q zhP^^uuaYl2w7~)U9;{fH6-rkg@rw3IS=C>fAdYCvwW__pM*Pd6##+_l(yl_=id!ab zlYXFniwPc?Gmn<;b*SXiwr^tVri&lv8I!&pehuUqT7+rfXNqaxyyG3B z&i^K5ExqZXH_IvYu^YHVAK9)K>Q<@s3w?9`R*3EP=i#dkRYg2us)hR{b3;7e(uh}_ zo)U4<^j&%O1N+gp%fIQ*GaT!Scz4+_K5XY)E9i42X&B$uVYLNteA5SXGIKu3?LvCl zQ0bG%8Ik&+3;}54-Xc%+#|c{_UN|y0FSh?H#DPC}^PDM*AWk)}A#XZ172=v}y6}j= zgXo8jP5Sef{re-H>k-Bec3glyd6+7U_n5j0eL~|!aeUB?>JT$Li0|K5FT$iXF|EU* zPU@m2qOU~#)J6S8Ec$S>u8MlgMg7Hg_zAxQPvh^1p&#^zcHjqm0mr2*kZ0ykY}*BL z#Iqi2=^t_2>F_9Bd)u=nCK&WIbAaNwj8R<50vj>tRXgX)u8!3MzJpow3U8|%kdK1b~#5LgK=T{HkRk! zgV-GJngzj=!Y-JTW8I65d927u+guvtso2@s8EXNIwXsG(Y>YF+Ml5ig8Zkl)Ir0z2 z&dg7E{vxI|K?K)UD`*X&wT0FkT8rrTf*cWfgX>eH-ONwh^V;CUA*1N?-H?mzhCYbt zJb~5?W85K)XoqoU(!-k9fJ@FC%t~Kxd;JV@hL9bAaXs z%^A@h^kKk9*kxOr8~S6rG42op9mt0Ni)R@;FF0W82kIa3Cx|1`P=8WC8-GU{BaRp& z8m|w;(XZ{5*!)KQN&Rg26?xLQ(0G9_ z_YA-8EclsmMB8cH4L%%b4E~4>xroJ|Y zRO3$WRhnZe2IKDU=iX)=6)7qHeVCrkf9SZT<6U&N=|k%Sts61Tb5WPXJknN|%(&b3 zU}=4$b&u9VLmviwX#J#h)p(8|4Yd*an7$D7P_NMEg3lLUr-K|J8`rbObH}vzi$7of ztMl^@#LJ93#0#;Y;YQxT+!gj!uwDFweHFyw?_AI!7X57gr*Zi}yv*k&&?7eZ0I$!Q z*BScq9N#Ou!8TCVZg1Z>ru=KSrg)ZQC= zuhqJZ@4+4YOL$j5%rr|t5I;Gvv3L4GBfTd)2;+fe`g)&o&!dmO7R)WJhI!v_6RtaV z3gBl-j`fc8IH4zY>CDIYj`vRT{Jma$sXuS>@{jmU$5r~nsy+GEi(|bP*D0k}IT^%{ z%o*<8@|UDhWuAxevPb%RUta61Et(L_J=6PpKL}i`xo_^prynWno#*?PTF*T#`G9np zyhm(tV2dv=@5%8 z=YvGwQaZ%qt2bfne)1Gi5DV9DgV{F|oHd9=ny6l^Uc1E_#A4Q-maNd&mm0((m&KPY z`O$$vEc%}+#D=vg&ma~*IAmdYllw7OmGGj2}`Z-rQCwU%bw(DlQpw~@$V+9^M0jMATE)m0l#=Ojikv~m-n?~MC|#zGSAq*0OG(ZuDot3 z4e^pvNA>q7JO8D9S<2JabQ7cw(a{XLRA0-}LhAEhrH_e?(b3R$nj1%+b?4{%Y`{Db z{^LLgIa7Le82`CJLknQxdk#JY>|+V!J3@!*fJLl0!~?Ltq#;k%DHR7S;>jVdfPc!I zk5|3pgV@Mh#B~}3@uEj6pe*a?zT9>4M8qW;hN?n8VhWqUqg*fqqo@99|%JatW9 zwTre>KSW1EeHat^FGUlVa;eTYgH~!Md&@dj<;@$d!r>MSe7^sL1G|;i7xC3v zjJ-Zu`W;vi%e7ago-D9jp=BKDPkGvoaObmX46My7k>Bn{Pdn z_3-W~7rjeM+1_#VBE8MUUP!+$!!v#IrdEgp9_HrNyM2YYQ6dY^Gs8``-)zWRr zx!Q%L?JRYETelIP)ix#4j1REz#CavXW8*yhSPseOwEj%5JzDZVoMf^7W{;Fxy1uKP zzNyrwRHsKaJ%625P)j;Qwg*@uwF6nDT^F-H)egUve2UM^&5o>;{I4DHX6=tjx!I03 zWC89{PufoVQvOs2swcI@h>;FCW5f>e-Oes7=WiN^_LMHk*!|{B5MMaSwLZ1KM%=Yd zBW;%VK*Uu$=eG>l9)`H4UoySih7iQb=giQXx%5HYC+Qu%Si81}Z(4KkomZhC zw>+fjeY+rjeYziC6E#9V-!*TPg$MKw^TqO_rFQ3 zzZ}+HzwHw!)>nh{Gixr2|NQxr#Ow54J9CMjCB!=KqF9HOhxHe~?eju^;M7p`8wzVP zSOf9`50bAi@us)G6bY~VzTnhJO$&W4|4*Hh3mst3ggtx_lv3!a2|XF;DfHKb{;&=O zyEI`J1G|KN8vG4x5Pr~vA2jg83V-Ltyxye6p#R#M!-_awy-@`4m*Q{ov9sGc{!=mN z3VrPCz7LNHHu-<9Pk!CjuE_qJyU`CdJg+bB6Y3*k{zZL)xg>ZN5ITPnrn-HJe3tuI zQU~9;_m=-Uq+OA+*LR`qpTqxC^EoE*r8Ir#Wa7PZ)?rZd3xsCm4%a2t{WI`N%j;sh zuXlQWu6I4emnL7(yO-{WcudeJef#)+h)eZ8WNo=L6mhyVlPq28$Y=EA$i7;VV7ab2 zzweONw?!AE@ok=l&1=&DvBS!u?158R#Lq6&U{QUtBfgca9h)@r7S12aEN#oIkAFq{ zs%Bf(u=yRtE)UzVrn~MUUR?c@-gIRr>^m&YP`zu7K*Xs^MOhbImb%TzKgV*&OX~Jp zf&tnnAF10)_rqF^s#3SW_o>;tc~ZBN*W6j^Yf`rvN2@cZGdYkawVm2a+o`?L(NNo? zqmPb;wi~|EA&!Qx5F5TiZ1@UswGuU1@weGH(61X&j7@J`265!kv@A!L`iOU=KCUJ1 z)*1250fV$FI|C8ddc4eXO`IEpz5-iKENFC-M)cLqzJez=c?wzFlqGcFrVc`XE@Ex! z&qb_F{ke#>sXrI7Mx5|{b@paP4%Fdf{i5vMz_N&gcpA3bp#kFBt&VDs4@mtR9}m?s z-;(-g3SMeColfd6u+_wZMmK3hU)}60cyg1cki|_|LI-Z@uFoxBd(sw2UFN28lG(a{V3y2)SAe2`wqRV(KGEs_sd`4oC%X1e;{RLYv%3CTK1V(WFZ(T&Zw*|HdkZnaG09;?6Z7$|e5HJ) zazN#P%7Onz4$$`$F~MR^@=1FO(b0eEe1^`2;scJ!9FNjO=Z8;i|I~2@b6d~@)^0Ju zzwfI|6z8waJ(iDR+)sqA#t=8Dg4iv5R$pMztvHl#E{mQ~0V zc{3>dbMWWn9_>q?9WlY5GuCL|Ppwyq{=YE~RB=>sR5_q>K;?kS0hI&)x*QPi>*D{} zY>`(=PjMbb`9bBX$^n%FDhE^!s2or^@HsgUlf6Mo^ZQ<3%+3ZY`k0@i{;&E<G zz&@$nx_*aNZfG|=4|z04au&3^F=D&HE^P2k4e{;FRoRpUc@g)rYsK=ceSz;TyHD%I zp6B}k@#IG0v%}+E5yR&=s{}+9g7=$7y9U^xM{MvxZ1875W5`8p=!4kM6Y;PU+qC&N zyCGiLXS+6Yx5V4B?9lp0NNmt>;Q6e1GFHwaKSvY(tT3C?mSOv{4Zh6H-T|@u{+7(H z|4Y<=b4V|CdWE#BcAa3BCBGZCgIzlVmM;aKMmy?n&?7eZAU61;o`zh+hCYZ5{ZR)) zf5eoY@}zR9Zd8A2qsV{by<5!AUMl*SpHux`@RfKDig)(^y1f^ra}3XltN5ziRym+@ zK;?kS0hI$P2mY6HVC(Ro_0d&2;QH(Fq=Wj(1@hj2Tt1uh1hczid+((Y`jMgmh)>u0 zSW5B9`tS_l`p~|TzWU5?y;%#1Z{&~A^ZH6WY<)1_I4wV} zG1>M2Ui+&Bh&wfJ!w0{-kNE4S)%n9k^0SuX^B3crH_Fe7o?e)a54}(i^~p6l9e;9H z;@(@tU46ME&q8|x_#-FDvv$ii{F{4{=dy>@`L$(|XR<8C__$q?C)gxx!!>My(|!16 z->HZb_X^=YHPa#f?tU2WJFj09tcCLke6?*TV(_2vBhutP(T9&|Ci?~kgz)l?vhTwR zuk=KdTQcaIgXiW?Cd)fFUZgF@@2z*ocCbmXn{ zYdPL*rR;0?9O=D_EYU+c_CkEE!YX}EZF$#9v)b$Rhedi|d$&>R^^5r>HsXuz$NiS- zw>)Lvk`GtuQ;N#IM(mKrh$-S<6Le?o8b_h+o9g(pu&H*~zIc@{yPMYmaf6vfn3ugb zVz5uxi5Tn?b|Rj$|7-TLyA}CV%Hq!&zmo@#eNaCi~SZ|>=z*x`z^ZIFGAeBL}#Ay{c#=mx1ZgR=L(gw>SSZQS~V#vi)R7e zs;HFZKQR%XIzh^EN|BwncB_eeo(1^wt=;6FQrE@n^p!PxV0+~R>-0unOKh|=khOhs zLcYtnIpT6Xo%x`?6%qf`tP1yin;&sdmlphT)3=xp!!P#aeqPHFFDVqvuOBUnSnN%4 z$J*Q#cpB|!i$Rar;DgxU&w<{Mi`dWyv7s~SaLz9wKT=cPwX&W$^S5&=B2B$=Rd~2# z0mMTawcy?7yhZ+3PWI$2+AT*sz&V(gNK_0l=sDAA6YilI?HcG{&?7eZAU61;4u)K+ z4`Qe{qV6CTbz2j48?mU{nyA}|#kkf)-9`+xP1HEVqHb%VZX*_TTN8B~v8W-MsN0Ce z7}rGIMl8m@Ch9igu@imS178{IVvStbvD9*3(Yr@-)^?KIM;$YMmzFiZ%&}ziJ8R`j z4B%jI&VX+$m%Gc)zi)kg#9C-!D7L5SHbP%>rXS)V4rlZxl{z7w*Ec<1RYTVHA#FT( zxe=wY-O@wk-O6l;d!BB~OIMSh+3)|lH!pE;Ci=Y7)yiz`cp0O5`>L>3{qrOJy5&A> zZ>xNWvzP46za2LZ>F3;Q!}A}JpYeY(z6Nh_Av@BnSyPNJa+l8t$DHYTkI_<}V%5&* zKbDbt9-lr^Z?{6~?{)vI)pwY*>*V5YmSH2My_HL})?9v+et11|t5&bz*T}!q#w09j zg{Fv|#ua2`230`3Y*TOEt<7xItyKTsywuA%h>O1Wo*E zezjvSq@nb*z3#HtQT5J9oug|XT6?Uvp^&tf($n^RQAmHUWuO{~tYy5>ZE0&lvrsaMJ(_G^)b`Lvezgk;%! zL_2&>+Ojfzs5a=Sw57s}C6;m-q%8tlO)O}1lScH_&Ax&sH+c$K+>|AB;HD1C#_+x=1>yt7vYWVv z=d#(ZC;Ba2gh8*T`OY=M;KQ50tq@_{Ma-i@>P8rM6!T->H5cD?V1CxDRfKs5HME;| zQvl z$h(`I#@I%Lnsw(Aru~W_}jVSIVi~n+Z4`n!n8s z?fBgm!y7$xH1qRphY0a^9KX!-XBS(3zIwbNpP8SV$L9UR-DoggVLS-C%(|foyCPtG zp9o4=P}mh=)EQmaWveH`E>cfA+vU4qYF>xr<-R!@Xo5#PM*jQ8ycyKMDD z*cEP!Q!eZZH^wg)cG>EQuxq|qPlR1Dy7xxK(c@ng$B)IU%kgcFaWU>d4vh1-8h75c zQ^m=+OY9pEFUFmU8)Vzo|I>d*b+J;uJ?SUZZo^);oH? zE*Wv2S--;3WjpH^v&}O@u2!|pGv_vHW}9cu%Gc30&)j~!t8Je7KD6@(=a~yv*S5_w z*Jml?bhpA$H+bIVIhV^e&wRb=g>9ahvG5ApJoC{q%{I?md+l6)bDsHqvJ|#?rm!nq z*oE^c^Ag!iaT8ampu~5ioE&>arXNiSXePnv4>%2 zx8Y<-mT*c}#1q@@)!w|9-|Ig3Zl$s*Q+3An()yX3z-`~mIC39FK)+f`jEwk>|&DZaJ82hPBN`APNyGw(X zjo3e>C)k}gtP*eI>%;)3EmMeRd5L$0+ZE3t-UC%_hV9+5ZPxdNbVoelQd50MmVt=d zW}ap}SR3vZv9rtCv7Dvl7Ku-|x@&2x$nQhFe}AENcUS<@+hTlF3JzeYT@XlLEgX8>Zq z605AQQ_J|5|2dsyg4n+XK3>(GwKOy3_qR=1v_P}7%I~wE@$k4dt&+@DQz9F_B>F>m=H;_7e zbtuKB%qq?YWUw!l`D_^9{Wz`lQ*o-o_NAaUruG@S=usFLS3^A4e@Gkei#h++9_0=cGtB;6vDiQ123Da4}C9^N( zyC;laXzgNs6R@Y`m8*q#M4R$|@aOeY!E5$sJ6&$(yD(0DZdwTbi3u(oF_52|R$I^h zXk65uuCCm#R9bzh@LS&1H8*`1;EMhnkkV~ail)-%YfJazjgpMfUHhiBmd%ul=Xl|+ zS9kW|4I1?0&$EotYdszp^{M$r>E(A7*x8An>|W*K+^zo`E8y}uTzJ9AKpn9Bu7-7p z%PvjH_pHB#7=FUbWRHsXkQ=e8`SOo*>V$TR6R zArCS6E(|94YeF8j!%z4fbe7+hu?{ix6Y>xPKj3TF#STvD=M30rw*ofkb;1X+!5^_9 zmrFkQ-5iKP4)_Jy4gC=(j7VHiw3+R;yrua}^W5+o(i{FX^$~4yynr0&53-E7p#C5S z>IJmVzkEV`hpMa}TZg-9soKbAV8a|gXpI*1Lb?P?UTEQITOm$1Cojw8TorMrUo^IA zste*f+Z(eAp2-on_@*1n@?ZzfnJ!Nmz()Mk7V(Ym!kEL7_EwO6w{0j}Q1iM4@bY(k zSsUv(4e<4d4lJSbCB!rK`msX=GBaogUEx2#&<1}447AV(Fz^6gfPpv201PrgHek>N zbOH=Ig06r;cd!94*aWr#23x^qz~BS$1z_+E_y{og415O|d}(~oh8^{-@h*S^g}FBl zSp0)`Ti9;CYlB8}%>vk5rvNtBn1Ic9ZGeSbwsy@=aq@k*ZFdB~a~^$SzRLg&%y$`p z#XoN7{n_86+Hcw{ArI|^yY_X!#+nqd;Xm}Dv4%DM3E$s}Sabn>5F2_THuOh)zDal6 zSfJQ^hZ0+Iotn%mVCFZib;j7oyr;F%82i|6jC~FI(;91xeQYh8d0QK^D@Ycvy^Je8Y+O^%Y z8Wu3?&Z? zLrvI~AD(y3GE6Bb>{?*fNnscG0qAvM7x)MGaADU%vpx&Ez@J#3g(@*4}&z0Joemh<6x zzey9`dcbR~rB6%#Q&fTQ;Lbm21E=)jlarJP?>)d-bN()vZ#Yvv{90T0sA|83@t0?O z!Z$xEr>}_&LOgZx8vWA79!OK*c>?}yd~@u3)76}! zH;RCO5d$iSl7mPPL{xS!#hh~n6Gl*!tfVcXV9q&<2!c6bfIV%_IblwibI#%IwPv<8 z_qpFw^}hApbMC!W=Tx0Kzti;ef34NMx+nC^=8nTWGq<04A^rF=kUzGmpSg6xE-C(J zIKLX!D6{GYt<>*99ADWHbA@#b9>(`MxMxPzH-g|Ly?Izljm+TY z)#1j^R{Y@ca+yP$`#=Eq;}1OyGVR|qhdnm7e9XBUYu**>3EDxXe8%7%Yi zTDWS;nog+^04H;#PgU8P{maL~_C_Jn(l^I4?BkN*^OHNe7-+MwmaWUS#dCsGk-1#k7HEn_L~r)-r_Sg?-@3 z3}1(-DHm8y&~WHfQR5K)YAM@$B?`9NHTe(Y^PI;-O^X;UlumBpu=Y_2w*7JvvBT1- zY){)*I?oSVd7G`8G=zA?m`Y%OxdU;iT|KCLuMY8zR$U-+YB^$?%EO`go{My?(e+Lo z1b)*Jukz7CqvfmVdUodZWLUFcKV8qBy%G!0bm>g2X$Dn?426>hH;B9a?g&$_Q~)eD z?cfW}d*$m{hdLGjPMxWIZ{I@p3WgESyq(GngX4&MEZwT9YARpD3fAda)RFXc#Ich8 zSkWfew<)x^UQ5`(^)?9GxZXBlGuPWJeBpXugpXYBqwt;UeHSs|`k07Vaeb^r47omr zBDP!~TM=_fA9K+clD;o0S^Kee&l5PtJJpQChH zQ{{W@f;D+6meC~c+gCKzz!{u zZF_lYA?ubDO?C!Yi+$8Kp~O!w6@!TxLB#C`RD+RXUp@Mgea8zDEb0??Fl+`-;_Qjn zrgw)w7JiY&%#u%PMo;ZFHp934j z_e_SO=qEJZ`VAcm9X|}AF;+?w0S3L+6Q_O{3=a(M5nFBV0giV~0gwHa-5l1&*%Hq- z_ksIg{D^nkREHhbt>rqdMsRdZZ{iMLuduKl@|f&axQewli=y(bft}dTMe;KopC$#G z3D4yFEd@Ka7R-AikJVPq%%l_9NmPH#ltgK#$(!#=p1=Zt0u(G=Nj-$B|VADjcvzoZmU9U6(7t`h0r}ygRUz=`Q^e>^7kjFI%kw$NJuJz*oL(T^`3^Oa%yLv}^*qpQ~uFUm;dB@!Ho&BS>}lDlsK z)-laZ;B|8wl5KlWkK$JKw-Z-75XAjg79%ass!ezfcO<^P(4HTABHtT{>Gw;TSF10T z+r8N+wLUVMxaWK?$=^-RkrT(e;Q0WRtL>bW(1-gRHUzX`-`z0o`Sl3d_I-LB|2ASg zaafCF-mbz+ih0H}E#FrAJlQvyu_eLpoL9#HRxwCk8`^Sl8Yq$j22dzCdlcu0c+{yr+w69@&1UtnyBJZg4sp zMjn|@cDh6*!y(gqWM?X9;r6vGd;Aw|z%u+BvU2~H+Qc@nEiA|RNBk?Uy9^AJa*Bicey`FF$2v;;#ELGlVh^!m zC-H=sxy;EqhB$Y^Ll$^t5b>*iRbWwGJ7SBN`p|TY7x6ixZt(qUY2x~gLgDU&Gi1-| z@nhiAy%^%r{k7n6aR&8cpS8)*D)<8R@4N1?@VxU>@@veFArSo(e@k1;jlLb>+q;T@ zd^6PtZjYDe#`y{5;eqVvDBGT%Pv?>+~$@NcuYB zSV@1ZXp`&P6k1%bC2Zh&8-#6KZ=0~0>unakaJ?_WN3Qo#_|EmdiK2{=z zTpvRbTdt3-h`FSXx#$Z?-xvS%i#!JYC-;lGkHq{8`gLSXn*_)i(S*kKn(fihY2*UR zi{4{=q2_G)Ine)W{m&y3_|&{cQg-MzTic!qTst&SYTJB=?UUSOzIx+1o&PgC+p}M^ ze6udH;J_DyRd!v)v+nxyG^dgq};y6=p(3)EkAH3rWiAGNXQ14=r4;P9$`LG8A zJc%z{9;#_P+Lze1@_5~nRx($u)j%r!+JnlAJ}!`4COHuQh(9GA7*L5gy6O+<*z;n< z`}{5V&#=p6!&G-Wo?p0%xN&4{9>Y2iFU|Ae=QB5wFUS`Z&YN3@_o?)f%8$MG=9Bl7 zp!&7^y?Lqm6^KKey?8EnBCd4VgWucSkhoi6Ext1>+o;H(sg2DB|&juDmEYp7>H1 z7rw)NBJqx8j$Cq?LwqLIj^D~%Nj%c52H*X7199nIR(#gAJ;X~YS#tBxqr`13Dv5Vm zPZK*mu;7k!FA|%4Da)f{ZxBCUU5aPDFCrdu#fV!RdQWU{+>k%7^M&~Q=3@NvydT7` z2mF*W+sHAzWB*=aHH;~qcON{KObpG5TQJ-G^T z*rft#aAY;&@?GnXG<-P$>ZVErK!^MFHThM zQZG#^vT-3^z9>=JvDTG%naMyY;A<`7D{0N7cFywH=)1*5x?t)><$GqCOJ7!c6KDP? z)MfmV@6UgU&DWLG`cQeypyj&J?_}=0WQ492p-<{mQk8NmBmH3YDY4+V#&ZC#@ zud#*4%29dUCl6W1Wx3xIM?7cECYn-tVU4$}kBJHKmOfwD$(?eJ`;|6;*$;oySW5LZ zfoXf+5I^!Z1PzaQBd$v%0>O;ls@1RQ@@n8Z0u@ z5!Z9F0gdApVw(rHF#X$V;^t%Q;Zn*{;$dYSVQ&~Lc@+(o zmw4_2CC9BK9y!wo`e}C&&vf#Ew^Pp&w@i>OK`29$Pcj6C#*5vG#gKW zVxz{^5O_R~xcJU$aOP`1vA1f=wa*S0*+Fx8FHotvXV~Q96{*f+uj6c5a%JKh6%VlVvsH-OmdRt&;;f0c8Rf98 z6>Ab7+P;(x8X@l^YHc%vc_%qh`N-sC)^3a|vD2r~Y~6Nwo&C9LAY1XG7M0g})Pe0B zEblvtuhEe0zwJTgt*2VB_szVC`4(g5cvEHr?MIFO5P9w1`|YCUWO;d?QmFkh&Dl>f zS4e5B8NS??j@@@=UckDKGLLNSQ!wPW%#EM8>)LLUd1=2Px|)$PoAsWpdtFWDRl&P; zx2MW&*0(9rB^{M@D^IB=d0z9P_A@#=NtbHN>}Op^suJT#S* z&rdeE7DzE!)u?=8yTj75BbLO&qOM5Iua+l%(CUWtyJR`yPnGUUgKL)|Znx!;uZig_WAlPiHgq^*U;sJv=lL+(@QD~+)e14{CbW#sdpBdMi%;eL5fSC{;-;LPCTbvVV{D>Qu^WvwP zx)85;?8Wbot4iGSo;S}4G$!tTx(`-$uz}wU%=-KRWxPE}&N%TQz5j=RQww_H5XF$?R2T=LMIv(&gnY zsSzXY&3bKGt$Tj^cFq5rI@YtadlrId{F2JDK+N4ZF|!&{^i*Tsm1#C zb|0>G;~x2?c#UUs?0j4s@Va|F`4yABcEiqB;k^g8<7vq^>~7{flwO`1#2>c$WS5vX zM>^Fch95jt!alp+OWlL!$$UwenZ3}_px(aA=JrB|p`NdSslCu)sAo{DxV_K;)N`)> z%1-D2>N);6XD4(3^=7ARv=cgjdIR@QuoF6fdiHNU?Su}X-m}sfwn7I`Px!S;=m6>o zzg7z!Kt17ChR^}j6Mkg~9Y8(dSBB65)DwPX2pxuc!mkXW!%$E7wMOV@P*3=^2IGf% z!ml+LKhzU`t-<)Ap73i8#t-#`Ul|xb)DwPXVEj-|_?3b2Lp|YF2F4HdgkKpLKhzU` ztycHfzvF-U@qd0lK3QqV^CCVKbQ&d|WBnI#Mk@opA?>{m+x$}Poz%^!lY~5`#Z5`~ zX%_L+16=Yq+(~Q_x?I{Z^CGeHoDtI8P0xv|*0hxTGJg|kcAFIJ!GN7P!Cz?Fw{d9It=xYg$|$|vd|$tWT8WP$U=vq93-_^S6V=vD%fK`>BQ4H0(>SI@W-DT&mOko(ee|K!1PgyM3`V`gq zcgKEjQIE}N@|o(Wb=Ak3N3;!CeO4YbYF+iQovmv~>xX}*cK+S5x9%>Jl0V90_1_&k z!RMO9CeN4sQt7IX&HeFHYJ9#l)luuJkNtP`)pgYE;5m@-#-sXup?~&Os`p!}_hG8{ zXa2wLbyxQAbJSG!OcE>mU5Uj#KuO+*O8Y|pyz8Otca`v1^*&Yg9!T}RR#6Y%Q&@}j z|CRAxK9;NZ$13g6`J2){v7$??-hZpuiEZoOJt0=_1r_?4iaz@Lm%p=+&gSX&i2kMh zc(F$L|CV)DdySch>&{tLvzbRkx|uQrjRJ z`eU2gX8qn*R63gWkoLPGt9@6;MEvPbtkf}7$5tJ4bzdlbNB&~piFa6NpNYCpmHG^A zP}%`xrF~*WmstD>?IBj|Bvy~Te;JdsR~g$>;-GH_<3p^(jaZ2%vG_YjJv>&4KiR4D z3$cETV4a~u>;J9sl>6^bE|5KcMLdTN-GloyC=P$OkMbUozuw2|y*7z?<i6Fm3e^r^smYbF;?{X{+GUE#iDWl$lup@gI0eQdNd~gQooum55_Tx zbC7|W)pNMgcT`7I`!naO*8=q#q0DJiUzyV+Y+t?Bpyt2$sGnQ#{R?9C+^C*2)pMz0 z&wmaka`L8EL{-!WVp&>qymxeQtS^JmUiuLbHgLYd2{zIqN+uQjMsyz_W{-qANj zv2mq7#X)I@W4Y2kv7$>X{)F}rD|QkqYY_3v%jIy+{7;-X)rHj_FYhHQ4q2?CZ6wv{ zzxh4$b{s%#uBi^yjam~A?HK@F2G%B?+Oa#FEK!QM#^_KmUVoZwUg0(dru9!CcCD#} zpc*-}H%VdIo21mCzEh4RR@wygSJ5I?Y#>%_BUWrCR(v5wUoBhA6Yu*Q7`RnW|(R@ZldCa)v1@o_;e^dDwo2J}jihSj>rlJyLE z3{)!emS$MVV?)-F^Br}B9vzE1LXQ}AgdQ>K2t8ud5qiX^BlL(-N9d7ls3Y`t-j5R=p^Q3vCQtnM#0uN8I5+>`6Xiet?jomTdFsGu~2^wd_k_`aGPg$+n^CwO9%9 zo-sPb<3H1VGFHb?p0@Q>pC=?cob;gJV>LTDZN-SBhbee1U` z!!*$}l?c=@Wcf;Mq``q{U$?t}niub%1xXSN__dePY zW;n|G^g0^Wg@wlQKE|WA6~XjGM?gC@wzrviw)}4Rw_Vd&%(-*n%+jr!5!xy-;NcVrnt8N8NYgy!X$Xqn?Y@bCfvX&)lV+)6{dFdJa_2 zjmliAA3yMSoqx*jzK^4rsC^{&m9g}9tcmh<#h59)EE9zW`Fr5?Br?x5oim{`|>u&E3)~CT=~R z%x{!Es{8cph|%grvAnEyvSb%K*?9ERAv~+pEva>hTgKJ>I`ZLfEAq^j6-^p?`tT2z z{dnF5Ka;t6<#-qOE_{b;7n7M=E=pCZ4Cfw|hns9S(@F1usfO=>BJDLa`K)tDTd`yH6px%(Z)>!BO>IuJ$gbtvd@N1&b0n`(Ir3oECJ>gfH&;isFex(Z?Kt17Cy3hgC z6Mm%&9fo?suXLfqP*3=kj`2f1;a57w5A}p!=@>uM6Mm&*{7_H$m5%X4J>ge6#t-#` zU+EY>)DwQCWBgE0_?3q7Lp|YFn$Y>vUut%(K8A1eO=RnuC#IF$Hk|h}I?pbbKA%={ zSXaK{VHt>hS|&Z@jz2F`$s2}N@lNmZ*pla!Z4a>)?bE-#ejp`$9|SXg4ocT_pDSIj z6$75NW77Mt_^A8llnj%clhfDabk;P@(Sk{iHhtB?fh;I{EOgHro4)JiAr{|$1Z-(t3G)qlrY~;l4)=mJaIm)~{b{Av5bazYPTE&bZ}MpX#ALoYm z*B`B9rEafG3v7`D)1Fskb+1)S>-bCyN%8AyzlPJV|qKAyl-m;b&ysU(ludTaXx4YbSBX!@YIpR(-@9>rDhF;=E ziRH!nW#!VOP9|x_JxdScBmA#QMqXEq>o@7lqf1)wtP&O`@4ET%#H~KubCZvWcjZd_ zm{mt!xoSs~^IvXDMp5FOzK9_vHJePA0?WnnZ)IXl#_qbMyO5mBJ0&NZw5>c&vt6s@ zKebwu_zEN0Q1h`ozSLL~$3@4POXo2Dy-S!$rGe&KOat?D)4QSkNX|*tV%y2Ip<~8y>-1Pw zb#ZK(`rJ&t?yJuS#CrPA`RBi!Z>Y~hl=B%nKT*zSh;e@Xm-87Wn)wg+rPb#}>hmS_ zd6YQh&-s=5yh}Ns0c_JLYxY0qpCS(GxT)i*j`RP7^UuHgp8Vf+-S^LPhyVI(qJN${ z{JDOl>$v|v*L^;v{ptRE|B|1~^y^(`zxQVP^)ANXshOBYXuYeOS7?UUuc%k{Ha8Rh zrQf|u@Xjz3^9jzoe1V7746lQ6UT#~zj+y>`OXzlPD&~Jcy-OusODg4TR;2}#mHKRG zUz;gPJK%PI#1y4{*id!J6h#-7R@gH|u?Jp_yf8(v6Cy(%PEqWKP5s|a@hQC<{Q}_^ zmeaE^;TP7Y>vZ84wnOWP@C)0g>vZ84>e6+(@C)t17=!R@ihiCHeofI|rwhL(V(+#|X_hW+(V-vz_}*1jvBbRYZiZyTSe_jioXoo~JHSs4Gj=9BxGqqF~x`Q-F1 z*FW>gKYbU>|0~vl|Bk+!ZoV3?3wV#ogH817-Rk@p6J;IYDY3~WIN#$uTqag)qO3c7 z!nQFc`t@#n|4zgR+nlvKGQnZ8X-R`W9JMJ4R0TiA+;;!S&tgG{qj6YgHy)zus+o;gzmm?^Xo2PhWmoBc2J5 z1K}5z(|RZT!uqt{3BS^n^#z1q>B_nT!mo7wdMEr!N54@|_?50-?}T6J%DTpcU!t9H zyyJIFJt|BC;T#2?BT*Mj6bb+!Y}L>TJMBk zCfCcH{nKA!y`y_{e^=i-jpEC z8P53R8Z}_ZhcZ%ja1&mXW((ziuGPhSYQukYs0zRD94%P1v={%h%@}5X&(FUfJA^+f zy3NYe{;lghs~7)W*${;7fIgu8!gfF((0*Y%pbu!jupQ6`v|rc`=mXj>Y$qSkeqlTL zfc6X9$p^Gw*iJs6{la$g0qqyIlMiUWu$_EB`-Sb~1KKZaCm+y$VLSPN_6yqqeL(w# z?Hcq!iN6MYP~uNMDDfvBl=zbmO8go6pv0e{4@&$Q`k=(0p$|&@8Tz2apP>&*{2BV7 z#9xCxDDe+KAC&kvL?4v+YtRQJ{v3T!;?G6=HA?)sh(A-}&qe&15`Qk@&y@IcF@~5D ze=f!lQ{vCX7-CBNxfnxCi9Z)(h$->sVhk}Q{#=Y9ro^9%F{DxA&&3!DP~y+U7;31* zpNsfw(EckMw7m7(l~9y%-&l)80^OB zq}MC=%$n9{EIi(SNNV%@Xx8E$BVf`l6TafTX?9#W5!1o0ysVdd zcJ(&^MiZLzi^p1J-&|u0M_Tsfhu#jz4*L3&wJSH8Yf40C`&``0zV=Jti&C}O9}YEU zN1keVlXBy;5BInnFla^+Uvg_)_6MiZl4aj$?mlQt_L}*NBv>?v7xo#J-7Vpfl%3O_ zpDNcmJ41XwW}&N(*yH4vop{5KOP4M9wnmk*%kAjIh0kJ_*4-?Oftu~xitnn1C1>}1 z)m;i39nMpOBeNd_?Uh;$3*voE`)6;eSDeH8ro8Es7TIU-+4Jlx&fH;%TlThgjd{!!Y{Ww z=8oi}@XIZXyXGihH#6I6U@Y7-E7@o&3o;8@emq{S*?jFsr zw^*vd@{>Ucd~DN0I^E zLX$L*g{BTQkcFlOHIRiS`bCUBq6U@=O+XD~p$VvgEHnW%kcB3o2C~ou)Ib(~0cs!% zO+XD~p$VvgjIl%wWQ-+hAY&|10~uq98ps$+)Ii2qq6RX?5;c%9mZ*V@vHYjM{`dBm zy6@C|s_tv`7*LN5^_WqQCG{9nk3IF6RF75l7*>yM^_W-Zf;vakxuec0b*`y%P@S7N zFDPSMr_N<{j;nKDJtwH=3iTX<`G9SrCguq;YGVE%qbBARGHPPJA)_YdAu?)Wej=kL z<}EU6s{1Rjs0HkIG=R#(xD?mWmw5F@1J0{j5nH#l;k8r0F|5=2q91SOw~M&nsaAZ# zmLTF|Yr69T+DRI$v-)EYZ<@YAhkS5W5O;J5myk7Mx^dJ%7MdJ2kcB2k4P>FoQ3F|M zN~nP>G$qtP7Mc=jAPY?$Y9I?u4Qe0@O@7ekcB2`APY^> zKo**$fh;sh16gR21~SGHHIOlusDX^JL=9w&C2AmJEKvg)V~HBb7)#VZ##o{TGR9Kf zU+R8T^FKK#uc!Z$b5PxnyPo)ft*HUDomh-ds&5710R}L$nhk%v>KnV@X8?9OKi<}U z7pq&!03O_J#Z$Hiv3t%2&?TcgUq5@2Cd9=6UcV3Gr>Aew9k(-pVRM4`QZZKEIvBt< zkrN|D-jx*NCsX9aIgxjL1TPmk(M{ytdr`-;niYR=$&Wu4$M%@;O$rftC*D4Uwj%Gk zukFsqit^)mL6Z5GApY6b0D^{3(p_2{#Gh3*fJ*~6Xkxo}q;G7;$yR`IYwoj) zo!{6UFrHJ21+%R$g8<`fup?blB{_)V|E$?2U9%nCs9!$n!lawW4@hgQhe3t325jHj z&5~8sVQ?rVf#ujQlxo@xgR}-q*u(14QqStcpuE#Iwr6S`X}G9gGy4#8E?cO}5&XvW zJnLm_q`NG5U#CKLxQ2^nf#B(HuCTckpJ=dsXXA6sUuY~7{Qmd>_OyEfTPt`##%4A$ za0y!>_?p8)=IpwSalr;Q(QJCwA+}QR<;iteQ=xHRu)kTM=7Z2UCHRSfk!JeqE9|7; z#m+9e!6nWyV_|2-N>6mcFQ)h<4P3pM$}PGkNM?=;slI#TCDL!9f$dCk*(M#DQis~F zy7rLNscfMJb*s6ZmuyUoG-yxF&V}L|DlR&-bNHJp(yEG2bZCD~<8xBYv<4FT^;N|3 zYxe|-XGq3oX;$D83FGkCVWD(NXkdIciC7NFIwWD-woI-gIo3K)@jO?$P`9N+A;tOY z=MuW{Pp?q?yESsrysC1J`eo45$C@D-J-N?zV@SQeURV2DWA6390!lfqlo~y2#q+9G zhb)hZnxFo5{Q8ly@WrbnpEu2$A3jzGrkT~1P6gHHhs<%hL7v9%A2iRoLJ zf=!32Y+1j`)aLgKPuc6=(bB+=maue3Q|{xnNh%O^-Zs83t@U^!Vg1&=S;S({>H+wbZo@N#yzgfWRUXa(J#rm?4Q?cw4ke|~#yZT7qJ zKzR4;j>o7Cn6F#$lU;e; z4X)jYl-k{SKsM+mm1oOx4>0t7eX22RDq90OF7SYqNr$Bt)hYtEU-C_gZrpbhKpzJk z&R{#U#kaUbY_m$&g1sBOsD8U=aZ*0G0NTH3^BK*p=xTs*EC2R28*r{M*^nA_UiVXc z-wWfg*f5C=p3w==m)7d~M7YSVXBdA$YOS*?Baom!rjkid3x`sOP)C}GM1KGJt#xyOwK0rOhZcVYR| z6-RZAPSST?x%PMusaz&~6PK_1njyWjwV?J#qwIF!zOe(jm?F8a)_^l4ATU4CB>B#T>_LoMrp>IR-kx?nSNt`3%Yee6tlf2>Llb1a@uRQirTC63w(~yF zmla&1Z&LE6S@T&~w@OrQwDJ_2*p|K%$sPLtWCzw?AlrQERR9rNV$>8G#HcAW$Y#_O z8e}tR2GaLpIcf?GvKcjn1~F<14Pw+38XRpyP3%8p)D#-Ts3|mvQB!CTqo&Xx7Jf-W zgBUf11~F<14Pw+38l;Pw>M?_{LtWIw*de1P#txY@MeLAK6Jv*rnixA|)Wp~!qb9}< z88y}YrDnAaeWvu6u>R;O?mVrb5%JEK-h6^*O|r*G^5v!ddyqYsC;0Ml78OWKyk*QS z9Kwm;zH{SeS7i{7+-u9PhnysSvab@i*h}A=Ngc)c?8?N~k|<%JX#OWzsgotqqy zf@V)Gh*^`sHxF$ng6#iOLv;yqIFyU~20Ngc^KxeK?gYs#Bk`K7I6q;roxwl17b5lpfq`#M_!#i+3WIOAlhb`STA>{QkF1y3CrPeE!fA(!p{M zbx(pr_$$8$Qi#8Y^f;m`Pc<#cuN(@IPLyfEBW6|R!gfF((0*Y%pbu!jupQ6`v|rc` z=mXj>YzOoK?H9HK`hfNe+W~z*`-Sa*KA`==c0eD{eqlSH4`{!z9nc4~U)T=l1KKZa z2lN5$7q$cXfc6X90ewLGh3$Yop#8%30Q5nLzXp9!;;%s;l=w6B0qt*nb}s8v#Sh%d zI&iP9z1fG*R?te!ht)n+V)5hYH$iw^uRWTt*TlKsy0g-bd!Tt(EE>ucTZ}PhXtxq` zhIT74*Pz`>%r$7Y5_5)jD=}wiH`*-rEf}mU?F*m3$-fiOpx+44EI&kh+>>8w;q3YY z0az!+HUz5ryr4bq5u0m3m}N`cGh(0>-?Tg_zM+ZSyK$T@X_EZg7|*vj@*R#%sQjjV zBtPSkMaO<_n#>dOU();VYmEo;2SeVFR=cM~(uaV-WY7B)I~KQJeh*n~o0^>r;^6em zG&*)rRV{qWUQh4U51T&(Mup1n4~I0Z4ez1?$cA#=^H`61@^7x3xcCI`7gPCiS<`dt*k8?4SIty5cDa(HRO(cg0A)=NKHMG#xo?#Jd` z9ZRgX^Fwhj81bM!l{f7a2CbGIr*g99?t3`qLYa=Dm+?p<@T%Oy&o^@1xjC%Lehp;g3k` z(aV?8wT%PGhN#A+SnmZ%#A@5rJnvi#Jor9?j_3f1GUk(SwP5BLHN z$%b0*cCpYW;lv|)GFN?U=huEGxlNa2`}}23zUP$*)u~ob%fkXzQGX3R9LYmsGDs_a zLu+n1*qUtXxO|&*^w}t4vrcW9-*x#n!}NBhi?P}5T53SAFEa{0yw^gOS#e^cPg;1? zHhUMA+kVi3(d{q!$R%EDp>@)z0_2sCwa{|=dg5QVwNTdf8gcC_TDZ~aH}SL6T6o{2 ztPbmMIidyKYAa$7u7!+LXX0D=T8K<>CtkTn3l66|iLIlwFsxsS29I44tA)LdwZ!Gd zYvEja6mj5GEv(!;oY-uk7Cwy#BCeG!_*zTif}L8p5>%JC-9a&4s@f7;oYTUWKIX(1 zZ)zdIswe=p>ORuKz~|eER|p%-YREQR+oy$T?;WWAD#1(II1(> z)N!#P4nClTS@Z0Od)?83aYSJO+U#;)3;ov}C%*Ae3lpC0B+hv%Vq114amp(Z+sb2z zF9@4&46jdoRP=kN2ovJ`kK#SfEsd$K4aFGfH~3q9Y=5jMum5>sL*x=-Joq^n1RzHU z8-D$|LdRw=PX_;W=XF@#O)%`2*<-yHR&Q)V<*#zJP^wr{;<%;BP`>j8Vq?L*qh+o> zTMKi%LNwUUvxVX}69-+SI?IQNK8;GF@&M5lm zSxRo_U78l+dWTc_8Lfy_Q4H~zXf1r)Hjenyl4K}0R<>cD;71E&J}AcUh)HFsPMED0 zUZ2a{F#|GrC!8$#P^k5Vr3tLQ?;>B*{_{*k|FTJB^}y4RPYw_%fzj&im|l&6ZPZ7b>g@4x}KqOo3v!8u=y(S zaS{K4;d1=n-Asl#F*+)5e>xdXuRTCKA}<-9{5np&ZACJ4?;-a)+Fw(#fAR}0Tp{JZZtvmtF#z<@h`2YymN%eH;S@*OU zw=4uQw}=)}T^>fqY566Rk}} z3)V=-=0y_kTlPiM%}V};NbU3Qn8yHlEvs{NFpP_qe{=ESq(rcL=1gs>ZBw&l`F+f+ z{YbKNYvLq#d_Il7l)qxZuWau`{PBJ-K7Wugaq5EvZne#i+FWPWpO4%ve{;k%^u6@9 zo@|4U>)L`%@8t6VgHQRaa!q;t^{nIsL(T;PwjVko3c^xWFyvWp$3X2v;s41_-AgYh zVI-fQMCRs+jY9I8dv0-OU8fv5p6fS$k+vP_N4C8PZ_8sVS0nE06UUP)$-kNRt(ca- zaM(fde4fboPvcr-gWK*!(zc$_#BrZ2*z{gW#DmZOU}cy0CEnC-7=+jtlAX^cB|vHz zBRkc$srmkcz3fak`S<9+1BaQ_0E|Z0j_lI{BxfA?NsfI##ze z4%!E${0BS5IXj-aV;P8Zc|50=#Q8jkb9_A4m&AEK;I)@>{Q}RO&AIEAr_!>nzJUM5 z|3_9`qX8a=$K$cs9=3~Zq7LezmbgaHiE9Kdt`V5HM$n0C1TL--nCg0v^&9wgZ--PZ zuNa=FQL#={2d^*m$4aU;C6yNWq}V_{DYlVM`s+%SFI?p#SNYCWG2yCMaa9aC`h<4i zwGaA)_TjY;UgPSo6VWI1NBE^vu|`#gsg7l;Ht`zkPk*V|vj})b{c+OU8`f~Ue_K8| zvAwh}usrO^?ZT^f^OjEhDhYQT7;lu9D!p%H!_7X_;?FJDNwp2#_}DE~c$t-Fq`fP= z`TPqdcwz5PQmF^N+;ZbRDcZFx-zNF+S&@6C-AC;BmAW4M=(Bm!vMF_W*%1zWt-&Cv z@ON`QZAE2XRLxOpv8OwqYj4D_^}eNB+jS7XaPF@3yvhV!QQ{~bcx$V4reQH%lNWLP zzI~FkC()sxba)c~*0-FrZKJ{7%XhSVeR~7l=Z)?1JJ-?jmIfIbesoU3f#C@}t7;?G z-QG`ka(OiOYdoJF^k1iY@+Fk#o;$)4?Tn-WyZZ9s6W_C4!$7*=*pU}=C=H?e$4PBg z0=KMC9WFl2lq{##=Kb7VVQ!m~l3(v?+~2_)4t{zkt(aiUFCFuR-D6Ah*`*#z;fB6& z(cYH#-mR0aUiE;3FTHrY!wP9#GiOl8Jf`bV-ZSX1?&kW-EMa>D?|f{KF0e%wThV_k zZ};M2!T6%Vtaa^V?%3yPe#@!vHT{2R`N>a1cdu^m9`N`;GLN3NBEQ48W4d;e;(7R| zO$8~zouv9hqIl@CR=NXgmPsGehx6|Hw(EM`KPB~d4d%(c&7~8~zDSeix94|qnn|HW zWpFIen82J;uE#0YlF!w2kF@ME4ryR!o z6~0prqZVG@E8`r;Dk$TesqTj`F}6V&=Nc93RCO>%^v6o7HgTTNYhkYGZNMDV+lINR zw;6L*?+aJ?h&itJ9djS=U0_UbPQZH?7%O!Q_4h7tUee#Yz&n697an^}@-Z#g20QB>KllWfQ(4qioVOS|X_E~@M+wetatbHNXDH{$W(`M@G zT-`18IUNU`+zfT&KP5}|3zHzi#H`?MpAyn8r z+4h$d_p<}bFlftXXP4*p{nOa%vjO~P%Nl&1OE$|3bLTG)x$+jjV%L4GRhEaj@Q&f<7x$~ueVnPHwP#Y7>936-Gpscg{dvW@B;`)y{ zs=pVfACq`54%b=zeLq}haXf>v&gvQ0S$!RSF5t1a&g$F5br$;$we&ef_XCw&L)-K@ zNcRtw+(cjWIg38(a~XZt=QzehpZg5+R24&9XUR8Zoy9psqpY)dKQ;jGXDV|}17)4X zxd<88S$!S-+=a*DI;(G!d_vzahALecW7r04-*sVj8!ez&c72H1I*pmHu!Y#SPEfJ> zHdbS_JM~|vkyJeggb|T z`-cb2I&-lm@#F}or;}JGU0qGB%xLIZbw1nSwK*U@EglwYJF&A13mcy6m<*EhGmY<@ z!Upx`X<^WwP;uV7fZkb~R(opBf%}gdHmH*f2Ls>fuH7vP_hZv-1{f8{)&GG`3(hQOByE z_2A}Dyx^IqxDIILEPjVmJg03tjvXno=1zyjZ!kS?$@U&8%WDnp4c)>jv%#(gJaNKc zu(^3rQz7-HbmUz)oF6_(^JB^mX<FkRHa2zr|AQI|IX5w11;A8)W zPD65Z*59dlV_%U&A;eus8sX%W$o`Pg5xyXyir z#d8GgNL``Xm$aYxy$^v7L+)z6x!wN{V@8Y}Ny!UZyKoJ|d>46v=f;$?$~iOU1+88B z92ftkH4O7zIsc?N0oN}5T!CvBu3^}w(4jR9$11Kfn4frFt(-&B*v7R>$qQVU@%)o= zLB+T(>+9gUjOVVDQ>r%6C%u;b9GG%bWgF%)DPab4Ee!8uTWEK{|~R9ZNH{^>iB z>k{TX=DWys33DFvUF5oiIgj}+a$Ull$9xyLE@94NzKdMvnDdzLBG)@caiHl%z4ark?T6ldCYf_>jjwenC~Lj z^D*Z!-$kzP#+=7|7rCB~Igj}+a=id^9`jw~x(;(5^Ihb+4s#y!UF5nBa~|_uJx+8l z-1)V<0FL*6{)Itbo;R;GOo_6lI;~UK6(4y z4+F5y>HG2U^mc28d}u~Euqk_p*9P=~LDfnCmWL%ZhJmx3iCbFOL5b?ki4D$tXQgiR zC4N_F13O_%zakD?9|sX1u8)t18`sB8#P&}-Ut9#Z8tcl@=E0$j zp+}Z8@rMAcT*8cG3oHy~g7j+@O zv@h}IEk3ZPr5|yxXm6+x>rZUj)Dw@!H1q;lxTW;-1qQLVGU{;$^Ee(ENpL|Ei-5)@Qm=xmrs- zhSl*`_lvr})cvULUvikvbwL0I`@mv+)$#t{kejJ$V%}WN#{dmLCm%qFu_oH^DA5ZEj z_u~cQ`h3_exgRUF5#N1`mHRO!NW;6-bEm$m2ftut~iXihfaTW`s{Wmpp))mg5Svo(-kb(PzJ?8e-* zznmAbZ5#0tuVk$q*^GBPCfl%%2k;t2vTePWHQ=4a@2X;+nz!-irmN+=_&L-WOQ`Jfam@2h*#j5`X)c0PouR5>M@&1ZxhKC$C~xCRTwkmM$2NNqmlXHA zSG<(9CW$tmSCQMC+b9VR&yck|J0*eXQQ3ypJ(A#ab(tNr65)9*2WscQu0;3{XGc6@ zdm?Nsk~w2fBKWtGStERm50-sg;gkqBe|u8>N?j5m_De0|C$WiOnC(J*Wkw?08SF$H zmLuA^A^XxPFA+{JmD{{oV+@=cnm~1eO2xs6rxS^fwT*+bW)q0#y2pXrcbUz^^W_vD zCmL67XT)>ob7hDpUlPwi9~UQHT&NYljsBIM^;Eblo>N~hM&*}JY9Z~F1#!A)=VpW> z@uQtuh_p4+Zr@^jmr;#g^je5~iJvCt+# z9zSPS#=zd&as(HNat`&VJbPdQ zx`i1K-r+#O5DDp|aIU;>0PTaLM2_amyN^u=B|o z;?G;cz+|1=PW!E4FfvQ#JDbAb*;bjoMvj2bj)$mz=Gzf4En`2igLqfmqrHx}`u=c8 zO507`;MyqYdqDR0!14$v|79JOH!6yR4ynp`^NNPq(Tl0PQ@1!cenOtB&-q2e!FF=F z*Q_Y886@|S>#8WQEhaNR5Cvykm(j6vKSn|6=SztFZ-v6F39`SQMPVRrZcurQ*+_Wk zBHPTHg@dI*K9v`K90e)jy#ibxhn|RltDm!pvmPhG(9~kYML&}ubiz*>hf}L1!@7p@ z_{`%;aI>Q^)rqQ>1e0b}Azt4s333eOxjkfb5|rszmdfWYPJ*?P8S(i`B9~XxAZ}A_ z6m-eUBQ}T~1>qOvu~DY%Xb4*+kDrt4M#Gez@;JBd6#@Clxm15la3rLx%p@NEJqns0 zk>g-6V=T;DEzfl$KgC1IUahE3{)q(0HuWby?T`p@u3p6UBNL&|ELY-iv97(IC9ee? z-9$eQlx^#HEgZ~D<^FZ)8v#xOWgGhUiGZgOGQahYfGFSf)Xsikv!vMk_<{IVM5-L; z(>Idf=?6KN51mhhi05(~ilP%>WkaB2hmDMd7sICzKkq^UG;O@^zICFm$m7g9T2_+A%A&xf`r|e35w;&JTf^M2EDpY{r)aE89dw{5Z}`zL+3Xyh<8>=2Hg&MJm|h8!PL{gsJzUx zB)C{l9zSk(lAzZ#+26)jlVIOKx&8P+u~#jAA=S4Oyf#zjaz$}4pr)4Wnf@jL?2h;n zuSz1*c@Kk27K*B}T5Z zdtWTnsvx&{dTT7y(aPL^XDoCXEOXF?SV+#2x%Ry{*sPI#^jsVV&c{{q;90_5IrM)i|y5@5DZbK)yo#)4(T0mQ9J#6wKqKExUR@!+|% z2l1sr@ldgUSK_te+`hGPZol%f`0jmC8!A8YIUc;3JkLa$CP3?(EvVeAaso`cEo<4q zSg`prjLNUSjsx#r^0|7eIWcg(uRNCeh;yVUdRx>@JKA^UdUsk&@K+5n#kkFa#9?0X(RXb`9(1>xQ?v#sB#=UT`Jef zz8njmefQn({lB$c>nwk# ztm*2muCDHx-7}pvERZD!h`F^t&ew7!F@KHg;?G(&JV$otW%{v77cUV19TLH=)n7?` z%{PKQ7$DeJ6~MY5J4y1+djgnd>T%*(^8%Umgu}!W9D~@I^aI3GF9k7=b_U|NdxKfx zW|7;Q?Z>ss=5oYCW82zg6SwK%&yvfCb~(lQv$DO;l6>M%f7a>EDWUHez$P-mXBzpjjTJ7D zeEw)Z*0YHyGh@0RTRLBqS!SLeYzh@@*zX75HVR+eyzK|W$_gG($RG0hou_g-u8V+k zuf*Ju-YgU7=IzK*DZe%PAuO?r#>nI5PmotQNd= zlOJ68D*SMvoIlJiBm5A1!5>C~h_|EP{h{Y);qwS>03;=ypz=?x3V;${MLB!l#DLpS zF=nR($3Str$)t1evl>*j#XR+^mj*)W)+hO@#TtMEwTV}p(?I3cHHbZ)X`tugYQ#~N zTIgJ}3UTvVT9`Jw0`UY%3!cZz5+CfPg}WC^6K@)xsbE4co44cvbwa;eig4g4Kdi^|EGg=cteb0TgWrh(&)>Jr;vTUxXc zZF%Obf#weykv#m18upbF?d?=u4X;{={MNpv8mymoB%SYj<6y(G5yY2^#Y51cA;hQK z#6zUD$g67u<6-TYz9c`M5f7EN_aLr!J09{zioCl1XFNPP(S_tkimRbZSZCr>mDMmw zC+uGB5(m&*|VCkXwNDA;>XK$tlGB*Tz7H$rFjK=10M-@xsU`FsKcRSQSk1wsN3dsQ7|S~)H!!i z6xeu)@@Eu^g{&tUx;EZg1CG_j9QOtHcv_qm`k!}T+rtGPxful&gGHHbY@=ayEn#a% z$7l$jEZW-%>vlax)UERUXz+Iy?X9nhfoXct-b!m?Aak~8@B1}T;FKrIpYk{gPB@D4 zb#fHQjfGr|^%;Cl@Wrdq5E3rR3_BSOmo5qJekK~qgWwbAqQNp<@FA;MSm!GGargch zn0jCWwf9SG3|PxzE_>7_1`dxFbt_&u1{O>aKL7GE8WvxeM*29f!AIk~RxwizR~_6% zIpG>`DJbH+&>#)CPN_$7!%;1COe#ohcSH+OX9d5G(7}$6cWAw;>7xVtK~IUpU6I?o zC9YId2l0)*5f^)|g?!^0_~K11bSPs@WoplBVM%BK;?^g$;NL@(KTD;Dsk0L4+V{wN zM+iPsQU}emzL0$M9WAUlY(>{T|A4=DSXdAz?9hVi>O#ani((EbUYWRfOD$-l%MquH z*21BqB?ZsX!nI1pi1&g9nr;*Mfej9ZMad%nUz71Smjz-@Od1^m2b=CB{a-er@cr~Q z;_3%O;b(R_@%oElFycfi@!`o4@Hs=w1=D-SL7%MgBtLjO9-4pfB)+g-4X0gN6Q>uz za~`cl40q_QfufEg=d4|%foIoilTNX2!Qk>-)U9yAU|88Di{$qg;5$IsTZk)93x(Ac zwh~_+9SXWjf^$!WfOCoMBwvj4i_}ESFFnxz_MXE3&oVU-{8r?~^iFE{_Ol)7r(TYM zANgXf-ZUc$(iez$o>VmwKIe)1^i3lpz+$pkhg|dyhk@%-=-Pfa!r(lo*(aoVy-BZ+mN>l{gDlE$BJ0$|N>B5Iw*GItl95G)fUyFbqsmrOH zeHA0&L$M^{r91rK*NF?n`8Y>cJ9CEk);gRMA0H?7xflpOtq&1*C>snDzKc26=S&C; zEF}E1cVifM?cGQ^OJe;X=W;f2tDb(aaJE=`G;#FbD z(ZvEVr-}Kr?OA_la_%(AH%0h^liyk5Cq@0iyUlsxt0{hSmtfPZ7l;qRqq&G+kQzPXorinO5>y;2pB1oywmhxfQ-Gw7Z-=XB$pk;l^TaZ z$8np93;Y!h)l=3Hf5SauyDWuoceIKD-$apH?1qOyX&=#dSzE)P>U`m!8I{9fz4HdT zw*KUBxN<<0v#(GDv`Jk}@-gQl;P_2ZX6)`r=vQ(H$rnwHf~Gq~K3C6;hQG8kNbX!E z7RqF*i3hrCU}UR?#7*XD;q1$z#6>N1@bRm7HfS?U2Pd7xy}3`l5V-3to>we?5dtfQ zi?!2VYeS*3TEy7bMq%*T*!HacVQ^)>Xx9$^F!)wk@W3h|a5+Pi6LUKlGQNoMvMe_k z*6$T;bp_8=OSGr@99^Y>DAZHSxh~dI)>*MZBwWRS(U+ z{v^)6sE6cMHl)+?1pc;Ou@dpMy?R&~--y_KvmV$A@%w`HT0PY4DSmf=)p|I3yBFz< zP0>TtU{B)W_}$LHzuFPs*{O$_4aDye@{bs}Fi*_yBQ!DKo-&ErRr{A3-Y#|{wjZSh zueT+Mn_wH07K=81@2Z7DBm{^$wj^XzKG`Iy_iUe_eH zkI}&0HFbz{@XWwFzeKDi;r#f>_`62+W?J}kRLqfnrZ8}mlg z&29(2V{uuOzwd|!uDFT$^dhdqk1rPd=#U29j}&|l+c;;cXye018o2Dzi0WhOt%0?* z>k+5wHSqDWGqG-|2C6I+^PoMp<-4^b$r;YwH4UOn7uQ&L(?6c%>#N4VsIaNTv%O;= zYSCokB##(4Ia%biZ4Ki=({~WbeL~}*=(N7XhV}7q>93x|N3-G~=cE_0v@;$CdW+aA zwK5)VRqaLcXT#&+XjVVsjb(71-*E`>lrwRV>ouJC`sz3+Fklq1LsA@soe{iqQyh%l zJCfvEQ2$3apf{Y2xz|!XNcP?oKXZ{IE)6B-@=->4Eb^h3LOu$)w2jb@JeHPq z4BvO<^KZ*1e`V$1yIY*QW_o4ad@HzlK#{E7`0f^$pDwacmE$Q`ZZ=c3bcEnLSL0Q` z;stw*9<6$tAozIa&Z==61=l&|tg^=U(|9?LLJF$fFA08@e$XTHq2S@o{XP2NySQBE zR^!ChULOUQsQi9ku92^e@HecQDdZh9IvH*o%P+H}nn8C|$UXA!W=*~$*yf-*s|&s( z%FDFuC+(MwH`ggVG)@(+5j<DbJy=qG|BRu?ol82e&KxkiSn`-FV$kA8+hD+JHo6K$~6 z3x0KFhGE=D!Dmj?f{V9tuMhg+(WhEqxl3@tMYW-ptKh*&P7v6;9qBB#t^)y;+7ery ztP3q?F=E}_df@uEia6MAW6X#TJ22bwcUL3UBtYHh- zbF2xmb(2=mFrzVX%WAD*Q))wEr>7q9Wp{mI?Q{t`ymTS<_{89A&$`5g8@7e}FT|d% zzy|HW>xdJ{8+~X8?{C*8zOQW$V_FHmfcrPB?$jcA@muZT@hQP=Hn)cj)@E z5&U^kI|%D8%51x>EkyPcwwj)913i7}P&wyi2K(oV`h@&Y!HH@3Eh%iH>T7E_zOMms zu|ut3Uq#Wz{$pBz>pao+9}SwpfwRIVlk2#_{By!ryK1?@+(Rwt+LQGf!R$5e#GN}g zfPJGqh>J|D2P-Wl;^q(Q!q*7VFNI?2K-P{nB%j#U8CD(?eRsQ~6J#ZdK5aL>HhgX^ z`Z~REZLm%iJRkRb+2GzUUVk1V7%Rj)Mle>0d5mDJ5L1jK3IFgI!B`F^>_96=EJE7%Rj)Mle>0d5mDJ z5c3$pSRv*yg0Vu(V+3P`n8ygl3Neonj1^)YBN!{hJVr29hYF@mu| z%wq&&g_y?(#tJcy5sVdL9wQhl#5_hYR)~3wV5|`H7{OQ}<}re?Ld;_XV}+Q<2*wIA zj}eR&Vjd$HE5tlTFjk0pj9{z?9gGo-6(PqM!B`>YF@mu|%wq&&g_y?(#tQMly)i8D z`~-=|Oh3Ok=IAhvxH$e^Q0Gx+;D zcn$HEn>uFOQYOB1N5|gOH4r~}s$=yGdxR8Uv?Zkyk>RGhkX5zKEIyOfmbavd= zu{t;Rlf3jZ9sAH<$VX;Hu(`dHsSYa&Mza?k<`DmKh-Fnfsfn-I;J1q#4JH1*NzIC7 zyAyADs9`%Cs}t8LUI<{-V2eOqoQ^&gch;|(T9SbOQoaDtAepArx8tHd! z=g)q1Jx9D=AIKh_IZT|B6v8%^*g<^8A&hO^wVC*!FYa^jP9ffsIE>xi@q@UF<0uw$ z;SKTD5o6iV`VWcs-yX*%m$^gi)Mzl99Z`t-tEt6Mrq>l9?s&nQ^@^}0ZXE5&TK}j- zY#85*9ZV`q?7JSnQ5RdB`0c#`EVOJ<;@b(H?DTb^pEcE!EqW?AU+u}J<_Z2g!jmn? z7kneoldUOSnXXM9@5vUI5L{%8C+kyIaPv`~OfE0D1#*^=9Z{#TQOC~Lll>|#bOr@^ zvM+@MhlF{unO1_2wCTaFEv!JchW7Mg&2CmCHmr?edtc8ZpH%G<$$aiEBQBR4&RUOK zL;NN+jAa`(5^IA(*{YRWi4WfjW&?lhCa&)m#1@V?Ks+XQJX?`^ow)Dev8+wvj;k zzSXhsIlG8EzSOb!) zq2EY84&U9GoBxJb+gZmh40=v%KM2R^smH{zqjCSz>IcMEf^=-!_PfO2!*p!vlpNyO zf%u+K$$P}=#yX~*_?9^CtA-VOUxn%u)K$w8lgkjVn4)FftJ@LZ+^S`H^+n$6_E5{t z6tyCGaG-{@SW}mHWoZrja@>`;!X7nywyG8JtS)Lc^;$dPb?4%lXP_r>wPE-UQ%*nP zoC@)*{+GeTB^RO2onFKXFb|)&A@Z=+SIuPBhUDiCsoC9KEs5VY*043D8xe0`j(ei& z*Cx)g(y})eqFteOIu^F{E4B9r?$^3@s{rZbU=FcIR`r$m zHjY2uPrN)|kK`rsp2=r<72?6~@EcT%+7pj@sb@=~XA=iC!1p97uck7a^}xN6kqe09 z@Y@|%oyE61^mFyBK=pAXPr>^S&qHmAw;soRl0PaD&&K-XU%X3Y&cJnjp`w|@nj^97 zeZesDn}qM~lpWQYI0X0I)$3A_xc$mlmK7()-M9mBY?#vsk{6y4$2NZ%O?*{~V=g~^ ziRZkIWu?0Z6L-vrWvBau6F;0B%j}&+PEZHNvN>y_N!}tTmhD(9xWQa48){pOffos+^X5|&E4X#_ew`7`VyFH^Y;_a&w+x+5oc9y=DfOL3 ze5P`AkI#9iBk zvdJ?uh?~|4XSvtb6Q4UB!CJgqPHflFpM|N;5x>{_vm&l%iNCk^XI|}ue3ESdv)nFh zy$SMXohJ*OHC>|Eh+Ydwzrp8l)~4thV%4co7Q8B*`1Z|UW^K8LxVb8b*)|gM*S*gH z?7_feB=@pav+}1!uK4*jjyW4d8wcd!JIl|5NXHV_NQVAu;$4~;mbzvVaf~6F$u7d5 zo=c;dyEKF3Jwl?{DDRoXA1X()Pg`dbzs`(e1ty5Oc;^f)TRKa`Pshnx_M?Lx=`_Q= zG@TZUeDYAEVUsJ=A^HAKYF5spDe>VXHG5k@#LVO#YSzG8#FBkIHM`oRBk3H!sAbEF zihR{51NZzm7AE=EMOyZ$gUDSICTVfL5O$x$p-yiROXW0Lwzst4Ztt{gN?!}Q);SmR ze1s)&-W@F~pDFU&=zJ}6to4(|xTc7X4O}MXptr{`KBL6=z1BRQ#bphoYm-yr*_M?( zi4Rv$v;F(UxH#gDdlBoGBl&5p!}wpKZuL{NY{>K?BtN<}obA}XmiU)<1lzo7CGn(h z5$xmXB;skqBiY!l%ZT^vk7Ud9788Fe7R4InEF|vGCyJ$)5b?7hF^aWsAjZz7`%x@h znk)33quHr`qVKj`j$zaD^(22*9CJ>+K;j=`LRdtDoy5+6hp@TZw-YxE31uS|i*?k` zz%W*zcpAya1%w;sd;Vdzx zmZycV3;Ttwhf+NI=p=kws!kkRKGC0Sg*wMFo44`A_P3+i$?jsjud5r)igp$4I(I3G zRbDCDYnOm~lY)gG26#p>eGB2AK}Dn3<6PmlC5s}N^M@r=W}bT_8|0Qqy!k-{dpA;y zYgr3xcJ)n3;yI35=CQH@@mU8o8~0Yka8`Oe ztM=6K`oB!YbVnKKI8xLLc3>kbGcWJR2r^J@LA<2v+n!GI87aQS9DW;U8Dr zXVqUP{8_PREX&!VA)Oc7d$NqhIiDy^s!O9&KYyQ*cd$8CG z<*EGnU%lAOJRxsceF$swt{}->pABGJ3WuN3TeXflh&SGAF zrShw+_hIu2T9A(AgP|otxYA0+D2VbW-pJ73f}O*fK_Z}pyZ zYT8G#o{vPF9DWtf3Um;${rFfIvn{rfbiA*JvI4!+iO2K~VRsjaetCg=z4mVwdAmZc zKO55LH0f-`HM7HZv1V?3M92PKew1S4$P68;m@Mu?i?qe{d4-oGFM@kn16zuC2*$bl zu8qhob}uw+)wpU@W|Nv4R%2{q;_R34tZ&6`#DP9>tofU9#AlQ6{gJGRLjEj@L18g= zM!eIp9#Nt`&IR@CZ@;Z%ckd5eZ%1SjefF`oS&^_a~(wvSMAiWq+K=1Zdo~=d1ZJJ&%);qq18m)PJ3wB0*i(uceT>6e0MkE z2Y1vgVoY=5+>L5hH`kqbLV}uodoSjZ;d9h1xtWUO5lhu<*DxWsm(?t{YAceveO0pu z1;iY5Q>DRoVH%J;3E#(Qw?)iTm6mCk@08jkKYdJt-+^!-j=QB{RrNzOK^pT{$u$3By741O$Ax#7No#NVf z+|!~xAo8kRq7FV46ZZlG@jFS!9ad8Obbh1*_iy`%gP!VO*Aww9sN*{wT+oTwduXW# z|797Z<604U@J3=6)T#fM&^h#62MrI3ds29-gB9sQo?{;gX?MlA_8Sll-R#6Vv(3m@ za32subso_?9vqH}xykB`8nRv)`|G;~qV`lForF{^I5>*={Ug4Ie&dF?Z{08(-&;R; zmFnYt6x--7#(2rAzTmf3 zU^rCsTuZzxBm(+25bKA$(ZeD4iO75BZ;pa`6<(3fHJfoT{;zw)KjX*4hPa!=6&;2^ z!b_1?S3MdEwpJoH#-;i|l%>d-+kbk&+t(rwciY<=aBy`UVPHNeM0&Vj2zcQme7m_xIP6Ih^J$w^q0o5F7ShRj z8w_3N?IwP54fnLvI7A$O%@i&Y{R&z%} zD+@8#oF6nCvWkBrd3S3cs9se(>kC{q1S0B+{&MU-5VAvTsa^GF_l2buOA=pM84IDI z5p?Z_z*soHQrr(_`^7^18NvJYv7qsfBAp!@W8v+&aN?YovEVvBnAn%$@17rgi5pJD z?YZ2M#TFQ_R1atcB;Ub|g=TP(#o_ zM*RLYjs-8FlVOG5A?_i@Z>w)Q=s!?AAGXZX!Il|2shp-bW`EuhV>XNF;nbRCBwu`A z3$|^os7yIf2MevlbDom-b&ydii*)AL=^$sGcm~p=nGOcHi?P|en+_^263-=G579xM zm3XGqYn%=WT^7%#&WGxt^G)%rqivK9CNC1tI_jeQa1rsWV;h!PzlJFDmX#JR{;W*( z@$apL)dxxwkDH~1gG0o<(wd#PpLRkalCOBGg_tQ~PPfGU0NYbUF7>Xafn}G(Jgz>Z zh8G6$%*U&{8m6vnN7wGY5f4KbbSHiikH4GCeTdzy;^EWep~O8W#6#hMLcZ!tJalT% zmE_ZgsG;EKw#3pNHLOY&^P@BFtzGh=5y{6d(1243C*nR@bNv0g2A z9QQ?pi5$KH_XTC%D@yvsumX(ABhp{iMF+);iRXd!8|dKdh<79}+)oF6UWn&Z z?M~?+BIPj2Lz?She{3>wl{u9FfAewD;nwoFh%@=viI_#|s#=6D`f43*$ekDEIAGZ7~2aPiPiJdORf~t%dr_~q6LPDcRlGhj;3*Rcl z5D)N-g#qhhiNAG^g^HU6Pws;IYku=+^d`#q*tAY?^wjc$z(B3OW4Lils1s$V^p!Q zWnmm~+Vc|q#*XPmj`q4Dv7DuCD`g`He&MTwAs+jQkv+mKbbl@z~aeER4#q8%2 z|HOT^=SqnDb7Z;}Rvi{xb)*&&i-~77@sl<1FxHv$pWwbA%c)}ReQ%u_{QI>g`Co(7 zFmATU8>^eCp_8{**Il`+h4yE}xL%ow`;l%IBK<2%wJ`miE%Di@TB!d+*iF`Iq1aO~ zFE~!n!jYANt#L2$tEv{H|NWU3O1oPUKfbGl^-&_vZ^1o>?=Fb@=;xS=MzwSeE%-SONGcN z*jjHs>D1UC1=l-^v6EyG4Hw4GA$i9R(Xeoi=(~nbV_?8NF-B%riGxA|0!YU-I0TOV z*g?D#LZDLj?Zi`Og~FAuVokDkZWzS%*hKP9<3eDq@tMr<@gZ=f#!iwK_YZ+}r3EKt zgoB*9mgKP>VX&yiW?~nYP)M>9V`@QC2(&IG>^5l;54k&qZ}Y0gK{H9z?Qw-zhpiA>LrNXac|-JOO=QxjMhM>C>P@1Icj)3MBD?;)~VrMh(z+Z zHfq?WZ7weLp2-u8LK3Gyg#p8Se9(Pa#Dx5y>FJ#Z}i==qSiccLfE zIxBv&9^A(ZT(63IftRtKkoZN&dxd+#2utx>bAF&F1RHXOt4WXuKz^H2w}g#NQL%78UZY_)YFT_-#{uuhBQc6AD`h_K)*~_n$=_ z^b_zq#;*lW`^yvVJ`}t#!4vA;5bWbR7%W1?@BZ?w{%|}+{Ej>`y$=lV5x*lZ()0ws z2jX7l?($(!GhO&C=At(wgb087Sq+8j@nX-wf;PUOtACAr6~1*W)O~fIxWdIzFukSl z?b*X4pxsO1^V)_8IN~YB*Q-h4(CN@R(*N2w49+c2Bi=YX6nZ@0N*r=A807kUgbu#1 zcdq?mV%s79@cGVJV#jAX=+sNxzt`EXgMs=JwEnrO!#(8ZZxSDJ!!_GFv6lXH1IK9t zYr3`u#{cC8BL0tG#J#N9_9PFq*1$k}F;6`?91q(hFOs)#j)M{j{>171W1z~3$;1tp zM8S{_VjlO))q!1ts87ld9ZZcE&$vE+&_Uff;=W_)D;>lg6Za{ZSpO&0g}zfWJ*@sE z){{-~*~J$N@$908K@0gSZOE1_zH|5XTy5gkGveXI-@S>qI>kYyL{Yc!rW!bKup!C& ze#JfNR!xaFTvkJ=#x02NtW-nc17iN&g?raKUKh`Q>?WxpyS5nPS7xbU$N(V^#CMC1 zR(7Xr^Ize6aQULlAU6%Pxgl(w3e-UIvbv;`K34X)7 zss>&~33kKx2ctXIAe}Pl8u&25k+=`uztmV!hxnli?;VWK){?Q0oU4dFQr%U<^iCp2 zU6R!>!>$$SOB>WM(?PT`agG`;HWqE!z8HNn#e;O*cB)~1j?n*pUk!JQh;rJO(ZJBX zuB2mVr-AX&4T#@j8!IdpZETyMfw1hQr~4a{_$~^_K{~F|CyWG6na@D`gmSMsR8;Tf@c+f_2r8XQe(6+*uCHYGB;E zyDw_){&63L{PGBB{WMRo#fnKD8TflS&qbefoZ0V6_GKc@=LIyPD58Z7wI&N-?Vg9L}4TdLa8R`C3^WYtGwdoPV#p=#1p$SbW$ zQoSa>sG?>2hXjcCCgwvAMUEfCB`GF8YH!7dXjsurFQJbvFT zkI)>!SEY#_w~cLF^w+%BV~l>7xF&c1Fryzn=Pk*4^jzq>JD<-gabK|hhLs`Vvfzss z)*CKY7d)cJN<*%z;H1h64AwmbpRGUH5R7{TxIdGok2ToL6P&Y)85$YuIkQ7eL&6~; zk65gOHZ?CBxW4Zm+$%oUmH5{pd^XZi$UAJ(Lob(3B)3G)(F-oIPzT{RgwEatI#7KO zd>}^;?j3Jt@iMO?H@YCsOPYfBr)A5wp?lJDAMtzhEw<7*J7179-PgHu{qe{hdd{VD zc|!5tcHa0>RL=0XdXUQuBwmR3wiQZ=Gge;Z>Y-cKI+9;{tOsqSUBtB?>cMW&5#mR8 z^)UAOWnwM9>(RWZGv)BbhxKqXwFa?tN)LIP%MmZQpodwZw!|Z^=wYp7N!;=#)?xl@ z4_?pj4{$Gi=uu+n1>P6WSw!3p%bz?}l>ahB51ZahqH7~U@xDG?@Ho7eZ*oW6%NNIb zE-WI-Igam@oOtqs%E>#Shv3^4=-S8o^bq@|0r3aCH$S|&ohUO|57&whATB=--x-M> zOFU$X9?Dk_BVHAyhpsgy5bq7sLxJL=4kxjmQ95r)E+e z9GByBo`8!~erl2qek2GE#PeOMTriN%B#iTE)kJ*eBD>~`I;=_1!-cHTREH1a^>FFP zG~xjPdI)!(O56f{*r}iJ;p>TdsP}gS$q(YS$Crs~?NNSxN+ij@MCifez0fa%<)}J~ za+abWW;7OdhcD4V^ew?XYUrUQTW{cguJ53S=w~U!bI;;CM^8#nnVVPWpml0C$v+~` zN)YUU<8hr^C(_CA$7egy!d7mu9^M5_Cb?C#9)8@>6Cc9ZsFD#%d~pfJbGkQi(FuCU zNQol$!&n`dDdOb(P(8dEH`~DLwhH4Xsj`q~AulK<`1&t=u9dNkbkfncJ4*^b&ra3> z`z7jGY@-fZ#-Ae{_X9f6-#}%#N`nLo6Vd62NQyzWpK1#&KL*&&zg#Yg!&_m~^;w-bZ$gE3k6>m!gjIrrqd7?WueX4AD( zF&`ebxkcm9{~g3DxKso~dWQ zmgL_a>e*gb;h$(+3)q*tNOI*lbTf~jj=eqgW5LsSe%!#a#BSMo_N+q@;^$ZNEV!Ws zaoSDX7nkzVgZFzEEWi7m!^HkC^la9^g~ZA;?^Z_q<19So*?iM+4j*7VLvRR|V>eNh z(*eIv*yH&(DktqEo-wzvJlVarU(YgT)+csK*Rvtz+Y-N7foIiq?nitj0l#55aWwJ3 zX?ix&B80d=ES~9hQ%l?_63-MnE#i6q0sK~>Lu~_ZOG{jTWwtF%-0r%boxS`ii_5Fy z+F{G>bHu^u+pBX|6Zb;@`!pOxd;-@URT`b7KKg+DwRCzG&A&6TziLJm_u%Cy&+Ss4 z=cPPjOL_K|@=Pw}SzXFAyp(5qDbM_}N4uu8z<#0sO=pDt>1;LS*=LvW{4&#-Xv(wF zMkvluQ=YA+Jaes2nEv-!Y|1m*PK5sB?6zw2|8Y*={E2v8o1Mt>6R=+zZx#KrH9*fc z{SeR6SNP(&c*gVlo?{(M=lae=fH!tV1ZjKhy2&nHgOv%X)#DSnh^^C{2lO1?_5R4NhQH7F|P zCMgs5RQEhh@=w{g52X4*V&yq{QS)>x=B3D8T`>+#XYDD^;8UK>r#$12p95IJcn+Y- zAIE9Bn7>wHzl^9N=9kwljoxDEY(_`C3f^2|ZyS%if! z#!Tnpso@{zKhD1^h-+}uxp>O+^7uJ=hmGgxDbLsA z=kC=op1bFcc1`E;DZf{&Waambm2&0xkpCoCeoOgJI?C@bD{U#uSC*sHSAN@BssAUP zx_+NGn!XYJpD9zRul(-xf2RC@rT_aI>B>6)JLUh@$9n$$j{1K_AN}zA`|5wHgR)Ge zzVh4M*v8*=Q0ibm{{9~OpUP3{{OMYyEv3GaXSE&&wl@B$%kSKkuY8FB_A@3mw&HR* ze7Oc3MomcVQ`bqZf$RLj@w+_DXf>TM0(ib%lCmo2EWH z-4fqVEeTUzmQJand27SI^7zcM#SHmL+^h}U2THEi=B(Uf&4mp!r~8AP zXahB}3#ZmRG#I`-c7z+toKlacc7PdgR8YTU+td&1>cMr_e$X>xU~1v!B_Isk()ihr zMgQ`wJMLyP;>7U@bqsZz6ZduS-ROJ5l{jre>rF%MI}z*D%Qq#RC{N6^mp2XjZb@8j zs&(4j5tsN`)^IVoQd-=$Bx2tIE@}Ji-H8i7Y?fB+#wa=?@lI~*w5?Yb*Wvnhtvu3t zANJyBHABghEz;~et|#ttq<)&`gB;@Z`l@MDe-w7%I@{w4rFH6IPrT^LolPy8H6}hf zJ7rVd`>lzwU7PxSZcFU0U$}8tmv+RrD+SfreNshSR?q4-Pi;cn^YqHP8O>`F=UU&W zTj)zMVvjyHE=k>TsScJoRb5K?ZXx!1-@s+)+hN2D46R&V&)-RHDgB7K4Ed`eweeH4 zHZIrPT{rPMZ`jz{Mb~>7ae!}QmnpS{udL75yL?EsPUAXj``Nl=1yv?)sCiI#%+`9u zFY{CDD*J2X!*IBK!BxKGFkM1sMwaWuj3#~?d_zul@FE_WP#R(q8WXqu=mxLW6ek|= zpeNkke?j8c`s&7lZjYLHghM3E-jJ-~^09-}FzU%61LvNv@jC<#(`C-wKDWUcZ34H! z8Epc$!5M7=x4{{00=K~#ZOYsRXS7K+IHOGix4{{0s+4WyHn<#ZO56r#w8^*)&S;Zy z8=TQ5<2E>>O~!3-Mw^V=;Ee5J+y-Z~$+#amb6;{BoVhQ#4bI$`+y-avOKyWR_a(Q% znfsF4;LLr=ZE)tktpSQo1eW&bGWnU{}Kp7j#m{G=(GRBm#r;JHutSVzz z8QaR3SB?ec7*UQL<(N{AHRTxO_(3yBh zO_1OBZc5zvss#*cR)yHkwK}{$^iAUWA%^C#UbCBcR906|b@Cy0N*Vw~cFa(5os{?9 zFtzVy1LsMLyn)-`j5dMW;EXnb+u)2gf!pAWHi6sVj5cL%gEQKcxed-}Q|2}}qfG<1 z!5M9;xDC!|Q{px_qfLq1;EXoO24}QMHaMeAvcVZ`k`2yilWcHCn`DDC+9VsCxi7g5 z&fJ&W250U|Zi6%TCAYzu`;yz>%zepiaOS?`HaK%%avPkvFO~hJ>_;V=$Do)`|8E|H z%6`=E@5~&ESg=|{4#>-Wo3daJJUeU^p83_L3cJ`GW20hq7{B|Q)U22V>wc*@EZ6Rq z?mJts?0sD!$IC|=UB`lzUp4@qY@MMxS<`~~=6S;@jFoq_EZBD(6RU9C6~_1}Fu6Z$ z#&I_kxq4n_=#S&>1M2wqX$sSuREMW{ZIk9zAPmRdUex)F<8Hm7E5xC^(}dl!^@;)T z*};N6_VAI9ee;Ir7mZ)ZV~4V?C|Y|HZgV`PP}_UH_J)tTB#lUVp$bu^q=Y zZkCgpTKdx-1)c#x(c@uK>k|WZ*HP;MRkPq5t zOWCeAh9$_)dtQ?q^PE(?{BIwwO3%Xs%xssXyY{Uo;o(F4)3o@HdxQa zpPhKSBxAb_SFax;`99_@_eUFCzikDzJQ;29a+)|N$tTbTFMnR?OnKb7CS>>Pk|VO) z+G{FapDH!7WlvWd6|d)sp4a5gc}@mi{|_Io%DX2&HSl)%pf6jub0>e6yLm{qt*n;0 zAHw!*l^3E7?w@Dq%hzQx$!`sOBIQ!cj*vfX(3eH3XOo|cCSEga>w1m+|E3W7vcNU! zm)t2%s?-I&!EL(@>yj2AKdI>ojUSa}76b0dHA1_CXr+Tjb`@7V8L%3nn&2}tiU~O>Q z`Bdh07~TH5U8Am{_^ccvq9-E74WaotTkj10>p3u9|21WXN?RLPGw!!SB}%cfe(k9aE@drLi@Mfl+z$id3{v%m zcu_xpFrIZZ`58TJl_cRN3kyz<|L<#!H`iEsBG zBe(8;mN@$DGWnQYJNZL_X0UH;Lx?c)0pzlW=90Yj5GU3czlqLu>_aND=!x%%|Ms+J3GwU1Kh0RtF>3@dUe|$MuczhZ0+^V%eHO4?Z zs8eND$2ONZ?t?9}eQHDHIQzbn?!S0Ia^GTh?8o1k#7?2r*u04v;v1=T8NP2seCaP& zwmaxb7H^~GaZ}c{_%;>iZkycL*iMqf*=u7%R>*G_aeN79CePbR+&#G}TX6d}@$KLe zthc8HuHEZWC=7czd}` zv>|imHqiz#w~020xlOb|%x$6#;QHJq+92jOd5m&7w~020xlOb|%x$6#Vr~;{5ObSo zgP7Yy8^qiu+912!CfXq8HkIRo`;Ob?Ho5OObDP|EoViWzJI>rD_Z??$llzV{x5<6S zncL*PP~+S&5>4F&1imsWzb5rPDWfis8_oW*s z&o%B?JQ~uf*sC7q&XT23!BFz`Y}K%CyX7B>GmAGha)b2MiPEs=wP8)A4xmd6kt{n^ z0%u)c7*(i=j1XSjM~v=o+59%kII#&dfuEP96wWt_c2OV$40Wm7rwbxU|rcejC;^Z4{TLy$u9o8WU3EdCz_m`?x)0eYl^Axj(o)F6VyY z_BeC@nfmKbJjCy-T#(h1xqd>$3-b2QYlxNd9QOoy*hl~FwZ_;W9i?66wMtt`eWi|4{;%WHoTGl{B8pX>Gt4>4oTE(n&77mwm~#}a zvrOwBLHyf-1a@t%d)I0lK$IZE6En(y_@_j>=v`c2|$$%4bdH=TYJrJAY00BO(7ZqD zKe@NlbdO+uW^R6FuDs_m-|LCJqkqaX<{VXza<%fgy7HdUyoXcldpAFiGCz+}<_h!k zsCSe%l=q3s9HLym{pokQKVADLeP#K|9L2wX!`DCjk9SoK@NYP9&YTwt9ja|5#&;9B z4(VyDbb$SHY7z6l`Tui$`~yZk3w|BHo(p+-yj;#rT<4^i?4evT$x&Z2>7yDmm4oFo zQ~CHeGuh?uN}?W>iPtexJ+VCc1_if;c9_$K>Kkz@s{x$cP81EGS=oa(1Lnj#X z35{8E{`~LBpM1>mKjv{K<{k5VNAs?E-Gb{UJ}&rr>i@*Lg_q6$n8%%Y++i5-^)StA z#&{z(&v*a*_X{-W{s+dLr{}u$|C9H3WiAy?YZ{^PeibN>A2%Ae-``seB| z^E%VK&it>ePt4E3{(J84l+Q4g{6CdH&HecQz90E_sd<0l-|SU~CQv{2JO3UuYg5?; zoHxYCoWqV(#cycuBzE6y3&(fS_tqKzoBu!8;r}l5nlXMIzn;r^dAwZCHtC&H@Nbh` zWs;-5WYWiSBvUz9zGNyN|0a999Q=2(#~H69dz`U6vd5YKH(gq^K_Tbgzc%Uf?_!(E zAvTszY_v;d80$l9tS2$Hi`Sp{l6@&>ULOC?*j|%9_XDxfKg34A5%czOd&c?zx5t_L zgWKcG{lx8Y#{U5QSo>eIQb&2MvG1rHr7dM0lyx)q9o0?QmLmttnQZbl{%*U{CrV!_ zeW>)UvF}W6^qX1#~sfX6dOEW5gYv}ak)UF=vvWjX9Ipm@`dlY4bYsAL}2Pk9Xx5H|9*>a%0XUHm@_qeV=mf zP|hjJxyI;Eiale_G{vO({tn|xxrR}$ZH(jB6qDw4Ci==e?#$!PJl~0DlIC@$cpj)+ z+bGvO%C(R(X3XnMkweV)cjo&$o~vv-UXGoKbmYJ1 zu^BOq*qcd(h<90aU=fYa^LI#D>GOS9-!3zV6M}}aHoiX%Ts~!m50kzg^C0dqn4R0* zNaFlxbq|)eV>R*7M=Dm~`Xl1~OPyH($5M>zR2x~0JzrLj*rW1IsbQhE#2f4uOIBxl z5xaG)AQg!mLhSh>eS_)!aFoj?IqJ(MeJn>dm4oGjseH5xCc9W4Fx3a^38s2Z=`k2g z^~ZLBsa@D!Ftr!`046`6f57A)^c$G`hW-STKmS>L`}dE)e`?=O9$JIl$!`cDXF%$C z!I^!i*#buFi;><~)Mrz6wuXXbuBs+oug{LH_JCvWiyM^v^1pHI@BYPWL17mZc0pkm z6n6i&uf_WRF2`Ei4OAnmQd=rC83ofSzL9ymu6K-ph`^P^4lT9Nq(y1sUa}rSRy_9L zI*~`?q2cjv66f3D!7wv&FR_K=PW}SWrgmX_nW??#2WIjE`iGhPgMMQszx}It_%HQ~GJgJV&Y8R~{uy%Se`XBE zPUy)22NIEWqZ92e*|mJC1ca)m7p;n%D^T(of~WwUE|NL(kTYY(=*pFRp zV!?Phr@XqeE|wojXF*gO_Gq&c>5MwsnoUivNji&y+}Pt$RT#I`rI`b}Q@kVTeCu3| zS+r|II^VmMXLWbCAf0v5-=sR5eMo1&cb=5pVG!xGp7>14+1P`0y4Bk(RXhK|h1S z&!F%#nEZ_W1&aOxMSp>*zp&py(eI$>cQExk#t$gs2NdxGrue})1VtQzA`Zb6hZxVG zh-Xm5GnnET#|0?H1t`V^n8pQ;FHnpxP>e4yjV~Ohpctp17^h$wr^?)`WMzI<=51v@ zSLS(T{#VWm%K1V$k0|FC<-DVukCgKi&TGHtuLskz>nP^6-}9Yv9#qbc%6U^cpDO2B z<@~FhmzDFiavoRC@5*^!xgJoi6O^pfQC_PoQ)x?C2W8!qbyl`T*+ymCl|E7WO1Wk@ zys>X>g>QfRT-g`OK2r9bvQL$Lt&9O>Y$#(!8B59-Q^uY$CRfqXQW|J90( z`ZyE@&h@S3=M<2FbYy$Y;5 z6Fq{hYV=9+X}V~gvJNjg7iXuk`$5{9(Y1n_v|>%=#_;f2*IGyIhOn~sHn8WsbFH!V z!EEB!{c_*bg0-qv)w7(GG{g46e>o-x#xt1HPg-2I(;8*@Td!-_yVf=2S5ML$i+|Iz zOR3%-k2bqGTBfU6kbi6GP~DCW`ck1xKC?|~JF3dMGg==O>|?>4yRBOHMcsj^E7xNE z+rM0wbF?;lR;E4kYFsJBz^vHR(cUcdOpBBz4|hs#ULkBz>E0=AezliIbx^ZMoyMfx zueZa)>8+lvzZsgMti!@^J*yixO*Q?Xh2z3aQLIFv1Zn2REoeeqgG1e!y?$NCIkOP`GM6OnCrVv?CkDpDLpN} zNtV9D*|2r3Qw&qnq^MD0%&%&{lr0VFOK*p0SdpM{DQoUt+xIMA&uZF*r=(11BzJ4B zVLdiPrzBSWTXwG;#)g-VOfkfLm%IKN#zuttr+hr(0LA?}u|huvryQ-^7CcJTVJqF* zrvzOY0t2oWV9^JhQvO99`ah7~tRBm{K>L)W+hJ1H!C3ZD9-h*r;3JRZCwjJcMrg{D zP37f7&9!WLP;^QOmz(m*W#ie7kdPGj*7e}Cm&9gN?)NXs$2gHORvE@>3dSm6tTK$% z6pU5CSY;TiDHyAOvC1%3Q!rKmV^zXfO~F_Nj8zF^H3ef8Fjggu)pZ!FfU)XV5~BX)f9|Xz*uD%t0@?(fU(LjR#Pxm z0b^CdSWUrL1&mb{#_BqZRlr!4F;*Rv-M0vAPCh z6);w1j8#XBRlryUj8#XBRlryUj8#XBRlryUjMZ8gtAMcz7^}4~R%MJ;z*wz?u_|M% z0>)}BjMXfRRlr!SrK|(SDqyS{Fjm)LtOCZWjIml1V-+w~WsFrvj8(u`1&mckj8(u` zh5v`W_l&A?Y1)L%3X((xF_HvC5J6B0yGupEh^Q!{A_9Vn2{0h2V2&6u=Kx~H2omlt zb53ABW=w!0=3_#qy7%^c`&rNTto6>CnKkp{J%7CHQ@g9W>ZtDLxs#8qqJDkrWYan+i*>OovZ;;J=ql@V8wxN1#Y zWyDn^u38gU8F3YftJcI-Ag&^D)ta~p#8o7&S`$}+xQfJ8>wmGKZy_hHB5~E4xXOvE zNL;lhuI3R}k+^D2TxG;nB(7Q$R~c~?iL2JcRUob+arIy3-_=Q>_q9)hS6^dNC)wGt z9&@HZ?AgdvgC}WhpmQv|>Df26#Qr1u**O$44Or@h(uQ!fLsuA|YLVKvvKK7jj8mEg44DKRFSjpSq^ti zf}Va`l~0aytnx=sg4ND(+_qnV)%c<)cs=71cO0r`-MvyEs6Ogq?3L!$J3FbsEyMvA zCHq*9iD(Q4jk@6KR|BobM}J|JB8Fh&t|P7MN9&&Qt3y0GlXzFf#qC!)|9B(xJXlAX=;k&n`j}4n;qBV_F7%K- zFtxHu6?#Y?thwASRpg4O?<3dsPZfGdA4J_4kt+0%KG^Vn+`rUDp@;MVtt(aNA$>sW zN)>g5^Z~6aRp=poKB|G5uu0lFtCSE%XRK(z^a7j@QBs za_^EKKR=AIPAF`}A6J=z4|#;Oe$4~C+t6rqNbhZZG_nGYoD_^Lo4Z@jD6~e;o8I`? zsJ`{w;Ewo`S>v{pH&*a07-tUr%^%&_Xf@_=s&1hXAwcdtcG;3A?4&1d&HJ~%ns(Y>B z&HQ$$Qzlqrfm26F3Gbi!{Pu5t1cM=T?}*g7zxVS7E2E*#qj9Nw4m$I^MpGbh*TmE( z&+0St)r0XZzT;UBHs)UV9*Q1I-*L0Q8}a$W2VR9^}M2G02)4f$2V1b#t%k$ zWBiqAMmWN^TSg%4S@^~q zjC7t#J3XcZK&6zmOxQo2^i+CYpNVyKDhma}Emd;Gdf!A1hQGfwmVP+XH~^yOujj%) zN`yB|zg5VE-^Sl|0H<}eq(8f78$m&=qx5tCB~Msf#g5YdGe53lv$_PxxNLs5P4&8N z34eGh3@2RLk~3jXDQ|;eIL|O$F@9XkAD;=s`g5)L597!D-svzrv2YBJpLT^$A^F?Z zYx$I2NBIlFUj}CKZ+>gIDajnxy~>a89K}!4IGga8cbjg(?-OooQo^&IZBs4~KD)M* zH(0vRL+IW6qL}MCrK_$I?pF6PZ?xEoeIZ;i=?Wjea16Uc_;LDC-lpkVW=r$8AUzug zWwLsNP18p4aNVoSm~ewc3%+dJV>W^?txKVGF){!89Sb}Tt}d11Z|u@lrO%6{JTA0i zE_ENvdA`pb!!{>gk@J^ZuVveJ9hG|hNKc=hYot9Xq$hsoC?@P|JK-_&oNgiKZ*5Y- zK9C>9x~{G*Wjd=C=7{y)c~Q*5ozfNIhkJD%vy4Sn(m&ToPbc!D@SD%>qpY_L`H?Vm zTf_XxkHXJRD@U;^)vrqbTOYMxhY}ylxOg2f#QwYOV7Yq*T=MtZ4Ye zWA}=+zoLgZW0&!-mE2(2xu%#HX@HNNKe0WnTcGUhKC= zuK}ld^u>xWZDS{lV9l{zL>%kzr4`|*Z%C)rZ*@5ZzZXj)VQPCXt7LVjd-!dGyE}Jc?Yz4yp*iq*A#k7q7&TN85 zJ5~bodCfqqH?4gxOaAMQw5Q&^*L<bssGc2}jh1At9;;af5 z8=$*WA8dH*rUG4kaBx-=%vsPIN)s}?gin4ysssHd&y@Ce+_Hi>zOO3hpQv#m9)@WoOwmPn@l-b?H5-j_ca3*7783-)$wsKohU z`D|vF6p2?_{$huYPn7f2dia}7$e!&biQf#Rx=^`H;urZ{agl37 z6f)BXI^zDpUJ_?N(8W7OffC=?bDnRVHB#a&D@SrY%Xo=DeweJhnwcbV@{>oZ(+Pwvv8z)s~pKz)i-%_-OHSRTD z;yJ0sY}Q4!u3wkT;Oma=a{P#&2gEFQlK9;4zF-)kFYyKcDA?t$wqM(Z#IRHz92+ZT z)+OIp`pr@MA>n(0s?T;co_{}?)o(IU$|Mfgh0K9!-x_c20IA(={%!uU{-2oV-$Ug1 z?A487+2_s@mkeVN(zv0Ii#(FoD0=MnHy2-cwgNHr@})f=xk;YuhmDksXX3)=ujBdDssU ztD8zZ@8}4~{Cr*N+BRqsbm%lm;>@E-5b&*o)HSDX43u2mEp=(nPdowQYM#(VTm|B) zlp(GHaaCgCDiBvCCawZ;RoX^e1>&m2#8n`!N=#g3#8rujtBklRF>zHzT$Px(q!3pn z*0zDT3dB{Zi?|BJRf&nKKwOpb#8n`!N=#g3#8rujtBklRvG)AL6Cke2apEc?u1ZW? zWyDp9iK{B&s>H-qPF$6kxXOvE5))TBaaCgCDiT*ECaxlJRbt{Q5?3WAt|D<&+OKT` zag`BQr3`UZMO>AbxT+9WB_^(N;;O{NRV1!TOk73cs>Is!6HhpCRgM!^k+>=`aTSTH z5))UExGFJm6^X0THsUH0S0yH{B5_r6hPaBvRmof8DiT+@;0bXRiK`M5myo!MVqDt> z;wlnXr7q$s5?3WAt|D<&>LRWpaaCgCDiT+vF5)T@SO0DPo-qgMJ@?b(Je~VFGVoLX z`y(Z{cC#)4F>*ZG_&aMI9wPCUnijD3w~xe)hqr^YhjtQwZ#@8h-LER~jO@{{`a5xg z{#zcB0KaGSmH5!5B>1$!O8Vi(t*O8Zt4ModlgGo@k*g(c?m85XR4bDBRHq(r16Y1AK;mur*V!6ngv1m3Ph~50CrLbK@^;mu7V0{AIp&zM|FgPY z)j2hj?;R2+W$ZTG;*ZmZOFSvf2y3?OBXL827hIXqM&fq2{IK+%x}MvIMPUCv&!lZ$ z{u8iO_;R(K%@XnSi%-(eLHm+$a#|0$Mr{uKC)}dPC@lMUnu#?|-4KY=D(iy4V!sl# zK;Rw28lchGZW3=E`M zB-XAuLJ#Sa<3bPVleUR`6?=@BN9ZAa5(_<~Pp)0)`BR^T9@58!ywF4XP+(Ep#C|NW z&_ntp7J5jZ#M*nA&_nvfpO(cdNhJ%>LhUyHtPk#3P`$j|?F{)BuQAaVpV%G3C*KUh~V z!&ja*^4y@^f>zk0sg68PSd!Kmmw&&;g+DiMBJO0*;lj^pdPA^}-b+RJzy7&UY+_tr zCE`*>eO#j!VlJtW_monQ@jyL&P%uiKFQ-;$xt&7*Yz9vxsmM8E-z-!2^S38 zcGPBFDZ55^F|GF3RAJ6ZV^s-#XI#qAxyJC6i6dUBf~M zS0+7{DWh2y>B?;Xn5~VoWXa_J8agFRH6%?{PUjWRuJndlljbqe7jGEd4F$5gEhb4!|o=!;u8dBEojHeB?@SK=E% zh`TiteX()R&uq=&Y9RXJ{eI3+Z_hR^=Bb=(3=J1P%oBZa_PQsm|Ly~_56#-Un2on` z0nsO(cxMNe;iX*I^Vja`5ZNV^3;C9T6Ik|?IFEx6D=mF!GT0rHkrYP28 ze)k)zv+g<zLfL zW_(Y8RRvun-cNUW>kd7WJ;<-2Q(;neExBjao;MB}-`Oa!$J#I$?e$jTZYJGe<$d+O zUuC}|Y&7HWU1@`Xe-iZl zx>D|;YmQHV)DcUhuHx|#u(|p(iLJkTz>WJYB* z129)V13zh44VoCLdysbBI1AmS?m@op?aTTGt9y`@DofS!%j##L&AC*oL_X3aZJYwYuktZ2Wd5X6v9h&57H_t9y60drJsB5 zNliQrTXa@G$7A-9jzd*)kPO#0SR z;$JoTVw=zU67PRK9#8*TA$1+6JB5TGH&5|gq&+|J1c|FshPaBvRf&nKNL-a?JH%Ba zu5$5N;wlnXB_^&SaaCgCDiT*w$PibNxGFJm6^W}76IVHLRbt{2C$37YZ3A%?iL25E z;wqhUt&~0?t|D<&>LRWpaaCgCDiT-aJj7KbuKwHn#1ka0%5mZ<5?3WAt|D<&V&W<% zu1ZW?<-}EqiK_~6Rbt{QBd$tJTxG;niHWO>xGFJm6^N@66PJLvDzUZ=#8o7&%5mZ< zC$36NT;;@7iHWNUaaCgCDkH8+Ok8EeRf)CdC!R3ksvIY-GUBSl#8pOIm3S~T2I8v3 z#8n`!N=#e@;;O{NRUocP-x61WxGFJm6^N@c7Q|H`u1ek#mw>p+MBKG)Ag(gvs+^O! z3dB{3iK{?dm6*5+#8rujt3X_px`?YlT+J18YR_M1^{9XPVisu2elAw$W{_zb+tx>& zo2QIFu;3Ny+^p!+5XPPE3Syp0Jw4&oG<8io@7EW+lhrvAx_ks=Ezg(s_gWkWW20tB z98{PHI+akavHGAS2s*!1uD#yZNl-s2h7>c?h z<`H^GpTt5B>62JHXN4ZpC+!z{NT0-l@1jPFd4wL)#{?F7NT0+)&!74x^pHLfGC~jO zlUURSv7d=?p@;NIEcB2*iM96vp@;OzaiNFwNi6gTpNe^e9^prUg&yHYfrXww`=-z% z{3ynS9^prU#hxSlD6r5Y{3x){Bm5|^cI?_5Q-R4-b&lxwX$0Rts&l79!aJ5&Q5~;J zR-5S_L>;gG^^Mu|P<6bfhkwj7ex}afDmDH1##8EeO*@&(RrX_0=yD%d6&uE>>(5Tz zW|-1WU6+bi`{GeQb-lXeJOsDe|1E7>)G!vqgLX(f`q~t%($qrY(_fP?G-{lz)iKj1 zW2?r%#Qe+Wjm7!9j!2v|Y7i#3tR#J9%sb#dd+PD%Kfm@?xU^*_iFK}&^U-|=OB_6B z9}m74E%7RwmfX-uoolUh0JgV(FZ;)5iVd8ZTTk9g-XEn4FQ&Q3`^q^Z3YgI=UwMzY zB5^*8>KrKVH+MDts49FMBKx~X6%Cc|7%KZd|2pk>`*VY2KiCxZaQ(WyWS{tx^vu@* z**`Y@YKrfiY-L~RbkGHRbF1{**umOyzy?igvo#<%Em8 zFD~&d;H`f9%KPG3>*n*Vu7UEtczMH*O8nCh*^l3~H&o3y6)OAmWk&5-`I$kof4|7~ zup4!Hfg{;w+TlH$PJWd4#a~Uqxuq>wQ(s(q&;^cq>&o+i?>~Iui$?(y=LUr?fzWcz zd?wBl3Q9x3*7=*cSwV)>yXSQ-e;=_- z_RAIg3;5Rt!Cc%Im-!d+zcP)uxG(M!{hI&Ul%$CJ;_jqp;Ko&6;=Xuv^CI5k_XU-> zFJAQMK0j#UD({79U7Xe>?{k~yXYg9rHp}s-$YoroBv;-Sk7yLk4SN>I`{GT{qaTiQW| z4?THb9Fvg9t=l%1edXYZQ9QuOMcx+|7Oqy>+55_Va3?e4%>sMN`{KyM^OZff^+EK- zS0+vO$~a(&qAwoVzDzZ8M~J*HuHU|*s`+y_+3$Dz>zm5fr%d*$&PRdeHuRSF#oXq( z%E`N*JU4K!){RxZrz3lLm)K-B`ilC#SQWO4U0&Eyo&&g7M|LTxjElZ?+_w9ydQ2O6 z51Uiz6+2Y?or%79@v{%?(cNs7=)uzteqyUzCi1MH z>()9Dy=)c}_Sa}p7tZR|l=F`nW&&FS-g43Nj^5QAmd(1tL|>ddsRdjdu**yI>`TD` zLald6nV{1hVaaeyCi;Dyxc2b#X*VwV;?uVRpkUxOMfAmO{9^D(K)w=oY8(IEVk{mS z5vHVdKf;v`fXQhoe51b^>JI3Ijs>CI)wBi3kt<2BuI>ncd zU}(F4GN0e138n{oW8^0T{%no~PWaLdYn7)dKYN_9Hj< z<+DfJcSR6x(EqKBtyNjrq7pUed8vlT>N#h?7Hfj6=!X}M>K-i@54+xty{sCc=#y=oz()b62O&b3w!X}M>6!H&f z{3Bup8vk(e4`}?u$v>d+kBAv){3Bup8vk(e4`}?OkbgkqpFHvpX#A5){sE1D6!H%U zdwRTaK*;jKps$Pb{u}?hA66xdhm`B9{%0yyAH$QNTF_qW=heP$a zo6?@5*`aV`^LvRqga<)`SJk9U=D8?v?R80x&!`&(S<|jcd~etY`fXjl#IG;K!ku1Q zB@TZ#2`1Q%lK6++RM>R4w#1j|o-zIBZ!qmN*wUp2KMH3llX9n z4Md;sF7e;DY{2+-4~d^9H3R*zwh~X-&>Y51sUWegy(0|qIwbAU*K>p`A=wglqIG%F zy1G0uQ2x`pw0&i4-aE~>=*D)sQN!J1Tf*YE2UY1dZSjD0@3eX+3*>m0X1&u)H{?s~ zw<2J7(w%~xLjKwLGOye-qdlimPZGX=tV(B7spt1aNqBziVHMVN@mlaZ5$yxoz^`vd zRVD7u*e90e@1&mp+xV8SV8a2aYgk-MxK}}qRRb2~tvuT>*WgPMT)40-Z^uz{&(WWg z;KcE{d7n?*_nb?({+Tg(ffa1MwiC{t=bd+bVSraYVY8q5dEMRPyz008@VMAuW+(i9p?EZr|aM(17 zAGDhUO-`7q>OJj_PIOPk&UaK*>^2p%y!CiuA8*xzyZ8Cur(%?zM!^1Yh+3q_j*cW#cM7;G+}9tInlI!j4-(cyoWKoe*Y_T_)x;~quZdz)@tx%eF+<| z#D_P%c!6yoT?2nP;ivvaVA!jKZ8x;Te(TKOv2h8j-?a`8t8$Zd(2sxzZ?y^-7}Om;d$nsOw@C z8+zhQ1}b;zvpXNw=ZBsds9Y-~Vqt~P%Gq^BscxKjBWn)KURp{459Qi3- zY4WtT>QLTLeE9Y`bAH)Oo@f*L$kmn8n|Vt`3& zFG^g{$`n7X+%NIQn~m|skEIe1ZPx_Lnk)rK5;?%;cHkH|Gg*>^58;LPV4Pmws z6R&hFtSzJcSdXSH={+n{ZmW{uKL%^D>ZI-N?ac4)1UYpqdYZC`2oP@@;M)+n)d zEVN^kej`(?QOXD(YsF4*^3ObilM;(qkv@sVpW^RAm-zo$u@jt>c8dALylQ)rFynfY zKe79Vt3r>kPir2DHS>cQ*XWg4=n?A|<3f+{qre*bCC=8$wc7L^6^E_zJus^O3f8Vs z{}ue-dHoMJ{yVRUhyR_|>OJWHbY8o0FP!{Qeb@7!u=S}V+%&nRyl44e!K4R;4)JvM zU%@LrIG_&xyL?_sTYMGnEa%xU!5g>sZYuH9MLqELs(KQ4UEBjZYjEX83{y0BquMf+ zjfUeVhr9C5rO(kgyxwlQ#J#Re#gi|pN<82-)!QvsBZuPj=C7EDqc)!6KNSy@sed!l zVsR2S>JcNK%>yn>!kHm4Qr^>UEOt%HlvualRCEed%YV;K#9!4eOL>2%1UyhheMhP6 z9EV@^)Ze8Ey#7}C7B(8%nP;-A9mXkREXIKMglu-pwYySzLlWGZbTV&xYOu0yd?M@# zKc%{~XtmP6LOjeJ7Rp8!DvJ5@aWKbe1xs4i%q#3i5+p6-xnP^4+8L4vwO`Fu1@8Py zWmR(uRI@W+W-hs^2kqiue!wL5bX+}EqlqzKU1b-0vf+eR%(vjh3b|)AJqa zyY1yX{9Qh)@yQ$gpf>(&e}+BCZA){EM)Hx0{KLsNNIp`Le>nLD$ww;kj~Dp{$ww;k zkMIqWk5uFzPQF3%k&67o$u~$o$|L`Hl5dcFq>z6U@(q%Y6!H%z-yr!&A^&jl4U&%( z@((B9Ao(bd{KG}8H1;qND~&xbjNo`{vk9+ild#vUeOrLl*pV|r8S8heVns2N@e;A3n8|pFSW(PC#7o4AVg@2!B32YL5b+YRqL_h* zmxvX`3`D#{tSDw6;w555F#{1V5i5!rh?M4o;j?wSs;jeC8T^P?KN6 z9@ONQum?5yCG0^>ehGU}lV8Ff)Z~}2hd3njOW1>&{E{5fe z!#f)q6OYm9I~D2@VN+M1F~U7xsw!68SFd5&0$ZUDzXIrLjlk zm&kWvkH{~P@4_CDUn1XyJtDtEz6*Oqeu;b+_K5rv`7Z1c`6cpQ*dy`_MNJg(60s6B zQN&BcO4LM6esNI~HTlIwP1NKU7d26nUtH8gO@47v6E*q8MNQP?7Z){AlV4oaL=i6$ zD^U|Q`6c!X!Do?QV!sf47WpOi3&CfRUt+%yd=~koX!tDhOY9ed&mzCXej)fQ@=NR& zg3ltqq>n_rgl{x_7WpOi3&CfRUt+%ye3tvP*falMIj2(FqP9n&^Ok#=>N}DDS^Ocb zgRRTpy*tFZsZ`@wg1lCW-+6NHxo9Dqj3is7yazcXm^-c+6-Q2FgE#SOW3Pp z2~R2>W+4_<@NRNl7=E$>c;^|x$t_jDvZpl+3;M+N7CmN87T$2j`8fO4=l~nvcMzD* zn8UnhPGl;Vv9S4NEoOJ9DqHL@8D6bkuG$bVM>YInA~bB_3q#hJ<7t-~icxc4V5`jW z>n{T(`g#BCdwy+m75dKR_7S=e+TjTw{h$r5JjZiR?0u7SgT~`uyMgoH#(1#Zb-vG0 z7pw~(^GkFWaE*S0Jb7X)zd4Y;dl$uX+7%Rgi1&YFHww>oz1!N86W%n&2QN;tz?`FX zmC9dquxk8c9v!R*okNGs3KP+}74~dQD zoaWzOWRA0neDL^31Eq%b6F&Fv2sEv1rW~jo$=CYCqt~)}N_;KTHuTOh6n8zJ9?rKn zTbOH4KF5q{VXf(1iJaa)h!ZLmw6?tEjN&e1rm1e5Mvq3|1=4$@nIj+jD3|~35QTmB z?B3yi+=jjxaGhA9QdcoP~=?HPb$SHIwu2*=hPjiX<=@(MK^(z2gEb`-iC zZ+GBNvvPRFz!CV%2YH9fR(QI!ITjh$#K>{p`2N}_owTmZY4ongBC>zY;utjMY5e+y#mbW2Q}8mY z&03E-s9^{mYUYuCViKP~XQjS*g6 zy@+3N*~(SX!%@h*DK>i-!n@SV${Om}Kak$Dmw6^0yzN_vn zJ|ea%iaB)?^!ePfzEb|_y&WtvdYF_S6S#w4uC_wTho21LPkLKO`P0u$ndMZq{DrFx zU{W~!7M|vJ`P`2iR6Zr;b(+ogOyKrXe%$+8%wUt3oWFN)Z@Aa+Hy83de3vQbGww_I zI_rng?}f~ze8*fXQ0xuloJQZ*t9p8*G z1YY`9PkE~w$()Jj9g^!Q2^yZiCY}e}`^M~upTF~u@uz!tvkw<-@Fwv#wz(tgKzx2f ze6H@7-2B%h2M58=Kb*fz92-x$U_rUClQ<@FWQ-<9O!w_(jCdYHJa;3kPduL>cwRxT z`HdPTd&E3(#K~D2PEI1OIulpd&^&I$;pW8QWST!}%jGu3caxyUIDMt>oeu0I<;B;2 zBd~5~WcrjByC^Sq)UFAyW4%$Kyl@}m41vAd;+vX=%CChnu#yx7QRXfZFWF zt)og>kDg#RrViAzI;NQG7qc&3;c$X2QToq}goY#Uanp(?B<}e#kN0{zk}u6+kXy4c z&heYhg-nIB3-|%2{c^l+@h|?$=b0SWNv_2gPcD$-ZI-9<^38Qo$Zwe9<5_h05f86b z1GY7;j$79@Low&qEe{pbBs(e7D8iJzip`fYRk9ZGzutA1GB<|2Q`yv0%gk_E#L~U? zN|{p~PI%tF-CxSQKDLv+n^;HAV>^el9cht#-l|1RmEMFGo}lkwlHPs8Q&{t|Zc=_q zwTdwR$YUw<)XtHmII3j|<8&bJu&tEo`nEBAJs&S+TGjo?HooX9=lM3>9duHj$nm0Q z?qFwQA;$~*1i;gVE#>&FZ$n{I*wi*#IsM<3&<@8|XPDT~_ z9bznt4epJtI(k9x+i%$XIput6zuD|TR%se=fw0<#v z8t#J)k}dEQ*%o8c7>90ejrEu8;*K>Q@H*LzF~6oAhI9|($7&zr&L+e0R`HpAhLO#s zZKBrIr9J)HI|C)2Z0JBXd?p*B$+kvRyY>(d=a9`-Wb;9?Il+7-w>9?0A4YZ1pYYqG zk$9>{>i_Y&t@XV6zqA+R(p&F3uUE%(ZW~`Ln4{)ExUmoZ)WrQE`O}>IDV}p~*Z0Nm zllSJ`EHFnm7J*Hi3R%BXgO&K06<*ybM@E06@8Rrtz&|A<=C%G7iF1A}%+g^oIp0Js ztQ+jrreFjl243en{&l>%D9-TCy)BN>UE#Su4w>Jm(KsS$Ht#p)qbk#Tg2YSu<}>4G zA^7%T6@1w$mhJTEEyvgFvjc-|uJ|C)3#~WpR++zQE@h@y|IDuYxk;ItZvCO-gfcE< z+8h z^Sdl;o|;v!x!|y?VFsUA-vsvm_QdINZuq9ZD|qiURN8KH&hnu>$ZxHIGFPi!C27^M zY_0lsmEPTWvSTn@+}K$0E}g~qP>s4Yq>*x(#%nDPg0K%wxe<+{NW@K#>{Tes8a8*R?y|^wMvBDRQ0oZ3#}Q zWt#Qp9l6W5Il{qIPxyW|K-o$5hE?v%+#_VNe@~^d1REZhcfW zvOUhp{(tI*>$<|$f1ai3dElRCY} ze1bjVk1$1-e!mlTAv!PSa38#IEeKpxV|l^XcYIEoIh;S$7&ldUFLA;dPh6Nin>!5H z%_drn#!eqx<+#_HJ_Ck(-Gmha)%T;nbl=ey7=_qmj{@c9ROZ_{R z|J~1W+BM>7W@nP>~M;wyw3Et-dM9=aM2lU%dwQYaGQ1W?oi5cn_*{f!C z?v69G;!e+O|L|e27EhXf)I*)uy`YbyIiEbLBieUTSY^9vXh!3Aet3d!mrHyIjq@cw z?Df=!SdqqikE;W3v(3=ASqe`qkA(WuQ+eSBJuK4U>~j=gBO2f2=M6Sc2NfE(K2wPe zZP^DO+NJQ)e)@22P-k3Bc)RZkHvQNLTxv&W3~1#V061&Xi0 zBPpgAD5kk-=GdFKF^0Gy#vf69zfgR|_zvRFNaBycA1=J$$;1T`|TNGExWb)O0ie|=_@H-|MZntlP~bpM@HCY zygN2DTFW%^K^)bN1K;c8YuybQa zDUs>S{_Z1!(nx8@1{TJgnNmtXT!2k%Ne{P`_DH}I{*p;MdN9hhEGez!31 zeK})ik&j94j9cux!{HY7!<1YjBozxb;$EGx8ZBr#bI|XjHjn`e3E@a-Vy~(`JzmdAC4=iDyI^B`@ z4~K>Qe|#?bsc~A*OMA%YfBLDZZ8j`kG`Z~@F{d`xj*E7@{>&-rytb}ehkV+K^9^6p zTYF4vQ8%y#orkO`Hpg?+GbVmAP!8BU;n80sFg4vo8KM)($NI)&Q^Lc~nPYfmUu;%x zplF|^+*xFUM_fBdAKo!^z~_M~iD!;>#)f^`;-oSICA?MDrj2%5%eY@`AHx?nTFFak zZ(4BRF)wPbi~DGA@;9lC$pvosh-^OeSf}ZlQ|40s`51$ymP$j3YkthwTY4dLukeFw z<=H&H#RC3{<{6Xzg@0^Z0awyIADt}m*;G56PV+237SHRgUM6)V&ws_6l~(uf13LIq&uCTET;35u==_3d}bw`&zKc|&cWMB5Z|Dd z@-oo{>vn5{L+ctS-)B$4<8CAP)TDLFD$h~)ZaT7*d5Ur?QwQBj`$5^T^`d9bqUTts zB%Wh6cpl;TRNMcY`OKu+{^!i+IMwz)XFfd@n~g5ci=+>=@oAFz(}T~Y&;IGb7tox4 zdhlTCsk>57olm+ljU2#C6JKSq4ZLfmj=T1mL-rHnw4xRDq^|3gXER5Nk?8xD@BG3B zQH(_2ceJG?G^QABq8M!&YmkirC)IIp`QhijjeQ%o5V3YQtqq^^-Ebhu z|2+7ZB@t&9(mY|_G0c*<^ql6e{%aZwrZ@^+-(1Sr2#TZ7WzeM&ET{Yxx~k{Ivz4os zNtq`LUa@_2H!WnG+tq`~vz?_(&r_>pUW}$38J_!EKA%*j9658*9FA7-#RcRCy&`ik zET*2M*g$cxdcyp_Mc|apCQ4z&NcM#CC2gCDBF-ZEY0e^&=f^JlZe%M`dD zP@5U`Ii_UMS%f8>MRaVUK8yHFXAwno7BR&~k>?(kbnfxqxD~i&wZ^Kh#>$dG&vWeV z(R&$g=qVB3YCzG5Kv-tFPFe6`BqZ6LV29@@%EK9x;JEh){wiwyKRh|5#hG)2wfpYr z6!$;o8MMEXdTC$cI z>5rFq!w_S(jow!;=5K5CoawACWH~BdY?~g+^4G1GbCzf2v0TeaAjWt1(1FxJDrtk| zaR*lI$Q~)PA$}OctGoc+q)CDV>K5pnu0;PUm3QvBONcPiGoU zb>hGe&6Jqq&E@$?b2>k9TiF)oH*=zPG3&IeYKe8Y+{PVR8T6JFv-_6eP|q@1nHMz$j^#Gs11lvfPF=!b)RtE)E^@CD66g-| zhB!f!;b}@QdOz6139s0O9(xrZHXgo5q_BypyA%`KBUCHK!c4aW<=MkmEOuTv)UUZz zIsIfj3@BN~$Gw}ZxY9ecO+GYXQ+CjAx@z@+m^@Rs)@hGo>KX})4&G-$$@`VtA-3Rg zpdCzHvq|y$GyukwRDvgWcPn=_+G_4~{J!=UrJ<}BWH48hpI~0ZyH-ma@y2HTLtCVhCdq7;6DWrAT zuWUFr9^QXh&L6&+tSs;hfbR+V(0J#5Wl)4KxY;&=Nvd56->!=JkZq zs5)?IeY)bheG1%NXvD@9Zc*Nv4uopCm7vztor+z_I5>8CCClHrL#cQ&5oYrw70X+% zI93=BgYT{8w*x0A8M%qz*gRhK`^6Sz*VA~|_^Jo?BpXij#jR{q<6S=y{_6be3O#nKLi%k|HuZ--Kj*g7+8_FlUMpa zN=eyo2Zt5`bb7r}3C@1awr>i9uyb=2TOE1_X10^6O29g$@vLa@c(#|%eH5jXn26GT!Dp(~ zrathv*n-}@VxYVkn+|?nSF)Ued$z@ePLDi0MrJh%29 zDRcAHQr_CuNXnR0FW^OG{!%6>V+ilAw_eILrS}>wORFShB3*SbnCi1w<03lyx%&bqUAao76SXHqaeUQ4PE^EKR9pcZ9c~TKC2^K^gmGJT85+jK@=b3!{Jg zU`A;ZHkInzsYkE4JJrBjx=WS)#yxO)uDaHhwTi@6hwig*s&$(_4Zz~!N^p zxO%6$zQqi&#UmN*U@+Cd#Zi%%d-N}sNVRVE$#A@~`UTrYwT@X#LFa`H*;uM?-wmf= z>|ASJNOdphP$IUno1tn?wNAI^BvckevF%jrQXbi2SE_ZTcAJzY(>r3}8B4IDS{K^B zjC*Qo-FOc(jBMQ<22ic*b8I}``MR9fES;?E=-LB+gqp%Cs(YtB18_UlIwPueH6nd6 z*ro|gpjwx|kA4edJx_IlYTe-NQ?UD7BQ~Du+ktsK@#ly-aFOcXoO%PXMvl7HC6kj57Vy0cZs_V-w3V%xPr+L|fjiOpN zb>C3bcPwNLsn+?_?28M6^}wHM-O8XC9Mg!- z>#CS0p=)*nl@HarjRDa(r*t3RLAB1Kei9bvnW$W-)~%y+$O1Zt^rUmh!GkN{1>ay$ zJup*RzMaL(Ys5iJqM7o!pMyM~>_O*~I)jou^J%ZQ=x3mes?`RavR$CMjUj!vRd4r^ z2V>=3Hr1%iB+XrnxFi1a>?iJy#a+w>dQNV$Ewjxg>NOmG=qrYSRaxRZg}cR##L=#^ z*!kYg@k6i+R-Af@tv?xvBU+#2E9m=X<@N zA;(_^y0P3?wS3vvD!k6Jju_f)H(Ql#ig(_6N|^%N-HfMPmvinMrNaz|sAam>+QOfo z370Z%wO_IU*$bu2+DfO{rFD*Sp7VxIo-;`5;FM||44qGOMdRs zY8HP>{;xdP1)uk=%2!fcJSi>}D$w@_ZmGXNP(SNXn}x)I#;*+J_W?vqMem~>Yr%m( z_i>+w`lB1gYtqaNWrkG(W*fWm_nkf~lT9b!B(s@p0>$fR#}3%*sudh*|5fSUIVk5zH^}qZ=PZ!(j4VHHhs5v_${v{?YSK| z3UZA)Ntx&VCh+WCB`MRXmK!@epsVEcH ziJ;eL4!hReSDZKgBh&H~y%*C{1=(2v%G>F&P|#o-Q>u1WDxbW-PW(*=$osvO>l4ni z!!QzFuI`|$eeDTP{2d|iOn+tPfI4ukwLjdg(nm4u(+;{t*}=5y{gquU!yu!_TV{Se zKzZDy9i+z6`!OdCP!=5yfr4d!vmvTpN|Pa;^e$pYX!$izX{JZ-(RwqJecRSa@$$IH zavwy&{d%30M(@8e_x>R;AhD}*aa4P-v9g7o0Rt7CGhr~&_znA3r=Q|;w;kNSVha~e z4pe^Lp?@3g=VNy9b`K?|eH?`Koxuj$`zW)6F0zbUQBXOqlhSKoCD`z3AY_?zSFRjs z4_B_*z|5Zm72lujpmM4$v@ji{ydM(>^~=1*7E>KD;y~EHoFR8gt1r(?E|ARoPH_<3cP9Ib@Km$OFl1yq-ruR0 zGJHC{ufDVaPBe;A8huKDx5vDBi@&=orzR&rxN8so^insa_KME1Xk=qNJS)CUZ;jCFXy~v1r}lWXi0!_aAqv5 zPu*+jQx>`y-SVhQ=`9d@l^RK3K7M(Gd=OwnRVo5y~EmBG&6tIPMMY z^Dn)_|LoZ;<)ieQh>Q05t@gRD_MFqtbTdowziJ2L~oE1KRp%~HQvV7RO_tRt4{EvCq}`r zFYT4*dZFl=@`0`B)K{U`456EiJ=};Lpd9Srft}5qAo^&3<@Wzz@6MyK>i&oE8wzEJ zD9IQ_BJ)tV_HIB$gCRwPgplSCnbM?5^F*Tt&2xraXTK|rA`yksOev+(JU;L1;=VuU zetwVd>ib*YXZ_att^2?CI%}VEopY|e_u1#Q_u1Qf5KM_|Esq;h)u2$*gC0@z=6=Lo zV}iD_{In<*?n^Bp4?4MW{m3&WQSm%H4*+aHYkNj>q!o6CedrZRK=eWE=?l zE+AXfT)CsBCynCzYlz=>g7Dp9!nNhxj)ShyjQ9U*TYXq#lmK&gk0a~sl(^Ix$zT=V zTE05sdtvFvW8!kB_f!Wy2FekuG8dSjxV(4E(`fM=2yc!_8)^KWxKC8B=SR*psv4go zF7N8=^x&D_Qi15Vw#D>x4_MNq_W$Vfnv8vO9@sZ` z3GZ8GO#>S}JQU{k)f1JS|JUV_UpDz=mS2|nWt{(8rkywA@#lZ z`&lmkhC0Nx_2u#V_1f#dtHyq}4cPA{I(~coZo9Fc?o?Ypoy&c7IsVtdl%atyebWDt=rX?_ZZ?6WOIAICqJel-H}Z4f<%ag*O^_GQ})>VWrC*yT1W z>C**Fdk=ueMr#2M42 z_5*8gu?I@Z;`A?L%3^I6d0 zHRA2vvbsReTjfObyU`|rpry7>oJKuZ3w$FEinq%=%48bDLd5AK-}i-XCV}GZYxW&r zyH4AQw~r}}gf|{1okYinhPEC*+ZvlPL$@EmI`d#St?GWmAZ{ZU7W~7+yAG^ z)c;?PGcD9_|Du`e#pOa(ucyl0H}d0mA%o%VVZyu*CXZ<9DI+(r7lnN3GvUfp@E zCzZ=}r`IqK|A_UZzR$bTF&Gnxne@TXljJ4l`LIbzG~=iu*@W@P{CK)!osJ!#vU-<7e{P&&hzDxH{Xz&oH&${qtfA5#Q#j$d{dJgAN zCob0=B@J>eP8=tW^)|`pJW13P*A@NaU+rHqy1V##o2!rQ53NiP$0IrsD!}!pMEUAX znlfEGri_X1!+{%twAL;|oF|oPadhK`AaTC>?Ho#-=DLfwyG9$+3^!kK`o@j@sZ?H1 zal8`yzMc$9a}*u3HZPYP8`>z&tC`!U;F_V5M6_MowvcGw+b`Ze{H`TEsNw1;`dutT zv~Ty;vNood1)cZ#l0dZm%MBpo_f6$(Bq-Dmvz-f_215 zxwZbe+%rz2;a1ty#rznog zde4W6Lx+mvZTjaP`pS37Wdwu~2g4Etp5uuoQW%>QnmY!t8m*S*f3ZhYQ4 zkDM@FhX&sqE z_6HT)xvt$>WA))*Nr&k{;_dhP`IFce@#46>?RbrUw-5g$?!It?)2Oz-?Eh}xO%C<} zg|+nox$W8^=%(6w&M{Y>{e3OP&9dy|`qpdQ{C)`=alQ50r50ahb(>r7iN3QGtgvdm zR}W_EK=#AddnkL;9wvNly|-pJCa}}5TdzG`_bc;?Z@nk&ZTGb^C^(Gw^UD)O?&oqH zdO%|sojv0|m)&1m05DE(KCYf4!FhE8&`3cilu4o5Pw*N-=y%JdDAWl+QVof z#En(qJkXF;&?LurpWs|H6KGtSHDh{T{$a?U(2(b&A@6_qnM+1Po`HruyzV#`HtRQe zjCLx@Z$m!+CPUL(cQ_}3kV-gZl zD4AukpS{95>dLBE`*Rw_n9d*_y8=}3A-=7`V7Y|T+J zbAYD!d@c=oM#6fH6rWG+Jv(wD^ME*w#fpQ3d25N&toZzZeBC%ooMuR}73p&Mpg7If z#&4562BDwL9IF04jY+_}sBTjQadlMPoqn9{d=iGzL=zKz) z=KpqkCbat-rW=dz|M=gTH@2`|FIxY*O((yy43F0TZo-V;EdKaJIEL+khXvbuzqsJs z`d^fcV7A%yY-oQ>SHZC-Kb_&KZb#4!Io|t8+kZ4;&xPK(ZU3Fa^Sb^^Hx3eyJBm(j zWXJHo&cgpXWaUZr0rP-pywDF^dhQkG4bfPm2V;7&sauYVgtPb;r=s2DcRqVihB2MFn z_h%m7A5s3d|M;8Lwv~&&?yYEhd-rw?_D7^(nKH!whzjg4Fu}69ef4p!QVTty!kUdg z^Z6hB1>dm0Ko|Q97Px)k+_Aqv9s3I&i~0*nTl*%ov2UX3f=fXH_EY3bD|1RR63~z~ z5ym$uav|SB;iBwAru^e3_e(Jb#s)7W3$PDjhN~V-JK{noPk-=_HYER9^FI}rqL*Gn zPZQk}IrMG6alJ&(ea;H!E@V z@MW}k-}d4^d8Y8w%tm+8Mt2gOLwoMTcd8ucIOrSHdd|telECRi>$NzSq=0f_>os=R zmk9Z7*DkXt1>Sg$5ubB=G5>u2BrbQ1qX+IRB2S!`8U9HuZ>*k&^(a+vU1anpF&-1} z_zaJ~|4(8(roE`1#^dMwNo+sWmX29tBl;Fw_$RSoO9V_gQ6-wYO!z0Uk%78>+uUoy zKZ(irszEV7{*JHOvoSzS)E%>TmbQ0wmJ+uW!(+qL` z>4>(_gtj2s-s77Q{P;SEisF<0r&%`If+)uSH}5a&;Kz0QC$iAXt?h>fja;VIqcwep zuASlPYBM0kELVKa zSLY=_({>MWTz)16hK`aE=gC{w<3V%$MDaO)@}3GAm#&Fp>-Zf0 z@BYbguAbV?eovkwzHj{V`S+Or-p_yYQfnFiw;cV~b`se?~zWj6M{}%t;_-XjtZOX^eR}xC%_QThPsgzT^B5vDMtIntPJDtUGabya$ zkC`TJUxgh{p}z+!bE5W-V%&VHk?tgJN6BPG(LTB*;@Hq~B<*6@+E>`;i8a0T+E(1| zO0HC=5^ZhK%Tktfd%*zl@6Pa3qiM4|#Bs1nDX|ET62}Iqp5$9}f;i^4E%~v*;$5Wj z^=xq(>FYgd;aPWa{1f{Qe6a68be@{ncd*6zr1)CgudT#RD27gi>`E^=*`|_`apPqkwejAJ*^T$;1$6D~m zV0_a2wypTOx42)X`)>!mXx|;;?}GVh`1|sYNsh`Nohy?in#+Q&*J3O~!khawb{ds7 zvjDZ_MVz|M0Gf4R3LMUmU`uRn5&rmrKN&ONw%PF4A%FB#NTE3Pyphjd zOe+(g=fXiI5bH3AiO%zW|4C4KF;RS;29oDkKOatc%w;xyZO z7P2+Ehs9~)L;Hi{MjdgQpkI^0WwD1iP03Ip8yC1yoaRZK8T5+oEKZXa5eDz2?8Ir7 zICHGSw`6gek}z{vxU$%t}_Hl=_q|{vh ztQs=@+!R>Eix>0a=Xy&AYN$@aIfPo+<@MZvjCmcQcFqLoc~CcRFFhyh(v0)?ZptMk zVc~GeHhjJJ@>k4Cd}^Pk|-8bK}RDhyU)!|F4eY*>)WM zd@1}f8!3C|7l^Lc0s`t_2mZZU#@qf5*E6lI+`>kVbB7am za@lLYaOmNk%EEJxF`dDEVUC)VqM5;Q_|9vswSL z$&k)FX3l9@7~FLWbMtbCD-(Lb#&B2gyywXA&p}mD4PMm5u%BCo!RkTQkQQbK?6d>7 zc%nJzpr6YrJYxE>kC>4#mix3e4CZvX%NlOva8W^1;JdyhD7^g1c6!Lb+t*rfGb)ei zy4t|%1sbp;3>fKS3&G?1fUBYcobZ;z4HfMD(Km%F*A>Gyb8myVY_i`wlp`NogK1;+u%GC z@;wicgDFC8gSQIYy6s7adK@F}Rie+P$4Qn@V@bd|OU;e%2 z|EK)2p!;Y=p1e^sU3cg*Qyj22Z(F`SEpxSkd3c_VUWbU|0wHH>dXoF`(1v!tX$|GS zH!v=AC^b2v3gbJMGPq|&HLj>bi)1G_Wui*=;CPL*BMl(mu7b=eF@((+Kg4(;#&_@b zgjqo?Wd3Rc(A(e#Zew<{NP_d=Y_yvI65hUCHs^)?o500%Tt% zao$kQ=({6K&%c)BmyCm8jMXtdgYnSw;h-Sjfo(Z>n>|@_hBf$JA~zRJ0M~o@Ov3RP z(Qyfc1$PVB)^pj!)hQSfn+sTx?IuzIZNw>o!Y*l(-@`TvpR8Cfc+(prDo1e#NK z^b>Wg4|jFBOKx4w;ih68I5_qZ*?T&c`+{|&)c8Jho`M1Z)^$G@Xwbf)z=mQS==Vm8 zdPL^2-lDqEz>-dU@sl0EIJC9In{Q{2tQ9c zAMBLh8T0cN%+Hn&zUO6Oe!hkI*&rpCY2S&U)4$=kFw-0^;n%Pxh(hAcD3JL~F5$LrxxvTlK6!kjwdbSoTm>km6Nxz>@y+Hf$w ze#fy_=Q=X~ML1l&-Z5|6Q6Ku@hXOR5VPyGoM>@Ag1>o%wvMOm1UEHh;&aX3xL7g-0 zZKMoGj-`|LCx+8wiCsV@Fq*_jjHJh#l)%2yl~~^zO&88p0_hw*5@O&pALUq4#Vb>gBBn3golUbEFUbYzXk@%e~n)mre|=_S>+7Tev@*_Bd8UuIioS zex=W+UuAG@JLi>LNz*{?+FBnvreyxSTDL%_F;yMw7UGQy}lTE}cIT z=lz)18=l|jLc`qTsnsf7I3(SHo}8tDb1iDYv@NCNTd5Ttyk8wM%X7$_1VU3gcY~s$ zAhO6UnhrJ0W?xgy>G+Rl3$ILc0O>*2bV;T%(KWV)3(-+H55WiFs=lRc!htBN92O$j zcB+_->S965U6vA!p8di5RXDBgF_>Jsb%jmWEhG_lv&c!D17nfhIU>wHOsbLs;bMm~ z#OB;};u_`$;W_n!{G*OkqQC?`JCC4dSF~ZN*+4FLt1CUK(+fI=59FpxtYvH`OqW_Vf2l(;gSO1ycc!SkA2Yqbk ze|y)$j_i?j*n#ggH}SnDDJgqE<)GI0nl-YoNWq{9Q1>u}xfDGh7anLr$xUOh$h=6l zYgVy{7;o5}x{BngoE7-|m<#8O4Qb1R{;+!H@qf(MC%sh4J{{j{j^KNZ8ot+L;cr#o zZ!vtYDf@4{*Zj$G3T1ly{T|e`+wYv{8o%N-E(%pWC%VQ`{9S=Yaeh_XHMUpB^6%U5 z8@jONmKnQeG8BAq{$aVdz2E`f=X>=pna_v`VBL_yLU%u4?$0$rrNS7T5-&32epPJu zJa6z>yo$}&J}X%KeJ)fO8N%bo{h@#KahB6fS!mprXXXd$fxDV1`+#}o>lRnosM`ys zV}8^0P!T?A%Wu9d_?u_-m?q{oC+88MbyXW;F@Gk9jerql4XhgT*!H|HtV_{2rzFf* z*V8|KxVGA(-Y&&29S0*O0o|vy5*ja!!O=aqs-{uS%3fETMU<)uG z^6L}r`d;w!yB-^l^@eCp=3zLuOeJ1B|Gx2K{(a+b=f6|%>#>Er_q#ze2MQ*Q_Mz6Q zilE&#r_C+=E!QRU;l~(D)bhU*l&M|(09j&mVQCGUdm}S4%4L2S7`?e-1JnRY%O0rZqSr4vcYC&ph zGr2Lw0LmRh;C`PeEbDnWTWVwtJC{BZRG+fJdHK(<()<48u@=5t6gz=rl?sh7Dqwlj zqhOcg7Qx`&#Y|#_8Tct}B-=_&pm>}W^v?ApI4K#7yAcKT69b&Wa2?;9%2A-}=f(X# zR?5uxo?si&Z{EXRkglu-m5z4_wj=2$$p;Q9{2hMV_E`A3{*zGGcsl71b@c!F(! zwos%!BBfGh9_)%pK`q*|d z!)qKG{Fo(QG^eDu8r*y+&&p>f(cN#TfXxuQ`kC{UK%3JojfQB zdK&|%5w>|!&uimcP9vzNi7eOi!yc~LV=V2Np$NSuv~cd&Hh6PI5jL#RWA*x;bdH)5 zc%FA<#HQ{H$sBjVxCAUW#-XA@|D8X8A7t_#WWfn zdr!D%@>lXHA&A<%y)Dez--EvK8%39`m*6aFt*FmCJ30sNL+0^e^zJ8JDtSzfo6Sw2 zT?;$Vvxc&q@uMhe^Qf4_H7Rio_hRY6LrVw|{uExjmQ2$#3k6X%GTeP(GTpFV$o2i+ zoh$7&kB%0`vv?N`&Ngd0-MTNI4cdZpe=VL!SGD|R{z5fw#qi;@o4GEi-BRK5H=9$n zE)F1jRh4rrQ>K-*USO);hx32d$d8Rk0|Chf80(!;gLyBmq{u|kjA zGh~|}tXm44)a)jnZvpcyOvY>B*Ez!nmFKR<_HebRJ-k3RPZHb77qOkpuQ&KHe_ww6 z!;krC_;nG#{^6(L@5@imPqUm?ck%6uzb`+1doe#fKW;C5d)vK*I(FUgc{d2{Zc^&K z+-3N@tHbBrYw4r8!`tlc{Xk=ZV^J`?>HmQ_-_#Sx>N&uu1aq(&s!gTje-UF9ZRnS! zPNnl@=@4H{uuD>*V>&3)+FT8oeWWvWAJK!>$n^lT8`AXUI$gTpNO#DP{Ys4D4XI>U zH<)|7kytdD(n=dO7;vwa$S$*@D~77V($Hek*mnR;7|<1bbqk2;CIKBOp#nGSbI5d~ zAvD%X8K!4$B3+NW($pJD@Fi*y>FDc5@Ap-LixQJb*p^W=YNI0L=m_w$To1aZry|J2 zsgqMPy=dcQ1&FPFBDk$HmcC6?fPkx;1$*nq(!iKCP-M^4|J32XaDeJ**X(z#}&})J|+k@bq=?8XsUzt<&l2gLqdnr&H zuS7h11VTaF2Ud1jnoM-U`E_3TLC=^Af}WMqFh^?wka-4VeZPs&W7P+ibU8|(qMs?; zo1Ox-AC?OI!#SDE+@T=Z12u-5Rzw3?yXzxbkaBxE-N&U z=E@=9zp|O-<>V9PGu15Y@>r-eqvV}?h1224`B1p!BiW2=6O9gk!>mt@BtAD~1hOX+ z!0>`Ry}#EQwgkOo-qXv;%JtV-cjg5(W5UVTW>-Nfy6#1sPuuTSe~_Usn2UB32};jn zXN$+c%IkAU&4NgQvEe)zx2z|<=G7No-)Uei*823xxn7{U?-|QoD?xAd-N&wmj)I$q z7L(wcTLtrjVj;V6IcW|*DsY(<13kN}C25C>1j=r6L1%>p9d%9>^rdiZm+$g44>H)- zo^If3ZAZ&|6+v&p17=~GNe*eh5lD=j4c5OLsfU{kkX85D!ue|S((ySgV%9MDG+_sk zm6Rgaoo4~f$|ma@alDPeOc3mFrJqJNvjIPa?yB+Hcb2Qwk=E%nkg731+ zI}ehu^xovW^mG_;bqrlUzMOU3QN_~oju7jw=A`yrG^pG;PHLN-$YM4XR;l^Y>We2> zRQC!tvy(B^xPP5%+Dzc|czD&-Rlov(7q|$uSlrfDwbeaOHmqKZ*`~+s{Ud+-GENPL4XTk5J z0T6UMoaRwS_I%GZcBRpp4mWlb7%*FiU0O(9Zb&0byN5x}wg@_DoEF>j`wDxB&!%aK z>14HZC{zV-WMps#5xxt7PO|6+375GC_b)NG1Y0_Q6bigLS;O(iQ|Y?iE4j+*A~tL& zBbi^fl8D-1FxZXruSn}~HGvnIf2A!Ae=SFLHd%oA7mkbz-$|Z-4uY-?92wntA360g z5Td6~qbl_hf=3q_>vGkW(tdVCGSUn>8FR$j@C3>F9snjD)2MOTQh}NT$39fs(1MgG z@_3dBM5YMIkqx=z`z?R)c^yr!>RuA~?<{09cNCKNUxj4({RuGSLKH23VoRpiK1n1-aYZ7?iyV$hL!5$gv;3kn=5q4%G}ICH8cKi4~NNQ5PKXDrNh;qF|Aaw_vE7Dx`n*fF~x4 z1lfB!z!skg@a|?W5_nYtmM!*!Ia7j2>WeSz-Y#Dlr#FL0cl*R%hWLWc(PXkwy@id? z^@VMdmymUf-!hpi;~^k$6*|b zR>cyBkA;pyE)!$Fa%O+c8v+#`lJRBd*(!HW*tNf&fTNJzUFiX=_7mx{@ED8UHX4c) ze-MX92U&sSXs}!^P1W;uvhYnKftxNvvyC&E-DP)p=%-9s)FL+S`fwOMyDN?KOlCSd z!=Wh?=S%A!!G@g0xo8gepmP=kFsDy0Fuh5a?%Qp~yj5{suGC(%F~Wc)P8tF?Iv7w* zgC1=6@xiciPj8wLCC{=N2SJ#bA?-KpC%4;R5Lk^jp%$03xNkNB7_ilxcDA}NylmtE zOVK>W^g8EMr;X-ZWqGN<}e z+Zp*JsNMjE95A7yEiV!2UHT9j-H*oHDkd+U_5$DZKGc2WWAbjHF7$w2bkd4uGRZ~< zk`oRJ7Whr2ULP(ovMHZ@8dpp{x%tBCJvroY`g@Xz|3%LHWd)-4n`qviEbS2czuF#~ zk1w|WtL>p$bk1&ATic_(c1wHP|D-L%Pt#tTZ~?EKmconqzsqmS@sG)m+dDr0IQ;bd z?d`n_x7W6mIr`}DHt>MpF8^r*FANzdde@W2HuLyQDOQ%B1P+Q?+$P&J7VR4c9hUXy zdZ%4vla@zAEv|Za%T59okDdr`cbIcJIa=T%aD(`+T3kOxdpOHkq5mjxk;U%t?qE+S zQ&8nhBLd;U{U5CJHZ|_^U0mB>nUF30q{L0^5fAl>kt}XVPww5}6nOkYg_9bk${n^( z0`Fg4N%I^j&QdNG($=jc8rl-vu$PgL>sm(6c2(jQd3nPTs!ZSgkl_**IbyrSj3(bz z=B8Wdz*5Z-^urTr?(U4Q>^pw9UNZKh&}+pB)?zY~s`ULXOgQV##$8UJxt?!@EemgO zMq86}Diok#{4(yBln=hQD1b(Z92;KeMR%en z9168%bLV-`4M~ddy0<@5eKd;F7DafZvxud4aig)jmB3xFiN!~{;#k`*P}7jZTs?+R zjqhFH+yNmwx5$ag3|4`=(@UAxcze3gqAMs}f5bkFu%H`-s_%Gglq56jh*jvogKEQ3Fb>)Irxrj)vN3!rXLi=;QZ`NFULH z$tA0}B_tRwPy4{i*BJ<>T(PGO)>a^^*_BgBu&06UR$y1SlNrM=;%GAl0vF@@d7CTA z;Pk`n!5n|+?01zEE-2Wz(`a%heYR9PQj zBQLxoArYQ%=YV zb^)KSlhZDfggN@qgx+_!;whPX%NrK;m;#^Qr4sior&xW~NtP!6kUZQy7MAQe%@q69 zlCXI`U{)Umws$Q_x^5oJd}ju)MxG=R%X)*xpgcB9^%gm8Hy$keM1xYj92pm1zy=0b z!J2>#WYbS0IC(#xU3-0vD6a8^d3U2>j<8Cww&ooBWqOX)>?tBMlKfzI@HF@V^8{`t z9EqKWkADGaE{4juzk;?3p(_mQp{W$BkTtKcLpNf6#!=Z!4 z3wCO7H8Zt1$|71UiN&R8aP57F?Mg8u1MW-%P#Ofzijpu~;T}7ks|~W=0w&wR8SXkd z!m3HKkQ;X&*8$waZr5}nM?TGf%raZp{ZI>-@3yS97htc*cC3H+{v!mbR_O? zXM)zoES3`XK`{91Ea-r1ReC?eu?3n>*!fFJuxM903$Pmj-P8?WfMPFrCHIVlcIXI& zPTSdft&wnJ$2xX+$92K)Z*w4fpBChl8A8yqdiK$C6`QGdR?r|712typY=GTvf$N7D z=yF^M?k%%~yXP8NO7Tbb!SVz%ST`D0jF*Ld8Ft`O@QQ_NGnfblV{ioDih*i==MiUHOLuOA8lq@ zbywKBXSdkhMc!aD3g@$m8V>8E-m!IWkFZFIhipZr5B&b^%Jz+Hc2ba<507eqO)?q@ z$93Mb;U5RE?Su2391G?{SYto7xq5-q#Nb3w3fRFq-}i!SzZO<2zm83r{)$Z+J|6bi zu3|622VRx8u<8TR%y;7_b}iBubSo6uec3d}hNbwv>=nmUoP6QQ#t%$>+%N8lT*ty? z9dN$w{SP_%_-^5@*ks6fXvyBi2EfX7`0ngs#cZzsV(*vw!Ta4xY>-YMj12g|cE-Qu ztgEG<(^o%O&USGoD?)_J%~N1~?E-G&oHfFxSt+1uRVb{BUBxno5 z0|WJ^k;8*cV3Un4s8$3J4{K9UsI!H#Ieo};e{)DXZwqqw8U+pYmT=;X4ZN#cB9K{W z1Bv^rAiDb=r>SoC;IYvhTubYO-}*U#@_G}v+OUaBRuaIjB171z-oiE9p)mEE9(4a| zi0j7=0fo4p5O3kdFL@0jG1 z@z6bQ49oufjipKX!H(E&?B-xeuqyV06?dL+KRk3HCD0Wl_x9ri`nLsHk;x!2D4Tok zqX)Z|xk8l08t&AA70e<#23Cz)Elm6s41Lu;u#kO}Q~#+4(#KsPX_VW6c~%}(BY&P^R0j&rT>s&&NA~;>D5AU0agpGB zEfPr?x@&gRZDBsX+ipg8osI6Ah3?vn?rM(idIsI~A-Zet)e@XFx~mtu>uhXy<)OQt zL3edMBF8O3cWpV>fd==H<@%w!_D6T!hVDA}ek|>LUB=&n7{ zU3Xqq<@C^9o6ueTmHTi%9y}m`?kZ1gxK8M=&s+;T|1TNakl8L5$LX# z8vk?d+Fo0?z3u!qaCr`~t^XRVGZSIuPk@o!tfrR-wCkqPxaEN_HBG?rMVWYK87P58buMw2(b_aB>=i?s^m5bsM^?J-X{Q zbk_suu72sKghA-8>(E`}(OoUjT`!`$W}&+-MR)x+_kzF@-8Br|^;et$xq|K*weka- zkM6qOpw(R)(Os8Dwz}(!v|;2Ey6XUR*IIPfVNY7!bq%^}AiAsa%NBM5-F0G@UrZO> zRqt+t;LgWZcm2w3Czdb0VBqQ&CizI3816618-nhtj_#U(?pnI~J+r;l6(^`U>L`is z+85om7~S>Fy0`2my6YvG7c3Or^$@yi-HO#t$I)FGx~pf^5YS)I%$m?$U!l9|qq~}5 zx7Kav3a5kUu6gLL-_Tvv!``qp=&qH;GJ+21u14st`unT_0$;Lq=&m6fuCv>m7dU%_ zlPyiIf<)1HT6EVn=&t_c1)G8HT7mAm2Hmv;-BmI*QecGc>WA+78{O3z-SsoNYv;mV zuzBw@b`#xoknuj2jqds$-8H#%t6(0w>s54DRdm;(=&lCnuH(>MyP&)3p}YE`yZ)AZ z#4^xbOVM55p}USicdbEp{pt6B4McZMMR)z}J{v62T?5fwd!f57M|XXV?i!5lD&fC_ zyqAz7*U()Dqq`=zxvMq0YwuCbtS`E&3A*bjbk}lp*C=#XH+0t%=&sk$T|LoVFQB^) zL3h1~?)qVS66RPq4uM|XXS?)nzpwFuqyb6-b+A-d}vbk`T?uIcEmd(d51p}QVIcYTh} zrm1c2dK=x<4c(PPcl{(Yl?EhV<|OMbvEk^hUC>>9&|SBpyPh##$w}7~F&A{#E$FV1 z=&q{hu6q@AIN6|!%m>}oph=FLMR)Co?rM(i+Kle1gzjpD?s^X0H3HqWU!8r0Iw@*UmP z7u|Iqx@!fxs~NiMUFk#;i|$&0?#iLNjzD+ajqZ94-E}6q>nwEFuPSSa8M>=2x@&$S zM=H==-O*hKpt~MMcb$Xox((fR9=faEt3VoHnoA_uQD%njYK-n$gYH^@?kazvh%82T z-H7gLi|z{OuF>eO_d8UO_vo&x&|SNsyN*M5-HPt|ed|jiwM7RS(Oo;CyPBc9rlGrj zM|U+tch&3f?xcY3nvU+e72Wj~y6bjyS1WW^Uv$@abXN}DwE*39Il5~jy6ZM{*D!R~ z#ptf4jbGS7bk{lPu2;}qPoTRFM|YjsqlL+#yPigOownpHyL@>(#G<=KRlH^$(Os9L zyM9G?l|*;VMR(nH={~zW)Ccm>U3I%vv4QBW6x~&70+yYt-mo6s^*g$&A6nlnbXRvL zAv=Wb`V!rB0lMojbk}$2u7}ZGH=w(^pu5gQcO8!IT7vHS4Bb^1-L(PT^)|ZeXmr=H z=&tL~UAv>ZzD0LcHj7|R=&tM0UH758+M~NpLw9|I?&^u|Dnxhf9cjQ4+T3*HE<$%bp?A*d5xQ#!bXR|L*PiIEuIR1? z=NklJ=&q;GT~B4}5{))@T{qi<;9_N9fbQyz?z$e`bsW0uX{}7+hwd7J?m8LWH5%P@ z47%$#@6&{!yDFl))=$qTGtgZ<(On-}Tq51jT@%n4Fow z>#gO@WDdHk&-{ae)#$D==&p|Ft`E^&f1tbWM0e%TU3cSuu`cG%-1VfW@H2iiT-)Z^h!{3*GO#X4&bJr_1|8dvPTcubP zx~q+x7Dv!sQ_)>bllyZ;3of!`bk{Q{t+|8fu6xm4!#0?6UC>><(OvH-X>lg#u4m9) zzoNU2MR!#^)Dw=%t8zN%uF7>kSjQ|i?n|4y2BW+7L3hnjiDVqQ>sxf!oZl*3<49HR z7P_nZx2`02t`xTl-Sy|{m1H2g>riyp>*%i2&|S08U00#I_Wv%!C8N7qqPxoCJo$;} zuF2@GhaO6E&(K{zx4CN!x@!}SJ7Q3pu0w+yDFf&zC(B2itc(J-E|zg>o;`Q zrRc8m=&t+GT{(2uvFNVGZSGo%?po94uKMV%A?U6L(OqZz{vzt=u1e^xJJ4NcqPyCy zHxSN6cdbTuwL^F9iSFu&?&^i^`iuP{L(yIH(OsoCRbpT7VP-YgA7aN}C6CZu`=PrQ zqr1kSyRJufZHzAV^)o;`QwePCQP;}S6j$sgFxSG5{cdf$L@!$!c`h&*-j;(OnbKT@RwW=DbZM^U+Y-E~o6m0$z9t3>~EtODJ27P{*mbl1U!^8~)= zu8HWb!_ZxQ(Oq@WUBl2_>(E^Zy6b+e2f_>Jt}oGDFTHXkW6)iF&|ODbMsnJLMJy5B zbtJm03%Y9sx~nm|s|LF3SajD7DFxghbk|Mju7c}I!~osZ2HiCU-Ss!R>#R0+eT?o} zh3@Ks?z$1(^%J`53v|~Ybk|qtuFB}HkI`MxAD98U>oIiK2z1v#bk{0$R~>X$19aD) z=&oW1z*8r^j#x@+<$=feHyuG`REgV0?S&|SNsyM94; z)j)TxMR&DBca=hSjX-zpG5r{GMR(nf?s}}vT^-R~_1oOF4Bb`c>c8o zA-d}*bXVHut|QT1rT;f~9f9t8uFYMu+T3+ro4Y=4$6Zs~+*JnMbqczxZJWC;Y;#w2 zbXOmA*EQ&_v(a5Yp}QvY-1Qf_>mGF1OX#j0&|N!utzzGG&kCNQyEdV_g6(dB3%YAp zbXTqAme3j9bu+rFmDLH>1>H3R-SrE)E6IPwcB8w_tvS#3pu0w(yDoSgE098Wtwnb| zjP82&Z4=WEn#MHkd<9?7T_>WuCP&)|%F$g1pu5gMcb#^mnR%eQj;P0Vp3z+m&|S&Y z;V@b99TTFvQptzR9o==b#4xtswb`jNx@!r#>v?q7WbOBCGrH?hhkU1j=&nc6T{FrT zIQgTyzV+Y1CZW5g`?j!e=&pliykdIjt_#pz1?PR>-mMn)4&7C2(wd<<| zj`irSd(d4cqq~-G_`m|tU8g&BEL@82IuG5|?)%-s9q6v3&|Uk)1wh@}53CB^^$WUd zKDz4}bk{I+*PH$ySUkGxBy`v2FMenn8EZRoD5=&mj3uE)?_SD?F=pu0A$Sw=>nyBcb$mt8inra zh3;y4vrhO0-BlIcb-?pYTmrglHoB`$j~4DRx@$DLt3SGHc$>Rsp}TfMcctjA@@?+= z7~Rz$-8C59)gRsUCc0}jx~l-)wO4*V>x1t49o_W>x~n?6>jHGw=>GUk8@g*bx@%Tk zJzIwEYKQLH!Q~yh^msfNqPvEF`Nl?|yKY2x?KVUbrv736(p2p&sXnVD3c^2KV{qX%VD;+28 zboh1(T_>&jk8c+E`|{gw{FvW<mi0yri}emjpdxpb^%@H_LHqU|AK+mCK4CZB$)njHgwJD zj_aO%AP@T)LEWp@WQ?>v6|B$!|4~=T2R$pgeNj)4YuQDD_eIeG9g^79^esdycM#p- z(jCsO+8~&%Y)fBvuz`bhU1>HAXJpq181lrBYJ8o9tJ@ET`w@OL=;SIk!oGo}g$L7Z zbpzSm0neDr)&4YL(OJQ)EC&eQ6-FO7yKv)vJYwDK`cWT;43d&+2`djDA)4}|NK+y{ zC%Kb^WzHgD{`j5i@Ux`;^)|BJG6ar!`O|ohOtQ`G4hyf+rKKIqNIwk|__=i)Rcby< zrk}gbia(zsYE5W-~~k)oD~4$%KY zBb!&UhxBkWVZOrYaDV7QGQG%vZPA(z(h}cDMujP8uUCXyt}jUaUJ1~Tbb>pkP2}nJ zU(8t336vH~(+B z=T2XB^7eJ=MvPo>EajxS+^%=llWjd>AP(n07p*nS|H`GVj&1A@8#!k=pfA@Yx{|2JG)i&Me9k zZ0wi_=4?Ol9+ks-^qP$8l{OOdaW?SSQyxw)+)B*Wma(&4C&KX16J)8yN%k^42-alc z7)U8I=Fod4EUPdg`z6jf!946Ikbh75qN-zB*Bi+WgY-p4>{tD5CLCcll*F9+}uh9oA$2x+~S4qgY z^@0sHU(HU=x+d^kFc)$|JRxgJ8PPW{XO7u=@N3`=l9Ffw31LPcNZU&$PB4dPl|yXH z+e#8z;0skz!EkTqKo)BAjP2@f2HoWz3;L`d2s>)}!Mw7^j!X9t$ig=D_@WEM@2fw| z+>PHRDW)=oEA{MTcU)t-crUB}-N39)>VwCY3hw-~p>Qhy3`?DmLxxNbhWICE*cROk za_&qh$PYiwW_(R0v+z5h#()#7>RlKa>mLcVUz9+5a}s-g*bN59?Pooe%t$xG>0piD z9XC~_P@Rii#dCCb!!d87b!kO&ApD=cvu^LdIB}&WR~RvXX0EY>qQ3HZPmfHc(QmGb z*Sh^{-fw+8<^}wAd&QosY&?FueFwkY{;=Smb29MfVc`E3KRy3A{PfY^htVttU8>(Z zfD8H*OEvc`BCB2x7Oy$0HntaAfO&Yl=dZKB45R5S%qLF_!tK}K_b>PUx9`FE`HEj( z@#|9lI7WWHHCi-{uHI?mG`E?tj*o2Vo?>TmZ%lu9UBHoU^cYbWOoXqEdF0!kVzP6h zFMM;`uvOUT0; zxVHQ8$t)h{Ik5TcNNeyLyFRZE3*1)P(gmXTZnueak8eIXa_}@ey9K|8*1t!l)|_O; z_D6_AWdoUU5FH-ZDd>jxBn|J$I$Wo~JAZ>P)l!-3^fQSXm46fr*r&|Bb%~=%xE^Z_ zrWvtp8Vz~o=wwvMSnM-f8ffl9I^lc9QXxm~jygtm4V?Io=hOyX8-O44@8_;hBWd62 zGV*@MV>Y4X5&5F^mQ3pH47Z00Noey-b99eo&`8mAVC)lA2X{tnnv~iMUopGTp{Og`x#r*pNdGm-PYV0TEQe z8OORmJ;P$ZoFa=m-y=04J`gfBoGMRTL~J&lX8GGp>ElftDO+m*tobFmcKse1Y&Z;7 zBt0Wb=QNUydMHlKyJ)o*smNj5hFd<3I zfQllR5KvG=cDDfos2IVBISUA)q99;E1qBR8F=qsfASwvV?ou&e&WbrJ=70){%3s~H z)j97z|I7W~duzRSe_ZPvKAP(4ny;&?YVVopPCL7fBo|o1tclI&z`ECm^$@ZYS z`!l_PtpSI*4s4C9ygB& zqK!y5_AtMzx_WDO+8v)8OZYHe?egt2DQJ)TzVr!a-p)r=ZIaBTcIQK3?X=e9>|nLC zXG$=Pa-2#JjVevLX3b@75(ZL_?_Vq{;vK85zNDIl34D9Cz)#`ZD zuj6`1BMuy6X9n*e=iKZ_{T@D0wL==-kD5X%;rD`N^D;R2t8ppZWDZb#eBUQqI@Uz9-Nh z{=fF+@3$sfy2C_cJfA&pygH{t5L_ABi%s0pO|8PSVjb|TSRMy#N!twW15MEfcFeDu z5v}ooIkhAVqs@9*|r*ci5q@SGmhy9 z-F#lMfuHWP8iT7t+^D|HKD;xe%#&E~ip}K5gQ2jaK{~4$GMkjn7!6k+?qlkzUZlC> zc(A^>i&<4_L%NLihKa{lv9--VsYZ{R4BtHVv+8CySrtzYaKd@%g7Z=hpOvbW-wmHH zkYnkzkN4Rd6FHVDxeZmst-pZi+EK>9GTpZQ7Ak z#F*blt!4$?$Jp@ji_@ruu`63$6f~j?PxfF(Zq?Jc+NVJsW_HGx6p{tNi7|%C` zK4vo}%kl8YyB91aTaJ@6zNE0d738?uaD7v7T_MNPr$6wX^a(j8dpM4REGoz0$b4}n#cev$rlDJ|V4$Ag`%6sMb z{9iZ5b_Ph(pb+?9>8EV!CYlbV%f6uMT_bin6+LZIC#7ZBywrXwK&zi@lX?p6Y0v9hOjEMX$Wmh7C_|u@2KsXzrM9tl4cB$jq)KoqJi*=D01GY{MEd3isae7z<^( zNMwEbd}8e}3Pzvvrcq@YsOL{O%pli+x{q@qJGxurGbC#A;C>A0erp8mo$Nz1y{(+W z1_7(J$%j6iY@pKFtY&1pJ)JW>kemo>49#sAd7QP1_+x%GEA*yE9WSW@MrE+QTFvRK z*j1!~w-uN-WTcKuBGKyk_ zZ4+DE3owD`-E9D-tH)ETH9d&_>jUijWr=*~kV;mZ9|Va8#?$1XVSlhP z98NdPP9$VXGJ9S>jWoyHZ8@nQG#ht-oSAxsI7fKGM>8+#^+`?otlPt;BqkBB?GMSe zDt+-?=3OLl(Q`8W3GQ()I+4Vuydy(*^@3N&Hj%HZzLD37JwUkz!B(_(3)}z@#sCm1HRJziFxzry3LEVjM+0-Cb>Ud|^<5QE? zWc^v}mX2_Ejvn1vcwSwB^?|k*4CuHy$!hN{z2WOuBijGq5_P$Gz2N7$_Lng~mcG@4 zc0YH4t+{@c+4(l0wOAQ8by-_@mbQm9@pB~Wn|l9kKR4xkDRG0!a*cfnb=q!>ax%ho z))4F1z=>{7i?EKphM#2;PF4T)S*FH@ucXE!53ooMWAAJV$tP144BY&R-MapYoC>H8 zv?AUwgL5Ql)LFJWxHou|d96~P%*ve6DHO^Xt{`(JUR8Yy2oSYBe}A(l)@eU$^?$Yx z?a%#VmG&!fA?{&2Lm$s)G%W>MxYyG{wEs5RKMePJveE4IL@HKq^>f^i@;zbMt195d z^H3uadyfW7)vC@X-w|c;MoR=fluCl$p4Pd>x z46B6mvj5;7wqlYa3B`G7aQqdUKLbBg=r)2AriE-8eqO5)_lo^UKF5wsI?I;N?2XUM ztYEXhCdbF!)39roM_4uYv5-VEJnry@MsI>V{xmYRl^IW{GsDH@l+E6xGjv<3P zmVyx@*g8v&8%NIC zLG>6pw&;{LgwEUL*rHvw9xPZb$D*ouFM9S~Id&~|!}lt$6tI&RyB>Tsf>`wubwymW zmKO{lb%DH=x6aXn$66P}8u#_732zR`Yu~oJF|dPjOh~#_#KvEfV@2~7U)bY5atvvu zlg9=|_hiW!TYk<3UoX~UYeU)|xy~8XxfFyA-Nx2qom0C>B&$^**ExUkRptEtN#;*6 zUn#Gw$CUCuyHnY^d2$`Nb3h~5pDfph%JT|$-fItEk2ZjZSqADB?*~BdQu29)djcjw z<(B)|1Wi+hLY2O7ec#JkK>dnH@= z;SL@*9{?ts@O%9snWW;CJuH2CJs9}xB`LgI8#b+J2uBKxPBL!Gk2VV9Ih3Vf5< z#m1u`K6g3kUpIx#dS(szUk?z&!4?p>aU0X_`iX=-?g{!9<3XqN08(wi0T!dv9Fl!j zk&b>=@MY;Pc3Ss2=~0OLmVB9j`#jr_uHEqYs9i~H!{&$NTGhVLd9ye81?8!V;?h~T zy8~QkIf9%_XaZJSQkV;VpZ2hW2YlU=#{6cVB?S`hb+FI}8g*{t{P`SXlWbbT^Mv}O zm$?lD9ZY8-=Euo1odIB3+6Q`e%$K_49%66KXEOUa5{W%95GLaDS1x@c)GMST>@zsv z9qb%c5XJM=yN-wYll0m9F~`}wD=pw-s}`!pw;W*U6?}flZ8w=Z)(fhY9t)+N9hqNP zHk;dtv7JHNi2Io#u)o|WNFOtb4Lx#-jW1&hi_WJ?;b&XJrh$xEtlU6Olp6+#W7Vwp ztr*ha_6V5VeK4%m*}yEPoo8E4G=@8{UA<<$3eNSESmcZO#G>0MaQN5{ysqwLJNI2= z({W$gx-X9~=lILa{JI4g;GXSTC)>i=qzqPYeJaz;jqC3rzMR)%J~ps^2?+zg<4-wC@J%AF+?EEaOh{8cYDsPS zPGsjZ>yk+Wec}1tt*pGO5t(#m5}1590JF?_tmTz1uw=tVzAu3|JE`K^;DbLuKia+f zjr+gu#X)G5sce!agd7@v~QpL&GPg^qvrO?)2T ze9H$+0wsaJmYV^sR!tDN*PbxAWmQ?6Y2{`a0&VJ5Azc5in^WOUY_z~9UXF)_s`COr zbm#-GhZ|BZ(`I%X=w#STV6}N|+;`YjV0%`;CN7uHOy55?nPoTh6YVgzE9;|{&$JqU z=ahQcicrz62jZ`u-{!{P0v7kSYmuZskp^d8@jIAsF7J?pML-TlE{ z;Jy1y=xh_9Wqb z?_bwpbGFIt-J`={T8Sr`o6&N)^4kAXdqGoA+U|qy z|7%~ROkU~fbX}KV!mqtJI+gPK3PS0cCy8SH{#W{1be}-+z;-b&%4__Soyu{QeN$A< zbQFHa%&+CY(zn}^JmR1=T<9szSW5ZKSq+KhKsnAR?fH|;&fyK&60U9lndHz$oUO^}fwb(A^v^X*kwWmYX#1|fcsNZF52q^P;R=k0I+}PG zqlkygw*9UZYcB};RV(&Y;6)02Sb+-^xLL&SzM~X)tpXpY^t)Cp-K{j!&60DIvGE+X zKvOH${dkzIIV9(%r061+5ijSatQDp(uCJV%T2yHTvr^?+vCrPFaQ>WJEAAUT1U7z< zYen-LK9D|Ft`+N+odMg@lba;^C3_EgYaAlHgMZ^pxNJGoZu z+PV+C8*C_I{#AU3XmlmHR&;Do8%~Q7?5klG1I-Mado*?TwJdU^%*YLiu0pv=maylR;)JNkY-rQ zwc>l}4!O5Xt`*(lV##=XK8xp$zvi2eUYc6bb?q9}M@_A$M8&D{93HcE4-I28vqITTv@IC~C#S7>_t_et)PHQxvsgA=Zl3 zG_|6&qE^&V)QZy;wc;MEg;r{6Atj!KwNM#NE%c}MLac?HHMLN2WIkdoG+$E-{j2i4 zPB@{dh5jpj>tQXFt*M2S*QmS}rJc%gm3{YMEi_J33;kF6w#Qn?QBe#1yv9F`rIg=> zwUCvj7E;>tCz-=o3;AnmA!T1>dkEG-A2hYlpW26GE!0F)3n}H5?ccE$s;#Mo{?yLv zjpmwKs5mnBu@-8gsfCpKm3ovi9k3QkQq)2}$NH1ZdaQ-)6}8a6A|HaaP$f+*R2=fA+3UqK>XBdarKxYZb4jTJwPeuN@O!=P6pYT$xm?o=U z_vB|ugIjJ{=vZz)DQDaXl=q;O&-O<~#xXC=wdkBT0jjx1Z-t#z6!yqa}+e=d$h zI$kDuRs;X`jEC}Ge+ib)-7evwgohFzDDi<3A1LvG5+5k>ff64m@qrQ_`0w=rhgZ{} z+}!!ZtKgh8sh%}l{@R}SHEsz}XZ4yi-Cj|AF3Zoa3I#RakR~r1{q3CvKgDOCYKqT9 zOWtl}3zE*0b&c_i5x2e&zvC0hKd_9IaW{d^ehQ{i<$&0bQ18n$c0To*>kv5-b3iEQDVg1S_(nggr zBn{~WcDt5HA&p+MQ&&fTz0VRU$7mNDXXFpFUM`mIcId#II|M_J$6_h#@JV&!v`|=J zyjZ&bzG^F-&tbsFz4G=qR@$>N9nbVlxxoC(m%{m#bFcW5tYj`rl3zh)<|j{qmM=dI2z7GdlUQD~38bqChZB^c(SJ+HT( zR7avci_jjc`qh8gQyh$T(r01e;&W?pFzQUh>!tj9i-Q~9d7t`IzRcqka_-V3YV&om z^ki0TI_7H^x_6J)WqJ98ed*4)j)e{&64fmxP}IIsQmGlo|AR9j&wkNw0xRO(_#vo0-`Hck$t<=@N^*Hs)`9Iliy*JlM%uQ{^*;^5+NrIZ;_ zDv<7SnlJ1x4p#Op4(9%e^Dfp)aqzOtDRlX#6~dl`FTV8Z@HFyvTeNil58>6Qja$4*^}4+`nq9^#8RHKo0%i2 z=iX@P>g^g3*S$OST^B74UFZOo{`S$rq%@2U#;3E$Lo1g?@wukp2j1|l`y#28?1;aMusmrn*zPI?&(Vf6`2OC+#Cq@; zZMZbDAuK%J7LKD0rk*-b7%~u|&;}dxBdk-7H!O8uB#k{bimeKn0sGO01p_Xrr>qTy z+i1hM$u)o3usznE9Q+UrOOs=y@Un~q?ec-h9x+m!c?FtM7x&)8wcrS-~a*Yyq8~&z#R8vLY;jUTGO(Y z&ftzZS44HE*A~ei3JigKs^aN(VNK5%TtH zCeYy-XUK=lD9NbMlMZ@ak$S3e?av~#`KQM8YLf_Qz^*!UlztcbX2$~Qd;VuK!C@GU zHjj`xb=*xl-SVRzGa{v~l{`s=dl0STzerMjzoeRqds8QdMN5|XEmaBo!{~>o7^$X{ zTjqgJa*V2_z)E}kmQA1^@0=l1r6|emjVG;BN|$Q0NNL(MLN{wQq4kVqT1vx~*@evPFBU zMHep@|7o3C;2J!nS%W`DjcK!9b6u~(zN%kT2&EHZVAllq^1l!J_a}ZPXp2q$;r?;L=c+jj4^kn*G~`kvd=1XLUoV0ouT7Ml(;e~mhEimezd{r;Xv54SDQ9L8*)@w z$C>RUPgIf8gjqA;!$m7HAJ1;-jyCM#dNzSjH&@P&#lcvs zfY~fr{(R6lh_SuKUL?dwYoq$Yl=b@Xx>JlaXpS?~v9yM&O=6^4X0>6kt1HyR^*ANz z1N$;$INaS9BlT*Xz`S4j!?MRQ(&q9iHgj<>T=*6vEtt4fU8X@8xFU88KI|+#l55Uy zE{C0uYp~LWCo{&u0(;qp?Th-toelc%7H#N+Hnc<=s-X=FYuAQ0U0k6$+A!MC|7CKxW`xVz?TRiCg3gRY2+vzC=IV?X|mx8o<H%$MP5B>Ho7C&KVBetM!V62p{9@)w?OJe zN73w*XSg4Agmk!U0JTWj#O~NfN+H`r=)kY#*~l{J16g5IDrK%RvyGNk+hRU%UyTe7 zh><$3o=&@;4iK?IiM`+dw(Z_SJF>%QCN$^~EuE|vPu`nMhQRWRr1~~mw0w*glzJE; zHFs!AGlr^Q09zpSyV{ewmaYPCQWr>C1!L*waXBn&LWGp3J(Y&lSk9{WL`qJ!p)~Kn zJ9YI|i=@lD!YIAmPPL|6v}A4&LX*@rNz6>)ZxsDa*oOZ0Px0HkRe#mtP8F@$h|V+V zj*l@?*~i=2uqpnueNl|0br{btnmmZA^{^gxZV4Zy7PQgV7%At;04VHMmL{%=kwQ25 z!hM@`GWlGz^yTAB7~^9~MwmxS&t8PVM4MI8o|tIKe`yG)ck8mN$YE%s8Q?j70^{|+ z5}&yJ+n$v2)+_++*@^Z<=i=EN0shnl?YVih3{>?SM3107-lQd%XSSdX(Vo{Y2H@V! zW$7BUr_)wnSZI!?qM$u@(Vp6VreqA-Q|e_HxWk?{Mut2`AR~%d%ol2RdSm*a`E!X+Q!PxiLycY*|e%hA0k%l6_w?5FH z&T3g6jyA@+V#GMQYt1!gQYuDzTQ7*_TMuA-jquNEb-Pz-#pjn}U4I!X^(;NupEk2A z4_8r7+VFAo!uo5h7V0@rCy0(4KY;n8o?aiS(rW%aXqEgJY1{j%bQ$8Rh`G*_m5hb{ zmv%Ghf}&<5`FXT-%qM{Mb=p9#7ez^C>Ou6jOBp)(NR-s&T5Gzpj4d7bFk1BOVJ7z- z?l6-kBsC+k*th=V0P0g`1380zLkSpQNT)p(v0E#+n->?sb0BuD7uXeaC$ z>Fo|P`&XwXd(cmA;=8?_pO6!CVx;OZ(;;v66f%;Dd4$pimD4nS0znOA?2+sUsjXx^ zY?3?V_Nh*5pq|KEqo7}hCnOv7+>DwI`ms~U1dW~!Vbz45OT&X<`kA)uNJxxS&1y1O z-NW~*O=F~lMuWiINgH&GVx*0;T0^>*EolE0BW3qCf=l~*i)&P3^f5RXAnVK<8Vo*o z7Q->r8EY{aj=q+4+Tr&~s@B?25p{M6Z;fZS+d@s$`EX-Juy5K==qwKYSLdbK`HFPE zUO&Neaj@2fmb8*p3t>-ju+k@sgD3Y>!8PZm!k*$_&&q*xn|hweQ^mo>u|X+g?;c1k zwB$Tk9IWhH9E>^v^^5#f99$foN|`SvfpGiCJod$LVSI5g_WhUEb&nl(P^-P8@P~k7 zrm)Jx4Tdkp??8?fv8Cx=Q2u6=wC-UV(|X_w3o1lQ4IXu5E9(VAIgHP&-4XS|bD=OL zF-FS0wl%W_*1mlGK2>0)emk`({21g00jR$SiddaYFVIE(^g|l^amN>8P=7{^PAsoZ zFf>5@Au&hPo6d&9Jk-DX%5VMJ+U6wg_)IW;9wXiPxQ)2hpA7GlVx+-e%g~BF2f>VP zG18fG*0lKsXBgiAYtg)Jbc{z$Fb~G>H=+j7%PY!2qq8xRy82k^WqMo8of2o*+hfL1(dXFeJ7aje_l%FsynK`Z--l9(|Q zaQ|O@_3n^fq?u0;jYJ%ddjneX_s=;?O56phr%BV7OC$@+9(aBI;%#W0F=tTb2HFlK8GsimtY zZ1CQ2n@EoCLZNwlvGqr~9lDABjvvCpcd8xDwegAGPxc;#k7 zzOli2RSsl|_8w}>b$Xnl&PI(itGHki#jZFQwMIYDW_+9bpb~Xoeh~q!<3S zhj#A8ghmrg^i%$`zUKd=uUWqtNww-b+3{Q@sT)$uLGj+^V8^N>Rp-7%i+tt0zkru7$QcJ{mQ z=kLSjv!?eVguF67DA%=ey({B@5-VkteU&ESARhDIgA~ zhtdwGL25BCjcDV&kos{^(j3DPlM;#ns?M&nmQUx*m>&@jBEKS}G{QYr!#ruZ>lL9w)NAKCM*Zlm#EP&E z>zp@d@f_3PJ;CLODP2Fm6rB}r0v4Os6QhVyw1ta1JbB)p4uSg^mp`&5n5%=Dl&4zh zZ`sKum&so{@<{rjPT)A|5HT86j@~-o9!>^yr5Bv8k{rW_Y+LWv)b2zD+V$IQ)>jM9 zQ8oQQW>$3py|`>r{$6?dZ6}4Lm%~$U;QsRa@<&6JXN9TTr+d;~Cv;(L(^N7I=1s3-qFMM^Hf^+ z;vN~>VhlVx+g#dt?#cb2sa-{CY4VqJ zF%x~U@eNX|@S4=b*$=|PlSvPkbSe9kmbzoACpEOzg>PkI)$2cb(0AQ+@w>ch>MhxQ z=`rMI)#<8i+JoM7M(awjN+Rql`a^%*Gj7V7u`H_)_wFyH4;^|(veV3!UdYjdOM}-l zo5daJun2vyZHH$gPHszmlMLXC!BIxbwxNeJ4Z*6_byh#eo@Spg0?VLWR(e1)TFuZH zvU(S?AO}lokx>QCe$j!0gKE=r<*LE0U<0UJy$bD^Rvq}B!gk5JH2+dfFx*%ZE;yE@ zKepF`r*rGV;q{-$#=2%;t9Au_*N3F~#9PdAQ&%`s{v$cG6K|Oz=be#r9H|G&FHMRI`QI|Eg~NF3>lP|{y9y=z1_8LBpgai+QwsG<9jpHw;k(!u&5{u3gd!c z!Adz!jxKKv4lxF-LF?AgWLp@#8ZO7WfS6GHOfAR27t97mKK)C@W%`BLLXQcR)Evw2 zeDMGO?|b*5#I}-oDe-|4A1LvG5+5k>ff64m@qrQ_DDi<3A1LvG5+5k>fqxGl=>DoH z&@^Xp-)i7;Hz++texBB~+X#qucq{HLnvV#;XZbb=yvHL1wz*XnxczN>CTiOgXMWH0 z<-;IYecO$2To~gE4IhUCjG9j*ar>T3L?pi09bNZLO6$>b=0*Q)8?W3Y+kI zI`q6ntd(}zIRcXf!B&YGs|B7qx`P$G-X(A|Jrk?x&Bc8^8b5fw|2j6GmOSD)9FE zx`}g_B?_EpW|esN>uiBvAF@e2Tt{Ev8ErZwZto|)bEECu+a(@qeNSBbywui-w)gz4 zxDBzFoDz*^922-Ku}W;$uvA0d9@BEmjzFEgjXBQGnn(0BJa0++O!jS%`G2ytF4fh{ zi|+n)Y^&~MF&BDs4dHdmdyLOfhK(}}^fVH4_qtLN+fxD0pT_x`?`sZTaXW-ed&l08 z)bcLl^V<>6wwvDalbXwH+h7g5>x~dH{i~0F)~dgR%+t?VtWKX1LgsUtJ%p!SQ1h`K zdrX82Ps#}y{g=ns$E|kGT#v)NmQZkUt2390+~WhGeXlz6v5YGpVXt4VQ*oJF1#$Xgb9Xkg-j4@0Zxe~l#ew-9mG88Y9X_#%`;}* zN00Kc?#5Ju&J`SmOj>q(R&L}jA>+1rAKU$jh;}adL%%jXM?E@nXa*?aL!b+P-D;Q zn;XdxjXiZwv?oED>$oSmn$O{cWZcfigs)ir!m};~@!_U#3 zE6CUlGSAn_R;0;BGS5fUEvWu>ndfn_+sV9P@_d~iWlGBj$@7(!*p)W-ljkce;vm^P zU!Heo>&CSDV0qr7*Lu;VgXMXDY;=Uoc`N%*azS(YBwhBO$p+)8MWF0I56k6ek;h$Sf3AAap5`RW{;cOYkmql9 zHJwpMUKdH#N6`9hit;*LI@ge{ za*)^QXj^AG(?edTCq|c!Z;1Do&!5G!A(rZpS-4k!P_%)1a8Nk8g8So-%QRFs$jc(n zJ-q2#YNXz#twmqV_M$EJ8>$CfGNC(OxY2R54Ahlyum174|7y}Jef3M+2X#lb3Eg+d zK>ZE(egBYKMCR2tQacXyrnyJ6$l7Ehb&f?K4Ri@7YmJT6-aA6*U3(pTmJiPjL|ZcN zR87x+tFQiywzLb=VQ-Hbs6XPl0Vl?Vvzv8{)P?=LX~MHCR_Tb5IudQk(AI)74o2$9 zPu=M3>n5<^wt@OE?$y5<_v$~ZZ=m+cGNGkDyFuga2I@q#r8VxQ|M{Vz+WkTnDdpu2 zRi+rJ3p~QfvU-8A=%b-JtdkD8ussA0pEgiO<6ixxaesV^$_DBmoepgKjL!+&#OElq z@>fMC8&u=56y{F5(7-6$Sm485yIa01ttW7@L9FHHkEH}|_u`Nx&3(dSGVq`LcaHhr zxg5v5AMejG*T?m8%*T0>uv<^jF7B;pf?An+qa<|Kjq_bJb_V9JdP(Y>W|0qevTW@f7jTPz~wmR{ct>ixjr0E*w4rL=&ie$ z%V^rg^=jlT6?z2bxj`=v8M~-7NUjCY|DS2If`Fw>vy752f z)F01b;cMX}u7&k@J`2a$h~He)VXg6uhEVhex+0v_s1*p8^9`U?&==>){^Yj<_fJ8T7;2xKDX0+^>8j_s@l15dFM}b+k89 zn+)-Ws;9Ep^+QJL>GcC4#yy=V;;BG6{LRw!(_Vh>-fo-}5u<@o=0-JY?U_Uxo2>cn(;fX6NEAX=J7Vx54guqWvHUYa=tpx5}&jw0W z%2)BehP`cJOz(7oaX!JlO@jp9{;8KOJnWyY=2#;ya5Cx{__h_}?PxD>yE#T1f!oTl zR%JcNUYsM#L=>{A(+UMf8yUBi%iJuJ!bW_mDe%S)5v+%cg}@pf1YX?Bk(p*S5g6@N zb31t7BNuz7b6Yu{)j3^7@ESPg*Ys0n)t6SJ6xzz$Q77THa=hI%f{f@UkA?OUZZ~gF zTbM)M8|w+Y)xVH9Mawp$y_DO{Wo8uAq)onPuF=(k7B-ELuMy|%ClB;Q6MD|rQM98i zl-tewe&}gS$HdBf@^!PW--Uy`eOqr^TF^}9Un4K(V)Lmcw8sN^zPMlTYvA(S7r5OV zn;Yp--DNofR|+pAmx5$};J(1^<}$Ym_L3!NH^&$4BgnAMvR`R95$)BRI+BgYWIxn! zDB3F}rK=XA-MnwJuHn~LkY=%qa!jQQ>!uIsy)?>1w;8*s-!{T}n(6U;G*n2(xa zzI%xIt}N!Mige-_@7bHC=tRYWgQ!*IzXGt~svLLd0UAPeaXhaXSU(<8Z!s`_@tQf6dqO(~B&B z`uszW_P^$I7@iHm+bwY|?1|r)UJ9`l;%}JmyfEK|p+C4|zH`KUR|EaT5A$6Z=DU2% z3(=VG`eVNPi1{KNeJ}#^-2u!aHkj`^W4>F1e%KiEjxOfA4D`=4nD5qMzN?FVYk_&H z4(2o&=DTyaPS;_+W0>!oDI{#(Xy$^S(+yL+#z&R;-13eH_{N!%YOP>KefE zYgq~W3FH4??JWfMxw4n_C{;^fxA+`3v7Da3qZbsiIsy2d3$7`tb$Kve|5)Hp-)lmJ z`+Ehp!niI~jSzT3b`x0jqLsks>e|5F3i&GD7vmW|)0QqUu2GmUd22jxpM>r1{nFJO zYvcvCM?J@1w_>~qs0S~ia|CWPzmU03DHIrOWZYIEUpj^9f2=96 zU;7C5sJ(^28Xg4x*u#-+I^0BHv{%jT;C+uC?V0Y4wsQQkW4h`f+R8D%rk^rp3R;oy z6LMeFNw}?CCd4Fye0Gz^LVF3fo44mgC&=kxZHhb+t+4wW56JK93I-Mp`N4_lhOT;`L`lYngwI zyqF7%lTB#)J$b$~`U#ikzQFC~__=`|ZMq~!;Cr(R$+qdTKX6~*c5|6t`Flwlw439t zEh5OLj-my`dMJlk2qLx~UkZ}oxJ;n!H;+LzEcf24I}Y<0gN*u7GazL zj5CC{EAgM?F*X9mNy_Dw7~>x9W#J{-F-|g!lLBL$WEdy^0sl!JIU&f8kXK^7UV{9H zcI1a5KLR5^6#4lF{Ac;C#PaA-a($l{SfuPG=kz6kcP~?ukcztm?zim%ne4G#;Ev(< zN#KvE0v~;pN3z$M2>jOn8!6P^q2hX)y!}CD?r{=$?}9@lE{`9#^ggYdPhkz}+w9sCAov6?k;5cIxuCe+ax_S1afF zZ;J$WXnRxDu(m8Cooi11dhk}Xw+{D24s!)QG4X`DRn0rJ5g7Sl$d8amelX9z6Yaz zWYdZV0=GSpM@)N|3Yo3hxumI{hrkbx-y~h%g$tb4M@^3QkU3mhaVxpvbxgGD@BWJ< znqHLqj`%<b03lo(Y^u`qqD@CtQI(bX$o07DNSI$4&{F(F~5X|5+C??_koKe zdcj;*W0CKac;%rEaOsPMX#cv&9#Y3S2<&fe0S%|g`B91gB=1Sbf!pxw;&X=*-vU3# zFy15Ddru66(gAY?mh7>9h_m?z{3m%$u)-fDzWVR(t0i;I8Th~H=S?4{sv3R`6){AK zjlZ`b$z^7W_LSxGNGm)Km|x{8%Va`_%5}aH|4ANW3&l7?cwZ&PxIr<_h<1!K6yuD* z7-uNPnSa24lE>IcF-`*4uf!PlD8@*iBgHuR5BN{=$cY;H5%Nlm*UOL} z(T@Bu9KK(B69IZ#0sbAz8yXoVW$e~V7pPP^$g8UHvSp)eY$dACt4?%teMt%tLBQWwqkRO4OAAr$DiyJLfwn4+6Qr-qd)YaGJF8wXo395CSWAPs0$&_) zk1J_y%4@dr z>9p02~tgnK3q>qLFFcZ3TN>?}<lYEJP{(Jjp$^8C%%s5@Xx|j58GDOdQ4;z&JxO&ctDy z0gN*g zO~|eXQ|a{240nsN1heTvwIAm-~Dqy|330xGbz9 zW&O?yd`>HkOfR!fVC};fNJumJo>5<~C*^8cvIKU#`Ip+I*LQ&}U*A(-J1c)?EMK)NX{{xHb{=K+L-qZ8zK}Vwo~q{E zmp^;fNGqkDFjLm^@0u5$nOtvK1)mM&=X#IpcU`^IJ5=DxR-Wveb&$ZPO*b;5Mgaov zue*`>G?eiJD^K!XBNH>|x@xYbZ|O?UN&3-|LVnlbZ1Pv%i2@%s-A^V?pCs^o*BZ3# zitYku;=X{<_}o6XVbE&a+pnXMz@?Us#k~e^Fy8LtGL1G)UMO%6zYtnjq$@DmPIZl{ zx8gFp@Okfsu{wm~7IpDmE5C4o+Yj-k8!l!E{AGz3t$CwJ;HF>P=tnT2T;4s`p4NYE zFR(VYJ;uNBcKz!`WXV!5f&I>BkyO;h+w1yy$CXUe-;5KoLwg9(@W3&ahO&p^w zz-{7~&n-Wr{U^?<^BW(lE@P# z`r=%2Tza_;$oBU_9sSWq`B+Y7xG^0LCJ7$|&T)5xymh9+o*$2`Vc7OI0$*BD84Qwp37lKuIctAR zjwfD=4>7L_KBB#y)>W3gah$+&3;iL#emvoJ7CdnU0}C_C@szi^aHg53z+2h`vtwnZ z3*1?2yUM#DRN%XjXUUna69m55$(s7MaTfS&so`|O!aSjK-#|PUBcP$cPY~bpZ7A&b zDm|QfM&t>6u(LJY?Boo5-11RpNuRD01m0U=yQ*)299Iom1v3Nf>7qUGjV}1xcnVC> z=I<6}0-NKtw6Kg9I{Ek1^1uI^_X~bn|9|yzU{wez6pMLoRpEt!ka{m-E zXb=A>Fz=_BNA91(e(s+iuTTCtkH7p@BmZ+Axeki|{q#?PHRB4*$5G7VuXUucU&!Ro zdBfl56Ij{K?czLg{rK;f9;JSMefYbO(Oj3nN;^4EsQ2f5!HXpRe*ORay4xESg?=#$ z_*i^=#eDsbtUK~~=g;fn>rq@U=a2gnw?Q)xf*+-ybN=}6Tn7LB({;DG<>_DZrJOru zyXJa@PK`hRgMQ_>N_&)cD((M|>n_%~p(Qt1)6O{7$P28|1H4_MUtrC+0^^_f^$M)9 zQ()zM{kyKaJ!@uCHK{~WLsQhn!KYSKYqg{JZ7e}X3hTDR_r)l*6 zQ_N+#9UA-pDK3u9N|`M)eKVVB^cM&JPum}bwtNp_8T@*SgSCwAWmeab=eIccU$q}O zX@mR-|0xbua$6icA?i-1na2L&VB`eMvY3;GpMQ$~RsY#zHahclW^iV0e8*z*{X7

&F3B5php-j`~1mCcA_b1%6Gbj{Ww=OTxL2MmrD@sKa4*)RU9UB6+F6mn?~)H2(EJ4jc#)$ zZie9M;{A`rwXcrgYVKx6zFn&+xOzKp4ykiN=IY!F9dh!Ho#1M7gDR>KbB+kElFuzs z^(=FU-9#QThh9^id6CI#Addc0iTJfkWfc(j%d#f>wUgKd#LwcplTzmK>>hIU{>eo0 z0@gB1b)aj=1*R6(3n6#9jX%_TB@mie+2WRf3`-h=@ou5S1JR1ZI_DMnn(; zDi|<$yPRCpV$*lZ)wl5>4brY;^`g zUt3iex@V2soolMlI(7)$GrMhnxmSM&R;T#=&mxV@q^rLvu8Cu=7-!>I=CV9SYO^6JC@$n-f*=B!;og37Jo zoTn2UQ8yw>dz~iMrSvz>t6GyiMTf}mCy|gpd_DT&8V7biZR7#X`=dCsWH8y(Uat14 zOp?(j4NRv>-x(8KYjOba)zs!}CYLAAI4Ih(+)8@%9 z))@`oIz1*ML^_Kbt|yTl;=r=nL;kMJfvmeQ5IRg(fd&R;axLF9s0`>K-(Av=tT9f8 z{pwxh<*V#a-rO)~(CR*!)zgl284?DA%kT4f51a2WzX|_VveFOA7*NK5G6s|}@PBR$ zbhFu!i?6)c&c?Os2Ak32-lnjV&H*xhmZR6jBcX`SC5DT}Q}I6as#opN{tp9S_-Ix5 zmR*dbp^I107)CsWAxsg2ZU^=&`<1R5P?=H$mlRL9)z|Xurv>&sB#H?xw8m-#Hvbm+C zaG@?-)NK#>GWxrZ5$e#EU3=z^M3pw?>H z*2IP|)n_2wxUxa!ckl{5S10-3z)y);;owMLd@+fIIZ zKqL$fD<&WE2zAp=R74@9U-#hmY{V%0_1CN$i1x261ESUsMz0Mzc8TP=w?It zd1drFu4D)Oo-6y7EB%fu#M1A%vN<#Tjw?)~-$P~Ja^3Y$=JpzwR}+%fmUQhi5q4Z! zO}49jB4$BB@M4KB>}j!>Tv*lxf?oE5#QHbnn&Vr5*~_OnrNvkHy5@%dA|!h?jj;O` zma5=0uig`O-;jp3_|-U5VE5H%?~O0?w&Q!9nud_`IO8+F_EWQroS+*T{7kk$P2ZgF z*1}n%TW+4u4oNWJl`&JMe@#G&g)day%Jft(DMN4eUsjeLG~`zTqnHgcgfZ8LtN+Piu-8X-rij2S;y_@ z)>vb%b7X-V3f;Sn>wMUtjqfb=;5tj9ZlgoNnq248@<``$8(X%<)PJIpMmSv<4vGw0EmX7OybR2LuXr9-Z%_`}-EtI?E-98$OUX!uBZ z*DYg^zVU?2I~^s9Q~Sy{4*z>TAGOJoB);wshB<05a-=6%7(2k5Gw$*deJ`l+w}&Yn zo#iF3z2M|XJJ|B0yIfV}2Wh@d6~a%jK<)ubmqZ(dSq>DBanRAC5xua%eU2J_pwz>81~ zxyAfxo+Hz?6&lj=Gf%#fPs2Wwj^SQl@9GWv{q4Z3N=xocIiE87eZ{?|kybX--}9V+ z^cRtluZ5grSE>S4uZ5hmsevuzM+!No@{&(}`Y4xtHct5*d`CJK-X)FVyF$pgp_a=o z`SJWyn|i#c4Z9RJu=cOXKX|M)aZ}`tD(1sby zgnZIH@-}HdNXRG4mPL~1ihS~E`F-+6k(Vap?Zi7=$V)c!-N;!*UixukB}r4{x1q1c zkXS{2)7JhjH;xeUoBn$P@r}xIJlhtQ~9Pw=P2yI`=j2~)S7BJWKe%a+T>fPKI{_8s=WY!=6f zIDW+b5&JOr`qxbd?*{TQv^M@1-|L^TIA=bHZtQ+^_5=t#aF8UqHFMWfnF2XpJ^wbh z5tobg#dGFA<=gU4$dk?qJJ31duij@+I}Lq!qTe2F_%BDtI#|Fdv-S}D$`zfoa)3^h z#{?aaTv_A-ovF^=9JQlabS~P9UimghLrWYS)jgIDeypZ zmCQI~3!1zv78+};mR-B@4&84R2E})>WW5&Y;+YnKFk)?{Y#EA_G_#5X6|Z9QdR;vf zU>yNh!;8sO3m^1eItG4Ai^-j^*=X>I5diaw>G`cYkkf)8P(7!Z7)`%Ozt<83^=227 zI==5w-}SyQAhDP%IjV;HZ1RCUBZ`Ru{U-U%k?vsQQB1^h_1dsFmx@_@?fg0(MBP}J zOR(}=inYMlv+v!WKJ5i>&Ktt5Fhf|{xErW7=uS@PUME3w`a`GT1w{N!A2Ekd*h8dY z6Je-LrR-R)t>o=0DWs3qmro43f!;O>hdH>VTs#jEGl=vH?%RUXHgDMR?3+wHFX}VN z6249F0kd6MvPnADaQt^ii1)uFJ7CZjRGM~#-NPQs{7l-xIcp3H55AEZHM9Z!AOz#D ze3Xgr<-4@GWTmSVikGL$?a@TE68ggL0csFFydFL~+Yg@h&Ll1Adh)@mE_6PAf~=+DtRE^VVMY4 z!$y!sXR^tKIx(==>bP91ML3!2J^&UvR+FjybkWFT6Jg7tb)?zX`RK@|82S#oBN0EZ z*ta#@jIJ@oI^urhw`Ys|q?r_se_AH1(P!UFI+~;jSHARzarH7~_LnY`%zY7XuYH!x zyvGdEb#wykh*>2&{LGd-?w$gLy)*xIZHK4EaKhV{zTaLhGfis<`#KJUh=5F4>*On> zC@=yJ*=NaAw$33L7vo`f<|>){03zRgD-AZxTrLyacBA8E$)&DOBqQ}waZ$demD{&_ zIW*7X?@!FF?`(L&#!4)DW2j2X}yhL?Oh;wZjn$wDVKEe3L`r7zU%!P%eVi?D~zCjXE`~S{%&|i z2l>>Cu8>*c3IiMX$_w&}h*S3{I8V>#66gG#)J~O>C$jlXx5&hHI{lOT7SQ`%o|j9A zMi>$2d2#;#`fxSrq&f)37(XC)DeG5HfFch^x*w?vQB_^x;?>!t@_R4v%V+@EF^kAI zw-^}OZ!@uNeoro&VgA=R2(SNRJ@`_zjuWr%#OprsdQjZ=ztHv6BgJ~^tEmZor&u!% zrEA7niZ!D~%N!JmDq*Z=R}jhmX`w*w_` zy~l1cbjk&!n%o-P)!KnkWgxOUS3pJ`42SVAXXozynZ@H)+>g#j?;&4DPK4WgU&&Io z*h*%sltSAQ1G#438|ZQUaL`S&ko%wXCP`Q1WNN(#aF|;_`W~``xC8CLrfq!~H@G`I zotj4yf_>4hy9D*7Ppo0#@ZH`X_4pZaTECg%UudWy}H*m_D_C+&}T-{o9S^$(5Y+U}9~VSFy> zM*EI5#Rc#5GlF%rPc`{`9Qo6}Hk0->abFO#*oIApk$72!&}TgcyWr8|gucA2_&A!Y z=;PvVx9PX5k4pv#zAd2NvU_$=@VVA$Z`4517Kbc{?#yd2cn6ygtHta=ixus-eu=Go ziJ~3L``jQSG=z2(kM*P81(NNG*m#t5fut&8=Gew&us&Fbr9G|{l2>zdq1>tu1TMLT zGzxozO2BP$q@6F9~fzfUilDL5rVOpOY z(u|hx+Z_t3l2_zrKVLHYTRaRgaVEv;KS}tVzTi^6l!$Hncd#{GyB$-k-NfrS@w%*^ zXuWoVuH!(_$2*DEcjA25O7sp&N_AWmdEh*~mME_ErFH5l)_@vx4Y*yg2JGOvfSgz4 zhulx<@Jo?5#P$E5$WujY6LFpw=l>m|_aO&pUmLUai7bbXDMqxfZJU!zis*RpkNO%L z*NkW%mw5@}*IoMeuidkS@vHwOSA6WOFn+z*Q-tK*gz>ANdkj7_brorR&X}zF(F-4o zZVJ<5x|3rYb#dgO-tf7RKGArx8cqB;2A24(BSsGY@!o!MoB!abp%!SvsuZZ-G*hM+^=KW8hd~HAO+X7#j>xD zY*C{gDUeL(REtZpQH6CZM0ClLg*<(|m1f9n=(inX>9-wy zR2ToP{*H8hzMam`-RSR3=2E^)xeoh%&aOuC$aFt&&oh9TwEQA1SEc3R{&jr2A?S4M z3U$l_$o^6HNs~2w;cH1D>A%SmPwMFdn?tf>b+q;68|Zwv^MrJHqldQmS*|xE8GVuc zh_u1}KPAwZe2^U|Z;MR^VQ9CZTsEwqHEwpYBNV1ymMu)Q!r$k1f+>XsvX*75ky)QO zm|~wHueh9xHm6U7PSM5k`C|`AjLsy%;yt}d_aV(t>c z;O*$zfH1i9WgA&nc@4GfIRMP-=9Bo98hGrlju6`WB-yoS6mfQrg^l48iP+~GX>Qb4 ztUDfO*vfw@)*XI zk7E7!Yt47qB(!2{b3A0q7j!AL9+gPGtUg5^Sx|^*3Y_5W6?dqk;>-WWu%`ZLGhVmK>ehqr)9tUU+a^aR zgpW<)_Y&ed#VmebA=Vea-&pYr=r=%xZ_3n0-@)xa=7(0Id760sCZ5-c=X>IL+Q?yZ zb1N;T@VQfM-h1O?(=C6M7v-{Xxo+oKmf5C0oIRJFHE-S3lfTPyT6!l3nhD=lTTb^H zPAJ}?O{aSe!xit)is)X$8^vCO7Ts$wQ@o3tL-!i&6z}2^=w3sqVy~f;?lnXy-swH0 zdkwc0dky>PUc)fOJH2wc*YHHK*D#IlH54lL8lKX*x6LbmzUy4`Lnhwc_6t+UA7=;mjY|IZo2FTB?1RJy&h+6-2*r>`C*(b-LEBPbR~Am&Ihr=X6xLTJ15u^-SFMVr?DF&$OD71}y@ zWTLg-8zBbthQHaPKD(|X^K)&k9bl8Wv(w3WJDL8tmIgcBzBS@pn|J%-+%D$YTpJla zaKru)1w7_!lb242)~fkgzjxe=t>AGxH!&~g;oJM{y$4KKa(3%FMXnfEPtS5ti(CBN ze!FumEo~-E;PxMMdzi>6!TK?d{sP;)uQ_d3l;ka?dd*( zw_+bbO7{`oDssgux{vT)k#nNyJ_1tgBbd{Dgma3Vqjqy8Nmb;o@pK;{Mv=Qr={|yy zVjm%p?jyWY z=5%gZz3ioj2K`PJi}`!!g*`sJSBm3r2xH%!0w-*&82iNImw4WLlFmzmHVNbGKbn`a zaaPr-Fgf8^VO`a=)7TXo@2|pw!k*m zg*?1sO?UkKhLDH1Ki!L*b_n^rmG$S>?k4uG_Jm!cg3yF3+tc@yNXa4eUHb=#jz^BR;(}9@jbHF z;^4fqd@dLBzLUGz#Utd4JQ_|f+u~mH`-dF%zoVLW_$mrh| ze|sl$x@0_l;VvV6rgV^3Qag>Poz6{t<*htrXmAOA|1+t>-|S@1M{VWr(8RWh*}8ry zaz5@x%pFEUe(_19`|1d3G<6V^om(uqHZ~HfKc6Dc%NwE}vm@byhm2%>ionA+d64a% zM~U~%5S)1PDADbCfNcDrk4L(?z!(2>MEztw3h6N(maKjwAB-2FK6RYo%+t1z8Lfir zo^^(2yX(Mh2S>c^YXQ+a-3rE@L3ozKQIe&n4Jz~;j`2oOu)e`^vhLy%w6{kTRIHyx zY~F1}4m+aY&4qx!?P=B~FNvR5yqEW<*D_zyy7)R`AoX_(PoXVXJJ9yvZSj`2&)I*_ z7PL*l-!Ou=X|H}p*^+)^cx=RN-kx6*8&2IS@@rz_K%BSRKZ*_Uv-~p-`xF8DvxPRg za3ch!-xk^^6Y|M6+AbF4jlA(2efUA!YkufCa`((hQl)73^rsDp*&Ly*S8P};e@bKE zz}HhmT7JV?Y@L${0|_Kurvo^^XVN<_ie>P0Nq1$*^o?AI|HKOa`q%i#gw> z96L~8HTo`2#Z}-U`Y!G|eHX{B9ZcWF0eu(8cp-fk*MPo@V=Ue`7xUl@U;4hznCtZP z3xh@N-|>1{hsA-()b*Tq_fLgv-=>^>?n)st`I$hzx`82?O<1`E2^%lM=B z5O{2$h8bT>?F8=^TXB{*Z3A14yK%06=_fgUdnjjZ{as{zlNipkbL~k+`xMSLX8MQK zzeqVh*ldrA73F2kb|FUE?#xbd8@!*Z7Qs>H7gf-w!ahFPMz&`V0Kw$YfkH zK;ZcP@mQ^y5F75<$@t^4K3u=u*aSSk%M9-Gp!766&!gkXz#kfx|Ib)qOV{rNS zdt7JthX8DTLznw=gu5H=dcuXXPPP%A>C%hy*XnO*8^^Up^Fu#;r-> z++^buN%^oe&UK;=depSh{VqDB#jsRf{(ABf@+^HaXN~69NRuz&oCo_h1heaa)VyK^&{%coxU}@n2Wn4o!D~Iy2qiw1NGGH&M&^J52E!%GW^O zJ@6U*R{gP;vfAj2ul+xrSq>{X8^qsX_At^lH(VCL+3LX(b8WTmoJ-DLHLr?r=RCWO zhJ{4ZhBNy&`~U1c75nc@k1@NBUC)@+$LeJ)+=t!qukx)Tea?z{I4kPUW;%-da#q;G zSz#w0a&wVBXGJ}n74=&%9mRb)E9~LS?o;D`b|24m19_DHU(bP$!Hx87AQ0<7aYy8ytn#T`1!GdqF79yjsmU z=aVm=&noL6Xsdwllge73Y2%~%-9dEdDr)NfD}=c>q==(%A6=c!B7 zk?H1C&djd&##%?14I^mT^114Wafnd@q=(Ps{F>HrrMQT*-J(#Ka;cj0CwkBGM~yJk z-$!jZ_{5cSeYp`JYAY)rbgi14qR+rs?P3wRNuP~z6@Avt^qCnK(DO@GH>Ywo*3v)B ze8kEdEmlYE6y*o0{qGg}W%RlH1_|}}U#UhR3x)by$c*q8#eMHk|IDMp>hb>Ui)GYD zj5De3Z0aM%iL{Qov@XV4MhW=(IN^Cc={-9w68ym0w5IKhm#C9A3cszU?|(ij{AqEH zww1!qMy1u{ki!2x3ymN{(Jn8axWW`gdwG8H1x@NBcHgW8q41IVi1EtcDCkJfk7YcZ z*8Pm0<;wWRrc|g{CBzA{rzWmuPA-s-*LUPGrXl+x-~7^^^N|u+{rGTffu1dG-_9RjNngZZ?92WR_xj!T7Gs)0rx+9zC8Mzten|c(_SXDeiiB$(S130r1qrX zo1AA-d*|5;@xbh@iIV};-o1+WVfIqHfz`8%+B-_$obzMqpEim(WcIT5W;)vO1(HZb z+}cFz9{JQ_$q|-6w?xRSPLKP+=K$O1Jhf^+p^Wp@N)_t><6WHR9@Dn|Jt~QFwSNoi zp-#fzgvNvzTVGq$hVR9YM~$qKouH+n$Ze!VD@;A;FvutwuDpqTIYm7dTr^-krP1Wk2Wa@RHooc}qD5t|-dAcU;0b_`~Jg zvG?C``!ieL%#HBzODE`htW)^B=kHDEcVAPuW$pp0^qlsi^qlrjbg%OfJ&(N; zJ&&ESjGo7yPXB(EafsqPcE+moJod%(Ja)zt=y~im^gMRPf%H7~DtaC}V?DYjrAhZ} z7}N8j`FZS&+tYKi*?H`YyU=s9H_-Fg8ULVXpBvHh*csc=bF)9wGqM@?q333s)AQIF ztJAV)^uIA~LeD;5O3&J697E4OKTPXl+?wvW%%JyRoJ`LTzfSMXxHH}BU^X#k=Z!O) z7_)Q8nN5tTEri*`nA$>^O^m56z-(enZ2@KzV`>X9n;27DfZ4>D+5*fb#?%&IHZi8Q z0JDiPwFQ!?O^nab^Rc(l^RXE>q~~Mzpyy*VwxQ=^8`JZ#8Q-GkV}GLOV>7O%=VOnc z=VLRzO3%mEq32^Weo4>A?n2MUW_+V+6B!X?3T3o?tMacRix*m)zaFecD?GmvR!&AX z#pYkma=!hg6<+GOlJiY_8@%OWN6x?6Ib!Li6LO~CCBX@&#&~d6z2StLsaHu%xz3IJ*j>#)I)72>=~FowU;ov z88=>imc%RUxjy?QIni9OQ|0P6vc~E+x1ZV$>=~FowHKJ(jGL&mf~MYrA2#T!-4upMmL9dm)e7&DcGG{zg7c@c+AL2hi>OlD7r9XA6V1tq9YZ+T9vr z4aRWZU}Xjla~5&#w#*o^cW&c6Vtq5{F_7*vQT@=3n$YCvEzX*I>q6G>kDTL=RT7<8 z6<|8gZd@mFBO!jK-?YW2HwtH)|0!R%Ym0BL^@bUhT5>;aZ7k962URQdQDjE`Qcy z3tF2LOV9Bzkhk}LhfbP=f#rY}@`00d@d52XFuB!C&gM}y_0)zD?98pv-`ee{N6mey zZKTFFYBQ;^nLZ1tc^3MNQ1gt`S5V_O>IbOtLl+ZGsA@ET+wU;q5*c+bg4_SF`84u= zK?1jbv4INddOVfeFRrIHZ1cSV|6OL*JU!WF$gO!6$zz`>+itH)gB~Vjk~R4|w)GyJ z2*ZyipbryvZ)1N0LH~vcMFsm?E6#Sq`_AaWdHU{)`V8BI+#%C_T*3Tv6THiLJ~^1( z8J<__;Ztp^Uf8xyJ}Dk=9!<>}GT!FRVL*TaREOY7O86{jxn^1Q4LsI^^vUS5F%(Uy-Uuv@1m zq(t|Wtmt-t>zK8hhrC;Cle2pnP9KMCKQ`w&4~}$131N%5PPc)(=}(=W%9xI0aspc0 zK!fY}r)@^bpSyFNsUu2I-QQ0LtKZG|F1k11f}GiwefbVD{<4#ouWX^t{|2ol-dKG8 zqHUzETP9&#(?*PI+K6#Y8~tbglX__T;+poIF{Bl~S8dN@pwDG1{IQKYkBxVAZ1K!P zUZ6(pp>6k99&oe0`d6IL7?9M&0F4b)6B{&UP)*Fl4A@uGmn9|NXIR(7VV(80) z7LuB_pmD;>S)9IB(D>x#EIw)bBG&G# zeQE4*9Ts~u9(Xy62O6uqoW&}QAI$Vw{AjOy#LHD1q{(RP@p2Y>G*&sYSQYop{|-OR zdO_l*c7T2c>Uh(!btLYZFSNZ}50m1SM;*?@9k(Zt!@k z8kX$eOUUPLu<~F%?DTao8Lt&Y=b82JdEdM8qk9KI{ykM5=QY><=eYex#i-3Nu)|EuEYit(c#W7$%j*PE)Dbaxdnq1b9e>H0 ztkg<@gFfd7la!l5uwu|p!ekGozvCMElQ1#y_5g96Gfp?cOxEvg18H@SBPR1QgTZ5P zu!PC;9#WXMZVq7*5i%ZL-?GO{-p-gw#613%JutDDHxqd^Q3EC`^c-NovaN*44)sy+ z>%?g}lj7y6(9b;zFc5WLtnLV$%8e6nHV`0AaGoe<;BAL$v|8R5tFl~L%=l8n#=bq1>{3fU0`xI#TmRSO}JdP z`awE|HpWagK5q#e$&71K&^c^}nEalV2s^jUAWR-6M#I6TDqM6L zIz#>Zc3gJ#*+DWh=^2bva(os^GIuxtlO+2DbZEN+Fd6TY!0W52)1mZ@oQcou6fiB? zMwoO@2?Oa;JubSgO`xok3zy|{wV00)6Xs_z`w#abOxATz!0WLcFc~m51F4*G1tx0w zLGmjHt$>N~kz?dc&>Jo%`gVfdwB4A{I`QW_j=*GM*TG2C)@0%hbzpKm#1>vQ>`#~& z?3@HUum+cL3$5{kV-0{wrk*84)9*|$@fozH@YA?vz@%hxQ+QPBz(s3E9GXAL6_^C4 zZ<3s$=R+~+ay|m$GHkd6+if9ligt5Z<~$tCyc=^dZruvkbFc>{+QSy0qf3l{N$hhK z{N(8^Ig^)qbl*Mg31O0B(H%dL82}SR|Mnm;NrlV!I41}{;LPPos2TZc>i|q{Hk^hG z?>7b}$LqGl4PEyTCKu}s$97-46DGYI#bei(-3gNd&3G)XbNke`z@+=31H}KaD=@h~ z#8lo!-wc@Kw!M$qJikwvbUE6S?WwW-dH%gQF%Pa=2Qz7?+8)oBn-eA-dnV!CKTi@S zz9j>2++8hTa@5@fA303Fg+|3}j}M~tuzE55ejhg03L#AFp2msqg%>5-0u$pYYtXRC zj=vr-eVUq2nB371#Y;Y$0h38pH<9&tU&7>J$z*)* z$Qr`rfzeppx1lRA(aXOk&puWkn3M;%#brNTfr&%XX4&02cO*=*8m8jjyPOD4=HsaWuT8(hHo}DFH%xOIVM6m8rumHv&2KEX zu^dNee#11kAtp4xVX{3@&V=SSOmiDzLh~D@xeYO)`3=+DMwrn2hG}j?OlW??G`A5Z zG{0e*-?-5HhG=fXOlW??G{14VWc35l+y+c&e#11saiRGQ(SE@C1Ezg}#Vr@w7clJ$ zTxefFv>#w5v@a0a4=@wj7l8Hy#Dw+*p#1j$hqVA>a0 zKVba<)4ssICBf?D{fqVk#Dw+*@x53-VEqBpzCdU{z)WagVEusg2SWP->j$hqVA>a0 zKVba<(Z0a?0qYN#_661tSbspYF97WahzacrtRJxcfN5Wl(0+iK(7wR>0qYOgK54Tz z?FVuuv@Zbd2Z#yn3qbpUj0x=vtRJxcfN5V~{eblcLi>Vv{AICPGZteyCLktsTwr4Y z8yhek7YH2_FcUg1Na&b=nb2_o(Q$zb9TzYi6A%+N*3dD5jSZNN3*xy1qGJMPLdOM6 z#{|TLjtiKM3tZ^9z{UhNHefm~U^*sn=`?7K7abEY6FM$nIxcXb;{u^$0%k(T1vwoP z5ED8sU^*^vq2mIg;{q2tE?_z?aG~P@8xz>rfa$nE=$L?+&~X9im>^+7#|2Es1jK}n z3sBXnH8db{KGscjYyx#RJV57`xIlOF-{jt#I=GO=o8cEdl01Ddi%W3qH<)}H*Aw^b z(F}YqEhj@-xZ!r%=By4v>*6`7?cSHXo zq+(ic+*P{?xZ1y^zwOt+3o~3HVBHN8?9>eB9dm~H*Yk*%UR!J%V*`6~(~0#i5A4^c z4NzN{O+3e+zBd}K=#)whc-%pT0TaMhI!mH2-;XA5nF1k87kIN+_~Immiw*p}`kHT+ zH-9OG@_@q~N><+VmY+<88>5d$r7+fTzUSdLUJ{Y7F!eW~e#g}3nEIRf9Z{cS@iS6?GruG1 zb4>ls{En#4v8e5^$j?~he@y+&{En#4G4(g|JEA_v)ZfhSi258;e>1-$>T^u}&HRq2 z&oT8k^E;wG$JCcH>Qg=r>@aF6@2VA#pOh~^P2Mh)qp)Z^)b}tFKbI&ruqbA*D3)-0 z#{&8HTjAJh+a+}H5tcuzI|(iiQl?CMI$}z$%~kNcn1CbQQ66nq(rMbj#<)Nd@mLwavCd`#tES@ zBB!x}X`B%8bI}+nq_Ki&oJeSl6wp|~G)`nRMr1TrFpU#JV?;({1=BboG)Ck!Rxphd zLSsZuV+GSVAv8t~(^$bYP6}y^6w+A1G)^QmMp&$18YhIth@8d>rg1`OjL2xLU>YZc z#>i0`E11TKoPB$k&0lE0tD|J4ACxih|9%WCHk!`=9;Hs5BU(yke>1A|gYdVrN9l|SZ}ZC4QlefyEobVp1pGh69}3;DC+T2yyr&EPckrss@z{HRvQ?V< zJo4{g>IX!9Vo7}h|5Hr;0MsYB)F<#i#q`;M`XQJ40sTApI6WJY{sx=2VLqDDH-z&G zy%%W6pgNqxuYN^M+9Y^09oxs%D9ybAV!Uee7xYFmlk2n{cL~*hJ&rSue}c}WnR8w` z{sY>3_Mn{U&;9We?HM*o#(2*2YE*wmqJ(j4qu+n4b7P~Wy#C6{E2#6le9l8s4olM9tVuVJ%hhe1d&V3?%{LTr zUf4Pt`D)(goYHzWTD)4Qv#3iCM18``sZR*?31{jPLVd!S`h-xQ@MobuA=D>C;S=I^ zeF@hI)W1rcKLv33mpJRR^+hlh!TYbXI7)gzwLZ)71=Kex%oB!k&TYuy$rPF{U;WW)ov-;sXX+Bv*9icRN49&=ezw!A+KH+ILE(V#eBt?#ZPI@Z_X930_Bem3-xR? zI_90(^d~QGS$Re>z4Sfj@B8dfcL(8F^ykMR|5@jG`LS-tlDHH;NhkM^n`%S)5{e2W;>c=c%DE zB=H%FKK6rbrZy~IcTa9(PzTmi{p@Sn@`#3Yz=75?WSxUQza>=izts;Q z^0SiZ->%Yl`~Sob>~Cg;f7rP^HUB7C>68DvVnFfDR?NPkTpPYvZkONUf_gqXpJ>Sf zJ^WPX1Uhuo9qM%sz=a{raJNQX<-M-=!Idg{c(lYz?&s47f4ZZGz4tiEjnn;c$%E#Y zU`zSPqTYDvFMYhBnTfn0JQ!cj`GTfTh$0UT`r^|aHlyu3)ZwOMQ#|UcIa1Z}hsxm2 zSbq2mIx+h$Nf_&c>(4)rUMHwRYU!PJ^;WNK$L#U?8`#hKRFZTE7NYv}>yvqs>98!CCZ&&Wa8=tVv5lexnJ@b1`V zoK4G`;18h}xxSsDK8~GN$hqXWG5znkoCnVthnokTN4J_9%Wt2Iz_A-Hp`g>&@?$0u zxL?Q>^mVwKyyb>)ye{M#8sOMje)GI34*a|cot3-8#HGu3<&C?#i`kj7>n4JZSJ6kQ zKdf16gZKTchhJ|~hd6_Qcvt98iO{yk)x(v?G zJF9hw)iZ9V6SkZmA<3t0PBcgZKDrvsd)Yb9dt|AL>{J+gst3)yaOYmNX(~T+&%ZCJR(OOJi0Z*7*t6{ zQ-9cDcMeyQBx~%h);tq`Kef)cFcXQB$ z9aaNiy-ud=(X314!H)73aGrioF*V&BL={&{)`L9X=)HG8z#&HX( z%!-9J^cgcoze8Fm3`&Nsk`+mH@i2!#$a$0@YZI>yRhgd%JDc!-gR$t^KVrX3Db5RV zlw4n;FRu+N#sq$rW^LK$u`}x0B!yp78@}u_9v1aD#?D)=!#G{RYiEYR`T1{odC}l8 zP$%>O=WFjGz~cQS&Ks!?QRuL8b45AR{~hvxjLVQ>huC3qc2>qT%Bz9}UP-ww7C4Xc zZ3}^!em{l&s)I>*^ta)JU90sX371U_x`(MjK5h7;cRm?2_GyQ%6aATBpi!J zat@u7gdggS;#}Ldpn2kNZI@TrVsFj0HQaUCMBGw)5BFzf|5SW)kS=Fd-bzt^XkaS# zY%7$TjrPMaW`?}p+Azyi$GZM>RNVJ3KJsV;q*uO2tbD1)Bp7&THD}e2DX?vw3Flc+ zQs@vkkDqxW);Ham1})ZI=H(=^Rq*5h@^X4_*$iZ{NI0whK2F>l=I8Scc6}FBx<2)NeVb+am!s=*2m&o)ip{_RE>h8qvMh)k}j*w|?>Rj8^f`p>!eF-xfL+;>_=G zw%XqpI)v-+d#(3!1IP0&oV%7Zfh(p#oR3Mb5?iwf&UbZ|6BD<|oO=a1kteN%=c)}` zZS^GX`BV6{J?HAmldnrTd(v{Ze^4IqqdmI%TF@6WYTK`HTeWa)AB{+fdWOKIc9oK! z?rFTvS3~<2?ojC1+E+?`D9TBLNQs(4zc#Ta*6DiN5xH0id8sx$PR$jCs0#Y(yZ0dn z{fU^h(HA#OEOQvZx$g>3JhHn3=Rt1=V&54JIG5$d;pI)&A*LVtG8KExRpHF~C-_Uw=Ds{oH30aSNY3&K)lg$KA_6aejTq0e3X^)1qCg3wKXYu@S+%^H1eV@tswO;~0(LmsbQ3*KKU zb3qFB=-GyI>46knaZBK-Ikeo&oR=TTOu_YXEI21br{Dt<+j2H{Pr;Eh>^Yw}oPs|k z2-jNBYhT$2*ShUa!DXY&xXxVbRQ#%iK4*q^NXSsJikY4&R;*#=Ne_A&!7H-^XV&6 z{LQ}}*O^r;#dk7Wa9$~s;H8@Vb|7%#|H+%h^b9@9M*d z68day_)qPj`rH!+%9`nKpRP;P}|Edk2IM)kQ-Wu}yYr|vTI>T5! zcV2&O_)ptw!CYr7OLXV<)P}F$>4opy6xK?$;Xk#WJp8HtlC6H& z>5>8W|G(mhb(3*Z-6eb;b!o$7d{jl?3y#S+(l(fvKOB~dbsdB`-n8L#?q?#f!--_< zGQ2m}**G#4Tb*vg*?m+h-g-#jO4nq(>%l-?uD5404q3gJbIPvC*ld@;4oi}7uPMU% znvLo6mZaj&FE#o6N6ZiRrQxXg7x{X#vPz2U3^4U(`bBr8cu4Phe2u1ED8(PIdT||x ziYfS%s~fLJ%&GKyC8e($^YW!FC*$Y2%Q=r4H3oNTFTCIAp&g88^=ZJ{wEoK;cxCfHU%&@%k@RV5}C^mUBdN zTYP7Zgmcxd=D5xmf6lK*S>k|&KAaoR?t;U$%sI#03BrYkv^kGk6^3VF;XThFwHU0r zau>f>$)QAib7L&$txr<$2+Nk7J+4V{m;HL&=i>6abiFw6W4%JwF4dI3L>(_++~7hA z)Em*7U+awHpl#*`&Yn4=;CkohoQF7cg5}?>xIIhm>p-vJeK{w+-%onpnebm3{UlXd z!+7~@)Drr|2yM|g$O{&y*z@us>xM(g=FhzTXOF!#_7%w{=pnG+sU@-Rrjy9fC-l)sGYu$X6KXhrM7n)i5r@#<>2CeI$_ z#WbdwNOAp^J9x}br(9qvaA=qFD1nRvrX%Jamxsa@<0`_+RhD#z`N6HYj_p!A@V4{j z+!E_T%W;96*V1?UNzaFKer0*^H(Z`!Bw@|kBdNnG|M&XSPpWNv;q=iz6xAT*^P=U2U*A%CARTs35VvG z@baZnBU~KP>%Z`;X=_m9@;F|8sOw8~@$pE`yN>B$$tGcJk~g)%Lt_yypIh7spXwpx z+nc?8@%RVEyu6oz7fwAYK<&_PXQ5%Lh&|#D#7A zIKS!qj((3YjPuGvy(G_f3w{uD(}`O6O}_BF?}{#>Kxd)dPcNK?!gnU{Yojh0p(-`O zZ(@CygTv8|6G>dhu={D`RWFKj>f}n4N=9%V_oJ6&uj0Ndd{@ff`3W{OT+)}!oRiFT zwy)enMkY=CFZyB~@wMkp9v~S9gz;#pn>v`R9n7zNSzrm$&cZl*;|YT18SQxarf>bmnYc#BM`wUHyf^#aVHSax~806yu(0i-8&xt z2V5t>yOH^vn=Ma-$QzS5d$^>5PxJ>qE>EQ6uX_3%-q$X@Pldb)y;nD3ebn%(kcd$3wmm;e1SQICNj~m2<4-0Js#T z2}~y>@Fe;j9mVfEh;p@pb!OA=w7v-E<+Dw9O3DoBoRa?IQ?**sw2Qz~B-c@fT+s39 zGYSQzCvlx$liEo<&j>mmLtn^aL(+t6LspV=>618ztG*`B?M8B*USbGGpZDTy@xmFT z#=`n2)v_~G?-Aw?;aa`ndnW^~W7gLRE^ZapXnX6LfRBqWFE1VPoH%YA#o4IOF4A5n zhV#XpA;hLiur2bTF$w)4y#Kkg{}!T#%) zQcy2l!R9?T_o1HJg3TAtw8iVQFff~4E_KBprncccp*R$;JtFM;tnr$Nx0mnbvC*W- z6nxXH2WP_rX?R52i#)DO=-Bjl+zvi>Euinpb(>pooeQmF@kP%Z&I`T_!)@w*;~e7D z9cy0{#vnG{vHJ`E{IB^*vLF8S*#NV5&ims0@PcZA`;VvP^$mG>R=6MTswMCQy4RP` zRN!+X{qWXi0&k%FK*4uM`C(68p*()9A3mck@X$yTkAhnrpyc#_*7TsF2ow=?x&f4q2|Cg;if`r_>a zbvQ>#`{3mJdYpG>4aIj4Rw4Ghi*ANs`_XlI`5Db2_&|gjXH6WAbzN?79g;U1H~;jA zv*YD3d=bCleEj%uT=el1=Ml0voF2HAbF=BOxc8YYoHc`DaHCB-IPV-f5$C_#!#TJ# z8jp28!dbRD3YYdQ;+z{i4*Nd6z`5zmH2krDfrQzqSD1z;&no5&X=!*v*=^3bE@>Ec zyyJZRRw{n%q{^@T7L$ryowYer}FZX`}M5D%d74T!=>)u__Yq#N8mPJ-g7>>Z6uyt^^)@nqtST1&r{CP zBgf!zjUI4bR2+q!B2REmN|}I7_Z{Ti_rgRxFg=fR`j=R&qP>ap;6amc)x=etXMdiI zOAjvMyzg#2Uf+EV=j{HyaZzatZX4^%e(f#Er`19(4W#^0!QYNALTbM!^FBZ0bVD?P zu2Go2Mhi!oJ9{@l{}Jn~Z}}hPvqbtVZ#X+GGH3c*>6+pD2UWzlA~^v^{F=_W@@*8B zK0VGkaN1B@*X0-IOv>8M0(blrh3AwAIuGczg^Fu+AEe?Zr-eGj_d4j_Uv8Nz%!R}p z{%I}Qze|`y7Q7xt?p_e)SK@N(;~mJMV^e_Hxwy?#BE2ol(^{{8iLB2Hb51em#l+*j zE9P^XS5zk8>-W<*2UMkD8?$^qzMs56_vC_G@jU$fSQ7TRGMupbe-%dH(wmn#cbnvo z7Yx+ov{_>HD(6}st^NR)J z0pAzqA%R;%;7(~>e&3H50>H<(8RzYHec(bpOU~kY#*Q8gPD|8z`N}KfK>p$!uM^Fi z1O`)Aa(3!A1zO$e%=!BOJqUc$2Q%B|ROx|wyudHsH1oPn=X|VOGx`?q%Lp3d0tx<~nhzlVI)j)%@Bs$zwo%^FHUgZTdl4Z*6|BfIttZ z*yhAJq`VF2BzNU}7wUsgqd}ave8?paug7pc>pTRSA~nqJHC6MyytB73A2{4y1uhN^ z;pHbkzmu=}2jzbAOr?q2ua|2>@bzI^(vqPn`K zr>Cd8x~KMx?l^AD?I(kvBR!Chm1cm+Fc0KmK^ZXr_v>viXM+Lan zYl__Wh63ss)4Qq2O9_o@;0(#loGz~zl&_a=dyLSJVciF zRlq_V#Tr@@m>X(*r4 zHw~Qb6BlxRf16n98!x9=G0zN|w^xN%Eb(FuzUg8AG;9>f;!c#|^Af|-*n;W_$i4X( zyjXWAK2tL`WU?1;h)?cLV{rwflm9+~t@11<{SYs<*S!(iRQF-Pmq@5yQi?k9XNJMI zK6O#&QGFM1>_zLZg#D&aoaKUYS+_=D73YOKU-Pq|;S`MAB>JMzb7>^<_`(Ci!`U=H zSLd1T?*s#Wo>yv<5%+Z9djnbnI?c9#jjoPl=Y%_?eQbg3rtJ^?uT)3wayXM!_P55d zLY;$FWx`U+0F*a8FM}N`>_y4GYhgTWoUsWxq48)~=z9y<$1#EJS-&1RKVQi-pVAz@ zxJ^2naV{F=r@rPn-Fu^Y$Bm1G_X+H(z5hcAKv8WxB>YcT; z9vrS5ifsBlob7u=vHGXK?hCr9;V3VhWhrJ{bwB(5(%BHSybc!m4!!{XU5#1mw<#5VOtV_D^nonp?DSmbwwpTu6C!N_K3 z^MxBO6tBoi`Ys&)9fx*{E=))-RF2+?mmyj!K=eizSFQ~@uLdz;d^>` zvEE{0-9;OP1&?UFjq4^b|DhCr2w;O*(>o2Z>?V0{X3y7hQv2vXStI!EOh6uHTPbwC zO>v$xjzXsL&ZOK8gPuN(Lue+`&)|^1~-fTUicvS@P{j61jYg3wg zj1L{jV(nj`|33acY|?0LEStGy7%R%Ci`+BIhc#|T@&MnJf_FbEn>YTMkWfbNzC{DO z!Q1`h&lXK*7PP)ImVMNs6T3YKkWXK2&vw+Lxx_~I_H3ez_)*|9(f=0NInZrxas3hG zXRl7##m_>B8CxOr45fOz&G%uybjhDadk={3=g{>IPh27F9!olz^PUPhI@BgdUAw`@ zM#baADXI~ATwPyX-Xr#3`rh1*uFB3v zyIRaHnC4FQoaHKpTCa;+x=<|Iyw2<5#wxb|nks~bq=Dqy9j!vK-5?t0<0=}kte7Dv ze>u^Xt)6UyY&pb}4L#Wyd4gsr>kv(6hSzV2V~?|T2$G$XbL8y1SqEhKoOBl3F$|yI zx>kD3(}ec&)VYVAjP3c{2X$6HRI;8RI!ku+W+t!+C2P@6;lMD~XvGuc!`D68vbyBM z)qb|@BO~8lRyJa%UwNW$E<0C=(K?C52Yp#R*V;_7x$a;FOFb|U?Wpt3>pfUgZ4=aY zOZH<9DVoTa?nki~%g&&Fc}@~@u+2rD)7xzS7&*%Ri%2Sa$O^;zuAB)I4min`- zyBcWcwCKrJS(48Smpl`6&rv*Z;`q)GZsLqO5uqN?umim-tJe&JlA}-2&gi}gU^jd{ za?kg2u*hwV{QPAmoXIX7d(G;a?+*>UP?mniu_l}k+kno<)D$iG|cWq@V zn6=78{d|o~FoxYYZWQq|j#}oX*#55ky!*E=BeAYn??|}2;}UY_!vS!=Z8P-w=LBOI zXWR?f!LBdNnreW&_RMeyn68C9Jt`K)_1%MIy_YB;{(N2JV!n6Pr*yw4`Ru!KqQe(e z|5xXs>m5PYnD!uQ6=gu?3c7duAB2Of_dT?8V)Rg$KZ@eXmuIgO99?LP1t&A8KR{rT z{RJ;)3rX8)ugC9;30$q;1LbF%&J?s9X&-0MqxN9_mE`x@%@A?}NFKAQJ?yrocft3^ z(}gahNNzp5J$UsX`H`#Bg&`3n*P0d%u=hS*SNDCM(8r0^eWkU!!P;szSnsRRO(861 zAadV!PlPKm^e#A;xmbwmo`mu!y=FrHjV!)@1gXrId1;817FXej(T0{^1Lr? zgt$jEhPXzq7q<4McXVXWcf!D_Ay{@?&F0|lGyu7@zy{v>*dh;hcZaZrEs?$J_`x6( zEw=Tj4C<`27o;)msHGh8e_J5OE|bH^7VVM0Rp)1hzqLSa+B^ex-y4qXxF7?rpYTLp z$74i2k5P;$BT@!6%v@03bwwI{&!BmJ`!Q+oX+sLiM?~`Zc^PqdW*R(-rMddJO=-~c zQUdA}zf6N+kznBqz?OuPO{&|mrt<(K`GP*Ud+vi&F}oValhd4C*V8{VaLVy9#!xGb$e zxh|Kl(4nBc56 zM5kz)YpHWZLwnf&l41oXoKP9=>A zTT^6g{tH04I@>O6$S%AYjP~z_cV%;@bVoks=gzDr(6hNdDu~_v{1wYC>KelW*U)!c z`HfQ;7|%kvx}Ebn@yy?g&hrEe4rldeKR}&hX9lzKvoyC4zvs*r?V>qA z%YO0o>9rEvLzLJ{#UG}~*t;BBH`V^2WK(M#!1u^oE;nBAFZpDZT+)AQJ0%?{h?n-zq_}L<=pFmcD{Pa_?{Z^&s7cC_-C{Z zjhNJxO^WOeQeCC#?)OXP{NAU3V=E0$eq9>bax975jrGnwfen}w`yr%XGZoln?? z@@^5~?482{Ft9-wL@lMc!N&+s zaN0uiihDZtu=Rx{+FZfwO;gpYuQ3P?FK>eK+{Yo%_YTe3BK%{a*?h9U@<0kqoSTL9 zI<<`g7hQ@Wgsky{{+($q6rAq_^QzNc-qcZZggHx-(Pn^ks91M9?Kw_p-2;ps(>yAU z8Nu15y;0{=_i8X~UI6lm$HhWgaSU?&ge+lCVG8n;hh2q3Ce%J3R`e9Kcq~o2cS8?9 z66%}`L#}2V4`&~36(xDQWgVf2Bvbl@>`3oQG6Z>?*zIq@-1_=uR z+p01=0nTh)hrF(BI5hNmh}^i=5b#Q-zM;;QM&a<-i*(NOvYFec?BH}6+}cGpy?I?{ z?7CuIEz*?mV$B`&A^oc-l-;J7PqP4DI8|O7eV$+z1bWxMVZ9xK!y$D9_0L&cf1gTU zU9PULZYTS!9e|Y;liKI=fi&>&r?^x7-J_xH-s@<87T0l6>8Q(_A58;`6Y;1s!ZQuh z>!gd49i0x{S<8~HXmhh{B-Fo3u?RgbZ~kB89@}n+dKnb==I5$$s?JqS07DDru z&lL}aAHQktWTz${aIVPt=8(Fr*t(Q#&uq(bPmTrp_7 zX#Rl4{2OY#G2alH^y`DyrOuU;YYMln(VXoa=bI{?8oE&M*hBL=t*0?U(XTWtTSJYr z)O7luSS_x;Pjj|jYV0%L2$~$~jb$a)S8=~f^@XS`s&~)X<-*ZvGzZ?x`G|^Z-CrSY z^(T1^H9n)=4%P*b%{6Uxgn5Z%XP}zR4QlehRV#(b&SWQ8jnAstxox^aypTaUH#uKa z@dDF!P_sAHwNQ-%?W|btNjto*E0wxz*HCZdk>g*9O{Rt-7ns#%TTl8Tr}-MOm^WnS zD_;YaF&mU8t?t7v^)N(Mx2Y~)^xJ}MzUF{BU0OC_SAzy24|x4s+`K;kS@Ypbam;(F zS2kFer5+-GEHsD0>u>c@N1by9n6j>qT~J=4(VG>ew?kH*8p_Pe>k-HMumx@u7kZNA z%v|*;2IX<1CF|SN9d*nNDnyM(qmXy!I*D&q$dJ9Cu6JH)N`1KBk{3efel$m_bD<49 zKh+m?Hq7k?9a0xWV2VB(I||1+j>HZa6>#gm?a^f9J$xVQkA( zmkqg2>+WGK z-B>eYBb2YHITQ|mr#7s4ECK@CUdFNFWm*ax3Ym_q6|R5<`*o2^zGcFo)dO*zt6o-J zeqx*)G`E|g{x1N%`UueRDPp%XeWMFs6Sj5B%4DMQeg8O+V`~Qc^_tJ>7iWm zf6Ur}xX-9wR$cCd78-Yma<1z?U5?qj%F7e&2t#GeWt#Kl-(Lvk{5yP+nX% zl(jfo4|%hX4?8zj8@b}N6FdC4GqSOE3ucq%fn2)jil`YCf$XrOlV~4JbA}q0r<_er z(4JuBtk;5#ODO8}+Gzlt^!p+g{pbd(Ygr?|dG7|bTeL+!wZ9Kz?G68fRbvRs4f$F0 z#lhalCw*Rtb>@-%RJ+>D?T|0Ze?%EEr+YN#xe;W`?rgR}xw@S={VvSvm;=h!n>ArC z2MTIW`b9RRzEa=|{_0Mo#sNxez+r_L~G*3IJ#zCG7g(mxxP`|i1M(ClDj(kv! z1J!g|dDj$X@;y(*-{(ah-P1Fo^7^+pJz|rMP++m93%1&3Qb^&xPboIge0rBW_1WWvA>_Lm@bs?Dtfw zt5i*X*Q6bcb)$OkaE?{+^#Loy^GRg?h8k;>+rjKkR(LIS`CKkJn!ep=z~^$U_g)vJ z_EFbSms{}o$gthe;RR#M8ZoKt;1FMEcAm!exXwXv?D99%9~c-8 zuS02FxtQzwsPxt4>iX(--keK;pkGt5E(ab{@T$0nbKrqICYgHK6z9N|b7XM+urt=x zb!q~Pd9oI{!YLfKJfnK&XbyqdsSVLjbq;a~hnY7?$A5YPY$~U+>*vW})N-=9hu78J zp6W^;tAza{?xPQl*T;g6-fr}5ZEOelu)!7Ww|+WKxOXTO`S5KI;pe3cWW)D61pi!` zH+CHHQK-xhM){D)Ht?f)KVd} zWLOPjGT)vmVC!&-&pf!TfZsW)m{Pd{ew?d;I&-QiVb!%C7z;Y5t%UDA=&V9}9#5<3 zMe(!;LI!*^@j?A;o`a=-vq8v3tz}Tr!wvbflLDH)ZHzoasemzO>m#pQ&+8gd2ic=6 z0ZbmyIWF%){yy}jvw!)mlR#d%7{+dyosn zSeWX$3wbvG&ZX7w9mvJA;$i;a&B%`7vCzIV>9f(XaH|dRcpf9~twVe~F9CM%TZ8)3 z9pm9r`>n`k9pj*8qXLpIj)nbAb|YWymI3KS)VA)e(qVKz@-4Y(8U(zQq0W_KDbW8T zoo&0?AO#lGq-*@LFPZ0>ple^q+eE($wMoY=$x!rd9+vGd)E_SJygjXxsGp4dtpHQwpV-F&-}152i~8rdI!f@(rT%u~k^;Qy)I>Xa z{0v>fIqIvud5jTeQy*s26p%Wd;*bV%1?1>9K>c^=3RpRac-903%o|R9ujT>;6!)x) zI=1-=@GzqDkQF?RUCJnqeYB4Z);{ThI`!tt!0(9@@{ETvsDIHGxqEjx3><8MTyv8g z&i`zOe5r>5rg>4HUy!PR=kv&i)qRs8*pu2n{#Y{HszvvxpnVDyhRwvXHzuS&`Gsl7 zt+uCt{^~5`@t0EI>0G+kqh6%Kx)s!KtuCiQzqhfd)BH|446GK2?5rIPJ$9EMx86Gj zo*g@ae9v+$bPF#;)~^`{du~$SbAAyIgB&)ZywSWwi1%HN%z8#aK+p5Yl`&B;Wa2sG zzP+Phq!Y{s127bPl2mC)XwJaJU-+<19g;-lA*F)HnM590^VxZ zL;f*E0c~y&zvJJ`)-k7kete=F#P|-Vl<#V|FS)xLXT(1AmULf1>B8V6p;&ep6jb6ukdGp?>Q)j>rF(5lbV!7XLFf^Yv5bgTrWE*DknYQKsrF>u=*GVu2&gRp!YSiU|cY zH}loMEFL>Sb8^M@28_)bf_C<9v0z%Jv_@e1ecAK^1C*=R`*C_7Ru)Ke?}|z0Y@xjq z>gbs@Vs>d>$fH6&h_62cBlmfHLM(n5jeIn7uGk=f;*ed<9mN}YGL&Do$tr#_mgb`G zWFizTrS$^SpDyG~OhJ9=eBht+w~P7M;rXEkw$ zVdTdA%HWSdGFv?JC>iCQ7u$=T z=V=b`pl4C>gy$3ooAF5|wrZP(I$GUI#TLz@kVS)9Oh0xw^0jvcEc+hCwag;AvrCh^ zqI`wu&iemufxPy}P^Mc^4_S8s6Pk~XLEdFr;OwhSv4Yw?Z-`IkQ5;X5&6lllZe~e3 zuh#t#w{H%_vgPmHnQ)*5NbPXE-VgD3ImwfhyTyVzwC)Iw>C{7}dFlL_0@um|$% zI>4eMJ5kx~1K8E*X2|ES+q3&EC>}m}eN)zvpGlYOUpW0qO!A<AA(e9@LlASzSlR zA*6nz{(KF;ynh1+XroxZwrE5S>Ho=4R;dRSJSHz-?z zEWjP*ap8_|A;JPVJ)=LITi*(~RWnOSxn+;sO|uOYMD#XJXrtDhE}639<= zo1xvG2_GMgM17C#`p_+p*0bGzbbhZQS+`Eq1kr%Y&Ux&-GK zjW#G@vp$_=P2uwjSACjSbkOASp~yVc34W`Dfys21HT07b9Cz(Txj+BrBK!4DWRGf@ z0A_R!HjkfuZM%!~jSP}t&_mUHb!ZAq(WQ6Fso*rY5Ri)g)a3KJ(`RU2$Ii$g?!6t# z$A6cDM{!H!=#2^(*@5Q9*R7P$^B(QJ&f(u{j6Ox*YxFy=gfA|~(VxZT5pZQwIhGw= z83iTX&mix1iGh;VhmZ$Mj)Us0@{qIQ;^E;}n!A2F#MjJTYfye^Y$7zZqB-8xkRV8X z^%do>u7!esn@VI0%~8;8_Fd$d^wH33+zsS*?fu}}BTf9aV$iD*aN=!sWT))`@cGqm z)LH*)0BowH??-+e^n%!fdZ_auXebN}u8%xmzYnAzuY-KD)j&9UjPyqo4T8_p=$oU! z%LAe8R1?%G?lu~JF20HO7t{=giWLu$H^h$w?@P~-U+0Iwb;Vocm+ylh#YKz zFzOfbMH_$6k&(~lONN8rNiDP=d2k54^lgB=;%hR5E}Dh<)isjf(;Av5M=28E<^8oN zcQxbRVvpa7JUcBGZXc)l{PQ(2aM@Nwc|meCXtGnt(sQxgC|BH_OYhvs*;?Y>ll1I+ zKW*!Lisv?ybnb+Y5Sllj@#@s$W5UZpV^FSMR$ZR6bA<4q4(Y4g`BI@Jwm44q7d()| z!wv@c?o;QVJcrsB{U*3ZR%ccI3e;C;RsIc>+wi;=Yg$u2y?*tApkd$dD3A2=1cx(? z(dW%&0CrP4A|L!_2H#dWBVS+K1S)ILI5R)P1Wu>ZyWq;kUhw1*#T7Mw4+e+v4N-sn zzEGHTsuJz%G>r#u3);`!QJe-Y2DHzm?weiPWO%=9KI+d69tCxK-$8cO@P!58bGuJ(|E3NAhzhbb$xU98f2@q#yLpYK`o9(ieJm zu8rJn?kKn{yNz`{TAT=5;N;rD=5$f-Mnhv&g14XH9%kX$OoU#R3=cOY%c-5Rq^89Ub zc6_2S%FFNbGuvSw&`y`@naue^J@lbIKTBv(_chvFa5k6~fBb;@L383@M)N%6k36Sp z;pGv?`nP!u>6<6o&;1Yr;ubo;(Pv4rs56!3Cj)H{i+lBAP$zl!L~&&(#aKSv=?>d# zbw#;DQ!gmqP4Otr)`8$L?-$zdxY7;APiTue&)V6*lZUp%dp?MtDku(9Luazk(uQnK zAA3}IzkCep^d4^{C=XLCB~+tW=2s1t8wA4hY2^RFh+v2h z`-InWY0hJ@d|nvp_gwkX;gRZ$+{8PzVbCyNl#l)11kM%>M85sn5b8JSgZyN>75ELY zL)Ll|3~7mUU;5qpSgg&z;gRld>ZMc8osJRj`LM*v?F0EgW%^xVtS-$hhb`|2_6$&e z&8(l|gwcV>y6^6bLPj|9)tmrWV_OY*kZuT^`|=+BAN2g5(7TXy9NuWbf|%7x}lV~5!{h$sz*>Nz+KU=&L z&(5Silknq{I7y(s=lin}t9U^DfAYF6Y_l_6yE=c*(P2Y+lAYB*--*^k$;UY|ggYIU(2B4@|bcBXU1YFJ^e2o(lu#FqZV-3Hq;}FqVZ5Ifz`#CzZw3orFAi zKhHnIbAU?yp;fa?cChU>Y!fL?SaN#sdP#n6YX)0+ZIB>wr*#?ZShOdyy3SADHxJ7j z<38Fq&UO~T$QF-e%xi5owC^)8mRVKM`KZ7{gW0l*hUoK;wq|T=n1DQON&|Lx;}GQI z-R_85Vbl+EG?$6B$`Vn2q>s6HXCOVNyVZEPkSDI17Kb`M)vB|%S^mg#6_%`l%pN&p zqAxRBM6v6Y8zNbd{YCUG@^vz^>X426X`+Hn@oIqFPGK(Qcu-wc;jbsmSVbwlr>er9 zIh~oaKIv=uc4pQd#P1gmWG&5_g4E_lb0Sz$jVpr0qq8Ddo%X~UI|njbZPJNc+!S>B z(Hf`i`IABsKRYk!*Wi3a#p*iJy_5b=fB*k-Xs1}H9=cbQ&P<+r9t&?r(wYBftK(pj zatF%CbcqL@sIAD|hQ>o_&KA;-jE6Rc#HNAq&>@uAy+tex-b*&aZ;l1w*FMyr{bVfE zX2ciEd7hjV1}LAqQVxsG86)p-lf%*$=Ez6h%V2@h2H9$|3~U}aBWIRpfZ;P)|_U@2bcopcxoZ9U&Ql#U)M(78>`?s(i&@e(nvIc<^B87!rUvqi7E0LY z_^DWG+awJoc(43{+_Xm~tY4RloWc2V2JsmF-TJ&&H&FieGS4Zrr3Ttz{JZsqHpERI zDPU?D*%yB(V9B|ksDG-p65_%?BHP>W?*S*hMtdSwSeI2wJnX(s?H0c~9$KbsLizd*31E72J+jG*1UNEyHL}gUL@w)z4BZyZMb?|ikxFVTH#E=lynaoXO8F`t3Vbxbo&Z$Lxzr zrvLV+bN}T%oyvY?u=%a~3C~xpbZo)x1eo;`n(eFOR8dXFN{svAv&?g1GoHU4pTqwz zEUleG)@J{ePyP?b>=^?)e;mPa?8xMFxcx8;`PO44bj~csab8`gfbZWtE&GA;t54G) zb7(B;OZNYa6jfoKr(NKA+OdqA%^IQK1=?>ddHhj0JUtlYuhzAP`(1h>SKsdjuST{- zmgNRQ?MD==T*32#jGuM@+sZ*Z0|K^omU9~87>&Z>I~2Wx3}mzd{l|Epff&p-0{ zUlp)zMl~!OdLbE{e`X_BPK$ssZD=fg={p2;el$QImMiQaYa;ER?(xuv{0}sTf3yCs zP^>))b#A;^BrNw#LgqQ!1)jgX%DiexQ|D%U?Iij9#HF=!UMX>kgM-krP=<0N&IT&B zweMAYWH;$lh5u<^;yKtwo{ybL{#1o|+p_r5-J2x+?U&>%pv+K|_-V6Pmhy2gveG?} zU3vWz*+0UZUGsKA`|Vzpi$$do$Y-tW#I3hw$db*_Im-$pJL>Z6J-fuXy|JisF{K{6 zr#TGS|6zBgRfE<7*`J58n>Fg9d>{XIu;~;!|C4%3!4{=yiETpV{9FG{I1VKBk;9VO z^e*sRDT9!`G*+13ONAZInW*ExEd`VtvXCe4PJwyR#MLgOK)ZEQQEv1i1?t|Of_$}e zDs)lhc)u||6$&yYpnQ8l3bYtUWeX3bfKDS~bAI0TQa|Dzyg$y}n~nNsrY3{=hB?S> zHYLNi)3cEsiju+Ig?Q8WWVldDIyw(hA=Hq3z7dlOx_T2)f5MLxm>EdE?Vq0lFMVj7 zyy21p`Riw(PAtz`@hoK)vhSH>7xpN*kwKdi^xl;2QSur6 zebPOX`22x?vGm+MUoC8u2NTX?OVMI`TO$>HdV_Vc_;s!i?r1L{GE#pT1pml zm44^q4F8>reWmp6m{s6tW^Qy7%huoJ&0dbu#kwv!bz@&ktdXR+xS#+k+wsZ)bcBgk`Wr#g& z%cXsmQm-b^!=B!i<1+6F<1UAzZ-!R6!k`88u6!F&M|8`hHG7K=wVXX~(KB@-s*c!A zC714(?XQ!6<}-h>_A?9djuXA7M$9S_J60ddq;?qnN|y~(of$5;>&R+8r1+Ia*f93v zF})XR&WdNXa_D(4c2=-GmHMJoR^29hDQCt)8Q-(#o$>f5cHHvPrYwb)tL#dqZ?PX$YV(nyf%y)q!44gIzS`EE#m zmUFxnwp90m9s%@ki{yQ(~YAZbZNYD8H#sAdLi{Cm6oxRD=s__5i+y5p1 zRKr?4(SZ7PRrsI!|9{o{M}BcpGK5>vyZ-UkWN4dD^9|4Q$?*9o%?)Ds`KX_{|xR)$E6? zyp{neTPQwoe_satFdc~Ul7$)Yc#|jc$RQapXu(kAhFTe*CyYSOFp|NR`@NCp|Byk~ z1J=lOx5}aYu6D>4bLH@B8MY+G+#{=!~#+{a%5k@Iy?UKFT+X9J0&dA)f>RPWxwa@g?940ZhG^Bjj?+9TIHE$2D(43W?A z+(e6?wM5Qot$+|`ie2>J=Ra}{^ijT(f8%*+zaH}25ehiAjOx<=o(g9-D^Ol7gMWwn zI}ACpXF6QoLGAyIe}kTuLifF7V=5?yk4GJk@KjjjP4ieQi&QXpJqhJkYo&r=U7FK+ z-$;SizBCX2bvOl{^KZ7Kct{KWE!hJ{;s`$9j@2hNJj2htog{sYrz!C61KDZcBo&ma zsgG3)N`)E|sNQD>QX%a8IJBwvAr(TJlAk9%GT?l>VJNTDkN@^uB=I=s3^?fGgYwgs z8DP`G7ui!U12h8tkQ1JzLtgIyVq$WA zb|+vcj;95C`m^@KTOl95mB{vu(+l03-3 z0_A18;cVPO(tlcD!UFsEKs#08M|Zo5&rDS9PzC1gCh&Gc`?r=H5oVpHz0RFO>cjHH zp(vlXv_JgFXocMTY9h3Lx%AJqKs}u_j2rNF`^yf$mcQh#9tp6n2Yq)rRKo`fKWL+! zob9b3IjKK#$b&-RNV~Df4YFIpE-!Z`wa?3qqhN9C+kfs6Shm@+S(2;kNOk=s-!lqo zJgGqaACs*_|Hjk~Rbi?9CEN7(_xx?Vl`yR_wOdvA#$6MrXGD8dRpFVFErsm{WWOpb zwZk9ptHNf>Ojz{*^5=@48#93a`s|s(s-X0p&pm}dq_}_fP z`=Ijezp}J%^(89suRW~rF~lBI70mTreZ0R>oIk!IuGem-I8KAskC}cS#g+xZX!r9> z9d@zrVC3f2Oxcc(uE@n+uI%?kItMi~VF>$vnbuHOZig`cA8*k9&Mjlvd`pUXR!dK1 z6?G?~{H3;>?ew!oek4<}>$7g-d|urLb@}9Z>Fknb80u>`j$tP(=v-o*&mnB)YN~7e zW^Z;RNf&*yRX8zE2Xkc8gGQ|Vs@}*8g6guiMZ=I+hgFCH<@7Af;d!Wb=@_675?8AD zHP1tJw*gboXJ{ySfjqgja1yI zfS>lUree-0T1=aTNAJor&O>$!L%@}_M{HpQ5Jt5pAY z8ne3}gL2b$^^5hd)0*f!Uwa+1r969&N2S7`9BTj3av5|=1k|^>=?ccybRVx+Yr?7J ze%Lhdts?X2=Y4lCgDzTJo4e^<>JH(WWUa^ z>TK9Bf0RFObw}(MMfWbF$w9G`lIj}Sc$JXMFHEYd<1nYUDm=YOJ}l<(97k0=r`NS%tg8);lS4Nw7Dn*gV3Kb(TXKq94kq7T z&s$l1)Sh@v{paGeypgB_9c^I69jfa@jR!(SGL5T#a~BCm0?Ce3H6J$ilj@zWwMYo& z-#1A1%?7L~zHdo3qid}%zTb&>PVRHD&P=jDptTJoyde82ruT*KTgkq`;as6pCfTvl z_F>hZkp0@-Bl%gQGEuT`@MS2Rm{E^OY@G;T@SgVW^CC@Q!#Nj}H*ePnE-Ji`-?sQH zwCNU%eB0xqPMXM5#%M6UauRvewK4Fr^%3Nnt;a%#(n93KYq2o>1nn2U*cT7Rp_@=X-6j(9s+S=T zi-?3atuG;uof!#<@{7o??IWSbYm)oeM8nKCr%_(NZZs(JOOT(QiGs-TGsyiCqF_wy zIpj?3D9CdwMUGq>2^IQeGtoJk|Bffw33Z5ukaFSxyJ$$gPkc2Z5$+G8Yd7L&COiDt zjCLS34mw5VAy1qV3l*~6$o|vDLahx4kl(Qwn6R!GImS2!95)|AE=wH)Ti+c;{&hbZ zObbsScOMrG^JkqxmhO?u^9$X7^Y@m-!zyNH=%EH2RgEl@zf4`Q_hOxcTqcB z`czM<7wfuwcZZm_gs%5!|9b405nXSkwJ$rPPuJUZdIqx!@J5?{@0ARI^5mS4i)UkO z=-l1tZw_q6O}gIwZO@9ok4Lc^&O9dY#9WZpwu5T$9P(|gk$>No!Cm)m$ZWF=T3vBK zzRtgo-0;E)x%(^`oU(UDe!5TwK2aoZT`Yq#tL`Xo@kItvt!=2RlN=m>Q(YUA<wl2Xw?N|3(lZV(Rje*o=jW67nS435bHR;z%=*|+EZfJ%k>xC>dsK2N zfQ9V)P3_FTMY!0Z0Pktx>)X-hWzxD zp7T@HUeB}xIfB)vB$RKg(176O{>ZHldBe}ay2zJu)4+Rr654M+B@@y%r(?a#a}r_g zG&;lCb%X#}oy|bHUa+|!bY761q5 z(=~Rjn+Ydx!;gk$sPoKR4nuvrARASe zLy!|aJMVAGz;ZS{JB4dxpc&(cIy`3;@Sj#d9yMMDi>w9YHq&KrI)mh9`7)U3PS4t$ zmooU!#ujzz^J~0!kFHU=zkkMtsM$s-C2TFGIr)TfvxK->DQL$w z=9-|bLG$F%P+vSB1<7B} zAbU<22IKbA99Wm<*V>@UuQjHzDg16q>&lpn+F-QM7kztw{8}U0xgIE>9!a`3bb1ax+R~x^A?edn`r4vQIX|YYdFf zWRvSo#qs3u>kr%h_%PB@$rkjXeXFD`DeV0(%29TC<5=eDLTluw`5_E8y+u3mKl-sQ zeOqI_D|5|RzYb2w8ZYXx!~-;zj(vJjG|Hs0_fk=&=+4hjNY`jT@=ft~hkvz?B%{Co zJqMO_`0qzE{#(+ls{H5rRQ9p{zvFtf%m3_$!XGv`-;eJrl7EK9%?0!3w6D5)%0^+y z(|GhpKcY6|ul7Y=H^>sKH`*gt*Bk&d1~x~owQdv~GpAUkt7!^MT1xx=8Cr745UoYY zx7t_v?+~yf#S*9Q{$>8BUZ;a{NV28#!@|-8m=(7c^{0FbfutNd+aEb^5I9`c$GQ$o z-v7x}${#qta2HQa(ZI1OLI2?6`iuiR43Gft($#O=nArd#A8b zXDN=CIBE$jm3a{uBEY|ltnp6LCBr2DVbr=k>V{~ zGvKWS?J3mK&45|Sw5MRmzv0LVpgo18J?UWdjP?|=)6yZMS-2?88=Ljb06!V+Q@A>1 zzO^P~YQt#P>cXs`frE$ECuo?-S6@P3u(nd5rdA3bayTZX?=5S;x;o4ZcBK zbU6hAGH9RW*~t|6a+_G%i-}Y1#i;Mm>^qVIJ8IG%O`l6CFnvDhzkbfoU)>>_nP&WK zRSnvsahRM6jY7yD_5Gs+zOU3zh)PtLv!C)%APaw-S2m$nic_g?XO=$rt+j-#j2UlZ6`i<9XUp&U#wJX`GL| z9D(v|&iBfQC4E7qzu|N`gYiLlzoIszv%L4Tzqx;LI$K^Ait^u^)7g;SB>#RPoqhfp zi1L-yGuUzY2;}EB8LazV>L*syGFb9WgM z;xm{_!eEp)Ynj1r7Y#@LbL}rjoX2NJYLh=4RntcBuR-lOe@}sMTA$XiCoStiTWeao z#Y}MkXP++E=2vd}z?!ABj!RmV2)-^fx4*#8NeAz*j?Yenn$3cya@go#h4RRXICvVn z9a;BiFl=e|5&2_b7ns?B#_-ax%fj5xo!@vm9BJp>s-s8-c#F8c>ks2ZT8k#Qzc(pBigx+O8?lb zM#U+YsjOmlqvB*0tIoDzy{*?dh<1C)2WfoM>(dO+*QvAWOd9HcTf0rvs!s97$&0>- zbI%5$d~{4(=9%w?>|3KZt4M8!d_F&b_0X(_?3o|SY_IGRr0ey3lELZ>az}otnaLW9 zv{`c4=>8Q>(V%z>5Z)lauM#R(De$pwGB~PIDOTK?9iOy@D0EReH` zbL~;*N{O5eTVja3>${xw*xwR)t$~7V(Q1Y~i=Sn4xJUMVxeu#i$%prW3Rclq7j=q% zq_PLI709_;GFf&)FMN;OUYp4>st-V(x0*kHHwPg1;!byIe^U!4CrgN0crsy*EtFfHz*AV}B zkjYw^9>TIU=P6m=jwGMV`Dk_Gke8Wk%ea}SQ`L6+x9h_Gt1A1q%-4^gwtoCu{zV?Li>u@-q$yG*vU-a6!G{M-7*_g`b* ztHZxx4j)0>@;!eR#yGm2p*FN4>79@Sl4pwN+J^+x**SP+jL; z18bqbYK*N4H|Jw)i@`L;R)y8;`a5pN`($`D^~sG(l-REGw4!r{Q8H`>91d=3ypld7&7~ zO6@%Ql@%MUZ--+@Rd~)izRoIbj`~$$-VUfM)m0Tfa>kuif7Jr-YgKsE6H8WIpJHoO z;i~wcuG7ZZ1}e|kqCZt(-Sr-9^7-bdUlrzcp{}ZZ{+2J_bcdVQS};k!Dm)|03X0O~ z&~8=upZF6pGnv(xItS;sAEza=^ju@{^R(O@^bvDh3}_h&M$KvMDa&fcvK9@% z`&D+$9-g+eM0Pdtf|QkwkO!9s!0_3026Dwa8*poCi*kkU6mfg4ROCA$hs9NOVvzT~ zP8T1k_Do0Ko-TxsPC@yX9uOwxj7521h^}B7K{0CGj+)|>GUB%9s@iTrbEFr3*)F&xW$Yq0m} zhH{}?8$9`0XGvc#qZxExOV@sl|Mpgr>bJKh9(h&Nk&i=?&Xve<#q~0Y+w8O~9&m(s z+n5jHowvcLlkC+2Y9FS!@#HbaFwCwO%7b0ogY~4I$SxPI2+x8kcC@VCQ|C{^DQ>Lu z*uALo8`+$5x~zEZDw3BK1w(ch^1soQ0C1Z|?H^ZtYGH!vT*sPvZ~5C-%jo@8%4KwmpF2}Fcfw~xJr|QYtLKt(;5nKe zs&X{V=Q)~csB$z3JV(<~RgR|fJV#TmDo4{2o})=`1;vFvjBNwi`u#wANaNQxwn9={%U9RX9v%1Rj(#}Ll@3-TfI@`wmQahTm4k! zw)*vJF!WO8w%WjRTTNHxwra$4TlG@qw#w(Ztvaf5Tdm{yyFyG1&sDPeP_uZ zb@_FEpWT}@z~4StTP9~Fg@&l#)IE{S8?X{Nc~=;7X-L0MG{(u5O@B^jAdg(oWfhU$ z=znvzQ&c>RMgFwrySVvXAacMM19s1Y_6qB!IkJmG=sZK%reGG4@e%Ete@|uJ{glYg zCwsEjZ;hGc=b8LY%&bH}-ac2COJxn^V}k8q<*Tx5(L@-L%K_)*zED zu-T0LbH=MoHe9zD`>^pyIlDE+4E4L0C$sYV*~mc^F>J3}G4k%XQ09Au#{3C;2C?jQ z`shOw%kFF`>x#V2--LzF?}7X&QJ2-V=PH3D_2IkjhE7L7S^ zw{2LgnJs&DMZxCHsDbaG57!l}nFaB(`wG^iZFQ6fzgDo8bE+Zh)mJi;ystPn`)s9T zqpnka58FT`%WnP<<>q{h_WMnCMlDmYchTBd_EHN4J1~V}P}MKX*^tEsDEDa@%gXa9 zPm5M+Ec~ywu$w=g)PZ{imcR%ExB{J5iraf|<_Ht%q+!fg`M$Wp==!m?Ue^2~#MmyxO{QJlW z{^VQOjj=4T#(tDH42oxU0?3D{{_!j@ns}2#JUiWKE9x}ozj5m0MLwH9j%8=%J5hdY zzk-<>)k5BTTh5lOX@flPjEwdAY=``^B!x9NO?z97n z{pHA0ekHK`w^t$0ktML(m1~hFH%MShVm2Um+QNM<*o0h|5YI+cZbp{+vov>lZ?N-E z4F4})!uJy+B6g<^mz*KwOBm&IIFuH&yf*YOxtu4CJ+ z7HoD0N7V1sq%W&kV1PU~vn8DJcmEGo&(W&jIaFV%a;S#$9IEY9IaG)99I9!m9IA(S z4%I9DX}n#)bErPN*$Qpu@*JvOsvN57HlOfZuU@KLuX#Mz>$LTx@4|Dv4p!xQ9maFL zE>h)s9n5pR+Ng59cILTW?Nzy6bN9GAKUU?fRcH0ww%@;=7eZ9|X${Yg7h12SGZkU& zTM3I)`DxYlT{?vbnnmg8|9a&KAzPLIwjlSd;G@ca8}-fIIbT(;RsY=LHy(7akI(fM zW2RS(7v=U_ zLRr!GNN<`OHgvFVE)RD56 z`R_}<8;tTj!(WM0=hFPGc$*13JCJlfmjSyoxg+YF88VbvPppruI5CPPtf;`c^ve_3 zk6%lXe>lsTPpJiR_nVpQnoS)XTe|R=Lbd&u@w&c^OJlo!Bny&n|Btu#4vT788h#}! zf&?R&0Rcf#K?Ma?izq0fV8BQa6(mT`%nW1B5kWEMEars5Disw2<}8Xip@NBRmfNdp z_BnIE@7?G4KKFU<{GmU~>grm(dUX!|`7yA}Swya>HyR4IenGb6=evANGhmVq8+c04 zj+=n-x^dP~@rSG%V(Zt`cJ1(VyL(DgYFBUEz1+RD7qQI!rjS!aI){T40@F`NJDY`b z?l(_zpZKrlbo-*3Q>0&C7AThe&Omup>?!eH1jYN%{iAqcCbhj~8VzB!oj>a68rVa4 zx`6CDhk^bbN~>1<|LruXeoxf$1oykt_PAnW17Ds|n>CgmFQVL7VR`B z-z9cf5sy4JB0@Yhko-w^w-BBA+?3?A)9N!t^)HbB>d#oQDOqf}gr3o|*>3UW0u2N;8C|fdR<&QEegiEkkzQ#bD+h@_*VHe>i4M`RDvEe<-+9A9X6s-9T?s zd*tTvmTz@i@WhFJ3Pc}RAwe`REATKkN zv0edvkgxH+#^w2!Fuxh_`tI27J=ms=+$v}L-&�WvfKiyX|IVogX3W^LxsBHO}7b z*6CI(`IsMXKhPP%Z+wS=VT?YW>wEpnNEkj>8+lPg5VVP{g*>}B1l}(ADoA5o6N*D& zx623QLzl)tQtx-j4Q$4NMZH(ZEk}pJdWWaT>#l{vZubYsz4k@G2jM32$~Cbt-KhZi zeQ`XDKADf)(IgQX2X9919G(Pb<5wfkEKCNUs$Aqvol@bP@myqAt2D6eHVt{ZVLHT4 zmm}Y{7yvU1>CEJiy8|Ggn9fNq)ffPwuSx#ndw*E-kyx*~KkWHVy#IZFm|v?2K6~Z6 z{xCqBc-!0lpsP!KlXIyK@#xC_a6pUL?L&XKSwnV)bDN$jo11uC^*@okKKCK8f_PEw z0pR$E*w|zM?6^U^)NBBlog>z^9SJ^<=}c+8PeUQ&E4{CKF9t)i#YX6-<$Ztn`B#19 z&tpUQJ?-Bx9hUA6f(tKdkl(x?1!LdQ+0MqdA|P`84U`8A3I~lr50TBLj)n8HE0EVu z3=^XE}Sy_;ldmH6e{9Afs^cJ~og#scvYhc*i zX$p{Q8X^mC?)_T(+&6@ zh@B4)qWr_FEQky(K$btxf+Gvb=DrfsOl*{VoAN-x48KsF{+geQ5%X)ZD9PXRJ0_+)JApiK zQZUnSqH(Y#oQ)ibwfG$q`!A4AOMYI)O};))3hVh$!3<82P4&3c?feNJa1JQ4-a>6H zb&mMFQrx#Q3CrPYuR}!LOVoZ-m-i~_CO$nbL!E=ICyFcXQ9H2p>eqs8Deaq6=lq0J zHYj&C`d_y?ja6)=w$0m`EVior0Ja|jFYtR9Ev>LTf43`x)i)g@NYC40X(a2TxQhJJ zdjR{jyfMaGe$9%7J@!Oaw_kLx9V@@#hVm69zHG)?Gi2|<+l9|mSTDLRo7+(*!V*u*E7?%!rkEbDb zTMz?BFH$>a*XBUDeNhABO}gk0Uz#;QzI(SPnCn|3tJ~3z9?8eGbx_{&P84`vqBY@j z=O#l*)Kavc<0S+4tDeZF-y6b(G(V7hi~ZRU8mAKPb4(X51f`>$)4h&}6Ys<#SBBMt z!$m`o^>e#GWO8TZAKCuUGmdSMe$r@MfeC;8B0 zRs+bG=#TQGh8x61+Y^z$$Bl&NSvnxa6<7Ctk+&PQB^G&Uf;=P;>LbALca$|WWjNdW{ zxviE0u2h>NpW^G3;<9NUmSYRPe(5-s+w=IiP5FXvSO!{`Dxl<+HtL%%Q9xa*y2#J? z{6)?O6Xe;Q6tKg(5pwQh1?YQdB3lg20_|Zh(9YPTERZ!XM?RUH1&@zBK(>s@f-lb> zBLCv!LdB1tA`j@71)hGdk$-mJce$^Bk6g%K**g+kUtL3ekCy{s#$2)))jg6~nUPJ)u0xqa zdjpK?{vF1KOr$op={sAtcw`The?M5Cjcha!xrN79;p(#xWF6mYLP10%@}y%0!m|a` zu2yIL$)AMePSiIUG|q(GJwRiI-#0t3$@Z=ocEPZIEPQ%XWc|^j*r$(L$kLwrN}qr4 zuYadv)4fV&|AqF~uj2dbcc}K)|5hfjHs!Rxe%#=2Hcs{szu(-K2{3i;7UaWxJ!IQf zw7=eh@2~fN9E0*a(V(cmYJa`)_XxJR^9_{$=KJfHEvEhTDSUr@y+nrc(RVypWLFyN zxYS99X|EZ{q<6Z)!ANl6_qIvgt#3H=+eALZT)rikhen|M;WA_PgAGQm_sW^?<8?$H zbS~a~`+Ta`ih?f{cIIWeWG89y5y9^qm50vHZipJ!$j&(bhvL)PS zY!&`Goq+ODQJ;h|=TKx*!!GQ`Pb#~1@ICTxRD0ydEFTQX4UJJ}&sQ&K+n_b_NGAud zTI!12Qy2=xe6OtJPj|CdVoHZ`$R~$u!qFjt$kV)pq8mpwnV+Yra7_xlX3ZdUK(kbcjLa5nH_VfKZv#A9%ryS{7As$>ub#&Rm z+@kIL98AgPg!OBS%)1g7#V-@ix+bIiquwycs?bMv8^oox;AI?g;*w&LE}3|HS7~lE6uCwJ7!bs%zrl%ZI(l@4Cl=qw_K3 z;Zr7n?y+Lz_KlOk>K;_8tPwJ9tpkNt|D*ti-Mkpmyl;=M#1sEln!OTqd@O9rOzR& zXz1UK*tBaTy!}CThAJZAAdnr+A(1dLjpWihQWmZj&X1vd{;jr!FzAdN^WmUDle&LZ zt))-yWGyyRjSs8qtIPZ7{9FGCw=-B}$HQ3RQ8@=qCEV9SEe$d7ya!-9tmkTohpA+?z1 z?&B85Ll@OuDr1zq-F3-Ulx%+9odIuaLb1%O>u3u8)`OTNSLc94Ib`eDp-wShZ zHr8v?)+B=UunlNuZSfemyZjxpmgzufSx93(yHdMCkA+U?k7Aw)MCVccQt*0(D7&3R z^0&i5^MfA7yWwaiOe`3Hb|jvp;%)bPLa8pDr_?oRB%kl0_8WT`1>yM@P(M058E*7i zitOkugWOY|$k#&Cq3y>s*1rvJmg3nc6;Lql{G(h`D>vd%tzd0dSB{pUQ!v-L0xW5#JjHmjp$C72j(=JqxG;QBR z=xa-D3Gwz~ckKYGgT@)n_}3m-^|;jKd+WCpMn9vn<>kap!a9#cjH@Q-qhL3Y+5_*5 z%-9*H{wR+v=*&j=Q$5wvuOFMRs42=z^hdJymbz@NK3{`3_&c_HC-HgMxUY1N+Y-KR zsB&Nh%AJR2!GhxF$P35vdE4brkl*t5dHGIipVv>!f>R1=!*80v$BXJbLY);Id0RSz z+UKk9DPV?~mLSzx?%(Cmqr55dvAzm$&8d(4e5wL^G%`fC-J^iVmbH;*JXJt|HuW9a z704iBW;c}o;(OO)9?@QV>&0@=|J4TNF{5yV5)zztPQo0SkuY`h8&yg*PmEaTH8pF2b{RaE{eUOvq@bjxOB9VW_Dj{YZ ztxLBV%-a`z7NUH$yApOzS%%z_-zoL!%wx1Uuu=(w+slx{J}RLHYlm#k*IORSHb;KO z<)<3ALSELD?-?Aw677r|!uwWNsZTfcd=|W$UyO3;8$VUcg$4ZVgn4gh_W>+EpT^!;)%8#uJAPl7ED#hiV;wuK<$wW5o^;k4{Ms2pJ4-LiT?)2TAZoNq;8%W>I_ECM=m4+=)|C!BL zHp~1i##M4FmhJ0*1X)>}$Vw*C7{Z{dW7)4+uTj4Jq94NI)O5sXZ`Avf^p2ike`J@&Bh(Ax4 z!N(i{?KJ$H1-F0GSpgrp+%)&!@_Q;dAKwEhjp_H_S+f5sM-U}_eQtlVCY?Vcavx%= z&g1+@*BLTMUqCwQa&xY4{ObtTS>5=|gPJ0DP7Q$>m%d?GgSIg+wd6Q*%nyFf_Vszl>UNsxB|y%Moha8E8wTZm zPmwpg9}Hec_)`~?BQQ8k)KZTXT4@nd!x+A zg&lp{3GJ-r@usWd_2Tyvipv|3{7oo}E~U0y$>=zyD<}I#{JdJr88a!~22t#^?`7nT zvXSgkG_{c~d$_T(OqzEq*O)I{{7hrlgZ0LVar}%w>A9X-_GE|4seRSxxCQfE(HrHK z4z-xWvLNKD;v!+fsTkyxu``9=kcwPf+)?OgOX;&F*;8oPPlobG{hkYoXEbl9B_yx~ zgLep0T)Wq`Wg*8H>O9yvRfzFOLmq75FMQvUiR{vHuQ0z8rSs!gUj&a|At;X+-I9e3 z?StHqbz)5pyC6I34Pnhw=$)!_*`-vr@5>B~cY0D58(j4W+flKnmFz_8_LwJ!PLi>R zx(w6JD=v}kPo}n3SP_%R+?Ax0mL+2kyeX{zDJ7eE+5v5LOv_@v ze9TLF-i&Yl?7DPkA^$ZA8qUt$sEs_$K7`e|`yK7uj1FUIqbPsQ;`)UueRa9IzGUaD z%Fg^!ejb9OBa`fV6r?lFh(xq$cwjthedsRoJg(D2rK2wIeJY*Z*+=71VSefCa+3@} zva?M#mKolzKsL7N22Ia*MEkqB{Ohg%Ti$o)J+Xe~c+~kPcDvSu6^2rK=F5X;!p|CN zQ@Lle4LcKTgvY%I;8|qCfrLJafzv!S^7w_Zq*75sv+)F>qbZg(}YB zIzB3$UT4;c>z+`3U=5G=#&`!@GZdm`Qe1~hR|zL)QG56#=i@5Yda_#F z5lHf%k5`NNDlXNxWE+FXP9V2wqO!TUwXu+$L^j8B`;jX9z~zfn^3iM82-Doj<^;}D zRD6}&T&uEKX1iLvnn^m>IbT!p5?f2A-J9ZF!MT=-gPk2=X^AsFSHLq9=odH$`R;^D zF>CG^WKW0MQ18re>boK7sBunzTj=ekVEyv$4D z&&GdGuLr=RlQf=IG;A2;$I>{`qjPQ`zGz4B)-i{mbYJB3Ew{vgC>rUS5`~U33>EqFQ!nPfvN6WzO}&0!l^yr zU2Mykl6z)t+2v^6V= zVA<>@mK%|YsjS(;*~q=dD43UyDYCl$5QUsguCYaVtX2{`U27e3QKxYBR_76NcRuc7 z<-G>m7;iW?{aK3V>%QbXzRlC4l5g!euerJr+eH#*t5{t}J*>LT4m>}+`%eASCZ{5p zZtI((Wb-sJ)@iPkDNV{2+fiXM3^u?A9Rp(<-bjd-9&@O;24dR`6~V%GY(6 zEqqd@BHPEC7B%JjrzQQh9oC4y{F0F8)~f^4T!tgpZ{+}Wwz(n~PV|I~-ffV*LWe{9 zOH?=AYvBbKTUwx8-Jisty`bGhOO!u58vxnY4Ui`%41)z;`p72B+#yk`9r6^tW-#xw z53>2w2V%{^aO7>xnV3FNhJ3cqTK6Bk{~`Ij@nnVYZX&h24li%P3_kTi`BPa}_Ib7w z^5ar3=Hf$Xa`uQfK$})%M~ziw2+G&KGy%<#gOGiAxwLWa802@IYeV@7N)x*%3wZUI z+C0S}UEr^6ol!^Kj%R}o;Cs3|%H7&Ff*k>V$V-0Ih|LdD8)^Tgx8l#QWZ$O030yx# z@v7=meD7x*yTPrZju>`3uTS-FSNvb{`nW_taS9 zhBI4W=ZMc`ye*w|O-K@?G^xkia?KCjMON2Qm-`f^GpnwNr~_f?%w<1~dCt@r$YQV8 zXOf-4p~G2|OH{VUvLxwt*j?Q?hR{*4PFfk;l(Wv~oxLZxY$=MKNnAY!tUyYC$$n^0*9FQ(TqYhl%H(6ur8pfLuMA*LLS)P?4=^ z49YlH0mFLI9QT3A3TPid<5V7*3V7*N565bj$Q2NzOBswkewbVApIPTYfY|EKzy@bIA*fAP8LLG)3}^zi2{leXbqC1b0)kxI1Iy9@%xa2 z^ZbyFn#kb5K`)YbS3rnuL*x(KpBCTAPk+9CsKb;xC||xO5yXA#k#CGjg3`^jme1g8 z5-7@+qx@-LG7K1*hkU*u89He!LAI%z0=5;4k+1uwK%iMR^87r$C$aNFg|IAnnHi!h<@VyluqbaPFXFS}Uwg=^F zcf>&uA9KPnNtOvQttf5fwi%F~N#l5LZPFq1RVM1}zMl#^yk{T_cBxR(i=Hcv@4q>{ zjGlMj!W7sUN$F7In*ydzls-BJDG>dP(#dtelPlI61WGgK>Jta zNpQPt6|y(KPqNyV@__#`1@t|mk8)pru1n|}W8|Zj3Rt+TF|wHjzxTDGH?q;LOt|)P z0P?O{Sx|lDC+4xnpLpIjr#xB3$AO1*r~LNnh5~+^qj6g8hYHYJMETSFwF1Nd%D46B zE5P57@^sq?0nX2f@9}kjJHC@n`BFZ%`JQ}UzmK0?b5{@jIo(hOn$IZT z-r(ap6C3wLxz}>;zXgqdzJ4nMkH%e4ezJ!gQZ}|n&e|o1vLH+3JKhS=I$Iyvg6H{x zCiD$<$V!3Wm-H@{d`SW2=6R?yp5MPQ+;9%^%)O~#F=;09l6$G}b11#v>AzFqsNZyy z53Z9A8_v`E)iba8dYk33DDPaE0gI~wkqz5NgWU8ya^9N>V0HWiaztz_4DEOnxi`;y zcB;H*+BOmHT-${5MWsoQ%rMG>*Vjboph@|E-vz#hXlXv`2=`;*&bPzJbA%X3vOSLM^eq~4 z2A)CgUsnbihrN;i`j7!rchEB`s`)titr(PBS){``PZ{zOMH=X@n2bDLpF4EY3|XpEbosuUdCh-f{i4q8y-EdBF$(L-`Sa3* zCK2h#aqnKbM~tMl&5KmW!se>Am!ZcSiEsJYOOnm7b4$eZP1HVlI_jpl@=yfIO-kxP zwtNWktp1MBaGx{s{PTUmZf0|2^>{Zf;BBH2)c!14*dCU(cSD^Lp*{pf4MaBM=R>Yi zoe!C3RU$6E9gXsXrx%I4#?x3_1h|R@+o(M}p#Q9*`4gx;W;3Uc`}n=YafNM!3VsHa zqzga){$P}>quKXr!}Gt_}bCis&%A6obRaC zk?!E@NR?+vr~sk)ti;+g55(9Vzgp=WgmK|qKplb&~V z9XB{}xIJ<+Lt6-J;eo8N(hvfA1t7<`KM+qop!GJs-t)!N6)7lBNOloxF3XTB2NxC% zuAu&SNq?Dm$)3h@+*e%^?{$wtokwSN;oHU$$lJHHgte;kX)hjjf&#y;DA$hb3pT%+ zBU?uXfN~u5e~%8nCw`qz<6r}{PrDmjp|~;=jtXHDVo~4LwA#I~>Kxs2BVT@3sX0i` zIDJAOOzNnKocV;GC)w@_reSEWWcb)^8FG&}8Qh)T1G&ma30*Amu&ot)p080^+y>iP zCU501#jk}R*_>RE3PZDJBCq$30qA%fx!0l5kmp^Ee4@iZs98kq!-!V`e4B5FeqL#A z2fh0<)<_~Oco2(?{j%FoVZMDP?zV+!6(KF<+tDSvwS=4!EuH`U9;fmst@>#`P0)NoS)++ zJ(suE1ZWd*2Du^cd+q0aFiGCA)DP-SYX}l|n0!F|wSf9Q^=9foXw*oQcm2y6b{q9X zE~vv`OQaogaejZe7u^K;$ZZ!eYEEPFtv;DT<{J8z=b3&G-`ojBo&21B?i#!4+f-+R zyxrnJ)f|E0=0RfM^i0%WIb&&2urKMWv$~FIj~nW%^X+H-+)wPHu-OHpg`ktvpStRO zMrfcr0rd~0d=O$q@=aZT`l(Ao2S+L=tLIM=TJA_g{YE#N3VXDvJXG!bL%BL{&T7hJ zLH$t98h2+d7ds$ZHSuA&R#YCYZso#4%P6hfW#;U%g)i#d@T?Lp4yL}ax}DX%Ukf*$ zP#-_%cths5j{4CnP3@U1QNXaFXFb@*J~qhf`}?qc51S!BYU0Y?A9aA`eFlKTEZVza z5Yiu7o~FGazt;JJ#z`~WqwzR8945ai$9m*w#5iDeUm}}K9s|oFE0Oo?8x6JXtC4G- z2ZQsLAIL9$2f`*x4YZ@7HwrwGXwS~{<7r80W z%Zu77O?h8*jDp&JkA5UT<=xF_zw4TK2%onL*{y#Zlx(NA?u$M#(5D(u-t2P}6q{c_ zKF81WyTHqTsa+8>I}<+V4n%g~?c06IC}j68N^q&BIo!#7kHh-cw8vp}5#L|DP#1MJ z{^a|zGign1B;PktZz1iQnDvgY-Mv8TW7mG<`?z&zkH*d~S+GtxfbC4n*ID4@Px@_& zlHio@N{UxE6_)g%_Lz*fCBg)1OLWo8geGlAp$^+F1HTL1k;|XT;a-at$bP&p*2$In zVh(Mxz&qm;#MUQV^MUf7U%WpQ&ToMF;;tbuGO8YO zM#WG#pi>w5S*|abT_gQ(vwdOJBjO>Gd?D@~u|Wpsuf*LFeIZN39K(K|;0yBF!~v1M z(9e)KX}m9-HzE$_T&7}gt`n@%X&2)QPO7k(+@`I{=GQb|DE~%rN#*A%i>2a$rPM|` zu|iku&-<^Ee9)`b?q^G>ESfcZlyIXSm2YQXoD$ypQCXxOR$cyi?I@v4pY+x3e0`uR znx7{7x%{k&XErUdJXhym*OlyR!$w#asI%(a4AfU=)wv%iujJ=x@TKBX`el#I98jKyDId&Ftn<-O+A(FXma#3gt7) z2D4=cjgZsx#xOrtiS~oF6WFsQGzWd*U^)}m(%hW7Z@Dc~*p)4dQ9piMI5X)&@Mt4YG>rcycX=%XBs0tX3&WFMp0RMcB=!s-j>FAuQut+ zu0~PVmK}$)(xzl{HXmaz)P02U&Xp&z_AOQ;FW#BOI@!}2Y<14!XS2+$FhCvW`$|?i zR1e=py<SJ=Aqfeks{+jiy+S_r9Ton&k~qU!DE4ve@+d4=`-a3x2n_U9ceK zu~L3E@Xj?mk=OIJe>ZilnIwP6&sUoJj^+^>Jy$~Hi3+r@ZpV9I795MJK%4hkM}Y66 z+h|AmK8`KQ+J}5xE0eie1R}e6JHU>qu4uo5Td61f9*iYhxuAwN`PsLVG-m;X)>b^x_4eauI8|IX(mB>x+h=s}V02xQys zi-qp|-AnQ&${9lZ!&Kyr<8y@rWi;n_?Q?zh^0hz8b*5>vw|b+HdyT8h8Wjvh-v4V9 zi+!VsJmrut>wnk`xko<_mVVa;Iq1wtX7xcE*`-eqJ6KQ)d4HeA&}ZrZlF$1h`ZPnTS!-(9kG7v3gOY?B-B~aqX|2Eu|M+CegZ3ZCp#UsHH3Ei z$e$q!ZCGqT@4DfkHe&m=WHZ@$mGE>O*?Ar=u*oec?8Ey(Y+FJN=I0R_!R*Y(-^h1| z2D0`6ls7I}k7ikezMy=9elWAXPC665D#5*F27X6RkIKQfjV0;?@$p2>iq*&&cgMl) zwCBjZH}UQ-xLJBZrz)9X{-p0=?AY;*69a&>>y<-?+l;Zn$8)Oor3qj)HmzD+@^T6}qy@@?Q8GswK{ zi#kDRt}r)%@?NupzF=QK-^JKlW1&kbt@|2p77Mo<7vgh`;_F$ABB-ylrCJWhM>I$I zE;l7?t67ERiL`F&{JFtxr2KYqM<%Sf<0neooR8raOz=lm*O6HIfBOA*{w1BEG^+v5 zX-a&30ddX~8Ho40qCYpi<6uI~LFDNLgJJheBYfWFt?fZ8jK0}*v+IGyrXeVQ?)gx> z!_T*pe26w)DfYWc`RAl}d-34_%2%h<_;{b)V#y3D>z-(6LhYG>7&aoc6MUHDf^3vJ z9K7>uBR^Xf2~G)D(I1Z&DKI&FK5~VUpJ9Ef9`gS-9RhROfm1_wkbFKdtQ{o!65m`l z06gs*qugR)1SD(S5+$9GnGw*g4RNh~1E8xu=|nDT%#8a|-QD_9iBPyd8p9fK1{JI8 zSSs3!IjVb({)E4sv4;nj$+!Q;e9tal@1QA4ZTN);c)NG49`bKv-oD-awMdfB`=Ws1 zW;Mtk`P$Bc(aVtMaGo}YxRUR)ds_Vf<@O_dhORjdHYHQ z{61Iv#lzw1oyZ^O@pFU*Z9|^yp9m-3Y($)J7y#I8IulsdZ!`VtdhZrXRgS}&*d=Suja@GKCxg|aTM9Ob{wp0co;eN zBtJXfbw6^}(0B-Jwg>s;L_TKQc{lRyCGjxp82Qge#6r$Wva{D97Vft$L>)!FSSW5n zTmW+Dytg&VpU#lOz81=~TR0=XA0vaK`+Fe2;N`?F6F+3L(HZdR zcsQ~PpR>%#Ux&Qodpz7*L}_@`B_5`WJcrzQTaLHuNbv#58U z>b~qp`^Au5arlkT&N6_@wWz%@?oKz@X4Dborq74MgjRKtZ`MtMnu}}kdpG9!vdcqV zfF{SZ}lw}dagK(JgiADtX)s_kyF?9@N=RY+H|PAAs)RPf!xKVSJBA> zN|3z&6W+JIvAfZA(tp{bx%=+R#Hro83r&y7(9U?y%~Z_q8W5hgmZSVnnBQk1@H-|@ z|7D-`!tK&TN|GFcL{mmr@Ca`-oCk4sQ(U}=cbMH9h{V%iFzOF@B&#LPf8DudX`A?MJf0NF- zS;h&SH+OJ7qA3F#yT0O?xe>0~*ZF~yDgRjSBCTZz!U6|o9vUp&DPzK zPim&a`c4YuvzPcBL;eipMt4%7OC)i>&#CZy`E-=eHcA8EYtxV~`lrE;w^NXdH>Sb1 z_({lq=Tf2c28DfaD;2B~iG50WnGeKMpQpfC%lWAPaa{^ne_numct;A1+e=(>JOzwe z6Mx;30yXD}XX)|%^)KY8ubYzwliyRkjGtYj-Hm)ZUYH7%9cH3VepD)iD5$Q1rzL}mz@cpr+#K{?yChuY5; z=1D9zjmpCXyv=KqLTfGhefMGxrmgY4Hy>!nmbYZc!TawE=YCT=ZE;O+p}Rem!~QJf z$iKh6i7cedYM&IZy8LEG55a6a=^Oa&5_TM<_S@NA--P-~YH#cDvC})ps6G5OB#7Nv zSPSFT+MU2|T-}P_V1m1xJuh=W_86#Sy;E}WyL&RTeo@9vCF-m5f4T#R(nk98fBtq_ z_jeFhds6xNC;aa;K%3|b#qsa5D6eA|;dM2Y?f=C8At#eA;1em^TL zA9@?{Hci1=ccw5(QiG^ZePs zf1RBx`Ea;tV?1|JUH&84L%cqg^gqtuCC=mLUrII~{rV<;i3mX+Z|4eaw>lvA2?+wd z>{`f!HYGrxI@{2v;WWrm7!vIGd~Z z>i2d+yFv8s{)wZ_Itj5>q|<50Dxt?JTJMy9>!lFfV;sh1nQ6wxJfr!7Un^Xg|0tSA z7@;?aO$|0hovKw~Odk3KefGYb!tQBPz1HcHf}e$}gK`5tz7oE053c_l!pq>{w>zTT zSKxPncRGYzCo72Q1W}sktoCBBrqDYonQF(Td=N0MjT37#m+axlvAM;t4BR(Y z_+|Cy^Q|8u>WE&uX^i54qn^7DA1{;A_BNM$tK@%aIf-ZLQGM|zEaeUF-zERLbMtT3 zf9)VXwkz{{b7kl9sN*!P+G>GKB;1*S#waeF2uz{DHd1S#w$ zzTU{wqY<*Y&HAt9P_?23%Fk^`ff)`9k+(TTz?#K0wq|z59g45gSVZ2V58~Bz)HnZ6 z-;@+5{r+7(bk^SL{CAiu-?sdVCE2?MCU|F7!4SSKL{?vv!e;YxR~szZj=Uz*2Ucxr z29iA7=7!kdR|K*YHsEe|{HBhJ8$_e|)J|Jk+6El!QQPeHn2|6hM+fz1usCRFPkCm@ z^$e&tCj{+FcZu%zevj?3*I&Zi*XGgp^4_q6;N?pB+~Z-G`{DmV&V9i5Ao=!B{NL`n zl0vG-_1{=?Q3}i%zYy!G-Ml`1UrqJb$&)D%SD(1vrxf^nn(DjMR=iG}MfKp?{;81B zZw`hH-joU-?ohqiv343PtWEX)%-A&eWI%QOoTVvX>`HO{{E-HGS5W(5<_xayHyQ1G zZj=U-R#07hdKX_ymPBYOvCf|W)9@IIum+JG7L;`)wVOn~QSDxU1?{?w5nj9Sf8{+Q84_A8SQ+j?1C_ zQqqYW&CgzLWrFggUQGU}(0X4G5$Yx9dCWjj!2Mkm|*-2Amw~-29 zr4%;js|<=v$^Q!j<#4!BJJbnUB8P*!+8__OEQif)TOq&X<$>i?>VqHQ=ZSia%0jup zqzo7^bsX{zAI^^SUTpqKgZqC`e$d&I2II`BZKjM#gHsJC{|H^vz-j+f47-uHCl_6% zd=mXQ6`Hl7_Mz3;RPcU4-2Hee6gHy#^Y&;ebaW^FRGbP2e~`}ghpBM9BXNjf8uWic zHqC~n!Mjrwuj5{Rf1C;Vv+Ye9%ves(GT)n@r!;LS`ct=mCOm9GY~GX4X}%%Wm=m! z{3XTpCw%XbH8ZfFG21`kdh?sI{R8`9S*FgCKOJ5yZ7an);6ONQRq+7p2uUt0orm`o zY99_~56VfN?`JFQm`Z+r*mP3xDxrEda)cqviVr~lHCOns!!jz*6*rPt($5uG4ofx- zjnlC&yi?7Ny4V@mwJ{L7By!{2hf0DfkO(I(V)G8+bGF6*P6_E(z0_7OhFb?Ov~ zLz=}hw{1$;;N;~ljf+;TnbF*Nd@eO48<}8?1eF^!_ z?<}~uXD@OCz7}G3Kml^Sds(nOMkM(uzBhW~Y2?27Sx~F26uFS!Po8Zs*)9yP!&EGb?Q!3!k&#OsAHL;ggU`=_m=c7JeOO;#$ftR|Acv(V_HgK|AcqmZNuvG zvxX(@KVhRrdFX z?7k>eQ{U}=FDsZcyca%?$AzKb*{3eDMTaza-+9`?CG9f?nHe@gPmpDl?>&{{_Ec2y{$UUoX#?8nOi zyB{&gf9Ekc{m@Ec-x&(<_-KglC5&@M6|s~if9pt0;iNzRXMQf@=M2s($M(O(SdQuNsYBCT@;}6mJ?6KAN5em4;JL-np(E0*5#uTjyrL+1u2Ye`pp1mZr28*Xw5}Je)^o z1)SVD2B(2jf*go-zy@;Rrxdw*737TBzDa| zEhwz1o%8!hp}Q@wLnQgW^$tgW^0{7#pY!uooPN?6NLZWSLPxh?lsB?JAdFs1d2F^Z zh!-ZspnO}u&*H7`l;7US?~3vh<57M)dbc=c5{(gEG29`H@kv1Wy_O|~8{Se}MwfaO z`KjhpyrQ3qZh=%D8sv?Is)!2oxmGu4_URnW5sWu|FEnmG2JLi;*eqz8Q$KogsXOdC zZ;$dLVSGM%j4|?0&EC*2ozift(MDnHMAC28HmE3kE%}f#Bc;e@HgV|3!{X>yu^9Ht z{pVtnj<*ZpKO+-EGz&V7SEpVuD-OYSDQEwgNSt`Kk2hxn4y}lk*$#xb(=~)+$ft^WSvEPD*c7{ERTFJ?$ic;ETZ}` zBBL#QFK6h3*G4PeAMS-5x7-aB=Jb6%{??VB$>fCc0>v94+n;f25Tu8qCu3aE3+!xEF{GiS+__?698ebPA`M9qEEN~8u;XpKFQ-8EY{e>fK zS=qfF#K!g6joGwzW$n+ugmhsv%5Ml)h4!1cE&f|G;-fHZQYiAGo5rkuB#JRGdTZUmXQK8eTv?IVTEg{U}9V+$stlJh_BybTAtB<&d4+ebF#(EwS~UXn4GX zxH2~h7W7z!`c1YafWzUf$fpj*!yV&Y$Z(#guQAO9``n0y)|N+5-rOV>GV0RY?ig7N zy#6kt{Ln4FuH5=0@-3eU(C5M_WXt#5ANd(%=LJb%8Ab7S-H-(Kl`BzxvJT(B<8v8# z^`j^#Po`(Q^C}vG*HG9ErZId%?*!_k`Nu-^IhuFQ*NTT15B8$GRapWgF5QA0aXb=? zawwg%9!G+*hU}m7U1i;);!3v~KJJ;4H^ZjY{$0Y)_3_NPGuW(ZVZgStq3n8&wr$zR zVXUjX4$EC;VjDd+lO69KAh^fWv#q16WDoc6E2_5Aw4J*zfh{iDD%zSA*qjb^WhW*$ zz~-2iHmlc_3bxy$VBP4In{D4?e!{`pru+flLvHu38= zp$Dt9F>LJ0o)tQ<=kZHzjE9yAtByut-kaCakoPU9Zf-esmpEkym2c-Y4d5Oh)0Fb_ z@`uA9et8|_#NbS5niqg&!be>t938#SUD8>+CjlOxrTLCF{axYZWCyhWBB@ktae(3~ zaKN}w-l*xn<5idME7&DoSV!|L-?|wdDf7)(1xLMUfR?NtRc?$>OH!JXSkXF8@ zbC5bEB|y0~ja%ma><(S;I)LQcealjD=IJO%>?{X3;UGwDr{nxCs)9*vkrywJgXR!x zemY8efd3B@i~^rfvIw6aKIKh#)+Td zc9-IE=VL+P=ABW#;JOUHdpjf7SuNw^yROI~(_}E^p*ynEWEtdJ2*{)7%HVDq^sZ(14M3-u>f)j< zuAsG2m2T&PVEg_WeAlz|l>m+QVtZiaj3oGdcNM08h=DiU`q2vCOP{N{aB9s6e!q$Zg-4y5CUEbFDAR5f)b`qkQ5+4d$~l5P8UnL9E*#6XbwA9&U0n+Si`0WV!Qfb~5@&$zR1Y6nvHj`!yiy5ItkV)q}ui8a?CK8R<}ylY-A!$m{B!ZE{!Jxnb zxyyNeXW(|qs}bdL7`MFz$~A7wVNW>a=cUKwFun=tPh2bqM94n zIh3EHd3(85v?Iz_K9@miK^J7Fd>O2nL;2G#o1gb~*$w6P^JGxnjq-4(B{Eo&LGpk? z8C>`5hC0st8~LF6MxMFLq2Wt}*Qkz;P!K=A+%UeumPS4q%=m2t##L-Lo<03uhAi{*V`n-wLi_FgyD`l*9g#nbZpC`e@5%)tf`Ii=`SK6aP|#RvQykD3Ecc>F1t^v0(@>7p`7ut zDo^tn_`R=^Ip_cFgC3s?`yE1aVHW(p%hcMlQ2$YCB(ycWhTM4k2w2um594a;(F5w~ zw?)3OtQE*cc_YU*`62E#3qdYAw?nM4rGCnt27H{{jGpo8m~BO=EvdfH%-+%NZy%bS z)f4*jy-kw;`Sa!pb9HEbcIw1C!mOXv52}60h`EjxpvwA zw{Pn5UCHUpwm22_Ym%eb*_?~W-&}^WJGKTGZ;LhVtmG%v5sv1qnEpvhpRG5)3c1H9 zeKtMbCCpwp3#RR#uTSs-cBr(K`H|vvALwho!b(lg~HTagW7OI6mC&qCxVz-fxfM$2c6TUp@D3%+ zjP*p8bNg#%IUx5s%g@x;HbXwZ{anAi7P9UWUd9YPkI(M)N(rxF3-a4IzV5z?eCP>E zm=b1#`uqe6es(?av=4lZ{BMT(()qfluTXk+=5}%&x1xN?V}4J?%Ti>ajQiQT0{I#D z;jSzBpv~8Yx_TR;eIM>;(f20E?fKn)gAcSs9?Zv?w7Oa$-{EQA;mX}Y>DiBS`+G$I7Z%6z)hu??Nn{<-+IBgFL;_@z;Fy#`>X+CX~32pR8ic(kwKOZBqg61^46=uMh zc$(8(t>j~DtHz;@;F}2-+SAg+7Ero&uM8i1KEhLOJw_q|KfAOQ6~TQT(J5a@f$vOyzVyX z+uu!vfKcMFkEw8NE7_m#lm_l4Q_+6vyfjc)(7FZn`Ro0BUi)OH2-Immt{Thnv|Xc_ zor=>r|6L{-SS&qq>|8A@JDv+cEM$%b^0A9j8~eYPRq8r*RAWZBYu1TvQZmp^nNGO) zPja2R%W*AK?;8Hyw_3;7mr1{gd>zOCEbls*>dULM?um+SgV26jBU9dvB)RRhdtz0d z7WbR)VOuf^{)tB~Gr_P<3kSi|oewa5bc@5`pXBP#_|GiGD*gUB&CZ)pdvw+6FQVy4 z8r#yHcTM~!IobQqHq~{sdE3J2RMf1dG+Nm)5QLw#h_B^p|elXmveS6#Hyr2Is zeta+lvW0uwY%0ED8j!7j_Fp}&7j^A0ogIT1=o%0=tU7J1opIk=^? zLw-6;4(8qZU|gN2wS?vI{gBs(HHB7MeUSsEw}4T-?NR?4KldeSUwh=fK5|%jmuyyK z@q4IR+M!%X;CE{`S&My=6lWz%eyoo?@E-5eo^r#sX7EuZYxvt3?f3XG2sZA~Lq5}B z1bklF5II-$1Jm*5$R>`y;JLIJa=|no__fy(+30#Nh%lLq@#-#51B0GE$S*!;!cJfE zXK0)pMmjp6{0v{G^IP8uIklb~MwNRY9}kwn*H8gDXqF7jXZj(3-JJ>jb_XF}eU|~5 z&m)l)t{G6)RW&D9m<)#XOz^p$-BPlb4|^3#@3A-Uvo!hakNT#oGFi~ZDAWnfQL>Rs z8zY-vSF-X?hutN8^DkL!t4mYlcUP1wa5arJbmZd>uNx^*|J+0+ySw}>+GI1MSQEK971+LcUOL$@IgckiXoyDELIsp01}WB3W(MHYi^( z%ae8E_YX+^_$+G5Cgvp|Pv?7n(i|Cbm8%_G{2GKj)3`=--%S0nQ;GUw>)R7hUO4=u za3hq~Lx1-Tfeitl(6?mwP;j=S_nU0$4_V)Cpxo+W1h^$VLT=VL9Ja)sL#{K5j|U&U zh`eb+6!-*^{7Y~&>_1$Ba`};HJ|;>1+kqdWd3{doSrrY{D*bC*|F?qjjK}X@FsGdQ zoGbon35y;2pq&{;GFbMcE%L=Aen-LTj>xy#@;lo%_Coe_lfj~H^bMM)C&9@RweWdo zdGb3#e_J7k7kWay^$Do&bDFQUpE3jaN_i?ASh^m0D4!0elt{DeuybxGrl|H0SB+=~v7P8y7Da_Y zyT`Rrzh}U3n0mbdvb>)^JbOqsA6fK-MZ@V`EX$BXroAKj9N0t-6GBHK4{w$UHOnaf z|3B<~1zeR&*Y7420~HiS5epCjQNbVto)JYr1VvO@I;5q$OzdvOZUwuLXDk%EJ29{e zyYD<}?XBDM9dvu|ckVgoec8X?mcMJSS+izlO|O{|y-B7YFJs;YY>uOI?$!dCO>4VR zomnP;&7wQeV12aD{tHU@uQvt)J#{@>+l_e(GIuujBZ~RXK<9nc$l^`a0k_!bK}K}P zb&wWzMa=6s5$H?KOyQ^YT@7IsBV*}F3m)qJfT!8S?;_gantKs6rz5WE+_>*cUp_X3 zu*Ul>=`l^r|0@TK`7wu$fqu)#jM#|JrE^1Gayd$vSAo~viRjBYh%0dNV3PYF6WWB= zx!Gh;YphcbRh-G!z3Ct)Yoa;dbvvf<%421cu>#j?>TN$|^?n7m3B`A{soi9q5C>__TmXV3}jx&b{nDxJQn z9u9bvc`8lZiv2~XVSn1MnJLJ3D(^@e>E!~?`0dH$Hunbb{5U^iZI5e7H0ugyHXYO6 z()fba#!G0!`qh++J9D@@SBisj&m5mk`swKb-d&na%**5e zE8oZ_ryJr}F5!+Bx%vt7p;h)pZhT*~jm3?7aG$T>x>z+s6FM;x^*6~iA_I!CZEtns zD>tj8Ht18D>Pn-|p`Fz9-^;}-V4l<|&E!sJB?HgR8$bB3F4cYM26%URO$i}@k9vLOFIvpzcS&SN-lKkE)Fmy9)lm%hj*r%tYhal0mKN1yi9h5WfPJA-6; zp>EaNf8gd_&I5XOVG@bkfbD9zvnhR2@d@aor~1&0sIslTFKZ}&v;bIE9c@G zsOzk!{Je1NTlYU1Opn&aI{0x)IGuQ;6y#jbjG*UFVH>5))`$yokv?a91idf@_qWD8 zaHIK6o&vw`;s9!IitWkr!aB6;7tF)UtzKAEdxp4s%1%q^u+sFFVt$9WZ!M;D#CG+7 zoG0z;9Rz6^G58*@-&lbPWl{IG7p)Axmcu=4mscuu{@oA=yFl|AFO40-7eLv~WbPgW8M5}zn4F{ zj%#aeq|ayc^I0E(|I#NPI%+@0H6zHMHW2q0@)u7PtBA`^ z=k>>;DH|}}uLJChgA5-**!VlPlGzpckzQbzq3xYj3cEOE{K^^k1h?~3E4Lrx9&A)8Dg z?8%GiWSny!h^y;Fb<+9ZQphX5BAZ+`@c_C?ni6?njCsDT;T`TmBW(AMluhN-ugHO% z2TwDJ%Wf<$l@XnbLmxOnSgvVf65)wyEOdLs$(12btEV4#t-p#q@rI4b=a$IRsLNwc zYx-A^x$^WNQWtQ90TV6wYqq)_rr16*KJ3!{GsnKNKzR`eHCMJ;};tF`^ zz%+71uQA{_y-Xs_|5D7a$oNNeL;iTi?>)OQFO-FeP9|AbmJT>ZD}_w)nFsj5{&-^B zX(!-uDbYXR(>IYnlkt0t`HwSx$=XEqTV;jPctwY7D#W$ca7nQ=ZYd`My78t#L>Bx> z1N&>=GA~jYKA`UpGUM`Jaw(DSfD?DsAW7B%fZL9K#yQ@^x?mmQMFySm0(weE1-i#P z0r29?+5C-hxW{nNu#h`qhx*r#n{BoJX$bIaeRGxb8-#Qdqe;b4E#iUh?zWJB^cJyY z^SOMn{9vFz48F*XyNdj&TdP}5`-pg+BWG#iodrA#qVE;IK9B)e^?fV;Lj~?_v>)ui zD?Ug5(1)8XD~wU+WTHr4y^I6?20n{;n{p4pX1>+w9e0fPS;cwoJzM`0^567kLf1iJ z9Jp#yQOi0QZ-D8i;&I(Ffv03qL%!l6%Cw)hh<~M@2=wa#Q+bW?i1(FF;twxQ1-jn- z0B*7z$~SP>Y?V0*WqvZbVzq?%@Cfn7o?5}#G>QOxr{FNBU4VIbK;b&y=8g~0J8SFSUCvj8Vy9$)fUscteGN>h{1G4PCn0he!+P4z3vxfvvbfwTow%{@w3&v z0pFnV#HVH$VE-3qIF+TwfWHhhBh`&?JUo0`GI?q|krTphD@`P=Y;bP4Aa4kHFqQ{; z)VwHCdyE2L<+4m-yk#X|h0U>~P#fooo|lu!U_GSg9gQW^mUIOktF7$L_fvHMC*)<4 z$o=1p*?rgp3QF?gEo2MztDq@-?!~7-|ZvXn1NMwYViPZm?!fisqG12 zUA3yyKuyF>O4aFFcK3jwKi{<0uFLPx#~{lCfkY$VvX3L{eLC1w5-8J0EL90S`=$BCe0F0v`M#gv3p90DS^SYZBiR zm{-GlALQ0n(*e5McpH*cAL&864|AK3V|iu7mlV^Hk-$@OeIHN9qD{{DC`TLLM0;-8 zOo48RLTq|ffo}3gZ1h}#c9BP%G(nM`-H!Pgs#J}RK9o&_{Be4vTikeA8sIA)&U~vS zaey~kFX8VD!tq`s_V%{!ba$YCPOm}te!#igi%HGtiAH8X&%0|(m6UY>ce&V|&atQu zcy$XGI>!~~`)gYJ(NwejoDi>GLL~JXH6Cz6^(4A)G_H}#vo+FN7e+$x1?9RxG=y!g9i9b~=T>|=KjfO zY7*PXQqa?i+4y_!r;zr!-Lt4~ohVMA@2{Oo6Z|#;Zt^CEhP1(P;Qf$58phWp0#D%3 z0d&Q1ToY@mZ9}iL#B$NPVoclmIsi|DLz=X>ju+s;>58;bMi}5vuTSx(b|(N%RG+~c z?@tFjG0~iVnw14Ot?(M?E9|EVdssr8Rk$i2s%)Uj2C8hJ$_6U40imCe%;Ek7lYxOA z&?mNI{)cW^`v9+>6G@t_tWO30k7xRky`>yrzl{c@)*L^;j|*ONUz^|<_4?7N+<@~q zJ}j+Ozj)Sc9HX9Q=L#}?T!DYcv)Xh{jZT0MeKes?b8bUiQ=NmUcC-F~8|S3aKo>v2 z`lZY_p|Aw->(-HU?9GBK0H?o>q{V|3L1y(PUUY9ncfha4=u(f9@qqg^n#b?-=_&DrAQh{F zA*_E|D#q6~@js%&X#q$+OS}uDg1HD^B3cYP|32^zTP`aU?288X}-I2~bf_Y_B zc$a?}jq$ebkXO9cF9mq!DW-5AmSDUwr{##eGLET^z8^paZb$=}8@i;B{McG>m*^KZ z_dWP9gBNs|rkX<4HeLtZe0T`GYi&XW`stER)YTuyjrkiW|5iL-?tf)u*Oy;$e&p2X z2tROEPvBp+Pm2!J5CLAabPzRI7zHw`E8twMviem;|L<;l$Ak?4JIRY?a|#(StN&p0 zf{n_8HM0710_VrHG$IR@MW!^*hq!^Df23a;ZKaObIXI2g1JqOHLnr+(W31O5&Is!b zNLNg(XfJp5GU#?RI+SXwD*{fr%KWYOeSx{k8~H5SVHe6A!S0@EBj!nFJkoUKS?Zv} z&33|?!LRd2uN|&C6*s=gdD-=1VMLeGPoc?OAU?2P5q)GA7>^bo19v zCqwd(9>eGwX~^HyS=V%DFBYIy$xY@69-GrZ8x4RozKTmDB3ZBu`7B))T>NA3-{{TO>R#`;2zWBA+hKXF zs@b!H??or3H}j?G*qEgW=~rj(*m82D3(#LKSEai~9Rxj>?iJQrFrQydCMzp0WB#m^ z_vN#P;+kQ<$543eZFC}ARohF*pT721=94L>Gy#@pivNgwFlP|Viw3z zw-S^;ez-8cz_8zCA*!5SHP`;9t~rRy5bWzuFnz0W0PG>FUL>8#+c29GiKZXcrVrU0 zd;%`ho6J9Fe$)c~cvY!5Y10I^@ zL%1tOpxcH<=44`dB;bTPd%3rYsAvC%o2=d}MLn%%)#8t93GFO`!{@Vcc;xv#ur|1Y`Qty{J0Ie59~)20-k~2?iIFqis^$h^i_X`gtJY(=ObW{7 zTQDC8LB8X-f?c;7N3canFHcTSz~o7$hTY3hqx#70UYn6PSSm%A>J9=cXA$^dI7$< ztQqMxRTJ=;JO`3*jPnK0+*Gnj3*|ezWRV8SPeK0EWdY>OP8=H-&(&$YBoLJ zNZ30UiTbS%rc<8d9O~Q%1G-s+J{~9PAK?!v+JVld)mpK4*J=QsztEk&tDO#E-*#Yc zH0^u_`IBOmMYa9jKwOz&e$-Rn4)pnWp(ULY7za3Y$5MVycX556F}K)W4fVfdrNMP< z)fafC$2KC%6CQz_M=pV6&C@!7BS&SD^r=%p|HT8d$@FH5ppT!e7b!l9bF}m(x+L#; z{xTt5Lj9GqKFkT|F?)y8uAU9>+s)IVb2j4sb;zNK{FQrXC(Yfi?@Bs51bC(|TE|t` zV|wkkxRdg?I=X@!q0UOnm!@|NL!XwDQzD4_ZAXwZGQ9~|T#ECoSK+ao{6mb($@HwH zqZj6Lbkrf^MHd$=mBfXAF4Uc0TS(H!Mm=wK^y49-u;#Z z|E~U7SemDK4)P2<>rG_A z(s9Xxm*&eu{p#P=o63SExi82zynu6)HpP)Y*mz}h>99Y;f33aAV$Z)?FjU+Wk%fbv*^ci$oL?as*iHCvkb{qw@u(nQ;o&h>ho>D;cN{@SWg$i z-Wl^{$E`dZzu6ZA@vdP3K)0`W%AYIb0Gk{)prYk5 zo=z`|WsZMYt7w;PH=y^6OQ-2;@eYF8w_@q)T%03JF!rZKbuB@r`Nnp1v` zzr)tr1l_tuDC|mMzUcz4Udv$D1pYA02PxD4{xv5~pg%21qsu(E0UlK?hDO~I0skvo-Y`*wGCDG!FgY5{%U?k#}6P!oypmplnVSu9tQK1qXGbvTTl7*HF0k8Wn^30 zviLE`pYl0?9-W4Mn9rTlXrICRfNr%Qk_;=-gRpf+b|Y<8qnuA4pKy1Nv$Z+)DQhq2 zi|yBw)6dKbYVU`zahZ|q_wV#OkC1=ND+jLsBa~BH;R$!W9OYN@>qhju)q^$3Z05VN zObRQHodxrhSG}@nV<{|=FX$l)Rw_${{29sS-3gCIKwRA0AF(tK%9TyFB>um@zRS`k zRPp>X*8qQPTczxe{yCOVD-Wkwpv3NF5k5IY8V?iuK<4pvEnBlY{REEWg9o`{Z4JN= zf*i@Jpi#U)SGk=;EbS0CzL!K6wnd(|K91x_0frrN7uVPXeo0;UHLhH53=6WP(k`LO z7Oq83pUq+&=*|8roh6v9brJzL30Ssc#5?p=GhaQ8T{Jil=*8)E=$7400pB<1O&715^+FYuhbbdR4> zHytobG9tZ7DDD#2yidg{do2Gd-^CkX{WzR<;26q16;9L7iWWg9p_*b^^r@&d& zzWwj5MO<)O0sT>HW{;{bmIKyh*xjuq*vY#|cI3sA_h46%QS59{AdUwPE5wk&Nx0@2 znwd&&7Ci#{8SI$#L)he3T_CLblXQ}-h<@M)PsfsGTOI;EVt61SFKa?vcb2;m%gs%w zP{yaWI}*jMh|{(?604n)K{rpPn|UWqUf`)Gmq}WVo(H(1IG*fKzXy2lkRUR&wGzn5 zj_~*)Y(+;5Tc3pu9)n?d7S=)o!?t8$>$JhJW5PX{Ub5A5K_B6x5HSMuOl0G=L9g0C z8dLJvyHK5%0WR(nM~_rI1DwX*me-tJ3(`Ks(v4p5!}{JMq4y6s&hk0%KT!>!IXmY8 zR@fR(%bT?T{QkBuR+XjxRMj1!&t*1WB$O4id0PL)a=^^yDYJR78D{ge@aB77;As`> zOM7{3102f6z#r3s0c&Tb(lzHE6$?By9kYH2>vp;e@GN?oP6JhN4|>bVSgLpKA<)}o z1k#RjwIHsy^W7-3ZP0<)Hof42*o)!gM%d1`k;|k5^RV3O^YL_``aMpF_v(-!8qrz_ z>}NuR2W52!FsnO1U{+s%pVb%2>I-02Unr|DfLVQ^tiC{4R$rK2ve?ph9=X1$p#LaV zH#Nt!<^|n8EXp7iE0+M?H93wXl;b`~Vq^fR;fZON3w9%s$vF3s5A6K|mNR|^VGp`9 z{`PYL4}Kj__)@ID_8&8tzOvNKDw`K->_rz=J7*U&c7KV-0T z1h{sw%h;PfwCNB0Yo@5sUQcijZh5P0UYftU9PYWaj+@4}33UMe{k$e!QHnl$S14@@2yAS788Gi1Mi zx8ch05jKw%!j8Xmz(PTc&$ak!vH4vY)cs2_Sww3HwiOd6`4W3p_XPe5Ru|8H!Ts6! zIn%g}Qv4ZW|H;TNv$?Os?SX%9>lWm3G|t}_u=^V}tfb(Z_ms5*nr&`_{kMn;rVrh5 zPi>D*BkJIY`#8q=W7+Rm7e1|tWcxqg@zG@D*&8;7AEk)( zUNGOwCGmXN>2826g7m1B(`qQMXm&Tnw3pxdUs}Uv4bV%v#Zp>|{Ejht)RE~b$kBg1 zvnZ{o2jJUZb*PRlu4%Z$M$-C^YC~HgtY<`6BHcAUlIE8pfA8lyR3jx9(%ZBknQ){U z$T>U1liWx}{fA9aBOlaKfF86ZgS#${_wii?3+b>^>LAYy{Y=hdIEFnjOpO?HLYc<- zos`licIdA>@%0+BD%$6jdpS3Hp^jXq8-(-TlH2&5 z)=FI0dTFjInk8-zYb`uqq_JlO)Y+8lu{2wR`_WO>?zG`-8_;|9TW$8ncsyV?%Y0s% zKY9bwKb)V(j|xH`i3E9Vx}rDADOPo->22|DI$PF{trP8sHsma8&p(UxQ8?SE>s^;% zkY6$BHs{j53*fO=I+F_@&Vz0$Zi9*1TU2{Le93CaGsm8+yZcsR(qn>0{t-@ z3WABp6MGJFzj`{c_bP(^=qb}*8gu#RbGR!ajl^rA&&>EnQ6ylBKFGXZO2~!!=won@ z7yKZ8UDg5OGOBA`Zs99lZ|Tn0x7_F}2Wh-ikxBYmUj_W7Nhq0mxf!Il`IufL?QJi> z6Z$kGEf=DX_nZ?)xuMqSK<{jB!%54@OvS!t+n_OA%3y!s(b!tSO&&U#8|5LT_+i(fW35b!(C zhy26S1aRF^`ZTUT_Mx>of2!t*V|68V59J|oS&vH6E7}&~4e@^Xno11{dB9%Nqo~J0 z1(0Kv=0)dy?GAYNwbt}tNAz{se_~4I3hG-(IXu_pFHn98h-&Z{%LwRiF#~euJ90 zULCy0i(gX~1U#+X?(#*Y)_}*@x1kHa;9SyGD}X+~-j@@?rmjh&4Gr*o!N)quq*wA2 zpg%hrK+`BTh97pYY+nn%M!+`#(=Sj{nI32L7t2HNCr{c;cnM=!*ra!eq zAGQ~}#&WlH{2*+s$6Iaz#k#OvsXZBSv>wnu9O+No3QvGOW?zIj|JZ&BDG)xD(SNVK z5+qfv7ya+87yZ-n(_dV#SM8fn)Wa^73i`!rhH>6wqX1Xjo7CMYUCoU*U5gCd}=du;L$y6M29L*1epfM6RAVv@z9P5_1kXWWT4j?oJi+CR0IAG zU7e{)u^Zq?Cu`C^5jb~v8_HPZ;6eNBHw4ItBFL1OT#olx1w+isKS+Ue( z;$6Vg&IHk^S@o&F^W}Lz`qH=`;9Cz4F!YAV#Wbfo8 zZthO(H~aPM%DX8b&+wy4bm;81!2j-@6>T>i=O$hOo>bXqA;jy_Jf3P;HU_+-4cbms zoA#gErU^FtZ!X`HBl0*Q4O~$Yl?DH?o(o~|^XKE+{F4qKf6J3J(#3i_;5?P2AFwPk zRs5%;oT~{$7F_w5KP|J`t2(B0ZJnZymw0i19unOxAp{^in&G}1a3c^vGLNsEbj z!1HQH5(&GN0a&ws3YlNW7Vv0;bn?s=`PKRg>tx^KsvQ5j?MKMJKeK;XY)P6&78{V} zsj@2}=Y>yYHumS`B82#}^7=Q?1zm-7=je5WdY8rg!giV9-c9YpvDD|12>R$lT?WzO zm`;F~&oH672YmoPwEV;eoyPHlv40NVgS~AbNOX8$S$>sb@Rj zZ`db;9237!6V2YLseMBp;;LWGn^doD26)E{V=^)l=h5p_A8`|!;{5tfj3;;FE$Y9# zMy}<|>(Rh(*m^s^@sSnaPAl8e_nT@1?lHoZuG@`g4SXZQsmmE`(}u23qHWu@0DThJ z9_7tw8&34Zwxn|H+op7wHq#Z}^ddLxhzVo3s)l@J6 z99XS0?Q+i_@Y}1;`PySs0Z+_hzIM-X+^g4Q)2<$gcz#F2W+!)lt_ARzwQo=Q&a46W z@i2EX>fAwy*I;7=(X$v1c!hH^SrF6&@Mz6U!sq5o#>Vt$U|ZBPFoOhVECy_`KaMz- zegJH4!Mdl(XH7dR{9swhEbqeso1StN31e zILF^Cr$_TYC66~{Cu4frLcHnETakBXvH%zG`>c+B#{7ITbQ|xV zXAJZeL(J%bleq7*{JbBHxH=7FmOoFRJI*u*e7ih@`7|nhyJI0O2=}i$mSxacAJ+ko z+5RDPbNlKbvyGxBEx&6CxMis!-F+2x$hx+>m|VnjJu}9wqm_GP6GTTKanhHr~>$Fd?pF8sP*kUPD=llypSV%E@Y592i5`Jb!-R;bir|Wo3Wmx zN0QTGX8Zm}+h%t3g*9HC#^D^k6zPJZHPbr2PpT;$`V}}OPb2EED zyxIn>sX=Y5vpcS?FCJME3G|eLz1+-?IOn~3*n+q}!+q5t-2l?IXbQ-0+#``3-QEoF zs}~ud!@s>fuhRdYI6wOH@x0Inpv?>aN@EFCnpQck>}*2O)$eB$?E4I6Z{-P}9GT7| zNS|2{>MDkX@V~^;=MMe}XA@@4!u98e?Y*fiSURoz>Ajrre-$3v75puSRz{Z&`!oFa z*VD@FNlI@i`;<^+3wN`U^D+(tzT4!27I#~t)c-!4l;w;_rg}PYTxtPl6(qVsw z|I=-(R$4)0c-o|uk)UrURGJ$dB0a`McU zvFk2EKUKXVlty1bew*a#0uTF&M44)r+m}Daed<%1qxeBXT!8L(P?a7kya{9Afi*(t z&V<(B8^03H++*0flH5tlCFD;Sy6rmsKAYC_7 zy3m>mIv+@CLmsoYiv_$e?<^;cNpB2$E;W(J@4~PzTf31Oi!f{k3)|s9BIwh%$3$-O z$bNvAG-^O1Z!`kTo$5p88_t5XBt|C?-;@hrCj%a2e+%1(g|!=lVLenEkZTVx?7~BR z$dY~-cEjKw!%FOAt#gl6*UC~s|MZbQoZ+-Ez+1+g;$Dx$b*EF=Cd4Xw1LVVdtsx}; zy_{rUjOmE>7WmTMNSdx*S_J&s`q89jVGEGStJ@PT@te@$wr{zX^Kku#tKN^L@AvFB z$IAus#CA*?kp)ZaL?|a&@X+WE^zIDTlKm_}s5zbjw5Pm~1)wS@3sW&py!66i~C!W{DtZDPV6W1lfNrjv>(UO5+5m3z%9?J{eFJSHm+D9L42AcrM4}#XvGisAY`_*z zlc`Iy4uI!&&7j-GajBP(qLS;afG%H}K}|L00-o?Lo}S!|{^tsI!L(JD2E?_nr6a9* z8~Zqw)+RKyAGWLAedOtYy|}mX?rILdLF|K<(Dp>pZLtqte!jx4ilkSPwPiY}vWkQEDY4`o7dC!#S1_bdvmeaW>YnV{!> zb{AZR*kAP2w0f5Fmd8>d-|ow;;;06WnOAqOPqM$@II7x5S8}FdDlhO%@0&sn>j>u% zgip>lIp>)iX}ZJ6VZgs{a5B*r;ktA|Z~!SS=niqswA3ZZ&Ef%D1TN$(>`VZM@9sn$ z3x@!RY*Z*8}`XeE=y4KKad0sgIU0 z?qO?px=tkJ1lIjFABJ#uvd~9&S3m{NjXMQpadv7L%^d3t{H3XCLEF)~vl^VnO+LYTyHs>Sg)wE_FDwV?v-f1};5lJnP%dHxgfR!D&jC-2f+Mg+o*o1TK+1pq0HoaVd=V?7<`f>@jEt@qx=)3XQ7Aa?> z()^C=zwJj~c^Uxvge^{`9fzI;9C&{)RbFQSa%j``lrD+}yw-OIe_2-@nH6L zsi0fyIs2^MIOF`+-De87AubT;hu=TszB=RFYWw}hr16{F{S-~pA7Nf4wW>>3vbV_vj>oe~ zIjbZMz_WB6$*|CUASaaF36t745b(o!spM2K-tD=R-R&9Zr3iTNKv(&JMA#_gN2#~30kV>xyzJxP|<2&G@X z*kum@yY-JsBeGzj9%4x0-#^EpV~2qqu1(1%(pcs06F8%K2kOnAhpkK|(+%vL=}Be5 z(rJ_h_r8qt&1OkyL>8<(r#9qU%XyhZ8mG3w{H($5ftSXz=pfCLml13wkK?Q<`V}HfJa=(}ihN8v83^ zdzH`HD{1_tE0*uqA!$?=Eac69V*6HgKIK2}e2QSJ`1#)M3U#G{+AztUY1R3Zs&^G( z58*$tO%rVY-<&R4)`z8er29cx@WJR47D67aXX}*IQy$g;pTIgLwil1RSv=s0 zYg5SbT`ypaajlCmpToG?C55#cWugl__vU1fsGT?uYQpB4hxji*w^8vSpA&UK{?^Ry zgrDdLxa?sQaw`z$t;76Ja}K(xKtJph!41#FIpf#oS6Q4m_UrR@gyF)nbSk8se__In zj)?+uipaj)2a64oaitwgxz8hLB`HE0UUcbo!BkT zldNSCNnB68!Z%9O2j^M<|FbpeWcm&C+n={KmPCFP_Ws%Xyu&<5?w9s}3omsgN4$Ci zzLL|FD5r|&Yc2P4QEfATUXp6W^5*x(wE0JI%z2)TIc33;G7|KY1$S>b5A3Qt8!JxH zT?M!$!;-K~7dI#j-5pN^X{S=>@lG)=fFG2q(rc}n01ni3qVLK#u(YwYJLMtt#ne`S zMMs2mqs_=)8o6bw39ctxUYknaPQ45~r?Nw-y&0}itA$xnt!(tYKkHw?kIYB|`DK3n zc_xR+5{Y_s+gZ3$2kn6lx8*xJ39L>(GiC)zb#7;MtRU(^3{*BudGN zpdXz(1AhKBo!$t#3*+Qq*keKYr%TN`Nz+dpwgUd#N$K=m3GP!gb&I9y8$JU)WRMSy zEYgCwnl9)`m4n>@cPXtwUGC%l!ntT+PviH>UC{U6+#de7>3>K3j>fCWEi9wiy~9HK zSFwADcQsK4e5Jc9sarP}Z01E#GMUzE5ZK;AHqY&u|tl?2d4!j`jy^ccdP%?u_efmerlf!-z?| zz+W;ak#zL_2;(!Ivg{vlMwBD)?7Nso9O@hcykbf?F?rAgWPY9GNZeOrU#5|)K!%P( z9bQETaUPR!oi11HMK+uJIm^ z+rf7ni|zlsg{rh&4N2~^}=-Ow0tpOlj1m{Jn=1H^+tZ= zfG@6ZPhIao-is_jj^>_rWM*)Gz&8R^h<8#9V7XdbID_M;Poa&_w_u<0Sx?toTD~+r zrXKQZzV66vT8%cgQf&z*`iT9@O7@tMrcxh}|FuG$%sYV86@K zZdbL{Rrh!O)i!`OFVtI!o&Ox;ud?yxkZsA>{`Zp~ZY7Q5YPHpu#4}nn4C-%AS~7WR zjlP$6F9(pULIU-uX`w!8JO%5lD0wrNIj(biN!S%9(Pv=R$YO4E53F}j7pjx{W;G$~ z@@DQtt6CDsPsl;v1W8y)N`96Woz1u>(zjaA;(Q(4-@jnGkiUJ_nF`_4>Z{RhCp7>o z-s(-Ac5mke`jXwzR649QUE>Dwt6%6%2cJPXlhxFylRnB1Z@Q4zb!Y%{F;CVWcWtI$ zEXZtL`XiR+k*z)X-sX7um3-Telg86XBE-9r-8CYOh4}IFUB<8C{CAHt|Jr)t#>PfM zekO^g7QGPnzt(;`i%L4+_^SCSe>$$BBk*{tn$iNdAi#&y?(vV#;QVF6QAb{ye=WNY zPLR39t2bXi7x_C}DCYweI|2RvR})%xw*cm1sx1B`DpvuIWbwBW_xl^XnpmEmg!QEM zrv%Qf%ooDmb$Z8{hT`}tBBcYFSf>%tH;45l!+LLp`sHaJL#zyS0F(6@q>1>=j*;g& zT8=gC2J~9->7*>N0C3}iA;cx`9bnZ{zU2HiE08&~tSxy}i1l6P;wG-IcnsX@SvyOc zk`yYWF@A9@x8RH);Ja5|aSIMw0`C04kX%{$m=}01%LfwGpn-r*{nNQ9Vu(Rk^fA*uXHB{t#QFG(ml~x0Q=BK-hMnau4od?a z?woVs!bd%Vu=V-`(m6?nKzB2;qBoBF0AASY6Q8pJ$7A}_0~jyXE2Bd?J9cZK{(D*r z3gpv|SZ*Z$fA`AXq z`Iq+}=Y;e%>ljXD!KIsYpuNib*n`S~nLY&bPx$xO_|4*$z~5qk9gzjgB2$`YegyhY zjtPsTvS8`3vf+P6y_UuQL7GRlw0|#OpLMt{otctGWWmZq@GcRb`kBPs9kE@5OtPd7 z`a*=nr~QCs(dWXU31HioFC@~}r$bX=U^QB~yV%t7#%x?$HA9 zg0c)!8C^FW?-;SUE%@&JTK^w;{vCBh$g}TbnBTJpAuN7m4flI_7{cx+669waFXyH4 znB4^E7v}2IQL6?5)={WK*K9$*>!cYkcxj$EOK;#Q$(5&bBk<1B$F&*(O|1X_Gya~3 z()sz<Vr6F`;WN# zu5rLKS38MFr}H|L(ecVb^%cnL!wvh;2|BlYxOA zkU#AV(uiBuKEUheM3QDJ>jU4%GyTZkQVy`+Mgvl7jvwI11+TfUO%efLKRT5ga31%e zN^8|Go;4fCSEs}0^O-)bz%%4oZ91n$C%}h3noy@XcxHL3b1>CzCipptM2&OOXrPN9 zVEximy0;M5h+emjqK0py>oGm~HN81+f% zc+m2U_>HihpJsEKwr;@Fa7-=Ya0T_*YG^`E_}qecXXOWz{qJyWw)uJ**(BZv@lUX| zI4(*jf}WZKd+~h=f&dq3m-9RFIKb!M8&G2QiW7L6iu`H*#!$d+-l??Py=rR(x?pSa zkH6!vFTTKY{b(v3wto-c^w*KJc(5YKtlq?n?v3aU_|+I)>TweNK>9VB$M5v%DLJD} zDpuoJHvhC#l5_L~$f0k;NIX%8u=U3FA>qcsfVZgM;VjZ|f9G89p;mdHl7Vj6Ig7ua z=nZ&&OL8L7Lq81&+qJtR zop}WF%Bb)z|1uimZQUWScq5qagh5ccT%0c7BYG?2fcOA470 zTMN#}2xrF*KEyU>nraGF+jyN9v}ry(gx<9_0sT&wbfT{Qf=>+dY1u&ex8iw3|0^TA zzWf>vbf-o~_<^%<{J(6U79FS|0{Wt*gQ&s6D3DoQ0rxbj`t<+C^J2el|1aKE1pC}^ zE|bcFS^X!1P2%U**tA3e?6B31Od<=eyf4cE+ZM)9MZNYv7TlL>64z>I%p| z=N3w3!N05jG0Qu=P{!@`f{85n#d91>M2s*Xvf#?fr84^A`5mC{%iDCN()ePiDbVlE z?ntGvR>?rfpW5DOL>63S&q59epFeNgWwBvt9$9QynnxBJmgcEU&&ues*swH@EH*67 zQ<>dXMwhl>X)JBS(pVN7mgW&k@*mbdL;EJ^RaqJRNJq{eX@72;$n$&czeM`~2l>!G zVSGQ+@n^qDw3X)hGn(}8f5bn_yKl0j%IF(SCjEzseeFs_*NXDQxP!x$qW#+j6riLW zYI467$aiqGr7>*JK%nk+V0Y}_?Q^) zRc~9IRfzM-nz!e1(ir6l|H_u`4R>+g-LmO@%a-McZyA*=w6v zXCkNY4*JUKZv>w{%=f8^Pq#hj`JG3a-mvg3@LSdKBVNgPW@P8RhtOY1Wa3}p-=FLM z&#L2pMVs^U^#9NNlH{Ch;j+a3nL2j$EXzKkjcM*TwVdBWUt+gp;_*>XHY3g^k#@&a zz$VXX_9r8E3Fi$&qL*8qa8W*S5*sFEV+1>3_Y4nz&*fVv0=DVwMRuJ?nq1x9eQBssaB>&Y7;+i}`tP=SiNe-2nY{_Kh9& zTW(n|2`f!MZ5$3fh6j%GuQVC~miOyR-_OJ~sG45|KNiX7kL`11blLJz68igJ*}_$b z@2fPqy~Dy%jOVU+ZV@@G$G5WpBacqw1-Z^I6G%Np9Z19a2{xpBYb4-tulI5hh37kA z+&N@L?;$`BpS+%%aoiEG*~}(n-3B$l%LAQBNbx$58Fyj`(c&}#FBN5yc71LD_Vfv% zCtUP^e?eI{+GC9u;K_*!RB=1naqo;c#*6vr@z8mPbXaNnt@Fq~E_(>y|1!!srmH|r zd{O?9^WEr2aoR5)-D=TiEUpzgxYUJ2zW;V{_tG{yv|6%VB*`!X-q2R0B zi>;wnMwjH9xGW*ApW#pUmxJH3F4O&^6#lYf0mM6&`7KLhlqLKttNs5KeM*(g{~KRl zq168F@y5kHfBt@)pc{Vv+3&{%1%7`&?wHj3aiQY(CkJSi;^zED^tl zn9trrG!(ywc%Hq77%F}bvANWHh?nkL78i-%L)^#SLu?>^53vn<57A!y9-=9G4>3vn z9%5Ja9%6SH-a{PL@YuiZJ;c`Uo~{<#Es@G|Y5cdn0r!4Ho$Zo3)ld9J-d^@bUid-m zyO**z^6K}m2DVZ>#*=u4TL8`rY)_gk&H^mwe#T0_YYbppyRE!WnGxWND&{m_`8o8V z3!4Yfb+gfb^#Xe%Z+xLD&^_22c_-D6|6|`V%$u+BZ6C8VtOY0J)#sb+eZ#No01w|c zgtj%VP6YZAc~2U8-x6?Oi6ND{mIc_dba!#)g&}|sPg=*lT;Bz-vwLUqihl!ghOl=G zOZ%YzMx6zTgcrYK_=UY=D9HZ1+vF-8{$0L6vXqy^f3?>?(0}!=3;M5COuEgvwC_TN z^o+gInOyjQ{;Mi(gNfQ(^k2OZ_M`vmOKDan zP>{KMLY4ojkhfL-t2p-`xu@~2jUSxge77(zQk!QB?Q^bnI`z}p2KZ^c7|5fWTc*g(T!2mM;Wpjw@_*#1sS!@q@()H%VwH((p zE@_yF=K7AJAlzqM@#36jD`n4+G6^RX;9D!%SxS}K~3ug8P zc8HerYn*@50qXCTCuyXMHLf@2sU-b?Ws#}kkN&P(t|ky!uq^dr{=4DOPg$ELleob- zfD=w7lM6b|fG@2`Bdv3h$H6X{w3wI&^jABQNW?AlH`A=2Lgv@81^Q@%bn?s=`PKRg zK6J9w&HvQ;C`;PE^StbX=O|M$*&9YOU|DQNn#aM@jT3Cv)t22oB?FeN?7r(Si?53` zkF;*GVC}-ypnq$xSRxDlUH#AZ!~E~Z@?RD#i_X$KT7%p{{{S=QHzETT%1Y8k{Zp`@ zhwS$Xuke^55am$7~QJ^5xqWpH;&JljLgDyj=>$irZd2<2$y1g)N|i~hH{3)8tk zpCHhqkKaA+W-Wcdf!(^18XfQ+GyPM-mfy!k%YIanX?$>)SjAGVkm z=t}IKyhZw(|HqxB)0H;2lcq;MS_AxFwPK0x65Kl&v9&L`8tVZvdp1=f3&r~v2Zs&$ zrjHPZM7N(~{8f?%VqQq!pX1*vuai++LoWUPEXAL;mybXQZ2Jeijb3K~9XJjS0qeh4ec;p7oS}#pEH^TFb zE9=D2=_)AaxuzcNuma`V@WOcx3@gq%kn?l=&ubt4Y3BEcnxhs zPu>Z2;W=x&T0Askb(P)OcsQMmqBu9ytB58^%Rd7>+RumF_QyHer53%&vK$v8@Lwxb zCC3Wz{hff@6FJ?c*cKVrisV`;`vFhmO>epPrsjYHw;PcWw{XvTUpHscxb_Z^ueULp zR17x){M;aebQre^aL|NU8ZZdgBt!0b&@pe@gPblmyV7RWTmgSfR;JFcaZU2h!?nEg zxeTDcn$(itBlhh{Z+W;#TBbC8%^uYGPKh6{`c9bpv3JLgoZx*8(8o1wPg6>5S_1w4 z0y}!T$1~9Fc>e$@X$OQbGGXza>E>&jErP^0^Lp-G3*)UeydWXOBAx7dit9WbHDbu? zgGww8k;u5Z2Qe6qKBaozUC97TJdc0a<0Thy7VT|pvM(nsC#-K8gmu~A%6Ux}+ANW% zZ6VJoxZi01Wu?2`=l3{zNKa6K<`Y`sg-3R;JRam z&?XN)0={zHhaT+F0_5mL+0)ehT>_CT`3wb0Gby)F?_Z*IT4*VP>_$L5;(Gt0x z()idX)VXYFFJ6(F7UTaZGqoNPK(+ZY6E^_-IHFE$MyV~MV{0?d==>9IxUt~ z*Vh7Evm}EyyM$}e8^$D(He$S<;T*ATR6l#o;#2K3BIr3_oEK;IA`-CYr9GT~gYJMI zywD|YiWC7aEB7QeUifxN%@^V1n)xSA2&+))Lk85-0UrAiHe{lUC*V&7)ktw5jsYUi zBy&DiSwJ7L=Na>DuWFzFt$Vvdng3Z|@ZU_Ao{PzXWok2})s8 zIJ_q?(l3o3Y=n4Vu+S#qc<;=?@Rfs3Ux50q-dbp%klw+qqWyxamw~<_I+QL<9Sn8c zDEK_@m~H}i!q`qUw;A@8bGA(74`1pD^tuUJ)Tf?2gtdB-N%PabfZt0K#Vq<}2kNlI zJBvC(+@jxDnpJ^oqTiC6Wb8*<@w; zEKTR)AH!IyH|z6X@3{zgGW7pwKMia5?BILRiRmp8Idp8y@&M@{fij~p#`dH{K{ZdQm(t&Si2y{gapPw2D$u6N$6;>G>< zs(h%*hbkMWvVkfasIq}78>q5@DjTS>fhrrQvVkfasIq~7qYbQ@kLz{2?>lp{U|~H8 zKeDbT$;u~@EBT9SY2vtugeqBM`%agY@4EzXSXdkT71q9l`;sG!T5_^rE!7@dCA#T) zzJc{vZJjJ)_3S;Y(bbFcC5yFezVS3`bRBr|GP773F|Wdn$C_Q9jr+o3cMG_wT|Yxu z{cN_zE9UX&IM(b*`y@!i-pFyBg#N4a;O`>Q@p2Br?w@2p9d{!>TVz15iTC){cBx); ze@Y7QbhwwvBR+|a zZ2LfRcAg$NiS)iyvFqg+fM4%l=N0YpUFO6Be~U5 z{54gOUZF9P>oX7eJq??Z;u4f&@mla1`E|Yckq52lN7~P1e783i2HNmH+ToA%Z}Mf} z739ex^E=P<7XfU4SNP-*$8fw;_r6jTnK2gqrtG>mC3BVV&fCxK!WkV5yVfUU&Day) z!%FB5HX&;QRFL1l@ks9E9F*hSzA3p{gz~$+Mc*7ry!aP&s0=5cM_;MprZ0FmG48DS zf^QKvW{p@5ov~i`+qfcQ^>MI`r>4UFwPIUx(qO+M_J1O`b^Hf+_M1pF;j$9-7UOFS zOL!!5@vrc2W#ua2_@1wfmz9O&^GE#0|5wI`^gJC8kQFf#bOSspDWLtI(L1IFv_GI+ z4_v7XY{$4eXVBJ&7hmR zAK}@T%edH|PWSl8voBXj%;-s~?8}9DN72WZ+7tGrPlpZXrEwIau`g*odN^mHqDa}7OlSU+u2Yus z?8~iY{urP49w=sCtJ0~Nbbx6j$G-g7FR_A5kjrFpSJuDe*_S)zVnqu>EqM0j9@-|; zxZxTc`|^PrY1AS34adIx{7DwH$hEETC2x(E@hhDbIQHdx>`ABhMs4ERmmA;5htgGS z0=6opSg~$4Z6Ec4XJ2m6O*3j{bc|`Sg@bflIqnh9TWvdss++n_pxed)sT7PQxyj>4Dt zRy61NPp2)}ch|79!W;DMIQHegj7XttRu1FYm%Et~O*hw<7rsQbR!6F|)j;@?|HIyU zKvl79>%w9J5pxDbf)PPbFafKk2~k8*!7PFziiiPJ1PRNWG3V@pWx}*gm{v`5&N=6t za}KX&b@#r@_r`wzx$m9*?!N!PG5YN9^r)_`8LR56*^4zntNHBNUMMbD-Y`u!d$l`? z3lggjVOv(Yqqv}N!y(k)pMAQYd0`TluHl$uwBNUqi;MXucSrrS5_CZ^uflk-fhS!s zV_ZS0W70M0ne?sUmf=2JTx^l}#%(dUp}3%3ubC|8Aukjc@_;q4tw&nvaBrOq6?xYRe@W( z^P#w4c8N;ZFLy1vpkc=aJKskaM{&W?DMj(l8F#v%;Oc>F!XPgc7j&4sOm`@81{W7= ze7rXfoLP-7=-`&lU+h~)7n@!)9G!g&&;?~39U!lJbrcsA3Y*AwOtnLCLEOWfaPR&V zlelzGN~EBD>OC$lW~}HB_jZ**aRIAji3y20>4LrkYhcu-nsmXvP-p(h)g8qJm#v30 z+nWVYT(HNYJXm|J=i*`~^M-@lCx0$3)*^pAcs=pw;$qvyZ?Bp6xoTKd6c_k!*~DAk z^+IvM&Cd2Fr&7)+E?80ZCUbgtlZ%Tr-qDQaJrozb6FM`;oh)*IxX?OREtp`cz{SPt zH%o+d-}ZBHv4ErPVBqzFC@$DhryOj{s)6DX-CtyKr$axBCOl-vwz2 zt|%@jo3wz14fa5B!Mol)xL+3=CNBPGl~la zeZS1A^bO$RVz-YDh8x=!aB;C)cD7xF8|65W->6U7FXc?iZIt6g zegm^u1Ilfb<3xS~%59Y6M1BLxZIt6gev`S4a-7I-K)H=_oXBrLxs7t1$ZtTojdGmG zZ$P5kPYS%?)B+kaGgf4Psv4G$+v9Am#-f%?UI&hZ=56uZQ zH;8!wXilKHLCg!B<^-A>#JpglIf3Q|F)skk2{bo|d4bWKKy!nb7l7sjnj6HtAm;>{ z8^pZ8X-=TILCgzySIi0GGKqNs%85BaTzq*&f6T{C?7M@bjCqSCx7aX`!f1bcaL2SDG1Z0Rht>YMZ~bT0L+$wm4my$hX7eUsjW&ZWLd??UHN-=ue;bE$9AyU;n1zDe&w=ThIK zccF8sZ_>Naxzso5UFcluoAfSpF7-`%7dn^vCcO)t1L>0VMKR`AFdkOhmDk;SJdv^P z{h;v6NxH59S<ELb zr#|#gNM?c7W#N8&4X9Ie5qtK&l9(T(;qKRUx>>!Bin{s;*jM<0?q%)!>``n8MAWU$ zM&`4EqXqrp;{FI0JGG?wyO4Z@d`0*PCm$hS5q`qW<@#7d4=3}r^l4MUpey-A506`A z)jK-p@-EZ<6xegRpl{Pfd3m)n2{8BS1K-0H`}03sV&O?hUtNc4t9YRwJz;dI!@BO@ zFLLr1@*CkZJIP76>17%LwT_GFO z+?cJ0Y=8KF>jT7dm~kD%O=w&P@f{l1!Ogf1of+4`%(xC_#&s|=uH(->iRUomI=C6v zVKU=7m>JiBv!5wN z#&ytMK;t@SFQ9Q9azCJQ9mIENTnFt1G_Hg80vgvrdjXB>puK>`b@t4qC@*T*seSUDIk@2bggkw5HX#4qDS{T!&oOs$7R= zJ6g}mOXWH=TNBqoYg&!#pf#<=b;xzC%5@Omp>Z8@UE4t6I%rL+aUF79t8yK*rq#F( zTGMJ=hg{dHT!&oOs$7R$*Q#6x@f{l1L2Fu#>(FUjhq|U^VoghXJ9(*Ghuq_-T!-A_ zsayx`?=-H1_IDcBLHj$6>!AIe#&yvCPUAZM>{H#}X8rMO5hsJf#{!ZgMi0{z24%**oTnFv% zB-f$t?=-H1_zsQhAihK6IyC>3>t-!45zk@9br6@UaUI0vYFr0#xf<6&T&~7-{Fx_- z=P=_sv{)mqgScFc>mV*y<2s1T)wmAgJ2b9?xLnC~aKUrXrE(p_0%Hz9cmmG{%Q4&wbZ zu7h|#jq4!ZPvbg>_tUrz;{7zPZ9=cW7J(@qQZDL3{@a-jBEr;{7zPgZK`O>mc4w<2s1<)3^>_Gp>X9 z4vp&|zC+_W{>Y&|-wR z4&uNyu7fymjq4x|T;n>3@6fmo;=obN3&eF02d;4)#DQyE2XWvU*FhY(#&r+}u5lg2 zfoog`ao`%)L41eCbr1(Gxek>B*SHR@aUJTuoA?`4_uZVh4&ph)z8i__Q27MuE3{7) z`&ATsRiyo^*vF#S!)ly~)JxS3PuR1{`Eg;07mELa`2U44iD6QtBLpxb>C_tenZ{2?xM8< zaT|iy*g^b;8P=J#(e~FS+Fz^tZWHah)xByK@f+%1btmx~#BGSZs)_gwb+2k7enZ`> z?jn9e-K*{(enaJyNI#O>5V}Uk#BZpa z5+{B`<&=>44V6>k#BZpa5+{B`<&-$_8!D&7iQiB;B~JW?$|-T;H&iZ&I7LR>hTu4m z_zmJV1jm8IZuul7iukstmjZ`If&n2 zYApxx8z!}ugZK@u)^ZTP!PQz0;y1Wj%kgKQD!&10EeG)%Os(Z0enY3$auC14)mjcY zpP2C*#7l6M-=MQjs^!qmI;oaJJL{xc4(+UyYB{vCPT3!=1w=n|&Z(Vs%Dhi=sangS zopn+zhj!LUYk%#mQ*s;X`k!h!w6jjC<!ex^?W~h(IkdA*s^!qmI;oaJ zJL{yizjoG1wH(@6C$0VES*IDlLF<27`)g;NRLep9hOb)7L0kk=YdMJD;A$-g@f)bt zauC0PYApxx8>rTD5Wj(HEeG)%sMd1)*{8~HnABPh;y1Wj%R&4Gs$IkfX@$!(~6I>~LQ zdpgN&sCzoeZK!)X$!(~6I;!Q+&aWl6p`Kq;Er)h~Ex8SKPe-*J+W9rra%kt*V0L~j zxeawsC%FxEPY1MC)^d?KR{0I$Z>g4p_zmK3sg{HI4dQR9mV@{W;%}*zgZK^NZ)Jbf z7v)Kn-yr^0o`b5frturZ-%>3H@f*b7%G^ddPOasT^&Dy~2k{%k-%>4yPUUZ@mV@{W z;%}*zgZK^NZ>g4p_zmK3sg{HI4dQR9mV@{W;%{Ycqa3H!auB~k{H@Gwl;hM|4y{&A z<~GW4YApxx8&uaMeU^Mzt>uvMpw@B_zd>9d)p8KOL0lizauB~kTp!hP5WhiOAJuXY zzd>9dQfz5`s{96VeN@Xq{04D-RLep92626o+fcbaF=zi-cOhd!^I?_WAg+&UIf&mN zu8(Rth~FTtPjVY7*C)9RmFtuHKrOyheuKC^^LJ_d2AJ_1#PvyTL*@D;x1n-%B*C)9RmFuHg4&pb6>!Vr@;x~xvqgoE) zH;C(#+=j~aNp3^s`hLsdkB7 z#Ba#ChPVylzSUX|xelN;fXZ(W?@hHF#BUJqE$0N98`N43S%(st>qwogLrQ_ zC(zuW)^ZTPLA*EBauB~kytkYaXl_tzIpo}+)^fmne zauB~kyf^U@TyPvD4~m)suI{_3mV-DB+IJJ5KpY485!G^_s4bv=IlC`3M(# z*q!Pg)+F|@+tod+uh_%VIX&%Rnb^bbQunY->|ssn9+rtctV!L&Qe8)u;67*%OLZM| zPEUJSs_P)`gZ8jg*I^Re2kl|0u49+rK4=e1bsakd_d$DDs_T$8pqxv(CmX1B9bDy? zXrInC83n(@HLgH#2wdfts5V5iqvVrRehKKmD!)Xv9Gvv7)^c!_U!qzLuJTJ%%fVHC ziE25x$}dqZ2Uqzes^vh^Da9G_9D?sKskIy^_zsg=%kigNG)5Y$TFZeXgIdd>`4!c2 zps3}LoRX;JK*4uNu8DXK!FO=AmIDRf!PQz06nuwCt>r+$cbL>#4itO`S8F*?@Eu&O z<n(( zRKJ1bA8P#ul7Fc68%X}4@*CQks3NV6)b&v|R?fk)^^mQHzugC>*o~;Hd>iIbFdNhN zVcB}f_J@C~53EqWr}UUC;_Lqyms-2X#Ql~UlXQCccj2iX!EkhSyUGz83d6q(dp_(5 zBQ`}>u5NpS{~cJ!t`mBwDD;4T2Nrrjp_3ItC-`?@p%WDPSt0bp{tg_mVJg40Nqmdr zagNpLZY6Qm-5=T47v)WK|5lw}tmviFI>NIS3;xwMlo9rP_>es`1k3g{?VhlV7e8hD zWv@T6QftdeoTU53W;XYi&wf1olZ{BrC!bw3`{Qr@ted+@-tX3LD_d@PPU3ver?Sfx z-$@)Pet(AgqW6lvbx(Fok@)4MbL{BGwG!7VxQlf@a!BGLMV7KYy>Cc7ZP+l@s?~^dPa&10Qqh zsl>NFH0K#rzDWF_;xiNVtLnrgbRx0P2^Tt%Sm=Zcok%Qn!i7#G7CPZVClU*taG?{4 zg-(9!^T?4;^8VEH9IR)aM-s1@(}h`WKOu2?m$__G%6f^rci+LxeTn3xv61~rPQqk= z(idU!qun)5OFZ(^Om@4fBD>eMt?d6M?`1zr-`oG+%^le~%+}$*G8bC}=0MjWp*X4h z8sDq6zVSWrp;&3z1zl#5SA3oL+fa=L`LO#QH+Ygh6yN!e5Z|kOyKUqeB7p8G3p}6Px7v^Mnh&zZj z7ny;*v|GcAh-Vuu=8ShsIVj@gd&d*!$bHVa13$ zyhw}EU@Gql9g?^5yg90amwg2Y{kE9*epnCEEz7~dG2?h;e?Mqiy*Pa7K8Sbqtq(m7 zN zcfE>%|Ma@>;e`{@b;L!f>~Aip6{zawB| zXJKz?YqGPjx3o3cS=gJAt;x>9-i&Nbb{6(#WNWgsus0)HlbwaV8QGfbEbPt5)?{a4 zZ$`EzI}3X=vNhRR*jw6~>@4if%xn#2wgypWqS>08+1g}gYi4F^W@c-uGtq2Kbtamv zWuInsCYr6O&P1~{)tP9vraBYN)>JQ{*_!GlG+T2sTXQp8qnWMI%+_dTYc#Vpn%SCa zDl}VDO@(G_`ChY{3eDD3Q=!?KYAQ5aQ%waUI}3ZG8rMwNo2zlnguPLXYbNZCYFsm6 zZ&c%&345a&*G$+O)wpKD-l)bk6ZS?mu9>hms&UPPy}26KOxPP$TT^UnwkF$Xw&o(X zHCvlRTx+&wBCa)CGZELCt?Bn+G+T4Erbzau^(kykzYjw-MPzIGeHhKw^!qTHt?Bn+ zG+Wc}oM^UYBEB?Ra}n2?t+|M6&DJPlTeCHaxYlfqBCa)CqljzG)+pjyvo-w|ie_v2 zEfmexf4*1Pntls~>SxH-^jj#Jtx>I?k+m~w{S3u5QXVH;lbtD#ldZ|ll*iS$M#|%A zTqEUiHLj8JxEj|;d0dTaq&%+1HBuf|;~FWCt8vXKkCUy*&XmW^Y^~*R8HZ|IldYK= z*JNughm)NYf$5wY)!v=Lvc;E zrr*7xxc>9Ks;%jFZ!}xe@7~BdDYG1oS`PO)>xCn$))L=sPu|tivNpbZ>nZW%%5`x3 ziJB5m*k1?TToqifQ(YW9t%kgRLf~~%6`a<&Ezmc98 zFu1nFan?0($F;f=pKDVCTg+B)nFTd)e=7wyzE=b7^D8*_>YC^kP)D|}KF$*t4^a9U z($Wi8tx?8LatL{38c_2zewXIfOhClN>@GiAfG2kHjR0kVj&YL&$@wT|meqG07q1 zk(lHV@<>c_2zewXIfOhClN>@GiAfG2kHjR0kVj&YL&zgB$sy#CnB)-hNKA4Fc_bz| zggg?H96}z6Ne&^8#3YB1M`DtL{ETEFImpillN{t{gh>waGr}YX`59r7gZzvz$w7Wb znB*WoBTRCTpAjZG$j=Cq9OP$&Ne=Qe!XyXz8DWxx{ERTkL4HP<5rM0npq^G>!nAgJl0bUZH>fw!FhAMv>FJWmtTom9T?-zbo7l-Fi`sp>S zF6K&5Fc0v-p`)wIHkEyS&}o)}=YR6X2{#q&kmZfx&Pty#v%Rry69unr>y7y*DtLBx zZ)}^Q;5<9LF~C8=hSBx#T2EyRb_Koh{zc{ftGmJuMU*l4mZ^ucE-P&kg6iS!B?`8g zT?11h6g@;05Z@|&Q}os=S=eiWB0I@SGLsH7YkOd?P4y)9ye;Z#iYVBlOAV~FKm1HJNvXab%b@nxI_C@7gtr~mapykRK z`W|q{1@=lC;R`@MLG6Vv0Qm%A;R`@ML0I?#kWUa6z5wJCgoQ5v`2=C%3qU?WSoi{v zPY@Qq0OS*dg?>QOkMIQ`pP>7~7l3?%ue!xsWV5T21(+`;G z2Q>W%UjXt6dYAA8AfF&Cd;!QO2n$~T@(IGi7l3?%ung4^C|AU$TgPH$>=KsPMfP8}9 zC42$MCkP8)0P+dK!WV#ig0S!fAfF&Cd;!QO2n$~T@(IGi7l3?%u@CDM3#KISVe1hI3d;!QO2n$~T@(IGi7l3?%ui-f8UjXt6x-WbI$R`L3UjXt6!m9sEOtO;9bf07;nF*7u zBr{=>m1HJNvXab%Nmi1XFv&_X6BfPzml0*vV9=i2mb%)10Ocu&D(x_TvT?Q^vVGv+>jO&8p#ROz zpZ^{5XSV3Y``YX2J6AYm^2ONvjaK{>&R?}umRPHRO_NcT{}oJaMY}pL;x|nGS1`2|?NIc; z;$Okkmc}9aFZi!v%|rh+t{^)PXV1miK9KDL**@^U_W>=dQV!0>|9#g0*|z(~+s>?p ziM|Kc{{8cC{&%jpfGg|Czr_E^^(3wJM2`8F*Ps7W`@eN<`9Hnu|8t!G+Isar*0=xJ z{{OS>Nw4CWI%5<5W3B$b!~duK|BZWr|LpkxR)5eUGkZ?dG?BeFP&D!H)5Fha;_pbr z9i!j;%+c|AG`<|5;FE9SFjt>t^1e^0L~I!tBXM%86x{Htn8ecsZvH~S-d=;TpZyGZ z|J92`th+W;V%r}nn73>WiK7H=QB=V{bEaa0JwHwK-bq%ecqjCS#6=6HV&d0t{|h$n z=cstL-bv-zIPq*~59Qf!6T0J^xR;Fj9J8o97IRhbrop}NIKL|IyDsdH0~&0W*yGCp zY<6Ld#5O8#K+pc);D+;4p!(_jvd=f;Q=!SQt5TMWy$8Vl=j%E3|F}>HG>$4H*SUtO z)!=9-li0!UHCtS$yTqA4hp_zJ5+pVs&zXfOaC5ZM|LX0DU=h+y_W5moYZ(8fsBB-v zc%RiM82P_E87YySKl@rQ(vI zb$%C#&D&7E*YeYU7Qf!-3-LEy!Slsr-@gO5c@c%k-^=w;S6+z~!54n~gnQ>{|f7h8BV{wMyWLm$_k) zg#+Am&W|})ePkm(yMt}zhrB?wBdlxJ7I4e3kw-q8%RGBUz`K%t`T24USwX)+ko+ST zx3Ju+v)Y^t%^vpN)o+;FF5?G1@cq7c>4qzeU6JOi;qd~;?<>Gr{`0yf6_cSt%qSjk zr88S=8w;0QIKRF=o!zVy24&;l^7nhrv$-dlfZd})czMS!HgZoDs6EgL7pyM=Fx{p zooOwTjkEQT?E`*WeOQ-om==r}KFWZ>|%J_#u=+YMkb3EJX6&o1Q9r6x;XQ*5A zI-66j7ZmvX*%0#mFdH(k4;0Du^Edog?f(ffnvcQ$^mX0G;i*u6rggeGwm3gdH@&YO zu0#IxvT^P z17|G;Kxk&}bQhQX++j!zB>gD`&8Y<8@U*Khc*+W!+|{3nm$ zXRT;#yy+yLf3=O1Ic~Z)5|5m?!%O9ia(eJI96OD9&tL6Nc6#+kXY3Q53k#)<`wjn9 z`+u73gSA@X2F$Hl=s=+CweJ7~7A`cqB z&2_4>G7J*zzVHUMr~HQhs{KDr-dOLUkfTlqKB`1sCv&`Bmkb>)R_90R-g4BROMy#O z^YBd%{&1}MEft)`ZZ!??8}%FhtM>mic^A(d3OQ%DW=%_s)oklikcE#WDU$uWWKL`dKDIxw|*dl{D-rA@cwDhuvjlGr| zYRqZ~6FOCbxY6qkji&p+g1XhAK>KaK;lFDCPt)hwlJ4+O{9bD90S65o4pxV{1%06K zfrEyf8yS2%>H^zRHyb>!1wxN8Wni`2GQ-M29pPX}OUN`#GVpaBq4f5=kmxQ#{IbrjDE*{Cpe`Kb}_Lsg!^XkXrP=mRO1Hi%jLVD;1r%hmG15_en4B4_{^v z8(t{wV}9u&=-7B^3zxAOyh2QzY_p{HJ>Il;q{L~%6QN@DNXa1=Zk+(`KNBQQ3Q2_1 z^`az>*sX^zeZ8c-d3PqjgMc`xw=Q4xF#ml!skf_D5};dhlDz+6-(KC9i^}-x4&AG} zdP%`+k0ij(j__*VT0o$-8rUU^JmA8I>u}tN6R)Izmj1?L|NHC;q_+t4;7pD zANE4WZckQXd3*9lp3zN-@rXEQ-HBt$yBe?i!0OId?gx2ShFljK$ajt2)DAAiuo1Ue6z`22sWj_^N_254tL;9O-upZX0o+{8v0A z&KkqX7LO*3VP|p-kzJ%f7c$Vz%V# z++cC2le|CTR8P2(a6^t^L~>b(oF5?XSDf;OEzMHeJ7v{^5^a<*+a*ISAASD`*| zdw}xWN{^0)g3Sh{&1T`lAKPR|eXjK{%lvXEd1g-NZe63BO1|w_JQecw_-Z1*`c=yb z*4Zer)1qGqn0#IFhdo6DU}Uv&Qm#4N3G@s7B!-A$u(_3DUzb+-;8sD!2dXuUgx2Tp z$?+eVt%q6`QF07C=nuA_isE~xKj(vxbY)&1)xQ>0n6K!0cFz&)>|`aTs_y9t#?6Wj zlfJHCBhSY|u01)^U0qhNIiF*p+r^yehm+5+z&X94{N-;3n_gd7=^0_LzR_#L{w;-| z&$VD^bnUL;RpG)gWKl3=&b(`=v*HW$7#;?t-CrBF*E_@7Ebk2qo_sTW_YB1GJ#67n zRj*}@J&WRyify3Cu7HfF&TaX+ZbKnqyo>SJ3@fNGrUU%k5?~zS)EjP$ILE>sr)0d| zlL8fVmh8sbQW@s`j5p@ROFKGBT{-5m!;L$eOI-Z57oIMotO3m1oc&l4{hl_IZL+TW z9bmjGkmwfFkx>IW5>3(ETUKnEb10*95$&7wESuT z9rCWoIB7_LUY7>4r+-w>sP!ue8g=tx`yGpCJQMjLPwsszROH{-zn_A=I~WRZ-coqEE(F1OgJsrfQm^f;!=wJQ~}mi9EhcE4?^8lMWQmNYgx z8Md+uRr^}oF@vDRr)Xo7%S$zPOB!O_IU*%Z<%#RXpR|Sp(m_Ma1#~OJn!@27Yp59JHTeX|y?;1k3#E zvSqm(GrYU!!V6nFi{DHfml4vbCagBrf!MNTj9%|TAy2JugTN-O1pM*rYzB>OsXDgx9oq1i z2}8jlvYPQj+I*e8pB~CI>S45Bo)0QtZVx?oHZ$(2*o?d7N`gJ#-HflSD#Ns24PejB zD#pi?M)9qFL!d`#JLBFywlKPSAlUV;Yy24P2^|*H2J4BXjMGn!;d4I4!@&(@jIADB z@O~=RFkbyT8Jnh^Vh8g?!=!oLjBx=cdFd9>5Mg~jV%-fWPlO#76^ubwo8$GXw($Ml;$^k^ zn7G}=zHo>=%gFO`x$bpEJvcw?VSImm2Af`LFdS~*$5^soe%QLP9W*Q2)ENE!H9vQ= z8#tfH$ml*N7_OHo47qn5$XGLbC2O}m7KWAVZQOp*8nTMFhxtpJ8q1{aV(xkR!Q~T? zzsYMZ`;HTSY@J&Y{3sP;To|{WRT?$`o)?cY?pXYYO>5Z$!uNDCR#@Bs&L>ue_gyWF zefN%LR%M5PbDbDt)$ZTe%iLiQb~4yFdq;DeliLo8FCMnE&i?hhe(V5PcI8J#1)DFr zWo1&qFDc4sYwHMi-Zg=@aURC1Lt~-&uT{+MUaJiEKe|D^6>nJLw^7 zx_E}Iby;rAnF75ny^Z;==I77mrNG<5%;;d;$bz5rhp=hAj444S;Z40DFj?q~VYf%^ z>L&IbwNu+0ul8*VJwppX-|m=U?gP(n9^fU)#=s=Qt&G_=Wpy#9#hzhrnDOC^g79o{ z2rRYoGtM5~8OrX=1y#~kXJFyp@bvUKb|@${qxlREXy3UW=r-CJol}qU{SJL#qTiK_ zdZSwODjy;B~#r+f7f-#6TtqHoQP&l(E(+s7E&7+s+M zc?Ki$Rxs}0(*s&xe83*pnv}64tuj2D)BxJKS233L=?Oh<-D2M|#%9F#EyA|c)-!Y^&se~opDiuAG=v239glhF&>V%#q2xwghv6P#>%rwLVL>~ShdC1_~^nt zcCbMtEP316cy~iMwCenUO=9yh+Rx2m8@}{|8d*J!x4JsBsoRpF_N8c}v3O-j`p^J^ zPgOA%%V7z-M|1=%A84G~pq}Z~E&9XZjjj?G1+*yANzco_QIUW5)2uxre}k7iEk^Bh$It zqByuz&(iqz(jaI&Y!(~csD4KI#$(y&M74@aD@Pm8h_z}@v1VQV#?4rDZUpF~ zp0Y-_r(_sLk2Xyoq=$noTN+QdFT?VbOMyGV(Z;#6wy_6?`$7Epp2of-Dsa9g8Gc=@ zV;q@P5$qfqL7TZQ#uJ6tnr4;IgX6mV=@I%3CN~>V@3T68`oVc_J_m#zuAa@Ge)(3G zF62`x_&l;s?;7vL8vjg!LNBb+TUM#f@M#jPzHOC0JNI^7?)Ry1>ArRP<7-wv*Tl0a z=kljd?U0D`-}Pc|##uW(vFeNwBXdKWV{7cZrj^7x) zPR!E~R_Qi4f#K5-c{W=7|{xfBvz|KkOeQyRs$RCAZ zNb?m2mzf?gvQs^H_3r%QW;Jc$b;m%tjxxvQvP8Y}g-+XD0sTuY%gR*|>Thc#+fUfP zlt&gA2s!W0bWAK`fjtX{!jVBCj?avtrmsu%uqFJsLsPp~rqhrL6{DHsxA_)0eSa4? z{j!bY*ft|f)sw^=TK1X4iF8*iW2uAN`_df38oBaZos!|4dz@o%!5EzAaFBf~aK^su z-k!K|!wpt1E1}$%@AWaxvkKfCyS9Aijjp^&+hn*sKF;xdstaU&WH560u=Hl0eK3EO zqbz*TQu_zP;_*S139NtqJx&4mnH}E~1~GFS(p`_eV&B}m!*$nE>5aR6Vmq9|p?QV! z>2F4Oiofks8|FeB-*>-q1nD*@n(X<@}OY&GNLfNe?L4ue~;F<-@h0%dFEk1IdKECYBc~R z*Ud6)yHyhMo@oiQt9DA?Sjr22y{-lR@5iQlw))DRwGIPp;FNxthhtck5A12dUu9-( zJ;@r?iiU-2pBpw0ImmK1VO(og&q5MUc)U4#lpr*GaNUZE5$OZr9hdk zSC(1jD~_|SwSpT=y1Pe6dTzt5xUqnG=wzX z#FicF53g_TG+fH-gpEC$Kw!vehnC5w`1pL$Fg{?s~U3CYN%B zf=}+0Upc`8r$y8Qn=Snu%%5HG;XJoI83jvCV;q8T3zUDdJ}>m$+!4B5tDU|mWwmK^Sv{n^ zDC)Q)x*YrYUT|6W?=8#dUClK6pdNBgH#js^$KxZ$Gg!sF1s?YdLo;o?Zgkz)`_>N|e91P_`SX$grD0kY$@bly)eyd^>^a>vBxL{~Lxc#m@9Qfp$ zZf?hg(cXA!kUNxYo!`ORpL6%seZl(B6vv_^+}S7ZWZ3DQ%kbrGQJA%)H8kDOI{o~` zs?cH*K+YTbbjORC>{z8(Sg>@x;i`i#&Ry&VO}>0CKk0BY?QiVl?<(|zO(|0yQ(AQ3-t~q;uP0nrTo2_pA8_dQVFdr0Gz4N>Omp0sGJ`#>I2eM4OfbCapPx-%BO?1?G=1ecyu90`$;rf}ej;p$j+x6_D9=dGVJ;XD7n)TN4~TL&x)ui{jzujp>eE^yAs=x$%NyO*A-x14L)|L)Aa}rhf~3$#2i> z4rPZ7a9nk5EYCU{4;3d&cWnDE(DZn%Sc~rC4!JwnUmGkLY(4ymSI!#_GyeE&h|YP6kE#$2JtkSCKkaSgll|hL?8-dpvG#-c z=E(_=idN}O;s)|xE5%vhajW#u3Pv8?Iu5MX_nnh_ z;ly->w{&mdgrjmPJX^r4=FI)pP&tO#PH&n0RE2vCv9pA8u?lz8<8mg85cz@nulKVj zJJC})Yw$M1=CTBDKhC~qDBNI1)5&b+Q-zm)9N>!19dxpvo>zk~Ft&umbs9Y3@9!z+ zXd|+6;%j1&Y+x)EnX69}y?;n4y$5;I} z$TOf>_w^X`>baDCV%8vh7(83HFJG)67Wfb%+dp$z$O@cL&czbH>T&al5c#ZaKnmI| zE-rO={qAPn?OzI4Ii}$xokLHB3yog6PREKUxXs8->>#!%K(*gZ|*U9a1;-??0@2k6-qV^;4v@kYU^ z4||#J3T~9{yF}j6-H%oJ$-KOj6|q)y;^c5k_aITZZ$7q?;h~r@RXI}_anJ+xF7;$T zm*$S+3q`)7KJU4A!S}OsO5AL|1^@P1;eN~6^}wpVl{1cIh6a3DH|5-iM+`OfAFYfh z*w6z*f*(rR%YM?~v<1pJl~Ki?IU34 zu2tn2;=VgG_l?R~*g!LEe&4+Rebd8n?2!+$|I0~9_&OCh$+gCQ0FD{`hrHi;xjVk_ zQMmUenYnTA>rV1rsUt@5vSK|z?QacDz-D3bvc3D)e5~VYMGwd0Kk~*A%6ZWCo1?jB zX{CLUjC;INOXW<&d_3lO`SdcF`>e9R2rc-USG8B-Vo`@}e9d{~45C5lbl+U>6n*Bq zXN~)8+RO1YZkgNOUnlQF3hZ-i0O;D0*;Dio;&jGo*}jqZ2SDa)`u*nl{4&)$L`UQEO`B zoQ}$w;1}0YIBRZ8dH+|w8zwhV3r(`5wH?cx9w>fZVgC=)yS&Q%hNd*O@u!mO*biq6 zpV?Tp@B4m{>8P(VhF|GrFvkJKcBSv_=CRIwWt$>lA-rUNMJJsDcJY`(iXEM{#jp#7 zm3$l7?lHe#zK3kTcBlhR9po?Z=Pnlf)muex0gESd*PF^1{EqwKs8LR`O%JSxRxZll zst7vZfyQb|%(nee2`A@kDBG<5WXZSeRQl0}6vn9j%G`9eLk;Y{xUOtddi_IQW1=z! zwtkIiaY;q4<7bbXVzSg+(fI>EF8C(Wm4o=3v1<vvY@+l(>tHeVy|vPQt;Zk?%bF)`=Xtyh?>tJ;TayZa zx0<`iXY1As;qkG`{VNuixs7dkT|G5Dzr6g`fiK4N*sRnBzn>$ccLl4@+0aKi2y|pLu5u z&5D=9(-i^)H+#oW!&DZ-q5@!r!(GGsA8xqjun%0>bkTjOed zQ6yPPSr0~^+A}%f(hF1Ze#HxNO>%6TGxj{8__?Y1ebb~~iVtkHuE*?-DDi0CPyD(B zd{TO#?C0RBSUmY^rNohydf-*x#}b>j@m>{!kL&D{_nSUyi;+efWjq7>V5y&n<^9Z8 zdaQ7JtDNh-_V>WW#~&~n=Z7nye9$w+*2S*O)_rfG_)@`F`B_cDCsUh8+ZLM6tNCH9 zsUiOytc=+lo6B-4?c>gh;>??#UEpBDljkV?6zUy~wU3>U@7=e0D6V*})OdvY`eWbS z4zm4_H?6S3(_#`AIWiQtFKr>)kKWr9%U@P}pvzA^w*Bx()`V>B*a01{DrfFa(|ciH zldDo*%fm6~XV@$85yw=l|KX!t6Yh!XfbI4w?OoDunieD}wz!-ch2vXZl!>$lJT^PE&&y zO8-$Ei!z@uRS!S(IEvZHb=2qYdMr7moWwgUtXPs+33S(c<>lyJ+S}v74ElOiPUJSlX{RM@19x#ieYT-^AY^x^I&W3c^5EE7nfl_f05@eLg5>&=&_j=c@}V?;RgmmfMTk7aBv+ zEvYy-?S!<^V6j%eu;IScN%t*!oYS+B>}Pd@LD-&C4U0MIs zSvi8cj#2VPTAvDR&03}ZtmgHY{XxZVOJok`u`84|2W^tkqK2o`RUyANcsh>~%b6AQ z__X&5`QAcBPMNB0P;_E{^9&z2T+!#G<&Jn^xUxs+6`zV->~G8VR@FQ(j@OfNm02R@ zO)Mwzzz(&r#UEZ02R%5*-`rQ~Ozb>?$XrmaiH=WQ!UoizEGgcSq_P0uzx*#TV~6`yZ>xjClY zu$BFf8uo&ZKC1XthX?K$o5Ne)KXxHEez~aFaoq42{P0OxH#U13feBTf$UZlXwZi>r z%38h5geY87?xMVZ`Dqm#+oitjr|}X!jvmrgjyYEyJ&yHTD)n=9c??E1Qu_2g70H_? zDEVi|(g&u!-4#7&40y+@)K>OcRUW5eKp~UtXL9Lew5eQ^lUy(BB;fV5q4K?z&iBVH zB{xZY)~PGzPyH$JvpqR*K%-DOo|DnGe0otO244l{#xqqr%lkR%7vQ7Ql=~C*N8+6Q zcjU8G@<-vx2A3t?le-WW30C$*v-{=82yx~}W9U*l27|jDkZs<3>hW{ZGC9uv@p?S6 zbdx2vr@zJvRGbRQd}A5k&Jwp5+~&Dk1pX^5)WKo6tA6B@=v92zIbNs)oeN=O$w4{0Q0J zrE?ro9M`nO-0UcJ+`{cZ@Ijt`%V?#j??|iXNTbC&|#eL>}PH9%3>RN ze{1`$XnEj=d{_T|HE`j0#W$KyXp1pwePcqtTG%f~E!qD4j3(G@s-ox6+$lKzhMj!2 zK*!v?%~i$EZ!}HBTo%3Au^NR8*SaO*oZw#UT+@Pv84U;G#NkVr&rzKrp?e>E(EJF? z@g~}EFRL56On$?PSDt7%F|r#DYW0>)m@?6jJERW|nsS8Qt=GqptK~r4;@IQ9nvNKMyNSf+Z7%6O@J8Qy@_sijYjjO%FY%)~)$!?c zABh_{#o*vQ2jqBOZ`0$FKbW-9p4O$Y)SebV#`<#0? zD0BVX(^GibABx`Ws($4+yM)R1Z5vJGl{zZ>#H%->@Jr@-IsTm2qVUWv1+Vd+%1bX* zp8aw#5W|+0kz?2@_M~sz>}5Z}MN4A+o=Obf+vibf+qq_~lRr_887oYoJoY}_u}6wgS-JiE`z+?zIgAg)STB>Ru{?TQO4 z{FH5sH+$l?dN(9Ce|BuERJ^hHseE=uX9t{~<}dsID@^^bRQumKHx|8GD{D*B#@y)p zyc1H4)HZZSAKRDmUCA%?m@~p8Wv@Ln3B8wr9NX&BJ@7!B!fWl#7lK`43(03s^{t2t zyEc+z_*E+rZ5l<(_N}6OV67UDB-ctw%oC}t+9E%;nJESS=%y$!qU_|l=+0TZ_ z379E3bn2)0t0A~Ik6w;p+=)qa>ZLq-GSxS!WdprP_`;?XA#0Ft_d;C|~ z&s6si>|IZ>OOkIg7Jpk^-hVSvj|(0r$^P$%@A)QHJ|*?+wj>D0?<*nu>FQ~XXH%4U z+18>B4(+9^ZN^1d;={(u+Q8?G9)E4MmCv60AMCvcP*h9QE-EM>C@3n5N}7NmC?bL) zFna+aA}A6Rm7J9*NRDH`oE0+&%#46JqXM&+5fuYwOqes~91!oGZqHx*uj;RR{`czD zefM3hI@WiVU$4DZ_v+r=t9yDsaz|%DgKDIwxMdY83CEdC#W@2V%L<6R+eR_Ic8DN)rUm*S?=kIPc8Ss41~r}Aq#5Pm zixyqtSGu(rPq@)Jn=#jC)h@juaXX(|FJF}%ByBy+(-*bpbS2Naw=WML-0w)9b-ziB zjbigxUyl7Vq?bBX-6@)%6q+=uX8<2^AYrWe8YyJlhX!Fa+s%8mKvW<$uB-@(!s z2koKyQx{CYJwxbk7M%O%V1|h+u~QzDgPtFq2o5iFM~?zpZ}a90aMov0Q9wBnuS-F_D(3D`m zule}qF72E9Pl$2v5DUV0a+`p?*HC|r{X63>T{^GcH!c^aSPvx6eOx2PH@oc!f3IN% zdRNRLI&b|-$BNRqg!4Mo7x%`{I@G?^B44kOPwHXE>6`4{T~i1?YsR2^xH-WW&WkZ@ zlo8Q6+r$emsn8hSYO05wZ@Uv8+v@q2`GI|z8Ai$uYC6eI*NZ3kZEXQN5;6#G%b6qH z#-1OPOyo@tsx8FF486hV zeuK{UTs4i+ayK0(_nvjf4GuI07EKO7_E&pQw0m3J))%jNfT?%>7JUf+e9OdS0bx1D3CiCOaW8-N?;V&;I0k;fBf}O6%;VZLK1jmeWL;Do^-dtK@ zjLFut-p=Tc#mIrZK~XlnL4fnBY2VqG+aI;>Q2URi^+&6R6yLmHjBcH2S>plU+1b(% zV#8qDOgz4Tu035+gYaGg?NiqW#$l8bU4yiq7=^QY8j)wsxq5;<>`P;2S#=89Y$_sl zio2%aF`brW;M2%iME=W-Ti4vUOz=^6Pt;pW#}JJvF(~$>@*8bzi`&WI*#j4UuQ7=i?9FFT%fj zGXrByW)RN0f!64Cn{t>JLAcHJH>;?_155K!N$;jyffxGqLSeQi(Ua0_j2}Nb6Wq4! z@aRA^x2I#&t;z^)KjkIS-xl9)BUk9}@JIg|S3A_)Nat^E)$Q0m-)NuG-(-M6@7&0< z?nO<(BTBc4Z6|EA@LBg*f{nR+ltC=bN4*JD!}g;m6TaixXgnW&m)MY1P ziE+272dM`er#!s0Oozx7_O$=h2x#(H$=~@crkYN zT|o3ST?;{tjBmuw6h|-o{ICZoo?F$BiH2X2i2O~v-uRgrOZ3>SQNvNjv|XB{<8kg{ zEh3Lqi9ofIS46-2kQCf`w}fE5HQ88@Z0H(#0PsoFIWQ=h04zrMZ;MWv)q zgukXH8gHDXeYQ*(j|NqAO}h3{4i5~UZ?#iUcS|Y3Pw$A)K|__a(aVb&xHf(Ukr#}dj=WgfzQsC;sA^tI z|{PEOVsGDn-}JGU)IzOGobLqs|DzVn!rC+UQLYH5{7?A zaI0u64p*l6gmrZ-tWhcDRQ8>KmNzvCN8`i>R-{Vne7W*SJfA5b@?Ia>F%!PfvD&Zu zM$xSiv`+kYyRf_La|mb6I~Pn_O8Ld5*{HSKi`aQ#);rN`J6c!T2lAM$9Wn{u>#G<` zgXfTUf&Miy_gxj5^FQ*D%m0ULBJ$)*88~+;eJ?NC7tP%t+eCD(-<5@oYB<57tx>pe z5bc|J>(;XiY^eQL=B{VGY$=Yp5RJ)sw5-LID)}UC4W?-KvD~_k`C`E;@cKphc)tVf z%jMkppBjH}VnbC?27YXrNuD*fxz1t7E9$%HtbE*m^bYBRE-iUDduThNXT$bfd@x5y z@GoxvE__fG`916y{cQX)&Y$S<=hj5>@)bnh*0x_sm)Q5~X>2ELH^y20M-V%I*>UTX zgc_oA{=sYP>awXse!YJd?$VAU^6@DL*|Y7Y5&41lsi@ajNaeY?7~88q!Tnqgut9N@ zv$CNlp1(uqFdt?G;iB>FNZA)XC$qj5*#sY6ww#^0n$Bt4mQ@Pvfme&^7 zxYCE%6ZJb0i?eC&$daeYu3buFviyM<^WDBXDB7{b)d$tv(=mJzn~40ghluZ&`%S_$ zGx|PiYfoG3y4fC$gcjskgC~r~jY?ezc6=0p-$uM3dQy9c(KTlWY4@%EqwvNCI^VFY zn~L{)(e>kuoJT`G9qp<(( z#yp%=)`{RB8zXS*WIAtrJ?|ysBJqA{2I$fn`aR{-JA??`|!~OSNkO4z1ZDE&+PVGe_X$h zlX8*>;s#wMQ6!Rgy=3Fp$lF!mC+c2d~0XMh&#IES`Ny=zC5R!t)EJ0lHoMjV~H z&e$SC-}mN3{@gYjQ++29Jw@Dk#Z{k-8HJt)-rU_t(Nl?Bpp}cE-G&f(TA&rKlMW+g zXVm53q!GgjXU-aXRI#RQXLu|OpH6vCfM# zoMuYlwmk*ii zNcg&&v+>zvFM=OSd~iIM4^r5Cz0M4is~CcBUC+c0Gm;2r3^!(Oj-m5`^GthecP@Z( z`ggz|48<>-axiAZFv9maE5 zZ$qM|DNKaJ90w4L6QXffGM(@BadpG{sgzT^%N~Dn=T{VEPumZ{iZk>*d;U!Z>S~CI zFGsjNpv)_MiT;%Gju@OxV=tn92u6x1-&kcLcV3j%^VPhkZ1LJiqBHeaCLXy++vss( z2lUhlz)-zr{_L(D5Ih5LeNZ!hs!A`MeZUiIf8XIBPcuc`smU=+`&;m5Bq#TQ#0aYFC&{F-My(c-Kp`s+6FJIG96Q28EBlMOK&-MdRF9EgR=N4j?{0<>n(BW)_q7YOAOFz3t4juSukA;QU+6 z(pggot{UG7EROpT+?MmC2YII-8SpPe-yCQ_}lb2MAw)3bxy$|kZ z+s~zKdilt7Jic5)?3r_)+xvd_i@Ym$ae2bz1s#ZOo4N7fPz4Q}dUKiK)s z)aKUFr{q6RQ;zwsj<{e1je+vq$D*caDzEtdkPXg^B6?1+9pL?Ae}d;|e`KzYqjjRv zC5o9in~rINPCaBB3n;$>_ikLHH<{QLb5|Lrs|1p=u9pqK_!J%Ah6<-*zw3>JBmWSE zf{qUeUf(bU4>{f>_#U?g!Ih>2Z+OJbh4}Bu`-`WOgFoe?i2Tz9F`k=dKOG;Ak!${gsKS*=2qrWlH zzo}plO7MnH-D5H=ieE z*X_vztemyzPGisNgDYC-@d!WUULID-+Y_CY57N+i?oxuC*NX8+&J+^cnZhaZ72N-m zcCjs#3&vCIM`gy-JEb{mb$R%4mkwtm?mQCc{(@V)utV9*D#D8ccxjP zQ}8^SwYSP7Sby6vJUHHpV9nms5fjRZJ+FUd;fFMVoqKIP)!2l~- zCtrFQ;`?QE{3#fnhBnJr5}kvyJK@c(bez1{a)^DkKarH3anu86{G>K~7&#bc?zScJ z>M#>_$x<4t5l0i*n)kHchJISc`u*v%^}V*RXC!pZ>&Lp|+p&72?5l@OtVUHd!D{hK z+0-XAhTl7O#v%Qw4Rr=S_|SpQ&-LoZ;fHxTguen*u#C$$De8It!yHrdYpXO?i~F%i|1N zz@0%+=uA7kmt`N)_iX-hH+13JRUse5?E$UWJeT+~)3`f(V z-l!(%*RqD)T%3xoF&zZ%osP0D+}WntAAa+r8;`Oj@8j{<(ck<4=e6v)m8n=C-a%m6 z>c@`u$i{(p)C5f96zE}elQkVYPdIz89e9`yLZ8>#0*CaA%&$u^7+T#^I=SB-ma$C2 zld0~4FilU)f7uH+pNte{@zSD*x#O;hH9><~rC| zL+S@Mb35Tu>wd=na5{0EOLyEMxSt;Od=18S+`S4JH=eNJ=4XVLkB$L{%HEijzDBTJ z{R=Z>W+)!sq9*;_F;T><5aZVatz~QWJK&FB1F&X;jgXlajl#`$+1a6+groHnFi`0z zyXD4D;T>*#;H~Y7KN>590bWkH_KFGmbYTVm;Bg#o>&woXKs4B@gvq|2gg1M;Vsn-kggcba(JGl;v_y?p$EScTfIT zwv4&)XgW5%)RbA|Xu&chA!CH(ixl_0%75EotkCP~gRmd~gc<1zIrUXQUp;QT`y z&)HT9;|Jz?TNQ?ylf;?8NQ3+u)Tv8T5S>ONH#My)ZyxH(QZ zac@T#yeuttUG}QE5NyGIX$_M)mY!J+wsezlgv-KDKY6ajw00+8@aNuTb;lSo`_-V2Z&K(;o z94s7w6LUnU@1QMgYnw=`fqBM@#Z$L?N)PPs$OIn9L#M)}lAw9}*j~ux%D0Ra96VCb z#CMBBrJlW{Z0|4Zx!h39uG=U$ob{Y}(lZk0-|8aGwYU=7|{6 zy;|V5^d*zHGy?T6YDq`B_%a>yvyt(+EGeGq%Npcnqs^sf{2v>1U~26+)NL)0Y!;}( zXAOTed-z!LPgy;#tV+8OM)!6WW<0np*|OIL*Z5iE`ToYj{|XoV(LaRKzvam-rXYR_ zUcA*q%3C)DZVkA_Zt0sQtm>%+l^@3At#OAXK}(bws~35AVlfw#cel!C^%bLwy*)oF z?;v}pH4)cp`w9kK7Q(j&BXIHX0;49S!Fc?=Exu6eE8KIc9lPUe9{xJHm_K(w73&1k zFnxr#AoQFW`#vTYZ4OoQ|MAzFv!|_XXI7*;6n^7!h`Q~|+=g{w@8xjcnwnL_UsN)i zox+_h3nhuxFS^A( z&Dto``=kboUQWWS&$lH9)c1*WRm3=KFeB+Q?KxZ2I}%@eEfZMJ^T(!1Drl}bSGZC- z0`2vTadFHj;e*g=D9$;+&OP{AD4%nHc^5nljraGEKDoJr@#OO028+8%e|*+qr-|}# z;C(6o`hx~m`C|+YNJ$qQH;7`U&B{WX!}le-LWW>``A`&V8426AqgsHR*$6`xoT|Af_DZDUH6%Taq z#|3lu3R0W9!-98SSha73B!80-;xt`wRDiS5p2LfnNVjyHAyAfPW%OspW^!kdx9*U* z76;pxaC3Nz-?vMma$4C!K`^F%k_s}KM&YNghB)b`k8tqVudItHH?B4p2|Qkp#=>PWIru$BF5&I$ z$gJl2?DZu}B?*C*qJexd&fpD^sJMM(c}`)t#bCW)aqPR=liWJZcToYaxUmzXv>^`@ z%2r5b=?Gc#J-N7f;y!**7I&UpD*!_-?G%J5DPg)n5H6WtAuxAq&kp4BO*6#H_-?Y> zq7HNO(e>aIiB9=P_JBzku1#Mr=r`;Yn`*?JJKwTWuu5Ys6SpxHzwGWPjcqMtYMN7V zeW9B4MUE;izd9L@TI~}!pRwZdb;Iy}y@603s>|I2Hx_la21$(UFR@DHF}P}OrhsSa z&tw{Aqsxy*iEiOVcKq2G>^3Ju5M$-SHag|tr-ti%rC?`N-q;U!b#xI9w|>bKZ;rru ztyD><4i1u!s*FUl1wPzv%yDmF}Gw7KY#9F z#(F~{c3i0=-JbzE8?ZldDr|WE$qa# z!DMdM6gM2-&$J}Ct)3Up71*%@K$ET20oZ1{fDEN zH+{)yczS+XPxP6S4>MRlKx*X{LyUR~(g*|kSAb1RO{ zGY@H5KdNp4s06*Y}e|$o4y~*1pCv;Y)F^6 z#m({%fb-u-y9|nuGy5AUzbC(y<%?)rq;%)*kh?dE{pz-D)BbERXe^y2KiBQFMB=iB zeRP=SDj$g#vsMGB4WCXHvR2Eu(4KL(}5mq2?K4^S&@`)_5wN+ixX+z&)Zx#yaT4t(}BU_sGXN`QTFDvG9ql&h8 z)m+LxP^D`t4=W{nszlq!EUc7m(5LdYwy_sPU~`(rwpOevtiDI{26m>IqGGO(D|99d zcYu$x2NEp4UMYWRMCD&TyTbflG!JmhvAFg%x3{O@8@Tpj-&s<74(=HR%Pi;~N&&wo z%=f3cn!AyH%uHYE%P6xTFnmq(QOS0`@U@Jt?-XU1{weFcR2QIdEYWW_>M)yMPS?5i zZE#!p{Wkg|^_{`>X+Ki75BHn+@7s6Qs_5M*>l!x+cC#Ic+`pF!8116{qCs5A_{iz{ zccPDa(U@e~^O?om*)_#;Th2{opLx)=?W<8$jJh3N50+Rr zi-J7q`t-|NF}xanptd4rq$D|EJgjV@xxuW7-(Uq zhR>#bExK=mTzxmKH;G0wJ28=tpBiI#%5A$*8+N~W$L2nyV_muSTc%4`IMLIkgBpAN zIJLnbu94{?qHXuq$eQV?Oxx?mF^%ef^8B)3Gp3L`pP}$;(8SxU)SHgCMbQOJqdSd_ ztxC@rzjV4!vCn&pTxLjZn5nf|G}wpYox2Rdt{2V!-0PwZs&8rA$)>78>V4X0AGLmF zObTeeaiT_%e1;P(dpPkJv*~g?v0*HC2mi-Z%73?U7E?cu+AuWqw_Mzg)``B)J-JO5 z#fz7(WHPvXlfr(DjqRYbKOIlb>@Sv2<@PER@@%I}dBLBtA|=NZcr48&?%8evy{9`7 z&I2`dcIjSPZ#|3lurvD5zH|9rFzkBrleAq!sd^1}j~wAYS=tNEczF`sb8!@7noHw< z)&|?^mOq?#>u$3e&a^(2SB?TrKRV8I+vf#_&U75MG46vGB4|vSUf$0SfgZ4%3!xN}qrxm(s# z_V_y5c2_F|F!MHzJ=3|(OoS(mtDw-?%((r{2kD45ysmZ+5fEcCO z_pf67J=}_ZqsV{BqDF=87F{i^BaeOaMds`$WlHri9ClDs)<4y-1s-dgk?bAXiSI z_)3TKqO(;LPibS@T9*`XPAehy8^-v;zM!r|&m`+t%%DHH+4FO!L-h+O;XM3N$uw3_ zzYN?m;8Qj|zma5riaB|izK=lUAsxGp zbHB?kS$mhX>8P_g5PF;LnYJyv<7Y6m&Z1+WNNJR4<6atv!`onJgWKw#J&e1byW=Wi z|AUV4kZo7TDC+8vZyx+u)1Al-=KDa`&Dz9wclSZCex)7321(DEiCnHj!57>XL%Se# zV&}`&wW1Lo)CS>T6L@upj^Pe_UNFw5=$O`D*%0i@==-RxJ#F!T^NwI2YfALLi50>& zTRJw*zt{;Xruz|jhh|46C6>-(EtgwET$T-yM|dcMG%%206a9F&aPuVbtHwMRPE5BX ze%;F(1Dlll5YCMJgG@P>gHrgica{VDs)Xvy^J*{m;?AuqsC z9%kz#$oKC^o;z&M17^$_y1!gMf1yJe_xmfwvqERp$z#vbxV@gaoVmA-j%n>2^C4gB zEoqDEH^gwJP?O;BlTl!L^a0VI{%s;mNl_?#-+OO@d?}ar zRy=FYt_r5$0gdesQ&z}}{i*!E>u4BdX+Ss$$CfkdOQ{V>w;kchWZHHO(k`&>nJ?i) zwY$g+dqwLcaJ43|ZWD-H$K!Zy=xeHTQWqYqZK30&aX~ezC^xBX*;7~NcEiO4~G>O zEQ!1?cL%>+RTqNG{ET4n3cBxEIi`@=t4jT9uT;bwyF%;dL{&eq;_^+3`ngpw4wRnj z5d5TQ8}rkW>Yq}ukJ={V`G%-zkdI+WNS(FfqGAB~6OgVew7TPB)Xs8-ElkfxI3-G2ZyJCSMg2u*8E)l=I2vj_q7}B(LFi* z#=s!3Thk8H7Omn-xoFsetKH#V)#2SK|=k$K74l2ctq z!{~Gaoc!Yv-=?^XNq;dNZ)+$CKM#83aQ3Mfhr|U4+v-_d6b)C#(BD)1zT^)rO&y5- z4JxC+x&x2kwj3oZUl_f!E0G^+83MaH4JG*JRBvD%yA!N4KL>R37^a8HnUeOE8E~L{ zCi}@@F>g)$RmS`ERD5*fvcPn)1{1P54<9}qC|sabD4H{#JD=y6Dx9CboUvJ-hB=0( zg$74XG5f3Hu-~cd|G>r^ZtKh1#6V`z?<^cOt5O*Ga|h#eA_*^Q9TraCnGJ=T$FX-j z9C?F(i{YSLV*l{D%BH(xBO$l!8GC>C1pX9W99ZPkvkk!GyS8%QsH%HyUzz8$>3dWZ z{2cL!RqsBQe_16Pmb3&gUuFACrgl$)gkyWy4llp+&R_C?E>HUqfA@s=!pt~YCtdqb zhwQH9%xE8-k^%ZjP`YFf`!V1<&wE5EcW-bCmQ*SU-}1*oe!t$NY+3hVVEfLB;B9N$ zL*tqNRMwOU=Dk&e*w>RV)1ydWFrovng96avrbN)Lcs|qdP&y`z>nt=?+aQW?6=N?S zC*kaiYni&-RBX*v5nA)+i7b=F7}9>a@X4brXbB5u91iR)dH5g;1apI#+O>O2biZsA z?cvrqs)`&$56D_yY4$6s)CVgn=5j>StG8U;%(E5nS=fw+0v zW`UZGU7ooO#TuiDDIaS6uC@!JKx+SmqL^FjN;MbW#} zXG*yHOyS4sVQfT}K2O`#4PK=hV&tP|{PU0VLDiBKX%9PAax!ZWypOU&&%j}V*c-WU z(AkJ-HojKU(#+k({?Y=+TQH^Wfk(Wv2W1YbE7ggP>$F?c=W! z)8TpLLT3I@ammpYIpDEd#9sbj%$uPS&)uV3$9^yE!(aKq6%O^~Vey0f)rn>oyGHV! zsMvrKcXr5UjEUfgSpw5RBMX0(_7D~sA7!5FB;d%$j|BxVQuK8ncdzBzIN|<%V$fbY zQsg&rRtcB?hH~o;BArvBlC92B;C1;C`_jadZxqJBD`RtP$<`FidSJpTMmHd^WLIP!XdcsMN4efHN?+mv^HhYWvh4?7hj)WH z)om)~g*6BkyeVT|-JXtzpR^MOJv4@$Kb`SI+<1W}_nnp$yLC)@`sk8Fz6qf6nY)T@ z-hxe@m&7n-T_3sO)eVO8t@Gf_lb)=B!E>W~wJC66SrNPI`Uzgz2Xn}-6rpF6lfd!l zex`T9H1tV+C%E_B0#xtX;o57qf(x^EGAp+wVOP5^g7jgT;I=xO%`+_Et^92ammWH! zmiBnTqRLcAIIxC|UU-ma9WxoM`>SE5`a1p`69$^2%uz>2OYpqcB>3Q@ju-2T`8_pG zGRxiKG0O3QK)+ig^M(nmZQQ})w;moI zf0u8#n7gw!GesV8QpKq8QXaSls<6I4ju_p!nFF(mhOy&k>GQn%Wr6$HIJU2G0#8Y1 z39%l-@yEL%0>@6t5SO%_mECCOnYZS^(oAc%Ow^nAadQN`uzJY`J@MyfM00tAolbc9 z&^W=uL^B9d0rX9F6;ydofjfS;S)MV&f4n#wHuU#lWu`7Xk335loirRF+*%MYdk6&0 z9*RlD=7MH!9k=RMQtkMhn+D$8KFF$F8)`$swG5MsjG^bS5qN6k1i{-5Z5Tj%7hiv|{x)aPYzj$;KKM-i{$%S}bA>(LswWRkI?wf$iLYT$uo|4 z>z`}b@g|3O;V(1bw5OQ0$(_$LznwESM($ezQitN zN4uNz@6@Hi7G@c{e$W8^MnMj!Y;a}YYJBG{T$m4azPIF>C)e`MWmGWc&B<`HUy|U& zPVSpgKRuvbXfMHASr9bzZU@b7x%>@0ZtQ)N!yXvtDRC|t0MJQ<>MjSQ9fVEXd6H;M zncE_5tH&V27^?k7z{X3{G@b5f!;>%{E)QEIP%VGXZ0HmTBjd^h|8Nv@s@FYL;dD2D z=zC{}V8-$N%=X#SAb4ScU|mdmNZ1>iw8Q&m_Fx zC%EmJHT`jU)C#FxgDPm0O~&A-ucTE4@0qyjFnqJ>rZnY&F{HIPW2>))bb!7+_*Ge; zPtLXfz}_5g>&rV;U5NTN7L)g7N&7?(hLRPw7%*;>bg5xB%N!sSF0ZAu(@!y6&l~OFH1Cn2e%}}vA-%%*KXl zq^`WduSyq#XMTYwc7Y~uneG61HitX=KA=i!Wc!2JGARVS6NU*Y-_|nQ-z0#4`h3By zdERioM|ZR|n=DO;9S>a|YN7G{G15gpyy0O|HxxThlny<@hyEK!;?)@^rGD2xF!do} zILG*>H2RDwJjilHrxP_&yUI7ro!oFVS8tLAY#$4lpbI}#EBH6c$HJgAT`1D2;4c~R zk@0g5!-OwCq``rvFzTiwl=V{;+~n4k&iH`+EK!yocp-wQt>(C*=W3~>y*FfB?2g|8 z0;GEk_*}lr6))%4Nj;;rA!nZtY*yzBx)=t7`Jz@f$xk3H_YQ?uRbSYUH@&6G>$o_| zeacSWswPDjPjD;gg+qQtOPyWJK+7EP>FC4K)@hy)9@z`$xJFCc+GeK~3}f!LGCiWQ z`6`$Rw(8TF(>)&Xo?Xm<{oHRMw`h!)w6hF>UT1zVwg*!A2MyvO@bXFaf~1 zOzs2@%a`%3pC`l1`4#N_>&23bdQmVf_Ay(Zq9X06=?5?4Iz!3e75u5|Q{Y!zG4n95 zE8j?(4=>cO$j{m>EaQI63+gk>V0rTe{(&p*FvLm^7HrzdSCno3Q?{vcI;=F5GQ;QT z@Xt(i1*2O$Z0J-VZHw#M$QAmZa{AA3`mGQ8Lk|rV(4RVo@4mc}nO>a?PG@5US6;io z=@kO#wvy$ueY0R-yLjfF`d!{=Zr|#}>KzVM-JOjNyJkS}oC4PHbdcm^;b1r%X$wB3 zANehb?ohs84~zO{NYyyLZtq>SW%9A5rfC`Q&~!E{De#x9%;)ZaFP|azk2Ne)*z=sT zr=GJ%fuH@cZMIoHT-^6b)D)G;%f8Ot$A4N|zCUnh>AdD#m>6WhPI+^$Y?xjEq(yM| z<~UeNi*}0PL$@)aAnzulyYI8XINzOJY0+Ea^0AT`uq7FG*k%fR3P!{C2l}u^u$RBq zEeBp!j9^lR)bcj|PJ~%m2iaMNt0VkKy{#8Y5&F2ar0AP`?X>=L>;{Ox_hTNG$T`dzRF0JFsJ=5Xo;zf*}o)Z7t$aFYW zzlhD+F-;Pn?*uMdrucI2Qt4B60QkLeKwr%R()^pzU_Y*j4cBdvxKD6|o*zwNtMOTW z_{qU=+r}0K=zZkR=e{#LeLBl*`)$ErSeXv;&I_1^mS4Py+#SPBzwU^ti^F+uY-8c$ z<_qkyuzQlGpF?1N=b^a2cct{;tvEQZbBgs7Uy_7u7!1B4ws<9FyR^X}7Z$vk{y+`e{Db9xXu&MT5eZWcqW*F<^j#`a}8-*X{JNuLSnvXRH?#zWJalkBEx z4HDhenXs)YmHpn?RkBYu4Z8Q(&$Or+^X1dhAadCX=K63|ek|8#Pbg1kBD*}|*)7O{ zSCI_U7Z36rYq{@n-9E;SZC5Y(Jd&HE+H4SYQW5a3FUq*{0T32ofsMoqvgW! znq@ooPl3#RH(8tWpCoCKG4MI~GMk$GR1)@D43Q&`*LD&{mqt2g!+PmNre66x?_ote z#4yL%(jE1Z7;Zigo>apoyUQgrLgL`mN@9c8b~caTvdDPc&3~YGSX% z{*t_S?gmRL3~*|Cp7dvh103!&5PCab zP{FS{(hW`@^Tv0sP0|sE#BgLChzyf28XZf^hp}Vti;Q+gachcPC{VU$J!Z9+cpMSK z;$_yNoh>JfdqHxML%`u_hM!{y4|> zd;d~s^2!;CKN+K^%*(i~p3AYznD`@U@PcvcYkG)bM$gHC`o*VY2W=*aBr-90FD#b) z!%@s_q=VHMpJRD2;*6@yup~iVx`O+zTulML|H98AH?A+;GkYPu_Ob(5)%(M?x(hPd zqY3bKYiH0eu9kH-Plb=S*0cLZ6bbuo=jNh6yP&$ggYjIRI~3^ZO{u}9X?+Y?rB zd!oBX9+MrOYzA+70bu4enccNSsGe|$skT`ut6MP@#ej~|C-UL*&<6c-71=@FXr}`H%SwwcVyNc z%!4#HW!cXyry12baR4TJWwx?#Sl#Un6W*{zwuAeQV*RKKY_rB|;ji^IqKsGhaB}i4 z>Cp8ia{V)6Ff-8O+lq3a{R$WMU{AjAoLMgPoNvjV%2OBmMC3r6*oh4sX&}77eXn*? z`D3={^^V35*0@90nR@7v=w;00Oa=4c>+Dq1AHt6O(V!n9enN}gk>INLly%k8Fpev5U>Zwu;M*4)nf|VPz=#I<`A?Gt z8NJ0YvTU2&JyA*`)0%141d|q&r~9#2A>fgNYGUuDQ5I4|>sl7Wu zW|6j&vE7*j*Vt0o@@<*m>6XIwOA8iSYQzIr*DM%{Vt39`dUEM0r zSW_z46A=kP9?zI6?pwDl*Rx>F=n%$j^#s}0FO~AuM%=fhHfsoqkG^FJtis{=vy-y- zTfAZL<8GkS4Q2Y}+}be3Pvl=*Ep25(VS~wM_U5IY#{C+SKnr)U!q%}2twiYQS<4LTT_{_(Djzy+ZxjiN)nppU z_Aoin0+=-ovMWs)aG~Q2c3;&rVcT}BoO_G;JZlOFd9|`G5*N7kN&q#Q^)jcJJg9co zX6)DUWlD9aQ1W>-8&kYS_^X2ZR_eBM?5^oAg+@=s5N+|a_MB&hWXktz%=DF0;dJd` znbD`6jKx|mhuf!2)-%8gUdx7oU(6MmTlz@&_=*odGtS6tT!LW3k#?}4aF1*gmuJ2& z2(=e#x=YQteSdqKYOY_O7tZ_0jmH;C93HjIlzNB~;B>?hc4yOd;cMA=c)L&w2K}g! z4SptujED!d=2x~!`W*;>PEqY4jGKALn$uvE(^4i_kR{t#ln=_kuZo(BRb^MWZwgiB zEnqe@rpVsTPKLv$wy=87_X(GGmyFyzA}S!%H}-1F)OwcNKOZ6)pyI$aMub56=WCvY)d zuMOd2SXtH+ZVu4(g+qDG3Tc<1Fvz(7fw^&Po6N-69d2~j2Y7f=W-@siILZz%S}&K& z#9ZE>pGSFZkl>NTm#ZJ^vxPO+PYjTX-QppZ%Quypt&`dB_2kwIy}jd9;YH}nka&y9s@vU^#$44;(WL) zy()T|qbe&mm=5M+%b8Q23uJdPk|DhFR`&V0{le?(G@#gFB3LZHB-0=9li8^m0uPva z*{`qwIPkVTX7)BQu98PW`qL+jQcAgOp;i!V(Nlt%clO9C=4HZxQ1l&bYiH%H82B3le`DZp4E(Q&ff-1jtN8n0 z;s4hB_5HhdqKCHmsaO%80&IZq>=g)5q*TTWK$CL6Oxib-p{}gsAWQu=NUWLft(fyaWLpRJzqUPCxE*@p*<-0oL|t!$N#`>?Vq&T zlCd?T_VeHEVBG8I8T+)5R;JLL+J9@U08T%5A$AVxJp#6%F~K^=0>QRKiQww<)1dG0 zeZ*#UF2QTF)t+FD7BS=vuqO7eljK5&9Ajd0^uc5}RaQx`)zT2ynE9RHe_~T%|G&eO z`R}-Y-yO8J{#8AYcKyTuKLNu(k@Po~{;7$76(@h|ja1j)y81I#{O=ME|0j%T7+SJX za$~crOfjbY#eeJJZw&m6fxj{EHwOO3z~3178v}o1;BO54|2qc$S;_y+Y5Y?Yf7j{% zo2}FTKb=o-Ggwl+Tb2d2qSNNaa@^8ltP9G|C{qgI6iWPbl_RW9PYx%#y|CKLo z<^Pp0ZRP)6zuM~mH&{{k9Pi-k^xazj1}nG<|GD-u`8W9A==`rZ|Hl6RE=OUzqRhO^ z-An%s{=cFB|JC~B?D?P8|37|lZTcTR{y)e6MB@Lt_tEx`30vxI=WbE>m-M}_NpVv@ z69wL$dBo(|*y9A-jX5?TM7d^wLO$bM1Y@l`lj*IS3>GcwaJpw-IMtv7fgxrvrHO&M z4_YGgAp_v}FcHDelr2EE#Gc@S3xh!C-f)6LcPT@SOdU+>&4GPVCh~b-DQfh|hX(x) zAkXRu(WU0l)z=ETqzxndp5KOm{tX*~L)P0sOfs0pFJp+=@yeqq|wgty>5ub$3_Tc&i8Dh<{CE9zIDYoR(fv(a|#%gj0V&8?M~y zPB>q8CNpKCG{RZI$V5q7$_Ym{sXHVN??yOgl|8`qaaV$ESEe(mzDb1t-))!9MP|^y zg0|zf8)k4biDFwFb4atJcuVF0Nc`qN>b&;mK)A4vwr{-cAlMLZN8~eO2SJXA;sr&6 zV4N1k|J^p-Jl_gl{tx!v1TM$t-y1Jfgpf!=Xt{|($kKhyAiJaxMR&^5oj3q*(EFnwwEm5>kspm6u-JPfNIa<<-!h#moNvZ(R@k+wALm?*G}`(NcR`ufCxhjD7) zzsR6i?k_3jcxzEWukcSxxy`WF+;KGx;U;jjZRct=qQf2uiH1J+dDMD z`EVx6`9Xtdd*%2%VAntzXDL3LU*W#mv5&=P_R|y#Dh(8$YwLHPi0oqtdc1KsPR`Sy zH)e@`?%!9ZW9F!FpS}AfC}`+@KDK9hsnI!i)Oq^K=>3W%Jrj8PiGEG!vRVzEUSCtJ zUjJ|5e=o1Z#)D{3mN@1_-Ls_EYeYP8w?|( zVjrKCF&%|X-}uIc>yO0g>y7X+yx5%6Ml z%lu&A#p;&%$H0r#Eh`rTFIKlK9t^x#-Lg0_@M3k#;>W-X>UOrA)g!B0C0}0WtQ=;~ z+JcqC{IE7+l#l;!faQ^v#FR2e64Yi0br52Tj%Wp!BJ zH(0;reMVV_ye}#1koPfV9rC`XtV7->m37Gbs6KmOwX{PnO;Z7>_>@${H^tLw+8g!G`*^ zr2A@R{TLN+Z-rX@7!{JgP`!SP>iOfYx-uTRMPEy!evCTvwXa6~7`0Dkt1--BDxbfA z7fa`36!2p9Y@DaSO9T9{ah?J%jruVPcxlv+QNT;1evATM8ueoo@Y1LsqktFqiNZCh z`f}iM?fR~!m4+dTjJY9~h8!DmZ&)V{>#AWLvT~q2s;pZ!w^CN;4cnq&8#QdZ zhHc8~p4qXsW^Kaqvp&H5v9@G=gO&4iiV3UR`aXkLUsBp5*2k27Fzb6t|CsejWx1I3 zRb@Pw^i17>ZZtRLP+4co3^n>K9ghJApQ!~C+o0e+N! z|Cn*O-aG3Te=)0p|Fe4dJD2_EpUWDy(Wx0mLs_f;fqMvKz7G6bmMXaa#`4(%jy(@V z(1C-y@b4k2zb>VpBd79oDvzYo4v03r6C$WjkS80XRD6T;iT4Btj;C#ENeAf(99L}U zO@A!t%JJN#W9Xc^I>PML&dKNvZSjoxqo?N6+>JANx}td)oweb)g4sM?7D3A$|7V=T znv3^@^hT>lw`<~eT6;`xDGc1j@39I-tP@hdhw!pGy`7IZzrn$p8))^+jJ=e|Tc*$Y7x8(kO zjrMWww;T7X`Z@xS4I;OO1pT!;q5zmeguVY%|KtX zzbHEEum^7oJ-DMfVEjjpFF8lhDXM0KS-i7{`~S+8a{tE`bwS;+%H2`+w4T_tAm4x6~|Rg&2h(@ zVp)eTkHmvIi1jnq!V!NS_JsSFHTT4GF6`pCUDH7Pe8@nKBg>cIW$t z{8sGLp8+_k>ja)YHb)FPz&~$<$CC z)CKcj;h1#M_l}req@qqzhl%!9XI7BdP|?roE}6tAMf86`SA{Os5X*h_O`rDoK7jkl z=s1v8E5tZe%qGxNnd0+XmMNnt$3$LTHu+LhE0M3y z=5SWrS&sKgI%D6Fi#eV)6wdd}sa7x>4QmVR_UYp#hI5(>#2b#32@Gd>Ti_=1%(zeQ z?~};7<3=1Wo*YjsUw7cR%Zn>ya8DDC$0lze_nrE1{5`8bX+K1azx}Dziiw9rtf4gs zPGRZGZQ#~LbZMw5$L)qKMyP!^j<-vaQMPkCj+eyTLE%V)Cf@*d{b;|qRVl!ru}e8VF2gbcFq92An3Q0aV&p20G~*e zVv{^9xmD8}-+Is)Yx{MT_-`18d&tUBfX8nWw^Odzbm1XnIryl_85)2u&z+9Xl+2LK zpP`9Evwg7laev8gSr%GmABq?IhD#p!dZIUQ_S=rP(UMe0KjE`10&9px8o! z;Qr-MNl5SpVqG>5Z&!FpKB~SZuLCFHS%s4&9c$ZB?@tzZW5GblaQ#74)2IzDSlw1) z{CYCY9+Qt+-g|1|9_2|xHCCV|16G;DO%J96eV}RYuSmtx^<@*@uz`_K2h< z;gKZpX>^Ly$6z{W*nP4z?NQ2XA1``!QY-rWXd8KG*Qs=(eLqU21LV7t2h)2dw)DRyarzO|$v9e$<9;c|z#XcZKcnR>e~%Nc z-wUO8zlO{A-JXS92RKr4ZKk|^yJqx!jW-?sY`%Q7aW=`W4yIk&ER`R_5#)4X1Z^4< zEl2OD;`dUxPy0!wE#){4@xEd><;QRm7p8%_DG&&e4)Rr)z}uk710} zSSGpprj?=s?uW{Eh?F?Z9z|TO7QmVIfs*3Sr%2eKS=i&{BB-5`s(5CC}qm51SO|)lt(U$GtaJ2DjO!8X?(>*_* z2whh_H%1#GXylFQik4GnCaWYz(%Guh$?3H-QaVovqp4Fak}s|qDcVW%sS#48B`%HS zzp9++qD|fDMPw{byfTW`-N7`Xe1!bU`kr)ZfUB@WCZoj%>d+Uf5-D|-QRJe6U4MC7 z%>Zl_uY%{iOv~^C?7LV6uf;B?^-LLk^YbH$p4I{RLEex9a0uX~q72=Ml;46@KxJF+qk5RQ~2&DH|vscmCpd8Ht`%@3~ ziEr}{r~_cjj_zc?UoL73HiKTplj)wR=qluWydsT!6yi}hq}RU6CG@E$dIt7Z)8CWO zurBBT#Lzyqj5r$Y5*|TpDxS5ZEHEQI3-UfXq(a{tols;#-f!FfkeZc-WCqlOdcjY! z^SvK2g}n3HydyK+cadF?_gVg3@_Efgau4$Mn0$uJv3WqWrpoBt9JnL1+eh*Y@`mhk zBWr?Hs4vv*w~VtH3(9JUGo&w8y`-3`Q%3ee-FB_)My{7ukw&gEx@yEL1?pZ*EIehj z#(FeS9sP=QWHj{i4$^h{MdArQXWE=0>9Y?IOYmc$af@u7zk<96 zKdN(|6MHWkqURx_5s!<=)}F0NDfsD>SwS2I-&XVh8_P~Lq(`coVmIXV+fzqIsq~jl z1D}&NsL+?K_Y0k%tbVO)NmaTwx;$G(Z9FQ7Y20KK1hM%9e<3r@u0%K8Wc1JOXTB;E)rf29n__57giIVo+3Dj9kRc~6nyVJEMmVC(Own~MyqMM%-?lxpM#_sRsDKNLd4RPd@JJ$DYVpO%YmL*98=@#OTevuK=~44Zs8 zPu6tYjAWiN{B_X-GJJ{**}2NFZHG@J_HIkG670KLR!tRnNi1Uos zE)vu89XSOtTx#Y=hLx9*0@M#?MRVUjIAai?lRoN z?}^}C^^ItN&wDQglsfzwnF@JLeO965g_p@Ah+*scBWO|le$pB2r!2dLTuOt<4e)by z=xfv{y9dGG|LxZw=!5-Rg#+Y0e!mJS`z_-LYk>R=ZSb#{r-B!JKvr51r%#*;o}1T5 zSOwg5$Ex7w@;dfB;*Q>~g4C*t1OaY-saWXJsg!t4li@z|`=di2-jb11W%xthe6;lN zeKN!W?*BNo1vNjWAQnzgSM)ei_#~6NP*#WMnMl`jEg1oEj#GbvhPH7fDiEjh(vL`G zkP(?ZLxykDpUC^oO~nzwTZh%4yA@3p_rNA*f(lMrlZ99erehAGg2RQ#+fjyRb&f!F zcS}*Zy$ttP>5HPK{Xs^6R~$Ge+)Yry9U;!j(r!Z&CjUW8q26xgpHi%O{sT!M&VKiM zlJ6~Fqc3*wJJF_4a;e!(6fs$b8$C@R-47o^`yl@H{jU-ex)PZ{Jn?6rk%hWI32Zig z{zi^=c_ciAyu+_nlk%uoX%^JO;!P^_UFS`T7ZCHR_*$|kyCYc*G1N>eC!36X$ViAS z=)*g5XyR^i4RGJycgYQT1}UBn{qWTZ@_qAT(iGZj!|-)PxLZUn!87ve!$dOi>u&<% zJPsUJu8_K@&;&@ge5;|jJa(BdJOJ)!{1un6z06-&xKhNOr_B_qwu{&@ZM5+CkciDR zy9=pTMZ7CfL>zh)6T6=_f+DTq5U%Y zz!``vy?WZ=^J*0$>uyzFle4ZS~i5JGfJU+04qDFDzdr;&p*jgne*+F-!Lt*+5f3)FCvEdu#5%!?rMtd~c!$d`D?_EvDC6T?%iR95fI9elaqKlBlpd`4 z!Zl#;N&j3Y9;)iYZL0dhUZ?x#i%f&mf)+{B5jAr4(53Xyc~K)r)xsSlH${z{y5EI* zpAa>2?%`3iTq5ehs;4H@@Xbuj{G8QmOl$N+{rKQ}8hHU{=d$$NGIPMnYD`5^giT{ZJIMbs@)2I}*{! z=(!xzhaV8WYtQlJ)7p5{6Y%kCcxlB&t#@H+5_R@o^XLMI7I=h_o7E%YBv{)TLco zi5fHf_dwcoVLP5)_;eEe?C^p6KbA0;_S|)bV_A_uHA&g@Pwnd*Dc;|>b!s@?S-y$e zY;+C62g7f2931C^2aT)ZxNyoWJZiHJ_uo9s4$mGg-v74G4C5Om0#Dz1uooUPZxYAH z+qTDk-r~6<^OpZX?H+jZ^w9U&=x1mk#~0pgM~z2_^;~2=61{CN*8h@i$AmV@yZ&51 zWM+7QE@167s)i~W>=)7b#TyVypL#rq8bpbG5?A@qZd=4YX?Dw*_W#ipGaFN#F?2kU zay<8EZ|dqaRm9a=bhzNbvCi>lWNmFA$19d?CCw&@`$aQ!bw~)Dq00PB)L3B^r=mEusJrHX29_pm$BGvTOE%-`993k zdE#BQXPoBa?RV$!^h?`9u_t=Z_el)rM&M#i3D>;&5o?jvyG|UZ#GgaAhO`!S@vQ>1 z0jqMnJ?sx^j`F}yr3 zqPjNX{zk`{(P*b!-1n$0(?oBp#65&;p8#q9yZt%$y3=xn#RzfFq3xi7B*|Z_w>3Lr zNIOGupTWMVgh->ryeBkgD&l=ae0YJ6ko;cE`&*+IYOOsRt7XrVe6=b;Mz3t}6>KND z6RC&a+_u1LGX_d@2M@yA19b3|x9uhNo9wX9&xLsP&&3iOw*;i$7|yGYkCF_j)khD0 zMdHu8%OouqEX=T@OK|kNNXg8?A>>=&0=&vQP@;3{B+2%6!Hzn!C0&;NA*;HN#uw*} zli2BZr@O}Yz$&eKNp5}`MuRS@VUuDFiLuQL`aOpr{PT)QRh%DvwciO19Vjz-YZ6AU zc0hvm(Ba0jFGkYRyh_E^57o(jT_WhmZ<~nLw5=&|Zb6jhz9t9OyibX{GLNdAXh$oJ zI>=9*m_*HnSyG>2L*yH?`qSKV_ViW{2l=sw+BA8z2VL9FN4{$1Gje9eVk+?ple-OG zOZKmbpmavGd|UJ9ifb{EG`KKY{`y;xaC>$rRgVal2U&ZdPgcJ4oWTP5<5w|yj^ zHa{V4H%-O*Z5$;rhqS0;Cn+8`5KF=m&FE`$1N`Q0H_4UovDCk`20dD@A}QbELLWz` zqMs2LOped;r|!$Apg*+fuPAdi0=|%zDX(-y23NG)K~DqsGX65{zgY zwV8C{0T;OMR)zc>Dl)DSXj-&^s@Mcc}S63$z^4w|6Z? zb{030nLTL96A5U@%a>>q;ByI4C?M@S+A~c?%PtQ^)u*e_OVCpXe!defI;!9MN598seoS(tWkuPe?{dGgRX2W*|hH&Iskc_WUeH8bTd&F5=~N$SPqL01)Y9CTtct=}YT`6wY|I%sVT z6{_C7F5@fMpZ8Ls)e{O8zd@U?98gWdRjtT1(B`L4eJ7_6M3T#(EBl%jl3wxyq`#w# zuKsY7Bsmc>9CUr8(Q&d`=P`K>d3%jpPlk5;LIy+L2$=)vIJ}bU`YoGU65H}x!gT$Z zPpgF1J5(ss^*=s2rmqjG<+}cI)>cL97IPF^!A96!M^5zpt#}7`(emG<+iNKq2^w6j z$9Iy_D+Klwpbk5|Cb}zj5dXO{T2hijwwa$L&7m!_{V$LJxC1i+@}7iyKF&OPL7D^i zT)kyv(TA@j1^l%BIEJ|Is3gVU$Fh|s3ENytib3zMl5S9>ZC0TQsOO|TD(OM;D6|>& z1iY8OMD{hwXfd?=^%Mgp`EW^GhHO%+`MeYfuAFEXyjC^Qf> zY3AHwl7AuuZ2|2ZQT>XnjNXb8z|X=Dd1TJ>BPbN~QMtusGNz6orfq)=IY!R!$VHAo*O@da#7%j(F1&|8-hA+I0Y z-Men$Pp>$MNF~Z$uv5YI0iveXqP;WvWE=*(Y_kg1t8fw6K7dPd9m)v#j0}N` z%Z}-2^ZiQH7PNfIAWifUet#+kjchvBQ7CkSy;{)eN5j<>Q&g)^AJFm()PE@2Z25|^ z!KcgPapZvcQ`8G|^#0#5GvN+~LDobi zt%`U+oSOb075WQRDD2r{v(nOxB}eOs0@Bm8JcJ&38-#&VMU8CNXN^!gSH#upqJ-;# zBA)#)Ksd2n#GZ!JgxPyUT;xAgXn#h;=u#KqR;Gx*2CE7qABi~Eq*UbJmhQihFI^g8}+U^!=BFc_FiP8Bd{8WkS-zj3c!tp>E zaZPjO-?`ijE+>1Ji1>JU7iu0dmZ!h{f+)5#C#d9oQjPj(0qaO2gX5Tbcv|ksq zl=>7%czQuQf9j`pp5yi=a?+u_9uAyqg<}in3Qg~H#f~ROg*Q2$fsH>1G!VR94VlSO#_5^VxLtRHKz}vc{U`%rK&9w|WY%Ui#B#k*A5jPhVmC zHdDIPuPypE-U`nLd^@l$x&YW~S~q$>?Wv)V@2^YCww>U(+(L^+?!3)0+0~K`9C3%^ z9p78f4SG2otM_X`zjVpvxX*z~(xG1k$1gJTNYIw%ocrMMa$+(}tP`iN-t^moY~Fv? z9k8dnO0{`kJ(=5|nhz59o_>DNr<+>BeWvhdyGo5N@|p23a6>=O{p@MZkha_=?rDGO zXD<2)cGIV~7KwfqJRF~9?js+_-s?D)(*<|0Ng%102GQGlJ@L+&56S4}qZBVI;GV3? z`(&PArLgt#!l?#%M0&EXLMZXVx8CLuf=v`I%e?U`_d8_2PG^Nmqv?2YbTwJ#?@MOx z?1ekls?)zSVRlntFuUteItpPb}1-FjgqKUOxh z_EmCAF^Ed;?;dDA+mqMr9ohyr8frvBylv^3bK|kh`XFg?NR1wx>xeghs31=d_z+pm zD10XAC;7E7pWO2qg{Q5%O)j|Bk@HP@;rxv)2s|S+^N}g8Y2TXT*u$oHz|^)J7q>9N zF*Wl!?zT}6KQc_=_*+(UTr@b3;}$9v=u>Vb$3{Kxp)YG&Q0CL|RU(S$)sf?yUsKRt zCq0hG2PdQBM8w_YhS+e@BA)lB95-w)nY9-V?{lB0 z;~QT1@P~UGpBdwgH|~LbeQ4i?{o!Bh0}uQrV$H}7yl+hMvBg#rU5?kgPr}#lw&PeY zWB}H78pv^%NL~Ec)RyB@lfI#r9nx_XY4xlr2j&R&?Oi+PwCT5{H&I~xeh_*Yshugef zKau9gci>}%X~aP4vvvT-{SWI=y({8=ciHH25&&~L8-E(wkJvhZx&#g6=~v@*Y2yjD z9KQ;sp+)F%qbQw7zcf|=>*23yv`NZ|?7_76b7)?BLh`fyL zgm?EGjMKYKA@uWAbnKct4vP7hzWK^j>0{Wt`g9>Q{Z^cdH0*aI{yJ**r3uc?(iT;b z_>bEApII zekkdA2I>>wj`z*^kfHh{5SQQGibiyo2->fnqn+p7aq9N*C~>)UiFv)fPJ(&rp+`_CuGo#MI8QPmfuk#lp-x96lbwCnIe+(y#2fidX$?(Z) zoiPF0{kTidj6pMgq_gzocVjd1hn`Ds2YCG0*%^BMY|`gLU%GT>QHINtQ5OmHu|pmF zG7iVvSmgo!V)cYX&b=tCf9sAt_L`PvZg+96aISJo(E#0EA2X5p!lWuuDm#Cg9MvL$JQT<)P zq&#o~D)^W~KI9n@)#dKkJZ3b_b$&s_y`#yGIIBK7Wu}du~?&ZRt z@v(PJ@zGO=dU#x$i9CJfjWQJQ)b(HBhW^jm`r$_{FY~hIxH@6iK^oltL{p3(c#FRk zE!8r>i?@rv&qXfziH7ud<2E7VHlj!SgE-!!v0JFL7Jmm?`lBfsb5?x+^6{BtL{_(e z+hiS8r`2gr9NQZ8qc?H~bKGjiPc%X*`fOp+0@-XA^A0zTBwEGdyPFN|L6_lrEyi%Y zMg#4J>$MwbI$W>mKNG{kIsb4&OHk!yCJan#-f3AD(R`>M0N8gy$>u+I2OI zJ6MSNtKC2YoUhbnX+h=49P|s*aZlQXVb@QhjvLm~4{QGr_1#Os36D1v^;*X-2zRp= z{ah*Qf+0_^M=&#xXYCI5yj7iYt!mpi%v;@M4Fq z_>%THa#-I2yC<6BH<@iw^PyI_ZsdGC>FY((cuQa5#na)qd7%ldG3qIl0pI-h)6w`k zEx}za40qIXLN0|`g7?;N9BZ$EMm}mU6mMCIC!On#V#nzS=5v?euwMewIoL)RS#ki` zWy3v!?RpBMj_z0Fyo_gaNftR z!qVMkXv=w5Jjb||&}Ks($?4~Xiv~IfAKJ-L>L@+jb+{ESewc!mffmyQ9T&4{g<{>$ zu6W?=(b#&t92qM0$mmshsO*TSQ(Adeq6jZhzufH80*~k}>Y5RkT43X&qTVqW-4bi} zzKdW@h!0(8i6!5&InM5pn}4 z0+iaeNGeBJN^N_lqa1abDB8ff2-mNphG=`@AVcxpan-b7oM08r`)bhLaJ=rd8pku> zeg2aN#QlVZxS^jBgFJE972^Iw{+VF>c8cg{@0)PE+o>`4bN7>(rS4rdOQwl7u5Cx( zwYkc5oVv9gO?TFzOvg=lG>MirYDbxlvl%gomOX1nnU3oeXG?Dvwx>+T&AB#_Zu+B3 znU1^Y=}2=^D!7g-JU5=+7;=y>9rvWKHl15(#C2S$qcv5Wui!c^*kc6Mh`qyg+?_c$ z4wpKtXJ`0O&~C={+6^?FalNMVK5?dJU?;<#%m&u^w1F<8^|}nS8?D!Fu%4&&nhw_a zw1MuU^|}wV8?D!Fpy^l)!r1_-yuxL6=ZtRh5PRjrsFPm_M%gr?-Qou4EB4{ zz0MB_({WGkbfNa;30%i{pC35DPxDGDi*wcUCuIJd2VBSb?(Id_SF2N|<2LF~r;#(N zxsIC=VMEvHz2G|TfcH@9bhL!)xXmRgWSgU?r&g)wk*oqyA02p5LCk6^2-8znZZ@YE zEJeN6cf20;F&1@}RBlLH*oyjV*eb=H< z1^Jp&$^Cb@)tufNDEgnYNsopZh&r*Xr4b!mD(XicwO+Kxa#3%#%QvNUtwp`*XIw%a zeG&Ce^V_=g+)q)zY{3KQaJbio>94AM8#;fSsCRldbECcdMIAKAV*wqZE$X8~dte{$ zqo@J9P5nmR%oFugWRxy_*i+P5=isiK5J%A`=rvle*BZ8aqvT0c65NiLYx&uho(pTw zu}N=RIxSq(bPfB}zt)#PZ_;|bncB&lYP;re?I!W}qNjZGI4-vfpe4UVeHwFgF%8ca zb!$d$7!CL+YFqmrKhV}VQNMJ5^b`G7YMIHQ-;iaDsDt{}mLR8>qD{ke!yT|6IbPIF zFSZWAnStV*)o>i}h?|JJDK(n6Z8`EhCu*@pNA<8L6*Zb+n!~O%-X2@UC;B25gwVXK?^t+*Z_&8uu6DE|28;HaApRqb~rb|W{ ztg9QY4W^ohNv+>cw^D^Q^Fga8=(y)aVH2#G6XC_2H&5E4?yzQ_spW!i7fDg!p0DUr z=|ZWl-sFqfU@ug=O4GO7q({Lz{8O(n(zS2SruTyN`8!*QRM((1{T|@$a~es<#kI=t zf^rLXJV!dy@1-Ax_3(fX1<2pZL7}bbfzQwBfkRsPlkZao;nbez(AG|?$itTIxXvE- zLkhN&8SUJ0REwFoe3Ca=eykWZv)GD^RvscDdhR%7z8^M=4JWY+H=qY=bI`p0CgjFy zcRVeA6kdGd6~WtzP=0Gov+}v$dck;tyPQZzWf}(s570+jUYlX_F71&V^pSMmT%0#+ z6gmz1sA2v5d)H25VD0n+)=no%w1lZyt9lpgujG2LY49Kv9digR1%21LH=qKnwFVI{$Lr?bBsuT5Nw{`b>e|jkD%4^5I_fFT{#{Eox)yQnbQ&ES;`OimX zGvc|=6DluIDrhU_)7cij?*MJZd_L;40hxqFa+_=Cn_$~JUlFsBtTe|ppwXDksc#37 zP3m}V(@aelo4ifuHa+4;W7Rg5h}jG;JdN&^x8gRxUKn9(|CQV(IolBjE0??0ABDSbN}0ft?fs<^AyT)`PKiPLYuP_5qr1=7Hm< zU6d9|W@E#H-_fX;Txt5mAUvdS6FN}WQ}IUqIg)*L$AxLO#AvNE_Fel8#oL6@>i42{ z`_Unsj=HAD*AHJC&7@=3H{t7E+h5fru0YgurOj)I>LU?1%**D&=53_>oz4~ZVYE@~ zH0~!S+KaAvp2zVJJ6n2WgZMj(&5xe+`y$N!7fZuvlV+lhdkMIWrid42mJ!tgQI~CK zX+SM@h}!C%2BznHM9q~s%Za)T7PZ(2TR*DaTGVJCu9XpqGOt9?qm8sht=F$?06o`E z)PM=)Hnig$Q5!D3=1RNiikk6Jxj!v*6Sd^;4gK(RFHwJ$ALxgx9YyTu6OC@16gAg_ z*_z~Lim1ihV4v^R08yh&2mDrv=NfC^%|4>0+q?ES@_8a^JzE=1v|cXebur(m@Ea>? zL(7&M$+1JCX4JVGhUZM4NSGXHh~@Jl@Ui>v`1^BKwUM}OehL59aoBD64(QDd{?27X zn}+EP?H#U8Nw#?6+MTswf_zHyymciUuM3@$JZ-{YLzdog@Ra18IE3RPvz*aMtzj8g zsza&fdS^5yp(_0&;F^j^+V z8@Zjw&=3!YcdOBXSvRb%}pJn;^p zhrKyI{-hPXaBT|5{gVgK=(*x^amjEhEgj#Arxy(OrPij`d0WH{45PlA#Ah@9btLV) z?so?BdFj_ux<|7!f5vH40DboKFvoxFo#|YexNkGK2GcQ)Ju$Pl*`ZILj}!H{NA_#- z^6EUEejqZITnb#wagQrhq5mp^<6hCx!jq-q`>DVM0T-SQTo7>K7`R~I!ZC2cz=dPr zf`JRizy;p>yv}0-E*Q9Q3|ug9;q3xkFmNF(PT+!p3&+3(0~gBDfeQvM90L~&TsQ_U z2)J+zTo7>K7`O<)g=65N04^LiY?q%sRw||hiRnjzE(nR`qJ5A1A?W^;5N^LUEel<| z;KQ-5z6SmsAdV*u>tt}v9W*;$tdm`m)>u7GtP`D&{c)Ra;_rP;H74WVF5>TrYrA-1 z$<_zF9`5!E#ZyYWIj$v<_|;rX-fz>chvS57bzTql8H@0!Eqgc)TkneVpNnH=+@(>t z^{(zbHoL<;aNV|H|AOP+zW1NA@BM9;zwPpm7^`C(BJuEjTNG@}jF1K6Uj@tgxM7jv zj;|Yu_vem&Ziibn6~DU}R6ZCFukFjnjW5@9aKbb@j^jT*LTlqaInEj!ja<{jb=QzC z&5`Q?aqZOaV4SoKtUp*;X1@0njZTW==f&}%*!;C8FV~@iA3m*jh2y~HGqHJO6K>xt z-Wqr6ZOn1HjRbeTKAhv5!76ygd>O|*UmruQD#bOM*JuOe_D1}U<)UL_h0V)kh8W!&s!q?#A#Y5qb~M=^uVVbq@=Riu)eOq ze^SfjYv|NwUwmOiNYa+Prr2PXBUZ(JN$F8N@Un};aHx|k$#~aryf8w7i#Pu}_pVPg&x*i$FR~Oj z7groCoEwbe5|@)xO}loVw9E^SEyyD~EXEstUh075qgzssn6rjX&#dsR&t{Yk|6`~% zzB8_=8b|y0>}q6ZR*n`ZT&ez2!N}aIlJPzUQUqx$tEt54udfG-8UM!=T>UkZGUfG-8U6!;neUkZFF@HGOy z6!=o$YXp2L@Fl?42>4RqOMtH-@TI_40elUCF9p5=@a+zKDey(W_aN}4z!w4EMBqz- zF9yDez?TAF415!TF9p6B_$C2g0(>#>O#;3I_+sFj1bhkb#lSZS_+|iK41AM-uK;{8 z@J;&LzJJ^Izti&z>m>^7CE?W_9m8Yo!sv!)GmyN+{;pHg{Au^Jv&f`EGx4LJD{W<0 zfvVNkCC03?p+?{JaQvBji5&;@q4VWKv3-2Yr1KYA(h>a}uyl-hlKRYiQn|zv7f8n@ zJv3fNG=?n3jlE?_%U!Az{yGtO@I=3)-A5V=-CsuH$t#1C%)Y9il@;MwUJ#Z9YbOe8 zC$#OQb^@%OD6E~($!{i!uy&%bcESV39!P|>6NR-CZejE}5!Ox=)=s#;LHnfB<1}dP zR4441*gwff<0grh``}0SZIV9Qhmzb0Ay}&ImbAg>qT;KWS>-3PE#mB=-Im z^7py^J8u7-m;cVof7f0A1=d{`mskmQ>5&-L?MY!Fjmh5E;rP{c-z2sMhqX9vVL2md zzkd-KGIb7q(`0y3iibXJ?LPrKRCG%^;UcBcGtDrp)f2<_Os7$eHSvU*#}b(i06l;z z8}~_M`_^oom+81-1C&Eqd5~@hX`jf@qng~F z{g?flufV zevVJNZb$*!`g8%}sJBN@9>>57LEIdJe+1=m%>K*%t&9iK;QR&P!tz0R95a7V9*>`u zv&P<7!fcf3oUhWJH1NZ*(m%(_aw)S>#=|iyht&&9XXUVZWLWP^BNNefAdP*t`=9XY z1~}nAxJ|7MV_03+xAi})P4g_e%b^_1%2L(|$I80m`2S{`W^SJRAJV4B8noAHeIKH2 z*^9Tehs#T{@~IZbx@&c*MUxx6&wLB(Lk%wX&EoG-zLQB$Jktr zlK$l!r%pOXQu-V4`nfvuo1$o)_$&Yx>M_`$dK<`#>+^z7T<;Ug!u4fA47ff9hz-}r z1~H@hn1Ktb=d#Cjoe6uFfz1cXI}13jzjHyHC&c@h7_Pr_f#Lc)7Z_H4*Ua+f7(n3Z#)|2BRWl`Dx|N1)@SbF`P3kz>l$`sq~Ke`q#aosi+^Gt{fqzB!{0ve|E>=l@4k_km_I@v;T)44I~~c~ zouAReQE>jOVRMpHTZtmE49`^YRXlrLhwdRb>*qs~G%G~~zqFR&b17GZ_^cXKI#Gsu z&6A+ezCY1%I431I!-gz!`ic@E@B7TRisv(`(X;+Ce6eS8M#wD{oX|&xw{%%2ggewB z1*G>e?1M61LZZ++S>3%hteB+BEuFM$|Jykln@>#|! z!1UbH?(vBNQ5cRPc3(!RJyx!Mw35E`8*Tn|3Z0 z9&E2hpFVRg2)H067X)08k_!SZNXZ2O7o_BZfD2M`LBK^&a>2kws^o%!i$ci-0T-g= zf`AKAazVg_D7hfuLX=z(a3M-A2)Ga>7Xi3XB^L#7p-L_a;6jvK{IzLqK6Vo=r#Y$&v;H`o^@|P(NK6A$EyDLz3Nf$EZE{q9{-=UmVi^(y-d)nSY z?#&X(I2eo0WF7{eSILQLXMCaE8npJyGtwW%$xzMVXoPhMse9^-&v#ve@-v>1!YXHM z*!3_X9j_71)-t@-o1$H-kHa_oaE6!K6Xf`LJ&CDt#@4Q1QROc?;#upAPj0P31uLo) zN1Ms;^ph(1cRwA)?oKkiMo__bi^mD(17x_%vtMX%k{Wt2NQM_>d_m*P9FVHH48It1 zAFUm^4XO8*VF$ZYXzTBER0{LOxh}D&$&9BcV}uNk`Qw64mw!ZuZU6Zk1oIJr`G~Oj z$k8E;Ec^6|B-p^&>!yk1EXpF|A@A&mmx)={5waNOHAO`}>G*0rDT6tvdfF$lsZ>TP zVIF*TuY%lO*M=CvxnRBa){#>~y%n)=9$9Lv3hkx)LRvfq&V3tFO?GR(6$TE2v(Fs9 zkrQ*Q(H8J|Wx_M!S+@#}g}Ktp58lFFDo61!SEiXABJS~5(Oih_(eagJ?T=@u8>D~u zB9POwz9Utzf4@FoVg9`utpq=ViY{c7CBq#T;D6*VA3^_09hx*2&Pjj#UPyXWg|y+k zvxf68@I}BEDfuGci2o;Uj%%Sk}m?jNXZugUqQ(i1K$iKUj%#=O1=pA z5+z>*e2J1T0=`7a7Xe?QKv|qU5UpzC_9QZ~Kb< z`EUFFH+X*k|M1MNdwl~LOiLzuCC>CCmZRFV>*Q;`GmW*4M!B)CNO86^)dL+dSyE0O z=Q`6lW7i1jaPP;A_s(=&Q#Hk{k17<_mUQ2wqiD;|E5sVoTmFtk_7e-pj(5&<=qx96 z`SKSMS>#NAH0p$QFR38WmCkhPjGcn&ygJgog^UunbLkF0Rp>Hf8BNVOtMDxPLkxS$ zsD*WBqIa-0zb4jO>xF zB5Kw$diX#oahcwa44MdM#Wt%U$D2J+>>CMZ`)*UA?KNI!d>;mP@QhNSTP6(=+>ngs zOs*mWru`7IAzgdLHzIjF9K9SPqnc4Kh)(G;bY-%PZatPs5(<;i2{^a+)vQCrGxI7^ zfK6)o8ZyqH0L_HFZ~ey;-{)UZ2>3kG`nO{J+uz7>gp3CH^;U!qQ^EcdWK<*RiIshl z3a$g6bIo0aC5P&mMx!R0P0>~17n>ufNund#ob;K^5wrkrKt^rz*&IO)Y>uH33n`l; z=+4^f=;p2@Hb+qX!G$PBHHys__8$s<4b@qQt~Ch7b*D?;ER-e z6~LFR0T|zO;ER=f|F-Yn_Wf`9{2ra&jBIWFi}*tOYImGMR6l$ndGP$IUyLE&jyxr2 z;Q3vBK~8+au8}$L{Lb>bO41%2BKKe%&RO}CG+Q4-KqJr}-bJK?!6ZH=v`zR-eEprs zDNFEk`##zAb}P~9D5D<}Q^~>1^TeSMoSCk_iBz`ECjq6-bY)9hGI4w{*#z^;l-WNN zpWLg-$REx$$9tz@dqN#qSoP26DVVban6ogOvyRsN5Te&rv;7cydzw9JT=A9dhtLJn zx1fzikJx?))hoJ$#tuBo_CsjX3(ruX{Tc-OA+)$(2`XNQ5$uQ1E;fIV`{{hPw?pSg ztKx2+GAZnbQ0>EYXoy^{fc+4R zyHK@RF53^G+mFsh#~XhpupdHGuW6ukxZeo&Lul-NTj52j3WfcUe>VRD7X@%(`&5hz z0WNHxig6*ph3!)@E(Ex+eJaL<02iXow6u4w4xe(wYD7g^e!uF{c z7Xn<^J{99afD7BFVq6GtVf$2!3jr=j$%OzHq~xLiE?CLsZ@c_$mw)K<@?ZTKnF)v4 zxdu66_S?+q5q)sR&Y>JXIBJWJXp84IWOnwzOZq+Mzh&>K493M#5gcozMB<5Y)A;wo z8BfCT^_V97w_xYpi}1%;dpQnh?uHj?m2v#}?P#25){Xzpn{(I@zj!*5;|NlTs++oU zZ0NcNt;$@)af@A_gdfwzZ~9L5Sg$aiD}Hkq7`BvL>L7j}J!1TA@~xNneKc^Pz=h`p zE)=+M3|uI1;TX73;KJhpE)=+M3|uI1;omI+7YbYus}tZtfeXjLg#s6jfeQsLnArdq z3S2k_E(Ex63|t6s;TX6mfD6aKMF1`w0~Z8bI0h~VxNzLCT~>F?Myvja-*>w=jzTM6 z26LMe)>%TUTcS^L&{q+=S@ijCl_TkD8CLJ-pX#J?ULU$OM68pJ?`&z@_4bs--|2`u zjn)yr&79sim^y{5;&pPXb0jrya)j5(Wv>Vtb>b~=YkDe>c8iMV_0Z?&9J;Z~7mj0w zOrZOY>+^D(nwZjxQQ}!2F6$c8J$q;Jbe%pKBv)sCeQbaG9@PJT=DzoLO!&_^Cj3`# z7mbnLbk8F349~@PCeyYf+VC;q(5wE`OCp|GG3J{#eRa^Dr#r~rlP<63a(uA!I$|+Y zJTs*Az;lW_s^YjeVCh*Qzp;o>+sUYPoHz!iUPweb8y51s6FNLc*9^tG@!SVYr`wY? zMV}85)k`+zIE!?n9p;bb_z>JL@(X@5XXE7Y`xi(%g*bM->@k!Sr7z*>+bwQh`l`H3 z@4GHSFV>0aUMtd3h~?k0?!U@B`(OQ;`tP{@Vc#_m?AIGF_ZQgrCPpvLjll>12Yc@U zRYkJ3fga2OBPs%liJ&NE5P{x>Ip=`k98tua6Gp(SV8EOe1Hp`97J8RCfglDH3Fd$i z6ak5ES95Tk`|g^z{`=23_rLcsYt77OTV1uk+PijDch`5ysx}ikar4e(@H zI`Of-Mtu6i?m{8WOS*#&uXDYG zZrW^8|Ax@mP0>x8WmXS_otD#uZrZG|eFAtVjuyIUvx4=c=uhIyh_BGan-O0|e1$IF zjQBF*3qmJOd>Qctp%W**jQE1ki4$K&d?le1C%%mM%0eejd>QdYp%W**jQFC^i4$K& ze7Vqx6JJJrxzLFdUq*a|F8%=V1>(zvPMr7x@fEswf8qNEcj98a$yBPhJy>+geWMLMJ|cK7A{5cH=@PPHQJdYbP#r;`<*0 zqqP$kI&oS%FzJ z7fUzfHW8j&=)`ZH^g_MYv$@cTk0=+8&-Es7p%X70*M;NyziC_-&dY`CuK(6`S8%B- z=>1OleJB6Rdj{ioI>%e+#Kjt%*5afO9pXPLv^2~+>cNFhe8I<^(Bkn7E_C9P9KV45 zc2_QR;&l(!U`OY4hl5h(eus{ybKw6VLxv^=I||g*x$npH^4en5*JKCvKDXUS9q#6NOHE&txZziTi>=C*E)KVjO)t z0fkQd)0Vy1?DZ|N|CU*=DJhj%q~by+KBB^GIVT|xg-*QM6(hW&pN2vw-sIRMtab7= z3Z3`~+nwmO`YsBccy8m1*v~Npg-$$gX$)>1?~6hw-ecfLyneAi7S$)cp;0EbzoLgi zC(c7vd~k3hS?I(^pHuPqu5~4$6CZw>w0rU!MJK+%;VV9z)Ep|7femtP&qU=)}wJGQneG(?ICN{f@cH z>3da7=){{Q*-Eub>M@}ckH1zL%y0h$p%b6>svT5`_zFTN-f6~M`2Of62%Wf9;wCuf z@c@KQyiw!Bkl}Jg(N??iyAYMSOVL(WSnwVUz1wAE{E z7Ls23xuUJExwHvvFY{f|R_}}6BGt*xQ?%8)Fa8X3?4rkowz|XGJb7BpEU}lE9USb8 zcUOKCdx=@f&^1`<_!C82OybVlOcxE;4Zudx;rw zaU?EG%S9qCVlT1a0>nk^B^F$OxG0+ULcbLHMwV(?D<_NbmHgnJ&u|`5`|9O zDCsAbcvT98PTZiF9)EVfi7a&D9`{weP8l0X=)`wsX5dK2vLJNgeP6sq|6b!k=){k& zxQjP0?*^e0w;O&8Gge#zp%bsZb~*Z4B!JL~k2vFqn+_y{(24hZ{Y0*tm<>WFzVYk6 zu-Y0uCUoMq-D2h2XR|@*#0O~{Fmq=z2%Y$;xEc84)+-P?@$sQMF}PDC2%Wgif>7M> z{3HmS_|~s6c+tTZgid^KeLB-TwHFATxI^ho-2ddKq7#2MUd8()nM*<^-gGAMI?+%T zI`LJFGBEv4Srj^PJ*PKVbd-@qZo22ec<6q6siK>{RQxMk({oaE)7}=Da8mO_61wTs3MzK7em_a*rq9h( zu`J_vVL~^3ePbrfnv6J}<9j_c$aiN=Tb$O-Sr$?U9 z#Ia;B#Ck0iO&sgsJrb{dd#mWCht2T8LrG5*-Lx)u;)}#rXyO?0MdB+oag6vP@fDgl zMtqU@%38jh_{v(oocKCw`6BUEbmGJpi7#mRBJl++UnIUDbmGJpiLcPaG2)BFS7_qc z+0U(!_zF#&;42efp^0O}H;ni)EnkWF3Qe5g3&dAw;sjqHzKSlM_yX}&bn%7$E%fhy z)A;@W!rN?`LX^H0`bmFmxcY)*22oO4PciIQncf%oHpwp)WjCqAg`CD=LV2nwC}o=yI+_|A0{I`Ks_ z7eSzNA_|>&TWfnLQ6?FMPW;ODMCsF&dNeJJ=I^uLr$%~D0I{ID|7MX#T|-H zJkIV1#w@NW<_Nws<27cbO%QVghs?W}y>^G9n_gP}B-XimQPE91`}v~X&_`m9;Kz=t zv84BVMK^uCPbG{hpRVYpA0{u54fiW^1lJrt?dTq){B{a=tQ0HtI-I5Grq^26hZQZq zi#bB@1>!5#0G#*&@fB+TPJDs*iZuWyzCe7%8h{gDAijz&p7;XsRdn&h7l^N<<;#e# zy_PQ!UqvTQe1Z6iHGtp?#8<2V1YaP&VhzBFFA!g`2H?aOh_6@!2);mk#TtMUUm(6H zbmGKUBEDh`Aozw6U-8>1g0D<`#TtMUUnIU_4N&OcLjQ_*{;wRrmkc&R*2?=JbmCQA zLtsGI1rR#%6|e5V&l7t<=)|iWe+JH!(}hl4_3SJBY~uhzC*H;+3#9!oB%u>8-(JOv zmNk$>P8iWu#mbxkN$AASZ_I$nr^BPH5oq&!p zVIXwkRky7HKes0!bmAlH&4hzbUxCnx>&{bzk>)J%K7?Pty#^!aDZc^8jadlJ{u!!h zt7}iXk9C^UZ$r@BXW8`=c8%|+XsZLSWMh}oPsO_(ex|t|cj~!C{01O*@2=t%X89;O z@osI?5bM?v??bpt@Jn13KTo_5;VY|L!@w`fZvb+)$UWHSak!$b?zws@R;>O;(N@10 zUJdhJr7PO%)fOY=tQ*R20P@7!wWU!;%5MPj(Qh*(S5xIT0RMp(aRK6@Xx@nn5Et>D ziW3(gF5*3v-~z-&(YzBEATHwFj^M(Gi}(#d!G#eQMJG;NfVhbFRDuf-7xA7-Z~@|? zXx@nn5Et>DiW3(gF5*2ECoVu-6wNzvk%)`<4M4#~CNAPP00kGBxQO>uf=i)aNGD$C zm)|#D{?o_E@BSuLwt-=*g5Uc7S8q)`iYLr4R<4ihda3m+ zw*lw#NH=Kmsf_iVI-y6z_rALg%2+pV6{p}7BZK;f<|x3d;yF3;H% zG$|lZ{7yRi)Ul-H=it)xoAV1<#=3^=)~tV~zkDkdI_SuT!eEBzZ=dhd}a}`|5 zd_KDf?G*fcya%hgTVKIeH4wgM^p%YVOkz3KP1&R+SLN2GcI@22G0eqBg{NBH1M~JW z^!?_kl!+MCguQR~Nhvdb-)Lqxz(gr?Y)lyRn6p7CvtWB;#=}aYsOQn9QOtIJbEQmY z<51XdazrV!%*~p;UvH|E*_b<$m0Z+YDf7krBJ?T|s+2KU+=vzFYps-te(1^^-i}nt zlnFl%AIC*0Wp+3joDV(AQhJ{_RO4Hhixm z7yWbjP*(<)H56Ri-IWcm_C@KFhTb#ShKOAXHX7l<;?I;*uYKL}++lBhmYdrW z#q}rgX6#zxChjwxmOZf(L!kXIV8O6?~?NK69^oPr+>u>M?`ZBn7v8 z{}GOyS8-vRE`Hp-3>#4Eky1wOW6Va)-LGJ~W)>`4HBiBE?;Eiy{u7rZ$FB`#6 z`=uyl?oaB$%X(E;uE);m$z!S;DmZs)FW!q+Rd5~Wc0AV3T*2Sn?YPvrnSvKTX~b{r zb^Ir6Bemy!EX|bb4Vw?*>32&h__Jm#-)|bDw3|J9CZG0Vi-Nz-o5}k|=3~A2^ZBtB zj>`2tu5gp9QD?O9V^#O!9AB3XEP=Y`6sMf zPyD1lEV8wMQf6&z3pS~7em%2Cn6TS3^6RlPd5Kc+D5Xs652NwNn7Inp*O?!k=J)2C z*5#j{et+d$t_gNSVcWzV9(+o8StYInUZBOg_cs4I8(l}_|8`19+hlB4(N(G6zkWj= zJPZ`vxI%yKJg$O*M~|CI=Zyv{_22XM|5|{P(>NDT>BTGpWc8S zqC9i0?Pd8H<*Uh*XYM?>B!9PeV0uMO*o9Kh;a(#v_Ob2>h;K8MEgO~WI4+?md&Gt^ zPt=!&W_U7}A3<{aw+50P{UTYh#P{^<*FdtN`C{a$a@Z`Xyi`Z!$!Zk;A!qwll-{iH zWFgBV$C0-T zS=D+y*_I>STBpS>bsUlI#jLh#9HOLUu*P~eyHMwz!_hKtp#OI__HEiG2T$8Yj@DGB z=bMs_Rjy8Sd`I@ANe+(Qhq^f)By4=u&9RXlLxu zk#H>iw)BkkGbO7dquF)8!K~rDh48NYXWC0*!nW=_2|?vrv878Vu(cO`pk>}VIGa@& z-Zgy)<0_73(@U>_)wL~HiBq<$)SwRVvg93z%pJvSUM_*G>1QGN(P2aH^%7zSLYu6;fm*8Ny z(swlg)mb{dBHQ-lKAgE>%X%i9g?kGYLwK3d?07GFce1oId$%YFMl6$IY@ex6-FP&c z-}*L;{L~JnveE3EvnA_4)|kZ>{QyV%G+{|iE3x`*KESLfTjsQ+B&)yb1I&n)SohPJ zAV2>Ay6d$62^Mjm|IhE=XI0RW$bJ7Reib!^d0U?Xao?zulUdOU7ZiMXAmxhe7zIZc zb7Q+My;pE8!p>Lo@rWD`W@Vs4aqn2dJu2tpR^{m|`;;stx9>0I$!rGYD7ZvXPu7L! zDpA+w-i@e#_{@s7d_qi7Joc$6XBB4f zoaL*-p3UEjjSa@~%r(x^i77ESYsY8~H6ud(dnKao+G$rCJANwWtTdT5<$kws$(=Gf zI!@r8{9NWTc}qkw$C=aU{OxijsFPeQ$N>f-<$8( zRAB?DpHHo*%Ij9X0=KE3*EP&+WY9JIu;6mTzY_N-Z3f@Hdh)TSyYhQ&_QR)x#rb!) zLA>vaG-whs0X5kjc!>XZ$e133T}OA|V;A3npt*VY!0LGe>;2v7*p-Fc>4d#`=VG_~ z1$IbnVLp4%GX-a@zjAoMZXYXgU3aZ$8dH&f(?o*kw?A4p>aInr->k!Jk8f1U-?=QF z+kzBqZEVP=dxt7``opfaEhYq=5p5lfH05=(_raNqt@xeYWBK->520h(4sv4JSl&PV zK8%ta|X=m_wuQd3qHapvxevS9I)i8yq7 zLvEZ~f*m?soNw@p#TV%hplGF@eA=S!ynb#BTv;BE^{=<)*QS4fPqT}1-8I;s!GAPA z{?T=_t6pr+{HDtI{WJK6QR7;lCvH^UMO^><@l52+PT*f9SkAg6WhZ#DDIH&)skM{AqIvUK@>NIX zp4f=B_`KHfk8t-bUi_H4sq|=_q5MC=*Dh}sXN)T64>rm_%TmF=>)ggp+vXOWF)GgJ z{B37(_N}n%*ZG^Goq{tuiPvvAJGEt0_TO^OW{G1r%?kWg=)1q>+}nSL@5I_doCPZW z{X62b#Ia8PqAf8F#5fmNoM9`*xxiYTpn|pfK?Q4dg-TAK^IOGP!v*<4j3WhW?N{&$ z*d)e5!S&yMw(o;lmHrleAN8NelU)3(iwphu*JyA5EQS(^ zeg*5CJzZcA7v;6{vVyhtE11Sz!F;F8tJ?WalrNa?L_Gy(g$rHM#U57nof z6)x=L;(l>mn>Q5u>Cc?}rJVPyy{_=pmIs}B6s)aZ!8-Y*z#jU)!mA*k6xgp^r~WI* zC(1LRC@cOg^qq3f`+tn@Xsx2G`?S6*Sdaa-_@s4a!MNihRz$nMBR*-J`71vEj+msi ziWuhwdFHp}6Iy2~>jlx4E-v(=GT;5_dExK!tyZnD_pUv)w&CPSE?GUuV86 z@78|D+3u%L#Vg`tGmM>HnL2C*Ff9YZe-Jzdb%_ z+)>;p{q}*96STj9pkOM-sGNf7J`m$p+^e-;!8GnH z{?2?tzN7bPzdxVQxclWV8h5{Nq3_x&ey5n>1u>(I5#_ozw<|HGuCag@#GZ(ee~0fx ztmOamuYWTtxU*o~7S>bPhlMflhcTdxe{KI1Vx=SgeZLc!?+5YULL2h?;y<$=wCfOM zJc+qf%&CHp_P5Il#u+bIr-?aP%*~?A|7MQ9bGu)`x>3yCzwLR=BCwM3T~yflcdV&S zR2cZTJg;fjic0?%`tGlJUi&xsj>bX$T=#dxCyhIL#`yiuYc%d?9Q=Lnf5>-#%k!G{ z-3SwXsC{Rm;6mU1@8^Plhwp^{^8fkIoUaS4FBoHmTnhd8e>4V^{HV395Gx(=htIZ! z{ZrUK|Dzbteh(FU62y0A@m*WN+I<%a*4;Oyv;TqX?2Gt^{Z~5QssCZWmS{s~|D@8M zxTdpDqo5wKXQQBg1?%kh;5z$2l>HszejWQ2to^QCa9!+^QLxVb6Z*5VPe!>;^@HG} zZCBY}BCvL!jA8?|qkQid*F`^x{t}q}WjcHC#C7q#Uhop-#lDe(dK66UDBoYjb#1#$ zV68n0*4n9Ho$vCrcT4%Mtz6f|g?{|Cm-0Wtk0L#h&xIeAc+rkKC0<0_dd+Cn<<$rW5C4PfkJnD{-nF7i80~@ls$X*Rfy0|E>GDsQ<+NAH^^Kh?V`! z1^w{b_XRbQZz}tBL_X8zncuQ6=)W~Sm1TkQpTc#1eqR*!Lt#JswJ|_>QshG=KZ!gg z@b6l8Q7$gf1^m`^mv&wg`Cst*?dxQn{p3n}qFtJ=ML#NQQJSx*UzL5%e`=kqoy!y- z>0&V^M4MW^zkU5&=*K_zyrY}LwC|9)xTd=givIX(f0XXNDc${4y8Enj_g~R>ykGmW z#CL|~&DN0K^Vj?Tg70o(zm|fv^(fDv+WHl&ZMWdrRM?|nt(^+ieFtt47%lc|6mR;X>VC)6+M|@w{q9M;eti$6{uAG8lrp+lw~X$+x^?Qd^}qRMdUN?3+I#x< z?n%@2sjjcdj9)RJ8ymVYqxEfp?|#LYHYN*v_y3Mb6dZM9SX)nl@BY_&2t~aGzRSnT zpB4M^|6KT9uCN~pW8klgf&4tF%^}M8)#eZdQ#*z88g;_|<#|mT3yQxA{n%caEB-I9 zPxAdG{#%&Gw6UxBtPmH*!(SHz`F*Kf^DFVCUGo>j+F$luL(dpy!fx&JPQluki}u9z zzv{V$p4Wt~jf*<}jyzA#YX$qY#Pg~0ETCQUD_Hm0LHC(L_gRBX{q+o@`)s1MU-1R? zAMJPh=h!dwU3;SnweGl=^kc>t3h!LHwPtf$9KJ zm#By808y8~x*T=O>t3h+;DUpwhq$7!Rq!RQC^!hLd#`SJ-RrvLb?YIUxoA(+Pd?$o zH^MgZ2^YQ*Shr5y^19bWe~7;m^-vvL)FtkvI=HAyVB*2WJ)(?mdEM)}n7DFbtJc3< za1faKl?!g79^LY~*QsxQmDjCDw+#7&3*QLa$R}L*Mqpizy5)7R6AvcZ7B+|&6m4kz z0-|lLUr^jH%IKCS+kagbF_f+N1$RH!mi3%aor^N-rZr?cnl)E&>UV2) z7Mm#eo~bnpUe{E?$2&J-fg_qJ_}HCx>~kqY1?$#n9^%G~s)Z@_8(2?a5k~VBJb2C& z=C#pX!A@7Eusda^D_Hm5-_Z}cb?WBEKZA91;Ge-Xj(*KGzXJ>ZQyeHh68@(+P_Xbn z^}B+F|0xa>Ec{P#pkU#DiUS1;|5F?&SoojfK*7TQ6bA~{tyB1);y}4B{7-S9VBvp? z0|g8JQyl!$y~E!vqVFu##M+$|;=+C?jDi2}82BA|L$^+vD}SxG{|u(N^4I$R&tS^u zzjfUuavtSACgwzu^C>lAsK^7TKpMPr2WWi`s13wa^_&*}&8zXOMl z`C(`+4YT{a9}IkN;dVU@3pua^imXk<`Kf9)FU<@>&3@qHFKXuUakkWR z3qwQ9^mrRO-`uM7OL@+#EUZyQ!yJPK;mMO9@D81s&dz(In)$mQZolhk8i2F$g$ElHM`m&56>J7l>Dg9MUT=k91S3t+HxLv7o3Ld#G7=EIjE0; z<_6-ICK~qPu6&kLHMT@c;)^ht1)HAt^V@qgQg{IfAO_77x zg!-goz2|87$qR>2{X@-DarPby+*?P(5}j1su)4dvu(*Z|xvSzA-!zxTQ9pafY{A7h zqwy!5z4%EUgXaDpQ}_MASQ`zWUBp**KAekz8V%2m-RIbPy^8G`S z9!iNtvN4;^f(&Wt01-u#(c3}8EB9Xlvu7uuV@D0Y=Nt%W-LBz=ei|MXa~+0y`=c?P zV>>4{0eYJ)#!hx9rsR@AKj85YV<=8%O7@=k23Fl318fY{X%Yo-HrwDk;d|#pAn?t3Xh(G(h+hXz z!4JWJ&TO@-I}md9KEMvLfBe=G(4%VxbavM85)M73IZ1gilXp3_-5=v^;Zn$|+Y4V&q4H{X!Zxpc;2hk3cUBk!dAna;1Q zb2b%gm#m8|n`-#kqHl2U^Ksb7MZ-s5xr@EjJFv!JIJ5o&4pCKF#AUFkj( z{)zqQe9yIpU7%;B&-j(j!#zA?B~0!96s_o-+>mmI!K%t-Y)|J7Z)Ue(*Xn)PfpAdM zXYggV7gi)*US=uqd_;2$9--mO;9arZTf_H-dfT2M|F0 z*{rw*HjjG`iM^(TQI$tQWwT;TrB%JO?XUUX$jKA8VNC@kO0hI;IrU@Uk^ky!f1Day1%LTRx>> z1gnBGtSM#=yv1uHM`By@IcR1Tz!=G%eioX5Q(65Vz&$OH^NB7S|HO2p&fGv&=TU5LRaVhD4Uz(=M#sE5} z7@GiWZ2c8?Q~59RmqXH+IP61Z%Je@7`?p`gQPfu@cVCCYm;CWO`SHoKcyRPzf;PnK zi`!RNG~59l-84LSZ5FJl_((oaHg{U1V!ZyguyiVa);A9tw3sFNkRSDLra_1M6+xmg zo4DmI9BVKVMw9REoQr~h>02R+>M3^aG}sk62WDjR^nIJ4MAiGyn(XnOHXN?+do{3-hd~-R4JedDTm>unwIu&2Hk2*$3ba`N+{Y0cY-A0xf9#?xC}plB=|W z5Q^26vvcuE)kD(hx*FctPLEIb`(oceSIrN&=V9qd+vJ@zraZc(p^>*Co~N^GD=dDC z=WdTgAG+7Lb0i-9v>m6=7*ic83kVJqpp@8AbGq$Z8QAuc$y*L&-9cK}*hw&i1Z3Y99Y37klOM8_h!gp!d>E1MzL=4|rChGvYxXTdz(>4RHy1)nh0y+z3@5p|Cy>Opx>uCuB9<$@+AunwT_g%$VZX8RLm=K ze3&EoaX01F^XjeA1j6ZFsnE;07PwKFNyXm4zJPHMPaH4tC|JI9E4-kwTrD94KD|B< zhU7=H2EK4N{tmthd~|DEeM z(5R|E)N8Kcz1}BcuCx$5DJBC>d_%KDE9g#r7=IxbBP@fYc~uG1cntm8$RV8ks5c@H z4Nq^8H&xN_x!ZrBbif#6JJ3Ax<~3@Xj>kxfPg~ar9O}0Vv&rV@AtCsq`bE6ol;X#7 zJvP#NgyouP_(>Rm8%BIUeY$s|sR}1r{zN~@!zSmN%G(;MxH;L77HlAy)7j6ybp2+F zPtsGDOx#a>71pW~L^l46^$E9M;tf08WAOv^L#r;w;A>Ar7mD+?XKurpMSj?Z`oHps z7f`pxZ2U~~+OE>y;86{0tU-RYyteU%W2JQ}W=Ugnb%UX@&CNV`NL*T8EQe8@)1eBD zsT7+DIQHZlSY|?F|IQ99lNbrSD8)(Vb2#|)83?bg;Wpwn_v_eOilckoit6!;;gMlAifj13vN;$z^M>qB<0~GMv6f_m zt;AT4kHhEtmZ2AMc{1cOy0kis4{3dMW4}LscDjN4XzZ7tvJAuf$74g{a>81|63$<7 z9>wjq@SF19(b;%~`mK*&x3D&wReUY+ihsRay7@B~t*Ea|cU6Wn%hRwQ;n^0$!F$y^ zJV9kHt=|kzW1}&ca$v}XGw{ajEIy)oT5P`u?b>d^qm)a#FMACwqzQPDIGWh}fIf?j z(S)vdv(AI7HI~TZDTfbStzxSW+;Hqk{omt577Vy~Ptv3Ki8z=Hr)Ju~FlyJZ?K4=@ z*9$Z>S8i%|6D9`jhru*q4PKmpAepkE&J96Tk7Xh z*YfaDqOW8{&jt3zdfckm$grcOG<;{R9E=LTB44BNrGFy@`JN`2PJTQ!)tAsMZ5oauKW=tpzMq(#H=;F9+cSCR7P*o`=(_d}>he!P=$0@r;E zg-(%kSWSvGkE`({iBN1E4```iXs`@P^#9CtV!1FKC44QQQUU1=q( zt{(@L>S}oFq|Wdm_cL5AK{5ZiBy{ZY6GrJ#yxF#wdU&eXMFVg|mHc1X=}>^U^BIS1RX zsCnw~P<-YP0`Nl3OCE|vN556@>6@Bo7fHse(EtN!JkDvCi!Q}OrPt|d?s-j*->Tm( z>~^4<8+hd6mxGaV`+aI&EhGi4BU(fZPVVOL6VxA+wFq!8F#TLl{xHp34FUA#rw3b9@8}eVg@e5Ma5{o zo0|e@rCZ_IavJWEkOR%;%W|wf%{$HX*rY4m-n9s=XV&I`dy8;sJ8|dPU*X(KfSP5= zM@DfFpjipIMj9U4jKk%L$6yJKh4KA&!h?B{aGvh1(|QC#7A#XKpG#aXqIZ|qmGv!yjWIZ_{AY|el>WZM(>@u->k7Uum>b9HAwRGUUX zQTl%MeBC81SMeCkApF=p4qxF)i2bhSReB|3rIHf#C{Ol3&&AOLPD+P9sCn^lJsy48 zC5(|T%J}4B+0Y32g1?$yTuSGQn%LtO^6!-4@wm3xa*U-o+5904O^=_z_|Ixy$!Z%~ zHoA}ZPpJ9&@guRjSrWcHtL8P1l*64d8CZ+@dD=1?Ic2wszo0&>=A)4YEm84=3^ji> z$^hzrOGh=;^K|c6c#`=RC#H}+H+RA81$S{B<&XsL%aAva-X&$J`KSH~ptfFywWv=r zTcv<$MLYahiJqfB<-mY-q4HE}>8A8MR$6x}D3+qKY;9R{Zu%~-}zI1^T)srBI`pvseDR|uXCq&X3 zuUoRC|ujMdvLI#W^zx1-2h_j5|f;F`pv5dx!Q3O~; ztGU;jOE}o}7z970wc_SDY~sBV4yCI3h{?%#x{4#5rTK0|t33Q1byP}trsjR4^|;=r z9$|a;P@gQ#MeiHoavsJ1CEFD2UdjPAUv_V32Rv%7E6oBU)|H0TTRok{;V z*jH*LY^ko{wSTZmVeeU!vGKk)Q06`LXP6%@sTl!%Z>V`n z+9iCHa1@G0sd@cZaX2kw1+1ccRo^cehg`FV_J$fh*((p-`yG-VKT`86kMwx(EW5Cl zyD2x)v-y*f;c`cc|9M}MarX-cTuXVtKIbV$EL@4(DUV&EZ?9QbPh#I!WT*ai++!b& z`d6u+cetYO=l2+LU(L_>mPQBbpD0oP&x@)dKaW)L?i5R1hijx|3sgLp#)5|Y@-i(Q zSI}7SYC9f^4S$PH)F-W0?132L2=pa9=F%1Dpnn(-lV3JR#zT1AGIXK-&n}k&X0z>3 zMSZ)hel8qvIxBCa>tpQn*p>#Ql&(GUQ#Az>3PS8gVdn%1YQq z>$Kr7WN23;7^;)Ms&?59yNvEZB-ysNuM0T0PJ%|{m*!@rVQ`UPD#qjW^(&w}we>zI8TWRx2Pf*=BD7|(4?HB5h*Wdi7(IT>-68DeE;XOuF&C%u z2)WLAHE->nj4W8fAhKaotEbo~!5haDmwu*U*ac5w+)K*6;oDHpDH^jP)cj?o5xB=R z37?WZ#!X7%$tgcEo%;6M_Nub}a~1DGF}5_&Sqk@3@yjC5+^YnKU#H^_nr9vDCcv0V zZ*d&ucC6_K28Y9O8Rd=RZdYKd+hL5QSe@<}4;#8J#|<>zN7hJz8Txj(pK{Un4!O`z zbz1hMzCGZe$L_Y$cMPKP2fF5f!O%#_lk8t(nhaYrBv?gdo?Lhen@znTfpS;XE;39w z9Sq}X3>v=N2K~m~10(9IwMSi`sdW;Zq`aDZp(LE#PIEow+rHM;QoRQ%wvFbF{_nfX zb62TYV~V%kEi2)Om+4T1a)P_jR6M-=4R}#}e*dr+hindqOUKo`QT%0GnRf(iZ>f2r zc|4kRS^;Lnclpj_T-VssbhkCrZmu*-Sjh8VEb8*v|2)Xhl zHQ(4N8B?qPPf{O_E=_*v?}M!=-mbI?!(_^1t6!`6u0z|fLE~sNeXQn@HHM>QizF;U zbBbd|as0UcC)T4rXK$*@n-Wxf4*AF+$61nRtGEe`_uAho!=8Y2+)pu<{dyu;Z-0aO zbp6v+Kj_*t95+(T`=nfk%a0CYck)s1o$-)aayibW+_iap3IvR@#TN8#N8_Fgy*r(d z*U`MM20hkizLDb+8Y5QYa$vPbxa30pys1($%oqX?NoBsydJ3!jykQUJu00iGXq*!a z67}bzy4zu%-92bc<)6QDflf`6U^w|AG_(X5#r%Znl()yUZy@z}reZ6}Us12S%d@>z zOhY!8NUVSl^)tYP{5wH!I>x~pcuG0sKj-?HKA&tBk8#yW znNIC~S(J>EFWZ9)y>}Y%A`hFZ>D>iabNwhi4sSYz_1;VU@I41h?uwKv+$NvqeZ`oT z3?EUuli$SR%P=1drat^uAq;DtIf+-_sd=w%+wf!OXe>`_gT|S|u+`usbS9f?RxOTJ z!9Q^(`Q=pI8nV|D6>mu6Wn+r76gNf1L&=_oJ_gXjGaa3&uRczl1aGIj!4b4xeZ0>P z{Q8IEaEf`yZI@w8{Ui92V#7#|hmlv7;bzLiKLb)Ard`d}f@sV}=b+8pNZI~@nm5V$O5a=< zmZCn~=n;!m7q7zBH15{#3PrE#A=v2?t@o~O#luUYaT=`+;wuirqjQq*JjH6KGR1N2 z>7VFK{aNXTk-YV>iVqU6y=j<<*I^ft91NKV{oWuGSqMW1{aWDo=o?H zgG<7(G}W_V(PcQ;p$6p{^S(LI-|((fj{GuZ`&TH|s10QJAti6K2NH7<8&58Gci-b;P}Br_OR&dJnInG4k|y zMXZ*Q4r9oM1FvV{>lLrThjLe$EBo=T>m7Kuhn`=$Ucu-tN1zGyZHd!yn6PREe5G8v z_dyD--fIK??rY6`#N2L3@UN z6k}G_u{gidYV1QXe`ruBX0{8#k2EfD?^g7i8;!BFHc-zShEIAXVI7J$NxwK^=udRa zRr6CjZ-+h9)8ls3Zr{UOr7c79@GjY7yxRtfT}Z*|!zz*=k7;t@UDflF zEzKz(&AvhPSuNo_#m3fManL}2C6uH7?^Qeud@W9bKVc`^b#Tr<2I|n7tz10@Qgkvr zx~t}oj$D<#_0EMdgyLBvnGa zyfkRgM#BbG9xcbk=E1N|8g~6hsN-hJ8}<5W*w?9dCD;1d@SwMbecNRRG2@aUgzjx% zyabv@CBRcV`u^T65d5EAgX%W)`vrZkf&cSBnm;tG`k^?uG-)~Xr1Hj3zrg!T46gLh zu)Yy-KPR)aQ+tlZ^$lFRIYHU~@VQhfJWjPz_CM@vu3|@8uaw39ht1I{_TplFN$h`E z{3Z)Fu6!+t{SQ|^zK6NHhJo1s;7;qr_x-nn*#9uLQW$(&bP}}tAAt5hfY|?F(RU^U zKYIlqf2i4MW&mY<(;<}hIe3h+mICQpf@M_=o4b3Wd~%eE&7peyV``wuoHVHMRm~o@ zn~AHxy@Il||6!4PAhy_k9d;MhurI5xV9o7^z?AkId^350Au~N7fc7L5>6nHsu_oN0 z@~_vbxX0Mxk`vYAMek+b-0USEp*_zV>!A`_9NMkTKi?PpKI-x$bPQ1AIN^x+7DzuYV8NIAGP)a*^gTL zf$T@E{Xq7k)_z9z%Ub&x*)M7B2eKcu_5;}uTKj?Q2d(|T`k(9vvLCee7xsUC{1o-Qc=UE>aCR%@UV~rov5nc6k1HG3Jzb22QkRxUz3B zj+`aKAbJMDOHr6$v>jg3{^V~~?{GrSXc$C$sz1-lz#dB~Ku6jaJ@KuI=j^K@*=4I) z&o~udWKmkKO?m#y(G0xzv=q9S)AQHMw|LBY6t1H^&)@4rVb84biX`Z9*lnuVooM zZ#K7S0!vDN!>i(%x2+m#AAFBH2xotb!ofAS!h%s6_QUlJ_IWfGY7Ek_(uaRwjd4cs zk=kmxKNrI;Y>}2w`BBGIyjN;UXm7IZ=Z|cxlN2g1py%SL1Cr70vMs(FPS1c96LF5b z2=5Hlur3Za@O2e`l={$~@DC@^DenS)qGxSt7pPs-whPoQYTE^B7q#sIwJU4eWz?>N zX!qOCY~k~I{CcRs*8XgKsjZWZl;$G;}LZ23n)539Dn0xc* z&BEMUIG+~Ir-f^z!ZlLiy0`FI=0EFMW^)%6H>+7&9!t+bCzCR8Z%Z;H*~JIa~_UA=TzjyCb) zJ9e1{g%&$3-K^=w@7$;vsxwsDC<5%bf zjVRiLnLe`TDR-X-Zraz4O))p&B}beOG~VXQPCI?UA$NTOCv=&?ZaDklwTaCGe>C)9 zcHxHDv-hTe&{QuL_HnD@z;k(K#dghSm0}#BR!S+0A5K%*w(t|M+-9=H1dCy8!L(d3 z@d>oJc&`I9^s39w^ozFeEmogJn73h$R%sSC`--#NAwyX8(q$}LW+HT1K8dYpSk>~G z>kw#PV;(Efu!iM~i*2R1XS~?syQY>V zg)waXs&bYFvkkc1whs$Eonx`OwhbSc)RJlJVl9H__TsbBtFo(iPg;yy>&6G}e+zY0 z%Po9xChudh1@^qRu;^;w$?qM^l(wB3ZT=(Ji+>*8RW57QGvLy!dA#n6e)zneVc@k- zllhvsbNDLWJ}pVT~=z1HJ0ZU=dySVz1pT0!^(wnEg>hJkelNK(8b(*4X#4 zV}p$b<_~|)V@A)rfL&%qiwtEO;LyD(bxNj}R9xfTgUVJZQdHlyUi0(d-u{l*NZ%v*JMaIuzW7?WnJ|3}E zI^W%kojz`A`L21C92V@!3@6mItU1F67r48#ukMDHtKY@YJGrs!VOlxM;VI?0>G1w6 z@R`c8R);2h##Vdw%=5X0*}ZNY-W#)?2InnG4tM3NtA2%5{Z?6IHJ`!PJ@TJU^yewzs-W?PO_=i)d!Bgad0^G-uIyZn3BNt#Lf{88SN0+G zE4n^k6O4MY?NnB#PK@=c%B!Vz124KnCnKfW+NA{3lkc`!m-)r z3EJK>vp8|wgEyU58ivhVY;K%HeYyNe z*z0Eo0bLi*=e^Sbo3|+w7(IL{FJ(&K7=}*@Txm0mA9Kvb)Nz4<4_bHR(YbZ__4D@v zZ5bT=^DQtx9QL#AXnmeZ5rBUcajtwQ(YUySGZvu@WP&1k!lSFbP_*4dkL1 zy!h-$(;$Pq7t)m}p4_)p&7kF9R)cE|cOGG981&=uGx*>*n&0)+54z!AmAS|C;)fp5O`U?a;{=UZl;4(zkijd@&ri-RjH53E^s7ISa13BOG@3mj6_ zlU=HtDIeD#9nd?*i#K`?`vsZvQM6hTD{2nqs%fhZuum~+lK(__vVr?!d-bIv(u#GL)Bs%PFi^Zo0) z-@NPIb8dK>wa($O*t>S@?waYeQLzKva!3-+Ztsno?<?q%Wi zJptczZG*@3_#zx@R~i>}4aZ*xmr*R8MHBt<-LybzDH}_^!JdLO)dS{+5#_45lONooP_K$X4UM?G_63iG>x-DrmB2 zSmE$_A>cUZk9azz5q>$PDKuGlTU`1l2rGWs!S0Bi;*e3%_{4>$^nRjoVt%U>yll#H z@^f<|v3v^^j_YDe#%0dR^?jzssa6ksT937LJM%gVPkY!Nr7g4)+G~g4Z!>nFCySDV zI^!d7g3B+oAum@*z2J|%b6oN2kPE`F5CPjQq0hK{@kMaxUK|H??~TiQl~Y^`%tKLa z2IDL9Y!s^|_C!L}Ec~ptlVai2p2{_=)OcWli=waUnbxd#4!)*vRb8T*xtH=LiMO3L>>sm-P6nz_f9v2mGzq8o^f}Cz_89xLSc&?%5E3(s}F!R z9qyy@#YYLPEYo0T)j8;6k6J>hy(*X$L+|yfG15(VqK2;-FAtO+;*eY3aX8!v2qYnq z6-9>`LtxR!o#fD=WbqZfe!5MgVxTTsEA}l6fQ{8^K!XkE#I*VDurjw5Sk3$-es?bk zqi`>XoL*LQddpsNIe#!ryKkcz72lOi7@P&_?oOJ{L)&Vz>GAOyJwAGFf2M5JD+jQ` zS#$g1R5bTT8Z>sb(?Hs7lv5!VHaS$#oE&bA2jVU;c2z=0KdUkPD!L&qeH@J2 z{j`Sk_FKfV5xFtP)VSgfPo zOSjJ@vvB?Lz0nF!Ct<_tM0_(OAB{^HB^<1ZEy)TY?SX%McwHl!DZE@zn_rjWU zEn)EIx_D3b^Frgn-68y1Iehc$8UYPUfE6!Kpn`=1gmZN>A>iylbnNjDx1dlp+?z8; zIVka5trGRru>bsOt=ZM7xizX}z`n!TBr&LgST-~s8g0BtmRy}Iw!Iq)leSfaXVdqK zH;1=??0)s3_MQ7;_$FrGP5B_?Ly| zO1v{}_OKl^^!O-7zVyK@^Xt%iw$6&R_I1UF6D{ezCUo7kKOT2{aGo?@I#etfo`Gwr zGsvhB=3?CtHSSeut~PP``88Y0t8vfZt;(}A=DL0CnSrZCW}wH5>I%N~6Y!B1Cz0c( zaYE;oVfglLa)`$={-LUaGQ>ogn<*g!uuVTc>IF3!ny^q zFwf&A8rLyfn72C}(lirLqms5l`5QTK(B`mmQitkpfi2area15F#(9%+Q*LFzL$9GE zcecB@zCj|)%05bZ92+g}Z5j?6GfG4D?5(23UJPluwL$UmhWI6^1}xqf06B+$ipMVf zAP*i#z_RV-HD?~}A~r!oU`ah&jcuwQS%rqffP5#-=p!=@9QmY%>vX@G{n8nge3uO` zD>-Qf;blk|mIAfnZ8S%xzChvU`@`_hWi?Sh?C=}2PGG6}Ca$Q~49DGW2+O)$5p52H z;49%)koaMPSkfg9pLlnT^iXGtQxBx!u4AW@VoO{^p+^p0H2Jyqo)DZ{ezY35JfE$s z+;5QE&p#R1?$RJs%2^>?i%G-@sw1em$7tcpsc?K{qB*XSv_)v!x;1|PSb-C-T@&iA zbH&v+`{UZPe+cOwX1LR0dXBoNoTAOp?Wp#LA^5=*TZK>UV6!W z#%C_NC}x$jA}tbBc={kG#rOToNZI}=IJK9JqC<<9q{5p1IQT|c#k>1KuTI zmz41X8@v6ARm0@C$=U&#s@zVSGT^Fb3c;}+ViiRKoR2(7qK=FchhGSTIa|xXdjB1w zb~%P82Wvw!o15a5CDp)JXbZi@{1$hw{76zCMM9-J6*QXPYe_v#5)2$|r-}dKO@@CR z4h}V)HFH*m9GFM9$Hk{yGz|tiqSF>C7+TXw)9}v<<5ZK$_!$mjb=Npt?cO!w5}zsdtlSlAqANl~#yWBH z>K53cS$)VTx*-0}a>6qgw}(uJPxP6Q{C$P=T?yqiTf=q}i>5=s+SOLG!8w>TTbl(p zQk^t^u9wt~y`zSQ7hN_C4NTMk6j=xE9eNZJ)X2=5J>y?f;a;gJ%%n(;T0Ff(|Z>3?vjQ-Om|QW$bY2_>X?Jy`?)Btc_wRn zO;zJt9xjTgvvK5NhfLgSsDom9ofBlo@&r7_wUT0KD+?I6zXwj;SweB@qdS}mZG~6e zdM0fDpivhm&B2W;P*(de653dTUh&`fQQ@N({b}DbD^1he7$G5yj-uKGKQ~7u*uaV?6lDzJf zKg;~j`YiLUPz|=VcOCfp(js>w9u7w%{K)ya6~qZ>2y|(%n`B=|74K<#Lw~UtT+LZ0 zPReNm=4k?~al9(dSx^(|J@*4=&3EzXsP^z;krV9jJ}GWH6bZYWKau0NR)`(CCc!QG zyq9v%28b)q4Tr?+W@Kd>bFtH|s&L_R2VCmrXTj33Ic&b#06UeqEKEEf0vDY8+_r^u|`AbFD9cJi3_#pZo$bb6`h@cvrE!!5>_Wvz< z<@i9$=5?X7?_DusR4D9hRtcVa<%u_!41$vr35hMI7L&;^xcYqr`KI;~pFUH;{$0h% z3ip$_Mf4oshs&GyPYzzY#_)6W(NjvSKII9iv(AVC+iT(r7yY2wnm6Lho<(TE(I{B8 ztc+%{=M29ESas-|_+ zadP}*0_?3@MT0k`;Ggf7kmP~&#n_;1{3*UJ8Rfer_r+~BPA+M#>~guLTgzh^c+RXO zG$f(6kQXx;Pn*3T#W&0nDlHAg8>a1`XJyBaVQH}4Gb5UeQP9^2ar{hU= z?G#;pydY?2fBfxHS;eurj&Q0&2W<80lMuA66}U`t$LkXcgkB+GP+?eE{I11np{VIl znEi7r>OZBeu&%!fvhP|U)!Qj<{THht>p?%QbGJUZe^w8JzDGwAt4wcE3tSoDwa|xr0!hp8Kx(+335Pds{^^vO+Rc(AsIJ|AhJv)PD{2UrGH3 z>c58ikEs7Z{nt?c5%nLa{~GE)rv3xOWBbMe0AM{sZ-2r2b>-KcW7M)PGF< zC)EF3>OZFbE2;l()PGFOcFwLicXd@`}4# zMMV9_)PFhua{lH1m-j#N{^wt4|4)x!^8Ww7@c1j||G#$qBj^9WHvgFqS0nQY$+)PP zy&@?5iSls&9Gu+QMUngBq;`@v2lq;MR{R{ZfNYIS#R(R+iaDR&lfGe5SlPXdB51cO zgsk?*+O2Peg=YfcXu0aR?P4Na{t*R}roTgvT2B$2!c$?~t_7%}vxh*>)xw~lx5|NC z!rTIH*uuUmop9`o?}ELy3CwHjgkaqz?%!Jzb>Xwtjyl(WJL-ZNlqtDC}s`XET?<3cvO9`!n)bH6);jR;U zzG{)%d3sIJu<6eZ*iW#}J>Dk^mageW-Z!@wOBPQAq1Q1ouG1LtN{w#t;#>vj8Ms$` zU#BSqU2O!nN<0y}J5&Ml^TFUBTT(N5K-)H==hbXHXn1wvS8I8$<9#)r zGUbm?@aJl7zn;?X7(60STBft`XiWmHUgZSp*n6xH^r#z7-cTL~Jl-u}k7hXjLPOmC zbu)LS=>ju1qw`KLc;B=cs7qI!2i`j9#BauQORN z@VgdQ$-%LOPKt4-mXLrQDcF9Njp9PJk0j4L3U{bcMv<6U9ZHV~#O3XZgd3IGz^#u0 z_KH0&6rG~)HrV(F`J9?7B%Mft*LW>`Cb&}A;zZADM>?Px?dG|4r*%0lzBurzu0yVu zcNV0q??J}cRuwC+NPvqTCrG`4W5t4#T_HNe63COiVrrYF(B@zxhjEJiO59bF% z$$*j?3++|XGbRrDG_S0wv~w8Q9z(C2ZRM!3zcf(WWDdQK{iuuP{k7l9)x~pQ>jNiE zDy_>JT9-epE)MTe%B(0Tqbj2jo7cc0Hv=HK^*a#)eDU{*Zcwz~s2Fs=4?Y<4hb&w+ zR}Aixgzv3dPpZsqC0;aF;cZJDiD70ieaUf&4Yo_j2OTwNJIzS;%9C|*jjIO`JXUMn8Y z&{S4*o}7j3n`Pigg`>i3om$y+gc=_M7e!GAGcx~&3OBv&q_{F;DM^`~f(K^XDCVg@ z5SK<#__(r+BEDgD7_=o2yLT-TnkBS>d6NZf`{0;RvRMTD^!kk^-kBq`{E!57+iB3$ zC?CPgS_LiWyYnWGnD4gpff_O@e>-sCqjT<@Z<%oTW^ZzFy_1;OI05WjPLi36$BAFY zc7-bYEFr4jKC$D-ra;t<;L761VwtDb(D!37oX#$(@fv-Z)P5cZx5iY~*i=p-4>r^L z3t}BL-P=WJPcKo!%j5KV=A}QClgj15vgb~k=FJzQ6(3UIi`GU{F8>3%S1k%oH!Pz` zKU4!hPY3|_9fjh7R=&8>OgH$t@~9ZRwGVct?^oJedY))MDhYdETt}j(V=<+s3NPDa zPZ9^t&7FQxjUSD)S2k~3-|fwvOze3k0`0itEI2~~j#+RVEv__HXzbVx-?>o%4-MTb z#BFPWbGmxr?8Q%n+)kBoT;&k#DwI2f;i2ELS zC#n{*+r~WCIK8@)4Di}7Z+^n3KkibFvxnJ7`&+|q=Ynr0Wpt7 zuLNtT+Mx@$Z!M`wdwG$3^NWY5{gpKzt&<vl$SR;i#E1BS!mc0lgmbn2TnDqZx9c z->=2qanej}wiNANnF7_v*=P>V|AZn}M1sp*3(a$9R~%bC0Pb}u6dM-z#k+61!O=fQ z#o<5u;Qb}&yF4Q2isN4-VgHdD@=)U=whB?<=3q^R`cKbYbxMuf?5?TY)~tzJJl&7& z^^QPS)wC|E1Z;oq1ln+RtPnM)D_*kN5{IEJ>q~)9-Zel6UZ;!#+YBSZKJ>sGnKD`(UEmA@2%TAgH$Ce?7s1$JRX`>0-{uwjO^t#wyg<`F*ZSeS~Zg9!+nE0z>1YY#=7xCUQN4!-#8DA+UlFgS| zhuK3V~ZauGN;x}FUqIL~k1T)73{9?gLwDsvY;l}q+ z+<$yUe5m(+;o1D{J%_>}erIRA?@=`K!LJIzoYNJSr{zx1@Mq(?QGK%+h zt`O)JfE7Iog%{p_FmOmM?9%XvFyuu9tjYg@`iIUIqRuBlyUJ_Po<2&UUmX?P0z2f^ zW{%svQ))2pUQ=uLt8wm$!I|KhI)H4S?J8Q{9SG01pCWFv$BWV1yVCc0Si(=MePa39 zO&~VK3zi>zBL3QD1$ERRpc+t0(|z!H0+-@pO?hig!KEbPe>ejwCOc{xdBWx>=dMYg4 zTp1^w>w-u8E~$99`63z|5|3*huB;gJXD}-MHUlr2=%{cQ-Bvkhn;Ji+b@Ay@nv^-D z!X>uQ>%je&5x4XdoE~SRC}H=ROjbo=-{TgF=U-ewImjPZNq8%~6aC=F)0#M8biM$$ zBEatB5A-c*ws6iW8Scy%k#clPA*ZJb(r;HrFFdBX%{{1w>Vmg6V?e9iXW^MJ^>!>7 zlT=fLiV5Iy<|J8WK3=pQ+7;H_u!L6=_lbM&HU@=f7X_tX`Pt&t# zi1S3@d-qV>I-?RUJ~B^OU$Y5LdF+J;wS6ii*QtyfdxYR--lY_SC!9xb&&1;nWvms& z_6|fY^)vC@jgAWQ`>m8gd(^o4Sr^4_FLMGXRXB6ElcKfHa`HMT1=|MMD6F%;kgkrA z_}VxN#hZ|t@TG=7u37f2uy&Xqtf^KDPdk+_EZq|U$5MWxS%+r}>Xyk+uqGF&LRtu` z(p3%nZK*x7&o6gYLM9yCFn~PYtAg4$8@ zW?4J!w5@8`L9e$zn_mIFo}dEfG4%RL?J5+yFB$BgSJ4P#KcmpTkuY?Jg~pa%-?xrl z=XbVhq1a)ZA9k^<1!z~kxN&b^>~jAr$sI9M{JA+9yZu;2%zri!-*;8vCTZ5B`HN|} zT?%MjIw+LGhBkAv56;BaW8)CIQBw%2HxN5tJ&OW!CJO6kh2oRdE8$1BdBP?4Cb-2t zFD$fqDwLXLg)1xw!Hv^ODV`iVi`F$9hGsmA z7LKw%BHSt67Y>E}KwbU%iyZssa>S~n2J<(?*^6ca=tIuw3HSArGsd7|GHZ=<-@?VMAyFww_sly7-S1 zw#J6wCzq`7Zb2(N?o$sh8qyLMb}balN|(gnLVMu>i_0oX|J;OX9T|$7m#|YDdt{H| zYN&9*9%n_3!c^_PNopMK?xH}ivq`p91};CxUeUPd2JsMM@y?tIitL46@S)@`<%g1u zL37C)ET)&zGH!dY0fcmRB8iIyR}sx!BbKjd0-e7d+mx7M?i9eGp>f)#F{TqxTlh4Qo}v+qORB++|oH+MQpT+Gq?} zE41jES5?ksTZ}`&F7BMq9k)SZ)rOo`@4ezP;E6Zq1i!;t+kRf016_NPDog5c?h_%B zX2+^?UU>2*>C?Ot=Od@h;qs~?ZufJ2N7&kLKj+=EYs0E=73W748o|af#W~;p;|)c- zJ$;yOrye$f?VIlK+HH5P1NYlS5;lHgZgn_sui^a0uM*gAyvbQP$s9g6dC&RU&M%}@ z$&$e2hc&7QPMLT3c!xJGKteWg_RIBv5(|?!Z?J3x6H}zzF8k&UQyoSeV7lYXyr9p5 zYdp7Y4|qb{^Jv7zkA+r)6W2Fzu36O*&Ia7)tXcPoocL0b$Ns(TF|sh#j`OWWGs(L= zH_m}e-O1;&4LBd&7^M9~?=NC=2F*@VX7-o(-hw*F<4k=%-r&Jh)NGQ#xyhBosNF1k z&f@X+=to;~&du6az_+_d_1#k7f*r1G;{Gf=<$Ny`TD13~fT9yYU(>XkkzGJ;A=L!}X zsGF4s=S`h&DbwFd+r@=FCA9&UrR`!$N?o!W>T{XLL9@unIc}VnZO$j_JKA%eGWiwx zI!xLw;=5Two2~b_-N$}4z#(Z3XTiH3w7THO`BJtwyu8wf`~PjPJHFsP8ZqB8+m*$| zmcQWKBX1wF?dOQu_=s^f$iYSG?J+I4Y3Hw%`uXzgWu$VRE0%{UJo>k4?t zaz4*Lt_^6VU8{2R!+BF{(RYdOUrT>u`fr#KzJ0CkoG*Cgu378nyajEaJ`@!1X0E+_ zz9H)ElnwXhr>(VKzl2`LFan%zU^Y(JxK%(&CQq1rhu#x4|8|{2t6XM>&Hu(`xPtv= z{~qA~OQE|i9UhA<+?gKJZ}DfSJDZQqn^Sy-JF`RWiC%82_2cMq$Tqz^YUjM){U6u2 zx6-=n=EpQHcb#2Kn<>j%U$Ourg6FJ{Kqsdcf7YY^?L-Saj|h0FQ#!Zd6oxE z<1)A=p_Q91Z|n5F^x-qF9W7=tz~*lpT@P8&Bx}YanU@Fz!L^6RM5Ee*sI2@pf&!UFXxkYwLZB|60x?bk7v-PxJTI?O=WokCT~Bg`8vjIo@E^|hZUhn6&RG;;F|KrNz z_4>HjxISJcug`-i_5EJAF?J|z53C1TY$%J5@0Rvyw)XQ-z@y>32k751mE$t>?}*Cr z{Sy57tN`!M$3&7E`CvN85I zIu9|JM{6*TRzDB*hZy)n4E!N_f7te65Et7{^l=e=Tr7VE`C)m~=ZEO?!~SlNXE4Y! z(dU`jG1wmI9MYPH+0k#0%wOg=i<9|F^T_x4%wL*E9y^Ph#m{6|+%%8;Sis_@dDOD} zu>Xc=`YD(U%bokPj|%pi{X4CyhdcYbZXUWX_{Ti_SgD&w$z*i?a2cIH{J5a=2Qe94 zTwF%V-!3kri;K(X@`ITzmOs{K%paCN)@N)UU7ooN%OC4kCd2Z_`jyG(>cwSP{-pgH zi_4eQi_7Th&ShBssNZ}ZmOtt@m(lePmtpy%dE_!Ie>8qB<2tO?T56Na*hGwCeaL05 zSuSUNsGo=Rvwj}d&-!^-KkNNr+lAgAwq5A`VcP|l(QRK`Mz?)&8Qu29Wpvvqm(gvf zTt>H@av7Ruw!L#1mOq0$v+bSB(0Z}sg1%mKj(^mPj`?yK<}cfxS-qIQYI6$B6#m4zsrEgenjeghWxlR=Ma_occ2YLWekQpwEt4qZ>y@5AJl+$s-G|06{koX7^X> z*D5qFL1!1!xY%`fJboINLgy!@aVd2EV;Yy@L6Or2Y7et#mg(ZfG%hC3*D5qFgSAR| zg)VQH#>MRNwF-@k`9pm%!!#~IzgD4f3Hr4Pjf?s-0uM=b_GHh*(v1@uSFTQ;(70HB z*gP~x^Zu{=AF1Qim9Bql9Um6D{w;Of+O+21T1T|M=D%A<-*5|DEs1`|eY+k0%yL8St`X06-YuHW4Cke>MV#3H)%7ofM+MC)e%6*fZA?PIBy zLMq=aCJa@hOydF?7h-W;ZdydX(RkQ+v)GelanmBicblp&A%=}q;?51*DSx3zL{1z96&JZdinZ;!Yx#2bUfecv{L*#PZXG+G$ArWO)mucK+nuRI+@2OmfEltvs5rJg>KO z#AmkM)Ux~wZ>({(#4ui$A1jWc_{sU&@W%u3!^;QI$GY}}adhXc==R(Wobx)bK##s< zao#9QMg4Zo;{2%~4mpO5B`uo`#VD`|a&JF`%-ETV?-dnCvFV{CrdtLcS^1-~)}mmt z5lk z)=61&fli}2p_)}e*tIFlME!SZ#QEp4cSFeuOPRZXy9(xbPEN&VRye)njLz1e;9ANomantx) zFk38c8h=Zc|GxF-l4m#Um8>qM*KQ)yrcY3^da<}^{7PNj35_4=>P~3r#eT3UCctGkxg zoimG@#?NJF-4D>ZBVFAO(7GdC-CNN3xh)nqji38K>#n4AN4mNzY2A^o?n>78EM68j z>wCs5Zr1mVS=_Ae8MC-q-!rClN3`yI9$I%q>(1wAakIW>v9q{Y-|Om*Xx){%x+7Y5 zrLOLX^}Vj{h}K=Ht2?4~=gi_}ea~cQ-4U(3kFM^B*4;-}cf|T$S9iqvURQTS>#o(+ z9nrdLS-svLDkP86qDh6jJ#p_Z@5t4`i+sLajKZ5|E+mJ3ttL@r24KaQ=Y+nk0!{xO zjz^uJN0!c8r#-hf1>edjPR9MZ%4KF=8$o*AI)#{S-ZF*KGqNPT4yh-;eRz@b_}Te{ z$y3%+MvSS9mdaozLv<0=B}|vjiRhe&*`>A+wWVb8)CWX;Aj}8q8=}5(8R|2lJ|AGZ zG!{f-L2ORLxi&rnt^1xY_AI`eG>Fu(7a;E;U z<2z@j$MUH2pXZS=vs16{IgPfz6$JwR#QgqX^2j`gu)zHBy z{WzCdX6>F-Zh(HA=*Ou%(aW=b(a*!|=;vp@^>*3c^?k+km_GA|%}4EVW_GrhE6^B> zBgQ&;&boOx>*mM0xR_neI)6Cp{N&8+P=hv2uP#~}6WbQGQ;@yT+@ zsMTSKcZ?c@PLv(WWe#55i+c5n;rue-3o3N$&bd>9J?^-t4d+D-8`002o}71+`uO9A zx}3MnXn@bVNGwJ*#GBjJ;p1;C?C_?OzMKu`bg(^u+_p#m|HkQOMBUE__IXie`q^5a z1@<{xW|jdt4^kh{=5$x)SZ{%P8NjbGSZ*-VXQyz!&o;D zW~`f^v;Mpf8>c_|^Im#Cxs3k24-*hXEB=|0vHrXdWBqv_#`K4s7t_zruI!5v zfbQ>nTz}q&jqA_*FlOtptrfeo^GNz}!dQRahp}!RV66X)&scZ9iI3BNGJiPh{N$|j zpYzFrOaG{sAUjMV|Ww@;wvRudiS#_K~SBZm5*Wvq86B(#HX8Y>jn_ZyH zqqdwkKL1QU`$lqZxMv-?HZF;Cor3zr)hnB`x8#|Fh4bOXWzn@Y{JCak1v_1|1!vWK ze8Qm~tB$(0)8E#gbi1Q{^VfeaquU+3{*UjU z|Bn3$trz`#``7PJbn9DQFGH5=_@DEA$lp~*)+^GF(f8!MuJX8?6S)We(|Uj(19bV6 znI}U2zFqEz|5y*O`)JsIM-I)+)!lEz?!D3K?ki&V>gex_V)ypw@1x@P{^{-q!qPo# z{JtN|?%C4a--GEK?0zzK9}i~tmIW@z%+=Y`-)F|hnGH71+ zE8Q2y{NBaxC!#uyxu47iW9C2o&DnfYpc@-w|NU=`F{I)W(I9rEK~D7dR?_%)A%h$u zgWR&e>2uEW$Z|#J(C3lW2z#IVDeCiRP*Wz4^zzIGV|E{%L2t17@%*zf_BUysU5MFW z%;sP=80+U|Y`*FE8c9~-zdFXej;sF87=gwHx}N0B`c_vvVB3VQ&*|UzcE@E{-E_6n zZ4=UcpG;P_9RZs|zYVaQ(d~|H19}_$zB)Fps~wlu)s8*4fNgiIj(mPy?fAB+s~z`8 zS37P~S3A8;%ye}<$(hyEKwjSiY#!E=T!z^+uuI3J`v{p$13&fs0n8@tNkJDE8|T|R z8#l-Un}_u_i;M3&baAnsr1l&0SXs={JiI44Gn*_&Y@GQo{k<{hdXkUJwfmn}JN^Ko`QnVlw5%(%jNI zTM#esdna|{>>g7t!+bQD2Mp$C_n7MK0<*z%Sq=>RWY5FU`wvTfg7|lnESCoHGI<_5 zwaMmT|M7VY^2Y4)aW=+mFd6y-Ivsx9fk9p9eA4=c=JFrkQ!)hu8M$^eAG*9^mYe^c zwPT)1J<3RCDGPEQUsExg2J0&}2QV47rZZSyF}r-6*)&*Rv2`OKXKOmcwG-_-KCW9g za%O8f19`S?sK>7FX~xq@vEy7f3`wjO7nE7&+&QycUi{;#ebTmS#n zwL3oU3B5L${rr8~o$i`JU{>Yt#{cc}pyB64gI;BM()X&-=S_oN{VzGM!Rq%{?>}jO z7@mjvi@#4`5y_v|SQg|wNLi5cAm>5u0l5d{9*}!L?g6<60X}PU1o4^&R}5kzgW4CJhYRZnOb#6PvSF0 zdX{QVc#77LP0{se_?$l*H7Ps?UQf&CJo$1CWZz!Kc~T2CoM@iPdB9|2HbwVFSPswa zi51V4VaKFr0M9z%seNC3I3FM2(T;d|O7{e9ZoSQjP0_s^G?rh-c-(Us6rPCVT(e^) z*lY{nJj``Cw1}w1x#{L?BQ`~MTGu8#=TEnL!E3W%&g)v*z{1thoc%gIC2I~y&$w02 zTw=tg=uXVr&3*e(a|qmV*v$DL845?^b2-oPPlg{GmT>N|H^qoe(f#T&gy;F#mEGuI zTo&i_t6kB{l~OJ44d|t;vR2s`mJoM-JUtec9Y~3O~yTdGPC_Jw7m5(RB>}$lP=tgvsj)V3y?h(&6(cI4k z=bn*DHKk{n)i)@nz=%!JEp(Kg z7yhhe7L3o2^+|Rv* z(NMP2V$Q+uQlNFJBjgwKyNl`{cxWHOAgodH+mZkb~`?kLLc9Uc<1j)j7^BYYa4EQ*=A) z`e&qBN3=0bdcKg`?%Jr*VJYYRo0moo`BE*4+zXV3Y>IB+69w;$->q81!TY5-Z~WW? zGHMoZpPdpCU}eYQobP*P7_lk3S7N2@w|3Y9lyE>=pZkuRj>Mno+*a1QacHo+v@O_- z9&W^@=zdFDKv-{R`ln*waW_x`2EE1J1;|5uL9HeyqB_XbJ(&m*($ zA>SvqC2OBRJ+!1w~{~e`|^1*x_u)RC%5Aqal;vM zmek|izHv(H%t4jfm6w2gEiZaBBO>4=p@wuE3BO{GuIS$3)8%k}UfNpeSTo~QEi%q41v9(&&T=C* zMfXd4>GQisond%P?P=W4Durpd{m*%vmoH7lGY&83{Jd$35u2iWvHmcg+w1kmqJ-P= zoCgM;M`riBb3R?W91h-uIG4WQVZ^5BMz~4epDYQ_!EZ%d?&sYmDm>J(Ip@L?!|^ZF zi*t)gSw?J%?(|L4+O_qo<0z<`bQ~PNKLd6ACT$nn8thR<4wcp?qehR{8nP+6v%5;) zU*R8WT<6;-eoRbxsK(b9`th~Ou$^igZ#|xKP?9m5qC1d&FUES~(S_DNlj5c4H$J`M zfmZHM=HvTztwMV}`g2}W@wE|~qKoF2Cv5(HvsL&+;U#_?skI^p*G!(qxm}bRN6)e1 zyx^)ao1)ubp!C_K^k7Ha!YT?gTTb6Tpksd0XN}al8&JO$(sx-8GklEL6kYAMWbXgr zof)`uekAAfhcdD6;ZB?z?9amXTYWg6S~}c_P0<~^EraK_^YdgfvZ_>zKgtc-+ubDY zmo-~ipiql80Mt- z??A45v!FUoU)q}U(kumDf4U{-HQ(yusz(}gF7EGb#HQ$aO;qswznYSbhgDn2xySEh z+-3Gl&NZg?$9?M9VOE#Y3p*LHDY~z-q~qZA{Bn50+feT3tc4Zvg5WNkWBXgV{ zm#$%F#HQ$0*;|h5&KuPoaA!}>?^_~32Lm{t46gyNBKvS|Jl)KQP0_7cDAjR6^ksCY zUJRdSfa_z_*+bgy(w2NcW{-OFaogBp*pN-p-SK=IKX$aXP~&Z9rYKpS-$twPgbL9- z|5avXVn;i|`P_~{Mr?|1u@Ta7@RijX)aK_nHKt|IsZo;q%>toZHqK1o;(9^7(gk>Se^H==$pXe~1@qdlyKt1hr6T z)xRZ9ak!hemQ!~x4ZhljLLgC z*L^q`90rGR_V>>+VpDXg2`!oVce6j7e(DqWvS9}uy_cdTL+|CD|(c`;&wki|C{SIjo1|3`yZv_U{PQY>{#x^=V_#F z4^x%ZId91g1lO}QIj_p|Gh$P8y9Nhgmj9(M>_Ji0i}RwFO(1(}70#)uU{IZV%=5pn zM2r!eqI!#G2iHdw<`TQ?u+%jTQbRE5<&yUydCW8OglZ55!t4#vrI$h$t zym>rK8g`5Gmv*s6Y>KYu<3!Bnba6OLetquA`S*&F;C{fDv(2Acuq$7|xmHALBQ{0% z+Xm_LyVI@==;}R*``JOA4l7?Q;v8U>3U7vP;C#ASk`bGtTQ*!;JK6h9Cbc}JIB5nbP+s^Jc4Hd4UV}v)!|7$otrUb6Fu98d&*q ze%X1r5u2iGc(2%B{ai1D=O+Da&(ovNVgAdXr)Ti~j=%AFdQ<6pnnwWJc4%JR3~I-o z8OX=kGvwGah?xxiF?yCYd+swE)IHyev+lWbyq9#(o#V`&r)BU=Hlyd!89t|u*bfx26;1jb~m%ZWa!WT^W7_w82kSS?w|B;ndLmlJs|gh+yinC z$UPwUfZPLe56C?r_ki33au3KoAoqaW19A_@Js|gh+yinC$UPwUfZPLe56C?r_ki33 zau3KoAoqaW19A_@Js|gh+yinC$UPwUfZPLe56C?r_ki33au3KoAoqaW19A`im-T@D z-WXZ}>7FHBE#z^Y2stNmKgc~G_ki33au3KoAoqaW19A_@Js|gh+yinC$UPwUfZPLe z56C?r_ki33au3KoAoqaW19A_@Js|gh+yinC$UPwUfZPLe56C?r_ki33au3KoAoqaW z19A_@Js|gh+yinC$UPwUfZPLrbq`pyk=|2tE~y?VIxw8S*CoGl3ldOY;;2pjr2N7x zKHjEv7xK@_7q<6AEQYz!+0dCD6H=n;M2Tm=J-l_c|QVkD%T)E7w z(`pEA70h)L#VnXN@jB;(@3D|rr#km%(2hX(Q@Ru9Q$=AhY4s1#neXP!C87AZsdmk z_+Cx=&R6>LsC^W+a;e5;s!nc;{}p1KbS9O@+waI+((JXA=ls~kWL|NJua{a$HdRXI zGD*us^3TeDUR9UZ-S(&&+$K%sy%E%34L1q~5tj3bW|?4nB!Kg{8p9#gY%7hxp=A3h9Hh{uWv78T$yGbnXCvaB%JVu;G zNFMqS15M6A-#i7 z6&Q?r|7pU<-ss$q z!`+=eyiaB=9S$o$UgW%~O+2I@t-*cEjSGOAzrr}b9asj|OqSl;HNoEuu1=78e&EHW z-xAwzSBsXnrER2M^jwtMQ`)!Ktty3IXSe3_c&||4w|{DLz8s5jkK=VYH~G;L zU;ovCbJ>kmal*eqj4f1Be!SyL!KlI>JoW~!OT&PkQqCt1EDImC-S~K&$K~OlmG9B7 zE14Czzu1exS(O- zdpqEW@zWI_%^jh~zF2(C&Q&pg`3*ABJO{V+87W-3`%62weKy|t+{119hPo&$DjrWO zJEO+w#EWSC*RDL?T@@^`mDq~&r+M!9=NIXnlEwDc!iSGYec0>hAH-s0`^NvxG3J(Q zEARwdc4=xDO`^}#}>k9Vq<+Y2;s~wa0S4Z@JP;4Kcf#@jfYaW;o1q`^5BVuenbEx>*33lY>+<2 z3jd2^OzZcX=XS401UylG<2-X&U$|E3Bj;0PqafqfTh2X)^n-s^zNn5=_sREL!}GmT zKYX^V2d@gc@g68~u{;cM4d(p3ybV-cg*Z>T;{i!U)i`f@7zp8M(mSlP+s8r&`_6>* z-oag25LYRh?_0VpQbVbCdE8Im8iV1_#&evtzvH3e8fibH{@Drs1b4`T)yqDUdYu(`rPzQ8;H8Tmt1)uYpa_;5Z2%6k1!}-bXFz7xzm#|t7N6Bzl zn9lbtyZWkOz<3q+b8hJj@a#96b48Cd7+LBIXLFxO*ng`9X1bw2>%qAd(mLdPw})i4 zDD^`fpI{PkO6q}}YPGaIKjd(E54=yA-CG(jH+P0IX|6OLUj3T(Um?bNkH_;IPQH*1 z77a#mHk&sL9>2}tTq-03lxc%F&n=Y+|E&C|no`}XG^q@kPEtS2JNJPcv`gl7?~*2x zo$Cg3-q>Ux`R3Z6bK3vM-djLrnYI7^V7G|fVt|buz_T}EcPk2FqbLT5bg5&2V2^kHK_u^A%e!U+}hdkzYhv#+EQ zH+V5b<_;*s)v?i;8cVlD`Z&%ZS5E0}uh%VIN~MU~5qe)G!;A7_#d*DKxUI{rU7M$~ zea+t5j#?pfo<;71#6RH~wYz!f9roxOAwSf}M7;lSglzWu6}|KE6(VJ$@GHcLQIYa{ z^T!?QL*LiV@39y z7bL@jvvQTk>2+6GyRklw`+cju^gW~3Ew{$p5Ls)Fq&(RQPZxPM>Sbo_-7=!t*)ZNB zcx2+QR`tZaJHvRB#Tnuwwr&vrglC+(E8a!Dw`y;qs;1xogJavE=65vZ*weCLga7J6= zJtyCe__*W6~#Nvy@ zdBX?Dv*-13+?-t|x!|T=w}h|CA?xNE#MQAi2OJj-rs-woNb(f%K3@Q(zw=H|WrJ9i z|NH-dXGC2=?^D$ks6&WV9fG=r-nptgD9perHo4%BA`){l;E*_FSfynHM8YYL9OQQu>nq?)TWilX}rx)~(X+jSu>-8EGDMRjsg=l_6u=EbcAOtFXO2)SmHEmvIQ zNPF3Os$RDg>}fCk>v&Llx_TL;^)$WAG_pA=Oko50lF$|9s(77KZ4J-0#@}AGr|KCW z{@~Auz6ZTe)%QT3gjn@S&{rW=eHHXch*clvd-J2eN8eQS_tqNaVf~cj&K+4erT=uG zD)ZePK|HHfX6F7xFEh4fh07XWJ^k5D8!@xJ-e&dtutT`?Xixe5+UJ#*XXs7vgBgQiHZq--@V;o{N z#=+Q!SdD!!#vxW?qVLU*@uO7lUyUE{?AO10sb4a&DhC26{oUiA*}XAA#C^AqW_c>< zd9vOr$XdMBkF60uHnntlz0Eo_K1_74qW5_UoqZ~@U)K9ASszr9l`6fZ`%JFhOWM@c z=XK{*=r6ZjjG%P4biuNp?--N1pGUz_a>a#>O!39F!(?c_y!74kPiQZ<`_&}gIHQg{ zu(3IDr{v;t@z^HB*OTld#=^vEyl;NS0YC6FVs3=qp_&`PoC&d-Gr?R6v6@T4oC&d- zWBK0vn2(a`Td4V{NpX64I2JUT9UkFB>DP*!VugDSA>N!S*=irXt*LS>mPG~Yby2=? z*GxzA={&Q^2d%TO-sj1}H;coS^|7|!mweK1a{)Tf`KN8<^T+!9-uaxJWyV6ObpKw3 zhf0qLVN|!Y`zcC}U+>G*y*cFxk-ghLC9c=5kL*;gC|Bvrl3L2>?zM;ytf?)pZP4ed zO{V%1b8D2Y<`4f7&v?a_-mRKz#T+cLnuEpMEU}uK#T+cLnzO~+?04nI{5IuR^V^39 z>*e8igk-nNezu#Eh5SWn`o+uyT*{ey{zhaO;^-{^J7n1G>dHTo9n+s#U7TSi2K)uQo)JoS*_uE-ID3r4Xw;Nz26d@f4jIn ztT7$C{#9w|AHaxxZ7RtkZS;EPg;QJkBz8WPlYuivNSSp8jpJIqj*^MNL+QI0K-oO& zc7V9{$-%PrC~L0D%=*)wvPgvwlz!E-r^MPHv0C5!Cp;t8g6Vy#wP36f6RS01tQ`}p zwPUOi6Ia8U^7rP)`a2z~*56m!>*b-+!Gip3AHD1im|vGy@u^RF_Wo3jdrodi+{ILs zZ$%rRzR{SrPg&31dYk2bJDP>P)9aSHb%I^u2k3Q+>&zf=y0tsyfA}biT-2`vahnTy zq*hR`XR_^alG8kX6Y8984h@i(R@)L+^^A~Vlde(S(i?4E?isOE1}^#q%6Ib)5tnQ~ zSRSsii@09XArgBDh}B*K^D}z>z|V-iCG=+T77MAaeY<7@JD=u@h1IxlZt97tLvM*5f89bKimbU0SFBn{q%0P@`gq)l;o_I{5Ksm0~7~=UOf+Y4| zQMpq4ul@|rBTd)TnIjacn%!yYzbwdd`7^J9M?9jo>S{`6Qc53idx z;agnvzVX=FUi{eVcQVC*@PtEu?j8WBhTvMeoKlxm5vufJDW7pp3eV&V_ z$FVNPSleUJ1LwfWBPjo<<@3dgoWqIzZmbvmvg&32uzOb7`hICjFA>^U*2}q{%E^PK zzH;|f8{)GVi@SU6pt;9vPordLNHHoK-M)m&Ld~-ff7liwv7eLr!)ib0Kj9g%_f>zN z*!zk-vBYXmEcVJ0tG%+=6HBc2(0*@z>^G)k)qdmDU-j}(D}6U!dxAdJp3~QtpFVkx zzENDSfxLW)43s}}6Ayj|b6%>P%%9@Mvo6xxtem9^@@`Z0K2OZbz06kXbxX z?Y+kydt$XG|9kWI+@XK>dH1^WKDp1+yKUQHAa~uNf0uUW19|`J36!o`2k@_s$BBm( z8N|I-=b-Cm!<>3X8~yuUIpfGvhkH@F>yXdPGfMBb9K1A|bsVGjTb@q{*E%QZ?a{00 zr#0(=dYK-@2IoYv`Qor}%& z(F&#N+;WhU_PzO&B2EaGe6cBAPx$a`c5}t=g-R?Ac{_q9Pst=oc$uyE58hb;0s@XgF_38fn)TGk#!7r}KNB1`7w#Qn@#v*U> zy;+6%F!v#{)QHVXHe8YHRY;V~Jk)P-iASSNchF|E^;*0r)11vNwT6Vr@k!;&&Ry>+ zZdK?dUv@cAwoTKwB4lO_`R0UGxhjL}%1uu`i#V36+)1oGo}05?j4xlj+`}Tn<=O0g zMb)CU%I!^r7jQdJxGXDGZjpbmRL`aAIy@J#^AG-v7G=O>Q8r8#WyWMtHca1}U&Wnz zpNKntB)UHFs=Z+R9ZGX+@3Fuj}yx{lWR-q!oW zzGXC#p^`q1yFRm|j6ALPt2-sNk{SCxqU&bM-&e-eTuZ!U;&6FaZX@2hYp7)%LUqfJ z{)`rF3bSZym_-}JEZQ3Oz4;I6N<6cwQWy7co392G5Hao)?4XMGVi&1kZ~Yo|k~lG?c~KdF=f&Z95ySK1@VtoOd2x7N#PGa0JTGE+ zUL2km#VkB84$n)dG6T7o!}H?syolj>F?e3Y@Vrd$yolj> z33y(_@Vo>(FJgFJ5}p?^JTD2)ix{5Qw>enMGmC%1Gg{2abBnopZZU_?E#~U^_vW`) z2jTF%=)1%7;_$q<`quEgI6N<6cwQWy7v+KH#o>7o!}H?syeMYjd2x7NR8HV|ad=+D z@Vq!YFZzz~yf{2BVt8I0o)|4bO|g^OA<= zrNQ%(hUX>Vc}c_b67amFx_@|H!eY;fFh3(auOIdqE%qRBi@izQV$Tw{*qg+^H^18V zb-%Oi6zu!r@Vs~r2m7V)yf{2BDg*GmI6N<6cwQWy7co394$q4io)?GbMdbvZ7l-FX z49|T+FAmR(7@il0=Oxwmh3CcLc@e|&;_$qP;dwE5Uc~UcOz^yj z;dyEByolj>33y(_@Vtb14;%LBrJDD)!SniIpV4AZBe&S=$Sw9ja*Mr={Co3T>?7sy zytw*a@Vq!YFXGrUHyAuGVt8H*o)@A^Q(R7>bqcHI)~>)49|F?e3Y@Vq!YFJgFJ9G(}I6L?-6o)K1rj9G(}Ijh}r4F&x^tHB8KP1;CT_l^J4J4h~arLcwWTt zycj$$Vt8I0o) z!1?-9`IR^K`h=YoJTC^%i~sUu&JuWD44xNP-wU3X37!`*JTDVGFJgFJ44xM;JTC^% zix{34hv!8M&x^zJqH+Syi^KCGhUdlMc~N@=&kJKW-T#8;#o>8TnStlU;dx1Q5AeJ= zJTGE+UL2kmF+48@&x;tI7lY?T49`oI4Ptm+44xNP=lPMJ(ZUH;bqKv%cwVY*p?40? zOVuI7@Vr#rLV4hY{i*yG9xj9DMeh@ymkFL1F+48~o)Z=gL^HO~hVt8Jv zuR;tj>`&#l@cK>gytw)<@Vs`y^CE`lCE$4x!}AjGyolj>rNZ+fhUdlLc@e|&V(`3( z;dya*Uc~UcI6N=9H+Wtgo)7o z!}H?syolj>ad=+D@VvOiZxnFzGs5%wVV}|BH!IW_hu$qbFE#cdhUcZmIK=S0)Yyj@ zUf7??kMSc{?_Z4{;dv3m^Ahm9h~aq&cwWTtyaYTiVt8Hxo)p8r7=4$q734W1W==S2+9i^KCGhUdlMd1>l?;CXR)UP3WEFAmR3Du(C9;dv3m z^WyNlh~as0cwWTtytw%{Pt7o!}H?symZcqy>Nw6>7L9G(|3JTDHVc@e|&67al;;du#oUc@sK+U$hqMGVi2 z!Sf=9=f&W85ySK1@VtoOd2x7NR8HV|ad=+D@Vq!YFREMMd2x7NR8HV|ad=)*l@oYg z9G(|3JTDHT+FAmR(7@il0=OtB{f#=2H zc~SaR&z{`kHy$m2`|*c;MvLG4RBOcaKH+((wPRvo)7o!}H?syr^!0=f&Z9QF(yp#o>7o!}H?syolj> zaf{!K{q|e3@VtK5XSDbYVYTOk-X}aSwHJjLo|oElLJZGK?L{Gm7xt&}Tl{Xbgy%)a z!t;{wyolj>NqAnw@Vq2EFJgFJ5}p?^JTD2)ix{4lfagUF&r87bB8KN>g6BmH&x^tH zB8KP1;CT_l^WyNlh~as0cwSUa;CXR)UR1Zh^WyNls64>);_$qP;dya*Uc~UcxW(^m zTmCln5BrQ3ze%q4u+ck&=cV?x5ySIRd)SEKd8xf^#PGuYRDO%!ftT>S=va7O5}p@* zBY0jCo)@LV^OEqqh~arjcwWTtyd*p?Vt8Hxo)&p+tFPIz9#@Vpp2FJgFJ z44xM;JTDH9;Tp~O#4$q6q20Skg&x;tI7q|G`e#_sw z|6!le;_o<6dt&Jw!t+vlWr^W=sXej8@VwMsSz`R12!AR+94N{U&r8DdB8KNB;d#+_ zf#)URc@e|&lJLAJ4?Hgk&x;tImxSj<49`o#^CE`lCE$4x!}AjGyolj>F?e3Y@Vpp2 zFJgFJ44xM;JTDH?dLi^KCGhUdlMdC`~%o)?GbMP&w_7l-FX4A0B*@5r$HyEA^+ zXSDb`Q`8=NdWZ15)ZTkycwTCcJuy5lwfCMFUf7??4+o0!!}F5xyy#oN^OEqqh~arj zcwWTtyd*p?Vt8H>o);Yp&r8DdB8KNB;dv3m^Ahm9h~aq&cwWTtyiD-Ch~ase;CT_l z^J4J4h~as0cwWTtyf{2Bx-L8~4$q4io)?GbMP&w_7l-FX49|Lk!PLxjf&MA3hYlPvt|w^CE`lCENqAnw z@Vq2EFJgFJ5}p@b7oL}d=S2+9OTzOahUX>Vc@e|&(%^X!!}Cgo=S2+9i^20EhUdlL zc@e|&;_$raTJXF$JTGE+UL2kmF+490&x;tI7q@sWOa5V>(V`3}2aw*IasVyLjB)@e zT{(l_o8KbtBs?#A&+xn?JTK}u!t;{wyeLlLc}aL)ln0)dgy%&J&r8Dd(!cKvcL~pn z7@n7e=S2+9OThCYhUX>Vc@e|&67al;;dzFPW< zKe0ML{v}q|#Ger(8^Y6wgv3|{H;!PVb+gqdyi~PdkJksL)(&D=69CRL)*Wx~< z#r?~^duuFJ_l)OK>E`EE`H78da+O1!$Kt)I>r%S9CjN{V*`)CQk-)_Kw`l@_>`@WXn-LgDbmJ`eJgXgDXjq>@eyjhmR1LN-4)0@)E zC&ikI3Cr@V-lNK6luu$66P9tI{!Bj)l}}=$d=eYwlX$>@?TB@~tg2@;vpU}5dH*Bz z46gTIuV?I2rvAt4nfWfQ|LgUP@x9F7SA8$@cUSEKG4gPWa`L~_+xRoegS`JsJ+GG) zy)68X?`5t(Rep1M=IR>iUetLk%D=iUrK>dcXDSc=QSAb;I)`O>+qe7YaxXK~=J;1u z4*qC*+^7bzLrM^HEmD#AWroenZ(lLu16%GhrFk*+B=@(abrd5Dek6C2l6=fJ;oKg7m;5*znV+#&Zodp$2bmxlW==NGsh zG0r1!Jz|_+;CjUBzv};u`$5`fVs#v@N370=>(TwIe6@~$N>Tqc(&>4P{LJD!#K!rF zjq7ri$G9J2bshCyRJyv3dXI`Ttv*l||0PcQc7NY*r-D-d=HI@rRR3>$cjA9%`K~AUHET(N8@{`a;VCSxxJ(I%BXMgXWz;vwQs5&Qu))vTDb?2&<OQGHQumikBz{g0JT^fS%v-G8M%K|fQ)xq2>okBW`@hw2TB_Rd^iQTq4RC+KG`!MW+XSaRBT zr1p;50aahC_pkn|-ml_6+b;aKz9Z%_)x3jLb*CC*s(B8@YM#P8cE$gyxi(5y^KRy` ztNO3{f0f_(b7FOzI$ou#^O?u4>N=Ry#5~-$bn|#szs|Q;m_;c~u^D z9n5JuC^FLN*^T_f#(AX5W1OGZxGpjNNZk*yai7G-{S#vz^V|1I`*!;L#ozSXArAEU zzW+w~G_NK6r^}~WKTvV5$~m6vKVF}h*Ak3+hT_qve~ABG^~wKSKS=v__&tvQ%eLVE z#kW)CQvXMfy);gH4{2rKKT-y$4KUtq8q7;$TzwftG z@oLO>(LA@BH&p*`F@KK#|M#sIV_uu)*DU5IrN#WYS_fCxQ*%nvV*Z@w>5X|O^Zjs( z`y{rQKbJr1dK})Ln%~7cP;27<;1>pP~c>HMwNbiS?4{WsP=($-S{t!t@i z>v0$y{T7unD^<;_fJkS@84^Ebw2hX>ihaKMovvJ@Au2LAv(pp4>040t||Z8A6P!c zyl>Fw+?{0eeysw1eAL*2w`#RGxooF%aYi~rdO7pHMC31LoCob*d3*CdMx5W?yhje# z#r`aP-y`nF-n<_Y_i1n5hlcyN&wDxx_A{!sVwp-;`?$DDM}D<0l&kzW5ADNL=P~+? zT%8}+Rr^A@y6(UBUzN8v@5@s6Y2L4;?jP5Ya5WtctR0ujNEhmPjr>Br2je_=&*jy7 zqkX69y&2b)>U|pbBh`C0?o+DwZyt-O?}GP-eERo7e*Ba6?f$;sZkhU)D5L71G){XD zX=UI)QwE~t=JU176<;|tPSuzHXa3eMnCoP&>SWxTxxM(GO#ASSJb!}CF|VHX&+xbQ z*B%F`^Q$)Ef5+-R&3XQh+-7nh`&uSI_Fq>|WN8@4o>mBu^Jdo*KW|79_wV>i|F(73 zKd+x(L|+M)*&X|7F+TCyyvdRBa^EG|W#3w+b?G8yx=v5D^Lwn>gJxlJhPUmvV`rSP zUD>W&0Q2b>AdkPVD_&K+X?p!3Os=%fDOOEx3Su{~}eNaZ{0~1C1!8+fuixXpNmZtRZ;_+hD z?h?eMohFHysYU*9>@R&Mij7)XN-yyt7Jv7rJ#i)XSTV_|Jn`p=F{0$@io~5}O%Nlm zR3UboK3??5P@Q;H*>JI-N=xD{eMX7JE8U3a#s4Jwzo<{VV}G#N(xNT#rJaG|^p^I- z53U7><2O1I4;wZ@?3vJ+_->THSUkH6akgsyV%Lj5@}6UUqC&5(lqc%yaFOckPTacY zP;tn^gLst9VBxgYi}+A*Utt^MO?=C@wYbtQlsGoPMcAzvLp=6(7ZDPrb82oTvKG*} zfLjAG^}#60v-43S(QJJ5AC7&n(phYHuIFdnokVG$pD54quJy#4Vq=L%o~bRWz1R8j zg&Lyf`*D;WvDs04`8uAs^`^XHa{ejA6YCZiNfYCV%TKZwV}FY!PI;M2`{o)yPo|$dmXM#OOK_ks)Q*s`Pg zY2&j=tA<;hy-^=oLwn|NhBasp*^P?0TY@wqt7|r4O0dB(=g} zJ$?7nys4Yd>l_yM>&^++b$%8+ZfA)*Iy()lvD5aR&bQj<+d1+7hX)S7w!`|qo~Kpz z)!TnI_(8RS&enJJ^lY)|UHB!P?ZRifXo)%(cXKnH$gAI5x2h9OWlQPL-q9x3blg$r z3vI`n&UM!LYk?@!bo}zP! z2MH$M+B#>xo@Dy6PyePJN-Z~aYN7M!MR!e&TI%0D-s6;s+s&bOc=Lj0+H)j<_<8Iz z)54B3iLHI!m>TcY%goU=A5H74>YRD&SJSCodbuiE-kLoM);VmZHM`d9kDO2}9s8-F zp5DYeJ=^<1FQ4nuXJ(Hp=v<~scJ{WKUj8TC&c~`Bm`wMu{O77H)^h@J%UZ51wDoA> zp9N>ff_2_Gm$9n1bZ*zznT2K7ccp*Ppn+Qco6ZHH3K0 z;!bQ)-2meEd&I6j1BI;husNB0e7y|wO?p0~g- z7Sr#Kye)Vb>;A4A<=H%FIP3ISuRoo0jbOdr>h*ArJb|oCR0qm)@k2PHqUo4MZlsTTc z<<`%$-#4Cxq!g$8BQi{49Y+-7{;ER^Tt%UP_;>}!;sC2}@vyW}@w&$qML3)eHmeLKuyyNjM6 zc8;6FUicm*Zn1C<3!d=nAGq6=Ic$pm5lWx&WDYyO{~+<#2?;Ey?rvhgTKH|>A=`*2 zE}zG2$1f(%As4c-A3G37l}TbxyL?Kew!T;rbM?2<^JGh64Rd579(*d1S)a^L+%Ptg zte60ysgSuA(V zP2yCP$!ilI5HCTQ^d0}1*bQYedVUtBp0Os%@R)YC#7T80vrO3v5?>0Q#EPCRO#I8C zc=n`AG2-zJ;#q?RC5RW_k7HI5C5erg`U4xWN$Eyx5*x8eY{Vw95#z*0>=PUH39(U! z5F2#}u~CN*8+8b=<*~De4Q0HD2c>`LGK3Xw;YmDl#bDMdpBM4fDL!mS^IpWhHUn6? zD}9J>qt3J&*Ppl~>daAALx{Jc&P=EqK>PxAY_AGo#CKhqu^i!%#F1KKmaA?waa?di zmOlR|;;P#kuqm3(U4M4P-<3X^(!){b4{ZHMHrfu#W3(N_M%zJbv>n7o8$@ihO~gif zM{Kll#6}xOY_xI2MjJ1Q zKBYUCo^Cp@O6S9uCz+=Iu5*0hI8*t&3n-7#C;0;#eH%(Q`ZmNy--g)e+YlRlBx0lQ zL~QiOh>boNvC#)3Hu_-1Mjwp$w%(T`zWliT&ak^l#NC$9+j;et&c*ZmzVq1?o#!>Q zPjx%3^V2mwQ{U{?x$Cj`)W8)wPyg*!>iecT=Q&kO+qgB6&Uq%bsdnuBLgL>hcxpZq zbv|b0qXjn7xw&(IR@_==pR?gwt0Ve5tWbTFHgT!WMxU9^W64I}o6?QGH?h(8CN}!s z#6};U*y!668{-9HV~jv-j1h>9F#@qMMj*C4cKe1*BE)4nr4O!{MSQq3jd)(4Y{IIy z&b3PC6l=CkrSw4_HX_@TDa39V6HUvnb2P?8OD4usdU1@2Cj1sl?2j>2I;#o9pY3aj zCo$uQ8~;*AoJ|=^{GnuhQQ`bg#HD|C5?Sl$Jk1tkz@uX*-53x4fsL^tr5j^IVqW+wjWH&%G4>=j#;_tXBu(Wwii*S|Xu>0-(eA09JNRA^t8*qE>QBkOY)ly1yj z5F2wB#KznOu`vfiY|M>N8*0qA5F2wW#Ks&8u`$O&Y|OC`TOPYUEJ5_Uv76G1ZBG!v zM+9--d~-$SqC1E;j-D%o+a}@~R`bNAZmWsa{L=GcDa2|XX}XOkv6^4Xb|IQr%{zUH zo&JYBH#}3y&Naq{$9{7+B`jPhRDYoP;j^Y!g@Za@#ariw4`?_C`Strvb zQ{gdlDUWB-ye8kvdR-TPHZHa8O1%!u{9%&z=z-oY1aE$$d2iI)qg+}gQJ`TA9ow}@ zS0V5C5r5bjE?WAvAYME^UOZ}CoOt4f*&=_Z^K{Ra@4N@zrPcfR9qRs%c`g(Oj`pKx z&;E6mxK&c`^V?;K6T{+43zcWs@*t68K|A89``U^xJ%fqo&9oDaZR3cCX1k*8aMZuW zPs4g?$s_e|WO>~T`4h$TbZ&G%)p{g~JP|dBGc8XPU1LfSyPQiD+M#^J;dc_nrnxqM z;8~9o#k$V9DBa3BNhGIcA&#z@BpmNOr+#t+?<8@u`BCD+T9SCuX^17$_Z@}vw@I+k z)H53ABsR`TY@Czw8|VCXY&qjtpEHT#T~mFm(PK-Zh_6tbjy>v^DE1zyLfj%(q6q8P zka%)cZ$A6;day~NK?eq#6LdGR(pe(9+NjDP4+fjdpMD4Q4W z9&lc)%r!wYJQT>k6g#Qi?-?eB+XVAMOJ15*Z|@=euJq#@_MBry+uDiE51sh_q$+&P z*5#V{evU@wS!!l0tLZ7<%W9@ytwrnWwP~F89@5G{S{Xd zB-c;05qIZbVT-5tmJiRliPc9+@>M1-x6~RWN}g)UUskb|PwI{qqZaq$gU)Xk*D_BK zvZXig;k905tS~_&op9pbPGzLn6)tYi$iv%aX(?|H?kP5T?_{H2`N&_-)D){z^RSUa z!{p54AGN1lcWFUABV}OaNX@(#%gSn@{r57~xdhfUO_(c?J+0@9Hym1oL0aaow|t(+7Ppx4)U=r^u5_TeG8vaWK@{nIfYKASIU=IS5#kn0=ZJ>o z^=rAwg`&^%4wN39kSH?Sl_hquN)qkg(7cEIS~y8utY}T?8SRq9_=lhA9xU%Cab8jG z`KB@Ni~VT};*0W_^i6mI_NUpmF3LYSH{t8BAFNn~qP)FF6Mh~0!EV?U<(+yr;i=d& zw!d^yKBiX_eiVDp(zUnZT{d**YVR3eyqmQ@G?=TsXWG1<*{x;)T(blbh(5(GH5kYTV?HExVIf}Gtp$(4d`P{qZrtW` z37#JFAyw1$=E=v-vg3~ii#vDyxow1r6~}x?`hY+lKca8_@x}SBSfqbw- zW0RT-^2Rx*ulnescrDW3mT#;n-nlD~XO0|`syG#F6E=qOsQlAbeWdh9`vdufV-DZ= z;xPxxbF|7qQ?*|rrE|@_+inm0#kAx|q`Z42fBoUVo?sy>21=LkjoRiO1$pMiE#K+xFrnVsre8K%RBGwMoV1TfCFu{w++I z5u2}a4&gZ)O%sa|n{0YlZWr@OOhar&?5@RUEO3++5u2ssGV{sTyU3YGKWYa*En?vn z{N)q-Nb@_9_`deW`}x!Si(WoyZ{$ss+m5}P&|b%dDCZN>H=%u)4k+gzotx0U$KojG z?L3;$zQ-iQg~yx5v~SZWpYqq%-^wTL)ilZ{?bS5OC+*cV$|vpBG~aXW@x@mfF+%$@ zjToW*nMRDz{!AlAXn$ra?Cl)XF@WN0EB0#s3RZDv?DM2pGxm8>tQq?}Db|dAo)l|F zoyN;F%2D3TCtH5ocS^Bl>^r4cyQ1$qrC2+s?>nVfYlgk7R%HXIu1K%%Wu>}emcDnC z>WatMJIdP!P+eiZ7V6cMzsecTc`O~e{uv4y_{@>s;?Ioq3Tp=U3i z0kQeSwluF<)x=LAHrp&}!7th7;w2E9&s%u&#y!?E6`S{x`tkM`w=)%+D<;+BZSR-k zcMzM$y65J1x3}WU5SvHWOk+Mz{CEMx=CUafshbN#@npoN`Tm~_ow76>^RBZpTw^Nk zjCoh$S(v{a`guLE7v^jW*4s_I7IU_DoKFxN^SZ=pZuZX0y~M_xE%Ds9pIEJFUb5*x zxy^OvCw6YNmt31zu>N9e#&;K}D943u)God9tLibr4zXD`dkFs; zlvitm*gVn2pEuavf?Y*yX3p-#YX_faR}q`1tvva>glkO2W~VlRy#19&rrC(i#FoK) zxyKbP2(ejlvM--=cD49$x~BM2za!_Ba>^`-&7YoE=5zD8$dTm`oBDh*yqoFv-^-PK zym_K;FMj0G??UZKzUb@4J!?D?YEN>z z)n5Eb(cgvIQ*FNPJ+vJcUY6#QA2p)b%-pRy|0%dG#pa#1jd<3Xb`+b7{M+&KS#0#! zH17Xls{P76mD})2bMjJbzUo$w&&*hjV)MWT2VPoprPyrgTa=eC-jZT-Tu@cfDswQ! zX6Nv#qAFO$rbov)Lag_r*xYmdvUsqqKgH(Nu=Mgm4iAdW4`uVnM>9H5Y|dC(SuRa) z;vcU*S~lI_45(*XJjo)1&UB^N%+c$qNZ+G3#b(CLJB0OOUy99sWv7a|yZtFP&%CZA zP8A8J*sRdFvWO@YOtCq7P8HEDS1`q9k*-z6ge<`no963&{Ti0?SD9}JTYAU+SFs_{ zhhnqS4p-4(PcX%1UOQLQwP&Fen;D%aFP#xHqYj% z#5dop&Q)waG#zFgllpMgZWh|d*woG=som^V=c5*PA(R(EY?hJd#7N%(dzGz`B;*q&Z^R6YGi1*&E$X{iv zK|Ivffx9fKO?$ai% z)_*C4>erRB8Oc}2j2Fsr*pV)TKdkO7RKL!A>~53IN|!#t-1}imq575?(+%gdmaG)2 zZ)r1o0N=3lyik41DRX-9ldE0{)wdk5BZq8sp&i9$z|I_U)%kW5n~l1bmtW?aC^j#2 zbd$B7m!;V3Sf{JOzjY8@WKGGrV= z9JqfiOPK3T+^KycdpE#`c>UTbEboiK#G3{zWvj{$B<>eIpT*zQ^IRJ@o%J83=eeFW zl<(c(A#N8sv+dmH5I!~DQ*8FjS^rr~1m9TolBs{xMlDOB;XGTbMeG*Fo7wkt;;#>6 zNax)4B_Pf!G|KDTZ|}JcM6IY}Rp&W-nV0Qf#(-;4Kf0I!WgVm=7nZ*4`3d93G0$ljGRFm;{|U!vrSF%NgXnRjBD;@RM}c$TmX;qus`icCF=-;^LJ1_m+p zET0Mvl{<%RU~2qW`b|Ii()u@gmS4+umNt1ZQEYap)>-bg%0#i5+PkxqJ2Fyi+C_Ah zNz*e@Y?`lYWmTxmU*+1aWgHSd`N@PMiEIe^w2O*#lRnAmsNHNoqJ~U=t{TsXK5f7` zYx#aoCw>yK+1Glin76=}+RahtI%pq#11UCrPsD4{ub#6FYxQBr zw%x}<`K;=#+48bQ>OTtgA zgG@;NUjAfTn=j7j$W?6K%3GVC%izdWY<62&i#vKdauu8PAJ*b;D>-r%n+`c^^8wi% zxr)tI^J?*(BOJMkO?BOtxQ9rL(F!ja!l(08D$fI2_UH2XH7d_Nx_06H_GjTLHcNOn z=W(fpsjV^Jb4;lcD?jFM#hpS5PTINqvBX_F=N%?rPKrsP}7x9MET^rebqe zs|Y#xx^z+XOl}?```P7YYHsSCTZqhkIu}!OQwutV$aAA}GBr1q>KP(C9mv7d+?4sc zR#w^U|0*Y^f0p91FG8L?bwC@2*vuCaCOh?dXNtpkbI*%Gve}dMEE8h$TK?9utxryV z3bFYjq_ph5%88dmyE!7}x_G$9gJN@E(tWXTMK_Ag#x3f}#d_LVjdv1z`4bwAY}WR&Mywxzi1RyLhHy{0|!nbJ3e`vMQ* zZHu0Y4YDiojH{o;vBe#U3uSvC>cw>I8upuCI<0}=+n-AJWiXn zB$#(VY*q@MCH8F@%++{P>z+>Tn9`nNGu1JZj4alc`m|^Ed5YPW{rEz}=F2JvozI;P z;iD0o8!ra3Cfx#f7W8RvCOu-kPxs;u=+nM_SDydAl=F2MZ|14mjxYO^4^Drxl<(yk zfvLZqm=wp2n>~Pb$dHL0oo-wOwxJ zg?N_votw$6S_v9E*ICd}rq0YoW9NzsddoSX4~2@&Gv|C{YN5TsC&T=YZ>Dv`OWNMyILdB-N zr@u78wTwq>Hait6Yt8GYWkziBYXNdtzPjuTV$<29mn?es1XHmY_<~DQ;iCL5#+$z% zc9U0P3i4GLZw`7rSPs}dhdsi0bL0D9>C=3TX)R(iq*|bS^lN`n2(h{RNq4#HeL9(d z*figNrC+))wMl6sN8Zmwaa68KE173uHsZ|{T;B`2}l z6E}I(y&$ov2<9d$E?52EtF&iB zW{2=*5gWA?lBISU9KnmCPrK#WNU>_|2tE<9X_x*$X!le8()v#MQpC_ z&`P!+l8wfj#ZI@8T4E+@H&c$}lQW{5a1F7Uz1Kle3j6jRAU5Y_uPk142@O@ zR#4t**;sJf#K*AM9xy=och^9y->g zIm$-lu%Yq`JeS8P8?$B(llRZ~(mdg-(}A-5Q}}Br8#~(i%7;4^2{qo?6VqJgTY#}Y z%Eq9bwzA^Jb}|KJ!+ifX*T*?LTr^C&-XBbJdL7l@d+6awJZrF@jFPR0m)7-{U-FxX zf0^VjFTSfy9Dmba*8Ht1@uwOiWZA6_#Pcrt$%wv}7<%Vg`@JN34_=)W;l5d+@AW!}c8Q0l2YAg1o zhVc38)@lU?922Fc4&YCVWR5lVfsNec<^%&&ysPE7CAnHd@Q^0 zVs4ei+RuLC`Q#w(T5gZl{&NSpKU;d9r&zG?we}YWke;#B9oyD)hx(2X?}LJP>BD=pbK!Y0pU{$< zoSj9H^&MsC1#9k_5G=~&8X+!61aZ@>J=)YRdFArlt+;zOXVD;~qb&T$n!k$)7S8cp zHo|)6`I6qk#@bcd)h)@3jrJCoUfaocg7YWinu|KmTg$s0v-6wlMu@e0Y~}UnR@{1q zlPGDIS9Yq`inqMuB=!x?E6;yv$(NUP7E`xu5L5OK;oHA{(Uwk%6|2*YeW?9yZj{Nj=qtu9i`HfoilVl)&cs}z_o{GeTZ?-|iRj{i z)V4l(xm1kHF^t;QZ}*ll=gOg0SHy#seWxA`0UWHLkp$bE9@U zDw5jS<4upGPFfwM&-r}0EXK9!Lw$qseXfWv)%s9>z$*6@Vc)C|^#}6i9VSy9b84&W zZxM>^z^lOd!AUi9YO}yOz^*NGYLVb~w!`F+kvX+q;FsXhQ8~4q|6-G3BacbtF^)B< zV~ul~)H#i7nbft6doZbc$cJkM;~tj%i%p7O>hD>qHoCa}o~3G|-SLd$TlJBu|L`Rj zJ(pB%^jQ6QrE0r<@eUuh>?2iw!+3{M_5Y1`NPP_B9a0~|c!$)-FusM{*J!b$@lB=s zzrLy7$I!ni^)X85-&CqThVf0M>i-{Hc-!RV9Vs1pm#X)F!v}oag?-Hs`K#w9tx4(` zao*Zn=5)=2-%+V3+YP8IFV^TFQtow=jgCDMk8?+g;tfW~pu+aTzup9~q=CO&Fx^G$ z&M-lQPU|d-W&14ZvK8LS?a%%QVY- zR`s)OjR>LUrHyuh*a3C;^IN@$=b~;O*S8VzN7VT>w>l83HsW1=6R~PL!euLB)uuG` z@FWhrl^|TL1Nit0V%xmn1mS2Kzz@_fRDWJX0Xh77Yd#Qt__OVqT;$=v2ci$3-^ELs zQXjHH=qLEC^^?n$Tw@4Ou6hU)cE@K@S*bL$Vg$0@pYSg zK{8#s4JJ?Y6GZVLGPL)6RuTOKpZ1;QrJ9-eQjD*?+^WlNR(1GrjIXQbPA6j?d+-Tm zBhBq2`U#0CMqBx(IpMRb{P~a_#r3^Uu5!v@JBrgo9U4eqcRQ*>0!ucK+2-3(%HJ*sES$J#H=v9kZiin6xJnd+8P+jGlYqdHLClK0VDv8`WEs#`M5z9if~dsE#q zIXIWrVs#kBlxP23+7Pgc!REL3n{sy#r}(nU<;Pwv52E;*Ryu`knd3+C<=cB7b1m;n z@n!U{?j8-L_)1r7iRola zIK@}(35B$*3&W^>$kC#pc0DnS>W7~`=F(2A3Zpt<^{YHu^0F|h6X1L?{5}uuC-G@G zlO3x3oVacGsjOdeE~fUkz*%GXjU8gk{N;a{$!s$|qWrdJX0uA?&JuTeG>7@zI7r;L zegeB^zn}PZn*>(6&_3dMsZ*G%T^>4Tz~^{&Eukp!FYV%3!Krq{)~6@3w{H4%?bc3Y z^EI6<@5lV!&_}iZtK4kMZw@lBHA}ZIM83utn>f<&m6b1yj)VKwrqrcW>xgJZ!E|pRX_7oyH>LA&}>qzd2PsSE4wajCU2sj z*{j`Nq2=?WJ9<@?Syd5TO(9dj|+?O3)7c6I?pJ~4Ty4p>LofvDxTqq({-J-@6 z$J`4NH^;bRnP)!Y%NTbo-;$F!AI2=h?q?#l$C$-tVK!nl?pXdf7qKxOA-?#ff;>2o z^T1WRx7|NeL0V7ZJj0s;^)J-zA&>0*%$}ic(VqIrTd!uaxu{#b_Jqo7N#jiQP`6C^ zX`~#UtCHx3y5;9ledNuD2ZWj*n1S)vnTZ9ZT93AU#pT{YMdjD>SexEANPg~|C|psu z3|SZ~m-z3~Y*4qn9vLD_yXR&LP`6}zGgz`Nscb6hmQ{_~$%yp%cpJRJRyoYMNI!#?&+yZ9aBO`m!sHaXrn48{>MaTa0l%)h))jp6Zra znBQm+>qB+RZOm`nj=@+Rb&E02Ky`~T&p>sHG0#ACi!skYb&D}aA#I-=UG|MpPa1O_ zRJRy&9aOg%a~)K-7;_y|w_MZbOsHoF zJ9pxHYyH@v(Orpq=kjMu3+a4!5awAsgi?AynMSP48Tx$#Ibtbe53ka17s#r4OzfGT ze%)R3U0Bb#I$Pe4`CVCAHM0M!yfUk1KVuB$-kP?RZ&0^fU%#Juw(+65W&K7w*63A` z3`gB^W8gw6 z%h%wEE@N(m$Tg^2(rL-;?%APIt*4JGTbQ58)=H|qF6R4x`gpeeJWXv}nTHKMi9_A`fwropm%vBN_^Nqyq^?69*z79Upe#mJSdiU3D z^=*7)z0;>zmRfo0A6XwE8+18t%8osvWwwRM;KjddeKEfg`)IJt$5xB&s9WaVX(L}h z&L-!fZYk8rURLn0D<7h6X}Ivd=)S6(RO{)Zeul^||2kmuH^XiQk<0GqeMa^kn8l98&x~MtrZU=G*wJxCMzz5mo zroArex|mC6FHpA_bLq4$V9ce{x`3KXAJ}K4Nv#X0xpd#_GFA1Z&G%e$sqIQNpWij$ z)=rE0d|DSU=JRP?z?jdcb%D=V*I1O%QLkI{bq%UpjP(VoTa5JuS{E?Z7ie9;SYM!Z z0b^}K1Pw1(-dN)hNq81xjf2(&j5Q8g7cka1sBSUVIH+z}jkS^;BOIx2>5jFPs@{%N zw>ar*D^#D9$J&Z_c1Nmb%-6ND8dvVG@;&cPODBHx;DugU$ybQY;x+2?R!=I+r)c-P z9?Z%s=ItOu5u3$lC9~Ll;&1D}6Uz~s=KELo6P?#xJ3T0n;^^Z# zT7x65nYdcpd}buEd&Z~Q!FK_~ZLr4I@;v5c&`%hIHNMOddU`E=osQDm>FamIp;%Y- zZ-34C&h7o%Y{6qXestb7JzxF3t^H-;3=73Z>~-nzp__DSVJ)wt-G9)smdsbsQT9P> z9*@o-zvk&EeG!|%lM+PFI)mj6#Ad&}@!I4Hfz<9V8r(@+>KiDBqTN4MVXyGW-%noN z7A{_u&nH_~XfEIP?kO(KXdtb6*~x>4u`Y0_A*E}-@UIEAdDbpc~tp3Y;e%WD?v@-7zZ z@+P&OZmj9E!jD&#H}(dwxmbTR_6C?N_6BI?y#Zrw3eviOu{VI8MeQ*-v1B!^3*^O~ zgi_I~XKlb#LaF9Y@o6`P-nL~`%Lo3&MlP4oS$ z`{{!{Eeqy)Qydw4SBTxPzvbfqAL2ypZ^{2+F!4j|jj2HamabA&NBj zktGnD&5z^|9k&L`)`-m((+`@;wM9H4Hs@Yl%3=!)q;_*tuXSu_xVKc}{oK=iU0iYo zONMr{(cRACO11!*3GHU-u2)63Dt+X5^vN$`4fJK(hO#O8}W2oRFpD|oOFAh-k%?g0Xk zucy~Q&G+8rzNFs0uj+kYPSvUNJ44TZ^_uCP=_Rb4v}jzpFTKZA|8`5x&5`sT*PdG~ zIXA!3J5(hKICE|;G~c1(-1MY(s1Dw5$+>yneCLXDQy!Pz-9rE7f8O2VI##{A#dWND zcgv9brh0da_nO~6CpwdPmwJDU_dE6e7}wJ3{V}ek)%#;yOUw7@%C4JZmG{u(dvv$9 z&aujxT)of6wY_?ujrU*mJ{#}9>U}oef7QEi!l;(9+;9Fw>x_D*j%xt*P94_(>YX}% z*G0Wk$JZC~-8_$l)2;G;pnR9lvHT3HydNmv<=gvUmQ~*Olkf8F=sd?N?+1RTcL>XW z$tKdJzgg|S!vV=gio4xbL;Ddv_Pj&gMax?ItbwUBV%-*F#YB5{Tp3sogJSxKX1xuZ z`DPHl@U1V>hh#QhSf*f3k6dESCSg3G+)Pm*pE&8|XmmdsBYujx&_Jq5b_hpkKS_@#8Zo|b^M{l^Zc86W}e>%Mjy7z5a&Lj2CC-WV8FLe8c z%FILPy--`en#_smol?hvf?2&&%6#5@FVwWB_eC8xS7ElUC~YjxXf=+`IdyDHKxxBx z>u8ipnzcr^>_IrY-T*Z6kf}v&39!4X|&0AX08jhKb0r;IW}DK{HF_=zs7x*9p@?^dYyW(|4=xM*B?lKK8K=VnWK z|G8YUv7DQQ%y*ADH$BXEk2yE9(!0mAl8@!w3^LzU=G;{8JR8fY4pi?vb8f14o;f$w zJI|b(>YZoK&EGz!YL$1FdheQZQ@wZ1xvAc}=G;{8U2|@hqW8~})PBqFy2$s>9qYd3 zcU{zb;6m2M>OFA2?pE)C^L4j+51g;Ne}AhaxapSSzqtyXi+UHGul?1#=zQ(3-bEMk zUblJ|UC8=ezSI6G*BgG#g}w)f^lehU zZvA>-0=E3ofO+fi={Ry|WoG)GA=39nnRWYG5$<@nFn<@w$Uk^AwiEo#E2G@YVfeX+ zdAk?`zizW}XMy6(b@R@}^tB3__G{*1!+H6c zU2ra5%V4tZPyW?T!l!2vLq5OANo*&U&o$PqbrQL{B{Af4kUVRgM6(`A4EY?yiEO5l zjeHLBm26gbO=8IBCZ5$CMc|%H%%Q~1h-F{T8jhmku1wswcTGo;WM?MsJD>Q%j!b;4 znZ(zKr4M;Y-DxJeZ$c3s9FnmH8t-E(Dwt8zO~Ee_`H2K%vfjv z^R?Qgaa<1m7L%dd)OwN`1J9W@%^Ie}YW?`TZN{n$iE&*Bf7{K-&>$gJsA+1xKb-)N zwKMtpin4g8^Gw!1F_hk`$jsklGhz|}HqL3@i>S0p;LPc!Z+lbK!Vz6eHabVcyG@Px z9QP4_CYIw|vsW~DZ)nV8b*O7Jq@;E^&Sknp!xdsV&UJc6Lu;~;`Oj;Bz-xyL#aKC+9lJs z2Oa2J(0q=IXYchNG}~m?*46Bt8t}KU4Ep||y>Nd1cAuf!Z|JwuKX{{QUvfy8U%iJW z`=z|#yX2+GXGCDle2NcwCv!Naj#a;D9s7n%rhfX5!|YYF@HYdE&yS|rTMsagwclr! z-KcDG>x;AP%Ziw+`_m|WGT3!%FrQ-~;yuK2oOcvR2DymkSmn)@48{=4ajugg8Ehk# zW0j$BGDu1+$2r4-N!C{ThcLfhGRfM2SoSTrW0Ey9vF!Wu@FZ*az9HPV@X<-ux5V;T zw~kD*z9W|7TtoRF$M&acmrUOk1p0L2-G8QA2W7U9cj+2cX=Q1BAV}@LPd2BWZEtFyLG6-r49sCPTU?E83J^CS zmVMt2$YG2lmi}DspTiisq#7UVY~LJ4@nzN6hZe+hiDf+0m{Zg^Wt3t*Kf9<=E}#_K z+@D$0NOH0i_q{NqsFC7SDb`#1w#QI>_9J zcwOs*Y~vJTGiG);$bEgHZAP8W2U&AD@fl+FllTy^^dX9l)t`H$tOzX_%YSxBe<#OUJDGvZm}?yUYz{)z>PItNJplz9yT`#ZcO) z=Vi?5IU4J$=Vi?5xfR=VzdQ#V+ZAG-M9=lSOB7%(KXpE2-Iaq`JtJdQ&)Qf=J!@lD z&)S&Pvo>b+tc_XsVYB(XlApH@GoM%T^VUMn$Hb|yf@O6o-HQd z;Kt8e)iX-5l6jLq@Ht$QE9U6dQo==xMUkH95TAw zYjo}f&$^5i2Ya8huRcB5I?CH!JUN;TSJ5-#<>w3Vy-M|bmTN-we3olM^?a6VLiK!> zYr@~}ZjJNy{rzm(7(_m+XT)5Ws%OMpm#SyPe1B3sBj&pF7(Htq*suWKpA4jD(=Htf z@cqfr^lUoSx&nNE(wCl1mpfH}?@zvhnF}gMK<0?bDUf-matdTV zs+}en%xbS^R(n0O z+UuEhf7D*d=cx8jK6ka}@>r=om&Z!&xja^CkLIyedpEP%>$$Jm>$$Jm>$$J04ft59 zW?&!G9?fH`_HJfX%d!8e=44j2D6^_LnRRST$*gKfW>rHntJ;-W)vnCG zX6?$XYFB1eyE5zksM?RuQPqTe?y835u~Ic8kCmz+d8|~;$z!W(QD#-Ua$i-ua$i-u za$i;J^08D6%s!}^lgC!oqRi@giv1s0t2DmOF^jnbT|?C?#J@T6`?`tSb$fLk#O>-j zh*@0+F{|q!W_2CJtggS9)%6#%y8dET*I&%)`iogz$1$sG89qmKjl<`zu8DZ8)HM;0 zmAWS4u~OGiJhtlEidkKYabI;U#(mYb8244zZhS0tO~*c{YbYLDb#2A0uC>``bx(j< z-78>L_XL=Adv%S^?dlqzSzY5Z*D|m1nbkGE*>2ujU{?1QnAN=nW_54Dv^Vc9Fzf!P zYjZwFbRtpNOWmVj zAJjbo9$R&r zZwGO^`gRbr`gRbr`gRbr`gV}X<~NI&eYm6HE2Z>rW3Nz;=_Hro9eYflzByu|y=DuBtUpFbt zeVY>}YF3z!)q?mz)53pzI6*$heNeW)r*_HeSSa^g{GFm`Mlec+8}abUbGHU-|#aA8PYqmi_2>%uAe1B>&f+e8H%a%lIzUBZ9Sp!lj|hUi_Y=$_^;U) z{-@?q&6kWr-j~$6%KMdCZ|Tqe#3%1>avzfR^1pH)lC14_LiUsKE!(A@jC;xQUy2o8 zuT{H@&)@baS=;Y^>vOw2j@&0qoj?2CZ$G(R->>-F!r{kO#@)tSHdJI?#x zajWfj6ubYr^@Qq7ndiUPnSa}QLUktB3-VYx$Im10cf1eC{XmY7{BKCDT8~twT0uzj=iXk6iVb<$vY>O9S=i%(9>C zFWaS_)RiocGr?nj5lN~YBrAJnr6Xj!(q~r3Wu`xp{xB;)nU(*{hY#J~O2_-%4s^WV z_CUvDCLQrxhx7#NNqI+c^Y4#O%DX?m zSElmucRc@F))UIRZR)(_I>Y%W^X7M+s(cdC=D)L^P~QESFUq?=ta6j}Rn9Wg;r?Z7 zOZ?pZ>*h|zf%%V_d+{7U4)HPYZ;1h3_tn_OGY`bX_;H9IhyPX#oL-vEKKx8&c|XLc z8Im8ndX{HCF?9~^Pf?8d%e0fYa94JduYAFDSCcR&_>tC#O!rXUuQN7<WTArd*LqTb1VH>m41$y zhq&9paQoCJ}!ukJ#509RQ88;PWPM=^EmP}XJZ13WQ*%}vM&OB`& z`n1Z+Oy`aA{N*{8Eqewp1ZQI|w*3k=YM7b1%i}vZV^MnMwKt#QzCEd#FHL=i;p>t! zhrRrU8+#>Yru2~U!7SV4pGkdbEBi>68d6KL)RxDPERQLVEm`^^eUhx^h*|nB&q21! zb2?1tCRv`VJZH&r4CGiymSZEwNU|I=Id*JAV=2c}vK(VM){^De%Q=uN=S0qpWI0!I z&Lqn@lyfOr&aIqd$uh3x+)I8IRoOUFzOlc?9EZxrs`X`7n#}50%*qFl_R2SA4`%WW zC_b3UXQ23CmT^Jx!A$1}6d%lV?m+RuOt}J-Gt4wrK=EO=ckzPXV@P8Q6d&9!*Gq~I zW||A2_+X|v0*Vi2nmeHQV5T_*iVtR*YoPdGrWgQ<4`zxDA^(-JA=~7iNtU*@&ZT5Iw-g`Da?a)4%XS$H6d$}+ zDCRXp+1Rzd%u1749gA7{fYM(1#;km1mT@6tUD~K~WLD>H+L&X)tj3C2jUlrdTV^%p z%xW%})f_Raxnovy%B<#^S;YXeiVZ{hsbYp%#S*iMF=iEe%qk|CRje|r7-m+n%`D@B z&W%~+g4u572(!u^W|dRSD%Y4*4l=9UWL7!Lta6!Io)82AhUK#`Nc^T&Q(CJ7Z#n1+;JD3%jf5NX!&D?hy?CO`QEj(B|ENLb&jjO-dAVc zhuCnQL+ymCODgtX=W<&;Ma{15tn$1PMef|^2)&6fffAi;W z?XR6&#rr8!+2?=2>_6oX=d_#)X-jtOzs{;}tnKx_I{yP7{^lFE>v^ZMI$!oj&o7zN zWXJyN99Mh2ugH~YV}>psMW)g19S>-@KzrMX73`yD@jIIi}8)6sp14eNQQ^FPU1B)i}F`-kId zPdWRiugA%i# zwb%RV{5OC8)=sha59?uy`9J%to?kNdWxPuNb&jjO-dE?p`SZ7SJ@0h>Th7Y0N1l)L zU+1{m>wR_BeTWU~d8hN=a#pVWGM=RWI>*&s@2j)!Lu~jz*&s@2j)!Lu^>jJDp{W%ea(& z>iH#WPZ{g7UFW#k>wR_BeTXIhsez?mQcL%6c?e)Go>psMWRqV0PUpYntXdP;f1TrMulLni_aQc{=bg@f%UQK1v;R8B)n4zbv+hG| z_#fmQ$GpBL>iMPiMD}0jxZ3M|b^b5>(S2jq^G;`V?jYBBJ-<{-nW>LiS(hxZ3M|b=G}|1OKObSmi$Zspl6ROJ3Li_WuvZ)&6ff%IE*& z&)?eB9Pv2otkz!kQ_nA&Yx(?w+jWksz1~-6-G|t)o_9L`lbn^;p6oy6-5-vtz1~-6 z-G|t)o_9L`EoW&iwR_BeTWU~ zd8adJ%IkObQ_nT>Q{J!RcAevDulLni_aQc{=bg@f%UOyOdB2qX*Ez2CdS9J&A7aCL z-s!CGiF$sKjl3t!{_7l9d%f>}V0nN0xBh?0bnfy#!|(C@!?dQ!`x4x)=bE&Y<0bcH zo#Se+_tp7t{`{?-Vo%=ZVSjYi_e4Fvq^*os>A%i#wb%RVtoslf*7Hv1zvZmVX?Z@< zf1TrMulLni_aQc{=bg^_o+#r*&aw1auKhBe{v*fL{%<C39MiwQScpuJ(Fgopm2#!+PH7EMr{8 zrSwzJFIjuaSeNZO$JJi%tF!JyEcs6jEd7#N(l@!rNWUfP`K6A<*Y!Hb)n4zbv+hG| zSjK{!Kk28=f6G}l*C_3Ej;p=iS7+Ua*sz{=I_rDlKgc`wU$ryG)n4zbv+hG|SkF71 z|CY0A-D971j;p=iS7+Ua*sz{=I{z(aRW7jqI>*&s@2j)!Lu^>jJDrs#$T-*YOZjQY zcAevDulLni_aQc{=bg@KPT7Awzf_#C|2oIjUhk{3?n7)?j-&a{L|%j9Ier}CV<0{T z;$t8_2I6BNJ_h1rAU+1-V<0{T;$t8_2I6BNJ_h1rAU+1-V<0{T;$z_dyBOem)@t74 znFnHG{5ZsqLwpRx$3T1x#K%B<48+GkdUhn%4Sjdo5?f;ZHG|l*AJM;hlE%)~MoR$8+jMZ;# z@ZU4ke%{tZ;wSN~09 z{kM|!-^x_S<-fnxB zuA%)#ry-B0{FJ|O%&dOnSbnct_A#{I=rn$xulkMS-{T{7n3X;=9p}$)E6YDOe+&7~ zZyZyfKmIe*@2kq+h-QwTyFb6LD#uXBvHIUKcY`Yp5s#Pn@!z9q@nxJS)YQg&cZR39 z`_h&Fe%Zy#6NDF@;lC^Ad)`%~^P0$iA0%SiK(TSxCFa!^3d7|c=HLJ7)NUEHe>jTQ zq24n>pmJD$=Dyy^#HCyvnOh7gC?-9u&-|lKP4R4fIp(s7TL{lpS(%^h>@MmK4`=;v z4~B>l#g8$svWycK0$rHD9GD;`O$}n-?2kQ#)9WApa&0Pl(Otm80w_8E;n5<2v4FYq zvVmfKg3HVun|BuN(>DG|hQl*-aCa5BF`7uq6tEqD`Kib{Z*tRN?&qcI% zF_t_vm=peVHD-36z`VKo1S259C!WU}5uU~)qr0O#-w{1LjP$uPg5)f|V~oMeW-=!& zHrUv;^9=KX2{t277mJWK$9FY0()G>F+#qFT!ztSQyWwZ7IgR?xO}RZ+!$|yfsw;Df zawjk{lMD0tO;a#eAM;xisjbQI(+Ll5-*~5m-|iUm?>U~2N(f7zo9$bhO@*?}P5Yg< zPs9CIgW29?mqko(Y5u;dPubj}&&|f%esNA^alym%=ib*w;;nNYZugnoMZ8Lxkonl5 zL84;NIX&&P-ft!6MkKjqLMS8B44t*m3NTm+x@$TsBqPSl8;_>6+`+?WNxzE zMeJ#b%*oukiF)=3W}8DZVI;|6Nc)z#s)^1o&G~A#JCA6(w-L8@_DLWz`*dNx>ktSd z*A8O#tvClfJDc&4J$-iQUc!u%3jtdkUw$^@r^e7{_B8#>xbo>T7E5(D<1I;gJHksB z*17gF0`Cp!#=P3dZmb;IjJeS63PzRYW;~x-+Q8V@DnGZ^bLnKXosxt(RrCO((EclY zF8zH*8{&wWFHYG!jLIK!aQm^Zo<@!YD>=V5x=b(@tbD?GH|yG1WBj>cAkW=q9cm1( zdW6}S*2AdU=ri-#11${ujx0jjge9tJ?0anH`{)D(jO)o7aC@SGNeqAYPR!fCT*1^I z1~6Y+u^4+a9L?M&K{1@Y*qwRkwM_OFH_Z46`EbHI@y-NpA3UKSbn7;bxqNvaC_Hp1 z^U*7xVR4Th%n`0x#Ht%Dm|bR;6)_DQnA-%`6ZL%xF@LPtLHMUk!ThRGf3dUDEj|}d zk5S_O#TCqD`;#x7{2l60 zw_d_}^EJ1psoY95&YRJYHX$D!MH&Cn%#$4piy7VOG1qvUT-0pafqC1yThO*bf94X2 z)#1lA1a9@V>?|ODLbqh>9bP z;HMjy+w5^O#`khyUbEfPC@`iqk4f9=p2i*Az+)A;YP?auoHNLCpZ{sN5!z}S^T_&r zj6CO_GJlxU#;CAAt&ld^t_$PA^b*WB<`pw;%&pCwX?SX5Yl?QvS@u1|TT}Zoi+Y=J z{pAtNlYTV7>KWabkDi!oPu|CjpFEW&Sa(k{xpfyO*jCiENtDkU+O#tJI`4f7Ynt@o zz8k#LieyXLFo$n1E?O+F#eD6E5FuMl-xB(@789SR<93H7y+w@$FZf(`T^=qT71++4 z_s)1Ry>Cr*b7$jCpG@3d=|E2--{W_DE`|CIGk#e1GoK3| zXH3aw)+G5edm7bO@8L0d=j&-SvsrnpGG=u*T6U`l^4#AJ8)cl!y^{Ik!~VvaT_Maf zOLa6V&rK$z&HGOEjm&Ay9B**HjBz*2f!m#WWis})bY|{z@Ewk__hf#W=pZ&oX8t~V zvTOZtYA17T>D}`nEdr+hg-iR)TFA)f z3h#!DW&4gbK3Ka6bI-aE*~0&rs)bIy%Y^e=dazB-gL5%i5p(bJ!b^C4i&+bODUsNC z3!T}frb9mC%Sf{pis)a>u&=Dh?H89dHEupJ_uM?&x*Fko%vvZz3l}3<>HvHl zs)dGHgdCrn>l+&<$K+=ArCR7llv#TeX_3&6qm@*sq9L3+1y+ z!TIA|xxMD4qZ+rbjdxVort=vs%l?YxvCNxk;Wj&E;6_owEX^JU6v=$(EPwN-<|d_8a++QJT=DC zm>KEDb>{f>9>%J+sX(6Z#&2T`?;F#ZE2JN6cx5}wye^=NacolpA#K77HZnfi@-kmq zTERHjyE^lafUL%dFmvvvC;o!%Tbp%GxuQOpeE3kd*?@C&YuBer z$*hg@76U|j=0@*&3oQPe&!up$5u%*G7xUZhZlcbC+RV8&(eXQU;h5P|(o>|* z?aeWh({a2I**l;-_n&!&i{;67Gru|4OYGSDin)7&Rw7HkjE1yXl+aQ1GRiQ!_AV%v zzo^e#AX!o|A$KR{>i4fe?XLrv`(<4O-jhZ%KW?874m>tvW>!7JvEX|ZGku=f%cM@X^UeHKjMT3xGgnU6#JKt_7jwi1 zn^CJ=4EsO0qKnaGmAPK+Ek4%B5sDie?#;aLjDnKSA7j8^mMvti(8RGW{Tw=ibm| zs7PGXhxv2!9^z`|FU(Qbnu}x)vKrFnWBuyl=-~>?7a^~3buh2j9xYBF+MGA9*H&jb z3n?=UW}Ac4ro;3EuFT1;DIw!_b1ysgriBAt&vJWlhh&)Gq}g70?o6~DH}^Q#&RV%TvszPVx!5{M(6P`9;PCC81QF4Uok6*dw#y!7m++JXHcVorgaQ6RJxuHg1 zk0Z>J2aPj=cK2l-{dI!z`N1(BhpDvYWl3L+$7j+nHzU#E${^2oS;R==WTrLDF&Fz8 zSz6vlkZxnDf$MRSCm5DY!lCVH)FZwzkZDn?1s|`TH_YbKHzC zgUoramA5W7Xko@flh-5cTj!c_(kXbA^`(=^4;nPy#g#eIM{_4z8Fi?MyQ@JVgv z#k(pVqESFrZg=?QDXwm-&v~@8&;*g*^Ba#<(0f;rIHf1ba}OBhB04%7%;IoYvDMS8 zE4q6(5hL^GGNjG*X_dwCDOH%Q5jn(%sZE)~eIg*EM>po?P5i+z-4N!m$Z?RNwz+N$ z>i*8!)XCg~#ywu(|18{$nNHtxVGOTpuG_!n^fBt~e8TPPsf7dxh47d7qxjob~g)#kOd*<@jZsM5kW(|D%+6o-#ZtgF)g34g} zM(%8L;w-}DWD91`1s~zouO7@B%N~M#SIjzO{KUSHafn%;gzP$Lt#iwa znZ*b5+Aju~F|(^=MeLj1jG3ll9d6h-l65*eKEx>-`!e?_lEw&I+?F|gn&L*kytSF< zdJCidakIYKS*DFq(=i>lXBgkdIQ#htpNspo5k}5pW}Wua+s!DQz>(WGAM!Npd+Kw{ zbk68$w5_$5VmeuR#Lp8OewRBjM_&YrfutrZDvh@%q}f%M(KK!ZUxqbc@= zYUy5p*HD`=_2U9~<`V+HM%#=uNq0h3mjK8(-e$C_6ac}4cf#`#Hsf;n5J>!LA@p*w z8BW!oLyE!uA@e|+k!AU3*bq4y(n2x;9yup;T_U(pAWoqCSFNxw;!;&6ZCXFN{&ojcsNcFp|@ zhmwBXj1{b2Q89R$^o!0s=%1sz#i&F29bX)>_fHvx^+`X&<=p7+_Z44I`^)GqIP_~6 z{v2X6pwC=fl=&9sB>i-Swqf|2lbF`cW>lDI$DG~v;1SaIzIhcJHC&3{NWV^lr&#;d zQ0z=PKMH=r$=54j9nzn0^CzaC9BMyD?K=}#jK}_E?59Y-LVb&o)N;Wwc$CeEr2Fnk ziypJ~BK@k(!f`;)><~rz;V)icvAu1eB-uOFyNhXd%z)9P6EglR#?;>ewMc*L!@bzZ z*&lXN`;_P36V}L+1{k;27zDyBub3;rJ8kQ~R3Z&h|?y zW1uV9cOTHzalr_SSV%fGEL*IDPDFtq{qgfM!>}aZU_P~9FVhw(pMM1%$i8CGOeoRk z4gl#~EbRru>DqQ5=^qU_4yEeuhxyc=VE7f7wR#0CA^Xq3#W#F_jyG$t z|Ct{~z@`o#ts|-Z^7@<6`US# zk^bfRZ{SPCW_X_LkB__$xie113#4|As-b4rCbthl!NbNr+tpM+7SMU?f z*T6HQAnVP?xR3OwTdG0kS06A5>DMXv-I}|31QwuqKT>&wb!(v*v{1bDDzV=$x4Xr7 zMLMUlEVlpX6V35cq+V)FXZ?<~sQposX4qif8#GA&V5w=?cH2GdPx?;pH)7!|fp~!8 zvtf>7_%8b)98CIkEthdY=xVG^`lD)w;>1l8Fge9}SjzXBZKU61;&*%@QovEt-(KV$COcRkhLL`s z#SbxX)I=yj`qeI9#7axoa{ji;>4Q_-AAt;{|LW&zT=C@+bS3?34csy2Oej2{bzt#b zz)!v2LrT)mUNRA;Z}kHbjjQfF189!w}MU?fVuEZ*K%P(yVp#J7j;B99|L!tc!-6eP&xNq+fox zMI;WnTcaK6S6UDa9Wu_a_a^=ElYYRG{Rwa#=`Yyz9z-JGf96z{*O3(b5*!S`Z?DozlkdZ;A8fAc2gT@EZHAtK88$CyM>eh}Zo{cWv!NaJE%yE; zOsdckwveVrqj0z~I0sB8uHPyOUM$~jwUCW_cZ=BccCO=9I(JwQ1M{9VwofGeJFS1h zn~KlvV@dz`)K4%fOF3Ll`blR!gNNY*aU%77>wF#7)Lo2+NV8;Wgc}L>;CSN01-+r# z)6;l|=4em#S@6C59b7{CE>+t>kwLGp0_ne=aYUF^5wyatNuAj|K`^ij7U|&x{UO@6#0cEi{7*jCjEl9KVy#R z#h?r6f9mxDlP~H8No4LHx`C5U&WG2ex!`pGro6HPx)ASm*^a-moP>d-U+&IaZ1C_V zgi`LmePhE{8^WL=={w)fkDDKS0fY4G1O(c1y#ECoNk6DYdb_2BMN}gFb;-UtdZ}9I zSm0@EkgA0$Bq{>;yP36+i_sh2r!{M#X465UPdToXlD%0o6jsR4o(}wFH-{TIftA7j#jzP&3DJI9b&~J{QC6!&NPG z)5qCb+>01m`oLI$Pg>o}!S0r4Rb==;ZbRHi24tpD=z-iPsUAnhWv{O?o z+0kb7E`1MrJ)4fDTG)&eL8sy5H*XARXfygw-T@6Sp1>bYHe;jPEXca~4i0Q=GnRK6 z2%8H%$B^bWV?{rJM2SCO=C-u{%pYnGza0Y$tu~`=ffSpPt(>75SX`Z8QvQ zHpgDRjm@Zi^*eYiN`;{fY(`?+8+bp!86P;>3|cs#=bqVkiF90hpMdVocH#u$r?b4E zdX2LfNt%sTPk|*(AK)y~?Bp-tZNPiHM4Fj<|FBNIAAvT~JX5Wyby6vdF`YDrEDiQw zyT@YeA)PIaui8&KN8&2tyhas#lll|3Ae+#^6ENxRP)tsJrzP5mCC8k{iZq6St&gMc zz5{rlj;5gyTbE#Gq!kIb46qe#cA7UJ29 zd*C+l%KID9tI~P+MVj-|cw&RCp^%#9;?vV=xTV=g_(gNH;!K$R)T5seN^@6cdvW_c zioXSwEwm-Fwa{dKBiB~TG_}uyfw4r%SUw;Z@bbSB|NppXNEfD$k zEOaN$5B2R}S+W;;k><>uA+WLkBB)K8n+m>!v}d}36X~>E_zh~?vp_zIt0wtkU_poZ z)_tT|^pHj5pO)S~OCy`HWLp&6zrEXjt`*hTeZt{EbS`{VkM_ZJVK8=c5Byq_G_!?3 zY1?9~K$_)J`N0&&1L#DW%?qpp*W8ydHBjH{V<70wV_Zv`mui)VK_@<8S<>tjebd@E z%pEL{q47aCu_=&?vvr3BwSaA9~97LMFPBSob z;(J(#@@QwLtvIpOXyV@_2X5Wn#!?ooS$33L^`D-NhOJcXiw4@l$_!VbVEew-MbKUyq z`2N5E$VHl|hFrxm#g;=N(j0aAC}!Sp7|xUC^bV`A#g`x`E9kmx<`Ddn`x#VgVlxU% zD^Bl>eSv|bc_!Uid-9`^kd`#R-96#|c8^8eszGt}xSh3E5sQeZVlz_YO$^>?BOrn_ z10!32-gWqK9c5;d=c<&RU#-|o$gWOwusf!oUIY0xqq@nq$~T-zhzUK(Y1UejHz|m zUYj(F@BR#PTuNg}(mXTgDL5Y;j%`UZ$$=m!61EColjhaIhvD1jqu8A^&rV(j!AGxR zk6N@=l<5m|YP`UQq}lU8esGxh75CCw*Xq|{tJBOV^s8+%7L^$3*zt_T$WEHKue#Yg zo{qs6q?xX28fxNB{KG@jmr+zV!~z_jJPNq*<`RPyF!wt38<7AGfj?tL~JtS0(%Go#^_q ze`aeGX)f#d3%kvHV4X`mtHLLIxVbVsrsJ;e{TN3d7zbOZ@3}`8anjm#ApP8%_yF#y z<_D?B|D_uj;pPD$u!S`DowVVQ+Am=N`IhW#cI~n|1sJ=O#R{&LGW&9v0zQ zB&l@@X&x?W5#?9au=|i^hhaZq@V$5T#}rp#n?JzN8;-c0VxvfjP*`zgA|@uy`B8ze z*J%@eC(TiF_kevc;(5|^KR6FYCBKE?q*=LfTX3uV8XHrbFFchVLXv#PwxpS{-(qXV z@Mx?@n)8YZKj#}3<2uFmzB`-k9;2f%0p(E>r+ioJR9!n;!4--jq+@1Tl z-IxmFNOMiHvzX_(7vv_*#ff*~fkh`^wbb;Tg+G?ufp)ZxB{$u&vP%s7RV`a|A)hsjJ}>t=oC;J%NRTMnN&s^m_Ce zM%640wMnyuV-yS@Vz-v3^}o{ri|F%gpkpK27hZ}OXmnzdUC@59w9gNC-7FdIrhTMh zqqp#_Of&3HntMjyh4$NLVnWia9&-|e>vn8Un(i)JA=}o|IDs@n4o`zusqW($(rjG0 z9_+aH4)2oYbT%#79%Zb?(M$QzpbCe2qm53$Isbo1x4ae;#Y+# z;PqFZFo-luml}`F(>%sHw9novwjRAdT)@$^|5gb+hMDP}fH&>SVHk|bzAVS1w70IY zJjZs;C=f|!Z{M$&rE?*iMSLT5G?uxr)1IGfCefZgzTI}e6Qt?2itY{MSZdACmh!0X zcf`r*pfG8E_jrvy&TXNGtO25KVX9ekVFT$Ld}iRx$X&3Nc;~szIB~~07)3UHw@$*u z!yZCy>O1I~16H5$0p5|H^@n`4&+PmYyy#fPN;%luJJEX{WFPVJi(}{Y7BPi%(&W8s z9e(E*oFP6GSpxzcKEegEIbCuRJn?x5r${r$oK3KzRv@$@&5VX0G_15AijwB}cGuy$ z^Ahloss6WJpgGsaOh#OF@$3kpHI<{l}Fm%*DOi3}YJkti4 zzUBhD%h<^625AEx;RVtx<5(H4CisMTNHe8>sP%69Us#4T=S|9HjUHn$@{wlki+Sy< zi5*F^+nBfZ89_g>JZaWEQwPtCeUGfm^bG?TQ6!m4WyTi;N=&pY!KQ-8__4x~AG=L?)Vxev@H&9m38VVUwvAqQzL9Pf)m zA0C7$qVPHRP#d8O&T_-ANCntqRi?A_`{!f9GtIyVaQ z$8{D_hcw^qt80y^YY{0)b6r5Rb>5x`*hiYq?oA-&rnm5&G$)ju1xJJLz$?-$@?aY@ zNqq|JwALM7cmg`#-T^I0v%2jzoPRV2qG-L%mHZ9V?ARKjX&r9t@dJjmOAZf7GfzYe z_+{y1?L=#==MuX9ZG6;!6s^5MD(S9_y-giWiwXwXocrnyoQyd>0WD*MHrqY1myiO-*@}5=-A_swy(`_Ty`FZ&)EPM zdr|yY9^&=2li+x7n$xTA(D`K@dVWl~|L6yvNFHNNI*hJ~dd6Uxpsv=&!)e{SK2`CjI4Bt!_u`)5}MpQ#;D* zN6q|8udo;`h?nJ`Y`s!222YXA&!ef~TD|Y+LFZ!gZVwA=uW$;Ti@(o8=)5BY?{=Vg z>vRAvjXsX&X#7WJybMidt-;zan z=Pny9;^O$`eoLv{{ZSNDF1*uvhvH;>sxQ#KNJ(&_7*5jlG1!ZbgU=Kv>jTcin7hUaG!)_52c*fbiTm1XeHQ^wNXWut#a7yXRKsA-fpTiYBaz253)omho%1RjM z{t5Eewu#mg@7s^|`vu#Y*+j0-S?wR&SwybpHqoMOVQVA$`v|UN)8*QGYZb4bkg|qN zEbLbY+U%hB21wKW*6-Xh^wo zrG1|uKLhBV=%S2xh~C3{lJqtBWp0Q0>F*~TDsT&~&zXk_>yn?}5So77jc-WvK-bMM zIu|`7u4)sdr%r|^r5@s$YNR=$HuUm+k1=2q`D#R1olZp{Hnxc)RXbSQzl_0R&Nkth z?zI2MH5Mb7Gy^&X*$WSf#6C4`Vqo@4xN!3)%to5~Hjcx)E{|~xY1V1C7T+DYgl$RF zI^-x0UVj*a8rejsTM(X@vkEJ=vI)nPPjT*(VYs=TO?37Ag4tRW#}}kod_feBe{|Gd zg*1On6|Vb-&dnl3eYN@nY~v=uDbXeP-e7=sWTrg2;Qh1#Ua~1~QPQdy-VR z?AdpEFT^H7+~?ZsJdTDIZET`RWRyb+dS2Vs$tG@j?XmWJ9|b>2v+~?RFrn*Lm`OUb z`wfB@4$t8*alg#Vp=$T5FxJr~ybB$KS5JK*3u*S9cpk=n+WNGEpA9TUBAur{1wAi$10d9D7L+)`RY|CzpPGjIyn%|!>r*ZRaZ%j?| z-l@$!3^+3#Ka%G4Deo|6rv^Bf;$pBU`=!#;^LceSt>S8h7kGm+-^)fQuBfp?B= zNb_j(NW|np)`Jv>$@YK7z#^p}A;ssgolo(2?P2hk;`Wt)5O&zS3bIp<+zC32&6XX7 ztE4&f-f|rIHW;EPr}oqujCa33gS(U$4PO?+l%u}D3(CQ>!_V43PK|_Ll$#}Y2KslN zYY{gozsmP-Z=IjXBF>X$vyen^CR+p)r+gfcygBTw@)q8cX78Ap(7(!E=tr8fK5T_s zIZi`f()`gV0KC)eg7373bPK%+4G+zOE3^)LE%F+QENBOwv_5qH@Es1+N)6LUb7cTM zUp?b)rE4^iBhVu1_37gOi`v`MJ;hGR_S?JA`m-W+I8^SD2fx!AwW(7WY@X8tFG^l` z9acVAj1FXzX5DdUzWo5cqP{-;*TMPZm*n-SDB5g1tgZ1Fms5M)_En+%qmQ_Od{~|S zsdawpU-*-J!?#7Owd-1pi{x{`5?So8=-E#cX=WW5X0Mm=7q+2uEcX`hNtX}!mNeUz zn~V=TKSa8A6Lphq!cB?K<4YQ=I$iznfjhlRPn!9wUc=m@mtqi&t!4HLY&N|Qo}%%w z&j`m}MRVg>(tNWn8i(CqZ~sY}?sSbcb!QsCP@22LkXByjo7FJ=;$?VBIr7}`2rRqd1Ena=vvs}1sp)6tr+XX_aVtm%!HN%Lywr+ugT z-KA@f_oNw+f2)0vH5$8-eOY?`@I3r0?j)V{Is4Udd}}k-ETq zusyj6Zlqbe(=HfYJpjH?9Pavf3aVb&3T-Kt-nG69L%Yp{WfWt%PrrqBcN^0hZ4(h| zA|Ui?jP)pKmZ)J7XAd;C(tSCRZo5UKE*ZnX%UgU&nx#g~z`)Y?Fb`>dT;+{Xj%RQstrcC%8u-51Zfrnn$eC+5uw>l@ z=uT_Y)Ap~>NYDu_WYe?%cdQ(i4$qTj#;Gy*^6E6Ztj(e>Td1}!=;%Z3V~!ox zyX3>kh2dDXd`@UYI`qH@vlipRUJWk1xo3 zQ=+J+2aas}2-=Y5`zgqg4~3Uc*rMNpttodjkaLy8tdU{#~mc2kWr| z(4OWcEYDTg^K%(Yruq7|=Q)JE>MyT}M88j8;pXXlke%lDf^#%fS=R4%hlp1?e{Jft11`<28z}Xa6iRt;p@Q$-FFU4?Ej}!1L z*G^nUnmwGnq3e+|SdcW=?3o6RjqhV;(ma{8A)M>}4zrSGs>+FA=!YLTn&Le4-DvA~ zddFZn#eb8|GyG@&ANJk?Jj-2K8*ZUEbm8t5ij@|M_f2pqT3m}$w76AqcXw@ZcPMXy zyBBwt;x0wLnModY*1ymC{=AQBrdy{)Ul@0LlWr5;QtS|8VLV1LSOT1$*T0FwTMyg20_U(@@Qup54SOyFzLXiB zwN!6xyA1VV-kL9BQ`B`*1Qx|3zTEqpq?}gzX{I(hOw1UXP(?REROGA#=Jp) z?a(#ihW}o8R|N4IK3+U>xWX0#c5d281XPG+&~My4JNr8313L#iqmQ*`?oS@Eo`5&GPh$!C#js7# zmqSq-*!D_$*nQ~ZpaDl%>5)s>e&~DMl{eXjw?kP^@X1o&S8P;5&f0>nJafmf`3WD} zoWX~0A=mi2%(kk)IjElluOc$r^8sg@9&xO7_FMMkz}c|T8@4&DsMrcIdNS!QJLW!6 zG>6zVt8|&IXf#1&fV?U)=LBnUa)G!8{E-3o*oXA}L|w?kyItS1u+D|VSFk6&-#6x1 z@{~O_*wcQJ18>~-<(|zj7HoB4jWf{ORvU67di7V9a_)269+0;!@rqsV$k=f7f8|?j zOVkjS3v4*zag@1qTf&;Pf;zKtBb%Ninq>qZmRU7}73_SDVGY?>pa=7dyU#vCTLm5z zX7_8qWgWogA)n6LvLyP(*1%YP@z%lS-4@1OL+JZRcRRlSuF@KO<#@}!H+dXO*cSZo z##7w9|AqxNg?bg(O;m;NCoV%@0?SMj6H>&m888;SzpoRyr`XvEur2)dAu+veBx~8Y zC9lV?iCN!9v0DKx`SgvkBJDVTw!TwKzN+X)F?L=$mKE^AG2ca9&o#C&(5`=ogA9AH z)^}EO$Xj<=q|xKDlBa(hTm`8oU)vvJ?{KfwOwHhoYTNXVJNROWyTX zj0o>IMU3kP<8-$a;}Wb9d3v_wHxsWGccS--v(VP-=qY06(HOC_9juLAgM{zB`yyqV zmVCu?A5ne%YjFu|Xq(}Uz37WC;tTY>d9pzJ!oZ)RNnlIPik~XG6rM+I?%t9QXo}Mjzha+qNcE($796Dj&L8^ ze-%4eexIlaoDXwI)++|~U37-^Tj}#`-kxdV8SwWlc>~rY!$tXCFqh?g$bNWq5?P?F zu;5!PtlMDL3fgL$>m}=$r#yQEZFMjCg-u8kXFCHty9fScM~k(#!8c314}4qIqjiHl zFhT&cy(0dRj^>=|q3Q(M4yIK1%pYb?@#r0{@ty}BG` z(r=l_3j7xw*Rxr9?P3IQo*OZhWp<4b8v!S>cV<_wJP<_iH(X~BCsyIj|u%Yak1NK#w;hh=SmT`=`81DK`Gy={G zwm@-w_(PGb3&huZitzjyBZ9yuFWamUYZ^zS+{#FpT!;w11C?e<+f&9KH^9{4{8!M9xz;d{bBzH0VQ;c>{{ z2H#b3Pp7Zq`Os&!;J$#@z7~06i?T5xke?mzi507Qvsh@i$D%VLIA9k01oq6?w^IyT zx|vl69`}I@#oLC*Sry=avS5e^cyyB`hkj+KRYim*dcoTDfH9jQsi?jB6T1#}md!cE z9_90ceF6W}&R8(IVowLY2x5A)&S=|^4L?{K;9qt-8S6j&6T1tXY5Lb>=}$gm@SPjK zpLzt_dg(gb0Q@7wVz#o=Q5FjR?00%6ThU-Ms{t{6obfbURbme712K)sf0tcsIe>M5 zxH!AKX8dIdRvvRE;wvkB{-JFuaAtCF;2EnHw=Dsjp@{?U-&5@A4m$O3ePf-kfe$D3Nf9U8Qv?t9V>jnhO`g%vrgeF#2Bz`>HAfz+p)a@ zzWw8^(oJMx`7VhMfIl>8&19j+qCE7mLifC^a}WU-PQHdf_+$-*)m7C%i4*5XbcP-IE5P@pIowx9KL>ej$Dbnq%V1k!uqWsYJP&#B!!{l4^f~fU zq`vRVs)7BlPuv#si-xj0(69H+PKpf&=P?`f_wduLf{)(L-UDa4LUYB;#iv*R;37`J zqRNOnY&`g_#C~6K=j}^Y0sOi3**E)$*w4%nVw&;L0DDLHu3|6v|4wK^U!Nccz7*oJ zKhZ+l{wLpAXNZ?$>-22-Zy(tr;0&nSh+Uce6u-yg7sicYv8k@I%An%}8}^#!Kg7Dg zwK)szVWE51vk>5XS@9ebx2Lm8(3bb!`|QEK?yNu9urT>s#-a+bwP4%%RdH-*#914B zW5(T!!~5Tk$!+%lJ9xwUid@O;8K95sX&kGQ`TftbE5x6ZeIT?g3*Vwz@PCHs&4KSfiB>HD=W z?K3}p5y8N7?R^>1De#rRI^dHnSR5a6N1O)vhoy5wqF1NHXV8DKWwUq|vQyLqJNq{| zD!$BJEM|lKSv%bjlU@uHd7#~DT8F@5r5wr{zX4tyinP=ECnTOp_K>@3(e@I+3w zJ?K5_0h|R=v}Q+YK4xbDe||fG?f1IGVu8Qlgq7^zwSBAu#I#Ls$ynYsY%|!rviSwJ zt?y)(1N!1+B5UedQX`05nA z2Pky7sQo1PaNv!vtpBYW_I2RfP4C{Y*$)efauCz`RUfb%1G|b{5K}M5^K4|&>0%tj zsP^<|Hg44hF&%jPqL#2Dr;iBu#-5K!K7x(BbzN)*dAV-2Si7Om#6i$^E%O_TTJ=#R zhM1msw%C?n&Uf(yVjA$FkZ;yb4zeAzTgbVmeWlk=F&pej{>f3qM1B_8foDmA%EGbD z3sD#NZ><_4+TXe_ZL9}v@>i=ME1g_|)6 zF-kZ5150%^6Wa(pqoUwj<4sXEjOnUAFgH!D?>h_RN&Ed|f%#h4r-1(aonKh>POt5I zf#-tHYc`;JaZw6#rvJXX>|L6EVmY*1=geu=D`d7f0`??4xdWaXY!O9)=Un>*tWlv8 z0(0_Xzrk$Blv@J6x91*@E3zWPUx>NT-waC=vD)8130LsLsbk}85wMS7HTb7aIMG4RZ`#*`S}nP9_Et8_Nhb9|(FP z=7u$68=x;)n_U)bvyNv8!Gf!rWqE=J(74eA_wdfW2heZ)`Edbald)d*1mt@X9d0Ql53O1vxu#T!S6k zaLbnS-dBceuyrkpG1qIa8P?u8+5527-R?15gS{L!lLh#mWw-|G;kc0{Oc%{?4R+=1 zA@*V8GFpQ*tagp>hm765-lJPr%hq0@5QikaIbMKXbsC4C|P~*$;9H4JsGfuRRZ4* zId+CUcsG;z0X{q}Oe8FIht-99y4a58#hGa@*@5a%Gr5!KI`=c{0Q~jNjZ$n zXW-f1)FHV&Q&Dbvr1n2{dE>`trN~b5p|4xO76PpStqR;|~k8ZSvS=ym|dZ5^>gj6?w@o zu7q3U@_^?@YQN#iok{uape7{0*#8up9MXmG)gdEU$^>dZb?n~vHva-@pJS>CZ}tqi zul6~n{8U<$79phHui+~3eO52R?^3-HZr9Y_N$*3MWzVj)NPfw=xJ(_V_T4XzswFS< z&rI?i`P<5K_g<0B5hr@dHl8a9SG^b_A3KyHoc~dT40U=$d-qaj3zsd|e~yRY^$_NZ}4 zyey;kArAi>Dz>B^NIFZWoVTx!RQncN9;jfuy-meExN}YR`ARV9Tz1~fcp|k|+U@FR zHh*_3lAkS}oj*UT_At)(EyddkZ<1$hTbJM5qR#r*TfRNFoqJ3+=P%!f7a6;V@R|jo zyudp*!W+Lu@JBmcX@B(l!C^e*3TJ`+Dn6?p&pUiF;a1%{@fve45w5VOA(xL*O4Mn- z(#B`KElBv(hupk;8nvJO#dQZ>(+Bp4!Ozg)c9!N`cfzx}cViVY3?jTG@p{{5*hh*w z*+-1D2g5#O#Ao{kh^zOM&g8MXMOa`E$!+x=!ix@!Ag0 z>&Z>&(hy$8I?CH;ZSM-%>#7x338idK6{n8P>`#nO2pGZi3Pkbv>KHsX&SjgAD zuRI(yn<3}MF&$-sdAA7n$WveTKb)GQJSMn|oYt-g;YTfV$dS*g6OPXIRm^X#VsyxF z8>}OGklfL~nXu(hF}>?E#=gIsignpZt8I<4E8M+YPqyir%8kb953q?FRnAPV=fu0Z zHz%Ihwk~{U`pSgkYB1izR*>-3`VIM#;i(9xDAkGY8GM;+F88w^@3LzGVb70Y{Mbha z!Vh92_~M6WDCbjohVsoeFM<7PmZ}dwb#O7^BO&d%%kxKsCx^fpGLzFw)EQj6B!99+ zoyk+>P!^tOt=bEJ%H=IPF-eWh^n=&3K1tP>-94@vyPG_OuAO$arp;-+j`gV1_9vUv z*dLy6h*-Q+)r2kEPl&QNRjnvfBB@NdPt}lJbKGUtRuzcHGfjC}KD!6uk*6BNxv9wr z&v5S|(|$QkHs4|c39Do)wKHuBjn>3g=vf@Y!M>eGF4#MuK{CvN#B*L z2q)^$RxVBOig3z{wdBzfnK|lgNarIzy)RBUMaqowWEWL?)5bm(Yj?II`BcwH;Sr+F zMu^Q-O5BVIA$i`JiR}w+s8~N9^UfCMsmA^q+gKJC)}M4nd0b%Uzp4H58*irIX}hR% zSN5LB&vVV>q?7GuMLv3iE8)0`&G^y7i3s!0UHRfM>I|7u?FaImCkBxH+uwxqo@aJZ ze=ClT;P*q-IiLA@2J^N|zQ;eSxM!%FQe2r4 zM*1S>G~wx^&OK;S>xRgkDUjs(CjKTXf2>dVA}cJN2l*2I{Hcmel_3w|#M4?x-&c-= zA8qI^*A)+-TA!D~sr?_`15h2?TT}*y(9X?1VckIBhU(+WB$#VO5 z5$=*FK)xILgYX>hYI4EETpV>i`W2RsyZaJeJiuAr+SGusd+BSU>pWnx_*KO6AC$H`#U_&3N_&%(?a!BicG-%Tkd9s89a99pKPeBC@N;Wj^8%jad@lg)3w z_moF=t1~VxbPSQhOOz*ho|p(3H7*nNw`Tir$%{QCKdkLDKxXn8#;}k5b9I#^VE-!O zVI7;o9sqT&NYQ!~;b>)0FV+p~u9bMqLRf7%)_<8n4bA zsFCo2eR3x?t{)xEW}9(VjrViW6m!UxkR1bwK!jxqX6N^TX}hgq3S%P z;dc^nZ>JU{zYBYI5++k~`l$zfS^230N!}xPpY7o_RnIpj=xCocTg5#jZ$q)IeK6^S z727Uez?q@g)|Lg|#O^f#gcrdB@%}@q6CSd&w5;LnMY!W)e|hFjTEcyOJIFfE?vu^C zU-gl8_|6h}>V689sfy$v{NiVXoF(_~M)~xjVbU#YCWd(YkG^uy(CLJ0j0%)h`d%Zv zX;=d}V2?9Loo?>FaK>q2!j5Hf$!C455svx%UA(9kK)C(9UBY!{5aBNc+KUd82NCYN zd%pcFSF!G$a<wW zIa`S2opUzeXY2h&IBn5Dp6|wWve~ItKYnoFRKlYo!}#;aa34CH~hKJeC69=UrO-cG_0DR_fdjYxmv!UDYIHAZ-O+A4gz zXI{b~2U_rp^HtqW8sQ^D#;W=B)9Q?J;HTOg+kKH0-j_aXOZa^CRU*mUUW9X0swBRa zQ{!muJ)3>(F6C$LciuKPN{zeodj_+iht+ue=y05^FRR9B_VbB(xkYOHZp-b)Pb{iP zoMY#6KJ;LI!VYeYc(bZ03A+sM#HW_LM82Kn*q`TLrPfgq_rtg^OGxq;uOqnsmJQ_d z#hpU=_-6&k&v&-<;mx9z&vV3d;HAghCAr_2dOToR8i{?Zk*^Fdv!@8*fxUC^uMC>xws`pegkR6gu>>L9-ye?T^eE$bsk z6<$C%ZFHzSncIc%t8Wo<+t8fU_sR>xipr1RkAA+aZOH^TL^MTku=R7@NDUALDR zrDENocwXDAlPU+6&nnM6;Otc7?|O0#8{wgH2HqR8%|qLee4;E6NaFRIZvl5R!{f{BY&os40N)F%8-_mCl zo_Mu;&#RXz?%mHgvTCow=-M97#aP$q3xzG$CX8&q36fTtfhgzWz^FP!@qxk&xZX^-ID9pS5I z_{j=$`~KY(1mZ{>P^aW9gWO<#lg#Rd~jIG~wr=Ta5-!0`v{Q!l7FcZPSc*lSaB z@%@R1h3luTr2nl(BKg~-W`v7haFNrut24x2_hPbSx`HGxm#d*X9+Qgj_}zhW(A=wJ z^XSliGOpAV!uO-XWXiDQgiFDBs;Sp>r8P#H?V)n+d>4lHZ>iK*J}o(iu;09nGG#q= z?|gYuefi2&-8zjs&n^q?Bxcqf zMDn4f*VrdyRdLVqW~lAyAcc37YsT{A3?`i|Lw2xaKh(8pQ+#J@$1Bc#7jp1*6RVR> zyX>WTwToVai_NUd_jFOuOez*_&%K?Wko{HD^xz)o}Bg51@+wJjFTfzD&)-LUw><4bD97tcYjHt0Ygm^AD zSSd~)R5=r!`;|!7QsvUs(V1k~hH72CW_&T}6I_Dy*FLKue;&w6cstDVsj{m3J`vbc z7W=$`>|gyRSb7fiBYa_VgtYCbLOH)%hRfj6$7w8_3>+xyPgVDuQMbCu3_klA_BVkC z+@nRRv)8V9R*|-pc{$3<1{Rc!+!^8E^C{(mV+{$Ph9~7&s;V*j^WzlJtaU$!QJ(H-~?sW8>@7H@O?iHLr*xmE1d>B+~j2N@1 zKk1)Kd0xEhujY=h9?50N#*In-w7Q3E_p}`0h0Q9+4-4H1NAzzZXRb|3c#eM;8CU!? z*<8bWfPCUQg7BKo;j+fo`_$hoXCq{y8QIAXnbw5J(bLK@>{o-fz2%p^>de4{kK0NA zqEAV_DN$XSpm+w3I^LN}%JI*N60Y$+i(EOnCgBRv@5I+UYL349Y=ijOS=}GCJM1qq zO;zLCHnG3Gz!){&D~qkRY7PqLzR{Z%+B}eW&gMA4=B-z2hVF+G!d{r>BzGH}m)|&3 znecO88$a2p5aIF}8t@jae|dXq1|iMqVUAA@l9OG`Wf%aQ7RSxi{^~8mt!K9xq z^;Xe0ss~}O=U+r@_f~`(24tFYm1sz8*>|@VKUF6SfrwCVm z)kIExuIAGTc`C>rcilPa6xir4Z`7zjIKzr0Qf6&Rm{&U~7TUWIZr*&PsGdZv_d2cm zYb1U!92lbf5La>MDT3W+EafwJPYUd zZ${HtSbTCI&y~NIz<#Cf-JP!wkc1~ici=8h)tdinSO!_`oU-9W&xgXM&&aKwW3E_` zTh*&;r!$DVOx3X~?bGqM1FpPg__)r6czCWG#29ze`oG^IEo}P%gSQ z$<&MNW`VSXo4@$Lg0DCcw!KZlBU8O1drZzJFYntMA5fgRH+L4_8Yp}AhpiJ6@8+ay zqx#+uXJ-CJcyc92*`}xJ*T9=;WR(t=h%^7(TvDE2O*qV@fE-g!{oSi+WxVB~j_F7q zyTM0(ZC!-^23Dy6AGvWrKRf#BsE?PNbHhy_-fV+fH-7}-QM0nkB8%1Ez^dIfm304k zm*kIMe-M{0IZ4!yEO$a&Kbe7WdNEJD>g+;z*8RF-O})Z|yVpHt|5>3J;eKBLq~ z!d?Tj!n^Q2ga-#C=Y_jJRXR>@+5N?dIqJV^e4LHRmXYwy<_p>8qj?D*wzp)1>J=iq zA>ljQnLa9}og9bR-c<1+xfyp8Z_Y9-3b-Zm9~}DCR^LzgeLx zs2?||D8F#$4f(`2u>hYxzc)j;xk zaj&_xh%8dbQ=rYwGrP+Y?(V*;TRkUTVU{k8BVv%c-$HrRZ>xd4vba7v%F4)3+8O?4LTy z{`!)-*0kZxhJ-wGr_ZXty;riqWz{(9@Y_w>wTH@P??pfDH47^|&wZn~xt~}iBsw?~};s5ho#kacxg#6i+0!qxmE8U)^pb{vP$fo=Ch-+Zly?+WshP$9?%Zcj%WT z7tpULtuLToQJP00kLH)qFRNV%{j%(l(62~sr-Xh*YWpShYuN(dTKS+o*{uBi@w&e# zchP=8eak<{WBCpFEq`LWu3!(w0_|}HJJJ7Wrxh2p-woRVKSp7^5Q9F&u5{N>nSFf$ z_DH618*{jqyz94;b-bR)t#CkV*>KE9)}-fW*YoSE$pmk5@~{%OT(h+;C_fZnJnbR7 z>;3A<tauF+c$i^8wE@~nwlxPBhrMXZ4Py1?s>uGz{Dwfl!e@X#`;T~_#B zu(`swFUuXfE}K?#46C}VKVKf3DY9Y2RTjH9ke|NLGcw=xG<;>-dOXRHC6S+D9+;4) zB!8UtaO4#DTO23%X5=}tK8!5q(t*#b`+#-X`91Ow{4JoS@Hc_v!X!~=UWD=4-yPYD z87ZT3orvIthPv9l7D5~c2lE`6>kF5S$)l{l&$#bS!lB(wkdLKjZbWsM{BwH>FCH$gO;=R8GFlujY>t{ZkvaFJQ*sh zY}veQ;)5Q0zQViLiD#Yiet|utM~8;U)tzEo63^HwdXDcQm%gv++Rr0_tkSE6^v*Te zb*HPl%y$6ZfqmNHI;Bu$nWu`2yjB02YnJ)}();3f;a>QoYwasNWrgwU#E`~`+>U#O z%Ke4BM6ZRvkK^e}c6W>;#FMuz9qnE;dk@Or{{6PN^WbNMdmLHr-YQq2<*4&&$_)3T zRaz2`X*Sq>$hBdFZ4>LbJEWdL_YvTJmA@ zBcm++p&OGfw|HVNmtJo1yHshv+-i49lVQs(duAt|yxg*L#PM0nE&JaD&V_bVzqA~4 zmTP^&n#UdGnxC+4m$0^nu(p%1wx6)>7h&CB!rBjnwSNd}zY*5{B&_{RSo@#s)Nvtf z#%mB)&oWcP-}y-JUOmHJov9mN8mI1MOEhi37kw#C<226Mhu?~9KseDjXWp$#H^Qw0 z53;t-A%ue~SA+Yge~fDr|JC)`iWUC*chqNW=kKV`*pB7Lzq&sECHYX3i^k6r+c3v+ zzuhmqBF5M-$HtvWDSek5wqcIlD_%^dIr+_oIW~552{HTjaMHil*#N3S8yhO=|XMPIfN zXWvulMW>x#h;w_sQu0>h1>#H>IZK=m2`A3?_L{O=m*>QpDD`!*`|J+lJl3_TZ0j6H zoGUw~koDd?B~IY81202grGA)KHrbGrW8Z;K055Ug%nIK?e#*qL@4zR3SM}Y$oGjit z568X(p8#HteTRPAq5s4Qd=hwx6Z$Qn|HKJ=5_pLd`YoXU#0h-zi+?%dgnkR?KXF2Q z><}m7gnkR?KXF2Q1jLCrq2B`fPn-}R0de9OBj~q){u3v}M?jp26LQ4vP?HlU#797! zh!gU~4tYbI5FY_?B2LI1JLC{?LVN_oi8vvT?2u2yxyB=f8{{-`LLLdoC*pjzErA=< zJK}^q5|B^CSvk)$SEzl&33((SpNO+W>m#mE2Q52omYt6;E^vjKXxVAA>>M$usVme+ z%TAkR=aqdoU7%K4cG@gEG2bnJV!m5;V!m7c#C*5x#C*5>iTQ5XiTQ5%6Z74QJLbFP zPt12K?wIeEKQZ5}xMRLs{=|H@;*R-lcD?c&ct+->pTltCkZp9t*-O5ko zv&IqTyOp2FXN@DwcPl@U&l*RV?^b>ypEZuK-`03XK5HCdzpe3(eAYO^ep}-m`K)n- z{kFzC#>c8l*l%mRV|=W-g#EV0JI2SVOW1E~ykmTK2}}AJhJL1<~z<9SVJ(6ton)hj&fZ;xm7ICb2KQ|Bjf z>Tx7=oyYu?y3XS`B2Jy3QrCGLN2>2CKc%koIF6*Q^Elp#Q;#F!)Z?8v^*ACH2^ zk0avLmxvSd9rB4dbzLG(%y-Bq;?#AC zI5FQLpNLb}CE~<d-m(+tBjVI`-m(+t zBjVI`-m(+tBjVI`-m(+tBg>ySZ(4TZd}R3(=S|B_oR2Jj;=F0uiSv==PnL)BKV9{1{Lz*3u4CMvuN3+ zL=pb!d2xJ3Dr>!PjwJp3!ZK0+QTz_xXawC#JTUb7mrGlmD(yWBtL(Y zE1YosjXC)e@AZVsu1L+dueeJ1Z0DcsxgR~#mRUw$Vc*lzdo+1z`8w9<5 z;Z0t-W7`74VMj8_7{5b=lldi=YZlNu7kQ=C2XQe=B7A->e*~WwORJ?LoM6;ivDTH| z9mrDf3_t$}50bC0=_6|S7a^QBHrnnUM(@SsxW{LrGbW^WK++lG3+{xAUvm@BeN@h5Endo= zXNAg>?`db+dZkb}CUFH;qN6A2`<|G??%sAGJf`w#cK$$m!hODeV->?43Gc3zmiI4u zk!)y|I4|$iYYE{YB?|LQP3jR&Ik6aDa&ZUc!=&3jJZSloJ!spUJl;HSr3?bG>4(h2 zvU0It56S1pCE@iyza;$n#64CnODc)_UN_gX+(YPnihLZ@l|A*OcSbU$?*rSZee})+ z>QMeYaq1nYv^gdb4X$|8wL98Gh!<^jeADg}&F*9)dDD-vLhev8t=}z$40-&B+D%nF zhl~u}LU>lK0y0I9euO{x7nNDvzff+Q_J?H6&X3jHq4Y2MvO4=bi9cW6X{=OpH^OID zA7lY>nFxRPd&4rkPfXb9x0Jkoi-&Zr$$2v_I}fU~mE`j;rQ)OB+#!4){tnXao%D`a z4)}4LRlA>ocy3&t%VsU6cf_*OjbL{7wCXRebB$**_%1-A#Cpb#7=G|w0Lk^c0K(R@ zdQ`BU;Ul)5?IYIj0_Yn9XostJ55MHJj^2*mJ1?vsW!;aBvo1a*L)-k~6dcIn*;V%=}j*Y5(zX6qRs>Y)GBy9eqQ zzPq9RTJH`}L-R<)nxC+4moWSa?IEn~By2q^!)x)KgB33m z{wKr{%=ndie=kqw`}n&hze_6c#qzXJY0$)QaFZ4=J7e1IsI zmA)~Pg$BmiUsR&+XQXM{*ijxbqx*2;SvJaBt_w{?_|z94nLA6kFWOnOb}^ax^kG^L zoC+%}XD+KPP(Ed&o1A%i3SrGjc-jyTIk=L#$H^GtCF|$PL-JO`e56yaCd8vLt(~+E zLr#4yVGIPy@V}akuh^e|Q|li#s*`9Rq}D|(vaA_;Mq@+=wqX;)|SQ55$N=e2E`o$05FiA*LMSOEJ}$Vy$(| zYY8V_cO(*Q1YU}-4dP1};>#eugdx5R;!7Cf%OJjlA-){qOYK5@ImDN+*>~*|($~Hs ztbIsW`WUr9JP}OYP4+p0E?|*5(Syi!blWpQbuW zILDSod_Z?~&VYZ9=6uZ6gyggIk6ZCir9P8R@^@9ZYqmTjZ{4RRpO88$;dfj7`IC!j z6;}5IgnyPU%X`oAB)r_GJP&=Bk1%o|7utz3{2gM{#cL3wEoc*BhQ33LzC@oQhS)NU8DjK3#sD$K z1Y?63a>RzQM+`Y)!&oAQ9I;`H5n~=%I*=E8FegxsIbvbVBdaaUFY8*&JBt%+7M9Im zgRpD>+k|Bs^j%nehrS4_FVII}^$~n1EFXeTgyj?Pm9TsTv5;0Qz_-%!E%;nmK8Kh} zE2a=5X~hU)C#~42dtmh)48&Smv4$LwRt^A%v~mn&(#jdol~yi+Ez-(W;FebIL7URb zN$8Wbavp4yRt|&h(#mb{jkLxN^i^780em2>F#^8n@LC8 zKv>&GSodA=sJ;-^eI%@XNLc%Xu=W*U9Se!}Xx|dnJ|`U=QzpU7bC|HsZNhr&5Y}UXupT3X^%x|q#}r{b z)(GpdOjwUi!g|aS)-{2!9^-`d*#9S;dcE6;mvaY^JXf7VB7Yh6?fAg)$>iWCYTvr( zSV*2^Hqt5W+AH~zrz_d@)k>dt{KT5&X-(Iz?VF2Ns#1+`;10$Q z94bI~%bX_sVBe&K_qFcEAIvyNc3un{#AAax5cZoI!NrqqG}c(}aQ?lFpE%znJRm>JYje{{v@K+Kah`UB58*!h()0FB>JnZt2ma=K&5nel+D>8% z_VpuNV%T%r@apQE0W-e;AB^(_>FfG$VVoBT>v@N;o<|7l`Gv5azX-mnbo=*wu`H`@mHwo)`nXsN`3G4Znu%6!u>-n0np2rDW&koVIdfq3wUJnq) z`2@#2>fro^AIm&TP#&M1qf9_2mV}IXO&G%DB zUKbs!1ag!YcPJ|xUR3KO|J*_H{QGEza(s?b)H@ZuzxmHx+ilfs=FnWNY4&y=z1unm zWZ$|u!n>%FpK6s>_Dx)m?D<#qH|`z4=RF-v{d|}soIij6iN=`o&(=Jf?|bTtM?Y7d z#j6tW&wH|jJ-wmURsWf5H4nv4^ApzXn)c8**KLtK|CwvGuc$5UL&Dm(gtZR||Ev0D z+;u)sUv!=jr_LY3IyVUaXRdv;@sw@xR<%wwagI(m?T;dqJmJnoBC>QJj@fy0ii2$3 zO1;~wu(6=*{J=)?oQ>WT@L$oE8EX?? zob1R)9dAK)oEck)Kh2@$OPR1P-&HaL$+!0G!dt97MgAYKCYYzcU59WZI7_F`!f9pE z{-0jKeBr|;)UQlKI`eI}&;1kr3)>=lbi0JLJ%qKLboPq2pKR0pBCPvM@zQ=EtZgQ& z{q|4zuV_o>Q(Cp&GHdvMSG#5n)V5LIwatWeUkKk*eI!5VzMDRw zIYs-5e4>3wSoe{9^54_$KWf+?)wXy!W-R{1`zqcK@i`Em1OHFw0L@i82jVd~BL1Ca zd_KhIKzt6w=fFSbfP;hi?BdU0^BInb$1M$GR}-nTUrV+=!hRlC??g}UNyIbzHKV!c z=m}Te{BcFXJ_XD1_j&UZZo(RK_nFBF|IxFK|0;gGPuP$zKkT8wpZ|YsJ|i`;`E2uH z+oz)8b#=~Z!F{Vl#u4fr!?mQf#qI;@%-nxf-@MoUGuXUWjhW`o^S4*$y4D+)klPlj z_ttgB?qdDtsQ1=ELA6-q31!>5{Yh*;uB&Irp2L%isHiZCMeX5p#I{oES?uU*XPKnXdZ4uTs5Z1O4);1H?eIcy-NLcrsu=WXI?JL6ChlI^% z9r1o{M?U$h{rtPX^?|O{{Am z*`RA9VO=u`>sm@!*I2^3HWL1$XOI6?{D1V!_K)P|yO{p~Q%$IrK7tP(w~lIp##9r` zcPsyqj{f!o_Yy~0dmV5OhqVU+_i$KyBXF;RwPynNQCNE^luYeoKwZ2Bd65IT5F>Zh z*@J%V#lU?8mK^sHSo+o;3*^Cl1Sm&-+(&>I+f@4zXy3-Ky*SvWwHHUXN&5AEo4?$U z+pN7i*rvgQdqFIIX0!`3wdVtM4LiAEKleHF4fha9_z&e)e^KA^1M(0?9>Z^3`A+Re zf!`qq{I~7b9u#cThzt1)b@VvK9KoUQ4m&*_wK=BArIr&GdNoYpy@63*zf&IgrncBgf2s03Z> zJW&Z8);XgRxPPs;p?#F&_czb&mUDhaOSCDC!RlQ*}weG_c6|jXRUQEDfY`c zuN3=bonwmqvd%Zfep%<9V!y2OP_bXj@fzK)C?hUWe-t~T&fwffF~$0A%n`r#gJS(Q z<_N0Sm;+e9jX476zF%`3`Vn>TKVyzSeQS?S+f*&_Ql0pHQ# znb90=2f59XgFZuy`oKdNd4QiV@^pn{`rU3CSFsEp-*!4jAegxZT+_ENGGt#9%i;{ zUhD04mvmZh=)=r*&1(w}{YE;W<5t@K=vqU^{zumuZ3zRjKe$#Ha+{$q3>!=xvt42I z#cb<$*BU+%hRwgb*6{5gUTfsQA6{$3TA1yc*P3ma`lgO4$6SQ*K(#s^|2z2MAL~G4 zefXEG+p%_AIbp1O|I&3koQ<^nf8)9xe2ME#oQL&~$~9a+82!aK(pbcM4yeu6xcuFH zka3@azb75kHSSYjuK#tPf`1Fbj3dl{zwW;X>oz&ck;k}C!FEZGZQ@*kI`D({Uxcwu zGY_pkVt)-e-hWy8G!G~mhu_@?8SSDj>0_Jb{gip1b!6m2SliZ_gF3GV?>@(`X58i(f#x{+(ke{r+Db?S_k}Dbh?|+3{<%Vv@vJJWa1pd`u)Fpl0 zzdwUHwyE|1MXdT=<6Hu~@1bk|Ja(|!!hio&EVa#e-M@rk?T_nxuAg5K#(N{Z{-=8m zeO~~-qi2t#gZC)FfI) z;=wjh-?;yx=XUzOiR{5PPzO2meb%pgBb4iBkEDaP82Z-z7xGy5U&xQo9<6q%4dg)| z7@T z|5mZX@%ra#*`KL*@jCJTjL(7J=YX1j;n@$aEonZ*^`Nl^!?h*J;kw_g@r*SX&ZVS- z>j7g8hHJ}TYsm1hjlcF|m}^dB4Te1UpS89mjO#CB4Tft=lB2G%2Kx`6?Qh+3<1fEQ zXm_CK-~Mc0Jxf%vGjV(zD^YG>ZklU&Bd>n9<~QTjC2>s5)n z<#Qz+-!mO~!r+_4Y4VtIQ{Ut<`OS9Uk0@myU{~J>n)t}|2suB0Qhbl$(D!~nd3Df4 zYS-^*3mG-tk?eV%p@eMtwiw}jo=&ozulgqOQkCgqdXj!5H+f9Csc-U_{ARmJ4~6lJ zcM=P<$HZChG-Pv|sc#+wV(&4x&<@mYm;Ua&X_)$6vR5g8zHWrt2RR^14?gkjcIwO0 z3gJ9c^Ow{|lgE^s`X-ObZ?^lR!en-IvFf{tgUa@hbIYlAEA{Y~r%Eb&b_sVGz?GfO zGwzE!{>uJ24H}EcDym;+lV-97#i$sWJf_^#H+f8cv)#sD)A1h<>yocb+-ZF!ndp`a z$&*#jC>Jr6hexZ}Mf028Nj_nflh}M&-@&)ceUuVTrXY~*#7lOZ9uSj{ONNq^0BSH3z! zCBi0;DL3^^9+Tf}H?QkWcJ979FU7=e7lU~IM(S)CuR`IxMy2-@)2lbb_}b?Q$!~98 zcIQ=J?jbz6SsgwoZ$^o}ot?myKb@r3jwX*OH}y>(lizH&S%!Xm&9i9~M-%(nnhF1$ z%2%0OQrJANDIfY@oXET`srsYF?! zzuE4#JI`$%)xyaSCSG|if)`DYm3$akH<-7a+lc&@B(MYD&F>Qq2&lkk%yp-0_Xecn zx9a;7o;7DX>tCP;VUx#{oBAe?$#1r+d1x${Sli4oj+&pa<|nNA32T0ei{>Y6@|bc{ z-{dj*&31KMB-&$Qode`I9WT<+@gl6_MOep+u#OjDlgE^s`X-ObZ?>!Roa`~N9#b6c z*ZEIa=RaYc|KvBF|Ack^Q;bX=Q*P>;JSM-{uC5!@cN6OxMRHwF2@=~S>q)NXWx{%1CamXW!g^jNtmkFICXXpM^-Ug=-)vW}XQ=Nc)@vtfORsYX z>vaxcz0M)5*ExjsI)|{yW6Di^lgH#Y+tuq>%6Sv(H8ZuP*SCcA`j)U>-xAjATf%yM zOMN$aOu4CV@|gT)yCwGbm93m-GR#90&wmgthPwn&yKC2HkfqkwAzaC)k}T5GmGGCS zj&h^hEwab)VX&MNT7z)y%@NYST~*3klgE^s`X-ObZ??N4Zyh^>vUGF> zvS)~+zZ?{!&Q%Ne6eK%Es&lu3ONPt+b>2`chMo(PT{r zG5O7QFQrZ=myPx3=uZ(lizH&WzLCW<7>69F!4PREHekzCfjO7N67RM zWhst_zVwxGOQw@O$6T7r7md_^)zH^su;YW?|S zpP%USQmwU29#d}Wn>;4J+3t={c9wCsy5BLe@01Sm>-2kMTg~|uWSM#@jx*P$li#ze zJPEI{L-a`6gKX}3@s&NTP2C?=bVOR!uG3BPd z$z$@H?e_fKf)A>o?#oR4#r?Lp8mQtpY;7&k|ERK|@IYqEwoBQT{rhzG@|oJRxIV&( z=S!jP`_45f!KbZP&mT-4Q*P>;JSM-{uC8wsI}__#DzFadx<_MN*FDMyUH1s^ z?h!V5Ou4CV@|gT)ySly+r-^kfm1w7~dt|e&dxUk}qdK7L9@(tx9&wsHrrgvwc}#w@ zU0vUZ)5N-#lAXHl5!Q8&?9_FSu&#S#v#xt&v&m!1O?{KcoJ+fKXJ<1c4$CR7;CXdN)wyWzK@tauJQnEqUJ;J)~5!Q8&u&#TAb=@OQ zlgE^s`X-ObZ?>!J8*!Rg*HUU%*FD0z?h)2?kFc(Lgmv8`Z1R|LQ{Ut<`OS89eIrg2 z>sm^3UH1soJ;J)~5!Q8&u*qY}O?{KcmFfU_Xz8{ zM_AWA!X}R?H}y>(lizGtKbKbg>RC5o{R~{?gL;llSU;~O9sRtTuzp@mSU<1+CmvI7 z>YF?!zkW_m?ds>f#A#yvY?)#G)X#xw{Oaexbgh04OxNn?z=ZX4V8SMkDL3^^9+Tf} zS3jR5P7~{Ap=76iZb?`_w;_s`M(xPJlDI}@${f5qD_Z^Qj}r1NJmaH6io`DZc5c<5{YuUN$m|2IB|l`sCE z^8@9F?t45YNBsGE@$cq0^W00Hddc|oR81)6`!+fA`(qmrHqQk$^-Z~{Z}OODb$004 zn`a4%q<7X|8inxQ5fuo3n-{^87H>;?)%^-a@K(1YZRkhyT2pT7n>;4JdG2VPb%kV? zAHLL=&0%R|gJtyyFW`^G>W=LRCo8`~EPLOJuz9U1H}y>(lixf`bLE#BeDbEO#Mvup zHC}9gF2d#+o~FJjH}y>(^GwnC^ZfYh;Or88b@ydUp1Rmi@@I{L-Ffhyy@cbE4&)pA%K7iV~@-&FmdNq)+d1kMvZ^})5lgB(mcr4f(wxC~G^yko_ zVf;z3Gef+#X@9rG5O82oqvv)WWODtV)Sg&e!JIYbv~7OrnISV z%1wQf$2{Zu!P#EC{%(yXLi~+|)ODOn&o>pxYlp zWQcch;`et7liO}(BW#{UX6l=AQ{Ut<&qk|sXrsMr3Kg%Q=r-cQmO*6y?tWWD`~B*i zu`=?lNZ7Fr$<1p`xv6jRnEd8BMMJxt5y?_@kvJA|^-U~WU2RJE(2l$^$I{A#@5Yst ziw+kiY+h^1O?{Kc=8qi2=~K8U?|rT$;ol-Nao_T_3722=p5=Pbny`7T zDL3^^9+TfZKh1r0sLZwBm3&n>HbQQEdwvi0k@X3eD-+(OwZzvN17*!RgD8K@YfZVS zZ}OP@<{4{&2@1+&Lm2g?N^}wF?NNrXc~+jOZ^})5lgB)}?|F$7JmOL#;_SQjDyzRe zkZ{c>vsod3bq?PCr~+(SSCyaUwWi$EH+f8c^PIPhbK1z*A8*K?Q=asYUaK|}K6PS{ z?3Jc9;l1f2WPw)eXw7C`YsyW1lgH#Y&)U*Hkr+Ge6T;eug#QnF-vQ@Uaea@7SYj`+ z2MfE3C1Cwo*f++Y5EZd&6cH;b7O>J6OHgAsw%7~1XzT_1zOgqfvBs7}W3P!pjj{aw z-*eub=YjQWFtDqbx1W#hVfN0MJ9qBP+$rxpmDhBYS02}mcJp%S1FjFT>q+eT(`PiV zrmMX2D8Ih%%k514-TuVhF2vqm#F|&rRbF|NU*8GleU_ZwXNkR!6RW(YtGx1f-=VF% zUl4nL=_&n=zTy2VN4ndAuAog*C*vAuM&8z7uuRO}H@2vAV zg>~^ch1lmHmZkEVuJX#`V|##oeB37X@toMld14>`X>-l1=_;>0%CGOu^LZ*l2cN%) zeO@E>`HoogYP!lRkMirg3O(kb4L#-|_85s+~S)&$ImQR^J==vE06N)djdVqC%?!4#J(A&G#J;{G*1Vdo^2($9`W`}Ghu+RUQmk{S zgRfhOeLYL8c{N?-eVt2r<=1!P`<@2t;(Hpz`c8h8*L0Ov9{omu?;DWQ_Y;VHpMlu- zABZ)trmMX2D8Ig+-}gxZ?CJX_8L;oG5c_@$vF6oul~*3+*Kao*yui@V()UW*{9pA4 zhqJm}M6BP8PSUflE;+8MgXr!%P?X*wBpU)`p!mISk>Ngz8^hbI&WgGN8 zh*k$^6U2_R(f*o@Weyg(w?)9STXDtHy~bd_Fsg1R#=hv;n}telMkDlSo3PS z$}5lZ>$^04-!h`@d_R*|zj2`Qny&K7qu*TceL`~j{vomND-!#DBeCYybd^^g<=6Ll z`o1WA&-Y7-eIJ#vuJ5lh2GhKnuJX#G{O)7qcON5mA0u|3BvyG%S9#^}wx)f&9f`et ziM`#4-5-cGucoWK@+iOic7SiV-x9k&6T6=iyZ;kwUQJhdk$egkOCVvX6$?;jpf$E(KOl`Y+If8y*PUuApTQhbNC_Y+HnKkl#z z(>1TAtGx0kzkYwm(`hT0Cw3lU=O@;@ny&K7qx@&)qr+Jj&raXlVDhLi@~owakDPN< z*nh+t#KUJ986N5VD`J(`bd^^gm&sv6mmzi;V&^1Qc}-V&<(Yqhox^sE%@V=?(&M{? z%TM@}Ja-?wTe$Dx4~P%=Vvn%ud&RfXR9@3nUU}YKd4;h5E59KBmfNlzMy#C?ciFdl zxZ;rYh@abMjWG1Q;u~iwujwkUJlk)TXP-E2=IT`f!K8*cAbe;Uei@xd0YqPbsdOZ2V&QmSmiZc z<&|f*KR3qiOV7qRcZDw+WB;R8;~4IkW4p_6E>?L>S9#@eAIo4L_c3DkF=F>gVwKl) zl~*43G1lFEjM#mQ*nN^%thtLk5R-vrV*>WrmMX2_!!H)KE@LJ7)$J9GO@~Qy2>jL{HFN% z@!okzHLTw6kt|WQb^H2!Vejf4`@JIUK6AZeziPXg@m(}&q^rjKWQl6bFDy~n;k)z+ ze~%Mm%MXq^I(uj1;y#|)vizpc0%CGX@6+=gGK_Aq$zIn@L zAWzSMos;v?H}ErE<-xPiQxAD(<9fS*SxwpGv;u zQT~a4T1%cg_|Mqi<(2fw%@#=?d}D~%_#^&^weI^F+k!Q_?fQq-@udnXKEhh{8sFCpp2;jI}p1ah^Oj1G3l)7Dz7|K z@!Oy9Q;mC-9V#D~(g%uh)z@X{V;$`Mg!pb9vHi0gODzV*ck7sLzwzBVV(+`e`d&VL zUmyCOjfvyI@97+iTt1CU0p&r)`H8(;V*EXg6|N`KbzSM-txM_Uci;4TaK=-PIUd_n z-q&TsJ~k4=9w-mGnf~~09Wlm6`)*x&KVkVjJD1NP?>rIM`H8(;V*3;HA$C29t(@|^ zdpf5mRvFE!oLZLZpt`BfUPtPWIzBM&bUhL7PJg2b*rv5xJq zF?_}4+v;12>XWQ5^n!jU*Xo7xBe2!0^m(gS*%$0jWgoG8W#4iAnHTwC$KrQ~4mLkA zUR-6^=MC@oTAg@>=EJiMmRN~+a;J&e(0i96e&D9Jvh}W*ix|K0Z{#ojK9LytkRR#b z18*v$^HsgON_q>h%jdw(L+t#-UT!RSs1LF0N$mO)-`jXsy~(EZ7Skii=T;uE)hoC1 zh>btD@`&*p|8{*WZ6Y!9S$V|Zv+}4v%6Y2G0uvzb>8!8IXTn45{KQ^vfQ;)yjB;QX zq@x_z5!me4RLD+^AAnt>$P+sc@rd-{j&J?*Rf0T-73AZN#z6I-3N57l;TJ4bLE;;_qB8^ zRXjaB#{Zr6v3(uXYHa_mJhrd+-|S0s98w*o=2?HzeQBQ){Aulme9Y_nndN$R8uvw6 zU$^r&@}x0Y_e*tc?(N9D(8akBUt@j1bmdq4U+_R*a(eup$}QKY-d-u)#9RBX>F}L+ zs`-89n%{K{soHMlZ9D6{{?ob-7k{YID?3y^@Zb7CH8#$?V`DYPmFIV5%sCV8KOheE zpC9&KWzsV3R~G-Sbgu01L-m37+gG=BY*+XJ&T_He4cr!ItbXp#wQYOstJ}GMJMF8V zha(%rVyGzZJU; zC^IeC>zFw4`&+Tv*vI^cG`*_~4%fAV&1>b|X1(+5=>i@8uG^KE$pkvCdilYxn$N$29g=?bwU{;Bz;z`!BKi+xPyw#=Uo)QJ3!b=skJA zN1g76;~q7!-nZ9#_pk$T<~tAf{3(y}(>;0UmF~~$y?VWGulMkadY8{H;GREq)BEkP-J74wneSXDNJC@I(;CT(U`wzJti*b@;CC7r| z-^F^h!j&B=AD9t7P;gir(&o=s%DF?EK3{3^q&?$UtjXFVzLGrzoQt(toNV?hpQBOV zuiCCxggyS7HO}|fcF=f6^xujH7ASrydscQxKG1&Sf3;6C<=(rVrnQJ3 zDc?!r?;hbkAU@4{E*e9{`8uo9D zn|{6%faQG3#uvVais^Db73Ewb%K23Eu^s1AQO>6@PDML+LwPA3=Tk`@b3x)Emh&mT z?+X8hjO#-z=Tk|4rrWt&nhTJg<^rCZK|kk7=ZWCQd&8J+zj5A|^a&`>^$aKv*vCWa zZ~qQ(2(PgK&A>8?MqowZ>eC$8F#XTdXN+ZFR2 z{$H%geg5MbwZfH6Dj%2;K2UJ9$No>XKiM|>liClecI?Gi{fB&yt7tF$e@67*il?$? z#?Y^NoA86;{(MW822IDe82Ac#b?Et zO4`T6*-e}5*V&mA&-cLJ9{a0yCbfdsi{*K}u%F0%OF3&x`?pN@eccH8Y1v;j`=MTx zR}4=`>Fu%aTD9X^)76ftt+1Djy?Xo`ewy~k;WvfP6n>HR$l)((kGx1L_Q)Zdd<`7n z0w=irnVVDw`yA5K9(hq_u}2Ob?2RKY__1dWj56(S#PCz>u_GO2V(%T;%Ou7*fTTBw ze7V<-eR<)}q+H`D^$DV9fN!HLaQibi(f*C}RA0!mZxv;h_9@R6P$udI9+W9|&I((w zUKwoU^PDO5g3ldJfNiVhqK7IDhsN|BP7U z0N@@R;%8v&1KBTP+?&JQHl*WuKJ1kNr+aU}*popSKuAw_?jUbT_>bRTLK(o|_cBdA>wOEJN^iNRf~?PQ$6 z+{ZS>_^oq|%n_LT%DGAAh$wRe=Akr4(2npE{3mk+SX^>pQ5g%K0)-HVx06lP~b&+sxRbepTd@3&!J*B z%zXiRB2Da!xsU1KkalS>SHwN%)DMa6-KFLuMf$YjPF=s`*m~RrXSWQ#=p*9#cYd0` z-t-1>$NB;JZbv^woUe6CzRBgc6F=JJ>U{R|FC<>7{y`gu#uESOhCk=MmhMh`{mK8x zpZ?=@Ezq<7QeWiuUfiy(vyHviHKcTt&wwFsJjCEJeq!)jxx^^f^dW{mrYAA zc|`}6nIf;$Ma#-Huh=9Popa4Awyl|0e4u7t@r_)|)x27k%Bzf~!xybTaDJ%p%wUJF z<3NjVITs-&mAEnY@ej>8U2%K5qYD3!xVKH?c0AYnV~pFs;l3*S9AXBkFWQmmSaVoA zrhYlaI!M+j_&a4FE9;ag+H0zIwE3@Ge-V3`0qNk8b;=a}qkg6SrhaI?LLSst(y{(x zI@U(QGsQYc%7tvwXNvWduCwerxAo8&Wr}}7K1ZsT8G%uz*bU_}9c7}Q;z;-4ADc`t*!LU;BgUnd*+;(}Dx)=JxoGxUk2jPjtjuhk2(RcSvR7_jkq7 zbwC zWPHS35^9lK}K z_LnYA{ENFLG+o_$0pgu5|5MYykLW;*-}txLDB|ys14cgN2L>N_fs1lDzNB>fW>YC& z2kbn=&QI*+))zd~huHNbcKwM_ij|kryP6(JzRvU`Hht@?JYwUov+{`X8~=8F>LKTP z)?0bR;Is0mKgt8I~_D4CeBV@c@CAKuo zC;VC9rV(M81^aOiY3=z3hfg1VnE1`5w+`n|nxA6p*#7cugsm;TADvFo2?OsudO=GL??hB?>DOENg;BE}qTCR8=PP>XxIDC_!a zf9AdFmkkZCt~`!@^}Bse$&TA?WAd!rV|3Q=)~e)L;HJ;AzFmGzo{g?pBOCR^CmDQl z?fKu$mOX7#@|?N*Z4CoEk0sBWOFxw@^UT`hIe39vvxPQZhCD-7ST<}q?*`=Abep5H z`G&npo^gvU8YV2TCVB2@m?N9#v%%z<^Tyf3DYq_5o{isqKU@F4dB_6}aG@U!e&({Q z_gW8;2OQu+pZcP%d-nA0TaX7F;6ncb2e{C`P$$$4Jm3Hq>V-O?Zr}k2xX|xVC)5o* zs1xc29@rSR1`q0lx`78ahONPaI-zdhfsJ8n@W95fHF(grXk+le#;`T}zO^&j8$7Tv zYz-c?IocjPXmhkZcreDmf5C$`N812y~yMCA&<8gdAz;I|+7k_Xs)G3k?A-yjdt%@@gI`s6kSk_YMLi%Fl{`bN?x zx4x0=lUrX+`m~rYlE>_mTVGB3w3sg@`{dSFlYMgYMe^8~k()0j`=GC;_R7r{lYLsu z7s+Gom76b;$J#45UnGzDPc&a7kF^)Z4)U1)MDs=RSbJgYAdmSEe33lnKe_oLdB6cK z__O&B#xnAN16=TD^B;_5INQgfXn+A#(MTIaDWT_0(C;&z=JxW zZr18=Eh( zzoX5~7s-P*H(w+Vd~n6D`b~ z-rvdN{fj*CL5Y9R-^l|X#M}(~zy~q+z&<|ykOw}9xd--v4@x|S@rOL{JIsH`3tz*W z2YHNLDOU8@m~*Yi%)};8#r9@|A7X58?|sEOk?mwYlBM{|{4~QF53Or`#bU=I&N3gj z*s+MS%ojq6t;`n!;;BAME;N3L)3zYz3V%Ii{Cu5y6Wd^#KIUk4d4m)P|oc0Gw*e`1tUycc(Du=K8` zN0RSq`VkvXS1XU$`0K1ZV*JLxQ7--tIoGq!$|D9Jc#)2B?s&M{JiwklUgU|LhuHa> zAmil{yFSDyC)wZiXS&y`#51DZ4|;mOh6mrT$~izhVv@}>vqKM&PC)G++)dFemf z-u!XH6Fq)T|Cz7p#D;ax*pTx3U$R*Co4t3SFMV+HT-nm6j zeUhC$aa;1NS$A9Z^0R*?&%?XFn$6odJ9)qXF7%@=8_W|v+IB_qfCF6UQA z19`v!F6aXeaG`&pPN*ArzyU7wHPi`p0}nXBg?@)Rp>E(oolrOMz{apOcu*(Q4Lq8zf43NYYxWW^7xoT9`Enu@$rW|KK_sgeu0<>cJ}dyJV-~3 zhIaSyhdf9}%m{se5$nM|rcaCY4e}rz@e%B7`m|WzAP>?JE5XjDPmA@9q)&_Wjbxt| z>#Iqh+UvnSCf76WFH$dTFe)deRA_f@>qN2=8MTbx%nb_ti5vc z#nfK8`6Bf(|H;i4$z$!6+t@)K^Pk*&kv!I3x%nb_%ztw8#pFM^`67A10WR3t{3n_( zk_Q~%f}PEOqWL0uzyU7U864(|sek3D8+gD0F4!4$Lfyav4sgNFs1xc29@NQvkvy=m z`678xC)CaRdv3l+9@GhS^Zp*q7s&$~+jvMGv^m-y`oPBKi{wF@qwS#&Y;3+r9<({y z9{Qlo%@;ZTzz2WZvA!8RXmj&L^1ugAIQ^1l@Sx4j7s&%3{KHCbHG>B}_@_tbnE*d@ zeHy?6A6#;k9urV6*N5XXd~o|`H=2NYxjt!phCUph-9F@TeKN66Ci-MzpA7oAeKH>p z(O%?n`;f=mi#%>0@_2iZ$J>iM?mrpo z^?3kd&Xii=WQiY~O=8l_+Ni=b#t+X9wqC1CeW*S5Ptv`#wmuuRyJ+>v@BD0$KG;@g zqv<|VTc3^E{j;*Ysm}b3e9kQ=aK_t=kr7_x}Ay&d=>Jp4gp) z6}(=!gOLMUy~=xse%F9~e|qj(_;X^d=CSq|TdKC>eUkEy>36*+)4J{8B|o@$iG2o| zRk{^csO&IP+o9E1S=8o-7Xv3Nr+Bf_vudLsst;5#|I8cnS8KN!eb*R8T~Fwrg^WWgq7RdXb@I042k{xjL z+|*&UyZ(^v@aECPntu89`(;PhO>8Bz%C(n9TU87GTnUtQuG1on@PSLbG&ad-TNl7m0ONo-Z!aF(Weg3 zv94w6zN~#*`##2`G$vq7N@InMbzM<^*Rvd3bjVd~06o3z>}}l+m&@ zul0+}#t_PAxtiDda%N))WoqTMzMR<@LVu{0*JaoiTCV2xvU1o>%l(GDl&O{1bx;{C zm+4*?EsI$5x=onwI=9N}w*A(;?gQVN*L{OBTCV2RvQ%DWQhKo`@}Qk<48b#UwrBK> z*w)?;+TVxx8OS%{u-|ikyUb<6k~bZBd6HjZp{FhZ|EfohildHSG0XPYs(ImM4~iW_ zbGFq_x;L*@w`&}D&E#zU_c}K(J=-SnCk;!7J`FcDZN1y7anKGu!_8Z-(KM;k-0}D= zwhNsPTY34;S3H_`8M1G<-u-OyrtVRjduU#C-sIKfFIas zje3*GAoI)FwyU?i8S-Wy98_yb~VzE>RjzISr{^4G5$ zW?834m}Tjc>JNE+;c!K^Md*vAS>l|=FnX5->tC7c zr}^bQM~B?u0u5S41Pvjp?*e9&>dZ?T9 z-e>v0>UIe)+;?@?rTQ!oH-B)eu==AXUAoI7-QsCygmBn{OE<09f5W)a`SoGD70+ur zuFv*y%W-psCC9$e^zRq;i(hSYcec;=%Qi2#^2m5c$Bnbe$7}}wu>Y2^|KLXzuIw}S1f#gY`kyHu@fAJ8*jM7&RK`lr*rC0PTitDohzO8 z=t^mEr!*gxLMqW1IY3ES~bvn|24f zzl}qv&oa&FEa{4@cXK+YKIXu^t$*^F*|S|rXKaOaWC4qm)p2EMP3{CqK$je#=T}6_o9t^(Z;=I z8~1V>_o9t^%{K1kHtt0m_nK|o%Wd3?HtsdsxR=|w7j4{YwsEh;#=U6cUbBsR4L0sY z8~2)R+{TKK#Htyv%?$z747i`?iZQMis z%@)2fW`CO)4(==IYuHWkn9@3R}mCL2#W#6{{Ct50J@|6@+W z*u>}m*IVfGOVgNg-FUr1mDujX+y_*lOG!bJH-kV@! z%_Qqb#Ta+q$d@oS;k^m*?d{*d*u?YNv1`7K@x{j64zbJUuVHNB+5E+iJdd%-&+IXl zj|~ewHU9*wS4z*UUP(Udu+MIZCs@4_f3SKrdAY&rwY=*StX_4lXRvzJyZ)xfkoxm` z9*QwHSiO*r_a+3ZSH0W8;=f5|=i)sDRt(F_l|O|LM`K-(I`UDBVh1 znV$a^~n{}GF=;xyuxcBz?vPLI4xZHR;7{!yrQK`lKRvoNY@#PEk?tB`DEHVnyzX4{Z#Yc>zb z=GGP=wS~1&NNr?o7gF0@hdOyvON43|M?h|#1!$jX3(aJw<)B z?zOOtOZH9%#xUs1LB^#Z<5G}uDXh_}6YNQO>HCmR;}UofV;7uXk4r(uCFq>`^%VL~ zk8U^KwwepbW zC7(Uk&TYrWIrcmY=^4@=yy*I7lg}W3{^SRnjVA-op?5ytZ2STIi=Fyfvy~fAuIbz? z`j>b{>iNL9iP+`Xx$*-@kKkk#J z{K!=g3L9SdV14gRCg;D|VAt^1A#`ycuS2w)-XiNPK z-5cY=D_+|2_T=&Pvkn***X=$mU;Kh&>KA!r-+0SxkK}4w#Xn@7;cwsN+(iBAfeqel zwz>z@{qvvwwb^VEV3YIT`(v}&D!^95=5A>=8wS|$`8mcnn{5MZ``F3jn$6|`Hh<}* zO`5GO0@~uppU&EBZ4}T(pL{i-$=WWU?V6sttgE$YhBjUL-n;9ptuwUs?44GI4`lEG z*!l5;?zXc(o_!m>m-vURGxy1@-?z(IVSIm;X#3zpupf_ehRn`Du^*3fhRn`Du^(@` zbO?3^+T`a9!OlRjACGf}U}vCs=8*6EwKLGJX@A|$KkKhwHQxleCr zpxBS+`ga-d1P3k3Du8&rgazb6GRSzxHaog`OH~<+Xj=E%ekLc4m$~)IM#u z`2|ng+0Bspy5~oQoq8;jcj~lF{m@|thY|mGL4NwC(6{n0*O;fiWyyYF zvEe_B<9j}ceTjfMzsJVA)md7wzr{IcU9YRjW|k*Dwom6Ke)?e5b~Eqz3E#vSDq@fdS9Yj;pz?vX@Bz*d zh-aGH<1R{l^J+GxwclNo`sP>K<<5!Su|ZteZg+=%fA(HBFBEO3xN67gy93sK?O5Hh zvGE*ZfvpkY#}%&ZQ29XR1Ch_xRG4RKGtv&}Yzv$vwllbN78dLbuF22H zf}O#2^|P~JXK;0XrWWiBuHMhuY@INq{`y^;xCd%ya7f45T(C2^dOx!Zb_Q4PXL-TS z;OhO1FW4DeI{OQLZiut3De&~_w)T}Ba6TBOQ@3>P2Hh%Lw9yQ)Lov3EjU!tQu-LEI zpZs==`Cu836DwTA%at7}JIpLTz~_L%T)(-*&IYFi+leOkyYZXvZ}n%U+Uz~2xG!OA z&<-8^jF#BXZi($rIMXHevtD99119#r6Z@Gl-_7A?$;2q9cwcPWzn8Z7b}jY`S+6$# z25|AtQIs||2#)p+Fl+a=udjYr3uoUr14p^(OdZ&Mc%}}J&eVa^nL2PfQwL6G>cHtt z9k@OH^SAqSvh&~e@Xw+QuOI!m!j(-bADB@-084(&<@16)Gh2SAkl5!Dj$J;#5T`pv zkhdS+F#u*vD0lD?Z*5`#4N&*)cv7`?yW) z<2iBh{`10)?J-}Q9XWqhZP$VJpZVJE>prJ#SYh;5{8aX->@Yn(KpzT)4cmVFxAC}I zubHu@cl{!3G+nP%?P#{0p17<1*4;&HSM<9IS9Yj;V8;3Y*uI_@tMyt}#{boNZ3ySc zYOOuvzim*gwX1P##*Sl^Ju7>v4{%gcQYE23&%zWoiMcWl?oVMR5 zxBD=4$yeI;ob+pdOy!}b6)vn$*`cz-^!Y$(zbY=HDXLhk@QBI|?Q4g^-n#FrcdtyB z@=liC)zUo%z1!t?gn8#nV^xe579-dhcNxQ`yHv&ZE-c-780$Jev6oBi`VhOG#2O0} zcae+v+hf=y&+lD82m2}SWa-|&#$S53OYeMHy~?}WRxcJ80axEsEvO=mrWYqGJ564 zgc}kznJmdz-Yn%c&X72*tdPnw9YWH<>qt(+G3lx4Dz7}sujQ&frgN#M>aX?E`l=n& zK594D6T0GAv@-tp^#a@1+C3I~edT%~wF}={i@a0S7kuQ@bmwQ@sn;V@@v~gjNA;XW z9Fh*Yj?i(~{$BQLkMpUsu2Zb;{#l)Fos`XmCuh-HXZ`PmD{TeM=al#6f9SSQ{cKAj+ zaO^AoQth8qcBp({#`!=o|5Wz|dvT1>v&dRx<^EE#A@-e!J#J6qcX>{&=hyCg zl=MUSXgpaMzy)oW4;L?_<@z|Hf#5?|ZX9LpjfAX-n{)@-(4&Fvv42u8k|6(g# zOa7MmhsNi(ypr;YPZ&8M_UZj4)7M*Rqxf;3<=HMDzg!nz`C`LXxR!h^{gr2-12&8s z99vJ$#k=ho&-v$U#Cwn2FCMkXz0_giKZeCao;-l~y>%PoPnNonbypruS9#@8el556 zXUk=G(PsL+KHO2$3I)e6}wEviR^9g@rxw~9(Xnf?elc|s5TJnpWJ2HOsc2CMH zKJL5&<8Q)^OkaHG{_(s`IPK!?Lbicb|CR zQcn?Yu-De{&0XiG&WdZv?|c2gc+<8YGq2)1=jaokxT_0!-rS;FytU&7#P1KAEnakR zVH3r**E6t7q;E}q7CD5eGA);*>cBt`?ZB_KR$cEc+0rLw%2qV9$#!K zd{22aUFDTW`L$fDQ#3BtQL)uKTK$=B_J~$bVzXIp_G*P|$y=L5YY)mRwsy;{{g`g; znOi#%Tbs9-y;|W~@~X39WW>s&=_;>0 z%CF__aMHc`*1HvDDV}@dUGnaKD*Er}8`o?3+wFy(wU9TeA+-+1>AdWP4E zyoztWd-H6i+eVOQr`zwy=KlBo#JhIy99m{A>Z`bxyy~o2^KSC{d$YL*7Il2@%>%R9 zUoPxC*R~foY`MHw>;+fX;{+ zn62&*yOp?>ytPFx?NVZEyN1+u)<#)sQ?pej?Ox(q^0o9=9}K|9NcJ@Qv?M#5 zeez^~vrnGdMR_z`<&{VIwOp(PrJt4b|C z7EEK5_5C2@Scz-N*V12kuog_?0M>$Oe85^TjT=}Crtt)8!8Fb&kEW}<@+iNSi?yK4 zJ0-?iFwIR^3#K^>YeAXUN?c1GYeAVeON_N(np?3JOmnWyWkKfU64#QirN8oEEtuvt ztOe72hqYju2eB4R^CQ-RY2H*GO;>s4QGP8KYe9*lN{qE&inXv7OfeYNf)b~dxRyND zf)WRo7;C{4D`G8}Vn~b4g2b66t|ebff91hiFvV$D3#RxDYrz!PVJ(>AJ*)*&9H=~+ zuJX#G{8}#7g0e0sG1h`?A*OJFtP}Vgi##%6~eXtfxYa&}~1X(wg zxR!h^{gnr6!L;tcS}?6guog_~6s!f)`UPvjw60MeO;>s4QGP8KbpjXmkrboeX)O$U zq%|^ZChO=D*OEt@$U42mXt%VMM|-9krgt|hNJE7rUi1JLKeiLn8F9vEW=`aCek67+dsj4|l*z{;cPDz7}s zujOLS!B`JY#h91UUM1$Mw1qISd$cAm%V&%#E1CfH7xc4g*#mO;>s4QGP8KF%)7Ka4JTemG<5d zf2BQn#Avc_U*cNwhymqXpu~t1)7b&y$8@HE7!$D?^if<(UUgQic@d)_CIcs8H^gMX zi0KfM0VCE!Oa_b?5HT6B@@TrsE06MPxmXh*76+$dtQ)X?KsweFSSJ8u&4IPY)VP*B z)-+h#KwdG{Jy`!B9qS>ibAYjC!rEhMTuWYcR;)Z&b6|}DPOL?+#sJ0|1#1jotX;6i z0LGdIYYbrJ(R7tp9_80^ori6w*z3-+ypF_ftDew7aV>do7v@#$ZO1x#8|C11TeZTq z5 zP+qZ*MNIcGhd%6mzZI?}uR1GM9`Enu^!`rl{hc~^e<$|-&blj)rmMX2D8H8L<9r5R zQtWdR?eB9C%k_DU`Y5g?@AD?*75m)Ebe}_6cc05z;ac*lvts4(`HP%Bf3aMjzleSQ zVjX?{V%?QT(^X!1lwZsB{V3|7*!R$w?t5j#zUS5o*OK==J<2QgJwT@WULUc|71%#) zg=@*H&We@C_u0tl`)tI%&qnO~Y{b6LMyx!VuJX#G{93NZhip^D9@8@2V^@~z@o+0# zOWxyc$}9Gmoar8W6MGEY3fGcXofRvO$GznAxR==DUSf}Xi9POR-IYhvRbF|NU(5CN z4*QE@U!$=sUyBj@`i}Z2t|jm5N9I-RYfSR^T9Vk;bgghLdDU65^7uNAoW71D_H`Vw zuj8nvuj7c7N7Gead6Zwv_4PZ;QtW#UO!vJ7V&AW5g=@+CehB3i`<@BYeQ$)=_bXcA zTJoy1V&(CD33B?r1hMZ+5c|FavF}R|E03nDyz(f&mh1abY&*rihsLseuZ-CD-&)~X z^1i=EdBwg5$aLT9Bli8bR=AeD>a19Ke4mY+zRyPN`)tI%&qnO~Y{bf==_;>0%CF`6 z{wg^Y`<^hr_FTVyC(MiIPWGl z``{d$*zAMzabo4sbd^^g<=1j;{K35xaw@hl6L(jbZet_vv=G}Ei+eAva4mViS3`Nl zHs<5*4byFG$DJHv8)I>AC(Rcnt|hNJD^?yGS8?x!{5G!QJ`AyqtGFjaY~w2K&k)wwM9;xLV;_@_tW@@`^2n!Cf+@ zTdaaRX2cdV;2v5lTuWYcR;)Z0C*U3zIW11W{VrmQ6L9Z~*y04-2P3vP0r$j+l}FQ6 zUU`&X%SD~Qg>|=L)Eo6jI_!aZ0$U7>dx`Wn#kJ(oCTJVvRg88+`yn0eiFN`;o5NmH z<682nvts3e&0r&N!j`ZRFl-DP0mJsN5ir^WHUd^2O;>s4QGP8KeH48IoQlzp(Vvly z{*8VMY->8)vu%ZI$zzPcScANZF%DroLORALj61*>!_fby#CXT{2cF#vrYoERI> z=YcV1pw9ziEJ2?K#u$S>53D?zuJX#G{93N#jVSuJX#G{8}#NcFd`$mtxHShy#$0xB&A#ua19K5IZ1N04HJ!#0tQOH4rNR zBL+dN0F2lKu>!F2Xu8TPkMe7|*c-#16gU;z-h0G88q#f#Jz~EM*!Jop_T8q&wdCzA zAYzXX@`~;3AYva7>2^jCvEK)5d-W0fZd2o0@~X39<+1(wh`ly&+WvgRUK_CO&qwUF z0o(q3#9kY)?axQ-wE-)SrmMX2D8H8LJZw9~UU!z|btHCMrE@6Qkhqq-w+r(s_O@dk zy^S)|%Wc&P*OFJA6)TV1hn#L7mh1MRZQVZ9)9pj7JescZ%A@>RuK6;@OYy^z6LD&cwXM?a2u<~fS$}5lZYq^+nFxG=pG3F)APe{jng?R`Va~kHesc|iN z%$b-wA+H$oD&|+DW4^^a3XC}!^V!t6mb~h$Sa~p~VGaW)<~qz_z?cIuhXG@5#2f~U zITLdju<~fS$}5lZYq{Vme#VA`s`ud}OH?+ge53M#$_J+OfmKi3Bd$N;4aOmgXMM15 z9Moqqj-x#nTP<$?(mKSSZ!uqN>aq>-UC%t3Pxw{wT;3i39-E(;7tiHgdht~)b1z&x zi($ASVUx*{jOEQzUgHdj)5;2|EYl$*9Za_%dX`vaG_P`MS*nBTraEg~w2oSLwTas5 zp@G-tr*AWa_St%`U*yN^F_O6Hi#PAM`SrpkkFPjKHs5Wo0 z@ONmCN52y^^>>Tpoe~l6B0;(O&JBGRhrXl3%cY;VKE$pkvFlIl?@dbS8NQo^vh;n_ z_RsP?)%wl~eV2v5^NM**PkdL4I)g9ikC;r}6JCD*)a7%O>pT(I`H8(;V*3;HA$C29 zQ4Z{gyk@`h8}InHm7QerB;z(=x(QTmXGZv8wjJ9q;Qz(Xlyg~1tz!OUiON2epG=z% zoVD6AvClQV*|!w$w9Bu;QVaZy>8Ji{)o|ux>l1Ic&b(pGmx?&>i|3xn-uV6AOrP)F zBe$xU2sgJg!;D}}0_-t}f)|qoHoQ>^Q#H*XWcy9L4^9PfE zRO8!O$ESBE9=`u#;p8j(5_g(qov_dss}VnS(N{ae|`d?O~GRBUw&$%oCCvgAwVV_EXC zOS|;VlJA*MHYA@kUu{XgYCfDNA2#34lW&{P$K>uQ-&eUE$NVzf(5Eh9j8nYA zEX%|tp6$)_=7s*1FSE`-;(K0g&RaSiMEuA(%jaEhDq^I@&)4et@#l?9Z|SsNc2>(s z;`saPvcE4egm{6`9m2tbi&*QxL0!Y|*YCyj@2jjo9rsB-=YXPK;kKsy>HjP0_1-64 z@_k<{>a}6NBYRH#S5dDs=G`Fs>X4#d*Ud9A`@^BdzUbULbPV;|_Gex0>Rlf~Q?V~P zf3J-~OSj_e?2&;3LieWP?CgZU3<+oMa}|AZV2@GZkU4q~Bj!l4x?+{lyvnI%sSc`} z>a2CqI%?h3CTc5fFT)}EiDL7mnEcAxI;OTZABf2Z%s2An8|E{4@)`4`JCZM%k7dcn z%=fb7d*+i_^2zor3$cItPOG&`Ol@cF5>uO6yTsJi)-EymfVE3ZzG3YWlh0VY-?Mhfl22N@WXV^pU9#lEYJbHlqj{B6%TgUwH`Q6|qIJ}|t4-8aYC~Up zvF|AM^(p%W)>v3)dK?y0AMx}I=`K&~JOSy7+k#X1rv*>n`ubFS-!3!PM~0r%@RI6rX3;Q{Tm_Na&Q<#!lNywdeQi9^P1 zM|}P0pU1DZT)!2bPR?MQ5#<_xiBDW~v#``}mtguz7wjHZ-SQpA7#j{aB%FNu*~C4b z8y$w7(}_6V(-JB}L%|0R7$Ly9RyO}++WKXkm zL$b5kswLUq+9j7ZD)IDiT79F`y~JjpnCxSAi^*yjJ)4Moj2jh~TX{v|e|^;$ubk)T z_26Ui+);6sQhmdqO9YU&$=@3#KO^1-`ZaRcy z6Vo9iTbT|a+0b+d$+o6LNH#YeLTU@`BdU+4tGx0kzm}`|sGh37)=TTFc2FIr1;amz zpY|QMQ>j>oRTvhi>`?eYWrxZRl@BBzura)hL;iN!JaP9;ih23wo1e%R`fc%?+L+6a z%sY%Lo?n|h=+2g|e<|+Y?)2434f6~v*5lju*+1KGj^a75dwzX?)~{o6ul1qC{{5U%=Jv2U#UXu8TPkMe7|s*mca`fI(kzG?@b ze*^4w&1z3&FRfYJ<2rlN(b?t=#XYV?kDJtR;_by+;Gi)_wEWrMQ+?tId*;iID%Jum z%io>hIUvrn z*e#5~<{LjEKD7T9#P{9T7`M7;6~^jEEgd(U6!y!OSt;`8qpZMxmx`^VY0 zD%$k#YaJL5-T5Z!x%I~*;_uhpgm}n{jq%k-=b+AW-#FaSY6qn@`1_+W*#4~xFx1|#^RQk;v9=xVv2t(Ziy)_vbZHr@shry2>k$@@u)OkLs!VYrV9-Y6sO} zTCmMuA2Dz7}sujQ&fs;BC&_0syP9W0&+DfUxr@lQzckHtkH#YGk` zg%mGY92HU=W${%=@s-6zA;n!tA3$(U1h z)^wFu9_80^RUg$;_1Ai7ebo+XAGMp>(*r8|HS>(6mCmq0)n0`kRCf4ZwZp>?J=J9W zfMf5|c25fTT3`!*CWYAkiDy!X^|>Cs^W%3vD5LkO^qv*^+nCYUT6rBhcskeGdbdjN zkT`#Yyq8OC|16)8(Pw8|f6Cl=!%MjDL~QBh^EiIrDe;ug@91+qR&GFfDA(&v?00ym zv)=!K{dT`+^$C#o^bA<<{5VfQy7Lozxy1G-=tJy!61)DytFJas*#utH^r!U~lgz8^d2b2=N})ELLEzaj6=-MieFIN`?PKI96!9~xJD?NsiEH{Y~p zT=L6Th)18)FJAV-A{>A8j+}Dpvqckccs{@I#z7pzmwR&FxZI(|dtE*}eAPInS5Kzj zzi^*;*Y#b9SDb4=T=?n#$36CKpE)3Q-?q5Jshs*uS+~^}%$f&|W?tJr$NRX5Ej>@^ zDzDFE8GlIpR&Ge;nm!@vV|s?9r|BP({#LIn)k`_`o`cycBwLvcL$aaSHYD4c%|o)e zwM9s6p*)JUjt?)jN_P29#hK2(F26im>A0b+`^`f?&9?v3F2rvyv`kp|f#TgepAHOR z!t5(CeXgFr4*Ag8i6_0aUpTho-L(0;_WjmBuTy-#b*(EJ!#kU7LEl(!oiSn1(jT_K zV~;t`p6z?(6#7H|zw8-y-l_17=Pv6Pmbt0)jq?7Eb#9B@v&K2h~GSD$GFsp;#;~aPS_yce8!3aby=wQ zvhje&Hzq#iu+Q>ty$hSq^|LGTBYPKZaoxqM<{dXJ+DO~caCz_a{v#HMM_p9dXGouC z^9{!CP5mES<*0o8A;lf?ubQuIi9ac9Vz?n;lgW~d<;_xF;|z(@?>3WDvA)0V#xEAh zx;Kob%vl3Y&%T)TP~u~be<6G9h@!nz9`#S-x5s0Y*E2g4D9`e6=7uvr9*dgafi`8iB-n)($0?$=pOquu1B1|ylLF?$t8#f-LYF7 zbkqCnYfb$Qj(4nfA@Se3j*iD4vl#J!Pa5OT4?cnK-e2gK+NFjoE_l6we@>|MV3N?=99y8N)3Jn@pZ$EN`CjDyKeY zVLF7QgXtEMZl-fcI$K>rs*BYzq&iyNL#n&kBqW=dtwOSumSuJh$N)k@e=1pkC%u&UaIyUi@RR5mHP~_%@5OX7pvNP z^ne1kiojLBtNLBr-+`?9UDfZnKftlt#~$KpzAL}cP=5Qs_cLf8KMx|V=DXtE!n!y0 zzi>|KcgQ2g5XJ2o6Si+zsOf)N@2bq$VDI_la|)KP#A++^nKpf^5mhu1&U>cu*Mf%q7InZMAC{(0MX(JMfq9o!0k4>pR{}pP2M9J!8_-^p8n@t5;0* zviinUU$a9@b};+IWS_R?hi4Z*#lAp=D?3y^Q29XR1CWA`xi+WEahCNUo(qSi*SMaPA*L?g7mgniLugmAc zL+t#-upjXJ16@s)xN1B2+|1c_KF;x(_qKjN0G`>G_niimhw|~h zQhYlQct*YV!`_KekMh9j@5&(d_qY<yjhgc_Og$6MMPD_9y5=tnZt3{h4m|!?zTZyk#kH)pj#u+rb-JwP1>=GbZb|&{{AC$CL> z{280aE~_m{yx4Jj#6dT|L4AI{%^`8VXNvc_zjWN_`0i!%F#WuD8sm+dKG75P>a^F$ zII#CGSeIWcIV5&E`#R#acNh?Vbt*NVA3t<3@%>wL&L4WHc!#{|pt!Be zb^m0Wx(~Bn?%TxPrqo%n%4lBY^tuH2iQAmm+k)8Jh}heX*xQuY+nU&YfI7Qx5WCM1 zyDzaF-N#rL_dR0wNn-caDE>_RW71#i;=V_Fx=#|juM)ct6T5E{yU!DQU!cw1SBbsv za6D10GMZO8wJg;^byJ%YA3`eLci^(L;X!ZJ$8k$;NWAm|v&2jP(4Y8>xvtCm zuT{KLahFM}<>xFlis`4^di45-nJ=P!*ZO$fZ1cQmU)4czTbKKnt4GEIH!Qvlan&Ka z#12pYn{|BWrj_F!e`%ne&pb9M|LRZ0cVrZ+jOJBNjeiucxBBRK%<_w}tiO#I72jI7 z8?ok9tTLK+o)wSDcYgP<0DJDZ%(MB(}c`8=FhFk@!_5YN5uvIusZd; zcEHg1({ukod_lK?u}`1EH-7O>pZG%4&m!`Eyum85$F7A951c$#T)E@+OjjHJnDp1W z9Dd77`Ke#-MVoiNWRbY-&Hae4t6L{7`|N7O8$Py8T%+&2#QR^rZ@hfuBeePFU53XK zZW&BG?Bd3_$-6so{P|#(G4bP0UvXUe-R6hHmp?7ySj8%%d6iSkQXNz`)miJJWhuV! zPV=8(=g}Vy?S63l?BffGbqrCgGMe{|SBJ-c>^gvTf8@9^amnLfV0|CoYwvjTP0y0E z*W>HPO&0GF;bV%YCGUW_mI=2$)|+`p?eST*{$|$a?dPkHuFCeguNbcux?ha+UR-+GaJ$S;d|r{lQu@`Lgsj=gxLck+cV+nqB1j*G=D59~`kd9!um z(5qG>{{7#!iXSYy0P$}h8Wd07@p;zetf7a+_s{q(ar2>L;>O#)%=+$ofxS0!=q_w` zt(Rhz(Y(s3WvLFTo9e7}(K>3~)h22ywV~QpZGO~>1D({=VcUablOHiFaCb*Esrb#d}#7?08UIZ*p@6nLP%Lip_JZOnk1*`D@+1JLAuH zt{WAXowY0VS@Mj7;>V{K@y3TA>>4M>e=z-*t8W^Yx_L?3=iSeL9+!Nn@QtJ9oi{G? z={8K?<(wz;`L-`?_{qLU<$LT`eEUpo_+!#v>k_x?5kEY=nA3YVZXS>Aws+PrS(!{S^k98dh=qhsRU*WbtSPyPrY?eyzGKv zTzdAVE#i|si#S=a%4lBY)Us3u)lGHQx@cL74{7QbpT2Dow)^&{ZXW-#cCojkV~Apv z(Y)wq@DKPW`XBljF#09>7%=)P`o`3FTJoZ=pq-ExeFc367<~nO1{i$>eFhkP1$_n> zeFc367<~nO1{i$>eFhkP1$_n>eFc367<~nO1{i$>eFhkP1$_n>eFc367<~nO23YH* zSY85Pcla(a`T=|w82tmj z3ygjP-vvg0g6{&OpTT#5(f{DPz^a4dwk{WO5Mm(cfcOY;5-{Q>#81G8rw}(xja5eT zDyPO*iicmkcD!|uHOPtI_&4}9uVR&%BCo|_n2(Vcu^8e8V8mjGCx8))AWg>^aTPG)EW}&Dh`$hr0V6I$drCXuS|4kEV664A<_E@FA8USKto5)+8bDPP~6t#Vjmal3h03SUF`D$W8WA1zrffJ z#=hs&SY8jQvnx>?LEL z6c~HS*gplvUNZJofw7m2{Z?S?C1W2J7<lV72FuNq?;i_IrZ0t8pja5eTDyNpEI;d`{v(}|nx!4cGo)`4NJ{k7BfOQN} ztTLL{d?Tj5X8kKqebD+>L+YE>FS68U6;DfEYoj3jB}jh>(qDq~mmvKmNPh{^UxM_P zApIqi{*p<5X^{TXBK;+o{*p_7DQ%*4v_4hJSYIpiS|2Pqt#6iPS)VO+u)bXCW_`TW z+4_E27aJ4GI@(xK*4@UC(k3>xl(w=lr?jDsMWt=k=H@?{_-%>JZ?ojv=C>jFy!mZN zeZl-Tq&{MP8&cmfzYVERncs%g*UWE2>Vv9-;$vDhZ2*v4X>m|`A_g<^_@EJlhcMzYu`PqCB5RC$W2EY@mCv6jU`4Jih* zu{4u7t;8y$d6iSkQXNz`)miIOt6Uq;voz-0c%G%XpjLlZ8O>{J&pfT=ZT;Sm*7&x5 z&(hl8*4-iP2`HYHytW1mvYrjH9uKk}53(K)vK|kz9uKk}53(K)vK|kz9uKk}&tyHG z$$Gp&*5fU*9xrX8b+k2mDPwE-GOw-iOHNz+mu1f zjL@4a32 zdo$VZ&1Anfll|Tx`@KQ-dxPxv2HEcovfo?U^T(vW*2VT_W7?awJ=>V}Y;7+$PkXtx z$D5};UfcU^NqfJxC)|+sgl(@lOMAt(mz$+MWZMf0vd>&%mC?M)sb#4Ss+;Ppb*WXZ z?MH>QXJz|QA?;<=8c$S4^IAV^z!?D6Cf5J5bVh0YGNiLh>#xE32G?bZrzNlTm4N+m z@LOLAa-JCEJTYM3A2QZgf}AG?IZq67o*3jjG01shkn_YK=ZQhi6N8*5W^$gG$$4UF z6Ro55r&7lHS((@RU&(3xvMkH`YpH|v<5D;4-=)sh@5{Q_cu>~S#)-1-Y7-k*N?X}@ zQ`%5%t2Q^E4cNzoZ55ke2b@(P-TXbIGePSIA)OUk{|M;}(fUnDXN%UKLOOG_eiqDk z*}m5QLOP>V9Tc~9xfTZnoI{{q79WLlhs5HhknWaPJQc8~4;jTOqj{B6<158>-VxH7 zi2V*Y{{X+{Rje|a*J80~^D*;UESAfCm0a$tSUnR(Wl_2+3 zg4|aLa$hCLeU%{hRf61CDed`V(qHRhaZ{e|mRLNMr#mMWXXWWGip5_I>5huUWm&qr zV)0s*?zC7O7t&o9i|+!?Kj0@80|uN`OpR4W^D3v7r8=l?s_~>Yl2ha9$!m8lGu)d5r`@&8 zaGw%b_X-r(lDB750`8F`uRWU*aHk*Go=pk3(+_OVrUcyS2exNZ0`Bw!+p{SFclv?t z*_41g{lNBYN`^cA!1ioPhCBVh_H0UqJN>}+Y|0(D(+_OVrsTNO4{Xn-Y%!*&RQ3(qt;z*qP9{Ss%_Qg_H0T|+*wDx6x*{Y z8Sd62-JVU!aJL@Vo=pk3TMul{rUcxr2exNZ0`ArW+p{SFck6-e*_430^}zOQO2FNE zVAVl!TbGOHs8V0R^Hr&j;JK^RcdSiA>QjnUM)NAC`TRGYMdChk>La+PocfODRje|a z*K8G~zeMRTQTj`i{t~6XMCmV4`b#eTC71q^OMmGp{UwwBl1YEbq`w5|FQq+yO!{kG z@Z44MZ9I>ad>+qfrM`gYw^AR$b6u(L;CZjqr|=wD+1Kp(u+#_f44L%P65|=NBr`=` z;ncEJ2h~k=*1FUx*Pea39nZ0#FXK6wgmny2tTLL{_MtPJVS~r^r$c&1!1k>}dUn9} zvjh4SWE4+JUfZkAaK4MYwpX3Wef}W#`Gef&4|1PB$bJ4G_xXd|=MQq9KgfOlAouwL z&fTGd?NtZ4&mZJIe~|n9rA@Sswx3AHCGg_SZ|DZQs4D zi|xmkb+mo@vhKEjU)sd>^-EjXet&60wXNFR_KXA0;ZS$Qwyzv)@0fGF?Kg*XC*Ss= zL%OSP`_m!a;kSM3knZ-|es)NA{%xN-q-Oza|2s?12&fK<+qzskCk(bP#`@a%VMxz# z*|}m!&vw~)W5Ag-Y@%3YG_P{%{(xfJZwol52dC}B1)SdlYhJ}Fqj~MDGPm<8_D4Ib z%;kBp7I|JQljp@Ud0s4&=f#3NFBar^u^`Wj1$ka9$n#=Bo)-)9yjYOu#ezI9R@(E& zq`%h1&K2|YY?qxk-kzTMvUA8RJqu>%lUaI3%+4)CdUnjtGedf&%+5JOde+R&KLgJ1 z;U{)R8gSM=HC7qTtDIVv>Y%!*&RUmR<=S~pz&Sniv2&h)^Lt<&Llmow=CwF3AVx=C zi|+!~NWd2N1+0;PEglROdu3DOX~}D`SPSA;%bO^1;p{d7K;VM_rMm51;qWp7K;U}2Y@XW3s@%rTPzl^egL*uEMQ#$Y_V9tdIQ*E zv4C|5u*G5l>l0wDmtvLCyvnI%sSc`}>a2CqI%?h3CTc6Sq1sk$ZZT0noPl~NwwNej zErE24rvlb6z!ql(tYLsH{t8&b09#xZu!aG)crC*k2H4`b3~Lx*i|;b5VSrT!#cf@# z`zqVieVFxf-zN4prJjmaM)NAC##f4M?Gn;6m9};XSf9WSnpd&PXkNEfL|$)GVsC3= z_W@$}jsMTymB9I2b^U*K5|QlNqmgXcv(5irvLs8E?0a@0d(&WyEUAc8N-34yBM({1 z_P>`XBqb6;`$oGWjOD%G^Edcr!aKm+SGVb*!V+!r+RNExOl`Xw){+ayocdBWTm2y-7H%zcM2 z_bI~M*GT5v7YK9Tr145(nManDb;`CR4U#rVv*bm#C9&JDXzWAqeHoLz9Op?gp2$41 zEU({)cV52{zr22mtIuE+Wk9BEq~bA}nc;IJMj5F`xM2Jvd?Bn-gukCryH79$8k_$#VqN zDKXC%l+N=7VOdsUnMao8y`DvX;XNr~-m4PkJuG3~+Y;tIuR&Sf3lru&GGX33)A+!9 zYNC_(+Jt!zPMG)R8g=rXoiOj^2}^mVC;BBXyf-H~^PZhB@8t>e9-lDp{YmD0CP0|a z3TXV{y*!OeycZyuODyxqva(LumZU+_CTW(u$hIWr{Rq*+`w_x&43Svok!AV*lz8X+ zQ{tEJPpMA6_telaiBnRR@8GB`--i-*wrRKzCG2d|a34z8*{0z>l(4f+!+j`WXPbum zP{PhO4fmmhooyQKLkT{~>^TWL+cem75_Yy}u;(P~Y|~)RN!Zz@!Jd<_vrU6NCt+us276B8*V(4Qo|CZT zOJbQvmX&qNwj>RbHc7MOMe-_2}>FzPVIKtW{hZH8-BuU+fSHn+LK_JN0ya!%Jr4RY;Q(&vb`B$ zSyp11=Qm|Ne*ueejBVNtFx$ElW*d0IY#UGKDr_@PI?T58gxSWPFx%b}ZETZIm~Hh5 zvkgCCw(Td(Hvfd#7l5#oC)>K)^gzGlg>Cyu=4|s%n0)~VvyT9crR+OEGH0Ix!t856 za${cr!faQZ1j{_KtgKVEC25efNtz`u$+gS&%tQ~{GZU6$h{Q6FEX)37#5?i`;g3ex-R;94jj+4hhd&x&cef9JG{Wv~ zAO2{B-Q7O?(FnV{efXmhc6a;mMB39FNtLy zSyt95+mbX$+9b`A7s;dKUCKntO3F~mR?3|HvxqN=-Q7NX$0(is!U(fp7-9AcBg}qb zgxN2QF#ClOX1_4{zLExsQ@dUEc_Dh(N0>1C4ijdd*(6xzk!62Vr{}-p)h{sn%TPM| z%Mg}jC6;+)S@uOW7@yf^mN5I$(t4PEY)Q`SdrO#oatX7qF44d~ydFKCZ!cl?`6bN0 zz=YXHm@xYe6K0=c!t85ISjsa!(Jy&n-(mU|>{Cp8L-sW$nX?ZvVfIZX`LNG2VfJMv z%)Z8i*)K8)mU(1ZS*L7E(jaM*G)rERYnS~oi5~XHBrL}eiDe#HmhCgCEZb)iX8TOS zY*(2Cr=%>~_))(=?0no=qVFJfKJF}m5j!7umcWRek2_0X#LmZ^B`{*=SSAe z!m_NyGLJ0lWCeSEzrVnq-|sK5=O@{+jXGhrU8lC#rkya`x)Wv_c*1NOPnd1y39~Id zVYaa+%(nN0*(RSb+v*dR@=Q%g#!!M!^$ z+x!!T9S!d3Dc$oCAk4PDNib}1aL14QzbWha5m35pOVS`|lQc_Sl53akjj4XNH}+|R z?Q{|>^T@KW)5IM%=!g9#?)ZUW*NHoRV7Kl9DoL{W>sgEphJ-3|mXw z#{9GL*8FGKbA0?%}|f z#ITFRT|3fYFNr&TVAxUOjvpBImAK;vhTSFZ_<>=Mi93E^*lFU99~kzVxZ?+wG)SD< z?XrIg(G2@~x~F&a!0sOR_n^(~NfC38=$BaLk!59_ZjOL|4b>wt`?F9w`?C<1WhIt* zWLdY@L%cqsjbq9Y=2&x7C&!>8%(3YRbIdxz9LtU{$G9WRvF`|TOgzFID~~X2`Ne)8 z@%kv8W9|{=SbT(~4AT?+k{8(B<6a#41ABbjmjlC2ANT0Mu;0i1Ixy_|aqkWcdw<-= z1H%sh_w>N<5Ae?r++F~20x4Z$nManDb;`CR4U#rVv*bm#B{A%gaZe9AVW*7ydtf<+ zNG$Wnvhb6}9X86se;RlE!0@Za9Y3%;H%3g_Bse8y;p>e1UDU(zU=1*QopC=63}0v5 zTLZ(_8TZ-1@O8#LH!ysiasLerUuWEl1H;!D_vOIwb;dn9FnpbHzYYvvXWY93!`B)2 z@xbtP#yveSe4TNB4=nkTSmu#sWu3AuNrR+K(kywAJWAfBOr)%&45e(P%;9s4dpPhV zG5nHo*N$}fE8~tI7=FyS;|GR+Gw%3-;rEO?eqi`RCvaG~1 zk1Xr%st|9S%5qF>!W=7`u)Bjpym7)DTbnS)+$PMixCwKNZo(Y9n=r@pCd{$E33Ci^ z!Wiu@{(M;hzEdsdeDYA0l2>h zmSc#-GLJ0l`WfEBpt7$2;f)N!u3zHq48pFz;!O?GC5cl~*7X&qwE8@z2{ARpJC@a6?! z*U#`4hDEyTe|RHgg=CEiP-bi@J__Lg`riP8}ZP}p1Iy(CIUEI?sziT9F7hHfo}_mW74hy^I@EfeLL zp6HjnxOEfWHX`}B^%UMbBJ9>#cngWJTYuq=B*Jc8hPRUlyY(90R3hxwad>Nquv_2Z z4JN{F4TyJ|l3RbHc7MOCAoIpe1bP$h#oi3;4K)!atx7J=8+3n*^z$Eyuly&z1c;k=iboT!i=h5gR?(6|?B`3kj<#%TZ zc<;}mtg{`!dw+xx%NF>UfcO3gyR!tm_otDLShlbO07fiZ*arYhxk)VZ$g;9d*_NaM zadv&$B+Zf+$)n_5%0$Xa%23Ky%G~Yg@$Me+F0tG9<83|~i`;nt-t41!%AFJ7Ek6S} zxbp+N@kiL5E8y)v`Y!Ig0dE2lcIOayE0C}|pTHY}ge46Ur*^yUoEUGp62I>J7;n51 zkM3Lpr1Az_%IuPhUpaX#p z1UeAtK%fJG4g@+7=s=(Yfer*Z5a>Xl1Az_%IuPhUpaX#p1UeAtK%fJG4g@+7=s=(Y zfer*Z5a>Xl1Az_%IuPhUpaX#p1UeAtK%fJG4g@+7=s=(Yfer*Z5a>Xl1Az_%IuPhU zpaX#p1UeAtK%fJG4g@+7=s=(Yfer*Z5a>Xl1Az_%IuPhUpaX#p1UeAtK%fJG4g@+7 z=s=(Yfer*Z5a_^vw+_ho@DjWC7A)Qw#rJdXFj%}l3M^xjN-XopvhFP`<=#W0c%^X- znkc+cihA5zSYfcvf!Azp zW!?Kygxycvf!$kJ7H^aS%NVWc ziGIn8d$&sAT~F}q-m|KU_dbE$J68tpfC9VsuMFM?1$OUZS-cwx?B2_=cuy4Ay`yFE z&M2^ZU(4eCQDFB5mv!&uB*8L|EGz4jZAls=ZIWimOLFbH_k1kg83k?boga($M}cLG zVu@uQSr%oyp9$7SPTK-Z!U*IL=tiIefer*Z5a>YK>Oj>hkCgV~;=i}Iit5U1n1;nx zs?{^SHH`Zv`rw*wv{u>lNR*B%(vUEIJ&1bPTForIZw!d0tWv&dgxNFGtI;MWL#jo{Y`ey!lw3VzX!Ms2Q~ z75rMkuXSxlA&+YZ={~>6@AHd#h-TLg>L-lf_&3VBAJ9V><iXqVF!Fy|-C^=PDX{e-z)!tPI?hcMGgnCbWP zxNP2DQ1UC~;4&o2N6JmgljUb!UjKWM{N;Cn{4V=mK3|F7m+K+gxPHRiu1_=QAmmrtsXKfSkAEyH|a zTp}Hidd}a?B9H7BvcI@LCH5oPzg&HwpUVDr{Q37-6nw`kGmoUzcbs+cpDKTg;iR7u z$1NG6SG6^yKd&8()jR6;Al!Opyk1;j7@d>cx^%q$e(bw+elqK(7`?df6zWI6)*q-} z`*k1T`K{XN`yRT6>VM}@T|M<%@14*dlZxr)Z{JSo-&H-WJ|EqauxwYR%lxt)S-)&o z(j)1V^h>^6yVmDdVkZ;h%g51Ud^#OH)~DamV|~6HJ=W*f(PMo%IC`uvA4iY%<>u(I zzC0a0)|azvSEkGSvL0E#Y**4F>6G+KzIOFoWu9p3t&1d)7l0M9OAl}Ze z8%z4o!;H5Z7QadQaNDRDJF$}Y7U8Lb1MToGdr2SezO}u*yRi4}>iTM7`{jrV^xZeN zEMb@Q_TJY%w&t8UU89Gu4~gF;bEYx2S+TCvZpOv&_LaxlQ@hLhjkh_ceNOGpxZ_@X z%ZzE%*1fa)+j6x&AiV#DHulc@y?604T~*6ocfJbMA3LO=o%xdYj^4QV<0iv<-g~mm zj?6W?4tsCIJ((k)nb0zh@@M+y+30gWduL+ROdXYBop)At%iw>hLn}SG&Dn8I4XW(X z|5TNdy2(oK9YBe{ocF7GC6A}`*Unv{uKmL6gHyVfR@)YM=WNepx_)!h3tn4yY^Z6b zAM)Cgx^Wp!?900*R8)hTd-Y(f_vav&Zv1ptR_0GkcbOCCtfck)yDlKV-T-@Zd?1HF z4uK8?IuPhUpaX#p{52hD-23~@`tx`TIiC8d_~sMtjaA0cK6ZJc{XCc9KP>yp@o01X z+_6-r#M5?^H9w8=_PJwb=QopU#!;RJ+GRBM)1)}L{Gbaofo9O_c#wEA(m79ZSmu|Q z^7mLi+P-yeCas4hK3jW~RpXwf^c*jbuwQ&XpYZx?hug!gUrK_L%MV_`Gw75U@_<~B z4mp8;V8{}3yc{Q&zh1vP?N@hQOR|;t_dAa-5Q~jvgiGNyLt3< zDRFZ79bMY*FOFXA_an!L_WPIPPm4a7h*MJ5>6;e%mWZ8BYF{VaZ|&=<%d3SxC*tJt zyRk(1J|7wwOkPLH%dmO5S2V!Tbn$>n$7N<)vK z+Y-C)sr~WCeP`{DOHLQGKVC_kTz)rqXv~qQUt%}cXv~*LXH0Vk=ShN-%kN~b{qfw% zUi;&`lfCxGea`lCmsM1v**Igjt@1`5Ps{DJjdeQCW$ZeoAM)2s6z|aB}&% z?`Y7^eTp#mHNxDFlHin-WgQ@TBxaqVbk+^RtYb-Va`}1eBHAS8@r}}X+#}3mS`wUG ze(vv-Ut%5;D4qL0VIEJC;NG zoRYG+Rs0ZT{`t9X7C1o-1p&z2G#Jpys zbj+FP&&Y$h6#e;foLqih+faUqG2Ww3q8?rs5yo7BK8$pUlgsaD!FrhTON_M%`XuVX zngx9r*zt<>b`qRieqK*fe$3(Mhp5N>#`=>m=702Cq)VKVvhKTKzd+-a#7+mX@1S(2 zo7ig*#{3UmL|ZAzgS8&U1>|=+h0Jl$3Sf3VR1CD>2q<7%xz# z`_9;R5O!lY_9IDfa`{o-`}u48Xup==tlpPIAkRRr0v!l+Akcw82Lc@kbRf`yKnDUH z2y`IOfj|cW9SC$F(1Ab)0v!l+Akcw82Lc@kbRf`yKnDUH2y`IOfj|cW9SC$F(1Ab) z0v!l+Akcw82Lc@kbl|^F2Y${}L*qYu8~pyRVO3q>zJxGvy~5>mnZ+>*c=-0BF5f!B zb(ZJQJ6`#kFn;6T$b-Lo`D#!(lt()1L%qORR@@fl<)!q9pYGZ*etuVv@#}H*8^3<{ z+xqRgzgwRkSI+u$y85h7ziY=%RZrZA_BcHP%=ry4*F%`=C(P}-Hi$3KLzw9#?AihS zg!h-ov&7}~)4{KwU!gs&2l64zaw81>&>qvH!9OtMf%br1eUKy3kAFKkF2e82aqt~$ z=)ci-wA;7Nrtg^A`gz-&*wRi{NZ+_W5=OsC4gGAB``N|NP1f5~8&9ggbDsJ)+T#95 zeS-Tb;VU_wWLdFeA=-j0gKtND?LVFi{*S&L^xpC~X}RA)KP}G-3Rui9R?It?fBgB# z)sr|+VgB*wFU&vwyk^}vov1I|??`vJ-x0<<=Gr67^8#U>7kqkL8qL3;ljc{@Df*Xn z|JFR;`RSN1{QQ_lz!&NvEan}WSHUOpFg=9D_(1b2N?Q=Z72!qaB{_ ze7R9N%hRXFrFrzQ{3)Hk3(=2uc)p|Z>Gj*Wu?1_RRR4ArB0DfGM;M-k+z0d#Qe5bkJrTW<7)|pt((ioCPV+*ZoQ+poY)O4!8G}fSfe;UT3TlU$@tozXzYAf=&x?`oYP<|11wX-e z^xipO{qf}wy&}x|Mws=GaN2#x|GqO;Pjm49fHqGSfgJw6a`>$t^SnUgC(jpzc|4%L z&+`l6KRa%C?@*-O`0wU5|6P_;eW%2GH^f^Xq{V#gsYe}q4xL)@wz@97uIRtX}D>?w_{d@h-{m!4)uK2r0Zrn(GJ3+3K z<@(tXl(?>z^QN3nlH;D^ zD{(w@<8iP*b%J8KX?zKmCt;Q!VIKcU_oNtzpwo6QXizANc~A> zUL&3%59q1)JHUY)0v)(AIzV!?eqHHpoWE{=wlsNvG40N;yzk}aOWK!RHs+`5o;0oJ z==A;Vg1O8aa{@U8a!3sw2!)0&n&`$zZ_jt7aoZU=^j!@)*d?!YS(KyjPBnkQAZsQL zTXgZMyVX@yV(q~W;};d(c3(Kl)OfqP|HMV7vwR%cc<*?-`RM(NmXCYHT+Di}EnIx; zqO~7>Xxhj2vqi&$7Uej&-*m}6(7yZekVR#VzNS5-*A8U_<;um#)V!o-lWrY28dyLu%0`goUdrN=hTU}C?C)5~YyU%J(`yEh;ECSI4FJF)b( z9y7x=dc^Cy?wnYCOA+stwL&}S1$=N>#!6`m2JZ+mH6>8wv1_14ovbkj*AO24)I zgxdE&Z+)rG0Gj)*^fyI6lyzSJ!#2}>(qLPv;DeD|r?wD2kR^*LQG7k&>wjoqa;#iN zxbbIWP5y#U62@=*8)fl#A&HHWJC&^Ri$B1d!cMH)b>yi1lH`rzl47-Z>lJ(27o$py= zIt?tQK!0*&!(|>d``1jSJjs+&nVt=}oDe41suvaF*)`Mh7&Zem%-i}GcdTv;a*<$nuD^Z#1b$yWK_QMN0~x^JX> z9gywHvhG`leVs|JY;yT!{jwg}XSt6Xd`Is4grV;kJ6O;E7GqSG(IprAV^ms<8;9~e zmnP$e95dy&O9_@`Q-bB#BF7M!F2@a-M~)TA<(Feca%JUMA={E=~kz83hRwP$ejuo<9Syqk}f5$P(xApvW-G_;GpMQi0 zmMU()s=7*{Yzna!`4jO2tFF8xLpmcQjqZMV>4BbVmA^# zy{(cu{!AspGe!*#-+Fg-A4h!b@)$plD{K6+u1@3E>Dn@WTaE_n(~ul5|AllW%FxmL zhZr`f;+y^vCYf^n6k#DZokHx>jQojM$XN@0&_W-y&<8E_K?{8V_VodIe0@M!UmsAX zuMcR;*9R^1Az5Dj3+YUhp_FHGSm*=3udffuVT*o_IS{{7ihX~d;j60I>UCF=AJBKN zR{rJv3{!p%-f~4H z+oMJu>dO*0DRqrK{X{!TU%K}#^TqRb6ONue!o-B<@EeTiHev9r=-+Qy~=RIxo37v=1OV1ggpZ)j% z*`(YZ7o*3Wm`HeY&UpPrvsGd6&o~0ic?>X@CCqhNq;p$@nFhj48)2rIF!Mr~c_hrd z6K0tZW?2zt879GjJjatv{;WLl{rtO^l;i)TOfa^jT)u&SPyH;1;nJs%sX^nizdZdb$9{bekryRybFn{)XW>czMEP$Q7qs#1?l_1gXX?zO7t6GN%&!2%id^<%pd9#`;2{p6lo33rQX zq_elWfpF_Py6d06xInTh`Tj87b!ty=06nTbOU*Ee!^T2VXogI z54TI0=^@N?5@z}dGhc+6UoVd*2f{2L!YsoinB`3AEPulMT?p?lc}zX~xwjtp6Iho0 zT@3#J{Coj>Y|lSsWbyHK{N7(l*FTePbHKZPB?+UM8FLHlxmF8Y2hz|EU4a5m+kkZkMs$|A4#lk#;b@=M!tX>;yueYN{D z{)26^hRr%Ke&gT3?kCZvUD~=!8+gZ46!<}Awjn3Xw#R-wusJ9ES8b~QKlywG-!95R zucW=Y`{y6}FZ|#5>;1WY>Gv7%7hq2cfgA!kB&P%Y`)^3JAC$gISKh~k`lIdNzxE;^ z>C+>9eWVYN^bL~pn=76;@5%X4&XZ{4f8$x^k!4-x#5!eLk_Jheq*?Of+Ps`cT9-+` zAFhYSV6Oi^8jo*WJPZDFRMznYe`3OpFNO9<1j2vU@r5-ArMur)n-JzT1YuV$*?1@3 z_@DY~AEzUUet{A*j~aY2kA&SnHS_SBbr$nTdHC;ynMZ|s9 zGL*7qdMxUf-$H()H+SuK{UGt%rJ`>csF+~K$E_lJQmLz~lOzYn7w9GVKu5q2N?5-8$Ue1p&C$efmlofv_qM7oHcsMqOttUj`Hp(uOXA==Chk8H_c#AZze}s{ z==VA3On^Np1ab)E@b}SyQ0R^MJ@oFI&(ge=LTp8Ti4*H7bXODobDI)0&%L{&ye|As zm~ioDa_Befb|C!4sNE{=8}F|1i&^)nLmj-k#)PU%!gWh~XRi)NeC+ZVKaVSG{Iaf2 z>(}YpvVL2R2J6!x`T8%UP0H{OF?8$nm|}D;moglT&Hjk=_vx43+Q_5(O5+Jy=ub+p zJNNctJ@I{~sxUZA@J?sC8U{50dU*+&;?+4R= zesA3Lv?9QP90DB(bl~4Q02^>=`z^7v|Mz{%wD2#`!oNTZ{{k)i3$*Yr(89mKy@&Ac zI`{2*F#KAL>J~KAub53`d$S7RW09t+)sBjUKdp zgbSY$@b3GhKqkIV3S{N`q(FwgPYPt~`=tEF{@n3meO?@o*5}djZhYRIOpGrRCoAL2 zO8Aw4ci-OxG9f<{^Z{vab8nZfwnvK$7U>s?HLw{rmL@z&McEI!H6&d9#gL6@@9j-w z*(Y;#wb|eC%HH1jR@?FU8!7*bpO&(_$2TH;uEGVAZBlo_Z{=NKZv5W6D|&iGCDXpT zcZc-mt~(R&CnP?#b7iD-F3+|vcJPtN>koLgv*DNnk!*84{L#KgA}{sw^2o9hm+d;! z%zSM$(QxbRdS>Q5V+pSqu{Co31Fs&Lr*XavwsKro%9Eu>dAqryBD^l=t#sk)a~}x)5Qq?QoDi8{j?{;^6hT1jaOHr^tvyVunC2l5O!@TpB{-N&5pLP zPn)Az`83NsPCj8FpRkZmSjZ>*NAhvsLiyjqeIw<6Blqo;|Lxp2)&4hi-&*_M+UbDy zbwJudN$m7T`}*VbO8a`{^iBKv=JZhedZ>mt?iBQv*F`q$kfGcHFKXnC8j( zM3yGH*!B{XXG0dPGYu(6_??WE^sDdHAv~;NZoQ~xTf#A)9aCSg>ql7b#{(P+Wa6E> z1ai2-a;RB%dZco{OJ>2%-E?x;-D%>k7-tLiUuP?tTDP57>&A4pH;-6u9_u-!K>~;s;kznnQuN{FvjK{zBinGa&`02;dtA;)%56{S%2QVd0w2&e8;rN&?Y~H^Jf}m z=e%3kthw$1m9KSgyM62+)A)zoDno|mcG}`+%%JZx>)zXMwmGleWEzG_>0`rl+J9t! z->9y&^#|9zWiswMVPe`g({C>uVbr=a=H}iVe#7s~wtK>FuDfVHn%z|&z4bvge*0;2 zer-Elt>s}={jIM|Nz+6xxjwJXRcD{sllvC^YUgUY#qw87jjF|Ucydd9`0Lr`&iz;E zZ@2f=Ikw$p&Q98<9vm}TKhQXj`S|&5}5_ak-vd-ZLJ&CAr;DL<*UYGA%Ll7hbE2=w`a(;<@JJ?ksxR zcWrd$ytB+t4HMM;gc z15Lq&Z>rGeef0hoeNE%pZ>UxU`|7xHeN4hfudCaR_R&iQ_cdo$zM*nHJWMx@u4Kx* z_LTZ8bF3~t?7PTQFSJl6oy;GaFe1_>6_{|i`RQD6$sCrKPj^7_&B})p?Tph&9j?^ zNAJ^JZu~L4?`%txqx(qx;^E>dX4XTd;E#iJ&sB}p!8|XSU#IlaOQ+nUPCoj!IZ>m7 zRtp|hFP8k#jHuC6e|Yg()#`Ls+k01Cee;DCYWIr#wsGMKy3^!{>Qgext{j?AuXt>) zD*a-0%ko$5d;JFA(0F>JV82Uh#?9UAfG78ct1rK()=cke8y$W~<(Ph26`0)4{`&P6 zRj<@{s!X>QR_1^B(dOpd`{&f2x}9vsn8jvvfs?Au($=+b`f z4i7z&$t)W-%ElBgsLDkqnJ23Ev+7(A)$`0&vv+G7JGJ#J^~34}Q*>+{+qm~ib^Nme zK5azL`KvP8Mn4`g-`}Tn;cIrAAFukxY@gChH#joQyx8Eh>D8#6UQ)2KSzhV9Y1OZ@ z#=6@5(D>$^VV_rX+I6P*=BsD^sIG3;3iFQp`!RPeTaRpE;)-ln@dwJ1EzG7z7OG$F z&&6k^6O_wmytCU%s>zb4=#2Hfy)TEWTrA}78Yu2~RI5iuE%eTMUyitR*k?JLqDsc) zcjaM2F~Oic@2q#BarKk!xNFzAc0n`farM=MEs`t$qj7ZNOk8y>dfqtt@gCKUE+5h5 z-BEby-dV4g-}}2)k9XGV)$g74dhL4aFOMGYtk7H(R&u(AE{D?(}`cs zPjcXTNIqOY$&K43c``jDXQq?n&-BxG;d>6pKlVFwZt`T|=BBZk)jNAHs9EoHu{B3e zR-ZNbRV^&j-cG)_O;woit=he}xgDA>q;o7irgogtcIAm8dTox~>f`q-*{0cR=;uP~ z)XFVI?SgBY>0dsbtA>WM+NYLv(_8XPP*3hVW{$)S)@!pjR0ZEyX0|qr(K(;Uq&|DG zuj#udP7nTUO8AX0zlvORW5_E@rq{0Y{LdRIy&tFFIygBJUEs^`oo!?Eze;2>Z4dQP zwPy|1H@wuqTswN1`XSOyXFV2gX3RdON<=l&Gk483BTi(|1B=wqW4~W(5>^$}+Y^fD z*%#h4lXh3qCMu+#n|I7S_np=^6yL7q#eQpw?{2OSKQUP?ZuqM?b3=PwZF^=l`0Wd3 z!k#X=cfzLHmo8m0?>n8!bTO0p;k^syhW%aigQX{%X?Ol=KCIkcZ+&5#dE)VJ&74n~ z>yBG5nQvY{W|rixr$1O%#MZ60+nhaHN#{9K-R`ck&NTj}sP6eyQ@g0(v*w4Jv+C6k zce7=0n_vo7`cMrUIM@~*+|aZv@=w*Wc8u+CJd>GMqn~~g1kB@Djnm1c!B5!uH&#j7A z1%@6otEx7$GhdmjE*#EcZP^;OtfZ|P`%%99=aJ+x_B zC;QA#SqSg=s3dL6nV#wl zg(^)eZku27_TW3}RkrUet4%VWIj)}V@WxGqBSl);g0cAtpLw~jEqU#yZX67S=07po zzA*by!ueZ_x4%sPhJ2%{J`-c~f#J)HUAL~|kD%Tu7j0rTkA0hE8j!fWliT3($C#<Q^hfJyWbBrI&x@6LbB}zJ!l0UT2ne97_1}Umr4Cr`}7reaRYT;c4&O=4huEB71M~ zXvo>@&FDE-hEaT z9!34`;kkF)XFh+6aEUGL>?a@R)TqDC(mJ+&wMt2FTGD{_K?mpoU7!yb^nz|+@Bw~+ z!5{bp2H)Tx81jHzfFUQy3mEc)9D&oWt<=!H^i*dkg#LlPf$xHTgZ=}I{)B!7jDChb zb2&~)S(4fiX^FyavYjjd2_p<2uH7V2t+|_kl4FU_JoG{D64^ z81n|k^viKt(t!CB^C)P*yo&i181pUWU0}?^n2&)mKVzN-#=MRB8yNFB=5=7q^O)~} zG5=#70GxJhr6-+F4PHVatdX%k#&^N`7wcePtc$Te2F6+&>*mXGO3Dr&{Z?kG$JK0SJFdKjaQ0ev+l>EwoBC1R-uKzZj>HhI*D~JjY564e zsXjZ$+iGKWP@j5g-@SJB(W%srS}f~tKl$u%5}cMa)V!mo?zinU(Ofxu6WwTQ3F52R z_ht2>7){v8R{OGje6v+0dkmrUH=1@-J!_94yuDia@Wwa1KK1C28O{1*-g>On-A|c$ z)4f<8Y1dY2=w5oNGZeaR?Pe2q&ijsCrfxOouJW)OGmSrH4llmjRJrJ_NhD55*)cWe znc?@1B;BaK<9oAuR4>BYDiyV}4>Tp*dq}jM(ySukf0plHqt@ggd~E(8yR_I&(#aBa zV(rfJ0}1~yE#6M}=Sb>Pg$9ndnU8%&eX8&WqiyGnGpHX)oR&0nJTy#aoxXzT9Q|l_ zZ7-ZB-0;mt`j-bv5npbu*Zy2zeP2esVPqFdFI0Gg(kt&F{Ain|D$g%opBj6|=h4%? z^!il6e0j~LySzS?c5S66olgy3LZPU`J$ij6#9yJ$F1RwzlN`0WxQE`-rFxr zoRYF#Dwi~+4}10!ub*FNZt6IK>MxMzl=;W&Jqb^_RNS^%(1h?W`;7~3^(SHdSY#oH#!>QJA$=|Y^XUpS2 z4%Ic(TEYusUL@k5K|TA1jpX>) zTdPa_$7LsI)aCsIIFLi21Az_%IuPi<-$e&PA?(qyf5tcKFEGw3a9)6P?6a}o2FCsy z`*2|F%dtNP#(o|9c3|w|v7ZO#yG5!W`+n^Ik&g2KoC^TstO92iz&OLeSq3o9HgLuP zEaz^Vh2TsC={O_7SqU)CPH=_-j58IStpMY!1!pe6vaM{}9#q>`du??;{&x7KRbE?p zN==JAHNaaZlzV2FX?(zIt4yyq&6_t4qI&jqxZ0N6+Me+KI>qe4EZ)6a%rAB97oXg$ z(bhAU?zG(|c;}hBKk9F%B^)A|9L;mDJz4V+!kY?>w-04LOETPjD&Dqu?9t6AJ7ip( zeWpxq1AJsqjJp8cYtx;gL5BXoCD!J2srK9 zN)6phPj$Na!ktgxYy#hf?@|fN^EaGx;LHMfBu+_LoMGS`0cElO#y%Vv`*Q5hfw5o5 zz8#qM@oqm4jQu_K`CdBRoe{=)0L}%Fj&lN>7XaVo&JVD+zZ|C}4LC=^8475?`3lZi zfN}1E^A})w?uv67oYx>7=QlXV0miuw&Ub)u-h*==V4MTtJP0`L+DcD4pBlWl`zd!m zfwKvG7rsj+EboJG&Ve%v!3Gv8Kx(lPYqrY*J-4;yp|)(Ydpfd zeoKORjrY4{c@3|j!xHnJh05}ppD^zQC_nEJ2=m^7Fz+b{^In56??DLj-h?pkn=EMH z{S;x|XAzdRi@YzRbl$HSl;wRKVcy?S-{E~9(Vv!WrJW2@L-*2Cor&iLqyv1mKv>#) z^LYZLOU!2uzgw2i@hA_UgK6j_pN|pdb2Gwxo<^9@*$DIb8(}_|Bh2S@g!ybO2~JBI z_&n2sM?PaD%x8~;rN0B8RT|{yGfcvKwi!V>pLvoD`7D%h+O?IQbUrnB35D3Vg>;X7 zSP0AWXZCrabcs_^mVGFwEc+l3X5R$D?6W|aeHjR|j{{-$eIU#}5ro-Sf-w6~B*AG( z1N)L#=s)|I5N6*K!tz{{eO0LMun!CM9rkUZH8cCXP~Tx+7{Y1SR%+;8daBc%Eqgu} zq=Qv{*{6Uo`x+2t9|Xeen?RU-76`L117Y@YAk4lGgxOCa z2~JBI*f+$YAFM!iWLYRG9h{v>RD?RCaYVeZi zb3xyQeK830zMC-nUnIfoukpKO*(ZYXuulPD_B9~PJ_v-_H-RwwED&a22Ey#)K$v|W z2(zC;5}cMauy2S(KVqK|>O1U9LRg-QvhNA?9rj6~{=&X0gxQCM_+sA{!fDr5YUo~i zsx#5&g1!s;Vi1<+%%zg@_dlIK54eT32{e^u-2(vE<%{%g3lzmT#X7))T%)Tnb7yGafX5SXVY1dYI z()rZjB@|*m3;HhXi$PePC$s+rrAz$BWhYP>jLq&2C%}Om0v!l+Akcw82Lc@kbRf`y zKnDUH_+1@vHpZD_?TcfF(B5iOhe5W;_+5m@9%^roR=b+yH=#td&GkY>!kK?AVw-1b zMtH!a@6C({dJ$&dWWwy*OPGCr39~OSVfGOw%)Y~f*{7H=`x+BwA7rA9{e_d@w4{Ok zvJJ$`zT32iWuI<3|B?0y>;q0Tvu`-@#XjSN*_WI!`Y@fQGiN&d zg2RY=xqI?h`(58E25~YYZ;i3VKCf&LC$rq15%x!2-XKoq`KbeK@mHdLlfPbuF6NiU z_u9#8Dw_OHtTW9v46+$-z0t&MK5O#l?`o&iDPkHlyl5)!?`*fXFKiM@WVDT^cC^LU z7c@6a&StkZYG>;X&Tp!=%wu1j+0y3do7XfRQoyci+|0JpJ-|KYr9~cx-M2aWy*^ z&29I6v@3$Rnq@Xruy-%|Il^=jJ*CDJvXfnW@2gwqQV(2ry}kXH=DPWeYt`(z*V^dp zt@M_SdDY=ud2NAfTI%E3@~Zcn=drD4wbbSN@sum=OH@&y)tS@{pn_U%m_UrV|n%cmM&&#^u4x!D9QL%d7`bw(zz|SJl zkBrf6UahQHAGFhlWHDkL^BYE{my30rXT*K>>bjN8=fjtqm>EOtx6{j*pH7@Jb6@LX z7hWoCqFk)w(~mWvYjg(}>-fvjb5zx9JA~t1 ztm8Ys{7OAMb3u5ni*?+hc|kqt!298HuitFnu31Z0`u-~Q?ueZB`kifb>_79V>+`>5 z`q%8Q%jLU4?f=&Zv+TQ3I>A=>4Zo`Co^Z2+WAuz~Dy#T<531`kkJNYdFRzNVIIJq( z)<-{g)j!nse0lZN*<0#dS@NojovP`XUsThdY`YMCc~VO~YyNfmx%zv<54%{$54QhM z6?pgA@EtDJamMRrs)hS*507?ncQ^m^eK>yV(&!;B)^YJ6O(Tb1&$W4oi*+2Qx|q@P z3r8X@*75Rpjmh=o1CfVatm83FGuw5UH%BTB*SdGlGWNN`-$u&ZP*Uev-O!fUl*6>2 zc1FEEu&bRmx`^rPVjVyA!4Ny|wK67W6+mCYAjDOW&8r0qw>CwP?{Ib?YPd z==t?-Quk#nrH21-pT6($N@~u@TH%L27_0luucBoB!QqVh?C6gA#PWjb_`&SD_wcrQ z`1{wZhaSwO#}8_)pIv*MYTr1I-ZZK)3f&*yKcKg*pLeL?$u;gdx->&M&H z(ybQ2n|}J&f=AUO(R0HYS`5N?9y^|Vcv-F79 z?$CdX-n+K7y7TMn!bc9q>DOP#pz<|bA6?nR>&cs{hgbb{v2Hns3va6)>2v<#rjk#^ z=|kCbm=fz>+x%S3SpDgoex~cfQjsMaN9gU*FPLfBdPVBCyIXI_xZC8ZJTua#y^B5b zQt?f9a05r^9GMf4!vwd0HEgv@;U;fK+`c+)a>&d7x}k#4{*=O;OEJqGgO`blow zF3FSWAvrUhB!8x#>TTY9!D6(5G#4rFCLbd{_VQD)c2M)m2Jx|@rjE45wv{)CkKNimZ)x1#d!3g4G4}Nr_$y~8k1o5%gevr|8b8*9F#K(SVa*mC?`fgi~ z_}HcQXHYjxTOW=1*!zl2R9&al3?n{v$u(Ql{Nq!@h>!j4*#z~_`j^9qkG*_QA^qvy zhr)=D{npJ@^{I{tVZ_HS^7U={#KoKn@v&Fd>#RrqP)H#@_BWpl&==}ODa6M|T=T4XR>~jL452?Q%2h7ww5=D zkKNtrNe!nbztyGGxJOG*b%sJMzBZA?pN^+BNr~8hMrIZDe6k+P{AA?&mLBF9IFv_X zj*~;_97~6=v=f$jCXTa_;~#r%4XA1(J3awUPx4G{UYvch8;=T{n^D(|s{#H$kVCe{ zlf&g>ynZ2Z>^J>Y_D->+|KFKys{JE_31=ytRqq+piEzfZZqiT2)FZt1yGHuWE~N-} zd##&(Y0o9B0YY;Z57j?pUrTsr%KIPKy#B*qM+z81v3=syvN{kd4Ur6G#i<6TW6OZ&Hh&7~0PyTGYrj*2$l5wacPDxpL&K|^e^WH=G`^9!k z{TP608OM_2hEac!I4x=5F_Xrw^b<=n^<%E`I)wK1LG0qcYwY6Gk8z!rG2~?&dx_JM z1{qsEE#ugyc3Zs9rEyZm&ieOT;fe8=C=c(238$nipPx|v;EinWJui+EMKbxTZ)B&{ zd)$0(Ml{Q~h#W_V()m0s2~J7bw0uuFc+)xc-j7bnyTieo#VLO`IqlvNPRloogEx7v z^t-@m_fD>h(UgYo|FWF`%_;KjgW%2C93+!J`|d5<+tB_l{k%CFys3Jn-*rv9cTPj0 zv}}v*7^&~bcgNTUlG53}F$wPNg!ALVN%i105D zl(KkR8f7`gEMeXQTBK(__E{KjU;t0}=g0`&bq40QMF?|TR>Dzha#+0Uj674CRkV25 z8F==ArWWry1Fs&{%i>*U;IwNiz3Ts!;wy+p_vnuqNhdeH5pTCwD^Kqb^{hR{zR|QJ z^`nwKhSd|)PcHyYtNYx{-vk4-pf<*oya>Yy>+17@Q@k)=)II@)`BBu zvhGhf=CSMS;7Y9tr(IiDO5f6JJ;1m9Gi{q9j^EcOFP58^%ke~xRwOy#%nWB|(5oO` zDEd@-)&DESR}fD%h^HC~@jL7^Zt(l;g!$d}pdVpCrJv;bT`2U&F=G>b&q=m2_H0VZ zW@|h-Ts|gVgA9pdzv-{CcZ#L-@60yU{*l3ivy{%N_YCSpIOAJ4=_h0A5nlUUBmHKV zQiQv`)=j^(=MwGl=Pn+qf5^U;@b(g8^`fsD6R!ACyxukMDmovKICa}iPR>F4@9SY8 zpFlo=4g@+7=s=(Yfer*Z5a>Xl1Az_%IuPhUpaX#p1UeAtK%fJG4g@+7=)j-Q0Xi$^ z`~fCGBo~`E@s5M!G;y4b9RGMc;Q>``WXC5SZuYf_EdJEPDT%2oWAI8`BKDt=Sw+1& zk;gJW8Tr0typGv?*5uFM)lR8X#2jgT#*B&WYM-A_#LWHjw7KJGS9|9hMNDMODKk@b zvoBm-)I8g?yS=r*IaRFBs_<8L_pm$5omPvUUlGn&vzHy3^INrK+~V-7ZTi_?3m#RE zM9&RpXfeocfBp^CuE6wgi$%k1u}jOKDx4rx05$j53l;^V%>5M7v5Gq(&zleO(ma-vxl zRi7-n**@O3mX6JkLDh{kvEPm=s++Dk8fJNFCr>pvoY9^g-BF)dUQiuBnBDds-c}EP z|9bV%gSqVZL9O+(Yp+x78|Sf`X1CN$2If`0LwW7_{4Moox$`Pn&&&sxm|=DA(cfmd zNj3Sbtoh-&`*cF5N~(GD1&g~D9jD*hTje*{{o5SA?LOVGSS8i4*h*9Q>%scT0%dTA zW#_c(tgBosq&7VgWp|aVug~3*O~n;yXzewn^vF4%hYzmlX1f+Wuio4Ha(MO3VYbGo zmsHt?Bg3v8i~2sw^sDoYnqUh*)@o6cBG)bCbmP)DbAIFUN4Os2>WOgu*3}>3cCBmI zFg@1MW0+3s=yYX>eza%SuIUOMEz-cJLsXtv!j~St7WGt_~ z-_k`bjlNgcf2pE+VO>#GG%8llTVF}_9{5=}`jIiZ&8wBwS8o^7w@+%Ub;g{k)R;ng z@{Zf})va@>2d=wb-~LN;-F(KizsYm;y>;|xQ$c_E($C>mYuf0XRdVZ$7j}g+m*}TE zpE#=O?wuR%*m;!R+vQ1Bwou#fwrk>asTl>;T~!Z8pSu*V+a7LRCtrqqwYwLM(>?PQ zF!vWbuzA_AQTou^vrWr3cSfG5-cOf){HWRR*xbn8t!;GYqPgw9k9I|hj;*81Y^Y%G zUi5Q>X||4LBe5Gll|OzqXn0Xo+~3)5Z(rCXl*p(XPwi-nuP-ZPd=z9h~1( zZJ9^EIfqnI2ycun#wiGDGu)?3vp;+e@bknUyDs z*sP~+vstrUW142KVVBmcYNJLZL>64z%&wSR$lf&LP~@p)-E13u-i$l`a^y(dVB0A7 zR`Wu+2P0b>#@NA+PBfV-){6Aq6KB_ckkNc|al__|m*VY9lXGnB)py(aO7F+n()%;0 z8>X#~zO!wN-B)a)>N>4vxc02Uw&a>EYX0%5;U6O1?6+qV)I;lE4wr~(W|t2tq(8m; zPl>rbxcR-oTNCP3U0I{{D~IFsrU4mDwo|WeF4!eTAN%Hh^I5~1kt%Zs z>-m$mm>YIZjYQt;rf+^b!K{4x<;be4&73?6*>SB7MQqs`dRfV;He;iN$Q@aW>K-56 zX1AQlX)2Tt=`7*S_Smf*HHU2T@+ZVwv#bfl)SB*m>~__ECxWs!-Z9obUZVkh$HE_swk}pe5{%dk zE=B|8M{EWcqk-xyQ76{A7!B0cUwPYNOwD=5#jvCAUNB!?<6_$pM$8Ep^Nz5Kfu~&T z3BoQmo^r7#2)meh+QptA?0n6%^ED%km=iAc1mV$-cGoWU1ku^?&@i2K`idktEos=) zVUR5{eizX&_E39!wA$4~=Y$f`HrERk31|Mfh;5#!8Q}qwzBe--=;d&r^U&GkY8PXIaEoRAt&1^X zAoZvA-D}gydl|$VcuHQE{y+D%;Ju9Cy$t7jxYe!wDjcABYF({6?SzHbQom{NKux<~ zOjU>fKlhQ8@Sf=NPI6;kc)~K)9Q)2wy2R`+|GQ;__cGGOdl~eNgZU`AJ{7!|;l^Lm z5jP$iH!c&-d~l+<5bwRQ`0;D2BOhh<_DUS5i1Kj!BEs@=TyCO^su|{NFbcQe`DKY$3JKc{^@KPo4t~EH&k_T zCj0)+ohg0DR~yY8?Yz6Bi$(7+FTdvLo{MP_aq%puZ*n?e&QF-@AD) zzx;6P=p@WA1Tnp?;;WYD{ocY<-MJxQK!UdNkck)FN0(XxdwBSCxze2A$Tt%crPO* zZ*v55kk@;XlSAsim%(RBG@k9RQ_LRB(v)z_FLmq}pWICNnM-%tZWD47-u+R3J1yZ5 z%}q!1+-pzPe1!0(LgVd2na_s7&+b$4w#8$QlC9B@adGyUGPw=Xj|_^j7w?%wSXH>k zwqL)AaNXN_+3q8MApG3Wwzk6uxh(Q`7~05oJynWu!w+lNXUkP5yt!OSyL0Vrg!gs0 z+Lqhep0IoiBiptI)%Mk1{P6C_-wwaDYCPr1Q)*h|sR7=)uG}-jOydJy9P%=~-ZXFC zI4DUy&fY=6?g8{v8?z(aXQx*W)&f`)ApNl;F{W;BubzzmeA{HNbvLDVTzQQhSJR7s zj<~iXF4m^>trwbG9<1sZw)`17E3=i#b(~BkFL&V z-|n^7tct0wU+Z7i&ivk*9W`&%uijeIUbL%C>pg|_nGCnugiK4!e0Tp_L^rb?7tb{( zcW2SlzH4JM=bdGKYM7w*7wKfXEShSrKY2p!{IZ*^*)rak!pBtC{&(3r8%LNXHTJ3X zYkJ$x7Y3Sw3*S_s&->W@E&7_qv)@py3ih>e`spWgyYuB}`$<`IWaN3%?ZwU-{yt7z7Iv}{d$#}Q4eWGb>$`g9kLK!jt+bc- zn3Him4cp+jBHK;;fwCGl!Am&5Sc;rzbZ7^PUYw% zyK49x!G8LKPTzw^q6;>?emZP@9bc5+`@2^UY=a$NR6lHn9beQgWaQ{3dSH_bJ7mxa z+hh3dfPT#5_ddD%#uF_oFX43Jm-CYxxE_)Z*H3cec1fO056PM7B>6M_^j%yY{Lr@x zg+9K)$M6j)*zb~=adS5KKfcRsnsu{|&X7@;`0~7Q3 zT-)e11^=37R}?g*YEM@1ubKPxGm#g|WKr<1$&>%U2K!L0I`FT_Jn-r8&?A`){A*&0 z7gXgUlMMW8)VUt2=b5br{xwru&r(0EPB8GVY216II{sM!%k(J6%Wp9As~qq4;YXXR zbMK#1d+K(w8Dkc!(FIPbHcMOE@|{0ZV|sp}1}|!CPjt?v&n-KoPR_4uW!W40y&HLW z=|$D|;jVVhj)%;|8K+g<2in>8ku9cp`R~+$J}oSd1Imp9zriP~y0Lu1h)A1^`@$dg z8gJ*#=^MHF{Wrob62{vDakoU?%P}up_h0e0;`FyRuZyY@uHtOA`|l}L_vH)IH`RAG zr+Y3H2+y5ADYEPMIJ^I$dEqY2vzvxT@3UQQ{4u=mY)g})`$+rZ;o>T0)U37ydskh1^Mw^^ z_lo?sap4NK)8vTiQ!>h~9GcIrcx=u1=C!BPXU;aZ_^|IHPrcB> z^|4UM>ysh$y8yes7svr)bRdT-(Jy%Z_2(%!uXyv9oYx?0f4-CRpqw8)S`z0e%)kCT z<>tl2c?$FILO1`ycLwSHJe4?Kb3Oh%l{mk1yZ$@{di;4Rah)L75Ae73={r@9D1oRSAauyH-Bq(=D z(~S~DM1lm7oP&T!mStfPQ6z|XXu61?lIAp^0)ikfN>G8TBBFxnf=cFJ^*y!w zHm(CR|7B)>@6!7`-uLr1J*WHBsZQ11RsQ(9YQY=B%Uo}d%l3FJ&%roukMH)lPxa;c zP@ji+Me01koZ_eq4c`fRA@Gh`yr!7pJ3&XknWF{=au~i7v?kwp z_4M|=9^VOCmb0NMwEk6(?*v`>R5rE$U%frP6EtxD!@>369SrfEpm!Het6lY_BP;k$ z(8s$bhUyjkF35L+{#`Pg*JgJw#dm_Pd!vDucf_lT?*!%8o9s=WwO8?-pvOO&;|=}s za?N*w#{9g@JNZ^I&3A%ko!;ap#7H)!J#k6ZF)R zhrMUNZl?K8(4i0adJFT^*L)|a?oFG$$`a53ZL&Y@T37TK%dGD7Sb7;O3 zRPna)UZJY{6yFIdGO(f7qUdXi?*!fbLpJZlntc@C3Fi_)i7PIIhyd!$!-_iOLkjlIEp7rf&wYCjnK?VppqwUhjHZo5)7 zy?K9(LHeG1UJh;hr@zj<@{UdQvK{t$P~q$<=VxP)=fj*s)FWH{_3z!Y-c+ye^!M?X z9sf!-`ok~Fj11@!gE7_y{@9gA-~2&q{MKeUpN8~U#NE5pVj6C!U(I~-s&8|6JgL69 zdwm6xt*wWS|E_Jin1El>e2DH+QT#oQ!^g~V`8YlwGso-WxP8o*a7;kW@9+P)c9d2Q zE+!z|m%&&j_h`_L=)AV!bK5L0I&yjdRqIGxUG8y**#E2^fN&r&lV zf2y*cdrc6$`J0@&{}PFZ-gdpZDeFL_*R9n@1&59XZ%F7BtTEdkyN^yg6e@71Z^wRl z)(nsCIw4P~yx(}omiXg!{K|4|hreg|aoNQLbTI)ViV3KFJvyH*UCM3E#RQzSqbd6N zo`dR{hwpGP0mZ)rWFmeih%ezi-FSonIb55HeN4cn!^i0E#p`43 zko)nW`rz`p;4fPC)>WR{4<3@IjsCr#f3~M*Ijvu6dIP@Oyzk5F4n=PT5BYa)z4y^} z;G~6Ls;5<7@Q7FEDD$=Nx95!m)zs4RNl5Q;f8k(YyMGroYxj>r{nq)ud)$ z;)`HvACvUdKD-^2thp+j9&6}) zs>h$nX1a4==L$K-x12kLWlyE4ZY_;P#rYzcGM z+$KmbnD2Lw`U>!er{;MT+7AVHtX9gSGq_-hp$V4QnqY~!2@b3YXgUWBt}>~tru!k_ zhaPM|>E*z5k3_GVbs2c$^MiFw<;QBYb-<1bX>)92H3kB9Tu7T^TW+{^=hD$Fxp|H+ z1}6t62d4v02b>N#9dJ6}binC=(*dUgP6wP0I2~|0;B>(0fYSk|15O9hr2~P0ZEv?Z zwl?q#v%MQp82Ufs9YYvS4!%w}IXF2u9dJ6}binC=(*dUgP6wP0I2~|0;B>(0fYSk| z15O8=4#Zpsa86p}>==S@=c41I4|I>a>Y~uRGXDLDE-mMT8aMFy^x)~C=G}e1Vfuq1 z@-q(IwE6kE1Y4{E>p~Jb6mK5h`2A&r>M-vQV2WKHG7+f4*X@waNG4@xiWoNzWr+ptX>ZL+v-lRJXf3tsXxxuV@OM%yyO)#(Ts{wA@C}{rGwKDj@vE&Eq zL-v0X2y~j($W+|()bnrIZ$103 zXJ&u)7uz?>ov-#a?8l#ma1BZ`xjUtDOk`;HFB!mFs<k;|Mun$KYMQv?*V?lYB6)MeX|t# zVub0iayr_P&GD=Q#q-o0*OT9O#EdSQ<9aev>`={dJ(;(t>ovy^WxjcPR?RU)nF|+L zq4eVWz%%Y@s`4H6+tlCtYzYM7SC(r>{C&>Xj>>-C)%$&`?{{wFss3KcIzFo+!#(yF z$-fqRLK=?bx8gqmzZJgb|gL`!11hu z_;5ho#J2-jd_Le^#1{lud_;i7cLZ2`N`S@J1Xz4f`02jSkT{g(+7Y*d^R*+f`{BFT z@rK0ihjg*^rQt|^o3-(KUQ$lq|MS3a)_ac~@Z%q?Q~SM!eSJTWD=AjyLq|H``K?Y~ zYrY-X0-P|pf+_fReXt#OY4q$V>gfIcy7;A%`+|MO`hF(okLnld^0Yq}y7iszUX^8j zpHOY)TJPA|fp|{oAK?U+X_}W$%_= z;yizhkoeBf;Z@zo8usnQlAiiqvborC*(7eY=I7fS&pPlp&tp8-A^YC_!NUE0`HX*U zSm>9jzI^O{cv10<-riUIZ(Vk2F7sL?@f}J&;n+7EKZoZdJTGD9c?!>0nB!NL>mOL& z=j$JqpBiO&9OYc%hZ)S{Eq`xL=W&?F)W32hzl~>{(C#i)DcTzOn(}xq!r#kYgOIN& z!*dr-Ctp*B=QPaZYs&CkhnfA-@f?Vmd`%gi8->>&*S=Uz{1-{w-t@%$rEh@m!(~a_ zXT>b>purb8Znfs;OI&Gi2GjxX>|$s0m$($#TI^%cODt*Vv&}M2p&d!T2bTU2Ed3;Y zEBz-}`c<&>w_xdq!Q=}tL~BB@j8lfcD*4#+Xgvld-+PAEV_@>hXJ|bJCSQGq)?<=R zd)I3MV2SbV@pB~hH&|kVBX(*$%Zi^2FNL;{o_9>0vq5iVE(f+_ZOHr$={C!J@4Ua2 zIlN}wvsuY9l)}t0LxkfENc+3tWChORx(@%whNMd5X^Q# zvJZmUE=cx4Fxv&mJ_u&JAlU~!{w>=D$vy~{^&Q%dtou;^c$O7E8Ky_aE`{F)0&>;} zI$-;5m9t4mmvcvHIFjE=>}LE{VmfQqNs09gmKe}ri46^wn9*SS?3TosM!LkF28%r; z4ac(%59J2$b0Y4At_n9oPN zQ>!(&VC5Yi#nAzC{2Yp-1LpWS6h{Y4cF|zUc}R&LhjfW62bOqqX*iyB;21s>U&pXK zIff6#@&R)UAByDzw$D#;3?GW+gSNvld?=O=+78F?q4N{)Q_V4aD3%Y}4#)7JSU%wR zm6aYHyA*yK2&|~w$o$smI_Ms+4^n)0%RC3^a<(uHNAlYv*=id455JXjXka;?29|Sc zV2Z6Q7H z7zn&_b45e#1mA_%2h@JRvhD^`J2TW~(r_fdEi}4-q45B}m6&K?iIoPHb8BFUtp=8u zYhXGz!m-%E5~B?)vD?5BXDtoKvkn}KmBvNG?MULyq3uW1(@2$nO1U^yR{hUE<5d4DTs_K-); zyn*E`99YiCf#vKRSkBae<*Xf8&ftONY#vz7(LwiYj%OX@ydv7mGuuZRTEBsNZ5(H4 zU5B<)zeTd4^&Z+z-JTB^S_h)eIcwc(XnhDyN@#0n-H7*+GnQaEdkKzTS(idvNY6W_ zo&&^pk+Xte+ny}v1CegCoFP2#Z{_?RbgA>uF=lO}`rw_PjWbP0z7M@hJezDvADXZV zeRzRnlV!&n(6QILBpJQ467*_zy$8$(4HCh5s}D1E4!;DxYTY2S?UNArOox8viywA^ zt99sUo@jpv{B7Q@W?8~X@R4^rnk#x_MV&Y0?_ho`a5=ctZ|%*TAN-g&9SSMqjjV+9 zJ!6ZT+1qaiZ?E^O_i4T!U^$BjmiTL6IpYVGvwvVY69|^Gf?zpA2$r*jU^#P$I?MUM zG#t-5*x!-QXplV=-;U2{kew9Y%eMFO84a?lqRxCqgY2z%FNxm=mb0T^Ia3O@;~6Er zpKNNKtctS6e3opsscTVI&yM5FBa04#ud0)1YN_@ptH9WiCU3(j;QWV&m}iDA1l!MS zb1>Pwy!NYltZy?vA7c)^l7Kw6Z$q1%pF@_^|Ly}jW_j?RlZlgq(*dUgP6wP0I2~|0 z;B>(0fYSk|15O8=4mcffI^cA`>44LL|6@7;8?@BfF$58IkIDFQ;{SDe?#m*a90CE` zx1r79d?DJt6KxKc-`=yZIdkq`&>h2Sr98U(;qMu>=~a*JpMb?b09gD6fW@BxSo{ot z#s2_U{1Sl0Ujg=p#E(Imy(ICsfPEYnQiggfM<$72e9~g0E_+ZJ@*nWfBeoh(YYPpuN~TWMwOdU=i*{pu4_jZYDf0@Nt>fRhZ!z^{La}10`^(u zj4C&y&S}TCT-S~+)Q;@){5D5>FCbk0_}%*m1nj#r8C7mZ-5ZK+xvm{us2$n&%WRJJ zo?5v4@w5C?wWo3*!T|2r^JF@*j*=*l4 zio~x}xcu?+8%93Eiv$$y&xzc<>}hdh1!w$|HK}p&Gvm> zxg(D};!`vYhs!U%I-$?8_L*s)Gl+k=m z&hKux{L-hP9f{vg@WuD590^Aq!7@dc__4&oyeZ2OZG zpQ4)ch_6ww*dfz!Y|FKE#xZ}BbK6uPApSq0hc?^(V8y15JYpM9!{PFa-%jKgf1Y6R z^9dIJpJ4F|3KoB%VDTdg7XPAP**5{p{t-B%$`v1;XglKD6D&SIF*g=pplDO#BNXk( zwu_2SQO#dWe2s!-Un~vBwp`bC_&c22c5IoP8(Ta*amH=m>9QvaeHOo+VDaY(7C)b0 z@&5@Hzo2087Ye>`{Oi>749K5R<%$na)IofEq8*9PPq6p`MVk^Ip=eXKT~vIEqJ4?4 zQO#dc&S|9K*p_SSjAQ-|=eDVHV~dL~Q0Rain?uh0AYIN5rQvY-#cwC_i$71W`1u5j z|4*>^1qF-0Q1FH0U#Fh0L;j2^SA2M)4&vJrEIvQcj>H!zSbT({P1$x)@hOUSB)&$$ za&A!bm$W&y<+`@R@;pe;o+O-5k_2qsq;w`024N*R`FrZO4{LAYjJ_ zx7m(wD|hsupW)(+hsz(&Slf0C@r)`rqvEH>wp?3h9H(tlfq)$!+-BPrEqCP6j>5$m z50~G*J8yGly+?1qqs^K1eeJvaHfPqm_L=j&!ull9exJerdnxA$1nj%^HfPqm@R{?y zE@d5#g}cktu)UXgt3OF2)fEggCu+q>I=K)Bdm zne~o*{NC$Q*5OFrJ$3IDdLG-m)pYhXOf1OEdWSuJ?-j|nzLfKvd)GU*cb@}+aIu3k z>mBp>z1O9z!;!rExp%Q+dp9`{2p4NUv)%!Z-+M*!tuN&~sptPOZ;`tI;LLiLIdi_( zrL4n|ynE_>G3fUH-op(9y2tTeb3E^EXU_MEIJ4eCj^BGl@~toBJm=okjqTml zKtSfk&~2MD>mA|vz1O9z!;!pus=Wnw8De|4G!O`Pr!}+Q;f>#WMe?mLhINPe3hpVCqM7XHD)`Er-%Adk(F_>E6bjD|>lo1R!Ik^DA2F^?koZF*w- zMe^J9#6FAUx9N%X8Od+c6O%WR-=-&ab|k-*u}|}vA@M%|ma!5n<6s(&b$U+d#an#t)ccjtyy`wr+V*OwbqSwaEm<0>pVj9s?~DkYnCx?pU0Fl9_xW7# z#Pn6&&ZcFrQQJ_Fg?{>;ng>^Zd%)*7Cx&G7m@-@B)uS@`Z}NY6LA zpLw?LPCw6)zNY-b-QY&m2AbjHJ_K*hala{c+1p^-hxU(+N12}=nuzpo`X-t!-?ahT z{_0OZJI-XkdMEs|Rb7y5>U3!bW?x`6sy|kaz$0R@4J~t@OSDatU1>5m}N}avW zT$c16(u?owZ$8r7z;=AGT}#PFeIS5uT6}3cGip$7upP@U*OA7iY|+wwx>BZGvr1q) zZYHIfkn-c9P+mj7K^{9sEj`;%8Azux4V4YH<3Up$J*q3xsqP-V1K5sBp77i(@4C;1 zBR$72)4Z0&MuMNKJ<;3Saum4Tq)A@$eSUho$& zFQ4*^_s%5$`7L(L@NStp0?&-3o{_w7Byx*H{*ipgNc15Ry^2CVJ=V!^dLBu8+4sjl zvpTdE&w0K3{ia9Zx4?Ekwqw!=@1{o|z;`LwZGcy^+-R`OrPHweTk%tbJmQZCZ2Qw- z?peG(+Kc!LLY@k3dex(IW`6#b^%TW^0N;Dx+lpd8fCFm+nqohIt4u1ZDfR=H{J~Os zIq=*KoixRM0B?MLu%_4#C@Y@+F1V~)iv%Fs+>Z~{2ba%99lmJUTUU8*KX^!L<#VZ z81fg&R}CjX{x&Ul$$+oew4MOTzofJV!qG-jd(3FE=NL zOf82%AnWo(uTf2Z9DL}jG2VnSKL32hSZ`4tpY5^FW;>7l+lo~eh31v<`{z6*-w2g0 z)&$j7|2K*ydoed3o(uh`TiN z^D*YoD+%bs^B*2!o*B9job-OOsdcg{`tUKIC7W&PTJ-HbJB~AtEIJ6js!pP*rP?EZ zfw3b^-iA}awjUmw3-_ma``-O{<}Xu|&G^@b;W>7E#=Wl$FpG+B#B*M&bhjzHG#A=m z&q4Lf!*^5xzhAYOnYE)SSoW2`_WZNZHTgX{w<0q112f&72={ zpl%%sDdUaw*A#ok7B{oE-;VU{^?vm}&DR6mdFU9kwo!eLoAb`k#+jxg-^aH|JezDv zADXa=(-R6Ln=Cutz;}7AOOnw$E8%@-*L%Qx&>#_gbf%)jW{+&Rkdw{gml)~de;6$G>NFfKfBgI)rJfH#-7>1&jPj!u+j3oha)Evo zI_LVC@coQ!$F}*4y_Xw`{{;C-ya2H5yQSf9`Qzt@D)qc2>XuREW|SYZ*p}=18Q0H* z>q8<*4+QM}KAR=(58A9916R%`Al>G0`QzsYEcN~Z>XuREW|SYf*p}=18Q0H5(w~IO z6A0M*{x(b8J+xVg#|M^kN@+M;{`mP}OT7<>x@Aw&l8h#`QDd`jAM{0|EPd zl+6-X7j4##p)BY9kZyCh{PFXHmwLY*_RNebH>3P0#F{b6*FVbxem)|}M^!D%`hW4NETiTB@v@eDJiuS1t?N@ttZmj1AtDVXnf@LhA8n1|1nKwoiu!42lM!(v<>~qv*Uv=KpM=XpHjSiY zLw5#n9>eBn@9%`mFTO?%f2a8P7xgtFqsq-FKd!MY*Yz{5p9$B8M3No|*!Kr*&Q>(p z@Oea*uk;~c>5I~Excu?+gL5#dO5@Q9GK~TgW-D)%yhrO<9iOw-7Vj_HpjMH*Uzx*&vRZ8-$wE{_GM+s zArP?dLE9{AC69k1Ya+0$tj4C&y{20f&T>C!0&0@QQK8TGDEVjNh z{P+1U>3+;=kCDs`Tprh-|G%aKsd2sxf19nVrm4BtjRfDd;+J4ja2z;y@0&u!*CvBk z_HOAV&PxPmZTy~>lyflH_UAl$_7rvWe*ZZymE0HXGuD63{89ZvU7q%zbL%_Zy(-H_ zDtS>w3RXq&vZ*x7=Wo-%{WlAYJ#TCFSn-@3j|GXVMCtEGk`B-(Z+=&Kfl+WaN)?wVUjm+@(%iw*_4ryxEy;Y3( zlJ5T@3)Zjm$U*!6jy#Sb47(2u1Z;mzHp^Kl$XL!qf#qyf8V;8~etwBl&u5};8C7mZ z`L&L1xvrn_`;oA6(5|03UmqI?*na11mb2ezvvS58EN8{jaJc;O^9!AN-vo8bsB$yP zuXt?B4copT>kG8OOCgVT{ml9M8QVXk&2pCwIwE)0z;gF34TsAgKfm0m_h(VJj4C&y z{JO`sT-VQBpfA;~pE-X&WBZAG+8AKP+W zKjZot+ujl_2LiS~aGT}aHTo0rVF(tVPH8w?{`mQ&KR3QWMwOdUaSdWyuIp!9KND@= zV&^|MCPE}J4#dwJ`Wc)5KAytG($7G^_S+oJH*6$+Wt|`97Mk14#qz@(&QG%KSK0Q- zT=|(vUg<{<#UM}rg$sH`)vE53+LzA`C*R8PdLt#q{k2Q#0dPKN8(4l z%72m#pP6Revw6w7M8oH{IlXz?`^=z&E5UM47X3`ls<)Wmj$aS%x}mfw(6=#obMup4 z&s<%>dsn>feOhSW4r4CfCw#wC3xteW2{97tlTjgr2 zTxFH3ta4RKx$!J((?_l6r@UjV<;iFH`Rpvqhx+^=pQ&Z0GqyoKJIhStLXgkkGDn-A z=7**`oekyR+Dzw04WA$7bUIIJ_*^Noy+=vsPYs_#<#aliYH&W4kj|@md~TJK=^U%a z=UJKQeCujHZ^}&my%moQ%zRgg?<_I%T_wJ=#LRb<_|6hD-&Nu}OU!&%iSH~i)0r;K zYkOwCtHgJfnE9>}-&tZNU#6PR_5PLPS%+B5lh!PX&pz@y(i%kZnMh_@vnW3M$V_V% z#b+p)qs>qD3d8q2`L{Nck5fZFPLWQ&PYwA##q;ewCi0bP$X6=T$%m>(K2*WvTh$}q zs$lZDx|)2hg2@-F;`4%B7L84c=NZg=cb4zaGV|S8zC+8*cW3zyEi>Pp&A>Lu+M4|iFb_RbTMs{2 z6`YjNR<~b#6*y76t_CWTAsA0quK8Uzax#$n&$`1^u09u-C(9Y9nHQrn4`^4`?-dF z?(lDIKK@i?GxwSx(l>vT)AV0*H`uoE)~(gY3l8=Bw+#usLN#Xlx^Z;cpVScApYdwBmUhs^y{dB>~JD?AzlSk?7 zyC#7DlRa5~weD@`293R%$6)^LR&SKfb8I~HA)!Klo!tLZF!@N-f9%SmIgicptV68j zNoNc+pH<>_5PHqGf$izZGJjmWY`BB|JLTOzq-H;`gUZxYHgto=Ud>}L|CZ{gsjgtEyQX*0 zoKEkj`5e_>Ii7WhwLIzjYd&kj??`%~d49mm_m=pq2{Y-D<})kI(dMUiX4oew|JG(| ziypN}q*EL9sI7vvgKv7=+roKT_9|5L5L-Y9zE{pmS&GCnr zsgKd@CzP4`9!-4^nEE75eG_zp`YKI*7IcI9Fim|K^nu1+&0{eCmijzReV=BgzED#e z22+2j`5X+V+Z@k2#9E#-o@hQR!0*WZae02gOyf`LI+4aD&1VicJ=**sCgVl7XapK9Lg<#&{}1Gd+LG|$z%XUut`%}?t9k7H5rZ*Asy6dad= z(>Wdm$E9Gl*IXQrg5y$fI>)2nxD?DBkAmY;FmpT#j!VHzYZ}e_qs+9{(QJ=n=6Dnw zmx7t&QE*%eW{yX}aVeNN9tFpxVCHxf9G8Mw`dBc>qu{s{oX+tmI4%V+Z)L;scI zS%+B5lh(VM_v-i^Wh@5U>p@yKYu@wYJkjPSyMo8DQuwzvlkFi$HVCAXO+t}v0&K6j z$cCZGmVtD#ZD_J_fXU{e$@T#zTZkr`2Q63zQtTo&0*G{;C|CYy@3?hb3~?y$D* z4r}Y~u(s|F^PEldb2v7db$3`kw;slKo8c{tCaN%1d)ne8I0T~f~Edod9O4a&pO0f zo}vR7qeVBs_Igls1L@J`m-b~?{v4l>?S{>Z+hLhG zULxCJnWe8-%`EK~-#w$sl|Bu1kiHHqeW2!gO5X^UJ`*f`DOmbgu=EvR>66oNtjm=# z1@9tb4cJ}}%2j<#D=8|=X$G?^J2w2uB7zbtjg1X7N1}tk0u&je1TUj50W!(gp z^%PjvSzuXzfn{9=mh}Z#)^TY#o^^<|JY~&`ca*g-*j^9HS{Uik<`;W{;csoT*dLHC zb_uY(<`O#wbVKYL&<(MBU>p>C2=qbhBw(>!pw41f0gJr_EOr>M*k{0Ew*iYi2P}3T zu-GfWVi!uo@vK9vo5How>^4eN=`V$Vdn*g2sO_L@uVqR)3UZGPGBFsvsw%l-&-L-tL;_L@ufS)d!T{{nrGeHpOq*Pw2) zj{}yy6|n64fMq`jEc--Y**^lyz7kmWo4~RU1(y93u1udz~d`KOl2C6N0kjtO!`nkbvcE30Tg1fHSIGIRk?_$k`aM zoS6a3SsJjMu>s538?c=yyr1m&iH}ltQuq`X9Cl(oaICQSd=Sg8u5HN>j<{jgL2jp>CxtwGqKPOo3Cg* zF;r=k@8^8*w{a}!25?O zXC^O8de19$*56b3NN@9s@AJ<>@Ln|8M^G*mZFVi~43>KeU_RGCYh!TPqNPo)BmOz? za?L84kn;Dc_>2ty$Mxql{x@dM%fCT7JtO6eMDeBV441*_QYM(|lCnR}b>zBo9ba_5l$^}b(z*0}J z)E_MG1(x^K{7jJpm}Sgs22K~b`RTqq!6Ij{$R8}<1uWkSe6jAEh+g5DqHkc9G4CI6 zo!jL6JalyWIPlp9JwiXv@%vBeZ&p!XgLIoC`K{Z>)&nq|)Yht*eWtFP8p zU!8iUkC7t*IE4Mf#9>mWk@9t-e}YeRb+N7J650_0`(yt5eS~ zkbY_!3q$-a)F*2m|CmY7Y5)2v>|aZIN?*vzWg8SGs^)?GG_UJNyaQUKi!unnDm_G3?><~{K1@;f5Xp|?*-;(a~YgY zfBb#Hr04wI!6akW2e9Y~nBR%tjekfoX1xN7zJXabR$m>o`s$$7SJ$=r>Qs*8w~^E# zl6Q$jCXvWCl5Z5rw~j<-Sgse+y(o0p44J#rvpw0oDMi0 za5~_0!0CX~0jC2_2b>N#9dJ6}binDrMbQDB@)VM%V+g~^!Pf~V2PX%o15O8=4mcff zI^cA`>44J#rvpw0oDMi0a5~_0!0CX~0jC2_2QHQlq{ak+9Xb~GXQREB9c}(-{R2ds zKUzN((dLiVuTHf2qxJ6;ZT@Kej76J2T7P%Z=8x9zVzl|A_5T@d{%HNsMw>rcf5_41 zkJc}DwE3frOA>AVXyfBVn?Kq(P0{8Tp9Z)?XLGFMRoStzs9YESizYSciKk}AN zlYM{O#n19%2Bjw+nH|&0=2*vLvV8@(_*TBpuJptUvtv%#9P4;VwqFPrf6D)k>51oM z$Aq#u*71yNA0RG1)M(7j(i3mXj@e{$tm6%d-x&CEaq*i5;X9@$9+n+b$>vzc1LCv( zF22&mi&xd%k1qy&aPf~yXxW$iR_p`Hpe>NjqRV!#Sijh z;HD=YlO5B?=2*w0v3>Em_&)0~-%C%tq-f)?M4R7^>0@)OVC!UcV6UXM5$8)iK&${?HPs7h}dg2XbR2-R%DmT_~WHKs# zO@_sJIXzaheTvtEagA$}N#o1dF<)$sXH1rOmh~4u_AdSiwIlJP4_gzhH(mS@l8K8y z;>RnYb5k5c2lh7?e|7@JOZVU@WJ<^xH1}2x*?Z zm+j(@xcDP3{>b@b-}rl!5yj9+>8t-X7LR@Qz{MZoSbHx12&Mu~4!#(i9Go1S4mcff zI^cA`>44J#rvpw0oDMi0a5~_0!0CX~0jC2_2b>N#9f*w%V6WO2?#1#W=bq!_>2$#9 zfYSk|15O8=4mcffI^cA`>44J#rvpw0oDMi0a5~_0!0CX~0jC4D4xAf*C$m2t{JDkC;sYPgvH9=fn;hI) zT;KjsW23WPsmdf4))P0}ZgRK!hkE4dYxV6%o0(?Q^Qu{M^6GjyTbea1^Q+JQkzW_Q zs)hOCiu`J4vwXVM%oe6npZw~H&i~M#O=@MH+jzBFT0f`0Wm_B5v2X$PT>dQjm9qDk zBG(sIWv}?J+Fh}Wd16U1b@{YCYW~ALP4UsC)cnF9s2$(*Gjne#t7cVvRsHwKAd~#r z^=i;9)6}$4L(TN8mDJB`I;utWMw(mRsG?qerkMc~#Z3|NdaT#}dt5?^RRR zHJ%pSJaLTqsdx2rnC=FZ>r^bse73E+vYF+al1~5TeSX^mreX1_s$ucPUXkwynx_k1 z&v&@Yvu!(=>Sqe8RgaZ5AC}`ae)+%KJ)w$U&Y%by*UW=Rgdp~T<4$5m(Za_(a4@kbYW_t(A89KO7QYO=qg_sa_p zn3MNZJtxn=U{-T{M0@k&>xI-0yK=-ze&;mujk)ro@`UgBxcE?>V}$_!^4Z2rc3t(pKsd5+*ruxdUJwV?i^q~cxk=Y zw&1kjo%8QECC@X6gH%nQ#=^D4G&9K5@4qS>~rmDl?FtAk(e8f!j$Ig58~ z!{zm=dC6wds+&Xa{C1}94a5cCzd6|L)R|SKo*8R)<;u39@j`PZd z7Oos>KB)JyntDZ#P~Eoon&nwHt9;cS5A|x-&Gh;1zbe$~^-$LmZOynhbL(rb_%QUv zsV3&-a>exE275xC>eVwR_THdN=lCr&VEYYb{QA23!TYm$Z?7$Ap3QlO{^!kkyjLn- zXBwvzn!Mw$~FLFXTNt@r;*iZ3lhg_9EV>)yKU81v=@6>lF3&v^wS` zj_#yi8ei0V@w-2~JNI-Y4wQ0U`CUHsc>UZc+^dpB$u zs(;m$yg$ER*Dk3z-9)X~?ksI2due+2$j zxZQBurM4Du?Bw8d;Nt3lHRkeMB4y0wxkSpCn>u#eW4b-o+j9VWZa~k*7${>d&n3#z zTw<=IV~!#DQ^wrXIf*T!%#PnI=8XsJfs(?b0L{aVD7~FV$G3wE`c%H9=q)^ z-5%@hIecoheXSbOF`Q)=lN@0A}W1%C;3HiwU&^d>J~ z5-eHv4)gke!seTMcL)0yt!X~Kv4;7*{mI}5CySb*-`{3_JaeV;$_C8h`W?)$Uka=1 zN_^lQ`nsPvUB9gQ{HclFu?fRWr8Sk*O&?_US{)f}-fvn>^*p(1MMu)VPwD$-JCjYV zJU-eqX;Do*T5h76J9C(sxT%s_`||s0%*lQxd+V~Q{o1ptci#?XO|By9i+76Z--Vyu~-Y9lXE)KwbI%wcfG& z9u2mrJxUMwc7iuyZmr-O8^`KVeY1IqAFix-jK;(UACF&IV{y&e?|wd3uj-dYUGe*S zs|$4;rS~3sQ0;G+5UM_Bpnm0{HR`&JlR}|Qo%M}dPpZYwEeX9<;|~3M`@%Y@Rl>Cp!;{ub;uK-DZa8Z0r<(y%Hr zTrGRi&%g0he^s)MpFi3dj?w0iHil!g`J;{D7;XM&V>m{eKiU|M(dLgfhGVq(qmAJh zZT@IuI7XX4+8B<}=8rapW3>707>+itntG3({hRN@cEiCAy3opOhQ_jh=w})}@ytE? zi@kpSoku$88VmgVJpS=G$>SNX-+7(S|EhAgZOQ$N*|l^pt*7g2o`;Mr`hiN` zQBm_eVbx>v)X@k3!M~^S#w*Up^9o*nH(B@$uODbGuq4R#5c+phqxw~4TRt|ttfYt7 zE+P3n%J0c@=>P8Z<$R(0d`j|K9#{cpgIUh3E4;f!+({vRtU%s1MIWc<#aV^vC}ts6Wp`UZ}Ta!Godd z3nd-zEBPS@c@E?w&xhQkT*y=E1361QA%Ceqz6*~Xem<^Oq3cqZ*TQ!$`brgl{8oKi zn}uG>-+oiKPim#xd|lD|a@Z-=`ClEhooCP6*O;w6wyC#9-K^L3t!N(q*{BT(<@I~F zCYUqkZPjW^5q&Jnt>$F5h3b`gd37;;hiSiHj{5KB%k|Ws?lRf)&s4uQJgGh{dXMQi zf0DZPzdx#t-*q+#Es~X2WUuPfx4Wsca;R!jbGur;w5RECy1yzkZ<7jq+sk}lP;WCfsh2wWpAXe-dwQ9L1AD7ui`T0wr`&Iv)~l+nU-yjKpMA6`asN-jXI{Qj z{kO(AGkN^b;9Xg_2lw?DXI^}^cQE(P^}#z&jx#&P{xi5E*Nefr|4uelr+r-S-Lln# z)oEVTW=ok>FQ1;a>Xti_&E~TOL$hCbDD=?}NoM=x7egJI<@6fvdBAim|7+-fj<@h~ zbs1(}{=9@YYUX6G(60kbx3?O5yYju^{rPYYv+&{jyx(SQ^?s~*w+YUj;{B`Cuimhl zP0hYD&wDNZ$YFYZRM*^i`b}^1n*~hcB9+ZO6GL9FQf1BJ!Pl5KpV;P=``67zrP|m zpE9GFIZtuUZ)HQ5> zxaG-@yj3%A{5w{ZuG#+ZYQM$m$?pqlwm(emGgGzObyBhYVe?(xRNhAG6x$!3f3uJ( zQ+uLf`@@{?X9xdv{pE`75BUo0sBI?Ks>Ak&?ERk$4gNBl$M%O&B?@^rgdXzP{-92D z^|~Ef>#_Y|QmdKXFK?gp*#6MC=VI@N{RLC%hWgaYl2w=d^-Hzo0i~<{W3yUz*&#LK z;XCw+JyTVW27jo^WOFH2yqX$a^^_{tr-K&xD3a$nd~Vx;pE_zo0q#%OXPsjw2d4uU zQ3vQzG)`murSUR#{N;H?%J`c)j@#qAJ?``Gt?`%V6)EE{&nr^KU!GUYqj|+Vd%j`M zL*zLr<8SJ`MaoSXf4M#><1g1UW&Gv(WBiqQh35Xk9+&O$n%GSPPxFfF?fHg150U3!eqzsC?D>q;CuP2rI{&ffMbbCY`?I{CU6k_e z*uL?}w$t9sPdXa5Z|raKr#J8Vc82X6mB%0UHg9WY*uIf#(Oz%E@7l0^V_B}v-d8)T z8n$n|5O~L1yr!68`^M34=6HhxISku3*5n)SJ-vOe$M%h7IU9O~*1zhpedEffvU&Ue z)!SqH#=!j#ht_|0FvRwacNb1uQT3%GE7-pA@ve!%dIi4=vVG&9h7Kwr@QC(Hu4O$ICU_H^%(DOr3nIm}dLNtkav+Lz}B=wr{-f z;$HQ_Pg=8miF@hn(Z5# ztG}ZfA1bEVzA?Yh^Xiuyb7;12RJ?7xDpYl!V*5ssfelrQqOU2oZ`}PuHuYl7K8o!d z9fv*=ynEmGLAG!FurW)Wd5`p{!}bj`U}ET+P6tA4-#BtOt2c6dFOTgTKa6SMHM`?g zkL?>Typ`+~9K6?K`^Mw%&hbuvez{@$MyaosdDG?FjB4>lCT40W5kp_5rR>oR=bhaPNTrZ;pk<=O5__Fu^7m#N8m z{AE`%vLm6^La<^8@GC+be?15(Kkw5C-Cv7DjSOHhG%a6Ca3AY=iM%=>eLdt+1Vy| zW}jL)^|9jZ!Ij?qT3x%bH+av2chsWxgTdeaIa#fpG!oplR82Mik1^mc?s+-5?Vo<# z3f!@2b+*Gk4=$YD%lVl<{;tnC#Cv3`uN!yIdeeJ-=l%HYJIBBB8vWsywPs|%lo-tR zlR#iY{c8G?S8IbGPpYr)US9!h``C|Xy!fy8f9_G7Gt^<$o=G0XIRoF6xFOVQ<2dk^ z7EcH3xA5ORJu%$vvaWdlQSXDd{j$3Jur>6?TYg#j%1jMD)6XyKhS~S4#yfo3Uf*Mr z+Eji3>a+ds-1>&K?Z6TvRkLij*D0=dU)~fv@@O4>;OiT~v(L8HUB>4DZ~jkTJ?-Rf z^gny@jnqdH9s{o`JWfx|ejNS$=HHWb!zX6YndCrVP|{fa-1T`p<}U|~(r4~_2&^jK zr`s)G1+IHr58Y+hFW?sjx6yZh@ejlK?;hMpclzC*yEfccQ$K&h%}8H;Ln*y+*==Au zmc7j`uKl-k);$o&cQjGYxT~pR){F1cg^R2JuNc-*-@H95zA3E}s0rYup~m-lo~^#!PlN&GtBEvYBbN(=n4RO_5Cv zEHbp&Sb4zmTd+J6EM}_^&?OQ|sWKU9TSAzcUnxNRO#4KxDu&jB(vK9u*8W|jGc}5$jKHB_t zEPI<>T>HNGzGlT_HDty}aK0*^1V35q-^CXD64J%)1QvS~SnO2bSj*FnWpA^KYd-?= zKRWGDu)v-Ex7(1=D^z2)KlatF)yE4C9gRF<2L_9M7%X;UaIEEN$FjHC#kC&``G0Uz zrO?Xt{hfiO$?8_+|S2ao_6fTjEeal&pOB+ zH0JHHPmO&U*}sOpPWH7iZ|6BF&rSJT@LZMWtjs)z<+&{L`&EnSSv!0?;msR@hzXAZsnSf z(NEQE;Bi^2?jE3vj{C@e&hB=4&rP{e*7%b3^gmwq>y!ORQQa)t9Z2u@(9df6BYu74 z>;%#)#4#?soZmqG<%|d3SI&OmT~1s!NOzpH7F_ck=p^ zxnREERp}4Afj>MoPgQ6?6l|B(body<>vqnc`|+XXyXAAiU$pFPDnGX$JS0yWbF`mt z%k5cCo0ppUWzGA(yy;N%Ry=dazjK?tkG2CRE&S4(rTj5>gVx3qi` zxZnMSLxJsn+rO;)N5OvU{QmsjVgptFB7PrUF5z8OH#ivi$8Gyfm0r*t{MN~neaxUDH}WzdJ9u!PGuF>8X8qm(EQ_>isLGg1a9`(#21d z0ROllSwA72&@#w@Ym{d9T;Ka11( z*<1#*e-78bo4|G9Iw23$k?YFLb?0|r=6B+EW2P9g98Vnl4fzDw@?9HnxzCdf%ZT%Y ziyNNu9XQVg;*TrNBhLp*xnQXeSn3I88B_hi@?KzhU(L@HIe=NlBpYov=_~?<~&j^m}JcL0h5fmo?wzO*B>nJ1(yDj-#JANV37})WXy8&)0JX* zf=R|KXE3Lc{K1@;f5Xot8T0o7%Xb9RKk@eklZ^ShgSn1eSN^T&30U+8EP4eNeFKw> z70ZZ!OMP|F>Z^lRUtQPgt5Z3W-$qi0NZut9nM5MnNWM`d-#QYViA49J&|#0ik?1z& z$uvJ%n`*(eXd@tk?-3E)!gXOz}=}~{%cZvQWPq;qt z@B7d3DbJ-xJLYfY44J#rvpw0oDMi0a5~_0!0CX~0jC2_2b>N#9dJ6} zbinC=(}9bq13E>T^i0PPhLeM@6HX3J4o(N04mcffI^cA`>44J#rvpw0oDMi0a5~_0 z!0CX~0jC2_2b>OEEFGY`awRq^j={zXEFIt?c`ZCTH2^2!*n_?-aDy*9A; zZ~%*M2e9~j0E;gOu=t1oi|+{B$#U^T-h>?5@4nxV&p~jk<6qc!$He~$zKi%p0gJyB zu=r5{i+>f=)5Q}R3z_5^kVVs62W4Y*XCe76L_O>Fd_a@$LNNIb*W|kp z_c6(*xF+9)xPvUdk`(tj;*%;3$FmNxmgn4}^)>m?gRI17HJE)Kr^F|cIXTj!&Hr1Y z>oolyzZGA~VD^oj5;sTu_#r*o{B{fxn`0gS!oD-x;E@D9H?aolAB$KX;^R)UPTCyL zI>cI@x7<|KkWWU)(B@djzp(E|53Jfsk9y*2)M29Tt7p#r5`6{xL?qvcVD^bfz7f%H z9PO5@$u}bU4Hr+O735~e3$QuXzV7Wi_2NGn-%I=|UsS*S;)faS(dKy8A=dJ=;|16p zYhU-aFOj*&lQqrt@$G2tuW1c{vG`*7?eFgUW5;*2Ii7WhwLI;30XDnX0WNlcv?=tH z($?TN()NWS?E-zf#Jm7YEDW$cuanprl1~0_Xg$yK7HP96E0S{A7bCCd`M2z&k=OIg zE_T2Q$WUU?fL-hW-|w-^H#F-B`%h&%0yFznWjg}1iyiO))jzp$?>AuEw-v1&HLoFAZWISn^BR)* zV)^ZtICOZX&GD>*iybf>Yerc=LN{bx34M_DCRo;?_+GZ3G+LW#{x{YQTAM2V4fDnF z+b`>GJk#cQ*1^RN@cpl*$8W#b!SEezw*B&PKg9hJ>ks!&+)pvP*a25T4q{IRi=7#4 z`#+R8*GQN6*Wiogw_oh)=o4&?XB}c4JHYlCZgV_+ddIV@zxbiOWc`N^%+k`#tbMKF zKIg`REzPUPe7kFwO|49ick?5C)|QrLL$PbXdup^azyI#@=rb+M)!P4U_Z;-w8a~r} zCe=UrgnL_utOv z`Ns4t-@;ysZ{fe_%q8W!n7*U7zN1e0j`ZDi%6BJy&?)*r`lBuV(U$(`6#cRNrjj0N zOAmF59@_f?&TlHWQs(*dUgP6wP0I2~|0;B>(0fYSk|15O8= z4mcffI^cAGbU>#_!EuTtoJ@R4I5{{uI2~|0;B>(0fYX7rIuHm{thy*TuZ$meyGzSC z!Nv`IK0SDPuz7c%#oq$vS$Rsn5iDECPcM{xS+GqOpPyfEg6wyL%dmOWRj&uL74`Gj z=Yj2K-co&>VxJoP+n=u(s}|+)&ksNJ)fhFQjL%t@C#ps@)27?`?dL@6LnGS!(fZJc zHh;7}G@{KPtq+Z8^E;m#&gVvzNo5V))iKol733=vj=w#^b z6XZsBu^$hEY<9M3w$TAsF_4V#_Mjf?B|Bi8b?&oj#%L(Em=?jg9q zo#Qm!?ZF+i8ncr%-7mr&wBXRux^AsLiswJ`UItuYU{ihP@?v0p*;!TnwC_hwy;Mlgn{+4A|GDJ` zz3MFmUSBprzrN4++tavFQ2(oIWu&icUR<~T^LFr@Y_)XfW7WZO2R03lo;}4odjCkI zzf^KxsL$AO;Q6Ea1-m?*48HZ9?yAbN(co$`*Q#S@2ZBo{U#_3reh)Zdas^%R?fT%X zjo(vAIep)E1HW0X9y>4q>Fd;f)v#}G@X7_*^g~BFfLoosR)0IP1$gVKY2MuH{QBIr z;+IfT(63MK-Zuq{ul4J*vUf|BI4=?TZ9gqG$J)n8JpHBEep+mfXB}cIPiI5pzAF4a zV;~T%Z`f$_+kSFvj1g9p6Pw&xOQ}*b`-4-=V0FQ6Tn)29^Mk-1JsA1R|7Zt{KG z+P-sF4C|%gy%FWpiwOcDZ)MvOnMYDB9R1(dH+A;fnp3 za4l?Zw6>&XKi8Z-f0WkjH=LRLlxy}I&RnYNApPWO16x+N+KGC7)Arz%>ytIx+&Rzk zy<;`o+?ijTHe9pKojIQV%4|PrHpjCLv6ZK5N32ulYe&(>7>YK(*kI8vY>u^$HL>w( zetYM$Zaw-Rv7dv*u8zJ)?Cr3z|Gf`D*N#|^&ex8jjRh8Me)2c3dEbj`VRNi~(8bfA zp6$oa=6Kd2w(@lCi1qh;?MUKlpx>6b8({I<43;wh;Ar#9{)YdKB(IPP6Ta`Io85di-m{FxE(%IE*h6KMpK$zoA{LC}%YU;7SerC1>vQ3bgZG>zqWTtW1unm!!ZHjDL zWR^3lsGFP(PQ&r6L#f}|>p4HjAdEMdzVo z^x8)CJ$|p9pN-Q^N4}5ml6W>*mp(LM6{jZ@NY+_)yn%1@T9+iPcUHpt&aU@>{-8l3 zIB)e~y3XO3z*nssq_=$%0-x#7Pk-^lPH?pjJ@pgq4}rhU+f^@1I0-)TZbyAZkF2QM zru-fBj|DCVS2#UZ^PWA|q0PZ${qowc5O-$g=VSDtR}%2s{D+6=XNE2W+xe5;PuBWm zRlLiX&yw|KbuH@Ov*S2DanV8WRdo_|f@+W778pBH=V>?vZ2P>mIi5ag<5!mJ8(F`? z&oP{QoP3-PI2~|0;B>(0fYSk|15O8=4mcffI^cA`>44LL|LZys2>d0M%_STEXveUY z=G1IIp3#dNTA7bm_%V<26>M#u+L70=u3ta3jp?}LAK=$-Y-gUSbtQPpA9tHUBXfci zcim&Ejq=aP&G?|Bx#bT3+-bs+&gQXfe(c>ZW_C5n1CD$A%y&C>HxC^6FZinLJIcOn2xE$2#KY zbIhWjADRf}SVkPvh|@X75yv`WKK<-Cll|(Qu$NX{kZkI7X$K~|7~YBVNIGn%k{>M3 zQJhDf50-MlQXg=sv-g?HlHLOs-`C%Kq_=_TJf7h_Cw|VZrMM@mnTs!NXGRUm4W{!> z98U_I>qui$wrFWTT`5zpnQ!-&cv48GG{doi_&Jo<&~L!>42~xSre_-}15DWrl?|47 zQedj1M|A~L-935-u*8!BmoEF1_vw{>%)Ui|Dc+<qdt%5)53dqiN7~-+3xyY=K*7oXVQV{-ms!c;9LjFc!?pO zb5y&=E7RQHzU%e}id`&_y7e?whv_I*rco$y8I&}5&dfBRvm?G~SZ%Q`7^-w=OK zBwzNtp~PK27d$b2RX5rLV7b{Wv9XZeCgmsnch zNMswyH;Uw2N1`*4=w2i`97$VJz2Ei^yTdMpu%bLF(_h6Ny|4sDGc+8R5wHFjug?9kTOp=(sXYCb=c z#tu$T89O+C%GklrQJjay4t_qE`wS`|tJG3=+D3&$n;W}DlhqA^F#qY*>_+71jQn4&J zon^y!iJ7Ut4O;zeFr~kx{<*HzSEn-d^Fgbh4_f_vFr}ZTu}N8Dld{GpWsObB8k>|g zHYsatQr6g{tg%U1W0SJRrl2)81yjZ*(z{fd(0Hn>@l>UZr~I8SBwK0+7yL&2oiFsQ zBheXYQ_xBI{`g+f2Emc&Fn{L@wFTa%jId34tTQxr{B7Heq>a-&Q(N;)ZOt=v$~=?i z#@d=2Yin+-t+}zb=EmBZ8*6KBtgX4Rw&up#nj33tZmg}ju}+yA+kGI-=e0GT*D3RP z`R<1044J#rvpw0oDMi0a5~_0!0CX~ z0jC2_2QokhU{9BF9YYZR*Uuoi`a6AgI^cA`>44J#rvpw0oDMi0a5~_0!0CX~0jC2_ z2b>N#9dJ6}bm0Fv9l#l4`7Vwjh;Vx%fxz?YO_1YGaWf7EcH3xA6If z=??}uz7D6`94^1@tIg*4`BDo6;#rpM@9xJ{$(m!@v8*I!I_@K!xNMN_IB6}o{I&P! z+;91Q0*`K2`uKtyAlrw}me6<2Z2~Ts?{`)D!*1XYPt8*tzlWb`-$SX;rq}AZ$Nlfp zv}HZ7$t(W-#Cz|1+Z%smF!D?Mda%S{2TOc*u*7W#OFVbfv+3|LraQ&7<8m|qJBDj7 zE}g$W|J_o3oZ`5Te`QrpLbOpPw1~4F2C&$Gqd_8&HV4^ z+6(J@_Nh)c zzL#r9tncS*N45`nn<*}q=J;6r>lzdXeCLr4;9LW;XpSeu={ASUZ^tsQIkU!b$ei!x z+7avf`Pz{k)5PXT;-T2FQNrc7W9!(QS>p<2&i8Wd=tAwtjd|Hc|rNw7WQuN*FaM#cV) zZ7l3_V{m8wcXaKD_5FP9h;7(x%jR4*+i|kk{>^r6&cilxww3>t!{z5a7T#;&{591w z#d|Q!>tI`1{{o)a_gLGfM`Gw)6D9u+h1S@GT#vu&U3l)sbWy)I7Yy)WJaW9FDqyl=#u z`QOpCBmU0kYe&3?%=^cj%VyqZ=KW?)m-we(-lOLIX->B}T>g(?jKvMv!k=-^7#yzPBpu@i!SJAS>+S@jlhfxeA(*A2d3$DX;m>dnnhqD_5TX^7st z;&t$;21$BR!yCc${+j+P&t*wE+LYu6%X7f;eELlwAmxH>yQS0<=~92NyrbdY#^=4b zq*%X~Ye&A6!^t7FErd9qvg6B!@Db{uCJPmwO;EI4z% zS2+D~>8vCCC-XGun9VYmL%Ph_z%uts!{PGF+5tLdGsj=0a{z|x!0}hKO#bE_Md`A^caah5#b~M!#hZQXABh=IOFUs*(DGn>rIsPie zVMUwb_^T9$RdIbd{wl>`1#|pWio>co-L_kD{8fs>iga`Ol%hDS;LQ16uD$U0Ki|Ag z>;}*)o5i+(bg?0T#TJowa(i}vqF&$Bk7-+~>mdE)YNI&awp-30rFHS2efxi-wIy}6 zoc`Ir%=uof9r5=+Upo@pHT2D9(HW$RO&ct>@iZJRzwD=Iu7%CAmxSje_y5#OsL&sr z=h%2}t2YWvXMIC7Uj%=(?(N`zviqEU*93Js+0Rq3@(wj)Z9n80KQFI-r&eq5+{7BX z!6OM^+b{I7CB1d2yx*Yhyz}0(mp%>azaOh}Vw^kpt zBinA-f63i?^EbZzf9^Fwef+7)n%^;VzL#r9{B6(Ij$|*@*FAra6)bZYug%;Kc>w7_G53#9Dl4K8=*(@MdYdd?DWvlZhkw;SLKu7 zCyV_t%dD8JhRpECvYB(gR16WuO}{}qqGxD&7MPx` zsSLC!DpOP0Xj8V`lIp0bu4rFWcTMl0`5iOod%1SR-}Zd%NY3^^uWYt$(Q@VodF1R+ z8V;9V&YMBUY?iZjcnAoY;UW{1_vgaoFdyCSmG{$Z{F~;B3mAqYSo(5$)>2uwuo^`?p2{pWzP3Z&dF0+-8V;9V?uw!v*(~=-p`UWk6fE~o@qD?L3YPn-V7bQ%miw(>x%Uc|`>- zk-PS3I9z_YI}aVRna?lKen0e(&o9vV05I7G4b2hpd_KQG=Lx`keu2&zfcg9aoj(Bc z`2{+c0Os=xbY20x>7&*ZE7Je|e4c{N8K4eSuC~h6R=IpG7r&))wN3*mV)~979yvf~H2im@cTcSY$t1OIB&*aqlMGYe#ePTI9!uXMRVKEqyNBQz_LyO z%lZW@>l(1Ecfhg^0?YbH@iS$8k%nVku6-ZeX0aily@+iANEe$4SZpa^v9W-~_5v203|MS6V6owV?R)(;$FmNxmZyD>(q`G4 zFsx&;XMt~OpTm(o4t!tP`@r}sdm{LzvR49@Jru~+jz=teE=ZTX7_jWofMxFnEPFa& z+3Nwz9uQdehQRiHSexTnhgi$gzE^Iu*v9eg#AXh*&n1eD9p6rD@AzI~lLw2f9`Y0$ zKG=>uEjE9o%U%Fj_6WeTcL0_>1+eTjfMpK?EPE4R+dqKK@vK9v)e(Op?WK6fi612x34n2MicE zU8sN<5DcIam0$t|MM1Kom~+lqLC2iq=@xSy*BmhCoE1Uw>#lzB_S{+T)#qE;{m(t~ zJg&bj>+P*r(c>DC|3JtrW6)KfAWJ3Vp7v zxkA>~Vj*j5w2-y6TgckyWn^uw7qYen3|ZaRsd9GO@T>j#@7kO8@2WRD_x)*WSuvJ= zb-mgednVqy?A-tL@2WRD_noPG(0+Bj>V6!Rvtw`0)-9>ox#tMq3$2aF{JS);sXvi_ zZ}_YC2mSiJPU?OTmH$qAUbJ@~`%dNT+;{V<{i*IpQ2Fn)=R)0AqH=cb`}o!VRM*3+ z{C8UOukLG5IXm|q{Az!y>vmNBJFQJp*I%ieo$I51wLjH$j4J<~)@rKjQB}^)^`gJp zpX&YymH$qAK-7IMDre_Dlwa*nb$!0df2TbN>OKpVvvVKBulA?99#7@J)0#tdU8Ty| zx$f~-`%_&Hrt;ru&6~QePvz`fclWFPsjXeX@3d9^)$6aad2Q0S^bfa)J(ar7N?l|2tNp3=oyxzuUbT(c>D%nAOKsz?^`~Jys`zd-Yt7<6 zVeNZZ)G;tRXqe)MZ+BNQ@lU^Ey{?)ERnE?wn4R;D?5r#Md}tVF@YT`QM*kC5-YNC{ zGO+a3w|lQ}ocR^|Yt+w8Dre_ssO_KX)`B6W6-jw>gp~~6$8)A0;KAW9& zWuFfXi_JWj6bXYvv&~xtp3m5&HA(YKYJJX&+2RE+JTq{Xy@G_t9No~V-CuHR$n{s z3!l}_0Ylc#`$E=o3i8kDYv&;0v)cJc$m+gMEhnPjy%;|km>b&g@Rg*6x-}n#$ zd-W;EYkG!(f0>QQ>Yk1#PLc3pL?X)X^p1v854s?$`**&~i3ihS7jgYk-J}F)=Ienh z_i7cyy;_=FCt^v{M^^8N)5<48N2?cEvj@4t*8z|tb_cS>jlOUU&LFG%Z7*%{5&emM zYO%!wBKzk@R`*utd+P*NM&e-riyUGa=yb+5fBTht-s{6Em@ zHd4>W5H<>1g@UkMv_Y`;8xV4?akI&`(Swm)FH9jV#t%VGE;Ekg9ua|D%yt}k6fb#h z(?oLJEfVD(qeqhtH>BKS>{wzmTe4cd?cAB9@_AW)?w1pYo4M5a5j%gRy+7i&AMyW> z^y81j!;i$(PsAq`{q?;#|B?5_v0exajz5IuoX8yp<~ij3iRzd$JeKJm^SkIoU43kr z?#OM)9Uf6#(jCdF{*R1l>iAYM>UZ5#b2)BIH=U(>!SBO+c-n%s8R5jhxByW(e?&7j zgw|pY*1pxbZRx}c)Hh?sUykWaEqgJ~C#kggnfbbIo`cyLuUWKunJ&5m1>;zyNu_B| zn@e`-UlUlDD;;+i&sn^wuX!BnQM?rS&Emq|)nS9#<;Y~YRXK9+Ct9+kH;imnj<#~hq_xj^!Xb~c zG{e%EwI1CK%I_>qD<$S(`yJh(c}PiW<64C6nCuGqgNjn8{-xMPr*`1tXGSYKP0*i6 zjDhDt^{IVMFZ#|Y0ur~>rX^==qwRJDgK^8Mf70nQ>x@o+G8!!I)uWDA#*!MR2Ei++ zNk2Z?M?R143+1<4QGN7#GMV_mlKkd>Vs10ZvN^S58i|hbhQ-6m(M1nF5SLVM=zO>w zUC`DST9!(u7J(ae5BvGS(HbA<%Ejw+#l*rH(IDOQ%R^w{+zGV0yOXXfAG6PF?MOR6DyF-3DGm-T$w^B% z?6j*#6JYe7hWc%&h>63R4 zf`fKT$oM?|`sVKaV5jj3Ql#EweV|7V==I7T2A-zpmI&*$uu*>Vl_U$f8Zm+BZ)4Mcb(K&OH=6Yv%HrSlC z-IA)){Li@mNr=uEJ`L%{o~$WN9$(4}0Ry|Rffq}Vv11BBd~ip$U~4hr;Zy|n%yebW zeT$L+qoVM+q$|5?R+OmaOdgX=!kQ0Y&vI2G&UdSmmkWoojP7*_--leq+dP(?KU4ot zEdKwM))7?hpnR>iqou@#z}aQR+M zpKyJ>Ru19i=(X~Jm#^3A1zxWhi-bME?V*~T!0qI9qy1Rl)$Z%7iaNMV$SH3Z%DFz} z?LvKC4$CTsm(O^+uzX%G@{GTtt{XOZ^C`s6kM79k9xX<;*ym*}&U9g3WlEB{ zMRT%cR^3@y>oUYD&l`HVx-Xly$(-bxkV;pM3}6;f70Ajm2kC`7ec19AR%B-N)%4BV z{w(3VHR<1C0-X>!h)puCNnY&pqO0s8Sc|o_$&zj6)Z8kHE!tU^1oXYDx0@KvI_;=O zDn*xJiAUP7{2dFCQN>EIHt*WA_LB;W*fSDsX+vaTqtL$ySYEXuLdEs`jF0l+$n{-(}d$kXAg3l!O@h1JXxDaqO zOCd{YjM1k!L_)}v;l#9d6MfLBIM{mCm^{tgwKtQ0mR_5fubF?)ft__P#zB>HIceqb zJMB7miG;Hj!>RXpTV2zsAy8q-v^! z1Sjj*u=m|EbO$raLAgh**^|rygj(^dEbTp6_{%b+a`}Vg>Fqx3i@g=OG9!_s4G(8E z_thi~4w{mVZ==|Ow)IFr#-65LJnx+2W3fr53EllEiaER1BV(#0(&babS>o}UBxT6~ z8k5n7nRd1!-BP~Npx&NrU%s;B>b7$1wYf8^ZB>vIx!jPI9B9KLw`b^jJZ#G*?kdCB z<;%Lw<9yi2RiEjG2Ag$ZeM4BSuoRj$V2sYSX(S82H=GV%-bAgv><+)W|jE{*cC0Z>e%v=ILFDFUupVT^NnxwF|GWp`Np^T8&9p@=5^|PPqSZ} zZ}9uA>c9T3Rc-4Mvyoe{|D_YA-K%vEiTF50PbcG}RuGzyl+^hX=^ zbPa}b@yC#3E_*;~1NmLkFiSfqw4^rr$MkJEXm8RExzC6fWYQ>qf+?My;rjYx_R_!v7b}XU;!)5PPt5 zIr{CYTM(-?_b&24vo7piA2alAKoww%+txr{@u({EEY}iw;QIXR`WO%7*yL+;Ch3hF zv3fpbx5JUw-LFTtRF!jsK4E3_MrY-BCOLW@)AiXezlZ5(9zu$imG5j7+wG*eE)<`Q zKl7SYOzMfeF{2pdyYGg4+O!rtpQS@i&esB1Ei+6?vmkT4e8s7_IXWYQH_&7(v z-Cg66d)|))i}doyPmUzO+>q)RCl!w;fM5Qq_+G2uMgPcm%Rl>l_4mGi{;%(=4eKSu zdnrD{%D?|d#{QOiKeCpUCG?R#cMXvzg^uomFYcrA@c$y5y9serN9MHectY{bu(ibds(^PpPARPp-21 z?DxKJS95WfhY7GGn(Cpb_#=!BSp75k(F3vxco0zaq{`Y@QAN{4Z-N5JwHSZW1 zscSq`{*m<|>ROTS>1%tVFosoDf2aP{cV1|F(5PtsufBUCJL}3mAO4>kH-2`^G>k2O z8C(85&ZukERMzeN_>Ev##v( zp<$fC*XaB6I*e~k$H3@_KaVr&nqHOpy<;HuX^2O(ePPJj9)!Q}_w=>BQK+x7x?b*A z-~FWRL1UsVzxocQ?5r#Md}tVFMC|+zpC2*4H5~&>UnzbtGE&#}tIY4A1~I;fN3?xm z$l6|{zwr0;)jOnAR@dDA>N~Bn^RBM!tSkF`Xc%X-F@(v##sB`vC-^>SItE5Z{CPg3 z?txNSJ5LpTrrooKtnKOh3x7{vz2i(}b>052zH==*?~=>Ty0XuQe|o2we4oVs8syR! z>N{oNzxu?;NZre+a(a&bAod4}XS91ck+r?Of8p=xt9yKY^}TrN9emk&=U{f$_3!bg zVLZ{^o$rmYn0NpBei_Cb=@TO(bx*p=>e@x^K5iUav_1ZR;qU3I`viaWy^ZP}kv%Q! zi8$9-wDVWr#hIOT{d@dr7-zIG#4ygFBYt-LG%`}p)==4=?~xVf1&Cs``{I$cvp)X9 z-_uv`Fjbk)xxeLr&#huX++88+I#+Wbh&wF=2jueuao2_5lD(Zk+<_tZ^(Si(cVh@v ze+%pXa5oWmX$ZM?CoFPy-W8jjb!DFq4daZ6ssG_~BF34fV_@kk#Si?9Q@+2SuPM}v ze^OZ+TTrfzA;{WT^cVh~zLx8;PL;L1OhvuRKP5o5E`hj4(Ro=6v~{z?v1QoXQ0O;c zGx8({eul>#U+Ro0p zveSp^nR_a0-`!!~Y2VQyYv1+#g}YdqB-Te-dJ>dmEJ4^Dp;J3Qa zx{~(}P1ofvE;)2X4zlW19QL*Itz0DcA<0Fq7a$*|NM>=x$nq|dyDTY7Mi-X6w{j%{ zhvXivBM+*RCE=12kJcx1|6Q)GWKgzq5~ z@&B9A0OI&X?tRFN>QCBh@}19u$$fLF^FF9A`Os4G(KkVaXytn^=}Ek{N%^~IZ*o0T z^7-i=k7t9Q<1wW(~^gxD4&B0zG$zNUoklicQ3eX_os^p)wC>SWU( z$@6S0k?@0(TW%^#ZktIzM~^Q?Dr^2<`mg|*qxDO!N4dzMgHq?=>Kr6S>&GU;(sfUY z$^P9O_EzVu^*d?#Lie?$l(#GLRCh~@6GQySJ~hOTjHREAAHF|v4?jO#1zYcl7Z7kgPt&4n_@B65eUZ}aSp;oR~@ITam2%g?I3~XL(K({^0|@=lbzjM<6F$fjZm%bk=7k}{wECpHrF=IJHN2CYHAmobnkDD@ zG)teCL$k`^<+H5vdA%&FUTzP|vWMHrvh3vcvn>00yI5Acczan^d$}K2mLIr(SeAdd z-&mI4xIbBzKe?Y-mY=!*X_o(aztF6H(e|05&kg-0a2K#++$n-7%h5&eCCBetbhLu`CK!9 z&@Fq3Tx4KRu%7h>`Ob_Ua3tkD^7_?&@TJ5j+^F~2Fw_Z{pG!)J;;cSc5Ox4Xfy9C?r(i**CiCNHwBPgk(+ zl@Iy-eh)BnmuE-ZbMkS}gg+W_P&zPV(@@?$EJlLDZSZfpi!u7Z@!J*@LVtbaC?&v^fH$D%Vnc4Oq(eEW|!;-N6Jfoo}bnO+8&dB z4hiiEtrkfC&uHooZPp$a+j+m|C@lN^ralnP zY4PykX&~gTBV)rb{zNemdxr5R4*g&le+=VKc8)(he=#M0F(rR7C4Vs`e=#M0F(rR7 zC4Vs`e=#M0F(rR7C4Vs`e=#M0@pB`;FQ()#rsOZCb~(1abDGh3RqP{;m#)Ga)BF>P^wZ?^1u-Ht**^(1_WawUR?oPy+lirrqb$24B;aQZN^_=yZj-KmK z?ODp7rCOPkmr1p{D6flYHc)N@(`=*MHm2E3xy?*#3*~L$Ieker-bN+oJ6X#DZG}=Zt>@#QL{Kc#n!+mk2ks=N5@E^+?k$xDekyHXEy;{3_=mL{aj{M}&jG~wlZ&FBk@6?ngE)UO$>AeOtLy>d{K=5hU&ydiULek&{QC7Pxya9% z7UxgCJpYAMKIaAE{K@g1Kav~uJV2a3Ib-@WGUs-C5a&-mJ#?KUo7sanf3kUl6XesU zx**P<{K>~L zt!VpptEo7Da^c1VS}OE973WV*-aemxxsr>C^Cv6Z+Da#^FlXZY$!+hB)AI-FGI9Ro z{dw1E&=X+d{KvJ^$jF|F^C#oV9i#~tsxxsuA2kRxgUS1E{ z!#|ta^Lo%u!tE4iv-0zvKNE2_H`g(eWf=+k4a~<5gCFp_WP=~%eKG$sKZv_3T1-Di z_Drn<^>P}ss;{n*b3+NF7d$~(j;Cba$aavNI-U+_^?@|zcT}`8uSZAJ{Y+~2@`Sgp z6ZFQtzLJ!))Podu+)u=P91GT! zCYAWzFycOr`H$x5mRjc`;y#WdB`-8(W1BP+_i>o^ovRPMWDt);*gNpk&oB}q`$9GFHtzDG2>rX7s$uHgOE1guwhmD)ko~B<+ zr>B~CXU369bV#W;w9~4NtfuE(8r|bQ4O!{Lo_OYA>8mf(H_Mtc^;vPhM#D9kbjt*9 zChphBH{k;OZd7bfmya9MSWT1;;FCw^lS4`YW7(seREtGnSJ4~ymm z>GEGZtaHhThYN9ybr!YiC!wQmVO-R z56L43(AQH=(JZ2Us8I-abk3jf8XX3L>y-xCT^vJATBnLWZXRTC)>n*84izLlfelcLEM*d zIQ%ndx6~8FeHnbr#d)d9YMxT_m(;zEc}>lCTAsx`sOCpCZ>srJ|*H)a% z&hw(oziM7q^R=4C)%>p6gLz+_52*75abE`4!+9x}^L+np{=nw}-{uee-@nZt_`KoU z{DIFWzRe%_c=T=lAkL7^nm@2C`}x1Kh*@irLgyAw=Is*ltoeh`&ze7oajIgQ(g$^h@%Lj}lg`N69(iPK-#2pFrXb+w0r9>!GFmoc2rQX71-Yb4 zJiMFm6xV0k%u9eHwt+gKqZLuO@jR&7vD}&F!~IiK9WtsY%<&s&1jk z_dbp#DWfBh-77RAD?iBJ)~|M7qC3-A_C?8d$M>2%lN?&cl;%Azzo$K%cOV^gdMG~I zb>=#{=A!&9e%q&8)bWF?YhQ#BD<3LcEr}b+$#-qGQrSZDi zePmrV=7kZb3$lD`|KsF%)nL>)%YPfGk>Y`@mN_$ZH05W&p}ax#5q;oMS*CV}Aj+p* zizLkhWSPdlpC);m^h0^K4Fw_A)*X59!@4jiQ~FceAB}Qt&o9Q(q6ve6pKXV{^LiXi zd1Z{e`)~prY)}*9sz=jkINVmA1zN$cKTO}tFviq9-76yjEMDN}0wc#1OQ@IE8AOa} zdzt^jXPa5Tu19`UXj+`nB1dEVE~;5$s7r+wmPZ^*CnE1D6A$A} zKcQ_W-Y0;=v?+LQdH>irm}_l@_FoH*gvy;2ZuDd0}W5=z6sf z6LxkDbp-GCm5?27G=c>+8Y1tlQ2~x_ZOwTY{(qtSe~>}88{2MRbjC1)AO4^6gOQOs z#zxH>N8g3XF?O-#4SlaTImWJx?4$FYCCBZS+j^4PTchy3uQxS?qvMj&Tu9x~)oh(0pPy?MsiY$M3kQ<3!5sl9pJMAE`d1WpO zxpSCIyf1UaesY&M^p-hjcajN=cq_h#G&1U#Q3CEoxFU~=vj;dNbLH=o9HHkQ+Bnvq ze;(Lwjyl)jnJpxehb=!f|xO~5CuK62~DrD5S{7vxr_YQV;g z1o^C$EiAragY4$0gIRvHIRC50f4*<7{=^koD#Ws5ol^Up%!Z)9PMut~^;jlx#J!gkRH!Jl~JKU$Btlyh77Q7CsjJA?gx7=H(-6^&)HbAZvCaYxW~+?LyYt3!+TT z56HsD;w(!c*Zd~s(x1qhpOH2HBWwMFto0YN){n@%Skb@8TE8P}@qnzw39=SH$XZ+> zYw?CGd@S}U37fm*y`q0NDIWQ2D}Viq`SPrLZ5=GiRi1S3kly{2)PHR}T0dZ*)GuOM zSRZ{!vg?8b8hBscVYGPK5IT0WT)Xa+uOD@98ii%Hv-6?#-bo(P%av~56piv6m+h%f za18S3`}JwKw$41?{Yo@iFKy0UuQ;vLAr5txR?J1ao{(It;v2nhLus4w@T>Z#VuWGvxgv1KEOu50E!p4q_t)-A2~>3(LF^?#4dPD~`PANJn;ZS5f32 z8B4YJLH+NI$v-l-|45F|-f^t!d%5Pn<+XpBvwkGsiSbp*WkktkM8t&XN9|5?Wd44M zyUvk$dx?m3p~L?JZJZUkOx&4{axuOtxlG)#j&kkpb!6^;5PcvD5%;kxxlG*QF6HH1 zLG*#p;r$3oKSEYN^4J3<_CSd}P+||1*aIc@K#4t2Vh@zq110uAi9Jwa53*v9zb~M? zFQB|HkoCTBAA^!xLCLKk`d+kGjQ2`z1tqtFl3V%ruedJ2h|gbyJS(>f{jA(7$|0gm z-shrxWZvhZUS!Q4WO0wZ=zF2h`y52y3l?Lo=zGChegnb0&q4IPVBY7VzmR#Ki++@H z*}uqIzawk$fGl*yGol0QSu1M$|F4Y z5heE#CHD~}_Yo!c5heE#CHD~}_Yo!c5heE#CHLu++^5UReLP?5lzgpI^0h82Uu*j& zuw5#PepcoQI%S@q%bF*sJ`w#d;z0OZ8xxR!#J4}vM?ccnKN2%P5_>-q!`eHAG5o!E zf#=pAeW$4K8_%u(^xgcCcU)^1mZQCE$l5!ItoetDy0mug-Y>NCdu{x0 zIr^V|_7vmy-|_S2mVU0RP664cVY^&e*~Q=bl&#YG)GxOiTcdH#;~km*b~zvWeAJD# zs4VAcE$XQQ>X@8Z zzb_27m-_uu`#|#c^QcoKst?TReGxhFZEvWWd>PrXUI+}1KZJZDcNm!G*o>@}sm-ZS zuH_eG!(7f4MEw7&=5n@kXOhb22Vad-5Ceu7FvNf%1`IJ^ zhyg1BMtd#DF0N3^8Dc0YeNJV!#jsh8Qr!fFTA9F<^)RLkt*Vzz_q57%;@Z ze?$!6npdqa42+I2oD*V*2SW@PV!#jsh8Qr!fFTA9F<^)RLkt*Vzz_q57%;?uAqEUF zV2A-j3>ad-5Ceu7FvNf%1`IJ^hyg1BMtd#DF0N3^8Dc0YeNJV!#jsh8Qr! zz~3PT?90{=cV<)mH`|rZ0r`Eu{H%R!H{?1e|3Pa#?1jAh{V3Y|;Q-_viMRDGt;D_F z8|au-pv!loAF^Y4H)4Ch7rE5pZKO-f_Qvrv6%l&f5>l@j^5{rh&%_1z}_&I0f-v*dK=Ctm}UC1fY z@@)`ugN_qPr`7$D$G1og?Qz}D zh3sCTF0&}5L*BlvI2%^EBl1)FoOYPg13ATOEltW9jQlXsh2}3R`~40ZqJOX=6y*)> zCF@$~`y%%p6F^KtWegN*wu2Zya6!54sWkF6wh8i?o@L?Lp7O{KQX0a0yBx@C@3)0J z4N}nN`flFP63+`ngoy#IU!=un_7^1;bDA=J_vc|(!?r0J$U$aBgJCL}Zz zd47T2I`^Wo-vc9u=<6r+L;35?9<=vGU*ya7+h|HJ7vvdX>Gb9p+1K|sn6t&}%c6Xt zT@$vq(0jCPo{1}4oNqmHZO0yL=oJTK=cr(|seKP@V?OIJ7P4sywmsl>D06J(Ohj86 zw+m*EmM=qY-^-sRb-jUH+TESePx(OTJwV74vC^@)zc%*)tp2FCEHe z(2?D|QGTmn3T+qJ8+l{?5pL!@0RaAncImt zd>)@H>gBpD^*1YQOFq;7>~e`^$OjVq*=MWg$hBNMGUo-Qnb5!Vt|{ATEq!&ef(0w% z(E;U~yM3fp2KGR9w_Zp6Uj-wN+0~p@jgx(GWN>gG>i9gJMbfOh zAa6T)hqPI#L$)(24kad5L>^9TpyC!eJ~Y&|1IzL|(Y7bx3oXxgLhiPsAGoC2VP7OV zhJne9r`Q*h_YHvgtH%>z|FZ_YU~tFF$c1isfRBqA2zgwS7I3C%9pu5cs=y}`XXGMD zrqJ)17jk0Seq!z^-<_eS`;rTfq;GRgpQy9$ExGWrz508XWxsUnG>jTWcE@KgZ#_lt zuX8{SO3cR|F(YJ)M(tp=S4HF&!8VX!BHwYpQ^lcm_0A|i6Z3#XdITU(>$s5kH|~#I zz^DRQs`d5JoZFij`$+lA9_DoU8L8iS%siS3T~OaH{0=Q;4akcM6lKe6S3&l_TZg5a zxhqcp1z_ zHcCRSv#%%1toQ_Zk98;3s#I|%{Omei$5Nx}BGZXhtiv29zT$!%oSyL#?Q~k`27lDph@5)W4<>i_L~h=uAKVXLg6(zQ z6$-{vgV7K6=3#K9v;z_Kb{-K7t9(}=cPQx(b4u|$7`gm)u`V!wSRoL+`HvPbH?bOW zwY4>2Mse8}7p#gxKD`{z!xuj#y6SQ~_nx<&ys9kU*_Ri*N#k)c#v-b1(mAx3@A%Ck z4fTCPL$J)jgX>eT!hy)M3eBa{`*uZMUh^UiI_-qqV^D53Z?+Bc)EX7pc8hYzmN#wL zwNo-C9c#5?y}BMn`&VxFWNfN@cgETFVpcawqkInceZzip(GS~BgtDCPWR93Qr6E|6 zrdZ~cs4_4!tpl=$?R(-o&ktEQa1$X_+?nvnvqCpXS^p}?hc?xLH$g|JkRN^S2@V@~ zq0ha;Lcyt~AJ#j@s2>bGXfEzU;CC%;BTHfnBJV$Un-1Vs;^HMN)BCH9Y9}2xx*FP9vT7n-KDs{gy4ZsB)Tf5X z70Sf#wdv3Rx%BD7x>Iqrk!LOMK&Ec2BKh=GqPAVk1%=JlNs;uqgAH=6p&6on&*Npcy zGVg1~`x=?|HRFAa%=?=0zSaqS-q-A4N{K32ZEvB5VDNto1Ll*1yPF|4Nqqi!AEr^&yM;d40%P^$YuRtvh0+ z$n}aoJvsG5RvUr$FWSue7kK|-TX_Eh?_Xrzzrgz!nfEX7{>8d@{}SH6$h?0=>>&%= zc>iLVBF=gL;n) zQQCI(9^_M&>#2X@Ib_;s3cbJb0dmf&zBG8rJLIZQN>UT6FUVsT&C&DEdw5@^yhm&p z$tvH$qAv30$*<`7Gn;fm?rr{=9zS-@D(mhcF4t$txjvRD^m&6u2ZAa#9CyJaX`a~&*DCHBSUZU8;???OQPd;9L zv!5vKBHS-4wDyAH2ceJl@b>b4`L8=a72oOZ{*bq*>_iXLq zpHU}v{3_k|o>g@8YQ2hFr_@CiCW?;wELG%xdRDPP)%nx2N?X*rsQRqp6ROxu)n^so ze)m}=2EO~O5*t*lSAABkOVw9(R5_1l{-5D{H-jItD+c5~?zPiSR^f5Sgx|BDjj&!m z_KCm$T@0e_nhpOZmVJJ-=NNuJ_`i#dvf3{G{&z9c`a;zI?_yrHd>@1@29{pIY3urjenyKU6j4-*XDi)wdjd1f7uQ7MM$W9&CZ!klv(8K{b(g{=(KPkR>8t{rF>B81;rjv>;%Pr@XeV!S(f7`ic)cLxLZP-M> za`tT1jClp1;tO{O8neFYooAOx)4RRF$**ITEdJdqw5sjW3n+l~|Kjv+ z>K^1f&$`i7wUUsphK{HF4>Ffg{%^=!m-1(jc^Qt&L(=dzGzwO8m9A?J09a*%nQqI_gtr>GZM$i%puFGKFLeFQ zCMf?rqB)zo)Dz_o%NJ&u)yi87{S_5juxiU@=tMcajmt2uPla6QbGbfC&dW!+D4&-@ zgUPTpRWi}vz%F;R|a7xxLug-^I2P%iwS$aUo^ zmqmHEcP`0FIYiMXO1(rWpD1>MVh>T;1&aMd@dGIBg-VAPuhjeoihn@yvyf-`6O?`t zO7R>)+apfG4_we5u_#b30WBlKc#axj;Bfgt362FDWg?^SFL^qpFl6pa@!8}rEFM<$4gJXdq4}5z-~8wFqp(KCs2~GNFBtq_@Wa18 z2IM$ds^rI{7IoxUTA*n?IyC01t5d{6Z%o_hJ4JXIBW2*DYB_iJ$7S+ zC31~s&g>J-f!u$CH(P!*1;_an??PDK)~tOS_SrR|QyVMfGhH0Oq(p9HHl#aDZ+i;u zw;$OLUY8hyyzzJh*e}U}eEd}$gm&m`C)zbJJprn0FGmF5HjRV+7iS><@p>>g4!VMz zaiBMlRRuuk^u6y6wOpzr8|Sizik({`Z%VETdCqi2zPdRt#JA{+eC5+w^6IU;lRGu{ zB(iTz9Ln`a3zCel3CQ-HU3a&LlJcIvnbGOzq<-s%ljx)(vK-G-=V<6OS$@M}`PjWe zvffG`tFmLCt6@2Z+S@Z-YiVb(Djv*t$z`;^?EBu#=F@a!*J49h>wIOAp=2B@n5!xJ z;cP|%yWh*0iZ<506UXknmwwy6CW3{QKaKLk9{t#m!P3v&n{{WYbEW?~6mekSNSJu` zsY6XRag;dOz-qF8KRumGXU&!UKEk6ab$TJ=;nhgG_l>=b6RXoN zblak3{JhN^PRh>E;ws=M2~YLJx(=Q+fxLO0kOwuZ1Rwct>%xZDgs=VRD&sar-w7IA zyNmV@u@8a~w-zIRu?dGEvuu!;7K??mp=S7AoW7I*Yd>AY_vP)(cyP~*BBIQ6`=O9L zcR%u}VV|wDP2aSJNzIy}{7iCP*pTUlJmgX_Xm&}y*DnV>CSDEX z`yP0HC7C}m26ejgr4t`_%6NF2OmwGi$D@2@J*GdJITV>Z>`$A0?2kO^;9fd3k1ulC zl}t)cwLvbCXu$@YsE=$~uL=9$Q4)D%Ls#Zy{1WZI5a`dw(lyALH3qU4TiPPmdl}8j zSPa0n*PNQbZhcBZpZudr0t?djq@uk$wnVYh&$lD{l?`PD!apIi$$so%#d1vOIIL*L zY7}pbZ1t`IyX@nF9C4{MBTsuE7ajSI4l0ZDY@>h$o9KGiX!-0~4|>Q?#=|_z$@-9< zk^}rF>9+VvosQGpNyP^8+4UtikTfHqF~j?WNf>?RRXx`g3%}Erzb%F!EK0WqutkN z7_XB)eAZ$hjF|EQ<>f~BLp~yXKF7%wzHX9zG0C|J*w2%Fly=AhV(!T~wr$t1WadrT zr}LWY$;h{|uj7^vAh&PG81SsVPd9n5jE(Jwo9f%mlrd8~NJm??ma+8OZzbLJO2$|_ zv&Zy6(T*VOG}}{*9SN2(IW?TGld4q#(#xZl}=LCow zTn2shvRoYGpCQNCNtK4ckp^SCkqA=mpBAj+>*!WwqR z$gzEC<9x8;V;_{4fb%4BpUefL`b{SHLu8J4o?4hZ*K$XRng^S;n;_-30R?HMNd!JS zeCkA6-KQ^dmxQylWri$2XJ}qlAgU$G!(ytkbDq_a(>?(UJ}2$WJnGK2zLdFdWKwSy z=sy$N_*?2=*7b}z^5^teR(51J^h4|P1a_*T%&q@;7ss|v9F4vja6N)$96gCVZD~K| zav>KJ?R8q%on5Fa{a>M<11tGb=JY`;YO+d&WPjc3XU5Ds$bPIg^(KA)G8~_6<2Ij$ zB*=abI8}|d*X9xn9-P|i-9^Sp-x-f}{np6%*)icaQYlr&RZ+7eWUQ?hmSfY{1onA4 zAtzj{2u+^L_^frgIkfpC<2J>m6U18GNBccr1VUotrN|@G2LZh*=S~Md#lW@BrSZM^ z{cHkMcyDRR!1cHA4@gj#~o$=%i&rtOk* zyqfjufz4Q%J95MohZCdZd;Mt56GAfvqW;5D$z)SsISyP-w5^7h%b?B;tpj$PZ= zfmN@8Ye$TZmh@*;KCZ=fS-cHn6Kl92m;WQ0J$H=3wogq=V6Lr~pijOwPGHv?`k~*d zT#jP4JGLQDbPr{#+|!UPZ~C!)qsubkhpuJXvl$VMkn{8J-nzeQk9;Pu44c1D=8juS z-&31gp(w9>aWnO+5sj?(>rUUf%JHGO@htt&0g{LI8Kc_~FLgTFb|#Jb%iPiB>ITxo zPv(xBm)?-n*DhGjakJ8JZmrB6HM%!|;U~(Wd`YEtkXAecZC+E>54vvKiM)UR02nhW z2stV?3fvy7!?wE>OMt^OdZJIpE=Yhe)mjtL#);-Ju;$fjKEAmkUoo-xnoqtV(iOdnLCCQ zt;>4NlDPwXTeJ3WbE3Ybv@jDo=bCk9WiQu4cD`iC68gy8k@Te! z+vekm@2MUbJ4?@Rkxd+U%ler`FojpYKmAPZpc5CQfQjYEQ&*y{0jWTycM_eF-rpeq9 zyJ8Bl^^iHDZKqt4HpoYP8_3)-&t(E#v$QYP8{gp{^qFfnw_cE8*;w12%{Z&r5xEabUsdG1(hiG1=#EDH%7 zgSq3$hXkez`;4(c3dFOLT}M&T-W$0i8Jl$ix!S#cEYu+v6Y|3!y0a={D4PhUX0`^tXbbiF2Bc3;Lry62<4{d>tc z*)#v1ZudDEKleR`5ev%@EN9@EL*&9tFJ#ZT#xUik6LOsf6(OT{9puKnn#1C-qR6|` zJ3<{TrjX=oX)bN3r>*bMKQ)h7Uk-4MQ)Ot|5fy^CC-}BsIBXh^3S5HYA zmARv9#42LpD8~Wkm#v8TYB@eEy4p!+kwbFD@U8j|9cAul8`g(TiITaaaGl+>)^=a4 zH+AS|x_XYx9sA?W*#;(ahe<12)-Jjf>OAr5z&1v_M*C~ho@}+pdgOgu!dSIOuE<}1 zk7f_2{)TPe9-F`h|1lqZQn+OT%je=vMSBBtM6*Dzt;p?WhqBzoJ|eeo(u376QI-jv z+oA1Q{<1Q6TzT1$sHtuqQ2L?udH!fxccWb4TymTWP)A(WtZgt{3%mlJW2$ z-#q=6D9Ho!kI;Qdk~;p4+(^AOGIu-}xt`S8EOW=`<*!K>hYncI)y1VC+QJsu>VXX$ z?Qf2JaAjM#*6B0a{A!;s4E?+dSvO(;WIXIGxqB3(?cR)Se{ag?mfO0ZPo^dFKB?tE zL>sMJ#z3hxtB?E$uf7$S@3}Fzb$h|(2Sz&qHlA2_EBgZw!VHvA3wR>Gu9%CNzwL*-vEvC^s)&5|t&5GK zpZRzsp6zP?S$~U zA_$O8jcY)+V={NVFWd^;4$9myymvS7FZK_#|H1mckXCX6vQ_g4*kzUvdEx3fI9GHv z=8lSd{EjGJoCtdkcZh>#_og5h96JOS{eA&?;)*_S<4!&hIyVb+g=$Bvk*j#MfZ$Rx zca$tq4G!$|K>4A-{BXy=5AyaS7s)1XnL8GmO(UP|WR3{QS&~fSc}tXe)a!Ed!+WLt z&ZXRRUN4zDGVhL~>z~Wq@yDk>=ymm0_x5<MGrq7EguWjxe>pT0LFR>n!k-Zyl zGvxQXW5B6UU2MDM!30>4^Dw?IX(!`h!^43@wAUsOP(Rbo)Sbg&aywot~y zcK04SS3chrWoGjEZ?g!QJ4(I{q8GNw++mrvlRnAihdLF!GN^OWcF1RLm19SJ8X&h_ z)tF5%E{*&k-G%L%`3CK;Gq5MqO_RT4_J|H+Yu9x``G=9wtksY)*mfU2-}fy#3w?5i ze-4Oz+now~x>ky2yDYXKUpgDg!tT6BelxxY>oTAW6FSYFw`ajq8Y0(=YQ%zTwMQO1 zpe*bC#t*q<;WYZTr_3E!hHRt1Uynlh!+-eFqP8*~PQnuXm*J9!-i*~tj4LyVYLC!@2}WTGN7vHrDSM1I{kV$fMp2gvVE& zAU}%^fT?4PgV2FtZm_6>%pGeMG=*Uy&M2SnUA|})cO2|+pH{W+gyr1k zdl-E;H%B%pS%oD=%hq`!L%7$NgY-v&V19R+}POiAs;K?W?-S zv&sc7VD7l^IDxIOsZK>3>&3*fnz8edKRya)IrKM?BU|-icSe~pp;JGjGkf?)P2?j- zbS!O{%pLK?tys(C?kKN&C>Q&%M&^#Lb5GLe_aabUpzCNlCnF9yrJWI7^GS=1-2rwp z(qd6Qq>u$^bV25hCevn;rSoL&XkO_m*|SOJj%^wv zWJl9(@T|>QwBM$0UpU-hBJ!+45ioFm0c5-Bap2nTZ8OoXyF7PzW-XycWxGcL*@>*i&kvshZ-m!Ii9c&@r97zuI<8J&A*QJmpamm1vt({p4Dw8? zC!0R15)(QzjytkxlkJc@RjtjMzUzeSnx_c6(@W+K7yG+(f{V-@x%I2Y$=p%9-Bn#^Etxycw2C2LSIOLA()0ki)z%yJ`}EBTlh(@I@ugt} znCM;?<;G*0!I)_>cl4;+5jtIcg!Z?{3;_39E0N9I27!5X9dh|OG4OJUEwu$fBrKdHbH~xZ7o=uenLF~Cts&ivV^Du!r8Z>OEEx}G#ro)OT1pOWzFMDesmvYk zas|-oX)@8O5fUNKLnfAo^MBYaRfmO^FjxbEDTg)AtII(x?QGXQSBMVp(I z=ASzrZA6~mJd7=^=#HEc7|q(vn1F2$2})q)qNkuwc6lc-=MNrKv~hd8Xy$x!6Y|U= zVa#{SJLKdWJy@f!rJ2yt*}Jd~rDg62dew-{*w7B;1&ftqH|F^v*J$^N7POMNqt>47 z^!c7Bls~N5lh&*u}II<_?=TZAqVs15w}O-5PS(UFHrSyO(58 zNmrEj999x;m1%`-1}Xl=Hqb|vKSVoogQ zDw#Xz%x<}Fe^hLpJ2^)@Fd_*KWur4QZwMTJ$6`=Jx(JrwLK#{ z%ek_F10SJ&jxvEP+IA80z@g#Ht6l}^>hqCezNK*EqF@C`G6{`=;aPED6ebXiiWO{?}fdIoBl|q z95X*SZqq$?mhaK4uYJgzz5`JIWWsJ@z1SDoo3lNkbk6n2`45D_s;aKYIk!cF@z`P5_EYf*kT!Aw`lO?M0!(@3O+q6?3!|mAG(TILueh{`jW5gW&%3PI!0@)qHP9ns7sH;Z5232Z zK88O{S_|AfX+4~sd5LRrkZ|klL&B~rQcRzcrFh0~H;Zrjb`LH6H!>Xaw*tc_E@s&4 zSzmE^*QpGL)l3#=EF8q}mgft^Z}LW_*(%LUoPFyl!#8|(ijDKPGQ8c~N!%xUz-pIw za2LsUDw);KMrN=xS~s*J0Dg%4iq&mUhcwg z)VRWMZICU0WmXQunt7XfFO43&BBsCh3jV?7aST7_IX-I09ENRHs`Gk-O&Gq{x;_7} zl_kSk-4fva0O_}XB;g3W?(+3F3&+h8d)@BHaFpX}@yEL)rhlNgT@>R^ zGJImLy|`Pu6T@BayNc$<&!ZLmSuO73Aa4~^;42GU#bcUh7*=uHE8eY5VL0{dHgRH? z&Y~h_Or?>iUNTa`dNV}-F*6wMC?6@RB^WX6G_SMRe(yGhhdO;l@9ldTZu|5MI?r}x zxYyL)7*DwsoWI7si8gsEjhAvAq19UH_R?B`b4XSQ@&*?`%p)GK{1MhY59m6UEE&1K)?RdrbNnI1(!a$wj0PQ)vN@tE? zn``5E#|I}3UrFF8@ zFH2ZoBds4e=Y}=QtQb$r_gAQryq4k0$!)~HWB*~8-q9qs%9eVEevO`J|3~T_BZ8KR zA7&IV{e!kxh=Uw&FkE+Ok9hg{G=^iIJB#a=k7u;-yBgY?OM(xt4)^CoL^DuJ?Hg-y>b>9eM*6^PiVhGX1*_ZRF1{3TIfwV>kbN z*m8!ad+y_J1{`Iz!yb2jS^JC3lSvER`7NF%ps2T^|33bd`9p>qUhm?4hSe~0HTWMJw^|NU3-HN_>tR-5puX(LVP0=Dr)lPtJT0PJfivgO0r_r&c1Z znanC3@XC{VN7%Cf82M4^9ZlEsq1Eu^Y;K8`GC%LSKEnq_Yx1A{hBAES#9ThHQR*F! zP1f>bJ>!`E{k4|-hqeb89xgcWDSZoA?R!k!_~3V`tar@(?amKL9Sw>a=i9mP%TxRq z#td6tr$;u!1{1dM%Wik)6*1p`uHcQb$1?ou3CEjUn9Xo@gF650`5K1X`nTu1pma_> zXKo_gFSlpoeOh@yMT;xL>alWeUcIy)=3Uqkqgo;DL(D&@;-h$}cN{1>kG>vK?`UhA zfnBdkz2m4#S8@Lvp7Erf9W4%BG=kxS0W-yYI-M9!9=uxAZ1}|VYdCKg-^)B1e%0Sz zJg3!#;V&0lMTfj0tarSZyNiEPdZMDnx=pU4Nv#*d*6Oa@uzqB2z5=X8NUCu1MeCm^^S-Z4c%M+0=f^_jp5=~EBSxcWHSA|Q@8LPWtSMJq$3f~H8BMuRyGH6AK9yI&Xq>d&>ntXMkSVQ)U)F88(xX!E*s$T7@IzfX zU+a}zA z;RCO&#qjrXhS$9`75m6lMMaFe^?Wh(fG)!i>?etFHd61{+`5lweM9OUmwK1tKWn7k z5%Dw>%epwT__OBo(DtIV9$t*uB9y2~II`w8x7%0h9p}S0!Pr8nckHct3|;20XLD0` zHNcD|3mKk%W+1;YTK?i+)m#;_Ut_{gCT7#3UY=3U!VGyL_<20p!Se_j!j zIo^;D7%lYX}48$aT+0aV6G>tV#1 zAa0ANgjI&@5t?(P-qG&KLiAI%Vet$8xr1G2O4om?j+UWa`z36A!-YPgN^4z)8yY5w zCswF3e5q=_cyL_{(`+@)Oq`?_!|+w*onq=UD~9j%a1!;p3#|50g>GWT)S1ka`BCoT zLV-s`joFUQ;#l*W40j&5M_kzOo8beGHi@5mO1;A*WvN*Bae}Cbk5thUNA{C?$B}!3 zMcXS<@9@ZMC5HZzuD_Lbd5I%eII{S(?~XXtU+Nt>gHnVyDbjk7$$D|`+PknA*T-7G z542_Y?(XX_W3Y5R@WzHbu<(_7N5ko!d|+P#7IXgAcs{btFou(L=JJ&%+A?g^b}j!q zBcADRf8Ub#vpdLe!zl;8DgO_vU1gpduiZ7C^^TA~?);9^BSBHu!&5GNo#SPOhbY_e z4ljQ&JbM2YKDtwPUJ>(n$x6O%uhcub^auXSEU9<+nQHL=n6F_mM%o?tU|Xqo{Js1h z=AzU)a&{eq{Y6sm_-xS{3h5bo1?M({MKM}R(s=Nkf#}~N^^R@_&tZ>LsduCfNyp_WKYOOA{#EK7`=1(%{SA|u{t(UWVwX*)8Gi9=uejc- z8^di6xr*-}mOfQzXrbN_SlbO1Sk28*tN3#$vy` z5uze~*5H}qM184uyy-DoT-#ad9ZoyDh*3FPS&UIt8aB3*ddJ3P=Wu#YS2k|$IRH;L zO6y_Zdx&{eAdMG3Z4I_hq~6hZiQZwhP3j$w65d0?k~M5@=j9#vHA7}IT<)R4=dT~j zaMd{A3!0?fv3B)Jezf-wrhoCNEqpz9nPIzuc6`q35e&=Ex$s5yFIn$6RzmAxQVILL zG|qM7uLK_iMU97!I`Gp}q-$S4f-L#`yKQ;J_}DTN{)@WQJ5CRr%db>5VBZTzL)F>PFmuxz0t zi%D4HgpvPV1MIZyCEob=+TeFtYw=Z=c`W8_%wX|($^?cdbk`F-m^oW%+LGgtCyHoVN^zSv&0cPT&)vBVxlf1I|;`cVX3=gZHB#u{=dWV`rAMx)Bsdr4DRff%~ zQtvp_;SP5CwU5P5-L?>YJ*D+fTWlk&7%gG{fMD+9Gba}FklzTNqjoXucOweA2CZjU zdrUpVy1qxL9WjU%qo8!ymT}0XJp(H`+-Od%V8-_AnR@b4ume7H1fnRs^71cp=g>4{7H{$bc@ z!4T09)-im;t+i-)L+Tv?D`WB4SVuPAbGb9-o|1ZpTTr@i=)1HYp2fH4-i>x)F@vs6 zgy3aT?>I308U*f;ddG-KKVj`3sdqf@)st8EHDK{7YUBA$VN&l{d}j_{KC~Shzjw=o zpQ$X}!+N{Zl7Dzhy0?>1=`K&IDKe^ElZ~c1@aq0peR94%@I8T?SV%#RF zcNiCR7DMk!z2l$Lqr|}3BU#LV#2I3|u@b{}Ta3lB1JXUsJ%!uEClS)U&Z$v*#q68X zJK*ylXNoTAyr}T!y8CF+{qZV>Yf8F^oi0edL(s{#xy~A^^2P}Rd^^PeniO@c34dYpHw>|H9O6ncg+H27JW~JVd zk;d`e4tHlU1DjXyR+(8${{{UmeCr@ThOgw>@^debW;oT}g%3XYne`5nB6q%hl5`J! zoUt39z#RZZT~8t%_?|)>!!G5lKPTRiddEH0Bq7zwk;PZ< zvPT~^Ylho3KF5wf*D}TUs1J{)H}kR%du_VZZbj_uynsIZVi}HV;O)3h#jY|uq-f^y537$-qddHl-y~T3{x-8fJE|bK2 zMrsV-88u%VxIxA+?_w&RO-81_%V}#dbo?HMKg2kS1Kr|T?W^g!<<_;D%#%y6+{O8J zdZ?&z=M!hqJ^BX2ey8_{ulE%&9BynOrqn8nikR{K%f!XMH5oouq9<;cC-shF_lJmM z3)Zsn**)8cex_3IPzrv9e3Jtk_t$kpYbU99Sj@~4Ze~mC;rzO01NkgzA7VUP6Z}p{ zy~8#B3Un8w-l6m}2hxpKFrFs+9(+!f0mEOPjN>(Wsx!Q0^&Eb$AoY$1^G$fOZSR;o&ZJ{Oo_E zXZd{kZRHEgy7Gz`k1nhDpN?Y~9@+%_i?vek(6kxO#|E!v99`P=)18i!M)`Na}eslpZjT=1djdM2bW$_k2&*1YNQt!AO{1pwOrQVUT zp|g0g?F<(4Xv`>aZKBjWZWzrF7d1(}!=}kdoclI~)pGF4HnFAAo8gm3_KGzLy%>JG z%vF3IpigzndGHf{AUR>Lh#Bi5K+r>+7I*N*zM2pqp;!ndF zo}@HO9A(HeT%kHfY`s|O9oC**#m|eR-r;Kb4aZ-XdWTSa0X;LM?f$mQ5H$Mt+0>M< zQ!%fUrFC-hT?6;Dm$ZIF`4MROEA@_+c?r<5lL^ZeKcYR~uG1Wb+uEq}i_OO|{B^I3cN66E#J~@D8t!JbNTLi`V4RM)#M*$En|4K zuQGr1-)D?}U-<=Fqom$Z{vi;Ke314756%)haKVeQ?6M7pofu;M;H-PdPWai5>=>ocsl&rkRD8UF7+ zKV6k$|E;L$|FGo3|M~ELKK%c+2L5~RyTWlT5B5%Vag}wM@LGMW;+^E;%5qEGp*EP| zepl~c#h-2r+mHK!8UL_%n2RUwwH2dozEQl-TnxU`N8H{00>jBM8sdn@Ji~pxG{q-o zR~7F_7h9KUi5dGl2@3omNn3omSQ!<#*ZfJMwV@lszg$L(+v(g~F^W;3k!%k@O$E_Z-+|RtU_{9$f7$`J+mg(>&3%)Z?ZvLLk z|5aKFit#G*@w|GPz z1;w}`hhkh2ugIam3LZrc1y=A&Ids^V;{QoJk?cEO3asEza4GPA+zRXg=WhPb_g622mXg2{wFX0KYIB8(aHapgSh$R!97DHJvxeUwp|qC6wf@Dz9+!GgTTIZ@bC8# z6gBaRe-v{SW2A>+#diVz{RRQkso?szE(JHk+4gM&E|e_dH7mzMsMt+$u4lljD$(a#il zODX3J{TxEIZ$@2j&a&vZ^Pf#OJew^iVDBqBaq>D&xi6s%Qi6F zLvZ^G3`S&Byd*nV=0}xT+4%&jTd3g za#JzP_#@0*{t%8Cn~It?Phb%L4i3}YWuLA>bmI>=M4VQO_CwZ?GDuiP@x1_ar#3(# z@vPrj&UNZ063d@H7g^8pg(rg&E@A(UA zXzmp6EjZgH8A6FO$@eTKY76vtr>3IL(tBt+AqaYthKl0X`0D&o_)glcPWy)OXBWaQ z(!6rTA6zl1J-i~GmAmS&-85IO3u(w$BgaQ4zD2iLV=Crdl8JNoUleYyGZp<;wVw@={|!V%7?7^QI=J5Wr~_ZR5n`vMJVZkNTk(R)EE zt|ZQrFHYgX6~A#B<@#8>8i(1|;2Y9lIYS+w8+(x!Xwvap`MVRx1^ue|duI&{7q z9jKOw=?>fp<2u|&HO4Mz4?Cy)!Fb9$LSqq(S@{i%h)4V4Q8=|V4jYNzJLv{2U2_kw zk%w`81;~GY7K;hjO-P0f1GeC3@^k92U+|-9C|1+lS2O>Deq5Ark2ve}o8j=@;F#%@ ztLCVT-??ZyH;gpowUP0m0j`iIou6I=i|4tZPhO1~U<)okDqtSv?elN~Y|d(gX@q0H zedZ>tk@4LrX2udFuH7OTzlP?jeOD5CJZ*&e#M$F=vf$uf0a}#HuVy0p9M1)XpQ$74 z(0kBFSVG!*KDdZC$3Fo-(#-ij#H9zW!VaqCAGded^2;4;sK(wCve11M2d^ma{kdhB zn_tQm6HnOU2Hc=NlWR?0T~n5cqvLPKgpr38t}?OuXOxgd*kwR71`Somp%l};-Cz2< z&aGHQbJzaN$HL!d@d0rTpOuXJeDC2r%Jrl&2F*ss;RMpqr{D%U?)rvrNZVF8ip9=< za0_Yn`nmvvj@O~W&p7LLn7CPv{iw!*5&MK*v@ZKo?ML0J^rPms;2FjGRJqKFdNrs; zUNw*E4f*s=mbsMIWxNRl&rU@H!uHLlz{39p_N5s8owp&b{cYS#bIns;K)U5AL}#t`xW5@NrEqj3*6Cyldc$#wB4TY1?Mo0v}GsMhBDT41fB)?%2nfQZ4s5 zISlC80k%<%c?NaRF?$g_r@Wb6|A1=gQ79oE!@=KR{-7Y}NM1#Zii5w#0z{FAqk7!~ z-yO;Dg>bFYSk^v!!<9C_8TA{W)FG+`FyUEQh@*Dn9W0paATMs%Fnfg4OQ zE7!?HA+f7qLvwG;lZoDAQv_||)C_7wlgE?jp024l)2RZlrQ0z-jn?F1$JUo{4QVsU z`GEbtKg4j-+@x#W?1vgJ)zumeJf5OJ6Mv8g84%LDjD#_=vPk2>u3o0~X*q(!4I{4~!3O ziwZvzZ`47Kii4m*HD0ulL+0al2AWj+#EUY%;FcffNS=gDZGl@Qy+MP#8lYMOw!chZ zI_15bR|s3_TbnZoyLC;4fXBCCB*na0`vSW6dI_#H*G9YrP0vzcG;wzCa|&9A{)S6>8Co4|0W;E8e%Y6sc}2!QA_Vfx1>$zc}Nvh$p)(05oJ7*UO; z^f#m<^NZmL<&E<*#AQVpP)@a!&hkLv_iN}wUj5t}gr$jh;XQfS>Y{)Z!_R_1xKD60 zDu-D>SBmND_6uuw4*|utxP9<1-h1$n6Nt0HtQq~6UozN4xm-@jL|@gpf)Qyju9l&XM3!Q$$^o`E!ms|oMdep<4Atnc`W?Qlc!IiAJNNnlHd%Z` zEAr%{%0)aj^d}A?uO>#=(BFDgB1d_9Xlderj!ih5aM7EO!j|$DXn&5?;G zXl_+Z4^G3Y5eE}zb<9_;U{wVUqFfCQlc9E0F59NMr}l!<%@4SVwB;_l1ZFoM<4e-~ zdB`JZ$i9M8sg~JI?;zoz8!o0A&CX{*dYV2yqP$sW%HY|TVxf{e>F3%2AKMrRs^ry~ zfim7IIMN`EJUr(l@nVdi zyoNEw7<9=4|57beA~SIP!ywckukMGw#y_b7=8=cNNAIFtRx;is{OQvfObYvja?&uR zY7=e<{ELcSwk>=xPT$>(uZi>5s0V`jDVeyJa{Zj)6H`(w$K9mCz1@87Yeqf#lD384 z{<~O3{!s@AxqtzFPiZ$109i2S9V+JDfuN<=izGv;P4urrNt}KZWBjeQ_muaxLH^ z)Hm$LF67nEWk2E1p7E$lc`wbaggyKRVF6*?K~1o4bSr_Un9b%g{`s9=Tp-Q8NAH>8 z7pHMb#98jt2+q1%(1UVqrau(A0rt#K`??&s7H|oyN!!&OAHZt!Blt?1ub4lEKKcou zO0@)gUjf56Sztgl+9kPy!Q(QxOL;d8&9MGYD;X@~$C97?UtMmYgN!dD z4|n-Q$Mnu?g3E-*UWpc_-Kc^(((r!!a6G;yAAZx^ms_`^s_$obOPr^&e6V?J47gFQ z6IS6^*7XLsl7@`5ID9+x2zZhwqgDZA(2E_mL zm>hcttH!LR+I23-#8scJ3iHU5Zv9&@(!MXYC9l@xRO2t>b*MvmFMAeZU7aT`BAjyd zD|TNHivLi|qKxO*{`5<{M|1rq-ol(QX((S!$A>#kVv+neDp9Wb)<&5Bs|FRvz=1t` zqHwhZ_mDQh36Y_Jbc_2!PoT+dJ%rm{|ijf--H#U!94vJ#FwaH z0nIIc@fTFDMF{VS)9gSq+??bY<3YKec+&a7pM~5B(qNuTeSSv`cbK$Ycv%lN{xe`U zY2LiO6mnt@Fh4VOe}KcuYcP}e6Eoj}w*6DsM1Ho@e*hXkK7s*xGHSOk3^@1`nn9V8X;ESVFimGLc)hS;j9RKfUyt4ElqNkEXfm{(Xe=7L8C%ep+Xx z3qrRFXiK>=>$LDoJUt&zwPcmsW4{R>z=5>UAKl;^wZ~9Int$DXgxb@uKpU#%ol^o< zs=C4$s|~vZ4;(5zo-|t+D$#InE<~i!5tl(0Q4- zll%<7G}_>Brxu(@o;Ys4&OvN7{w1A#_4`5I#zLG(dChy6!pf~*aXI0Oi%x^}rRQi& ze)jbVg#o`qFrMZvO?U~zRA^n2p8@7+U^j0SwvdLKV~QYgaSx0o4SU+u!uXc6f(wmj z-)RAd8FQomlIAW~W&F2ehqxM3I>zoIhg+kSU>MaXB-MiIhb0h5dB^N1hF7zXK_l_p zSdamY^Mhdq>0B}HHEb|OP$oZf>hHkE6<@%S{G2oT3?#KLfS*)vuS4cwl=BzzX>RXv zYOwNbGo%pbir(Rzo|lZjM7e$s^)QG^lS2^sS)IIC&(lIzpepdR( zc+dI(t}l7=xxN`T$ooM)>1+(DhR8RjFqZOmo>B;^*H6Q0!jTicg8W-3Y$ZP(RzC;F zj`X+CH1|Y62=JHFAcg#_7fyiQsv@W&4Ie#M!q>sIpje*;C%eP9XDx7)#)It6aARp* zcBJ^gzJ2sfm&euk?a5tc^QLJz9Zw@e9hrx(Lz$~)`$QXJPi16qh@{N-aPD|rP= zNaw)w!MOF|9T-i17G6M1|Kbhi8(jBUhOLH&Cs`13hyIdx5 z4!hBeVaf*#!YJ2mZ<%=D*)jpi&!P`U6O`bPC77d z3$074C2^%AL_dCyCuw}7_htBXAqtf#-eGbi$gcTg68V{0lK^|3IAceuarTC6*ziLa zeJSte5#{jge!d_h+%v5K9OEVkMx@hgoQyAD{oX)_{Oqt>#@|}?oHHgrr{8IUhKP~$ z`=>rTy$S+6EFqgT?EjDlT3^mV4)OFW`UK9?Bj6F`I%W|KqmRc!0{OW@I}o0Re}|Ri zr}@OgU}#kW<4E(*9dkinqaNN9k5{S;{t1=CM&jpVwsKKtX}>{!CcDjusrlUua?*3o z^M>Gkv>LvWPVdNnj$;b$*{S{zpF#d*_s_?s3SoS&dKh~jmx(zh)h z92H{8Ppirn+#T5&<;4H&QZ3G!y$pRQuYKQQbSXQAtqGscO2Ecw+Ery@VB^? z_*dCphjEtoF^K&9q5llFIbOgj()0Ih68LNE#1Eu1w`U%B*o;99$~*mICCuypM%YMr zm}L{ZulgOcpX$9~E#u#89n7^OA8IGdc*C zCG78F#zL8 zXUo=V%+_6xLn&`*W&x(m^+F56L!PJL9_uhXM)fZEDx$@~SX3q-rYnbF-%jZmM*ght zc>*hM7vXo(FrwcI9J#ud{obqFb;EUEThNcjLpGikCeyl{Nby7F8$Vl~--4mUGwYvY zT$5`pmJ+|Va~H@jDZ*2fS5>|YvTvtjd&2i;9|x74uh5Eg%E#P<*(2`YYSMqcw+K;V zy-|n!+|()s(${RjXsUPW=>jK#IbQsSBSsu`?`x5s=WKbKM;(LZX; zRg#~j&*b12)Wl6CKih7ohe7gB|hzQ}71%yFPt5x(aY$IYVslsDDe zCG)4j;0ZEbjeKxjHB9j8+6V#UPe=7^;ksKnq>_fw^;1yZCWo!h=EqL>mwyk}Y207a z4D+D~FHk-&;w7rLDKZR>zPpKI$cIs4ER;Pvj=tp2(&_0i%yc<^A`L2E zilA_2SA0PldfC;2cG@W+n8tH{w!q7bs3)^2ejxRE+4tkz8RF@Y)&jZHyFw=M_cgDD zPfwS_5z0I96@A0^(s58C+{G>(UhcgK&ZKjn<|}x*QiNTk-!Cf+n)Om(F!?D<^@48E z1#pk*9UHJ7EKI8*gEaVS41{Z6=$;7iOe(#_d7P8+x#VY?BvXUu5pw9do~|KVng|VZ z>p_G3Oq<*y>@ySV08oY)9MCxO@~0pu9JgtFUYP*W6CRx6U+SR9vP(0M(mB$9=D74i~19 z4^zj=#G4Ou1W)p3TWtgWc`_9fNrRqAIWF10kNNrdb2f&$`e7K27q)qiW-XDpnBot= zi^Svi6Y((dnBVckx|(eKLi{aPolx^!IUc0EhXbZy$bd%dO88Ho9O00zOgu?^ zM$vJwGwJv2n`O|jrwLWaPxG#?xuf4I@fOuPvUW7goSBE|WUHS{s~gpI`WJ^nnb z@qdQJJ zncWH;0O`=3aAN6kd|Mg|$4Teb=k#5?i(%kF`UM{mCm!^Ij^w9z0j^)qgf-?E}c6>cz z*SXk*G;8lK!KEJ#;TPiB+%^+OkpG^YBJ<;yxasBl? z3?QBJT3ey2b`|!ayw@j;!h1nYXh(RPORTV9FMTVE>irmz8pDm0iA%|cYZFFs{c{@7 zk^C7k`zLo-ryO69hSQF^U>K0i)~C$?XNZkY#7G+VOY{ToXe63byvocdShUs;Es5t? zSt1-McEniX|1&BFHstD{Gv#%7QVw~ZSwc_3$0jyH=t*_q4C!2BK<~hm^k< z;qA3Ju9@mOyS@pUo{RxMsyFg!C77A)gsc(n3bH@S?Z=ijM;V*1&eh$aexMs~KT)OB1UZTItzcutJ zwri7!7p!RCrSFd)hvwor(y+zS4o}Um#Gb?-pEVZyIX59}rgftCLP)ZZiH(%Y=67&R ze|tH;*iFZ)*Vk}M7u2Eu4%#Cm{)#9upnItuMubA&RUr2epu*gOi`s-+}|4tcSd*K?FZcF}WsspexS5Q3SOV@7He` zb{L!imc(xx>Vb0#UW1N3op(RDfeQ}ZgKo}rPj+<-9;JIlz4y`YWy5Dwy|f+nQOx7$ zJggZr8iwwrbLu0NC@y%?#eBqyoPk2YDxI%=zcDWYf3V)eZd65*`3a> zW93NyfC4MVYKv>ZlHyYm+TpuyMIaE5(ykR~>6r#4gk9(u@-v;AdsEE9P9gZ#Dil_^ z(e`Z-(b(S;rjX8h&97L0+62O>_N*<1xWm0S9HP1RBdhWCMSm`p##?`E#=Tbx^bbH#k(7AO7ItTNixvw{l z1Y2l=ImDUS<^>m{FXPvf2Caa%1_H|I)fIFc6+TJm)l?75Y24vXk&seV3OvQjrx{@H z<{xmLcyd$SP>gv;=YI5CyLJUNdp?8%lsBg3F%B#Ag&e}|8b9DXH5&+|m`6e`E?7Js z0%-1>R~5K>_CFQ;qz)TeZ`P_0cPHV}@Toi5aMm5CALxlN;rFsi>yJVM(-e_$K#p;04tr*)Fh z^D~z;p#uF#gV)Z9Akuqd73-?YA6r;!^8rg}9L0;EJpVCc-Rj(O#A`K`yppXDg36qO%(vG0_x!f;Wthd++067^rV;_OXhGIGiCf)(tr2V zt(Xocn&2C8wq5^J@Sj@+9m&tZM>X(nNgf=fxpTj4L+8$);V@~K_{s;Pt)n5Aw%z{y z;kYg_0G^YEdrRUm_rxJcCH{WLzT>mF*`P%6ll4ll)9Gd|jCeNX)S=fAQ!bwPvlq$H zrE6L(cZ9jLegCM?^$ZU+oI^2rv;N`@-A#C!=JsCo3+EY}K_lYiKP2O6 z!@GEhG}t)`sI}rX^0clNYX_lyeg;mU@s|ciakT6YPN4W3=N4d(esy@6cziyzMWyN% zJV^XXFZT+qO=RL7$~$3;ib3`HW{f1<@$z*pd}=j%P>kcDeo*(Y0R3og-dR(qIi7;! zi1YQ`(~$2f;wZ{huN(#r`){HSY3O4SOV{C#;RzZ)sh18WYnS30ivJQ*1X{^Ttd>r5 zYTBNcv=hFGtYFl+a3@Su2)0YMaZ1^h|FlQ$lMPwQIfOZ>aGccEu$ zir^(_SUP4o-YZUnUxYWh9!EpRSa745(H=MPO<^eLk%nk*Ixn1f8Ws_!VPXn?`m`3F zF%5;N`MD2U+rDGoxC9!vp>Ozl7k4zUr1&~|_QUg;y`VxoC7CUFa%Fq8ApUdd zwK!7Us5E>7+A1s@QnV}dt6 zivER_lq-AxM*M!}FCL+}NeP3{dP+0;(zudUn4q*uCer(rMGdcQF{h`>(Tgc-jZMV(y3pSVR0u zeXpS7@rSUD@+KdDjJfs~p@H!6Gt@iQ?1B3fW4k>UbNw|TnC8koD)3YCN3J(PO*;r38-SQmpf=xL-rMWK-YGZb0 z16C3~S@}(f>mU=akcM^31_+1MWa19e@HMZ|z<*yO4kylRN2!`Tg^r83+qla+R_6p{chIaAqpxnY0=MuksZ5F&W*Tc^= z_wKSX7}2dzNFnSop#lCnP8JL)Ci#;bt_^x`P)>6vYs>gw@|WBR;%wKq2`-Hr4c{o& zyM2|gaI7`^eHDEC36q|jhcFty5RwGJlkS5i#dk=43YA~qzDpTTr+a;S%B!Ue=}=FLI(Gk+$9aw&6HpRUmvP4QW|%_*4Bb z6cPXQao;hk`&{Tr@n@?4;E6#p2qB)x$T}>@Hs>A_{~SFzW+<7(v?UF3%VnbBj8MUh z)|KJpX8f$BiYqDR%D%stQoj+;(A=#ze&Mh?-nfW3YbSoeu1R-rCuvwwEMP{?D_low z`($(w#(QMoEE@Oxaugk(7Nai3>waH|Tv09h5|6Wbdo;>!L0jU#tmZ77Un>)RDDV8@ z7X4B8oACqTQQxm{hE~;hfnt<3`+|k65U0>Qj_%u* zHs8elq+x6QOStKN9Iw&1(zi5N6tE08QG6e}BG@*v3!WmLp1o_qE#kPKMf`;>EpT^! zYyAEy|%5iQ_3tS4krjP=SI(7SE~_i3)M@;8X|(q%c}wpUZ3Zpke` z^4z5K1=RO^0hei8XlUJr(IZkpP8vE5KLxJCf5TbQ@Y2i}bf(mRVxL(xQW+|`w?Hk8 z8zrCTI#KQzS_4_z_USJ=(*jYXA+6I9p>lF9j3oZ+Jv-y->qYQ}=Bno}MW6ZUkWIL@ z@EGndhy^Q(32l25eJ#RZFllfeCgPb_r@@>!VS5VBR567($|bxnz~>tM*xJ5hSdAlV z12~b!w_R#RpU!Fqt0?|5ZIgKhHo^qr@umAOA&qU(p7=k~^FLKX7GfUd9rUvp|IRsz zuL<8M$-v6{H&B&gzGu9qb1ngIlKw$w@8XW2WPD4U{msr`k<~A3pyRY&<5@_R2F30MF=foJ1OSkBtV`3Ln&_?VFhT3FMo%p+3d*X_F7P zdTO92%?({&1^MtyFeOemuO_(urY0#zLsLu(W8$;_V!dDKR4p(qPXx#E#J$SkC zFpA<|8kPc&@t(JQVS&yQbfNgZ zKOR6^`4yCthN?C1ptqkJ8WX=un=CkZPao50F7_ycmS;u6N5Wwp8esFMse(Sm6u*>% zIleSVp}Cg2GTv?Wb1r~5=jt|r^0$#tNV)VPE5WPW5)}RGLW%iMH?BUk`=&$5o(CG4|O*F~l<;6z9|tCR^}s@@LpZ z8us5jiyo_D;4y8xgU9aS<;*~+BMo7@;_!ORVQ3)@vZQZ#clAFofa3Q>{J}DtR&axO zPSbPWCk?i7w}@YBq#V^p&5tRjy#44{ujNpP;6PYwNi*7J4McN_$%^=kC!TGLqFr?Jl$9KZYynvjMvQ^fJRU!fzd?Oij2F=BKE8q>J4l?N{0Q;ahxevi5# zRz%k_9?r1?j!S4k3*vvk?H4NO7}uHdo^PF^pPkT*1%%br{5ad|)fh}M7HPe~Vo@Om zk_PJ@YawspR~$&3vrc$I(}w5RigIx(p`hy=g3aW^iqkLQPwx}>h{iRX(;(~DaFRH=tULjAq-RodD!lj*0%7F&F|(I2DEK+JlLr6r+u-!-E2z*qY5(jL z%*iN(E2QCa;A*(uriQJn$Xnfbfi<}Le^8{18ziEj6t&kQ-A`STq4hm^> zzekt&eV%qgr@|umKzWZ`TY>{Z(jlGj^p(eOhtVrAp_mT`f>Ap=4BC>0)Q5=NYApxX{Q9K2xrP`wLLbp+D;#fBRLV+07vCA&nQfHsfPWEd!q7+tRsUxnL8#_T zc%lG)Dt5PGU>7C^#_fByVqjrlcXu}ypol06B8Z6r1_meyx9>y&MI{s^6$GTDM39F2 zz1bgsz0ZE;X5P&%x4SdnnQsMj-StXylykVnyy)}>Bc+LaZJ)lcgX-*Z9>T{H<#Ze*XvVOMtYk*WoDFe_H-Y?%Bu*`bjBp zmdp4_+n|TRUvT9dOlBHF@3?a4!*w=n5+XVGS7BFftG-R9`eTL;25=6Kjk?Gyc9p?- zK7Pz9S-$Zi4;FFxqB+A!s{Rwieejlah(?rs1c~eauIEat4tT?GZa41wOWJnH8TxUb z9FRllXXtK-;4&WCBpNqj5QzJ4qel5;Jn)-Tlk5CFvYZZnZya7c+wsS3^DIcG|E1tSCOWcLa z=WWcULGP-Acy7;KTta)VY>}L~{)f$Vv}4Q=%@=NW2#+zJ489|u=lI&DN_uCbPusc7 zgS0|=dvF#S2^3!T5brd;mxSq>gxR&t+`_*}$w zc>|dbZ776uh|!OMrhUz5AD17SlnJxL8!7M9FTILjXruFT8?HZndKGMa*4nR#&*>$; zcl;@bXB^w zRE2h2e(kx>qt3`YKg2l%wziNbTr7quT>qpMb;xjF7JTJ)_n4c~IK4QC&=#C4Tc3byHL7|G?` zKj%V|{T9l&)9~;F_?~tRwsHO4EI+{WQND1F+a30WpLLDG;VZ|ht~r52W-_>NnQaHQ zgHuYr^1nIhMqhaEQx2WEPG|Zk1@%^86K-qyfI@ZoKOHpV9C|hFAP;gWgFAfuP*|co z>tCMon_yMTm`*JCsr**7t$UC*ulfW7xc)JRu2S`UZ|KDBhV*(#BRjjmL_RNRvqNcL z?Y;1m%XHe9MD?tVl;5b85r4=yAzG^BbGoKgIo%l4O!DJC@7R=ovqNjj4ty>q@O|XO z(MVa3iyIVE%$M2?(uVB>s>vfHhULuzA_=z1MzD&*rhDvWA0@}`$uzF&PG+P3*4 zX*h=i*IlV3DUl4h{+DMD(L=9162H~WHw>qlo60DGA>3AWKSPL^{r|nguI@J2*C2v4e7wQ=%gkTBqM4$6 z)-$Nl@&*m%dfprjf!q_v=pffWbXEe?o&d@{>&UrWXxZYA{FZaDdRYp`PL7q^av482 z9hjCsR^R0O)uVad_LH9!&UMZ|Pyuy}yMwq_zUox~HU~B+tf44xhV;LMzQ2J`hYf?CeR}n`v%W77_NIt&_n>}Uyo`nEh#&(1Ol^Uig&l0T@SJ82o zNaY#hgta}Hs%5a_9BQ0@Ob2q@U?5*tv+ROsdX6P@^HxJ*^Me`GOoDT#OL zxU=aLP-;iwS*!m1Z!}}>Lo(vFmWtZ-{ER=m&@Yj%0c*Z@v>$#(vf~`)Y^{Pu z9U4L-u3ta12s(b94X?Q$JO}-Ts1IjAJbUl*i-A!e?}0U!X##Iy$OkP<<{T>T^B9`$ z8;s^UyQZ9jqhm9`n{#N_dlA&X_W!-ZpmQr&^`;U&^Ks43Ytj|o(_kN$_kLSGD)&nj z)Z%(>IUkTm1Qf#}uAl1Ermg$3AdcJp*K9g9ToDJM9B1~nrd5N3z?jRZ4&9;HC|>8l z`LFyYlh@G;aF6SJEq$fVvCAQg+w%F9M(TF$m3JR~&q4~*dmxE-qC*oZsU-fITD-4W zOi^jS@w3ev?w`!5chqsiD`6Ki11(NJk`kBygT~Au^v5=!{l9u24Y z_^ZORaPDLP+}gqOIRD(CnX5ZEGIw#aEC5-b z!?D39W|z!XO3haBb2!g0luy44%nabhwSiD0^Q~Y8FuD3YXt*t2FatPxrzK=f$QH~1 zrp-11qsb+L8Nfd+YCvWqonQuV=#dT5bY5f5%m7}C8>KnCvr;evIN6?)VtgL8yno)5p5}rXz^VQjRIk{Um>Iz7u2JNi>>-!|T)6)=?Xi6$m;v-~zE2&x z#Rz5qGhf(HQ#n&G1NbG{jG|nM1T%mI(3q}It`f`uu68^pA6u@{GBbcpc8q#ew5Uoj z16Z;DoOCmyNH7B!Q>zgKH26(BIERUw=YZFo7-D7s_s+3_X)E6lGXr?m^FBl-dQd6n zu<873n9F`ZW(M%kt|-`JyO8d1J=-^BfYG#;#LNJCz4!;is+?tJ2Jl%_B?Lsg^=D=P zxAXNrWd3o9nE_nYhY#oE33!Bx4m}-Gk}KU z10mj)1T%oUIz9qN|F41>z}Y{~L+7UHf*HVl#>=5HxKJG zt3qZ5aLwh>YBbOZW&qo5+bGZ6S0b1JOs%X&H5_9}+yqcK-9LWD`n}*JonHj)`J9RYRcd`6}KdY}Ur3sD33T6PGhUCz@i6@Ae z0em<42jPR8#LNIjjeJiZ_xTBC0KcAkN@s_C7R&&i{o_FC%s`6kYQeTm)Hw97U z!vr&c(QW>~D%S&o8Ni6mKfzdg6_^>oNo_uXwdqU244~;Jepb31DwqNEN_7UDlO*or z*yzY!IQ{sKUeZ0frg9EJl?|nt`YMd(`q%i>mDMxL1v7yA zu13nnyf&4Y0UWh^AZ6tz0W$;W(PB6Ctq28X2G9+iY4)#|z{~*p70P1Nz z(u#sZz{~*l2~VWMZAJhy1NiNH9_4lVB{4IA;}(}u(eUmPGXwbbr;ZZFrf8TM!1;qz z{G0wx9>C>|bIa+hO&`GwVAHXGX~M~^f*HUmTT|%7tINd906vZhC$nbH1v7xV3w`NW ze28EMu#&D*vvCQ68Ni-Tj#0t-T)_+=74dY--BQ5};K6l&WW25u%m5~tNOJHvet+QO zlLmOHtxi-3W&m$2@Rt@%E)dKB-n`lkqLY3RGXr=gV?Eq^{F#8;E$Qn34=VhKnE|xQ zc>;es-J(z~<5&2O-?>iGWBzO#UQhG;(|BTLfS2UvK)-txGBX31{i_5#y3CWA8Nj2n zbZ~muNi{PAycdoN>koY*F*AUM4S9Xu{f^2xZ7`t_K8#-_m;pREEe*Q5*aI^ISaL8D z_69x{%m8LqXdt$BuwVwz{g4}&H;)(00Pd_~1$nwG!3>~>%M`e+Um}}X% zGk}-Mw@PITdA$bLIrL=@%>cVf!39FaubtojbJ-iWbZOE;TtzhPyHaGk}-d%_G%@ zBEbw`v11dOG_XoA1E`yGK_0^Q4rT`M(Jigt=3P~S8Ne9vaVrBrNnngjUutmho z0J<7vK;^Ag#LNKF@qb{Vag~`Fz`mMFxS+}LXJ!EVELP#^Sx2NTT*fE53Zy5s#Jd~L zh%ScRE2jx&0L@)_?}ujAz{~&wKP#pEy(5?boa7Y0RQb>0ofM{1v7w?+}p!2s1(cq`gQh@Ue8e>GXwbg;9T`_Bb{IdaAET`vWHuV zUEF3m8U5ASuij&fIZILrijm;z{~)SYpS92vWvjX z00v(9Lho9x6Z6#QwltLvxOV|&2GHqp0Xd$0Au%(6t6x^o*<@!mGXtobsM5BIpC*@b zndp-`S_%JTW(Lr7Z7H=494(juOl^=$MURdXGXpr^?FX&xbd#7F!0R6GNmt!ZFax+x z_moC{ju6ZM8Xa|{t@$a+y<^IQ%@ls|uV4mnq9t)ZQtK( z0zc{mGl0z>43Q**GQkXBjh>lOJL5e1#&P`bk?`6$k(e340l$vGT$c~T%m4;Hx(3U; zdl54O=#%FIUS&=c&u#sz9u9+s>{RX@sfUtbfMb7p$j9$k=ELO?VKOrVy!U50B)J!B zm>EF#PAa@}yuHNC02rp5zGJ{n0SM>{Qe=B0rZ-5oKE$~ z70dvB88e#XL#2Wlz=<6SFM;b;e`00;op(KfZ})ByGXpr`^gF0obds1E zKwq=((5n^i(af=BVK#JMsFR8Nyw0l<=zMFD?84__FzTQi>`?1Chc;#^jJ13uF*ATx zeJWw(ToOE3edN}dW=vWo>XfZg8Jggt3hf*HV{2X;%__;+e0*O}qaRI|aO zQZNJfX2nhU+~)u99SxSWrZ(m2pylIj<}D^aw{O7A0M6WENA|0$T|G%e`B6t2Jrr@OsWxjmY5kpmu1m(E7P5r8NlkZ z1E~I^0Kp7kEmwE)UK1^t0X+HrEJgRq6wCmoEuBx#hZPBC0DZEX((cw(f*C-IW|!or zeBWYb0L{J+_TOYvC71zR-0rlrc~G%n2GD&H!a~hn?F*AT?A8A2=o;6vI5HiM6}P5yT>q@;|6s(y z8!|Hk*!NZ?td6L!VP*h5`F@^QxKCnc0Iz0O!Rm!I#hekE)hvM;?WPK507s@|LA^s( zz{~))*2Y2DCf?_Qb9mD&2%PTAf*HUr`i~))*HADsfJ3Xgf}7f*HURpJnptaDMLL&-T4nCAaUG1I!E{ zO`kxAR(=O&2GAqqB*k~;^~iiKEc9+u@bo9Z%mB{6=1;z7E`bG?cN@a*9kbU1GXv<_ zD3vCacLin!uxLpErJ}FI%mCJLs-U?hcht-bpff+;wLd;duE+JCbI{SEi+^Qi2C&YB zQo4Eo1v7wmX5>;zv*X0f03NCQLB^MF5HkbVuuTXRo_i&j0rWlaj2t&b2xb5+>t80j z8_L)n`u^HN`V0OFW&rI9dQ-m|6@nSSWv+qpRq!y%w0W0u{~FkfePq7|&<#GGFgYJ?7DUL*4B+84<)Eol$;=Gk3f{BG(y+C}%mD7G zufl3e<0NJVFukA*y3t@U*NodQ|ABLc`vfz91#OdH$Xyp;W&r!}`k>XzUkGLZP5oZL zgrHA?89>J}7r5#EQ!oSgDPupF4g4dR0qhYz6pH0C!3<#5_#e_gl?s^|z@Uk3q^A7- zQ^`5p>sY0k;#4k}0nCOl+4UjsiNp1rj_yZ8uO@>#*MIWH4hjno17-&BWtS@y9p(ef z4B(luUUYZeHDG1{XJmY!4hxS0GXq%JDUpJojRIx{@Is?JI(0r%VrBr{8kEtSy#pj> z2JjuP&+cCts$ph;_smvltvbAsnHj*UffaNltEXTFQ0?=V3hHha%m6-Z{)_yb9f_F% z)VW7czfR8tGk^!;Us1K1A%YpetD!e&jr|Y74B)@StTULNOeJOpaNwr3 z;BxQ_F*AT`>RkfEpZ>(m0PZjKgr$9NQx2Co+3p<_+nyqE9*axkp$jGi)XhQ7}V;lkVH zf*HWF%ryAA`vNdCfEMGwfz#KXVRkOAbhnczlGJ0e*)n@i*kP%FGO){qt+G<<0-^9gFL= zqU)0~fSCc@*nAP$)rtaU2C!f3Idc501!e}&{l)_-jl2iU4B*9KZz<%fGH!_-y<;dh zb2ex>hv2@ysmqXtz{~)CN##AP)}4`<8Nh(eRWu+Y!;hH(JR`=9&fCk(4B$LtUOUr3 z8ArwYmPOQJ(Okg{U~ktEEi*U^-?*dQ?>sGXt0s;V2jJ+#)jr_&EEd|KFQcf*HU^n=PgG zE0pnM+)}R|Sf&3aW(F|LWd=Ok8B5FzV6O|O;oI%E#LNIL8+H%AE_q1I4B(5AS~ywb zycoyEqr4uo_Dp4b8=qRGga5R)bd>Ag(&isjAAVbAW&odBR)RZq(l9fC{}W(M%sz>{QQ{|=ZLz+;DQ(c+LN zz{~*l?d?xP+Bkp>m+u?#nS$(;`3~$yzv%6BWgY~7b}OLDazBZg0UWrmg32Fzs+k$U zN>pi&^&Bg=Q56P0S3SaSb0RYwAqQ44}!7FwnXw^IzEVYZ9y;GKd`bxLf^vSoSzluFmDB zj46k>?zLoQ1~9dy3RAx|mHfH>Q%zOaV{mpV z6U+dPu1u8L@q8jP1Gs%d2T8w=3Yi(e(fbQD?fl9GGk^y#e3Y-IEAx{0{&Zg&nwJdD zT)(t>JGB@Q4$KT-@Fgd*9Onzn3}A;3&#A_rYrxC^Rv!64ZnnyND9#E=pqNTEFf)K- zLUU>S#B7O~0c`iHlpM2%NX!gi(hHtnUi?OCWx-|Jr@9#Yo%mA)4^&?Z~_ktO~Rc1G-+*p|x#@u};Xx2?- zz8Hg}#!_^TQo#)1GwTw0>t>x`22d9`T|UI~&ddy8r-hf)_KC`TG_IfOCDqSY=BaVD zM<-YrnM%wI;19z!aPsFDVrBsE?Y{`~W@(6-0qknw3AWE}Qze(#=NSywyIPWXe~h{w z4{Po#^X52bV>YZ=UY(pdhsb3mQ0w|ynVA7JY|HzjW=>QyGl28?w_;Pz`w}w)_+?ck zTzsy~*W<$ULYQ+xna9T_!_&bp={ztqfKT1O!u&ap1T%n>rxDzc0|hgH8*1MLy{cHj z4B+SxYglTSC71zRzReWc^4f4_25{s4I?zH>C71ymxz|E^${YeS1L*D(=D#OF;S+FO zjjM8vum9gW4*9eouS*%=&biHvFelymC}3s)Y5X}Fim!p00X*0B0sWeLAD9`yoZvU~ zV!gsk;N7_~w7S0;_;C)_DVcQkY$IT10KL46s96tNiJ1ZHF}I3Rn^*H=W&rK^-qHA{ zo!pkooSacbM|~B318evck-C+_b>Q%{Op3W>L(B}IS?3ta$-6I@0c_dl4W0S$S}+5c z?dn1C>|9}P1QV*Aql}9RPlBC(nbV_)e}Wmnjm|A-39n0MW&nGizas1Ly@Qznj7fRy zU)`rlFay|}PDpbuC>#qGzo^6OWfZ;zmztTv`OmS$%m5meT0=^MKw@S9Z~5MZ&EFpq zGXr?_J%J0)2{AK(A9BCK*b53*gI7kR!=qdJ#LNITO(}#s|L(}l4B)E`l~CJbsD_yV zY&KtoCh9E`GXtn=p@Rue6`lw4`TA*jcCugw@cOoF_%X#2m>IxJ2jbzQrF%mB`5;R%id6^;nQI$Z>>XoWAr!$xZ$H>*G}16btN35KUu2xb677Ce)Jc`lEc z0en;2Mtx#~PA~(QRBf&t-(BIF&}K%dy!>7cRPs6X_Zv$S+x`G%2C#+G3Hqpd4-Vqm z{(F-yj(-Zw4B%^TKU#9n0hk%UrJFv}u@4Gog=SlRQTB}0Jh!ooTlCg7t8?m>Fz|1WeTf|)fa51nMwJA8Ni{AeaW551v7vh znthO`F}KFd0Pf08*UT*9{YJR{u-n}vI|qexLl=W2$-6j@m>EE$WeU-8F@;!{eVq!6#1P?$E&^3HF{eB4!4#F!T?6SsNuY zGl19HmqW<3`tozmVQ3THkLXwfiJ1Xh*jj}K)xSy144}DG4qv+r63hVhZIyu%|FnzWeSIhV|OHwrHR64 z;<2;2bgv>;VrBr_`j=Ah#*q>;19+JCi`b{})mZTHq%pjQfL0@$aX@7U~2ufV;-cktZ#R#_pK0UYD{RGQmM z;bU>&0t4m;(ukP>Y?r+X8cd9&M7{=G((Iwb8x1itfX;gS-Z9LLm>EC=o+m7MWy$;F z@New6cvz9A@Va=hTQ>N;szJ;Q;0b z2(;j_i{%O@j3?UvgGZy63T6Ob@V+8urssi~0X*8^8)QU36wCmc`15?VDUWe;{a0=7 z!q=Ozf*HWkOHad{l;46G!1XU?z@25hmjRb~9#Izz?^OwA01XbFkd83_%*+6qp1$Kh zxujAs131y_id?t0!b{_Z)y-*MVus+T@w@E;8htPZ#QWOJ);1*O>BW3K&)d_&lplax zfApB+^!@A~sKxEh(i=j$ZWS<`-&Yk)lj@p&2jIT9YfTLp)? zyzhuKu$vx-?!mzWWIIwog_D>o z+#low1`Si_7k{?(yzMYl^_SG!cz*nHUvT_bPRltqnf*!n#e3z={?`Y~WX(snuOEVogTkF9m{%pzU66$eiI`BRl*u_4J($1U)bB@<(V(ClDJ!rI< ze|y)yr8(0AAc4Q{(7_&bl$n@w{MqzcHk30t3%u4dV-Uye=!g<%wvNXV_td06%XLu6 z$4AasCwE+}LNop@Mbpo#+aIm~6@RvNCP_ou|Akdt-o~Xb%;}H}wb$^R=EdDmv+NU0 zU(5d&`d4AjMlTr6-=(n32f7||gw~wTCcV!Puy74TaC!YkX)tqGJ4jo}bIoo4L2YAK z$$u5+)}{&?j@7=h;2e6e3*+sT>+c4CW{vPQhm07E_^H%e7MKwqN=G!XiDCc>+&LjC^@?V<6Hz!kn`et&TK66|34t}F+HRn*mLVh1P|C^SDRj1nv`2Q%l zguK{k&U?*aYE528VDLeGfy*yktJ0p5{H1pMy^uMCP32wSh&i9@;sOeuvKng5TY^jM z(#Uwg1!%#_b{q81T=KZWXaBk}yCu>4(=-?ao$y3{A91N(@2f}t727S&U-S8(Y-s1)fxPMNb3I@NXZ-lP|mu9%bwn5*4_sYZB z{VV}?EIN9w)Nbp(mLL2_$1f)W~-eh`ADVkmEgs^ zr}8oXLg6bx^OgqGDk2ToSAw6HucEMqJf_2a8*XP$&+3uzmEa@O$7G&&NBBx`@BSbP z`e7}6C75UvN7mV?%1S4ECHTmGhqRp62EOMUqNmgVm+WleE5SGKCd0Iv-^reHer{q3p`U_< zuLR}xZqRh;6X7dC+Yvm^9(GCiO7O?+FYsXO2H`8ge=B)i`PlBlSAsbn1rRmGU%tV8 z7{$E&yd{2`ERF+tPi`}Z5mImN&-y%vHr4gF#Cvz+>honVeatBE8)$fg>x9!|0C?(?gL*qw@vfCA#iV)@Ri^^duLc#Jz4A}jz;=>!DB?e@ReZi zrh~!cXu0r};JAutX&vu7agF<=fAi*2$O;vzxvw(cSCb9eR0v-QMxPIp&*5L;E5QLS z{ix>T6llz4s(0E!;1~|({Mm((PGsHVmGG6|WV`3os{ak)E5VmNKalgnh>b(hc z(Py;qmEc9ETnao>C|%{8gA+^1X3J!0BY&6gIqU$jaM0}F?-+JgrCoI3xg5ytYBpC= zQIvt$;~g`v7E(x?)x^FMJajvaYOs^?0r#OzWF%F0d`yWP|NJ16qfe0VmEb?OJJjrT zobZ)k*VESI9+)M3CD?F~Dcx&OB77y-Xipt_)05dF&S7nWD-cOm;= zW`Z=rSAyMJKY^*=zX)Fmvp|=ix_zqfm7va+*_98x#|Zb;MvHFHrmRBvO7N@CE2-{5 z6@KNo?>2AsLwyzMbD3;6wY*|~nedfhLAPvqxJ{n$mEddLD9X1hj{av`!UYKSAu<>hY_vYBit4kZx{sa=~$mfR=l>~=8!rYEzn1mE#{t!di`nSCW#%JV8S7WO9)F^`!UecM3>T;_J` z6uR2|3bC&Q9TtSsg2?B@z7iby%a=-5e-OSB-2C%8HTFmlP6}*Z<2Y&MTw-4dt|&$N z#tazyO7KD1Um1&aG?TxJjpYQntBs1C4BQXrUDR6_RSI7TcCFzp^*LN9d?k4NN+;0l zP9ye};Pr^r(A_zb*jIubjW0rujVyd6XcGSzb}hIgd?k3bC|>?^^+w=&^MPh05E-`(m-G}H`p2lkcV{#tMN86-gXO7M=m2L!c=7QPZ3 zH~Jjx&B+kH5`6f2AsBWo621~V6x0%EWR>uh;PiP{rR7&t*qiJ8JfVi#XdBNNa9amn z?34FhFHv&n{zZ@4yJibt3HpqlLc?9+!BVsi^x#cf5;Pb7yi*NJ^4xQCx56N-K4A?H>% z%!~Hqgb7~>dgouEA*+&=YopzZ-L&smzVMY``T0S#*S%c$O3)_ut3204rDb0U>Wmu7 z&v>mn`%17pskZbWuUz;_P`>?HQkUfmUkRG)4}f;*$uxk=jI`MapW1~J`${li-xUbG z zY|P(f49};Hx^+`+%HMG9IGz~Jmf zh~YlGxik_iI(q{9N-%DU3^qf9g|7s^G`IsD`os%g310ke1-)Bk3ttJkznTUM$Ce0R z2|8xff^MUA!dHUrf(}S;Tvf=v61;NYz5n{{Rl-+-y4}w5Vw)o6x9igJ=2W#OQ}{|S zeEtGjxGx&U@poTx#Fhfz2MAvY&Tr{K!VHI?7+NvBGv zR^=38UkSSH%BHb1t>_cyd~kI<#s71oKKxzO?Sg5fN*2Bn%;7c8k*1NtSAyMR*?EnlKo40`BB~{g=5zX?wY5({)BxcX!~}olw!hb z()qJ3hviAU6P56l;Nrs)xO7XTJ>1r#n#W+pjt{h*b9iWf9eSPd6221L&1-RdZe0<+ z61>+d9Hvy?tvsu2yp#+>!v_jq3EpwbhnkZkWmEp{GvsoZI<}r{#(m<&Zn5y(dJ_9e z@HD@7cI_J}4d-?T$CtyjxBT#X0 z%om0veh|JA9xuHPa~dTo&ls9H$KXNTJmD)r=feO8dzJ}b2{!(oCwq4K}qyhU%Fag(6S=UI&<36mNc#-bb zlZCGY@2vBr<^gWPSAxrT2a}tXmGG5d!P0o5%BjLvf?kkKBfHcRz7j0vHG@O1?v;*k z4sE9C$id~O|2fWWysJukzsf~sUkTn=QAK^nw;=YFV6QDj6x!6B*jK{u$m|k{v?X)? z?hP@TTo!xKWbTt(n*eI{JAl|%f{*!H&9aIXz7kYlv8C8?nZj3sR;K0zON)fB1ohM{ z$c^8Fcn?Xu-|vdtz=f{|e&)Bi8|A-xzE1c`@Luc@DQ`oG@(euDycXz9%@)2A9R6x5 zIQNgIpPaMHeJcn_3=+N)>;!k<))-IWE5RvaWvFF+QTR$Q+d2};Hm()E5}c=>20w;% z5xx>kGc1I8Ro-$r_hHt6N-(~8TXUY{9mjZYipU8P`%17Cv%q%rM`B+It~V-!lOqAx zSAw0|=7Gb~V_?l~jmS@c`$^ZqhI1Hb^Z|;G`obyBt;cvT@Lv@!d?k2&))hGRHd**e zaO#X*@Gv-E_)2hAqk*9MQZ9TYxaK9VPMgWs1NTY4S+%8U%%xXwo{{AZWyfINzk=I6 z_TsBN-8*0SO0bX1K)PX>3^TYtqY8G>k6U5j&!5$_bEfm{eTAS5h47VN;OIoEPLlAI;Q9f1bbeZ{^qX^Tf@Ku{K`pVb1ZUM%X-$G2Y5MSY^g5-| z?!4(M-{p2M_oyWA?_G#}C0N<6kR}zcrIDPc>+e*GGP*>y_#Ja-<`;VP*pp6if6n-z zAp@^q;VZ$Rd)(;3rFh{hL6?D6)Mj0_@RgwFn5jIsUqTnStq+T8QZioyPMpJp9lK=j zt19h5&Mi_d8TDi~?l)&^o)8H^4m%3!b_bMxP z-Em))#K8iqJHWmY9C9ZJCY+LmuLOscJ%)_ek-}GkpN8-~XHuH*mEdjfHBfz8q41Sp z=&sIic1)%4m0+z+Ueb0Ro7m6&+4_mAdP5x*vabZ?l*w|Cewpx2HYem7vw28>FXuE_@}p?hTKfSGxl2E5R4n!^yyPr|^~Fu7YGT zojySLO7LuEK0WFdAsyiUJe^if?#uL~uG}Z;IlK>9-KH}8O0a4cuMdJKxj(lX_N<)p z%?Ht3j`i*HX@mQ2TE_kPz$}?AZgD2w!xnv3htaPzFZ#*-`8w8z>Y9HPz7lkCzeX*0 zB??~&)|+fWIyZI{_sf|je;L9?TddL8H1 z^r{MLHoGpduLPaORl&fJmhg$|nP5}|>n#@o`%3UoK?bxxdJfoEf{ntWpy0O$u&)FY z8wJ4Ejc?=X{8a%EUULdot1k0+Ik>yJy_LX4Cr(EjMUbYcg%){`|Ul5A5We9e3vj~S zMA$l7Eqo=o<6s{2?UyAt&*;ADI{Y2I`JR&RR`OwYJWz`hbR+4TjUk9Y#?E5R`)8kjTio$!@lN8VS) zzan1vN>F{u5_bAz3ttI#3NeAihb6*Sf=|L~K-E?qeB}O|)?tgZn18d(xIa%=w$LmX zQYCyP=y&yoe5FN^@Ri`zv#rSUU548*R@*LfbcrAP-SkLGI%^2=3 zd?ncQ;Tzg;^{nuf;5fq=>fB{MEaiAbU?v&lG!?!QeDb1*=5N0wm2!VhI#osKzILNt zbN|%gXAG0mCuR1PppB7^Zn^PT1LyFsZ3%VEnNAn@I7DQT{$p!u&*gjD#?kdwcj+zn z=e@qXcVcZ4z7kYzdQ7%PUxlv(^)A@cP9FQH&hgGkt10+wA+fIn7v~tzjMbIGSAqk^ zKb1%Ep43yhKixlE(70FXgs%h->dla9Wt9^9O7P13f0D<&T;VIhrMpMNn0W~#bAN`d zKMq;DLMVp&^H0PLSibwY@ReYFlUHzexs&jf;QSU5pdQK`9@kSiI|Xt-^b@`kjP3sy zvQ?on`%2KDaRo#aRcH!0pJTiRv9fDxiG3y5ljmcX&x)10al7xW%RwD$1S>d}rsPAL zrh9>XC200H39_5G0Q*X?(eF@z?cVT``-kTEz}_z(g|7s4^{;_hH1F}sImD(P0r^Ir z@Ri`s2ww?)4=SMv1skMP?oZQ$Jm2TiNyEMpbl`WBUEOcV>?^_i zZdFt?y*06~1m70%y5o{X#J&>rznVdxdfCwv?oXS=QPlLn14`$7rd)hY##wKKuLLLM z-ly;td|h(8ITM**&dn6Q5?r)?9$9@U621~F>)Di!U#uebmEh-id-)t+mk+sr_U+!{ zU(j7g-#G`%rj}AgmEtSGinVn??|zo>m0+B^DQM@$(LgTWTJJPG{u3yCCHQ#hT^QQ+ zvGA4POA~^9lD+VipwXtU;Cx|~@RguVcp6mnHW0oN-1@K(+@E^N3poGXdn#d3w2fvc z_h(IhSFPW2w&X9ap8_3(B^F8SE5YAiN}+?%7|7*%1|Q3Xl>x^gg8Oqe@2z{N(@kJs z362{Q0%-dRjJZF5^nVUI(+J@!!M07D-~{{c*jIwq$G5}8S$~DE1nukggMM8rgs%kC zw|TvAnTtKHH zHxT~}?_?Js^mpY~O+Y*{6IB{<;8Z7DeB zpYWC7*d}ejZCi%$m0--X#o*L6ih{U5bw}(VY|d-pE5SOiA3&!&_l2(nCmOzm1%GXX zuLPwlF|fsRuJD!M(zd@rUfD$WN^odi5saC1LGHu-aOq|hG}$TnJ8}Q0c#P|liKVYk61;OH3n~|$hVfk9$RG|p@7)D^uIHk6AS^yh!dHS* z;~#;>?W^#WVA$^qaI7Lt_)73{>`MOaDippFJifLgY`3Zuz7lNG;ju(#m`mXPoS$+^ zosy{&z7o`QpDW+@D;2&HELc|}UpCJbz7h<`8$+XWe?T(#XJXqEbhPlj@Ri{2Z8vFT z<}=|d!DZpEXuI~Z@RgwLnFzWQx=r{>F!xyswVK>l_)5@r7w-e{Jw%G&{%mGkK^+Y9 z)q$Lk1+O7^h#h41m7v~umG;f5@3KC(+hs{P87>$?TRDDPJ)e3V*hlOu!7b;LD9+1; zjJY3vZw;jxrQXE85*!iwk`7P(Bzz^9yVaGNj#7LOm|=C8QZn;|uLN7w7)jTkmkD19 z_BfIz$8_W|6t2f^Xn(oSL6w$$C3vpqNA=o|%n5M2t!KTKoc6Ofh2s&od%*E(sl>h# zG`86Ydjmf6{)~LC*)!&4K6-N32waB7!G;z-q73+_n+HIEBU%S!Tsa5vEis0>}3q*9NKp~ zE!)2@R<2LGoO;y3EKB%Gu-ITGoy>@Z1zi5)v(wA~1`1yZ-p;*CV=g@sz7ov-L{#s} z1>q~f-rv8{hAu0GuLS4xPN(eK9fYq0C;l#^^=BSR)|~%1r%D?BAvD&+pG@Are$+MC3_5_I)`Pn(+g zQ8Vt(eQwXF@@<6hmEgmzmuW;&itv@7L)&fi$nmf6mEaL8LkgQxA$%oxY07(?{RoYveXVCOc(xpk|!dHUH**~O@34esI1T9(*g||zRh_Yun&At+h<~g-@aRJgHZuhxw1+-n&6Pj|obAAB?kKP3AE5Th~ ze!-=lj&Oj2`I5(S70R4{A4u2Ks#Xq;d``QZ{wdcRl?$7=e17m4a=#S^F+7it;F@LnF%CXmPT8iyNP&*Jsr>g1*s6voWM=JD^O?d|?j8OKXn_XRI)GU@N&|3S+g z&@066$E&npC;#?(e1Zn&570O+KkNKY7#}-~e(~`Oe4TW< zoG6R+M0yW+&!NNma?8W~zEgwOOG2r74m)SGz7bK3c6Z^O0hBx29dU7jN@n0p(K+_?{O8hp=2t5YOQQ{ZRn&8GZ8-0*RYw^#&xw4PurMAk8kZ%;@MN& zX#9&qN_^ROB;~xeP~vwUgJs+AN0nI4eJ!QbIiSQ^X$$CjY*pf-FaB_L_fjQJURDWv zEv6{(q8sgTa*mM_TeLF9M&+%QxKA}x%w>K~^1x}4&)|&sW!**=Hjn{kg-@n-h z@k5Ed^4({fTi~{#rzLSbb*lx&o6iCfzjZo@9aefO@#AOP(c#A*C9a>o0(+IVLQ!T9 znPRs_MoN4-<D9Fj3-RZXK{z7(dJKpE3X6AAGn)iGxQIjM3~@Vy|I4VGJN6=l}M%+n6`@2SM6){N2m z#*S9vAB%cvO%~2m;-CNOYm;-L`$~WJW2~b_i4Uo^qE)*pC9aN3@j`BU6lL_sPC@S}|NmBm`WT^Rn5lAn{`1zj z@z4q-ezff`3|qBbiT^cu3K!NNRN{hIGte&m|9Y6|a9&!r;s1Dhu#NoW`2S_{s%F!T zbN_$Vz1I_}@$&yV`#I**Q``UB8X>jTKJfWJhmc7|+P0=0l=`EJO|-6A|L44}#!_wS zaaqaV>GKw?@5k**Jn74RZCiu)%6DHDd{n!%Q4gh03_kqF-kHbM_+1pTthz4a!bE2qdo=N7hWR^LhGH0mH-jTU7hbTlz$dsh{u4g@;&+m5syRUm+ z_j`YT==JL5ZMF8=YpuPWz4tlKInR#fanlT$5aY(;aPA#<7Zsn|PA=;#LcVeRIk|OEtUcq6ov3QB@hE3X zI&@uE9prIp(jt0JDFHdXOCT+ZQAK_!A4xmCT!7a|Q*AWO z^=`ua%#w?u>l#)Q!Oy`xgK6xcd&mn^ylLl6;x+iqa~_={8$bn}?TO~}ptE?*ddwY0 z3%7{ZvfVyK>iWkWb(|VXiB{=y|#J)(J6S^!kB;)Uh^-xl-Bb}8m&LMJTH)ZyP z;@tAd-j8_~igQl_Lb9F);@sZ-hZ^rOMx67_2)rJxUdjcV z;~!)(m+}zgdrN)U?}y_2u>Q&o*_|6=ZJg+(C#|{{jykdLjL4OIaSb{)@d#P}N?e-` z_?D4H{x+yne_fGY9%PCv-93yJdx~pZ?t62(Z)RJRzuYvBPKD?H2tEwf_ojQcu0}2& z5KMp6*JJDoU83lqw_&)pTK|cri5Y4{(0^JVL0#4*ASX8l&^Zw=kYgG>X>NHZD(Hl{ z+0#aMaZS&DG>#_B9FOvdr`psx%N|+ZsS}+$QQR9e&U{YR4ionbJ*I6ZTuIzZ{Gyp6a`HVJ-h-5)|HaxK{8sfLR~79#E!QokEV)k zJ@%a?3min73h#dsS9P(k+fS9Keh<-yli&5}>b+`cfAlH~I{!c;`pjG%Y1h74$itL< zX!FOV$Z1U>wCYWV$CR9^t63UGS51@}_;@Igo%h7^)-YDPedzTcDVC2!+v821I zI6vG^`y=gEBi6>5>1(qtevLpKHHE&+^i2SAgw+mq;h`sTYtus3pd;4ar11(oeE&F< zR~**i@AqgUyT^>@+vLR>)~UAVv$sA&|3COH;?>dd$UmnA@WLz0l>u zI@+S#;bS)*X6J#tZq0i(dZ0h@eB(pRs$QHEEUt`ZlOBlm5b#-Dw)(O-hrGO(C$&lz z=a!t!{zPu8IOk;FXQVzAo;3(RCGdUunFpsLujK0V*UOQ}^8JlydU9{%=e0Aa!7xfweK+I+}htFq;T{B~1vUvKi-) z@9Fr_F>zJM^M<)lpOMN`&}mg@N$-(S$QN%J&?}e3x&7g6HM%cOobxZ&HjoukAJjSN zoJnL#p~zVimylB*#M=0_RVEG05^KY+Vyw(1B^-5ZHk+`z&Egtl#E-ITQR3P(@9hT` zT5XLw+9BQf!(D0i~f=08WwMy@*5kx$zv?hQUZE?~Bc#6838YjLdANO3PQ*-VMOZ4hf? zP-~5>sjo%(fH!T(!R#Qk^AWyRVtc>~x$t=&F?lc-d1GulI={{g`CN=9jgQntZWt`3 zL0h{at4+40b6>tg|5aCb(6V(0k)6i-)5D`jAtx$Czelqfo{ zDu4*_&W{VBE>Rpg&3h>o&YltE!uQ5ssr5x3U_X_n`xznItQ$!ahRsA?>)e}a8Mq>U zy6}zYeG>POA9d15|0`iAAN6Sly!I9A!8jmBsx(bxFU8%mQ^Q4_(M@w0Z7a5Y-sL>& zRPT&!OD%q}#9fxiSJx|Z$4v&J&9G5CP+1Lmb-4v!KMB7306$A_IPy9BGmzW3`|z3r zUdX#ggz}JA85n!=*C;+Yo?uSouSRpNK2j#MeY`uI>#RS9eBXOH?|Yye`RWXJKJQj{ zF6caC);w#r9`dX}6aFlA67s7f{rRt<^O4=B%5k?easS!<%WXC|AQygMr=6h>-Ktf*2)W6-S|E$a-WMle1tro=4ysKdh9?x{oPRHewU>@qOmLT zg;TcNCAL;th&OVE8iZDJa$wBA3w4K)`sz`XfC&*K+MnHDBfHY%!GIc zx`ptPhHPa0zDxN}lB9&wkj8^IfjUT_=2H zbmTH*w|yyW*t;-f=Zn)=$JJszc;5??T_+;@=p;(ZT8lbtqyyQQ>5KZ)_g*0PcRC|8 zxR>!%&k}h{Zxx!QW`G>>c@%XEP(_~QF^%dxsYCyDhdI$heXb&Fo$;YYS3HsB971XM z&2)_2p)rc4Pn?E18Gk04E{hsRgm{yE!>M0~{s@ zrt07Ikafz9={M!c$kV@Q&?npHBVX9xhQ9sdjeKOyEwbWhF!G?gD~b1HaekQHqf*-N zRjiHp6B${3QpNd1Eq)-AE*AHnS~GUD9@?JR)}><+dthgWoVv0z*V;^x-xdt!oo5X~ zmhGLu2Vd!coRl}4r|~D~|H+<%}Y+J(gB1)~qeF@H z?I+4kpuGMWv%Guq$$Yh4SnHr$s>?2D37I4!M%`w7R;p1Yb(XL?zqy2g{P2r z+b*NAb1jfBSB25H+XAsR`fiA(1NR@o+8AsQ4bSOYK!kXGK8Ml^_7{Ai2rPWI0-LhbA5?Fz;-=7u5M{T-= zYistGXx^njiwQA)JP^SZ74{&w@@E~EVHCsFK+^} zW}iVkO)>{LYGDW7d)#8=?vf`=t}qb!*|jaq+9wiOH@zF%3w0^j)QWP?e3mN8i_dl- z+w8^t=MlS&WM92#M>X>SQT`>`FD{j*AF3u|+v2Q&)WBybawiQ!7tiX7JWG8RZQuL` z{r4KRklF?BN6ydor7!inJ9NxcxdJMud6 zwg*e7d`>GW$UCMvP-W5&Id$0-dfaU+a{Pu7beggiayQjpH1D@7veNS}B*K3g@>s1? zM5C=Z?xjsrNZvNF9%L~-(#g6aPm4SzdsiUV&&&l*@SJ8}Z0jbU&Kym}{pUEj8s>gw zI?D4es_-Yv#vni5HJVr4?1OChX&Rrrt`_}&vfhb%re8+x^UH^)U2{jiwKkN?xt_+@ zn-!z^CEvL+A;#TDqxmn(iA><%)5CdrKr(X5=Vg5FyidroeQtbL$DUl!343Y9d&Lh& z?ljYw-(5Qy`If5&|5G(zrbqs4M%MftNb44LMeZ9GNe{DLnL=Doo1^KZ*`0{M-UlLS zpeCG806&gngXqkVhsbLlEv6qvwWor7)%7{lvTh*qi0p}U%0eQt#!z}_{w!pLKV9fi zr-jIGr@SGPUW@zBG4R~$2`=J#F@Dcb68T=Nhl<1>rrkot_2sC;8(F{J;{Mb3Xav(u zS%P*#^m3Ri$^kh^u{F0CHU+tDLO&j&I|8|vY%KS`)f4&gEGxct_R- z7$e)=8%|RPXdu(f$+YNDYveXV9B8oR4fH?XcM1J-GYVO+Dwuw~_8wyoTO37uo+-rr zXVJ%Kcs92V5n}um6+uf6?M1%dDS&R6@EW<@!G+XqWfv;w*rv>)XF$*4Bse&7`0=hV^LwnT(603r@>iT?hb&vYa zo>tC4JEO1k=G_#Hki$NY@VEg|RcF2Om_CmC|Y&ZS%tz6T`8`=^F* zzdm_b+gVqmxYqc7IKIp8NAsFCW0;`xxh9d{4U_?|$D4d0Rs++f*X1ahH78vaE07+Bf%FD|m*9 zSleCZ??g+1D|R_R2$1dT`5IH66aCFme8 zJTZ<+MkpX#jJBr_dKIGoNrj%Yzs?S1*RlX=$<&eIFbAsAbv3Su^Wi^WOHvYqF=c;=HF}?88#K z`Jhfavn=*|jwAB%YwJY4vjz_ZAg zto(THPdns&bHljJ@HmXU@BC<Kd)@=5y0HCGIIUBy)7cTVa&wsZlq3Vc82UdB@7;lE_;)Qu2i*VJY3 zxkqtLJhb$V>@eJq6l^Xu*OIDNi1VKJbOUmwNqpTsLj5p_?F)4YKYQFt$sT4S+O$`s z^VXRn>*)=nZz~5N#|D~H{<|Db|BRcdX5}vyoeh4b)tff?Kyj@@=hE1`o!^c+iR#x z__4Ovp?!Vrk$)AyeV=xVkbUi6z&W0Q$iJNvNLo__vfMH?vLEg_32hxa2bsEe5^JOR zc!MlZU3@L}{_<+pVTd>CbhEw3PQ=VZwsLOEy`GD6V^z=qK5*SIly4hj%45$dBCm+H z;SSTv(EkIa?)<*Gc+aB4)8$;6V1)7w_rv+5G+nF>+0AJFZP87vje`48yj`X*6MV~h z7s7*nWg%a#T*?Q)ckl$c%1}pc-CCUsd{f_oFO4)rzPd`Ezgai~`H`Ozza8g->;d2V zzP!v2IrZ8ZHqJK;`OExS?3|le58oU%%YMN9NWtc#3!9}W!J^KGEL-w0T5P*K;0*b3 zRJ3{G#ShYBvDnwcrAl;Ufart4W_{YLzvx?W9}D^=P4u}>FGsp*lnnhJUa}OP!{Uc* z^*V%hwGd+;{UD0Ewi|*uiM<_7FQ*$4!JqUO;nb+?Fmh<|a@v1@nA`7P-D!P_m~*>T zHgv~AaV#QcnbIF8#W9+28s-vzaqOx>+tQT&;+Xyny+^jFh+}=_>1wjSomc~J3LB-F zaIaeESDNUWwO3AjPsaMWDm&3$tfk8|fhBhlYb;Oy1?v_q)?TEn6F<{+JhuI#uEWFS zb&w}$j^{CJ-U`o}Q1_h+17VAEGT@ zJJ}79{9=fBO-*YP%=fhsueHWD-drh7yaun>&f{*m;LOm_wnt0Z;~&d$+`oDqW^+o!IpJ500c!>KBZWNBvjb&8H^ez4IOC2qHD8=t z@|2d5y1U|>qkKX}+SH13QGVBEvip-bM=3k0({E$-(N3S6hIEvkIH#T2HG>xUiE~{B zccF7ziTA#5CHT?JDdODNeN7mx9wN?}XT74S-oR~G8{rG0>Ab<>96QH7jIJ;e=iZw6 ze)L;{I4657bD?{$i*xmjAv5T{8{!;pNDOJO8RFdD_l+7|In@!zC=br~HEA!d1s8m> zNT(WcjX1K%htxe2Yh!25btyb>3-!Oe)|1I@h9j5Rj%7D8#Wm>b=_BkV7uTlm#bxa3 zOdHe*_^rszHB6Dm9vsFC9mO?nbip8h$2?|c7(31jD8=E=?4iEHO+-fz)G z`Q-vrn%qkfS>dw{wf`;dkuHt(pr=yAy;F>$Ked#Kd#c&h;j~b_FV30T52C4*=3;(A zv!ZC`>gAZXWtT%J^Az`NsYjR6s=MM|&Nm0X=X^ojP8KTaEYxc~+ zP;8q4=V&Ow(*lLQw$H3$t$$l0>vmM;(H%q|cGT(f!&}r)?y<>&TbPJ@=ISU%Zj+jc zaqZXh;V-@~K@RF1%7@L(#@MZ1NAW9lqcJDVJep@Km|zV!oD1hh%Z?)V-v?_DJikfs zA#A%lS2O9(1#YEb!=IH8L)I=f;d>1xAzyDjfGd@VW7qel98dD|M)~FrcUiDSF!IvH zv8+K&oFCFg{E-cY&q@k5?W#AM4tN)Vd~|w0^6EhVvQhdD5+d_NZnve7D65FIw|cGu zRSX%2^59$@+Gwkd{DO_AJzjJ~e%@m?eLdkB`oC`FA{t~AkG$VLkoLT;glwrBNyF~- z!)xRne1^19yA2WiF)W4qK_zREYahXVpQU-o@#$VP(y<*CbS{6GOD{!eBHJ{Z(TxgH zWg3uHP0D)|enCnCsE)C;B4~UonZg1j!-a?lzyg&cB2HXYYW|9i^>8Ugs7} zQ(}H$?Bj+;!Se_A z8pYaZSJ%xO*6&X%8we24xw?DXJol@B7P+xqi;s`|*?R3i9m*Pd7#^-rUD`O$}%ANiCh z__R?V6XMN@4dJW5a^&`QOL+(Q-jg8Doxgy4jp>X0Y{FD-;%kKbYW+xFGI=JlxoL0C zY+aE%o5Ax0n#4V%-Q`r)lpTihR%8Zi8!pzvxy_cy&AXK8XfnYvTU z^6pg7$w{`RkM`&x-!X&-(OjN{Ji)y`RUJ1Uxj|cw8py=`r~BdCBsnS=<^4)x$VMY^ ze)uB)L+boftc_Lj$yrNpi}T6M%KofwM*!+S7`BV4EEMni}rtgbzQKQ`=$ToX2%x4QEb{SSDth&vtHhTM63AiuM_C-QWQNUk^X2j2HF zZi4r6U$`PmZ9*OcR*NkY}l3vJV>u1sq zd%mLoMJrsXcDqz$lfKL7=KIr;A3X`9wtXY9Hh4@lb?=mjwb6mX=bTr}CqleO6vC*> zkPFCR4}IxOi)!RG>CW_Ul`<7{-b}HieJV#G_fs{Xp4QWlmv2#}Z#p|6`%I`OefRhv z_lECl>RW{(+pk(gJ~fE7;aZt44LU2|R7T>Zp2Cwn(}h`Ouyumf6`IIVJHU zd+%wDY&oF^?^AD#ocmIbuhHp`JnG{l{{B%LMn>-uz?N7-XZp!TgQt zSB!n@#3+8wd8&rKctnVjO!Vg3H7CTmst$1@ODsuaLJJd2%iH&RmeYF1F)G zb`M5&$)ViUc>=P@?m=9ZJ{!4RQ3oz3w;1_j`=_kvjJW^QF51c(>>^Q~I;RKAgSr%K zHu~Pme8WU}-#zlgHZln13npwJgN(e8qfXu@R#WF9FL#iqJ)O*u6{G{H-b3-e&)VBk zx+bS9%6mPwrQ;M!(Eph49`w+$MC5VX{OKp};m9KmBdDjNJl4jjqG;;&^Eu|{WPB98 zkRL(>-&AIW!1ENYA$L?*O4k^*qJn&UlLKv4*cbWnwJG#5+>aFGZ3{=x5!YuT|BUZN zO;TNvyZ@?$PmwM|-a8|O7*vEIuNXXyNZ@{?(6;JKp!9*E$RmFplx5b6^;7%Yfh|cB z@B1W{U0}~wIir4i$#2#mXNkOhh6=y-atyML-e|sOrYiE%mDBj=?RDsXC2`_Y?_NRv zzFftDZIQs5l(i=8iF6*>5uP&{7Rr7v5 zq{w#92h)ybgOI&XOrS0+Iv|h!KAWDheuDlV7`B+67_=36{=Go@xLFZ7$TgClJiZz4 z`?$eNWo^fL9?mJI&ls; z)BIAVOvL@CvThiA{9y^|3{kkwdfanB-W%77`-DzGo;A83AD%D*IcnZmzQ(E-^3NYL z`J;)I=>Ni(uKdi#Q^<>5mhp8#Q<3{Ohw-BszE~S4wnp=4+ap*Tk48rG{x*(G@a=YK zD33jL5!r2>FOSdqjjU|t%ykc{a6#wbo#|Y~Z8Wm<_!vI*@-*bi_Nu(MzZ3Gg!dlk7 zOx%C2YjcGetq4W=9CHu$tCLs{>Ir9M@h3!%UTG_}un$L_^_wS3D7`w536fGEi2lt;#zeLll7lVipqftTxRa?0S*R;2D3OXy~ z?P$r+A;{OqQEE^-0olAvi#lt~LC)0eK-bP%jJ!ALF4L7db@mx3xbp4@2Kab9dij%ujxF z6n}IqoC&^78x+FJ@~$JB@g=;|w^m$`Yi@VoyH@o>b~T;?ub0Ondn_2icMcNAOHIBP zpWR6u$EoYSu#8x7d<}C>viKh2xVsfkW_=UHdbs?>OJ+G#;=_n`fROn@&F~~pnj;7r%_Ce06nMRBI)}sFg$xhUG!e!(! z9pUpKg>J|SJ3?vKo~JSPr`_T6%w6V5g&4aXh1abU%!t74$A{Ay70Jla&zI2+*`JU@ zR=Ux;em$w6W0h+~C3}Y>@0e^%51gKi?4_?kH}w*)>sdLisn>k*dXGPIgA~0J_n&KW zqRA0gaef$kvP`N`A=bu?r7yCEuM+1I;;+Mos0W};?NNJKhYWH4v3Oj}-saCj`EAQC ze0(KA-n4!QAGAXY*<3o2lXvZr6K2if(|$cd|AQkIbB}YIkrzpVcu;f~jUZ@TcH(RCx60pDl<*h7Q)2{MUkiX{iqk38+kehPG(zWM$B42Z} zqHejL(SJWvH@dvx1ae&RGTJ_15^}g!ICUJi5NpF}cQhTQaRO^2Z$LC1eAk5tado~B zN(~e*A^V&8(&rlDd*c(oxzqKX{4xZcTDaE7P3(s{E8j)XnKu)Wt2g-5uy!Aj$BxE5 zBl`CI!UEyn|0Gkv&wu*;5Aq7^>yAtNB$!?QgDm+sM&aN8B=djrEcE#wdH$W?ObOgE$+ZC0A;bM527*mhi>A@KKf zWI^}#rH{zQDIK}+E7%ld@HZ;3pnE8yGxGH(CG2?aS0c#Ac5Tn;%S_~5tPi)GxDI)4 zx;8hI*FpZ;V+0?Ok|-7QLw}6oE#rm0(5BEA{Gz_te>$?@8~BVY_zbb29U+#MzHL~m zgLZlkie*RFjzmt2=*;qKMOeu^h z_61`~U`&x=O#c_(dOdrNHXWMv>Gvge*jBqvmk#Zfhc$I&RGM6k*K8D9e9iwxsSV0_s><4a+Dkzsr(j4v{bFNN_%hVi8^zOsMDmnPKZ zCy6%4&=$2sTGSZC^k20{Tht_NQLD6tZw$s4efwv8k^dQAQ6^IQFJ zZZK0n!(i?Ccb?#ps%FTUn+J0EMFts%c>`Hkr=Sh4n_z>3Eo89G^+#?V_|N{_zWxP|`TafE#QlVdLA=D*K43f_n{D$rjRv+y?$fAjF) zum*6>6-P##fB*8|Jp8SJ|93U8=(8)$XkAIlGEB5yhd3d>PE==#rgq51M*G;&STp2B zpWm^)PlqA<6)AG~MFts%zY)O>=yGU-3^q8}LI&G>HQzQ!(1AV$ITKir3w;PI=nH-P zYe(oqV8OodE3hCF`Vd&q71{_a*br<9EZ7$M5cqkUw#hBz*vCKm=&Qhj?=9@p7X8u| z{?HbF(iZ;Ho33HWq8(R3{%^d3KC+NYp$|bv$YqPXQRtTnazWN2&w`&Q7i@t4$b#*E z$Lo^ZE3Lqj)9L9uDs=Grn_5ACM$qeZMzs0{S7Fcv2`DKw0lhs{9zPf%7gI{EjG58xY=rU-7 z3^o|pk_tA#HrpU;qa`r(FUV#8%7s1z7W9Qa1QzTFeF!Yr7k&j6WWwJB7IcL+0t+^T zJ_HtQ3w;P&nL043goW&$wA%e|gZ-?_z&nqZ5N@&Y}Y7&&kz8c4a$1X&=`*o&{sJ; ziN9F2UnmC!f1qEK3;lxsC>Q((KT$6D z3Gt#_h!^7Gf*m0)$O+1YoIoB>F65zwT)J}R0F-x|%8s|NLt5yQ7X6YI_DKsrX$yZy zi@0bD|7nXn&=&F1)kEhe|C2Y`B0qxuzj+qq|K^jn7#G3Lzxk&v#!=`O<&ZbpV%$lK z@g*(lM2PF(dLS)oN!p@*{+@AZ`}d5?zh_+j|2yL{^zRv$f6uu5d&cG8GcNz0aryU* z%fDw_{ypRJ?-`eW&$#@1#^v8LF8`i!`5!;yQt$5>mw(T={Cmdb-!m@%o^kp2jLW}g zT>d@d^6wd!f6uu5d&cG8GcNxR&bYk!e{sg;Qu|8M2F}@>`D_w--@TSJ*~59S7bIlb zzGgBS&J67o=q!D(Q$pL%UO)@pm}NbvZY1qN|LpZ7*{uE5qyWy!JdvQnS}A=b+u{D^ zpn;BT`Z+jz70%XF)7i?FJ>%pMoVj_=GKB?pO(uKbEY5x@Ijnff2GYYC&R>=*WU9uq zNC@z~rSJ^h7hOmOoTsU#Q^Vx?Zk8@s0B4(KHL>Mc8OAtf09X8Zpj*;UsuNlGR~na zD*^m5_K;8o2Tf@__?ciTp*4YTq{5k}MI-Bp?AaJ1oQ0Z_@ty2?8$zx_ywyWXh=ct; zvKaDUS(Qh6#iSE=$dCS{OGM>H9=QZQEPAw$SR8nZXWANSg%kf#-$^#e4P%W+)|)yK z4En1b-bb|>K7=X7r?&6=6O~@QUeKuewVxF$g~WqNH5?rO&vDwXel`a zeh#nkX45PlkyGG*TG$RYPcD;`LtJ4y&$7pkhshR*_k`yiw)@E{BAi7_S{1YLDwBwC zM(u;hN;aghS=tTqNp)+PUgQGlV94kFq-Lg6YnAmI@+sRP;Q`Z=Wx^S_cgq@Cj(r~{ zoQ?Y?vYM$DJF-JyKloEQYZtkd$-}v;)xia9dqN6Z2mZwEf@coDBa7*AMiYGQEJrU2tZ?nZ;XT%1MB#8cPO0V|1!Xnac^;CGg+(N+apsZedmt zZKfBElKXxp_OtLRw0Mvzx!3T}naqiQ`7&Wx5czm>V~{7!_kq~Gl@U~TH& zk|z*v_k>Vpm7YgpAP)h_`&d-#OJpYG$Kh5w3ys-FgtMy0N%EO;Kp58Nr3Y`>t{a9V z7v!zxd}s1`CDM(c-{p55bMVuW8iAeKArfBVS)6qQ?AI)paOJNzWWw3mkK!9xVyO-j z&eT5Jvx@nrEn#QC&yW74EG>TryAJ-Z>GFtmC_2j?K|UL=XRsqlci2jZw{`c!tafxU z6VCF!8L^5fBvmrujPEWE=FH!`mT5vhdroVTX`F3lT_B$;cF&XTO_1>Skk5rZ7MSiY zXk<0euko`J(g{x0OgLLSUs;vhmX)(KuwS{uiA0eCrVjah{%9-NHixri;E(026fz_1 zI1|n;-#g?6sXefsbpks#{0hmin>I{1>pbb&CsHxJGb@64-JEO4(O>IjTOkkQo;Q(` z^Yo3(AwMbyBy@cCCh2kT`Fv>;X>ZsW^LaC{hGbjY5aI0gqt8B()b#aaC+Me4EF?O& zjuTz5^YVHQQHkSZFWC3UNFmo^3y5&GyYj)Uq~>%v5zc)7Q13)MCRdY7;Ah-yi0e)x zxexv;+&?b;xm7}MK|U8M&of<@-AuwEUfE(7S-Uy4L^x~y{@Nzlepw|^0UsunnXx@; z#bg-dvoUNH+tun0X$ARAIB=LPd32V%gnTN!%3x>1caSRR_tf%7Y<9yEIM;arweTrr zZN?8K7s38O_?(x=_8h4WbJk13`-Bdb1%RI~MoW0(+IO-JV5hom zJ^Mb(kgWs$z3e;lm>kARA>PW{Z<*hpeQZDEVN7ryi|cranLvI{vUFx?n$He{&r3$_ zW0F=S>^k^x_j)Mviulf+f&7`AAv08{XNN%F+vKh6y`F^k13Rj#2FSeqBs>o65083p zniSo@7D2yPgKtTDR{doCfX5{bCf;VHj0yR4TS^W;e#l;e|JyZolBks#EEDp%rvEw8 zkB>%%&R1YSq(A+$Y-=;Et!8|w(OT9oS~f2 zOtSSBn?8bkx^0)xR?erSU!mX0Hyg>Vm#U-)>_m>MCW$kgNha8@+Ez}s4%$XWLq5yo z3P?@=R5BO*@loMqjMoja6#U#g{5aWrypYI)oi|h0lLenYkxjti9c{?8h#FD}@k-Y! zkkwFsCm;`HPV1y2p)N;4e$3*hWsHD&-3LBjoVrE!YHke?^4YttGh3DVi4=kSrh+XC zP$(p)Kwn*915;j;LwbOn_nnhj@v;=M9_-sb=Iq0?t;7TRy_!|P6wRDSe_-jWa<*f8 zA954??7y&@X&NU$mbKub(!^23AY4)ln*`0Djp%>3&GE~Yjvf! zzSXg|VCQSMQmM1$ceWL{tcMY~u;VSOhIqHsg^_xrJeCf5u%5b~TnI~N+K`_MGcJ({ zrF+><@R^3>lWB^fSf7LSOGveu0V@G{+M(~{+^N^HbkH{%P*0Zb=qHm0J6ZY?`YEBp zbS2o&TPmTmTHTSlLci8a8ps2WAw(0{>d{ZKLB)sUgP(VMmJ%obo#ZF@zklaLQnm0L zIS%=JO*6>!{&&eDh*v)35b3tRnB0dv6x@#?N>!CaTkx%9B5@6_B~u}vVS4pammAIG zCFCE=Eq z7LZT9@NI0!OGYMuKkP`faJy@P(^ zKRhBy@!sq$*h$GPC3#ue?7lEwq>2pn$(GqcKKrCJkfG`MSq9+GTVDx%xO2F4Hu(8K zR|3zAE0eYYJ3fVVBo%BjC3o(>-~UJ2)TFTJE;VDRqPnj&8VK-1^t&Q#nM;<3H=KBv`JQz z_VJcbKgg$I>bI_tl zJ5z2g<&aOS`_0V!;)<+Ph>>rT@Ob|;*=y)m`&c7e?WoS)ft~Qy)ocfMVFh6Sg+Vz> zf3S@?Lq2Wdo-*|_scb0Z^X6X0v?^{eEATT7o_kiI_>wh4Tc?BTm?Qbj_JYmh30Car zg&Nis`Z`kIk?m+|Vy_^dwg#(Zx=@!LAV2nldzf6zY+`G`=d%uR(yje#SPt0fxS}h0 zH2V|#3G!tzv&iAZ7wjqMXI$ApMkwU463EH$#AM?0_7qzL`CK(Cn~Y4_!sbH1HoDKq zmnRF@P+-SVABlA*6;=v<4mes(w7MUW^@g@Ze;SF>WP_~Lkk2=;j{HjWlG;JMpAR+@ z|E;Y^9{8|Gp_WWhn@q-l4;>~~lFFD^vJmq5IkJdEha4g2A)m@Nw~4~hOmY-r9N%E8U>})9ZBGjph6oLIUb%V$|Sp!)D`CR&nNgbCx?};Ptd%ykD%GP{N+v7)}0wJp1E!R=)0)^flx&+p?bJ zT~U!1Ku%1ICHzoMb(S;a({7Q32lvdC*+ai0%^TS14@227V5`kPS%=lW>sLp}!#j3abDV?7|ByQ)*k))`4`0{9uKbCc9eUB~L7t=r_6 zB&KjCI}A2Ycz!17V>+__&{vNKH6;4*Dp@t;)2UN4DY2PoQVqU!fpvcDhj?iO_?(&6 zM7~exhWQ-UwuY!k?MM^I$*@nPw97_P0r`|$_=51#WO5gB((%D{61pRs%z=Ea-F1rm zbbCf@q2JTiTZpmKM=}C z6<;%L5BbaukZ_&!F*0Kzp93Y_H|3+O7TQiutz)CDj9C)cyzu%P>(L{U4Tiq-n%=M( zCW)*y_^>xJmnHYP%szu}T~A+R!9(w}VDP#3?>(&eMhUwCb}rWkv26-Jn4A!!9GrXW zR?n&+pU-OwWhGJx&w`x1y4zb8=^^1(kk37@>PdFS+ROVV(+6%ku1ngl ze$VQ`&uzwjlxEX zno9bTaqP_lQ?0VdFau#wjUiSoB zIpY+W0{NWxESq(0+Dt5=-@tv(SbsMMG6wkPhL7xIj1p-BI;-DQv#%8gq?4enx^ffq zbn0t55Ar#1r-VU^4I-vePzxcP^~y|G~*mMx(E z<3Eu>v0K?rV0*;^(z(?+)&q2$`(_Y@e!1*MFucz*Fp;<)e#1V3PTjKzvflF>bM=Ax zk2fY`hu5*~OQ8-YeUf^V(~^xs>pVlUjj5e=v@wPq7`Zf-qEgz*hAeJQ){BB41jKUbVB&2qTYOpL*w zuqV@{zCHgCCD7MSk|%l_D~K@v#N^H)lAw{yqI(%JVFkp)41maitC&A*UJ;14!aiT;#7 zWE<#w@7ab_bZI7bQE-h!!b!1nCDb4s_LeVAvLco@k~3g`cy^LZzfCn+1#KU->ci5V z%gJ+)o4#~pAB&!n7|_3zu$9eU!$@r;)JgYL)?s=Qu?72&R^4F3l-7~w&~|QqAuCdu zNge`Mw*Ab!bUTo7pffk9hV37+Qu+$oo;lmZ_MN_=Ole{s;Dh^)&9W8F5-tb%?6%D0>hJkY zOapWpLN-eeJ^anqL)#bax{zxMpV%_+VbT&?a>4cm%L;=z({=-y?s}d503SA!(z?D%K~Pu~e{sA-$RyH0^<7lVCo1)<~{B z%*k8^?6*KdN6%grLcaoAzWow0(4m{=a{zDE!+p@-1tWClfq7F8_-b`klPrV{- zp|9cfu`GW4Ez$;j2<&wfUbmelXF&cnHjCwW#}jYR-_r1yt$pD^Hh`URr_0!UyZ%H6 z>|eWI#k$@;FYO8anin*{7;ZJ41>-WpLc+br*vKkCCuMmv8~&+AmJV(EnAS4$E)!TC z@Y%bS?DnJ>b{2AedrC2*rw*~zFc!~@@37q94AvFu3e zC!eMD)nDOkMOae|Oo`%~*US-g`t^w>eTUs+9l-|;qXQ%`^*r+joBKSjkS#vD*aPV6 z%;E>+K)oLmt}p!u??`9!VeAsfe_#7SCPwGV%s}5KwVu@2R%V%joeV7rB`^9*W5NE6 z#%418>KkbVwB355j@ZmGAlHDOD}N_$`$LH$=saBVmKefWfbrn}WaT`v7T(u*1vY2o zT_hSi^GSQi=Y_I8gxZ#nHPE(8WDr@G_MOCn525;SenE$N@(#vs%9H0(oz4=P4L;m# z>@2nFBcad1zQ^SbGE=L1(h>B7_dSsr>i-}qV8gxm)ECwm4k-G+S97koHM z;WVkzOJov^?`8dq?5*8?Vh%cTS-H%mDx7SAwnHAgVG+t>i9OgX*!qoq()FN)a1RLVC{Fmv%vbra7_e{Q z^Pa_A-N{m+-?SGG*sSj7SvqjQuPbcDtGjG1=rpnetoy{*Y#+4MKC^;VE&9rI!6y4n zSZGo$(}BLiJip86fo3)ad?=YJmED>s;Tu3cdH4m>H8BlrF6bYelPR4)rHTo$9NIUK zJTEC_o@pRgz)H8)T0l=U+toenm~TpE-$ zd`lzA03T|)9hIpWiEGEYGs>(Vyw{xza>v~ZSj;$h4;=Idx7x~dsu}4Cc4q8KVVxc% z5qGdJ*Xst8OI=5bq2F5HLUz*0irf=e_KC&Cb|iYBlQgM@?W|ZOy(Z*vZxc(8+>&`7 zY(9pyL#1-3>?icKt1Z0ObfG(24Q*HV|IPNlpUrlG{Cv9#Hq>E?6R0Bs$oZe&CKE7%3#ovQXsviLW95BaRw(Tz)HgDAeYf_bdNjz%0unBl1h z<+EE=<00z%DWVGuGyjgZq~U|i6cQufqDZk@EFFM@&mUt~npeyI6Jej#4eUbp!9x;Y zZT=A)O87Uu-oVg|Rd|JXf;38?A-FFF5kKz!3-jZHq_^aEYsZtxPFMQvp6OYcs3Z;AJ^{G3te|D>Sa8DuUz{w*&t#u|btFcQsK--; zAN=`|R5?Y37m|i;xzFO0(wfkK_ z;j1^81*YO3>YH@yBCOSl#Dl~c{W}^W=^OhW$X9;r7x3R?rZ%0=x+%ds=`8c50alD{xPa5EUxoM`5*G@mQf39J5PZ)YJXb( z2d1v4Z`Tv%Tw*?0XWji-rYAPjHJZ;8dENLLuS z?GLzzk2|w#+rlhs4 z3`Ekj;1T`a^lQ-4%G4cm^A3LaKHlP9pw3H*CSAPd3WP@9PVvAZTkG&ZIFpzvC{v zRtDoo!szdR3aVAU7*2g3F3W|HeGRaQ+J2R#pk>h{A&q&5n13)Vc$E}Lv6#e~U<7Q} zYa$Km%T(AqzgzN?q``l50~nbPhURDHCC^G&*VYEA$?kNa2(Gq20r4~kNOzS6U4YgcE^g*fNa^Sc9_mKw=dK!}}X@ur1+za}Qz8$ZvRuc#15SW5m=dd`a<& zF71iV{TlH<(xB*dO1eku)?|wBvfN2=_6Hkr24PkY+%I?duNsd~-#E+8(Dm|nTtl2a zKAXUn-tX`fY4{{N05;PSaWu`VKaooKn0Et*lKs#v4g;Ky;z+{hP;HS(_ceHtcvinG zhF#VD@CflQS@ailJuXX}{EiK7fc2T3n+l6f=7fYh_;gUzo2~& z^&P8hlm-p?30;X37wMy?O)h+*F~6STiywwPg*1wVqU}{oUUV1Uk%r|LM2-xBnD>?=R@~! z46x6{aMIw{`3xStT+s5|e)x3@4p>o+ugHG1Vib;RQ;%MRw+c#%I{!3~2IY{(_yuR{U;yDuAwvqfSq9gLXMfH(oO0m{gb}~*Bi|Fef7#T&aCvb|i+{UIZJ$EG|i^Z4at?@s4J|G|%?S%hz#SdZR61Z?Kfi!R5Cjt;n< z`0w@pigD)y(3AW&g=ONnq2X9eZTAl`*h)18LkV-?`DNU2;v-(AzJEXM#%l#XaUgLj z4$s1UOKPwc`MR6^SMv34!Uh_LlLqr7H#!gBC%f?XqF%d4^|*!b`)VJ^=f_lF^O@SR zb{H7@7NQpMPqg0%fgah|jr?xtbPC4g$Dswq#jWNJSdP7lKMCVI@F`Ru-iys~tgiV0 z^_GVCkJ=%3OChISE4)c#e&g^zIICeTDM*9E*d`d>YqeeupmsKMtj(k)d+1#L;rv7@>`T2aVJjypa0^zPa}*JlgIJFv5>}cLW2nI4mHZu*)~F=A{z$6aUGn ziJ0>00DLFEL+-z&JhLfqYA28Vj>9K+g|39jF08_(wg=>gN&h2ZG9{GeD}cq}(^f z_jajoT=|tooKKir4u0}M*45bjyxr2N6ZjW@$ECzs6u20|o!+4jX&8BYKfJ!0hz2yb zt)?pB)tZ|)nd}dybMS3*4F4m%kI8FjZ(@nf&;NV=#Spi!Kl%{=7WKc-dfHVaTL_}QpS1sh?#uZwnmCoCN}+FoA83-V1A{)m zny=Sj0%`ab@B~gymf#rK?a$tZcc)&$D#DLBaRTnjilBKNbgx_o>oqGuPW)CT8erL` z0j81PzZdSvLyc9~I2w~xItsmO%bOsRFfpqwq+hlFpn3hRt*w*XY<_|&aoV<>i)xq) z=``lMCiNbw*w1}tE>5uVeN}6yJ@oUtMlKF*v81ikv+$A`qJ(2$^YSLvR~_523EIUO05aMU{)Qx*J>x7Aq|CUDy;BzPk9{i@9n9=hTqGP zHUD6%Q5zztedyI6*i`NUpJ+V4Z2JsR{Q^OsH1x7~4s|8>VK~J%c48E)S)C3O z3FEt$zU^n456x%lw}U;PYuRtuKpK7z(t-15YvC%zZYKRs$H2c$(1+%gMZ)rc?id- zJvcQ2+x)o*j)ZCOPQ`176)k7#B`JCMwm}bciF4NTUpUvGRBk}N27axuFJN?QYzp<4|3kZL6Nj(N!kYV%rWk^{$2BmLCbK;NR@Dt5Zg{P2)p%$m~PJF6ISHjyFManyuRbca(dj0jGVDqvN)rtS(m<`~Y zpN&-%Q>EKUFkcdn&ZI$8aR&~EU&RK(xZX*IOPYSze13d$=>u#K=V2MOmu@bF4QpHD zdD8IG>L0Ybv{70|8piZ*f&t$Q^hOisa(Y(S3!?lwX~7JnYsI zi#E|!sMmK{ON^!!eZ#lG2k|MzZrQN6`17}j1*Ac3^kY1bnt;DaLut@;{1E!4We()E zI)Wu9OIqf}(61};R_0&4PyCzD_rWz^sXmJ4)u?0Vq_(tntf%(dg4=PeqZ@HKVS3{p z`O@RnEpxK^K?gWI;RiO)Rm)|@a4hQ`ZYB+5YW6`vmn2+Ab36E9C^+QaL_@M)c!m&2 zcS6$%pZe<+%sy^~&3UJDy2WrScmQrA{+r>)iQM=c2sy)%$ zA`c`?Q=cZ#zt_6uf3u9{kJ_PmFpM}aZ7YS33;du5`8wtP0Zy&H2E9l_T)Sj2dK3>K zWMA6n4g^em+44-t7$Ko30X$WW@H~TEymAbj*OucN&S1i3OgG#b5{ZWn|q9u70;Xj(w z|6-3Ay?D|vMo)zsX6Q*{i2wZkCRFPFl$xK_-M`e}%>q5lqxPehzwl3-0&NL%=w2S? z?7D>gNkc(J3Tj?^h_=Mpe@g@!U4DTn)-lVDtJ%~T!>InJK)3q&YR-ndb`TgqOm`EB}I~|zE^07Z* zteFSoe@eqEq(7=d5WG8bA72pXrNdD$@Zx!FUMqK}KZoe|F4%n6a9Z&hcKT}L0n$+U z{10Srd?Wp&*j*e%HERnyOA(}DN)HwGY*!a~2Ju_;qZ*~wujTCszfxWYuZI5z&3W?i zy~-f%p)gXn%NBk?JzhaczX^Th@*}gZ{#;nU;`6_6L5&u*~=vxDwu{%WEjf zxe4uvXMP;rR~u7~oA@sr424%$-obnFJJWJMgcN*-=hUWe_(F(PHRuo~BC{imQ8vO0 z(y!sMNA7KnemyE*K^nTt>Au5p@$?=PUmIFG#{73!k`YG7mhRBkcWpTX78X}wn=DgwAPui3 ze8)GP4`Kwx?)>hznBgR16KU8V@EF&wOu*J;&l+?CH|oE^L4@yp`UoyEENMBDc9gBc zs-V9ZLj0?Kt6~4t1}r4M#)~dUA6BbyFKVBDnG+Y3PIu^pIo*AiyeF@2ISX4@w}&CF zKX4{-x_4a!suSO%8Tl%<-UlyTlhBpswvBEmgj(FfRb&Tqq+IuLY(9hIVX9NgT#L>3 z-D;&pu(WC*S`$Cqu7p96qU1t;4Hh-P&SMMWe^R@ga+o&xw({$QQH*SYR;yaIPL+DSO!ylA_Rm5JXr!k-U<^wprx(Zb^4mz&M@OV)?#E^#E<9DDYJ-a0rG34G! zFy3F-lA};@+z74jSHSRQ4b{WoTyi~hAiwr%_vPX9RM=XIOXBv^dZivsP(~O_aj|4< zQUlSXKlfUdl>O}|R8c$5aTa!U{sd-Q;dJX!DkIMuoCi{}`a`f7fAiqrbZd2Dmo(Ga!YILF@y%?Y!;<0lOJdl4I{?|kc2v>NvieTY-1 zC<3ofdx5XXmsj{%^cMfWc6>a(9cP4=wdAt)7LLQ)7wS-#@B!)Rl9{FoUqXM&$=T)c zsjXD_5#s-Aq#=)rt;JH(py8A!ubcV@n{#N+F;igPnSAU>7?<|$aMvgu{YgVduL~eo zeSk&8nW7d2MM5Ap=jd$LKL@Rzt}V}*+oM0j*z8HzoYTuX_6Mpp-bpzWyPegw;P2E! zdQKXabW&m3W82H~iN9(P-A66WmN(}N*I3uV<5v?}a)}m;%OKKc2P6=``+zU-xb7VE zBn=tkGr+SZ5=<$+4uhg0=s+4QB#hbFAi&U1aGdlT`g?(F`)^o6oHo(Aux)-VxRZt= zheG+h_f4>f=5~*pf_(QR6*i6RKgQ?9n>N<9|t^$U7{Asc~>#K07N33K?_@EQ@*tJfxCAaLpj_NH< z>~K2q@9R*AQt>I&CchDRS-3j#E>5B`QJ)ltDvzGxE5a144aU}cbMY=|P!WA`rTR~7 zL!1LP>tlz^fB1~X-1AR^ls&HruTw0(KUyK>n5ys!(s0dD8|a-F%79Xb#L;b^>;3OBhBPau3{w*Rj`7gZRB)KB2sXKQ`y~ zor~W?*;FGeptg114|v^668e!CxL3-xI8M#V@)jtcCCy+1s zg$8KTO}%C9&|dNvf*M!D6S9BHE{1EdN5Pu#-?qI5!__xo81WR3;?OZa5w;Nj_O41W zq<6iV?>NfK_k-t!?=5#9O|>QvHK7`0gozv38J-?%g!`nwhpwNz*IE@O5$9;`9Cx*6 zBm5&@<3j_aGrCnR`$M5;FWfi!8#Ld=G|XF$560#|1C5*Nz{9BD{}BX{hUC%L@!EE^{KVf@zaOr=+kolh*QE0$ z$!nDg51@9zN0oT|+=$MEv3cwvH~U%Lat9aCr5((`AE-l|y2(bMcJw{YB42A#{lSB3 z{w+v@TSN#b-rhn-vR^Ea;MIfUxQOs8M!$l&-ECUVFT$lFxV>O7E+ziTot3c3@rJa9 z{H~bT0L9y_;@i=f1evO^q`fxshlDvWqX`04Ra)*M!yf*FCpG#lca;Ctmcpg}d*K_6 z`8Mrbs4=<VHAiC0Prz=8P1yAF8IDHHaS-(H0QlpKkH zcho*?6^^a8jk$)Y z3ND=5ghwbAHZv`yiDon}DW2s4f30EML=cCywZ3u2-c&=o{;pCl(%_fd2y1q=*V{szUFpstrT=AlI{AXA2G|Jo*{{JR{|4w0kH$F;*^Y^zApY;il(4GsEfkYq^L=z*ZTh{X=1Oa( zDJ*WP0yV<;@9F}@ZjBH~`u|k#lW(K7;}vm^@f;ercQoCD(0FQAos@3aSGDA&qof`< z*X0{D*MP;fHOHDGIZ#5ei}5>zQGSo$A!!(NCk%JK3xjOpH{1CLgNGl6_Jr>?EeAW* zEQed9M@RJ=PCniX(uv=1NEOCgpO$Np2FK2g_@rXh3`X&_q_yMHOMht=VWtN(qIrC$ zmYO%1SB=~CO>hNqMm+kCwR!vT0BI!mE1lN*-nn5$iAEI?j3wz<2b?} zj6RClcZyqT@EpU|(4EU)^e6ref$BK;bOT0`-*G8dq{5Xd{0_CpWT?e&s%k`E!o1nw zA|E>NUrX)Z&FHpJ*tQhM6X!*r1t9%+kK@SK5p92XZt(==q+!aK5U4S`jeE%+>nOor z{S(++a~SyaC3G}i*YdYyEG~k$OG9uj@lTpr3H!#~mgbV*-@O{Z*u*(rgT|!0i3;03 zYK{CEVFnpfO~u*<`Ar%_W2)1;aBnVjB+fMW3FmhC!W$a%nMbKMBQY3|VljUCQ~0$Z z4hl#^#{Rny*EYMQ_A>GLDKIGc+7eU$Z+4J8y8_x1|Hq&a@O583ylb9^M`Pqgv#9=? zG;Cql^(=#$pcnDmR?L;2UaM)T1I42VAHfP{3@-;Z+9QIfF|JqTj;*9sllwly*)%_--{<1pk zM)+GZv!zsZ6~2!&l=$u;l)!TZ!!(U=5n=X}Nz z8qZN@cEXI|&(V}LL|F&Ir}77=M)BP$JOF3C3pk1}a4H?vc)7QnsqZNAVb|8FxS2Fe z?DYqXPUK0qDR$8}Yhg|707;eR)%!Zy`**C-YfpBCK;QhRPL~fMe6?5y&vnMN)J`vY zRt5t)ZiisvUzzv?_UE02PvlpfYP$M$jD$VZKGp6a1U^WGO@w(8b`i9z^ID$y9;H68 zbKkHzO-!*UwWM$eGq^W99?EQ~*0k;p zY(D-HCeV8syBbe`=EfojCwtou>mYwcC3GY__R|36s0MiGM0+IRj=YNMg1*uF4o|p` zp3D9w_(AWL^sY3O`XCb#Ua9 z>)>H{G2T}e`@)Njdu^b1|J2oxadisj)l&}?$>)_ip`PqiRV4h>>Mg>JZETEs10m_M+AwuCNXMEDlsyy&Z>fN) z368AC`XuqA5Dx7OJ(xyFy6C%TIdD@2Tbz_Bp2#{a_i<9Nxp|o)`1(sJ7d=?dAL-)q zA`=uIIkIQ(lf)BU?%?evYc?SDq1bo#AME_gn4Q5mSr)<9)*i zvz~u;iDz!i=hw=cpo`%WF*14$->pQb`!bMTiQK|>>+Jx;FUiXJx7>K8QM!CfXF)kQ z#)k)14UwkT?$!# z;7_`55e!t8a`-xyN3J;{j850%`iA=4!Z=v?sHMs4J6iB+!w6x9Ry*GGd^2C&z=d!1 zX;_!PlgH+!2(NbRLyh0we1Gr@!R=Km460LbYvU}TMk&{uFwC24)no|DZ|X3?z=gj# z{7mpwo`eirJ3hKS3U(21pyG!)-w}6LNK@;~-a5_Vkz+3juWt%$=HZdtE%Sijcy}h# zo!Eu%ow-5KnrzOr2fV{#-~WV5Z*AFz@d3EtZ-s2@S7#OzJs5rd?vgc?d9gAt-}ou* zaz-4hR+p{0{n#2k zH!)k&nES_-L$;fN*xJ^bM>*UBHmirY-qevF$~A-iAMYsBEIfEg^a**O(XY^=l?rbD z^?)>7@mXu0y@L05HpMZ0ZprHRd+@!%f#qO6s$>m6xBY?Ou%HP;;CSle|+ETt}8AsQYNi1ByI(N%eDK&EBbC-{{2m-c1(T zXas|+#s=PXMVydk^%XRpm~wmbTSDx@o~*mS9?#SY6mCx($0p_t=ZD7l2`+o|*~e^E zuJYDGIHhO7zRga>V*tOwhBVcP%=zzbfm+gOTQ}xLjar zOAm;`lv(WEx0&p2{6*1b{z#U)*_;(Exhs0+cBV6i9g`kN;$f?|;MAJ9%$|vo-D&93 z%A4ioWr(LH4TA6g6l~nWEb)G&qn>vcA9g6_g(zQJFKy9qWhvcLMYHRE*f`prZJeJV zUNWY4O%xXFwiqGGH>&c_srsxsCRm*8Kb+4xI*vt^91(v`(Bt=|o=nYbtJuTUl$#h8 zLb2xzG5G6x9@6J3B>1-#PrP>Ghs>ry?!z<6ORgVd&W`-=g(P7!<(xvddT_s_bivAY z87{C^@JX4OLiqNh((`o+J}Wy@IBar6?&j>l=cS|zn`@Rrk+&mHy_O{W_PGl&*R1(> zpNE3iyD~^|G3NT2VS>l%e(bu34*#lpMmXWG%|>(|%tiZM!i$j$*t@HZ=r!3yFi^K- z);bcVM-33{^S7`RZAY})m?Yc#!HqcuK9Sa(944EQ;lmb%kCDgN91h)>tYH6@>%bM; zGs=qBo=iVC7{XSx6|3`{SWcfpuv|PtoKwD@eY@I|%^kH>yl}vjeQ_Vhy1qRkKA5e? z>f-d-v)jR<*}35?dz%H*yAUDD6sjy`h&{7s3F7j7si4)*m9_1dDk_TnAh&}LI~Dap zjGEsdXEh48gXYHA8TRp$RK3}pFBxLe(}Aey?84ryekT4Ldm1vmqZaPuC zJHd`WzIFjmfJ{Pu>OvPC# z3O+?EODM1rq)AVG_!QGj!Q;bI`Ri0SK5I*w@W5a@%uU|HRqP)N5wQ{^{awSOy&eby z1~$Ri#`%2Ws8FFwe=uujs?B?3oDgDf>#*qI{kWUpD)hZ#%+xH)P<@rYz>}=m^13@X zy?1vZFTj!YEiuK`J8sDe_IR)ls)wYrD+;t;+bNh%n^XsI2Yd!$*p{;+L+=9`U1E!3XIN#%E`D$(*aa_|)>#_~~SY z?95MRo=o|~B(wj7>_S_9pjrC zb3XO^@9FrOnZ#sw8z+| zF*klzg*X2e@CidZ5QVdeU#N&e$US_-V?X=NF)2>2#qd+rSj(ub^boM)2*k zgLQSEf`6<}%fxa|R@HNuB#-pfTKrtW%qFMFQ)Mz`P(1B1(w!jLKUt{}>BcOa5SBk2 zC>{>p!Y({+f@F;);*lp*Q*~xA+x~u+IE&9`XX?cfkFu2P-a27cH%pz!*mbv&_vDX9n$)e_WjPNnLiryO!yQX09vuOe2lv!{1@~Na=M!HH>!7qdz-s3&Al_Z-=>Q~ zq%@M1y9)g9ul>T4%d?pMyH32c`#Pbf*K)RV;v19=pCBar*|CTrCo!_(m(0n+g?0Gc z4lzKi*1)juH4nk#M|YQyjDyA9^_!LecQ9C=g5VmR>qx^mGi z4}NIYUU{_P+tA6b3T{zxMr!-MN(&b$_{$Y5FtzZW?BX;JKIV2f&Nb{QEbr&Y^}bi2 znWLdFTg{q(wovDlTJC~*>>_SsJ&BjyJSjX1naY>HT)@3@LWSGfgSgcVOTMm0l;BD4 z*$gn*%I|-8EL60L!!4TbJmNu`u+YaIwSV~VkZqZQd53sueyoE3Q_m7E=j+Lhu6pub z3D1RYbk>gXcH;95l7&qgAy93*p0{}%D|k#VhWfWl`0{|8!rv>sSg`*L{&(4VVW|Fi zwjp^Ke`2s#_+o3oE_k-(Hg9PSF%J&)KuWSevEvs=^moJW*GiadrdWpmiC%hqe~4FWJH8x@&{%*9m25A1^-6 zrMLXC=Jrs(*9xAJmnEqMj*-=Yx|uK11p z>KwVy>4|VB^%l-}A>3-wc;K-xmjs-KAc+G%KwZAIXc@1N|=B#4XhLK`V&9+QG!JfG!CWyaI zJ_WPgt}MqYReYDe2R2UiVJ|+s5O<#|lMk&>Fek$-QE%M%NGc@tPT%c=wL@uya?wqRUKnvi(J|L4OpF&yz8O?fb<% z&Ds3!=uT{0xwW{?cR7E|U%{=)aiaNqJAU`-ahT;_s*F16!aKE71Ea_t%J~M~{9tkA zj2&!V$e2b2chqZ#%Dt;(E~(!1{5gPQKIF^1&+X(UKb~V3tC2z*o6X#{b$jmhY_%|V z_e#E~N|Oil@E1l0&gJ59IZtZ}6draN%a>kQ%8#qw7JB#T!4;1;@Kqn}f_(V037JA_o7Zx$EpGhR&@`cH zsw)&~Q!b|bkn*R!-GED7rK5?VJfxrxbw0Qq4>lQrat69J}>*Y5c_5t+f|~* zgSA`)pS_FO^RQnyW5gWcftL;Y-1!!!-s&Pu9lV`YU0H~~Ohnm;Hy&*0eNRc5@mx!5 zuY&Er8zlD_tfKtE6f9}pD!9BbQW@UegL#gQgszHSqD$sBmT&qObk5EbCq}MiDJuQh z+$kPn54MO|f1Sj-_B$oUYffb$vyGUywo;4>9>`3(S+RjOQDW}QI(QklmA<{2C>r_3 zfYQ{REzV67=dQGaN%eF-_0AM$jEj3il;lRXQE52*zraQ_O)BW+UwpFRcH6+-MYAvE@&jx&a zY8&Race!}bZ51E)CK>!s4;P1(*z>KO_dxmeSIQTGu6$sQKND<)+HGe1 z^pR0K|LQ?Oc+Pme-E3a<_mc46Q5lbjUCtHj?+J5Xb>y$wY~qqX3h^CZ;rKf){L|-W zLQwHBoVCoG7Y~0SjNjiI3us<;Uy>zEYs2Fd@w6{>dm*Uhw}&=9J9);T6v0`35WJ^v z<_UYb@byv#q%B&>``rl_W|_5Tcb3iND*LYp9`i@A^KoOimi=L2sUk!j-NBTLCZNChG1;DJUM%91s?<{ynj9B=N%hAepmLwgPpJ9XW{8gyGR$E8cfjSZ_=%-10-=*MpH z@WXlZT?t)wc*R+<>Fq?O8@retes^7LeMyZeZrZT3<}u>Os-IxTwzD>~pNRL3Zo=2^ z9&FI)=iYiv9xmA{Ao89<#knTtdl=s%{WN%GhfU4gpF{amM`UYrw*6RHlv48)SEHr2YJ9o}s z{MT(RyRQLs*1aH}**b>xZNH4&UUOSCcInO<)i*M=5%Hp*eLn2Hy@TC_r=rR4Ah25C z#dgil5Pj~A1O0pjYd|fBRcWu89>!y(@x_*8yxq};)ZaY$0=!D9-3LVi`!32Q6s zsIA}`OD!=d<$>((S9gB#=6(Dd)0_UUxA8Sn6<*-;h5W^9`OQoHxr>gc(DZB}|6)Cv z-|{{sIEhpE!e}F&e?lpI>oAZn-C@P=-;WYry{*9kge1^4QdCCuHmRBmAI$-nJ>E)*V_4I%%wbN6>oguGEA@Z0Nn z!l+mwpwD-xsWaih`8Nck54~B=@#(zb&^ck`!U^p3@u7Ujd|%<0jUi+G+wgJg%!N%~ zR@`DuN+}2VQU)(= z_bZ)Fd$DPI&cn|Rb;^#q&TRgukKq4$vKa7XBP*@$%3?>^i4)tKu_R$Ms~CDnw4ck^ zn5x-qxy(RD`_GiesHd+Xly8X1rxko* zZKiN)>SpQrXa!eZ%M^UOhsqr?+_~?pbRp`C6(q0Q#s^7>f{w!jFdVX$d(Mm&)@`o_ z`{N6_-5gP<`_`XD*-hc6mYo)Au1sdn9}eKJ+IkD4D~;HK5mfULWh6v~TCuisqjBmx zH6gF#HshzltOtD?fA6|0$`!Lc zS%>c;yf*46TIOtLvB}@TzM6^oigoOStPgvu?<8JJHev5hPGAF%9TQEBr?WkwhO8@G z6O-ga+2X#d*}ck0vD4$$Z0H&X7B%OQxKd1lwO?J?%X_J!>MaE2LuLZ}H-DHf9K2T}NYMA?4-uvV=B? zMe!Ogw7zuD6f8XR<%hbuaj)!Dq3vjINI2)fcRD{3;`Swi{@T@i)PMH{&~MGc>kYZN z-!-8mQ-g)8P2~M*j|sQ4b=ml+KK%Z~9m2M?ChYg?A2{~)OyR!nIu@#W9pff-68?tL zI&W@(v16{vs%4&R-OcsVh?-cfwDSsfS6{T&!Ws%7@BF(eBJ(Y!rA@ z_7NAcZ7f9d9~}9*Kx` z-OaILiS43AcgKGKCXCTrHfCDY+(LC1*U8l z#2eLC(){tBOvn1U==?|@Cq->%TGyV4Az@*-*>oN2{V7H~zw-xPIBvpn_TLcCI`!ce z9i}szLFdG}+zGtLcMWFrXpb0BV#w7TS~Hb-X5xbRt9ja=L|8g?sMyxmfhSG%fkC-1 zlxyl;d6%p&aw8XAWsZXn_gPmE-|?reRzi`2=QWJNdyNNWVNPEB(!W5QxTQf>*sz1= z9n8bvswqOik&Qg|VmF>QZIiI{+%n!LeKcPr9ujys@FMRy-1_Zh;nh4Xe&+BBKDbA? zaOyw@K0vvNJ9Oqk#Plpo8@QAE%t#TgmmkKS$Gmxi=?h_h@2*%+^YSn4KX+8nXGiyW z^OS`z1ofX?!K3$19zHom2p@X{)Xr_vaH~yjjCZTiaGS+TE9tJ&{BIsV+$kv7h;=gb8vdf*EDd#W} zUDXcCF8O$|VXHsHJFlLkwW~zIHY_ZV%iilMHSB$u?tLE!pPi{(Qt8Sv^^+jSbEvp( zy94WVsWpo{ZzkRyvzl2B7|PO0_K3xg44G&5=}c$%IdR+T3IF5hyyK~U-#?!AR;g4P zh;u7SLq(kXk`Wo%B0|dEdpprUlxS%$&Rvm0rEu=6WN+Gg@4f5O`o4d^zdRoPa30RN z&ilTv*Y$k8E=bsI3oo`DXXjUshS>qDp#0-`wq^2bdbcqGc9hjKBjcm=mtGPy2DY<# zmrZEte&MxyceBB2o?=6xPTmW3a^u@^S=+$`m^ZPF%^I?bcT5O_h_p*=)9bTby~Y#h zhqLU!Bsuj4sl(P3p6ENhd4lI1Rl|`$~Lpg;BQ1La1Wkgt^yx>ny&9h+R2YKO~ z<})0v&;BZs%?Z_^|B===| zg!Am;!frA~<)eYEcQPuh=peysH0k08Q8>%Lk(8A05tt5N9N|?%%Eb5SHxEb5C^|tD zKM#k2ffTdK_K-dkHKF0J8eV;|fdtkVgS_5A^sDnArsx9UYrFWU)ahhMX8`Qf&f!V$ zR8+Vi7Gx1ac;7**Md|xeAjNrvJ{uH#8^=1>TQhXu3{5=LT z=k`#q`uk{O*!q_%`<W zt2Xr7lFKZt7h=fB(O@<;k{!Nkiz$AuX!bE+!3C?ZDvi;cZv$D>%LqK~VocwkKOl{; zO2XPKSMiklWku;nB)DX3sqDkD;i8UFLY*93%@sdXiB4uEV9Bvc?xZ!AxP1#nrL>>i zvbPnvob8F1>L%doaVbRcwIvz`&cmxt+eqjE9aJu}LXig}34Av`cn=Ss4E*mu4r zCJgtqULx7U&+v$=3Ao6tjm-1$PhhwA+Ps`H+pVAPyD;z&_k1Lu}Jec(Hk`ewngZn(xIK?ebOwbHJ*ZY zdg(+f#2hBn$)VLeM-out4u0!v`J7=>$hY=j7%xuZjv?)$J6iE@SL2TCb{`$l!gZ-I zY0h7Rr8jJfB82|n+7~Tq60}JgVxJ5&bT8HJ`X@E2jRLn%0#7?}0h7%41?MI5kZu>q zI@KJ3253Sj$zki&D472+hA4xBj8&?E?ThflFbD+b}5MkDxZbb$SuBEn&c)4^OJo0&TRRzDjC`-b_m!ck7x z`}!RU`8v$>n=kI3yo>ht{ZCqK9*qmy)M?k245`V1WE{Al-auiIN>T5(68uA6%B%~i z=#^6{ZhpCjzv%1{m0gI#oQw6`sa%B^s0O3Vst_{t8f>sB9>(@`M$xCsQIFv9J?sxejZ7fo7qnGK3&9J zg?_|Z=tt%>ILMw4lHi5RF4E7gOq>&$fUCc?lGk&5>9C$q{AzlM%<(-(|G0VLfkS7B zSnEH!soWC(ZITjoc_sMnq=Rpxwi2@n!9g7`9$!63BpK3t^~^Uqs1S~8;g9hC9piyg1%f=Bt8Bq z5jNg9PE*Q;upWm9FqFKdA7&Y`TP@yj+h+{?wuxp3AKAdQ)>+U$cMA(t*Mp74=3q6t zkcqxd2F<(fV7~J-8xkQ0M?VKcE5FF1+Aq>{(|Dl0TAAtD1bQSl6&lsLnDVt7V)MHa z*gmhDH7xBXJ7*-+rEv%QxpF4Icq9r=&u?UpHTUr;gN43Gv4$laeZc7}2T)vmf;~SV zk3|o~(AQ`Wv#Zd=phz_s8M}e4o@0XL+Xle?$`wpsIcQtfk( zq(xz|*tBRME$;D<>YYzPm6RjZX(#%rX$$B4f7+w?SNSkel~)QXMd$LUov%bAF$V7( zyUe3T&LI282jI5TgK*I7mE>K=GTiSYLOMK?oXa-Cs?C6R4(=t2R|MV5!U=syZc3B;k8CGXL$jyEltMldpgJiTQxrBy#%KUI>tlQs+uf|R5W|j zNq!l;5obsRJuX$4yOpQW9sdQP+UE;IlG;GGZ*fDHj0!UGa382qG((jZK|gt`3||Im zqt=vM@~vYbO!ZU1_Ms8vo3$Ny{eHoV)=;wf>ncd=Bjx>sw6`Uik)RT1$RBy^6ZHyD zf|>Q!vU_k;-SC72HXb}Jett?py0@1Eu3qq?M^a^iESv!4%IE114@LIlL?{$q{g2j+ zvt|iep5WrH1g0ZWS$Ui#tob(&?saZsg9qtAmbNvd*E6=a<2a%&E z9nkteO$^+hL);IEu_DL>dv+frpJ%Ay?d7i6aITD)7!E*X%RqF?N3znPgYU?W#pgSk zN!pz(?%a@qGuL#IC+GU}lY;*F)V7<19qrWrWuJm~R65CmVg;&nI0pY+Zz4bSw$N|y z{IMj46HlKj)UIF|t};JG`VJlpA$CSs@n}CeaZCh0xzlh(;YO0(3Sek33@?B4C9P|n z1V-XE_x7Gk_)g<)_TzySu$kwl-At(I9y%fqXaqw-iwFS z8cUDTRKSFE>gsV-YLycQa~C#Jn`f$Q;N>7t_|^xk+Lp0t9&W&ORG_qTEwj3}7`hbn zVf6O`=5}Ew*lx5Fa+iyl)kpT%c^2`%wNzj%Sh0i)W9OlifCq95||gYGqV9e z4a+6qE9l{2v1a0b-%`OMp^J(BRLaUt65v@^E3-8Z;F=plVdjua?8S}q{L^m_c;RrC zNm73a-hWG&swrg&CzNpE`MFT{IiJ}rosX|;$HBO+1g0EfjVS}Z(tKBQhK*i0;8{5x zZ8nPO-wngJua?s%|H`FTM+!|T3q(?m@Rf3P)t@(~uOti5r z5#I>=9m&I?q+w(P&VTTZXW1E(38CINa>Q74_KhKr{cJGTdo~&m&Lac1>*DVzOK@#e zA*ozB89iVHZhL;3ylU!&S0DsO|G7v^mtEjyae_Xg(MpVV#d5ErRNOSbi*&j5$i7^Y zV8E=T7M`ZSWH6Z`3iQ$Dz)qnbQad_*H+9B{|862dHn zNyRELR^Hl84pS{qeK{4o`)wfVMJC|(sz1sfawmFQT;bV{cHV!22FZ#JgzPa{{JYiz zku8e_TZ4YQ{h_PqNlyyYSO3y~cE!4If$Cck3`xmksftFhdaxnEGAHP|RLYW` z4uv&|exPD1V~NLa(X1oUaAQCddv|pQHE&CXa}^!zb(9M2{aFI8!W=DQ(h-AYa|B)f zMkmub_DQB183zFlEvy{Y^5Wtk*js*q&G^#DEwtRgd0qv(X5JUy9$pOl0}rzYDJr-o zYNoJ1XERH6)5o6bQBd?HjOjGk;ny9{sgJvuZM0pDwwns6d`^EhJ}45W<%;Rnzq_S& zTayqw429?QzM|!o5?r^UTDENNc+s@Csraxlkh}jtk@n04?8z1KinGU&Sl>|Gqw$+R znX!~SYxBTgy(VJXBnip?X@Lj#%*PEj+sTQ*x%it|<6m-=6h)0g-EUqv^kXGC=Kh60 z`xl0F26d!Zvz%v7PZU_+Hj?k|%Hymg0&&zuCZ_C^&5xJh$46b{Xx&;=tj_7ZFPqn7oVBM-?MAv65Sla30sxv#thoiG$^MuK0 zy*Q10T($%TMfF0(;r7H-V8?rQA%AylB2n`Vfo=U`_+^(Sk=B-YP+!z3%ZZ&P+I%t< zrmr0<-mDs1B)cqdc2#p|)YN?Gpi#+iH2eS^;L)48m_|Wq*CYBbT92is`#{ry5wJEb zn0?T9fc|M(kUw-2yDkz#-hC6u{dtgmJUkUy0Ykz3o7YHA(B6GYY>=CVv zh5s%!vwE9M`tDu|SZ?cN=B<7HfBxPm%-^kbM%P@Kmje9`B&@Nb2WzDTh6 z%U4;N(h^aLdMax6S;s3MUKgpj#NmjNCSE;Sjci*Ng!gy%#kQL+r2N0-XwssBAC{~m z=T|SrokjY%ICK|jo;nj}$=T!lv&F>CZxkw~tVWB=Rpi~XXFOtKB%ZQuAk(fK;RQuW zSYO*t{0ABElo|=vPv|C1_w-~|k5f@Qpo^58;^JS53FutXN=hM^ZZ!(U!me6!YjHK5 zu-606_dQE$ul%N^=PdB##Uf(rG!c@g%tiUweB%9dKID;cIHV_@SUs?Yz*C?3@I_|i zrP@kR2`l3pM~@_(s^RdkX&E0EeoEwRmC&1N5HcAN=&Iounv&X0w-q*!+6%~EiCGaKF~=CK7M zbm3U;61dz^$Rw91LERA{3rg<{yQ0(!;&VcP>({c7+nhc<8ZY!Ut?Xq~6kT{e6`B@z zv7bh5;_xmBj25_^t^Fs;8ha&!!>|sfPj$G4dKAp+Y+&1T4)XJkKCpXjHOtR>%me#4 zfLm4xoBL@5PJe9xN%6axXRQ`y2^^8Gz!4o+GQ}DC{b75$8%zA{ir*)-(VnLw*3}S* zAG0&)(qng}C3j=-@yg!Rae^pZ!^iKgNrae*ASZ{_mR3&8n{B+ z84XoVl8gmIvAN3+OS5H!>EGn7ccU?JK@<7nx}9shOh%{H4svtXWPVcMxZDJeYw+Za zHL2rL(d|+vF?Rkbo>;mc#i|bT>3jLp<@f7+@H(i?cC>d<(_tD+GIgLW_miSA;Wwu9IuUGf2a+-nY#dnwQXmla}JbhJ3!8f5>{F^0{q7Xz?PkyX`j4I z4_u3dMOT{HV$7g-o~1y;?oQVCT5nn^a9~El_ub~PT8+)L6lnR^!7h&+$I&(h61F$7 zW>4XLjrWI%V>nyme~sr1Tn1NrPO>d82jk_kMKH%p_`a_qxIp02(tc#IEdr-@(tIea z_4i>aYR-bLbCZ@_n$27q{BT9icKUVm7wLp+(HQY(GVS@7CN+GTj5nTT8?0}7QWzn; zuS05o$VT~EiY`q^#jE-2xU}tt=(R~4hRtr~jcIB`**^$-UGIy^2ChVWZ8=VmS4G|Q zb!4s9VoZCXkG~6dk*&99V2zeN_S`HcT^gg%df#e1__m6e_&wv-4@F}4ss`e|(}>m8slGMf+7PMgf0o8BSq7*ALLc3&0oz9gRb^jiwkwLbGV zR~8eg`ASH>E$pk^GlC4H;jmuf%v-!qibmTfg0wqNRuS_~y~I@lwHq_Vy)Et+X@^Rn z$Hk6jYZXho1->$OMJZj7Kb);84~MqvAE?z^6Sm{UN=W-}ES!BB%MxWvK}&HCeB75O zcy<=R@3TwbzjuXf;h{+|s!hmsSbm1}D)~oqj)#D=V=ePH;+hZNcB}0ZxZ3#B#NRaT1xQyge)TDpWwSzL)0tWM_7;s z*0?!irs+v?^z#rj`QV4aMKUtt%ncs>DH=V^n}~MLHeUNB8GEjDkjn5$+~|h{3oX0J z^6N=8uZN}L*{V*W)AzTyQZo*(j&C9MOV`uDMM1*fy+HJzHPfoY%kg$yIjPj_CotQl zc(eNuIqaVf%V@miF@lSORX-ag5+W-4c5IRJ^wKt)N*U6 z!Hfy4Q!W&OhX19Lt8LgtBM+#4I}x00*RTsl7VvcW0(kv;JDbJkz+?TT@b=(Q=2WZ* z7{3x4+|IFrgimzE%5aFusbfQwPSJCI0&C9O*v*%Ybg7r1X?J!p_Gq(MN8rwHU+rR{ zHrXqtD>`GmKP z)hD@qeDHO`NYsB8LOvAP<2Qv?mtWH(z@39n@7lcXVY2;9?LgvFosk?ns7yc(y0 z(<8IU*wKr?@!$~Daav7=ECEyXZsun~#M@d@;fG@vQ)q0E)!mARC5f#} z55oDRJ0Wl{xt8^_mhoVD4=B$&!>TU+^SBfwG@@=KT@ZYrflZ1mDu5WlE!(-v*LB(*w4j*W_FZF|0XA*{E!^6utcA$mG+0} z&TFeNequFoUi*|zi?GM~ktJkd!$|05Vt{S$cafy{8L&1*6(x7pk^ViVu++34rhjlH zs#}-C;|VSNxS=|kI6nybu3gVVoNkGBtHr_nAHQWYZ!8r}9-Ima$&m&hOd1M%1Yg&k zPZQ||$2C&v&t$0GyNxOj_$=M>Uo=cjzd`c{%w`(D{oux}A@Jn%YW6P3860gjAn`yJ zYkq794sHU|JAOa=+(6)7gEOe?JIMyv41rxHp{7% zm+LNvX`$t8_RW6y#7p>}R~=$^`cK98|FmFP^d{C?Zh)#rBcXS82n%krM|0aJR9d=_ zIZpM#xP2RPFR*3^=V7ar$e6PsxFkl%f_Pv{uH0UMCE1fOv3m{aZd@Yh=L^u+ZinF1 znS&lBOYzz7qvZ8SMQpyg5+@g*BTMB!@<%Kjr!>?N<$_Y)mY0ae58KG!Ry$r4EHE}V zyNHufmMq^*f*V@9$gf{p#7!=VSXkahbbC9~kdROd=%4>b*a>SxjC?&{)!-Ulc40h` zpBM_+6(PLLtyXkTE&;rS9U)^fCW}gLrow=yv&A2y^NOYk-kl8dg~AT;0%=TD5|ocT zLXSE1V{?ilp!1YG**H!e-|GPajOj3at6}Lu|=( zRj_DW4i_Jlv;D$dcg%_)aErXa#`!eU8gU%tX|%A_P3!21v8izXVkg_$_ES7c@WB>a zbTg)xQFG&EGCXPRVBVRNx#qoSXkO67l9p}fYkT})+$I?_)w#(>%yWj9>L=OdnM1L5 zk0D%3-p6VVYoJyFflco-*_r)|F#6wMn6h*g^Zm~mBlcaRi;}ciQLsNI?8>JJHSeXW z<}r9<$2i(IGeK&jmV#dfXc=rfmQ%P&=qa8h^yUQ~PNJTdDR?0*gC8!qD;jk_78l94 z@z$Fn(z_)PO=tHd%jcyVz&Mmw~UVb)Q!J2wQAXf3I0;Z*PF3bYlUA(KY;0_9Ch@M2pbslF!ovtP`{ zkhnauVze%_TpWwvGh@lkXG`I=%Ll$`y$Nw2>fvzv=x6$1 zp&9!sS}Ev-@+S$5? z`rJA@5?0$aFon(|yd`Bd+`e4Jw4OZUF8%Cb-}z#;dgUmTtJH_J$-7veku$OSnhK~m zu49{*FUH6{eWB)-3v(5;g4k0{)M1<&D_k3dN<-IC#}C(~ADrW`b?rBC=9VSWw5h3h zvH$j(xYM82G`>pEe7G`yc`sd*Drgia^=Rd+T%ch&`Dp9DJb1wx?ZS5p~9`>O{b+Nd)zL{KF zlu5;hgqh6^B&jWJRH4lkUB{FYmen6#-Z#PPKM#@&K?}N&sD%*&Hj!K{F>ERvfi_ve zq(s*N8XrF5KhyPyX{rwlTzh~I3+XL9qoTmIQ^-oy$rnu=DR@ABj*-ol3)1)T_&FawYXnJ;Dle9ZO9xAes;@*jDbwCK*3GM}d``EKv(L%1xl*wRgk;W7q zmq4byF8H3^!K7?998|S|f)&TuzOb=ydZ9P0`0pI6IQ*U-ej5(tUmYtMbAq;>PlWGs z?d)aqQtB2j0r|&W>{Iz#ahkOR`d{c`6Nl}T{nAQ=E1TO`rM4^oAQui{w2qZ3m-C44 zUNH1iC7bT@g=-5G&@ytAosS-eO49i-&Sg83^O}nXhEIgfxe_+^y#=Pv`c0SXEM>=9 zJkVuZ6}`229NX#>iuKKb^!ZPeDhQe+dsr>@J}_QdD0p|aP>|Vr?p4n?C(N#+#a#L2 zZqcS~f=_f~Azz!-pBxH`M34OEyvRjND(qI{y>g*0pM{aQHapz!JriAbY$iHE`q;T| zF^2gbCYtM1&|Aw51LjqblY-W&bUX;1$}W)XUya-&JPyCxwU9p6Yq|NXRP4OgN#y2! zmT7zz`XaM#GH}*mgZ-_^IJ2UI#I94JHw&Zj^}r?)+P;IPr}*JcGa0GbcZ*J}bHYu{ zrR2)3p@8y+xP0(FqGB`+Vqb`GVL~QJS2BX9o`Z4r5^o}2xeT1Nukz(;(GkxT+y&P-e5K{&fi)nbpmR?R` z9y4jL_C!p)x<;&UvZrXSFyk;Z-YqLI`K{h#D#4p|%X#gCa?z`?i2`$1&T|b%k#qOL zP_5rr&X$>zRZU*F8OPzymIQJr%o=Tu&BY7P@`;?se0-#BiDasj=vFD=sb3!W(Ecp> zn*NKYX9?Ql;7i2%&UyaDH~}rYTFD>B06yuf;B}1aBF~SUlNnV=P*0(oe3`ab{3I<2 zw-&XN>VK4uwu;2^Ne$$LaS;Xe)fk&yMLZV0pilDbaGqN+S<_zuzD&_aIk{cLtzsq| znx}$(U2Dm~(geHppG!VM0aH1g~3RLSM8Ah@zIotr0K6%E}O2g@J7mj$bv zi0&Drg67#$gW_Ami^d7Fu>BuZX_)?c>Cc*EP|My)#XaApSsBsr-0?QecAm>-*!w}( z>|s#*)R&cSbb{hd)8O;rjcimqzQvhDIG+!_yTkYRZ_K-T(~qGZ8X44>I|=YMA_86DIA=VXuye(f6M` z7$gNTpJNW#D(nx4cGP9dZ~EZyU;Ai|mK=lhD2#2=rk|>ErPJpMtkc`U;*qmf6PZQ*@MA?CClwW~~CnjSU zPb2zI%yIt}UA&~clUOOw#`?WB70``dvhio*Tddv?5{Hrx#Qwp0YVVRzbR(0yO;$XT;eKw##XQ`)lqoY< z&zJzT&&Z|s&c2cw*TkTs?kKuC2k;TGfeRJ12HBp+Czq( z)p@J!82suTP0VlEz^x5$xoCkAxzpqg`|lj*J*S5V zuNwghQ5L)*vq%&our#8W7@0vule(_p-C6kYpg5tRkJMqF1au#)pyPwiNR?hEK#u)s zsuH2Vz6z{P!SZkPM(7gOJ4iU^J;p<0dm;gC zByOIdd+03tH$%u=?+S$)lS}Ml$T_+tJOS#zv@$a%UurW@@EB%vvGm7f;)0_RNE<9X zHxe9Vmscdg*vxje>*FGBH8c{kU)HmSl~TU8Wfhn%s$w~XFFB64gP%W+Gp#ZO^xU!# z_GA|@W~Ggn4=aO*%UWjOXogv~eV{<*%=|C9VM13u-N;qg#3{j8|5wOn|I{OWFN?!U zpO@l>Yg9TwV6Kjf8fyCVQ&qqGMuOQb>O3+xL*y(lS__8l;ss0o6Roz4MsdR(p0!Sg zEdI|I|K1yhUwiqJRz)XlP@0ZvirHk04WLhp5$-iTKo(9E;fr1__#0FB z#5oqjgPO?>=WM$5R{+}BAu+1%q*K4RVAJX{(*9%ssD3dp_=$wGl%>Y zygSa0@&d0MNLEgAgvtNzb2+krte)!&fpL5Jto#2&%@?9T{izlY^VlRB?~n}Ne*CR@ znrN$T_&@^fdv1%@ZJ8@o*&xiOrX*1}r*>)O%y_t%QcFMfpTaUbgW>8WIk>Ik$npgC zFNjWo&pPQWFv1)zuG9m~Z9CcKoLP{dXbWxX$JxAzV_@WWZ&vI0e4#x|CX$Bi-bV1(y3rnpT97t~DviDC*%6IjYi z>wZ%6epakwqbJ6luB00C#xnCSq4>9XHJv`HT56S%fETk%#lI_uOLIm_P<+5ucIrc! zdbq%FYIzxRg$oBnqXo9}el+6)-wY%tUPoYt%PVfX56I%ZtMGpR(b#8HB$;&A7Q?n_ zqu-WXa>Z()@EkM4Z_|ztH+N<1{lyInZ&Z*ozk1`^#lfgM`yzR-P|x3Ak3*@ng?P_j z!^6FVdFbCxA~ks?+x<#{35LRR!=c;YX>KyQrgsq2MT9aff!&felGk0kXm`6WzOSqy zZzOkVpZkueKfIKv>I{d^qX3!yUSi`p9jvdb1(5(giNyXxzgs z-)NGPfdP>DYZE`D{X%r^YYZGVlIPir14Ri*DKO4pSatq4->El+*;xe)p|dJiNf#bS zf#gX!^uEed>4Jr^uqC#OW=BnDuet-kSa%>yxa7g=1!h=HP95rAZD2uF#t^=eLi+JN zY@6WSX*`MLi;pq#%R@5+U^ZV54eiQ`xHL|Ve_RziF$zZ>tgRM@`q;nrj zAb6p`^xpVnAWck#{R&;|@r!%13uEG8&dnBPa4eZ8919k-wu|hvu=DF^k~?fNJI(Ho z?Tr~a=J2Qd2>ZBk3f>pbf=?5+2z9H69gU-5gLM?U z{NfqDX5VPC!66I{D!%i=Obeno)C&jppMc2^l8AMZ6>8kq!3j^clFI4x@Qs=ku6->f zk?|AIqRJDi-kl|uw|;Qbabf5wxkOrioaM9jC!oTFHZn$U6%UypL8BdAWRq#J%wxX< z)p~c6JE@-H@e7miL0~(I3Kx7mPhJdrO-~=R6|~pm&+mcs5jm!aw3a~JNP=+alb5O@+l-3{BNi7YVR&l z`$s|l6hD@kb?Av41m?fp^^U=PO`ReO!3!|4R)ePh&XPWrB*T{NyXm~v-_qT~qM=sr z9<@C^kEtE<1)eb+UXKo7Bbg&?J2V|Ot;=SO*M;ZRB4fBKJ;0W4QHM97E^z1jDWL`i zLhH5wF#W^Xhm3Cecw{X2%xz|k3pP>HOu_4DE%?^24Wqw=x)eMS?88L!g;VoV1fOju z>wRM=|1&8TEX2*s;c*UMc{Bi)3`4edRyWtqaS^h%%Gmsk1JPe%4Et^#U_;E*@!ZYn z5M7?lHWX2u$%ccYc>w#B=P2mV_vpRf^BB+e#kaq9(_N8&q#lCTBYV(vYA`TcIz2KO zvz4A1OcxmxsR`bYF7YGTi{HAU$Dsn#tCh+xUG5b1`xA$rZ!htTxyt0c;4$eA=#7>p zPUNtKJMOwY1>?`86ZJ1<==)O-r;R8eEpN2($!1#&&p1wc#f--NcB?Sx-g#1*@S1m= zjzGD?_2kH@qkODZ5(av<6Sa4y{PSK3{_fRH%qFgsB`Ha8%FZrw?ZI)eq&NY;sI`&P zOTDT7tT6nRe~EY`ou!*^d*a(c0z>ZogGT6E;hR5FQnGvkXg}6LpXXaixo95Tm^lF# zPE96R?p9DW;|FhhV?k!W@&rr$v%I#~7!qL+2Ad04@&d^@(d07;FlO9QS#rc6(L+@U zyqxYM4p>=T3f=4GugP$mh zy3Gol@;Zg?$3AA2ZMb#Eo zN&N&*;;s3WG^%3^TQxKct}FbcUyfQbv*Vs1E1dvdUy@ndFH3k9I1g4hZ(|Mnb--q; z71WzDHuc$f*ge4u62+D5bn16{+A9opRb66%$!F-7)&vkpUUq)C7rj4S0%wj09Phv) z@zQM)c=fZ3{W%vXs~9clpH}UxxWSBn-w**ClIvOW*<<|Z@KsR4&a;h4Z#bE53nS+p zXDYqN;LBV+cyWFw8{$3-zigNSM&aq~^a6AA`zi--*E_ORx$Y=`tCj}ZPhq(=!T6CU z(bVhh(j#i|Xqb3cd|q*$RDeNI;pnHDSN@CDso>oyxUb2#W#))XJd*M7SH z&L~VTzR!<5nolatd~xG6c}$-aNER=2#8o0qRQs4s&U#VwxL}Oc!w-_N|Eb}=yDsQq zUq-424ivQ009?KZiK0RmuQ88B>eWn)E3>)jp%lEovXji|JA~g5>hgwg|7;7C*S{K- zg69o{-%l7pA3lx2K>22(7_ga+cMd?g7ETWD@1e0G7u;KOiu4yezc=NK@pI$>GU>KD zwCPR9GVN^QsRP0e;96Nf| zCIYryuV-cp7`@<-1UDt^tY58>p!rK+uF#KozHtz*7$Sj>SzT;(%PHB1H3^{6yNx~4 z_2GkFgu?q}mzesOO1?ba6FSeGWj7jr@<%n65V1qb^5vAU&k7wlm9UkWm&`-OedFPw zP7<5hVug#_ztMedOV}DqFWg#lnqF>HV87Od;g19l+V$d$bju^byEFE%cvNOzX~-Nw z^Mr8Ol!!WYO~J!nYQ2O%C@2)okW0cx@yGe%RYOSC>ImF3=Pft+w1_;r=Z!A*V{r7W zXi_M6>_!fRLgzD z@woSA3z@$lkvn9i;=Ua3D6#@J5y5>bO0mUyvr8JFbQk3O5i@9}}2cHbCG6 zR*;aBwv&zd_F6XTbR0NjwXjf&G=6(zFlhD{?w|4v z{6M)IXdS6wrU8BM?Q}EfzIm7pxTcJA25N(BQZCygWKFEfQGjzxBG}ovcK9;rCB1%| zvi>($A;wAR$Vmg4lVT)hkVSOz`+d?Jza*?Evlf5QK3ZgZLV|U>D`a30w-r_lf`Uybde!!PFDC*(>4FUa3SRvBd4K=izqTMy5~F z!Jl&0xac4wyY0tgL$VhNW@yqg{u^I#EDRriy+nrouHaoi5^%<9f$4qW&iCp`u=ZpZ zxubtTb~{Ugo*#vLgKIHj)whZGQL~+VzimNXj3O}5q@GOIFQ(H^dgBh)^W@2kw>0aV z4Qk#vM%)gLf%jwdP}6xQ8GL6JXuO+@_Mg+p=rVJ-VkC!8S2~b|KipxC$3@<)G?{n} z4gv9*c)r`MRdm=X9&{dGm+fCaOLR9s6|6M+i4`uo7P$-FogHJe=}C=T>Boi1pmby( zJ@TX%lWd8CM`It-i$ipo%6lIeQ7;eIl!DmcZU+b~*M!5Xa#-vmF{GH8!2FbhOzf%# zNfxf)U0lZUmk)qAy+C-m7FpJj4tgdf7B*)$v;DA<-mXf4)>xqiMh>Kdgu2ug?w_tj zWz}6yDKJB=lXJH=*q48o>ZBM{3S zU}IAS-C+APIC*R%YpECdHkV-n@8QS(g*#zD%WZn_>|ACs-w$ht7tq9GKco|)qA{~; zDy{gqUi!Tv8Ncp3X)vomzUadT3GRLSPL|?sEJ_wKb1M6#^IZq8h;sJ`UgqWo-khaM zp1lgfHy8Tg%9v$je5#wkbgST^`nBZHi^Ui|QXi*&Eg;WoXW|!sJFL+wCe4Nl_^SVE zJQ`U=e9yh$LAsH+e^>))KU>7rl9F)vL80&11bkSz1Pw-Y6Z=Xt+1_8ND4)_rOuWyE zC5{Q$eYch5==syh`-Kb_rAuUamewi~caO#M(JhvQ)?>a=kYfCy&}n z%BIbS>;1-KrZ|yU>086+)nEDFB6G5+)C*MgEBNu8QN*=948q;r_!;*K(Z1n{FePHI z?D3U<>gx<8V3(UD-h8UPXo=w6c^hU$uW2x8;f+LS{#{HX4-RF|r$oTHeebBIk}*3Z z@rFfj#z2E+3~NlYf#^xIp|*PqTXtO+HheIL(^iG-<-W;auC)SwUO&xBUkdwWW`)3| z4;NX+p$pVCBp!N{TbYVp91Y%^3i{ez?Do*B;@-C;@M2E4;0qWcd##ZS>N7jo=n5fY zDk2Iphc&Vm@BQ5Ck`E}{t7cBk54rzd2Z-u_f+dd{frs~tVd0QH%;t|KdiGa?^OH8P z+8h(q?>7K?w+pvNi7QIqwbO=`8q92EAj+-J5@sb2r0qLnaZ+-B+W5vz>e`fo8r3hW zk4ywLr@um`*4NQoR1hV4Dr9X!z@mXG3t>2dhftA&idlukn~ z1>xX^3#8AwM*7;^4biHCxQ*`%=LM>EW9VV>Uz`ezTr(3xOE;5d8-0-bG72}?hLbz{ z?ciqb7kuAoF;Snl8g_muHpQ$-8tI93}U3Wkq=(V1VZS^5JHh<&RB+yA7p{DGFR z!*4$Pr?#DKJ1`e$tTj0NW9;bJaZr8V3y$8aWC16?P>YXY&@-!!*(R3LCsPx_C!>vh zxaLX?&4hZW>S7(myTsn968Q66(70r4WbKy{L49yL3mCAJ$Nve3@k8rbpsa*P*m{H7 zP~rY*`<`F7v;j-WG1fkRtdNbP3*X-EU_(~U#!Ab{uqHH(Sp4&95#R05lxj#*F}Uw2SyfZ0x{Ki5F<3f>e{abX zT^^f^>Bcrk8);FFb$U$j z@VkSgZ^cv$uW-e=a^)ml$PBE=48)2$BwY*J`H!+#TynOV)Hh{v#cL@zVpAt6z15dT z|B>JmVgBAbXoNwmZVJvA+DTNB$I{JlF{pE#VWQCZEGvLJY}wIu~uYtRmd7C+EFue`8T!KUxc1u*B9}xe`eC>(^Fym+O^bd#C555 zKpYUmCYo9^m1XS-0`@yC&&QD;6%dPSE&(CyziW&PeVkK%-mC6MX#(Sh&^j%8}hHKkB^t&+XFUyNZm1!tTYjCCZFJmw}z3?x5II$ zoUnsKY(mOayip@KSg=^|eOO2HS*KEQHFOcdFDvuvk>GKyZj#?MPTbKq84rvQ za)2MtrPXtzQ0aC9`F;BUJr?YPT05)BPmRZP-Ao7ERZ>E{Dn`J#psOBn`-2kz&@@4C6>}IL(j@A!@j$9*;6Cxt~@ULGdlUDbQH@8S4%XDrTy?C`{`4tx3gD#pt+=iPL>5vnJ*GUy=-Tzb%LX_wXVS2o$S z>#EdE{mw3V%L7koq;ng$mk$rizoqC>e)#=omY!zvQ!&$p?Wga$zU6cBhh;489ICEi z`S+}Rbe0L1y${gP>T*)v>zyCJJlNFKU3NOM`kTTWbd zO8(b9QgclDI(}quPM+{JTJvQqTXBymzI#lG)?DAtLU`~1d;D@DHJ?t`r*NM`^0L?< z%@|z|T3WF~UXRn69Nv_YcIpcGF^%V%iz55TUUk%wA3J?dvrE}z*^VcJy8#nWr#b56` z2nncf`Mrt%bIj2*2Y%32u_F?a8$TJl)iS zqfw5Yn#_rxTzD2Rfr=n@P-Fguw%r_FvGe{oeh5xWom<>lEr+uZD_ypozlNytdEps% zAP-*C#7|Hk>+dd3STB(e0)FGJHU9TTD)}h-vT^%PVcn@(b^*VQZ3~)jQ^-|_>z%cb zT;hJQ56Yq8mng0{m@7`ex1CSOAjE@rLxWQne|iyhhg+XElpk`5p(VMyc_=VbT(W4| zp<&H=;^fn!E9gtw2hkK79)4>i`-czw{ZARn{gz5(`W8!sGHAGcOi6{s)j}OK^qN&i zO+DvOKj8a>7SXD~=HvpNV3QOoX#JR8fj=!Vl-$&OsSI)V6~85m*l03E`Oen6v~yY} zZ3X6!#Xf5HU6rFp{&j~Y9U)cj9(hWu0Ks2RBHIQH+RkB8k(G29^P%sX$zspOI$DkT zfR~-@(a|Cv^9u3yABl_{hU^?I<1PHVsj{ zXs{_g0p^4FmzS(isPrF@LboxT`^B0y2l976U+D^G*};)MDjMO98y>lJwlsJqqqq5EWb}Z7JuXyz)Qb- z()%0->|aE^HgdgAIL%YR-{(Ured(jhT_xAJQ$mAxsB&7#^Vii=$=tS#>|Dj9ZcaA+z>3fSQ4?Z-O5w&nu<@S}oXK~l*Ru6x zLm>qGY0H#sk$2dCFf<6r6Mj(fN?d^PE$oGS(H4VwJ}{YcEBUF8Dz}=v_u6b;Bvs{H zlgpxF`R4N1d=VOso)B4k%~zITUagqw!pE|bc_Qk+NU!i{Ng+>!hNremxLd#4=3H-b zo2b^TR;6Hb@T-0KPi(nKB7cRr6aVQYt-9O9UMRP>e=NM2QNx`VW5UZ}oOFDl38Bc?TKDz>GK;BihME!N$B-*rj6>kJS&Oe{D zV^ult1Inmq~OZb_rZM{z-jb^9-D~`yQMp zB5v^qzici?thDnx`1fs99$|TOggWn^-o$pOS2KAjs;!mC+W|k)+Svc*3?*AbLsq(> zkoByVy}_TUD?#oIRSrsd7smy3W1=cIrMyb}5_xS7;S7w|(-eHiF#8QJg@&1qex$qI zhSf2?D=3DxXztIKZ<*xA#oSWM%tsB(15tG}jD@fjy_0RKPp!sx8sCrU)z zw|m~vhkem>4P|-pUFw~YLHmIz3o@Zp+j6=G4=vtl(b++&oS|}$_kqG)x>HW@RrF=>uQcxR+@1%5 zzh$d$Jol&ulgJ&RVT=9%@zP+4d@nTo%xsW4oNC}v;7nWpT?jTQ<7d!NICvsG+W7x#$IK6h z$th8l(^lSd>U~-+|HwALC$ICQD@PnT3mV#lgj4CRGrR!&%FU@1W~9oQD}SwDLKdr%aW|vXx&1OK`U7+ei<_sdDwo!%vmd(y^)> zzVe*!88q2PmD^W-&n=oZ!z_*M2MCCt2X&d?yoa01WLR07-_`mPJK&!QisT6S^ zN@vl@<8|bRa?Yqq;j^WZB*4(~C4w_@5TAgCK#fQK_ntRWIXEMpc#HebRZ#EdG1VTy zse&q(vE1Ko56ch6fXh&BKFx*$()}nBWB0E08`fC+gnmOqVrnpFjJQPk;GZ?_H>Y;R z`&{5}R~53Qx+=G_+{>$$bJC22kKmuLtK?+0t^Tc{AsBhWm(PA7ZpFM>KBb9cvPXlpVkNwppyofiADf#WQhEAejL3qV+Sj+x3!$ zK!e$EIo}StNk-tLf8%*hFGC7OEb&_oe;%pIy)J*XyoxnzaNrQ?jUP0zO~=8~wZPkB zOcqH^#fjjtD_5{vLu)<;{_pK-xnk&2&P3nUGYYtJzA6{I{Ap1#m%n?;gMj&+{FST6 zi2Mxt)$hFKy)LmF2G0IlZ*#s$HY*V8NPrQWZT|nY!*mdGz4mY78>klsdWf$v7t7&W zn*SO9PRL#N5*qgJ+#oc>)N&a36#-2`nR*eo2EJj!Qmn;4h`X0j92D* zXR`8p!;_)m&{#h@Q)a_cF}{%rKS;UTnDv0^(<+PHyN_fmw0*Iyg0je0Gz8~a>qdGU z=izSy4LbOZ+E~hjF_>3x?UdBv5^^x0exGd};aD=#0{+YLV&bCnsACU1^6P~=$jN)jUBNPD4*Is{lTERqmj<$1_mT@oh z7@;#btF|_9vPC-~6`tFvBNz05Zej$+!beSlZ+8;KBxtCst7lI?Z9WHl3)@m&(Rhq4 zz_V*oI^P{^&t1T8yzd+9HGSYr%z@xR-h6akBwvMwbC)0Tky~l32L1!;Cz+>|GNWzG z_h~%Fr=AN?9{>1{xT%FiejS(~H++LXLLy%Y4QaQ^q-u{ESPz^p93yeYd>OxkhLWi9 z)cf^cZhodtF*BuGvhN&+`tI&_v;>IZz$LSI^897?CqmoKJ|sb+r)xr5)Y zojEPfDxw;+&AT$2jxVnxZ%YD>Qs!8~+!fjiiS0-JIzfRPqR|#r_3|+Yk48ii>XI zag?=JHt~_vfoud!>f1`T^xe+3XuF~;o1YK7#dE>A-X@O6uYSdwpaDk>^7unRd;)X( z;2c+eJ35)yqrQiU1+P9_z_WorJYqSQ`PHa+gcI#}T!eymf&aa5UM#~st{LLqZ5gkZ z7SY5xD32KYP&o3qid})(mDrnhEz9L6(6GPTX3AXplLvxxuB8<HydwpU(;Q6B9px1?I|Om0e`fG9V53D2)? z{X*)lpXnSlIJ|jICxd=cFU*s+zBg!oaxOVSgZ+~Y^te^EYFq*wtO_Y!NgXZ@I zQ#|vy0`Guh4Bg!n6b%hoOU%VYqZ-lyzs;u(d@?tmq7e5o)`c%nY% zOcQ^cpp64=a81OsV5zuITmqipwo1PGq!nKU|LtkDyd`Nd=Oga?(S@A;<}%AsKC}22 z|2O_AcLwIvqF}z^>(4i!|0i+qBFP?#sgINCg*fsyITa+9E4b_>e1v^D8{|0|Z=LTW$jw0>|{8_bmq?`Gh zUqHiwHW%sk)KCrtf5eZ+v}xK~?gtHXKlzfWxh*fl_~sq@L6cqn<;B3Hzssa{Mx(g- z|Msm$1^q4Z7uSH(_h2K9IP%H=EHpUJmdKWO(iIk9ZeMj%Qp>1fVJhnXh;_&dMl>1t zV(VgRzZU!6!87UjAId)Ph|Yrl>VR-+{nm$`A@046@2TAWJNcok*~N~=3mJ4B7+>Ka zX$&bR2ee(hYAlUTZlE#X?A$F(crZaC8-Z9IE%T%ixk{P{4X>vR7k3<~Cu`K7zw%df z@+zUtz*n!)VWDLjHD3pv1v8#mA3*~6f46qvohLsamlE!`A9?dZn+G%=o}3iFaoV?| z6b;OCc{o)MI-<^a=cwW;-BG;)@6W?Mi9(0q)>u3BF zi=m<4kOr?jB^-pd_tj@`-R*kLLiyS9ba79Wl1~EjOfgb?tR<08ZPuWh zBW?QJ!1~~vkP#-V&B8)CG}xaVM;ek0)wQE;&LNuc>^p~|{?kA^>iE)!{{g;y*L#{^ z`G^OA$D$DDoJ61Ff5CtA#UCoHlX5EJZunkIPxlmwVJNRn#aNFK#4*5FdE)=u&`0VA z{RgBHS>jbu@BwG1jg2(png&%N*0hpxTIscyE~D+&!r^06~@!Wv^GrNYk|!?i*k z)>7v~!(D@G{&RC0X*kB$d-OZ;RY?U+0!GVfD7Q(;qU&foV$g1$J0q5ML&Mm%_A+%x{rV%w?c=Q}eA%Adv*@Dkwl_pacvRyC^Um&C~S zeBDdI>%gyFXfF1_+PV?qZs_q+Pd&SdCGezi+kIhJToro(bI`mO)!OCqGiWf2+DL0& z{p6nDY+rkWhQ)m5VtB4^`hE1t z&(z+Y)ikY(wb&2*Im;Dv;9XzeYK*B3t{o}W*M+0d@Ohnr%#L=UCSY3oRFgwL1J(26 zvD`cg-D*i?&?DKBNaL5g(F15W6!nFYXMCoe(2zCu1?@KaNn^n2yTXd>Z|2f-Xy}~1 zk?urSss6WTNA)7F-%a!f^|vQK6r8t8WH*8T$LfdPHBmtY&=A!3oH+kZ4J`rx!X52- z?4$zZtHZTy;|iYJI+?N`=VUy@{1kZpKv3*`sNkP^2Ppq7#g-%c(6xO4A+A5h&kRl zL}hV*U<_vO=2b-%s??G^)nv&Ph*k@p6eg1Y>uqo2|dyekEr>gZV$pg-@gF zxC9zBHr5KsE=8(2@Zj?tQVJ=mx#7FtoNhc0=GFTJzSO7ZUEYPV zTZbQ1p1zmY10&s@Nm}nURCAJw%IUj0#eOVPW&U%C4guIa1OE-u*{0bvtoRweFP-s}0072-~h!M*O3 z?-YmfPDeYk&HGFCz#Kezi0m@TRKLxIPU9%_V*?EX=L3!qzK)j2x*^u~iIviZDkb%R z2CeRc#L4#c}dhUC42QZKHlyar2#W^Z#t`4Oi}$u8AX@!j6VrN6UKCRp9XfC+(Yn%=YzZB zKl@u7(H3JdAJ-A{v$0}pjH&GT(*fAe=Yy^X5@*{?C*rrSqfq54aNbGQB8n z)#U?w13$jwM?Pp0!T!*2@{t4Arl;~)@Oxi3AwJ7d z@*ZFmYsZLN$4lh>p`pXy-_rjw8h8&lO|(LUqM_v+hFFE;$5Qm_|6e<9b~s4KJ7F&` z>N{EAqnkrN@v3Hg!8>Zz+li-v=gZkJDmFjQr@%i={|~jBPpWIy8LMLI-K$g#goZ2L zb#(sX9I-zzzE733qT#jlG4xAkNn|yVzQT8Ku0PpG?PrXl=4<6AtqQU{`7bqJL+t`H z$)$@eU4w>_pFgNaz#A&U*fmb_qZXDS^bQ(6UUH_gkH0Aj{E@mBDbuis+5&GmU>>!v ztyQg)|J7;~_N`OWcksvgY!c#DNMvK7;ZyV(|7~rWNEhS#$HYS%pjk--%#E2txNdB= z>RzI6>Q263AFH~@Ft@nPE2JXbgoakuulZ!rQ<{W%rGN7)FE6@GBT+xU&o7>xw^(%# zQ-VAUtJGVo?rq{G*0O8mVZjpouapXoS~tZ16XFioD3SkZ|3q|0`G!Rk|CrXF&jF(t zSjFdbw{r76Rr2*54ye1y&G%Xz*T?h9wJ&)JVj0en^ZSQ^JP#V8=^3vuN#b*;Uuuus znt$`z0Qi`A}wL@L!ns5^u z)*Mh!mqDGW3-|}*Rny?O)$|!YcudZxpW)Z2`QH18ZzAbMJR=KWx=|oa4VTj*XlQc7 z8k#bmW`T1=h83NilS?0`q0iVP4olx{%MZFeM1S(*hJq08}y1} z6x0?x&JRwCGXrX9Gx)iEJ3er{fRYins>gEfyd#;up`16`f_G|vr5V6T%v?C>=PUXS z{YLR3d!D^T&%pUvh~r^N+o=GtKH_W>=|FYWv(EsJN{(v%LTG*_GQ)>Qqt6;jdjdak zokTt$V7qt$8a&4<*{MXrufhM^x|VYnE#&5Bu0iuR<$!|6u@q`QEXWZ}* zwo3Hl4bb4x;tlhW819Dg9pB4_^Uh?k1~8A$|HGHPDpb#a%5KBCk{j6s8s2Dmi*uGp zOzr z&`51RMES2ptk9VfS@7VA!g0)P`Bx>yZO;=nqkcozdOG@0kD8ysOL~;h`T1wb2A-s7 zq|(W)j_WKDjrWI zwhh!DoE`Q@2|gnwvPO9RD_$Yp(Ly4th7ZQYeZ?!E>**6T4DFL5-kw^jT8sGTGmVWr z(o|~{t>aGcipWSB4*nHo_H1nIMePxH-Fq*7?_p2dF)p<^k$h*?aVl%}p;tOzi_@l$ z&_C-=DfhaOEL5Ysr>veAS@ad$ph2ypMBc(xBA$Q-aUk|l1VxMeF;BAhH1J-W&Hfmg zYnGMq()CBUd95aP{9hh==04}3-s4FW$KCa0C*UnEeB^9pI43~E$uW-H-!hd2@IU%; znhzZ*;pR1>IbJh){JeVA+EFj}Z1G@{lGgzf`g)?6I~nUEXgk#+MtZnSBcBE5p8Y{W z*Dd87k65|CM^ks#|6e;CzwalL!_lg>tPU;jQS9AMJQMiKrdU68a$S%b%La{?L#zsjO?>&`Xfrj|G64|eAK0-D) zH6JvRMdk=;pc6rc};J-UJU&={|zNz>_)iy(S`vb^bH!` zc78&uw*00v@R!D3r1SlYsCmus*UtH5A6ctfOY9n_5W37$(r56u>a|@ssV|XrhlcT$ z#{MlvG|_5|Z~U8=V)w0;viF!0;prcb*_Mh?i&+mwbwef0^WI99$6miuDUNewyK&Y znb?X=sBbq&K~p!a@C(Hpn2T%2f|FMScWBsqSwTC#cBCQT_vv3lNKGl~4Dk zU!x3^uk}l!qD9Z>KVXbs2h!**avBc}StDLjPsey#2hQ2YZ&FEB4t++ffPGu2~)z06$IAQ<{{cpkd(IGw`VRp`?cPgTMAo8=k`jl!mx% zBA4<>F_}V9UTk}X4?BM)4Pd&~Jmqx#*YpAUZ|@fQbobjNHqY&(ST5>sM74;ec`uvm zO$Mo+scVl{a_bMTggdCet<}VaFAhta;9Kb$iQHw*X3+r}OlRSp!&s##2fxCvmOD!p zumt#Fb%mT-aFO3Z!?#VpImyu(=K^C5-#UbA{_$gihDftFyuUMY(qMe=yV|hf_$;0Z z%o+I}o^z&xZ=kL3juD*e)W}BQ{F2}!wp@sJqtMWM(R2S9)=D0TdG+z%IfC`sI_`t| z*Tv<6VoWiQ1m14!EZS9?!jHgnOt?S}$HS0c3i}5HCpzo=jw2Cw_x4X@s(p{|qTEI| zn$)-K=cB+p^UI(&`lHznZ7WWclWBdBI0KybJ2%q$bxHoS5$p0aiOfVYM%V-m<*`b7 z_dHuTg!(Nr>ZxvpE-eQ>a7_tq?{S8j-w6&mn@VE51FZr7{*4iorT>u(5jX0KCw1Ev zMQ!0pj_-ZyJNqyB0CTkDFm>NoMs8?(N;;7oOdC}1C^rxMAsiYak>$a2Uv4ejZYPl? zV=NAY_Yk*d*HaWU95zfAw;U;@Q_ygA?^I4{l}^p?sf`{T=hUg+s2BKK?XhQ@R4*#S z95}D%#ff?k=@c}0oQ`DelP9PJ_(Q}r{yc0N`J?T#HKiOrGesytxiq4l52mOKcYzV{ zetcd{wZ9=Ww7`3F549+9A~SqnYCdvHn{Y0JhLPTm95p$WSAf4w-5I>^DBo*Y1wv~D4i~mXQ1t{F`?2*jYhr;&SCEZ1o2)urz4itbuB8W&QM*yH13*E$HZuM zMg6;@cPUxTmq!3Et$9l?M?Yp0^kw3cP+I=+0y}|!zGDh4NuI?Oh`XzOF&UUtiJwqD zy|a!+%vdhg!cR|gCEcC)KxzUFIt#JBZQvy+z-i{wNS?QclR7Xv>?_DjvPX3tSMJQB zWo38hC^VQk#n6c`5Bh?!Q|s?f8(#!d9yI9RdqN8&zo`-$ewbXMXK{tp8~B7*3+Vmh zT5^SkvvLXPPFB)e@Si)lTgY7_k=0^e-R^1NuQ{uU_M+@q?k?W8t)xxB{CiuSpM+-9 z9keyyv4g9(#nD1=&fIg0y9{UA4GnE=UvW)?3;m0^?ea2+v(+tV8R`o+C1cHL8A*Y^ zV^_e#g4@zv@My=?aKP&`f(iJS{#0;WLB8Kr#GQk84nwUR#3Yn!#U}1>y$?GABfE^f zPClFYG1`6{naegmt#}AH*Z2R))$3kxN5t|U^_e#Yf8mbMAfM^Rt6wMbbJXt%xyIA= z^Vt}9U+HRYsi@}W^|y~L9L~zyB+tqh#Rr?gKp7e1uw(6M2@^A7@Aab zCNRZkyV0l^;{A66^*_3=hA2K>o6wH)d_kJ|x%O(XZQ1B|CeH>YzsZ=d&a2>?Xgl-$NZxh6kvD)d_==x+ZLUOq z4H|N@JpETXDR~Cwm2rVonCo80qfwu%Q!4DOBh7N%1uFoC0w(!dF2^b&1fSx%zpv#>?b_$(Nj&Z>MW5l#)4csi=R6-PzE#{aY+zAyep+kz&8!l=86sJsxh5v ze2j-Uexr8a-~RgnUtH%+NtgqRgFf(!(1&CT4eh%}^7?ltsYmm?`X`NFADB)7&~UF; zDR0b46>?Elx?&I2)ZxNKVD>gDdCHSQ|2fdmO+zAIzbZnU56)1J2L5ltc>V|t%CBYo zAp4N&+7S}>mxt}P<0#bI9{SF!UEcFy;4km@;jg2@xf6I!&3?rFlK${E@E1)u$984K z{0nh?mPz?kWgSPN9NeN%bn#Q-I*04pR$Xz6u0$RR{XfG+Y5l@Reg)2l)htv+mvb>< z{h6srTNY)ie&b^{?W1+V54J~rs~lT$KIh9_fVVmQmd<)UW(#OA(hj8o`sVx&{2p^s z=+MYHT#vX~UyEo^zgqDF%ClzHAt&c*F&BQGH&xQL;G5Fb(6D=nMAl^YUg(YSHArZr zTQrPD19LH^f~ExS#(gT*kUjC-VRVP~LW8VTEDc=lL9a1(?{4^0Yu#XKgL!2?_$kFb z{YC9izrW38+F)HsgMl}zT1fgwYsncrF}+$+>7eHQ!T8UN*eeWMCy}KhZp8$de++UJ zn4>&%+B4BUypsL}CQCYy*Y(L!{pU9h+s{!eSRv}MvqtlHkMc*!|eIs^?p zgdkq>!GgA<-lZ{#&&rq6eBh_8D&QXj+N++aU%S@un#&giL-6N*R&dLTfztKxQ;vN# z&EFE3fd}6f@Jy%o{sY!w4a!_1YxQl1&}S#s3a%;1cTxwk-U`n68XU;8hNLK~Bd6t5 zjq4P?qxoGP)^PrDr)$QThoisHtF-}SWr}C3G0&-dc>-A;!hiCZ8}#8zE;Sy&`k3uT znzylv+M_<|P(KFV!1h%{i)y zA_NoqvkKQor%Y1pxKHy}<2}y$?=)w%CtY2S|3gzBQkR9(CA8K5@re8y{?JAA%VgPk zN*!845&F&VeTZ~$ADIiDZ3jw)4qYU&$~7o!&llRBm&j~4VSmNXr~b>wHBmLneyhAh z{ZW-P2^ze%4(GPrv#AM?*O*3 z3*hBw+iAsfzO^KQ4ZwLl;0Bwo$>W)b^}S#N4?j}Pq0q2Ty%)RhQt%RJ)A6tuw>e1U zcc9te)i1vni5EdO41AV7CpdO ztJg%A{&V%8g;>>BB(ej`W(mWgA+wc4_F{ag5Cd&bhu71Ur-XAeaL?SLgkJ1EPhY_! zX`MVm#cTp7e7TBmfe@}^xf!<57+;5pDx3bnOfg@*6zbJ4qmk{`^$qXCeU2O-O!?(H?RI75X!L?4SZrw zJ7EYg26z?_BRh+xX!~@LM1E^*yf_t{6I>d2)5poIiCA+^ma$XPQI((Tu&=p&%Llv> z+BT&}alhZ5{05pkqQ_t}hlM?nvTpc?pSM9FnV)SL5 zVUakzFTT%&SC@Or#0WEqJOCcP@O~q`*uIHFQ66~QN3hAP;9kI-z&f9mR~DC`?V83t zl-D7aeZiTfXG7L+{dp5&IsNgVfJaYxF*H0k3Z{ze%lrY_Cc6G2-2qE@3p8(WDWvf) zT643Xkxy$Wz1MMZB>H$C*ZP!?ZKM;>_eu99vK;q^!U=fdHbX(~MZIYxyc#g5nvP^| zqFIP*pP5U0^sQ(%%4a(#kn_jqqzO#u<^by2^9!9pTT{6^HR4^!XmEDzbAwvG$fMzi z<$8QQ8N9Amjp<0c9@N5IL0h4%)ZR{*<0z5&K=ZBrFZHhB`Ef4#a=`YC*mrm>twSFT z6WXz6Rss1SZt%n9te>AurRYoXTniTSzEU4}m9fW#i}76W4IZ|*FLK$aJ0zmq$2FFF zyxc{df$4iTn`;gYrRK4CZeGbA?>z+(ob_9q*kSbp=}yEtZ7Gr44O$?sgNF6khoZBr zLVO8r#pQK8Yv?Rq56#tH#az?tf@*HOdGv>ul|JGz=;QGX;T%@x!#e1@@bx`6?)uIq z@Z@{1`+Rj+2CKuXNpDTL^T=`*5VxE51Rl`7k>{bDANpPV2WyNIfk~UzTAVx|@6^$@ z!oQm^(z=0%fV0Z~r;xL@jMWjV{`eHC(fX?zQ=J?C;Y_S3-U)4g^&imIXCL_sG{+46 zK=o;kJOh21*BDL_=4W{Y`ndIODkUZA@dw0By3RyGs>&fC#3I;wme4ToMQ(2zC+r)L$2eCTD=keY+oPh%klf$cd zP4|0(F|-}IrQpZ`Dkh^KSTM)kJ}vmGMkmqFuh_YZ+}wB z&DS#HH$!;Vp(g$c&TOss;)oj(`G1I&G26z!s6fewpy6Db#lp|zI<|whrN8iCrmETgn{8a9sH$OZya;}J+DCDyH5Q?*S^@X0X%VX{!VrEhqx2G z%FxfC!o%ZP2XP-PD5t}+C~*nOI_iydYIF-x2Fz|FiR|;Mp28Ef^}v2P*@{F#4V2Cf@~`2oC=5I<3AH?=?2sS@|EH@;?&Uhje*^kH z?Vd!w_QxY}5j^RF_XA$X`f_V{wK2Vlv)6CoX^3lYmCLoYR=f=5_(wmv>yj6|5SV4j zpSkVLFYJM~4=1^E`j|vkZovKF-s_yN%wsjgs%yE9v$FA?8XBH-@6O^Q1s{es(ZW{z zg?X6<&20`H^ZVLQ$=%QwN#zBhRbdTlqmM2-JJ1T70)CFT(LGjDBiROSmG9`?r9{WT);b$AY_cZd)cap*rtwVM+z&wK*q4VMVL!>Y+CvC)i|9%`z zoYY7wQ7-q26!dpXWGmsPwQi%dKS^YMXgk88k9c=i169G#{i#W!*rkkGBUVbSHphje ztDY%ROOJ8CiBWVM+GJ%9ICStw%7^Cc=O1|LEJtdEzJ#BQ;POFdXbk$;uOXGAHtUir z;+p<0;q`&JLLEHGdQs2unbQPa=$t-MB7b*2z`yNgcy&~Q^TR~(68wDfqmh@7)8Kq) zSZ!XxI)nCdHrlQko5j;6+wu=^S{cUhD$h533$gCz`SItTA#4W?N4`GcOY?v8DQN4N zc8NpOix>yF%5P>aWP`F=4hPS$Z7sR0t&$gke^=^$QT?t&egJ-YJQyv#)Iq_M;K_;I zj|B?E_lMBgSFays?#Sgyh-=i%kPP z-V5^*emWZ^($Ph0Spf~tu-7_rMK=zFhQqD!9!haXJdOIaR|+~Ydx2jiG_E6s+^HRHb0_VrkM zgrDhk*mtldj!wYO`J-=BblV)tK!1B)G@^Csm6V0Hy~hnEgF8(W56(5c-w3+a64?X9 z${S`O^-ffh3;e8#T_H|*fq4mS9qMYttU1M`3(adc&EcRne<%VxQwEyzs>flp0{p3o zP8?PBj!wc)9iLD9dXOEBgeO-AM04L;2dM};$Gy+sUFBnG0^&-qm-D`H5yD!Oo8~t1 zt>M+uZSZrnG1h~x_ZMT)_9)hS&K~+Droqo{D;s#|r>R^A4JG-dT=e9)%Fph0>HKAu zJzqfm@rrLOEB?R=XiiJ^=IuTaoDV;8I0i zp@uXTaXU`Wr9qEx(gu{hCjKPluNSljejeZOnNHvghcvXcbao?|eImuf&pOePbl2un z1vGrOGN7MBYN&aB=3MWJbH)^O1@$iYZfq>(WqaVC_U)r*s8mo2{CqR$vbf5thPt7T zb|q^3cUA$}BktU5t9V@RWKw`d$zGRfx83 zC)I_WGaEPp{v2(QA~XbJUP8m%lhbJ2KbV*3OQgXG^85IWucKb`mOW+P^X4AFAD`ky z5+?_ahMx)55p>wcjN7A+^S0wW!#_G~hq${nO3C+KmMB5FdtyDE2%adegHG#l5?Sen zZ_;V-v)v(y%zf==VLkku^{SET-)iFbkL&EL3UbC75NXhGJ}Q&6<7_D%JpJ;2klC!a z^Z~K1?((D2*Fq=)ey*ANgg(9bO$PAOXwoHGZc;?!pgCjj0@52ogkrwFO;+c z{4)PNg7+Q#Z@|ykv$OrH^O{HrJ+@X)#amaZ=qGgE3hd8a)N)A!aZ}H4<+_@9+KTd( zikocG7xNN+hK_v6g&W;*~#{XF>lTlUM8>630v7r@{GKth*zJ!_ePdJ$CTxAyu3T z4QB4@9Ol`?S>Oq1@k(ra2hYs#Gqv3@|HdFCC&JGMj}3&Z6Lq`e*V$(#Tgs-xB_}A??jWs$O9Y&oqxM$ zl7;CQ9*MZKaJI*y{-NRyl!xzYq;C~@{^!x(r~4(c&^<$hHt?ZlibS^T&L6=W{#cD@ zpanCh(_d&ve^N@P+n!YUsWB~`4yD@DUDRiqeZ%*5UZeqh;%aZ2JS~zwf=9Z-fu7z; zqiXOUZDU5GmX^{j#Jw~`hxQfMQ)`qHwK9cAlO(d;(0S$KIN>C8EQ9{Mxv~EG*q1X4 zey+|95Z@2Rc_`?w#t|*fz}jo`8mx`fgtg!PpnULHjJnHzhxt)3{7k>{mfsdQQx^Pu z5g5Y%CSIi3@bfXgamjo=pGH9QPn#n4?kS<~;5jVRar}#2!hY~;c`140!R7vM;HU9z zoEtFARm_2&@}wqqvlzg^(5cu{#c4X*co^aqr{r+_0&Cud^3c!me0cv$zKZ@X`6=gJ z=7HP;KFsRj#(g^^@k{u#4QJz&KhNji(4f(84QpHz zCjmcv@p|9YSqgpup1BLJ3XNxKxETCX%{oz5Q9j>5+(AlxN_(EfZBc$V?;7K z)I=r)|N4K2pQ~^k(YvxG#HvMMHOLx??s9R&&Pc! zSlfI|N5Q`^CzQ^g@g-mQ88GS{)kj6sFX(wR>Kk4O_ApDm>XXc%2Lot4-N z(foUF`goEnW#8yA>K!IL6XS-9B1^%?4G`_Wc23shA)#WCL!g(BFwo z<-DQHgnvQ9NYhOIeC#flgGc+=57zkhmXqM8R;n*|RD`e+ezth(%)9!h@C5j|>HJ03 z@hjp1&>U7ek1wpN;~(I0b5e+ZcHJ=CTq)-fa%#L5=J`gH;LdHo3I|Yjzum~*!6{N_ z^fwy!eL-`OgBU){7>n~IJkv!h_+wmC&xJlSI1(CkHcj(+briymCZ>N5U zJNI%94J)!HQzodI=MZ=6(KS4PlBg@nk;T_ItT>RaLFb;&&-m~Cmt+C`qK%v7(oj5$G~2q-zjxDN1m*w{2+D@ znDx5&q;2Y6yl;+CAu4?d0+Px%Tt`3cI_NBejwa|2Ok@gF4MA-!}u zYWh8b1pHLA9OIJ-6BZ}DaSuDx{yH><<`X_^?SnaS@U!Xwbr($n8D&!ndDZ#liTb)xt)?rT({PJJAYlYqa zfzQM*C6fnylKcbgB>rB`&_l|dAAsOFEtwXFw%vaQ1kW#yEJ8fR>p+_Dx!~wUBz1?J zM*B z6({c*-gY6}6n~nZNANfw7(rtDRnazr)3En9vQt`x1n;XU`k&EQ!ETg8dI_VBdAv}ouI))5CzD9n8AGxb}Xdkx+T_l);^}NyNdnC4xV2B@@gf>kc zLxT6}6ze>GIO&(`Nqg0tNmh%_k0J-6N4$6^Cw1xoIz{w{?~wxLj@?M`-WKUv3|^CY zm*9QQJFpFC#@$901m|Mk3Sc|=G^!%_gJf<1r&l{sE8$c8b0hFg2|$AJqSEFI@OrC^ z1mnn~>ObIE=Ul)R7qn%(Q z!Rfm%3KXXN0)p{$;OuO$@XKsB6MxH+f1(Sw;*j7w=h@{CX!G?VB>4VO+3^hh>%534 z!e`QpYv}Oz2WT4M6D5@*`JOiPf$(XowgFi!CHrv1uG?Q*q<3uy3BJ1;c!PYWE)vg2 z^sn>v<-gua#xug_&ds^jspPy_0>Q%*JIiT){2K|r>kj$P0@hC?y1F2Y0Cg*(78I1f1xe%`6HfQ~pXbev$GmDvLf=T92% zpC%mxpq9+j1>dDH%46WwCQGX#(q5d5^JRv+Ir>D;nzB()vqTyc6aBxw_k$UXFA#k9 z{#5A(#$UGq!S`_fp;zGW(F#ySaO%yy4aU4~fO>-8|IR5eOT7u)BYYZe+zEcJ`2sSD zziRvyB)8QcAovbfn5hin0}{o{PR;xDPH9{hwhus(5%F=ny_@Zr31cb0G*N zcx;9m5c4*Y)Dk6oe|3d!n5GRkwFIxYhs|k0lJBhz8Swgt@ml6Lk z;h}ei5bpc^nQuk-Sx_>JDyu9}8NsY|{~NllpFKX`bf5Abq3Xk^iCn)T`xqrnxr$0j z`@hwf(c=?OkQ&hwMq`Tx%>n!+6{Jr9Vz(leRd4ljD9dZoB`m_LJ!p};{Jg|=K0fKqD z<7H2ABhV&McVJoi>e7AIT_`M9+TU9_>M38!B(Pw zNJR$a{pbRr#O~yPB}hH=6%ec^JRoNuXMMXx>V}Z#h3pT6WS;_`2>$GyH_$(Wo!|oD zQ{Jx$JrG?1Vu`;~4}L+9{FKJmF@F61gQ7TP98H2jh#o~ZmS|Yp5I(n%c$tBlk^Iku z&ykEVQu{~*-6wp;-ycLe!Xys~vD?(%i;nATLT!Xkd$U$#n_rG@68(jV_fe5pErNv4 zrj6%Op4oHcN$~JZ3enOPA5j>=`9wPst*QQnCJ;TNdRoZx+ds66$c!(apO!=7gowX| zZ9 zyaYriT}D?(`x9PQ!3Tw6Bu?~re|iF>XQrU_ME|01?Vz*M1g#==<(z*2ugKSYipV*e z|AO6%l=x2w&hI4lvcLGB^-qHTJc+AH{_>b}obb6!`X88s4L}6(_ovZM;4vow2-ewJ zd_MrZd_NGZzjZ4;16uKwz=iOs>2VEAiGK)M2%ircj{@aIZvi5Fn#QgNi`YJrtDMB| z@od2Et|1^;_e+cW!;u~t0}qIP3o|dyQW8(*O8D%L*plT)%HThGy9BsKKPY%wZv1y>u^sn5?5} zZ6fQU?J_8x=uf;#&R{7nMM1>w@VzeNP_!Kh)?*cx}J(TT7f_32d{fa2kl*I583>PmQ<$D(k;YEbc z8e4_h^KoP7G2wHpXALL$>>#>A_&jh+6m(qcMIFTMNxlo{9eaZW>(c*nHUV|B`>3Ai z&w5o3esRttU&1HXp%!q+KJ;#GenleP|NplR6Xb;d^+4Y2==OXfOx`ZeRwk1PtNog zOu&Ide}N8>rQSDl!pK?jR)X`dgFI(HiP4=z?rns^eEJ{hyM)h>jC%gcX+Obo;&1di zLu4@f!}z-TtF{EB)Ake?5e!CW$eA0-YhVT8bK8|lGL9StnDBYv{6mzlupXQtK7QK# z7RlX$;4QJsKI%h8pMP;W2%npThtUJdozqD42Z##cqTr(1V8Ulst`Jtl7x{XGPwB-Y z=mx8fya~>(nBOFhm-I_=?_laDl-RZh3HEWo$P46k?ktibwhSKeQOoMP=ndiX({mE9 zfm@Iy;b-ykE$DfF4-)JXUAFc>TBd{J`*E{+#gPRVLqEy&2}&FI8Ha@MOVWNNJZ5z_ zWfZj&PRx1>IVr{cD1z{5bX*oVAMQea#BTDlrQqv8GZO4)o#@^UQ0y(#NpN1zJ^`G* zokWV{Ud72bf!D?zXcOV{@S`ShWw$@_CH^*i{{kj9Dva;@q#5;tzq&{G^9Y91cB9~_ zfn;qM;dA04vc{ztGQny(%M##_YzLwxkvI|#%wTtN%5`*2S$uxQ)_1p9i)b#K4{ zngOjuf8n2dpl4GpSVQ;}8axN8Pdx`}gimJsUXXn4BXA)&FJB7>$A*3Z!G2=(Neb+i z8v#d%&N+71IY&r5v@)@EYW^kb2_#PV3*qzhB@2Gn(qS-0uobhte5a+~fM6f<%r9$1 zrMw&8kMrg5Q0|NIy2 zw4IB*h`%R$exP}K5|Ln^H=w@*ZThz#Sr80v}rTXv}pP;>Lhwz2ma)%Ns#kjM1Q)R3xC%JA)G4cpFW4J z58I6(Il^bU&m~U32bmWUoL|E=z+u-0eC9C-+IFnt3-;x6UB`f; z1>dTR@cF!$yC3vzT?Q5ryNL;1;5*0%f_MP!o6TU; z{S!bCClGCT3mCcF1cu~Z>cmN4DB29-2%j$vc7V*8UBHF-JKW?4ggpC!APym4Rsr1Q zjsh~d#jd4?Ij2a!OedJf<_%jNTs8&{5I%?CTE0a3AlO5Etn!+G@*{h}b7I$Oz8iX1 z^oGo@$nT=J8GWlFXV8fLqId?4Ts#Lh5I$Gmt3}@y>;)2p&(e?2QM^bv5X4b}1CTCGdtk>~NNb5*F>AU1vP(O%{ zZRkMWgwMv&wMe(}2l6I%n~xbGpSypN36T??yyQ zrz2=P@nxwY$pa9w4&@OamHOTS1xJADiQNXpZy=%RJ6{mDGh{Rj+(jMv---VEDMGNq zzTA2z;d3_`Q|dlm=KLe_m=W3MoTCX$3C=eLzd=V(7!bq@%~bsaCT=JICy36_?Js}} z=NvF0w!9qqU{32@FpXf?Y{vqw-W$+Puyvo=47NJ=0zsV8={s&P z2J?ulx;Gz*^xXuaq>YKpN%TGVByc46>TbD-Y+mI9f5PVxt7bGy)emrptx=~gB_~qBH{`9OyD4L|LKMv z5xcs!y(oPBW+aF!(_QrjrPMNLfao_(yN7Bg^3g%UVOR7y6t4aP{UEYtX8{^f_=NNc zpAv3i2wMIgkKxzS)_ zNeu9l!$?ZK6D?Uo-d8)w#12&xW8B*tGfyD@#8%EvRyoZFWZwRgTtr0&@}SQI`%CALQ+jgg#7L;6+1y-6My{7g~#r* zKxq8WI_x~erT@SD{}vCw#O6Wr7XzbN`q7U}#^t@+Iyh}Q`s4EM8$m$HRbyPfyn+Qs z5@pBbX-{4Xe)n-%@b3ZXMj+55Zest{>koW^eCxK!|B_oeC@aDBlcdd$!=K0Rjk;h0Cq51u*ZECbAFi8EzR^jW znT@0-+NY=E@_rL}n7|nvmnYv5h5q4F$8kzXc7TdAD&z9k8`YrX+3az-wJ;x4V8d}) zt+eg%b3jcj%dM`H6uVtbhJ)Tz=^^4Ni*`!-6(;ZT%qC zO@3UKIrPd?F-&mX-# zcl^36IoC)^I*rRhv3W>m;>>aR*Pg4Wcf!>FuK(*muO9yy$CLY642yrN8<$H96>y_T z$+&!2n!-7|eaGd<0eu|k*gVd^w1_Eg?>jjDyL=!%xL#@-=lpz!3D&yh4+MV2?$XDJ zQ_9BWR5eX}T)JUgj(aGF>+S!I%NEVTxS&ZI3fi-}uTi(A`nY`e=?OHnUT<9H9}P!M z+yCot_jmR2{r_)2yjdSz^X>V6*N?Qk=UDgs*WQ1}D)4mWe|j9>SAai(|LOM)ZviWc zM#k-aHx`CLc`wK1?b~JlS6_Nkt9xC5r;pgNwQ3*tOR~WP&Q$xaFa4RP4`pQj>$gh+ zH2&AUcW&;}65K2J8)!K^es8y%32sVB8Mk$B-W+UZdU;%~7gEKR`1812Ejt<8=}sE= z*QBQleQ=#QF6UHKq4(9g<1%=Zi5^Y<&)>*O5wu10zvr=J{goQd*8i^moBWL$QAUQ*o; z21S*ypnc-e`#?HMYg~?{75C8RN@BR!G=5z8%LfbZQ#O_4(g3ctBYVSD%U=zkWwo z56}3~H{PG0Y&F6E^Z6CjrZUj#&u^TfctTKjDm6ruB6X<1cs;7S>#2+dM}VMC)t}>t zB6X{Ppnlcerhbalvl4I&z0&1r!M_~CEEvB{nhCZrLb;O@q3NwWCXVE&xm+Fshcs?5 z+aQUZ;d{e%Gk-C`rt*07qXkS{AWUk?XGI#GZt{Y2xy73;F3-XHt|;<5UUJ#e7d$L)WrnCqPqs%W z3xB^-iuSK?VxLN_#ljVx$m*RHdu3`UK6p(AXO!!+U($WBTB8BJNY7x?`>b%YnJ8FVBk(oR|&eTM9wOXJ^{> zM-se|{2GWV1A5NwaA21mWmh0k%lI$62}jpDWI`XlRCRpX(68F3h=??DeQWvhcnU^V`bZJM)%1yoOd(~ zi@8-XF*a|}KJ6r&vn7j}`Qsq!-JgXo?UG>Ha%Q9OJ|13Bd8mwf!LMBmbFhrX9ZhZP zZ=Bm1srXjM5^C4z24K7|8n-QFDbc_OAo;yNrs`i)y7$E3vx$zlTV?{S%h7}@VhwOs z;tbly!x}~}lEJH5_38CDd|(lYgY_4;rjLS9xWDHp`jzTL>lv?w$p=hO)J;!%n_L$3 z_%xL-_L@tde8q!7NzI(GdT)AhVGexrDIJU*b)%E)(xAq!TVT3{9o=8I1|FRu0vj96 z=!EnYa6_*e{QifcOFucmgD#eEV1hK=x_>Tg|LYAc^M6un-pIlDmmyGYBc`5acL8gY zLF=K@UZ7h>e(IuhOhBpguRO9BzF#Hv^@vL+&)}xrH=VCgwx?}VS6U< zMhub~jDZc$ikZbXYS9hxKsaYo1C!P|iXPo^f!8>~?92jHyyTHFjFD4f<&DirEUY5j z)1%9tnd61~#lL}j=PlThkX5*)_B5FL)PZ%=OTZGFT>$#g!h;>pp>OH=sQUj<+KFq`J5xxr6g zhR`(o1$1L<5X=uH>rImu(($5k@W7r`NbIgVeYqkXa=cFP*V=PwZ%rO7>5k;=EaTFX z_wnGj{Vrfpn+KgVk^$|U35V|;=m|CnFtxZ3B;B{5v(~MG0VawtQgRMG&C3g>A2Eir z<}1;`%gy2Q5*N5}wJ;riQx$4=1;8yU8>qjIV}NdtfxNkgsN1G|aQbH&%)4(-)n1GR zur&u>Uvxy%S>h(=axD*5&QmTQF0kM)Ey#p%+f|r13ff#fTr87t?ww4^Hsc`3z8;3PzFncBp0xq@;>9?* zuZwzEJPp1|0Hm(b6xv5l53asR@;Jg=S^LDeLzFJ6RVx zN-G&oHh2ZZmjZfJDgw4hO@W(k&84|6OW=(L9oX|qmEM_X10(xvp|gx6-7-@f?n_t- zy6!^s?f(gyvfo?31gi>eDF#9(>N9sS9!o+Ru%<^nWJdxB% zf4ED69VB(qmnZAOr>j)iogEOnw@rax7tLj}Zu#O}A76uX5x{;q5su$`?F08-IkSu3 zC1Lr)Gr^a2UaZJS7LKk6wzmAuWt)dcE$lNwXn~hEyKOKV?=Rj$YKOV9C*P!C(dNhK zZJZ6e;Ybu7eLoSeNHt-_i~KO9M&o5#8mxTULahISgR9!7u->=zaHP~?jBI)sp-3rg z>=T9~xmTH`>)s)aUu*HZ<2lT7>qF>ZP8MF6JBiV0*Fk#SJiK_#*)rky7qvHibMPex ztohfZi!)e}itW!YrlwY`2ePlD@nkMT6{+3_aNcrk_T?2dY9R)z5*_iOV`B8oYZ`Ex zupwS7I)i?E*9tD|k-=cIKApML2lgm@MC%?{(PKYWLmB-tl<)3D+x|<0Zw%)lgOi^0 z$e&DjE@=jT>I*I%(!hfuehr+<@4V^DCvsrZ(o|4#(~XXgP9rhGH$hE|9j!Sf27cZu z49}>{qxaXZfb)ITVD~bbb`NrfJNe`rk0(tJ>KVb;2fU$K!Y@iBTps3b34uG(Zcxf6 zyTQ)k1o%#NEA?nr1?XFy35APiQ3C=OAo(tFb7f8Kh zlcT!;2<(#7qAW=gYcW8 z8F)&dHv4I+J6>^U9^N)0$4-qk!y*IjIQP(B#%|?w{H-V$FVBC-I9@05?X7WmH@|@S z{<#v}nUjG(E;M1*E%QS;i+DKh;M(#nyh6TK3=iu(2-fVGxRukpAp^Vr)2E_7`v9r< zczkZ|ZtB{j^T2K8O8ideK6UfiPq6T<2aYQlqPTO&*l}P!KA6qP)gd`ahvw5$6@uW3Yt^Xrr9J)kW-L7J9*SI9clrr09d7%2hR?O&(ti|qkiR^b zv+o3#E-B%`>-QbO?O_jknMNku^5Z0Em2sr^WhKDL{$D}d6id43_M4nM0SJ z@q)>w#*nv7iH5h#Au@D;>*^U6%9rm1Rv?DR3M`B>F?O|%!1_TNorNOyf z4%Db?0+>>t169<^HJ_fm%W=HJgGa)o%8MEe`9qg8VWr-5QX$L|Rr5&g?7f?rBXTTS zZL=Ew&_+yA(`QtZ#)UPJKbR$RV^#Op7rL)|2b4RdzFy4@o1PrMnM zG`bvf9Z8&YpDpW>um+!8mJM_h$-HAy8dget%UM|C%{pe~U~TDtwJ+as*}?au=J0(( zl+)?SdV?&?*FS=qFFCPuGuGmhb{*)}a%*=EvdQ{>+;N;@XtKNitgw(1x&BJl{lf~i=j+K)M1or|7ogS99=HcUU>ondK9k!N7S$Ng12^7_&38L2|;j2~Y)O8C|tzIk~tNgl5X_T~r z4AHbPD1K`jDphr*L!wh4KS>;Qse99kH?pBd@n5UT0WK{w%7gU{ieTD#FWPZlHaurh z0Fo_T=$IwR@I`ME_`4U-p8gTgC22A|sbEB(Keq(tI_SVW&Meyes}0P}vxSn0lJv6z zZKyVVDSUY41Jy}tW&b=A0sS=3Q<9q-!O@+`@LhZim5g?inBr`xhJI+?50C?yWb8N# zm#AwU+F)gVEE~@7{7`;=_au}zKLxHA4P#a<$Vc~%MZ(sS(~K^OzkcAm48G5M&n$f} zft%ayptX(!TP-vj&*;#FZE~ut=LU%JnyFBK;#~H8h%YWTd;{*^;;?XeI6ic)2wXbj z%pN$IgnfP0z`iIiwyr%3A57n1o$`~*UKrq!SlfU6jX~aQAQq=P3NiaUxE=Yr@+8@xwBwDSRPGgMIdDA+Ct!;G@=4+1V!gIR4}!?7yIw zSu!StBSgaRyufN^+JpD#LCsnm8@G-*SacYz3dzD+MN^o$;d;pW6X_3OwPp2{A8R*8 z=3uEO*EQqt2To>FD*m+Ehbp#R2NcxS;IFWpDt>ksT->=FTmEjQ79JCY>dzc;ppzJF z?x+FfG7Yic@#%E@Vk_9bNfwV8=+hs2xDYJ)gm!MWqW71rhEbX2sAiTE9eO7bx)m)z zzGU)Bw`9WIyJ>#=6E3Y-$Adc}>Nvb_-t?cE9H_WI2?Tv~qb2vJL0aktP-X4tIL{b( zbBM$m2G66rGy~w_=2@`p6ixTua)uU`7VyG%X?P*au#AG!)M}zw=niCl$U;hS9 z*mf=}k-@{2j}Gy-1aMguJ06ZbyaJ6*@?gbA((#s%%V_t8h3xHpad@xv0BZTNfE_Xq z#{7TN@g}}D>#@Nd*DK7!nbGpB(r+`YvELo*#{6TX+R6VrkaoOBjL3(6)afsGEDzxwiDDw2gq0AuFxkm{;p0ohpsgtE`hfHAl;+goY<80dP znky{#|A&rL&ZkLsAqXU|BmblJG+q}A%{3xW-+Fht%QqcL+gI`(47jv|I1j#sOF1Iv zxpd+&9{ggw5X32X(rvbx@M-Z0Fx}pfE~!p{M-_U(Q?4bgryBx4&QgF2&dj0n6};it z10y)~trD%KV*z>f&al#2gdTn{3$_{uz@CT~l%*V)rzIuSn->_kA5DYCbDgQZ z(n+8X<-mB^(lNCIyEydo+GsI@|$vXZ_idAiM#8bA4LLJJCEk3#& zuPM9>%C6Y5XZ6+PqI2-#PoHb~AGmDoM;?~#)I<5B zo~&G878YqbjGWt@*rJPTv9xGAQaNnR{{0n-GZm$A?oI>t{J}-|G0?{WOH^3x5Drf6 zUWkwAPh=bSQ8+`~A6Lt_G9J1UaqF)r+;rnOW933JoxSy+@6X7_x)zwTBNyI!=NcQ%wA*bOeN zbfFzKCqt)ejpSTCpy!rF!2A!B;LcS>bljAsaN!wk`25r?IyKQ2mP^{gcU_Wn53K|1 z@DgZspp*LMHyJjCM!+j-7pT7LO`tI#87|uqNA-ypfWH>maKnLqO?r_ch$7>bmO_oX zk5Z?VQB5{1rQen7i%TH8)hST&X9#oT_crvsHxim2IK^m7vKa8bY<_~_b9HcKAjzu%|A>Bx|MHrW?**0h4QTn>9%Dja)@9ssH9o!O40 zBy6`(lf<=pu|IBS;kNzzt>wRS+52QXKhGcFZ;$n6YiH$P)SZh0@42$GEK;#8e1z&h z+OY11(fGrO33!@_xUG>vBHtY8`P&j#sx7@B3KC0 zr{>YFSpjhFs#)+vKTVgYxxn8~%wfKV3~i%r3~iAYGzKePQ$H99>Z2tG8ZXLbbrMQR^UDL9kaG>iU(DHu@heGvi1Q@7j05{RBOZUs^#QWk9_);~46GEA$N9aU z%jU-Nu;ZS6d=$xL$Gmwsr`-=l%<*8kR0b~8xP)XcFJ#r8$KmHaf6(JO=4|lRVEij# zIv$hNVRO6P@$+0WtlA;ZUeBF}7iziVo2y5d(bO6E^RFNb6YH2WlLpbIkT|URw2;{y za|JcOO~(^2&S&as1JU1kJUsAdWBK-TrF{Kd9$psXsX6IvCWpD3ffv2gp~^mZ0F6)a zIA{7!DjuE%2Pdw=9K*YmO!#+TgFG?!qGe0-XLz90c!q}i(W@ktlf}N}3 z1i4z~wfjf3*Uksl?E1!pNXp`(3sz9NZW{Yd$q)~n)PTZIHQC8LN6gg}gXPVp>?Zr= zIPU|AUCXp(xgVqP*3k99TgQ#fyO4@K=r5dCN4(imzZ`7R)mZ!c6PK;%;^81GU8Jt) z#Xir-!nWy$kfM|`8{4%OS6zRHZnjyo6BdTyYn!C7<~sv+=M&+F;*h)N*G4b1iI{#*4v#{so zVRl03Fj*hTJ8h+Lrhc{c$-yjg9#n{0K1CJeHzr~KWy#dgu6^J`aX3!us-!eETEO;; zzW6!kGd0prR@|B)-Y7AdUcEsVCdSOhV)<(H#7%b4Cs-1z7#h>XV$0xqS5gBd5z;b| zk+8#a2g+%1p$n#^z{q`5ko!L`I&p6{RQCU4X+&ZxK9I3v(x^1J^2Up0nv&{@ZL!y+CF3{jMCGFb0@0NZ`y6)p)EG>d&nf3e@zG8 zTCoH+?)gY5{hSO{R3o62#zm^~cQd$WkPOk`1S-yDFOby8hA-NNHA}xLgDYgc%J(FG}R&+C=U{Y(PTzryox?hj7rTpLy_AN90nmE>c zYY$(VinFMR#s`1Tfue3R*_a&w=jKd<+u{vbo3o4Y$l*3H&4t4@-wVTx(?QU?)S0!m zOTs3aTHv~c7i)Pu3(Klpw65;uvgg0^u$#|M{&}7^%b4cipQkpW#4cC%Lr5xC7a{qU zRc%?T#As5>c>=x{Y|0+4^v8AEG%;7-_Wf@JFY&WhLvx`L)|}u&($e zO@D_L&K!d@yl1K>mYrOK?PiryJ_~MxT-Oy?;aejm8YKc9PdH&FT9o#&REM_1*n)c;9Y4dPt88Ra(E0R329JlaUZOs&@>nz>c)4cOvvw;GiEXJn1P1 zGhs{W0>1BUE^UE$@a~zLoK+HB+Px(QPMRJE67}5awB9s$F@_KR$=cH;jWO`lx-ro3 zXCA%dRR9cWQ-x;kT6Fgo7ib@44o{TJ&|bq9KhRwIB##Mdb zj%xx`aLcDoPd*I-#WJDQ7n+io<^m#%c(A4nXv#)Ma9Y)Q@F#CudFPuG{L#{M7(d^V zc`P1+&_FCqI8wwUm0v}Ufk9A0?+GJM4dw!k}t>$_F%n2GjRK8J_n_9+4ZY= z*pS}M|GSpUW(JTsi1<=;*VTi)=bC{pHC#mQpBJ))((%~(+HVvWXUIwe7PRpMjjkKGWOs1=6`TK6#uRaGda zCLOQ3YR=p@TZvk9$bP6$Ub*_SWBix9$Q&eNp=Rs$I8JbP27bG1Hnm084ct{vz^zku zP`v}E$$7z5IL+b?bpbnJek3WvHM7jI&IcK~qRkloT&s%fcWKeSEiTae z*eF`BJD)C43WW7}wP>NaJuNL73*Q9AAVphu`pv|2c-0s28EG!PqB93Bx&t{&5SON^ zd2mPtg4fQTbpE!^2VUCK$83p}!L^3g&~*7UHh-4^R-`oH=WI=O&P+$Feo+j*+HJ}%`09`M z&v^iJ?QPjvrO`O(?gkJc;>P-HNX6&>edWyB;mwLJ%pvFhZ`B%fbJ?P=JWMsuMk0D% ztaD)&wwYawjI5klQ?(?#HsvkZ@8GZ-3c_%8_cZ*|%#b~}dNB_4*TVy2Dr}!IAh{$K z;z@lI*^2cv-sS3toh08fiT>iGR$>&+={UjUe11Y|+ofPd&tPVKZ650Wn2p1pHI)ba z5RpaXs8*5f38;hilXsT_T0m>&OV<(lhRH;cJ@c9ysQOiY2zWEiXkY9q2 zI)0+ugQq}fVT0+jlju=dU6Sv8HhycVMk{IB!QmlET-9bo?<-#l)r(%B0y9V}&x(Y5 z&+J6gPq@%CT9e_e$x_I?+l!9K&W76*&^0GAc8m$;9oEx;(RVNUd~P<(v)c(OFT2nw zJ;|`o_ysU=f^@xEB;5R15^n!vM6-A)TvR(77A#hyV{Gl9qp}TrTQ`YLGS`L6`h8(g z!6zzX=M*T{5Dw?-S5gs{ufen7BzW=OT2dOi5GYI{>t!{gnwOnbKs(u|-!P`FapSqW z^~c_9_%FJ#eEJL#|hN~E|$qtJ#{pu}vIElmdW`yCz`NiOufio*Dm4xpV zYlA@Ai#5v6!m70otm!T;>(fitjVyclyaI2wz%>Wgtk{6APjzF}cBkTp_wS?Si)~r? zE75q$CNW%l+?4$+z8p6UYvAq!nyfO%5x0n2W1KyWJ$20hC+_sY+O2&|_aPbFIwKVG zgKC(CiJd4zc`X(?zLCjTUy3G7$il&Sa*WwKQ`G;GhpW?nm6@)Q=Py2zgI%1?Y5vK0 z$w~4}!%0H!)U@g}V9>n=uT?opJ@|VQIF+x!dVgP1iyDRDcFGyse-)uYsTy4UZZ4i) zs7%XFw1l^2$m1mo^=Q$j-cWmTH`;c?lGeWv0(Dc4BauCh^dY50`0gh}$u^#}Pf8}d zveKTfT+5}yuJEA9`C85?d9q&7l>_|_tO3tm-RWxCbQr2t3qqak>FbKIaL|d=PlfYo z50gM>=A;TE&S=qQBQB6Lv;bZbk)>yfnZRwrUa(zefULVJ!e`d2AiMbvRa^WG?3tDT zbAoqJ9|F#R#qToUQ9ErarPmFV=JVipJ15Pp-xE2{^m*_-+FY*f%<^B}ONZJr=FH5f zU=(j22bH((W4yep(Ce!~5K)gA`459g;)NTmP#k3vI%nWMBQqF1TY(jRH4lGQn+`o4 zbl4Vc4}4Df4^Z_tXQgik7%(L}iXTc1te{By(GJ(r>`tk7P zb=&!ISzPvEI1fuYE=Fvm2OAlmf$wHsK%y!RY^hf~7E1etI;zZBJ+qZqHdz^OJ*&g^ z9rwU5j+_+lyjxpDZRWR2+2!Bg|!Z_s)BcaY%%=|23W=K|}?!t7u ztkaTt@g@Ylp2@?nYqyu%1)k#1J;=lRRIN3y`-O5SsZ6|T0Zm2EcLquU30S*-JEg{+ z0wpI_VfzKQsb=9m;F0cy|BCceBLfN$Z8yiWHp|fFYmDK5_$>U~NQ=%3bAij=lR5?O z=F!8o0g(HGj{-&PY5$usu7y$Xp+(jg;2>{B+bOPwH)G|X)CoQMpfeY;bLYYimFe`6 z)0Xg0t`oepOO$pEQ-`+=SHNzoChGM85%{QZ4g4BcN_7_B1~KYsFuu~0auLn~3peG! z{Kc0w8{WL(47c%MUDm6z+(A+P34<&czE7G#jz;Kqz*<=Awt?|}a|CV74u!X-UuPOS zJ5Yl3BFG&7%2>UV#x2*Zq0+mlto5Ki23Iwq_6$unzuW;o1ry*rS5sDbzdxC8J_LDF zY}t(g(RiCwE?E24mCam|isPk!a~5QHvjh4$II7}g?ai-T_U8{CF7%*Lqm38ac`ge- z`)~l^)z0iYZW68}b!i_j=dhJ+VR$`v8n)SL$gZqgj7=ZT!97tk*+rKDo>ya!n|;OE zc|uw^==U;Q+Vhr)=@iFOGs(Q8>m+l6e&UVwxAgZWiG+@96nOl zZcm1iXKe5@+ex(MZXKx1)yA88X3@)T+QQK-lkh-+5uNO`6rO$i5}6DD+Tle6l%7KB z_vE6cDH?3Wq4TnDEgQ_+cI#o3V zR)1;$>A8^3<&l^vV@bHt(U@MLxeU&6oDFwXsL{p8?clPj5O!-#ra8xT;p#$PXuJ6{ zrA1AJYd3~NVXI5juG|(7c{d5hPDr6LhxUQc?^)0)N0_?(UKR8X^5AfWgGSk%cxz*k z9C%N)p?u}31p%*u37Y>HdEfSflODA)jr%8(eawZhD{&&5 z*F)hw19~uKy9)b?;oz^8Qc&cc0lTbi5k98+9!z{>%?{{=;qLZBAVk=it$DQ;7fzf5 z)TO*w*TgLR;^Q0Zu8&+cgP$@;{9$au5If^u-$@H%wc)Q!zSsd#tJJ+yp>ExUI( z8W;Q)#TI?0taQ+FoRO=6CBJC0yGk7K{vB5MU)MCYoMVWwrVnmz`Nrrkki|`Pt8x3P zT4w&ak7&3(5tm%bWsDz{p+#MpSbl>7bIWNy@~!9LBX>p0yW-UNag{mvvHeL+jlg;i zXI&aDd+b875-A`_F9v^+KSEusxdHC}S%GiJyrd+YgkkS4XS_aJgdR~+gKra!@JbD3 zdR~SFthy+VZF|XnWr#QIx9C9|*ICjtSB1buS1Qo+5J!6B`vh3G(+*LyJ!z{YnXpX4 zoB!n!mySM7VrdGhICd1-3;UY`e@ux2E27+K1B-O1)O{VeW!lpZ7RSO`jS=9GJD;}P z90>QHn+f+$olT!v>k7ZDSpZ$rW$DU76F5-f3Ge?Hph~oqpitjRD3NiOO27RbIKGUB zucCHRN6XKG=Ia@7+jd>*z!guha~-iA#nnvm;c>hydC(?!L%GlIBm6&I=}>m+eCG4- z0OXPq2One?GU1c1pmS4$VS`p3lXG?eEpc*(FJ_D|UtMQl`!i;+`=&gb7BCM76;Fq= zhqYOY$L?6hxgSU?nzPFB!8mL4C2)XU$lBsKe7xEp+*kKt3zahP8t?s_fG{rG?#{yx zpKj(?=5pEA1Rg%b=OSj42b*7zfraOsM<+cT*x()U*n7cG#2+zdcWzsWAHP?^G2*)H zW_eFMWMPWs`xMxiy7^eG#}%uK39ArhMSIF)@ob3$OycruC_g$K z>zHyFtutZBSBi%#UhFF0?0=q5m+|oGi)Nal9xFI{#+f)wRFitT*#VqAn1FA-*+xBg zI|=rUtiql8wy@uD zJ5RTx9}$aS;qzXmKR_Da)aSs_)T!*&41L_|K|!U<8tly34){g$1eiKv!sc1{bx0h!Z}UucojJq`miAcj zg*e-FKnu?+^vmx51JWyrgI~bAQ=(Qg1OEU*7P(ys%XQ zJsu@-HLuIn%eLRMQnbs)QpSHYC!{HWdux($@RwLBfYjjX%#6TZ4d*HUZFnkCc}SoZSnQHlJx6AZ8)=88!yS9MZ0_0!spW_8pn}rf#}>OgVQ<044)n~z?haJ!RF$e8P~V{*XcTrtwDOf6a3{s#gNbg07UG2>K9P(!%8$qU$#P-;*Vk0GH3O5c%oNTV3H0fuLd;s; zU5LBtL{rbpaEny4JWVi@|20Ng-;DO_~Jx&{(O69cpRjUCzhD=f#1X6dQJn?mALRP zI>&)rc^i$f_vOWkbU5_Oo5pquOQ$J~VNz$nI^|#{$Vb%Y}daLdL931JCqD+@j~Z$-*@SptaV5o9-wju30iz7#w5l zUo}&5FhB-7CKi;h*|J)0)VTnnU)l+(kumhw-c&f6zf6d_vY)OPJr;i1UlbnB{y|L+ z2ZOI^tB`%j0G(klWCiGn>n_^k5YwJ8NH7)c#|2|W@=tQ*mZKQfZ!Fq8I6xfJyv2A~ zDqet5WR*&Y_~&ar&cE?DG?u zUjnxIAz<`Arp5qtXP(~GDtO?CFKCWY6?Nl`u-MHC4DK3;l?z>Q z@K7DN8!%A3+bIH7d%h;Wm%55Id*YEoIeFjTPaJ(U1E2GbWXZ})|W(P`ekzO{{coHOrFUrG^pc>k5t*7YWnT*$Tl(BZmU@=gS#V+aC z4{0ecu3zJi>AB9>a;%GZF53p%d4!{f>o>vjxgJjQiNl`(CxpbU^)&KIIx4@LBRt}^ z(!8)j%uzEG!g_kqh#hQ=eayW4mT9Gsd>!8%r%4C!wJD*n z(Bun!;OxxbyA=xse|AyF0v~?=sWiyy6Gnr|L-@jj1+eGB6#2`AQa-3e21S1BB@0GM z`SDQ@(()gqc26oCC|Sl$y0xF2=~4h^FWGUO z2gi_TKN-wwUu68eY>mV|PX@CGM3)KVW;3g%*mj^ViPtPR#Z=`Kpmo$&`7 zyL9`s6O+pO;@wadzo+{xA#%48IwU1yp7sXeSRvANm3gRI<0q)k$)svnf}vU!<%Ss- z<$Kwf+3&B0@hxH|X+B?wzURAhOFB7|89Op?51q+f?JSVXQ{r*>FgfRQ?=?}nA;sS7 zK69}5yYUBJjRzZxF3>p5l3zYA5-wy9gb>SKd^cMOOz7tW{!Q)q4pAKZH5dVr zFX}kkj%sjKX)+vMRKZ2-Tq2geav?k?hLfM4Nq*^v(fqQ9r~e$h`p91 zpt^oXl=|C<=?zhs@zNCUPU|Zk_VB#j~d zM(5zJ?0D|6_dMc!KM|il-OimHdYx3Sh(>(=gwrWhhqeA*sClLXe}1+JJRE0^pAPos z&vyoBzS{{yFI(}(eTG6d%U^P3rGzgtnFyQKuA-L~`t!y!vtaQYBkCF*#!tFb1ZFv_ zk2imk@)h4?FtbmSBsw{q_w7>x{Uc_QuhoJ4Ad6fG-F%VkyzR~>7)%D~-S*(}XAqz5 zG6HV(=b-$m5ufkt1FzI2;JmsMf2V99Ib${irT5nyrnW7#!v5c0MBqmt{h% z>r~ET(FU@^zX;Z@)aIINEy;#wGB~pGvXMt>v)kG15}4a`xV&fZQ~B+0xlsN*T=3n= zau!7-!O5I5A*${)t-luoqFJplV1NqlvG;?NXDZ_73x=3?)e2@$Fc3GZxuX7K9Y}1k z5S@2Raf9C*vUrHAD8|R*AeI2{ceAg!dQ}E;znzJFVW{{;UWi*>T1Y-zkc!@C*?H=! z^YU9i!o?S-OYp_24BGK;kQj9+4^MPJy62jwxOjRpKF(9ZAsYvaFOpd-lFYt1yq*{D zbPd25WoMjW)Ky&a#Rg5@gkhulcVWpGedNB6!%V-ELe8TGDlARMy{&VFmdtH*f<+-N zh%**6T74*AE<;Q{*GZE!O0#V}pn_MVy5a-E8qucjtG9}+j zToaLkaUT=O?a9GnlS@A8wH}fL8B4_%%_aCdI#?ckNGitfX8qN|lXf-_72CxWqE1yM zJrvLWm!74wyc+d%+!Pn_TWlPjtlW8QU{F9dy3!P}qhc*(dJ=sx=_eLl~FKi|amE;>`GrEL%& zeJmFynZA`@+ZfKT7+wOGrr&d$`dZ5OddKX?Jjxad&&qCf|P-L)EVv#&t?cWD7gHyAv8v=AD{--0wpX z$XP`4%{F~$|BG3$`)0N<@4*VHK7S$%?6Y668T){$R1Afp5pRTC^-j2c4}j^wj^e#t z1Mr7=e^^)DPrNPn#4=Y6aP_bi>w87x+)g)%v>3#TIf-a#uz*~z4G?|1<>0ip9myc& za4~63F%IuM^w?iEcU1nBq3lgpdiQpi7!_BH+a4~WHPZvc3su=@e&{x3VVuR;4-?QR zUlXsbwGmaN!?1ReDf-^;EB4&sfxC{nWBb9H;@l}_cxQ4Hew_SD`2CHa+$>AT0A--`|~daD=9KhuGq*Ubd9@0jD@alQEi z+X(DP)y92!R{WsDLm(^q5uF<);r(kTfbqB0v~rw3FAd9r3?-gU^a|tE_7%Y}l^w^I ze30@-zQ|y7X`@6<7S7)u#LiPcPA3}A1NjFda=~Nh1@c|ngU=f~8Af@xhZH|M{@}6^ z@OQs4ME5r4owoRZe7PI=Drxh34K3m4p9mOx{R6kFsS8Xm91jVG)!gTX=VUHBtFH^5 z#_fK%k=R%jLEOA9T&ar<3417mNk<+T^&ikdQaQH-thDx*=LJ2GyBp=f*~(DC|63tV zT9E_^$(x0nt4`5Lmds`e?h5_ZwL`P@exRDCB2Ef0M8i?maJQ+4_;QL1dgtl_FIb3c zJ*7CM@GVKwa~0FO#bd@fk&M6ME4svHVAKpZGILz0cyCi7?lyFid^srnG*Q z)uf`qy%OB_HMcs&clnB96yiy;NTz=asR9U z49IZ8o9nuYyJy+rq$y!|yYaigf7D0M%5gZw^^~C8;Un!hA{~QN=L@3_Zl|-<3$c^P z3va6ZX~RkxKDQv{@pTjBH+wN3n@;nMWi{I+OPA&2wx2HCn6Ggp^KA<5e6o^j`Er$wu>;+=1yrflNmOtV6|ff_ay%iF*unIgQA?cKsuI~TgzbU zpP9y2MhTK%bJ?DBmw$Qd_AI%}OSbR$+F$rQFNk*UmJW@Q1;S~&o%ELPIM_7twD3Ob z6XjY$A>8n%@Nr8w?ElOWdUw|m|MVV&8;A5^|1l=w$;JSDkn@Km**l2O_|f>@?>M>a z=_S7DoPtZLSnU0PU~yR2e0*7TOrqCaDmpfl;2C8v`HiPP6l=iX&+CN;grfBuy= zTbJH_Obj|o_>jU0FiyKOxEopVD}sl>?nn!GtJ<6Y=14%#+8ZvsRO83y@Zg;|93qcA z;tU3KfSTM%5WRdW=U94$U`-Bm+CPT-JF1lIdR+_~x7{_au4_k9T4dmOpl?}yvB&W@ z>cuei!=Lg=6MNAfEm=@`DpT-Yvz$8Ko(PUc`vfJ+`*f>X6l_R*EtF+z;VDOVn6+C| z+@&`FryuPP3!?gowO*ds?u-T$HnV-f>0xN;bBk>90x`oT5#{3-l9_t~#L=&_QGBIM zBJ0D%nv!C?xL;vAAu`(uyqnUQj(8I$zRPFltg9B%725+u!zbC8o^y-lx`60!l8C{N zHPEHOMhrMG3`-vL#|Y>r&M@_4xd+_w&MHk&rP&NG>au$}|JTC$SS|eUWFlHM?G>7T z-J>#$Fp30%NQ`fk=pi1)iATvTa?ubTWo*FZ(wcBdaMylD+u8+(ZMIxaY+iynjoT8M#n z!_ofuJ7RIeh5c{DVQh~I;<(XQJZPGM{@+;KuE0<+by^`V`s^Y3!^Q{MAsODBcU=Bg zPb%(uSAusOl4*CZU@=%DA9qbZP7R#BL_O6Me6!;Z{ch?Y?$#g8_6>b7aIJ~h_e}s^ z{^E%3G<3wP9S31bmoNx@LolK zVXjpW4Vf>)D|7vry+o$mV<7XFY?x)dPbNy{SLd@_C{A3QcP!b-Y}L-*U%~C#cZj^+ z$n2k!FLV3cnu+7(ARKM-hfDm>6HM&vaU-wKU%N9Hj{fL@ve9PzV&4#WdiWcar#kV; zkH*5qhkNOUSKjBNT`#X?hI4;Z%1jK5wM0-h)A;O7*5eu6JM z)6EHjwU7UBLq_+4{1Ibdpu-hzo9!>6)tCY`hgNdkYYvmoYx1G@dKd1*^f;2(PX_xN z=Nez0xJ@E1XST{t?&aw*ljLhu3gPBAUWn}zz;bG(gO$~MA?59M+HUPQcp867$aMZl z&rS-1PuvedSF0N?jB;pQ{CgQl20eDgPOJ;r;ET&#%d5KoYNun0p zcU(!vA5&6EWdC5%<#irzwmc!(s38@v)|H^eMQ8c<6H;;hapqfa-;GMfgo^jq6{4!r z7CQBeuefel27cW4mflf!6~olyao7r7#3dHucuOfNXINwP+a98OvJ3vG^uzCyRm4Ls zhS!(DEEY@IoZtuv?P@+1|)ce0vClQSKl zpUou5+O&;(dgUtVuq+4qUW?_ND(8^fH;du#(g()oq&*4w&HVA+f8E@&NALJilVZ5s z^;fxjdJp=V*)~sDmo9AZUq*|W&GW&2dj+kpwN!s}6ii$AO6c;rBbx7YhrJ$};_pRf z_$=HMcGUM3OHX*&iW`QuCAW#U28bc=5-_V`5%HKCARa!X@lL2H=UZ+S5~L@uDM*8{|_otS^U=S^Cc3F5CwiI^6q zfo~mb#i5;}F~GAw`fl$hzTf7F=PmuX&k#&iPXNz z!HZ3!xcKnd#AELyEIMAvX->UN$f4nQxZxq!yi*NUE%!#}scL*{D+lvyEHLCiFMih@ z2@EdjjA1V<`7X*spyvJ)y0q4fFLav#D#ALtS;L<{`#ck34h*0_x`y$XT?B{8t>X!A zr2OFbGN7vOB#!ID`N>fwAb3qBUo3+7?+0>W?eVjuVwwj(^TT9_(Nu-}7k2zNX$6)2G$X7&I}lgT zX1@L7bVTp`LHJ4t#ln|Ag=u}d<6@<8c;EeuaH9A#z4jsvb@+wC(BNHE^?U((9yJr3 zSkQUL=`sv-3M1f(Z9JaSv|pUw>`$!=k@NGdAIYNB+0flLhzOs>=dF#agPK$+U-@3!J7Bl`&`%vgU$PN;}>GP(y9AJQQ z5IEic%k}!%3j#ZgVdq>|xr@VFNQZ+d(5-qE=hJ$Gh*|mYb*~%yTPBc)+A_HHbCL0; zSyhtyO)`K7gUdf38YREZ7ecQa#=^R(zSL$;I@~v#CtTmQjXr!k4%AXk3dLF<=+xRU zC?EJ;h{)E*mKRR2$EB<2*~J#6L;Aw{zr0v#9)R|-O0aUyAx5$7a5euaxq&zIoqV^;Fv=cVGX(=t4r;zD2Lgo=BP6r%MJf$Dzs z70nlAU}fGLIyTT%bc&A0&|f-eQ*R-rua)A0k5>3T#6aBi)&=YR{P6h|6|v_&L$;2M zL7{!Ea8p+WJw_$5yZbWXSOv@7*P4qnr-lnp2A5C^=KH49c&J=e>xsOa`S$mGe9fpl z<+q!XPZ5rPsLge;v?A~4X5#0GQ@IsqHjrP(+1%lKlpFct8Brb@i5cxaaC~7GFlltd zEjv5$$Eydz+in~t-#6mRBYj{ew#W4vc6^lo2+*8(kzRQ0&dW_E!;7vnsn*FrzRoTe zLR5arAE$-$ON~n40Kd*nWarz!&bJ>vG9tM{!+5RpMX>!Yi<3XwpTAj{1+u`0Bxjz4 zzuJ8wNWOIf>2WJw)EEk9v&`Y<*53S;zXaM1@dBml4t!*R2|U{p4ZDv#;gVz3q4;$o z{H@x~ne}Ax_Q&PG2F-YGt;#%-LyN&+#$)5~EgeYFA7+nw?$GASdykKmxHDVj-0$Tc zf=Cy`cZfJ%@w@tx* zVPA21m@s(#cZNoT^udEv!a zF5T@qlbu=VvbkgOJPm5D6E61JU5tlY=26$?08tfkaES5^TCp3%&-)T_*I9K`DzOz+ zCPd?_(7&+jruy9r<6qv8;>hJr7P6>6?nfbs* zEzK2D>sQiY_lmGbmWojBZAhJeFrSK^31yMR3yueMEx|hFtHyr@v`8N6(PF)TdNmzBff-?`eM3g&?z~Aj3auJ4VFtD=^MyaduYZEz`8$A$By?XJ-f+S$9-36_d zS@L5xMS_pUGx~6?8=uoS9s*vir`}Kec%!OJsF^m9{%s27!-f^XbM+6$&pwy(i(blL zMB)p{qn+XW;YlUnqB@0q2?^pSJm*3eQUO0pd;ar|7?|442%K#> z{?ZR$NDXy`?M9vXnNzLc{BtRcN&n1!TB-v(=EuW18#za|y(WDRWI)C8ncTvM<)r>< zAt;UR&i$R|L}p)^=~ujiP&Ula@ruw zuR{70n180nE#c)kCDgd>4__VHiOnbaV*V~0SpBuT80YDX@xAoHcelCNxkosbN*YLT zfQxvkZyai#-AdlM`HDJw+1h`aH*wYp6~9UfF@E4sN$MV{XkE$95nK1k*I7tKNqZSi zIx&&TW(A9dG5Kiw^eBD5#Y?OyO~KuEt#sQl2l3Q}(I_3)8|x+g#f`fIaj~%@-aM=$ zetJ3xFM5VzwY*9AQq~<;ZfCyz0cV9e{6e2>Ny9M7BEebMP3JP-`LnI&!s*;_`Z8aJ zBW^^MfBia5-ocmo#Jw*vF0x!JDb-}LV+PoB_bOt@#4V|~YtJ$+s>=a#GH@*ROS{N5 zUHd`0mj>gv1+ARccLS)=AB?jn>+vSv?BQ(Ro>;Wil;4^V47+T8($&u#c_W*#5Sn{{ zPLp}_8cS1QP5wx_L@R{<{3joJ?OMlj=}P%{Pj>$`eyZg80x936n9UuV!pQmcA^fS` z1<=QBH_=V^;TIlBgH>a`5YEz>k3Jm>JMz1O=re#HJ2n)Q=pdLT?Z$8Qb_A0J%s(?h ziQl%MH*DHH8b+C4<7CTP$=j?H$UDE9Yw)QitHSbO043b91qtM*k_>igEjOMr<$&bN zHW~cvJ+R!cRx01@UkL3B3B_V}atLkS|s4Hm0;mLp2HhU5yK;+BwPJiRB2 z=)MdRvsUC`QSU1f)%tL@4=us^dq(n*Yf|y%Wf`+;b);TPLdCoH3Q@={r|$jyM71*+ zI4bBhy;ABb4iVXXb%GAQA_G}$w+IX!W`&g}48-beSHzpXc-UK2Z1pt4?~7xw!^c{o zs7wXt^h&}TA?3oHXJ_cJ8@brEB0?CFIE9XjFTvWTW91(PzLLAKSR4i8j~m7AedT67 zwg}(c(&7sCSr7}%MB~v@xam__E;Wq_IM?S0_iNizVn`z~y?q1s?rCS(n<2qpPM!FJ zmIEPmDf8{0X~g?~@P?KkHGF+?5O3Hx9K3g2qQkei^M{^Hg8JlHG-+KRe@ZnMVj5cI zmqvy2;hHSg+Lc*u%8gRq@TUxhP3cE$6T^6er$umZ=1TH#uRs5yDhuq@>PXo|34bGg zA~;2Ng2=Acynp&oxcOrMoLB9`zfT2t`OOoa>8tb6?@a&#qv1@&Q*KG4I#jJs1XJ9> z)x_T*f2?!hWatFWbNqa=wSvtN>Mx8JOwc6KzcRQzCVTVj!YwqyOvB@K*WTI1pE-Wl(;(vh%+Lx(J;FkdA>JHJmSRWh%G-{ zPyUpOChWdieqW99CgCDEQ;gYb=F(8(K(R-94ptnz#=>-gc(XMT6YSK{@S?4F^JFwe z4K=~MFhemS(+fL2Avpd+M=^bkIr8;G(8uhZ&}5{Irb-i0R5~b>?RrQTOwPjlm@fpu zYTB-b#ga>CFPK*t)9|k{w6L2|w%W4nxUN|Vo^!rnyk_WkiM3}gPFy#fbE}*|qFpEB z**#mh+3hZpUvVRFT%S5__R{uHkl};RwzTILeKCd!&jzx4nx6cbtIQ{CTNfPaX2};1 zj)ceFEN*{{8{aC9hbD`S^vixfKCB=Uo_@BX8ZScmQnw=L@=;mt`dG@hf5L1hf*wg0 z(r`XtN(sCfS4=jg2l4MU^1$8eG=WbZd_#H?_`PWdqcZGy3#E||KGzVsEMztt6aAp+ zgbRFL-K#r2rQS@jl4R8=8(E;8T( zoLtG<6Efxtsbg&8HAs@lVmfVAEiaEMJtNn=kOv=s`v?K?>69-^hCGM$LTnbL`&NvC z+R&SV8OsIi9ufeTk0^`gW_>Z#)fOUVbQh0QJE3}+KFk_pE@~YKL)*j;#9G5e+{*EIM#M@US4u_sdKu>4-6aonl!`^VG8X@4Je?y3 zi@m1gW6SCz^v``Sk(^J#rLDhcg^HtCYBUD>U+je+H}n^Ga6$NKrvpa!WO2QQ+hOqA z5Eiq)SvcOi2fi5=i&;MBgmqsV>BfXK)Rrz562DeayW#@O9BL`_9ui4sr?C5uBV)?v z$Ck?5OPS4dRJO6|q7{Rfv;T-OuhV@&z&n!#Y2+(fUfapc$C8v_F_9i*26z4_D9 zREYE&L*LW~^L=XbS!|!p@^_I^KGs17L$>BihOLnDrn6X_mRG@KP<05u`DOt;f4P%f z5`6ghA89b8_h)iC)0xleIS%?Zb_2Cl1Nb$kLg8!FAUG{_5-#B-S#?1Z~Z0<2Bm=7<278w>SM&yG#_jl-MR6S$>jdm5^%b*%6N_LQOT3NGFbYT zD<9qHCx14%5Q4bAg6kD`YV{`_%9ZB`XEm4&{+u{)O0N;jHovC>7l(tx%&&rdrXE^d zcZMOUUBrkUHs~tr2SpNItdsa-)pBJh>NZ&PK0gwTMxP)dNuFYyW-@++Typ1RkoX}f z4>#4_kPLksE_SFa!SeOpLK5Sa$KnYa|B^xF%id&dNf>YUs|b?4R}lLL{=Dw9EHJrxpZr!MeB$njFrr2a z7ROoh^Y07=+i?S+DyJJaU4uh7N&p4q#18jyS!rN0jx$WgQ ziR<5NXe~WM`AmXXKe0hTySO6uJymFbCZjqy!1o)m&;vf=2_<3 z|96s*@3Dvqe-ogzd6!_;`!+o=br^Kp@mvVE)I|QZ2lO}45HtFlqVgd#c+${Ed_LD5 zclXqSL&vQ}iDwiV54}f5hY_(-EdlHHEF&>m0isi1=1UZ6Kr+{biDUW{V`zbq+s+?S z@kT4N7cNqz1%ty``1WFE!#Rik3>|cto$+XW{nWg+h-F zYiOESgj-j15L7}_x~sev0mYsh%GGHny>Jj;(C2-XJrt+=91i0xM;bx5YRP>J{Zf!rr(L> zCxwOb>QOB2gKv^?y82>CRCoby)Ue@{H%F2ChH2=yWC>T3zn7f-F%}yppXWA?_(u9A zgfO3tUtGn79ZHOIgK>1l#bCa8cRuv=s*uqq{QQ&*fsJc9{@rns-kJvsJ-oO$?G$o^`Sx3?t~c)DNF}F_$iQVy z@A3-`MBZ_JA-rhn#bRL*n&q4U<*#Q8@;zJVj7M?6!srR3N4%rIzK6s6HI2gQ7rJ=B z&IQ^TbP;u{tnqtGKe$}aiCz!<@Z6wwz+JQ#ttOAev%61{({`R>&Y2`!*qTqCZVVE; zd9eHHMRz6nH^Rjct4h$;sgpeNzEsq_FGHc#mUcN8DyH--!uYG3=<`B9@#o-7+;D^C z;?#5#Ydy!KIJPUky**HjI~;+>5-qVMyQjE9>W0@|```!L_M&aPG2Xv30&l**FKnq* zMd{MX*f>rUX0sgSLSZgGsf`jEeomvYP=bCAr^`<|eUh*HB*Prvl}6T%huwZ{D8lA$ z>fEk+6Y}0H3%BGKaXa6xA!PFeT<3p?E0#PaHQ7TD{oZqqH?-LuBf+HMTD)l=3m7Hm zape(1zVNFT$g(;hKX4F>(J>r07+Ob=5GKnf090($a+B&WWITViy-s%kHbM zXM^{GN!;p|g(NAX80Lu$#;-lPkgsg+nBz0M-;f5;W#Fu0sMda0K0!yD8h+1)FP{>G z^1ln{ioirjd%sf?^YG6`K91t)4=A_o<@$7Nsfl?d!I5WbYz{{u1ARYg?{`w&$>N^1pIcpZu>r z`w{%_Ic@Lx-}BqP{_nm2{ao>!w%=>}{kCVeJ+JM#ZMy9}Ri5@{ZR)>r+NS@juh9QJ z2iwa3d%i;d_g;l&KWh6t3jN>bROtUcze4}$5X{~)<$vXEfA9b5x3z;pv*-M;9hLrT zH$^#nZ(DmR^ndSB=(gW$Ysa?F*7m%%c5Ksa?>TcInYH8pS5DgWfAtmmzvn<(`Tt-4 z_bx^Gf1g32S+)Pijx|DC8~@+L?sK;ha+9Aq@LGKatvRG8mpsacrlT=*%E$%sjqaJy zxN;pW*42`?niRn12T|1Yo1VO9T|Rg|j-jLd4e9Xl!-4CqjCL<(Qq7h=Q1e@YdLOpZ zrodgK)0$Z9c(Iyp)W7aF!aD^!J*{T>&=0yz^+~~5lPam{se>eQ@K}6jQ$qJ#HHDcg z9dQ4{9<;<`B%GVlOvn3nmd7#wsHBn6wDnCjZEt+gt<@_9JJ(gyt|}-0={xNC2hJ&U zU`;gzp9c!Pb6Yh%a;rh17aXmoU%o$4=%nk_G~n+gh4wg8P3wQ%QRs6gs;T3Q7jC5< zDHw5~n%=j1>=wrKX=8S-8oi!&^c;)i(oVYILT_|bazxifbLf)+L$K4(78GZ#r^h{9>%UK;oM}*I#hx{T?KSBwu68F#-b9M2?ehF5kBK2`xPPLZCVvkRj zw627mi?Fs;d2dZuayj^!wg0_@5ZWO*1wXU)Kfz3%owsLTJ!AB;r9vXh{>SUeqRWyO zNAncCbnZ`+@X`Nx?KHh1+50gMHnC@p9C=w1b2tyqe2t;@UAoKD?~Vk2UKw-3Y$<=( z1Y*?)?jF2|zG^;6nl{Gb%t41)F4eV?>5SK->4)hh%jJ^QjF9NN33jKoB znG(2JGMh0X8i(oh){T-jUM=dk=o;rKRFm;~S#y^jck7I7ygE`MG} z&oDon#f;bElWXZC^%Pvic=atlO?Bq_q7LKL`BW`Ebh|xXWxUetZqiO(X;g#pia55G z$~vYfc)eS{juvi8R`6=-x|L4;9_T#UA?YM3ZDayX>J4{`^tYkGWq(hwoHU)Cpc&MIQ#XBW?Xl z^=K9K*r80qnXb6?obGk-Qt-+xZKX>t|E4yK*BhH=y0p~^KM!f4q0=7HQC?&5v;Am# ze_9=V**F$gFkZE6&2Rk40Sy?hyYGHcmk#yx9^-Z5$y53?(T?gcUOkKIs2W?BxAm_S z$wNA_kUfX>ude2=X_NXe1+Tg*&*-PFBNe=E|EVG}vxy2`t9`4h7LCkBgxOApo#HPS?%Svc8Udm-@B5BS$1-F+^r8`D}#1|q>$+J~x$AT?1)yrC;J6f~njQ&^u#4VBbd1I^K<@Z~po20f1UcKx;(p1ZK z3SLk4Y2zoBH@l73WkY>jcFzPqGF~g=wJ`g5DAqGxv;TC&PDNn~UUvrQrjDpvCi+bwX|Fyi0*XEXvxLFpa;N=&ng$J5K6}+~-=!~5{cq@2~Nzq0V$3O+I zcbh(vxNXr2UIv|-$&{PX3SKksz97MsEUyw9Ki7HxBHvk@^|tY_e`^z|V|A>R+1<{V za#FfH1O}QZ;RsJ8QldP0ARr z`__l$x(6GH3mJ<|^&Lsf7i(}89MEOKR-&dB26k(j>DepIMDJQO=*gn#rm3r`7&u(f z&N&*ZX~x;5@?N~+oZ~Rw( zdkD)xTsBfsr@nS2ZO|I6;FZ>K70sA2O2Mo0%QtG6QXp>|4+}^1#y%r=D|qRhWcK_8 zo$&+Xm4De3)2*HHE#sv-%@oJ9I4gK5O*KdNNu3nDKDPEi`%~-beb&Ery!cEXw|FRc z?U$Ki_+MuQudCIjcrwLV!AtsT0KRFlQt;|)GXT#d*(-Sc3DJWCjXnxq5yb|uJJv_R z>&8uO@ZayF;Pp+vCoFaMQSkbcWdMWYe4sPqwO8c;9yV3J)_FFIiew z`BB?1gfd?8_p@l#t*K-sg_JX123|*x zR{43re#Xm-`K&$*_koWk(e&!;+0^Fx6h+%+M9-$jSe($daWBYVHr>W@gS6?)z*)4e zc$z}{70je3Bc?0#Y0X*G8~>HBdpC>v-~U%XwqO>`3I11}-7u4yf1ak`_1J6{eYAg? zg4h1{KPY$UjB6V&)t~*bgrBP5HNA@jACxuFw*KY)8E{VrLwv({HJ=3hU1zA^wQ80d zhHZRH`>^paCczkELSyL@#%mPIU9IZ0+O0e5Ulu0-ou3*ic&&H?c;DYp!7F*SJ3c7a zSMaK>aK~}|dMS8yO|*i2vDOM+K`b|AjDeMc*O5juuzYQ;;B`mCp80iJDtM)(+Cft< zD@bSK;gF8EK6zZ6fCLzXLe-Hsej`}SO};FYY;@&fK#A!*~aKGF&=+%#73dcG$J9SB6}qJudVCjSD^Djj1xO{8&xYZ*~TO@#?R1 zTJpB8fwV7=#W8nW>Dph+#*Oi^I6$adpE3onJGn0;Dbb%v9pe?w{D|&P(SiMp*EL%s zmba)URI{@#i@-o=^3;W11<};bi_m!gGDZ7$ed0#n?D?m|J>2M%$N%(Fi3>fES+1z_ z+tG=tcMud>Z<90CEBjaOd(o99EC1794!F=F=|BBEz?mL7$HsTI#+dcQnMQ3aSMd5S zYoM~u+N6!w3YJH6*|;h4w)smsA`0UQa%kIlsIeg)Pu;&j+r~rHo$>g5?j_o`-Z1hX zimEZGv~9gHQnbLNF5Tp9<6(ynujr`C?xb!0%GeQ)?U!GoZR?GSig>&kbCI^KH#}m; z;oPYQ6};RV&fG+XnJ@?XZq#qPDT6wP}8PcJ$EVe*HNA5pz;6o`N172z5P!UEe*QVbGM?7<9toJ z=EuMC%*R^PSoTks9_&c_9Q&sYEH&w;Zo3t{u3pxpqndUpcy$hcN^7QuDtPt3Gzi0L zv?Xo4s%l5#gelGPw(-y>H4Q7>OKAh+1?$r={@ok}ucM_gn7Xn--p1>duLYK@O_a2) z4>ua$r+$`E3SLrHe@){Y1+UtvX?TW~DtHN3lW=ZUqJo!h_f(W67AtraZ=V3e7wuE< z@;fz&<@4LA;8p)T7U~-hD|ijGn+*HicPMzRppyW&oy77J+fzq-!jM%riN6WsB~ymq zO;1TZThBkeF_suw-6fWcS4qYpdBy63WCiPAk@d&rh64^N)*F?N(n)tU@@SMDIn$Yzf-}6+-yHvp|kmYzN_v-ksf9=l2 zL!a4mSbyoVIRmF3JS%S-50@>^M&G^l^0x8tAoKri?-r}z<)4)W&&?wgytImwAZJO6 zf>*<>EcoLVuHe-*JqtFtM38G>*jK1<)*43nKzZ`JGLf*CIC~4a-U%a@2RHU9Jer&%SY26dPW*sIC8yuJqO$2;9 zyNXDWk@82_t_^QLX;swg$6@WnT0~;DVnKh5|QSCID0quDV5T!d7d?wq2agp z>%5bE=XI`g?ZgPacFZ-7jfbc9$MfwsbGdEw zZ)(vtqxu(e>Gi&N@^iXZT^vFtG_OUyScCd<=>8Vp=(;Jq0{ytV7rCtoAm?s-NPM*D z^BdJ`wPdIyYD7I+NcF;B_Mss=YEX=^KPk@|&PN`~LF4l2dj6^p-MeZ$dbX$?Czr(Y z2~+dArxxCLuj?R5r*S>#HCA)1#9Cj(mT5?`g#Jy|N1h#>E9o^@#1)Zgk}G{h+@Lu& z;0pcrYWQ)`>-GIu@+njiF};Rl#1h8{CB*dFsj`IV%NQc2SMM=Vqrh&kF&YEG_opTjTuzL?vysvU=w#q*ArvW3dU-uUXQ81Cc2TF_<1 z@kB1CP{cMlD>$VT5fAi92PQFkfU&}5bbK1XdH#w0mbZl3odil#NA%E?1 zkptDM|Ar+bNGS*Ox^rg=d6aq-vHD@3F!Au1^$wX)Rcm{0bk%cj(;WKK4N5ealt! zP9q9^Eejye=e^|8Mjk{tRIf*!kGO^92hk>~SM!lO=w`n#R6*-er}Rwuq7#+egRSOd z$|vewiAfOx*S6ygjZyp>BUc<0>y7(ddCaZZauD?Lc=C)JJx9c9+zZa#M#L?<-*B$4 z4nP~%eyv<~wutw4eaDfDBG$Bd$(fH9+gt5?%{BZIk4L|G$Ne~S0QAZ)f6IM%d;s*C z^uY~VIXr^?RbVMcR;PbOtloQf0$n#~y+^FxyP$n8Ia+%Ov3l=(>TA@fX+*5vyN_n? zXuNw5dIj$Mir*A`L9E{EE@OkOH$6bC-WyUekLc}c1iehh%p>m?Ujn^0zw;qYa<@S* z*T-{+t4lNJRjwAwzdun1dOg!y$lL$i4SLm%4CaRD6vr z^~V?c7kKme-A!;DT_4J)81O5$SVTc(W^k5mE<8mfbQX-$NUhr7*(qw76I?C3lKZO^EH<4aqHqxh#Hw%MeE zW-J!lsMYJD;iE(>>!^pCZ&bi|XmwyXy3ttydIi_1;3XH{fnG1WJjKs$_2fCKSKAkT za+B}F>r=fVQ{BnI0p0lhRIjDTgS1t3<=J?6@6kxI(6&AYmx``D8xOAu?qpJDSDuZB&#q4)H$KSoY&;xBzoT3^r3cT(L$e8u zoa?=nsIqqqX((*s{NhuQt8on3VsVq}`YHu*hRJ;{NH-PQSe$>z_1&6^etwH46=4r) zj!G)}^*fq8_j|zAPE19|y2p^|jqA7{3$u~Zi)b=YQ33UAh)2CCesSm`XF&aoKj^s+ zreEX=!qVW}HTy1dRXS+{BHTd z)!gfSS-?58x)0avlnrW?~<1lV?6~e)s6SWXB2Wfu+}Z+unx~<+@zp-0SBLiB+M9 z&(4(R3?_?h%&mKIJKp92=g<9naW;GM;CCPS^yIq6TlEj33;B5Wkq+}+S59h|LIU_mui{=s2>zp*ZQLMkjTY+%mK~~J>u%) zA`5_X%dZ6uibL~(GjBDn;kt7kaLxvU}rltdY=kHV-&!eQ%IRKIa4Hal@h;ZZwLV8~;W%Smul8jwlLmuy)S} z&hEDZ8k%!O&aYkyk{)gOz<2~nISmf9N;`!b&8NOJO?;?Dsh5$h=`x@ zrb0t@F0{Gz##pd(6tDBsY-6Fhmw26x8pa4A7jl8~MeChHZeSL0p7JfZVYXQTaGtu# zN7ykl7p}9XwU5xKkqg&(Sctcf`z8lCuTAk3jvME~b^fKA++fNT0O!KgokFh#S-^Sd z%wvLSRXXr#j@d8Vnwk!rcUD#jtImn|-N$laV!upi^UJhcnEoIWuCwivor3oEO!(ae z?&X4#PbP4-Sl22X^-2NGYm8A+bq zJtk-j$pFqX|CuFh6>@>|^xLh%d+!wB?A88PFltKxKIgx+3D4^jfU`~9S0P9x39w4~ zM@lgnDOa{(9|7jJ<*3eod9XDG0eiZB+l7VyUFm?P-;bP$2ajsqniO&Ge zAH8Jpt=oyfSwlw_yDmtCb3d$;!JJ+qaBfwQ!6AL1`133Sgq>eWfEC$X> zO~Y{P;UM5Mbm|cN&-WnUIs2>zK3Ek3IADT0zSg`5+Jrc(?VcfZtW7HK>9bPvHE@WCm`%WCffj2I}IqyMlppdG|>; zWxgwLE;?+DKXrG7b4@j@vCStJ;QaagM11vvD{#K)u8Tv?1Ow-O(`Vo#C#`_9Ww0-P ztz`;))HJ-Ysn=NGc~5r+uCEyf_;WX#(fnqiisj>I$5f%FM#Q=9mI!neBe~l#(f&+t%F=SM)Lk&X=2g@t%*S zz&U%U4ZgU|6*zD33&$qvn!vex-w53GzB2G}{1J{{r>O!@-a8Dh)KCL#OS22OvO&-$ z@KYG>(pLjG%cO_l;wE+YT_uk&oFGvL&ZloAdwZW+)aUV&zeYF^+Xvs z_p^<}bGInNxeKZy@WTVjz}a(s1pZj80-S#jnTu)+OU%6;C)ecX#=)0w1t^1(>?9u$pBnv{9#7rR9%5acu66@=wNX%Rh0f4|Z_L z*fQiJ$HwRHJ+g3@XO+PD@TDlMTB8h{>o2F`w*wz=Z0_!|E)~DrdmqmAc1*=wmj@i1 zQ&vq&#SzyZa%}FdZj8bvSCoPCTh%N){75Bmez7zQ?`mHSe1441#Hx=s08jhV8Q2VO z0sMs?uUWkl+E~kVUzYTj-B$zWvP)UGUUMyQcJ^6GGsN$6Y`w9*EDt{| zGY8K7tnzS0_+^q7!`tyYc&&QIEN@tVnF z;dhJA=HhLMCcxQhK>-fEde(~F8>S7}SbK00aDLiG&)p^uoR#YH@CrA1IJbLz9`@Uy z0GyR5w;u9Jz}egA5V#^v10d0 z^NM^dH)NX?yHD0F&Br=@x(kfIc|tyR-2JTK!G~ya`EWk|W}Ioo?twe8`M4#!yTJI! z$O!*dpPNZO`M3Do0@bhlTYYY8D{lQC``rE&Z`)b3^Z%jO|7a(A9sgC2;{Ofp9t_n( zFqJRQR<6u6Tte}9@$Hu{Yq@kmLtV&{G zKHB1@fELNd!ra$=Ku?tF9F5qxF{{5Kdi66B=12Fby^yV3Bx2)?px6^lE{KKs%Wk7S zI%Yl(<^t-yWd2Ii^cK`mgj~@4Z>{cm8XA#s8z-|9`bBI^f6K`96ZWoJ3(3|Ks!?J|D&;*@Fp@%L*mqP~b=PM^PjutMlh-`j=-yhVeCe&lA- z_ki;sPeXHpHla1NE|<~Q1tm}0jJDFc+=d^Yklxoj++h0Nc5QDHenP=ZL6!MfZcXRk z|1HKJ=zDfU`dc^C-s1Dr$FhH=3raQH40X1ed#=dg)F!|&k<(E2DiMzka6>)bl)&+8 z&K~H`L=kJZxuHErM11;HXT2RXLZ!Tnf=My^5HzIqwf8H$aSk>JgcL&9_5MGTP>c|QFH87Nqfw2 zp4Gimyen|iNHw0-Q9DCb?@<|j{Jud6~gM?@r91O*D>fTYQj(n+xDq(f+s4_=B zBVL8rP~TD6PaA%7^d-E8>ZMRMoZsDOf(xi#H$pz4efvDPBUG=e{gxq@S-Idlx{()) zCefM_^BoPNxyM~2hH*($uNiIz{IR1RIG^g3(9ez^`MMczE^fyHURpeR z4>;XK-s+b67sPzC?r|f?w{Di8SHM#}vdx5k+f1+j1Y1p#Y;6U4%|9`WJR4#Kdadyr z$Nv~T67(vuHskNx8-ZSi`)N+}VQtW>wyzm)a^DE_`fg*!-{XylEbU)IZ;s{FQ)S3% zs#p4h!Tdtq4Ezt(YvS3@C|PA*!zZfOQS()(++r!(K>OEE%>rb1A`*NNimQL1-09C7 z8mM0N6SetWvc>o;)ypT*jPGcXBV|;tRy{Mma;FhFO?^iO(+W^lU?g1suD1%%;E@r4 zJNvFewVRg$4!F7srQKKz*sq`veNmuw531eyo`uNJK|JowtwKp-#rC#4S0O{R1lm|m zpzknc7eoJw?^1}4WGsgF>?X=VTmwhHQKs(!-TGM38i*m!-m_;noyLpiJMip1`_KW3 zBw&jx&)&2DZB-1)J#Kp?W#)lOai?DW?6URJ%Lb(c}txm5T;U%T$X*YZD9l7q`f;w+ZK|5*xk~RKWJou@uc*Vh=c)X4SdI+5xUP zT87*bZ2+e`mZ5(4Z2{YFD@Bc+lL2e}C`A+Ai|w~Yl%eg}wxCzVDH{59xh8+s4>cld)|?@d~84|*=sYntgmOq!^0($-9*@0weHUk?ES1EO(HJ09FeVZ>nyi|cV zQ8yxfRIlka-FUv^HV&YA)hv05UU#Zs=Ih(~x(dDfG!XQ9WLkwf+cltnUG4t{`TObM zGgPm|PrCC-neXu&+P`e|6!;q}#*jq%Udgz$14Xa#Cc!b@xW%gqok-Sz>pZ%q3f0Ne zx)AL<70p%1B5)Ak(@xcB^rQiRjZasjom%|?7c8kp{WqxrZfvbWo1YH^{LZ)<^*tfB z&strLCL=Y_%XDcq!uQlbub?`FR-blO!+zLqwh!p#-mJiF-D|)zpV*&glToU0AM}c-EWw4eJ$tY8J)#&d zYYzjxVvW3A{KYx46$ z=;hHSj`?Q&792vlLvL|x{z{F!hcfmAVvg!nHU2G9r+Y}c(D#7%S3E>pA6b(X^t~;5 zUXN7X1d;LdJ$q@&A(X0j6a4>Q>klEj-pzpHZXQAv`>q1c9dQ^nm|p^XJN7WTRDT|@ z&&0#X<@QCu#jg*caTQH~>-!x>dHiL-IlhO{x?UGK=IcweJB;MK8aehIfuda^TH$yD z^cu0^K3DZ*4Cpof_V0%5=d(etqY3(W5EsKU-)!9xBiubX2J{+r=Ssu)MYBM!+5@sk z_UcH`>yBv(T7KdZ=+)&PBfOTjXL?-BGKsj2ogQt8-FpZLr)!N!?hjm zMDc4cz!SXdP;WI)z`IlG(9lOtfbDkIAw#+u8S8_8^XpKe;uOF?0_srL?{0umTph}l zaRK~rTOB&;YY%#5Y^X!Wx;TPfcOpyBw(1k0*Mps|=r3IxvH5GeTOD`z`Yh0E{rBGu z+H_xD*1xKa6a~HE%Rnz}x6|AMeLv8vG9~N&$*5_+Mua+o9!BcM;==C_g zixB)O9`wpC8)+5)JQDPp?H1gSJ1rLUnpFIQJ021ZdcEI#lZ)6C2YTJ11Dk)?QqXH% z%r&m!1KsnI-UErW%^KR~;4xqPC(#e>8#IH&Da(>+Yc?V4j)5eF`i@H1A4U@`x8XU| zcT|Mx(IB;Xbz^D&I%r;xI?WucnD0n=&mpw<{BE32eMjpJ)}sJ99Ws#mj@CS-dA9v# zl6MQ+@#*KyoZPKAqGRrjH*)pp=kz&N?E0(n^{C14lO@9u6jwc2`yaU9)3wLhan|0@ zZBG6FYJb%56CB@6+YcC`1??GrF<1+Zb58Xr(4=2I>t9XI^=QS5=Hsk?6`ekW>YaCk zUZ+;9N4vwdL9ZLU7iw8bzfYm#VdsR~+@^>)&?|G}HSYeqIM6G5vM*Y;bq46Qd;TWW z={X4W%Gh=oxsKZgdKHV;7W8^4UVqT*ws`$PFMFy{T}U+ORYbMRn-&XtHB)_qUd4l6 za$84Q#XXM%ype##mvbQTD%c3@; zyV(Krc*1}q<*Ja-l^zF$BoNVb&e41R4>LmlRkNWy5 zMjhp{X3r-5X#ZNSBrhbWEF(9m50mwmF}o%S?E16*lAt&RFzZv=kDLIrzNW0^37GZA zmyWXmv;O$xwHIL4r*dRm0JFX(_uUQf9M?KjcW9=-^t$d>hfMl<2~4lmYc3$`?FFEh zF;Bnk^H&4CUN!GRv+laUdL!{s6dE=qf@i+j(=#KGO-lsmb;Pw2Rlarxy$%=>jk8doB?|Mpkvq8`!u(X_5~wxd;`61h~pdR)q{?KDh=VFS1}zM`vygUUjK;W zC+O8Kj-Q}cH*t&wy~^DT@JII;`tc=w_qBpFT>9om#?$$0`>rlXZ^207+XE48+Z6Oq z{3X1Nj)$juA4WBymxU~$v$_)IPrl=v8sF zYYQWL>3aU`eib~rZ6?vA>%+@sy}3wd1JX`?&ZD*L(bA~?(d0|x&cVJ8i1wiNx;%IAz9kb``o|moYI`-%Q9nh<^sXL!j_zrxSV@wtJk#~%F=9^tUsS_1- z_vV>zR@JWqZO7j5yzJz!z`L9?g6Cz6nceta-|m19Gk4uf^s+=1e3%#L+WYTGZ_q1~ zuFs!M^aj18>vPcS?YF-uv(g>(`a#$BZ=?J{ueaj*AM|n+*Z-i`WbqjR^cpa%1z+s& zC#Cdxd4O{|HpFg3g+4F8)mv(x%M3#^EscT&$cm^cA%H^ z`4{w(KL3JV>>0V>0uOqXiOnIsmhJNOoW(U{(*&92o&vTGIf`Y8{DVmjbq`FF-f*BQTr4622CoUA-be zuh*GBP>%Ie39D~3DrxiTLpOqN_T)@6-iPkV%zU%WE@pgK4_3EGp^yo_*_=P0(QmIs66Tw&qqUavpuUeD33@FMYg3??zgWKly~d06E6~eBtZ{)}Jl%ui*jP&vMf+EU%QtK?ZUWgw z^$PDFgNJKskuy}Us?j5@0v>(FFQ{H_DhX)VyBy5wQBTs6ko~!A%$~p6x{YhFe)j|K zqk5IE&&OYzb%{XrI{UQ)OFAZyy;QHiG#%1H-I7?){w1vk!nKvw0|AGLHABGn#abfZ z8)Cf?u(aL?nAHq3Kj#3J))E27e~3f9e$aRJRIjJu@#vM13wmV?`hh-1X$!1>we>OJ z=PJ8{Z+7WDTmEp(HSo>O*zU;NPgH?=@As9CyzKy0sP`(4w&fL1Tn684=cnPk#nQ3h zo4r`|34MC!CNSSDtIclFPzAkM{kAnl1@vO|Tkcj5(2Lc0y1i;G45YqU!x9yu7do6QrFz{9-i6(N_a}F#Uh~6Kgpr3n zV#VzN!^f)*@>dal&x-W^UZ#)c#Fn`vH)|KA?pEG-hV&nS=e9rgQn4riOU(9?I)dNQ(i#D(gH)^Jj2`!{o3LOoNc>JLvFs- z!1>}HS9G+CHJod%;)*W*m5PR z*mU%8r8RIas*Xdp0~LYu`SJubw^RoBl+xpylez%UE0S20Xxt6(o|&;|?jd<-)5jhZo#VE6OM*~?Mm92wv&*`I^1xu*i>pL=qU^MIMa=Rk5cvR*wGc*YrLqbVyF1D;)% zjkdi?gf@>|b5P;#WZ)dEl7rgfli_zKKFvlSl~w>}$t~(Zwz=BC`e4+<45VjrOkjQR z_u^c%;^z$D{KqsGMP$r?a~QfI3}>`ocAan9S?45 zV13Y8Js(}47SX`2bJ@^5szqS~yUw$_<{_h}m4J)>$wSKHPC*-|rPM#Z>p}y&&Sy>Y z5f^!(fnDdV9eL=z#<>P|owwQ+pogZu62^H%Yc8^_^Z?G^ujM1_)CCRfI&WN)j|Mc) zhjR-&^3jFpg$?XF8>Z%?&X%|acAY)G<|0EqPvHF7sQ~5no+V+N^C+KKi&GNDc_!sK z@>QjTaW1C(kLMNwwx|DB*~|!N^O^o`TFwFqh~5wN>5DnWc^kb?4z8UG_%*$Mq6W=`HXo_J z>FqPXv-gSW8=p0UW1J;a-%}M{;MrS1?*~KEW5C&%-Y5MXu1Xl^W_n+(tx5*Zo-e(x zI+rEGxu*2K>ehD!c=pyA`CvF`H{zf^9|a+++JJ&KCkw! zL}P!R0-kBKKc2S~02k1H>VKdX+6<@tXlvhE;Cz(!qk~6}!SB|vel(;OI6KjPXUNNd zZ?+rlk1x_w!Dnbn`|p&HOTf9)It_gqK^i&Cac|V}E`ZbNc=)JP2HJeKPD0h0 zGKk$9@pQa;;z;v$=>=|1;X+VH!7UI(G4w%WkihR!3J z^Q?ihI-Ore=qn<2Z|tJ;(P;+*;M|SQN8Mx%;M^s2KDr;O51a>H4n%IU`oP(iUblk- z6%o5PX3_b@G0hq{+tYdZ^E!LrlR@X}KZdrza|)fuzjjyy?n~$Q=`z;P=5^O;=zy;^ za1N*QZ+|&!_}x3ouE^-;MBv;u&J6jL`T^(ivw>)IkRfp1yTSpv51#^@73jSGw~4-U zq#7MpaX=r&IRIy+j}B=1TYKRA^I0HjnrR4}t45h2Ex`{sKlRf`F-ZZyCxNbuc3aH` zo2(tTYRdY=k59rpQ$ad{6F(0{*QM5 zZ`r5+-_>qt%^U8`jugy%vubHd2x&&+pLBkSzWtb!JW7RiYz*!1^UNYKn~!eO{(k)& ztsT++o=yAv>B0!i=A)$(l~Hn71ZMN&eL8OFauJyMW{=TvW6)w+JEC*tBkG&|+9eV* z-|PcA4)7k4n9W~z_CDr3-lxL4m)&#!PM@l?^Nw=%i_)Cc|2Chh>UH`5a-Zt|&R4ue zGIfOX|6;kgm|#YVhe1D0xl=)a8uhREQ zqh?RS&MO|^-L&qVT>F~4@$&%Gy<3z%az_>(0KJOGxzqahBfOaEHL_NY*suDEE9rZs zA&)qc{o);7K=VuICe0&5e>UPVG;ek)&40+rJ^y zAYf^}1Yl`K1Yl`)1mJt>&$z*f2ceGI6!@IentKrRaw@!oLY%`edrx8CV8U}k>iy;!D)W`9f2tAl2J9Qa%Wda*o^ zJ*_#Q7s~_L^lJm?wVq~%RCmh(z1Gsb4+j6t!Jcn@arT5MWXg}Dcp%LOR#Q-*d)!>X z$LV`^Ym?fEPyA9*(`uB&4TLuBY!<+4`zCPqyK13-c^ppS*giwd7m@t=ESkH04d~TZ-iUutJRb7; zCM3`1x8=tO%r`sPJDzVbPUo0!b`i}QdJ&k*G2iU&r+$23eLCccZC|0wD;C*9e(4}B zjH;in!z}-eW!+rL$mN(Xg5}{X`IEshpBT%-ndjOmVegf4X=cs|U0aU%FjuN^dR$56%)^m=nYmb8W{VwS%>H!YU9Br4$w`VH>(ZXRTu<1(zPE=%%< zsFC5Lcj3t292s9zg0lu6$6+*oyL7j^`(PtwK+}lSiT;o)Atk();sW}6?OO< z&ENivw8-ye+i*0^-@f15i>PQu;qlAc@x7C=E`AC2jhCs#<;9xQP2=HiKLy7-{deH0hb#uuN^Lo&0Zrncf1J{6F z+rI1a_my)&uSa8OF4LzO>jB6U3!zz6 zHX2(Sn6HoJS?QE2*R$^kSe{itt%|_DBQT|zSKPkRTIQQw-hCNS?mM7<@CRS4y~~Hp zd?brU50fPmOti@M;%MAej`}kH9K>dg+wqRg0i>&ihQM1L$B|U8$q$u;QU1sADyo-b za6R_>y%k$p_>*{=t;$s_z`r(`lc`H*k$Z!`3Dz`EY~%Q4G_N}3`1pm?H!J3Y!L>at z=7RxV_zg0|04IvsVt{{$`D1`n#r!eAL&Xd+z|w3nz;A907m9};2fb8B>j(qK90$F= ztzCz%#Ge7ZP|YCz&bDKqm*@8Be51og$XA>)If_5>(hc$z4_=GnwWdyk{I}J$uDrtQ zV$kctoW6Xo5}LzK$HP6ehS_~N&E}^4i)FRRaMLi;YYNSCd!+A%nO-c(H>lt-7o zQ@!M8kx_mR>MQAZSU++EX;o3jcc~Ba{hjl8h+7tRrM{yrCWnQO4M%VW)hl#&jqpkH zC@!XY`F&`@LuaMq9@KZFF>wsZde{v=r#{T<8FPq-(m*Sx)$LgJYAosR-xHmU^u`m# z{5`m~()>NZ2gQs&!2V)(A7DiD{f<~40X##@_XFG}X7mA;X7>TMZ>STTBaeVyT_S3Q zlwk-u5`81&-)+VbN^Tm!vKR)zA{Lib?in++PXkXLc22EAtf zp2QEdYzDnPcgpf-+a7~n#!CaxE1O%OmjTT}JTkEw^l~^I%9pC|0lnUfd5NG`BF$9v zS#=Qf>PNE{SB4}Z*1uRD<7u1)dTpn9j9F13i1jZwn%P+LB^&gbn7o8o(9D?xnqN9( zh%fQ;ea+?4^~T1h`ec=UxKKcSM|bYt!QTRB;6OTmJ;jPx>u3$mr+V$$B9CXe?!{ZE zUeA_1#%=a4SdY$M>BeKp@Mj9bF6ujaWHXB-<^1OQQ{U0YbxX*S#B3Bw^GkU#-x98^ zG~W{N1u+8?urwPJa4pTx{PcAXU}=6PU}**>;0Q4r6Y#XS-uTIc8qn)!ixT$rsR6yl z*o;MP17Ct(jW@m_=h7~O`DP0;%y``1g)krHOnX1xpvQaYUlyHy{Lp^yK(Cw_Q{Ihc zTCwr)j@DB&DM6O7{&j?AF6ljd271NQtkDvscc9lwnn%i?dk1>4Jko6W@1WOPnpxW3 z{WIugO|wjIcRK-kvAol(z866+mUo(+as>2ZnW#P1HiBM5X&Y^)i)bMAMST9`K|;EQ zpG{jqmZe zW+i-|>ZQBGloXk+o(A<=<`!zK z3tC%%AQ1~hXxyR0kE#=}P1=1Qj=??Qb?L&_YWlE3?m@!lb>&T{@2FYKXNGGl&1VKI&2R=>DP}tZt`PH| z0jrAn&w!;F&VZ%a&Vb982IIKLt3j_j?}Mft8iQVHzl)I1HVwkQt16iATY}er z2EA_3tZa{GMxd9on5PYTN%OQpufAgDHt5B&xaSVl;MsV{^1AOhXn|hRyl$S2hx#ffVs+Z&5&)BKw=7!5uFSn=+ z?BtRP&tH|c>3BlYO7I;e{``S;%Y^#vRIk$}BS_NU6vXnJ7a@+gJ^O&_s9tf`d16?h z#aGh)<**F$&*9oi^UndZjP#bIRKU(+b~<2|uWo!b88FLNZ}L)8N4&He#H$6{!Tu2y z%Idu3BsJW zhU(>Zc_4XmYZJOg^=jYy2`66QIXPP2I5Bwx-nrWkd`GYgwtvHyViP!4 z-!D#&`9}i=lma*1u|sN05ydEcmrFuTQ$a09;$?{sMrddk_Ftzp(*t z9PJC3?O(9NaVB8t{sn-gdk_GY?o9yL)odgFJkDA=E6QtD-)X~TQWe3-@JUJsy`h7#-t0eWSK`$2$Sujrl;fxEpyFSeJ2-grmQ zi|sdYsLciRlI}MFdX>>VDYmU}1-&|__9FK_yYS;Weeqc1{=|KN4&OoNuk5&9WaPaw zXg}3!nCv@T{`on_d}1?4mg63wW1t?@?zIyi@EQwxy)$pc9ZR~P+f*;(%e_e-?Yn3* z)oZg>e`1rY$NSRxYpZ52ve1QoYf1NKF`)Z*?09Ah*H*fJ2Vl0xN8#-;fZ5(3_`+zw zY=02bI`HsbZ&5d@ z*R2zear!@|=sX<{e_Y>(&mWV4{&m`7AD(na4)juQeu{mQY|uKY*Q1hOION0c`&r z(~@?;Z2ujHoxcD}_t1g%(!F)yxcvP6`23Sj_>N%0l>NAQ_-}#v(rXoFtUoKya9?|vu!hXlF&6mvr^QA96bQJr>?+}&zgqya zy{m3T6a!}aTRA>o3z+S1<*l?4uyl_qz-;fTNy#OE)t4T_yR9~WUN`)YVU4_vpx2A- zd3a0vMd)9ZoCuYVSlmI+Kb%w&2g~5*mAjR+%@_Q8p}yI`n`{^ z#&Z_vH8NogKCPn%`-^SWUxiO|r=i}vi|z%szcmi@x+(4#270N9`-OpC59pp^%cEmJ zFC5Qf%c=;_tH)boyiO+u^twy;BkLX}?pLKI?pX$U4Q?~W@3dn0Sh^qF>L+x+vjfxl zkfE|l?K)*;w|12d|mgjwLmtv2Q>OALK{BBiMZ$AGrR$fq7!t z{%&8sKLX75fU~e`0o<4F4Y%>|dBAM{xIe>=0A~Bgsmh%K%=UnL-*FQ#+Z)dDZzJGg z?~db7g}8xz_fh-uI9~ehbOY;O#%UFJO4t$5%i;5K+<(dl!hEw`J=O8)YG1;9v)eTW z3QD!{g!yI-X7&=6>n?--b){tp-uPiAVZPbPThsBEfFX3x503QuQi*FqYcTW8W{7+3 zfnJB`ethUbJm{4u?#Bmu{i1vJ>HZY;>fDfvtCkoG?0slD%};w5pe?X>pwDQonyix= z;GR}_xNfu}w7E<3&>VKigJ-X6eICy9kQdlH)?aaXIKEf`JbNQ)ewyKsBJdfS(p)vQ zCui%yvp1fen?4pidv|CK+g69MaBd;ZVH1{{fM+j8J`eXw8!fQ+ty$p(_^9)#dgi^E za3UKooLvMy!-q7FPFS-O_?Vo|z`{8f zLURJ!pH%|qzs1RT!;??Ic_z&je7oWkocoaG3XTo^2%MufCgZtwt-!g7<^gIRtpv^y zG$*k7iZW(C!;W!b_;A@Ecvt?`D-0`Ys=@p5@884m;&fHO^?f36!hL0Eb7oH@)_AIn znV0OcO(ed)MH$||52=d4(+?_R<|Xr@xr+fFroeeC&0`E`{{oyfX?|lwUk!M7e>^P= zD_m8FbI-Vk;g1q^cz2(#5snSc4uW^_$~1SewD}8gK0IVLmX9_C&O2z1W0)zl(WH5m0sf}Ixq6!)9@(3&k?8%rmF89URWb$6 zZZzL=N2)7u{({1>63x6|_w!DglNniU37lxx6~6jADA`+E1$9g&P!;%=&3Wo!1?`nb*y!L5%6g_ zqk(%>hXBt_&O`99A3=bNuMETI4hKP-9diD=@7;v6A z$P#y)^a9S$Ji6fIIZ42|U)o1uSLX`gqZ|8Gs8LA*o)ur)1pS5tz%$$a3Jcp3piP{Y zEbeJB49&~!R{P$!Hw$pFr!$#sI$_jLH(re(DPX-o&ss|{ug zT@K{}XREcXLZep-aF(Gt#`7O!0%wQEJB9IdTw|OA-O2@RpG@GqbV!8|wXD8lAxTTQ`zuP0oTUh@l2RQ3~N^S@-D*( z@Ss;7oZIjC7$N!sT~E+4=en7hQ1&htIA^Bp6b3EG0?xPlBsXwe0dP(*++F|0J|FlL z&h6R|=aUDVZB52C+;SFi&u9zraH}yNIH&!LYT)wo;di%Xg*Vu^=L2W= z_67;}IUhJ5jy4jS&*lN=i*2jw$NtI(&Ye1|>h}ubxxqh5>aCOWfwM5{JxGdT}9%l-NxF)gIuQql3P_|QX%e4U7=K0hznd_rtv zIq#Gtnr4Ht@!9{)Nr@XL{_f!oXC&lT9&p}JlE7Vgn**E!iuCry$8m{F*7M#2H&}#1XzAWH8&!dR* z`jrKoQz!M|@;vi_vz)<2F3&U_IOmz(=bUv@fzMgXo7~HnDZu%8Q4@#aQvq9AG;(J5 zRzjP5hc9xf6=}e^+3g}16P5CX;Ou;99rtiyHgF#O&qMBK zSt@Ye5>99A`Ly;$|KF#x9&n`-Q-O1d;eBr7##G>Zaq~KEVQjW|ooPP*H~KeOANifI1i z&*E6%{~}f&eYTtj{JpjGP;2u7%zU$^y?UZ91+l=bj^<28n$H71tuL>l>(hPt!};6L zqO$8~XO$1&>z=pJR9O)Z?s*qo@tg_AH#J>BX;;Pe7Vj>ht8`CicCOdPM&w>7;<48+ zqGN)H?N$)9-g*wSX*`M1&`=Q@cf}}WwTPEa7SQqIBF?DUi?-JULi;s^G@GI}0I*GX zE$T1$16EwL2ldgM3%Js-28H|-+mHBAgG!o3Ty%ab8Z4O)Z3ez7Lq2mw{MV}#WmJkd zB4snuXczI-@Dfz(wgB2EHy5EBwLySS99)aAjfk^~HlR6|#5OuxRv`uDU}*DgOFl}U zBjW4{d1&7{5tjw$qW6bIJhyW>st*o@_N&5@(EgPoE_jrH5=uopXZkXvStsJIXMEAN zt&5<&M#p?)&`redqn4nGz=d$UxwjX(^g=v-c&j&hb4A39O?^dpLxx*L++(K+`h8u*U#|>B7F!m>xl>OKN2z`ymOE^K!Uu_X zG}1tpmqk2s$N=R3Q^aE>{g6(-C2;Q50u{7bSH#hB-?+zrMVxu<6L-AVQfL!i_JIo- zBw~Xwx^K&H5kGIN=GL@{*x}#_ZcUwt->$yN`9_NPtHE|oN0q+Ur}tq%KsguLQ^W_? zS8~O&BA&Y>fb(7{VvTM-+^`%G|GeeQm97(Um+2g5xn0BtHw`#$pNL;QKPTCHTg1~x z{gf1667kL>s=N$xWdyUufy%zP>0*Tcq3j=vJ|xg^g9Bk6J3 ziHjR*o{PujQ_>n_rRTN<6gB8S5szmUP8M#Jh{uv5Ch^p>~{zlge6!nEoO@7(%@ae?;BQ&;Jxs zKZ*Efct32UBH~Hi)v!+&5l3tpfPKG+_fn?WAZ+qf#P`i7;7MuX{dxO^5$+`;9^bl3 z2Oo?Q@%(QR{8DCI} zDURD(?hRO>RUF&*^BA|Ji`ZZT!O;>C2hBc#Hz|ww>b^$&I!By4?u60|m^mVD7=9U> znu$2!@nyV8Uc{Z<@8hxSyy15rc;3dwr^I>6t+W|ey%y)MG^2+&OD&_$$953Qs z_&$zaAmSLUH+bMMPxw2(KE1)8UwHt&9rzA^Oc8Nh{|{JBLBw^xTk(|@?$GAjjURZn zWIA96%WrtYUlE&b`HY1VZg4!bxeYs)PXj!9O9yVz5b^W-)R$K83dil%|HAF5A{KJx z$d?JuaNO;w98r-K@zn`kN$(3zaNK-VSMs7z#83Mx5;=W)INtYzJlR#@09fxtcj7eE z5%3F@USw|EWWbeJku)3t(b=~W=&q@gOrsgH>7)BVn- z##=+1v@@zCs%awNI?n;5vl{|@Nl%R&{4V18Kl+i3XFMGLA{j_NI&*-3^cqB7@00*; z-ZF@EGZyjr&x45HTPrxOxqk?m|6x2})jvZ>*D4Wza2iTd7l^pJcqnh zA1dP5BL?K~O#?XIW4<9N94_J~ql`$vY<)QX%4G~Wr8xqyqpdMtEfbR|B$ectGYuuHP z>`NjJGPEWi995xBaFjK1eXk<6|7uNM*@$>-_9UX1qzuPH$Jmgd&3yr{yK6^UzVred z*Jex38}$xIc_ri%Z^%8Ns@-$LTIuIL|st>u4?UsK5A8?&YWNypC zxwH09BU5VH;CNobG{Vnr2fS|bG$P+eJom#zchd9g2RPn``ZG&(M0|6h2ibV=9UNDD z?m>+Hz5zTt)RP=neGND)$BRtv{}`~z?HOdx$)|vC4Vyu3E_?xau8KDq+~Xl&zPbRT^Zorr{-Ets(9X}a)+}&vE|2q}g{8%(SG-DX@yv@k=G;-q949?Layx_M-Q)bM~)p6M^%$tk(aKGqx(0sKt8{hog?$p5&8Iuc-nQY z39`e@cpCY`7&-BIJPipqLZ0v~o~q8)M*gOsNRPoA74H|@@)GFAie=Gm7m`4y4XTXX z!8MT{-0%o}v~3cp$E~Nx^UMXB zJ<)v)a$@5oTDW2{ve)n=dhbUx@`3*BjLfNHk&kysq66p8Kps9ViME~41Nr3QBucJ& zBAcvDq8n}9k-at~QMUmtkn6BL&-3#$-T8Al+)bhta~2|--A|&Hm!~4%dyquCJRX4@ z{WOWbd}EDl@gj-Nc)Pw8zgG8U676`k*9OkqKlbs6JkH$z*BfhO?!WTw`dn`3_q{$p z6Yc!I`Z)`c`F-s#PetbW3=eCe=Kd?!B+(V;+>y&HN}{8Fbwr*&HHjV>-xHaa&-EYC z$h_RHuUL%C%O`yP3}jwz)2EI_?p7m-p1rmPxzD#mn$cu4^4e#KwDC9gU1xURELLAD zd+$c(^?PW;BV=B`?QT6q=JmU*%1dP4PENubWZr(r+1e6Mhqsd%gDNBQ_Oq#CS!CW0 z1Lm3_^L7~Z!x%Y%wZs15M#z^~yFL8V5qbM+cE;<47RVQdvF{dFZHfG)Bm1^!kvlT) zFBXkGka<4}y3-Yz_m_8HJ0X8y{b-`TC$jdvSXwu%J96`Nv2;;NZ{!2RV`&xNVC0Le z{|0>sLFWCv%kNZV-ro<;7>3OId&RmVkomY_zG);fA5Q{PXCU)&<4yczWImn@889As zJsX$$9-D>C$ED;lg88_V=spwe57{{OZ1z&*J>SFGJiZJ$cyBm8USVHJ*^FW zH>C#hy&?~~D?}gJEY5?@|0p<~#e4U?Yoc9_50QC%*l(l}vK${G%W)?1T@imGw-9kA zvK)UR%W*8S9LFN_IMyu540!;HdqXxhMBeM=K=)`_BLCiJPlqlQY*fvj>UXh1JCC>X z>slkraX2!Mw{5%|Bl9@i$EgwWww^ZhryYyqS$$nu)|C3b7ChLfDb-D~L3=2R|3f6f z@_GU7FT{EQnXeZd7TF`W7V8dVc|C$GuRDPIa^zw zx;AWs+$OFDZ9PwLXSN&0Aj|7e4eqUcox2p#t7hArN3Ni#27Cn<*z7#x@=>z)pyP=P)Cm=Tx zdIIt~p(h}JW4eUX{2s`|glBAp3td~GlhPI>?U+D zWLXD8mUS@Xx=c6A^NL1}(MgjkM+v@jWrS3JrQmr6LnV_tf*%UK4*hE}9j_;eMcyRz zI^>T+$3vcYtgp0kobV~w-BYSX1urQKlGZ&H{DbL-v$Y1H{{W#kB9|3V3wE zXpg)6NWIcUa7&@zqP?sc>bl4gLcc}6E_7Yw1y8fp`7gz_(F@kA`w2kXPZ2ybzQ3yHc)_2~|oiihUF0sbb#*IZ^DJATMS6EGrs{Hn3xW0h!BwYs#Ou z=Xyi(TGf4k#f(vtJ5wFUE)7XCBm3@)ue@^TJBBzV} zK4dEP0g*qiTt=RK5aZje#VbhT<%09RvGbEd1P^8VkM-RJ%lnmh?MAU*i7f9|BBzUe zPvj)AABx;g?0X{56Z@ga^1dqaX|b=0Y{&Lh$7G1{--PYM=BfLj-DvYE@_U+K&n9O` z14qI8UY;eJPxMBgS7I+1*+lI5B3~4H!N@UUj~F@1Q#nE34$vRsSIr$1ZNJd z0i&jixU1f&8nCys;8FGT;Y@YGhvN0&;6)L?<*zjY{crA={^JF;q5EY>4jG)ba!McH_u*KaK{TpsG1;aNk$QOOh;PwE)q>?#ARUnwR|n)aS1rMEoIUc?U@J&0 zD|p;iE2zEC4(%K3H-#rrHpqF=O##dW@7UE8hFueJ`=lRDVctx^5y|%O<)J0|msxKM zj%UQWpwH!IFlf723w-F{z}{aLJ`c4Vz_zpCoCEf-X0hP4gPdVklsTqTBhMMSRTKQN zgA2GNn4$g5GZ$#T+Z5Szl`CAoQxDmGN-Hpms)KwW!wqK4F+q-5(h`R5uZw)Ioja5t zZ;TxM${k{N86htWRe_d;;N&b71fMZP`?nMiP(9a2ZnfJ3%oYjm`Q8Jbv=G(9&uvgbq7(F)t&MDQrV}j5EQ{>o=m(igf8zRgdQ@k~ zuC0akYfF8>D_E?N9nSc{{?*^n$G*EiY`!Me+CTUBL*<2H4Ica2AI27bL7%|#fl$Lt ztkb8v27*bh}+#RYMy@%{m)D8S1A0w~0 z*#j^f_!8dJ3slyF=RvU5LnoqBH!K_0*hnR z$kE?JU~o;L!vtCO1Mta3yYrAxXn0y^I5A5@;iI15)Ptdr=_7QWUXMbd#k8&Hzi>e~ z+@V5K+PrrFwAr;5?awcS!NJuVknesAhf1l-keA&E2Sc~z$j$eKgYHkk3m!*8s)3chs=(GL%pXXZ@C)<_HCyk*D;Ra$1oy4|kR4aYLF-#Wle{t` z4r(X3pxtM99GooI64`lAJbX#2C$2pa5A&CsAYXYN55sy3oinIL0_>b%fc6Qk5}>nv zb>uUJ32yd5IZm}o{Vy+6kdf=@jIB{eb>f4ps`!AoK z3JtvJ{UrD}Ug+L+*n2LEZU>=H_h(5^tFU?rf4EiMosT)vizL`*>4Dli=QdUzsH<~- zjnA$sC$hLM&;7eTHX{CyL>#;0*8(!=VFcRi72GBlEJW-vY(h0y{Hrb6zs|7%Qrraj zVAuB0FI$X<&l~lGS?U{D=I`f6LV9)v@+DOQ&=1v+m3er2js2d<&z|5oIV}us8*f6c z+_wv8M|?&uf87;ktq^;xcMjBn=j~bn_rGxa4e8lB06AHEEva&C0J43u1^aeMJn}}% z{M>8LlaP;hZ!Q&ni$gw_y+QIn7lvG5^hu&p7vylgdep32OXLkF+~|Bi6XXMTyVB%l z?=U}~=MSLP@nWy7X}@@yGsqI{teoj%OHt0Q_1O6gAx$NoPb2*SG^oAMlV6#2rEgDu zK>MK!E!nr~#r*Z;feC%<>qfc%=#lTG1!KA*55Boh@(Ub*d?BKd^pl7>;$`?ruIqb` zSX;W$3+sIvd%r3F!c63=x0B$VMHVt|S9K5XLgwwz>Z{o6;qCBtWLp)#FK>s5S34r} z_I$UUKQeFUhdyQ@^Y+}ZVg@pA=l;!yBlG@ZGf(VQ@%~~RvK8&Tzm#ht_N~UV{x$5u zJ+#krO@zAh#9mkjvqTtQU+jO))=Gqn*FK0eS--w8@dq;R@15+cV>$DFJ>FFpnfLd; zq#W{{stFKy!~i+?Q9L|i-!bIRl~WK8!N*LHUD-HuD5)MYAD29CiM>BQE*U1cpq-CP zr^~fO=Hpw)VmD+y?&(DIMCRk$Lu)@|KJLwZ&<>f8pXqgik@@)9d`cf=K7MZd(hE6~ zjkmsyhalVBi-vZeQjuS8iiW+GBZNIV8k#;Hjm*dSmb1np^YP!V?Nnqw&KLGgN9NJ7;9Jc!KaQ_IuY$b3Hiq$ilqr|W#Sp}jYof34Yf)Oa1m zdZ9||*3Prxa=KVpb`N%vTIGuL_`6!$Bzx+6c{E)>1Oe;Ihb+fe$Z~vzEXP;KgIPQlUHAog#}0qEw4oT; zr@cRPtN9JN@Q5F@QGZ9~ap2meKau755XY$NA`V2B<3nUsvrh12xi<2hr9RMebUEZ> zEqoxajt+8r7MDh*2)-=hShUM=tY8+$7PZzxzAWNlWF9Ba{~+F1;qh?v^=fFp!{X!* z`>G(z@iwv?ZzJ~*@iy`(7M};4F+?`*qXL5_M#$;c++pNd!MokuA#Ij;4~MS{45R9x zj~81nT)QLYh*+^MKs#SAOrImhaL+p~kb2M*?M8MkFlws&ZcmOgSQ?6Vfwr)9%ElYh-!-h0NDqt<7zaw~O@`@^rRdtFq4y z`D>6B%&26Kd_K<-o-7u;zPu&4v~@uHez8tO9xv99$nrW7nXex`*clwWuhsu)24zk= zBTsQOgKZ;RkiD}^;r1uN25jBB*4-8D@;Vn;UgruH>s(~MUatAgT`*fm=U?jq!yc_DK>K`YA}S=J4Zxt{Rli|{%9vmEU6@Q zSTK=CYk%D&4X+Dk=gso7z43f+b`C9N=T_r6 zwDP&T$o%Zs1K<7smh-f)e(w6Wo~Lb?HTVyor#;G~9k4TGv8?2?WRY3i*ZZhySV#l%A*k=e}Q{JWpH6rS&Mz*q6sc;N>BYlgMn0;{T7#+9&Ywk^8XmkDq^z z%*I9dyUy0;_ZEL+Fi)jiS`MXcptKE?wt><%P}&Ac+dyd>C~X6!ZJ@Lbl(vDtz71SH znM4mp=H@MBzr9&{Hi@QWXCd2NPNL`nN4`N4>6%-2kOyr_px67AmAKFQI|;P4Q8C)fR!yXX*S$pk#D1TZxauMD zz5w=}mvWWS-!CzNeJ80Rvh&OYdUc@=viI_MdZ4!{@{hgowETG!WT(gR)Xvus`Ba?* zy69I8p_}OyIp_lU2$eHXN`3aA5k^2VsrIU^qAg3~&Im`DL@|y}Qor_0=J*GFE=5!wU z*N)!QMfV)CPV+u=PVs5v7E&KNVe(02i;F#|*QJ}t+dc%){06U(@0IC7Q$oHVS6I@S z>IeQt-XHHrJ1_l#e6G1ajcM==Idzvm-4|Jme2@LMDD*%X%AaMTu2I>^yhJ~X4Y;M&K0==}QS(C#y)6WyexjeK~7C;O(4F0yTy2mSm^A364r ziZ;qHM80v+jb67gL4JR=6!Cg3cuSfZ zQy2Lmdtad6X_3z6md^CrbaS*X&SKwVs4n!HV`AYlnO^ssT;egsXcO5e=AC#3;%+}^=Xh# z3$$lASVkVN`0KsemTRK zrZjX%&Wd2?C#1JQ_E=q+RxQ&3IrV%+dUb;ra%g>BIy&DIImKU(E?~c-;bnWbL1lWU zr{K@0%F~uQ-e{jNv;y5Srz3K9!-{ljJ;BSLm8Df@bwc~(WNr5QZow6!%Te8h?051k z%{5bW=#85q9o>`PCGTuMv`<<0Rhk>Bp31W%e)D2)y6f%bLXi=>S&g@1A0MJerkFSI{!xGdEg zBG_@m6-m!T@WG&y(()61(C6^DQ_|WAf^FuXk;YaMY^i--YM$B~eJ-U_$;&nbc}S-% zQc;aC*iUjsEYh1WDs=#3HLDkWSQ!LmoJynKb5;;LnE~C5O#|=MHKqoeCFhG(aW2aun?F zsDZS-e>`4$(9l})WAEGWJYVYAM1nek<1=bVk4+QMzSqn^dZ{D0{8}Sv^L63#`At13 zZ?)jPoj$6Eyb(S>kFQq$V88p|Y5wjNuAYz}czg{Lb?9cnOBOh(bJ=gRxsUl;ANBBb z!H19ZR)-H0Jhk)FJo9|PgUrjQGY$y0F|Mi(*d@5u9_u{s8-m|8?vm%pext$DJYzT` zZ{tP5E426J4L>E=aeY^JN7=`4OfS_`_IqjW|ETXWRjZnUGb8g=CL0pb?!IHUYVbM1 zeH=HccD)t+$!fJ~OL^fx>d0l)_XuG>?tfO*f0W>~!U9$8xq{EH{Hj`YLzIvE*pI5! zuLYBY7b-RTy)@5*%dxwv#8!egv@{?u%L$*}1}gHvMbw>vZ6J|;i#E{AJA&+a8-v&G zG3ZCU{e^w;kX|G_Q}BjKK}4%auv=a{`PozW-&+t%o=g{9m@tr7Qo-x4jv+;jMSELq zmqrG46C6-5oXlG-xY~jgGT^IVE63?%$0X5iJzuRP&{gz>ujMzBUVfrarSIHDwzKop z`7>G^*iJHCLXk&S+D1O-2~M`!LTVZd|0^x_5#N3N(5H3I9-=NUuC;Q?AyWbc_dR@& z1ilDHAD?-YEVB`P*?+j2_^%W^Pb-&9YADiqF!K~)@5-S67{?;=`I8u1TCRCYx;b=1 z`}~7%NyO`}$N^tpku&UjlRVF(l3x(Y&g|fPI{O)!_f+t^q+qk)^LM|Jvu*s*9+>fkTzD_oX1F%Aap;70&zhBC zQMee-8{Mi7W!{K+Vf-uuFf?zCKK*=ZLIqzE=i9)9ay5`2viElMZ1j;I1bKkv zH^Bq#+r#z4RnY!qZ#!rkTNU}LsvUGN5a~?6?Fq+=E1`X1nkS@<(M4{5y#x3r=pkF{ zcYvl-DkGaW@qx$Hb&zXp^oMm*Mf^5-MF2Dnc#W~#sKRbw+x#)|D&uaj^T$)GqrmREW}w*nD= zUh(e%SI!rrUA?P2v~;?I{9t!)c=z)x^0Aj8@LM+zxu{_%G^n!!+3Iu{WDnecY^w@` z#K_Iah5JKcmGL&@J$*vq_IDA7yRRMqr>?F=`>kFBU{2q4$d_vlfZGqUkXu+sz#;vm z$e!=RVX@CLK4Uylm(o zFq-Xy?6*4(K4>{2ub97u<8G;tGfpJYCg=0rxlfta3G`RJs`!i%nGrOr!6M`a5JYQBqU}l3 zfG+G@i*o4+r-BLq9QwpP$)H`u!pn?YRd%)N^MgAs=>T z@6}cl^X8ld>@3YxF(0-5af5hN6tU&S5!GQ&i?-V$j({n-$)H5H1tSo=^{Y02xx=qFN98o0(K7}R|&W=TWq2A1+$U)n^q5er7;P#;v z9iYJ064`Q&0bDk1jT~(An0#aXnfnC(T1Kv13P(QB(2RVUC+djbx2;_71A8UG*fk@t zephr#f*;-!kn58q=z3%-a+zgGaAB-Ha?5#1F#cLAt`3cLUo`!c^@~P?Sstw{;V)BHPEbjC~_WBwNNoxX;_p!0)(2-PRd5l7S%Eq@PRhJ^SV&mcIt80-jH4cY}%d3zp zuMLOWbygs6{TvQE?Uy0*@pk*b4aoACi7bz$$eS!fp<3-7$SeAX!ixLZ$hS|j_m&TC zMSjyR4E)JvWIncQ>E$8cXJh{RpJ$Q1&3i)JvKz?q{DOQ#-5t!T+(C|G=OdbqEJW^j zs|Wntb`yCdYwvc=A0x|i5VE0|n~;~T41ivKuaQIE2EcsVSIBcl2SU2t3*@E^yFtCH zPm$%h5?P)@u^*i*@`P`nDFwg?K>EH~Pq_?7Tzc@`6Kdw}HFwtD{|xJ&@&?1UYQK19VDg zi0moiALP7DJ1E|4g&efn9yYEJV~9%^2TTrILe z_SJ0)huN8gyw678XbM5gnj)__Wdq3@njp)u9P)7y;~^&**MT;B#Js@c$w{jS+G7qF zf@+NlS@)(9>^|U*oUz6jmKX|_<5jfFF(#kxBvJ`7N^eMVIhIDKkjqEDc zkI1GkQpn{G!hU7+2;w_maPfdNa=VM*reb}H{_+|V`L0-dBCm1@B<+63BHQEzk>Z`yF3ZJ#Hi*4;AZiX8AU|wuo#%f;T$?HM4YWUS&&ks|E$mkf)AJ@=lGD%d%^S+j zk>>ZEDfAQM=0XEOju+Ypvc7A$dR>C>ul=Z(+IG0$%j><=pQi|J*TPYq&(4MBY5o>k z4f1}W;UFKIQbTex6XoM1^dhvsTU1Z#vQES&w;vly7Iy`AepXY`sVMwogdT2p>20O^KP)1(y^09{R`{9r8e--62o1UoE8?i+)k_ z+e)dNzu>3~%cX7Eg4cFfDh)A>Kz~_FM7}IEM&u)1PfF=0`yhW6dM0wOTj!)DV|pWh zBWI))^<H6--GoeT-d@uNcbD>maXb-e| zUAQ6X*6fKKC$w4Q&rGv@)mDsMvX+bXsY2sL))U$<@{uQHsr&3s;##3IBezb~q3<7i zBR6eRj=tOOgIsH%Hf^I4{<4mZc3F!?<{I_pIUSKxS5~G0Wji3BF{(^=^cOs}u^zop z$rJ6Js_D{SX9RQ2TrXYB7qXU)KKG4H>4sje$g*yad^*ycdiHWgzS_l%2Kc%l51466 zM|~E|_XUzSIig+G_L1ib%^&&ZIV*Z|oE`F^?pCz&N5O96Ea{b8d$d=Y)R6XD=YTBl zK_K(JiAHb5Jnri1Oh?W%M?2pKsiRvDxpqre`n$DQf35dq-wEzvhW7Q#ovDF|@R#>l z&@S(lAoD$xAu)B4tLCd{(Og61J3Uo&hk+5Y+ZuNY#e%g?Fzu&o9kk1PI>_=~5Au?e z-qd%E4zj$jgdCsTiQ3fEMt0xgLt{FYL;h*%Lm$@{{uSB2RgJ*k7^h{hy{8Giw9rT1 zlR`eM)rGo+eLKKZ*Rsn4Lq|`3$n_mfm!)#X01oY#*>i&|zeGFArJX<3p~- z_6_yU9zgE>CWP+(m5V%+opadVSVFe>988BrS$kog|2k*iq0@V#C0OtB7nvn-wl4=_a^zK^`2 zTxH~uhV0wx-Sm-<7sXSZN=C@1bK>cJow~?;pZaRQvdDa|`N~2aWO)x7c`@79uJGy( zuHCvdO{DrQeVj?|f_8RTxw-adFf?{O8C;s`~c4WR+?%v8Bxq$7t7i`VN^(o&^ zuadvC6>l4Aw$C13*$M4^FD20=o5{$X*uH$k@D0cpnScD2a|gIT=jL0^xp5ZnO7Q;` zzh{u&ouH-m(lRM+1Ep=Cv<;NDfzmcm+6GG7KxrE&Z3CrkptKGAb#1_zeed*g<^%U4 z_HD{@<7Y??8JRg>$`7Fn5@$%2s+3pp?>IMNTHhtun){i37j zq*}JCbNM%9(>u&U_ELK&7S0}$odkPza*Oza^Y-e>!Ld_v# z@gq{vu>n0~VE{g97s$1xPSnjy2m0z!a&JL9>Tmg!99*@HB%kd{=VaxRum!6~+b_ZN zW9~xIsrh_jaXpG&trbL$EuBu*wM(EmUhh=f^wP=uS}8Qpu)y7KN<(|?Av^1Jq96BHrg>Wm$oP6HI-_kJ_73w+k~7(cUUjgfk(1t#rAzA2Z6VF* zN_APdu%H6X&2*soR#hQA>xp#Wg%hoC+!#Leq0(VHC+Zqw33-(lN~=fP(S>*IVCbG; zX~M(CbZuF8I5e+@R6W6*-rv>%k~+*%*K{?Yl@Its)fnyECJ{RH(fgiIvv;a0KJlrv zpiwBq#J^H){h2S_w;c#e2U?R;28*QBCvmVu$B(qz8ziZn21CN7SQ63sy}G^D5Qs1u zL+)2RnRmf86^sHVkTo_lRo|};fo59c$!BnLv_0BdsjH%-qZa+ak1n+ zJQywvI-sg@{kSwuKMMA3HzRMKW=NAp#RI7oKul8XCC>@TQ2%KPd4DTJy`)SkT$($c ztoNRzs`+3D=rqFGdF7UP7zE*A{EMWbnb}-guv-(n2Ggubj3}ZgIO73SIAp)%7>7Lor z`-4uf`nDk){C)I4t;f#|r9TQ5&gpDsv;rr}o#M89_&~SZd+OZ zUI#X=sS8(6KOnQ1Ny7rJ?qH;cVtXl(GnTHR0ggNz$cP z?O;OfT5x{d4yoP|H)wyaHY}fgLvnrD474qc;qaQDQd*`dG~}5s zaocVWPoFwctre|QlcW|<_o6NBu+LUKpSFY}CmYechuRWZrGml_rZhjLyVTLo16-5z zY0B;l>7CRL4o7O!pk8~V@ee$qZiRORDx4h5fNypZ6rv7G;I!3noUvPy5a_(t2jc> zjqBY5A2`F$A5IWd@t(@~rUTHYj*z&Z6EQf|98R6LgGrM`cft_835a zkKK|}B{y&@YY4^Xo=89YHiDC8b)c$)E*(2pAL72$gZcq=X`i+4NqUS0jG>Kb*F6Ww zk)GDDx0(YzRBtq~US{vPwKbN1ExICqg$ibO6IN|AnV2pY3-VGl7*=^Y`VBl`kC`V>ea~?dbJuO_4cel zJvaHm##t4l&)cfeO_p8YFln4u>4H8rWY4xK>5(d7es${GxeE->h$SIaD$#D=`~b4D zN&cf^DLUU5R_=d5Y&u_+w(jIBVQ3soMU96;->1KgW4kd&Ly44lR{g{}{`lYuUc{?mFa z9TQ5&gwipgbWGsN316S_b(+o4@9HOyQ)rd3X~a4!RhoSvk>)ywkq_l^q>WZF^h3E8 zq+riescM~2T0QHf%5AeQwRj&yXInH>B_63ux3b@U)+*OV-MUT_>b$=d9W|$>^s1c$ z{V>9YI$DjA*!7hA@$|U;b>%Ab%#arn_wT;)yEMQe97= z{J!gNZ0=h zD}eXa9`wSr9;#|qugG`n{`BOuJ1W~A z1;nmv6x}eeK3QIV1!>5B`{~)xo6KDvM!IfKqUFdyQtx(oGGs>zJy~@$88a$f<#lfe zz13hmo?EARu0|7nsNXZKYkF)NF&Q{i+IBpV+I$TqV*_#|Ka&{Rd5;qbU;9)tHD%ui zEqbYP_1C2ijk?oQKN_nHrq`k4ANtT%&8w>8^{i;a^R21w^1EtvXmdJQuLT`;)kB&Q z=}3oNZbY}YnkKDaZSqoVT{^^Rk5uU9NN4I-r}uu{m9&hS(@n+N)RKKu#C4-3`+ogf z>B25!>RYA`T@!Iry7S0}-tp3-{huF|($^B|G4+E~chN2>c5G*AyZ)3^ShQ9eVAhA$ z+r3iiX|Paobd0239`%!MGc8YVQam*?{;n?cNS7)+Nv3Z$=jOFpHbJ^!pGrS_u29Wd zJW(1EG=%yZI}uN(snWKdNwo8hsl+}YL-OttLt_W;BW;c@mkJ{LQ_HURNdeg+?Jf$W z4!PQJw4YiEsMvwNR96KL=aW*|7jF382#>RPyv6$n>u0dDWf$OmXJf63u>Pzc@ID#; zVNHrYVg1KU+)b6Uas{uZ!3LPeY#w}uP01^`cH zkc_VFU{Xj~FdMOtOsnYy)sNgH`(196Y=0m4GH5fo+~hl1_t6)OlH*C^vlYSajUQak zDMPk?s0Ic0UEpK8ajN@u^&wzx7d+Qdlb^8NZ`B69tAlpCE-<6rAj$3*Yd>H7VCsgg zQj2e2$%z}j;I`*jr_;9LWk(cOTaS*$}XJj}tpy$#rt_vIIJ(2u|G@@fn z>OhM@2c;MB&U8zrA*|gtU%GVAgWg$J3%*qGm!fUGsYhc281HsZy_}78mt1PXu9WyZ z$4y=6Dz?sDaBiLILb^Y_tXmV(EFFn)<4&~p`I@ljdpe2DYDY~P)PjixyU4<(ZnVjd z+Hk90A+aj9p;i2ip{b=7%<55(cC1ksk{?t9-6eX|!@&&h8`c9;oww48EDMO5V+{?} zN2SO8tl+DuEj(zjSQ_cq1YWIhgqw~*(%j(Y@J71@94+@=?J?W|?k70Gy%|%~+Y6kq zjx^&ZZ>O61g7-gGSKGz%H3760NMwZV3$JqYQd`F>R(jzO) zd*VctlD`{) zEPpownU!lp&Hd!()%f%8Mj*3v_;(|a<k8MCpYt4eMsvYbQns~$^4_T{CkIw3i>`~r|n%{1Nyt=3@wZ7UA zd2R1L)WEka^7#vKG&XV{&M8mnaM~=OGjiC)Guf?7kMqHFet5o-c6SX$ zo*cDWa($nK{8eQt<-Zhbjh(ZbxDWo3hW6O@j-*IW*t?F}OcpsOqTOSCF&TcGonOWN z%*UC*j8169zw1+pZNWUKKft;z=gbwNp$X(lbQoa4=$d7bFs5i8Z;h7Q)(MwnQV_6Oa~8Mfn2B;M!hDzMD91Z6P;1L4sd@Z|2yQ( zwsyW$*?15>yOMJjc86kJU9|6+v=~p;ZRjC&auVaoUz>jE83eqo@jv_Q!Su<)W!Mg%j0mN-Horzb zJi?nc$gB(82O@1~5K$q|vaCd3HSU2NJ?*gcb73rU;Elf0$QQ$q2c2|L|5A&w#iyG# z$-h4e?SJRJ#uccj(|IvQDLETz?^PuFy1@dfZx!-2V6|nm)Qb z^5tV`^i}1iD(=(Ya5(kN>xJdB@=+|Uq<;wc%Yq)%guUm;eg4|?OJfyY#{7@XFH|$v zusMio<{&mVQO(@M<}9k2v)EiFY34FE$4Qzwj?I0NX6|EiVxDGBWOF6a%#~~oC7L;u z&8m(4Z z+amp;GvdjxM}phG9Yn}4!At#Ph?$jGI|t-Nl7ilXgFV8?zU6}RU-l&fp9`LRzB?%f zk z2qM_m?76CMSHZh4JXR$J3!aw!NHr}~aJAEqRTE`~jW9?SWR?x#<_$@%Yb#F#vhpDTZQed2veJg@G;#^l=& z!G#CyNsW4fYd>vCo=KwI@}GMU>tMk;>pPO2KSVj3fA=T5mkB<2v^$y6T5!?BzT}2n zUuRo|kxDB>-A&pTNq)=q+pu#CX)o9N+1GLMH)*P67&@geY_pqR>fH3Y|n!=p-fgV){vmo#`qi z{!DKvNr&k$CFwJLrsTd%w<*aF({oDl$#kBQ{4bvr0SDI?p^mYxpdS=f_=J37R4?$3 z(!u(Fxg`KxzEwk3`YY{9e`Pu@0o`E!#432LQ)D-Yj}&}vbvL+DRq$S|AjlqF8GS~K z4T6IGddTDJcZUaubdlQ@b%!a-gw7njy9We%3%vza_5{<5<tF zX`{V(eIHnVsthvS*%uy_(L#QMtP*LR5c5Z)YVkq)IJG&oP^%Kw4E-wUZFNx=^tPX~S{X{tw<@AMb z#lJB>uQv68RmViRZCKSCywXK^<}d99ja@`JH(1>hYMc}0e=ny8{PGm_((_JtxUxjl zS4WHPusvVYqxQHU_`FZlZ}l=kU@g~sxi#HjqTC*QSv%<{w-ct_fkMYCVWzWzLdOGz zjt2@I4-`5cD0Dnf=y;&e@j#*Dm88$~y%Iaq{Yw0q9$1nN(+Nw`XZm5ueVMLUk{_lw zmgMu8pF8Y|5t{iQ;qBd%VY#$O;%(`VuyX%J$;rnCgHfQ+d#`j%gxA$KV_iGVi-TV4 z_9H8OY8>xD7CVTTA@ZY|&;x@g&%|R zpt`mb^Iv_y2>2fFf!yYG8YC}~aId6m@F-Z7q>p(}-dDN*SZkRHxnEwyQMJ6>$nXOq z=27~j)))q69)8H)YwnW|Gs2Nm=4X&RuM}iu9{vo=^^5ucBP_Qc z;Q9O`Jfv+JB)Tufa?pE`2E!Vi!}6Eeou?!FV7V#%m3F1SGM$t6QmN(TG%U|iA4k*A zH}~Pa;=8BOp{Fu1%?cHV(I%Y+;WMtai={h99z`Bu-IMOjsDRJXC$=>`f4vcMmvt7j z(~kDYUQ4v-s9t@MSB316Cbo!29zMZW8h>&)^5}&P)O${)Aiwr zzb-Vf@meJi-59LMaZEO0zhg}9iPj4V=Fjg)*QLQax zr-{3j?+^3$@A&(^{95)`^1iY1J!E!Y{@ykEu>A06LRP-dtbAXQ-G|<3_FD74ALaMs ziOc@TaymS%KlNUB`Muvtv=QZdfXep+*)2-SU->?v@?ACM{35^qjQQm6Q)}|CtS@Ey z%KM%krL}=SKYuQM9WNKoaycWj|K#P2ESEE~T+YbK@==zXT+Wy`exG)g@|5q-6Mipc zy~ybRw=3&WS-zs6 zJj>-QSTR<3hj`QH$Lms_e`T4te~G2ffvK-qW%P|k;Uyg;4qu`5AU1Z({k2+bfKBlE5+m+Y;VSi=){ux%5;s2cf3Z0=eP2NT{V^%5uXYD~t zYm-?&Qs&e!?8|?UC58Wg%ZK8t!-+ltn123j9jF%G3wiGDk0hX|A9CdS+ob!E2xO(d z(ysJZro-!){ceKAH-G)_3)t@_cpOFfz5b5*o&9ct#W#Qb@5tEiCiw5;u>Ak(`JLZ~ z{mv2VOIdeHyD}b7#tF*#Q5jb#;|*3^C2@!{K2bi`$rAyVis$8V8a}%+{$c5q#6`+@ zNf}4UF$rF)jJxDG4d*6yA8M6VLm8*xJSF=hD`OiueQaa$eUat-Aj|ngR<^_K)q;3E zYV7>?fEs_o@5j>Mf4qE<<#I!o%M)2HXJonjF`sh1AS>T5RdW11c3yQw8{juOzqbw5 zcCbRW-RenOIGH0WeHeqr-*kW}7@BrOpXSRyk%ue9_|S3ndh+9ec$c`=&&FhXlBh3b zJu3qPqqnw_cJaO?s4yY@oA69c?5u1jZ^2GasVyVb>DPwJc50q{;3DntPcn=|e1k zim_VB4_~;$+S5SFUU1n6CRt*UUKNf6iZw3%ouxeWsL4%jEBA1E@n% zrf*}rWt!xF%S`8_Oy4Fve}9Boj3H@a4;EucnwW&e7*rFhu$Y8uVi={r(ysJZro+~x zpwYgVCI%W!jA>;=qm?lYjc7D9rmYc;w#GC!wMKJeTAZZO;+RG!X*4>f-ANklj%j*S zqvs~jY0jY0oSDu58ZG+YId6Q7 zHXW0VapS<=BO%km2J5={F$$c4%JV7^vjJqk`@fe%pr+TniXu>{o->HW?k47JVtvS-u2|^R@G2)&y z@v7M4IC``eoxNP_ePm5_rte3HJ&~F9y3#d7?3FCYiKI)j#U4s@&Jg-6dot$pQ1)mV zWPc7dgi+CHbVi%0s4e*19ZIJ^h$lS%7hA_r?Pn*D1KtGDdDX@K;I%Y&n&cwJkZ(Kd zQqKf$;Qlx7zLjhq_eYk-td<;Ji{CfhuVx~(tvm|t=Xy_dU;kOm-Ip7wNc}}4(EjVf z4l=2FiFR5Nb1KW9Gt+oAG5lYu@qYQd#!53k%P}G5^RJ3&GfcYuEivuJhg1Hxm{wU| z$~A>@ts%$8ShjL(jO|U1jgggO1=A`)qg5*7YNk(uM%z@*5r5`d<=C!drVUcIS1a*0 z&on^F_G*!tHb~iCEwa*w>6sGStHozz8l%MaYLS`tNZDR3GSeg}+p9%pS|w$BwaD_? z0-0%>lVuNGP9 z!*oT;_G&R5rZ-ZySBql>(;+F_tHrT`>64W0)nXo)Zb{i*Ei%(HDch^XG?~sx*i?|2 zvVQ*zE6ebI&ZY4%?^~Mjx0L_R_D~Y%W8ar!{{NEYbp+-0^hcPzt3cU%4mgIe_Y)|4 z&jH6Sne%u$vJZ|qN`IwY>90(Ow;Q(a%+B8W>ov@c4=b^GyF?@U%l9b7{Qa-fFqLJ+ zne72HEw7~9a6DJe%gXs$IgcyncXoM6{Pv$|hOB*LeVZwlI!UuGiFo7jtA^^ECq=yd=GJFb zQwy;MoR~C|On4~f+=ZiVk#w&}tcxA7H9$YRD{^R%J?vlQitM$a6TnGhWY`)C4sTy! z+vs>H3H&V9AO~cRgj;PIBFl3h94da{gvs+d&hX~A7NQL)#QO|t;n)=s>uV_W|5WtvIhGP{;~#(_QE>syQ^74fVY(+ zudk9@J)@A%&#DFuKZ*V5{ts=TcNsUdYcKNwwT%h#${+n9WBOYhPrk$_!J33j{#Ex_|ZGdM@!^Fz-SvAI}TNEgk6>MfFz-{6>tSDz;ILmv zaM(vAIP5PHJgR=qRL&&qM~chyJ|)3n|B~RauSu|OSNk(zf0UF7`=$izGGQ-}Tn~GM z1c$vtg2SF7!C|jajCl`IT!!~12@ZRf1c$v$g2Nss!iYVYQ;>s~0_1SeottaIiSQlH6Sv#SR%7)6q9s=>1XOo{rgdEKeOu#rQh*55BtS1Dz`fzP;p;LhK`$ zb#b}zi^lU4>X;}aVgZU(dEL-(TiWN;z9{`E<)hMbrF>WI)6#SC^GQ9_PhQWG_$7>s zV3r@rQP%ZhS#rA=yL6G;-;Lw`nX!Z4$efMm3^4d`a5+Hxb^RVQ)~9>mun$eHhdpM3 zsTk{L!C_CD;J;TM<9Kk#5%PpQ!2xjKU~zyYxx226jtlns2IV1GBUtpWT$>{~rq)_47cXHsncFPWSEnQ-_kZ1c-d>8U^ay{hh z1Rv@>C)$?9IETRO@6SK`M8ubE-PmdZ_nD#ouiY`ANxP>fENzdFotf z7(3(V!|vRv&Z+8L>s~fGL)Z6r&$ZpTbGjDujOQY-3>@U(`3pJxcXHsnVAog*K{twC zITGy}#xYIC?#LKN=qsLcu;X3|ki)^2!=Bs{3+KDX|Ame7vVa^Q zhl9m|J?9ndTDs`EBSSZ0>_`GKUPqo?lRZv+{;k-zaQ>~}aJH>re!k%Aq=mC^`WwpnJIfi}mOjJqK(LOZD4&y|=d|y&hX?zm$zcz<2=P5aPF=9x8y3bz z){l6+NRFxf(%$D!OVc)`_mKW(%n6ssUaSgF-DJw1wnWaK)MYNM(aj7$c9oQQ>cnQI zM@#>0dd=azu#3MTzV^Z5?yBF<6`L4s{Kam+ql4hNpHHyIeD1$hl)qj@TcNi<`>1i_ zXK7u<`{r~#imy}oC@xR+L~%V-zlrOoKBU^Ee!94y)PEQEpPtLD`^JBdTVwJ=>~V$t zx3>HB%Ho!Pahb^0jylPeeEM|3AC_8uRWC{(Bbh&^PGYEb`y8xcaek%!iFj%Cq#DQ^E8fWdwhg z|5)?+_5AGr*7yj|h1ee)00+PUZ~z%GMK`;U6>vEGxc_bTf>%zB@*-V3ewNb9}R8tXl^ zdat$KgRRS8kA1qV4~MgQ;b{yvs?Av?A?2+)6(=_YrO|s@6FbGw)I|aU8mj? zuJ?-TJ>+_CIo+Gu->$LVm#+7#>wWBcf4koIuJ^<1ee!z$yl#u$xwDOH_m^>`ckYty zKk$3q>7Bditk(v~b$aJ6%ADys!Sv2uRCjA9!Sv3Zd8gF*g6W+*^Lw=_g6W+;^LzH} zf^}Q^x-PHl(e>+gb$@g}b^j|raf&I~wWhSY7k2UW<3B6p# zW9)~S`UrlYa2ea?&4GgF&%1=*eTc6|@pUR6#pS7|XC z*X#E_m<7(HdbgU*mSS#T0{xKa|SeWWyTg2yly}zw|vqM@-Bw1Utibd zbv?R%-LCGB?x(g{^q!Y1(l4v@;i)w}UABC0Ngp~E?C+Y)Y$bTfJA>WE<0{EJIA^~% z$lZQZ7R$0dw$gR(jOC9BKB``4_sp{I1=Bla?y(L<9GB5;>Fc_@u1D9e+tvNi{nY)Z z_sGopobO4W4+PUYq3)Ee{(T~i>Ag-jYr;yYf84tr+{$Br5j<~DE7$1qV?>7gQ>JCT zu5Qt9tL5I)Ds*)Z*ZoHDfy&Hs>b6Z`|L}JyP^X!L?uN;L3FM{mk)Zd-uqvzsvQlZ?D9LGlbx)G0okRx&8Gob~Sg~2m5*&4Qb(?c+=N^T**sag|~gXqrbS+ z6?@9}XU5Ad-O){aKc60TnVY%9_y3PaTDf)!|6Eg^Z0)`s?w@zX_%`nL1zrvdr?z#s z9-SurEIgx~yRDa(+pW{vyUDA(JoCTM!L9G<<(&1tj_$kCUj9oubaF%U`Efal#;Z_c zKVD1T?CjoM;m2|58C~4kg?@ZX)3~>;?8p5X;zPUNJRiyvPu2#WXpU*DxvDv-xvI

$*Jn34R_3Kk0lATdn+!j`hFBbdE=|FLDEq$AopZA_0 z>e*3tfZzu+z*8oM*4v?w|3GT}^GDCq2$O|5AJL=^nTLwymA;oqzB0?5ML{ zGs@#nXLPq4T6=uu1wHKPVy_PkL459fEb#Y4MOe{XBudS7PK7nj;5#`p8o0vFkqPk4O$ zob&8i+dM9q?MyqRjep)pjy=_0pY-^HRWVjoCVPbOT{B=)vP&5ED~o@Z z>=5`cVBy;2^?@gvlbU;)lbVORyuPl>>w3UX@bf_U8RuB|`yrp5bE9cctXjl*g%iK+ zX&x?Ep8YiUX!BO4#?HbK=ON~mJi}}~Icr4k;yahKwCVHcHwivRuT9bI(UOHz6MSZH zo$FqRDm3Vmpt|Y&=4#QGnSZO#@m1dA?oRKJ-k?mlZt42WP~KAcWT?kdJ;_kNqxzGf zT}SQO&>u(rv7w)i`bqal|G7QO-@4{D_!^(HOV1_O`TSjaE-6p-7=aTyQ zi~)KsX_wC!py!hQ@EHU2T+&aL8Mnjz=X_Q7;*BO;G9nkZ$=Bt1LwS)ys3&6ig!)Bp zpCw1)RPXwsQTpwDOtCqY zqT6@QiQ0X8xw-4?^yu3BY3A4STA7`{6pmj0u87I}%Q@zltU045+3J|Fr`I&4uHBXx zm*;%*{LsQCeZ;cFBNN-2i_G?D!1}3)&jIm zAoKC(M@I#A&8WX~*I;w(Q`t|w@2)v@t1TU5iY?A$3*S9`=Eco!Fe{7QVz0XUlw_^@ zdz!>6v+V2ZZ%=-mY-l;9d$;!T`+QJwDp!guJWu(w%*)hqKkg& z=jJr3Zu3^2S+6zmVKMPx?T*a$%|H6N^DeAz2b3LZ$KBt@4Vz!dPJeoi9klIom*tXl z+idnO+pT*mH!J&z_VZ~)+?Jx}x+>{8?eWWMyZqPGbl1JME!kyVBX`G)!tV8D%aYUY zYU{3fZo3^*>*eGPSM+o_d(XCC_qrq5tlkao^lxslXFppvIfY``oZU0qHFMvX`TMTH zF8#qFZ;WnNXT~d^4RR-4ktrJU%j@;?wZ6gS*l=@{e)cJe3QzQOZ{IpAI_(2ggTQuvjsfp)np6|A|ENpITx-2oXLLK*F$(knX+1nD0k1gstetC|0>-XcLij~sb zv58h@<%Yshk79Fep06)Ah0aKiE*&=1W**kZjGA33S~2t(+m3irhj>EV;~&l|GPmfg zk?oe}JkPI}@7-*3G;hlB2>pEp&A-$6oNM}K`&>KtlL~y!wR>~;So`zMxx#sxLoAhx zcwX}yId{S%{QV)Ci&K-VLs$>ccaX+59e!PUxSrs-9Lh&jp6+i;KFyGb+Y9waR6n&N z?MBot`#jtqs_%4aNBS92KV{CdF57rl)E`uV?wwt&l}2%96~)JpHRQZEwn504E+%~ zhklCuL;q!5c)t7R=YCB;DaQIb>w%9J?y&cN)Y`BfSbgqq_Sy0+4C{ePLpIp?3mY5O z16iM2Vc+@17}f(*v%hawF0E!*4?LDO&Au?Js9`;@)&nl@5IgeY6%p%! z8QB`xV((0hSPv8&nc4n2rfbA{;O^DKlH1myZ#t>D@u z>wz~)WR9*_*2S_OIQ@mQqKel~w5$hetr#4=`p^o?dSK$bC!#yP%i>rMJov+_QJ$$q z9qWPTcFd1PzF*C;9+)_KMfBW8<5&-j?YAK+^L}H;dSF6>-=aUtv~a8kdVaVg8nU3Z zV?D5I*RE(O@r(7q<|R9#^u?_m>w)2y{1&aM-omjSc<8|m(c@n=cB}_ByiN7zKHae% zIIY(E(I0+en`J$)`I_4jqgH&IWIgchh)kzeDc$J})&o^~4oxm;vnIiMp!CM0?Yl#| zM63sL4m`{DIDcZqdf?S5gKed&S46A_9)9f!d-Ug74C{e1t6sJDQhty1!0SKHw@c?# zGpq;JKEA?s`_35F19SUru;%^7hV{T34S%z5mu+EK58OgLxqx^=JWBK2twFX5{s8+M zJWr1df1o$~0r&&(2ma^%fv3yEAAmn_F#LfJW_2)Qx^Ic*p7nfk($(jizS#?#x4!x` zc~6@fX6XlY%v1H!?A>LKH?uCdz&w9TUR(30ucHAwI+~$fO4vJ_J|0!=+}q^4r-J>d zOwnjUg?{GtnboX{RmsOq`5X4!UDfS|rZ<}B%T%)so4;f~&vBJmP`$kE`8}O6H@1}- zT<1i4+jnJLoe5`{c@Jf^C3~OcvM()dcD%eM`PlJo-S4OEj1o;>Nw&`2+l@}297VZr zNETf*z~#TUPLwBC8s+Z>yDZbcKdtx~}5)1ea&9oc}QYKu>oeyu?=kDv$7`|Y#wYDyfbBHnYR5-J3rSTGjK?u zsAP#xXI30>tvTf~3k7 zBvq~;sd5ELl`F6+S724Hz^Ytgr`RKGrzA| zoosyB*>=Y*J=9PFxG zF?wc!>e-UB<_&TSF1ju8^SEylXZE_zt*cTfx?}#W(X6AoxMx1NJgW8Nyy%@Bjom3N zAB(>FAhUVlxazL%@)^;>pG%r&Gv{)z?OYNKy}qu=H|Hb!=^yK(oMRf9>woQUo7MO| z+Pt}iS=wlH^5@fbMY*%LHE(^FOgyn>XLPP>V_rUKSoB`?-=ewsTA129mPSKcd>egR z=R9+Mlf355xgSSsZ$H_L`nIOYUF7v>=L5yfrbLV?q&Bd>FjOyJm zCmKESdNb>xJkivv`bU+{xyf9YepMn*`vr+5PYpKBKVC8O@)J)dKjFPNm$-+_RW8w~ zT%uFCM5l6zPURAv$|X9LOLQuiXjLxJs$8N~xx}Q(CC*T}#DvNvMk<#Wsa#^Da*0Oe z5{=3w8kI{lDwk+fF43r5qEWd-qjHHx1)sQ@ZU;mpdIM{iy^?v>Dzk3gYat-*_GYQ?Vn>LX3ogh!a zLC%7M{39NtFfM}qdM&>7?ALDnzFfa{n=W$mYqwsuBsyMemg|1)wzpuvb~{k;Kl82U zw6q*!+MBdGf5`kg=lKri=03j&uJ}wxbN-iG1dkoo$*j8V2f+(2>TI^&==a#KI=YLw zVD7haJ;!5ROobcQ3O+w~S2OPEZv^a9lsV_;kB-&;I6L(fAUgS z^JP(gz1i(uP0^&s%}rO6{LeOVWC-=H;8{)daZm|?@$32r~Nvl)=(JHfC1+{qOC za)aO^#XFh%b8QxUU$u@V`<*`to>#epSy2Bs!FQk7-gGapP4Ig=+M4RS{C6upTHeOA z?Q@i4&PQ*wHn+7oTJWsVt&FL8jNo!3E;Fxe%p$nj@RsK3JF*I%`}Cz|(e`YDS1o8^ z>NUtA`1Qgq%*d9<2_AY!b5pcVPQg8jHa9tzd3@EI> zWjX3HbIQVFrL7@3TA4Ye{j{KfY1qazx+at0udirp-X5GL`1d>8nUVQ- zh}^&*@aI7I(`QMZsMb}349~SIdS;7Gn(Xmxn<;v7oyR+8{gGIH!c9_U;DSww>Ish@ z|6pBWRV$CTum38Mv$w~?8>~#M8R&77uf9mUd9%lzrmskRc$3FV=B!GTxX$Bs+t(!e zbo6*}n~jOf8hX5O@vn(Sr9IwM@TjQNFTOvE9zQl(Xg#jjy};fPka3GE!Rd*zwU9LU$2hJf9dh));*(3PVn{H z>D{C4tvx=YY^P}1iykkW**dx;o9}0yCz?g;dU*W(^2Sl=#U4+7yg}sZ`{!Nr>uJ&T z<2`<}P_5|moL)XFD_4wO4BtPR(7seua6!1fqEIxZl$SI31O6Nce+EaLT>Fum#FkxO zxTAaXbMGg-v9!JWp^yJ2RKCIO+&8Csd-q3?wr>0}-ZwaQd29D{S??P>?pnD9+r8bq z;HAslf*IbPelw}1TXm`T4bDkk>P}tg?eDGYTDb8=y^Wq$t%W=46mPrRJl@*7i#%?0dUIFk8Gmo$yXJ1~ z)4u-Xhb<@%>f60??WNA%>-#hH*vs5~Z+m}WdU`82^AGRm47jMZE0e=N*Oj-maZhLV z{y>YFZQXre?-IH7-_Xu|G2Pq25qUbe{Lgy-YH*p3Zu~Sa&$CK(axZ1_{#gDjon5~t zy`R?l!_IE_L+hoU(S5tP5ozA9TfeP~JL3oMLr!el)!o+B`+*yt=<3E@;r+uQuXT0P zc6cB1rx&P9y1#zUOw4RV7kXW~yjvgp@)%l+WAE;by9Z0^xM(@M|>~+-BCHgbf2U91yg-oZ-UG4zqzvuaCQ*h|N;1BNaJD%&~f80K|$C&%Y?fJh=i+p=^+^4P*%Y6zZQ{uVp^yORWeG-A5F_01xJuUxp^K2qCr?D~e;UD@&Lg?mrVE8?oP zpDuXf&nLM&Ki@3)@hfV$p&#cKoM%IAH)T<>KFfJ$r&{i(TyF{ITYXm9-JJhY%hx{~ zRLT{&|5?Gk$K-Vlvwr#~e560u#kq@?<7ef6FBiVGY>f5u_HDb3;C-z~x9^2V$eQUa{ zkN+rs=?BXzI#cCp%YQ%ps^YFn*~x-08=BK~pY@gCwI^?}xp!m{-{6%8XW0tp6&9Rh z@Ll%A)5{CKDXo-UHn6(jr#~%~yk}-@!QWi_Orq~9@`I`Ve51~d7XDC0@Ld&0MNi}_ zBe>~9i=tkSA20a5Y-y&~hF#LG#z%Vp^|NTq&lO$RwLJgcAFS_fGVyrRwZ|eqMn%h* z4|Y8%_>-Tjn48W!SMUp8*D|v{86#tT&zrT);-5;3PkTwf>ZU?eD&jUjI<>rc^3l5l ze|BbJGjGBy!To;CVxB#Fi{R|9eifZ_XHLWAKR9u6RJ?a_!50_5Iy!NM&wF&f`^QAv zzCItK zbCK0^Czf<4YZ z2a^mO^-21#vF>NN@=x03O}%`^Is`e**r1bfRtIka>f5_XZf%zUxTvov2HCfM!>Ncw?&sDbP6H%{0 z-cGfCe_{0fSAVusUv4?xlp4KIgqM%jI%?7mTU-zd9pl-)PV?i*$I4dsr~X$)EBdtj3J5z&8T6V3i${apKl zwS1JFGRjUFWv7g?Q%2b-qwJJXcFHK*w1@mNx-Fi!}!mUl>RG!$!M&6Fr$1h-ZvQgU`F|1M)_cS za7OdzKX3+bDnAD1X~1e_Q$x^HYy?Mz^bS^=5xC z&mYy#6ed42UPIw^)OdZC*H`29S$f9Q`Yf-<@;a&G`qcWYQR}ltts8ns?&)Ow{+>y<{WR~ofmY1De9QR|gPtydbgUTM^NrBUmZdyJ7DuOt1r zcufCl-l;V^qt*e9S_d?09nh$Cz&*xYbKpSg)cynMfq4Ik?6ctc%+I0rpUA$9uwR1p zfb84gGAe)0dO-Gh@b$3Igkuw~D`nHeb&g-+@*LO1^#~623s(D2;{G@;&-+2RJ;tH` zf=6y$5br<9aQ((@pVqb@uZ_lfPo6jELyk>iJt;WoPr+*c2|pL_hoRr{T&#x$2mLH~ z?(B!eC*m>~J6X3nAlt-p#MoipVcyj-(3!Az`{U0;XWk$_N$`0D!&mvwzKY648<} zy^YFy8Fe^*1wEe|1xU*%c%7)qt?HS zTK_U?{mZEJFQeAKj9ULPYW>To^)I8jr}5$3XWh5`!Rw#7+dg%EU&*7Cs`8nwwxqk@ zONQlf*)O<6aHkimyMAZZ6Fl~m#_r|zCkkHOqmvu`t^XF~Bh#*R?=F5O;(W}969&5b zwxtW^Gf4cmLDSL>Wn1)}3jQ9c^ppBxsZWBbkCyr>nEGz%83fZaIeIq1^sJ7aSun}K zkt_t0Y#hl*o{MDW=y?Pm%C@>s=wt1;8y(B}u^GdY-*g%*c=3*p66IgKNpSA??TF2g{==b-D{)^z8AbYMF}!&&yZG6#cEXU|a7Zv-H;E1@~{*-JEvYa?AC%8QIso zFzQah#irh5TD)6@0>d?Oe`X+XXi*d5){Jx}?bS@~bMk4q1%g+v;U=XB2BG_<{NF+59*4 z5Uk~PB=%GHd0$xbWO}b2=Kg&1M79mGwlpJJWiu?>3pYgO@w+Mto<6svSzGrU!8_jA z9`$&(o#46A)F@fWpUtzn+?mnot^NCL$M;=R|Gc$>rOXv~XR}3K^6!k^k@sQy#_a3l zda-V+?a;Pe1($16z&*D9LczMvM@m00IPE_E?y>ZLe=t2`YQ7g;+|+E#pWm^}E5F#y z%sY0a@OD$CzGmrD!vzoOdXu?zMZZ!g@;HHp^Y+nAd^ zA0GACdcBl6t-;D@^yqGapQ@SP6tGPN>;509eePTK8UDTk{S0ycAJ)E##@#;o!cO?L zo8el=)boYE`@`P=;y%zBX8c_) z!Sug;=C0raJx?z7Qz#$L3fUE$q`puCJf}NHlJckF~3g z${Lk_&Bx&HJfAgr%W@x^Kfm*Q+kK@!Gqnhd&#|b4awxHB-#jG)vTf`viG%ii&UG`2Z zA+q{tLLX!EjS}4b<}POWCu;>CweUhSd$7-s70G|Hsr7R$k+~jsjSr+w?pvv^pBLYI ze=z9{dL|ziXnZJQgujw!Mz`B@W6AOH^X?DU9M*W(7qwiLN+%1?AE0-j>VJ8m;0-UY zwe{}mB6$5DPuh5!a)cz{H?@F(Egl}R>3=*DKaFByws)ywxILJ+K zkf-4Acfmpa(&sQPf_dG6K!V_v6grhh|NU~ z(3#Mg(3#Mgqz5<$!~Zz%>Nv(=jC`iI7sy4Y$G(K)xQn?#KZwmq2v|pep9!6b^}Aq0 zMK^}ELg>teH6r#Q*jT{Ngr5mNvqr>o0ec=MiyWXc{XP?lw<7i-m>J|xLT8d3f=tAQ z(*Gi#NkV|12|p7$6FL+7GqFFD^Z?sNv5z4?DLxg&TYOd^{7j$6hM$Rj(K1J%GY_WD z91>)jvn=Zy(nAurupVN}zI)J5{J$n%GvK`l{Esh&Yl68f-^16rj#z(j-G1EoFGEsi zpz?JpZ{zax+cD;PsD8m*Kj-22I=4xG6HNbW*pKGx+$Pl}*ta<(E<=CajddA)udY+K zrTah?NuA*tQ+=lP1pmb|iX6f-3J!8L+~@F&g2OWk4$ml9d-$2S4ZawjRWQpyjUDf?i2Lt+&X4aH!q?;HO|35mSvoGk^(eV< zyK<=?s3jddA)udY+KrTf6`aiifGrT<)qewKG{TSI4F z@sB)X>e;nS=#Pd=gl81YZPGu%;TZ)}F@8qDR7dKa9N*>;xz6VisVnMo&=qRz_SP-&*l~HmL9QZO8oNDomm0fNZi3pwydxp-9K^iyc8BJ+@F(yk#U;%# z;$(_@uy@`E;JFmfUoAt-J8!RH@8D-DUxnw2i{}gb4UE}-!QT12xsnh3OeP2XOqnk% z2<5A!*5TMbs~BOASQ7Kj%M9^dO1H$m${sPY@>Mv7l`@!jLon}1_iAn^|CVKw;*yFH zkXH$MTFXSsO3P5o7W0mzBtMvUBnHeo5(4`*Dn>v)lVlQdePWwfXJ{Xf^od+&9mBGd z>Ev^Lf>|eNA2N>3eL2iKk^|-)2?6siwFb0DPM-O}a|QD*6(e9Bf%t%Rga(G^1=}6v z-|{uN&hth2!<_5GI)dLDfb~19o68*W`R^fuv2MQGchx?v_H{|OIMz8qw_qKC_6O-$ zNy!K62uu{>i`svJ{VF67w!=g4w`FnfB z&a9UMmoV>wAaw2p^A7tnz0c>@D6u~ic@?EIkyjy|iM$H(Dm*7tT!VdLyL~Y6)q@Wv zn0Tk`?kQi0{IjNX0BF7mfWYG)Fit(K4Y+DOn-D!~1u{58(srQk_Fn{^}mF zzvhhQlI9rlDwuc5SHXT2@2k*ypkD*Rd#|Zn^d3H~S_5LAm;YhE%IBjGg(iNeQ|7$=!fl&VAd=2PjIkBf?@Ac z?~-tiJ&qArHnDto4^=F;Jz_2;XWm04Ww;K`*R${gCk3;OgS}&^2qz7Lz)8V@lY#>$ zQ$7{!9qgUbW3YELcVO>Q`WE(%_`tSE#Ryn8Cz-Gv)-s_>v3+5i9@`zZ>4MqLv+bdB z{DXbbUJf|dh~&WB(43)5DK2S_DPINeBao1SU!0PamLcYy*m3f6hqy4+=+|zn;t0G4 zM3MnL^9B1=QaQ0bayV?)1Aq9p;NVNAazQ@U z^8O^=1HyYiDn`J%IZYa@-=*S5&asQW4Zf{l=8N)GuwR8Z6ZYh!a=dgYB`Yn%AjjCI zOBpU3*4pE5ugG;Dd%@lj*RW5FNP>Acd@PB9e&m}+GS@Kg8aS2+`+e-^F{U4^-;oe- zu2G5)d&H6|MqoQ5oC&%mjuF_V3+DMn{t)IJ%`GLjJz_4*JFMTS{SsKeBc;M~Ld6JJ zzayD&{#(n0F0uXDSL{1Ch>uDjY?-Cz9X5izl!*d1OY!&d`lJt{7mc<>FjXTr}U znXsRwbmks8M%Je+H~L{8Ofbj3dQR!RVH)c)`d(e9-W#L)KY1!rl=XSeMX0!^8+WMlkChox9`Q6PICKh3~zlbW2KBT895cJ`+l$@y^RBy2ish$C+txzq5$j$B)SdB+UKykjAd&yU#0%Yl6g@hjMuV?U4O!#-Z{ z^A30q73LjF6!VUSfO)q&Z^oQpnPA>EFf0f5l#ydj*q2RG!MHeL+}9V8uZ{@H63O5)I&I`tvj6vpaatYU=$3B_FIKkT6I#|I^=O zjQvj%1@tG$;7C~y!gygFA^3o>cd&O7J2M{;7o^Uil6ir=3i2w@lTFIAzrenpet$V5 z;{wb(%sb3G%sa}-@p_-UC(C(kQbOXZAfK5!58*Grt;yON`OG6H9*4byy@S1jy@S1L zAaOV6QOU*&CR4`e)(YmBL)kT2mlzV4fxRO^9Vz)|*gM!e*gM!e*gM!ee-73V!!hgs z$~PI|xA17=oCg*H_Gf0?{v!C9@H63O!q0@C2|p8lCcb%eq~yogFI0I>e4~owL3W&T zy%HyKZdk1g^S%^WBW9T$4reJNzGDU>zGEREzC(P6{VG_$j>={A%7;Cb?YLJJ>tCZ~pJlldyOHj&WpLh4>EVJP-}ww;aOr7fCJzFH~P$#Id7?ZRtMfzJ;-qKImt8_qH|T)id(gNf|8@ zEh{a>cc#=!-OMYqSm0b41Ub;D^XOiv0ziQyS|s`d(e9 zZcF!pDuTTuA!y%B`)olzqUVF$1P6Hv4swod0mlg9cZG3@eK7c$ButW(ppLe78G>MSSNu!+yKWHO#vjv2Hik&6>fOYfT zF@oeJg3c5ibf(zi;HwA@zKUSFopaHGbq-eBZp=H(JIp)mSJ52cSchYBj(0+AE|~ro z>j)$S>{m&}J{%W|ebF{Z+a_(Zg8v`q*s*>`T*ACVUIpt2SVsstQ|zqHjp&?-&ZTIq z%jkP`ok2gxHXZp)(!H2>n0I=P=((fkl%8uE>oWRYT_@(9=NQ)SuzsiKf}SIK?&vwC z=bFa4jJ{XbsoTQ(o#!6x9qgT+BYN)WIi=^C#=4BYSJ#Po2YaV&z23tU@`sWy3VFpi zcZ7XnBpf~0G{(HcJ~6D{`S;L+93+oH6Nc9}|CH0vHb~nhZL{>8(sNB?T}I!l>(p(* z&xD@|d*{~;^&HW2N6#re*EH5;^u4-H%scp*@H73|nVt)Jj_A3g=aimn8tXFpUR|ed z3-%874)zZAj`Rl3HKJf7=uGU-#6B^JNwH51`^3n1VlFuPhjWcs2=oI#6ZuT!Gm*~> zYd~TvDXvWIIS)Ehu9HuN_kecmOuPq#bB$zPgm<_E!_S1D2|rU@OZv|c7bEzY@H63O z!q0@CiSsjcj#|eQI@ZuJh~^C06TJ6ILV%wMKNEgt>|MgoWJv^_DL!}5nX&)PI#aM- zBi4I1@IC_GM+h7-%q6|&M8|GArqfuL(f8^)v0nxI#I(-Qx`-&3(otG>X`Kdp$1{_E zVDDH8nj4xk^rsY;G{-deVDDh>v~AKhOWQI%*EH5;^u4-H*gM!et#h<4(mG1(F0IpG z?^w(859}RFL32ZMhW-S5M?%2)nRx#$=*&2V#eNl<7r|G-eiiIjk$FKri6u@5#ySGl z5#VQ%l9V6#nJfnQnW?ps)Hm6K&U7pv_?hrC;b-EUcFlpHGsUM0vAJMU7aW@l4*4I! zAul9&FCQ%Bn^AezKXE-Su7~PRof%8*I&P2k68+tAdyI8XQs*jlE=6NqM&GOJ)NScL zP;;ri=|02HOy$^FK0G$@H?jo>c?u4H7aZg-@tTg^c)W-!P?=bI(Gk6bZuepYK=k1H;2HPM0e-RbzoycJ?n~v|B6FIaE(zZ$4EN#p5 zT+>*W(f8^)bz87^f0^rppGln5x=ZUc;u6nenajj6tRs*xFzC^*#PxJ;;DaA;RB{fT1)!C~wKhp`ik_YqQS zB`H~H8EV;TnTN59*Gf`j#A8>pM$WQ4E_zJ$SZfYwZfMSgu`^r`<{jcY;s(C6OmhMA zjx|CmCl)a#nK;%FjDx-xy+OJqwMHNKBiE@I$1kyNNv-v>onf8D_3UNSv5r783G#F- zpCD(!LH@BVaIwACF`dRF<5U@audY+KrRP31or*o#7vTH3KVj?yW1krIiG}%Xm>a|q ztRs*dFz=Ah3_4Th1?*ia_DR_kZELg*(zZ$4EIp^Rjni0{(f8^)bz8a*G;LFTgS|sO zlem%E^Fy4$J~1}%*q<54KCIV8w`*=_&hX!ZZ-l%G<*JxHWCs!7ksP!Q(zZ$4EN#m$ z?@~Dj%sZY)$g4OOg3d)~pDoBo%4i=C^DebUiFE`bNzk{kO=rHaeu?$7;J_cj^e2uH z1S7t~ewE6r)W8RUlFz*@&H%Js5BM2sa60uyEOTkYTjCJ!= z?kFWI%scN7hZsTZ7sm+99sjc%>oS;kn0MM|#`+!B?}D#lSZ@ShMf6GVRbt(OePSe^ zV5>#X>R2+w2(kX<7(uX(Nipy6zPZj7W8UGM2h9P^jo{ykPA0X(ey`vVBM1&Lg5bUO zP^I=(=^O>s!+J@|2Yn?t=rO_ccgO9~zdd3!?L)%P#J*_QyT9DKhVvK=erY2AFrLwXM{iXRMoJ-8|?_@o8zkq-hV;Ag_m40c3vq#-9JION0xhg`H^;*#N90R4;i zJj5|9_GfyT;G730hxb*4Cz@lySCQ+8?-1W<+Z22iiFdGWj`PHVuOhl4_$q=)w{R{x z)-5<+g#@B=@&bZi*-Aae@y&gT%2S3zDy&jme4^xVPvo!6x# zlhhejBrCQ#vE50X0TSX$xz2wN<#5ge&UuJ^l|R`a%)8V#AaHIiDUHB~ShwK(Op*!m zDyetsQ||%?`y%=T`Aod`N`6`@M;&~XcukpgNo;pgXAx-5Xf7e2>EDsoI!DVy%Sy|T zeCd>IgWo4I*JGi_i1xz4-jOh2?^3zGly2AD!#V=i5%e4hu{qWeVDDm^&M|^u{>?cZ zQmg!fbp#Ru=~BFZM{)?hieX{|Uqx{6RRrrCSMXIt&#;R_k7^lQm~Fmo&#hj39j5>)kZiI})0fp_Z+dxgHBWMzD9O zvn<%w!QS~Z7-g6Vxt331e0#zoS0zxJLkj%lP}GCYX$2Z(O$kZ<{jo8&S@tO z1b;^Ifx*ua9Q+@dN0@hhtt!L_j>MLR^*gNJ={ch3j-FFw$AvG<8I5%reXp()^A7V) z>m2M?Nf&#h=ZKy=dQR!Nrm-%g@6~l;-eKNh-uc){&jme4^xV;NO3yWobs2rHu2Z*# z_zvehz}~^$k>22(81}2+JTdY8D2Ph!!N9ut5RpmnRRn99Xj$pC7_zgxr#<$i`L|%Q z%c*xEG4E1mS@797vi28z6-V;gW6dJ?Dsr9vg#DQ$1mYz2tB@Qp?^0`9ST`p=XdO%X zB&B<`PS%{ETVU@<2w1=K?-OZT6XIpDJK8pd_*!gMh`R-IJWg^PN8+TP-B_2=_v$)z zTe=Ta5$qia0rt+XziZv4b(+?7S_i_^MePT36 zg0B)0#QWyE&z8jd=ER4P6O*}vb%a!|kL6)_zUa9V{C}B8dd*H_T}IyA9w{E~D?&b;90ZpP1G;S{ISZO6e%AyFyM(bQkPhY~^6@SQ45WnlqY9 znq!)Kuy?R`+BRvMrEQtEaT@C~`d(cp>>cc#);U@iX&t3?m)2>pcdX_42lkGopt+$r zLw`#7PMTwyd$4z~ciJ{-o26};o@*NGGWuR!C+r>Uoz^*87ik@(b(hv@uy?HG`3Lrn zrJ%W?IYWPfy(1yKd)u1vF;_6}8koQtJ_lH^woTe*XDR9KUR%YfC z%=~$a%W~ax9u9wZOuiGO&j9p)Y8osV(YXNRu>Uxns_=v9ha`P;RELwqV2Iukk*Iukk*Ik5(!4@0g1IurR! z;Xue~2-e>~fzE`^gwBM{#2Qe>eajCyG33N}ogvuTG_1Y)^@WW7mLKLF<{jpp-;07h z4}RYZ*3Bnl{jTUh>@_0A81evy;2z(`g3g4_Bo1J&5eWf%9W=1N=yNriT7UdE(zXQ#`+!B?~qqPUIj4%Vg$qph!GGY;C=JJ0ge@UF9)9iA~@`E z5=?*Mb$r2Ltx9lM!xD^lC-LrN@GFE5@H63O20oaeTW~fG2?9EEpzr~E9=x4}&cwTu z!B)yTCUhqJOvL7h%}EciA1$^L>vvecLu`)qJFMSf{SJ8*Th zCUhqJO!%4bGaHCLgwDjdM#KS}YeYgoE*iOLvJ0#iMK|JHBb;j#_BRS2u*VO3{5TiI z@g(U8`oVX&SPIaYSieJF1$hwS1jGo45fCFFMnH^!7y&T?Vg$qph!Gmd zIvOpd;oMph0%8Qj2#667BOpdVjDQ#cF#=))#0ZEH5F_B62b_%)&Xtw5B*X}a5fCFF zMnH^!7y&T?Vg$qph!GGYAVxrpP{Z^f2YcGFUuAf@iSv!b3FM+l2*Iy* zJV!!KUT~0);E=-?%<|*BEtf}Zj@TTrIbw6f=7`M^o5RmUY>wC*u{mOM#0Zlkj*oa9 zn|&k3^iI8d^%Z>YHN=dDB@%cd82iNhelYBLKt2&rYRWZy;b8?j%-zbk~iia(PFI+ONou^pv(0-fpgMH=1%g3jb` z1I?eexGc{L_?hrCagHC(@e6U5*h=K0k&8wy8o6lXqLGV6E*iOL#0ZEH5F;Q)K#btO z7Z&uP<@^c0vy5-3g`BFy&O`{DNku{kdm3d80%uY+Kwbss_=&whUIlp-3TnU{Coe7=Uz_GocAG|wBLcqI|cy|)-PUe(%fAAhqn&`&x zzJuV9i-XR@yOS{oct20f4gU6=V65L^{SNDQSii&i9oFx#euwottly;>PBH|)NHEs# zuzrVJwD*yai$*RQxo96dBNvS`sfYu}tB??oi$*Rwa3IbrI*uoa8hlopi}Q{2zgWK` zAz=LuxoGH2=uGHL|4uQfME0X3--28;a?!{|BNvTaG;+})?<#Qw-Z#hl=Gd=-{VLe6 zg1ic11jGo45fCFFMnH^!7-5Ly%|d(>=g{!JIVBZCPEq2=ux~-mrU*WyV4QvG?Fe$w z$VGRaQ*#2%hdAHD-yIVi{B6M@S1*`+FuY4b0wLYvSVjc-TU2}oj$oGMtFL@fPF)wB z6Uqz5yu-Z1yz6avj?fS94-t&`4)Go0JH&T~TYOhw(;VCG)}F3(p*xbfewiislPp}*7ua-`%|3ae;D)OQ*b@ppESP`u|MR{4cP_`6@8kO!bA4PdV{T_s$z{)~>j_mp zVjSub9O@Sw+7%r7BRKR^aOl6_*4LLDPwmCm6V#8md_?^dO!Y+6o?xm!qV@#yZ~p(# zpNPwaen!-uV6Knalm2r%%kqyZ$7RBGd0uWOmIJpF%O})txqN6>aOjU?S)-u zi5&J-e(qUw>?ggC5*h0H^}Vfny<#uBqFBVwuG`Z0Cd%Ju7r!!8%IxdjO1GS9AG_!U zDYLJ8pW8Jgx%JH1QbxC{@1-({xQuRB-%I7AxUK(iZxr`=U-wcUqWIbOYBzN+JxdhJ zP`9h^C7DF=SWut;@?Mf{6p!P+?xit`Vh-qb^}RIKiI_9GU48Gq%Ih+^9?kPG$1U?A z%zeQ;w^(if0B)43j=bMYJxI!(9%9p&Y`FC9hl8~1ngk{(}u@BUz|TeJ?* z*R|fzWwfr?S9z@~_I0n;6}l~buhtd1U45_C75lnZ>xzBdyO*v==|+98))l(lz3xrv zihbRyb;Z8!)w)8rtMApi0y+wQ6#OXfYiV5p9p(MEed!tKsFbgs^3#YjDSu4c*+bz+ zo&MV&W8p_hEE)Ty9An1*D#xCJ_vJ^C{L22few4m;W$I^?5#{z}JO`_gYZ=F<95--}q!=kyTk9h`g=bQE+{oSW5p20F^; z>i4B*_7x{0ABAxK14;YrA+3C7+7zn?_s z8~10wfi9!-PTJ4W*LD1*%OD?xe3V{KByJ!dMf(|`qyDUypricWD(%nc7*pr6v@fLd zVEW#@VlM1G@cY(Md#lKPrPkx1qx{~>efd!(uek_&IEg>dQP5FZS73kC;j=%g(oZXS zuVWkoVxKwbD;>w}57sfAj^p%o#Cm>zyY|6!-uplJVA#V+oYa1ojtBL1ZD$X~{wSIo zhvZ!t=%_!(efy)AbQ!ISprihBA0}cw#CrTbp!h=co8Q3^9Nx_lysuafIdkZ!edUyp zkMh2s-nXFlRqpFO8tv!o>t5~u=onMqtJ~7$bs2rVXUAps_wN^upMUh_=F5Vg*p=r$ zoM1e^+55Kn(fK3BMZ3Iddvp_^%{Cy#JI-n=cAVEh6>i#C%)V>8d`SRpURZ% zw3_WU{-ssyqVn%Z8Qqq?cgsBw*akJ9k}|qoeQ)k2)=vAq ziImyby&JFk#4fphgz$e~_l7beAKk9LH?(D0Zo1vSxL3;T>)y}@T}HPn*Tb{uwgl^Y zgG}Ul=<}cM4YK`@_XZC9$9n@eq>OG?->ciw<#ic-ont-4`P5v{b41S_J*V_s3wlHP z7W9T-J!e^0WIJ`)b3At8y6{2k8LfY`UJC6-d~fKF;LuOOVJ-{q|5C4XZja0BXWSp$ z|D_+s#xnW4nCCY?8@DU^X}9i8>F}U8q)gBof`i@=9Q20Zpf^NT+^-AoSQyJNrBAe; z(fUX0rO>VoGEC{Q&`-G@`Y)LE6LCc_>nGySpRTihBF_D(4C^Q2sLUx{k1o&piRPF* zm#$ym%le7tTf}|d*S)NtXzodwecj9YiS&h((e3JcSwE4!kTSYmeJ_g*!bD^YBzN+J&TQHxUYLjCN>@m>hoXTOR}}`IO=xwy);HP=74Tj z-%Dd{W6tdB-hGwV_3L`Fy!dYVPnqi&{#W_NZOM%dY6>nt{sw#ci4_I^lzE!HW^Pfz z@4oh}J#|uc!SvhF|3`c;{oPSH!E~Ra`vp^dj_OT>Hr(9V1AKmP}k*oL-|P6BRJGAIJ9egJ=3^9fnS=re$9A{M9zs+92BjFWX!<6%#o>@lVvuKbT)b z@O?WTntA0fwFQ50>N^S7w3gsPEn7re*Hso=dGna)^|hr0U)^m<^ywq{1Sg+JGuhtV zDe|fI*zsoZql*L|Zv8o&$L?_84~<(y<0oUP@r<*#L|6an=Pdm;^#6YvYd!A!Dt|aU z{wlv7z}~pLH6|Z$tAu zVodYi(EJxn`oL@)@Uq8ik29n%1e5-bXx%BeCE`uZN3W^5)FfHh5es%WKJ=57iQx{N3`L zV`N_Nzx~0wt^L7Nugmh{Ib%Z`DNM4BuVr|irn&i^pM`tBOs!}x z&vuP)^0K_eO`+aX1YbwKP>Dv~$4G0xDeCp1_l36Ru~DtOC(0OgXmWd0cwKqHZ#5|# zb@{Hk;Nw2nUVp)|Kl4G4(V^@EkGta2{$SI!@+Ya>+5d+()hp}Fng=b*SYvKC=G(kP zE%(HY^JR{owxx=@dBC|+em~1lKFIU-@nJR1=oy=2>}nRSWHw&eQ^u>(&&ACx^S-tYOPovMJ z4=k4>x&Mm>ZLuv^cpvqZp2xYFeZP_C8a2A8OWrtNJ`D9C&M9RoA>_eY-bjG=DO>-3H$lFv(5xr4Jex$X3=Yup{Mq z-KN#d;I`ggx9(lr+%dbm^nc@-waxh*hstxEHLt3f+`hg%?|qfi%^SBoDtOY&{H9W? z4+YQIm}Ux;+9`PG#E+w+>K-pV8Pjl7v@}N}*9lv$Ea7I~GD*gw=aNe9leaqyemQ?F_ek5tGNx%i*LJhVKRJ`@ z{Hb#dx8aODQvb%mC%H9^hYD_T&x!8-!7~N7{P|e7JnJUGIYxYK3)jr)_}))`$=iF{zm@WEbn$N|3QUB)X-GV+xmz+E! z8qu|g+`D4LhNxfGY=Zw6o>9-u@7JfBh37sbaz3+SHM3^I$%3D5TiZOa?s}P<0n0ds zG7*nOxL0tfQ)8(oBkI4WPZrnmiXWx^uiJiUlh@~xv72+sBwKKB3Bg--b+%7@ZjY4g6Ms@D=+}JwgmT1UlC&|4R_I)GDThVjl>a`o9XTHuV z*Y#Y`_@C;J9!HHcLgspW4_5tUKm64e?wwg=tFe~ni>orZw~B6+v98p4r!Bd_=kE5W z%psCVhVi`jE8p5NFZlJ-DY>${Z!3Hk@w^+ku!tLT&UC>oidAs4OWZ8@z6Wc#-uE0Q z_*`0ZX#4cTlB;~PLM=Doiw|Wk=Zq@5>~FTST+ik%CEdkKCI~L~OK!Jo&~m|gEHwV7 z`lH8DdLFVpCyhobL3PM7lk*5^7z+>IeT%j{eEGDI;{kp&V1qd5sSiKQ-qyK3Mf1N?B#ZSRW#pL;pkn9}K_r zp!-zdzmF0ADgR&VG>yNyW~A+UqK{jjJ)xGZ(AD?zoG;raFYNDQnG?s{nW$OI<0->U zwCVn;!m%n%9*>&OE+hDyXkj$!`22!teUI0S1=BS{e-ph#WewdUnCdW8mtd;fP#cnC zp*9V*E%{RFi=jS6Z1<^;hWaX4+ZTo^Ng-PB96*jI0UlF z=(Y~JtVX=ig5Mu8{O>?8-~U(pE5iFDqE9m7JrTW!MB|KZm!DVdqxgR@t@-o&EW$&L z!#gi>J)_>)`Kxis=yrRZJ%jg*$aC!v=Cbj=2#skR`MoN!P5eGn{9aOc4@>OVfxJHz z#!&jHaYnbxtG|6KnV+Jy`W*f3cLwy!087t;SkbnSL!}=JkBc z^0-_xx{4|CePhA*Tw2RqIeD&(W3jY4rfHY*vW7lvL`_pD_YX3rTk=#kb=P)~`ZJ== z^*L*qb3a%jZE2k4+{$LCX(#P=U0%|3J8rz-?I+|l9R@8EeD_CNqpWvl64^d6>4T`q zMV?D}j(RMrnA>wH>y>9l7qs_t;o9^k5@&4nD?$q`K7eeycm| zgH!yzYdu~X9}a!H_o*D_)*fpuk7?yeMNRuQ{$2Z5uB~8ly>XLV&pWDynf-na!Iy2R zZC2j!oa{Ngv}G-G(#>;4=2cfzHfOGGA@bDx(KsX8(qmnBW+ijd`YzIkymd>Mj^+iy zSALz-xW%gk7rk|JRH@0aGDd~BCZjV7`FV7(>e0`*KX^&i_oKBRd%kIW>&NdzgU|7M zWpC^8Rt_`ulQR7+pmVt%bncqsbu@_{hqy?KNe3EcRqKQUa)wyd3<%p z99W(Aj;Nz6FZlo1I}5lfllAdq2MXAMC@Kijacs_v-HpAruHD#**xlV?VRtKMM#aSL z?(XjT&ph+u@44&cUiQDj%HHww+2zYH@61y(@6?&IxtWCwES(j&!I&o`V5T~=7oA?Q zQ5Uw!S+;U~7vUBFs*8`H@RCbO@p2;T)utOP@UYK`e4Pf_qz(EY}Uqb%D>wXVA%a5nQVt=4;&dR1iAR(e97E%!HCp3YEqsC@izz=wOv4%lv( ze+AjF%_lvZ#O4)H@fPuMKihdneTHJi!nf@Dpu`Y|b!*u2MmeuQ-;%gb4*s;XIs@BI!y00#$EEe`Ra12@MAe~P*}$f5klxMj zy`^Mrbw*vR2T1)OJ-*A|?!zN?x@-!tKW3~~5vybD`M~s$XWrf`>_U25;F#pWYf3TU z;~DRpU#?Q?IoI8@gx?k8JQ+*d?&K=3jPtwoFwxGgO~EGEKA5A+ zpSt-Qawn7e>|53T2S~eZs*fEJI+bjirN-W+6Bj4VTd4P4+XoBHE|=8UJ7R*BrPMj4 z7uFr~&nh45-r}wwP5J6F=xg5TPVa10W6s+)#mJ``7Y^W_AQAfQOuna$|99(7$ znF%{{Dcgejd)bCvnSfvH9>ZhAePW#9o-SA#bL1MENiSnt2c6HR_BTTB?sAlkZFw0V$C^Z`Wl1;CIix6MqFZjE~>G??A?j^#B6UthQkq=xOXje2g0PA-O*1Fj3* zufoy&DjeOf!qNRI9Nn+N(fukM-LJyY{VE*Yufoy&DjeN8Bjf1%ob^|b2krUtm@v9u zg=0o{>2P$<4@dX>aCFZPNB8`2bk7e*_xx~l&kslU{BU&74@dX>{EMBj&3^^iqU%p^ zJB{u37?*Y7*g*I8aCC1EM|ZRQODx4CzqF^JPqcj_&V%cU2^(iWjQ0TC)dP(Ei1ux{ z@g8CF@94}-)O!cgjrWmJ&i6ZqquyVTZp1*G*M(yPbF)&f!qZ%au^I1d6J+VzL~(RB zj4nSqo5W+n=!_hX2@AW+b8%7cn(vJLC~O;bZ?m*{)VMpc6WF}_kVo5)4q$p?e3r2XZ|m=JMFvp+wT6ZbLnWD87tp+W4sIG*h9{5qQ;qW z-V-%%qG;YEzu)FBec#RJ0;gfTj^+_kFQ`w-faWhz-=`zzGEwykS>&AL&wbyG{_Y!f zuHa|-F|NM1$o6!I`J{2j6z0k!cA4q#Y9BVTaRTCJug+1V*_xBo>!S8OF-Mob>Tf3A zV|ouc-=RkZw+iTCkvuW8H}AT+fLsTl&$l}9fsRvw+m6h@-zPc@-0f=u{^aE+U{d)E zn^__)w4<=!L)n3{xqv^;uEZ)%Q0K}zU0!NAb3n;_@JcrGvz=Nzb=rDE?IUG>{B#zZkjFK9N_s* zUUc}%Qos#UnCO9ZQ^DqOS(iB9%f-2IkO4Ecd2w;SZm+|cKsIqp8Xuo71>|?D?aqfy zZw>rs^N-qTNBTGL1^ZxTYxb8#LUSe(b^;ygC6 zIFHT6d2C>D9-E8v*l-S~b{&5%&SQg}#d&Nl&SNuK4)zP?*r*HpB5$_Ar0)nMZd%-=}0vb#<0_>V{M_=>c_K!ow*$o#>&?5;VE%M!hz60QrZ^@T03gKLWjI zB5{6YaIM)p<&UG_!t{YgK>t^CyH?TO@&BVEGU~#USiF4h+(diW% zbzz%q&*o1XEIk2s7%#pLC{0QAeL&tred)d#sfpCF#C=!V!!!`syS_cmbZi^2SD6&F z#Ft0F;f?Q-1dFUem$|(*kcaskfOjqLPSW|p8Ya!w@T&av6WSS*b_Q^+?UnQ))%;>!y2}JTqj_$ z#>mfYXaKxpj1v#GF9|Gv%HQQ0r15uP`J8-SrpxkVxsqi)kp}~vB^l{NvXLLyD2K{) zqkLeaUSRPjDG#tAC$J$u@Wr~T!$f^i=|t2Qm7j?EfJHepsvJ>174<>7{3(BzG8lgc zmd}a$Ku%ens1I1y(|u|Y7n$EkXOfNlz(zS-rW@r08}$NpA`&%x@PQ4 zO_RCS1U{4a3>h8S3V5H-2r_J;(y`Uid*%!El#Urs<+HTlO2@8iDzT~udPDx$D06N$ zCvs!0TF-w!r%rh3kE-6@`w1I2xDV7jGRG!XzDq~obZZmxPmcA0A70ACE9NN<{IklL z`aXo3yL1nivAESLm}U#e25aMeZg-)1cFYHU{wUB^+DM{25g_7RZg4K zRrrz78KL|M30v?M`>#X2kqNr<$R%TdoyYa#R-ewBrOeG*g>dJ>qb!o24eiNm&F;n| z|EzLeJNDxVJ>EfG15btUboVntT~G4%;V-h3hPrMR>%_{SGOJbyu=m3~ z<_5=wP5&V0Un%G6rivupnch(5lhfPD(>fi1$KOg!XCJKxytut9^^GhF-278%dde;* zaLL7u=sD*PV8bSBJJW=bOM$;m>Prh;%>z8`O9&l1AXR{rIWFr;T``ERFEbBh7+oot zW-6K<*!(brCe3^b%=iUn3VDoP@QL{u;roYWyoX)?R2l&F> zT(oMRQos+7e<9UtGz1Q5yPAAhqxLtuUGXPblBj;eukXep3BRd+<5!ah_xbkY8}Jim zE6{~6=*W9z-w1Yi@70G7+fWL)%8_f&NVO}o2T02h>gw3 zu;INR&#xxWjXN97=f5eL7k?N;TGs6Wa&9|umP~Bi3ixeU8hUhSb>Qk#{OQ`x`GJr7 zRi#ParU#x8)`DiveHCmtymWVZY~Lv0e6#z}LJnuZ=5bk<+?S3z&(LRMU%opcH^{T- zUKj4VbUv`%#irb$)DtE1n~FT3Sr*VGFw&Q2@+}D5$2u*~QB3LHGW``cDk+&Ybj|^1DsTG9)NVA4vbzE*P`XyrYOH}krz@lHGqF(}z?eeR=tw9T=u>qM66>dWZ z&p8TmUK`kxrn#!dJcFBr(2cdnLfa|5pdTGo;S}^^7s_|1jhBuBIiJjILB|AM1umDe zDxK|>fl9sdm-44AcjgCfA#vhWxVE-Tc5gs zY-_ADko2X4fj^MD;o0u0cV)NmN^J4|-jF_}NI0vVwgYg@S4sF1*LuJ|tDNZtgX!p= z8NtqnuXdqjuBfqeC-)|_?DSWV9=4<`wf&eK>aCl`jn=C}f&14?N{c_P3;eUnNwLzF zCcYU6WsV+uf>fQ<8aTtH-o(bgCvf>hQ_ZidC|m6=bkuTZeLqMqXETZ|YTO<8XO*+# zqj;CjQL)r7{|RQjM9JgUDmCBQLe1U!w(#P!S{8wNPpmJ`uhm!cjvOPK@FxXdf(<`b z?!s65Ee1Y1rZ3+S<|Ienzi}Cm`RN+M?T@+vpFdEWXJaXV+vjV`(`Sza zIiGjw$-S?22QK9r!po-!gEnh0v}Gd?lkL=a7T740%XFhIU_%DXQ17oM&o62#Y)`P; z-{8An(qF%F{Jd`G#iuk;eTDeR#qVH4(H6Ogvmf|BjW!n`x!?UvOiZ}q4ZCA8I zVA*y>`vjJ4SG3zGwnVYW!=mztXIa#btN1M&JEv zHu+`c`Iq>qLg<@9?$CBhuQbta4b)vH4MN;#-M6X@Vz!SazkR;+v|4yoF5ih^E+*=K zL*0?ov}zSP+$STX4|v<0-bi!@-l1EDcBLK0t91s4X~DFmdn!mzCf0L)%YGWxB^Gz= zLnrquN@SUxN_V1%SFHuEv%MkB-R3j!?&4)=|E;Q@`4>5VVR^8v-p+KR>#h*6kN8Q& z@4&*AROI`CqsuRR#fAQmU)X~Sy8sJ2F<~!YVLvA92rTT%gnfa9y~BmwfrTH4@CUH) z4-tL>7Jehbf55_@RQMHG_?ZfS17n$gWqGh{BHp=(dyrqW11{nl*cc=Iz|rN$Yw|H+ zyl#)V!L<-Nr)UBgi{32|Lf=1}2RuGuKf2@c*B>~#{Ibo+vAF#IutOfiuZH^UgIBfX zB)n~BNY7aB1KBjS5pb5dj?}u2ikT~~DBam4FQk_|P?w$$>n_j}|~*)XpxLCtsKqIQh#EJ~_uSSjPw}+K2BgUlMF}I!8xd;>2d) zu8)4>=~5;F+a}0YoJU6H0WQaL@yD}D0T+GonI)X8+V8r1E7`3#s{Qur@69UaS3bp` zVfiP?k9Bctl$PH~s@6sloyf)$*DVjezi1q%abT)HOtWD$|gxo z+X9L{Q;he{Fh`dk@6*ME@m?Wj*`M7DTe(%*Ei6YrzG1*S==bm*DCX$$<9$-hmsZr} zyDUkmEdOzaW_&@T$3$`|(w5(Peeeg4EgnHk9a-pR>)mef!OB2()FY7^i=ci&nF;K1DUG}U@PVMRq=|vtVFeer7 zEh%R;Hyc)Kh*|^uQe!r&vM&hID<^rv!XGvT-u1gZAK0k^aNy1&{B2S-XABRm#dnUd zhIFj&KS>w7XNuV?(?*hgQAaLqIJw3b6468T`D1c8Qf^W2<#AKYv}!UB$dkHiEjl_$ zD&Pd`TGJ0HPB8iGq<|hY(TTypcuxm&Y}AGKj4+?Pkep=OsK%35-{mKDZ>TXR-fP1g zU4FbDhxy6k5T0;VEog%e8}{LEFBSvcZ&vBT>w7K+#`~C81E@#jxImmcgFmrcW>$y5(xU%+uo19x_=04g7@n&N0(prR|9g5 z6`yC8|NcAUHD1gk5)NUH@~L%ZyA;D&kHcym8?R|&jxIl5_r|J(=ezL!2|MiwM;=_4} z^N8WysL$Q;z&k>N>FIRVz{>xIN3waqcn=Zt&nh49 zOU8upJ}l-&2VYoL=2PRt${(|v=N?t#AG~LcIlBCzyWM#H?F9VdG_5pmI9k2y>-KBF z`_xxwMfTtAz*l_S0`|Gyq&MGQyC(3Kun^ugyrx;Ug|n0T@m({{LEmEI(}QR68p33H z)#a`EEf@6;!gb+voFA8i%g6O%d9a*Veq0x3;#iJ1Ymy!GZ5Gso4;!QQt&%1P;$>{r zo}f?hU|zgi2GBA2{Sba>#1)vY`CjeK4<)P!dbO_5fnUtB1GwS%di-p;BwXsduVhhv zGl`lbAMhJ9ikj zm1KAcJ!E$2xv0hkTECc2}84Gdu zOFp1WiW~ksrAvO`p@Y5n!U{!x;OO!<9OcA&I+Ua`wzH8E+;y@u@cVl8dA`aCfs?v* zhGoF=3j?>?l$v+(uL+!d=P@?;V{70s_4=}1S$hJ%vs+|o=&9n|&%DWe z{i}LkWU4!m%owlEiP6=k$h^$z+4do})NEA)p2hqR(~(E%7@qwU%Tq|{Zgw5OhHq6i z>2qV1rC~Z{H^Js87I{ci9`P)RdKTMC@b~g@I?j*F!R6z6u{>DLKa~HyE}REHi_64y zVHvP&SZ2&WvHaMU`Fr_)kpH{Cuw@L~S$%bE%ly53-T(aCzT&%m za9rVd!*Ph?6UQx%XKd#`#3zm)-T#Yz3EStNWdFTSPq0nFYApAxWH38zt;WE?6j- zRK}LnON^JPY}=B>IGW0~jTr1>{AKSW6 zX$LF=mJQ2{b-_Af-Ld>XxlE7~m#^(VAi7wM?U;e`wf(jI|3CW&+?IiVa$lk2U%l_5 z>mRiJ(RcvI-oJUj#C9y{_($Wk=o@Nnw1WQ-i2nwjt>~`R=YU7nsZQC0G+=Y5n)zwv_5Q$5-lV5D#pjS^ z`ES}@B`K%00G{7;G->Fg_K54=K5y{%3UY5qX@=)}E&Y;UkS#Z+r6r34ZhomLK~I z=f~yX@^QUb9xNx8AM1tn#dg5jW%ffuGyZ0C>k3Cmw8H5?K7?;&)*2 zcP{b)i|4p_9zLTX%HyJ3U^(s---`#I7ckP{Y`>8o*eFMqWo48PY}5;E$OCN132ev@ ze6j9oabLCap{!rlC(D#_$@(OVf7GbYO6no&lZjG4S)XJ>Z(wN;S)WXoc9Qi;mY2{~voo;u=IETwQyb%w;dfig3Cr7uoq5IGH)qiS##V>#9cK6TN z_tEW6w>v$~)ZYm%ngZ!>s)nzx=5E6~Fw2+Ztx=$N1$(?XURdFWlBJYd^*> zKWcx)FMr{-hFSYDe)&=RD}MP4w>8Y#kMYZo+F$X@U%0Jd)_#m%e$@VoU;e^v4YT%R z{PLsrSN!r9ZflseALExFwZGz*zi?Z_to<0j{HXmEzx;*U8fNXs_~l3KulVIJ+}1E_ zKgKUVYJbHqf8n-#1wuV{zF@E_``zwC=3%51Q+K=(ekJ?}H%U`&y zVb*?(Uw+j7ieLW1Z4I;bWBl@CT>ESP&^vi#ycpjv!z3HuI|KZ)?$7k|P3;`@{gQF5 zV_bcQ=Ee>6mu4_Ve{BbC2OR@C z26PPQ7|=1GV?f7%jsYD5ItFwM=orv3pkqMCfQ|tj13CtD4ColpF`#2W$AFFj9RoTB zbPVVi&@rH6K*xZN0UZN626PPQ7|=1GV?f7%jsYD5ItFwM=orv3pkqMCfQ|tj13CtD z4ColpF`#2W$AFFj9RoTBbPVVi&@rH6K*xZN0UZN626PPQ82F!#ft3joIa^uv=Q0dp z!Xht?JQygRk^laW{d~uKFX!}eUs69?UnsMr!y2-FTqj`h06n*%0q~A7PBhrQB(V5N z#qYr4?^NUi7SB=fJd-tv@~9{mI4<&Q1%9(l;i2Z<7@>zYhjEF&p*~wzIN2QoS!t z^VkDyLRxgDRXQyPUOci9tvTcaaA1it^vD)RDCcnTywugUDDdjvlhU#`>jE#X!%5ko z_P{rf)FEa4dIP)e@-vU$6#|Uwwcpd17Al$x%CG4hL4K*?YSB&`$T5v zYmbx#9yi6zt0waRo^P(ri%&}l>}}VUXE_uJepxlBCr@*t8}PouA$-W5xn?QPjie!b zSBv!)$-kOB!q?yXiX;zRS>b-lCSfzeSpPI#K*s}~ui49lO@J2;ci=ve<$!xE3*h!C zJ%O#~)#CL=TLV|x(1tJWaTx5-vTjfQzGqM1xxOL%aLWZ?ljqhUyyKL$U=!>w%)f$c z(q~b9OU$@G7jiE$@_uLB56gFm>=R`k`EHT@ugY)5qxx0(E|UGPOqcH{+5buwf9K){ zuzaV<{#T}p^0@4OCC6=D{}(^8t(Wiv7w>)OpE2V&iESBP*#7?gT@w?Qa{e#HgVa~X zp!ydRmO1}jzW=kE5!+1WG-4juXbVuE(MEucwi6|XY*WBSTLU)Y#K;qOb;V_@;x-c7 zHoRDOwQLtrwvE-Xx2T79pIT&zj0f3|M)iBKGme$D^r!Ow>Yrlm$G<*@ic3F=ccOEY zA7#AAxRL(E^B3{!_jwJT@8Efm@qUJ9alGL;l=VdQ`9^wF-}QYiX_N!)#V8-xs2A9f z2iTAk*pNRekI438|B3V9XK|UhE-V9<&Cn6#$GZF*9f>GAR_2m7oo2lQ$_hsj+Me4YJ=pE5tf7da}ci+d8MmbdGG0F!v>ID{m`aWJY$E!}*_k^7$jml2?iI@ewJV_=EH_ zfY;>B$RB$~0^eMim>+BS7WnI-YiwY78!Gc3y0Ml`eBl86v&vbUW&|rc$_2{AjLY}x z>BPGgnFjLAE1!vfJFpLU?uMlN?!_0tcbxCCV&T?M&V>!zSdHfPKgju4%E7wFgs0c= z;cnr%nY7#Iu_k_NXl09JzxpPg>Q#5M$bbA;9=>w=XkdCM3s3us0ryIf zf@hfb7F33{zrw}ah@%=&}funpr<25gh8UAnPqmE1tKxxoopJ{v#a6%Iwi zCx0~oThBaW&XCd{c=pzYq$u$Krd7g7&PYe#_q)#%t1ouIIaVd4!NWg-9sE0Gpu4Ib z2EO3xM7K?x4xG2M7tP+f81Szq&yy2bd9Rr}KsL|^u zSEzSim-KXs*D>H0k-6#eJTrl@{W1TQGF#_+z^uBbQv|g$bYG}BQ2kFDe$fB z?$ql;bKr@q{phE6_ds`{Gu^W*gR|5HrzHDWlBG&#jz7 z$SEh__SelMV2u~>mTyzdb(5Qb+f>PIDYQfJ;w;%1jqri=%`1kmC52squbEgw6)+h!%D7T4sSuqxTacG2z zcTF4!?JH=3HzyUmiS$c+lzCt$8xqvV7i@yL`^p>UqeuN9y=eL{v;Qf7U>q};qsx!m zQTj3|c>gbtz@FDzX5}Z|h67(2<-#x6i~x44@52WbQsbyWb4~nO&!S*+p5MfqcOMQm zALZiBhn&a{Hpel8IkxM?wi@`&+I--sioGmdCR& zwXiM~vw}UboUu_REc>0oZwe_H5LNYymFOI4}Ji90J^c`O-9w zDS%6UGSQXC+XcvHQ+@NJEAE~H-!(e#PF3#)!x=o0Vb#4<<6SjU*~&@EG0m#I$Ruk3p% z%Q@ByxOdT+mTF(rczZ^M?B;7+jl;`3*%N-;2l8BNFoa|-?+W~E{Wdbgm_tP;TWr*Y zbxgg?%RGCnYC9$O&b3T`qWYX-PG#A^cb;6v&w{aYSl5rafF}f>WLwIp{(SigD}Fib zE5y>u#-cxOdJH(W%fC9dIJ4AOHph%@#vTeE32Owq&9^*gPhAvRf}|^yegdAz@$(P5V>?8be_b{cZ+CP&^s5(|d-1keixX+*5|eUsSG!rj zPv58GnMWQ6UL)R{p%1?S2k$t}2H#Wjg*~Nbu_{B=*cICWb8OUwZL&D|C3Y;Q9oXbv zoy7e1x3^5{(yCr2{%HC>;3A)$`R=acfpebp=C{ju0N0*m;%V2EhyDu78QbOKx?;jD zhxzeE&7Oh3az1zG^}07DQpY|`a`FhPMZib1q~mA4oCNOBJ^{a*?F(?whzo4?dOL`{ zX8tQ!iT*i&XP@rOzRXke_t-A~_2&fUVrNxfgc;XcsjWNTxS|!v?0GE*KY45!@OW=K z-v0JQ;N!zTFn^asApg;T!z^)+48Y}<%wSdSt2lh;Rhl)hS8emfr6rcBhgE+Vmvs$q zX3qy~-Uc#b9+x=+{rjquc~5>U3F+Lq--oN%}WX+`zGGB_@Qv=mzd<~5g1M^Gt^uLbJv8S zq*xO*PRrMJAlZ0Dt+8O;F-Mo*z54}rX`6bdZ*7@~-?jPxF%#A}BQHMkAh5NAGtbmw zGH|G$HxG2l54@s|iCYiq1$trKG5@UcvF>Y%3?WylDt$*xPESs`srhwv)2V>mch&fI zNQPY&zm{rzdu3f6mUf#5mo|S@elhb*of8<#7Te|Hx?;jj%BG=P-k&2DL-+ z?9pqF2QBJY2htxl^r!2;?S|Of^~glmd|?n*CmQ+E%#-ZEN2^b}(g!mJ{=h%0{F^Pa z(QG9*gFKkC7ICFP%Z5OD^~ydpyQ>p$k02ARTm5&C`Nl*OZI-zL#LwjwKGd2!{2(Wm z|F4ueX|)F(Tc9q;fEnAN&F|Uhw2Dd>zX{ItQhl{<7LzJq4E9UHE?;6@%1@RYLuJckkF+;C<8^(%IgdBw7T&3gsEB)!@s1ztSLhQ4&Z z1~xA?GY4&cayjtC`|dRJNi`2Tk=dVa4L%7mobR=XHs3G{`kY@)9_*v~?m1|!4lBWi zXG`1B)JrY`PtEq3lz5nc%XnLU@dPyl|0P zvyJWYFFdSG79UXU>q+PW(qel~@X^6fr^);#X@S3-v!bq*)E?rKed#F6bOQX9H8K~? zP-`ym=suqG#;(f1p%eXS`^}rdcOUPV=sA80e23!-b6m<$FVLS_7VZVvFkiVZ`pHEH z)p*InmwE=L2j5v2a-~N$3<0KrS*d4X3viWN$>`5xz*&h{mDG4=4CO-gKd~7Q9jz? z-l-ij&cB`WqrJ~xgZEDMs~$A(xmsYW*ZFeO0n=s!JEhM^FSm~b7UO>^=DEPJQRc_Q zS$K|iyNHynj&E{)IQS`WIoJE__Fc739vHZtO*E-Fb&_wxm?=WpZOa}f=37ejZwX7) zvb-Il`n_u#+nUX76;JqbTTm31@oUR2g}y>(G}vC)E3&yffLKf(yKXu*L80~awJiGW96DB z%p|)SZ!cdkBRuT28izj}Xv2o~R^#&|CkC=ak!swYWW;vX#Yyc2kKFf|wSS%*%6yzG z6<;LQYoxrEaSptzc|Gu>?ryyDf*{~7_5JvT67L{}v0m{}W-0$|>->x5&zSJDz=6c? zrm`XCB()vL(se#i#^7w_&7Z`2t1NGC=`<6xn40*|A6MJJ&c}fXvS54SCqW z@#aMiN@jC?Crjz=if6aa!j|7x@`qXtVh48qXZhn&2JDNpR(7O9OBM5JD{l|@_*luG zFz+7Ag}SPZv|m$)l`!U{C#Nl9iHoT5#yzp`@YOdB*daE`tTL}Ca|lsuBbc$RT6K6z z(ic?ivD*knK0V3;@-*x_g0%1E0^G8FP7>N(`69^1%j~yK=~&Zcn&osd#j#Ol+q$VN z1C704%%4l7X5B_Ao15x)W#wA9ft=lJSFpPyRDXqSi#aCGit}$ooYjOfOV#Z|YDMG) zu6xFYH0`eHwLktg;Oa%CyVdT6md%%xud$sm|CKVa?nSSqV%^6n8II2kV$*sk-RBKk z&djTo?uo{qV*wpiTpfM?wxFM^K(V!03Ueh$zPl<3talD zKVO@AA=vYt#l$yNa|Ap8ta7sL36^K^AWmY!Vhqm3SP*2xoOzu$zu3qN(svXzardLc zevlc-MVhjf?#&i}jwgblTfcejsgLM((UoOVMpo{${IOUn;E2m6TGjVOfYi7DZGXBda6Z_i>P9a* zbBdYCbj*LY9I?hr#JW1zCvasV8qx7R)Z6=5M*7Tr0Ql`xXS%DnT4M~F;!U0HeIPx- z026)KvL5)QNInxS@^<)tlr1*u!Zv*5;ZALbwguU)uk@pBD%=OzQiyq_UHD0uS7y!b zN10;+ChgWQog1zDya(|5><;vL7@z$e(ASJa|NQ>_0ko;kz0K|Abrf|#iZ{wbtXSL*?v~}SeF#u zkI6pY6kPgfONH&^Qhqi6DwuQ-S_U6;R;08qaw5jkIhttMSaH z0u7kCftvTlcKKFctl6TO%C?xXeSDpNW0Qs{+jhU`&lc2C^Zl6QsT`JsY`m}Z#k}lD zn}80Vl+?OVk07|(Q__azDw;_7R`U0b;_6?(q}ID%vOb|HP}@()9@#!&q4q2 za*-nszpB>N?_Lq-a01o&#!g%Oc)ntHp+Cer{%Z0_+5XJDUgZB%=ktxT!4Lz+nR8&{ zEIP1pMjhBVyAEueX@?jy&bk8|XW)U2v+)qCQnsiw^O8L*`}0Ws{w^6Z&G)1GM?ZuZ zSTV$%ehO*{F|++<4%%(^GT^64?P&EXmw-QQe@~7MPsF9ni_S)p-On=sXP7pPWNfBB z*ATp_D9P1N&5I{_%rsB=qT0KQYc5NPa24BCGdnQnO=`|tapzFhHIeEwv3-6u**YJ) zMW(Jz1%AhjefM~EPI9A*59Fy_dI*WAtooM0i#C(p71X()Kbt>MY7hnoSjTJGI4Qx@T3=G9F{J5w^?8b+gS^S}xyIUT zf&u1D6;+!$P@RYW>4whn)>Kj`R5})}huKLE8wp&@U8)}>xmvs%!;>!cB zWB{9E#x^|I#g8xZe+9nFeax3P-<=Hd$0Scyw=3jRRkbIAd1JR_B;7l;=9YX%6EftR z+GlKSbK2Y?jp~AkXB*+katZkXzq9xv?A9-GvXwObS$75I z(b&$IW1}u?^ZmA~$?R=vZ+AieZX`iPwf@=rWpXlpr?Tz&umb^350uSc?_X{4Td#bP zcxNd_bF24$-sRKS+JNA@?w!I=1FR9NxO{g0|Ubj?xPwP95A$1n~XMN*R2A|FT>`gt@$704dZ@a;R z-u+Mq^j(lAC!KsxwM~cQX=tIvs?Bbl@qxJJP;I%3Z6tZ_uiAKUW26UJq>dys%u$^IGa-*@H( zl5eFQ#MOu#%gN`1>YcdIwmo^3QoR%NJ6n;idDVHUDmDWGf<7plJRP~yGPJeopWoG~ z%<2tNYY1^!m)`~#`k>Nqh`qG|KJ-gXXW%J=Of-GTI%e5kTD3RPY$@A79B%yRO|4d{ zHTJKiUFgmRYEQv&cvf0$OgPx&V=8f;#q%L>bheG{dYcYJBdsm75O6H&UH%@WA=x~N#{_IeIGdPA*84I6os-CU6#VzpPUkL=}@ zguunm+47o))qB%5cMd*#w0gh9WnE$nK*TtW%6PkM^M*K3HFwytAvOKI+zqgyQ;-8~ zzd)@Y=5L;trmhhJ>8Z@VG+%*qz!{F1Xa`Rluyg6J{`B7a84$PFN0?)~UTn{pFqS7K zjLYmA#i1wy$!)J7wuxU%sbLVz3oCke3HI^#MMyE*o!E zY7?+udTYLR$35WKE`M>4BkXg^4B+>638%A4<<)19YgP+jg(KBx?i$t|YRO_YL7w>w z8<}VHR(!j$FL~Wxt%29PJdwQXs`ebCvs-M`CH8l?*pFi}ZZX>waObvmZ6W>qWK z+bZX!Iqb!~T#%=QXHAyso629d^(jlA^lIN{=f$B#+>HI`C24P)LwBol3qPwIY+JEU z$HhJ!*jDV*aj{PaaW3}hxY(zI@w3>c<6@r<>?!u?xY(xy7W;Hu?9%~@JsmFg>40Oq zd|a2zoHX>ljD)>L7ZADtie2>SLBVo!Fp%O>#k z9BY3XUgiwMz!vU7Z5yb$!;#Xt=!*8COt#JFWQfapTUAa#E7bo2^4Og`OFC{!!=-Eq z1}!EBzN$6e(0h%@T4%M!+ac{$^SSG44DX@Fjn`Kd9^+x%G^BUUA*E{9Ays)!X4!!Ur2;>9$F}TDs;}vAW`Fd-mzQ zTARAlbOjp_q~=6NM_ppKo~gCO6(| zv)6+BJ%&2-#$zS|Cz<8WeY>{+{N5g%zwIIoQ>yb~<~z>nW3r}i-) z3po~lDzjb6Gkm=tuVcCg{RZ3a&ToBe4st%L;K(EVmje5*x8oy6UI5;`{3BaCJ0a+` zzTFWPVWY;4wa(3CTSC=c4S!d?#=bnrh8f#-$_jJ1#kj|E;n}X{bd8ixW0FVQxyQu4 zi(J|bbCOZ>SZF`hzdibJnpJ6<7V<1hnUIHH_{3!Xfjctrok53y_kM8VYZFcZ9#PGk z+m`vvo_EVI-z>Ku!41_SJ1oXr3ojWZj-##s(vOZ$p+N)}4r01N?#iN||EZ%fx+N3qmcU}&l8JRoV6ko)F4ir9#k!?gtXl#{ zCv$Aqi)}9E3QW!!qz%Pffyp_8WHDE;$T@>#F<00j=M0j?T)`~o43foMfyg<7WHDDD za?T)G+Dy(FB*$f4*lsalEN4tu>=AIW4+ZT`>^pF=?*J_J9k|$c2$%YbeFrY~9iZP6 z`wm>}J3!2ceFrY~9e|^g?PrybbvaVoiaxEP-Y=s%rKcZE>b;XNqZ3_!YdXkdf82|{ z|4;;YKt&T>lx_gXZ{Ng3m(~h`zNK7hZ)$E@kVze%^>U(T{HFmIe4n1$u2$nu*KbyI z^%pfq%TVspU83L@%z66x(1i~iq09mw zU1+VRLxD$^v!{(yZwI~+o|3K_eIGbkpC=^Wg5+TTdQ&*rJzbsa*!g%gNz2r}XPRN2 zWB~JqJar}pnIjwj=r8QMxRl}2?ZRy3O%+R9g{6!oG|+Jy*US zG<+1fpIq%lX7+R=4_+!?XU)>woVc6v_1{%5mf^w7{ox&qvl%}5&sbhqt9dlG|DVk- z_U@S6Lz4Cpdv{Fk;Yk*IcNV#aCt2*>ndKgyWU+Tg<6usE|ua%(1K4&0EPuFs?PAktP!O)ceB|FERSGxFtR zGA{F!zZp(kI;g$-fPI6BZ7WwuFWxW>=~UAfc>98|fPF7id%3mzxTS7R6`$Q3Hf5P# zs=e&^F29InCUuZD5$6DzI0pzU&H*xU4iH$J17zYHATUcXz#`580*iBiW^oP>SeyeS z;v68bI0s0?IY3|>dzfRp-YVuLq~2&X@4%e;@&z(%k{!tAR3Z^gQuzbK)%FA#Y5PTy zz;nZ#=_#DuZ07pAyK>I_uA?$9O?_4xFjfRB7L z(pDLjub-cBq8~%2KzfnqUbIb?!obA}ndsU1YR!j_665Du)nIJa`HnZOVC@cm%-%8& z9Xmv=;ja(OOt(*ufb`ZjN$J()7w5Mjp2hiXF3xX*?&AD5 z7w5Nu#rbV6&Tj*Y^V?jU-v*A(7eA|fY{QtaIIqaW*+ppAn6W$~wwrkUv`XKV`+az` zgZ7|HrOK{+ep#jOn<4f*YYC-q>)k1NpAe;Q@>`FY{q5vX{#hT!8YNR>0~$J#6)vR4 z3~^Z(wuz(9b&?^s4fGH1GOi{Ix2XQa`u7f`>=V_Wq|Nl&{H(p|H?phZc()& z?{`YT-Pe5q?m6TvTW}%`lsT%zVwTQUt@XK$X~a@^so~jI!@l*Js*iTQV&hft8mzHL~eG1ZR z&HPMquTq~CO_KgFc`-Nx#9Q-@Q;63Mb#8ynJQI0aLCterE;KXOH0HTejt{r2%4dT7 z=eALHf2GEu{Tw9 z?laYy1Y?a(_nG3*gPeEC|BUwquvnwg=T+3chKLb8H`jA>brwsXHBx7UjQ#=oPd(1m z<4iry)Z(oR)`{9Bm;qd_Y|_Z_tNWnLE{|ExeCoUQQGILq3 z$optJf->!>;dPFEaq9<%y;& z^uD_H^7Nfk7O%9*cM~g*518;)`E*IY)MUgkG5^Xk3*UX; zFTjlDkL~wtT-JqSDJE>1UG4klNn^r77mmI|`8!Xy5%-fUISuW%ZGKN)xNdcbpUbmz z^9A>20{i#K$ZwTC2ppYkf3}?H0w{^yKeuDo0LsM zx4b_mZB8-YGo5E&ebYc+)oJS@w$?8vuwRk7to&*Z;P#jIS{hY{JL0IxWnDn&XD}|J zb~9{9>t4Q)=j6}8NMTx79ab7jH;Rv^3*Drl8)UEcRW&YM-hGA zXe*QQ_%Z-meFE*Z z$AcDiRKByRn3I03p?rs967$b0AKL*lE`LE+Uz+Q^4d~+g(nN0`S_JYB^!KN|b{q!z z2bA)lykSF#w}HPo(mL;#07o3LrQUbo&Lz6r^DSAl9qwGBlSB8CsVm^lB|7uBam29@ z+_^+2-N;LNy@R_4>B6B!&0W=fgLFuesg}9c@E)gAK9yjm5-?V$zb~4_Qg?#yKA;|v z$63vraA!5`b>|x^o*Kr1blu@}yi+o`SBE}ml$&R}KMQ0_QOJvb8&wi`OEMFG?L7^2 zc@}EoC%uV9`lYy)58qNHFO&SPOdh^5<2c|{J2UakP2g@Nn)`HO9{%^9}ri@8Y!??8;ts_5EWx8`QC+i6LrXYE9BTX zDjj0a$PaOa)>@;=hjgP}E}u2z0Y>lfDET4XIBN}Ttkp#2kGfBTigM&y4Wvswq&~8I zV^1(j9+?jqt$9lMp*|%Ke3o{Jp_fbteU1D?ri*%@K2$!W8}*96fnHH-M{vK0d|sv- z@&gO|$#EL+Kh<}}IvYp20~_mXz(3P>Vx0}{h%tN`C%)T0dN^wv26tK0?UoI!TP_FC zYuuhotnfwEuO5B;jZIGhYjG5F+q$VN1COe{wCJ@|tou0CmmZ%P#HRIdgL38#Th7d@ z;hs90X#6=A&@m09Z>}3*Y1%;b$z8|Tv-gockZ$v~GF#dMzITQ$uh4~cn4-$T_5NAj zJ}n)8Jo^N+olZ8n`MDxNuIsOq6Is-S zZ|^e_>cX6Poj1SO$P3bU6f|-7qr-lX0m~Czeq83VH{N{0H}wuRw>9x=8{0yeZ-c;^30=|TkY!mRSeKA%x^mwAgZzK?*=&1) zzxR7FVcbtPNc+URZxVb4ht9m#n%Gx^^%Gh?Xa&jA5!O}ckXl#B8EOl128AZ3{w>~u zFGeTGME8a52cBNVnN}P;2{_Wlo9;Z4A2?TO6YX4f5cs#GxL^FDTTSqL#|PeY)Im2U z^&d7m53PH43~>H+nQ6YRyMawxlG2AKUjWz1cator3HK+{LpRovi7!;2@K4eO>-A^3 zRNX$LR)m^k);(iGns!(Hp8fH+0aq`o{?KaoLd)h$s(-68uPAc}f%W`BvbcT2#%@pNjN2olmXGsqCxWdhl;2iDtZjnf6l?2O)! z&IXP*FLF?Fn(I4RN{f4krOdP2XJO0lE4@Ok2C)M>)qJyT`pxWEH#NS(_0}u>l*}ln zZ1vQOkvGZUzIwXw{&2E#lCo8$qd7>xSXJiqUC!ojTa9`hW?OE*RsO9w--#73qw>&V zgIJ-Bs@@80He2igcVPZM_TB@ms$6UM$ASgBV8brWhEzKzvG3n~^+6c9yWHSSyZ0)I6NNsa%Bg8$IA@Z<)$-lvi1?I0h1Rx z@g}Rc!#!>{(T-m(=|E)Ln~%5QdumJtHrZE}j~}-R_}OW5J}P1lFt%a(l^neECwNXl z2gMiTBP(+z$ldtvCui?Is`ISbFisMjqWaoMEqot@to>bm4m{vXuZLSJ)_ z;x)xeFq)+NzawTMi>{^of9pa#yV^zNf6}rcqxE*5YsJGm%>|!e#(HO$olBZ6Q{#O3 zr79$Bof_v3wrzDUrl~egTR2M}UPke|19jQ1LCPn4voB_K7pO6|W7#RT{*@{C(A&g_ zmwfUa`ffvJGd^U$A#^ zlje3rj*Wk#&A8vq8t3F=lAl0(Z+V#W)9(|2uTQh#m-9{quGrn4kFRL~JbsyookrFH zpYUqVyzhu9;FD=Kc6{P#^_z?P6mv%F#q!g`qMJo$VB54`wWXMC@(di4(AA znAS0i(m9<~^Kg3V$Z;&57sz}y%{kGLhMs!?{rjPCCAxcpC-i&67o})m^9{hiyXU3u z({2LKKl_GwoHT~}YmCKylFvr{PHo9Ci+paTd{yUNC1Q6``4HQW`DfZ7b>Z0ee`9e5 zA`$0)QhA*?Z;^=e7JBE*kC@~kF{;7axcq*GPA0A)!HGZWSxZh z>ReZvE8@JakcnF3EZNnQ)FGAOTG~2_lsyX1-|5GFmxxhvekd=!Au|n{@)_FVCAth)C%Td$L`KN z_nQ$gSB%oz@xx)ZpzG90YaSau9hm-Bj2C>vfJbG@$qOxi3cPFQBbI}jfKN8X?P2$h z!Wkm;cd@VIS}oYuL9dJT89V*nMb16rw>j}1b{j!gIbSRCw3dn?^Q^0)Te4aG1~oXa zOdtMC{l3(-Y{JHUP`Rm9GnX>o&*iw3GbiW_+u2yfUF&0v__e5SOqR#?7IBvw>?@;K zezq5`x?S3DT;(c0`nG+Pu4x5r+2#Z4wm2M_=T|k;dG=2>saWQYC7$&>d_uO(;#1T-O7y%#x3qyuJ=> z(cvv=G++ImUS5zymbF*Er=bor$V4snNX!0T*=B58dbqpst3AUqtK8K3l1z8YN6qJx z_tYob8drgSajiX`WympiYFoZL*TT zs8A{0P3{bJnpqYn{FFWL%^nj;(Prg=Uu=mdi?q4r{nwVvE>y(^FAv|%|RfAGwaHKu(c&FpK z9u7+8a3{Nj=+kR`k1YJYk-9gd zdKc#PLXW_h&sEZj7wJDAc!i@KceSYo9MjpE=Ndl>?wwqNocWGro-i+A8-A3`+!Lzs zeVyunUd)G|JMwJwD%ddSp)+@@_Z#FKusxX5s*hzZE9T5Y_RRsA&6hayvD4~7yZYv^ z=PrlK6WMpqf~|Rl!ZU$4HYm#d4I!yEOWy>vgt`Y zTji>Lf1B(HWy_t^?|VmE2Uc~0dbYmKWv;$pQFV{J{hCQv_kv=q_eaU}5a$I&y1xKF zV{SRP65kdx0DNnEvot?*avkt&yZqei?iJuuQ$8^#n=H_-6E4SCR{ui4O`{jF)(_QM z;6s&0tVeM*pS-#ntzURd%_q2Bm@`^0Ze!V(m3Y??ZqSy|eaiAAqe$Qr#Z3A60c2B^D7LgCwi;^m~Tr_Jt>$pTd zGpHug_%s`9b{Y0|Qd+ZPLUwh&JUx^5vd-s|`dw(;&7F|zm7xCPE9*$@ zYs$Ad9j}uoE!8uQ-ldG`*ADMMZ_mp`=swc}z2FQO^k#Rh=+r`Zix< z7~63roT=xD*)X^KH?;+~>#y=svCf_2rgC~Y6D(+yyUO+1H8-QTmaAB_=^P_!c}>Nr zp>@uXF+Ei5TB7+ zTN3bZAF|O+_0+Q@>yvlMmL|DDj&bBZ@_D6-@f<3Lk`v@7LXd~$z9%J-(k-+tWw7Uz>+L7%qo1@4iI z*xw@dNTlvD$86|FHD_x3g`nU6Z}ututbW9K!Jjcc4g0TB_jkeXnqmJ{#gsW;&W*tT zFYLb(>pLRWwlF`q#%7^OLqEcJ2sl}ozR(>8e!tL)Ce~BW5PcTdQLEziP@ZY5GkxsQ z6=I>5tH~;dgKfr~(R!u)ySb{t zv$phbt0-f#?V-vMJ?_8IrTsgVx5=9~QSYkdh^qB(%T713h4~?A!xL`6`G)lVb+Jx#RryKposPU}-TQFwV4qQsHy$93vQ28#**tT`Y2e}OSqWo5)|7rb;k}40Do;tIZ=c3~W-v?jiw0lYpI^+Z& z?rgrBT&7eEhL03+3UUB|}Gkatm^HPqKmB|D$gH0>aE-(Fox0EVL zZyntV+@F@Gr{+xrITL@YLM@03@a1}rbi@U<$6LhP@;-xp(c(8?yf0l_UqHDQmjY{X zDd@uc-tl??uOp-$v~J>ZohI9&)d$-&IlwsX#qls+@8ES1jz7h^DdpVE|JZ-7?ZKu} zueJvp7{^gUZ_2ru|FQ2~?q`?R%WLtvPyQRl+ptd4+6C)0$=d#T@RcSXSknvs)a(J) z>;#s6`k!JOL*J#Yl~T?;O?meL`UtJ*CYwUMuJv&k1Fy4|;uDu_2KJw1#e2_~ z3v4XT(sdZoANa4KVt0X;<0rFY-bC81pRLdbN5^fo;S5Gi|`W8nMce z-){OC=H#bh&RO%N@ow41DO((QXJ@sagzc`xfB&rZnY?ITh9^0#C9;mwmi#<4^fK_i z^`F`1C2GIQ7SH1>DQ_Vv>vX&r!FH}tIqiQ+uQ>aAk2t>``T{fddC=8Px2F)_>+>7% zflrovbLIuWQ`_3{d`+E!%lkTW*F$}wj~3K&<}2(c!*9W)s4CpAHzCr`9(OGGsJ)AT z3)L~>bGce~_*66EPv?Gz@`OF7*pLUNf9jY2=%ZiQW^t}JmFJYp_KI`isW=xNIRBXo zM4Sr`z7^-f6LBs)us9cIn{awIf ze-{(`yMV?1E-vM0i2f28Lb!hm$nW9`?d8Ev`bqz0c-0iU~Qd6WgE5i7qGT2 z1J>4Sz}h+vSX#|bb?mhGoX523mx|gGIg;s!1=5Ms6_w%&?4ib5i zJ*QWLKL>AfroA>)gfZ~a(Vo8lVg)j5jIyQ=>}LXJJzazb+a3VUX!)JO*Xau$RCyK5 z3u1H$dTnpv>I=R)(_ShMgZl_`TJ_6Yl%`9j$ATXkF04qa*BcJZA34z6vyFl4zI3Md z%r`(zDSwy~^lutq^F76tCQ&Qn$-8r26e(~=B3H+Z-O7N%^58p z>q-xcbuJe<0kBi#1enMPfc+vTz(h^}SmXql$O!<8oB$I!0br36NDw&zV38BhiJSni z$O90O#{kCilefNLFV<#<^3}S1Z0^3Iz}{bGv3Z59f$cjwv$!@Yw`MkeiaxxWk{?lE zjLY&*ikFdlx>X748T7d^HspD6)h}3AdRVOGxme4?coS=RF4pqEVlB_bS{}x#Sj%&< zmWO#>tmU~_%Y(1PTAquwJg`{HbFr2OPD^h_=yEj6#W(MH0D3WFU3sgEcI8*?y0k;s z-&5tm3TLj$ckVNSdvkMkN4_mr7LarCdIeslRsgV9VhP?a-*(`PkSWF|7jp=czc0Q% zm3VOT0l@uEI`XiYx558YjH>d%Z%TumYu`KY{iCyjJ>+l&?qWF__;g$eKA@qp6Z-*k zM(Dya)5C7#-|Lq2R&ij(t&T3<+P<~3y^rdhiHi9z6mw+^Yb#UzD`6v@@UFs{eH!$KdsT!M~%keX{^m_93h+6-y&gVtmm{fxDYF0+Xw}SF{ z>%3!Kd_Flt`SZ}d`bh(o4cKPP8Lbz~PY>^~tw=AO906l~qS%{b{V*G_*;{8yS}cKk zX#cy(_vp(cWK@pe@Y{<<2gu&TMSu?l%_N5hsJ38#V$KL%_B))|yRK@#I%ceE@Yc%o z{wKBGS!G?8&VLXIZ7i9i0Ij*^67a4?pGf)AS)eV$^BpBGoeBd79i2~nvZ=kk#*3?w zVwIFGw-cju^~HW!d0)@F>!t5GK=D7Nw}Ags!V0QqC8byENp>f-|9R-ksbppk8?f_W zKP!?{Ta9`94b602<|&)Qca78UZ>$*m5c7|ckL9F?9k<%hM=hri>F3QZ_B6SJ74U-b z;`_P{I_qTl054}+!ekJP;ccJos8MVM=+keFZ0Oz|p}=LPnA5s55`aJF7VjC@J_b(9 zhK$y`?0gk^CAv1)fEnwZ9U`6qohn0Q8_UKz(@8E)(BAuE&tVy+_8k7z`Uj63CLdN5 zrc&m$yzfX!Y7D$*YaZIK>21(u=~I$=ty0fCC;H&yBJe+M3+9a0i{+<>o8QRGUihgsLSy*kA)uI)kzhZ7QWChDAnPSf2Vh)GC z5OX*eb2#*on8Uf4!-2&d&cz%KEaq?~=5UZB=5QwFa9}ZqGckt)i+P)g-$&q#mM?OQ zwMG6JbYaGNnYAr%W#bC=mzz+I&-Yyp9JI@nPp)$s_>g5LUMWuPsUA7;0$X*u0LYwH ze+@IuR~ES9j9x6Kty=eaZ@aEvcSo(!ex|N0d7OFnhy`%JV4fh+kUeIXZ4xNiDk2#!Q8f}d2iBqJN9y! znul4YvHI;T)ckz7ejQzc_Fc-hqe_#U^VHlpaQs9PT~FnmUgz6IvfozusGq4zu4~1b z5PXXn`_u1u8Q!a&isv20v*4n>>RIp{ckxZa&+nige-~?CpN7p6WIu+A-;@BO{m_p; zN{)!*n2cAXe9X6U*swg>Z_R7F{`wxnmCt*X@1Scez9A*+PrOx*wCcBd*7Lw}9WU1NF#hE_UaaSVopOqZ>$B> zNy`ua#z^*(rY@g7)Wv@7JAwqJ6jdA8kz zewo&(5-m7?Ao$;PYbmFT2IpgeKN4O0GWUhs30Yb=@JsB)+KjR%vL;+cWGUyeP0rgNC3a;Lc;Z;XE} zo~g_7OO0RXzlwKICELXeX7LqN{k1D%*{+gG&YrC|SfgD^zH?_|PA7jSip|6v~eAwr91L*6E=JwQPo(+?77X4;T*Tqf;wtZHVcH5ZSsJr<@mnC z{NL0@aZUsk=cIt&%Glo`g)Gz<{!n-$S-n&FEmyxGq{%bow}M69>Rxy$|CAV5sP+!+ z9vOW5vA*kaRc`TRAWLke?vWfOu`IBWx<}S`xxso|Rr2pPFy>7&t9ujA1DJmW+wj<4 zo%0ImJWh@6A%n8e%3nSb7?Tc#>43s&Y`;8jNk6Yx0Ohq`R-uE6)dH?t)0tjasrHib zY0fmVV_O*8!|vJ9=D8|?|4VsT)0q=z0&j6GN_U5=_fN4Oel>frZRugd-r#@l-e5!D z8T!ufK1J$#=!W+xM7(5p7e>WJX}t?0p6@X6j0|GSbB{i(B|s9JtH%LJ(JA`N3n}u|prL;&#jsSdnO%RInV!<=~oOApX>P~@x6JXHDW zDt=CU>j}M1#yMD5df2?;b@HW+dN1QpzKvu_yox7RjqxLyS}4B-yv{*p?^WyHOHqei zEFY=$@7qHg^^RNA`Zw#|hKyQN0l!sPAI3KKR5^{bY{+Q6A~(oHZWippjP-8wTSrVk zsJJ)Bo<3yacNGs0%zI8Zq=0JIz8e!0=6zJ{ZIUGyyC0?e@O1SU_S9K@KO`e$%DkG$ zBY^!PcTGg@8d&76iO5|8i`+F4xocpNyVi-^HL%EC>qYJwSmdsm$Xx@A+%*%qYhdgX z%o(j0%TEuB=P6V?JA<(;p3zY8j0VQPct%6TGa9%r#4{Qyp3wk{XEaniqX8DrXsCEb z1DuwwA0@xV-bu_ii}EdIEPqIZGd){ht(V7pC1Iy zW15vVTJQn*H`6O*d~kl~JNxBp$kY$&osJ``I+MD)D?|B!UR*b2h#I$>$KOgQdq<6d z*53-VN+xRD{%ZEfIVxMkWZz4bQ!Nx0Mhd&D`6p;Y9a1h>%}ettN9YzLEC1M(FQ>1cp#0OO zXh~+ZUEL$N?=b&rc1nBj_f!5i*1iQz<#pQkqJg#VNCRu%mj>3pI}NOTkDAD9weM5| zYu~R1*1l^E_bK+3}tasPX_EXPR2FJVVK1@+OU{+bO(O1=J>N1h=HcIdH zlQXSdC$h`xlfsgkJzk=CeYpjd-ky0ht+eU zwoj(8GV|2)qqOAr&+5eA9k~EwCf}V(+^DQO$ggm?Gx4T{s>UUgh!;2-Uy<|h4m*F$_t$}heCR5H2 zm3IHHjK493S$k)k%Q3FKOAh=a-+51&8>O8ooY8tkjwt0^W{MfxfX=9;=&W0c&bp=O ztXuGNiv54}T688aO%G$6)5Eg=Qoap^S$j_(;tlN`a3=r$1K-F0AHQRk(RyVY_J`C> z{We@m+p(|EdDax2!A;Q_+!UR`P0<O6Eg{!`9IPm|FZ^fWyz&U}Y@QnolFo@!^rQ*lN-)y{~QF#`Nw){$lM zZ<1wQd5z?>bY+Bman`*~oO2I)<+=AMENoy>pJp3Nu}#>_QfwA&;j%q{w7H$-D&3sh zY7ghpuuBQk?kf3BmS$u5uRB2f!&XC?&$Wucohz+l+(bPWbNhOMon2D^%CUUh_Vh5m zHk~Z{h0C^R{RMN2){nrNUSR1b=`UGdWBA=n%Qhi9RlaPWY^S_dwp+Gevh;`ai)861 z=`YFBf6|YVrC+6gCF6DpnOw*uvRugILME_~$%RZ{A(IQ4z(OV$G9fo2WO5-B+9K@d zvhV*WU-*QljA7vuo-($z`XE#Ify?nEuhsZ}l9}oU?31(@+mjyF#x3-tHl9;hj&oq` z{sPwSJ7Dd81WwDIA0;2RMe`^4T=O&be~NALzDu!L-jBf89xSuxV=JC`P_1DzH7ds0 z(!C(FY}K4xXY&+T{#X86_Luy-tS4DsC$E=`<^NT_<57Z^Xt0AwIs0~$r!}0%10TI( zPmf$K2E1jLGi_Pe8pce&GS1W|Y8H%{l_l+Hoq^TC&Pyk)Xt6qTfW3wlrC)2SXM9aM zW~X68UP5{3*?XkSja*>!_-Gs2X|jqlW6kX7y;s#iSL?El^!Lj~!1v!c(GH)MfZln# zo$2K4Dv!}&zCCU4RvKiMU1mf3Zl3}iRM?!J{jLW-(Jcp!De)W_>wV;2k!~E}3+0$6 zMwX$yZ$&}*gs-ObQOGIac~MzumM-uABnQh(&$U=r_e!N{$04yG^FpKiG*9#u;Dsf= zlKPL;ey8PYo$I-})xb#hX0<$u<%T9gp=R?W}P$K_>{0#ts?`1ClI<*3Tz8Bg8KhFhu}a_GUQ z%uNf2aV9R@YvPPtF3!p&(r@DITrSSR1s3P}a&fjU@ZY%>%Ms@Wb8&t! z$Q0)ZGjXmkm3qZF!%Unv3@pwcX5t)TU~w)n6Xz2Hi}Q;0;@o0jagMQ0oM#Ly&Nn9F zoMT{dt}+ql5Ci{HdM`ijMAjUx3^rgc5a>yE7O4c~^9PS1%V~u_*^KQ^t3HOT8G1rND z?bre1;qyIbdXb-n`8M3sfx3s~W3rF_DZQ)rbz(<;Q~t!fCSZ^LW3XCZT%G&TrT!H) z9_TxB;(At%ndK#?l8aN+c-RuNmn^TV-ZdB%^qPzslns2fW?EkQ+Uh3wq;5oM+V_mg zam{^Li55NM2IZ%VI?-K0XTU#I#XHn}w=VvZf3UB91>3N%JnP2mou?>YSyE%&owLeU z*L9`Hfk@@6D)!TeYjNePbvcvBsW zo?m*MAuU>(LjCWi$>i{`Ou)KZ`RT=cmqFL@-sbdq9zAfkuH~p-DfMnk+3Pm+Oz>nV zFJt|gZR^oXt~ZQ4XKrARFM0!S2(7_BpBN1scWH7$^7|0rTqZ?G6{jHJ^MOmrriDJh zL5@#|NndwWr%^H5BUek{YsYKQE;bIp-W^?O?os)HOOzi#dmp$+q~4@0BWQk+^OXE6 z+k1Uf`Pj`Phr6aM*wGp z94s>}mUbH%jR70ZopNB^O9TQpD7lGknWfqyD)5V2dqDY~8J0Y#cmrVhU-@q-LHj$f zyiQ&(%cVRiSF+UO=rAKvl2#6Vr_~46k0&DgITSuLa68cig ziO`o)p9p=xLJm!lBji(|56b0#<-es3+TVfYbwVH5Ddh=$z*5grmzFlNzE;j8YxRLO zIb4=&@_{wIz~WER9$=|Q`bE~4dZfQ33;$WA^q2g13Ttgoxz^Bk!ZW{e-__UWVN+^#v?Oqg9errY z`LDna6H5BfXKpKivo;B$?=F}Dw|f{u;~cIf{Lw$ySHFU7*jE?7WoFavDPMVeyXcne zR=!$vq!&4Naul?E!o~f>+*SE1;!#eTZ$l?2pI6hC-U)I6PH5VkjtDOfe8b+Ie*W+T zd@{AFFC87e2>74Udt-DXeU`22x6-0!W462aXfFGxQr%d##dH{OuZpkOtTTOplRb;_ zC$TMo`+RWb6AM-a{!wzU%)iR@cDLb~YM6mNyTbePt=(@h*_K^z{rIrVGlA>(3g+v= z?!$dLX>kbG$Ghod9jxo`$dR%PzY#`8hTnH17>6>ZFvMmVADcCLV9BeWst-Qz5L%b- znr#DIu74M9Q6)R@o!Lc};^^g)jbG_KS1OAy#hBVBpc$jd}iRU4e0bWrR#D z|F80Ci+cRn4QsITTKBHJ!ZKsvy01NX^K*$XR;>q);;Ya12QE7_gjXpx1;(x0wO}6i zbuWzDxNZJCw&7S9t37N6@k#Ga0AqVHTGy!)dFbqN9l(CfCDxrFE;R;0xmiPhvebX{XWiZB(L(o|4)9y zKK!@XkA3bCdzKU~HV}N$rT!!`-9+6Z-qX(O_D3i`FL~QvuMboHZ@I5Kd-i!0)c=xG z&xSqn0-i7+3op2}8!#SAKT{Xhn;w>Pfgv6<#A9L*z_>NUV=6b8(Ydmb$4Bt}nbdr1 zzcrZ0lsf_QZSvp{-f#9)_??PiU#t&}yYdE@=WIbcEivb^yl_KD+GKZi;C1e1wD#gQz*j2WC-r0d z0+*`0jNBUG1031QitJpi^4J+I|5!v24cnUw{EWHDr4U+qL0-7`EoKE!{;e&vtMUUc z>RCt+yoq+DM~|ymcXQ=Bv|-r_VE^RdWoW6Y876R9AdtZjn>tL@?|+1@prY#0e3yylmAxWEBI<} z!C~CLk-9II>jL@Si&dap#&jvqws5=tEjCL(7J8AydXD$x<%&+x=Y6*q_TOqoloQMnG)Cz3Te zz?ytuO)s!!53pt@ux3ASH@`AbLSIU`PS}xBp9uSag&ZRE0Soy==mVDjmH*c4A+nxk zClUI9r97bz?3a2jnJu-Jb+mG5uhf&`2dO8;Kbm|d>uY*}HG6=io)rH}J<^Y|zVM%A zN`K+LOAq5~)5GHfzUf`t#)ICt&E9PGvIt;YJ~n$KyU@PlpX$_lsb{VG?FB!iReyi| zBzE3A6ZjCz$JcfpvXyliSdz%LV_o=Koy}}^cIyPFlh(DB#?@kr+Qveiw60zIeT@Ed zJ#k)+(1rElYegMhN*$~hUn}a96kY#^Ye|aDXL{i28){CzdeXUCwGgvRaHm&-&4wi$*wswy**+<&F4=nF3 zId{l%ZLR>;<`7_QZUO!k=BP?*0q0_D^ll1d@Y_Uu--phn>tsdbuFGN(z+JU z6<9C67S9!iIqKJmqYQJDijDDa5T1Y1!+37Na|kZS^9HVi=ZduIV9b zbCilj4Rh4LD~>X(^$c?qp5Jghlh*u(e5=?Mcv@ z6xfiD`t!VGh@(_4%P>c&+@N8t_rI_8p4^{dDd!fM15U{~YxygfXSBQ)u$J!v*79J$ z|1Zx`!hbT)#-tDN{F5HW*QST@8V#?-a5-Lo;W~!3p32YTx$zG%m?0k}#xRb%#P~_g z$>VZ7whcLR!*e~Hr^0g)o_}z;VUAMI6Y)9`=Y!q=vU4RO?; z^X-N>O6}wQZ=R#X@ApsHXKvUZWmxN_6$=^m9;h5zTJwzXTk8Jyv|^#OuElG#w66Wt z<0!)%<;e~2!l-v=@LYlOU1DsfzDI-S88Nm~-@C!r;`Lfu*W%oDTGtxZda7RxbJWj? zqYOE7LmY+YH^UtD@7*8ueEbCVxRLs{PkLB>n_K)J_U1f1FTN$eReev%v(F`RG|K=e z7jj67%pJj7bjz}-_qzq_QyA;QGI2SskL6(bSTD8*%S;aod#RKw_hJYesnmxUzD1zb zfp^J8TdB|uEPOzPZfHB!g=OM$Tp!E9@--VkFSbW(JC(L+Z3ouc4y@@?tZW0;bU_=j zZCEBQ$MrRv|0Eyl#r9yC>0x0rmv+l`MPx0?OMh11PCu`E!Q4BzL3u~>b*$4W^=*x% zy$B1KIvUEy*%Z@PKBK;iva01h-BWk4kmk@uYRJ23JamiZqxp!!%2mXGyfd!&uBp41h^jEzUY!Su>d~*4M886;ceUBynLsfo1zxp1X_l34RB2vvK87)6?e=$BFwguS3&)4KW1?_=H zuW!$z#^nX}9XpVl-#86@*JHmwcRfA^xO?sp9x!AxjN50HA^d2YXc)H{Av3z7G3~v& zE7&uAa00oSLwy_MNa=QDzzp@x5VOvObe`vw|KCi`!LIL6-xzsaa}n#)z!$FVv+ohR zw$B|H+nLewg)S=mOy&4LP^}g{8)FAty>SP+E-Vl5E!#mf?3t_0J-xJ2;zo&x@KSl&s{7a1*o2i?II)gB6V+P7)U7MQEK_xIv=6T?Z~%vRo{a;Fr_8mwX`VI_qB89gOZ=XSn|y4!`rhJz^zyypLwbrFmCU! zW>0p%hIHg}^(~;YnQZ80WA%Gvu_p_iJ63%==vwo5623;w8|`N_C*|*|dE;n~cP<<5 zD1Yv<&Bv+*Du1r`T*AihQ{ODgX!&^qdQ-i{dl-`zX2WU6&?w-Zn*!;nx|YDr#5bc% zvZ!xH`Q95%n=h>f{bD)Eo9=F_&hiL!>PgSn{|4pQ=8TpvbaCN-xJQKlx$r-*@IM#+ z2NwQk!vDa+|4jHFSol9d_#asKp9ud03;z@0f8dOkFZ{!W|G{s<|6KSVSoog{{{svE zbK!p%c@GNzbK!p?S@@p|{{svEbK!qrY;#7-zmca8A8Y&;?7ZtgoZqM$32b*OklO~A z22T7G!uvYAf&H-?MsthqwZYE#;@&)9K^*YdMLqa@TO;uKi%ku9m1`Ej87+TZ>ndbi zef8bBdbRWk0Kn)7Rp-{F$*Liyy4RSs5ux0<8wKAgjR+|-=^Gj-LB@uu+; zH^P`1F<~?fK0<&k#hD#fb6$rr)-OJYZg9!LWWUVI=12Wn&Ii7kqd#4+;TABqIU{5i zUK2zo&Nl&F*OPtdsgDuBbIZHaM@60jXNzo3YnD^v#Jy}4dOEr`^wG!QT$Dw31nxQh z2#M&Zz76hQ)srkNs$%|(mY?WsLyuop-@7v^nvIq&sA6DO($@h zoV+=NCKPB2ewa8tm_Ff`!4K!__|sN#Di828bi+vX#lWwg^4WQ z-XD1GcfG#Hyk>-!ah@~x3(;L5ReNu@rcfiK<8ql>+y?(1>3 zAN0@5sQY@sxoK=(1C?6{47|YV_^KQ%w*P19!uM$ji|jPnvkTbYKjIMC%+&mOpxQ_h z+CzQA-)Gnko%a{jmdH1g^~1#Z1hP+ePVU3_4mGEJJ(a-ry;a|nKX09xyA1CRb$+I< z9xH=s*qpO4PEITcp%2Uk!u|W|(E%xcB7}RQfr~`O3V+6*Z@Q z=xoB{`gMZx`@0XZlRF0kiyRaaIWFLgmf!MtD|+T`VbE1N&Yk*Xe+>3NGxed_m#Vgm zSr|xrt+a;n?_y0ftEdsg8(pdf(Mu-_Guf^~Eq&>iWOcvy4em#q+`a?lINtb~x3OI*aP&wL#`kXrT8*xb2S+^uo{YJbAa3jfU)tDJ$ zyPpgl;i>vGJ_nsYq%&~t0hMTk6#;%(t|@)rqZBZug zk;VaP4RVFgO$dCa=54mjiQUbv)^RzV*0N1U)mmm$@7HWhh+5+mA;tOOnax4w;Q=*y zm5D0n{PcM{o;7~~DF3JQ;`!m`^=j0{#tH0+yWERkpKT4K3d z`9H^^%A{LIW!r!juC>>FSGGMVWX;GDRbJR<4NI;+9OPVR@rIqFs=v0>EXj9eSFy_6 zkuJO&wS_u|Cw1hJak+qhHG9NbgvoV+9JgXE!sMDnvRI4g<(fpYSc~Z7nnbc#ix9ac zku26CM6O9Bi?s-qYZA#~EkZYoHHl=gCZqDVT=LJmEog%*CBEI^Q%^4w6toOOdCx8tipTI>v0a)Y{ zxX32}i+lnX`2?^>XzL<-+$VY)LF~4y! zzX6N+jf?pWSj=xs%x}PAeq&;O0~Yfe6Z0FenBQuP`3*QDWQy2~i#U+WaW3LOF5*BY zS;T={#DTyf4&)*Z1Qu~17ja;MtRvz;F5*Dw3lRr$5eEW`IFO4t5E$G1Gj+*apwunx zl(|5W69ksIK#>y!mbpNY6NGljT%gDa0?S;W$O!_=T%gDaLVIN{P~-%mT{0Iaa)Q7= zQy2E9$nSBH-vb*&-j9pCAF#*=a*+=N7I{K0@`PZ&$RBc%KV;G;A_vGtUJ)3}#O1g? zmV@PEz1W`2O@jIN$4_Byc_Pkx|8~a~=A1fL0=R3N7NB=R^iW>dcpLCI-<~{k?_}Un zn;P@34rQQ^`aG`0k8RQcyIjo0n+#ET!giBSG20UZq1@AE0&C{#4~+HVa$FzF!Sbo2O*fXU40g|Vt${+TK%SI<}RqJ%qE;iI>x5_tW z6X!aP5oct|eo5%njrzV(>si}jUbKii2cJxwJ&K+#-xoNaw>Z;e-DL15){Dz=eJlsd z$9l0n*iLLeZkL?f#JHi-W_hp6wVz};2go&{WH~p;wW4G>XUH|AWI30}wWVY^$H+CO zWI6Z9wWwq{C&_iAWULF9qSl*Sme5y$aMpY95@p>aA1)e=OQ-_jN=x}86i`|gIvaiay*DQk;`~d zvWOqKj3XtBxRT5GQnH9Qxr{p{i#U|acvP~8Pq~a!C5yO~%b4(3T$gVurl>?QFHs< z%_g*zZ6_!{*Z3&$t*mmGK6XB&&;~V^9q_E*91tBln10A3Vs%8OM}^LakAs{Fz`XDHuY zzb%jPGXms`2wW?l_4UG6>2yejQ8r5`SR-p2u`|cBvfrQSSlzz6;e@dj7dH zyJ!~xb>7sEXJw;@0AJ%qe075!!2guqJ*{^Uw+qUim^IDG(>uz};|W=GMQekT7v-%xwuCxZCN9VIu^cQP>&5nb^lM48?JP=V zUmPypmxlI#2xDVxdyyYLqt*r1F+p_Zot#kK^I8ban^&blmZV!2gt9 zaSw_;1INIAkF6u<5HaXFvzOtkBn}s^T$+9Sd~p+9=LBx-U6BO~q#YJrl_097CWjv&vE3&Jf$xaW-u*!ibFq!w-2GMvdxG7t&=#CF1$O8$-blQ2h*N2j{p|bUb!o6dnppAoCgzy*R!l3PIn~dV2S=C;S z33a^qP1n8PpH9Ku_=LS#z=zj|HsGJitNh!{)#Z7v#dV4d+4h5v}~Be3u*5$y#2 zr}S3nK8wxT=f~yvyr#RxPMdoG^PL5_{pfbU_A?x~v1bk7$aBYK;ki=|q&P6?tqn+~({t@!H)F;5;ShEvY=#lmVw+<>3E%iw`T6|(oa&KWa+=o!{-WpspUknRv%cCBW0z?1jcnVnNVNK ztkc&h#aF4iunpKYY%^|)P?y?9Z45wLuup`qY>=-~eTaQ4_XX}F&6g>@;>cHW z45avq_gYv7-Ye0@K#H$q{S;qG8Q>pHKCq@2ShELMvlCeAk$x0^H@Z00K1%vgvew>| z`l=Sxlxuzi*8B;aR^Q<|_*yJewn_HcA8jz)cZU1UaNni>zQcQ&(!+Sa(|>Tu zNeR_IsF*XT%m&@yLW=R;A#=IuA7)%tip73S`%!ijlzU+AMFrHhcBjzPe9{}Sf3 z>dR+t@_Dly1L#`Y84RtVv7E455j=hQXM* zSY;I5o-hdfbJ=S!jVi3x<3qM~q@O+2-Xy#?5_3lAO5EFxuV|~*#hA0-smrTZQhA;N zwaf9zIaCfL@8~b=adJ->&qhWu?0gIL%noyUuEpzX%+>uz@+J`@z&{Q*gZYuXd%9{Oiel&@cSHA2)ZO30&2GAdks)1{kk@|IW4I8IG8% zQe&ai7zxKtV#vuD4}6GYEgXYsF&@+raZPH>hGRKwr&bPr)9M3ja$uZm@_{wIz?wb4 znw`K}j0b$B%SIXFrIZt?Pu@FP+yyNDnHmFYaT=6s@f)z#ZeSc^%UBY{u5`r0+Ubt- z|4w`;+mO;vv$oeW%upaNB9~q~X5%_uhB-c`oMI@bYv{ zWE~juH+N^FksG=IR~fpGOgf|XalLNVm&~0x3d$?mjL^-Ps-DA+NII|25uu(hcXyt` zf)A=^WSD=H{Mp`HQ}c4^Vf>6h#12fv5LAw35mPV`TL6n#gNc{}7?170b1i;8m>$O8 zib)rvII#Y-dfd9dHQ2xAHw(U9-vHRe&4`y7t>Tu-E4Q$GkB35et5bwoig&7|AC?7# zB^-OJ)_NO87bEM6D?hwQT0uhc_&}Yq)n1YaQ#at~0VTv9yk@}W^;~FZfGsfL9qFO2 zxqy>P4W|7j9fdgU%(0R5vehu)?EOM$*?rR?Cd59$aqPdnE%+VP^f3O0LwXp0=K=G` za>M!kYEckFj?f2k?|bEd-+l?C2<}64FSv_ z#rINP%~9X$X!JFNF5X%Nd_L+_Amt`yp)cl-8cu(&9tj*(uMh2C?+x(EwN2^5ttGj< zA1`*SOdGY-0T(Z4LVus4_Vx@kK1?#NReQtm_W>~fOdIfb2{606_|iL`i=bWC@4M4W zRUZKtD&CT2b|?nz8W(I&%MPsxeC}3WT4!*3;KH6~$e2EAZ?i?|v1Dhw+P}1S^=94S zT+VtZw_GonKp?1hN<6ANDt$03t+Cgcog;Vawl>OxQ`2=;{$?Vo;)Y^ zvG{CJ`&jV1{Fu{ot(b39_wS{L@ps|U!;KzT(&}PAx3u3SrarYcReM%v9qCR-&&>qo zF;j-ptn0Qx8}s)ZP1iiF3*7p32rcCs4fo4Diy&HmeNh-QOS1XU+0WFw7-jDFp*e1= zcNW&wX+}L?mVhzyWPfFP{-F!-?iMC=x|h0N#%(x6*6ddI3%38?VrR`JfwcD>TksF& zcExkiUJpA$dtY6sOgmpvZI3(Dl%Aia<`AngeW>w1HMfM-8cvI^UjzPJx-^iEeQO0A z@;!uxM~$g1`wPp&<+whUgXLqr*d8p??{y^_uvX1!$xWKjI>SnX{qK7BqCw`L!JgU6 zz3ImT>b;C=b4JtSdvs79`ZR>DT6PHDC1B@5Hj;MFKOAhUy?ZeA+jIyxVQObubf(%rvu6XP#o{V} z%~y_B_Tm%Y>w)neek>E0WUi$+}D`}4kjW|PbI z0uCeVS(c&0fM5Jpo&|=eTickt&?@vXdyt<+wKK$Ack(ANpd6UBV{{FUP# zX&au;G2=G=TiSx(HSl5RBbtSoS?uX6+XZm8<7c~5OyX|T#oBwIaof{i|xU7V*7EsaNCEz`At`I zx5~FHG7ly9$Ekdao7r`;@PXQ^ym^NiHSMkTFdy@(MjI|t-x=5!+m4!e7l3vhju=2K z&z}ch&79>=v-KGV+^lE_{ggiz=7jR%-R`8&9WW>4tm#jCJ()mcU-;)4Al5RMfbTqQ zOGivl&rC~=txA2SsAs15{WWYqF30t;94sH}#r9x3vHiGRxV_j9*gx2B*q_+X*yi*w ze#Z?nevhwdnJ0`7aHrCrp>J2QqML^UuYPXJwlr3G*R0uRC1iQ8@-t<^O~{AHAgF`o z;Bs6a%fa%oUa_`KeP260jNdcGjNhNNaT(3eMKyr2l=ox^zuvGEj3rzLm*e_)Z*zJW z?|;U8EVntWIzsKuHeOYeeraM4exsJ{Y2{}5fInRxKszO#gE8FH(VtE$IT85S;b8i$ z^C1}X14Z0bzWOw#bk>5U>g4FAhfYX!_L(0a}F;1@d_h!m|ndHu_{v; zy6b#nC?9>~6Itrt3;4jESdx^ieqW*=S0z)Pso$MmEjqgN`>f`fbHT+~rW|T6tyo|M zORlKC0fPCzsg2^dFZFvD8;*3NTk5H2+%e^b(gFK+s6J{lnvTp_A2|QJ5W02U0$4M4 zdlpDnRw)I2F}TfeTD78D@9Z4foBB3=59L1R8q*qC%Ba4mU4bqxq;lPBW*Jj`zpha3 zb6^iyS3$jV^l*Ml5_?3wb2NSJ6PMd}Rli)FZpsR`|8u|mH`$Ndk{07{l34}YT9sErX%t_*%xz;%bz?@*0 zDS#hu(;dcPZQ~*QYES~O_p5F^n~@r~ja(Y=mHjQDUB$-Q@XKL!fvW~)<9*I`0e+Wj zKXVUK`}y%VIxuInUi>`}%%gAm@|&#|K)cGG@5i%@y$u}xunmuSuhx~{S5@Pc+?}8; z6E+v&rZrjtKiK(*O+TQ1*UFkMW1WJ1p#0kY5^Ts9^}B|@?}0g^^`_@H4%flo?!YX5 zx4HZsmE&CeZgctjDp~w)bNRa~S^REu`Fku`{BCpkJ1rT1Lj&{Qktt%5)bDcUC+`PkCa;&n->mKnAAr24yq5M^emAZS{w|0hP zo08);sw6LZLCL=}&xNljtMuaUcVYf-Y9sy*YI+#Ilb9a`#mD=eOLY}L*#W=hHyCvdsd7mD5x}EiDJ``B|&Zd6v6!VXg zFMeD9((@7Vo16L_RLtE6hS0r-RQ|K!&XIKT6qOfktRF;AG(84$QJK3PsN?$F(5~Ev zYti-v?0~B|o72F~Er7??d`#*_x&t?{TSW3SQhQU&x64j+iOO$2iKX=WPAI?mOzpsG z^-^(QxjBsWS?mSZV*V9ulY8RC-Uav`#nxqkwBQw$=U+2tI1O008vJv#gc}VtRnJg* zZE8;2nHGn(WVvleL$lTb-sqK&(%kBK+?YNW$f$q;Q0`8qkP-*foct}v6@oafx%Mp%sHc6S16ccZ2e9@{4`A(E zAHdo-K!CMxgTOqmeKQ1D`<4hW_S>(Z7uygK-Ip|&s$%%L0SV-e@epX&WvfiIa!!@2 z$M0fePS3SsFGT8jE9qf;?oWDH`1UWor-09+!TctBluPJqHU8TbFk^LFt2qRp?SeV2 z`uMCO%v0V)Ft=|ie!kfyn3eqO4}Qky1Yu6Aep=%>t#bU%CgxE4Tcn3gf3RU`i$XN< zZEN7pwW`s8<4(XPFWb^rAu1m@b(IHQWpo9`bJCU(G=I{RKk?s@*`md2{4See|F)R0 z{w@2r@!a~O-b2*(sKXf3_Nb@MrJ)0}iuXBF-$iAT@t$_P*B$#1?~NCir0$u=d+9a% zxs=(Wg@t%Obqp}xlaKf6i)!+n0;q%c7z@3rdynzE0QemN{O*9%lk(n#Ru1je>H}+X z;NH~a18aJLHG6feSnpurD@F<=-2hB06m1BNkR7z2he zU>F02F<=-2|6OB1JjW;F_o-*`nDJTUA9Oca6F2pIyrzC3>m2P1Yw$@yh1i|CLBP{? zu-bREv+Wi&EKACsPrW)YknuR9E6X~+iB6Mo6k~tNPb%M>CnC^*ZqE4^uJ-# zbPs>jeMh!|!bn$+=@**(JJcPUBz6?tjW$fd2&9HTh4Ff8WzLI%%8ueUfgR7N1;`4{F7G z>RSKOHh3USfyOEQ7 z*{XMxOX^0BKlC1K+{>=GM}J(OZ3d3LBi_T)>W9A${N{;xZ(H9ln&z5q6YuBg^?8_^ zc5J+Vvd<|;=00vRQSXT;Aa&HeG{aMl)gXdNDW_xP~=y;rEb^Vnm;$4)t471GZQXu_iaw<{I2W9gxBABi^@-QoD|O7XKR(aJT@&n{hTh^t{WdVHJs7$ z{lyaBJ@?6l`-QuVjGvFV^^rZpLwAke7j(tMUBg=UHwq>GE$i&T~(g^!W+5ay+*41!sn0WF1hIlmDhaej@;+(9j$VW`{(EGcsqU9rKBvM zRjWUW%fxcA9>@S0AOou^1MWKslY5=o$GQ9TPgYD+m**=?@$DaqV{bA(F%zogV1$0}M0f7(5f z)nTmi*lGX7eT%AZcgyU{t@8g5O5a_O%=>g*BC)Y5Cu0!pgZ{|U#}UghL|y~=1}avxu1w!4+L@09%=`#ZKf z&s*7RVr+M8cWifTcPRtOx?(y;3T130^A7wT%GgL`jx%}hwN&o`vA<(~m)bhc?>N6J z#r{tE;P_Ln{V`?M0~z@97;xW@w=$k3pE~8XmGUh4oeSSwsn3#+c(}((d6wMWE9L6W z4R`OGxcxrbO~rbzyAJHG4=3Y=bnX+$`O@Cpy_d^*ZY$kGCGpceRFXz0=O*c^oLpCB z{3Q8NImxHW?sI3W>N_f>UgFQ6*Ot>1ML(3K23QX<2diH_xVDk~+90*7t{qP7yoSsD z_S9}Cc3y3`v>*0s70)BHUvu^o3NOw+jfy?n?04Ajkb$aWfc@H^^WF*eYwXu#Je1g~ zihc6z*Q(BTv0q@_7Gi+?8v8Y_LzboU?r>%OS5Be!$Z*w^6n`!)7!?AK^Z|F|t>9af(@WWUCKjr|(? zHQMCrW0R?iKduY*YwXw9ud!dFE&b!Rlyz8r>X7{!`!)7!?AK_MtB*~lF8;VK*srl) zW533JjkffU+fvqH^{K-hc9=a6@5|8lX}Iq%a^Gu&+*Z8r$bAn|Vh{D)tncM`@(I3| z74;_X?A3Y`U%n@8LZ0VUIeDH}<>WmuX&gk2_2uerhaK9(j00q+UZwEqOPxKC|Zjx0GDxtWiPwKD1Ek(TT5e zl1^H074Ke7uB+imepF8KsdAG4G>#;VPpmV_tOqji=P|(f8s}@(xnEmV-w&DmH%i*y z<>kF>V%Ms09Fo45HIn{SuI0WLE*bBH5}xp&ax(r=89!BwZ}tZHT=$nL*4l)+nrRRW3Sx$WV>_QUBGsS_k{i4cDK6q zcdL@kr0y#IN516xJL-Ne@m+ak*jtQ=+sDJD z@+g&8#&v^PC!@^rDUY(qY2GA$DxcSHN;H0WGaXmY`({GaY4JrWw>@ZNbY`PBRNnu| z-6OkOLmem2xOiZ+bFFT_lK-r93Z-8teBFavM>qd#u;%CP^}o!&{nCLdk3Hy`{H)gF zRlelqwer{Hrl@>t)29a9@X0il&ug)5?zA;0seH`Hdvnh`KU(Du3vBqv+54${{$`!R zE1%t5<+nfHD$MQQR^{NK;bFa-ng4ozN-J^@TVFZsf>CK)B8}aT;20L zcih)0&tVpMd1Z9xr-^OJ3#smW)}80d_)+E+5(l4(d9lo2Wj-%~Xj2vQXt#~Ka#def z@*(X%KJimU{@rr9<#p@9tsgi4!VKE!9Jy9i&+9wRdw!+PlI!NbZYi zyKrUL>Q%Dct*UwyF4^BLy`KDg>_7Xviu+}MYX82n`NY1Rm0~|vRXbT|JeG{Xv>$ZG za?o$Z7|$L1xnn|itmuv*lQEd`wwy7Tj?LULn>&_s+qgUSOY)=rnmbl>$B?VTy`)vQ z-RT@b_3P@?)wRoj%ZAI0%aY63a^?lPhU2p8GVHSLGVitpw~e@M$8A%|dat%GgjdX? z5x-)7jdcFBc`McoSBjlXI8=SPa$;wwM`v9H{8V~h!OGGj_4ViM16f)6a@(3KC$>e~ zU1D3(wkftnW!SEYz32&(8lL>FGHhTd=S$kKjk4E8Wm&UXS$n6GF<2ydaBZn;WAW3U zIX-dwf+`!IxNS|!CUq+A`PX&I{r&8CzuA@h&&}<;%{UFe;kd7IgC@r7>Jv_C6+UzE zb{Za>*FUV;zq`sc&)p+@tXl(>zj}OB`1n=NY5wcpbzJCgd7{c4zM2}Ie8YVM8jwaTL9amz+I)-mgW^*{#502v?yWPl8i0Wv@a$N(8217v^< zkO4A42FL&zAOmE843GgbKnBPF86X2>fDDiUGC&5%02v?yWPl8i0Wv@a$N(8217v^< zkO4A42FL&zAOmE843GgbKnBPF86X2>fDDiUGC&5%02v?yWPl8i0Wv@a$N(8217v^< zkO4A42FL&zAOmE843GgbKnBPF86X2>fDDiUGC&5%02v?yWPl8i0Wv@a$N(8217v^< zkO4A42FL&zAOmE843GgbKn8vv1EHQ4pG%qbKnBPF86X2>fDDiUGC&5%02v?yWPl8i z0Wv@a$N(8217v^fDDiUGC&5%02v?yWPl8i z0Wv@a$N(8217v^fDDiUGC&5%02v?yWPl8i z0Wv@a$N(8217v^Gc-T0d_nyw z(bKhBYWSR2r$ukwx5i>g@w4{Rq9=ErKX6&OQ2fir49*?(%L!T*R~~ZVdbxeyo~+>w z-~M>uWjjq(`H78Y4m^9OX}^*S#b313y}5&48LjbMd8>yfU@!@s@uT*)~V+Vydo&A~0rw-pf+SP~x<1 z(miZ=SAUiF%hwC1P2E%F#*3fK^=@*6%IAb*a?$I@tNd}>GX^#|dYa0YZ}8IM5m!%D z`NoUR%0D{xSd}NWdNcn>+mR~&cwLj|(RRD2T=rG3XyMwuRowH8sd%q`D zKKk-KqYuun7fE=l*ZN1jKHX5|Bj&e^2Isa{`Pz>@%YT2%K`IZt?#le^^Tw-u_RL24 z@X#qLe|6M927LRkSYIO!7@QmEP110;{=eFISa{33UMSaU`tecW<24s+o-f#AV%W6P zVJdIlV_JB9r|UHTHxHi{cDrJR=KuBACWc|N{WZ^SI(^JO;V#eA(lqzX?;d)GG*r3y zJG+FB&upynbKXwj`d2km`Ph%jLfd2$l^af8BRtjM9DLqB@%dcmnWI$x^3+MWuyd@t zhyHu%z)!Y~b@%NpPb?n$msodyz2MCJyBEj0bLG7|yqs_O@L`(HrsE&T?^$cK$`c06 z&YL;oRCeQ>7`>O@bDKjn{DC{Z%(uAZK$ZV}`49P92JEl$m`nX=&A$#+`S}q$L}eXX zsJz{TKGDq=^ifBf~3 z$TVmkiC(_jqgS-e!rm&MFtu6q(%L(zoV#s}sLR{Csr3Ki+H;7;+3@QR^B;aULgj{+&&s#$JwfH0KdhHOd{*3E z2A}c6fW6<1ul1iB2ItQCDYlK*Z+K6xW5c60{sUzueCmjyDmU-gA~B==^yBF8uJi8EI&AvY3E?*rV_SFU+tb3a7kR43IoC`HPiR&zC;6|r z)r9cX-m_wP&4a_+F8WYqw=8c>+Iq2F80T}=W838CH;vo%Cr{jz-}J{Zdfnqc{xaY7 z>H}4FsP1y>qU{oVe@*hL`95`oeJ< z9{n;cTr{>%f63>OvnPiy9NIz4^^Z~G!pRrSQ8~Qq!0_dtzEpYa4cmn^N43&(YxV6O z-gjYtmEW%2Ak5F*L*x8G!buH(03HN4rC zcjZpn_h^-O{@cU3waz&5S8}2FBY!$3+UV)&dM#HTa_M2wXK%l(;roBHNA%5%xV`t9 zmW##(T{ZpO;B8F4w%o@w3Qj z%30zr6(?h!DwFq$yktx}jW7OEd0RmpR5m|Z({=Nr`Kd%1DtnDem!T4Qsp`C^^^~;? zS>vVYrhc|M-TK+y;cNZwY?trXE6gJQ`0#f9zYcnbC*g4ASO4YZJ{!~{+~M6`;T6xF zklU<9m#}lxE3A9j-MO)kv$@3JE>PV|CoB=V|Ra;>prSi_`@z8av$#AE1dOym$1{k<8t3`)hpb5jhTsV&dxul!H;Sa5&$%A?cf!5CFXlxrw@q3)&VMc%nit)5*%EUeCypB~b$Inv zceP9F^S9*vf0-6-zRgeTO+H{o|EiMD-TC5E)AUn0-*R&F(sO0GH+xL)-*U#7Xi)20 zbD!UTTK^pu>XEAAF*-844hUH!7Ogn!19Fd@5P5VZ!7huo|Lw5>^+1;V@x%5f}>-wzZ5s${KV? z%bUt>9QRx|P4`-E9^AaSd3MW!>-7hR?WB%ZXL*AKxi-*yWN!MU9c9+T>dZig#(lz5 zzg^g_`?o#AEb_wtou*^sE*KlT^6_8$IyT<+R;f5IRZTmxe%=Y+beYAxZ!Rc zW|2{T9UF_TT)A7Hcx+s+VW05ydhyu!?|z@~vAg22@eiN%4(DDGkBxtPp?CQ7tbgg) z_|DsVhdn>ML&wIQ&+Z*|JZij-jZZwFci6Ai*E%+?-*ahQyZNl@>$YtXkBvVM`h>rX zh{whkztuZ*!@Jz}f{u;fxUTn7aTc7upN@?$-K%%##&N?}=eEB(m;Jq;r$qxEU#rb` zALRRImCxOIt<%!@sXQo|vrP3L=s*A5c+PUo!3+Dpdq+HH8Mgb}{&brPa}u0eShWs$Rtx7|2}%7wD)*c)ZPA9bQ*Z`29$5Rbi4SBp@GI`&2#E<)Yv z*c)}b2z9PwZ`AoB=t9Td(8VIum5#lkBQ1-Jx6^W^vKz-e*G<#CmYWARZ*HF5vIsZp z-uz2Dsms+_uB^?GKCUa)F4F$)&z6M)=w-Ip0Lt0xL2Qz&!uBYeK3C?-B4d85>n zNRqcKGVDv0*AH}nwJiC_I(n*?m3!Tb>m4yK%|jM>Nj_IEe%=}~szX}#KT{q#vR~Rp zw67CgNV}BvCy`|h3trmRw9k}qS;LY;WLd+K^(~R{36pcAEo+}FfwG2`=3l-S>$-C7 z_!IN~+j3>^F~#xGwmOInlJuqQVw*&kIuV;CGCop=DoY)Tjg!EnUR9QQ6`LsGQm2CY1@jw$6PN@hMi3N zT$yX6eQ}kxFUd!-uA8-9;=1y@V%dRWU3b{F`*ch>$s$YK8y9p5=RKQKJDNpC+)(1l zxmjeyjU--jt>2Ifvo7bypMr5#XhV{73&dGc57Lf4Y}`3K`=kEaj-J}TP59UlyImVB5w2r$#LpwXj>(Zu9_i$yA4K|jq@R=i5!a1y zT`7m;CqjO7Opbg;$fu6Uk^cz!4?E6#eqLJtC|52GmvMg@AL)c?Ix_B0)0c67dR-a! zr}>d_f0|Dj_ow-nzO2cMwdWuE-{zf?a4l~VU+W=BN9!j^U+XQouGVLgAFbykpIZM( z{#7qK>@d6I@>r$rVm3-icUf!*<7BtDRb5wUyJK4`y|zZ(b(#rKhpe-v9w+{iBoXQ97+D-Pr*0^#>~H-rzhz+@t2gH{RR6A&WYkV;L4a2 zRo0#`{-10AD_fsg`Up49??|8hMZDg^b(nZPhwCt0LknR?bPQNod&2naFP6+f3eFu? z+WbQ19&Z0wNUkimOUmfZrwYl%uLsVvIM3odi}Nh8hn2N;t3&*>U!a|&our+lour*y z{(hd+PD=e`kt^GGl-jtO^$_n9W53CMll><9P4=7YH)YSKa1ei7dC8c8{RR6A_806g z#70zhj<7n!Pv=&&leCkxleCkxlN?uP8CMG@Y2UFTxw3s|sjbVg-(HGj7@LS-AH#D%ZbPw(M^FLgg(KULK*&=c3N_ zUAUE#m(&CMP4=7YH`#Bp-&}FONjph9Njph9Njte>J1O<9P4=5&ODbpUR*(2;UqCxaJ4ri9 zJ4rja>d!Ak$MNU)kE`YUwC`AvT)93s%Y3R(oI>-dLgAGyyBmK=+1YQh-(D_P??+`wRJ>KK{QR{~K{-|2Jag?8)k3ldE%` zxP3tuxpHO6(k~Q>Q>b4k6kgdr!i~@Vg8c>mOSc&RrCT|B!u~>RbTQ{XX&=FL7_P%` z9fs>L#k57$x$j8rq|{FqxpHMGG-l2cUTFMWDBK+JIVP){69feQxApaM1{gDJ3m?~eu4kC$ULXh|5j$d$$pdl zCi_kHo6GMvll3M2pYSYlvNol*IinmQT}>bHe?!h<+Y83gYlxnI&+~d&%FZ}lGILUu zbv1Hizj-N3=-+c6HrDqjM$UT_C7c^6+^-sf{lFl%1#rZ>)W_73He_&LPSCF$glPA*A5 zhxBvFb;F5W8;41LLfKc4 zQs>FFeygw1GDuvh!`RO%SH2#q(jH2#nSSBE$+e|!J9XPHs*wE!?0{<@T)UCjpR|8u ze}QoV`-^ydRlNS9(l$R7TN!@}&LaxNsbnAF_9?W_GJchMFNJ=pN7-~4hwJ!ZRq8K# zlr@-}j=|hAie8-ZR{8wmlFbLqX>!7@bKG&PJHB)+LjjE$GkSGAg7l!85x_O&YJljG`&btkUFV7)6D59_)R?1`+W>3R{@ zVd8bg#NL*`I?R&sfY`2dY*1LP^jO**W3SY4bvph@%A#wJzajs|I+9yIf2f~4Pv@>rR=@ifZeNf^{$u@x*vI(et~F(mS53Prb+Ib; z7w%dO*Q5UY``yc|Z}5Ki^!8!8e*jIY;=Y)Bzs%)O+Fd$FaM$15bvZ<-Sg+%Hlbwpk_AdTp8B4oyO2bY{*-F8l zS9Lx)uCChtg5&CZKIxD0vfmivUXH6*%0AL1^AWKj>D;8S%yk&4qpG&IrJg?f3-%YB zU&POYRQG*BoL|KDob|wdt=Mxt_M7ZC*>9FczgcWsQR;JqKazjiN!m%;$OSxe?w)w#dm7`u4=1=pjh z)=n<7zQO03tNHU6%jk>aYP_>u#*Xo)pv?D2X$85@Ay!uA^MIH)mdx`n>^IqOa(=O7 ze!+fII)H-xW1&8DrS_YgXBDr1VSmB?g8c>i3+W^9j@b^aXRbTO@`XDo9s8)Z?fO~9ebkOy;5A4TTSL-ypL10{lzl(1-LF(&DZ6Y(N~qO%gH)OW$ZM@ zmXXXcx~U;aSS)#&OG%MaH?6+EbLJPTV+I>covxs2&Q1 zyJgQJXQ>l6j$4*2vRjrca-nh+3eQqTH;!ADEHcg|4{=4o{q;KovM}JrN$Q;Ifm#v2 zURx-{d7*HZ?JROq|6K2l>;G5v;If)Ut}M@$ji2aU+e;QXVL;<&k&`lNJ!Fw9%MbD( z_EXc(D9int%=yn!CvKd|)_-Noo23rjI9YV$#&OG%MXrYBtt=0W4<%-7JEd4xt6O_7 zMIABERo4c|f7R73xvlPDkXw>gtxaQcVqpH&p`LDXVCAZbTZpnZ3*Ad%M)#-@*S6$tb+v;Dpwc{y&I)CBFH;uT-OH3kcFU4Q{*7|!zOv=SSz#I7ddN~n zH%^u^x^c3U(T%g5vJ@(#8_x1-#TDGoto7sSv5@TQE{p8yE{jb4X0l!6nLKB1vu<0? z(q`Q_S=y`{hwZm`?RU2)YIIEMKU^K;w5-!^dSOl$xvJ|VeO_qF7q#aVPnMb}535U^ zRCS#*{aD|uhgGH?U^}!d5p+r!b9vSSc_0I;1_QriZ7x!Cs7|J_b(Z*<=g;xAD|_8E z$G={0Nzz;9`jt&TYr1JZQa{^uz7Be8{@_PhxNEvLD|WV>g~7cDNCAeoUG+c^WmPGQPzATu9WdN0DRhrukV)FHZiWD+dgjFQt-eI^~u4$VaSqc%jI0O{d=Ex*9Imlrl>kd_<2b zOFkXFpq|RpILeAdmTNlY5`9Gyj?Yr{=9Ej)&^U5UxBi`SEvqjri{!;Am!ufI@q zTvx*-%qf@XOT#4%r(B{h4PRZ_om2KIu`N$NvD;kHOTr|$se0S;`aZYJL%AZkR#h>1 z?9A=cwziaQsY)iLJSm?dRdpGcv6F0f?C-Qq0X_D2sD!GrEi1F#Va%yIm9b|QS?svj zp7>KO11s}Te4T5c8@cA{dOP!+P1hbW`0{TSj({NI#gxU04dRZ%ZY zv%)@CDSxbI)-xF(17v^<6lOr`rrM1mbnFvrt=Q`w)vj(hW>7Gwm!y4=2l7A$$N(82 z17u*OGEgnXAdwb1E_boy>cCyG%I;p5^{`UgpIoe98+7$jESWrz2bVqaKpx0L%mC|w z_24q#%Ar=ZbDO$}>~NlC>W2-V!{|5s!0jBrTsD~oRNj*G`_v*wvEIMqZ%UTcTG`tMY^Tq9=2(s40lrPSxsD~oRS`WBxMLiTj zt~T`$+v}p;tJ8W&@=z>Ud0;&hjRCj*i^YI@T{l0)lHL3iODywTdcCX*LCw#EZNOZvE*Wv-MwzH%I;h@9yz4r`rjJMRQA1FY3fXW`S0#y z{YVWIey1PnhxOw!@cZmf_V?eq*UBQVocu8Vg>=FCuPhr`;!AB8yua;?9m?gs;+1+Q zZLG&EdH5r7nEyh0Vf|;}iu{nDESwaIQ`P)bb^3+MwY+eyyCybO=k-OnH|Jhg`{p9t zqjayU`El!{2(soUxo)v!)`Kb_whu+PcdzxITvr)@TyY=22y&7i-nSJjQ2%%jaRnPi zkrVq+tahqQCV429T&%LY*DY4r-Ro+8s>7Zu@{n!aA+9HJt0cb5XR&0L&tl2ND!Y5# zVwK&!uA84?$!>m%B^Rsg?sbb*cK5n&eu^c#`6-rMtg^e;Emqmx>$>?Vmh9%ISaPw- z?q0W8Wp}UZ=BHS)o1bFITJ|FB({`_`WiP^hb@#fOpJZ%bELroD!Bfx^X1UdC%s;8y9rZ zaV2He0~sI#WPl8i0Wv@a$N(8217v^fDDiU zGC&5%02v?yWPl8i0Wv@a$N(8217v^EuJ1^*{#502v?y zWPl8;`V1svLVY(0fDDiU zGC&5%02!z@3~&z*_cDfDDiU zGC&5%02v?yWT5mIc=#Xdc8c{@9=`NkSx)4kttN+qTHmVj9W%zr8j!97y}EE%xM+HN zm8Y~E6v`p-B}{%38J{pY$CET9EeVX%j@PvMO>8mW3C}z6^G-UElYZn}H-`7=&KmId-91F=hizY z*6D+%bfT^v7qbJ#y}(dIpCYxpM* z?H#T4`NPWC@RN^>PJeTR%I{n>F>15mkb#oszb>5?T{q;Pi$(r)#MJ1Z#nZJOZvOe0 z$aH*5<$umSG!7#F;>&jlm)|9x$a0>XFS4X3>544Zk?V;p*Oz>V zEcufBi7fe*e2XmQkn)Hu<&$!XEajH+i!Aja^&+y=lhl{UQh&wPBikU`Alu*)Te`(V zjYDahcm8FUaM4aZRQ~$bzTqJ|4pF(!r_IC58;nqS=Cn_94SpG?^2RN%&5gQ0wuf!X z+U3&wHa*H3%yrXz@`>F#Nc!^o>9@2*JkRS^b4obi?O7@x+GRp`$Zr2o`LJsb3ElWk zzgDIFvgA3t~TsFOkGY z-FA4U$rP0j+^$7##{(v)JofZUbNe-q`=<3qzmpp~V^o8&U*+VwDku3-ImxHWN&Z#7a=?)JDc4DP)A$u*f21Sz zqv1)tsVwD_>q#Dxa;q%$A=i^|sVBLf$kNVGkLjEyjKeD8Q|#|JR^eDB9``2WMjcaeoEhIA;5c(ol#IV+&Z07HCT%8d zCT*t7(-Yf}&fhsVkJoc(Gr1;~GQc%47>Q);p!R~}%-CusYo4^3w3*s2lC@ctc^`rI z5oj}c4=7zPsBOdO7J!10F=TOq}N_>@*Ylad-(vdQV zEZ3B>i7eN|Zz|)fJcpvPTvO^u;>6c1S6TL&rt8qIOg)yC9;vU=(wE!TT$y?-Ej?0S zrKK;ot+_JwSXz3dzDi49Zd-F@>an!+NPU%-zTCFv%G6_N>5=*>Eq%Fd&6TOg($XXK zRa*LT+nOs=kENwY>Z`Q$<+e3frXEX6kJMLb>C0_vu1r0amL93E($bgP)?Ar-EG<1! zU!|olx2?G{^;lYZq`pc^Uv67-W$LlC^hkY`mcHD!=E~G#Y3Y&rDlL7vZOxUb$I{Xx z^;KH>a@(3KQ;(&kN9wDz^yRiSSEe3IOOMo7Y3a*tYpzT^mX;o=uhP<&+tyr}dMqtH zQeUN|FSo6^GWA$mdZfNeOJ8nVb7ktWwDd@Qm6pETw&u#zV`=G;`YJ7bxoyprsmIdN zBlT5U`f}TvD^ri9rAO+kwDje+HCLt{OG}T`S83_XZELPfJ(iXpsjt$~m)q7{nR+ZO zJyKt#r7yRwxia-wT6(0uN=sjETXSXVv9$C^eU+BJ+_vV*)MIJsk@_kveYtJTm8r+l z(j)a%TKaO^nk!R}rKLyetF-jxwl!C#9!pD))K_Wg%WZ3}Og)yC9;vU=(wE!TT$y?- zEj?0SrKK;ot+_JwSXz3dzDi49Zd-F@>an!+NPU%-zTCFv%G6_N>5=*>Eq%Fd&6TOg z($XXKRa*LT+nOs=k0qnW$V)y$TTNE^rRU0Wcgz^0@}SnY=3ZSmER7RRX<1ROaMASk z8ji3KNvMptAB6DH?)l7^%ufpOa9DtDasd`Bld@5IkL=|oQYk#pTht|4h6Zsg=Ma`GQtIbcX9 ziQ{?Y5}uY<;;W2nN;-0AI!?XGbv0bVJ=;;q{I{n+2Jzhi&L{*L_}`#bh`75n66Jzw`T$Qr-wWt4uBc5>z0N%!7?D|6gZ zTH_Y#tF-jxwl!C#9!pD))K_Wg%WZ3}Og)yC9;vU=(wE!TT$y?-Ej?0SrKK;ot+_Jw zSXz3dzDi49Zd-F@>an!+NPU%-zTCFv%G6_N>5=*>Eq%Fd&6TOg($XXKRa*LT+nOs= zkENwY>Z`Q$<+e3frXEX6kJMLb>C0_vu1r0amL93E($bgP)?Ar-EG<1!U!|olx2?G{ z^;lYZq`pc^Uv67-W$LlC^hkY`mcHD!=E~G#Y3Y&rDlL7vZOxUb$I{Xx^;KH>a@(3K zQ;(&kN9wDz^yRiSSEe3IOOMo7Y3a*tYpzT^mX;o=uhP<&+tyr}dMqtHQeUN|FSo6^ zGWA$mdZfNeOJ8nVb7ktWwDd@Qm6pETw&u#zV`=G;`YJ7bxoyprsmIdNBlT5U`f}Tv zD^ri9qDRqGxxRl^B+79uupU?sWPl8i0Wv@a$N(8217v^fDDiUGC&5%02v?yWPl8i0Wv@a$N(8217v^fDDiUGC&5%z)EHyOlut1rL2{~dWe}|J+L0g02v?yWPl8i0Wv@a$N(82 z17v^fDDiUGC&5%02v?yWPl8i0Wv@a$N(82 z17v^fDBYU1LaYC4RI+a_02lbiXacfDDiU zGC&5%02v?yWPl8i0Wv@a$N(8217v^fDDiU zGC&5%02v?yWPl8i0Wv@a$N(8217v^fDDiU zGC&5%02v?yWPl8i0Wv@a$N(8217v^fDDiU zGC&5%02v?yWPl8i0Wv@a$N(8217v^fDDiU zGC&5%02v?yWPl8i0Wv@a$N(8217v^pgfH0 zKwQcR53Ccd2=YK4$N(8217v^fDDiUGC&5% z02v?yWPl8i0Wv@a$N(8217v^fDDiUGC&5% z02v?yWPl8i0Wv@a$N(8217v^fDDiUGC&5% z02v?yWPl8i0Wv@a$N(8217v^fDDiUGC&5% z02v?yWPl8i0Wv@a$N(8217v^fDDiUGC&5% z02v?yWPl8i0Wv@a$N(8217v^fDDiUGC&5% z02v?yWPl8i0Wv@a%A>dr#HF0@z&g>2AP?k$43GgbKnBPF86X2>fDDiUGC&5%02v?y zWPl8i0Wv@a$N(8217v^fDDiUGC&5%02v?y zWPl8i0Wv@a$N(8217v^fDDiUGC&5%02v?y zWPl8i0Wv@a$N(8217v^fDDiUGC&5%02v?y zWPl8i0Wv@a$N(8217v^fDDiUGC&5%02v?y zWPl8i0Wv@a$N(8217v^fDDiUGC&5%02v?y zWPl8i0Wv@a$N(8217v^%sGewwfHi^juj^zTYupOgO0Z ztt!8|aG1o=cvD&q3Kvapud?{^Jvl#2;(2nOoG;;$o}?>skFx3Q)9WETpN1oTK8=rP zQJN0YkJ9wvN9lF(dxUtJCeDk}d?LLl%|EUab)5HnN4ahio)SIS7;p&qEaxIMDnvE9*TvcF@0$FYixp*U8l z7zgTjDH*S+EOjGwB;zRBOxjG^OxjG^%y{n4xjElj>D(KQ{eiD7L{ z#!j@Ew3%GbjQb1P%=S9BO4h?whKb;P1XKd=BgFk?GS5;rIL_oalQxq!llSj<|1Pn2x#xlVRWNkqeic*#_Zo4p5%1q|pBUGoPzOo*ma!xURx=6|SprU4?u6lKZo|*D>iURZiB~(t9y{mIQq$Z6<9dZ6<9dZD#x| z757DRUo`jl#cOWdufqK*Tvy?`3g-x%BXEwuIRfVhoFgP-V_ic_?nSE1{VLqA!u=}T zufqK*@!XmFRm!2Do2^@A2ckSH6Rha|F&2I7i?dfpY}T5%|vG_&z)4iSoRg zuA%W=0eoLH_q2Q37Lxl-X}jQi+F>YYGifuEzJlv2{C@=QY3I8Fw14Ef3fEP*uEKQ{ zuB&ieg>wYX5jaQS`^5O%>mZ#YC+n*!WACE;PoK)%)6PBZ+|$lI?cCGOJ?-4n&i}UH zy;t6Q<-J$ld*vLVT<<9)^COj$I#HSXRXm+Pa!)(=v?uFq+Ag?Xh3hJ`nemz%*HyT# z!gUp{t8iU~>ndDV;kpXfRk*Igbrr6wpf8Z;ICTAla|F&2I7i?dfpY}T5jaQS9D#EL z&Jj3A;2eQ-gxC(qK4lpj;eLDiKX)qgKeFRG;k{SBPmIsK^10XKnMd7&L7OSPh4vSr zyqjC(WS6~K1|Xd9u;q|KzwosbXj-_d6B{vGe%C1VD)3$njM`U$ZQ9A|Qz$#Ev%NyT?k@tst#1JWl%(l7AY zNj^K7@Q{uf!gS1#%rP|_sDw#8kK;^^Gda%WJ~8eSi`Sr%{qt%kX)|Nn$Z;menH*>G z-KX61Fi7WFGT%abP?`7d;`lk1s$9szwpl&(u8{iCi?aGc5KUimx%pGSZl2r+8Zc?9f3DEqKw6q$@6 zxtcFC7PM zCT%9inS8%WGVf5^m^|x8n~D7+vR)&0l5=y;%{e#cy8@EFGAA~HHk0oP;65?#d4L^| zF@lbllDW3phvZ(5%KRTL{tp)z;oe$Q0&OO3CT%A7)+P+-{F=`r#OsjUC&qnZ+$Y98 z58Njf&!@N+Jx2RS*)zzsXnn>xFKcj^M#x9zQ!3MD(q__T(q_tjNm+vv<3O7kznd|s z6WUDft>s#Dyr-J?@3ST+l6QHj zoIE3-GHoVpCT%8dX7XOU5H^GBDzusMt{&+hln1UwORK2Z)1vF}w3)P-w3+d9LueWt zXQC2lGr1O>FrafQzN3Th=t%kqdW@^`A z)ygSL5661YT3|gS)j%G|0~sI#WPl8i0Wv@a$N(8217v^fDDiUGC&5%02v?yWPl8i0Wv@a$N(8217v^fDBYQ15(9H-g#6-auvN-qRR8F?{fDDiUGC&5%02v?yWPl8i0Wv@a$N(8217v^< zkO4A42FL&zAOmE843GgbKnBPF86X2>fDDiUGC&5%02v?yWPl8i0Wv@a$N(8217v^< zkO4A42FL&zAOmE843GgbKnBPF86X2>fDDiUGC&5%02v?yWPl8i0Wv@a$N(8217v^< zkO4A42FL&zAOmE843GgbKnBPF86X2>fDDiUGC&5%02v?yWPl8i0Wv@a$N(8217v^< zkO4A42FL&zAOmE843GgbKnBPF86X2>fDDiUGC&5%02v?yWPl8i0Wv@a$N(8217v^< zkO4A42FL&zAOmE843GgbKnBPF86X2>fDDiUGC&5%02v?yWT3Pdkla#drKL0Ki~1r1 zWPl8i0Wv@a$N(8217v^fDDiUGC&5%02v?y zWPl8i0Wv@a$N(8217v^fDDiUGO!9V5IyUMf3x`Dr3MG6>%R$ki>Frg9AK|;o_$fj>m2qAk z=c|nL@<>MV9OIC~Khl5}CTA?h=kY;YIisN`x2TUSzgAw!4H8 z`j#d}f)?Ec2OVKC_H|LH+|egzqK)4XtvrKVN08 zt8iU~>ndDV;kpXfRk*Igbrr6wa9xG#DqL6L9AS*ErzLYJmAS6Mbrr6wa9xG#D&=Yq z`JM;9=Yh{~@fogU&Zz6je8+w~ZiH>j;lJ6`PI6s^>ndDV;kpXfRk*Igbrr6wB=1Pn z@ltZ%O=Z}JQ1)-h{rcp8T~)@KLwM&xjx#yVfqFj;5x zz(y$JOR*FjXVPYJoXK$}#twYvFzg|1X8TC`1+GPNEt+f5T#M#fG}odzN8lWRa|F&2 zI7gVQYbKl{aE`!t?8oyX&Jj3A;2eQ-1kMpSN8lWRa|F&2I7dKV5Xt@n-ba`mN_&uc z;Qw&N|4o+MS4#ID2q!9YzY6!Oa9xEqlj|y6S4sA#>G%O1r|er(Ik68abDYU>CdZll zzt?2nyN7fpY}T5jaQS9D#EL&Jp7OElTVm|I3O0k*)LPWKC6NY)#?+-!0jnqwCCEiyp*v z75@L7_7_}N;kpXfRk*Igbrr6wa9xG#DqL6Lx(e4-xUPb}K;A{nIYRtyYObsB|6Y{= z^pCmpnJ+9W@jtRr38;@q#tjfXu0_*kCUZ&JOxjG^O#Zh;F6kHe-xf>yO05(Aw*}wR zK6T1%9pt}Wq>Uu&@U)qJrCUTz&#J#^T7Le-1896r+EJ^ewQid z2%IBuj=(tr=Ln@UM_9|-#B1uUEJkk^4b2!2brE#PhmzZKk;a5wk1fV&00wT9fvTNiF?xSPRW5AM2fL-=jr zt_L>*g;nnbJ!mWw09yrRp zo(SpT^@7_IZUDcxXW{q8(aY=O`JRDm5Y`7rZ?7+w<9xV2zBhr~7kO=syf=iq2J+Vm zeghm0kw2;N`ZyXOf1-(cIO-#RqM^Dt>LGt?Lu++#tOIu)gw{q#9pr2+Xt@@Swc)Of z(3%LTh1@j(8#R=V8VIS0TsFaXi&||0w+X%*!Vk2Lg`T*sWJAZ-_%I)zUVqHA*9vE45Lg)4Djs4v4*~gCn+1&5?Vt z618!NrHZYS=&>daS9i@&7ot(I082EO+Njt%H9>yGaxKqBrCi01-Isx?H8nuMeNTKlG7eGrgtrHu@-7@X)BcWu#HjQ!gMX2sh zl+j6Jw0^ONO>s0q4NAGBbv8v^i#=?HGSq=v8=-4Mmho*p_|0+1__n@M*Z{up*c>`< zprMi#-NLi%p&2dOsr0ilh#d_94s94r@ zl+!wJ#mWl5b(LV@SZuJ+En{`50U=(v7i%rHd|j^%O41On*!nh**24&WO-PMV9?{5} z`0m;YS6;fm__cnebW60neEmx4mT0+h`W4MC(Q>R=(V%F0dAw!GkIS3X_7dur@RpJ$ z<8L8vdAy~httdZ#gnwaRNh^rSuS|Z@F=O1Gm)LyQ{#PZp(q@;?yM)`6*m@vT2u`_8 ziERKvh2WIil-M=EsSvxqaxC-;$HJr#D03QVcQV2g4uu4n5Gx zcEa}n>n5Gyc7Y#2l9@#pNHyWgOtmZgT5x67(G7lWxUxF3A^h4{H`x#^p*tj5Ly?ii zM)2$Dno2#ao@@l>H^%q+SU1@it)UE31FW8up*{3~)DUYZJCq2n6RxUT;W^ux`>DdhY|NF;-7x6=f6nO>hVU{dDzfQ}|6GNh{t|YqdZ8W;mp72Vj+H zZ5(2^2jW|E9MXPs__huXX}=-9weU8B-vW}5uo)y-0ox4jX87J3>tM3_wI%#?HB8pU z)Z`PDBlSgnaqLlbV-L13wlB6XwlB`b;<*^@A?+dUA?+dUA?;x^tQ?lw zS|a-|_FwG3*nhGAV*kbdi}x<8`rakS8ys(Nyit|o4G+6Ad>pbLH-3gdo+YrlGeh<{ z)zqCGM(;w$JG|;5M0T*J&p61F4e7HF@!s_GnF!hMD7znJhmGt?kDsBC9gngHU3NXn z-gMc6E_)wk7qskUk!LSt@1yKnNcWcc_?Gp$@fFi&G}hFsH^i0VJ(t<88<#iUzgmpz zdZ+=}H|y@)mL~$z9k%jBNcseUJSmbsOCrw#$d2E*yt4CG>Otzcp|`$~9mQ>o>@IEt zd402>zVdO_F%U+?cldIqOaEY zbzS2d+2QQtckFCIcxz)2*3xSUxs|c_*3xSMxusbLZVMA2tff~2eoL=8Le?=gO%2Fv zLvC&w1@%om(>SPS>cVXVe@%om3f2r7nEIwkP}kIf+Zg^DK||93ZUe+<8q_hhP1B$W z{D#3ArXk#h_-(DAwy9;-!tb?B0|^fr1Z$c#Ozof+u38(v*MeIUSFexo20{Ixky+E! z3mTh7a2uKWL0!o8g7<7w)5QG4u4S6SZED`L@7pG(v3cLV2mgKB*whW)wav_0=3TqC zX$E&K#QUeM8`KH@iMVxxcWh&n@E!d6uKgE&sS~`7kaz3{_*N%)3-a6cLwu_f3^FFD z4YzjC(%Z@mLf$^YFLi>g%~p`NG&V57mWVURY-6@Y$QB6M(rjUZzy{kQtfjX(f6#W@1ogHip~7l)>$3dcf^vdcr*({;`OETySjgKl_tC zHu%~84{k^JCj=XsZsvrbyV(%#My5O5jm<`IC&E7lagGg+3Dyoe!0mu zg1at`ui>_a-xA@i;5PQ&vg;xAE4b^zZ-J1Owhg|01@|larCkRhE$shH8_54NU)nEh zbA+s8e>VR!U)V`O7qfwx6m&IR;C3@z;hq400`hQ7Fd=9Te?qVh{0Tt|_!EMb@P9Es zWW> z)`LGDp%a2m80fb~cA2m!05_ z!ncu#bC?=qY-nAceJ;bZEBA|tWM@ovv06Za42GqG~>O-wviq0je|cL zagO#zd(G@xkk_`&?2(Aw(Hv=xfPVaF@q7W1KcCw z4~Epz+r?Ycu3>laCcr<^Yi`$uyEe{w&i>u5A3TRT7z=lOlz#+LIN0opGuE)X;%I0O zLdXcSo42di(C+3nu=U|Kv<>X;-fmufyN9>Cy7g^6yI*jiIl$}}9AplJyD$7PNOf#5 zCV1XHXU7CD*yrv3_~igI9Pa*RXfWIigS#L6p~1dpACb+zaEF@x;NmxPG|n0m938x9 zU$939FWDFE&bBV}ursb#*X{&&XSjQK_2BO5?cwbRcPG1}-OJn4+Xe9+x4R%l9Xl)- z8th|s#ka@p5d69$+`YZMyxr`s2-yMh5V-qzdwc&iFX2l6H80zj?Dug0YrZ$H*q7~h zaKAU-nOE&A_6PG{g@-2m^T#eaBrA*k$0Fk67DGY7sDUv{bYVLql0hEYxZyU8>IZLnTgOt zy_xuZq<0}=UgUKS_AtAf4T8>rxVxEM;qGpBGo29LIp`AXYIZSQf(_tb;2n-LF7S?k ze*vTmy-SeRA#i8H?;h-F_AuRXR;S=UxZ*eFKjwA&ntjduggk77U%Lkz!`%q(US?0T z3EYi?O@h76UZyLqvkTl^%+BUgqVW|JUIQBNLo7a%$ z*GT_A=42U@Xqs&L>lMeIN$4o6#52VnK$hl_A8u) zGm+Bhpf|$%1RDn3f}PBUICeD0;_MOLu{aL$dg0gJ!JCLXI`|Ujer3KigQ1b*@cTjD zao&O60dNn3-xD!=1;^vt0p4)PJ%giyzneGBQ8;^a&?6X*kcr;$_;sSUzc(E20r1~4 ze@BcH@NKwv0*>wN+vY8Vlp%hP;2rZeFW^?nwAY1phSe!~K`}C*1dOjsC#_NVPwXO@mSPF#Cxah2vv07~%bc z>A3O`a}M0;=4`m%aGdVl2|{PUoq^Z~BAu;+t%3vLo{IRVnN!WK z!7jlVb2L)846#pxI}85h-l^Uxa8HAOIl@l!2H~u&g0YC#+8b-ez&{1&o@!1py9K)j zyW7d$ByV>+#hVOwsy7AhG;b>0a&H>k6TNb{lR(-PNbeMHoROzi$C*e82edRM^T0>5qmOprTG^d{G~A=@XuF3!1i#5n z{n55Nj-#yX(HHk9d!%je9czv;?U80XZ;qX92L#vQm~F4K0|SwB!9ciSkb}Ef5C(JY z9Q-~P$9BQS-jVhLBfI>MwDas-yIt_IdC80n=HuIT!7Gpsh5Iu67je8~UNx_nLxUIe z`wQl-Ecbj*s_jm72b#L`<@!rBWac}W%_TIp+Z^FGD z{u|yM@E73xy@Cby2Ke`wyOGX4I1UM(L2A#MXUwSJu;6W+eY5vE;=ciRA^g7fU$8Hm z*uM6N;2rO6{Q3@#o4nWX>+4=0)Xu+5AH?Zv``C@W4@^JAJ3Q!TH-UezxyKw5JdKo} zF*n);cCX+@9OaP9%{0>+@%z}`R-T*K)b_K72aA#RP2OT0H+p|V`me#g6Mio%&r|e5 z%-*&?;*ARW+fCu$XYNJ%d7N>hm&dWdyU9*7Q_W5GM)*CgJbBR*=k~H2*{97@W+OWa zx!DM5j0z&0vA~OP+~EBm!k#j>+Yw;=c6)Fz0`5T|{&w(ioy{ZUc6+nE$xbyloI6|H<58?Ou-a|O%c^f0mGP|*rXGU&C zdL6vS5a)4oKjJU4_uKo;edacME5iSZ@W;%32*Gc5k-6VoYi~pNy^!y-_u2={B6APi zd+j}Tv3bDU4fh^~Z;O=AhhP$ub2kw4$U${f< zesG7`p>T)WVQ{a**?qm)@VA897w#PRcOm7w?Oir9d9wvVw!~8=bK!3eSDrhW2mem| zdY8S^K4>Dd8A9aQl!xFiM97_Xq5X?_(1Zxt%=7)1ycgkm@QweX_X1oW{x9Ck-b-*_ z!ov#If8Kk}v;GU-^KcFPpS@S``_DLj!35L#&w2mzUPajdaQy7Oi`dV?4G{hl=zA6J ztN86=`-t~2+(*4fyqWf5`!L*xk&8?0Oe^j~c&6qe{Ccsy$o|!P)VmPwMfO7bnD&wJW?3hp!T-$UGIyz%x) z?+Lj7=RFDcal{^PpYR^{&bRVp(D_!L3_9P+9sKjHJO^~Xl_!ACx3l2Ck2Ie0{)yxN z;J&Z&{~?us;oErof%h-CA9^3a{mA#1@{j4x8T=X%`N63`xkqsS!k}ZH$%R~ zoDbExaY&a5g|938_gs3VSAyu!d?#d0{9EeqxKQF zk08cH=5l+Py~tb$zrFvx_np_?|F8Ew-0!>&emltR{f>~o^*Z_;;9rb0F0-8w_N~{+ z|Hk_d+;6>aytath&Ts4g;QiO@?0542kpS&NvnK<)WJJVbYzXoD_ z?bYx*!*7FM*Y|7sHTUwU7_{mT2&YiA!e51DrM5%VzIN6jN}|7sqE z`xmp&wgcC9z`espa3lLD+>P*iJCyPUi4VV>eaQU9)b?xnUwG~D`wgZ&j_XYwzcxbZ z;P~9@VB6d4O$QwFOiPfnKJ)7Nb>Vli^UPe+$##Ta z-~Y_})T{4*3XRwI>)~4izrH`-cD8fP9Mjo$g1-U2&4D||%r;%@23FkJ<~p;j-^y?4 zZ|k>)KNx;Xe;df#`rAQj0e3L`?cuk8yN=%+ZVUKZBhEH(*M+~ezaIP@@Jn;J&Hc6g ztq`)czX86j4R>w7nLh|2TfuDuzYD^e`5nD$Va+;1GuPUV-X&(H>F8Z*E`dACTnhIx zGYjtJ<}$cfn9Jc_X|8~KmAMk`)#fVG6)83IyZUSSP2o0!-wl3KzY~7#=xvB^P5ljV zH1Rtlq?0!QR(E4Nz;1S#fvrcJ$7$r(1D%^oDq6+B2-U zL%bclqx{YM&_BvQ68;hX=IU;SZ=(^KgL@SGqah81I~xAs{uYRJIF2Lyv+NGu_TE|c zO!#9EV}L&fu?G61{4Eh{6pq9FA%1^ggX*3#v*Kg{~Ux&_s2mR4tFg4@$iSk9qteFC*T+g zcRc)KAngZt0{mkk?F;u9_{Txo2kx=(@AS{~&+zYpFYX!s>Hb25-09zqZ>PgO-9OF0 z2fnzc`KS7K;Maw4&w_u4e>VJk@yn@jPxVjnZ%4=-{%vq?hkFkEi}A}Ta8LG6f_n=5 zneb2YFY!+BAt^FKF*$O%l&EoN%k^-7Tj3~J<(q7U*?~Pkdth= zy~4lTFGt9UcACA?zrvq}ka9Z}@-(WR`8WBm;keO%9mfK=ufcy6A%BB=GyFIF8~p3xE`a|AeqZ3fg78=2-U9y> z|5o^K;+O0Fmm$C6-{;Tw=fS-m{(bo6djEd-^ZZ3P=EA)n{sWNaz+D7?F{IgWAAp~S zbRFEq@FPgq!o3!GjSzMn`!(tC2!lXFh$N$7s~$ROuopmMfqLNbgOWNN<9KA}H_oJLA6R1mQ2}<=*?ge?I3k zzcp*ttaa92^UTxcnVEy~+rVFOyfJLcZv}7QcvHABY|S^$j-&k=XIJqqjk7Cxr^eYm z;coEWa1VH2xEH)X+y_1o?gt+X4}`yl56S(NbT|3C!(HJ6@*jr3adubuh@*H{xHJ5P z@()6m`-ps&yEEJo-lya*;XUyE@C0RdfOmx3!@I$8w09|gFFZ-v?cnXu{`+zUJI{+wKzHl{Z;VQ@Jet5RD3189J1`!;U@4m;n(2J;Wyy3{P!%|ls_<^Wt;Px zz%BXB;MV*W@Q=J-mOU5#2tFU4178TwgD-{`zysk~S#}fc=xFQ9DA6xc>S|gqtCqBcwc|={qV2WVyv()zQS6$0fiFA z`v!2eKR(#nj4kSat(_ZKC@}UokgEd$Xa z33lh|7Ork)ETJ(Yi3es)_$3G8ac!L2nsvhyyp=jz7?WtquRDNRO>^5Q-^!@Q0er)Q z$ZumrWFz^5$sa^tY?gH`ycfFS!+wvx+YJ9!H+-glA@@Fg_PtP9c$c(G;R8zkLJxg6 z>{57#G_UX>B_Gf?-wE>y+ez~ahjQ;B^t|n1e&KD>u7yXb^CA85?XYX%Ez$z;&m7+j z3-GGFNpD;L>ZAJ;y;0Q5H z+u*|C*?wR*$|iDUzia|tw*By@O#sK?8QU-0o%^QaS)PtJb$8NCa3=oG-AS_T4fde!Y&^(Q@GkB_ZVotyv&G!S*h%4!^xwsW z=jgwS3(wPk7Z+ZjKk9RyjJJ0Z{_~~LJGqFOj?g>}$68c)1}?Rz@CW$7qQbNAfpV;w zBj}k&&`uq|3hbS)<6SJ{%KqT~v|Y#WH9VFbDer(jUIs7g6uyclvlHbV(bL;g62e#T zCjo?xcEQNwzyS(h^erusBR*nhsR@?O zT}bVN3RjZ90v}T&tdcA9jj>j)B7bH6YVazsAvViO{Ahb-AY(o&3oEl#*|x%6+`FxC z2QqzI;ZB})I}&_b;ddOj;fY+8F>+Pdi&3yu_|8^kTMIWMW49K5i|pN6xCP0)wQwtP zdu!n~r21Cw+g5lWyBfRsfvjP;I{zT}0G^%t$cqQF2FQ;4@dEuQe?RG({6mb))ejHZ zX4w{=ytVK!B@f{@x(0vKefW~D$v;BL!}yARjF;+OuKYNU3}aMnQrMgEyGdbHVQ+9X zk_`)l5w{7*xqY(9luyEz-HYEah5Tf#7e=?nQ)^#5JsTK_x|=6I0@8$Z%`CsGZxR`V^9@}4&o67U2XgeWg$MGN5;L*K_D?cP% zg75fZYR=4VKs%e2{Rdjxtn63lYqKcP(wdpw7-na`M8BKO)mhnv)c!4AY`r=ca`(;n zOmF0Qmy&*%-`2DN$MApFVTt~N zr|gvd99{Kj{2@1BCEmbO&gU7ofVV)k3mJ3WQs~OPU9>g%#-n-0`fLGXy;};?v!9{! zPUi_bVPpP^`;Wno`>Xt}T;Ect-zB_9k@;n+x+PpU0T==ECu`*3YpUe@?CANyp{8Q>z;m<Ei4o3asD#5ZLl`6V~;JMP9qISgy}*Ic~`Kjlzt+uu;~Yy6Qzuy${z zc2(FTS1$T@ls_RGCgQeNE*odXs zb=ZQX*-yB;H2W#{mlDyXZCRRKgO%et+m~bKjKRA(5DWTNo_q`5&EY)rGOmx!E+dW0 zPNM#g!&mV+o`WX)HI84$=O})kv#(HkF8EcB-@wm!Hh4DIj-vED@GBfo<_RZZfn65H zWtWo1<6#|ug?=0V_g1{B!}yQi#25KJ{2kxp{v)~b2jEd0PvPE^vCl3I`(5tb8$a-w z;F*-|P1*}j(-7`DEi~r~o<{vsvG6Vl6SIp+lNc>H5wF7y*|+fG+<>q5WbkA>&Ntvk zJ{3F_FZB&@niClb{x(lMJ+vU!?sT4Z8up^AqhG}HCS`-N!TgtB;kiCN|0|w)8l%5w zaK}ER)%k&3KcH|%Xi2o*89d>1Y|4wmvqk~08&6rqGu9TSkzX5Da<-P(y^&eX!gNZe;agfs$#QJ_gBg=u z9`Rs&7Aq)O4sPSPlq-jThvW|h55>n(ncE@e#gQbrX2m^m)_N9sSD&Eokp!+7eC!&A7KV_p7BokHEhdH6$q z&mEUBc6u4(oX=&;c#r3@<-EyrJmHV{P&aeW1nlk2`K5T@p352$Wwjp>p+;LZD)fii z8$l`kvvwT!BZl+5P!~KGzslo0)sflDvn%k+ZsI8uvEDc3_rOEcl0IX=p>evm!NQ?JY#@Pzt>#ngH(YentZp%wSd3Joc5P*@ZeQ{Ix;zS*HA zX->!}Z%Eu<%fg({g0xd;&Y8GV*g2FIb`EpF<{VEWeq&w!G}3x-JtO$1(a)|Xw&`j{ zlTRaE173sI;55>;;I+hKoJRTy_!A;MP9t4U4Ag1ahWx3d{qoHUbMd4$BR+O+IE5?w z=acvzbfTf0j*Dci_zK8Yx$jrk^pdH5EZ5Q{r6e2aLa$#`lP zFoHRXG!h@~0&=4n-CU3#LCJ35NRDGD84b>3^m7bpSH_!1aCJCo5q{!%lnx`e7#z;A z9kF5aze#HYMK&F6{l+$p~^xHEOjNbQLS zJ(_r#C-cV;P4i^_SmJ1&%pXV0%#-=!iGF#Kdtb;u#j|FCvxu&HiZlm&nzC}9R>nBN z9F7%~%>j3!v;+AH#-E-d*9q*H?+kXzcL6)+yMkR9C3=e7aiKG@m&b$0;f?N6=uG~j ze3!zp;kZx+mJySALiihzyeCk8JihI}=Kq#Ik&+Ye8J82Yc?{m+^1`<$KM`N@F`=Tc zE__Jb>^e%m6~4)Nhr&0xQc+kRJ|L=gJy+M^kN#%pQ1}L^V_`%13o*JIxVj$SbjL!c z!q>Upv9Mowp9tRlxVj;<%n!&9Bm#CIu?Q`RjU7N7WlQp{^NjF=11Q^{`ul}8jJo$D z!nPk*+K^fkzuAJC%}Ilaz3oeBDY+rw5GbIOD}(bJ={@g*@B0)+n9&EhUW^%iK>1&C+q18SPKE7RV`9v=XY=uzZO?YaYqmXG5Eg<9 z@o8_*cEd}*J!?;V`u407akJaAMfBh8S(Czi%D=`h|Bxqtkb8&xcE&=#iYNZBxgLyC z{gv_$bMI2}4r8ZZ!TbI<#`Jm+3EYEg?@{tDqp3&XlmCcuzwY^uxcax;``M9rj09%1cqQ148i9P4|4ViRe*3>r^L@rnk0AF!b~s-555W)cA0CF+{q0=Cd?TU- z8|51lnb>NKL>d`KH8g*5lfH zxw`p!M9;mIYnp$MJW-yxI{CUp*S$%}pGeK}4^i@9u8at(tWcJ1WDJCOC`LcZvI80S zD9bi6;!&1uW@Mo(+rr2~S+>g_0e1hzQc!Ehpd7+ z9r!ALCI46A5IT@P0zb+!$}>ipJ5b{g@`o^@(IGpO5sg3d#BVbS{XECVdFEre$8#k_ zKL0+K&lkW#z631EKc0JwTHj_|`rAaPJ;BxA=icP(Ova_pBtq>^9L4VtU-kya?=o)u zM#S$DJN6o9;#ov zmpIk;sFah}yi7+_#9oxsmvc8_1nRjLr?jWc&xm zlSwBLhw)3!P9dF4Z0Gqz7aUEj!1>_$oPUFKLGBnzjt0-;cr17fcrM4UbNvGF0-_YY zPP&L_)pNOa93$oD5^wo+O1{cbyoh(*hw|gVvl&m{hjb2+_h*w^1MUl+#VG$8(%D4J zpGEG){4aU47l|S{6+D$Vju-Q%5i{^2F&$@sXAm>+V*cC247`{>lbC@Q^WPz6;Klqe z_)YH-r@sz-G5=lgES~rtxwDvavW^(ick}OYd?){Iem%IJn9%L{4Mciw&%eX*?fia3 zYrdV|&hgLrxAXgh`xArtR(>NflW#FYVbGbd*&XH!X2i1XdT*)-BrqJ1}WHk~w$nBPC;H-Vcd zn?afmzQJ6Qncxg!fnU$Rk)H+5B)0f9W`E2EXXWZ-yXW=*_sA^;m*$p%%XqUo*;i=S zI@wog**e*B-m^}|YyofyvkAsAbD$10iRxry$uHt;Ol~Y^Dd5WBw% zvxtV~YGhr>cgc0l?aZ+x8%$|QHiU9^)?&6%fszu&+Xm(a<=9n=^ISF{H!zo@B+vL+ zKjsrz4Il=216FLROjeX7*4eCEbXmeS#TR9r@3dM88%t zucu?yjd?vCv+m66>6rCk=26FNXWpq}_8KkJF`J#61J23q1n$I}cFbO4{#3{8W#&(H z%wA#sRLAU9W*c?ozf@+O_zyjEUC4LMh?imRQfJC~g1sp1Os*GSw^_a}X(%`pow#nc z1lz1`b_8CMy4m^pTftlNZ5c;kd^FcAUnjc*UR@`<7+%zY_wR_6eihchQ^Ya8NcuVW zbD|YrM9;XMn8v4w&4)|opM+CBm4AXb{ipJIj!!XPC{LZh(e2Te1_mS&GPpApnBYII*8;@ZxN?bX;1eEf7P*xMqW(hRiowE`s)3w%Jf890N zU4gwTIoE1;CH5}lT)n+3$Ifw%X=ly?erIErWe?C$j!#j>=^h?l<0Gw!`aRpOF&29ccy$N zP|xdJ&TE4DO7(%)0DE%O2VN6&41X7{&IOG|--Yki8_%!f{LZVY1@_@MkFVMX53&&f z&a|ox_T{)MI3F~2U{_k9FF2pG1)SFdcjdT%a=q9_L@%VYK4`4MLdxoa#yl@1ExIc)(-a)WaVb#DRg|^{ohj_RrdFV<;;$mD%=V%$j|Ina?o6sSj7K@+WpDcXIMAqN=WAI$j^k>s zwF4(`?p&|7j2Eq@WFJy{Z~|xhz(Xc5Ueq2g;(V?4;6#r5!eJ(YMgXn>9W~mQI%`Pf zjPpz;x0YN5xF(hu0l1Fy4&Yjj>)>6E%oqW`T5ssW%jZ%z;WQC5D~jAW8<%{`R23Jfl0+CJl+VVw5|?We!11%c8tnM(z6Kcjvf_dJDmYoGp+1YdLk7z&VtL zE8wSf!DSp*@Vv#~V$SyDnM*;X*q-E;!!wkLE4imOxPs$KO7{Tw;A|DWEDtIlS5dDf zxRT>4O65iBf2+tX2Ypt(C>PwT%^ek$LGH@w4rcDvmP!27RZ9%Rf~7GQg!-I(&ejb@p3Y?c=xDG`#>jMzPc7~ zk5ZR+heq{xwRm?&QnT+)N?N>V&-}c){D?^F!($)NvT?5>Dc(vP1aem)wGASko>~Q zf=l+CJ2SbKpjMOLxFK|sEIw(*@7w@d(h^McAqODrE@=j4%BsUe+opai6l)7pVjK=4u{Nre8^V*1q@q zbmkZ81Mn+J$x?Ol6!^uu@O3=*i&@Ju^F^7HU1yWjO4qHKhJiR zkJtJCl8se$|Ct>9Eb^>qcYI#olv+cThw77kQ}W`Xhsxfzqdb#4?CU4zQs@dm?Ua2anrZ>vomONDUwomd(RY|o^_f4s97d=$}D9_}4`ld>t z-_Pfp!s7`wYd4qB-+e}Zupe*SkNf~q54cA+N|~q4`5~Y$+ok4Bq5!4$94&=^}+*M^G52xm+*w06i zYePO+&4Z~untFrbvE8^wsi|hEb)ZeFC$qY}JdE1os5cD0-Hm&+jz>fepZucwNVTyi zkmUVZ-V;gM&fU023sxDCuDQk=GM$%sH#hu#4yMS`e#gUh4)7B)f zb-jcd^T2u0YVO57MeA5TOvF1pxo9;nh7T{L#sY8w_blW2yMxND<&m2&j~rf0c{fUS z<4&zyZDj5571Z4wTokQiCDfkuye%ZN9h6Tr=CY{E>xskn@_3%?!wuwT-gOwKiM_5v$UiKx+hl_P_HI9 zpQAKrWVLOzkfbk0-}G+Os0A+IxQH_SH+?utMS7QQlSOd9zW+&^(%oXN)q)cAK1)k_ zm*tU5NP2V@Q)lOS=Drr_Qj_XYI|59ivx@YLa; zn(e-v?~Mmo-F8jX@zzkUDV|?7;kD%T6OW|cTGBrFe&w3$C@sa~JBrfv@a$3Gn&=zW zo4g_N)D2NT+(2n_W;(5-bU$jX14nb*4{kgfR2$zv^3?sQ(UN&yV=3K8et%FMek11_ zmX)Iv8!>9mP@t(lc}0Hw}AI{=)(aWisZ z0xNfILLzO6GHNUNEv(k%T3}n@KsfWQYUJ#hfs1bv(xn1973&a;1rIBQd$lwwGJcitT1h&!{GPRK-XEIH3(N$S^GA`J0lEs* zQRI$@t=>G+O0!6LjX~|0hNNcDtbREuxEWkmJ4uRXW!3l_?Jf1`E6PUqaCcwt`kcxC zTfz5jHFqv=1G?XL7Jo|?e@m^{Mr!G-t4g^%RDHpo-xdy4L1`XLYxc@%YjU+fNz&5I z+b)Ip%?rGb)jr`Iwwblv8PGrTv;~ z!gYLKJsrs(n7oDBX~{~{TI z9a&{nYG)>kQ~kGSi6*Ob7`?SI9bMHIF5^L zWPj5qs12PwghdNmKVh=D?K$mY577>n+U*ab_PV`7l(waNQR!wcLi;%?kj4-kMOEJD{Z~fKr*;oeNv3|(9f_j6 z-j$?IqzrS+Q$5D{HVdiUGs+lsrTLug22JEaW&3XA)QKDcSVU4YQu|jM>Io{57L(M8 zN~pCvNm--((YN0V)a$YbrH&q`(JY0oO286oEh8yq)MC_ndV@-)<>dN+N%v8+SV3}p zK&hhEqmHv@#O2gf-{}kLD^d^A>z~F1^vF3%pmwA7qmHvDTwkfOH+B1g%AwUzwGu>0 z<4EIPaD3;?$@k6ck5Z2GgU34}v4*r73E(KCe1A3EeP8OVBMkuccsZ7+)KK=Ur(e_o z>rhvDu@=6*9^8+lT-Xrv>$uAqqw7KajT^~rh`fG1{97N}0i5p#?#G#{pKgGoYuge~mO8 z)HC{ZctjIW-{#lJeT8|iU*R5C7yJsdS-(ad=fZv!G+yMJJE1{lDRI9Q6XOPB%M%cKf=_y39#u-7}bsF)jr%`q$=?w7OoPCFS zN5#PJex7lId3-!%#N$5do}4w=67649oHK)KON2G8tPvK>I=Vy+||tc zxCXqI^ds;`)VY?jtC<7Rfh*S`Z90O^5xI_B2WEwICg+NuKL(8s_zAgdnJ3bP+)vRQ zx`1jBKc#dA_>*|mS+74ORnlA3i1ZV?hea{kN?(`0Eu*TEPir`Iul!Z3ZVA6o-`2CG z2gK1H$0J(9Ka9n4oW?N-eP>2_wSgNMk>%(^iUmufb#35h>S>Nd42CN8vpB|(#vleo z3EmD=M{?A`Sgl6XD5K1=s`2C;X=n)QG1J?k3|GRdAK!Q)*Bo`22!}PY zD@C?-fHo$#|%i|Cbh^r17?)Wgy^Qg`y&p^huKe}l1MDFVz9hptFgN0^ci&he#6^6Gja{%8M- z&r}~)lhE&*;>P@MRbv+3m3(>n^px3-a;RM>k3}_yG|J_h6=T@aIEymUU!6v0{03EH zH2VDY>MOTIWvkLlOd~>REY5L*Vx(P_pVOGUq8HS*FUIUOC0F#97Du{LoS&2?g-WlE zWf&c3T%Z&ywMw0GW;tvcMU(ncl%c#-&X~r@^y#Ij#58W4q7~(Ma-VULvL=F#%g9+A z*-G(_RZ%W!1l4|PoMdsVO1hAHs1b_tkZ$oA-JrZO@)aDraYqGc|8?}rww1d&($EI< zEgU&;?4cXSRvcUNyBwqF6x+X3Z1YaEd5#ieT-EkE(Ygh&Yy2u*Oe z*JAAva-C!Qcjii`*!rF6uU)yOrq!9=*p+i>s|l^|7=$DHO=xdNC>oJ(99!Qp4C$~T zsZpeaF0{VqQbHG=C2jhawc;Drif`yxY6&Ioo)Jh=VtIKgD{yY4ul2pl(Qu!#W8LJl z(syMoeOdM_YgPHM{_#J4`t#Cz`rkh3O?Uj?#n%0QBVP7jA7d|$Mx;LPXoVc$iyD)V zzSEd&ab&`_vVSDLm&U~$HA~!3t|(<17ppz}#YDRz=FzCqDoi zu^1_ zRF9NRv9rd#HpgaM$}vUCrr6nHr0g=TR*#o0#>g5oYozQ*>_bupP0_I{xmt{oRp0q|q-<-fPIaFY7h8;%HBxpprN+prrUd z`Z=rOVyALu?5q*Adiac;oeuv0Enc?z$lqs+lyxl7@xO_1A;?o4V8BWL5F9#ZkadkDC4Dc-iWavW_PfBWP39tlqI5qh{wuUzgs3e~g+f zjtf?gl-2+BNs+QCf;Pp=>Nj(w#b{W)XvNrB^%f&&^?ntjW*t#crW7M(Q*^9aZ!uoh z7};XHtp2jp?3zR3cCuN{ooE)bEoLJjQ-+CiZ4&Q`x zRvV0btWD%&^2#=FVy(bZlK%H5;9Ks(XsXNLk}$m8a^wDI&0F`KkH#;+^V7RKC|E*OOmfkGwk2 z$Kz$y>Z_t=jg-}@(@R##FViBFrq#2*h@tWRY=3$@cwtd{NchH{*h#H1p%$-3pL`fb@Fm}d{XO-3BieS1 zlueetet?fh%IXQwC$M9@Y?TKf#m;_GysW)3c_UJ!Z0arlPP}aLA*6U&y;R9N(h#1U z;$`)pe*SpbPmh$fP4v@LkB+S#HCv34)jIOaYX9r^apq!e+A4X2Qq*knE7=k$Qnq^R z>_0}wR*#@fF=T0!?8|srJ(OR@%Qk`5{%7K4Q;e*-jUF#4KSj!_^K^kbdH(-GysR^Q zlgGn2KDE{vq?y=i^494j=RE35nMRt9)leWel`l|0vo9exg)dTqb*N8nGRfG(n$d!k zvrmLW)BW5{|EyG@K-tH*!EJr>rxgAkB41V-ADSFPp);odGcjX;})E zay}6Ku{qeB^8w_IAXReoCmENj-0eqley0+mFR33KRF7;QQeWhpe%aonKJdu4zJg;Vs8*==*QjsxL4CkoK=nbr#*Qg; zi5%QH4{1a~j;@d0XkTZmq%jRW?#^>lr%fXrDP~w-dm1GvMrP=1FGgl4-PG9i!>BE& zp*voquU$Re$Sie?Vq}I|hn^MVGnBMy?`dQxjRU3G2gMN}_4neaPcbq>AG_8-(mb8l zP<^gLn)}cW8Y<3;(BIyUFIW|sQH;qjKBE|uA=NtTqMYxiN5aUA3cjCyiH@WWd`F{% z^icR!odw^Sh*dtdL^1MP8b_?Gs#UgUc7jX&P+x>I70OT90Rw0ykZ zIrG9EXYcC*+T&91tLk_E9zCe#CaS1T54~ecrMWIfT{$1qSS)Q#wK&@@tufJ$HgZO} z?N#)yJHlq1mGjJPH6yT$o0oIitJNzUVKeq>5dGNp8bTWUpRMNH9wV$$1lCYm)%LPi zr@27GXl=*SjI(mCknNS`4%xRyLN#(rBd|t6O}3Y|i~ZcW5%%pd(4Fn2#W@z*w7nd& zwV&JX?b-HoM{*rkn-Kf9BWkwSB>J$iSI!KxKRcFI!O?X`?Cq{cV*hq5&Gt(3uTs?2 z?AX6%)5n~{?J5^DV_#DaDgo_l%E2T7Tv_B>ZsQgK?uPwRWfA53s$n}bCYERS) zVmm7Pdd5EZ@5#QR{4%D{v3?^t9YIJ^EJ>~;#Xe1bN!QN8k+A;|q3_UsaKXNoG}-Vo7o(DV8Kxl4416 zB`LO}{4y54D8Gzw?@CgB*$Z6JMfnvtb7v9dmvXH;N%>`u=s{9`*%x|}lwbCRUZkG1 zt$jg$RRb)cv=4c0edSu3QQkLlF(XE6Ln-nvBSwuIO}xu!QYl{j#5mF%l;g~MM>_H( zXC9~r6iCjdZbPmHRM!SN*WbdMk_3!42YC+w&byGG1S&n9OWF=>7khVma+Q(O8d2iN zw{lY}!x3>MW)INF9_6O<@YF_>n7u$fJViaH7r#>eFpT7{wjGC){Oz{m2$H{D{xFi{ zZ?^?Uk^Jo?|YqK#UDwpTB5a>drO+I(y$Jl2m64jwadTY{xOA)Z>~%W%j^N>vvsZJ9dfvu50XfT`7@5Y)50Sq!44S zy2aM)4%(+|P3?O7lr5;9BWg^44~311g7|sn8ZwN;{9C9jIJ#Rk`+{(F$_& zGSG2BxqLb3Sfi1!6`-SzQlZ+88oYXaF;>n<-V|Ti2|Av{7n#I)XXtw(IFa)%@Q4ZE z1kSrg4$_qpTdh84l_Xoual>w;`e1!ZyHjG@IjYzLwCx;c)T?boX6@L5$>W{o#OMP| z>kbrcG{-~xknG)#koG0nyOq%WNVcXUtLioCIgX{ONA&0axZYRY_=W3|R~zvQ+dq{3 z_J1Xl+DI`*Qf(x~uo^$rh$pH$I0vFJs7@gzH38K%W^rr^s)N`T%|I!^wkQSFeQb;7 zpfq4xv;d_6+oDBmiACCTQi8}Ow2aDll3YXIMSJK%KcT+FcC?{h zM5T$cLs_ED)rL0L->6SgYs^;BI#Z75Ezy^v-DX>A&B=Rh<3S{OuWhgOC-0RevH&JO^j+Cr6G%$`8szkP)d2Nz=?&BKtk+8^rUcU)rkJG3a_Yj1isy1!()}%a{md=-V(t*mZ7PpF$oe-_y5Y+_+Sx&%G1B zVJg&ZOsVT;N$38qqCZNBU*)Bg4wd_#-#@9WPhLv(ZS|Stk5bkby;6=I7WHj4w6v0o zmYsB1Tz?|X1(cs9eOn(?b+6Pv`lFgcc`3@f@t5rdpZF~PtuI-ca%oV~MJ#2vbxB>#KzPh?NC zUsrSXvueTlGn_SN2dWmF{|9Hy*%74$=fC2tIs0R_;Cw)K1Lp&>8#%TK53@rjyPdKt z=Riu;0S9nw9a>PkHRWyCz4W2%!K^KNqCSNFcq7;QXE$-wx86K!Ma|aiQu`n~fwrUW zgGl(BsL_wz5^q9tRIhAFomT8^dp|pVwr2;?`@wb``%=dd>ECedo88RO5oI(}>bGQf z-22$6vyA)hLz}pn8hzL~kzE$4)jVrXofe^-TKBT&?mg@@Sx)XAG~!#R)tmhdZvlVH zJr&_@_NA+!?%ilBw^G`RedBIr2i`l`rLIG`iyiDbgbI#5*_G}#@OF+p$>H+~cW~A* zbl}*7oTKv{!|h1kj=>R%PN5@v!qP6Gb8v*dbLhkoUK6@yy(q(*8G1$3h6?0!A%vbB zf0i|1kK6sx3|+Zn|A<;f*Hiv8upxV_=7UyPo_nUp8Q$YT?Iza?*&jorC(p`44~{=) zufF=>r`&ZtGcp^oGpnn7OvnmBo36lEC7o>V&15a?Kxi;5FSr4A_6YlzH zRuT#UA1i4Vy9L%`zusSRU%lWA@(IiU*N*!e^*;i;^PgSyWDGIbny!j<~`H)Gm{ z($;gy*U$dId(C3^p6=mqV7JgcT+5TLV`lL$v$|m&Z?c{!?77rr2RghB&vM5s<`~yy z2jcHit8Q3J9cL_PQGS?JvfJo~Jm;^>buDK;Yl>>tKUz+-_%1x>k33}#_$*uA)R zaAtFzu!bi%7ec?v2R!FP=F*n)6s^hfIFF`2JKOz{d!Hli6z4$K4nN}BHO!?L$(?`U zt`ESjp)xpT(1=}zo}=dTafXj8|I}xOhSu&rq4i>;P*IQ%`<<* zT0>FTlv^#?cNa2ekwov1k%)1=kVOvMY{p?8+6bvZkQxLAc7j^LSj@ zz8(?myMeCn5Tfl7usS-DFK0e+U~ckdp!1mn^O3Irui_ZEb`{u>TF%g^#~kNC&4od0 zePNi2g*c17rfag()>O_Hgq^WmW>PYXo$|WyOJET@FkWc3cGuVCaU3T%>iD$ga&Qve4htRh0GP??G<2hTy;^6ub zi+R#s*|gwX^l98XoqhV=VNbA~x%(YM!xF_fwqbb}wm3@(& z<$g$bjlGl(39qx$(jnnh?w=RlV&|!O?Ckeewg8xNzq6ugvcdxjN(STIV)hn1WW8%BOySj8Eh1oC6qb2yOOi?Vv` zIo5~&*c;r$PQIJijcgQWn?hgej1H%>GuZ*)D9TR*PiKvTk<>U9JdM>2PG|qJQ{qm* zr%-Y#>l&Ov$+t-xgDWD48^iwL$<#cB^)k-P_75jfax$wh3}esWZ;?NV6*D$d zzJ;`3*qZGZHh^0=o*4HMK9QQP^)Qrk*W1_-4kE1ww{bi^?lF8kS5IK2h{5b1d>kdm z#}zo%hl8{AVO=;j?h|}0SC3;gjdfvda0QNa;ZV-jhGV#TEUQrrWZ&PT$sfZS8f(Lv z;5r;@1G^K1eqcZLEoK)Sb`NDQ0`}|GpVb%q8f#%>tb6e_(DgDh*1Pxycr?e1XC93& z;jnB?$gwWRVdPy`DaQ&NM}S9h%(248QJ^byw-TAZm~(dmTuD#f4(2Jz(R<$}Um%|kO5c@mw8coQ_4N9c;7ZC|Yp@WM zV~dgT`%$(NxwNuRAfT5TCUvVy0ThexUT2->!z77y{1E#Si(_u;P9(CFUC!glDk z$D@1NlR9u$MR<(*?jWm|{Xy>7lC6p|a}{^6Rvq{5gO1&fyE@Y2z6pMlJ0FjF)8pLr z7+SdN@;t!ZTj*2$xMw9?a74C}G!kvz^<~uQk4JYsn)~mk_BJ%~2RQzo=R6KC(0ja= zd)L5SR|aS<4P4_BRC%p$t;ULh}g_a>VM#C|C!xK-!j`$XOd~ePxxmSJbIM(55!81<6R+_;5 zPe+~lZtgq;E8-rG$U2^|lr#qJ+>3kf;>sbcozsH5Sa~P32zuoA1NVdXmxktW`i-3J z5BD!6e+oKpDHeh|VCu);h~#L-wNufEn_(gJKz?*59T<#(a|JT(0Aw({^V=K`i~!A8^^25ar$@PWI&!Z`aEx{n=x(Hy=p|b~cO$JtyW572@fuIO6m80VEY%xa!>D)Y z$bWbIRUN4b|LFzvY4?|O6z%!!hv;dqg0FJt*;ya7i?gFdRZs5|+*j0bTz5E4JB>OH z_hQzV^ip;STH-6EQP{ z8Xdk3+{T^S6c>YPYHGHpGoqkna~@}><83esME&!0{12`Zq855Oeg;<#QJ*|Lb5y%6 z+Rg>!ujWY?A%7c^Q@j5Wm~otdRdY=?5y?#?0s7RBz#maMiIRz7Jo?-8)m&+4N{Dd>T%8=oaOGO`TE=eBV~Li-GH7oj1qOX8>o9dzLM*)v2P Q-*}@eQP3g1^MKas%mCcnll~xea}!HfW^7 zZRoCbK`pG?_&>A5ZP+$*z&T+j(A~XnMyFgh5?)#%o7+$Wx|j=8--SHMHBLLWfKqSalk&iNr5!1a_F3GezC zMid%J=n95&Kv$~B&|`K6)n~G3RcBF4$>kt~&*Ed{kgCQvewK3_?`8~WT5P@6-K z%@TNV_lR1m`gcU_U1L&3H57eDq8d$Fqqh(5o{`s9)-&a9D>?pC9$q{Sbj-nBvqpoC z0m?Z>XPuFS?waLX2O~H}!xP4Gr33ejh10q(m+N|t1IJM+_jRW(eYfS5SI`5TMd7@; z5%l0Zr6tjiQbOr4@&%60$u5KTOVCe@m2@t)p0%2s4*}Uhlb&s)pwvGYS}>}zHn~BO zf(K`>3{7#5;ZX9Ag@{TqHc!lu{#_Sju*$6aB zF2F6_A<3wm0Jm=j8i^B-LCry*`)~4X^%A09N57&}>q?3LyXbaGq|Z;H z-jz`Ae;3_Kt5wwdS?RWlViOI!&)euovF`fzNfbK<+H^O!Dq0;&ek`SlhCdtK{v*XY z0x#VT`%k+4M~an_rQ0F@Nw-qwCsA*r+uHw2=+!iWM#%wq{NDd%9SKZwE3qYC$!^S*FMRQl~IyRMp`IcmXc;5>s%{; zZ*VW9#f&IDmU7fnPzkC)b% zkz(agQt&6yZKBvjy`PtE6UFLxl5PwCC3GvrChGk(y2XiuVQt2R`mUM=oK ztJSGjO0E1)>XlaYd{zFPVx{43pNVc0tyZVrM61=QH&LuKsy-wQ7pYfmsYthpViT<< zx=ob)MbT~Y6zWSXL|T>_ZCTg%OX~(2t>^p;{fg`k4j0P644&i8s?L8JOg=@pCtft1 z@?o(xYez1`{^pbnrp^-%U}Ic#=3PSU!REIP(hpL$Irw`t1Vb;#GD)Y!6e zQ10z40AnqU6KhY-NHqNnMq74@oU19E+~~A4(@wtDH1fNq@Jr{`8vSk`mQSX*QDaDr zB$e|ti=3w!oJVVNI_K>oPi`0KydAVYjS@MqD@m3{N!ScDs<90vj4DS-=UBMXQ4Zwl zJ!!0b61Ajxy}zyksUNrmtikV8|JC|(^~XBowZ7Pup6{a_tqxv+-0B3Xr>L#gp{<92 z#@QO%IF#csQl3^-8&XGc=S*ujry+pOc2F8Q6VBFCLb-o#ptaT11L(}DQ6zT=a@Qc| zVh*6Sojt1dUkP(Vi%A+$Q zJ^1!@d6y>Cm_^$;KVc@v$&^fqzqvN3j@g}Su2aw?zMX4P6<4Hj<=u(=w@G|OHCDf= z(Ws@Ajt3|3)ul$;z$kE6&ee)6(0--V(2DFvyOwgU{ph|=rJQT&NGkQNHGb<-+Q#1E7at8uS+-!y`1MDDQlD)wlCNDBQ3|c#Oq7=G8KRVKKN0N* zMk|Z#n3%3R56yP8-#Tx}emsSe$+4fy2kiImI%`~l(nQ_BnQ87rJ2bYe zI<2$R+&xRpwi^^?481a?8(%2xPBw^q=h&w5`BJ`ObB-O!xxRp-8}jkA!mhK+J5tht zG%L2LbI&`FuOJoU#^veGSXbM0_H2q6?*SzkGw!+)&U`m!+U@THW; zey`fGhsy!%@y5Ilj9}8%Cs2RyMC7lWAj9YuERO_s9 z=Z;I+Z6d9=;W@@%+W%a?BF+6UHd9%lCr5v%RNk7Tma1&gE9%^v(R`~Zpd51wI1qHc z%@lHJZeIt!qchm1P&$~Svu-An8ww8L>&m~?_M9CkZ>}IIp(j(rwpK>j*0#TNpcESg zD(!nx+t#r~)ZlF$TSFcyJ&XcJ(b{QTs4Q}pvdD4Vd)6@_XV7USbOt+9Pi@*Zl9xF9 z)-S4sVCy)WOKMSDYsYtYuCB9ooV(-f-J0ap)?Im~1gyb#Rby>SD>eZ26Ss}+U5Kr( zo}?B(mhYMa^+)SPZbR!f2G#Yn6`F#LxRZDvY6Vh`HW(9IKwU8DP{z}$KWSyC&l+QE zE4oHSE52Ovat!CZEoXY>hLdYS>$K$SGE&d4)F)X6s?R2VZo4#(?b4if=}W#Z_f*8T zsi2P5*-*~aqtcu-XQMd}t&}!ZX4o#Jv0c=_dy==s)gU_au4%@xGQjoror`R1IxpGZ z?M$|&BxC#3GpcB43SVFfWs{&Mb=tIdx3+EIN)uXX5Z5L^g@Zu(!Fci$_~HY}jRnW? zjn%K^<4Sq;Yh}HCOkc(rk}CuaAU6tho~hcdQbCE}7=!B;)C83ZBV!*JNln)!>Cd?< z8Po#Rz8gYGu5IAz2d?$t+6Hwwmp;hu-Rm3-1&L$q)DgKGBjh>4)R(2=PCUA5-CjO2PY_Up8o zO`fazChS=SlDgFda#|XCE}Rpm#^HLm+RE)otw6O3wT&{qslC-1bK1-HMtg2;Xj%E( zj-++26|VN8?xLPzKbLDJo-F5ezHB}Eggn>Y+89*YwRIY!>SOjdbv5-g^)huh^*8mk^v%@m{E}*R)!(6AdukNIB!8XnqAjRJsGmxE z&|hb-_t)sL&|*wpivNA>yJO4BAAMJ;F^x_n%B;%&Z==soe*b@!9;AdSs*n<-%pyJ1 z_y>BB5{gtIC8(h%sz{We$3RL*9s{W&QG)U9Qbu(e{_o{E)!X-fTbq6wK6ts%c% z;+l2&?up|R$R&>Bszhp8avWDBQtz^LU6n{Zttj2?m-cpLxxH16~7-zz`2t^MVx6~4G{U;Q2Y@}8%bP>y}k zU%0%y`fv3&7peWf^LHz=(|7pdY3k#@x7eTk-S!5fY^-B1NxnI?E_r6s-Hpj zTM1|nw-?s{?cw&~nxH*W8C?sshs&$==cc3Q`izo>mV8D@b4xy>q|qgxQPT91&nRht z$vQ}yVe%OzjZvRb`X$;cOi$xn>i&2?{_p&~>YT;jpT3A1sXEr@`@N|p)P&XTs(x>3 zH-GhxzqcscQhUnZZCl58?DzIIeHm(Lt}>@b!&Yrha<7b}pOtXlGPbJwxM}^`s;>U# zsuljK)+EQ+{Ecm5+qze^_ONZM_e85$3!r`c#qG&!4@)s+r1t!tq^C9DTwTbPOYf{+ zRFpF5&3#+n-#7PdeShEFxApyfb7|1`_sxA<-`_X)ZGC^=+_&}peRJv2_y71i+djoN z_icTD-`uzL{nMM5@pPq+)Nfx<>S&2bvr?~PiSXl#d%i2bxF%m6 z&K*UTUQ~KiW%tkALm|7HOtPE%F1oL6K(C_b*b;e+|tf zYOxiHG-G?Tszx{}nn5!tE(WpGkfHwe6dDLXn$&G9UZ2 z_ARz-J=!<%gd#WFk&o4g?_7glptr^TTa(}BEVK~6gS$umt96P`(7)poKg)Bf)7Yow zcjP&V&&Y|4c?qELF7l>aq?^R8jFzZPiCnAz>J68A~r=#d!T*MK55UikJ?x5vG!g2uszv6 zZ7)|ZwwD)2%H#oR1@Z_j^Q5;KM=b}@&Xj}Luk1(mD!p>jWU{mDb@n}bVU>T)krKH| z(Pw1ewGYdGq`73@+1u^&u0rbO8-C-~4Cv|7mh9=|V*@vb}cH->TDp(%*{GtxA8Z z&i6j93w_c%OI=l3M3v5&^tYns`T2BCX|3wb)!aV2{!r8$q;NI4f2Kzz%}qI#Cso(n zlvL_-RhnBJ=p(JJT-4c;wq|eeJM7r*o~2U9cN}kJ1rSCA9FOQgGV07RhO`pBBLT)i zxsqjdU%#u^I~wY!Kyh46zrX7y8sDQI-!<{|vpYWOYU1PhdafQ}2_?c^f z%S#>UbcX|Zsbg%e94;?)Y|I@pt>pG0!IEpkft`;_m^&W0R=Uxa>J&PM;h;8FhtQFH$IvNgM|B6g zv+fEj+EdE>jL;!yP4xhKuy)G8xFX7cxF(6VRq!k}owvdK`Ufa~H?AAydIz3%s*hrcKE{eeTBna;!9LCkLdN$!j%DjwLgP65JvOeZ0y*#L2`u38+e~f;6 z3R}<>e2mx?T@|N<#9EQ0XTchr>GydSbd8z<={eA~VlIp8u3W~tE3P+})^E9#xa ztz1sJjFo9zFDPRkXPU(T8JGq&iXqqaDE(5e}NTK zTqEluuDp)@dK@cC)gqk$x`t9M>Kq3aI697aBIwFUbx9{-2fNacV@oGt2fLz>V@oGv zH`gX#k8~=Q^r@`5qo49r>}*%M(Wi47mUjd44M}HUmp6=f25SN}C7lU2;%M~Wnc$hM z&C`VRU2OU$5x>i7H_bQ`&tmnOW~8&T3XbC0tTeMHYsH+;4AdWxTge(SKZx^I&u2#J zd2wFqxg7UmotahOIUJW$`vUL+)-Q5q>-m|purFkGY6VZ*8(&BTcn-Dq=KLId9?ol- zNZK1;h%*=UjJUeLK9VVTL)wGwIiHF*#QB8IES!cPq%GK%^XcTB`K9O9Icn442g~@6 z8R;U>S*lr_d!5BO*;$;coyFPPS)AdW#rd*XoDn_~Pl|KiobTpbY*##S9-Q-~orm9w z^Vu9{#d*}ObK=@2&aX~$^=IQ}aP5j?!m*(=J31T#elr{mej|Jn{CfBX__gqL@T;We z;MX{QC44nB2lXc(6z( z3eR)g6z*howbkHiRu;UIv@f_XD;?fRS_`fX>p<5RyOXp5+`x*AcaruG50Ey3cXGU+ z<3`X`yzV0%2;R@Jb*@eBuFxvi8f=+s1-8hw1e@ntfTg+SV6$8)*fiG+Y?5mVHqJGP zcvrYPG|Dy3iFb#4Lc?66oOn;TH#EpK%!&8$zZ#IcFVx6A79Iy555EV0AD#f82v34f zhNr-%!qec>;TiCm@CWb@;aTw6@W)V-du!xs<{k}?g<4?ET&>(A;n7eVtd*;sdpJB2 z>VUO#SA=@G60jt9dAKZG&hg4nH&+j=N9m=MmE^9XZe6f0r9Y&sBzJXqn6j%$SA|O` zE6JTl$<^V!@DRs~DJ#ic#IYoIVYmpqAY2HZA1(lwhGpSQRwg?$e1~<#mPY(e_-*G^Ss~p9mo3~_c6bjH8X40b+1_y{~Ynka24Lat_thG z5ybieTNmW#y$@c_Jz2?m?#oK_DV3Fs31h*rVH`LvbOhh$7iA?c^2<6Ccfyy_x^Oi( zoVW`)o$;b{b+`r`Myx-pF8EIxN>21-HJH@3L7z(3;4@Y4Rr*o7He5%1Ego1oKMUVW z$8p`0bPxP9T^H7ZgNS>P(-VJA1Iam>bT5299ZR}&xHMb_mLV=hY7JPLxNNwDoU(*6 z_{+P5R7uJ%21^l_Aify9IIPA8-zC&2&edvgb+{<}n5-r5$K(>qijj8_cu`mtej;Bl zmIHY1&!CVc{#wN{0qgcW#XESlnqa6vdoouBcVsmH2cNFPi+HeL`4Q+6Rf z8ViHJQmS9gKA|sZJzN!})-xxAUuIDyGOxC!@lq= zInShC>h^`llYL!&Bw{pzpc8;NI{Eew6c)dmwovJRI~Z_ei)S z{1ko$e+~!1gW(tOm+&k2YxoWPA^ZsbNUb~YiK%yIy)o}k9u5!T(dz*5ov8=TJMpcV zhjbol=+WyT{CYhUc83RP<#+H7;%(H_JDPqw_a(c-9`I4(?c{93hu6MjPk4aZN!A10 z@jIT*vO^9qN5~20q@JF>_Tb}dPuPX0vutwp^|cEhXS_==D`bP&l--FJuwCKK)JNDo zl-`YRu|4E&!<(4+5ZB9+yTd(UDY1A@xHp`Ohst}ydE_s{6Xadt?r=VM9{w`VCI1}4 zePKy*U)TwrL%clM5$*!-qTb?UXShEs#wX{_Fge*Cc7Qu5J3G0b|LW}I0sgPEsdayt zg8#E^;C5k5!S8A|;Y9F6JdtLnK1s7vf1%l_x6ka<4`+7jT{AoNkeQu& zr_4_MOlGHE9J6_Hj;!p|vs^aMn$7zBWh$H4M4Uyw@{54?xop;LDH?qo^DI1iW+&gV zMtsLAaT4k8NtMJuVO3-}%kfV*F+9#X_&DpKJ`Sr=a!P2DR86iAf8~q&D_`#&lul%o zo5))EM0he3%z6PVpH(pHui<*;=j+1_U@meCg71YFLR%;%{2>sI!pmM;;`YQ@_{cN2 z15{KNUh}*@f~ze2=y}~TO;sQdA4hmD#j_D!PqP@AwV{$6v0}|o1FS{7mwZQU9pb%E zO?4Qlk5amyP@S>9KgDWLMh8e$W9-(Y-Xl;=b(tX!kpCE=3gfsQxer4%)dL$4@4=H} zL$CqYdq_246h21H-B5B_j5f~_*v)li=%nU&kCbAPLXwJ-3i=jLzD@Cwtat9FDa9l` z)Fh>zq^P8rnu9G<>Zv*RNHOh!Zj#25V$z#-7V-0x?7?q#7S}5|G2wa8GZt0`Ph(g~ z`5tCZ&t$j|Ke8`_FOhoz-eF%!E+FSZX6VmyTINh(TO>Eo0x(ubw=loXRxk>1nw53iR?J(No$eGcj? zQ;+c1OecVP zV(gP_VGpRcjV(dXQbVDT`Xo07eN7EXHiy2X^%}W3=!0r->W}KU)Hl_jWD_NuS*Lb0 zHqT(kI1l<_1C+sO;OS5w8%Ui3p2`fjfz(OtEjNH0xIU5H=0ipq|^2GW*`mx;CEG@ow;5 z;_<9}_kuf#$Ft7u1Ro$C&r1COxQlo^dxBle*>{B<;CSMRq_%?-h$oTS22Lc_FZwnp znGc~Y zF)MkU)Sb`=(6PGW`ZV}7l-gg3 z#iv*ue;_;o{+0Mg;wPY)53)nlHuNC0^g$@;ddbi13AGdb89LeA`pHk!)@Jl4=;VXs zHb{QtUhPMJgjzmGZpGvY*5itlJOPz^klbpZmiPyQ+9L;9!z+VT@Z(%E@q`7nH%v#-lpN3CNKc|BFB|`}<;nHbhwNl9 z=^;=`>a2KfM0Ro<>A^vLmgAtC^anhMtK*=XdXOF%v_>6B&LHTfp5z=$&Oj)HUZe+* zJ{B6O7+$?g2X#|Qfu*5~ione(3%yhfRHwciR1=<#g1U1hDJ=z!RG3tWpw4P}s3vr7 zNtb{|QfKu?@`{3`9A4O%`FrG7E!CUu#L zkW&;oN$RR_P?xDN`9)IdNjgc2su1~wQ(8%?$dgWfO=+xxL0gJ~lom=UCg~*UDk&x@ zBx$Jv)F}wXBrPS~geE#U1)!J`()ny5sNI$iib?&krwC6&9jWQ}B;hG2CiS&EDJdsj zymOQL1bo!ocwm2q{KrXqDw4WJp4OBDis`u&^Fia>Mk*f^Q)g;C20ykl9-yVD4v_ZD zq>jW5lfqervKl5u;AAvRio)B#w+q~khDmYw9}SZd@Io3UCE<(Q!QGK=$^*ruefNIC z0sKklh7OWq$_+|gJqmxg9TZVJYH)rToE5Z|Xk{C9bEVW%PAI1K)Yu1Cxjp`*rKR?g z-UpAp6t(fT0#{}SB~nZ|poXNIazHV)rPd>ay?Bq7u6mf9NAMM$#XFT^l6sP&YDE6S zaKb#R$}^S%^im_z+IjB=cSE5pOZ17f6x5@?o{`Q4m!@ZAGzXi*5!aJ`Giaoil%11k zeZB4qn$;)LD?|DS9W=OF6F3Ov=Lv(<}5&=p;{>l46pYk%~&7m85Gt<0^qxnhSb1 zRRXPa5_k%608{gDdbkA%E6);A^ZLud#*{%sNQBm6);h zdZtF8x`6StR?lzkNltfWch7b89M^87^oG`*xGO2S-Q9@Q|EmP57wDK2^|#^J6P-sL zb)s{uJ}^XQV<=vBzGYCXTUw4;d?;3!g_b=#IWY6R-(D4q0up#rQx`58B@}TpvI;#6BS2}a{cE%f9ee&gB=K`Jg^dzRoHBWA? zO)4AI$5<^=SzvAAnxsOi1(*fjnvVpmN$kG27yDGdsXl35AM*8hUW+Tet7d_ecrnjCT#>Vf^qJC@ws-~i%dc?b1D{Y@N8Y5==bJu?j?M}GgYTn*wnFF25R5cx_Y^h_~` zciRa0gwiC>i^&T%CLYXne$d%N-|YFo#>9GP&kt(HF@#cO9?nIc4OS5Jq_CmstTmMU zAy5Xcr^C{@PHLeb>1M>z423|~-{F+%_tx3+c&>|p&X&g$^pHE8Jn4!eU`yf=q>6&h zmLo|O16y$|)ln35<~)Ji;^2{7pODU+QX|DuYNR-*zWpddNw76FMy0c;R0{hkzWp{} z8?MH1&2EaTlHgIqV;C1lL5C@Y8A~Vwwk3Bg)s*K>Os^JVBo7a2LDsU>aH1)EZ{C7}`6h&<2p zX%6bGN)N6r=xP19v`)uq>vTM}rfwZ_ni996W-CySFZyvklK%X&|MJ$1?zYs>w`X(i zX-AC~U<>YPPyM6lPv>^MvgwPh74&7^M7aV zuL|miyEC~R=tKP)>mQ~QJ=2a{R{~|ARfxNBt3Y$V`zw<6wDg{YO7urp?(0R}u3#tb=X^@8l$I*zbT#Qs-6O#6+}E4H8GY2~ z#oQLCeGK1r8PJvG7|P3my{LN(p*M5c(bVln=)?S_N9qCTDl>q4N|RPzI)JiXU@xu) zP`3{=*U`ksQu}DIKk-2B?a%z=dNhcURub$-?LmZ6%uoHPC(ociGn3T%5K0Guu1Z7F z)oKWL7AHN3cnG!oF&ho!9(fppnQM+EcQ`YQ^O7staITAjL#Z>I;7MEqxjLTO1DSE; zf{dhgA<%hkB%v@f$}q}LARNyu;>t3LFoOBRRc|!43xdaU$7sSx@C2?#lPbgvGJ?Cu z5KdtJa5WsuJ^8`W#GKnlJdQR;fv#WU7&}mFT#o=bL5~^4wQ@Xn<^{(Rk0f>d-q2Nq@MGsEwe7w`+v{ceHla)>#V*?ZWlSqrV<4W3^b- z3Q)VE99&0#7}_>#XXIL`J(Jc(uBY0S=)KF?tT^%{&vxY3Mvd!-e>%(ce% z*pgrD8syt-!GGfZ+E>5odJD>M6fUWw~t6=L+6h(#%vs-)0)B1RXASd`Ln{}g!p z+S24qQ@KFxF0}#+^kx=sTno&~m93K_&B+G6uX1I}O<7{??0=DGov0nA<)!ui*YEwG z?d5$(aYz5>y}Xt^aYrBDaNN=V^Syj#7w=x)K8w5fxTDvy#~ppN>~UxRpX}ui?c%lU zDav?=yLi7y_ww5JG$-8*EW}v&^Df?R+P!?nvd3L~e#V0%!M(g=;m|JLJ$>GEm3J5K zY^1hH9>#(rP5l%1@{Yi`qmR4zxTF8`US7+dY{r9@J^yMiAHA#|m45M3IeveR4R!B) zUzvC4+8n*RI*Qt*W574;>hJ0y#iQ@Ya+I}C$41L^G)B*QQa}2gEKiy5&9~>cjkH)C zIq@CF5fw*~@3lz!J`4Zt3vfh9FG(#)Aw|kBumpPqU3=3JLvQdh_swu$zQpnD2?p@UolXiB!5S`mxYeeTZb=#fWoY7om#7^{+Yfe0c zuLIwT7If0g(#g(qt}X5OUi1U16tjekb*9e&T3K_ZTJ@a&ZI{~=Qb_p zw3^eJPWw5>mNs=-&PgXb<{V%4xhs-XQVV+0Z$Xhivb<+P*pOkv5^iAlqvJ~jss*}FC+UXmuoxbDR>09^oF;AMSLy4!)X_M+n0oBtt zQ9XS()zi0Co%W;e=<4a)sLqq^;aX{LJN7H`Rn(&AeLwQcYjIs8eK$48bA72ruC#3p zezRX#)a-U|<2Nj2@4Kpzex0r^c}Pd@fbYsL*{?bW!F4GYanAJGwaJ~6YgJrx;`$S4 zG2{_8q_Ubha_KfIm4uk-KL#zS>|wsh9NT1TB<mOhESR+_Xu)I99 zWyfChbuD*S4d=KnJNE3OxG$_gZ`h0W&=G0h^k5{}pMjFNE_*Uk+>N-4m+GlOPdM5f zMV{!UZMb8pEdAlSY~Ojdmn&XokL9RyH(3UhVsJO9k5A`q*K5a@V=k`ouIbMG?yKVd zDsp4vp3eS|f9xJB?xo!C#ob@Mbo}TE(jA6WRsD42$WgX0-BIb4!W~K6nK+g_B_PsS zj=ackcC6_`)Sir7d#ht4?czAzB zuD-n%`zZF8BTG8aK8$ukFY`)+J>p<@w#t?QxEm5_Z%%b4m}zUA|He=lQt$+0zx6HT)9YZ&moVEP6qhu-0 z^p21QjFY%FIWFAyG)TWWxrBbLdAN2Yy1vEv-qkyvlI7|bS4mgJxJpN9NnDc;?UVGo z;1}w=;2iJl?yg4(j5EB{TpiwqYl?3s;lFj=cR#K-Y*%^T0J_y_EAH#FnfbiaT}KXn zYj@H;2)UpF+?z=gXH*=W(hn$f-{EC{SYo-5jZT{>0=`YL2uW;S1L-2Hx z+FaF5-?zU{u1sC}q<-2j{?CPYEB0LjLecb173Q6~w) zwfY6NPQNsFE#>+C^-X_N`lY#oR^aE)P&%UwOoPq7T=4lUk za)Yz9z2^B1uDte|r^Yzj+iORred7rO_Mbfzd(D#@Dsml9YO<$XiQPHaQ?3D3h&!Zx zW|eEH=U;hnh;$WYVH*nacH(r;dx+wtW$UxIh$`0~py$vcbGy1cMRzdOU1<{d`r zUO9M%>epjVh8v(4oyZ?>jw;XB9k~b2;m%Y?@QpivJ3EPvuMFqGJwkVad_f?@52|ugEL%goXc3e+5RCz2*sM&WDjJk~xP?E=lx2PR@jptK-Ouz2@xXeAqM{Z&D$SFF8T> zl)dJT*1mJ5vghoZ*lW&F&WHAzbCmO;yCAtza--}a=P2hxspQDZa;9=$ANk6TGS8TC zK6I3|WqdgwI?CEHzMK`^J7suij;IdlSd!Bwmo0j*a$h7*P9B^+6wjKJV<)#Ro-*mk z(#q2@=E$nV$co;xst`M})TD7fbY!VvlbH|ozvX=Be#RNmvr?4zL`jhR8mS5;LCOH+ z%_<3!zaxKJNswFFKi-3QGkcQQDWcn-N!z*)p|$(szSmvbUd z(uzzQwi5|i;9RawqV{xf4)MvPW`Jtas5d!1)tj7&zGM^HJC#`pyKH)>DY}z0Y5O$F zXQDxQDy63r=AcJ8n^w=DWH#EAezEfiIYF)1<`J|^JAc)2jNgqIP)a5*DI4>vy=6umFwPbICc6s|DZ!?mnNqh2TP3)tYcI=zP6AovGEK zHGeUAE4X73xQM4+KsX0nL99*DIiOaID|yyZP;K3n>3CU1$+=h*oy&7BBJVtGiI&mo zYVww0MYNjq#XKQ5cs}tOYODbD^RR|H&cm)~4QcI*L_I%TM$0R~m6TtWj>ol>VADic z1+LOwiLy1|WyDvIw;H=5*PAPOPHs?N5LzFt#>VJ!YOW(-y~NcTY>e~*q219X*aNwP zzJ_pFaxJ;oFi~=8avj%~gVzwRCl@;=O4eeJMdx!O+Z)>M1^7IeY4lfH|mYz5uD z-p%!G;BDM}H|4jYJ-n6s?xB1uI>>jEe_uM2-p3R2lfHvkP3Sw&ioTs^?4<7P=u>Z_ zZMCbnp;f(|mejG{j{bEUT6&N*qzxz?vx|});11e;h_ZXY2Zqj<#(fp z?yh1Fp%8cVC58O@sFtzUoA0mE)_`Ogv#V0EA!_H%^7sU^YztR(kickn#n2@uO~EGC~P{UYH> z@CD+RX#c6y$4om=-p0$6JPAHY+bDgD-LQDkaZiL+P&THJ(-&e3n=n z%V)8te1)2C5MBUZC)Td=1yEl%e<8e#C8d6D-s0+IY$#vijHv12?T^TN z3#-aEx$k4bd*Fv$eM0U#;77z-X}$wWmwn39ih_E@`HZ^nrPi3D{&2L(6!nVpC40Y) zU`N{fitCTSFNnV;??doI?*4|{Pr$E;zfE_d`WE_x^ru{XOX^dsWIyIf-*LysSk8V& z`g_9XSi^q7eShW3wElB`;E7*?(%e6=`|FI=jh=>nBKK=hA45Np`VPCAuXxVSlz)XS zjr*X3Tz?DxOni`3acpURqUNuJ@4;V)eENp6i#PY-abarqjogEJH#O&}hPs+wJ`{K@ z8M$aV!HOj(SGj{cgWRDDPt8MKf+bCEo|Bgl@J4_MJD7(!KXDeA9ZF%xlSN#Bx&aKd zU4W1izX}DwLWEpkLE^%+pBt3MEka%{Y>{%&UQzOLYoo*+MM>qw%R>?JixKi+_mrQf z6epAhi={dF$SXnJ0{ECHkzxU!P>N6pEJ<9NrxXUIq05k41e>c;#AV4V3>N0@a^w{O zi_mI$o>LmzDmk3dBSm>iieU|2g7%J}b_oz$EiA*2Ag3as6j*_{5>F`&%1xr z$k36Jme>up;=WFlv;tdmUuVkNfNgk2XKEdZ-C)XR;~EVe@{YoKuq~~2<&L(gEnz!s z1>4b{R)p=a73`gK0JSadNnU$w1>4h7PeNyG1v_wGFUt8%wr@TA9T>4RZ zELZw?=}D^tiA8yX19?ux)PAuyzF>OM_8{))g{PQ7q>m%?#X3^2DTBG{i+`EEJYz`E zj$|mg{jsbZOgxOI3;>4^4=49nP>(XhDesRr9I58xxvm5bCmuoVLEtdrk))0T^;n}- z=pZacN0J`JQ-**;s5L5Rl`@)=!C^FEXc$A@urQXZq2N$j9TzG?zmE&j@Z)%9Wl&E% z<0v1F&D1d39?yNlQXA(Hp#FO%5>5b5prwiAjl{yaA6BcAg7z+xg4QjQf_5#FDIbkJ z^C;SwLis50SjwgZEn22hHWvHmu{>`oHqN85%bH4h8lh@3oqM$1nnFCC`cpt{UuF=G z$98)>Po5F9cbP%{bi6*zAZI3FBB;H~OiE{jSzJv7C-Q_@LED#El+MILdg21xr`$mvjVH5~=i0Ne zi$R?$ftFKK6h4hwI7PTB3aws&w0xW*jE@Rj7v`!6RC`6za&QXs6<6fC5LbnvaWn~(>(R_>hg zszy+T&B>Lsr&UQd`O2=EKqIQ{Ew9$JT)v!yX51|wATRBEwv(r)mMyDerpNnuQq+Ii{(n~A|Iz=?x9ETEZ-~Fj_vZ;X@h!Br#(<+i$H-VvYbi&;I8Z){)?nj7?GNM|P2kQfa5V8ma>j#l zkL2NufL}72vPrZe-$wrzlWAoPe39c)?#)Q*O@W&;64d*|RN9r3GnRUCZ{)0K12LUv zWP=lkXK+vC-b{m2GKoBSIMd;k$N`!~kcTsg+}S*33OJE_W|Nu-I%CXcjvfq`WGeOa z29yJwPAn&94mg9S%FmILGn0~&s5cXwPCYp}C&ELS#r3JQGaHn@b1JDBa7|{V{1tgc zr&Buz=ofYd?aEm>k$4_?k$ZDG>6556pZqhxlZoZq%mYs$mTxm3>`UusG0XP_PbF^w zrDuZjiWbsVF8CwzhZYeQz&pvAa#kYu<}6x}hqDNrPrQWkh2TQ&I)^8n4W3DSF6~F| z&0^B7DN89^0>9);YAmDOGvSLYCFeZu%ndFfmQ%A7JcoEW&sYG;@mY~_V=f>i$L1Vr zTuAA1a53>pt|P~0Maq%609;O8IWM{4j+{%a)%=EYLD!nqTwe(9WEE{)OptqXKCP@F zSMJSf;x(jJ!8?&-bP3@i_$8~TcNsaCfGdgD(%NcpHMQ5WZuL*OFsr~-)V_k+D?zzD zS5m$Pl$&!UHP^y7xs>v&2v@){alTkb$O~S?m0X*P;FVlXEjcw;!7Guob1iLM0?O05 zj+W%!3?P;xb2WH1>*IBV0V$_Ou8tg^>&d?gyozVZ$ypBvWgXAjK+UVctI6F+y=%a0 zD3OPA1Kbn2L7ND2R$O^E6E?sdSx@d3?#~C_KrFB3Mo|8c+?g%lM&et@xe44rd@J{C z1UFK)m6kSu-D!0zVKXRa=QdiAle39>x6^ula0~Gr$kpuJ~VJCbOc|yAg+d+9f4{?7% za3`@GnFqo9iS;G03ogk{${r?nC%BvV5pwSb@8@bS&$tJ?huV0DqsF78q zpxm7U{FeK`p2P=8?FFSZ@Mp(;j}i94J=w#Zc)lZ+KeHd)M=XElG4N4hc`;AGE9u4k z@@gIj4-h}i&b}9XlSiqik3D%ck5Tto!c*`|o+j@(>O2iTp7K}l)d#=iF>1WPuPg-a zCw`GKIW|vHCjUjg%@dToM0f#Ci5#3)Xy-ZbIqJ%*c@cb(-To_tqv4u7MLoGQPr*ld zo>-2}t8h(}RJ=|rh2Wa>=8iWAk$dwRJd~Fxk#F-loD%(Oy~#atZ(btzE$Y7kN>jW| z{+sYhVTVG51IAjocKuL!Z!A5%7KDPpK{U=AD#}A|L28!Y6P{J|Oi4d%upL zT$(Qk?}6`8`%6kc2jvgRo%s^{loq}sd;|~WGg|nXClv!fA^wKaui%^Lo9kPGT$ayC zeNTIzf}c|3dv>Iqz)s}JvC(Vvm&8ACr+gdvK=NqhuPBxLkyeVqQ_%z3&$RV5_%*o) zxl>-vw_N{1d*6WHQ12Jo{~na{^DC`H?#)5?DEdy5Z=?6fA8Gk_LJ3d~P!i+}CE*8Z zgzz)DSwTLKe3=06L_Sb<=t8^M)J({c50fMO$}h-4%`A8)a)ad2$XSsalq==-g`w44nGC7as#UrBj5St;K|eh=If_W1=! zl}zN<KFtBF9E=A0<4cDc<+xw&O$n~bQ&s{jmhxRnQgQ^L96Xd#_y6eo+O|*ek*>sl^=) z2zB6&)aE`pHg(~Q$lqy1Th-v6)S`xbo4R0Ku9}c9@1zcK(;zRsDJ|D0U7t4O;WUJI zBJV|BjU1N-#Bflk*Mjnfpf%*%GzS|Kx8hf#JH}Jd{Ub+iN;BftPV2Y(uS)}p!^l+NKo#27jinmO=(NqHOMLIO6~HAJR12n9f-S;>XPzkx`OhA z=5lJ8J?*jLv3uW?c zdV}(K`tk%hIr4;#;m&SgH|q5xr!Sn69$fbi%1QgvelOB;i3U(Ae??x=v9uC7HUr?J z^dWB$cj}L-0=}o@*bD@ZAs$TKif~Zm0KvDRp4^$f@Jf!M#?YYbawyM|ha<0O81)B( zgNTQ7*ARFogK6P-LM6O&4WUHt%rJN)$MKYr)EN#ABtC)M!6|p`W$i6gY}{@>Wg&ClF5|H3{BF3tE{P)GLrbGm-Ro;%TJDf@8T;F3m)^Fq64& zdfLhia;Cw5X~{h^$)65aMgG;SP#NC9ES_2^k;fv}Wg77ua%O>(i06X(=axToVo<($ zBJIo|J%hR@az`t2rV*b+ow=Yqp_9Rrz?sCS1o>B|(8?^*v$#5y{FB3}+&LSZ&DCj? zo`RRbIiyafl{xqwY(>2@f|AX7v^5t$KyxXZPg-B*Cll*qwQ6z}>G^mD(l6lx?mq=Q zg|dazJ`FsL>qWG5DtIdO7SZMzU?X@QXVcc{;cUV}a6VUy!L#wVw}2Lw(0VmI!|UaB zNszy^Bxvt(4z0|`8{Z=0b4V@5C*P7#BRQ8)6I{U6(x6txQrcZWdI2@`+*cDX^lE)9 zrA)KP z%Lz>&&6tlo&wBL4VyTflN#)9Nh&;VfE`n#-YAJ3T*2<=q)U%p(a#Qk>_Rd_~7oQic zz|{oH$(_++&gaSp@rl-zN;Bni?@jvnX{rB$k&B*zR?^Irz@55fpybs@}oGp1tY@{g7 z@W{05_Z(J#t8dkwjlV*!TKx6)WsZOP`+SN$Yq|fAJ?{Va=ciS!{Ga~5`mDO;`Bq(h z8xYhWcNfx-&>-bgmIup212jt96*VF>O!=B>@JS&wX0KNoEKQl79Ezsg&?0=>rN~vw zycDQs3-$Vnfol0RB}cBKb5n2fih=H=d#C%|X3UONSWT)><7o0qFnd?#x;g7cWhgTL zbG<-l1#vWS3-X&o_w^#*wWS4bsVC`{T(y8!?a8&PTuV?MYku;iyVVqQjco;$s-|E8 zLVo6rBgm;mI1<`Ty}W{i0?aM)aBC9UfVH^NUcD>Wl^WW26k>LgBkVlXhMwt?_Oo1W z=dGjYv(DsZL05EUW~)w4H9}iZ&T}^Tj}vyS9q_2Xdj0Bt(m#3bZA+ycNH@ z8mPXayPk{%S4)0RXiQ!c{_~uqN|L9(XE##0xo!mN zW2ppr>V$SrzmcfDuWq(O(8z1EHJ zj}~|O%d?NvukXeijMjJdpq5PCdDq%pMQh3GX|JgT{9oJMDN~7l9sb_>?mxG?t3ywz z_o)rkpY8547I%NPlXL_{Ysu)pPQ6cUuC$xd=2+`AHA1zCjNb3+(=*ZEgci!qrVZ!~ z?bI?Bl1f1`{iWraI-c4^DmAgc8qp7GgGLKUdrG}eZPxy5eHSexwLFV{`x?_r(f5Sb zYD3adGlX|t9j-pRV9@b3EbYf(r1gwsKMp4hgOl%wJDxBce!ioB1ou>jV;|_Hk(3?} z+Os3mUOR!(5peRAAB^Juq2N%iN0S}}DnC%)GwO+|x9J=+mV0Wz=Xd0dqjU_YZ|ZRb zWeQ`dqempQMMrQoA(a+PAV+z_D6S{cwtAvth$j)$-gIu8LYw12$F91cYI2Svp30py z!O7H_N=kXdcv917OFdDwPn9=#4uKxqlsZgD3g8}VRyxLK(UOveY+~gN${1!+I-5Gm z9;On{Nu>x%8r0#`C)->?lrc<)+pk37B<`sLSKsgMWLi?1kb^iQX{b$&Q@Ec~e@N9q z0-#?`Yej6g8H0uNu5rsYKywJo0rZm^U|+UJyGQi${3UkC|RgOz4^3KCzTA; zg~P8m&ogP|RPYpX)eKeApl8no+^5dyY2+@X^?Gpf-8U^F%me39b~gEHbY#?FK0ud%o+hCt>N%kLoC}E0O~=mCbWErvdJfWoJhZr!pfsT#HPj-l51!4{d7!6R zsFiv?ttQGYZa_pc@_2bYt3G50h8m1VA>wsHt16>GR>C0zfD$yW}s2EP8q zTq{+$7*sBy{;2W=We;kODu+lt;B&ne8G*CGmE6-1Ie?@8DuSA$>Y1)f97OLSxXq z+MV2|w&+dN*hZVm6mCgn4_i_>g7>Hgs=Pr7gnFRcK{Zi1X@yvw&?a#1cW`wNK}m!2 z=)Ht(;5P2Nm!KSBJ9Y1)#&%E*)1Bnrg9P9%t{+I};RncVlJfYKG~7kmgVa!GRL#;| zw0tjkFZZc4s!YKy_N!nHFS%SKuPf)I&sG6M0D4wUK$KmcjLGBCO zuWslwwD2OKIXwPnDSzn?sY4O2)CX0L@D#NVmo&UU3$LcRN*A7n)Bh6jYouO=&;K$d z${3V4yvCI>hURenwXOOKL21HEl)Oo+FM>)T-s1Xoxc#2tp{A$Og`(7ZhoBtcHEJkb zcolq$SPfCNI?a8b)?0wC;A(?5hqv##{sG|~@I9_RAoUjb7FS9dlt8>m{2{F42IUQ&1@bkuTY~OYzG0_Q9Q=y-8&Xl;@F{YDPpR=8_bXF~QU_1|Q1+mVp#(M6 z168u{CAmLPyA|lZ=tp)%CBPDtsV!O(ZoiTSbw9razoy>Lq<>1K4r*+wgZc|Kl{9?M z^)K9`WZ?%|`<2idIf7a_zfn>OEJ>_3sImto4N4u9BPeN5-T;IsZ#YOYE0m&sR?x?L zc915@4!_c7j-bYmGJ(=yDQe^lzyBe1$VMihFZW!uq_*hqiSmX(Di5`lFJy70)Ise{ zDXF~37}_NHf;2)t>g0jXpG{eQTFnO4I91Y+9|=Hi;(~+%@c7j)Ekur*oOy@~bI(yp zVFFq`L23(4PFlo^JvE91sgk0!k{8K9UTPO3T@)-pjK_RpWe>_53X;OBJ~7_*0~Ud# zOTg(@x=@OCih%B}OQ$jhWe-K+@fW5x-ug+E;eMqF#YvUp&f=gl2G2Ds3lF~}ZI&lM zbp>^skQnfcBWxAEy^;oXMU_32CWYL9xDr?qEK6J&^hDHh#8s$=Ej0lv>Y#oUQU_Wj zO}YA`mErK0r(QMMQfE|6)arz4$N?&nszF=I8!8jmB-DWaFEv_=dpabwX;Yois+89b z{h$-oBCQFxzZ&Ir2(`fKT-62Zz{9UjsvfPVGg^aGeQK*Ys@`dX&=G1zS%DIVT3jiU zsE@2bZH9)lUmMuH=|ysq#2=e(wr6=A^}iF(LAWZ z(41D)A8kxK>Wwx78xbpwXn_Pk2}CPeQGc{4@sZr87HJc5TT{Dp(wfjEX+vvD8Jbhp zCa9619HR9fGKsdd(gJCKGKzNGsg$85*X^mTl%W;Z9VlxJwhmpA4ur0WvIliZkEL~W zMU_UVm(Yot${~(Ig3y^(jzSus)In)PXQTk_x#~*jf&`#LfNx<))D_LhA-dB}Mln)4cA|DXcSQ-$HL1SqEzobv7Tv?u= z^rO2%&X6F^o$j0T_Nv}jL9X@is@GS2zUtvsudlAadU{m@tOzN+yGj?i`sv+O>dVzh zzpheut|1BYwAQN5*>b89-js8#{z~;h>>R1T(w@9c=QjP7_Mo?%hqP7g&UfG}qOGdF zkIRwLK2@7l$FX**T~gX#&wkn!cZ3>^oPbV@c4^ZNgpSN3l}JVJ3fiYeYt{D5gHova zD{aR-Ta{GwQL1HXv{uz~j{Fb(m9}BMkmqqEp>@)V^pUJ|@;^B7nYbmXR;<^xNi_$R zx5)Eo1}YblFVYMeq%M1=dZd~{J=9}wSD%!+boJSP$`5Y@%Eys6KUv4oZ{lChBPMk-@DtzE4i5w)mxOzF+Q_v4t2K5Be#zDwVpUT(DZ)z?kbCKV%( z#2#_})R&Hy-}=?jo0mQ4IuiYOX(O(^c*crc3vzw(=n+x-@{HBF7U$ZnYJILfdge?4 z?bP)Lap*LGXw@Fi6!4pLM;AS9Y5Sh>n5GX3?c?>Wrf&-E<|8*GT4+lR$;pa*6a5xN zZi`x_hy0LgsV`+3z1L{FFMmy1Sk8`|Ice?a@8-WcO`vk+cuKIorW3~CV8%oivFJI$ z`sJ6)IS|x$zx>T(K~M6{!OT1W%t`F&0iFYpi#R7Ex*sV=wtUdOpkrNqvOb`*f;{2g zDLR|@)yONCBkcSnw^uH(GgjpLsu3l(H}ZWWhd1(iBR@CtcKu$|u;~o?y~y$I1p2+m z>+T4;9?IEP*Vr$mSo)>N&2C59Z$upqzYl$O=xHE&@$kFw>ySepeX;7f$?rmrdMnVq zq+IuwpnKsmd;@x8k+UinwK*xQBS60hIr&Xf^qcToP(Ixl^jnb6-3auHsK6J|5cK?| z3Vaa_NL3=P$Tv`*RApk(Z^EyjGNY^x=vN@ezBVXFNBNxICgm8(&#no|m#UurMt_f1 z_Ng`nPsT0=^ndd|_V<(owKnpXcn*^9sUq*Jc=~&afxcINNm0=ET{-Ome@|i3_Kd%$ z5U945zel~ZYJ{rvt-99LiL0gkFBdK!*M1i@(l5o|s`pF3Bmalopx>AOn_pgSg1()i zPcg@WU#o9KUl)GGz9Bu9_;vg40+@jH;p0Ue?jfWd5x()kDLN(`3HHRHlPVfB78<1^ zqH#JF?7so@n<>C3nxb18!Epd-TXvRjId31?8hTJ}5X4C=SsnQKRc-*+d_5#bEk5p+bf=Pl^% zO^+1vn0>#llzJ8Q{knqsZsW}23=?OZ$Vbl1M|#ncJFG7N-*23?B6m2>Y0hrZPoC&I zbtV-3>RshU-=;hg(YJYsx0^Y!C3?$q29`4%Impq!o^Q|@Tl5XOzKgy)XZXmo&hWKe z@uLT}c-G7zUv2Wn^_GxXLE?(y`V#$!==n}BA{kHEu0a`J6s}EiwNgHlS;bt@^c~^q z7S}mt2yq?k%9x0<1^d$#Q?#G;Afogjvz|sD-@X1{>8}R#TkN&W8uWigf9Vl4vqSh- z{iR2a==CMz@#Ww5SNA{q%l*us`^%oPzw9}8M4}_uy;(Izx#P^UdTN77x)%24%5!-< zg~IXW`4!F%eYo;09#8CXRrd@ZXOOz+#XllV@SIOyDmHWGOMy@`FL)R zbCWv-DJoCpaU~g$jz>@A@!THAtLOGOvkf5jR3A_8$wNw-#u?CY?CCx344eZ!x5txs z+^rv%j%H8nX+qkO>q$P&o}TM7nCoU>ey-i`dmhhVay+BQGkhHJL(=)t^Lz#)Q7Opv z&~$VwY4KDZX9Cag843<%p7d-B&+T#4D|Io)^L;#>r*JBP@q`}d0Z;N#y5ng+p3CFu zJA}6Htho|?nA!j79)*PP7Q-atNdpwWF z8D%sprswvIN^_ilN2fE%Xv*~E;cnD(c}9bynNP+Ni_XYn({I(2e3TEldmYC-pG{>fczTbg`FMtp`OagW-qQnF zP-RkDns^?MC-`_qkLUJGOLH74p2g$2J&qnv@6n&g^fceGGlOt6@}?OnRwJItc=9A4 zshpYQ)=Wo}{yb|RKNats0cMn;;uS>L>4%CoRa6U)_b zWX1ii`;Gq8agDck2Bh!bk>!XfOPo0o%lGeSa(tCbN0a-Pf$94nn7)5UR&H|26K77u za)0bt%Lj7eB%{T5eq8#t9ZjB&h1MUV#J#d(ssLy&II=t)s}ix}%Q01%ICCPFJ1<9* z=VI9lL(?}ul$57q4NXT+RpP@>#Ij$86C7FYs*g`+v*YQ5zdsSHdOE(`{VDBKh8j=7 za&I^??XQvKD?N3boj{J`OWM@2b`;~I7AZ%TX{psw%yqTFIF9O&(i2aezm2I;jIA-u zadp#C)E?AV&!LfZXiPb3#!}OfB}J=;9=-L{`(tD|n)KV_$ms++z9ujaHUOn^9XXxB z29!CzJnu^S*D=!tY(%c(%Tuo!lXA>>>hVNkN04JmEwjwXa*RyoT6wMKCwfL=cTg&O z3Nv9-#!NF(j;YLOauoGsiZhwSk3~ep%A?~E4kM#N*Detzl6!%$4-pnOcj{xJo-m#r>RKY>V=~ov-8pbmV_^4v#y(%n2oq z5%<^8mu+F*dfaX4%R2f}b_FU-Ke+#jJ4?rm8bSJ4b}!bI{&3&v*ies1|F%(|BkoY+ zTJL_f06pOzE$(6ut^3s(e{q+qzixGNq+(oc-A$bu3gw|j8+&#uO< z?|(j@!kxBjb)@#)n@i`%-MDLe)a`H=Vf%4EAHB*&ji3L2&KGi&xw?yvJ6CbhG3)yM z_vZ^a>NBSdskigz^M&*?r$@PBVC35UC+7>Pt#tS)L+Uiios&nWzd5;ea+f0St`lFH zUt!eS(TkklUPZpve|Nr+`dWTJVrox7O0Jz6U4AE`=8t`1o>U#Zji0=nVBGm(H2bQTBh^_;N=xojKT@%2ejaX=t-Jm&_t~w(M;5 zRrGA8|1!Olok%zZos*f=?vbv8>ap}j(?pB0GpM6|>AI_@wB=~C zEGAw-YCO6suDg0on*eHAdjVkuS}Lx=`bpEfnc6k_RGWy_iaXks>599OwY3`QYCK!b zm}TIFlt*2eF}#OJ$4xiT}19B>F(tc z@-If`#awM{^{?h0=CX7Syo{83GwRZ)H>0jhJ<9Z=)*V!r@(NPj&|b0Lm6WL!qZhWT z(i!zC>Z>uMo$xxs6{*I|m1wU7)`4rNqqVN{@HOdv<{EMvqP3!bHodQ{0oB!sdNX=o zQ-?qT!-{wi{^e8c;i5HD=VFQIlpPzhy0`m$psR?gFkS){ELYP;YEEQfDK0 zHSrd%*Mm`GW)t;qqUL7sdg7Z?{TltNU5!4=2I^@=tKN(jy0=p2CU7J1)|6`AN=@x| z^#Qk)Uw8u=D_Z!fH>2M*b#HDbbt`%+H&J#6DfMQY=kMg%ozZi-nHpN?-T~fDyo0B9 z0oAA3K}y{iDRFgZZU(c6?;^Dgofq%Co0PuRwCB}Yw-eZjl|qe~XsxT|ZZ=mt`31Lt zx1`!LYTjflch$prfYP0yw!eB`y8}%YwQRK0eE13!s;P0K&2BvHyaU=R>eCz` z>_ewz549d6s5hg2&f^5NV)VDB7q#7Jueb+!lCT%l_nKbR_MpR}74K67HDR>keVXt@ zszb96)I#@J*3@>OYwNSL+W}PDMlWlRf?Df7M@mf^b!(m{JcFLg}2pyJ?%-4s@-5i&AxH)V$HZ+Vh}(*xn&m3*9%Vqn+-X=&`7g^DaS682!7w zM|c~pl{cvIKDl~R)AyQoy04+n;%@Ile#I-`E7bmw>(|k2d6&9+QF|Y4mba<Ns;OC{mW)=p>f|KhAgv`qEgSu-wFb4y4M7S>JKf)t z?C@KvF>{c5`cDgJu>49JIVsITdqu97-qh5U$;T7CqR+JA=&IyTN`U%zt3)^glq;x(u2#8tN()t}sa0-S;;KQKw<@hSPqfD^ zAJmMgjHZfuG+N@8MN_35(jt0GI|99x0*Rj0wBD^v{b-w8jr#+b>T`GWsiv-rw!94}s{v}&+mPQ?8LW(!i&nAf#MGutpK4m` zR-;V)n40LSpb?X(4bupnlse>UiCY(}OPMyf^*}9qTaapsW{Ol)OMXLr(t2}iNoaWe-F~#v71T;sy%xQx zsn?=cw0>B|_6_jH38V3vCjVg|Pt=>5wz&fd{jrcmZwBneJ;!lRU$Ad#Tib_{!2~UF zj}3StB49T_9qnm!3c(zMDQNxkXZt*5l&+^=u6DOk=<;Eovt?Q!*}HjC8AWENpWGMmyF zSjB3It5xoVFo$Q11IJN&E_pLRZF=VtW`VQ9h`-t3PNbfexD&C4olV&(+%pZ-R`=8( zci~ii#T3%Tlj-0TYM(~gY;ZRBXg_-*_ONrf?{vZ`Sk9h8?mV7xe4_R394uZ>C7w^} zbZlc!r(8?iGq8pok<0_<5^I$^7rWO}skb1=Nn60vPsOHnK6hxFdnVSeCsSJ++~cvt z)wX0Yb+xCRPmRUgr6uhdJbei@7lEe{YkfNpoX4H#QmU=(5=xhne-5Zs?lM|G13ZHo z+SCrmvR3Zz`DyLtlrF;pb|JC0uxEqX+pgg5bHWAGIUm%f_rjpm<3fJRLeeGqeHW5i z9#&FwMOZ~E=Yr=_`y%cimRv*_nyjXDWmrusOT)#~UIs3s-Wuv$1g;>ygwoaE1;m%~ zlnX(*k(cs><)oK$&t~JHo@%c_=(W{%-IA;=MfW9#HP!UVg()()Un% zA2lBaA0&R1nva0Hi1%~8+?@b z2~r2blhk|+ln41F&)rLUFL_VV*2Cb#-1#&$9t9ueo@cmcAGnXQXK8Uj@+_f$@*H)Z z4$o8L0C<2JFL396a6k24408Nlr0vH@AHkDeB=uZ)iF=*^pWvRCY4LIJaqfAA{FlJz zh+pOY{>iI^e#vXJ`&4+1@N#&aHeUo^q}J<%SHc_I`7HP>_xyzxp8=nt_M1UD+neO} zOWxx8C{xp0^OYeadY4^(@U-V0^KMP;c?mOT++%qTnjJk7@ zkGW?K<)4MGd0OA(YeFCJbFQW*A92U@ug4H;3}Mgqd&$Pp147!s*bBYJMGlVxbx^ zN_PI;DTQi;#Zy6~-j(F2Nfytil?z=WrRV?MS%vE9#Pew7m_+%GrxeC>L6jtRPWkWh zpFOKksZTtyFrNGI_a_$q>$3{wqg7_tskA4anyLQT;b#@9y`iR|`$MIwo>-`yM>(sy zn#uu{%Zf?{Rc)7k#ks!`~RnBJ;__hocN^XPdw!*p7@kG>q!dNbGqV*Po767?db_!ht7JEo;q~m z(|`Z0r_3o&@kF&lXFaKxtB!6wQSCoF>q&iJZQRR(>T5;W&f#Z0WlnkW{B`xU)Ik1c zXFYY}>+wWfC4)UcwHxHR|Esf}qE56@@Lv3WcM&znr~X>? z&Xk`2|cbj(U2&pRVZ}iIP)K*He~SH63l9NSo1W%bd2VOf~BKMfvHU zC8tqZ>d30jm+mOcob{?KRm*a{gG5=XlGBim#V9$=;wq!Z81)gOj$%fSQJLu>ZN^%R zDK$kMSs7jGKg)M!B2!VG(~Wc;Tp*U^$$|Ec;(t%@u}X^v;voW$Ham-5ro zx%P}yYNM1#`HuF}^9ZLU^LdkpSah5-e zGS9kEN~FcIvK@V^F60+f15YLP6q~b^N1Iduf*pJV$Zr!?$ebgdD4w1-b8Py z%6-nIJ*7NnP}_5F&OlH&|f|{O8b2jk`?mYW%5}fn7_X0vKQ0r$;!qJBLJX&5!xB#>tSCXoQ z3`Qx_D#C?GSM-p25oL8iZJj+Kr#5mCJ+Q9kx!N{s{j7YY8yICb+Dc!{J$1nq+@qYP z4ziJp$yr0F2WBjvFGK>GPI>(m3ai*87r21r*DzRF9HjwQ%# z#*n%U`PUevCSyshMZz@}iOV=rmm|{}hh#-P2N%mU08- zTL{`aucyXMJXd>ZWsWz~uF@aR;>lP?>#Zo zyLnzta4WI)(p!L?T1neM*s=bntLCrWmd z^4y1HMQP51ltz1Lt)pG@JvS#O@|7s}(e8RT?P%}pE-_;@t*l46k6v0mc}I!QT}W1x z?O4LAZ0!GBWZbAR7s zC>45wpxnoO@{`=Dm(~NsPm+2JIZE`^s_f<|T2Sueen*e3xsab6px!gweE{i;wV&fx z>;^TN6k8|rgI}HiLxF&u)adg z7m>b5p}a~<&w%}iUnQj-v{uuetMfE+70=(%cKTW5FzVpFL0KLoE1tIFSvt=l!_m50 zdue4jT35eK{$D_?so$Z+7r+;&r>sZ&XyrJbn4|PY>+1J;@=KuS@4TN#oxM+Z6&Z|j z9OXXmB6so39c`qQ^}I)kHq!cJeS=^13Hcv_N|ruNWi)zYRo3$fSD*3JH^6s^KO?2Y zN7;>XAN{iq;OcYe-T_Eal-GPg&@-!2BIPmKOCL+@xjF+uY2>eY_PgM_)cb~CkPrNr zSXs{ppy%&+qRuy|tj7~|l<#~`P}ZXi=&ywDkiEE%)+cMeKV&^W(!Nq1y}4=^?O8fn zRBIjWSvq=YJqX8PAUKeEztG~>ptjV9ys;|%`IcPI()l)(_@H?eeoCc0QNHsdB_VuI z4JA82fXZ>Qf|k=6Z>-u+=Lmy%QjXxsJ2`^94!yDdnB+{QIZA(&`)GxoE9kp5H~Be{ zto+XZg}pO7p1hPI4MI}$Taqu8>3E7xZsaZ5#QCYIU9^%QPtH-wlY_Vb&+-%i1dXxbbA}HliE~9m{@*QaxPs}L*Mk$ZJT8k12A$vjd6V!uiu^=bP6LpmJ=%uv; zL0J!SoTOwb$0^0N7SYOyN)eR%C?P6MD1q#yIJK4aDBsbCYdJz`BreKsGV&c|HyJ5U zF=|!dxy3;FY!$dx;-g%qB0))xK3SFcDC;RrT!|W`k(3-knHJ1?Q&n5F3eRQ_NlVcR zS`Vz+OjjpgS&tH>8a&05b1H5I}OZK11xRk&ZDtQEnElJ&K5})XYRk=@nYI%N+(x2gp-dN@IYV#bWKMjztMCng` z>Ul~|eIzhSbCmmV9yPh~6dmP0p0lIe$Fp>l>?rqXg>*&VtIB$m_#B@oy^&x2&*VO> zX(7se^uX#VI!bdoq*9)aJP(^XS}X!83G)1$_Q+(kd{)-e5jo0;q%Eifr)!X7uk@!A z5}GLSiLxGLL){6=dOC)pNe@D?L_6nra!xm-DN2Ks^|V9Q(vf=FId?>w(v@1udX)H# zr1joG$wD7~MF-?3N{IT9>V*tOSx;ZW(MVK!Af4z(sg}sy$<<=n({hfcWB}n9e0wyu%`x3NP2^MXFV<`HyO-5%5e0?I)u<4?9Uz159?6s zDeLJ+4W&HAl3|46AQsTbNd|L=r{w5?Rk;s7RTCvX$8rzS8)QbFpQGGoF!hxC=z({mG8H-%S6LvfwXE@RlWj)G(l=bM*brSg#z){4WeRBe+WM~RfjFQO|?k@q3C!R`u zJ+mtNo60X4gRCV=e@1i9G+G(=hulZGOUXp(&om?}N||O7^u{VbYBsG*KnA1qXAXBN z$?>e5xzs3`%q7f1GBcH0C-SVR;3R6Fhy=7rauO|0Mkb^0){_bPSJn5bepr8n*4 z&`HQ+W+83R-|ET8U}lheI<3q=QlcE`48o~MR+RG0Bb}Cn2N_?8}>?rGra-VZ4U5s2sDNmI6EJJ=#CRxUvrIYh$>rA98XCjkP?y~^t$`b0H zPdiF=loFjEt%6g*Q=VEG~hb-m1RN`|1|qCmlfP| z8SSnCqm<`Dp1zhlFGL=r&FvwH&!tFHleyW(_s2A!i+UIq|i~EXpOvG9Pa;`_FqC995`8R;dfHrZ@I;1qpWi}I(CrWniOz+u7E1QwNY^L^ho^=bjg?ih0+7{#|cTjgn zde2?dRLY|?=Wc3l2h|$7o9i8CZi>tmk&{ zcFOMOSKJ0F&AFe{eaKss2R%U8iHt>yTd7dRa1wKjcZ=C&M@L`U5F0|Ny{-SAa1IIVX zJxAh@HToF*Q>ur-%WGxQ~M5@llKGK z;sa7@Z(gF^hg{=J=vdU_sP}mv97L}llTz>VDlI;tr&lA_xVeJuy{I&&R_1+lID>K@ zfoh39B@Cu~FtfCuaRqOn&v}C*7v|IoE#xRQJ8FfNCchfhIq7UYvFnKRO4^(=IFs%CY%{Li zS=wgI(`74Th7&u_>x{4ZEbaY8=Zdoxv)N4YAabrAP*dqTD^WdZw(>Sx`;(vFb`4Or zvN~Hsl&yVmeU~%j&WC3!jLNSnD!-B_?~}v1Zs)@@pQGxFvbk>kbYvbwv-$1(s&V&@ z&#xxW?-%b3wLV1iJ~^^A=+0a_H=XHu)PAT3aivc-L+zUOY<0Uc(duw2fa+762h7&( z#bMrBbs zwrhu7OT0ZLt`5#tH7X^#YPd7#sz%oZyPnbYj*}_hw5n0LE5EAIb;VPWT3jP6e{|Jw z4NytO6~e9~c5Sg7&o#l_iSw%(l`*Cfez~gARm83xc2%Qa`TVNJp5$FS?Ak`ZxvpWX z1-gpZmBPJ1*E#M?scU~-QS3_LZ0&F@q;DnU8I-uH(QlCQeQjoim2zj2s{^{OcqYG& zzG1$&1XNaZjc`5C)sL&Bg z9SFLTcn&GO&Ca2GF28735W5D_*<{xX`$cxWuq%jN{WzbzYl8hA&8IwDDcp#(8jS^@ zs~Xj7ILquxVOI~kQrPvv!^pW(co=Uy-@~pEZVI}7cwv~C_g&~p;p~m-8*dTiuDo%^ z-nXCcK-U#7=500tU5NUZ-T39WZc#nRZj`&u(RCcIXB-8(;-)>%R)_G*tjP1_YKSgi zXP%MHq`MNf)O82D)4D&QHTSb0 zZ3fW3FW8%SAV>A%ZuO$YAl@G>Ky{CUXweJoPfp(-1GqCeS`Vc~b8rClL#b~8_9Y%h zo5A2f;^ESjT5iodNj>aDTGs=&A)ZLxXmB*SiL@QZTWf2Mn?x87 zP9V1}$4=lK;`I zmB94pw@qcz`fzjC%UwXvQd(LNzD@<Po;m z+;6|Vc);ZEuN%IrzK8K4$<-Es#o_JTh*ote)ss>IWf493eJ|s;9uxjI>v4S#xjSr^ zFovDO7>a%;9dpqyYG$*M*{V4Hu0!@a>^&8IV^t&NdfaNH|J{0AC5Yni_VW33{|Dbm zKBcY0bKVMcRqpR!kL$bN-=n_t{9@=sZzx!g*k80>^!(cV_txX)SK_)J*YE9bt;hB5 zy4Q-koKy&@ilBS5Xt(3tbWacW1t~4fc0#cvq1@w2OS4>7W9#JqK-uq?>3s|TQnKG9 z)BCpFB-wB7ZSOym>AjbkWdHkR`ts7e&sOFO;QyaYUtXH`myp?;Y%b0F%W=KFYxMsU znLe`>X~(nhdu94;Ov*Ey-|s`A{2FhW&u{xs@C%ylHIcEg&2516KBU1kZC`B0F7W_)z3 z@TSUa>@vRzBlz8D{gZj2l7Icud%`A5Air{D`~ou{3YmYn?0(9~%6l;@Zx6J|1}L+u z%X}!v*t7!C&P6{nWxU&(6ZFNUk4yboDgh~RDwB@PDW7f?WLQy~5+z*GH=N%Z(KnoS zWm=iJp58A@{tf51Mys^J+!wz*nYEfsS?S#G%K&~`TC>$9;K`U+RPL86h`!t86Qb`n zIfp3U@QWtONs0;ju&ha3#P3WSFuzFho1T0rwHGTS=)+PUm-@4mBg>%ts&?Z}dd~|8 z+5>9+r%j-ISs$0#SIDn(Cw@_~KEK!Q_u^N`FL+1Zp?-hlmrCJ&kz}0hdE+Wo%S!cp zp?6FD_GSM2M88FTe?{eKzviM}q_*L&Y#aXWwqYdNhOu#{le*M8er>{7wh3e0CVb)B zg!`baP(AKS8}3OH(7i((iI!nh+*ihZXKK>QF=-jbp(VX~pIe7JuPss&o`cpr4USJs zo{ZMy%fbkiQKn3;2S!J!EL^klhtH~GrF0;}cdUGpods~L$`}D{*&M4f&?h`4WVWHL z7%B69o0OpZRyl5tkzXReJ??jveYI?p*`5AY%T3?3?D*_lS?f(lXJ`Gjw&lN-oAMkOF6bms*v(akjam=D6=p90_zdjzG@O|XGYB|!VCPtd!jJvSgIRr+meNWg12e@Qh^Ijj+>hCF?Rq?GRc>k7&L zyX(wfVajzm8nwCp>}oe%XZ{K+ab1=E4_&8{j$`RlXvosOo%5x7WVXI2loW?Hj=%TI zG50Pw{@!Kpf+L^(MUHmt3wA9?Su_rme768WY@|wL`udNortF1)JU6H(^>^ie6tQ@Y; zYs+7!*H$lF75?qR)m9_#bKuinjqCj1UQhl?95JuNG0d*Yar@WTlfM$j$t!UTv#YAl z=xma5vv-Uo*)QEYp2@%7Yk#3JXstfE6VP9;zfk>j>#@5yjA1b)j;dqms5+irv!m*G zdbR!)UcaMPhu~jPHH@cY$bJLlz19Ly7WR9_ExUt0V?K4+9dz9CBle%($MWNrAF=#> z{5`+l{4cixe_#3c%0(mZL{e;lYhfh=e^<^r~G^7w|>9n%gc|g_cZgd{_DSy z|72{vzngw3{)&I!Z=_cE&DP>N^yKdK)F$|}_|(-Q__X-cvDXFpy5Xtw9axcc1xo9Y z_FdsqSD)a!!mILKT?MR6X+zSEq0gId=>o87cvt(}H6|!IIHpZ`%BzFb$?F4Ii+RUb zAIMFS2#QF_aD3*A$p7E`-j%YPi^vfmXmO7De1-g8xeS`;n&^}nlj zMQw^wW9E(5CqbD~4kznSAETzm)d}iu+&fO$R4G*dyV?37C08X?*GDMPD#2#{+U1n4 zpHM%f=16H+xmTGuTXW>y$yOdY)9nt3%GOHG@*JgY`X`*GF?PY$+Q)6q3^)V zi?VWSYothhC}*Cjm3EUL|0??`@hTT96DtENFDol68)qwXvQ;`hm+q0EEd9s*`s056 z@%#GY_w~p7@Q?T5AK$M(TTc+w8nzbwaf;Q=^55J5rXvPG`*{X07}ioV(I8$g5Bv z88g%6)v2L$u2M~#vtR0Q{A-*Qb6(oN)j2a~$o;F;=c>_C$5j+Ypopui8fM)pGb2|- zx{!cxPjXecBF91Pt(H{&EuK*wqJN`3#q{Y_XS%-H9OEpzGwy25oPBpDKCe@AhF&e3 zv-Mt4UI*uletx#!k?~5@(b=O{qSj8GfZ9EEeBO_O(685*=_|bsuOj~Wy1c&ZZfDn> ze**Hl2+w4ho`}5SQN-@nISO=FPj~Aa3A(GNyLFBL-PP0GI=2Gd)w2O<_3qlbyMO0! zW)R&OK%X#~o<7@)GMh_u?ohjTcLH!f0IlEMxzqVx_wy`eUUC4a^}Bm^Y9F9oj5~Ka zm*{?;Etu2n$E;yrQtsK=msvyi^DJXL-OJN`hFXQuZAFPQip60r(Ro$vv7AM8blVb~ zOLTPINue#XhK{jzUCt#s#_b8tB|63(2+k$?v}jSGZJ2gpdi>GLkH01@$@KN(lct54 zzJ7dOx)8L3_3m^Hcc&}mdi+Vrcjq3YU`oCR_ap{=&U+BLGuIo18DM`4wFo``xL<$V zuRnfYfBe4wcpv`!J}m!TE1%Bm)&1U;mxa^{WqP8NH@bFI%DNRnHAdRKsZCO+qzAW3 zpcYtpTVXA;vVDZ~=2nI0(D%M}P$_S8?YZv@UanQNNd^3koGM=M)U4dm0JZ(xhR_T9 z`l`XYzA7nqIqZcMd{u1XUD?zN)I-|1@U3)(5PO)1FR81d`d|_78YA~s?TdB)n1FtB z-AzvPi##%Xsg)J_2Pt6y=vR9y!XVHuyAs1dB!a`TKqN{&g|FR2T@!j$8RY2Gi+%vZqxEG$h3JCjv`{2b(?X~Nt+~w9)RJ-G^ ztAKLX)a(LkqrZ?a8-H8{)VUI8HvYW|$S)u@2Xwa;SMJOXt9x7pG?x)@?N1!MR}}<* zRt0#AD!_--8K7RQ3OI{CuL|&rwFVDhCll6!r;s~|cr7x`8F-N@CaePs$el>(f#6BR zXHm8epHju7PN4K4@I>O{NgWKHKzt6h?oLunN?%}yfX5T-FYHk8IO6lDJr`e6#iWj* z^f2&P;-g6&4!To}{=<#{k0w^$Iv+eAUsSi_8>tAdO1Fb|67<<*>Q?Xq@HXOGNnMCX zr6THXA$K8Ol#0mTOzuMPLi|?UL&@EEYPy;9O@xcVi}6f#Bk?8pdb%;-CBb*q4FUg* zm#XXVDJ5QtC#!3T#mn$lbq%q2IsU4Y2=4*!!Dmwq!hPU<_+P3)xF5V94^1@)58`jB z26#2cT@gH8U5SUG8o5{TDfBAw>jeD~y+Zs(kS*T`r7uxd1Fu3gIQ~t_-@uztA*qez z9|m6{ew&iF@Otzxo|;}HJPK|k_X6>wcql5Q#k-(8T0Dw>r{}486z@TWlx`sZIQTf8 zn>JAM7~Y8rse6vRdv>^s$KQz8<6~((9-N*fr?03d@!9kYxhHe%e!vlFRLGGj-f*ht zPL68kPQv?+evT5n?YxhF9(Wt8{7<6h6vD}@?$`c2jy}LoQB2zpa+PRPk@fwqYB)7= z4bQ2xIR#GwCvrq(YAdm#zYe8;id+{I;iKn6@I!njMUj4#j;C$S+-Z^Pg-)Z*pP)BU z^f4ZSs&o8t)K$wJhX;b1xvG>@VeP;6^QY7PG`s`lX!#Ro`2_p~KTOAR1Xd>mxE$@P z;y1vR5@&GK>G&G@i8jaJAE8?AOv=x|_m8cQ#v?*CJSF`|?GJ>{;57AVQJvCi_!($G zT5n2!$D`5TgAb)2$bCodbMSM#Fg47r!{>l2FxKHY={rjPLC{;1KAQBa`XoFvkqwt}z3{Mb8f=7~TO?eFvPd<3ySW3wf{>o~2{5XnuIW3prL8lsCd|J_} z23P}6M_W+R4nH4Dh*!{NIbJ#rCteAz01qQBqiqpbgeRjiLQTBuus#NlAG;B^q^u^M zcwkR>3Rz6Nh|mG=9fxuJDtuZThDV>4v}r-81=hl=(Q3RZTnb)F{c6H0Jc}&iEDH%8 zqvo`#jn9uuXtg_GH9ku^;>l-M>O11);}S}n(Lzs0&50LK*9qK}xRkOwU>!Uul@jXW z(WDbze&$o(32z}6bM&5sJ@9?f8P7lSsOgNikc+6E9{M>ZGr_fk>=z^D&t?{76A13W z&>cTSBdO_*Z=R8)M-X~~J@G~~k(Lv{Lx{H`-y0l3Jc*Kt;6eBynM61QA2xzf@tc;nR${Iw2P2PxCp2g_0=S!F4NA8pUj%j}F5~T81FS)v7HCCCqMg8&l$YgPaZrR*Sx8@qWDIG&Xlunb2C1_rGU!CgN0T0d+&PJ~^G>cX)}n0`@@H?P%RZz=fLe@c(Y6(+ zC7Bj&TOo70#t(kER}n8j zVx0lb;4J&lrUbchCi(fuo->g|_n~ASX}y!W(sVz{N{}#Tk#~LQEF{JfA#)x89zfl($eC-wgNTnMbsRG2I@%mViTec}Onf$FjgULf29KshZ?XrIItrQd zU?k3SC_fT8^APZm@C!VQoIY}oi52E3H`D)4IXGU5iDNqOLI;s!{XcZ2s5H$c+77yK(RJ0uW405;&w zav4YJS@klc#|FrhFM%%yS+fC>VFU87k!t`doxBKc1Ro%NowEAKhYyf{0eSTSB+l0< zd7ktO;6uc3QdS>{^G$FAa^^$eBg7j>xyRZgq~4~!J`(5KpuR&N0Ux36UCQbsH$Fz0 z{zV@H^%wdK>1TQCJwfc=bG{ANlhdQ<)44cEUUBpu$H&pToFPH_tCu?wiH})q%46ir zgp%XQpMadHz3@p$j@5D%sHw+``+cO^94(_D*Xi?07JhOhLpzxx3XtgZ==l>Nhd;;) z9Hn%39J1=kQ57UnXXPtVQxECxL)!jG_z4-X8tsljimZlgD(^p)BPt_tR-)w(wEPkL zi1=vQ=r7ATgFhkZRze0<0S{{uzE9V}iqn{-=WldXPj){FGMT623z!Jv~a16+ffQUEcKK`6+b?Qs@~`LVe2D z<#TGjA^d}H&FA5(^98ZH!QrdSMcOLR) z4jJ=2@B-w`9PP2bMarv&WLUtpvHutG66Cuhz{8Q?mXJ~stVXLcrDWvH*0fwq`EE#k zb@@9NBZnS=9ww#^95k@vQs-2$Z5 zEs#W4(6ST>v=}U=MF+|kAp3OyS5bE{xRSUj@@Y-5Chg`?J0I*wyc!AdLhxeZ)wI1B z39vS8n;>b{2HmY~cUoKkt|p#~EZPz5$nlM7(*#LwOY(bAe*t&_4-HQcFGJy(!BfYwit>;e4}^3_Eew(WJ+KTM~~#n(YL3BCo_b z8=Q>{I1(weGuWBBapZRa#}bb~^6Ub3BOXD@eZ9s}yA>rPkU_U5y$xX|I1_nrIMQY} zup2GLQ>KL2gR)_S;Ygh0DVc!exE4H!cqp~Qz@EetDN{o1MQ#XTD01gSN+uyWt^wB) zZ%e!eT!XBq=geMUFIo>m+UyPLCv!XM_Xqb!($@E;`>N?zb9>76LoVz`nLacJ!UyY< ztDYNxR9HRNkJ9S7$+WAU+n$!ykwzzjQ;|LKe1l|K9cgq2a5|D{bw=8ib~_@UR!17$ z5!@Ncw0dp^l4*4$&>7&qFoNnxru%}0^j05+-GKX52=n`rlCSt*2>*T(e2V{t%qv_0 zUdjJL=1~p@kKlhH^G9>Qx%@BWdp;XvRoD~Y@CeP0RAr(IuKECl-z_aU_i>`UC6)MBs? z@%S)PHy)X4DbnL^(bJT; zzicg@Tjdjdiz_E6y{soVKLzWFo+Y#apCR`*%GyLvAoFZQme@$U$B~6z0$(D39rbM@ zC9^isV@OIbBaysJ-J_(HQJkN<0m-dR^ayF?nAeCO29f`sBb`h9+xIeziJ!Qaa@CcK-gOG!Q6 z^~z68sChS6LP_1|yC7qIN7*~MI+T<|-v`<2d%pf}=W6r)WsMe4C;A~sY(F45yp^lP z7aXlHwY8%kgFL5<@@B3kUwKyKQdK`d{ zD@_$5OZl~L%Tv>m_w60L9|uIr-&Y}>-p_mMfgtTFt6stQKM4MW%yk8+E5RQrQltJMb{pk=_Y*BH&*h?@g5>>IP-$9853k^aYSCpmh6&6?mm{NJL+!Oe?si6` zZf+n~G9WrO$m7RSb1(9GMC(g)F>{aD$47V~&ne+m4Kf`1f21^QT9AX3KdVK@!D#M* z;V9StnWL2cm2RDbsS6i6j`HJ!?0*U6vIQkw_d>r51|`S1IH!!uP7To|Ip=cf!ZDOz zFQWWnIM@laIT4OBFgh`C6=#O(!cVFq&0a`Lxr%b_NwgRQo=AKFwHLzfPGa_>3$5$r zoO7xR^Qj8I8JH{0H3QW&4J5Px^#RryIkrC7h4?&Lo)3T4I%5!FV6Ic7#fNid_4xud z4cyu_VOvIeV{oRe0ZdyfkIdd9^V^WwfefQXBlx-YA;W3g5Nt?(c+UB|tw1$J&hfGL z2l)}X_Q+NvL2XgCKqeans&{IK)HWI%1w)XVs`pTHA{Q+PT(lst&4R!%3j)I|2z;_2 z@J0E;dC2NYJG|bQ@|;FZ;D{+yMStpiU_ko^+WoTa<$`VW*YRn zw*#p5t47du)nIO6N7CxI^j)!xG}U(JQp5 z9rKicGQ}$XkJ)x<*~?*EGLkXXupQ-vj*$b&i~& zV}E2?bdMs=(VZ_*1a>3t6ggYhi8i#OKF9CWnLE7YQ;Ju7q^*vT^K=~}=jJ*_&dTxo zMYiim%PpfbxUOaV5}i5o_qdE-W{$Gc31{%zbQaCoqNV&oI?%^yxgPX#8f{MJH|vg2 z&J!)+x72~Uv&kAQ^NPgQ>KAyC*q|VJb`&a=Pbr$(;`1Q}? z_dbP^t$7d324_>c1Nn;JRN`^GKjwgQsGCMbUf&Ht6BKAHA9*^ zj`!rww5Y~gXJ@__?1q69*^KXIbHXu5m(3&b82AJ%h<30bVs=^J$!Hllt0$vBn(vph zX4zNoE>aiqT|1bvI|+XYU&)KWi}?HQ=I2;6*a>J3EH2tzIebfT^J|#Ymk(#YjCu#i)4>tCy&lctE7r%K@|> z7%3mu2(koTc_XzF{iEPjlQsj8f%G+`M6?AG9$q$K(E1Uo66tYB8L1sIk{*Yg?P`mp zq{kuUr8dY(tvRL|NAv{?$WVt`;HxT}E0tuqa53MM#TRl2&RgLgKp`e3ZYdn6y3wt|29hxdFU}d@ba@Ye468 zYrz$+1LX|0f}}1VkqtSoRSPX?8_-#)TF4{qKxdI^A?3G^Y6nJFJ8-tzfwR>{ivJdV zr!-$13H^IeNxgQEaBBy-wRVtC@xXw*i8lr$M|{yBA=ZZdrQp{{f!Y!`;jhQWnGjL) zCFl%7#P@9j_(ZO>v^ig}QogeKAZrx9!tMjuoVROp%C*gHm`iAzx0TYm*YBTS%M$AK z3njDw;81a3hd{C93pNGoiib*v98_-HGk9u!t zL`qw0efTJeDS>Gft|hjTlc+Q#AMMK1=C@PM+Lb5Fuc<7y3s0CjE;+7NS8BcVCe?{& zQQcT8LPywltAIZ5WrW^5FSWV8+;YrVS@sPoG~t@0m}UPo>YWPomGC&$?q%5=KRTE-o^DIUKU2$XKgG`lq2m^rZ4iAq+5jX_HWL6#Pj*e z{NIUwGrUUCuZ1He`c-h;MDM?&C;Hy^$r61Ee6mEJ0>?`n%(LkTihjKuQ_=64BP{xa zI#QxfsAJcUar6mwH2X0+KBtatU&czA&k^gxNcijVY3j|m`0H_WdNE4=dK{~sj9ww> zYT-BJSoUB{{S7&?nf;^Ikp+}g3BPaeRo8IOx`6)5eS$=PE zIa>4!r(`Yq_426_{ciEH1#Ow*NY`yt45><>&y~+@1o}Mtwks|5sW$C1?t8H^$E9HQ zUiAIwQQ5QZ8C`b~6TAAt)gi7HDPL}h<*w5xU;caB|0n0k-r@c}?9cbM-toLT|H}Nk zebe9LUuVnwo1Q5X(&lYjTAKfr|8g|4zdvi0jZA5&{n$r-6!PDb&HK)ewf*E4=i zpO?-1-gJKZ-2BPPT24SdpU9g*smv#KOJsCMU^-z^klMvbFbU;#(OGLHa#0`uO5UQD zs56O0?PFycqBgX%=w(7+6+3{=BFH+X!YjNZvkB7!(-56km`m6xaEu)Tqu2>_jzM-L zI@2I)%Iptj!lInRkW-n?Y+rY!kA;EZXa_q1R_5JY#3&@79YJz(Vt5w*Y)Dmztu}pkvVBDhGgS`mL1MglI8255eEy3P|Z9sR^+=u5$CN4AI zm#``@@s)6IcQlrXuL?|jHMp7{+);QBaDU6Fp;fTFZj)8;F_auf&+Z7UCGhd2+&|bog-;-L z1n54(Cy+W4mU$$7$vI6cmz+coM}w7#<)25x-?bxlR_$n*zIMl_l0Ozah1h+1k7JfV z+hph2j$^h!`()^5LIJYwl>jKw33p|T{di;RaC4Zh8Fm@OyUzcHiI3UdMfZ zwFh@5!JT}y7QdU^&G3A!$eks)1wOBh`Mrd#K&2|@0o>JBu5lmXcDTA$>S_&chm+qy zPx5#7_PvvH%hTQc_b;6LL4rH{K0r<;em8hG=TmzmYC|s97M0o_AvHWO&qA<}9@I#Q zT9`Z6Dr#r0)r_dMxmGixHs?bavthRP8RmAiF;_$9uD;ryJLmg1=6bb8cb@k-W_Gnze~sJ* zW^=V?ceeL=W^lE6cPHQ>pi-@~y)QU>OFwTCHU=%2sO|jQ1or@bi})Q`3*`2fa2XhwMxhK(g^pZq!3uiIDW%iQ?DTrh(1(fy=^GgY{NX}$bqepiI4(k|* zS-(W5*6YT2$3Tjp$3d-`h0+;n^Tac|%$I69&Q z?#Q{Bspfn=DMOP%+=33|f=n}`$>-O~KF2LJ`v@0dF z*vj?>9*?EgczV)qYa8sfrjXu&FcEZBgEm|fu-$T};AxR_4AV$;!JeyGt`v0cbUHn6 zhfP;0eQVprPQ`@n!5xX+EqF3GnR9FHwSAY+!@@3cp){ruv*4B-$nH0{=e?WusCuKe{tko{bG8YgGJ^dVs{Ik3zpGZ zTTOQaZcU3Nk@NOTB4_fo^_)wIYf_dF=7X(syJ4rR$$Y!0*`iAr5$0dvSW8+nhH~u7i&*1N0#Bv z3k=s)A~WEqb7(U^uIJxnip~O?)0?;o+^XhgRm4_%K7&QTzgMiEQ7hqqxYhntXYP= zH)V3?Wt?vx%9ex615;kXnf9edZS~5)l=mUtKQLT%tuke~v)p(aa24^Iz_<_Kh}AII z)tq~6;L&Soy%(%?PtJE>V9*DV-v_=bYd)B=y}`XX-yxLBk@ut3A%Qy|3csxgTdl~M z4kfIGt;(Pe3%vUSM_ zi6B!xl5?C){gH6jlc<#&9}i!Z=blP97S?(+eaMi%_ozVN1sXENuUgR9cA+6lR5q@O6ALE5}zG-?%D9cs-&xMCYkaWa2@eEfp?!v zYq_%w`#f5ymp_%W%An7Lzq-QteCkhwvz|xEh2+)+7t@OzS&fAZc{I3= z_!8Q#gSno?IsQyIAH0a%r5tfKcs6I1IbQ&q{WG<4=L_Mimj;e}8R;uY$&qEvR|ST9 z6@AH+FXZf3!)7l8<=wL8QE*rJ^fd(6cl?<%x&q` z7HVbCHw12cBX}#dcTjc%Z1r}I`%7TBf1yYD@=es=MV);4X8O8|wl{$C?z?F%cfN(A z@8;+m;jw?A{k`OFgQ>cz=03`9g{j`gaet-ew!n(-25;wx`>DSjzN+W;2MB+Gt;)3@ zq;uK>ID4Uii4+mx6PtscMEVFhM%EK_&hdAHUlsyDrl}SHCkSRYBn6iA@wJtJc zS@U!7%_6Xfqh-azKv%wO2wdBh*X!Y|k8{4~IpT46syzAyf*d*H&QH?cM)ERcx${fp zWy)b|1h@SuSDEwYV5+igx$yu{Ze1n%k)Emq9$gh~ z`%|teLB1@LE+EK}Wzy9Mtof%b0TYfcq>T0d1lh6Nwnku`@K^dSqLsE6GH!Wtf3QN} z%T+i>F~?~~QjvaYa&#pSi&@xgF}1ZxRRiVIb;wr-Wzr=aRSe3fO9+LqRrYQHYtXhH z?J~a1-US>{osytCr)@DTwk~b7x-JHbIbS34vSXQaWAbujtp*!Y?>ZcLvukon;Hm68 z3CeS2$PFU7ao=1iZDq|e?q;-;HP`3pW*k=nTjdD2YcopV$egbwWes4e4LPoinuhSy zj43zbh}MBYx2Bh-FjcvH8`{Z~OUbq2h{iD2CY(=(jAcGYH-V`(<*e;Ex+$EsE#>XW zw*=+O9RhpqKxxL2+rU#>a$HC1Tf$vi(`w7WskN<@DR-bhSS;*YzT7+4nbxvqIdvD> z%9`78bXUsSf^7p+?m|g-QXN1!bPw_!L0NN8&Yv;mE~I6A95d1j?G{1)e*P^UIpmtImVTwghFn za%a{b5jul&$SvTwoxq*wK{h=LZn-o4?8?zQgRMAnAvLq$#xmtafdwz3g*-ZA)~#~8 z!jorlzQwei1mOmYd6sJA;df<;!hyOCve*Qd%#dL}tB|_Oj^( zoKGGtW(>L=?PSdhe`d|gNi8NVKhLw{kwI%QNAuvgyrPvus-KJS%YE1z>pwtv-4QVH1PS zxO2v%GX^b3mO-m=mNjP#T3-PR;jFUim4R88=g#uvrEt{E8MHRt>TtFB&e-%Xd9(~V z&!%O~zhu+DdjG?n<s*ktBcMvXnAp-M>qPJJD2?rcP!Zm~we^re)4E z=!{e6d9=KEb2crH&Ny|(o#oNpb8_dwa93G##-M+VJIk8$3|e-aXV9|aU*pm0k;ezl z9(>@D9>-DgX!Xwj9Ud(!p7=j(TJ9{5?uw@nxpT&&<<6Pjd0RNE+&SaXGU!d*Sr(jU z&>45mcyz{~o5Pwj9xZF00)Lge&j|cohCB@hn=xovwhVeQd~_z|vjeA=LGJ)N&A4;M zqkoG*t0T^Mbe=C~+&N>-8DEw=%aO}qz-6?~b7$Fc#-JAlPA!9;`9BO=zASfE*PQWX zxw9Nu9ddcr+&ZvkwZNNmXZf`ZdJf#UJcG`-bH<}(&~j%r&a!6p&KYZNm&-F~b)H zGYGDO+?jYLaeuHsbHck2iv#$cYN0I-W-e9s4kf_NW#(Pmq|oVVQ0+id5pwYAdT1HP)pS)1)W0&Ct2EN{7eK+rztZMM6@TGcxr zNKbma(N6oIpi?`D9<|&)h>~AgYww4aS1az!THDp9`@>c@*=)OBRPA$Sxn167+qo>+ zau=BE2+n;}&>J32Dznx;2wwWXx7Jp#+!=95&rXV%(UZfmoB z3j8&*)>g}WE`4S;+kZm)`_DGpt{GCtyd{{~Y>%d=3xdvCYi-%I_S-Vyv%$?Rw|}3_ zwzewjojZb=&Gs02xIF0Mf6ZoFYwgT(`?qbjGiz-vx79JLgO)GLojZVfw!V&3dl>9k zdb&PX8mMEw5?(8V&g{3f)|N+WxvkCil`!akZ?i3H&NR;L;k3>-YPo$KoOT@NzCBn_ zZF=54mM z*3MgQuP2?i+0OW~mfPx>+k*1xr%APezmBKBXMzn+-dbDBZLPIMEw`T|{L*GyYwf({ z_J+Wkf6ZpQ4b0Wq>=)^&HJI_}3G}xy_$l~rSZ-^x{W{!P`|TI$OPg(Z^hEl2Gk8hJ zthMzxxe*5a&oPe?T8)u-P|=Gt2D{SuHgQ9y^I1 z{u7&ReR-&f)^aixcK4~@5d7JIe0(bs^zV!6*0jPfAi{S6!3wqRMTRZJ9NvV%k z`>f5jcG{b4w!fh-_0C#r>+$OoSnM~XH@DW-ep|hAOHf^g>&Eplz8z=%9*ec@K>bN% z*4nNl{{ja6>o(i+=*(vOn_PsBSk!VmZ?mnnb_{FQa$8$Lwa)B20k@S$Pv+d^t+g}z z?TYApwb{>P=b93ZaHOAVN14BOm zYNfT@E+k|&+ZE6U%as4M&9-*hYM-^-u0@bRt8uOs^k3?mo8@ZLi`LrOZ>v!*1T*b( zouGZzM|x(ht>t!MRF7N{Y*jmLZMIEozrDH5b_4oQ$6T6g7&Ll~=tWJm-a8sa`s!#* zFPY7@I_S*bqn6uRYm3@%Z*H?KpUy0|^ETU=wRVHRptZ%7GdBg*LARurMlk5iT3b8q zyv??D+S+WZkJe*bW~ZImZ0D`DwbRbqY-^#d%{D&Z(6=_qZGk4VG1!7wn{D;c({k#g zb67T(x7pTOy9~an<@SGKv#qtZJX*``yv_C&aN@kRw(BCh0eL&^%w}6_ZEd!-;?CP_ z=dHEzQ$x?{owe4^EVqB%X1h_YFFiE`Wzzj3bzA-Tk^H)~c4nuo&9>IsJ>agHwRUEw ztk2Z{c)kt!Rtu1Q5 ztzJ2^*&YagRTrJN+#W;^n{2ja(AsHlvfQqp(`I`px?idNv(5z(wWV+7OLCQ?=Nk(<;Z!< z?SHn}mQPQmN4c|1T79$Jc`B%Oxh{6v+HX%IRT6w~s)JUuHa)^45Bye}ZLPJpg`uin z&TO{x*4lYH?a44`Ew|;-T5D^kJ(HX|=$WMD#wEGD&9>ZmcBH-N>_~0YYABKlI- ztp9?=kv5i#BXu`bwSrqtn@yJ6#pG8+TCA;zTvepyb{$YZ44KV#W4@JoE$~a-BuF4l zNb3VaIix9}33m6&Kc$4Gd?l2@nh{F*BDEvc9LcX8-zEH2g36pNLH#Ny<>tVappte3 zGD(bN-;v+emZajqDH70?*>af#*3_9NvMd076`eqRhT3;$P|u-WQx~qUK3Jc8 zSJGWT|Aub-J$1plws)5xg9Yo1M?u<{y;P6Zg zreqNJqcZuS;prJldI)#Lr)n5M--kYJ!wJKpR5c(Pxde`e>%C&f1Lx@GMaB#S0 zcNwe1-{IdiDEwW6!e5ym0sn62tqMR#qkkABXSJ#^hWh?+&dc9`-awoMD`bovZRf~p zF!q`E5buVwX~o_J&A?ydK^8=(&9-PdPtZJq_63VrsL@TB;h zWY0@y;(9z&K1-d#bLI0@k0;LOEqm^=C$U3#8assN)8~}+XyLidp5N?=*7r~oo^hY; zcHx=V1Cehoe+&AA5&ezmA*MOMp4I{V1?d$=^qu7xx;KU6?Hu0_#>+e4NDgJZyeE#~ zFviO}<`@oVyu6c+;Z|Yv+!;fEn9ezh-hanX^ht2^a*UVHMt(=pp5z?En33`s>lU60 z$1rB}viG3-k#-5shGSTP@$z|aB=x)Ed(bg-M?CjC?HHa7$FMTLZ{LQFUKK{q--x4E zl~MEAa109=FMmglB)bfSC&V$V&UpERxa&y~*p^)D@N77eMPVe}-Na|ZJzi^t@hoO6 z%Sg8fPlzL1i}Ci^Xda#o$GvvAA0?nqi1$hK3Gtm(FWgJfC&c%Z==-N}ctU(zv3o>( zYkW(5b9@`|1@T4kh2X`+e+DlAFCo4ozMc9z2sg)%#*fF3flm;h9G?`Q7#|m(5FZbo zNPHY+C&rg@+y(KI@p@W4Nq98AlcR5rZz8@qKA-vvz{`kFq5X03Unsu`yeYmhel>nQ zehqws_&nO24_;1u7xg!SH^w)_2gGaQ{o`{fKM%Zu_-<-$h@YaTN5ChEkLBFQfu|Bb zP3gnnQ^fnk`^Ec$`xEcOnf8y5q0O=2pNQ8|vQPXBZ65|7jvtEOir?f~-XgpjA03}Y ztD_0W#LrUqAovXNQIsDIo=*HXN*@59B|egpqv9{(ui`JkuZiF0Os|5k#;?SS<3;hp zcyIdL2RxAY9co?yUx{Ci_lggqY%jvz@w?<-0^cFtlk&ad`SGst0&pSm{CGFcHJ`9B z{zv=`{rrRQMZ6}xH@*kFFTNN2YkVJgfBaYQf%ty#Ij(X|`Zun2O?o$@wVJ)$vu}HSyK)w_NEL;1}`d@w|8mf5$w+{J3&bHK~$RP6~*> zqyF>wJHp@NsqvI}ay&O)O53@FdGYs@eg=L=JcshR;4m5Aa~_(thb7@xkDs@gd-0@uA@1@nPT*@!{Z+@e$xb+|h0M z%O-={$J>FEiMNe+psYG0P&uidR3k1Vt_)UADkYPs-8P;SPb02DS*4@~p<*(Tl1cHz zcsg;Tq)E~^X_Pc2E~367STU)POrUmRJR#nZcz8T49vT-@Qz0oPq{;YrCu+tMCd4%< zOOv%}&452Jo@>*ODD zJJZ9y>5O=1aArIM+$Ej~&Wd*dXUDU^Iq__8C$3}PbUF8P-*iR199$W%0QV!_H(kb^ z-iCO5Tq~)`*|#RWO+1LdX(%`(9t;j89u#jySu@6=QPM0aC2mftA=r#~U_65QfrLSE z3(6WMEeH*g0hAAn2gDT@s{y{X`7^Va$wpv zX#=)P+JY@VakSabVgiDFa(4t&)8h zt*zsI(vfk0uvgp@>>c+4`^3G$zHuM0U)&e$ANK=CadrEoqvKKFn0PceHXZ|xi^qan z$K&Gmac8c!ecUnb0B%X#KJG$U_oN$tO?N`4qz7S3usiV<)V7beh`SQ^q_ktwlbS7) zc5ye#+7Y&hdr{gU=|xS)q%Gy`;<3@4A zxL({iV1u|m>4tFwunA?Ol999;MHrUMNViDZf$ftmz}}o~M%st-&Pe+veZYQ6U$B4D z4;+y62L~ntz(L7CupOhhciKH}6YrfikDGxl;^tt>xCK}iw**_oWnk;L71$5ya$HA9mU%In4@aVhawN(U!nsTq>g zp`;|PL*J$GI7$a46)Z##Z!_UlBr3R zxN=-6o<@2~lExL|3UNxlB3L!90#+fnV=|4}9h2$AI}uL-rzDg485YngA*AunS4{)z!PjK&KFL0k^ zZ*bpapJY$|)^DRd)4hoIOuwbSJ=3?Nx4?Izx50O#cfj|ecft3g_rMRL_rVXN52B6H z%h5~VE5sY4*SWflgjb@2xwZL=Q#}M-PFI5I-0_PT6V6 zpJ;I!;iTkr!inH%#1BMIQ2zko!RQQ1Pe{(7=EUTF${&dCkJb~PN$K&)nbe$+%u0_= zjslNKjs}lSjsef4c2;^^ax8d!avXRR*S1HxXZmckNBSh^*du)^dJ=p(dJ23ddK!E- zdM5fS@p^DQJ*}gMS?PV0{53i&Sx5R_()UGYCufnqhxEPC-QYdZImy|S+(r8C=-lKS z(&r`Tf`6gpuIT*aJkmEsw?sEbmnMHsE=ev+E(Ncr#VRAJ!7bVw3cTjc> z;o9gLN-s#Rp@!P%PHL_uToYYO>G{dE)Lf8UMfugy?DTxDc6NFlrL)uPlk316lIy`6 zlN-RBk{iLBlbgU>lAFP6Im7PhozYd%?&+oOe41Xy{;0dBmq(X@S45YCS4LNWS4CHX zdoV7$6YgXWuM62v>dxejKxjfAKjhYMT@%$w@s!U4MFqd42K;4$obdlac-z!NBYmUFL9o=u)1{u}XnaDDPbawN4!v3J>t#LrRoMDiTr z@#F}0n>&#m%}%6l17(jV8wigjhtu~-?1r{FJsCWS7SB^UCw-p!$CAS+KRkLNd7cvX zwoMOVvkMKVDF1Zgm%j@9l$!p0f&aj&O%?=>`h_cs`j|i_OD=Be@w6(+^Q}$}| zaqXhx#{Q0-@z}E&%rN~FThVi?Wf5nq(4hO zO;&L~S468)=ebv<&T6kp^*FLB)!J)S>iqO7S}bSId{w%b+4cp@UVoeXBl#xzF8LPx zDfv42D$ys3Gwj)1yPi{W=~u~@Opbj?Pr39b+Gw-3OEi=7EQ)^Q$gh(h2|pzf^>fo1 zl+TQQp!~<=2hROX5~mU6vpK8QZO;8`2e$xRKyD84+~|8+{*dg6WZ@YdS`S6 zt4O73LdkT}J4O}Kl=Qr`Vp;*LL_9C8OgxYL+;nBSigqhgwIVB1eb}rduXbcRv>t_N z^|V^LHF}N7QSG#9S|zQO77*7W)K16Ic537bKUV-wLFcm#?evvB{PM-`{)m?olYTA7ZD>ZkQ6Z;;jpM^G{{YDjKgx)tdWQKPgW={9MT zv~k)y=*rx4SY4WHJKIvzIBiR4l(wc#8?Y&HFZ5Z%(aWvmEWJqeMu#>SOOb5`WIpr;)KD6nZ_DQ=DH>0F^G$N%SknfCZxlunLt>O7E#t1J$z#{-o-~O;u^FmLT~R*EHw!Yqem9VvlbJNplX-vz6Io-bMQUvWYqWXn&Q=fwsi^hf-R30J$jeW3w#Z*26fs!?3%vG8Qx-ExH0KBNWYm| znl2-?Fl|D~!n7%MuT%C0v&l^H~Fqr1ZCw?a#zPsn}7%(ePcePZbUqKH{) zZHbGRrB;)tZ^@6DJul@v>Ms|j&jeelXE^`sSZO^?{1oA7X4Oln@4#$!DVAZcVI}n} z^{-+1WeaU67pCo*1#iZjdo$YUaZ~@BdJowm*Mb@~sqL{P(;w$^)V#u+J|4u<^_<~J z=KAp?mOepxJ+t#IIU>`(swG{RK2G@)=nlG)evI_v=nuM)W|u+QZQzVA1#7gIvGZG+ z{ssNU!gMIsc1vk}7uJ7E(>n-vVyU+zU78M~b`dy~cralI+7WD#)4Q>DdlbvOyNCy& zvtWe+VK6p%?o4tIHIHIh_7YZPFVfpfIkn3z(UV|NoZilv??6v7ob*66AwAHn^x*j0 zD8C)8$ySu-{j+NGcPr($VGp-~bE)^#yMHTUHKU8t0ccWsqL1mxS#F`_t>{-qQr?DE zZLxIQz>zmoehYe$VqQwkp9z;@*)*A>wkJ%+2J^9!lLwIYV{htTe>8jMt(841M!tuc-|bWIB&vc zbvN2g;wY`*#t>f>Y&|ne&xw>w3KpmnvEbb;Jq0UlJb2o~{6tVvI!-37to_d=|Fcca}> zEVmb@^J$|$aV_N^V9Xu@A7YiGy7OLGJTFdnOV@zfJ|Dnw#}nL#d@-f2c|9N0Z`6U* z@0Kp(tc%nA2>W9LeIO-zFQ1Q1x;FT(tb737SugI8`uJX0SdPUeao=#vzSyWQPS4&yyrFu8Mns5UeICaB+<(&6p*{y~9J_N11^?|J~?&GkF z-zR)sJ{CLi71Yh3&0K8iXMktYvmUU{!*+QkwR?ek<@UrD{1_~& zwG2N78`~SOu)U6}xBQ-0>;zv%d9x-}}$|Pgd4k=Q`z{ds^n6Is4js`)}6x zSGv8r-Fm$As69>j?>BAr>)PhON&UZd|F87df?g5NFjkNFzehiDb`nP_aa``BU$1Gs zy7m81{~M1`CeCHzI=P>I)i&$@M`923y3wmguS|_feQU{o>~n106aEb8c{-oHf1aL1 zG^)q_{_9al92-3<|DJJ;*rsP|aml?&BUT+Mxi@Kir+54{p;v}pONsm1i~ioWng5CH zTxZ+q(OFFu(K{k`G46%yxWhgGs;+z;_v?p1jr_gN|7NV?7v)iYR};Uk`YWsdY5M;* zl|9iXhQL2bgn@dw>aV)~x)1dK8HqcBMr|C&vw%JmsQ2p^C3m8+{%-U$ZC{|=)#r;1 zM(=qWjNaik7`>luFnage;O{rsYB-`Bxa+I|)n8--_oj8=2K+`g7`<<8FnWKYopOWG z`@~v)Q(p#OMIFADU+Y)F*U^Bl<=6goP=CqSnq!=~wdOd#>1)jio&whLAj_|NZKaz9Ai0|v3T`dp+qS^>;>wt#72G#hk^RrxY6jZ-$tXqdmH_4+D44UD z-}Q~A7dqr}!5Y&8-jm;i#4k_c_d$Or^tZgd=<~Zi#ivo~GrrF$NvTf+`drYFQr{U8 z>ffY5pEdM}L;a)meM8?m^!-DhUs@3HNp-dQE<}m8p}uS~8`*+QMxWX?8GQ=dWc2xK zlhLQGO-7%yHW_`w+GIMjj!pgvX_M*7bJZrJ&rO?*KJ{#3E!{zVN?L97jc7G*8f&oA zRN$RtHSaAIz)HN^tmbW}5?BSD^J=4SPOEv3N(c2lYqfvRTFtvzCcF;sa;tgws}rai zOrNk4Pe!WHOFSnf-um>Nu%UnV(>FkUBh+U`eR6C_sa~=PJ#hU%pF8#GQ=dbdl)Rhj zJE}gX>eH$|x9WRs4$9yrlv%Xb5q*Ewx9EsY>cTgUQ+5_lCe1uem*Y%>-#ju#fRARC?&)MZv6F*l$y1^Qm0 zZx{NWp-Nz#b@}@qcogS-#bTP5gX4IOyI3`I9%Ue zCm4&eXoAr<*a=48Rwo#Jx%YypOx{|q`RiNsfS28Qq3+&Cz(Msl(dV_t@ z8n5I#`+@z?GOuJ-YXqosVk`Ze*f73rIB(_?cnjCrv6aluO%0|5{rtQ25ZZ?_(>8{7 z)d{cUJs(S*NzB|O-otzGCa&-6i8u28ypQW#p3dk^r%cT5>1^MmATc}8)6WnjW)*dQ zabnP;WOhMk8FbE3XC5aqtJu9{W{+Ew;$^4VfL+MPk&PVHPa?_HzE1kpIK%34lFX6kJ zu%9~THIZ^7Z7Y}yn@D|Aun}GeZ_HfUMA+tF6D{ZaIendX%fV`(Gy7T0$kp+4aym1Y zOOMXY)intlz;^5k7cj4{^ZRN8I5$Yl`eiaQ%jk^1&iij;4nHxgnBiv@6Z8H$vwu!7 ziEnRYCNXoE2kH#sBtKs`$y{(>j-_Go3rJ9V}-)auW4j*c6sC2Re!RCBZIuO?WM4ODDn9!m*tB(@E6T&avEF zjumA&Gp&D{OEtZ`d zsa+fB{IAXe>wK`nyX*Hz({pH`8-Q0L1hGb?i)u%FkWx`? zglZd53xV1S64pVr8r~J0iW2q&wLEycptl;{8T^cOD!|?l7_~a6{XwmR%giI*g7_1? zKSz&ZF8(an%*jYC#D}pDA7%?a zVjGV|YAs%B)Nb@qq&DNFSiYuESL@dYk=l=!8nuTVjns;~)VzgNe5p}u+56Gk!CP>( zr5%Y9R{Yn!H7{YySF7DyQNk*Jyu@O!miw1Vta)m|Q|q7F0RO9{@hxu&e3{Rx7T~zo zE2wJWLuv_I{>Rw(-wR$WvHq!*Pp$ZB%m0}21uT6pVwqHnpQ;evL4)v4@HY51Tl+li zFL>+ad(mgKEyd3B6n4?6MlGUKjaoscdMoHuZ}FV!EuK@2T0WO}CBqW0WLV;r3`@L{ zVTo5VEHNihJ}g1=z?o(phoc|7+C#0o2csXo<|Corc+lHy)uO9*-3KXuMbDwCj+1;| zH5?~{2UvsJZ`HB9C;BV+6F!Y&b9XciJNO;o zUD(a1dAs>y6fl2boB1dB8)n$sjf@aU8?h{8)nmcKJ6EvSW|79 zYD`pJqAHUeuuGzURcxwVQ=Q5sQ94St+My~}c16>@s${xXl}zUhpC4hDV!c?f!W>Yw zXIP~8mTinZH&PYaBC{2~4b@zI_&M;cQ3Digi_8|ds%oagim9v4PW5)hEQ`!)+Shm$ zj%snXpvqAN8x}Uks9vuj-mqz?%BM{zo2H|0 zYJ&2xX}E!wjnNErP-v%&YM*9cAzKzL^vcGCUfH;iH7!Ed*e+ZMs>*RXqY_#xMb%#Q zM(?=Lt0YhJ>df}xG+mR|X{lOEbz7>2TxfchC^}WyIh8Tfyv9qFUaI+;Ld(=h6_X2% zYC?N@RcOa>GVN0$)le=p-MyYvm6Qunqs{W_v4!Z!CNXAmG$8Cxdl#=gP3X+#d9B$* zdMBZ+9YF5{_{69y>rtg@7fRKu&5OEG>mJU5&y9vKWIJs{%)rD2s23(Nrc>Cq(Ax(m!muT$<%%K)!3RIQ<^4kx4H zU10jr-andxmUn^a3-1>V^ZMq5LUFWLDXQvOwa;Gh%%|z2HZmLuABBE%CMwQFXnz-= z_r=l|cBVzOlbt9#uyl+Pn(z6l`!@6axc0uUONshYRhWy>4KFaN7gyD|>c_j5Xf{>5 zsfu&eovQ+U399Y|C`xCdCtXTy0UFbp)MsILY#Yr-@6ES(y>}bh+D6OKe9t$kzMmU* zE76ClPIRVM=l4V{sv1^Rv(73}=&N482kkv0RsYWkyTf}#XQ3LOZ_Y+3KHn6eYE_l% zEL5%qQA5gnmWI)pD8-kfC|}Mf)zzxHwt%vMAF%~}`FzymE4_!n3dR+dXmVAXt6l`^ zOQ2o_jY~AVs^vWgJ^FmK%hV{M4tsY%Y-xXmRydLW2>Xa!gsZmNa8_VLA^v(mXpuCLb za_>Pg-z%Z(p_{H3kn1{xCHs5hI z-U#zd!lUC7)^KT9jrQc|8vGOH8P#^H!n-b7?@NqCR! z@*X5r8JQGahd;wSvmTF;4PjG87NMJ;ZK_7!F{Os=b+_( z63>vi=3DsRX!*aPd>pTjx!_#yJ90O*!;G41zNYUa9sqx%_WzEtf8#-NnD(z|{~GU* zyYVzpACkNACV7hX?@N3y)Cc2B#(d?yV&)q4(m7P(#dDGO8cOK$GrczdT|PO-yaT?A zf5y9f?hBSL@!ptA>klP<9_sILg#I~3J#gllw^-iBhvNt>2_K<^Cy{z4sW*~(C1r4C zG9&d$+UGrY=9)MCCx2wE>Ra*$UM5HV_Z?+TbIeivKt9J0CFZ!P*G0u>2W#3H)@D5! zQNlAwJ%8TBBjQV3aqTVmR;|KFX znDARt|0VSh`o#MPeHxbMyDOCVf!tW)ouz(RH{qjoeOQjID<9oVZEvU^Gv%TOy*HQo z0R8H{fPV8{Tk5;@Am4e4Z~LXho9k!zDev3#vG;EJm(E?3&cl?>DV5IkmCjq1&cT+>CzsCim)a~!?JuRaq*5DSslBq)_Nvz8 z(s$%i`+libp;UKKs)s4n_LSAqran$~wj&tepDLp==*T(<6|CIh; zl>T3o{$Ko`{a@6>n+=cC+m%aMhn^h#m+I4A z9;|@pQhk_a57eB28iQ2xrD@*Ay0EhJmhc5Xs&nNw)uqKUbo5yyS2Q_l7W+>A< zWx9`LDa)}18ZEYgk3!XeqgEBJIn4CPHti>(i~Kp&BbiHkJ%6_JoYmvV z=F+NXt{%rbm%5(6dK~v$e;)KY(DPW2v!$(iHtP{}Ouf>YvZR5UPp=uSve8#i?2JG%H~pe;zbzUlwP$BCVRYu)RN4^}+g#NaQvAH-n!Zw{nc= z0BXKI^~-C|nbiD`!WpUu>TxeaUGpY(B4VxjPj%$X^rSyv(dTT<3#oY;RY|OQ{T%f! zpk`jwY>hp@9`tF>M*StwoPhe&-39DM-NL$pnl~`9*P2ySbBpReCiYJErs97bD?KWj zpHcTu_epaF>hV(#Ki!)|4#)N!??eVhJ@y?-_DuIxGcal{Qr#QP1=+FWOg8stGjXo} z%^Iou{cn~=y%rLCrnw|L`)ed|HEHfr-KRv>NzFE>Sxa@Fs{h9|n8?nmd#}epb2)1M zM!h!msC4JL(<`e+$u+1~rT*V{2lW^xj%`iG)bK}I^PKASRjcIc(`!?6X6iZ7^P|^Y zEzX{v$A8bbp4HkV*P~u*dJSrfx6{o(Gde!LvcP1@~%(nktf$DXc z$Zn|j2|ZtWSJBVu^{g@VD)UJ_YkJ?zW8HdQa{c+rrM*7it>;T)>Q!MY^h{|qJiU0{L3ey+u$XQ~rdot~*qoGFd5n9ic-OXD=w zrLO}hlzQiA3ASWJHht~Dx|Dk7Xa%;SkC=k~4vRGTh@{ReH z7QmU=eB9yEs-lg*eq_5u1IHFa$ceGkGPFnP8v zycWIL_Azsikq^=Sps8>3Xuli&kjb_6;ZK>z=uKy2E&DO-6Z0oqS4Iw-r>NDYJ>Av> zYuhKyVOmbGd~E(=R2g~NJV~tvy*2G|-}g5?Ww@sAFn1EO@J@3Vc$c{yyxZIZ-ec|s z?=|;<_nG^_`^_Ch4{Tubt&@D)5Nv1*zyjL{Y-Dr6LfaT@Y@2{hYym+t4CnL1?CIceyOp*IvfXS22hwu7tte-kEvBMu zG3T)2k#>}|GRh9N7n<#i8N`@@c0cS^Q*4`28(~K>Vl$s$Jl|hNj__UYn*sCO z8G9zZo6T4|f{|4jkz%XbYBmW>rmSjHC|@=&nCH#Q=0(bv%}bOoQ!giH@!2!Y7(15F zI&1m#d$b-Q_HRY{M%yv8zrxsZQiZ;%_7=WxziDoZ`TqVa1MEfS0@`Bh=zo`S@0nN4 zE0mR~^BEgczC-<8^BO(nq!RVYwx9p}#pWVDTb5B}iq|OPjpTC(21hSS4HD zmZN-=`dj7=@J;Y_$_lhrv=!(tBdu)<+uXLcEh$^uR+O!&JGqJPxW(LL_L`f)eUvwu zTPXX|*U#=S7t?vc3_$bq%Ol z94is=b`_{OLMstHc>}nCc(IjaBQZ)V5$$y~5i`%Qv^iQqk}S& zgOlwPaEd(xoN6c8>-~1Lvu*kQ6|8BcnP#Wbw}%!92F5|nF zn;CXG-?bFJ%*?bi;3MF}%~rb&K8$#vmE>I5HaikF!klBbQd>kmoyF!%*tvEn(LyW9 zAeND4i#><7xptPFY3JJ6lymJI%DL1HxirW%L{^QZlw=CwTgMPlw33`f-Ui$*1x$EOWBBr5Uw%6!jYa4>O4BRSt*U?aJ}Zn5Xt^I-$%8A4W!QH@YBt9dl7uTok#zC#x3v>UAZ!-Z?e4^GtgXUw=-rQy=1Mh^Xbue zuUtd0jdm_^!YP#bT?QCkn&VCTT*nniXYwF$&=<@$rIx3gh$%woHU+7i1MoJGrQ zAAOMweAL(3Rd$VC4X&kJW!F(oAvWd&qcI65f)n_}QoDq)Ghwrc<~D_LCG}Ny25hET zW|vaaIB#4*u$6W?Oygcnqg-y6(YBmrg{>kQ-L#5yC(3CR>0!EqJ&D;`MS2mtwThfZ zZkH<3n;5QDqz{o_t4LqsxK@#V#A>Y~n%5eU_9|Ex*4NcsLycz^co$-_YDCsO_8MCD*lQ{G*y||w z*xi)v>DB11RT$mgM{R8fZ*Q)rKa{rccIF0qJ^Y|O1ZLAx$2pyX?cL6NIHgtOar*?VH5rv@ zZnihk(~8#CL?^9E>(lmedNnR;6}gwb`)o^CE3?<$OzkQAG`;DJtY!Auy|lETx22Du zT1D=mey>fTH{BezPcgDNy)Dcwb{{BMcB>I*tH^EkR%*BT)*|Z7e0C*` z?V@p0lSJdD66=MCsl5LaRW(VHG(xIWBOYp!Boj+DNm7VVnk1=2C{2>;#9~d7G-9+S z35yYV#y)FBp0&?`&)Mg}=j{vN3-&PhqJ0T`$-WG}Y@Y#Nu`hzJ+E>8W?5p7G_BH#4 zeH})gE~!XF)$&AJEd#FrYTm9gEM?6*j1qarzDfCxeT(uP`!;3F$TH?#Y9bCEoA>Oy za0_?lhTR5>|6T-5kHgUXM2j;N!ZuX_ptBm z_vCm>lAr9))V_h8ByU<0Yx%$))fSfT?RUgCO_Cq&Pt?AJeM9ECB-ju3M_N9#AAkX$ z3e8E_H}*#|!|@I9llCXF$0f-}_CspIn817m``Z3YKDi`0WWgWYOrO$#R5fqsj6<*#(p3C|LxPO&KWnCGtB3u3%>wZ0|#NPCfSK+Tkm0czHEAUsNDy}m8W%w&mRaXW668z;T$yJ5F z2!AQ6=91vat{V6PEiXnXE*btj{Dr6^6+hAxNNeXx6@y0BdL z5b;QpCDo-+dk*$|l{r?jW&HlO+?L*HCbx7G-^-7o{2JG znNFjoCd*SS8WHw!%9^eQJvCV}+>^8&j%vGFuBNN)(kW}hGMvV8eTqn~PZ6;-h3~%` zyqn0X-KCK$bls)U)prH15$tw)?unXG>n?Y|Z;zU|rtmxAcM!2O1=iR#q2(GPm0lZl zaUER;*Tr?B?BY68UQOQB>xd|N9obn^MI(!*isoWXmFvk^nkqMt^E6d%B))2@+(d-c zRJob#tf{h>7^kVSkBFa+GwSR5z%PdHi2Av{@DVJd-C0B#O_fn@G_@_Tv!ju26nq1GOElh%gl~jz zi2A#J@QdIVN5f$w+&RP;O_gzOJhe@*jnOdJaJQ8V!l|;I<)UbS>rdMmZXCFomQ7^q z-A>fkLGE-nzzuQ(DbJ_nf@mlshPiEI98Q(N^mPLVQJ&}5bsl5RkA~1X)D3ZiDbFPn zaVnT9=S5@P8MK@U-%M=PRM;3dmX_+WmPn}8WgXE>yUIj2$#s=UZj77YCc;+Hvp$+i zt*fktuZpI)sqi)M)kHk44x8+z(6ZDmaf{tDx76cex5&-#(Me|z5p))jPBk)Un#_Tv z$ux3Cr^$43MyJUPvPh@NT>8^w9IE_3$&`TI}031ywOo)Rv$yTg?bm+LeFM5g7IUBKstuL3*C9N z529sYbb-4NJ{UeIIu~}H8$vepG&#p@p*9>gBH9K!*J+H_G&$d0K&>xqaJ1E(1K-NB z&1po|G#SP+Jlg5br>!5nZ?wbhg!hN{i!OFM-~-_Oql?_d@YCS~h$Wf^+wLx+rG}hF ztkD|Mn<%E8nxYL?QWO51lEI|KG7A_I!jM@kLYrD1-uu$CoxoOz%Fx_({hX3 z=k~f{AH%blsGu!~tl5fkzq^I@{VX@Tn$n8an$jd{3~Kz#no<-s1)C8Gv!-Y)&YGf8 zNo$J6FRdwUiDOz*+C^=__E9^q0})+oO2?=Z*ePlcc8LmO5-cE9*y9&I@T@7CCt^u!c*Mir&%fRd0Zg98T1MYEGg4et2z#H84;EnDE@FsU7 zc(c0+yp{dwB)7R+!2|9#@OF0qyu;n@3i;;7(VgxN>UX(2!A7(cMt8fr;05qT(LL^N zctdzWbg#Pyo)2#r-RJIwH-P6y_q+SxdGH3&1MYr!eRy8Yj z>Qg>Ky^}mb&jYS5BkL2Nv_5^0x<_cwrloH5n0pjn2c8`rbdSNa;B}%y?jSr9o)tar z4#CsmnbBeQIJ`DIJ$lj|hG)QQM^CsX;nm?8(R1zzcpAKV^sIXhUIU&MJ>#B**M!%I zo_5c`iJMA28LSmO<(}3SNhX$SElDBXYe#v(z34j1i|#4+yn6vwm7dh-6>1$N30^gN z*}Vd<22UcMWi8lC?qynpSgAquPZ&l5YUI>o?gMw!9djR29&;a2rb|R$x@b(xbkS&; z>7o%k)8$Vhcc#lEzfM9*|7OPtJf zDM#eYbSY2N%yg+hl+ARhNTknnsYJBYbg4{4)pV&6m5n;ctL`<|L0)sOgRi?cz&G5R z;G6Cx@GbW?__lioe8;^CzU$rs-*fMRN8Eeh`|b#M)V&WLXRkWQ33nX)*qs1BaUX-9 zx=+B*+^68@?lbTh$Keb2IqVnq>DTZ}Y8~Vh{Fm@6_a*#i_^I$~_Z9pn_|M@<_ci=S z_)pbXt?pybb``&#Aej9%8qqzP+`2%g=xF1+L$Tvho)i|)}eC9{mI><@* zH{nn2NBGz9li|y6FYwRdpM}4<-{D`tKM#L( zzrl~gzX<*9>`sn6Vl1X80EP7V%&+@W20s{P$93S3!XFFk#@X;k;Exh}_7P&v=Ega3-8eU{NBJNv z4~6xqx0Cv`)r}uu)NQ-wVGlY#8Um?}6VN z7Q_wVcf#)p8^;CkyWn?*g>hr}-SE4@Tfw`-MsXo6#c?C>Hd<~Co5jWO1Mu6zqPQ9S zcKCs?X%UMBZ&H&EpnvTWJxu1Y5>U;x=(} z*v<6c6t5>@3k}*;#T8k*%}jTH;J+$#ulZ&XV0kiO!Ne;q~D4L>fNu=P$K&AZ;TysU@p$+e`1){iJOREIz9yU$Plm69 zuO(u87HncXiIy4hL~sQy%fspM4ERd;if~#y9li>_GMpMugRh3KA_jdHY)U+pmO8Q| zTpHGqr9_>tBg=@3-&$tIv*Ok=E1nI`j;F-);+e2T^e+s@6QzFwsL}e@$Lr#?@p_gu z@oLI7@nqV^hjaNvYgx?rMd6%yE_@DrahNS zE{^AbOX8*A(s&uTES?W8kC%We;^pAVcm=pBUJ0&_SH{u-A=ugY^UwKcmN{@lNn+#*&Z&6x6|IAmI2|#@kQ`{@c!YB_+ofpc)xIG zyaV0`-Z$J8?}Yb)_X#hHcfn7C_X;nKFN61npB8ondxw|Am(p@|dfX3!aIb!<2~?J z@Qz_3-|s-5)l@U7Xg-w;O3nS*Uuwc@g*lQ*nIlwwPbiCrwUoU$(@oTnj0lYG&4z#G!2`8MdT>Sk!E2LsM%9; zq&b;Va-;Er zNDa2SW;lde3rU052#1mnwS`oNr-hpRw1uR?tB1qMY>MIyo*IrKziA6ehF1$mlC8Ui zq`;HO5`@+-96`p@7BY_Pr!Ay1EtSGEsI`zP@XDcPVmcKpk|nZO7Rge|-^jRhDi|wg zFs3SFs)P$^UnH7w=~OUA#?qcddsVU$<-kVE7+UH{d9oeVlM3W1swWl0GGTKWFB8z# zOpuA-L~^Z8p{2Q$rN2x#nObux2QN#GBNRsAB$-UhXTcZ2=fPRBSvJX8awg@cw0stv zO>L8W0{=9~70u?9D}R!~DOdg?cT=u>LFTJm`I|gVx$+Nrn$RYOL5OBC48f3`O=ud) zn3OAqtWCLMLkBvtA>~RO3ivyFm&-SN41US?Ad zE8mfwDp$TI8&$6SK<2Al`H`Ggx$+ZPr*h@z;3x1D`KO9yDmj6RS*C;2$y!^?G83FB zlfYSI0WQ|;=inU17Ly5h7C4Wx*yl4ZCbRE+_(IBJS;pBYmgSViWQN`ZuAo*dD=CX* z6=kukrYt6N@M>@^Wigq9*MjRQi)904v23Iy?<-}oXb$jV*1J&7ffvgOw*BK^E45-d z4nGlWldbS$@Z-T=vMKMACj!m&b~AjhXr{MA!MU=HF&{AISa5-y3;z)QL2wgeZkEI3 zfjbnOFBj1M5$zw6yDS%Wo}5q14ml5ekCu0Xi>VdM5%_z-MP!LCmiOUDg6(n<{3!f= zGO^{tE|l%G)R(u&byi>AChu8&d50Ws&B!Oc3l-QdvPd^$xsZ(9J7I6o|9Ws4wPx}r z{0;KW)rVb5R_SJBgnod0-FN!Ddk;~&U+#e489Ypu==Hr@ z%aezLhd|BLmnWK|FHbZ(U!EK!BVV2z3J!u#k;^Vmo+jH}o;*X2ygYf9e0h2DT<|RT zJUR68INcPZHB-c|G$qkf6awBDt+(cQ#8NUhK zPgz7B?)~6xltn(5dXdk$UgR^$7m?rn4%+XcEb^J$i+o1+BA=VRi0tb3(tbZ>kvzhd z7LlL(5%4j}_c{JYDt__|g(>nXc$m@e=$QaKa!fyzkCU-ph3BNJ; zp3j|>Rg7O9JS9)lelzVikqa{qc9?ARMKaQ7uN_4O+2LesP9~dklFxzNK&~TCW&_zB z>;d%5GXYl9cb zgWgnnk;V43pdPt_v%wt7p0xBL2XZ}Hdcb=I`J(wn^JORbKl5c5xjpmc60&;c%cW!i z&6mr_=b0~;lfN=wt{`t_zFbLm&3w6vyrB6U?{mR*Xw=mlb4W&6kzI3Q%*& z=8I-t&6f@2S)`8THgCf6BKW4f z1->P3gKsmoiM&Hw6M2`iiM&VIM2=84;R-qe9^*P{LLT&E;0ekm3hzEiV_ zH<88c&9dM(YE5Jbd~xtA*~FX3QuvZ!9=J64g)HMuCtZxj_1nPq{$)lUun!29V9UfDF@fJkfG#@E|6j5jV_SkULTN^h@j^-A|Ef?dx$6rt zKF458{`o?3)RzUzax4nTKVKd!PsZ~?sSsGOBAMO`r4rfC3#BsI&kIGfpBGA1vY!`9 zD*vg4lFNTzp;Ra9eW7T!cU0qKeMcis_V+^39PfobqkExfw)8^DAX|E&WCj^v7TMAZ zrB09qW(Re^`usl^lJC7f*no`ag+j)6upyb>3#A}v1hRmIWKJ(4vv?s{&I_b1`NoUj z?cwdnfZi0|0p6Y*;{~wBw5gK2nEd07q&fM=8%YaV8%axYgEx{^WCm{}t;ta?au~Ht zAdjG43FSh|^s#KQ>bE=EB0QDBsOOyI>NKEapmi)G-=kz!U2{1phnBd!lt+tOK`Njx zttb^yAyyLA$5ocfsH&=7$YtG+jo|#+7Zr-_C%H_P} zwURl!`?r=UaT`?Ot(c)|D^22d=*J^wO54jH%)54wmzc5dC{Ho}-$^cWozbvw#}0+< z&UKZpGRAeokD)P^^zP^adZ4WT9Yse^`2p=m!h_>q9~SlGUA^L!GHJT;9b^x z2dKwd!iz{fJ^s^=qaN2-!iz|~i?Zoa-;IPvQ9h;mZsdaM+3~Ljhk6yMA4fh{W5Q3U zf%gkgFOH_PWwO6@D2rH{vgg^pA8El8{VFpKA=xNSU z?Dw!XsNPyFXm8FHn_jYq>g^EF){-URA*FsS>dDuNqY;1seGRGC@Oy}rk)wx}k0s$D zRf9cHAF?+5_eWqvU&6yo_brY8od*1uT6)`n%wKXQ^Jr;Dtu4nRkGg}m?aji!;h@tC#UoL^LfWsTkAAAj3sm$_sOS0wV+OuXRyuc8~BshWv9s@*9j}Ye5{6V z@GTAa#{BpR+8=ivnJb@@A=dZ*dE`Ztk0Od_)*3@=DIL1KVQD1^?Ro_o;lt^Ia6{OQ$K!$F^{^g z%-YZQwx2oJ+NWZ5pUj-{LT`hgDpO%o;!9}1+UflELT}xiDfL)GF1E6&tTP$=Q&n$2 zONzh7s;KrzwLE@}T$lpRWQKg9jE@&E4=^4!Empg1X8Rv;YGar$Ih-ab`_J*pRfh`sg*_Gh)*sx|s3c!V|W z;szU)S|Fjdar+sDO=_?=zIY?jX0 zFJi`i4yZHFiyL!@9EoR4dPE*n4__YT>#Mm4hlIR10w*-}oR3o5_6B608r4P;cyE`^WIfvGMt| zpXU}c+r9|Z%w+U5_cH!Ir?#;LUg0rSM#IL$Tj||~8e^K=>(q9(fZ4>we2O_mX7U#^ zd%q~Y5iQ76>_H3o%-xK<$EnR}0qUK}=yJ|+I{&wfx&FmoFEUj|(l;u;i;;IbwM#9K z;og>{YM7hcFt}Qq7BFrf^{Jv7nwwCKOhY@O7OVxRi6*i3 z=#1PQjJ(sSm1}{waxK87wSaM|x|xb9MaLcROs!uFymDnK)-N4*8|?>BuiQ$hR?;u)~%?lNZQm&i_* zE8{7s)Fz^4n>_;yZwO1^~ zf^iMF8+*l4EDKApDC~x*ZELZtXY>YCX>%wqqVHlX57*HFkTH?b78>sfE3n;fS?t)mg zfD2IsE@WLxSSHCzmQ_wITZ@@_Rm;gTxgJZwGH+Q}<}C}$uq<3li&_?z$zCi7%djl$ z0k7paY~_>NV$~T=k`;c9Y9V87Xb!nfVOz06+{|cI>`el7oZ8P8V?|rci1DZ=hr03T zFGqkQP;QQwk!~2M>d5hEFo%N^s12bU>h`m~WoRtN%Mf=fwvA;n2tL@URb!b9gb#9R z+gK*2!w0&%ux%W`%A__9wKd%V9-z0MS911a%;_jZRqv^`sAbZZmVQnxQp=+FMucpPfn74l;IQoKT5qW@Wz7h+ZAj*~ay7im>X%rdmHvx+c_w}>ew{J-^fY#A%ULG9SkGzbv(KRQZTeTB@omlc zrx^cq+>_p3?g7Rv_g0@}QozWDPHjKSr3bw|ovMMy$zkeG#r5b#`%HTerY8I;2}`^R1e)AHMFXWJF$$Du6(u|+TwB8 zRUU~SW>jZ-#>r!_gK-x>q6-S@aq=iFkHwG1k5I0Zx7nkW@@D*2yi(qZ-v-}_-v!@| z-vi%^kAO$w_rdq$H{%cEcVHh-u9Tzk2jE!L=XKp!sq1pU99IXd=W@YZS07YO`dF`C zA1e)9HvA0wvncDhkK&`OArqd3ihL}rHkjc=KB8UZSo~2eay&i;o`{df>GaliAIB%C ztL-TrZF(&f=xJVyo(8W0A4B`+@h9=e@#pcUl%L0+QGQNcq&mH6?h9&y0)GtkFXJ!Z zDezSHRs1D98J^<4j=zFegD1O_@z?M_tXjAJ1plxXVcp>U(EVY@$hoj>cr1*jPpuNn zgy4-ZM$Utsix0zS`qVZNND{5p+&A$_*0z=Ud7@qoWAJbo&A1EXLfU?X|6|oM5=d40 zlH4l!hVcc)Se_*kkndN9>0q*p!Su=`=X5ZBq{4QFyc&aa}rQ3dK*|a^7g299=ze? zQt(o0_{y=(YO}%rjWWcRiEob`h4;=6pnB?zVk>?Df3e?zqpAHw`J+7v{$#%aPvSK+ z3jdvmb?AG(T6-dvD?qhzL@ZZPC6zRSqFeD*!779E3M z*-P|10((@RfIVl`3S;mT8_Br4vHKXj&R(YHVb~+`B>^_c7z} z9QGf}!hXRmcAaOz7bz_^^$~2%a5;#VqEoz}~EN_BuGS*?CcpZF!^}G#tSSQ{F)k=X!KE8!_*;s@RW@&WdyP~pYc{&Zo^-3nB0oT<1pE8W46mN=c3k=*jqni zQR`>yttYX3K#y8bV%f*|TddkqV%ZDdhacuJ*v)n*d!?3@*jrX&d_srH&G>~5g{hS# zmK)$VTD7&ray|S8s}`3SFV~^e)$S6@FDzxSr6^N>+M#&T4#lVT6!kLlvz!9A`__xV z?eObJeJ5;W=-_jF%&)%WnP+GsE zuC~K(DRQ=x^C8sF z1-IF1VfPINbG}u{)j(}~22nyI%h`WG2g{TbJ zQ;6k&J*Awe<&-EFSWwlbQV!kBVA)^?$r`?CkSxQudl25+%fJFR^NmDJP5Ii>+E^%6Y3yIax@{B0Sg!!PG)i4v+XjvcRSX zwczvM^Q~HI%HhjDh`QQr%E=t~T&tFwaxxn}$Ey9NoXqr|{%XI;3TD7(TD8$;1=ATb zoA?5=i7Svpy`1E*ln3iln`j3TaiIX~PI;m&43vqsA(pE0#9Wv_Z8FOs>_Egm3#PH2 z=~ivN<%z{GnOc2VUND9+lWabApz=g#7$no|R6B)IEyBeAVW}UCWy~1c6zfrWB0db1 zu~uzE<%#<+kh)rh$`k!zAoW75LFI`9GLX7jn936kWFYm?;3!)`)Yeo1Yg#c_j2)^1 zcBt~$NQz)BurgIZRW{5Hx2F?rWCS?c5_<$)8K0*dVb$iOaYbmeJ+b6<$9Apu#9r8~ zDTxo!-FEXaBPwE_QVWLKq=-a?EwZAwQ4)JAXa{eH4XYxStqx!ZY?KwTUA6){1?|Dk z*fE*W#g560F1AbNbFp1k#D3ll`*|;z+R-b@0O`s14PdJWfn9AEu$%1)_F^jr$Z15b z7(k?r)4)DNuoyrjjy_;N+ZXI_2Y>^JuEH9KAu@oq3@*P&j) zFbo_@Z!<==B-%?$qN=F2p^_BQ(#)#Dp^`L(7g<#%R3b`Ff9h(rtwh|M{?yfWTglsQ zD-m0#Kdp_x0y_aaZY3h@^p{3@m)@cMQtR$d}n!Sk$Ib1M<4r$6<| zSmLGxm1PPo4Qa`@ldxS^mK=CPtCrx(ShgpE{Wvx`wjWD9n@d^GPRAl%+1rDOD@aSO z%?9h(+1QCIOI>)jt%AL;GIoHO!K|PP7V+7j+S99GPoD?Q3+99Kg9YG%U?#XQSOhK# z7K4kizpq9uu`;MkY?~^!vX69A*+;xtL(j@!4aPz zQFHqExHx^J9I&zT^=bK? zI9q*SyU@)fp_|zS?m#P(gtGHj;#BpP--y)Jo1^k8(Yt!f59SKAHAEzU|7cW6L(~HJ zPe!#hNks4JP5n}oJ47IWpE9byNh0D`Z|Ya0$VtLp-kW+guf3^;_U7uK8Y-Xb!0XWD zR6`GxgbwIh*lBFV_vSQWdwmXmZoUA&AY#~QLOJs?xf7M!fgstdl9Ev+T@SxLxB`$5&kC3{^Q7JM{y$>``h@*&Z#dJ*O7 zL-3gS2t00%fhWvy@MH4{_=))x{M4KPPowQM%GZhd)Jt9?CR8tZl}J*(h$rQABnOOeCyr_9r+08_jQ zkaf~>*gOF~Zk|UGm?BTYpD@p%^J6RFPnu^@1hTF0N6ahe1ykfP_@hSEfhlqj{+Lm{ zV2T`qA2ctbj%1(Vhm2|p)dK&5$JfyrzJ|^+)vF0pv64PaEH$;EJ_tT&9s(aS4-;99 zI0)t~bcd-#gCpL7c@yPkDiPU;cVKSx@vUy~ajtHF-)KHVeR~46uc~lAL+SfTP#ult zo1khttE26F7koE(4}32;0v-w80N)Ref=7c7zz@)ZR!3d>KKN1aVbERnnj1`a*+UGe z?sC1^1Kwb+2Q{)*cOq@=1NReQt2`2A&9xgP*fkX=s%{2UTO7<~7D? zUSpi*HO6UPW1QwS#%W$-oaQygXw0YuUwiU6^)h$}!GEFujM z^{Sg(MRcofM6|jJyvAG&UTdxauQS(zyUlgP1?wi4f*N0Ir;o?=3wq_BydwPPUNlfa~~8dwcQJ$}AnRWKz?22;ZnuzHvZriInP8etmfeKhcQs146l{|xV!QOo;f z)RJucGSI5vmqD!Mur62+zl>VmFQXRwp)qvRIRc$!3X!xr%T(fKb(U#nD!7=V(OISw zAFH#Elhv6hS~K9Y%uH~$nFY=RqA9=+q=ENu$q&cTJBip~lju`lmj>Y(w2UKmS!X%Jq_h2+ z`K>;FCF$O;B;9+Iq>FmSq~l{!2sYwVV;DcysBcNS_bo|B2{MMLX`N7hj4?&{nWPi5 zt&@y4Bf$}-IX)-pG73J@6yr&fP9(KX)SKaRl1}WjPSo4rk&-S$;X{o2pQIB7t`l|j zNJ%F$Tqo)+!&dOq;lqu3t)vq*trPVD_#mAg_6G-q9ZWmZ*2n8=XZq37AGKOLJa=m2 z=b}-H+vD@1J}tG;sI>(`8fkM`^#4+HXj`y&qhr_k+vy zesG!I4=&UD!DV_sxJ>T{m+AfB)PpY*MN$VMgSD3i#42m=f@Iwx$yc%J^eC8J^eDJE-kqx2drym z;`K)?ZFr8EfiE9gFnB#P9j`z1jqnVU1!kJf-rusUiH##hR~gDpv}{KIIGvGM-ZwA{ z-@xf%9mZ!F^%%^Oa*TB*o0d9eb~uNYTJUV6zJ*!%HO>Ot(UxvB-g7Op08hv)^qP1@ z8}%^EA_f`0(ZnIcYuVHUYZ&!!R4>QHcvSwU2jz13@^A&XB3ucs4ApaTb+`sxgRdnz zMIxbTMD3bjW#XZ=B_3K;uqyG*+7b_~GFXjxXl;pymI9^_4-I`8@zB~553LGVlbC70 z__$c7z+a+Wc;sH}eSdd^Khtt5x`f)r=s;J6tHHJ5DsWx67F-{$12=^0{}+4b9bi{c zw(&FPruW{n+3Y5p-m__>ke&buJ@j5e@4Z9l(t9sbEFcO>M??`35Tr;E5TsiGQ4tgc zzTa<# zR*(UE5@^AOYW(`+l$LC9U)!gBVm^EAxvxX~T)^G*iy>E5_Ims2o z$-PU}u}Rrqs4+Gv`+!e6iTYk2fd8Pj*CgtH{R8}{^db0h=_4>}^f4F+!kt7FvjCPF z&5jVfh-;!1y}V%ntaPo-a! z9xpuxK7qWA{P5fJ+sGcjBY&G$|5&Qz^BV7XAvx5QG1Iv+W;$2KOy^3nn=i?4<^8vj z*?c+gxD;7QR`aFcM84(QrHQdx+C*A^p#2Bxu1(C|p^BRM&z01En@F9sH^JYR%!{t1 zy4yr5zgbya@HeGbO80PuAC~%Ock(^^$ISHp{D*!-A6`%1dw;UrZvbz|zYTsn|2p`c{6_G` z{3h@w^4a^7A^#old--?4oAd91x8yg2x8}Eick%o6CqMr#@NRPS`;*~+H+WC}1Mr9W zJ^A?T7u+N3*}nw-v~)lCK1K3w`4_(o59-lo`dJ=rP^c46Eb>7CuI&b4+owxDSd3&Co=c(H^o;q*Of-jX`24AM~+uQj& z`5*GjsnT@`^|~%YzD3X5`4ya9QhJm2Tf|o1OI3%eSk<8_yD$GS?VsfLf%oS>0j=s# zm02C4DziF76*U2az>R8fiQbgEQkrH`m~l2H}qqx=+lPA&bC>JnAdIU7e6G;2vzQTuHi=T?`f zqQ)CJqtsc+N*_{r;%RzrqvzJrjo@u1GSKKHi;e#0sZTM0suRzHJ5yU~ajBxzuT%+I zt!5YMPc1GPM|~rBW9cUFrqXvy)~XmlMYC$6<6oqP#Q^G>RdfCw@Y~cvtETGO#JsXz>QkCO{d|<5RF_3B=FVlWGe+7Ice-(T+{}uRJ{yO-2{s#C4 z)jtMOPvo_H99J4$TEulWDviymskk;ayOJ7iW2vZiC3qE8+Qw#AQ>ATetkO1?Ds5k* z{WYqtjipN4HK0}6#!{v2I?yU@V`G)Ju~cchwls+UV)Ss}cN;|2lHY*8%YO_0KK~u~ zX8wEdkBq57)J*v!_~-mj;Jf*s!N271g74*j0pHKx1OJ-85B@FxEBFC*YzAf4u^ANW z*bK_v$={@HHJd?M&fQ`s5bEI!iq&ie#cDRh@N>7vQ2Fc(@GL5pjiFZBS>QRPv%zyq z=YZ#x&IQk>UfUR|ww(`NNKLmfRCc=%yts4`cuDDEaBOx3czWp+@Cs(fnC#fnao`E1 zW5E-t+%_gVsdOTEG8NaxWY$g_6YHWKk35dbXJfMCOM_#LoxxdCYUvE7#!hpvIrVl1 z^O*-_gJWHt!PM1hO68x{^tMC}&Wxo$vNSqYP8*#aRXUpX(WPU+V@gX(has0xr>7ymFrL@u1OlwzaPx}bkhf}v~G_6CxgG=lkK>v_fw`T}7hC0&Ik%~n_$i-+2b}w}( zjpBbE0`5%>v{BSX+ZWuAs%WFAigo~a09DaO#j0qdsEW2X?L$h3f`?K+Z7B7d27rS~ z1Hr+iLEwtdFE}*oNRP%*2tI70gCbt!y)J z3o4e4r0Urg;8vwA!L3VMf!ma}2DdG318!H^7TmtH9k@ejdvM3n4&Y*H%8kr+WrmN; zcBA6lNNUaP23lEeWUMSl1{js)$nm1GoRRSk+|Mo>3x0l1*F5L~;o4!90g*+x*WZ4Gd}(%RtqrS-rK zO6!BxW*d=>L|Tb#ST>ilg{67m+|qEWlkt7BSyUk#p3N@J0q5|(;r!2e;5_QD4JXrQ z7I{BUVn^yh?soUgx*X>7>;?8i3#cTc;6>KJfm9lLF)uG)-kvjNh4_nhV?NgGGvjA8 zTO{oq@p<-~k;e_q%(zH9qNLoJlr2*1Ipc0ADGSG0Bwtz9o-?k8dB$B@GJe7SV1Ih+=2f^)OUjH%`^==hT2c;8 z%9_zHzdHVGd3DO=Nm({2|HkM6vwLP>^=L%KLn#HSFj4%gjf21l8=(IPuwYr9U?fWUqE{hxg}<%m~r9`O#?aWz+uKo zb9&m-L-l5`J-=)Vdfb<#UCb{T1Pmi9h!$1A^SfBGsw@2X=jjk`PBMI2)-id?f2tE3kqdf9W|$fB6yoqH{Q}#6mxZ zUwH&;tn+;Yzw&TaCV%Hq7fBge zGm&OvnUiI9*7P{5v?I3U^S0*|Gq~o&)yEmQI^W4WFSEVO`zo@-%oH;(%M*HBjns=V;F>nO)e2!wf_9 zHnR}>g61R!uGIu|RSUFQ^11xQU15pyq16n`k&WUn>q<-H5ob-~-!=km=kfRTubT1> ze^dX;ykTc}6OP95FMOZGxR`j%FZ2B2mbL3#oYXs`XmaDV98GpTMu36vb_kZ{+rf>1--=TQ5 z_Al13_h3AV*L8+3>%Mr`Tk^lteb0~$zwgEM{WOlBbVvP$ei!e1V|vqP`0V$5v7ezK z@9cfBj>o zA!Dy0?zCt7{iW`D@_C-c|NY~tc&gUc+-g5nYc#jddbX~r zaaH#^^{;7P^jgud>wmHO)xUCF)&0%uf1ds)KjZ3t{x8Q&dX6Vn`02H-K0UKwKr6xr z>;C4;A2apo+bg5PH{}1;eNX-4p&{>S*gEjVa;Pu*Gc;tK`FD+(|1@3t%Q4e%yHi8P zOhevN_cveuI&sO*I*S{8h(Q~|E*I&Lq<67~*VypB{sM9zq>Kli} zo%+%?s9k#1+b8SJi-yddm48p6dnC(YZM*c+YeHSi;iv7=Y1C*xto!+k(NfzI)wDt5 zsv%>qn7?1z{k&hF-mmOw_PV-rx&C#g7&CZI)U>|F0VvUc~OM`0udt zL{GeA`#e_^CT4m)5BY zOGRzXs=j=vy7&Fd@nhaxL)M>v<@j0Ny{?<}R--=$G-*AqHE{^b8b4n?zgDGhx)?wI zDK^qV_g*^oY2`Uxam|MKiCk4yolj@w*QozC{pYjB&x)_x_5W@SS;y+T*DIqxyAl=g zmi1k;c#74|JX+rKtG>@)ta$$(Tc~%<75D!~UUoyq;i|gVwZ~80XX2`Qeib9<-)YbM z_m7|A`Sn>b2@SdLtLi-~ey?3;mgZlz$Iq%7lPmrmSAL8&?D_TO`1y2glNBF7-lL`C znre@qRdvlT$Ir5B+Wdc8f09mBF!!1mgU^byT2t6pS zuRp79{QU373D?J2z9`${ia)28uRE>yHS2$#)*UnT^V7QTsefH+$a_AIpLEr&dn-S- z8={l{E63G}tZClaW!ZneT+=?gzTbb+*!wJdR71vIL*7$&F4w;%)Hn84Mt7<`_UgOl z%GjeC^7&W%J@v194I3LPzveXT`pf5=MIFjizs*rlX!dDUOZGDB3N+)ewq;W!`|0w| z6lc(ambEagiD{&jxyVJWOfzEtxBoVMQ@?e(m;dYEcU9is`o^BuFGisLu_F6F{jOF) zc1)-0&suS{BmZmP(~NOm!UExZunut}4nKjlhZ}P=;xk!q*zsT$R_hHnXsRlR2b^_u%pVcMGO17j8Mf%FWZp0qW-2XPFf zhO~9S2XhRfaPB0`d?Zz+tqg5_ z_)(x0psg4`I#x;_O?wm-qPuZECRSM=8>_63r9Fm9(^ikK=I8=;p^o%8da9{aZH4(% zN8Ot0uwKPg?=K(1nOb8qs2~NNOt<-d@?n_+k$O5pTZn$1GeFOYMhl* z>6t?PZfD}OI5(%!&wg|COrt`$vvNAe>Qo80qWlbw>C_nae$C`)1~#L27Wc9V=uQOg zNHB{!;*Dv|;odf;cDS0=T#h;H(CSJzk7I5&pS3uEYJKxL=20~~qctG*4~YHNM$foE z19+WXW%xU5*juxHAZJ!TZ^ZrazYO6hYNlIby$SbcXhc8l@c3!1)!vl*<9D%!do%8j z-*F^IOVE1m)`oA%{c)ul%~?zCjBCyq&e)SZ{)S^YWB>H{+g8)phI`^~ZuR=M+!^o7 zc+T9F!nGo6ed0YC0ONli!njVikRBUKI@#LUPF#N*P>pma zTH9tjBe%_VL5kaQ?Oi#x2X{g4Mr#LfSLE)rb_91r?m=rYxR`71!LbnBoxVL8u_aJF zc28P6WqWb#4DN~C8@V&MGuPe+Del6x_eF}kagBXx?UwC_+&$Z$t1blhi|vKk0@}ON zcL1ZmG1!=^9*7k8;(7{*bll^xFY56F(-I1oHMwh!cbM{;&hb`)1T1Uv|N6nzI}M(L*F6U z60Wr-co=dCeTQYoGE19)O}OfDNbzv4dOT7*g6o}t6p!SpCnCk8xZX)f@o27eGRG3| zq}X0FTZ8rz{?}KS`Axy5T>BKHcr4dGmE(Buc&>LUeaB^|Ay3Fo=Qt5Okt>}}-wD|n z$dj@&x!xM!8L_f8!!#Z|w}@pbS9pzw~!?U?V_DfoigO78iU()wj_AK&=>^Y8KfX^bI zr}ZTG9P(GRo&ulZTEC+2$?OH>)8NxQrC*58?H75{cg$YocqaQbS9=zG2Kj6Hp2=Q9 zKAXMF@f`RP@)cUogD)drSts299O?^N2aB40;)=mfgE%ImaV%-%qX zFLLeQaJ&S*#Pxnd->+@>|)v z=sI1pztDOcd>8p1tv`T&LB2=po$P(&JK0}3{s_L0{2Q%5fq&v!f1~e@*$1>%1OJBn zAnI9vM|0|${hj08>>nI|0sq34{z2cn*@wvYvX4042jAx!AJO+-_A&CWsH}hGN?G`r zb_jptiXnV}?iPZYT?p!QA!NLghi+Ui58e51d2lb9Jp7$&mqH%?ku~D@5G)}ZhYz`S zx+j0Hop&eIl5!xeLgbo}n!S=|G zv|523kez6?20J1<(`o~DLUy6m7Hk{FXIgyA)Jo|2P20DcMuvH+%IS- z|Eqr(MxWT9|1g|m05}Xe0yzL2z_mvr#erOP6jB_-^+s_F38RssoMv>8&5Y)JOg4rq z4+~@XUqi!KrV>PgS*;I=lZLK8Jw*aW^zmhXCP-GCxer@>THgw;4I`ETGPO3Tx$+}Q^VXK z|C`JCNN^5v9#@_Y%5vt1Dmf2l)5Cm@8DRfxURWc@P}c}D)HV2Dv*?-6t7~w~1grR) zHIcKxfxKg_Aah+S$XwT=cQ!o(vo*mrIa@&gTHsprFW{I1&f$|S4DJQCFvx2c2AS(Z zdfE3e42N$m){dOZ-bNCjS!UVs%-V{3~&>`dFC!tKedF zS=eG&P-0;+uY!f`NxL@xl6~z87uq{Auf)F!<|Y4}>duj7%1G4tz*PCKo#w4%9F%c46dQiGN)LFRGt^$-5H&x)ctS_?K*}U}4up=B0Hf zaWVNNKaxq!hEij>_S(yB*;9~MGx!4_%BTWbEacoGl%fDn~@~-DV`I#*2IT%r5VKT3Ri@id-F8`99$-;gGBT6hx z{w4eRHN5C`u;5>B(Ecq~ei@XF)#hI^uUFtkvarwMU!7q^vZS{n)02Ju25wZBk=4(| z5(|@&$-;gIHTizvOoX|B~%3n}yZzuf)g_3zL5}h7~0)miSj|7?}J^tl?j6 zBQGoXSK?x_Bw1Kj(!*EG+RaxmXPg>-UzZ zzY_D3hmDI|YQ>-3zKbqnu`sBSIN8#Mk6)dYtt$yQjJy zXZ_6jqV+iIXVw?3$5}tKzGywpdYkn{`#<3R9A(j`COU)kV2WukVs|V~`xVPwdvecR zE4=rj7AHN=xX+Ka*bCLuv>vv>LaAk5KW1y5@amuXFe8aHbJ+Q)6L;rZ?nE= z^<6#AIo?A3&ia}4NUOoSKYGARsW;PC^=8iFn9n=XZr_YN{yyymUP13{?v49}_oY`~ zssFVP=q}@a8hxqmLGGv2)2ipy&#f;u?P#9%I#0Wvr~S~=&gg09boWj7*U`f}nS0X> z?8f+;x3C_f_Atd#sP+ ze(SS#clBz#5~d0KY(K(^Cxgt#W8?8 z#bY_%wJKPP%=lpBAut=6^yQo#1YUtW0C^w`OCRZFaP=`jh;|TxihRxfAU3~EshLr zCp^Fx(Q_ekd+;LUg;*=L1+|E5gWMM1+l90)h+ggsXl;#W`T{)CdgitS^_icK4P|ps zKe>!?GjJ0;;pgG=-UQUgz7cZc$SpSl7vW1km%c^#*UzOb|J(pv4^RC$_}|w9H$bj~ zTsJb+bwEATXGahC0^~w?vOd$ZqJQ?R==0UrxPbX_R`h#1ljOtmz_XBZkaO`*IxEiL zYWK^f)U{kMm?2XRAlw=QPmKe_C7>CL^c7&QD{^pBhK`sf_qZ zv|U#wASc4(Po;HAT%}H-V6vxq{AG$ZFzIQCGUaaHC(q01g0A0P8#8rJs zT;aQL))oJ@T;mwlgwE0D-G#N_79lDXU*bWJ{zzLwxo$RpyadjvDODQ(weZ9wLS9Kp;!Jg&WmbJi%@iHrg}oEdyr zTw@R8EYLn2SzbOM&SQTuqkEj+J{tqSbBggv(LJsQt_~%B^M=Iu7~PX1ed>$xNzpy7 zTSoP`iW&Fg-EYPC`2QQ@V}uWSR($3;m+Oo1F&f*I*AZcMhdZzvnQdIB(VUJWBR!4g zYeTDX98-;HH)3S8<-7^wtu6Pb9j&HuR5k;BLO3>?gGObkWi)5pcI4i4qBSax>ru2v za;F^KqdAPBQ-2x5F`8LjXf(#qsqa*C7(J&3G>*ds~N;M9LzPz7e+%Kc%#Btm&br@snyk}}P_$q0sajKEFrIn%|Co%HWMO$-B z1}Afm)M{2^j85SmIoqc&f~RtiTnnZ$uBUO2Tpgw{?$kw_aZCrNbB`RGtH;qggYi3q zJLM>z5y$mRa3*)n6-xB}HHvr6^=nRC(M0cG9`Bs%-Ml!TMDO2!gWtx8xtbWdhDFaM zk4^I4tgPQ=cl4>+F?5CBCdJJeF=xEoE})(qy*D*+bNXs(qUTb?+^79EH4$?uhR%pN z{Wi&Cqpv3UZ4RPUe+Nay+;)F?2=TT=Lr# z(Q_$oPF+X8&GBe=DS9r&%^5>i_-&RIJ*W0o_-$&(&?Udk@}uX@=YOW?xzo|2KRbHP zh`GXJqpv3UZIZ7h`E6FlV`KE3ULoV<>i65oB~tX<%EZmB3cpPeJ*WSsb_|`Kny=$W zsU1U?{5Cf%<+n*5o6nA(tL?XuBNs7r>I^A*uJGIF!%2~J^~KN`Jy%5189iqt-A&PN zW5iq$LpPIlilLK(*Nve|(Q`)972X@8=aLVnz8Jc~dt)Tsom|c6xlem+YNF?inoH4h zcjHs3iJsF_WAxllz~rm>DJ`StjFnqDhOY427&n(<=!)n$JvS+auEt|i6FpbkZ)3!q zk#t7S)%M$HVM&p6h4)5{tG-CO?voXx6w{iFwZxB-V(5&X>xiGlNV<-+jh#y|bVkfAD~7JN-zIr% zmX4lFadXDdt(@PcuE(Y(daf^iA*1JvqN|{#$3|aG;kPL~Hofqsq!_x|9vkE4^xGIi zrxhec&lx*cj!%VGh-a&!T{ni#xVgHKbc5(IhHW%)bG2jW>iTesxVaQVHyrOu;kRi> z^c=Bmc!P|UGh)t2I%DPfWMlZ`M$9eCZ)5b_ID9$7iCr^#uJGHWxH&yG6X;9Pb2WaO zPkU@q#GH|G)%a74p)+o-h?q;!bG75<^wAhMH#K76t1)g)i&u)9Tb~S9ok@FE@HFd2EUpx;c#3X>d*T&SabDh;>!gxhV{Ae6+Pr0A-+? zNA9VGc4D;9P6B11TXIZ}*4owJOma`NnkHl0od%;dpJ@sx58aw$8dl%cx%xIR&DBBu z1u35?74dXtGRez~p{t3cGmk0dGwp!Y zyLLX)Vy;@c@@}8jDW6EAy9wSScOeu#+E@sr+{?T8sZ)9PkLFbwrZGRY&7VE<~ zo1{YK9jcaW8waDz}cU{$QqW_l=7L94SNay zG37a#$8;R_?YT%9Sxr7uk;!BvoxE(>j4Wj`nZsmm(+E&|(pg;7NIGqV+WF_fla|hB z(o$b!HKlmE&(3Em;^~IN(X?5~#LfowF4W{R$;fJFGS!ZxTUI`k)-bc0hJh)cY5qUC z*cEs#=EKYMY+Q+4c065OUS=j!?WnqI`5!}KB;8QZ*t)NA&H5whjGn8Br(1R;U0p_| ztFVQUT4;@@8vv$wx^=jo zTud~#sdgk?k;#;@no>SfZAO;3SjuF2fGa=B(H}I!=`lX-gW$Tz$D)s}Az4jzxmbPi zbp7FC+Mf$Xwq9gpDW552GMUvRBYT|KHZz%utfnHL=}Gud%4bS3bXvBJq3Z`GUY26$ z)`N!?TukqxnM~$0)#YMlHGOs@omO=DS0z|Gl5Tyj_j>eLrW~faTr5S>8AF%i>6RBs zr`=vIR`E|RwjtMkD|$`eqV;-=pi5k=ZdQ{_%&aE)m$^+fSxxWIQ{*!hk#v1wWOA`T z^Z&|WWQ$@Xo%u}fM&GQw%uJ@5tfqpI6gJmADg?iTR zicF@0k;%@?V;UFPS;}f!em;}lOe5*KfQgZ5v7gR=Sw15(ld0fkvuGFjOevE|%b2{Z z^QU+jzAV^T3wX`^peMJ;WHMK&h@@*lRNWdu5APcEnZuN_np(z8CT+rN1}(R1@}4zd zVdgd!nM`fyEi##mDOkWe>*h0=rDP19zTkzy*o1{aZ|}m;5f7eOO`X8R$lCJvUxXi1 zFXpi5%@mUd(+V!1$B(HOQxB#wb+!GNdNIfG{jA!e7qf`VD*TvwFq1d4@L=lAG%jl* zzn@%EKjtKU@8ri!9!wc!jURLJKRuXoNj;cT;jVf!^A2rs%X( zNk#vzv1>*krV2Pk1Y(LuGy<^`zjlg#n;3t6W8<_@rf9iTNhL+mb!E*nmaaR$-DFl) zBkg+dOHJXv8-dr8UrOJ-k$Jt4th%5+@99W6xn6Li`eeC!$Bp)rk?Jo`QGl~(868-j zRe&jKa5lP(yswfYMOmaMLvjlF)g0gR!76^m`QUucjf2U+jB}qT`t6NDvY9)G(D{AR`s`b#?Ej3{(% zGUm`xXB`@25xdZ`9*v`{E9m-bEgDDKbfmRty3w){jpM63=#yq9sDFGmau&a94_ZAr z^oREZeS*#f9ZU0(^Z1Q>(dx~y2F#~7sNS$9xF!r`0dg&V^#$np>MIM-`1{Zk{kMmv%+0J){1&K2dQM=z40L8-muJ*$BCayHQE2ABVMO`hn`u zn}C~OrP&O*DR-tnttt-l8>>Ls!WN)4X0}3Z$z2;jYaqwg*j)yKvZHN4vlzESZW}q+ zcA&Lnc0g{=-P7J8_uB#M%@Eo{kvoAykUJxH;vVYnmgVk@C1n`x;nAWZi{2IM$#85b zBam5S@4GXGM$jIK%)t@J5;A9g8lm7UHDYHJ?a|04(K2Esw$Zf5Ae(`skbIIth3!X;?~UXakR-TXH|19w~ceU9qXYp+z8|Ld?KT8jqG&H z8@1xdui|q#`W^QJ_;g0CIPwSbDINXBj;3)xh)?Rsw*r)Lr^T3es zbwsAQmgb$Yyv1B|-c5>g&9%z8=PaAdEOOpCzosyMoPo})smvT_pL1#&bH;h-Y+9Y! z;v94yO=pHU8=XNj;(T$%ay~j!L}#XRM08df+id)EU(nehIyapcqO;W1$(6}D(tPb$QRe=o(!{ju+$1k>w{hp4?U6Z|b;n^>>X=qs-Cg^VQMnFW@uM z5$8zM8s3o+m&TprQO!pE#*yw*(=q7StmeF!6@E`gsH1W$y~WINoH|+^p=n-?iF3xy0Ccl6gR@-57=aDC_oI_uR^jAis$TjIXfssoN%wc1cAaoV(4Up~fwOox zqtd6i&tg}HcF4NyL*9`%h-||rxKDJSRo$ACrOAN_7m!4p$%B0VOE^%bY zm7Hg;_1&Uw;Rti>cU^ZBIv&##ELE8-7?U+7Q}$EhMu{=0XOzXcQRGY|mZYZP%A96K zVo7NRIOo(f9RJR_;`x>IBR^+-Pcgqy-RIZRPcENmKEFD}@1Q2-Q|ya)e);rL^D-l> z_VX+0ly#qC-gULl^yHew3gJ5P+0QQ-Wzx{*Fb|SuTj;btzx)M#ip^!*$@=PhekILV z4Y{_~?Rb_k`gBXWx3gZY+9#CbU(V_LD4u1-^Ghw`rk8c8a696W_2c{m#@* zaqM=Av%FKB_ug+TOdOr!{cg#3Ye}EJx=#EOp6jve#P8CQb0Pw0&!jyo&ecwQCjYB? z;Y?62pYjQ*c1E^foV4IQ&R45WYXy<XlHT0WQ@4g zX!{h(=$!((I!r{GdzaDLEzW&2!iK@VcH`IEonuJkXRSP{#{^o zt_eGF?93=O^Q<$+U~n+sYb|;@!~aI|j>U1sSRB`}Zp?(PFyOU#bw_#@M;}{fxTCAb z4jel&y0v=f73&PY97FH+aYfxeuBhf0^<<>FmZyBhvbYMA#hG8m-*u+n*=}XjGMH*L zf4?0wraJno%3!hMI5)Gb3})*pv<=6$Fzof{*_vNw0_eK5HODs5i&F;Q-hfy8M4w9^ zxb`C2dKUV?vNs0JZ0iHR-W1%BcLuJrHE6U&fMstEZpLdN##sbd_Lj7bt&lwiW{_)5 zWqfM)8IiFclZ9sXRTvf)ZHam}ZTfMj= zaz2L{qH~dJ&@-R0>1?k=TI%yz9G%1B zh}B{+l-BNy#-VY1I!awhjNTX)N2w7R&U)<*j#9_0W7RC3Js6wLzdgW?$hDArG7=rp zj@VIg#G3cv>b-zh*J4yUe&r#Z8JC^t)#{N(>=;Iy9As_!7c$ly%Z}Tzj6v7x-uz7` zup6>B=iR_gyjxz;gHhU>_IA9xI*wJxrsI8G`qyDpI&#;ey)Glsk?U9;&sgnEucOpa z=JP?D&3MLW?`SFN9Y?D+B3X*#QEO3Iv=Nm>J5gD*4wXd<(E$Eh3!c`Y0UU*0NUM;x zAuU1!`0LFWhh?-JlVzaK1V^b_ojOScJ^jGGaU@sJ_HMh9yUv+`WyY0RSv6Jm&Au{2 z%hAw=k>aZBcxl6UaqTq^t9=|pW@9y>Z621{SL$D``etJ_qpf!NSvpeEj*_;hwv;k? zlis+ZI#Sa5)RENd>erD9E3$RCYwJjb71=u6g%w$LUs#c?!@WEmDdkYhYSolhjgI7V zr$$rKo}8@6YW;#Rgx!9 zi?|w1^5n?{lebU1r+x)ksWvpJ3j zGlJ!S-uoeO1pAG<(&Na`!qg3P1P|vP`^z{cjGQs=Kka`dnC%*ycgB+E{N6qQY|^$DXbEywMMH9ZdRT;)mb*S)!o(!Ya`c*(P(QE2UX4aIMBGL zao~8+`p@IR382wb6Tpd}u~rkoNuaS=lfczLBezxqCxi2dpqdO$0nNsl0(JxEgq@Ld z$kyscYbWH+#0Yk$wHUcm%nn-|c0?{F*03k79gsT`8`z81_Q)NG2kcF2JLLAnAC}SD z7P(z02e%E|Ah!*D!EM6U$ZbLexOLbHxi#^C6|}ZQZbd|3C9N%xTM}j1kJjeMEn>{! z=3z7B<}v?kv#=?0GqS)2(AosKDUpQ(X>E+$B*qzT95zC392$cgg~N~=#j1^mg+q~t z5&hYO)*;A4W31^R;b7z;M3*+BbrAC4m;-oFI1qUdQKl_u9e_NLsLz(P_D3ENa{%`b z`yuxyAFnm7eUbac+Ku~$eUSSSQQDT)-pGAoeCgg{FXY}argX2cCvq=hNjuQm1G#6+ z_1h!tj@%>G%ilfhhTNS<&(5@VMeatFXBS$#Aa@OaBKmWea5{3AU|jL(;WXsw;ay^Y zPYb6aPYXsApBhdY(3@pjjAe@i9AehN}emD<#ey|SfdEs2- zdEqT0$IlJtAkPhE?4A?OMxGPQ+dVs+g*-bLAAVLi6M0rJZ}-e_2J+1CGcs(?2sb0o z2xbl39KMIVIaqV|d*Qpt?*((WzZ-5sem9sSa8tMuc~f|djDZ`&caS#*a|FHO9?TB-TDTVZwctJ{*M@75*9Lbuxh7nVye62PeRa4Bd3Cs* z82+omPmxyzb3=X_?nnMKm=AJ)_zCjg#RHGUB8M*bj}{c(5rKJxAmD=3G% zklznxf7})BMBWw5%D*$*fxI)A19C^W9eGDEH~;o<8}jz>Ao(A+gGd-GE3;pR7m>dXR@itkynuW$ zxHHuY;aA8Pf;G{96`n`_DjY@j*7G6cM}bFYM`a<;@}t3HvZFDue;keh&FT9%d=!>| z$CB0eQTPz~QLq;Nhv6T{4}+Ce{t^C;{6{d4@9*IQQy%+w1d@r~Q*!UEkd1TqnroDokd1P4GfR1nEajV0%_h$WAoEz@#4bO)mhv(Ll9F`A74$JlK4b6ujhvwFz9Fh-44$1ZN4bBH4 z2j_bG2IT{hgK~X-1M`mfPzL5>L0QUJ&{&7W5es{a%)HoLGwrphXHgb30W=atc9f#$ zC(>#K$2EF>60MfVR`A!=XthALgt<S&EZOSO>yUHH9%MHgLrKVo)&A;@(HpzxGCT4U{7J^>Eq9h>n)aV{Ogyy^?KNBYER4=zL=!Ya2AbhSH#m2DlKI%TY0hsK$9D1X_9 z_94haS?ksXUGom*9qWVZ^2z{y{bc8CXcbc}pv#VeURD)TExc*J;uQbvOsU_S@V~cH zu@?2@Q*ag4+Nn>$ktCLLXB|)VMQJ*QDj7k}26pO-=qxEOch%K8?K(UdY3717FPbt<(OIW&Vjc5&LrVooxsqu^(?V)S4vP@v~=y_O&^G{*v%ZN`lm zD(i7{293CJM6Jz8S`E2=T!}WIwH~9(xSkDYb%`TwT~?3Dyko;SUl;LOH`b61kc;Tu zAg(U!vxZFJ9UH~jyfN?S&MLhKxiP(qz>Scb@ajfj%5L#FXQa)>;KsavQ;r_YnQ8QG z7U%uuocClNnftOiM~^tCHenu4=k+Z(HjA@T)N`^W=bM9@bGB7nEw!o#|i9)4~XqU3jezxD(Rn$YP!>vyi*S(Y70{ zUEtG{Mt)>mp^xM}hr^qW;MJpO9RVJRJepUJgg04Z@)%z04<3b-R~-q5 zS_A2B%xl1*me4+ySNelis6LMVC2%OKUdyX&`?Ncrb8Bs{N#6-^)jyHe@v(a4ap3X1 z=Op@1fKQ!BTaIPh=jh3_PJ~;nMc-HAv*Hw5C&yYTCxIvPo>S@n3f$@x+VU;iTG3CV zbqYLd0ez>(C(IeNPJ?Zo#;Y>0Q^AGEGons+2CK?K_?H^OnXDF8QfZ7lE9wt2vk|nL zAkU^X5^T!3JCluoS*v-T%h^b^YaS3!*lA z0q;2vmVG|2UdS;Tv~IjRMq6+G0?saqI`GBxTo@~?v;Z&Uofp%85$s!S`BKn5#V(0$ zZT6Sax){8ecU~6t8yR^kn0RaC<-B7o*ot>t&M^j7t~P!pcm=3+|4Lf+wB{XGa*Tzc ztMOdLSv6<|)m0qh!LP>tHoS6m)PAn!sojpY+RWAb)mLHe)>gTOV?5Y_UYWi9MnIRB z58yY~b6MhZn*%qD-^i@EQJ|he@9k)gL7=PpXpRA(wUo#3o>6>0_3E+l88J3K9oVIl z=Ysnr3<5_Wt9j=bKC{oEalBRz`gC@Wg`wa`+*L<>6@{BOX)cqg&fmXVo9B0*JW`wz|)x2W7-)gMsDYw;?+Z?f8 zpgCky`78aA?hi37KKZ8c{wb{CQ+dzo{N+T@)z=KNGEo2d>bzq$*6_gJ%!uz!`LE_S zbf9N--Z_(3r?YZS;d~ao9l>dw&7x(@?hN{5KQme7rg1)pqZ8=Ua!z~_&f)K;v3|*w z=EbMqy!e!x$MdTdJu`XTNXstZbfi0W7$2;!d<~8^p!;yF!RutE)0)RB5qRHPyw(<6 z1GyG|GaH=E*#cf&lUb_gejx|>=e*JubpMZq9Bc7xRwr1SV*yWXz258azQ*7}(aL#|10ST3urH( zue@B==t4VXYp7iqJ<$zR zmyi{82aWch6i1I*OAkiNYK)(hFFiSqq?9i`C5{qDO&KG^v7#o?2QsN6@MW6VLC!6|F1$eGeFY9y^Itoazm z5*U+EWPcj5Zl;rY&-!3f?z3yBtFiuDwdeZc2ecWqWJDQ1kaT;Q@2bpmtgYeuxl%S( z((PSs%oFj`xrQ_>&#^6|!gvP9hLH>@_A%K<3TsJyd5#Uu!!kO++`trrV|0Vo5;aVt z8@%@^lEL@|V;qcRFn%FrIJyF9ElDwu#xv;KpB2ZA){@@L#}(7?%|uPvSdJVue4`p1 zKXS1F94V_uUS^!?ita06EQ%w?(WJei*jJ(^pQqqr>3-G6$XuDUV3<8;M$g!|N_n5W zTSlfV`+gaB8>?|k$JaL#e=%{tH>(0213eZF=8dvN-!eB7^m5+8bxf2EHLHR z8S9ZEK2ki0pDN{$8aWYl$l#!Y;rBl97%AhuOrO2#Kc|%1EjAJ|H9HqFkR1qQN zX%{)OW*gPckTu3E)%8fLuvx}xAw{fOy!*ztxSAWq;+%DrceJ?98>N&oTGMVz zMP7Q!QCC|uDkWvH8!4S~c+_4}9-XV5E1x;=DdHq$?1-+GuAIh|xM~`MmGbJfLAmO> z%BH9vybgeywO; zYRdTbIbX~yXPHk&_l{6!G0JQCdEY7Hd+GU=R>L&QYOjZ`gvF|8bfJ-5u7|bf*V5}@ z{qd6xv3S&84?o}iQs2@3Y-Uu-)Bp5(nC{Wi&#z_OFUPp?c(vC{JhKItw;raI&{eUxQ_FvTxgyrL9=cX(p>n0FeZP#}Om?be z=Mk^y{Yn|B+S{F3wdYs5Up~cZKfh8&s&_5TFrQ+do?k}CsdapMUnJKmpJJ|2%er4i zPJY(>T2;@lhTgB*brovguauGMQ!L%76|pGRo?nZJk;<~2h?>f>9f+gKvMo8tNh4k= z%ZzvmnK4jgtc9(??ZURavWQlmEh6SAWE*joXWNJE=--}WOQM-JqGv;7o^3IO5G3XGXF$&Sud!HAb>E&Z;?Y0!~0qC+co$j9!}pPT{@7 ziGpjAjX*ZZCet@AM%hunh;uYC&YDn-Z8H7F)KwEDHY_yF1|XYeW9h4oHL{1tXtAbQ zf28P>WfZRrC&F(qe_`G6W?3I3@tX7*?Popka$?w;WxbIyx8C3&Ua5+4YyFAA>K&RB zeboi*#}&$mTB}5MBQC3X)*0D6>q}o5k#n(PA2D^ki4Sv*wIQ0TdDfP*7FjP|?-Jw0 zT4b$}Ewb*!*L8_eVV#LolMyx{x~xTJ+#0#C{B4^UC)PPeuMzWzY?-yEuT6|qYfbc( z@!%ivO3PTwu~pWJD>RAGYpsdC`j}TgWJtEkn$y=LMqV{0CQR+rYW=N<278ZoqhJ+% zW3d{?2(i{gkNuVYKwQ>GM1Xz3d*7z7HBn7(gI0cg5Bxjw9nRZ;e?Y#4Y(pg3KX}zB zwZFt_nr(=+dY%4vIk)=dpOMC2wIMdk)#NqK+7K6IJxpV+-XebJHTqvfwk6ie9j%SO zdMh(3tSym7a-3gr)|P0kH+j`au-Axc`W5{~H?@nqEW7}|LccLi?TCMJb$XJscG*k3 z@&b`e&+-?K(ASZOeE8N^xVzSkw~Vy!JqMp5n%4-VRTbRBA@O7AE56i zL@)h_zqp0-PT=>EM(K2-?yMDUjc&S+=$u>Wxf$7sC@3PGh^ca4dgH9VPt1_^6)XF8 zB4+3Y+QwYnLd?*&X@3jZnb<7%v^QSpW@4E1NnFb-orz((mbS4&#thxeUmMrd1uEqLy4gFdJyAZ>49X(gj>Izjnj!Wp#7T*(V{6V0$?jx|NAHuu# z;Jg>OKT?l)FYM}C+}$bhfap2sh3{Z5`nAs=fCpe7-n%1xy+CzHz1qF;0$3|upTYjo z+tC|e$4>O?LC{mN3xBaCeZ4{1oSxUR=-bfKzB|{@3tJXFHD&lccB4lx?+$p5s|M(@{#a6-L&YE;JT&qJ=uD+{rzX~&yNU*E`Q`(m?OlOC(Y z&5634yYp#n)yioe#9H)gf0&JCIfZ_?Km~fhY_1}=ogEoL1q@C5tkLL|u;W?0szq!H znv+rKYEYHvmQ(m^HOwhdkE(=sjikRHvJ!oCGOw!ZR%cc8q@3PrL8U}FB-<*sL>6}1|h4m@^WK&`w^#mN<^c4Pa>lCRHAoJqURW-Xe7r8w2vWr z*J$43z~hP1JtkDfXx+-}DB^d;qmf63qi7$D6wMAfg7(40;2udd?qT5JL`xqWDzZb7 z71@ErQHuv54n;ETMj&8Lh5$ii}l%p%{0B(n7B$lIVZA*K* zpsqwjdZyOZhu(5DqpfIdj^?!$8j%{tvnLzdC)r(879A7uFmGtoiX={Y%}- z9DoUEMyr8pNIiL9FIJNY^pB^H{2Pu@Xinpi)!;ZZqVZ@ zaAePHAX<}X?8z|N1JQ_vqb&^qhsH?!9@$`IkE{yaN*sXfkJi)!4Xb}d?JH_beWJe9 zk1T-xwA8k`qcO3247wJ3$$(|ZUT96!m_dr&vo7dS>P%`$Jp!>T^r?k)%hbHOp&xaN zs0P*%ov2&Z0V#GvziJ=#s&-)e&^2p=R@9Z=Zc!KOnzck5YKsolmfjY~uINWCB6dX! zYDT*`SpzL-b;%l|19hRdYnG!yH70hwgv@Dm$pW$q`c)S+p^rK10($-t?T>km{++YV zQBP7Q>WpS&4E^7tK4tyw&gfsA(Uaao+v*H@uIBX~&+I>O)+uUH?|_}qtkj&`t?6BK zt#{~oo8z}=MSnoP70=(K{T7;)QS5I-UFr>VtKXwN{Fc`{()U}mr8j83#_?;kpx2SF z#`9Nbs};RO{|o3-FM%&2J8-UT>jk7$**l;GbwHz1SLzTorRSp_^<31mI-ms^M{eEt zUxLr@9yOy5XhOe;sQ>PXs2M#DJ`uH~$3M}(lFp@0^e9@8nwNW!wMW;{_jey>?a`(l zqV)jyAX?T#w2bL)7j-drO}n4A_4)5dgSwaY50PR!bRD9{X%R_It1aj4(39LH&ZzUY zXiaxVyc6lZ18vc)Zjaa&P3TtIx1lZFPOA;)+V2VtsSP^O&78YS-OXrLH`4w#Qfz~s zbVJm-)VXdzOICAg&Cv#JN^Qyg^{xl6qu1T{TB9fFCB25T)}ZHC)4m3MUEgUdbSS;2 zU!`?<)TrF`T>U9|Ut6I+UBa3ETfMOt)7Fc70cR~g@c>^)OFwY(4PS&tbRIqDaGV}> zq?VxPYEWlKtx7Mq5ypDH&xG5Y&g(5WJ01P!R9au*I6ivRTY#P?zxuIJ_c}J}TkcVE zA{^^@UT+?~`}+8sqdP5$*c`pbxPW8OvzE{@(x5pSks6p$2uFhMJ?-9?&CzZ2=PU^E?zCoBirN)+0eaM}j9NAR&TP{8Q8O~GwUkXoYnp|e z!7(%HL^HCSUaiLZ5+;K=s0B^UNPqHVdM0sHXXeW0pyv~4Ped~^YI97c2BsB!d=@y* zLGyF9g$Hz^fcB%OK7gLQ3)`o{ru5 zC4EY+!7-oj=341@*9+d0-btLd2UkN{`&ez$C-fXN@m^pr&aJ+w9okiH3OYz{us5$6 zTc#ICzrj@cQ?6}Wv}Zl9sjja6)>MPD4VtlD*m925StqQ#YeYq=E4Dfs@ao(-s|;AB z*Xq0#oX-ID(dwxh3y$TrN_uC46-c8D$ADva%{{qCgQGe3H}=<^8Gq|aq)~Ln(iu~S zlKD5~Ze zQ(_Iun!IjDx3LDP_N&?5`npo3*HrbjZoOAWckju5IRs zo(X=s-mBxPzIu6%v6RtWRDHF=p!Mafs9@a$Ig-}+`l{y1-s;xNGqyTacQwb`N_l$2 ztd&s3U9MdzPk)(r$L#K<>*b~R1!s(RFU2vW?CvJ42<6Pcx>ZEYS+83^RF-Sjx^vdw zs;C?)N7d6%!R*%anPPbSmVS2qs;OpZsvoM?GsOi><2#_Lg2rIz<@2-mN7h$4w5S8& z8ozY?Q0oFX>QY5IeJ=9l#;gp^PFLSltwRgbM1CLh1^ktYTB1d@O5;=fRa3Tn6MlJp zPTIh%&ZM_4dB(M(jgNP#ZWU20V>;T3>K*Rnr?;c1BB~G8kx)}VR8Op)R!4`s7wG3G zqHfae1x2+E<1vy?Kdl~Vo_jZ)?TtX!B{R>RlWAT$L-n&Z~G-uYo$8Z-4d8*<>hIm_L}}z*E4@3tJ+yd%xhSM z(HeJN+fm@P%gf6mN0cF!!6AD_?16OG8+Q-wj&yI*aTJM#Ds#!Ook~Vy_#x=NOKru=vKb#==e;!{!^&s)m_1g5S$f$8pH^WvJsh z#$gKxv?kycU{74wX$EGTPYNHwS|`yn5i7!ncoSBmXA-sqt^AYe(MRJ>yi@3zjMd=- zcB0S`W`No?+!=T#=zcTq6+8=ccNx6`v%y(d zKK=~1odeFstK`nZb3ylm`6Fz29yk|Yl?-@3I1lTIJa~=Z4q9u_o{!DN{k7JlXASHz zdJfj2N3WKc=Ub^r{0*J zjj%So2%Fx7o{jPDy+~`*Ah+I>{OK37&1i3mO-hEnIjG&rU97hNwPZaD>)sOF0?U?r ztZhYm%dj==tw8t0-X=T^^WKK`)?wS=UTxdbvrX78$ji5*N2{5m$omffwNA?Z4+OPW-UIhP2-Je4cHe>qUS_x!QaBRa56n7VJW^Iugq8IIT<_g^|Ve2 z*I{8e6+8u-@i(zFoCcms4T*1Hhd3QPjoK30Ah%>=6s9|s|wuiI8GpTKG z4Yr80!Lz7&V7&D?;MvqdxC#r!x!^g}NH8kA!|r2xrjxS}@B0>)_X@l;9qx-vGZ(HHFh?eKTks zxeoj$wHCCCTn}DH4F)p^z6D-SZHAMvjod&M_{reO^nN>>h^^$?^xQyohZAXiCz!2p zV{pIL8)<)sY7k~R+(gffREf}z@?CmvqI!fDl<(2=U8+iGN4c4v?@^_|Op06RxtZz( zW?|eKj>4jHEB&`n+u#UnDYwyoD>V%(2 zv=7k#Q)(FK&3cgj2dHgehR#FuJV?z0tJ(gHo`q32<0CzuoT zb9x@3rh+wUAEoE#)LJla=rMX8r3QoEugB?mjM@y_(|RJ9h4c&X2`V>OVfIPz7gTgG zYw4-5HMXCpXg^8qhplNn9kc^I13pb<2(3ZC1fQW|gc(xLg1@Aagg&$9z-Os2VMf*S z;B! z1P|_R!KFB*P)dum#ai6m-JRktrC2Fa+WwwrPc~_HUrS$4wHv(weVv^Wv>v?)eS;ko^sc=HeUqIPTtW6W^euK=SQAg& zJJ7e;iNTdwpR&(^)|1bnpRxaenD7he=j@R%h0@fs7cw$K%85L`oIncT36~) zQ-_@oM7Z^+smqQCqS^{->akOT7LxkZRIr1B_K*hD)MsY}(P=|!8nEL6s0gZcr7^S- z`!Q&BX##D`J`GxFnnIhfe}jm$8MG<;I*3u5Lz}VRgJ`w|v^jf1^rh4?h0TSG;sZGwojZKwpRwxy;GI~nNpZAVR8b~wB}8Gy0fE$(GWeTsSG`Xh_WX&Jwh+aJ)t7X-q2p`4`IAVA82p(jWA}UZ!q4Z zFXcY$Fu^WsP_a_~AXe&6xgWb4h?NFV)1TcA#7YCH8NeXU3}kl%QPOhM3}V*= zG1FjbmSZ=CEC!aE!R)di>KRJS5O!Y>4Gp7aD7!L*tRNh^kN;TY=1k;aCVD36046^@1;&DD6yD?yJWUl}?c zdU!YjdIVP!D6b4XEG&R7;A$e}3D85yCxwHTAXcW5ZXf1D=X13N<<+6vk*^uHC0~=YMp!Fs!_``(HN)1F*9vQg ztthQcS}Uv*w&ZFZ(%NC&FpsNsN$Z65!WLYuM_M;*PIC5rqB(- zhU6QBO`scwjmS3)8$&l@l*|C!yNg`PIGPD{cR9z`Ea+_Tmg8QR)QZ+9>S|l@GaFT^FeQ$zAM-r{TIAR8AIS z4>n8Xa7GUwB{6^+S47PRn+>GK6;V5Y%?44US7b-9*>cnvQ?er^ z&Zq#P4S^~{+=*@|RN1l%*lZY7nX@aXYa)Lq~qS1oZJU&wjxMO$?5)kW1&ja{lI49ph{X}PsV}4_D2#Q zKxri~*a1lB1Gyd#20IYReNZO14+fh}0D~#dja``tRn8v@Dw_mV{vQS^n+%$B9zH{ql`%K zbGY6N-1QqY+TU=!Ib}6m_vPCHs{ZSKeeb9rGwfyc}H=i2U@4KVj4%Ey~ zb_9K0lI}>&4#`fSuS?UNsBz`KJLBz4jcfMZF>e=YT&?d;db?7yOR^id>+*CrYFwv( zC8%t7YFwv(ReEK*2Q{wKcc;ERsWJA>9sKs9#&!DFg3b1(#qOpU(T{ou(L&a^kg3S(ris#(# z?og;`?{=`+VNfxj`{ONu>RG=d!-#i+&5i(xi5>3(n;i)iQ{D|WI||%&H}vidak?+x z(crFoq4!dI47lq)FzS6=9}D8TAJlq3*T;dl9stcg!1eJUt_Q)o4|071i0dIR@Izex z0>t$&*!W?tPXuv20%m@M>ytoSkAkQl<@#h0*JB{<$GAQP#PvAX`*E&M1#vwAGJk^W z(t6YINs-kDHs0Pd>yE2y>sciTG)s?ES%_|ArEOK^9- zUqiJqxNF}zP^}K`=Jy+@HVJq6I~S_0;$^VeZ=qT*+)eIxP^}v7GIt(SYlpkfxd+{O z$@yTg*RYSgo>@oU0GnL^`g#NF$(xie1bw}URpl+Ne-HY43v0{UT>lZO^~K%rE&_eM z1APap%*CLucd^>M%k?FoulKO#yvOyW;I8+v^1RRWW#Fz4u>O3&^`9tf6LNRHKSQ+@ zxoh9$P;E%==63~D+mgHdT?y6Z^a%* zeTzNrTdr>def<+_-9Nd$9rX1bR=n@Hz60F#FRXk2;`&a|*T1p){hRB%68G`Di<&#J z3!=z`yQ#Sgdtm^T-9wGB)OFZL?p|u{!M<1*RCXUV_hNUfOX>ck9@y*ws8-1eu-Su9 zt(En`W)CF|KxGe6HYTYdsO({C9>Vt72vqh6HO6^229G^T%_G=H8&i55s@=2+*zAd< zDX8oT%8z4VbyvM7sd)m+YjaT9Q%MW(*i+O$iCwlO`|>?ajj>a$KxNNRWAu4z_VFXi zitFb{S27F-n|(>m-|=aT z0Gs`TnlJHnj0Br~MUAn2qrhfgQ}Y!bl2MetVMo4E;ajNwlQH10e?s-EtN{M{4ywP! z{r&z0)ekck%!OBmYy2}{uKz&w+pGlgO460MPSWvUt`w?=XJs%~fTs9M5E8wyFo!gESe0RRPt%GzC;uAF7vWDyXUfR3Fr|Ff}xU>YJJlo@xZuXEg&n z)flQTYbHpl2~;1~ERa;wbT;UzDdi@3!{&gVno-jfFWFqsQ*&yX;XPXg+|+`a=6Kas z1vj;%rUl-%RVlSfR|7q@hU$@99Sqe5+8Qt28lb1PP(65Sf}7ew_3W($ZfXzJw=g%K|A6P8@@?ohpu8-trFq21HUbQ5q?k955 zYV<$O1FQ9+M*riMVP5DUrD&3_2{`5ga;<@=!dDJ5m~+?gUyL zPI-B}i#vm2M^G~y@8T|C+>z9{+GyF^A zP-lW8y9?AA;#lttb>=t+IzjcnJ2yH)ony|K4p8Twv#34PIqB?b2X(GG>)Jw{!_LVz zQ0KODwKdc^?;LIgl@~a-TSE1}JLg+K^}ovtnnU%!%OjdWo5FGA9ZjM7-{mY#pzliynejDLFTAqkE2v(0Wz0XIdf}BlUqbc5E0g{X)eEo0`U0vKUP<;j zR4=>|?lY)fcqQMbP`&U<#8065;+2$tgX)V{j(!YP1}k6x3e^{{-2DiuFJ4LfAyiqe zg#G}kj8|sA4^{Rn(cgor6DaB5g{mtk``>}8L#PwH4OO>LS9lAm&Y=$RCiD$-kzS!E zd9O@I=^1*E_e5)X9WA7iya#&BYiK9k$t%%sUQN_pUV-Y1SEqRysxMx>=Pyuw@#;e_ zLG{I}C%p*O3$On40#skTde!q#eevpB&q4LYtA{-c)fcaR_6$^Cyn5TyP<`?0b5B9_ z#jEE%3Dp;`{`Uk_U%YxD>lHJdQho6;bVPmeYLJgY^}?%JJ_6M*ug3W>RFAwm=tEFF z^6IG%Le*~7Umt*~^{Ut24^&x)49y02OtJE3Su%MnoFdK}9JdkZYl$7m>*|P*IJDL{^tU^~H<0E`{og7l~a0)fX>9yBMl3Ui@|u zRA0Qf?vGH>pm^^OP<`>@z~4i~jpD-#q2fsq;{{NC@#4wzq30#%XE^gbsOa=f@aONK zqE->K0L- z2^Ectw0{W|rHjDNfa;MKnV$~TBQIh<4JytT$)5_J45x(Yfak;s$X6!+m2BE@><_^fa;gmDmNdhUtVk7_E7!uTJg4n>X+BLw=Gn^ zyjH($p!(&t25t@2FRztwE2#EFt%qAewKHl}oCn4pfi4R@$|p+HT~0yjJq5Q2p}S(5FE4$RCj&PJTpYc|SZ|Kz?{SF`1MsNDm`l zkXh=r&QHKPuLb|m^bqnxGt2%V>A~cOWETH}(}Tzl&O8AJr3aE9l=%q`#49isuYmr8 z1JeD;56Juq`=|Sn@1OY__DlCA-!Jn+?3?aGzAv7M(Rd*CCf_IXSnQqdMZS0D$=EC1 zlYFnt!?9<&2l<|v=VK4N9n0hG&?B;Yx*PfKnWtp8bXW4-G7rkG=`Q5EW}cN@(w)h7 z$viGQr#q4Fj1Oix{4P6^?}Tq=5dN4Q$alnNGceg9olm|4zMKKc{B(Qr`S^JHC)=mn zk#CRhr(d#Nx-I#3_=Nf<+os!)Z;P*}PqIzAHTgF9ka{Our(2P4jc=(}vQ@ez`BwOx zdL~<@^T@Zv7u6$~m+F&p)of+5MXIlAi|>6`-IC3}_i1%aHp9!MuWJ+XO*8M;Ch5lH zn`BPAbtYflaTJo!Hke2*yML*nn>ALviqJM7PbRGP3>*BF%ldO}j zO}%vJEt56VHOSY*7uX_MBVC<*4Sa;nlhxDJ$XCZ}*eqEs zU6p(_yopVdRnt|-SH;WNBv~b$OTG%;$HvLrbPoAkypoNQIq7WjIe04@CbQF7K?9 z?P&kjP}iUKq$b}(zCE?A@RznD??HXfqysJ76zY174)j8EsB4&9Mb(l~)qwk4Kh-qp zPPsC1RY}vN8|CiMrsTwRkh@!cx1{}nyE z!&MLTU(vHWPgbJ&#^6&;9kb=p{mwzJf3^ux@&=JZsVTD z?&{eJy?!*gJF>P!(-%Fv-*^jj|B+m|*FbZ0cjExvDb&4;jTLl9W7pWaf2g~vHvy}N zp552i9R-XtbSF{~jPZx=i0&#<;}YG!H11{Wp26I>$<0#XFYftor!-zK8GRo4Hr6?;7_CFP&8{R`Wl_9p^oJ zLe%EJcV7#!o4euKM)`^L@s#?wWBC8xv+5m-r4#EXEgY$?;&<%Ev+Bioj%H&jE3*;r z&a002Y1uq*HuT`ieZJ!iF{ZNmv+7-^uAJ&i9(Q*a-KxR%r!QSmuWsW?b9b~B9lFNc zwdd+^gSc|ldE6&g4DTq4tIJ*8?<#V4&31>}!SqeOL$1B%4!Lnhe%Fa>JBTa69m#P$ zxGToBHN?G)^Br>SJ9qbPk_c}Ta9@S#l-xsMIvmd4b4Pyr&fVL4XMB&d zD6{{^X_VB?%KrCEsJ2AgWd_v#cSqsrP`RP)I1MTvbO++8&|y&9TYe}Xv_B?8<$$i^ zp9GaB+HVt~%R%i=IiWn!y#!W<$_E_<u9MDlS4%!duXp%R|0sAq+R)o3( zzvHeIw0G8Xta;(OSJtDwsOe1`*wZ~p@_emOJxD!iGe<@xNuKYB=}wa8JCeGQy3^{8 zu&$(TjKD^ex{!Cx#-sDB0oR=vvkjnHOgb`l>qF~vtqn>GOTCQe*UNam7Ls<%fx6JT zjE%O;jXKaeT(@D)1Zc>3zB8&dsSR)a!{wL#73aGDr6j-XuPDE|^43v)MaiWMQ+`e2 zt)u*kl1mw;{F;!B=*7veD7lnj$}e}_iSjE-E@hbV%N=!`S;{X@-%)bKGenE>OX;Nr z%h_5kzse<-JX)Tu^pcCq4Qi5KN-w2Bz88Nkzm!{1epS#n)ypsCR+L|L=$oHIe)$IO zt>bC{C0CSU@qK;olKfI~MH!}qu3moSl1mw{BvbZRC%?20sx`a>Urv?(iN@W3d0_i&3+2hj-65a>RJzMLf?T>O}FJ2gjFuF^;?_xuOhn zT$bdQk}KE0qU2JB#qq7=ihG4mV>U-^PL4Q}EBTsItQS;%Cr6Y+s1K?a$``$M|L}YV zct4GM!plwF*Hn%wm-Uq$IqLq6;}6RBKUo4i!+Egz3(3*@JHc&^7p=9BZx zS>`TXYKR@6`KcgLZny@<7F3$JHb$zHam|cW>7!hdDwkYcBlScQ<(O1%ANT54%6TTQ zl1`o&ccF?WpSb6g9ABR3K2vghd7|fEMIA`#s($2Xb6mwe>g9^V7>QArQcCAL+dDqh zznoRhHg}SWr%ZTqqa)l|Cbw5llqbsV)f453a(need1AjzzmUrJ^Q*pG$Irbto)hV} zot5!95uPbWi8mk3Ty>y*r)=)r^*o?OmI*E~36s{n-imC~(dd&rVR^$Tf{P zjvQ02l#*{d!m2+@rnYDQsACv>k0?RSP<_zxpl0Z}QD<}<#oe3Y-cC~aqaGKjd|iGh6|E=-q@ozLd8zV2on9&e zk{e2uCdwJ9C`o=ORsP5irSiwf6{FOO2rS=!OFdC7(Nk#Tj7q<_vy%Ft+G2ZVtNLKh z8{?Ta@8E67^S_vHI*KcJM|!! zs>i9-Pp6mUWAa0({4sLHh>|_+F3mVd!dpB4Da&D-^6v5{HQlDX zxARNB+>C$V{8H0x&VP~5sqwNhn3B5TEONEQ)=<_;GuGsq@{QJvGP$XILw$Y#W%))s z#+uw$zM(!ph_V`M2gaFvTE5nSaV8g6!|lj8a~-0ZuloE@%4)=27-vcY`KD)nD<#yR z)#ry(md`3nMnL7im5j5I8IAL66n!PX&UeHfLrGaRCZo!(_34`gnhE;W8(V{)l+4V#cljd$3TTr=Fn}(x1+QLbX)T6 zDb0g!M?RltZUx<*n)#$HiBp+R&5oq4pMMEvZNQR8&>Bkc~|mwbPoH5|GhHT#qHfbK!v z0nDI!(0V-e0McH>7#)yNql6CPYHy;Ej2=3etG$U*GOFkh(tgl`xjK}5KcbrU=lO?` zMnGNBb{L=RN92=sk_Ds#h=?+R>2R(r8`*RO`9VZb9g$Jvo{r*5YCP0Yq(h0jItqFW zx%4oee++3P)L5!xnd$YR^66tKEg+Wb*o+#1bv)?^s8L$S^U2{vfE`cy7bMRIIDz~` z@}rlZP-FVeqwXx?1<#{=0qGp5F@P6P_iN${#Zwn@JqCIKxqA~ghBoHep6&2k zViSK4{Uf>57{iOmrN$m!OfEGh@e*>Wv5J?HOODqyMRlLL4K0-5cCQ1rzkxPHGcUi>K-CC`YFopA}%$? z`B{=Dx;&GWALCb^B~2jGT1|?zapccYdYm|H~E&y0D7_;2I2JtxNUvpoN0(nMm!+wi%EPZ&=%T;XTL)(HA?+m za;eel?~z`IzDxc-r8l7Ok$*txP3ZgNAM*6c(6`9lEB;NWk@6q${I`kD|0tuz)PKyC z)L47Z;dzgke&g}~#?^bo`u~mcr=$;{pOAk>{sGij{?GW0DbNqeKhJd1&w2hwtSI*`$h;MqlAvaZgPivCUd3hJ3g|Dp6X^lP5^AL_n>ivN?e z1J6rRHRv>TrA5l_iQgn4b=6*AHOIF}ozzu(by(%`&!leZs=d0b{`fAbm%3`N9;-tB zl~kl^$Q7w;_bSr=@Z<_sj{G~RpQ?}7Pu0Zh^D7B!PWTCEeewpB0xMDi&uhq4V5Le! z%8kjTb$E6Ya%o+j*OXkUF7A0yXtZ2cupXu}Pj5~xtanr1K>Lvopwts;T8Ba@sJaE-Xzjk=tT0#l*U0_muKwc zSmG)tQ=Up151m3jjglwVt(>k(^yO5prcqjrs7#UQ^i=dYJ=G>Ro!^>3^yUPfJtNh= zKZE+|l&4cOGZn)b>1lZ)zc!OJ8QPcoW~HLKS==*|@=WSyr((O=l%`Pb&u2!DPA0Nc zoM%+&6v|V0qdD9;o9I(9-`rHRH<#LJ)J#iPqii%cXUu^7=JMS+)X(Ab^)oEFKJ%(I zNJuOx3Tp!r(qbnHYYP_Ikn%>P_Fy4*vk`^02mOd8MPVI4Lob4 zMHCh>R}qEf_)Fv!QCLJ?5ryr~)9YoJt1dL+FR@s}Tn8}6x>N4XFDwaviMfg>EXQA3 zMMPosphf)U{9Qo$vG_|%O9_Qle2>4JxyLfQdO~~rX#AxO=Oj`?=rR0aj>yDfC-W;m z1b>OVA_^EZOXL+%SatYI zJ6n#wF3pfvzweRP)tTii$6q3^h{AH@6;ard@K>|%@t6GhCeq^Ym&hxku$u9g_CQfs zGiVWi$>;CPEO~cQS{(km8w8f)FR@reUJ-?r<1g)v_wzf=zsFyL7K^_`UJ-?r<1dj{ zL}9E81!LtX%(Idr3VS@WJ3h|)FByM{ydnzA@t4ReqA<_W^bDwozakd%WX1}@>%PMCe;WMtGEaMpG!v@+nWHc*uWw_K z8wwr5??wC-u~@`k5sTG~!o*(@i{;4cEuNp_uVFta{`!z7vs*g)?dRC|hCzqb8h?qr zA_|L`tBAtHU$ei*U+TKw@O<%?R_BPkA_~iqS43eEe~G*z3R@ihn)5yWQp-(JZP-aV zoZl$NUm~xF!fJ=Va^y8PsmS!(icJ5^QP>E6gT3{!EY?r8k>@B({1vfSbtp{y6|q=# zD69evG{;|~cy2^q5rviGFELk+zr7&W<*EoJ@ zLaNU#$6q3^h{B4tg>cN}N^F?0z@uHv=m2(u0@duOjA} zgdGeN#%B?cMa%`h!hSU?oy2G0E38a8{+e9CUsI?BL187z@t0T(%#~p)J${^Fjvc0i z!q%m%XKHS`9=4i@zuGcxL|w+UwaX+zJIco6DI?mG^xtW3@uaZ!AS&%V9ZCAfr)79c zJ5{I5n$(%M(SK)LZ;bENx2gwEyIeP@9=wU<-J!;RXkDy?>c!KZ*#lY$)sE`Pxm8*LUAi1lkI?q6o zyNar_4I=3)S4&)uWE_!t<6x3;uxh8Cu@mEn^pNW<_Y^SWIgH})R4~s7Yryqz5KDb% zeXd7&t!S(SvT(OZ18xN2%AL4J}$a14}Rym$3D$QOv;t3 zLydxnF%b3X`*=c=r!yHL5zoWYgBw?q#)#Y)cj0+h1G%q)(Gz2|`_rRFUFgxYY`ohK zjmP#W#`xrs8#Tvc$LMnXgT@v)4)uuTqtO=1aZbkH#K=OUd6S3 zF^nhu4n|9@z-V+78AVkd&lV%{jk>8ho-Ia38g;WW<49YvQC;QnY%#*pD6sN)wiuCV z)R>Xj#dx;33c-;zgRvANH!9&}rFb@@)nepEPx`hL&t?=}`)roQc$54DFz1gmORH3j zOc~ERJD;3|&ZQOk2hKTXSv*}%nQx?oGs~G|#GbQREyHLErGk+u@=9k^E2uHla;s6< z%yK?C|BR*?#Xoe;DI1J@h-ZJv&74`zBspw6l5NGu@l8%7%%^%5hZomr6&x|%`Mqg}w0Dm|0US=K9?Exof@=9yf^ zddMFg!P*A%bI_c5@nkkAnnP~coaAZ_xn(nw(Xg)YZUWWsDxYkUjlITD{k`(TMo{BmJ7=>>E28nr&NKO5 zeW;#!d0qunKA32f#`Sp0j&H}$c*fRn#{CFN^T1b{O~%YA^m1_Jkm>OG{`6o=Wok$7x*I zIu%f7vwqY1jIS8UHkn*qumMyKF@e+wI+1*3N{yit$j4J^0+mat7dB?Zji)@0)C{T? zC%10O=ov?OMN*4wEH!83$W8NjUQeBMf5r=?l8JiR@Q zHkq2Wc|0jKYKcv0Yok<)v&@<0>8MdZbet;1dNZbqTB5yC-CVOh(~J{4%RGTMM&YUr z<})j_MUr= z>kJ*4%~TPE+*tV|l|L(&q;l`57shCFwZo_zi(za7`H$E}L?gl(1XWTf6~#g#AW@MR zNn|8i5<7{QL{VZYrILNzpBWY7L&aJ0<-Sm(M;%*Iqe>lNQlm{Bky7;wrGix5qXTJb zHjc%YYB5S^F{V0>qgH%52|nTKo4E2J>WH2ct5&6i7GJ7!DWT(8(&HIPo-gf)8V^-> z>p?D6hBB8>c0YiCA2x{P{P7m^!C&Mf|jtB90e zN-p)8sNskm#0Rdv%%ktcXt^!kXsp&i8^H_dSf$~dUDOZq-$`|AokxS;Q z1k^>MJ`pi<K5u5QSVTbSHE}FtLqumbk${C_gXXl zsu_7{!%}yQ$Sa~SbwV{xrF@RU?1zZOY`rlVr>G8pP0D)Ge(jpgEV-{*guF)lrPMCs zFZGWR+4v};Fr(3P{56F(UON00SE1S`a_JHl%Tbs;RF1#&!&XIM<@hT{TXN~x>gr+k zUI~{)%$2V@w#U>A)e`0QYIXLiy=iZ2-%vmFiPf(s^80?%RYiVFo5qsX6NwbHYG{{< zD~W6c?HlTcwnf8Cw#D`4u3c0=RPr^ZAJh_+h)w7rp+T? zJ?7l3ZatCup>m}iqtQ8DTu-EBLoT7sBVWxXuZZj0q9n^#zd6Q~c3t2>avmk3G_ILb zGgMMmX0lVNmZ(gXsvo+VNUMgt&b4_Z{ZKtNo@wq}lLx6YMw>>oZ$z6$Zr|{osxspvo%`LZeEIOO=85ivv&bp$NBhIxrKT7tEs`D%5SDj_m z@8_Ua=$b#R**+<*ye(M{t6LB2yox(el&^=)?T68h?M#d7fqx47VQx9h*Teo$`=RKj zv?_LdHkaZoTRQupa@@I=uly?751m(W2b1#s9E$cs=T+PZrF=bX&G^gN7ExHlTtzK0 z+BYKpaxRIyl>5=j5iwV^(wE!kMP$)RukYuIFRPYW~pa5M6iGH$&R_2ZK* zsM#25l;Re|8*Y~I>Z$NqdHFcfN?8l^K-;l)ET2!!IQdwj5Vzo4t^tc{!K6k(uE^(N z5qZ2jSlCxR$cersUx9kjiTqw!%vpPUZv&{&i({x)7n)7J4Rsqpjj|j~jfis&xvR$3 zhpvx*kQiZ}+LhFebxX$Ujp82p_FVFjQ03?<G~#%J=tY?USpo4kaCcv>d=^9WxE0 z15}+_jm7na@&j>eJE#~^&TN#RE4B_Le=Rkd^7YhJZtnkWc^&-Ducz~QleXM13YE{l zn(jo*<*VHPTKY!%db)P<1|I4)p=;w4U%(Uhg&KS4NU6gf;l^XW!na;c+wg?8*}mgz zLf0U!;7vT}Yp{2?E9740&R0@-Zbh~tYyoruPkW5L%->=kZ}&8J5AS!xCgo?(Wnon$MRfvCEpXu8QI~n@F;gaojwM=i@WX)k5l(FyKsvsuHgAs zF5Jodq12Udp1*cna#T?JJ1VI69Tiq#EFKkBWjsE?x1UarqHVmX47UH9knBiP6G zDR#GgAU%Qm4xn}cr?c!&z8Cd-hs#rKsh9KSSFl^SmY6?N9Fu$;X^I{JqKbX=X;Z)A0JsNs6 z_Z>w2!QpgDLzB~kHki|ca^&agxp+oG-H%`A&ReuW(7Kb?OqHe`#tw>eM>4ExZx#Oz%kF2zRA-LhnxRN?+mASHmm8wUVy{S4qAZo)2$@v%{~# znb5PyU!dmA@LS&aEY=O4OO)$xNoOa&<&Iy5-;vIM{+9e)zHuh>Os>uizvk+^AjUtB zzG(^l9e18bYL)zkPtOhKKz|dq3|oh-pxcn2ADXj!{P{sE(E0p>KTtl8t9g97Ww;=? zr~C!n^@r5;kiTN>qAMjg;~#IsDLLDOd0}(%d7P57E%~Owz56%if8PPUopX7%;PZK$ zoAV}hn~*jQ=kbhRCFhaO%yx@Ei<5KStw&8p!<_Vqu9z46`O{}-ea*-PL3`cEdE z!e09B?|%~MEa-_`okZzm_Rs$<-#CHvi}bp1O}IK-7p^5go_crG_Y{HS((}lVBOT9P z`sZ_XEa^D*(m$WlG5qiI*-QV5;EwuNhATK%Xcp%T&EO28S;3P%t`DB|A-#_0zfb8p z&KsJ|9Ur7uhpV9PlYf|A6|RJSKt7evrv*8-j(5AR;XT`+{rH;o!%MlAip!X z`|f6q>$RLs z|la<0+1@BrVql1OCN>E6Ka9GTugIwHND_qik79y~qeF1~d)t5R>{X|901o)w}G zaQ}l@y!nHy&s`;Wipv-29ej2jQPkJ5R@K$A*Aqj12j%@aLx7V4_{9~&jbTB0SbAgd ze1aQ;Cl=foZXkDM>nh~;xGUMqlw{j)*^p{(C^V@^x&)mvcODl2jDAH)?c&=^FrQpWhm83%Bw=jpClj zNlfFpVa+rS151`?N9NZNh0so^13XpMJ!tPeb{B zUrwDG8Y;Q33$#1=U-|52&S2`onM~XA-R;sZgJ%ML89XKEOHL^I4*D(s)>9e|;?#zN z7zMkM_D?_N+c$H*QgeQ-6{#__C0Bho=V};q7{BK^5BqcOgJ(;03_bYOj-)QoF8u0y z;a%Qt588Hb&W!L3i9IOo#hDSiasTerdwzsxQT&~Alj?=PlfLA1Cr@2!&961)l&Bs& zt3&8Xz7215GxTraW9ZHNpZ3&u;Pj|oT9vR5zyWIHBrB?zxFiTl3EEv10o1cfCe> z1Nuhtda@B`S!|rT9y_iVc#T;8xMuq=-2Y0p7Qyx1uMj!;XXW`ReMCfN> z7WK0^QDR=Y1#~X0xC&`rdIPO=BXO!%@%c>BEKZ=RTIU8`Neo%Pd(M6&k|Yx0y0IZa~?@_Kw~1iWjw8}V7M z(1^Qwhq~0%BevaD-HnMy?-kbLOpo0RO&NoBqitxdFazomeXSWZ1N$sHRLO*JnQnz;M zNgc>CPN4Fts$f-te|biy?sc1SugF%@{}hBP8C_3?+)eeNzftWy}7dw zv^jagooU)DZNXJ9Qg7D2PGZI9Fz%g{_RQk(d-7>7qPr&&8@)WAOk~BjtJVKaN+>5O zC$X~TbbQ)_`+GuLk-MJUHRfM(UnMm?Skv4ptz?bt1nwQqlO{k{X4UF9*;)$MqPrr( zmF^>`^&Cpio$Su{Dp}?56`#4b;;U>W`*%d(x8}31*=p>rl)ACjc3iglb_97B>bpYQ zl8@q(u|$uLC6;>yuEw(d*0V1=^Jy1oJMz)gj7d8X&EJl7(j79|j?X%A)j9Rtr)wC0 zo)>i!9OY&>&lk+bhe2eXpY>dL78H6{cn*&BH8SO9IQZAlkH}v~^M3>CIasd;PsXaO ze1&=GOmnw`7f8%&0^=ZyDB(`pGOmL zmy0;Zo$b%T7vv6kKg6~EvES^K$XlM_u4mCnT#0ofNu5be}C7f zUYB3Vwd7v_`)mw3;v$!OGUIe{TnEPD7nzQtrlR)KDQjc7r94ya`8Z`csk}0uPtFZF z>ElU9`k)=NFwQaO;`IwP9<`aM)u`X7<=oA?Ub|4EQnQME+nN5f7d!HtYZhu|YG_xZ zr>WJcy*&*N_#0Fn@HD^nDb%_D6jUrKe|QSMQh}}FY52%9sr>huRL=VhT<5P)`OsAh zwLmpLts5Ug+*n6JE_Mxtwa|n6CP2oZAyb-GI_YmI%on{!-GxN?S{Tk%ol;=H=@stNL z&h$XWZytcd^vbx;1L?JB^-n@0dblB656|nvcUBJ1rXO(9=i~hP%1FxhGbAh?7JsVa zDPfhbDBn_(6G5pJjDv~>ZsE;uhCYDZPdqFt77q{M zPW8x#!A0VkNzf_eQz^|1D`vcG8do#HLgK0Cc)~4M75dV)&r^PmvXVutGy{Eo#Y}4# zeLTy(w}dkm;%(9OV18u?I{FCSXLP1xkES#R^xcnVy?_+!hi&RvzNL;nI=mR3q5LB0 zwvc0T@%dxi`2sdN<>0G)ep@(gAyyZquK;HrmEIp7z!v#9_dEt2h|GK?yvm)gkZuj9 zCL;M$LFyMJYl3`N%Mh~YSX{dS{d0M;K2*%SD*1X)5xZFU37+;ibPzK66rP~{Ma(az z{xejZzhQ=zH_Wi|x;%R|F#l?Ne=W-EVmr7MPX99Raw~X#Eox5Y38!EOy)R&at) zKE&0-STXO1-cOx~ejO|k8-`1=EP?$4(K z(BVWdeMtSGy}9Zc{=$3o8?u)h{Tc@RV;c3)r4C)Q)4-*&aBI+cQ7V0bNE%UHCZHa|T+mm*# zEufq8{LUFp>YU*!Enu63tw|e)$qTh2wIemEJ2*pnYwEYjY)x9aHp05KQMe@8mOeiT zdI=UjwXZwSy6(WX*NJC##$Ko$bUW@n392=8J4z=eQ@P_VbkHf}9Y9GPu|aN!ZPfia z?n2Y+lwlh2UVBofpg-fFq#bSZHd>%aupOyA*yA>At8J-o7d&h2u5>!-ZV<{XXd`Vv zI=4Y@~3(%&FCwwxu*>X>t;$jXBJhho;!w_+;=6_Qji_hhrb|eHZ#d^sne+(9@84Dfr&@ zSbMjpJ@+CVkB2~C!JeeOl18BB#&{x*<$4e7|HtCVIF8cp+;?2kkaueW#uHaJq|^u> z$KE_^H=cAno{!_XuK}Nm2}Q!}Fvw^1DT^m>LI|4~Qf&OppZ+I36g&NX zLHqteP_6b_`}c$Df%uNQ{*^AEv`=RL-#7Ct>=VRSVy=j|L|&UML|h`Pc^O)ZsO_I= z9c&{1(L$6Za@!cRwMn{V=5hQs)xz>E@9@ubYwoTW#O)Q>VYH-t!>8Y-$7Nm% zy#~jC_P6Gf&r)qppQT#1^cWl;KBfFwx-Fl51KoyP&%p7}+~e)u-68KIXSRg=$&5Jm@pL zoZj0JdN{psIf>I=x%=?Up8rei!k32~@a%4Z@AnMqeu)L|OTPct%!2k#=Gpr*_g@~~ z#jp1kHqW>4u6@L(S{}8dt&@2}^^)ok3B z@nJZH{KL!>q=o5Y?Alt;wai=wy$lPuUc5iz3%fY1foJqxp86U|U#gZ|eaU*1qrZ85 zu71NWoPjsu3_MBr8F=Cg=^rS)z*GJJeV$y8wtnp`@pNCp?`V71uA|pn-?{skZcN%F z^MmURkKXiodpz4&YqCDj^A_5Q zZb-Eh-H@KjKffV8jeoytauMHukE{2wbbZ3xyi2+$T%Z1ie{p@PNA3FbT>jPdsUDf@ z`PL1rufK?I&V}j=f0z5`B=7LeIh5z(Q-6oj0xXI1u`cd_{Z%{T4p?9pP;)qGd+7Fz z&)o8;6;ccB*HCS#S{t=F?!+BhiNC^%810W*6(eT7miN(yqTlH1RO^?vKP`aT9QVmA zbw}~dkFaGQNq!Wi4>QZ)LD=SxqO6VnL#%oGV8hb_s2woc4YeYBuF14S8=saw?Ss(< zxbH%HpLV~!`1Zc(NKQ|F2M_Gkl#CB}2cPU!;OpVkjL4z~-U*|rosFmVDr${9F#f=( z1fvtA#xD%xMCPl~VcfHPGL-VLEV9A)24f$FP%|_c3>}iiLl_ld{CJF^IG=y>;X)t8 z1>_&%o6&!uf8zYiLvbvAnhU78kn~ELM`Rd>p+7^f#_{C8=d+ig7n1*$n%_b7edslN zIh{z9$AmW=0tL16pU0bxCn-uDC9?xP7 zioSR~^7`hD0qd3YSQtaoE2&I+Qg(%2j5hG>@9xy}B&MNGVw{8V4JlVwrkG2(?*?Yv z)o8@8p}XCiK8oJ_B$)fD^kTTlMIqk{+;6OqJ;OLJS9ur}JBCybx&l|DDOEs?KQh9r z9y7>jLZiCsGnZT)<*aHzWP>rV#`QNO*1_0BW3`NgjVCR|6`RJu#)zz;l$tS*hLI1U z)EqjL+?8d`86U2cT8`8bI+&|Llv+WTBOgeqHFOa907`A31IgX%yDfA8c|S_+p#91F zQfd$FN8X202WVgN-jq5*`;Z&i)sYr8s?-S8jrMQw|0iQYRc1djT7xo zUWc|bR?D`kleLwxTK0qSTb^p^&g=G!JFYKl^Pj8DV{6;;wt4+!ZT>Tk^HNM=9Oo6w z#`%AZw=5gyKQBM8$T)~2+9+IQtPzrt$159+!(GPDe?A$S^A=@kLTfMM=Rc3$V!OJV zg*wTyasJ=Y6_>U7e_uae*5?2HHeV(~|NCveY@9D^^Zy_0E%`WCGtadbEic+&mg(pJ zbGl;e3z3rjVt=T+yHYV)B~z};KegU_qW&50{2}+0KS7JcqQ6zsJ=RzMR;Bl;%{}G+ zy7-T(f1e-o-xqzK#kX@!|9xrSx%%g%tb6j`v?mXltu;_~=R9q&o`UVlL~XNmNsbF` zw)IFNJ#D!aBu9%j-ufi1XMUf*t2a=s!(B66t)C>7l|RRSUD{_hL2qe@4$}nMfV?4^OjAnr z$&D0Hv#B7d5hq-g+CY6({Yw4Gf26+MDARx%b7zyq{J--4j_v7lm-gM4_Wt;$QA_pz z_&Cr0{F_==SLuv>OQ~r-}HI9V#{FZS&jY&;-qYCO9klI4)lQ%-=ZVheC9Sx~%18u{# zAf1$2W<6R)@SE|FB8cR*iXU<4$a!CfRTO(7vnsZcFo=dfB_#cVd+| z_J4~1QfwbvEb@fdSK31S*U`r#CUy+{cly+}k>AR>9W~DXh{}C8$Br_way&poM(+xQ0E)>qEwG)p&#-Of<*|32gJNub)c-qVoAOpk8{gHpv(@5Q zP(nqC=FF5!HKz5IcJ_pv$)2~Lnn9b=hmD|qDV7%HO@i zG1(}4&xBkFtnI-$)Q}{Pi_h@eMLFsd)GmC2;OkG|p|u z!Qy_`__N}Ci=4+NTJLjhlj_Sg{g>K2)0v`9;w*1WvVR+qYtv~6wa4X!O|rI=Cu;9W zNey`$c|k%_>M0om_cet!3GdyU&+HH7sCW1uO8v9A|5a>Hzg0IIQ?^Cy#oUhU z2$5gb;qzh}#s3yLnEyh_uPju5P%cGz=>PD&9LJXYEVh2s8SF*xb(EE2OXQVHdw=oW zifv)r*-G-uG;4pYWa=`F7PfT)Z?mo2bC>NXm#sre;d`D*;q0rEalp3OKdA%PltZ@8 zIAUwcZFt+LPx;SVQQvxDTiE{%Xg^!1y!~uBr9u2&sr{l(V4En@Z8_V|8LC{j4b`ZA z_;-u#B$siHtDQ9=k7LwPR-bF%Oj}X~)Zf#lP!H;_i!JMBtyPy&OWw8xZ&`;@D{{xM z?ck|Mt+ID+&2=0Jj>$!Nh4RnelPlSlQInDL$Qgadz}u-$`p$Ap+omZs+CSB9JTb(1 zV0$+wX&tT0XWB`dK-GPkQ*u7}rY%UmyFKsuBLV6^^36*+gzs!G`Trw!a;7Z)zvLs@ z=SO*8n`d_8e>FgQE3-K-oo{-kNquNH@~*r`0(BI0B^i0^8@b1%ny)RcwYe+5*@gOc zw0p~J96B0X@>v}uzfrnfxI?M0J=#;k0!bTn8)}+B+tQjHsBMwy0WB!o!fFN1i?*~- z$E>}KIahCQUS(Vt+oo9lsmAP2^_g-nLCa&M?m%O zT&ypai~lROPxO8{o1EEE|IWF7dD|}S{l(ucmX}smFYW!s|EPVjKE33um0!vwTaYW8 z_0`y~@=kp<@}4NATan9`>d>F{vN>w+$SL((D5X44t{%C)AVO6RiD%{ho-N!!`$)h8(@gLZ~5%ERMUrsGPbrv}T)R6ptp$aegG5xc&-z~P~kNIwq*B9knP4&g! z{i({1sFt*@JVfc{cynag51zwShq5xf8B}>*dbc)=Ri%8yEK%~y{~gEnsM>1-dQ^#P zAKQCs3YC>=b#cb~YZ2!}y*z5D&K)JYx{!A|Zyft#3)@MqsP)48N_fdx5cOFly(31v z67Tlg{(g>E)D?Vce7ZWTGs$;|PgJV=9r<=;rTVveh1}J7tgTqRTrHsm)VXZy*cxgT z>f7oYYD9IjmQzPm7jT5DoBI!(tG=P!F20GjOl>aeP`0E0!|!RA$?Z0d{W>I{rvB%f ztM@56^7qU=!M?3;=sWwizM=2z+xl+4bMbBcm8$RQ^W`SKXS3|rlq}lhBA2o@jvBS3 z=Cq6LmX9d=Q10c3vaR)8d(xZ#w+*Q^vc-PT-lkSzAGIT?P1}d6o4zRT1@&|Lrq~z7|Co;<$5tHc`S|w#I<6fPwm_8Vj>0&1{YEb9qYU$#{%bi{ zl=Zos^jq-$a8+G@s|IW z$cOV*`ssL=%eDr?!uuijCw;_JP_@{O^vHyiIJ0ysi9)ww^rCmdo4Lv0-bM zTHcoSKWjnrcjP0M{jTMD{F?nDAJLNO`-uOQ^FAkfs>BBBl;yIYD(=Z;LHRf@AK@{! zuc&91#(De)QQIu`RMc&>{TIi%@8KJYHMI(;18VuQJsh{W&RNt69k+SEJ9qrwj>sr6 zZ5MfH-tRw`K2|z*X-j?EcE6$PH=nqTM8RD$THHYeThB*6j&7q_-L_VHt z4suKH6fsuCJ4+|8%g08MZ|53giF-$lQSC7w8@a|<vv;DeZ*jbL(XpqD$nn0~gqlQ2pRArQ zmG@UsXQ*lH6(vzFJ4(NjqoJz$@ZxpI{LM?&mH7VEKVM0g+bfE^R4J_7)_0!Uhm3jA zwy4}zu8Rw_%PZG&i@dE|oC|U&bq!;J)Ctu!)Kb;C)H$@KDgD&})xjKHzPVh{F{XUh znkMQK!Kh~`3zW|yDSutNx_VAgPl)q0&RKOp@71fK2c{#mBiCxJ9iaMQ)LPp^m6Rp< z7^9oi0it|#G-}OP2XK74(!jaknA9@pILXJMo;x+#5)ae^CQsDstUua!_Ab48*7^)J zv}jROg6Qki{-f^duln2mX4~wId^=-E?1grev;z4*{7(&`{u}?RF)CVwI%fa1Q`Qol zvli)0xl`7@YRFA9@0e0XSyR+={Ev>G+S}G@mRZH;I66w!x#}=xZg+Hss)K16b%a;d z#Hzkw@ySv1%B?hu;{!F#)0$+2|D~jvxoY|)yN&M}t(Mxcnr3rRE0<$h zD~R?j=cb%QPn(>?nIK;gQAQr(tdzIpJ|L}J{(7{xDxu^sa+2t+j+#m26h;X7J96@f z2_1EjQ;DiYjE+4=qOBoclC$KTN{Qi<9TjqI$A&0C=@EHU-lvP|#x;$-qKqiYpz6n7 z9($=*tEvT{gpX>H>G^LJtpSc4e^-7RHE{on|FB%%`Tpe==3J^eW}@XhfBt_%o)+7x zdU>7mmdI6#Z|i&J@9cBzW#2jHDq@jnw-oC}3vk4YYWj|muH;RL2r#0sE7wintzDp9 zxNZ#3?F^Os%9}euJ8><~?g*7n%h9#oE1?=>yj)H%XBN{LcWbLEkCY60pxaWb#PB_p zO?sm2J7tp*BeCyd43zV_WD}^3zAE2|y(=nq{>J{cUu`Lob#8UB?Q)xp5-ql1wAI8> zYddN$x6Pbyasl7RnN_pDAjb1LLt{)&^mxbk0-qpf$$e8|yW)SW8T;6tOR`zjgnev- z+T&tnteS|uudFp9p;I;<90QID$Ae?QQQ>&7_Z=0*@t_p&o%8XK>m>HS+%VTk90U1y z@ckVXjtA$yqauz6Be&#(KR4fyzpAy#H;luL+J^JO|86@t8*G;@~{O_gN5nID~ z;VdY%K%5uOh^1?Xnq{{mH`jl1K45z~eoGu6w~a5o&YAzOsBPMl+Gvz(OV&B<(~`Dn ze=6;qUAfL#oC`J2Bfp_!F3l#Tb5T#I*?t&(B60@bMhU45mKXd``=MHZGGEV#-Ylhk zTw|cd8*LWq0ud!D?fiB7Tbb?eDzT%LIlfi&;6xqWxALDVu^p4@1oC~ysqG-ws>+wF zFZX8Z1#g~l`(_!pm-EN5EvGlOynJkz&+#JXFV69*JU<`XCC=}daCW=K*|Bc#$2nf) z{N+5q+;-~yRW$_1TTwT#Rm5E-)L)d~i?f~nH~C4` zMob}BQTEhEuPFL-qIMBI4$fTvvznQ6Q%)?}Q`e9$TO%K^W^q0UzgzB!Fp92r{70Ts z&V@uH<($X&cMe5eAzCuD3&^FNW9rtvLu{ScYVseskQ~gimKdMl|1~bhXZpX4^RXTL zzs3RC0_sR=NAZ7Y>n^r=k)Qu>(2L~mF@`~%C-U_l7QJ9w%HyL}CRdDp%<9MC&%-xz zUR~7BmtGI4`Q38+Rgtq*)fIDHA|i+->qs^6wCZ)msx|@jac7ryK)o!ENI9P~Dy~(C zD>@vJwXp+uk1giYjPs86#ux$Y*eyO;z8mAEn`D}^`ed{rXw`EaW7Ht3^HAGU)p^0n zebYrNpCf9?y4DZ1@8y;~wOIAp+`gAv_C$kfzSY_H#0}~eq6jtUn(TY!`fcPTa+gvB zo&PbHK~b*7Sh=E>yEqvXc~ZF~s##BV9fVrP;_Z#a_o-grt{Kbc|E`GW{f|*@L=^Ay zOZKrP`)cJg5do_&E!n=|Z$&$y^0#_>e$<-F<22%vi6EAsrJ z{vXTH;^q8_TA~=HHnLLrvZ%klHu$}Evfg))Un}*B)`KO>`aB-8h#JK9`ZAY{7m7$> z@$%Xh$fb5wyiks9i>S6Xd^@-K{8)@%y)OFGy_=k~+zJtWBDpu;#f3YgMx7~7C z>>Q68V!6aA$Mxm>Jm+;jr?)M z7$|u^je&8T)Xwi&8@;F|zo&NClJ~Q7_D;DREc&m@<(lJRQTtE%J=Kq&xK>k3ylamf zpRPC3w`&W;bt78w-N8l~_k%cbFBLB z^fBmL(DTqa^F=g)>V@dWC~OMVJJFq4*bM4E2>QB=ifqnx%@`!-!)n*L54~u$)|Qp? zz1m`snmBOv@}e9wI?k&iNBOPKtQtG*+;q<75${XJjE-8dxahn#eO<)Y#q!eF35zXU zlySB32rMlEtt#Vc?)U$B9j4}YE4EloW3s4UEvmy5xn+4=N70i~v#qb3Z|7}QoFi5F zc8)-!M?Rzvhf$iF-n{~62KS$xs6)Bt6ua5IP0}v z`s-?-#sCKqNHf!k_T#S%Hx;(mQRa5gkof4l-&Ar zeOJGw=I}#epK?AX@5;H^qH#^dh^9sPm~oOhH?x&|AEiKTz>bIiVqJCRD`+qK{ z99K%oJRZ_{Erzvaayg}BDN3ju!#dZZ)g)hu79+2!&NbzDxzDsbRBi+rBO$it$hQH(z<&eNi%5oc&I3Ng-5 z`I!H%q;)9MoC|W8qSle~#C)Er7cEKmkbA0C8fCro@zwsizY${}dtvG14#c zQtc^no!lc+^!4c9S=296K6h%P1IQoB;|&(InZ(#brB94VjBh6|iEEVqdu#2L9mb2t z75Cy?F?e-r?fqXr%wOQY%I*2p#S;A3^=LK6qt@n~oiQ=KPg(42tv<&1$IH;#%!Q~| z*kaD0(!8#@UzAO`2PfARi{2JzpChgG?{Ys*v0rK)=khcWNY%KSTnBSD)uii|kMKNp z?&tq6t}by5%eUpj#!~tIi*GC6Hjk2xJ~hWi^m!HAs$5t1zZ(e?XNOuu+{dH%v>czt zk>(gP&cSEqe!94$k2rsUVVDuU9sCYI9L7Hx^z)^a;r zw6Hm&wYh0$i#}FuYg*g1v&jLpwrOEg7tQT#a#16HyU>F2SobS(pRv-Itj&0q-!3U; zKF8n@egE|ObIm-z=!Gx&_ltAz=d^j+FD1)o$>y0`I~&vX_Km%;IGd;aQ?h(oD#oT3 z{dYzCQc(xXwa^mot4Z@&)JK-(8aA??uPbl5tIOES2le z^6DRE8!Yy9ZTMAf#!`__{!igk+bUl-T0ZX<^)(bV+bHYHXI#nBvUKzAr{G1#Ka}v- zj~hSA+#C=7&y8){Hebt7y>F=KbIDizs|jdpa^;9)HjiL2MzXkOq`Lc!JS&fiwOtz6R3_7s>CoxaRg!ujm8MbZ z26gB0spMUu?omF4ybIL5%O@q1p_94lOt}l1$RtXgl8NLUp`D-;$U8vYeSBr|_E2{n zA5Y#6D$*U7tOQ+&tG1NIyJN}QK;4aZETz`T3Y<#anlzRkSb0kQCu}Asr`(k)HE5MjDU{dswqhex#tNsA!+Ado>HS^7ZQwZRY6i}3`_<=2T@m#r0f_-sctfWybe?uH-J(|JdHPy2GCdi zD5XhX@&uYfbNnC|=)<+2_Q}507wSEA_-;R_-}U+Zq5Zk`9R@)Ct%~f|D|nxQyxpMx z$KE>yYtk(7-evXJTw~j|ZQHhO+qT}ZZQHhOd*=LW-fu^oI5*$bzSt2HEAp4snOW6% zx}T@Jsw)?kHMS}RwmKzB2HTwS&mN`vv#0*f-tV2m{-(y>r$H&eUZ=rPNsE#{R%!nn zt8{;kr2n<^$1MzwXZk-!IK!VK?|(Tn;pm3@^BMS0B-5Wy%Fi$MpH2jPUYY-Vnpwas zSdN6xH0z(wIveOeS^w$#yW$+sQ6PTwIVYC+kjT_xkcrNq_r$i~jAO{~zn0|NHy(_xJ1X@7LeoufM-v|BhGw{XYErefanL@bCBG z-|xe}?{EAszAN>2yz+l*yz=ko_4o7oJ6`$U8?XF(ef_<@{$5{yudl!F(*OG|{on7y zzu$*{zYqU@AO8J5{QG_Qw}0dB+`a$y+&w>g@87%-|K@Y^IVgO__5bAY_%|=`zd1Mj zZ1VriH1`>A{*&XvXQ25{?hBtC#An0s^Ll+I42zQgf2KZj-v2%4{r_*hevN+K;lEjl zeO8-)XSo00>-~4O{=aMYv-bb9-hby8|GRdd0()d00XAfLgdpn*_j4?x!W)H0 z<^EVj1Eccrh{BPDAcF+bp;3^+7Y-g|(1j&B&wwRMVxk;_r^k{du~3f5(_zVy*eJ*1 zX|ZIMVOdNUVQC>v#Z!Z+`69ZVhVVFi2efA#9+z*!;foE1@a=RP zjm<;&61tdLvVf-KsrUlaT}XG*9W*ZA35mzIB7PhFhb}?Pe42u%C30nX|x}oL8pV$XR^9&ID(| zH;~V!v*0cgp~e(Ch|i(3!P$uD3BM(S`8PU;4u*XYAHu)VZ*&MO zgZWVYg?^<&VHv`Qp*)m-reEkVa2OxXkMi|&9X-m|(IfmYKLUM>Z=mbJ^{^g-Z5=%X z*-ek*2yFlf*$8ex#6kFX(-W{9=bz|jIvgC%NALsi?4~DSKf&M7Pjm!0f{)}c`9XSs zzT}7KLHYtq2fzb#KYazuOa2OV4$t(K#-BsK z#(H*xkD*_q^oqZuqxfj>E%Y1MUxSaJpYlEQFnx;Jd+2*Qnvdb{={xAR@V)^bLO(&& zVfqAegua92Eq}-F^9SGqECu2TKSBd>gdU|y%yd43CpAfo=L|lRCpOdgbZ|OPVv?De zd=^h;l0qjkQ~5M-8hpvkEIykjhkq7NXr}O~;8gfhnAv;|PXYgI{+{2%I^RRyaVG+C zlsd>UngH<$O#(BSPvP-VV-8PgCh^JOWS+o$K&|)u1HZ%Xf_JfGg%ii9g&e1;%tStk zr$T&6liEz+6M1S_QkgU;rv}IK2|SY-$H#-?c^Z?^jNxN>Ml+U=1INK?#Bq9p8eyS7 zVl5wd2E=4E8O(b+2IUVprs=^9CcXJcKhShwdZUFACumxf)0wp9HT_6WQVoj|TAZX& zu@60YR1+Wi1Ut*m@ssQfKMS74@^N;8o#V$L=fU&*0zU=sNp=jL3;Y=5B0mkwDR!Ej z;-^tQ&9Q{GPtv1^y2#IXJ6o=A@SA*vUamcF@>_fvEX(yea2a@=-{9-Pb$X>

Oe( zklTC%EbH|Vb`TlHhqO()F zLxqrHqkhC5vyHHC(*L0LSALdqA;ejD&(I}U{>GQU^Of(^57{HO6Y(4MZOQ}}w-I@k z-l9}6aSN8)bg}-%zw^a<3G^=gfIVcpP-~~YiI`h-j$W+4^Er?o{01e0iW{)sq;vHT z{*%wubD($Y`|JVRjk>$^JUv(c>_xPT>=R?iO5s< zjFX^rieIO{@dJ4sYq>$^qm^HLKHB@qAL`dQ|Mp-lyY&M7i~r^e^nB=r`ZwwSq0T=jF99Q)C}tjyWnzN!q5r{FUt&waf7m{(cdy>3@3MPr87xcL z67~=FaS7xyTMX@anO$Ma;a$d-@<=AKS&BCQ;dA*s9@EU$SLkIrTVJJDz-#m>xCnYb z+T5r2>pSc&TZH;o!Nt%k(9UwUj7Kz)%rdmLlpjFMetkgSW_Q?1cvrB6h`kD4W!KmV z*bnFv`WCy*mh%WEqFIi*%lL79ligy+VLzb{Bknpoj2hS2DzvZ?^qD1&=^N}OJBG;P zdIjn(=PP)46Tz&8cNJUB5+SR^QGEzCkLv5}26!0l97U~TdL<8M!kd+dU%}TPay47S z5+cvRL;679*AMAK{Q$hJZ-IC8ZSbzX1K!hj!Tb82KB5n@L+l9JKdM)uwUvA=^BEJ? zqMbGDus*;Jf(Lzs-p>xOL$DmyVNE!*iid@)=04ZLS{5I&j;)7Y#}4X!Y(Kak(UI*w zzMn_2bMYxeu`x{ya6dkkC^j;*&)Kk^MY4POJ{}2?k!={Wny=wuOjzisHj0g5BHBHC zFOP_rNH!Xlqnl_pDs%+9oA2Qf;EiZcVvPs&NxhftW6>=lOmxIXH{lTz!G^cH_--D? z!e+uiqJmLPPgr{5ejqL~N33UYAsfIAY$FSY`0zHI-N|?H&?byo1Fqp~c~*Xo-l19f z9eS5$LpdwY#?RApG_2jhck-}^4`;K(l8t9U>|L4#a*v+ER-M$R^d7dCWrpV-%?!Cu zb09K1&%rOy^E4CB%wV*mK;1Mzeq1opX*{H%g8hF2Q(w(70m^EPM(Wjq8Di> zvzD*pp-gD#7}$oeHiq5KcktZ&GQC7|BPJKG!ZY$$vrf{wwwLd>-c*9 zTZc01cwWTk;g$Fc`kYomjTbbg-Nv``nAoZq_A=tH=*xO1+l7Rn>-h$x-TAH8^NOhP zoK}Q9qv6CgeN~4C!-??Xy1u5vimUn&7!EoDEa622aYJ9%)DW|QQ^-bs32k21m-G&{ zlZ6qF^kW@HgoTcX$Os~$xT$aGSlE)7HkRGWxA6*C=QA2wJl0QiXb}cF5@I5XNa7*A zh4L+ZQwtl$T5=I>UeXu!cD92tL(N7WN<7g|btn-UI1yM=G% z$-&q*x!ugS@F<9hETV|V^bt)Xp6X{hjR*yO0c~Ccx3TT)f({|uSTehbZ|2ERE4ht| z_$VT(ctRi3)Z&?bu2YLN(B~0(K_|5v`6iy!GHg#$)JkTfAu_5+C7$aSI+aKbeGZZ5 zbrQ=BGfAv49AqY`O^K)%`lU_@o<+<#okFA(FLh$XB(Y~;Ija*{X@p4xOJe&9{+Ifd zPA*c2gs>;F39T~HB(&Nn^Iazs$;EegU+Dy}B(&dP`L4g|q#~J!Z;jC=KI{o>Tl$nf zp>4pnUQFL=#_i5|I>4D!%C=@D^o7SU#Sg7h^?P0k8ls z$Xla@HncS@kI%9_>O~XnA<;!)He2WAg%Mwb6=r#PK3<#^Pnzo|lczND| zwx`iW2S^N22(=2c60A5Y#7jU5^OlHdMO)Icyd3XHJJ1-SBP6CMh{!@LH!IAG@Z6|T zn72SoOWJ~#;bnO)c#7~&v?GlvIzeKI0*EijaV|eDXkWkoHsjc8*US2Tje6IEzpkwjDmtI*0c zkw`46(y#i9u1c%WBq%4rSyBo1%Cr(qC=!WIDlpD;QonRyIx3uepfeWi1YHH~S5{T< zPa~<#%CcbX)#w-fSy!V~p&Qb8BED!y8$s8n2}D9Lp{PU~(D)*OXaGxnlpA8HgNkS4 z+72qdjR$sA#&m$hx1H4w{Zn^VKlLy0m+qvh)6e>ou8#G5)>YLzbSqTF+N-E+EGyPt zgMQKabK( z)zt^{-qfNW^m|b-skzC~NzRBgn!RVi#r+g7EtzfD`Tox;{e zd@WU5eKDU+cU6bhrrlLtS_iC6yQvAPt@>>ys9)wM_}lz4J>c!GdZ>D|F72Tz(t30} zqJEn3>WBFb{xm<#7@e2pVPkY2RuZhrs({s4Rj@j%2G(HJ!IG>78>`3YDqs~>ne{|# zJycIsfmWpB)OhvXj8ostSMa;}X2$8Ux-u(IE6|>57QXS$=w7Nk%45}6^Tmu+)BGZQgzt`Jzm#i6ZHgeg09Q1*jB2wx?(Rw*JqRTL|q@=daMo`ugB>+tS)o|*z2>} zY#fe2Z5*jeU>z)7wO4FwRSQd%SS?6J){srslXOGGH(-5LFfZ1SpuHjeX;U^` zPt#3dZ^C-9{qq<2o@linePTzeG3p6w-LsETeqw9#@pJ;M1=i%X_&7SA*5DK9 zM6f1wZCGmY+I%b>M|+^9zF=S4hc;(3^$gt{YiY(Fp`FLJ4q|HaI(!TrORMvVbP`wt zx-KkrcwIi4j-l1~Bw7xv4*d|d9@&R>lp3vCuvvPhZhqC3f?qF43j+OiCQgKOWdQ)(%n$6H|<5cfjxLxS_Z5NT_5rFczr&Sj-vPN zNHt2`N8Jau6>7C)U0FBQi#C9_K5xJW(~-10FGEX%J)m17rWNagh@P|yVtdhsh-ttZ z@*#9E?Z&(F(zFt}Zm-$Oq!RJGX0O_cuv8)y$qjqmRw0$iRq!g#s0!q!y`2jp1#?8}ngwC@n{B+gr9A zxnpmGw-8;LNGoh<)R6Y69ic|5r`Xf`wk)}8?|^p@_t6%^S^L2jr^V<8lt0=}_M`2q zK0*4a&sgfGzS$DAIQ?cz(h^{C#C@@!VK0Mr%AyOs6fKE=99|N>udw!4U*Yeke%n&8 z{b3ccFu52e7ejs2k{}ydk6+ zZ?C)3F0?)D9rRoK4%_e+GEg-_R5RWP(ww(LOncoX_@m zJMz)Gk#5f0BBq^gtGm-~bd(+q%NzUF4peU-gH#*X+v+yD2klN@+97JFdWqIv*nWs> z!Tae^(A>4>9l#Epxz~1(8mwO1H_)%_YdaVmtcHL?P_w^o!CUhFx*v3F-5KX@Yu%If zpsmq<8{JxWVLfSB*N(U6VbLac19X4gk`I8i;$dJ9>%zFUyd7_)JF(8J6l~g=vI6nq%{wXm@qE1Ys1^}mbxSB#9AW0l^&!A>ef6I?4eyKH|S5fHE+XP=nkwS zYk|m?I&gy#7r-0JHP`J~2i6?k7J7&t46AcPz-GD~YtNd&+gzt5sazRi-B3hWc%5si z+p>17DPo%GH1PWDkEvZMH%t#jgn_oM31XV+)Uf+Jk!c+Kp2#Md)}=u?olEOdf~km6 zDO^ftL8Gin?ov3dj7kY+aOuH}E(4g-WpoZ+tDH*ak~^h*j!LDpN{@1Smkvya76W*l z3RF^;%)Mp9^)UU0y=9)pY4-*tqk@`L2-?5iWxNz6ff7nZ+Z;oWCg zKC#cNtL~!1@CYuV3&SJ2NMKkj36&IiH-(bWp;cm+#D&JXLa8r^|IEIyZn~=u%_F&( zE;J7V{S}rk>?`Z8yXmj2hwiRJ@z6Y`3k8Yc!k~rFDvV0x(30}GPm?GC{SA>{**Dfx z_s{_k#bdaDM|aV{7%sZ|4*NIuo%PZ^brI#WTozSDl&8;rSs0cgs<0}K{FlX)&y873 z!A}aQ5~Mg-91+D;F;$ophmH<=ky7L*Ys1>IpO7Z{ zC!{0TQU751l+PEMPvt_M&wR>fvdyP_ZrgmQm0#tBHy`Npi2gzgKUp4>^Q!PH8jIq> zLn4EbT`U(BXdWI-d=7smqBR zs6D}@&N0gpf(cy$x6Cbd`N%RzUJ@|J61V^o-z|4}Np7_q{=8&4_CA+NfHo7d1Wa

pY5Ixt;aT(QINCu^` zEfK&7Dx$ihQmK^cE_eq_4SgHSDZo3>_h7jTrh&c%TM96RO0Mq1at}-keG|6iU~-jA zJ%HuD8sy?*jW=LRrfxuzs)w*Y0MkJ~0w03up&wyu(yPbdBc)hG6$#YPgVDkuH`v9) z*0(3~-8|P0Y)?9n42bSP9;+wdT$cfCPv*G}kh!icV%m|mWPzLShPb#Yo*IG{2D^^r ziF&F!qV^Nj2Hv)$4O!?GxK5-ad8#@=o~hQbv>~m@BDc_uLERxvvPdejl1xE&CePG! zuoHAE#Iz=@$aJ^Jbs^8y3)O{mh8~StV_Zwpg}hKLAurV^7e~bfLHh~?K{bLd8-A$bkHR&P|{;EVdIiUeQPH?S~tAy^6rg@VuO ziz*s?Q{TZN&;^4}>NEHm5ygU{!FN>*@LS1(pmNlSbr? zY7BX+iU&W`Pp}wt1$avZ6@m}yqiRALlegeo^-kpveyU$!ap>~!RtU-m@6>yg->VPm zJB^~Ef`Ua+<$@;U9rzBuAM`tos>%jUNfS~Q_Hscp(iEki^at!^uv9kqMSr6F3ldE= zAk9dbAgc>eaa1-Oy^$`P%L<(ZmaHy2mPUdj+;DItbY|GIxExp-?n(y@Q1>_eMWd-q zF188*LsVv$6aL}gFgFw&4xI~nsLSnQsn{wvA~U%>E~bj5^1zbY6?4&5ahD&Aq4K-p z&_!J|x4E{2MUa(?K-jxxduBeIAqgmPh5 z5G({TMp*%{pex`wW2`;4XsBxs84Hee(_B}aX{|_CGR{qR9blX0`k~yF^dsZlIM>ll zbyL7;&>i8Q=K8|kkMt!I+<4aq>`VHPiEaYQliWnt2~ksAXK2qUZnEnQdmqw^bVj)s z%DqvZ>?XOyjAP5HlLn-8P%)?u)(C2l>ZAtB6@&Mv-HW`3^aQ(L>Aiag{nmB;!!B6* z09#LzCCDHAQduCsRrR1IK^thNM(`279^@mUdXhJ&_13*{-Jn0YkFE##1nEv*!}7+x zcHNFk{T2PDBBrjce(hd9s{R-aK?v-l?T@~JHLDir(sYOa)4+^*vE(uG_O1Pvf z37Cu}1(UO6tb$9yl7q>yT;8Q*DOh<}D!6hk6-&v=!BXCpb*Wh@Ru-0Wt_;d$!89y2 zEA7&kkem!@&MzIN78&s^q~Y zNQz*s8bC&nwWzyJJ#xdyQ1Zwo4TwOPa)pm8jI&L5v!0NhsZU7qyJ($&UwZYo(4PljBEjI*~!K^>4=jyxuh^^=P zvHGq7*dKZ*tL!R)l@QmLHE<1GU)B$L80jFeIbPFJj+z8l* zvk|PCtLo;nMy@Tm0D6+j7-R@0sZ2peFjbHVoCv)N`?6ZCQqSB|w@N*C&%hV%xf{u< zyJ}!Hv^bBob#2@{HXnKvtKq7H)#01V+PKzkF8poW9FrzU9n3MQgUn!N9N#&twQJ?( zAgZ++jasAFXjaqJaGzacoco_4uiO&Unqyed1U42lbxpv=@Qq<5T}7~>s|nUb{n@OQ zYw2dQInawu+8|A^7Bh1|EG-)gDTQ)L)R~1EEgeOhELep2#b%L77oE^1s0(}woOX`}M zX0iv@;F)f&sq8^El&70%<^sGI)phu@1=k^2gY&RlP>F*iSl>C6&#P%_D%QFTw&m(9 zEa%j3`NMs81lsev`{sVZ@>~9rKiv;U6;a>7Z|r&0Hey5n!6127Q5cSQb>-{o{RgMF7X*i3d;-jO1> z3z5M$*uTrAW*WBktDMHBv#+pxllSCZDT8|u72L;?rwVlN1uDl@?YSmFdB!BX{5K9DB(1p80N54s)WeOy1L$~wy5fe-Kr|;-D(%O3%(lqy2={V&|7dG)X-UjEGSpUQU$$7?FM%v zt{kGW1m*N^-20Y8>9;Dc_o_YM9z+CKmkWa6iF_<0fKJ%J9S2XU6W}Rz5=L>miHPO0>VitTeOLEVa%pR*S&(&^uh@Aa<|=+q1zPMtO%j1Ri#)5V_Kyx zxz%pIy6IMdx7^J?oUi7o-7aPjBiM~vd)#JOMwixGWNBRr+zh=5md$dLEUU}tt#XSj z1(wn!^=)^{%~Km;-y}E6Lb|NpCQIrP;8tjY?Mn})*BQVBSc<8inr9{^wlkLAfcTAa zgDj{E>Fu(FE)H&k-sNHiF@s&$p51Pjdn027cd(8P=8n4!ybYvpR0MQ7HlVOb+@xV2`Dx#8|ZuY!HG zTqU#WESjOcj9@;U7t9D99WBQIADbs;C1O^|N_M)OCM(-%*oVrt5_Dxd75h@r&XCh( zMR+UODz>sMuB$+bX|D6=++bd4j#l&PXlN}u_{cmq73@qoLsmfDingjPs*C8VwwNvo zR)H>WXUUneJYp)?YVa4)%&uG6Hnz3Rs@p(T$`-J^E9DB= z7XFp8IV>$~bDK-&)a`6ryF#{uESJ^oJUJJfE6dns@HPi?>s-2-71-xymg5LCwC(J2 z*$}c!Hif;Jje_lps%xNbbz8&Em-A#3*qhoWR%)Re*oJnQYyep*8^hAX*0c-cd|4Bb zHS7cP&_vPoZ3DYh)`$Ef8zH8#tz{R=1+o?*Yub9YzWqnmgDjD??IO7lTnL}iQa7@Z z^#im}7g0-OUC3ft$1awOz`D?N5MSH2M{FZ|-#jppbtHWs>;Ox9+retB^gVOmL;@q} zh`J*z9c)KywANEZaa+tz6;p&~F=a76PY3&k%+1+21wyOhnxmE%dW}EnctDUBwJh+IEE$ z))P=`qL?5G+ER8rI6;gT1#Cgv2a$d4IFa8L01Lp^8w`0Ju;yPN7 zps$;|&^OF=69J5%!|NRIj}|#>KIog~h6%58+RLa8u-}G+)46RfJ3`zsw@o-5hX&f|xHJxRIt1l7G#>43d)au@>fT^n*yBO0jty@J zjZH)8Kworg%ocOeZ85vS8(4}@d)b~gK5F-}321!U(_V5H-ENZ{@v&(_EcdVpX#(gJ zuq3A`XlNZur=($YXfU)+K`$eEm$~dNL1%+KCCv(E1Hb(ht-)8lZDPCy+toEi_9dRy+ltj1D2U&2I(Vui%j$m zjzA`Q&D=4WP%AT?O?rwRVm6rtJsmMK$aKo9rolU% zOe6h7Uy+esFxN~*w3dm^C38r3F&ENJOeOtAKd>L7r;xd%o5+C3jC45}E{2I^;BvBz z7QLa_FTbkIikDB61mNBRkptwyo@M2Y_v$7n7l4 zh**poLq%(N+sM|kv+ZQt$pLmC*cSR9lGo+|^PrXV^rE?7(ql_9&{l|SEnCShwzF+7 z+sT38Ks(6JCj-R*F(2DAk1QeCZC<+sE&M|kk;P<)SOgg?TB24f*;013U2F&0UJe2W z*}--J>dq$%$RIILECd&jg=DZ8gz_Tjbo7$BXwqRD($lhXupMH{$_~&iWD?pH>}p%e z7BVSKLd(e^cBm~U%R)DYrG;!RlhLF!Em}xNo1xrXHj}YvGFn~^wZm+ASq{1>EX`z7 z8I#7M7346R%~p`*p)1O4HY->Gx(U2ZWh$E;dsRthwOMQ>SrIx0jY*rx7?8%Yq}*<{ znG$k`*$(bBJHV^%iYozoNm)W(aXU>ZL~R4NnXRU{yymXD;)p3BE6Xf4v#l&EK^K$P z-8EMX-r};f+-mli(sGa43zouC6`9#)vQ=AgO6bIYoM=rm5%{ zc*n{y@}N0u3ds}hxGRKhC@fRUGv>5OEf1J8U@GWNG8N5EJIRjFqvauU(2Pc{F)}LF z*$`|f8^}@eusLK#!8=-Zmf2|z+F5pjP9sm7Qzi{sJ#7lglkS8oh;8G761K8-NXDeVJCCGAB)1nFhLmJmpTh0%)_K zEFe$2Q!W?nin`roSDA|rM++llWLjU=1EWCaM@#|mj63aeBPtioO}oo(($dJZ9#~J- zmHFgZcgE#IOn&KTU0DaT&;hL@Yl99t5A7klgWY9rnpYliXI);@$|pn7fYt_U%UUut z4Mja`$(k|`V)DwosFjE2r9EX2+0Gm{$4om&d(#0t3LZ7XWd|%DGht|GT2r<~Ogq!o zoPh2K-!Rz`QNv{$lMY9r4UWPI(*{T4BzOXGD@kgb%C017Y-%vAO#`O0X~Fb19hkwU z2Q%6XU^SezD@j$E(RMP!%VRGg#)wR^_AlX>Zv}ZopbLk_{vr4NL36H%QhqO`*GBjV(-lQ_l>N^&tc0 zdc?^w=zN`6!@@Mji^q2kQb}=4%utRJYp5w3&+r$Ji9vn}$i=AQz_Mty&bu;}< zW|>KD6%)w>vK2Ag#4h+9`A8a?{_-PQ`$V>gNn|285fQuLccdR`^*8-Y7MWSjgw2u7 zh}j}Gi^*gX`9K<(hUNoW_(*2K7l1RNH^IAEY!YwDWYX7Um04t8w9wDICyh-bu!(65 zHbTwW!vBBG*^%WLDV+b^DqPuxu0?#B1_~%n`FiDA50(`gdsO zJ((-~4Bxq84)l7&Y!JOsw~u*6USoNkcm?)?rMKy2vde5TEMol(;CW)Mm@npuu%v?s zPs7m;A{<>$I*Ja$b3Iu{dYT+EyX=Wty-a(=bP(-D1R9=p5*@`l(h0JbydP+4e0_|O?sG|GKcJewe&O<#cHyO zR1{sH+aR*7Xd?`bM8lE!*uw56m&_@`uz-5N1%#0zZ2T5zpcBU-`I zT2vO5#1>K+vK6zL7hpfblZ9ddIA4S#Rp8$WZYA4DOT@Pl15Fe2j#L%f$ab&_^mFop ztP#&4t3?FV4NrEEYND#x0snS#3;xyO7G#w;MyiWyU=2|ntcHk)i1#y?7m0-;B3UdJ zflI_<@E@@RTq^z%x6#HbaFtjo24L^Ho3CUbw&5!oWCo%<*bFj9Nlj5h97W5=$Q`m$ ztPpp|ZD>sgBSO<5X0XX+49#thkXoXqID+`2B#+4rTTVzWa~Jhih`W&GBClyFT7Y@r z$qQ*Ia{P(QXY!gBA|Ir=I817bT3{`-rO>{niVihH%sq0KEEo46%S3+DTr>moK_4P@ zL~XD(>PSQ?D(NsY)D$qyL{m|~yA|=gcnu;bO8)`Ha z56FESwX7zaX(Bjc1kGZyqWq9NfITxxjYVdY1^OE)XeyXTm@ zhJH*Q!CqFJCTB<)u&gK}PLb2(33&{AImDMY<-{3smXs4^p-YPs?XUwU8qyt)Dv~VYS5(+S=yu*7s(BhUZjIAhREWgnAk&hqr8{wAsNJV zat*veu7l~Ji^5(^6czi(UXoE{5ZAzKCWuSrS?y(w?VU*sm_C%GkWO3$C<2e}IGHF;GsN@-?snOq{7(e`C>1(vJw zw){c9liTtZ^bYx*d;@Po?~va}DRWs4H=JIUoHCHnD{`kSWlEZzatHJ!crVLKa)cRf zvWU#$64@n7ni6IgqDq>Ja-066atHw!eCKT1T1EXnklw~ zDGnCL@??~!fV*S~GuiHzyW}KrvYll2$lY=xILS`5d*vQ^+@7!n#BoS|F~RPWd*uY! zC))9LzuYIs+XHexxDVE2HowRxj@jeT<6s|e$JvAOfE;TN$%EiQInEwMR6a4r9+rpX z7}&?!y|CpIdm(wnXnRB+mZRYvWB0+6SL}o25&N;^nMdRnqYyLNj4`Ml&IA{+*kAP*Q9bu2lV{$k+!Vb45i_LbEy(~7_UEnUe8{CbEgYZ2g2gL#COJa-NY%d}5vN$B3k*DMk{LjcmvDI#| z7va4m4vVMw9y~0b;G6I;qMniqVw>G+FCgZkIFIrLaRgBj$x-NtB#GQ;ciN;fiS*oQ zci6KSGvGS}qBP@JpK?5CMuC{Azd_*RY@lcKr zuClAGlV`+f;ZWlYhQ>~dQ=o&6D;L{UHZEe~$x!l?I4MHO06Grrab+C2#4fg>;W;Tn zP>v%*k(-HkpJP;wCUtv39kx$~Ih=u?4{z*iEJu?0q{0H$~#3UcZ2QU_N4A|a_ zsPIO?f0=(HUW;g8RQzxGx8jY64o1WOmXCp$=;WPv3%(ccgvIklQoJAM$PE=6|3$tv ziw$W5wqfJ(*M^P5UmNxdmhtSJ9EZ|xl;6p>DF4Qrf3eA1c?y4T@y&i3%#FXdc(Tm{ z9&tx7X0a2a@Ubuszl5wLsq8mmXhBmDcW&8Db})x&PCL^aEC*)Cl){{?94tF~NMF;3 zn5~4liYzbY^yOnG?NnPAzhZSw9n)VVBni+5mxv@p|5pMM|4*-6fEHOcJ3VFbPQvCW6)XdBsDYS3D9IeTYe5^*vv4|MZu6#>K4P-mv>VNP@ZNzUM9u zo-_!ozP~RHo;?Vbeg9w_JjDuFG(>F%2{EhjiqHnN##oNv^(F5(@ zZk{Q^a^LqGj{BbBa43hx+s`A=LKyCQhW)$KBgJ>L@C|QP`(ADTuJjBMp8LM#@Te6I zZ$*dUamWwEe8*eapV@Tr2{KJY;A6!Ya17%7yVG&-E-^uze|LMD_z0Pb%i8y4OGHM% zTe_hT^8qnG|Gcvs2X794WK+d2$P^*?crgwfhiLyUZyfR)pZ*l_8!}mNcmeKv&k6s{ zCWDj3B*9?ec$3ukuv1R>Byb|E6s3vcIo9=oy%PQ%_SeF{;qK4!*X$)M{+jdeu)h)h z?Rb9%zhN(ge*^sm>@RW7zGd&2KbxV&JN6!Y3;i5N{yF%Zy#QYz`n`CM>=yp~hW1`u zCC`x8!e2Ab*hldc87=&k^OSuOPms&PUtLd_zcL>qU&ZG?^jByWsqntBe{xpbKLcyf zzpI=H%bD>cYH>{bQ?B9JAeLu@-S-C|lM?q&s&PmLlrzeQ?2CAW%ohH7_fMp8NP5^a z$lI_yL`DSv4NyZy<-|rHMM@Bg^kHYVu z?rmgT_>S+ms<8Y1n~f|IuZ8y0qqiwN`Z#@0Q$&83{Se>9T}0ktRpchj;;(|ps_46_ zg_zoqit-*}?jnbT|0ealS{2dD<$Gi+Bi{FcZpK`A-}6-g{b9a0w=PQM(NDISRR*_U zj(jBRf9oQHk&wT@|E5K>k*om?zWt+E|H~Ey_Q*DZjfh``2!DPbqQV{pISc&nTX=XB z=zmY5!4egD3jD8}?}IA``u^swSeNh1+lu-4;gG#R%5Z;vk-{PpSq+exK*;ESe!;rP zZJ4d!1(99RN9g-#>!W@dupV@bKfh`*P=m{u$PK_i|9ck8#>DSetUteD@i8Z!$oP=o zBA$(pU!{0|ev{&%^hKUwK~h#nAds>v*)*Cxue_x3j0ii21CoRHoM4+Z_*qh5586XJzpN_@AGoY zY$Bh`3+6|^WH!WP|8qZw`)lF*8FC>am&^*Uzwax6p3R+DLr0kf<*c{^#l4@b%uC4P zvIv z5m|%#p6VK~!^eGpMMGX#7LtA@Tw$;fYSu(d4a`FHJ?*=&R~^8e&<(in`SA1bs)~y6 z)KbN(uWzJFym@+@?ayCLnRpFvnj)P+)io$Gowoyn<*3 zDKAd2ldO#_3vW5hhWDc*$FbZRJOMqC`w^6hu)~LXi$~kO5}3`@0{{P?*CW9u|L3W;EO65=B@iXLWX-_gLWri zOQst`Wm6dfQL@GKBh{xoq!2<{`}Kw=O-t1yFT4@ocloIp?CEAzv|LgWt&JyQ;b|}pp1~As+acTV#OBAHHo~7;cEvoyw4y5{jo5*h z?Rd76&>O5DH}g+-sqm~NVO?Vh?)2ASHmpSXnGiNAiI44$N)m|pU_9I#ug4f&ia*bO zDdjh8iJu4WpQ#p$(`+wWEY2WDnC}DK3;HZN>+t-S{Qr9<^u40{*dlS3odM4vx*O)Q zrUBE4)aXM!3+qC04mqiO&*?sJAM*b!5a*GfY60vE(JSe52l*bx{VWQ$Dk^#^eP$uw zUwMGd7dMf^YChr@h_BcxKU3d70q(@pW^&L!tsWFNkR=IE(}-Ike9j`@XL^uz=cz?1 z(H(PcQ{%ZI0iF&blY}Ax%85imFfsB%L?%f@Vlb&lg5KN};t*R2nZOSSpHJxkT0STS z@Khot*d6+di6`UAFW82!#`phD;QJBjpYweNr(J)Zs(0b3JDKdyQ;HO#KOX>H?9UT# zF+9zFG5dti3bhaM`$cb=&?d5eWW_U)O>BF~w8)~;3-;a^Gf8ZdSU;wc81IQBknv@4 zv{TIXD{bUlG6zmJV`_FU#ZuB@Lm3y(qeWJfihHId|Olp%^ zKl+l?_CPH^^5)0F*5W)_WBc-cJh|u#Nrrb#5@3A;q|X~R0Ao29Sa(GFQ9eIvw&zbj z!XB(Ai9GqI@8BeCi7{&AGmH(y_|Qc*3u9>+@J><&+gLG=02#{4+m zFg6@|7~3wki5KvG!n>J%v}`CFA&1MMXkj8dgAw-${3Yx!@IIy=fjf<{_6htI$}jP5 zrXRN(!bZvwatLY-Wv^j*g|{`giY?*|_!@6q4rAL;-X^w+UHTESIqcSt?Gtbp^kC*k z(+8u4A;_`!&_1%r&S!V&J^Bf91nkkfp?By9$iJ`y-kr#3_tZYKd*Od--=gI=X1l&` zAK2}P*@296&+J{h4^hwTAT}B!{e#f{VB~?jiwpz%eMUOFP2aQk!TYH54lTSj2ei*o zaKLAkvp3=0rU$Yyab$FQiqhj#$WgXL`numY?Hwa@nwxRlBOzT63kj{_`>F`Fo(qb%skn?LB;*5_7rp z9PlIBpapi!Kf}8CF`nW~;#>axn_wRCbHSu&jmFOVen+%l-uK_beT)0Q4f5PWtP{WG zKg_D|Dui%WYU4p0lC;ij#)1az+F|#TIm8RC>{XC4oZvOkFjlxvqZzWoeGOfP z6|QtaSGdwLUExZXb%iT!+ZFC7Xx?2y>I(M~S6ZB(fEX~%eggW~bWqn`ZQ@s01_=$66jRrgQc~W11u5h1lH`{lE zC&>9E{_8nC@glKnKv#VM_j6b0lRhW@3D8xAk$Z}iH6ZX_$9bdANc|in)U{y4o+f3j z`>A^^=Z!uk^)q)nW%74_J6avj!Jqb@f}ixChCkzR$e!|^8h3k~kE_4h3?(c$r^{;bwIluZ(#BQ~>Sgmo3-vSoo31YM=d>hz|S|7g| zelwVoAG(iU~zC(j4&`>sywJRjQw(x-MW z_Sg@}`B5y-*^D+wTW1q)TPV+IL-6`ZqgiF=dt1?WaMI%Diu_)WMsJ70p(cQf%fq4Du0zT2I# zcAUN48E41CZzOap@wb3s(1QEi?Fc{UZgP#cw-JA=;qgK2PUwB~Dt`i#Z8y*RlYa!wsrO??p!Z^TI7b}u_t<$m z%vESrfrog|-U;otcfo~~cmPD#yWLYUcDe8iopC>?uXnpI#`fDi&X3@;?LmL@NB1b!~9_J3+`@l@xZSRA&*b|^|Zn5{eFU3yB?j`>{?s39b+T-pC+(V9V z%ntD+hn*wjxfcw@mt!x*9(Q%3>T&X3Y4Y65@=XJB(kust=L=4rr|JxNp0U zImevC@Wbv6;IKYK%!ANd?v2FV;6BRk`;DNkK1j?1(3@^Y{(TMm^TLdMgdO@DL05f% z`1_$VZV%Ev1cRg_?#-m%fQz)OlTnS($IMjosFTf z+uVJwv_Nii2M{9-p!?DH7=Z4_gOSeA{qXw<4~y*uNqJaopSu@66n8q$FvFkjcXB#A z)BVm)7kC$^t257+rq4VOWZprm=}AYrP10-{9uu1SaPG7Rz6Y%J5i#MYk09k5cVX-) z^j;Q{|DxE)m~hlbqCK<2U4TZ-Q|OzYM7w4Ic^1Z|@sHE}X?{v>@o)F<@Eba}Lyer<2#GfWMdYa84E&s<Qr-X0pqVzs4Pi5=PdGHMn`Co{|eefi~Lv7CRzk)&&$q6-enU=fqg+%+vxWLHEpAR zp>v*7h7y<)lbwmVvC{4w^!rM?WpGQmrQO+Z=>wK@OS!XR<=v9-3U2v`OLMTITfvDW)^sc4ZU!Z)CMXG;!JgU#)pEMHZ=hk<#XW<@ zQ5W)ecDIDpof;q`)Bq!)tNS{77hTEI#l4dFEg&fz0(<_-@UTxVS6YxY_=g#>tHOie z)?Y>Hm0>ro>Iw$xYv@^R4G;JS{jH>46`n&(H}Fsw^PJUPX-QVcPR8`u#&AFQ?i&`)-S;uko*oLqNWY-%jmt&ZD+oZa1P!B6Q0 zT1qdcH`oySx#P~T4_{;_m?^!TolqaAnw#rRjV%GYst3rgOW->~p)&3uFK)OGMEUhx zyCJMfzA3S)ZZ+IaHoTNQU@xCa#Zm84z*e$6%H ztn5yXO^Q`^tKeQr>PpZqc7u1mjr8??CAYFWDOL%Z7`u%4OF`+l9;EhF@XNsL*ahPI zI`XdfSL0s=^2c@H!FL3eZ3%pd-^uL}Tn!3h&tMzqg*}5FxZR2A5p)l>g1&feu-(4~ z-V^tn;407^&mq2ha9(hYzr#N-I2RY)CU79Tk$O&mt{?d9*MrQn&PV%+*sj4AFeEP^ zWe0o*DEPgCogm-$3a$mQz89K>JN@2hQ(fnGa4!b+tpm^2(cR7UYyI8e&aCsNIhTi5 zfK@ZixdQAO=?Q{h!~0BkdUMruQiXN18eEepMi4&^l$n9}Mmo}qYnGG_b8~nz@FB*aKid@Chf#28 zIJZcSMIXEc@y$7BKN213CY-|`397_6bje$i+Jdv!((-Oh`Uub|8YhPb!mSt{-2xS0>1A1(m%V;Ql7!=>PG4ThG1VY47y2w#djg!sWA z)+})r3b!U)1cyKeSxVYaP`H+YVYAp-94>Tl;Y)~Jh;K<)nbQ+US#W9;%BEAJupU;P8ifr>X%*H7O}`aLNcG*8 zp-}l-f^5{lZ4nB;zXixb4c+FUF#el^deq2m7RnAlGcb`FyI?C}EubmrNln})U@J9s zbArL3*5m|3K&{CMhJr{_o|v4Ve9#?yo$|psphuMt204SB3PBgJpeh7ililFmz?P~& zYWW~LxZGLoWCz2*w8;)~aD{2}euQN+*Qt=am~e&UWzH)6tH8Rc$bBjV6@&9YpDGuu z2BW4N_gL*zOkN7^O+|8604HE2_%@Y@shF%p&Wb^$;QZuy$+Fn_Smu<4mcy5WX;U^> z0m4jW@>fd!VCsR^@;$bV>L-6Rb-^n6k(eK_W>X*hmha5>xIYp9BNmqGfM@cpX^?CP z{|@(OQyZLaaVnLt<|W$>-Uzmos{)zk#V zYH}2nXzjn_7pXh7i|AsZ5Z`>~7w@~NsJGV2~Qr{8RIsD2M z9?Mtc{M!A}?E&7P^3Xobb_N&_wr?rvYFveM#LP0P0{b@R1VM;QmbP`Jktq zA6@|el296VD1fbkz994b9s4w$;GID4`n%gYY#au*H>gShn1sEPzhSGUarhhcyB1bu zsNL|!V2LHUHZArO_q!kzCSISU5A{u!3WOz6iuW#`jPXretPS)7dFm|J)pCC%cQ3G5 ze!}%YtLvNeY(MgO`1&P(Af*?GJH0?05_ViH_?}R2kg9rvGV~qP7ydnNJaBEy#sdf* zCuhkZ2h@|2*qF&l0t!g17g%_SK!_^A$2n7yI+C&HO^1Q!q_-}JnmFtrhwo33#eZ$ zIfwF%>4ASLxDi6p8S5uvL2Rra#uD&xxIKyQ;rH}~r8CAK>j$wUXp??08lN8hF8d0RL`M8gYVI=YfQFG{BET1N|342q~S^>EhDKQ{a}Af|p9Z$cg=| zpd`3T@#H}NF0O0LnP#0XdY*h`k~*1OI(a&jm8jF?JjL15GGM|y$LZoS$%3GdhCx9n z$tnJ#2lPE{XyB1o*iJ2>cFU;l8m+&uT_b>Pgn|?=4x-Aeq%|Ggtuq;WP z2@56DlV?C;DU`g^$fD7m1qCQQcnmJPQm=&>U^cx5wnIj;lD{*!HmD4*1X9k9 zU}sPf+?;FS*Md}5g_z3V@mvE&(c@fuEUe&H^sfslKwE;U#8&~QXFFJAlfZYl1umS2 zN%+=tzHL?TDJR@M#R^S%P;Rya<)O_%HS$*lF=!i@X0L`tl9|a@IRjq=o=JT;&c8g4 z*7xnEP>=(9&t|yL`#kbj^G}4gncK|?QjdewGYItd8##MF2sENi!A3BOa&VsrZ#7tr zBZ`WraE zUl#PE4Il=U^&f&i#0mXJ$oXVg+Q$b@PZ?aDq}B=Pr?~eNXfh`SKgPz+O8((vQ_3&x zKN2L24}M4pPjJS28*c(!8b~Gqr@sSu0RBdj_>eQ+SA+02mGj!E6Wltb{UrCjgu8yk ziN}wyRm3JJ=p8;3`f21(avJ<9u-($kR#4zP(t#C+l70c=(>RUjf$b58(tJxy0Zx)# z2~J^*lr%pE74Tg!Its#LxGVU#53!`Q0$$!c5oU;+~`EQO-yayuuFPtT82s*~B!1c~Lj&aF#7M%HC$PsuybBfSW_ zc5pWS1EQ~O&_}?<6?VMn4PzGMwmf}>%+@P$jYwDS@c6Klae?6Y9EU9Hc1)m$t3rdn} zZg4Lx_mS}4@Gf(+DQD}Ly70POla0Tey)S&w+-2?~^i)0-@#Sp=TNB)j`nCb7^`S+X_ugIM%*ow9WSR5ls9RdFcEWW|!3y|do zn<2P$Z9V&%sSBMlqevYI{}3F%LFP+P!Ukbg=*##(Vn&%d*v2}A4X_{LKgOrvivJk@ z3I0?3YiG3iijz8{u|@P%e46iX9sgT=j2VqP5!+?oI1{07o$=<|_;>N~{Nn`kD!7N$;nhtI^S0N_ zG=(?i`mtE)`dfS~^i6!6`6m7?d@Sxbt{rb`+0$6JtYvHC-tRRBvE+WPeH(<$SG^kM z6|bVLWM9Eo(LUg{0H5Rm^4t$1XC+(NzD%x4wx+FRUotOwl|in5iImFrL9Zn!B@dGS z0q?X|0+jvJV0)IZ4-x+$NQ$jYOY^YT6(o^|@jv99B3E(S8tZD`I*(v2sH=H|)Q7!d z_7w5O?2F{M+q(zL)pvOhgb#*ydG}(W`Y!K2Y*61tisGq(A()cp9&-;l?*<|AF7Ltc zDD+VHDEE8>w8hR?a=DX~hr&Cdhr@flhs@pPUhiS7A>XTO!C&lzt)j=s`6y_-!ZgA*65py+p?gI;0 z7=d?qcY)-02Y0=T4)YbPnp(I4+3jU4if;2B!)o(3uDTiwVxbt`&ULqh4t7RgG>&g@ zU2;mTnBSo1P28^z zesY{VG5;N}I=*+jTwC1=G5mS+cj%b8Ekawojif_=$pZRGk?9-rG_9L~hz0f`dzU76)^uy|2 zbNi9k0{R$K;iKRz-UxQ`(eNVjT!?M4C&9z)Z=V1gvp@ce><#3)DQwAgAA2pKPrP-U zqJGk>gPt-Q;OjYg{e*cE|BpQL0IuzC*Cy5_o-%8pr_IL154_JtQa2>lB-SRLHfs_m z%?@u3zLWTOfHpbZ2r*|mlm|ZsYUp%)ZSl7SrDZzQ9^T$`fOo(i*>vcbw~0G%OKeVw-o z+T|IiE3;YS^uj)$ae8CJ&p3Us-DjM>*xWPDmGtq(8HkNG<9vuTH_k3Ft&Q_R{6jFe zzU7}<+fTv&Z;f5WPrZ3&AlAv|Vb^D%T|(+gu7#ocy_16&l3J z%GUNXuMPCMcQNrx!7UTIzE0Keg6{(DGml)K!#~Gfz%o)V2GvX`{hjO=SPJN5^Kh?9 zT$#Au>u4iO0obDa(yQk6!=_&@@7E9B&s5`t>4n(wt4hj+raJMt-gTVlydHi%D5h0N zzsOX9`kNZ0R`)t!o$@RASNv;buRr$sDwC_fsYz-L?^@2&?uPFMH#H=trdP=ufVH|x zUS-_&b{V*8?QI8Kmc|@|{T<_kUPY|koo{4Y$b5?nuw;kH=dE_kwkK?A}7V_SX%kJFU z@wt@LJMgzbL!N`JsBN5u-tTRL4tQ_HWwY)rFp~${cjL3MIrT1i-ii0%A9|V|rkt1U zy%`^3huSy6ULIoKBhR~_A9Y#xuVgO06eeD`7+dUCq13ej^Pk0_U zg>!NDni5!Z*vqwhz+CKW=Y!7pD(|}>@d{WZv&q%hF2uh8tjCu@9=QU`c2B~eZ!&qjc+jbK&@NJGV@S;tGNn(6;}$& zw2K{=coqbcapWHhKJ3+ItJy)Ghrs#0JHE`^1uZw@$ukbb*Jr>j8I%~zRXfSK0|eP^ z=4x{^z8q_DN4a9TnUFZi8Tbk091q&+AaY(C-(|L$YstA2#Nngy73NOp68I(9^}8;9 zt+@_yfCHP;if3k=t5%ntlJ%udtA?}25^ zuJA4(4R^OaY-ezFd%}C#b8RPN?cZEtx`S#A#+vN_oew{s`cR!bxu8xD;GNt1 z2f%-5Pp$)?#BS%lHT?dd)7BuhI=IE{{ey{i(4j>v zc##@fE|$@JjGo;qPDm9Q`P#8tw6pb=LIFHBqn9|<~gm2g^OWTHV>CAxQ-b+VFa~W%(Cb<+?e3OB~yE;HuZb+FWhFc38)+3$F`0 zHGV>6!kgkZ$IFnjEcWh%S&j8O+?t`#p=%OX-!Dy`GT6Io03vh^Z00raGl?mUCAS;F zhOQnq1RYxT@EZC>iOIy0*bSgUXTghNL+o(;hInpRJ#6IXLXG`m#AIRVE;nrKSA&}P z#lu73Bo`;X7`En`fU#Va^d|nNiK<~!cvFy;yLHZM@wKq@*2OCkc7{rZod}7S#2Q^4?|QS{)FDr8uP**NScofv&AX0XDJWj!!7X5 z*rh0h?Y~XL1#sCDypotL*rF&H7790F6U2x6*buymm@BalQ2=X>8?Ynn!9DB=ZYAa_ ztSPkd^5A)dX5ruJt@mP~8?N`_SRP#OZNQyP{48%a_TpN@TN7I6xmdMaM_xBv>)Fu2 z*Wu0~&uniF_SITp4Y?)0x!6=|iA`4%{uJ4oHQ_vB=6dt6sn!Dft3M@vj%>dEl$cM< zJgk-ejJ?mxN%=XkfEZaTZic(s`vsezt4aSQu@F0F&Af%s0&IK!iVe|Kr2iUO`uuxh z5vj6J+yr;3=Y&6EIr?nE38&$o>P_)v#dHcOKVqf&Y-CmXx5U}RWKUL4CzJj|Vg|NJ ze}n%3vbej7u;A6bMC6Z1budkPM`g;A~vZ$SOn(zgaj;v@Wor|!Copkzp1K^?4 z7`_O5&q-&ow*G1gs^&N7}lNxmlVj)Pum*C5k*opTMD&KvIQZl>d)LF&ZLqJ4VSoq#{n8R9EEF*X5| zoxxaYNyrfb|xm~k*6#?pinpkifcEK8VCE+Iy| zgp-{5&4gzX*0(7NFG|?qUlrDT$4390Lcs zy|v!e$JJZwEdyM=uijdyQJVXd;9d14^wxUUB(C0CZ<&Ux_tjhLdlbT_x77F0`|7Rr zB?{xyyXt%Bt@SSY5?yc|^z>EJIz!l8jozsfF`YTjpttD=b>bY5-lGH5krP9DoAyu# zP8E6h+C}fw7T%5%M|!6`sIAimzs@4*&00rq(;7c^KBISPMNDhX1?inyMsL#+Un|b} z6d>F@dZ*_2TX42W@6;@Mn`Zc$qr;v~xJmR*P5AzW@uw5p7=IIV>QyHjMYXXJzQ$zBk|g4kO4 zv1d#fl!B`^*2Gr}P4F`Ks#6AK;Hs0=@zrp0@mEKuz8t=4ltejr4sKO=HKz)^D!e>y zWq1{M1>8#T%J7P~o1*gCM44^ml$Rkqi<5{O;2W?lxg{#cEyQo;e3vCWlkH&csg`^;gs&vmWN1oMhpywSV1gXi!*`*VynHAHDu-qBdw>`w~Mwf6Iv3rTxgWmE|!V{p0oL^Es+z0J-_T%5@9Dwgfds!Nzg^%;L97TAz~;a>@{fm0UvwO_h;wIZoi{*-InP!Q-yAq6+ptqO z4=!!bvCsne0|D&NX*xFQ^9u?L6QTRrqHC>qSh^Q5eh-&@_ zVn$+}QPOxgGy)CHOngJ5`ad+P|3irxh8Cx4{t##=+M25WgP|ellNQHUIcf!!@ejgZ zg;3R~6;#Dng*sc3a4x(WI;uT6Z!!=%4}KoG2SS6W?$ zp$0^!qtJCFPHjqOEYzlI!)u{|dk*>fbAqTFyc?l9QCq7+YHiwO8NwHlitR{bRu^~| zLiM87SC7=XwC1veFC_IMct@n!g;3|HW$JVeSYSwka`^g@dLg_$lC2-qF>0kcqmxaJ zzDT$B@b;uNrj=&Hvq@`$zcJ?|+LGP}>Wj>4i?3S?=BhUJsHyldlR-A#D%G^b|Eg5ef2ov!rfP2BYp*v_`*mUUKB}8)%XPURbz;L(1o-U$y&9RfSSr& zg4QJotv2SOy~jE**gchaxVOQ zTqkM;PSh?;Bqt4$b1Z$IWUoO!kB3jhHOT*o@X5G_`%Z>C(fuv;%z@^>=OCR6zzgEn zxXOWg^GoCX9o$~j3xlj34IhJlG|%cn<@k-_nO)qn@UqmQ)$q%y!TKKyxzvXy)QFR1C_Z>?N6sL&Ye2$(|BWamu~}zLM0@4wQX+e5E2uQ!0{1rSX@d z?AuZo%Ft5t;F3OIkKrpz%WcDxwZ@kX*N9M3BuCN%E-6wTo&(nj?F#Vn@RagmU zs}8AWNW)i?I+g}cBV3DGnuI3_*QV}<@Q`pF>T3d?AY7N48o&d>^{A;n+$UV0dg;ME z!VUQDF?fu)29RXDi%+uBg}a0sQ$~`XmT(bD%D@fb|LXEmzfqd<(g1gj@qMIrN%WQiBUhKk-J7XrRkY8Djxxj zq>Z*CMswXV^j`Cc9UhI`L351SuSOBWh#8L5?m#OZO3yM6K9AUP#FdT4ALZyBHM$=H z4W*5DA}u=_r3@y1NHliIre~c^Xb{AyD&n%EQBDs1?krLULY%US#zN&u$)PvvMtA_J z1Ca^mL^51`Xn#g5v*5ExQ*T;Zh7+k!A7uY|QIDX0xpLGmSC0DSD&*-+Z_ta_Dp4O=l`+p$ z`UIVBtqQ59m=g678*y_X^%26%sSf2bo6_v|Fs}FpVh<8?hlg)Gj>Pkb(deo!bK2F!)}znL z@2z$cb1gGo&6Rh+cfvJ8u1_Bqzyoq?1*kqVXU&y0f8K#a42jWrt^qUcONreU&62m_ z-;T`Gn5`ky02!Tz?`lTEE8#22*NC`=^t%P{Z6*F{=Kq>QUj=QY-_tC!G1Q3F0nMea zgsx)Dq8Voss4=~JI=(H8y_dt6lcOnd!W7UN%w|UE%izmMYZi?Vn$e?XL}TM-tX5o1 zS{9*ZaE*~;e4V(Hovpc!OC72RFAt?wJX~tF!Wv<^v;l=R{?u4YVU4%SQH~m!YHdy{ zb(jr_zPE|Kvx&YW8YZ~tn&6t~`rE#|A3#Djr8h>jZQIeLcF?UC( z6Kzf7^{%89k6NV0X{Dp~uCcgUeVM3L7DE=4C9L^HS?YH;uBr-UQNOE3T<@P7eFM#U zic)tqf6#0wliI0ora4p*>Y~1@=2jWhKb1qRs0=i#Dop(=#2aaDRfsQH8~=D@p~k+F ziQ^*)I1a8caUQP5!>!w`qcMz$j@Q4 z$Km)i_ZbG)EMg53cm#YnX=@_ct69=eWP;`%8}JRG1&$<5GpWIF%}*|mXD+z52s7N777CT=OW+1jYLy|2QF!t65=RB!*@KmbS7S zu34z1wOs<&%+u0pFNJG{X=&-J;5z$ix#n_Oish<{;meRq7N5gi`@%JA%%7diqqlJA zbLPPp;5zhB3*ef2JM?&q;F?i8(OlZ$E=%$ELFPK#s}J=;a~Sm4_{!+CA&u(7>){uo zhx+Sw{4}GtxNYHWd8g6vF?`1%)We~WR)q%R4vWG%bDUaT8pbyph`&t~?oX%)->X0T zLfj&JrwieIaaFICF9XVhYb=}rwS#MnoB?%!Yxa`?b%JY#lmT^tYh@<`>ITU+}hYRx}6Y2%;#T#crec*k_rB8)d>ZgR2W=!L#_H^>Cf2);dw0cA`4%P~UrUWovjNxK_2Qk>b$mdPMC~SU@d# zZneS;+!k=HcW2;})YR&B2EGzp=TJMeQp|a0B#ESMIqFvqaVsFz98NaFC3&=#DK1%b z33(*hHN#$sJS`6|Pk00}wgS8Y;gONV9ZAdx>S86rqmZ_mBD^rJPn(?u zpG8_BVkg1VaRb`*O!!RF3KBaRUI;fq+n)iSL0SP~r@#y1hDe6#@ad$b5jz!L05?gz z=BsJMB%x{iYX;9)9Nw6pb|bVu(KM=mmNsCihpLg5R-v%!sHL4KtXgYnISQ*DTiTMs z10&xc_&{2qrR5pYHHJ}3F;Pn~QA<%jrd=Ji6m(c=B_?VqTKVXXUvaMH`*suq;SRWDqI+EEI(WYnTd;?rDKX(gi8 zt@Vqx)K~S<*_2QWuD&|8ZjysPo7(A7S1Z8FQzJcmmAJYc?X*(FB_FhBSdn&H8-J}x zR%orb1Fg9OZzY@_G*ofXV#PJIpImrxt|~??)H?1wsBu&$8$~s;F_+O|(vBSy9S0G_~I0S|D)sD*26vx2&(QJzLP zm(UhfpPi`oI#FG9qMGSMb=X0|RVGzyKaxqU;jM{t_)qP{twb7V47m~+r}mNsX-#Yd z@h|6s=X`$x+B=wc;WW)_9^eu5rw0TE#eG zGyZo=PybWf&)`2RQ+Ap;7^o^-cvKq2X`Mz-s8O7xjGjtkIZ2sSxwP&u~a?Mlq zkCHH2AJQ&)YL`CFziV$^d*j+6*9w!K$mct1Z(gfU`LX$X>dKeD*RCD*)V=d};&pfZ zpLXZ<_Ieua+UpCYp6~Z(*Hi21^*(wl?cYkemVuWcY@-%ti80(K)xt^<8>3y6gsYv! zsWBzsB?zmQtF9L(oWIkY+GSUt6+qf$S1%?#0PV7?*OV@Tv=G!YCn4?qONOOE+GUp< zEdXhkJsn>bc{1Qdaf{)T{LR8GjxQZ9>0BcE-WnyR^OX7y8c!GEee@mFmlWi!RBnKp4xs>Pp?0Hw&PQfQib#gUkrR?L z>h0o4kc#*#K`u2)a!&o6OTCf|RbOKH3Wjf<8PzxWl%f*T{6Hn7(otEIfvbevsB|O; zRU#^#7^D(W>BJ$Gh)TzUR3a)JwR-7fNDm-i??I)LfKqxPzw2bEbW(aDDvKg~8A}XCQDv2N}okUa;KD-=np^}g+&&E}G#G}$txs=DR@<^47xJpDN zVWToq>FB$wbZk@-vh*Z5pmI?uq(@vj9hRpk2iFWxJy2@(U1gy%ia{z1^-*z1WuY?i zAeDv6$cI!GDx&~W>rffx>!7HN(7z@u9UbY%q%>pHg3=(Bh03S^q_R*M6@;XHqB1H3 zX+J@=NV@>4ReEw0J-NZJG(EZAMQ@=e*SqK~^yGRMy@j4!@1nQRlj~jd7J72Mi{2uo zO`;m6x}>L84U>M4o?10bbxBXH8m79Wr&bM9UD8vlhN&*;sa3=D76tjKJ*t)@iBajR z_Jq8L+M{Y!f_!R^YX8!BQt9W*Rh7Q#rN=+1+%?Nh=>%z4L@NMUyrG2`#Vv-@`q2CWBa&efmL1-QN8S~!nn#_A=2WMm`PC`rKw5>%W4_dy8B892t*zuSS80b|tAp*Bt!cMF ztBxHReRm+fC7}+{=)6lbi|7K%sAe3eqZ!BPXqIuB6vbYRza#c zCrFtKE^8xlFDG7WU2}1@c2W(lb0?t*{>h5qdRroDqodTPr|s!ZkM3K6ib%W_cB$H{exCslZ*U zvPyT1D=!BX`WWkoLWjNrx}3GfM+mKfu3%O25qxVwR(^z4%ZKr;hp%HT@?m@%;Ts~o zvVHIa>_zNlHU0qm1iPc%1MM4TRvm6MkK!3wJGR`r8O?hjzk+$-W(u2A)vY zx3eQ~4P1K%M|s{i>8T!~&(cihA^1jC-2?u8BV4%8NjS&432mZBeTZ-xh|Uku6AC-t zgSNnZLIsG|8pi{;nl){qFBArJK}b5#abjZ7mGqbQkx~fKeCH~j#wAvohB4f9Qq{-a z19EsebRYfhJ@^WP<$h1Jx8pEU)c8G{p1M3cIvVF4ge+WRr-RUT(Bievb5pd#b2BbT z=%m~U{=0*F8({~2GwyAKkHBvsbenT4?rq?$-wr>5o5}wchHE^4?bv9%P=Rlk3Ec%3 zlDtMHMHqW&7E+pVT3NWpwwn87!?OveW(%R72xddsY;90n*Xo20~T6O76 z=~RSQq}6ufZOg-@Ytadk6v)BXfjj5Ga|pNR|FYrPgxldy?L1;Zj;ASy9MOKHGzTP6 zG;VAI&x32M*aj+%)F~Os9*r1VMPo(nlS<>ZIN=sNVKKPIjoM??3S<_(X3@w>J2YB{ z)M%DsDZX(vhYQ8i8Tjw-Zx)jh3%R{pEJ{wlA(+Sh;E_N7^KN)o1I zW4=6;Buq)gKT5)sY?MxjG(#j6|D!w{9!WxtAd4|tlswd^u_fcqV#JM#q~$35BN=aI z5pF@c_D;1w)*>27wunZOV@MU&b5=CE)hu-!l5;H5RJ&x&$*=uY?VdG<1~V2eN)D}! zYF$-psFJx8khKHI(Tq{(0LHTY@l7OU0@C*){7o6%Uc^{i{nsQ&8Z{aCnh>wOS?#tp zfi7gcuAXiRG?`I(VSJ5A)o!hJA*8q5ml3@B<7v=T#_s9(8j-4}_endS; zsyF#R?MJlspp}m#u1hbLgeM8xs9&?hXlAIsOganFQ%I2J5F?$2e|D{M{`n4oyGB<9 zaNR3^{lwwlwDzpka?L)qX0CM}ooLgVxYnt)Zmx4=snv3=`{;kQTAoh5Nv-E-1x0J& zsnzlfo?D~L5Yifp-Yyoso!&Ig9YezZ_=JCayZq<;=kKU~KmYsu`OD;AtFupqcn_WZ z(ps|Ck##OgXQZ@Rsa4GUlT)4etXP%3-ca93 zbwV{GRaf-=R0euxt;y>v>k0KQDgixb{)(2KP;FDCr7~0LY1cu|sWF&JSkI}}r=18r zp~n5H2dWLK9jYZ72j#C*YCT-#tNnr0o)et>RYGqANqqj&s zlg>w`o+EW`GW8rfRjF^Hvz4jm0MUg|YTaF2Pm)?QQ4X!{rJf}9RNBK(8T{k({P9Ur z^;u7-@1p%*?FIe$dH&cg^kq_CMBhSRB=wA`|JM^KRw0cZ<>o(Ue*Mp{`Ml|JdTx z*3|BFep0Pbt?wV(-Je@r2IZl4_{VmaI_aqvC^@DQ(`ik$RkcyIRm}laKh>J`rm8b) z?Wr~D%;>+Rr>}Y?c_2M~)qg#;W_+rRI;kqjqMd})c~!|8o!OM^$=^vy?RH5rNkWyT zbhM_Pl3uBLu3ZAHYv;E()o|Tk^<3wMQ*!t}wmz+Er&|7>+nwI@&$V6k;?FJa&-Fb2 zIZ`_o`SKuD=hYr1k&`@;q?Kaz#G2*nef6e#J4slbB-XiA?cqr(2e@T<{s0~j)|^wj zdww*R)qJfSl-jdQI?@w}!{fx}@DDL~jBt7U(hzX)RfKEp#=)oE>`Khuv}4?g?^J{_ zo}^K0sFl+u`ZjHd(ag6Msdro5NZ##V_sgHPzR_z^L1$@bc8xEkC#?LC#WN{NNFW>hB`6tmu^BAs54`f>e1?* z^c1w0lm*ugQySx!dT{9jq(K`0X!T5*oQ>epUPyzQz@?>-1~r3A8zBwS>2b}c|9!0w zX_8z(evR@{x?zSdS(Tsm-tu?dQ<@aHjJdioqweZtXa9SBn))%Fo0nu&?^YmcVOl>* zqr~Hc1GqKiqph()zcbukI)Zj!@#!z49EJxF$TB5G@Di6yySDYR~U`NRl|JNs<%lLDhrUs6MIJS8GwtknVwY?zKOh>NWIK z+Sga_DoLX!E{SX5>dW+;+R@j3m7Y*L`r5B5j_=>w#ZT?u>-i;*Q+s>=xT}}i&(j;_ z?@DTCPm-_@-z@)Y>bq)8l4{-RHzXs}#?@=5`VqDDloo^9u**Fh!g?>=O=BFjUP(}g zFlY|=RI2K=wWls^IgOq4J+*r$DeB;pZcYkQK;K2>CQUQxJ4kA1&t3bXTJKVwEY8(( zQ*!c;evhYCdFrdHPN~08TT(64fBv&kx85>;ysi4IZ>g`LubPs(8Ug8B>l^>$xJ!B< z8jbyV+@*1tMqKG|jW;BN_3bnc`+dZfsx_)Fs>y#I14zpL<1_2pKR&I>AvMnb^R@rZ zoBn?7KOeXJ>#=wK|LPxqpWWzv|Mj)1sp=uMtNZ(IwZ3`&*G}oH=$mVdr|&Ebh0N${ zt43>ASEa1h8H4oA)d#A*{_&fq+N-`^eoNIiSG&v~;pF$W|M~d#kK@TdjwJt`@vX)i zs*!48s<)}}q&Q_y1#$|Hr4&i2vW~_w~Uqm7XhDZ~%8 zIN@OEtU@mFP2o+Lzvto;R)$veRWfCxTA^|&OAlI&)aG#YrP4JkLk&%hVahTNs7h>0 zdc>;ms)S2N?Xh%J+e?$P3}cHbq)B6~6;e#CO#M*l=-ZZJ^r6v-bT_2SAq|c;j9Mzg zE0d-^K$=6+^~hsPQwd&)w6^&3BFU$oLj8m!b#X=?+D&K&wPl=90iUF)gH0cz5O4h$M5~TWXQkMc2eVHwWa*_p*PT3m4Dst zREjA%FAN~bfm8{qOm)2^l3FdJQ7sEThhu?yM;oc9bKKhsX)tVN1FDZv})KMo$KZ zaP0}}^juwd9l~Yt2?L@NzA}uZJHd5Ur!-vqbwUIv1=l{D@B&K0wKJzvawSKPb{r$Rb7>N9yjE}vLm8|BYrQr-TCYtfzA$xfFrh+G zY#~QyTnfT9XB>)KkhSNb$gW}d3b0B&46gHtX{=65dv^rkBx}?o;Ufu$tVoZ7k0P94 zU3xTJr+X6k)ayz&BY@Q3N>jsUoq0Tb9I-l`If31Goz`3oU&7w}M10Z!(JuWYxW_*J zQn>W(J$w_`p`S#WG)A;nKN%ip_y1zJa2w*0{y;p^F^CiEvHm-me9|q^j{X#QEYd-U zMLGyEa>iMkoFU2SvIn zhCO}tS2~Mh*ulS?R(SIyoef$*dls5PnW&WJ6Sn}FmPbt~ zO^n*Q%55HT^J(E%MBiSeHWQ&NA*a$@3WDabC8v-@Ck8a z9ef>mW)U|ViP;jLP&wAa*OMmg{#n$Y7WjnRu>rmbw-~{cDad3yq3R z@J-~UL9NCc~#7VVmO1M0;Wjd zGLkM=;Z7iKB9gZ;z6>-kR5!QcjwfycdLmm1YyCiHX|BdUj?j3tN3JG37XLVE(l-1W zS&c>4VjJNxgvL^5x8v73#26&$_DBMCjkqN1Xry<2czsd}AYE0jC1pn;q3glxkyZ!) zDC+1rQJt6c)vAdklcaAFN{b}0<^z(xA(TXdX+1^jC?jYSlEeupM8?%5CLl&FMY1`F zB(cVil7ltiL*c_{B^Qw9M-p12#i7W}>Tr)3wIE4!VVv|vwpNcMtj3Uo=%WTBuXFJY zfDfdP%f%Nbr&^Y@)8a_wzDV+F#K-Wfy-DXRhAh93mZ!0!3-yOz6tzWZqgmoLlE^>H zU}@nRE2dUiM)0;H`PJcDWoK(7r@Sty%9YYc&`2Vst1g`d{f{&l)K8~0*`?W_cCWr! zyHy&Sr?er|2YY;jl!k<4NJ@J`eQgl+wbH1N{7GqBsNW5FmXrpDMq1iW)7n%WxHPS# zt06fiJr3z~)T2&FvqKsm_2Jt2lg@`$2^!)nOzmq3*PfzIMrrj`r=z4nB0UoASxVDH z@;0S!qCL(mT8Y-iG-i>miZBACrJ~(g>8wawE`<{yJOHh}Y78W87wO_?ER;IyuhF;G zCsVpIdBmm=Q?!RHtQ3uH%Hk`74ARNna>%asNGnM&>ElQ%N8=gE#g35#mF|w@q;z+* z8ky4W(J17v^7^a1{%T);wXeVAp)?);l867(`Y)|AJM{hzZfd1iD@R(rRIFC6wEm*7 zR;;v^s&EQ7O{1F>7Kio+9AZ=FH?_`X=p{9d(YlqP&(!QjTCgVSU3D5N8-Hr8Keg^J z>3#UWK9@>?Vj!|)Hu+Tm_L&65p4uxh-bRaLpom6C*7xjkqThZVnel$0U3$;F`neJaBVn2%6{UOm9nO1wsK4 zT1acS=1Drc+lrZh=2y~3Ys2VYs3AIyFRuBRa4>YjSt}PhCoeADG@)VWoW1nTbWXlM zTzYG>iP5=yt#0US`~bLCLv(&#Tv~8K{t=fhoKQQ4Fq7H{7xIs|PM`}5L|o_4g$W`Q z5Fv#K2}GD5!V3{L$Oz_sLJG0`=N!0j288k_)PWQZf$*Fxv=FXy*%n$17n*^kJ_skX zFINj8Q|IziC-tQxx0KKlX1^An%YTf53$Me4mceyG+l5xZg}mTGE8#-0)e42yB6KD} zh?A?~I#J+4SHOi_A`A`#wTHWWYvFMSfkT)GZSm{mOKN>x&*?&%C8SmtwZbh;Y>k;4 zL0XB^n7JXO^*D{38$i;**2uX&q%}B=pX)(diED+gE;XSQZK5^4I@EyHw3RmaYE$}c zXis_gYVkCAv_Gvo*W@YN(lXoOtHG1EqXo9dSDl*Qp7z!OUoLH-1Ff$kzG~6fomS4o}w~bI@pG{s)S$j9tXE#^xl#hI+0-sm*@R0+!B^*(1d_=13AYWy#w6g!K zUay*Ssm+B}+7F4BE#s~BDqDg46&=~KF6w+h%!k+>zS?fJ)t#005_m4|=h({DE?iOC z(fekbz1qG{o)3&#@Flhew8DOYE%Ktyd!)W^-ZR_nHe1tKVVA>e;A(eoxz&o!a;yG! zxqaJQW4FV%+xJXe!pm%3B*k+3j+tk#fnP&fJ!hG{*h=0kv+tVub{>2lY4x3@c8RU; zTx^%Z>*2m-7TEdl`Q&&L|6A~dc7Z(uf76^Xi|j)C2K zT6<;ekrsEVShe;l#1(VOlcxf9YqOAYRjqn{*|p7ba;)|ra!4(Y4O_{^YF4Lus*$&& zlWnznnN6M?Y*|*bNKU9NJQueHRxy#Q5Rw*~nc{g!;H8no)>?Z@dL2n}t*MJk!Y?6p zDO@sqF;}#KwU(o~DfJGEh}T+dZ7irRgljdw4whJTwyzm|n0k{5 zP8n3$sn~?RQ9H_`p=@|ISAw&QWmN4M6tkm99nH9;kS%DZbGK=%7iVFobUwMV zEIRGjyGOsBG>sC9T5z6iIy{}&xr8&V#t=pAEaElJ$*_g3#ul0IOk2dxCPw3&Igb3Y z^Z5#O>QyYOuH@NXF~R|R#b_=36{FpVSBzG@wATF!c2rlxwF~hw)=FN+8g6HMIsVR8 zYulZP>4Jr?E?8ad3Y|8ctX8-?k=hw6U|q4B+YLHpI$EuCcOGM&ee+Rz0mOdiEs!Y17u~G+$e* zvxjX-ZHN6b**!fM`(`Ii9;t1u&H?6OvrN`i&m;XA(}uV_ERmgOpEWvF*v4*#THEK$ z`NUj6%5!Fu(;EAjI(gXIK2O|pSc&b0B|Dv3Yz1$Hea{z&dERJD*wSu*TG$tfc>%k$ zy|Ig@QDO_YY@t3u%!^oSt%ps$PK+3v!)00Z1Tjxw(X~EynNOGo*mu^*qZzyzc3O`U za{^nj4Y3y8#gP?QjYXQ;$4w)wOFvHhaibl@Cblco*d8PPaii7m#re1ZQf^CkRi^OgCV`5NChxLE!%-@v~!-@?B)-@$({-@|`2KfoX5 zPLE;3_Z)mbnIDOH82=;YXF{9~v4Kt4iBJfifIHs$#Epk0*h$1D;S+JkS&x))(0DtU z*fe;WEdZZHXsnHsJ{B5hrw|*1PsW{!8-vHJYsc8zO&lI4-!$S}JKEl1Za1TeA7e+^ zBjye>ikQ)MI%yU@4R;2vgbqk)668zu`|hK>~La6*n2p8 zdDh$o-OWkSdvK33z!jfGzN5}e@*jeZT*IPUm}`u-UM|%KLrU{oQl#+>vMI$~osAyV?Gk-ns{56S#gNyS1x@oywlr z%kUySDLXOyFu(N?Ja<3N9_P0u?D`CRJiQ(7-u<&x*FML;Vt{G^cKzmnVNX_Yhu{-JPstpV7OMRoO~*Uth)j z<5Km$)7d3^S#mRX=`Z|b`b7E^&-+(;PqH7o%-+M@`(+!FPqIh#2F~7`%wXT_Wyx6X z9hct6uiT4|?B3a4*-czy{89EzPoKui_h0ObJ%cMBOIENO?qhh-uE_4^%KPxVUBV8d zH*%$Z#!s=^`i;rc=~L{WJ(KGn<&Ndqr|}~GSNZ@~-j9#&KG~A&5zZ_JF3*-_4^s00 zUc39UgYgaAtJkvoUO$X~?y~G*($ef9&OV6G?!$@YrR-q*89bK%m0r)4`Z(`I{#lOy z3H%KCb<|vsC-y(nf25zo3;UnxGs!>FzXLx<{%rDhX3Mk5-74X-(l)@`$Zw_QHsDkl#sZS#nES%T>3KZcT5dd<(FS{4UPp zrNy4`OW8|z6!|{vPCp7bhI}7N`?62&QtFqHMzDkM7;2YuGy*uB-PxB@8lK+Gla?hL zc;?ONhO|HVhI9b=hP0l1LpqRr1=kK^5BU{29LDbND>)JlO^2kb$c01F!Rh|w!olgF z^Z@SN0Ng(>58|jbYfg1*S_x?Jcrb7*@70?1^;qEU?8w`i{f~DC?#VvKt=a#0PvG9{ zh0Klu?1fA;cD|%F>+b!zSNnql`GpPXLFs|OgUL6rWBkFudE^_|VYYR$8+*v^%I>^p z@bq1Qr<0#X{psm?j&@-;=GMt+>6sku0^B8CoSsEm1U!@c6waQ?4#~=>PNsZHdN${F z2A)NJ4yB!dXOo}AH7B$C=Z@^={yu7V1fD~FVyaB*M9!YXUY`ruk^NlGEM(VRrCjSc zdm{VoD&<;B%{q1hJ(p{gbgc!hWzXH6i68M*dIy}Q4W`*~kWUP?}2pIt4N zPe>PW-B)rg=U0=PXoC&x3Ob+sCU(4@4_rWg6Z^d{0PaA36Th|t@I3OH*dg;g;0MWX zVn@vnri*#jmyr`KBEONEo7ideQ1V@<{ZcMf`f_puH8-+n=wal$Qu{?DOuLY)O*|fC zdptX$?MCeva?R-%lk2(i26j|Doc!MOo^&Y^rY{f)L)(@wu=ne|)Lh5e>)9!FHTnJN zebih_+5J`5kf%KRIN-7AF~H-}W7((m2+mwXx;9M`_kv9l_jV;J9cPG2mmUc`Iz0+_ zOnNjhB~OwgxaUgptI|&V&eEhKuv6NReHZUfJFqw71HcD3?o92{q&+nq()Q^?Z0odd z+9%y3>6`9O+xDfjd(x8nR%yTV^Tgrk$NA4E{~&)Uxq=qBGJP%iO>#l{YtnC$-zKk- z|0+NJUGiw!GW{KO7XUBd8NbZW{W7_bomPLJ{Ep}Tp41}!1vS4+evw?nj>CUQexI}e zHcy)YTcpj?pC=cybMenP`-|j{$sdwt>3@?8OKApdmX^|=am~+@pCy;DSMr~d|4y>> zr<8w|{4}|g9hU#haSHqs`K#3YG;JDh1t(nIIF9JM29!}C3k+H>9afE~!&bKH)nJ`ZJip4cLKNWDO*n(u!B z`gASWVW-^EVrgYLX-J;{!RW zfzLPq&gpUZq#F2)kIOHmtKd>Tk?s%w^a;*>9A4(}vh3;KS*{kUfZXO|}*hTC)Blw;umbMNBpQ|x=c0=UBKxJG-rq14pqdb8>g!?yMd3Ocw6JdO?}Ia8LLmrSZbO z;CXh2pLqtHzX(2PXVQ{P+50o;D{#Fv@cKJZb~W$}D~KJFXIW+Jm^{ZCWXI%r_>}La z--9>#XAZxYejhINyBz&1{SNuxIer=V5Ay$^=3l^XlK+jmmqDxFu zW#G%{57LwxCLZg)Z&3b5`fXMSf2IB}q#vdk^(j2~*VF$>OO!MC_^(rH#_H(n@bX_v zo59Vyf;x@W+LxihuG&r~odykdWp@VYbZD{bu~Vu2GL+Yq!YS!j$xor~E7W|2qxD>W z2GG^w$*F6NlR48OJ1KQNauRhdvol$FejfV$d9FK@_0E4oZT?8o>@-d{J z!$JI-+7pnx{Tga{3^m7+egW6;D{7BNUiT}g^s&?&M_G#f3-X1@3%nP5U%|yJOx)L; zy|3h87=teWU*x^tPkt_3!@|U!%GF%eW;-P3rL~#+ZP&5h-65%?MoEl2cK6F_$@{ZP z#)gHnb=d&Q{ekMT`f}9=)4rth(|T$KWcAq$^;*b!&PP^;WihfaWl+750iB=rCS8yY zqGlj+F*OUlvJ0T-y^tSWkPfD15OOhPQ#~^=dC$!K=6fPhx-uO?{b1x`Y8-kXT@v5- z01l;Q2+}cSU)_-weJCA9d1!W7+70>7WodV6wnauZESHxJ%Pvj3X5E0@IHyEy#J^=~ zmryU&>XLQMC2=FNi_^}?e=erxl5{?jwvkBg&|G8}rJa!WT*TRn)9J|2suHIrY4vSY*;Q!=WIk7M&4npGd90vwue|JP>aT+LX^*@}9bOw? z8)Q(|P;)i>PCKMb>ipVf*CHRqA)*hFu*jxZR!^y8OnVr zI6o-aiTWLpUa6U#ndM#>oF9zbM{Bzo$ccs|J0p$l4(!g=)3X`b(4=$e-n2`pYpDx) zCsOB9H;(R2JLbpTIl4FPkRSIbbtgX;sjkvbb-`-#x+1shihNPsUN>Mjo_;oIQFd0c z2VP_8CD0N2@rUu?@Y zZBq9=8HQZYoi2}|tbTMl?|&>3s_958rz6L#;=TvqG#`NDZO6TBfjvt-O6&Q}U9$D0 zU0Hd%i^~0^;Xrlf$05m@hFo(RPjMYT0?xT-sU4hhuTsxaYo7HG{Am^W2l@36u(yhP zsoYB%iJWtNvMX}UU6BtT&vVrHPDVa9@x9ot8@={jzV^D zFZuaA^Mh!HCm}aGfqRcfHgOMU?72GJ z^(}Sgu1@LcTz>}A)1!EzmgHlQ>yAOTd>Zvizb7E^({6Yya4gcoJ9x@?WI%V4ci}mm zQ{sek^{L5tq=ly>Cnw{8Vh2T4(`33bRBDtw$xmV-1{gb zuSX%Ly^S;1rEN-WOI?9oS&>|VMEyu4uSaslrO6tOE+t)()Rfwkx}`Ow?npt^(qG1$ zT@75r71gDhQunl))Fb^6^_L}8rRq|Tw2Jhnq;=^}@ZPOURphNotxJCf{uw^JW$7>Q z;Vnz8$Xk?Jmi`L-D?It%vwy&c{|)%}>~GoM;m7}x{S$8dAKBl@o0nRY{sx45&ze*E zd-BihUvTUH%>F_Cuk4>0oI455J%e!v{);>*{SQlppCvzMZSgZwGu8?}V}(3ni8vrpRz{zB`WR|n6X0nB@fG30VSnhCcjEpT$g?g{8jSnBrBz*-z23{ z2F$2^EooLNm0qL9b<P^|0(+eE2=+be`&Prfu!V**?(s_WEKC1?2nny$d$j(j8pmh><{F>%ZyO@ zyX^Pmzs-yx_uK4u>I3OenR<`?A7dBtWjRgULk*t`k!R4W&ec~;b`4p)O@M-erlV4@O z%%10(=U5N@I{Q`j0yWPguY8JYUQB+I{W^P*`WKQc=bD$2A7wwzjO_U%;14sSf&MW25qSr$H3qR!2Y-+mG4u!756NH7 zzJ$Ewvz!$R@GG(YYA<-m~BX`}HzLdR)9QY;DN0M)G_J!Cvwd})C?{Sq&%pUBwx$EnkC8C zv#$aFEBiX|tK9jG?7t{|Gy4Yc`Rtp(vFX}uT{b2in+n$q@nykw{-p&PI|>$tF-U9!Y-xQe9~TlGszS5u{VIiPTI$ zFEF6gzcdLr5q&{@X+UXsdMf(m;mBrB&4wYLJq>soTIR`|orL~iV5z<|CA|ab?-a_D zfp?M*O;69x$c7@HJv|$ORQ8N)D)Qtz&;i`R73--xBO8o_c6~Mtx%2Hv^Ka+ebjs7x zGdZ&!?f0N`aC#Q-O!VXf(?RLkz_ZY$*QW#1bFu+xJ+PkI_htRl0qOgwIR~wNe@f?O zb!q?f{lIgv2&hf#(({1t$G)InTAO|Vcpf$geUUv~1^fVZ1bvV{T?y3gpf{4LD}dS^ z^hBn0Mb-;x*5%nuBwm+Oa|N~zGbw#2n}O{AvTQmUgUcv?2-}G1lrGI~<4Z2dZslt( zp?qm}adu03YkDy?mr%Z%QFRgU;_RYKt>T5ii?Rzd^@kS#FU&5;)E4fMKA1g}?Frl? z-7|e4dobHQ-6MSn_)zw6wih*frhBFLXAfk%rMssO10T*F$@ZpZuXOM9zU=;N*L1h^ z5#S@)quCN__D+|i_h$EHyQI6Oj{+af9?SMg@5$~3-pdt>(_PZXvc;qiXZxmiXZHZ_ z;oMTn`vULE?#>paAI?4kTui z7b}4)k?225&2!na+4jhaXHmBbi;7w4?A+>NR{Bh~07>#QoP9RCF`JDR<3_A5W~ZN{ z{+aA^*>*~sIkQdr*=#=Y=g(5}x$NWF^USr+Wb=?qe}?+cW_ZnELy{#oXB&XGWH$qE z&29nSmfZ@xJ-ZEfM|L~#>g`CCKvQGk^%087< z0rlQ}I(v%pr?aQCQnDet37C;LOK#%bwCK7iYt30b;y#moI%@^g<7Xc4r_Ind$mq90 zchiy@?YZV6SJ#SY4sZ^7oEFKpXlYtd-;(E6^EDsLs+Okcq^RQJ@Dl1OYQTu!9A4vmGn0*tX{Vy+LCW%3<$kov_LaXMnqIA$5QjFj3N;c z)!ctpX}vap{^DEz-QpLGeP0>F?e)K#@Vow+{qS!7?tkuk{bj$}*4EN6_MIs91JOP! z_Mp(y%6JIcXEkGOrDv5sS9)4)>|#$I2MD`rK<_*_e-2 z8&(kGkUbkcw=tgrX;t>F($mV=EKTvTQmRw-v@*_>@|@UtweYc0 zR#W!0(z{A2P2po@1mcZ-K*GB!Vs_5M8p_zl+I%Z_sr0cz(!jCaRfVV30OVHsSB0mQ zeyfhtfqAbD%6lz(%3iYf9KrUKk^y_oUa}9x8~VZ7Z+gb*4QG^Kdrf~h*Sz8qp=(%Y zh<@(=gSwWsuf(@)MmvZu81 z*0Rmm6vm$DO)_%yoWz}O^_J5jO>a1DkCo$WOaJI0ha8ALQXVAKs$DseP;0mThNq?NZ43ol-FVV!g~bUBoxYG^*599?=~>UE(1qPA_u&Yqf&v;seLrgk#@ z>R#jFFQzBMWJa4sS@fXxrT;AGP{xI##vBbfk)B^zAHqyDslFd(SZ;bVS%s^YU>MdzU+g9541= zc|_R%_Ko8rA&=2!PuUyxVLkN=^3mBV@10_7+IP=t1_0D~f8Ju08UdWl=$Y*N!)siE(QO$s{^BFDRwv!_vaIy(3Z)6=j<>Bc$Z3G_zqu7pty z{b^XEbmLqf_|)F;s~=*Pox+(@(ZpYzo|3HN?1|`|ltdnZe&ZCRu3}4f%#dm&l*t?6awRF!V*@ zc{%5AC*6^J1+CaxG>F~!hOeMs?3R3vE1yYkL-Kt&Jox2Y_f^iUMcdnjbGIT3KL$z6 zF`WBat|$8%=T1O}`Bm~;kaHi4wB}f@_&RmRqvup}b~6&|Rx zeIfcGb9of#-Vpury&?J`Px%OPl#g9;DIrKw&jtncUWi@*xxbsSCI#KsTDsF$06{|Kdd!ZjZ5_m*Uy>^4*6!*=R>#M%D&8a4AMU|d9h>gMRd`{g$Md!Oq$lv* z`*3^$@~~QDUw88Rcct11)gmjarS=YL?#%7YIw6VtGIgKN&uN{|DY>0=M_R|3T4Zsa zdx!6B@hX1=5Sj{i)WK_w#!n2i`~CF}W3)RL4Y% zJ*_xyOSQqOL(+H+_dJhO>zYKHp~umbXxn)+SKX3op;d>h(wG;|k)BVqDEe5sfwMQK z-$Z6whs>-alCh=8^lnI&A_=?^xG(u`*fV?>X~H*o%iSn_Gu4`;4k=wn?zsVYBQk}L zaBf#@Bt8Pvx>b9>8X63VO4w{}Rhx$2N;b49cdw2U2C z*IopSu=m?(Xiq{gYCST*5K27=4)M=$O08Qzoe2)>5 zE=~92`jzNO{zCn4xc)V?riUgwrz@!6FSleGfDU3MHd?<d*(MP;Y`G@57=xcrm)Z(iiea(-7|D?t0bNjLS+;R-AGW{QFzDGWvC$0g` zBcH~Tr{}ATH7S~SI6i$12f=}Em#j(A%O_Le5%p1a=cmDNEkEHXK_B!JU_G^yxn>G{ zm3*>MdF89+z>UglgkE`dd9cZeD?;}mkk_7(YB{M5_G+|z2cyO7h6T&P$a=M(oR;Rk z22C$lMsUq!|jNwR2W-YO`RUQo_sts@$Qu)@2cGvLg$o1jXk@3TwqZ7afoi`)) zY-&_XdE4eWSKFMj(w@GYYmsE=H;KT9UXlocXf0VspxMN~6j^$Uq!#IVi=-~C1@=b* z&)%nLf1p;}EzoAx3wdsu5%i8jEkl7UEWUHJ_K4noe~DjAIAzg02>T|g^phonT@ z$Y+%nOY7&!*I)Ru{spK$W%CD~^HjXL`nqn~ey?P?XU1`C3gSiIH%wRvrc z&1_p>E1pqX%jfc~uC_{~jHB9GkClrB4{yo#ke`pTXTY1;pxQe7SyqY6p z5gT>E_I0Eh`_cAxOhnvAW3RTN#;BF9%#7?=^jfU4?3w7xj6BXo58AU{WA9e>YxKES zIwHNMd464teSgPi#(kE&-db0H9u@br;K-Tb7-4>J#;D#t&G$F9w{PwHHzPIY-|JnS z$8UQ_%rx)xNpa+J<0`MNt!pK3UjnzNc*S?`WYft-4_L|T38|-&Sm~ZDV`Fox>o~852JqMh1-f!O+qXg{7 zm0&-vZb`|fd%wREec`VZPp_?w_K&Z&txEsyA8}wYZ|tibn8orzI{>w^RNA;bP-&== zbERC$!IZ1VKA+oB(z0*{yvck@)5xd80nMXiG*)A@8g+FF`BX6Awv;B5Ps#D2oJLQM zCj#X?#E27sawB5I@i{IWPuVCB;=*wxqdbTO#fx$$V!<&a_udo>jwZR^o~x=+q|xBJ zj+BhR;(mMLzY!$&+Y|o{C%NCAm~R-#{q~$+LrKHH^0xjEl3Yj)rNQLxw`cDRBFTT* zUjs=-p|$twNk)0F*9MU4>Eo7^`jZbx>VV3do%OZ!8DoTGlm|zCKa#N?>_2w{H`ar_ z>welsd2oyvTfPs!>{Eu2YV-H1?-LS3sj~X`<84=3(AMv>y83P zgmTO|z&VUqX`%FSJoT;faqLXmhS4yATJfLM$}ugKoB)(|R_7yIyy%`Aj>1A(Ej6vl z$GUiPCL>18hBQ(7SVP{P8l{JhY3V5zu$&1>Dpi%rDn$$mJC#|awBMN(^8P~4px!~9 zftm-U(rP7?LeIq4`kjsq)I+C*r-glt-wbjYTK_Cjb*)EuZ02z`or z6{X9eb%~gtY6L>AtUOhopex@HS{pS0p~sPjP{OY~HRQ(|>ws(}xez76etk%SLu(}0 zq72w}3jLC@-$L(HXro+r6k00f%7yky*|QSqLa(KUq0n~~S}-+Wg?3CWrW%aUo`vjO zDZ1lSU0b1LldDq>KbV?{>UG0 zN8cEIQ7ywf`o`FdMpBwf-?-yxZ_>8(jhZU4;vD+M7>`Cx--e!1v(Y$y~Liw%X2Qu#nfu9`W=aO{0Lnci~zixVf& zL(UO#;zWALnI%qimFSEtR*z~2#foF;8Rs!86>>4-So%pVV=Iy|Ia$BZGvWqu;wXAX z%pq1BNe_u*#D*j2o92`Y{j@kqoM=Q)@tHVLC>9ncy1um+jXpYvXW4gB#4_*Z-TsQy zQO@mK$q!h2e~YBFOzTPQ5PyhV?HiQ8o!bt6n`^#>yh>}r?~uNo+YEjO`P_eT&5y}{ zg#7AzoO_X@pCBjH((xtIkAXj?*8Qh{f^_Z$;OCJiehv6F&b>n2Pmoh;EBOVIHh*6x z*P8DONY$R_3a$LUfOJR;&QDSI3h-4VN}oc;_8jskElaf~d=&}Rla!yLUOPm0hIUuy zXOgE$PXRwmt_9@NNY$R;%Ab+{G`E9%8cDXctd9V-<@*HrBS_#rf&BYn>h)j#Ia1}1 zQ~N0LxsTJP4^pFb-s8xbAE)*)jvhzO{838!L?=j~KSKF7N-1*h2gq+HX(OyJ^{si2 zX_=BD$G(*wxr2J`i?!(1()vE6?)T*IK5DhGzBAE!F+)m!H{}vX8S+^B^y*{-M^}^F ztJ$5JwY_SF^xFNLuR&6~0l0y4S~cE8?_WXvwUo3Nyn$S+#%qz#U%@#o7OzDc;}|&~ z{lw+K<{Y0-sX00vN03pkTA=6o0Obp~#>iL3b1Yo2_++DwM6T3 zG38bqwM2VjEUnW?t$?l2oSX{87no8jG$N-`J_B9QxxjO|LVNx9F^f*2emy0ldl}nW zdwus2KZSEz>aRy~<(xC3_{qSNIl|IDmunrJ&(EWPT5Z>$TQK6sv7}>=#vALySmMGH zsWmFdaY*2fg98>Ep&a6bsy-x}Z=t}y1> zY9yDdIX;-9)!>m;TyrSpgONtA;@F5_2P2Ua-|S7D(!6#Y@16UH=u;=BwkOcIa2=5N zMSOW9tQmc61@gcZ)b7L43M7ilC>dGKSoBLNcjTx85}VyAEhOnlWJJ2{DR%~V({H5jF0q)dkGE9l3kn%MrT=m#gT& z#RUzW#aY+TQgZp>d0_K-IaPKiE-CnI@UpsFDfnzKsMviBbzOnoz?@^i)KkHlQUK)z z-N2foD37IHIe~OonmZZntlVxKN0Y(U6DcWikcx}|N`J>ex1=xwz_TNOBRCpBk_YKe zy|j!-L15nDz~P+hMO{yDu2PPHq>wHS1LrDZl-_BPARjE%(_*GCP)g@cNU=VV=8B)i z#;!S>QLedM|A@=Q;Km#lySrPLSY5220mb)W{US9O$~#HZrS1i-kdh4NJ6&ImBo#I= zQl3J8J(^iGiq?`73~luoO77{R{7_kFHBibWt&_sZr6?VBH<#dKv@VcBPRMDd^iuj5 zT%bJQB>F*17-_80(d3b&x>M*~b|az1)T4d4sHmOyKsunZ~li`tdQhlJ%-nZFF{hOp<+ znnx>%u)Ojclqbop`V9pa>o*kKt=|y#JcTun?>(3IbvDf>pO?RV@Xhn{u^jv~9)BDy z$lqJ&jFD!FS0E%dR}^JYq@&!i)=+#Y0get*Ol2k%JzWJuX8o# zy2~%Jmt1Mhp*%bPF8i}}-ovh|{JNR>cg^H`LY`R72vN2evPRcT${m$C7E;OS)HuFe zU-?DODQA+aD%Ticz2cfpK3Ciq(offWVrEx;U4auh67RWgEMy3-D_tjwDP4hzA6U#o7xvhFpBxi{2EYiA!7si`&F8%6G+fVp1i(uAW^*yZUyW?HaolC{7iB#%kR) z`VdB?>-PaU=5&oQh_b7Vdg@bptZ{rOE-holGCq`Rb{zUP;>O1Cp_ov<+;JH=uo5da zjt>J9iWMD)fe9Ult_xg4I2ywmu)vCCd?+R?W5qH)6cd)QVi_M6n9#M2n6bczV!|?3 zd}Dkl7Aa%JGCmXs7Fbb>z`%ro6`O(&#UZgDiP1i{_Se?_QWg>X#@6|ztZM80+KLZ1 z&ChS8Uj-&E?NRxay%vHH?$9TP1HK);ar6gdjj5&I26>n?{hV@9W0IprOBf0yvYnKHicfXeF*q-F>*REaMnU9zcl#KV?i_&2D zj9x%j!de9M2KMGy8v*SD#E0(1=}K0<(0v5^0qe+zQ<8J5qck#KyNskf0&3Df=QxY? z*Qk8WGGHse!C2VJZ*1i^lnE5_jjjB~*7a9o^24qC#(Rt3*t%Z+-$lQA!JqZcxi-0; zDeySz8{~r~1C_kVA58+PgOG2U2$U<7pPB#+`CHg#gcW0F_(*Mb#^rq3SfG+Ot#!ua zP|mFbM_TS^!Q(zi#ePZc;EJ@_842H~tV<|o*oIu2o#B+U;i&-*BiAxm%N;Fvs>rq3 z8A7Qwxi&k4DQUxl?J7s^7d4QwS`KY?xB7m^6oj6T>Lu)BdWK zvQj^-b>yX$24=|f`chU_sBNUzYXPZ^Uu$yp)7o;iBG=B%{mfgED}jCE>*GrA^7<6c zH{|Hb)72*_nN`}pEl^plvi)sIGl5Fv=hCA+fpfTWE~yt(RgPIX`nEvr6Xx^PTBpp( z`DFWkJFe&nM?9C(0&3^N3lHFm?Md^1Ve2w4=b0TJJ8+%*QE4x+khB9DHti^Oq@C-5 z%H((CcpCV=#KeT{zx@JBX~w@vi6~cjK%NHcpr3@ zOSntT<&s>NxfC6zv3-}5)OTtN;f}8R=GxAVKxc@$(51ko9Ixd3GT?CXm6Y6tN{z%S z&UFAfi}t5>1#kt&2XKBr;0W>qD5=d=YoTXLJD{E^2T{8UxQgS0Ij^URd(<9GN!_j% z9f#y|?~r^B9>R6)(Cq5%awy5jefqW>#+7P<56X4G+Jqd=xi)Bq56N}K`l_s9?vDoQ zpR$J1VZcMVLalQR@Nn`YI6fTxw6#ZZ{TiT}lcOlD2Cn9uI&Zb#t|*V@x*Bxd`js3* zIvOpv7A(htlg0tZa?i1(BY{V9#c^Cwh3@-kO2>12G*F+t6S!Xe_^}+X&2h!r9D}GY zucAf|y>Jv%F1CQt2NnAxVZ=hOwec?_4Lrwrr;EGd7>wxPxr&T~p z;7R1Ca(oi@0oI<*`ICVsb9_3Ob|P>hb!TvO3*f2bXXI7|>w#xr8!(A0&ZN8^sGZN5 z9G`~8fZBnxxS~aFNpJ@6435vq?F-J~s`Zp7lb-{gpNz$UxbA&ibyjYD;Ew0oA-tdS zX9K5@zn_xU4cZr-m*cndxWawU-5cct!1J)5aF>%0a?SgJ=jIj_+9t&g=I$nzQ9h6S z0?wTW)PME@O6OxkF^!`ONm^NG-E>ioCocl))lzo%^NYc>eSxm5FXp=Qf#>HI7#C4@ z3FrFcmKhfSr}GqjU;6^p*%r2UP2#S9JJNt0mLNUD~I{Zxm47 zlUlNoz@UB7z@UKY$FyUW_NgTs29)-xB^wHq_NgTs0+jZt9~%sm_NgUvUngmw`mupP zX`i+R^+0J~cW}QtGHG9TD2JLdX`lNOYb_w{>qV=pBMW-~Emfs<{m5+zshreFi)ZPT zEvqGRSiqNP34A?hac$OZef&JgZ69sdefNa#uw6P*s>#1B;frk@cc54Q>6aThq)npl zfW25->$9r!r-T)ESdnW978cTBH?Ez2ZEY9sAXYa}`j7&p%3|>h=;#!$mw?i5v9CVl z&J8hZbD;A|+-bBL=cHT-{waLF*4o-{Yqzf@ci7jmgYxsVa{QbiBAuPA8iF0w4 z&@(YUqg))tcgORhh2vhY((_(Vb|bKK{P#Cl+bRDBzp5ks?Kc>2z-T^FRKKGe?<}?S zJG8FV%f2daCBL8xtyV<~iElgerZqtO!M!tm@8}m>G-Iqdo>E3iPoR8?T#@$7+MGB; z-9uAe$yuBxb>u1U60L8$7jNr(`i^?`J8nAVt=cJX=T7`~TWahJd#^oXwT|ahb5z6o z_NVNqs?NVE&A&5cWOt+9_e_8Z=X>PGaxdED8-?8{N3Hp`PL%wvR!ME`==_e+`L~YF z-*j}|x})=U9i6wR){iZi&9-2nAF}Pj&b6L5alX6L=NRT*Jy0%Z4D)jku%0t=C1aS! zLxA!QVdJh%yQ6XxZ>+t$BX?B(Rik)bSIRy&xMw+tF|>$#j>;E|p)W=N#V?Kx@ykf+ z+zm~Pqm@w`+G-@F?$j%lR6c2YjHF*YmJ=LFPkC&gj->BA?vt17U$x{TIj*g3m$yp0 zyj7ed&H2@sCALaCTB8-vR%u6jQ~@1PMr3f_x1(hpPxh>DYcItJ6Ei!$#UFa*$T7DB zw&FJ&8O?z$c!oYMVwL7RRU9Iwspe@u$(>)Tc*iz*|Fy~ARR5P|+~b?-anSE7|`eWeny?}i#pI-?y%UElKU$Bi2!-*Oj9%zA<ux%pMaUPfQ zcCa;kvh84N_=e7O=cIGadFJ!=qS6D+*{5flerw^&=9BD0d(J00B7IAr6yve-{ok!` zjPDCNySZ=lE5t#5sbA3y=(qV5j#t0Uudr|ZHgTDK>$h35PrTBS(C@44yST<$V+K0r zHy+zDt{ve<$FUC`;c_w&UC%!C4P%5G9mhU&gul759XQdwW}VaWnAIfluh_1NO011)y_hxk?r6t^og-n5#x$qeU??Xb$Vd7#`AhjHpV^k=Eby6fc8*4$>96>FpXsjzM;M%f&zJHw9ET0t zr}CPnwTW*P9!b7OnI}~GYiqj}_FMEam%=#;qwO50j$OY|4`oNLW3@~l^%!;@_+2Hi zi(|e!_q)CkAG(&2gYUsnPwKk^yHnqbt23bZvlk^TV0&`Zn|jyvy{PZQFO`7e+dhNy%jz4DBK)GOU@1q_*o6lZXbeFsyk{9_Pj zl#g^{btL~WjFPewJ%3$i4Pm9!jW!%ksT=DhuNy%dx;paQNUj^gdPyJRQ6wcdj-1h) z84euI(HPEZYnzg5XRL)yc+1srRbl@vT^P&pXe2|f?#7X{0oOKJ8}J@UZEf^tx4b`n zE9r?e&K`7?CUtR__bQ1;N+nNq}Z+E0*pSPqp#l3a(i@jZ&*K{PepVg;yBDaUt zugGt!X;A0ViQIl}4(v=mkWw?CYh3%edEUSEc|SJ;D#KEq6}?(`dJbWn>cKsjdkd|Q z^w*wMPt=us7|=b)m5SN(U4hEUYHOti&Nat<%*R-31m-E@Bj;pb3|B_-cFswC{>9*} z@MUwR-$QDad$u*h=k0FFdczTonxyC3{nXq}&24zY5y3h4d%K@r)}QW4&NT<#NB$%p zfA{4+fluNor=Oj^fX(r;bC-_?fe#?(eFBNFUS&@p^?ib4J;t6u((AD@=qK>l$o|)%16W6X0GfeyNc=t43+<3x_plCW|60oWldVJgzm{Wt z#nu7W@r!!Htpz6h(&3c!D_cux4RvdQYjdr@Ih53VG)JC)4ibO;#hN4GKZoO^fkz?D zKZnw>K;`}CP@2M3&4GH8O(E?I)QfBiX&F%c%M{WIv^7g89nW3Ip|#nYvhv{O$cObU zn@ZXPsK=UeUt=5Shcyi?(yl=L%%+j1GM~qDMj7yAX15+(YCb0;iQa`PrlXJA1$p#h zN;A-2EzTv)6VcW!;@CJ;i_qKcoNMpg$!#`TFExDntZf5S=jWbUM6IGU2MyXnw0OpM zXp_&5Hu>mwRyZR+A{kFfoBGB zXFJNuE(TKS02F^H3+_m{1DGXz!$MLl#SoJl)mcpLEbhzaZsNbkwqBj8bC)G#vMxg$sdWzmex)Cqb z^C)dV>v3N0pDG@?f;YLDnhju!D>!bApX(LikXv%>(StWO+Nqdatx7fNW}x1%)g(Fg zgfUo6Iv%L6W;JOC;12XvHK`sbJ*+0hic1QhygsD$>NNIb?CNQ$$7_H7FXybjxmSRR z9srZvPr8d4F4p)2X+2O~(kDn~@tly~CiHIT#l_+M`7-IVIDY_N<~v9u>iM!l!#*&_ zmf~sk?@}wVt$KOo0FFv&s`7yto5tdhGKY3wx~9h8u`2x%I%1_$LdUK2Na*O5?g*V> z(igoc)x1d?wP4VWK`oCuA9#8d@5J;VRlLjrtziCfPHDPX{7!@ zbw$%CH3v@ROyTDzZPD9r4A8kgJ)if5&!03~FFJv-kLd({8 z9OXDyE>~XDSh=x#8>`>a=Tu%_`OGx`iufMCH@Ii{Ys-bbMaVjB2RUrHZd=7Qn(b)2 z%5S%(y|>}6ZaFSZm|F>$bT-Fbb4=R}ylCw#j=SV|xGOl)-30V1%u%0wCWJ?t za`#dB_#Mv3PPtP%<%K}$0ejMMUr$nRM!h;0dB5I_s6N~kzQqSI!lpoI6K9 z{9x+U_^b1jes_dYPvZCx#^t1(es_dkPvrPe=GMfVig$!YPvAKA>08M?9iYss$PZ_H z>m}}pms)Gd;QU=pjlSbjMk7?V%jtJ}Xu30J4QX{whs6O#l(cVq0G-P*qNUYs^UxrviqzE=k$6UqIPhjf z3ld|hS%^8^lJnK1en4@PYgE_DL*Y8an|*;=nb+i8NKMX#)a3ZxeQfupUhbuaq(mqr z$bk=(Fgos)bT|_n_s#`pLaa39Z<{d>$~Yl#MBtqwrdHr2dEAU^19QX-b&jcb2p(E` zXK%?LyMlG5x#E?siKpbNL;A0@#(8ZVvhu23*?@CcEvgaCyw4U;H{-l>l^?Q%kR^wd zS-q>jto}yMLHR;_h3_42>o>;xi#x=te%m|q+phBqycBQXc(uL7$l~OLWXQ_74jl`%eG@}oqvz5QuIWU*F{a>dVjsPR{5@)3s>bCNxiB%?}(1>^=en; z=#-%d)p;miu|Je8v>>_Si6~_r+cRx>bM@f%RS~x?sEyaEkF)O_3(_yY)i`I4jKIdy zD!I&>m4|fDgow`%%3SRa7dvLx4rRYvg zPf|DNMi1(h{U{M=&mDcJ?E&mbt|X{Auornh`n(-b?o(@!&cMzb^`lm7v;fv{r~cM`|ILBwe{Dp!D()P_{d#8Clh@Yz%(k5KI~-ri57j*T4$2vASJxs1 zPIb(M%+5Y{v=yU3{2JrBGtZQ|X(^F%r!%B8$6-sMUcg-qs{h?T#cl`Pd2(~w&R_0M zsRpPTllV5BBEcaDUj=R%FO8k0rrW>#&dGCMsSTE|e*XaSYAMBq_z&_Nw zHgkohX4!VOW$o9x{LAWiPH)P7Z5<_hOd79Dr(@p!%5d!C0knb zBk`~+6vwLXBi8qRe^;9AclajG7O8o(V{L7LbAw*{R#7VC=KgM2c7=Ax=ZMYiXR)?4 zP>dfvR$JSY`+_s@p7QVcML{!sn$PrHZLOopbN*heDWc_U!B}%i3v9=Y+b<}gPm*5S zYVljvL|Isr{pNBx#$%kXtZz!WSP$6_wwqK=Y$l$HZ?YZBzg1ao%DYuwUs=}TCVDQk zv|-^PC+EDe&zx7mr-prvwYHrj#yJ^Wl5?h**ROB87OgI0 z@m*NKh`0Ri(1CBxy3ZAe?-DdY3pvNDcs#6xl(+|;Rz~mqlUo&I`z~F1m-*D|YpMib z9+VoV_I^_9%9Z#mzg zOs!)Q`(o)CFbBFOj&>!|k@agI&dmlB8&A{~m}`^{tX2C`I}6Njr0c=d&!jvnag{QY zZyrL8E1q_&TWhJQ0~$SgC^c$Lj3!-2jVqezKrMFl&rm<29A`i-BT>>njW*F5t%fA+ z)`D2#vduYYFzVmvv1*Qdu^ZR+#m z>HbQ?=f{(a?~3R8{P?Y=y??{!+Zxdp(K>;P51yJ>T$ zSfAPQ#hh~#7qi}9cq{K8&oAa$;EdNlzra6%WBfX?j@U-HdE8R@{CG~~R|HP0{FeBQ zra!+a?+|?-zaC#2zgzhx#XH0(vsL3ADtUHsr_uoNsN8@&i@ZT-zO`M5o#eD_2tBu2 zAobima{A~B$kk-wtKd4v)s50Pf44vLG6jmC2jsZ9KL5pmc}uH})^kFtKZxh3S#!-a zh~$2Zj<~^`Q>!tEd`M1RrJKE=kLtjNQlqY82uFp-hC4_M&*`(C99kMkz1>4mZHLwd z+IwqFAkU%=L0wM6j3_5BWIQkFmuqw*XB#83I~>C}-hV(&#rgxsaE);wQz)9PH-W39 zi%N2hlr|QqrhNiQ4^E?hOy=tb0oB?};Z24CUGYuforVL4aWs{(QtBzxPou0pL`{f# zl3I8GwKUU7#`qXPX$Idh0`6fJUo)E)ACqhYh1W-M9B;cVDFfD1yDe!9(6!>Wl*YmL zOybJ9yxRnz5yP5JBE|XnC-;G8VtKN7CsS0`YOeE9$aQ{r?)JE!CN?M%DthWa)&h^lXs9R22 zfMi?`#}&MjK7Hx~)OGKgtfVv>xF7jSj`u_2ZtbdEDy?>X7s@MhnZ40Q51>37xIg)U zoZBC$FW^D+bQQ3Qw>y}$2k@Z0tbW^_srE#+e+W=by!%FVCO?d~?+o0Vd<|c>1j+gm zzVryvzR1_rt{+Jnjg);KN=H-L9=JVUcMNGUa4~IgEMHg$Tuy!*rG>zSxu$awbtjPY z#2d@|t|e(tpy$In-k>vZ6k}^0X*=L{xmCl-y!%PH2i-}O4$f^OP6D1r-Ra4Cw3}y= zRs&aakDhY+#Hrsni~A17=0JVL*?jSyx&6VRz`dzEo8!IF!|uk{oKYxhA@?0%4HkVgYY(;^p;mH}-SJ>sl6hWtXl zd^u1L#fxZ@9fA58UPM}m-ueVemjEwDx4o8@xs-GOI&Wj#T}E4Mhrag|zWYOz)tze> z;;xLR0Z$~qg6}^Ocp}GFkWK@hNu7HGo(4RVT;2KUKw}tRNizPjzJ^x=)umrW-PN?) zSwKA*ucn1hM}xkelKbMF1yrAWZLTl6mR3ES@-@_7OF9J2`uk|T>qtw`tUHFTC%qrd zy1tq>&}K)WSwElFxRExQm22IPLCao8tK7t>VIMq77bY8Mhf9Dfm?;}bC!j;W6&?4@ zV2N9SVw{^vbFjBrOU-SRCIKfhvTma^5qN8Ub}Z*_r@d-{^S~;%Q<{fujJsXlK^uMu zIGGu92k9W-Wn6IwX)^F2&fl5qweIAruc3S`M|V=X7Py+ayZGMgfY)IaWVGvZfqG8f z!&o^Ncs<{K5B2u~-%s5=)EXiCUe4S{i;M=|Kz={t=X~I3a&`FH6rE4*&Y7dJ^?87! z2WdSccArnHJxH1boJHM3wAXUrv9#Soqzi$|IeM6pbP-U0$%kphOMpAkq7UcV#D^(u zpnMTWk1*B_0Inr}gm%3Js6D|Wq_w~UXzxczH)Bg=zdp)0TnD_4qeuCcyMfn}KgQcW z06dRxGP?MAz#FJjzLG+XLuR*?{{O#A|0}6|LtfyWqyJKVKrO#kHw z4uI}U|E2r~HnV4zk_(kf(zIaE|TtGqprToDK z1mzDdU}O3(3>lE-~xjFOY^mQEVzK6{8~t!1Z8Rp{XdlNEx3Tg`SODP z8~350|5EfX3+m zoSgobDZg||%74qhxqw?JH{=2~Pyd7F2NzID`GX^93jGhtA6!5s{STTS^gn2Ra0I~x z1pSxt2NzIK`-WUVWAtCjA6!5||E2krTtGqdE4cvehzc%1${$?7#`OP|*U@}Ag5U*i zfzAj056T~0z*hRNZN&y<9|Jt7yEB}xMyuIuH&a7u**O#}p{&(fSDf(Zz{&(dcT)@Wb z|HJc@e@FouuK$}t{}0bs{%7zl#rofse@Fp}mH+CT^2_lQ^#4D*{x7fmg9~V!{#UO5 zW91)GfX3GUvGNZtpyB$za^+u1|0~!0!3((Z4=$jf|E~N)3Q$n~-~x>H6jFdUOaG<$ zm0Uov{&(dcQh>L6{U6l6F)2Xh`d=Qoy#8PPf7kzqH(~uB)IN9tX?`IQkRxb({a;@B zhb&-I>;FpnUrG5x7N8X1&C>s-tp6LM|F2*9heTlO`v3nI`Tsjj|Mjd0$$w}8HbwuH z{D%~vkpCX8zmoD-N&$ikP!`ZQ{ddh@NCeac zY%KW?T|h(nACmvj0>}k4F8>e7f5-wt{vVS6&;o?yKe&L9|10?qEkGgpk2QaA0ZRTu zF0irWKXd{Af6M>X{D&35dqe-Pw!fhjz}u()5BlG5<^OK#|2I$nD_8!m`3sKV?bZK> zLu z|9|WH|MwdG-_rGeL;7E={|hUCrmg>*uK$1M*8d^%f9v$WG5!DMH2+~8&^Y~%^?z6a zG$#MA)c?o&zr6AfEx@MM|DpdcOa8+apwRpW{cpJbucZH*UilaFf2;og-L?MFE z49mZ;1$=kx|Fry@h0Nc$CH0iH$?gBP$?gBP;aFXrlwaxpxLh~q?#EjG&B-nQ^v2h2 zQ2Rfv|4L{OwEWu^DZl#!Yxy^q75_B&c31xHRv-^QoqT?7z2^>K`r@}_?YdpA`PbWG zW^N52oC$^3B5xtk71vJOH6Qyr?fta+b6)}N`P^N=Jp*>lt>zY?F;?$CA2^>YcPA}E zL#(ag-aKPI&}S{-$uoiOb+Ck*h1i3+Q-HQ|I{~#h+=sLTD}a4-IFpuGN@*s#^PQ+$ zMsmjhE%ug^cEu`ZIdDJTPAkC0xfP(h9cbOB#(y-qmVl$th-=#yQF#ucWORSy_p9wc z2<@z^f35t~`AY+h&u?^ot^W?Av=?&C)qKg}r1`-4SZy6aZ5?nmxv}@_u-Dp=^GDID z3xMwRa8zz-aWpNt6Kmd`_=aQX6Qk`b!#{@i?hKqk-7&d6pHy!-Rsc%8kE65#{i1u+ z8$rle`$o!_rtb{gnR|?>FNHsjD^DdEHD9YpE&Emi_d^POCT+AE@GSC(f^U@jGbyj+ zDk-^i{7iDKv4p#!M=_4Q&=~jcr)|#zzK^;O(7TKC)%zmgVrs*t?*dwN5i54BDla7M z0o(&^{zbIxfk163E}}FV3#&sYscE&Wb>+pB4#nnbKJ9%8?Y#zQA6!CdK6X}z(ZZKf zJ`89qq|0dY!-0o$d>Lsk;9k^yh}IXnbHe46L)&lJmndTAL@i9^}hr(pASJ#{xwHoDHql7DwZ*g&7J2cE`QxS3u)19%2?H69V9Nn4Ey1VH83$g0E zkbb|5q@CZL)M@Q^C-VIJSpD9UK>r= zYk{@ky9Y>;{L9Wr}?|6FTLDE&g2RQQ(?RF#36~jZMlYlqUYTEzp z$I5?K+Ua4^&AAppo4=cBE4BT*vXVDC*dvVb4*<1xe1y{Nz(=Wj4ESN-hxxk4a;wD0 zsC|?eVUJPs5x)8Y;GN_jWju`mUP=B@zUNBdy?ozCNk;?6&=wyh-AhcdUAW_8Jo8bY zk;y(r+68zgb&vDJMZgd83y<^c3xJQ2KThojliJ#?egXgc{Q~OY0SYgGhSGtzZWj=G zfzA5`Y?TW%^b61*%LU$? zUZ5#{0dt`Eu32C27Z7%V4fO(Q1oRrX1)3Lr0S)y6p$n*#4pdqPR@w#X1yHsQD7*t2 z_X`NUK-dCS+69D-pi+Z3k_&`(AoKza{Q?^51sci)!XqH00AU?isSzl93KVvMVgDC8 zf{+F1i&6LmXfIg!0=(WLu#gK>+68RY3vBfZ+%}g96db`@r~mWeqTg=2z|ao7y?TL$ zc7YA`0!{G?Y`R^bYuE4&*py#jWAr~X0+rqYZ%!{zX&3lb>;f92|7GidP0{}{@3W05?)m*N71FF>V4An5-@bO7bJ023*1X<0XB>d5D@{wJMfL-0vHh>q60)kfQSxILMqvh!GI604k#c zL==FA(E$pNz;bkeP5T9w?E>E%{cpNoU}ao@O8UR0et~a={=d1n0Og1PZ)6wH^!0y4 z1PHsp#@7GF0(i52fqDc)bbyWH0yM=guqo^R^2)zyaRI_Q;2Px6O|uJVXcrg}0h;0$ zXe@vtEA}R9XjwML<{w6m|h&5fIh^@0?wL zRsb8@1!yUtJ--$KVI9!WE& zw+IMJfzbaqW*zX>>;kj}sI(4vckKeo76D-+P*?;l3T zAoTxX3lNq9VI81FKv)eFRsfZD0bwZ+b^&1pphsn49T1iRm39GI0c>m+pj>8Sy8tZ$ z!aAU^3(z7UtOE**fJ$3{unq`&fl9l8un5o!U}L)g?FBZr3kZvVunq{jfUPlw-Wxsz z?{rMTN=d;xXFE_SJBXNqO^+!Mnu1Etf{-Q{YhY6`h2C6Dfrc>!8|n@k`V_qTF$F7Q z3T&xQ;g-e}Y)VXlhCT<wG~Hg$-j0RK^qx-NAnn3G!&Y-vovhPDHhRs)Us6u$d01sci@8b%W=dlp6n!6KSqV?Kpp zK@hrwkST-)K`(RgNF3Kp--XFgtsK7U}a3Wj%dPf6jPv~?Lbp>2aUxPZc0pnGUX3D!Xl<{ zSPC}uFDzRS6q|JzOf-SxTHS>S)mo&pg;pyAE} zZ{2pVDZT@nk1710TK_kUDcls>!FOj*f&X1G1sc--veiKBFR&@w!Ai;>9KpLo|0~!3 z4Sffivi^T_^uICRflA8%R%{0wqyJ6WQ=sX#1Mgf+fmrP~r2LKf4s4$OH@2rhWgNla z2!j5ZC11-Eql-%MmoqcCg|4zbW$n z@EvH(b}%dj8(I)HW;>3cW#6nwAI|Azhol~w?;{{PR? z|H?RmueSnd8vT#m1Y>8x*i+Em1mDPapmP1+*q#Cn>Hp^U6lx0nFH`eaZxS{3bVqVy_Pbks>`gtA9eO8IKM5Fn`;KJi-YLX7>jdmX?Qo7; z0!NTf&EwKd<*YmGy0i2!&a@s8L31Bsvgw$1kPf|#etkjNf|p88=I;Z zXJ)YvV?AdQQi?TxFY0>(waZ_?nE|APy^!UJ`*3C(bOr9V+n=-mxPUAAa%K+D9e?_g z<`QRYKIi&zG#5|&`5Z?CKjZfqYiu5M^Joiq^>v@&d0aV_y1taQBTWX%cWgᤁ` z3wZCoz`k6!J$2K7?m)bK{;ciuJ9nVx#uI%{Z^s?DW+KoX0v2-b0%Fy9r*Zi#FW^Ya z`|W|-^PHV%sp&u|?M@ue0#4`tof$o2f#b<{=6F2z-|pzWh_n#se%FiWn`T(|x#HS| zv=iQX-nlEK9f&ozGf&u!F*X`FmVEcTuXoQ!!tUI)n3_f8yYn2Q4KC&xd*shD^59~k z^6bKs_ROEV7f;)bSa7?NyA$!QM0^{?xZInkj{@#Sz9b)eOY$A#m+&jQQzMn$hv)1G z+=F~yN_!EjYu_BYpW#wUyAc;onbNX6QuQ)wM-qL^JB>%!8tAN9&hz#FwkBV}bM^)9 zL%v@gzi=gYEhDPhQu0-d=b=EYLRV2c9Q*ic?%Y40cl+nFb${+%LCtbW47K59aAZfUC$4;c5E=-7)--92*?M@d4=I58xSx z=Figd{s5xv`K-fu>PkEseAeL{uOh16Am+hpo;wJ5F!>sua|lqpu_nh4YdAiX2z!Te z_YtJSh^%)QcOOYQJdd*{Je<3aBCW;)!dY}Q&#ecpCO?`ptBIi}Ryiie9>?TQJci>n z)U4s?Se|_t(5D+q@dzU29ZUH*(oxv*9mP{lAPoTaXMUYPsXsn!;-9rSwpmN*7|O=# zTSqz$xR(4xN=E^Gicyq~L+atPPU84zWFY;R?>z^U7Bs7A@sm$(ef%@&9O6`fn=sS_8o6A_Yp3JYDk>j&7a=dj0cWgsV zH=cI}=~QC;&B@`ZJYzjrX%5gQp2?jl&?lbB@kzkbsWTGbHo)0jcUF$`&dM>|S=7#^ zrU&QG&hI~)D^8<)CeJyCGwXrtIX;K$&jOyE*NX+u$#LE}9QOgExX1b=pc2Jq%v7;V zGtNi@dIQ~qz7OSIlzZpcZ!+)U?)E)NlYo;rCnlWC+hiQqQJR>y@?=J>-_@3s(Joou zDs9Q_-HEhITWam&iNJ~cdRJTrE1_d z*cAMQR~-tV=Oh}xGP89@;2zoh-yxa zoY@SZqoE6Dx-zy}Q0`3GmA-A%isM;8N0M`6CjCB$bDi>5Yfas3MuTnGk<^Ki7vs;- z*n!bq53J{0bv{O`^RX+<-G;HXfOGBhIZ(s-Z5esnaojGS3G%($GDaQoZAkMNqw_f@ zHMHzJnZpd*mM1yWwjmjD*_k$*WQ1mC+APv+-rAWqlQfI3HHPwx{8x;o5V4o%(^|$} zo|gaCRNypPv^V(_pj@5fQEVum=Qy22`-=m6ay&5~(G#gL8bx=GC(zd2867bLx^X-% zpBdw*8PDi)#*8I7uAE6@NMjjA&aly>F^m#t-YC*&#)mU63ztWHPaTN8WcY4u=&YsTveg<@A zI8r+Tt2mO5vQCop8VXC2x^2 z8rlKd^Plk^2}fY;+MvB#PIcudg7$7qb)~mKdxPEv?G1Vxw6~zQ_KaAvivF<$%2cIS_P^GI*?mKPUE(Yn#5 z(q8FpcUoBtCjII`yNlDxRJSMn5%gBtTc*111T58+1_^`qzIm$adcVZj5F-pFIhLHg zAq`M^(41dUlHf|;^}f;or422Ba(AxuUGFOmkdtc(R8kRg069A8tFvT#t{VWXCs+E> z8rYh1(h21QVjSfpavkEJkO?RqsH2Uxd;cQ>MRcZ-Uoq8QkOVk4y}HYJFHw1I&wVuDzx*oygnf4k5By?=P%5qQ8y z-}m18ncvLL%e$AyOM1++mcC1woPU}q>z$qo5GwaN=mYA zQD#T6a1M!YfwAx2IE3NgCd$gC+4p8fqc7P5Hs1-lk#GsydE-s&PUovX(0o8KXuNR z<~Y(t28>YZoR4uIQMY)IXDlP#tmc2jeWah&9M{Y*!QDo>NDDPYb6k9&6}gcv(m*lM z92XymbdQl9GSb;b^IYFJ(70-MC@QT9Mmk)r)G=*jsva_;-el&E_)IfuKi0^IF59E6WWD|=Za5gcc%LkpAcn=w~9}QR>e(Qgm)u8AzE!l&>a>g zrM8Pth+@Sjbw343iT_DcB6?Ok8iAs2wNb56>*|M;EIubbAu81_Np~RbS2v_y@k4Qo z+##P3RjV(>Cq$F69kI0Jl7_@5w3cfGHCE!t;_%`VlGH^B;uE6pNSm+qL-ZoL(dr^< zlE%L>Ger7)%?_(ywcU z)k>>XRCF$ldnssAE30O%=v?~&Ln;^do|`@u#}Y>>#7Kw_NwzP<2#E_y0?rF+k&Lhq3OkCY^ZAomB+eFclCN-x;me?ArKGaI9nWkRV zeA7JC`V+IZh!Qn#wHigUTx)w|%@HpUU(j90>^`DL$q^CNNyZQ*#(0$IF~-3}k1<{+ zdW_kUM2|6^DN2m-RZ(J$_lh24(wOKmCb5YgV^W>yQMBhm+7rczDkb4X^cIuq;w8Dr z-lSjAil?!UY)tX;Tx7jElEYUFudiQ>c)R3r^@|1{nnadq)?%`!>8nsu5{;_Z>1Gse{=UyIlOzr@?c(g#2ay&=d{r6`NrK|l5m!$L`Bg%=3M5cJ8~NEdCsVj0WC|%o z`iO*(?@LycM4ut#lNsQZ(t~I`A zKa{se`>cqoM|&|*;y;tOYouaaU3@;;y~ku`$r|xoRFYOc##{Rc&Aogf9TW&>o#YMe zKO|k{4k<&rKGjYp$PT6bh-9hQ?m)V^Wau$Baioun_79>}$(T7PDNYc@O1_GAI+lD< zqogTGPC`js(nV@FB3UTf?`Y4FgLDq^Bv(a}hNLRZjMTf3#Y*=jO=1$Y#Y1usa)WA{ zTATxFmFybrZxT7qM_ThwElZ?DYO~sr8BC-!6DeuEBo)V6UiAOAJOjU0kk(83)to8} zNqU2=F&jMk)r8(6d6$yV! zGqy18(m1I7*=fDTF$*>FfZ2(4KiRpP`2A*b+}-Jp)w29xey*w=VLn=`5s?IF!!~F7 zzoVe>QLEE~>cfCuFknHB0*tnXJniry3-xyBWQdy zdilA>eE;g5sBfebP6~U?bIVuG48N`3kd|Bht(K>RJ(CjlObWfAaTi6T z(5|eY_Pr_GNk%Xy*VD*o9Ex(bMnd}Y{9IMib8^_$7trE3LGevrDwMxH{^RSj^ z))Wfcp_!sP)owZ`zY&dy=1g(Y#lqf^q^uDW?aB73QIO3uE2#d-5cW|9j&qR~ZAN1x z?rdnU=Ab7O2St6JTv1vEQZaf{-%E24^|+*aQCvi0u{+WjL>wTZv1rz4hG?gVlt@yG#Wh5_lcj?HH-AQAlQPVxj z-yoI7;>YFid-?aV&=`rLq7li%9cV0~dx_SLXpa2*9YuUwb0*?8hu@L*u$mXz-^P#8 z;dd9^m+n$`Bzn{RM)x9am6vhWtdD3cb!E{E5C@3H=y1Bq5#Es~F1nX!mHGGf>+ZDr zL|Q@hXZ*cbN+PbN6*F38)Y{m+M5CjX=kRqix))J`?1QoOMeBq(sP3fz_a&YiTP5?* z(mdqq9&>X&-B&b^ijXc0_t9NOTEWznGo_tyb<#|{TAHH^^$K#iE4qjcOLf@_&#CnhJ1aJanEkc@+ ze_|ngr?gU?Pmm8-c2e?eY!PY%TY|0GKQ|?A0k&YowW}?RpO?n{T*7(iU!;ARgs0SG z_Q2A{TtHf1+dY?fA~nwir;wY>zBJk?M-t;iJg~A-HVu?tmwY3oDQpNzS6G+00oZ^u zQ-~uuZ5ouMr|IMykb>9MB}P8qdTw5x11b1kP37o9YE2FOu`XiP)+b+nPW8j}=0fm7 zyszr8kE|K)FKdDFBdA7PlXvr8#g|<5rQTW0Jb7lyFG{np8gXVkxMqU#%psu zr3)+xMplC|r1f6hoB8_bt)OfSC3r{9tsKwi>vFfk6)JLF*=MC2x|VmVX5#AChJ5hy zkcV6Y>U+bMI^rSH=EzPbol!>eGZ3x=uj4zvj$bGNR-lI7h*1G9SeBIMT{+V7=n3@n z)Vm>E=Wb+P>b<-HLELgaN8(8Hzm5I_`QEjGhClJC_O+- z(;MlHMJq|+?o8vRStGiUW<;|o(hn5kDB8Ky3hAj3qbCipbkc=Fy4N$j(x^*2R1?aT z9!8X11DbBaaikxXZabpb>LIl!hg!Sp(3EtL;_%f%%9r&~dgDl2DXn>P=tEQ>DW@u< zEsdr$>n#{>(T3=!3L_?sleF(Gp#)Km=s`AjX+~wWXvGMMuC$&>&n%6zG|ke=N%tr3 z>k^>!UDDx|1hvDH23p!WY3-z4E(K~AD7i$ML0PP%`O|ob$~0cm5=tj6Ep?f&C0XcS z^@{c!S`Rc9dBJFhpIO_ zCe>@_Bxy+ZSD2vHMiPtqPg1g4njGFoBAC_rdQ49XPj%uU}YsTtCXW4(%j#eY>e3X;^|6Wn@sr*o+#gQLpPOcJ@p0q!g z#$BzDj>nUZWL^DQHd+?jL26GTiq1%oPNqQEBT1lEDD|fHYwBCkjPyEM2SrzsU^UA` zd)fnP71KE71~r26+Q>zlEtr*G*Ih+-5RF)L-;sorlA;pF{iy$xr#pz9A&q`?uIi~5 zC7-AEn`*{-HwgP);}Bgdk{s2)F$#!&A?jVVF4o)ng)AKD-c&a;sC(A$B!KD*wOkaV zou@`ka<}9J(R;@5H)HM84nw1@WBsDWPiKfGG;bnWh$zKztWvdF?bnD&2PaFYW`wLA zqI&JNrJu`9uJ+$KL3yIehbapq6pf6=FmpJjnZr@e3{~VON4xdRq_lHOA|+Wjl3vyJ zBBV7FihxBp)?F6`i<%VLE1xIzNlMuI!nDzllb(=?Hph1A>Y-$=thdmN^qg{{AiH)l0A|GcSeui3> zhgxbw9xxLqud_U)M7wIE=rro#9JK0iov5@L*=U!cXQk6oZTTw8PdTD}LrU#Z&qp+= z`J|DIMpU#R3Q-%>R?(qoK<$lk)F+}X(O%?Ltg)3%JToZGYGg%=XfPl*@@$huJS#`? zt5YwEGSU%5KcbcN1pSgE>kI_64JlFo=$A!tl4=ccq<4whC0&c!EWQ%WL*13eDcTK- zL#56a-COLgM7tWt^q|IHqa!NU^~4P|2FlTVR1c{y)B?3dzYUG0L}MS#+f*K)*&p>> z^xG*ZG3%iEPL!t6jO>Ei<*SdPmSyI5L_2DWw0EK|^{fpkQoib%?WXHl=e}gj_As|UNpw4ALWZabyf9mG^Y(|ovFE@St06(=wGxV{vc`>H`a)X zxCs7}WJB$CQT>Y=sYhGst#ZPi_oB&Ewt93I|I6|5?q91v%sQ<;Uv@_MnWg*sR zMcOBgg`|&&*J{i(HliQNACdQiw87HdM0zgST{HsH9BV(Dy1x~Vm(EL8=B$*(Ebf}e z(sAbkMPt$!N}Dau)1n0Ft3;p02-59{j~C}xBL7rrtE3k%L5{pHq$?;vDjo8gdc7n; zvYRB9lBBYO(%P0JBqO`2H%pN!1eV~a6sZzOZtCgMgk-Q3N2SBs;uDr!jj?97#waC4 z#~Nc%iGDMp8I6=iRkU_^sd7aNq9ajHBr9lc#AGSuMtoGiCY}{>lIZFhZM9F=j@qDn zX_q9m7H4;%V+WWV4jNP&R@zC-MTwN|4@OJ^Gfr^wf&A}CK$JvF1bDjxv(nv@6S zDVmNT{vaO!4~ho#e1`UV8u!QxK(-@GTB9ZJDtVtsUz0XoY2%ePztZMc8b1_2%uX=y zb#X~qqopAc50&?vq!aPhTm;DnTDK+rOJ>o^nTH@PidIxT|0P|DzNm$aK$QGP1r)UR$jqsp;{}S zKDAJ-)ss4Ep<1h_QPe`UHr7tHJJv$AR!_vJg=%f2lTh2Ft%=&Hb|1T)lFL$CtG%k) zDd|?af3;H<0PP;sPVJ>6VM^kZM}RCOYG)!rzRPN-);jHDPtA2C=SW_bTqKz$l7Ave zN)k;Z$0}d-Vsf-n`it@<`}|Y-|7h)u=s89$N2imBo@3M!QAo6V5+(mToka93`i{}b zf2QYCMJH-!DzzM)PISMiR2Na2hrUE<(uzb>cR0OCvK7VY-1u=9CB#aOMoXd%(XA*- zJG7(qf2`;KPV@9sv@^y@j--=_@5Q)^DCGG0$&q~T&-g%$lW2TnBYQIZb(K7Pef+!8$;tAQBWdYW&(lag zk-Tzj`Q&)$U9g}8L<=Fp5J~+d=gJ5e+PaN?aN}jp49zLd^?YapTu@L zC$c{N*}8MQq*_`{x9}B$C{_7a@~n+%-OhC+55Gl zljcWWoazaAcWCb>TTM>V(yOT7r2o-=S*wrywPnAO9auJQ@fmSHy&FW{@3MdE*#b#c zS|#NV5cBMiFMupr((}j~AU%ufWaL^2oGELWe8Q#em(@&`PU%5pUrR@jwqG{TfFPZ} ztk&`|kv&NMAbNURyA1h>$nvT^h^(lFAnnV4)}@>%Z~0HUlz3V?+Ft3%^(emnsgNNf zU0jT!{#V*&v?hMA|LQ(*lG@3;LgA zgVV7mIv#qCZ|C1xXM4Q#b~L_mBn`y#4Xs|MOUDx9B>zdr743;4-TtZKC-FMNe~Juq zELrz>bhamBBREwuOyoh4s{4=G0%RZ1Y8&r2A#Jbh2@(CJCnXs`&ppXEQR}bt(^{{! z{z~7hE66uV+DWa~@{Z9=(C^7oqC1yWLRZjrwCi^d;^`rNjf?J5BO>2gQA|X!vHSfyj*D8U zH^0S?%gMDf@@;^9&&p2K}X-e$o?TK zh*rJCaMhD_L{I-oTP3TB-V`HSkE|)8RB5YZWsz-2dwf}6WEGO0M^+ixhGLeROr)bH z))Gj?^CJC%>^*vNNwyzZfRZ?lp6%7U-K4RQjYt+F=`O@iG7@A}l1)h#Ch0CD56JE$ znO3?KNw(S(Nd}O0O1cZ#iDbXh+95lU>{!w2F1wfB>Hc?~gQrS{IdPtIEZN|6tOciP zPZTf198Wt>Ue<~qm&19^iSdf~_4@GZ91rjMU+GxHGmq5VMsq5rvpxJ?PQFiKbSpc? zvFGXEOK1E4k_;1XM~L4O#l}T^{qXz!d+EOZ-`W$MnBC;RnS=3rBH8W@tEqO=TFLcB z4LxHM`|gc=_w_W52PG}&od@y&iR^=t8T8z^{0$^C@WaB{Rf4;pIsg z^TC$IR&R0Bvp@0=DNN9N@+3XzspUjaPXy_k7e!dtWzo@7r^%q&oIRw@|J@TzYIDJ` zwb4^TYO$;|YFqTK4@q2-zT}@GiA!8gek+o=%D{eEj?8qz41YQHlE|ylSks{`VBo3FWuXbb3a~&(^XZj5WQJJ zPv}Qa>+7lgbX-^OLf2FLdPjoZjG*@)==ys8L{`H8bwB7ifAxSYj_Q$EKd9BZ``9}j z^o9`m3>k7FX<03ox0231Ihk1$uMv^VESiWcdPnNYjz`CPs%(yujpg|j)0l~`N0h1W zAZfHjnb9{EMW4F&7?nnAb3~cyJxSZz7ihG#FA$Z=S4;FLUoPzyB*BYss3#=d=cY$R zxsv+zR+Ch}JN=R*`RL6Lv3Hxu>mhoZP3n{RT9x#E51p-FifqUlTg?NFvPM<&K;x@X z*7%Fsb#0CR@%UFnK2EaMp3IYmF|L@(57p8bS5!+6f70;Zy=x*L@_*-tF;18W{}U(F zySpN;_~-mk+$Qz8PK}Pn@xObbQ@txoQS=;~xcbrgq275Bje7iEPjf^2yVzb&`#bIU zwAa)APL!pQ6UB<+L?NPK?fA6Ui~0U(hbL-1+yhWE_*D6BMeiFEmFle!(Ys3I3!yj6 z=>0_Ei;;#=?~xHd6n$!Lq&{~k%G5lGJu9cHMLbrRIv4(IUHdD?Q5x=OCm(UIqsa-n zk5p;l=yHO3B2`*A`n-tzxHLOXt(iX%!O}idMA4d0_O#$YaY(F-b|Q zlvW0z%sR9BrM7XiKYA z>iYpAN{jXa;!BZ)7OjJ^9f4Lu?FHi3!9QEePWOC|#!r`l@$jYpW)B#z=lnB%F1{MGA)U(oujbC5 z?Rn#A`)G6Ic=a29<=Fk5bseW$&l5jh8sC^a_Gi54bjUNul6xhC#p^1MHrI~atDflo z_n*Gs|0n8yj<#Poa?cpQKE|j2Otw7Mp5@5*R>jl*(bhQ4iNCY1;O{g~PuKo5evIOI z)X~Q4@2*dX-~S$s{*T-*{~4Xf@1dkSKH2xP9c#WExyS!AdOO|wqu9>S$}qk^9PcI{dSKI34Tb@$UCe#k}~d^(TKO)Bclm6!GiS$&SVUa?c*${=ahn z9=-G7Xm5Lnz2`ypAoCUP-u4iC&x3TW^3;pH?IF^*Mlz>7`(iq@ zh{HrOXG{ZA@Fd>D9RJ2_y+K>=&DPhPPTza8qc_CX=N|Rm?E3UU^xo{~joJE^yWX2! zmp+VtZ+83}v-JjTeU(S=$=3U{_1HXX~3f z`bN9nkgYdqrw`wzt@mcjj-WSa>%H0K8TEgEZ+7&?>@wl5Meoqo+t{^#(c806{Jq&} z5R-!E4L@i}RKb zxvzM$zF{D)EDjxg@j#qfwgYkWis82q^hE@5cYPy4UrNw76U0;W1qFReLEl)&4C?C& z`pSa7wV131}vxZ_nil zQ>rC9WXxYeHDgD5cHpmUPabrOdMiU4;=G}@E-z_4lOio%K7y=@`etr^f}S;y)-Q=5 zt6~dM1wz|jK~Qf6hI5bc>MIQwEJmC8LFGjP9@zsT8!6 zjnEo4BvllxWka-v4M-J3kJ$j7VSQ4?(RkJaWdSTfT07^uq)LW%zmlN^uoUT%Xn*z0 zT4_Qlw7+_0tqegrVLh`}mLQ$5-d$ggAf2$DUn@^2hYncpPpCkUPFT-?S0q$G`>W?_ zD-j}{Z~{8ugit3e`ibd;ML$&u(g}-xsu83U7X4HwNGB}%sX>rVSoBkqAf2$NpcX;e zU{OVFLM^CB^dnEL+Wc#zYK0?Ji*#-3YNTosYH0e%063-P@T4D zjH(i<(Z*(^s)Qp|8LYw`X^bj?l|hYKMX(Zg-?y)aa&F)B#VQvjLB zEkKUG->vb|^8y8+ZjG0o64jT!^=0;a;i%;e$4k#`K9Wa)+aqn|ysi z+=MeLZGQce=GT9>c1PdDmPJY5&6X8O7A0AcWJ}WXS^AQ8#64t7ioU!pi_)Ljl4M0n zwJ06kmK3uhWrr*1YxlL8HIYRr)s__bNkkSUeRo`Tr8>;dJfvc_Bz>nmbp?;CNcxt! ztV$Aidz^0%^tufeyd)G)cf}bRS znaFJjpUDhn=C}bPlm*PfaeeqwBACc=J<|2*UD^KX66(?4vi<41?%Ba?F^wO}%6uZvmZsS& z|7v?>+WM8Yexq>Nf;`BW_@RCvMEyzkt7(pLr&!afm;gL*^yU{+K6?ey84ZT;X}1H2Q<1dW8CB zCppiB&odnY51F69pJ?67ocA&Kk=YM^O#BM*{_rU%!;?vWaDH9$Hu1AuVW)Wpe3qw{ z-XX6Jp{{w=d}#K8`-xxW?EO5q^e*LRnD>a!AXUe_M#(<&H0M5JUMIB|e2w@ia-Qbd zruV4#2Du-AuM^iY?~_-HP}}UF&QoSPxWjA%x0|itHnRoXYBqyg%qDQNY2)S(9u zlvG{=B)F18Ix;CzoX-lYRT2a5XYvro( zwA5HP#+3ofn097@(-W{0s9VvT!?~l}Ic@@ROKP@qEnRhgr=@G* zYVb_fcsI_q1>53**PNUduDPqp6I&x)8@%yGy79!lU2C3G>+MDow{vgO7wy~!^h7&X zi>JNXx%cUjcAVARwR3OKSF@O)ZPuIicwY$xmCNJrHHm`k? zGxOSZuBW?_Gg_G|2`$a#)W5>yxA|-jmxua!?NyYtG*=N?n9C@=9PH=%x+I&QI!T1? zF1LNl>^8aW9`hEs+vKrVb4Ckub@&|J)ufu6OHF^*&t1y7mzi94o!JBKp>_eAWV^cp zgtJ{ij)Z5sv)naMoH5sMjbf*oW`OJOW^$cNO%8H$+8p*Vv(6N<1?^d`5TTp9 z#0+!;zyZ`NYzx_Lt}x+Dcd;4d27&`A%Wl`3$H2$9N_P9WS#OHiGhJ6##1&eqcposwq0Epmu!m=Uu1^3!QfzOWVKJ2$H5Ke3Gi`hCz8%;vw(@38XWF9vaOACfK=tp>OZz5_-7@!G-=o-@&yf-O+V$^ZW=m9PH&rfOCl- zApb#sgCFjOxf}dE;`_;Yz~ApXxsL8eN`|@nNZ;@8^POEM(p_9qrOI+W~%(xxmcy=b3X&e?Qqw0;ibC;3PA^U+O2AbIhgwTr&ZjNqmVv-<$`Y z$2kN21!kfd=m!w@^Ha?fa0+K$#(C$M%Lq4^S=7J8&+-$^`Q}Q_mpL6~b6QM%ao_P0~s+uuRl zn^Yfvv7c+^n2V`9*PQF;nAzaP#Dn|-Y7O#t5)UHP+n?j-aC8n~kRMO_96!!qMLdo$ z-j5|c&W{1df>#rd2FHNc5bw0-`q^fuJ&*}|+h6a8n8CyYId_m5Xddwo`{${9of$xSAh^Om z;)j~+{dM3F;-|UVGxlja(Vy>!nW5%7{}kz`?NjywKheKnuVp^J!1>pL&lC6O3Ioh= z>Rs!Hn_w8hBx9P<=KjgPiy47y6)BIH5)1tQlk4Q@?|+NBL%3kFd$M^W)4|(~i>izCIb>v!FywO_Da-&yAq?Q6E2FH78<(iZ*?*NE~zTw~t|Y)HKl{x$omEkWJa zY+nDWeFZE*oZdI4Mta|bIK6L5oZHtR&P_<~bCJ&NbAq|Rio`jb7E|<^eC7qM_K69q;>F+o98DUS~3+&~q`yABI>2kYV?iHKc zy=-3sU$HOS<))iI(=X?&`^*ETy07LRF!vK@r+yBX-6i?_J`d-;WbZX+`ELGR>Mu7B zQn#9akWkfUa|L`7n8Z1GT^?%Yb-V0~;7fLwy@#{zH4kw{RiBlb*<4mv&=>IesQaQ_ zM(I6fnK|2^fdedGCh2EztXHQS;4G6(Pwr=d||LK=P#x7F0<5h^*ww7 z`I%jUOZG+lDznlgf{8whUt*g3u3%Tc)T}nEOcuY`bRlmsVToBpdNJ6Qc#%1icpi9B$ez3P-kE;AXvj)bqX@MjILAAk+?rO1A_j+qh^ii9AtDET<4$@aX)hU z2mOMz=26on=p1BleM$EV`UW?ewWd!n-`oh^X!-`dgPY8J)0><=K`+w1!JExZrdM!_ zx!L3oymPK@@Q3}~<_iMnUA`cl3qbGk2layA?60<7@VosDtV^5}IA>i_ke|2?pP2u{ z*5TZ`L4E4}YU>k{UEUzQO9!UoDvblni$x?QnKqA+-hzyJ!xUDAUAdLfL)0jQmcq-NGR-jP^V{*i~QW+nZ&t*Zp3EN3t1%k7Q%YX&I*2Ja3GC?V@G}wf=Bv>ja0hR=t5*G(c zfX#^O*>XWaSI?FY$^~`7dbX~u5R?xN+Ofena9q$T_|gs!#)4xx{>mP-t%9!zErUAL ztZVDr0xrqbw*_4RupaRjc0@2d_=2;(v}aJK4p=d$5Hzq!F28HQ8AQ)JfFn4kHZ{)xD+LvUhPHvt?+#GFGh{gCv2yAS*jyxrVp_S!ql?cnWZ zpZ&rY49W(-fM57bL7|{vkcse%|I&Zq%LZTi+CeR_Y*0JMNNFapF!4dkYXupCA{=E1 zl8G~r${2j*50d{Cp=OYt{0v|U@z?$@{BDka_j~MH_ILlb-2=Ww?i0SeEoa~LrEMwu zIO!++3yWj+A{VrT3iXN#F>xz?>YLwzwcXtt!zvC8!i0Z z|K{JZZ`*bL2g=tG9`k#BOWVTk^&b%bO6hNYt^bkowf-mKwWQYhx2e^_zD;OuH~K@A zZ1g`9ZzQ$Wzu=qOX7&YYHMh@^ztKPEKPTP^KIfkWcY^zgp8=osPlL~Z9}z$0KPG;P z@U*Y(as~%{EtfgS5!7-yf}CK^ptie|Yd5o(+86nync$^%rrqUV^fjqj%hhyQg3Q4g zuC_bi&mer}FQIg%y^J%Ofz51FTf-#=S%MnWtm*2wGu&ss4&hUOF*Pr-7u%QoE`K@o zn%K)Zqp7V<{Ti+=bwBkpD81OuurK?U{1wz_Y_FhJ6I+cs)m=50HAoEVQTJ0{kMN1V z$iCuV24CjPS=4R>UO`;dWec(fRjFUi)pzyWC%!)6V}Bv_FR~ZfSN$u#ipw5k3#w4F zs%zjrre7LR_haxWzr#@nQo`q*Zph0 zk!$F-gWLT!U&;OI6M{`Puu!1WGmIvRr@7byDO82CnN_gJi1YYTGa+~~3_jQDeH> zxyx7E#W$M4e4va;>6du62wor@phcO z+ns06wReGcySv=^_B_%P?fLd;H`a~;$Jw#qQ^d>M-R@lQTsy(;;M}L&4tI_nZ=Z2b zyD{JxJKHYh+`HUTcY&Q~pQCh#d(KU;=h)}nGUDe6&$(yaGj6thmTdb^Wwon1_wC2q01l=v!2uXfuhzs_zaTx%D(%P3joE+<|@ zYOz~O`L%W};Tn4n`HS2=?h4|2+$`cXZVK@l!aZ&^={0VZJC}GBVYORHdX-z@&Ldty zSm_=iy#hR+xS(0H32GY+rk;yTv6@S|EIj)75r>o$MyL0bFCU%TIn1Z+%+t9&>tI(ABmu;VRpQv-*O! zxm(>pJIP%D4j|4)O}#tnakt*}rnHY8WCz*{TwZeYmZ>M)MvcLgO>~2) zb%D!6soqDm!9C%6+B@9s;O*2KLam8z2;qE}o6 zo)13a9(K8?qjz6D={CAyls^nU>>hI6Ije{5Zf|xA+;BV0J_J7G9&|aWnTvO3ZE{b# zvnlOv&$d^&n_Uia^lq)qZj&2fhua6;S>&H>&$1;M_3Y&5Fx^O>WxLr@P{EnDv?~Rc zaizghuAA*j`b-pA>3DOPHH~aOXL$!!VbXdRmNj}8mNi9*ttm!qO>tryzVpf&S?w&( zU6%y)-a{5jVryo>4=oxFy*03~xr+3a@JCDPN-!V$BfX)_nmz7b_o(|A+~f2{Icwe~ z^{D%voR7if#P7Jb$@z}-_uzfR?{d5ie24g3a=ruaCw`CIt>C-F-;nby_yF-Y^xy;T zeM+{1Tiq7-H96maBj~XY$lC&Lahu&&ZloPyzasx@x0mDWW-le1-9hrd0!P`AcAwL` z&h}B34ctroCHV*4mu|EjWj}O!H`<48AMqFDeCfV$t?g*L-zDm)U&g+S#`DGuPg>1KU#esq0|d+fT{)%zZ-o zQ}=><)9nU#bIuEd%;rU6VP=zHb~(M(ZI^qI_#XSad&4aQ@3G75kM1|pzq#Mt-S#K< zBlsi7_u4ny>+W8A5Aj{(-)--*hulwYxqaQe2Hs1&l$^WlefBl?s=LoFCthNIc89=2 zl-+M%b+5SlDSy>1CVz=tY=3b-y9ewm?q%?P;zi^vwu|hq?icrZc$>Wy zyxragu7HA_S!q|0US(H;bL=XxGuLybi|q_{;_A-KwR6CEb}o2>od@!LE?3s^MMPFu zZ$7XeSa0^)z2E}=J^SiA!L#`H=4}2w+O>?7X5!qkt_){=VBe?y0&@p7&tezO*S}m> zO1s)FHYFt;XXxvTp4kZpv)fG{8Q>Nd@V3KK93L5hi;v$4(wB$vJ3x~(WIr64Zcx=#?ds8qxrt^pkgvZjB zdy^C%H@DJ5Hv^j^rv_-vC4~k^Y0^73B{W02b<}N1nIqkTxQUe}vI%{Z0ZdOl$-v$; zCZ`FKcPrA3NJ~D;MBE5lMJC%2Y-Af)SuPq78ru4#wJXd*d=2&_t%9;EX{{9IvAMy# z#8;EAHB45etFiXvXH~wA(yK^c&5C|K>Dh!_NCUG&%w=;T6O0K_Rvz_Y5}3p}&RmB4 z>Wt)3XC!etc;^+M_@xW^!tM4~tWMeNFJ>(F{!3`3`h}cd z%>s6FRhW(1)h!@(hm{pL8<@>zwLeq;7p%XMr(_q-3TDM7b%-3T6_?V>9PZNc_C@?}q#JSYoqZBV*`Z^@C( zT~gk+MpD~1pltDyPrnAg!5S|a_A4{hP64No`z}28ZaCh(aM*X?qD#T0aN~E#e;1Cq z91i;u{P+HlXD+vI!mF2o?-IWVhrbuRm-FA|T&zw-{Yk*dYJ#gT~;9~nWJpBRqa>T>mf&(wIZ&A93HQ+(Gvv~f4cDIv8 zVz;Xf-`-7~w^%bCf+K6Cc!(ABVL0+vJPW?IcZMbbJDTA7uu8GqYb-R>#--JbJr^W zIM-Q^E`BZ7d6cjciR%;2A7%Gr)z_N7->e~b6}tFU(E1u`twdA*4QD=KB}I(3A7alB z*LO3-%9mjXR~X9bz86dNm;CN~ZZ&6mvzoK#ps)YdJpoEGX>Ipm^Op>;&kW{VNsRKC z*huLHH1(2d+St8ZrA;U;NGjNC2H6AnQw*Z!VEZI>HiADO0ZBsm0(tfTWdrT!cu{;# z-WP5YtM?D!5AI1jfc$|-3~iAkHj}@}ZVp%Y{`L#}H~LdLz-|dw^)2LYM&kYwACG>N z_P1NZm3%9uTadoLB)2b=@}=p^Zu20vCavV#sIwLM+L`I#G-~vL15LBN$?0QzfxWRz zl<)^#DPI!YU?j6_Fj|2(nD$tjW$`%Z9w*%nTXQ?w`8amx_I4vHXGgFj_10sL{@kr6 z9B@yPztPD0anLd%4gbb;8wHUNM_zndYjqncVP9~>z~3JxEBlH zGw51&gu0Y%c01|qb_Xa~<^%r=y|aUJx0@YCa(IH5e3{@SM<#g5iwR!RVS<+|nBXP( zCHRk#_7eOj$h`afUaXG$2+xAgV$0m;cVee}pX+~sp64LaP$s{J_Gj{+A^~RNtOWlQ zzqP|WWwbBI=-7efYeGWw?}eabv-w7>Y!@AJ=r&)Mg}=j{vVsLK0t z=$$GMzlTkx0(j6#6IG5ly?+y*i1b`7gMY^Kv_0%IT<2-?tm$QY+Gojm#-#Iam^Z;U zsTcUy@$U%8N$2AUC$_mJ}z;dS(eZ-w|emb&+;^B!8o)$oTmDS3nR z8ytN=zNERW{sX%WjmKWQhhKjitx5{ zH~=27pW8RdmtID8syDGK74o;3oLKN~F}bkj-AeivbjMk+V+FbyD?@I78#%Y4 zJC=RvcJMYd$g)k{gnc9rmrQeO zV1p^b@2|xQQ^YSM|4!^rIj|ExN=ad`Fzs9KzDED9eZBA-bnB0~uh7>&M*ezs?2o%| z?GuFW>>`sHd*dRmun;@YqvlP&hVX`8M}6raWM9x8|2yzIwC!ujk>=t{tPa}Oe-D0- zZhbM=S%ih`H<#J3=1On)N2#;cJ?g%&U)mLJqx%8;0loDK_apl0CDdGOmf-XDn_Got z>J7h!nvbGM`P_bCm*UU%0`|HWsId}T+#7y1`D@UvJmo*PcbT2$IV^t9QR^0n>;kC5}4e-InwYyKgujIa5JsrM>5 z(l$PT6;s-}XZ?J_GyVqfMt75&&)M@x-+;zV+TEMUd&V2L!u@0|Xs}@2Py7dWc*y=i z_!%^mI`RRh{rB(Wp=~Gau!?CfK9{S_bGNvgx!Ns+mDtH1q%1%O@}T>T+P`2Y`<-|W zHKo;i4(+mZK`XI`Jw&~9Xi*+=zf$i_>}tOeOWU&&OW4DdWdPHI(zQsRvl1)dBOGT$ zOYjJKncK-($TjDH&!fH0M1DrBiOY$lw^@k>Y5{mJc?sZh;ziV4h^8#TWd`phzQDbJ zX7mE`7ojJ5fs{0EnZe9hZ_jtqWS>v|M6_Tpl3Ge`BDjQjDXFaJ%3k#6p-0T>vVlv9 zCy;Y4D9yJtjM>m4X2V*24mlIh3TAgXz`KdZlXDLGxMk#=kB`tx_zOwHeI8ywFX1gD zP4)$(CgN}OGO2UTE3Ggdjk+??5ga|(m)iKlUvbmp`0O`M5t_$f5D(h<)LHNP`M zt?o?p!aK=%o_HqOo#(+Pi7%!04sa&%C0t<|cm*Di{keJ({0ln}%g?X~zI2=T{f>m@ z_&aVQ)fc_iCj2Qklj;*{zq*(!(eQT0;xClmx08_$xRdEj+|^u#J)kRfx?uai8vWv# z~Lop zY1+@Cv>Q5)>(INOP0m^P+-!H-+<5A4ciqkPXyv<8dN$rU(({d@e4FcGE{WI3|a$^WRT`#;yF99#1Y&0c3U2k%FncjGd;$;f<1}~HE zC|;iUh!Xl3`Azk6)9{Sy=ceOR)X!ar4^lrT52b!iUQGSmMn4=M#*JPcjvM?)JRCRp zQFyy<@T1)*a0F$uLLbIip%3FMFHg)_{!F|zXZddUbEhf!|--|5{ug~_XNK*8XV0PZ=}vFum@hNH{c1?6YSySGuaal*?Hv1qjD7YxycW~ z(^IyaA?|U!uKIx&6F=@RA%5J?Bz~OSC-BL{gUrn3ta*6ojliF54mor2t{aXQ+H7*> zVA0v+2V>tEgcs^&QiI%jt{@xcrNry;F1!@HocMY_3_rH(Id^vGS0}HyVH{uUhu~3n zt(RBbom_9AdyM+BXI?@47#?v~;P*C!8rS&2c;j6SUV}&AAbj|)0_7<<5dS~C9XYQUmg_zs>=Y7OzDejK<4AH;FsYWxz%gA<5X z<83$r98dmyu6(6mg|FyXP(GupNR0uj8D)1KKm3UCz;xn4Xei4|7Sl{AV z1TOLmeS%ry7lVsE8cJ%)J5YX?EAXql&1W`C{St5qHKbo#=(CWcZ+6|~m-ejDacWBQUmPq-Y_SB$3ZO4q$x)Dv$62*} zGxD3`&ppbI^kpc?ga3UVlNax)2k|B>ODZ3}`1wqJunb2{so4zQ{j%gV3B5R*kkb_3 z$%ien;AJ>O`Md}tX6$$zZioRUd5D&7meM8P|#1jSjK1u^}8iMjEYs^_q zyq+~E#M1?Z7~RUDJ*YmV4S3d~Cq8A3ynKNh;W7I#csp?;QjNWyN3f|5E^2s?uG}kY`elf_y{+_k}K?uPhUfKCcbzLsnaO5rh%ZwEUi7in}v-O5+UjN8))O78AJ71I1T27X@8m2U%x~bth z;HO%H(weS1=^D4dMV!Ar9fSd|_&*a1p&R%xEf zFrlr$U}Y#vj-K-{MmBxJFI6Mm!B;0;!IcN)17J)gR}rl2DuGp8Ww5HN0#j$^0Go}y2Gr{u8!5SS)p$otM{`q6LhTSO`@;iRbXsuk=D2J$|D1p#=m|tv$Zs+ zSvv`wjQ9K$a;Cx?OMv{KK(lLf^be>K+Q?Wxw42(r@SN*c~;6U6N(L_`{*^gf!2Cvto|7tIeqmM?1Pf9o z-MF5d(#-ssd0Gf8M42?<^+C-7bmPQ_Lc8uE>impZ_7C!n)m-?AUn&9?p$1Qf**a*# zlR5s8-%sZGubIR@5Pn3TdO6ZiO*;tbs3z%JXufON%g}LO#t7FSU%J@Atjp4gUkYBz z*`IUOI-urPbxNfn9>O}_$PQ&?Z$!E}8uyv}hBWLmvE2+MH^~k|LP#Rr*nYv8wb4+1 zPMqHk$G1K|rAg@T^{kro^*@+=Rvz>DD9w)@Kw5a|_rEuJ?MUR7yp-m{8XzrveagQx zdF&`;n>>`}#ac5OnI|_nc|t4Dx7gLrLAvb5Zs?rQ$~GRkbUbq9*&K~W`kg>oS5SVj zdTygTWn)3fritvZ&IR=hM5I(g~%z$(?EGW^)U2TAHGyi(&s8$jmNk8zPUTSUm@rLb|9;wtB8FnVb}!JZem; zh;3pT8;kAcTT=qGJg?LQJ7Qtml+`gCb|xEIo3de*DvAB56d^12pHiUgRkHAu24&gG zf_<^6DGW9+mJWA!SF#cy}`RAMf70J}?W_chNy%76T8 z^p~HY=X@)CQt&NOADf(RANQZr?WG5DQa=~ZrhP)aH&A_iV&p&m6(~E(9;_Gp!MBKW za8^!sdmmyoc%7PWn7r&24}#LAzfG@aRdF-vE$IBKklJKqLwphnY{4^WeD{;IB(^6> zZ9<3t3a!uYwu2j~^CUX??Iu6#?hf!Nj+J=YHl6$5B&y zmqXm-1nQ*+&mopB;t$)F(9U&4`}M2s$l1TyvF;Z%U}HIV9GW6|f=e@$9u0={7oDj4 zs~r>Sz{XHhx|vQKokzU@jnlcrt(`ohTNB#2&XkT}@7Ng}N_hYVjQvnTR?`aoMFF%O zg@{{`YR#UtGqp#tNA1imwhO6|PCM2S;7CyW*5RP`yV||>=Sr-uPCnxm**O#j3vsPs zlnw`55?5fqQ3NbPS$WcuK~jjz(W5EgPUN$4q{<_?JcndamYj0-Sf_Wa))J*UU;<}_R0qYRgBXu!Ymv{#8#i6I?47@b! zbKHP%5k8p>Lc9oFQg7RjUHrZ1CVII(c8D7c_9niEoO@j_N_%59JBxei6+SI0ucuz< z9Hp=5YX`eQU?1XTZX#zaBiw_Yayg~<5qh|uoFzMqGzR^wcIC3#4MIyek=pW%>fx~Z zP_Ku*KTJzw(BBSp1HgX7ccIIi2u|dj?p8Y6?y6~*qQ$!az2szKycDU?#c~eVpRoox zI@?O4dp2iv$KLfIsk5xKxZOb6(4?n56YLgxzMYAG+7zyL6*{~r;AF151f8txZ%e={ z(S*tGbSh=Dq#FaJ9lL^loDMc5zJk;&^iqvDx}0zYnkVfiE+bry&Z#k}*4Rng+G{wv z+BLzV+SXo6{-x-aE=AXLt!u*3Jn&kuDe+uTUZu^5=YY~VHz%GA%6qg0@%7+rH-L6_ zwFB&pw0j&lz)EvI&PrP@Z-tw{G2mGI^loxv@M9c2Fl zdL)+Vw)hR*7<#X)Bh?9;_gdl`$dM<9yj|p>)Dp{dQ#@N9CA0coeI;?67*itfQSv&3X8G+(gaQgl1qf>a8ZPIo9*_)O?)K z9-H<+YR|zJav(Nx`9`fGtj5Ph{*klo5aQXS=HMeBtL}rG*B&dn{HInDR^b(LE2$O4 zEAa}sjnpH=E37=Ryp7B!)sNBN0o zQ*Hr&Bz}o=4`3_aOpLvk_-0DdHQ;Qn{s`x-FnUtp5%&MrlKU`6kANS9UWyN6ZQP5M`(d-sK7@sF zAGYp?*!%CZ4}#06FO9)6@ZL~+u$6;$*I`#*k8`w(uLsuWycyDZfoD)dyMDY3rSAf3lPe7X9*5Fsfi)?)kZ=)N z4s=;y4UVUgo{pZR8u3)ZG_)wv)l4BwWglL_RAiT4fz)^CUMip^_?Db+2$k5?mnZjo zG%MxVp?yQn*M!RG2+EQB1Dct#U|Ej7qNFld8Qss1;@xHlS-5uh|B zy-D>!8}S*}>ctgDp??@fZcnr}b**$5(oWPxlTwO0)oc&6KXt%5lyyf#bcXFtP7gFB z(i)vjPIq)EwMZE>0}VlG2n>7w#$Z!o1C=>&0PQj869$0ND;RV~gTP3KRLh>l-o7cv z-Ow7H#on(O>BhE^?H29?4Z4XI zVoS1jFXh&wQ+W#w$_K>jNu{7GNwH|ZC@qNwWxXki-lV84hL)rl+A4V_7DHE39BtQH z^eM%ye40vtB^cc`jH^L+Qqr~!J(Wu0H)+v9WaAE`MOj1X29BOEh0zCXKu=K^lwZL{ zG#!ONc_zp^vLGn$g-vK)R&$m-A2xxT%w{wzNp3URkR-RoG(!VYgnh64b(*sGDZ;*8 zUO23gT;u4 za86NhDDg-%7Qfn&oHc@-SQF~Eq)rR=#zlz-Q>!RgjNDPw90|%Ns1bFuv&)kgOe@M; zvNs+~st-DqpKTxLddd^g$?@}OzJzcti3v;*6*!|zH-9#9@4U5JJ9BI!)X4|WOD`RUtE z90}!X+7V5Ra4Rc+2iMVUGt)xt!ZddFGtrE6Ag3Z4l@6q(S*ghJc2j{^D9_UJXikLk z`7DRFL@3|RvS?3)PouFagAU~xY&xT9Yh^+M^deI@szRuY3^IjORrcRgkVGbvs>U9F zG8&Odq^h&mpM<7lB5@5ubu=IoN!28-!S1&gEnSG-V=6oLUL2ok@vLBXw2+)Gb{hNh zF19zj_Acz|d$T*5LES}!g{~Vl&qOPL)`FeYRCG}bIB%-!Y^VPp_Ra!ai{gF%6H9kW zcXtZ{N|z{#iUCq879c7rSQyw6N|y>IQYtn`gCZbef<-HKVCVmH@B04E9ykZjfrIkB z{^vT^+%r2f`@Va2b|;?ue&%Ime-d-lYnek`&lxib4`4w!gL6*9dT|E2tQpkrX0M~X z8>{2%Sb<+py;&SxkKN&PYWKhvayl!$fo>2uo%lr7>koq6h^LY}7#xfpZYt%2TqpX3 z)4(2_-w7K`4{RJKV)r$YS=SRRtu*5vZXAJ?h zTiRoM>LsoC?Ab`Sd~2%qI_w_ada=M@kdFG=Tmxty|BuS z=kt1omWOfRI9B*m$vYc78%x|2LLYD{@nmdF_qfR%^&yR=4SUOEawZY(b@Jg6-pg8J z0`{A6?h5QE6R?a-2-C8vTtRBQTNzp&R$>8Q_bl?pyP<>$?sATV6R=WUhW$i15i8ZD z*ieL%uu=`dhBDb*#g*QI1?OSxBEyKUVjaGa)G}h>FjhcU6Ax#dzl_v1to4_IOG(Sa z;TrH7Y$l5d*MTn)e}cth1*_s&T-RhX6Klm}(vw)heL}wU!ViKEvYwx4RX=U5}l>ad+UU)vwaeGx>DjBVsa z>}b*(zlhC5-YDM_t^FT4pWmAnIlH)ENSzraW=Bcr+2H?iT2HgAEl zlst~TCkJ+e+d_Xsq4bQo2zP)|Q|2P?cGOU}QZGBUmRnh)&%g?mje9~#4EGr^fy)AA7>1RtbsK5EPAke4&^V~6;_<|prc zTY#evK=~UK#7^`PSb(??mX?pekFc}I1|-~yeWeH%A>lS`SMtcrf|Wu(pRy;tVT%&h zVds$Frp2~V3@panPZlE++L>4rnRONw2d!$%dfL^Pk=Q;BerlJ1mtZqBW(e=UF_W>P z8+4mDgEuo`P?IqOMM|g`sRQdGZZjr-Z5Q;3>=vyy?#KEhhasR(QvPTIpR!N>BgwCNpHtSKp6qkd zUl97z+sgj_31LrY-R%pCE&7tOKJ>r?D0`Ko-gY-5_5e^8`Q4%wmvh3Ip7@X9mVnGU{T_F%sA$Pb15qpat_5Px!l%e{xT1oM_F-7E(66s)M55A zADmBF366(=#ffV(OIZMl1F21_j;+P);z{sHj%zZyJ_SC-aSg_wh2TPt^LkmG>v`?e zm&d=F9^0CrRfVnv<4<0(Q zNH^fTH$m-~SDo*YK0^FYV`|n#<@heCCivoPwoM4{+FYEKo88xBZElEK^9@jY?&b8d zB2?JLEPmW)X9n0*XxWfb*S~aE$?NaFHhb^o7a{1uh~3c zUN@7KwfKwj#QB^o_xW62;@p%Ac2 z(E_YE*V~-b%!SRQ5*oCJsau8_krXTUQD1yYMdGr2SAM*lN@2PAit}E@vQo+C#AZ_2 zSMoEcBfh2*@lBjv8Z3=1Cp)EBU_yV%n>jA)#S)cb%q@$5)O4%?mF#o^BOi67F{tXR z_>q*C@zW^PY)?9w(&Ux#;*d)FtklVdwWJzelT#_3X0y2J_(*0UC##!6ju<&J}_r;%4#_3SeO?M1EmH zDW8x0{8;V8$K(q+m{ZY#mh*W@=ffgb*p~7|2qoEV@l^8jkT126JoWRiUbxGCXNuU8 z{yS3=Z@1j!(9YFe+*uqQg!U` zQhw}U!2Ju)&)RrPZufMxZaeqGg0+aZQ@X=v=d2vIH-2&jQ0EpR?v4LkA+QK>Z#?#j zfb!hy9s2I|4t?`>dMQ74digi)^iqWE^gD>RajmueHo|rk!h5;?i>comEJ2)&?~+PK zJncnZTDOa+!=ACEF9M~C%SvfBtd821Vwcy>X}i3%DZBhm;;ra^d*Fk42Ju!@w`YJo z_|C0_ZK$B7x4VGPxzK0f6QmRp+Z?ch83&Hz_$VksR##yZq01 zev0qg?Zx-)=J+T35#O>EpUty~KSB$97AQ^ddHxqHsORws15k_qLh4*EzyEW*b_FqfH3iRKo*Wdq+4Y42CA1(SH=6BQAOEcM*bU(D# zf0F9srIzgDrHcH(pTOB45b!H?-`NIOM#Om5b1VG!;9e_btXR&5*h#(v#kV#j^{s7$ zo#Y!^mzwpku&m_z8e=W_#x^E=ZR?Oz7kgA=_q8oZ_{!EMrw*2!l^zR^U+HVHZ`KK+ z|7Ta?n&fFeu2rPkpbnP*r!>B+eRXD9tG(2{@&c{Fu3BwE|IfC>?NEqE{-0Id8ZS-L z8ZVX88ebLN(-z9*|Jj~+3kvA=U`Jy4e^zoY`--jtSjkmnXReN+|7R!S&Av0b=daAM z=()c#$D#B7lC;!lN2BLPm5GM_3({Z0u(U!uE{$6&|BY#l*7+OqTKmsUGt~K?Q}YY> z8fl}YxjWu}M!tRr;9Jwhe@a?@@yDR)-^g)i@HOH+ra4;wJ>=`x1Uhpy((-in{2Bl{ z`%fs{V?M{~S&AKXJ`YhErq9Tchq!b|UsA%Jkc1L$Q|Rp}1<+>yv1y6A`eQ!l6Z2`P zO!}1ipRtpVR8wDZMhQHu%i=@6$4RC1HF?Fs;@I}28+zC8<`bm)>w`Y~6YA{2gS$NO z4(xtK!D7TaIHMSL?Kh~u%NW}S?8BKKQ}Yx2zAF&Fh28vJzmw8kSjMe2>=odwwYw?( z7!UE6eFYSVj@%u_TW5EXvm5{MS3>_!X#n5xZ}AE5U?G3UZ>P=dWySSht{)2W2hu)g)6^mIZIY?mK|7EJ9w!5;irQKdX8f*YsbdpeoW z9sjb`l%7P+$=Fx5+fz5fNlqSeJF&8EC+|c;x6sFKr(4Ho^67YQuJm8=uuZ>7j`q@!|7R8-_>L|Mp#wW7z3$(1S;^}F zcED1;iJUi_@mYO))?AzXtJr_#^Z5$tweTJC1(jNHlYg1~S724v;rY3qu*q#OoDHrg zUSrN+tI+R*+fP z@>^mlmSSusVHTEUDaIZk%nTK1EkWt`9;3eWch8uo&HeBat*}|QqTWN4H3uIgz7J-j zHQ1W6hskRWN)7lZXFUc=@j8N*X^#cFEp%xt+szMrsx&D-xckkE?gj7# zYDk~*Js!7rW4peC)ZOkrN>N3bdF%#&1qsWA)GK$n8RXoDh3HP~7}H5hq4YfQG*GG} zDVnF57m25W(@-KUBA!B+YHr4_af};@U*i~e3x17b+^zU2j&Zl)r#QyljxWj>{4u9u z>3_*fbM}&#+H48F?UO+1{g$wg>l8QE-v|pb*58D3bgaJ_wr8v#iB)B+m-p;ge=D~5 zvHmvf@?*V}k4ybTEVWBRzx$>5e@=3X`KIaMbiQK-b;g47%bo7|&p`R*PA6vuURie; zd1*CxmmC9*;ZqjjM|nGVC-I{2Hy5V*QCQ2Sa@I6F6GxGn;zyfN zW->Sh-^MZ6{FdYYsr^02VTWE$Y8?Kbqw(*2kxy6z%4_pQj_<}Jatvoq@?)`XP6Xva zDb3RaFa6U5(i6S>Kks!f;9)u%&&?Z%Um*1&ey#UXW4xCZY8*()OA&Ri5WiMwq3-b$ zvE<%E`d&OeZ{W=5@oK#Rf7}tIo+Ex958dlYJxlx?KD*bEdWQH}{6w!MHH`Qf|1|!+ z!@yx-THd}-nO=*6VPV)aO1C~YyH3$FC zvS1lg2`mfF#RIe=SjkiXE24#(>nnis@BqD$J8+u05oO7#<|g7(&CSF@DLZZ^b&9!x zZ+h6@K+PLXInI**RWb5LgjUiKq;4=HsoNct;zQ~up)?@Zqp>Ou7U!JGoLeqbLY;)# zsRX&#p~)(NPHCR69BNcf0;LK$hcmmOg(^vnb2&aC)UKR}B1(Q-*AT8n^&~IQ+MHVl z<&AVA(&3zdQYtUj;j0Oyz*5w%Ma|l%m!w}C9%|BtW8uzAIxjV(>gkGVY5|^~HK|!E z)ckY>yP_W%7TSr2aqjR?^K(2Xjmrg;bum|Af6oeLrCtp_p=PN6=?r$JeXqnapAF1L zjp{sc3w(8RnSTOY;Q6&FYFTtt*{M;D{OaK4Je5)k$)EUgUkx1UFZWkFF#*G!to*}C zUky(z9iMdHIn6NF5C9VykN zYdZ@b`3g|Ft+Pn6HwO9Ax7S1W*3(I=B_%%lWRP*RX!}8WBQ|1K=Fij0mTzq2ZO%rV)C^w zfZ_asqzAb3NXy56v|zz#Z%qYnum zV38H0C4OfH)==@d9}%X3)2Ok9GWNxz{64Iq`i`yC`3M`W_(|;yb$@8d--?~}0c@M^ z5@vy$ITAB93%jrQQtdA_3;V8i0~9y*pp`ObJ~$s+a%Hd*D}Hh6Rh&5TDx@pZ=P%$p zt*Pi1SZm6&vb3fGEB&g}sRD`}FXzgW8<4Jwo=S|kbUy4N;KX@nAtzvktUUv?zlaUh zMizZhDbi9H!8EaEhG}ArtbKlqfzrcRo@gQ;r@@!sA&P9Y3cCZs$ zJlKgn9!#A)kAiyl{OAL9Ts7! z2eR>g_ose8!a5iR?JqWzFv*Uw(&tHIkOOZ24RWu*&i;lhlGv=JQeX!na;|{c5RW^` zO1U?R@?0?XuakRK$mwF)ba|XK6S>_ma>U__-<9?vkGqSI7t{_!*ix}`OP!I=-GPm~ z0C*>{^b`d^DXJcz@9gEq8R>EEr+4fPK0v>DKjCaQo_ulS($S1JQsPXd{sYXQr5F-R z&b}msGnt7?YbCa{x0^tHG4iKkJ-7|qSRwFs;>pbX&U8~aSAGGL!?bipGw5IYg7*pskNTQ zUNDk1&q!83e_7+MM+tX5{NXd?Kkc5uc5o6aB<&9K6l^bj1vzp)!YbB?D|ct zAJ&87%WpDb&~GwQN!(;!j|3VmPwQJK3yus$N?wYF=nAu6*4lK>TP&&tntCz~@E~9mHDW2{&KXQC47UG|XXS-3XIHZ0WWu$|+75njRwvhXQ)NS@LC*6eh=NfIK zi74d0Cltm?`@I!PwRa+Oxf7Uw-OS8O+P_`4BVo5aiJWexGij*+rS|CTMsTeiob)9f zu*K}QU7Yr#>Oy{J*B&d($F@D;6MHh}o@AtJ{KU2+>;a`VIo@5zJn(qV>f$utJlRxp z+WV>+`NzAqtp7i?)yb)b6`(EYHiXYWX-iI_es|NFlFw}`YzxBA;bNtE6l$Nis$RP%+|O1Q<=+eWlrA%+(yZHM%u^onCI5S=F$SodUL|JR;o6kv@hoxX(hG8 zP%U?ksf|YA9Olxs-EO{Rm*33_eL88W33q#`4?hyiVLl?94xY{`>m$}zXEL|1gB`y= z^Y=QgA4hdTd6)JzQcm_|1teBr8lSR)wf{8tAq>Qs=0n0+;91P6`>=+p@A?oLxZb7# z{6KH=8o0Ar12zO3!VmO9buVlLGtkRO_xAzZ!|^Z?nv?&A-Dffupvl-4{s4amrOf&j zE5i!^DtB6;^Bz)kznD+^t%@5dUR{8I-$gJ|mlGoX+_TOSFTJ68X!n4}%#U`_w@>Q@3 z?^EMF!f~b*@o{F2{|d|Z8usk?2K)wV(;CiQ4Xf~;Z)LU+T7#`wcW&`*Ok49Z_19p} z{=$8Ub^A+f?VG9F)@&xU1KY6@9UIQQ$A)wDG0dhYL~EnderQJYmokE4_4Nl*!SmhR-{7u6l>h4 z?lY{cJIS4Ab};K5$|qcomFRYNA-lC*h?PMKrO&X~eFpb|?-jM@n{C*(=bP93&v zP;5)Rm|sf`+6&9x!*C}L5x!vc^sc`G`_rvFfwvHj2Bj^PX6Xy?3tB~5(WY3cq%EC= z{qJQzi|`7&Pf9QR4*O_ciH7(ce-$>Zk<^)KW|>#~Ou|}rpOn`4Z9klK-rHWQJ~#;S z*e{SZ+*_1i<93?0>@vC2yy|zD?Pdq@E^>CVuGmg`8)2Q_P0lXU&Tr$tV(%og7Hmh{ z-fzXa-=6$-@L+ARfwv*NYC4eL9**lnSb`4zBRGN9*vi+L*3^2HRmwKA&VS5j!pLBQ zTnpdzA@y2eJ6~_aX00U(K<{H^)9N&TWHV22*wncnrB;bNpJ!xNY#iaP*pAPU$i%>rLU&e&%>1h#v{h_pHHE4DiTssDI**m)uQ2kk+6c?L5e8wEX~ce8t0-M*`7*W#qf{x?f7pYO~pG^6z5lhhOkpNNc2;w zEpSEh_?oE4iCE ze#>uCiC^S?HQyN4gp|F`({wGkiFh&ji{OvM8gJw|yADp{b>i1ZT@P*~7DK!kTnsM- zr$hb*!U#~h_4ULzIM|{PZ@_XZ7WpOcC3boB_75Xm!fr*-LRPpG4$awRuxCu|tZ+HJ zSutA+-oCi4i8`P->0)S7YM`JfK~8a0M72@D9EEnMHjCgDFk{ew#6?lc)b&LvuY@S$am9CJjir%9TrKM0v)I;f07-dic zP`j)ZM!B=p$e*bmEchzevp?~CS>-muA3P7kD({qygcrdVS-Wo}ECv^|uHQ&l0xp4z zd7b+5Eqa#t1G5^o?E~2K)h;XFUI>jq6^{-D%!<-wDNIdiu4SpIX`g_psY%`wc-hso zPl8Xv+LVRIeA|@s@&_tMx~wnn-+&!0Pfj_sFz}nE4Emb4O=%d+cfm5m6}-HYDp0e$ zmk-}lraEDvspwyar>*Fp<@zd8rvh3M`399@N8xudT|7&!@y~GW>~ahfT9We3#(H_z zSn>_J3hf6|Lc1Xw=NG~XIZ7>Ri}&EKic|ic@qFh(a3N*7s-+u83a)Pg%sj3^!SXk~OX{x{y~~A;Ma)F!69S7sIeg zXR*VvI%lz0W53Q~ufd|7#a@ezJBz&zh9D2RmnG<8^6^V^OVG`{M92@y1MMX=I4Ev> zfNJShFHfdheOX%$EN9DuwdTp6Le=W`XAuUr7E1;QhqfgK{c36_)5p&YR-Tqt+~N7L3D1)VUDV&3UBH zAv^@0OWdFMA>WVqA>WtqFxZdy2|i;QTAIG(cvFRUUcX**AL;w}ByT#Q=bmpX>9C!E?A6! z(t?D?eIbs7kHa{K*O=pr6Xt@2iHpGk%=Oyeajq{4e<7TU4gV4p9uI@Pxfjw<_eOX4 zFdWBVl!y=eOYPa%CNCv-h}CY9^ZaGx$mgP$KO2>#yv_&NN4T0n=ocUH1FdZP1JO{j zuNZaYsd1L?=`XiEeJ@`Et@k{C5;>Qndlge4Z<@TOB0R)Ae=_;fDv5B2n! z-vckCQ_%EDF@B1dAJWn0TtZX0A?J#drVy|v$m^PGGHx0V{1~ zHw|}yX5Se3oEszmb9@6(-Lros+I;-BQRy3au2OtjC1M6vd;tvMEKpun>_lnmkY9&# zV|t>^HhjOny(rdWe6!IL8S|Yjg3@j;$aj(Ad(luBqg|SAV$IQv^o^w0p^|yptIXPN zB)yiDF$MivR}kgpTG9p3VH%SkjsPx$-c>tnjt5H-vws482{wM__xw5->ttuTvR0P1 zzN_ns6-AbmuGm1dd-cuC(LZDsG?Ur-hs=W(fPuZrXCVv=F<=~xIEaXSh?t1 zOoUj6m7utZuu;4|Bvvh>1wB5_(<|e1y1(0sqHJtPc5zHK4eO z^s*8M!$+*O{X;Gz!Ai(uE5S`13M(N#BH|{Jvl8MXB5oq$BO-1h;v*t%B6U_GiI0dF ziinShxQU35h`5P=mz5A75pfd_;p3H7WID-kgisdE!zB_f6*;v*8=gm{Yda}#1EB8DPj zB_f96-{B_2Ojsj^!ZM!i1>+1wr;v#dOR*cCq7xiMf~VLS@)YS~DB^rXf~OE?k>Do8 zN<<8WxQRWsZOCFI7>bCS5KocBO?+lshirxTi7!H)LKtxqtzajTGZ9G~M8rw#fKy1$ zT!@?a(jFV~8X3n>h?|Ibia0kBu@%V~3ULz=PmvymVjE0EYCOe}!BB{shO4gfLlJQn|HM;>p@`UuI5!dJEFy*? zVk^?iQ^dK6IA;+t6cJl-a6CoCN<<7roU=$9Pq71rB4R62;wi*XL~OMZ{M86Hg(AB4R7j&Qru0iioqwXr4k0MZ{Jl=PATcL~KQJ zoYh!~29tw=jhA%-GiE7HSLh@ptsisU?n7>bCk`2UHg z5JM5M6%jWPXDcFxB4R5Jji-nhiik}(Fi){R2N7``NgRZDjIJS%aYD#roEY*L-9jGY zq>#rrc^{ra3`N9Nq@Sk{LlLnR>ES8FP(*A+N<4)aiioY)pQlK06JjMIh9crDBK{)c zBO-<(Vk;u%B8j2s2^S&WB6XfZd_;1#;tY->ZX)6-_GKu}fPWB^kvdNyh9Y7sB35F5 zwjw!CA#NhhR%8TEk;G6$oW<;yn}~B3sWTK}FKUOZgxHGy`>_?ZVI;IC z*}iOrcnUET5nB;wB_f_8VlL{3yhRdE(K`j6Vqb=$7o0$^kf#ts5wR5!PmvJ}MP&bv zcnYxq3AQ3)A|lQr&Q?UsNSw0}Taw^4zQd}Mu?$6=l{h#KA{!nRS+TBXCC*OBh5}uw zfILJH#NOm2pi7MyP$>seLiv7EeJv z-krd2+JySzU7Wy(hxP6>=vMzJXiR{!<@Wd1GkDEf;cq-@pS(Q@SVAEbrkgDSV|?7DMGY;acf#?^+XI@S@`%!wakb@~5gqA_Q%Vm^zvKM%jL()5yw3ZUhphm!wvIa*c$E@KBXpD10Asx8dKrC zdV=D?WySjfWwq>(wJ5FWrr>we%TI@2>9!hsXM71tOpRN73D@H(FahO2Uq1nlkv{Aoa-)~lSbCWH zpcKba$c(pATa2e}Utftmj9#;q*cWLdSec^+PIJ@-)T|F1SIKR}Q$-7^N{6zCa3)=j53cr~hN_cK$=~B` z;K;FrYy4;Af9g$e4LTLVwI!M$^Q(LGUYFF8@j(JxsG&0)YM;uDwQuN{oH@S ze{&9a5C7YrUi#`ksny7RNzNDkOE3SMKfDyzfA~L%zar;L|CN`|&F}sX-^Be+INE(p z&R707|GPih{YEJ4e&t9gF7X#HUhx2h4EJ9f2ZWtk-q;6^sJKrwyh4<>>ey zwIkV){!(*0C^l>uHMOJtRm9igbubznW54#-lHylYs6Q0lzr2}#^2PAb`pN%Hd=1+D zul+TIZ~T=;K229r=L++q|H&73SEK3w#$QeN7W~$K=Z8?|N<1Lt-_+lT5$;cV2worG z`Mv%Iv)6wQUd_=c^S$2<-avde-W|KWd_RP{{l{J$%*Xx?Lf%0BBp-WmJb8oL3HgGp zZWexRTit_v`c~K9oWrh!xq>XgRW^5!3(OPb26F{hTG`9aF&`1mHPZN=Ylhi^L7re3 zb*{48_?)fo3Y#U!8e9PX@ar`*HPzM ze1mQ``AFY}7tauzBgh#HVHdd^!Df6fE<|~|h4^|a|Dfxsa~(>fAvR}l2_XpHMHzmP zd6ykJE;J*kb3GnPx8P?aJyH-1Cj5v-_agN3QtDn5>W+S7hW{h2KhPG3Q`daHxVzYj zU6;P7guBSf=TDlVlK61-#Xso2&>ws(cpv+K+(*tmDC7Hq{qRYd!|_evT;hAlzXz0Z z{&8||2Imm-tMcUWtMio2CU+$GIPrL{Y#=z0^6`Xm=;LQo`WRkVBkW_OZXqqNs|iLH zy9xXs7voKKF|{8x@`{q8{suddQhAC=W&8*wH`+%CH`z%>TH{INPc*Vfvo9OrW;>bu zNk-P@o9#n{zE(B}e`KXH5T8QA2fnRf}( z!Rh$k?ZOK{I0L_}oqm@eZFcybA&$mZYrEfpm(n)8hlFF$49l-aDAjQl6qt*ARZyy7 z=`pMFEid>b_G#@811`ZgRC}{5wc2H+nwQT-HR@FLQUNaVQe(_FFA)})Wz>0aPQae|q_DjAZXDmi@y$j!s8k|+# zFG4BvgjqqI<+cLlFZl|DCB7zm80~U3saeCn7;2keWIxU)%u4$L>gko#Ut!BrZz+1_ z3dF0(mzG2->lg4yeiD@axg0f?`Et}+>YukSpkjWWu+XfgrhHqs`sYc@W2r2)mVr{i zt|3Q0uj2QlHCkw%Bg{i7y&T`9GSph`U#3)g6LELaAkD)kdLI6lr72(GpTQgYe)A0B zJiKE+p!UgYMtU>qM zj{LSkZ%Q`%-URj?BfnkHK3EOkb~YtjK=EuH$Y~#R2v+&kzE^N|@E-Uc9z`9==@4`b zR^pq~Gw2n(55A9oQqSN6|BCHIe#f9wumUErQ&5`!;;f)&@QOW)u-0}ar&G{5DCJB0 zGlR2&wf0QHtF{X{or5lcwBBa~^13}EIFtBza=HYk2kY?vJv}&sxJU4qoeiE&d|EKu zJ`VOEJ~cQkcpQ8j{nDwy96Q%mG*WXHMPpXTS1=XLQJ}Qm6+#X8QK8c8s8Drw6m_&i zZy_|@(tj30qgd2eM3pGrcQHIE@`L%&m6i|H<Vjhn&X46fpnF}2PKTW07`Ifann6GC75T+ zprY&=lp&k|o)DZE6gHtXo|+|4(8|{!D>;Qx=an%h29*fiz;3}wL4ERsCk3s8dT1hB z2X)a$3R?$lf;uQ8+XS@<7lCz%Ynh9Ji^1B&-JBG=-JE0E;9~@j5bfrcP)Ftfcg@3Pn zD^8~VNzVBG!8w7f=KX^#eo!zN9L$-=v!g^#)DT^XyR)-pZQq@`#%)bYcImoaPkX^;-TEYIeu3?wsJ<;7{tF6J+xPgF)aR&gsl9V7c%d)o)4t;m!@t z3;v+)xj}Y+aWD`ZNWD(@p5`{42zku!?z~_?@VoniIESxgE(T@m$U*(=Xx3|z%IT%p z?C7KlmOdm;=pi^D_{|Ln`UbhY)SkJhlM~;-zCrikSGf7UK?f&oa0l0s_?K{JfM49N zu6ytcVV?cjvD=jWiLd}<|0yefzy+YRd~HxfS4P{b{YDxQ+Ti)xhMdNzqYHtBC}~V+ zgg31et=%ZEjH%PtJPtqI`avr^cdG>QkE;?$n_7iBm4iw_<)FE%L}=k^ zac+a4Rv;Zpy`X;38f@*_xT>60C8!$o#JjF0rL}?@oY%tDAYGGm3%q8lQCc;q7RZ~v zZcs011Gd4FxNgwawZKdA8@w#r;V1cxs}s}>T9`V7mZm!Os|D2qsnpt1>swbls1vj_ zwF$?9$KtbDk<#ix#X!FK4TIXjai$@m71+wOHbuy<7!(QQ_1`LJ7_>I62o20}L93vF zIhN26JdU_!aBR@fviUdW2N$d_#1nfa9e}FUb z3OEA~=q{wrFcV$T;HW@Kk)nYVAx8!B9O#b!KzF=@yUM#3?}0ve+D_&ZCOLT*oPv*m zyoOI8zbjq^(zA?5PjXZ+o=_~9LQSbuP9yG!7s09KMCzQtK32to;=wrdC&hxPlumI| z*-hXy*!7Oo=|DIQpM>7j?&hV4xtATUiU;=+N(AyOJk7Kx^uS}`Z0eolrIEP@-_sJo zJ%p0M$^Mw2IoK=oX=onwGVR!Tvj^A%kK?iI%~UcNODGkz#rybVBY(!z@n$%NbGrLx z!7;%YS1KqCjwNp6sbSjqw#29Sra`md6zX*Mqh0BsOducF(m`wAmR4@v8qCJg*QQ)h9xP9dEck&P9eiWT z1ZBapK{>D-Wr1zV)d!)%KcGg_Ab_zuI{22F^79+TmHW_l0HXl$cjU+;@NRr|UFc1~ z06@H#9C;Joh3BpfeG@F6cRl>~jr#2Z+35U z*8ApdBX8Q*IamI158^+##oU3f@D|R#!@Y^u=tyuRKDBRAQ@eP+NxX@g@>-jPul;7O z|9kw^wwOCf%NO}~Bfrky*}=A{e}g)k@Ozu-W;uDaeQ(|keKdc=Ke3r#PyQSDus(qQ z{yU*h=R5dy{)GSByBsYs_v357gwpkRs=Y)02ZWzNd5eBZEc^v8)IG$X;nlh)#Lw_Z z{g|WAjr?VW{3g2HMJz023*(n?AHMu`?Gm#T|AqVcjymKm1(&j~-}3)YPxz9AyiJjKnfii+aoPahQSUetqiKvqRja zE*F@~=C)T*b0~Ttc}&*ijOC^#VFkM@4RN{cmE>RH#N)3pH3%!&Y3UO32NUwxtDO8P zucFSCPVD?jQ=PDi-IDU)RX4~DCLZPr+ah2Q>WMX9WvUTYo8jaS!@qf_*+qI6ew72= zAeR@+i!WYPeE(LPs)RKt&j-4E_F_T~d$rqvis)+28t$r4i(e!sylkXA&w>6thyBf5 zt)lH-RH1<6(W;**G@N0SW zadjBd5774$AM9-ypMh`j^aNGZC-4#pW*3 zcj7~~81IRP@N-*i?k49hyv;tuL;68VJ~X57#C{2UiLzOgd}L-3wwlp+ajyf{Q8v?W zHQUTgzYTx!nbg{9#!xCIel4Eh4^X}x+-|OQW66I^tAJ-S0%F$%s z*YyLZ5X;lAANx<1wRhlqsl6v}#T)T0D%Y{71UYoRycVRKBav~!H4l@TuIIfx6J?hUMH%}6;CPzNaC2c9Y23+mdxDvLcT|kX}$pO);z>sE7m;h9s#9lw&qcGRe_|gb}sbGbLJvjiaPRp zad^SBVE=$){rBw2@uQQMjWq*Y3tz5WRm!xhoAz|820v#(?Yvi=KEr{I;~LE0J?J^E z$(%g^1CDEvt_kW_WNNb_%L-=YxDIQvY+yEy>$0B84rb@L9%-%ev~OR1)AXTGbQC0i0&FuT>xlE)HSGRM`g;2cLd z*0eI($FUXRIMbSybP2Eo$8A_$mjp|4+?F+YDXc z8cXwpBWvz(tksCCu{RotbA+R@#%7Js8ml#CYvk4#uCZJry2kcsq|XwL_8R*&1JGPR z^8(EdWI@z?L9+%~<1~-ZY(myM%`Y@+$)1U_J>vJpS9A-&DfHc zUbzHuE`s{%;vD59sIM-@Q4T^*dS&e$lbxWxTAJ)^1U*aQ1@$|g>Z=Pex?~{~0gI3u zkfXj@+>0j!^vz;g903z2V@Uz90LO+=BtMv+<6PmD<>Gtu@XfjgU6rm!*PyG?_2?RO zRk|KsgRV-~qie_-UW2YJx+-0Xt|4(fx&~d9u1D9PtJ3x88gx~<9&u2*D$7;qF6mxr zM9Zjq6~9Y~Yb(qZ=??CDZSgyn{9b9SGvW1W1WY-7c-lIC{krE#SDv1>*8SC8*8SFf z*WFh;s6EswY9FERz263<(FCJ>*WB+UV$`MlaXT3^K5H$Jw;^AAtIm$>EwJ(DTFvl-p* z9qK$;^I_dh&D}Li*D6kPcRd|i-D&Qw-d(Fc&E55MYlWb>oBCU=4>fn!EM2Qd&GIx$ z*Q!!;cg=^j+SJ@#{jFA^n!9UVs@19H?pm*E)f%m1wKCJ1wj|%3G&hd7ujNWKi`G+{ z{`V#A?{Cy6r}n-aT>I)yCas3jw+_;sOj-^7Z?1#lZ5Mw}<86H;uRGHJyrtGZ?>}A~ z_<2itjLW!tmGSnU%Bgl+(%mO)xq~I@wry=w$_nanY}i`_ddbb{P*^a!!x(Zn6WSUy*d=TLE?Ff zTMW`aPl&f~YUzx-=Kbfci5brSvaKWi{ab4Df&K4KYIFOCL1$D*KQ2 z{C|6moIU)%vU8_$^53fMvJu2V>#5F4klkB$fGh;Pr)sr;pr>7S0P#7pS;?Q$5%Pk0 z$(4N~H<+7aLs|@AQh%E~oiwLP|9g7q&td-XYX8kOX1pIxjBD}PRN8ES|J@j&=V4zJ zgj!km@WA%T_`95OZ5|uc%sz$K)qA@>LOCNKd1lxq&AP*|9TE) z%!;>NYU$+He7NUPYR3cHH2&S|NxTQ zZ1~CBH!X9~)W(a{`jGU!v;US&AW{J(n1z%%g#??RaYD+k)W+OI+lpDpxOrg4+|Pr3 z-VT>tNHZGUCCz9w-;uITa~#chH1E+2Nb@1hiZnmcJV~=9&6_lT(kx2zDb1@iyV5*M z^DWJ~H0RX(t6(@M(~MT1Ba`M%YCpZJ%1y1U5B7ehrd2ys z?SW?OhX0yh3kzrL{8|(_nz!peFGA3~UH73VLHwHT=TQXB+jT#S5j1bt{VYz(iP~ zYd@_3HA?C^(*4pKrRPjfo1VMmW5<6#SBcs)@eU{Pyz%!s`8B6^ywg2N4`&pg&!jwO z&gk(@Z*CHko<0tJ-|;S`zD~W0t~pZY{&zaqq_Q&4Gvem#f2 zzDSH>TB${Is?_XhDUTQNwo^JW*2eQQu1ynHo1|ku@HMBrCQAQ3Ol{2F|9W)ylI~=D zT+=!tya^cZ)jHp%qQ@zif;gkO2W-V$eO)Z^*iM!afD_v%QoX~f$!(NAlwlyUuG z#>}byyY~HOn?}antBe^tlDDaPYqhMNxTN%v_DmjH`zF@o@!cUbc4W*NEv0*v78^@? z`7E&#NjnClzE?oJ9pmq8Je|@t|CfDE#=Rq{^(X1mjb!wiC?jp)$>&!|cIJ5d9@_h& zIZsOasASChlDw@C_xdO?{-!>cPJTV`MxNsOVmLaFYgiV-)c))8Z<*4GS7x>Bi2r8E6EdDSGFvaTfZ_0*diU-QP>H=a&g zTWgHlclROPx5N8fs-=X+*rtN;}J>7SQF1^bcHKrt5Ieu4lhtyC0cl$L(zGjJCo09vQ z#oIS+_fTU{O8c8-)I2ujdlrtZ~&^{DZ8BzZb% z?9PbiGb7*YjJTeR+}|wYp10IEM2&+7=i8XPO_O-x_&oez?`L|~fbsp};`_7h>+5>3 z*ApK{4yAqf?GF#lp1=Pb=1}LW@wSWidl}ca=$d6=h|gg(JB{}(@wG|HTuIulO?_SZ z_al<`t=c>8otNax@X!6;zk9Ftzn;V$)BBm1@jrgA;_aLIb*AOM#m9^EwrOIVjjk}U zZ)f~EGp^rDTxZ73pHshYi8)?I?hm$q`{oPRYii|aJ|ABz#oIR{`nrr9TjS%!q4j%- zHq~4uwP$btb$a4XMi!6c&)$)2*NWe__&bsj?RzL=Sz=bN_d(v|@#{?e9Z5^yvj4bt z;66D%UZmW&9BKC|{+`Cu$?w~t*Z@;|FXH2D;*E$r98-EP;@5U)Yc#d{;j^6{+O-|t z^<(@V#?$HV1J&=Pv=4Av+B*J@BxVTe^`hPOG*3u=ZRy=_T z?@(=}iT*Ejy-9p-6>r-^8(R+VxEH_Xf45&u+)vFKQhsmJ{~jOS@hyI@j=c6wd8~_H zXZqVWqwZ(o+SL0ctvl0yJ@J0}(8uA#Qx{!T^7%{J?ps>cBI&)(_3>J! z_b@H%Bwf$G*0pG+AD{gtYzZ0HrU^@A+}gLVolo~CJsg5sRjr-!?<%C14?L9l)c$MV zq-#qXf3E+1-`$3EfAmzRzRyr%haq|8%Rm2M_k~LA2qm?Ec8E%8U#P^6P*NR8e~{9? zP#Wixc85yazEJUZGoC)QaW?T@B&{;zZ*F97*86g>Tt`y-rvExqTN@>=@JO^xrnaU` zUw;yB-;C?`68G&u_P_WV?w|YQ_;ns>ePHU>^WThLTH_|xL5X-@%}(mqoS571Ya>^i z9;|KSpU083tvfPGUyykA;ya0I%++(azvdUUay?@fP7LV__o7inv>|{pr9%*Y|wP{K^we+^{KlgRA7#wF2%ZgVo9T2ign)(WlpuPjVjTnM0@-s=?f0eocU1fL;t*Y(ZTMeBppQ3j!H>; zDM>e-w4+kAi<0J@+MOqEgH*4R@L@RE{fBf7NxKlGy#G*Q=OOK8qxqudgxcjM+C4O} z3sKVkLy4V-a-)omb`O;nR{Q6qzW-4CS^YQX*ctI&q_;mgkZmviUc}ovuBH7q?@!wL zx5OM+cD%zo)~CK#Q+$`Eg#NlLV}^EcO6afCvR6}lmnO|;q`%gFT-w1Yp}*Guo3u-l zcJ$KTO-ah@)c0zNw`tPbs~tXdbZEcfqvtT`mwXQXH+=Tpe<(htr2af))OKUx--3w0vxl}m(tCZd+$^T;e9%+4Y z>d#w3uMz*%daYYh8_QCA-qK>rO+0CFtBc06B>P6ZtuvyZ$;kdWew~NbzKMHyAbaWl z?}+Z6*qMkeN@Hb3;S9E z<9+hJyjx<-%}5?Fz4s?RmL;CFwCNDz?`+169T_$EOB!>J(aZ z?RzNCVfwB!ZS9*_gJh(ZN%uDK`vxhGamn8cUBkithIv}%qW}E<#@8D0wm#S~_i*`# z#ji8t<}ew*9zWRomQl9)1L+^)?VI{NlnqV446S_*Qsdp?>&nC&X5V#3YV*LvyS)FK zqBhq3i(hB*_a!k$)wLzw-+lSY!)rsxxa&#F`a6Cn>Cw-i1i@uYNo68&*mD zT6~@yAB!_$&VRV<&;NB>@5^1L{{E(B15a(I$^U#05AFR;TwB~y8efmcceRhN*Y?$rB--~tHjSix zbmE*~>i09=*1FD=bO>tSj9p{?n;hkTw-1xUG2 zaVfAg*oL?ySPE=STmmc!wjwSLmH>|vpCbTR&)mZXZB=B5SMf}6Bi&9Wc+EuQGP-J#_Pr$FblqY3dQ@Bxuf7m!lj6&DrX3l${{nxi&}H2+~c};wURY z?_dp66Rb&I7J@7%HNy6)LCTwIraD-iJV#nBRV|!5RxwpcSLMi^a->=N~ zE3-e$><=@?ugv*I=6oY_ewaBw{NJ6=7i67~gEdMHRxSltCu9e+hiex7K5c%2)-3vc z+I$49Sptso60~OV9OWTs%_3W~Joh{(Elw_Sv}TdbEhj<8(QmEE_LgzqoBSIc-=ph@ zf3H?E34Qp#`Mvr-Wuemd|C`?%*G^}y*D}{@nd`O8^;+h7Epxq=xn9d$uVt>+GS_SI z^_u3ViFtXUFkL8|J8MOdlUZxda9yA^LV<9dpcO%O)&W{4Xho0>)H*>cf~=s{30e_k z0kuxhS|9+mPSDI;zy7Bcf;9Vy`SHK`y>VXn-~8UByDUCTM;URS6YH<|-A;a=#oieB z8;yPuqf?EXsv+CsK(Rd$15|@{sUC7f0VsAzOp*8^>CkG?$`O-PE995NGD*)Y&PmKu z#6d~5B1Woi$We)@5@#hYD;FphOKg@nEwNkTy2N;i`w|DHnYw;SMx0oqkRfXva%N)A z3i7;(Lu(Q;YDfRgv^68Y>E8_8F@JM%;^M^8iK{C@nYg>=e=~V4Lmp2o-%;>Z_IdgIWZLI5 z`IJmPC6oWkW`CI3A7=K4nf+mAf0)@H9&Z22%=Op5v;Hb)y(w$U*s{ds3FT~Q zj=ZT59+%?Cn~LFaNn488gvTXpNn#rwyD-((9%YN!c3@kuDDiJ5i_L0(2Y)lao4{tV zZ73^d+f&*OEJFMT`M;Y#44*;T+ra*6vf6CmZ^W%RqZnAs7PlR!-ySSX{EPY3WCOF= z?DkL2{lol;Z?&_ns9PK?!41Zq20=6JnkfWc> z&y@Z|$N}cCIqk93^`QuH>Y<}V&sFw@; zk@zFZKQvWsK1!+*s@U(%4<;9w%jULQDgDS)qqM56X7kv*U|x>)n%o@iHQy6&qs~@S zo#Se@I(d2QcV;ig+sWT%c7WT>PH>0W1@1Jv!CmHKaJPAvdNu53@LjXnd`G;+d`rBA zu-Uvrc@6sxp{9MCBVkQj%f4s6q1JnZE#@urwy9;`BGk6;o3AN(pYWb}laku@O+p>} zJo)dN=gpVqEAT6h-Y|7+UHb;L>ev^|7nHm}c;0L>b!|PniSoMkMe<)TubX&*sm19{I7o;FXJhPIJ?in50G zNz=$S2A?8+mYUC)Cro48#6Dr3B!14UBkwuFvt|J$P3!`~(RRFfm6Gv<=gfR_v~6nV zQ+~9aVAfJHfiNC?g`;_tH?lcpvdF z@G3JL90txH9?t(e!(41`HMg08;KgQ;8EI|-Z{cVVVW7E)+}pt0%cq@f~I` zH3yjsxc27u0*>z_eIfBB=4MJRAq+O>Q`W+sPf2sz)!al$SHdOc1al)tClI=t6U_}A zok%#rbTcD3>P9%xoJ6`Cc%8W(yq=?zNuLB>OWYki8N7!06mvE4DTMCkRQ{){!K*nw zjr6JJE_=7_5B4|bm{H)}c9iXB`kOoLx#m3ZE_)7mjycziCV!M2ZTpzMr2CqF<_>$O zJQ#EFsGXE&si+z&(C%_x*jo^(OJw^ISa0Kx@YTW|f zVsEu`iEp(F$$!d@wbv7mB`maa_%B<6b19uexXs=}=~(bO;(Nh+z-#Qa;I$l$BYm$O z4~_$`CY}I}2Z!0=;Bby6lAZuwMLY?d2wq7%8JuLN*ei&q5GLEV?8EjE@Dckc_^5r; zz5zZ4zDfMHeTee632)hVNWX12Q8pWVgZOpg+2CyZxP8|?Ncp>jckI)47DrDL-nAPk ze;jj=@O$FTb`7;Q6MnN> z>}rm-5H{QQ>`J=|Tt(h{ge~@ca^ABafbWCL?Fw)OM<3c{9DPXmz-Pg7R;T!N9`>icQX=zu+ePO?} z#VP+5{MLSFi@DA)T53c5mIE8^C!K!^o7I+nabU?Eo+EbNN7Hk7so^SS(BevVp_TNFH&xCL=h z*Ot;Yt~sfrz@yx;wmBt5T{-gGf_aI{yFA3@3FTY`(&fS2#1&mG;);X{u9C~)a)LR@ zt3;^iD!c6DRVGw&RY+HMRb5t>4a~+-RYDb4jhw2kI{#l*Fe}IBxN}_-u!%bwJlZvN z=aD`aY)ssryryn|Yv>w*jmR57IM4MXw;9->F7GU+Qgj+om>~voxz%}7Fdg; z<4JdMUBTnQ8pJ1nUBT+a|Btu#fU~OD(zh#bK*cOkGDt>1KqTj!bIy{3Rkdn&_vvGE&Z(!~RlAC6 zVOpB1sGNb*+_W%qE>25RjlSIXqnT-Ls-x9Zb=A}~Gd0las)lM}nwp$w4NfX*Y?_!! zM(%1cktizXq)a9=$xJqKR?!4A(d1X-X$8;;#3|$_n<+-_Z862jT`~(5a~03!{r^OzdJB5yzTwrl1;2E2O%T>0-u^E2O&7?`pc4hQ!h23aQbw z!fKR}dwGl^S6Fptwwvj08W6L__ZG>9SF|*>+@)1kHPXl(Kt`HT#2#GJ-SjZ^iP^a( z8x`Mj&yg%#R|b_km1Lonm-xgSk8X1nT+%%oKvY3WpVE%&DB&TKbbm40_!P0JmBs?o2it82Mi zO?5KWbPX-{si{Gxx~{3^u1Ph?)X=rG+?l8rnVPz`mOD??CR0n-pn3Ou-4t!Ao1x8gbF?`>MX6eRuUe)yTHDl-@5^5Z-`6~XDwT_W)pboDMoM}9eb+U; z8L{5uHM%Z;O}**A&byIPPx6kW_}ug)+K8z5l-P*hy#ni0xm%B=RYK*&EK4iRsW%LoOKUKVm%rKjDivog{uT|8Ed zv`U*8b8Bp^jOKqzXuv(J`BSmpmz962m(f6AB%+``;Baw+u@=2g6^&j}OA$rVQ-0tymv6g?iZffF$sI2p5n zQ!yJ58t{t}GVmFi8>Vn5W&^?meue_%h7|}4$Q{#wgYo)5Ps{|)#!Ns~|3VRj34DU) zgBW~4?kubQe2@ZJ^XJpT0c6F0Hf91s4rI-rA106=YOpz`1;PZ*#4G;-FahBOTbMZ$ zuletX2?!|=CU81t0>S`<8OZ9rAY?$O!B%poS@)lgSO3BWga*j!|GStB2q)OaD8U3y z!2pC12pLeUiQhzJgUpioOj45I*oW3}8NeVFE$|gb+LxvjHIkyI=r91)iquWc4p>K*+$3mtLU#GKE}+-m;%g1*OHq}ZY8>s^}aBH88HP|8?X5vgb6&T zr?c)CP9RKRIl6) zSz>?UQYAD%7{F5E0CG!V0E=T1AcSBLBcTDp280PLKo`X{K={WHMhjT?PmFnhaDncu z`X|OTK*)e_0$KkjXh3&X`QupA_ktM6ieJbeCY% z@Muf}gb)Y^5C$+TW&%P88ZjCI1CUk!G@5XLPOSZf08C}I-!Y~HLJWiwv_;#;96(6H z49G!(477m;JPbXU#P1xw+d>G00|*lk0wC*rQ6U4LkQEvrv_Mw= zE6`O$VFDkr?td;`{R=JlfZt$Myz)N~lYyl%84w;I6hSz^2k|O;b<7Hupr6J}UKOZvz zS@8=wkQK6!f%lmcKJb3b1a`+vKuCa4ghRvx2M{J8oZt({fRF$o1i}P_1_&WIOiyTl zuz{~)D)1HKH(C7)8xS(E4F(`o;0WyvK7R=t5Hj#OG~g$gK>C;fq=x|f7!!bW=H5Rk z!H+Qk_!%-FD}Uht!U!@j|3gd(&cFnIA)A_2zmNf820{i-qi13!aE>cv{d^7*kkJSa zI31IKtLPsw8xS(^Eet@Yz%|-8d=wKlAY|Z_=3^&RK+{fYV}uO|891RWOh9OWumJ}X z5C$M@Kxlw`-V{PmhV}lPFn~Lu0cHQ>0C)e%0m{Gt60G2kKM6qTc;zpAK=^@>0bu~Q z6J_OJ3Qa|TNh z(-RsXgdhh!S^Wze5Dp+rKnOujdcpvN5C{#BPu4;RWX)eJ<^n~~VlfX8HXy704y^t= z!T@B={~-DxSz!Xg2ZR~OnqO!@38FB8b}wIAX z!VH8AG=K?|`I837ieCspkC+w+2dKw7z5!7v!6>u{R6$NXDutF}t)E4ejmbbcqVR#N zDl=>Q1Ru!4`o2WG$}bu70bvO}`F{0SuNQ?m2oo4-gagPbUnqjC{L7=|`7XU;ejsF^ zE=)kEfzSY90KyD}2FU7PIDv2gp#eo>1|YORXn>Fa;RJF*^l)@I1VGM-799ow5I!(0 zW&*+hgcC?LZ-NO7Ho^pi0SG6M)1nhhKxlvv0$~CJjL?8oF&XF*vjAZNX&4I)kafRs z0$KT|LDMiNG(gtg&tm_ULC2m=sKAT&T2 zfN%n#0m1-;69^3u5+IzQPD}`d3=A+fK1bR@1Jbj`mHX7Pt4*}ffR@_A0a~GLAOjW- z&<1U%+oJ7tJG28#!1Aa&py`ORZq5i3un>jjs89i64+a|W2-*)aV4wm0&;gJEIdxsu z^mQQ=1}0D!tq&hCFoF7LL->G!2{c3-!v_pZpfTDMK44%1P0{A?0mZ7l7XNY$M4&cW z2QI*O#5D1k)i^Oh1B40)8xTrxl^uWK0Ui&4?D|(gWxanRANV^m zARIyXfY-tY%A@j=lK8-XM+OvRK&f&u4Y&&xo{+=@WG+DiWX&%w0O11(8gL^YD9v|B zkO6T4$a+6P27~~}+W#gktNs*Z6Knj$s$V<+=i@#8o7meI1|UuVS?SCAUv~O$=7|!v zpy2?AQQ-laHU8JA_zyIcL8yb!hFpAgN>=ki3B)aME+zvBCZJ;`pkpSWVFAba8esyO zmGDXQ8>0S`1_%`pHXxKB!2}X~;6^ea-hd6own1IlL%`rC+ zKJeo|kbyIhfPc;hwlJGu0tr6wcVs|lK!OZxiz$Kl1a!;?zKzL%j+ub|lK|XE280TT zH{d;1`Tsf-5I4Ye8X$Z?n83S#(trdR_@6NWAp+tKnD-|Q5GEjeKxlxdaDXRcJ|JY^ zIuqE*y8k*ENcaS{vohY!^B`nkd+Y-ccYsg<;Q*pS3B(&9G(h;kUunRa|DXXv2G+zr zf$4vefg~pIcQoL6n1HYX*=xVf1cU?JNCpy2K!||21N#0+1B3}IixseQ^j}X97YAlE}bBu1XL9VFKgSbq+9@ zzR&@22#6Oz_`zS9z+Y*A_ymLlh+7~*2L7H22n|S(fg~m%93a625`3UR>=*buCNPBG zEL<2^`1B4GGu>xTN zLI#8qB$0t6CLm;B7z|)e%nF1I421;<6G-rZBr+g0;5r}p_sD>7fd9+~ZlnRi3O;1T zFQh=+04x872_y)B_ymLu2tANp_SLaZK->Z1DG(-*a0?_cflcHV#|{B;3nVdtg|Gl& z1wsMD9k76y#0SJX@b8iV@d3R17e0_g1KwdppI`z)3@*e>Ks*BpJ|OHs$iUnGK?Z~g zB=~^%1gNFTOf%K{2sFb@eEui1409? z^MU`K3)98A!!g_NY?*$pjL7Kv=-df0BXBF(t^t=>HWN5O096fTA%65S6vRcm|5Z zd_X9HI0=LXJn$Dv@ONb3@0dWsEg%j7p#kC(xXuT}K_C=B+yO!c5|p4SQG5cz1QL88 z!2}X~;P1$Q(17cF;Qx*ch)W=E>=O`&K!Ob9#RHI_0ZC*)Xn-(*39SEx90&yvM}RPd zBt9UkesK;YD1kTx#5EwEf$Mxg`~)|0fHAOwv9U8Ci52|UWMCAl@(2D!K9C>-MIZzJ z9TO<0vZw?Z_v!4G@m; zpP7J=hm?Gp`>)7=_z057fL7PZfWCnY=$H)Xm<;Hc4B&Hs3|Ll@!UR;z1XRofRLlg_ zf6D|i!U3#GR1G952>#vL0rBWtcIY7!Z~&=c9S{$|Z?uF@Aix0 zRsDT26Oc8%)ChIK9HAY?!)2yUz?_{Tbe zf2<&os)0lu!Cz|!q^3Zaz(3XwNJW9T0e<)wD+sRF4kW4xk}3$KYT(8?f<*1WHlBfR zU;;u1WNm!Cc0j5IHsBHvw}6m_|GU}&sTxRB5d6<-2ZRMAd;(HIAoT*m0+K2S{{7kk zp&^M1f<)bb5P|=$b|6tHFq?I~_yiJl1X4kes3!Pp1;O)hg#U}$0jU&7svr=@fY5-X zssSMa37^1UYX`&|FeoMii(sOO+5sUTi3)-qtp9}xNCiRnm=FjZm=v%16LkcM3W7=T zI=?6D{-g?mNpOJweeJ+#xIk^Z0a7tA3O*n{0jV9hUNw-YBlzdF1Ana=7#6z)l4=JU z@%KE0)xXpZh-09mO4JhkwT?iTfvo+-1t66IQZ?{*)db=h5MRJ#Vp1JJQU!rj6a1?c z1ic^t3AcdM5lGd5xCDA@@d@-nrJCTz+JQthK~e>QR1GBR2nOI8=nwOjY65W!jKdj_ zs3RDSJK%aXfiQv5jKwXGR4E`;1LJT8NJT-SjzC-jqgnA^uOLXO7f93&NYy~1njleG z@OKpiiP{0FA`m9>Ik;t5|G*f@d~^f zI|DAV$`=PgqFx|TJ0O(;;uesaf<*0rtofx@KA_ z1%WsN5@bLs2&8HtQAZ$dfiGj1fVc(T#3>+5;Ccl?qIN*42#&BTBh>>^Q*f025!U^Q z3IeGVkSYS<0OBCHv6?{Y1;i~Nbp(m3fuw2zsTWAp6eQIV2sQZ6RRcHH6#P3C1c};# zQ+(_cm%yo*10W_*J0Nug;u%QP4kXBcR1k=7z_S-6Zh=Gvfm8~JGe8J{5CS0s!Uv>M zAW>ORima^og%gNRpj_+;5TAh55l98W-LWS?DhR|oaAO@oqIN*s0u^F^!1W3OsT~lv zK<3yPaJ_=y#@Yd?CJ@hn)DDPmK>PvX7Wh{x2&8I2d;*DD0wDn6AV^dYB&rE+tQWYk zjv!GrAY?!s0pckTpTNVYR2)bJK?$4zQZMk=I)Z|X#Vt??m8t=$BM{F(0ea#VsDeuE zfDi%k4CJF%4R1ic*dIf3`0*TrI@d=18AT#m*u7W^n z2NHDzH`Wd$stNvDK_I??L><9jD+t6lkf{9OfsI0zDT1b?j{klKMn z9l`&;g5aN52mIGn0Ev15@nYOqgOI2n5GGJ7rU19X0HnG=*5tKu7D&CpjkNElfa2@wvRf>*11hc^P;u>mifac{Tsy!{J>CF?PoN1ZwF3&DfOrF> zc7WY{D2&1bAr%U>_>NLRpzsUSk?)QpfbSmH3M$inxyL! zUn^gg(P)(kZyZ$#yt-#13j3uZftG<+`z*xt@mO48R4Bybv~f?oVOohROsh1sw7gph z7j>w(+{8U)d2P&t=3$)hhe_R7l5Z^GBa0Z{$Gc&2t~E5vyQFx}G|j|rGkGt`!B42b zJ61*Bof2+0q4VXT_!W2+ugFX#+TFZ<3mX>?*xkJQ$s;Rgg!PxBmB+D{g72$hpPPbl z-$Y;Nw~Bpn*K{(zq6%MsC+`52iDem=(H@Grcan zkCkNHm45M<(>@eCwTh$So$JJ`P;&AAiAU=}RD5?mVwT<`X6)k5Dh4m@0bN(B1MjR# z34d2gTzE>A;_D$(d=Fd~d}>hqrIf+>B1~S`srdAiYL6SHFz=zg$rg^CF%R(0s#Lq! zF;j^5S*6&ylo7hVYFFX|1n z3wn)_J*72Vv({{6UaQqcJg2M4uQ994dG?l8ky&k4(qCm(pexPu=nAtOecn8WE;rAj z&zWs{vw79Lfr^WEi`i^sN9|SgRkO*wPDUKHubC|dFEQh-daHTOZ09rfCUlc|#k@vF ze8x|jtwub%ub{7(m+{LgUg6I0$^Tiig<0_>KV_bz|Fn6^?Bo;s%jnDe4xjKjUUVbB z%PwZO@EQLZ^R(He7no@t5Fae|eXi zYxbk!Jm2N^vYOoG#I?T5iI07kn`h>lT~2nWce(wnKzH#w?sgx#`DUK^kl9^sJKtaG zY`%A=-2w6+qEDFl<^wmtJb^x84!Ad&-40(oQ`X2QlXV!FL%$m{9IFjDlXx+g=rh9SbN?rclnsjPes>;xXMf1 zUQ+9|kqWmJ?s=D&Yw|(drP^yXk8qJ&?Zl6?30>_rx#w^v<jiF=dzt(zsCb_?qA$CRPW(~1n9Z#>(BJ4bIH|OH3Ekjca-X|Z z^u>ksBK?=#i|z~J3+_we3+^!S1$r;K_4HqG>)cnwb+q+vE&X-q*TgmGTJ$4g5xvkY zKo_`N>~JikS59ws3td^XoGz=kxXrGN-s)aMw~#HPUvpbrX)EWL_d2?j zY)Sg1bS0ZzSGJX`cpfWRaX3~)E7>ZxGBZ_dHr$|9=w;JY$z?^e>MXjNt!hQH;32JU ztJ%!@ipqq~R2-cdsmsj7__C@_{xZ8vnY4IBGoo@{)g|(mIkTyTt!~8^nt`314AiM! zR5fi4dy)Jl_CJ2dmHG$n)O6^*oL_Z;*^8XbRLj=1;+{;W>+(1&+PbzVyDu%#y0)d2 zdcE_iwykB)bL9oq!b-hf3-T>(b6cGAe43MKVSiP1Y;ClHt%KI)>SoL~x6Q27zMUig zt7=NWnQdyt=hnnZrC1aCO>JYl&As6olW9W#4Odb(vTwR=t`YghwxQkb-gFJgG_nos z4!7MkAk)y+w>#YqSD#D+ThG4gcDj0G>hoc`f<32-lBs8Jqp#RWsz5I#daEvGE7+8% zRK*sv$#pU`g-(u&H?^3(nTph6_7?V`igDd7I)5a-*#c4iNK`zr`N-st@FY%gFC@L7GBa@DQX@#Rgkyg36CQp<*O3OZ7uIP6533JiU9p#KPduut#MevYVqbR?MYCTN0~Anqc zM2iy#GcFnpA&M4_ibVa%4?rIx4vij&3Zq4cLzyoU^&{UOEkW!Tr6%@8`=M!w!?>z2 zTA2U(kMPLSM32z=Mt$f%65SN_jCw>VqF%%lw40*jQEx`cX(^(cnd^?;M7)LAJxaz` z^+8(`lhNyq_U7u8%y&n-N8O?*YQua)OBUVAxGS2H7@|^9Nwf`ffnJ;FHfFk_U863M zXEsC*^=N70?aXvRyF{I%JBXqWN1f2lL>raiDjSt0T6!*e#EpqYM}5#oTwgaj8Wr_* zj}UvivC$ZG40HY5sAy!=kNHtiFV{92i;iWkC;eV%yQpo{-;In$p#6w<^3ys+hM!`i z9pJSN9`ibtU=2W+qxcZc+}3dMO9RuoTBNd7FX7GwOog&eRM69 zCwnbaV7@h(TCTP07+%mh=c5@SK9oGhJ8z z`mUaPmg~Br%ZSg}uC5FEEOEK*>>ftDxX$Qv#OLjD`>=c1c5)qEXZx`2=sGd(gm#jw zeV$Pl+nIb9+rhO*JGu_8qg}yFM_MP_)poJ%T?f08TnAc5+l_HM*Uh%$8SBP;d)MBs zV!l1CgKfq9@Te8-(P+GF>YBLmwwY^+*5}cWw+&o<`VCzJw2^CwHg=8BCa$rYZJWDh zXfwvM?cGsx*Uqlyd$*&tw~vvTjouU89ksPJsrFL17^a|8?G$@CTndxX zDRvS%8NCuNhl%#La0R^*CfU~f#*api^HbW`IpimzSHo|iyPazvx7}%N>>xXj(I8rP zJJ8N&G>|sP4zN!!8bBLp``afO^`{N6{p?eW`qBE^zV>NGeQEt{Iycsiv1#2nI~Eq)%H^A{TWl9uMMk@8{C8e# zukqh{4!W3Z4u021qg(jt_qhk$EofPnl314ZfGb14EP5-kw7ZR1npVb@ah4`yHTNDP z(Q2-$+i%~qqE%fL_rBe4tGKW2SGF=*$yG!vyGrhe{n}P^hwb~!9wzgZJxs5%`_g_u z?n~NXdz33GxTE$6@e6x^nJ;Kx+GDnYEANgmU%`EDKV;@}+86c{n}cWL6I-6=r+1|;sxe2K&A+K+J0vXqYs3_VF%A+p|F$ZvJm~kpa(hy3Af`CiI7G-%q88cl!#iP9&y(44@nf;yN4)l(2mw#M8hQjF0RNxKO>qd+!JPV%^ZC%{R}=mdM{d*XE41_9a5p? zcrMeS>3v!>9a=t=3u(}_K8>#s%7@fw8lT!%3>88uG__CVD}{>T9yFD|#}^Nk!eX7x zXZ4G9R$l-u;Ai7_$wqIr&hE4M)jEgIj%M>~aEs)iw^HBdbNH3?S5bp0fz--=Lp)^e^UT^k=TVW|rxt=u+mo>vQH8)1BEK`VaFgXK?;up2J!52iIIP zznkTp&ha~$KTJ2Slv?PM=A5}o{&(}6$;Gqw8~v;FpU2m8#pL$6{1x)Qnad`R&+RXh zxneGvygrY=MCP)&X!7~I{vw%6<^uhTXnvp1UocsGet#alUu1Uags$m=b=yd z`RF{~SUt<^bN*RBOb^u!$v0BV=s)Y1`A79Iy%b&MmwKuEYM`e2Cwv30X{eTvS?ZVg z5qh{@>?5AF#q^i>MLwC0>>@IY{X+VS(Bw9mU4Sn13w#Qj+&+UY@Xz?0Yzq4{`iy_t z-)wK9ukFqDDfDSS%}?bgwN=w%eV%a-^}KJ3TXBVd-gifP;9XqlSNLvfm0yXjB-@pK zH*~dM<-4dgel@z69}E`f?sYf3hjK zwm&BnZ1u1CpseAk&rIM?8H=5A%&8%;@!)EoYFACXVSIRR30DQ5)q zR@;3$oSNHtv@iSp^tYq!sc;Nxn}5RxzA94hk=gIx^Bp)V>0R_a|E}+dAJVHg{WkBp zGN^rI-u3%@CmfPaZSZe;$E;U-{lmB-_mbb|_wbxOtoD%E>)-Kf8NEZ>W1Ko)(C*H0$`VHs?es%`>x1%5UjXr}q z;6L#9st^4E^Z?`Z^zTJK@*nziXnIax_}G8s)6!4J2@Rk4k9`_-(0_t{O!kS8hq{~j z=o4Xn$Vj!$li`Vw8_i8s&M-3b!&BkOkV`#9%c-7bB$`v*r=AH<2hsaf4z(aW6LP3Y zE}P1VW>?wNM0Apy;1-adKz}0r94fn->?XOaYCQP~ZoFF<7KABoGMOo~ENUE?@ot=3 z6c&c5E{n>nrn)J_v1G=%v2Jl#6ov+=2N@df;ADoOJi=jNQn-urBqxy{8pd$VSU1Kk z35&x-@{_`ZAm>g@pg%E;CO^iFc1y#OFrNGbR8FfHMP{@c<>rN@VH}z9Xev&(7#HO1 zi?JaMZkDn1$AvNU$D#*$21lb~!szg+Kj=q?&-|x;6goPLL`R{A{AYe-_}m}zBhZmy zI64CT!hh}`MTdt+!~6aVzbzWzM!Id$8^qV6flhRQdn0-?+7^v;Tgkj0ZH)%Gfo^*= z)n!)Oqs%H3I?_!g^Cs~%X17MKMT6ZSweeFKT#qM49;aup_#Se-}HV3B0TA zh_;j487V~>m;uB=1x%qBdm>TB0>0uf=H9X!Wq(I<9z+{(kg@Xnpi9DklfL7`;IMDfeQu4}F*O0G@VFxqa#xM~tSsr=zE$ z8E(3JGMedTpfkum6Ftq$6J(x@o``0-nQj5O=_uE^`O#x;7CMV77DfxAC*30AlWtzb zGl4$F+}!A~Fx$-~GcQ^kJ;Tpi%oWeL#nB?-1IeH+wt!M!gm7 zM&FL!isnRf!t5}ID<6-(Wqx-wJ9<2jBR?m4ESei0508kQp=*H=(Eu>^ttHS=p=fG8kFVHbI}R( zBvmQTN6Vw*=n3jn#zoIZ$JF>}96FBdQ8ghN9~~ugOnn!Aq4wn4aEgkTZ|Q#*PKTeV zM>!q7Bfd-i+weWPpVarXv+7JZOMS^1a%a^K;Y|1urKumo58(&3Hhiy6qh~l@Vhy@B ztRZ_wtwz^`)q$(jy0A8!R;$8UMyqJ6!}_p}%=+*h=S-}p_nlhF?5eOb{6u_#`ES(= zwB6APGAqN1@H254GrOZ@v|Z7@@VPpr_VH-n4WETC)aU9mGW){wT)6`Mh4^XsQhlL5 zW%jeMoXqp+IpV=^n0lXs;VY_w4sy+>;gcXIhkQcjV0eyemZRSgKMqIK*Xm~HTql8uZXXOuZdgG*TQCW3wngu-|r23&~0IF7~uDWchLUCeq{Rlf&QKF zb{Oaf5C{3U!&~S;;$Z()*o_V%4)KHi?l4yE3Oms;#L;SZ5Zx8VP=PUo*>P%T*ny5E zjv_N!jZ#DX5IL-(#g1#I!hDX&1 zPmcU>HOapcUJjGUPxcf2rtnIbNM@2B#x-(cL|;F`Pw=mXO<@AF6a9F$NJ;pSQvwj^<(^ra6F9mC&LN!1ldvaN2900$>u`zqjNbSv@^Xq zs*CUJXQOkd5bEl?(C_BE`p3}OoJi8$ck{DU58oZ_Mz*P6N|jGD-_(mP;mnVcWSaVt zex6#Yn)_ycF}j$FpBBEkU!+?47O^g*-lrwKg{qZr=@)Qj*aA*Kd4MSTG^eOOK<{Z) zi1`JmTv151_N{yoW}Z?7=@-Jc`y_Q%MdK4#i>e~T`^ifka~t2<7h~oLRe=8eXj|XL zKd9#OoIFU??i1=k+I&@l$63;s@RK>srJA3@IU?2Qm+<+yzJSWF+WEHh+xvFDs-H@A zQB|&~=BxN=R8LhQQ`P5VHovOur*rB`W%5;gUNZSqUe(06_m%t%YOyLYTiI9iGt~@L zk!NluI)iKl`W4Y0#PVnbU*7j5mh-)c<$P~qIeO)NS^DLC8MG|ghgjM_LM%-y<4gGt zj7rf;`{MlEysEgW;hXqMs-~}j)*xGvekHV)uj%pF`iiQ8s_kphuj6a`@@NHB4lR$? z^>utXRnOP;Wzlk~cc{!sCw)TiAX=ZZQ6C9?f@nP|qZ%^XJ2VUrsmiKvcqG(C<=m8h zp>GhaO+{5ddbL&m&@a?dCw)y$wma!-shVgFb;_Uc1493B!uMzP1o@Nx8(*DM@xEcU zI(mwDoNG?_Z<(p4j`@LMKsZL`xc`oERrMV+)zncxC=3ionLXyeWTvY6l2%1E;ITCf zZ9@r8fomH|suJi!WRGzDQGdh_4uj|q34=o$X4{6Z=^yc}>9+~3Ln)l*twL#43N3>d zy%m|(;VZ8B+JEJHg(0CO`BtF?+7hkDv(_S%Rb^E3P~X?{&B?R~&FD8r8~FOZDcUSF z4Gnz*`i*=;-vn(M8lz3n#=enn9IAVwXgJMJ`O2U6?L)6{!FLGl(T<@5+Mc=d^e^~d zeW%bd{7V14Kj$9~ox(XXzxrQ%=kRd&h0Hnsv+oi*ho8y(;xkwsRJa$-VDGgiX!;ku z2^nn$t3rDE_u5SKuK7$hBQdkR=Kt`S$zAhV>>vJjG&AvG{hPnyJL#+bH}p5g9rf@2 zs_#gq6a6gqci&k*tgrYE^gHSfI;+iMyD+}&dXET z+J)GTe0$waXSdmGD^9mN>~q@h{YCVmPj4TvXZ-j60WvvlTdrxR+v*%PJN^4?4qMp% z;LrHNT=Re}WPkKO_(Eg~+cwO$)dlTY|D!KRzL0HArVY;WboM@bzx~Od_4hMd&=#;i z`=5LPGWXm3wrl7T@{=h*zYEV}KHDvH4f)9Dw|Q;%&@JR8lh5X{Jwo@8hfH3Z+x84S zLT)m7Y%bd_^bEPkf#yK(zn~&Y)yTKy&b)s zES325YUn%d9hOu3YznIrV?<{A9j++**yU!h-{!{}FNDtnLp55KG z&&@41t^JLkb=JK>|8tYV?=!!-Z-emD{uBclDWm-Oh2W+1+BtY8+EHsN&hx~D|)-X4ZXwPjvnUq)TlfC9q3K| zPH)vNv(s3$+w4N$GP}{Y&0FX@=52J3c?aEV_Moquz33nOJgcs`KO83>_-p7b_6_nW z?Jd@-H_YqwcbM(ycBA^&8kwqI{lm3U9+k>ud_3v z_4YOTjY2#6udxSXRlAVV&WQ4b;$(_L?Po;y_$+7^2=9#OywS{RnBa`)DTvXGXgTC) z9v)Mz=Hf%u>IvF>+`V&&PsZb?;@%u`T0KpB3disq;xqC1F-BBE$KzS}jpgnai*X!F zO^fIfoXB!V3elx_mHRO(H7<*Y{ZXlOSzs2T3mM7%Dwd(ka1!^TjYfMDi3$OlK z5FH_cR50&F^Un@v7O= z6vmlYgZH-TvI~(bW7) zuR}{~>(Z~opJXLl8Le!qpjG%vrK<9^N@e1`QK`(l(V+i*R}O{1xaly+Dc^W z)30ai^NMp1dJm%t%utC$roJuDNU3r}rOM(PQ>u(DiO;G z1Z~25>In0IErN0`ukFBp!5;XOi`b%8?uAptK5B~MI+RMbqIQ@mhL=z7e^bm3H4ob2 z=rH0CQyg#J5c3coJh>xIaXZ+Q;Bm@*aY|UZ7miYMY$vKwX4{9USecEh;bHTb?Mw~J zV|Z{no5z`*gRiCwbu6=R-*ho^ZAWTP=8}ILk4;zVS7tKb)y(5Dc0@ZeH;?DKgPD)c zvooyRmuLppb~Dp$cPd$?lk0A#+3B{unTq?Sy_tgVroEYrO+d{d}%{o%R+^fcf-ZKP zGLgCN_+Xlv?zCp68zWJ5C6&Jh7{lJ6miOSt=2I8AqgY#$&*A1dS5M4!l*vcJn9=4r{ovhpw2hSLBF#fJp z_;glrT}Ru=wlN)OZPAXz_O>k*N9}C~VtbxlrP|r{{H5LFU&9k|x4*}WZpBNH%5UKn zJ{9?U{9S%A&Z)cn61;DB`4{lf+~w~kruLihg{0=nR6dP=6)#8{GO5|y-Gu)mEtxbv z9sRWI+q{Acq?>vf&qp`R%nRc|EDl?CLsm<(H z@{DArw+vl|3oo;O7Ux}N{~XS{%zil@y3GE0d~=!o3ZB2relY&1d_J=m9fFgpBl{>B z*k#G!GqRJJ&kwbEX~S$DMxw)PQ!D3FWMqdXqtC=HXdd6xwpSfgCiZXGOJ|R?DNgHL z%rvz*eKXq}%|*P=H@7X&oWvZy1%B=v>`%9_*?mhqYuVYoZfUdmRyeYM_hSZFHMO{H#v^RTmU(xGLWlJA+@V=+^ppPo&44*v9@zutkc8{?4 zciMeVEQ=$``m!{KI)9mpoWAT6en-trU#fTdu|xPRxqhk)9 zz0r`|&-gtX(oc&IwG*0-n1)_6G%Ybb-qQ|f2lDA@>F_MJr*|(-)Ao24+Y&R-?!|%F zmfj-O8kg*1RM=G;a&jNsHfUR}SfX0t&|SjpVu;m3mC-GrWpYbZOWe9knOy?aTA(ty zXK0z-GS%F*KwIG1UB)#_Azsg@%SWhy(5wU*1y<86l1F+2T2wA$_|uFZmG zaar+1*2bw@keS-}CJWNPpH|mBsj|9kXf|AAPeRAC;=H_{d;wZL_XPAT75>Ts^z+l| zycM;7^%t`MOnu~ZJ@e+E8TB>Q# zwp2Ls?xQ~yQkKfey@^w~$uPB4_}V7NI!29EsohvOZfZ9UYMa`PhtZ~X6JVLCoty%c z+R14@54bV(9&n@881=Q0yD5Lg8cy^vsO4cJcSk;Kz9JrB_G@#*$SF!kjofMZDE%X> z<_?=V>Py<=>I+7qa!=@ErUu^VV|?amNPj-O?wD!Le~Dv!?NM{gG*mU*ab}OP?)$>b zRiD%5sY7NSllm*WQw_0Xb-wKS@j=ag?WIvmzjCcy-X|aHZl?| zj*oFWl;8taW*>0f4j97w==+Q}n1^sSZlIF$A-B`K$IMRJ4r*36m=f+KT1mHy_3XQ> z5#MEg7i}l?t}mIA?nPQDx0{vWKGu%=n3L+*Qtky>Y4;ZS-DbThjfZzVGo{@+Q<%S= zb>s@8Iru9w_8YuS7ByDeZ}B&2Ylw~vCR%(p-|(V$(wst1kyTvvol&&Y=xMx8*NCFu zvsMlE1YVuM^&W@F33`z|4t=16MIASPaK#?<8u54H9&?qp7v0O6_bRzPRBm6PhPwui zp)1sEU#3?Rm(V5j5+k{f=oR#e`OVZKFDHInAXeq8-$JXAuS&a0jrRrSs*rsftxBwe z6Y4yAo|!td+NLsd&!Sa`b(yVWDlvWztxT*)d=7n%y5D;EoPI@r<+`EnX4cw6*gqD% z1p+mU%ux1_Z^GF!nEmFIXiDhQqhyA$pPT~U%OG~6Z$)plXQ+_=8J|^s+Bx(b-?suk zXF0l@O5+N&6=tA2gDY$xJK|@|aK6K%>_sQXOEZ9d^dHOs+K;9`nc=Ph->tqW&)2Om z<%psys9r8h6kSPGa~H1cPn|(BoH=C}ujUk+vc%HF)#z%o23=#;ni1^Z|A_vG)2tM^ zwPw0Ii?3|D8$q1re&VN1V}JK2Gu8b}W%pEe!hc5PzNJ&x(HE8boKD91(8x5>eW~hb zj0)Lmr2E0Sq{g8kz0T;vI0qW)k$4vx>QOiwnrNvcX~Ol5VQGD+CTU8h35>0m>+PE9 z-mVYYhir2)&G2gVpoU}?ibqR#qvql<-JOb%$H>gWvDMS{ax=KHIsKW8@M^*IrZZ~J zSytV+ZW`m3=yc*7-IY3yIpk;K+iD3Bn#xQ|{8?S7*O;V}QIRo;Yvw>l8|u-nEo}@s z25(1OJr?IjTRje6NLxJ~zerm>!A(Rb;u-1ASBOr+Ez(_2=9!tocW;erY$~xE_Y>hR zFto;IGTAmb$lAaICo|s~R@;p#`L47k+|8s3CjoRJ*TnQ-z5(R-0aL`t{Z2W3hY|Pr zrE$71tXQ-trx0}1owR5%PATZ1ALI;!4iIJT{{uxXjuz*fgLe8MPC;m=+Y>9niA$g* zINx9xzx5>eUk`p(MaW=D)02K>+=i85fJ10i(VoP?^s1plh=b@=M+XxJ(yM_EA`YNe z6CFtGPp=j_fOuGq$JO>F&X0-cVd7V69NxCC$RAc;;CUO${TaU`eobCZh#ZRx@Cf>~ zI-+vMJ2_NaP`-e|pt*>}`#Mn}=3 z>KL`tBgpPm!}SPiv5%?aY8Nxda5xOtdr>(9Z6~?oYA5Xk)y>K5FuhGhIN!D@ITdXi z*X&a}m^+E?B!0tVAF98h_0s2*oCHie!0{9FX|leXGVQcIW6u@ z=1(cP&tu{w%1881oG#y2KT9rgLS+flG&@;r-@%b&M)%V2jR9*O|oGe*ae;c3W@~!%g_#RxeB3hCE;_s<%8ExP<-KO?a zC;Yj34&6_c^M1~ce38+9?i%?%r&zwg=zS`zKTrqI7l`ZVeTc3nuBG=8x{kPp-pA-# zVm>YBSLWr8o1$+}znq^;KJK)+RlTnAaBt3+Q~~<=bpibv)zzfb$81{aM<3u`7aKs~+G4s4HO;G38QN-eHP2mXa-wT^CQIp$)hFmD>L6O0k(^+7ko!^`RG*?Hi4Sr5 z>1SvOVsY+{atJ+yr>D4nh|#^&`o60izn9$YgRB8h~BELexA&7d>^;y zl=@j56;`jH|2z(noAoVvCAtE4iJUIG3SEf=02eJcIewxUN>?fSE&nHqNXW^rzF-;s6SI4$7iXKOVdedKxop zadNH23o|)H*6GR2K91Mpg1V?)#1&!ni?j=BE4hoPoTQ5njO(Y;*5mTHMD6!$_&+YG zDdg7U8e5M?W=ptCb@&$MFRRVr3Kij-$z4%BnSX)Ztru{eyc*>E;8$@r{H8WBx{6-q zIeY~VglIOMUB8S^LNvS1p*P~65Y3_Q(;IMCh~B5EPR4;Dnp5Y}^KfQ}=Aw#xK0jv} zd!apXPYxxD&c{JHgedw1-pRp4(I@dv4yHZL9`E2-pT;#gkkK>jArFl8nXn){>?hz{ z?BplnYwUz8Vj@0@Nnsd@XCicF_FA3oE7}Er#8{k*-Ebw2MaPnj z%qSd+$gH3J5%?EVFq@pykGkUo zV8KqjiM*Vg_b4vLo6PVqB3R~ocuVW)|Im+;HKr$S0X_^9`}kq()%U>AW^ixJdfVJwXIh{w@RgkAz6_!*@r@kf^qk-IXSAQuL&VSZZ{$9w9pbE;&&YqFuaNtK zCg)6EX7nZP3(iWpOz*J1MEu@f)TgPGx}Y!W@9ZVA-%;};{llET@*TZP`V6z*Q&V+b zU(nxD9rP9Y6{ofQK;{f}SHJ4>`WySL{Th|CDSssM1GQPdaNf(0_MHAzpR(WBBj^#% z2RlaoN4u5B_%rA5{H#xK8p;WM65T4%p0Y<#uH&qfllm08hj_vs)5p=1L^+r96ncs~ zP`pk1R=-924t<+=+#cu5mgDvWaW}c|^e%l`xAME_ouPwpn@5>>skkf)w;af>XWl()G^>E63 zM$KSNW>SZmv^1dsnflyE_*1F{Yp66-W7WX>k|tCk(}11VgH-dK_it0pcivwhn(z+w zmIf!sJGMGrnY5ugEghPUIxijeP=%?3Ay&g5lO7+34tw!v?4=g-npZ(|AGMfO@zA6X zRcW_}Km0ZSE`E)7smuHwCx_^JJa1S10Zyg8il5^E?v1PdL-a$=UAp2w;=G_MxH>+< zg>l7yjDD;?!Jl#2i+-XHq6ayX=OSK>z1s0}ZV%i+F?h5pkvk|-C0C4nWgm*-xe92Y zwyubZsJxR?7o#92KPE$yQO8#pXP0PlD*g(o6jTBh!u6Gcnzo9nk}5$It%S>{RH%TH zsTBE=RDG2Ql~o2>aaB5$R~66-%#{h{RC!f~Olj)0%F!!}C#RgsiG!yMKKe4MESi&; z3ujMhv^1j}WXpye%#_77&nRT4l|#!>&y`!1dwGn-(c*Z*@=&uUDkpPh;VUYHEVPQ$+vN%QRBl>+m5Y&Req3vr zxvFBwOsho2Uan9;<)q!OGBHyrWTHJp-5#}k>i^^Jt)sh0_VwNB?y4><5G1%HNN{&| zcXto&?hH=Qpuq;0;OQ_alTv-djt+;i7&-}}d1v+Av?PjyJAL&A5y z^*(QTnUdb9542?fEf$)R-k*^# z8bF_d-WTEl~ZMaPN}EjZ4b~hr5_B!OzJc6w5QamaBokgpC#kLEX-ncCjRbJI<=n6 zdMcfkyOSa(O`-hwp=p^-lBsnX+~JeybC9axlFH%=jpm>ak!f@w&hkn0*|dhS$wmf? z787M4sT&jVng^2e5(OG3tBxw7q1l*a(Iyo%3oFq?X7XX8qtQh!Hxt<~MsvZbX41JK zS2OBNI**%ytQVtsU|cikyly@>J((`~+;p`3XnOh>cpEaI>FD?CH4qW|^=#6L_QF9J zT|h9)GS_e6?j>M#0FcwDFlc5x;zmta+sV)AGEmCV|3@+U}P6UqZF)$mE z`VIdUM&f4w4lA)sZ-9;1KqAu)n2C+B5j#BHNPg2cmfQ#6KZlWH>N=&_s-e^pcNS4W1B#tbV%cN0X z5=WMhZxvfFmP`%wI78*SJR^_5O`MTOp(-xObr292B1ZHVXpiYHI&30Jr_1&E{Rohsr;&EQJV)LF^>eXdFDzeh~+R2^U-;5 z6Z7Q)2#HzrGng$v7s!Qj0ju+MC{HCGI)i?pKFjA?s8^BYwUE^X&=a9Nx9K!Ly@=I? znshk6o=ABJ?juqjhWnVtx*zIC{>DM-k#Z`t_;3^Pbplw4sh%bv-)1s1qX|i=nM7|i zI$1R#^hPuBJ1&G#CO2Fzf`$l}i=iRHr?Wy>_l($w2Y8l^htRNJtaGnozqE2 z$gcW?Jc*v9+D#vqCuBD&T}k3OCXdVRRJxJbbBs|veOMlm_4E;WRMur?^r$>0>yUJ0 z^qA~HlF?zVs7)qP544BwNrus3Ss&$T$p-q6JS=Om(vy^>o@56#q}~8ML|>CyFOryg zkvLS1N<;J@eLwDUtL(@9M#vG&wxV0fVynTmy-9lNO)k-J_>gTR=4>Oys5-SiWIgpE zsc0B0+ez5jE_a|iPtS*5WS16vmqq)>>^)hh~7<}&Tewg z29wKU#(U&w@^wbTK@1{=XEeDl!Eg`*nFZq)8v_S1fY}&QjmE-0^k+7f#HDd~!x}Ri zr%Um*R3n>dJg%}v)W&;BNgdD*BodXNH`;{sq2lyLo09ocjMf}2PG6M1Ioe#eKwFT^ zQ-r=Hi9|&_ZK;EFn5sfjRhX)(OX}r}!=OSdlTNh^QnaLAp(>F`wSvlWsL+a}P_3l0 z0yeY)`BST?tb`4%!05FqN4C^!RbCr+YI#zqUQ%Dp_!YA^sw@dpZ@A_)p4Qc{k1tqR zjT5*u-nh4_3^`M8x#kTX*fp?_&skrCXSfvpxp!RiRy|S&c_NRfyu&lQ7E1CNSFKeW zRUWdZHgd0d&}H;{RbH~E_Og;!Kjpgh>M7T*g9qKK^65Ra{Q3#i4eALi>tRXrlQ*@S z_56C5DnRPgE@}nzW3E`D9&^9kF?CfjKn^lNLq6&|(?+J^k6Eo!SW+LolK%}}#O+mR@>32xJ9d%n|~R3pCQSNVD$ zK_5Tn9`>nCYJ&cq@lth}wjbTE4xqm?yF`Bg*6@<22k`h^q(z_+aHAJl35V~z$oM?% zAbL<8LN72IuO6s}5ZMnHO;Gpg$1!?{K2%rWx9?M(i2waQ6!$$wA?hyuBs2uQLq8dv zgx;oi^(}ghx+G)WRJWAUlOeg4zReYiRIJ-73U#fc=o{*$l3M90Dk|eBI;y^oTiszk z6_xbSs6^G#^fesUww?;XZEJ`AI}FrS^cq)uhnKttjXjRLok2SRd3^$QcQLaQ%F@%| zyDdFkg`zgIMXa4d7t=4KKZTxxI};>Zg{lRN&Y%nFf4HG)EGnqar*;NC15rDV-so9% z4n4DC z%wyFn_lG-Jy>wrBIvD=vh5Hir=LKzudJauybch;?4pqa{GxxbWOg)8DGdc`D=czj! zV&@6`+6Z;h{pP-g#`*?@bqeq4Hz=*Ij82ov^wm8<^)(FFXJ%(;r(wH3k?C}n_8I+5 z^&FM6c+5YL1l5-I32n!$4J+r-PxNi5eZpz}juff(v=8V9u4>K7d0gl3n73kd0c}m+ zkxB>jEqxHxi)btQ=2SYOZ|E;`XZO$(^miHENAJ52(96tP@-e@mzqyytAZB-1dEmBS zb_rJL4&&RjhcHYJ-ACwcZ~O@6uMAgRLNB?;Va0AyxdHt*Lfv5Wgz-)K>+~bkb=pXE zjhWGr5K~v(QSek(-O(x-y~gYcd|EJ!Q!o_P@9r2i5WT`|FMQiTRhG|l+$~Gn=hmd{ zNB6r2(6Y>G&>tY%<$xQG)}XJ(C<3icUzJfLT8+L6ql0Kw`nOIKn2t^-sEEe~^?>o9Z|2tepFed#vR~li!?jXgRmMyTtlT!p{=x3kg3< z__)s`S4ETM-Kew*ZWJ=Ej8-7UXE6yHU-?xLMOJh*t&+Ql`AhOR7Sp?ATvc*iT4h&} zab>hJPff}yJUuB7!um;)uBy0>JmelmCA}>VLkO}RPjAU1?orgH7xJik47KQgILBZQ ze>g%ObH9^uwZ~m+EwWxZYiX~XUDhl7+q>YUUpYIi7-U@SB!xPL+(FK?59&kC)pjc; z8CToMJ&7r|S+U5t+D0BqEVs-b3Za!?JftPXKiRr%RfXz}futk!_Uif<>dE3*>cu0>`|s8x%4 zO=zvkDuG>zme5XOuOlxd33s**jY*%D+In<7DJvDZHlbaSmdFmYH;~5?Xs4yG00WlD zu0Ts{r(tEIm4>#-N^Nf<%_TLpO;#4%@QLj#G;>zVX3}6%*{SJMGTVa2CJihlqpgg$ zTCrt-ozjjY{b_O00QwYmTvDx4*zu$v>d!2>ox=8$$!PJ>_%b@0oLN?tMa8g_auRQJ zS%lP^7;e#aK6XKK z$un_8782|ok(C5{M`W|JquEKY=T9R`pFfS$4;+z;uh|hcpTXiY+QJcrikQg%#|ROk zO*(&JJP<;xvDcz&?PstN&*UximQ?sB4JBc&E`(dc5&L-k6QWOwLW~FTuVjcmAx?75 zK>oc9(aG3fgVEr3Y=};3C9_~U;DtkUsGF4WcYZ=c^mMWZLUbK99jy(y7NYlBwb5hb z%ZKQXyh9kG9rq)Z6ugh*@88|-fsd-2-5u>o>)~+;Jz*BQG3!n1Wp`m_i9X)EGc!XQ zbVmDn)qdWnBhGhARKbBh2;WQ4O#}mV>B3Cr> z{5rpQ4xUD6BYeu$`E&cB{kSd^7kYcNJ&y8F2#vG(PqMT z81i8nS9D}NoxVJOViU9pzUK0@W@t0JIa-00a$H@VeEin@8MA4#phA8!B0+X5GVxon zGKcmLUL=V5T)U+mga(n9KaW4F1=@nzJlb3ckn+^#)8@g4lxMUMU0^Rl7ea-UXEX#| zjK^#O{KroGW)nQe*+g_AEXZznjq&Js>bq&X@Rfx?er#tw1XtNOs(bA*&>MSc39I+J#n%x&lvA zZO`9Si+&ZJq*dH)O?r%LPI25(HVIKiOW>EXaJm^SX_w-k(&8*BRHDW3P6?cDrO;CN zz<$shEsZmb?Ost7EsBH6ki-YPbeG$)-R>bqI6~V{$ znaU^nB6!z6p*e7l`M}&nr_V{t0X-6pSuR>mxEvo`X4$FwKvl-XS(c4iOxTiWT#*}3 zS2SpzY}B*Tp23qurJ4s{N>ryX9xZ;$@p+2aSy+FDKC_>r&vB4t=9)ZkLdL@qfM!O` zyM`&?gKi$3be`PZ#Np z8V}SXRv)5?;FB&;E9kjHjTXcYb&lSs`F(%R`<;K5-XSF@Bkbx(naS}-N70X#86dMp zQy+yh%ok>8gp3U{G(!5rRgJ(W=I;c{^zdB4TsazNSUTviF;s%_&ZT2CR;Gm=8;6dS z?L?rH78W89LZZD$;{-ZwMOxO{!bzlsg-GLZ5~-au9w#wQwjq0HyzD4adz?fnC$+~( zjF+v&c-(uPL@JMy2yjxuLZoz3d7Q)q*-A{{-P`6OfU2P-0-VY65uVV=G7+B8$ubVK z(_|SJ+G(wycr z8=OP~{Q2F)dZ!18-s^FqwnH~Ct1r95Nz~`6?xLRT0Vh$9S`V=f&ZwQoDD)I{Wlv~{ zI`9#_(Yo|?cz%OCQo-mToT;_wjSe<`QrZyQ_O;L&w4rEC`s(yU(V=)YtI>L)z4*>n zqc#k#U>%=vH#Asdd4$#k-A#YkF{FaoQ*I&;k?P$HZ3fA3h@J7K@*sR!a~Vl%fkLIp z2&V-ULOwTj`Vmc<5076KLH(&ntl2SwDYiaW}ki{Z34{Q z8AkJk*{7c`%%1%M#`DPsF}wBiU?$F>XSi-56+=se!1B$7nFw(f3A0DNh`OOACc*yw z%K9W{G4(}au`s*bi-p$&@c43yM?Umh5p(Hr?-IGK4%u3#59<_{SbZgsqJ@WG9Qi3qMt`K9Gy=;mr;br z02*2_!f7dgr3Ils$-yAmik#A++n}@QXOf%V7M(>u1CMSa zbSAx_B}T(C&Ttxew8Us3^Pwb*4?0s~h=4}q4bp@)hkjB7Hhqs>li9a?Sn7nVZEnH`CxjyW$P z6?-LSFSjnO4*LPioG_;vS1ohu=>XR2(dwFa@L}nyvL5Et*Z!>3r`6+q{N>IH$GpS8 zoU@~FIJ@caM_effCR55$v3}ZLzG5)XN`l&ONeXOTco;Z(~kI;{Beht?T zoe}I0J)|~5KXc4()-$erifikk(_BBGwb0KUv%mG6)n`sTK9|`oZcT6Ar!TJWIfL2p zy2mxoadSOzTIl<y?S`TvKCXTHJXnmLmy<|IADb*1tPbsZW8QFb=POCMO2#sqhnn*ja35z2<%1 zX4V_t`E6#sb>5-x$Te?fz32VjX4VJZ>22n{YisC=*Q61D;+ zkQn=46on>~a4JTnVp?>dn^oR<>Of-d(Fz@%bfth&kwzkYJ zL2GIs+*U9XA5pVo5Ck(})a)&^gqARBb{JY%Ev?UPb2tg3W*4HgW%eZuGx5b8z*icK zZ@#qk)h$K)<{Da}=AX1gCq`xdf6Po6S|XBmSNtiuQj`OZ?;{DtpYt|DKkpPVUZQ@spW&3>#ti zh@Z3syH?^6)Wjyf(tVH-S70LyEpg>vXbHnf{A4E9i8HVf>;8$BI0qH6_D^PFE#v?9 zXo&=WauVDAEhn)JB4XSBF)d*T315CX{=rNP#9{CkGqDU#;veKh*uT&cVek_rU?#%g zAPg<>lbk4Sm4KJ{@0bZgOZ+4!{-PxeIboQHi>P5Ielin9Jc^<)w8TYdiHndEgJZ2&RmH2pU zePAZy;lXvRgp7@MHU`W@A~d0!$YUlFqsA#44Q4{PQK2F%RN!=t0yFVLMY9sSKa^no zhf0h$)~0Tu8d~BzUe_ecE69njcwm#c zUuntRKh!`ialEo2g$MG3_$UHAS|Y%WN1w@~B{H${Q5er`a`y`@1s={%;t%8Qr2njp zZ_@Z@Q+V#qKX7;cAwG-ruo7R;4D{EPKj#u$$6f1>hw}@}L^?d4Uqo7FU(wWX5@{Kw zwgT~Wrm@oC=ro$f3baz==rkH=rL|Jw=rn4WiIg}xjT&ac#mi~bFcZ)CivGX>V7#|C zI0-?c*Xf^7i-JbMfor@NQQb%QAdE)Ehx<@P!!!C&MR#MMkC;7BF>s4Mz`qc~y{{f9 zANM!;fjqX0@;7PpBW_^hGBf%K|Hma(jaThG&gRSV9cgu!8DGNl_7?xi?^G`1gL{Kh zsihvJt4MC$!s2Ku+A0f_9#qgeUU0dQ7{c9x*d|2M5OwOW5b-LsAp& zs)w|D>H#yO_j!5`7~Ll|f$RjA>;$~Gq$c3Hy(dXfaPP`k_-^k?G89}=6Yz20kt8U% zq$Y6E#cfG~f_q5D!E=2`lAr)NaUMUH;U~_^mzHsdy|j!w>?QofVfn%`?ywh76i4NA z$cba}8O(%H<1Bk>8L!z>%ec>;LQx!-Pv9p`%KsEO(GWJG0m&dAASdd3X3JI%c?`WZPlRO}P)O2dWOw{!FiG!>da^mrSF%yQOI4L7&r_f0HaO)KAzi`NjQ}Tdy8h_>i z$cfW(zjX#@;ePlDPN21n|I+XiXXRe&oIHr`qc7!=6Q!J*^d(7(I*uNPoG9UxgqkSf zkrTz85-=0RJ$|B?QygZZ811xG)F}otQPkrnijW|6#wy~G6T?+CGN^{D>dr8Tr|M2= zr!_8@>dpvNm9(l6tPaPMQI*k1RfW8(QK)fdR3;5;G&)L+R+UJ}swOIWoJ4u20^<>5fsAASZ$qTm;pM zVhk>!iqH~cR9Py9mMG(tby}&s=b&0*<)+VgfCbn4>bmOw7SAmr0})#?O}$eqxj7`N}M2tIUuSvzQsp z;*k@^{}&*(;HwPaBR1pv$_hDQykJ>9eqtpawwWrMm_f@fLREH{iBM|U#dQ2^InW$p z0Is;{JjrRafjH;PezbB&Ah#}7h6Lr5eL4!)krxO*nUt48q%i72dU zTs@AQg41UTylPbHQFtk3%c=N%45>Q9mCzD1U`FGhhU!>M4O;?NO~VH?4GM4(b5|^K zc{2iC%xobwEsQg0I{u*PI1Uytk0KVhhLczTQK-dt97Cb_hC<<9=evfSn9o&F#XQ%L z6Z5D=Ml`B)vxYSysf{&FfLJZU_zIv*|ad!_;qK)jV@EOph%ai znY0z?Ec$`&3OtAd;Z0Yl{W_UPPDCRsXfNc1(PShB9njJKBqx$XP9!HK=r3|2D!wbj zPeetd{f(U9_nY{OoT%ZHasJLv?1r330XdO^RH0qkpA4a0@Du)!6VKp4|KcYGGBdP9 z4JT4_VljNgE*$_Z5kRWY4rVDmTEb{b(u20?RHOuLgPBO>(GscA)H016#8VvOZh@9a z11*t;RHV(&5=mhqHlxPPGRRFN4JVO^T2eBG20^AKU}caSpV?q^Fg$B~`3tnGA1){9O@23he6F6@6b>;4sN31=x}J-*f@?xxaHv_R_O|I1)M|$#^z+fRd5pJ zNXuHKD^jmO0+yjA%F5Ny5@lImtt(NfNM_V=eL|NZhieVG246jl zQpIHnW^=T0rNKE8mg-Gbp60vzEq0kbsVIdMyU8s|gp0rRGC%I}7x=>HoBixbhbjXPj zZZ3I9AJ(}%P9hgyT`^9a80n7UB#G(txmnExEinr2*)S8M+$nlA^z#&$iP4-PF+~TX zhJl_0En##36po=KjQ+~+HFL_uuPTQ}OXToqi5wm+kwY%k%XAK&%_5zhRH|j@GMI^M zG7MTG8wpimIxCdKNHiOL7AT2PXjb~naui%%}274@gEw^ zPqNV=R`1|bJWPLxYwzMm%*%BLsoh2I;(k5m<{?Gt81zp<^Az*Q zn*3aBv*obF1nuGOIcMNRAQ+&;1^b>b1Y{U~B z&E^~lLra{*sXI<@=4;uHn|TSJ@q}xbi4!=Q$Lpn@!+9z7QxN(~@ilLtH+mXJ^LpA@ zbOZf5`m^X+T+D0fjT&F`8rlUfso=buK<&k=n?UV@{7=Z(oRXJ7ZE_Q-Jvh!1Q88JJ zyYYu6red-fcacz#gi2!46?eM3+@w^JKp<~-ceu?tX~E?F?;xR|DXU2tH)Ga9Z6lSS z1=lo(XKuATODnV+CyOkt>tyJs54QzJnQ3+za+1=tc z;;Q7(=E+G?Y((={DY@%SZc4R`bcmFUmbqD|g`r`jLp06LMIr)R}f zR`WE|k;QlsHQw#C%6PZalF0a*8>lYf>JC(C>C>n{bs4>ke>%12rB1EV(5F(V@mi;% zoj^~x6Ldws>UwxJQ>h8MJa-XKm8bdPhV;WhS&o^XD$6K4T8_R9qa0`s{Eua*WyeWb zhH)ucF0?d#Nk+NRQuJSC9a#Tw=vVno*2X{h9sMT1%UZDGU*uO=7p;H;^b4a3>Ie1j zWG2=mJ718Z|3eCL^=m2%6=-$(-flJeK4@>!9*iHi7kLlW(dt~$%e9oP`cm&hE<_dl zxIM`+uvI_CeaVh6PTU^k9@wZ&dSZXqIC1+^??*mD57!|f!BJ9m=I5d!S`qhcXRhh* zYVNU+GP#sS3*lGo#z#n0l5QA>c@Z=&eQf$7Xc7FRv1!FrSJD_1s>rzXrN+4rq&K*z zt3JzE)QYKCwBjlztpr+vCm54jaq=s3F}FtF_w(ZA0xcyiRM*1#8O{msANj>`Ur0 zvn!m6&qf+igY9(P_TDn1K5Nj7$Ddk?Em3Ggn7H&(l zC2QrN0BYl{Z%$v1J8ceGP>#xZRT=`}JResYzMwV^{Tj5oXiaA4;8)6^WuOtNQ>*J% zqt!#}K?YQ#R@dFC&OtG3r4@9mQmgM)p*29OdgBJ}JI`Zp^qqW<_x`>7;5qQ$d;a_n z=m+@`{U|?q9{x|BtKaA+`G?Gc|KI2zS1%$*=wSsmGJqE9{+&a$M za%hR;Y8CaBoR4}K=4X|41j;82TB3~;Mr#W*ahU2dIEl8<5^bG!XgjAp%*0{NP+emk zREN|W>k!n?Qm$(6ETwgTnK($b6L+>TC&|LkIZ$+GQ3Ht#OghqhZSf|h9NWgPETy`9}qaJ`&8kaE4K z?NL3Qy*#&`PHu?pp5!6#RXs>i&g1r=<#oH0u52_f+;%r7AH;Sya+veEU7h@J|6NIJ z&hK{Nobdvv;qp6^_naA8qA3}=hM8yzEwR>WhBk8sLQCwjj1F`LIXj>wj1D4EdOMti z(ZS9y&Nes+qrZ?Vy%kQv=n!(H|IcU%!%6&PCJso$N$i(~lh_Y6JImS!FFPBJ2T8Gy zQ9L_bhC)k(%NfuT;aqG>!h zIEkf(1zOo-)_KHwdvnE;Lul zMd(?GM#Za_E4jp#$($Jwn3v2nnbT2nnbT2nlEi2npLGBy3oU0gla| zwU|F`v0Q=M< zACd|^C=YSXUh5$GlapxUaS}a9nhMb&yldp|KaoE-1iut_iE}H2emrdgj;=}cQ|N8H zVWw(M?6Pr)nfVxRWX|(~eG${pVA>dbisrbU$WYY29#yPUp|=!&TGSK^!Sku%kE%KU#8YG=8*XXmZP+ z3$)C6Zh_V>_{##V zH1uh$LHy}y*;B)PW~H^di1h5Ebzx65J(`gmyDlP%l@TpLvR+AcZ{yP!M@yh4rO%vE zPxy@IYz!DPnKhB zPV+GulYP+&jAB~mtREkKA`7yc%jplK;lcQjkH@JH?EZ2>gjEDB#y+uN*Si>M^ArTT z;0e*hRw64ueE};UnxCC!!OnFaG%v}1LgXPEP>9?l2MUqPsxQnbL-omItb|74Yp+lK zVr9nWgrfQ)D!Z)pMKpF|>x<~@&DIw&*r%;8d`P>iFDi1M^+-glidJP_m$5k|Ix~rg zt@s|=_;fQ{=6vWZWGB`ZSxHQ+&A1NU!E9tD)}m6Iyrk@8CDx=;i(P^oWF^)RIjtOM zcB<9+J(1I@POCvelVCp1YD=R2Sj!~wk7Yd08jshe4d+z1$7?=@`dDiM^VY(gfZav} zTODwu2eUec^v;f?^^c|!jBBX1aeH&8{LJwYt%W&5+ZLm&P9*n_;>yt^dkK#2EStGR3kP@5ueov5Ftj*|n`jNbP zB9(+T3Mcslxyc$zvqgkl#;e;18OE#O2)Ufs%@J}1ucyf&;fY1amAvMTkgIq_9wArr zsyl+OaSOR6-FTX3&D0-Q(BGw;f{8+wtx3x0=-=tbt8@i+X2{>Ho$=3~NHjj#{f=3MH-toM}%sE5PaE#cMB5h#&f zs5#l%oYvKc6!@jQKHAUf0f@d{Jd@q9ExmYU*^~QQF5Ae~XlrJhWm{&OY0Kq4dl|1E z_wlj&?M>7-^J=dh{a)((AOOR7y}1`cCXCmD?O59=+tY7AH=-Tr_prLxUN1W`TTk1- zYr#&;*75W@p&hBN#VK+bz07_B%l7>j- z3~hsbjLLDG_p2ZY&%#`6KsUfc9;I>&8e%n6;ZbJ|B;+|LjrHhyILT=cNxRTp-1k(7 zq+{qY=0~{lDE!D;_{k~u309`irb20+WHy;L#XijH5oZ#N(n*NTlT;5;ISgI02=+1r zUg;EiinWP6v(xBl<`WoCM9o>^6L^wmAWWw-8V>t=(Ud7=XYG1YTv?N9LjaKoEdPvSI{fCsecoX@oitiUuX0Yj_r$7%vt46@OGOs z$RDB)@nm11V$L>yiWmHMvWg#|5Aa@}r((`Re@0^H6>-j4XI~+`_&(#^{C~<7Xw}_R z?!(WRQ>Jb5rJwOJ=frc;L(ih;a9G|WG4zbM;M_y+Q9Ug#!rz>xat4p)MMkGcki6)e zL{IVmA;xXJ2|Y<3^(96d#bq4Xn^`$Q=JO`{4OBLwGwk1;4Pqwj@&@rc*_2!GzaAqs z+MJHQg=;xGoz)HKESTnX=z6hE%!W?h%K9VlM3RDlrdUc@^W;q+#!1btn1e2hqdyyXX(12XW%A z6!W2(S91L-^0aqR*-eWeeR=_W^9oj1lDxf}%5t#~)_FPg6=Zbpp|Y12F2clg=;tt2 zmy>rr8a8_wl`zJ$&*C=yXPR;5eWCu9b{&V`ZK~gxT^FAi|AF42 z|0wR#f24g9-&wncexv`v=qmc1{s$vle8BH}7ro2X?-_qU5756ujSn-NzN9cGsh2>F zSL2mr6?6KnIicB{wfmH`%el-8L2JzwZyjYx zyzvTW{2PZi)$zu^btEb+2RFRS+G|H!E}nnQ{FQT0XzM*LdIxnZ+cGEpJ|)NWiFk}Y zr7y^zY)u zT);=>M+=|}>GPra(M9z6pvV@9Xwo7DJevH-pOBYIKHN1+==0F>icii%9NC}vGhaBl zshjhqm(oX(kHkatA!}Mb#xt#{M8P#tkxwr{ID%29y{VhEYRCf-Eq;l?29|_-$vuG zKP;Wt>=-kle{RQOxB0pKjQ%MG3}4ij-R7svpFyrF&P91)$7FZ<1tfJ$C|2b>g_M3_ z`*22v54+HhsXVbCW0+OWD?0{z`L9@y0ZZ#Tk70|o<2v{3=r|Yd+0mr1ID?g0bQqEE zc62zBuW;Yr>7(Pq_>Kzs1GS{!8XIp%bjQI3lEA6V6G?z|#6caZ5A7&W+z;)j@Z1mi zERQ&Ul}ue2-72`j9#DU1`{6OGBK)YthvTivD4vr^R2BE_Xz=3qx#oc#*D)t=$E6+* zVmULTI8GLPL$Mumns;o*abTFudEmZOVjCizQ7p%t84jr~VmUFL9JqmeP;)Y=IdvSe zop}r=7tX5R;I)O72yXp8=fUP;?KQmheF$@N3hX!ZHPn0(2<)%uHyHY)5ZhnSuaNY~ zAh|!IU*PDIL!SSEeukz`;UsrHp?|>C`#ULk_xQGb%kJacfiLgF*u2kt3o5-IE4S?4 z&RvM}-mLcFz37|v4ZA<tM(Op6S^5T z_L_Z_@j&{m&KBo)dn4mb&PLuJ9_Vaywo=(fyKHZuveDVVd&PsC?W|n3x6>}!>#1yT z*7LscVA!_bcrvS;OAzU+xatxrtRKRhR=6HIbqM`%?z}hp1_FK(I^3D$yoJbL%j!DV zwxRSP&O5015bBehiHt+g_b~J3bi=i)I3FPGCs3aVM>mY>cq$XnkMQ^7(DBYV zp6Ew=EIJN?)t`Q>6F@%(9Sc1fz$n;BNk1A5MpMy`LPw*i=|?$f=trWXc$YSpNQkCk zJ_1@i4Gici=ZBcWXJ75?fI?jjMLU)LAZ-T}?KEbQw1beL)0sukA|XaYnT11khN9D{ z9$*~qK$+6-ryX$8K@=``(n1lgKvytN&pZrGM;}N%t&@RS7#ar4n31*=%|M@t(GoNx zeP;S4?8q#37O?}<5^Y6Whz8NOU~Ms)nZ5<1mh5_DVb+}1g58*fu&=GTb|HHSSy^dD zYwon6Iv;IK-<0HrtY}u&8d9By&f}RhWPLvQ4!fM4=uYl87cCGE>Mll2NPx(OX5%A^ zQYnV+rf*D2M0PYgYelFOMfcDbhR@xD?qS}DOo<$54z4Q%tGgH7%UVGQ+L`D+<^>t; zNB1);K)oQY&{>S~L)^~7Gdi15K1kfzI7fe_&r8ckmc(3Ud1!e_pqR`oH!Tl7*M@vW zCHTCJ*jp-r_QG#l0xiM3CqCSgXi4ThaL<-POEK?`YYRsztp|HFWtnxOb!Vrh9J8*p zZtT>QW7Ng1kDIwO+J$or8sK>D>ej=-+?Bo7dQK-Qo!JL%hflg2`@nV4y116RvrBBW z4j$zm>@6FujTgD0TMK`%IfLG4O{a#_fSu}Es99^kZgvm$WNYC0ZOndb4W~Xk-aXk_ z?8#aaR;rU>Rt=wT6GqjXdaTxGcd|EqQ@1M5qA6EZb?UO4-kaUZ-mKMhtMGhkvR=g* zz5-GAFi&$E_)xmM;+O18^!8q_C)(pt4*teW2qz6k!~mU z&_=M2)d}t7jAVzkKUdYF)y5^(h4=4=vpNFbSb3h`Ft;4faTxXCxXQ{i8iEc*E8r&n z#jS`R`4`4R@TFD4l{}crFYX|>GOpx7R0iW`Dvp17AeBM*1^e@vn$a5_OWzS~hK{4} zfOcf>c^sqmcrC}V`#hdeJA9Vo(TVhJ(ROGEeH*kbyY|)D$JMGDJGi{{Pp?!B_Ij0S z&K|I0)n%t$tEz4kS`{}cGow}9%5F4v;Eh%$c`Z8o^F}L?%l6W$NK)G?s{*^Zuki9$ za9>!_RYlaSy|&7;8~qx;e|h)06@xwg=d8XUSNXM7&V55G>pr9Y9EZOTK7hBZly%?I z%D7Lhn0N)AQh&x71aGY}?mJp(_X+i@z zNX8C%3pW|7$<-t3kMYgN#oD;zwns3u}3 zzctRD*31*B5T0W~G?7ZEChNiO zjf=*^YY~j+^u6VeqvAcE@gWpJ0B#%0PKlewvID3JI~5)sLB+CvSg9C&w^HMG`Of$U zr$wZ}6Z6dq#2@pG`giLq<8M}3QrLV*&avss(8`kJHVl0tw`_3C_Y+=SwgOG(FFAIsQ96k=@U^^XhQn9RN|pk z=o3S_IH;me%(}AUP>+jNrB6c5A;steP)iN&vo!kA`d~FdYuK^5CJtJSzA=?1=qKx= zWvxyVSTb1+Fz{C=x3_2xW*SPMc;sWL(-4})mN*&{nh${ zez6*miIf%xQa$SR$wW$rC#f!#dSoJ{$E#F_N?p>BGT>yYO{ETLNEsN_vNPgys)^Pj zBPa!4sJwiZSnL<(Mbo26(R}pj(DZ12`m|^|v;ch|niefcp9T#?3(==W)1ZavZ>T&Z z_!veik9||+CiUkgq*QMEno7pb={1#sM4xM{U5636sYnQ-<+N`zGn$j#$UE>sMsu(~ zxkhCr-))V`MzY%)y!hGdRVq9AZmVF0vZLAT)wu81s4VtMDy#6U-=$wiEsMQQWoG|# z9iz_ER|^_^NqB@F(`pZOaVVEfyz(KoPIDeVAzDXYtHOJAjbrBc}` z?N`)aLtYi;sl8OG?Nn$gsxMR#p5hBt)GmS+ruv-m3vz;s+RxEqc2WB&`V2y>IC)f0 z(5KL6CCIOOj6Q)uD@p3rMn2b4n1NIHL^jf{;+#0mY%gsiUW(I<_TV--jnm=`quu1j zp23-Mj(!(yH;#>SjCSI_Ifs+uJfj^rbk1Y2I)Sf*U%#%=<2X$u73E5I6J8dHujPc& z?A0DakKr+i0x@UwD6W&JFmy(b;3A0zH)r%PzLKZzK|C){+(Yb#KVfVfm614Up5dm9 zRFA1Y!TA}D{t;ANG~Aofm_NsP6Rw_fZG?IVX9sUbdxT3f9JkF2*2C2Un7bG_MWOKU za~{BR^OE%g%9p#9aEzN6C381JQQU_hgCwIpaFbF=hHinDNP;GXliUgwaSy%>&dhZT zXU6Ehn-~w!RyfM7Tz8lHJt)lW_<<5pPYj*8ol!z}2kw{zIHGo-J5)lr&I^p<7X_V3t1T1Is^5LxOL-_A(0hFvxQnDFr=69 z$aqLkJp=ydtWxN7RMO)B_9Jm25qA|GeT~;3P`|<58^}13PRnXKnO4Rpi6IU3K=du1 z;57OjF5%Q@8Xd@LS{W!4kjIdUN^0~yuHsbs16jdos0Ye4G9jr0DfLIP1X5B@r2`nJ zL_d)z;IF^(?ED!AkV*0lx;2IV4jG$*x<8pD-x(#-KVWE+X#s(oj7oB{M}(VHl!Xe{oZDeD+7Azr1PUUFObr#01WsbFPKsmw04u4XB9g%t?4hz(hwB4W!tsa; z#;JKa;XJP&ZiI#yvLmROaYp|2iqQM{eHX#}C6$*r({}6Ruot`e)AqnSq=3EHMP)Y* zkJ7wOjpR&o5Iwy<5tf=-c2Eykp!GV)C=QQ&&a5N%tSs;0mcRKtY>1BUuGslC%?=>+D<;1 zl`NiojPv77&&sF_G{j0>7DB?15M}5~!$GVME6|SV64Xn|5|9vUbwyT=p-1%*^q4-Xi&HOw&wsr(6vcYx z#b6`W>!N(c8_^9^i!$1vi%=IgtZG zA~z>I&!W!h64Y`)N92I6n9nQ`ghU=rL7vGqv!EgJ;=!Lmh0`VUd{#rrH_D6VrMi&0 zAtVy=Sr@XN2qs}6cQc(Vq^xidSs^7Fz>pk4598Kv!00eEM0VDv(WdK$vH_&TR8o+# zquHrWA?GLunuGadotD{T+7!r$#LOnqCgTrE%qT?1hDi_Mryw!p$zr_-UBcNCl^`UR zpvyR0q7rvhMAl+#%wP7Mg>e^K5$XfXMN9kHrYRe|N zl?;-Nb$!_iZNIl%d(8i;gSlXuf)8Oti(!VS%ykk zGGbcMS0;t1p{&e$BeWq;vNZKFXlwf7tRF%T;VEmcE6e(_J$KuPM54-!dh05(vMfas zPHXaLTJtfzsPsmw$||xX^-^Tnw59J!r59RFR+T-_o+J-dm(^qmR!fqD(~iD7l^$pf zSzUHRyOSbRQ`TTyOV*TK(QYITji&DcB{7=Rq0!7cLrDaq!OS~BNsK|qFz*N@F%})m zyaSZPICLEITzoYLNmrUctq-jONl<c^-7c}o4rjq1;+KIuvQ zNtGJFs2*ub14y14$fz!f69Y-78pNm$i8Obi{}%}wYhaO?zt;OMm6%YnyIQJD>Y?oh>hwbZ4Kt5eu2NJPPK`u zK_=HAHGtY6+F+QA8oCKulO(T3Xk(~~TBLmqgw{2z<^Zm1NTm^4n{2QKYB0~PfvQ6W zSOY2zAt`?0S=LuWNLQ-QxB)!JP;!{+QK=7&FpR9Gx>V{xBMc|osScI8&Qe5y^Q z4(vf6Jwn%_Qk(GvzTY$XDi7)w+`~ZCoJuWt<`#@Y(J^RC`srvW8bm)$wW6O!n~t_- zHWi%)PuiN%6xD`)GOTbLv<>sjYKdA5Ig;7a#cC03$P#9mprmJ@Gni#%eG$4yEmYa) zjV@FRRCao!3!qMO&>Ni(hZ^C|gHDZf=fW~Z!X(XA2cf#=ppo?9ZceTXcXM!MI9EnM z9_3_o2nuSBIz*eT_Pe>@IrdXO082F+!uBxhv(-K~H*Ci~R`)|)&4RW);?Csx9O0^2 z@CIYK<1&!iW6`n9_j3I{IG;SQ3#DPV$D!j`E5*1pI)T0vOz;HQpS&;)d$@A1TarpC z2%vm04ZErDaZA9aO@xe?2nA6b`ZffeOkbQ)3FwK*jEX^Hw?*4BD+-_84sFN02=sP) zv?F~HMn&N?Ix;E*?cEXW$h;u@cPF$teL+TrASIeJDhFM$8-}bLdJ#Q}mZy3Fy$GdK zL6ukM(F^W*c##T>E2)a=9D3e82U$`{okh>VN>zb1Im7rYjO!h^wi&crXej+m`djd^ zzp*l%77B}c%e{%tq@PWH6TRu)fLgubUPous=X9^RSJCVAIT_``(?5q<4rtdoC@dXr z{wt6`xmmq}=AzHeY7V^Vxv6J!=Q7Ji%Z@kwcPOH~to#l+Fprh2v}`1xT!u8t$jW7R zk$c=dh92Wi7tyA}dmU$#h3m7T^Xb<>7#&AX(yw8(78m<`)-t;b=vPx;0|9l4eib~~ zDfA@OOsr-`7t*h!z6yrwG@}(fxzlJBp51bE1zHu3Ck$QghPlK$g|-pe>WBN z)FPD_NeXrf&NEEzcI4g$kZhix6q^ocNAk@JKqsW+npC1a;|?UH7lcu0hqfmjy%0o8 zfEY!Bc7W(l_IChRrW9@M!tgU~S#4+gQx6brsI;})*hS!fTBB|3)^<^-pjP%ao?I(? zD^IW$mDYBUy&Xy~hlJ! zzP^r8XVTyOq3=7RzM>0rU&gWF?z@sTAB&1F+9)=5(M`x~qz6*rkB zL6bn?-y-M4Xky6w*Kqd<#4DKyBL5ZR*U(mp7`>FYtVH6ayiNAW8~A%a@dhG4KKh#e zg}g)R$qQCr!d$(Pe&RWm7r4^zayslgYJTD!EuMHr`muHzf*;{t;G>l9Cb?BLA=z zh52JvpOA#}yO*014MzVEtB0+FR&==hgH|-=2d$nwyGW~--P4X_e2{dM-kb#xK_!xO zlsZJ7z zdhn$69j@@C^#h{tq$S`5Pg;C=tlF@ECoKmS@FeE|JL(iC(0-MtXkX-M&Y?B>MSg|> zh{sum4lM|+#(am5x3KXa%YKha6GfwU4!TqL2y z62Eb(t0gXxN@9u2oCIu%6P$)@&RW=qnlmNL$rA7gXm0)!_#l>|%lJ>=nwgEuZUuk- zL|*fT=-gzHSkMy9AsBLr5soFA^RHuw9>K1fB?_prj3=|ZW{I-=p5=OSYAmrB9yml7 zcMMrR&<#d|dG9_%$Azcm#0cK)4be48z7NqQd4DiOKjti|5Pe1Qe^)%4NbT<*mwU1J z?nI-H!{5NDs7Zf_LyOB#c@##z{O#4KX68#XKkF`|nEY*bQJ1+7f1X4oH6NP!S$7yk z=e+{X@Sw%uC)|9lWLz!y*)~ZXNomRWsWwR+NoYy=c{X_+iD^mrd5*?MCZfeaV^B>< zB@sX2<~|d6_nCl7LVl8?Feg8Q-j5cazjfxG}?e-KV+3f86c=bf15}L-X{^eMU#k-JARTd52NCFLU4jsrz)i=jm|ghFLJr z){HUd{B4%RtD9#F%iuld#NM+u&(nvyGtc@TcN>GTdDj1Usz2{J8h0MeyYrvV);wpj zNxWxko^xF9S;z67a2%en`J40CvsH}MzdYes+@UX@$K12I2gnQWeiC~3l)(FrC!k`U zn|YG)Y38|^@4KJ(efOhozRN%F!Q4+=n)%L}`-$V-lli=B${C@iReg4Pz z@ACxSGc?ai{OwuAU>w7HVn3gf`8yepW_}jTGmJ|!&&oVE^HXo`?XPF08Jj2g*RwMB z9Evz+9AI<&z^&R}{?~=JA^WFXH@6!L~`)HotKfZ&1 zJ-7ed?-_HS|N67=KmGigXZY7|7;|st_l)_wZ+`ojpNN0{J@fB=e*a$oPyC(y>k0oq zd$#}m&q#px_bq_0MhNrz&m=R&76JUbY*Ls~(END~XMUe2r^P~JQB6iAIltY_@5!Vz zAJoVD%^%(Sop1i0B&M0)`R19M-~8tHlKH!ukY;`(nXkh9<~P3+%yW)U)2OEEN5%X$ zFwZ=m_sru_F<-BF{Sn9eIf}zLF8}?1_wU``zmNZJTnrZ{r>x@-EsvJRb6P}{Wmbe% z6t`#@W`$`*aCVkvR)|&@k7g-m1!;wFYL;SD!1KH2M~!o{1bsf#I5(5f=S7WAGYO+S zJlQ0?9!czZGfj>a9xa}5E?RE9dM3>(CoLBqK9f|HgO(F-pC7aAv>bT;;xWrc%Z?*3 zF0-t(Y&ZquFv~*AYP^I07kg&`rggD~{fVWwfL(IgA{KUG>5e6r?k=T6q+10MK@=1V zY@`fq#SRn%u?t&K0Ta7BzTZ9X+0O;R1IGEzxxT&jntSH|%)IaW-+$h7&-2W%Rg093 zXQ8f>nxtCvgLGA7g{vhCdrkUEv251}*Gvt{ne@MOg;XcipqHj=CWE9^=5=jUBb5M4 zV6BRUzFW9Xs!*;Wu2Snxb7cz+e}jRL+=zz+-fp?ZG>e7>On zRnY$`=r0%am;ZP54U5*HF@%WPY|uiqB^BDBqZA_*1}%AUN`=5;D2N3-pN&ZDuTDB4Q-aU|_YF-j(AJ|^so z_APHe154L>%ti4EV8H%_530gX&)q(Gwt2aY3X^g#bhM0t*k#YoZDNQnNI$cUJf zb&Zyk;D45WCJkQup<}DP&>1cKul+Os+F$Lr{;SB*%^PFVrCZrIULVq%F+^bja4E^OVqWOMACSouE~ldjeF`^tw53nuDeI$p3=ZI9;b0J zjfUyEC<{shj}2F$uJkhDx<~|djp`at0HuEGy3oi&Lc#eeI9~<#SHb;N@I3t2^DzH= zEy8Z{7=+%%vP9lIWwXh<#YS=3BY)N8U?~{r=`;)?3Ac<02$|=0N zk|-te*2w_%9!d;vrbM`$J+%$NPaNzB?fnmHvW1sr8Y zQXb75gpuKQWl z=`e$AX>%fZ=`e$A=`e$AX=Z#~faPTJ(tPq{a4!Ev=`g!(=`ibUY0iwe<^|N3rfvW; z)aYnj997A%^VOY>sgf$bXb8fLP(8H;A&x{>@&Y@5JM%w%;F zM`i_hBXu`Xx{>*{?!i>>F`-(BFdSYM;n6W|lfI`$m)=b0z#G3E=~9cCljP0izBHmyhD zgRf(cXD`GJx0A<**}vk$++gux&an6}XIOlgV=O+*I`#&iiVyR8#WR=Jo0RvG$A>w) z;+cbMALTe^mwF3)hdhpXpWXrABadT#r}x19GE>+OVHU1m!hBu7FbCM@%n|lAw(rACU*A*uftkQGr`NB{3icWEg?&Svv7ayt zm$9ER3zuQ$oKKk@>^W+_C4FZs?r`p?TxrI=~C6tf#w#a4=$ zmP^`ruqt^5c{~_z;+yrb!-T_-P+m<<#n}f}%Z^O*VEx;CR=ThIqb|f_h zbIChVY6Ny9?@Xy-n47r~^DsALw&X5sHDs3L2F#h=dw@OIK8_aI;6(B<%+cBt>`C1uY}s}+Gqv^t z`;d>OG=@2QYjGxyr#_oquiH#Dz+H2gz{2mQ|?E; zgxOsCF{g5WN~bcLYky`|9zba^v$+mne&s>rr;rvi%km&fi})`GG3RiyS!5T2Co{wI zG`{ytW`Ld!PG@U5xB{F(ein5xVIJtItgJp0+Zm+g%=3H}_S3PP!Rqg`$j`rU zj>6*Uy=(oV^0)>>W5~pTIf$!W~D#3Xg*;j)YT+TTX&K ziaAciGJ!M-90dm*Pc9q{<2;@=lfYxhC&L+!0gqvO9Q9)YFKq+1Vb8~68v_>|3XhyZ z8V(Mp^;9fV;GaV&O@l=a0f(?Po$@qr5cv#nIt+9WrI|3VK`_sOlxD${2Y>_EnoW5Y zOmPX^@hp-!=BaG0B%K9QJPXU&FvC;9Q?agKdl|S44!VMRG1SG>EoXZyxPts#EaI)F zke`9IBDkFVJQ(09;3?Fd4_90SE@FEX<@3RXfj=&!RGR&o1I`HybZ%gv^I)Q4qhg>Z zz(mDHPXbR040J(Yp#Aw=X+FOiTn*!t|6xC{AOGcrHKAPr^SRqwYDjo`!`!%GN8Sm*JgH!$fyc^EAx!QLL}R79R~9^#*Vk zwXb1$6?~XnjPfNFh+6Hb5-19*=sCeiOa0eVzJai|xlTYj>e=RW2-OL&*<|^j- zMqr+A!a&7E^TN+z zqCaB)0T%iR`A?)DVGLiuN57^13s~q!u*;uGpMamx;v4F|0>9#a7R&q+F8UF5U$gZr z%=AOHekJ{4jQxNu1K<4BSi2wAX|WhM=YC2Kp7}nU^nF;ed}1BU%)vqN{SVwTDsaz2 zfqNDX+_OmFo<&(bA{lmB2`n8rW&&HVpMZ&hhnA);mD&`rB+N0DR2n{%L~TVzI+_-DnyOiQwz4x=myAFY5zeD!Nn8B02hG>*IqyfO}qW4kJ>G8T+wyPCKq7{hi3 zoHH7X);4^(I9NRJP_bt*&Y_&r1d1SDNTSYicyZC%|yy#sWr(*vE2h4O+J!RPp~Ikb0oGN zu+W;cJC0+Y1!l1|iSlu9$C0!V^PB{C>;*qP6sKaYnyo{D8LsSnr()_DrKurJ(m z5xKA*-1B7e{_x6^1NMi3E+i$vloo;~!IY9%Lu5HD_6*WgIN})rr@}f{@avPoDb%mv zm#4r+V_2JH8Lg&)(_o{^NHYTSJQGg5jIucAS+L<5FwmvgX22bnQr<+G1%sRg>(r`e zv*3AGQ@)Bc2R?UIz&UWxD@pU~2}xYcktt<0rZh6`YLTAxckV;90rui#e5=)f2%JVV#9xvKNCz$Ss`la`1BM#A?Ms3zIw8 zPX zdF&NP1G)Dq1eBsA%~dERkh_pvy}^FGJ*5*$C+h<*=}Ue(HT^&-hbyS*14>b3MI~xj zGl@FsW4%G?ji3`^Q5f_YGk+&tb9B;k-QM>eIhuCybx@B z5-8oc5KMbAIG%Hy!*f0h)JU=v2%$!j+wis#O2Kc-yGSTazpc$+-`ZKJzU_EV%{J0d zW^p%7;TxlZ&Kw0}pGsMJaui&BIw%b}ineMwi!E`!6ni&G3@??pw-{lHy`7W`-a&p3 zb}_#+-rM4ox%OVlVu9(ry~Rg!?R}KR2&E~#2uIDeTPTYiN?E!e6i<|<^a6Dqz!%Aj za$jbHQkIJHX3hYmCKU~8QPH3l6%A@p(V!L;rFAWPKHqac%>I6u<|@kK_)@6OV|y#S z|9tY*JngF4)udIh^P+5@OU+hrD~#}*zzWru*am;+SxHah9C+f{r0sBdo|Le6^^`9r z6$Oi8-Aw&;@? z;>~ZsuAc&*qV8pE&w=9EZw7|`CbiEV7dmj`vaCAs5i8Dp3$xEC^=Bdh;wPxf#(uO z4?FRsZ$R-~BJTMd5%+xlSNb zKRJ6X?S7`kJFw?p$h}p6%Tw#@PgviDZU0OjWz`#tqSo6VvAzdK|B1X1cClpjz>=-_ zelqp%nZj7ao7LZ{6!^8c^82O;mcnpgF>&$b{iY&({6jE_TrBuQQ2afbwncffs|SYe z!xl;qJ+o*d_KhBdEjn=9=)i69*MRS0;S-9yjkX|cSW1adOgV<{{TN1}oEEV#m5-&_ZTCFj;9CwJI08I<4Xi1SJYiBC=MP=dqr8Q2cRBs94Lk!hef>! z@qP7u<3Ta{cr0=B#nc;6WL`-j)8Zz>NLkYZhqTGF{>-|I02i$d1*wpV#=5Cbowuh7k?q#b5 zSFE=!_-~wT&X%`tQj^9Ty*XuRS3>pcnuIG>s#TPgMpX#ZwJOz0sGgqmDxt1H-qc)k z4Z?Nz2G4{vo*i$1)p_ITNu5DnjZ~Lsbsel#dH2=hIb4lA6H5(S1zSCy`O@aHuw>fG z@PY=s5gKp>SEjx`PxU&~rE_f;2P>1SCs-U*&n=Z)sB2t3N};aqWKt}cLY~fkrJ3~b zG)m`b^djXKdETUlXHt52-ld19VS0E+zS2;WdEA!cO-urq|Rv}g9y}yf+ zR7Uk>q*K=7om>+nfzl=E_t2siETASFqy}&7Y+AByrF7QDk_}tQFxBBG)!D9VrG(bS zQpeV_(njmqUHno#>~-l2?xIxR>RH|ZtZ$hMgpv(UZX2HK%p<}RpZP+lvEiP!;hwhP zp0?p>YQxjihNr0wPg5J7rk1Dale`lf^L{)RY-05$Y|MMHF>lUuU~)~Z-h@qfTdMcF zI@Dc2c{T4l^?UVhY-(4+=bD3OlV3=!G_OXK&NAxvp2hv#++GaFYXmm37r|*;z=x#t zwXhymlmn{o>|r)-K=rvjJftJ$guug+N ztbswUgBKi6%{sWt!%Jt^KNXVlNG9@On@x-f`jGA|-hPd{pliDa;#Ts1qqq z2ydA2?BO;TsorB!mapWUEiJ?FeKRR*{aF*VUITxeO<9Vn3EW3(l3q;N@(IPf&*2>* zt+f-zP@a6_m~{El&#kc2F#= z8*h*C;5O>IQQ8)C`yHToS$BE|B&^QoO7uZF+!G z(lv7MFerA`E9mUKu=k{&*#S#?(xdd_Mp4&0Xz?09c$6OB61Mt~q~=TS?n{!Ue=4PZ z^qx-TjVD&6zUrf(*j5qJ6QIT<)Jts*whld6jWVb|s~+wXTpJ~6qq#CPh7k{HY<&cI zQI6Lla1lMTqNK&(Vt!8^$0vi*sf&^ZfKum+k_LfN^NW&(@b(_Tcg4};8v&z`;xC`k zA-wI6#TrYm@K{)GG3>=j!{83bV2z>Ycnl1=IF@M2@)#`<${JCSKhuZ&X%($+z^}20 z>8RHqYg1EW!Z&M926<5Ht*H5WG=GoYsG6k#rW4-3@=%o*vBr*yk&3f#8Z|0Pl7F~H zjf#+pau3UksW3@i-r_=$A{n^~M@~me$4^J@pWgHQ`>g*#^TTK#^t;*NO{cuJ}sWqQh0M`#{G^tW)=a_ET5A?gQYen~h&ZSW2Gygfwf9CV<56$>=_&v|NKYrVP?Q`B; z61hL}?|I(+k$?ZS=Q<0zgY(}Xx>t4A{C0oDv(J%xH*)PouDbu^{hD{x{dU(zuD!@J zQhW9P?)jm8i#$d0?pvMD{AJzE+V-?Nvh$n&%FH{n`LE9-y)ys!{2u%i)SPX)cXYq# z4${4&`{h6NgpNF$^WGbgXY;|=-haz;FaJH8|6b02k4vG~vqJGzii1-0lOm)P2Nj9l zDb7`)*b>D=6$KS1CC;ZAZ=|7ChMQHTS0xXMbW&xL2AApxig%@v(&@#DU!{^1yV8MD zGAKn{{HhWt)m)rP{=CxM#ep=dkQ8~bq6(mtdaHFeR(!~`iB~OsD zfisn%tT-z5mlHwF-_)E^Lg+P@2E|y_cP<6We^kBZlJt|CfKAwrr=Q#yY|M5XWpO6; zm*Yr{xDp#silH~mI)tPKV1sad)(cmr`pG3odaA4cT%4q*y84sFLa(zJc0JqG&qVFS zT7bSqu*H_RKL_x*7cb|N%2O^ zMSIxumH$lX+@*%|r!$qyS<;z1)cMjm$~$XqDdn9not?b1CO?|;;hgDwwLawe61y!E z&ROJ4>8!Q<*ZE2eXG-Twu|~f?UpiC2oi+K+M$T8GaK3boB4;f&oE@F7hMXUrKbaDNrt zUy-L`!Tt5e&%=WItKj`r@c#O5dw=EU8+ptyKkGO;zHub{P#hzVCAOrL$2THOqXpaI zhb{guKNKg-V~I^E9SuLsV}`#mjicp<`OjA#GtAFA{yaa-|2z~Y%wrwZC>=dN6nj6A zCAMcfkIx^DALc(_5hgEA|L6GOq4>Nwd>*TBLMg)JBdk6?@b&{)eM4CN!OZYCCNEBS zFiSj`&*wj1{|)>w|NZsHd|rL7yk1y4N{8xy{hfS1?|dEZ{yLb?AAF{MmTo{dMGg{&453;QosAm;ZO~uOrbn4!*x4D#wBP#*w_g*p))O#P-u9m)BU z2KArPHxBna{9`@pNc6+Q@r^%oe;rDX`eXetzaDiY@2|W&E5C|(X#FrxIs7wvl%IB)!^81;Jsb1R*Wb$z{|UaKXW)UVZ)Q+^rS$4d zX)G+F_x|u~R{e?pJS|2+J2 z=SzLAyipa+6_YoflK*-5SI*bp%jb`_zx>~Jz6$jD0)77X`uvgHU(%rRkAMBU{&IwG z=oxtMsHMg$^FI$YI(e|l@n^=rjzo_-^!qE1&mYV;BBPf7{CMTz_(nnhEC2ZNpYMNZ zoLS?T@+47=jOGQ^n0jP2Fs=8cRlnq;s1?&9EB?ugN@MEsLXa1gd=KT5ATKJd04A@h z$egb7rjh?!WENBXN@Pw`S$_LneM+;R7UBD}AM#s}zpvUCrX34R9?)L}ZDfvC z?Vw6}^^kl&Z~R(mMFFYT@NP<~(9Tm7Q^zW)7wYA@wqBZi&#yOHA)`SqhcKKjMH zqa-gQeY<@0B1g%Q>;IKsM}ChFed3SjW6gg&XIpuF%(n6dnPue%qWIRLW)7CwA>y@& znM+x5t@0k3YxV0htd98%tFxdu*&;-hMpLI)+CoNgwLeUU5E(wL>jNOIv-~RJd;S|6+|f;qljfg41(rX$_8tN*lI;t#}FT0 z8ze@7qcRLsq_`sAhZ3a_qj&|jh7)zC*zxLY4Yx7aiC|#+SWt1~ik&}(2#*o$mm)w$ z5aCgca&KZe6s?_31V`@>*`avvlS9OJ6|gE>JwsG>&kz;ThnBsG+D;Eq+^Ix)^bK(z ziW64^cPiV8A72D6BCfkTX)zHLsnpdCksyjmUmW7og^CQXhrKSCOg_mdTKjlV^Png~ zTmJ5+gNpQ?j79$Piqo!7`+8s!Q3uQc#nwcQq6t3nXHX7N;-+`^sL`ZZ16)iEE_@a`;RVm7-q)|gL}_SV zmWxAVk)l_PKtZS4`bJuZX)Dex|Pv zitEnzimaPY?L0r-&+rY*bW%ez*=uf<$zCz1lf7b2C)0AipGK>OW*VuHnaY+>yn2eC z>V+Da>f@*QCT1JaRja^N#P%ri_*w8-VzLySygJ1GtRimZd|EshqLa51PjxQwD~iL~ zPI{2IA;rTgp7~QESI!BsEsDC@5@Na(Ve}ahJZDpPUx@EgT=nPZ_%%6dO-a-7$y3Bn zE?d(>?9vzDm;5L9hDfjtL}#5%)X&*`ONS82Bh_F=h=H2yHxgBK7I8p|;o3;rz!;!r zbJAGFOrnAmd36P8V~C}i?AwLNAF=0I#0RaQu5E|{()jLd;)WE9brtE#;HfzWRQyjY z*VqD35k9dY!Y4LFt;B|?mDmuq5*s39#A6;Z^}PH8>x1=teXqV!U0=_)23zxub$uJY zvjO({zJZs5RL3j6sE)5o-q1_;YlyvpALZ}nIE?a&7aQdjNjAzWVr-OG#CvV8c%<6C z4tXO!)zCNc>T}&^L)@3u{8d{h-)HZ)is!i>%NBdDRczS3_CE5_UNP~b`TkM<9;=A5 zd#GQ=3g59r`#iv>?zh=q@lM&kHhB#%?Xd>G(#YR!@3E(wyGdu5t+ao@j`5098^d>w z_O-m`qpIbz$?vj?XS<6iW9AICce8buUCvQn!>6_~`$jCKJMCTeYI7%PlNsw3={A;c z8{=zw&1hAV?>o`lVHNLu2W>Yo`$sHuc8sItSU=7y_AQIHCxO$r-?J!9Gq)2N&77z9 z4)S%hUu(rmYbV+P(HoyT^|AZ;~eXx2)pt-lBG&eZx-h6a5?1Pw;PJf6KmY6-EBKo#>DAuTwwK z@3yboB50Q4TX8S8xc4B#mRoq{u+}rozN%A6FBYh{+n{p>J z%nzqL+#drT}m?R zhwURa$`x|LN9?24yGQL~U=(>_Y74o-Zl`_N76A*pBJL);(>mwfW8h=+JR5^|Y0D z_SN7GeCAia<4N#I`;`5KT=!nVyvuy!?pE;Y}=0k&2Yw zvBYBAcfoh%`@OL_E}rq)o^`%hN}){ zl4`h4wCw0R`JTl1Rm0NHS92NUS)s)Te8YbGBcFa2eAe!=Rb4;d-&b|j$ZNWhzAvcO zo%x1NzOz?kVKMh2=eL-9!MM>Mc+DT!h41O?KceM_wuF1mJ`X-m>vT8J5Ax}JVxa$++K+5k+IR8MZkK(|M$@u{ zOLK$#V4vm&b4{f2i9!AoT7GOl1wXMdw2XE!?nnNYRN8hksjj=}>QgCoH=ohwQ~Npi znN4x2uB%TWb@R!to9_;$kXLfueGf31yqk-6C0%zHN8X*(&2?qF6xfZthl{1A2dTU3 zg0(c*mAogv9}C7(*USCDk?n=0C*>d6zs|Hv0K1Uaa^Kq@Y%SXKa-Fayf}P2;-FNnT zn@w#k*AZ(OuoHQ0?AhSA_B)%4t&Gbhm34Kn)CRw?-`WmrmvbGcDeKykmjlbW@~$qm zb-=IfH+H(q_0!x8aJrl7rjbt}&-F7&Gu%wq%jf!fw5;puxv%WkwjH0Z;M(y`<=tdA zg;uj@Gtf!s4db>%q%JmJX zt?wGRFYK4Lud7I_zN9|xIO=nKL+lM)L-)D;!uI30E4qH9zOIq0Xg;@%us3v#DK~Qc zsqF{0BX5GGv0LQ^xxsEVxC$IdemWyj%!WL9MWueHrvO5=aA2JIn>N0 z&2cNS9t)mLKF_tHW*%v-I}7Uwa3%SC*OHp~qmFG1Oc_y4c-HeG`8YwI{lhTr=`Z-Dv7BC0*h+Q{TidzYMn5*cZ5koTaAjWN@KdLz~OM734S5qN%@`woUv^Y&G>alA3`xk>B8& z`R3q_%sMI zgL?z}>)_?&uVUK(Zg3mjn^@ie*O0%0Z6mnRUE%hypKHM79$bb1D-+tGOexv zuW(no`>|{RPbYr~+m+yz?ke{HmixhFuB{BX`lPSX(p&2_(To!5N&q2hukUT8Q7|u zx7nNP+}otL-1oH2Fgx8M>UWYJat~A9>E2-F{aUtm3Qs_uTugvfuAM0IQH!^Y6O%!1rj8;oouZx(qDU ze7gU@edyACW%BBN7r$Sf+6-UaKgWKg`48PkU^;mr|E${u?xIDiPxBwSRMN+;F!n;e zuz$uq>r(v3?h`PTyoi6=Jp(>Ni)8xyLC#?w$aja8H6Kb2gGpabJSk z50!9|?8biQBnx+VHDUh#18V7xEs)3BtQG?U;Hy<+A{f+c+^ zpNb{Tq?*z`!7Hw=6j&N-3Z>F;r<3{Zil&L4CjKto8h7zD%=LHkl+1;VNCU6pH2+m) zCuO=a7IBm+u7pX)QW=(0m2x#wG^kk%)11`tG$*}0jW+49CB-{u&^E@TQkw=#kZPVn zIThZS;h6KDJk}&*#|k@*HI*nQ!#@jCPNH0iw^t!bMX|-23Y06lVr(%ZJ~{E!SSq+* zQIEwzEAXC0G$sE9%dgh4T@L1I$$!T3i}h@mh1WXrJ+>??U=OykZm%r^PuNQjqKu0& zKf*4e%ug_oDDyKcPYVCfcArgzW9*~fkqEj{Zey z_{`hXmv-;iQgEJku$6*IM44}4sqfg5?p;zmT!BZA`5KKk3XC$}@aAW(1e8c;z5>7E zE&m1im#{BmzOcvhmX9^ZktT7rijz-<6~vl}t^`{XNyou6CS#dO9&0AJXlf?FqoTnQ zwCDz7i8bS~OyJ!WOFoV?o_AFoTVqM%cr(3ga8zJgqufaNRwuS{ zsUHoFrY@IHje(zyMzV+d{M~>QF9x43PWsSBQCo;RvN&A41nC2t z#pj0d0x&$^qx}cAt&67q0~_tzz)GThTR2NimqnYJ@SnlpQ1TpVT06(5cz;mNfv?u2 zwiaoS<5cse$!2R1EF+p08j`WT1?85ogJ??4z~=CVTU~Fk7aaIDO1)qMy|HbE?e&Ip z+=l%Qa$!$6^DWpngMG>G#MT4s0mr@>%Pn9(@|)pi{a|%>Vqe9z5NlRZ>IPTnPu-2+ zP2d3X8^9aEf#f%^uLF4l4We{CEPD|A>^j~dXR~!3cpcj-;n&$Q18(B|d>*AuFta**;w;ii802}_&nI04->QRk8e3Pv7wWLR0`^@8tVcebnybJo z;S19#T?vDzN8Jpzu7H8h2)GeGGLzCqmjtJ-2R49JC&7*zfQ{hCNxm_hI0?4C9Bcw7 zPV!CRR!P1YEGvn#-3*pKlkcg-(|fL4 z>`w6!{1R|AXY^M}t9h$mO1tmih?nw4zl_qi z@UF|?aKF;#8~E88a4q>al)iN_T!F@ajpZBO_iK6cf5m^Y)-^ZPd6#SUP+^9zhI&39ryEV@fm)4{w1^Z5eC`4#y~l*CrQfHS;8=?fU=I%;0z%&!B#qQ$G!d=7pN z>v)0w$sBMFb+2Lj4Ezk1@;vqzzwQ5m|Jo}|twWlzGXdc)|R1fPc8_2z$i z8XQjEnf6`KUdod9;&Yu%FH$G7+rAA$ehu7>X7>(E_;u90x4^gH*st1m;ia!)f6eys zPr%&zptwEZ-mv@F`!~=D_qkVS^C~Ldd$8P2aKW;^6RERr&+l}iAEi}4U$*bVhhL`6 zD=3d|*f`S{mG5!am-LwH$fr8_j&RL#{w2E~F8z|-!m)jcPrZx|c)yM^pNm5kydUd} z_5pf8ThN^2Oh5k^46`2^(_`?p3VcT{siS{^HZP(cZKY3izuiL1{{B%IX@AtKM_mV6 z=K2oY=`mmoTMwXW$C>A8{{l+VHhN5ojw)papkzIQX0#1$={fr#{hh7$0a|XeTftpe zp0mvVh@zW7(psNd^Ro<=1Wi_sC?T|O3RrY=%VG!L#UwT%ue*r za(t=`YWBnQP42Xhz;*AWd>0D!0QTVy@J`g{fv9A6+nw}c?ndR_>F%))(f7FrCHx_G zyB&l|b~|nEKzZLmkLg}?^&Rdu?6;#w4@Mcg$Zn_qbrJR3-K};AI@qn)Z?jsJPD0!Qyy%ijac6tfh&seS2@+>;;P`?=*hSqv1)~BsjTzLjPcbLD$UdHxQ;HBg@ zVY%6AeU+zBLWlXA>~TCvj`258zR}iXjOI9B(`aO?rkUesgLC~HaGswF9_Q!zTBar= zUbRRweKw<8Gr(HpwHeEr4rY@#;VSFMNLp>ivCd~6@3nX(Xnhy0SF_fxrnClJMSdRh zd#?l6QF8&-r@+7B={t%@7ZYd8^Mj#mB;Vn z3GiW5;_~JZbmQ{oQ55F#<}tM8^5${04Vv7#^k6Kni(4>h5OGmB3$V?Fw=yi+wJnAY`4!n0&Hz9n-goyiEnRd_#K z#dkGhoUVash7QsY|B<=Wu0Vah8n1|}X))DK^3(7andGP9Ych?zIr>Ng)0|Y_OlDgv z9UYJIuN8+T`T5L|o@ADzTyJ77_)UDv@zm17PDc6H8bp)8Noema7+b7oTJU}KO)q_{9#6{&_-AN#{6*xfNJy<#mdf$1{8-!C=YTnW z9KI^8DUGph&`Y{nt?JZ`Gyv>M-i1{O27!av(%M%8K&=JUnRN;VgM+E-!FE5eJ9$q^ z%fTMxJt>`m55!Q~b|Q7QHL;xmYGtR6_^S*Bhf-Gy+v(uxb{YNSJ#} zT7>UJaqJ~XBk>|x#JOuo%_96q@H#QkSli-3QG&cNwj_KMn5!4B2xjsHJ$YDh4vfX) z$5HD+=IzDDq7atCq-gvUm{AujMb4bWd}k3-8?Z222D=5B`PcqxN>ln3PmEWFHEMU`MWWg3KfueR zx!uM{e-fC4N6)L&zJ@PJGkj6B%3m}4AS3-1!HW3syh81(c!+3re69Z1)NW_IzXGTg z_+F;=75qe+aE7#6U=zGYKE?-V2mAH|qy5{-Uox4#hJT5cFXO|KN$CYt+)V!hWv$Uz z(`WhTvAlq%SbavwnSGP-a?40|1F(^A2sUO^+d}X=fKqqw#aHBEdvZmnv0E9o{oRO&JQe<4Srp1%kmfjZ!Y?X$gB46W_g^NnBPAF+;nGyWUTfY0!~t7y3zPnv9B%U{YTviQ@VPJXoA?rMi}TQMv%oA`okuz!|AOc75}MB^YBK&`le4vvcAtYA z$j?Rj%>*-PeFE)vf%D0)pv7n4Msj&bpNlVm*5lM#sk`tEsgC7JT6_v#L4Fnar{*MD zYz9vx&%obfC3p_GVvo&4}w#vpGKN)`eC~TyoGUm{OG8` zkB&O6u5mM{l~JeQZ?Qxkchn7F`$n)oIi7pe;JHWLK&&@_1IY35!-~Hj`5>&Q5ve}6idL0*mR<4sjQGY+gqUWL+Fuqt^a zzV&)gtA19(4}+QB@wB)a)XJ}w@RPU()T*(SXm=f`6-Fuc-}0%c%x{bVtB@ySuLNrKjdW~dK&^a{f<^Ozk0ejSHX0m_cU3AD%?+Lw%A?py z;`5(?pYSB9;hXq3@zrbM_wY?xyDQ(XD(nYGlDlRGXhhd2|tr>FkFe+Ih1GPb9+4Hxs>PF zwnpp!v^Da^ZEGfB*UCX{VImVi`PsHbD`-PsKZpK1>(#+U+L{`CwmNUsVwB{ITFhj? z^5#)4#`k7{nfRm5gJa1%bsq2SYLu&zPJlBMGg&Z%Vy0&BK|KM~N;Z|rg(t$3(#eJL z&P^j1E`SxKk}sr}kwXtf{xvz~9@5?PBUF+fO^%UwOpdvabT56bvFz=Z@IPz`)-Al- z$I=VAovr&RZ=ugMnp~bTIYwS3IpzT@_tUr7Ot~Asxex}WSQA5IG^`iEuuh`~vX#D|JgB$QvsjAtLYUN2`XSrs9m;Qd8$GfmSTACqmVh0}&ka5{ z@}YhZt|{NofusTS%R18HV)$N1`XuMlvpgqw-N=V}2R)4)^e-=g@8yEIv|GvcPVj8< zOJRT=zz)=%h4o=@CHZAAy7pju>ej$?+JWuZK9d%YfM=0k4y$Pkwxwg)E}!Jb;bQVbE(EWv3)W?;5Ge|NRU2DjQX!aG z6m1--0qDt#z-?=TwP|6oHUu4cQS3$FjjXEz7BgJ;T>IHDvxcxhL#u``utqQr`JFa` zZ^_^G7q~}L@K?5ehNTPye<45K$)jg7DE|cc>`VdW$sjMDNlt!1@=CZ7&Lz*yy`(*i zPRQ3u{s=eOskD@j#8dQR-o%r0ASjPctyb_8jO#}}vkwOGqmfVXKzQ6hdJ%7!LG&5k zf+uL*1o?ZuMcT(Ghdin@nt!vM#&^mGLmor&K^|=1ru|zyt4F|jtD2E8FCVzgsNiJ(R;39*3(*1IAH%;9{$%crz5guJ=mh4FoBhm(((h|Bl6NpH}cX-H}cZbJLhU!1J3e- zsX=-Xlvi~P5_~nRs!)S(t{&b(*P@%ro8@(`;~C)TpAG-N283y${?@O(`m`wTt)C!Bqq_04E`zDjV0l%SbGOhV< z?Fs0_^3FN|qt7YqiReFqZz){q(Y8z!m{Uoh65C_K5yGk|t7#B=6@hR9R#^3gTu~o_7X=P}J6ji0x*fKBD=jX8@ofg>k$M4rppU={$uGrz z3EcVuEUQT$(=U*B=Vhcz=@HyaX${=(=HN&DG59f@=6uqp!Q=W9`UP4w<8snX;7zpF z>QA47@~1wJluRGtS?bPZD;aLD6*Sh7w6>Dg)L2hi2QxmG+70wMo&vR!(gu<|uFt`~ z5qrdgIvL))63aPmBqN{aGHN*z9LXrx*=&yn&mljL5zG(J$AZUF zCy#5sjk>Xnb*&^{75q3>(dK+cyyR6R-=(pP`>{Cwl*P$=f?D;U7kS@c?ZMW=DEeCU0R26n zA`JS47TqX4W>D?P`(x<`16PdK08)Q+e8nhqB|QOlW6QFS7c%nx3|F0HpD$os-eNJN zi`=i)1iXk*E=L;+%1=|ipBKAdNS825|1@UrzCcwSh^IjbxP1)yKuQA`6;L#T{9IWZ zfj07GmDk(P_7XiMW~fmY>N35&wwB88utU~au-MKU=(b{aTKMth?8I9<)D0{ zieV}05Z8h0+0yVhbTMJ^mhuc8#`nBZ+KJjNUg9!rm*G-)I_(u@K}(Q}x^2t_CQ zaUChmW}K-beY{y%W^$x9f}P1{vfY_JT`n!=Fczkmftl3KAYB1!O{%%r=g_;GL3ti! zdEvKX3~e5%13lSxl%`RCC3q#hovEa&!D-|t(BBycj-%BHr1|vjrcyhFw240KSgeY_ z+62mP{UmxqW5Kc1E#Utc4US=Z0i`jFIw%$^ku(w1+9rvlNuXlE5=oQ6<+MuVyRHT0 zy`D(A9+W?LBI!nOGW7|3>q2lL{on-BB5)DC+yv5Ma4~&X%@)1D+|EeuQpV!tYbH;? zrHs(uM)_9KGDhK-V7r5n%_WS@%YRKCf6EwuKNahp?ke&!^gWj|3bLHvuEh5)0TamO z{dYPe_wt6jiZ;>=QwG1{ zG)AscgGXNtJZ%#3-$06|DPG4L_AojIBFT0jT-gFw-e+HBvoz?}F-&`}cnwzGSwK}Lg=9++79aNrc zjg7q68dD}lfwA2^`1zFMH#<|754QY2JG1?Uljrpwa1W!tU1%fEZFyMdvb_)NNZu8T ze7~EK%kz34xR0^fZdl|iE`QiY{G!H(K4B!bJ#}w`9mu;=+YOXgY&)#)fbGe9;LFhj zY(iZ_BmcyPMjnU_jXVt-8hI2pH1Z;B$agj}ZTaN8_!hMz?}<-HW3VxwZ-eb!P+pC# zN$-Pg$a5&|2V0ZN4|%`KH1hY(H1gceH1f^PH1fgDG!6N_Ow)*O%rx?2&osU8+{rY( z@zBXMeelQ0G=1^M$u#oBZh#6Xlvj0q#BqBP3y zILpXqIm^fcI?J?Tuj(=~H3*bXcTGN(#i-&iyr2|)HyD&pcP%V68C#Thc5TLkhPZ6X zwHRTn9m?|QPDCM0CY=c;@_bxjQcMhc9K*ekX=3rr$u#nh&%_>$Cs{0aNgb}W74&pg zz*lliYN}?fFKp!FrZqeYnIb4l@)VToQ$%OdS_1Mrgcgubx0bTT>a5Y2TyZm%(lkcZ zW>B6&c`BoUGbvA|JO#~Z7Ukn9Gnxk;&j_KS)HPCA+!)lRi6~8zP@d@Yl20I?h}IM0s%T5| z(VViV)p!-2lvt_;t?2|*rV}YiYdR5?=_E?hnodGxT0lu!(*i5~Ck@T%F81b5(p`*Z z-%YMj?bhawV7(6osX3ymx&>GZ8-EEx`p!Qpe#vklJ?Y{l!Brp?MXV5)Fq9bNK=aFPu)Kc?KsZG+MdXbWX zvJ_F9x}YCvj6~y|ihMqWI;l*j1XU-ZJar0clQgD^L3xrsCC#Y?C^br&la!{u8u_ae^rfhvElEq# z2&qQ<>I8i$qC)wgBe6;$3X+s3sZvF0m5tgY1xlKe`X(BgmC9sMn=}e3iwYQ#&* z)2}E&8XNl=%P*9r?nzC$A!trgnxsI0N-ESOCrwFe)6cY(^0WsPNm`YZr--T~g-HsOG^dFE^ro2>6e}rAPog$S%aUGn zGYXT`sJBVq1$AhUeH}$*FeuHc8k*AxG#!n|Rzm?AW#z5-Bq;w0DNhqokXoBtYzA$a zRRPUuIH-~747QI&ZIXs1&FR~q)x2)T(|!VKlYA*=1P!YyYSTJ&s|_emRndetfI0kL zRkWxabR}t3Qk$ePeM>%$Zy4`1o+@2Qqn_1Kn}&cIS+9-?H4Ky*rLom=XjdEg#wzGc zQnTc@Q3ajpN>Kh58a*usYW(#Blqac3QlM&}2n_+Ho7F&bV&oIeiP2I14~>s%d{^V6 zWo%_5&y32bO`AY@Fi3H#Vlq*io(Eqf&qQrvv=g<7@lU?%Wl*Y9I_)bPX-iU@q`^sf zIvo{CzM9gaq%cW`lG?N^=t~j(X?M_(W}`XHMvsy|mNchjXiw6gSSQrZMUj%`^eXz( zn^>eT%|&gJ2DKL(>x$a>=ugs|UdH2lFBU09^U<8n%d{cQ}~}y*{nPir98bDw4)P)^7H~~lSbw53)+&@CXLo=U5ZmW3Q|1nq$9=K ztwFbvzjhj)UQ)EABP|G;)7_{^@&k~jR0`ce`jnKXVnJD2h~~5qg-UAET|s3kO@CfW zl(eQh(Ss5wNgYbCspw4af${=RMQ7R%%HKK_o#{hR-rK3@Odo^t_Ler47W5@4O46RB zJZ%m-QbcWvs8F|KxgG6EW4fDzvh*P+ZAxRen?a3DN^QCT)R_Ba*dm(K&FDu`prkzA zgxaLBcxg_ngXXju1rFQm{&MdOB!MQktYj zNqKq-Tt|KmZO%nqT94&y%IDCt*7*0vphK<1ayCj)3aXQorHI-jT}cX*G^J7CD7K_F zNmr64C51^Ul5{93OQS()Q)lu$XQ4Tb#U|xxC5qDGpesq4lENfKNjj8Nrm>*3Dd|ko zZlptr&7J8=1f7w2N39}6p5v=e=)1ZtB!PD=!RNmv4F zPxPgSQJ(s+C9SC^%91<`x>J__r+g9mQC}jcN!`(y`canV#N0q^l?ZCnW1v(iDNIt4 zExg@Sy2AdF6dCwnVv>px(KUOri(%x$kSFj(-%Q6iYQONTB%J^js}oRXL=lz zx+R@SDv~rQ=}f-_1?dvknKtrAl~02-r&v&0RiU6sNqPD#XikbHkx#Z_U5G&-eHt_; zMViPzTWXWkq(S70fg!Gelxn0lDJDgJ+Zt7t@1<7lR8&l=k=pb_P?;`w8f}g@ijYY) z(wx2zTGLvTr(#&7Iei!OrFCdXLupxpnp7iwDWW-jYolEWEK-}k30l(zr#}AIwp37@ zq%#c-I@2)J4=GLw=uE>wjb|rN(#m}ry-q-F8UcW8hIFWKuwbRBu(iG)FmlUQl8qQA4zqZPihy`rs+Xt zlJca{dMQiOK#kc;bCSB$F6d8EsiZPZMOTt0CADcvP=PiDwMiP2)F}Boi~%(spGcCY ztNbAn(T5g-@}EdVA6f)1CQqbpG>VM85XuBEgfd262xW}C5XzuPO#Gq&7DMm!m1=5+MC`pZywj{Mks*@C?WkGqm z6@6%VP=Cggm*qFd)1#ArMlvbUNMVweBuz^CQbc*$jB+H^NjlRNK~0J%PqzdmNy?E_ zCuvQm2JI?2_?=%7G^dRy9n1NQBK1!XI@7YCPE`uJ(~_VqNoSJwR555)715lQQkM24 zO-Txqv?r-e8$o%hOMm*xN^PnV^ribyo1{ZYdHNE~X$w{n0z3b)RwdhAV=uFpwipI%7XSyD|5zQ$FUFt?~IcMT!@@qoeg7BK4Gv%0<(Uqh| zNq>syOj4JmL%m4*m(Y}Q%!@&DlEx%8>Uk_L1kFhrlQgO4usk0$C+R-Yq@+3JpgHB3 z=TMni5)bk$mR+b!Eh)7?kCK;u3$QtA(^H@{D9wx_)k)s`Ql6dwn~_U-dK_#@E=@@a zle8!4OwyI!5vlO@iw5I4Y4erMJMhXx*LqreIUlCFwt&F7mZMx zJ^~fFp*e&;3ChwtpfoF~O;U)YTS;GvXijZ|zVsgW9#*ML?+4|nHTsU!r!4fOMxbJ% zve2CBfep}~ve29wfQ`_fvQV3Pg1u3mvP>V8r!1q`uq@Q3zF>cpr-mS(L1&WkG=S{} zW?;~t2C`k>3_^dZX%vZ96P@W8uo0?LP1L65U`v#zny5`J!Ts!+6eoE^E6z<`?8Cv~ zXiHL@te>Zz804XMaVqnfQ(GZy`R4Jkd{^5&e^b1iQT zDLrfQuUQ#cT{N-=NB-4C^H#2mtT8Hm__x(X|DH7~r34@S8l&<~{cCFkX!P;O))+n9 z`I2s%e~rf)(Fs?s0XeT@O!?Yk>x|Jfv6GWL$7SEIn|GR z&6GdBzvS8a_pNCzFQvn;S$R0VaX5acUhm(r#!Y^H`1|`yXD*K)>e=`kGyH9h(Ier9 zzdv8KIe)*cKL1B+jOrZyeodmtx>1pp9sa&GiSqNqKR#b=QSuJ82L0jASAIUPb9bmU ziT>RCOPs!7jnM<|EZu2&tBY!#(MoWO1J73h-#AqN>yMv@e{cV*;QspWTx0b2{jXg5 zV=0V}r2gyul^ot=2i{*t`~J%RJUm$6_;+h$=jZc({QeU6h^QO~G7Y`64z(uH;rNC; z*@}}6USl+`=k;gaUzsp_55xGYYassqe93=0m87%Qfl}W2(mBdIYx&n));sG^YqaSc zRUowqOryg8)uWE~{iSnss5Q-huSexSUw?%k9_{&($Kv7F7_EW-L==fxIyqZXdjHBA zhy~~Cz+Uqot!aL^`|JPh`6_rG9_{^=U*9+!pD%bG7Ca9-;dht!<|^PD|0{f>;CWc^ zJj{V9=8abt@WX%44=r5M1>XRN4yJgN|I}KLKKLd0@Y{wSjaF)m2IYsSwJo*wrPjLi z!9!4csg*J12dMsvR?O5)jGD(qD`{#LM|nJGh0RiotjO;{D{sm-Pcyre=6{p-n&x>) z;J++JnF(P3^}l;`F!@K6<<|{kH`? zi>#R$*^9`UnUTGVteF|v>&Tj!k^d&LwrAwO%sUS{CzkzCY>%6`5C7`ArHUVx zCyLIXqL<~DqIEeVD{?BTS;t!EI`SXuzxijbJ^i|VMJuJ||J}Uv?*70ZCjXk_`Sn=! zY9lH{UVl~!Ql-$R%~N8f@#Xbo)u+uHsn?i&UQbqi+VXf*99lou7)M!Bt1yx%-$kji ziJ-2-=9Kb!vg*_3jU;MJ@i)(k-^LUFxIdexLd0>L)F+A|MOH?R;ausRa_}hdpV1%G zS1J_xw~>*=yq;`?Z>w*6sQ#?x3(?BR)j5OJD0LPbbPC%Y!`;vkODE2Z?uJ}a zN6v}vh7P1$&W-Md_M{HzuZ1bK3-?4@upO#{?uIsCTTu5zYwm(#U@^9H`0tB@#o2BZ zuA)|0ayU1-x>}N2ab|SQw;;9T+$cuAIjIGDLmZ{1+TjW6iq0inCqNr zgrf-~8#_DtiUxm+BAlCAT&+?hijazOHP@t6h;wu3@u@$)zan>*?lIk88UI!HSLDvpU6yx$ z>3%!#{?eV5cb935Q1{v&-CuckR%z}eJwqFY`z`PON<8BGEAP%K&siydl=qkJsl2;P zcb4w5tbg5KHU4#HrLmnsS#fHSyDV~NRc2djuqgUXciGY3Uw{1mI(U4lV$ftO^6Wd% z-|XLw*B|`;`seSjyf;^VFG0P(q@|Z2N#FY`)`zx3vcyu~7KuE<;L$lhO( zH<#XGdH0vzXU)Q!>+iU~^6soe-dB2a)erBpdg0BbcUj~urZ<<~VtMZ`z0VGOf9cKj z+gt3&-d{DsJ*M|p3is1*@2|t%Uj^^4zuUi};QbZhhXwDifBOCPPw~To{#QZ&tDyh& z&*>ZgJU{#^{(%MWuY&j2f2RLc@cvR%iS&(#vhi2rv;Noh!~FV2p0W`i;^(9nO7CbK zG+$|ne?~u)a+s$gM)bpSf2be+nf_Ovekjc_PenXf-zd-z59J>y-?Lbfl=*`9*U{?p z1^VHCUOy~&e-*sH3dX0+*8BQ=>E-B~C4+u=iIo!j<3aWvIo~kQo8153q(tA!DwqL-vXodb1_o#U z*I=Z_LD>8&vGo^kR2D1)*$2M=pnN!t)=<3M&1lJ1kY8mSh=Rc|f*$i1$!r+;6W2kG zgS>~4`E4iTP5AE9XnICvp2TSU@WmSd`oiQ>6z>Yit58bx&HD}U=NIqa>;D>$7tGk~ zYGLF5&A;sS8vpXYl6?3}&zEeR)lb=f_IwrZU;32k1NX`DDf7wl`BH0i_4WDk$y)uC z6;GCL&iG{c4o&ft6;GCL&iiEf4t?>I6;GCuw@+Ht^Hud^DXIIU6>mJs<@n|2tLn*; zuOnOMm!7YxC(HLRebWBk^Hud^>6evNR4|SH@#o99BgLB^?f&NTrGI(+KgqwmMn3%K z%7?%7eEs9=*DpU`e{cP&TDg3_s-CR>Z2hWQx&B{yzI?Z>U<7WEt*2stdYWBllTEEuFhiYN}ugHgM_`UzpzVUzOUtaTk{k45#jsCUf z{S<8pe;wILCjEc!{ghvNzSihp|J?QK|5pE6vwp2vzpAVpYwU-<#r5y)^K0yfzZ~W1 zU*Y}Af5!UtOZNG~|5d~f)>g0Q>%U_^)bq94N?&-sw9glBR#sW*|Gs_R_bXRh>4#v6 z|BwDJJzrH`FyGzPR$q9*R{OvHmVLg;^W}TOdcyve|LebMpI?_8b}6hwKD!jiR2TY? zyN4i85vAIts!JPB)<}MIiropsW+5dh&AaON|wE0WJ;{T z)-ba24JYSYb+(3+xvx6yk3u!@<4_`>-^Zbh-jC_|h#XiYS|5@rZbbZ$jBV?a3vL8C z13#c|MErzNGqaOGiFP6b;HR`dA!po3atyvtUbvCurh7k(0!NXJ@H1Xnk6>iKcgZ+6 zn#_2k$z=FB{pM%yNS42M!WeQMzQg#K_zvV#g=5eJR`IsBjy=o z6>Akw53R|fc{;V0Idru}&pN*2AEg*-xQ1Tl;BX8-CRTWR3d@JdM0%4^Y~~ zN618WGC8qMX5U9B50h={0rvSdS;|fVPome{?_Ysmkzej!YVl8G0eqBweoY3eRkR)p zH<6v~G0G}3xP48o!F$;2Yx2H*LtewX+4_boRyVQ7U2Ods{4?1R@1lH1mZqB+dx8vW zH-a~^btfa=k+bXuwx1*?+YMwjyPnn^^nMS1Pv*rt*y}s;pk2?{(_~<~o?Lc6guj4y zP~S%V7qZX&CHx59MtuwQkKk)u!CPp(Mjj=zbT0wT%5C26gFth0o5|Y@;8&7$=`ywt z&Y8j&<$T_Y7`c)>OqbHTl&nvelHF+$d6f>xdA^s?vy{w7<|ALm)x4O@Q3sG|WPi%l zWRkj?Ja7xyx|$4A3u*61xi&1I7O&-ZY)kH{`Jma+r_kP(%vkesCU^6sZ%3I&Ca-JfxD{JF zkilwSa9{S`flPDzkZ0>eT9eHr2yRI|iTZgmZ=Jx%PLv(Vu=YIJ6t`gHd2(?b&&V{& zPGn?zf&7Z*W_y7wUB}ZqoeXrxle6l$oFo2N>dn~WC2(`jlzL-YuY#LUZ$#@BaAWHA$mnz^*q^!|t;4|es0WZaY6WP<@d1?n_?^v7F2D0I ze9Ft|^d*D>HR{N{%2(;I9=-I#qUSZU2h-+(d` zY{*t644AdRwb;WvZZlzubZ5H>{`~HE)Mt`$%NQjySxvjq+mxJf6TyjW)n#lq(Cqcb zG}#pipf2rZ>|?(6@zl-1X2=ERwy#Z@1=eB9C?&Jtn~Z0V7MT}PlkM4f{%cXUq^AX_ zY}yJm>$_gFR@w7igZ=hIrT`yoajB;)O^WWYT;-b|+CvnjWd z>-J_^XVQBscq{pm&!F56o=JUfyfNMc-o#$#QqCcN>W#F{BUAE?om68l5zD0_P!v#NPPk2d@}#G#oKu*<88w!v0Z2no=SZo`&>Zg)aT<1 z;0tV>9NUKu;pEr>Ho?hc7;aBy)#n($h;ku$icgLm$+G$!+n0bBgTJ9(MQ^9DigB~1 z{)XO5$;bH{GD<&2mgxh?=ld8LsQ1tK7&&Ga(Q^R!YwG_D;*KSI{*1@tVTeIWP{^*s8X0-qwA=Ui&>X)=D!;Ycn8pP`;Z z-!o)g-j}?~TgAP}+r1TKUoth%VV}wL+TNF~tr^{lY|fXG_jM9|m&R@4Ui584*_w>c zljz@qayfW8`F^)$bQ^F_>doo9g3PshvOOivrrwP0E5XgFx1(nYcnmp~x1-D^C-s$N z65f>YE6H(t485DMeHFMV_4f2k1&^lQn7*sPtH>L?G36RE@*d6D4rF3Jn!LP6(b|!$ z%14nSdt*i?QmzHBC7bp{`mTvPF}fpo1oZ^^t|Qm=b!6NgPdN^pz}7hG+c+H>H=-OCC$c3TM*ims=?IQ>LOPt|oj~5R!{Y+- zq|GM-?pQLbEuf4i_w86(^XMH9jwfr{Jjzbw*qxVgr#LMxWS{-WiMs*0)fQ65l9zW{ zoF3MMdWwhJMBUi=w0H>cp$k+XOfk6CYf*dWMn3pqG!fk!ClGizJ%TY-m+3T)IbeVCDXHb82Kq*iHDP2@|Ac58Q)$Z)AQl!WpX?pNp9wsGagB< z?Ox<~Y)TfzO6uMeb1(LyrzfQu8RHr=vNokRxf+|1Q?Uml&B!HJ!N@w4waM++JhcFO zP_Ik>I%I)tNlw=8^tPnE7Ik;Fe;>P1i@zsBY*+G0ieHddwhP%N#XpdpvUAQz*_n)# ze~g`S*2+#~t^A5?mYvA3+L7`nGFWyb^J)jm*O6#%WPc>S8~Gtip&@xAOQ8{2B}<{4 zV=0BLxJyc8!RrG)#C%;MA7EeFeaQi+pLlR6g??lLERhwkKiHofgQYNlT!p1DkSvC! zu!NbS6e{>_CH7`zr5=>plR@+AIK;jb$Rqpb7|1gFE%+^&YD4%gz66%S5JuaxX9(^1 zOdx0WZr~8I0){Y@tbl;!tJ ze2+fdmb=zF$a}YQzO%c4-e2C|qW4{6ikV6)slAW8bA2i@de3|l%h~>O^e*}{?Qgi_ zyouaIxJ9$1e(US)o*!_!@dZJ(mGd6w4Z ziTgaR!~N+qW_w+(!fVl4_%-%_mF(c3bBTUS&uh#e&dRUT{w=w~KcoK>>OgMsPe5m> z5N445IkFx&AMQ+h2J6I+acAaEXU^%A5;%jcnaR0vW^!(v$v(TJX^fOurG8+$n2(*E zORQMVjbpfK--AEIU75|Dvz^n+n9+-Q-C2HnW_VWsSAwZ|m2l;#!Tjf%au|3hbK4YJ zhv#*~nQ^K#hKmty_o5p`*)|`HE&C5SBQ654Yy=_52TXG;AFOD(RRI5QgNkuhxNu)<)FOU z9F$j`*^JIgOITUoV?};1z7M|7`m!heuEfegdx5Us%0UOR?+2{xAF%E$X6r+wf)811 z7Ny112eAHxZ~*Jl$Fvtw9~G5Sj*8>ckw`JhCxtAd1U5b$&8V`Q^2{-yQl3)EF;OW+ zxo2WJmY!px@{m$dAs;C*&8A=ZQMqL{&)t|TKNZrIsI;X_CMtg^w~5MYyCJt7f(&v9 z(#Y;{DOC9gu#8lPqQ@mY=^&pzXj*QUq0X#)Mqqv`__!3ju$ zg-kb%dLw$2Xw@Q=XXm9IDf83D^eFqPbtntZPdiW+q)q5idR7ZjUS5#4r|btR7b;&b zOxq!6i^_sZ=;Hp!c+a5`sO6|BsMUz-2+z}_ZlqrDJY^p=sJ&>tkhOqke$qD7I@Ckd zM$}7QWb_5JvKVHAd$N5)))CZO)LztM)OJL*9JL=cp(nGBRA@_2&{q0?6jZmm7F5z# zpSp_QsFrXw{a2w?EdxTaXtOlp??%wh}y_;S*tpZ{_D|N z3f)B==6L#D&mM>mf)BE#{xOiE%YA7E@FEd@M7vy(8uoq?_umh`nEy8 zy_@Y*(Z}yb$5l5|)7=IgSRMT|%Bg6^YG~&(vTYn2)WpXHHS}?`&FMZi+!n_NHTUuK zkHfa1Rz88A@z@^J**9RX+v1p@KCV6D_Bb)9zfWY(31M_lE7u-zN9-2V-+g1^2JlAq zP-h+vYK7=P83A^r?o5xegSLqF^o|5OPrIB-#e8 z0@^+91V>S~rKR@Yj;%7RPJ_Y0>|Kp^8P*Z)3T@cy^jIB>)gbI9gBWYg$QiK)wylBK zRtD1BitRIFtDyBl8_XH8CZpPAw3*eU49J$7v!b>fQQJo?Mz!*2OREjm!ZxR!>NrsA zomQ;lvW-j2U2klAJ=i`0)C#Dz>I6y;>|)x(w2t-u$x?Pywv(O6J}3NSM>{gx()P)= ztbOP|@h9us5kFbr3M<_a*?w18@A`2}g)MJZw*JiqXJKd3*0%?(LqRQpdr)d)VOqi1 z?zFUNY2n%{+XnZde^2aU+QYPt)xpxVJlmzT_3fSQfxG@>Gt+{$5jMcRv9T4Fw!#jl z-ECv~wMA+R-Z)!+H=(ViQmb)c#oLtjCRp+cd!E+48QJDH1G`^2ZS8=YvCpR9f!Lon z%QooEvjuu{dNvEw*{d9j>S8RW)3QBr8hzzhTaCTE6MYp}WR1PNBU_EJ-D)4)fvrkx z=UR+!pv(v7V<*2Z+m^MM&&S$6m)=I4L1H&4PE{R)MI zBJA+DWSjgg?DJ~2fNzCA;39f&1N9JG5H18SWUH{1Ka=g{x8vuz0AIodjA?V<8r&Ky zyFLd|yZcj=DR>>uW8XU{x8s>OkJginOu>_(cjzw4o!Of)1)PFqUXO>k9rpRhDcj>4 zc^rI{TGSTbE}oYCQTlP(Mg2Sas6;(Dh3BVzJcY3iV0%zMjy|C(FOmMDGx3w19Q2Rr z>j_}T7^40i{YiS2^e?rD`kM4joddRHOHY*^s=}AmJnGRpmtXQdelGnmdcMA;ukhm7 z*8lZG_ICY{y<D({J%ymdD?+&uiHurC;hkJXEjKua~X?9?;kEeKv}3(0)C8yzU3@$FKDz zwWv?*OUgrd_!_X^oA^^3#J4~_g7xsT>JNM<=s6VirTv~-d>D_IUPti}{9m6@9tA(A z9+N$&`YdbW&(yQ3UsJ4w-*p2<^AA*{?gibXh*VFZG4i|7#qQMU2r7z z`W)BWVSW6(Z-M%I^|scH!=oNfJ+*I#VNs8$9^7}r(5UZpXdFg8BeaRo9+xsrAZwl@M>VHl=*#QhOf)p^t5~wdY1%1IORO7f4 zpIODH^j)XWId%c{X{XQ?|2F>_fXx>4J#f9)AMDS6(IU|c{EVwm;+Np1rr?>T;DM%m3VzBsHVVG6 z#NNHx{{VheDNI4`FNO1wD@x%!WQ$VJc3%qTV8btkv$5xwm`Tr$`c=-3`b^G_&G3kv z9h>9-IGfQO7%%bNJAj-f5EU>NTlV#VIpFW{*YwT5r(ga({?>K)HU27(Xl;Izzs+CM zn_uQHzuDirzk&Q0EpEG^nA$@ z7|0zYtDph*IyNBcQjjGuh&xVJfh>W+psa#MJW<$&s7pbvz!2_cSp{+hhJvyR+2= zhg?5I@c1eBp6meG1o8$(g0c-R3S<$q{ji8IU6&zd+7Fi50Gbx$$B~Dww~W%jFF?v$tYKKQpw>^L;C} zWel8|*O1mx7Qq?JhNorLfINbSgFFIR1g8W!18t(50O!urf8r9zA2^NA$Q+O(a7tzo z$T*NI@Id%AeJ2IE0tIv6ex4B71dmcy1?Tenz^|zvqi+?s3i&~nfHVHrjJZ~P!;G7D~}{|@j6YIy_l2V@f5#)>41;73}waP3|LUt>%Dz^$1xa2a?7(#jI#H2DKd zkXDp*t^nl~$RCg?Ag4h7z~U?u$sdqYAdBFV%p6#hSpvU8nv_!@i{N7LVxE4P0|#Wr zz*U(sP_PL0&&+{^nKvMd;JPfsT}MmifUJQ9)KjQs3n~xl{p~GKxTk4kTTEq^vVv9Qy_ETSx`QKoPm8nSq8ENl)B^=>`1R10htAp=%1Wf z0?#3vo`8-Ze?X>yECX2rN_Ee(hb)5Qz@4aN5p0q90kR0D(Jy~Mj(}_e`2jD2FH_4U z*c=&p2BWeFj>(LH&5*cd637^kKkzEGEP_q475G(9K0$vp1=#@wXJ92d!2q`85*)@z zKez!h3S=0_73hafwIXu_WERLA=$lyrhogNhM`IYo`0~sj=#%*Y@&}f21!WG%B9LVu zOF*4RhJm_~8qqP-atX{Ja11Tk0I~)ef#xj`d!kRt9O#uf0R?|R=71an*#c@8>Jg3E zPo{ue133dS1!NY;57-6VmAXEy2CQ1<7?6`Ei(prJW#e@NyTKh$D^mYa$5C@qQ&JC- zWj+y{h;}VoK+S4a)~nQ^WbYM>f^oDbz#WjoH!d>XzGbdm+xEI=)EP|S7t#S%lQ#Q!_fPz2Z+XQk5%nu@eK$byUTI$ZS3AFMT{DEpg z{(!6jc>?kWWDdwCxF?Q4f0sFMFII<<=|wG9WERLJ_;t3BEyPkNr$83L zBUsI}l4(DC0^6dT0{H_EXS>=0@F_-?(DyL-Fjg#WZ}Y*YvkmTz3MhX- zPJt|fqcdlq;16tq4OC8n%z-1pqp9TwTn)-C*pa>?v9Mmlw)_FP1lLjT#K@7Lwrsfq z6Ekz5U=d8fc6%Jw!f}-GnK`fp_VPopE6W_%9INwktjKZ&mctQ{T_B5KDfZ|U^iIY` zzclj)3eJGM0C@yjuQ$b#y%OuSEP;YQunAUw`33R^mP8o?1%F^;SOSN!Emz>MD05(9 zwz$h2kRc#vK)%3u>iwwY1&qbsE?3|PEXcA8=4A`LEQ0Y^skJT3643fQJ<286kNxEb z%*9SDn_z#6%z+u$t>q8Q!DcL{-~h^)%nZ;DE~`N1fEZnFX>4 zw#6f~L-q@8&sbghwgtDvk0U>z1|Bmx1@Z^B0=J>o*QB3mCu$i5)$zI2W3-H(YIvxo zQI{xX*~c{v)Nl2^sv`Ivwfq5bY4+ae2YWa3Bi?1~J^VHy$qsm*`W^Op7cb3^nK>Y{ z;B7oeOViu*zk|o-FPS4Cr{FF6-v$rCk0f(Irhv=>`2%l(%ke(FiO*_zk~tt#;Ct%d zvDf!_?AqWf{UkFB-hdgPXKMv}%My44uihuIb&?sd5|mr;8GWsj{DGEW>&zUGRUl*F zQ2d6U#g<9tz-yT+a9EN*@G6XfBk-WT48D?i14q!_4eywq?3eLhHpR0lb3l%OYy$ZK z1%IGdk~ttpKz@Pzfu3M_gV4`>d`Em)U6J+Uq6lRvN)D91tGz~`Ac&>f%c z7x+144s=WM2EK?g2fE_r{SvRK%z-YcbNVCx)yO(F7`?RtS2~7<_+DdZlp2EN_-$jT zz{4AZERu*Xx&rLO5ya3Jwm@Y4Q|IjmTObB`UJ*ZbKid6a3&bFYXaI}>`0adG=OjDf zk8vREff!^dbizyhCwL2kU=qY2SD_<*?62_>55`X(gPed4_{;~>mN}qj|J%$W_%5>u zUdk+juVZ^O`@+NCKDDF08|Pi-fV_fXnME)>vk2DDEP@f4MKCh62u9)2mpL#BY?oOC z-{8RxNdCL=#F71q*)oOWm^V{69?wY%C*UVZ@B>Z+SFti;5#cW(eQX5YLSGqn`&H4r zO{=0AWmZL_Y3Y4W{OV3%7fNS-X-Dd=dAnO~wWkk@38fpqqdoO#Y7ULQwW#!=hoIj) z1U=>+XLs(K5WI^*=*^uG!rEM)5Z2-P$R6kma;5lf3A4^9e{nGLvYJmEsWkb{iWiQEws0G&K85%;X z%IB`9y~LC<{x_K= zaH!dJDh$Y@`Ey?}Z0mAAOad z{ZCQPv)=Z-`IH`MnH_ra_2=u~--jMqce0Z7`A<%}Q}qAK2iTW>JeTQJ)l&$En=g{&T*#{FsQd6xa5B~kvs z$MouTo&m}a+&jt`+&juD)Ze^wnnS<7=xJ#>?dh!VbK_2F8aRz@J<~JOo|Ij|y{P9g zIv1%?2BXZ>UBNLtoAaX_kokMEClsJ%kn7v?^Ql` zed~qiUC;a?o3nsCqFH4i?-vWt74#FOphcG!a3@0->NvS6u3?3Ze zrqZt$`XHnT8J0_tm6pb3$m<6sz0LALS`LW3h~>!c2PVDH zGC{Tl^)t%^(F(i>Ttx4!QAVzQ<)hHaZpkR;<2L&BIm`06jdCPf+RgOeL^%d6?QnYU z0QD`)jJ+dsK=dvjgN7!5_)hxuFw3WvMUa9%=3{Bg3%QGaecf_E?gsC|JHCR}JskIn zSoqcpKf7$S`&e=G!k>&xxg69Be=;pS>iXm5t?9$pv#*!`K{UacjGcnyx(g^DM9+T} zE8tZ6Phnk?FK`-d+2=E;PY3l*%l?pa{17OATL!`-XsFW}I|Dg;I@-nc^qh(0Jq?^j zul$8aK>6WkW!}eGjGl>hBKP4M%A@GUJ2G}Q+RYB29FT$|As^y#+Oj6jVf5_Gk$4>4 zSl-9ElmnpFl&N!kFCdr{cIEM`SE$MoW1j z8`2(&#bR7|E{>->56TYNfKhD^GSanZyb#9(*&kzqJdrWLA z{eCokZNnA(7C8fI{7>%cC_tZLpvW#O5V` zK)!(d0%JbP5zrFWD#-X~6=Z+3;!~}$$JC&|CH<|i=J-ZI3)(HQ;%G%PE@Xc!LNW+y zQ~G6_T`y3J)-j;=IjvY)`g(%ewd4sDHn85<1+`ykCG3%HV_L}8!6tTMwqtZ}}*l8C7CLQszW<{QPkw-W0quKQpyUk5agZ&b9m_Xl z_h9?5%p6z_Y8Bj*eOG3i)N(9db=X6Dm{u`kUGAMZ1#$-D2xtk^YNqW>E1GtwW!dWH zyEwC-u+)7rNgeM^G;frg-# zLKy`+V+Yj^y*cAcu#?Iy*n(}n>+%R>36z87jL8zH04vy*CD0g@NuW2Y5|l|GXJBq- z3CsiK5NJo956U9Y!af(P^M3TnAGi+tyVhf^@N+X~z<1kxuT9RtKA<*aE%U--9b`+`cDwb!G|pHeF#WmrtPG{8!j|FUN{5e?aT6R(F{Lat5woTjqdV0$CDr z24n}kM6GpM8}lS;-)5VXEy8jJe4|af@TH)3c&*pku(za^Eg(BUJNzw-Uy|+JTD`Z< zmT|4%w=!}Oo&k9TvIs8Bw(@7QHC>zfHtZ{NKt_Om8~q6v;%7J?|Bv2=^YJ}sk(VVP zi$L4_leC}0J0Y9kF6x3ga4uerDcQH7&0fxcJ`e5mG6tsN9oe3ioB_Ql+T&#j$QfuG zPsMv9i$J!(Y1xl;DyU~i&rh5DF6rr^1AeblK>au!@tKKwcH|EfUZXRz7wsfa502g> zeM)D+F7Qp(!rRmmKh-(;9alY6dajy-`myx8G=&SG&+FUl?~*N`_eRgxw?BDw z|C31|OW;9JznLroef4q*WDNWva|ZM;KEjrq0X>fT$Mjei{DIGdEP0lMeY~pj2ZqKH^Xv_vEUgm${js#=kCf=uKOJMB zC&dWrw$r8%bzwIuX|a^}S=Ahq3>t)PDic?@1Ns?{utC39q}gf27C4@NA?)Nr+V{!C~YtZB4r9~ zS&1>oOpHO^VhpkxW036_StXk=t6m(N;ybxGHp549acquXX29A z$eJBljT2awSL6U{TPRV>TS$4^{ZT&Hwsy-AKgZdp)S$0=#u{vCm#D@*W%Rj!8R&PG z=XJZBwV)O&iR*u(yw1x`tI4|3h@J+NYM?pq>(esxd;{uww9GtTpV}<+=A8E!eA^U8 zK|Urqc9C_p$Vne)6!_sDl+ujrr@YgI(v($G`Js|x26<(J#*|8qOL?Gz(wK8<9PDyR1xIR}`9_p- zen$gZGDfPdq{r;>hkWGrwx)RG?$av&5|6pWk@`zK<}%P<;xShP{UsiAbHbU*a*>0sSQ&b6wD1;xX3){UsiGeb8Uhl%w^Y#)JemrLLq^ z0-I1brd0-3QdiKb1~#THr&S%Sp!RO_8kSQxq*dI3HTVuWsonuK`KDSNop(kpj=($1 z`=&NWrnk~>4`9f@%kx%A@ppON8dLmTp0^5$zsvJhPVskn-WpN-UB&(7^We984BmHs zyT?$IZNJ@PsKvHt%44X__L}qX|DW^lulOAK{J1JPv;Qm3V_ot*Q1yPDzs9%hu>9xW zC0`!vH@~h7>_pvxRyD9Ab$eRX!4A~z@@&wKt?HZyX9HRBHJAmR4dlSf5O6k-{Vtcl z*+8zld;`~)mTc8w7IbcqiWQmifwIU46=?()hWwYqI$kM)$*07k*`kmd?jjv?Kx_%M6G;vYUV3ZJ71kz`AXCQ z+i=ugiMn8GYOhOO&PQ=wycVmkPW^mU8gN#cb2Ypw4LK{#GI~Y4I-*y^tMk{_#cSbp z3Hge6by`xqB3_*q6t9R^r#Zzd;?-$J@rrnLno_(XUY#cS3VAJR@LgUZuSHGJE9AAP z1$u?N7PUdIkk_IP=oRu>)CIjlu9Wpauh4mDfER!=&o8DH<)6#9J`auRJhsnb%eJiS zv)H}_2A+)WW7)a{JUzGNZy(F{rPaSr$?<42YIzS*9>P-M`xb{%jzIfSD|~?RVAeG+MLRl~?fWwW@czsg zygxGu?_>N@Y$rx&SwT4hJc1+H9}CF}(Dy?2rjBYpsoIYf3{!T zpY0m=V}qEFrNK87=3z^i1MY=&WgqMuzJoA>vHd{bVwgcW1e{0T494bxd$E^1u|v?6 zWkWrVEoLUD1?KT=fq6XJWFF6!oX6SMJ>^zCj~!=Ma96f>!eTNV>&Q;v71$Rp$7Y}< z=sC*sSOo6lSKmUp3=4t$sNYbY%eI2c(Eo3x|5^HfgH_`)K7SSE%535I6`H;80!*Q7 z56b_aLfH|kf|jXgDB2dZT0Kp920OuQTG#S_t^$4Q;#$fzSRH&TVQb11>@>d5aU=U& z3tpS;HrHdh(GqkS)|kuay_sV4rV6$u^SLRY?@dgmY|TA;8~u$a+L^RrGz7IgX~Srk zZ55NUZDJBf^d$Bbt!0xqJ9~mtIQ~hL>EL9xCNcID_y3)IvO%_R)CYYkw-Qv_fppZl_&0{RSPs<)xESTdBz*_q&f%qygEk&wwi;@@>A}d64-V&XvrMp+@nO@ zidoCmqkWz$+A}9a+RhK{8Epf$VUHI$-Y2jv-OKk4ruL1l7invUeGyyfi}Vi5v&1lZ zYtSA_Juus+2If76=lMjNuU1tpQUfRhvHK2Zj_IFmQT^#3fX&xgNQ-baET`I~)}!>t z9_&mtl94j(lCLq+FWWHs(UO;_-J&n0A68Z0x9UY%2fJ!7a6@dNV?f_^>%f0;P1VBO zAzP0-u*YcHBNzMnUq;(K`;(%O`<4Z$s_ee-E^aC5dcrrr>ofE|5fif>nK zLf^*pPGCNGoVj2Lcu-!wiWRL3$Ke%Ro#6;iI6c3d=g1j;bv7}7rSrTIip_ImhNB{y zqFFBf(L6`qspb?jTB&#N>TF`aoae~r=kMha(?YvCn^=)S?EfOq(LXDWqSD5i>$N)W z<^NV(^flMZ^<#B}(tk8h-)m73z7-`M-y!8a_jwDkFRx-95?cI?(o6s7tr_6X$RhfNh9X055BfI7P_~C488u~(Vf6TJy6<5O zL#EvcoK9`@-5KC?wujT2jznTi-u029njwW4lefr9S(T5n1=~f2gTKy~_aEmax%ov@ z-VKqi%;(jX?Xk!u=A$%gUJ>cK$Vyq2iPEf;ddba0Y1X`&c^#>lSNxi+C^cB86TP*w z{8l^5OSS2#g|t{kuj{=w?=rTlK3nyv$X@YhpRM|ow(HV=_^i5KO|EHezEe9u4N6V^ zb78G4XS*7Am)1k=h-KWR4Z((NYs+o`Hej0=zHAZ0mu>Ck^}u>;2fni|sI|Q6IF)LC z={NrTIQ@02kM@7|8yoU{fur|(wMIAOcPbT^Q;cS*EUML1joa_ldRxJrT8);Pay78f znyb;f+S;sq?zz*7-jsW&7OfVX$6BCTa|>F{k9(d(n0 zuHV7y=T-E2uC@<*X8fhvsXa5!liC5iKfF5%yFlTW@eBt3pSBl&PvF05f$>+twWZ~q z;deHqReYCsl6Q=fqSolbLhij)!8iI{{v!3b>YRJOUmJxwk(LSdB+rVLB!6L*pUCr3 zbxa;d@!S2ao)wS4-|kuQyZy!9rT+Hfc*-~)kEH6TJQ8Qj>OVW48updoV`A43G@l{ zS<_!pJa;~afBU)9PPN)&RXlMudBS`Gf9biadg8R5dM{|H^XV&|yL$ij-1$rteGT$n zK9fG9g+0$ttEX#W^_gx7`ZW7&dp@=2c@&;cb#=W^o=^36Ep1xgw23;K_}eP;S@jqD zYxUoF4m=m05zme1$TQ_R^W1p`3on}YmE-y%|8MT|;tv1$bNBOmd-ap&arq3|O7_=wIkb|(8EJs^*T|vr*r`I|H=vrp&jS02B zJ;OOx3vA&7)gD`i?JDnQ;XN!Y)rCb=+h|jcr5S6l+^wxr|@Fi_iyv*1wfjS8@WZ7l(wdl_Oe%abw7lQBz-F-wdw zON=o~hB3>7F-w3kOM37Js3S+J9bsKs#Qmox;y*R9|EY=kPfe76YNGQ~CuF+;plmwh zBn|>);(4v*0F*eV`bG7LIwR_h9Kv5?j=NpE>iK$B=X})Uu5fP9zwW$JH$MSN2i_w- z0nY9E&%KAdPniII%DcnQ7V?sx^}eY3taqPlV&qsVz`(h5 zCaUtA7PF7fozG@jemZ?dl>(|(eV^s3Ro`#(X?7;^JDcTiQx0%G^4s*m=#QzxSc`l& z6rP!u`95fwuYF7UTjZ1Tx*=~T-n;S^NM=Tv`Ko6 z1OL};=cICu(K}Lk-FeDcN;%xs-|hN5nMwtLZRKoNh_-C|{;aY|Tef|F)+^RFe`i}- zzB#MkNsot5y!U`!DdzyaWB%4Q`B%#HtVY{=Lf@GlG-n8BqN;iF=WXvJ?|0wymiuiwA50$U{KdzR_S5?=< ztL^`Bb#)!|zg9_EuE4Iu-icm^D)xdaws*9vw%_}=b%dYG&;L=*FFyOXWRL%?&-zO} zpM{39T5jQhyEjc2vEe>}JThpIE|8UO1utemo%^WeGlJj=cCta_ds=W|`< z^D54;vd?O+i%+>M7oXyS^U##5>b>;0<=ZNGQYlx-+9%IzTP08W92SyfA>S5~tx~Sn zx{xRJ!To!A(s^&S47qxp{iWlnl5agfg=AaE+n%ke;I1-}CeLj>i?< zmEB|V%tk)r_j+b!UCG7zxeVZw;MKF&{oTVS!u<-_pp5mvRA+FxoFa*Zt_%$6+kG%4`9s%$9)4ECE%re`8i-=ife*zO2u+ zX{`eqUBL`uO|oQUT!XH(yYOFn=R3AHqxwqfu-!Dv2~D$P(lkpiMJ9#1Ss(WCA=N30>*o_)JfDSq!2gHr+-@>YjU0)| zpx#R*>EYae-Pr2NJu`_`cO=J29H*AFNEr?eXFt7S`poobDG3e%^&Tcl+SMgQ8|@te@<1Fnm# zy9upoJQ4js?VtJ-`-56Ct5Lky`qHY-zI{OBEY_gy+0o}#gR(JaVIr-XNb?i9QWI#^ z%344zqOH&S~j!TZ7sIT;N`3Wjn7y{DRK4H zsFzWea6gZoKbqws=} zGK8M_ptH=$^vD-68rR8eFJNmvcj}aU&&tt}HR5wJ3~b7*=3Oj08KivQ>UsWbGWl%(*_eK4UFdwYCJeWRFG6t0TY>j4h_Uh`Dzp zt(JLhYssE1@>zq>jvnU;*PM2FEozt7 zqV|kVU|yI&ZwK1WB1Vkr2s+;wRjLyxpHw^5&fLi}xHs3P)vjG(Z!2VM{YZL~##8%0 z^f_tU>OgUJ^8e|J(j%pBN*|S;Dt%V^uat9L$;@e`MC{tu3RDkwRnzY^nzJ^NRtr$Q zz3`d2w&_39dQte(lo$%{T2rpJHjE-Grm}+kfMMJvLuhFy(!QW1Q2}b}QdTGj)l8HL zl)DFU2fM~MqG;9VPpbh>&w8K|fWC3(wtlqg{0SzvL#O>g34cOuGgCDwdVO+^L(wD57*3x|C;L;Z_Q?z!}nZ#vqG&wHm=+1 z4kaWDw~g3PLcVajO>U{_=(%yF)Xt)PUz>hmOVon)*Ipg1v3fkU&})fRUn#u#YBEOO zY=KOp-@u%mNMm6uu|-xM)8m1B(JX)Mq2)Ji(aY`!UJ>`xpMj~M<#~Z6*2%5<#dUxg5j6xROi2jX{s|JGV07hvT2&z%YJR5+#tJWd^Yyi@* zI*Dwvf>qWJ`B|o!+_HY4I*&{;QN75xw$stUjBaa8j3Q&M5pd;V9YennGkj~Ih@5*g z679}tYG%zXqUf5Bw<_MQnR}~Z@|w}txV=URm_y6hy~gl0MuYKxWs%8}+YW8S{K7@F zVB9wIB6@j+CLyG=ph%2Ay-%4?0r@ zGs~3I>dJFf4wkdsjc2M6*of`!JY5aJhHM)xxB=LJ?HCAJm|wy|D&ZgYCiw*_WO^JR90Hv{=fS*V3~d zr5{g{){_2|^?1Ux3F~9;&)lH}MqA8)HP`E3?0T7rDu#zC59R1oF+7sDjaL=JuPKk@ z_*OC8leh0>D~8)C_YgzN)(zpd=$lM;6L-s8Hn+tagW02Qq{oal*U>{JdE#ghGoD`a z*W4Cw4o2X*nS16A@J_~jW9qhe89nB&xtg{)Yi=WY)2}j`7ygFmTUs|nGuYe^Z{eM< zJ9)>;=v{Y$3zE6$=O<%*%};lR8*@~-JHvkT8%OST-jte`j21SJD0DXwH|}=E7N*;H ze`;xZA=)V#=9~#wd5U5HI)Eus@OS?&7_%ec8S>N5#7(ZcWctM85N# zseRI|u^zGY_NCs2o~?<6=lfH8=LoNR=cum6-m6CxynDkvVOvJGAzt6!IWp{CIWp|M z^iE0l@t)J3jMOF)-hIJ{va^X=TZ>XV898M;V#wVO*33}=Ycg6Z`R3nLaB7Y#JBzUz z#P^$(jFVzkLZkgvr_@LfvAqNMAa%8z3$Pla)ziaa2O`%QIc0|whXoXLJFS2Ds!xuqw+Z)621<;&C zMtFQ4Gy{?GAD;t%!~1?liu?`uU3`{z{l269EzxJqEc87+-w`*{Y(hWK^L;!$8L8~F zWTdjw(&^Nvrqj|>pmD~|VD$8KMl!zH7RgArn-hmo{D^3|XVQO0Ix`t9?UZzCdKxq? z*(CPdg4l~jz1@t+j30s@5^47=_B=D4m0lpe+R5pZ^bBZZvrUQL_yK4v-pPDw67d<0 zk~^8mho2DJ`BPe35*P8)xCs#<-v^EFdjS9EEFvQtQT(KIa(b4S&zq$8!1v;tu@C!i zN!-ydiKDoPeGVYT-b?XC;yrJi-UN-#*_Y8iMBsagJr<|e<4dt0J;u~D_Txn2RK5ki zMbyp^PU8QEaAI1OLRghf0*%`iawNBqBen%1wmnMEqg=rQlevEnah(r{Ednw~@GF<+T)2Or71pg+VT zbClL2dB^f;dj3L0%_D>HFpms>B+BJ+;rFqBI*yUw)9z0kRQ&_u0HUNG6O5#)M_^zY z8{Q?a@;Fd=XB@wAW8|DSBAP-{YZyyJ(yfq$--t&CBeLo{7?dW^uV-*W;*x5Mek1BR z8k~-z3`rB|*Qz^)Sfmrf2E;4XI{ij$6JCx=J}=Yi8eWYDr>>l*rQlMcM0Q0gdO3Eb zyaE~vwjFKdqBr8paU=el{>ss5Ou|P({7K(aT$Z{AqflyRJR}`YG~l7&QPl1ElycN$ z>h{_4t^IL%>Ve#|JgJo|PrWEBz@F5n@t-%s7ch!QxgFSFtFs>86No1~EGd%@O=N{2 z9_B!#pB3p;_B;*wYYX<%_uDZ`>BG{AL>?ZV1_a}YYO7tDP6;E^C~y>?Srvv8JJ+|e zho_Unh%^!$$yg`;2T}Iv@vUnk?)p~t`bn#MCnO-FmTK)iG<8Pf=!6Ec88Y5_!91^8 zdk;%p=s^qf4kuD-zhLB4Ey9PVR*ZB(+UggMOnoUwCH=tSQQTeHe~BENUGZ zo4dA6JOuf_4gIZ&8>X+aIk{>MBO;i7q-OLTPTaDy*`sar4fyYQ%e^hp!kWb+h#htW zT0j%F784z;3D`UN_B64zk-&SUsT@-;Vj)irYbW2UUYpV0L`v?Jngyb5BcC@W%Glzt zPSOLj4*RT4H07SDc_7+0viiD756rrZu0yQl9;pRU#u~H#AkG0iD@NBPLiYCPM#f@p z0qS)m3O5>nnUci~kh;6k+JI=<+w++QNsX)_*no)IYHDUyCa)u92vN3oWUNtAn=|_| z`5`GoLpeQ-h%P)0J+CtnyN7~m0TuL=C*w#D3!Nywu``X{j!AvN$kM|@<20QfBTKKJ z^~}a;27Q&OJ$>jDlo6p_QU@`<^oXoyRwgw}(fGi;TSRPNb-yNQR%n`7`s?cc=L2@tl*3t%Sbs9PRrRkf&Gm-+JO2*&?u$#sf~`h7+rji z&?4%aQVXm_{IioNb-+4AH9Lt?53I*$jMlms4ZdY+ zmGru|OuGgnC+mlAmDKW1M}PR9*mA_QCcjUj{0Qn5OteBw*?-6*5F>4)D=RBFcu6leq>$ESk=S#dvt_A58%FAT5`a`G@zo48HUq#z0<4y81#$H1U zs|HqMy9V`dK{M)UYkCbWt_JNZ_}ocE5;eEl717*kS44BGT@lTIcSSTa-WAbYc~?fW zuwBWXR}g*GyllUs=gL@%|MCXfU`^_)=r?|=8R)Ji&fACJhxA?(%~f{|Jy*xt?ENPC zh5$5yYiED~_NT8E<{!%?_u`4I_zTduAL-89}@~W8IFTjEut=pG$1K zVc_T-A$K&Rqas-v*&=Tvk^F`bQEzS_t|EOzT%>m}eRGYn$o3$%<`QM`l-PlYc7tel zqTMkLpf!&;a|5Y6)6n-axK*2uWm3Fc-^oU(ZTD6y@?}U zH|#@{@w#DOB8hA1Jug-g^Ke~IMouMV5ok8&$}ovsHkHBH*_B~SB4t;Gt%!(S8Mfw( zR|aEqSB7mk|9pxl-<4qzF~2K=alb2rF}*9fgM44NZkQ7rvyVRL{mJB05f&0Zyn=S) zY+;@g>$At)D63YSOD>-BupiOH%h|I6yV5-J^=QML7aI}3d;z$C80C%FN9%7x`YKsn zjovYax)RIn7|LE?B^Jv)!9~<_!%@ubbHmBZ@&_VwA4z!%?8*@;$#tXdLNPu?ck0f0 zTbpxTSAy6Ev7S&X4-?NQ=djLvQB%X%roh058uOHqn)+`Wx1Y0 zcyvH_4$_zy-wZ41Yv6=TP-RTr7972B)8laP{>7Mo;wunB!9(mo!!y$PeM&}Kd?=Lhlv&^r-n zq_HGNe275dA1 z;ChVhinKf;ukRz%d~})qV1LG@GcqDgr>vitQ|XEJ%7N_GbTmkbvcb_CVI%2$^;Ql5V%G>CI2Q&}Qaizv>nCLaXQt_T@8X zt=Sk!TXs*+B)g|;)*HL>scuN&YAU_hYg44$ag23I>X}=hMGXSyQ}4-t(-yTEI$~`; zfo8)#U66N2p@~jPTckmtmhDbyG;&ra`a5Tv7WVx#DGde(Bj1|mXiHG5f5#+ysU!P$ zN_9d%zN1c}3C^Y71}osOuq&V4EzL*EKZ1F59`yqB zqr<`Z)H4~~HSLEsbr`el0_t7pnVA-%YaPn$ydU+>^z4%MM^jtLoW78HY1IF+H15b9 zwKVF*S{gS;r(YV?P?pB6&_`BA^8~GAbSZ0X{j^0`5zQI2g8r4Pre+RWPR|M?eb`g! zgm`=$8BU;V$P7L*9FL6O4q5s{#@nTH=sB77w;V0#5I(ycS-vgu_A2&jo6ctR99G#1 zbfIPJa|qIFYb5-WVjE=pli0USI*WbI#=`VM91^rN4GC{XeSdF8eSdGV{Q`EWZ8&3Z z#%-~az8R-r6@8ihk=PVoqCPIRLi;$5|J^FR!|0pXhql8u`Zo9uR;a0F35ktU1z5px zyn@7dCO9&j1-?xE7W=%7t!Qd`3k%uQ^lrQdd=E4m*RioB`jI-3d85ummNZ+`nMf;@ zsc|}t|9mJmY_oLT&Hndf&8P)dr&rnYbgWKiAj?#;-{G+ddfZ*)``7{8fxVB8Ezrx< zm0F}DVpDXtBiQF~*2(5*ZR$kLv2(q~e=)yBvvee-DcF?#PQ&tbdb~64geCS){^wos zb$U)iW_=yJBTh>@r8^kC6PwWM^qxX}Dw!^(r)lZ-I3rC5r?JQL^q+z~e&;kJ-A4cI zSgh-CZ{14IZP>Z%gj=zK*9o`8o4}i~pVtXD#Z_reJTaZir%#C|&^{PEk@_UcDy(b= zBOhs(I~Z%|^T=-}=dt6`LC7as;SR#)Ifq`YYD=(vo{OAiM!<8ipw3~eb7_BU5}iv2 zAhC2R>96cm>P+2*p3bE%rA5dy9ZQ``D?&%g^3au@E~O5oj-}Q)-UUW;fiVryvZR_YE8p&r2g1Ci#n^YxF~ z_WIKvfG*L!v{q>tT0{3z3%1rOtrxZPt;at7V-Nb)D)l2D&QYl!{p(>{X+du*N>8vQ zb>Ey7r!V{Ti`A349IJuVQ#CB7&(MB`GgBj(`>{rFQl{u%Xup zH#((M4D1D*n>W{K)udV!2@>ku@ z-hYW^`1}}&|8npn>L2JaznmF959L3Y+pRtN+Wu*6G?e|*LTWAPmt(^>+voR`AJl^B zS;?Mv2` z88w@kSuYo*15z)r7n;*I^qA|+ESbysta zXMj7Szci(PhxlVEFKrL*fNmQ~Kc*egbIVIRQYuPQ>DeAVHxl%ICv@Qou%gtsv|UW4 z2uAiGt9&VyrqHt;y7W%5acMZU*tk?#+BTMzN??gSwu#kBWudCWvo@IS(*$^j+0_}7|q`0VGQ<)az4>0)GpO3O^UTCTf{o0+9h!d_0!Vk zaWk+Ebp`tq4ZLIq(|V=4)b&f7q8ZmO)uV1u+5}y>L8(4yd+(knqs5A4!ka1o0`R@QM@)?lPcoH=@Re~_AZYXrHd2! z+u3f8mHV31oN{&gQ@A=^1vZaYr$+I@bP;$F`!%H92)rO&n7$5IrC))6qW&iQDqRVF zP2GUehFDn7PZy;6SS!v4&!_j#;mUMHGQ;|n$xP~3qBeMEkDBzo=zme*}LFH>F!>-wehWusq(Cex3dhew`ix zzo7m-J!aOpGu@TG43DIT!9P&{F+7|e0>7mGoKZ7w+>!1~pM~4g9pD}Geia@{4<<8v zJd~ad52gpeuc$u_x24;`+u83o;em92GT-?F=@a_R1#xS-Etw_ee(?TuUm{0Dyal|K zJ$@H%Nw=ow@&Dcj-k0u8A2Vt;34Q=R9=|g(VYf*;P z_XE(}7iQ47JDKg~ZuYt-y-$x>GOAl%NzZ}LG4@n=J^eNr%k}m2Sa>%5 z2K)_UPc!n{^fcwQWPTg*we%|9_Gi+w;Ir&^Rd^=6ny#X}f|vandVd|BPS2#P8F>YK zCB2N#{b|M?2~VY`(={+IUIt%IFTnwLim`_|#;0f-*Ysh^lj+*lMs1iF_k#CR*XA?#W8Z&2eUMW4Abkja$hXSD zx(Ad8QsSuJPbKy#Vq@Kn;v{?JyyvRoFnG^t zA1>l&{k;fd#T%SPS~mhq@mHT-%lFs4M!)o3-qTgzX#5xBO&HD0C!;D7g&A=E z-go^xa+<$rHRJl{k=$1QF26;Kw{OjxZ)bHRH{UXqE%~>9*FWpKy5?)wl{5KYi>2%v zUB21n`(3{2Wpsq%J+SK78uc0eb?nfZZ2SJ$YDTEpMK8TBKvq!*DeM`C4^ zML(J{3cH{lhB1`U*!+rj2lW~h(J!%!;WZcw$|i14T|~buB4PSgqI{c<)J62m;@w4~ zEErixe@r8a@A}EQZ%FZtKYvRDitqaQE9z5xlc1Ug&#D-y*yvlCms zMcoPPNN-hCv(9Xf$A8lW>_YE2d^%mhuCk73o3B$p&xYK2-NA13Zor+l7PuDMV`y){ znU>2ln)|UQXe6>xv`2G|v~Q23jN)2p4H?D-u1cj)&bXHdpPa&x$^7M8pd6? zE~q_xC}>=izO;sLSM~+97!L-0hd{gWAaF2t@&2@YPr!FB-N$z`*8|sM+jlnmgTA3z zk@u>g$Ls268dH3$eGsim{?{O`@^W!-oL%|JOXS~#17a$7v&7NATPZP6`3 z`6=42TY<9BM^ei?mxVrxx(#To0d47K7nOyswY(iD+e-U(d$1j-?fM^i2e&iVOcuKD zk#qsgGUB@DGceW{_xEK8MV&*Ak8)L=DMgQeF$5qLg z6h$QWV#~F{93E!!FsFyPJhsj-WEc6?5acIZ+2 zoSJXMXUFH%JS09fKBvauleOWqY0i=spgBy;Wn$bf^URpz#M}l(0GmiVaCUt*Cs6)B z_TB=_jw)T-uBzP~>5jX0cii1Q9arLnAn_nc(BMvj!{F``2yOuq+?~N;1_&11C1|kk zzE_?7cLx$kX2P8F{olFzTF;WIy?a+Jd*AiiXx_SWb0ldL^TxS3g5*4EM9nqF+2jmG z>Ja9UGc@hnAz_9h&!9dy%u}Q$VIFC{gsg?uVtTJR*qr*nFi!{4;yiMO4j?&?oTvRs z&L-z+KT>~2t24AO$=T#Q?L+FzC~rrpcbKPYTRHZfr#(SuhO@N?=)7{ab_bnF&d_e4 zGt7DF% z&_40G>VWo@&!z7m`_SjA1=_bhS5449cjc)8Iu?AQ>Y%H*PgD(b1o=c&K}VKPR0VXz z`9#`rcLDWqowW#dRms|J`{Wf!j!fT(GAu`?Zz_-E$n*`CCpj{Gv*k#x>b~)^ByG1{ zRmzaG;C5Bf1C+Mgt}6P3k|K3g(QlNix~qzQryQ9BDd~%9AS1Dul0K`78Hs}^jb_9Q zVk8cxG%BnuBSF^&*On2Wc4)3G+VyM6KY~(f&7WHKrz=Uis$^FZR~6R~*OSron;st{ z(3PbX<j{YHtuCXsTo(2)T%{$ z7Wc?bBv+D@hSB$wbW1)cHDmu&0HtR1QC|^sJ+Ys(ZE;o6E??Ugd%6dyJ3ZtG=t=59 z4>>YQB0*^Xul0ZG5kT*ez3CxGSPAu_9|5VEjiX_tTT)6U_28X)^G>Okl#)rQmz0v( z5Dn9qd6ljvMZ76zfnEaIf_eie&%0{}>K{N0A+3hmQ`g%-2T+@#3Y6vHoCOs@PllZZ zl|Xr*bQTz4Bb^IXc!TmT&H~?>d#i8Mx8~mJ8`Ud958jt=)VJo|>KpZ~sb``u1!=zC zyf5FVZ>@s6Hk1C*d1)J(d=fDr^)+zALipm$RaAm?zSLjhGjss5c3-s43Wl zIWmU48R%}S&0=%V-8LfM)P2^yDD_3wnrC&TGnS5?cw7x@lk`*JzN7AnzBb))YLfI* zQ9!8%&yf1vaeZ^&sRlZVU5l%Nj&4`xDxjm@^|>GM`?!S z%H}9dNUm&-QX8GZeKaG|cm_r@7!}6nC|cZ+yHOtz z#_9;l?#10hZ#!a#F;X1`j@Y4~qr(xaMwFw*5jz-kG&y1ifsQXnY%%D#bHok=i$O=M zBXuC}Sl*x-J!IrMc?7*BNp0#k$(Wh?E_Gh%fi#a^twrl^Pd4-rr;k!SfXZjrCf7%> zo`O?~MgO)^FZyb7TV&=Kyqa+h}3 zcCXf>vD~>HLhN6AwH0mUX_0Ss#Fr;IE+T5{j(k0fq&q?pzh18+F`uo)w>Jf)1Zq=n z1UBNo*ABm+HdnRuETUeAPZWh`OTtt6%n7YV`qTfHv&ML=T6#K%8jxH8+(+b=8qfpo zBgPeNNDmm<)YYpY{gB46O;5zihki-vM`_6d?vgTh1uO`Cq>u6n^rGuyO_JJYwpHY} zTK7sN%2KekD5WtCQ=U+dwDz@e1@-T*w`^BQeQ0Y-sa2&ttG_>^0c=YDW_z|iPgtKP zma1w1+Otwr&f{j3wdt^z?BAB4{Zc^5Ubau0a!z2lDNot{wRg&g-f6_IbZv~u z8BE*Gk=s+PS(2Xmq!g31 zQ)}*#O45&E5vx>pP&<<%QcqAVts+uyP}_wfQeRNJgd$QSRwBLr4CWi;!rO$EX%H>N zq;{-d`Y|0yN&Z`Id?+nLSgYj22ar0j_C>Vzr_>Sjj7YnN4y=z6*Je@g49ca?q|^nR zMXo2hE}%9o(@EXH8RXkhDgvjIZ%bZ;Hr=+Mwjr(t5#Jk=Mu48Tcm^>F)LzMVEUF*p zxXgM-EKj?;O6oUJO}F&jd#<!cA$aw+GK#{XBJcuqK;(O}Q$>0vymRZr?2 z+1WmU(W3=XW$vlO3~ESOZ(NhYtkj!p1InrQE_=8N<23c+rBzj77(4E}dcSjI6_RR# zQaFXA+MsJ%A*n7XB~wW9vs2LXDkMz>^*>gKPGS*hYp{^|w9PUe^%(0ua*N4U{^!WncbnXJDHxgUCDf^tT!}0o%!C< zH#nKxr=1est#81 z%xxEDuXA2*zL;6=>@H^hy9zk#o%?OcU7KB@-D_QmJ>_#P)`OzEv}L z(K3`b?T*)jdNZ&m`Ec5Yg|$@sJ!xE5SE=7_U?Whf*j_CH^*z^>Qeo)Tg7DT0LT?m= zUMdLvRuKBLAoOzqcNRuR@n43c$$3;j-_wy{WF1Yr(O8dUlpPU9+%dEqjn3NJQmfUu zw9H`y&!#+!bTX(vO#M^N4P*Tjw6OE2I}=U;^^>^+E!#6&PDLBrIddvH<$1KaGwcRx zx3v>%N*;(DlRZL@u+F;O(MFf&n9mAR0YqDuy+exxXXYO0u*<0|AkAl;)P~1-y9k~4 zO0-U+u4ff}uE^c!qf%{oDZquSf>kJ2BN!A+de}8cTd*c+ z3)GOb52*c5L(+cWG_Evcg_{hz8#D|ndc&}yyS8mbi>r9euu93VY0>H4;+`TOSCiGN zepm}@hgD75aUAQW-XQCR6%qRaO49!0!3nI)b;1tTkY7*`R`h>GK9Nc$lu;<3Fk-}? z%O}e5tEI1`H8(~+p=6?nwV^1i8P2y1v#vxw;jAo?QY6fIXK_|O;rjL0$S34Hvr-B< zPh}N@Sd%(XQYPUVEaxc|v?=n5-mD>Vi>Z{tQ=G<6I~IwIUiPN6C?UsBvt|IQKN`0xb8GnqnYA1UfNq^8h7bHG_)gh>%Kg#v0!8y*7~S#rkBpo1FII*(5` z0vl12E@}=+fp1UyJm?_(yy2ICu_krY0=h@ubvsfSa5}Xexn~DxpEyuQ+tEIsvb2z# zu(VJas2urZ>7TODJ~4MJ1f_!H-KLT9z^$oCh2%l+#N4q9xO1RR@<2JeU1`~ckr-3b z?}VdOS|}SSQ(DLq?kzz1ttikcQJ_PjK&3>1s)+(E6a`vHA8`7HleGN@cTSAngb1_Kfq^{x|NFGs;*n+@XH$xAI`2zQ9Im3GmX(g~ZFzTP!kE?W(zR67 z9#iVlaq8H0KfzfBi*b#6T8|l!j$S{eQvJn zZPSQeu0RbySEryQ@A=7cx^lnbD4V05jIp3%#B0%&aZu zx9!9=J)PfV9`m_ZnAg3+`s&$+{!M#=dOsZ> z_F+Arj$>}S8|(RWJTu%q*?8I$nCE&w)z@iP&@+t5;3VdJAtmfhSu3zZ<^LHeA`c!u z%iGK08@EI+s3~VZo3j9SFHZ#K!pWz+e#+UqzjQ^GkyKK#5qzMQ@M zy?dIc3`$BotJfduZk%u&M@=88^7<(^FUPMJqI^zAjsfNJ<@Mdu~sbEl6_bSJcYrt11B+ff8cDU zW;nB{$+^v8ls(s}NvgrR;~8|_u$LKM(bHEYyY)!5K+jHk9>>K8+`Z}(e&Q>Mu%G=kKUVBF>y-wpZ)}W@`Q~7)iQf<(AZwJv zx!1UQrv6gZEb-iDEGV5*oiq*{7gj8FPn^MOnn~HZ!i@x_W?kDxgPt*~lQNuf=lWln zF_Z_Yv1U9kS9ecp)CkQ7t#O8cFq z>Ydvo&Pn+kPk*HUvKswTgUV(Sez%hD47E&ne&3$|KmRZP&+Z`3t29oDJzEl?L_H9- zLQ<_^bw}J&+{ZR9PKooQKI2>3#Bu&-aY~#A>Oy4Cd#WAgJoc1Ztubj`=YBR$Nr~jbvq7n8*8zF-e?^Dh|DS5o z`)f+{SzRsGr$e7cV{t5Qj6Un8=+MjE+drumT8aLdYe9(?+UC?hlQu5Vo_Ab2DqX>U zt3&Vpk=3MEKY3Gi=+#F~=aoA3|M~gl&Qh2CMIO^Rr6$=xW|g|y+4+^utUrzeB+ce5 zGa8UO;_Hh8ltutbwF;ea8;%3yzM9n{bxvt@p$?-~7+PbfMJh#FGPB&D(l|iwTvc)HW5ovU_YYNMj2Zn`s#U`D0; zm9y;shWX`QrrxYOm%G^d;%vERIm?W;rBz0{XO-T?vip~GYe|F>wSCp~U0@3@~ z`Q@B4!dA&H=2+gCI9u8MOF4UX7i&Q&mA`NL{*~^L?v2juRExS~|N3JaF!!wNEK?JB zbL?LmnqN}9QW)thTmSq@`#!5homzkWk^Z!6cZns~09N#Lex3SV}CxHlGdH zUpc>|3DskkO8lcZcIhs*?*6r@^x<#kR~pSu8br#_IpzFPFW$YZWEYd)cIV34LZ}!1 z+nuX~KHQl7Yt!b}pY31HHR(aALTSbSF8WZN`gG?mv3HWo^WCJDmL)cpp5T>OTK@Og zCv0ebWoOoJ>BG|VE2R&$VpFevUHY)}{xzH(E9Ia(4=k~<{GUu8YKM?oqn5;p{CD;* zPhZxZSsTB9rEwxl^IxUsS9+Qu{Zv9F%AK#fbCu@2N+LvVJpZ-1=GXtyhyQQVhbiYJ z50;IBE#V+&n%wHuwBWXI6UZxuNs<|2;qa&z~Ru(f*}1b1G3t zV;`2BAG(WWrFbd-^+*0DHs$=V^!!TCH&QF{^n6}RXHOB=e?G6Yro>9T#6CQwfl^O5 zDgPyB?>Y7Q&o?}oclA$C={McS&4&1||4HYE|IYrEp3JAGxxYQ%*!1(m()(9w`fy#! z@XycZH$)$La+f`s|2_XDO_-H}wWO4le{C-M@PGNQKiIWZcedZ2AC{h9|E_%buiU>j#DA66-zZHV zmfpWS)5xB3=p#(|Mpkn}ia;rtKE>8Izf#Fp>V+oN-*9G?Xm0%eWWKZ%EcKyPB46In z{*-ZH)egy1^w>;`;puZRmWX z^!a=`zp_-~=9^#tDf&>JE9C~2(dqx|-{-&nNdC3H`SpAHa6|Je^%mucM~URC#y9uN}q3RNWNTp|Jsm#)Nkk4pXqOG{Qk8u=kwW_^+)H2r6pg=ynd^NxMBUn z_0fkL;=eXV|8R4iAF3HuqJ{Wd{iyVOqxAWF>GMM+&Dryfe`kJ`rVlrD|4QeV5>)w( z^kl>NwK4SJAI&fQp{5$QdM!+~an+LgzlHxQt-n!PzMN|Lrux1Av**{w=pSy{`G)p( z+W)8@^;hs;8`3}24j|Q}{H>4dzwZ1nJvsCgQ7zK->-TOh{ixFWS9*S!)$-l+^TX2f ztMvX=T7Tmr6mKq!F9t6nmhXk+=aWZ7SdF5KiGgLwsJ{_$RwE*=8tFHRE(>)d{YKH* zL`92;hH5<51H-igLL{mKs9jE+FPeyw>K*%ss8stC>uXtjFzp8sYs{Fk#!9_{_+>G% zR`(4Nr}m}o%J@)P4k7a1Rm6YVhbvdbhtYB<(fN!AWn|Q=AtIA8SFav1CjY+;_~fI=|*r5@}p=u zl86$!)3O`sCgRV<(NRR2*p2crl#eD}mhrdWC!G#{K>i^uAAm;fevj5O!1u{NB97ZB z;3-^tm)0}E_sBmc64Wi=EnItt*0aEO$v+_~)Xm_{Tzi|=v%z=BKjnWf2bXhgHLX#! znk#3=Z&8b)2Z%TIIq|u6<*o-wpMsy#_8{p2;&JW5m4`?V5)JGD?!2G$MSLH*_yzH( z9_F5hz>~=z0UriWBEOewUxD|LKT69Zpb`4+q3tX1D`HkXM$4n1k;?C;Z4J1F_*Hk2 zi(eCo>T#|<1{#C!3Gi{yxO;bU{TuKb;#A#1E`Cc?swcVn1ZX_I+iCj_{Em24f2ZY1 z(0Ii}LW_<8kEQ+;J##D(^}Z(_*lpbVef%_6pCYc_4@3@IN!t%Zy^Eu#iLtkmmZ?Ph zdyU9at0-+n1i@9rSbmk#G$IbZ8gI$9*TJdeMh1Qze4Y4xTNByr74Q}AGj8x3;2ZIq zL~s6yE8CE^CT`SZS|*W*c1TRKpTM8EHj%csh?TXLw(UsU5|4T=Y*Kjvx&#|5?6YWdJ@NN4w1dub7c;3`CjBoZ&EMfvdty>S39oEB|6^= zTP>Jx`pqHng`U?MQ6! z=VFPF(W&#fGM>0q3uvv$|6V}MrhM8ziRM%PgveI4z!qFF>U%A)77?sI zrN#K~&H2Sfdan)ECTi7Zv=|Y7WZXPNeXj%7A)eLev=}4a7~aNvuM5^Cg5ejDvAw^b z{c|E7eGt_n!cje<8GcE-apa8xZZ!D%V0~f~eia!V{43hOByP@oQ3ImEHz4xhn#kDU zYqYT|?a4F1fu^JskuJfHj;+OGzGBtMtde}LzaUrPkCAHg5Fb`Guo1kWYEj_74; z!L?jFo7R`XbI7kJw%HHh4_rHo)>pu@$2^?C+9cT0Cc&OJ;oA+Nl#WF{kbnvG<0v1C-ExM~-@xOscFs`RHu(P97Rz2e z7U%&?`{aGFUEZ5(+XXx1X~9N#TJW-_&y9Vtg4SYrI%&ILrMy3=?eGk&n)d|vyRgM(#0|QoUe1Tp!eCTZ`cO!6LW;W$mR$apKu9*b5iHvl=Nv z4>-n&(9T>R33{*?fwW4`Ex9CpE9jdgmsA1NYBrZt3DmMSYim1|@srCh?gARcAeYkA zDD`iyRj^jV+OFswTHJ|ul*4uXb?6%*htvern?eq$8K_5voS;juPmh+AJsVMvQJXTo zl;i{(*c^U&5ggnN%$^&F5|@x}0&gM;Ttd1TyqU;v3F%hwR-(Nnq?O=GW^}@5uji97 zYsmHBcjPha|9AY-iO`}Gp>p)PG69N*x4~Y?n_<_?WhE{T-bbDr-AkU!8gVap0J(Hw zZge8)gg_VOMpAyc(Mh3IYA-iBIn;LvC8@n!BEscHyFiy)+8vZ$mm9bVlya9FSPr$n zC%7kdsrV|nU5p#M zAC!GeG~a8e9}u{a{ow%O=oEN@I65_OEC+ycMW@qpTHtC91P_EqGRm%a5PZ=YTsqs~dDKPOUc#nV3BBgc&`3q3Fxsi0((UgsJE$x*X{gbOwd54pq$@iQQ_^X4#gW<1U zrd`@_3Axl*ZgeYU>Bq(7XL0|TP??LVuYl893|A3HXF(+&MtvpR*kN#bG5p?bl%=E( zAwQRvbKnW%=v=66xwzX&x4|*S(Rt9?(*A1$b-$LfF?!_;q|Wb#_PsMu!P5IbLEB3s zr!>A?g;f4MP}0lz)}LvYvc7^`uHatqUU-pL0;l;3_xud!ARiV?{%U&UkYAIUH<1GQ0{0Le8$sI zQcpvlN@+a}^)!_7kU*~v=c*K$+{lQ)rHr6F97>89($G>;ywY3G!ZTdVe|UrRI^37M zR?35o3_QIxp}s@)e!nHspBZJvu|vf5si713xTSPJL)TlNBb@KE%loNHS3=B zJv-FbTvyGvVyuviTyDX^;d{|w$ExEDJ+0WMSiQ7mkp>fwxI)f;=Yv3U~ z3n)h_8=ncM^%ZpRS6nMkyL^VH24@jn_e*HyFS(W%P7CsAFCU-H_kICA{RP+Z!}&oz zSM%T`r@%X&!&Ry9I`DKa2YUY%P#Rns|5Z>LT)JL*{Q^*4VO5~$SJD1zpzkjP~=@-A{}3g53NApuC(M{Da^F&@)d& zPl8Xv+vNoQE{D%u35A^lHGLA83AA+%6n74-dPdGbiCdS#&Oo8(P}e_F2Fg8$x*nD@ z(DXUf_XHQg3FJ`PoBx#q=1|`U4)qD}3F`Ys@~iuj_JNCdEbtSLlJ5_ntM6v{-2=e= zp^x>JvwhGA4Pq);Nxhw;NwUiR>wgv>!oRa z;COcD>TXc#M+BN(&q!O4jtEqB2HJfI_3?qv8c$hoREq;2a3~zugusPOg!|GPmENf* zktV`3$lFaO>5WQ$Zc5J#(7bs;poDr0_2lZYh-8>Jf zdJcDt4!n>Q^A6D5v#AdYyp5Ff4p8K?13fMuH8yZiLxUGCxdXjU4x`o@E=&4d-&Sov zZL9TL)s|$0s_B&41@5jL{M&T6g>9*K0Oc+8Ueytlw~*WG7&yXCl;tz@N!1zDYG$iI zo6F}lgNG@GsvbzGDWyT6x<=C6#n9R65w##S548ATXzl@l`c^(GjXoHZ&oRoI^tif4 zMiJ`=_M>ievA&>D#Ed%D2Q<2vamb85Cg)b3R1Utv=wwDO>j@gAtO8~E4EaAJXLSdS zYNlUL{haEDDhWJ{{!jInD&L~l)FM!BA|a(wCx=khyIVpsqKCdwOYB69im8Xx)HmvH zBM4NbU7jooyjn>Nm728Z5i1J(n7&l&P@c;BjTk?Am{jtq@4K#W5R>5=JX6I7B`YO9 zhB%SKw;gjm;!Niu(6gY3^a%I}-@vvUy~{3`1MiX>_?KK(`?Zuk4ap@9f`ZBk{7p{a zb#emdlEbOT^|W70p2LaBwVJTsl{( z=@RHMsbK4uQj;#WzLc6&vvq0gv*7`jk{s6llHU(L0DeY(A9z3bIr)RM z?gH)trTP%LxHA%vd%1ca_yzgHw4DT=gaqUsTJ8nEB!7gq6TuVVZtte$9`GyjyTH4_ zHRO+S{RHp?q#=)yi+_Xny%RoV4Y-E;9;fYi@Ob#(J7~WX{D%Aq+KvN{gB!k`mOBEU z^bP#OF}(99xpFM!W2xN+e{?(e9r@pBgO{g#8~oh&1J2=EZ`xh}Ux4Rs11~cdoXfR7)Sm-;ledQ7 znFr3}T3=e91^bYdQxdvC}LlKXs_2XzKc-4=gA$J06a_uAV zW5TQGXZyL#fIzxb`og!+yrUKW8@FO z{geUAaP0}WzQ#yP9w)yaE~hM5mTUJ>z8^~Z33$UNNsZ!5p{SpP`hSvNbSdd|IE1HY zyM%Np9L3YrE+$<9A8;vBk)@>9p#7Hye2uO1B53=k;Y^gHTnK0I4EPN7%enR|cp3Qx z@C(nv;XKQ=WznzEFW}|m=fht-2R_HOD`@)#`~{BuO43i@73Al^wLA|#&wW?X`XhKH z`MGdBFMuy_?P^-rf>)8B1E2IF_#)S?p=~X=7T)k|c&L}am$-H<_3y!J$j^fJ`Um(A zu3bm#ci^?;XTq2L6Z|LF&VXBc8B}(1I=tB{pt6&dluw6Zz5|X+X^D6{+~uL4 zqNL?`awRItSd^sf4Gp~)Jkd6k_5!yiSCX<1xDPdbM(+vjyf5|bC@liFC7()*-k|p* zpHAx@;CAF&(xRX1{mJ!Dy$84l9L)^UX;Atzz*+EYdbT}{d=_oWRc6tmM{H4kZw{rC z;Xme3)+4rfBD~!^N+-gN=plCpa`6P7XNSP+?MR*p(vykM(cR&IdXV(nt4u}D%Su%A z)vc#qeKSucSB9drMNi)PWgZU|t7N4M&!NmkKi_(49tS6}C9Qp^j|F>^_l0NE%kWro zqf?HB6VRKu(J6O@KhQ(5ktxMpf)quM#slFB7l3k)#pDa%Ll(dX4x+XI9%DXylJPF* z2dT=A;9y#Y1lf`DlvJ)F8cU@rE$YJSiCWzzqc0ojvkEOn*VFH{dW6bS^pjnSdTX#I zxwa8Tcdi|<6rxsG|4^5*8ib;8jP*;ee^fOg^;vC11+AyEp0Txvi5LU= zpYO=;Sl2)Hmb^!OtmeVb=p9^tQX}Dt^t#%R`f#uTd0AS@!RHtqw1C!OU_UtmJRx$B~W?v}GI}8|u=Z>cm)AYw4Iksj9uC){+z~(E`Y0 zsQ6vM8w34+11Rmj7rE5(B5)D({`Is->&r)62WPQ2xHt9XT-!a++e$>1Q@)m~at`~F zUjxcf>_>hzyv%;!e$=B#iaz2$1Mn5Qk=@K^qe!Y>?jVY;;(j@n1IXnRqUg%N9bHMw zRq#71bpt6n(beJ57blMT19Lw`ueF2Ipj-C&6-Ql3T%`(1C zE=!(DE+dMh2A4n!$_qWq{m%uuaWS|Ueo2laf+D_!@~wfVlGli!ns0@_S`qlJv*AA? zDC-sQU@HS}c23aMIydOb-Nye~7HIB+k({VQ_dT@zozSt;^U6q+i~K-&ZJ^}83p~Pi z-1B{)jc*5~;lHI_I$mz#o4{*)L-||iX*o!#>)XKFsC^wcl&`txn?Q|U4$60~pdgYAg3))aWP!h zL;R^9Kq-!(jD855(i?$Gm)E!minAFl%}I~KQ(TD5Ltf)TXkz)U z7F>B0zVHIL`?t7q0o1cRn>6$zaFFNIPpgCG<7%!eDOpXgwc?J?0~P)-{O8-W>;zTc z2AaEVpuF3W?*RQTjozMIO1KT!28v!fS(LWl9-g8-sPsg-x)s=pZ(d0H433~9*XNP8 z57hW)puFi^IG2uKN3Kc3e+tUK&VlRc1S&llP5t9Q^M4Z0h6m~lcIMiwz!A-&Wj3_F zoU^>Z$8bGzM>9#Yp!Vgl7bhoD^jjKFKn;D60TM)E6ik%+r{$I^Jr%6Kd}S`nx;WonO-^ zQ1wM%qqrzg{)K@@D5P8jl`L)Fn7h=8dM{A(auZDgZ7&rq{r`TT{y#tmt0~_&9V+~- zXa?AXyaBw4JcIm;^!fBSCMgN|Fz^`iI|*&uLF>!cO7n~Iy7l0Ob|1?nV0W>!?iN+vO&v!FS1D$$iy{S8~T!fqGm6b-R-C>7*~=Aj-h!mks9vXVCT~ z6tFy1xo~PAmoYUylltdS$!Cz4=d54~yJI=>vuOPcO8QLlJX$BiE0!nEC!ZXj&9&O# zS>!K6&z}p`eO{oy&nK7mJ{LR}%Kaa30n+OikiP^<(_cvbD%Z{iUkQ}|MYO$0dI?JU zY`$5#`fSSbol@7L{OAktEEmB+T*Ted?KR`uNj2iN%)<+fm3)G zN?49XdiZE4VEL8>fp1wr$%siib9I-%+svnZL7=gZ1m$^lqD6{X4oA%x& zK$(m3RXcKZr$D_cO_AS{wig$}fsH2}8n^%@Dsp#n3d&I?P@YIS7;ZuSZc^a*jPs)$ zWfCn@;P3Va<@n?#l%`CfMf!FwC~q?|@H4{$KQo;2h(Jp#I~m1QB`UL^api4>k%mKq z%Hb$E*#X?1R;lq>pnTLAN;3n^Du1vecSyY}M`;yM?yF7U*4hN#OqySrN*nmMc7fAV zy0T5+6qKp7gWHp{5RLrPfs)dc4wQ{bPkKA`b-@+ftOKatCmTj>_Km9BwLkXw+eG453w0n2z;aveswG7^^D zMJAG;$nYDDuQZrE!5(k*0Sj-x7BOHpdlG?0S>C_jk{9ZE;eV-LmqUx+ zoW~tyK>O7`G`75N(dZn;=JcnjHn%G zLXYCMSWCj z@u_{aKH&9dpzKhKYb~&~4_4Br4ZfE6`u)}~g7#HfZR;;VPt^LrFouGbR{EvZ)4P`V zdRH)RhF%!7%hyMf)^~l#^)aYtCS{AR1hvBYq30AOmY$;2VRccS>8ewg^+VZcF|~TE zCrU_NUFtJK)%DcAT`y>QZ*tapTA&TQX9@E6N=`jl(9`>{fJMx3Pai~Osd|0a%e#Kx zn~{rZY3e_sHt6r{OWsCPF> zqXlLtr!%HGv%*>8oOB*IKRnNIMwg)_H_Q~Rj9Z1dqZFK99t3Oc-biec|)V%Pt(z#TZci_x(memMz zsb831&LQWVGfO=V_j`3Ls)Ozf&Z%^M4Pf3l^PFE*nOV*^=U0O;r<_U7IsJjEIpVXc z>rf@kGIyyi%qQoPYfb@os1aT%yoJGGmJJCr%UwH@UE8u6FwU~pVPf%bhE`i@Bb;iy867zF6P><(iq@#q=)oXZx3{cXk&u z_S2v3U#|bI_U>ZFzRB)iuJhSl%+-B;`&YVixr@0v8v(9l|8o6xez}WnX#aBOGG2+h z*zfl*f4%c7-M`$++{J1$i+o1sQt$A)-M^fFMg(!c(&M5};(T)cIhWk;-Rsl+%URYS zJg;-jCPLDhPAVeSF>ht1!$tcXQ)Jmh4}hD0dF?%QunT#T*mP zvvqf|inKa^I`T$Jb}{#?4q;9W3vwNuztZ_tohNcfbC$V_IrE%l#;z^d#hg*n ziq1TDF|`-ntFP?>pP15~T;F zAe~p0m|3OwuaccB-N{PtU+eB%?q<#}cP_2K(*4Uhy==f8{%CqAMvC_VQPy=Nk&ao{*= z#&wRtm`_e7O$cW|eO6qM&Xd%#oke{*IFo!9^$wg%NfXQ_&EOnMeO*tp zW^jTvi>u1$XM*aHD&+J4l zs&(v{p11?|%%`*i=y+Vfs3{MY=iY_fW7PEpp=_jI&k*N>^SN{9FqU@?V|*9ZuRP8W z^TO$&dfCe97jR0b*7k0suHoEpA!nTVT-lwKE+5nu(sR#UIrrR+dlr$pf$DQFqSPJS zgW8^9ZQPT&QIWDScRddkjkdctcXbD~GxcnA4^BlZaeW`sUg2zXFU~`q&HGW`8{C_k z=cIdak|TY&f0(WNQ`(0!Mr~j{aomTKMpuXfxwi+nFS%!s`*Kd{+ItXb|8QCQ{F?aO>)hA!Vic=M=%4a-P6%XYz zN01hSi@D#ES6f{Fjtpzpk$h?iC%9_1tD~}nlU?=Ok0$j2kD_)orM{g0R_FRLtcKM= zSIc9m9|aymek`Slb=ATf6x~> zj)N z#7X(dthb(?pN!MkDPDM6y8uutWISrJ@IE!_@4(OVH7NygXVw}!( zB_*dL>2SS1C#=rr(0V52Gig&2at6|pdfas`>1<>u+M*~|IUBjjd6ds54MuJv*K+~s zT%;vhqbN%`7kP-Q`bA;SyNK5FDW6Z9a+ULtiMYR99QKrpDP4dxMC+AHNEd+@Q&U26 z5h$N>DW##vK(tR;%5KsSY)DNlvP+P3Xp?d|X&87JwPoD16x0GmxyNP5FD~cmm6R?I zG7VeYDX!w`6<`7RRbh9&D(pqdI<7#*p>@eMq~SsCVT*PN*K+l0u!vk4$kjmxBB~#L zJ!u4}O~Vb`b1mqeb_0}Oqi`~MEvQ!cO{D9=>$y{XEL)5_yqr640JXbSH|s{Ea9ZEq zLK+ohb+%|JaVvK&2j$pqWru45N=dF@Z)+B$bV}^BZCXM7R%CJ7KdlTL)k=1*7L=QF zZ6&Rv!4+IzNofo?hU>0V(zUL@(ztSvQn}gPJLN>(x6|D|T(lOIa!Lwk=>VZ?L2jSi_X^4bWHs)vr;}> z3Pw66<-N0meupj+6_2PhN&RH`ba?9~<9-TGQ!Q;~P*5I&Iv(2DOeW z4{E`kPo5WR9hVR48AZD|?KHjwwT06*>kCl(H*K~)2eq=RjC}JmP+Pt#$Ur{@wf)md z>=RI%KrP8W2DKZk9<+n2BPag|*{a&XHISu$hy=D4c}=A5A0VZzO$ht_--vPCItcTqFZBUEH`bgzhgW63tKzmnN{hMg)Hbi6hO;Eoj1)x@s zdIr%p@^$bvbPkH*M&w0Ej$cD>pfP!)SWg*^k@>$0YQ5JaZc5%H)~c^58YnM=TJtqS z-{ha59y*%GEy$b4TJUMH`x2<9kCy0wya?(Iq!oH1FMxUsX^sBK^PrY@ZQ{1%ZICWM z7ippUEU2dvEp(p&wW@0$cOY+%eV}xVJCS!p%ePb98T>oBc63_YJ^^am z)+O#r-UYql$D^)sH}bCN9zPa!i@TF|3;M|2;~wPQ(LsI$eT$ytJ&>uaMdq6#j zXsvrUsE3h(aWVP8SkEI`;@%1BmqdH%J3u{&Xk~pncw3}>_H9V$hs63W&}Mrj=(?z- z_6kt{271}K71ZN_K6q{cT~9}%TXQq$I;#!xa!@}B`X9OpbnPC4hRcnhYr39?ZUFU< zphfWYpgVzyNg!6SA*_A`jEN`)DlUXs4GEtEPYX30lK&8 zooX3)IXm1`P>WP|LG4yA1KlIFd0h%>!>MKMrJ#GNwzijm?z`INUJPEuzN-(ai$Hg4 zJyBf(E{nV{6k4(Ljq0ZPGWPkuV6{}e6HPXkYl=A$1aJv2X-HqyHM6!2sy zCGE;j2BoNWMz`@KP#R00XD5PMdg{CF1W@`+&u)JMrQY=Ma6G6*rQRTp1Eu`*7;!8p zMW_#nV?eDp^(}EUC^e}MiK9TNOuf_{2_6BhsjrA5KvxEzv>@i3Ah+4R-3QI zptP@kAPxf$h4wuN)E9)-n0ju2%8sR;^|(MDOJ^U7?%_e8mYI5MI1rQ~*O$Wqp!B+) z9`*;dK-DM2exOvoJ|y-9(qJ(%S))$J2k__MjY~KJ(^*TBYiva4skhsn^0e zpj@Ti3}=J->CwyKEN~`VsD2S7ZQhMe)Vt7sc|xdU4nm)Us5M z5!-=kpp!TJDr`QUV1HT;o%&DMUy1p*91og|KXT&L>eEyYay-o(@ z|F1$bb`q$^AN?Rs1U)a%1L6eGGX*`8j0g4UqwkV&pl1-*qsO}i=m~{BP{x8|IIqx0 z${0|(Q2&CXL8;H>XzD_(#?q|%JQ)c}1KonI>j-c-dax_N5#&WGLvV z*lp;m4guvEZbzqeFepuS2b!*fKxwr*(QhpV2g0A|HDn;@xzye0vis+oLxqm8ox!UZ6CnK0JDY(x!Ud=mAQz>KmgwC@rfe z!){>L=&@J})o$dTcR_4%CJ=?w0p;zTse7`ZY_St44K0<|5tOP{UeN*cG{p1S_MoR% zsk|a974(ERm8nSawSn&QB*>HE)}W_Io+GycJ&p3*xh1HSMX5y#P)UqZi{_vwU!HR} z13ev6irW-auA|hV3Fyhbr|FHsM&#AO#^gohp4NLNUV~H}`nix&P4XI0*9DYnk=KOU zZb+#%c`bOn29)ZM*M>f?PsvmMI?P+&m(~&U!TFSXhhI~byb3+koB!T7{0=1uRq0EA ziBf}V^l?AR{ll+mL0*F=^moYBi2jZp7-?!RwWO?dLTy$AHJ?@8%F14f4LPYFXqMvU)Od6UwL&Xl``cdoptkkMv8s4r2(SnNi* zd*~lEB^onQ?L8$YO&HBR1KPLEsHs8Ki_!w#bpkpr7x3<5FvB{rfc0TK=n3V*Fj5zW zF}jeJ3@y2=F$-B+CW7jx?Hoq!&SAXnOiL~;YN_qa8Z`w}munZsZaL7gtG-=Xa4PvO ztZ!36b;5QHquFz_@|35M@5-t;4fH&6H_+X}QNCLk-|FGzQC81vH`dr~LG6S*TdN2< z)_14P)3WL0+6heuJ&*LvtrF-Q*n`v?oJrdrtnK=1Q(JBk>(xAPHg!+odV^|kEMk2d z0rn%k&mEM9UMtMoKiJ# z1o<#ZRl(upLn&1OhmjAVR2dvfKA2J^a0vMzN)^Guw*OAubqT|#VCOSf$Rib0HIeD`%t6aOrBSzF=Q!ld1P%M0zqkC7d)&VIK6R+?%#3wDx4A zdXB#(T7GRwDVOo;3H?-B63`WYDybXjt}vC9VKm3AYg=*E9egUat(ddw zI7ZCot-{P!=TScro}f&lTnIMetxOBEd|H^_)2Qo%!aYMhGwqm?@Lm(jskT{p{-08d zoX`VV%`-fi;tea!apf(fm-|y5K=MpwKtRt}im8c?aM#9E0$nexouVV$^;L9)4-F&Q)wd4g z&=KvLU7PXgh<4u8V%$2eoqvvT$F;Mt24li;?P*JO#)RWq>1Z`ZhU40upeiH9aqS*Z zg^}jCcHOVcNON2}`i%C`hO(ot0%Od#=W1SoG3K~-+<6Y>SW9KL>bj}%mg>4W)?BsA z(VLERSM9R&t7FZzy9^^lAAVg)j-y88|XJHMuYu8C{rM1YVR}3|^d^3!cl>vy)RP zot2yoo|&8l9+#X6o}3&9o|K#no|v2jUXm2^|1RNwU7FaRmw@)C@mllJmiHk_*7o_~htlAHHjJR41tm)=jE|`|{1Bqw2{%$qC$bY*IU^ zLu-BV(b3;%IU#A3)Tewr<-aA1dDIKok$wA=$$-&?eTrY@@OpX8-Cr5(E^SxvE4%hi6Ne9ZUk|tn>q$Aid>69GE zT?Zw5fCqvH^0xLMElOG@t+-=v+V@CWP#Y8d7`FiTqGj(SPJWEXMAec#dB$p_>PbY~ znCMrCficmV_*bshOKR}M^+@%TLO!=AxF>fPMm4!o7}ZK@g4L2*V7;UOEZ{C^Kt3}T zTeTnJvC$7$gN^0;+_UnN?Un)7jbW6%FU9dVDqFI z*f?npHci%YwH@D4#Q$jr7LsqlH@VMtNy<|0k@N(6CcVI3NtdKg(u2~^eD0UHnA#T6 zPn3Vg+U+Oa*;kZ*0)OSH2PVZ_9gqwJ2PXr-k;z~%kGGJY`3PKGDr zqT$I1aC|ZWoREx8%J8`)8JCQwK8bu>luJvQWLiQk%AuT_bmnQhfH~w_ab;XIm3&;Z zO)?dnm23m{=Gprsy_2rwjiauV+$VCtZnQOyx+mSh&PjK$f6@=^o%9ED_}=l+jASM_ zGnobMl*|F=Bs0KSd~;v!>X!`SEe!_yk`JP#Z?a>u6L$=wJSf?L8uTdn_-H6C!;;;T z1(Zke%%hW0$q@40Xd55xN6I?*5egy?Oo3@1b%Vg)!Mnw@OR8<O`~o3eA8$ycQ=i;Nu3%H@AMy4+j*BvlxLTMg z0;^{V!Md61;3vG1x3IGO1gw*(OUr6(Kwrn&@pYa|$;U_FE7Y5D?`xnoqRk?$K$}I{ zd^U@;L2MRjq1cSOKZ_?tb@-l1QGTX&W>QooQx&Y5$p>p^>SW&IuGMknOcm;xOl9z0 zTHcGxXEK!Eq5N*#IP(tnevNs;CYf@X^0b#FpA`L=lm+9=kIAH{DbHR%Q!mpLY)-8n z*o@CNCpD&AkZB0k%M{qoUCpEBnPwo@GLxe<$*;-e=!awt_$v(4WK0rbFy{Lka96`j z1Kv{gOf||4zy_4RPk!L;TC`Nle3yJr`Qzj}uqG|FGG8ViQ?9`?=V$UVHNY>DFKPKa z`2xHn`5a6#6?o!=l*z!sQ-Z(cZZs-0Wx$GDZxL0>R0Q)fmB5;Olk`u`%oM)Elc5Ka zdy*;9J;}Y`y~%yxeaRh3E_ap5JeE8_J%@5`W^IBdCYX~c3zp@bJ(@hm)n8~|n><2o zN^~{(l<3CfYVarC$eQG<$xK3G%7YwX|H9Jexd0`5MaCCfD$6%afbP zmnY9~Woq;^`P8UQ=4r4~rcGvQ^a{`ZYVt~QGkNRi_2f11mE?7>72ndDbQ5?B*IP%o zCbxh$CAWe%^BHWeG95EpMIAGpz+RayU?;v49wpNuvx>W3OICxcz*W4h)ugwRo|#_U z_a5!5lOCC#l>20QfbY`sUQ(RtL;1Pn9iH(y((}o{OffA3G6TWEnE~MA$qPL3#1ZyW;FFDDgQlbop~~O8f-(oHSeuWW_)G>SKHIlIx~*iv}h9fv}jsp64*J@ zmS^uw;%#K6(K6LM>diCu$@I>2B}XfYyV~*{1 z?8+yjXhvoxI5RT~oR!%IoXR&x(KeZ>ne8((sQ2UE{+W5yqNp$Bewjg;zPz(Rq`_cY zTIX^-ie{5XoN~_w&ko)WMrDTZ21b!aXFSKon|5XlPd1S>DI@1H2pq~??V@3sq2Qp* zFmMcaw2OxD$#&6LKG81PA~O~omDwVrcW3?2>6t*E5&DPr{5|H}{kV8b?wXkKd_G2A zp!bL=v}~C<25AC5`6y4xY@M0R(``-KCZlvfZwq>tH~lgmS^8SvqNTEusxsK z8r+VW9M)uTdS*Lt>&$d;TkdNg?UdOO+#$15CgD3gv)T^{OcG=rNsw~rq3)1)4tMRC zIfb{RkBB*$*_7Kyb29rPXGu8!Z;#AiALK8bd66eb2inuRJMtnT1RzH^Gd`Ad91@`2 zY1x%LK{B-~xR~c%f&@h$8XfrDY2fkHJ8XEGj(u}`>$0Fs(@ExA8 zZG#jm6XaL;=0|dcpLOJ5M{w7X$jP>$emLbLkOOs~v_Ef5-xi0H&*XXr`A!F9Ldw_B zaVO_2896WBNRbd7f^_N--iZ=h&XmbB$f5S($>t-US`f>n9t`eDy(5ybUBCnROh+VC zdxCo-x$4L_?G5TVqa$}86z2qKZBCHW<{+ExLQ4m}IR|-f2V~?usPD|ZyTpyC zNPRYMY!0}PoX9e?7I7V~C*(Oux(mTpaT9QB-pDq{9p{oO%SMAAY2yqe*)w>uPDmPC zgW9`yLb|vexOI%zHl%`hHb5STA84eAc!7rRo(<0ByRaPKdvc@E$joz*o$6D50`l10 zAUSW(U9FL}j;B6}oO5M!WJ-Y($Zw=0?THrgPB^ z=*rXABh`=P^xJ~nXzPrWyBpXU={M2(xTCYzzyfp!I`g@LxJ-~ymx%@88ies(^?meh%!i=Tkxc# z&?snumP1`yYLjDIi2g$vv?dJXxYbEFzvB(?XIg$iXXJUxKT-Y}U7MeHy01uU&>wl3cJ)Zg zqp$G~@LBTm=*xV~(|<(znDeHexZ5+RpTMta?T-Gw34)Q#-Z@SZZ zAGJKRZ{FugUm<@L&5rwMQNtq-O^SQKRXnf06IOvexaSq{IW%E&Jx+Qe z=;Gz07t@2fdK>xCrR4c&TU-k26Ypv8Y2LvVwB@61aRvAw z2f?1`&^!t19j_;) z`@tU6dUEx4@OHFTkUCOB>PX&`J06ZI@J-6|&Lyu9^dl>vb#XD}i)mXxO9eDsdh*%b zsZ~J3r6={9cw_o@>q-44(mg=}QX$AtDj=)al{@z%uYl&r3ZDBaG*?z2?ca}GTH|hf>)xG zP#GN=wUyO8J~e0;R7TU_3fk2rRv-K{P>H|^pc>zOx&IVU{pY@1-5=CnUSBkFP6O3R z?#mr#L{-o!xFN0*bPB4VM{qUeWqflLbQ6}LPjEf;gShu#bO4r9K9I7$Fw_TMOc|{e z(vqMvP$g1}pbA<6E5Q5E7N~;O%u&3XbK=9ndy)HBLBHZWp6n9RrExzrHO>R|-qa7x zjtf9_$orv%a|F1UT`$u_{AxjK;&${Z`ct|eU5k6bdw9~vc_Mvg zJxD$PJ&QX*J$Ma358@&4e)J;-M33XIYXBM<_k#~|xALI7@YOXSdI~RH1ERmj&+(-C zuziyJIa;2?*V=&SxwtmJQ(62Acv7n$WI#$l>mn&iwF6$@j{10Qdx5Jj;iFAi`AcyN z_@{r}7E~Hb9&KG;2F7DfeHkd3bl+8?lLw|A4cs%NpS4wU6_(o6R!wW#_4zVTqAVSv zM}w}E|4Ls5sTTwF7#umZc}Hqh=)FK||J0*_R$c4!WuR`xpdgzYOx_SVkD3SCfEI#T zi_okU=rGQo)p^!_O?lk9z6>^G3%a@bOU-AkcGZB9Pt0mRtNE-43iY1X^*v#)*;D$y zx8KtK(t6ikORaWY{j)t~ui0Pg`kqi%y$U<@Z*6zgRX5hJwsWO@PiT>+ZTxR-ceTz- zy*AXQSAO4L8|!<*9!q6!CHH1%hh?X{qBK!4eHrF~CqN`J|_dOD}a5G}S- z4RyUDr2Y@!MrqT^y0ooz+F$Yv>ziNc%yO1x<)2emSGo=PP75eWsTX{akFwS4h_GzN!Cx4dwW1U+8T?IlkH-+H)w!SMQ=GJ(F6c>bFHd6R9nT)*-2#h}NfC zj%YvP9CVJRmL=Mnq?RU*0j)@#+uGr4L98{3qs28K^?aZV-*vk~SQE4ib?tCf*Wy#V zPuGytZ-I7@<-%T(>f5Cr3q+;)`WZ+)6KMCDT77E$shxCcA)16eDzzdlk>fX~HHZC6 zA0m1(Dnnf#NJhYe52mC(M_GP_S{{B!`Tytc_wD$OTw6TnQzL>S&+umS-}+tijZ zE~DS(H&y)q-EVPj>X$)EGW9X!%+(``K2lP@Lel)sYpIJN+}RV9x=ei!NjcYL1*t*n zVCHb@A*FtxN%WoM3OtB3m^s;>^`kRMZIWuV7Bj1>g|*#v#x;B(sW|M*`bLpT8Ndv$ z0#@N#H|hmoSMpI|FBrwu0jv)0fUf_>-mJtm*Z)HLs}l8!q!FxnJ!okI7SWp(X{kVR zoptYOL@J`k-7}^0Tsx&W8k3O6(>fH)CvU=9(GG0KHTSTgpc0t!lv*>!q(>r>eu&h} zjl(V%)1G=DGM0}!YT2-(CV@^-E7&!lEbV1TdLU}bl~iL`%2kijO{qIKEGuhG{Y@7Y zr9PwnJ)ax)W$Jk&^|q0E-jIqc?Kx`wKBMfzjq|x-Po|!uHso_7-I+?fZMd3Cy={um z4ST>oEb+YIj%e@MGwzfn-ZoNi0D7{qSMAUC^aL_suo?H+hp8VMS0sBzenCpqQR9lA zrI75s63-i@y+yfCxM!qZZd!$X&|T3v_pka$`SbotJ*Bvp+H20F)Kg08-D`98*XHn% zvZ4O6N7n5%=^Xp0#IIM{Q%(P?r&1pd+5Y-%Pi6gjrJlZi-(RVxFMG=VN5|Tg&B?Jl}2?Rj3eYOWsLXYWLK~EN$@LV~s)1ceqv2yR+ z9y%Q#miy&&s9q&k%?{8RWMR5?Wg_*JeptJBh$)mHNv+>}iJOJn%e0uI}bD;XA zT!}kE=i;AIubT_i_oTM46I2hBG1WUm=i!Gkrg|Q9KHe&0s^>!&kcH{$TL4{17N+ZP zA#@kKHB*sNyFhovYhxzKu24NMW|%C3>VGlwWHEFJS(w%rSpwY+?~TZLH|WyJZWR&r zQs^@LTq5md(B1LNh`@J;F2~n13%R}=sy9c(z5=RGMk7Wq+u3!_5>r z0BWsp^_taC>w_E5ejrr;nR?JcP`gyA9~}%m1W%WG(;-mnRjW@O3bhlK5%h;a?S!S~ z^*QL_cofyh4u@KYTTSfIpSQ^%$si#ElPK1GQU~ zv6gG0>ndxBx7?32y%HQOaD>;$NORim-iLr=uJ zYDU?K(39}e8c%c*^klLyjnFw6YR!7%Tuy=NZ#JUjRH$|8jomm6dV1xwl;L(d)ZP+i zzMTQJ!-N@eXF}~WVW!+!P7xsGe~%4=;gUN(QDGiI+kz!vk-o;$_gwE0=4YgCA`6kyu?NDJx<+af3hy*ax(tJxh<(YwL{-r(J%*?z2dLt1C z`dV&;+5t{)&X=IZB$(lO6V%8AGe2*J+HKB^&|9E(1Tj)lYhUzh=V57fRF zX2yOMss&%)hF%W)Ug+WY8dU4O8MgO9wc(q2dq31J4QAv%0DTZkznQuZLLb7jVFvF* z(1-DOnA!U<^bu_P`gLJi;`6kp(BlzY z!U_ey3DsL+<$~XW+8xk}2EPrpXN;8&eh2!y_-L$v@Vij^saP4|_n^kg>KXris1dVz z%>Mvt+^iKA{t#-96Du$L5!B8lR%G}-)NUo#X!rs2hm{|s3JyPn{;2Z9RN3K2&_AyH zsG`sQkD>M>(R2SNPvP=_Q$Yt#GgU!p0kubm6)64^Y7Y=A zQ~VXwJ|RXL{590RBE}y44b+HVD_s07)VN-pv9iWLLjQ>fdm|tI32IjwV(U2h{ulV=Vp?YIhtXI{pj#V`BWRF!E#Qe^-87vGT}&Lw`b+ zffY%90&QykNySPfP0fGP1oUmTf=LD1Om>BpO`4(Ii03zkq#Lw_n17>6TAhFY1iy7vdO~{%m;&_3iqSf8a2)a(M|UHU@%kz--h zOFw9TG7GHp(jRJmf%RVoKnId#U|pDj&_U!PSTAM}bTC;L){z+u9YQvS6=jA%hmr$g zWX@3NFf&Jp)fomgE2Ki?%5bQ;ACaUU z&fST#>Bm)1&OL~@>C06w&OM15>cf>fh`PxTs5;1)=E>+FW16>tqCKIB7!^MZswScx zd^l81WFiQ81hf@80jfr_HB>ve8p&2rvscte#zVD$tC5U@Y5`Xx0imOdjOCiqq>GGk z1Z=M^GMW+dnAJr_F=Fk0b&-*bSi!%Qs}V^f84lGBJ`s&%7*spB8VNcc_e0S{CZTg| z!@Zh_8i|@nXe5KsN3?^hkqm^I&!$E)06Gw@XIrlNC%vQ}v_CqLdP!fXR&e!_K2WXT z>Lpk-xTm5odI`2~?(u-4m*B189zQ60Ne^gG^fmPo^3%C*NqPx+>)dxsdWkWJYNYBV zs0p?0z_Bl{(-A_#!pH*3fcXj^b?bg0+t88ujkrq zY&De=pzF~B)Krd#o`80srg9wA9Bwt0W1&XqsHv=j9*dTtrm_~g4(&rtWewCkay1q8 z6f?_1Q&C5uS0$r#v_watpC$K4B^`xsnB3D16CH(Km}ou33ZbLW4U_xBla4|+Ozyu3 z{Tx(Hh3bpo@QahCLKF`77bQ&v6c28{Flj0mBprq7jG+22BprnsjiCJvNk`eh$QRHT z)KSi7WCMDHI?8#BoR5B?j&d#|=b?98!PPlQQ#l)Y4qAztih7DU^J*&UE9TX!sn8>b z`!kcKLI)l0&q$gI9e2=oPEVT3Y0%TrlGIdAg<4NjP36nbQ$gcuD%42io(hR*Dnt-* ze{<4QK=IxuO@-Jb@cfsOrg9_HZlh`{H$aVVQd7AeY9&WCmFuAP`cYH4Ht8tWa(x|o zhdRnNj9iO8qKTwC>0P2~~jC7^LN6>1xD|4`CY9!fe2-EJ8L#e>@)Oq$9ANk^d$BB=iU zq@z#=5ww3_(oybX`1GQawj8Jj#NjvgAprAs-xV_$Q|fM>L|A{Vg*Wdlv^3O4IKU= zSJWp2fm5FleT9mJXe!^}`jsZ|JDSSNjBuYcm6sf8qJAL=|HY)Qya2UdjQYy+P`k#c zuRI5}x0L$Ivryv>)mNT@8i}aB@-){JI?7{=JdWP<9#MOqoH5yla<#(ZWQBz;}9Vs|pedV{Ic2iSdp;sFB zzm@cr--OylS$*X zub{L1A0lPdRKADK@+)XMYAV0X$oJ5I)Kq?nkzYnL`g5*+G3hJch1xqzedX_=-vx)O zulybK@4@P1A41hy=#PiK@;6YflD_iSQgFWd3Q^D?{J%>2%3nh5$EUvX7f^flsjvJw z)b4)jD}M&H1EBiKpF-^?uDSAGEfA^MK` z%J-9|@_nvlH2j+zRUA{qV1q^bNP zBmabEq^3fpNc13TL~_-=qQ26-G60RKh3oF<69b#AQK|0IgX?Z+4C*dD8R?WJpigl zWDqp2CO2<`w`4LJ%4n{ds24B>ihjZbj3bA>!U&I-Z1-`^&5Rh;uvPQ;=5CDW)7hFF z`j)0vvfo=6H$r4Wb8B;VMvN1g*gT=R2P4LbOlqFkOa?~tBTh{>b@fx8G#O^?mLQ+k?2;grO}LxLg!NV9m9z6p{}U0jG%+1wKR^Av1o1TzT+7g zhc@Sm+KQ3!XnE?sTQjm1+Mg?`6*({f+Mm%0Ng7OGq_t@x*ZNSD29u!rP?QPVK=q+S z*7DzSAGym@kO}%wv|&tz>O)Z`YzwtE%|CFpU6Ksbpn6Y~4BJEXo+ufnL-n308Fql` zJy9~ufa*O_GR%bPJ<*ae3##`-$uJwL_e9AsCrO4mT+c=qP%`X@JpWJVfAHGeB-Q6K zVh;tS`c90@MZZw0@65EbYGISMs9m7?P?YVv zLiM32+ZRFgp=gU*4AqD7Lu^q?p!!gh@Vi0vp=gU*3e|_AEovE5ABqxwcc?xTCH!)z zJ`^SV3aCC5ZBZ+s`cU3Ow(kMehoVh!&$LJH$@L!S7w*xk7_l3od-Pt6tU@2rnz%P3 zd!eVeNAJVP-c9?aJ$he8_Cc?4kKT`weVg`Ad-VQ{?1u*A9(@2K)L2M+^lC;9Kx5LH zcpxLI(WJB{9>mCjO$T$W4@H~eAy9oN?$L)r^`W>&lO@dkVQG*498@2QHpRoC`cPh| z{3iN=i0cTh4@ZM|k*gyU);cO-t)sX;5{*Nwbu=SKp^s=4K8BH_o7Nk*tL|G>=ayOPl4^`xl#TmjXSqL=1M zsGbzPG*>09=PItRL}yX!xtfuy&}DAr>YAkcTnp8cl64CX0LzdCPu!57N+iVGb89=N%y&hk(<%l)P26p$Svps8!BI` z+{%bOUpH`dThe52hw4dDhrI);Cq-}Dolrd~dfUDN)sv#P?JlS_UiG%!4b_vPx9y&! z!`{R7-RL;#uwP~59&{gd*n1hVF1en#$VdVp&^DeABf zLiMDm!#)JnlcKlnVW^%Iy={*`^`z)+dlafC<@n0==mf`e|5&n1JPy^9qFv$%sGbzP zreBBZNzrTiBvenz$(57PMNa1asbq_I8mcEnTf{R^Jt^8Eo`vd3(H8MsvO+w^^|R`1R+Q#v1Q;Cx13Pu8T@8Gj88LXYOMduJxp7U-~FnmOkS8Lo_&TN*`khJPvv+uYEV! z2EWV5$7l-L27i%}@1jR6#Wwg$jQk?{#j?s$^ogb1f3Iox$};qfW!(QtvJL(UBi}<$ zSy5SzUP2dp^p_P}{c6+7$_g}?m1r)%)})2-*P;4Tv=IIVRDX&V!rz4IPtij7TTuNe zS_pp|sy{^w;qPDx+y}Z3qrc0w{uC{QzX$zYbTlo5zn^S_zt70;p~20s9Dw$A0HgLo zpN}>$pZh;bc2v8h{~?|fqddOP$RD9uXh;14Bi~2k(2n{;Mt*=MvNKlMA7PbU1YN}F zA7i=Q869P3?*9bq?p$=2xkQ@$3FCi^b~A@)ls{$sPtba1V-5Z@M*b9SXco~cf6mCC zp(V}0lKdA~l4n6@G5VK`=waCbYx7@0^{`CG3jNnmJuKT}o&FoB9+qiXt^XFPhhh^eA)Yd9PD#TlH`~>}O2v?QLV9w1@JuhZs4}|J@83Oc71;HpI?Dy0^PJ--^H_c)pV;g|EHhdmagBQ@6Y?~ zm7TGRI+NA%&)1!yM*QFP`L5^JwSKzz=VwWNh*ARGE46;M<(Cpygw+VYwncwUZSZH; z=ewR?*ZS$=pDy`P-+oe0eojr8*Ln_3>aw*r7wuFPIH-=Kw< zopP-!Em7tt*tyT_b@LXAT5?hA%9?VyLYYxmxr&@oSXL^E8W&c)YE+xdymjlISfR`+ zNb@)bL#vYA~|Px^?}VCh$ts?pndBG5X7Dg#CCr*7veji8ZWdGHTY7wP}olBD05AtY~7L z2P4+3da@1FZsk_HGULa1Gp#w3S*=m|%E+{+dDYD5l!Tuqv#zHx+5;|-AB=MoSxtc( zwqulv+nluy(LaJ~ZLZc3*fRdo#v5D~oV5e@a#`jttNvLX!h9jSa2e~^xmt2^+gzS( zd$s@MEV*nTYocxKzk2)?oF$jZU&B~yR)@%(C6`&9aTGKv%2_2X*J|u+?LRwhjZd64 zj+GL%8grFKxlI0AnK*3aMlNe*jqJf#=W74CCat~W-*K(RYP9S9a>iZN!PQn6G)~h0 zH32S&Dw2LTD<-+VthE#U-{hTfY28(z*4;5ruZiD2mUm1}Qr9|075LHGa&qO^wC-GI zlUZeQuAC}YMpdM!LM6X1N-Hg@6SgGD;1l;bD=T(MD^r=REO!nk{rqiC8#sHAaRQQR^<(=fy`sIxhkVxoRY&@I<6EY@4Up7)~#`EMtwP@ z^G=C#SI6%UKJyv+jC_VstuW1b3Tk9md~u6WCU@{dhB3U z!jjL7Ahsr|tHcQ6SX6 z(aelB4%b>;a~O5~xudyT?G80A*Y%lqG54+5vwS{E5LZZlR(#&Gd{*vfuA+WCn_|x@ z?`7rPs=SveMU)!uO%>$GHizT2$k>qGDAb5${6DGStortMnIKbeK|%!jkoX1RiCET)|KfQuS)Z@ zin*Fdl(WcbFOEq>IXh4EBxH;pf;=s=FX?&4c^l%J&A+5K9b@~ar@23K*2;Ag=l!|b zn^@=lc$H3Td}4Ka_N)2yHpDtxY34v)*@swXttbpy_aBpH-ptMIn%44}BcVre zUdOwRfVvviaU2ajf>(~^^&_E2@(HWfZwGay9MAn4=&_tnNUP`s-o2LVb(~M&>R4!Z z?#w*3)_V`mC-R9kP^-b8#4!!(syvxB(gWIq_npkUkB6@3dzv)X6~yBuM$WhJS+Zjpx6;imjDMMftXYnmiPgTD&)&*$6H(eX z@z-ukd&BKX>fg@0ZYE-TAm=;SG3G&U<9sKt-VXKi=7io%#I~RR3imfb@8o<}+Kukw z6Z44MzKydPrnfcSllGZ=_zQP(ZLIfK(|-0J^iEw0`mmsPy;7RT#Qqs!k; zsN-$kv5a`}x4{|T=DlwcBmPa!@35DShK}al?{IvRc=0!R*SoyyO{g*E@3AwI8&( z{mYd(zwbgtSRZjkjxSdq5NrM+@A;TJ++hqdM!K zm2NCfZ)IM@@8Wc+_`Q+sNv+jdeCnjDIJN^3txDAWe{WF76sSGOMOf3oH}2%(tZCpM z5munBjI-3x#97-yr}D{aoV72X4Qv%St1-e7)0PodV6L_}YkQE87=d~qC4|*2AuKU) z##th)KwF0=1R>6v4)Q7EERljZYX^{x2rJOm(FrS61ie z;;i+2>Xd|ZGS2E%g|lXXgv1nqurk^bRf)4^Lq!>)Epe8pry6JVPB`my-t+l{EW}xJ zz&!=d5<#5>Iuh@k!y(QJ%oS+sY+e;x?FiNpbBVCdf{L3qBwVwB&$h)`A{09@wMAR! zC!8cg5ohhV5mjZJW%s6w6E?XRY$C!6v{j3<#3SOYxlqxQIBO@U`sQT`o7nj%oQCqE~ZV1{HI)#aZ(}GS~9i>k|6NI4cmA`fbKpgA&3L zTLsR#F`hp}{EV=MCbZQEXNgwCSqninWt=6ZxF_KS@shO%MO*hU zdMDWEE)GPW9b#6WlUDETk)(T%B%A4p$=SXT zeWA)o>t);PK^s?(qzm;(dP~HR=vg+3BrHVgCoPHlTN2l{BsAZWIFDM_oLdrNrp`6z zmb4OE`20Ao2lF>txEcf1E7{sQB7Lu(e9E39BlxD>q49mFi@0DPL1S<&-drQXqnPR?EmY-wZBA5S1+!#k@*Y!W!mEX*8V1KYks>C zd{6CZUN>{ykMU-xHl_Z&vm3M<_XGHB3$%s%f&4X}Nq6oCrI{VXh&3sk=fND>$h2Av z;jkt}Z?2qiZEwA~x6_B;!1?z-*z3dj_pfX7a~1g4opGPHf8FXE?kN6sSCr4&zph13 zTde=X-%WLNsQ)w1f#247^%?jLW5#1V;=L|`5a>g{btUGbK|qtd*BTDZJd>2 z-knQl)b}|{?g%maS{!4JHgA^m9L9Xc+&c3y*RCwrYVG{`%bej6d@s+=Y*Tv5%}{6B zr`!$dJouDbpw5O*xjWR^@F~lW&W2B!&afOYv%UC*&PI8D{kwT)on?I>TQa{fv(7RV zRW{Bnl}^%3yQ2M-{tBOx^ICt#tLN7h?^7$dvhCc(ygPrxcm~eCTsV|xP|Ut_KZIY{ z`DYuv6HnNux~aS~GW{?4-#L|QeZD?rIa^MO&O1t1SBrgf>^k7;>&ItCLX}z7mT%=u zUk>N7+6o@e$MvhVybot*w%}iR*8l4NmuKzOBPVBBE+@;g1EF%VJUa*~C(E;gp>nc3 zTW@}YAC*|nUuWmq*;Udyr*dq}w9-+Ve(+|@Y|LrQqx@`_E9Gv?zOz1%ztQ>m-BR8e z!M7XEw|AcN^RD$&v^QU!TNSYqlpwJlTqDkiE9KMX-}dBl%x}!p=FM`RU;m4|>b%Ar z$A0LH*PCBwR>^M9vY(gv4NsIF*m|?92 z3s>WK0^OnAxfVH%Q}2p}+Waw@iOgb1AeKHL#dh=W-NxM!O8-%3p4@ z!Eor<^!vv_$MTzv&#G|v9fxz*%yXm~A4i4nHjpRUjS(^V0ItN6U`Z&v3O zn~BrNthz&$_^zeF{JqV?;h|w|8cqv2uz3<7Yihycfz@0mox^;E z2LIEP^GZ5Vn3~cMsM?To=W`gyIvBvczh@wGJb-&=Y9QP&fO}_0lsSNV=So~GI<9aG zfCk2wYn<1CJO^JB*{hp*FV>g-^l*6RXEv}`tcScGJEt+bG1no-V}7+$^yasy#f2Rv zbh&Je2~AzCt{#sEcl(J?SBEt!sNcpJjJbWzM;)LOG$u>9d>Pu#;qMTFuB69eQqg=Z@J4ycM$(I6G!1uvb{jV&2Pk zmGT-08%x-yTnYZ#u&=oPYc2B^ch>f$oD?l79gXA)JwC57XQ~f;<==Ov+--fP&XoVn zduK|0()+NS_{}4eYjf;iVFBATJ4tzdGY)qaJ_|coBmQlSq{B8To{lvTvtORU%%SpT zdERSzJZ67W`IkYV2%X}U3I`~&i zAO|bwH+TPa=iO90r;)9ZnUQ-3mwO85sBQB%BCa|*3mdg-G^_a<#MBQca0fCVobOzEh1j+ zgA!4^#`x<0F*|1hV=K~c%~>oy732AhbN07JUwET=jQ7{eVzl#0p0!WfIEkERvV{8_ zg@_Sql5osOyL)tNopEi;p zGKZAKUK@4oGw~N{<R% z2{m@F7vI$tB**9-yN!{%xa$e+$$RCnyP)^rOWv8Qd+UflUy8{2Or-$QtZ7jX3u9%keD7V@tC z(64efXX9R|KI;K^R{P_TeTpl)MGU~#`Xba^0FlGhjVoo_QBZrq3?rK5Xy_4~hrv0!F+QBTVMNIc<@Gg; z*)x49SIdZSSqrsVv;AU*LzgjPHqMdIBN-V<^vVdLT#o0;*q4z+!K{bct9?Y0X2ao< zV;MP-yAjY4yw~nICqb>#tYkBScm*TJ@y=23^a`$4a+p7H8r)|Omodb+oDMyO^B8#D z2zRBNy7?)LoXNe>#d~nxlh~BApl5P6%IZv_UG`*T73Wi+r|=mgu1-akoQt$L4?3Pm zlk=cwbGF0#D&DgfhdCK%GqQoZanNzRcWkHN~m45~*?t*AqCmrZ}ywpk_W@%5gDtU(WjxEpi$3QqKD^aw(B8`!TXV z=L?}mjP1{r(enE-Hi-z9iNu*)#nm;OClT9n4fFtBpNRasg6nI!x(a##=hZ}dp4ch{`wXOZP&K?8Ivi zB7Drg?c^=e?&|iTn(~LL1Ey*w?)jZyDKWC$c?_)INo1HrQB3tKH zq9Wy+^{WRXM;0U7)+Fh*7P7_l=>h&ixc2bJXJ0eLhsq#(q zWklX`s2zJpBybvv zG-cSaNnU*(`Lze{vtzFoGv%8y%8Uo4+y?HD&LILYekCe%WKyriFG08OOPo0aaPt{1igs& zD6j0TyFc`5Ub_%!bakRiGv$?83I{;#*lRA4lFd%OlaL|@@Y*d&VqL-c8YIeU&dRqd zp;z)A<(0j44}@Ab{tBegO^GValvGB^9R#&wuQ@DR(3E zMqX8FnayKY1f|pA;Gx5KXE%-;kW5N5bG>c=Ek$;hmJH)})UwU-?*=;3m*Ge^W^^pn z{iPd+xXRUF%#JwA71NzVPnK(|2Zz>8HJzRuA}e=T^;3P9uI%0%;Y}Wf$@ox&k@5sd-%yZ)|qgjr@gcphh1@c30!PE_1W$Wp|m^m1B?F zW_Kx1t24T8L%QAs;?b6xV~@@2iU{PK-DL)G;~XzLc^GLtA2e2uG}b;;WOUui^{wEi zEz9c?H`UATx}WigJ>InJuFmCkJ;vXD1cXyByQ|3SYA>VfY2>}RT*esZcw_Ur>Sc75 zAwwyDQ?2JCo5Bxm?S;6l2OOyc;n7wcjde;bG#zn*o>~o?lNzy zy{O}eH;%ln&S!L)0cKv;8=u4&x6SJ^OUqoWBD<@8UROEZ*o>~o@haza`Bx<8rde zIit&5u82CO|07YxW^U2Vk*mhpU0r!yZEK!%<#m-VCtUG z$e-^_Mprp=K61H?)5zIfIe)&$>ni8ZmovJ|@yc2BW^3ild2_R>Grbz+cxf@qd0qBL zj_j_SKOZ=&ZC+Q-=n_wD01>s9*Hw$N%6VOZt<30(%z1OT%$(P@oU^+wVx&5MJ~Fzr zXgAL2iY)qi`SWe_x@z<1MI~2rWVBVz>oR-GO!+IZ!&GN?UBlQ7U=Oq9#UPO_A30u; z#g+5A%4o~n_u?J6?5B9}h0=k~k}nmpNV;XGIoQ zATMhu0>oT5BZ<)~|{gQ^$FUf;G-05#KrogzgerTx?`)!stA>>O_AfSwJCDkttHf66`{y(Z@+$!pO3uu>iR(i z{>k-&0{KM!pr|F(`6@zzf2<-@jep9OgF3b|WeZbSn?yLBt0I)^2c6%6g{f>?+LZc1 zTI;pU>oIIpODJqkm-8O&Ox6-olI1Ew?c13eRSv4I8Ki|t{1dtC=CEJ45&u+I5&9D2 z)%Al43zKz&tQnN;OkV=2v|l+WY)jS{sbT{wJ^@E~vP#O7@Guqp)9~6~?qKZ&w>IYf<=hLYo)V6X^)C>|4WeZbS zo1$`%7OIZyOkrUPYg2)L+UB(vm4mDq6gloMr@b&&4zk`*WVefW3Om!wTsNv8lq&~? zZ7Hx&xpGk1!ej(dVQ1P6EK^27QAMbn*IrZ++LZc1WeZa+{xN6$T`W#-rtJ3m^@E~j zP+?)pIquoQq@BrHLLDKWauuPlHi=BK&B;1J8S|8D30Xy`%g)qgXX>gSbmS)p%gDY@ zuYS-8L_P$nS`YT_xN=b0&Q!KAbzDEFx^hq%XX#zr-1NI9+Q~mlu+0JBD z#z-p6yCe2(-_t!El=6P6rMaQ2W8)0*qO9kg|#VH5i0CVA}He_aup$K zGlrch(3Wzwxz)v{kMjRBLUjtsi7DpwH-YtzHLQe8htzh2Y~ z3JX)N(^%M79EKY!x=A zs3;V58f&WvWouK^X>4p~%09fXHbsR-YY7zy%Q}r^gjL_pv?&&*vOlkEXR>loR1pen z75=>H`azp#XNvkk+KoO)e!^?*jjgR__GnR3hM7sH zrA3Ki=HnnFY}lFPV69D2TgJQ}txeg&q}{1A7AB*OjA7S$q_xSoq_8%Xs|dLgjR7AE zH5RG0wPmB7DMvUN<*&7=k)6qyqakgqO~y85JCm_Zy*PUEo6V0fvU(7|!8oVh9KF)- z)Y=rePu0~r%(IUQ)kZ@3{09BZ+nI_A)%EKqwyjeg6{@3_V$`XQ3e{1qdh_a3M{R0n zHY!v{Eya%NRBMG?$6@8fur{?{r@CB4F=|tbouW2%R8-8!Cu~b%p^oZQ7x*V?R%Z`e zqdL`%>`b+Fsr`8zI;vGSs#Bf4ZF<}!{(H$Rp&a@5y^BRD9Gsbj_OoLg=#;OEleVrY-ifkYSl)ym#bAr z43qVyum1%9h=>|THI=JXXFHSlCoD{Xf3!MvWM>Ks)22o;m8(^2ZOTziTA13}mJ0l1 z-NugURBw)*>9dPxDn~L|fqD@r$OxxgOVP^JWj|YZ-o!%IsSZC|L^9RdnXFA6)}~yc zx;CDvh-8Xt)tg?Sy0A0l3e`mr~gPP+c#Q=@mR| z`q}DNsD1+!5-3Q2TCP(acBXQ*>TmOEN0CfnVJa$Ahn*?=*}~dXwlf9VDc7kEt5P|t zDXJ*uc&4y0b;UE8nPu0e`aROR>Qr~tsSa%Qzs=5Mu8Z+Zowqg_$&_){|BRjKLU7c1 z?bw;bTREypiWsDNcF@|L=(@M3NG3ahh_f2onZm*p)+VE$ z!rIhPZR+}VCjD|+j%w{p+MjYikcetBGdagLmE)Ppwxve#Otp2Y#X&iqDeO#vuxjg6 zM?Vm~gY8+HzK+ePt+lD6YSn?W!opP8oZ7cD)w3`~h3c>~g;y^uOzl^wuJz=Vqnflf zRoj_r`+=0>nZ#Mq6{OnQ6rDh7Bbmfj8D~ZGc;jl-?bWFkE7=vK96fGVkO^eS)vH!* zh3Z_bI%1o?!(YhpOzqdHj(DbWBvW|!BAzM7Eop7)ldMhFY8t?`az)!xwlOma6pl1A< zY3Rrd&Ih5Z&q%q2y`lC)Ihez)WX4V%lCqV}F6_*OvBMZSl#E2}VfHEO2etab=TfF}uFaq|?eJt#J3QqkTeYD-BRg?Eg7ZM= z&YX|rY7lhilp|}tvRVHFiGiNS)ls}Q7;294QONB1&?6Z;nrm}$kK)y%Ifg*B%pJq{ z(NHszk4c%wRvs8iX0NDsO+vkE7`KDjF^sL{dJS|9t7a|w<1Sd1wEV5(dM(s?3G28T zP9Ck6!ehA`0bRuT*pzu3S-92^7)eahV$R2_J^(Y}_Xn59wBCA{MV zM$Gj+o>xyu8OH0m8jB}xDfh;GkAYed;Y3EqZOkV&%XmH4>lr(V(eY60x}219h)?2` zaa`}t*-8gnL6>umY6qvJd|ErHZH1l5S_r3*HM{~$bPBn&r>3mhQyDS$*9r%xAr&S- zPvv|XBjyR4F>F?9= zjBXE=1Ld!2@QgCR`UBfT&C!?Fv~emu4oqBkAfs}boF{+DO-dK}YX_)ZVdR`%Pu4NnF$yD(}f2D~a3` zoaMD>O#YF-j8rn~T`m(p$!iOtN2hUf<>jy7tc8hZhC$cxp0ymiK*O{0N&b_IIr<5X=St49dzTz%T%lYj|BQypfpXby ziD%>~IZs}b%e0NiGh?A4py94BYVb#l>osN7~=|MJ8|a+X{t zmpNj`2sulha?h669I=OlTqI|;axa%TqVGn|lBbL;me(9Hf>_RykE}T)ugOjF-x(aM zpmtr7zxIaio%k<0V8$+{Jj}b;g3>N#ZHByyElgZi-oRL;x0n36E>Wh;2?aJWv+ zQWEB!Yh~gueMCnvemGQl=w3DeF4~i;yq75t^DZX;GWV}_jGJE+yI53? z5RK#=ZF}Akm2i$jzD?(PI>!wui zVml>Xv(8iXF1B;xII)LZ=FSy+S$Y4OmpD!w;{G)s9+KlWcNeSOzued4GWW08%Q~}* zxpS5Gve>ioUKYEUe3bKz05t%-D`2; z8Fw`CW9(LWFLTeT-O=Qww!4^nR_tHp9WC!-<9IFhvc|hu+x;u{HL;+(Sh0V_j<#jH zm^)Y7z0Cb-gCRTuCE}*otE*PhkmHTQfsT*r6A5H32Fj zb_ORx#lOz!B&gCtgfl6vgl)K1iY!dKuxn`wD@j>0g!9xS`KNL{1v##Evn_`;snmnE z69oy)N!GE%*DCyu$uMNz@d96P~D>c8_itOY2# zurtg&ez_dIF!Ap~uH^}NU-ZzQ-z^GVz_E~LwkzX{IINgAh|&3pix+d>ho`%U^E^hB zwes&0MtegSbGFW)a#}9ljnQ7vC7gF+M7b^(FJ-J3RKz})k)4=nvAyV_C%;UN-jQQ2 zD`+@ZyYpIi=(6+-Mld2`P%IOu*QQXghj^r$QP&-+fsF-0iug!#x z;#^^UHnRrZG3D@?JhjQJ4QoX10o{XljODc*pkp|X<7zr|EayqAlF4Z`HL*g+F+QGS zdsf^OM&;q{q3-w-7!fmC4|4)*Xlml*X;4vt=u;|wXyur||MXi#Z~3S`sorHR&8R4( zR^@M+%5QZ)@^?qyc5iK_3oo}_9$?g~=%8ds8)C#`x~)SryCVog<7h!s?oANFXCikDWxT$twG zikNb%vv1W*SE{pYg-toyIkgI>obC)RVpfy`&Yg8Ul@iXB6+e{~&eU$qL{te?x@?tX zi?g#V&4Sfcl|RmcRJ~vVXQ@&v>Wx}g)as(jHznqttPlIJZo{!^5Henx|DywVB`lUX1pT0BV z4ArY&>JDwjqPl$4GIdV1?y0}K-nQR3<1yd4a%t2ojWwbEYyHxBtU&emyc(@<>MDwk zS~EAUszGVhS;cgxv`S|}i&~~uF&&iF>g=>WU7gl39gx;=)GwWyo}rzOmGkn}wj9cN zpVf98%6XsAG!7-a&%@5g%K4}sD2MHke(?@)n{wXYI)fwRd@sI}{1p;@7Qd-C-#{rk zn?pITjLlrtm(d;hp2~T@Z{{kwY^TIqJ15@SIq{bgco0u(5YKErPe*w?nEM5Z!xk_y zpV^Yb7IG|L_LQr;a4cl@<*i*gc40L*yNft>Wi82Di#Zmts^qOD9E(|v^44w~OW+=P zYbnQWaF4vTjAJSMqx{>QV;Q_4Z!PE89saR?@ruM3E1~j}d}g;}`AI&r+p%0FpRG!q zwJLF#lGXmk@_}_iNAma7jO5jk{3R`cD>#<(Kh=Ol3}Oy($x06E1B)}{eCvX0W88yd zW#TVUhreta#^o~YlOa3gv$6c&A&gGusSZh8rY5wQ-#3L3(Sq1O86+}U1f9x=H88~q za+&yKSLn8kD6>Ti$}%PW0Pb74vsRv*C7#%hU%!z135n18aX*dq(Lb%deq2vvMi)RA z@D8!X_B<7(=p>GbtS5O*oFVq;!?ieL2iCVd)xyV_!fDb+;;t~uqo(p_XIDqPB0DZB(KDsiqJG874l z8AXQTLFJCS`#|PI%qTJx4~iB=hT=gnqsUNsCuVd977r=`l^fzgF{8*(JSb)q8HxwR zj3PtvpqNo)C>|6uiVVerVn&gncu>qJG87Mr8AXQnJrFZ0<*i&Tm&LBzs9w7Jhn2D2 zgUhwkeX?WtTXI=cQ1|J(56fxgs_D*?yeHOIvir^CGG{K=NVh(<-(D`0qpB;VNA2{j zSpm6fx~pMpo`QJ9wIXL(MO@CxRnsRhB7eEAWp>s(TQ$<+6gm~04x%Wr){v}VvF1D%rSJ3&oR6adCS;von>YtUrkK|haQ8(UwB*$Ucu@C2+M=^RhRE|E1V+J;Bb6$=~lHeFV zYwZ=S<5nNn1FMZ?4eywNHQLS!)-^v0OZ3rPtxJ-_++pjrX#YNzcg(~Vt-t6v4n00% zzvDU9LD%uh@f=1h9LqaT;FyJVS-bUm4*M<~n>;(B#}kv(Igu-Cujmc3-uW!3Nd6>_ zIarppOk3~#1n3Ejp2DY2gz8(h7VsRX2;U4DeWUt>a16H zD(^ot-Jiv(>_hHMAKqb2bn|HJ&|n4h9idv2&gT9M=o#Ff!y2~UTwmUI4#%0$GgDpP zvw8L0B!!%(7WTtmO@yZ{o0uy0wLG z=KVK9Z{+?KMi)WVn61KYH5WTW+={Fo4pk$(l`Eq?tsQJdyDt;Hc?<8qjbjN^?c9vx zTcGxmxScDrXGU^&2gmJ1f8NG>zQUDt>~7=!E~NcP=*X01V`QkgHn*pK4!c3!q0AGG zI(B!HU!xBCRSqLL@8XrOa@<16kALSj($)PbL`7sXrE7V?m$d z-imhSAaBk2`Lws&CBoRwXL;uf9IMDSewHh{PdrPl7kB=bIG%@^cl;8E`N%Ku&X+m% zqVApjcC6g;GO?X%^RKYWO@zM0E3a^Gp3RHA<5k|V7u2|mS2^~9?nBhXYrOU{^kwc} z<8Z`?rPmXtc%4_RH9U#GVx^aFKwnF*>ivD4L(Q&zd|0;6hh^TKtMm9UY&D&?&nxwE zw03(Vvpl^Z4J0VEK$ZDVv==Wg<~6F4_EPt z90lqKydm}|BaOfwfiwbjh&N_~9z-UmCZr+WFi#}#hFBt_4)I1{5Antv(1Tnc>NpiD z3OREl-ssC&?9mo=h&KXzWYi&7)x#cYSOw~^28mci?9mo)h%wrtj=&rJ!3|=Rz#D-* zI)^&M8-YCnZv^%*tHjO%VvokCqre-1Kr-r3U%Vnof{Z|Fu}7c|k;YYRu!otvL-@RS zVvlaYp~ zL!>bbDweo8VH8n^2;>Id*BkA;uU1ZV;o0G`HOaW^<(%TR}SBd|x{jldp(H!}7RW3)vb57$K< z;*G!_fiyDe5P?+V4e^JlBdW@YIs$J5_SihsA<}4zJ)Q+O)S?bM?sbGZ0&fKN=sfBO zyb;(VP>1NE5%v&m><69@otT><)_66ci&wZ3T}*-o_9#$C*)p#`ywMl?9aN@^uX5gS2=zoM{e}{gumoB zqc{rwQuivj%s9QDo%oGL{H0!>qd3&P%JCcaUv5R)w-a-t_>EO*Z763~u?rM-{pDPT zzcwPVj0#bUcNH#Ye+hrSd&f%FmUe9|+;T-kbVaY{m5G0{r@>X2W2M3a5iw!qSSfA% zdajKdEBAUfhRm2KJp<)fDdWuS9`1gt4O>5tt5qv@b!1fN^?DaXplZtHF3({XkDksE z?WV?69TQcKm5Kg zDB=%;`&^ObF6#CAr#I#=`A7sdGx1mK$6DfwD8%kyN_%=5&!H!N2;baj?VcRXPmFUJU|p3}Y@qo7eO zZxny4s~^K^ENglak7U(u3q73kQOQcD-|tW?XiCATjdwIYMD1{T2s^5i7xi1*Gjg@O z_Uq)C^Kv}awPUcciC>~N-U)pAD6Y$$7_{B3=RIxf1lvu@PU_R3`bAG>rSyPCwY*K~ z{;97|Np7{^>Dbh2>*Q@-Cx)osQm&AvjqY6Rai?Ql6NzbKn}NNo<9-a)eLr(QhR$~X z`~v@@{f?ixAA?p&t!}fDhi(owF?l{}wp_+lbo{&kdzs$A#yuFc!A0NCtCJt_YW~I- zv8cH>Z*GOWs1vNjxq-tDRpqV>ML(*}Rmiih-Yv+l_B(!Fhh@x)!d7nC393xpvW}lc zoxEHjZ%g}r=1x@lJaV1jsF_#vqk14AIQ?}Cu#*+_TmGl(s_W!MwP5{s*35ep zf14Wl(;VTo(_iOKTwN{iDc=8l!mCjm&+byWLU7a!-t=mDQ71S$en$P4qFUZ(Q77-4 zSjt|ZKZ3s5H&d0DsNC``ENX918&6;ETO6;aPE;M$$&3D;jqBu9ccrTB$52#m5eZr$ z&+eb)zMtAIV-=fF$BX)bcFGQVSE9Z6f{nVnO)@(jnWHofv z$+Jd{9`XHBzVrUcE4@EhrK=yq|K@%SVx==d=$qe_LHmGlR7LmC`u!Nr2Xh%UC9Wy= zW7xo_?a&Y%uf!?2H$!y)G>+;*tPXRb=W(v>#E>fyi%^V;GMcJC=W;#b&eh3lzwf6} zTvy_m+<7CyGG6Kuuu!>9o|d?bxuPq>RUo?P&5*0*85I%TKchn4_54k%pe^g*Pfx;-XGo z=lU_|{p?(wyr__uJAU2@E^4nIL&jO!!|p@3w3BCazlshGdNPfa`U+7__5jV@KaGYqpVc*pYwP5-Um>qt z8_ymL)g3?e1lQ}tU}wkz%QX#KgiP)-mwcS5o;XfPyWCw>=xhncGM90sf zPG0W&8TE+m#9)Mz^@v4MZ}92rehk$eKg$*JqRXdtrMEZ&XVvfcS?H=k7_n?v9N{JB}8n?nzpAM~e30T4~xHY1a>`{OgV#b^ufx zW_RSoAgGd~J2+=ZvN2d2&p51>gzQ@qYPYlJ2u9?C>b{?5v$yc>?$~g8C#zELWL4_T z_v^;@(dN{f!|$e@sW*p~Bdtok`Fo?GT9tZpjD>1{>dn!_x7SwGheHd|C`OGjw;P3d zR-NtmS++cN*_n)8|KDO~s^G zH=;}KI+Me$4AJ*9aFO<>dc7H<@44J~4u^5%#+U~R%H2P;E!DF*8SAxy72g}$o6m@U z&Ia@J;pz(;QBbxsoeh>Lccn6ZP82i~bR+*?#1Y-kJ8NeO3zOES=*Q5JovHnfpV8|x z@J}N;|o@v~efSP7U>kbNA&+Vo{4 zV(vi|ozNTgW4H~3H}4Z`Q`8Ku?ago-@3|BCYUGwN!O`lH3&j&y!{w?Fe zcZKQ|eTw_XKd~(pn5S%K>ZtFhIIxU-KD~YnfrYd=b!1@*{1e?jjUInJ#fiVpK33o# z^8v&^pJhLWPs74g?)z!?h1~ZutW8lHIQlU(vM>easqOWd`!U%4+-kxfv-5uh)%zaE z=VLtnU41|Gota%Y91al`nYTLvE34SZT=Szuov8sX4b+RgjutYqbTbu{)DFORY8; z`I4*fzdCB>ofQwI<|gco)o2QI3S;{)HjOw%eMQ!v?6NZ%MIX6)$8a{5{&1-Ifw|X} zp1Du2@28$QbMQ8;`)71k7vto$=kYhQwJAJ#VPVp?l)ZY|p2~Kn-1n;et_*hkybP3bag9H( zy^fz{J5%TTG1yr>EKD~f+f=qNsT+oEDdVi@!BE(lGTIVbX>AJ371k#EtA{5qcl;D* zMGuDd?Myd;jBevt0BR~MOpW_~ioc>0gE;HvDx76ro*l1@?+|S*1Z_p%E4^0ta6~R% z(f6wJcBb0ypJm%p;mOmgGy)W*6)JaPD0fy5J5$-hRKFj?qhPNGh+?m`HtBDx*Oft! zRP+F~?^WQe#o#QX)xvuhXsce|&vM7lXL$d!9J^r&D*9eM$6qqfF6>NNBy#u9us>;e zvZK2Bc4p?8d1v=e4|z0M)R3Tsn)b|$;1 zYbP>BNq^q5)QQ1<431X!V+hNW{=c_*ZFjt9MnC-mce~?d`xayGurn5RrjGin*IJu? z;S*Fffxq-Vhju2B*9RPSUubJ>s_yuyCoe2dAK~%)5ERwc+9Z;i^a;)io0Acb+1g|_ zWov6cq)z{2Yf%GLMmn=b{3z*rChJj8B*Q?il@L97e?MqHUeC6u!k(mssV6p|3icdx z;VW2zI&WLj;$=tAY+*72rit%pUxse{ZzGwEAsWgzGoGmzM>AAwlXfusKxl31l`v2* ze#bbjwJq5TLc3J8{izqfLfewhU?9}$Bz88nQb_xeO#RY32l1}H{LS8c$Ca#)6|BW^ zJk?dKjIE$s@w7!jQt{H>Y0d1-tD>N&(Y+UEQP4IU{cPcL%igvLd}4pT{{(0&pFe<2h zH}$+-2aWFMVR_22O~yF|BFdJh@VV8GYKp#}VP~?Q!5zs8bq5G%XHZO_plodt1(m&R z^{q{JCu~&R1GLSW3u$c%%Tw#`q`fOlABdhRGJDJ=v3Ugi~0XL_X0Qy|vXUt=49p!r3aV)@C(7!TbZW z5cFr68PtrO!q{>1d(85&eyeqgBA2cQQLEFz9%lSRl~!{P%uI-ynCALKmXo=3<`SAe zXKs)AKXbS;_rUtCJ0?tG&BcDm6VZt^7yBbw#38*kYdH~zoZ&Sb=ReGAi1FP3cBb0?>g~ld zSrIBCnQA+Jo(DoQ9%|F=OyS9^jvjAoZ3=&0c=FT%b8J&YGF5k0pO<`iQqf0_VG3*& z{=Bd-MfcB$7|*t)jIA=-ig+gDpTf>$G?R$xI{tDXtXq(B5ixFO^|FPjGkrfhV`sA0 zXU17!XDTDCvW2Pa&kGAvSewe&sy#c?ec*xmkxb#?6FpV?_U;7}MZ|b@JX3W4G^*+U zfALJ(qjKNRpT3=`==)i1VJgQnwT)!T{ncwNOl5=>b|x(WIjX7F+LRGit(~ce8#e;| zeJlxuo#}m$S*^7xt%#xJX2t(jIGMnrm!;w&eHPK+FI_{sa>cE&NelnG zJKr%ZOrLI4Q?@5Hie%c9yt%^8^s{PVItUw6+0JwbR;ksgYUaM=w5`TobtuOa>QFiB zR?R#BYGuyDxVK(rH?BU%{UOl9I3Lctr$P_qd<3Kao8y@_J!9@TJYr_wb(A+3F-(y? zXH-+Y7^cF{miwMJvNPpKrn5jEdEEh^;4VOCp@Y!eriD z_}t3bb64>mBe~l~G8Hl0x$n6sE_>Jl5!GhTMO4%E{Kd}2GiBRS;cct7Ewz_7*S>`* zY)fHhYU^kFY~q{DOxeO@B-5uG&lG*n9|LuT zok^>b@l267*M3w}ZN}V_*rFnD&Uo&{RerW?VTwp@ZA;nDCaNhsY)^8nM@~OmVQtde zW{kE~EyKMmQDtc=;%wj^%Jd2`yL z0{=t~-P_48r?+j{Cw{gv3aYj+eXB#;QlpON`nDo(E_>TVH6LIvdLLRKB7JLS%tiKG zc-zD?AMwr)pjwzBhc4rv50h1?9M7a@t}C7?x&d{?Gj-+7wT)*wiU_1lk7`=Sr>s@5 zju&lCtNY)-~Db~@CQ`96VM~}CkJy(uuiuwdau3V04GLosSCof`{p4sTh3t!#K?Ecl(rrL}->vTQ` z$`Or)KQHIaiITD>uZU*~e_qa>>nN(}RXll}k7p{-R^xc4$e0UjQ>}&RZBSX^$*Z+9 zZGJpcBRf-M%o$1kG0`(diI=0t>sy;zTU|LLnH}+>@kC>jrNKBPZB8xh8`j1N%hP9V za~jPzY2h1;hHC%P)>XmIq|HfBqmfD7Qmj%pULD7^8Gq*6X_>ONRreIJ)II%$9{jaY zeE(6&a%NO`PYz?Aj27?3Va%4bmwI#5i)}J$X)snbW1ISLm|>^Kuy67h>Vvep+fZK1 z@l0KIrl0NlOx9#7sx;NF&s3W?7d4s6_{U7TQ&>NdH+MYVv@OY->x{LjoG}+s-PL(> zrxAa>sqsv;d2_XPrrM0TO|vuQ`b>@T=EA~MTQ^`+Bbmw;rfNT1eLGXx&lYy3TH8{& zGE?~0sw26pW0-D9C@x2JZ;qYmwiJ_;t2BkRN&FMB-Bv$u8`YHKnZz=;f{z;6nKJ&- zqj(QT+oHHpeg-$-N86#yBVQ;ue8_8d;kno+(?K%%1x?pULsuWjj;EbJtd8D&o1T z?MxBR6p>6ude^fp8QYyBnaZ}M!rLa|v3p86lBpX1WD8S{VG7$)Q9Ynu4AYk9&4uO3 z=%;#iCL_SVoua^V_MFj6MLd(%COvEs&-5OVz8%+RGFL9DG-az&SePP`seay^8F5;e zBAz?!Op!?!)+Q}gIeNQnX9~+xSKgdmJG<;mU3R9ncBbyBA5Co?OtFBS?`CeSfO$Ms zFxP;m)DChTOzli3U~v*>SrfCcIf=GDR5TDd2`v$)F^vSJ5%J)Ra=|d%bOEf+2O7n+Z6Sg8fDA{&N8nq z+nL(So9kSCCi~+>O-w5oet=OtrC1<@!w7=47pc z?A0@dscdJ;kxcsVv^nK?rif(9^_i{*5gAvW>tL4aGeta85i8!<&J_FT2KsfZpQyV0L#uAJVx zsDoML$`y7d_xx;a3WTN2sga$@j5u@Ps?k;vF`n&A`tUX_Z?17XQ=qDHR8#wTb7gN7?5Ty5NVAg{7NFVI$DZHi2~jI*k1 zH5oTCA{TOHMnNHX?0Hu0iwWv@mHM(#|xF@A&CPGIiBwvLo=% zM?BM7Y6sZow{bP_V-oV&4r+adKt7$T11>gNpAb=7-b z>ws6=nc7xn%2>!6PS#(VpFD5o(A8R-?%>sOeWq$VlbEOT)~4#bxg5`QH`bqsXR3{4 zDq|scj$EZF>Qh<=prfd!a^75I%oTPfy=@PIf(mO>y^OhBH=wA`RNx=8;GX;h?bKSE zYNMLM&lWLEQKhNKn`?`I$}vm@3M$)~%#sTWQ)JIIwljr?t^IhW_H9nNO699<;+e|v z-0s2U7^b(tRz@|6i|W~#3jCur>22^&ZB)~@8Lzf5iB;Z96$rkA1*(YWE>~%a*ly8I z+nV5363}jxD}cXOsvD3kOyAiU&y+LfB5o zaMq`5VQMdu>3`DB)VMxV*^?JFnQ9}Mv?t}--$f2x#}=j?K|IDtUBu^&7_W_IsxCpCk zXDWO0%27??tcV`3j%q5$GigtH8V%o0DvdUh@DD4wb8$qQ5!)~1MR z(%RI>&eYh#6nHAznO>kWLDXalYm?oGqgK_@ClYiH=_KN)>0?V36;?G{#2n49c&J0-iFH2U<}jXL^cs)O0hTAfkrom8uPbm3J0 zS%Az@imBTy#8#&dUpcf3nnCpZw9jYsDwO*d!N<`%)PAASUsUVel2oH}w`9Y!W1^Mv zttDl@QtOq;L(8z0T7^t|>+Z>Nx*TfNDOad;1%7F*pHj63EtOJnd(`LLhO1S~O~>

P%@Piaw+(^R-~3 zJRI7NJp3%?>$8xD)-YB+TDMrje{qxd_0jAphS(X)b^CNO7cqXt)1+;iRypW zQnt$Sa%8tF%j(O!BO|Q3Y*prE$aU~J>)GnfR(D>)3b(4WRi78L z)~)vJieJPY;}ad8c9~&NcOZ8kJC?aW8M!tDsvLBmQYKmx$cjLNkdpJD&Zl*Rc7|Fr z$ofLo7IOaOVQUUqT}TdBF1v5qd)z)8_MNpixwVVjZ+oYm*NR5^wA_(r;gf3 z${MR8SqsU!Nz;ay4Iq_58 z{q|tK@~&tvara62cm?O!L4((0XASNT2_D^wog3wabLQMgowL}v?K5H*Mw7IMyLVgVz0*Rt|@T8J%dAP?#wxGit{w+6Dd2F`O4^K zN9HSf0tf1G=Az%W*eFoaEY2A{S$`^{D!UYCv}Nz&jKb`#oza;+kOQv;4hSR{=pgqr z7w6@^=i=U%>b_4|a~yX0xt$JS7LncLCa9nNPvAgw1c zn5!xJF3T1D(@x=j;abc6(CvWk{%#-oKxj%5XCts{KUS{$zL>TzD?E3a--DTnF4E3h zg|(hBc7=Csvk?;qLN253z|Dc81A7M!&wIZdSH1hhJO?IshQ+fZ(@GWHy61{&of&7+ znOd0U#_IIWq_Z|U%~bSH9L7vJhtArVG%NF&4QJ0;3vL>hX3Dx{R=}`!{kXK|UHPK# zrD+bGwee|Ik(o9+H-ir9n%}QowW||*oRYX0JIdKl1i9OP+O=7;R`DUfJ8O)b^ zidvAfwhiyF|B)PKr8qUB(3R}U?HoF5N5Fn z)02|As(fD31+0RpiGO`kL-^(Ltj}dIzgP~nD&HV}zr5*F7|4?nhx)t*@H9oKKGXg@ zanY;Ky&p3Z8l+Ou*@}5}4^zu@1@vZJsC~Ldda;Vsb>?v213H_twfVZIbtiQX+bQi{ zR^@A9<;ru`=Ih4FclUCQH?zhotO0e&3cp-lj{XU`qk`xocUlmGp}SBDzV4J)*Zn?luuov|^8lsojMY zChib*EaX>+J47AMlDI?E5lBOPA^H$$h%dw-B8{kAxHB^o)eFTSA`Ov+7$oW+iZnzW zA`$bE0%?dZL?2N*QT}pfd4g}qZ*{xBWgoVVf89ICUQ(j&wOj<(0b0!q#0c1a&=?GEVHdSw{UcW>y(*RHL}u? z|Gy`n-Ws|!W7ee}4;|0F&u|#jXFP;s1i#QR9n$F60e?>_6MzUQwwKeO)y;<45b^7&frMi6VbD7Pohzdih zYkhG4Rq6+FRI0D!T6rF|I$d=$nPDZla=uo=E7e_TA=}-BC$knpwk!9uY*!|gCA@1v zss8`idlNXjsw&_A-m0W3Q&lQMRZ^AdR#oPCo~KGe2Err|$OvHw^C&Wk3?iTm4Ty>; zh&DLjgopylpkRY&tKILf@3nTf|7Y8+-B11ZU=P}Mx9|V`?vXOt=snfCzY<|c-k~{V30;}p zc};{(&exOfU#&}4>i%jAuMS%av>@;~rNclD)+D(kOO#npQSQhys?tl=W$dA%O7YyI z7&#%&mStW0qdnC=8(K-0x9z9Cc^kajk(y<4dytZv+KMAP%kB1Ab(gHUC}F5?g+6BA z%$SR95j`rT4_n7pQGO3RQ2i!kkwvM0N3WYqD@R+~(rOr?Z%m=>LpG0IAumxE$w;sB z@l^UsAV^AuF>@>P8K;`%=jf%=;d-GbDaBXz*ubQe`IHOov1R;9Ibmj+Ba955#aErq z83k%ej?M5y&;-B(8=q3aZSw zfqmCN=;D_RoZZEG21jt+k(71N_3Ulr4(nOXU;|ej#Yh+dbwnJ+8Ec?x_~mHMaDDP3 zXCIqJ{IO}oAIt9}IC3QC9!oh2dNg~-ao&39diGpNVI$e(ifoThT;zDh#&GIKbN2C+ zR@P036%&dnhn;G20~Bbj8iC0P}h(;l`~F;p3L6PB#Z9ksvY=+%Ck@7nnvg;Y>jL=g%}t8MNg*~ z%i=bSz5%2N~I#ljNf-=EK=&A&Y&^Bh6LtnAT^vT z$8D!)DzUAmgnh)BU(PI-Rhkgv4c$&{Qf)@w?EG&JR<;XNU%o5<4f&<4yUKY(^Xp_B zsMn5TKXkqVJtxaY%NesuhoJ?AB}iV|%E(n_3`s$)TK=nsE&mOPKs-!7tQ;A$;9}lg z`9Qg~H~mNLJaqBU2<1a{^fhJikmEvw4B0ItHF@e3zLmULsm+;K={)2$HPorJVd$~) zX?1S-t-M-|sV}`tsa?r_E^QiGamZ5YRw1=1RVkIKfy;B1(Uk1ftwR=5|CT2!wb@d( zi>($YU1;Pb+Qilg&0by;vRgatWxE6tP~B?kJRxxgHW)3X>?tpdHnK%RrnBuv(1KzT zA-g$4I(OQFfoR!AwX}=~RJ2{lZ6UQ)wp~~NZ6hVQ+;(b7wv=r&37Xr^R&w^Vjg$_f z?Ubf%yM=uFa!ZAjX*({U1w;{|y`lv}lMPHy8A~bKR?V$ryVzdhhqh)$Izlp53bxfm z6hj{qOU!L2s#V#72g;Wpnes!!%93ntdP8yF{pZV9iVjWAUKKjI@@MGep#z3i7+Ldu z&cl%}U!65;vSQ^~!xc%-ny(1^f#ORY*LihDWv|e+)qKk9GKN+jt25e*)!EhD?dN%Q zMn^;Cx{O*FoMpwY?d{V2t;?wGLWDtl{7~9U{!FR%g80{dfN2HGst7b@2`*k60e4+Ew6ZTo2kGNT2^ zmU{K;Xeu#`^JjOCd45MY0RK~%hTA^wMjMH^kqF^AB`xJg2gVT0{9ctN*t1 zdz|U46LQSHj^%eQ@WfuBytA+K_C6NKQ!l=Z_xEodcs-L!{=D~iujJ2uix~CV^748n zG16nyiJNrLSFW2I*xw+=c{Afu z46un>OX7OXj9R5XzfKF|QYq1Sd066`B7O}V5dmz421+;pZs1HQRkrCz8JXHi%&;%@ zKpt&Tu}9~fdde7jvdCl|rNqc{esLU>=vlp~*HSv5%EtEC_S8o^>2=OE_Sle!m9g{# zvrmp?2GU}?o}$%OTtVylc;+u{h}n=C1nP*i|q<(GodTlE~hpNs^%|BG7|}IIrU|fIn3tE5*05HVVcX# zq4vF)G7ot`ZG91CKC+nF^+L)5zJ=qkclrj-OoRDqzN?(72I@DfPhY-1effI6c!47| z{Gw%C%+~hmm)grVs;6$|F6T(C?9PcHJBM7BvvVo^^-ukzf9fIqQ{U*HdPRSFh|Avk_f`*%$jV+x z16J!kopZOL<(|q_`--WIl?TPia%PFhCSh)gh^AEA-8-8^_n1mEb>-Zpk;f}CnC9GF zXCGwlu5&mqufnYMeKGfS6=t);M+VdV=ZMcSm65e8GD}>{9S$XHSL813o7T&T+@%ps zX>8?HDZfPZ`pf$3M~?VwsLjCFUwk_I{rB6G$JE^L<}MY%xR&3on>F5bnaeBX$Q!Op zyrG;gJ~G8$TZr7HksZG0^#{#45t-t1UiblA8D9Q+?&q}#v&X-l{bj%Z?s>d&euDoGXGke?xjm#28O5UB;B&^OXaVK2wor&|k zGx5B8;VuKo+I2VQ-%IW86hXOQPXy(@bHs;>%2J^sxsudjdiOz{y@DH>V1{$S*YKbY+B)p_A#{lRhu zubyKnE2AlmuY8Kx##IQrXYk5vF<0h@ugu`}dGeO_oFiV%<~hpKdm<~1seC@o_tn|q z%UQc}G-YHhRV#WSMPWt;uNTSPb+9p&>QXtUM9$##EWZ9mR_6Q?=J7Hwd|rP!M^-A$ zm=XR(Xl0K0$l4XrlwakXuOShb%~V}2ub}gK?ydu2D~C&V7ip=)R$iN~-nmxT`|W+E>=D?lF~>a#m%I_=vAO7iprEF!pM=T1@tP)mAmCEvvNfSi#H-8 zU6JH0^&;i0IY>@d?TM`X&E)Pnn3&4F*Wyts$&y!O@XEO>4!jm&L{^H3<@m~;vUcr% z6~d6Max`Um6`si2rQD%})jdbN8s$4#;b-BVT&NLK85vQPVyd&lhlG`LcU7UT5g&5a-dVepw{mvWat5!QyDPGzDsxrGR7Q@}$~el9wz7m}zAh1i z$l4X_Jb#)f%8wvnMZOAid}V1%8KE+FMaW#`3|^liM}=r?Ug0_7D=Tw%nZx39yECPZ z8F%G^#c!l>A zUTeRtE!tT`#?!}1gi!zM z`B0HV{jcXieJ_#Wxlrd-rOr7}aY&`n*-+n0R9Tz2*o4-=nNaaeJ+Eg#eXp*BcXlNd zbY*%Ysa8hcNUAsQGPcWkpDEOoMy1-XeIu#9{Nk}veR@S`rCO_fBdIn~?L>p1v*u&_{F8+5m%0> zw1xDzwf8A;NbQX={=&O5{PeVrM%*A}8S$5Rs81op%_KfQG(hJwM_Jbtj+k{f9c?NzplF&f%8CQ~NCYqV*}e~jAD@-c-n8NQ=UMPAfIt7ylXN|};4 z(jchzmWZ&K#;;R%^Cd0igK4+$ACco5L*<-mYYt^^2;@BExlR>=k;5E`S!<%cD#`kxq^+fI6Z_COej~Z6g>b z_7*wtLb#`vtx=Sbj3xVw+;|Z!tCedsWmMwHi=p->TEsuT9^@`OBHinM)e8m-AW7U(R0I=bXPBX;SB`Y1CpC ztDe8)tVUn3K@ zaQ@QLTAsh0tLkVyd5p7IAKJN%BQbNuEar?=ORtej*>`%Up5^@IoK-!GIbS)873s@E zsUL@js=lVq)h96$#^L4Z8p$W8(X%;?Emu%>?PSN_7VKLSv0ZJUzBPT(ZCs_ts5buX z9GeW)TW&kGDbOkG?cn#5peJ#sQz+WVcCbB_n*ODyu-(aa3skGyY23~1>w0nNN4gy< zM?alfXR?uP#X7c)d+0~H4NuP<+#_cnJ%c^{MfDEVSM)5(PLLM84bG;V2F9YT>>TdY z0W~Z8In>&*h@H)^=TgqVesyl5XK<(UQ?~W>wkz<$h`-RYpx%zTy7bmRc5^xyvVO`1IC15R=a<17#F9nOyYwBu7*=*=6uD*sl zje&~#TtjU%R9o4b`R(##>$(hjId{_XbpG*8@SVG=v8cQ;H;~#U|r8SH&WgVeKYrXE8Ab?F zcCPE7>KeCjzfsWZ*xt(THbG#WJNW%=P-n9{`Tb_-&D`$~*h)W8W zaj$n$MnLao?_SQh6M7HZcTxKT=)G*;P3R3s%7p$P^g-_Q5w_BYxYI}32J-Tul(kCwA+C6oyFCn5Yxp?(W=j7U+mCbi z7U&~vKf&)0LtXFhlWe6Q=6;`|d^BM$*3E47X|^8&XIab@kHPB~gR^{``+SDd4E;2} zeunaKtWV}4eVnr%CCk*~)IUr4Bv{I46E(lp=P2SVPq6(wcY6%#4DuxR8Vdak+b0tW z^JGF}p5hFxTAye8G~36ak8{5-P@aH3!C7D6*k==h@;MNXrJVZ=^V3pLl_$C9vy>sw z&#@=Y@;MNeXE?_kp-(}d;_BzwJ`ED`H23-v<%`hg+50lvFM_H#-@U-RxE#7Hp(;xB zFY=qYtDfclFLLe|!B(E(PG8}yXFxxm;~uV8{2U02_{&S|Jr6GOrG%tp>(!UATRG=` zmGT0(i8ARc+R(~+kJ)>v@D0k#&_8DTP44;C z!nYC<^DU0OO#Kz^{3rbKRp?i_`cK(PzsA-7jjO%^{nJ$cI(z>Yd*3L0J4piHPIAJx zx#u?v-$`@yceq~@^>48K4(EQO@ZUN2o6v7^*Z;v*`X}7)&)7=;l>2>`t@OWf#rL@9 zx1q`;e~!f22>lM*Kj*jaK)=iOFF51BL%+xNFS*a3LH~jye@Xcth3~Wdv%>#P`7ZSP zZ2u>B`(EJ(+^Yfl=WKt#FW-fJm%YE@x4(e?1=sx*=YFs7L$-fe_-o4dp+98%H*CKT z{XW7gv@H3A67^?L0vn0>_jQs(H|A*iH7Wz}Rf6w-Bp?}An z{+`<375;(k|0?_=zo`L-|i=k!@{pJy+Bgm5qB9mF{{KmF{{Ke~on4 ztN5SXw^y--ZSP`j@xP$|#og~m#EowLH%bjbB{ffPc zb%lN$?M1y0+y4As3$5i&11NRS{%jlA)v5{?`;y~`!7rGHUWE1=SicQ?H zH}yvLn%J)^4C42`#X*$*#le&T&_Qg6P-}n=W;>KxBXkJcX6`l+dKC7|mSVzN_@%Mf z!u^n1sWlacanC`}X12qr4TcV5+sbw@bTD^nr3@{$QCgs_Y)5dE4r~JFmWu71 zQ9%0iOua2@pi0i|9PLET^J|Prn!*^4DOc)|Dc%-qP&6Q6DGiRKU-pLDKSy#z`Kvcu zdHukohls3&o+8d6zBUrcLRmdoFGo*I$%#@?$v8xd0-b09twks>*UKgS##*az8|ZZi`Z zdo-JpV-9{3KFFdokpaPI12r?{6~Bh~nsSEO6GRG>5Bx@YFgUxLZ9y&2Ies|voO+?N zvTdNg-vx~*5%Wexq?7rhoW0ETAZ{Ao$9f@0q=@=_#2g$!ttTI3y%i$gMC6{3stp^R zT7)iSyO>%HbP?Mn)N0dv)$k6sm+z(b>r(2zSMT&jQn3@?NGiVK8%b@ozHIxX_v*_# z=ritn_2rF3czmyZyov4Qd-dl{M2bWc1~A8nBRSJF@Lr-xzFi}4B7)>RF%aG=POL_5?8`7(W-4{{ z5v{S1D;Y z(h?(D%|t4G)5*329bi7SacpyYMRZTJ;o-<1l6zLfBCSfjPZ~YZw(>o5Pc^P7_uz8o z5c7xFyQ9aKGl%HcW3P!3V%`w#LOF{_j=K6y<_|G*NJJ?FZ?OMGrm}MW5Zksoi-^du zeLC`$<)|pLmSxTr@tNf;BAL^bGl$3r<$^u&!<>C&|1lZy6ppEKBvyXb9GT%5vmfRR zDG{0Bd;9i>8k6D3iYzVmMl-qW9fM`uf;y^^bLMe)wJ~#t>euDSvPYVos5?KDW5^F3 zWpa!hnb8wJlw&x49BGv?8LJuX;=Imka-?DWC3SF-+|}IIdC$Mql17Hut|+ev^3e2m zn;9XQkGH|0oJ)O%p^O{Hk&&rl*3PhDe-*bihS-_c$kf5SrC6`Htue&T-o~d6;@!l0 z#cj<9;GAv`Gyj!XZ(zD|IZ<~t9VLY&P)A$?$JAHkd~&?VS0+~Ms1$#X>`4RoBBID5 z$P4K~V)ORB{(L9fT)AW+eM@X!Y+CGEd^$%Di`*AEIu9zUEefxNC8CDJ?`u;3Qr4MA zzjib#@rawt5k=u=K*j8pd*(pppuMP>dr8b*8B~nk-hFWV&>oTJ#>lGVoM~U#Up^&! znX|DpbHc#w_stLU4BtJUl5OT})14n?PI&n9Dfz9ON6n<<*9&0}TXwJA0>tHh0Ia#j69s7PUSFT-o(Q1GNqW`)o$m z67b_C3A%|GX*2;4cckBhdfWIn&T?-BD zTGToa>_Dvp!4A|q5bSE~dQrlzwJ5zQwQ5GNMXg1!dx0qjY8?o6PuO*=3R;O^F9eys z8t$+VT-muy1iLp>pTmq=i&q<`aaqEtuY?A6eeE8+I9ri(qHeS_J#8d$8*_gEEU+2ZCLVUC-l=8MRhwy@fl~Lo;gaY7OGmwew|8={ ze$YGEW(51yVb`w4ejhwS1Y2v~dy~u{g58gLC4zn59@IJz>}u><)H)Ds@o3jz&|3N+ zMFd;kBZA!@T8UumRhUuhK(O^D6s>*$8VI%?gb%}^WKEacmLnK(hnE4m3OC*do|ZfM|oxd!?*CZAuABCQU5i== zf*p8uAlUl-Jppnoj{OY0dm3~acYKy78w7olZ8dfssI>_8^Lw!Cr>F;Z{XF+`)$}hy zMY3Pup3gv!W&0v`6t#YqZN{$mk6MdYXY4vq>zBCiS3zx#g&xa&MXHBD)#EZ=EwU|Y z{bi8lO4K^=>cFncsI_Qypw=&g9UleO^i9e!&||n-)OsjXkHWyQdqS{9uKyTh`A>Ia z*CN^hL@O6+=HsP#tf_&-4gHx_2X-xv{ZsDwBd9UMV%L8I z{V{j`Swgn=g<1z*EmAFNEp{!AEo%J}Fyr;yOT2nLSaM+0fm;8Jd;Xl#wi~Gq)H*Qg zj8}_Y_l#HTR}vWYFO#nP%Oo?3UAJ*u9J>;`{?%^mTGUzu`=1kb{jc4y>$M=$|AlP2 z7F_w4NTAi&wWxI<*cr7J!7dgvcKxd=>{?X%*M-_*@>(e#k#KB%TY44Mr$n$>Qx>fG z*M&f>1Hlf|IuPu7aOR9)2WlM%c3^e|uk?M?NS0dPB6N23nb}b^kF9cidctTMf zOYFJ>8aVdY-Pkoac9OuA^2>OyvaWh)5j|5GRh?6;Bs2!S^h8p6&IzQSZdq>(d?Sz> zQ5*F`HJQ+3lrA#Lp~j=O(>=$Gv#`2l0}`2j#jhpDOh&WR=K}TJ8}AMMPi=4*Z5Vj3 z944c_fvA}?wF^W*-7>Vyp70I(f1ti159+Lrg-V@v9s4GMvkUmKQFXyuz%@Lor52Y^6*;*8w zWwa*@qs?s1$V;K;uNe`znj5w<>q?-y}n{&n9tp11sk zBkx%~zjhppl}+RGdt zertP~PvcYA%X}tBhP|u+^&QQj6x1&hqsDjgOZhZC_glZMx$?cn7VuoJ>6M`$Xdko(#2eUNK8sIg-;Srr zZ5_SE)+}=e+cTcV-kQg;e8T%ny+?okx^Ll|`8}mRff0=M1>c~7^OSUI*l*ysT4+dK zN>)lLN@z-JdVKf|lo0h~9|3hO0%aN{8708JNsh^xuIf0aG2t_fN%nDl12c^2VbVaq z7y=!_8TOF|WJG(d(&DJp$LxoLI6j8sqtllfgZ`lJ`UHv=qzO=QG_6ruRi{#>6-vBI z5nANR_Vjk`94Vn+jOPqTN;{gy_@r;>EpIln4ybyKyt^H3VjO48M8g?}UNM&175vf( z;(a08%PIO$kL9;3IXV`41=}})(2I>WUH)qW$j9asvk#@=xb z+wBx{TJ7M-Hmm?=L(k@yZ4|RuZRYqAiWZ42Y|YlJ{oyRmSc+|93v>&=otnJmPvzI0 zSRwSrKb@^qfB$8isntbKr)89_387dAHP7}&wnt&>IGr<(L{B*aYA)~PoWBgJPt*!% z*nc*G>#X4ntv@TEYSZgEqFq*`;%JVo#K&qi`^Tdptp=w%nj^Ec@7oJ(G`0Y5T z8t}0kKaR4BZ*d;q_FT%<^Z>`5vrusOS36%ca0fL8`Hy2tZY6hel*nV`T5=G%n>-|D zQAeO7)o~|BIDGR<$Q}0Z>bd6iIpxsi6#2iisC>k^J7)0EhHXuIk7tBz;GTTeV{&ni zh7{xs7xRj(ZR>|#XRpX}fk!<1|Kz#gy*yz()*7Xj_ogSmFTK}&JaupEInG7*QQk`= zguVL@CXo*iHThk-#zYjZ&_NY&C(3c-(g&fg!@ZT-Cla536#6I@q6?tT8)or3k?S@kPW3UU zR;hC-ML6O{emk3U%qX*!t$uE6;cQ28-1P=dOdP+MINu40^SNTdan!Usp9vQ?SL71P z2Iz*wv6r%4Mp@6yaSne)Y-&BTf%cThne2SwY_OH>cD83R-@K7CS8(21=yJ9z66WOE zlKN~pr-vV;^YKLZt{9bTN34R1ROu^r1as0^Jk<{FdKUCd<`d(cig4br6~zutjdAXYXtNdi-oBru&TO2`)_j=q_@7)5n0TkUyMky-R|5kp*nJ@_)_ z?&~O*VW_@LY8Jyh-9m`+3o?ouRW~_Dl#w0_SG4OKc41Hs?GS0`YJA*TC z!bVdJVhrVCs5bgB6s4gn`Q>S> z)HgzJGY{w9} z@j~It*vwv__ASnQ0V~~~a76pxm$0Xa?0%Eu--6C$YaX^QL5-XF2ETq28Pt3xE$lxB zeVJ_w_Pm#&udr>#HurU?(JIY+xmnOz><#1B79`DPejQF-nb&-5S~9+l#A?)wXzbUK zdB4VQZBTJav$l<(wDFCVC;}NMzyteJR|@dBe8SfA_W^K2TRSB0Ua22BYd6A4?VHXq z1L3FkbR`Khi#WcNFb2VYMHkhsTp!2G|DiqPY}5W_wGIDbNclcRZTjo}#R1&izwTdb z;O_Qf|6(I|_pkdG&1m9Z_b;mZ`PcosgR1^+NKn3ANL2an##k$sH|&7(Kq}49ZMKjQ7+d$~f^xj?QI&C{$g>5jBL7ZhK8j-)b7? zOos=}#d@uV0*Au>IIKl6Dx>UbT#`*bmx|-^|Ny z)^;+T*87tH1f2`-=3ijsH zyK1NvDDBX8jytce;5@hXF}G5Cy8Xaj-@rZXarQ)ex;@UGXivAt*%R&Qfjo#XM31v4 z+TZQz_QWB4x4uwEfEv0hDaK!nzvbWdFNzd+By`*8?~XbDVvI1KAo{yw&c7HV%qNKc z?wIp0`q%A)@fStyeS-2|6?6OTy>I+oziBQ1yMJ>>hhN&?OQrmbmB%6%GPNYSOvJpA_lG@>TOP5d*|t4aIZyhb10}{a*A@Y}TpoYNZ;@okz1@mwIg2 zr|Jvs?A240we@E0LlLEMjP|97nK(xKQT!f`$o>@3635>Fin+MQQ)^&+xh}#4YUZ>E z?^?NwW334)A9Z96g33p=Z4QRYjr5ir0+j>lXFe1v?-9{xhRT8TjBSC+U7YuaLFF;d zeZvz!8%}*#;n2RRI!d&cUr>D}t}k-jHVJ<2FM&1{_&uXp@*|NZ@8I|g4Ankk50dlS zX99DzO+=CGHTH-Y`O#1P`(bl)mhf7y@;=_dtGthQ&<5vyyn{A4=fU6-KA$5tXWa^< zQk+r#V5{m$Eq_q&dhLH#-r--AQ~3n@`n&$c@?ZB`$v1r`|9*^?=COG{Z5>~-X@0N*9@H3k>e;*E6sQIH`_ACV8{cu_M!C;^Nqbe=6)MvF5?8w z!b(r}4_ni5SSpDe_oipqUxH6&i-k6dz|7^^_8>=4Ak~4H2a;YYEl3ofE{BIsqeMnxGlH4UC;%+xTp!{KB`QMJGmr@$kPv1(?k|A6SOkyy=) zVD-l#l%eoiqqGLI9fH0ZE7ojazllAq@cM%dggQd?=FoY8ViX(6NJjG~Lx?d5=r*w?$-HeU#xkZO9)jOU#_V`4fwDP1{>xUm%?d(CehqEyusnT((q1a+xX4ma^4)Zm-A^CyrFzUbdF~-CU3d(_Xfgqbf3w8B-YT zWlP2CX9w3_dN)OTm1vpVUJ)a`ulD+F@&_3&#Hi$??44K89?yPw5xP>Q^PcjyS^ks}mAB3E zr!1trZ9c{vIc}_^lD|=%v36ptni%T~Mx>-spi2IF62@xav1(=b5}IdJSxhWJ+(5}+ z9w}C!lv<#WfJn4^-vqs@GbO8)BO^1;aO7ct|J<*zx7tH{b2 zG2`Z4UCPl|S=Kay(WRG|Qhk0z_zCYf}^;R^Jq-4NpS3 zp)1|TTAO0dBF|b%<&I;aVw_^gQ8P>JhTUh#JDrQQuEsj5M{qA!^7O9pm)3CPi1fGf zYM-&TXRPxX>v=}RyWG8tJ}2H5QIoO0e5|%=URvdi_$tm3ej~q>Xp5Rtcw~y7DBt;Y zor~4A{OXH$w}d$|1I3PZG6SAETdZHNCKnN~uEwm6XZB6kaJC1SmD9DI?HSIQk!2u| z+Q>ej_7>5{(Z7tdGe+0UlJ-7hBJG#<%IK+Pqf~Yh<1x3WbA0q}=X(3QyIg|Aqz)wwV+EBus^twOjgUGHX8v+4#cGf} z%Nv#RSC%(I)^IM{Ti)nt{>t)(ytpiN9Gtx2%oU!xT}je7l=&-G$_{y>a{h80>8aaY z-gveAFubZWS5$Y6-XscPJ4FvuXO7+{3Sob=SIQR;h9BDBgCE-O<%q!#l{R98h^-kp z9^=OriV@}5a-?N`C?^cA_-gr~R;l2M`c_x-!{8vwh4K`6iPGUnIG<6ykwv4-6|4E7 zd`s>nUsT!%jwWxDBks))Uu}CuOF47JIInE4p60LD(q6G5v+d;?&cW4ewVv85R)~&R ze{FriG0mY7^Oyeb^3H^K7aMpUcu|-@iBizl)pL4%k8zl`73soq>#&M3|; z2P4mi#uZYA=!a5BS*lkqIXHRVeq--Z51d7ry<46SjZrM^(B*mc)R58YkmQx&L!J-W zUL;VBSHw@Leqxg3U2j6EJ~ZTUNlX4+w^wedSRdqYwpVpaDVNxO2cv&=Z>d-%WLDBm zly24Y%dK{B`d4l*b*_-oY%hI__N{-ZdF`vc%rGR5D4rNITuA+aWEr>DfxIcgWsVwc z>>`zBFw!O;D5m(0xTff)Xtw%C#y!+SX1Y%lQz?HgJ-Y`foldpVk_ zN0}H^tefQcGMDDw<14W27-h;)d3-sh@+ed8`pt~5K=Ug{nX}oUkFP*yDo2?k%dzGt z3mcM{fTPUu73fdpC=*r4?d6!tttNML1`7+87V#Kgfk4G5lSlrx=C6pe4ir&KL?wPG z*Hg++_HdP}KoOTEt|wktEp_yaAIk5P=EZrl)FEGV{D>DSfs|)4@xwq*s!_x_@ViP$ zBT#825LXIv77P4P%&;0o42)auDDM+BwB2kWZ4DuB>^*;FNuv@)>{;Fj{{}q`a^$ot zsA)eO2K7s+*BaR@-m1OPh-dLuEeJ+Ji+qPqm;Q`;S7rYzy{@ufmL8DVUrV2l?8jvs zcJ}YmtE#%u=UE#~sQRJQWR#*2D%NGH2U6fc6FV^+acR)GIHF&g@*?zX@A0$z)4?eJrh;m@uKNquu0|Z1Njzv~SL3I}d*3tgW;cp0RV`N^98DD@~4-t;F@T z`B<)T_J|e1>KVi1sEgRnMzUMS*|XT2%@zdzJF6}vJTfDtr&4IP`$YnfFcWI&cuJ*QJ6g?p9 zk;5sztNpVzy@yfgzOnDoM)8e(53>lh?H(JBk`Y|vJH=S&n|?6^f^)KO)`y~&Pv^$-e_V)|wgGn#$# zdvSgA7{6ciu#nR9=iI<(bp_cCP*<0A1zA_+b9Gr)kabl)SC@4KSy$zAby-)CbyYrB zmvsf%HBeWVbv-`45%iFAB|d%3)nQ$S&(Wt=>w0{SN0B1ek#&Ts)w&L!V^;3vIW8n=-p03Jg zb}A)LSGVY(uPJ$!C_T%aN}SQ3dzL$uu^b0VpRKf^a%Q#ksod$xvW_xW;#1b_E`9ba zcP`-x8+c>+@?wf#!XBv~N&|0iZ(BrJ%$Hlr@nw|$v~Uwg^_*pJ^7L-eP$!$(hC z%^9K})ZVYXD0`>qm8Eai3byl7@0`c4^Jz)PPZz)Rp+^kmH+$<`TDyzmt0;B!4x^r& z2YN%DGiLLy&Cq6kbB2(+w6H&nV&?5N9B~FvDvhWFqZ4X5){CBZ1hv-GtK`Tt`F3kl zf7Wg;Uv{Mg`<9-=)9LeOKrd2^?r7t_xox{K)Jqi4NEry}A^Jb z{?bOXg*-5ox(Jr`scBGgEVZ-gP_ZtxGyU4bk5hkl{oH5rz9Z=4ZPaGbhuatlB1N+) z`UD!6Gl%gpoROqPHkYC_tVTAEqD-ttHlLzTU`B_AQXk6E@V_lbQfsf5A1q{Uq#V>Nq)GR zqW`V@Fl4exfYPK zrYqk2O`I#0lf;3X^Yz>Gn<&FZjEy)@HXJlaX-ot0UcPIA*3Ql>&Lp9*x>P zGe)UZv?mK__(aNyTIpMUeQ+EVmDr`6 zNUt16PNg+2e5t~tw9+#&{7l2gH2fo-KVm+g%^20cD!i-0wi?)H*s25Z46my|Ktop! z>s@$Y*)qo2izJ6X1&HQ-#BLk3KHJHw%RnlzO#tdIy1V2x0SrC(&yOr z7D;t>srEk(f8(&;CT>*<&)<1`_XT{Rg?zm^P(7`j<7Y$X(0Yrg&0?!mwwT&X#`j|0 zWC^tyNnV%^)jGM9XP-uUE`?()qoxez^V!C(jI2kfGT9)gv4@jVZ?~lf)3&yyZEQ>1 z-nQ#ds6E5BY=$~IZNC<%W7IawD_q-J!&3_lr>&H~ZI4!plDBQ(+9pcgYI!3lY8kF% zH6NY`Q7ZN4o7;1ptQQJ~l8bUEofU=SDlbWVdQIV1`QTA#mYH{s+bx=a~d-0vyq3!IO zA4^Us7A#sI?-C=fhdL%4V|}2G8%I}PXrDrZQnDKs(epwY=+e)>P5CS zJk3CAqQ&B)p_e+#j^fSiLxH5K*NL9Wlf+L)b4FWwyH;o$N6j}|4|OJ1!{=G34Tt($ ziJB{*kKvecz;(Qp{oP3ZG0-s_>!3uQ+g`kUh^iJz@n~2c!U|zd!XochaDapA0--_x%uPT-gJ zebwFLor~1#`A&`r7Xj-2>%lKN-x zZDy3cqsZ)nW78Ll+!#jPnDMZ2&nA$W|}gd+&*f{^edD~W@Iz_gI~}b zZF10PW3xfzwpZGV?`sZcIjG;mz9I+p?Ug;{pthAcoW-krGwqf`QftcH%zs!a`HV3> zLkcu!f@3u-jWL4CBRXQ=Go=r7C|B54=4{kX+sx6vyhpVi-u8=lpK>&hx&3VK zeZ}#-I=?^1c8=!JXCiFxA>-7&+k{(v?7{EU32k26p@&d~gqxoUed4tHAmBI;LKiW}QX98O@Q%rr>Nko1QBIEVd(-vxIFs zTvfeT%vf8Q_Oo`j%9wL#r%tHYpxUDnhPJ-}P+MDUy%C*K3Bzc65o5ocYcTeK`X!C< z?#Br8%jz*!&$v@&5_Qxcb3S{{l3}Y{#`j*t-*h$Lv0S;Br|5)svcH7q>VS5zzckGS zOF3ffzOo%xa&$R$zqVs$1ysv{ZM+hyMZq2+rV##fv7Tah(Ycam8>4SE-@YyBoUPDS z_K%=tv}ZUMtflpaL5H!wj@E5~wy?jRw`qnpv%i5B844ZBzBY#;P$Q-%@U>$#V6j8{ z_e6@=p*>rzS?tiBJ((hQXrG=!G1r1U+ZhP7m+C(kvx6BI z^irM0H}3;=y^`5{ZSAC5M(5B=#o$HV=h8oWLwmD7FOBAT91%NoG|#7qDmZ2qQ0CL~ z9YLZQ3pmfZHY8ip`^ycKOVmJabzJ>Cj zIn8~G2Dbgvd-?okGVjkDh1Z(xDi06tt^5}nNJv(pllbHGu!wdCkyD9ZM&>6_VtrSx{C)M~7a#MSE0t$aB(fu&GKw-UdztQ>I&N5z_4J=T4( zCRdHsQ@o44_VhK4t`_|gacZZ}8vp5B>l)X}YV)AlGpnVtK^(DN=29Y4=3KbXYOd;l zBdmssPKh4MrHswYc`@}YAIlLfM{B9sn&G7|F16_#c!Oie*;>@1AHVuF=cJiiy{-@S zI!5VCs7Re7HAe3o_{j#Yb#2<2w5S%3-td5FP;DlT>KS}}Ef_WMj=%=>YYtRVe_8#S zZ6EPOTPw1@DD7zp5vjEO)K(qYwx;7-o!rr`u3;Z`l&jf=4$_<7Lz~ne!O`zu$ohzy ziT%i@vxn%>;0)|Jp>cUvfAt>PT9qFhOAQp|49A;30{Z>w7ogvO$c%VRc^w}$Bm1}7 zyn3@^Ky6+cA=^>e%%>II3-3O?Jce^bdx_sf4wCgbztYgu zPI4lV4|}U$NnO=m>@#UMv0wX4YMidzpyU|&^_3&#c0Q9>QRFnY#Y-i7o!%-TvB~+v zUm>2>U;XEMl}a1Zd#q3Iv7WkFAUsbyky#)-do4xnQ48^!bl){RwU(t`99>P_Ji&E| zA1I}C@$6czwNh)n?t&`MWGiZ4_Oq2-i74#i+GO?IRyxu~)&SMMuI)@ayp}R$Ed95` z3a<29$u&ZTf4yE?2)FhwMmN$oX(Gsgf8J1ZsgIdb90BS4LMy`Eu zCUrfZ!kVgud^&wm`BGU@NmHC(%cJ&fEvX_i+EGROl_Irl>&2}FGc2N7JhfqKBh@l0 zw^4G`@~!`N*v6G2^|pvOmhrs3eW}uRlyz+FOO=^1Ds4?+K?<8v*q5|jMy`zTb$3nk z@TqsC#TTozEQRE!#wRD2*LTs1qY{6QYypF4?XqPlqSDPM(3JXx@fdQR*&LA%JEBS) zlRr5VIE$;b%c*CwoyC{X%A}rVuCE4;nnzh5G!YE#OGl*9V7_K88p^zCZq6cVyyioY zn=1j#pucC&1QD!${90{IiaZMP_pmILtx59w@r(vDbBu?|-{rAoYtlrH%6CNtY{i_@ z#vC`VkFVda@nwb?$Cp?{9$C&V`u{k-oZ}Wz!v9ALtvuX3K#LeZ&PCDC<75vgI~1I+%@P5aY-3<%kL|pwWyZF|Zg}VZV)$6{D=ua$7mR zsz;XN&G9uWji~lLqf8%KM~=GD0JeFQ#rRTZ($8ld)KOPyr_}r`_^vEQ{-+%NM+F=4r%c%V{mw3_WG!qt}}xut9)r4nP1lyQwlnvz=0yk6?9 z@<5}KY=z7l<&(BiNX$~XWwy6ZNaq!~^90I)^Cc?5l(QzP!U@dWCq8?_ch8royy1GIYVyW1=ln&LKJgJ-t9B&DDdwWo z;jAt88Cm$0H^j#yYvRG>--}4#$d`C<`8vuz@s;@!EAw^O8}x}+#xQPKGRa6Y`R?2Gi<=ZE2iRLvD5k6rLXXR}JlFnp0h z8Z66)c}A=BFbZqUYvG3>89Hkz6$V$7A8LhBk5%h&oi{aDbsyL5Q-f9a(X#By4vieu zvT2N^e(rj-YxmRwss^jxs;yjITMb*iR=c8+3GyGK5yFqHg;A|%w0MJ>ncPx-DvuPu zH&=Xk9r#>Y2>c5^m-cc0g3nc(o=bbIf5+!iYmUDV-g<#eNWFVxq0e}Re>YoMMZdxl ztX>&NXq>Ijgh+>X4V+Z%RPD7?YJ-Z1iNysfr|zW|?!FqB@pkU3frS^ic-R=~di(nY zd=H;mAC`Cnzo`g?xP;#^e?hO&HZ77O_NXO9Pfh1e*Mk@f9m~FBpc5)rUB)ao4mytC zx)QhT;+GD%zq*9$L@YyVD)B5LX{Dq=iO5gjwRCT&@Z)+ zvWT(i*IhtS?{zNJS|BFpH#QNK01$W zkyV(^gI>V4$k(!;C`T1JdkyR6TtICzvcWXyH12p2$BOuXDc7D%+005i7jfh$w#DSp z=6pAU-wNzmSMMw&&$dGHX)7dewnFk_DOcw zi@B~V-DM&B#*8guyDA-Bz`phdaYL<21*l_l0mXGg=ZGr`Y6&`(W9y(s!koboS0*&d zqm}U__NLHc+7vgjHe)$&mq^@FiEnBH8m|aUbHmzN;fiBu;n_$L~%n zd%Xer270}m@t!od+>_>(d*HM!91%ae2ktu@Dq40A+_^2$dl+Z(YN=~n$*V6;T-x=n zMpN%htBG}{)yg_qvFtLAxJH*8`(n7JYhra!^w=x0*Pf1!O)GefO{;T_-Mzx+l{}?< z`AyKPl7Fdwr6V=ZDNBl3UJvJCac(b{5+HD8{K?{Enb;!sX8VFiw`*NSX zV@0a9{g93J*7?=&v#zM*RE?u`N6@OZ#K;GowSDIZ(RaC5%+%uWFbu#kt8 zgCgQD$0X=mSfBc=)<0z)y*RXOYT?v7Oix~AG3BJ}$s0brdh@Q~cq6otZ>$}=1*(^| zKGbDvw!MBGMQgTwe?3K=$`P=EvOf7xkAUiHtq=7`sJ_+J@Ypo~sXsEu{dQy*p z>T9hhbqT7MwVu@NP`#}6r0#&~WvwT5CsZ$Md;D0a{oQ_V@3%!ZLFH~rASXfPcgmwD zL*;`an46)&A15V_Dc=+Y*b0@CiUl}dZ>2AbBREG$owXNmMBR8AwT1MaY0N;=sjcGo zZOl*8(=6ruyM&oSPXv3Qp7QF$&W_8|EV-Pz@h~F7D=5ap%%;}GXqXM1&A#$W7w=J| zZ`jxDi=s?p=?yhdk%~@wLoHPA-VSCry`y`vuh(yHs2P`0L zX8N$b&pvFfc>AWkxKs*Tvop1}Fh_ybA|rT>c(rGH$5>m(zvj5nyT?8l_UKXR@A{Nl zk+oTm;!fJ8^#!sYDlaQv*blW4Hn1JT6NVSI{@2PN+LBwK`d^DkmHkS6a`8eDd+p9* z@cp6v*$-?faCg11^||)#^e)xztF6mE?3sF^j^&N|K>ZSWr|Xez9B=qN)bIt=CyH#f zbcR>8-^4c8FWd30%KGGEL7zRu5Q>d)(ymFHLft!&2)%|u;Cds;C`Ek&e|Vv?6n zXS<7XW|Df8KiyZ-QFe7-=|&0G{aW_aYLr)MlN?i<2efhBz?4%Ujywj!`>+R z=5US-qilq3grAA&n|DB|Py~M>z0X_(u30mg{--=RgfbO6ls#wdsq{JJK`mZWX>oDd z0;L4Cmlr4VzB(+J$ifun35*s3;v$AV)de0=P`#?3k6)aKMr9m{H|YPZJsDyKU>l++JL zY=Q6Rv&oelZRTh48N<)fSO~|cdcFFnzU7WrznA%T^z)E^lp_oxwm{zMcb22-Qz&oJ zGeOR)rmxjs&jkBLw)$)74{xOKPtq^bziB&%ua92fVOv*Ewr%B`dWrX(t;%mzowLd> zSt_Yh$!mP?h@~*9LL5V`D^_8<#GA*8YjUKBF$mxCIKMt!A79S9?cIWYS95g9r-SR; zsvy4|_Z=wLzJIQv^uX7+&?y5COKP)}7j4o(| zx;o!zertjni7=X)bAfL;CcUL|VK3S*%}(6MSs)?}JkNQxo)(tR8=W&0+MbR$yLM1B z0%r_ob#TTQMvh<1=z@qVFw#IT4QCA_3j8w06~ro>eW~|j?_l`3Q5*KhJPYWHD#~W$ zsozY5%@_m!zSx@H6h3=kZN?Zx57Af7x6d&KA!#aeiVlghMNSNRMme9Aesp^I>+_?R zjx&`#C-)P_hW#e|fFmw7{DAef6@!cTkr+dcDDUTS`=F6QB6Rk&h?VfZ`lYz9?^=N` zrUzSh@0CF2^t|zGBg%}Ah^!?(zu2Jh2Z0d!?VJl~?~;}R<1}Nf5Zh71CiF> zc8r0Xz8qa};M~HF{mPiy@M9|@+hS(&<4R217y~ggM@`uB4quFc?bm(95WPffOKofV zirDieQ4T#!{7~z;{5!qt(|6Nna}@eND`NGe<;H zv;~O&i?$Td#H#f*HMLi#ulY>X`dZC?^fmRg(AT7)uPsDlQ&W?wyH)CIYHP;wreNAmEv^HfIZ9udVIC?kmqICm>^&4fC?i!!JKC~>OsD_JRnsvRhwtFM*ieEo`N(OcBl^zXhX6!+{E_Abk&Ulhin>lx|oPv^IRpd16)zc#(gwVe4DMvPzgOpXp>AVtIqsLehEaGC^{d&t2DIZM_Roi2z&E`bl;1CVH6!XGj-CrWkG8+6a3!>s z?S&jWCt)Jm4Bv!Zp@_xcP0%aY7CG+Ly zOUZ52Y^B?vx3PaBZ#D#K-_#B`l<{xR)fzYyj-XDeO|TgraWeJI6lK`W&@E8M#uliV zC|cnxTcO+8wt|mrhl;-(&!{>o(PJ6S8yLOELd~kNfunDL9>dv3Qp80zu$>JCawK#X z+d0%)(_DTeV|)&E@m{gpxzyX(O0`g!WoAB9FX3s7xJghYjcN3Cqo*cul@TFo>)ZRzsBp9Ou%mH14&s z^ryFJ&lfv2GE;p|Py3w1S$x4rBK`73DAb(Qy^JEP zAyh2Km5|j@#k`HZG-IN8zi%_WV4SM_AV;gpPs@?)#Q`mU^!!muR?Hdy!`mp%ov>@ny!17{xk*cMx?MO%X|wAFDx|Jt4=b24*ET zV4RZnxgl(a(h}0S?8)u2Mi?vchK}en&!;Wta9#to1?kD>^Tu*-v+x;FCobw+ETDZI z|K?5|2A##8Z)9|*XsWZpLcZKgel>$?^a*qBIU?oa+EF3{pJUEwgUHCeh<9_$E#}So zK=lLgO&8M^jy7|pnK8{gX}WV6>sKqLQO8%~9r0=wG ztX;hM%JfC_)sctDNkq_%iSt|dM*8mfMSR~*sNY5ZjL!5;#!@#TV=?bDj;|dVGUYo) z$sKx}s{NxnT6F;X(^CJKMjz=Or)qBqUp6CD^P1qli8$4APIkSFinOYTlbWWekdlsm zXv$gQ(;`sz3D2wLznsZEf3@zl;&EOhN-BpG50%4u4|DyCh3Z-6Ju> zwU303NKYz1G`3w1FISYG_|Ec1Wk}^o@lid<obe)%K3d}@o}RGJst>kSlw)&K)r20u}Edv+}6$pVvx~4oDD>*eSZ=D zK&|E2;;~|zkyl5I)4t%nok2xL`|iH476Y-)@Jf_pd$ngd?|N6S)HBh)<{kA+6v6eo z+n0Q{`2O}skNKN@&2zm*KSuB2z4UMN-u{jL=_|zFHcO4q;+@2cqJ_mM(0-}+YK3j5UgD_PembDq zZ?(aS!gsQ7zA#6uJ_U79dy3u!dJ*{TCP0-w{0b8jRT^>qGry72qq3tdp&y9;sIm1+ z$RS=!8_8GfFX2Jz9mT-Z$13?u@EChQC7-G6C-NP+kH6c8v}oC9yo>j;hsE91^6L4* z?nTen=4OAl=PR4o-|hLL`}TKxe%KrpvGi|X62+I6yH|ONUh3DC(1)gX^sZxedRMpgEEm) zrtfS7zEYa+Y|l_uv#p$qlrQZo%1HL?K70?kgtM?#)Q}AwwYH?AT3JXwp^WCpFO`gh zJpyUP@3?`|k#sGolETJ+gHq#OsWVQ&-Hz5#kX z+mon`gDS0@%)8V;Pvp##DaS)=*xSr;ajfIHMosm2^igHGEnGJqt#lLj*h)DG-88%| zx3JyL{uby~wmVX5@8If9)HiW#2lw2J{;p4^{=k#a{q+vs$u--c+u5GRSzDowx6>#) zpj-Lnbbj9k-NqGXaNQ)R^5&WBp9(#l?XEPUc5(Jj>Zh^Y#eD*a*a_aSle5m^oL%4s zXL8lqlrz8t&fq@hP^N$o$koo}yfdM7oP93kbdZEIIa_bzGokft&*zFMQ03wa`0Whn zd2BC8cf2r3&=>Oi)Pzr*13ibmi|J|g(DOL&Vru7sd?=M)0xmHPoZ}MeZ{)lSp`sX< zr7?FIXJ16U57%5qxd7DSLe6~?XI%((p-yl)S5F7QxP>3VeI&1>el^!z4!wfyHQZ|^^m4Xurmy#d_T#)abKVuutJq#k?P_R$_OGQ} z0U~rYSGw{qPasJffj)?Dx;eQ)1E zxfQBE?rmK2HmExPZCrgLw1MsI9K8j48{6CY^)`^7Te-^}Tz4y|&)d1%os@atKX6<{fZyH+ zeSqylN!xjd>lPJ0$kF#hKfv}w@Z-VI!Cdnpu73dfAlpA=`v7zZ+driCfx^RF@qXz0 zxz{5}r+OsmRFAN~xbR`l_#ku$XMZ@!K_8~}fx<^PcWL3H9QiQx!<_R`%EN_^Q67Rm z!Wkb+cYHMIY>%?PwD56`eWdV-blxYp;$iAa)t{hzwD8HoqiA=ZO#0rZ*e)-8nkzm6 z{RqE2#{AO^{RH=TjPh}4Gkc%m_eY_Ra>e6?PjS`blof@~vi~XQXV`w0+T(>Mn5|l% zALoiExccMJ7Pg<`_!H32aNg(m?K99P*nXb<#|uwVRzTHGpJLt{1|7y3PfJhX)x*C+Z5{MW?EMkHKM#GLy_cAy+n_IS#Y@y)D7?(}%TVw2GQYl5_$udp1^N~4 z@Kvt+QsEVjzYKkub6#O)9|3)lU%tlg>!7cs`X90PHGX{ss@(H6ep?S+&t9n{K2~I| z8qanjH8ZzNU^|JL(yH^lvP#bTGKKxHutxS5*Ckax(CbyI3}NJHjI$Nl zjMbQ89qWGZH>C(M!2WP5r4DVYX1-A}5d&<1KPa(eZv-P##bjNRRS8FAwu#ZJm*B{kPt zbVW=fPhFMPRcOUlVg)VH7JanDRY%g^A}k`XT6(m(96@n4Cf8;%3e`1n*Cr~?BAzQ1 zXVI!EReBo7R;t_-a+Wfu)+99!SKgh3T(lukrGSm8JvZ{J($?4m(~)zO5tO#3@0PPd=E~BR znus!2Ptw*5CJZc13QprWlIVQCFICrMamLzRFoPEy&$)ReX^ z7t(LYz&Qj_LIqNcN7bEc~RaMJemvRT?tV@xglxVVS)qjt)broZH0P@m+ zBxi-prR=2yrTkPWb6w8euA$6DnrcYW)>WKyEn~g`+K}X|khwzIQqBsQ>$)V5C~eI} zHVSF$I{3u(l=(r_l(v+!Lgu=Wt&&rgx#lAsiC!yn%}4rC&I*}JX-f%9Ipt=G za+dOx($@7*r88x&1;{qy+{#=Fka=$5SeCPtL9(2sgmoMHN?Xbr%1iHn-p2NJ_LaGm z)RehyLb7=~_f*=t6{;+zgr&5lRAuDS?McqM1FG~9(M#Q>t%b-#$~*5&vQn0|l(X*T zs=JYt#BY_e79k^vyku!>2xo-MrJVInq#qGrrLDzCHf3q+e)#E7B&DI8T`gzb$NBH4 zEQP+0?E^_JQ`&kLb)~8Y;lIt$khz*GWUdGJRXJ;El9wKWR!Un+7Fo_}NitWZw58PW zhm=a0OKD44NjYj6^dYuc+8Umutt@9PL;ev14+$$vTf>v&CH|15t%tdba@KOF5>S@5 zTDkHQ%oD9pCA5&dl(tqN7kx5OrJInmLgspmIi(HR$XQ)U>C@1VxkCPGOOlr|SIA#V zUMrD)$}-mzT>Ds(vp$Wa>OziE7JG`TLeBaOa*;U6 z)0FPgmevHNtuCY=C9IISl$ur}{d|G#vq}C^+IkWhNrWIItmmj@nM*lqb&`wLK=+om z#1CFzW-LL+bd$OEC2f6)`L}SEI=DtDO9@NwLM1O{t5?zy(V?$VUMZAH_D``)M~1zzncfgcrX$Q=G?ez1 z2iQ+y&4WNS2hnQs8+(FTALU^M_RPR0M=Y|}$PA<|Ek>jFw7gdQNK7~K?#q>(oke<` z2LhXQwiV40i7Sk~+s5zSB$519A zNqFC5DSFo^k!YEpgajduaa@u`j-#fh&9Usgf#XI-IPbn8y@l5MDb$q`wBbvY0FLKZ zBe{In6Vkh$K+WihEe;#GCe`?p(WxU-d#dkv)A8W=GfNM zVp}=KNU<%knBju* zq~6L={bN=j?a1SljaEY2*q%kL3kk)(em1pL&=DLp*1Zc!MlPnW*J|iUjvD>0=a;-m zf0ory^{jK*KL-hCG_~^*#}TbsLtT{eJjz;RrSlS%vz*W9FG0s}?EEz5jh|nK^wiGw zf;9dwWF)sEF-V*PdYON^N&nztt<>^_gr-sr+5PeYv+;e?qg;t6$xzNQ)gh zKeYAs=8AGaIbpBF6_26bGd~PYSmuGjA?1E`aJo8pVCIMN#%g}pof8I!JQRLd$qD6w z!6D0>a28z8p7WdGhxV@Eiu>n;!7Y2{hkJ8E`)1~c^2%y{X#WhZSj`XRe%1U?4q43) zgA>|wGd~OtX@8aju1LHw_~D8@JkZ{qxnd`45uk`o4R+#f&OS8l<`Dk!%o=k9EQA4F7(Sd84IoLexm3RY(u$g6Oe zwKM0f6Sc{i=_1=eWF9bgyL`mV1C_Z2NlRN~VxI<2D(4yOo|Va2MpVePNVTwQWsb-PF}bN} z-qE`343x9fiT;S&xzd31ka(W+juuMiAZH?Nl;VO1oBK@c(AW!eLu=s_9Sp2cKOR@< zn3lNNzH-%x9nMTM*i2@za;`ep>JS$+Kabd@5Jd+g zOI;v__!YemL7`Ge?S_gr<6rOsK)44BSZ=B^VReD%5NoVCOaU9r+ROLTA)RP0cc z(D_PD$yrORFjj7N<`N?;F+UkyCPvuKOy$faMi?u{iU>N7txng*ENG5c?_m#hrZjhk z_s=t-85FZ$m``G4N5r$OP4lj~IecdCyDs&u&NM5V%fs2&9;b9;-<02(@iWifZK=1} zFO_{_j@MsYc}F?OnLp%!*3{>eee9b{l3bv~Fr40G-;_tkn&FdZ2W1HRX_k(ZDr}{) z>|vjtlKR=?B$F5ktL&uypvQd3EpildJ%$9O_q=nEc}bLT%voxF+>oh^f0lEY2PDf> z%2&oSD=(Rs#GWUQQG&7$DpQ5rWq&oBuhQ55%ideZZB;~VqtkWMC?(z9jevBgG^m7t z3M!?Pl8PXpVxXi5Vxov3V9+QbrHF(`sUS!zic;rV?(aU&BQFRjp6|TBAAhWC_MTZY zd+*6LYi8D_K7#5gohnN9=Xgr`UDEQBPB*Rrrt>v%%`la6Tw_e7AJ-&Pt)PA<(k{of z&QzP?+USh9ifgH9UtkrKCe=OCVaK)F>2Vd;cBjKtTnnBSSJeNKcARwNq%V)!07-MC zQzs;idZcA1eLGplr?wQ?$d67Hl5U=~^^vZgS{&^bjWqhD|7@?+dP&YCTldtqspV4p zj?Nd71!`*Jv{q0IIZo%Ys8=k8vZFNx+5<>7TOvD`B>mFr1NAc0pTt)vEPP0Uj#e$= zs~OZwQ4bf{*Nj#?s0X7yGQKJjS+b8-OQ;vjjgtE3>m0hlVU9P-nJ{qn5 zMJsMP-dP+lb0MZMx*`@?88@1K=d;`a4l_lG1`Mr)+h6aMq^O57h_P5X*g zgQI_dM61OAvp@W&=Rc|6jU-OeY>>Q4J@nO|*Zr^m;YNCm=nvCm8GzQ5X}&=xIcTIK zEl2eCHj+M~(J_8%m-g#Na~B#vNtZ$M71DRm9EBt#(s$4pOcGNxDo5vaX^bYlMts*k zozbOT`&54u|HF;O57KXtv=~{zj%FE&XBLUi>qh^Trt`YBF^2v9+JCg_AGKQA2@oGG zX`T@E$d_9Crx7>W0TBOx6!q^U$x}Jeh#igAG=4{tJoPtMv-TgY`qNyDJpBU7R0rqZE5L=^rrSINRpG+(5Vne3vI^|I(M7$n(6?UN+yg8y&ZAnA`Zlm-55 z57a8CozQuFvVTtPn_5LQvyc9J82t-|T0f27(ccc^XZuOoCkytp6NB1R)Q+M#Yh()` zYDe+eF3lsTHIe2pYFX6MXhuTwVCtEolkn6Q68?=rvlaSx8_i*;1=4N{vZF-WfJiGq zdof67NUbbtS@DxIRN9dR!pL4d?cku67}o<-`?G{dt4dNnm0DzhFw(tJFCNVdXoe7J zW~tO-f0hc(B4|EAB^B4<(u^WHk41KqNWUA+NvKrF(j3icsHEb$V3N9N217I4Xbu!< zjj89Nc@NEYBW*JEVbrftuNKXvNK;AYq9RQ#l_kj}WObLyGtyDhOt=Dig-CZzx&qRI zQAtHJHqz@-Nzpuybls6&H`0DnsnK~mnhPdqdMo}pd!#ue%_eDWfGh{oj5nHdlDthT zU!)DDIcMcR%O(d(ipr2mjsC?I&1h-!GHa0Fx5G-&lCMMIQkZPNPNxsZJ|bDAqB94ynoF91=xjpbGZ>V&^zD=rRKE1>loOP< z(a9YuSsJ71+v$rbKPWXSL+X3UrdMPUk;<29P_)ON{>w_=LFv=CMdxwooD-d5qf;T2 zDxG(_6c2^QIq75+on)hPC&WvqLg-`=@lYPo*#d`aI%!4kNasq3TL6jYO7%8saZ&A! z>TOhuqWW`f_4ZQrib_9TyXaX|$D-PG>3T(9No_x>UCIB9`*;1u<=R42OXDqq>L;a4 zE%D;EKxIy6_Q+ZnNi6iAH)@A8p2knUk!(Y@#ONdqjm7kbH#(_9<8}NzHq8{{Ht|U+ zAZxKy(j-&GZPk->L1*-+bV%Ny-33wW`zPNR|GKC)Uj7@SQ;}3F{#rNU_T{L4(Wx;y zk3{v0?E6LM=BVtbUd8^bTa-_9VvkOzB(7tZs>2u8^Zy(5kb0qnUhdNU8`b%QUM``3 zyPA3!^_EnA@f4!gbh+`1YWC&oA=Lw_4OB0veo!r;Jt*{#1FAh#kElLTt)dgF^zQ|# zZINX-s_j%0sduF}ry5FqEcFmnbE%J|vZWeLeJu5#RMY9yDwQgo9ivmL(YQlnLwt859#UDH%4Fj*S40p@4Zs}xwsGfcXgHWlg|D{ebL{wwadvNiN7)ab=03w4kz>~ z*Cr>#B?N^WqY_Mk(xiN&93*=WWc7ibK{jj2`UCy3@ltZa<;pAS8>10C8oQ$&{&Ice z#ouzN`Vg<}eBH4q+ zc#=S<&O{Ojjg};PM74$L2+b~Ow;SaQ%`s_~Lb4_OoA_GVQPkVh6RFRq+7xd`(dpBx zm4_48^LP!v7J2weV@G1y`*P2UOWl-9RL>Jy)?eGyrQ}%p?zl8dxe&L(c{OruT!N+3 z^CZz;iyRx5V9EA1$)0qUHj-w^ek%27(Vj*6hYZQuWU-$9DNAol_5tEjcVsb?+CGg7 z^gr0>&1sxSgSVo0G=Gi@lrtoOlhjRhB`$kYuS0K6vNw$vB!QFEO`}I7d(-=oL`QZ| zq7&#OMbP+55^BOJWg1y1594xRH2%_=cG_o2avz#=u zGNnalsG}47ly6s>!Cg%)y0~YibxyJYOfxvLpFp-0DBtKTHreHg+WW;a*tN_-{=NsG znMl+RB%XuBPbAaHagr#azYs-#7LNX@L^XwEJc=9rkC@~Lk~OGbr9OmYjrc!=sc#|e z2Gtk(R+1_3ENvgk5ep24iynw7^Q!S^OPj5nXmwGUI6Y9sPf1o#^x=Vc{y$RJ_ zic4=obvFr~YH)Qu+A_6=c#9^9lD>}S1T=5BnznqU{)$>6eS2ilJkpuan4ef@5=ksk ze??D^_gW-PUurIS@mzrNj&d}TrxN6-E6E9z&v8v1<#SxG_)l~lm#Sm*UI{hr(shi= zG+xu9I`%(jYSA3++UgjMpHX`yyK=PRN+WY*lZa|0t&`KZO`}m{lZdqcG{VzpL3)q4 zO&`*GkVHV^CFwn=x1%1J^d2NZkfw?B9wY~meuH!!)T&74p!O7vE!6%z`ucn?{isxdzMB+JVa_Fnct_|%RNd}5EhV*}u%(y4nizKkfjtQ+#k*<+)m~xx` z96)(X`AoV=(jd`}%DB}h%59PXsfJT-la7;em~xwRpOnLt+oThv9H!i+e=AZBQ*M(E zmGYMInRKh9L5d_kY6({-2S&YIBn?KrT)cmy(L62;zNXnwNLJ~=0 zS&MpvNYfQbUGeLysSnqC&P#8bSU+&R#)3%K`fs%N@%4^KD;2$G!g>eUHKV#sbv16$ zjOr@MdQ`Wmu2SAp??H8y%7p4R)m17hs@qgosSK%ZQ!hbfOLd!i1}bx^+oTaCnUqS3 zMmVY?k#>}1JgVC?;w0#!u61snSXXng{^4@t$d&q;i~Er4QLm^KTxm^*T0va5c5!)K zuRivl<~g<2_;?z&)ly7U%tIV6%m=v(3%<7h0n8aage{{)FQ{hvMkKbJ$Ohq+i9`8zp;dYHdTBP8R~ z_mkW~eGZM7)Spm3U21)be6MBQlX5BX`qY2j4_~QWQ+uINAkwSQtbuAQ&4Qy@LtO81 zrF7ycTuL)T-yBcpdW~O~>Sw54lMMfN>nVwK%k*9eE%C4YOk%n2^4AG-hpTCu|3-Iu zrFl~{W1`v9KU-`5r*lKnv&6MMG*VxSo`?23#kD=ut6r&ZkN4_-w}wS!`fv34)b1~q zhpApAXh$!t7rh!yMPmI)Tyt_QdeKYC!*NNN@`lr0S|uU#I#RGv`p zc)fMSktQVCt&v!#^mn@A#AD^9_Blj59OBwSvh7Q4B--b2t^8Nh#xK<`#d{=LXSh~5 zEiO^V_bFXTM{&8e45|b1^+9SQ39E!uA4nSfpX-C9St0qH#zC5ekbF)fBlVgzs*>zY zQX9$VBzsfeL-|Yl9wSXEt(Q{IL?a}Pl$1L(+C;k8|9b4Zmi{D~ImTDUDNiB^CoUyM zJzIjT_;1$46W51pT`&HhbC75ZBKa_}T$i|AL}Lfl9C{j+!KHR6{r&2|)vgaFe(t5l zyLd~a+7M~%sXdZ}9oce@>+LTkm(ur9UleI#FRdR-tbX*HKVE9N)=6^U+J` zVE;GCrIBoQt*cspzg~8we(c}Y+v_DyUaxfiOS$xVw)e#CEAiYg@%7b=QObRJQ_|jD%YHD@+$Lz@qS+bc#pU`C`j)sZD6R#H zODt3laarh6eblwi0qIHcJ$00FVqI(E@ibw@=+b*`FV?YKO&h%SI(DhrMN%ErJd(Jm zX2ok7)v>?UF4}!gb?$ognb#s;#U(2mpQ(HkG;#@h4x>62X_KzCj{R3U-b>Z7f774; z&pMV^e!KMb)zqap52Zl)OBzD@?+NufBw^8B@$0=l75$GSzA{CB@u2mp%db!Ub!Ce7 zw9tChU)QJND^scP1+-FiEptzj;p2O&BH52};=kK#ai#fqd?rqH|7zB!sBR>zQYEZU z(dd(~N<~sENdfUvrV^*p{p+58nh(%Ci+X{?*VmGt(MliXYQm1Mzst|W`i*EVAJ=kR z%l?qRu0_&UTuS%yZ^}A)xBsbU_`9`8dWXL|pF*{ma*5VlY4w$A-PN8?p?tggopOJ_ zcja38c6!5veRO}-_eOpDf3uVPpR5bS^`BJRX|_ls8EF!(WhP6K9-ZhT`7FL~gk%ZQ zY+P@dmeP;!bE6$@@!f8;;u+uPcCr5RYT9*TnI!RC;J+*{s-N-sGPRv(EiB!ix5>$Lug?fg#CL!JnU4CulO3%7nUq??#cp~X-sMr1bGb!W z=xA1Wxp_+TMbU1$=qaRyiPnkY`{+nEi0g$eKC^JW`if|LzrOnIOZBmrn`>Nd9z=PP zFuT0AeUE>)ruk3%qN_Q7ak;*TPF|2j37Qqf`y$#CLhJHzT`|et)aqz2I-MZD8eQ@A zklQ1PJ)yTrd_Lu$p6{T(n&ef|jL=T`#QkUD{J&H^x!l_K<>sWo zFN$_&N9QRnC9~1H)7VOT03w|O^;(xd^Gok`z4uF8YyMp8S(vNMpZ_oW*#Fz}uV}q8 zJ`1DTL;8w;zh^%2y3(cOBAQ3gdJ2^}?ZUm(S+KZVMDppsm5Z)szLU5ulg^v;;M5P% zIG9*tK&>QN8zK!UtvJwX0O`=>5usNn#5;7s3j*p{XuI<(HW4$ zZTxE5SA0yr8oM`%*IsF5irP|C%9q#0UCldOX?{d4I+9Xoub29>7a)B&^;iGf#?8yg zpO+gq>ASCVPBXFmd9hq^C7FlXTEYo&(tA@|j-PytYayx^V$j;zL!rQFCCdqvDB zqJN5z-8r&EO?q&$6i$|?Bb)B!Q6gjkk}P?aL!U(U@5o**{W+d&~dt^nPPS}xUZ?Z~FC+s3?-ejMeELoD>O8OTDS+bls{QWB+IKLchlct$nq+U zQDk|KEK$>_OBVJbDIv0=L7I}t%0{%>7wtizdKs5HqF$2r>_&T4Xw0G>E!sU2t$9!{ zMsf|+ev%|evLRU~hFWl=Zv1bm8#l`9e^*<+QC>I7>&93a{XhD@7%OkIuN&>_M*F(a zzHZDNqPfG3{_sYBc%whO(I4LE4{!8`{~L8*H^#3U&EzXWBj@?e%%keJ$Qw804f^--jlEd$y;wKo!yEG94f*hfe0W1X zydfXnkPmOjhd1QI8}eb|z4|xg!yEG94f*hfe0W1XydfXnkPmOjhyS&F82`T?wC7h0=Q~H-W7a5(1jN5M@n+^0v^d>SOhZ%FL$Y`W5vN?lQ9(xSp;)#9e0gDz0a!g}BSiX5#u)^&)#sy{=xu zsnMCh*Kq$5u3l5)*^BIT;OpuQ^$we_7N~cD@342-2Wq~W#TFukS?nFQ0M`qU;sm7d z5_^G-XK$z%KyRwq;Cz?OX7khs>TU35W)s0PfjtkdH`Vi?x72%Vu9^p&2ky7n+u)f5 zo{8)^aJ{9T1HG+gu=mwm;9T&%39iiSS@29^Z{RL7n+)E!)nw2tH65HY*mO2Wy{}$J zcxE<*%~J2EDd3u=UV;B~_6mDX%~4a?JL+BF6u8si^9q~BW~=wq%WNup7dRWfFXL*q z8ii*)%Npyk>?zhnk6~khV{zY9k7i?7Q}{H|jdWxE6l(-}nl;oVs<>D+d2&x}F}%o?!J5GLqHRPp}cd zdT{IL5$thbUAVP%9sM|a3@%|UU0bh|udWT{Z^2Axj~&l`5q^Vjr?b>J9m(Y^2_lZvh+Qt~C5hsnY6W_7OX2 zOY1WFXIn~_2A0+*?Fm~(m(?fiNw~k*lDZVI6vB?%vbvl;j_|Vjlr5o40!t$7m@TKv z>thHnr+>A@bqQbzgf&!e$+u-g)d+4GJgc-Sqds9Dv!k}WuAq-1UU_{4{J+}YYz2L* z{>>hR+d#c7XUPU?mV5`;5O-zOBK8R@i@0UfX?v@#s81utt@?LcQC9+xHmGy1FKWt@v0j6PZ1Ky^q0ITS#x*Sp~tIDaxY!R!k8mM>Vd3(WD)#pJ&*g1RN z5)NTQfkW9acGjM=!&rInms4l#SzMn1J;Ii-#qh15mH_wJV!F8Ahi^GzUy+~4Y4R2M zG2H3ESAZYNkANTH?q!610{lcSl2hRlE|QCZi{%nI1Dw<4Qlwo$O@ZGM`6_&702j!G zz=gO=9eYpCkvGL=%lClq;XYL?b!?8j1@t~J72J%mTVn6an`7_F*}&Q0%M{B9pP@+S zRhbJ{bAg%Qrir~H-vz!4zBIA=$c;3ydaAz48JjET$(*rVaEHnHh&K#0RHj8}nplq5 zJo$ml5z7fT9emQp(#7hkdMZ0YK9Jc#^MUgbCwpv|94^x%G+iuxtd6Ryma(Pyx@DkS zRkm36*l?K*^q9mm}nIwv64XmV+v)%&{!7 z5i&FA3E390GQ_&G<*cIW4yvTuz^84jO{|uxt#ZdQ$DWY6K_g{1)}2*S-9VMqeXO#& z4cHBC>sU=y3s?&=^Tcw;M#?;(QSx4PAG=L8MQH0-(^w5vQ{996D!_Z;-VUFpvD;(S zRSlIF@kYtKpeJQB_}m`L#9ovy$xQ4eIRQ99P6SSrlYo=tWZ+~u1-L{m1x`U(XJSjy z&va$?uqvu6sH$p?behGQ$EvC7in}xR5tc8OH}<4#0iWiv7O|?TnraDb5o;Oi%BrgT zv3v;44;n2Wk%#P0_ECAz9s(Y+kH|stM|;o?g3qIJp!~@mwgbWSlWi62f~U4Z3N2%U zoz|nGy zJS1O`9*{qRYd_pf>?edClKqg<9@`JJ+uninhsY+eyIE(}B-WXA0d~PV zHHmd%ce8@AF>^K8x6EL2G1* z*fVk*uq51v5c^yE5NM~}C&_ZhKE%t&ipRzwM)BCQh*LbaR(=jF0lz+ovD5YeePj1Z zvg@%|?t|NlS?63Y=9~w57l6UVfH9W@n8YOoCUx8ui+wKF$zrkMaC;-YZ|okK0ro)l z$h~lj#)`$($)ce3vPi6GjBvf&Aa~f_;M`$*Ax=8*lKqg~a*r$=D-zoP+#ol~)#6Th zms}%$u>0*AT(1^u#2xZZ`0Piiqy;}&8u?c4!u2k>Tdop!$@ak2aJSo@vKO!yp0rkc zZ+`&(fK)yct3-SG8K{H&9R6#?r||0_KLvG^rDGfACSYN>>k#_6SSR+`@9aA9o&Daf z6dh$Jxe_rt%4P6hCzgp~=v$YGJdh01u$}T-nFjBZmaPz-;bkPp+Bha)c5KxRwh%& zeIfV3?=H3v)SewsJ=lZ52f@8p?Nja9UQh@2qw2|e0DB+Jxl`^^ozPl#soii_ss3yLZ~)S(5-S_~QdR+NmTT<; z@`G8yl z{?%%Y>dX4E$x1rqrT{0aDM~o$rUIv^sVbQhZjzd;6i_+s)*TAiBzppnK$6JZp`bfN_znw+(F=cR1H$8TuN6lRw?$itO(i)+=?9EDZUl=$(^8Xa=hxp z9%AFwi*N^ne~=oiQoB^{)>y?D%0_g@+k7Ls$?ozSvEFXL^-kQqpvJ3**bsG-OYMe$ zf3T_$yA}L9#5ZDt9SZ*;>SlM78>-63D!_jj?uM%EVh2LEgErc7vGVZWCbo->b{lAu z{mkC%hN;i&Fg09l72CunyA|{W@C*B;{nQRukEu_=HC%lywu&$9O8c04T&+aNV`>ZT zH`^`ZYq*?0#2$uWo4#zVV*Fv&7uOtapRhxHqXd5eZ!W;Y`3n2E8lhGorN>q8&?kHY z{6_6m4~6Y&2XKe#6D}Z?&(#H_u~tdM6;hZ`e#sSoPCc)BhF+mbtZ&$=wyD10e>j|D>(qL6j-7|A!K1k5&#LEC zkI)mG{leF3tLg{-zTqreuQsT&>>S(|;NLG8aB6P&IQ6W0F!TWb^YDKmoMC6#26YCs z5x7xp0&Y@Ys3*e~^)>Ko^?dk)jZ=pI!Jbj$)C1u`#2t;$C&TFQmD-~24-dd+OxUcx zQe)sVI{eO_R?n#4!T$#v8@^PV)mVg%2~UMD)R*ch_>9H%8TN%rAwLm|L`wOw_yqWg zNFh%n?(gh0drCd6Qo%o^OeH@OAB*HNgR*@JS_8%MZmzBAHAs7XufICE{tM z`BX?MlgT9_DQKy<2|TIgO>&|5Q2fTms;AU%Ncl8NB9qFcA_?fYI3X5-?}S(Y_Zg({ zbco60;+TlZBydl{|AhDzaergKvN39``jL%LPpAXz2{jVCc2iNZ}wm#YU?! z>J*;%EBl#^QctR%*?zdcuqV}M;LmV>0naH`M6I@~Y!S7_t_Bu`TU>1xUy0(V>6>x= zmDqyo&3J>K*fP7^{)F@oF)xpby~4`?_gOr5TsX{@*roO`TWXg9mw~T@`a*muN~kZz zX5eO|Qdq6BAKJpI2wW%kihbw|J=`N~v0Y-1Ace#1Ii&V%uyUXHPFU&S9!2O8R#NQ} zUx<=OvxF*yls>eDKpz1=vL9O`t^7_H(D&jP_>Zz{1TwKVd3p+P?gCAB2{LF^X= z)yMV|TTm^s$5=u2iCu*2Lhwt8r<7DF)o!s%q*QyvZXxAa z>=6ajF?O64P{-K`U_spFS0~s>;7RraumJ8-gFlr@tqzHwL~8YuI4r8gx`pncTC9KQ z27D|$4tzX}0FDSx0G|jWfg?lzP#vMwV%1~A!(-tl^`kf_Zc+!uA>bjTl~4V^zGwMV zez-NjQ$6+_?!ISLW987}}JHeN!_dth#$q*@cWMCQD3vIz`Ss`!QIMot8HvM za68)p%!9i^;aBmSC>VYdr-7%%@4(;1AHYAv8Q>Xl7I;>i1D+G-frY?p`G7DmSUxa3 z0(>Mq3VbvS0uBm;frG;k;E*sh6b`4vuc9!XQYaJ&zlc+!2z&~Mg1T0$cC3)D8LI`X z6)UKVBD6>-8h#ePh{C!?tY)k*LJR2vx^}Eitbi^EH$U#`#ER(Qp$4!9IEv_DVR$Hp zSVcoVogbn3Ky_n9;a@}-)kDLukW1xOJ6JBzH!QEtr|ZV@g6hSRBDAPZsx2QHlIokd z<#}{oT`!ggR6mwXr{*{DWbjX_bL;xC2C>{a58UKB6;I8RBQ%-Lr5nT=#&RLNK`ez% z$y4zZ2u-ec`GVoR*yV3lY1A$+?`0`2-|@;>C_JY4czQHhi)9p4yqbUjr3FLWIQ=ft(9KS)-i=N*0Y0ZAKL=lg81A0 z4xdhC(^XMpv+3;QB1USRlqcgiX{pz-&zVH*b?gvg9aM+ZUbc^I^V<~0L zcEGm4VsP8wssyk^C>icRT`C4FhOpM~D+w$aN`*VaN%6C|6QOqmrn&x%G0-a33Sp%~ zD{z$xcY)_l-~x;X7ZlU0*afwUt!6C|UOKb{l>wFsWkWOY+y$JEabvgN=F_X)pbV-7 z!pnvhpaS71pG$qi4*8!v;Wun2I}D$n{9&I{_mtm*eEG#6R!4xR;2s3eF@Ml! zS2@(r{uh4)ctjmld;D&n0hmGEqE7mw>KO26xF`Hce++m`9aldh)0 zN(CK$0sf*+sawFCR^I|jr*nknDE$)PDb7pq-_&U(g9@jBr_`@11HXl*(-}bNbxDMl z;1DdruS$g9R7qU_s(w@Hc?OmhIPc5wvi!Wi0QY9_ zX3|{|k}GrxUH`;fA$RDEJHp%{Pbev~g{+|zu%s*{vxjV!2=yQisH$c zLQzo0a5J7;R^BY{4IRR*GGz$B0KO(jBM)x^%F8Rl|5jO1rU)rRV}#`8jY0W<`FMU_ z1nFfAML@TNG)U)WnMU3h?hTc|Ur|<)$wG2mCl4t?BiUHy=Z!!GcthDp5*FYEc@oty zGzv*ogU}GzFeFhi)hIL$F_i>vGF3k`05(8aP>n;A5D?xtBv;KsePDfrdDSE|4Ibf5 zLJBosGy^t6SOeKm7UT^;Ie1}NMBWk#%hcf};4L9_NGq#^`+)c1y`5?rZVwJAH4R5( z9yVVbk@H0gW!3GWUa-o+tuJpz{j4u@pr+QB4dB+7nRI4tRJBk&81U8u)(O>sbweFs zy-+u3RXx-I8o2djeVJJ+rB#jaLx_bWz$D>t_z9R4co?okSWTdUdnhDB-W@_%GF<-z zw~)Lk+zh-qqyeT0X@P~|mk!^OR;H7cLS(xUOF3 zQq{zDE%5yos>$l|H>6!nzQMT?>J9L`&UYi$uCP0#gZn0DimNvf`Uc;FTu2x8fOZ25 z;%$Eo)nyI&YxoWB3~;{5XYdP>slmKzC>I9vSK$ukFv50COee`5Ji zA)E>|WKDSrDb0P<{K z_%0Lx4ggnrIRKPFzQWJT3&0CL%#G_@Hn%-4Psr@J{{@%>ZXWpLwt4I^d0b|*zsOU->~QnKCy&i*kIG|m2;S}% znbn?>zXG$t)$q@2wLKz_$}IL*`5Q1R+|2ejc^a4nZi-kwnID)RZ#I+#xu%Hau^>9cZ17l zGuaJ@yWXvFQ~Aq$4S1*WjqVnk(QZWO2DjS1%%}0yZW@09xCVDmB8^Nkc`UEY2h4{z z+vGCXTkIyp+UQmx#tZxlm)>TuU%-Ep8-*B||KK9Xma zpThq$_o+*3)7h24PhGND9+_7r!&8#SR={VaTjA2!wDtsWg*)MHwrT90Jc&(e@8U6= z1egT(cknxTQhNs|nQhO5jR9i_YsZt>940DRuR;GaP5J?EeIS>$+Jzu?FF5&Q}MtbYzZFXDQ< zf6+h2ALlRn$N31}g?HtrTo=%B7m%8djq}ffa~vqEdyd>nDVXa3_OjQfP#F(uOzU z##-B(A9ROYZ+^)A1nh&mDPfEI8u+!F99{|&!dU+j=qcb+{%QXr{GRqx!&h#Ln+nb; zp%?GXe{$pDJHn3-FT#B}Y<6F{m%%eN^yIw|+7ooxwf8OkAE7 zX21KvNpryM2P(Ks-U8SH9Cdv?-YMW0c~it{;`^ySzPIlW?5FyxhkPI3 zSM^i9fxUe%KL9@c)d2Odf5<QUj9Bm5IzIcK-JeHL_MtT1K#Jm`A1Yg-xt^y z9DUS7s+;cv>h4>s{=OfuAHsSgq`U78y5F}^1AKpAe}wfy$o;+-=mFnWJ?;kp2O#W% z-X3;@3wlTR2KY_b3}j||*stsIdVIgG$Lj;@^9H~M_`;q@=>gvp^q_BtblR$R>M{Sg zze5f8j{zTpZx7W|J?MK7`SY%>Z^+NPhP(#9Qw{UO{hi>vLp=zt9v`e|W=9|#-| z_nfQ2Yw~mMJlwa#K>vt;J4}Onmm2Da0f!;}1Bl(zKcMdQ9e_Rkz5cAL$!qbm?i}3q z;Ji!S53UaWe$^56`F>n=#I=h39^ML%_(%O);cd8QTrFOkpK-N$9pG8qo!1xi=5QYL zWjLVg@Vfi}@?pR3j`V&HZ-z(xApa)Pc+~&l>LBb7cLweoVUQo}-$3{v|GWFc9ni0b z!G4H;J-h+;wJ^jF1-=gVwJ_ATSLgJ3{be`@`Xcb^K5h9!hZmqXFssbd~-k7&a*9mEqon6-`?(<0h@v2eLL6I z@eANH-!8CCcvHT>qE^DEDQf2&gxB#4;lIExw2gTa{+^u!pN)9trZC&ShwC$Vi;dwB zo_tWhYiGl!wtY3s40V9DZ5=x!yc%lR+IA*zW_T^sg-;z@*G>;J!aMd|@Yln2U0ct- z5~hcm_O;Mn)wH$X*0AkW2UWw?gj?Uv3a^Cv;HhV4*>@1Dy6vDks_M1|+c2u2IHCr8Se*12CC*((HKKzvWf;*(E+D__jRTW&FQ~^6Xyc-IDC%>&??^c~v z6&oEjs@A|~b*O}^dsHR(bye?&IpBC7RK%`D=$cT`Rv>?heppviWnZ_F10 z8}Y_`C2GM7xPAeApZLjkiv0w!U+Y^MP~g)97FeMAe-;eHf84kheIpptf# z|IAMVPP4Dr4?{^?3iuJ+)&3Pb9k>ea7Qfn02Tr#$?7~pWmIi(Z_bb1}&j8M_uiDN2 zD^K{UooN?@(zXn6A>1$hWLcHiUfmr^)(Ih@IBI>q6ixh<})D2%iP|ugQiW{Skds zOE2IS22UYY&A)Enu+{t<_D$fM_ATIB_HE$XsQ1{tIwz0#);i@YHg45uRVx z7C{Py*{5MqC})eZ-}Gr+6h1|m@<;VCt-OSL2m4k32K)_S#n@+IaVUm2`YhavyTyV2 zD6=?de@q|O+AFy2z<&p8$4=>AHT`2|aVQ5`0xS=AkFMsc`@MRTuLi8<_vpQPBi^qp zTN0LrviSGRlCWFv(bfHKPz_)WUlUl<*Yf-HdcOgXZ2sx-`;Q z7D|Jbha~Vjq1&*Z^)J9*@Qm-l|DFC`ukmaB_j;}W+<&X9`YOO(a7(e}VMQo~zvC~R)m#-{-d)ZJYyI5g?=3H89UC-_Y3^f z_8GenxX^#-pM}pj`>g%I&-cxdLNoT1ecFELp8~z>pM(Fi_BlJxf8clOZ*>)56@Qyw zhWGqlFVkQ9HMrjDzxHG8yZ#;EQ*fWRbNxKvJj5@7cUc)qfIbC&iu%w3Pif9tu$Vuo z$JlrLEI-DMh1(Ocp0_RG--5Md!N+`YR?e2U#qkfIa(1*GV`ur%ptpT1gtla@nD@ay ziIBH}Z~G~JIo@QMUasHrTm3isHeVUI6K-p8wqmWB^$yq0dq2uf@l%0M!X0U+`j>&D z;5GqIYxaa4X6*lGS|(aZL>X@ED2 zG~#_f*QXJ4@jYooPut7hBzoIEz?VKLno0?qJ6#Rz;?Q8CTG z0(=D=1ra{O7X-cPiy^eAC?+1aBWwZjs-Ni#h?)L1U_sm!7mwM;ZE=Ja6Ss)uqQAWb zG{EK;ui-oMivn=-i_*>If&cO{VO zDqY@x4gM|qYh0DY{c2rOlz>~#f2Fqox4^%YC@EI!QlK?@q3J5_5g(c^qARegSZEfQ zd&IqBfmsOmBhy)Q0d_%HRZ&W;(eur{;yy7ST=$BP&E29iuroM5F!zaW;sY}u?kA>` zxEq*3bOPQDj`9V5U-n<0M1X$1T))b5OYmO(E&IQ?roxq zSgYSR9YlNazL^WRGW^!+Ii|h1OUyCv!+p=pF?WgLNWZKv?lYSGHn?sr+K6|}Y*Pw8C4F05w-If{Ec1?OE8a2hn$qwur~6#5({};yba%Kr-8$XgRmNMjcWd?Mz)E<__6WVpwL|zi-43)~ z*Ja5Ow*x}kyN>QwQBibs6-6arCDFmvV`-3jJ@C|J_afeU-N{uDw~9{S?C9>p{RVxX zyBBUZ+-(4E&>MAqcC%08>mzPG*3Wfw8+BjMCSX6fcO!*P?qS#0ZPE?cP5x%z0Q~h? zXZYXkI=gbByy)!8iwfc)aD1U30`DgME}v>%HnV~6^4WZfnQGqQFPmw=cj5MN54kUN zA6Lc~^L=nt#=i%i+59~|*-SCB_&aiMrAE9&j`+TCAWZvR$^Xb6pW`>yypZ9q$*V`5Fi}_pTZL^5aGVR17zL?YX z+h!K9ow!5H<8Sd9W*+EOvjm)r`4ax7dCPpl7x6p9C%T#_EfxVk(Tj9-QB8cv-!N~Q z55cp9f2=>zrNzgfGGZ}87wN^ihNvz+=AR($$Dlh!PrN}v-_!Mi`;q=wmk}R<%8Di6 zT&$PqnxcmIfY0Nvnh!uT%}4xB(Mo*8KZd&y&-#!r?y;Ro{ zHN|}X0iS8+gI+TWz`2kw;PW|Mzh+)HJzPOw$oFtP;V#tWL>ISEe+YM>?&7+-DM(?d zo}z1uT4I4-sJprapnKd@_)O7LbsbS#Jm`A3LVmtppzm?>L2cd3@Smz*)^$Z4@qupZ z+PDw&e7Mu#^Rk|%>xsHzp8i0$aj)QdntnyM6!k=Xd{Zki9oMhu>AHnzDO$UE;A!pV z>Ulb!N$FGhye75337F5&bpzIrnKLFX+bG;m)+dPs<7-P2i%y+?eqAU$>VPU-hy`;0G|GO zfbQ?QyXSO9pUFRmlrs7jcvef-!o8>G=x22%pV>dFpMyIPoCEYgJ;3#MNlY%E+b2Pq zF_XmxGM?r&iZG<*+wcR`VU7guvF*R6bP)$|`KDAvPH%q^x>$6j;pTHs;d}BSG_T9)a`>D+r^|_4 z$cg+&2FwM&rF^D-O)urQi6DR1X0S(`)$a`VHV( zxLMq2Jq9=i+}XgF!em2?d`t4crv+yE~`sv(z;RlNu3t{Y20Ug6>sE*A@*=R4D^^z=SJ#L zz)|2RgcvDJAy6ta99)m-;h@KLdiR7L2^>j$?r}Xrk8;D|7DkLzW~3XT5sr`%`gs#X zOuT?M4Zt9tH_w@vNFtsy&%+%L{})UdR~WI%fKr=hO%jn*JPWQQ;zfjxH&3|qE`xgl zPsCH*NVwxnQjtuI18-9C5_n!TrCn-s6R-^2XG}7o#WQ9c+=meQk{N+`8QjxG3niXL zxE2o^WFvbRp%0l-?k00Hur%Dq!FP*$9F!3_0(VatC8T)DJPo%mVm)m7qBuA!=}Nhq zO-WE1GuB8U#8~qb+=zqKY5!%m`a3x(D!^If*k2Yg) zRos<;PjOIML;oi25A1ISn4PAPYwUKK&rn9+0(Y8k&8Pe`Ud$DDX-zRuI`fTb?3%c5 zz}wjEGAsF~d>44WH4JHU!NikhwAlf!CT<6)soM>nU1qmg!B_I_rm4H#ZAW-hx5q5! zEBGGx?>0qUF_#XQ&ZIYs;J*jBj4$Wg%h#3kTYK8$F!cQXZ34W4~Fi)7Wu87NE zp2VA!b5DZG1IxP#ZYN)9J~cb}w{U;vkDC#|5s3LB!YjBJLASa|ZZdN08@`i&YQ6z| zW~ShNvYUvITJ9JAn0eg%g1A5PsqQPY#Y~0o6gSmv!M9HUS1tFl+ibovFC%oS+rd9G ztIQ7m4czfay`meB=iKT}A)R0NDL&jhW~R9>&1T?c#M#bQnbl@H-vRdpa946KAVx*^ z3V5agzc62#U!n3F1{`LF1BaVa{CRLya?gV*yXkI|`NB*G=PT|vaQ@1d!)LmC4&jyE zGF&frr{Vt_pXWB3O=cc^mbseleK*7X4*%194z6pu4-h&JxWQ~Rf588D{62Xf-^)3W zS#H1M`}i67|H0pLbHIPWFuRvuFnjoJ;9kCm3-E9&?DzaTJ|F3P;O4vaW`j9zE|}f? zJZKk}2o+Y^ANcotwtElhEO6`0db0qW^W8b{?&9Y_o45jxw94-1Kk#?mY;Z1gpPO}N zA@~=#y=Ff+_L>8HKR;_W@h^bq;C=|6h3-SQ)_iW>aqlA58FSWr!Owuc_>3Fp9)QpN_5nNAJ>?#>W87HaSoq#&yV-H>KG3u708-m;4w!@d5Wg28 z&$=Gqe9-o=qum&HkG&T@_kf-QK8Mn80RJAgft`h~YhY`-(XOk#$5sYbcDK2P@NZxn z+PB>-_ao9gV7l0@_BPiARK+!de?!~IzUAI_ooyFe1z5#Zb$8p&mawX;=DLfI+{eI= z-6z0L+#=v2w-~tCEdj1JYfN{sov#Ld&A0OIVk_SU+{U*9*O-so{qXND?iXA5*Zcu- z8u|7BuJ0EQ;`#yLZ|1b=Wbd}sTqjU<*8@HeiXP%u^PA~tJK5^4BdCV!37;OK7qBPr zl=;r`Ut`|-CJ&`7$ykcLQV}8jcj8(L<|*#jcpS9&9 zf%w_{Vm`pLdW%6~uxM%rfo`{tirZ~7U^CksI0$$1!1;lgCr+B5%_HJb(cC@)YGDV8 z7Pcku5x8>^I!_D`Ep011Kn#TYHhkuax5Wu_()1UtY-`&e;jQc}_`EGhh_`D*7L%=?|w?1r+nBKY%+=t=wkbYPnGC!GK2svW<;`(9TS06NoOiz8(%oaU$ zFZlNa9X0*n-&gn3sC}k6u%B+O5Aq*P58YGG7Ck`ki5Bo_t{>Dr^n2n#&>Zmq?g;0I z_eD#Dw$Ls0aek1u0=Crm>j(7v;(q;>coX=(cuTZ~e=FTxPZO_*?)nWe4fv*b19(5& zHu@Yt&f9>eweAM4S420^bkSCy<>z=?gtpQ5A!NF^4>Uux(`Wcu-cEaV26z@6_v#tq zRdFx4W{7)m_o}!9q3!gYz&mt(^SXFhGyv8&4a{reby3gMH!lNU7E?t-_%tvL%}nu{ zsB7w(slcgXif9C%hNh8uRm>E1OkFbtI7Lhrjm8@ql>{Zf~UW0`LWd-EYQ<$He^zA1nHp z+Yr(R)Z277kBP@ccZ5GCn!vx0X<{nF?S_!YMK{n0(G)&SOjA<{?tNy2ctYHV@Dbv6 zbE~OnZUK)0KF%@bmzxEC>=5Y6G=%-mx}ic#Vogp3qjaW_h&W}VF4 zCN;a;bOv@dU4UIoSKve94x5?{7Y~7Flz0;Oq!>a`2Nqn`CfPvn)8vkeX%IS#)aFO=Z^IRCi!^ zRS!EzQ?m+|?(52WGBqo2E7K^cJ=F`F%KE3)Fi?pSv} z9`a!RMK%YIU$@WJEOt?;2E6I8WldmoOCHhp{3~MyNe}mDMrf~kn3i+ zmw+!p%B$t7#k%8UU-xi7FrUfJa6(EnryM;>5a zU^ZC4DQF6q+|cu6gAORS$;z^^LZ%>m3W4$f^I*=B3;wyGsma2!vS12fHj@+AxlGL9 z&?2-kS#X~OcO3eVEVxgKI}WWy7ThPp9mh$r6qqR=XUTDYoF#+Larh-SM_EeDd5@Z7>x#wYU9$}7Kp2;{+MkB!U|FHKS&{h@M+V;v}Z*tBYa?UyDjO3hi1__c? zPyrQ1KuIDZC?E=gAczVoAPOQXDk5eDR1|Z-tl#slbA|h|CnissF&t=lyKtV-z+iW0{|@gOAl7Y191H$j&

!L#cEw)^6;d;a<19AF`uurK=rhE8W|P?{H5Wr=Tl|SGXS;A3{H*+;aB} zI~SLev%+2Fo-$4vtI%nkGM2d?v)^$UN0+0GJjvdiJKguW@|~1AX)JZ$Gd_lXOo?O3^uoF(X(w5#P-a&AMT^foE&by*BujFzaF|0{b^i~Gg=UyKrd zacEI;iupzT-;7_4B2ZbY{?0DgB7Q-3&6e~_P^KhdlTnzQB7P|>Qa7fHx!&{FSyu!WX+8^Ot0<}D>&Le5fj0h_=dTJCKC zV`sT{FSt6(y=BD5ja$&b9Op{6xVL#8*Sw9A(joZVV}-XKbe$F6a^lyF1!!PiJkOFm6T@a)PoqqeBR>u3Su+TfHfKE!oVuKfr4K0T7xtT4=JO(Oq;F8n=7N*~qAiRw$YiTn$CP=58S8UPfIs zGVUg330Fa{LesaNoDGb+Xj|OP%&M-0qW^Oja<4^b8PZ{EIt?Ae7W4#Lz<63m$@Pr? zXkHlqH(N8^2S~4Dt~D23%`KE)h~6PRmaDgT8L(oV?rk+5M0YTac#Aa;UCkCsKERCY zdbBiK$=SlJ=LYmM50bOhdf2)VP0qvQJZSB-=A-%9Y2Ac&Xeap(TQj@|K^&UlO($N! z^>1Nrc*3~J-9ee1)&$dpV>g@+%bZrkZLs~#1I68nZaM+)k!WuXH$nWGLn-K z3*nX=ZN*;9?AY#>@k?`78A49KF1ze+_F9nNl0BL^u>P&be*BxgdW4(2=H#?sk7ij) zH&2$KeDh>ZtdZ-p$Nwg;K4HGM15L!0&?~)%*tJ^DFY7m>d~*;b>L=%W)d@FxO_SyQ za(+{eHcK{1R`ARFO~`4Q1Q80Y$WE@XgI%r_vHWSw(I#M#R8QXMJ%2nL4`yz9Jn$*NcZwWG{s$+7-g=I!HHH;b-e zMtwPJWl_zd$M|<^Zcmx9eq|6*_JYSEET!?j=F;Q+%ZW$(%bC@WrsNoZg0H#s1lG-W zTBFDx&01RXObb0n0mC9R^xG$^VOi9kXK0tSvC*oJ)}kS?jfSJ4Z&1ecf2URqbQCs6 zM{{f`5RaG-E%p=9=ih^ z*?e(@kx6y~j`mFc!dbtf0m%>I*(t9sGpJKsqpshbGCjZ!s*R=4FwPwg)r|dTFQ1X$_?hy* zc-=VK9ju``%(A*APoo*>mOSOvVg0Xp{!q#f^MCU48u^T$IO}Kcu(8W}$~tU30gl08 z<4Mp74jX&HA~CD3Xp3%ZO|RxWUJe(-V`-=iPMMe2Jm6Xk^t(vkK1Le@Ehp@Y#G2+QLRD=T58 zl`-hViasM{GJ(yJHCSn7AV(-Bomt)Y;=Y~0oBG&0<7E%Dw#rV4+o9Qr(^Dn`SUz1? z?RCzAt%^8=e%^3Ne}i% zw$cZUfN;pL$hWbC7E)Zukwef!#HJD!13E_s?|}6*v^{Yyo*`$DE9i-?=B)b(JJ36NPg~Eh_Uu61n(}Q}+dmHC zM{Bs}amxS)$~1B&zd$#Vlk4Y7UdKKA`sKZ6z*Q>Gy7U?J0M8kRjaHOz?VUx}lPfrj z9;YW*U%f#6`UDM5FTbUCgq`LsDcQ=a;2i|9sREjSgH{f%oD;OSFVXGfpf$eqKBoL9 zV1xA`ZsBQHdkfBOi5}n(Xiyb7`;e7g?Up>_&tV;UhBxm6PFNq#Ipbf)vo+_e7G5Rq zS?e%bf{Mi1D4#v~5#`VLl{s?QdJa9oVJj>7*^*Vf%HDGzOwDD5{vl;P^0SbiHTi)* zkG1&+AWOuI3Bu@$UldiY2~q0J@lGX@wQoD*xU zlE1kt*~jq{^d~GlJDH!kpF%(7%pRQA%Mf<@GWLwD#B%oz!Vhjo^K-0QJ5s(A z`wV)RO}(CkCf*WCE(Im#2dp%2;fx>L4(1owh<2cSM^pGQ-@CmyqlwpxfKG+-OAnoWtJo zTCgq7xr@oU75s_su#mitBi~`o-w2(_W$bon>1vj(_XU1=r&n=r>qJ&P{yH zonH5Ske%M}J@BC3@Lwlx%YJ}{URy!~?@iwYOG+qZZg7H##$*Hu{sty!q&P9`kNOZ}X^kGkTjxy;%z(Z+o);H^!)2vqP5UA(1BGmO-aGl!hLa5`__F9^Cy*kiV#4X8bVeaM*H(I;B z_rcuT?VSXdZ#Vx>`j2?h89(Alqx=YWeAH{eb*EYlxWhE?oW9_mFB4wzZv=s*JvaqZ z&@VMKr=rJg2+qJ%Y~HTo%w6cyud?=dyS?}PJ)V&C_KPT*QAy-)qm z{FUBkAcn5=9_QZ?|2xh*LU`W4!~5C)3HrJJGjt{K4zDRV3p>1KU?}Y1IyrU^&gzi8~WH&ASq-p=%O%LD#ZN zCZ~BfJ1KIS_psX{r@4+@82uAZf;iM4M35)_0f{HT6dFJtv0FG;UTnt-CifCHB=))+*bg!&F)*>m zf6OhKERuYTGP|*4-s`SU>?5p8Y~f9}dRshU3q0x;OBPK&O3BBt@><7JuBPm|#A@&u za+r^}#goO7k5J}Oth{otZ~ZPxFIvnjZk}>ax}wF+66Sku z5wj??sQEs&VOhY*xd*$mEanbZ=$=@daourT=W^`li%{-ex3F2nJdK5W31|tkr1=gx z?_#H3$SiDrfDL;|Xh{$Z#&Xs;beC(fYrwntu;?DTzv;sH7w+o0XsyDK`sjsRz6TT;~?EM4}4lCnY$V z0?O1Z@@Eq^d&Lt~!8$3<(GrQ`iKnTPVu@#DzfHP0XjQWlo4uKYOZHXgJ( z;whXpnLT8$U@xsbX0NdG>Rxc34ktFsGA)q-M5e>s>p8HHp2v2&I#(;ruCfObFS}a^ zFS*qcFJL2Gjic2Q&nE7Zl^W+B1}mvgVu7h0XfL^22}j+ki5Ibju1fi8i9?ip7J5Hc zYTAu<)UCq)GSQ=0M^~X_)x^QXChYnSQsxktPuhQ0nNWq@MVrWdCb1a{KRl9t4A|`hD!avzT`JL=V6h_KJt;t_u}cnFV>>Or~(SHG40WEB#( z`W3)pTkP-TxfYY7{W7=uJ6K+Aw`wcQt%%XXgaAy5Dx@$WPr_3toOLRXo0 zK<@;fVS%rGnhX4w*eAPy>)gT~l%;-+#6&{P#LXOCz+M{d7@fqCn$Vh{cHHD2V=wJZ zjk|AWf8I*-ZgUy;UujPE>wrlznKSAn=KHTEjzN!c zl_~66X`GlsXq32-{Q2yzInF-n8~xW3#}g0w!kl@KYi?sl;4=Sib2;H2b1LUGN=)?| zg0eD|RKvs#l)sVPI49UyeLeIB_S?LkIFWc8>+eU+cOskbcd&hX)O^d^Z9WEl%zPUg zHraN+>%Bw#Ci!o9Z(^ms8*8;)NYeK>zRP@roHxBUyvMOXf8SeS8rb%{M?B9z%8u!I z+~s<9kTwH(W-CwoAnB&y;jG|!?=e>p)|szk0slDkajx}*_r7NYPY_Jw1UBYRm?t>; zx;K}r&0{yrQ|yYJ>u<%LcCNq0eJb%9*8E${*RcNI0o`HlgzhvShCa-h$Fb($Y96P| zYu+5rn(Mzx&T;RX#8050d_$<4_!0UOv_A1Mj=qX5*fw?u{6Nh$0NbTL$9|w5>nFDO z%|Xc7;>q^$S$H{AaSq=U3=2?4@nVJyvpu`^}Yv`^>XE zaT5@Bnt=9mmN%%I@RBnr?Io{dkI$#(diFGYN_YtR5VlOh>}iwuob-0=o<36^SU;`6 z%@O9$XCV2sNqoVP?bt(YXXnEg<}qyBz94nXbGfDmmcv!-3Hs7}1xvOsIsS?#)SXs| zugsUdm$2ablK2b$w*+CQB~L6go>mEmvs`cmu4b>$S@R|DC>B&-5g+6UKQ+Ik>;wKY z<_7*fLpX>{<-PoSn(&NiCugyf$mU!p`4!)QAMg*D8##V}@HCcFXU(JDQ`E&qtSMLe z_dz#u%;GFNx!M1U@?V1|v)SKo-l5&Hlz9s4lB3>>k=@l%&rHr{FOo@lEBOiNG@Jc> zl-!SX+l$@{*sgs{Y$UH??~*}DGx;t@Ucmb81?=4RQgWa9d*T|7{hqj%Jy5crdmbyg z=do>jlB0Xg-xAlcbLuya{+@UrySgJ-*B$Ym^JI-D`kZ&zTg4vTC$Y0T>^?1B0o;J&~&qH>A6~ZU+flwiQ zmUAkwyFfXo%xAp{q)wS-!w<0lEKA99;bC(%yNnNWg=fu*;S=`bc13n9JYkoiOj-8U ze1tV%C3Z4AZdW4gu}hOvhTRFW_bVN~ja}c%T;Z_!QR05~(tZRg)ct;C_V(EkA1r->@j%6P9f~F3x&Jzk5DK~A)aS$!Oz9@V6})ofai<31?vEGq>Rh;yRAb0TX2#shgoU znFFCWn}x$dA-)(0JMH=A{rCZy&)N6e1I+Dskr+Ukfo73#C%ztvVC%mVq@elcebD>x zA<~~R1I+&BL->{GZ|=Zn#5;+N>|%Zg?5vHT@9ZGAA7}5d-vz1aUT}DdvLm1`IsHJX zdY7C&X0fnn*oXYS=KG*k-Rr+k*x=vI9__pQd)VtJdKWdgmYloU%P70xb?kV2(Og5$ zTJ|!^#&~@wi{kYhe*x5%G?BNSV9XCwdP%!S5qyBfCP^vmeU9C@#pZxh}!>ycj-6jbuecfvQ#H=u7}O}nZA z9rgx|NIQ&1ku%7gVF;6QhEXf534JeootzV9Ez+-Jt2x7%&hcr6uq3CEnr_SlWxi%O z6>O-D;A(BeE6qq#`;SI)%~9r+9IFvtNh!)0r@)MyYMcfMaw=DtW=tVH)ws&I(x?$$ zMW`N*FtrP51XmboUcr&-;T42x;bh}Ya3m*Feu^>N)c&L4lpJC1ydNgp@`*j4m_lY>1(A37g6`JnmOfApb~muLFW z8Ey_UKXN{FM2DDzp+n6f&|zRlop!Vj@wB6Ti>JB52lyzt!l)LGA!H558d=#vHr5zJ ze9B3(kL(oXPdjIvkDS5g8Nz6DoH5qO5{@He4lg&x8KRllBX*MVr<{{cI(BEDbkeg2 z{iKtDz3d-z_Gt5C!WdKD3o?b{2^qtI;cT$q20(>qG7AK_LFCOc`-egr>reiGaBz4v z*l&Y5ezn<;{Qh7+O#we_2uH4hUIhZ&P%wW)uLSSy{m2i(`}je~7{1TlPde{A8QEd~ zjPtQG#(ah_)*Kej1n+HFIFxvTcZgl;6S3(N)&BbN3TsP^@bC1)H~efvPU=;TfIo`(uaU<^59 zvF+Or3Pxuv_FjMrTVOOfW3cLbD%>A-!FumS=!;3MkWdKGky zIncRy?CQx=%`uLHz44AS5>GqtaL0G?F>wg&pJ%}c8VkJ~#Gx_7W5c(d5ynX4ZA!l5 z9H!J5@Q@BetJ$N#@TqQ(1iz{}IH@DUsvwq)f{x-?4SPg5Jgi|?C$2(%Rl6p6!^4{P zuyBT16STtV(BYt4Rpw|FyB5c%gF8AMWWh@0RJMm3Be-it(v|GD@XYfzJ`E0o$y9-y ziuiZB4lhx6+t=bT>TdpBYpk*7;5lp!`D^jrbd53FxCgIJ*BIp~Ujd&_J-s=`U6fga zFQ(bXEMpy|W*e*RUf6A}=ICAadV7{JAD>|Bh|6(Sc{~O6#-8&|%B;q#(tNzCT}!F? z_z>!Yh36`c-ie>3Yweqi>j*a+lf&nD!aMA~SZUrtnN@gLx*6YXb0~E)UWoc(nYogq zci>@ZfpLp5m*WfYmonUV3qKG2phtMi$>BVX--7R={#b9`ZV$kE^LEZ%X)iS9k>8&) z-gK_VGt)x691Tzj^4@fo+XKA;-g0tQ*o%zoIl9QW0Y6Ox@u%{pv&G*HXH%h>XR@JxSVH+MRS7z`Y}15 zfZ?1M%*jtdkj@3oW#_c%JJ8o?qMlVAG?R8!ItbEmI3#&dsr4s z&hBA3P({0gF<8$2nY;V~(r|a;JB(ZL!E^_Azs+dIe%jZad&s$iy{)g~6Qmw_uY*>0 z6we*gx!1I?u5khnAayx@!fB2V#9{239mcNbj-;Ej(|Q%D8R1L#_?W?2(?g-$yyny) z9CzAtv;#Z2?<8(VXb;|e51u07{v7@U?anhLz@+caK5zL^yo}Hel=>cF2r7L~kP8F1 z7g&aY+gliit`M@5?oZ*5&;;>J?mHtCa?Ww5HsMvLEglzF8*K@f8P|m`<8$OX%FGOX zw-4xvzS|9KMW3q$ZaO#V{t%{fzX#Vm9jWiZHhY=UZMZ^PqYb_s?=r3-=i0EA@hV`J#+c2y*MLCw3f@U7fz@-& zsSFCxF{cXQ6=-GRR`{7*%f9oqoYONxb?y~mEcXIOI)9=EIX%IQ76x^1yBB!Ly(7%z zs-VZb;&dm!2Po3nK(X#)_XeN145fvb{{)WqAwwLq9sq#ihc0+5Vxd1+yle& zcx%-uH9Kr!+=j=l7M#`6=t7yUU`%HQ#kYnr3#_&pApFb}0!Okayy&&frITAeVO}r;}aLxC%VFieMI96?U+F zaIHIVw4-fv1;@2rp{srBWCB6@Q^y8D`cvmDaeGR3up0$+?K*a2c4Udxv1>zfg8|$) zsLdNS4C>i+?S_J@ z2AtcFJylJDoC$Ukf?-{s{08i%YD!MCAO{G{%}C`))C(Gdu3S%L*jL#s$eyShG_o7o zb;+;CF3Luv>I98JS~j_h<#qu3&;)@%h}^BJuV<{&V)qD;%+vY<5>#o9^U z+HM`R09Uy+M_UEIJMB65OMD4*WZ!)&u#VeOww2u`XbCE^_TsmMwxD#s;7iK13)_dk z;~AhGw14mw9tZl9-!BjjavKTA6*u z)tpMSy6`Z6b;fXov0yEHgCBu%lq?Ue$d21AcpR+_txex3OHMib$7r|lXiAO=$~fiO zp<9NWvd$=SMhB(IDdUuO%CWP&6tuL{99+#`p}*qGphfr#{smfq3-*gsg5xEj<%nB? z5%#lFGT=Y71Tn~hn{{K;uzeTSEU zrl6vH>og|a#A;>|-3tRL}c(1&zis})xo7W5{kk5vZjxEsUPG9RmLq1+R)&j625mPK!ud^GH1O6Er_QK zq4B0b3py`@pPPa&jINe2(7JN>ZdNJIE$x1OS&c8hG1x90+(oVkjc$RT-LnzjHmP!uy;u^s#-U_dENX z8^Y^J-x%HiEeq1&Q_eh4Tc5&%_q=egQ_d)hPw%pL^v>pHb&CYq2!(?uo$^LG{Cbz; z*a2rQXvqg0p&}n}p5kA2H=A2H$WAB}JVD7P@$+55D31s5K1N??U!wxP5QTyKG-ode z>sdwJBCgP*isJ7kyIUy8K}ZQ6r~DIm0qB5o!pMD zs1W@2Q1Wqngm(p@?;d9%$k+EccN2HUqje*w@bo%^QrE@m;5G%lume|+hwIhg8MY^< zgWJXJ45m&OLT9V4Rm3gq3fZa%o~>6?qMa)&yRIr_btQDN@M#Si-eu&s!%J{ix06+w z(9zn>Gwi`bc{ii0vCa`@_Bv+~c-iZmdx)#J9YJBL!WkVcykm2ITlZG*x$9Vk-9oN# zvI^r5`_`~6^fpkvtGfNb2dj$r<$l(BN0{8}opr>IasA!+KJO03Uu$;>Na3w1-^Q)x z_O}LD)!eGY)%iETYUM5kS-cfxTD!HaLT(DQ4)F#@Sl}C+^~8^IoyYK=-UCd)N1dLa z{te{p0agvSx;xNn$rW0G(p1|@fu^vV?-9y8ig)y0;QbA8iefX>wA~D{>gDO^K zYgSO1x0@B@!4J+X&YBI<@qNy3(EIUIZx~;M8*IaPf}Q(@@gzI<4P!4m_YGqoyC4nY zaU{5b&$ld;%;IEE7{)WmbHm7<_yQc`pSjC0t1ceBhw+3%t*e8oRuyO!?)oig#!cOC z2~FHEyx;j1Z2Kl|WA{6bGy&bHD&>ZAu5kG3;Q{KIIF9(ALNT}&OV;L z8@}211znt{g8k6_L06|cUfB)f6la|VBYd;73IFQ{@H)_$GF_Y=95;+H+^wNI#`*zF z2S?Zl z9XQ$%ALs_iGc`DF81Hk|NwC1TI1f0ZC^;IG!5=|#ZtnZWg1(HS?VQ?<1NuvCrxx+MockUa z8jo_Ut@8-<9dh0U8T~vO*=cIS4T2}?>ooZH9D}y6Estn{^1={+9obz_D z&3O=yHPx*2(CSt-E2ERaxiZK|mG;;Wpad|mC4CSoN#J_ zK9?XriFd+G&Ws>4VLHg}+nl$d+nsIrrzs2KTu8};^SM18gul=2%+B<{=LtQ-#}9ZN z=gr_DXFGJe^Hva0K6JjYr-6a=h5b44!#qnH=V3x?Jl2%80_RKn3;WvOOTu+Qz!iLO zWa{CI+~cV4d}V)WUl)8um;?4aJ{zpB?XT=P!PkVj;G#Snw03q9S~($S1?;S@k1z6h z!8i8T_B=|>1tnr<(8}3JXz45ozQv!&lHfc1hAg4XydXh&R5f@UukR%AAl?Al2ruLb zymvQ(Ho@!neO#j@w58L+`GB{3Gbm$y$di<@KH{0mSZ6@gzb!b2&ym}>@)A%eS~$&} z`$48?;gsfR8L&G)4$cIg#T!|-2H)d<j#jei`&$qz17KI=iSViHDP zutxJ)-{2GHcl#Sqf(&OHXfp}?m1{ruC-%p-sPKEXgJzR3@=!jnb;cH2&l!6;yS~p* z@?-m~{fWIYI7_$#ETC`jY4a`NH~S-7I6WUx{*3)8rS1qmC9Dc^bDccaclfpW)&9=> zmiR+TegwT9%%0CEy9&Ar1fg7%%x#^+)6FmTIgo*V#dG*)_MO3D!s_4y%718oV1uRw zs?RU@wfWvWN1T(ha#^SC8^PH+&Cw6=G`<=HqUSh!H8?*%Y5SBtAKb4~_Dx_QJ&$Mc4bb)ApFB@$eQ=WeQ}#*wX0T#jz^C{+=sI@7 zzfaCde1^YZ-xIuO-wiU+i=^%juCj|*g{`aY!d4;ZRm4}?MXe&xBGy&*EIiMH;z~%d zX4@&?w$3Im#hPgsvx-8CQtl{MT^k%FtO;h2KhwU(E(jv*HTG=c>Ez77TYPb=80k-g z;`k{qz?=26^Mml)kFo`G(6xVP(fZc|YQpxb~W0s{J`$C#F(nnmxeI zZe_CuP%67M#r^_c6;n7m6(8+ikeY0NiQkGN){o{7<`L^B^GE2<=1Yrl-ASkZU!!#+ez=E2hm)I? z<8Rt;;E#I*bOgCcd>X%rCtz~z*YUVL5;~G&>BxHnZ^Y!{w>VuyU&llG3Cg@~oxsQT zD108LC+9WNC-8VZ25;RN$vXih*FH|pYk0gKi*N2%p~vwFJPse_ligSGdp^aT>>jhP zaF64u{0ed=gIzO)oT-FY>`CNb0bb2i_Z52@;bnWGn~`fyB!3dPHeB7F&heL_FXK(V z8yJ?NFVPPtP;w%;Hko*i?rt}CO)#GH1aNIK;XH;bLw?g5_7nxF^a-k_)3 z!@V~cNB-sRI5)&c@i;euALw3gPx8mQrft|`T?603W8DD%!(%Bk&h5>y9YJrm7x5U% zjCIGj7XDcKxI4f&>cjCJ!Dw>ExT9Sg53POOhmeDP-R(%izHT4>jdC4)wvOWHXb^22 zQvKY%V2Jc5P8fGOzXRg68V~TIK7NT;k#i^B-+!}yx9-9lyoaB64taV1Xw{vtQ-rRq(eztCR zeztzGX5pKCggc8c++E@PX#HfZ;OOmmVgJGU(OOQ<3THN+*oV8bonh`!=x}$KdyO;H z9Ri(Ayv+I1`oUU8`Q^^F&JcI7d#!T~@lxk2{9iBS=ra7MU+WBZmyoj*-{W6fUs<;~ z-&kKmzqXd(O?|LC$elx}!R}mVkUJ1Mhxk_KTk9L^R!ZK6Z}4wP&BM?7KzANtfIHp! z!usBtfiD-)@2zvzG;*fn)8%vP3u~rx4zIy8@#u2Sn(BOp7woCzPjjwxzO%lyuEe9u zch(f=G@hELaC9mj?XTnxR}mKD&E+(?lbsK&(^fC;yvXUr@x^#^`Ox~nx`O=4PH%D- zLVFQUaz3&?v?g)%3Oum%Cch89z!yLl689x_Gqex!MCT0Nq9;;*lGBg8oAJ)_v316p zK>kF$uzXA^oAI$V9y%73mTbm2yq#n-F2{pPHe)=#R(^{YV;v@$Qi{hTzL1 zX!CN|e>`c-$Ip1uxC#H@N#kZbgL55lZ<0noo}4SwZ-p>3%E@Ys!FNVh zBO7r#u9gIqW+)y&(vwaH;!Rd#l#|&QiEoa~q((xs5N9xk;SD4MCDVglGmKP5V>tdk zG8!YC;Z7zaGjS$DM#BWTa)WIWp7636*^LK5xOoti*KEdCcZfH{+v*PWhC=7~*^D84 z?;MJ4>2;)+*te0s4$Hr6e47~0?=~d+1n3TDhjW{~)7c5_WOU+a3-E(}!|mB&QuqC-O6kOV6(?*qC-St2=^}|BdnMH&CsnvL4MHQT--%wf+w;)v*+LE|AsY1{e#LY;hK${acB~=jGjJOGLL1;ntm<#b%v;e!v zg{3Q+pB>^2iAD3V%Uj68qIuc9Ej(h;JnYP_N5}=OPpmI@xuCh&i(H4016r53HmU5; zI>fa|WrNlxu1P8@v=(sA^0Nzk~FA{YnScQ6>JRL;qWebOmPdAv8%`fxINTs|w_lBLvX$#AQkO&~n6O zNO{n*#HEQnsK>gj6v2U(CN4?JhL$2OLCS)bBrZkJgGf21P zNO5R!{PNl==Owm zdAuif#Qo^K zwV-`D(w}45ppqG~uK?wWqy4a)s7-1BeZDrdF0pJavSS&c{qzI*r*vK7LHy4N9Y{Qg zoPp4K#DmGr1r`2*zT)SE)*~Jauhomb-q(-5_vePzCpZ3*Ka|pWNH>H>hr+)Np+m?U zMs8lHkROJ@hVg63d#dFtiPFZXBs1P@#B@xy5(+|_ z@UJE3HKA3Sa&{|1b1V)_&Tqq!d{B)bZAj&XHYcww$C^T$Qd%;wH8MBzBGq+3zCBOwoUrABD6dyIDp`r-SyR>>$DbB!@<> z!G!+M{+u_MFc7Jsk#PuThR{L8L&)t1)fI=rWj0i!O~=gBk@sgA1gwi>M@m#R`bE@_WY zIjTERNg<#AmAH>jIv{9n5olqgE8v_^Y-Q)p)HQAga+^{XkTszj~6W<_7AE zqMA8mj^t0~NOq}rmZUy1BazgnMT^5d>e-@_uHq9>Nn>$~s3f+yPE>L}7olmyfz7Bv zjTgE3-vpYASe)FLHqf{u{%=ezHbPcN3TUpW(JG#C79drh8qZH$kW{@$%G9U53zAMD z)TO;sBC1hUGEP+EtR$VN#^@rXYDIFhX4HF7CelVWwXc*1RUb5?lr;PSY2QdmQ5jVI z(K!Zblf3v}e8l9KeUUts)=`y@?{?|u{&RDAN#b}$pLQ;vk9v-0^cT+M^HAUMjQ)>v zdClVE8GSs9k7x9kGMCRvZD*t2Yte5moXek|#cNKV8GiWNxqRALyn3)^@fqL;^=!@J z)58(!@tVu0gBQ-v;x(sFMC0{^b9o=m2;hivwCaU(d2wJoqmO6t@r>SvGaNXf6zz8@ zbNM<^U#}hUfL1m+>5;jJYegKQ^-Yfds>ygwR5Rit)lYVMwfG^fYpr;+`VqgytEza7 zrFD;1LgLBP))Kc=i+ELam<7&>+f|&SRZ(WB_&K%J#YI&j&esYl6FnsECtB-Oj--R? zIV1e3m0-L!RNbouRO^}}G&KrAn^Eg=-K$N+bIqVyRcd9W)s)&tE6;cx+MG7gY%6XV zNv|aGOs%0-;*%t0HKV}0P1H&uoFg1olf0s|SiBO`>PwQf7*wkzNmfyJe554dB-b?Bh&H0-G@6J?!fAXFl~l_`sy@9&YiEr; zqLOV|9f(S{X@nA$Y}2?UDygPXOjL3%Goc1F3vnh=;;qcY8A(-xisv%W`r;>zNE#)p z(S}+zrz2>EtaY?j%W6lBLP_!}(@GkJG&)zL)inNSeOH0@3Q79}@m4_Wktz!n&$*<^ zKs{oO^=cQ5MUtwb8jCcVi)t*=_%5m$u}P`~JwR*cQqfzMir%|aR1>A5x+xXaR;j4w zN=7wWGOFW}QLUGZT0m`|i?%6AYZQRyr|ne}MWebY8r4=&u3svujiOO)6y?rp;Sz)t zXi5GRB2J0wrzriS1pkXgbyJKy&B#lTtNJMx)l4y-yac&M)IU{A>d#u=tCrM<^@ggY zV$irhOH-h_Do*XFXRF3kN_k4Bjyb9^lb=SG)KM!wu97-W_4v1C;=K6y`SKTD=Z|In z(b#yt?Ef^5#@e0ia9B-ROggF@1kJdlqsmFhK^sY4_Ib!CQyxW;a++_^R=l~99vmDF!SNEg*|`l!a! zK{f6+<6Sa9Gf++%!X#8dy@H@6BOmn zS)#THpqlv>Bc~{>A-S%0@~LBui^b_T*`Qe|q1N(fh3x!y`RCD(vh!bUDUDnX(hmP5 z_2Y3_(m*p+Y36E^Ye#LGi`>%mwVcEjeY6&|7RPdvTLzkoSoKm9su^S+a?3(<6C2cB z4XEleFS+HQd5DWp*VUjJor@3*dZu0TXeVI4k&X&Js_Fo3cU0V|63$6PIDNLoK*aaaqZT%fw%?CSP+a@szmCjrdFa zByN(#6qkvo#A{B(OJyQnD;@EgxJ=w6E-Ui~E)zG2%gX+N%fv_GvT}dmFY%H1t9-;+ z)u7@)aZ$yHzbe2(;yQ6z)rh~uM=>{vkHk}z;i@VTuN92a;>5p#zy96h*Z&>-^{*bk zF2-Mf9KX_zS(0U`V_7^}#UoeRu`C{~;*l%uSoXJLRy>wzhM_s0#w_vIg*=s(*Dl6i zX?ZFwuSq_Nr_PUDF_)zsv(k=b@n{u~TxrL$v}2YTjag|&w6r6aMl=&Xibtzdo)WKV z6iYj|e`Y|Nr=vI!pX_j9>rX;jarh>-=0X9=R^$GL2tp z=Y)TTzceR|x$OT<{z^N3#VfCPei+XT|MB`u5;1iZR-e@0TYtqXFRj6}{;G={{l8&; z_^%$nv{Jv=`YUyo*p!*z-egsH1At;^yW-_pFb$+N-nATYruEpZ{Vd^UE{QB$sh?ctk%Et^bUT0}8Sc$YowzPA_ zc>Fp)Gt}BEo-1m8C_9^?(4uHHWM?CNrfhL!XHys|TO558mF`q}2YqR6&P-o=Md@Ls zKa`$ARyWcdN`IkMR;)|Z7m@f2iPmG%2upt`orrYAd6{oWlPE1>tgo*R_ehs09kjkB zOQRU;q-AH5gEo*Yj&$>~z0tZ+dg$8JuQZ9Wu!*(yHK|eQ5~W?PLH$aD6RY zqq$qRXUx1Cz;&$X9Y>U^vHvAxtr z7q*&ON^KXn+F#jT7q(RVl|}7!VN1mpQ~#*F)JA`7wc?k^U;nth#8atUCQbd{<1cZO zT1{LgO})O&NHZ^9yO6)cQx|fXI7_@%7fzC<{?hnMJoQH|`)BzpbDEKbD7=(q3uhVJrzR)?WXNJd_Olqg4E(JWS=Rv{Lbp z{3RLqN2w@z__ysPomBiiMe;EImMN*IZz__6|9k%WXXN2OZm+cCm!x0nC??%u>iBi( z{B^PR5|7o6#;kZO)A*&4D^(KetFuNmwbviz;h!D9F4kU`GJd7yFUi0^wwgvRjaix# zotKKKTo#XF7azaUS|liK!h!l8DxH{xw9*VodN7L_fc{IjEX$ev(40}O<}()3N@wSY za-~bQkX#1;vqACb0+p2v`$v&d>>p)3F-T>E%EHDVl^!Y^9fMST<~)*?`WmJgil}sL z4N2)Mi!>wk7=eo-dmECUY6YkHWn;!x3tEU+vmV)TNdH&|8B?4V)|cGc1lg@MrerN@ zja`!jwZ1fyH3@2WeJ`j%Q0r^HTAd(n)y%dULDE%UC8{z5NkGGBG)$7x*H3-(G>9vc z(j3MhHHh)21++zE!6X})f!L3=g0>`g2>H#SgNbG7)Ep`sm;sa-7}-@egX;Tne{y8^ zDWo1*S2l%e<~N*RVMo=5WBrh)ZLrxYNvbcsqa;*cN&C=)N<&NYzc=YVScB=?YA+;0 zS!fw@dy?*j&6mE#_CSJ^hn6F^J2R~c&ubpk_`6)oBW;yNs#CtD(Y+nnrBX{^I+ah;5$ZCg@h4#>U6wR_HcjoBuaM zxAV_79wN4l9mKY=li0?`;7;f+V%u0kY=ZeY4LXf`n8s4_Ok)|bX)Gr;jTOZBP$f3O zIlCQt2eAoK)*aA0iA~PD6S{;eO1gCA$4+d1vZ0kdZ6)$$(`^!FK!r1^l9EPxA6Y3| z5novFfyF;@hXn`dzwC`=W2pb)1@(XZmtCd87VZmmrBW zf+uMl^>#_5k;tCQITp*G+EH(>O-`MNhb58PB8zH8{k$er_898tHK4M}P(QB@l~sm% zdo`%6GSttjMLoPKR5Nq+@G1mJq|T%yk-9+D=VOVqDUwL{LpS|bTWpS`ka~LydUQ*A z`+Z2Lmh@@KBK7>{^lM42jgkD>NJ>5b0gi5oq|+AO!=l%>p@jOMMSpJ-ae<`JhDa{0 zM-qt(B$3t;)c+-y?jeW^B$4hWsQ*hYttE&HB$3t-*3#=Gm+s=JD?rPWyPEV}NSt}} zj?{TLl1u9O^CNzlAMuN%(>7$!E=oui zZG~>-jjkoIU`w=lTo z713xeNtKzPF?}+rOp%Pr6iKIyP<_dlbjkqD2samulhh zKnS_FR+K&gr;D^`ZfI`)>pM>_Xs+mKw8nG@Y!0O@b3k+O-=Y<>L$mW=_8Qrs+4!&d znPzOV;D~30%Cn>QlvR*yh4h|2*Uj=kjA{r-6W%~|l`gtUdd{+=+O&9M z)s^bkrY2NZ`iAXLPpUQ5mP>7EZKAsKcpBYLwjDmtqu~q<(fg+3KIh-p>{r>WoNBFH{X?U0)w`!uyf z9zyPjzkR4UTYMit#qp8{Aykq;av}khgpmA5LM1sQSJFWxQ6z8DLnUbn)5aN~l0ZdB zOS`PzC&^s|s@|6>>tfDVKUSR?+&h+hfavf}dY;&}9cWqp*#z09>v&tH ze;%>;T6L9$(q`0~#7(LtaZeWNOtqAapqf-IWhba6RZBSts!7#SPJ(Ju&y|ayn$%O} zCa5O$RCx%hNf14#Ej^p0r|MA8mOpwf$yU{5`lt?7SCYa7qI$^y&A@+2HLXzNaV8`G z#Xouq@sIdQPnRAle$!LyeI;>J7kVQ}Dal*ajQCjkE?rYrsj~M|ZN%29TFc9VRoXD= zsAbtIt5(^*%HmbluF`4C9#&Scg`P%rp)c*ya;NU|kPf^ecRX+Jr+TPFkiDPk zLF>~>%nj8_vfY(ElIo!^h%JF*$B!CY0cN>;@2 zE?j+^krt&6Ehmd(=~(L0aqS=V-x?4qa5!vLLe@T0(o#OVAeP(KV`Lvf>DsHulwU=5;Uy7vr zyI6avwe+1z+W9}*UTP^>g6rGOf2zIITKYb$FImn1yS)lt&|Ye%xV>8ZW$h*I(w9Sh z6N))2=CZW>mA1VkYvT60kiW!T`tGN1QWxVdahI&d^lj^6{3Y&^HK=s@;x2u+lr(hDUKwdUB)zRxN~yCf&44xE z)>x-Gm&QP?gft3jRiO2PR!SPf0_2qBYDP+$P@SO_fz|~ol^~W@IAe5;3{Z`>x<-1a zMq7<}>7W{IHJ8;@wK~(2>6-DpFkY!>RpgKp-&u3UloTV%Gon15<8fv@*NNvhdKO*H zq3mDx&YGF(%{AZDGwBUAgV5ddhMGaBF5)$d-c54{$^Up~Yd~6SKfSqT9h#eI-JoZW zXKq@b=?!$nxW-jdHLiD#*ROwDJGw^NI{GW$S+)3|YiISN|74y2Rek5LnulC$TuUn_ z#kaC|mNkV&wA6Xy#pWSt$F=|0=OKU9yiwekx`t8>#%of27t(4}93JK(VAOwN4ynF&Of(4(nujW zA3xXm^^w-n(l%&D8tWXSr;>I`t8J~KrM1#(TdQbkv$WdQDq31Dt+us_mi9}lZLOlE z71L^4t7vJqD)!wThPZPOELL zr3*o|+Rj8;Iu*@yGDD?DQd{V4wAxi$=$*9MRa@wtwAxi$=$*9Ml?>K9X|*eTNSe@2Qo)YC`X+mA~pk@2Qo)>O=3TmA~pk z@2Qo)>O=3TmA~pk@2Qo)>O=3TmA~pkYkRHyRUdlKyil$F^`7~lst>L0wept^Kx_K~ zP_6zmMlG8$s*g-j%Vr`c9yO$gk}Q;_Pr5MGwlreW391#O84PG=wN9)xjOQV-Hu1s{ zKJC~ZbDwxF9^s`!jdjPmgKAjytULVudRDK}nbLAezbZ+h*_UL8B#HEosk15RA0;~^ zNn)+E`c-CvP%HH0SqSQ%x?fg8tl?CxO8+RXkNG{OsWMI449!ZUm5lY2u>^|sm$77u z^_sE7iuIkbB#ZT+v4o5Dqp{?R^`@~zjPAa_X%w_P(l9&88$l)4s3XR&Ape zO8dTgTeYQHRJESk(*I6b9rK#rQ7P50>N-wcYTwf+5bLC3eQs*6(|fBvB+FGd7n@zC zec#lX{9marO*=NFl@Dptu_j%zQCudDi}lXZzDw(>7K-)pYDujf)NfPYH|?9MpX*Jf zg%mHuTK`xZp2}zZ!3wVc8I?uq-wKO%i>e< z#`&2=sy_VuydzaxuKtv&MOQ8B-Sj5$*MN9NbN+qP_UC`6yt)+qf7-cL>ibGQpMPhK zJF1g^tp69sW?-bz_42~G85n`2P1RSr^o&fJ>**_9Iz}wY)PI_ zS4u+FD|DrJWghFQwN{r57vIER`839-l@I@lxoc|A)JUo|xyC{DB8?70C~(P*(Fjsf z#M%0SnvwcVM^MeG=98pUv#R+7Db=iMJ|v}@Rm}@=Nj0mQ_erT{Rr4Mx)vRjXC8e5G z%{!!2v#NQUlRUhwsMdb^7EltZZwAs>mV)Y=fxZREMq1wtWFx4jmkot5 zPxMx@q0n~$-AOhS!rIUi$c94eJ3W~!DWtd56AQINdS=z8usdXXuUeK3iS(9g1EGIN z&#cxE28e9LC5>f^BE6-0qij^9w^aX>?TU2EvNM-9QyMT?T}r1Z4VdgOr6bd~0NFoF zJ0^{#tfQqJOGP-5j!YU$SyM}!sc!+YvX+iaR@X5?N^CtJV?)JOq%oFCYz-VEt?0YE zz81uoEcz}GBeUo`y}lF39#8u&^qoMKd-`Ig?*y%(MIsv*&|Okg*U~NF#+}+1r>MVZ zMI#PZf6)p|9IhU%m07%E5`RfvXt%#4NFG9Zs3b{lQt6p^_vyqw7m*B&iWy zUs5AMP3iiQ8X+|(2_mVX`HUopq=x1>>W`8dlJx42Y8B0k)CV;$w4*lDyi9#N=0ItQ z;@<62R=MIvSzYL@)5>(sK-EVy2Iz|FBN{1m-PAdm?y9Rx-s)*m=VWQeu(WeBym4DxQ!HN)jrbkR?hwsCYsgnI5Y56-Q=(>V3tL!syWZiX$^Y^}gc8%n=u6 zCapQBxG)PrW45?3D?vOVF3d&{PgEo&PE@-Jn?anY_O1*SC#oM*fr=B=KdM5-iRw4i zpyEXJr|QtQ5ihnSEri4x{1-pA;rm%lXp@L9n~-h{N7Ukf(}+8pLG?XG+}Rwe?`Pu9 z7EpaZ6L+?R>U)fAa$7-LM!eYy{%F8|@n&njD>Q_rq(~OVn0?|Cafx_Ett>7Puc*D_ z@5z#pl76vHGwy?_^C;D?MpsFH)w@OlNq@CR91lS%sPX|wQrlKy&Ht!gFx#o3wYix%mBW?q+; zC(^D{($4EtL#gYOOPS}S&fKKUNjuN^vvv+?=dNkz6>6DFU8ji8#q+7Udhv$7qf0KR zP5&n?c-nc$rL0rZ>d-FbeJ{37QM;zD%lp$C{)5>_QD*lX~LArt5FAlwM zos#x_)Ar}I@B6PG(^7T9nj>hOSIeuXY5dm{YfRHy{H>kRpIxW?Yx=GF>ff%f)7EF& z^q=M5)Rxt{EVacYB`#%M_Se0ycr#T)9%~gOOaC69{xkhHZsoMS_wTQ-rRCE%SB*5% z@@eiU-CyduPrAR<*_>8`sdGK84^!uW;>pyxq1KbBb4IN*Q|FRef2zHt-P5`>txQOp zPUYFO+MPCPA20My|I_!HSnkETeQDeDttHlMtF8aHI=BCs zM^eW$jdH0{Lvy#(Gvo1JZy9U#G;&DC7ta^O{jnBM>jUWo^`x2$Nmr;9PJ)m<>aTh$ z?LX7JMBj+wvGo6*`|3?o-#T6msVC|U=C|yNGL8;OO!Ga3d#X?m;`G4PD?03#d?o9%s{Gads?wvKWXVE&tS#rdBOK)taDItz4j$L9JS@ zq4hznTFRtVLakbgrL{sXsotj*L+&YEmvV(&NIz%Y@y22+D8X~tm(Sv|u`AAyB zvF~c5AI&xT1IJTq%eSY6Ep7b$f&DqUxw+B{^i@)82yaj=*zs>Jee7sJGckBWrf-%9`Y?fbw^vpO#dw=B=gwig$NSN%)2OrJdRKevS`y z0?$zc@ylyT)vg*Iw~i6d)bgqX>^YvR@cl+Ul&@x-8#NZFN@L>$2pF zwbfbcx-Ls!GQGxJouxK94k#|DjjDx?D=}}@|6rzA8hBcsK*R zp2I%pFlK{&5jj_UZlV|iO}uyB(FmK~Pn;SD?lhNB921kql~^|lY;^6EF+j!v#YHi9 zC{XS{h%yc+)()aI9_Y--pc3Z?mDoP0#8lt7^Ow%2RCAlI@l}Tj9CeOVdZ*8_TDMpm zI8v>((;A^Bqz%L|ANhX5D_qSf;*3cD)NP$Dc8trdgFg1*EWG)eL;rOY>ucyW^}+KA z9Y6ZuIY#u%(+5vqLp}5K!E=o0nWqn)zJ_|{=~L)ia-`^k=lou*;B$=YSr{w$YHRnD zscI|u+FrZoxM=Zd%Q4da+P(U*zc$=m7oS6aSIzVAU+;7Ha%h;}v!Z0qA5=7~@i4ZtSuI-LtIL7((fZ`Tne z4No+jx)!uHl>hEeDCqb9S1cpPv3jIajlx|$s}tV-}Qc_abIPlu;^Czt)!r} z`IRcus9@;kLq%M&a4)C_L&zh-K`?HHh3(r>6dFp7F4 zMIG63)99<}*cE>Q%U-!}Zs2qE1?6Bhd9tnhR(D*JPq3q<<{2Cktl!SjQh5f)eZ$@= zb*R5@Bc1h^`t8IAM@Z!f%?Us_UUfSVjAF(i+>G9q7q>KeBpO_13 zJkTrzJt=y5>&ac|1>%;RdMHqtBrsYXV>oTUkQ8PZBV_<>Z5=%sFVYC5uAYpXzCa}| zX=#68{cn7&-fdg=U6--c-ZzyZRCHj~vE*CxJ;fVUq6ryKxo#-m$M-$Dq-LYbcdV!W zXy~S2S?U@7Mdm`3uPAZ#=lx3ErM>D!zS&Cq=uLm+4X3Z2BSY(Uj34p7TDxL=0p~^a z{Z=>XLR}Ouk6zZ(t%_pFk=lDt>pJ$^`abnICmvL~<3CHMgQEm52_B-nIkFt>Bl$*N zzmm%3D1Nn({K9y1NjjroYA_1WKzjO8 zq`rP*zk4sBy|4cF34W#pzfs3tbsVn^Z`TEX(&=(DCJ!!5!5j!kg5!vGUV;PAT^4wWk+> zl5xc~{gQG_d8c1fzUj8#*40XG`#l}aj-W<<*4`Meq!4jyUEblE_{!Su`>(@kW$IpF zL|E7y(G@lG{Wvm$)+tvzFDsSvt0=AeUBoVRT6vxGkn(8pP}(K8^jAkjkxHIb*Hy0Z zi-sPo2VA2(TR*PXCW}{6xK?WEg4XGHZm~zICl1Nw!yCYH9V>rghEdua5_zK^Kxonf zcsq_7M@XebNCRpV-VqfP-Ro*6Po0|W37C07G>q&C-N6Zd8`og z?fT|?Gx3h)3}S_pt^Q5RAEb57&98I})sNkJIXdv)8CtpME0?2RO}G^FVcCjA0kr8${c0j%E^_tgHUir>UefsB1;q}rVQ0S{$#VrpX{>6Mh zv$Yv_*(|W(=id)6;fQ+fcrX`itOe)`N2@XqnDfeL{;n73gN4y({>}Im%K?p5EA^ON zdfqGLZ$+=`4P13#tpAzRv*3#6H!$zPR*WJu^qLD+O+e3lb%AXdH?fAn80BVp9miOS z6%J+ssPsB*plW)qQPvmRwGgg|Fd}wj(3I{@W&CNAtfCI;1lBz{Ho z@4&AbP8p?2JyKtH*Pw`Z;@8lZfnVa%$ab*I49j9xg=LFqyMiWiEzbw5#4ja|c_pri zWv;bp#4j-`u&h1&npI*`3m6wzwq=Q5vv@;dR)uB0xz+Kj5wm<};@37nbCNV-S>RVI z``X5=X^dd;t^>c;95byxM$oGfgX{k<{Hn*PdR%M7FIR*$axVEJ?FS%G?R^OMn*sFzK6=v1=m#fIkYaU$8wPY^`zuLkqb3ex% zn!HW^Rl_nlmt0IeqMm=rxq^#z@UQj2oxN?z zhsuP(#cGma4YML1wNhduW{GcN*2Mpj48=6%LuJJd`OwvNFF)qz|3?1Rp8h2st*(Ww z&c9aWS#9B0Evs82|N8ghSH0%-%H+e~UlUg2U#oMj4*YTj{eO~tsLoZ{H(Xylq`{h@ z=B2i!jU#f>2j{9}MR{59EOBaJDKQRjux14RsyLduSn##bxgwukNQ@D?K>4u3wa~mm z=c>1LsBu*>5F!U$V4M~WBZEb(gs^o)Rz~?(y=5b89mZKO+QO<p=Uidy(C#r7 z%}dS|wvKvjtKwzqX_Yjn)gm-6d6^QUvZ9=8N+}=ecO@^Yq(S*qaIN5FVe5$O3mx{2 z|J(da`(bEd^;X1}!@pLwZ~XK6SEFTPUF?TpIn;`{I+hh+huEWiBWxXkYhsp`je5yY zJgRU?E>>Y&SUKchMrrA=A2!CU{!ijx&Nu19;(V*?Z=He7j1%V`B37n;tomn1t`g_+ zoa@l@$k{7Ll=E`oizdf$HK`tIav4{d>K_raY|g2Nuc}_$F(a#oO3dcVN1S7Hmce<; zb&EGtKcA9#8dvCe1?Pl~g5k5p9GuZFjMeBIoKmc_l<^xQ7Do7WME($GqQ!IPlYB$| zF4rgcuKZobaCQdI-&M_nx}G=Qi@y1_cj(hNlPy2f|FP!J=?aK=d(|olpHLk1c%Mxk z7xSI^_PnTI9)G8AS6^diFMYfEr}^uB$B}=h@~c|?_s09L|J7YN*IvJ* z{qgpUk?F|u4LY0VyN=b#zNi1oV{ZlavgO4=rCs_UTGPlhH?7RWXzRdo#^*rxPbI_L zG&0T|K;IOgGSV_?q1yeS>^+1$a#H*K>6=7mIc2S-Y)=60Pd%NZ4g(%WE;whN4kZiR zblUsDZ^i-TJNt2LE4kyQvu|Iv#*t-iI@|lOHI58(S~HHO97Tq@edsxco}RyX zY#j@nL9JwYEbv(3`p6N5I}qluet?{L3ut|jtZ8o}2i+G-_%?E@T|!Q;lYu9*=Mu^n$wYTC{a>R05;DGmy-wW^}yHDcRA%NWR^RL*7`i@>wvE#yW0Ac6M!d>-En=&Nx+jhZhf+|eF%63 z+3MD(Tm`&}Y<25Xt^r=derIcsLkjy4+2uB%d<6IrGRi5JeF#12JTl5{NcmW)Go6P{ z^)YhEZAAGva6`5h()tAO6J$SINcj|SBl@a0ei+4^Qp%co6@sMaxIsUyo}d1FU_ZaGx|48i-4P@xoI9fbEwB+O&rT{ zv(p^fTNI1Z;zUO7v^j7~wzi<&JdNTQ<_u|Xk+yPA8cC09S!Se}X;?8c%>vF!vw>Qi zhM@=Qqdl8z4&%s?z)5K`dnczUz$s}eaB7+coR+2or>7Zd^J1&CHE`=R4oL19;J7p% zI6k$e#aKRtt!V;q66Y)~CZvh9C#Feh5nGXkgY|GpDn2L;PH+ecTp~da$)|(Sx!{(VeYLif*Yp@Go$gG3g25Uy46d#-u+} zn$wf?JW>3qXihEZPwZ((gge+^>2#b7EQpW)G7VC_)Q_~lsczh6~8Wool}?e z%i>psuuJNiI&+_AksY2b{tEnS@i*Y#isyjO70&~oFJ1t?Q2ZU(iDU1izN7d)rE_st z$x-hrIq6+&-&x!ZXYC4Km~ha>MUZl(9fz}u+r zEoG#8*?UiM3%x%9-b#HR@>36B503Z&?fZ(G+4oc6E!4f}yC2w-+BMMk1Me>$06tLs z5ctF5!Qvt62a6v8A0k&}Z(2h+|6$<6#m|60D}E0AdGQP2FN#Nij}(srA1xjOK34n^ z_{*YeBFc7J4|rqoU3$J-d=GdtR~ky|Cg4qM=~Zwo@Y>?5z^@ix1AeXeI`Heob-?S2 zZvekhd=pu)PYJ(Sd<%QejhwH~^|yfEDy~OLx{=<&#SPSYVP6ltzW6p$$_@0oX7t;@ zZx`P|PP&0!Wn|mmVT;(F;M97l8?al7*pNnq?8Zpl6dX2UV{>!78Q;=FysL+JE56AG zc+2)cY?8Z0sjPU-UaNz9Y2NS&G`lg5IFkAd$k)ML|QjIB}Z9S!^gxIHR84xW$W zsIJgZ>CQM>J)mY%v60;Waj4bf95)`rdfy2xDuRwaZ6uICMwypqvscc`y*2QdHQA#M60Ojx(m)LMIt#80>F9s(rpxjg( zlW!=F&Bx>$8PVf;suA#y>%ooj>0990ars#GA4mC4aWuyqlaJ2d1y?@J**6uh%g5#K z0KWr<97X@p`S|?0{O#g+%Js#O^c__cR5=t^2GEO+7r{>^nRgOo(}?ko_d?Ke_je)miN!wrft$v z;L^Nb-Y#vMg!|@wfcxcr^VaErybQREqqj;2<^%Fp^lY8BPurz^^7fRyfqQeO9q1EI zNUgw$)LW*5@_~6v&f1Fh7m9;upO0j@Is03YKU$FpwxDNAqzdJWIl$RSEHi1%XWvYq za?E^MbCG;z&{`k3AiW>?_5-D)doHr?`)F-I|N2NaGmxK@ZDyqRlv43~*mo{c^0~-{ z?K*xwTcjP6S&ny1A3=hA3;R9=d^7c)^zWEXX8V(6 zKI2an+h_9|ZwK5yZ=20;ye;kR@($S?$UEfisdr@SW5qV?-8S#R74}SfBr_+Q9r=^R zPVD*|$7xkk`-4(}sBi;QI8gpuHTp zQQk1GNDK2uc_nZ~TAAKdEX*eYSEdt_n$QWr6VnMv9q9O^_H#V#6VmZX9q4uR9G|-7 zlZx)SNA6C&9;I9E$<|3l*K)fT@O7ydeJ2%N%HH0&SAJdUTyFQty=nK&eSrOPUts^- z4>%zA2OgIO<^lP*G$;=QcFKc*1L$wcooF3PeO$`9DIc4Tp*}YK6?jZ~C=bm;@C*{fcr_{p9c}jjDkL0KaC_l^((>Db;B~Q)w z=TYprKaZxqpVkBUXY82@oSLTrr{y{M2kgBcIEMNM+<8p?IeX>+=j7S>K6-wTf5Fyl z;Osmr-%HPZ`H?&`&j8M%euO=<@;zA%^`5MTdQVnEy(g=o-ox?t=A+Z!cy~vq=ctcP z&r=_rUZ6fY{hj(~_8pV%<_h=ZW6@9V&cDuo$E5&+?QTt7o9@Wp&s}M+*VLuy$l{LNg`TcWooRPz>ICfE)CBC* zlz~l637DIXN`K}F3)-paMSeli)YA0ld{jCzwXm<5ts~PB)JLX1P0dY5q`pmkfc={K z0{b`h1NP?J7xUq49gz-C1Dg6b9i9d@4FC>m8VDTRGzd7PX)thT(~zbkio?@k>4;(| z+eZ|`nugLdylEJ4MALBK$fgm%QB5O(qnkzn$25%w_HG)}bT}5U!_r}tLxG1|7l)=p zfQM1PCA}%VIh_oAOL{BtJ*U!o2k=ewolVcFz&B8zn_o}; z0pPj$9N-6lC#Bb?59V|88`Aq}pOZh7KS=vSl(W-^*%F?e-j&{$4^AfmPvW?bAVFi3|UPgIO{%AfgpOp^4Quv;H0Oj5J zWAvSs&P*Qz9*AY}-T6Su+4;ZOb7p!MTW9Bwvvp=V2pidj#?Z7Rmx1h&4?$h$Av`^2cWj%=B4t!gFEAZ|4ZCRV;Qmh=O zbHwJwJM-yz^I|3S=EcF(+AR0QI`r0ja&`{xt-zDH>z?e{x3m-PjSb{r&Rkp^LcN5( zeM@WMp6G7d6z@#i7N@7vfbUGFr`_4Nw6q-VTb!3Znm(4!qx?5^l%<@#h_V>CJ6nrN z%jJjDM>yic9Px4BdDNex{y6aC=@YoxVi__AD>HKs7@PhQ|^jYf9q>F%`1)fj+dEiCBi_+)P7t(vU=NGu!`M~q( z{Q}#cN*B}rg>+5+KsqN~4ZJ2VC{9c7P7AohY3V9@uFhBGbJGXXwfUNS4)C1x{&WRr zT?~9L^_A?sDqopDn9faK&DZAlr?2I&mhk=Qed!ANugq8E52X*L^^13>4*?fYU(UH# z0N+P_IeV|jmuKvV>FfD@^nN{mjruF}T%NDXU(c5(t&CsEUrE=|{&L=c_BYt`m85^h zm-9E-`bxSiZ%F&g>6^5_Mc(YFE{ubL>AHS5p&DLe< zlDv@irRm$WzeC@pSezCXm*kBpU(8>k@6vQJTVKpK)=TmW zz|V8sa9W?w&Bgg#y}7s~eGxdOxPYDu^7+|S0on`oS2k)^MBq0og%$``dVVpP33wiM zcq8u^M{6Ed`kBCp;A8BpdF9%Vc|}WM4&oMU@I!${;%Z@gUNMe(EN}|-MCKPee0zLl;|-=usy-I%_UZb(-FZv=jmo~tO|N#CQs5qM+zZn}x~ z_tLGvn}9c^n}Ii{TT*YH{z~8w>f6%Q?7xk2Yx;HiRr(t6Yw4@$m%v{EzfS!dwyy>L zn))$%ewlvD*0rfmab@}jus8Li={oj2N_i~(j(yhve@p!cM_dQIj(xwU_iEtpsBfor zTlxii9|2-TO4^Wqk^Vsc?ZDqt|D3*Gq{rF1J$;}0_SCQVdHNZ!FZCbk`F?tst)Hbk z*!q6@6Y!3th3Vn+Q|gD)Pk=v7ce3XW;Ge0rHvJ_1h4!84$87y1J;BzUNt@G;fj>?^ zN_WwBXL^XOA0@3(4*?%a4<>ybg%745rYF-q>2Bb?)K8}SsGm$fpneMYB=CM}=Wm@A zb?)|QdY(#8rw6E=&veGlIcDeaoY{5l{4-qphv^xv{s8a+j(#@v!b0{e{m)?CjhS6% z1C8?A38+txbBJAl#{4pV^t15gBjLAN#>PX-Toa=OUoRtV`>qPns;^CdD@L-OORlZa zugNuB=1bA*Nxon#jB4eVzQCJP^idp1E4-@A%Tlc^(${g-RLU7Ld2 zuDfydja0xH)Y^KTg-{dcOKYCaMz=DzOl_6G21RXUn^Cf=)c^~?C+DQY=PNSV%w=Ti z*X0VEIlP&<;HuwbcKKZ*`^_wRT$koonpu9S$d)sMo|(+b`K|OD)A2Ur#L8j7VZ$!KUGt_A(7y{gkS`BD0a8qit zUAkIslTzzZvo!WcWXBwU#bjZr`>3HBzgxfj4QZ?Um~qqGn(97g;xzN7x{nz;&B&?l zV+05@b*lBK>zKh)t;bBC>O*Qh>N>`fQ0p->sQQpvkGhUgC)9e(B&t57)}t(DtO{)! zYB`Rmh-abhqn4v4q}F2wQ+;c+Uvx&xnM{vsyVP&gfz))=denjRvDYVG9jLk4{F(X* zd#rxG#sKn4`cd2OJ&hRLnPV$|S9`sNN9xra*(>$8wdIwXn;kt~P5szA7-QX0^jh`% zoIb6;r~Y~Mf=(|zwb8uXS35G^K)j3iW&TERp*iX}qyG5D>v?S3*Npd9-MP70KVrSw zSACzpJKv&D>4@Bj(dSr=`0@+NG3~rbp^IikD;|5 zu$g)^t!}_E)J79Grub-T>0rdX><(QqvXWVkBmQMjQu9rl5!3v!y`d^naA~cySgVKB zw+~cBYlxKDH3!mk>2yD+ik|0E_5O?-sfN^DJ|Lwwzn2t7x@_2HHb<=(??`w28ZR$KtC;3`g2Z+`mGQ`Gl|dX4RHnJP zcD2YRP+iZXs;dSqGIp8IC&iL(`3t>AJ=JP%uD^uC<)W*Y`K+Eh5BY=LF@#T9T z&vtA1?#GwkU_7|vXqZ@zCw<~wkI~H0X47@u%tTs~%kMdvJ#y-?Ym=EKi9@7uwb2GJcm>(dbB@NEreY8zxeQ0mYjU)WbPi zjF?0j02Ci4QH)tXi2Y*DBz{3(-~`SX3Dn{_fifC6k-jn1j=Tx9A}{b{-asGPeK@Oy ze%FMWIautS%rBN6Xvue6kEbo3Pv%#42gXWI^AS(xx0;_gB3Vf+wDUGYA+_~7LnmEQ^3l#KEfP8#=D%%iQ>c|YHXa*nc3Wa9SCD)VUZ^<4{{FBwWpX-C<|?;+IIs}!WPqs7j`EH(Tz;wb%P%#bx9|D}zrlRoyXzjLkMnr@u7vPg%;k-{ zTA~NrRo-*I!YtmnD=PdJvv}jKvG6O*=u=EedmS)yJqh<4(R z()fx3Mz1|V`(kg^_Gpjv-L%*Kcb@xl?-jq&XMg#>SNYJHAK!qyCuG63zmN9blVh)n z^6N-6;;Cat%#cn?%VM;KZYT!G7ag0%cI*kJi?>GSHvXqLZ*Kd(KqHb4WuI}o%}*0! z+2=N9zEmS(=7-iguKZ17IVz;8T#lN~j4H?17>eq3cC^d)``Joj>jI_{}BHB}EQL*|z zw5uvMKtv9Z7KJv}yQEB^r8zI<>{LWwRCf!lt{+q`Vp|3EGva|1(KsVUW{$`S&Wx!$ z8Y|KnGwG_a7mR!tvuj3S@QXx*g`myOzd5h1oEGc7rQb1M=RBSg+G1+sZ5g>$zYQZr zis$ly(GgxDC-yqd z)pVTaj5VXk*Uk2eJ&u3-Lkn^a)Z^5R>|pg=1Ms$+f_)2o5gR zgE8oMt+Wl}?g!m4s(VkKxti%Vi=YyKltk(g6hrzT-53aTG{T-pbEF&;RcUZvnxU~Bp7 zq#;VoQZhMte~MPIkR#>u1L3;LF!F!1BKgad3kCzFh|-WDK!2r@#ZaIWQu%_FYP49X zMm-#;Or=yZ0;sH|ECMc1lbw6tfIT zL&j2Cc+1j|o|LhC8)--nih7$gq&r2*uhiC!qQ)i-S&yRMf|R5yMNLQ=(uE>N*o;=E zLVD7P;&@!lRue@$T}&&N^dterNa;xdOh75gcEAFtG`c-dja^Ez15k}!dLjkcp*+JY zI4bJLwpXh4s~dfq5@I+~kfeA%wyljBSL=)(RHjEmun2<5c#l#sZ3%zP5T^JAQNRv5YJmWzO4cpjMdL}a}9B0!wvnNoUXgW{V z38*|dgKJCxPT;ti96b>@k>h6Zv`xS!j+@OfX6Vz`U=GL31nPq@mn$myPNSYz{+@Z| zubju&Dd@?ZKcDlb0H<*N0?wKPoI!2Yzq!Df)EjWjeBdnV4cWT@XtuzOIC>^#D%x&4b6>t&tb{w%OaMN;(ZO&2KQygPbxE(mU4>ln!4m(n|1a8TBdJt}lx8P#V z+=*)~#;vO-Hk`K$We5BTw`KpX6nzVKWNSB$*%`PU^=|ZThd<-?oUuD) z7d#`Cy_Qh=1C^_maFxESuHKRJ_W+N_0LQSkC+F_QI_&K^b1$yAJsy`kaP;0KHQJkN z?Ld18Tl;Y4PQaZ?-^-mjdSA}m8NbfmIcmR>V(rJV18MI?-+uJ&jgMtBcUsE1`v6ZATvb2sJ;11)s_jtbF0H8T=wBC$@x@g;JrAV)|*=g;OUTN2v#QPl#987N`rP7u+g)#|x zAdL!oHH~vdLlu<1rB|b%3flXoQ&y!{QmUX@@-fz6Q&y!{QmUX@QYv|uHmZ62rV&8- zU{I%^RR0`}Qa)WsX#vVDH!idr6U+fYP-_x+L};Skf%1 zQzzO|9% zlI?E5e)O#@F?%K3{lUqXD{1&7A#a3?5m?;5q@j!v@<#iTMm^@fT9Sq`#w*2QWsHzF z)+T8WAw7NNWF@dXx zPxGoek=7dRZAuzyLlvb`LyPDo}H;b~WjM1J>N5k+d$Pj#cT^+BBnzYN^+>tr=BRtEL&L6RGL6FLg-q zYMRlAl2W-IO>HPBm21{^gT4f%l15eZDr66-)9RX$QiqyNP%5S3piyl}9a1Fa4JlR7 zD7B_a(x_=ep(Uvk)o4_`PE=2+q*0YNG_a&gO8%7|6gttWlu8^{Q*dU!^(B2ly`h@% zY=xidt>es<*gdI~{Kdf0;IBG_SlkMBDqU-X7*lErS}er!X{EgF%7|t#M#`XNL%W5R zd2J10-7H%&er0feM1}D9F7|Y9LJV6h_OiXvp8}t#T8ZB zLgrDXflpde)Ecx~%%xtRJ=1_{CgQJ_38fOTSo?(b4{aJs{o3%9I-Hr*7P63|#Yk-- z8*}Vz;B2n92~?>Quv3Y@b4wgm!`O`d^MLa>Tm03&q5VVq#s(!WYnc$^H|I`+fl4__ z1KK*Y;BUdP3z6J6{b{kihqKq-NijXl7~C0uD4oU<=*DO<~EEk)kgpCb>T><9k#q4z*IZJ!dO#cORV z2XWWoKrOgR2Kxb(SeA3-fk5ZmlsCj+C6pEL>s~-Li50Z8Zz$QUgunIx%Hvm3)E!39 zx036P0BS=~0y%)b0UTxaUb(eaBdr_SYJE#`b#1l&UhNv%YW-bG0a|Q*e(f4sM}0P> z1}(NemC{7aD=1TF!Kmbo4E=DQN7(B*p6NBbmREGdR{5*V=Ip(F0-wca3VB0&y1Y2@ z?rGC-rodk_j^C*bR{MvRjsDOTB`9Txu*&PL(n`-naCHDs3y3sIj|{cZMoOhLC8g>O zJ&;BzbxeRFC^1Q?dO;5ca+T>|;6Ug>J&jWOl14edS5Kp)PC=>Wl#K;(F~Et42ztq*u`^X_WLTK@ZxaRD-!wc%$lzr!*0i zN*WdPDyUOXD&>tDjZ%`Vs8dj?jkx<3C1u+JYO?`tDN-Z7()VMllE-b${!L$^Q9-XN zN)J*e}d+yY!q)|<)&?sq|luGMsJ*AS{?nIGNNuz>ZHBu^RP9wdNQU%r8o%?l$ zHYf?pW0w98jgo2wjXIFMQYR_W zfhCVt>X1fBc@E-ET}!&u1t>L>Qtb`x(aN{Hb%dl57~LpuRFZ~L z$Lf-XGDd~P(!Kc zze*{M_}iYmp`_7>#ji}>P|^rouH+3lLP#A-72Cdq%WcUXJF&MdsUz@L%oU4=fHyU% zqb)3!@9bG}9A%G?G*-o8Y4|?S{T?sjZ-v+0IkPQX4yhv~5M_@>siP-XX$zM_-jEY5 zqf{7O;j)}dc|!@JSBckw%k}bxGDagVE0;7%8X;q7ZCFuq(iOBSysoT~$}LJ7{eem` z+A5VjYPc+amP;#j{B!b#GRCS>M^nj1l`}%#kYdqT~KdQ z(in$~pkAh=F&62dUMFgS+9+?dtRiWs5i4mlza(Q+I+6OalExUQMd(C9ot!fcd1EF= zj4CCK(a-?(pth(}XhUZDox{<32h5~yU(%?jQSIqO^^%6#O{2UK+EBfI)Rtz{s1r$v zHh}Zj%NzBY(I)I|lr%ycQctPmji6LY9hJPHq!CoBo?c0nHiK%^sFt$DB6N~U_As)G zmfFyUDtTk`QYWg{hUz7a)oE0{PNWpkNS&lSZRtl5Z${f~r5{Npf<`HIH0noEDs`fI zZAg5pX+!lis-_buT~yR5sMhK}HD0QMr8wx$BMx&%o zdq5Y|o+?QrC{<7=DOKn`Azf6Ok@Cj!lA47ERM9A@+X|$4sgoK|MV+Ktq3KAA`qEY- zSV>E|R8OyhMoG1dwVyanIa!S;afWiN8d2s<hQ7;i@UG=pMJVf~h7Qf8Di#I-bfFU{tPp{*FbMvo(#aZ8Zl+j?a5|1=u8Zw2RA<8k+(H^w0NDF3w&Cb^-yJ%z4 zdr4b~`K|O`+K93tQikJ4-D3_=Ys*5m=YqY?EK40mgSYxbZbI1@T-TpzQ_3dbw|a|K zk_DyKp>;*=Mf-@9MBfkXCmRCwWZIn8V({NFxdlb`m=#j@cKM zaip=*oQ>7aa!`qz+CulHeIQ#(I7&6*>2mrH0`5z_oK|P(fjC>u#_q=+wUsVF=Xj(c zHJxQYwqov8da{)EQhw38&BJ$hY~I{l^+HT3imiZp3JDS=nGF7&VDj;C0|~;B|$?$_8^wi6St1F56m4wPOS> z2VOT~w7492U60Wlawk^+ir0-8U60H9CF)yAB zA}CTpOe)} z(l|3Kc31P3YAV_qD=#W}d8}-A22`3RKI`$--aM>4OYg1PY;0IU<(o18TG>V2UfVou z$Qv;m>z%!;&mrydX~Hi}kFR)AZ7kunrlq$Ve_BufHS&gXVquQ1_HY_ELRVme)q>i9bA$vHJRg*xZS4tg0wLLi9%^h&9tk~bPDRZZSlUD62YqOy@{ zOHpR3G?$8wbp^wux|L^zn7%e|^H*2)SQn{7d85)MoUd)vBkD0aa5yP{I+T zdw@~x=@IKLbtrFC+JsgQwF&iz@Bs_iBcu-HkI*I>We+8dRkew>^@w`eL!F|MJpz|Q z_E=r&sL2~4fwU!c)Z=nsu^Pn=&;_NA7V6L->Ln0;JM~Cc-f3U<5W_>K2t6WniqIn} zokBfAZDKd@Dzu3f?&lnadV~^=dPE=aCo~APiF#b#n|qk0Oxa_fQfml#Lp#DQV6ak0 z=njF)mAs*3V~k%V5apao_Hd>z^abURngp^x{gv*pW~n3OjgURm7b@99Nkge(Fi?&A zAf8THV;_#tb7BzCSz9#-{U|D2)(0%4j=<%5&x*j`dZ|PIik@JvRswATy=ZAY=tZsZ`ACTjTTEOSomyI{u?njs;x5Ymd>PTag?G~z8v+lDz#bB z%9lf5u;pO1J{sY_;jB#M#SwEWJ=xYL!__CNdvS#SM)-1s7sm>Y{P)hMguaqXJ>`|n zr>v|0hV#MdDN?dm+kZpPjcQg!D*NjBZ)l~dyg1Z`q*Pi*wd1t!#i2*p+I=~+h^{{W zTlsHfs6tRGXH44iH>>yJSjaJro@VV)s_@@v^fA+aBRn@&r&RTx8~SFn=WnJJWpi{9 z=~Z}iNVU{Q>b*F&;h6B;*nvChHM+Y0hL(iYy*SiUwnLg|-|I{nMp<1+MxTw^{BPxH zrtDKc^SdXq#c-q=eT($p&@QUaM)+?uQm2?tk!Mw29C~yp+w1{sq*VHwDVbMuD|(bD z;poK?G^*a0V_&Y&IIAMJ4PTD%E{j=}ic-~kaY%V8?+)ozqc4a4W^MUz=+&VY$LN>n z(yCq@HP4NhLkW+L@Zyl3b@*>o{-Uen??3Cmp>DF_D!8oHQu&K+%HGOY3_{ zY+L@KYFPTTh8IWw@{9U=!a}O%SksLDRbCwWZ@6Z4H1jjz#i8z2dA6^MFGs!CsGb{@ ze|ycNV{M-8?P*3eFAnEn=e8+tv_-F+wOJR>_IiKOdKy*lFB(1@p&!-gRpq~-)KTxb zQE5hcYqaIxUhi)f{u}G!(;k|UzUvjGs+T(I{o9Q%Q7>aCLu|i_X4D?N3eS!3X+ zs60j6r&RS`95sK@pib@iZ>*U{)wH3d;DlZr^^~eTA2T(bMtP&A2dN*ac|m`LwREDk%El*6RTpCI#!JrRKJSf_!|o;&a^rw*gCh*kWnuiw{7pym_t zH>#K$RivQySHiXxDX2b1kd}=qI#9&oSi+qWT8QyCs+b!Qf1|y~8+yuXt`WklE+6-*0hYepZwXVkXDOw;aU$2O~5o`AK6w|YP z#Ve3EwD!Ex_#3`kb%(a&ebujRcipUBUavgT*Z=?VH|p26w;g|D3v3XsPjM#3b?y}w zYq_Y8^i_|)Ymf9*A3w+W0`YfE@xB_dc-8nhjgdEEJ?uXlf5Ub4>Ji4$F^W#CZErvR zMk5witJz-U***GJwEmsgFY6YJTXW35)T2VTe8 z_V(g$)Z?-^s|Mi=Y{cKFR<-N5ITl*bmfu%M9ePi!4P3#{_{($4YP#^2CS)K#&sRuqnDTy0)CGyZDF->8={oY&JQWKA&% zYwf?RsRie~kWI`!VP3jolrqrQ~67e^*S;Q*-TD%}-mx?;oM-8gt1!;ZN_oF`YMo1lv zk%A)TM$oHz8l`2oiV+m_Dx{8xxebQ>8UCTttMF5e)%vct*G4LBa$TIZ(}?{ez0w0UJW|zyVgH-7q`ONN`ktwyh{z zLMb+*f0I%#(<5~R5>Vu=GE?;~lwrWFsdp~1K>x3pQ5^y`*crUovGjm4$N3QC9679+ zZ;S-818rmN4g#yU1G>^>5Y$uqwrdB}(8Tn4l)30$&9satJRe$Vv|;52SN#}mctfD; zeOhRZEq(IFLJy7G(!!SbVDuI<6&S~55>mGrK#V0br8t7`+MnFTj-4YZM-)fVKC(Ex z9B+rS-M=`Ro}-Gx7=L|%hf^Oz&(X!9Z1({kM(vs?vuL|+>Ja++kayk@bui@^;5KX> zj7+^vaV-0K0}r8oBX#fM4b;8yEHE~N{sr=@lZw{^U(dc?l-|XO^qBX=$Pr5F)4`9| z6~_aQFHQiSz!5zu#szi#MnRbg)E~N_%mx}`qDOHY=k=gCYgEv`lyWdM@Hl#%r`i{| zFYUzMrNE`o7+2fq?docoL^%*#+K1y@9k>@zpS*6AeZZ5%Uf0tc#CXpo)XU8k&(5N_ zf@nR;9za(Lb)`pJ^{!Cgt`uk1n>b$Y*A?JcrxLnmrVGbtLGN6)_hYLIt^Ho=i^%Hc z$LUmF&m26)6NwBt-r3({t{1bTI41mJMyPIKv^mnuxY7#r9gi;GmU)tl@$CxS(UfN1 zuJ1_f?!hDR#)2((;J4R>_$@VOw-tTHQ#!Gdfd=^f2qG$e)6xmuj6HP{#bwC7}qg|&AuYXbR;`&&3R$;oNncKjxlVM zb;oRsUPtrja#TB3$J1_aB#-5s+UV`UNO3%ye<`waIs4h0zG@`*WAEC=up@T$kvy~< zw~pkIFO6jVM+>g3FKK^@>q*28vwo}xH1bm4^7pzfNdD|wQTkL?5bu?Al@)w5O54f` zj@6!QHvxN5>+_w8I%*HSt zXfy`1l8ptL8?G;{S=?tNP)a_FUuL`nF>zLjk+V3ag*%u*LCf|C_-|k8X*_>_ptv** zxnmO0mC)vCa7AW+YNd#orA(oWaTx7G=s6ULMJ_R?e4w*Lk}-eSJo?E6w|Gj5Mkb&{gFNfUXKr z|JWEzF|S4EQp$Ban*~EZ{<-wc19LjlQmZh6nlgqOv*d}*^RNo|cj;FF2f zYC1lrxZNEnpA@&d0mW=FS-$1^11XVG=nzJAWbaLkU9opC#SD&Ouh|~W$l~)3q?qT) zw>5w=5Ipls$=3?-X&lfzjRp8*?p|dlr6g&`Fv^&c!}uv!H0zr2 zMWnadoV(B?1s2MqYZ({KvbgqKi$=Gsa9>JlzSht~&B7YlMnfM}rZ>uzvT!fTdO*2= z)~T?M)udoob5&l7O2O)Q#?sbC*1x=?nqViWo0LSlr}fJFO7WCW6ZbM-Rw~R@7VE`( z@y#+to0n9&vVv(v^H&Vy>Ynet269)gD{rW+Y_3PeB^!?#R6d!Jy_ELM4jRW7^zMq4`Pk<(}65uIO)WF5uF}Ha8!&`Ksjla&7Zid93z3 zvs@_)XtOi>l{uu8Wz2_V{;5rAbpb2Qk+lh}uB8;v72H$;S;+Q!$U0`)+K5)SQX1+G zl!qB@qX$qd(!$mgDCbkQ=>?QiD(Q%u^32EpA6RMz_`XPMbAe_V><13c1}e+-qZolz zi&TG#mJ)4L11M&2Qz|q5soYxo)*y;G*|dk5(aa2kTGxh9%rL0+&MYwI7Sy(9rSv)y304VWM=0N@Qhpo_ls;;g90QbMYMpEbN<)<=rMF5L zN|%vgaBL}8jsr@Ol^DkZrPoIFiQM!?YB3JIbYu!&!Z|H-KTf3AC~QWkmje0A94S-z z9_IKm;+vTy6Tf^tdR=*xcq5Lr>3o~W3Tgb7#0Zf?B;K8|T+DV@0F|FyLu9r{NAyfu zGydm^m91vcKa(fbir~|aEwR8a){A}qh8AE8zgp?BnQz^TeZ9-CX?&9Aa*U4QJNw1O zax=tj&KvXVI}*$}X(mVQ&*pLLSB@6xgfZ~L5^b)>{^f|0g3ag4II7JHsb8|APO7tj zZ>lxgtdW~BF3d|gkg@^L5o>-)t!0kzVdcn|wrt3V*qCi8+=f7xyRAwbbm?^3?BggEptV zN_kw3PtC3yP^~XCyU_9~PPe*dr@p6t*P}tdQ?u)d{$@Ur(CmWWHEMS1dg^z^nylCC zwxC!2Zi`o4zf+HETg%%3+zQPuFiu@h9CNj&n%~e;->a~%k~8bIyh_^akTd@?U9 zu8MKmSj4-qv9ynORpvl(tsV!%ep1;|w4BsqpSU)z0S7CoQp-ummi3sZEyb*2V&AON z@}d=9Tgp~oRy_{RDJ?2m=PQg86UDi(rPMG^>q?_7rC!>sx24qESVolAl6s3uy`@E4 z%7_LVOFgdD+gK_r(@qk&HmJ0^1P+E>rPA*fu3}y3z`OqxybDX_>e$!8@78S3)RI|` ziIr8ep6kio0w2XYxt>0@6_&Nf@5~q&)|JYx61L3_d**-6Ji^-eowEjQNt<2EIR)j+ zRk_~O207E&g0}dbc9XHIaXoWp#+-sOXUrPJ48qIdcgmK*^3_>H<)1$qS z(^dGj8Cc~!LWP6QECjB-9DY}?<#q78|K$0*(ClLVE+ou}NSSNX?;0^qEia_adO36T zxxDu0?^f6EYO-bh{9V0lxi0#hx?FAk&N;irS-d{v@= z_SI(bR@Lv+>4NL6E^}6LW~JrT&n67*n7`w_{pZZzIbW_VrBSo1X3yKRt2E+W&Bjt` zcFvO5Yj$B#3G2$b*;UpB?`rer?b%gAzpJpX!aLVJ#q7Cwr%XA273}LvPra^J@wj@t ztDikzGv3J)L*uLD%zBGTP1pNR$2+}K+V)y`?fq5sR0*$@f4#qo-YFq%%J0lARF8dY zk~7y0@4|OQt7fA;Q#rE{`)acZT3Yn8(b7^cVTO(6i)4 z^oOU)+VnduEyGK{l(zJ{_VDgMTh3e^?`HFk!)NTZ_7m&CyH|pDVb2VmuHLE{Qe|MD z`LtG@N08ICe8_53cp#VW3+&se4RjbOH*-mbD{IkN-r{X{i{n&Ful zUYhITpSd=>%9`fy+TwR|x0umeRm)qI-)V1&`MYW!K@M1NS6P+QjeThrFXj;%xt?17Z_k7D(L!4y4;{c1xfdK5dyI+UVEu{N$@yw@JU z?(`04UZyv&H{1HL_X74}TVMLt^2uCtt4FVMOZw{S_3ON^tNomv(qG$Ljp{H;S86y~ z?qbD(7ChG?I4kU$FGrG|zSGJ%UwyP)!Ju5EkG5Hh!lTz2CjEPzXL4qD7Ek5;uCqw` z>PnHFIhw=ss&%MY=pm@4uRNok;d%?dtnX4er$74of|6S5d#gsTCvAAz`Yz3N>X-6e znw`jXANuz>C#!E!tP0T*y-E2lT`4jQtDD-!Cgr=_jFxhfmN+eP#-`9-px>{a!ukXo zrNS|*-?09}&Pc~f7Cn!vwJlmX!~o~vw1hbGCiXikCkJz-jFwDS&x{9-ua584 zfnOc?)jX0`&V@wWXIK7w#(o6*J7+Cy+_KPXAHL&2~UZ|Pa!U(=wX zbMBO}ZRgIwuDJ_vz1$VpEw2ac#Pz%9ZnS#j?!cau!N4BWL#VZU_srV7duF3%{WkT? z!-2z!A9MX@(~r5&GwCPP&!nGH3!h0(rysHR$7uvd4lf?2@9Fd~<*D=#{Xa@SW9up4 zQ|Za{AUzMIpR@HO@X7Q<`XN0JreCo21n@8E&%h_BAE5t-X(ZPiQ9MH5pVR&HJdhqu zkI;UU@~1S4y(5dq*!oj?jPl3yOKRaC)8lD0dyVAr%d-8u^jmsrmv=J(|y#}rXNs$jqQ7Z_ojQ&HS}Byyr25( z^xXrzC*7T{rso=9kK+Dx9esBL?@D(9@20+r{;ShB*t!#VXSyR@NzYa3n{3^YuAqHo z`W9Pv0KcDZ2i`$_J@xJB+mzdY*HeFo`ZnOL=@#H^)HhJyl0KBaoGt@?kov>v()1w zg!=?n9#?#ldyFeSl|BhPKYa>#K{_A!xpWcmqBOQRE}flTmyS#Cral&U9PmBV$J2W@ z@a*)ibON>TUFocJ4113SzL)x#^gikn*>e`~taN5Nnx13QNo<`7JTskrt2d}lg6%`D!QE&yJ@^UW;Yp58|Ll=ODsJJKn@Q`0+u zr=?SYr>E1>8#(XvG^5xr?F(F*_5;3&-WkQ4)0=>ANpA+8oZbR_YdRUYZ+a`xJIyHG z$hkYFL(?H?hjbYA4wN0!PLxB^_VnxkJe+zv;P${HsCQ=nA;3e@!D$z2;lXKT+LpcB z0gt5KmA;k0m1#xVhMsMKM^W#__Hy8^)YExd=dAWmOKC4l`vVV1%YX-_1Aqsm1A)ua zLBQQOYj@6@UM!)WUhI*U0QXFL0QX9J0{2dP0jCuU()={7SU)WQZjjaoZkRRzZj?3z z?vwTg&QJRQ_vZMCX^XUZnv^C2CsPX-r$xZcsVA^^B5+IUR^SBSR@AL&Yw9T+wJ1%c zYzCY{J)Zv7G>z>|fm5l+(K8;n4fS+-Hvvwgo6A!%^xm3q?ZO+BUf zS@B%)bKvvT4;L>`KV1Bs`e9l>D}KSg=YW4J{tA4K`lsxDxOjxEzZO3!{=wEyC_gP8 zW&2s+Bh-&kKMQ=OcpCUD^)IQPW}dY-cbr`Ov3MN#C+f+?pQ$GoeNyifaxyYoap25!S>=w7_Y zGj^x^1UQa2>-=qZ;%ok}cmVhy^{&(pFf;r+t~IInJ@usG57d*2Td5~;^*;mu%u`O{ zh`$g8^+C?qt+>DV0q_Cp-MGdBM6!B_Jv&i$26ks_clP{%*jC-yUP9}>GUncH?;!^3J;mK+MAmzlEA7s{ZGqbnmG$o8t};gJ-RK3* zOz*??oxr`Rx8ay=%ZRLZGN3M7SncaH!+jD1<+`P zshq=2}HBRjti`#g|Z)D$Xz&B7IN59c-H>7?OeYXN{<-H$EkMVHT2j9&0MBtmK z-$Ff+c)89U978#lIJygI9bL|YpUnP=#aoM$fk)9}tX<4kz+&qIC%H(Bh-T+qmLKDHDO`vGtMS?Ik>g`XjW?D?Y}aiN%MD zQ`r7*wk8%IqWxjuJE%WS-$bDP2_K~AL%?O!pP+9-@k#0l#kur+5NHJ7PtiA__yFy5 zfkyNFKw&iBbATTJE~h@9qb3yZr+rRw0b3J_Pg74Q-bc^-fh(xrN3`J;#e0G8E8YWq zFYsXMck{~*1|H0IE9Xrpt^>9LFQonkb!+kU;xlZ0opN3AP5N4kuhH}M;#+LB7GEts z%hp#ZUn{PsueG?gIITDpcq)6YrF^ycHhWr&Yv{kW_zqjG#SPT0#nr{>^j%H4rnstj zCtFuht}d>meHHM(sIM%}puPflC7uH}a_0EryVT=p8D;%@Y>h8&qP`h8zPN>Yd~p%= zc)Tz!D&gm-XBD3>J_q~)^{nDz>RH7Xsb>|JP|qs9L|qhTa-X6&i@GS@MO_qUQy09U zvw??D7mS2MfL|^y1Ac|NC@!Zic*e_tXHd`PYQ}H7lzIdDF2nERQnvMoy9~dNOW9sP z>r&wQ)bnT=M|c7Ce9Anqtw(Vb6znK?T61$(?rF4cb)K$Za0coVY&`l-Ks{{qnpuyt z%o%0;cB9GL(o^2-F2=Al>VVNL-8K@U9z1&C7|XabP?}+kUnxsO2al-2k-Z`E$9Q++ zgqwHUD8$BV?7=mS(-;vPo13LIz9)|rs;5bN&g1xxmKf3$6p3C^}LaRrKH9bna=uu)s5033# zVnvT~T=ytPbdPf6_F!y$mUA2$}02F7!HP&jvc4uA}E0j95pQ ze>az7(J_4{V_6(=yoL6yC2rhS;*50kozPElNosm}NpVjDiif`ex2}eBUPJ5G z;NLayv8%x@dFR#e)oV-c`c-Oq;8j2|@0Vb$9QbS0a>XlwS2D66qep)Jb!z$K6+p-R zqx8u6yHGz)-{nBDLT)bEM=XZB~|KKQl*~!%8Or;9y;@ETY{BJR^sNPKsi?Dl0S7W zxp?Q2i+3)$cxR5@qQvD*!M9EvDc)@g{u$%f$mCKZ`Djsc&7$O#MadTnj@yL(O#M3U z{{x^>%W<^j%0`SozLZzw;P=68my}#t>E(n{nvvt*3;$JyIfim9vVn4p62d+3-#ts- zY@GR%N;yUu;%<2HUL|jyNv-s77w|5m#v`GiGl4TX;tjl|o}~=&3{c7P2=*FPUr#%w zhn{fi*(K-J-|jHztFil?PdyZBIu|&%o2kLLPl5#M- zvY@pbxB?Da(CV9%H~J*yiaxaaB55m!^h}}-o{z)08e|jU&rd0l> zqE}LS=*5w}k<9yJQ|g(N9(vN>3n_g7Jw51AlHVJ7Ldm^P(VezZzcSunwtJVdJXy5p zQ7140zj8ekp0;{}(wO=Iv5IM{TPTNh0jhZ@dvyk?mzXJ_6HwhnX`>0KmZO}JfoeDf zzdt8sjzl}7<*ALV4^;0{tJx53q<5+R4Wq5bvVeYdL$w_>LSod?R%cWrTF5qW`q@L& zT6*TAU8zB-b@f6Ud$t&jE;gE8wKqH{liI}``sbFq9iEj*on$usb4o3cIH^hfWETCi z(GWM|teHuzW+wf!(u|~TGlQO)=z?lE)9IO!rX_WlY4l7-kNgL%sb~rRD5e0_H4Ey= zz$xjVQd2#!)MF2%eGr6gNmil)uv~Bg+Wt0O-9laM?xH|3r zlx3wh-wW-041G%}`Z7-p{2U@;b`R3yuomE;E&MfT+XVN|k zdyMu7tujZHmKNeEUq z#c8xpPkoDbb0pck_(gpS?LmDDEk4?N`eK98&T%T`w9>BA7u$^1k#|r|#V+=Kjya{Y zot#4dJFt?SL(ki>s_cLzX9w&!1BwsOb1r)ZVDHi1@;1ubvAms2&s$3y%UkJx8x|XF zEGJXmiVa7*%3CNWW7XM})|WZ@E7;+_LLK(K%V=rq`ylldl>WfWsl(QHX=(4f5-VQ+ zLi?UpKJ9^5VQ=hTT!QsWE1!11tLf`se32e4ds@h}UiL38rme+K``EQ?_ro4~4fPl3 z(aNW-OzUXB;`6k%{%If6LfWtR9Br+C+Q%*eYK7Ap_F147KkZIq#y}jZIf;=be2Mx{ZI(#rh;{V~Tdgt>$3>3g2yT!QxG=P1r7e21;SQJhz} zfvvw%oL#tq*0b1UZ%9MSIfkL-9K+CZj$vpy$AGsya|}b7V;E9AgYEW4W(IELoTss* ze;4>&wx6QyynxpACxOlgXyJVV_+*;IoJ6-gk=cmu!0vfcp3FAUy=isJ6SDIZ6DSk& z6!r`)T5~V@S}7CqRQiS%<8yEN##37JH2Q`XvtF@p(Gi!;0y77+&Vnv-u6C zbJWmcEXRz?W3%@E8QC?KGqTaZXJls&W^mq!q9y;9d4U#=8JlNjea~m+8Pv`6x8&yR z>_RhrV~R1foAa3LOhXGj%~-2vaSk!Iv;OF_^Q=6Yy<>pRL(Ivu**A*z=sYSrCownA zp=Vy63!IjHKf6Gz!KzJP!ko$ismn^9bOmJQ8>_?=+Qm^HexP zkctZ!Td8nfBo)q-q{11LR5;_33TIr%aFqMxaYet}7uY}d0}jajfdlgZ;GjGZ*oS8r zR}9XBvN?2yLmM79P0bAkJVrZU3 z83G(aZyCcq6StjhHBC&C6#omXuL&MF2{;K3k+2c(3fvXSm`dAs!VdoF)Z84}UZ?VW zb<;<1rmbG5wiOi9uCQ@^O{}Tu2}UyKNKuP-b!;!Na0KxGvG>+-UlwWm|I9h_p}U)#?v(BhK_o@# zMlrAp3lR}X5dpge3%k3!3%ffAJNdnjx%PfQcYS{D>h5=+*NZ>qn7PiGtET6iV`i!# zEkRkV23F&`ByOGkpwq(0>s)JwRH!hSzh+LW@gzN`D6XntF>J+072c_LDUGY}E&39r zab><#-&rtyr&5|4j;jj%lm11qR)HAM|LR=Wa$pWyai=pi6eo%;pPC{2e_N!kl(M5V`&4nt=qDPQQ637x2<9IChK{0XheS35WmyFwakR=}+}Tb)2q z5u=$~tstv}(fqB}L|4XWwNhVPRT!1^B_{gds>=AR5Ao3(m(F|1&VN;n*TZG2ZM4p& z2iG-0)pc4|nFs3p1FiU~1?GWTQCS;Qy{0`+>wu~qw2rGTsPhlBLq|POE8(U;e%W&P0m?{mH<{EuGSLoxpW}bkn#+XLb8A|OY7@d@+RL#x@Z;HGL^-WQ( zwVu2vSd{A)#Hv7(@f zbLsW#l+uZ5IxnqlN}Ye4YDzDq)V5Un>(fhRD!-Ivrz$C>^4GCt>7_E2pK9GxDO1T( z`O^IM-XOz~7d#|E)e$nfi6Dm`gRGN>+9v;Xf`}+fwa6Ss(th z>7_O+zZL6>>;GN*^?T{{XWFmds}Fy#e5ozlRtu#^F{FN$;%I>S_Y3H7banf03?9x~YPUGpd5pToq&lSRK@ESOxjYnqZ-HZ*lIERxOW_j~IXs z-A5x(dI-mLGq712FKOOfnoj8t8zU{in;L*(W=hwow9>l90!X#eTdNkN<3cCSA890B z5|^~JC5gY1TuVz^l33KW^s^*%r(xXXdrgO=Q zfYPxRNU^N{jQpFW_!0X@F(GDAN1m&bV|9+K&Q;L4>1{ymIHuFn+kxUjX@n_`g7zvB zA1Q#vc}D(8;hIH|Uavk_oqSRnS9S7-^nTI|>U43PG+u#lRlw5N6_VbqLejYD{BfOl zUX8D)fYBH?V<{;`q$gDF(Rskq6=r-Y{e!NhJJvVpS}`K+wXPc^SADPnG359n<&>Dnw{X@ER~mLsl14LU6-8Uc#}>e zm0S9LF}$^RmCBdOVeOO)VLNlB9UE(rBb0L+le)_1DxW$7L%Ch~x)E{F3i%-14M`i7 z2$kF#q>##p%42oXNu@@mvKpzSa->pOl{Bl&w`y16%AodpQ$68H!w#VMCd?b4Dea%w zvIF4Ih^w$*3bmwglSWk2i#6I14}#7{Xa@m9oH znFU{FHh$uX>o*_LmG3UhCTMApxke-#8bK>nSfwN~w&raO9vlC}d9KOZy^~8!3 z*Y#w0Xht}3S{K4qGp^4|JUKC27s6OGq~{|$2^3H6dL%c%>JxKQoYe*J)C}ph;B|1& z4A<4*HSo?1S0L1hpxAOD@#jL~(uKsa3yB#R5;HI)W?)Fnz>wIZA@Q_A;%SA%NDGOh z77}YMBnDeZoVJiyZU*Xf=}zSTKiu0Yhc@u5);6=*dcNCJh@kOr?hb5zFB&% z@jl~f9e8PahoyHI-(*O|r!&4%*W%gfU-if0<*5c%YPiIlbcr+RQcSxP$Bvjh7hlDw zOY!GY47d~nF2#ULF`zHIB*nKFx!0%o7LV|x6w^wH>u`%BIG^+oUs1e6F&vFpzL9IC zu@Ub#rdSsfQLI|y&u>bpu@YN6N+U+Zm!69`o?N?%tK-O9tH9Hc9*g@pa=94T$6$^n z_bXo>jX8!=;rQR9Qm#A-`O%aX$Muom97>eKH8tgDl@>9mGamJFuBN5@tP-`1aw5jH zSk{wM30w+_6)OIiP<+rC7$fyoq*5i$_QX_nRCotQk^jxvpY4K>Wtkmqp79DZ10BYPCcc% zs4J!$b(`uU)pUDP(}^pm`fe7r*S@JfQ@zwH)kvxt_aayBmufgM?R%%XNVVslxM%V& zol=d_iP}K9co(iZf}N<}cS*Ip7?SO&kyY>Sirp@)tZ0Y3JuSr0)J|xnL>uaPwI8bQ zcLLR}sE%(9s=X1LuxhIRtAJ`@)M`{t?L}qW+M}*2t%KSmq1uZ|_^P#3Yf_1pK<9>6 zM_wbf6cuUD2GODp!mk4EinO%q%azAepzT$Ut{g_a2KCm;V#?7ztG8ALqy9qE)W1;M zTZ(p8ExFoT_0rU~tGz7&s`lyjdKj8jS3gSZZ_OvG2PQUlHixMhP4&cl>Y=F5Pz-lA2k*%7%+r%! zn5U;z90l%%TO3V~QQurGe}0d>W$LkHy_aqMqAHXc%~w{%u8gUY;@=UYx>jsE;#Jo* zK}-Mdh+Rq5!!Tl3*Xo5>iVI6|p_BINAW>Xsx5jNdH!3dFqmE$r6#HtS%aC)`cj`(C zl?BVBe6I9RJ}*r^R(dF(mm)8hBSf#1D$3y{$+_xlb;hVAcU<-6Z;OMyusb2?Osp&R zlm^AgJ?inPw^59IrWjUkD@uM;4^e#-t+!DsD32B<_bGJ-rqogYrcla}1;}|yyFnNO zcjiht(x_!J?&%b4)j4fJl?O3X+feJMCp9^hsL8mdP{(xmTU{hR>vTej)!LfcMg6Ra zm`SPM&>B>liV@o~m1Hqvl{2-nMZ8(%UNLK%r+PsQ+gV6dj|i2|RgVZ&BKF1Agj!)= z+_N!_!2PgKq*hX^tA5jbP<6igO==7F0M)lT0f|;|s3)biV0TbGvW2)tQ|pgQZGn1K zY8`efZ=eUtLbya1^NClUmzjXkFENx|G)CSnwERS`~5>ZR~NW*Qq*!t(ezfAoai#dt8XR3K zezYn_*DFDvzDcWfB-LMeQcBnARcJ-ZDo{NMpZ?9KfAi_zeEK)V$65F;BR42-DW|B% zAk>)Kc$G` zVlDaJ5kjeQaY|{SR#_dGQc(HeLUM;zWhsALNRCm@SNY}w@{v+sx$1oKm-^9%rCgyr zcV5bc=TNp)R`*GzSEYUdVXre zQ%*)YIOWE{DP@&@^QeVRPPLDEc{BN=MWpRua@>$qzJ{c-qjESmmC|D=r7DR-QyJ8{ z%wtn|KAMuPa;hG~(Uf_WK9&5Vs0&mcRU^!y{+*I)VfE?yr`l9C@Dyrejf46j>7Q!j z$>3z_$-b#i*EiLpeevy=YUW9x^6H?}pX-Bf-&9vmpgmBZt~aJn%8?U5)mn{Gu2!8m zjv7(5oNCOmsm2tlK2&`wR6VJhSE#yC^{-Ghp=xKL>c%>>W!*rvX=)$4(JpFCs#a2* zAGL3_F?DD$)sof6uS;q@#Rlq$pZXJ>X={6?7FVrb9^c-J)>LEhh+ikL0k(GY%}ecU zN7^N|BWkNU(vqnsr}nHvYR}q(YOM;TR!MDM+tdmQ)n*k*ZI;@|ol>hQRNG|q04jje zX;|u|8NG+fxYf6_)Tgl2o3PZ6$odXOZc(puCSPZmn$#3(sY7bb#f~e9TkU>GeFJg7 z%HTHM6;j_Iq_#eAEuPr+{hLvg<^0~yk+@Y;Z|fnQgFCBFLux}?rj|(D!PY!SeFN=Z ztldZkVrOTwi3g^$?WKFk&dKPT;ypVXqYv?`J^1^kG|+y@+xFepj>_si&tCe0` zsNR<5_JoQnY3PKCy==#BY3?eM^4iNe|GYuPwzPW{Nn!oF^nKFhs^^oPUZ~j=?ZB^n z=CV_ww7azSn%3D+(!puRam8)6>wk6@mG-CBp4B=ZK$^R3M;gV7(j_}7Rr_5RC9Ydz zYxQHcGqyNi$`?8ZS==!3!t&4D(k|Nh=fCPaAn8YQpz@t`q1oAa*&f~6!CU=7=|Xir ziuUl`2Nh9PzT@C)5M0&bikQ&$k=`K8>0XP`h5TqgX z4-9OGbO`TiNPVOpy806VREggeGlcp|T*0BK+z;iOo8aCR*-*l0rFc_Z!w69Tl*U(m zlpOV!YK7sLVX0;-nCdj4bk8F&g~4X{jYxIINUn>dx~?#&nqwqp1UXqXhw^g~um$#R zxQc@6`>7XI1Z;_|nx!Zx4f$w%cLUW++?{LIlcdtBny47=*4TR>Edi=@tF~el3a;I$ z#iWBDlgj%TeD_H8S_x`8Y39eKT4HRfB~#rU|8L%VvM6S!F+PN&)5$VKKn@vo$*(ChRQ)_GXU=osvsRl1cUEdkk zWK0E6wdE9C6~QiCt8J(Ns{Wjcv=S%{vs#ggplaQz7-;|f4R*$_h*bQ46 zx+-7~>>0SKf*LQWmtF-_jXeW1of=KGvFf#6U{9oKSE|uYiUXRBwxtKGmip?|LGcUs zBK)49#wB}Elk}lA?u%;{el=6eT!VJIFRs10&I6_YSFgS%s8Ner`C4EI`<^o*uY5kbVwXFRnX*s{ea&e{HZkb}yveNipeS z`Vg`w>7Ws*T7sHjE$qHrYv=slgz1avO3L))j((Wlq>tym{+K?*y;_F>sl6D${WWm+ z=AHqVnxsu1?i+~dM+#~0hC!*-7{onQaSy;AgkNv4H&=rR(Fg3qJ*o+%O_vU32>G=# zI0$r zs|omxr7lsMA|0)CeV%(JQ5zNm)%HyyYzc5IcTB>J2PbefnQ(i6dvGJRm;rV*|%I0bte(h1-MuBKDU0;u+JI^ha}A=N)(tg99( z1Zv&t^z^JuldKw{7I{RaJLBxvAV+y}kXp1Fm>j4Uszz#|Gz(e?w`zbI7zav!t-7W* zDWUeF3{TQI6{^Y0a9uLhchy1FSE?(klD4YDrB~Al6=iT$1XcU0b<>K3BA{BUim6pn z{aYD#4g4$emNH;fuEeRY$`@$POQ%MNGbi1MQl&lLrGBZ>rX7DG&57cuE&rpIOZ8G4 z{!08w@yf+D7sIk3MjUi8&&5U;H(iW$^;Xm?QLCyn5SLvHPW4=xrIZt@l^2J)Y03xU z#ESzjcD&|k#gG?kUL1NcH^inFw_dfDa%4mPOf{17bc2+q>x14X|h)W#*=Uv1o~J%wt))r*oAQaMMOOSKQu zWlD1?m-K|vUozvKr!X-|0;v1)^5idC12H#h0dB=nR?P_T@`bF0ym=luOmK&+p4`--}n>re3_} z_0^}(@5^uBi_gl2%E<5a<;8c%PTbA<^x{P{N##-fclF|RvZ%^x{;9tCeR*lcx9`O( zebsxHPD#06V;Y@rqkONCPG|C)N{Gfc709KE$!tudGi-Ijn8rWZ$SFJjFN<-Fcr*r5 zsnZy%8!@IhRJ@g?gk<9{l@pDGbjGJjY*vc0lB4mEPP|sB&ej-Y<2jw|lf`W*az>U< zls|O(k48>AVXJKQ29<*}f>H`7*3~=clj6L%tA$%yXq_gcGN+SuG^*6dN~0;APoQYwZv4&&bHF|I~sARRudE5Q$DkLG#fG1r4(wtpiVgwrz0DWY4nw)fl@`Y z6B<)#RHph>N7Ee2lD+IJL`0?{$OqFJY4-i zof}p&)oN<5`ca#aZ(j0-t&T6@Ys?W;e>PQaI*ja6!P~(+S7@gUq zGN9?OMx3if$~Z=mRM44LYKzpeHzDnm7OG9R=~In#V?`&ark;RM zEmEWOe~r?AYgSA%Wr~|dDV`dom}A{2G1@T2aYN#{DsH8N@lK-{xfPkLOuh$C|ZT ziqR}&)-L^{Fx$6V+rt0)Ilm2~7V-Dm#%*E$|Ju>*+d?CTwUSghO`0pUj>=m&6AN=511w3b!r8ZmlK$@B!JsaDSF3CiIGFo@9vM|pml%B6}`nGMWaTPv?(HH7#wH{N?*Vl@HmVKdSKlR0` zt+KuY%k{~r`fKSNW6HY`x4u?+T5CtMwWWHpPNplEa=ciA**f1ce2YqYA&lOq6{JN{ z3>3kwKT!-6#fWJrUYl0R>O4Aja7o`$jCcI|c*{H1-KZ?*uNzgl-L_(M+d4#*(EN3y z%E9^T+Wzsnn_rh5<$vW&<cDA4sObgDqn>$%9AQDMKIag zbItn~<67lZe_Rt=BfOfRbm+O%dTO+%oUb;t07map4K7Zs-laOd5JvA(OR81ddY9^b ztshtZR~uRsqc2b!S_~tes7h9GjLL(`S_zCshiXYnV#M6lzn8*@73sJVD^lD@#hzkK z%vg;VvRG40>dRHawQl>LNtf-@G{2t7uMd@)|5|XTZS zJo2kbmu8%5;bJc?T>4JUPpNe4JGHZf@~!e)4x`l6cNV}XH|smapjL@IbN;*VsCKWWoa#&U67${43ETPu`d_72et$smkl!m%Jml}Bp?FZ=K>w?F$Qbrw zTB{eJJu3CSKi417SL%sbf8ekEPJN-CuaVVX+i&@IJ4Y@T7J$HuPMv9`8iX)$Y1AJKl{>X=YVTC;)Vis?Q@K;?ruHst>Hb}9T-K&-Yv~k+rTE6bHcw_f==_}d z=gN*^Kff=X-&X!Bee!>28T@Ts@yGJXwtTgH9?Q>rk`*FnsBfoUop$C?pHKY*)pOeI zRxzu6gfgC`>R~-owXEvKKcA*5b-y=0`fq*yuWRz{M|r;;-({_(G(2iAbxwF5F14{@ zo~U(IE339vt*%;Q%|NI%Rx4c{RQs&fyBer=TdjIkQ0=)|d+jx(c3!=JZF?E1k6JwS z3)E||fBm_1W?H4E_|3jpHNRq5SJ}LgLT9B?`+(^_^-r@Ef0_0wTk)4^ zwUh>mef4vdHcA!se=}ZMHi}bj%h+jpw&o48eae&`dY5*%Q*H2jW%KvOfcd%cw`Eg# z;2-JMwtxPgFPnd#=l{M;<-bKaHou1XSIhpN>4zwmx0NaBKcx>;E>v5PuMhmSCQ$q5 zNk8~&ec-P(f!gO!`oZ7V2kNi4X#%wZG~1Ez-%+l!e5+FU$I6S!$gfL{@~858{+@W- zmzRH3M)WTAjg&Uq_nP!%m7FY3E1&Cs^LIg1u2+9aHAeMRGSspMjQZ_r*&{}IMlE{| zqdcRQy#PijqLy9jrB%zRW!El&YL%3lViPDul$u2_>J_MEFN#sGKrMSQj5JhA&Egno zsHAz*`f>FNq=!&1Ky>N1?t`@6F$dQLD!b zr?(eIt}oQvRrd9TdV5ifzEJIQF^s-Yqj7yvDNyG(D2tRP zon=bp=+~O|5?m`b^2^k}quu$vJg=4_zyGFQg<6zC*qSxbNTKlGVqYT#^|YjC*|y)P zN||&o+eXS-AO2URMSfn*a;b7`Ou1J1lRbk|u2uf5$oDGODt~IfP32n6aVT#p-{$Wc zs$8mks~oFbn(c0?`3~h!)%mL5ls7dCvMtBv=hZ(`Z)d&AOo#Jlp7ZPaUt@38HfpC; z^GH{qQmmRsx&oDA)jZM_D1KD)NLQfvQG9B*Qk7-Jr}k4-%qTv^U{YCDd=|whW)zc} z|53~+ZncYqY8%CB35?3NVwE!jQcl)RrCIIs&*X<+&(>`}BbM#Ct5K?QopP#j-EVb< zf26%oUozX}A=B2WN2k7}dOzyXsn01*r! z`u>q`*k1RTUpDm|nQRP|_1w1g<^Hd_TRC!mt3(yAE)l|+?R=>#%ufb;+=r@z$({8|s7+$P-mH`%GZwawWECfqjO&V8out1^0lLU?I>S6%GZDP+^Zeq zuRn4w&yI6mG~4vQuQ%Dze(h+#cC=qR+OHk$mzZ$c$3yefnnTb`vc}`t3NUGdHM6Fb zVcYA6|IECno|(@L%NUHA&RH_~Xno&5%Pq<0A8Jj__Hz&!Cqk=4wN6hw5zU(yVa8AV z5zYSxab6TJnjw=dzDH5MRr8YiesOg4U;2Kr;`Cqo{%qZ>{zB*Gmf?T&7p1XvZf$m! zZMOb4JKI(3a`i{rvtb*5M*H_|{|!2sR%h0ViJ&>)?Bv>P4mewpD1L_4fr*)samBK; zZ^d^JPfYx*jI))k_{~-YXJ_bYO{P`^i>0m=UW#L_GSMuiX0J6bE;g-VTCfF6m||z z`$3qe{9vwxPjdG8U|di7UBck-1o#9epbrVV1mWYHfWB)O5`>R&4*JlrYY;xl+0_fe z(C~;qF)RRkS|!)ZjteK^J`VG+?`^%1^)Su0_rTTDhVcyp!?2)q7zYju<3ewI=7!_K z!+tL2A%A?B8-zN8ypQ#^aiNcm4P(G@VQlDbN~`WXvxm(KI3hw1$X}FEJT}r6i{EBcNr?9U;eo9yqbk6!3BrC!) zLe+GugHBstjeJd573OiZ3bQ)Yw$WiXaQ848?2Fyi#1ZPsmvpn!2)Qbp7EZuEEzHMW z37!^C1y_Q{V%M>eVFWlTj0ATJqrlqOT}-*P3s386b*+w#2z4>TLuXUY?Tl|18;@*w zsE7af(8-jGJK@{eCLkLh>T_EAgwPRrCsW?;XcLi52n{&bePZZl2gO! z;V|s>$U4~hxK9t~hr_YY1J4JKz@8Kua!&jto-r|;i{w1;NNkmn_O>U!lfpS+4zhDF z=Z2X`_6#~{ekM3G%n0qQ1R38 z6b=r1*_q)C@QiQ)xF=Ur?7(mkco5+V#c5$`C>#sLsi9zO#8(!KjjfRtjMKw3+|xp# zSR@w4w+LoRD1dLlXvn4n!%PMzhrL1$d4YJ1-w<93*ZOO`@TKr#xXxeeUkq3Km%|2d zL%7CALgr$OO{}q9k6%r9y}u6oD#Bdtukx>im%|PIdUEM{|7v(8tVeQ{4}_1gpIs0x z4E<~`?8*Ga6q{^&hgrC1g#$xT!i2cO-@v_Ba_@Ry3`x=WerRIF;uT1)^jG-T!mHuE z(A1jPd&u7pmm|5tU+!NBuZ4G!zZWjUeYwBPKObHQ?;v?MTy|8~owpVzT=dJV4 zhUc(u(o@0ho)!MEeEbiM(-=Z6)kP zNJv}3r^8x*iGP~=*7~z!b8BX2foI2a;@Pp8or(LbcrI7X>|D&-;X)*5#tUN$Yi{S^ z^L987^H#VhwzL*@5%LS;Me$;;uEJa#2igF;I7~1fU7TRw2M@Y9(aw+O#ka!w@y+lC z_*Qr`tdFg%rL9kQJ{2zU7yGBe)7Y1Ufjr?#eAmYd;`#B7Z~^A^a7Aowt?UZqSH?5& zc|BZ?RKce2)YDe}wWW8p%7fqyJKioFi` zrEy(sV>{W-Hqb5!8Z~*otksWaC5}vR&_Qkhf+&QlCtNqS#Aokj@Gw&T7 z&+%vb!T9!#yWk!i2gTKXl^;ad)qY4k*PjEP<9CV2@U%%ptSmEd}CsO@T_;yvN+Fe=_19tIx{yT z+i1%}UMp82S3ft}YU0kz)y!=SUxb>uO<`lG0oKe_2WxJ%SEnon4xA!Latn{d~P=@ zhZ$uBa=F}4E0`+)R^|y+a)okNhAToLuCD|OVwdJF%azWJu;EsgyGMbeY^0SzQaV>A zS2id2NE=~=b614RLt&nAMJSRhoVz?Mv^&FH;beO-JODlv9t7_S4}lA@ixT2Gun6`d zVsVeS$Q}sy<31UCk=-B0#FKc!LOaQB4|jxCc?iS5Wz+4x0 zN22|IOXW)Dv^V;7p$j`z3a<;dh0(~hYp~Ci%CTc-PP+_mWdnuXSaRiaUEOWr)}Vd1 zZVRK3Yd_*24KG?@2pJ&ILb{RX~w9DATaWK1{J_J4-ABx%;`u?c1JMNDUW8W9= zk2|}2<9*;Q@m}yj!aNiojM~rs!KhuLZ;iJgzcp&_vs-ZubSq=UT!Y-oSSeQ#temTq zdw`G+#s{KyjD8^gfPGuMH4Xr^Kich4JEPqmZ^J$vO><3htKwu6QSZyB~i)HO{rWaNiy8 z!gWu)8@xH*15S(k;X9j9)8cW+=Gs17O^bW^hPh2~mfsXNgL`4`=^N!5=JrIsm*3lO zj$7j1eiruLgx@Fb!*8=KDAU`Ak2aT@aJewsfu zo*tjX_bKoj?7@DJ|29tbE8?l(sf2ri(BH%-Fi(Pm@x3YD%-`;Bv*KQHf7?6G0%v0% zYd0aE;!lYy;uM}R)juA0@q@v^JY_QSDSonF6iLrTofOT zyZRyiQG6eZ6aA977+g$ zSi2E(jJ*_x`(gei#+k7>W(L>{ zyD9&@9%u(xL)?wx(X_nB#0E$j z#yf2(|8S>G@ZyuS-G&fkvY4!hl!$7S(uyUWJ;yD?*Z3!cy* z-iG{kyUk9H%j2zfw~h6;*sTf2`Z2yGVOqqS?G_v3ueF=OR!CaL>+D+G*J1YX*ThW7oy&u^WWv<8!e=crG>!jY320`r(E6JUEirua9qo z&={ZRV!bfRkM#AB*AGpQJs0bS8*MjV7kRxx6wtrRlL2Zm#2zc7$CMuf@(oQY$QVhuFcU(?|}sCAgQS6H5-Z<*r?9 z8U5oJ!Ir?i6*x zS(~`ZjwSY1*>S|1yztn&IkrO+3O*vw89OcpAQ|>|?GE2d~Cn zm#E;|QwvxL}15b$a;&gmxxKHCJ$WOKT@q~CP@|89X z`E>Ug(!=bt_$l^h@i3$-2y?2fuoL6_I2HeC?(_H=u2Yb#uv2V7JTZR3^%VC-{2Y5Z zl2dHCofH?ujrdG)8!?mJG9=4wnJtVb#gFir>^{Owa!Zjcv!!-)Tp07*N`I=)bNj_U zxM#=x!2RQF@PN2K*oPdL=T7x2{P+FOZwXcOO z{Mvuz-}G;I_GFB;;#a;l=1X7Cy@{kw{L*jnbz*Joy0K2&0&ek}eSP;9_tYm$Jy$Q* zjhlTv%qCwm){DYTexq;T-u7>S@A$XDw+LM$){Gl{LnIAc^;iRUb<7vOLaZLY@Qsjb zr^$EyJGkHT?}G39_rMSQ`{0NE1MnmNp|2P#5WXVjbN>oyILTFt731f=QvA$+3V!ZC z^Oa+z_$m0Q|HM~`m80+z|FN$ct3=_){v%&4e#8^2#j4olW3||befM9Duf)CFYw=a^ z_4pe2MtmK7Grj@7!nQ$wH_2<=FfA{W)i7KVN5Xu)m+}4|Mxu4sr{Soa7hyYN2X4z#qivLkIZ%u}?&@ zz@O+VglgeHe=sMk9Ow_go{!{2Ki`)R6~aMY=dK*&55ztJ$$WpX*C}-e`-8B{h4SG9 zUk)?RAH}&rtz+3R&mZs0hH}_tLfLSMCADd1(`p9(N)<@RJ*vEFL`w+=T_Msi>5ApADeTaL{KEeI~$%poV9p(@9bC4b4iiA?( zI9~*FtbZT*2ll=l?ho^wqRu4h6m?=zr>IlIIz^ot)+x?)$AQPYx!^p`MCuez;4Gw~ zp-4E^7sVXoKjjJU+h^dX;1T|CUo0Hsj|Pike~#ocD;|#aNBQER81|P)KDRIJNPh(G zIsQn$1^m*s*in9t-wbZC&D?R6-()31@vsT^X4_~bLy52v$tL>(_eQW#C>b``LQZko zU^;JYgU#V=rVaKU_RFRdpkB5O*sqw*b$i8L#=g<@jJ@Iwpw8Lq9DBy=L7h+5C3cQF zZ>tyBE0&9|nogB^)n38AnUlE6#hWo@<8_48sa;)Tmv{?4Wx=wsOuW{0i(SF4gm}$P zAf{fk`J5;9n!Sp>%H871#A^tnlhV4!ZgDl&rNLF$S0mABYCU52_`1Djoxo19M_l7d z$5P;G?5ptA>1(fBkNAeYZdY-_SE*Ps>a5UGalLy3$r-L>ED?2rZOK?T6bfJ1?(fg^^rg9YXtX1wI|Z57s>t1`FeNrL_<3!j<^958qpl&>ifK-+F5o+J^P` zw+r7{&(H(xfnQ@+A{LL0UGZ2RJd<}fPA7~tPA7~tPUj9aPA7IXcIByO8WW;KY@bdF zYX@qd;WunOdj+@W+^|;Zl(AOn46;_~RI*m-46;_~46-Ip=ejn*GV9t z_m;hBP4U$Z&*x*eac|pO)&_Z7b`m}xX){g{JD;70FXqg#mg#J=mg#J=mgy8T?FPP% zy@)R$T=R4Wnf9W-h<%AKcZ_qStyAb6YFOvc z1+0!;(`r~3uuJF~s^MGRs#(X-Dg5kug`VLT_p=lBBpz$|_0~4j@>dbdwSC*rCe-$| zu(!Hj+;_GW^R4~ldWT-&C+_{(c9;s$qy1#Tw+byo@P=It-|D`aUu)~EnqOy^+IKwXd-s-m)BR*` zVScu%_*U~({Tf?q9o&od68IA7Q3Xj=U&WtpYwT_A_!<1!ezDH(1$z;Ek#O(0Uu>(r zufcEKH{f^fTQCp*D*RJRuw`fgMjw0?%lQZv@Hw!cF95b6uD|4tuUsKtkn4*6 zOgjTSgD^^c^{U`2Y@Kg5*_?i0@{M>y8{(`;L z=RypXcuQrgWF>tGU&%`Ol3;0H3M}JGgJpdgu$(W;!ndtH23{KOF=sIZ-1peMR?*HT z7Ao2~*cI(u?225MLsE`AJt6J`9d-qLD}v`?SFrQ3E7%3t_v3$`Jz&p~x@J$?Q)c!I zw%N1ThX1pm$1YF!3Kr~fdklO6JJ^%hfqR|=4LjoZC>XGvD`#cF@>UMKfcu@hkY{iX zwOt5aY!`u-*u~&#yTr<1mo;|QvC<&B$XY+&*O#_e+{>@{Qs>?Oi%aJ`WC_5<-LWiKLm$-VAg!?!-NQr43~UK%WI zz5K2C6tEWv^P+3u>*M=8?iXA`-vIY>xSwaP`a$BWxO>PR1Ru7Cz(?$1@KJjN%<=!M zrnejziH+j!0phl}yA@e+cN=zbcRO|?-;ihCfxEbSmM1^wsKQ)NlB>J#2KMmX!JfW{ zFJuMnSy$2;5x%i+4|XwkFLp6^A9gW! zKXx(q0Cq9=Aa*hL5H@GD_%{?_;iGHiTY{~9D{v>@8f@ct0!vy6i+p=YFd$=f zwTa76*a{gdvaLACifm(bv=s&moA$CQZpAFE&Nfz@BV}E-6){$7TTzge+F()q#06N& z2(g4a8p6s_TWwn9zQSK_*U+=bWBk4^W8Y5kDD;76#Bah%%-7)8p>poI_;Rcs^75n& zsON6N)OR;C_7`e@`#8 zhBl>&dmWIE~$U+*hHQxeND| zxYyH%yp)oCvb&5nXCbIQ<>j^rLokDmUtNKSJ-Y7U7Ob@GGKdjOJw z)*l?e%+PX9pw-OLa;JHsWv*Y!bN%q`&rFH*L7FF8=K3PBwhrGL`0Px*_RqUBPZP4as!QuF_o4RB#$6SZRJ~3MfsD=BYSG zi|ffwb5P~n1RD=dv8!;=!+c=mN<(yFSaTVZNjAeAtk#TtkOh?8o zov_=dYmH(ip&!$AGe#(r(0%E;psxf2rJ#o~M5|wcCltob-cs}gU>14J>T?kvpR+0W*YzdaYZh_qrovookE$K_c(kRIjcnWT=y|`AT zC8uYgy=KZt!uVXeQJots>>US3of|A1%v`C)!ooq!vuYeI)V%B~CjIfNCjGHScrzKR zy=pV!%g8lOlrH&ouJ;9B!+zcNrKD^?t`Vhl>Mtdo`b)SsFb;X0a;Nb~V|ti-@5cftrKp#~kr~%rWc7P)Hn^C#{Fd#C;nOH%f`oN@qNyu_uduF_O5X#b4Su2 z>|@eN>|@eZ?87tnrI$028M$Y;>sk6elbCaR8p$(gmJhI@=$3~vgS@xtob|oYh3*eZ zzp}SUo3c00(VWzQXhiBs2k+`*W`p&x8=%SA7o5!*iw$TcX1j(_x}Sz<*!Oj_Y?jV@ zG--5ZnKVGNc+1}CrVq4XXs3rUuiXgk{66j{*PK!HPtJVv_%mbcUf@sI8b$R2dohAP z*hVlHEY0?CaCjUM_u`p65eejd^%&n~k*Dz{U zA5i1zNsOu|5f`i6NameaxpB;`ts=~7cZO4sPb2K7>`bRVphmt=+F9-i+XSA8eMp)w zJ;cVwF;N=qv2jnnLEM`<=neO@rp!d_X?2;4_{42Ov+)Vz=1q)jq{Dg3NyDSD%ZH$} zH*X@**hjjachKp)pT;g9Fw*)IEzcXs2|-VLqkW9|!rpc7qXE&_<$YRh&MNRFoW@)w z7!B3{H6ASCYWX~{tgq$YLo@WQX?*dXz0Wh>ps)X#eQF=MFYI&hW9-)%>AnqW?E5-n zjd$$>!n{xK|8sOcAL9N1_eWeEn&y6`huLMld7OsooThvtKRCR z1-T8bpRgOcgtLk5Rql3Q9395(u-A&mTL^P2oWQNN$KROQsuN3+i z@$pK<3-P_k-R(=G*AX|bbiBcT?|yJM_#fPl;E(VaFL0Xc=7e(Qye}a9h3+0-1`X^z z{%-8+2`?7YSME#rO(DY66TeK++7BW(d5gxxo2&)2?$=!f>9KlVWE66jx> z5PE-K5Bm^8w*(Ky?nC&#L1T(KK8L9bY7CG=)6tl5AzW3P&0W&s*2g}SJ6nN=VE5+U zKCngy^8EeqosI5Sqng7AvDrx@+RFDLOmEnvI}@fS?p|SE!tBTVtj0Wt6K<1}c677T zyv#Z7h%}y-hI5naLHM5GNUw3WG?^P+cO*T6^qF6{Zn(P#je{Eb0;bvJ0;aj-0;c)n z0;bvG0@jc>6(B@IzZGt42}Z_)`I@bX&$=}+S+~Mo9fD*i?A5K5S7(>-E$5)IFN=Qv zWAIhx0?OjrlPB%vhrw*!>YqbeIX=&fp0E~k9?#>dg+{(Cp_nfQO}ULt=@XBM|6 zGaN7R)S6%oWbdO#Ez7JxS>CZ{_=a4yCk()=!I@lje4muc`YkMakHgOZMXtviC)m>Q+8>DgAlQx4sUH9y2!l|1 z_bG`DJq7mW(|&&>2f!VaUVkzy&8Pfq-21~GoXZ@-q{Nb*1XuGZe|lm=pAk-n34KOl zLyt#tdKjM=(-RY`dSaM_eI~5YN5Dt?!+t`T2)lX$VaA6EiD$jeX|{G9U%S?w1^e`2 ze-_;5cj8%z4PD6Q@&$!#HvB}5;7?>6e>^iAg-r7vg-kOcg>1e*0X&g8l%E+77jr)o zC%@npv-oE(rt{B!3{2;r{aBdPKYKB$fA$^2IItMG=j?D6vp{EK-j2@@k5f%NgK4$~ zpSR}j4f)viWz zO&US(7YZj{XW_)_{E6@U*fznzz^fr9b&Aa9`=3 zic@T|Jr$qE))@S-@FS!2pZt??vYlX0!t0o9hle7_pMWzo&z^wAae~I{?nmFmz2shW zO)#&6(snm-Z=>OE!u8wsIBbu3;5^tq8owVNe(;64>oJ%xbM3MCIQAQU1J8JaCuzp> zC7$v+63wN)>^3;fX*O~9!uFVJ_hOE-`{KPYL|*gKJ-tSl*O|+Fi!k@Y4?50X_0l)J zitlU8S-y>YXE)FtV}me9gF9mnaN=|fz%>va(EZ%?0OnZhk6dRp4dfjvjRtiqWt3!WS6@kX_lZbA^Wk~fUja@ zfiz$5dFlK$m)bOOnEJvTdMNgVlQe|cg$@3B_X79=TCfd-f0=n!Y5w15*0ot;NA*d3 zsXlP8b|riRv{ZMx`k*-Ex1)8^%xrT|vjZ>rC){)3bMATYd7k(PjH=%55lk;vkMLro z--ez`9P&HCJJCaFR<{LfDxP#tfKPB|OJptFqws%vfxTQ$*8{sJYb~B~Pl8VpPP4!* zU0t455BB?Y(xSmJzYDwz9o0SXa(cMC<2_(2W{g|1660z26!;YPYv#9=yDQ#}uQWVI zgxlg>xNpOBcbX&C$~DdC>s+B9{O$3!*d4A`ci3v0O>X5H8}9%cVb|g9b*+wR7OakG z?yQb!Hcd>fZeTZR4^ltX^%?9A0hHj9m>FoY%Ta+$Gl9XgGc~xxN*wfn5=aIBmPb1B4mMbskL6 zTU{RJ7S{kteRywsz#(i1Hh?iUhEuVdf(_xciFqj9+L56NZt>X0!BA`rHi5M^-i>oj z?LM@9O|6OD3*PJQbF~sTwHDu2+iJl>y#+}v-dZPDJ6FpZahKR;x5f#sQEmcU#tq?F z_YC-qdl`QGGwx~kN_d)-ekHuj)hpq7|C~QJJdS4dTtaRLuM+Ax*zeEzXW_a(%X*yG zkUa}O|F!T8_zY}_g6@0&9aso^PAJazzX+56E8ondp=@SNv74E6mU)R~n`ial*XF^q ztz|C|_ACD+YFr8#xDFx_A@Mzy#k6|NWV;2^1&d zSzH@^bNK3yxaOFLT}`V1L$@aH%40Re{pd;0;lIv>GyiP(0#3fz5Nna26V`?Y(8#V0 z(#VR9TNBpxgIr${9zr|&Ja>E!d;fEC0FNrCHTS% zkzW)}!hIC0CYrv>eEPHT)r?71=92vqMt3ob|G*P|v>)sX_+){Zzb)Vv7_#5nDdd&!ZF%?t_ZRU8!y{~t z5wj_NXDe7=_8noqw;Z#3n_>?0ZCnzywrNQ`IxGyQ;$9L@jmNUiX$5#{ToI3B_0=h{ zDKUQv?iKNrIF~hb-}1EYtU&k{hHQb5!(JYn!D3h*n=@0robac_(z&WuC2`!VTEXxg ztXs`TeixU;7R+NWBjoaUS}FJ=u&a9YI@+*(%H1hTps#HLL&^V6Td;nHyily{Ey$TfzS?jGE71 z2wQJOFqr4e#9}Jj9Ey+P<5H2RRY{FKs?N z!!PXw%ocDy_Jy$nERqWeb5YFk+%9P~LuES}PU99cM`-~sqC^<8QWyCPVj1`*7jV~w ztZ@;;=NK5bThc0rE_N)k&ERG$7tSZ-1@Q|0^zu-U)el`*1JT7gvr?dqUBNnmw${eP z)hri|!;}r@5&rymUMy>6>^gj}59i`OFZwk5>RkmZ&zx#S=5J9MU|&m^>%uvNIX7N| z`&!nfw6nI>9bVMWu{*4$BB2|onMiS%G#B}E?BT`k?}6*5*flYky5if-_hgRp$Ji6| zLp+;jYK>JnD{E)-{&LJo77ty07cU-DXTtsvJ7Zj~voFQ^gU%e1Tq<`KAcV<4fEF7}a@jW9B zz^yso<6xStL2`QR@8`m7?T=&tGswroZ|&#j!Dj7;ygzfz^Kj*2dux~0=C!vFJD9M& z#aJNbVmns-6-d~Q6+A`p4e_(kF|GXRWF1*w*TIU$V)1ii#bQV6z{|S>dd+$i&_(;wTA1%hvbFM z_960*!UwoN1PieS=6&#k@P1m^@*enpcrUGQc^7;yyqi|Ayc>$KF615X-S9T}4p^ME zBX5TitRuOXzCbJY7VfuMu~s7Y7Fd$CBU-n2B`fu=WL3(K*upzl#quMrJJMRc+tXS- z;q9y)`2}+;_%rsYX>H94Q0(0sSs8N*xB|xRO{{J?C9P#y$ts(>!%909dl2#87gql| zIKsPugZycBH>;h*8@?O7Cp;dObJrh zTltP|MnPo8uke89SP6=vUn-n`^ysZ{_=Pk zZ2T+Y<>2K=hvF7%|H^npTxuJ`w_z#k%)SG)qHZZG>O6AKo0i%p)=RDCZI6HthljvN zSj)95_i7Em`gmm=0`BUE_^aajxC=Ohl?H3$Rjff+%XMr225SLZ``1~0wUhsX6=ypk z`ywo{FIic&gy%1{CAOJ0SW9dRtFPABgW&=2q3|HM8oQ0xEVSmwzX@%<)?l^uT7#uI z`mclL=)Vl&2t5GaAMOJmU~SW4)4cs+)4cs+-ldgF?FcE3(0yT%X(oS>X(oRWVHVpo zX7d->$=Hi*s-NahwuNx-r}~9lot#+u3*jW4!M&~BeXLq*?aqYV)7pvG)7srjt{Vf- zepr*nh-Xz$!;KLuQCmmpbZYr*-p4sOSV+|x0!S~|lOxC923SS_89bc9RQ z*~y);T|7@3j52<0TuY6#CN@SB@up33GhMTIkekCiUTfc(lz)So@=eNMXJ0b6fF8s` z`p%!klS5vfm=oHYUi;{4H;n?IcG$>v)X;wR1-RBO-P%n_Li_QntTwi9fnzi_2o&3_&)#kcBDE>%o{Od8t z-vqxJ@IaclT1Xp$wXtg=5i>vx5wQ{)f{nP&!`0}2{!o9S|E!q)yaK3L(7#nm|0C4C z5Bk3<#9etpCPV+lg+CN;AU`#ga@n8j-}Hz2E2XhgS~)>~ zsQ=XeTgrLLllf^>j}TdoRL<)`nkvRZYI;eT>Qzmy|;r97mZq#ULk*$eE$bq<&EsPbNYQmzJ=hh3lV&P!ie3#`M}y7blc zh|j7izf?>4qI$|JHAsVc$SZ?YNXvS-8t}aiH0%bcd^g~_KJN@%tCncM|A-$^mpdwg z^{`cAG$7^cA}*S%r$V=hY$wNhO zt5y;!1xsRdN>(xK64*jXjc-$Zq}pivdTD!k=9?cb^HII!(tVIbu@$4LAyrT6e2;>l z&il~*K#C8Y1M>eOjJ_oQtFrq1@4sjJF!I%xtLE2#=YR8mOBnr2)=nw5vv~gPH~&>( z^8fw6ElvNb@7X?0cjS$2dH#>&pB;H4D}DKO%WunIe*A2o$Npc2`6FriSB1&{_rI!~ z{|@a;Nh5bW_G~1x!2PhtuxrTfFtJ9%v>JtLG&lzP z1VSDQ&cj~GJ`SgWtFg7(cvkEi`^4UHEFnk1vpfJPI~X9>I^(_2J)Xe5^D)Q3(L4}I z5ANs<_JRr616Qx8mB-?D9t569*kjl~VKwhKon01I!w(zB(?`OS90!i&En1N*Cg{Q7 z0zw}Ro`@~3W{9X4tAz!RgqW2{#-Z0ylOuOxGdcQ0&bxPKScSu{Xg}KLiwC zeN$TFy@|EmhvPmHdsABDy(ux*H<1oUA(6&>6PoXZpfuo{&|WVBmtb!~@4o~*g!ga4 zY-VSIOX9`gwb%{#i-vIN#IUPCj8p=}TdaVo4D;b$V(vc7o$wj%jCX+dVQ(RByMUYd zi!HH!tOqv0-oj1`ZNc`~TVe<7E%3EFfZ}a$NsR3++}RnoxXD}KEe`^B!QR514Vd{m zht%B2H*eA`AofPCmx1Tvvk`swx#0QO8`BP28{>u88`0Wd2ugduk-5U_K+PF$Omli0 zxxScvNbcwRwf0+lJ~0H#!_}$|TTGm==MpFEK|jv%5KFro~3$Oz|ts%ASgzWRpqedoH)kNHuns;jE2_TJsQyVj~_J*%jXgO=|h z*$zU=QtXm^Fj_)`iPJ;AAfJKG5pL@VmZXF_*_O>6Z+J0t|MkKipOrNyAU;O>p zKaXO4KT7ZYSV514r04#^-rz6b@_xfonvGRHn>J~_Kl=gcC;wOKe+wm{!Ag5AN-osE zm!WLq;gjv3#4eldpTZKH?VrXH47UxI;A~&E@@ziuS>!SDYe>j0nVC*)p^4){WQ9e{P4@pM*AFjJ!CdLPqCL zGCF@D=X3h(0^1;K^ygS4zX_G3M4_%c7iV0OJ16~ z1Z)q|=0BrmN2oHIema(h40744w_z9FZlvtcTPSTs%4%MXK9#WrRV6>}?+twxI_`hK zKEQGRLv}1+0|H%f+!wCmxGyZlabH-9vk`K2s%RHS+4@m7F*D zv|HG#kd6Nhb{5_V)u6T__OI&Xud~bWF8dts(pHn&G%RH`$T#y%-h+SaJ=$tv!O8M# z8B0zr+S8m(eBSrjHF=*NwXw!!`5UR(gay4eb>FH1# zY8zvF$|Qe^`Ze&Uy+q!Yy2e^jxu8zly9896bihovzwsE@TVF=&9D zF)?U}{V*|Tgtag+XvZf=4BBHcOALgUOAI<)LLfX^LNE-3 zT0$@!pQnUi1YTMT4XS0K!M`j7$#4TWlN&gifM3jLJXprdKZepM`LU48pJkM@fS$sm zEFoV2-e*Zj{x74P$)u6ad}@S25fW$$USSEr6k0|)Q%EBmFc4sbuBCN;XexCH!8~fN z4Nb$pCLy?n^1RS={BaV3t0`XtAM8mm7Ble8NeJdpo*SC!%%FT3eo+a*Ty|GxJJUlm zK@ne#$Kh;e3RvN(U~`2To&wf+CUT~5#dsgi#?w$_T{pA?!HnnivcwO8OHxsZGUH4{N> z%mR}Q6B>x;Q~sC`2y=g|Fz5a_Fyg1ckjz1j2N8bCp8)dvlz$cHo$_bHz{5fkHxCZoiLc^q&H&1TLIXlV9}l2(DRL-vcjMJ~C;o(Y(&rx1t;oB{my+M= z^bZZASO3s(^8Si@R8*Aa(ojW zMmO==HOGE}`vdYF8T0kB5;fnYA^at_!>wUFacnbzA`Zh~GN& zEZFO~0G1NJRcI}|C~-jx$}RC&IPJFxJqMdgT+obi^U(7kyyJowK#j%)O{r-X5^^;z zXhOMZXg$c!SDiYbV(NxAfU14fsRK^|6r-FR`Vzc)Y*3VPF;GEg{Gy?+K&r!Gw zc%if4hzcVULGPXQ3sHC07xw2YwMk%F4$wa)_y+WUOz^Gq4f1Qgkvv&q*m5}QyCHcb z#RM0;v%Uk;5PnimEFdw#@08DbN1Vfyk2*(?-~~Yx9>aGgCOAv^96Th)D4(GW2GBX} zoN|tVF3a}LI%g;!^iF%HP%q^7a|lnvQ}`|lr*??aNzcX4?gV~x@)(1YhOMXr^goCX z;TiJt)Ld|2wITQ1Y-ZsEe9SyjHvWU)4)G-9+XGwlTs|#5&pW?6XUX?dpM`hjad2vf zne7BpNVLP0j-z&l=zoNxqux3C|BgrGS${vUIiLD-{!e&Ap7Ve9enS4@{fyk_{eqOA z-SfYbyyrZLo7<{3lgMiTz@l=j?zrp|FTfBsS z#BVa$_(CVkUpgp8IT_ErIC8O2?Z#L5oc|;K#k=YGCBBn;kw1_Zr(bkXl%B=hUG(|F zD?+&_Y$x&LCGhx*4nC)TmtjVMjfJ}CU?(-7!;cbAzry%M$GczgNxs2z`AbIriqhA} zz0~cX=T75e7#$?hv#`5|mao0fsNdn0#_KRTDC3q!eoD<}#_umW_=NJOUNyHo9-?m= zK9sG7-()Mi0Uvo6;hk3wkG^tvkyfQoHDoIJ7Q>mch5q7F*@}1UHp7szjnW5RbE=>7B~ye;b;5~ybAAn74bu?fEQdUJ*rSj#rsajZyCOox9IZ@d?VX9 z68i29Tosuh{-T1GV2bL4A*@foHS~GfTkDAhV=cX2MZU^W z3;MJK>z7IYr|7c=mJ?x-nv+_%tEqX)YfF1nunsPb7Y!1rA-KYZ^mvY%b)GmiUqY@W zf0F*Iy>@O}`nLz$7ZnJz)DX0i&Ut}e>tID`Liu^hFL=VdK8X~%=e#d;&v}lY0C(8| ztYBo&5muQv~n`lRlm(%MpkWtGy>t52MULWv?o#6lMM2~)?$Y2?LmV$VbS9l6u7JMW5c_;LgLgIl%4DSv|oI zb#{A_dbxK~e-9|B0o3=Pz9)Q0LNEzi^{_!wMFw}#=Wb9^m(u4UT2_L8S_$GwXtPV) zJ88YkpsFH+J1F1jb)&Wi2(_-{57Pf3uRBLQ4Byg&_+_1kTXQ1#tH@v?_^ZMAa89JW zfck~_aS5Au9lh?r-*X5p6To5(!NYSBedg0=0hp}Y;o!WUUbo|`Ig}pbT_Lun&?_=n z1aj^cZxKCiMP5%nj@I$+1>==<0gUo|(6UqLITlRUFn26zoIB6EfN#}Q#)t@};pG|; zTtm$~Z#rJF5y2RGj&-l5<{ED?qu-2NL_Pz5+lXK;^;df{@zsq8=1`ssZfyi-ETNxp zZHvioL<-?HlKN4kG45#cF(A(t(>9s2rg+zK{(SuU=95pQW)3_CQ^+TgCVTU!m0#jz z_yEr%MFbN~+cbRWW*g3fIo?9f=9ANB9-fVtlTXLHa26~Cv&pB^Yqoba_1Cy_kyj(H zAfLcE6OAunL~uR6gb~4bY9@G#@FY>n!|w8H3s@ z@Kv8dei`y|?<#8N;LkgYd^Y(UcP90h!P(&i7ySN=InG;(zh@9E#ou!geiln95Aeo$ zW8w1XPu`E7{k?nK8)(0WwA39)+ZgyY29WoqwV$_~^Mc@R`rLyz#f{{b(mn=uk1_bs z-bKybcu*`MAB11(NEkpylZ*Xhw09@}P}{v1K@54x`7isVZ1M%p#PKZGmI1jLm7XVcPs3mH^B*d6Re)k(h>yElKh}0XSISS zraj|yfCHv0vOD?XjPnG3#m~Ba(1JcKz1ukZc6SJ)4fP%~z8sIy=W#sR*V3mseOh>r zQvaCSkukb@;+^S&FHdz^UZ=+!?nRWUdt2N$II2mxxmS~RH`t7){d4YSl26&EcP+0u z`1e}0H^-~X4KDIF;j#a`yNR?J-}x={+Dh&RRcWn;Pe?QH?6oyoKxA8*GxLNc`qpH)#W=kLe?Swlz2^V`{|eEx|BTc06vJJz=!$33l8Eh z77BhN?FT}{@8cbE4{~&f#Df8*0WY}VdV%9zz!S|2el@*6X5>%sSUZHDegr)V;|b2d z0sMN@?4!@G$UWry@T%S89-&@-%tw%se7Yn&pd-kCp>?183tqTiyYDjQ$N0z{q2D?3 z-`yyDl@j6XN+OTqj3n=8dj5hp-BEg+B|nGf={N4r#K3x&bI(w7)=lBJNP};(EcweY zS-j{r;FoIzj$iowS2%vnuwcCC)~CLK_bns*1f#|))Yqe?zV{;@z(2Xs%ne5vGbei4 zjC~rPz+>d^6G!V^HQ3W*coOe0m9se#4nw#!haC)| z)r8~-u{&YWRKl_O*u_11Wl--SQFoBq!N{OB;LHqKt1w0`HcvYXLg;1WAo22I@G3eL zuyt2-(#VBEO+#jomnTofB3_YFIu`Iar0n_W2DO(+IUTEcMS5s&Al>XDq&q^b=AsZQ z(nGr_=?0%z#;MFvy4hK&oP$o({z~N>jG}fUDznERq+$t5mCO!BWwSRSsWu^iiz0sSx zD+~1H0{cdR-KM}ERbXc;upbuKdkgH?1@`%ZeTRbml!E=Qf_=S${mO!U*n<7#0z5zg z&Y=LmQGiP+z}pnyqY7|e1$edsoL&L`umCSwfP*c-_ZHxmg=;UsV;A7e3vlKIIP?E^ zIP<(*2YHzyEDwU17otL97LZ53_3J-MOc?9eZ`mcpH>Aja)7cF(w2d`QCqHJpT_9 zgGk&8mc2pT4L%GLM)<>7s$(O zAZ7<>2@F4j*ek?gA+CzOc-nvEiKD?K5>p|hXPA=Z;WFIRvVL&O^*RuRiNVA%x37$V*fv5Lr#UEb{PkXwKG_wky43;qGI zA6PB|F^PyzL~J8shY?3i2bfrP(dP>Y!R!AWfBmBz*a9V5MxPPAjXoopb)=WTp)IfI9NK8kcwav z2Zu)yWU)|DWOAq&vUn&NDF%?ZK-?yAfw)cL0&$zf1(w@Hd=9aJ_#9$`{Y1u&4YIub zNbyRAYSrN5jgY(4OiiI=dJkkkWK%Rz=qATB_6?{2jpRxP~ zVPE?fJbBKq!*|~L-HS6w%t2xc5<`&W02qGa1F^Ei2i0I~iHC2dF|sM#E%7kZG(|Qi z%5FToHO-MNLqrXR+lDy8fmnLt1F`hP2V&`o=NF43R!vtvPkbO=n3&)vZC_qB_8z;2*fm%5Qt+6u8-h#m_S~G z#UVNn6GC(#CWPodB?j{U7Yo2;p1l1pC%23NmPyaDolpa200x;wsF7B`=Xk zT4FGWgh62(a)LJ=InkSdoa9YJPWC1tr@;6S32(#{WK=K@c{QIp63&UMk@JZ9E9OM; zCq7SZ85Q$07>H%Saw%G-May^~UV}lNxD>^x_#%0jGeMjPFTSG0X2qxxa~!mE~`NPxH-?{NX!$+YGm+^^liGy8O~RlUv_^ z%fh+caB{v4|E5?tx4>HYj^VYm907Sb2i~Pce3x&)U}^aXEWd%}yA-eG=8$DQH~`;c z7Tl!bdpzKa>G1&kl^c+oh$MEv-we~`0bhKW2mBA`u^Ph@Ye7qXAn8`;9wFv z3=6fq@2UGN^gZd*Pz^p|3wRk?(00)9;iej2b+O{Ykn4X>pM(CVe3yfU2UYB_KTz{i z=trbDX%8As+JlCZ_MqXU4PZb>hYlbEK7#-*h74pi;tB^aJ5)nfCmL=Lh$|u>K4A^x z_b%`ER8Ri!)*nBOBg@ijnSL#AuVvu1Y`pT=m*0Lan}L{l#m~DR-rX=OLS=f0KldOk zx?<@SC-1MJ(#)K07!%5PC#XBkC5gotzyfg^mfnMY zGUei)xOxv7uHJ*b_0tdKVQ`jbzWnp!$ivJ4^5++)vzVO&a`82bwOL%xmd9D#0b&ry ze24t}$2h>M+hYXYOA-Ipvg%0^~ zFeD%H3Oc=TS5=P$A=Aq zu$AyV`0z~>K^F6hB9pyhswekhlnA`SjCsgE&lneSI0{Pm#r-fpc$g>QwBalWGZ~z4 zEvLG8!^0fndAYX5+92)*%js|iwu2Pdx5dF-%rEMT2||1j=jb7>?V^TXyNEBI2(d+o zSE9V(rY;XZ^&!8!VYC+CgjgqhI4M%8JLDgteAunvr&2yh`H-9DSD-BBg&*ANdD!F+ z`)Sl4_A8Pf_A8MehQYiNGM)S|tmx^)4)x*Ausj#y&k!%he&T|QWkXyWmSaQg8e(}6 z*TY`J17W!zexk0H;lmemeKo@@FMfG3*w-Ha_!CxMOzGc7)@@aMO1t zKVlf>#Z!L?<*xsNb>D;4W)s{euftvA!GrTUQY<)L@Fq+)o?)`_0`b;(u*qyQOd_wk z{qn?kc+s^?B(IQ*1x8#jVj&r5;z1|^M4z1a4vN0e+ZT(CxNJ6(i_7LkcTk=P4T`nU z%NH|__;JLPVy#WD%{4;fh*fc&~0Zyit}x>JB)d zZXyoEQC|#Jx3~+5IC7nTJ^dHCHxn7+C=B&C8+nW39GeIc$4s<^Vx3!CjOH4#lLmzkn*9LtI2p-3JN8ddd?*3uZBvVG-{^1;aDe%J7T%a#FZw-G|Or>m(Mtrp3~fwoOjH`M7h@&8`>;bdS(zzdY2Mm^@1-(K+9*hhDa@n*P>V{185oO zzD)mY6F21~Nu3~s>%ZWwOj+*xFd$ec!;w$X#zHVZ@C_>3rV(N<1Pz;IUNfdu#Tl%+i z-zSPjwuz#V?ThiSoBIZ_VH6=|6R}OUkiSVR-b-LZB;o-5h&Vt_3j7`qVKzm}0|h2_L5A(^QO*ul!oH)^@)mO2qL$B8+@W{E(W|*K+sz z-%+oKBfEWZWr{IVteW5Zd#SHMpPKFuM3Ok}iw#qpm}1D>Y2u(%r?rOrBM~N!`xjBJ zp2MN}IdM`HCFL{5-DRSiG~%qrFr1#JUxf1`{Ue;8h)E&lspEcG>QfABs<>0dqH5!7 zD5gaOd`Xe?DMO#KhIdu$tJPphwQ)FXgbuM*9rsgd5#wqG%&6i~&A{mV3o$%S5HI66 z44&s1<#$qPmb?3i{h`PoA*U2|rQH}fnobbKAqH8Jno@2YY)&VL7@|laC8#M0Q)((B zi+45M70cBLzc}?JTyb5U@RKPQcPr7Jj!bteyT6&ZCYEJ&KhaGT<76KrrqQROYvYkb zaaOcjn)9{uT!tK;T=88qPsH>P9B@F|XqIih=Dqx%lw;b$MCw#@UIDzu=JL*8HQ=W2&vhRvF ztGFZ9U2*RgfhqT-pGvFPb;Yq;*iCYaz)F?mBvMnzEeh|JqM?MNh9o;;1Wt61IlnXF zG3OjtqPA1PNhMN6D)9*vvErnk4X<(t*5eS|#z*OMjF=W_^it%D+VCZ3JK{n1U_?Gb z>ro;<)Zwgfyo@yZouHSvm0eht!|^pL5-USo%wlA|09&#+moJ#88#Q2gKIb1Hc0^sq zsZV~=KSa&pKjL>(qF)1|N}Ti$Qh$h;5)CLHpnQ<%6AdY6Q9fYed|YH$o5kHMM&|ak zb%1~Roc|46)ZdVcb6L#Gr^u@~=}u)>w$J%r6Px0s-=6pr9mv0Xc-#%;@SJ7i;K zQml)U{$9hTz1J{mf91eL?SDnjJvos!Y$T3OjC9f$5A|7i*%TQigV`z*$D$MU7n4r; zUvlnOFm&&QnOi*FV(Z>dt{5I|Ow5Z@{%-nwX`-rBGYr>fa^ip}3P`4jIdRJWfI4IlY0Iqc-kiI~z92K+PdUO$g~fmjjK z8EppXw7-s)v%Xl-eP;LaoP{_@xNhs_r<^eG-o}N6MN%9q8gm>7twDq zQ4Y@d4-gSzF-H#(=irR5_zq(1sFOV7-$#@Q z^;WcxNknT{LNtbz&I(#qlAbmZ9R5M9i_`vf$XO;L#+4l1OkW$<;oh8R2a0vD#<6iU z6f7p(q{mO$?HWCKkm~6Q4j) z3KXwE-27tb|Bzg9V!Ffa{~^aV%1bX37iKmiTx%k}^fA2uADj3e*E)|dv*J3eCaQy? zUMSv$;$GN@2pddP1RI}45fnD$L`E5BqO>SJ$^;W-VZDhDp(qhg5-(z|iA$mw6^|2d zL~%)SqmRrpaV#Dq4#(}xq(~czx1p#Uio9_b|9KvEJQ2hl*pVYep%$B92aXhNS}cQ# zIIalf;vG~xa-XM-kS{jQbQ^NTnr>sH*b2ju(=#cDqpK^9dN=~RVy)YF*ous;nAl=T zRGe%@(YDdv72Vy&f>#XqM9PW)uZZx93m=XGubAG#U)ad+;rQT+1a6~;E1G*z%8K@0 z-*7xC!h2DkVnm2}Gv@2e@ z;;)NCpgO56vIa+rKAwWCPF~HhJ}M%)jjgUo>f#!qs|X|9^2_$GCQqLG>8t;nO1!Zj#1x#E}WO6dy4mp?GuE z;>@*4KsKjFS1N&Pq^oAHl&)F=Z>c6+tMK&_vu60JHKP1i*UMfhA6}fu4u4%|Lj&;2&AS-ZO)r?k^nhY~vd1QHN zFJf+c-<0F?h3}^nKEJ)sbidW)bKASH4Byw@m-@c7bH2ZRhdSmrsblWux|Ho*UV>j$ zzhOO6UGslPMkaHt-@O>J7{?9GKd2!!4Y*!Hdo?08_)PfK%0wKR8??z33#wpi{t-G4F27>@1zsrxdTvhL9~ z=HAtFCz7X6B*!-5eLHH}nkQ6%)YD2&E+46?7lG-7MkPoBhAmkMbB)bnx#b%T(DIBz6% z?U8z>j-qZbaxiC)rmh20&)qQ`4@Hh5AIoUNkc#a!j?dQ8yb(Gg^|T&Gx|q0GW9UDg zG@SRtSo%*Ojo^Jco|=h_JQ_Kid=f1qkRup-GIgU_Cyb%j6pqIr6<2F2bB#rgrSDV| zYit_*#t|h;tBh%sS|TS?H=Q%avuc@2&zX!i89APOCN1MxolK(rGTJ8~CvbE*Et6SW zTt@wsj64ZpwwguzWZv0YE6rkt7RbruS8>J^u~`o+X8d`qfwVrnfw7w*6$$JH z&bXSD&?5TZNSe=DXE8mOkQN{pFvd-^%ty{=?3+l}vvyfR{Vg0_&syO+&c2np>v)Iv z;OyJX8sv7yZpu6Udh*-pdp)u#|G_)xeIxQ#a=rZ*BNsE?UDVx(ypd70B3Oc4!l?If zd<*g}az)#^19>y~Qrd53ebkdNma)?5Y2t0&j=Y^&mUD(8a4FK?z4X0<72Gm<{)2QU zE5JJ#?><`YV6CWi$NjY2$qMo=&U=8CyI3{e&3O;fayP5PUYz}qSv@^u;^wVj+(xVj z?_rJ=q{hexI9ka$_aYx8f0%Rrf&2$!Jj~h4SZUqM*sEy2m$lKu)IZA6eaQPb`!S9m zL_SEn)=u}cdg{Y@PcTzMF ztILNO?`i5DCAQWhoc9cMj}Tj{4`)AXVgRnC?FnLQJx#ur`5GXfAb*a&k0Bpp)aU8@ zIP!5ueSx|skxw$}I*!*MpC^Bj`4)Pt2cF^`d@>BAi)G2P)`<(YVb<$J^ za^5bYH4a3({g_$4pw|aTSw6m?^f7U{KBxa~(kDdZ+C~2_8EpshBl53k`2;ELWDm8U zBflj7n&X|wugJflb~kbl`M1oq3+a%5#~ihgJDKS_Qf=hd9POp=ZZ!69>G?hBOSIXq zX!(Jb-N@Y>{YdQ|lZ$4{-DoF}kuSA0+)ubS{tC4)K2X zkS=E*rq@r%nyiryGh0pMPvl1!Z9noLXB{E^O6;yf^gl}a4I9%DTC+L&4XG$)$2mTL zJVt&(akh|IoPCnH4q-_-z__PKHITjej zPk+}v&DoxNl2JWZF~mZyY)c{RVrL!SJ;SIz7PK>1_ORYL5$-u=iXhI{IVaK$n2p$7 ztezrWpIM{ai&%w5VK2J~`8)GP5#Q@~Cz`ojtdJ4pG1wq4ATKaq3?utk6{DFgmK4G! z7(-1wMAFq*TIC`DsQOk}pg zq!{dsv5ZxOmRKy8g{e_2umofbc`;*)Oy($oNMN!e7iX44%CZ)hV4kYTVvJCNQU+yN zCQH&g37Je@ioS`+M8+;nZ4qQi@-iG3MV2BjOKmY^Y4Q|mlaXb}%P~uFw>)hnkR@F7 zJrbG&eT%uN^ec%h$$6=qk?dAru2RTyg4H{nd8(2sU?opwylS+hVpXq7 z%|)b&#Qv&AeRWbLB7;@ryc)DrbZatKIPdc&^d2RYuMpkCj z+N5g40ISKIbx2j&!>CP7JxUiL>yX#yxH_^fc?0S$Le`*H14=d66^LJ9@H5pI44>j3^sLgmy*-@y?UPKe>o000VYoVQz=Cssh52POF zwV z3#4{J+S02Dk;B^1r#(k4hybQNfex;A13EBQOJaakL?i6TY!#8s$vbjJb9S~`Flr~x zYr#HO2WGpNl*!IhYsTwLOKWzO+R}arwQZ3XlXsz|4YCbmbRl&#QMlT(E0w@}-CbGK zySuWPcc(24*@e6Zz1kz&Gip!zc0hJuyk69GLUv+Q#S!bmE?Q6OwexlfQoCAxXz4lYLr~^2oE4zsOm~9}bCwqxK80k`4 zda!HRlko=8(vv;RUYs|WmR{_C4x)YtsV_UAg_vU)ZT*q`8Gjh5JaRB~!|5>qIfQ%! zvkXKIB_Bzx-L)LRZs$P88%4`NcQmzwkt4~q4>|}rh_lC#v?r>V=3`y$UyOCNk1>|n zhf+V3v&XsG6;YJ2^2ovD;}~f$`?6y=cY>?EjtQJKmhxEoPh^(SNbQPFq}OnEYKx&^ z+kM(e^cY1=QO=pf86${lHj(~Q++;NJDQUaaV)J4^OvEiA2B zvJY!i+2PYDptA zX02G)gVAQCRgWbNMGj>K*;I$2rw(HVSyrVr4`+r697$`IraaMTbJC!DP#!@(iMOza z^q5E1^3h0X%~QywO^;@tsU&I8(ygaalI|>hdOGC=~!CL<>^wzT4@$jixPv7d_mD!q6XNm}zX#=eRpm8UbdEYi}K zXE6F4j#Qq>EOU$wK9~2skN)a2&($Pp&{k`f4t)(ty7LvxFpr}v&}FY=>}xr?5=~W_ z^n8+yVLcl?R{HWnW|8hZ2OWQ*u_P>{Wj30tRu|Wi=Ax(0Wv1&nnu~@i?RXLC8gx|Y z$cstRqopI?K)M!vRr>UeBH_n38m7Y09f8No&53SyqucA*EG6!d&+w?`PCU$)!O*$ViV-k{&G`S-SBGPE`agkM2QpWaM**=WtLA{7_=4RUGC(vi22q&vUH=+cVYBimzZ ze3QEM=(1W}Y$a_#LzO1IjkFOBbt7ZH#nDDI)J=@Kouf@?vzv|XEFD=pv#%pxXP$RS z(w(i=EKT`6=4fm5lTHZy2HP4XS)`;7D+@;&DIjMN4xt$7FU;6$X}#XBgykB0g_^Jwoj9RFIeus=jo z{gC;z`}-l<>_^O_o#T(tSEXC;CP{<-gi*ibNaatNLmF}$%023zkQ-taWakl%rpbR@@3HefbzOwM72LeA%pNiXe+HgRmKrS``6Q)7Na@I@C`pf& zrhJ-`bZ2SRXDA&-N?$%pNxJhfW;tuL=ChPqpwVgtb&j=BF=SDrM@zTY3NrP^IlyzF@lQWKQR$@ZFNSi*# z*a4cXwCUfCHZ2`ly72`EZQ7L{eZi6LEKNBYZCbjs%Sh4GIq0j=lw)1lqNOLZC(3b% z8tKz<%q0z4`f@xeKsOB-RhSu-BN#Q2Tr!gJ3Xw;lr%H!TB1I#k8A%#)EHa5)7@b(8 zY}C@Dn>oV%6h{_!q&vqkw(vl4=%(?Eoy<`@x@iJq7w0GeomSd$36ivC>C+`iNoc4^ zj9rSOB%>8KbrdOE8ni6Zr70Cbo7D;v4Vv|28RjjDhFX*vq#GwAr9r2VC!?b#Gmo_5 z5=d#v(xyuy%aNy&3v*SH87gp8(oLgeb>}8dnk$R6kW{5y^k`ilWf`dwb!E^| zD^V5_OHv3k>BiEU(~%h@Y0asOA;g%lV;PjIxw1%0LvD<$KrXbIbZ4!NFJdlf(9)Ny zlcYgQU#>x_jBYCJxF$(@bULHf;wT+GRXTKSQU;o;^yWGw>C4iQ>$rBA=gDpUzTp% z&=HPL8nmp_&6uSg8m-W0&6!0Sw6x|Hs*jYu+}3C`ZP8>>oVLu^3_Z3P^GGXhfs}@=c-+#aTQGxk<5oy% z%F?4-BRi0HB5#eR+L}>?6m5+LD~q%=CaI&bl2|8peWwm(OIP_4Osua8%?w~V+#u`-MJ5AODpb&l%_1LxIc0Txp2k((MJa`#&Al~pru=nARp+CB$ph> z=+cwxI3r25ol(ZBFp9Ybp>Ymk)X`|L(x3-3sv=zvM(-WM*uoYMK{p+0bYyAILNO0V zN_(C_X#`Rl@kCb^>4_XmM;^)1M57B&!e&vynS`w*4JpgaBxaYsJc@ZH8++7b>L*d2 zM9mazQk5M=23L7B^G~6VG+J57rgA)%vb5u=^qhiLEF0Z4YR6HYN7re6{Yp_t zAv^S2MI*I;u3sz$soizi?qZSJb=R*H%Qv^tSYuf`R$;9g&v&lE+Af1q0^cwLsc)Ky zOkfpOjZz`L8+KZxPyqU-NyY|H7@5SoU$*xmB*j?OFHn?JgtxS=Z!uC)-r2f~gySg2 z`$zY!kR8dqAM_6@K`PE$LjT;7q!K(|^{gmGD#?>iPp8tPQmm!)gv=zBW*ygvQX8KB z!ba*XAe^Ld0!=8jk$MqdX8ic(;){o)F`Z0pKyl8=bSRG^u`7>IeKeh&0Me?HsWStmG z5@tXcfN}I1fRxQ-oUxgVGd2^87O=PB0t;yua$o`VvT&FeoP9hseSIWW+w7@N#AI1#G@?kLp%XrE}VQG+! zVi_fC_qfy8I4(in!&%FX<>X#wl=VZ110e_gJIsJE0Ab`n3}@%!1Ugfe4P=F}nFuE! zq^PVPdC>xYg%c1$Ko*S^NZCUE3N0W@#p66BW05h&;vs8^>>U>)A0_`Q%z#A;2s!X) zw7@Ft4MGv*#|*?VdVaKktR=E>bi&?{7cC%EfJF;fy2vixcQTS(cOhI02yo{t7Ly#n?CUA_RmS5KdqNHU?QIw)196L?$p_7$+cW zi7XxMkrp!`ONd1dShPSGIUsC6UgUsK0^6`Ryi2`B5ePYuiy0`yOtNdVLt4y$EFm9r z+!jlNEFl&%5Jn3K74Y|%0U-p08IY|*m;qq|KF02_gZf>(Ukf1%VcC#fqb+hL`4^Ph zV0REsz+wi%XaV5_EM`Eqj-6N?gch*K0gD!}$N`}RWaY3p0og#l<(*v^nPlu6vUud8 z1=>)SwPY`!OBN5=MJ!stA_pu^ATM&@-(d!dFjE*IkjWcYc8yHr-=PKmj1!PW<7aFQ zLJzOcGK*)joXaV5|LRcqGJ7Khd5CUP$fUpEY4xDv_ z8947my2TAnAQu}DvwwAg?!T0kpC**ls!{~209)(?vr_RdSJTbiy06eK$rp9 zI`U!$QkYM6jfRd80>(B>&<1-%V=N7sw6fmR%a(E{!1`ByjrApyc@f&4guT!es71oB;Ni;Y1# zrfeJ+Q!dA>-Cb#6-CgNlvUk)+TFijZ0v0(S%z!K&7AGKE$Y0|GI%97TiXe;@kPh3A z8D-^=^&=N8P}i{t0gD!}2my;0un2)LT0qzUixaSz0a-NqV{f>W+~Nc*WrDo)ONxM0cqkB_*}AnRHC8-L!Z?A-oGI(ZIHbi1 zNQ*5V<3Ka3Nw77vRMu-JfV zw8_>n`7do9vTTHH9aCM|J!EF}(^jPWB3&>}qr&@%7MGJIAGyQis z0U-n|THt>VCm?Jn;sk^l2;&5VAPA!cgbEO5z~Th* zBLsvG5Z?YlqdWi45CYNc*$a{I=pQ(N`_Y~AA_RmQc%1YQQfPsHjS~<;KuG&sguqh< zIgl48AcTPM_CgDU5duOBJo^Vu;4!q>Fizlcbkn>z0bv6yTHpn8A?;WH6HY*=fIp)J zgcA@pAU|3_2mzr5q(Q$-`R{N7(x8Q_52FQCmd+c-2?!xz(E=7BV9^3$oPe+a7ANpJ zCF`jhMhm=wR-20uuxNpQj}wr#ER6kDWPY50umSne0^6yP?ktS`+Xg2fgn&g0$UFQ0 z9w#7#fJF;@OdduHW`MsnPy@CQ|yZFah#x{%6d9JiVny3wyuQ z=+Qz5ShRpe4oI8+1U-5exiAAl2w0qe#SDbe0-5N^LJL@IfW--f5dsz)U~vL}hY+yX z0E-i_2!XwfCrw${03qssAbo|DW@^y_!U-gy*GeD%kFau$P zfS4Du(Q$JT0v0o1aRR~z2z7q}8O8|+A>g9n3N7HeXPjJ|KrTW+ntm83AY6hF0+K=t zo-TAN40>TLhX)nyczd{TA86hA%z@Kpf z(w&73usDJI2mxUOEKVSd3doBS2qOf_vu|JiKfnoCgn-Zj!UPOJN~<1DJ^;;CsDKd$ zIWU5{0r?ODLJnMtCRzc#dz8_O{~cODI01_p_;1hxLd%EI0zwYt#|fk{cNigH(E`$r zEn48Oa00>xpB?XNwsSDj>d`_AbTm88+L5lvdQlbzd5ovAa@23Dz3U3>G^Aoz(av@%DI&fvJQDIcH?4@+LaUkLmX%W?LUgIBZi&&nv|=PqL4Mn z@o8g6RQwN7pcu3pE5?OLY#!ApS2g?2RVf8vAF8tdT!j=uW{{_|&+a0%=Z?n}d1Z3T zB;a7tsZ9A2$1zezmyjG}I&EF3^^oZtcj4T0tfIVatYP&L56?UD)W1zj~ z5K?znH&R!2!hJqlcRp=ZWH*kwQ|iW!yAUBgNRejuJwR5Ytq0$(8d5k7>#HFKn@Gyl z$>rA_i4BF z!%<&KeLyhurM@324q2O{eq68GAQ*%)k$-X=QctA*q<$b3gg6<%RmKuXT|BZbxjb?c zkYbh?NUOX+WSP8_<3h-RLwkT4}81h>wf|TWaC}{}xp(d1uakn=?4yDgr_WdQ#ejTiaSNNvIe+q4#xtD8lCkq`C z!F}d%7uQDC;vT9+xeloY_l-ksJyTncQZ4QbhuQ|_f7HPIcN);Q1~qy@G$2*u?$9|P zF3B6wzdl#G9=+Ht;osWW{3{#NH-mB=@+S0bh^$ZEl>Uvl&a&$^qjzOwWAbM7sE4e_ zQFD6KN7m<@7W8k*RTP@2CFfK`Hl$xm+8QF8QP+xIO_7Z_rxm3}TtkPtOpe94rssbq z=T|_sBo|j(ORk)l!P?TZHCLlKwR#hjL#C3q<2V)Bik9~DXn|}?-kwq$u8+%k9Y}5Y z?e%u($Wk?#FT6%I;H)I#`UYymP=ab$&#@u&=!@)2-B9zc8Oqb&qb$tWFrJBVNWBw>aYh32Qu5)n z4L}ay%n>|qV~~0qj-WjbIfPy#NW*x3gcxfiX%JEmfmo}FX~@kj#Po~q^Eicca)3N8!d$tAoaFN zAw?qf_DP|48ZwQ(DfAWsvK)1V`3~_&J?#sd=Xqg{6V3BZ{)l>B=~-EtE37AZF_I95 zg(($B>Upd;T5E1dK2k4s?Yb)n@i87dVH&Zas*F_+DN_Q^b6Kzo=7A0MAC{xQg790N_N#! z!(2Z}@d@ZEO6uLMYcHv{x$Xc-i_8>GGtoSq63z2X_hJ?9K|Qr}M^@pR>4~I!I^EpU zm64VC_vp@+)RR{K6G=U#^>2}seNz8ANj=+3klLDmU^{*zy-iAT+y+^KT>s%remT8s zw1Uj!-`|?2g`NdkYw9glmgAO4tvK~$X~8wt`>`CQ=ExLsJ*}E?_mnqM?@&GIB=xq{ z^G;IlVm&=2_14y%=kn|8&IwE@0tu%9QYD8TQRIk0wY=8vb}iq`TuZIxOK_F7iq~2`ncw!`ujR$&CSI^G zmzx;)EbHFit>yLP3$NmJ2Wu^#!2dyawq47|lE?91sLg#})BF>(ir0TZ&nLa9WB4!p zCu@2A1MP}lt9Y&D_0P<|me0G2*ScP7dC&ak!)y5_=I)nHQ=H#LZyx&_H8#JG^qb_I zUsAtdGky#Gi=^um<385^p@sP;*k4?~m2@Ee>!f3~;1|;yM!#DT{ts6F(!WKTkoXJr zkG0yF)zzdGNkh^vY&Ez{^DnB)aiaNc3vq|o`$QUF9cmNI@0{r9U)2VwJ4nC1u7G}Z ztq$6n-#p$)rQFV3fq3(uYloCpsjH#uAT3Lpr`1E-b2aQW(Y4aLp&~MkTpE|2YPxPN zwe~qG?a1LMif5R#FI`D#VtOh{2ea2eSEVxlFI^4kW_oh!N=p0E^|P8-h$CI$u%4!? zo59?gE6qI5(kOM}^TV{j_tKLr)jZquR_e(2lXac-Jok}!% zp*Tu)kkY30?yJp}vF{wci}X&c&DF5)BDgoWCc1i&TqEhmdKc*(U4!3SS4{72Nxh5o zHkZ`9NY745X{&mgO6o1-QL4h#m)5M6fTZ3?8RlDNnD3ooeuE72+hmwuE5rP9Rm^W$ z#r(!q%E_DoeoEm! zNarrlFH?~_L)?z?k%&XaQ6uKY3g-8*9u$?#C)XN9_owx*(38V4zfUE;q3&|sy`K54 zDj{VF@JV_vMUV&PSnnpSpY*P>?;QL7(SO8aH2c=F?dtjWee%Aya{K2W=g)oq)w?mb z@4tVK>i2NDEA`Fw9Meik-$zd{t(5eR)Kg0HV;d$k!Qt&N&-mo}xOwNX><+9s6J%$rCnq$b?SjX0KVFqKcB^Yt#! zC)GK6+DVtxeKqPJ{Gu7U1BJs~{v4A2u&?_OEl^ahXx zPQSNoje3R#)alOGQ%2WBPgOlb_2$Sx>g})RQv_E}&r@B)#@uDH_{lbDIZqpLujz@V zHP@Dnj%=2C{_1_HHN2j%_FmN;C;O$I z!m@7axvV#;?3a4>=qao_RPSZ2i1gO3jZUa%$3Vuag#I>=@};D7G&kM1vUH`R{|%x% zn3RFeraN4=tPFI#8k{lIe3D_*R&$2YQWZUIDD}fh(hBuY89_@mv^f2fWr?~7sejf; zl7m(!JDRk@OVRSe7^*>7k;GyuE0efZYBK6r^L@urE3OrJDUGKtm#0+ruL-ma!ycsT zF8?AIX?a&H*NT`}CXvLoBA+A6xRRf1r52-3HNV(Y^D9lmN+jNuF^oN(w(&@LDa|n6 zNHeGvl1g{fpYc>49zo-o=Q7S14~{99aYY!a$)K8KnYxl$rh;9vNUAA}dKGn3kyANu zwn0}3J2jK?H1av-E)~~G$e^mkR%*SFrZYo+u9dtPD%~6NNJ39t!Kl}Qd6Ku$m7G1_ zcqR!+H5UxkEM{6jyZFv^-wRLWBQ2iFGOo<0r)62Oj4S!MR&)n0HuvgcO7cY#`^pU@ z`5(<=z8h&5PpLeUmXO4?B7T*dm@fip*;f{FbThq$q>``FEtKSoBwW?4lq}=Q_28xI z8w{1@T3N)XcW^AO70Xa6T-BW<@s#RKaF=-p+{LlDR>Z<0R8<6MrW+aCa;@CW**6*t zmAF>&VyJGTWf?Qd|49GeW#<38oKGbGBl#TNOP!EZw=;H_cSTGrLQ+K`#lCVsJ;Yop zoRwu+v5YI0WyLbCJjBTIKU&JTE5JA{byjjLmKE!Bw49M1re!&PK6;bMvnUE_8CNXJ zie)RkHxGtN=qWL-2uby*K~L!!^*Bi^D-SZ>6SO>tT*2sKg?|Y75VNkPPUtDUDZ@yr zRUCyeRPseyLkgp(ERrfO*UGaz55={j=cL$3p9ItN7^AKQ`y`&yXAOGl31)hpx+lOh zY4s>CqZp(`QVCVHj(*}S723+OtjM$I8OoNk^hL@qGmE%Z^sIi_JjvyS^gQ?`%f9jq zN3YUDyeslKdW{ybtZ02EBvmZZqN;?h+CaZB*NWKnp99%sxmLuxA|%y|V5pihl6Y6d z?63FA>$F+6($^@9iRBGigr|C)`Q9{7XECnCQMRZmv9N5Vhvh8YNLiRG`4nyX15dS$ z@^;1-A5d&qj;p{S`p6beUkM&+6IQ{edfr| zwW7D?M~!K0)d&{so9CF|K^b*t@9{Zt7#>b0kESe2x;4dix1CCC*YIsrDFb z)gF59pe(Kx;iW!DTCSC^DSylOVk^}e;yaGTQz}2Bz0}I*$TF0E!KmNU@&y$ZKna6Ui$jj&;Wy@K5+~B4%8SfM&ajghR zb(&*wtsJ4(X^>9hDLu@5iV<@d#FX?^&hDsbO zVlEAsA<~tu9_h9*zDVbpFAA@r^G-DACNZvDaD<++NGb;mmHdmuuM%>TK~lvS|06N7 z$p0uny5#ZX;#bKLR2(wWV5kbwN4TkECqI%( zE7qd)vQd}9j4R28WyLbC6lX4ZAsJgM*d{TqBrsD+>JpKOoL!1zajnQ3skAHGLN1aD z`!y}{JW9f=2_zNy-?OY>)dkO_6@7W;5^hR(s?;3xR7uWHWnOWulwi~fw3l$xT&>U3 zT&>=Pq$+_FwknNwF|L$hzKWbD-j#}!E0a=?;$KN;E^)2M!d!(q;i*y>HG?|gsmgI) zRgQ(E67Pz*R!TYfxmGM^X)0q^2ha4^Tr09>*JKuPt;oX&&Qiv!4bDl7E9uNs$Ka{z zP@BuOB0WW1E2WTC$?MTK1DU}*VGLDu#;c!$q^eK3q1%a>8oKfVZp5+WTB!q`$@(1C zWDH@a>LJCx(u5Y_rs^0Zm9(d()TySfTiR(xFEOsvV-9hwSPYf?k8J$5iyd*ThzqV2 zbz)p;V9-;Fq1Kv~hG3`~Fh-dAU|vGn0Ic+9Act zBF2?mt`&=+>Of03SC|N5?m6;8YR}l+@lp~`X*XJXa?}yoF%O2Svs=yybFEk}q)v=& z`Bmg!B(_p9t_VXVew8ka4$BJrenL?70M#VkmHwpeAej15Gmw%nRAOAoWmzc)%ZjvS zi>ew#UvZZ9U~Ksx^+o1oTp3KwP-cavjr7XvZ92G)qPoXReP9p!96pj@oMZ0#gP0E^+z`dp@ zL5e&hE*8bpvC)uHsZ%T&Y5H-joV9x*3r_{=sv@Q7!G;|;tHugldk`@s z+3Tg_%U*vG`hjeB(InaHg{g2!HPBRK$BQCGqd&{m@6jT=uxxsfq$qS;S?6T6uZezE zk6Kyw?5=1nv{Kpe>~5%R^eW5B7m(_5w(J1W%;+Lrjw2{*SHLHaB+0%nn~%dUS>IRt$@)~0{BL?= zKhcgxMSk_#T$5p(loLCYd4FRAeiX?Pi>@%~?w_h&xxjFI_mghNpiQ>?pJ7aV_UZU?Z7j>?^Vx$wnhf&Kz16kgmnPqS!SHNwTS2 zOaJTXExz12^blW+qR(7Ik420upE$i=7Snbu@_O>cl&-^)GLNGhIX@C9{@o=UFUE!< zTaRMR%)^edm=;-TZp3;bHX3=rEx|gni1BZw&rQgMt|J&KJ)RwA+HD)x)4 zH;Nf3yN$SbWxbI#MNtITaHgy`;+qkBjH1Dau}0jumMM1)mXar^eU^7vFJv!{)^fgB zWge&BbBrE~TuuHQTZ>iYIa*(!Ue*-Fv{^@b-q>)&^`gi&@^+IqTzhhP z!zm_=^a%OC$*LnO&nt`)hh0QgBKgEA_KPewuaRECo+5sl^_;iP*l=V`d4>M6(Y%0s zfqt^ZtVebr-^7}}1C|t7fW(cv0lUe|^c9E9M(iW9p}#?G9Cj12%WNT8zTC~&Q)E4Q zlk_@vlnut3vYC7v$6K(Jyh__!%=9WY67kK*VzU+N$(yvxMzalz$Qz9RE}vpOvLpGs ztoS=36`w|2FtXun;mr3qLtHU$arXP9x3SpBKJ)?U9jqj8(?hXl-o}O^=G>1smIvH+ zj%1yY-KG=y$E@-@Ar-Oa6Viv+P2Qv5XVkrqyqNqm)3$?p#f15gd?%kW0V&(gPUefp zULpn>*=TlPH~HZIu=f^FbQD>mZdsJL5g|k&LWBf}K^zb6?(Xgu0!e`2u7kS=2=4CA z;5N9s!~4F||9OFVGk5;^2j0DRE!J7JtGcSXx=+`xs%^E4yypm>`tlf8o-(5}Wog=a zo}l-bC#bCtnMpu-4W%}oJEKn;&z<=z5*AOOd5LGVs>y3wBDc{$&C3MOikZZfUU4h0 zxi29*abKPC8YL@}sPP(9{v@O%FHoY_T%|0^hxCf;*)K2Avi@-Ok*oh)_q*xMMgKH< z!qq$OD_p-rOZv!NhWH(*vSolTbI-fn^Eyx|kvrf#@8u0r@6&E;pxT@FX|WYj70%Mr!gdsZVLe-Ei;I z{^#7|DKqbp`vtA&Dc9X`dW!iF>B&c=zJl@`5Bz|7Uy)L7^D$TY%hj{XC&b@yzn)}1 z;rd(d`3$K1=UY;3kg0r1*>~Kp*IZ9a{+{4Tzh9F2k@mj=enq)w%_vh*KJyc8Rr}z6 zK$@a2Ugb4EAxHU^mVY6%gUnDe<~IC!lBA6l$iLyhblC%6#;V+b%R>C!I2!pV=MP7}-nZFINvPi7VwY%374YD5=q3 z?xH-SDJf65){Cy5Vmx<7FE#p$X&;cOK=UiRnFG0r(jX-@&5)aT0!>TquKeXz-eZ)k z=!d2i!QF68snI%)gd=FpbM>98HyVBBwnCnRS6t*dl?=xduG`agCByMFn6^k_I&gn; zBq+_1y>y@@B{?l9o0I#M$bLdMYAC&FPd#_LwU0_?^pra)D9O>IZrzhiXYNrV(;3)}Sl_wbVqKCm zH?8&Nx(6~E&$>}k(*>y9M;T2opy$=hi?pQ&(i6|CQC`y<>50B(`jOI`OCRF?Tr0il z$(7QZPGLUE^cbV0eE@INm9(C229WBD3`c3qAX1g5-2TW&=H*W1HhPco)EfQe4n&5c z|6C<9o-#9#cxY7a%^5GWt0ZR-Z~*ZFH93r4afc{Jp~ga#D7P6z*)YQVK)vV=Bc-QY zWm&^{YNs%wRzr!6o^l71Hh{_dAdxOuox{>o^mJFq%(SUQ9h)M#?xTN)#NDSiI?PV&zI3B4bq!10XP(%RY{KC zUnWvxQdC|vi6_hzl+jE?cCtiGZZnY@?ts&qiymt{ccyF5L+&z2QWocWdG2=yoO;X^ zXn85p%8K-z>j^MRQbTXKdeHUknw7YJZlpKMaJ>rmcV$Of*RWDedZU*Y{nM;Qt+|8V zV^%_5;%PL>ZS)(XWJtM<-e1&at`XI|uffxm!b4vKsBIP3Xqnx78`v zH}0CqZIt+U;>?OjP?YN^qgflMHyVAxD8pHuk`1V%Hy2O8*^uk?kdLfOxiXsdk(4MO z+Jtvl18K;r)Z2vjS{1p>`qWi!qn8*x(C8y~Bcw3vamVI_jgfkIQjNRbHmylm)&p)z z{Vl1ZXP8a6Z!22f1gJJsiOpt6K0JqJYf>8_h4Id9xYi@CW!q9yFELwjwH^6-gHe99 zee8~$V0)h0E$l!&eZp)(jUCC+=k4aiI|21@tE^}z?%WcOF4{lrOx@wYVL{(7`kv9Z z?GAAl>g)v6_sp)qUE*$0Inr*l*dy#t&aQEH>TL%c&Qtdwe>dQc#Crnw0P0D1FG_a@ zs_WdFoIT^-w6#;*2e>zISK@uSvuD_kmUfN%5%!7uQ*RI8Zj|j$YPWa*Is3=S)Y%WX z7x84;+zU7u$;W}*vv)j@ItKvvCZ0mhf$<>P?G+A++6^8=TRp?U+`msem@p+yrNw=L z`%-Ue)GA{tsd>V*s6ECs+S)%(BTNNOC2u-U+b>R!T7XQCT6aw6>66LXj}{N1#RGv_ zaU2qr@EpSR0puLO{f7|xghPq@0jCfjMyh`}EGpYMjQgjMGoARbcqk=@aeZi<5tZ}I zh)Q*4P%Yv}~nsSHAEw5FsQ0hK~DCT;}((Ues8?oDe_ z2W3O@_SR7DQ);y`wd9_)%GIi?32EfOuO?XG8Ier`EJBfee zKk@th&+hZfC=aT>sd6E|hrL$+9`>A)EoDiNMwHfNSXvM^Cf|4UtJ<^GTPRhl-rl|} z|M2~Mial$&|HmHp|NZ)D-Mjz0?>7*+D!%f;P@(JMAgCTsRqsTe_}c|2Uoju4mW&;# zqQQhgHMwRh#*q}*{Di@b8mW1$__XrWvQK}~dX?@;tbghGYtqv;tVcb$9vYmLCQ-XB z&|MJ=FeCN=_MmKO^4bEWeHSEO8KyJlQni2XE{VpZmnL3_`~~6umg0-Jo@fWQBW;|HY zi=0M;(e(59YiE3jh@(#;6kwe}&m1^C}W=gp4`wf$bduk#<+s;Lawd{8vp!>zen9A;RZvKOPq>bldd`B%pwf^kN zztQer+tkWlwX#&L_mp;@b?ble!@Ujm)I7BwoQEFlO;2kJs`Y0l{+a!y^{2ZfwFTAs zvm^h&{?ht$UV1}YP%&#x{)he5m(YiQqXnpTpZ1#gZ?9=LUhP_OylC;MwWk)L)qV`^ zKHJj=uAuf;e|n(Wci~9X2GsHG3{>BppmnI$pR;?a+I>;&Qr8;PUUP>-wFjc=JNIVT zUxVqBYA3sTj%sg)y*8L0QeR?E3Du5N`!KZlv>)A@v3l*Bug=%*jXZyDuGgrIuQh8u zxF%`$Mcb!q5!OVOZ*Q(maR0O8ejV=VjjTTM?boH$eS-Gvx?J}{dcQg~)}xixk>#s1 zSf8NX=9;87pcVHMsx#0|RJ%>*8_%Pi zcuLunUs^9Z2m?D?1?P z-;vZFwBq@Ep8BVzK^=owx_1pv)d1{DTD^jnquP1)t7#f`BUVe$AKAYi{PrcNb=ZyE z{m9uDNxrB4sbkQ3Qw*P6!|}Ha~qa|mfq)6=t`Uh4HT zuMd0Av{&mO6>vDMO#`aAIJ`C^9?sZlLi%9p9l`wrfHSCh1gRNF`lpjRlD723=V^d? z;M3akP*O*8&!Ip);U7aghXW7i`dIE62z0a_M{P9=M{un^L5;())?rfCsF$x>YR!EU#rq{DLVz( zzZwNS*Q;r8ZaJSCgOT*>_g>3T&z(Pm+85IDSwJ-!Y8pIo{v2Zc?WuJ*mstDJbCLI} zQBe2b>GKzGrPg77B>mcbUPe3W7o5Y?I$VMl;CyOm8LHpCi^;2N8q_Oj0jl5lOKCwr z_4=%L-kZtY)%kptra_z0<~41?#oT{w?H=twXCnWv^a@&^&f@wi;1$%+8gvM9`d zI)=xQ>Z>`>o8D8%`Jdq4X9)`;-G7pDebYY)RNtTlsQQA(s9o19sAG76>!*O~9MmOf zC#nzomk6G^_Y7rf6cz-!=Dxz3+6t)W`&Vi@2DJ-MBiC0?@hY{S2Wma49q3EI7l~gd z)6EvcHk4PO^WEbfsf>nJ2!@>fRctH~F_oy#dqIB*%;eU&=k7!jp z(RWCFOe<;^)Fr50&~8(IeQFofF|_5%^Xi8IrC~m=QJiW3+L3Nctd61byQhVx9{lS1 zhL1^oMJt}hr(WS}?)en>3Ax|U-f*B4(Km#V$o#*CYWlWD?|w^7{l^QPgw~+y z8?-f5_n;5?uWDL{_SEzo`%3qq_xNvU?I*%0vKLS0TgIAg5BDq_TG5U+qgtY3$q7xX6{#oAt9#IL)U)QBaiylg6X&%-Ro~!= z^ID>|BdB9&8QDKd8~Uv8L@OPlw6s>DoZ!cu>Kob+Yb)v*^leC~UFZmGOWcWiZP5a> zBh`f(qeB-0{8p4!_hh~fXb03W=xI-_Lwo9V<^DN=>KM=!kW%;H$$XuOJ&{iv&d#KI zQ0Ce8UE-L~gD^JqjPh|kXy@_Eg zVbL&-c1FcSu4cI4P*H@btaqYw1a7lvkidz22*_P!^Sn5u2GF*YD8MQujbIu4Qez?1JX+5q!CJO?JcCV0Bgl{0?HS; z21cOVm#b3%%H6q=gxU(={#19XqPyjLIm_zLV=2C%oU;Br^xEUBrazA*=qG0*_p0gx z$hpM5s*8bbok_VrwesOn?Ngn|2$cJGuj&NGq*4Lp0iKbj>}M=Nk44=`jfN|Aw`vb! zcdL$JPLxB{s|Wfr(u*)_%a6J0GvpF=%o2b4TXD{4|;9@DXr)RKz}L^*W;cN9OX3n z*VA*r(!~1L(@Vfo#O{05f54K&`Vi1#z!JoZ)&8Sc>ONY(fS6y&SM(d;_i^M3tM69% zLvcoQHmggsoZqx5_5155LZ1O+iJh7C8(@Da1JPqZ<#W%Tb(N|1x#}@sVRH1Zr^kR% z#7Z>u&oPp??sKp5(;*f~GgNz3^%5|Q9CxPbKR{msb)S2B5zxP${sStXd-5gH#?{VM z{Ra#o=U;i-Q`(|bWwy_~0p!S~3YFc|B{ls?*CjnldFs+2R7v?!_wEsF zH%D&|iLhjCge=89S`0aImZUAEbIOpG;E77^eD31BK?Bka3GD757Ag<)ZG}n;9m7K9 zijHXEc>2t7EmSh;mk}zx^ot3VZ7R(XD*yBg3zd;dUkly4Y>x=F2yk52eLmFpCEJgB z4H;JJ-{JJMIzUJIFfc&O7atY^L&SXX#1j+6c`;`JFiD&juZDtS$}z>XA>f~w?--w- z5$zZdGY5mKjs`Jy5IF2u5t9dk*^VLcd_WEJ=L0&zdJqd8e_9~-tBsewwGkwA)b^sR zPi=gec9i!bSG!hAd)7+zz0m9bZKp4}m7R09TASTyw>!`7UwZ?e+m)yLX1>*2K;PK6 z?E>_l_%AvG{fGX$PC);;|GFd4FXGpj6X=)nD|s%ZU(m1TcU*uk>-SY7;1~C6w*@-V z?1f4`Sl=D4-clbOda2T9M=Sbr1U+rfwj{Iy1MKk@1pQ)(3F5~hK<&Gmk!}tqi8DqBV?P3@G;J+IUDn zM~I_C?`^IvjvCjG2y`?lOV)FOng@Mp*pq5#l&YMhiRtC3j(s3oVeR{fDU2Wv~D z%w5U6l6WQT&d2J2l+kNzuH;_nymPafBW3z(0sIFYA zRzsjRK`oWEoq7}JNi_=kd{O_PzCjI(bEz7L%8!rpduP6(vuz-M7+C4duFSj(m@b#q zi<04Bu5*1?0+cPe>QB^#%uT*}BwBdhBG#L&9`B6S#*pQ6fVk?WAFlKAep znFq{JccG4=FF04%Gw2&f-9_D7k!zg(D)dRA{P#ce3HE#W_jNWD3oFmQ`mz#>{(b+x zVud&(hPaxEEqcmuHWWAXUghd1KIq@qRk6Z>$|F_P?^TaFGAsWWvpxH|>MG;>Pkn;9 z{`>VS&msSgf8Rdzwcd;L0MxhE^L@!tFJ=GtBlM+R`&>^*{lEjCB^LB&p3@JB^iKn@ zO^Rb6VF2@)6i4N6NiR3*44vyL|A6{uY65oq-z&dO(qMD&b)?6n&GhahohHrJ9H^Hk zX*skLk?p+W80Ox^02jNZHCbEmghFt zDQdNn`sR|-=6o_>MS*u`?9?f9eS1l>OR+D>Sd@~l=#2W#DZhqmud}9KtXh3tm0g=% zrCn=XaTg)3*6$INs;hQAb~SeYlwYh`=UtPV@Xy8&i|x*fQUtEYuF7MH7b35s+!o@$ z+RNi9X-uC;P55OOwTg(q>JpK!C8Xist%B3_VpuV`2)T4!}4Gu`|8zj6Q-eyf$9hgJ# z=Wb2sLn&mrJ?BHIV!1%)Ln&doL+3;3Ub#l+L#f}YN2J>2Fy$_#-Q_%`?iU3IHbk(^qIj?Hwc6OKZa<+Cx|26+r&C+sSi_$mF%=VUZb2Ss!*Ak9@Xidsa#8Di3W^zkz?KMUS-oTs+VDdO?Y~XRS9(`Exboaqd2v%>Q}@#*4e3lMP3inD&MMt;WY+z+{n}5PqqOe7 zO@FGDpSJ#dQRPIATl-lVSKV8ily)_S<^SESEM7>@H)aI8{z~)L{j^DwN{_ly*Zs6< z#Z!51bDUQmHUHjQoBV=Y#$d2xw$C=Xk|DKuK>AgBRZgHj-W+?CR7zV@Wr&VW?O7eM zN~PTC>rC5#pk1sps-s*R+G_MW_c|XqD>ySdPdHmRS37?=i^yv^uQfwl;@4lRBrm z_S%0+OPq6^d7Xo$>cs-7mTIO}Dy2_EXKb#k?Jy>iuZrLB7z6(3!j`;q5==tFSj za!qj_>_}~~&-J)ZZ8mh}kp^%LZU=O&RvP8%q;+d0jZ%K$i1OPxLw2csQTKC8iMR&$ z{;z-MS6_nv?7wy0U4s87^7ZjNOXNL5L%jILqs7_i=PTlWuI`Ri6bR@sny?ukiwE?8p#Nd7LrcVzoWBs z15(At~5uC3Ji_&sHm>^R45`7NwRQQ9f1r+7VTaEGhH)$dY=m zk1YR9ePlJQji_p5$tl!FmTN|RWVx=?N0uCiBTN25PQn$)k)?dlktH8d@ym`cd5cQA zA}!)NSJ5fT8>^A!dMF=IA7Ay6<@)Jr>iBY9b(K}B>3ZwxtF+VcB}MO;5(~verK7If zuHs^&6qq!-Bg+vbbc{K^l)yT&97{r1B1e`qy(7!9BouEPS@H=|7m?ojQ$GK{lFvJW ze=DW8|9)@zd|fgxMeaH*uOzHX=B40W$^UO3U-InAG#q8s%H@jX$f{@oN7+9cU)9Rx z_;O^qBDiw7qu^hUFX>#VUPqbhm!qs&vu2Mk>1C;BM_Dzps!`_1a(p?`em%Y%S&lD9 z+ONl#Bg^sSNOMLjwYkihtwC+3lfJBE0#c*SaL#miE;rc!+*4X*$Z_EnVjuETEBihzW&+zrPRxB=PD+T{g2kK ze>T3P50z9^oW0+(;`smB_>w-XQ-=SY@udu+8fDeWRUcnchSeymR<8Q^a{X${`0yVk zLi^fi!CN6IJQs4siLa#Q1nQN#L2a&ZOjdH9j*LB5WXGV;71?nobjEP330;vLUqWXL z$CS_+!*L{ZEmn3ZbgocC(xWzBx`X{KNVlxb6|MLuy=o((C!@ew!m-c`%&+up&L7G# zwYJdjd9}kxs%u_)-C1Yh+C1b4^bD(o`DUXD{eh0sF{I`LjwT*ko6p8FvIdeK!_~Oj z%qNXFkhx?WBW40&Fc5nyW+VGk>T@u2mHjM*I)81xa@UPijB}LG+1GhV=&Y=6QYbZ~ zZc-?gjUX0EJ;{T~iAfz-bg<*FB~PgMH|bw@UJRiX^$+rSt#}u8432jBz={i$Hj^_{ z*C3}@X?$mEEeG+miX*DHPgfZEPtO>X`&4sQ=T_xW-CrWlD%IPbFQ+z14TRjU^r&2~ zystY|)DHEh59F2A=2hIX^sgEV`Ds@qd#2*Q)nKT5lIyPgsB2A9?X2ktjyg9>BhL%Y zspXM&o(G(>$K0)>rm~vXRo{Kiog0%t5?w zSnH`ulWI>X&2?-vq)+TW`%B5ME4f;x2K1D&j%qiP{iS?FNl2w_Q-Zumt&fza*o*Fy zvQM0?mCui+zZ|pfnM$=@t9HVTrPmzM6@^{tV(lsWtCGxDT39(7rQze~FL!b&E0Vj^ zHpxD6WtKy-hvY8pNo7m+mE4lDc%eF1^(hd?SsV<`vgDMG>T-Us{p0a=b_nsdsj@R|ej*?2hEZ1C(irKboQcsQ_Pm%q# zMO$Ud_Iv4#@TW25;!-9kEfl*7L2045)PSJ0Q0!_*P+Azcs`k=H(v7(9|EzW@zX6$1 z=ALp_*h26hx&AgF_>UZ44GI1u*YQRKy#x3)8Wa47evKvsce)3zBB2Q_HReD2#TwI+ z^$WrFt>1uP`+mKK1l#xPRlDMCM@tXC;2-gx%7gW|S-q$J6aKjGkeJ!#pnWNmOb~yZ z*$Tn0;g@ev`}%(8R(uV=zTdee(68@zZUOY``<>1$YP)%uw-$DQ^4GS(?vdD@as{$JOzhHu!C^{5a! z12b_0Qk`n=)|nQZ>ug7A-<98Ib>#mz?@3R15~W;Y6Rz6>8x#8<+VO9k@%(S?_?OOg z{^z#*d#N2y!E6omq)K^Y?ZI2s{%;H7Tub?e)xTEbAeCn@$CU6Ne_NmV+b>-Cx%g+_ z_K(J4X9?}!oguV&7gL-e{GVcwGlaM!W;sKMQ(~Mmgt#UqIzxzq;)Ekl+^k0WA2G&l z`S+iT{%@Jn^ygyF=%Gb?cU)AX%JFDFIkp^?;=6d*gj`31HTC6EjY8M4>eSBv&Uh5F zE36jQ)4#?43~o5zb|Nl}!%o0XT-W*Zj$Ain1j?;zrO~KHF*YJcERu$7Oc0Bt9v!95 zaL%qx31XF4ItQT*P_F>Z$Z_5iV;!Z^N%tvi0@r z|BUzlXLLe+)c=}V_${5_3a|g13PZ(Iu~2-h<_70UakTPKBrcgRb|rpQTD<#pTHF`E z&2#3reQP=r#D1~b*-Sj_N?dB3P9ZHG%IP#9h=+1I4Qne(B`H!)Bp!;ljS1qRoPU$r ziqf=(w@qs+${aPkoujsvG^^olGjha3@wPd^^;f)YK@dB|*p`GAyq!CX0-+`E=o{wR z8~V1+y}qIE?A!W=zO!#DFXlTtYAP95r`p^4hQ70J>&Wt*9W@9 z*~FQx!tTag{rwy`8*l4#qqM+pzgvA({WUdi&;GOVe{Jq<+e}VdZ?o3vn`?>e`p?@km+1XB=pmejdU`wF$pR;2Npz|U=WVvcjXjhw`ngN|hXP+D2 zfqBgt*ZH^!P`vF#(3(XKNV&e+b~&If1hs*3KywkaW|0HxN>JPG3ec_g{k!oM3h6?w z^sc#%wBJJx(2M_-Ym&N*q|W(VNnIg0j+E3jAUNuk)HNhHpDUwlL~!*{M%S3&e6EbH z3Bmci(pk*K^&F(7d|VNl5xM}oklUQ^(h1m!>lS>qj=+vwx8%Fd37nJbR-|2xTo+ms zIsiM=da4~M_qMvjH4=*@;)odQid}Jw@&V3;&Xw{7&X@I_wa%N)traiooa@Z$x-56# zeh)EF&QU6-PES^2!e{y%*X}=dt@)$d|DWPgeP(XRH~96O{71=fe($;N@A38`5 z%GUl^8vc*|4*$*^?s#*}P?l5eWUoe#qexD>8gCT`?r2j|qdTO|VZ_ zrsKOiOG)4Q{K$_ zKbpt?EqC7>>za<=V;%q3GM4{jT#FNRUCe(+uJYf(=ej&nJam??-cOqE z*ODLSKG&N1>S68Qrt9O*TxAfhWzONsP4veiAECrTYhJNYd4~LjU#ybow+BO98?eTvl$NsG><@e!F|LA$+{|wnySX9{uic1y!DdqRC^c~8CT`!dsHy|zUIWtxI5p^ZM z)sOsreV^pFaxVJ4$N2x3POH|nI-OZ*@a-4Z=>J@I|Hr@o?=wyl*di4p=BQC}t`l?A zEBQ6V9Q8_KshFc)Nh}p})GLXlVvc$xu~dn-dL^;c(V<>REUjyloa_9;b&Zm1j#yb~ zl#~Sj{`7`;RhJFAqtO+y;=Sa-?0KImcFM8I@5r+?Bc*k~9K`N{3qape9#MX+!fxl* zf2M!0&%@$#b*_LTp|WnNxWUTmrQ#ARYnW7fVr3;0Yfqf5dGRfLr)p#g>uEW)$~Kcz zo9Q8KqdE{=h22XuC&5)%8@Y}IS7GhqJQG$apMKNykhU0eihk3&)NJJRVcP{HTOsC&8ZReHGX&a?)el0BBQKV0QE$_6A z((k`^f7&2=LO^BDI}%$Wv8WHhz1U(=UxItw#3Ij2a7UXIOMilUv87n%Be)k^ie&)7 zz1Xh!0}1-3kYdpScHpn<+4M~z#Zq~w7(%Z$#-6G%*F)*EM!-f~F961P8m#^cJQ215 z(6e9{qBjb#a6OD(%D~LE`|;f&mbh+9&nc&MC)uC<^=E(mIllfJUw_Vrf6j-0u3vxB z8-LOpf6|A4(uaT2^MCSRfAU{{^2>kn%YVu@{**`k|0$1($flI>DhsV!cq`$obc;%S z>)Ir1DtWZDp8nVO&aPXfln>9gQ>$y?D{Ho2>)(H^c~@pzx5iOst#-O@Ggp^|Dr>D| z$<27rrpW%3?EW5hGCu3q)-vv5s@u;i?^7@B_fXra{heR#zi$g&?I6((IoI0q8~a}> zZH#-O)WQ1iwJxYE$lW#N?kP31zKwgU)Xciq$~{+VW~+T!m7Th~vfQ1eX4XAh?%h%| z>s~JRbZP1C9xwNLX#rn=?g3Lj>z*+8hSe<}x{&jDR37_SR1*6b>Br-vq#uh%L3B-%02jc^A(KL~Gv2=gD5BNa5AGj#-;_1G4 zFK{v9CDOg|9^m4{OQw6`-M}S?r=%s*-SNOQr3UYgcg3ZWvgM^{eO%fn9hmNl`w;Go ztCGJ|S_Qaj+Lw|$zT#lAg}9;&t(vd|kX2_%!iT`T95uI4eG#pUv0CYvQx{ z8RBR2HTr`i1;@z9rrqU(dJ3TYxvm7xQ=WMLz-1$mAAnl)Cq5iA+Wzw$zC#M6_OTd@&OL^}!Ie7}!3c%&la=;bR z^65)(bq-G4QcC|N;VaHN`ynis{u-7^lYq;nWq`}2Wz!d6a8pj{YD&H5sWmA*Pgokb zbXqNaPU#ombra4F^Axq!(hG#u(`V#;4vshGw67N_Sv`Hq)n{Ri^df2H`=4@J+KXI& z0``9z)=V#vR@VOsXQREu^~a2aPr_R1Wzx$1J%g+OcTRir-_}mAP;YHY*Ge0cUOT;! zcP4)$(i^Au^Db#;;I3&G;Leo2%E@gTrB?|Xrc6s8GM)0Q$A<#+RL zY1i~l-aYLG+>PA(=x6QoKIB9+XPyr^Ic~4CXL>s9l=ezbg&oq4z#Y?0z@5l_hVnhr zGhvUkJ8;jm2XJ@VdM3P+-_B2l?b8nFN$z?o%#+to>!o>eZ{l9Oh43{_i0j4sZa{kd z)H~0c=gI4(c?s*Lo|N`tqWXaI+nlXF2y;`uZkn60PU=Bv&-^UUe;fF>{3h_N{5Rm+ z`K|m!*e-3Kp5Wue0(6^4;)9_hc>$b-{4fc3Gsfu zqo+3ApGQ-34Cg*Qk{`|!<9&Qv&u+ReFA^Wkj{qN`#x=af2l*PphxxIvS=ux`7B)@W z0=MOD7N+JRu{-BHvC}{Pk{`>X;$!(y;G@}-r@qZU=aKQ}{0s0Ga!17P^0#>e`6FZB z{3fUI_2sSlbqo25s?7HMI4pP0Tcs^i=iG^S!TdHS`7KEPLixJzasC>3ZTJZIQT{kT5<2HC(<8jq zqoE7;JrWk6{(^a~+=cYe{0=7#4kc%SynOg3|CE;tpX6_V-*CM`_$mLGJ*n)cJcOD< z^NL{@=YFjie#}3RUV(VU@IxNPiCznFUYO^DEyNjI3vw=)=Xxy|=jW~=c@@qn8(KS$ zYk@eJocZ%$aOWM)zWg$Ok!OXk@|VD`^H;#@h#wAf@oo=?uDs>Lp?&U}R}Disq0AGv zhQ>i)^t)jYEey`9g&~|`=2=)n;z05T<<-MrPD5Kg%+E<@t8+Tm{BZ#J1G6U&4~lCL z2FCfw8IafFpDtHBi+Et%i1b>VApB|mBySWx%b(`!dAl$2L!n)64{XnSY)Jk_z|Zq% zc>~~voGkoB{yeWw+Ea$F=W0FR`kYRDeeG1@>q*@}dL7QPY)30=bG1%ro7?3F!{D-J z7#Qa-gNtwg=ex~MYCs%B{@^mGEX$h>Df1W3ek1gc1IZawhL--E3^%k4As#@^z_LK; z$N6y!P|`2XN6vtZqmiuu2 z++Xq;xi_#kC)u4!&T0A7+?NyS&dh(wy@0)9&)A0dejv2TZHfEQX8&>ubxzHv1>C+1Cf z+l|8}oN{_&IG&sn@^Qf9bL-qDKM-0I?hnV3b6h?Kcx*lzcuXEn{Y}u>-b_3U$Vmg- zaX;{W&Lmxk9DSSM!gwr@GYcT=2rPW;C-BC+9Kb}d8I9KOX4@ut(3o+^x^bo zx`o9Z;K`BL#R-cjcdHNLi8SpO7f&B#dY5F8JrL~XK9Jy)!I5o?20GsAd(nq8} zP9Fk40yfXh@&~{V(+8WOz2c!nb;sFoJV*V+rNzkV*vRl7LqcUq=1Q!(~__j1SMHXVVCv zzI&b{H7@)$J(tFY=hI(nP|sA)lN!TGyjQ~x%_KA_mvZlAoDQr9tV^+S7zNbB)eGtQ zG@A35o0O*IDDG%dE+KC;X9vHSUPzbF)*_@Ap|+>X2nyQ=O`D2r_(d(B1$g~zwpIANXJs%tXvqLN>8T?DZMB(FUOK|d-{cM z`cQg`+}j`{eo42Hb9=fqMOctq$+<1vLi$!<$}xL_bn|jSc$j-G2oG`B1>uqOaC$U7 z!gY&s9Hqx|l5~r5et3-B^TVU$&lPh{xeIVEPSGqm=dPTZnSi&Xn^RX(x1`ST=TvfM zO1sp~&%8O!9dAxIrB38`=0wgf(vPHnOg{mCN zZ_?N4=kP$fANUjT37mM{vYbGev-}e7Pxqx?!q3F*sM$WYi{GYi(jNK2^kmu{xJTYI zKan0!d*&z86Tm%)J8<`$Wv~2rdMxcl`Qxy`zl8fzTkdTa_s)Ce$I{+}^Fw=Tb}0Mg zz4Q5DAHsQI-@H#gFYK511@52kNq49H^WEt|;DbExU~=})2jzRyJ?S9Q2j|`Le$+gX zmfDpQIpMo~IXCP^&Xjy#x;IUMRlN^*FSQTMk#l1Y%!#vN4+6n?xkC~h??i*C8@JiIgHX7c?r@> zmX189RoNx)n$HQl5Y7&VQhHckp3)`CA*2t@E0A8ktWZwowDc8$E0i^XE0#5YYXVQ< z9QK{_+2JhUF2t*ovqo7BxO&+spB2swJLR2;7f$Er^YS9;ynHTjVdBy0+~J~MPpm**>T*EARLxYD!qDC0^m;&G)n@whS%@whTC@i@N9 zyk(2Lc|J94K{zFB2HZT4r=&+2Pv{ODo`$9Iq=u(0^A`D(uq9!&GIzQnUzz7lU5Pj4 zuFZg_aRU8TdCR<7*($GERspV7RxJ}~V_2F%SSanlJDwSKAp9kCOLM0yb2q|udF#AY zUZqSd3#A3qMDAE9ZA)vL=56!ooMOKX<*Sr!^2%i;;3{S1(mh?5ug%?4H{$K{4*4%( zd%_uEQQBBAElOA*ZO6Ua=I!zsoNm7zway5eb}*h8N-BG$@TMgVI3Y z2;wWs)%mJ?d6}87240=7C>ND0%2oNY(vzoLR<6l2fio$)l$^_ey?BF5fR~m_O7GN* z^gO9|x)^v#xw6cg=1EtQzPQZF7tzjDFUxq^#S%tSCyHiU+SA?l5=&r zsSHT-rE7_W^QHdj#xgJs01ikum20Ru6WBlXOV^ZZiEk()DZhbmW9blX$k*o%;q2T! zb_h4-8%W=jZvLBVI91n`O*MV{UykXg(te@8-zPoHm-Ma}lm#yPgQ5(*! zfg5CMlnwIw#M{KJW9M)eHSaFxl)Lhs`J8fhz6*Fyz8iRNz6Urf-wV8m_}p@5z5{p; z@ttKW?z@w4SNS4tTsA3R#!bqmz%Piqgl*$Cu}j#7_RlNlmOJu!gvs%|GC3X)KacB_ zwae#m?Xod&WA6Vdei=6{UlBGd=a=)!0r7mo{_&2oHP5+&aA&!IlKtZag#F@Yaow^` z`7Ewi)&;IZD__&bX65U+UD+16S=p}46}F4p#<_TtF5yD%-Y;HA*f)Md-EGS^aU0tH zhSWB|t$D_$as9F$aKpSo{xtH1NUulhXO|1hzQBFsKCvrpYInbV+%BF~&My1Jxk+o4 zzeC(Ue!{(<0yoMV=1=0rc_ZN3dE@+ayuI93p61`&4*Z7r%yJg@o=Mm{b_+Yk9e_K< z9f3Q?oq)Tu>TOuVh!3VfRQW1jd) z{5YpZt--&uJMd=dg&JaQqBNA7w;+emgl(pp7J5}KZ+m5HS(JI#PSzP{~GTt z_m#iK=ZHTb|HJq}Ts^Omm(Q!`590fAdEot&-&gK0&&R*U6)1T>u9#N%o%_oJ<%Rfse3$(9;)CVI_yX_+%AO$oV0j$)1n{N!Vtfqvc-c5k$P@D> zapNeQm>10(#qoIpa6;ZVZW{FZ2JS<=Z&*3M%NgBE z$=H5NS0b&2}4yS@IlPBfHxqF$sZXA_I0!MP^kzuL4WImGmlfxd= zeJ36fmd;D%Bgj88EWv$~@;Y(hJPJ69dk!aWQa(IP%1Z;6rrz${_fFiM@OE4~E|M3{ zYg2!nID?vphZ(_>#do9D+i@*Q*N&Tp-AErs{)})~@Wk=W!lvYGMtCb88a!G2Q1TB8 zn}^N9Tk#N1HeVXJG`Ta=OYzY%Grb&NidO??rfbq8<>7KodbB(OoJo9DdL_ObucGwo zbS>o%mn~@Nt+)l@Z}Cb>uS(aYhsqA+I?5gbUQ2vMdNsZhub}kGG@Y}`C&lSJ_mFUT z+M#S;F6WLN%9de^@V7XPQ`DCME<=s2!j|OB;@&ILRPv{Vshp+0Y@EvZ>C46I$)A<3 zPp`#S<9y+eJT}i4M(0IOSPIzBF_T}966@V+n6@e?qm4K_n zm4W?;`|>^qhofodm~?b{Grke$OuLsoO2@QE*%LS?afh^H*&VohnKN}tdzQUQr__=7 zDC!@bF5&sRmP-h`l+J0dvNy03ar?AW*%7!SceYDAmz_#Ga@waZY45U6>5@7VADOo1 z>mQl6;`<*-Ye%Ic)8FEo@!Pmh*|&TfyQFDfgk4G-LfiBmckf%iBkWfWPuqm8!{KS$unll)?)*M}7xydQ6ZQx0Uk)g(X`xMO zoh~D81#AtxfcS^_eLSH2K$u)+r0v4CVFv9So?24cD*YILh?C1<s{IGUuPdb)$3&d5zPhF>=o(F{PL;A$@7QIOden#pGNPFN@R4)N)z8l=yP4 zrUIvygUdy+q?|6I=Ed>C*dUd3AvqVtE8@ZBpmIe#s2m17tjqw;D2D?tr(_1@hXW5U zCzK0f!_**Mz`Ym7!{dy2LOGmpd^tZhN)6NblwJ_ekEimM=f_ic+asuTd^v(}Tse>Y z^W%~6h*i^l?wkH-Oz;9GSMM{`&AaAY|GcvLwOcyu`mcuYB3 zNW0y`vGJJLBb*SA2OiIL&v0TqA@(FkAO5GsQ)8cSdOQtyMm!z(mv{z{X95}ViJWvM z>4Vboq|Z!$0iKo41fHGF0-lr31|FZzNxi~J@x<7R_B|2c)ObqNPw%O*cQ`qo1U!kd zdBQ32H zk074G|LFnj5e|nM_KO@w&J4chk+ggiVIIDbPxA}U6Apz2>IUpay+cSJ%D3?y{ZjMR zzEqzuo%}=i#>euXr;(n{mphL1RMOMtWCnDkWs>j|Xqfli+Sg>p|3PKgJ`yUDo+ zT6k{i-CYibg1-+c=Rn|radNzi{JWu8?kkg_N2Fu#B?Tv2X87j5`UKc@}Fn>MT!4O z@#bPL-wbDTM*K9}7oSq+Gc*{V=M&=>gg$5y?7L4W{S=+X7r77m81dv|@;^bp@g+GQ zJ^3MZK0=>1i`4tT5Au7!_t7@aD(~fYfbZr9 z_@{T2uHmurDDd&}7*GnVYmg?BB7UGO&Wip>Sqvz3(ltC<76mQ_)v$Pcq%1*rxGWi6 zsihLwe@a1 za00dnJF_xQtgUVnu|wFqjH|6&(?SlN?;Lcj!t+VNADOD72-=p8$l=NokGrvU}sCM&PbePwa?}6V_wh6L-T!W%>#2syfl1(6(P!HclG?Hv(RPgknSF5!V%UnLne+R0F#K`5UGU(&b1# zwobpGc2^tvOPsm#6kt!nyVSqnF`bzVcV3-Q+Zpo zu&Jy^ef8&;mdjYjmP<2$S~#pr&U$FAw@pvw?FdiiOOULr%UZvDI;dj1{L<9R2-W7rn#l!T9= zeU_VED_uZX6Pdk|E@k&ZC0Y-X^AJ!;+Jp4YaOC(8lm7@|b>!l!#0P=WoDU@FTjl(# zBiCOYD+_t;HIa@>@!n7A14z&xCI2hJs_DKY4SXM^_al}6ikvSAtE7*yFIf@&j&>#= z5k5|zaJ>TXW8yEUwF+<*%D*6dls={G(DEteDD zq)adOBDn`Sg3F%hnY6p`#FahMC`#1@om(zO3)2DZgxb43fLdt0oupOXPHzzp z!A@hhn&xl!G%}oqlw~A$jS549HX%d95aM^Z4h@Yvw>$Jap_6wEclvt z;Y&K9&wLm7KJg&#LURrrR0aSCA_F~>R(hq0=ns{Oo=J`;e{@8P_C9>ko5USSbxQM5 ze?U!IIwAB<owH87JdH4=(sQC zj#ghu$K_+Q^6C@v@p-v$0%2Kf6racD z?keEbSS!AeiP6cvkglf9nc*1fADgcv|0*mRU&JPFX8bD_d^53W{A)fDtAu64iG*ds z#XNffbheieUqQ_);dx%lFJc`y6Z^kw2+v}TFkdQE|1#PT^{Ey zFaMWip>~DOBV$aco}{1RlL>J;V4=-8eN+b__KKC0_ieZkV8{TbzOW0Y^-b+ z&qklL09;-78W-22bT3!Z&Q;<2*sL^%%g$(=za#y9JcoKi(>ds_7J&2XS$e<~_9&Oe zlX%Ke*kCBzzaqSXw)zU}4_*PjoURPtM)mdI#s*jkd>b2<2Ea^E=d#OI>t z8w#h`lNK-M-Yd|Bo=eU}u~+E{FWIwPjLpxHe2tTN%1Ky*sOk7IwkR#(!+#+DrY4>G zhW5WjCff*`hHv5~^!qo+u{H^(Wc4GbaM#J$q6{W=T2^~<8tGHflFd)*oUDfB9Mb2a zVHiS6KEEY=drLHTUq_`}U&r;s=D^K@a_4oi%=tR5hn3D*=v;@Uv$*SQEL7CpoR!t* zo|!KQ=L65D#$QOEiDk?MLHihW>SyGO!iC{0+EL!E<Jq?Ul1xt{N!s%#cr;(nX*TFJpI;nM#JWbDQqiMVdetQYvl4Xg~i+G9Bn|LYs z>GR`K<-&LYa7p6D$zKBQZXV*r%e=&k!|}}v>`T0O=|{XcdeDC5(0m9jA4*sYo#*-S zytp*&osUNKJUHq}WohD5!Yx>wo*Hh(5>-v!&GE2&XkH5q=UP}FDd}j9{Gv6w*)REz zY6uR?YlbhQwp3rnHNzU{HgBPolf$j?mbeW3`hCDj#HWRuuzEcW-QG>{q;Olj6?l8R z4R~ujIh-DD#D?~Cv~)Md^YX2Hne*~(e4}NHHo(iG<-ISSNd1%0#2%KvjAw)!u)IBk z`)-JT33p(5`xi=24435F!)?IZ!g**1?;!Vta7MU3o6A9c7g2g~-kP*htL4kxF{DoL z*CBO=-wvq_+UJ0*rwv*Z_10gYgFgZ|gE#*I9rKL56?Z97TcIqEoO6YuWOGGy##;cD zdoEU1L`&J0ep`vKIJ&HMT&+b|3As;4tQwRJbwtN9m3G%GS`Ms9SgZ7icVidSGxmtW zyRhErPEL>5J>C=U4!vT}cqj0Va8d3>>W*+Q_5z>BZj^QhYW38c|94^Tjn&shd5zM6 zw$~u6S>~oxOOE@(yDq^fu)1rHEf>~%Sgmy-=P|6Z zl$JaO)N%;_D-nB=&@p0L60}xnAGBy`PwmdY%ecEeGu!1rE#I!9DDfvU=i|Zydi5Fc>|?4=5fDOr%{7IaZwaJ{7+hCJ9i_+`SpSKCK^2gYbd=jrEeI1(ZHsRX5Zc*;HF72#S zCUf`4Xy6)fyigpUo2``rcB-jB@@;!+cT!NK$<(cELNIjrKZiex8&W)*&cn# z7 z*%s7kj{VT?)Y*g33|rqh$ZZeokawZxu0i{vW~m)v4&WTAeQt|=QM1&xmfMDOTdW(k zIqJ*oH4DlAEcPb!4M&C}kRcvL+_z?B)|cxOuz}o*+O4rZ+6$|ry-BqqZjA-WKBTsc z$52;&wD4%|+#()}ec2Y|ZyD7=_YIqqvqjuI9*4cyHstli26AWa-He>g<7V-AY{a&W z+mOF0>CMoxZcBPQLcg#HIh)2!&@CNK`f#kSwy$YCwx?FVurXSt8NeBo?GV+OsFCfD zHUIds3vfaiUtS0k%LL$}Wny_A=pKND(WE~g7AcFCjnKgy95zDpaTxG0+S;+EpV^W2 z=3_6x!qod~7=@j{i?p{3`vH`?zldyoC!jKRHMj%9hP1O0_DegF{voYjHZMPb9q8O^ zI;0IK-4N~WPSp4@ZC?gM|h6*|H_U6W&SS__5i-f)gbi31H=00rKSO= zg$>XQ?~J9?Pf7jtPf4x!Pgufjht_r%@_$Z0rEQ8@+d<*kumx5R&j#%Qo(*d4pXFK4 zu_IxRuxD-m!X80Q@E~jg)rtR-ekOi~n$KdLum1fRO11_D>;PZkp1s(g@G|jD>5!l; z-l5@;pv9i>kT4y%eq0Y5zUjQ{zUiQFXxNuJH(@<^OIk19N?14Eme!5y0B~e>%h*^3x$;-3G4^-+=Yr{%F9o1W-%1ADX@EYf%0E zRq4tkR9}B}x+)3Pv(HRdC*fY`&1aI@E2>r86R3XtDXi4KXP3kG?1^{{ebQv$6yn!- z>J;Fs#OfUPh}Wjw`BvAG+C5%}hH(&9Zr^d|EHsIO!an@pecAJ)26&&e4;r^C(k${1 zHV4g%n%;we2eY%`Tkd+DCmjHMjd)5@(>sOIgVKRX?e2l(Od5XszyJ_Cw?gP>jls_5v<7$8G6Tjj5aV-14X8%FI+?SmZUz77@c!L_dFydO~{<$By zb7B?NGEYr!lHZlR5W8UQz6<*R9w6Nn`}YTcUD!480Pq2>Z)TRhCO?MUzdx`)Elf*) zqupt=Ff}co2jzk2@|PoCmc10hL0qkn2juyH1Buo34@AR1ANQ;ApD#~OZ?Vf@I_*qL zT2wxienl>o$1~UtppwmA^s9NW1Hw+gdf5^SgQOG?q%=B58*!c zYy3dXAJM@-79ItzL>yy?ov>?ke?yEN*&Fdacm2SQqg%1+`99o&#Y@88ac#AYL1|DzGQ< zTEMk|y@=POz23lHT(6lM#s*kp^yX>}(rW@6#fE70-On%y+k!{J>g23}9fmfLs{vQX z2B8VIj)(GGG>pj|8S9X<8dgV5;yQUf;JQGqE;q|sU2aBtz3eW&n}MIPAF4IGr#=II zLEJigN!*%$^Cj>uY>HZkyRj*1P3^mZck*xD8Tcs{1`mf%fRl*bCHQG@H=VFm#6GlU z7s_5n>_R!I0=v)_l(mhU@(x<=Y592=Z+mDu7I+xYJsq3m=GcO6Lg}XY7;=tH8`9!<_MX{r1PJF}L;%Hfl+QRYc;BTBW_;rVEr-wj8nqtbif-LN4!8|4jv8)7fj zB5Z&?#ZviWEGj-`H`dtvet55@>3=^gLCHtJkJxWDI)4z}2fiQ1U?(y*zZb?6j!NUR zn(Xo9y%#3rBhwLS0v0Dnrp5CT`NOan;RE2}we$zvKM`w{BhsSz@H7K>L^>Qek$4eo zS!S^BW(F1j3u1FHBQ2DVLnFCRUXb{lbVVA(9v!uo!}3DJ!}G9wDp0+r)+a*sw9mxj z)9Jv|(N{hjpFv~!Ea5Ndx%e!4%jXDZrl;cxXb+!`>Vco8{xj^u9Fb2>Pm%L9X|=&m zMfJd1` zLR8!S0@s(NC*sh&Kz<@FfX&Gh)PIuwqC@h~{5bhfVB_;byd=FCwQ+cn)WzvBN*~8^ z~dw+@4g=v0v4n2m=$OY)wwJfUOzt^wefs7YRmaBrH`QSd^w(siFq6=0l)fHcBlRHp55))L4te{W$cy2P_&N+% zCjNhzd&_9Yb*x)7yJE{qu_Px>ak3LbF*7qWGcz+YGcz+YGcz+YGo50(Q+xLrr~8iA zc z-uA$z_%Cf7*RhC~5h}{drw|`SJdBXfUcLmrjCc`2kRzX3e2jm~$Y&{E0OdcfG~~#q z9Ob`sZXyL9r6$^ZX)53hXpZuEP2<=e#N8}K(-mTyu1`z_n@UCQ$9+w%SC@?FaEjmh#o$?{#w@{P%Hf$|OB^1aEifpNj|{qAvb zUp@nJ{(kGXe2embzSlb@j&B;|#dOIxCjZax;g#=CP63O4WAZ=m;Z<-B$?ImtWh3=J zy@$7C)DtmbS4p&5DHkSIp#1&46wC#bZ&@yl+!#O`+js^ETpFne+y|BCtGweG1L%Ou zATItzgj@w!23!_(Ob$$rt#Zg!fhmzE@1H92PBOSWatW{;xIFfj1EvC30G0>JbF>1E zN-AJ^Y*oZI1y%r8M1BQe8gM1#dVm$dm2f1}0OhYJm5{3Fs*HUxftA3OkzdJ$=k$=O zg4|fZ^w^Sj)?(s5lk6q(Ilfpx`HMU2RTX!wWS^*xcFzc` zhOO#IRl_|nIkU;TT5*Ayz%_85WWs&88py8+ix13#yqd5YxHBhb$Xdv$3Cs$X_w3^1 z4xgNLYa^!?uokvzLS6{%={{Z#RIs z!42{IS8m)rmA{S4yXbykUgR}$53#Fy2D7NI?vShgbRurjL$PEHpf?MI2n4-9M zR}87v$c+R>qQA&{bwO7f8XM8d6$gHNsseF=HizwaAxFWMElFWlO?LZWWhen?=bm$VOr#6jq=Hga_Q0XF8E}J zcLt#Bq1mH)Vs?~Gj&ufa4wTFa%nZ(n^4ZX~7J7Fsl(v9!UEN$LkqMXyTe(ppGcYrJ z@}PW9v}A6i^G1#EdEpsGIx9-&MQ&DLF68BdS8iZVaDI5@LEA*)C>6jFi3H{a7eI-; zXuUirRS=dBZQ?@d!Z_B+fI)C!lqmqr2QG|M5bcv69z|dU(Har(C<-ftW1Ix%NHMf^ z5@0fLF?b{c7KC>(SYcohY!yf8{J{L!Dh}^L82ci?C2?*g1SSTTMA^i^BH&WkR~(~S z1j?1cS?dQT1ed}7guvn`RR&fPSPENZQLZSkD7MPNuLMT22yl7y6CY5ns8Jqe{lHS- z3fNZ`BU1#*RYD)rfpS)=g#A8XS(K^-D-W!It;#4@8dw@zRp3<-V^0O_tBT&vfO58~ z3KapY1g?s*6)+B!16M=oau|Uk;8_FPRe^HmssYdVz^dSyC{qns1zZayt79CghO)I$ zE-p}xTD7rV17k^bl&S-(iBTj5%GQO|!bl-!y?Q7e2Ur_i4<)Jrt6{4?yy^gJfg50K zjR}kmZh-xuk%pL%!!ku0}3r1li9+z!1(d`7g8p zP>u=mJuULBNpjATZ%~r&QIhkKd|QrOiABx@|GY0lj_C6J%yKMC0+gfE-)s8GQC+Td zssQEN%jNi(2<O0L>1--=-%M~>5Sq&2Xe6qpowvOkzW6FpI`EiKoZ zmTOAOHK*k|)N-w9xfZotpIWX#E!U`)>sHIPspU09^y<~=k(RTYJc4o^Ub(upT=812 zzb03`mMdY)D-=%@$~iYCQgYR7dDSA@Qlgx@<+|FbqRs}n?zUWQTdu$@*LRkyaLbjs z<+^@yb#A$0cl7$*7LI`&yW|<^M4i(XKDk`wTfp$UHdvw@S7mRJC`V@5XC%roT=q1H za-27iDje183gKwU`9k(#xt6({L1a&sYnjWrM)rTXo_T(Z7IGBGk9LwXmmFE-TIO;t zljDnA%UsTh$*`Rpm=r9>tXyb;KorXPG>BBrs8KIR)Tk#>&dwq1%N{j)X8YHfr=X4G ziu&>#AV9gMl6>EnY|ZF*o@%Z@Ao>iIId0_3Gd2*2-iqEMOS}I|o-8f*%JR|C{?C2? z@2=(L(UDJKC&O_oh;#vO~o`EswDL?o=?U7e${R8IT(nM^+wt*{ccyc}}!N7RWr#!l2xccNNAo(F!kjf2)m3QU5wmq#KTb!@^>M=K2d z9Cb9ph%8&!j%sarKFOKhM$60N6UO;rW7~{6HYW1qofjLq^7xohN5(|WZREO8 zdpqhV$#YwNvzJH7j5>Ga9AY6QkCh3O-~JVtoR4%Si42HaGrL_J5v7jd)s&n;qR;5`Xi0g#%W*Hd2gtEb_6>PgNxqLs-c6Eso8&ku=O-4`i)4S2qwe4R zOpeLfur2Rn$#GluNjdk)D@WN^<-IO>RhcvDjFmlE&JptcFS3Wrxm8|Y%27a${qp@U zax9Ruu)OM&BZVA4qUUJ&F1G0LMP51KANf(|v>a>XEHB^nEXQ*>GRYBKj#zS>E`)Pc zj^6T{oE)i(AQc%ky2)`)j?u-i9R|vAQC{Ok&+-3$r|v&zHTkLJ+@(j=SY8*%s|5M! z|GtA4eeDo^B@sQhMc>Vfp3m~4-idG&<*|#N+vI$f7f1R3c|OaJPn9I99ip!iSkx!Z zkG7ICS@f*--{vzpcg4l0|MyufJ#vCkM<|G+BWE&s{UGNvc|{@5jQ@RBlk=H8a?!Jz zywdn*K9h6Ff1lN4ua3ZeGwO_$=cznL<@qnqciAWYp4;T?6+OerxlPV$DX=ZSHQ2y^ zX0_-!?C&cU*(-8Jjf1jP@GL>pxhBsld2Y#;lr0r~R(jD=vL)qtmLTdJm1n9vbED5c z*=o_(e~F^nCR^0G7=3k^II5+h&wY6nBHK`2dB~YX&N%szC+9mk56Y{Mq)}}XeHD@! z?Iqh#wp4Tvlh+^eOpQKwWedqWxANLVwoL}KjciYO4i}8-o$1kDg|IEpWZR|u*VrY;aXDhi5lvoy$X1ghn`|jLKFg6! zj$|ni^Z)+(Lmrubu0sC5Uw{046N1Uj0LXN?iqFOV(d z@xpO|uR`&{zr)`{-$K8`KSJMu-$H-FzrsI5KSIBd^BX7Cx6oHy*8ahs2=i;`3(y7r z8C8RyD2Z}19gbms34IR5FeAX6+ccHgH3U>1t-0ku?pTdUYb3TVZg(I*XgL{$oIbP>W z_;c9nd<}mI`yB(N{II{m3df(GTnU`N!XLv496wm)$aCo^>2-AHTlgz3*zo|Pm_ij$Oic;M99{v{Q$QKTGVz|DCHSBS_exuAEmdHuyybu3E z`Zr7LBtkl|^Dg`r_&)qDoWx1&ybb?kZ_rvlQRWv*>LfuK2tmtm~nVmod5 zH};ja0k-9B_;>aV=^yMn`+&V4?GJWbCyw*Mj_1U6ye8@Nmhcr0=MAL!_UGk;MEf8XW>}p7u(}d z=L`Hjz|Y_}b_|>cZxH3J{l?}Fb2{=4{4?ta`@||idw{zVtiQWBdkxj%uoA2}lw0sl zyd(d_I>G*8U+ph8bt=Q7zq>N5pSv^m|HV4PKC)u$4ZMrNinDL_SCsq))0}3|Y0jJR z7vbmODy%Z==dJ?l>;7(kvo+^Cj5tN%TZ|QDZ^1>`J8&1?nSTU+VDEt+*$38?2c4JU zrqF4|oAQ_87f44sL8l1H7iB-}?>2FMz*MIXBJ{<-B&)J2tSj%r-?Jtt*_1coAt%x) zjPga;Py2_hIzM5G(+wrwv2MI8xG~B!;f=Y=2|0~`jd>#;;kcY%w&J*fKfw)=(}*|Z zF`NkJxBbg@1KmyxU<~YQ!2j64?FRg}-H_Mkx9mT5edILYx9wX<-G!hUX_v0sAEAa&N>iMkeMJF)*ATY={%#^N8{ zwRf|EtN_~$pMt<$;MMp?_$d6xc?@_p zqK(17ttTMjd%f@Q5wusUWSQFfZ zb!I)?U0^-j7ZCM{eZf8tJ_)Z=_ExBEV|x(409%S@VkY3f+Y=CP4dRb-cZGKkp!~;a z8z{GB7wyOPBl{v$9s@6cPoPh{2EK;k3G|dV_Fm`}V0&49mJe6}yoFWcJ^2>I+RD~K zdlc3W8-;)CFTwvICITlS>Jt1bqMf@N>&m(V<^N>6$&|Y_;w$d*dJpZE&}qe5vYg-*8auV*)qd&jQVXK(M525xJKg

o99M7Y;N&`z=NpK3stT{_Cno^ z|BJ7%kJ?AM|%Vx0l(+!4B(#2o5Yc`x&JkAzUJ^E5whoBP;~{Fc0xX>?litcuj!G!D*O$ zUMLMq4PFYJW%g4jKU1HoTk+3(oArgN&1!*dq#X7}eXXu{zk#iDuR$FT+G}73>=+^f zv3?-#Po9!DVU1Zzo&p?+h#~$~U58%xR(%7uSZ(N8Fq^G~_W^sYz2DvkJOF-zxKGt5 z>LmA8_Y%}+sl5a}`#3O$>x7+_&B3a`X;JGr?(c~8155nIK-^Tk5o^d&@y4tXFeNyM zxRE@_7qdky9h)tm$YN>1k5&0h-eYwNp1pgFC{I+A)j^F+n8nti7W?dPQ2x#p;f8W* zo{BeQ0q6vIfG=T-kzUG{u=Oan*IsY01E*&*v9fS_HVaRGrAM?`?nkP8ChrlVJXXWd zH`!Nce&cC)16H4Q51{!_ zjYNqMO9F+YJPBXUma$Fn-feG!?XnXiCkao?SFq)5GxB!Xn_)ZcM0_P%!4e@qG2epi z9rhON*=Z+4ej=WbuVO3NR^;ulx7w>%LcSHL?MQFORsw7#kFq_Cswx zs>PvJf=@>DDQp;OG~XTun`cjBQ`tRrFlsx*4htew5r!54hQL86M*=dPxT8T_f#)|dm`0Koyf96bs}sM8wkxo z_6#(KWo3A2a56*;h-4xb*g_2y zpn_gw2@_ibQG>VYK-A)$+5^#hsx#Rg^)_$@cmR6z5_-6z;tjC)S)OZi}*=dS)PO?1}0@mSW@wf#}Y|Vhh)I#{28}Vi@2`th}c8z zu3iR@g5E597Msa#tFvIY)bY#<)$z;+9*@)nRv7w4cwx@KlYK3_r&cTJa04IiK5|LQE z;LrISHk;j4=dc^L0)hT0XH-PAFNHq#yhn_*YriC98bftLptghC-c7E#8rvCIG` zf=*(QNWA1P_*j&lZjXiE40|q{!>+3ZP`)59z;$pJD0fx6sMo+<5bv5=ktbk&R*@%U z34j&AW3X)i4X7uCW+IVLyy7qUIOtBZ$3c6#J&(fHDTk`-LIi@;7`U_Dr^Y;vIj>eaJCH2bAfk zc2F0x1uPGA^71?wd;GwOD47SNkHPz~g{*_x57u67hrHapojnoU-p;WwN1P$*HJ(PK7T0)Mkp`F=k#6%_h8Ts(lr2v!#g z_3XNKe{chM4^|t%2B|fbk?IKG2dB`51J`Z8T z*%c^X<#*BhV^lpD$(!($k`guR#fHI{{E24?2hSv94F+FY#$7cGD$2-bQCq4l)T=Bj&%&=l;TpRLwM+aWk0;`amhkLsw}f{W z`zic}u&1!WtO~rUVm0PgYD@JB%f_?vD=a(D2FwbT3p~DvCoVwYB5!4PvOC(XpwbE0 z5_}mYudvGSt%4PcTdS?q^C*9TpXW@(7nfKLo}FJpnaiv-JUZIvkbj<^<6JON3FYPU ztZmfR>RB!X7iYOH1dxk!yp7!&<=enI*cVw&o`YY6+9lQ&c^&Mwu=e&Dlt0Tauv|PR zFege}VD0T(NVmn_^S}%2JS&CL1DqOmbvq?}iqD&p4q^j=gV`XK0y!yZ3i=GkVxTj? zscsL1RkN4kDYd4`Qe_Fas3;;H@uK1(e*k>MAM!!YK&P7BADRQ4{!UH1hP@civo*td zH!Z-6ky?TkR+d6x8LWwt9Qr9}a{8P-W2tCLI*=6;Ma2VN7-~gCVeyzhLi!1R%=^bl`OHLOd?qaOw(nM(tTm~)#wZfvf zD26D-VfT4oX!djZI<@Uu_7G>VQx#a%u41R5scC<<0)CCL)=OhN#cI=+>;`yfhRr;k&|u5DXT zv#CXov6pNCbQUUUX&OXK3+o5$$J(m}pjJ>65Qq3vUQ(10_keeC9a<8pyL>*p7GMRG z;^1M1bN8NsqH*%tRE6=7&xJkzX9M!)gGp zG&{vcqBiC2kNTao zx#5*ZXJa+qGT<@JXzU#WD`V#r zC;17UQ=H-_fhTw_k&K>YXIL_*1?X63j8n!Q3oC6WrRUgLmXw}n=YVHXA_u&3iX8Zq zr+5`sJK?*tW{jAum+Wa zHH#Vn2jRLfwkx~HCgiVR*+m_vr_;mvfOXW?DRrGXNY{0`JKcaiz-hFMG_96K%S1EM zG+JhwiGFl{aIaH7!qzGi`2=20Oyp%n8DKe4R@8%EH>Wl<>p1VB`N5qUUTL&+T3RTj z)7q$&lyq7KoC)c$oq_)4{)jcq|AMVi#zSEOAJ5B+a$*vn$jgZO(CX^ccj|#_IlZ7- z%jpfSg;Z_llY5P_TKR+(^VTTu5bM4BoqL0_UP*V=*agheMVbO7^scq zV|Y4IQ8a=^XQvUYlan02DYWF8m+CaR=A&MkNz15}S2DrMVZFd{${Y7<_js(f^x8cE zt1Zd3+Z5Mmo?fIAqoFp2H-=Itr?Jz~=>Y5m&a7q9$|;$(vN*3ZBUKhF4o-l-TnSEb zje_rJK8j}$>4k%c$+af%>)WsnwFJ~phx5!LlNgTjBY1O^YwI+3nt_KQe>fk;vxv;%8GN6+ z!zgcRVJ#s|fS=$J(S)=GO1E)Zz@x1bLQYs4it@wwP@Yv}5s_MAnutasKcuxpxzK2#@W`CWi2ABC80ZWTY0(RPPdP;b*X(eGUu7pdbaFWTm0wu-us?hT zU^P~`Zs8zhAb6aZ$!G9!Vl22g^hzp;*AKg8;M6T#$g=RLV zukr_L1NKG4epuOWFnU~3C>QfgfZudJ0XB`7L4+B~NHLes;Ul3uN@Rg=RwoPkS#>8b z6w3qifcrqLFIH;2g;fNHLQioO@%XizS`la#^%U_W(EM6iXiZnjddh$&qPN9$O%&7k zR6bEm0FMy8_*~#zM9K%+dcvz0P_D04(340@s1@`i z))D~|LS-oQhl!!0FYm*LihjH=F9@a5P63oD=;;Bko>&+29@hKn5w+ge5R@4z@_UkK ziM9MFQ^3<5`8||EPAR9PQwW}=fCa&WQF4eFEc)|)e6Se6`}1xnDcACR;J)w9=Siw1 z(eincX-R=epj8-tC7nSiIam}ys)SR-DGbhwGWk3Mkv~Wb6a)DHp2ri=l4*H7K`j7G zrsee%Md{*BQFxSa2A~W|V`dw~2Z%v@Anz~aKRfy(XMo5JuRNZM)&(nra}k!_nL;ai zrqU_2lBc349*IjvDe+(F;$#L`3u&0E2ERaxny0m(gV{w>72>% zokAzm%AQJ|$+U{6vS%8d3e{<}g6Elg8d4RIe&&Aaj!#A^Bb4|g9yku7#3gaaXskgQ zhm64*hTHg7K2>bvQ^aK8R53+tMjf{B&3uNKE-qV_taQ$0SX$>C>TupVXJv9SBAwaE zg2=u>xW=)@t6jKIo@jKl{sG8|{oB-Cm$-Oji1$zl_qDP{m?K>aLy&sj6*bokDI zJ#lk*E3PZnWhlN!MB4qLUR+pYNc^f zJ6EkM;4@G@Yn`#OIGLT9^ojeidnTO$7KB580(2(Q2{eJcZLnU)IGV+i*)tAN#?y7sSGem;|C2M(4(L=1|y+lu753!Elv~HmMO;~bg49(`r>KOyyv6R3|BZNe)c#raH z`7P_FmE5@na~zelSK28m>40@~Rg@uQG|leG<{1rzF?2QWEqaO7@LI!fTaIHpx2;>? zQ8b4qyJr;5>B#}ij?xMgRI-Zq5xvDK-dFSi_J-#j>$YV(cPz^>fwp5gBjGiQu0)wt z{H}G!GMyDjujDIuKhal=pt(FbJtI(NBwdc26?{2*TR$-z`6K9Xn%k4hv&K4Uov<?zTYhlN&4Pr0fC^m?Fd@tW1_VaywHGJ1t>#+Yg@VIr% z>O{L??cYvx4!9E(=Fm=1nM*T4+aQ@>K9Zg!K$P?(Avir!8Ay9X>_FSo`QY_X-XJ!K zJ$yIcgot~98^P-l;h41^cGOyBokHYQ)@kr6q*hy*i5KTdW~h5fX2kK4bkI*v+R+72 zZATY^+acAScBWmGE=p(AtE;jZadz`{h`3&?69@Qy-WDa>(UnkMWomUN|EpbS(xD{W{$#BT#@OIM(Gp0-xNR$5s}7NWV-uue*A+8-LNVQpw?@=g7!rY7IjZ@{l=8j=kv#FdR?1#dzv4q2Kbf3tPaIsiNbP6dV3Bs;u`t2^z8)uFr7PIzlTciIiy3K3h= zR&)S(6?9gMl;nr{T}=tERHO&(peVrZ;4RQQV6~(JQMM(l6dl^xCKhKq%G(ma0>EM{h_8Hzto?=A5dQ*7V|}X1-w>@W!QgFB+HY-x?X#An{0h+w`ORrFIt08OxqGec*uT$mppcv_6HEAFzDz9TOMr{{ za?uneo6)9pD0m0T?zMKn_E<|%W|?S0hha|>^rT_Hp(wWm`AfwTv5YU}jgjAkE*8uA zGQJo&OT-9kskOu!X^n`&#nvLEmspFf6G|?Ulbld;lU(Gaaze>TW@x=>FFI43p-JpT zd(swSm)I#ud>RpQkkhd2!0b2^ zjv?-Gtks@}qC3fX}ht5WPH)$sJAX+n6bI}@+wgX#%#~{u^YYc3G zH5BLga^P}AItsO8SQkDo$wSUy#dG4Cs@0->=~QS=)8;@i2AQMH1~-LrGtpG+1-F6f zcHnlgO^k)=0&6U6zBL5OL#-o95|Wr4f#y-HL7$l9C1;_ly3S&~b>f-={i)hqXvZLP zVG*P)dRSanTj*^QZDCtQ6EO>Mn!uWhanPP`jf2gz&M9XV)pZ#9N0iB0ZCZ;?hT0Tu zo)$q|WFAx_NMram5sk%c@OW#kHOCqc&$+;H;7M8?TANOS?__Ph_DB7#&PNCR1Dppw z1m(kW6@8L~G=f57(MZezPk{FvYXWSxH4zGvw24|>T8B>5>e0G%0hE5LSYsdl2bE+b zDLJSFNHWq;%!PMDF%R4jsYYTVG@t;RWgS47gUSRbOw<~nOhYjVduCaaU^A`pT76oN zj@KH{`oMa0g0>&!4=DSUAPJEDN+b!A`tWKX>Wlf{$?%(L?L+>4Wt`TKHlX9+3s3B= zFY1W};IYUbr`1Keo~SDpg2!l$XhS*%`D3*@$f+yph(+MhT4UOXj>g_GT5aUi5w*o) za8ql5)!%Aj4ForVHMMroh1yQKgD%n*YCTC0a!Kh4yQn1cb`%{%LSQ0qLT@M0Q8a^R zKdTvh`df{m(8St>Blla~MR!7D7io0O}-D@r$# z)Z1RP6G^>Ez=pT0=mP8_{N9$(?rk-Iazo${@Ls5!WG~$V-a-dyOSLVCvX%BFeTeGn z0?n?(=dC2V3LkU~Z!&K?^r&Rsw&-8Uyh*Xu3W~j~R#r>!K5CLM*+=(+H`Bq|AZ;@= zx6sbe=|Vb_%~+|vGueW*==+hr(D!;Pi%P=lts*J|DbRP|q z{jd<(M2BdDwM|goOgllRGtuGe^|nFT9@YW6pN7Z*SR~m*;W9n6{pd(1vU6QN9CdPqyP-7VXInyvu@ltBY!aL4kYQ!>^mw9@f=b zhw|%bJCtcp;(Kd|>LNZ$GVfaCucK?}NNt3+mX6X!YVo`^MGX-TW#W6+p!bZ@)*yc^ zjq9x?YKpkn8_&BM`DLRog0P6#ySGW?0j$qsDY=8t@3%rwk^8 zh@lK31A#v9UhNP)NcU=cz@PQ7H{|`ShrD0(LQtt?6@pT2E5B72YWb~t;QUAxunrrO zF+LoI{t@G_G1Ho19W$m`JAp^Ra;4OP#19)lc58>}A-Wstd$fJp0UAm6X$R>6x=-5+ z-lt(3>zocIKIIdlf7UUiaJCBzku^0ZhkADRUcd!b*c$01U`g195xOaQ>@8I zPqn64$BkpgPT)?=@yCrFnC16tdzC%Per=z!S0Y$fhLFKTM?|l(OFKdj(_N_HZcVNv zJAfpB^(Wu-uX?2Sn;!HAfRWyy_b=V@nn2V0NiTxx8k}+6CNW?FJqP??jYc+D`2#JwgSd%Qa<(k|E@PwqM(WHER7xv?{;mQwuCOG@uAPKdUO-gm>kx2 zDLa+J+9B{^ZKtwBc?X^MdI@+}vG&4upRw2IfIha@=xTKVwntx!r!*x^NIaz(X$ovY z;wxLByiMDxEu~B75$&+HLwT!fUgCWVwRd_+XjQgKS|z}HjE+_ZUZ}m4i^=jTy@ThE+f>p9Mqs$gwnh@&(o z%}5-j1!)d!M&c^3q3}k3t$V!GTN?fqt)9@FdbZbbej zZKJl5uAndVSl*c4mwIe(EMQFUD}4j=nL$9sjo+RgZ3Qh7y5HO zjyJYAEQb)8=Q2wotg8Co*Hk9ws+w{10Oq-49bI3e07d4tkl48aB zc}OKyhU*btmv=a7H9`*}PBtrOWwo*Zvw>%kNF}Jug70jS7;%$W^P!PM>4zHj_YL+9 zLY)W0P8;`WThfNy$Ee&Ecn^FFac|RG^n`X?8;v^s(nq6Szx82y3~z*YnC|w*07fA8 z5Gb8ChQLk%@8bLW5Z@`|u9XN869aRD6QRH6w)*-m8W)Vdh~Cc^i8^MnB4L@W1*lVE zWdTWy9<+eW$JS8j57TcV`Yn2sp43igV-WwBJ_hzve?afkHe@C~-7KJ7<9#L`Lk%f? zeCv#hMju4!>l^AD;xnD0u&@(CoXl22)FF{I10`pYu~7P{kA?lvAJW#O6?q87*1!kg zA&5RyAEMs_57F;~Z_s7hN$mz|a+5A33kY@f_N_P88NCs)k8hYSj5~wF5HswAtq@{` zVVSH&WFbmkhwlw~oi5jwY1iorZMpV{KBTS4U?>mKr;`Z9rA$YyW{_UK4aRz-7nFPZ zOlV}XOe>?60hkGV4ZhduAb1Vd2k8&MgY<{sX;7F>rjZzU`^;n7lC&U?q23bs2;38z zy?i}=8;uP{Pv0hEqhUcWgEbJogY>J=yhg9mmD&pJ34Kgkkg3G2#89RZMR5aTDAR~- zStxJA(px>C(9<^sd#92CP#CBW&>w-XK;bIALRV=kweG&n#wMdXO7`$M@JnwwuyodC z?7c!S)79E4?J`}Xt=1+(X9}52R7FwxLuY{AUw;hl28HgvZoVzXW@8c|imFUPnaLzM zl+szrVQH;PP`FGl(Y4wdtslJl>;3d6;ETw)MEfG$Pw%Tg1@}RZe+GPt?LJ67)i2O> z+FI=bU9YVJuGKEm-YC;YKaZRXv`naiRo*HaDsPnomI0RymBaY;!}MCZ^~3a8Uh6yX zhxy$!ET1*UKgu`KH^)EHH`o7!JflzP6Y`usqi>X@CANYzeS-88wEkn%{0Uiy+D*_`>yuI6)vz`CFVsm`zfe2fDj(Wq>@>=U%7JI0 zCbRvs{9}D%d|y%jZ{}CiZyDBCGlAu|O36ki4WX=t_MmYP1rzO5cFmj03I*R}Aeiwi^{ummNllP%5je zRRT3E87dJ!b1kBjHQ(0yTL_XaBjODIbbo7KE8imjLVq!55v(P!C4O6c zj(WaOo-4!2Fmj(9r^o1ha)KTQ9z*QEl#i&}EAo<1WjUg+&?BH4-->|6vnq$S8C#9Y zp-SLlh+8~VER@DdZB0Y0>HcZ{Hon%rXHb5wJX1!H;p8=W1)bMK!y7kVBc&<#5bHi! z2Ib}YGQA79N@%OG#i$ah3@!?_Vxgj;ly@rLkflemr12E3Wkv%FmRi z%1APTOhv?L{;B@9zBax$7)d6PH;74;yNGg++$AUJ33`{Dq9^H6#9F2=)w_b-P>O50 zVR5V?h*C6EB$U!hVNHR~RR0uzJ6~Jh6X-uxo+zWpNb*D(O-7MB_ zG*~rM1z0UqHS`4dG09+5;yd_puzILk=rNR^1fK=B7~Oo&f>lCWjAy~8;Ag>Z zzOKH@h;_xhX1+7u0^ftLA?kZGGh$^iG8@bN%lz4lrT!(rtl;v9TR|(Yy(jO8t_tWO)Y}dB|cj()J+w||^lKB@RUot;|FClf= ze2zMH^*x7m@m)tP-kOh4|Hr{c!5X3Jp-iYrW+Ria!oS>~-B{vZ49o_utX0w`k;<@% zBtGIYHNN^?`KH8Ie<FC*rIO+{sezT z4Zn#O!RNs)zK6k@p&Frwi2f*e5%s)e-awt+0I!3~Y9Gl5QdT=hJ_0|Ga#}`XrGJG# zBWjq*@Tp$)FU1F=u6U?Pd^Lx$*uTi1!^jTKVJz~ucB*I-$plhGs|@~vxL?H=u~Xln z{}#W*Cj9}TKMXzyW((B}y$rrUeO?AT`#J%;_&WP8pgtGP3m8*BnKx0RH^4XMYtvBW zGuDRc1IJabDL<6Bh#pVPY2+|kJ2_#koD9Zr|1f_B)Hb7$!5HRW=`Vv%QC6#}O(5e* zRjms6vzV?=(?5%8`cB|Z{fqd6I&IYdh~MB>!I!~KzWc%Kp=_c1sNsX)EyR9h-a;*2 zo4JgfMk^d&8rIQw+k9!hFmEH$OW-Z=yun zCANA~xdFV6NTsw3*T_hKP=TVR9+BhH1${ral8WUH>HB1YZX` z`rg1g`0gOi3-fL;XDCPLZZKCUCol)%r8P$SNBGksVmhOSHkOPbHK00{lth$LS}a75 zt$u{&U*e;frO(vw!1r$OF0`JTcg;KCG{z|ZNPimWq%}&wtE5&!yF@OMnCdO%rV>-V zt=t0MRAQ+gpzu-L4(1N!3f+dzo!~vFJTvb>>A6`PUL~~R+GTQyq=sf1BegNwKgyrl z7~>!9_dqA6`d-Y|XX)>u^FiE#&h6l>V4hI!(5+zJP@d3zXgxLWL+_bc3_8WNV%imQ znNanPa$BKL@Tl*^9DTO_4m$5eDk!Hm9>C{``2c=T&707<6?`k^>T~qBDEUql)vl5& zq$qTXX%A8AiTM!r*es%5BUecg>@BL@2tLLbcmuvSgExZtLV1yXh%#@)JbkYI25N6b zVU#bT71pkkYvi?=Vxf*pLv0!P8e0v&vl{Oh5=!SwqKUtYuS%VXpQ<~8ydUc~bGyuSQKKBF3` zN)oBnUf{KM|PdpWr_cI1XM5uXW~H^E`M9>T(iz(mY`vL>&$V4hB93KLig3&ILaP z1>)*H;VWnqFcSI_AZ|imX}gr2(3i_74a{xiGAg20l}JUBOiilRAk|3%pdX_|4W#_) z6V&E`@&xsIsNB`+qK5BsCi0cS|F#qP5`sBuE_~b< zFbWzqNezNkzqKdY1LY~~zH$fkxvSmLa)ED(8(947ChU*6ARdcHKuy00d;~rf80R1B zKNUC$-jBK+2y8>Wj+@)eW9Cudad0iD$8^;qHNngmGy-@8CV+=So@w`$d&)EIDY!gp zSb>x$zm%WKZ7nw<-`4VgZzFX_JCC>*#Oc7Pz*zrws2(-r`y!2?5g%&Iw-0gm2lfRn z1kVS{L7_Y;M}8~6l;_$#pFG{#MG7 zn}~HwyQ$>`pB2v#?JVq^*a__;=1$mQa}SjF2I4{|p05mi%aStq>Fd%I^&92wV#yf>sEAS1>LX0v3e-36wu6E+glPHr8BWE;q*j$C`U1&j!u}j;QrW zU2;@CqDrhw>W~cnfG?SEPvp74*}$I2^MP}~vw^*l8U4w8Nqrgp8Ne6xd*ZIRpx+nw zgxm81Rn&*0w|xi|7mU>|G@ z(qsIojD3-*jFiSP^{85h>_*%@k(vA%{Yia?)%v6!IjlAy^?~)s5moWL)Lv+K=@eM; z+`&AgcwT6CluP+yM1U{rTBn`+R)cmlzEAm3%d|($o*Y3#6`X&9gIHx}l_ks7td3^$E zv&5W$dM!0aqCTU5tHC?rwJUOGfKqKlmV&521T3cO3gX=oSMzBh+pvI+ zVH^9PykFg?79jb_KD8hzKvMZ*_#%9%5GA!gmEY});oF8-+atF{ZV0Ro{Dl55`jei~ zPHR8uS?!GG@lcOjJ*6KI`^70lJgrYbw1wsr*aGuNq-DhR9f>>)P6@SC{;km27P&QY zV_-vIYviWD#=u_0-KYM5+E4m}p3}~1F+Cn=#)QRCPwEH70dZ14Bn|=(AjVYa&Nrtb z!UA&(6t+fgiQF966xgE{A_d7FsO?o#AXZ9$3cuoW`%?H-pW^!tV;Wy8m zZq7C50Ox@>q5S5^O_5syn*+O`uv`5~FKFkruTc0#9rz~qJAUF*eaG}8;;=Xdo#Xlp zc+W96!fR9H#>lOKErFx@QE@~Z)sKmzz#}O41v+2p7kW{H_tgx==ldVtKl1u{<$>UBCtOTl!7Cpk4sj${b`4G+RM^5U?e< zxj7V3n!{R{vk_}faCY!`85qXInfOk139HgNs=G+DWK=qZ-Wb=UN?a^ z^y|Qz;LfOj7p=1v#}nJrS&Qq5<7thW4m9Tn=LKW?=EGw7nwi5;>t?X#<}B29c5qhk zMC9?vS;3Q$Cn8^=KCgZ6QIG8Y_oz`0|6R+v4-RL{s8%$1M5A$eIIa6Xoob;S(b0!6|% zky!*N8ZI3!g-J>Sm&3g=Yk7a~Krd)ZT=Pb{ErC|NRTY%G6{hf zK|5lyL2gG(H`rZ{X%x?L%p!aG1bPR``}+Xp{BLo!OBH;JiSn?wBvp_Hx?qy7;AcT2 z^n|2hDcKW}k`)0L!SwT_4LHAfzEykS&zs=l7^*b4~fmvumW%^815hF7bxTJ50v(IL~f@* z$H2?ri(tpVtKiFES0wavr@?JHe}JxsWR|oAezSntQU}y@4CD_VfK&ePL1=!g3WU3% zr?1=1?FyZW-f4U)Un|y#nbKBt&y==7XJR!=x=%Q>*?l-aAngOMgRg?^18;(_!LNcH z0{P&XKRg5VGo|0**vI`Hu6^CS*v}Wv8$JZRM+D>S9(?YT-_YAWFa=pt`4qlRtQFnS z)7$NizCP|`>`dX4`FgQVOy(QJdeIK`zXjR_-UiV18y5A<2H4hxMkdC&^*#=X_ZtO>oRU>w>fl|vz+gCb~!8f zaxO`}atlLLEc>1D$}<{#?>p zPRZ{!VpuoUDd(6=xWFxhF*hX@Na47Pbd?F!CE=N>M{(-0w1)2&I zrVf`wPGfhkv&Tux_5yMCTWD}#P~bPXwGVX;bqei~Is?0E>n@|gsY6^dw)59B@3koJM(#GJXLk~ptYZb|o7Xi2vPG-bFl@>2q-!W^@f z1KZH;@Z90-bK)$<_Bnf@B~V||E$^1YoaKQ=ZoANsz~Df;P?NwA@L!4I#F)$WW6~I_fVmpE72Jky18^hgHfJOs!MEXDwmaLL z5qvezj>H^NTg==pR6tVj4v+$vbh%VO8id!(7QjmJ7!f`4mKXpJ7!e*Q6fz=(LL-C4 zaSxPmi{pCS!tEOB651*GBbUin;>T=(h(B_LTqemeZHlmi$;yBQbSq}q=2XN)4cv-A zefNOlvM4*??1#3&ByB@&LQMlr0&POg0!;(mLOZ1GQa8Bo0C$CElg47|Y(RENLJEG! z5V=aOkVrTa(jq|ea3y%xcegmB_(;A5iCdk6&H*RN4mu7K;3#ugYxuVb{T|wmYryZJ zZcrA^3=alG!ajIPk*v}O~d=%g8jNzlfqu_f8u7Xu|D`IlTLN#L0@VuiE8)dEO(gENkgnWz z+^fQ`w)<#}R8ITxmikfDjrlB^0 z)`5|pdG1_ylxMa(3p~r62cGAS^o;P#b?3Mv@Exvm-O-+&?riXE92Lx*{W zL(hAQNQEUO&?D46w3sGFl0_ENa3nFZ2)vj&ZXvgz>$ruXjw_(m#bG>Fs*5AeVQ@8Q z%W&FoJlryz4tfr5=e_5=MWrH=9OxP95t8Ao1X`gY7H);Ac$m9I;KSXbP>z*wqwp^1 zRuxB`BTiK~RueUZz~5Ch#34K;Yl!O5g_vg%T}Z7+II@H;rpY3$;TH>s0=+^#Lm_0z z0X3lD(WwSzNYf=1t8L(I(hTV=<~ip*>n$b~#k#muO!}Xxy7+*^0CzRIugn&KY0OKM`ed&G8&;S6kmyDp|L0FFX6Ofg-m zB91vnohstEa}0bGXSINmh!t6Y`4`fqbP48P3M54S^#0FVNIHY5&U%A^-l1NhAkHWh z_!U#N2)Dr*y5QE(U*J|nq(QFj#*kJ3T)@rm&Zjg&BJ<(DfG&e~LSz{=BL+AjVn%9- zn&K|0CGL>h;Jf4wX&%l1@8-a-;Xt5IsCOt3s1xb~?v3oz-V#!A=``j!Z#0Sr z2Bt`pB{N_^PkOmzgKg=QS3Vzi2d7@{Mrxw$!7O4x|By;Eo_MXi_;#``}O^d{IZXP!`I4?9IFd0{-gn$XHD3&=(or;*Vl4ydd znueQ%WoVPI0zKgs5|>V3o|9f5W{?8DK)q1i&}2_FT(2g3s^iKv8S_l?48*q@ZxRDN z8^s3jCb3ae5X+rqP6hZ^6zP$i+nr56vJY%FW}8FniMrw@sR!I3UU>TO747vy^+L%4 z34uw{ajzo@a8z=@0uwaGJWaxl!zy$Z{lq@9S#X<8%ZnAxa;H49Du@io$mM2m(?c7D zHPki&8i$j@*&9e2Xb`F&ItI_<-YK4}ZgqDG=AVr3UY^7!@&TR=ViI^DbSjQc!MBcQ zbF;erJri)X?eCe$C-DBBb2jEsleAL?)PHUVp=q)SC zh}F(2Co}r8yY<5cs_Fv`!ax0uLY}}+f8$W2kl~5qUm=F44F1<Qn8c!nCDc6gQ=c#ZsjpPv3(xEfhdY70 zggb-3hSOMvXER>MVt9TgZVqR`G}+uN?ljMIPZq4Efiq+82j=EY8Hj>fvhOBJqgJ+#>PhZUkHynuFID^+XQdK-33k|4*fQ(q(Ub z;2&=zvWBjvjmT=+nEVo~91I73!N<`h1BU~Nfuivuapo3^r*M;lle>lEO-N(ZHUU=A zx^So`)s?PzFMI1sSG`xfRf50Z!<4H4lcXxaNm53sAz4e;(1v6kT?<}=qz2MI-b>yF zQhjJP-cU3U*?1$-5Zpjy=Q+72@{{G{^~4R5ljnfuXQVH`^4pzd;c*B8Wn2EZ@ z;zgmk(D9QsB~8dG+7wtx8z8G8DHu=brf>_!Q@JU@DKLFS^i~R1#DAu(Ktrj4bjjNg zxah4K%pj$gss=Mk8NgMbb#N|qrL34L8!rHdg7M;U>JqnjycjeKZ!8*#EI68#*G6R> zskU^@d(~T8+Tp$CtpNXu!3sedAb|?OcYYdZMw*h9v>C91=H@@xca|Fy{{ZKLRtr`Q zrkCoI^>iJrkI5U5Mp8rRqPG$7w>N)0wVTS#j~NQYOT>w5xg{_Q0b6d^t%t7qq#hYV z*VB4rEFD9eljU?|usLZ)R$x6c*aGVnbUDq;3yQ`fGbYFMxZbZ!))-g(rHPHDrFe%= zW2uq!x3@8H!CMPwQCq5xnbLu)LG$q3{5va;bEyz4AAIkB=P!v_!fst8)+2SvI69Wr zL{}}TrnJ+$!&_6@<=yGc%fGR&EH660f%8B!VTQ~+6E7qRicGw)C?v|kt$eUXFs&4q zY6R0sX~ET@rQ#*wUn-vHCIg4vM7IV!Yf2f>m5J9uVqKDte`Q}-KAsm^7Cz;IWrH95 z@BKC57ne%MOU0A98Bm{*XW&IdVUeHb<6l^9^wuG@$#^=BmO*{lV42`Y{|A4W;3xk_ ze=T&zq*}q6(CX4|?=Ek3r6gcz1iNp}xA5 zo);BGM0zA<;AP`w;t6h9z;x4LKRr*!i;1G5sTezx?3Xn)&Ip`BKXb!75v3tGFTkz62Ta1;=Dq< zJZdV$XLx3MD#SHhVJhIZ<`zRu@nEswcmFrPi^>>x`FvcVTwY3)6lvoX;xj!d;<@5E z<0;~~p~>TUpvi$0@eEFSry$P&6ySYWZ`PXh0a_7%uuiacFaXp7`=JGV&822iesBR_ ze&4TBb15bIbH*cZOCHbYWN-@bj6iz)`RB54EcTe zd@ZD3rGmZ!zGhOYc#e4Xcq+`41Dq1dFk1wi7n&C7>72AqVP1%5axyy8X;0Rcv>`n) zNiWuq^<^zcD0tX=$QwfDVXqG)$iYzXkhcfs z>B)MqcBC!w2J0i=3;2SCeNCk%Qej^qXddL|^~I1FcSt-x(g;A~X^@i*oGqR;K7ftI zI~4}7=A;F|#_zHClbX9~^cOs12- zQ|M&M<2HPFJWD(?I4jfxpCmy~Fh4YkEZ2!Tsd*~ijg=?mNH_TZ&a|K!-0#ilD=n3h za{9_hrNO17Ts{YtQO9x8@YEbnD|lvivN@AzSM+vcU0DTEo^)juNd=;#f1g(mYS5p7 z{K)$mD1gkLfr7yT!5qG_QW+@+oOAjdxMYeuaRC)@b{yf@JPrSW%AbKQaO=vlqdtc( zin@&PC~7msIckK%9nNje9l<&8jLI&oGpj@@lJDsK5%?Y`6f79b<|`+am9qKDOXa|2 zrR+ZYzk0`Z94@#Ezl?Dg$Pn+uDw9g26C66TZ|MCV_!cM}EEN0}C=x6j%nFBWz8LD# z$7ATo5KjXK+xd#4-vV*$ri;gMBz^n~cD@F_1d0ZW1XDXv44E30X`Ij4`4adXC>AUl zOy#&d%2VNJYA2O5-{WFE&okfiA(kwj5dRqa5KD+BqeIyce1zr@d;q5`aymI2S>$jO z5f7O`BNzk6LxF@6zT!SVIFR5^DCsNVdml@TCyT#_&xhD2xR~)zv5(LMI*bj)2apbD z!@xt~8>WNVAQp!IU~nQ-g@1NO6*Wk8q6!7KR56Lxz&bnrltUtylhX-d5?Q#RgrFI8 zF+(hrHWUvT!L)!5)`R=JX+!(GRU|2)l&_>u!c_i*U_v0FxK9(Rs7^k|%(xN%jOony zyI44$2u{SrQFywcXee1QA($>yMfycb2k$CUP~>)U;p5(NA=|>#gP4i4NT9xi(!NqY zA5x?Qw8B4>P|Q~pT-;a8_ZH6YVsB$sJRA?e0UyjH@;JF29TQX|y3n9sVn$q#e~EpD z8t^o!LH}UG@dB$sY#`WzI+!OKa`0ip$%5%am8D8j`p_>@WpFyE7c=-0ya{D|rG0Wj zQC|^o2>K>Q;#T|((%;5(`YZc`>2NlvPFt{F8Knc+0PtG8LM%gkA*_g91}Ip$wt)p-PgHASV>@DS&1r z#XR1GqzO@98Q-_q*O(Un2B>ij={nVDOV)x(@bn8wSWX!Kl_QSjn4${#g_xo$sRA~j zJoF~;I>3=ALK%@!QObz4N>UOyCrwC_;QFGz1YwF_$oJT{m>T~cQ{pmMjVo~#DH`>` zSrVB-6{PY~rcgzx0yrbohBL>@jAA|)U$g7_k|cOh=@VW-9pWT|V`YL5mWKX_eUHg; z1#T);Xe-u|We#Num6y_l-Ui+T(!j?K{WRmgnD3{V))xoI;FuIXUXfHVhdMuFKj82) z7K#VKay%55;iFKQwq~tZ>d?Eu+d%5j`@lQ!TR8rJ&rj2X+F(2h9FmG8BH}P76>3t4 zLg_a_Fu$AWd})0i)Fcrek=%jCJ;+KD55)c8AT)^j5Dn6{tPM*U`Ve>@ zNC~%8p>Jk-Upn76ID9vM^5l+3{NyQ|%HDMQ|PQtWsE zDgFaB=)utxq2!@YfscXYq0fO&f$zAMq;$UH=no#jPV&$qJ1i2#VtbLDD6U4I$F4=M zMqk99$KF^eX$tzrNn-%Pm5QbWr>3dEDKSSwEg`{7XoyJ~X-zaeK}%?YX>@R7=t0bL$bZCt81ozf zGK0%YS$#+RS$$c+nenJtYA>-nv86yq_HXoh^l5B?O@t*D*i;a(B^KJ3G5?k5<>>3! ztJr%hLK%H;C8rVaJLoIS^V({FNg8Smv}6eh2~9DJmT(lwS$qfl*+bbv2mCog*}>UD z2mLpY@g#O5`Y&`oQWn_D?4@=`w#@Fp+Jif?4(uOfU5uZS#$r9=#tAW-GNoqnfttoUrQV#f!AvLq_nExpBX7owyaqMRF2K1vv>BhiE>jU(o zwK4E#@CDpnS}&~cM1DSlcqBo<|1spJRXIAHeUC^bDTQt!LH`@|~wPpzNi z2YCv&XI5=E)X{2dZ_PJmZS9@;*4*t+3?&QghT9(hDgQ~hodVMP?nWQP?#J#%??9j6 ztH6JfCsq>bp-=)6qM_eh|GMy&HP~+=*>R%?|%G`y2nt zr=e!Lz0HpcRcM<(5@KK)+U}off9K!$RMbqfw_<;r-}D^8?|@DGZ07&J2NS>L!1uU? zbAiqOeiG!V5v~rd8Lk1Y6|M=c9j*ng6Rr)e8?FPc7p@CFir*yToB!}T5`2p$euiXv zl7$n(v&9;FwLJ?wTWpX175y`MUTvkd)V5*0J!&wWeX|Vq)%pVdW_`8J;plnwoZ4Dz zrJYmTXsxyU+8O_8e}3((|BSx?Zk_hegxf4JQ>?Yu*mDGakU{5&*vp3|z#{2p(gi}IKJa|#9?Wq%x(8F7 ziJnBtDfOgUPAjX0kRr2OaL%pe($@Od_={?v%}-`gBz!g(!pTebqVIHc3jC*vAiH7x zYX#92Vkgw{S~=|md`_x4(VI)lsjc&`^%v7VnIFw!T2bg^G2R|$Pe$()u`jw8KKp=E z(M4h*oEHH}X@K3dZdd_02ib9Wo=}gg6}0kN4!Gq6ulKL>=g>Cz*ZYfWAI%SDajh71 zKU_{m_rvd0bP`e~i%DXFJ>K@iEx`QjmUYwev)k4!>loaQtH;!eS_LgTd~$#{`ZxGJ zo{iBB_?pa3(T(8E(M{kj(aqq$qg%iP|LXO4-o!3peG!jGkLObKA~-dE-skb;$N#!L zp5pjDkjK-~Ee>8EU5BF^qU)m*G07w`QB1Ta*lV%3E_wj7o&fKMN|*{S%V&42+tyJ` zbxb{~R?;eJN7c$&B`q6f%dSm8FI>bV8y;e^J;`1JpS970@HhcJ9z6y=0rkO0Vn@(> zRLzRsY+6=rlYgUsJh~=`)#zFiJ%rk0(Ja`{s%6nO`#1SlVSjaW9BRgkabk)++0LwO z^>6WK#?dTVW^Idqvwtl1$BD6Gsy)SCiTYL1OsL7Mt-yL^G>qrF<>|whh{fVGVT`iV zSgsGb+x(*JXkBKmCy!jrJzHgCBP-L;#x0M_U66#Qn5tz<$d^K@M5tD zyhtRaeR)#+O>lj7#9v(4p}CU=9UpXhV@x zTpNVk!CF7wmp`)l0S~RSgfNSpC1;=~;CYgqAjw&Ttx&JRZw0VYT?@yH;5E>mn6MY` z$(MjAhQvm|R zXBn_uU9a}Tdo0%@;R4ndaI3!-MNWTUfc6K{s)4I%Rkfq&Jw^ud0Z17L+_Qd1N_W0g z-37m;z%sQTdi!hrG#A=Wi$O=AyDGSSUj(@z@-k1F6_w94Qr(5^Vzjd$fE#2;cXAH?rihv9RC z9424s7rI#84Zp?e9_V7MmZ*KSIGp-uX`y|v>Z^@{*AaCT{3>f*;M0{KLhoU6h7kua*_j_8Kj?RQ0QCpS0(Boc761#?o~Y@ibwo`k-jRSpjJ z=u7Q|Hb#31jMg5q2kdY1kX;~uf&V5K$QBt@>QwYjbEZ1O_)tE>xnud*3}?DC1na^0 zlbV6mV16I<57>Qnk^D^_v4`w0@*JKowCCDb=qtF70>6a5!s>{+QQoR<0dG+^$upf9 zj*ra*yzDW1gx<&OPx3$TU*u1+0hJr&4e~a1t2zZUOm(I>!}&12RoP`6^fjo>ZN zdq}^}?y*bcB6+5bL-I3iJoFh>&$ZXuVfB#u8rg@zub|uHt?~wSGTf#(lbt{Ka6ZeK z>3G>JCn-w;_OhgGy}VuBrmjc&2Kg?W@3Fh=A99J@Wn0KUka|#k zgPcR^Y$plxu-VQm=uuFHhtWT*htUV%JF(lbKdcAQJK*8i8)5xn-Hwd_ZpDUKN25og!%#omT7#6e z@)~)XI#r#3874XtoL0OgpXL7|uhi zRoGuGuaak|)71xBCwM#n9%|!|HQu=a|C?+ODhFF*tkIS)J_d+`k>R?4GMGsYS1 zwBv30U9BsQ+|{~4?_zaN8*h!XW_iW~vpxOcIl#Juqj$AYs2}Z&a(?6Oct7m-w>AJ2E@ffqRQops6{dAGb?S*Prl2hdmSB^yBdLmwEQw2#_D?doLz49J;t+G$v3*IBIQ~J@@>=o+=ul{r( z9Y9~Qf%FA?4t~jAuno$3ByIq9$&ZYExSBsQ9wO@z@B#cm+o#?)K5L(}`?ecZ_nfUk)>>twvO(D;Zv=MAeUaFY_N8ywYu1;(WpCI$INUex8DF%|+GAsZ zI$wQkJc2$p=BxA63}Ugf$jJcbj3PU{_mk{mAK44uPxg^b@ZKqJ0(QuK;MSK8rq6I? z8I0^_;6c#Um|=~wTG=n}lkXZ|wJ+LTWZg5K7>|v4YI-ryS?r`oN(PZ$3~~lKtCTtN zet8w@S1YTOx$+!&v$9Fq0p1~R2Zue0p3Ta3Iqd08|Ht04-pK7kd(%JJ|5y&Om+T=q zFzH@0gg#}Z0z)v-Q#OQ_3S11_F|KHrwL8XT?JM{z=6H%J=BZDCxoSEw*cs%c!wl&~ zPLV_GA-&+)o36wRtCW?>JbA9XMcJ$*dTtw6wJX|fxZN?H!DFua%$TFj2G3RJsJX;$ zvWw(G|88(jXj(X@6FuS9i}s{{u|HW)dV&4LR={(matm&^jpuNht;WR=XE1)rGZa$}(kvJYSB9q0SH|hOD@_0f(E0i=CKo#V}{6vlKPUl%>i- zd4arCStKu%e}_YN`a8YEF0y}7f5Z6K_*c8GMa6Jum=i^pE4tz6?{o?3mnzqd8yb$I z=3m1Re>lVO%c|k1yJpHOA2dH1Nk`BeMt0+sk;8b2 zdn5-|FAWX7IyZT4+@B^l;A-++>iK=O@|Vncc`{yoRc9*0{>^i+m!1Ut?EU0>93#flcTbd6%+N83UiO@Y!H$upGQ%4B(x zoao6-+R)ZCH=Og3+@v)fO*6wei&2EU$2%N~;8}PPd=c+;C_;wPA+!i749$b&WpW;1 zsT@M0%)>m9UtwY3GMge#hVw`yj*@f1KR3xm+R`>Olkq3KGXa^6yha{lshk&BB3tOb z%q-v^mXoxjZD~%_=ORI#Ttq|={vkd>o~6uGM!<8VoYD9TP8oqrMm{(#k@Fdgx`+2C2|55P0X13ZODE^;6%C&^%3fL{jVZ)gUrG8*~e zx=8l(lp+N_us4MW@Zs`YWsWi&K7YvB$#1kB%}(0W-@xr?4w4?d84QW15-EkmQ;SsK zl;|8L&r{|q!_Yfi&PF=W_B0#1vXgYiMRcSC(i=Y1OMECQhsjw{lZ~V`F5!4uAf4gG zQ6Km6G$OU|a$BSkapNBxj~kbvajeoBNwM$cG3?+)Cg2$O3e+$P;7q>AGvw*=SNY5T z^K^Nd>~|QaJmC19|Cn;ZYq1ifHmk)-k`hEmmtp8eL8xXFf@(%#sD_npNa*!Dk`v*K zOHOhg;XxoS@T~Mk?qBxtH8i{(!8H;GWQ*NK58Pig~fXxK=ELl{_~c;Jx4(VUL71J#^Pv?ExBzJt$u`JLPw`cCcx zt-@l&B~{>Am09pupjgIyWgd8eGG7V8Ib{44Uu=)_Q+&0**gwTL`>U z;GO&ni<21ng{38Na14$CBMrI(h7Ap16*P!3PZ=r`!-7^u)ddXkR#P$?Nc1AmDbU&T-Rhy7J}_)qW;`+OhxkFB;F!)4-hpN%NBCiGV6Ed`J%W|)gv{hd#0bGzHf?x$6&pyZ)TK>X z6IK`5^=JcHpEhDDe2Jl&3RJ~MNeq=aYLhA)NTM`ERU_8$Kd_WYPo<<({LlkPKgbX8 zWKM!}fG0Z19L-eCp|S=Hk?SC(F0DhGv8L=OKf<$;qdW`A49-fjkRWCYnfuXofTvIb z@JpfGlLKHs+-sw&4y{d_vt~>;HFJopn}g*+;34v0`4~USGZUeBlw=-(`8*2#vV%6F z4QWHxh&EvL!3|jh7BEv7$&CQAf~H~W<{;Ss2FeaP6Fhif2{bu!Qz(sTebzM8m^Om? z%};s?!;jv8={G;?pY-GW7!r>InaDo=TD%hbF!_GIkG~R$PA$w?o7SSmSW#As7G=%Z z34WYsA}4^1B&s+{f~O{q)}p34P#z$gm}Q_W!P##{l>72MIf5CID|_L*k0+R>IY3ST z`pY$FaaN4gKyOXTln3&CnV~+S_|PkvKJ$zISwG1$k__Y|KLOnXhrN6ce)u-?vp7@q%*06&fIc;mo)<^zFK;8VOJD~alu($7B2&+vYz?r+aU{XAo?Vd2+$#o$?7DW;@@{?9sZHK+dr zn$fdJKW8m4`pd861x7ObSuB8mGIN13AKDjg{p`N>IewP+wa@c&e2`s{RbYecfzYB# zdiWIuiYb3uO=%PQr`3!$1^*9P3e&hsDWxQI4rZ8Z%rS^*nR5($JdC-}cqPA-7a9wo zXE4KA>x|WswxE5G($^krS77DYV0#dBHtOdXrQsD-O2f|uNAVawjrudzX{!}&Nl#lP zX)F4d)r2+%{|POE*@`Mflnl^C#tZqmyvTSdzW^_U7RG)NrLYo&7FI&g-u4=Pp7%z2 zAA7N}$apSau>P_d(+fb;&;{$ezgX~s)fBIlFN6F9&k)R5o(%!Yu~SGtZOt;?8}E!+ z05xX;vyEQ%TE2$&f^%M;5^efVU?k!=?QqA zv`$#1X(_tYSYkYrmjX}a9&qSs_psOVb$qy88jtDWa4OA?qw9oK04W8P0*V5i4!0S` zbmJp*nX%M(DlY?`$ldJ?d_C_DhaUDZt1K-;kD>Rtm0wZOmtWDK`LQaXOfx>Adz$eX zIt{Do#!;&rElZE0>zMVsy^(L=zuTMmM(_qW=2LWZ=L7O9Q_(feIAWEj<>(P~9kue} zXg;MI>VLPV7+-LF3NY2^YH#M7cvpK1-wfWwyV;X*bc!+A_zInDe1mqu(XRF+tS1{2 z!IQw>p_$DU#&YmVV};Q}jIjT(vzVF9<;Eqsl2TFmN4_Ng#}$R3 z%ho?uchvU~Jw+Az3+*ZXu!q|{MGt6CG2E^~e-|U|5%%w>=`J3l{t10duUMC@XY?t( zWMws<$YCX`nFU!{fo0%j#uND>axcl3<$vS~%4MLuk_oeAHoL*?chOCZvPaszkogOJ z4wsA8bNUQ=1s&y;D?mBrZ#Z0(|CTE&m6S*Hs&&PBgxtq88?I-GN;WeqG^4r7SZQR0 zb0#ypnM_GgvYUxYGH^C%S25ZiWp@>=?a|;-b~n)*d6j8z(F=N2E{n(KRk<7eOz;r7kLW{s&AMv6z@!(!e_I#87p=do3`oytW-wP9tBfv4=_+zy ziUg$(aw^k4KqZ>q9AT_B(xWDW`GD@Uc32PS4(l5Dngw6^s+{0?iDzfA;7j@f`j?zZ z$*BB=87{~<;bkg0%^c9qqK)0!?u?W!qOYh(E6~2860HdC1N{?Sf60H!nUze+eWW~~ z>CBPF2qPWR)0@}jYe>munu?+1GIK&Z!L76CB-+|-?0)d8K>vr{KjnLLm$lQn2Z#GK zEgaIBY0Xi_NTZ`@XScOGqP~;pkLvQYzvu_;FUsRFeV6XGc7b=HGmiSSX51WYj56Zp z7-O`N+cfZa&u!{TUT`klIxlBYGJ~@!S-_c<|H(0PtTD!jp+0V&!~S{s4&7tzw(h|B zF6|(Gv)kDnFhfVtUbMG=v)f~*gSbuiT6?V9sJuhZ%Gs2x%2_$Pk`0_yIVZdDjG4cQ z4mLW_)n449`>egzEp*+cXHa=oj-tjjqvkkctl@y8relsb#u@EIN4taF4!yq#fgQZ0 z(VSq6H`-#qooFjM*&S_ePBbPM9Q(ptM&8l4bU9f@-qN?~8}*j_7Pu)N*YlXU&EtAr zGY|L}v^KBB2a4Lj08tZMi`V3X#6VGpAF&Qwb$EYq1Uvxuavfe9`WilO)Ys~5`Ih`n zeXHIC-;{62C-l5Z9_567T+eNu0P-qJF~c&ll)R_!=nBm72D}`4RL^JTHIE|un7)#% zAaCeO;5B^(&)4cJ^^Sa7ey_e$Z-8&e|H^fF9e&t4qUSgBnMd>jW`1x!^q!}@CSk`@cDCaa*UNwMJPz#?*y z{!JHQp2cJl`I~;EAJqg8@qENY_!}9?xs}sEE~P4*tMRJ5sc0e^@cR6KwGh3F$aD3e zd_aD#9+D4&4;qC06CS0e808NY6zG8;0DkI zR%8oP|?PBJQd|2KOp9A`SJ%yRv+^?rJQ<&%U?8+JW z9K3TV=YZ_WJoL^d^T-u?nLa_+Q*|FI_v`!gRAx%EGXGUH7nPCz3$Mgmh+jn|>{Q0O zrD!4MlB@Izor~Ui3|h>$`N@Ok?iCk1K6+CwQ0M z)oG0Tf@j5p0k(;3BnOak zkR3(FT5^;ffrgP{X<_Y$`dy7^O#1@K$UZiKYzA+J zZ!$O}YRRQ6O=mRuvA9!_`XU)llFc62&8MR{{h^;7amnd$_pV=6;$kNpl#d#4yL z%2R47(ACrFfv%pwb-EWR`&a@zlW7Uszv^{0LA#;;t7`g2bZh!1sD_oUGySA|LS{OJ z{^k_t#rSXVZ13!0lgLD}hfOAvz!S+{7SWH($K;59LOu>=&|XeY=Q`~LT%#uZ6Eqdh zn%>SS!He^DPDx$@TpW(Qoon)dWQ&aTK=u-eyPp(JwV{%*c zwsT~C3y#QuqVHl;$Yin$y}OyN-BNF=x^`Q=1-=QFHclyClD9!uTW2RKcd?ypDw#qw z)aY6WKC&Ltw?bPxrFkjd8ue|Q9c&tzN_L=fCsR?WX{vTdy{!gOi8op3+n}wSGQ2cz zg|604K;MqN01(t$I%Rno-V#S!IevWyj`;PRP(M}yUBcS0XNjCEqmVZa96R|2qAk|2qAl|6+B+xrJkWz`dQT z^cFCO+`{eN&O-Dq(iiHfpoLVf*;*kLzgPg$A<>)du`lUd}pGl$Fu-+~r|e<8IPyi;q% zfK*yWIAn@sL-$Fx0Fx}#7wD;>OZ7+ULv<-~9;x%Ovp}D(r-5FB^L6K%GXQ!A3A0E6 z)zO4j0L}%~;_yzT6$es+Q{u6`3{DT#WxxY91F|wkGDOa^b1XYDPl8Xf6D&vMINR#a z5y>9;Z+(ItXXztr*&6V9mLZZpvWA^!`BjhRX!(&&x^9>T=+|dKVMVBzH0UEOG@kSDky#OfrMqbM8X( zAtk?>PfenEw0vq(Es0hVY1A_p{`2$|`aSiox=bk9yPb>)4bY6R9(3x1x(p`AQB7dX)qVu=Y3>w9b8;M3Xv5hPzdUL5WP(M?jp?jehQ1iEQ z!D$Yij-46$Uszvo{&IeWPSbtZn}+9~5A4;a>r=6wrmwQ{M)E{fS@|M)Bde`dR-VXc zrL0;;9j%Ol?l;%ytM&cnKIl{Xk@L`bYCnNKwjVqH@gwJn{mg!dd+?e46#C45fP3

_OC(f64L%+wz=Ikl`h z64|4aF-mE*lsZN!qm~AbhOR*UN^6CcKawx97Ja$Fxg)tEBb4%LIduejM=E2{S4tfV zP|qHu?==sas-|cMk*{jcG4Brc9N5kt*-spt2hQcO{m_2uJaHak=aIb}{wu8IR)I+V z$U1ASl?$9Jk~8v$Qb8@R{(-C!$~fdu&p3d2b|Ynvx!YW?uhS2ivKG<~nTjTZ4?eNeZ9Q)1h>V9H^X!7dZgZD8MqjTVHbYuaJ8T|; zKCn+XPn`#t@S(j7Q!TfaS&;~fEVEdoKxDX*R;{28$83Kn!SOdH zW>5=gN6f>}CFoshEwPeEB9SFlib(Rv4%F;4cbMb!vHDT-h#Am^!g-i7R7tO}4~uMSZ%su|Qp*k5ejf#+TOj(x^C?QDbF zc5|CKK_9OVM$HgqA!-&`3$0Xz?sqCQB;q-InHp>nWt8xD8u z+xA)KjB^Wo+rDL=bIv+jP`TAy0EdOv0xNYSRb(K#1}OuT%xWg}CTeckH|_JzIcGB} zx0svF$@(O{u$6>+cwx)Kzlb8%7x5Wf7+Tc&B)0LQ)@Shv>mtxXmMxOA-2~^&<|cEBK3Ttk#GCdF`+v@Pr+_um837i8ivrdNM}WB~ zXcf1%@-4i$wS{-Fi(AETYa@C$nH$Zi`V_r{)y3{?mq1k)JHIu`8R_J=+VkIde(N_r z3hR+@ENPXnI@=|IPT)> zc4m+T=FwqUV6$X!E5+SigF_%BxVyW%ySux)ySuwPlv3L7^!stnnYqus=UkHA0Ldmn zZ&IiPkQgc%OboREmw=WGw!pv6O9jiOEdwqIEgdYAwluhTx@PH02TS8$52b^pP%9HG z9c-4a3=p5LZ16(5^Wb=VL@OIC11%RU8$6#b9orb(5FBa@F(&CljfwgM@Fabrz9ewW zK59P*eR4m#4?>^aPwvCegV0CtM?Bg>Y*TP!FofB3Y-wOg;HbSA{YwIi1IO)SxISSY zx0eN$qP`3`0zP8rH15OaLFiHFVd#VV2naiaku}5^Y)sZC>BEen#sobr+Z@~!Ov||e?}fg)U);xV3OkR1bj~0+3^oQCQ}oIDaJY;I4}%WJ zbI4I#wl%mV=)yBCOAo&d!SulT;3Dj~IIujh49|<@Kn~+BobQF6gdT^|IZuF)Gtii- zPtga$d5|%}7;ZSqLQE|REDW5qPuP-83T_Qb_`56vyw?Xa0PBJ);F`l&0c1Bavb8}k zkdbx9E5I@`53dEw$kqkd1~Xz}UGNSP?}qM#F1cUbkw|cqr^pXEPl2?KfWKq|j86Jg zeE>EYXe=>pTNor@zrz z@1*xPy6Bz3o!~Xf7>TU;f#voxdwyVry&Sv@zMM@CP6~21B{&&8DJa+~Fb1U=$9@2RM2&b>nRqvwrHM;3t!Cmxz#+tzDKo)QoBeOv<%NPMu@U-C6 z;Em8V_o{m%bltrMzUtl#^}%dkV-Ec12Id4-*(+@aorF1TdT?6sIy!HJdK=yKZhCKY z_AzD$R@5KdkuIsy3?>3!Rf&? z@O0SK&`tM-dlj?SLNn1bD{uvstD!5QTkcJF1}ZZHGXm@Ewf6MDdV3vsojoHE=e`cT z3T7UEpQttNukFXM6?58Ycql0&4>&0_&kCp=$$m+&7`up*nDg zbL+V;Lc*!%)^%To>bb(17p#Y?7opFX{i1)?#~b5}KlQKrSnyb5jBy-3CjzGenT>w> zDfq3$^%~rr!qu9sV&!I+g{xnZ>XOI11ei*C;!NO^yeS1vWrW2m0xK_0!m; zpI!@DwcT3o+t8a(17yw(HUQ=XKO*as{!yQ3Ofde^zu|d(6tl+yM*|z7X99ioKKdCr z_0`uRaUI)&oCw7EXq3e|K^h2DbShHAMD-3IQQ zU_)Sb@VovOQjP@12gU`C02{#@k#{!GNAInlMP?s;4GS=XtpT!tv#_sp z*a(;ve2=UT`g^^-(a!i={|?W?@H`SY2dCcpxj-+yC%CuXOJ5DQHLSXOCUiPf-8~yR z13n$9;WmcftYBkzW^e|0R&ZwUo!-G{Z@h!&d;N$0H#`poCcyO&a5%7vnQ&SKtY+tt z(^IeJo(r7~RfA`Bw+Z}a1mD8po&HwuXml_R1}0+qAaE#f0o^_H3xV^{mCS@^(T=&$w8Mkk}Pdm(f_RN1{4x&S^Os^aboOvT(jV1Hm4OOCl^z;gBq z{jc>`dKaU!Q3?H(-M#4C7uXY+2HgYf4ODb5g)W9F;x8}&Vb-GS-QmYQPxtM{-j z2QCGYaNSaS;Ot^M*+b`nvy&C&@orPMC~xW(<2|iQfs28jRu5<^?O**Ly_MDynyC2< z#Yn_#l2(K_bK~72m@3MPW2%W;oHxPSwm6@Gj}FCoG1MM858?a>*ulCZw};isx`?-O zFY7{}hu+Hqj9ykx)b3-G2hM$GH`~QpXg?V~qXn`Owbt4XynkD3|KL5{T5AP;>^yRI zu*bl5R+u+;o4JLtNfBNGKRP-!D}i0ouzT>i@7#0tu-&YibtP~)(9OCUxB|W$=x+7K z7QGCx(bH&y1V_1x&U?;XXD{2so;Z)4?ci;A&OE`@HkN>WT4)KH-}uQW#1q`+ZXx6r z<|Xls;Hg+iB&TLwtxbWefv!mDX7xcrPot03!{`p~Y4k8k;g=EwSt(4UVr{iHNNf(b z1g*JtPxl)Id2u(vEePjA{Ejo5&0=@3$zA7;GmGtIUEti+>SApUYzp*+cXy*N(9L-2 z+z(v0o;q9cyngCDfwt4y!nv7tU%#g}gL8B3Hr(zw1>j$h7vLq_;%;f4lBHm!d61<9 zmx6YNa~G?h)y?Q?^t1Xx%ka`X1?!JmSEE1B#faA)==b$_I5*R7Idj--b_>q8o&4}D z!1MExZV9)OwI#4Q(8<~w*aF@h=xqIgdVc-~FXfhW|KO$FQf^tE9FOC&a8C{{18u53 z)F0?g;UBMc#B3*PfYsmXV%$W^E$5~)m(5}Mcp0~}n-30u@FwVQsx{Fb=@0cAIKAoI zaOSbO?1nR+&0`&`ZGo+U4)Ez{HP#;MkMzdqY@%Jq=?&+1Ue+z+{tmZ%ygfQQSnaLt zfo*~I){emTKwg~w&hzqeZdtdH_C$ZIH-bZBtsPF=Ti4)l-MQv0VDniX^yKAjQEz9p zwRQ$}1akB8ZaFtM>Unq@RN7i?tX+Yff!5$QR%>f_U{@fA(mvQOm_z9hY!B`j>;Uc* z>;&!->!{_E<#{=tPnP3<$Uf#EYoOJ~9Bd7;`kH;r zfz}rK(%DM4&{xh&$3Z_a9HX<=Nn=I_tv#4Rx6!TW+6KIEdSkYa+0X2Y*?#5#yubRH zuk@FCKim&MrHk=O|6Nw#<@xW(%_s9Cw=B;u|A6L~W%)9;8ChHCX8PKBc<%HvhggHHUP$k4_BUVZFZBM{;-#KfR^%0U zURjA(1Xn<60c0*?1%RbYz^k1m;MyMC4$qOE@abjtG>2M4tUQ>?D+^*`DJuvpVX2L- zS{E&~QC;f_?t+~*Vv|jDBYo?&NJ|K=m2c-LLUG;*9*a82`dCFW~nfn+K`68 zzYR8EY9rl1PdRU$+%lF|;<=HSNA^H^PqT*^Zw<9}((8DA*-pBHK67@`^mw()PWsfj z4u0l5bq1OP%;&lbKS$|qHnZZb?wIOf=7L*pnM-;+mKTqnnT3Ssl1u7|xu5jyS=0JZ=nL}pb znRyPGm1p5aWf8fM6$KWswMbt_*V41j8D}j$=bUwhAo+>j#cW|ESY6=I)y$5m95Oka zQy9sO+FC7b4LaA-WJVpWww4T)Mtu!kP0u^$oYnM#bKdD}CR#15&SsL8 z2yOw#Y;emiv&n2cE6*ykbEwS0vxBqoY|@5LGGi5HSJO_I>TGs2TUtq0M_hL@v!FAp z%q(;A96U3wv&ar+E32i|!E9}{0=Gn8dt7%g6ZCXO$Y>5u(3|UFBb_mo?4x_>R5As6 z&^llZGYjwvbdz8m@En=&=z`v9x|F?wz=L+Pj7^c$z(s>M< zokFIOsbnvm2JE2@9Ef0oilUMM3m6j%*fnQAQVv-At>NY{^N=+JZ`(uG6MS4dWDPZk zpmGoz5C3L*yq>{GZ^YvV;AAio^%h7^)YBR+7%y@+CLwn+nU2gobULt`rV%A&3H<7T z68NtRNAfj?16Q4W)(CUBxetl^t;1F$t)X_CX=-g-RwMLpF z%p+C9f7veTOzA5Qkv+y(X+=o zW*xQaY2(R!I**P=$^;UGTPhJ0>19~D;<9teafO67!c=3uk^Zaki_u8`pYf|Pjx3<_ z={U@eCn?b%6e&dpnO>$9mz;}ETH!)>A!WC<%Stj6&ErU`ryU3CY7ODgNFPfU(gk!Z zSwt6t7r-lp$S5<&6e1!sf-~S(4}`=;=YkUwX`vx;!C6Ij!flte(`soZnJ28eTAX&m zIu321|7QHpXaMJidU80V5IfMb)7oLRGFzHs$YQ#PjzQK~QXicS^!mDL{AO&oTAQuR z?daKIjYiKHk_@xSMKTd1BeI^Z8LCkao%QumWC>kNN1#g8+W?OTM)!uApnj%(a!WTg@;ibl#QQ2ZW zuuog3tcUg~>m>LA^rC)2Z>L`b+UjH2JTjMzWnld9mcUaWHxv%nM2ND>b!2lKbaeJSJ9O; zh=f)29(KEL-?PtHr>)1>(K0T>tF?X^u5I*DYyp{1MzMut0eC(c&Bn8FY&JQocZA$n#x^CSAc`iyY^Y@jCI#uWt|0|vF_PV?8iuX0+_}XyDtWj(Na%PhWY!;qT6L2+)+=0Vg`>Bmj(i>0VVH#)j%Glxza28wzcUR%z zD5>34?s96nzlfiOiLETxbbl5Z#R%4)^dlo!Ke7CwmY#ghuSDt#tyYC-ot05E)2@u)$;ycpw?duG{Oab=GxzgS8&K&bnc%t}1>LDjYQTxLyNu z$Mu@f zSvrkPWo7AfHjR~|W$9FQ2KBR|sc}=kp*J;d={Lbmpq=5+#qMmshIWI~OYlqk1^9(s zPj3v*CPuu`)VQISfm>NxhR$HqS$R5zO$JY8Q^4h*rv-PJds+yWgPD6qoD&r9k8@%P zKH{7c#9czqiLJ`ZhfT-UGZ&9TLGy#xF^+8ylE z_9^fw-1S6SoZb_tqn{9eOX;3~+evW|PQyt9W0!tcZ-7l28VSZVJOdMqt9TA37|n54 zl6Gg^SV?SEidLeN@O-O8C$b+_C2Thd*FW&O&-TdbVD~~!9le)bTdxJKqu18!8@u&g z;9YPp0iTleIMPpuTV4{w$WU?#8w>+qgtmiEd%K-|2HMU(3+)ZpT6#VB)HmuG zd-UCUarl&=#c2=LogEYZ$RF~U_*eb|{vnTx%VH=QLN1F-(6(@BXScP_LHod|mfi=b zsn>;1J)^F%SKp%-qdi#%=~4I`6Ib9dgtWm_Te~Rj#d@-$v^VPo?uou5LUI3< zN6>jx#KEDi5ohev_v)?f^O$H2w6TkzzbHK{e6HdiM*k5}2R(5{9b><~Pj6*kKyNFc zwOyF@VZB*l^cSIr#80lzJ%p*lVuF_|m@_!ho8bM&IfFTZ<58L5P4XssIf9db?7_*n z`;W5+vjtn)7vb6xXk{N1e)lK$Alwd#Dc)o+TW|`HHJD^yLRS*d(mo)5cKz-FbRHCm zs3+Npc&1*m+jw3uHrUo{7~dzph?u$`AF7zMY5wnC+~*UHNh%p7d* zwezCjXfP(&5|vh7OK++-1w6&eib~dCmS6`jCKv&?hbDQ`aGnIT^g4PSyhyMkP%fD0 zO~*+hkmPmp%HgXpoxD5lZMPG;$^|=l=hK}-4L46PBY8654^07iKY zFjYU;Aec?bu5?A$!zaOO?#+TWL}!Cw!(dh=n^HYkBRI;d z4vh4g;j}q;Hnf}9)vMrk^K$cCyqi}ZpHt|D`|@rhOf?Kv3sw(~^r`_Pym<6C1J8jr z#%ZHqRh*CTssh8krl`k*=R%v{v~jQs&WC$dfMH$}uNO|508PEh!C~G|a204%bT$b# z_Il&IG0?=T6ddXe0au2W(pnlxMk%e8(Gpw|8YR_fH5w%~Xmy&2L`gMpHCmN6@gLCl z>v3j(yPsXxj5Gh^es*7b4ZkL?iZ%SYxF*)}HTTlxTuQvti7>&F>NNxl)_DXA| zv?Qa1*4k(VZe^6zVo6n6g~pOh(8lm@;*a;&F=`v}{-)5?@La>!@wM<=2V4PP!E<~a zAA-N(Vz6P9)WJS+W<9g6+1IXT*3^&b^~^qYO>kd)?C?k|sY1(WrIA}kOEg-5lZ-^8 zxYovK4Q`D+BJhbJ5mJ-ZppCFYV}B$6LH&T<47=1engO+p+DNHm);0&&{q0r!hPW

*NSOv zjW$Lxt-R6JD65sxS{NBgEn1UiBspm% z*r&Ex%N%GAup5~5&7*n)^N4;Jd{jT8ujDty4Y87M6F0#(u<-^yfc0k^_&_!QydK)z z-^^djXb#jgiei&uS~)EN|Bow&Z4!)fT3KiY?30mXAh~Ex+Q5HUKcqK6dPDyTIIrXz zd4JZAZG?A!mW7PRtC_QqN_4!H1-nf#0`F62QY{FjsSPOr3qngpep8zc%tPmXJl?MiTZG!{70pRk`Fg(+f zM1M7-s*&h#0j&=I8fJB~iQU+)ZZ@@>*oCn}5v{OR(Wqb))+!kljmBnue?5O==2ug-Is0Vo1kri1HArTn_ydL>tKJcAGi&)kXG5KWE6s1VQnd< zmhq*0m)I$`@Xfq0+XD1q>9AXvq$7D~Zkpsz^j9^iVV~+|H8bAEUS>UiU4Ij^F*HPe zr+M-1(s}R$TSFu-%|olA2i;~9v#!4>5a(Y4|E0VjatmoK{Yh|Z2~;uCVm3qyXjP2L zMgg1_)E1+2317^2i(R4$e5#sN%w~4HUBzr}L*W|dUxd@ed=cLxb_>4+xQH-nHg`+v}Yi7rXA<6PP(O~;-y>{)gle{KIPdnWV; z%|&vOA4vL#&bDj$Yx-x~wf(igv!H+D^auT$<|es_k0~rWI6KKk7Quh9TqJk!?R=5k z$#?MOvM?<~mm{+*~}b=&Bv?b)HeRs{>kbjHNQ3)_(OBCe_C)=XnJg4 z0UU--wG+(d=2Xm1v**~e?VA3vm>s8%RonX8_@}6o)jzZ;Kt4@s)i5mqSNo0)|EAw* z9+I1UrzuGu@)OHSvVeUo8#o)uN-`j$yp{nu6|{xed68Tp3(^8~g)Br1f|o^48sEuR!lMA4f}N+@Q|uCEadV1Y+{B$a zMa`#8Re#s=g7ay=YZ;MU4qOhO0nUgm%4>f16Fw68f$ip8{5fm*=i*OX(?1zLQ|x*6 zT)T#U9#Gvs8e5G~N2?Y5<^9vtscK%0V=Dp92IX3I=r@{*1j#q-`4^opr}JrizMR3Q zgQxKYauv4BPglv6(E0GL?w@a0^H&8|_gC}(iP>*-5^^WolkAda33IwS4Jp%sJlZ_? z%$KWWe)eW!9NQ7j8+-axi(U*>28GHIFs}$gNR0FmMhi)pA0=VxK?hSNz!HRAhl&)nCQGz@87C zV3#&anG@hM(Ozg*@mKaQv==}}Abq4dLapqt^9Mu3jU4V zA@|5#>~IhGmF09d$n`R(yHRccuSeeRu1h5O9hokTx zIYj*f-kkgex9{p-YA@(R@-y?ZhnV{r>}T7}hj_;RVrIuw4)7p*sr?5g2djUW`Jma| zadM-~jy-d@er%CS^J_sZB{&uI1~$1#^1FW^B|pGOHg~)nC$nKHyZcS;jm&RqALut+ z{iXhlxs=*<@|-@S*U1a|9Q=&lAlZG^;y7j+a^8iE;vX zJbVkd`CUc|0F+!KFX;<<4L;XN0dt@_KrLVnQU`+bLx0gyXvwu-ke34dGc+swvzb}V zA@*Q9t2xvjV*iQVzNuNMwzPfMoR+W&Bt4E!tf3VN=RE94b@ zNi)MCi&+Ts{nbKdL8#|WmXo9hhs^G8n6S0W=)6KMlh^bWy-eQF*VMyQX45l=+r#X_ zW`E=qhDU$(Gp@d~Z!vPstOq&)Ey* za1)&KqHYn_#Wo)cww5@`&tro{-1jeNcu(&eL+2f23)F5A?P9QT?F4Hb1E! z!LOjt%%Vts20S+@`WdIZm|N7nio|Q`9W|gC+8x!@0^r-wok-l}96;J55`y;!`qV52 zkEg&h^Nso1{GeXJ>{akH=v~#&vViYEcR0t$OR@tFJDr2hWOKcJ(0NFHF%LSw;8o)X z;rNgog!dytumk0UyKXTz9SAvZk_^SAW9`Br_SzQ@el{}_57-dVK! zKxXX`JRh5nO#Emo^CCPisTb9k(2MFT=vH`cbGAAs$qBO6IYmyA)NoG2Q}eK!&dtEz z&`Tr(GTzV(JU#Rwd>)w(&2-R*W*GXxd~d!{Q}Og}*iD70)O-tkwmKK!e^Gsao`>c~ z^EK{1qVF~M19UTbwm6%e)8rJ{?3^K|Ne~XH_i5liW(H^qp3%+Vra(OcbC(@eMd9{{R(|V;|P-|Kj)brp^*uJLq+580lXueWY%TzKW z->g2y)Mj9dx(yx=)baGVbIch}PdLZH$D9dt5}inoI+N%T=P>xFbHu3upPE)}s}^!< z1LxGBjNuU;#8&u)>GBe}NYcm*{1P}dQqlk!_$KuU(l!B`)$K@o0Dge?@pd4yHjbWj zPB`O`JDyHP=3%G0^~L;bR=2*IU%;Qu8de=-o>S`pXVsKQ49b);%44{L%!_2B`V5!0E6Phq<$A9B@Y6fwaup4#3mKB5@q82LI|-3izayDP$%d!sIz}7JQzZ zBkSO^UR|difsTU1Xj&OlRjkU^74x!L-#V$DQ0pV(B)A^bhFdaeOO30X!|yENz!|a@ z4(rsl>QU%g^%!&{UFocFM#6Ixtz=y_ub7prYvxt(6|=I{z^ZSZP%Wu*jazWDrI1{n zAp+RstbxN?wIRArfKRB$RTG_-G^N3HK7y`tRyrf#Kay62XC-SmUG1!LhNC`$RzRhq zRl&M$UNak64Xxv9BjA`Cz^p0p4Qt%s!{{1kwKEJ;!)bYRR9(Y7M)(y;A+g|KyvTZ@@;Uvfb2bVpT?e6}z(C#AM+ z?MY|SiA<-J&|lfE36~XWO}hrPEqdCKE;ye~y8zSZM>u@qA9*?%l7I0H&U)uBzR}qL z{s#TPeNvGhaQcyd;EGHqE82yvrdCBbSF&r_E7av`EhMZ^+mK##E^Pz) zp}oPq;P@UpeBgicbyI+I8u89@8f(x{iQOWP%_5>|b?9!~26 z3)L1lO(d`2@S2yxX=%HZUCJtHm9k4)rL32zzv3_X|KzXo1^6X@!GDwglO_KtyoLwYdE}-@8nzg4}T|z(V_I6T!Ux+JKV2vT3{-XwZ=qu@*Z77X)8Fk z4!4IlQC`WPgipMZe(@97Ctk~zsJ04sz&TM8SYOhIB*38sYs0$XQPl=6-N3D(FERB> zevt3s`9Th$gTX`T5ZV^KT}fMDcOVHaEyK-OJ<^vnhg$+`&gzqT`AH6>pMe3i z1soE?Ey4@%@#UF(!0+>Cn0+o2!VA>}Y69vl!cAF2(ttE&jYvaq0}{`k%7^>`e~SKR z@{9Z|2hb)sZOWRk#-tH>A|LUG{0VxVN~(0k+l4Bf!X3e#!=1og!kxig!(G4~kl!ub z6<3Wh+k`#F>=XG|KIV^jBUBo*Myv^GOdg?vGx>z$L_XzDc=vEOO!WwN2R}sRk?a}n zf$ImjekdQvXZ$Iz9qx%rop5b%T(}N61MS2*vK8V_`BknE-{hY%Bh5fNvWem5;b!59 z;R(={VukoB$Kx%K5FQ^+KxKTmzP(T#A8ugRx5wjtLU}u7j9{(OKY*3Y!Q4Gi;>|%c0qe2dPaq3 zz@jU7m0=9ro15+id*ugl$dhq2C-f=B^!VyWF~s+hXv|*F(9qYYOw|ATqtIR zXQDm}s2Ap_3(9F7R-4Vo=>jod+?KZ_LxodD<5(Rw50&|1p131#%h}<&;kfW@Ox6X@ zg3f`)f#dMVoGb3iJ8~{M=ZU$fQDu&}C-2HRsLvI>!gEpS866%T79PPjiH%|;-zYYK zM?ia^-ZR=GIwCwg{6F$5$x8o6ve3-ntTYSl9xa5oLigy%@CfjTaF1xOXwT@d@Gm(1 zmHa}o(X8}0@;{Q94(FT2CNUiTBlsx3K{O$w_(l za?tG5kJ+EeQ1lGrL-|&*MU3I2c|$e^Xu!Hgi`a$juGpa){s9zAGf|DG&@R!Ub`iS^ zPP<0?M*G06FEBX#6FmLoCt}kaR418eYfC2@R41+R+O#3?AIgXDNn)!Q%g68rY%EZp z^@GRYa6e#B*hi94oBH7J6B*1Wi%DWI`iJmwd@Qfe#_@WrF1S9c$2v!g*+uQn*rZFe zf3#n8P`H0|V0Zv{PatFl?HnC|xdGvSo#a#@ z|2ipXayk$_gZMx`RZI~R_;_?q0OHudX#a4(@IZ9;|Bs>np#NXzA15VELH}`rG$kFt zr-`Xz0A>gBLD7NHe&HXe|Ks%M)5SE=AEyI&KR!cD7yVG_&j&{bp=WTkZ@3S*U$}4h zZzmNE(!VkF!zt@!mYyu@<>EPcS$u6g7dR(geOu1+WGvVe0a4B?i@S1OEMEUNBsw_S zC)^kQ{diwKQ_K)$yzZDQE>( zuMRXmIyBll91rvY_rkNO1nMQd;@}eCIA}3&ad2H|QE)MEJ!lbdQE+`|VQ>*}1L&04 zh?|^GiH&h1?$p@iJQ<%FI|bTYnIWgkX3BIq4cr{sOqqtyj!j1Al-OypQ)83yX@Je+ zm1auRjaOoD7LThKH$j=t=kWw(9-ko-;L}{0gp3}Au$7)iQO_g|@wNUoq zt8^`t1$;huJ|6QO z!@s~9D@~M%v5kQVu}SDjRFag+UL|ilY7=5-#mTiFX+vOKY%83$R9Y!jy(-?E*k}BKoD(}6+CXWjjEijmjE!xrRP(BO ztRpu zrL9uKtM1iP>Z89NFgkXA?7Y}HVm>fi)K%&!qhsp=qhi~kv#rujsp-}52FS^L5}y<8 z5N#iw6YU6{3vD00K`nBV-oTGgvdBO=Ku+QV*&8hZ_%5Wz6F@1Kl}&CL2{s+zy|?wY>hOS7VWW5JEgr+ z%d6?dDRq@mv2no2*jdryb}@SvK2~&!&Wd(I@+@F>bbhpLv<?f!2$$T*OVstP-=?J8aj9nPJAhr)*2=wM1 zut|HRjuNMgh`obvXwk_XxEf?8_L&u3fXp`0t26~kPOc*N8tn`JesYK$EGZoV5ZVuZ zy?H;N7q1Pc5wW#_;juHKCG6t%4EW59E`(DXaO-F*a2x0qcwVJf=sPC`xr>k4?ajNi zy}8-COYh+BF5PThw)@CVd@ApQ#J+N1LGMwehF3A`A3k$!YOI2Yk?iT1>7FF68pspwLiCq^&OPtHf@0(vge9yskO zd&q9QD_<5}iqmD$7SRN7BJ?~uFVOS!v-8R6j-DQ}yX?-p@pGu0r|0Mw=d;sI_TZ?Y z-d!%oTtaj?&^)>V`X4usHj8#ePdC|B_T)YIO4OP~yWqO3>>_*do_ts|K1!8gsK!T! zMOQ+%c$pPX+3IcaJY^dY3*HLdjQSRDySL4YRW{*zv$x61qGVQfc$t)h;0`Y#*a94@ zWI|;-bR$kTc?YADqm!aL$qw>}?gSpv1E?H~9*9nXHWf|8DA`nu#M`JTu13n8UW;I2 zaHqEex&aOwy$xPe$)fB>|AFZK=v3(b=rrgdxJ&|1icXAfhw~1yojj(G=q~b*J^=58 zHil;t(O8U@qh!1of%ihZXbO!Nsqi;qGZ8QTr;Mv1la5$kB2i zvi3*!;qf&sx{W-ckLfm~Y$vfl%iHNC26q8T!6R^*5Z!~W`*aVv zNAH5~(|fd`XeGzWhH!2q8j7)UjNA+7ebK$q(pE`(FCN3wab3nLZEZ!?HnNpGrB7&c z(M)`Ingf41dvLlpdNg_j{zrlF(JkoNO16+g^eJrs|At~O*@NfRUf{BwAig<&Itk)0 z=Nq^=bT>9l3hoA42G?Qp_1-bKjEf$F-}q>K(OR~W_2JV%?2eYT%2>ORxF@<9{#(dq za+n^Xo5>M+n6?lJ;!kIf*D}~DxX0TKT?@B$-f=jMiyn`TjgA42gKk3qW>QbIk*#Gt z_}3SSq6KCXfv?V9uT`*haId!qx&{twy%U%l6WvIT(j#;uW;c<#n5`%3ing+iOv3b6 zCrNy9&e0@XeR1~Tbv^yOecoQ^$><5po&-imR;wM7Tn zUY^1Eh-fX*QFf5EP^m4>M$e#f78o9_iFz$jQ*@FY@|=MU^Fy z9ntO4C6VpXrIDG=4CfG;=^P{nz=y~|@}0F5N#Z+eC0c_2f-a8ijP8go#?+F?GE8lY zE{iOMriE9?7xtxtPRHyFXS#Ek93r!vna%<7jkOl7#5c_U#r|eV;vD^(eTPm%&va*+ zbA%iwvz=M!obBu<`@jdte)0po=jadMEKLvZsInZH+oH=OTccaR+oD^ef3h~BwfGbM z-`FDTwm7mVvMahXx+t7@q z`ZQ;%bCet*bDY`EKJt~d6>Y>^URF0dE8 zmt3~zI+yXP+y#+4=52EU{1-+t`Z6GWinEw3B2(Z$)tTZfB1g#=R$jCfUy$;Z{fmUt z^k3i`Bc8bnN;(|zw z5>?XrVie)yV0=0W?D`})tRebWU?iKyC+SbX2}&?U zeQP5dqU)n;BWs`&oMmJwncyrZ%fL%9{{gcf*#}lxR1yyQiEmwGZDf6PU1VK!Ef`nP z@#vr6yhqOm_MTM{l|>qKI=*qv3bLGx!|8bE9qRAdJ62Ux5${+vQB|yuz$uyj@q>Sz%4RK9VzS`{4^S%v4w zxX4D_r9?gG`yhVieqPcS>&xUT>GPnapqYGa=ptvK)0VcO|M5a+fpao)A~Gj(5||zN zC_V^3KaT4Yk>ioM(BqML&{H^{4W1R537!ot?Th+ie5K(S1($-p7r*eI`FrGk5TC>e zJpVtz>nHw6tRri2{SkMc#83PLErESX`dZV)&LXEZUE(YTFLK(@cC;;B;IsqgJH^pc z!dKjv8G0I-Gb5*g8Idwbi}AI>RBQSfIcv!=Y6!#s)V{d-sXe5HK7am3bvB(*?&H&GdOplcHm4S0vUj&cjvbc))TGFM?5~n4y zTG0-)J={9bdCpw$d}p5X7Afz{H8_9`^x#&c;$iBULvNF=xgzqJz}rL z6ZRPVh`kYiimzfd`4d=03d5&}udvUAo{yY^!+Bt8(8_;)Qs|p0WbyFX$`aO9n0A zOAft+u1S$gz{JRN^t=$y#dG$IHG@xcnjbv{e9y!Sh8pV6#bxwPj9dmLMB>rYjKr|ZYZ~uO1_G|Tgpx7dHzHEEzV<)3;Ysafsa#{_+NPM zT;dm@uOf$#`3iU)d5^q3;CImSqzCOz%afk82e><}K&p_+q%*ySlk4>nUo|q? zei8YEiCvL<%3WopcMn+Mo#wa2EpZxIXZSUKm5*}DkT_b0mVsMYQk_&IFCx`}=aI|U z`HJ#6vNN(H@)<5W!JnX)l~!LLJ0VX8DKMe5Qx`Ze+e zvtNPjkqb&rUk={|_*_&@z~Lk>N$SzMv?Mx9kw4L~E%GONw@1z^xqLZ&=h1&bInM8k zd*V3yPw*0?KCMSfkOs6qxE?0Yq4T_QPRZ@d)0~x#s zPV#{Bc)7hW>gmCMKx0tL4bJW5^3tIa2Iq%Hai0?$1I+}@3C`)&@w!Yx`MMpvwK~YZs2UtEy^S1p^`l2Y2-;{ zEAAdDDPoexJc*YD3ew&|?C*=+B4IWQzq$G>6W1dBxMuJFt2!0rO5ZMIh&B}K8-Un}k7Kd{QR-DC= zI;1$OOX5fwx#jmlGaYy>ue58*CVOfcp_Bo%N!vID;N zlpVkdZwIg(ydAZp@Hr-r%Demyw_>W3=Mf9L*)dkk^T@MEG2|9!Wm$D%#gt`bSPfDZ zs7}tvrnCt?gZ!p+1F|+M8}u zCbQP{vD?H{_Z=})vW^8=OGP;p6KltaZ3XkPUE7Lyl!YD_Ln z<&N>8=O^l;Raj;AGxgI-;EJpQxDu<#E+gfN@3QazI6BL~D6TdNk8O5?l+GP&lNBJ# zjxO%*?(XjH?(Vcupha5Ty-3{^cb6&@cen51`*EH#_ultC?T78dQzl0yMNUOeMkhs1 zM^8nkGqY04^hm{&3b0a2#gr0cC)vkII3XXGf0TZZ&XM#L{7PDvD9GbAgIy36vL})- zDKas#D|$NmCZ!>Fkd#_0l+jK~^>GhLsTrwD;;L3?Mr3-VLP|;7XKQvz(tWT5{+g~g zDX&xVg&KzZbQiS!sDOQpxyR*W@^a}%>Abuyu{LpDK8H_W*2Kt6vdX8-jLg7Gk)+v2 zsXQhhl~+j1rK9pnX@zt_UYl5xxFDa$^OIV@9v|5q-4z{A!i31Hl>DK5p;yd(of1g( zr{=e3ky<`w7Alug+Ac+AX{6dmNINQzi|mQ+j*cT?d}MZHR-|0YY*aSoWlDii{?JR( zUZs?wL$%A;iY-GGf5GX?lou%lLj^*I$vGk)mRCtDrLmE{(LK?zWR8o>A+K!898?CD z;n81~ZrMIWPJR?=X9T(!>(w*vT~r8)?9gx{D(XjU6vaL)2F6O zZ5Ygunm)CKoyShtEl^9l0Xq$Y4T2d{Go*G2&y92qcL~22nHyrCEPjue&oGK=kUD9`;l(pu1x5L z=D<0TQla|HZ4hh}Y#2_|! z3wC5~r*Ow`zsUSZ6Kb2YIECDsGKTKk$=K#1n;KYNvRRMmvR^0p{EV?ZNqKCgCYYXov4o4 zo$QYIWa_8LljWcB>eSZ=whj-D42ra-vQ2mr`;+BK@-KL2deZF9^u_FI!TTxqQmRp3 zJ=iKdBr-VCimuk-E>z^QyHJ&8Po!&-JW>7?Zy6pM84_tpWvlQ6b|%Ub(8zfCch1M7334SWa@duq%4rYq8bxl026&AljUofR+o4;bf!+W- zmzOP(HIdWHx~Wl8W0 z9o}1JNn}pMs7do;UNDh8(T|+|UO#V8v`M6&H#j;dI+(nhp~2pj$iI=nTwRF_@dkVU zM)<=&Ugksu8HwCpN+Jk@WcBq%g@;7@dPAav;oxXLZ>Tqf`l09__z(Z~=;Mu}s*g7w z@55DJFYFl!kqCPcJnp3?QeX;+y{YNr4I|^1@G$gq*z`h))PzY*+zZhs5+S4~dQsWi z>*Y_j^KZW@r z6YuRWroWpgnCQW2Pp^kJ2_NZw6a6|mlG<;gK`+HCmPm?i(IW*BE=8UC*uy>*M3dsBcRoE|evz z7s;)uY!huA?H}$JZWnDE?F0Mp3~CpBn(`#2U9?E(Y04|qphL?!u`YTqwS(kQWSbVkQMqCz*UKr35E5l#7Mg_86(jsdjgZ|z&dtq zdmwWM1qTM(;v;yUHPRlz9W>*5I6i`_#&!pCAE$JPw#Q#cOXS7!3u&0V1TN-2S~9&= zv}JT)ctCg}skLoYUYS^tP?^6n(IQ$uTrb>$)0WW|(R$&5;pgt9iop@I-*A@nyktz5|iwSWKKf0?Ecgb2=)(_#zzH5*u(8nbdRu~NyFt~ z@-vd3OP!*RQXZysigv`CGrdK0GTpW8$*88?kKX>le!(*MQ)z@eTz*RLGih{ixIN4s zP3myFS+qg8ez;k*VYmUTA8sD)9DSJbAfn zT}`9Y?5UhiL)Gj@oIaKwNu%Xaa_?YyGI|Fq;Jvx(6Kou99BveDOmCCuLuwvL52Z2k zX!)TuRvsfyx2xJ!?CGRbh12j}^!5%miZ%(;M{nck3@R$yGdQneKcMTO)G*pK+$7wP znnux?oK&{&OXK9R@_kMpNDVk`7;O-37H%58$Nqiko-|$_CwH@FQrQhvvRB$e?7?s- z-a`(^ez~XI1Fm9kuw6FNE!s6&Hc|#(LCs2gHM@i0D!jX#OhlKORiIVh|ij<7>jP{6Dh*Swy4pxX%4OW5W@hSc^CM-{s zAh~3uM5J1@XLK38AKT09alx^{_0;yWJImLlYf@*XbdmeXedQk$#Us_D)uP3zFA=Fk zdZl2cNJV^u-Pi78Z=k0yT#t96x3j#Iv}N{Edwg(Quvnxlm*t_WE_X@xQbX-K2yoz2MuQhCoSEReGSIz54 zUo}+KyFmR#?@v05z(4TnoK}OK@CtOcf)(-eUS2OB%tyz0biw;WgP@Bao zOVt>!me-Z4T3$E27FRXBGgO}S{-r7l%;IJBYI9o4E8~s!hDXZKGn(tN_-QK7Ko7q{ zZC04o%LcP~*}c-YAs>A0C-Ml)ews(qz)6m6Bc`d@t z!=>nM5iaR94>yAiqV=OCy=LJCuoQbcXB-ZlVqL> zoe7;L=S-+quxId0s0z=QGpwtyQz6(ZSi&pm)sJpx$_{zEJOtm(oB?ov++Y5Q{GaWg z>pM0FI6QSdwnvoijA4&en{?VQooDkec_Ck9fT40|G^$2zko(rADx016>-b==h ziM{BD#D1z4*!$53_78Tu;Kbk$B>ZTf4|NZA3!V?1!;g`FJajB%MQTR2kg!$WA~(jj z$W8F0Av`zIX~D3Nd3UR5b74}8oUrXk8h@ai+qsX`SwB1Kd_I` zdo*+;>Rutx`c0_ zexrPZllSc-=so)&U57#kLwu4SIT*?lNkrDmEvQ*Zsd%(3^ge;~9!lsA$mvX;|z@>;nSe%wCB>2WmM-WSRj$s5^6&Hm6Dxi#l& z&{}yrXS3|>RL!=_s9(!p$z|2AR*LErO8~JOw6bYr(@??B2|7Uj!b`1VU*ERbV z)nCAycu6WtsU_8KSsKjDp36yERSEcI|n-juhRRUeVdLi;1~Aib_sQvyi_hh zS4p*mx>WvFuBh&ne@IkRe@J`}E3mpk?^XK>ZMW5Nl)Q{z5axrR(tN+-4hW-fsL(RYTJZH8^N)R> zlf7_{y&LYui>S-xPvjz07F8dxx7#kPu8^0@h1oBnK4iVierP|y3#lvR6>=d?3#*UV z+hspOpV|f0Rq{%?Ag6`Y$EUL_Y$*T}2oC!FoDpK!j@&d*K( z^#tqf_6hcO*pHQJYE|`#@>r>=W^(?r|FknX@8FM=>S{Ihky1mg4y&n;m8VJ-wX*t@ zx+?Gqp3(W+{>#ot^*c^R=g-jJ_Pfp>_GS2|{Rhm1KP2Ii@{I1vY6j=8(4V0URAzK^ z=dyjt)}43p2TDz~hWdcYhsty6Dyh%usH~=U{to>WN>5h?N6>M}PUn0V`a6`4{q#;c z=ljriq5JecQ0^<1T2p|}8+*yrsmPG* zrjl390~1sPozwOyJLsITPs8l^4Nh+=DNfKiWnWkFsd?4w?A%aNS)a7|Q*Zb+CBK?a zy~gQvyq?aWyhrJM3vc?I9# z-RO9u6CC@*{!*5qqJ83#Y;IQ*(rry z+O61Wt+Z0E;H8}x_H(6+UuHt2!=k_zZj8htK!A?u1h4LR>)+ysW zvzsf|ST#p2l#o-Foe+9zN0k0bKP9U4Rrg8sk}%CU`q`b2#ld&*@}lCyUbFi8>Ld zJ-boZ4ma4(tQbmDyaRg?M{sQ@LTQF~bULup5rrL{9iiyF4Vx+D*b6)5P{^sMSc<7s zR4U-#xOJS`&Npst=UcbDVzW~oRZuEX5r-A=uid&%9p`Jeo>Ldrq53np zTfCg&&|MCdS1QvNhjAsh@)ccQyWhJtof^*f^wo6ADlWBUl>lCrt8z*e>SC}m{-wJw zRNwj1t?$%>`S_gROA@|ve;}iV^8>2xsEIINzf+OpDO{@wg`esj2gmV!eFcRRWt3zl zltE>cAKmIsHRne%syknh`K9}Xn?I5-A}4zCES7mc{e40vL4n`n8i|glA=mSMYGRo)VeBplX7Kr4JeD2oc-(5esKf2YNq=YYV%1c5gy*FNrN7Wmz z3NPauFOB{;UR7S&*YJ(^+N-8iRZ1!8$Sb9!$4hZlTKSojs?N{uPxvcpUV9}uEv5Y8 zR&}a4zqmi+C6o;8l|UtxU)?HBW#?D-7reNVk(1)eJ9u%fN+`d%m7Pk?Z|<*nG4_iq zzq=Kk3eN9tC8r|%4KJ!>;-n}lrtEWncPltWly})Hf{H5pS(kVAyZi9MJf_}N3Zo** zdbd1}s`c)E{BL)UyW9N>{tfry&*fT5P349BT&}77!`UwPAI^5We{%X4{0x6a&2#yg zTwAH7yp&&1`4ZJo{^0aa_h0u@cPHG1|4a8S_bHXnwDsG9Ode&xON-f;5D zyGqAS_bS@qUUEzD@0v?)aj%4TiTum%V{)FzkL85oDUW4OsjEnIzw|CrbIJXWz8!Ff zyWM?6&13l*tL^SJw9S1e=TQ>MLpiUK2PTw9axN(;anj2r9rcdDW8P7C+&czOc*o&M z?}T@q?rrXMcdNSvZo?mt@KAmr=Tq`3X_7yYlt_~T2|r9qz$`oL|YO z+;nfSa}#ZL@3C`Vj!DUhKq4lkOC-Ypop;&4C*PF|DEXDUazUkla*K}5?k#tdyAf{2 zZ{r)?JDlE?@5qIeg32BC*g+fI+w9ztZ^?y~Ldq?!Z_5YRUGE;?e1jX6a!E(LsI=eP z2M>7r;X&^JJmejOhrL7ah38op z_?veF=3o_<-brLk#HCD$ci>Gg6TIc!WIrSQ5h4DnT#^5k zcPY=kXWlO5Q#^xr(mmm3p!TFIldO2_so9{cSFXxeyN^(si+ z`O3=|-hX^8<_qr{{v}_L=?=Sd_9c5)xxUI?IjKB-bI>`;`4%-VdBqlYT(er4sBm@k(&s*xSkJr(O+Cs!KJbAF12H&Q9+q??-ljLN%rB z?CkJ;m35;y>PFxN7+XHcJCJ^)RKNdwWVuxzi_Xi=k7m_KDrAN>~l4d*B{rx3ZOlZQie5ZK;m*D@nDbznx;9?EUSuN78jo_h7@t1GSXR&%wP-Ys5zR`sN{-Wskpv9sA*=dI;> z9cm!mbZ(G#6Fqgakd{@=qJE@&sN_(i>QgTVdgA@b+`pWLbTp9G)7?WC(6f4CidS| zA2{r}@350eeMeoce4-p-eb+tWJis%u^NyNPU7;*j(z%zMi%vTCvUABv@1}DvI>(fl znx-C8a;q`*xN=NMgK26mHJO@pZnFD_bJ@w@rl&Fky5Jn8@|bc$Ij-bV1Dqzi8Qt^F zIVYog!8s2z;76!AsvJ?`YHsx;wYgv}HK*!#Tktyd(-m<2?w`&d&O7co=Pb;KA67Kg zR1ed2L^-UOYFs_VTjPm$N;#?IzT=*C4$*s9Ii&bh zO+BrgQXYG!(Id}CO_KXA6=$4x-AwpFY7Qx9l+(&1?+kkA>F#Ogl%u<6oYU}K{D6|A z`qTqd9#n*@yQdt1PCEM)znY}(R|2XZCQ)Iy!aeEiV`smTnX3~{X4k-fXJ?=CyOOL1 z)ZdkKYOD6>seT*7D5aaQrDNx1nrm*5-cwUeK# zH_lY$GF4O2G-VF2*N5I5m$QOT=I7Dxdlji?G!+-oGIi? zRi-Fk;f~wPYtBDon^QQKZc{2q?JK7sdg)B2W{NUd`5J#unaio|HuakE15VB8DdZM( zUpkXGovch!zQNz8%9ILo^3o~nzHpwym(B}kBBzs-iORS5MCCht9<`=a#4YSTcZ#5A z&II-+D)TuprJ`;T_n9-Eoe9c#<$L@CPE4toTa^7`=&3VK`BC{n8OP~(_yfLxDpM-% z7IU9E#oZ^)WBAm0;*6zooKnIq?ml+LC_k|pgT^W)-4g7SM30>8Zb|noAMuuM;KtqD zZbP>Ltj~1=XyWx<3va}33^v3YbCm`g;q^GJ@7Cq@V?&!&T~yC)LPajv7_Y-=UD(8H z>eX?J^RcRqTS8*x=5%woO{vQXo8YxMt>ZRhmBVe0qOcj>!i~6L7{yz#7j;|WVYe0j zmSH#Kwsuq96d1x=vlnvP;3=*p{me^mNh^3d?fseu~x&1jE;ErZh308C~z)JWSyn;Ixm4{>Sad>%H z-Yw^j$KSG?Th^U`%E0mXM6OE133xlMO2LWv61R`r8!pB_a{KtTI??6tQTB@ zf9UpOcbVJM?E!n?%Q)%fF5*u6!G2UM;-34vA5+mCF2fhPMWtfWLiQKApRm{6U5>iJ zPw*97b%o3Em2MZeGwh15WUs5c3h(T$#^18D+sR#nzhy_a1MGya#XG;rc`oX?pZo9oVT?bv(nTxj8G zu?6l2@B=Cw&gZx;{+6@dS#XX!+x22@Y?hmd&2(qLS?)~e;dx>+-03iZ=Z)owO?UI5 zX)rIIKb9{x4Ni5Zz-jJOw?Hg^Y>HbjR^b1f;!bwojTMZ&n=ru~M#BPM8+U1=sT#OITXKOBI$HN{zT~ zBsGSOr6#b6)D$))sb;K3EE21U!m;YG28`m>NsPv7aT121SSk$T)!45N!%~h|ZT3=Q zRk^MftHUZ4ro@7f|EM8Wh5f3rx~zh+%3N28)#EBVtczD-r*f=5>uj(dUXh(ju?DQN z!K|??FdNGhUYcaD|~QHzZBsQ52H&*t_hDm<}KE5jG^X;~B)S6H8^-DI6;Vi^K}U zqOl^dSga^49xDb*@%|(vHDOjrDiJFVOU6pP-H(-orDLUFnONzVBq>st++A`j(u~|Q z;MUw*;j!Gu;N#qnVM;tDu1IC#WnhPR2RJ1@1#XOQgoomXU=gc`rARHT7I2I;2DUL( zNt33l(^XBHq0WFa)u5Cj+3AAFf>t^+U8)q4j_~`tN1VHEs&tossijH>__{%=wB9Yp zemTBkNsYsI5u~SlHz8Fz!S{?(rR{uYFjbnxPc@`U-T3L9RH+g_Gnp#ouwU}qOE39- z0ZX#^EdmSuE?a0k9M8{0Sp4iyYpz@KT}DeCadkq8Z_+u~A zUU98RH`8wMWx!i$x8d6}1tr7eSUQ+4mLBq7kirbHj4)&D9r#Wx6U-F5nf5yNEbTdb zp7sL1VI}2$n)a5@(%!^g#a^T_DfSwdb3aLY3ZHWJlKHaqlJl2oO76#LPv8^IUc_E< zcWUlOX^+!X_LbbvV=vgzaz9Lal%}z-=Jw@&koGXm$BvdeiEAIcpY|ZlpZi|geRw}D zDR&_E-L!jY0e1YklXKrmyPKBGP9V1`_@ai$YCVcQj%Bs7;n}T+vA28_%VuSQLhSF@TF@hNM&{_Xg!EMjQLn=A~PLNW0}#jnDn+vGOWzjv)CJ5;yMZW zM2dAUc0ZP4-H$zh4`M+}Q1Lt_ECUzTb6&bsYEmr!|9f8RZ*)a^rN4$D_EW8pbtiT= z7P9Wf?#04fhpd;J-A;R{zrrKzgsq5mJ9a1bLcg7MC+&s)5`UrJ;bo4p&wsvY-HP3g z<$zHuhjlY{E0z=HuyR^AVmD(`Rh~g=9X-9sAnNFK@dsuGE2Gs%Jky`+eZ+J9g?`_B zU}m)Lqj%stRwk>jc&b0s`%=?KOji9O0H=^N8TrLDI908urxWQ#Jre8cwe>oB22mSj z6#eM!EAE;1%}mxqW<4-_i$3Co-Ww(7o=)#Hb&?to$zqZ^8LzKTQj=jivg+%}BAuv3 zUPhQvydxfw@X&l@rnAypkIeK|2CF~${X~E9M1QK^HSaOyE_xTfYw1=m(OV?v?uF9j zuBq43-w`!YCeeT?_4Nk&L}m}5x4#%59_vr^JLX+ew|a_RB3LLD%U5oV)Jw^K5JEqP# zY9rW4Z>(3N_7=RQ-`1a*ek))-qwA?TSUk`l>Vv5tB)W<2By>a9V`J5EYGZvYYNA)A z?>4-x-+_1ZyZUnyo|(_hB+G9NAz`o>BJSz;^&#TE{y^_4ZtzIzDz3+F#JZAt9pk3miKDrDc)yNFy?n$<;g#VfOSSAR+U3-hI^Sw3r+ zxU1jOhtWG!bQWDin$;Oe)+g={IX6W&oM zoOKYd%{Qnvob&NWIdu*x?;4YiNW_ojdAo~OKFSx&9 z;tMof95Sz)H_R{f%ItlKzR(Yw*VsFZ4w)O(x$1lBM)W@1#A*-;1NA}rD0Q^jpVa31 z5%a3~pLqmbgV*TXtj?iwGuotXpznS4E4>mEzCvH>2g$u*e$J%fVlX*_^uhW_b(H!w zHDBpp>lO5hup+CYBp)&R>HV3~54F(OlQmCWPwM;X0a9+72hc5ekkuA-mO5MAg66NYPhssTb4xlGg&ZU^Rs4gW(8uq`FuCOdlz};U2!$_mg_dJZ4_u zE{>t2<~nB2SJyFrp1PG;ThyU+4bg|{!_^ULAM%Rn-_rXHET@-;^Lz5at<246+S0Cg1_2nVWz)KB$YdP^~qv=RDg^H2Itqf_RO)c>IWsF%ij zkXst|#CPhSQoj?mf~`brv67@g>Q7YssQ*M&X?>KwlATdxj^uifI#}(_{!jWD@=u#* z%s=oQB()Z2&C9ILqBG`peFr<+Q5$j2yu`^lbk^LaZ`a$1ZK$o-s&CWZvaM(*&hwnR zWS&Ro;8y+ZPCK4`pK*O2Zqc{uoAoXFXXa+~xfvHf=|Afxj0;nA=YFpHK2>+A*L}Ox z-KwLnP**}1cewvi`bP6-^A~d?`W0?sb%XlrzBeMH^jhQ=aq%`wYM z-)?n}dd+to-)#Ow*JiZIyy@GieyZLi;fBxVwK7`gM{{sbU#_lDJ*K+)2Il-~Za}}8 zuf%KSNJd8Kjj)+wiG==%x?D|A@9A62AIaW=Hk&c-;}<=~9sR7|^6gM}s<)VR)Ayh6 zns1M~p1j}8_2_rgV(J*3U#7-ok|pD%c*PV)bkV!&4pVHACVtU>)zieU`f3zMPqd7FE<<-6_MuI^B`a-Unwt>zE7!bI74 zAzm^u7jstYuIQ|HfnAt=$G1)0uHK>Rwr{Puj-0h-#`mp#JMype}@0SUnTZN!CbKjRa|)$geL}m#F#m zCF)YRl$0DIr&t5m=xgCxeVx98Dcj8*=C}AizJ=-{^&j8Ac#Ju1^rzw(nR!S{h&-ab z-a*eJI_MqssK_DK=>_zU)WvE6rsUWE_Wk2qr0yhVhq=@I22Z2Et)7P3!5FJ2;wfnn z5v4bR*6VpiJH0(@Pi{fd3g`v(57m#@s(oU*f4EBsS`)Xp_Fj{DQqbXt$XnHt}ra569wr z+23RC<$3uz{G8QZ&Nu5pks|h*ADBV70Db_oi=dcdt~6JfV|)*M4}D{NWATODdm()x zDh&Vh{l(5-z7N%fyhH`{MeHnufB63NO*L20JrzwcYlyrepQwTIi<(^5fbDpV)D$`N zoO(@>Q_lr+y?q@Tej{L{pjnn@svDa{>2K zSpSf@i}dQG=NGj|t|?-M&qy+2$PfMG<|H{8=EA3&pO7~lO*2O^>9KDV(;oRgBIiT> zBmJ`P58rs-J*JIE<9yY~Eg-6i>UeGPYr&|VL!V?$<{l=Y)o``B#{7W0DWZR%FTis! zFP)KtnaM_O?k8qU@ZBYK0vhid$xhUR)$1^~wwPgl%u6r>O*gA@X9Y!7^e(K%D$3OKMwH3vjJTmOIgWC}x6hx6zB}B- zL^Q!Sg2^X*OZ1DrOYjnRFo8*H%?U`BCYTdh&1BXLxYS$*m$911J!RJCad$=aD$IOW z)aBmlz>pr+>x!@*(Iec!eKA+$eY41) zX}(Wx7X5vc70zQ-kIcHFvZ%t8%19Ss@~(;5)Xy?!n@jLv{N&-%{!KGx6q&ijUv zdfHc!K10kUE1N!7e-EEyE@u85G}~;zpG{5G8<0t^5i+jB>*9u(Ykox4Tr|i0gv^ii zh9bKjgh4$8rqEMCR3y0q$}HxPo?V~Aglzf{CZF~VL1*9@-&tRZk!su!Dd?tHPTD8> zd*+8scn{4r2UD?JA5868-)vGEirFM(*UOWeMU-bkW)U<}jGOSLxFz1F_dWA{a}i#S z^DLqq$|_cnv0PuF5AqH6WjBJxEs-7F7Ax6Vp%3&8@~za%QkzwjMcKqW65coG@t$KL zT*xY$k=?j0vY|U-KKt{`ti~O2S7bG^;RAdFNf>}u>19NAvA`@tQZ`WrWrqvQ`DQ=% z-m*07{=NaeReFCkPVaA)5~W3d_WPL~&C%u@nHYlUX`E((6!*SN@(3*wAO7NHHVqQ;c!-ellhnaw>}+jL)HYd4SD0?1m0tuV_G56 zLYwL9=4+v~#7~LSB7NWaW`0?X)T4kfi4>S~^)r?5DypTnDL-F)4B&9xTz zKTP>s|3{yOpCl!taZ+S7-hroBbtj>l`L8~e^MBDl`U!DTyknfv3yUJ+jD8kxrZv~P z`ZfI(ne)<`sPkeOJ)GdQ+{L*2C8n_4J+Ai-@A)w0;IZPF5!4xHy6LGzZh& z6ZJ5!>XYfdimvF#L?+{1;~2G>j3!!7UoT%1ttoy=Kdl!Pr%*9iOcWQr%z@@0vlki+ z2a|PDKcyEJjkP9PFJEKS+jmqP6Ym;Fk#6*+zL$A|iW1_4eiA<-jtbp4f`rjXYpnJ5 zH9~!SeW>hh_Av+Ghk5sA7>7Y-c!bq)y@V(!j_W7zzSQ(F`a06H2RsBDGqSef7 zZce0fg0)WTs&&)Wp|x67;~!DQsA~Kr{uWh@zr{ad5|tCJ@zw;Zg*hIzH0^*B_)oXd zHGK_T-L*BS2VBc)z1D@i^=O^uG2IPRBdw}Y*{DKxW%MunS6mU}NNs73L#@ooR#USX zY-UcftbiT3rd#N`o(PQBC%_5%L^x6R0;`$RL))NrX3hq*UaLg*6;Yij)r{)KpW-hu z)*5HEGRLCU<`j}ATT`qiW>Yf{X^Fr_trOiF(FV;7T-R^te8C1^MQ%@R6{-eTv#MxR zBDo^EDr%5i-Kb&wA^sFoNtIA7UDrQ>|%MBeSuYkNUiUe1U$x z{=OC3O43%K>RRr=Z~E_g?m!$bZ&WaT66Mj)@MrOhhy{Mv_vx`fZhSg9)2!)M1GAwy z-D+qyGMAH4U0aT7XyuIZ#xEj2`S}9*1ATmbefa}@ef@lCfqnXZJuMK!XV5#{`h@D5 z+9#+MT+XTh_4xy3jdCQEMZby+(p_;6-V^uXeenQ35D(!)@d!Q=kKtqS1U})tO9m;k zk;TX$WihhCLp+8vNC(70P7jJhFspG_%(Uv84a}L`!wf4|V84Dq&lNbJAB1VF${1yh zUqu=8oA{Xfs-?}c>YDY;Synx>KCDk?&OolfL4BF_F{jH=ZLPFX#`sN?M!$<3ft;M? zK!^0%^v<%DQdL`9it1>kjMB#Mq7>REN*epbepm`GY3vsV#2o5pTXU>BW?eHH$PqZi zf30>%KdjGXXO1=3s%_RWOBe@uNlF+c@krpXengK1j_5~WlvOwo2^`gn8zp$jRjGs4 zQB$RkJT_HnlCJ}t$=6d8n6{-;VCwN31A(l*0RJc3neqHmHfy;RI7Zlsrr zlhei;VU4uztJ}35T3fE$SZ%Fg)^IqSRUUuAK%qb$f1yC(Kwhr%_#dd-wC&mh>hG)b zMIEEAF;C1FZ&}x8k=8x+zPdw8`1AM+2OiS(Kz*og)wXH*{Ef6ezI>$R z_2=^!2owzD^Y`%;2z)@=eDS`RC+ZpRqxwdBYbbf`Q9J9Ax<%WnJtE|Hx+D0AYJ*L%%^^FEb zOOi%g9jqbD?10)^1?bA}cl|{IMfq``qJhlNWA&Ijd89t(HN9DTtZvq}Xm`}R>Q1;* z`xJhvy{9cCe}PyiY8kbSx#B(105&ih8Xd{+V0E+x<1Lss2DZc<=41}sR`00qX$6^E zz+cc`Uu&Q}Vaj855jhLRBAx>^jYT}~YZ-IIT+t9VH1ZjpNb6{IvIgO{-yz3FSzwkx z)<7Y03i=EA>uL41Tk37{Z=v_$``SG1Dfv&-*&?5j-6qt(?4`|E1;w43TJb)NQ&-lwYNxBXcIv&3wX-FQ#2wff=L)%n^7+I95R(KwGF?Q?KK>{c(TxKyDNaOc#ZW!p3wl1MhD2rM5fj zW=#{*MPXwaDq{SnUQ-upF@J7}1mV*cX(iP{VGr8-f2sZP-58cW1dG1pis<`^|Ot&vauI(~ zf34)DylrZcTr;^e$)&8)RzrL;Z|CRgWRfRolX?H~OdY4aQeVUIcrm6nvx=eSusEw~ zq?hnlOD^Fr39GZJoxE6EqSa1b^7g$XQ)(s8GM0&t#Vlhs{=V^%SPU0)e`Tx&%q)XS zTSduhZjIGmt8dh?+Bkd)(m<)- z$~9!7u3<{qB@P_saoaaD#<~AJ<{qX z*GpcceW=w-{!sf!n{Lc7Mv3WYG#o9)i1Jn)tFBcZ)r0j&oKC_tZIpIVy`+xPM&p&p zO7T}pu8h|wtzPmpW4bX$RIqB(T>+K18n9nKxk2(mZIRX>`9B`d6_YC^r}!(PRG8`y z`KKDw=$eYg!m(nU7|EPV>PU21tw>r0t3qsmmKy-{N<7( z{wOTZsxk?ctVzaXV}ht+)nHWxRkq3|mrIWNCmNI3pZHdy4C@^JGRZmoIbm5=RjulD zR7F*+3C2WYqL^Sz;+e&@m?XyY+)F2oHzwevlglLM^dFBGu#Ux#$MahStap-TYO}O= zk}~0o0*#Uv1{MVxCO1mnD;60a8hgZE@s=MN9~npE$LKqX3R)-VJsv+1&u8Vg76ca3 zw*WPUjgy-se@Mcjz=whV)COEPNNxzPs{g6)Ce6@hYVR^BQ&PsHcamml8PRMwTbrZp z7JI};#%{FO_>Ad$#b;uHv5@P9#vbusColx&bMlF}vh(t2y@lICi?V0wHfc}t9) zVwf=;E-{7~Uoz_p@g*Po=5syY_`pb}ueX+&1S4rF$x8xD1OKT1s_zHp1qvmgOG@(NTg5gp z%D6zy`S^vnW!aW5sh`$g^Ck7y2EZg%vjfGFizm+x%)z&at<-Npqm7Gk)3U6KbX|zg z3KUN+kvuC zFPM}qDSJ{uR3K?v{CD=Yp{?-&fq{Wf0t3+Uz)s^+<6E&4eFwi2-;3?>->BV=w#Bzl zy+1yP%7KAFyyicKL$zVrpuorM6(YZ2QlX@*cz$MNhuM>YFqo8*)Sn5<1O3s8z%KGX zHFgPPB|KtHq+t_-XS3=Ry@hH8Vkw?TpJ#txFVqaVa>Chju&Qnf0uiPVGfo$+6oxfAV( z520&tph!{@pVJp%O5vou%u9u-Nl$%wlk&0JX8a(26x)m+#d5fv)gI$3@iqLK^iShI z#ea@}ihhB=kei3@r@oV#tN|#Ze_Kb{ax|h@gL$p!XH`jOOHv6P!b&rWji z&*I;a@fq41?@s6BKzA}G1vVHPjWwbh>nVY5>`e}Q9{-lw&(UXbE6GlJ?ORX9TCv_( zE7rjcth!P?HPDrgDS|`aHhQSZ}NoT{xQ-=z^xhuB_G?>)3~4z39x|^uQWp zt+8ILK^w%(`0DtY_)N4mJ_CQtwefZFeOk$+Qc3%?Qc0zg_H(^YTkIbd7#&yw7yFm^ zM+Qa(dKh0CUl~1N4`Vug>*BLWn;HLI+ozRIIzZQc?SNJysbtbe{>A>$fu;N!ftIw? zuO*G(dPHC(97$p?;|nr+p`J!}vc7^}8DAT-Nt+d)9bbh{i%%zi8d?w6$2Y_eYCfrW z(n0bMXa}|8NhOkg(|%{}Z>UVths+xj_|QKlFcyBqY8lg)`n!?)jnRz>UmLxR&zamC z^)lu#Wp;c{d?h}W^o?*D{;T$zRwn6JR5s}l6Ax;O{9^;H0*m|~;ve%1d1}(fBro%K zCHGsSE7{)|eMs&NKf|Yxv@t%HCPWs^clhc!*|Nr%Zlq%HI> z^0x|n@;{EQGO%su?RkrRXQy#tw$ImLY{$-+nVFfH={II(W@ct)Ue|3MGcz+Y^Y-fh zevstHxs#N(aknOE@oT*jlZEhKKs&;xgVqs`texPUm|7xf9=H{B5`n3JLziIvVmg&JlpD!Y zX(PEYcp9cdVoH*V91>HJAowt*X4t(zYX&R?FVq%kQ{gbho9fMj9uyCWK{5qSjpe4e zeUUZ|=cjtpyt&ZHINL;?Oq<9}!Ba3D5D#Mg0l)%V#3oI&rr6a4SgcLQu4!I^ctEtt zB-&JNCQqW1p^b6-Vy!W-M4Lz_(PnZZOiQ#zz*21j=H~JQIuY6s=ay;>fo0lw+FWiS zkEau$4RCIm)&N+pwekjgL%fz=tN-UA-cWCkyp%4Zd*o#_PVP%CiI>H`!EQY7McPn z$&D07XRV9Y1}Xn}ZM^>80Pp}z&5$$P+bQpoSJ0inO1cl8d*uP-ym&zzKt$m@_yT-; zlB?o1u_w7EZUgtil+x&=b=FeCIfY>w+~}d1Ku@hL{M+Dl!p-2^6d2*{mtEqK{czqV z?~r%OE9nkk7##@z0i*}Kw~5T?sa4k)oO)`hjE-6-uqt!}cS1%xuOD370d2hmIYeBN z0MGsMc6k^bPPfB#80`+HZDMy|J9xXeLmUMEfy6MXYc({(sG-#aGfeHhK3-q1JB{4K; zC#>w~b@F;aH_Kb(QFJpf8a$egp`A$=vP;~@^4 zN!~1vp`A!)5+_C*b+o!#v=IZ{h_hqqMtLk92i}A!%BZW=)1r)M=mvQl9ZxsN8=;X# zJ*~bLX+%NS%Ny{xQjJKXzNP{Vv|?TZuc22ADC!+GXM1zJW8kCaF>{tT+uKhM%lqhl zdPqJjGjSLhPE0TpO>rn0M!xEf5i-8&-=M|4`fw@^6!VI}t0B0d*9hFmYwR5{=X%q@ zN6k6lIk;LJH}`n6z_XCY#UW%U;qWxYy>uTk_X0=c1Zv|mlt2&4hrkKAwj`j*erkwJ z98SLIU-gjj1#pe;x@|aM$M~ifMqU%IFp?X4CA@m*RRSpP9X6+XGr%*vncyRsPMC4t z9`GLYIAQL?clrZ#pSWKY{-x9T-94=@I#;98dQ`W6_z5vEpDdg#1AI zcm0PRG%VwXZW*@mS^uKDVAt@Bl3rc3C<&DC3ZYjM?~r-eoC%)kb@NV|@!nqWUi@3* zBs!oCJt`lQ_t1E#ChFn{q5&hxL3BGnlOi!zOp3?EV3HKyj|P!X`e)rUJ^^9lCp!Gl zOChnOSIVmcEr`q};3jwspF-A2^PqXi?B*S!d&Pa?A$T67$wZ3R_$Px~QZb1*k~Akt zL=758kIBpAIJyV=QU9cejgNq6{L)hyL2wXxrM=q7DGikJ4#2lNxVzT_d=S%VB%U%) zoAl%jDg_a``Zg7x#*X(drQWfDgK4e9$F>fIng?;v}3(}HAi!sn6bdMM>9)ag!dW6P_d&Kwp2b~yY z;Zw%jZzf>xezUXJ1>6IVv;AgIJl>+jmZTMl5?hhh;Al)c=`OlL-U+OfkHY5&eFqn6 zywl%9%Xu~6R}Lua?KAhAUBF$uuHFv1ldhC^0ITFkF-mMr-sgI8^}3 zd)w%Cx<(F&s@R6S*5Bxg@fz?OTj@5O-wLdiU+I1$!g!@e7ynu-tOKu; z*UK;US9-wMOt;YW@(UcP#tZ!=bSOJ(o->ECbLM$7rI*Uf8-iVffeYXZ=0!6I&s1K} z%MDEd?|k5VUViVs+zD5|``CL=zK_qtF?wH)6OYny`d>JY1IFriO3<^soL(+)E==>V#}?<2`OxG@&hIV8-bG{( znqD-Aqw_E}oSiYxnz!XU@(FqyI7uJK9Y{y=K<-F7fjg1=@_79ZdW{Fh>7(>SMq*=> zp4jk#M`Ien+|>8H5$v>i#vB2+;cNuEhsQ}WFF6vE0R_MX@Q5AA1|fGKaLKgM)ADRD z2XrJ{ea0>MBt1oM$+w{s^xw#w0F2ikqR#_)37Rh^OYk^LAub_QNG{GL^N0<$MF;GN zf;fO(GB=q6*g)t=v>L%ivQTO_wSyEJ?-fdh4s*y{B8U_9Ur3k;Owb?6?MQp_NN!I$ zfIEm&60`UCx@e2T83H|1NeWi&(Hp>O@M^k-K1Sjrc{scu=(Eu#kvN;of%b#bX0so##dP5i z@?0;gmkpc^({=fVyoL_bhhx_;;34>-{z#ui5{Ze$S!6c!iQI;?B~RqGq#d{&c`Wy3 z{n!?>FR&H7)!b%!@N~VQ*!@Vq2FJDZntUDl6nme@GYQ@zF3u!AQ3TJz6vleb3wv3h zeOO<%&747I5>dP=uchngRrwlph&~i-pE_GW#csj(~UrS>vIugL4@dU{1( zPd9+CVwz57z-KxjiG#8Gu|61hqE91|NW^JmI#!*mfVHqndnCb}7X2~&UE z{zAVXUz9h~icS@;s#nRW>{S8pH7kRwcom(WF7r(9my2&pV8dfz=KXXR@Ud(hTfi4W zpORWx41U3(t$iBNj(EmHY!Q6}W$~)-pEk?sd z`~%Y8i?78u;u`W88879>`>)SHN2G5#N`WftQix;N|3l zIG4}k6WJ0zij4-B!O!%Upy6V^gqOnO`6ZgXAdk@TrThqZC2!Fup~V(pv%VJ1W`fs2 zt2w*PII|j>RCUTamAv#`S*IMdtdri$;C)4>q~LGRm*OjNEqMuyB1?H`Jd>~#xl8yQ z^k~QC@VU@`E?(H~{X_r1?k9BqD83@HsDKsG5B7^M$wTr=J}y5*yI1lW^ysFqL6@1} zZhCipE3Rjgz?0Cmy0gpNZB|FaYEBun!>=9kV&E=#(a_mQZpUT=?b$N)S<093wy8^} zUdG$wnZ+04C^DM75MM$ckmK?R`2jg0p9DX|^cmegiLcS^6AicU%8mSq*(#X%?&Em6pdo~N`z@Cev$r$ond;xt!h)BgZgo-j)hVOl3o|ISV ztKqx~=%Lqic9=WOnsBb+l!9wUuauJsSAkMa8ZRw4Bd!ODk)8+~34JC$7srriz*sVq z&*B}}OrRrsi>x=~Etv+rhm2G5J#tDu4Ze?QCDMB6D}kQ6&r{*#0}^{Bk(m~p)=THj z;4^tgHUsFyo{G=JvE(T*4m^&GCwIwd`HXy*+=H%wQ%`*b&`U4jr1NC2gi{hKdI5Ng zfX|!GXYfvJI?$Ot5ub|V$sKr{k(Xm%FMT=CTbH~D?2rJ_dn`V|n#aHdQrwX}#VhWV zfKKDnd1p2a=)!Je|5^DqoX*J0;L%%O2K3R3Ig01^iaEuh1V<6z2>245^LtCNs*k=D z=&Ro%XXSJ9Epi)5aVznPI>j97-6ZGa^YTq{UcLang=qAUy?tYP}4?b3g0zqFnDF8zu1 z6rN9jI?i*e7u#Vzw|3yG=Q(npS zsSJE1f3$7-cKwgGUEcxTfv(@tG){ksRxhkaR$Zr_^T>J(y@WJK4j%JO-UB0V4?|=BGKTw7>O>w#H?mEb1lzmj^d-iYxyW%kyfJT zNiFoLNo&!`WD5DJ&C+MicnR$F5VDT znPf3X^D#V&nHBm)`>M^>-yrL?^~UPTy0JU%OZSy~2Y3yBjlBD4k;l0Y~&wj?;dd1&1jD0<9J3h6SOS$T_RDf58pp?j$MXqXk^Isf@q_je z4j+K|`faO#Q_#6>6?6)L?_hf1K7-!_;J#a$mZ4WjY2Yf6vGcAdOA7S8HeX+$zt=uM z@u!N+3H+h^6#E_m58PYUZL5&;PFtWa)Zc0Ep{3|ma*dRtrJ;{-wR`G50v@_0={0hl zl%%DgH?6|X6Za-|7Ito0x1cwzCs_AZTc|J6-)irmCFpf>gOs2pp>MQBxQ4#b-a@y! zr`)g-k@GAX(AkUqk#*Kq4qZ5#Zzx<`UX;d%u4U>y%m<6YSCU>Eil$8V9h z842fH4rh~bR=_N1a#qkRWEzYi(*TN?wc%Wg)Fw%#WYS~$NPH|lrjNx5lu|63bGFIdjQg?) zIPcy^W&?U3Xh@&@uQR=@UD1es1G(3=8(Jbgv3@c*g-_)tk$57w5&O=&8-WY%4m8;g zJ_$V({Ahi$4h271=fQ_DX-sEDO${h!CS?`E`N8GG6~al;A(ka&`ON}mHBud|ssX8_ zxJl!+N>AxS@saoxt)9?(=+_8*A9_i(z_7(5g_Zyf|KSf_%M_+)-6IGIlYPr*IefO~KOzg6P`uB25-HIhoI3j7w6u?sQf z!^zMyDNDjMR?JKS1kHNrR+l_OpQrR0eIPy*@1jd1dKbt~Zz27rb_>@_LBFUy)}Ck= zwM!bsG1VVyr-KvuBz_tlP6ZDH4+bw-yU=i_yURW19tR)CRG%n( zad6)4#<@qK`-2y)OVl#PRw9+5 zw~$nb-a=+UdJZ|yv~$37Z4aE|+&%6Q=)U0o;AJb4MX``skyIl8#EO6*RV0FxNVQfTG}=m@1Hp_(MJwfW(r@ zB9Wp3u6YJtFSIk-S?FH4#k<$BqbMy;D&SX(#s~KXuUPTGRq$2onspj$UudU+ms)_S z%rygmXYL8c2d`QC+=KAg2kdpP(d+QJ1{9;Gu;Zn63U~#6rM=eny9cm#Kd{e@!_Mng zTyPKcDpnV#SAi1XYnV=A$7}5hrV@0byV_mjPH-oJ_uFTK=YmJ2Mx-%0CN(6Dz>UaJ zDJxIKf^46CE_gn;&psc#0N#%&8&Annv23_CE5E4U)9z~*_50cb&8NJguc=RYO%p4Z zaQ>n`2`LlZN$x7>c%-cXuW{G9S$I|+WLW@&PJ~H9uBb=~m1OCJRG%~;C!_|XA-EwqF6H1USW1=y{j>AKQd825 z9F~qi<8eL3F)My;7V~-zpdTT zt|Iq}eolX=J<`r0|DlE#RY_DLxG$12)m`Q;cc%g?z$?&Z40>z;kA-GLlE5Sy%??SOVxf21XV&q1f5=T!GFQV!XN z?bK!(^MG_vDohRlMaXG5oRTu|j64zBZO7T0gR0v+6yl3!4Sm1wm>>I zz2JM$W$3finr+RoR@t+G)pjR$5E^v?I=b`WvRRrBr%h5nH0ewG(bA+0dBI+?6ubaD z_UfH!7y4T647`y$y92SiGtkLh4(Daoa*Hs^mRpp`Y#zL}Nb}&gS?Uj;ezZR=MM{(B z@Jh*_vlq}==(5_L1+1|<(a!XZ+zEIq=hq7$D?hLgyieb+cX9i>1KcjaK=44Mu0Ymu zYo;~JT4T=y)`HjC>+HG6+#<~dwo1=fN}h^8W2tx${2Wt0`0dvRphx0~$evm(cJ7CHKzXSR#tlc4X zcl*M%JJ8L|t>?k{+`vKoF|)YMAG0UWcC}=MdM@CQo)h{%KBOPkr&v?1O?DgFmVT1k0H491|tmvS4sP25sIQ#Y5iMp`SC#MIO+2{d!#oR!upE6&*i^~XlUeq(;%JL{+npaW?~ zWgr~{9z;7RIi+0Kn-f?krPRyo74%ekIcO>%r5^9BuvS{}PHIkAJiPWe@eW}ttliEk zYc)6yS^}BP+|q6%G%5|0ayuy{$pG3(iN|+}PDt#iu^FS^A$?UccE z2yLgdhjvD8C#AEpM~av7NUM>P2goh$a#mYwtX<9;Yb|&;COP&8`^n^31**n=VPC;t zk(V7EH%P_Z61ZQ*f#%@mZVNX#vMcJz^%PJ`FN3}o5Y%@%yPUPwKJ?k^>~lOG=Ebn1 zgjl-*Jsj^m^~QZjU^q$dN?gOg*Tv2yHBMuA_Ow%nC6oPYknagu9hpM zd}y8*yc+KeiHf!8Cl(buS}veOp?_p-RBQpfL!_u%3?G4_KufnP+ICS$>@Rkmk=X0( z2AE<>ioWS}2iAp-sVUFm+RQ zO1q?P$}VX)c(>G5$%4k?r7Tibs1!?LZ!ihC$zqX|L66mwLMy+k~x-$g1F0bn8MhVf92Q6Lw6HTEV>;ZKbq^_CQK^#TP5W(+AuF z-(t6!iM&j@iOh_8B{)=cE4g)`Tb!-VIIE@7j5en&l~&MYWv`ev*iZ*6wAKr6$cl3UrW<<NQ0w`xx;3${Dp193rZiVt(q=#_s$pF=UBlX}dQ+tpZB3gh&7d2cjo7sT zm}DivitIYx!VGPqG*w#DCcuAmv@qXY;EoYS3;*Le?p*K!caA$snCH$1&v!=)V}-eH zFL$gk209K?FK{onw>uJRMhPQ@{q8(>gm3`=S05oH;D7BSaAu@1UKl6zcE0UCln|9CE7Jhn&MsOFgWo)>{H;^s~M~Qeo+=?;O-mdn&yYKaGI4(mkwd z1+>&HI2Lp*pb)r_Ti6Z3-*KzhRpDI)IO0^dA2XX*M@lujx^44=&SG;3`YZ;F*k$Os z)NBpUR=PraDZLei`k?_jQ<^0O=nkm|j(aE(G(czJd*T^iVW|kXh*T7O7Snm$>vO*I zz5-G~sRcTv(OUp%^@+j+p@%yW=;;m@ll>Zq@A|x)*kX zKoQqP{}4DIR7HmXt!!7Zk2sZqqu`^?F=vr!#Io2$=3?k_6ThGdoCNpe0y>=co%Wsa z6_sS#Tj`_7RDm`}qqO>eI-c4GdwOfVl3m$8=A=Sq5!Z9`BFzI_ccHn+WU&hYGj;`> zmzyihsMu&6N5{s**0dk6hpeXkkUauFLi=X$O{X{0n?ot>qx4lM?W@!V%a~4~M=|LX z8Woiy=?rNmc&4P%i@tnPe(9nwzf=HRK)T>-qleJ04e*~nNth_~bSDAT-JwEU@VYe= zAF*M=P~p0D!&+c|=3n>%(~SKLUI%C)L77qozFs4TlOtgx$fo;ACNvP~Dvj)Nm`<%bev-1-l}2zPZ5s!c!wL>^6b7 zqSwaWT6S&wK6}8T(KCuh)2Y%l>4YyRS>TgUi4vqsKpka@Py<(sDZ*svU}1~BD>xX5 zLxjP?uHf!q9r)C?>)7|$eKyaWkF0sXSDprmsogYgPB#}g7p53GMVczbAS;@dx0gFB zobq-BXk)zzS~UjzV80%rANN_3EgkorfQnS2brcb(t4tMY;+i#8sOnY&Pr)<@eFh7I zgiZEldyuf%-eQ-tS2!!3a&~!WTBN6O=bH1(uY4}>jn_rbI(A+AF1yEkw60Q5@lg?) z1l?ljF`q3t(lMVSg}}!#HA15Zy%7-5)44g|mkvnl&N097?|hCq7h2X{>8x_fB6+3L z5NiW^LqOFNQy;CTBnIj$M}5b9A!(XW&CTpi6Q)833X`oV)<9tj{(zQA`ccRMlr7Ig8sLDFcN5!a8TYQ`%nb ztO1vSW^l8*+1w03c5rrN&oXD5Ke<2?(S}NWy#XBR1Cjb+-w~fD^@Bryp_IMGS?iRt zOG7ilA%j~Ft0MJ!K$QNE2-y3NG*lWXk%EKAU!*V*uQG`gR3ViSDTMH7j1;cn-zJel zDf}BHQuu|}p+pK>@$6}&a0@@}iWL6gS%FBQjouc=ZS{8Gc6xhod%Xj=gWeI`QSSuq zq<02)*1LdH8Nc*Q?hM@DO!!!51_2$^t{(fvyrDUFrCom0|Y=kyaw+NCfBus4$%aAyfKg%Wl@VIjCA^bcvQG*SMLztGCq+f`SwCg4`V zab>+KxQbp4Tvaa==5DN8C>-l11t)b2hO=39?Rs`LtDapST;I-W)swFK>Pq#bYrgBg zhHS05&TPmUK`Y5RtteNLlTeLTlJRs1Eey9p;R5hU<`xJSgf_;yMyxSgW3DypNOj>< z2e<*g;k)UpjJ=iQ%JLK`39T%r$G;gGuyy8ovjJOgZU8sLRA0L4yXLEp^m2B**J4NxE`jARwFyVozcn! zZHC0AtQi|EuQZ#n7I=SLGq%!PWj2zQUz-3<}{4d~=uclN> z+U2W;R#oL{avCYElnb46T4m*O@@G;O_(F;!y;!&otINilb$|(G4eZ(Nt0C?7#er*L z%5DAPzjQW6U&X*n@1?}3b4x3=+v3~MjJP%TGTczbP@F@*^B{kqyT`q~e zCBo^f^jMz`C}iiw`aD)GRvUY30Tazq@>lYWl#;)Z@8HsyYRaAzmTJPGhFlGKdwkWT z>d;bfD;X{oj&Y%KDfv68$!f8QW=&v{SykHOi}zKPszK9Qh3vxkMT+(Qb8CgH170TWPE!c50xgU0g09|0I>AD$-tGWniB#Y^An}+F_s=xR_ns zE(?b;;bL-etSkon0{P;hZn!cL9#<-*Cr*~2-&Il?)^Nr7D8WYBa@J}bYK&dG13b^7ww ztPk(YTd~%R$hG9!G6fTGO=v!`snkr$D>jpwgY!X?!!ubp7EZas>EV;kN$=#f@>%Jf zpFA&kra8+@@65vYjx_KuV5M==LS=j&Ys#{G$amN$%ZKqDM20_=d-FcX?+yIN`k_N# z-jBCnEpgnEwPF(5)R85iE|_4-BQ}>>NO{D((ER9@PfQWc8qO9@0b~bf4<`?EG|LT+ zg{F4WI0dZKKtU@5x}|q|@!tGD)(dFE`Xj3!SI|n975Sj=kWWNTUAX|9^NR(j|`FK4jOEeXkUD3~717slu6&mI_E29>~Yj7VPiP^rk7=0cyGVsWVixRq2~a?vb>r*oGEMpnZcRE!EnfNofK9GNNEXj zB6tcwUb!1w%Cc^}J5+^#K+Z1afM<4~B)FthN^+c#lhSg4RF(~AE1VTsS)8uC8!yYc z0_DKvSa}u+2UU)g_xbkw{!sz`|7c!0A2^?!U(P0$l1fY2#OzQ9K6cm%XZW8wjss^P zX#J)CXnwg1@5;-wtYS8?v=qV`Cmaf=hgy#91TE`-09%%Ab>>~LvNKSD{h@!c_YY7& z&Vrp~q%2|?sVq1vrl5n}RuFJ37jB`j8%_u9#4E6htP}4H{Z0SS0`hO5Ah@7hNX{%~ z5z9(mI4#zCfE!Nb1RclvMSs&mayXm@w}b&N{FDB|nV&#mIVDzvtdveF=nwjn7M6bi zMdTDt$a1X|PD*GB$F&v;DV&AE0^zF{6HXHT2L9?LF^BSDJc+46{dP7dyW_VbpkXCS zj>Zd6!%DPFV~UE!L=r<|{>R0{;^G%CNmvVi@vuMq-HQ&#fMfpWXeKd-@fct@csL)y zb#pKu0v^JLf`@X=4A@znY)-(QVrB(bW7Syzc@cKNu8u3SVrO@9IEw9uy2y@^UB!c@ zMj!mq1SL|A!f|D3pD(qt&lf36F(jtAC;=rz89ix?3eSN3!;1<>hku~kcki>Oh4t`f z?+Y}fxJnHE=t+#6L{6hrk}6AS;FemE?Ho={N46EHfzG-aZN``*xELeFln_Orq^Q7O zj!|L?i$!o;L@X+Pg0~+21Q=mz%XUtO0=b+>yDF>3BGE*(e|nMOsPIqpK_|G5;8DOx z&dfo4FnBOGOh-u~YqFz+plOu~Qbj4PQc`vi?Nqs);!5@-%?&RcNPT#u`aX%6Irz=M!vnw#+ssbA>x)BEMAVf3=Au&OKy zZ6j@B=W=w1*c56j@976>D~_V!L!!y=X*#q@t3)8z9}^Ly8imBfF}|2m;8J2p{0+BX z-fu4uR>P_pX|~`h(2`4V)g1{iz=p$|Xe372(RL+PnMK=`Sruj}ALvJFDK<1cQqn2u zmGV*rDN#&Fbj3t5iJ>uAA8r4E|8MV)=MP7O|9BDMKsaEkW=k&G5?%n2K`AShlQJmf zr1IeM_~W-h#Zo>}Atq6bD++)o`fL#^eSqmCfoF`J#IDFHvA^(yqZxo(1kj3Sgj)tB z6+AxDRKO?tFItH4#DCGA7zT&M)M8@WhZg`P2DtMN4u8FW_$7==_#YlN`13+$gxQMw zfz~`FoIcT%z-RDh`i1_D{uiBE6v8rAC$bacN3My0SSN*&Qu#s^({Hxs3h*EQ6a5z} z{{U%3!A@kyIs%Z?Nrb&ZI8m5{DVSoCO~w3=%Rn2R94=pJawP@ycXS#tt@u0o5A>fU z*h!s#R#GP!IGK~&NeqWX;bh8J`i&-2l0$tslQ`@POVGd8KP$PDRQX1~)1=CG`U9K{ z(;u8o;ry}wLSvPr$`86EsM)%`6ucyOGjuET#=8l;^*$QO%;e@r;}f)@8Wj^A(+J#9 zJxDSsnU#Yivyw$QgyVzcM(Aeft#<=>2Y%IQue~?k;-GFD_Tu0Y z=(1oETLWuIT^6j!lHj-#ugE?dNzG*DXXJe{J{TX3FTH!nx*Ph2cU79^H+X(Ez8M$r&Z)O>O=Z3{ezQO9EslP(1!(ixS`b_a zU5P#`f>%S=(Bvxc(W|T0Q?;17!29TCs%k{UG(&n*wV4_b6TtBcT{ZTR{phd{h*pk~ z3}Qy{82TI~_e0OU7v6pJxfhxrToC+h%?G|%tB|rXxGLC|x8tjV?Rb0s#&~P|VRh8H z>ig(Azz6V$=#SBR$vzUT>;+eLFk$H+?yBtVtuvd z1;1L~!1FP^hT~uM+IRz9jjUC{)xkErEw8QCQ9nkC*XOUJcQ4K(8JJE z@0m9@_|5um%?-|juEDO=!B@s#_K&?XUPEiCwc$_;_yqnG{W*FMNup@V9uf~dNz#hx z#FOwmK^}#kcu&1Y@O&70Y5Ze?`O*-~MBrDL<^<;kzguxcQ*}1L=!W0v{8`Dhe`DM)v&VoM0-Y21_p@-fh zZztJBOl3y!m-XA45u6F#L3ZNI4uFHX601xP{F5 zi4vmq7;p@pFPUqv4Xz8$vFFW(=)1GB-2+jmH1{WY}zP-RE zCN<+iXOS5P><%U2-;Eze5@f~jQ-L;WTlG}nH1s0;F9a?InyW3;2p-^njR@eMkqepU zNI~^y^snfG$SR;-3cS#pf&1hAo|mxxV&GDsnc7^PVb8QT24?`{f_p-zLuW#JfV1GU z$kzA;`J18fZ^n1^P)1d_pWiWZs5#YjBnPmb6jr}S|A;OO|3d0w_$;#bVsCtCnmyf~5R|d{t|4;; zdOT1@Evp_6oPcImbExY{c3=Z3qJE419$f@Jh1IF{H0+uRObqUW&)(3!&`IbLJF)3A zm%x9qjbD1o?-~@iXB-QZRm-Wz0>`1*;JSfi12%#;l1-#2t_a_vi^9K%x<7ORPWyp< zp(*yn;H2Obdn%N0%I_HjxDUQ>JTQ(1js?o8M}hKcR=92=S%J+&5H^K2hXi4BXbX5t zXe)SYXdC!y=%XhHdBZ7PLAV^cf-_e_SHT}W78ZnU_{tQ7qIkAl5E%aVEeI*`OpqXK z2yMjqjiF7U$@Zk+omMz)iTY9@6ncq`dP z#@iF@X~FTp^x*2y8m!NtW>mM6RiV{5#*6cXH(Fn7slCiT#Z1omDaQFp*2n5=Ewk4I zt_7|K)`HgrhN#8V;_48fggO+*L%>C$y{$f2*&A4H_k&MgtDlt^UlaYT=SE_)pS8qZ zYM*9|oBTBVPq7p5kL4%WN$6_0-w3RR`}M%Oz*Xd|1J(wH;VY!5I!vt&9fp*l>R{xR zQ2WEPpVi-bW;{2}FoQFG2F|D1aTd#y^5gK1<*VR$Gq4J-Hv;PeSKzuHSQqGJ^|qGV zy?_<=Ab6Ej2LYwPgE0+9)-Z5YwHmk@rU6LlZw;`X7*CA>)>Gq|(bMW>t+0CnEA6vP z<2pafbZ&qR^f<aaJEg3(`zMDVH70B2f zSb>~ffsIJn0Pc@#*~Y+Pyw`GoIuI!XfRH*8StGzzphwtI_QM=xJvN>ggOD}Q>W;MG z_HsDw4lD=a0{yWsr1l3~u&a9NDC`{xt_&TFy@Ra5)J;V=qZQLO~7gsH1F(jH}ZwYouvz;m#5h#h7>%|pO1 zb1A&`1eOBv;ANQls{P>87YKvHYHD?idKizLG4LF%cCorzqwIt1m-*W~$bOrDz=tp` z!S47#AM8l2cE*a)c4up}JqFwb(*bsn{V^9~#ooZ;z!GS0tV^Tz2GWB2VCrObw#L{A z>;P6K0DsLzSiLW>2s`!$dSO*swIf!HwL4m4?Q!5vn0l(caK0yyPVHcIw8q&zFr`y_ z0O{5CRtKDE4~)0FW6q#<$1UmAYU3S|=xg%*L2h7N*P;W3*{SQJ`}R9146;4+Rc`4+q|>JFs`Vf2uRh8DUKYMp|>w zVYV~JNyHQLIZk5k;~V`u0y_g6{hOeV_+x&RJp!(Qud!|HC3?Q#uaGcN{iq%Y91MI! z$_I6>Bk)9gE_~)VulNmej=jRlm;4nkL2r;({2V*a9`Z+g8{6RD8JHH>;NJ+{;GY(l z9(W0_cIr#@74#E4KdMulsm@4i3eeoz>3^dw)_3|fT(@`nHwHEZcKR3V8^N0bJN%QK z=2i=9veUw937&#!9-7Q`<~jdNfv@*(@J|msKGd~}%S+~*JYc6J}w0p7uOvgc^fL4A%E?bRNN5F}(1 z*7(=@X9m^)vjR`CzmxhD9v#&Q&P1oRb(i1cyVzi32v&|W!eKEy&Paowx{iaxSYwbe z80W_usqwSe@y2W+H8>4!8}CfO-toYH;Qy>P)*XHqK6ilKY_)%le^y{MFdIBOFemT? zsh!m)NbaOgFy;ueg$ZyQZwy2Na-H!`8|yaT&EnW?eh2y(tGlR=v7@uP%D>t_Cot9- zhc#n?w$>xu)>VB3bOS%eG!dQ?jETlvVU92WuGxf#xTTvq#u@9hwZ;JLtp3IToS%d> z6OBp6JYlZz04uty57dXyenx-XI@y>n%mdHEy1qs~oaqD2CiFJ?fO{Fe!99&$;EeVn zXR(vXUf?VQFLV}x7daX24H0|%@&1kA4G{y)clne5E=Uwqax+xuApTOY9@BHq6q*bCn4-{f@*<&=*k) z@jc@OoS#R%h*}U>7)WQQhi5uqsgo7XS?sL#Ubc^AwfC|8Y)iy0|8D;l_-~HrYxXlg z@ge3b{u=z6zX8ADgUz)O>(F5>u;2eE>T%Rh^%3w(eF^^;QEBaT_EIM;FbF)z8SJcy z*zcd`UlXwwx+Y?tf4+Y!Qno~Fjo9hmh2tdn*WuO(P1x!0gS_*+kJ%U6$2`w3@NDRo z)y`(ev%PF6nhY_AnkD{^qq7W<+vd9PHrs$LTT;Md9?Nz(nJ_amGcz+&!_3Ug%*@Qp z%*-hyP182bci!*Ed5$IPo_lw)Gf8)6w~5~w!}J^Y`Mam=wt7c>%KlMrgU{gaFvDB+ zjxA6YD(QkD;m|N$kRF}`3E6|bdO!V&v4*TA3*LU}v7ZzE6G9rdpIggu47N9{ZI zp3PI{EAQESWr312*c;gw$r<9Npas+9EbivTDkKPw)eW0u0RpXkmnyeuU<;Uy^ zyQ_Xc!h4nm=Z1x8P%$*jg`AwhDzX}9RzZv8-g+PXn$a7&ZahNGJ@pa0r``u2WA%}( z#&hZ;az3z+Y_2j->81D9uN%Ff8^%hqiY$^>LW||p!LV?6m^w%Uf5;xO`)aCScsL?V z6{Lo*AS=mYc?GltTp}-(d+NRP8%9s)rttu$AE*!5LwL$yL^v``8Ki>u(0l4Pjpbwo zSt{RW57dV$2oHmi;ixbSQo`@Chw3Bs9=i_@f>GhKT;qvQXi#HM&=}Wf;>^)O(sBlNDe%z zA6X8hWoLOK`66TVtVsWrWrcoYimxJBf${}O{kz6JBdLGSxDVbpxIbRrL-vyK$lF7v zAbGMpMczSnl01>T$jJkZ)eE9;fk?r~2z{iU1&P12EYKfdR;+TeRq|>%CuYdOh_Cqh z0s`d^lA%{pzYwYlMhZoS>m&4W@_2bK83*knQ{`lF+rjN*2e<>hb4T(-#_GADae8K? zUuK!n;SZLJt&~^ExzHsilYQdn4`lo>gbC&kj37C>B=eK|cZ|EnSa~*?L&nPEkl zFB0;AOXX#9UbakLE=Q1~`4Ru7amyGb&n5H7D0v>4501tvv2O)-kl0TG&mPGUX|HEM z)-{#^x(;TKMHcQ~g`y#+M_i&vGx&x+$GkhHR+28Uk zdA9ry_%}Eco+#9P!%qw*3KNI;k#)b8Q9M#2Qp>0fr>M)%C{%!{P(iRDD+E%k5{8LF z!%qmApy^wFlJKSx0ej%pBMH(Hhu_d?w)_p6BXhPKuO}RjXFkR;4`csghJWOmMu|wt zNKK<;q!d^St2#!pNO7=uq_**Mm@u?_DeSKI&?O`%3I9Ug9QiM3E;v`7Cx1uIzuz&q-+^kPLiS{XEltPMyW_$qiCcUSPZ!eK8C_f!N*aE#fLv5KOVAu8C|4M4!h~y z^{>dDC;x}f-sxb{xMXqvA^*Ev9a*I#)r}hPdPb2*QLrd-3Gxav0y!)hx+evfkfkIU zTS}G@f=oFiVOJfF6E2f+)?t6jedNCKpYm7q`V;CS|3I(*NUBIxqZ(YoEH0CvC`*BaBkW7)RhJPUA7x@pUzg*eCm(3!TjWm(8U=^$qqtauEAps`AD#C{2*%3h(ja4!# z8)+lIqq@KRU+^RNS0utI!M+Fo;rjdkBz}{B$KBtc0pI|6pj;6(=^_=4O7Mg@?X!d| z5&Ylad+=R=;y>{#&JL6-80jMEBNdE_@SkxmU_axm&;AMi6FO<_4UR^6GP@YGnmW`X0l^G z50CoCd=~OBO5(}SBnl-2J*)^$%G|{&Avxk7#n~fJ((t&S1+NvyQFY8e?$eNAr;|=Y ziJQz~5|`nEBtU|IJW^M$hbihpO^pVaq`s~onQ(w650*J*U_2pD#J^D! z{h#B<0iVk+P1uDgTV>Z}eyAZ+Zq@ zPWxy443UhH{iy#v*zf-y`~e=oDxUw$|EBTKKj1&~Uz!ZbN%=m1zyC*Y)~{fskDT?> zM>2pJB4>P^80011Ebvl(C0Eyr8O4q2dJXtqe;>~8g+2$>^x{SdqncjAC<#`_Dglq@ z|I!F~CBMcG8o!p`fI3!H^=f)aV~_ti_!8{#_ribT32^c!=sVR&guIdC_;>mrjpIMT z@r!k_lLC4xS3zYdql#V?zT4m9e+hO&e}aDoUxOd)Kl+3Iz_-x;qr3dC!C%2He>Z%m zzsvtC_>cXdaSViiXK{G$ea9+}6(@M32DzxU&|B)4wB~vXu!Vk6D~8>)q!=j9##w(b_6Lc<;;etpFM+h;WPlimiUH6Ce*s&Fw}vl( zG+q>m=}1werX`oPW_ok|GCE$;E@&6Emil5gP)^1dvtRK#vzR60$#I>WFJk@00CBp5#@~vMiC^YCqM|mmxD1QP! zp=%-BOF|0aeg-fJkw`yuUGMi3zrdH_{8DyJ`<|$&bWJOoIE^2M9Lt)G+B-rma*mRz5GEgKnh~N03?$>qOaKC_klM0Bak*+ zj1Z-a(#8l;+9+epM(UsJv{p(lt)JG;XeGgtdMSMca+b3d?4A5x?kzU@oBZCQ4}7Gk zqL(s8B4LC$rJdGF>-o_~Cix*kW+CeH6r24meowK*-wO7^DlaN2$%|^0 z%s|CAc3dl~m(!1HC*XN-hmszmr`YOGXEShjI`lW|j`cRbyV&M$2YX;O4ZHuaY0$sm zbga6G?qa(?6{~;Q6gKt$`7fS_nfNNU8eGlRu-?HaFDkU9Lo~L6yPEBqMpH-_`DEuk_dOk9gi(2d`^4z#Eu217FM5 zu?(1EE$bF^588JGLb9tRrm}2rM^c?$49dWfVBR> zW%-Jni9AQ;UhTR50-lzq<6~G_Xe{d-v=i+`=b#IGU{FpkuMZ54YvsW5`heh>zE|6) zJ=34V)9|ru9Nv~Wj*SP?VwHd)Yvg7%_==oEB@cMLj+j$kMF6MesSKzpJ;g$XJP(+MpQN?@LBZglwm&$i<<|s<1U3Cy@H+l6?YLIQKdueL^}t{dI0)x{L(UWV zH|2NuXC(ijd{!RHkL1%dH_1az(>!=&Pov8zx+3yf|Dvymtc0(|B&#B;Bfsl^=qJ!O zFF!#~!q;GDb!1KCH~n}0SLKQPRQ^@@4gLk0pOr7l1Nos`7n5KPnwRI}$7w#EA3TB8 z8JdgaCTGz1G_Bze35EtW{Gq`xuqIZ^BP$|b^ySc>;GgNMKPX4!qu@uZ{zAf6abyY77DG4n_sR$5s9eQw8Z-;4_*LPD=@Dx23p6{)K`tQYJgw|E z3z`R&{VMQANNeaXiY$)Y)E7awz+3ul{T)({$?ue7@^SDzR)^?euw~E+ ztc2Bq$Q}Kzz96y?{ziF=+BeV%`2amgU48(H@(O-Mzf~|lvLJF--%k(FDBllx{IzmI zJ}JLe-oVS_MC+iuUje?4?x!9v=a=_e2j!qP!Ctx#J9{Ak3hwhgbT9RJ_pp)Q*w@v6 zlz)|D#^%UTka5`98aV`Qi=0IF6UIqnePlx< zxtc=#Pe~5_P$KA}(Fi>&pOa7F?n&d6@h$PX$SGr8WIbr&9m1!K9e7{gL1S`cO5~t% z$k+yMi%gCrQcVNt)B-y!S>-;esKk^RQh$TaW(Rwg|upOQ^_NO3H%5k1Sj}(HMZIn<2ZlQ}w z+lB4J626SRZB&M~)4iyf9@%T`gHx5MkI?Fo@)&%qJW<+)?Qp&=RMOvLOpnZn>@oJj zRh6nw6bbb^sDz~Lv`yGHEa|s_O8L8uJ;sd4ZfIsiQB|B&pr=X_oZd;3pkfDY9hUM- z`>n$^@Wj~NMHA!BPTDFg?U(Ueg{|R0!|+k~OZX7#A3lHvfCIvT;6tn)<1y?9{(@7F z!})lvcpUb_Y6&V`x`Zx;7etz`7R0v}0?C%IrvI>tt`S`lrDlidM~_>M z$jlFgYB9x8T~Ld2Ko^}>B4GtxNna|jlniD@^vVETGP0p#Rx_J<+BjomH+LjD1)efa zgQsyXy}91lV5B!Qn3upy#(E>45~^`(J|#cAxDtue;)R44fUA6UnROQ{vRT z&`;n`Y67(cdKFg|pu=}{HGQT$S60*K$_wy?vWlj|q#KO+xc8qrpDuvk4(}lIHqpmy#QqxuBob8{tiyya6>0b1FZp3DulRLNyVX3#&Oa zj{ZdFKncLPSmA#jVQw+5<8-s|I_jE+DY4#aq%>2(b0|5LMCxpuO+aTu@$?!_H4Cpn z&BIyPi>FtyY93yNT7)y{EbPpLeg=QW^Kb?{AziEGHuIQkwLE5Ca~-bNYU4;5Wh@y- zN-JfQLwr3w$Pe*#bUl41UWKp2cj9&UR=fe` zETxnNODp5ZYMjnzuGZGTH=t_0wn58j<}yc2kF5@Hmeh{0q z9f`7=n~=6q+oZ+t&dg0(b~A@L3276_UcQfSqI;q7^cYW~O6oD>9OW;?yYO`QQoMq% z)K+Qv&6S#AnqYp@Fh`P6q`Wc`N(-h{(kY+N@uT=8b{IR27vgkyCVU~zglEB*Sgp`j zYNk1Yj3nul$;61$<0hl~B=W1+ZtO6AMb#&BL2q<;l*$}-@&KS#o7|hH5Wrsb1)e~ zV#;7Blk!MB78k=u(4}x2-;R^pplP&_7U%!u7t;R5cO?pgg|x!jx8U!fh_(}7DJ`P? z6?_A~1%8-gf55qwb9`iuz=xj8?`k z3$_fg!d;xuT7)gbve+r3mD8@^wXB?W6|ZLHuwPaykDYQ_=xo)tX`__sWTY}mnM$US zQOYzjovc((@zeZi@Q3&;o(7-A7x4_&PlIQ{@8S;;INP-CTHu86RXDj)U7?=lXZQ;B z3_lC5#A-D@<4%F6_$qa^nnO9sp9D{XFXA~8o(0c?l;-bZgfbGHM?f>kXmlT?_|A51 zhvqvww4GppRZ2`4I*(ELr+6IvDZYYFuzG=n=fR60G*gWLQq2?T4rY?tj&Ms}b<~ahM8kwn_)XrvYi?$YNYt*%BHYK}~ z#(9Ewf2DDH;@zrgoS3>vOXFK;#>(s1DHZYsAR(%j$7dOO%;352VAWYwUjht7( z5M`*+gA9Rsf;~wuG9JCgDNEGVd<|csuHkFJrC7P>H$!us8QM%Riq(2_S*K3G`SHsA z;6ZRh+=p(0H^nXSCh$yQzCo|o!C+;G(u*us*Yb6IvAP7l0k!MZ4Qgg3i{d!0GgEV* zS=u6XvAT}m3+@NE#9Ji13El=#(=!L5zBd`9^d^14!B}lX?FMzDnn}s5*pB1O(k#dR zf6mfoYj;t9Tigw9i#y;wtOhEBls;r3(%18a>LR%5Sk7$Cgyv{>g1f;TF#sp}k^#y< z_yTo3-@q5B3*oneJGcvqyQ06+m-Hk3l>zYi>IS}%&sR6{P2d8o499flXa+P_yA|9O z_r$H>Hhi8sU){uS2DgHH;wE%o%vI-MXD+mv&rvt?E#O>uJ@G#H5NvZYI2oO-&Ni?< zcIt`x;$84Q_(~=#f0D0ck}_F2t8P*^t7oAt>N#AWRqKim!N;Jks0VL=^Yujou~>_m z4e(gL!%ozE8+;*uBI64*MfnRkU&&u&qB2Q2gZeG%dE}e}2a`<7c|5ioalH|HTQEn= z*@B5OI@>YZHZVQBj;Jd>1`W}rfoLceX^XYb-!Q=wwIj`0hbJ;@PdQ1jS z!7r%;$Ut%l9WSaI9sEayvl0Cia1*?ys3k50O_0!7G!gT)1=?@qchW`q4eF}=i_Cw> z2_#KXFRQ8AWjeuIBU=D*~)dIFipp{eS6q)=zQvjKhuT`sHD#iihKP+io3H$zTS@rnFOx+$Na z?#eOLO;wLU)6}bKKk^H?imEH>I;1dX9g?V1O;i_`gSA+5XD#-a^O1Za-Ib3}59KJT zr>RGw>1tI`4JWHYSArv0&rpv*Gr^-+twA++)<8*}59A~1p?rXPDpf>PaV4k%T?MZO z*Mh^SnWY{^-Ar{gPA79#qb{lQo_ruZmG@9DrLw3Zt_6p1YLVfT7a zNmPa(z@6FZ0ceieUj9Milz!~GdP8j|x0mCTr{+Fqzw-=yY8G>wix#4oTO9ri&h%ry zuxsjdwS)X0`9V6Mw!PdIH9skB<#zC*ZVS;;6m^TiOSsKMbI@?+Y9-vcS~FZX7scJ@ zNPcEMH}^XGoW86dyP@`HSJi7^KRn9)k^c+p&-yF<$P;tFbHI6GK83eIpP!UAPy(f+ zY{Y#h9p&%jKkz@y@d9bj%@^h#XRlMlZ7EubB5qN5Nmq9arzB=5;XXE>m{EqS?^Rao*c?2DDULyI0`O@6w?8fzOXOGib zZX+j9T0`+lVYiiNEeg9u;HBJ%qdTS0x1`&f-BP!!y;&dlKqL=f16g0CpE8j3Q+`oO zyP6YmO5=Pfw=+6+l3U5G<#?qP^q3TKTZAbVxrVNcXonDeFi%6y{ka=IY7v)odCOrDUI=7@B(f@x1=Zll@dLWvQzEBcB;F;o>=8~3%I33eyB89T9gsx z++scrL5areoCH^=5h;och-aLQir1N5O&X8=qz&XnfKxO-284Ckq;^> zn#s-OXQUbQoZL0_oSDS*Q?-Gbn|-o;03&LZh5f0o8K$ot;V1I4tuBl-rNCw06&-?O+)D^_mU08 zguCeIDBJBF_D6FMI_|dj*l*0YW`8;WefvWr*%11cydy&}!(f`ntLRp8^LUlq%3xls z3ZhE^ub{UIubWY&i`-R?BGXl(__tga`4>8pjbgvh{_xyh9KAC$l$sT*J{n~tE4yA9%TQU@r455WlTgWTyt#DR45k*&O z$R2t{m96$R`;)m9I&bDer;KhcFE_j&9mQI(e)JdkK06iO=ef_mgJ<0L0^&A;A@=D z;pOyVZVo7uThv?TEO&~cR}n9TQd6!ar%*I_a;27B8%zQ3P5aQ+EW4M(%j9N7WImGOPyuTCiK2!Zn7_#m%+_gjYQuOv==JduwJw`Je!x@%i< zqrJ(#Y$jFe$aUqUN?o}gm<+28*u7$Iu&J%Uwr3q! zH`;-91iNF^m3E^YS!)s~q0)-9CjVooq*P{EhwQ`lEbFj6(>lgR)1&Md8%0M`D_Yzu z;aSlVUP;f67W0aO#j$RKgw~`bX+=^hEumD(4AdU6XIMw>iXLMvNGc_@(t_Yu z;eai%YK!h|NLwNlAJ@JTDATPO)=_(ob-+Fd9z<^g{YrU8)P%d}0x#Reu6cYo5&~7@i=QvT97nKJ7l&c?eK3lp&Vj|*;slA8b?pEhH@kMBx@u$1{9Sy#lzib)QjFQZ<t`E#vEw6vGfi$rz!L3W6Z zqX$_V+7=u~+t5>(^CUaP8psXh4(QdMG)1?B$^mwewWX)Ae~L{(`VxDJH5IN!Bhi$e z2Bq>u^tyS&6qvz_HbGrNr3sV>Or#`MCR=7q0j2i*=r!}Y>7!Oe z_p<}&vL9+k&#?M(1NjU(o@R|n6Z`_{N!C((nLWu`W-kXPW0gFbBAVJu4y6Ipcxk;L zdeyvU2FS!)(4*_|dA^UeqwVQFwjX{LnP=EpR!^=kHzJLZ*$7IaB#S1GruFu+_Ot`t z%l5%1TFdPf_C#wEydh~sk|+%!N!i2pvJP|))R9iGCR!`(q|s!kO$w#+8jyxWQW`+A zG9LF<+T*PWa2`$XW$<`3X*3;}&P(s@W_wsix*O_5S(HaJc)M69+L`WRyWu<8F4h_B zOuK+xXje*cBBMv648DWy#PjeeKhG|(XZ##H51waF`8CpoTqV~?XZS>Ck+s;G1Wt64 ziR2=TCWBH&pYW&r0(;KSvU4C)xbmFWlh5M%98#Whj@O5zB4spHG^t1xO${c)Duq~Y z2VfXYE>egf8b+_6M^|zM>IPoL>N@&f13SSdI1`=4)&yvYHQ8BUEd&=@i@-&g=`t$1 z5iXL7)KN{Wv)9`i@>7V%nCv2Z%%8wtV7BM{2I+{r8_;z!-dSQTwZ=P3t!3Z@tfnA& zvU3Sp-N_|#8P1THCdvedN5mR?tsN0-?RDTf^mxQCvPfs6sA6 zRl!SG-9pYyqGN`LpyKCf!YCDKqCbNSKGqp*4Y9^L7m!hv zs3KuBQB*~B!l)ru*{f|sthU#HYiwOS;14mw184(#&G9Wrb|2cv-f&qV${S7;1yoRZo?Jl3^H4Rg8mUf3J7bVD8X5`?wT4;u z_S-GeqUyvT{fQA@0}SJ@WwP4O0)Z}?l@fXK=yXS6fSI)|j{@L3tKa2Y{$Vi+XZjE$?TO+_xSl!{9*%o$(Z(&=(yI4sgNff{4OUUpuLxewka&6J*~e9wDAA9x=;R&T*~NbG}0?j3Kc zG*cds7N}~jl(pwLbDgqwId}zohBFhK>C6IWp~r>jMdV+AT+kI!aXC8PT4`U#JeQ)E z@h4+rXC?k@dZ60}-UIpwe&nBcU-az*)+6;vUtXUyAWhKqA=nh&Qn^F!f_E`TMf9y; zm$A#*bDi_i3(=^!5*=rax2~Yq0ed7I))0a0^9+F3-vC;%y8mH$urR{l6AFvEo zm5@`>u4GSlW;o}N;)!$7^YE+DG1ge?YILkM4jhNvR?2O1hqS^BEtPJ(JMz2n^ZWw% z3H}Ru^#kjYdgN@>6aRW=qvzn)kaIQKNO?r|lSWEocx&YrxeXd|x4_#-EM@m``Z}fT z((uamG-oX81t4yj8TD*MR+uo1kZUCQq3 zoQeMHefQ2p&%&=qM_Hq->(SBH7;ubrE!u^5MNSv!B6yKs;scP@pEpn%DhEgd=pZS9 zlzvVLyCnQ{^t<<;cRKo?_X9kG)s5&#Ym{{Z$=9Quk#UK4hA#7gycVfV1|n?$udg&v z4wCxNAyVA#=ltRnw@biJMNdb6csG%7Biaddmw7S!7pK2d%=F~ zJ*B>Kh}44)la9O-&Ub{a@S=7xdw_Ey8Yg}dC!#0eb(MO`VNw@5LOS5YRo($-uka!` zH_$0!7lj{>{v;BJ~xNGiKW*vXdPl5W0}BAT4t>) zcDls6#?oo&wf3dS!@627t)5mFk4jE(a%@Vh zE*`I3S{+>11t-NO$LixmF0HlwQ*9*CZ?o56k22Hobw+CXz- z4RAJFTy50W(Q0cGW0PVHwFcN}2xX0{g`L`3Ep0+nUp;gz$#>T~3pke{IAhs~pRBM8})v#Y(tEP>Kjg2+OorU1S*rHf7ttswS#eOxd zsx~?{Ce{qQ{lVt&D%h#2RnbPpM#q|K&2X|Q?hS}F#r^)V%G$`-C~y?cm6qEn?UmAU zd!+-|K`AAtx2oGU?DSR*yQZDNs%BRQt7F|P{s=ir>e0b`2(M2E@xkC=UXN~cZ$)oM zH@df@ccPncz0qxslg;9r$JbSkkS6FlFxCW}2gJ&tS82HkDlJgkJbr__(Y+Jh?B0yt0&gLGvpdqdiRhdINYEtqGs z+Yo&l(1!FBIZYblV;&T1jE{R@tdce&HWD0(N4ydC2E~e_emT?N-w?5cL-_$KkkNMqX`YbmvrR`?iO#ut-| z%N3OJn53LsUT&?l!L3l|%(DjC6Wxxfwz+NMt1C5>Ht5?rz5+5UY8A9$vEi}KU46WWwEh;JCb+Fj%BiLQqB zf_tO;qC4C{&R}N;X4vj_(uTx_#yX)_XRV_)I5s5K5j&lcK1bB zLHnaSQM<$4=?-)T;TNi=#B3py+ir&mF(0i#oAc^W3*HRfo6=^qetd)Yz{+Fiwec%k zt=wR4JC9wBR;Mj^bKGr4o6~yn_2XB%tK9w3LULibiqalw?c&?VS5>Mh_#ta6uU!zk zRh5ErA@~Y+B~Gq@4n(WcYRIVywFF!8R=fq$n$zX(3im*CIdm{8P@m5hmJhE&tI}4y z3e=icrd4QbzRX?j9*i!74n>!`%iRC*Q1o!L67IF(m1rCM9af1}#;PK%MBDO}-Y$2y zyVBe3?s4a$TT42R*NblfwxDzQJYF}xUi>tvL;O@}n$$kN1Fj3oRh4N{ReV&TTuH7h zhfo!;iX6zRyq)eYcNH>MdOz$O)_?X7JG+&`nj%d_#uTVy{B$Htlcq}rcpj&rhGKkPUso0Z*K;jQ%cxU0P)_CRN~H_+LM>zzoS!{_prbUtRA$LI4p@pa?B z+y9~4cPOW|fY*wz9lwCrj;{mOiJ#B^wZGdrt$(3h)=y4WD;t>2igT7DeXqOR+w1NF zS75cqD{L3B*P!ESZ#JKUF0-Llbh6YjzEk{UX$pJ>CZ8_Nkn+m~WP$0cfj&GH=1&P$ zgwNuwXlpu)&xS9=JPY_FX|mKQeiGCxEeRWX4|FQqIb6NjDxxw64 z3M+w=*~$WDv9f|$F?VXY0y?CIQpwA_<=#Gbtyj=4WUuuK*@eNvn0}(vIle;tL}?N{ ziu5dU6dkI|f7>Z6&HCH^2fh@Qv)!fMGWa?qto3H{60{_p$y?JB;4JtoOgK}TCFPOx z%Cn@raz6Y511Yqqr5 zTjI@iH+cE&0`>;vtoO!C72_+#kC!IE9rVv8kCVnrmEy-imE#xT^gMTww-~Cu)ma#l`6+qi61MCgU>_eTxp(^Q_dwX^yazq-G$yF_@B0J z8P=b+VVU4ptSofPA4 z(8@)Z^A$Wd9fR3&<55|T>*YKb%}uM|(a9|~dYio5NXsR1id7i$<7m;e{4Om5;}>TymX{AO3F(|Nu$Bh z=%%UOwSkQ7fN_S{~@3$3LiCB>jWx zg;E04{v;=mBk+6ZN}PKZabDZ^tov9!wSIOIf(bEAcDj}3<# z;qjOufgCTVkTp=l>aKOqdTkdFj^$bf&?~>lDkghVysRP{{2TfWkiJ0!!N0Nk8MX29 z9qTTt?m%zAH}+dQE6qlS^Q_PaUVsjlMo0xPLw=e?O!20AS;SOt8kiNUg2J{Os~|cS z5Vx(j_B;Ewbq8J$RRw54I#e1a6{N$Y;Zj05nVeis2&Dj1$Unr$Wfs%C>0V}$1zt#4mTeUhpYi!$2)zo5uQ)MC`U(vO|N7r~nuU(ynW53V5IPp5 ziO?&de9O9Ry|Xik%woFtC(aI*63bjpDkp}Lfyv}V@=fa&&fJ9F+nH!)I+_=zL!_Zn zVdNB|F;vd*Vj>ef32GC|H>{i1d;13T0sLTpv|}_As$$R>UW5*ohDb$_P?&y^{zS)& zVum-<%P3}gv%nZu*R31YM>`{p(J?$DG?r%&8O1Cw1I!2BR3yUHm>J|}2g@@~?`xf&Qp>Jss zT9m%S^;_@@rn(~~ktO+#bQgXfIrpRkNO)r%Fb~2Hn=h?b;49?1ZqzL*T&S23cpWMP z77~TQ!ssE~KkU!;8+0g2-_y_17wJ9n-_hHWB+K$`fPimCBf&MQ2A$_2KNS~$G=vs`v zrf=Z3>)^Z%6&JUp+Y*r<;*0SrsLB+i=)KR}Z@#mRqSp~KK&J1$LVa=i3K_-dM|gDa?yvT5;BUyfA-$H~NH;L!Yw0m2d?f8L_nN1zJp1sTx{kAN zq}}Ej>#Vig+yggU(+z|Hg(4O5kxM^HpQPXDCkYdw_E-7@$&aNcQYJaG{G7f(=5r{Z z*O2&5x(2-muVb~#+-;t~T1?!@vxe+&&ctW4z{1Ye@-EQtMFIp+En_8rBHTYxPNktz+scCXIwMZk9yD8w0 zu$P)Xg3{1rZW@tRBy*F)A7U>JeF&wc)9h2`X*1%banriHq^Hs|X&3Yyd@k*jrrOi& z(`GGJn_ZD=vGPU!qJ5cpP+JVaF(r%>flBS^kj5)@Ze>afew6-o2by6Ifai@*)RFc^urrkAcU{nRYdFx=yRH z>hSvPymUdT&n`$8!HZHomds1;WpI;0Nn9JIpbL&iMr$u5J48%2)mMZN8Kc5Fn(X{j;J zG-8d}8R@Jn`Z^%#7tz0O>3j;V1Nr%D1 z(h=~8bQC-)9RrU^i@|hqdfALiFJ}NV$Qi+ma!jtyo3LuUI^Q5|l&bTMczmk!(^3=G z&6;P=x4VPgtnSuad!GH(^*rHyb%pn*+tuo3&9}Qk3+x`a+uiD6&9Ud&UvSs=zPP>@ zfPZ537plIxf4SSuD6XTP=T+s^(6cJkl-1ztr1eq_zFyh@Zb0vv*r~z4;rw6jH+P%4 z-K@f!vF5A_ugaT(O<6Pc+5O@MUKeYDz0mGrEwmSbU9swk8G2Zic@^HA)#7WVby6*) z)#RP6F4iKu7w-17dRepWIrbm!XC(Xqh2G!p7IUllx4YHc2L2y=SJfRi&u%5Tlv1W# zlU#6HTb9er%*;)>O_`aQ8Q(H9Gcz+YGcz-so!)&v;jHD0y|*5eGvjeG&WyBC{ce6R ziAAjs=0`I%IJHHr^5|GFynLtvv_@!o*ov?k=wCh57JYl`ZMAmLZrb|LRPgk8>qFhN z-T16#H_X*l>!wZBr|Ca2%MY_$sC=kkcsZa@c+JqVu;pPj(XB?Pjn-T5qqoue=zYO$ zVZFyuQ0teuR$Zt5GS{i=!RytZX4z1=P@(X$K;iIOp`~HV!fK&U%}{Htjn-FxXTC?( zJAi?irC7hw;g{J8v3`0htu^$m`OZ|VGNH1e!r^6rBH$w7MZ+UPOTw0hMWAP`&>vL& zHvgDw)U|5qP?=EC@Y;w*gldNtg)I)N9akmmf8Tl1u#%A87dVj7G4r49$q)JFl2b1NB$tYcqybB2+R|JiJ5{z$L;M z_}^Kr?KbGz;a~SxsAT+=#kc}~4Xc&i8j+6wGMb^XpVrK14sC06)4GGZYdyd{(D9}9 z%2N0TYluEn|6mQ(hk=Lb@2z&oY-_YLcH^9DX}3bBrba)lj@Hy@25oB8(due1P{WDU{>>z}N_`Vc+RXkygU zKEw0L`fLr<2kFi27U<9%SP=HidT!k}p8*fdX7+-xg<;L?=FrBdsjoFQ>T318TaQh!`2_sLd}{VURd>55xQG4F zdSpE{dtuzueqcSs_yO?DtO-vqyB4^n9RaRor`0Gc2XMs{QSKOhnuiC(te#pr6-dK##! zcQ87FJ0g2EdamNDc{8oKHXg@PFSHEv{jiqt<I@NAqH?*e$jlhlU zDYmD#Guj)TzB^t!aGUVm@jP@E`VzjB|Fo6>*Q``}H>0YNN>2@4i~ei)THZu!s*SP7 z+WA7$&~vJtQm<-MGg9i+jOyT2uom-c)^%$!zi!?4df4{(5o9Yj1+oG=pw$D->^p6`9lRlqwLYp8FpQC zngL9=7xG1jE(C6ZZ(6r3OHZNKFgBp)dcJ`-(i&?skw3%c@YXcAZb29Dh5VK^%dUgS zEMTT>>NSm8hN*Mte8g^B^Z5d(p__Uw!vG?Td3-*>i>gw1*gF7YOx6pI#!m76ZA_flPWV z)Lry|_7OwvVRj!e%pMLNZub_^ zwCGwUJsOZ%57VUXgMB?cI6b-#H%FM8`EXzhAA@eA%`s+uqk+*EefkJR%dBV76)hTc zm^s|s!iND{`B>zPF~^$qjQU15Q7}{})J=4U#@0Mt>aj6PnATNv6NN%ufx@AF=+;;C z6GQBwHq#U>i_Ut+8Xo{m=l#tAW)x57Gx!kE*Y0Nz5&i7`;Qsbt@eA2W z^37{spB&_m&v=q@(l=lztXyEARQr_Rs5AfoM*Yt}6wfsnQ z8zv$}Z@Z5jDKygCE`~@gzo=jAAJ_6D{35WTIKr>(7luZ0ZNH9R2pYw8{JMTYXcX7= z>-kfplfq3gMJ6y@uPL}`4NHSf<#=D8>sG26H%P=dp z)tF3%zd4z2E-;&uX3*wjfw_-2C;Rw*J_9+^Wh3M?CXL7>Ia#(q?tb0^DDSr*<^2l& zO!>l$Wz9t93^`NAvcjx}$ZSL!l8JJXY)M*>3VutVqCY`Slnu!&`P_VA&O+5p*?>%d zrxmH_SMpntmeARV&XTj`GxNDwAJGP+J{d13$kxcJzO$RIkROwMC+4! zWSkr?+mP0zvfl=%;*XW%5Sxq4IdZPNZ#}T;lCki#C2dF*zb#PJpC{+=d)7Qe=gN8V zo^{`9hj>-L9Z=1$gZ#Rr4jCiI%K6Bg2cFI6@Y?XyA+^b9IYzc8)%@yyd(sX%(3))i zXU-8FL`N|P=p^Q1JV)Hn!?lohL%#_fgq(raAZwyI$sA-&GAEm}ki z>me(JXemH-0B)8d2U<7oO@Q_QJme`^4ar#~>o9AfFZp%20F47NtfQ8I!olzq&; z=0Y6X0@;ytAT|72WF-7|a2<`S-9gXW`b^AUG_(M-&lgwqgjyo)s(uaH&+2bYHHTW7 zuIoe5d5F~?-4@FJvbWjCtcgCgNKGEcL59jVr*}a$VKCqeBnUoeYsfS6XY!O-RCuuLo$O`$796X*(Hx#(tfw|bi0fL`WG_*aOoRxh)++12U>9ggd0 z6EPfD(MWI;u~KaDCGp8t@D_g?cq`Z=l5F<3_&(W=@iu>xzZv6AKzgzRp6&h)zj=~o zNp|>xc2`o$>Kk;Q+udC(syc)^c~s(aS)yZz!cG#kG2}|#(bnT%4*C< zS);9;=(EG$>9-P54jsmwFg|4vE8JBD4W-$j4X> zfU(v-%r;Hz1Ez~@+IH=+z72Sy@5U^27D}dtToQsi{8`4UZ8kruP7N_Dts?SCBwIB+q5V8 zR^X}L6i3*EH|0OnpXwgumI^JRV_wJG22w@T77$!;9yE`OcB9!Gvmj7O(qz)?{b^=+)WydHG7*n_!t z1Es?^Ylrm1`eyC0egwP)R&#W2#`mDxZhw#8I!UV}Ythdo$I0i{AsBOVp@-OOFbsuW?`uqI;(34^es!swZL!CGy zE#%Y$I$CFtb6V8kHF-y?2GGem3(pyGR*ZmF=QVgIt2)rxS_RKpu?nxX;o#x0Qd5_t zqD!2m&UUc`*db=BhqM{$O!a_vP@Ab9)DCGsjh4I>|7o=1t--DN4`Z>j#MvPh13Ses zXPej#-Y%9pDQPP7vw_rfx;g`$rUQqyS?D%X{cij~^>?5R|7D!hTY_7n<1}@;dRUtV z9MNVYbCx<=-KXuxc)xZ)`;E+B#&6@SeojyGulsV$xXfAZY!O? z_zqp<>=e7iB4?M_4PFc@EvnMch0bnKI((s18h29{I*VW}bZ*7J9e)M-EO(}=)6^r{ zRN$yK2eZ#szZz|MJO0)92K|HCe;a>{)A||xk8wsntIt)-;nPZU)xFw2Z7%ZXsB_g8 z_$=;R^>S#hw!pcK|D7yw7DCfu_Ox`0x=35BO;M++N5Mz6McNmm9WTqj7+;}((fN<@ z*Epr0)>k^4#TKy=N43InP@9gfayE(0Vio)=o&VG+>SFD)@x>_1KLh1BF;D4#jrq<3 z=T3YFi^{mfAtvS2!EG%IY|#|p6f`BJ=1KjOPLWScgPQQJb~cJlVm11&aweni5^b{j zAM}&)*(k?90p+<)4P>ryHi(U44f0nzlhh^JQf-nt8T!#E&nxhc#wRF4e`+%Ggnm-j zsE(?&s9NK!b=HdwVxl@pU8+q4mVuXP%e4>2N23D&0952E)sVl=Su56wb>#8Z?Df+7pO&PG2|2l($mwJ_mp$m znE@?@c}vpPdK-O-`WgK{@nbl~dCoClzVnX1=h4k~Kn$}3`n1=JpgsdFf==n_(Wo;o z{!!%J0Uv{&LC@3R>Cn>XT#AB;1I8ImTVal+YAd}pv?IE8&^zMwG!Nr>>U{Mrf5&5( zZ-JQLnC2tn3tywH)xO}UKJ&tuH7+fTnKOW~Y#cq}9Ce)dM*uhe8~&C*GR|V&GtOCO z8ng`NEltbNHMpvO<*T(d+E;Y@!dvP~)xl~@y%n^jK3E;1cGAnmp9`Lg<0ypQ@#taa zh~vgT42byW(Cw^K7JbUlvUIh-#&4mw)Q70A`5Vmm8h8wTY& z=u;4gPtT*nIp@4H75bg8&{k^S`ATgSc$M~zH%G6bYIA+4It<(b)+_$Rcxt@juc0sb zEB@3dfKKsg0U(@SaQ<_qI2VAa;Hl{Q13ka*Kd*vv?9GpD$*O|jq}#o@4NvHIIn?&;5X2B z@Vo`@b@qYx!78VfN2hW?54|F~RnRJGUG%Q{b@Zu3uaio&GWZ6pTckX#0Iq;J&f^$< z^Yi8f=p}Q7_5(a#U7=mVab7fEVZKAoE6jP&dGGAOZ0~`0PFby-)(!<%3tl@A*=ne^aVPN4!r=zgszZ`G!wmoSu=vKLhmB;4!KKK`m6ji zIF4KVjCmG%6-RQ#ylReC$Ea7$G3r?LBWC~Ld~|j>yTQ9*mDXzNwe-?j8E6%)T>MVp z&N!MX+6!k)sEXD}?+nivd~Wy?sy;gRFw0$XkF4-l`lroX{5C&ro`GJ&ELY7^T4}A8 zUJ8iNtD-{{t*Z9idEs0pS4bxM+1cUjbUp*Sz`LAJ&Lwy=(@W$s^pts<-{GgsJNz#A zG_33BdCk0Tj#5XfCACsog#HB`K06mlW}1awB$uEk%~R%GeiFFHZTE~#SKy0tfn=ds=>>8Tdcr(u-s8o!+Ik(mxK;xC&DnbF^W)|TXfdt0R!1)e)CJeo>*?o6HkzHDBj=&V%=`QSKV}|>es{Jw zTb=K~Ht;s|EvgmM>ghk=|L&Y6*=Y`XmgJy0!RKHdH6QSY{HS>h`qSBrte?OS=L|VZ za?&H_L;i>#F^@t|lU#V6o`yFUJx$I)ui=%t*|`S%1Z#K=r}cCCx%_nCwBQ`jG#KRq z=kjy=4m|0=*`YRkxxu;pJiZH$1I`9b4PPE`9zU-y{H*W^!1Xlq0>1p<{C)x7hhKs_k&Yz2-Er_NT4w~#~_Cv+3JkDVt@aigYIODh2`Zj>-;Xf?Hy)-Cgdb<(ZNOGi%qVWu(n_Ld38SP@ zU8|uTw@#qsc*h8c1bV3rW@3||C$h&htD51fb2CiH$nwv+ql zy&c#_iW~mQOc;MRo9ML$E`c&Y4kj0owge5k@`l|KP4N1L*PxY zlA?1GH>rEydEo58tNA|JfmifB@N$2JzXSGma@0D8K1YGOX1M#@sj7v$A@`XR4m@{? z7)6cRT4^KPtqQJ&BPeZD)v9S{tVVic{S4+kZEe78hsXxtFiD2FlDa#|GJm^gos+rA-Fwb`=P+`2nTLVhW+5Y|mP;#S6o!^H;<@qNvY4feaSr{@S}O9ByQ+J~ zx$CIzUFV*&j;u%Lb-)qu5pt9qvJP9j%|pN*^E|4~S?8_#dIPgo0M3szCQ-Va)btUcyIU@v&DxzAif)*^oma14Bm z949*ZXs+(wcJ4R_tb^7*Grv&)-SPu@HN(B-+;$8^b$2x?j+1;wUM-)N&&UtmkL>;C zervyZ0DJ(}DrB4>tALZ>)v!!-FkI8U>D+Si8u^TT8d%G(?XwP;2hDvJ>P(KP>2mjm zbJJOgx|3wDwa+?euE6LNSwU7pEkwC%x!0W=&K_$oqI-Zt=5l15Cd-j^3Va&xk$ySX z9n1ZNtI>7mD&0q}(5rMW*+;UwVQy?UI}it)1J+P}$+~PQdPRfjieAB}XbgjAC?Ccz zT9>SxZY<>F1ai39P!Y$aIzui6DjCs`ujtYAaz=TK%NrGp%k&CnyA13H?qv@CEWqN>IN9SwwI^9KfW4xQ}A%po4%rY3b0={BhwMJmB;d}%ytQFBl z@FH4KEjK#naxcKR`w!rk)vnW1=>O zet}-32gwCs9=VCxZ_t}`iNDkz$OrLF)+k;`E3Az|&yhSYy5(`t(+hMSISmYxaG(dapfkLCrnLRvob%tpGaYchAtXbRjtdECMeg zi%DO;)!JtD<^7;Pw4YiQ;|GuxoYlx?oTg{!Vp0&b1>AxzfqvJr8QG2R+7Dcx9QPtcQeDLDZw124mCtcd&D`QsEpRbjU$-)Zf#dh%Y-*j%yGOa zFrL>!JiS{B$Nyoou1 zPXsrG)f}Chna$0-##oHU@^QS9T3L;!SH-baQR}(_Gt>p@xTDeU0iA$8*3%^u&SxC^e}Lk9vd7Ry&}yf=0qL|OyVstS97z4na9X$)NpH}Lk%F4 zTMu*9bw|1sC-L^Yu^9=ij(Mu9Bk4Z6pN_-~55W&%O+x>P;D!DozrO3@ zDCz_C+(u?&vpp}5F0ZumY6WNwwK_Vq!YnP#YA*Vz4O|Bm4S@RY2=v=eYpT`YpNwvk zXlpZvk<(~x<}`AFa~ZA7a%y??l~xXT4Sub?(Hdfo4!oh+2-?t1hkgx#2JUe5IzWfh z5zw+~IrWX!!0f;~@&;x{-U-|gRvRd57pwWH%r3kuuVdDQHg!`W-V|u!4no}#ItVyQYnye@Sf zWPa2(iK%1DPKp{!Ciau~7Cb4W zEwNpKZzDIk-(FVdovrrhSDm+)ovkib7x|b!;a%ht{>tcr&Yfjfc)Ca~6ZwgKjy{%5 zgC44%2GIO=va8kGY$v-|U9EPqJ+zyA#2@o+@`(8e{Frx@ZDl+BZ?G-UALIUVfHcvK zgA@9R{In7uA_1p?wn2P=?2g)Q;KSw-Go93Z!%rvEMyX8TCj=+-P1#zuL1t@UpzMLn z?%+e_VN*wrA$4pamcVzU;hW%eP**zA^jo1~plk&Ul0A{%1H8vNWNI>tk1wX9N|!AW z9|RsG2g_cF_5|;?_E;)%G^xtWeipw4;)7)iIYf3REif7)d&{1Dm(^SDvUY=aTfJm* z#4`KIk*~@=vIp2I)zT91o%tpTJ@~iztML({Z0NryI{t;Y8T8}NA0dg;3&ES-P8e?rN2ACEf4LCjCyKk zWYtxBsI`#Q1L&?&`X6Sd0HM9zJ~+1CKvnk_nNDZWU*tEmj#by{VAcUTnhkLz4J<|{ zqmBU-yue@RGhBrx(_W~q>h=PvxdSop0B|{IC(K=6?S%R3sXf)2n7^mm3pqV8>Va`J zx2D?2`l5Z+8litf>nE8(XVRZ!ChZRX1*^7I$LeU-20EF8&~u=x(E0uXU%~8*MpzZi zN@j#r+v)`FWL7kPke{SG?TA_PsvR+NeYKa`6Gzqy^Y&C5W3EP4W9zf_MT>?$3LT7| zgWSPxS!f4TDS^K4>4crl@UVwS~8!+7|Hw z>M(Q|>V6?#NiX^Z=uN95yQ*2;ssSDDmPC9wFwFf-zL4JZGth^&L46^$4Nw@|7FIQ@ zs#(pfW>trNBA-bg`U&U@?o0d85pHp}ggXK#2`-6_tx;E4t!h;>tD9ixNVgcWMgk+; zkK_~SN2^%X%^GGEt15I9q9ff8@b;%4$VX^ptA<(AtZY?*z9%0@fBGI6K$|0Tl-nHF z+G6ekw~N~q+|}*owxls>EZPd(k}iaQfm?t#xAOA>yqVS9nh(31yU6W~$Rc2&+XC5P zv<0$b(blMH1&#sD$Md5uAJD=oh}r_YApd|zwjgh6H3OGaKWK~Hj&3J+G0+*@86BIW zQy6Uy#HMX%baZM1w5El43ALnJ2vr67JRCuHcOKA3o#)Pnm6zw^Ev&piORE{GW7B3p z96A?Sebl)?Uv&xQTI{w(&o;CzjRtK?=lS#fwm5I2(L6jaZ)xQLT3Lm8F}1i_m={+| zfJYB>y$jtywFMV(Z=p$r4lm(DeP?kkT zGjKE699#z0HDvknF>)S(lS0cO(p=`p@9sX}KB&tN6p&Yu>w|qMZ6a?mU2A;D65GOw&B)<%l;@6DAc%57`TB)toYesQi z0^<_=s&UO|jVp6*9915wvCwGiKQY?f^Z683w3_fPw09^grevcc(xv8JCSx z{1Q-_UpHE+t<>x2f6Z8n9$o2Lpc}XwtxC6`&t`CY=oVZV+S7~1C8IRI2$bOm-9zp` z^&l`vJ%P^0-4pJA&>QG^-MC@2P+O{N(5WijirOvU1O7q(q&pc|CxH|00r#LgNId{F zP;VmthH=wquC`Dw7#EE)`~u+c)u^vVR|D0-Yhax>E*K6!54e0kdNfe?0}a(v=zP+> zWi(TptGCeSrm+eY)#+*YPr0YvNzikK%LPAY2=0N;!@7<9TgE=Oq1s5@=QdIsgZIN) zNmrqEB~SxggVv;b-FUF(f|?_+X!>=gW{0L6_0x z(DUwCcbt137!Mwgnp4JUBRyY=cm!Pv)TS4ZbKX5^oPz%(kby6Ow+>x`cx`$S(F^WH zcMSA|k%4FACybNO#faCTi-Edy9j;qr+;zZ3H@~ur?xqF6`IQ37PP&V}aCf_V+?U`N zZayWyvYQrEw$mNp9dsvnC$gWrd+}I3N5&raIk4A#h5VP`o$fC1E?9X{xrgRe@<9us zLqX*kY9iHVsA#OdM&>K`wYvkFN6D+~p?QG4w6L<3ZUb+l+risW`P7Y6o2XCSXV5pu zf9<|;w?lI)v*>J^TiHuzf%8C%C#+a1o{sCx9&T48#E_kb7)Q_7xa<)*u7^w0`42{5q;;rceg@wC^?lmGzT!3 zK6D?s_l*zmzjr^lo82woEwHjHbLl*qUC9Cc2>%B+n=+5ir`eS3&` z#gyXU;z|i{3Dm?B5AoB*L;gcIo`??(iM#GS@ICiF_&$1lVxL)QvAE*C@xX{H z;z1LLJMLXK0rErQBQnY;AK5494^~tu1}=u0IO2iv(7>iu(1gfOAYzL+;-L{6*azNc z>^DBJkF1RH0dSO`sQtlyvi*2=f3hM8z!o&e1iMZ+B!ZLujknxrY#Z%t0chHz37NRkMgGN$u z-M!%^6*t_Q;G4*P!#qVQZ`fOCGDMS#*GwwD@|wMYCKuP->uz%RlZjW%SJEr5Sb8M` z_%$q5Tyd|us<`T217AblOZJLoP&D{e@dBfa$_w@qs*B6+6<3E}6VF*jC6n@;y?}nh zb9>qS2I!(0`^$*Z3~0(Si|8VT$PC03SuoBln!rz$Cafv6Is482u;##D@L$%9WkN!Uh-^SKa5Us)MBPCnBXG!Q%$TAmjaekL zCGuOamh2Za1F{Yo8Gyq^c67)l(u)k@u#p}(Vl-m+*nQRrrT4&%p{?-T{$j0wmMn*$ zsK^0i7Yz}=&wNxLF?`^tkrUAzBBvnG2CN~X4S)ws3SS&Ga>1WdngqYQcWaYQgu6 z8RDD!-8JAZAUJE!Ixvg1W$nQ2U|9fX)rBjBr~$4nssRElga`J76g7o|NKK%IFp=GX zrC@E)BL!fwT8P#ZwM1Hx4xA2_!A#^BKu4AmnJHLRbUA8NML#KYcsns2s0cP-rDCm- zl?q77s)(w{tO6V}BG9vzh!AO@8geT#4XDH_iz?!nQ5iUH)J8Nyq{j2vnxzI(F%?;r zSS3+e95*TfCyYACsV(XV8=4&PN-TL)7giUZI-;&fB~pV^!%BuoWtI%60}1yb663eFx%tp^~#Ao zKzUIJ9+wq@*I`AGQv{qAy4x!+Du~@)1yK>a2i891@AdY1Wkgww%ZhTMASwkbh-#M= zV`)%V3@FNWdAq%eV!u~flmVAPb^+vhtN;)TTo6`qhI@A_b`?pGsI#Cy^^Ao zIEW4hyd7Rfo{8`9c0#GY-~Y)dD)#vlqgEL2gD)C7D_~Cw8Qs5vzs93u9L*)orxd9TnD`vsEY2#@Gs-9`M;9*so7td8b9A(Y2)Yo zD~q!d><=PQT!NKkdC@C2I5vv|&IjwTS3;B&htchj_gnsvC0QOs;;uB7f0bg;^l%j9?J#92j_-$%quF2iDSq)>g9wlK06N2G4HrnSQHV* zy&|Hh$N_IS%fWI&Pr!fN%ML4?Wd}m+q*q837AN69;bnuJfMr7@#FlvlMIo^a(Uaao zZ?m_>djM<&KZO3EWmsAE6a0fdLiC~c$lC8I++ZpzrAinu(<*vHUPU zHNny(;8d{Q!JC=AqnTM2@OxOVk^jnj?XB=uf>*+NgYj$cEqzC`u(v=~_SRbt-&^2~ z_lCZuS=nnK8~6?Ml(!7=Q@~q~<7Z4sI5{CtN={D7Q{YqbH2AbU13n|qg3rox(k8L} zIKEA=F(){#9}k=wK8qZeC!~cASoE13lgDKWc(7nJc`1*{G$fuM-%ms0`{Cel{}nto zd}+ul`C6LDNkL5VLcWwS<#q3d7Xy03Tgwy{jjaXNuvqe%cioGHXiT{pp6F~fywTV? zhCdd-3i6_(=B5{2-t=yPW58O4ycld15EHx_)_UZx15;=;8C~A;!sHe2D)_2*4SWrA ztVC{1wt@YWzvKpFuE&@_H{e_%Op&*7E-9$IjX&O^L1Uvsm}EE$bAlD<3e-QME7(ft z3XC4pjqHc~DL10$1{OzN_O5twP!(G)NBl8e4m_co*mwCuZbIfp7FS;KE_-p28AsxD zM(1U0IeS8v0Z(Z>dC|M%#Y0Y9xs)wqPicI4!MliMz%IhO1okt!ggv9r!AoI<%k$m^ zFC01XRpGo$>+AZ^=wgB0S@gBKX7AM8X7Q{`Gk5rMBWj;jnlg)AqJo^ycEBDC~ zq&Ue-s>&)dFR3Q0f~z2JliZA){jww}0WN{;Jc#Bc8|5bW55T`)9+0I-Ns=4>JmBiG zn%p2aB3hc1LPlxepj;21Ne;m}C=baph^>RqB!@9RBoE87qzri?{&;`Ar{E{zsrc>v z@pNSy(-d9V%C@n`;)(d{Jrh5@U*KQfZ}4wqtBQs!71+)UWa^5cY++m3TDcDWkD&8m zc|?{YWyy2YJ`>Ny5AUb<2)&4WBpySPE2^@cB?orkWA@U^`hdB{`HU-|^bu=w>Qh*~B)p zMX~}ZPZpuuQMp>KLH`G$wv3Pu#6##yba)|>D#?_cEGaOJS?ItOOZg_h%Zj7|Di=c+ z$yKN}NhMN|ES5`TCGbl4OtMr~hIc7EOXMr@&HL`XLeG~XiIP;A#*zTjSqgNsloZNW z`Ayyz4@88lLMo$X8FZ<9Exvl+yw|9GB@!!1l<6!nFatb;&17#7eJ$RI&)ygBjrihy z^%5yF*({bwNeq1p{~M7|Nu)kcpts@ z;-mM;3n>YdIqU;G@QU}|2QM7yc zm3b^4FrUTtZi_ou;OLIHE8<`r+q=M0E4Ffh*-9GaBE}ckMV3lQt%P~8y}Kd|xF_Oz zx5RDmZPc7+7g!qQ5^^rGSYDWSPsH;uiQ8^3JjI$ThDBGd zA$pZvW1r+_nZUauu8IWSRdEe`4SA>7Y2=&&Vkij_P2eT;E{iMTB#WWMR8F#(N-Xdx zSc%|I=$&9ESu7>7cS&3piQ!4)9cL%tISzz@!<5)c5=0YwNxX~Vk~qeWW2w%g?ASk! zt;A81!k@%T>YW!CL{jg9xG0igoYXtQjpqJ99M~_d=lrxdGQHI=8a@G z*)28_xXngkJd$PbsK>kvKzeTk?AvTKyUuQaZy-Jz7{z?VnCAluSn;BH89jo!j6eo& zI2(bg;lLd>2DPJ^L{>B}6LK2D;;>;-``AQePGH%Qlg-QSeHTB(Kt%SjN$^i(IpE3e4PXP|8362O zli{Dla>Ad(%jta+-$j3RfE{H05#JBq59>eVOlG+d&FSUxzKE|Pm-khC6a5fB$a2Gz z%j=8LA=a1mgXV!Jx0lEJEWU{3;5=S(@00i}Dtl?Xv|bf(Wv>#D7M#{g2TtcXURBRV zq$*IwtLCMKRSl@>RYctJDtN9}LsozlHFjWCM@}_xDrkB5YRK|lb(x!#$EZ5Sxk)Zk z!%N|%^lAX9z^Ra34!OBVP55hgwLA-23#jQuc&5j}*p>=x!CM=i2(ON3K0lkcx~2-N4;gcW`&s1Kfl41ovdUz`a;+ zaBtQJ+y{?cI`SWz0-nOAf~T_1;KR7;r6Xw(Nk{tP5w7p4n6o}m&&!L)RRycCyLqL& z(q30+X|D@V2HX|e9sX|MlF-iZl>wLW%6dKE=?*ULl>nE3)f3|$UMIxMg3IAi>V#1_ zuOqBnq$7}%^zw>&#k^iXad2_e^oFOG*8y2MNgs@RdwsmZUJ-B+SbZ_> z2CP|LYs6;(Grei>wfAOwExlIYR*1|7W_eR_q&dk{#5!O+4LZkbfvh>eY;Ou;Imi@5 za+105&++DY&7t#vx!!!Q8LauhJa2*5#A^y}3f}@?zPAvb1>Pd?LU1H>F?bQUk=Gd9 z7}gSu7lRu@mx7mggTYI|4WMc53Eo669XPF>#-8X+^3vF8p$x~1C^Tvb6BQLdW+mpT2z<-`V)U`dZ0FU;@c%D7R8|z7oJ=+IM@JMfz=i8&a z(O!Ccgf|jA5_SfR)7u&C;ob-@BgPr*O!iQ3n3u^O<_!lAhc`1knd~g!%-|v3P%i|| zVu$R(-Vo2gqnLvjWSLwp4YFLW0I$GbFb4S#kFr6sk*tVjhZ-cc{U1CzU>PKZozgZ) zN;?%e6@DIrR6!4eRD~L(8q^@wp$4e|HPEF7cqRTWDr0lIv|YwFp`|d2Vr=FIw(Jyk zS@_F(sA3ni z3&B&(PG~2xs{x6@i4iM+2!3YxtJ(Qs;bY(=IbIVw`Gjk$jz|q#CpGM>;K6tfbkYFl zlTJc*0*n)&PABK^TUIA|ahB;MpJsu*6=F!X58)BmwT1rX$&Kk1HK{O|yaL%;1aMcyo)OiE)JVxjO7aPzONYWLKMZw#5=^IINOV0 zgfj^5B@Lhm&WA!6Y2c{Gq##rUN3EJy0Gb>e_2}gz`N8>NCBry5NeWH|&V%=aNr8MM z3C2lDVsH|0ZfGKKVsK9UCQSt7CJ8Z4L=u1#f^$Gac-`gz=YSoK*JCztHu%DU5Qz^@ zIEhEHK;r@NNnGsSlo^~EzPLa<5(l2RBsO+t$^^~?I}E!nWdvu09SiG#WB_M?9TRJX z_~59uL1F^2NDO#llIY+VV1X4vq63md!#Fw^|0E#_I2zc2GO$7@n1R#c8KnSDSd8%j zL_AOApFa)aQNMNBKYvthI@G0u9o5qTNA-!C(FI5KkMVED7?@q)h&GpY zQIB>OaMZOl^zU&`01n}Kh`O#O1SbGTU00)?!5rWmu%n*GoOo8Fp3x-W#NepEl%k&f z-2cvmsIwsI97y)>%!oR3^8Pz>qRyJU@T&jLBn@X${(t9N0dRhJ^?zqw)R|cj=VL+G zCeF`7|IXXO;Ha~d|2umvFvr;)bjE)E$nf*FrJ84x-NgRCq-c2N#E(8sk*p zsCyJqucnfCRYkpyg6Avhl^Z-?!Rsq{eFfLU;CdMR{tEuy2>#v({yq%;J`Dbz58i(T z@4tfg%m4d+Ik+G7|LcBK@O=IMdcK1DQNjJF;C^q^|0#m|QNjJF;C@taKPtE%72J;s z?nedpqk{WU!TqSVNM?1@D)G_shZi<>38t@Oif2^K8NA4};H(2A>xVKHnRB zzBl+hcJTT6;Pdmr_Z@=oI|ScP3BFGhe4i-z{#Wq*ui*Q7!S^eJ?^g!jhYh|D8+?B` z_`Z4Yee+;_fM9)qU_FOm{f(&gUV`;Eg7s2@^-_ZMZG!cPg7t`k^`nCIqk{Fmg7w*w zV@Y_NWBuzqi_-g29tPLL;CdKb4}<-` zVqt%_V86CtzqVk1y{LT>gZIn9`{m$z80=pe>^B#B?B^TozZ~qB9qgAK z>~9|IZyxMNPf1#mh6LBc;CdKb4}{U{8bq2mmTbv9qgAK z?3W$vmz@FoJp|XoV885OzwBVY>|np_V885OzwBVY>|np_V885OzwBVY>|np_VE?aR z|F2;GuVDYLVE?aR|F2;GuVDYLVE?aR|F2-bn_z#3U_J9-{oY``%3!_9V7zy{#FWIk{{wK~f6$tYkQa4vamGKajDG%9gN(rn;t+GCpYae(Dv;3~Cjm%EUdtGk`Ow8{s?+ zIE}V4Qh8EJOIcC^ECo(ZrU0iprR zWxl^M-(Q*Uugv#X8bO-xugv#X=KCx2{gwIt%6xxizP~cxUzzW(eDnK>@_6h#9y^c6 z&f~H3c^vSjkH^mAvGaKBJRUob$Ij!i^LXq$9y^c6&f~H3c^vSjkH^mAvGaKBJRUob$Ij!i^LXq$9y^c6&f~H3c?@!71r{w!n^8G3K{*-)wO1?iO-=8vyuiWI{|H{Arm4E*$|Nhr6 z^8K%Tzh1syFW;}1@7K%s>*f3P^8I@Ge!YCZUcO&1->;YN*UR_o<@@#W{d)O+y?no3 zzF#ljub1!F%lGT$`}Okudij36e7|14UoYRUm+#lh_v_{R_456C`F_28e@ebTCEuTt z?@!71r{w!n^8G0zlD;J0pOWuS$@iz^`&07$Df#}Ce1A&5KP5|wlYDm2-ZW^TU-%&JS~bnDfJ&A6DR1&iP@^59cH~Kg{`I&JS~bxB|~|&JS~bI1$@n zZa>V|%ej7-^TSbimUI0u=ZCp|nCpkRept&cy__HB`r(o!=Z85z%=ux?4^vjkIX}$# z;q)ZuhdDpY`C-lv7ZGWb^TV7Uu1s=%nDfJ&ALjh9oJgCTALjgUc9QeMoFC@=Fz1JD zL}BOrFz1I8lAIsr{4nQ-IX|qyvz+t8oF6V`mtJl^%-73rhklrFLR3mBO1hJtWIS*k zc~`QQyo=PGbS7)4b&|S>{a#J2gVc$3x{6vmsUvBl+zwnxJ`UIhTtPk-I1V_NEC(*9 z)=GJ7(gJJ+E+ZcUYymDMZw8J5E)FLgFQGO%L{T&WM<-3mLNLFHv^Z&`+>|r`8-WYR z>wyixdC7d>d}?)+>*1O6D2+msiz;gCvQW&meUFH5E-(}2@xDeK zCBRbPqzU9jns>hgUE}J0e!TdPv5@eVA_h11bwt_qE>_?=%aoC*ZYtIebg_c)`uLh zei5}kB!Kmcsr4ZbtPh6LGT+~If*<=PA1QiQ^+%(^c3Lk zV{S59l4M76B=9KmB-u%xBuA4c$u9CFIfgu;-!aJ_CfkxjlJAlql6;5q9|E_Ne~iZKjz97;AYH8bm;E_e-Aj9{F_Loxxo44-=y@r$?s79W^xzQcz1Fq@UG-N zltv_XknT+0OKn8*?ohvn+KA*{QVP6>{C3j2ll!Qp$^GPM@&I|7JV>4<50R(I!{ll5 z2zd&X{wdF0oP3|WIQap2aq>g*;^fcBi<2Lb_a|RXUIzX-wSH1D@W<5plP{9@C%-}7 zpL~hDKlw6wfASUbetz>6xX4Y(jli49E0bHuE0bHvE0f#ED|z1Akgt{WnVDRXTn>B} z`OM@>@|nq1`$!E#?lV2h4Pd-Q9pZqGR82CBzUn4J0ex1BH`8;`X@&)qZ}qk(C9_tSspWtrMt~p$C+~hkMZk%FqaUDf^Y6 zax{raz$xVAXckj|)5z6JrUBi{U5@^ujxvC5R0mXN8VFj{02);zWi_n?FpBsqe= z1m4m|?NZ>S$tA!`;9>*Z?<4&6Cm-dnKlvDc{ovmKZ7%{}1Q!NKrNB~VYJk+nUm4nR zJFtTmb>){Bg$$g13HWjH46Lo9_9@^ex#!1e`84HE@n1eh`7@M1&Hwl)<&3XEjhkKX8D&hTa3fBKlUqQEvj?1jnu*-2%J?j$J{z4R{+* zJd!?gfy?38BT4T9z6*{$l5`dDDmeB?(lx+q;MgNc*8#7CV~-@=0K9>FDDP{6ystr` z*HAkScsvrmhSIUX-N@}4O1pr^AkS+k?c_OYfHl;QqP!EyUqtCh;0|cEh|=M}Bj7b> zpzV~P51j#2KPm~DQ3<-x*_73ZN`f|29Q2^#pyLz=U8Xo_F~vcDDGr)TaiIO;zz2#0 zPblWMCFnDQQ28>_AbQPm@};4!7pD|HW_>YKUkbFoi1K2%SQ(`Sz=d$DGD`D+^U(v! zD9r)RMPDeRGz&NzF1r>js~SCQEpR<~H5%G_pqg5B(A27fc2*tqvg)9vR0l1kI%qZJ zz-oA}+D>`Uh025eQy%o3@}TFG2fZbQN;Ce(Fp3$JVtzQhyNs*l{K@yrxtICvU~d(? zbR_9=U=L8`tSB<#yvRif4eiCPmR>d?wc-MAaxu$Hur|J_Ax z4QVY;(MfGJX${ZTK`nmaHtwQdNy{qmBieGbaW99Pi9O@U2Z3T$D;!L_$vCh}3(8X9 zGT<1v)>2X{*rWx;9VcUeej&<}yxgCxHDw`XWo8rk0yst!P;1J3ct|6#F<@OiwRt3Q zuMQ3{mm~)IRf#zy@zCgm*(9-1ZZV5A8=g^3P0le3E;5qZOp?;EidsKuCY;8(?<4iY zdzAAtNPR&gsQ{`4Oef6T8XK}L`_CLW(qA+nHROB$)qXFj(Wr-(q!gHEklcm z-_rK0iJopb5x(pSZUU(ne(gH0hcqFduYA68`g#ZHt2gk&Uijezs8D`5k<<%a$`2=z zCPKCH!^xycP_w7bO(9L@soE(`g#)%j_idD>1%5aks6ACqI0LA)Ro>VK)Cwyn><4O{ zl{d}|{BS1aez3inx~rRJxRji57HI(PB|n@^ngv&rAI>4o4&1K+*g#zivb<29I6v^i z`LxV~YswE7kmkcp<%bJN3*fc#!$qWpa9{c1V$veGvixufX))Ydez=sh1YR!pTNb$D zGTN7dnHAKR!}ltH71Y%s%7F626{O`s&aFUt$Pbl#E0Hqt!_}l!NE;{=TGR0U0n=ZB`vtJy&g39acS8Z8rJ^<2qO!Ry|j3 zRvlJ7S8X=>1xF%hT)(T+s>!PDDutpRt4^z)I}Prw_Ns=f9vl6F+UQ&fD&@+Mcn^lJ`cm#{#&+55qv(Y1%1#LC~MxWqRW~7v7DB)?m$4sEIub=V&X$tQ% ziPqVnbvC7b-h2|RbGbeRs1%q>>H+$6b4lHdn!lMxznP5cB!07i`T)@XynxgT^ywDx ziyq(r`9k{50?y)>t~TZ{gOkV?Q=bi7K>x+e_*mdX^2M|+VBVFcOX;~N;D)OnS3}FV zF1E}gUq+94V9z4@4w9CDRg?J53fh+iY>T)j9xmgzE9kKhj9khuR+0w6(MkMfHJB9Yd3g0|K4SOR{pqR$$BwGz0Td@a9P1)N5{j^8u^)g{)^e>HG5ZR_Yg$clU| zJ=c@gur8lQZ6p1ffv(Xu(z+73j<$`I*0FA1OYei}xq)@N+RG-AYxs@SHgRnYa1FK1 z^gIZ-fqV=74-V`38lW1;R(iS4KZsv!C2eAze=vOyA#G;0KaJmPr*sfd?PWWu4!D)t zc3QV$1vr@Ahtlt0Yys2w&EfQ@2f9K$oKyzfOz*=m42XQT1m^+0wNhTP-SjPi>b6$g7KK8RFs{9R+^vm6U5m+-qNL1zzqod+x8_zJ7ZU z_f6pvlfasuzzHUTZ@tW}-ac_AWp-G4yX$s#OQ{w47>9t)(n| zpGdzGfb-~aBAjv_P_OApf$mS@+9<4R;_k^@JrSr!ks7hhE#lhg@ajcCdz?=F6fCfE%`>PsVuwAA(wT7D#Xzlk zXHq&H3#~l$tiUhNqDK=}+9g~&8xFh#sO{@)>SqAYpx-&9W}uw)+)zK4D`!z&Mt&~b zco`O2dFmc|jlsry4yE&g-S<4Mo=aIf+j;Q*<=B2*N1h+#()sjj!4ABK`UPCy16)CV z0X%yJmf`b}NEedEVIMx9(nVZ3AE*`bBGLs|j4$Ns#X*8yLiu8>$66{cftRla>KVU; zbRqU+*SnXJI)E2byNoLr1GV^GM(I-E8rm+W)B#j>U4iUa3)B*P1*OY?mj;XcW#sRo z)CqLW{Vq~Bmifzrjb5AamGr$FxSsqfTDyV9fn61(x?a}_SnuCOel=WRBTzYiHKh$e zJ+xO-x-!gnQ^1u5pmSFj=B|z_O^lA?DK6FpJg()rmFLEdwew_-UMHy|&_gv(slP^Q zG}gjrPH535DxGG5M->5$m?@*h7!&!2JW&o}i*leO;6q86_Y(ehGc7ILsf1^#16Grl z&`(QpjHMaNJ$l3a_2(q$B=S1_t0_EDZagXcFMX|9;FHDhFaNi(TxxTZsma|+1J4rr zjK+cO?Ss_=Ys{E$DJQCczxcjJl&M{+Map-KI+IHnd!{yOG@5**8m=HukegJ)1EhC3 zMGc(5k(MviLhFvX+(8S4v@HGCLBZ0gbY2e~ORZ9M1C%Ol8eh`e zC{HSr4x6DWX)0Qx2g586Qfq;R)ajz-dIcq;0gV7$8Rp&iz-aFt7wE(oLgNRGCN#EC zooo%sm_s8CjXpFM(FjDN62(v>6QhJu0wqYD1nHza5*~!yQMw4#f|XFprcKliVdhd` zO5bfkS}AGNX4G7^(|Za~8KzD&8A+m~K9qC_l0)fb9EjS?HhLUR@2Nq$s3mQub_5up z!BN)h3q{ALIJrU4HpH&VqG<jzfo1enHVC7>qtr1nN9da8Buafqf(m+_LOKzs^iVGJ15YHE@1F=Xn({O-y8>82 zFFC&O<#%ISQ#wSKEhNEZT?5XKK&1fO;-Dp#Kiyog+W zeG&ZFHR$D}O9FQmUJ^LD>)3bEYaUQZV4TdQa9`K2SCTG=Ps`n}B3%JzzA8Z1!1D0< zKs~hAK>wqFu7AeZw(tsaXf3LAXH{eaak)B2b-H1=w75uHV-wbRd zH#+EMyo$Hb=XOfB0F4VaUg&0g<$9st&9837pZ;#jcam-g-cFx8X|qK;!d>vJCSVi2 z?k3#xjlizlWYi zUA+fy{TSNrBi$3CuI|BSuchMwt`7pWfIPspdx7_pKM0o`102I|9wgl#BD3ztum1o& zAEy2Q@FDU?;H53V7WzF(dMHGyJc!3s3(I5lS^<2B{4uUPgip1V-jBm=TY-9CjX`=e z#2^W^&OAZimB2^IpM)om1&*bcu}MPxvQLNTjHl_fit+H&ym&;6Vk@@_miFlY7H`a>RIALjO;Lm%JOsce4ezHh>>=#e-QrP zPTYtQCB|00pXd?eN?stX1%8Oy3zXIoPtr->4kfgSWU>PBen$wx>p0AHY|F*&xZ zL*Mx*eO?51k$;T*MPh7>N%=TwJ@8|pWj)%>Cy+Eyb36v#`| zKL-2+`6p?438)6~$)G#L2%b-J*A2A1M9)uB+6dgpb!}H#u(W6ue74%Qv|wq?(pOvX z>*~$bL#s_ozpWBkU$0VFYgsG2L@BSWEBY?x1xeisH`4Z{q}Fq+bk^>r^-JGw^eqo^ zWh@*~T|!Hk_AtG@(HE^W9|v#MKBhHK`-&DlZDU%<^#7_8E5o(?MK7>cv;H9EmFKIt zrnO}i+*Tb&&8DBx)c&GB*e}tk4XFe5G2Yr4^`ozb({!Z1Gm?Fae}9j$F@XWGtsfck(vzkC8vYnob`x?3-G{l~pQpNlp)^*c2_z08yN zo&VE2`#bgFXp8f1(O%aZ?of#1_qX0ho1QXTE1x<>wEmR^{UKTfeR8ApqODMUQAsIO znkxl`O6r2OQGGF5BOOOQ@6kr7zNpj@Dh;Dm(^=JnA8noLi_r=y1{AEL;*J=mx65b% zu`pUuwWf-T+F0X03@xtmRTiW5-?AFv0(WX7Yi0)Ii#Fu z5S)^;$yuWHcqLe)z9?RaLDAN%jV@ZD#h-$8T5Ks;t&PT5$EeG5CWU+Gd+ea>?3T~&q(&t-T-U_dz}9s(s*Xv2+w-j8<_8M%5{|M18&s?9O!`#C(v3892GF3 z2MQ4b)rxwUlrJNRlq7QvNk1@HXR2CQ{a4 zZT!z9=u}>!ms;Pn*lAo!2bAk-U>b8$1(dr@BTa#R#q8+;r;KcAgNo%}g*X_w+6+>p z^J!4H_}CZl(FmEbP`6yHpX5r>Jx4~-Ob1S(N5gsl0X|^fLmr zA3h*%x{jO))Jr~_nJfX8(578qU%38pec=gE?QBlK>$&vQJFca0E-3@LGM-B+2Kq}Q zh4d)Q3B3~9omn}q@#Y;JuH93v*(%mc8P25h;!HM%xp5{ZhMAlg=6qtH9cOPmbKv|> zW;SYp&irKB<+Sqd$<&=O>3m9e`&i(Yzdq$Yg837B7T54y6l}xVP<D2HW~Y8OkO!XW`!QkTR-FM%+C%p@0iEgYhmP_&p81LoJo0p zDY-M#3~XZj=e{zZ;=;TzA4YrW<#B%Ik&1xMsuqM4=)BLPK8HD!YeY-6bLk9shkF>$ zZH&3HOYT(3I7)%8nyMHv$5^{dF;L#4Y|;`VPpPFf1y*sz{diT3l~y9{K^;JMBaWps zj&bRx@z)&2LtdK(%+(6zjyd_V(9s=DsTC+^Ul;InEq#oNFhXKY zczb0@hIDZZlrcrf9>-M)RE#u|#*|4VL1L8xohv1o&>0&f8NIQb+;xRf9nSVrl5rl! zd@P}46o?Taizyi$Vx-8TfUQc_kw{#%Eah%BQdg{364wOTter;+C|G;uQ!D6!T6>~& zpB-puHe+IR%N%O6C>ix)1dJ5l1V*Wg&LqWHnIjYxRC}CEQWncM<-JPbcqd=D#|h(pfV-+JItDGdjIF1h09~2ZbEOfe zMo>@c1bW|kQWLWm<)c_Xinb`1#nO~oEy)OL`CAQ13>NdH0^?(iQ`X8@6llP>S*?#F zxmNN^!M%ueVxU-835JP*L%260=yPJ7{Bj8QMjjyUMXXZ>i+ipzT#pp6P7D<58o)X+ zP~2jK*%1`gp~^qUo8G?aqTOBW@YI#9&3mj}8m6L7C5;9F0?H+Rk#?9yuVW9ZpITMu{W;JKU`XQ3vH zxx2~Tp)rEC8b*8s<%CoRbSC9Yt`nRG@xVR4_9&w?insF(N~otm$2&^nAv%55N<1FL6FEvgYc22OxXEp6ct%Ib_pIiPoi8b5Bu_6lYYVgHSSXjK?CVY2X@8@4^u6|e(-vBMpW;`&sc+|-7Ke9q&(0ga<8XemG>pU& zpney}V_CSpG{XUD(RHAprca1(8 z^>HI*wDA-?HDZAtO`+If%$KX~RRM=whmWTwZfUFO0g7{aZ(N)8qNOxYN@&p@qbDc9 z%BI$(7jgkmU)utpD=qO}-PV1HGl6Qg^~j4^K=o5?6zVT(rIFW3S<$yx2ewvImZpSq zxDk}Z9@lIsl3@za6<3N3nFe$n<*vUOK=pEQt)Cf-^c5*f9#Nn#?Ibqr%yKm|U`0l=` zBjCIHrjCH`?wdLSzI&uxeZ~du6lvCXEKsf-$r13a8B1vT!~2^_QM7p&T!M<$m5*jn@C;|MMyQ|Gs76z2Y0iC-sTF-@+%T z=Rf;iK1Ut@-#7JXM)4HByU*mTIU0qzb9{V0_X|2=&Xc?S97F$K6@M|e?uy3i_N#v7 zcmBRGciy+K_K&(_{Qo{j-7C-K^ZC?1ug_hWJGt&#doSN*@3$)rPwczw{dVQFywmR$ z^%!wX8f$RIJK|a)@{wX%ig;f2x>CxX@uJjG3-lBiC69W%c;ksOK5-@YaO4WSsZjP# zdPXXM{;HcK-yKih6?%6u(nXY&c3t6rc7^|IG;tX%{?9H_w7F{2F)~Mc9siSZCvv-& zayw-)*Jlu?+rejdZjT6(eFXAw66J~XR2q+fUQ&7}la*2_btUr%Xey#R1rPQN$ zsF|{>K|LX(DK|5Nac7~k>&{NCMq+bS!0)Pn@l^qrr1yH-UF}!F&l`bi2ab0We<^qD z=qRkilw`hzW9Zn7r?1r5L*7k_*2ambJsU%=u0&G*iI^v+i5h_=eFXkGu4Tkl z<%sz0I;IrpJ^Y1t5YxSnk+I^rbHPY;48Py-xr*)5vb`fExlWc=B8QT43f_;xxl7U0 zq2ws%-qByEWmF%bwhOJ>-bLF*5y_ZZZ5P_WeNJr`B_!_`ZSH#D%FtVV7p)fB+qLud zQ8MDo5s144q7NY2{PpsU0Nb@Si}O`bfxd&OltzL@`XjWVRZ~`mYr)VH;fj6|rCM-q z5@WCROxw5mu#!Vxi1sS=t$H+W_3?F-8qmRwUtde95j}k^Sh0pu6Z-oaaAY;5(dhT9 z!9XpX%_L=>p1Cn3?QPmQTS#NTYAu|uER3&YqsD;ZD z&ZHPEUwRJZ2kH`*q-?o@QS$aNW>c$&JRxeXL-J5b?p>;YaslO`I))rZ8kN_`V`8Me zoXsclH~KkK>d`Kx#%qf_&%3*-QxEp(T;=&cd_wOUpUpe#lM*NO5_gfJv`oQc>q^TM z{I+gnscYUCS?Zd%5h`c{DhsrC=#QL4`#5Ua&nHtJOF2r*1nO#}uCz>`x<=|Pfv#Hu zMJqWID6^i{F@g5gytUpNGok#H`;VeU-Z2I~QUjE;D1np_${r<tNNXk)Ckx{W94QJg^D9qNvG8?#|uNgeg- zE=FBne+R!7+G^ywzLI#_WFs|qlev#6o|j-`#8j>~hFNH2WSu=nzA=n*M;PahFh(6= zj6CmWCVd}vZG|g#aw3EUC_=~eVCnic8jYNIk_|C>ctg{O`_$`!`bb60kDNmuSe^$+D zGD#njvDxZOQofpH8t6qjX{X#tE{#cPdW6zIi7+*8S^bI%LRHE#R^~%X*|#v5V=4PBWG(#D9IUm7~>x5&V@6g4(1xN zjypv?NRFgV?~FJPauKb#>hVz{ijnMIi~LGmD{@GAp?-CtoM$#==gZ&en=b*%J?D}< zJH}_68=ie`cn@c`h?z`Ynb}HaGI?cY^+G3MX6N(7>Vx_Mn`M(6cDF;ya1O(KhEZX+@Vqx%Wu>y3Z!}){@>#tIsFB7Dlv(CldE-NygXtoD)dS zMhT^wKojak#)$c}y(A;-q>^fq*ymY{p1dgZ$$eti|I&~cpglrdi0l4ITocrw$%Jb^k5JUYx>NTCfPTJ~8T3M?pMIW_ZYiC$0ZX&5&$WhfsjowfiD_2GUwP)zJ z(9fuR9z&9beGa{G(a!G*)u(ACxk44+$C8SH#k6Xp%77VlZC9>P)iR``l+jBlMJq{1 zhre=%nX4A>BaiX@?HPSR(QEJcs(nT4L)6FQy;6lX-XfACr4Cz6a?aFhOTshx^sPL< zPh9ZLL?5beRnA*C1NGKaFeamcqp4RiR!Zw8>gpc)_8X~d|5CC^QToN|fm*_<17_$i zlYX@XNw3ng79#B-k?MU=OcaBMiuG2lOT{&V@x;yiYZ8vJTk(ItQ zV??lf|K&$9w%B;|CCCb+jXi6p9$P^?3qtx)uNgY6LGEUxy7mQSlQx-n8d)uthZsjJ zvbZmQ{>KA(~o0l>Sc7xzNw4bwvGE zoz~cEbv-lUMtW=ekzSM$@w5o(K1PEV z(HcDmN)gXe|h;rPka&KJ`-Ro`-TfiGxI1>l!hNL0KL54;S_f`wfn0E0G==*)=N_Y^Br`_R)?8 zDx*9ZqB-ouZDuF#X3Cps9TRrzj-g$-y^&fANr}CYQY$=X1JM0aW8p>Xf$OP{qpalA zirofOqH4u%2P(Ja*6t{FAF+FjQA=MBhj* zDiNb}R1(S|-PP3@#?Fy*OqC$7mX1SmG44iEI!3uTM3HgN(p#m=*OQBTQ)JvespEiBr?lG!lsY4&O2O@vrBUhCo&Hj%l&X%R_eV?<&%`S= z7b$fm7_}nMs8Vq}^eTTBqLl~7TO{jb(v)t}=kvLGR)HX}x*LZ2(HA`5a- zedmqzS9PVhiX6UvjB>KDiY!RW*GkAYT0a)#q`F(A#UU!(w-zf_i=k4XTH%4OANQ7% zVzp9k|Lez`{(gDu$9IzcTrKX)eiJP>u43c*(bEN7#cJ1yHk-owak%_*O&q1*zU()z zT|XX({F84)Dd?I-`txjpc&ccm!dF{v)E3kpUag@P=r5kn`RbKpK?)YA@U5>O3-a&P zt4P;%d(+==J$2vmFSpPYbjSeBTRdj zcCT4Mdvg7*$Jf{jeQo-1<@|otNsEAXG1u~X)(iH63g}X8&UL+Bc5P%+Nz=j_-;-Tk zs~LZ(Z)_fAWzZC;e;)Pdfz*mNIamNXft_gSMm4(EdL*TG+Vs9^575Ro5x%mJdK-B= z6s!Hi)ud;=E}~V>N-uKQ(@VyYw26Cy!B{l)CBP-L>W^_>fF~X(&9zo7hWk4Y3bvZzUe7W#RlPI^1^bXIta8#upth3=v|MdPuC^*j>zQfS zS(PMx0#VyvL%k|+$|~M^HRaV@JBGJi30z72SjJ@qa0T_c>;| zG%#0K$CH+E>emuVCos#4fl7@NDSIZER?j0%~P|X16u4yUUPTIyC2i+?H7$jQkq+gg zHEr~s6YBY&u3U~FO$T~z=#gOjRNz$VJA$sigO(#XU(Hp)QDG%;6zw}WQOz~OPLk(- zs)rp->IL@Fx+|7C-aGe2W!Zon6 ze>9`y`b(ZPllcMor&F_+SbF{|<#<5{Iv;|z>vZJ?&7NvF)oBl$N7~N#iD`=&w=Q58^`+E1fJ?|1F~Z%z zZmvlS9l$6b#l3|j&mWhr2f3p3RMvTt`a(uq8?NI&j@g#h=5tkgHp0ZGsbsuet;W-m z=FvxvAm#aNmCS&vZlk~A6VDB^GL|`U-aHW`Mv2V{^VG_mID1C48y99=yYuF(IeY3I z>KI0h8Q1B_F-q8G=4=g^ZPcffVVu}nTAk0e;J7hCQcpi~>>1}x%-=f3U7li0f$>DW zv^nQ``lAoSQ&SoO4aQTFGp>FQx+JFSV42uk3Iis(WwTg_;Ho^z0AcMH!iq*7DY?DS7IL=Y6cAQC!!r>1s&dj@-y^`)QAe77EXctz~Tcfqv_6RNyqD7}q|^ zeYDmwX48Swsc#7UW&`8oS@e$ZMq1P{v=$r$RMU{_=<%HljcG$WIB=s)K+js0>ue%< zc6bk^&0u{Gls2By7ARvpl-5mYEA-L@R3aWiSs5=M+6D!*1LZ*5NYbJlXgf(6FYh^& zq>NYhI*g=@m){&tY6Z5^dIUH*1~`WLk>Fu7u$lUfzXQ+&C3@mm|68!?N)QaD%S#XhjM1um|^2|8^AsB>kF-A4&Mi!>XI zTtSOpJMw%DPk9k%OTpchl%!U_hvZo=;&lo5y^4|%o-t0>{m?tvx(qRmHH+bUtE}rco z=QH+6Dm8La9;;NAU;2$G>DeesIj|f-&gvO5@oYD_Ku3oWJI3uu&F)`v7n36$&rTZ^ z=4uo(=pHd6cZ>})`q0@n7Dky9_aREm$5nE!92 ze#(7)J7a*1%rR2OsI+co%`s>o8S&IZDMq9=@&3j-O<=w}Ic@^8;aPHHfMT(u;3;+D zxaZUvuRadw$n5KUJ7cAz7c1J=ji~kudh#ZzeG2oXCwN8}Q+)!}%&@T;eU#)4GpNZg z(<-Dp1Zflceui2|SZlcR?wyJeSb(#~h!5FrNd=-XzNId^ZwV zxe{fJ^Pq0)o+?k(o<*7tbSH%C-swQURx&$a)oh-}GqC!3HosybHyj|Bq6VNhExhqe zE5AJ=9~~g~`-XnGMDMm=5s}v_Ll@C5W$VK+CMlk;Y1yxl#IKSp3p`+umIct_Qu0Ac zYOU%3EBLM77x8N(tGL$^pkFOnP3tl!WsshJO=J-0*F^jV$Z}|93He%*U+1dhE`Bv+ z32+Imen-SFi1;m$4cuiFa5cI948H~P4jMyxJG9oP)!CBZ#EWO0&Qg`WQ%#FKQoqctE_aeBy zEbQ*+=y2?{KRC)e!q^?f^DTtOE~LIQjQUPm{O*FBQ;m25&{;d0QCJLIOh2{eIY7DJ zF4~U@WGWlv~UUS0v8XaLIZ zJ=3`<$lN|~BjH|G)5p`Am7|x_uRfdy-2k;7%>PhQ&j2?PdS62yzs{?ay^MZ!z{|;v zTw5K^n63jl|JTyz8ffkyemfmJ+6Yt&5GSXH^QlJx#hUBjM(x0MesewisSVgh{o;UM ze*K`9v!BP&dQreWPrk0<1n6VY)Ztiw-;LmG-N+r*Gi&ASHWvwPD zX*!tQ%^foC>L~)AJ)VVA$1_eFKa;ZOif7@B@h9LqlQ|K266Ym98F=$kaO;Vjg*=hE z-?^R)ln*}*U+)F>a?Nv=rvSA*JcA^d0Gz8Z`rI5k;0 z`Yh?0aLRKxXDE-S?#}M#0zWox+<5U~uDkEsZ**6L6O}8%S;}gj&q3jyDP0mykS^gA z=|?C(!f(pMdD?2K&r|km-sRy$-%W&MC;OU zighU`SwBemLGG(0ydCJbuFJw%+-2bu?lMl{zKa%5*e(kvY?pDS_IoM6mtS^txHDKz z6l06!Tg70gy93=Xqonmsm8#v$UJn%Fe0GuiUcfq9^%r-6ts?)EZ9 z$n$Pifg6RhXI&mH`5T?($zFOa<9Eu8<1(7j*ex~x8t6ft z-?%TMA6*Y9la1k4|91tZoK{M^t4AKKq<3esyBO39Jb73PkG7upwKDYu_b({Zji)iH zMw~4nITvafMz~F8HjHZ1j-stapTGNYv{6e9o`vCTNdZQg>al4HKt;9X>5cg=UgF`NoisrqmHQc_-3Udw}a__kSwWwd%CRp+R<$YV>j;^QtT2-_gYCrUZ=y=A)WZo~Hx}oJkzU`hsJ)Z6t zbZ1~yfUeygWuX=iM_H(bqDCcDS8>FJ-N*vRLZ~0u(Gj|Oa72V!PPN3$2qU5eMoru? z((0m(#gTS*zjhVJ+VexIdHbQWZkl)|^$nj>Z;kp!#0KZvSr;3`0?!rm)ECcmaetWS zyu>|<5gVLu_bQ1E?qQ1itMq}os&dZsit3B<2|dk6o3T&mE>l-uK4J5#@YFr*akpmN zWhgF*Gh$CXMa?tEoC9@?p;Oe9uTn`oXG*+v7S$7d4`)~Uh*%xZ*pE0LJyxz=rMif# z-rZeiuB{5==a@OqQjlX7SGsXex8o-rIcAQZ6y%sWem;qNI2}LfNE~$h+IU)V(D8Hk z*IOIE_}spO);DY7oRVAltt2n_wZz)!=~DK;dM85E5ybo95zp#=?tYj?tFdOjm)NG> z=-vvoL}S(*hiJuDtBkw$np^Ey=lbeeb!|&Z2gM zc-EtKPjXHk4Ox;^wreCa3%hQskEkRw+y#{K5@#|$q zG8xkx^+mr`q3-A|1GPzgEipdO-GQzMjFeaRR0nluf$L{2t1(J7?zM_hs_L(5u`xo` zHA#$8jeD(r(fM+YhW3x_y>n!L^K~FQNA@>gO47p45#y7iR_m-eQ_hzjgyHk$OvPD? zGgX+iIA4Bi&Y5z5pmrd455`%GGo^3ZnbJ!gXYI|+mn(p{DsW8~W5}Gfc%G><o#cm9jcmwbPS%8d4q%J#L>=k1}d=tGmf)B*NQU;CS{{n1y!|KMt~FjJAfq^aRl zwl{qhDC^bp71vj;fu%AjOFLYFzFaBqO<%+3OG?{6eK~89%7)KZi~^5)8Q%=OB##(un@7Y?d9#Bui-oC^cxlS z(`lVJkonr5{2IQKZh!J?_o9f-a$e7=U$*KmDf_JHWl`(cxBQCw zhBm%}{3>W2L-K3*d_{euFl+m!uUF64f#@6iqc6|?h^w)}%FsMTXIzQKm;%)vwRWbY z6+mMfGFsH!wQ6Q0_fu*4%t(XWaWSPL_{>6}7S1BlV)*I;N`531wF^S~W}2 z7K~BxtfDe>h&e#NP@{KSJyQ=~1xe4Tmdr|$dZxR(on^m@>wfRJ%hj_h-Q}u=Y2<^t zrPfYk9@JH0oWl%CG4dhCIn;q~MmK2lG%ihzMH^;4X$nvaX9F#AS1p#tq!@joZBvh} zl2Lz8WAFww;t|qw8~45H?J{KujMzLr0u}N=+PPcd7Z)k*A=d* zjq4H83lM2!JbZ68I=OoQIy&Nc0sA{CK%5f;JzGE`hoI#l4f2S$GnKXJhCNqaVe`^@6G1Mv(3ZSkI; z;8_ZVGYCA7KpZZHW(yvOCD5c_tS$;T?nw-;*qxo$FwU)E+|<-OBd?V))T`lFlH3Uv zcYLVRxki%uqbJ0#b9aLoTJ*<~{3eFpEZ4PN;I7=y(^ZU|mXgK=N*Wg^$p{8dzZuIF zPru3FLB?1|AGIgacn*zGoQ2b!QfkpQ<_WQK1-Y81Gs+u$x561-o@?hg%46cGk&aS4 z`zW3O>HqQU$5L9gE@@*br(P6hQ2SE`UigJ*V~w@}{pLawu!*-{N_iQ-^c0$e+7h5& z$o2`B0A0iQ){Dav3Y8E(;i52KLf1b&q0kkP&$}QzmC*H4jPQ%GfR*6V9G*@6FXEW7 z{BxLPS7LFjPk{?o!6)?bpAyFJ6mYPHauxG=D&cOr*si&~@^eNQ@OgwTd&tD(lR!20oJ>P4Fsh za(Zbu2EXlj!1z_>HRSRuzrO5h`CNFzTA*=*=fa8B1C3-jmmX&W&!%<(_ZkNr$NXFX z$K4F{yWba3-wMCFfR+pCa{-*{LdqBM|J#6V)Gp>3E&*Od`^DVr9N<~hE`}3t1iB;i zV)*sJz|G`xv$KGHi}^DC<5-|EX_vuYwgdet_~me<~BfczG?;{Z^b&Mmaw2=t81Tgm;( z^KIm}!= z%PgM*d@sMcm*2Mo{YLb?l+FVB{pWkZ!1IA;fe-i6`)uI(T)CI}CHTL!gWktzUjw{` z+I@`qwRps}iQXUh<^6$Q-cP&U^82`QKi9f|<7s<<7=@dFw=!-IP`Uwl12gpi^_%gg z`+e*O8LwM_w@~v7(0cM8r2P@bR60^nL*N5cy-& z{fe~Toqmk|j{qN`?QzPF5vkx;rr$@|sD;O=J;5(~h;HzU)W$eGL`1`*v^_<7f+&V3 zsXa}4iU@@#=;>FYpCCfveO&Pi(N7VJ@Fe*MxY7f(-}Bu6eZcq8?}J=>j%b4?!`Gkv zzVr*UJqLU$eEsf1YnOKg|`t`1}IUuSUN}dYW%Je~8jYxP#w)evzww3AzV3 zfnR=v^gK{W^%4HxlR&>p-O+Io7%rt>OnxCLezW~p_=xrMffs-`$5Pq@JP&Rtb~KUv z&UhnvL%^K|+O=!>{c*n`ekVNiy@8X8LCV!Tfqt#L4!pSscn>|4mv;cg>`~ywy}*09 zCg!{wE`49%-C~S5_HLlFt*pHrE`L8gJbmtVpx;X09XR^#z}a^P`q&-lU^ke1CRfiU z-yQIGH(d1`%6rInGn)?rPbHV$_XOFrJ4mbD$fVs!rp3SqgGAd6e2`h6M~hK&_wyXe zz6XGQ?|f;HLdr)^TG}0?m;A$3tLHEsN9!Q9>L5pqW+qVIoXj1fUqK6q3ddg?{Dw z4>N1WK)(-Dew6aVz{}uGj|Q3ZD3axJ%F3ZfgA92z$dE_r=Qrao5-I+F4&)EYa!&*)_ax9Lsz-S8CxgU$lG4#o{Z%~KQ^?Z<_$b%qCx-)-dr!e-uLjC-pW?q< z3w)C6Ptos5p#1A;ewhMY%|1;k0=h zp9WU&KF^Te2hZ3N?zcJoht1(XY^G%kn6UvI*+l#1fDcBO8JD>%;Kee^>!Ii9A@V=C zM%8EKe~$h)HD6EGttB6dMK)U58E~zuC(k%#ao+P9tI7Sg*Gg#6m{7m}wE_w@Hq~!? z8C|-ZR=*dv972)H|Wjae+6?2-K(@T0PJ8r)4Ru9UgEfP(9BtkRA@dkaJ86y7IKZYo`TX8~KVm z7`6wlI}OTpM}s=ZH0ZjWx*T{K62Cprx$?%n5SPGxRRwF zfEM(2N)evPI1e5@k6B*|j!zADQNm5)npO~Hn-&s1GL& zTf%H@p}ZAJc78UKwt(~Mew#>}!Ehsc41rKN zOUrula~Yu)plio-p^p(jEg9!Bvr~a$z_|ev&ZRz$vO5mWr8FI=J>pzaA5i<+9>!-0 zP%POKxWgXmODSt1*h3lw&-7TG2aSvXY9Bd2P|W#(V$P>s3zYbH0WIf)qo-23Fi_Hk zfs!r^^m8HOeg^GvWv48>5X#yHlrAp}ba@fKJP*7-kNMbOv< zlrH6W7XUAyei`LUk%<@6=klQYT^=~i<#3g`w9MswE~m#Oz&+$w1ZjE&Z@8TD9`Y+_ z-4i70a-b`~E4k-o$R^i#S5vzTXx+8jawOD+v|Y=SUkF@5eqE4c*VB46a`q~E-9Wkq z$$2epHKF7|l&d&ro(__P|yB}FC#?@V0@`HdCKMZ*CL&`r$z8^5;`;?|9 ze+ETQ1x`(VnEWYMW&me!pC7>&CIhvx{)qHv$)9j#Z1U&e*(Bg3TK|}~vB{6Y#)-g* zwEiFPvKQD({V(8T6Mz$_|6e#p53q;&9Gh<@@jf(yb@H@#LvV!=1 zTJKJNkNh_3-v!=I{+{G_X?qXpZszMY+HWO&kJZHQB;N#nlk4v#x!V10+U_B_R{bq% z_mb{m)$p6t?jzlcX8sLo_ml2JPyaf#2T1qBTW{r_t>DrPKy3l70b5$Zn42jZQQsPH z=)vS`{O&>01K`~Cv_6!4m9~dS4}w+K(ef}Y4}pKzQr0%n3g%u7bT@;R#<`4?-}3Tw zdF^Ow8o~s8)W*IX8PX7-_^Fj%D3{a|DpaFUZ(4<{QL9tp=-Krgh7w>g99hnIGQCy- zS5rSZaL*G1mpn1>M|t-ec#|5Hb~Ei{we&k7@J{*oI(U=X)v2UY0ykd|)J}d{kR+#Z z^;Ed*@w6OA+6dgp8=emDs{&ThPuuz+oJ`&A4ASXv>)o`R2}iC3R?>P5Bl1-9uTM+89db1J6r7g)G^bd>Z&E zpqBJcQrZdBGXEJ`J`HsL%}cZ$4RnvqXKDEi(ET@`;K?2azC`;cc)G6wwfX-FS3e7M zFV4qldl=|i;&Zh83edgrpCcWfe2goP03U(x{wnRC1G@9(qtq`1evJIrX!%v3`))o$ z>qWqilK(nj0 z`2tWs&4*~aH2Dq6Uj(`%=SxWIO~6gmzfAc{NI`d9w2&SLs`0mwo&dU1X$dQgmauwg z2`hsZ)&4SqGe z#R@neqo^=bHBQuK>RS2Al}r{RZ$GT+?p(WjM`mQa^z) z{!L&#`I)qS33vwi@wA)}w9qdBzXWcog$lpOGo4N8i_pBfsM_a2K&{u+ylV|y;2c`c zC2fR9`3(bC3>$&k)csn?NVtPOLp_G;gFYtIvayx47I;3n+Sgii13eag=gxRlJtzZk zrgETqW#Js|=q>ZhC+_7eoKfOQ1Mv)_c;Z0(N>mY2KrLPGM*LQkUk_0x810uLbLUfj z5k9jEPVi!Y+5|pK%ZtEc$v?`Kqk-zkFVON~pt|tKXxj-?kNyxXFTj63M)~7#xg&vU z*`FYnw`r$;iCn1V{*&ZF_4H4X3ta(znp~*v`5AJd+URG=;aO=fn$tGm_Vmzndpa{Y zjC^Kt2rb*v!_&hkE60up?&g{5;1*8_Y=6*AiwsahWwKa7Ow>5PIwl#H4ww3>QNIEw4+uCF4F)nQf)+X&~8~K!UGQVx* z>e#e3)%(<%>W_Mgdq16Y(6=^ep`|r#q2HpUGwq;dOX@0aOKQx<7XHiDbW5s5e@m)G z|4DxPR5B)=!Y{^E=|A!RAzNz~AxvG2zW5?5a{Kg)b+|i>1V->jlhG_jp?s|E4L+c z(>bYD+Bxa1ly3``+&Sqjly421;+*tm%D12+&f)G_isz&^(Q-4|;cWh+Hs#srjkMg9 zY~Y?7(+#PX*bV6eNL}sG)#=@&k?Fj2F8yvu<^kW6j7+OiZPp{x>uI?G9kD7Mk?QZL zO0T2kdNjomX=SRNdPKUOdu{+~6TX(K*P%OBrWL6+>&o;RTCPQdtVqjKt<@FjeA=!~ z=JP+VL7OaN-0n}x)3Q{Xb$Pmu`>ao|;`-G{dhOL~Q+*C=X8rs*U zt0}KZR{>W8wfn6Eu1Z&?k0C|>C0W4#`Lb z;J=dpELoH;1TN&-&ylcK0QI5$oa{d=zd zL-HTAUIzSk^1n-#rc2Vlt_3x52b=8=%4dc?}Z<4`u zS^76z{o5o^nk`qxQuT9jVI8e?U; zBK-;NKSkqp{W^-?7Xp9Cx@#2csUHG=L_Ugj(~p2ZCLhIG>BqpoARoor=P!VNNj{2o z&0hllikuzZ+@DDLv^X8by-Jw3QQ`h|T>mR*^C$e(L8U(-JqCP?XBj|}PDnaBVr-H2 zRlg@^o&hZtV(SZKd&Dc23cU(tznhW+xWmIpFQN2M%Y2onuExok6=gqG#sb%y8ox<;ejSu>R-wE>Ee)Wf* zpg;7$Rh3c3(7RL4lcLntdU%_Ov`?aD&Q-s&*h$_&YUe+s{Lb}T%3U2{?Rdtb zsxN5eGiq2pqVUZgbr3Ct#(F!;Z6xiq>LcwW@2^(U!KhXM%W3VT+`)5*V_hU;QN^@w zlCk;X+xUQQ<0<*fj1fH8HBfYEhvH2(LFLtzBO2l>wsR=hpeZa zatXa8QbXhtN-AmO&G3g9u`8cUe(8Mj!1;rmK|bl%%3q&945y2?!Y6-O_)x$E`DBzA zky{Rz7yHA90w%~O-^w^BF$>Z&jzjS)(sOUR821WYlm)r@TK@2QbP>-9j=r-3XE<`Q-mv*U0ea`Qm(;mz;|dE<~ar5>fsh}?2tdeoa8 z2Q`O+9u+mH*OwRj8;8gz3tB|3NBvjmQ3s+wyjgsBC+Olp^~rtF#s2tYqzk{tss8ZB zbg{qng)57~D#Mk<5Vv$?5%uc*=?@2@SMQH54pg7iKju11kJ-M~S;P55#D_Q*)`} z$Kmb5hu705_oqj-zhZx=c*XLtuXXnu=~4UR4{v3CaiIL6V29ZspNt&xzh<2^T(5q! z_J`s8p}-mbx7%Tc>yvL5AO1J$)o+GR4wsv+)*sqlu}_wxXGfc4w8m(e+!ufNMdjxH z_``7fWI>~TtLx3-`0#ps@{Q~;Z$*!Keg5!T`@?X#`A)1i-^w_=T5b-v(-!2#aJd=R zSw^z%ZI}D6us;;^YBkA%RVvDhf>!y)c6%-ML)QDZpDy+{4$&g_T6@%gcX{z<*WJ+` z6<6Q?lk70>^f&rSob$gZZ((b+EY zqqD1kyRu`*cV$-skI9ZDKPGz@@YrlO`LWqbezyX6D*40Q@dDr@**(v;b6=`MmAgvbxA0l6!oy?Whq*d8O-l`Y4jdzg;}6F9AM4zBW6ND{Dz>vioSg6nH=RI@;F)PawaS*2{qR zk*}v^UG_6A4$S3h1Cjt*4e~Gr+fVXA0XOn4}1l&r#D4US=WaG(uvMIDo25uq$ z1buG@-k!ZXdn)^M_GI>PN_PN1K|Yl}Q-GVvKStXfz&o-#vuU(U1#Tk$C~bEF@67JX zre_D!Hk~vr`v`4!0q@H0&Sqo>ab*T+diEl1cLVRv-jnswJ_ERs{KM4W3w)8hpO(I? zG5Ivl)R=sR=Q1+jGg%F9Pz_wjd(@D|XAQ|y+0(#A^4e?xS87Q$nQ^2~1E0>G$wtv$ z3!G102OI^QM^2<$_AIcT+}MR@fzM{oW%XRG1I{I{O`gl%4;)3_KubMv4!Lm;?+3m= z`#{#1&8Dr9)R0vtAIP2u){s|a-Py>jiK~skS>!3c^|&YQ`D|qJeD=X?bT+`1(WIuV zD*0gcA>c^z5&X6)Yv$_cY)0_O&p@MTCeF<0^q-|8vVTZ_mUhwWXK6RRr_<_*o1VY< zk7;MtmHi`Ef0j<8wFpnXr*r;O+L3i;|HRdQO#eA;&pNVyrsbbfzaJgX>xk!Z#PhU^ zlYgPlKd1kawq@;EJTESuw*9ZP{7d?;>A0*dE5vp9HIIKw$7bWQf1~|h(}`$N<#<($ z`1pC+nvKnV&eeZQjee;J{GZ2)cn%l?+0f0zD$_Ra&^iXvOsU3D&8xa6F3lAt6dC@LTsR3w-c5kV9Ya~u_O zMiEiLtcVy80Tr`=f>{JbKqQ#cnBzEx|NFY%dH3q*8)v=uhgm=CtlCvwRo$n%!mhn{ z)!zF>>bwwNr1j?k=P?RjButM_Q)>vYW9$SRLOdYp!1FzW*8!-8?}kt|7R3!b=gY7m zd>P&dFY%lg<4e(#GcVDf_r&Gg-3i!<{#;I|9X;n;pA)?Uh&P5Zv25JPb2fy2={~Xg z0ritjp)i(-n<(8FHiy!&Fm5JiQ|O!Si>Pmv*@xH4Szl<@H$$mdI=)HG%|WZ=`lr(d z+FPL@mWppt`ex`&ZWB%_??U``$i;&AHl=TcUgS3A)N*g)cS4N0_ztCShZWINKr5mr zomTKgFU4hiL2Y2|SO-`q)&znWwlviBClipaGY0HIS3L+a|AvFT(n;4)}UlN&T1O%BXhC%BW`7%BcUi zC%GfUC*ynJ{qQ8I_rhq-2CM1mdEwFN3F4=C!n*Jj;Yr}fN>Nj*t zo(&(9_blO=pf|nkIpe!O@pIuLN}eM;8}v1@11Em>BYr-7NXher=fXbZ_TcpIzQiwt z4=8zo@O;=i)eKU+q@5apIWa_x+=aB z)qhwLm&O;v62eQsm%@s$B&-cf!@-=w-ZfcFdI@I%4<>y|dcyaV^n~wSVR5)K+(qeP z;2L7}8?;WM?!evQHS+Ez+!gK#uZGp(M9zI{>qHwSCy`crLVbq0l)V<_67B}x!+dhWTM7v3@y*b9!9e zj0NP(4-3M}#K({~f^+6-aV+F(Uk(ci3xd8nMsgzkmH28rnlsd|0M!7wk5*X`?xW^H z;NrL>YANQ`ct7d;!X(bNzZxGPeScUTCy{<4F6R1FPQ{N)=7cB09pQH198T2g`Qz&F zP?^>k`H8m3e05zgRh*G6rt3CT6#L7s69 z;cCv~9>FPmb*_#`W`sqQ%phD7uH??gfYXVma*}^MCvwO0+>5DwWU3=Ik#n}537wXn z8=XdKTr!P29t+b5k8_4s&7&&_YJyGU>IzE8=WC_{pCG=1>nFm@@BsfjlQ4r5z!&rU ziwKi|lakf(+VBLeaV>RbavJy|a;^)H(?-{ke=VneSI5_)I)AI<_2gg2`Cm0mE(^26 zP{w{5l*A_Ex^->=Wy=# z>|_q%cFuXyJT(suHM&md)0l?qRV02H9j21|DFSUG(Hv&q27hz5b9nKmQZIg znkw3TQ9o;KTuOQgnkxES8AGiL!x+Lv;b6kWz%j&6QmRhW4C2Fi=3(Js?pznu{8}4F zQ|sa|ns7;YiaKgZX`kkVaA`O(%;kLdHOYjqIX)UEaPQ&aAnINMyoB=O2`2y#B3?#4 z^{M6(FH5x+<^h)_qbNN-yoN5tL!6SI5RTxy{O&0{B1{Zx(6@LH?W70MR$7f-#k#nf zdJmI+jd)k;PUKAe#Bd~f028=xC~q<$tVLsE5gJU3xKoYEb#Vx_j^vd6kzrC;N2wZ@ zYNZV(ZxUzZCxxTJ>*TCMr%8RZ^+2^O)jk_U`B9v9KPnuJX2YhqIqt!~3=QZ?#n+?y zm+Rs%^7r5*`ylEJBpego;9fN`)l(Zl-Z5bS;n=W&9JR5uL(`wUV?%$!ap3^MfnhmX zD)Z5hnoo_5==97__NV-~uzy-Z-Jgw|vsSC~Q^M=9OBfc0bMjkl&(8>-a`Jx|Is{$A z#<(eV<*kN=Psn{eenMCux1;t5GzYp6t8=uGGxYs=`se6yt>o1CN}jSUHAbSvupRLi z=p4PwDfO2r>&7#?qVJ#%OJ~YQa%NrK(Ju*Kr24SyV|VIwLvLbFby}#kC+FSODgBD@ zC8y@qDgB!8Rnn32z0kkd3w@Oi#KOJ9KAfjlgY+B1*J!b9ED>^4Y4t$ zjYyZ`sw{VvL3`mt&c7Fs(-_T>4!lWw!oHyir{5c^4TBy)J)WVifEume623v(;RDXj z7jbV{PU9C)yD4!K^kaIUA5fP&dZ0(~KBw%hgCdcOi%F#Cr6fbEGBYBoo!B?11DB&2>xT7;J9 zGd#yzZUTM>RD-k+_w)_5cveqfZQ_bNuLAHLGy`^_R9%8?h}Fsa4vmIil9uSq^h6h- zCU^7_KTz^p%FWdIEhPOn?)?e)6FMM2ll~jf=T%MLuPX0Yjdt*j zHWS_fzLV-BzMH<|&(v4D<9jrbYVg0c(s!ytT$MKdg?u$VY-9B+HW4ME zhUMUl7r=fm@Wvhazt&)k4#dmAD=)H&yhvFm@>+vc)Y$3+X6*}R8$hZvd0PRuV)Q-* zu6l`e=q2u1nBv+e!EGy8)mD(ZEwx&K*;+AsmVygkW?g)lvhB!g2|jGe+*$&bUCEld zlCm!3wE&m4VCF3bAFpEdT}4?}uA6~_yAVG?zM7=3603973@xZ;%>Kt&mtKV$c$G3W zqnd_$cq6TqxiV;s(7o}M3 ztB0u00{$XdG_@$KZOrKtYnXx6U-Sb^1;QcG?}bk3v>W>cy@qk55hP__fB=uqO@ zpimxxCVYglgPR`(DhYpceIGAuixDr}L`b^!nG34zJ zC9^+xYZ^J~v8kDM2-o{U^Nb-LOKKnBA;ecuswSK|W>bOc%&A>Ajv9MIag8O`PM+Fz zYL^{K?p{!A2zNsX;3F zRKf}HVOlyl6&jzIyyKzFkB5#q1#aLhIM%Z$JB_^Kp!|=620EQscr0|%$#58F!?B)C zy_4WC&H#{Ho?r?0%;avu`rWW?5co9#O&b%mj8ajVscsfpmB7T}DERSPS?r;p;q1wLVxw;Z= z@G|(v%ivC~OgY4Z;bO-lHyBTi>Eum;8=V3TJ{nHshe zyb<2=ZX^S9!mh|bh9pvhdnb31HwSs=jno)KzMf2#rVJtsPUcc}J2DcbE^`TU!a(XM z+fw`g9?E7TC7DZnFZ|=I&>xA&9>^7kQeyzAp}_vc^Qd zEF|ttj&>8(QNN$Oo5KBs8$&O0dLt)%gKzIeOYN0BK*^2B3T~todO~Br0emC&N*0m# zT-=$Qp2_p^L1Ycj$3^5ULr%3MY>Nc0bE4#K2{LRo#-B&-@d#40N0E>{hdkp^VV-2ojn$$k2MA6Qkwo7rA~2 zY1#|K&mjGH9QZi*x95pnk-Bd~+?x98xod5*V=77&tjn%Pvs7ODDiXDKkhi@H zTutoGdsB8snj#Obf|Ruxuo-#pQEydvk9x0!w~^kh2Cn8FPboBE&!q`+W%Xb^@uMbY z4XzuddUlPGL%&Atw~!9LhOG8Ip7TCoWl)DPI~AdZ<2v3Lc_tF{4=8&9_&#yPR4P!B z(n?6&H}d{(@|?GTYl+?K)YDpO*Mpolk(aL{u7y;*0Xrr&i8qn6Ic(z2b-)e8wJFp4 zvXXeU9vdWYkiRLo&r(165P9i~u>${FG5H9Y>x=Ajsj2x3a@>!@&%j@RpAauZ#$PU3 zNU3{do*TNKy4VAczfd!YA0x?Kz>~@+3y>78W&dj}R|~jnVf+bs@+aXZ!q4G>sD|hR zJfmz9(jA0=MEoOIvXA)pAF26M_z_w3r(qGhb7hi6gu-M#&s@N+pFGEd?B*3Ff2Yom z?9Y5o`~$M?&w-zF{ZN!gd5F4jCrHX)Vvj@F)xCuI@o&`pfqkJbi64%h7_)4 zGLzkvd)PH7;3>7)l_&rfaD6SgbAdC7XYfYzfb+PT!5iMo9$0DW)*{qqub~e2)+MZ9 z2X=0}8+a}8HPoEJE?OaVYZ7X)Z+ji3*Av{MD?>>QLQQsluP5gQ!kz3g-;lyP+4rkX zof^Qh#PxXk%fPzCS4X9lR}-#bAFCeu)!6YV3oJ|Rn|Q_@z&j#)iR{D`0gEWRnY=l` zInf=+@|08|RAnc!0#~<@J1gEo`R%~lxvoTR6<}rJ+2q|8C-a|I0ap`uVrQ*ByW3aA z>A=avoq3Oy!1~0UDX-67_N&xAgD{z$ss`kBWQVRnx?@@;y01N(z49}8!dV1&UmH>0 zfzXlt^efqsJ)4p%*^BJVliRaD*a+B&8s|_l4LFV6+|&7&GuX@AmO9%|r#-L<@wt>= z0lb2p;PZ%uQ`s%vn$m56O^Mq9w+1#NKA-Z-ftRz-JcMVh0&Yh#*a z)2FlVH<;2Pz%In&x&90AP~u(5T@}Z2*Esg|x=>>f`?FoxYj&q&H_BH5U!lff+;b{$ zJn_&V6Z+98+GIqxg=e|>cr?N9YhPsEa^SwK% z0qi4p19sz{36z}-Je>Go%Ez#4K9p2{>I?vGPkaP5P6AFK9!>ed?7{CrY9e_jaWY^B zYV{-Z=WM}5a@wT3_HB5>w(%h9j%F`^7^zXj!V$!t(3rwbzdQVwa5V)ug%cBfd0IbU z58@+v+KIpuIm@sW_1dH-23l}V;6iF2$a6+F`v^@toz@lYCE->>qolr#y}&_ZUur97WuVn!5md z6CX#;v78<0MUH1tj^j+pUfi`WVINMA?3JE0@ia=~#`@JR1x`tTkx&{Ki1oy+oJ9%D zzf#91zn(Jk@Uav&i_;2{%4-^XWse$wL1SVf7c(4v65~0->LJj ze*2&KuRj{A|LQyc_Bjoq{|7;>$;C*s4T4IPTai{A2n{L6A|-=wEWh`W)>Jgt<2dy&SJmnnj;k!F;;DGUE1 zJt!Yk2A)NFP`;)x1Fk~S zxN%3)A^oz1uLzX;Wr1%}>g|_BI2}(D>3KuTYT|4yv}#{%JJMYUdfL*zmOi%%`3g@8 z$wd{W-=t3>&j|TteqZ)wo)-E?jBD)3alarD}{WPnJ2xsx#_5gO*wN>rbjy zIx=fAM)jZNh^@ug)qj>Fxi({3KUt1&E!TJ|sU=r+({Y%MO~<2FAsn0a8G&j$%h~C9 zs5R*}ghuJ86ndV=@hEJ}d~iGpn=mUJk3vu2I39)C$Y?>_oPHYs)Fb6U;%pvy^2nLw z%<{BRQ@*kZ&-GMM6Ta7(=&7Ro86wXUIcqcjrE*ohxDsj~yC<>GnWj}+p)<`>Izs20 zz5?}ps})48+UieLu1jB#dh*n#pgtn?8>z2Bed+4sPM?u_mDJCq^G&<&nJsX=ygJi7 zhf|f&X%I~ZF>CGTdCHdop0I}uE2cN2DRRU_3!6= z)4Fsy+Os`5dK=cCt@F+EbY*FO{SfQn(GzpdH?0g8(r?bL?5v#jg){%FT4{2=c_vO< zPug#4$=peR&NolMY161BIa)omuLjdcL((}nBrO?|mJXq23nWC&zgd%;3g~>@gM82B zIR1vEvvwHY-Y%6il?GyOFO?z{0-epnDfL{A<8nkgo0TY)A?@fKK^Ts#$oV}o#hFT! z%93tRyeB!Hzj4OzNsn{@j^t`DuFC_R@k*4+0mVLh5%xriB=*^xUhbSqlqvwRbch5_ ztgsLHo|W30t9`ky1QaXm%Lv&PC~i_(R}r`^@qXlZ7HePXXpvDU=GZ^QT>DeH9}>j< z$?^P`r@X`^2N0?O#bpNqJryRF)&^uXB$VQnQRH}jOuVMe$ZAM5#WC8FtPT{%9Yh#~ z1XO%8nyVVX9f(IWM|J>;?+zxe2^0_M@nkem+&2cORbO$^7*e&6)QXdo*VYD#6AvMb zLGCMl(vLwMp!jht;SglH;;M0k`oOVVjbnEA1d1!iks6EqcO0dMlA{D!95$ZN5GW2E zpJGqF8Pq4;oA@wtJmDlhJ1oVg%7_~x=k3e2a^Xfmaq9$9jZ-ObBVa#rmHajait~;j z#}iS~1V@0u`Xk{TKx!goO@ZRSiCi}UiiM8^dh)3mGwDdeK;T5K+A`8IFLk9EUwWx` zW$VC*=|H*@VH?I#LhiO{?zW^lFh&w`yQFic3(sgnx)U|K5ZVLVlh-x9rz`b3((?)T zbmtkJfX>kF=}hcS-PWW#5pPe;uE6bxcc6YZ`c@jI2en%QyA$`I#HWnX<0H9^`3tb_ZZL?&(RY8-1uhI6ZD`4;26R=KiKYPipFc zV`qACCu;YhW-t0gj~%WAdS`7y+?Q+p9`~fAA2oIY?!-O)Q*73syZX@ft_uU`W4+V3 zb_}3KPhd~(96*rL>%-jx3H`u#f%^xitHxmNtVenP@nFh!0q(-p5Nh-R_Te6}pYn0n zl+0$avT`jN59E&B2!p|5gScaN!Vs`m;GR904|>9M-Pwa$wSoFS(KE_!U@WEY!>Bh1 zIFxuecMSz6=|6J>^RPP56$;Cl< zA?ZVi$C4`+((>V0Qlo)B#Z^r&8qRlZsdo)6X}LD3tEa}E>yCaR zwQksqx(%tF12!VBYPxDvO>utJ6q8rwnUzu;rwmx!B{r-_--^R)5cH~Bl~gUDSXP>} z7NH2}+Ej~B9w>HI&Rhmqp1QSoN<*MlECTP*0@#B27zx@F)~;}l)OJAa4HuA-K9*W8 zMXEDU`dO+%+s3YOS~l*KwqQs8r;wa7;3NHYikGBF@>Gj7%Qk5*3SEEgOQCCbc~b4t zanLp$2SV|f6p~P?K*~udC8|zhOQ5*R5t&&@%4}N-TQYAP-$L=NGejtUu0cvVxdv%x zolp#4o6sknfm+Cy&UOy>q4ixmq!f3do|AbW!YdVw><2-2FaQyInCkkn4JbOYi> zq;>>0Bo)ZfqT8;*M4=hz9bqtE?oXxxb%h?ab<^r-ZEk`}KbBdH+3H-Zsj#0{(lnyi|Nf z(PvbAM$!K{TD~L|FOKvCeKlsnKd0s8nB}15l=Z2tx3$iseoe(Y;-%%wGZ%`fcxn2g zbftE_NWZ(v>yh0VB`sfuK9+u$iq~s<=DXc_C>1YsX8xLrcMeO-=a>s6sd)QWT3&16 zj(&NXT8u+ip3Luk_jGQ^-{=oFp2%R&qbKp*+@3w3}@x z4^)lWk?~*77C9lgB3m`%&N5z2u1F5a`J8cZz0+Bgmrlq#W!zrI>vc-8gY8@?ac=Db zbOgyq*$eVcQU`s~Hm{I0A>Eg@??9Pzt}jroQqD?lssm+tugA)BvOW=S=`XB5GclpO z|9|vPS^B7mR+N_&k7gWG^R(aWG5Ilj&px!@vOcg^TBd!{ik{4PGy5~+yX-@GFm39V zqGyYHSUa;B-`p(4XX>yIj7PVgkrTir1TtM-)G+2U1#*ATq}j*Hn{_#_)PE0dS;e) zcI6U^)m+Pj;<+k}5P4&{6S)R|tFLKSA-$Y;0y^_t z`}8dBDx{C;4nVnSXPI-${&dCEceHCxAt||KXP)b|)VH&(6v2LxgDxQG16tl$pU|!8 zMQ!_L_KhPcEgL)Eqy&VnPTFwPW`f_X&oBLf**2}y)@n_Q>G8|9+=`$FDcf5~V0~a~ zN|eB8S4+u@wwv9*wr$+St_svLg{`4wL3MOnrTyG0?Rn>ZL&iZXMu9EUoYB&X>lSGX zwIEOGycM~&Pm8o=TBL6-jUvx)D>=61`)wbs8av7}jAC20prsu71q9cn(!{0GYu6^} zC)X<5Eu)<{_uBQlXZzD>oc2_PucQf z5pj%I)w$+qu)S?{`(a0Nq$V6Ij+!0mBfrM67MW+xL-B}`9Bp!o*J}gC-KEI0^&F|r zRpnUDPi3Fw?U1^kciQ8)syDGH>I&;d9DojVWtE6*S8CchJZi)TG zg3bUvaXa&>q_fwVEuME}5c5h6I#;C$i_+1p=Xmk4_K~~$v^az5`FtI-(U95@Aulj-e1|Av8VKEZr|Bo z`dqTV?57?jdhL(<%YG_FKiE_DTB)?x^8Mus-Tgm%P3fe)RY;#yCvD$l{gw5VJ!L1@qEi`!bX6x<=_^R(jc9>qk#XOE|ysE4A|8Y<_8RJ}|SKWzEz1l}Ui>F>kW9 zTluCE;JQF58|PA;v~R@f&cKY0%+pxTIwix|{HjGih_N#&%$b#^tTHOfS(abT?V+0K zylO+ANK0k%S$n7kJ>Z;kX0=Oalhl-yRVLGwK5Uovk#c3}sv>&MKCvgAU#_E4SD9>B z8gmb*E-NQ83iSkB_Hnml18mPf{J`@u+q#vZL zoMl;0i3#P3#E15mJ(cxZzQ633-|IDbEODcKm-UjgRwlO>-`QW8^xj@`7M1KNCHeN^ zulp;L>f37>)tmKK)_2aRTIq~Z0w(P%_0=YwQ8nomsWf{^d-d54fW4RXRMu-*Pl*Go z|7U+?^7yRRGP*b06Uh3`nP;#4w!cdDlzo)-SH@q64}aTJ*-k=nPi5SPxZJN2-}`OZ zPKKDq@#$WLV^MtXo<|-h`S#suXIGhQwaKuDZ(RL9)+P5&>M_nTtS`2ZDwI|%#+i;a zzfDZ<7j|I`h*^Dm{UbUq z953CMUnR0#qYTq$JGJ>$#t|-#5YxL3J43bxx)MnVWjiWjMdwyFHl>8xrI?~Q&^20m zNNg&8&DLi}q;yJ#<6VJ^=_FTCS5&EZN2FYtYq2YGhQ-C}y?Jg(+a%#@UH7HO1K;c_ zZwo|bm6VbzT8^3I{jOyNd`Cah{nO_S;F*OfH&7ZL!8cU`QV0(7JCux+N#9ay2YzMV zpGGUvt!aVsK-XH|wH$A4d;5MB(r>89H`_0Mc|}^tUfY^b1=x-&M|9P+O{>tBjtyJ3 zcn8{1WIt7-XB~mA2i56e$7<(vthzSTNJm61Mv7~rD@`p%kfYS~sW!OJ@##8Nhxz7c zl=7&{$aMsECo}+d<4S6#0V7^XniNlibo@62N+-Au3msdIcA-??PK2iEXm6U1ZJ{GZ zxwX)-W8Wk|WzqIcNPDe!+BY%nH9fJ(&Dm>x(jF>Ed#!KUQ({7KjD1rYSek45rZDZb z0rZsk-d-D+_LMZanBHE=dQD6D;s$$7zX9U!HfjImrDzqnwpX%V)6T0>G<&UG+EbN* z_Mbgvf61}8C$&x5L+#VP@!Wv&vyPOy6H$YdJyj#^wN7c@)CAgp_Km$J?zQhc30;Sj zeN!jxwJvF|)J=P>YuZ!wfcBq#Qy*ym?LhBjy{4aGd(M7pnD&$_vHZS0<(l1uc;~dw z^j_K|?J3uOX#;yoYAxe+GVV-%Cga!K>CC8Q{n9uq^IV=Y%Q3Ir5veRkyU_XSI2St0 z@|>fzZpK$S+LeJiv!sp6(pnh@nsKJ`qZzN7=UnsjYXw?MI>}QPa=6Z{jNf(4SElux zWf_m`$gfPBNeAS)X=j#WzG^z=tJ7xAFUNd!TF?0<=C47UW!!oX;+@j@<;d3;pz}-4 zqc&~k{1U6zVRSpcdU2)H)A^OjK=aZAXO@_%K4UyDT~Nl5$sC+n;wYgrtE8+#*+o-E zx2I_`X@*jb{QSyu(6|*eQecOBgYJX+CzPx{Ne`PX(tk*J`LDpYcPuXksR5|)4 zlQ7tO+oo7C<4p4Xm7S8Y*X*xK|Jh$zPl*-nuPXo9Us+GtYvQPC|FplvgyJiE%@zA! z=`ZnNzSoqkW%8dsX&>2Z4d@})*1XinT`+s9G0RZ zq$RF_*(}qWhxC`y6>*f9(D@~fQvTx1DxJdVka@7vrHT%KFnl3_DwnZ zONozMqmm)}FO$p4O)5!JPGk>>oy3RAn#55`9-U?4DDh$bbceIf9uh}MkxN-+vMe!` z6qLQ9tjqc4TvBrCd~+_0Gkc#Dw;pJDJkB*?xkvtY^XZX z>owOD<#_gx^tN1+{bYYR$MWaXoN3OhCh5%bgiRhF4*U;%ST=39(zIzI-*4MiN?Xre zt@5O${VP$YEKmuw)Q!Dr4=P`Ak3ktq8{)R~Z$e6cUaiwHpiIj?t&_HJowRN1q^(+q z7OYCXEmes3Y)Tbgfi z?Q_4hCa@-@RSE95O2tW)sy(DEPQ2VKZ6W7_JzI|F6aveTTPbbZO5|kn4SU=fP>K7r zm*)JiSIg7G_PWvpdqatx{HUC&GQ5n+kUMZ+tt1y9m67oR87Gi&3Yp|B<1aE!BQJBy zWHqi|EEYA(OcF8OGhMpx;YM${_zOgGhy)}UWtEg46H+3i6@B%s}Pq@d$%HGW#~cs-rj4R_Gb~W zh#FhQ-j=bqW$bOidl`@QU*o+kYwngc_y5+K>x%2j>8hNqvwT#AI;E!4v87nG8v`4Y=lUy0QB3bi@s@_pb>)@Xm5O(rFUvnP0D3ylwN^^r)fg}5 zJf%D(uA)*=6?kG@U|sSmP*w+6ma>Y}t(mU8()l&X-LmHXd#$-8`3^Zg`JQ}UOeuGH zA^BXX_>AAp*O8lS%$Rk2W^`l1l_Rt%wH+}TtyrIQMm^^QpVBBD$u${mdEV{UBU!G{opi@-p6_tPN)0+D9oH3kVpCvK>Q>~s8n7C96}gsf zbbN0axBq{R+mc+i9JQk|8^dDYl4Cd#5vVGVW!HB8rkr9R@*np|brwK*fRF&w%hvw4bhmGEV!+?2A2>nfz9$x%{;Q6Wv? z*ihEuK3U-Tp0ii-S1!eu{b5oX9NSy8PNtDqha;v!h-4r_#dG>ANZ+tW1u0I0saM>IhdtSdknhgfSiW zN(fz@e9y@L2mZ@<3;##|D_a+RkK&Z8o80khKT8!*(LE zP-)nSgoxd%&Zz|~C0dh^YaNA7%ZcP4Nm|=l?xamj) zjO%c6CZPA#E!F-~(ls7=*J0?2btiRbx>r*Wlt<-)(x)8h0_;mFtty4h$=*pMKZjLH zrBbCS=>_bC94n9$wPVWn7h-L)C-yW8Q>X;&U9N=6#I%?xR92=1OrbkJ9}o+bt$j$m zLu!Lk=q_JMt%MvFVzGva9nG(S-xBAr!uc)mdt$AAeh<`&Xbx+iKLCFu&S3@gN8r!I zxzw&FbP)DC>3I%qwn7JIZ)E$eQm9?5)`UG%Ip$u>w|!Dcr+SKQ$Q=o6P22+AALXEG zD>erzgI8yQ=hDI+A(gDT-#4Dy>(4u^IY22QdE+B-IpMo&%w|Mv-cgsE^nf z*aSG5xDn9Z4|RYV0vj=_oQcvpQc>;=6)=yK>bkGtoKr6E{zd`wQQ5BhKAX`P9E+V% zH3&D+nuh|%k-L%B-5$6-*Kbne5a4Fw4XIVn4U}%gM(Ug7zeN~>ZPd3?sE*?sscp|U zsJS6o%ymQH+r*1WHNYC^U#YP^wf6Zsa6Q&QweY!w@&-WnfR+;K0hbW3!v^A~Ky4we zBlS8qIG0komYj9i>3ov(Q-r!$K>VECHCR9W9E+arnJlBEE>;q?i252~4VFROX<1H5 z9c(CSHFY(;{T1*_YP?E%HMTi(q*ei6!LnzLlz6TR&>fsYFlRNOdtrrOZ%?whgHuS2 z0<_1(e#3!7v1RF=&ZC6F)VgIYY+lw*EnhAt*1BRLmNJ)<`w*5)mjkuJtWCy3ENec) z^%GnbVwv&@;39Ig$N4Pr^<0-uZB`ayv-3If9w01AEmxMtqUZDE-H(0L=Yh{rrsc}g zSOa~5>zhao2i{1$Ftwz*ko^0So5>rFrBQ9DE=Vn-E+Dlq(PkwU{Zq@R^T}U;rPPLlsck zoI$=8JcU}oyOR9r*yfy-+VIq_<4KeZ!$Rk6sl`rh&Yw))Fl=+qPVIJTSM(I}hGCUc zJEWHrreas}6ml*jM_ZlRE!7U?Fl=z%ky`1zlXyyM|MWCUhGB#AF0N0E4nINn*B zd$Uy$JV{ASR=2kNr}#|DM(Z3}<y|q*L_fTL#q%sCvK6hriEa^x?HP;R|p1`c9KGBmaeIO ze<#YMxtamRu%1b=rQ92mnr{MZKjCR=T}1!Y0ZQ=}5!`{TO-lVs_k(J4EuIt$s9c*Z z|LeY*G`ekRPdl?6sqW2}B35ff-4%D|GmgN0;>^0&Z|it>zNS0v($IN1QpxB0rjAE> z+p_7{P?y&+;|ML2j*v3sJ94UXo$ViH``c<}IC2~nr3j9hDx}0*;xR{Vj^MjiBIQgF zk2y0PKfZ^OpkKd(*z4DCA}00UUEh7D-+PDb-~C75p(@aKDt?pVclh#n zsf+5oSpb?_gJ(pbJy?U3`^yESJaJzDEa18}Z&V6sd)FqVEWw_vLvWY545@m2Lm8m+ zy&frdnQeDv4N9HMk!qOsMMK)8Jn3@eDl@A9tiZLqvhKesU28(yRsy;MEA7~Xcm4hT zEt&s&bHT3@uVgc#crN&L@`TxpD4q*`qw7yLBYr&>&7(_fG z{t(j?0L3viNZYEmVNHT<>%Y_@Wc%2*q8O`A+J?5Rt!hguAGd97N!!*|bv)a)wyG`J zfKWeeJHMqu+Sb13pTh}%)DHO;_&uEPd+nTW;r|Jo^Jj2^t?zsABt_xw!HF$SIa zzc=5rneJHiq**r83mJpX{QP{+X1ZgwJ|UawMT|jbety1ZGu^S;h~P|j)_b3@oa?Ip2`nA-QU7o7{v5#L>GZf}dF#Q1)nqrsI?y33WpmC<$0wsFm{ zRUB2WO441nrK^jpjcsi2N`u?#uKBiqHkV7{b1{C_=h-~4ZT^uaEIF5bA8EppGy1nQ zp>OhQ%CLI+{=Vn$&1L8B?^A}p@qdRV%u|DE(n=jlZ@RwN9^wpF8ONb(jjK$yzKCi5 zcztmk=2sclXxAFYr{ho>Ia_7^`TAm8=T{kLt7}cR$~d=u&p)OKeNSo8j57SQG-2@= z$m4%UMxHXvB*EhNj3%^p9uJgEXL#@TD4ai!@iJUzOF9F@cw)dm#&{X7bB)epJTag% ztr+8FxXzYrLU5PUIjV)5itvY(NHwFsD*>fwJo8`Cu_f1qKhy8odLfSZEzf1Y{4w7r=Ff9~%3J02lnqo%`|2xi+{$$bnS`mxkzTr5vQ3oETj`(*KlWkhgP9l5en`#rDoVTUZ{^UT}WZ zBslxzCY6IY!~DuRj3A{X(iPIRwHf2?{mKXWE^?)Er@n>UYW}U{V&yM=7vCiRhH}8R zg>T{e_@2I@@8cV0?^gU)zDfSwib!P~xO2;y;XBxyu6n+M+hDLT?TU?h}WAHq;r@F;>p7qW&l(IA5y^!*G9^A9x zS`*4ni%U)AwUs?f?wN8=mV3tBv*wxA)*i?c-6zj9pi62xtI?yTy_#~_S$0pgcSBz3 zJW_MMD{@R}D$l>`9YuMCdPAO)_l&$6dfH7?mZFBT_7s(WW~b~kYcpD}@D#phQ9YO6 z0lBTxRW*#;Bj;7#tj3^P`|5zJNxU^OVR6%K+PK4Uo8RkYwRO66*GHJ z>e^_9#(i%!4b(Ykk@m0J$St?@*Ova;GQYOWuPyixthfaqZdt#!&>LIm4RsT@(1%;_ z;lCq2FO{F|G@6pflsEOnk-UT4s?sHS2f0|Uiu^ef$3}k7E0e)zW7Yrq6ESHyZN7aiI8$2XHnMHd8v#imE1K@s-#An z=LNI91Mij3H!g0srnF4uROV6z`AT-`peb>Fk1{)x;BH#BmzF=hpmg7z_iPs}+beM& zz$1JeOoChzclC;%fbAJQJ85bT{swzQY&H^VCC$ibibum8 zVy&b(>1KFA+@5p`(#`Rk*qwAs(k<|~*o|}-;#$eY_@wNFXTlD|mk=(-|6nKlQeH%= z6J873Q*tRme}|p%MR_45o$-3O4JA_um*Nv~TRcTxK*_dvaNL@b%Lr5O>39M8=i?!= zR&qY6E~$^o%Ybe11$jAPYdlk)Pw7;=B(}weWm|I3C9hU;1vyjk=-CSIiFW|!09z8@ z!TYzwi{~8jZ%;id-bv0K_}grQKg`+WwFb84YBtyB;CZxZawi@>XOq60^j-J@y^Zu- z(s$#ja~A1ah|h^P6Q2`rB0dK{qc;I>AU+2VrZ)g~rx7^~@$PvQab5CiCXGoqijDCNdKEra>yqZ`s25Ht;QADdM+z zhf?uPa?1eUB7TRb90fdzvd!d{1-?oAF8S}^*SstqV)e0JHoiyByZ8<-!Z)lQ&x`O4 zT#bKOOa6PnD!Hn;wXtfhT5bb1%BOzD%f-sMD&)Swbp_xC;!3&7&5Qe?t1vI>k!fDs2R#SjJp2MT zOXlJU*^{+%fe+yQxEWrN9|S&#@8XM-!d#i$MVxpRmdTaPU6S0(|6PIx#l7(oN-ySw z^hHV8+=YanNcT9ty0h1yYXI+#of3|&thNU9eQ`*Zs;I=iTCHBKs|_kfmdkHUT*|$ z#HaQi0zYz-~{@oc&YaE_9oz_usIANXBhJM&Ed`9Iq%J3FgZie zfBFQ^*H>`X{mXa-;Va-*@oV7M@tZh^(!od|+a_;@c7(TpZ{cmcUGg^G$=fCG;IX`2 z@-AM-+u_6f{V3~izc>3SALHZu<@iJV zJD!&R9)AS>7=Hr(#8|(EJHEqf@ef?DjDI8ULw)@te1z}sRpjW|_+uX5Kbu|IXRRQ5ie%;!^jFZu~{D8-*NHCD%~(2^KHsTR!I z5ig+5d~_Oar;b`>1JK4;7Z;%SFq@qFNH0WVYy@NLEi@&rLdRx0skhOWn2u)7TjadS zvtNsEl3E?#A^&Z(t)>xgPV_Urnex}-yX3rsmd_eIYj2`tO?;1>chT?Jl&pyBNxz34 z&qmU35U+@5ld~S3hqHmB(O)|rcszP(qX{PhPednUG~s06$>?5;CY*|HSv$UA1*yLP z|AKbK3c~5Y)6uS2L6{7jj7G%@!dbx4)LlVpJsKvXNv%XTX*6&&*Q-dcOjd`3lQGGw z_`4U5K@aJ*Fg`gLcrazJgjd5M$t#4h$*M3Gt)^AvjZM}BeVwfddO2G|{nzkIe+*i0 zYsp!IXZvwJJFHUoC#>RXWjK`odpW#ODy5qVOUm zuO*+x>(K4_G=4_>P|#o6L)3XNyg=ESZRqB*q#;dNjSu686}`=ZZ<=fjT4^Ze8H zl)Z$!Xb0k*l4rwnVJAv=WWP>-Z(9>40v`$whpm%`!y~{)!lS@P!(+h5!sEb+l&kwO zfn7(ninK5N61$7b!_%Ql@^p9x_)K^f_$*IX8|3k@4dIEw-N&cGvY@8r65x`sG;~g$3{L@{ zqDH4=X?QZIZ@CosB)Rj$NAcr0KYSej3jAyQ1b73QQuD)&$xXmd;tk2YVScy?coTY2 z_lBF%V7fQlf(FyQ;Z}6G7Vw1mVL|vHei#>o593F`&*KNcFXHEMUbr_bPv(VX=xWU) zwJhlqmdB@KpYSnSaecyH>8ZZqBQ)pwlG7(N35%1)z$cQ$$u8mP_)Od-^das?oxY(_ zXiRw{!jhyZb((~x;c;}unuW*E8*4_oY3Lnx3D3m-;X^d``g2#m(2)CM7#S@>6y?FLBaX|P0 zoy-9|zkg`JvzI0f2u~)>!=vc2HRny5g`S~TcsBMVJQrJpFVNs@!CeE;34H_|xIoS3 zp+0v%nbapdm9z}%>$Rk2i?B0yKNll4L#RhBH2nwHun*pqx5;&Xf7@Ea55L2*Bt2_TCj5orGTZ-bDhgON8rO~{Iw0g zBuQw?zqAS4^W^(NAtj|lJM!CxpV2&R7q%vD7k)w)b?dMV@z!B#*fwkj+%9whb_rd9 zT|+lux6mEfoo7uY+!yZVX@$VTPzG2glm(UzMZls^4p=Uf2bK>N!WBHbJ+OV~0PGMt z0y~CIz)qnvurvR81z~Eqi#sX+D};)`ilGv)Qm7299I61TgsQ-*p<1X)pF9B1TP;*4 zT|LwQ)(AC$HA5|6txy|SJJbQz33Y)Fu!dDl>e8cCN#Tz#ev6jw-oU-$o_Lr4F4>dt zeXnY)5Gp@DCwbb58xhg7;sn|9_NHR zg3^&Wz^kY;JzNzA$06~mFeL5@+%@h7+%4`NZx3^VvXk3^S5xPzaCI0I2gljr_Mil1 zHt@DEJ9z$aR=6!x;HqMBX_yr*35SIlVSKol)T}Ti+?v8!;nHv@`7?pzi4P|n7A~UJ ztZ*51ri2M;?l{V4hOuEB@Cb4ygbS%PD_l;U%fdw9<>3PIW&vmMuLG%bL^y;yW`-jv zofyV&H8V^iePlS8tC@(0t`64#uc2;|%m@R4A?b@)c3>DpdQccFj8_Bu#(w1Yi~WK9 z;{f1*IMAALP#i+};4qq}&J0KK{7Ku^Y*(@bJsA6y4QwdxcBIAb~uN!-O1lA97xHv;aKvI31?AKJ~@u` zvEfXv$|naJv~W7`^l%37j4&BEnSU*poXP*@l96H0kW2Oqdja{H7Ws)1iO~9KdLxVZo5R^P#9}1Hj!i~TiDN`PI1Dw(Q zaX8fNu~2-+LT5r*B4tt1aw1%6wn^rT7BG?^Z+B))?DX~=&(nROK(DvK2%hKa99G=($a|LX9BcO3NDyA29yiDHd@Thg+PFHeu8l1$bNN}{=AUuV)e>XXq_kWxGcYuFEvZF1B z7VsdexaTc$v=49^vYxk+l{`V~4lUq5R&lL$hZgW1tKd`CN*lm;tb#Y$2;7ux0B(f7 zT@^RL39Nz#c^$YO+I3ZY9l2-S?V;Iw~!G)d3Xn!ppMb6R8vDNX_ID(SZaS}O4 zG2cdnSK~;+`gkNclbA~*!}_=<;SHeDpNZrj2^LfSJ~4PwZ(>lUd;~cYnRR=H4RJ5R z+i?OpM=%5T3U9}~32(*2$(g`x+&jD#_a(du+=uuu@(%~=)=Um#e!hvUYCmS{n{ofJ z87bBNqF+kd%zFiKt4=9gaU;EgeLtk`52n?!{o2fxlHifMr2GI zku611?;tY@#6Oes3*5A+AAvu?Wp5<)1Mu&0W^$l73%*>qf7k?fa{xGNMluSFHiOcc za68u~o8VqHamO{}tMz{n*zkHvHp1NOoEji!CX{4`&KOM{ZQ91WH98~3; zba&<4J5aTi`O0^YO&+F^oR(C{eFisG1&Q5fNcKL3>aU7C?^9$Mmm`mu znjFeXHkJBUB-N1qeS$pj6ZnH_xxdnmUs304g(`rQxB$S^e zHFMgxsEN$-)1+4JuTb~3a-Tr&*Fu*0Nm3iR=Ev}pM?;|>ML0Sc%hgBlgkB$+rX~Wl z-SQDU)dZkExIZRt3H9?4;I2=m7QtmNUVQouXjU4M5sEOzJ zrx~ovEulo@!>*$AYUp!0Y%Oyfmds?mZkbFE@^jOva}`u^rQD;e5HrcYGRPNRN$GTW zB5jZ?ORddlw_`js*-Mn2M7>t5GS?D6%)O5Q3y_)0J&j}C(c|CA)M~{Fbuu!sQwXgS z?P`o;O*{p8R~zEitc<53(Hey$;U(b9#G{ZQybN4LJPLk)74TK!QORoJQSj!gfoq7{ za<`t4PGgPL63a`;K?G<(!WCgOSHdfxnh$235>AE2X-ECGNjuiz(~wRaoLmmP3@T|1 zsmqW{j7g>dr$AM0%_@C5@O17u5IM%B@WGQ=y|*EM>s0c3X*ht~OTz7Z`@=|tO63Z2 zw?Lr?lewoo>-=QWXR+qDPtJzgXb=5zHt<}illIUr=Z4wbrM-+Y zxx(B?q`8-bk%WuGZRBWKqb!nIZQ5KM_9R>sE?`{eau*~OkS1S{R7A>rL6SorJ&T&! z<|sm%dm$3p^1$-BayjkfTom>qK>H!PEtk89P?Xb(&V^xb!UafQA7*wvM0glE>?6bv zrq>UG$)+MDF5>B0$tcP_M)_2vzaY-jQ{+pA|@Jzy+kqvYVQ+Q&>a4FC1NNFc{sLsd;wk6z{bU+3@ z1vrJW?I^i1X&=rcD|N1iwzxDX32jlzA%5*vm4 zks>yNce@|BD0u*=g_*`k2=IA9z=k+722MMKCZRvF9qm6o0(=ySk5-@_L*~;P*c;j2 z!{j`IJjiqJ4*?$z4+ZU!KaNCbAaEd7vmOtFkQ+Zp{zKtGp4g9cv(S`uQ?8ysYBU%) zI2jJ5_(TwD31$&>9t?{@bK+Ckr&|!Oht3=Z)u@%32gqL(9tbUnPoY$MFL%W|;|;EZI)uyfLiJ9kFf&4j{nJF=U(zt7xk%&YA`94_QgsXD+P8<}uaCTJ4xD6X z>UTl{b2nVKa=5#Ztj!^JTX@|$$m#Ba<5gOB7xK6};a&9ycPH=;>TM1uAUob1v}?AR zHa-zJmsZ{!?qTnBbC?IEzX`aR9Siq%H-&ql{5OU9>@{r)cd%#mCOZ_zv%jEKwKqu} z2Rs(}@|!^!^G5F46gGxy;_Y!`a6fo(?1B7caMY&H;CM#T1Fm_8usv`v@lovS-o!59 zB;sA+sket;o=m+#@yuj$awL1dH^Z&pO!?8&x(Rp_yT1b|9R%0CJrbGSxNrM#47oS3 zD|$5XMD~qu0p7x$Zv|!EZ-sM}*@yGkJ9#Ud&K}ZR?5&)}Zq7Bl<%TeWUEvL3W}E@M zmVM&^@hoKG1NfJLaP{4h{_M`bbq~k#AJ?-Ndkpar{L4h(EaLw0Y~<$sxobdd#~s~5 zJ3=oc3CB`@DB(IJ8?&fAfnDxd?5``!+nTz)LO<^9kHldpbq=R=0&q6*Hc?69Hq`A6 z*;tnmkb@JgOL{oGY5S;LvOTqSfh!$OZim<>^bH-@`R@|~{OfR_d~3(p7rwS5Ck6V# zBkw`(+u>|@^|!-0>?pj=KG8YAU1D!?`f&c??a-Ig4sY{bed8NQL9PQ{OS`-g+{bnrNDf2(R3kYYiB*kcHht;2m4&fF=pXupipci*Ar z5O5IpRONaPWE$VohLeyc%8sRv|9n?8GZ! ztJo?&6C$Y`XBS=xt3oMGP`naalG`e_jL))L(wdVj&xF#HuL^BAz4A;5)QGVKr7bzJ z@e0?4oPSsqnv>Haw&i@wGo1K%g)<(%@Nch#GUPoIno-(3z7qgPs(>}YSSF$o$C(JMjd522t>sxQEhZMQd$XJz?Isqm8xu%B!>&$2YD2LA(cCZO zGr2=KPEZsijd^mD_&&S6tJq0;HZ+ba+4Ef$%5#RIfL+n|!^+SoK1Y5fcGdqLDsj@~ zN8r!lC*UvPXJBRG3Y@GcV88VP>Nli*qxb_Qe`g2xLvku|%Az1?Kz_scH}ZdA$M+-h z>yy(UeoxNd*g5`~oOhyd*q~FvS(f~`HFq@ipkgEE8sWbYv8xx8{l{0TcD>AO0#cPH)7j>Gc=qe z-f&KPRfSohGU@g{NRF6@;MLn?A1nQ|(x<}85&ezPBv(%EBk4n+hRICnEf6=+s z6}qU{>uRRED6ORb93^uleXsT=FRy9oY;#9YZ4l{LJ?bd=%RI1V{(v%#O(|RT(lh_f zos&*UNq?)E2Uh#1Q&Q63svd+hok%^c_M=RHtNoJ9>v>5(teJP!lD=29;oBT}c5`M} z-Y>O!lX)Mjo*2nIt>*n9sY99hRkEkmr1We?<~d0n$yUt2R@88Os8y-|)l9cioyx69 zd&WblroJNeKd3Ll>|FCezBluHr;e+>@cIGuuc4bb`Wy}R@^bT}TY3kw6e#pH4so`p`snweI?x@GWyq8Wr3ASQH z=uI&52zLQ9GC(f|V!7=A1?jaMc7UezT8=qDOL;9f9H0fgmg^1BkzUKI26)J+%)9Wnh7$kwV>>%BSumHI4K%?wL!CkaD2f(bR779njv#0;R$4 zfSx}dcnr1WPXp&%r19r)F62bu$;5NGz9Z#ZLvlMj+sQzAx7$h0K{BD0&e??988=$y ztWTH?tVdiID*80wX%7HKJR zA-T>jweGcKumd^H40(EIpl7nRD6l;_J1}-Vo$W03?6?~I-O1lRoyn1Tav#^u@QCEX zJ(^qiVkINuoLjhVmEwYkjNm?M-=EH`F2r3^d=Z&F_cNOYaTS?8_j5g%E48x+10Br~ zS&6$mH#0v<1Kr`dnd@7SINZ-Y52Ul~fpp$Ikj})Lm|N@-F~8VHB6TxTi3gZ>i_&?w zD4mHn@-;=sR*I-`Bi~gHN$?`(;Faloyn&n>k)$bAR?>Dg^0%vrwPcL6Ilb2M@m0v~ zv{HKzVRR~iyb7qCd6Y71q>zV_K9KY%q?t;am2FN(+NMnV0K$RDMz3VvD=EDaN!ko@ zCotzd_aZh>rn(K%q#2Ycw{3^SNo%+J681x$djvTX32l*9%_R3ouG#{{411HK)Jtjm zUckM<6m8Cktq(zFo;+^m&)IBsZ=1BN(FMrI(8#pnMV$p$xxuO6Sz0x z9I~R}KrK_VFG$S3AaRa1yq;fzL_SA+9ewPIQLO!<9R&B&`V&f8L(mR_t3+Rd)(~7P zTwD7xI$bMVdHXPeGY@yJ82@MoL7#Z_m<@S8iK2YD~4Y9 zw1MDyq1RG9^|@Z?wNL8@t`}NE&<=tW`LC@ZxJqafL2C%E652%28iH#?wmzu$B3+<$ z1g#-x2f_8>_pKrPSvv@>(#6&gw1bfMobEd9y6sw_9fZt_A{#cOT{l{#Gp!|kq@J%B zN=hNKhR~99g%pdmAZ|rynf6}=?iD9&mF7yP==EIh(DtRiv-M``im&f;{hQjC6?j8E zo^B1)i*`b)Jy5T-38{|24k<>mE$ln(f@Pj9)XA{lOWHdN)Guk5v!q?ulJ-T`c=}tLwG%O3ON) zk&!A>r^$0MzK5Dko{Mp&IZ8bP;_Px|)#^>-#`*tN$7vAlAoVN(HlI6|G#y8xwQcLjQ0ydzLBfS~vUAWqV zlA(;^W{lKc1iLn&8&IjZ z9PIW$Pslny>!hPH0cPBtoSY-KMcSHD@8T>+wAfh;)r#*Ge>;}NyW(GQ(^j-hX`py% zD_XG(P&!DStyS8GV&@{R+W_?^UPP)LP~2QZN_#uvW;sYXmiBy$c=4ZO<;IR|-b7p~ z2PA(Z{wbeg-K<5l{_Pr=c?K?*w&L&knh|G9q1obMta1eB%@#acOg;QN;MvG{a2APa zozvo0v8otW%VT0yXSO<|VpV6hnxbM=F>Gc5OwHCzdsM6{hRrO7X^~QmYjLWY)oPFW zf6mejw~JrZ&Cc|`OOfv^QQO;ha;~Ta?rh63+mvTyD@R7_WOP!ibQb2AEzUe`N=Zlg zoYv_RTJ!#eq^<2-%rT>!dCsu1K*w>L^bOnauH{LWp|_nJ3SeSuB>@ z6t5NAZI#;${8O=iCwWe3CNZ8*=*Tm+%)x)JIVg3b&bHD7=b%;x|94P18GYjj|6lCA zchnTsw(ecEsv6#^YBDc5XC&vGvxtb2F`*zqFd<@ABngTH(>8$_Q2`SQDk>OI5D*mv zR3wN26%{0>`+HV(gYI$mch5QFxbNV6{l|RfN>$xeE6+9OEVUx_Q8|lUL@i$X4wrZ}Fz#Rfx@T$p z(B30nr>V8;+j^R};+gC}H~UG3pgBsG^IA>HV*an+B8a~OAa9RpU*qyR9@~EZ)t{(5 zIBEr{b!6;`UVTR}>wN_vMyt9^v!GE=<*1P%VowfGVT6g^O&bqE$ z$7r`9>1!-`O?w#BJfuCypFIr9x8R@m)M~TZgTx*NC0S8h)_AXZAl_N4{c2Aw--2q_ z|GcwK@2S=Q{vEpv&4=oRS~I14R@@WS@6`V^@9AIbNsVoXdaBshg627;$uG0+q8U=H zHtwmKLv_9Sc09MM=jsZ@R9>MtPq9DeC>-a;<^Ej05^bO$y<2O)N>CwCy|I$*jcOs< z&8SaSurr^&-BX-!CDKa3CC$}trxaL{8c?6nSAgwnm-!ONf$PYFyGA z*6LjQHMJ0}MHJH8)@nj+sG=Q_E7~!-B2S%7iX^@jdA7p*?}|LVzIs#y)UK&2Pg@Ku zLXM=`Re9nPpybw7c@nLkD)7{KL9Ma0vdPagS0FtXn45niiFOs9wlr9ZtI87AvsIvk zq}o+@GCg@Eo;n28rc?v^>PjV29P;Bc2JJU0k*YRPnWwEpT(w-8C#*y~2O+Jn{=9op zUc84X!BsB*UTvYIEu}S#>QU{m6eQ2vDy#3*#b2@37_aNg+Pjw}T!#Oubyzt_wWbwV zc?iE0{MP^si0jLiAs7-*KT$-yGEXHbEweRh??N4pf_QOLbirs>3c+bzRTa zbv;6LZGG3{tz_QSzj{~cwCvCd{5e+~@z#W&XFm!~giX&C-oKlOK>i}2%f^rz*JY>_NGElVRI;-Rq|sx7yInD zNqrw1)%URXlb%bKJA;@#!H0Unt8EOjFbYDkq^Ul@kz~?lJc)pxw zF;AG&%*5+iP9u+FKEEz|LHU*RjeJk~M!qUXxsUP-qoAu?ozCctMy;g;p)Gj9d6c}X zv3SQLlaY6@EF&*lSw>#Avalt*4{OBL+{?p8ZY5!PhV+a)P9Mz{u-VfCqqUK>3~ujC@ZS{)vZoYI$=tM!sH+k)PP2&Q^CDSPVXr zU%brK>Ekv~-e{#GAe2v9ol^?snN}y4J6zd5UJuH@R%qm3D>U-2g+FXgfm~y?lKDl0 zhwN<1yGH(OT`VZS2j%6}HS!9pb59qaK_l@U)QkTx5|j_IUeN8X&NW>;2Tdg2+m(m0 zKA^mF$>&%}M*f7;*OgzfzEB^xAO1YXf#ZnxcgGUz5B0;+ax9_9Sl?g9`u;N3_m{bq zQnJImiDO->KV+=_kkPrSWBBeUzJwzD44n%Oz_(9?KcU8)(v{>qUnh)>2_^9B6Pfc| zX+S18)z|1EoyY{bk~$rg#$*mh_MGQq)hW+sNh7~#$6ahxus+q<>v30Sug6`T&0@>R ziClfI%(9x7Iq?9LG#9${hzC}KGm8^5ozP0}Gr-n-1UBS#h)L5l@Ec_ z9v*0DM+3ya@Cti8VmvbwC!|E{D}j~p$8i{cCGD^pmVWeMyq0tTrFngre|H2Q9eGVR`OIl} zV##N!;nO9bsgAGDLzFt~jPWmFJFNsbPH_mWRY`)waB@Q zcuVYkT2fBlgj;|uh|Bl!Ay?jz54i{7!V8=WorCU$ST!AV2V(ssU+xF7YR_kKVy&JN zo`e5UlW;y$15Xb1@#_%~&a&Q1Yl1cL5*oU)f(}U!uye14$55Y~TKECTPij%F!Uu%) zBkGY;8+-RUc*QZK)xj#fE&Pk z7l8sM58eU_n7rP6Fk({z|N<`e6-tE9EDXBG2;jWPda9;zr)654clEktcfjwwK3_;^q#*Q?NY5 z;t(H0^42A<^>=_*!e#$>C$@?=k}H491Lf_*lub}%ql#S1WY_l7W zdfE6!_>P=xyd`9tJy>iN=c^I3K-q3Rf{poX!n5$RkZt~O9wj^*3;rV5>OV&KQSf^B z4m>Rsc6V5>tvk4DA-udj%(ahWmw7!ld)HI$C|Ak$e+T?QY|)D06;2lH^44C|JVD9F zu_2TX@NX$|6f3z0NdMGYzpus5R<`+!FkZEtwS?tSy(r!rhfFus=R$*iVe^gct9&^-oOfS zA+e7scL1MetKb`Li6#7_qGk#7CU%&wkT!?=KaFoS`DT9$T7uQB{H4D{eqn=mcV`pf z!e%3$(>~^IE1`qfzD}jgGteAsr~3?cp)XPLZSM0HDDUoHlC}vyY%3|h0y<Hj-jYsh8xRp{zz$3)vXL&0=-eyp89_79P=fmG4Nok4sqmc%o#1fEM+ z{;S@@H`^9xIsV(W5PF}ITd+2sN9b$r^)4tc&`WuDb3pmXf0p#G?H!i!ub(A+7r9IA z`*|8%%F}&G`d6TS;ce31vG?B0dy==TP0*LTDgDob&=&9mVjIcb#BbyI-@e1QLHWbm zK-xy0XC9#glsrg#QE!(`^jqLt)TX{<@f0m;K4re(EzNh)(JXOJ=zdV_kHX;I$n_K~|El;^&^;670P`>x^_p0Z=j6i~LwR}p^_-zXnZ;t%TX zBYdN*Ahd^;u!1_-N=>rMpnb7_pbh3Qvan^(!arkILeFDYf`>cyEO@v}&=b~y>`p-W z4r50{yGYPBUj$`^yqi1kvE$nlpzMO#k8odhD?9_c71|g31lnXyBU@YcBRmni75WXk z6?zrB75ZOJ^E!Q!T?u`Z-3tBNH}bpZ%bSU{9Df{qoUtX_-NsX7yK0l!uG-{iQXd7c zhO;-J-?JZJ%*Zmbqh-&+-Px7!PuZ2wli0J+FFhkqf9yvXh1rkbpV2e&6yq6rieWFq zvw7^9)-VRhf>;*ok21#0#@bc3>a!VJxA6}&&rW76-bTEDyPdbp4uxN3_dz*!ABTL4{{pVQ z2QZnrK^|7~k)EH~a0j8huDq(|apgTV58=GbmfsU%Z^GT#n=r$$%4Ze|na6HoT`%9N zuE7f^xRY7MHS!wiGS4QNisk=@eTtJCWVhr*@TA+D^~7Ym=C}-$$AR9&Z^u)P%Y5C3 z_(Z!FnZ!KWhj3qL0<(nXgMNg@gMH!s35^5$!3Pk!4eSq(jI8q`Ba3|YEX>1^k$44|aLDkLYnm4Nk%!#X1XUHG}&gIx%-IQtCd^~luWcMG|7nE48W@-(im)2+AA9A}2BMYuMrnd5|NvidmAKIH<+u-{-!#D0L4(s5QV9=nwU{J8bzbKLp^I?gZW zWS!)2WewIX4y&tyTvMHJ4OVmV?^BH{4QPmK1wImAZpTSG4XVaU@;IR?U{%(h#|deD zKGLZ~xH5YHS)sE};hyYMSf{a1VI9ZLfi<1J*Hnq!N+s5^O|A8KQ?49g*ZpUMXA`SH zennQr$5<0LV;wo%?guVq0*JA7vF^mT-Bv{0-zb z-CV5zyFvBAV#MS>B)2((a5q-@#aOv_W!+hfJwz#1?57i!=cp2J`JgHZmLT4RPziP$ zrAX_<@0DWzaTMMW>V%)MqlDUn9q>_hl#q5&?O6ABDS8dUMY6IJ?w6| zAt(#`QpB~hDo;u2BtvN8KGflXz*n`;tXy9wYr)ec4I+xa>d(ALc)_ zVz<(qJ?3Hdlg+`F@WZ6GWKURya`K^OvMXVy%T7RAutt6h*t2lwLzFq69c&Z!$b-4M347Vb?CCBc z))-mAA##V=-Ptg^I~&G7Ig=f5Blr+XHDYHxgz!*k7!rmLI;st^acCF z4-)T>gySG7IvZez!d_m;o(1WG{H#cJ)Bt%v7HJ9g{Yncy{fBghxJK`?&J+ z+8gYR{AVm&*b7O~aAX-hkaZp4n%hY03HC$=GKQ3E!Qyzd8b{hWpnULML&_K=MB@k} zV?$atfzWVpJbVHn$u=f{SCcy$DOUk2sVczELY}z_m~WvSNCb=HFIzsj3YzV%^rE-h zyzOp2o^hKi?dWZ!Z%1w??dYwfY(vWR1Lb!@+2D_G`QFMlTU=>PZ=vK?q;Wry@{OzW z-)~6Yg6!~TQtrb)R&gYc_wmd3621=^I zd9$>yH@niizK3h?MRqs}X{Y=Pk8&kpF5>KiHX|!7hJ^KQw;l{(?3?5VvRylK`OYEkn%@p(vpXY(uap*jtehvJFEMFzAXn#t$Fs0u^9{xM{ zJ9m7H>n;N?qx2;BM9u*|qntdo-UZ69vAo

*AY_Yw*nnznzkkI7#@Nba}&@i#&S~ zB^N_?BDG&^QJ#pOAzvOu*TeDi$MtvtgyRE*MH+Tb_!%4w@DKFs)uB@SKlxUu0m=VD4U4kc(aa>29gpTDp{#o}0|{mCQy0=(ssq>D zBij&-TJlv;2-MqaKuB-9KD;3z)q>u+yx+<5ooYcgcKJcoj{KdeHsu+wDIwLe>a-al z)xK)EIU%(Q)qV>?YAtFNEeRz-wHCD}wK2_gS_dX+XKHb6pa7JAhqi>WK()zsgmQvv ztL+J?RjUnmAf(o=w%w7CdVyMdCqn8S>IIz%sn@7?$Y+!bs@GH`BwH-?ro8sKm|5X@ zpuGHFy#Z!i;<@ab$wf+T{;A$r5|W<*y~(rIB#clco>H9@_W085Z3YbBk*=mf;GZ9w)+`aXDR;tv0{G$<==jRo@krKd}O1z1m= zA1Xkd=xxZ`h@M7oN&ZLj@icmS`UbR~QExRjq-WII&IRci1N(HU3q6g#NUb|at3bK| z`j`5BX&UG>SpQ1jXjXg3&F|#{^-HW=h_QCD_tg7LLa~2_g50?vaoN7=i_!Ak5ZL#b zwu9CC%!2gZ^geS!dV6Zy`hK$Bo7#K=(mzsP@FD$Ay-yF)|CEK8?Ax{OVxvczMnyf5 z{=3G&w6=rBK#i(dl++lgrwX`6BcYyADY}Ew_0)Rvaf)JbSl(OI7joIRk;}djR&vCW zke*%dgcY8BcD)mMIMB1J_sNHhY=HGnWC^TiR~yR->Dl#8^rdJ$dlCB-dNaO#Cq5xP zyWR;NlkKy+#AN56t|Qf_YE}JCwVec2+iC^5K=s_5g!Ef#DQT|?s#$qc(0kLfsAcK5 z^4nk06B#J}6?vhH+oRrn+)`zcC+`Ak#cJKEA+>9@dexj-mujmd|5ZIhy+SpuzLNe@ zw%Vs^y%^7_9;V)=7NdTa{{Fc7pL(aP*VQiz+GkY1Rqs`=Ri7@%f7O$!U8<+3zSLgz z6zTdD*MC;Mr&~^3@44)?s@Xi;QCBA+)vVr(Jd>zZ>z%L@Ag($s0IH@{r?D-s-nnWy zC#1KnTE<%|an)>LP&MuIoT}frX4Uf3^(+51Cu_Di|5G)sfB5ej6aHV1nek|;o}L~v z)tde~W@@xNIdbaV{Ks|r=YIV^@m%pNpn6Qt1!}D)X92Ziwd?=eToBI!ni0~^rQUP$ ziT*klsGqA%s2#*!$uttE2dS5-#i;M7ucQbZ4^m%KyHpR-$fUNb z7Oc@jZCO1?BbnN|TD;o6`ha?Z`kMNLdX&b(f9II4WBN53p;Os(m^G6tqcKh4S-4gb{`C@XV~&}t`|-(|V4Szk|*6V$9< zl5jk)p49MBs%BudIL*D9nbqPnCu_!5i_=`KnOrSSbGT-BwK&b~g=i^iahmhBB2c^2 zT0koWc|gz_K`RKgJFOkGve3+`HHB6jnsK$((73F2r!|OXc8v*|@%0q3ZlwH)Xx`Uo zsVCCBucuSWU+4GqO#kP3;Z&^C(7rdV>NMMHe$qNm^Ssu5>3Lu4L9Gil&&RWWJnw7$ z_@AHm|5f|ZyUl6e{C{n&7_SmFZ>kk&KGnRb)}g1+ys1{Br_gw-)}*JD_ri29CJ1nMK|J6b8IkErix1rd+Z^3bDEJ3UsX zM`^7>G-{{EYPErrBX&GWYfYn3``<8RRO9JAS9-Vg&+}}& z+tN-Uz30+;GrfLD&$jUltC2b$yESsF&i=Z7`16<$uMp$fzdQcM5>Rme_%{uy4 zK^E~p&jo+3>p!ReJIB>{f314cY^VK&b})J(?JqQ|>xnc@CLukM#!2mj^jvX&iF-=C zE={jUwUSWJ(c0oa+h5W>MdM|9MXLUi?kQ?dYEA!{xgf4b-AOA5y=krJwSv&S)l)TU zYs}VuP@}n4NcyK5<+V%H6KM3;np!Jv%?f%ZjS!kGv`f@%adIu8RYZD4q47}big-nF zaxI}%#K{#!KJKVK@?V<^;yECm0pd3F*Lfj+c1d=$rdNrR9&EHz*0byVYNxDc*A7ST zM9-eyDeKuauIZiV*|o3GJJGYJcgk8pslN42^z3Q}dMA=*rT55xULWe&)2qaItdML> zs{wgR)+q7!>^1bC(>soMuc0|#Ydq~R;vGjke`)2X9mikiulT?Hdt_pN9uxjL@1I;l z{<~yBn)}icA@yRd8??6h|B?m$JKxo*IClMcoKN>-y|X{3^YwY#FEr}rvn@3*Jt~`) znQdF9M%_G+<{*u_xgm|%^71QRfojXDJNXe;8&}tx z$_c99OEQoH)Oeutf`p@Ugao8jjm{T*NG(Cy10JNcjm{$sq_Ifn6zQ+Ql(#)w+5wV_ zOHQs6j4lvgG$$V<<$wbwWk?v z3AaP0uhWb+P+O<9J=HK6)rV&FI{z z74;a`nrfzQ*o`GtgoijmTF41)&$f^Qe11QDV;azwCR7oe`V_H)T*z{ zcz9}!hnf1y)K_M`q4_Jb-uUmV4>RkHlk54+`taYsKFrKtnfWU-fBk*)SEhfRTKy}t zUp}?=%bEH*wdyM~9-dm`VWz$^^_5v4{(bAi%=~p~&0m@NI<@L6Gk;~~ugv`Q_sw6K z{&i~gugv^)YRzAn`Z~4hD>ELRTH|4+zB2WdSs(s=>%+|ab!yFDnff}l>MJvUW#+HU z{Pp+EUzz@OYW1(o{B>&0Uzz$kwdyM~9-dm`VWz$^^_5v4{(bAi%=~p~&0m@NI<@L6 zGk^Vk^H*hSQD52G(^tXT-o?*>iyeJcd?gsr5I+q|eGl}ASHri05BkKbW5b^S6U1u} zmUn6SWvFRAHPp1e0BVv_13USE)Y{flKyAXcu#%U@2YqL-HrDd;1X0)ehNw%Z4wmz| zh}XwwL@qEF@dkL2$PMa?h7Iv9kq68}T)wsQf_be4y*vfUzqTyt@?6mjYKn!vJXbWwLq#Dlo75JBn`6f>&lN497TEa9TSY6VCAR+ZR?!-2h0g|g zt7v2W9<(9U8jk@bh_|!e584rKiw6jKt7s3k!zV;3LLIEnijJWCmCJKQCs2OO<+-Ah z^;yvw?1X27a`-OjVm((>1iRqvAoj5BQdj@e^`$zBYfUwkMg7R9LoGsat^LRKm9D8I z^^^P;^`)9RS!*ZjOEq<})=t)!YU*UI{m1o{uBk%Qk7}xgtv}V;$@)@FovgK!^_8xv z;?z&^Kh>9N>SV3`wZ1yono@mr_)C3trq<+-UY;_-}w9Fy&3sN<~$|Szy7}dm6^XX^H-*SW%^gF50E*p z%&a#u>y6BKm>CZ<<6*4NmRTQW)`yw#@b4QBGwY4adLz@n{=WW|nZGjgSEheu`d4N> zpRrHT*EvsGI%MoqGWIDMd!pF#E2A%((HD)a_A>fW8U3jLN&Tpdd?O>@$n3u|`>)LY zD|4O_@4x;odDN(c=UkPz8XT3lGI14rG<0?13Sypfjg4PU%yY)r_+^R9;n&*ubv9(2 z%izWtlo*^a&fvr);3bJ6;E=>naA;x}I4m(79GgmV3lkmT7bZHu zg%>6UCfdV=0}~g47xC}g!G#y|6m8+gX_IIRwobGGt0np*`X;JDrzNTrt_JpoS0$w% z*e}r^JdIcl(yN0#6TQG*#Hx_fAMBqPkf=#|4bXFXCMuIQ0348LoTx=g%|s<)jT05& z!p4avi3(6tup+!Xp=MySM02nLv2yU{iL!8E^F#}* zNBv{Iut=gPSTs>Aal}9B7fT%Wk60|0D4savANGaC6D1M{{X@R61W$O-FUd1*_wy#U z`P=>6i9Ctzex5|$#J7aE`&<2O5qW#!S5$+1-Qar>E8!E1Ktmx&GWqnzDK#)JoUT&z2waW=lair_Yu1X{;YpD zT==a2oIevTe9nK~p8*#>@6Yq6!-ezw`TjJxaK695zY8v0;J*OAz_U$-zvz$gpY*Q* zpMZ}hBz)3;%D7PaFZQyPGIIst?-jwO(cPBQ^@59sF2;N9)AD;0B|4jcve;_yxekP^H z`Q6|H{WGA8z;5uagf0fpfS*oi5ZD#oh0tK|ba-d@U~sU1iQfq>yu=>@4)KTj9pOX$ z4$v^LBfOU1-yZ-D@XrO$^=taINvY-6AbcKpo_{`AlUQ~5`FA7%emlP$)E+DkFH5KcSPmZfjr_)7V?Xqhgd?yaJRsf} zZ0tAjv*5xeep5dexk<1AJSS;Q!KQvQKQ}44!20k!U~bTJ>Vfr$<)BnEu$f=PPe4V% zqJA+j2QeRB3@qjs_dTct=)(=X1X#i^>AUcfz5^GQ^h<%I{L=n$&jF8l$30 zJLU~a z&U5_){!Dy1&-%0X7NtJ%mcWIdcx%D6-lyK1aN(!kXWkp|&%D>+!q2?Vy~S|h=iWMR z5wsp$41bN#7vLA(25=FvSK%AHg>c~po^ZCe()$?v*qh}&0^`S@P7EcgkA(+^j-q*BX$q`CGT$NW$+&OO!&*-%ib&A z3}_)Z6Mnrn$9o360e&6)8Soizu6LvNG$}ViH+a{QHW!@hJ?q`%Jw?t<(2d?0(w+sM z^`7%?_MRl?X6PpG7M|uw&~u&upCt7fN<9ZY=iLt8?oIYa!zX)J!-bQ*Dc&f!aEf<_ zca?XiHx(RZ!*>w7lGs%53b=5pcb9iLG!480ei@Z z_qxJ`!@WzvOT7`^>F^O=7r1Z)PgvKxz`M|^2iEoK5E=*$^ezJH601*oJ@9;ZZPG6C z8W64zo(Hc*+C|_+-o;)+?_AOvLJho{q+JYN?6vk9k=_s-0B^+84e)A^+6Jr%uTH2f zSOZ>-P&=?X{4_%C!D{fT@b+MPuY*?wF6`iS^eV%J9lcIoC8#r48D5c47qAjMx7W;T z4mS5%czFot_Hscjz!qLhFR#~>w7gIrFG*TUFCQs+!6xvCw3c8?ua%dd|K1pEOiq3% zpI3mC{GjJF@d9Q+J;1xUJ{^THif*x zU}4JrV16{kykAK9+5BR%y+Ypi#EXMJz;}`Ii`iugcm)X;^s>EQjpq~q3lRU#6!#8* z-@|v91LmOFLF|C}me3(^2YfsH5O~NO1`nGfW*hv7*$N#6x52l-kAg?dG4l;{96W9u z?;FyNna#u;?`ycw;R!!5d(0o^186U}oY?#Dz2IK6&wOZpH@m^zq<;u4H}8?N&wNDs zhv0AUcZu%@--E9p_?7wEJYiOwHQ*ZaiFq6@ z{KTv^kHOcPC(SDIpM;(;PnnO2Jq0~!9wqNn@G|e963Q9)iDY9)t^DHm{fm;KEnTLU5sZ)%*kgs<|I7 zeAT>W?t=?oGmFfvDTxfvlOX?JGin#;qN9;VxoC}VJ_aW^Lb3WnoOm8#P3A^6HS*!PJHeJD8597F^iTbTT#J!cL~MsR0*u zHeJ9j=5$jXe!8g!7oKjqn$w^&z-sWSgt~#J!SkEerj028<_BAvR$wb)`G~hM1xYDj z@)BzUwlQr@HYo+c7VtczwFTRncBT+1*cZqnL;?MxX{n3O_bGk7lIWx?F=B)lwG z)|4|5Tv*POHz8C3jNk#h0$9OR1S^_KCJSE4Ke1&_!J?O3kSAhH6{osCL9}z$3eoV?r z_d`O5z>naoNckB2!`%z+CAOTr!{CST)ugX-KOnvVTn=AD%4%>A{C(0kfE(P6;6`_o z`yO1l$^FuO7yhNY3@-fA{mNYm7k=e_4SwxzcHe<-cHf2zH@n}sZ$VqYx8X|&Z3W+g zKka_ze(ufzpLU-jv<`e4{tPK|z)#^%lC}<9=dO3>lJX3=7XAcj>%sNz7w)s9%mqJz zKkmNbE(D(-{c-3O_c_v^1=qkIBW7ry2$a%aJXi`>QTBk;xU z!_e#CBk+d^y#YQ9e~{3d;6v~S2rU60gpYFKIc9UK2Pjs@}`5gz$cMD(Y=Y-ba1*m!@UtM zoZ-%NZ-5JDx_7(RL-&C9xc7oL5W5b3uX`ESpSO;Ewa=FABDX=O?Wb*vYK`R&Xo2 z#d)&UU~5X`BdwyF7cQ*mR&w*eg_YdOZf>}+vRehL;#PHY!K=DSxUi~w8hDyp&5hvI z+z>9T=2i!*^Hc%6hP%fp$<;?@3=n` zG@x-k@E2k~u^9KkpW!>5pB&%)(b;LycN6Xp&X0~T;pT9^cYbh$IozCJPB+W_&iUTS za(6i2SpC{!xa6Nn; z_&m4{{tP8Hft#E!!MVidz`u0nJD-z3ADZVpO?(kJ2fl!3`W*b6yr)Q81TJzGJ5R!e zi=EfO*PS<2|gLT9efc!p1jw<3Gi|7*PJP&PX-q_ zFMux)yMyo)=Qi?R17CCQamGUTg15nMh2IO_>)hwu0vF!r-0$2B{R8}m^8k1Yv76uz zI5)zD4>%8k4>}JyH$V@AH^Q%nKkQrw7e36hUF=MEE&}gzrh(Il4J0m{?#yrok$$l= z7#svng)%p)0}j;pY;% z3Oo-!fY2!LTzG#%SAzrK{RoW)M?2Sm{fYG@GzRPk?*kv>^o9$^IM+J8;KFNpwwBJN z&IoXXGZJh?thF=D84eD&;Y&$tLC#40$`2#8IibtI7Vx&tP}15$ZTQZ>WzOYbb9hri zXMkro-N0tVn!vm9)q*A#yE$j#C%>`9Go9{y<)D$p?#@|+&vJU;UB4k%A1>_SoDH7s zoP$sP`e0qS@EoTnUn%H>xBB9syyF)mT-1JJpeTOoPe&`f179L2VZTODf-=SNh~I&D z5lWp7p6+zz%L7Ar4#(NUYRGZsu%mJ)Q<9Vg)P}}9J8^*7`UI5&&Y8|okRLi zp5JjUX1sR@wIke)Zz4GMy9f@~4^$h@@uVlDT4loDas$D1x%;Gx>E);?x-@b66B$(u@7cP_=>_yvi z3FQH6@x2Tessq-cUS0AY0Udt9rH*@nb>S|hYk})H5q6yyIX`usshlvn&M;2mT&Dx) zR<2W)^BvbY>XijIa$ev%3z4Y1&J5(wt}_w|t?P6_lIc1Xk^3>hAsKU>uQh==i;=Xr z&b`PbT<1!5@vhU2J+JFjWuM5Cva52Pt!@Hb!iwE>9$+y{mPoji~LYmE@=O zsAZ`Q6}0bOHJ}zz%eD&DTP@n0+M`-twyne3wp|voHCe~DT(#dSlsTQ2tX>!Qzplj8 zOVwlJzS{+^{;XbIjNaPO_Suev(mh$dSAAIhvpqcB-{QU(j~p67G>*jM%2|vqXWNlP zqeufrjgw=EMxREh(Ws{#ReJKT>)Ezem$B+hMyYt*(pc7n5lthR+G9^fwRmjPNEeTN zm!-zPcyzpsF;b(dP$OtO&R&`tWm`Gv5muwB##W8F@n|xXcs#bYNsUdT?O3icUZeZy z6QlnqI|E!p?r1ySYt+|xAI}q4*}39cJN92|$NzXPxzf%j*V$P>y-T(h4hHZ^i4cx9mDAUX#6U*JW?p6<2z- zrS(_5Zj0A(@7VR1R(4w7Eru`U$!39Ck1eHUA7LdJuLtARqE?6T3Nl_zZnSGjtw6Q* z)EZRlQLRej^=Wz~`n+9(3gh+Yyc6qAtup5`zs=_f;9v5$DsW{yk}U=ZXw=Ftg$->?JVM*L%f&J{$VY91ML&EOZd$06V}>2!)GV< zF$wp_)Xv6p<6VyL?qm<6olOq%5_UiIOKL}y)773v` z>Fu?H%&+-hk_JgPB;$~@ zL$VM_K_m?sW~C#Nq%=m35=&DgTalba(iTZoBzb9SWh>2*r%1LUsY>&d3?-JcNNytO z$sqU@DH)GsJ+buX@{|NfG9gKQdV!MpNKVujNlz^Mku)flB1xXqFC_=M+RB0?b?TRr zHjS|Ir_oj}6w8OS(&=HPQL*$&C~1~tUP8&YVo8`JVv>u+aI#4pYv~2Hg((g}6@5aE>^1qo#{$lCf zKdb~#l0nG_B`MU}O)EIb^B%A=y;z?3a!RHc%N<`v`Y4H{@YWL&%onT_QgHkvU5Sot8>}dO`+02f1=u?);3EGS3Aiah6P3DEac&R`M+=xFq6VTlsh_ zDgTPFw6gYCQohAX%VR0LdRm=+vc@iBD#9LKC0gl(c6!C5%pZbl&qz>g=bu z+2#If&wGTwx;p#$%}t;5=tL)dx>J}_oZXz|?B)q|;-qsYojK_|N+(e|k8Pp-;SM(0tL?1`4nwQ_OBRhImuJ(bdVl+LND*t4oKz!8Nnza9!-#pw0<(X4oZlf~a%En)XCdXN)>O)G4CQ4?B`mn=?b5BI*oMCz0`) zq|PVf6U8&^siMv=>#|?esbYM(sJ&xV&N+3$sZ-Co<`R4Isq@i#CO#`2oH{9uPg4hT zrg||HpSCtM7ZGa&HnQiejZd7U>fBVPr#f4`fKYsH+LY7XvpM6{Nw3a(<1=2J_r@o| zI_cGUZ+G}`($2A`#5yzX$%(N}fGjIvLgpbT3fn%<(C-_Q%>K>wH)z z(>j;#bK*Q(C)+yHo{~EM)+u;D&ci3cg*qdjXwShX64JT2PQGdSfUaJu@3!G)OLuOmu zkk2eWYBfhb1wVn(8YgS42Fe<%gCdO+>77V7CDuWa-ifqNp0b)Ht4?T{NV8-PnlI9S zkrvDbP?|4a5R#V6TUJL#S~Jp%k#>x9Vb+uL4jM6U5SO0KJK#H3=VmDyH`15+5_}yl zU7TgeZ=^HxHBa_B8am6Yo{ltnVy&HhDXpLVaA^g-kG7Dsgrqa{K3YMs-q3QZAtYU* zSX(I85c(Z`pcN@CqF5j3H)1QSR?tecl(wR^bku4t9k$v`hpkrAF{{UP%<3{p<4Jl? z(t(OKpQO{Y1+6A&G)X&Zhmn5MaWK|w+D!fdQl&p7jjC9i%C#C#u{M@;tzzA*AFLLa zP}*D4>XL@nPV~KspyRdEYJExf>nD@e^vXuB>t}Sien!WupeK#4g6MMnlG5vvF4wOn z);N={S(%g;T4}3^Ru1hl-%D$sCA_let4Uj}l+{<04q7?1*`&)B>$Fu!>7z+EEv@wy zq6b&P>b+I8T51*1;xbk%PWo|?)u(G^F`3f9%Vjn5gt@G)UT&+UCyl+PRx7V5acSx0 zP3h$2^Q3_%%y&X3FV@5BVD$t$SY5$(Da}D?5O%aWgB`8jVB3^-p|lJ;d6miOWOWGJ zq%;s~pp)3f>LYe0R~m&CJ!uhEBG#ImnpUr{v(;^shGT0|r2i-_$cy0vt&XHLDC=4s z%Gy?+QW}!Cjx>rkF=wJXmf)&T9u2Ixt~x{~KwEy@8_V{)j~=#+Nn z(3HlfbU(XWP0wNA8RT3-PIs_7nxWG4JOh;G=U}TjDjm`uCv-oh2Rg{=mJYI-r-LZf z1LwCfV5JW$-PrNqZ6~x~`=Hs{H>LmD z*Xp_U1N)uOe3fqN0JLwfwA#4R(!C?4rF$p*E~}q=m(|ft>+@cXhVK+gjY20^n!3|c z`ni`Alh*HOtG7E1o#4?{Gx!=bg>NTkwAJLD4vyps=?%wv#=Bvh{{#AHd2mdXrk1s9!jaFxVBhUA0N}E5{?BAWz>wm{;{qF{2`vBPt zEX5{ZS;}T$85RQXT04RF(Es0MZ3ljVzi%x8gzsYo@Y4xPfDf$I!e(p~zOt4IvS8S6 ztr_+c+H5Tt4yLRfWcRQItA(#lSTpP;M-~xVu#GrkEgFubtQj^D`@`B!{E@Ps*oH-g zY#okR`wH1(Y`4}JvdYM|HXGU2Zlj>J^^aneQkHNTYyBcim>kw7CMPyDvWm%Jt!QLplVz=Kn!;s&BP*OH z@J8?u46)E@Xzg?wrfhYRDQlcu*xBStS>WWdRyVo9+*shWvGzf2tesFRtb}AWR0;c` zw$@gtt+g3yXKjVrr7VQX6HD70Rk5~5ttj7uw5ryMs2y0AvK_$oDLW-uETyfOF0htN z=UdyS^R4~UdDc4WJnW#Vr|hQAwN_IDu$+o*t7=-SD%n;IAf+GHQ?VsgZLFl~SnH{} zJWpS1Kh?)tPYp_0be)ckm#n)6S&Of(SaWqIc8Rs~8e%QHhFH5U*?4tMS%_VfvJyMP z+KpWV%JyrBwf*X7ZNG;47h+M?4eWNp>TH~~Ji86sv+mffbw6RlHr86O-D+*!(l&5o ziQR%7T-rKLws1YI{hP2SmTos%i#XZ5^~Tz*cgp6icgh-XvbDxbTj|}7ecqIm9o`6X zrdS(2S>{bi+4D`rj_-0T{jNA+?{}xQ*t^qO?WHXOud>#GvI(5ZQw|4*W5YKGJHb)b z!caKM+8kbOtq(_It@spaS6h3d9gZsL*&HWhMWvzI3S?k_i z*z3MwEq<3^8@wcCA-u#|49jl#Z7hO+vX;ZL4VH!QPjFcR%N|%Z!#}{6`QJmaJ@7It zl{Z>@cGR+|mSy$k6E@iSQ+C)}{H@kPd#knN-ezsNw^|$TZQwS4yS4QG zHf8&r3+wK0vGM-a-;uKSmR{QOV_)A|;m7v*^|7>1BxI$Z6FYp_>DRTk`gP!0*ym@Ru+^6}zHIWt6L$D% zKLO+hh7^?V>72mP#nguW>s3G$fG2X6_nSB2B?kx(rm ze+t#{jnLbASLg+o4}}^Dc}$Qeg@M+8!$9l9;R5T?;R5T~;UeqF;Ueq5;UauEbg*6= zF2WN;r<6a4P6=bR7Yuq4vXz(4gK-X0AI54#n3Ru)HrC%mTkHE_F*{^qH6@JIjxbi6 zLcSAPbCvWW@P@(YVyvcwv@I4>Ub+^>>QRuwUdLE13*)r2UL~YiVVsh@v-7O43VE&Q zV!dWuY`ty_!m~w}l(&m6)&s|2JYJkjihN*nwca=`v0gFc8{-UoX536pSL>f+i1nS( z&3fq=YQ1d8*G4zIZpdTDFg$RanexhUruE)29IqSQQ@%O6TTdRBT2CBjfoI{BLtZ^b z;MGIEJz{ST@=qZz6+Ntn4*5Qi4-R?aIENaFJ$iU}5Ro5|%dCHq%dN+ep46b{Twy(t zTxoriT$PZ&l2O)Q$<+yYDjA)SkCJN=@=h`)A-^Qo@;^MQMdWeHxBwj^=?Hn8#q9^B z3*=dyBF}0Kc~<+#vsy!*)l>4U?vUq5o5-_TL!Q+m@~r-nG?wP1ESF-tELok&_H2MB zn>twxde%--_McA>mc6U2d1ccpyJcBr%QpK4Ykw{qdk?Px@*VI!Bjit!adt*OgFi(- zMmym@z>V_@^mFum^aFgCjekeXIKSHXZ#J|e`VRhWv;(|3+8S+(ZUJwOZX&cD+#Y=k z-c0P)XbU;FLbpUWlJ+h5Emw_=z9DBUbZc}2X~wyYl(Erm(PsGdq#0*i^i}kAG!EJf zZYFO$DdVE+$T!Y}=u2V~pz+bfXcMuC(1d7Gv?1CEZX|6IG%>oJlu6O#=nME{==Lao zG&;H_%AMR3{Q>?F?TreMl0V8rO73LA=xSmGp#o7p%8dcXMAw4(iRDfH9_=rQCI3K6rLCiaTXP1*3dil{cBB?7pZ_bQL*;pzJ6QWv>IT(x;R*c-D;7EARWLENvs5s$bQ3_Sgb0nVtACKmQVf1u3Ck&!6dXkhUKqjx`W4!Mv(PNa&K{zM(e2m|l z4CYAYOg=;TIpH&5Run`}g->&jr=Tc$l>8~tQ{3T6&`ZKePDW4isJXzWh|T4yXTrH* z&L}H-nlev;Cg~+-bLAb;Z0<27dLn!>%oROLnYrP!VU8$gG>g2U;B5Gu$W5B$9Ikpg zdYp2(!Q8yz$HOOxJxBRx!{?Zqazu}C#ZYi)G%R|CtLA`C(oH^3?sMVuY-keE+~_!I zbD?LVhbcP@92O0a=8^k+IFExDkFXc{(X-Jp%03ItjUJ-ZaBw(pbUtO~h0l@uZ1h}o zBsvNnCANU{`QZXo@La-fWTNMz!{k2?Jr}(|`hsvCDbGhQ5`H0kF+2`GKYS#d6*i0> zh#rjUB?~8uBrhQ4{IG7a9^po$H;gVM<%00S@L~9Qym%G)0ih@Ox#gg^;t$JW~vJhB^*ty(wc6cuIXgDx@FnkDn zh~FFtT^Kfr?&sH!UtHsB8RlNV8bU^sxQ9|a!`9}DYIqI6UbIzqTU zv8K^|+@mSfB&wCH&9$|l;>m{Gp#fMB-k+-<3;TzUhsNno=<)Dk?tBsW0K6G@Xc{$( z?uFOo-bcck+@pB1CUhVgM45}jLE%5(b;v&g9tn?z&7*s`qB+zoszJGf;KAq+Sd-Xb z$`1+$hxdi|gZC3_5#7xdEuiL6?Wj(4G^`CB3#%t& zM6IG>KF>A}td=|s&Wq-Q9}vstsy<;hSN0Bzggv=a5vXwZG51*s zR*z~#AJO(-3P0iehbHbufPp~KVD#+dY zg4ys7x%#DW75DrYtQJ*|-sQUa;QVMoRDg2*!U9l#upqG&-1(zuMN}zSIa!Q57Y$c) z)he)RbXv4JJT0mgE$5Cehs&Yq;D^LkQhr6WGOC!Ylw20w8BL9r@e2#U1;p}m@BU$a z$T-Er9^AD!R4iP>Jy(YxaF6NXQm(lxTFMnuqmQ}IO0Yt*VzLC~i-#q`v*4eERidiV zCtS5Ae4p#4gVVzq;EZr)xQg;0N2{Xp$qLDLxYJ!x$?(judsq@W3p|UvyhquY;o7iL zR5@B3R*tHGRk-8Zl%5v79lZlz%^g;O<&x!-rMN@M@KegK1uI6CqIbh#;qdTX+TJkm zJ?{1{baz-fJR|G|cH@fDP^oZDR5n>IxrY0!jy~hsPs3%D9S#l;FAYB-cTMz3R61EE z`AJkJSvFaQJCqJT56edtqR+z$QAMyKS1#p>OTkOS&f!|hb7k0-vSpz%;X2BH9==0f z7jP;3Q_8H3KBZ5TN`4xZN|sKR3s2{Ya!}duZAx_kyO8!aR4)9ClAlIz5i1wI1(gq9 zAmy`Y39<5_6D|Q?B;|!@K(r)!E9wsyzQy}m6XXhWhiih|;p*UAatB1`MsGxKf^QP* z$2)BUz76k3s4du^*ec5B30DQH;h%7aHNhuL?YY9f|@Oh9G2H`+bE{q07 zuff*^Il`Rbx*%tm1!jex2R*sIT-1|$l#R|IR37XJzlib!!G+PQ;H$*ebM3m|Vp1-O zzF_;9Bm9Dt^}!%gE{+C8ufR71Ug(D#5IrWq1SJMXFGVj$gP~WzS17lUG8=+RNFN++ z3f$0yn^2VSKrh@F4598`jD|!nl0O8xB>Ivvn}YVF4~ZrQ?*|_QyTV_?9?>r7Z18OU z@g&kG1{0tUzz>4u;PT+Z;P&7>a&Ctv1;2#5!gHcupz>h(XkGXlclZ_T9-S5a7M>OL zh{ki>hrxL0qhK=E-VQDc-UZ(!_H+0PE%;|>efT?9{T7a+>_@>A%1jP^B4>U06ZA#6 zJ3KS$9_^;g@8KQ6Qu6PBrUbVI<0yX{v?AC^*)PJK&@15{%I^lxh`L34!fw%-(Vf9N zTz4mQNAM#h7KT4UuYx;?{Xxk+;Z(}p8B7h{3f>0aCbl>18l4gCCHIf;2g<%0-W4n% z|1M~1@I7g-hTlW4h5IPE7d$=c8cn0jUBQ0B`@;QU=cr4xKkO2n9!(G42;K~)LrcIV z!L;B2x%qbI=NE8H^`=TsS`54j)Uo@4)Z)_hX^g z!WNXdC1^ppn}gQDja=6nY86bN{P^%zN-P4$!kbg>)}T2w7HmPRO>hHOw1HX&w@_+P zcnh>RoEUE7>WR>Vuo-2?25p1uDccrm6HFp^VmK+>5^e>z61$meUI%Z1w+pVLY&)oJ z&@^bqwN0Vhf}1GuMtBpYUJq~Q+DT#i;9APIhuQ^`!*58N4BZ~yNU1l%4#61mJ3#Hh zYluyu%;a!N_;t7$+)S(^=^cVQNSP9LBHS_P6pV)78Gc3DozNX&XHq%^orA04Q^QT+ zm*G_CEAT5y+(pXNa9X$#J`K7n96{}D05=jJLH%qD_hmH*8V1e6>%!~9reQO1KPmgN z_GUE<8U=f^8U>BPeZ&rA)eGu_^@9drgJ6GF^KeXfZP*;T4!n-5n{bco!Rx~t!h@7Q zko5<5Y8*7?x!(vIlX@fA1m1#cn}>VIYZC0qYQlTmL)pf`A+9=@bttP&P?vDspkC03 zE8h$oK}*2K#9D^eaCJ+lMYua_Pgc|5Fy#+rHKc?SHl);&uoY!mf}`O_vT6mjgCkkB zgF0XxO1BQLCZ{#jDr~?N4(Nm~=!RbgN3&`MwZK}GZbQk|VViIiyif9K-gTekRlz85 z6mPwEvUAV{>=K*~o*r}sy9QOjKI9zZK1Z|KhF5WQTc}OgH+gq(MbMW!^hx$jUJ+bL z_{!j_pjWa=P!+5ioCcm2R0DgH)-JpvyfSPDT?JmnUD}hNS(E?Nk!w4I9mC7uoxqOZNO%QW#7J-? z@d~t)5n=!2qF`~*Ke?D5-=F*UOP<5Mk7b<$9S4tN!gNj&g=NqUOfVq%Wv~cbMCr4W zTe7xhot@m8wGBKcX@avM5A=d9S$l%oVV!VKP$#S#?hfjP^}s#w1zEeY=4UO)`UU=b zusf(1{z1t-!8}rTWzBn!{z2yE8>{0aVR@LNzn{55DmUH=+<$v^&;c!Tgc%Ko0UkGt&+_60S=TH#AsJGtVe z|3lMV2U<~eeH@>2=1iS)=tjD`1OyT3?(XhJL>d$c6%Zv9l62%&+s;`+tz{ z1b3O)!1a261HZ-%;tlQ|Q~xM<9ORAWi#{Pf4xR*gqIshmsoCH^<@!nRG{_ar9eo<) zj^>Fz<2*`nE_b>dt6t$v;OR(~6Dn?Idcm$?-dsjDY*mdOZ^UvWqx;7yAkJ;zYVVQq;DDD z1dD?uLF@Rc;2LwQ7~cl%*|E%T&sgsFpuRhC9=UeBPJB9Xy8jjNEB|Za*ZvIR41cD- zh$ppl+UHH_84f?#3LCf=Kx zUVd+XmOq;~o4d8aWvbRP)&zZ+@9nP(eh)4M>ll}bmsy+7?l$rD!9`ZqGu8!tsqEwT z<##sA-w<42WdmbpR%uVI%T@#T1I<6tKW>Otc)yvYxcB@w+`4H?-I-m zW(8dsvx&3W*_D|tL93v3&@P_MZ_2)GjI4fkzX^BQ8QJ`nthbAI3uaK;jnOrz5wGXh z_iMy!l5_Zt{Kmw_?8w2$?zf=2eY{1`lH5J`ntk0F-GZD{=J0z2(}S;q9*nPvU$fRc zXc4rJ=kgo)4gFku6qYHiG7Gu$<^a|{JehkcwXNp*5IyMyn5Ux`hMW2 z4PFa6#7}!E{Zrm)FNL4dPZOkNCLQCoARWI0T{j7ua@~}>U%ljh3jbFsPkX<3r`Y!k zBNZ`~pW07PWx60Wd&|aC2WiMBsY>nt<|Xr!6O*$u73*c=8G^>tW?-ZbPEe7?KjEd} zGkU^1$=w<1fAh|GN&RGg${-c>$GsC?T0djZFlZEHWHcr=X8&0)iJ#OzOXV3a6RR16 zOhE&3iXbJs&arydJLe_#llYmL&lDtQwp=_p>t*BTy+nRu|2(VbykxADi)RVyQJaO2mzde|@x(zA@+B&N_b&16*tnmAn(V=4{(2YlFEew=%gIcR zAZJjEe8uCheEtJfVSY040Qo2OSB(GU|4cqj%_;vh z-$qXmoc0q034>p`KJ6dzfATBFr&2$~o9gW+e?go|{L$M-+{fKvsw&2RqyAU_H=l3U z2VZ)7S^tvpg?Gq5%<38DfAi1q*XURXv>E3x}&iUtkJ`KUw-Y!!F~R?s>dNtt{ZGghss7lj$c~S^YThVzRAW^2 zKBB5}e4_s&`zA6z^(#>KiC2NzkG<;NhtyVQRP)L+JC0a^Jl6k+T{XOstk+;v_dfIY z@{G?I6a6u)Rf&)B$C5v1{xkn`e-F8)_W?UE{KRbp2~|C#&TE#p07l=VVhDRzVymRH6v>sO6erlyi# z*&jiE>X!A&c~9ME;X;+y0r?o+oMu^gYdxBW8gdYe%#ZhIwJw;5rt3Qwr)SMi6F zOZ#v0-+C4>i!UN zbw)McrPA?gFjL*H;Scf$69;qWdBs@q7_L{7`5M0O6=lw6cwQ}LYWlVO0scVZK<)zX zb=Cuh??t`BUJ+su=Aw+it4(DsKgN92tK+}NT^&YkKOdjB_lWOt|I{ntm-L@_Pd&ww z{+q-%{ZjrW_dj=|yUG2R{MdWqmGYla`P6&nz2TSeH?a1fyMgi0-Av6U;y>i)tUmMB zv+~eg&v@i+VSY350r`>lnCCoVyyZXiO7oF?=sogu{T3hDb?kWLu46nVK6anDTiyHY z+sfGDzTnBvy%%0_{|$dF>rdSOyer-h-hVvf3h@WNmb_&31+kc4+~4NjWA`@3R@d^2 z`o(;U@zVR3x*5d($lKk&soKui=I-EnJMmBVFXCU^h5Xmq7h+g`*e}9em=W^7qh^O| zGZXf0zmQ*;SeU!-ng7oH-n~nXFmL-2zaaSs_YQMEFur#kW+J}h7a;Fs{s(ubdzq+FUE>&4o)ZZF0v;wpEw+t*!5ZC^$own$w~cX&c#Dcb z%nx)2xeLkLy&J4=XKeEZGc(8?>@Fbh@UFA6gR$Kk!pvZIh&#`nPn^%)cdYL4hB7n6 z{ocFA-S>>|yqVrr?q)K+_j0hJ;>%my=<#2N{)1ABJUU$X{FFW^L-0Y05 z#2nn^ayzmw7bBo9E5<`Y{#|7qC{)ZN*AKMgjL-R{ME{+?LE0Via`ydvlrV z&v@4>?6zQ~Fr$$Bo;Qb;_Za=XB5re5iZBYh1H9R+3}C$Hz3w(+<#k38cOdfvyn)^< zazo-k;!JWDuf5m7%j&iD+7a7vmz9ylyWnJSGrAX@^lk=X2KRz<-nrmpbbohVbJG#i zx#@}NS<6gy2QM?DqnC~6WF@vCpQAdHdyah>-AnBH-N{5%M=v|8*}St(CO5Nt);UMM z?4)ti64Sb`5nrP^BOlqAm(j~aeMUagg^3->IlR{F&cVp;U18T{CnqyGyqsPu@)_r> zli5AP$l_*TN6gE>_`|(QMKkdbzxoVY8y2;#|PBJ$+F}eGPlb`u~UVg7Jxd1W0cZ-^vPC>5`cLf;*yxUF^ zH>rD@`CCq$&s!re&M4@eanpLQd1u`;URq*W?$5fZy)@o5=cMzCGmUY|`I3Cf`GTx? z$~jFu?fmLYr)HY-oBNuV&ilH=#JH_l=_Y^C; ziF5h7GMQ)m=1gXsac1zGuZhRV7pcGCUUXA{7$2sgAAs*rG3iFrU zD{f*hiFd_K;wAO2a(%_U>L&6MdvmFrs)gadWpPi)LeDvvpUbY z&dfFUhMT}k=-uG@y1T$Rz{&!~d}j~yH{3mL+)Ln1agVvj-O2706OX$m+}h5k&P3kc z`;>S3YH{@$u{OD`Gl99fj5^LF>Q1_o*muI6$`hs#e|C=&k8<}pD<|DAn3?L+?3eFnd$DMY9?cb+l-l}ysi47Gm1EhyIHKxbZ5Iil4mn!xy@N^ z=FD;TGB<}Y+ik&2bKZa*Ngl@MZLd3wF~_a$j&sMmHHg)TpO9VNPpxcvZB=rrF+1L^ z$$Sms$7F|<%DmxQnRi!x^De7Tz2{VQt5I2%F~P0nenf38Mol+j-f@kvqYCf)>dn=_ zyayYw*LSM$v3uRE!k$lwRmoMjYUb(<k3^6c7-T5e@G zv73Zgg(p;IBzEhtTAMhA9A5@r%RjaY5yHgZR}?-SqWE-CX#=;Eb!nHw|T$Zg^d zCpTd}7v|D3FM=oR&@_z%qJ z4SKy99-_K}8)8&+BkZz?W!$pFvfNp$R3uh(E4dEy5#rnA?L6rvZ|c8{Sk87v$l1x$ z^d|mO@-|jN&NfEa*~NS0Pk9UfDQhnsi|4%LYyNHLC7*#LuFKOLcPl%>&Tigye!{z` zPpI~ocU{jdO@86rcJ@0j*m2w0L(Oi^EIi~b{5__d*mKqnIL{dih%dPF-M851GdwqN z-*ih6OEDKPe0MK<_i+BP^FKynTu0rQTf!|#EXmz|=5?Cl z0jCD`GyaXlS&g{|nAsmmz;)bB;J!gV$hmzG_3+HH5f^ zypf$BI2+lwz!}EOP)-T0CU0Qw17`zcr1OLG56}34@x8Otx$it6K45Mq;|FIr^*UL! ziadfiocImrYDSn2WxJ@~>Fjp?cJ2}HakrbX%Xy!g5u8@~#++GNN#5i9Mb#e0Zf7so zdz_J++4+DzT`R~xI)5_vBV(`gAu}U654D`U&$-LWKE{vEC}wn4Y8iQ4QBoTBJOZ3*7JFG-)lLC#8c3}Os)ikTi{#n@Fe zGMIV29lwHHocUsrAEaT1pWvmZn4Bb3-UO5xw~O!=N#b;J4fWYotwEHPCiaBbR~9WH6J6dbB)!U=456L&R%BY z#Ni+8x?$(yd`J&Yko4eWLVkAXTu5i~RXZnL&aTppD<|hOvvLmcCcFNybMi4u#wnAY z3l3HK#nY(D$q$m9P45{vEl@ z$7T`%`^?Nq#_XJJ`I~r;uQ=Jcx)&)#eL>FGbR^%gGgE!X&cu1g!ps!nBu;xy zd=zGMbnY^Lhpt%}I30S|&d8b1BCHm6{$xfcY14B`^mS%*o~Ir8FJ^SkHXY|li!!6r zK04`A)buU=oB6-&V$2lftWX=%hqE>L4RfaC4bGJm=QL4E?vgX!-~?0_&hK1_WOlL; zvv99-%jY@4e4f*|mm-%VS)Hp9od&u}&6UX2NJb}6G>FoVEU)6TLIcsowc?E}Lgx;G?{h^IjLpH>kW$OwXyAuc^AsX^b=G{Pb^R zoe*2f`LLyY75Rgj8^m<<{anbo;02r>|CM}`nLjwarn6X!m|4gF3voY2|4~{^mL@CwE`7bjJ4 z+=-;O+H>MJz4a!if7A1{S03*PJGG^g;;F5ZbV*BX{lc%G+B(JW<4<DG+wdgbdbw^LfnIrE>=(z*YX*2j1NDXmY?0>0)P;91T=o-wB+btlXHVJA`LmiKi&8U z(~u6PuxC2wFwb%_^DJiuXHh>h(twJu@D#qHGg|{{r{f?@rnWhwnLW*%F`UMqj%DU- z=Q-js{(Ccxk^Ujw6mkM@V6f$5N=zv%ls%kko?~ zjLF2w{2E{KluXu_JTId)$DCN4!!u_`T2k4<{(_UGnXI{{hv{5a=a{ppnXGxt%#F-5 zeNJ1M{%EbJZ;4njk-OH6R`z^z7IZ!}^Egp^+?=F6MqWs_)CI(&%6QN`zL=UM&uFq-Z$#m|V%<0<%%+^L5k)e^mh#85Ep^=!% zM0P!@rf{Blk~!b3GrW>Y>Y|O*pehL?v0az5&{H@gJ(Yiwy5>A@Bf6$G%K+>{r@zSv#p!7KtRORSu^lsa2l-Xi2RK^hQf=x}GKHImv9D@y=p3HT_JR^0X$L zGapB%(`KgIX*1@VMp96p937@I&PfVmoz!GcR!e8dvsfvaPhr=f_h?qDIeVK$QrVT5 zOT|cOSLeKWR;z{SsoH|o=8@ENT!kL&}Nr z`^aWR>4lor+Q(mfexwgr1lwjGf8}#IVpENk7$X|li~i%4vdw-f_l0>iIFikZ zn^X32>SK`uVH*kO0IU0rE~Fn11k@y;CXPy=bN9Ph@$KD=fEdv8?I61jpa+p`5APtG zm5@pq29?RXaEqe$AyyC4kxMF$OGS3e#ZAb@IlaopHmF2C%<3UJcv;vv4w6E4D={)b zBKmVyBp+e^Fc#AbOrayj6^h_9WVe#AnwYMh708LK$H+s8@SGpxIK80GrXq)B<2huv zl2Vg|zM$pFKePH1($h1Xqn{Zs!u&%=a#+b&l{Zn2972%DVI}8UeMie6E+jX-S&yK{JOrHQ4v zPiP%Stx9OAqgg^!>f_-Ah~le>tC6nWN0b^t+(F)j@{!XT&i!{7UEd*1eZc(t#BCT; z9~g&fCn`uzYY$^LB1jIz>^<~X&0!5=$Mo=8sX2S&u& zOZ^_ikQa1h-OI2dL)oztA#5iS)rZuN41Z6*(TMdUHGAzLtn9)x+iH4~Z6WVt{zuMY zJ|};NVG^-MBUz0?J=;v)!Cb`JZ@QrFr)D1#%M*l=1Expn0p|DHW2hXBpSFp-oodJ0 zj*}9x#+trtV@)r%v8;{>Z^Kt{tb;t^fc+7xV^P@FleeO=IMyN4kM$6%2knoU{|K*b z9eE3ii(?%&y<87to;*f}d5jVB39BE6k1&7O^f`5`&D6QpPew!eiTNY;I3t#gqw*7s zxV5I^*&6cCrc3P4RQ^Q&Q8_3p89&>_P4BfgOuw}^xGo+ZYP;4DyO=TGig7;x53fHe z-eBfEYcK+jYYk%z#oXC!t~Zg38Xc}EoyZ2_6`Wz^`*k^;SKrL2WUMTFpf4*Q99f^+y}9+4^^cZZ-x8g5c$?fYCb?l zT1S4Hn$qD9xgLp|w3hrXeM^0-Ot=>-Wf*UV`*9yw{aEp>QKl>FC@Me1T3UrCG@7x7 zxCVWxEW65}CH5qjL;veZ?8*HYDo3L=eM>GM?#@biM!E1<(+74e^JDA^#s#dvYWeU- z%#X!>T1oE6_z114pB-4Q6XjREL;fpNz}S=da2Edx<;PaMi%qFm0A=xRs33;o-=TcQ zq|A%5SeTuGRg}H2qh9qT7ver@6~f30tYXX*#l7l7zC*XNLdcbQFcWMPe6J_k*P!0sle?vLZEdQnc zpU|78o9dg?l(he2_1{n_(|xs+>AqTu)i>>jSex0y4@23JGapj(U+67kcfCbrDfqx#G&SmE& z=C<nv*I~Oq*dqz@y9r5-$e(6YK znT}@fsL)+%WXR>PbJ`!U@<(V4Zs`@`71qZvMu+~uq|1j)7o)GiA6&((vDAzS-Jqjr z-1?Kf^5?SKIqdh1gZe(o?jQKLmyMNsiF}>91lD!5ySViim4Aju(DUmiO7BfN&V7sm z`w{VX@-?iy1lBdi8aj4nx7D{Zo1NXhNBkSJFN>X(>#TM*`xELvMj^gP9%tm)aa?~A zx=+nLJisjWePSj%v;82P+0J5*r)FGeys>P@o6c_ku=*f8ftm54Pl*$VXUYFE{|~BQ zMmv-JAMszb!3@}V4~hSw5vI2@*e8i{3DaTV%{OLXN~0X7BBn&R9!y@q{CsT1OXL*H z4#l}1Z1n3vBUE<9z&uaIQsXwJ$E1Fj4pi?_ zm7b9iylD{Hy{))?)nbl08ZL#{DrFtM7f_Q$<2+-*}`a? zEx2wTUTl=&CB((Z$iI?TSP4VR>EIMcN?&0mKu}+XrLUL}Nqw1>2qk?bt1FQ7V|eOI zja9sqy-PyPc;XEF)9L&QEg3Dsi+JuCB<8dHsaj;D zR#RhvHbq#SftEUrC$(a<3@=6YPaOJ&UvZ_?n)z0^s$Y_qFq*>?wRbsBUKVP?XQ>;a>r8SJt|}Pab!K=0zl({8(GzjN7chE;+VITQSgl`>SMjuO zku3rw`1!2&M1#(R_`8B9FAp{585Iy@E1>)~W~>OcWmlVUThlvrHM`XJ$w!NC#QF;2 z3bgEbJf#=07moQnp4v0ij{3IYcBcF4T;_UXZZ`_ABsN5-UBeSr(}_Wy#oANTF5Dgg zc1n0HGi&JD;L>+&4r+F9VsHK|tYc;^y&U*a1lJB7$~u@1upLbA*ADD$A70PuI;$h| z9m1W69f_ZjH}F5;k=#5v5BWHt+~{7lsO#60C2ViIx+o|Bwd z8}&B@qi(pg>F!vX%C|!0_??usO0b)~{0a-vVU}1)aJNVBbvQ%^D9t40YeI;tMO-hk z784g!6{0RF^SAgfEIobrzowM@Dk;L{d1g7QyfvF#iYL(Nhu_V&p+vaP-xxhV3o%P5 zD={nm65ci)Cg0|FRXUUkdAK$XN^PE1!J5T0Dlp2M?ksc|LX-YBl#sE?So{`h{#WcS z!+1NC0AqR;aTS7lYMzq{|GEZlb82HZSENVCEV|6h;)x}BUdSqDdNmX?JsgVhJc}L! z(|KN5Mj3je)?jBPc2%S^%?xr;dIN;%Nidy?a>(@4LnU|;y?w%~apdFp*sDWn*_DQ# ztJTSsO((L-?5$)vWYG}_J9~}kPY@>ZmpytPe1Upjo-vI$jptTjS7ob;>2X%YbTq3# zP5IDkJTom_UaO*5zh)%s;yg8ErDNtby24f=S7lcft0Mg`r_yI(D*GxjDujyBJtt(P zN4lwJ8UnEowC=Fc77KnYJwuO#Ts-n4ArH~~2+ur>?e21Q$n>N;WV*y0qKDu{I)W5n|8aUe z6fm;x8wJ+DW1PtbA$hLAjrVfIo>22gmp}KqP#OCmap^Lj6g) zvE&Wqqwg!hJyX7M~3o&;nPw14DCzRI+`;&>2`MjNG{*-kh zWTDre2=NGFn5X>8{Aqf?p>}F|GK0RH9QvCAxgHqGC63H*;-` z|KFA#06V$f$_+E?jg5hS6kD0qH?G$>(%JDSB>sc zomlNi+)Zx5uT;f!s;Eqd)$iERp3yGUhT7`%H>ysbsy3!qRcGouS)J)Iv)gKJdX+S1 zUllrGWD8}d@5T;xcVM&+wPr^ys|%H#i95;7sLD=fj_p)+WON9%G99s6(a|rL)s>nq z#2?7rh+T=_lbh0SBRhRKvWIdIbA)oz^csboXj*I)F8&OH^K~ zD>Yr{JEFc5T}>y7W~}F@<5YfngY{%r58^gDL-sV?A)B&N!0JYQ*HAC!dz!ve1&9Uc z2-bvA$m-5&H#(hcB&+{mA$m-yV^|NmK=ER@K$?4Be0ZV&x3I zZtBz3Q+6vnmlAxT}?OBL+P&RuymL8&2;~%OE;HC)I6k{>0P>I zK4#_-u@0SJZkz6zw^`Xr-=I37$Hdz7k9kUbLZ_jcbe(x>)uI>eGph!DYo9Uml&+*T zxOzc+POMIcnU_{I`rN+c`URb(ZqYIIBRUD)BHrSD4ENiJW65K<>P64Y8}t(Tm~oSM zle$ls`Iv51z34+WnyOybC~|LNZ@QF?qo2?X;tlFPG@ThgWTg-NsIIXxo-xjJ$*M`L zY1OhOm>x?LSRGFv&5_J}z^F|puPdy4%9uc}tq+)apHat}Xu6$FWc5=zfBjDX)6W=} ziI-U$K~)`M9s042Fuff=r{*&{dySw=+i=s{aS~mjey307?{p6v#$0{+WL{uyGGh`Q zzv|PoZK&z?IF$AJ))4L*(oJiKiR<|@WLXpV|0>ILFtg~C*^kwJbjGw8{fYgp_lWOV z1Be5xfy8rkl(M)QM6AX~-{SrPaS&a?EXELGReJweRz?21W$}BN!i;)!TBdKTWxBvw z?3v8WGrsCs{BG14E-CIx$T}D#jfSibaS}q-o1CK$S@${39kP~layDeO=L}}ZO3T^3 zkae6>T_I~6r-VXQc}|^#tS4@H;#%H>4_V!LcRFNc;l13Db;ij;oXq=yA*(v?oAG6s zHyFOcO7j$ zV(M*qlK&?~=Hc(6w$+jE7ueQHzMErP|L}bsY#+YUYFnfEuDWd<<~!?nKK#7Rwpz+` zv=;J{Slhb8&&h48C~u|M)-c{KvaLP5XJlJ(Zx68{?`YcAOy1VCt*g9gYg_qv$KAI2 zb4tOswsT&AZx|T+-Z^ z;Vz6Kr2BN(Lt$JY-KXa+j5MVC4BUmSqcI6Fa$qvWeD%$dyCE%IQFF*4$}NPLmv z62@rB$j&1%c`{ONvcylIyo9a8Tpux7PS*J9*a>D1#U$ZK3fMbwk9^@x>%SXKoQ zt=bsBMGnknqs%3bON`lK#25)NQePg&9>oe^VCBcAdd!tvtH-f?ap^Rzah;xUExAg@ zQ$B1cxi_thd$SD%M*@ztob7lwQgNi^>@fDtcgDkMj&LRsZ6)KGu|cGORL2Qr z$sP$~T}UO7Mp6+;MP7>B6{#w>mQO~AA&Wz+3$uLrE>LSocpONOb&}e;9{Tv)W z`8I!H*3`$Pk>DrC&t>f{Gk+q{G(f+R_;J>VA5uLef|Nlmdu5KvACpfeCsE#F;&>vw zMJbD)QhU}|A`(QTg_JW^SvkBi8A#t7|471=474&BjR}pkD6vug;)B>kqlrin`3*bd zELoDt1)_|S@;pN}Qd46dH6xcco|+uC$;M%ug4+0ROd?|(Ls5cb+$fFrF&C4>6URT} zslP=l@Qfz0kBxsKJLRI0-%2Aj{s&6}VX5t|TL=FUMI^EED@88GYTK)23caDe8CxH350LN zMl%0lRAylDm}Ol<0JW^^=%JQ%14-0E9=$=li8*RvlHMfVMkKXxNN*GGqLf-#q<4uD zF)b|8KZ$?G{vt}KvlvO^GCzNfRYW6^J0g`t^5<#1Pnn?d!Q_5rkI4#?F7^p4(kP`; zRx)yl#F9QJCjHo3o>3txS@bsyQHi25&18~E7?U9;he`I>I3rrhxttrT9F=_{!=!gq zLg^VJl*%QQL@KAHAI^%TlvC`!OT1&Wrn_Y6YEsj3#U!oe;8&``lX??-qn?cC*O_Z< zODUFfF)XE_j)|S-88V!1V=|RBii`A^ccYTujuCUma>b;k^h8aOq#{QpY<1-svyH7P zQB{U&86(L^r0H*Tn)eW%Btxxd+%)do(P%gJ$hMTBDdnb2R9@?OWL7z?8>qb*{mEE! zKcU{`j&;Yklx{i8IG5eXrHy+dU1tC~&LHweJSb^UH;oG=VM;da1uR&Juk!cu5asCg z;7K!Ln~WZ{i9I8u(q%6q$V!ft^HUlLQ1YHUz`QZpfcavwg9c&$NCJA_c(bx=S1@oT=MLjf^i}j*%NiDw zEK~wlXd7bC5N3wr%SjrNGgLe}n3*9lIV!oL&y1=fO(kbkYHLr#*52fF`Ojp)D}4{Vg4U6JAWeO(&Qsbk9o#E z8Jw?UZA!cCOYBEZ#Z~Iqf5xSeev==AvxsptpOIziri#75)RdB0*m#-G$^RPnMgmWP zs65_&n7gub|1pY=^qzuvk+L;kG7dy#|GtaYE1OsTk8~dyKJtP4$C4S#_dfFv(0__x z1W5#z94ssN9y9li@>3)#F?c{s3b6Fx0aVEJdFB7y!}lqM0wgOqNlebq-+=_+L9s-P z#6b9{MRPAn3W zxa-6wQS~D><&UV7%b8h0^kQyID$c54GAq(3_ZUHPFL@cO%ZVJLj!EFTj+!GUXNplK zrT5&x69*H_jsazIa!OY5F3D--FT8tqKuCT-y#6fI1t1FBPbTg1hyx54t(bzJh z1xW|G704ov#pDt%ib?^xjp=h62S|2sJhmX3FqVKQvv_{gvR>K33!<`9zQR8F$_Oa( zRJs_gRgUY_sB{$BC)3HjsG5$mB5y@DtejW*t`c13X-atQ#+VZAPL`3m8}m|jirf@w zE3#j{CeAdDi_8{jw4I~UXl2b#CreqGim)PiMXF4%{l&4vf zTK(N_DxX=2G;(NU%XFZ!V^o^%^k`?J)yTJ*6|`rjLsW|ISLm5P7(=rvxs!2hD?XGG-{&y33PnTy9W7h^}Jaa-hKImYsfXGPl^ zt4Geyyg-_9YoiZKHlAw~;<;Q&5^iZkV5!3MjSOtzKFbGgfe%_MDkW4dsYH~zfxHyS zCz4U5pwtPn7%4@{O1(hdX)WwhNv85eC5Fl+l^rT8^m`+ON)FA!N)2q(I_!|GDrZ&d zX=bCc$aSe7+n>gd3v&O72a`bt>Zm zH!^x}V`5Wd1+l*-8M|X&)F*Z*;!OF%{7_TR# z(RxxD(I>UhfI6THNq3XKCSy&aX(TGqRC4L*AQF}Fat`SwKx;YgOLLLm;stV0PZPbU zi&x4kqeO|PQepyZ7`ZTK0x73*O=Xwb(Qs7e>M1lA=`WIA9HNKo@|*Ew6x{^TpP2dCn7Ij~M*?}g z`-ak~j299+FEWK}d#S^SI31SIX`YW8l6LbPw}A!lXF55^)a&5{4uM9W_4C zF{2HYM>6^>kYp<9bbBBZW~wn^e!z5*{_+Lmdt=D#B+84CoBEk?Q+FVn%0QjOKsiO3 z*@ZW=$EY(BW+cPNeUTX>0afbaHu7Y4Y(rg@zABydyFg0JcB90|hLI~H>t>QKqf!2& zlt#I)-=n%pbd@9%<~x1U$TD;G5ar(V4P-gWmHh!7Rt9Xv_#p(Kit)onAv$90qMwX! zQ~@bTV$WV9_DI~3u_Li|CmyYI*?0cuPBulR>}T9bxj++r$+zQ-e7h@{fDyD0CFp>$ zf+YXEi%r=i{;{!frR?s;%H2yIPt62l5*_gS8x2!7@5h0JqVc|b-n}Tjd+~VX^o}L& zBabGIA?_!SG6Juh-2Gf1BuiJ4W>k?}DgKGEipC)o>AS$scBRhDKbOQWomIhh&Tv2rm}HUC9J-Ot2&S@mqr@R5UQ)8 zd}4YUt)@0R24cnxM2?ZyIuMg}AbYAC_p_?eY$V|f#kmW%+6qCQKw79o zpb>aKvU;T54#BULOe<+gdQfGuBvE;waz*71RWk07B%zV`Lo#)T;^PiCO0N7{Nk$d@ ze1Wu3IlW~AiAE!hZdAdS!#f;}R|aqXK*ne}R?8dR=tHzqd84v-MaHUufA;#gVAg{zoCVk;IL>`q_`qG!h+AtnAT8%WD!oGZ0`K*NkS+9~&L&mg` zds75yMoLYXr^qdpaB3r*){o1g$!9DYIW%%>ETiJc*m>QTG5Z{4M`n&3o}&KmzRc6B zp2se!HDOCuZ6OR=iL{qkuOELwJC0_NkFmrH;x`eQs%k6z5_y@(eL?GShu~Cgm zA@i1GR=Uw6l%mq8NBZeb$>2Wo4~##$+24jgBV$I^jQr6}D5TfP5=mu@$|v2ys?3?~ zcj6Aef<&rjuR8ObA(je8d%S1zs`q4%S_%|l*8Y3mi#r?)# zjbiiw&*%Zl(F$f(8oTyyU%Jt1qZ|F>NwQtR&*JWr-!+DeC*KE%FgqqE2o zX69hY$f0@1xT3Oaq}0qqq>*dd$GE0)Oy}U6zQbxiRGS6l0qm1SGaF|{BF$`1Vrp+A zlFA;HPb!gSCK}BEvMiki#0Bhsm#Uiao<>iVygJ91R}<#vY6HoVc@`2EQeD>=rag?v zD%o|eQC{cyy^YBu=Vy^8>r|SjoKu;x2(H*c5`Y$C`_#umtr73We0QVH&i8v7U8pCr z&=Rk!k!B^?F7Ra>^)$xOQm+fL?Lv%OS+z2bmSGqzW3981Z#$#iF7mr!7A;3FTFzQ0 zW;z??cCjzT=#^;H&FhGH+sT(~yTtEegd+(>D?K^49evrgGH;g~!*)4W@?@GAXGX3} zQ}h^#qYaTn8yinlx~Lq{`oxAt36(aQ-v~5$j8G%HrkN+j^p$9u)6Z=L8@V^l@n&Sw z6ks&=PD))4{cWH zNE2%9Wyc$8<7GAytfblIel}*Zd(voIAkIpWm2KOSD1kOBtJ%D)ct>rC?a6YGvU+lC zTcO!Xvdzp)7Ei8Gdr!`7Yt&k~xS5Q0lnIZhgD1nb4Qj0ZjeW#M;;VtJpGfWs)Gq$ec-HG*LOA7tuhk;msuWt}zm!(Ill#5@`a=QOTm0j4diJ zG>Q)zM+&`U)Ec=rNsWP%3~xpn&2>gX@4V4UC7mY34ZY+={Tr@)8tF7~VnP%e`8k)| zE1u-hD||)&4|z@|psZ23fTj6bFGDpEPO3Ci*)?H)&V7S?(WpD}d6Hw*Nvu0-JXN`@ ziTw-4=aKo70+&vz+D*mv@u~uP8MY5|C0G!}eEWBAs=m)26_+l~pU_C@nD^R?=@qNs?ImO0PZT z$tU{FJ;}^3#-B~)%P&fYVw8?G`LrkTXVW0uN})~T>#c(y264sit2e zjY=Hd#m7$W=q_e6s4)JUV5&93Q2#hH$ubI6@Rl|;aue9UF2?js&BimC+FVeHU* z3VYnJHO+WC(-3$LyMw5fUN?g*uXU>TC2r3VBmc#PVVaggjad3 zUl=E7k`Z5}$R6~jq7um>`WZXubK}Iyn>}Rg*~3OaI*MQoX{FO1@h0OU z9m6@2aWo0-=r~bc(x=9`m1K)yi&b<2vFHSA6O3;wk@ja#evuTTldMUsonXY;qei4X z#+xRxYa1fZe1Iq;fkv`uT_cN15*>js+K8185M@3Ik~osudejX=5*>;mT92!t z#w?XiI)a_`jAJ7Y=R*V%R!ZID(AF5yI)D9gFWdwqi}RaVdFHRcDO4; zwH5;1U_Q>Jz?Pw|_Bh_##1Z70(FC%L+RC2vqH1nM zt}7Xf_9IWOQB@-vO>m{qevCyc(^hW?eL|F4D^s+n7dPrm9C@aM3p2`0)JQZkYDyx? zlrXN01RB|-#qdWZjt01*@lM(>Uz&qkU}QQRF#JJNgJa{s`q zlSU`8PHJljqO?`l_&oA|O5>?Xtdsa!l4x{RYi}@)Riss7rM+nW6az)B8|kE zAB;09S@gD%MeiVw$`_SQde@a;Baucv%}&;DyHaT6%}A+{ZYsf4TB*d*TSO_Oa&mSV zC+EKLa~=@o=18iMNh8l@yU|hQrvBybX5THM47=S3b*G3ox!cX`O;?VM-uaStBhTj_ zqU@cyRGq?Gy~i`8v&vqTyej!e>d!-?0Lkr<{<;lS?UeD=q~Ogn=9vo zSLw3%T{%TNoXtjyl}7u($h7|$!*(v<#Z30KlY7r4W)W@O1M zBM&ngjSSL-Xrq!vhv3pIGj@%98fi7dsa{N!QZtx}1*oNqsFrBDh`5A2*myT1sCwnn zEOO+a4nQ82R4SWvzB>pXX9ZG@RGjzGY8E;Djf^TibqOM!+`6F*DRmM|hcf251C6dT z5Orszv3kC7nzAy{ZOMMU&G$Z8I_pv#*5yWHmBKo}$UYM95TRrA zIkw-p@8BJ+MKY3))Qg$k2)3)pa%@+*eT|6J7pG{QBcrw#QtcYDEF&pK>(Pwl&-OF| zZ4csF?xc*iB(^rHs07iXMy8QP)7FtGDm_&4Xc42+NV92&UekeG%qTU*sB7a$F)fHx z+J;=5l{UyUtubk&*0gqHpB6wHZO+F_9;xI}siiV=iXiB8K**7<(}CED{0944Ir)s5 zDqFP;CY@Bf*V!lKt{HcU$yJC|u;}FZ6mq1twnbxYPtMC#J~uf}dS&CZG%k?TpDxA- z>V)T$gxzxND&wk2h0W_qA1dI;m~HRMn3WMLF;*sRZdamFej^%nadNtyn9Iq?<;p+m zif`1NoR_P7P7b#->p2)XT`5U)J zNT88fDxEYHW~t=T8;-7#N<|1>6zgqf5WrxH%(jwV4EO@=jki&`qNac*JnNXU`E z^P2M)8cj-KO8gl~suEIDxz{k~B-Y6(t%O>4i@YC+PR^VRyTkOUf92IA$MTWeBl#yC z*BMZK0ktII>}-y~=TwL3BNGiJ8leT-mg)bfasL zt9VBl9m%w^W~InVuTAG(Waf8cC1o;Jl02kLC`Om@j3g&z;r;@Z7x8T~pxRzSHOlHp zJGvY>&y3{Tj3~JBY|k6776q4@OGrl9k&&b!{T?~%WJbF^%jZq1t=!u)T%UCopt{I( zIf~J;5a;D+MDFNZNA9Rp(VxhYVUFR!$bnfz)z1-`r4mOak4hYsEqa(dpUgFe%yASM z88Wh8B)-Uuk$O7YsHYN7kD{MSsyTs7BXdSFj64{bG4fR9q#mVi0Z)}s`rP<)QUVun zwUKy`kN#-m%1DwqjCS)2&y$BE`Q{|g{eY^C#%rBv?ABwB1fDr~Ij6}Zk?S_1s%rz=SQiIQxJljdk>TEy_M;?pxm1IN-qHm#x${bBbY5n?s6&F4g-Y;~?Af^8EhEY?R6nJqdsBF$wP zYx2mX*X=S2t7O;55xFwa4LyqNaV`e)ibvUu(a9)S|oLEbH@Pl?D1Ld@K8Bb{U z|16^2b|&i!{{5E3_61RfSOl3!hR_cDo{06G(S5!*GSCl*K^d)S*lZc8&t%Dak^LeM z=6&OrN;+L>Ow{*{i7NMW6*lTfY}1v*6_Mq{m1H?HYw%+v#z=;d{<4}p##k~ER!5+# zt|ouT4tAl^ti`8UZLM&69W zKc#e{E$BUtwbkB2+-BsV?dU{p*&(?vqm{vu96QV?vTGtzXmol>GK~bD^+w>4vLj2U z9o}CCOG@p~h$Nr)?e<0t9Bc$y*|uvV!;RP@3uvP~$f&l1&~De^-EJTcGxCpQp-r}w z-9Z?;GIb^GZZOvF0Hft@ByL8`buo~n5e-2Yl1cPRCz4?#9Z3pe21|IV?xD_AQLr{`VG!Qq)vj!PkXfPI0DfAfGFx|;-k-OTGQ9GiXb|#k~cZ|HrYAI}( zw^%LB=wi!Lm4n&=Be5hE(oiL&mZb7ce3~9)IW|3zV@gy1HlwrsCROqpWh%;OmB}i9 zwS-Y`B;@qOn0cGZGK@~P+*e7iU8s}qC@)glV>;G58Ih)=v3E+?saa2F$&&4g5!;nL zK8llsq<67{e5=3FjNUWW(EwDW;zr{sj@r|U>ptW(NR;U;Nw)H6CCwINzPK%=Qo5zg zO1Ze*jf*SkR_<+4{GdKaLh^#->lQ}AlydpH@r7PT9qNle)Q_Cb_?XgqrSMADEyDck zb^&GzMhc+y_KHaB?M>`!%>(3_ ze^6)Sul_~MfVTRloe_)mo-O}V2F`sXoUC>hG#V*2GHNo|(p+CTu79G3-lOtwYVH|7 zC#(I?7&a1Y(%W~ayo)V*pPG}#vyo<#4r@ooj(nbM_HAnJ5Hm+I8E-ao~Lpg~#5Pl>J<-it|F)9%^3!<&uS_w?~h*7d^qPyV} zRLBpNL;44mH*JZ#StAm6vqhvHoWv?kZQWq?4H8R(d*3Iu&>)W zBH1I??VOPu5ot(y(2(*_CzGLYmL#mF*^WEI89vTI)HG%{)A*(^1N>2l^*;MtrZf5Xb@@G_&C zF6Q?k=TuVaVr0`L_P4B`#;rMxVIw)`3{et}+*1jsQcxFBzt}jjr);S^XOVSe>8xVk zDdH)t8|kvA(PSmTu0TyqX-V=qhtng6XM)jjWaFF+e{9s$1=KG@rTvX87wCL=u~B_K zF`DXp<`>}Fo*~O1x_}-e5ojFGl}0LSbsnqpjkSBmUWjERsYuGucnsDQ)?DN8O6Wan zOGEk{<><1pj((?Zg7Hk}usYZHzvqY-uzaN|EeL;#bDF}E`8&s+XFMf|NSDL%Q00nB zN0kG7!N|WdfiEBgOH7()w4*D;Yp6%^d}rBmkmiQv`pz`2uZ-Wz_9af)UgoMJR*X~_ znK5mRQYv$1Qn)>%10KxhMum|dBMnui=_}7vnrS;UQz@lVO=a3lMy!!JBS}VnjHDT< zs;yB}KPR_mM>4Cek!>XBObN@GkuD>FMpA1ltW%k%GG``mLRuP48)N23>6sdqfhr+X zBC7OP*{+j~1Z&h*WAaD}`XXEoFEyzpfwqO+$~Zsrg}w}zH@c_{+sUZ3laXWP7fr() zk}_1msG|~bW!!#YbX@7RGL)v{8_6cB$a7_SN+y-2+tik`^p&xYWGu-+lC}E<&aO;d z*+$L7jSzId#NC}vZp2k%TlP`2a8sP38N^v+nYoQ@`9)2`a&)I--A+f+)rsh@h|+as zkjfL4S1Oe>2|CJaSSffX=qPE8oRSttr5e{Y$mv&o2l&7V|eW^)KO-zH2l7U?kR4Rp~v!*~Tm0_BS)zru| zwaAacl1!7KwpPV$mB{)ml#zP*Di!f>B-o@x!l`B4Q^}r>@K0sQRx_5YyjY2^PgqZ6 zN%%==grC}BS+%leWzHry?oV>upE@`|^~f@Bli10)P9Bz#TNC@XHaQVjiH(q($WDqt zR1b$ps!uwhggpsH==H0V;Chy9cmDke;c=TQoSCro*lDg zl7z5ELScy`a!TZg$_;%^J{p!nDzjAarO`*zu8ad@5wx?nAcqY}b~j z6X5OytVy{25nU&S#&dxAgP}dl>@{kwXG^SorPuC34v5-;y^ERMc%O1ZrGv`;+(4Eb zA`xVZQAFg9$Q}JCEO&GR>Zc4*xg}dda!cfqNFC|Mj!mI)tgpiaU55xdhWfF@O=O9t zo5HeCI)@~RNDYxYA`^8C#@t$?(_J&>+#0?%kLMX{!_rr_g*qA?Mc&Bzkh~FDBl1YP zqSHyBn?vr(jyV{sa#Kg4tZoihrD}ah#>;l1^py{d!YaXaOIU8qj*#3K=`Ye@Z`??nKzy#g(+r9>iWo`ji{G z3KL8ER04dd)!0}G!p|^EYGISq!YYxxB{NGpmYgbiOEQ?&gjRF+gqo*DJE?_YQWL}E zxh361PH8VJQu(6g_|0MmA1g+}j4T<6F|zKKquoijlOp>LQmhPEsk1U=`;+C+z8Rj3@3a?{X)n^# zGUMaP^vfKUWAmRig;}XclgTC6RWdC1M#7CW8@ad=aHZNlVE!NcoJQC<#hHJ@2)XZt z?;9aUl1`&gF$~-R;bM&9VTn5T5p$X#?Z~}y-nq3}I;l8h0#BI%4bav00s z#!;zA{RIB6Qo4vlk*fTgC~xGIF~S#8t0RBMmo0M%E#{IjW8}?9Et?v86q2GUF*PeO zdpKKI5?aNObQ)pBSlS8n#8k8?3YJ1g^zY6hFmI%X#eq?hr}G=?C7eG zLRrI-a3&g^M*55N8hJIgCE@K$JT~cUmD$~j*b+5Lx>d`NR9N}1Il}+pHcD@m*DAYF z%A(YrE66(6jISe0X9`cXE%|cOj4vlc&S-BuuLT;doLQN)Im1tRp8UsU2#`{JCRo{! zs#+jbHOG|7##M9U-N~qvRo9ni+t#mC%dC_e`GDvAL(Gj^JI=^IQiHBp+1V|Xsu|*x z%)K(9cMx!F>o<1FzLZ)iYd3fJK6@X8BoST58Imc~4~NIL&QK@0QbML&t0qJ#R}uxk zCQ9Lx;(MQ%7l~J{ku)P|MLDT$Vtm3G#92lkl=$~9&$g|zM#lV`UH3vVg!6{`TkkS2 zJ?Rgkj3haVZ-pce%NWiV{yX#@7LaYpAkP1P?49+yRn-@-=Zei)Nq2X5cXxMp3yPqE zfOJZUiUHEyAfPBncS?(NE2Wf#sBqsg`99D67w+@i^~3ml#vF63by(-@vpIY3caP0v zVwp-TGnek@`ARZxN#-fZghZLYI2V_xjAaa&!ZeOKigQ^HQ2jZB%r4Gv${gcAjSrbA z#BYUBkeSB!jY7;czR&I-#z5u^SxP1k-`6vR3z>t|Kq@l*@SZVP4I-C`vX_j>Opg`4 z$fVE7WEYvWCKK9Z0-MZT%f&P{ndEj>$t1U2dKy~`^pT!>CDYo@@mu^z$qZYWL%W#S zoHB=2riD(%Wy0-c^s1h2D>H0AVP_HZ;bbK+i5*DPUg|&F)lDU>!G?p zJWw)OcY>buxd2_HCw|Ht(o=d8oy@z-YrM@&PMOg;75|ar9xy}e0h6@GbL_`V=e>r% z!~T3@lb*mO)3)w2Z|hHdoSxr1jyb>An4DLD341bU@06aom(S?KaWdU=KGQlkbHsf$ zR!;^V%Y@#4`L44Efb2$dOyG6Q*(o`Ed$kZ&^!S!NFwMrCf{ z2qqHW*7J);>Iuaon1y+lnoKGl&cxZi{QG1YZC^c&O(v@KW~Q1-{?WS-ez?h|BoY7(OvEB?P^9&L=7vNl)v9hq&cM>pu{wK4KIrqq5nQttUhC?GTWFGRH zNyw}89ORWuB9;lsG6^}pAybJH7&3i$In!YilF205goeyAt;t-{8Mw?uoq^8OQ%+}4 zt;JW8`HnKXROXSsnFlG;9=~QsCa+dUXW_M}$z;cl%xIKpuGN_BD03dGkXJ=#<2k9x z1ji0cXOs!Fv(ee?<)YReZO`OInRz=0ox@&kYVFXr%uUQq)>g?>UYUt2Gi>uvYr}Nj z`P5{7uT1KdxxIPWX@j=WQx#?QqRduoiMGaNVs8Z|C$`k{6Z7FRx%bT!-}1~-Y{6v2 z0_?ZY({&f3GTXNxHJO+w6P#t5u1w!;#%)F>@ye9lMS7BMAw6@ku%5bFL=|SYsGiJP zOwVmCu8L79p{Ko;)YD;0sghJm>p8V$^wit3%;Ytg;=2f4g3G+$C1_$prvA!QM}v^r zcXzqv8qC9!*>{O~N2|=i8->|GG6zp)-<{O6?^AX?7Q_4Kr#m}Gn$!CHI_MeGW$+GZ&l{tnW!nRr7;IjX5YzY)X5yY>rA@4 zu4mtU!!rsp2Tx|-c|3MCn1eSM9n9agBbdtagExX0=_Tgbz$82uCC>^bA`Kr^!G;e_hIz+Vf6QW^!O`!{1rW3F2y6{=<#y&{6_SARP=mQ^!%Yb zpB>#FM$h*~&(BBC&quGPM6ahruYX0aS4OW_Mz1eNuP;YDK*VoE{6@svM7&MJM@2ka z#Ir^GVZ>w9(R_etK0q|jA)4n9&EJUTr9|^mqWLz_e4A(Q` z(dV^ApRX5vzFzcsh|%XEMxS39ecovFd85(i!$zME8-1Q{^!dxt=PyT}mmPgxcJ%q? z(dW@epGWVgXg*sspDmit7R_gi=Ceif*`oPu(R{XOK3g=OEv<4@G@mV+&lb&Ri{`UM z^Vy>LY|(tS|KH}b87ijYDMKmTMolz^TPlvsB23hv$0Fj?`?2@f{vh@~+K+fI)<5>V(Vnp$=v%R# zXs_5?Xzy4r^zB%0^qtt-XrI_SvHGzgv5(N9cmw>SSVLTNaBL9z5nhko`sgsc5mluc zu`?)EmrA`@9kebw9B<6NQcZBBYE!8bs~u~L*NU~nYZ0|$O=C^itr=@ittL?`RwLGd zRSlwMta_{?tLj9JShZLuR@Gvi@oHq%V^ztk#j2oHQA2e>yRfQEUL{rutsJX}R*L10 zwT!ih<-uFTa*^joTj9B4t?|6_m=OHuCIfDLgBh4K0mliIu^##LD7X$g;*V$I7wFOk{~=ij`-TiO3ww zNS-N{0nLb3z%y_i6=LbRmWpUa*6GO8$Ku6`#)_cD@Ho6kEJhwL=8zRe<8U`tC{_?H zjJwnd$836HXmQ+*mB203j(PMIKwaD?Q_5#mAZEsrvTqU=nv9i!nlXhMXmVV|QsA%c z6lAZ^*Y+zrCAI(1SN4B)s#r?$)Ui~tf6@Q!f6#x?G_lmNm*_wCOFL~WP3&*^ zE|!+uQ0ZdV?F6wK_H{d9ECG3;#eXy5q($e zB(cP?EA~VD3iYe@Z}u%ajQvIgvENyV`dsPnWPa>2omcEj_9OffaoN6TKW252xMW`- zzlc7;&)a|D=ZOpUIr8)9Q~X!-9Qq7DYd^=&62IENke@|g;AhZZP(%HV{>^Heeb3&G z-p6;4iQcvEp!e{t)VHC3;9KoK@ty44vA5U{SZyJ;+PhfaMt9;rQQv|d!FN;r9o>cR zCR1uN^`Gob_ECJ3{WHFaY_t6%`6l}Z`xyQM@uR(w{0H@kYJ+_m-$3@Ay`Fr7y$)TEp262~rDyD!_I`Vx{f&J9|Av@p&#(`&nn8SH&tkpL zo=xmUXW`TBL+no{X4qfbhgp41Ot9c~Y^8&PR&HzOO0 zHpLs-qo_5sN8=628rcoV8`{n37=kv#TW}ppwP5`bd2_tJ-I1>PL<75?-HBB_qP|_% z?#!w#QO~YpcVSh>?uyqTt83S`yRoWG)Uj)k*S2fg-SL`4ExU%@gH;Wprd{3c$*MZn z)D!JNwHkSKJHOr5ZiBY53)lti)^;nj4PKCS8#|xfj{ST@e!CF0R(4*yJ+-_|Erz(Q>p(`*wg9M}6F- z?xCe{*Dj4asB4FIF}o;Q91rO&ZpTq~&@y;@YDMjMTaT|@HX>bd*(X_aUTDD=Q!wtf;m7SiIA`JVrm4Vf3D?RI1Rz^Dmnt}CyRwg^6 z{U4QA)^Ao)JBj_9mBjwtx{W5bZ(G0Px2$A#QZ%`p3{6VM9V@Y&$i72YV*4ibTh?gFZSx?!yW-He09h&BRaE zChH8VO~hvFN9z|>KN6eJv#fqVf3!BDKcK(j-=iDRbNC$Vh;da$+B`UqWy4Vl76O;)AFUMwjCQtrhq{VvseI{l(UY zR0g6e@nO~?u4EY1Md(m`IKB{F$kh#?=R<3N^)Wucnt=C52Us7V{n3f|`{)PgB>X+} zeRMM3&zgewBi^(6TA#4$YfZ)blJ&FRCGTtXu|CE75bs*=aAlvOpR#UYjkZQv&CwR< z7`(YP7H@_&w^~vig^sdDT1}}mL&xE*sEtHNS|h9`RGOmW@z&HvSZ%l_rP`1UCvS~6 zX15926>ns9!y6Het%g>2Rt>Elctf&ARs-^eR(-1{Uf+5PuTR#%sz+Yms*Bb`d*OAh z-gq6fu2mbYgT9T|=E~l-YN55Q!d54%qg4bK?O?S>JK{z0_EsUQGy8>z!d5}@LRK-W zoz)g?j~An>y;XpEL9`2AoLXBeKY0PPB3^=8TeL0LS%Oe1ANBlJKC2R**Q$)?CGuH$ ztSYSX5P7ZK|9e#vuoAN>X(b^_ zpow)}f-Caa^)1gzi+ff&+(kXhL0vRG9)~(;20R`bhi1g%S()${8qc!P7@8Tktt_~O z+Lno0Xja_h%CcGpYFhWq6jpNUE_%Gr4u2NM_wOQ(LLf zRP6o1PBQBcBB}MenZ`=40~_`UF3~{u6VL`HY=C#9s3twMXV5T=bFo z(A;f4XMeYO8sAN}$2`o=L-Zk6c$iRX7rVR7o#-y~48Fts1>a$w#dnbHG`ExQFt?e% z;@iw~_%^cb=2r4;<`(ljzQw$NZz0=i{zSgT+-zRNH*-xF(F;^Jk#9B^n#ata(c}0+ za{)fzJfZbCt3}j)HWw2|(M9+?^CbK8i23GR^AxMO=C}AJ%!o5Rdi=qhuiITRg+uEs}DTZyhPm!m83k@#|Sxw*_7LeEfi4gL{21YL`d zVt<)AnEWGjia8mb%xW|{%g|+9;UMaR(NFM!=pge$bRaqv|IqvtAAo*n_D2VxpWz>v zpW`2x)9??-`kU{Qe_+06eu2M7yl?g+e-Hf4jpTbLC4`O*llUHXEnxbZuVr=oM>ToU_Babk2f>lVy79=+-z$0 zV%5~_jW;E0W;P*jYBo0C#v7aO;Elxh=Z3sWy*mSNoiEsYnVQW&j<7eou8)$syoL9_;*A1#2^#PgfA@O)-%JRgzY%uAjR zt%K)5^P0KMx_EA`rY>5CYA*8JW)d^8SrM&ZmPae%iO|GoB|MQ?8BfYic{3q-A~PAQ z@@RRpoSA@1LbM8=oLV`woLSb4PbC4G5l=y_ELxUp3(ZW_LNhZSlEpUz^3e3r0L_AX zsE=mFUDQLf;f|Rdcg!5PL*|-s;L%JTw>nz({MRLI1@6Fw&W#Y0W>4 zhejGRwfWF^fZsRLo9WPW>^(A4o2kr4?58&G85zv<=)d?qdhQ#KjZ|hz^D$ki%)7>a z?A#^p8BdIqT-y`&Q<`_E-!*QdchFb(ZR0imJ9^vr%~0lR)G(F#8>f0ZvU+OlH~wL@pEzLrOzkQ9)cDKTXZ*^}K4QOdjM`u5UtHT> z>if`h_+H~Yz6afF>^3goyNNxi4E_+sOX)?e_&WJ`=?#!2G@dJ11g*C}I>@e6y)S)DKzk}pEf z;tP%M@D=QwKu;LQjRjN|qTk~ysU1g;bA|Jbjnw873ygWj53J@9^NqRW^NcyhkN6y7 zt}&Z@4!Q}SWo*W089(8($YvWe$!8hg7+dgfh?&L=u4xOph4pA-t+59E79VYl!bckG zw64cTl8rLPu(QS(VXS98mem?`jj`GoPGtnT0UyVD6*?9lMrAnqDL$UsDs&ZBHI&LQ z^fP=2Iu!jJ{|Fs|PQwQqU*Lm{FY&=-9~pzl2O9&?LFiZbhsM|Vhr~c*fH9rb0Ip^_ z`Zd-5np_jd!MN z0y@F?*yw_be#}+1X19&e%6JEFMYJ|r8hu!`Bw86QjCWbJAX*yDjlQg!6D^EpMn6`~ zi00^fteT?Dj3#JP^nJXE@d4f#ZDKS+8>9X4GDc6M2U;30WxS=eC#$klyQ5|Ba(H*N zo6!~Rj+dmf6xs_fftEyj<0XumczL?I8pX*=7!}C6pylymREndu@M1=7yeL}CD1sJ6 z>)?gaB4}N_kWmjWWYotCkrg%yk{2=x7!B|OMnk*+SwSN|SJMz}$T}Z+ej~Y2)u@72 z!&Bf@jAZ1=jg&@ZqY_#LPsvUdBNblBNNQAPKPi#SNJ5?zt$`;ovf`=fs)SbLN>Y!hTzH7aHv%+7bK^c5pm}f) z_0hbzi+X52{E2$3GNKuc48|k$v3jI385zkl8<~v1RC*&Fn!!kqKEa==zf?NoA-j*% z1C_ij_znGC-9mpu zUBfYssh`!q>KO5lI*R^`{)ZoD{SrNfpTJ+Df2$YhOZ

Mb{DHs5-1(vpTFU;)ltO zsFQTPP=}}-R;S3GqbKo$R1Tq+@B`{Hen4Hp50D*H`^gWeed;Q{PhG?Jk?mJ|$@i%} z>N>uM*sFG{8?1H{d(w*`6%>De1!T6A3=;%!^uaWU*p5j;plXHsG5NfRo~!4$%d&RSVMV-d^=(r#;a@^`JHxoy@hhQ~lU!N3>UM)qAYk675tQ^**aML|fHbeZZuinPX6BSfN zqL(VC-l0~GD6cB9ehaOLm!)0~?Sq$9@8Xr&>xovv%TOt+N~^kfX`&2Tk5wsEA1_6e zRwc4hLFM<|Do8W~}VTzmLrg~zeFirjiJ;;yo z*P5xu^EZIW_i-(iF8uFlsucXyZK^cfC!1<1k8@4-PO)2=<4lg6gjV4HBU4qOW~!>V zsjA_o8qH%yQyu0}zsWJr(UttwWU3B4{xVsoAuq#YmNY80s;Sbb8mc;46HkSvMr+|| zsZ~d-bJldYXf@82lHF8jZ9D~<60L)$P&x7RbeSqSc?y+*m8p`ECr5MP8L62n6K<-c zRFa{&@uYkbaBh_ZO{y}pZ>lV~sS+z;P!khLR3h@kXg)kE`=&}ro(Rp4CsYOSZ0wjS z0eM1|ot3F_;3kwt4%E^Nhj1D(@;J?GIJl)LPfK~YrF`5{0dA=fx47*!L*uiuICp%s zAYZ{!g>Z|XY9VwsT^7{@sI9-&PHGlMHbtA#C6vfI+aji*Q+Tz?Qg89vj-{&Enb1u3 zf0m{G7&V&A?Oeo z72#LvYj&l9=2QlwgQ?Y{I#kmv!{Ai-iD{apA@qu{Ep;@{A~efz_!X`gPQ_A`GOw zUATrSWL@A`s*qR0O}LLrsPHQ-HLa2xGDWBsp;=m?t)NqcUCE=#mF8%3Rzj=fgjZoMQ9cwSW0VxrHtlQ zgl!RmMYt7VTZCW{dPUfljJU8X8MT&&U=f<7q9#~O=oO(_(y=m?kSj$s%~DJ=EAik{ zglZ95rHH0k;xxhHXf{PSmO`3i5!yv)mg1Ub5k5tD7GYKjYMRB>9E*qYd!`ANq^Qs? z!n6pzB0LL!tZ7XK!6Gz^&?~~Tys}?Ivb-XMU3mq`A~Z`XG!@j!zfdiy;a2|Dni_WH zrRG^)LbC|F@)DBeZ#Whc$|Eh;d0q1=LbD_!PY9!O4XP!PCRlE0awS3R7F^03n&qY~ z1d9+W*YGQ_D?+d&i3y)_mDO)_-qQR^7!!8oH`osDhsb@%mdkVr!6H11a4c^K7NJ*! zZMlFyMju132*D!sicl@*@W0T%U{`*{MV~^ioYg$bS+eJFD?+sh&GG`aLwFV;SWNhi z7x*^Kt_aO?-xfmUE_zqfEW)=4$MT2fScF&++C^xU9k41wwFt-Zz!pyB4tj?@;aG%K z5zb{dS0^0H@0w!~(q*$IT!dW_g5{{DSA=c(QBy5Kun4^(REuyd!mS9~A_R+YD?+sh z!6L+puq_+NgkU+P=@lVd*0U0JMlCfLoeRm*PZKUeun5O8R?{m&wY;l&7NJ?j!>tIIR^AXS!~VyyG=WkPwnf;K zVdyYO7GYO}U>T+972#YOuo|stm7$tuX{I@rA*cnNBQ#5MO|S^J(tu7OScF>@mMmmd$g5~>MR=A>g#4wG85e>@h!tU1gh~+=rp2Wu1WQQ>7NJ>$RS}*=I29pS ziqR`HO8~JVgp1HDWi+!ALa7MVA~Z`%D37946L5`1G|f^JVnqlSp;=O)sbE)ZTr@T8 ziluoLp;?4m5uQZ|7U5QeY7v4(xD{brUPG`5x1y*B!6Mv>uq{Hc$X{^6wg|x@l!~w` zLa2xe(<1DO5G=_cRc>k8Mc9=e1gj>0c3&A4X$|d{) znQ$u?@$+QDtq9v91dIG-dLG}Uc@?2q9zvR`3A_U6`O|YEQ^op=8 zKWVB(2o~X1glZ9jMYt7VTZCZw1r@eMm=>W|glE~Pd6tc2zw)=X@GL^JoYMr0&?`c! z%*KzPM_^TiQxSsY5Otwh=4ygPxE0}CgjSgclOk-3&@9I^xpGj`Ec0PIglG|hMQ9dF z?bqyz5G%sG2+gue6D&fn2;njvUjwlsJd4mQZwMCQR)lI1fe7O^8V%TP_Q3_~ro5Mo7W7ok}`MnBf{itsESXr4uAmWgmH!m|j? zG6`Zucov~q-ViKPAXbEG5q3ogmQOUjB81Dktfp#$MYt8AT7+PcM@Yi92&W?KitsE# zvy4HrHf`(ib1IqAQzgYBE&~qszR^`&0?uG5Gz8s2+i__U=eObs1_kugkBN0 zB{yD0(=2ZY79m!IY7urt2$t%aUJ=422P+|1YG{I`rlwbfZOKNh7Q~A1DnhfAMaybp zMR*n=SQ2PLr3`$Euq{Hflt;_Mq6n=b1WPFh7NJ=ZLa7MhBIHUUXpR!N&@72jOO=3F z5za+umb7SEs1+Aa2e%?Ti_k3T;Z}ra5t>EV72#QgX32oQgd2K4_l`C3#qMTA{5Ibh?Udu zDZAJ|%`;&ZypAv}hagsVX@cd9CRl`O*-j?Jim)xht_Z=h9p6eO#L6~Y*cBmIw&FjL z39+&T-%KV1%SBDE2-~uW)g{fT2*Gj;c138G1@I}yHKnouUj&cxv*uS8YBpsNtjhfV zaV$cxoYVx%DNU@*W3`0-#hO_WjztI;d3NszDs;$|tZZ!m$XwB5cb5{8LyJ;aP-c5rXA2O|X2f=@nsH-q%#i zdzxo?kLnjZ?KJqkdqS`Xu_By{uq#5a^wRW-5H3wv3Bl4^6D)6Q zdPUflMw)7AsCgElS^8+2Md+1=nq3i|MQE13nr4yb^Mq#+LZz#wS&D0RMF^H|Fe$|} z*&?(`7frL2fKn+&T?m!Vnr11f*%cvJdT3%rI2WN+I%%4v6vT=UF7k|UM^xyRLYi$6 znxz`titsE#vs8y$5uQb87GYO}XAzpECR$SyEW)!0$5I<^MW_~`S%g^0s|l7mnqaA` z=@nsHa%rkX*pmb77GYO}Y!RBJ5?TpHMaY#T5Gz8p2*Hw6Gb`m`RfKI3nx%>+ zSdwXGr5t=p0xCkYWYh#parAS zp;?4r5uQZ|7U5X3o5HOK)glCo&?`c<2*)DNxeD7NoJv|$*cBmIgjEryML3l-s4y-< zun46hoQn`DsZn8Egk2GWC4(ufiqI~?siZ=MbP<9@h!x>nO+@U7yitsE# zv%ErIX<|iq7GYO}VBy71RM?hVnrab(#e`eAh2J2xP+?oH^Iw;6E5f!2!6MHh3)>(0VOI`oX5|_BjMV|nxd^jzL=!B+stDU61j|v)tUT2Oix4Zq zxd_4XGx`MIOHBxtUm;k8W)W^hcord8gkBMMe7q&&%l+&nCE5fb_!E#2kDnhmhts(@=NxFn)SqitZm|dY& zmO-fq)gm;@S@bNtiV!TzHM4R8N=4Wfp;^Ay1j`Ea7$l1jEW)h_;UWZ!&?~~W%*Edj zEJCl$C7-RSmf27&La=Po1j}YkugqpOliC}CMYt8AT7+PcXZpXvg-{WKWi7;t&@7`2 zVONA;S*N*`QLKbq84a;Al8O*4W6;(3aLu*|&9cD|T4go5n!RC~Z4sK~Q%$gpLszmt zRI@EYvwQ}(B0P)GET6-w2+txkix4c+G{N$PrdNb*8KkL}ftqI#n&m4^un4gtRLcO^ z6(LxrYkEZpm;S6~z^w?cA~efn_!Qw;gl3td*_95OT$zYYWM2rCj&Li&xd_c7?27O# zLbFUor^2TQ!O}_dD-$%q(it5O$uq{Hc2)80^ix4crtq9v9 z1WP|u*cM@0gkBMzrHSTQnvlJ(X%?YZglB1_c^08r`fE<5Co1epDOC6rVOoS->46I4 zBJ4_8v?~OQ&@A2IR)l#Gnnl5cY=Q4waP9K?!HE%K^iSF|hDVw!Ccnx&Se zS%h8@o~4N9S%hY(1FIrDi_k1Wu+-HAOFd1m2-{LnQ!T=-2*J`ob1TBO2*D!sim)yD z@J5TIFAu6k%F~X8BK(EB|Pk>Oix4a;HNSFJvn#7Kp>hU21IZ!; zi_j}VzAVMhYntVPCRbML*XG~QENe8uBE*VtF2b$|!LmuyD?+#|VzpT<)I5vOEI+9Q ztVDl;U73%IZh>8yr+F5kS+>Eg2+txk%XYXG;aTPoJ9vdzcov~qc4~g*d(Ezl)6B{S zbOR*ISWUPHzcOAEEFWt^WxXa?gkBNOWi&1X%SH$mp;^Ar?8*eqtbB`p3&}Eyoi8+_ zFcD%!s1~7F-ViK8uL#vLTvIJVvwRJ!GFd}UJ5G>s_Q88H)EW)h_=OP4)a4W*L2*D!Uim)w0un4yzY>N;q z!mS9~A_R+YE5f!2!6NjEur1B;4>is5hF}qzK&TdBR^AXSLaYeYBD6{cO|S^DB7}<& zD!nw#QV~i;2p6GQ`k;MaRfGk33l-9(47E1|OI?T+p<0A#c|))Wy&_agNlmo~%_8)Q z@GQkO&muHSL%0>;S%hY31h*nQi_k2M;Z}ra5t^k56oc?Ag^8xjzz}{~@tx~Q{)E41 zlv>IEnF?NIH0;S*ZYv71r3;lZ{Qa%qRnm~ldjJ%4%2HI=F9nxUhFpjo#W6il;Vc#F zD&$pQS`<+YwKUZt^qYd5SxHYC1D-`wD?+Q(&@@X;_!J>qgl4Iw36?aPU#YGMmb9qi zY$-M8A~cJzE5fq~%~A)g1F4dpo^)_4LbYTdPY{03<#EbsJt`4 zfMAKC!k!xtEL%|_nhgk+{;1HhTs!|G8=Ay4_;=spyPQ^`1Gk1q49Jz(Z(3obc{_nhc~nRh6j5Jxd0%D*SF|;Jzk3S!I6b)2m9T(1CJKQ4y_#rskfdB9WGR z=+tE8(F&;Cii4xow%RNLfqB!@(a<5R7D8_xU{4N*Kzsp6a7v=XeWL-%A z))&&h^@XSu<~Q7@T0q|?6d*6iy^P#T`H1}7C&@iYULqg&R&w8xhseu) zo7~&vCh~AkC-*bdA4Y%AM~}av$6wLo<>>Kp^!!Hjd{p#&RP_8| z^!#D;d~fvpeDwT$^m5yl`^}^I0MUGaXr4nf&mo$>5zR}9=A}gQZKC-$ z(LADPepEC+Dw_8d&HIYxvqkgtqIr7J{KIJeVKlEYnlBp77men@M)P2!`MuHn-e`Vr zG`}~R-y6;Ejpp}8^LwNDz0v&MXnt=rzc>0kj_C7KqR&r>KJO+wpLr9_?~Ug7M)P~4 z`MuHn-e`VrG`}~R-y6;Ejpp}8^LwNDz0v&MXnt=rzc-p!8GW8_^!dxt=P#$`^Rc7( zz0v&M==05^&!dk%k3N-(?hkYE%1Ly87~LO6_lME_VRV0JtLXkPv5MyRM)P~4`MuHn z-e`VrG`}~R-y6;Ejpp}8^LwNDz0v&M|99s1-U>{0Gx!a?72F7J;@5Fg{Z9NATnnz_ zxApoeD^uOk>$^I;5?sYE2UpO6!G+*rFbEwO3=YoYgNZ@Ghg2`21MvaDWjY72zD)ih z{t=yn(Q|lzYNi@O{!uU__!a+vnyH484+(|_XYpadFZeKGXz)J!rW#IVSTH;|gO5Om zqo?ta!6|$sF(MchoCr>$C#j7hMh2s)j0%F_-JoxsNO~I(z}P)9c-oh5xNae6!Z#uqrK@(L?jFxjyBbn z;OF32u!X*#(XIGis(XUO^d|~_qIN7uLY^4y8N7wQ#cDIv4h~vhfV}h~4Y=4d)4~-YZp>cet7SX@ZU*xO62wDXj zIIb1ZGHA#VW6{n*7j!JXn4U%cV*fQh%b)E#sKa-(b+De}S`)2;26T5t8{$j+SM)9+ z7W-|2b#%2MS_k#n?;0%i|Mma#mlChgSM=4R+AXL@q(JMlY8!mZaczkLqRbrMg2QeZliUAy1{Jfvx4IOSL_rgiupz8n2t{OXP`6uZ~VJ{?VwI@ zm;O8c?_5EO;CDYokP^MkY9_}YLJtLp(Zj)!U{0_c@8pfpF7@^ARh{O9O%{{?!J)t`R#phoZ~NB!Y{ zP4~*+YmQhEl<`0HKl95FpQE4qrTqtfwV-m2>U|BCKa!B-ryGAK)b8ULYQ zHK-Omr1OD)jjk8y3x1Mc(zPo1l2{#-^QY2VjwtIt@+${bf=7OppekCGBOgk9*jfx@jbQF zUcS4Q8W)U5O;#V{faFUXG<4W>w(ILbfI(W8iw zehGSt2PJ~Z!4z}~tK6KUV(^6i$KDe!tDnt(;$`!*`=k9|{d4F!jvh^n@&|CftYI#? zD+ReYu3}J<^OOkw;;1Ly82U&1{prdYmZDxVC>2b?pR)Ux_teYcXZ6SWXXzSCjPXC9 zH)~irm`GP?qEztA%j{?IpV9f$d*)>eGyCKGGyX5=FB~_H80){!aaqGM!32&gLzE7l z)A`JMkDaXHc>2frW!Wtgl;wBiWAtNIFX(yh_4D7OryTXN!QWI~czykTR8mtZ7yLry zZ!Zmb>R_**GuY$r^|J>#$a4fagT>xWZ;`jyyYAgUZ?M|UZ~0&TZhsHGyZu~zPj>TL z|Ab0TzB~IkcCWvL{>9!xj=YK9^lo{(*#FDl&+a}nTaZ0iz|Jji0r8u+)Vu0kL$7h% zQeug>)89q^PU5M5fd2hx)*xFjpYGqi`NVB>0jp&kyVTo3-${Q5M?6JO`ltMZ^dCU8 z1X+W5^xpQC)42@2f*+!O&_Cp74zdK>IpUPRg8FiAg?AZ0O#P65*v}Yb3J&|3g3Q4- ze>*+fh|~T`dRBNVy^G!@^b)HhbRPD%vVR&q%}-+$yDPn;)Q|W_{R~0IU^SIh-fHgx z{xg-M{?C5;AVaXmJ5Oy5vD!OE4W3s$NUrAo2Cg)_-TT)Xj-ak zsGRVVhkf}uCJ%f1Z;`*{_d-ZHU=kdwSY=E&TER$9@Ys zwxCK0^M(KGC{=BQTaCVw-!nN@3!p6#_J=6D@ALwj_(Hv^r)stuj3{WkuOcyrG2 zvEPy14qhvcn1jyo=Av`Gd0sR2Ciu;W?r3vXZ8@rq-;(`#UMG&~h<=SX<@!>EP3cRC zHpAP|*%saC|A79$sq>tY^b5QZU1`EbMB1<;XXxOUrS~(hEb+P5jh?RPG`thL9sN%J z2E3u)$WI%V3Co6`du76Dbd({R=5=Pbli%52kC$e@n^&6X?scKk+3(`7!%KzTy&hhv zur%J)U+aJCcO}-L>*(l4rK?{u?BVtFN`|HI%G?gu_?4-5L)YLX!k*q+UWu?IUOX%j zzU3_rmxNiurNokOna-A@%fc1t@^EFC8DB}P2v>!fSgj&fh6%Zjv|%DNp`XaF?>9gj zuuA4N@tS(ch@@TuI?{y+=tvtTrYDh~oZVzza<4I-gq~(-Qarw&E=(WB_Y>er=uGS< z@#~4x(cDW+v_O-vO5ru)=oCb9Z#Dm(RblAI_tT^4!wg|kzm8wmPfFB7>v5Ju9NE%K z#L+FhlwL!QPD!NTL0E<`BM;<4JQ+tN^%K(7(o5wvpeq%T(o0S~nV;ORjr)E^zMAi6 z3Rj~6tJGe7dQ%grycF~#_fz;a{aR=(Rvt&J4n1N`n8vH?)$`I2_0jqqR zS9&6y_gz>ZEEs-A6haGyh0(%ckuVKMrS{YKRsCvcHCDT*77cf?UnJZ~Rt(*Rr==&2 zpVqH}@1R;d+`&$)KZoGZDDnfY9HTUZ0F;nnnxaPfh6z*`rt508=`aSxIo@D6%${<`pI*Y!N_XT(Q+@2Gp22g9Lv z*bTk-=n+%$G4@ zhrO5|&p+rMqVph;08QW}^p3l6o`X7`i@KcU2>pk>z1}`=QFy>T=qB_|&~x0~Lv2xb zl-(oVQP1=(|EOpAwtv!%dGWlHZagmzjiYF@G()8mFUy;`0d*5YUAhFe*=VQqevZn%Y&!+v_tAu^yDyo_i@FB6){d*$x*c5#N& zuI2!BL>q!urX3k@$GVWOsIp_XT( zHvhiUoZ*yr+WQATgP!)*qi4{U_Z@Vd?J+z?nHMRKAy@r zZ@l-Tw+Y?EY7+H{?j(0B{xS9O-ek_c)tyXCawm8{P@6z}>`nAGvYJRt@FscRdEcYo zQ=3Fg^b+uIjvponXW(Wy*`4B=;S~21^b>a~YK2?SEu42U$4>I5cpLC3#AL4*`4n_L zJ~JHX4MGQbgVDj>M_xkCnIKFUeieR=ejQFnr&CK9enZXRt4(zc;#2ff_cQb}w~t%W z8_4mc(2`y$Z-Dn9`XQ@w?nmwrw;WN{Els_YSAve2VR`E1-16>VybQZT(Xx1P_GgA= zy#Dl-Axe7{+(C3zAj-R?=^KWY!Hapt=`2fU8LzDO0bYu|;chARhq)EqfgD$nsNfd$ ziqTn)p0Zv!?|r-^eIwkG^bU6`xgXM7iKyr%3g?Fl!bHSEbRk!qh)5VJuDg$`hx3brVuF6CuuK;^_l{SE=!5p5qbijuUNx^bUX7^g zCFc8(D105L@ICi+P~EM8)^Ka0?{W6b+;)0Tbq)P3p{b^mf6xpTvL;Ul+z zHy523K6IZ@FNXewKXVGZMbIL2KVWx$_`sbXCPp8!dhF)&@_Ucn{QO%VbB0ImpY8)U zaroRR+Y#=}r>f=eWe-Q#ZGl$9wAL@$#a1y}#U-PJXul zT7d3n>^^nxx%b^9;Xh73H^2K2yDy#R)StP}-JD)7@41`H%kABzD@pjTlh@7X{!8aS z&K>tIl{-Yz@CBXE-T$0CZeBDm9e-1K;r{LB@N#;$-8*j5@Fn@*?n^hjm&5zry-npe z_jmLkDlgrC+-zQU?_cyE_g^=Qmz6xLm(BZ+{9pGx`X8Fv%i=XsuY!iEfoh01AYKQJ z(MGDV`Y(7D)K@j#T5f&yI;e>@z?)EStm>&+Zg#hxs*g9N(nQszmffvOZk+ZW#@`>AiUyS zMGuC`JrG`Xu907JuA|B|s2J{L=Oq0n!joYwRa>1xPll($nyQvMjh+gZyUD_3?rP_r zbKhA_ta6sR%c!kzZ@Is@EBKB}{u{o6>T-7_J%2bW>AUZ&aqe>58e+9`hO?axm(cS# zSmG|lS8|3G?h3m9bXIW0AI@6m4o9pd);NpZCGO*3m3xz}Rm4hnIeibD<-|jD1*>oA zUyI(xtMh%Xp{lEYf`5Zw_*!Se)$R?BUQMiW7rBc$+cJ)O=&W;o=ZJO0x6VR#9tUgO zYwmS-4RHg#!7=OUS?8>Ge#7^3wqL@v^sI3gxC`lDKs*UHu)E&b;M~H$b+5AjEwR>} zPuG*+JL(&p@0^?XI`<0u>xggN@2Py}eDB=A=h6ElSnpnPFT3lBE9e#aHuCei?rfyz zd-OU!*PTb_2KOSp8;JGp9Ct32ImBPV5A<(zs&VbrRWP z+PfXxr$G;n>hAP#=Hs0?-(qyJv&8Abv7Oyctd=;Ph^6RKXPMKJ&K~GIyq(*gGjw%l z(c6{i;+Ew6B~(XxmpO0I(-WPGw{_dm*_L<~bfdqk+s*yPor%t5)r+3DoLK#&Z}493SM2v9 z-g3*T7Ic(VE$Qh^y_ehD{StrMo#uXle!=Q(qPP1FmABp6{G6wu(^#kCxN<6$+uUtI z&iljA7Sz%?t(`VbI-)Jw)=BH6LEE8e@$~Gbb5hV>UZrqT;;A`9DmS&;3_lyzcN#cn z!*BSvo(=mr@1pNIebK&7KeV4yAN|Vt8vWXtj!t)Gpfk9#96P3~4u$%tYqE$2z&rgfX* zSHlKQL+5IE7Ej4>9i2>03y#Y~WOS0c$=qTp9i3_2bZ!$ov(udY%tR(9iJO$&^wiV2 z>D|Wom9U}H$hi_;#WPSz?`Cit;aQw!9G8X2>?C%RaMb0nk<-|@95!~EpjTKWauZX} z=r-htj6?=EtJ9R@vJzRGOX20PiIa`)rf5^DncN2SW+F1W3Ee~-o7t^TEi;kH&EnQ| z>!J0iWg#-VS*c`kv!PkhI=G2uLu=z^{0rg5(1?FAyo8##5&sfj(TFc!RmIQdWJj|* zIZ%U@MZX!}j(;vZAKLNHhZoQbp%wpin8V5Gybe|T98N6$ui?2cMvoo;RhZMs<-7`C zkIpvRpPPJB0kd%{V;)t-q<;v{v> z#3gl3#~pKyJH^yVc278`s3b#AQ6V(K*YQ_g88a6|V*+{w7)&Iuv~nu1%&ubkm*+^=y7okY$VdQPLh z8@R{gPQ;~j&c!8g5~2y|`-S=$=NE@3Pu%ly@tp+Dd3Mjmou%@NbJpQOyL%xna6;z- z4}IgK@#*-L`dQ~!zA>(Qk=+Y%=g5C`&N*?e<6hzkl)$+}{bJmCD(9T@PCPfxy-fX5 z+~v6cLeII(69c|;f%0?%Mp`^iO$rxgLF+LK8d@|zh_@~J#4Q!sIksCj+*T3p?5Md$(g{B z$Koas$I*$bK8-uT(Vr4i77DMc0OkRc-&{~ev0nL$2em-+l{cDYLB*8*Td1y z7%HDQyEyI>Vv6%Qou9>h9=8vl>g;fKI#Y>V=q@^@QU5${THKzvz35(6qny#4VHD9q zUE|jNZ#dE!<+M;EiI(b9&M?*ag8pf7pOJs+eCBM&zoha-+?R2?@e$5Qr==P}v{Iit z+t~k{_{{l=-7n+5ira+`cSbm^)HG*{v(=eKY(uxv_XU+{&X@m(qjL<9T#2G^MU^xv zYh%{7ZQHhO+cw_X)~s#Yw(Z?n>wW1T=iJn-dn?`3y_oLgD`z)xI-2Hmadt84f~Gs~ z)I%Q6d;A^#miPgGkH1!L@HdP;a{NJk!aw4#h@bIK_)B7hdO?gppH(5Jj;JdNI|F$n zg*h(d6y~UoC~gn6huOtZF}t8s$f+v|qI#l;Gl1G6sIXI%+2M9kDu&r5>>+fNK*j9> zPC=)hD1hpVB2-+y+xd&PJd!adoUd(Q3*T0Q=eBZzw=l&e7+N11J_8`_Mg-Y7_oG0q3%ID-K7N@tEQ;4cjc4>PcRi#lWJFoLp zJyUs|e8dve6n9EEeTZf30aTSirETf{XV1WA*fa5&_AGps-2>lmAHWaT2l0cvdeS|_ zt0>(bc2B&g-ODb?Y9*YKPA{i7-kVWbRxV?gwfhtEIM38`mB-0TjNwYRmmLH3wsSjq zoaZVxdZ9|uThb{I6a6_-STz?JE|LvSe8r~r>xV>>5g}26vd6|R zigr2jWu5X)S7Lco&WY?+v@6+>-6+H~N_Hev*`6;Jh+k?US|ApM zjuzvK#1ee5SSo(1Uur4GOT;qqL;Y0C$Sf6qWF9-O{hj9#p?=G}c0T*J{6qX<=Wud5 zKkS@NE-To!>+4=GOb^-i1qrde2k>BhH^+kPSjR^IVt{?V4ncL2T=b_@K{3WR; z{}a#VWOshq*_|BDSNog&MSb<8mh*UcOw<*$f5?J%A^ayJVdrKQVdu1Sah!|M7yGOF zrf}kKR{LdZ%nJLv{2>e35%xFrT}4p!P5rU6I@z2*)cm$}I|o%d((KRnclASkruIAj zgLD72vp89uztsP+4Lh5i9nVgOfpq&Hvw!hSPG;wyo!QCad}58|;uBgSOzI6=IGLFH zXn(R-h>vKc(3}iTMn^-L@Jxqc_7icEH9d#hMS+#)jDS@5mI%_0krdb8L<+$6H{95#u~#EoK; zuyD(k_68ws8{bG=FE$7pw{6D`7wd)R&*XC%&XJE}pZ!d3uvd#UVypZtBjgsj72jyT zv)|hr(Q2^~ZLrtd8|*b=Jz6U^F}u;;M*UW~O@5T0@K203(;b0F$S-m``E7C&qc8Xu z`BiSV-_o}kZL-5zZ>q`qHZ^{yX0>9M!v=0GFoM?rg9IN-Es%@+wGn9bK*|4!`>@jGqV@%kt^+0RPM5$ zF~1A#w0GN2?5Frsa=Xzkdk>l2_FnrjaWC3q&*pe9{)jkKyp*rx5HVDE{))ASi5K!E z{!$JVgT-FCPYxDC#B2ODXC2P$Ffm*_moGRDCk_((p`;-H+54`ehz%$E!B1#%(2P%gq3$;EOM^&`b-e3Tf2j~1=$l|0AxatBlR8dm2wrnict%@CB3bg50|acdfAEDjtP| zs`auJ+8{eq*$H1kY)?%)yS=@H*o91I*+niVcCZ(d>wwzZ{aIn0=x8sr7ug-rVtg@k zU8(FMyUL|<8NQ5BH;%i?PE>ZZJKGD0olz&dJNa(1yIex-LcX)z#hy>>L8iOx!B2Jx zK0qv%J@Fp0E3;kfuJ&Ae9zKszH;%j7y_oGOd*i)icY6-G?x>qxh4;%Gd=BGevZ-t) z6WfjKM0R4kAu&0bWHO9#BRdQ=wv&)gj5i=AWv-b_ikiz5vI(^*P;!}&+QxQ5)Wl9o zWfHu;7pZF@lhDyzrj(6jW4tkaDNzcU%&tdOGL+O#OkGQv7`4KaFiJ&zN}1fQOI31| z%ud8iE16n0kPY#M%%?`FWD2_uRVh$%I}Nj`WlFm?xs)h{omSS9^<`Sr0B<1E$aG}V z%2akOs#2kpc504O;WdfrWgS^prbqSgdQ_(&pW04i*C1wKHoZ*CaT+_VU7eT?Pm5P0 zrpMFaRf&E)Jzj-)Q^vM$$eS{j9oxQR-L>M$J1D-qE^jb%9mTP4F?&R<9LKa{ z*|)9uGJ(8p-67ti{;qY;iYw#E4x*0CfY*>U@tU$0UQ5=-YxC$j2vK^#gH*&ThUHL!K28i zcvKlpKA`fxe8TKw>xmUz#*l49TMw=9WJk82l7C`7wW7)B@)4PbxNAqUALEbY zV;Qs+$I5o?CmcVPPw^)>7b4q-@Tc;S)v5F?2T8&j3)^DO(iPoZtYAxE}ZA4?$ zRJ9bXL{sujR3p_`J+&I4XZSPgxz&)I=g+MdRx>J_s^+SNXepX=+)Oo44b=;)0eWfG zSI4a5_;Kq5e!@D5pR`Wl4U{+g(mH0LyeKE*lkoGz>DCo%nl;_J zWL?HDGn&fS^DEX>>p$|-t%>wpk`w8A6Q#A|C zv}SWW3qMEvkDBT7KY3D~!cQ@p!SR1`4zshZIo4U?Tzn3GhB#B6V16c=A!l(s6F(-8 zYawB|88R}SEKk=2Ly#bMb8&6DHBC^;G*Eyv(vnmv@m57^G_@5`1*9S=@V6)RdFudVUtatN`CHG`$&Lsv@h&evGQ2s;AW4Z;UmgYm(>I4Dc1QYw;F5=FLNSy{=xva&E! zLX}jJtr94TRa})&QLHYitE!;7p{}ZX=%@$YUG>C!s9tzaye_df-V3io+`+TyDRx-j zh&wo{PG%>gz2-0Tx49SXF}E{QU2R7-)Gq6b_0`&izTw}f-A&COb2oLr&3$z3#eWjF zS=+4|Y8$Glc3Tnj?MAz-UDWRK3+!tEQ@jZzJxZcek~Z zj=$zk^bh}M3hMw}`^_!ZR;!lUf@-V1)@N$>qCM6Qs)TirngixR^BZxqRY&zvo2@NY zZM-(;*=K#CV;|aU9WuXCbqF0a_gf#VkJf(l3I9aJCaaI?t2SAiiHFSy^NV>HeZ{}h zv(f6S`l*dn^;JihJ!~Feh5gn+>pk%xI$&+E`list6j2k1 zMe(Alm^xy;q3Q@aY>g*ZOpQmy)lus;Ge^-8YaHV!_;}(tj^3Gzd9S^;7NeuqSoO|) zZ;oZ=ojFF0Rqyfl<_EKrH9!qiovro6&Zv{s&FpS&HoKuMW>=!;TgH~HO~j5? zCu^YUhz6-H);cTP>Vnqe>#fdK7dp0@UC=hOC-pt>4dzCCBcl%1Ak|rQusRaE(%Z%A zOzk$aGun=CH+Pu5sPAdEw>nszRX1w7THUO*#CBGDGM%W}VfLn`7rvg@o!M?ycWVu? z51HO(A2XcTmX6M<2l?(+4{J5CFZn)ZUvnL?jn$Ufp4KX6dZHfI8F9=!Zk`dx%@gJ}btk4`x5s?2E4@wzk@^axZHoYxhDu zt#e|88mZ2Sk!ln^N{z-xv({;GMl3f^qZRlHb0xmgTxGVhTC+lLYXxicM!l>))^bLD zP;aZRwTw|;)W1Wm9{jvmK!uWz1qK2vqVv-ty52f>@I3@a-CsBXAzc~OOU=G9w znuE-XVzQc~E>eF%oDdDnhUN*;&}@VcG6&;>%?9{MMyae;JiByeTeF>+9#3bcCX>oa zZM7t(CEMOiOSYYv!E9}|!P`)k0i`!nQrB6fp)$3V#%gZ0z*{g%Lr(`Y4Sns+jAkqP zGNKG-3M(b`X{k(OrDnc^nHqJ(JDQ!$OjKqxlUpgg$7404DjiB|UE;Z16qm#lHCY`O zjm*a8anaapf;Tan;!VwF_z7lGu~H{9v)RIIiMM3E%qWwYp4HM>>8+;3EX-y$GjN>V z%3w7iW;L6W%Zjp?8Oda@GFpv^*;u!^nGIz%Gm*(?WwII(Gg}RbnNcPyi`9Tp7L?h_ z%5fIFKJl`cs-~#RJmyQ{m}tf-$3!+WJD%Olf#)!D;>W!itFBeg%7*IW_36(}CYu!% z&yLq2wo-|##CT#W37*7CYF!a6)HHQPOjFbG>1rxImGfN@EmaG3ROB>snMXw~GdG^w zjENs3_s|Tp5?N1;Wabm&sgcx7WT6*0{tC>9>ejE%=OY`QT)^ynV}Ws#_@6n$ye8(DSDBfEW}CBF zV9z;6(zoBz=}*StdaTr|g=#`wCJW=<#0q~n3Hh{}cd zb>ckpGPU#2TywE;jof0i$e2psbupjWdFFic5^;(-mCO?3igDFgg0A7$s9s=RWPSmf zZ!Tqai7}bF8)7mY*Tq8f0`m*e0&^L&OO0j5CF3%Fnb9P3vUx)+GS5@B2rV=xnv=*Z zCbP&~Y@Q=7r+%4{Q5@n`$$;J)8AL{6CNdet1UhbrB~&gpmzZaX>8W~eq(>i&%+zEO z=|p<*!AOTb8d=C>7FonW;!^6Dm`lww#I)k0an49f?MEXkvsuJ4@=MKS=4oOYan3kz zq!DR}L(Eg;hM;9;HY&5is7oWx8>!I+BPE$^Fgy$(W2!X6>4&hLM9cv%5K5lV_E~O(iZGncXbzDtwhO!YFT6Ft>?ntXb8p z%qlaD%B(cQsKq)pjhuAla5K4?-4RA6G}0(%mZ!eDIhKyCY67=w>7#u{bKa;#Is9K%XAP<6A8F@ZJepxQ=mR>=^RQZOw>HPM z%-ZHiVkxsUmG!BtXVm8rjm5_@%1dP)w+=P6%{t}?VgqLD8zt%3F7h#(*DYa|hrsKcyA6h^Pu`>0csi>NvTgJl8U{=M0iqs4>2*GNF>1%i!eNi@R>V=V=AMpQO-~( zXxOGh&PF?hALoVP@suL@`P- z69q*!6um)HnMH{XeU*%;MhWJlq9}%8n&vLyGRs9#W)Wg+R*NNc(;y#-jB7?R3lpOm z#f;)cG*kjFL4O=7V~aSPZ?}lfY&1hNb-FYZM?^LY(H9v-GUJkqBZR4O6vZsaOcWH^ zjA0a|F9wQkL?s`^jA|Aj#x#mB6BETS;?WmZ#1sDvVa75FGZPENG@?-%)r@B5Cq~Dk z;d#w`cs@q4sf=aBHVP4AkdJPDGV+=+@H~u;>bhYVM={el$Qj~`gGPLDfa8CRj_5~u z`iGH)TZY7sFgm7dhK}oW?x#M1*l!#l9y0#YcL*Ic_8AF8Lb1=-Pdse=VdgM8WE|2D z^Wn{LT^Jg!vC0XKkL!EsNGSHA7~+WWn~o#suyK%T8@CMyKg8%H^(XX``aj|xW3LfI z95sH?aTFaf4(JE@`uY^JC-qbMU*c}6Vu)kL596nC4E@4?QN7F9P5wCfW5#JJPwA)i z-})c?52G_2pVoI$6+@gbzEgDq9XECuJIS0hzL7hLP8esYJfol0f9k*RUyM#Md(t>% zd?lVEe^x(jd|`ANoiffCpN$ASg4`K&+Bi$*jIrAIL|l!|8ofAA4AI-zW^6ZlqaFAT zvi&I#Sney?QMj)=k)V>n0sEofM3ur;urOB z{Hy*A|EZtDzv-k-{T#t`y@^&$E;;s7%JjRD3cVgfgzyFpKYHtGY(3@`>78;L`y9HI}^w-V#K z8}&{2CVexWfYC603p2yeP<@cGfsR3Fpb^iF?{3xy8|%ppMuUvudOR}2sUL=KCJr&e znID1%8*$y?`UpL)8;>}WI6@!F>=0w9v5pwWjq8rohZ$=b4MRhXQF zls=rrwSC)JH{8^k{l#M$u4IJp+B6jSQ%Zk(I72 zhO0-S-bFq1Y-F+;*^G8XMXragP*1!kuTylr6DvhW(e&)pWHYiGZHYnVd+9Osj?BkE z(e)hUvl}^#HpG~E2WDcT7C&uD5i!<#Y6 zhw>Wv$>cMnNNJ?PQyHo8)J7USjgb~lYos&cQj;HVLafazQ%irTr)2J>F2xIdnI?4` zw{-`1^rc!&y%tq=bEY^IwUtg>(A+F$`84I`QtQYF3uGb(wrNPd}c#wz}rH}zFiuGA8{O1L7i z>xxKtBoP^pETZ61L{vPgh=xZK(edcQ5>P(W_9~N`IvLgkL<;9~0kG^G<)SCpMB8Ycz`VHP~vcGIg!>%5=2C zTk{$})cqnL9@6a>AEFJvP0FM2#9 zzEOlsbG?Y3&Q0%LBJ)MRq{lVl84LCM`U8C-3W`PgJw}VrLj8?aQLm)G#ouVTwK>{c ze6E&DTfkgUEIcAl1#in&@IZI(70pG{vLlv{hv&p4j`T6?2a!sF@j z@k;!x-?9E%?VVOZuc*)07wC!I`6!9IM8Bio)t8`q_&t5G{+^n5+Iy|MUO~^nndWOb zINLleFXzgmz2Xe(gOGa{!Q0}!~fYd(Tjf_ zG?9bVmU6}=dUjUTL_TdMtL8&_wU?|NUw?@b;0g4f+6NxPd%T=pUZ1BYag)09cdD+WD7m{_ zzp3BSm!sSGZC1>xWn;Ah+JCH90Oi-7)Bg+qrTxZVF#5zgAMrAJSv`xEmHL9(bUF&6 z0@`fOkldY(Qn)Kvf4TmQzTetst+ZZ7|4i2>Ewh$|u0q;0`U;_f+DiQfwJXsIeU?63 zPvOo&Dcz@Z{?VRl&xjGM@EI?qm(~kwQ|T^@3TZR-lx`|_CVeU0Rjjj8U!`9sexWi# z`=XW9OX-<7rzVQfRah&cO(CwD`#9uGa>j4cbuZhu{yi zhxkKAne{As8aFda>*k^>r{15sjaq*?HfY1B9E#s3X3{h3Y28fxNiU*j;!k{0Jgu9~ z&8<(RFE`4i_oH)y){pLu+HkstX&I?1s^`%s>r?P4)aF6C^}bY1(E6f@_(W}zHbT2c z#|SiB%b;hZD+4N~=cPA~-iNA5+DPp#RU^>|Ej@F^_4HH~)AQ+*sLF@(>bl3NUkMilG$&AuQYqyC7^a;!qK>77C+AVTp&}gloKAxF^sDM6}{1|Pl zc9U3$d_ldCK2{%xk7HDr<3f5uyf8k77(?r+_0nRX=-LS_t)5Olp`9c~<1rQ0qVeb^ zl zmP${pN2Vi*7Kh5%cvs>Ps;}WkiD#)iqeappQxgd#)#6eU2k$~WOx<<-2=N@1XYmwz zO5LS4spg_&T0AP_;+=`-nLURm*Hh?+=)0~RLO1Xm{OlFg$?@b`3fyHBU+Y9)d=yVR zNYzd40=?()WO{Nv0kiS71X@SpMKTxgq(9fLNFD0sJQK!Uj~< z*Xl4Di;vaDX${FV!1oeslN*PR)5dF!$TY)vDpu7{3?QS^vHGKzuLS^K<_ss%Ta5 zs#LsVK1_Ru5^0~we-fWXWvz<#mYGC&A}z5NAu4H=@yb-Z5s9_G_*>!^QBkXeS7Pop zxxe^d@lSje6|{=lS7yJ6ZybNc%WD<1SIqwtuaMAQA`O2<{Lbt*@m-YD%4*lh=lqk;tRhn_(GfmWje5HxV@P#yS!WS7I1gS$4xqO504^A$8CHG2e z+()|-kIlW4nz+CnaGDs!{ZssZfxBZg@m&_eH*od1#udaH@I+j#s)-v`B773pylJ8o z*GlmyxHd);J4}8=q7&aiYa$ij{b}L>-w51}eor#Q zCw{v%L>@kGGQB7?K8Z9$RK7JaL><0$GsI%Pc{9W-zJoPH7OoL7L?5nOGQ=US zT{489D;f<^g)37HF`KJX4e^L8f(?;|I}i-fg?mv9v5Wgr;6{3P$B8oBIcbO~+&yWC zTiiiwh$Q}7cpI1whS&t%!4w%>OGuH9&n40s>GAaZ1{_0VFuLMhjc#~1qkAaRgc%c?G{DFXQ96vT;0D zIO1X)N8`m!K8tlCoJTNMBv;oUkzMm&$1|#BDk)c8bm3~5`f32z7!9xn;;mFN zzU@tBCC6K-q*gMnx+%al7jslU|5DT+pQHNv`}vo##ujyqXLwwl;Qrt1_)h0P?f~7# z{Z9Mr{kZMU=Wd?F{2VjzX?y`bX)0h8#0&CCW0+gWh=a#5zVca8AwGSKW2986ln|*= zDwRT|B&G?ClQR+`ZD^cKB_}3T$?$ZcZ2Hhq5}uC`8Blt)JLqw!b_YEU)o#ecnbh8( z_nh|zJxbMH#(P4v;Vf!j(CgX9>|R*F9bPmwvo-Dwgx@I*;aBn)D~#KIdPACwk7D%(KbW+&8;?}Jh(?(+XTfo zx7rA&H?OJ)Yx!u1<$EN^$I#Hp3>2m+!)rba9r!Twl~E;Fy+`4oRzSx?bl;;vi%Jvr zPy(V(Pa@nPR-w0Yi0*qlC}GAWfNGS0I*p3NA&yNVRh4IPFjzH2l&(sB6neueE3T7=@j%N!I2PjCst*tI|-4u9I+bfRE4g=uaClknimfmR6IJ%P;m;jZdsy_ zJU8dUtc$Bkhd8~ZnK=b+%j4Mj5nL*`x~E~^o`#zn;AfK;GLy%y3n0HL8KUWygoJwz z-fbyHB|_Zk5{%BltStdSdM15A^(0UWLh_7Y5W3L}azXVtP#YfdV|cl>q4m~))%-M2 z6ZY~`DxU;q(KQps?ndH&^eNoqB0YkUTL+TwM&@RR2+7areHvonx@tPNC`D2aVdT~c zK16l#x-gUHgqX>5Ld@hjbj=Pvr|TJH;p)K}uv|U5(6nG=2s6{*x<*nDV6@f?QDUR0 z`!HMU1@EK!czsyPb6IUp@I|0nusU9ywO#~-s1}?Dy*eBZr(#Ml3M82+tPw@sg9_UK zHmk>VnaoU7HJ{3Pkc=-7?=sgAZwSrxF09uEu!_$!vjEM9>*^6&Cea;D-GSQL2$rhH z0GSw!0a99vW8^R(&hb1P1jj*s6^~^wpSZe9&V`j%O58dF<4t z@KqN=0QN|&3xho&D8CJHS>FU6K%@8>e1LvIa({sLhR6H{-s>Bf)cxc z-t@fA=kbLhZtQt-Jy`2qh|BsmaE~>9!FTsKArD#kL9h>m=~pmkU$JT*)EgFVG1ka{ z(!(fS42w85XILEK!vDrSu1j}Td>`Vt!bxVGhrvfsEq*}J^(e;~QHEe&R_+r>MgLOR zsHusMsdZ{r z3q7BpzIG)hr*;Jl;O5k22{FJsGxr$+Y!~7)x}L)HZOTm6;7wk&tQ=*5nYscdb25ml zD}v919wGEOmCraH&!`jKpCO5UhR@n5#Ar=Q^(t7Zt6)$krEg`hBQsy%s3s+oI7FyU z3`cc!P=mR{f9Av`xcHj53@=|3SK#OKzjcWEnz#mQUlZ41@AJP7nEaaXSpAx~1>Ij0 zxB2;M!sC!=;tPCzP2Az9t%W#0MbuXa*+tbC_}E2NN6uc9OcAau{07asFxL@&3lt;o zT}9X)CTg(|6Sa`~4lUWc2Jw5KIC<|{!gg>|OW@vhs2)kRp!xxe*SlKrN1&t{124Ly z8Vf;*dqya>JwW`vbID3B2ihB=!J zc5zo`UWN#?*`baPVm>o0=7IP?Mj5CZf@dUlq4p)r{+Gd5!Gn;5Z^F9G7CeC83}hvf z6_)ZoD7D$~?68izbKY+Fcw!dT%pB-U_bYYj9^Dd@w!d7#i@X&_kf^ z-eASOkZf}V_oAG5PMF47d589gqTZjCvZ5@3p7i!$PlYisjC+QN$LUyOXdoRLh7W^U z+=;WjW(R}U>{`$%v~$7X5DED(XE_8BxPZDIBF5$l?g`|AgxrhOdb0mPr{LRQHqMw8 zBD@g&0%=)qIK<%s>Trlfo11+e)=}FV^$P8p@D_g?d>2eZ?eIVvGy;xs0d*uqp3NQH z703-UIW^glfz-^82zdJ?ykpmdcft4U2(gy+`k>yyoq;@1ly?U5!cg8xcb?!e);SvJ zOHChkidaKDPUcu3RfvC^iuFbY+Og7mc1L*6jtT8TyC>{`W1BCuYr@B1$`G+OB^{$+ z&gKi|4{nD%n=g2RbzmYxvK@nu;XRZhkdo21Kz``f+o;XYo(XN)TcHj56g)}&38=*d z)X6|{I!db6WIu;?R`?X$8Ylo8+at^t2<^D=8IR!4Mk^{Jg30J8sZP^-D$tS{O`PHQ zbRcOU8Tll{lBxx}ENEghyDezK4()*fxPtiHpDU0%@SNW?azXsg0TutHKPLqHmyBQd zef&)NvL}SMi-wOs>ud0S^hx&27=YWvXAqln2cDrk0WJ+EZ-sWz@Kf(&FA9&4>_>@% zuUP*jROmc#>7T-P&JzeQ>t}}ti@i3?(0&`Qsd)v#JUb-+C)DP}^TMSMQi;J$4htH= zLF~I>&@m|Z#xF!RDD2ro%=B#RHSpM<4`Tdd{}ZBuVV#gYHxkmR(=iwy%x)cz{Ez+l z1CLMvKD5xuXlN)qY!sryMJo8vUjWYhL;oXUq!5`r60fz;KB7_x%t2g#!0c;n2PgBZBwfP!|r|Lq$TnIE)DX359!5qk=!#qk-Sh_&@xaKq+(<_ej&Fl*g4WrOpQ~ z;1?iDmr@tuWS3HxU|N?_m!Vcy=gNG~ufT7vrmjK*uExC`R|5{zd+G{`dHMM)RRGf5bmRW1k1{I1+ndL<)L)T5Mr7o4pXC z1ZShD!Nqhf3h|(+r24bp+w~!8a2ARdoKO8ccGU2g#!LKfsa=8=`xlUzAKE1%T5x6{ z8heGzrTa5v>d*cNJOb+a9O4)F<3hZ_-_X4jE%7f5(T^9h!UA>ysmdKJ3wf5C*neVX zAbM~HiV<8CsG_Q>Ma(V?%x0CZ(5dGT|D!5K@IMqYSQ9SvZGTO58=7}bbq5M~O;rRw zZB6Czz-y|aP;G0fVi0g^s(X-YYpUNcO>3$@FrsI%-dFsq|C@h$ASSz7Ob^6jSBvTF zOc6756Fa4Ee@0(HoH_X^A)UkCF0PyZD5q=*xog5n12lK1YS z_>a!Xfw;kV!O83*5jR+mOkGt^O^0PYiQOgQ1t+2S!HMh#;dy+B<@K4Z$8VR@AXiUd z7Z6QM2qfSg>Fv{yAlLvB^)!D2X6tj8;8c$Gakt1h*m>uOXNaZY;+?@y5lch3I~8*8 zUXv53EPj$$jc2hGYIZetRjG=W1!{(Y&;%p;yClua4H@H5hrn0hd)Z z1LgT`x+W{s2r;);;49cIr7pd7V4W``R-M#~PIaBYF?C#3reb}FXB`e-{h0Fj>PPt*7aXu2!UOBQ)wt#QJ3F!ACy~MYaOjO;D#R63fsR4!yYv_mS>L&G2U2 zBf1~eP^IBkheNLphZ9~JZ3sN1azDhH#>7YXL)^RTv=s9j0*^U-n49_Eg>ciBo51U<4!>@&bgOIA3CKH9q$nd)xK%|d?8o`Qg>~Dfc zBDz#6DB%YnSoRZts z`t(~?c*Ezp9^dAbc;WGf1j1jFGw5yx@wyp2c>}e8n|=UdyUwTuOzRfxQ=p+%xX$RE zXytG1exDCPkJuAQC^W_I{;9iKg(Br(%pWmtvLWe~C zK^R=R_<>&Ulk{W|N;m@C<{-p09jQLoBgRB%YaEz{_P|FWMEk6P~IzD9TSkT}Pz~YV-I8E;<-$x$v z2k}uPg8uzcB<9o6k9<;^6i*6s)%*PXo_dDvs{Q`hP~!KqM(n^DdQU@6j}CkPj8BN@ z{=*Qh^58;l5Lz^_~ci&i6#zfv4wvk8q36PtW?# z`TNm-7C*1f;Ai1Z5At0MQJF6g`%rNnB6VM4e`@;q2QYULuJc9TCFt81_#}U@?>w!J`Ry*z3)6OsKNdl>O6j44T5le5z>2)5bfQgW?%I8VePBX zuCKyf?}M)UJQnt4*yq<_tqq}fu)jAm*L_3%*PuTRB|ikFb$4pIg=p{H;Jjb;_kw+W z9jf(pnC(4@p5K7Y-V@#Ob*1(yMDuI(5BFbH*VJ&1hxvOjf6Lbedi7Np)mQ!3Lab`f zz0b}&p&NK-qDP>>;{(b~w>v;DC>yDi6vHSNxI4?$1lcqlXVCW};&xMC_5U)^jqO z!=DWT`#5OU*@^jhwTI(E48w=hlZ%?1u*@o> zAs+*GJva5a{8^};0LMBjF*8RK@hrsj)Q*L5{!rwGV(xukmY3r^eve)~5k~byDC_AU zT#toFJr;6%M#htU8JU?BqEwHAS3M4vdp>&e!X1Ag^7+${8;_4?PnOhZBA$j=fZ6;I zrc;wig(kt4P8IS=?6i`Ck>`{B9sC2J0DXlJ^d;n98TIGr8$N(InEW8T8?WnN;jzd2 zG4l-$QCHt!++&aT<(~O(VyKu7iF_!TA>1+VeOuXwd*;7!$9x}-zblX3`U86W6nu*B zJLIsb5MIB*2%GBrsY2v!W`Dp!%gD3-%KS8Z8vNH^D!mW>HZ?zCn++Ai#1}Ya(|upi zQ1P4DUr+$k`O^C$)G(+=5mXHme^eSDENVE^khfJC*r9(^S!kkvR5@s)e^hy28XO`w z~Tc;?b_qR}?i$GJ)4+;M>v!6mV>SA!x?}>L%!e9Cd`d^?z{*nBQzr$+sz7_V^ zhrL9ElMmj01ihc3u?vw8>iRwL9;$d@2=LG8E`%3?75~~P21EX}QykL!YtB&2_X@^! z2`Jb_pu|6;qX=~Nd*Xx7BP{Zh;rOHPlTXv`iKkQ*^~0-%82=K|bqU`K=+!0hlF;K{ zIHll?KcS+S{|VIVqW;fxeey-%pCMBhgD3A%t&91e!>=ywdydNZzAzgBy}CGipgf|g zxc`~++$rOGhW@Ch@Tnnv`bx0-$wOaBc074VZ3&3%n)b!_)#rUt7yJvOmaO_mtn_);8?2;$g>MPnzhPSccK*OLkDzWX?~MqE+~48R zFJPtbzQxS{fnEIva{DTJSHije0h@k4`h_oG)B@_wAF+t4zfi0H!g61PM2L?4%eR`Y zRlep_{Dra6g1Cm!U;M9F4W0TI6#Kc<{_-uPPxzWqwI;-^{*C|k{qcE(Yk>>6?rWJ} z1GoB*?{A23{l_;Ssv(L-#sg19~<&%H0bKTDkMNlv%m6;aw|t4oqz2&V{tCT#vS`T)vNI)_`QITodLk z&*4pH@JJqS( z4E4OBXzYtj-s5BLgx(t2-37h1DfuS8TGZ_b@vpZ#)k2*2YS6AX`=U@8*{#Xk&JgE% zhf@`*^%mIGTj0G{McaJMSfOc%XT1#$^)~jV@fg^G&YKX z$6=I!`uKP?=+_BhP*=mNISIH+AvQH(ZWTz_VdN8X>@h;a+^#T0!`yCgM#J3hu(e}S z7vw7HSj6Z&qh@foqx0ONq2|8WAv%2Q5cxeeRQFi0zgxm~jzMK~NZid~wns%R@o0=< zhRE+R;kmbk6&;IF43662F^L|#yCsD2h7iW%vW~|hZw{|MZirbQi+oIM&O_ z>I`|hGw%;SOzJSV6?FNyzE%+85!{-1ZB0V&^>97A1nde%kSv?5DX(Ccf`1vuB`FC-5coonj_|?;M=x#LhXC1ZsB} zEcc6aU9e9&9+UkfwF!Oa=sN41g#?`hPXcBAlAQpO{3Saf#P~~eU9@eSD>My~oP706x3~cJ8u*h3ccic(jOYA#NZ6e(E)O)eEU&qJTA3^ppGrp*TzxDc z%BLlIuECy9L-bsC4X&OxpvgE-vrxJ<*T9OjH5dkenvE&De7?W>U4hd|-J3LE?e*Q$+%4S&NPO!hit?IFYw zjz{bo!3x8j;q={x8-AU-G4@r+@?+3-DBRa!wGX1>It=rxWXHmvzY5#DGo2%OZ99vR zjt@TVF!Z>uFakMj-weLg0zHdLUGr5mp ztY+dY8Qp$V-w6@4Z$ntOU`~&vYm769+6Q)KDl>84^&=>(eW|+(3A-P09F=38fe^DF zK*WAvKeV$@lbJiZ2ZoLx!fowC?OpiRcb$9qJ@%=|>JFefD>Yf%-i#lF_}BNHY~-_Y z?|Od-*d7=A0Tk*7>|)asiuD60JNazfncff5bq})pLX_%Sqo#%;a790!RzAI~-~8jp{M17CoODR9FlQk|blk0+jz_q0dtp5PRLVm}cI`9vymL+zdb zaeD$B_yW}A$5U{JMg9;+K0kcwDfTp2a!K8M5UZ!cw4MqXzG#S>UzBxT@$U1CDhbqDR4=0uOr%wD}^=ROo6& z=qe1gIy;$cXc|5Z=6q3Ri{Mirw&kLKW{8D7BSg5K4sG3|z!hV*sFRbqS#Yj%5sQ;A z24~$P!exPQJso!Sbgm)v7}lQu$F3ro(M;bI=t^l;G!3VOKcYv*v+lMjanJqM=j z2CgHWgU_+o!;GHI(MB#VNz#<&%Kq* z7O^hGrd|h)I-9*tREJr;j@hl^vpq=^cfQL~Q02dIeQjxY-;>Bj*b|}reS+X!9FBK! zi19zD`3^n2B#inm%tqi7AP0Vh_FUTjiptnOnf)Pu%Hq)Sf65YeN%-R)b?_^dU+gc? zq08W9;KqN10bauSh)O!&sQGF~K%y>-mxUPrixqy#4^)+OKA=+0XUNs%?9Zq?@BY^9&w!WoM_V0?Bq4zLT9PD|6-W4pkM-t+%gaReQI32N`>}de0emGrLP|SJip_ zwzKbKHG4a%ZttPS+s*PVWbAFsuM>OK8#vi}$?OU3D9QD=>J{YbaP=B0b~v+p*`t*& zYwU0pfW;cFxXcn)_A9xCj&)))SJti*o7iV`9oJrSkv9Zy&0a6p+Q02TP`v-Z>R!uF z<2NMkKlWdI4RIZrwRSj_I=-H`k=_lkzyHdA_&-J)*#ni8$!vrh{)e~@cC>DNmqc|4m#&pB3U_>&|LMmc1HDT*78w&%U$k#46a=n?fJ$GQXui(F`epuBewD~2FtW9S*3~Rr=9EGdJw&h4?G4qzQ$fg0e z*}rBH6l>`$gIgW0mcp+NR|}zAJI(^+!xs{lK&%c|^I=u{ocZXP-4eR`PT4X_*HSko6ev4RNmbgh^SS1|9qjS=csx5S#48UA(aFOgFL&Z9_;}35MIG=C@WvBR z>0LG7mY5Kla~H_k9b`wmBlU?FH`lPXfIRsdBn@qA*i>@ z)L|&O%hVAlxy#g1*yPJpe;CwpI8R5e&TkvKM!yX)3F{|@X59tmc>>f8Psk`X*y}3VPrRoFU zbtRQ6RCKDk!m;iOH9aXbJ4S5gtH;K&1^PcQ-5*hV|LfxBJF%qNR@TVhjd`rZl_a^tTc)p6=y>E)u?CX77 z#DIYPKYQmLW>t}H{i?IiIZb!d-9QJrNgZfnlXK2FXNi)dhzg1zIfFz2K@^lA!3ZYI z3Ic+NfP#n_K`~>_VZPt0J?Az!aGjYu_kQ=e&-_uVYFF5)@>_4MdefwE_cw|22K-O2 zn|tEk!e4u9lHk664ZnNhUc=lA>(y&UcrWK-zYSw`QuuA+yk%ZB_i^&_tL6muaU%}x zel2ty?)DN<$6;qb7JfCH z6;+(w7R95o!EAg_zyVzrp72s|v%gNNlc86LSu*MsnA%H$$GCbUR00P0H$o-hcz=VK zuZLb{KSn8-$+Ni2tEA5XPhcMp<-oyyJX8+e_2Y0)=fH?wf;2~oT{`M0?A4{Bj=<(# z20V&=436va@T-?_%<0*%)4u`(c6qQotm&_WD!_|=I9w*GY}8?xuFFKd6fPT;10KeH z87}LJa8&0+m5VwA>vc}lQCO@ihL2(@!9`szs(jRogqMpt0&{hx@DWVq@L_nXg;n@p zhjCSbx4L{(g{Xt!3Q-lo7rA;NTrsK=co6#~IINGGL$FsLHwR#@t`xN&QyHvG3D^&B zb)~2mVXQuG4#HJ^+&mALb$rx1BX;<8=8f>1pg7q##of*+F`GCcW<9vxYydZyjUWcx z#5plb;b?ykj^_7ZT3?2HX=ouS-)6tdTQF2F;!bbDSN%4e>^E}#HoIZgu_tB;@lM0j zeTp5b_~R z)*r&YJ_o-uFq*F;v^Dg%frf!N|QD#_iScv^R2G?JdLWIor2oc#CNP zgZTzd@M-3_-J5Zb+h8rfnY*^dv~f(`Yv4e?gHwZBk*a05Dg4)KVai?$uX{UUwgp#W zH-Pzi4Q$qH;Bs$G{8r%Yad*Tuas2O1NU<)o&&+{Yd>^~y;I%cMivQMp1~cwHb0<8e z`^;u|r1z1NpMW!A4&P^H!8N|m%!Y5gG5qm&fK9O5gx7KMavSd7+A(O~3f>B1{PSiL ztfOx-4WW)-n~uWCQ>%UZ$qdq z>DI!Cy%vV~x|rL;?MT}ee40ExK&%a+17-tz{SJ_Jzo|p4+ruy5e*liu25@ZGhU5Bn z*sgEql$P3<_2Gl2K1|pL34OuT!f(Cftro85^p=`B!6p16aSp-&TMy>!8u(2OA2M~} zyFP@^i{>TVhhU-I34iBGcszH);JFf94x8srI8T>@%iuf}?t}$yY230n;iK@d8QA1I z!42LC26%({OYqmw)23bc7dXI$?ZWNB_AtZ$41;%v@Nb0v3aj{2aH;(s>KLchX9-8JOFr{4kWz#YZ!-6?FsPY~OLABU6dm*B6#ZlPZ=-9tf2 zTzjxRv40?5=kO1t=mh`z*rv1ILv>B3%fgf*`48;|DF_`!#@Rk zz-sX@a zVc3Bu;d4XWmvCkG3{QrY_^_Fb|D?Dtxb7AHBGe0>^Dkh)?irrq*wLpDXL8&WIMQD- z=is}p5uO^?50>?*gie7^x-Xov)9{%Z_b8K>#zk{1RAE^@Tz1$^l_+IW88-9|zJrUXgpLPP60IPhwoz4!{csm2G=6E|Z zZWfq;Uw-Z>ZiPg+Tl3o_m|gSRuX23xSFtyH zSMUmW;h%vAd^jBRqj6sWK7~C7{^#8=LGOn9{TevvcY(V|F^U+^z%xEPZggm@={j)D3)SgZHK{XUwjy)dCa%{|6p z#yU>#UGSa{hy6U+9)Mju*}ec5hm4SzA*`Yhw*U!$G`|NKJE(cv=1Kk zr?}I#m~p}3aAfa-@p>0L^P>oR9(L^KgZmvv_P*dSe4lfS*tT@;CL_Lc-~9lUow=<)nquWC&P%I z>a-_`(72|p)Ox5Ywg@`o;9_uNgsiE>A@i~_#PC59k z3*nQ7nFdF7n!{q1Vj60|C2U2Yc;g^Tr^(w)p zehPdSR_)O+OTP)*dWF!N!7F*voA7LphAaC`_}1Tc?AC8{{T965Vea`JsZPP@T@i-% zcf885ufGFFbmib_eBOf}yaH_SuamN3=ykZYD}>%5)!V_hVUw-`R)LlMBz*0aLMLHo zuMED<)w{%bC-@fZ(^bK$@UFk*RfBi^j8`81`7_+}G(6iUgOx+4f+4syP7(jz;G3{s zSBDe59Gv#=6Z4FBf*4goCxTVrV?O~ucID7}#6J~$119b2V0BpBPvi4m@O4?-S=t@HH5& zYk{@kY=6zG4J*Yf!RnmM@(OXQhdv(3zmV+xhVNj8s6qY_T^v= zPJ4MdSd-IUUM6*o&{)N4g*nSJ! ziuhN6>$)B+uf<{VEo_Tpir7k~F3hi$@UIA`brD#1D#Ptt#NGn$`^VnOpl4SESHsrv zvDedxue%r6)ATaOVeekfSDba6-kx1f%%Hs)Tp3&iYxBo2L4WLh0$2D)q+a8l^*#hY z~%{<`~@DuM-uLlg>S*C}%jIZf|sl-Xe$GqO)D{zFbChaOX!EfSjD@pMwyw{(4 zpTURz0r%=ox-8Bs{tmwDzQpfiZXy0^IKe*(e(bo!KMJlO#b+>Ne+FOtT2kExzK`9_ zbSG_l_`bjP+QVM*4fqXQt?kXXaJ9DQo_)<4?sf|d*&hc#0heMg=T4u)i2b>D&g*Kr zafii(ed>6$KY^(|VAp^pV6C}{Sm$8SJ_mbz74oO3y$%0cVY~h`_!;-&ZY~YOW?R}Z*GM3`g2&VKM$UR zsl9|<8|-8{6M8%DbuhAL+Y)vGVP81@>vO@yFkQDd9Ze_V%*XEwc&xwRoRmc{UAKqJ zybAAG6;sU4!}lw=tLI}cgw?ve=|H+HGZ(+F;HdtJl6oV2*X`juuWE|fYM68z#g#DK zW>}Ug;1Cl3N`?)>6q#Y$@jh*X9pRVX2*clc>`s`DUK_Z$vuzv9?J$F96R&-+xXrem z9j|?7Vs>&&&>OuxCdhsAU@~oMn7VI=gZp;4AGUNc==5pIF4EpYXdy&#cfA0%NDn7 ziMQFYW8Vn_`#Q(Nz81R$Y~CB-!`=W3eP?2J3brBM7RQCX*~=&POxv9Bjc{6Tgmbix*ucBPOCN)|4A$!2@U(|8eZeqShIBn)9!Dt> z_VO4~1_|j4|9E%O`~^<;UctW*t0(;C(Zt}@3H2P4dtTzi!fDIT7GfqZbD?+WDio`oMfZ!j+SloxIC zf_Z~adb^O2L^#Z!+zb& z`~m}ZGxIAf+Re;wFlje4gW$_;W(LEy+sq7sZMT^j3UhfgQ`GwzM(+fk_Z%uk2{3EN z!;${DmjEOB<2*S&_zX{c+It!v=|q^squ~>O3ijzlFcGHorvgdvqVFN?bFhl%g=c-@n-3CS0H60YoIZ!hupz*_wz?k6xQFkI({M|~%8 z^9Ngys<~-l3d6$sII&W|6nNAhft@`u_y}kpG6G1!WjEzLt-61?jV!NQ&bKFrmla9*c+k7ClmG_RF;5N_*~U~BVepp|KD zcEWo72u#+k%>!^-rvx9s6b!a8kKpq#A#KbK_^S&BcVJS3ZSiYk9)hd7t=aCSavIBa zxU5ry_rqD82Bwks?Fesc+L;I8v~Fr%g&(^q?slddEbK49()$AZyVt^^z7N)`Yr*b; z{e*PKbPJ5dZyzkt``}9-i`frD)^jklUx(QX?j=PR$GYByySxAs@xH+G;Pc$02c|pR zu?OK)?~FMFcH!z8?zA6%@aIT>H5}CY!ToTmcOv`{JjnY<+0n79cZAvYP~a-U55Q@C z0DkqJaMACBVR;|%#^Cn?Y}YTquigQ^^}{gE9)|h61F2tv^YsY)=k2*V61b9B2Vt{5 z2=Dr6%pvd)jO(NEd(mr0tfR289)&5rEgY{$16L68lGldoS72Rji#-Ys>z81seuy#l@A9aij8UTI>M!pwl9Jd@a!ybP0R&JcTG;0&Cr0|HIpk4`d8Fv(yt=QuRM z6a))$wn7tkzCsgDQz(R6ryy)_{IMIj|9Y5=U&SuT6J~fNF*9L6Pd6E+GEb@Gowfr5 zg94}Rpuk}83|AXTy8%3gU4j%dy%LVSy#!qCvtd9_CuJ2*B1kvy!R0(8ATHOzFby9g zO*V07!--y$(+#Q;r;2w9uGb-f;$AlX#W8chIh=k{&7F);jhI!vcZo4H@GeZRLju*! z3iw>Bo0TxgRyQ|`gVwBqtG2pX&Ht@#ZsA+ru|osH0`J&if#Kl0TrG#$wYtgT-g7_?U;5Xk}O1v6oDSp*Wx|e}ZI%a{l1V+{xW(lUI zDTdzyn5q|0@&e{5=I8;lmwFX2*{n(iOgrSo0n>|o4VWM@!GLLoR#3onqc04Y(X3<# zOkUd4fcX`Dgn)UAHI0B-OFtPf53|Z0Fe{Nd2TVEUd(aw^I$+*sv>h;?!Yv&zpV`mB z&ta4fm}`*{1WeCBFId8hm}=f+xRxiuX8Q%)&66=-!IXO^?8=oe6$5ABr?2jvA#OGA zGz|1Lz%$q%1PXJK#RuHseK^gVP+F#NhsiMKp2My{+AT2KZh;}W0(aRA_wF%rw=!(V z$G|(edu6Wg1Y6;E18?vZytiM$)I61UJO`fRUgb%>6^7qd#H$i$iTxhj<2AhZFg3li zJof__*c($`CzASW_-Ma|yZICh_qDuJ#I5OlNa$G@-W!?5rW}m4Tj8?Z3hQ!J?p6hC zfjxnA-@sz~4Sdbhc=}Y>X}7_&oI~7gfp-J7V7z}fa0>e)?(-om^9@ZSb3G}(h41!T zSevT_MslZWn5u#4++mu1Cr}$E{C5I%;Jtr`d(`$mCe=r<**7o^Ol~Zz+ktlib-hox z=f^PK*EbE!Ow!JKuVWf|CGguGxW+Mf zU&B3qh9fy(=Gc>ghVUJp3^d|&m6N1s=*`1_u6+&G?8e@F-1F=Sn6VpsCot48eCES; z954&)1m5m*xXqR5XDytA`+huOpK~@w9aGm#B>sfJ zbHu3w?!n$?Yr+n_kF~NYJHO!z&f%zS>X;iyJ29{u7T-Ex9hjV-C+0p_ ziQmG$mbhPVs>ByC=1(I24PY%(+w8J+;d9<)>%rc<%kJiCKk=W3_4rNfaisW?^CZ56 zLw_>yCxJ@>HO*v9E%Pjly7ggZev{Y-9P{&7;(o=M6JNoVKZTf+!5y66F$J?E@C@9% z^}+fuLO%m^)`Zo`4>{Wh&gDlBGz|-C*kUC1U7hM!^!=GZ31WZ6EOES4qQpd4*@auHVur%^&@yC_7&JafHPg!svV%jKGJm^WqZ=!~L|tbZ|OXF z zVsT&y?!j<5--tbg*5F1ModaeF=R+)}#QaXI#ewxUIiT|pk~k;jc1}kSCUaWK2Ajx< zDjO(yiQr@KLvJ9?dhl`l)^RRE3YfylDH{ph;Ldm`7+7lya%Rd}o6318o9v^6Y{G1G zr$nT2R>@BM?!;{31c)?FOSzShw7_Qk@3fm?#@@-v3WYciVvRcqVhynh1-9V7*=}+C z;kOW8B(N3t7Q2|LCra2IDIQ~~b>t72E@-rK-!gjI(Xx;@w)zskh8$DN6A zH)le$C8P$XIwug^WA6nkW7ovLhONl;ePAW*T5vo9Z4EBTIgZ3fLe;7{O2AKM`G}jMX{DgN%TyZ-DjS8hJ|X+jAsvsXDXoc@0qhv6~No0 z&PI8r2l}F(iAT@SGtZ+}=9#JJ9eIY;ckmpm@SfSiIntiFoV7O3q_9@vnZumw=^>Ro z49j!_BvGFE9=V5S?&l0HzMUDC$H;dWGKC4uU80Rn&5AZU!z$YBW=6W3Iq7)ZyKqIj z^UV^GbY_`m=0;?j&CGqAHrUME%lS^tOjBfEO_71!i@OP~4$NhmnEob}eRQeOX<&a- zFgi7Qq&dfq^2KIH)H=)q-~(s^uQLxu4F`uujQ~ePjRZ$VjRHqSrGx2F8DK_KCYTwO z1!hIPhA!A^;gjIW@ay1Wvps4D_Zr5XMxn==PP`N0*WifWj^6eCa5S&wq{n%2dpWoD zAR2o6%;%wlq1Nzn_27i_EcgH~i)$X66+4`hu!mu;0f%$a_0^$?q?re!^hPwLH-0lZar*cFiTw8WlACzSs<(bkh_&0lz9>6-mMINe7!? zYd%m6scuyy;`sU zEr_cwsPS`{oCxvn5sdO5qxi>2PO)RS4uetnX7N`oSR7k(`z*dqve^VoUNA5JDFGAD zx6&z!Ni#x2S1Ok6G9+qZIG(Zao@um!oT zcNS9P!RFX{zozb8g-u+3HO1EZH+F9zY)no{av^L){-k0H8}R2-aW&xGlpB(F2WTDa$FfI3zngN!{Lvua#b2EP0d!x5SF4&t2~wbkNom; zO1Y-|YW;_tQr@Z5wft*Nscg0QkNk?{l=4ftQ`F_4N|>KhLgk%G%pdbhxs#h~4gQ*I zets#p>bYFY%`fFqZm#9#mvSdJ*OXJrw@7{|2bE811tPhooKo(@yS!7bRd+d6^*?e- zIjH=qdeQt+9$lDgY6maOFXhpNxyDI%E}#7TQckIj&dn+1m-0?IB~(sv9t3tIzcTsv zYDqJxUD>!e!-7ApcqLq!3s9z%x-zDU`@#TEC`D*lcOR9B(v&hw43*jdrA+s(h^gfM zQGoJQf;*Sz&YTHAx)PvT*z!C(9aMQ!Ssg2DvvzsTP;wv&vW%r_0wa$xDYW_8a$-yg}81Dw&UNaj&uGl z{whg9(+2;x{9&~NAxw}QQ7w^-voWahsTNgjtZG;cp;6>-2$xD-V^Hl$K}?9Up*kAx zN}0;ub8n$9P~TtBeQ_G7yJ`fG z%2$SQ=fM;Pqp+i0&Zu86%-5^F#$bwp(OjtqFUFUvRaUQEjGCZ&ABXY#>vaAEr`_>a zIJpp1ucSU#s8&S1tx$b}dR3uD4W9cljxuriuCk}EFcCK?Uryvc z`7qgFe(VIEqCQbILb;Ufax07X^G6r)*m-%w440Rge2+@9ayNtTRM}Q5?_rv71wKdgUV2wUZ>5Px5PTlHF~o?hP|RR6DU5NeEI zaV5KNOTt&*s4w>aPUPFq_mBJs`JL~txcYnYiv}yZ_Yd$r0lq_Tu6{??dh^Qe%{9hC zuFPA8@rlPB$9o5H8~5jo`-{f?UE}_`aerP80bN{18?mj`GQKx#+oE^jz*Tx54J*8}6yHthS_(Yk3N} z7N`*I3;I3yR&alT6QD_RQ)S}Q8`xqOC+D7!94h?-X-#sf9_d& zO5}-pik_<{>M44z|3v>Ota!VpUhG-=qTH{`{Vsh`?$`bIe%Ga*<$qV?PyTEE;eYqD zR4O7R#DA807nP9Qe|V|yij;~-e#!RBORURL<*Qmnl_Sj`q(`H_qtd4QSB|Mn=xKTj z<)6x_a#-)A@~gH$`K@y8mpo1mb-w?3IXwTnB44B@onH?966lwCzZ^zN{)OdGPm1B` zYKhfa>G_;f${Xq3RNvHI>765Ap)c_3oBpG|&;M$Dv0vX*;&cCxp6k~)zs*#Oss2Sz zmXDs{yCc2P|Bv_a-^Fjy)h9%H$n)Rr{C4Tj{+pl6{@+t>E1&#!DxN>)|2O}S>F@bD z7x{1gA5-b_bME~2IsZM+cVFy%{LRH^$1mr(`Kb5NzwrCU67FBA$Iv`S zat)21HUE)RqZHRc*9%BG;_)BU7f2?eUQp5zjm{-2(WqVW56MR~&XwdtvvA2jG|Dee z8P(`N#*KF+(NLMy3{FxEe_mIKuZ+z1)Wd2v81F{t{=7r8M702#H%clYd4*;unxCk} zj?6P9m(bWa5!Bafgq#Fwe5rA=WDc6MYi1<*g2tm7HT$zCNf=V-lk0Px=0?ksS7-*W z@v`R3l4)oTRv5SX(Z<-4jYvA6F|*_+Md-UVa+ZvxC_T64=aR-WH5s5rg_;9qf*KoY zE}sQzJgAvtanP3nNJ1pJK=xn9xBq#5`Eyu5*OXJrJ3rSh%r8!wb2$~68~?NU<{lNBghy^UIffs{hhB_P?HA>bY`zF~8?he)&12T)TAt)!6k~kzOpf|MF#$kzVY= z{wvZRDyJf?;(wN3zGPedS8;j?$v={?V?jwlk|?hUpd=qjl-c~C))0~i%WDo`$Fd7M z3DEp z2%f?2K%Dk`=ga05unqQL{0D)jvHOxD7WrKg@mdk%7}y%Sw>bq5d2h^V@HDae5I2?) zz%g?iJPwmVOX41*RwR+W6W1re6L6DsBIH$Mgr`W^*_{I1#hnP;1$Sq5&~zeBS9ely zSNyxME9N!WO?o=k6Ya2hjh!KH5#9~cm7Og;VMFQeP8sfwe>Zlmybgy-56qk3n}liq z%j=w@thJ`k!OuXgF6Fbs%?Oj<4l~2S;aq=8SaZ(RXiiByN1V?=tv4mu5oRQq54(UJ z3O{iHQsuW_5PFW2FSH)@3F+#YcstUJ0u!(kiCMsYjBiy=y!ZtBOJaUuwC{D4NwQ;75~lhpQmLccRP_{GpZOY$apoLcNuLTZ^XJN#;y zDE2$n;vO~Ozf5C)**J48_BgjMOg)}vd73o_xU1IPboXN1BN>#$PZB_lpuUG~zL;a4 zFGkq+%p`JnuI8tjiIqW{z?!mX7W_o4A6c_6!}ZU&e{!q!oF<0*XSaTD>7T;9(^%f9 zu&rZ4?ANPhDfL&cx*xnGd zR}qVI-!bWy6&`#`GgY*>Ejytmz#f|pYERGvw{xcqp;{IG3-%0H=`+Dhn`O)5qy2Zk zV^4>bKg&+X6t_9}Xt&*O*wY9pZl__gZ8?0j=k8bRsf1+PshAR0>jl3sGWeCS@{a9% z3gIQ}6ii95B>$%Zamt&?W(t3>BJK)s`cK9!>0m{e{U_nBjJpzCH8;V02%8J8O}JKo zcVcgWzi%11jF2rDSY-%X32wsPO6V4F3HAp3R)Q;Gi`<6KR(NqX;9iee1mDSG{O-bR zgXv@yS9fFXGJ6PL1TNwPf_w14+dRkBESO+caeXfgJFCoY{APi(I6L4zeC`Er$KJ*D z9B?=G{rE^XU>)|e_{{<5a3TOqiTG{D+z$`STzKW5A!M$BFOiTPnC&oIJcIw!nE7xg z-iGf}T+L@pu^Mj9bj%u1oSo^8zcZaU58!^lJP1AruVOmpVenxX71J?0!JRN~816J5 zoNpF@3t*$?Om=wa4PkI`U|_1iJOMrd4~D@!1*Q{TiXJi@Oy@cix7L(2%P!7UDNqtz z$=^$X3NvORxjB(swYX>EGCXM}^=Ak@!Vr1}ttwRJewFzytuknKo!5;>;@l`R4j=Wh znvKU}d^x0K7GbXQQHOKotCG0q$7t>>nLq)IWP_3rBw`BiTnav@6%}7%;L8sFC!eb) z>Ma7`f6sGu_dkBMzTbbUp8ntS+>8I`3!kfUz>&4&K^!I;%!?h5D-Rfloq#LKjivIC zlfEoUvOLK$L!e}Q1zhW`(UsQS)ShdM6{Iw&W!IXUB!>TU&&rh>{?9)5e3{$-0Xct!k)q~Tk}jn)-_!a@9ZX$DmXbh8%Orz7*O!+` zFF+a%S)epgBH953h|vb$;-K_Ye4UP(l&e}!23M1ItPP>rjFa0?CMBP1hg)ly?Z9|9 zGnHhh2CZOw{7Pa

y}A56Sc-^Q%s4*n#j;n39ytT)l!~jDS1P26iA!Qo|~Y;iM&^ zc|sM&932TurdRLC=&CfX6#D7Xpk{wXiN*eACv_}}s}iHAvV>_Jw<6=AvRtRqPnQKH zAJfWNMNrbq!ni6hZYoDu8rS6*MHR-@npzs~qJN?mUG2EOR;_tS{&W^D{r5~z|I=cZ zB0tkz?xo{W{ww#=$<4-GDL2!(Rtd4>Pde8s8Juw$efh#ABP z;vh4``-pXraY`}b4JDRgCU=}z126+!ju&GzaUU`7#~fg!Q;gXCnN1xBj}vbg=?o)_ z`w87b=vHPn!|=JBIQj8Vje?h6xSbn+l^HWFtObB|H@^(JN? z#w!ouzXAV^lth(EjqZ!kQmD0wa_LVJvp2K8Ud-@L;_Af=`C(G+W1RCat%X_@j^4t~ z)zHxVKxJKH{0(3l_e^H&v<4IhdNSj#+rV|$$&A?6fp=ghGa9@D+<=`-8tDmWm0fcs z&6}=t^QJLw-gFhSvlv={tH3LW731237+3dWTuqN*4%?9#r)I6MGxyYtv?umn-h3ap z6MHWst)0wKUnlep=BVA=oV7b+&_@Z|!`O8txRR?k3F!uQW3~$`AR*6T_ArL)%Ix?t zLb@^%U4<_Uf!OmHWok_MG$Xn>;9T$-H?ExLMukr?)|-vb9L9z7ao>n7e3FsiEc|DK z&tfmc?+M0n&vLy8*W=(q>>2pX1b1Oi2WNo0u@@8LF>n#~G~Q%4xSOyg_;vxiFuPwu z_+yOOm*Aet_;xk8nt03b>kM|{Z!W{tiJ8M1!lz)S(gLo*mBf7VI`DezB<3~OgA=in z7cPLe2TBIN}OU`vlc#m%Sa^?I6e65?KvCGYk)25MXs;gDf z29X3n8Xzg4=JX?6jn}Au4EbQO{kgz&-Xxm**QjqgW*TkHC}KzE^3p3AhR<-?tWmf$ z8<#XsdbdM(lTqL(!e(%t2qtou2|VLUa3c0h{AW;`C*U&}qgM4cY|ZPFz$9V}!e=mT zcQM?vuxGk?)F4{ZTM5%VM{~OjP_wLow4iIiOnfxM%LFwC8$jE63#ggT9NNfRxSq?E z=6RYAX|{GbJ!o;R`*C$SwJ#g@D%}0(Q?t45%T+(>TM67Z8q?ye>2?pno&Ze9+(To-)0gK8zZxb{TrlohB;y}0fK zs#a+R-3ikhREt`f9=0^78DeEzr9h1wD&txJR^m$i`w~!d?IxIIu9siR2w({z4XM#f z=-o9>SC7Ap5y4`78_*6ccKtpl7!bCc(ZM2o>(hoTa$|tyj1d-c-I1^r;0oTUBO%M( zsGuXgv1Y6qC*24xB(~%t^%y}^aU(#D7c>H^!Z@M|zO}ik!Z@NDuC}gCZtL3Qw%oM? zJ$ei5HuTFaz>cox*Eq4J>z$>?SRHpY(yIhZ=UrnVUsGQ7LE1*rrdOSjZoRK}uQg|_ zENfL+>y}zy)~a$u7hfyOlA&m}Bb3BM^+703BCRrORatU+X?qBLy?L!OYn54R%hHP1 z97-#dTDR1yN>$g62qQZ1T3MFtPOXN}*LByrim&mm^%Sk5NY`DfmRhOQI&-czdu{5p z^wm|vrNJ((b=C8_)N|>#YkgVkCt7({-OtsQ*P63dQnWHD*`w;XH0z}atd(W0oM?^3 z*WOnRZQ^RBH2NipRZSH7y8*OgKy^_22DGlCRTb?m&^ohLnOnKKCX_T<`K5nq!6;B# zF&5XwWPsL%Y1E*xgJLP2MjV>gYDS|}k``(lBFSOI-#UNm{N)$q9{xy0=~XHuiBRtl z#3X^5uZD0*i!_KG#+3qwu%mDl1jE>QaHWD#*wMJs+}EU18ZRYEjc)eZsmG#bYzfa-5FqR$7agki*>+UUGSoMNR7t1&12UU*LdrI?FGU-^pM4GVDpY`R#dAO3SS0yNqD>ZpssgZ7K z8a^q6t7hpx>g&UNm9$u;z3Smx-2GLJBBd{=e<)O$3h|vqK$W8qzFD9&HAA?xFXEr8 zzpA;BS}YxVz0sf5U*(S0*Ze&&7q7p{9qD1J7XLlaFUpYOemi zzcVGb{;K9GCsd2I(;-rSRdXY?SlS|5S(7G+YI9__%YU{0s`fT_Afhuv@KUCP|L=jpjm5ZjB zCa#4o463X)!@nu*ugbGpVP6MZe3SW)oM2)HlVueoZB_6s0Z4l{wXg1lPx@4Jl1oEbB^S0)1RQ*WYDiNFQBo znc6t%scT=5%BA)dC4xc1R1%Z;5|v|>!2+N(+Ed-#q&cm&uOL@xJWm?OYKQdKq)jiq z>O!v0=nu!^_OJ_+Zyu=cDU3_A$3k5By6i>Vmlq+9T1vH((s!3ucYtf+MDsO^^qe+XM`zh6EI@;vncdIx>I+DyHzzA_rrx9H2%6R3UFH>oF3 ze(P)Wz4|kHcl89ySG})#0{vn20qP0#pEF%w-GthqHBR;3O{hWYkF}QAl)9#}tQyzM z)km$0s_d$k3RPZJKZPo(s*^(X%BqJ#ttqSB5^5z{HBG2BYqfL2c8u0EauJFNPjyKs zPCV5jq1KQMM(ajZuq(UkO85m`P12qe)mx38q$i;syn@RC)f>;%5AAqSpYCgrX)NZq z@Odch(swD#e~xw|xIC0`&HgpAi>CZ*MyL^A40S}aL5&1sT`lwLlj@vigQ|IPv`!^( zOLD0F3fT@NSCqU>s5ztLYC@Hq3|DfLGX=;cl^o@m>X1r~a?+pAq>#6obt#`E0aQIv z{`)JV+Mid%l^N~WQ~gvPC-a1S#8x@b{=RrnwNbnL{Q8+dY?T<*QkBRQu2Q*<1q))Q z;xDa2mAo{3H7-fTPQza%)GwVXrG@a(yQu6I=KTwRD#3+uNykQIT{509n24|HXB6+R z`r!BIMe&#PMLDUOsa=hU*s6`HcdAkP8;M{suJpI0hhtsMG=!*TTG0K&49%U#F@x6H zu;$j+F^krkt7hJsQEPo$^Y8Jbxe9kFdljydU@3NDm$J+PaF=Aww>0i-+$C5K)(UWO z+}W%OYjrpacX3v$b8u(k&SJ&89PSLcF>hvj{#R;FTh7KA~BKP?B?H+ zO^sou+6&+L%tw2{Q&N#N{#`HuR0J!+Lb4m4fJ$H`uAkw5SR-zd3b-q9B`MaG%!GTA zejfAMp5{4N2`a;^QkgX3Be7@Dz9CxgjcuW=GgNu{nZTk#h|LqTlmm&{?tJqKyQHY<7SHu9|?yb1-0aVs*6k;oR- zVE<&qd-9_Ze?o6SoGCvO@+9~a-}r+O7sU_6`4QQLq^^=%j%1zvXG-SxMhp|* z8!=COPs|@!h5rTr@9_T~d<2Gx38WZ-c7^y4zBS@J_||a}d`sweXl(pS{BFGKEU-Iv zS6nl}ZrHz>?XWHUX2iJgn-QnNZ`|iwbQr|t5XSt5-hx;kLXP7hgn!s}A^i-b3|+B< zjwK>UoRIZ!2SM>k1RV230Jmpb5qmnlL>Fx9*eNXkZJV{k30Td_r_*mtM`C2~=cic7 zsU?%222MqG)dts8H;11BO4_Ft8=>TXpYWB|NdP8+k_&2GMkq<)`}S+}X2h5Fl{t<1 z5mmk$ViAC|U{aJ^^0L|aF^WnY?8==z)k-@}GI&YZP-(d_xi?8W^d++yd@ z6?)g6!WPrm=Vl+Fdtv$c7}tI@RX#TRG0(%olZWdAXujluXD1rhK{RNh!Dy~uMDHdB zjN$qaZZXv4#eNAqL?ibOcQ$;V+PhD&4f;x-f}dj>BNifK#9yXOJqOG z!4+`IyaAWc81O3ab?lq)Uk*>m3ftMN#B?%OIwq1U2^|BY%~iy|8uJ#sA}ehtvyAvR z!PIdQE|1ZUo8%h8jJbwbZ^1@#GjUd7I-0St=@_$=_{(7J5Rc0hn9)|_ixy_J?Lc0v zwvx@PCS6CfgqTa=l^RQ`QI0KU6sfL&C8i}|i>*c*w^&JhZ-M({q8Uk?QE-5Wf#zD$ z8M6kKlnLMj%KsY5jDg|mTKpH0b}<|v$B8|{G1=Tonfi;l6}A;h7(OFFapa6A1=bq21s$2&U~Tye++gF0IgC`p;fA@*{%$6~?`7QlLHq4b@+be}Ns=%5`kePKU3 zWctBobVzGb_9fQl`hb04PC9IQ!?bjm^}F8oi0K7O(-FQahIPQhTxmTphIPH8pw{`OMZQb`(5yN?6YPaxp)@;57C=khbxx#v}53l*s-`` z7%jbs>p3_2c#f+i+%IAmz}A|;bGY(>8gK2ve#nis9(1Fy2l2_rT37@PO4k|Ni%Ki2k3;hweO?* z*%qFj_hGhKhhJ+<8(4tOpzGNVj-NBI-`q|}D@{1==Zn$@*;@1q* z97djLTs6fsvrTX}1*c;-2AhC0unTi1&6KqERRq)+Q)^!p%nN*Z1-A-Y!L7BHH@mRQ zV>CawhgDfg%kN}_Br?6QPPdfyf9ElIMsGI!bPR%V~&F2z`de3n^7br_h+m~QZSA?1e!tc>Xa zUsxG)8BAqmOf@*m%5Vqm>#suE(wNPRa@UeR-K}J5HnN#H$!1n!Gu*0X2L9=8rhg|W z&ALqdHN((qr)DXez)h^aX5pi`h}J(fZ`lZLWF53PKANv&JNE{zs+t6I=scmani2&`{r zfVH?wJzR}#b!_g4(Ogh-%$lI2@|q{s!mW9v=9snItWy$tns~nDpV+i&sq(gJ|IBJk& z9GcflZ&NZ3?E?09mrBRa-<2EL$0^-R$;c#0C_vqn{-VY#iGOt^x+}#}xZ?Tycy*U( zcW>?dm2^SR$m5=;H_*FCd(_|Y8s@zuKhRqS|N8b3ok3Xh|ITNf{}f3q{BOJ1Q~W=n zxA6be`OlKPLf4WR`R@|h5v%_id2jz8>IsoQ8Tp6)*Xl3$|3H5<@(=a*B7f4?SJ(PW zH0^>`T_icmgVCCpBuY^jt&HhD(ydGc6Y-U{rS^;KiPEgqs8?^|VYC{izbGyU=`|$a zD^7#}`J`_(7_GWVCZy+TpZdS*xfeb$p6BR2{uR&Fm*#%;AHVm{pR1AJzy3e}`EyJ0 z4-CD$q+BJ*y8@sjVUp)3(Fc~qC!22*D~cq1>dgzd9^98XYJE@g#|V>)cvO7mHH`}- zAJ%A7l1Isnm8X&>OLtp3+ZwG%+N_+`2uSj0N&Ym#lH^ZPKgs%{7|p2^r{VH>X(Y!M zYl_C8LX~>07le(J zAHO&qR6q4sRVTFrPwk+XMO2ejr^O1PdM>^Z<&aij#S;-(iPc~9`9~DveBKDZHTWZY zgwGqHf2p@nJD~rU+Zw1H5O0INL0=-hWaV&C=ml#NKK(08d+L`!3LKKbr&*J+reOZuF|EuHwUwfb2eySw%QnhdFRHF?StAkkY z#CRuOJh9=aZu&fi(!D6lj9Z!)TAvHK)j6%vDJR8~D9%0Qo7nftGaHxYMJ3nTiC0ml zw5iV$(_$s&$?CbPU@E&Yy|nSAKP4^>>FsO0uf5FD+80lUxHzQWuYJy%gXIIIe<3ao z?Gw;=-`BeEnIg6KT>A~AKjmv(_*zrqm#o9gRWmbR>q1PF%z^0}3WDk*#8X)xIiPed zw2N81h+?wzwWh?JsC8KNJ7QFnBvE~n&y1-#n0Ob(!02;mYGf}KO|5%Hw5Ftgp^<$H zBA5s7w4*tT9#lJ=eP+RbHoufdkzCU{s#a4Y`6ULG-29Th+drOP%BkF3 z`^WOj*N=(hn&bt4n_rQf63?XcWiFOqk(?60sB+5Z8&$4dJinAvxw+PaobvNac@)Vt z>B_YDYkp~dradf@ZD(R@CZ>HYxw zCI8V*jvV(6l6Ms2K3Q%g<(C2JSe0|7OFKu3GKR9Wnb{aIL2~9IsB+lS)#8?fW>e?1 zuS9H*g?MY#=oXlkL2K`m7ImrN{`uUFk~hG|X-3gQZ3no>_H z6DNgQTG`cq?JAN+X)>iiyJV#6nT$)?653~?c0niIRKqt9*Nt46YfPQgev3p*677OC zRMl!Uq9*$c6Vmk*6R`R{>8WbG)X>#()qKt6)s8d(rLCIJ)qb@m^=U!GO_@NQuLVlu zGy#{izVqTAhp9_zQU_m^UAZ;u*FP-*YJ~oe>yxTgjA)hmS_-OVs$KuAKB?aJV)|&3 zeu$+=?V(!3Ki4PqHAy9vQ|%H;K6k!8siakrmNBA__K)h5`kJKDDwPJQ-!e9GrPgOE zlC?Q8w2W`)T~jVqL&VlI?surE*a8Ksol zCCMMn8&tERT%A(wQ7Q1*rBuJ9*QNTVcM-3uG)`2%)SF4;M0F~L+9L^#-nuyTM`K{s ztXOJ~^kSuHmqmVRY^nN{m%60+Tr*5_@=`f1ePQjt^;w)$*Hoi4;uhnP=6Cvss%z39 z7WIw2?JK^!1C?7OQ@#w$S zLe(Jm^yX@Js*|t!MzuWE$jK1yu=_t@Tvc4FQrXonq5h~^j|g+K+6v{3az?F$P&uad zL8#o$i>n-eJuhyx145M!)hwY(km{GONmrWxq!wIbj?(-mf6kj9+n?cUe&3pZkmyir z<63zVwxU!>zfP#~p|(?~GLedD1{TDQu+pmKE#z`pZFE!eLpiHk z)`(nJ{;Gay_n&f2y-Nd1l6L!LVCqrMG8`&*)B_2XJL+SE%16!8h058B$?Y%2e-mN8 zxfp+&+CkMVjTX=6ztIR$bx32zOUdmo#ozY#$brx2zqwEj{I_y@>FY*Hvh?lGFSmat zx7VM~WxsN#i?BDh4{B_L#3+>?^r+4-oC@l}^ojvDt&7{xK1`Q7BsqMx``*EdrwhP=1 zO4CUi9<4$3qYwSBe<8kk=PP9 zcG51tn&^-&VbrwPji8pfUV9mFmZC*k8?DltT%WG}ebvz<)yQhO>+zT4e-k>Si||?K zMp-NH*X}-z4YZrDDyUJ`N_?~zu?4pF9##Q0M!gvy@%Tu4P24q=L5;yy;d3*3o%30D>w)~H;(NLd*8l+a6@0#4yN+wHl{#z!ZohzqF%CYy2I4Q`I8-Ls{5hY8?Bd`sb) z2ugFTG+4^<8>GAaoI6432NlCF-Dy1?by`nH(c0*Y{|5An9t5Rlw1Mk~(PlbIZ0R-~ zMbD!%z8`R<{rR1_7HgdL^LOT2>~Pxo-iczJq>NVf4w~VKmxR1;?oOrA0w_e@l9b5 z{hMyb>wTd3ntEflgWJ)n>Wz5-d;l$%WVFssfMTjk#+(FCq7|2nc>{cdd#!U?H0Xd5 z7wu2%wWMAT-r@9dq)YQLVaeb}*xJdv7R_&IaTf*)q4zB zmvtvJrCGb3rlpTW!TCvl`gYkrE_q({zg6I`rk0xOp7)RLEgoNzXn6Mp>zxK<= zqEC1YI?GYu)!5hJqdoO8Xwr%YAPS5^|MpsZw9`HseOoaD4c9fvC#J!P#USnPn6 zmMz-0xGlP$grMj989vhb{fxPvhi@!%c+bY7kNq=l>1D^FPyH+SJ9aFrYriuC_?S|W zM7mGFPq<1#!}uI1P2(i=lD`C{pPYma^ViHCzQL7u%Q^?dKOw|FAH?5p z^IiNd79VzkAD%;qTs3 zO3mOTIq-M4`MbCD49y56kJPiZS4Q$Vy;EcdS7fbR@&kXR+~2{ay<0ksMR}_=b?tpo zPWt<}{F7JweO%hbtG}srdVdF(*6-EJC@1}WMUk^ulDBp1<+JIM_ssn(7=wL+4MXpfWR29k?t&$YB$Bp1=1YcX#~ zE}}ixT6b0ts6E$OyO&%<`Qz`r*6OqJO4=6MYp2}PZZGMcNJdfs)atQhB-Yg+%a=$B zsM4u+N9Q6*awqv|JfkGZ_atMk%LuFvKD9BDL~E^Cl4#&&uG$>t=XlkB?@p&Dgq7o2o16B!RlhS?a?i1D0c=G8EgxvK_= z`%AL;C}K!QyloC@OsLg{mgI_bcD34&=4xw8@<#h#wJxC(WLh$s(m!lTK50ct>llUk zyV8i!m`hxSlDifqRB}wo)zyBLBoDO?QjE4wt0me6n~AU1SEOUB+9rOiGK5LS>aW2_ zuBz5jIq1vzTl1b8;j2Aq&D(2)uY7IAw`o2oIb=)zf+TfnO|(-WggcB8Tbgzci#M$) z|2@i~WV4b(3MI8uJ0fgMzNiHeN;;%=L?~H=+7Y2-baA-qQ({zx)Q$)>CRf`bl)O%T zf>820wID*t>mvH7{*H6WS5?z$lB<%hs=n1AZ#4^0eXC9$O1`T4R*l@#XkYbBd!aSL zSADBOE@@P+`c|2o(Rg0X!O|%?;y(m8E9{j6 z8i8jxlzdfnOeh{T)iI%DjFLkNC1sT?N0J@AwZBRs25L#=Bw3V zD~Z3UclYIUl41MY8cF1alImAJ%7V|Jq1Hy{Vn&!iRImKjrzw9yHA|}j>USmi(`rC-N<)NA#Mh3} z`hn_{&#vL~j`*x2`eQ9ARX!()>RO~uNk$m$>QpX&iF6NDv-}k<>uQ$dvC_BDI*7kg z<@2DZ7HGXhb;{>c@ps_*D_p7<;#1LzR|uCc_4Ty`q(cy?U;njrG}W*FAG{8#UlCpw zu{uaDqITIYJ1QkANq+fKojZRW?az2wRBA8A>!8-$FR3b#DuwhDcmMT&qyLJWG^~E?k3Cn)UwbZ}3+7_|m)}~bZMd-iQaj=IVi)#bKD(28X20k1 zdojP~@_Vrh`!BzBQ7?93|D~SG@5RpVztoTC_FO(sj_RD+oImTo{@8PAyz{Xwk_?D^v8#4v3%wSpO?#L<@(#cOuP_&e<4jk^=KFC#dMxjm>x@-ZR)uqeVMcc zG{!rBeE9GFOJl6_^+5hN_Fq1~V}3?bn!9P9rQS%=3C+b4F`8wI<62S>X;o`(rTLO} z2xwP}G})6VZ<-TD*uu0sS9@N>p{O~EG~*59N`EGkiccM@8Bbj+X+~YE`A=PZ*i~oM z1J%R7E<5csPpZvcJC9vcc!3U-kFx=q<%*&n<^|8yC1&Iz-H{n?2Bmu_QM`X=m0wi z9LWCN7VPotLr4pD8>g5-?A&dMoUu24E!n@@8+R{E3HI;ya##XM<7He4B`xfMEi47= zMt5vsX;?S9X;-B7N5Z;svl+(DYpoRwXWwKue7a(C>BuN zx7H#?*wtnTd!JY1zlxQCA-Ha#G!BLrVlX?SZ(?WpC~!G;7w(#4m$4uH3h*ZEHN?Dy z-LK2c74}x_)?jOP%HGPlNGrREU9xS#Td{RgL0hmb`(kxQfv_F>V%H;cZ*T8FUMy_S zF4)`IFWV8k16$_^bObxHw^Szx2s^RE^cpLs|7)z6{;%drD8B!z?A2B%*8j1@xrY7o zIvHRbIF?=UIxAodyZ9dkA4TSUEk5Je6)%bRm3EB1-&}|LTK45%iF>md4KC$sGkflr zI+VnJv6Xy(v0Z|_h`sn*K}q%(TFLPjT1o5|+C^O5XcyYMK}qZv*c+`-^7;AfR~Jeq zf5cRV)#C^y?l3a#iR@2L!Ax=z>>Jp}T@luhqoxvEAV-OL#7UMXA$y+0&frwyOBy}_ zdkAY-hmk~9q1+C^RmB!!7k(#mxVI`#kEGDlI=Vhez^pZ%slZcaunQD&_s6o0xHMgT$;wE zxT;9%959EgPQ1Zza5%B660Zm-i9=`JZWuU>uqupH(rp#OisG({U4`omxJ~vEqYLY{ z``j!b!&YWBB@_0Fz4&%urB>^^yWCo@&I{>)*#qt&T=VTr3r7{J2AsssIs&I4vl3H@ z)tBO6an=!ZDo6*`b)NyRXPqLiod90Xnx9rHCbAw81IFMhuA;nFYaDT`T8!tPUWb`w zZ*Z#>HxP3o>xg-{7SGWv)-h(mBO&G^;cVC>#=$Hx7n}>5#8{*C5q}*-D<6|s9SU7GrI!P$NO2}wX=LuE9z7ibG3QZ+eZ>|Ezu-lyLCFCS)v6JzcgSpME&YlFd;`TLbtg}F^!+ygW>r8Ma z*I#k{I`}pAx2(6$0A~>PrCXu<(yjFAbfnkKcdWcl2d5L`d$$hzJwD&D(()y%fj_Vs zI~ANt*g38r1HZujkyYa<;1t4i{?lWi&P&m$Q9_-X@)K*}bHTa9`$|^n8lXCzz*L5z@-}ub5w0|M>);k1SV-!Q+LHuyaaYTdPs zTZwJs)@IwVK6@4)oe98<}K6Kt>w1miEWTQXq{F}y6>Xj@E&39xPFhBLM`l?n07|91EILvYGVsE zC-5a_+P5!uf5`;23!ydG8o&C4OOmGj{bE6>?qPj_kyV9& z3yH*4OsXp>6wCL`b)Wy-+&e0kAKPEEh}_GgMd?H9;qSkYl(QnOsouCRrYo&rUx(sk zQoAk`SCd+Kp%|wIxNjIhs=o9v{qY%yxy%EJya#iqEAbmlt1yi4F@%U+YzSAZ=kiQeaIvq#HJsLBC{MbY6hpxgJpF1+ zCvtfVX~z;{6nGW(IQ&L}Bf0mr_>BU^V}2diSAyfP#rZZGRNHjDn~7b|v#z3by_$Q9 zIs9r+S~n9&aV2^dW4P-?Qj9?hL(FhDknSql)rt5|!i=M}x&i;m+<81W7F%5E#+;1h}H!^}>LFg*3mw+p=S2L5! z1Lol#tC=fBGvZ#%Gj74O1Eq6y3+Wcq3M}ESYe=_*G52cX--=ldF6U0S5w-$cgS{5N zm5irXkZv7*D;Q_5B;D`)XH$*mrWh7FS7o znX9{qw*lOOeK&FM0Po;__u#hy+`#?r!E9z^eK-F1V(z48-AwxX2-(a?|4vfhPsp9L zlv|0lo#$?4WPBfScJS0z;5O_Bh_waW!o43P*4@k=?&2O|D!Pj~$KBlHVa)yDgIqmA z$UWda-02a_4rU<_6Z$AKVV{*~JN@Mj?*AC!J3y^}Jx+`Vz@6An5O+Jco%=nB??d22 z#C?+R2j~kQP{vf^DllVWw^-l09>}Ofkhy&xe$FrCx7<)a!Gj?HGf=_d`3s(z9 zWYT@xO}d?o$(|+V9ox4Zg}iI{4tAd9R>HM>NjqnE8zrs-uVd>rj?gOa z7Ruj2i5tLMiSH!udhmMcyNkRVz#FJftGgS)8#(SC@@@ie;^=!h>JHGko_h(mVuf)t zwcp42O2NC?x{vKKFqd1X`+knQ1)g#*M?J{a?cnXy{Se!Cfe#QrOx~TKYm7cZ-d&*U z<2*v@9=^?;k$9AFFW+1DahAs@dpGFJ<71@m;~VM`%0EGg2SAj)_&&OyTGb4@pRa}o zsP!rKJiyn+gB<-d;W6+@ww__%Bj8iS&xW~#yZh_&*0fiJ%|$bXCQGGBym zvR7-Jx?o+7ewRHjgCh$gz?Z50UBXDdL0_TP_c-DezE)qQruRAGRlZeUr@jveZ-MWz z^&$J-1m7qAh}?I<4~YLx?%Uvp#2<6UcR*((KcU13@FU_+NDb%P)34Z13GeZ}`3^OG zM%j1x#{86=&j~6&zE4eGu;+cyZ{jc6^8xq)HGReQr{EXFUvrj^!H+5XHD6ox`HcCJ zGKJ(L&R0l2;f#gES>`19ilfrxYf7fcXB?d+pHgdanqg-vq92yWep;S$GsdU_DAPV!+l`?5htpC2me$1Gu?k z_$@d~!=xqq8i9?H!G)HTs!!UP{Z^D~oV4PI21#pzBc4G1zQofWxE;Jnz$Xg zTY+te+mULSwCC7XU^C+OlxmiANSrC?z}Z=qG|^_DBjpBx?T9;3sukmL9XMNOLTkn| zT2WsY_OxPDqcb^O32hk>X~PlS*wY4VM_t{?Z4Y)O?vVsrfW-On9-OfQBSYON(=*XB zp(m+x;@%w50qnpTdK0=brrC?VeF$9`c^fgjEeRp ze*kCc!N_UPWb4A#?CC~YkDjebaX#wl1NNunKteCZUVBi}AVObo09%gB_FCKHmto#&Pse#xh4z$9Rq#$%tkd=bS+OrQmSliR>B8Smp$BwjnhJoJc&Gyi%}~ z82 zMtf(FGmEedqrfxCnN66?=Lv`GlE_O3x#IAzL#U%bvjzi^!Y7NcU{^EGBn0xR7`W=bFPv_}rvV zVJW3%k=DLtDXF=PfiI@~a!Sns=TP4Y^5%i_sBa~C^TGMlw2JLT;0of^Y%c~^60f2D zC7@$_YZ7ghwq-=B7r2NsZA<7)dKFu1sd)vsn0PHmFJ{DAg`9O9wTAQ(&bE%4mN0I; zmXg~gj>&CD-g45*Ioo!WU&om53hLXQQY#n>cFb)D_N^w}fzmrrY9(XG+Uo4c`Fnw@ zh!VrNq88J+GzuG+As*HhE3 z!_1^#FGy-ZgPNZ&ym}m_+XU@3Ll@^3uSRml4ki40$fhbs21U zd0@njC(eVd%6wM@=DQ*=-<9y$H3}?I@l$&+A~Pa%5TYRM1hpT?6yoEpYJNIHTNIzPvkOdswNASSGAa z`u4;!;hn%A5zC-=27gSfChyL0R5|haNR*r-1V1p9SVyT#GCZtXU5IbAqhd z5lxkyO*_)5zO(2^s7la3fuqW#UD5idFjU#GYYp!KbJd4JRy-M$|Egy#Yj);!f5M)i z{ue5A{~UJexSy-y{Ty~GhdziPca|OhlCTdPRStbHLDnosK7=4^mK`4&IIj$P8`6$a z{t8B15v<4=)L$3%G&zhQca~4P>fM2$-YROgi;h|yPB<8pPai?*kid!$1tVWR6uzrY z`=OxB_b7OA30T5;T;clHpsd-ot!2>i;$uk3o#n;Hl8W5CpZGg?seU->iXIJvbuLZTd>kl8 zK8;wutf$TCY#j${J)YX-!xKRHuR5g1!&7DYXA(|?zsjM{BAf&-bxusp)05z@&XTF1 zdNSPAIW!elPl2bNO5N(No(e;iBcDr zf61CJ1ZCBF@5r6?M$udALU^n`Df(_*1VeS6P7kh&;ij_VD+#h@=lEpJdV$H5uL{ic zs=$1&4ov)N&U+c$RMz}gf;`$8L-lYkhoL%SD1*KNlq2hZb_IOZvF_{Hx&prHSoaNV z{RMPPTkbptyn*qL&sAlx50y2F@!_9z)vsl)C~4zl$@W>6J*fx;(G`(Xc_Un1i7=bUMfPH zb`DKl=-c6`&cCS+EnjxlPKI0x%9kGu%=aM}aZNaDP0r)Ws-km-u8}G_=lCe$UQj;$ z7^(X}+419~?g!=5GGtjZ>e?_==L==Uqe1!dlY#j@6*%})obe&Jsq=p-Y(E5x)eA{J z{3s}^ewJA7EIWRV@EA;04*fjgaTux``2~WkSzjkv@hETR>T{eyZ>Hy9sCs?ryCPqf9lsHnuMBx4 zY3D57gcsKV>u{d82rq-O>bFU~0?L zzWhG5%Z-PF^5xG-4TIgvzP})R2)q4|y7ln+5H9->b?fKz5&ZS<)UCIVJo@9nm%j#+ zds-rcrhejPX~2^CxYnDCNA;_KUkRw}0AuBNb zdYnrJEmN*fs17&P+p7Uv)nTX3HaBFe2Iw4hBjQ@{ROi4OvsDY8>dbi)wrayuoqLxR z4=ykx&sNjGe47RK-HbEVgU8CGw<6Ss#nz|p=4{o6oi?CuX1a-663e5tFla@PHOr@4 zlWGFWl-rP!H8+Lrwh7F)4SSj-Z8?_=T0Y*6bIG7(%I!(Xnq|@*NVNc+S?)kya~Ny~ z(w&IKmYkt8p><%$Z9w^Qm%u~21kNi@9$4tY9#@=cQfLdx#Jh1Wd9;^ zx#ZFE@iCl59xZDgOG*YUFD@e`ca~d^BPDB=9gin95|l$vAeJ?c=aoTgrRDk!GhwA#Z@B`*ESRWPU9JN$8y>5* zm+MB%fxl`6wv4U0@KUYAma`>m)?Q48+^evHJh^jgnEp!6C4<)PY!!J6VVqi}t!8Tx zj906*HEb=0r)ssfZD7G`Ny(Ju(CbLaj^)tn1IJv?IeHf4z`elb#OuqMvP^utM4OuJ zVAgHH*8GC);m+*}+ryFDgYC$5Efn*$E8Brs)apzgEoYTkyW+}f(%P-Bykv&(1jS14iz=FIzu_zy44LEq5;R zXt}dIT9iA>qyJL|Eq9JQdQ%21caA(da_7jSH)YVW=E$RE&CWh+@!}k`Jo-Oj(2+aK zmyd%{JMZj_v^@Ho+&Qvo=ZiOG&~oRGY7kPA%L0=4W-Izhkon_0Hg0kri3|cnrtnuc#v#dEX=pt*54EkSl=NtdQ zoyWpuok5mCUkQVCF1yH}<<5~ue?JC&9gI2h=zo_%%bGXv=x;LU$ercU_y2=I-v)F2 zp$uB?9C>u)&XGs|HyO0txyYlRCjD&S(K6^q;IDG$$fF~7mN`EGmz7PwK>U3fwA?xJ z=>K;abmY$RXt}c}kKU9!%cf<}u4wl^%b?}XkwYZc=SJK&~oR?M3JiJ_e0Cr_HgabHa_1tC z9`_IK9C>t+J4YV<{TZ~}Ir8YpogtXZa9WX&?@AI_TNyz|D~ zS&r=Nb7asP__DLl8~AeP!Y+X+?*hNxm^(WMz45$rWYCTf{LgXclo{luVQzORssCBa z?eA-|t(|tX-2SGu_HyQZwdHoEc{MC{W6SOB!d!E-*8b;q+S+()t-Ts9E5nX9+tE%t z+H7xXt?i6-wAtR&T3eg&qRqC};n6}{o;;QG2FvZu*=)<1cVkxAS?LXy+uydS zy%(kB%h6^#T5HRxi#FR@aciwDgVsWOQ=9EykmD@#UZB?6(Q>5Ytdb_*>*lU zT5fM_vn_LW-dUUNXuqw^_BXAywdK}k`%vb4#TIN-_~;bn>O28Ye&oNO>MTnZLPh*PCHs| zf74p~Rv5IF-kaKNJNq0hw>P!f)=oQGZht>(ZLPbt*}exB>wI*y+%DQ|YoYyJmfKH~ z|Ie(oABG!i*DXUH4Mv-7ZL>FTx&1tQzsqLZd1+^wp98hu-n`BBC}xwRowk#Aw9}3@+uCWr0dv)s zyJ)Sg4R+CHTTAR{vmNcXKcSqn&qe#~w@4T5x3%2yMN zZMNmPMVoEyw>P!cj`rJf@b9wOj@H`Ia$7cCwAtRAwf4q#+S+w*u-5*v5bd<1&Gx3& z+S+MHo9)e8Yeze6XP>puZdhO*7-k-=vcGMut(|s77_@fXD38LFwbm|yxyqyK5;kwM zy{Waf*4N*(*{;squXf$hW;@z%N1N?vzpdr=zqZ-dD*InqZWnE~wcq~!HrsLDSCbwv_?R<36a$6hkXumC6ZUck{Y{(gXs6xIxnJ0QPkx;? z+dtG=TRZJ&v%Rskw)4$Bne{E&Y&RPjcvBI*6zhjuy);> z+H7ymT3bu(qRqB*&?5-WJ4gHNXt}M0cC_4%R@_={JL5c({7r4PwZ7ieay!~=NBiw> zTW)KEU9{XT+H8+tCRl6jXt}M;_NXx5T*^G~x2?6c!7kctYpoqEx3$@BQJBJf@dnH7 zXtTWy=DA^Z z`I|P|T8C@7-Kwy`a@*NwIk=p80rSAoa$B42XurLJJZ-kM){d6jMVoCcv44o=cF|^g zX_#-;X4|>xXt`aq+1_BS9qqTjzsM^RM*$Gsq(N)blgX%Z7Af?iyx{m4vyOLQ{JZoOAd#1Lhnvg1d zs{g50q$;4QgQ^FiMrcp$anzPnO;nXpH7C^??ajMIElRaX)p%2*QvEk|Ox3QePw0oG zmztLK2r4R49UDRWB6|<4>DwSJR8Be|WW5M}sP~s>E7UUsa#36uW1Y=yGCF z4LUW0ME&yhXBYL**Qqkm;K-J2kMxgz(ZDz~)c2H~47WEDFuh!^sP9d&4)rj^|;aLy0 z4Xg902dWxqagCmlw3v!%sJ75HO}R(?npG1`g=fE?T@NtoprJcLT1DB?aIfp{>DpaB z1I`t?f}<*(Wu(+B^O=#IwFP~a^yKXjT2FhF0?&}`X^)Wb4B5^;^C{1e?eC~r##7{d zp@&A!lcYYCwj&j24OdfgB}Z3p^v-e>rPxj-JWJk#DzsMSSyEfg)izyY({(s|hx^xY z#;UZ2ceE{3jn=TWY@zD3hEISkRD;&AwOn~Kwo^^o#FmQBlPwfAXkBBo*iLnLs?=X~ zolVzlbX`YR40DamppHdeeOkuWa-B_A+qAu0x6#!bU5C@vHr2v(1x{Dnbj>SOGF`XP z)f;UuSKD-rO;^Tp-Nx8jScrv|a^+1|+jQ;Cv7yauAv~W#o7qmTv}sG(Hll6Tj##wK zVlSv>j%%d4SA|;FNcC8iYh5GNJ3w9APPC1^ph~x{k!nw<8g2_(%AQb_+~%~3J)!Ek z__2ZZg8rkPpuM2~v=?YE=oL_xS502~!#i*UT?GIHg zb>%kuL)S?4iSpSRNSmn|tXA-#(6TBDyGE*Qt-whPacy0+sBC#EN-C#5H*rx2e8o(P^wd`Ws~`bY3G;$NkQ zriY{lr3a_K1P>uTh`dA6Ke6``@N(i?(%aHo!P|*{oc<`?Jw1V%PE0Rm|0U_^q)$k9 zNq0+k1$QUjg;Kkx2d2NKrUMBFrFW)xaP*yoThimxGdSjW!U^e_q>oRJBR)R;Gxc2r z{)zZ3a*j)H=7?L;W7#?`JsUhWy@LH0r3X;+f#6}p2c*9tK8F3rg1;yJ3#BdsFG?>= zpG==lp8}sD-k*{OfWIZalKmHg7p51a%hP4)(saM{aQ5s+*gw6BJr|@qr$6C;>`d4t zy^G&+6L=@_qI5~R7+gxch@+RLceCfFbf@&E9I;cn2k}m%c21v5pXJQY5uQw+Abv8v zhjKT9cN6bO$(_KT5#LMh4d6Y*JEVJ(w*z6v^gi-#NEfCnIL|`DqV(PL{q#NX1LAGc zN$JG&dFp-~e2(}9;>Xhk=}L}Rkgg(LKx$#SApbpAXF>i4uF!(~ob(Uix#>CJdFi>} z`RRG!Rs8D(`333u;MH7(1^HjotHEp1zozr^U!?nh`=-AD_e=K$kKmfk&yP%x0FO$K z1b>$v1s738a$k9IzL~)){FeI$G{he=clXrb@K@e(wE44416qoG@X~OVb46m z{PbnE9|2z?9>;&32u?`HgA<8gVb3G!+;m%xm`j+Ke#A9-7koE;2mFw&h53D6z5ITz z<3j$$f_!2AKzcvv2h#_@htdbZhtr3^Ytw7M>(Xn%>(lGN8`A63dHK3@Ex0~i2X2?H z2e(hR19wQb2lu3%=H)-9#pdOEr9TJvPWJ-$N%scl6PNMJ$AOcH|IY7v2Ye@eJFSqF zWEHatSta7F(*bG!^keqCosOks890S_Y&w5SOOY z*;7gwlYU0tn`xi4U)mS!PuwTnnz#yQ%d;w3WzJcJP$65Ce@4kg`6KDW;456uMfs~- z*+uzl>8s%D>1*KM($~Q^(!YUkrf-0sbB;y%7wPBVm+2Sa!(6Yq`C3|IZcYH_u{Adz zm5u~Qr=!5qbTl}fUpY6Q!S9`$&rD~4v(lO1>~t15C!Gz>P3NS&`OSU6fy7n$-C0(Z zU!7;wh_kF0`MuL#=^)}>>0sjOu7vSwM+tVy;NahtSt+A6I< zxg@JW*);1xnVxBnbSQC6@{+81+A?jCHm6)munlnwj&7W_poS)3bK=GP>qYtEye8!r z=U=5?ri=5h)33ln_BEJf1@dcUHNo0hEwD~j8?2kv0qbRTvpHO?k?EYgOWGOinsx!Z zrCq`9X*aM(+8rFqFPoDOrB`IqL-0>Y@f9QJ7n#%+4-Ejb2>Y(pVk8#r1imu zX#=oP+7N7=%lJ+LmN2eW@ko{^KMW3w??Y4&OIN%C=0mW?I-Ve%>I50k$qAAuhek0*C@Ha;7d zm4Rh!eUN-csSgMrCKJdTolPK&$|e$z%HB^tXaD=j7sT(A`XHG^?#OHs`$uK(C10}V zJ;M9RHsp=Wwjqqj-c7z@&%1>8lBM~OY;d+TADRsThh;;-;n^^7L^d28%ndD{SCG4A%En&~xY$@@a>}m3!NuEw#A$~e}m3SGsv$JLFpOZaB&eO?L z$!o;R$(x-mC(O#8Beq7739szmgOq~&d8>do|(-6XJs?N>HOMd`O0hs=~dZE zaCNo{T$8N^x6RgMGxOJ}YbICmP4Lm=5%96(QSkBPG4P4xaq!9H3Gi>6b7uZV@;C6! z4?!?<=w1~@*sO| zCES+$n7sAbj|uCtTgbmPxg~js_$O?y&3?k3b=gme*Me*L%{TL#A5Lyg9;VdIgjo zCD$f1^6Qi9z#Ee5!5fnsz?+gA!I{LDCx1@<1YSXWIcK>d`6XxAFZ(57U+^HdE=#Ur z&t-(mlY`0IH#?Z{i|i2MUu2giSF``pMagfo z-;i?w=?jy?v)__FBRMNMGdVsxE;}|mAv+#CH90*wEjcwggZNbTo{^kH?lIX(*@=`m ziEwOoN^&-PP9dC{oXozXvy<6#Om+$}>E!q9KRNjW@yVo4NlqpAciE}zKRP>!{F9TD zl5>bpBloE6H1_;1JCU4|k`t42iC5%DWQS)f@*}e&z@xGw!Nd8r(`lItlIi(*l$xHO zpPUC?kem;m%aNy3*NXgf>N_esBRie+3G6vBIg_mw`SGMrNR9)KPtMBDBQhmt-F_1<5j<9jHnUnhSg z_x$XS*(KS<;KghmLYYHR^*x;UQudvfUCN&Gv&)Fj%MK?05OjWzAU-%blK66R&&@7p z|9ROjlcUJ{CE?)YPvoAH{fRy2W(Os|W6wc^UnYMh_Yc{h*>g^I1@RxU1CyiKe<0x? za5}$!W&Q{L#mf9IlvtTxnf(R4D!UTAI=c$|Yj!nw1;LJEeaH z?nb;TN9_jgO?)S%uFdWwT$AlWj$S>}@_oR4*t&~7*JO7QR_1pTugrI5?=Hzb+1;df zBE2(SMbk*#o83dss{G!7_ht8HtMdD^`@jdX`@sjZ2ePU8c6b9#&9%UqnrnMCHJ_I6 z2!raq!vf;q0MIm65f{Go+u*mN1&EzQ|f)y}H&W&r#yR>^b&5 zls!$EXTV2@7X@#sMby0>53O~SeV$SeX3rB=nIDqld_xq+#qUdmo12amRVe)4km66sg6 zmqEPR$eqG0!qnvL?5*t0?49gwa6B^zGn0?9*R$8M55bSXzY&kaV{H~QA+wlK`8&C< zWq&8UniW0pW-=?G)#A+L1ImAxy$^l>zCrvkWnaz8f}LO)^^8ka^D9>6tMga0SF+Xl z$LyWLFT(dOpQHC*K9#MB*b7brClG%^9jkM!8uPN`J$~t%*?ZLdKKLdvUW4rWH2Z`y zlQ?2pGKqiYyv{V@cPal~rl+CmJX7*9$!FQ8l>9vV3>-~PY4Sz(Iq6ZPouisU>dWj4 za#R-@obW-GCwZ0ptL)3H5Bod2hbw_adM71$fxHqzrMy30mqVE2)AO?@dwV4{ zD7!k(^Nin9kx&5hkS^pUxifPE@&0rkZve*)Nh+|nV$RGQ`D^l;d5wHcUW<55UYmFg z+pF`*x!$ppbNyl`=TnF$=X%gi&h?v+uZCJZX6sc`tC#eqOrN|L*cTqOa|s#bL^meAefU= zA?cQP&Aa5aC|5ff%%0LbBR@}ilG{1&N$8bVr;a*FbwaJAd)|#b-3dMOn&j0=da%_q z*H#}3g2G^G_@Izs+y6mf8|tb^P6;E4L-N77>v5*ZhlC{2#*S-37?ZzGNwo&@7e?o!NRK8YK^x&SMnXrER)uX${xo&EYVVl5 z8CacI&zeb~8V@K&=Wn4aF^O`)r#f#!89mf%5bJmICg^&qjTr&10oGujDvU)viRan> z2IJ5*+4m&%JOxh7C*}H1j{(QzWAlcLB-dnwx+dkEy&juCL769m|IX{6N)@fxGd6#m z{3ozmnn^YAWDkNWfp#fqcin~16}zyz$-lHPA)lBtXOWlXerbh%mSohNH0UhN<&?S+yb(XPQpWlRfCJcf3AO!^@p5KAa#dH=V7;7Ji^;Nl zG&2EPGb+C|r7x!BB|&4TEWe2K#aOPX!lJI}gUo(7m!%%g_26~b=KYz}b&T#0BzC22+nUgccL=Peb^+bcXJK#wfJC8$WKPEYazc% z<)R7s0#XaH_?(cda5O%jkgL312A1XH^7-HbRKO+?qtcsSh|bU{#HaFGEzdb-DK~yN7@r?N8I`bhC*F}?F%I%=YY6r)&kWUeEgldui>HkH&gfg(~%` z)Oy~IGTUR({bNd~?zJ!0vuAJxuI9I^`Fjl(p3dkE#!g&iwDnl0ufX2(FYFse?g&s_ zdA*x|5$5Nh?&`gi(MX2?CX0Xsbiv7RC5`Go+sZ_o`corXpMfOiA z|9eWE1L_w$J?OLPm%TSu!Do^?0~_>N;B?}d#Ivx_Rc~3VX;rO{!aiCpxK-Fst4F;p zTk4vx;!JA6t;72IH|*OJtMNVXrQU;@e@@VgTYYh7(d>1cWvfM~57s8GNvZ+p44pG- z_31sGvvWqRA^oc}dd{ddqQ`fRuNt8#Se-4c3tYq2IYDP_U7OdrLg&(&@iuY}u@a#L zSeY$ne_QarbLP<*wHCa~TGE3$qt=plmNS*ksI?07%B^`rW#puUHoRq=<#aBs4et)E zKX{!HZ~0$a+H1>wxaIlU(r;|(54XI(w!D|Od~a;|j@t5lxaE6(3s2d?zqatoEqr;) z_{NrTn=Ru}TgKV8j2~_p@7*$vy=8oU%e=#u`IIg5Ut8w&w#-*$E%t|7>?;3HvxD^wUIBYq=RDJ3T`Rk(h?Q&! zcCrQXO3G6uVarnPFCq3gkFH3p&9RopzbDpOS({~7^-(|96>hF3))ra2WLFs07FmmA zZIrdG*24O)#M;MeCGRS!(F$1&<1>Tp_+PNa)*@R~>u9a4g|ha_+D~gmeH1lD+kI7S z@A-!X`?(yY6?@UHy=Z-}C4RJq*Bjv;Z0Rq+@?A^%Q_F4rH?-Dh$FOeI;oAD7@ffvfn;6=2}8~jRrcU&PhTK_K(9sqj$==bvm zar7Km7Q6@EBKMhcuc2s9KegP}Udwt{iG2pYh@J2?SV~wHJeKrTir!0lF0H}~VrNiK zh*iP+VHKVYyOGvYVO4$r*LYQ~hr_DeHOf}yu1>Zp-=C|$3LoNM7M2H3o#l83Jx1Eq zdYAK$R^-d^CVGOj-bc&vWqJyH41b;F_~+aLx{mSkT(6)hw31#0vx%ce)>pwROD{5g z$!Za+Ha4u>ze_(1y)otle~h`rg(UiW>G!2yh~6Rdi1irLZ%iHE=v6W)c$VmO_8}e* z(JLZ)Kj;OaXPf?QwK=CAZq<|3c&Rex()wyev;WLT{&T9NUmV)}X zti}gs0jOup>fiyhI@h~pb*?YVvRt3HWq5x*4Z8Z!GW^Zn0bOfo8D4Ggf%?BK3m$UI z@S01LW%%G_Uz4cW>Ejpu00)-)^yu58&(ElWo`L!Y z>My7lk-kKw#CkC5$EcrU^!U-^P`|_a#Cj&_pQLhIL-HyoDz52W6#ay{5O?6{;2%k> zcV)X|4c?*S3u|)yy4K|SW39>cyIPa$akVDb2Wky|QDZ>0-`3=KJb`*Xt;zL~TFU=j zmM_iqkz9(uVg;}SmExs%MV5eiPAl|piL8fw)EUmnNR;u zy+B(fMc+|_xq$c$xMtED0XCOM(aP61;qSCQI-H?gcjEDlEZcwi)Se z{GKJjCs)5cz4sat4=wi()=xNk7wZF~Utl9*y$2f=hL?LA>vgQ3q27l29gZmXSJrPi zdM8$AZ;ir8yqJ5J`#FyywFH0Yk;K*bSNhTD?^uoB-mEYhrQIcYRnpZ8uHQO|$5b!L z=zXo{r2do9t5SbTJ+t-Co*F#Qr?54gGWufblNtTJrw5is#h z+{;{V^XN4?l)b}pz1HvT-;Rvm+9Y6(7*(cd(Bjz(`$Ja5U@pLH?5 z-%G$!bcz?_C0+`SMVojrKIdb>ad@UjA9y|37vrhUs;+p!j={54-}S|K+m2y-AUFu$ zdUSa6=)JE$Z4W$k$FR@Ua2DtK^Dj%f;CrjLZuG(JNvy}ee*dcy)dy4o&|g=tUHx~X zM!*_M6m?BMa=~KM2cnm9hv2Eap1eiL*x=XBwxAx+WASHh502qKjK#0HAEQP5ae6x0x9^86+M^A1& zx}$Q0$`tBTs7aykw;tg7f=5M(J%g%5RHM*)Tp#l0#Cnt0&!f_WDiymW`laiguAh2T znoxmaSA5=E2G4eV+*O@Wd%~4-enBkm%)hG5Z*B#)qHJwKoqS*REW)dPEZchBSIB?; z4-Jt+lQQya;c2QKKw0qkFT?x3I%&P~%Ys+_Lh9h!1$B;v`TnSLEX)r;onv88=UA8@ zg!V^*?|+KNe^CP<&!b*RR3uTyI+oPRUc4qK#dZW zN)ASQM9l(~3)C=Bi$p~d^-8|XqRv4XzyC|he3kt!=#{8QvM@gyWs-&Y7g-tmjzOzr zA?gZcY<~uRo*kPUL(Zq9Kg*6wjwOA1(4bM5;oa&ogb0!)! z>eQT?M8$_Ug6hNB(ks7)M&=%cV+5Q&Ck`bx+N%8%}0M{e11*#2wU?}VvV&7`QU_7b(djCPtDYA+=(CNH2p_Bu8Efq!{UrV`maRG22P zeKz=eRNCGk=Pc4^XKy8Ml71USw|V)QAWW`ea&G=k@^*4exf+(LScUX!a*v?wk(ugxp9OtARrb{5 zJDmI@`1miNL0Qz_QfcehptJP}Wj;+*<~km&u8AmMrD);J4O)0}^WTv3Te|v;oWn@} z2Ia4bq$;2YI5)2vv=I*sI%H8#P=zpc!Y1aw&QuJXo2xKbA&tsn`vi3{wFp%tRGUzR z!MXWfl;1n(k*P`+b<0#Ks}&Rt)k&P2|C};=Wl`%;rNdh3zLZtzOwF@B+57WMEycO{ z2CYUF8&yuM5!4g+qpZ4VQ9(_eHkBW1r2CV1KsG5??`;ywY(E86Z<`d<+a{sTuqVov z4XAle&}p0#bQq~IoRdez$qqqvQccM@`C7`X3wm>^&Z$4A zPNiy<>Q<`uI49qhGHX$)i)waJwNCXq)h^qoYuLMO7PU3izElBIMa=CvLM=R%@LC3y zPu22vK^L@nP|{RWb2Z1V$)X}>t8xWUl|ZAu-VT&kT~8gpsMooQ@~gAfX)BaC)#=+Q z+XmH-Rp2UA0cWG?IR}MARXtVn?4Hg-F>rY{jMVI)?Abk?N!gWX3aT_XlVet7L&_CN zdlIYrIXj<0nVCVOP^H4sj8(8 zO6QhqC90V?jbo>0BT*Ec9n@N9=Tpg}+%shf#7knv|2#rBU5>deFBmP1Unh)p7*!Q1%YXW}zWFD_0d)ZCq7y zi%OYM5mRN%DM3$HRoyA&8oNU{c4#&m<=I)e`kJb2jv}6e3hgWuFem3jvbku{&dLXo z9*oxKWK#3cx1E)5Q?BVdj<}TL#%B|PHnIAhs(6+XPei9!wPMwa)%`5XCb6|mI)?Pv zY%OZJv(Q4FoOjODFP@dJA#9s=DOVWn%$_cUfvBZUrrbJ|h-c-hBd-bi$n(;!XoO`Y$ygr?Y z2J4i(1InpUKUE#o?b$OEoz^MrYYVo^c0d7nX09&vil9urFzvw+eX}J&9b3)UK0)=h zZ??2tCtJO2wPJgt_F9iRe$MfG1@-OaX;1Qdp^Q5vub1tOhVo3bm1hQJsf^E%Iw;>guYl+cImBsRphlxa#0h7x?RRDk@w@a^wuO zfTyAad=y&PGoZjz&;Tx=2t0*!E!2RIKs9@2egxr2l(Y9^>u|ymX~I6WhYQ5&kE=qi z9{HEl_7z&%M^RfEG>g-qTYNNmGxDfr{+pm^{skq!MB)2r@;@j2MY$S#)GXeL-`zaR zGWC(Oas}n;#D@j-^v@{&c~DQEk*lYESh>3T?m@|Y_n_w9EGQ`d2vzqVr>ZG8Ly5Vl z$Xqphof`gzn)n|$`y1#)PtAW%>JO+#Pt9Kkr=bsbF8gPIGf+1?8&s+NSmHNPl%5Js z&DEm*4DIUkP$Zw8zsgas1-3B|LdSie;~To4{^j_DSZvf-`5a7$o4}hVLwc)8u)aS z(5F-40k$7RwOa*kmFv~7SIPc*w8E$7*Au4Y_fzHp^u@0yzA7B4qWbjw(Q*~@X?fH% zpO)W8nfuWuzaC|BwdSuX*P?$1jqkq)C3N-BUqTsO{rCII)#{_B{f*?@8+x32p9^I<&zR|UA3dY=rM_bTS!RlW{E)Mx)7 zsI%Wf{+(fE0@o*SWrFvEs{N^KofZ`C-!EUKK=phz^q)gbKdwn|8G9~4(O+Hv%gOsw z(D;A)AFCAH8CDy(h5BzN@0RrY%v)_-rZ{JnF$T5q+}6frHaGwEe?ytgU7zCoo-=-4 zhdBTDzvCKi?l=E$Zm;5Rc6Qa7RIg-8`rrM{#d@5v{ZH!gcWwM!d{?^{&-Goux%j`f zJYQZV+af+M-<(@7Uc(>KUfr_2w%$Nt-G`rr7?|6las-=|H#PnmB%gWspU zdItrzUd%HUSCZ=!l-XQCt~WDg>afMt=K7NFnsREm#kJ^qu&)WTh-$m_BlKmCPL;N} zYMpD8xz?QeZ*fh#ZtP=?%b=a+>Sg_z_jAR&u7s_a+tgFgHM0gVPpF1lTp@2D`L0K& z%8sk(sq5w{dV_*ioNLn!WahIoxr50WRA|YpXeZEB_w>ATwYutHE9Oc&g09S`Ud@m~ zYjV_nb1lEBY!3xp!%khVA4?+!5diW_VS^ z8qO13#(s6;>=Rwr$u*hmv0c3`C6v))k0Di&eWO6v!ONN19RrSGpH?xWz*4p=ka9)5 z(QFM4|Ec)j{l~7q=fCkk#*rPU3cD^})$lKea;4+-R?RN{GuNvc zM$5$ZvF-e4uG{DTDz>$4>)L((GyiwIE8;4H@!yOJ|0u3O=x?vculFChHdlR6^}o{a zpIo(26+qW9^uNYyP|BSb?>p~J@8mJuZSlVIuJqmK_1kbgo0Q*o-j&7c?^SPFe)oBA zVxT~qc*n(+7Ms#~wqvoaZPl&H?>q0xcyF|3fBSGhdRKZ6de?aGct^#%u|>G+T7)~% zJ5a4b@3oFxsd}JKO~>%BJBEMTF+6czU+3_B$~uInsY7^zthW*8@4&C$3UsZ#4x~DT zr=U}4$4=on>O{+R3{OI*aA&9%>J!pF`~vUn=KPNK<@dbnv9)L0|I?cP?VZpr-0$tU zTRMe%yB$}leYh^|N!j-8%J1ZqtCNIQZx`-Zu^o9CA*F>(+0t#nwrscOU)KdynQhO% zt`9oj-Jbu}kl)>&y>0o|jX-C#+wyOlfQ{JWEVXUX40I0OmFAog@4&yV1v-DP?L!^@ zdk6BXgEjay&eXT#-?jjob5twR{DJ|<9~J}r@;PpT!{i$ ziJZ#(;{w}$8+GEpcOqAGoX76QJBs_?99GvGU@GEcr%1U~9d(}=h>b_YA|{#O^Q z&$^PD&b|^*OB*#{D`Jah?>&Q18Jy164E9b3wZoagb?c7Bp6@#C_9}x~+RP-V5j&Io zS>(*b^2q-F)1u&SW%(m90cU@!K~q1Ad}5vDzo7Gu@H-o*1r)d00n z(qgPS*oRmJ;u@g-QuEn657d5X0o%2}`NRvjbNYeWGA$rAADgcMq_hC51^U)oM9xCc zH=QIOS$I< zVc9pB)G|T?P^I7H;4;uR+;T!Aa2Z?6d5(sF+Ptj*mxIgMyOPit^vh}`&)_g{82eNT zZiG$ca8j#yPKSdlDYKf;6!gn#HTkQ+k;E$YHo^K+tFtvc`=h{-T2C)D2Go{p zJ8*r_Ic|mZWErXLDc3sKdYYr9*$!;C0eugvvfLURN4x_)-Z)Sjza4_Q_70So$Q_Nn zS9m@va-S8rS9^gyxrcg^?oH^VPL4f9e?k}T z1&V1MF)*4;ZXLE;u^IA zeUFWzY#VS8@n}j621gQ)CN+X~E3h?&qeg+g6N_((QPePo5<_XFk(Bn^v;Y=3W?XnL zj05S&arjS}O*@oY_} z!~}2x$IPI-TGo@;H#5AIW^!bG(o@KrNp1uBr>Pt9VcC1%j$B$Qsn z_AGD~B^I$~F6cXM5!*HCW9CtIF<}8citm>t;f=F|)I$0c-+D_aT^(G&F-r+G=uH-K z+%n281m|)5^6(y9PU)(o7gKgQVJWyQ>|M&96}&kzFyputgk|(5z9m=EgI5NZ6R#w9 zIsJ%l$yMwt0dq>PVmk*{lDCTOWuV8KTY;`>rJ+2ivg6 zzM~EQ-u~bIr6t#|I@`6WqdHif?Pkt`VUc?O!+a-@XePgg)PXxf*v?HO|+N(173S8{O5z2k?u1v)CR3_}#v1 z{0`{P`F#_49sBXWeWO)iyHDty`tlnqkmI!z?S)E6_2PGwkoH=OzE!>AqVHV4U_{@- zwx8%*+qM^dr+Wv8egk;-i1to3L;vPo*pdHWujReik$)J!l>K7%p7y)DJkh z=A?$va$6C%AT>1fGQ()e7NlDehHy``4Cp)5{!a7_Yp*BzF80e<^bPJ^h0z>A4q~bz zSb=Mugp^<5l}MKqTDFX%rRHR`vd6V-8Moq|B;mUrEB*SL4R^#9~r-gVq7hqt`XkzetC%a`yhZ2T?nvnNltNAfG) zZ~2@j!LRuEMgM)i>Yegm|`?6gw1@MZBigHBD^KiOW+biW)7FGAf;*r|KzlgfHln>6R{O-hTZVF{Gz@6pCU+3+ z+hh}>eVcD9(Y{S4BHFh(DjG*k9l`TmB%>KXtNJdI2lc0&ee={{+b66hvG3D9w3zQD z-=uwLLEl1E+3p2aBd)@>ZD-s14)WRZJ>`-Z8X*ZQqEt=}2od2OS~uO0*5vCi;=KrT$LgYP1bk!!abkFgk?R_8xLTtK08-M|d}Q&*b55>CBzued8TfA>3o$U*1pMxsKjVpGcp^!Q7obslFY3W(V;EHy|~XJJmOVPxUbF%7&m{ zMn3yP=>r;*8o|BWIP~(duNY3x(Ufh!lKf_}f46UujcrA$lzY=2Nd9GCG&=NArJ?V# z$FlD#z>dS$wj5L;9o@pD&-R;!_r%FW;=2f4<@u zaq%gOPu4fv>py+I9G7>-plx`{`~sQFGnRnUi06TGLC0L@gN|N0+Um%_e9*Dgg`i`V zj;cB`;3%adsf(#41@WGRpU)O06Nd^4Bu9wk51# z9B^3}Cv;q49kn|`=qRSEn>jYfa6Ag%UsG?a~YM>*{CZ?t-Sk?v&b-puT`!+dl{QWF<5`QB`w6+f;K&j@?E8?nFJT|N>h~abKWfUf`~;b^u|2e8Kl3bs)#@ zg-7__qz>Z9z44*ku>>4kdLYbsY+-bZ{goSDSOCyQ2t4qR5~g!_m}R1^f;1G1PPz*q`_qQolnV zK@Esw2}h$4pd!R^gk#YOID*vi)N%xB0qRDaKsX-F0CgTtB%FY9fZuf|aby+r1N^E! znQ#nv45dycoQM*@vFtyEa1xpg$FX%P;grH@)O8%FBEe~-PA!~H`ZQD`R3|uta5|b3 zeq*1>kyTN)@C*Jd!pY#tlsb!W23i*&ymw*GQ{Ze}Cf#CV%T}H`2qNbqk z#pTp;A$S3~e*LiI!SjK30GVe!wTuH_h4$h?x+^)|05T*sMefqx;s zp4zSiuVmj1VfDou$iEI92sK7-B;0@+gjymu5pF~iLS>Pg2{)mapz_Bpgqu-KkcHjK zk+slHxR%`8cpD7?hfw=%glkzj^*T!2PL0>0xNrlhJE-vnlrwH5btkpl1gb%C7wJ1u z?6{fK-PCn6Y9fwL-ox>=Q8c-Q+-~h= zS&8&cQV&w^ouDhJK1k|;pcC>SdLZ|3mWK&-L7CVi)PFDN%Bzp?#WNhdm#s&s_a5*b z$~{Jn_ks7Z{W$5zKvz6{g1R37A7J|lj(-r%iHAr%#WD5JT6l!5r>XN1@FDg+!|@M; z4^!eyWl&ZYx}-O?G3@d z5x-B)yWktd?{k(nSeyB8?E8Qk|Au~ss}g@mEpLHulKTgVv=Tq_uNhviJ64!GsB#x~l$tRRZ5?5nR6Lnxx(g`XWYMx}| zq-bflc5_ZnhPH&dBNfQWQJ9ePS4P)ilC3fo2XkE(3fQesD0)=qmNnGqY`}ixt}ms+Md;s$EdwXir_ullFvmNeAj`0k$IUK&pLE|LB0m zN9&|{p%VeCDUNK7x`$dWofEZOI&+3rZO+10xM+Z%ij)jSdI{|=Pf8poQgfsW zIECLdDbey}Qqq-q+e!SoQgTY!Uzu-pN0=&um58(ORqDF)l}P(F>=>2GW6@GQ&Z@*2 zmN+u*n739`j)t@LIgGvaKSou?(gO1IqBWL0UDh`tus?AE_pKHH;zU~C@lJ7r#gFzq zT9Xy{9gd6^xDv8FM@$p`w~Wk@)RccLZ*rV9gXzh19CwYQuzBEt72#@f6PcT~5dJ^; zn{$nRjmw29!A|^smaA0ei{CF^8A}xyfM2J5!`Gv%pekSJe(A{#s`DM}x0zqnsT>AY)Swkv`Ch@DY$?z=JjnuNQzggo255C7F!rm>)Raz*Ze-k`J5 zj*OInju=)TzarPNnePk2c&?M9KRKZSS9m;kv15_r!+4hC*v|K4gq~ne%C)3K2T-fi zl)V{GkUfCUkz>T&$xXPIyMfLaIY!wLv^OY_pM)o?6KK!SjvVLSed--s=?r#ZyDcf7 z2HP@@rRyP~KT&+LeZp;j?*gCrD#Y>5s8Vpw*Jmrv*cL(^K7-y71?sb$_l7-)HCWRR zD<6MX#qi5E_93v(iM7RFR*5tDyZ-(E;n=#rJOl0R{QcHw-{&u{2v#81adfZ6|83=c zHf+7vie7K8iC4XZd%~;a+@y0aRY+$bcW_JF!y_}$yT`YL{YbpOtj{Bzm9eIHTx`WE z-*J@Za*oBe-}tD1=RE!vf1SU@dp!OU)ibMx-{^VlKRlZ=uu1rT-VuX&{#wy5`30n3 zggu*I6ZXoj=$HKR8b}yKujluLJ#=e&C;Qc{2?Oc-hLS&k9Q%BGT>I%ZU>mMOe|nK- zpgtWV!gY}?YB|@G+O5;k zPt}Or-r@ZqPw~muA40~Y&wy_=S%&Y$F`!JX7wDT$j^G=zKIsy+Du#DZ4|+Vl?&-B1 zNv+HN?qEIQO6(~KZ!zbu?QJR(%D^)A)uwb;unw`afR%Z3_-^)X*p;j9TfZuOU3*Zg zdf%8`K;P>%Np>+EDlwrh~;NIUq?v@_7kK)VC&4Yaw|5<#m1 zt*W)Pwxt@=CR%1_TcEvxmI%%}MXT+mw2A+00AcIUYPN|iUwZ@F%eJ$pmlaF_W3XR&^F#nwpw#q#W^?I%lpn5EdQUj+Qs(r zt{lTYN3NU|vb~}eyWd=XdD%+N?rG7jRYDtbyhCjf?G0=N+s^M9=Lc;azjL~A_xaAS zul2oRJ32qx4s6Rl-xOMV+ag*Z_{HUnt$lyAF>vnEx0rSYzUyo+Ee+xuM|%S;541Wc zwwLYXlVz*fQVqY+QnsM&)u_CsVyhKf%2wO7rTo(IDbqe=bM3XErL?Pxc2>5Ot!R7I z{ziM*QnA%qgf_CJTF@T0o$XbVHn5HK8HlYmI<#8QHze2gDlKoR*lMzl#zGz?Ff$NGlwYapXUP0%k2-xk$Dd*jBT z#qD){6Kk*NyS663-6yCJ+Rk@HZQ94DQrpC)JRkA9wJ~w)@PxJw&u_fDTZgOBnxpH| z4voW8)sVO)=dxYA;w|}w4Z+sLEnDhCppSuUT;BtEhb(#uCI-vjMr$|F{VetH$#E1A2CGlfmb)zhFSb9QoyHKA`_6Q27uY)5~C9?as&FSg}=*6W}d z<(%c~#*E&!0e$-QD%h5JJ^c^#BxnwiF&r{zCv{%@U zxD%)^f_l=OK)J^D;px}+U^{02WbyhE=yhQ4vqR`>b_o6b4xzWuCqWN{?b-56PK%uQ zMd-a6zvt}<{QmQ6F%NgC-;=&2yeIuOv-hY*s%6U#;cUK7+ESzEw@;Go`0MPMTJ!5$ z@z4A(t@tngSN~B<{<~MgH&u(!M>Yq&ioOFyudBVRXbadbqAlioRkRIlU(wd~ORHhH z2O4o#c&B)8H018_p7IUSfcwll(K}7X>b>cG=(j|i!S|h|g-mVG`TRkoYK1$$HqV1k ziBE?t+vmxrsU}aCPoYm-4W2!pOTSvGbFGGv_L;59Gwc)Z6J3=j-D^COEx)lxlD2=S zMBia+_ztT?&tiY$*9O|Kq$-47sAA}^DuDK0_G6+w+&DrSdc2HY(LU0?F{O>ilWqrU zA>-Zg@3xmM6Alt}M! zzbEvR)c4x&UPqbq%=R10uS7l6{r+$?NzZk^)f_vDKJMDd`1KI|vWwq;T2~i6ul?3{ zET}F|sn6yHZ+)NWzT`Oaqc^qRqmKAAq!;iT)G?h#^bUTDICj&RUc)aEM{}Cco5%wB-yv)?0**XZr+mx<#&aZJZiANw>%g+#w?98(tk zhWGkU;L7{W;`N`v756E0+-p47+V2rtVH{VyjJm!4W#Rg_1nnEW@}hmCS6;MN^va9& zie7oqUePNr+A9tsG!ECl30K~y%tCO1 zZLer6)Z>cVD|-Fwa>eZxZG}2qaeGBup*C0CUeQ*l#TEC7vlVJ`t?d#-Xf2;F+bpF;6P_*GH7T@g8TskPJal8O8hK6Rs*$&j;mXvfed}`_ zBV(2AG@+I2kz2~Osz-Zy5BeU^i=-~Oqq%Ng#bM<4CTLyfGck%Vnycy^YL6)E@#z^! z7{!(EL;eVIMsg?gCGAr-g4XHF_HedF(1zZ*zSEj>&-p}7An1A5|Nmj{Jizp-%EbTO zsYzxsnLd*#nQuyFl1cA9WMh$0FIiYS687Hq8I zq9Uszift|b-|rm1XC{yc?CQGvU!Hl+d(S!d&i(Ga=WXXb?|EPP=g~7C?3zGb%ALp8 zo5d|iu>y5Rj?h9R50T4jL600yPUshr>nH)<97SR_m=}3qj2xlFNGNZP91-Jv zxSPRo(t0j!$}^235&4^T>w5adQK?lbdUNCmxnjmXE_cktkBGcfJ{n_}#5g9}GE?A# zG^uSb&O)=m87-V@nb|6seBSOV4un-@!5PT zpTuV?2v1T74*pMi7RNG+FDxx-)m1-mf0uT3dt58f!m7nsOS`swtpd&q;+w~j`M-93 z#_o~LSLqwRUbKt!4PP+sS%`Kuzm(rg-kAiPECMeI;IQ(`B8t|NKGfud{b*^kuL$?7 z2qRG*?pe;)k5=5AAUX1o$38_Rr6S0TydWp?f>elh`bzGX2R+Hv^7w^*)aC7wlc&QI zq{Gvs!>?;+iB=$aa1}*uLu*SNumP&BqBa0n57!s~FVUh?1FsoCP0fM*sA=&jejo9w zoL|WfPn=EN*`o5zcM!kipScvVOljsjh-E%;et7C$;kkR!BgXmky(#hmzo_;o@h}y> zqZX}nx+=)0>cD}jscS)!yY#0F0S@6wYv}3E|EMn*`K5-ZR9`R}ig(dk9dm@3Eu@Cu zXrs3m{HhJuM!Sxu=nFLKh&x?cfvud&qn^+AQNyXH)bT#@PW2Aou^+u^AFeGHQ&&S8 zz_*C{i29+LNH$-)g#HG;jg~dFk*JlV`EsR1?%lSI_K-V8C_=4_G?nPVOPOjOTcK5TSIHTrS&iJ`wxr&<4)Xbg4v{H)k zb9`Q{+|B%2HNEm=zjx+~4&;f{a*HV?jF8XSN^vyQ4f-* z&gT|89Qi@v$$es1F4V5Y0O?p6zNA=@;ggE(o#M}UM(&4qDVjTfZpMa zq#QYs^i&YWTDj>uT8g$hl~y0EJxX8cOeq=&k1ovw&H&2T-r)YbSxmq=pjSL7FS(m|3TEMcKDh zs{6ljJ>9it*O>h>eqUEw#fM%zr#vEydrB3~9J48YDK(-TiesiupBtXZr^mZ5JaIm6 zmdJ}x8oSDYmz|vc0zptx0&TiD7U7hO-Z*fh|s06OaId65%r;zXFN>AM5 z8{-ya_V_9f{I0H}I-hk9pA_V3oU1)ziyCs=zwJs++>xym8A5N2$duXX>uQ|qJFcd? z`r|5`YjJWE`I$PiGfE?3xh~}!$5q6*LZ#1^Gc#8a_1SVKzMfp#kK~nFB3gkywW}v> zK%dC9ltDnbo@*(C!kWq8@McD1@+ndr_1H>)dUd%jl?BwR%l)z0K)t&3-^u~%)uqQ) zE>N#7J+`7Rm%HYCb62e0HRm_dm&^Tf(wDwm?wXUz^yPAYqr6p*Eq%H4?b2hbFVMYo zdTbQ|_3F}Ns~=FWE_W2iXn^j*66^Hkau=48RbMW5VJTJh<#I2UyB^((RSxF6D@*^a z3ZRlH?sAO#9^>9QcVy|s<=(ltk1p<=%fy9n?_AvX828S(?i~?RTa;zf;fM_ip4FA z^@zXHUkjKZh4tKrpP|AG{YiP^wpeOhyGVb|Uw5XwxF=sNQ7ROB#e8vC`jgr+ROotZ zq`XLrnU!*F6PfjL?HAIhvRO+|-jvzh9{moK>Dq#fA*Za@{^J;`18Dh?!>Su-^NF5}?nhKUxQ-#VyCYGm zhgs#b0HlByeP({MMiR?-;5KF)eG3t~!qkMEtzMC%Jtz3NP zbg4!erDH}eM!J+oXxlT|iJmK&NF(wuWuz9u0i1iQTof1dS1|&~JCTd}G`v+h>emqE zqF5K{GRnnnitH&DrAy_dSX{t2^xOI+m55T_&T_FQbxI3wN0(A$q|Qi@kvcOJ8L3n0 z^mcR^eI}&N|6k~G&p?-Z2D)5<$3SK98mPjjKdsMXq|m6j>bdWi-&u3@JHAmUzJKxi~aA`U*9Sxd(I!DwCpJ-)py=be~og|nLE*w-7}7x{nSXEljeE+Bf2zLVJl*)H>JfTwxW7!B*GS4Ja8--f*q}E#b2pmmSUCN-pnr`E zJU+QtwoHjk#(b0{3%hB^ZF5 zGFw4CUsivlY4j*pTY>s!)S<6W2kNh+m1$s@^=hr!gWgiwMz7OfULGnuDW?(#1C$z&p7b z;97vQ8rKK3-Pcje;x}r6&U~`@k7}US`fN%Ku!eK4$W#Eehr~TPIb7LujWe#)xQ^@k zP0#htMSM5cH@jCo^U+jYcUnYmFLc@kK<8Y&D2o{L`P6!c*;emhFX_XZ&t?Bx*~8Tv-Nm_Ni@S8D%2#&+%a< zstscWxa|y8Tg3{>IOeWnsI7!*#^B+uy?#%Mard3^7;)AIYhDf+u>bJ&MsOnqlA z@1qO{4ySituzV>`yVev@?eTD0-`_hpnQt0o&+35Nc`x zs=XaZS;dUP`R!s#BT$ReVoEcxnJdz1{bIUvdDMqHs=-EDXy(6(GC*nJ{;r|utyIe$ zayZjOY350k%~Dwn_m{6UQkr;XFl(qujy?Ud!KaZX5m@K@*eji%PWg1u1{%ml+#RwCgqzcN-@+ZmrTHo zu|T|^ete%1 z{QfZ7llb1lcnUFbGG!=mD7{kxCQhN>)dw+gDrGQmFz2QPOq@o)@fO9wXsy%^Vmvr; zQ(LA{{KUi=6s?}_TkHrJ+Cjgu{It)w6DkeV&(xKOj5aniaJ!j-7iJIsMYR1#91ZsDhM_t>HJaRsxUIuivaz14qoJ|Y#0?K^&oA&92 zlm&qY76XfEFAh9%F{8E!ZsMx(5=s%Uh;vK9u0miT?PcI$0kDAfa&WZ|un+A_wvXPl zR|dYC*=wUceox9uFvT_HiIhDV4`pUti^M!s3}g&a<;Ay9-eQ`t3` z(#|+b*HVP}k)-uOl)+%c2>M4-%x+}#(6&Hv`j+Ua>Uy#iQV*1G%%?5S&*M0sS{v9l zivD@@%nwgIk5SPlR642UOXqUVweY!&%ouv48OJDx9#?slpWXXW^$d(Y<4VmeM$mot z@)hZ8COxwPWhgDBtSX99HQ}7p<34_At&-v@zVcR|f-Xi|>eB<(m3}3*e4vw2mj;b@ zs5d|%{YDRvlf;Ol87*T5qw8*nQgD3=&=ompT#r^Y2qP9u1y1E$F?Dqb;~5lFh^3xR zF;d!{hlJ;hmL93i_^i@;#zriyOK0lsejj;#F3@i{G>pkmYL2#}V+7C`9oVr|LaW8a z_!Ews@dsiQiqX`KQsCO9V<6Y+9lok~Ii7l-@I|AZ=C=}e{Wb->>tx_0dJ3tF-|mVk zq)b5ut)kYKqtKX%ML_96K2t>5pYIU!#>j=_N@^GT1Sr=k34E*s4yMPByU9u^dhF~; ztt?30GALqCMrj4@@*tUA_mPIR9lP!$g)7@DDa#o9CDf{*M^}FqQ>%trUH4f;t$)y9 z`UefBhPqrMuKUcVRtv_u?jt4}i(wv^Z|;nGuyGDhequaPIh3=%0Tfq%j65nAbLXa- zjl4{broEVGF<_6pPL9_>FR^6kYoatl#p*7^m7(1N22BIH-`nhY(rY8f=#8o$zdoya zr|S9dE&w%Refpz^e;YU@H7i%$uO!vVGnDk|<$C_R|0$u>LKz4SDgVW&y1+TyiJ;`4 z!!_!?+IrlXpues=6=u`p9uBEf{^5=WDRdTn?&r|A*BuV}1H0qFo#L|s9#(<5aleO} zuKUL0?x#wy*u5WW21e*G=b<=S0WO=XPR&4>Kb9V~0ezUw(^nR-*crc`%bj+H(F3# zd)$;0;?!V%-6%Lp9r=>nM%#FX&kUz;1n=1oC~j%fF9PaYF_N0v#RyuX0$r;+sap-> zT4$E-Yxe)m4m1=fZ!uQ1Ysd19(e#>?!>^?$%t%IG+8-0}dJIoEn0gtlu{>oKP(JBg zH3ukf97`Dj90HDxv zMDKXu1dfvfUYG;OnS_{PP9gC_JkzHrMrp8aMxp7n&HW=acLeO{pmz#&cj$F;eh;u+ zX)=?#d4c2sv-l5l0ZrvNhiglK>Pqgz*#kI}<6N#YJJ3wp^SDD7+-eqm^C@$Iu1+lA z|7QVbb6h}8?q&`jwV6_27r$T@AoZK6T(yv1_bt!kjH?x1Y5t#dI-k+d^R+KylNYdF z|6TomlyA9|JifouPLE4Hx1A?vQ^a^@$XOKe-dS-%$zp8upmg-r)yrusS@gS%ezP&M zMvN(w6MolOs`rTTqVmHpdT*(?jNesLHa3zTWsa)eHN`xqBd^zuJI>XV^~TXdGDav@ zQx*^XZFOgL9XWzpv(e3^Vewk2Dpjj5D{bXI&gF~(dwYim(xi{#$1;V zDDjo`@=a+mfl3Df2Zit9yv}v~HeegQ(HqLuq!i<+r zNd0OazLESu-X!M9Eu<*r%!Ghv`nbsZqK8ZLebL{+>}2Aj+|9KcZOMA|X*-txMSmKt z#qvw}quvT51Gedlqkg7u(Fkx&OpJV4uBq>i7C2W{R<2C*Z&^+dT+dT<{|&n`Jwct+*2MH`N}<8YTCQovlZp9 z`^og9Rst!7`v$qhKAN=ut7fE>^e*n)(c7t<`zmAg%q|ODL~Xbn+Lm*aQhEc`HTBbX z?y6R*kG`^0ZBPlXER|;zQF4LGefJqDOZ`oE2Dtl3UgDG3vhGv6bHn=-hC90t&PW69 zMf2^|l)YykiW-35LC`z5o7+vsD4KHbDbs&&Tsra z)!!}+?--2B$=SuW!3-L>Fe4RW+OOM@QYU7aJUJN4*b6v7jV8r#PV| z=X1JaLk%xtgX8U90kOe71aW_ZYY@&9eL`0yoFn>#H9URlQP^J<#&-j#4W$e0De>4^1HaJ;=l4; zdeTmeyrfh%labh^Z1!7;b?TBzaOJl$-Ibl59==ibi_bkh3DsDmp5V-~+ru|zn^LcE zy=K=QzUnA`H}O;5MLZL4jaub*cCOyj!&mJ`T5=|(ZX}I47gt|WYf^twk5ZdbuTsBK z%W@8_zU6Kly?moqriP}Trk1Jp<_tG#q-t{NsOosm`_)wSv>eBG4swb80OkWwwdh>WmS<+e@H7QFf%g~qf zwljV89IrT1yQ42hEwekQd%T?AI?I*H-VJ?aIN`e)uYbgjhj-5pcTHcJk;-sF=_^B7 z&Q*JkSBA2j&-UbpkrT%8%8ZmVeK})>AI9;Db7^_wJK=}M+tB9V7|9j2UcXy@__xPP zuINlwUMPQbhl+a;<6KuM)>D4H6Moophsy5c*Y5aX+@YfUQi}DYuV@iaiv9PFmm`(o zgx&NNb7*Eb;jZP^yP>c5_@P?I&hqPj3O|f`uKHkR#+T8lXQDA?)9At#ns7RJu(&^GF8^cX$UT93)881@gd4*uaZ@;_+&LV%<9cl5X)Wjz zv(Xv!txcz!z#lUtyK2!)QCoMtu7%Rf{hTwZ(-Q-S8j(6^886!T?m$XQc-B5ZXPw$Y z^%c}N(D&~RbTyz2Of!?au^jYJaz%0g$C&4R5SV8+Y1ap&FQY{{=M)bIL3gedNPWsU z=cVnG!BC~^2GXW02^9f@oxw`8?pM}dO0OyRgGif^MzaF7)5jQ1)<~~)6k~}?*+vwf2-I)G8GQ}-p?$|VI2WH z=Si~YspGusna=7R1tUEe-$C!FOw^QwRbhONYN_l>JE z&Zm7o_v2K8yZbW+2T&^qR)BTOIL@JzgROG{bZngqMt>sxhvre&lSuy|J&jyfD}g__ z2DgY(4FAxhXfdT99K|nW#NU4K7V&p!_;N=1)ypLMw28TUaK=>v-#D{3T|6DdsJhy! zhBS(ib*6!6sZCIE3-wjBHqko}xPjKuKzZ*m9FK-KGy?UhIGU@QfsOEOb6=X5 zaua=<`IZxbYS^2h?-@YXqBbLIJAr#}{#fdpft$JVSSV>cPz`bm{l@~8wOaz+YzeY< zOQ7>DVXnIcjy99C&Xl%5{j=fU+F6c+I>!RFt(ebp3{YFl30!q7P>MW(v&R7^({}>B zl1s=l!f53pD5FYHAfB%VcH9I4S466zVkBWI09K zL?xLht3rm#GWw<3D>%vDItNB^Q&@};5*Mx7lCVay+;MGR@#jiC1 z&(`ox$51zyb?zWC| z#<12}D2LE;=t^dcPi^$-5dmAwaO?V}5vYe#T-n?}%?Q*RfE#EJq3)XI-W=O0u4e8{ zZ4gk873ZRQXX%$E_jM1j{#s;@1Il*?0M%*az5@dHZ2&6A<-QGpyBMO%TcBr5pull;EMC;`2cs^LAjCKrE>L~0$0B&@a>xd z-@Xaywmp5>e)O~=bbLJMZ)}9VDgY7N+ z%9+5MId8_*n}IjdcPsyy0G*NCO34N~&$yM63%rr*Zl$EijjDb9HcCEF8~kmQ-oRTq za~oHht+hArW46{CQ|a`waKEMD7nX)!SW3?_Fk=BYvV?x}l~Gsg)#qhKz>68w=R?oY z%I_~Y&v13bUyf@dYA-RXh$|>QSBxlT{3;{q_2cNi3L_rHSXM^Yn+nCuga-AxnFb|w z1)e_>sQ;keKk9eR*OUmefNHa2>6s2xdz7os2CDH^!^iZkm_%LvR0(cX@p}jHUQ2+k zpBzMOF(c)Sxe>G(Wly98+Rotl(Sjp9LgRzWs|1jQix^=Y20j2o; z;d2KBx*i8qQ`|4`zWwM|itAA&rH==r*NFO zn5d)O2!$F|eFHsGV~j^*Y#M2+0qWlis8-Uz_4@$RT$71ouWT6>c zt~(6MZGdi-U&Em12HHw7W5g;8rTCM84IGCCt~`|U#*%H~Y%}EqIFWpM2qk96IsvYv zZqOchb~`oweU-H88z;c6Hgm2OX|)BYVc9!{oyFo-f3j-d>1qo|9v(sD0PT<0=_ zjQL|GGU|JP<7&dLd#Mu}>rd@hjaW_C)idYdYQj;&j_ayw*sgiSHD||J$$2ctb->MG zgpUP7?3HtG1{-WUo|_q+^*~2SsdOyojtLlY47F8^{W0K$oO?6ltsb=>#hmJn#!AX& zzOwRf1x0V(mGms9XGIv(&CuuJw3meub9^^5x|?}cM>!jcRkK@4Sq9$jL(d|LUiOaS z63SAr+EH9gSpp6zO`UIU0&b)?W)zWnT#Inl-=9*=xGFh@0@a+AALKpcIE13?kyEr& zlsyZn4Gxq#7-}^RmDD+i;^@r?`od>p)J5m?wo?f4+skB9fn1Yc*-7JH8a+nr0C2qg{&I+r*xP_sJY zDC%mcCvwGHpz`=cYIA_I`2UmmjUu3&@g(lm7pN|}m3A@kB#v9db!vKBk%!XO`zhKI zPNa5f;KHZEiA$*~HBY6s1!!LPQz<6{w{n&G;ufHmjcwHGfNGq|(t4nJ=;_?^6r|EA zw9gE+GwCyL`)OQrHg9wy(A-I9Q#&0As|@=9wKI{Yr*Yl6v`<62o=)!vx$1PJ>lyTJ z=h`!ntsme@Gqs-sJcr)%xatEyv#p;GJQsK__c4QeJzC+}^j|=2K+q8F89?6!TzNk5 zgB;UoBWl<2Ovc>SLRQBpxa-3CzO!{PO6(dy4rJ%_KLl@w0f*840qqgMmpJ|#I6M?M zlyl#wZv@b66)%Im?Lh5iFH`=FOw8Y>|3~2SVBlbSU!<>&oXOhGeoQe_vpUXCDCTHZ z?|Fq{re<;Rr<7L$mZyPYvbf&>ZHU9h0M{p89F|_1$g$kQ|7iITw_9i{6RnHe%FS2F zwLBH5ZPLunQvy^n{){q(yvxeOpHqHD?q#{OReXi~+m}kIU7c@{m_(sK>?dM5SLIo5*HrvtZfbbW6EU#cod6g3Eai7Eq3!S&>voq@v$ z)n?>5LbV*}RH$a7{$!kQwL3KxS5@7snhVT9j;PIS;Hp``*|axMn~jvw2DqLw4|oWz zLj(UfH1Lc=xqbukNZn0)!#t#kJmxUUp~$R*>0d`#fHaZA9Zoq6&1D@uYbgtX3wgsM zf+ReGYn+R@!}Q3Y!yQTg5y-za^c)rB=TY<@i4-(v{6X}70l1pu#vo}oa?Mf57^Uzg z%0^_L()eh~CM2Lb;xW8$E-;VY&D52i{i(^Jk0s~5yJkKKd01TV0{ba?9tJAm9^}cc1%90V2YI?L0=3_MnzNq*YG3^reb)k=Q#?Y?r-AMt ze1x)3>H*GN2fPm6{3!j80Nsi6QQF4?AK>^HJ&yvF-TxA#!@qFm_|#{R;46VEId?yt z`$XWsaD1Hp&j7Wp-$(CB!23BqLC@nrckbLv?^fV_96w9X6F_b5_t3XB^*QRF1!`@7 z5(&NpxPt6|z{T9LhH^dQ5#zxbVX8mlV{01}QG<-x2GqJygG@OEcrwQtp7LbiogD8>-37cW zbvN*C-e4>L_dR&#_u!ps!r!HqPJaXLQ3kIlTDOc|WP_6xMi;1#yN1uO@?!0{`g z_uI4w!fU?8@ww3Z9ojAMnQwFaGCj|6e=SwtrLTowQdj*Rt!92*Yu1ajn&9D$@Zx`^ z)d+|GSL)w~Cl3H>Kl=g40YG){M}o|GgjPMH?(;uNpD}i{s%Qg{3z#`qeZj1{+EzL! zozSqkCT7sn0pE5HyzzXhfK~LmGVQvWUpNz|)x5**8P&G>D8FUQ|LMTTXw3nO9s@qk zaT#z9*zh>DrC`hB;KLKtmVhTuK>tsJ`-f4!06diA2DsqUz^7@cdwv1<1th>B@YF8> zzr;DMF;4-X0t42=cb@@1!#VZM&%;l?Oy9wL;V%Q9<(&HF=YgLG2iMVmFf@M@^^KIz zLGv2}{4CG3iP~qOd1qTk(_ReR#IcBX?FSb)n*L)b3*k}5c~-Ap2vp-Nq^B?3!Sx?k zf98XY#|Ef|x|}i>xP_w@iMi+o&IQahtWTk~;W2QgUO;WbnOLRTkH>Ilqm(*-P&3U% zE^BR9gUCTHJ3CNTXCno)^{cDK9n1-`H9-!jt0u_YN!0I$&m0K7-yfhef&1vWAGn(1 zM>(?!sO8{ZdhP={<9vX=1Ay8X?xE*i_|F5>KL(fE7pUdPq0A$zI8x$>`MH97m^C(6chxC)t~NDNk|_ zP|HFoeBw6X9UM#H6L$dbwtDYl~AA$te0ND3wVoeZ{HrWHf!{l!~N{zT#9FJ>|(D zT11IV%97G#3_WGZVEXX8$0ysV zpBFU6@yQ3NZ%0QQ&)u~ck5A5}=Ywd66=VUCUD(3sfobLQhk%cCvhE%lq!)MQHX8~T5n z`V$iN6rgs{KXKKz)ElX3$<*WxuK7*s&zyTd@J}3notmCZOMcDSH&TD0_hjIoIsPiO zM>0M66=#2qiP0HjD)|d%Ur)_Q_DEjm?5|Qu;@mUAReo#gm#L0qM)FI}zMjfTwEtu! z3CGt`ok>UX8fSl*%1)e@W+z!3f061+I+I^;_O(<_lAWBu9AjqEmHeFkU!d{k&{Gm- z&L#ZM@zj6F?5l)X)enI$b1Y%@^fK_r97~un{TTQP#}Z~huK-`=SiM<+1d+}l}5c5^b;qy3e z>;O52oZ^C%)O#URH4-?I_C@f^QNU5O&*$85-~}Adr#1u}*S2vn1zkO$I-qlNF3Ke`+|F}eqK(`Wk98mI#oM( zJ%RQW$esys(Yxpw3@5&e_b=x9E9t)i{(L9BgE$TjQtC=@d=lr>_TZ4I(^ zE7$d*elkaG*aM-U$=vHyu2FwV9g!&6JzLiyNsOA9MokIC;>%I_2q<)0pomtdW>K=?T&47;&}ohaYV%7`HUl?v zh5jts`1N&3D2D;f7Mf6w0J@@^P>uq+s+&;UE8v{3nz8}7f!^vc+pP|>-D+mL>**<_ zZwhbO3~WY^R9apKbiHIsm={ce5_X__Y8x>|vvW_)NUMi@5kN#MtOE; zZ5sX98LWAjwO2T^ZAAOhmS#NYd1$s%_+8^T8{4UiV~iuPfNPwYcG9oE&jK_8cS1Nb zH5R*(qKwGC5RKOrhdn5ZfJP_SgR%tZd}k{EkpP_=PNl2@I`5krW_DB2tyWWap6Z(4 zT40QgN{hQ%+|A)?jJsOg?c|D$yIS1M;eHlZ zZrsh`ulWS7@VKAF-OB#HyPDk9;%+DRjmRstD41EsH#Yl>JDId%*lWBVuaaB&Uoo;) zyqgwzJwE&uE%W*S`RiKa%|PQ5`dmJrPww;j+y(Fi-y>$va3J#k@(G>>TFlFk^||&1fj`KHjB>d->M-z2hUU?H(Va*Qf6*pN;e>o%%JTPsd%VQJzXe zQj#Z;fX*h>e5M3lXfjZ_slGG`=zLzCYGTmlCQ^5vuYNcIsMe*nI6i2L zW4hF&^!1WYF!@BGnJgk}`^3*D$2^v6OtE)(YcK#>kX08c{y~DW@0( zF601>SE(JM7f^2E9>{E9Hs>bLj`51zzorkt2+ByFQr_gVx-USg7)~+Dnd_duPXSM! zqIVeIC&fE!BlgV;dAFAEhORgGU5xG`r!@MOU%|Bszo2w!{@`|chJ^2H9A;y38BfJs zq|>vy@_wLzr92l@vJDoPV3h>QnTs0IiR-2viCM&^ABmMNJh_SQi zjgi#EVDz7~yYrOg%JvejuK-riF6PQgU?uH-)TJqDpa>|HNdtX>QlB(n?mGF9G+>6Z zT1KLdS^;lR$7t14>%;riGqPGF^|F;yiT%AOa;ipJ`4l;o*q;~hK98FGO6{5{=~qPM4UWAyx7!N|4)+iB|qFa$Ux@SR{=p+~+W7A*}l zu#}p7$2rszihM^JSWJ=cNC}H5a-7lB76$5A7${)@P>Y}TxA{PAed7H*pte3|Ky!gw z{KV|J0gvYZ9ZPX{Hqh}CYi9u+IWg6kGRBvgM$ITQdY~9PrYqoJSHQbYpx7g>jp5ri z@)TmTG}_3ssv(c2NTX7KPuawqG=z5&Q+?KEpmbxTxEN1P8XZs11d3U9#ncfLX;ixO zO{7EdbvQ*Dm5!rrQSW49QW=YCGQBZUViweQcJF?R@WEMM{c zjeBACMZbdDg;6N;Xu0RIin?D!9jc0UC1ntJBz5Lf^1yO2M44{BJ!!NTML8~wD&O0{ zO23;?r_}GnF=f5`!2P0qDDEgOqdyaiu9IGMfPp}1)VQc!z%H(kJIn<-u6^m3H#u^0 zlQ}@gxQHIPQom4-G-`ZBBeiH-pBkRX_(8@s@hOZsG?lN^8NQWcJ&9ivZ~WznK)<=a zGXdzhc-INx*Tw@Q{>@>O=Z3Ks566Oy5ntzl8S?|Sh_|D`UirTGJSyP2c)u`U{-Qt+ zQiYaq=|pN-$`RWkH7to7r6cJ|PY|ih(bmE}6b(SCTuIFsdMg>fgkw9{p})5A^ zwc;Lw#=zei8IdMvM821%G(r{f!)PYUqKw}lu zf^ikV3flVXR{|?(%Te`Q(TiVs`j4YksWeh-q|!*SkxC=QzB5{tN+ZSo{b*GxjT9TH zG*aw8n^vWsNU?86s|lFu%7xl+)Qfke6RQnJy?9qTvD$Fdi~n!v#OebX&DaQw9pL`% zbz(h8)Q0se`P(|Nd_3yJLb?6!b>gTEs};z9qziRoxs&`+j%?lqQ8RvLIXs9OR%ujh;~J`CPM{dq&{_LL6zIuWwf_MTZ~$`e)P&*XIFaA zD}$BXYV^+7mD}pW&ieFf(aNN?X*A=e4Jn7#IC`}&X@45U*lI({=A2U09qZbiMl$}| zkg__#&n@BrG$TlXU^rl30?y7t>Lbmp$mcPDD3twHklXI;C-k~|X zsc$!hUhPZLsg|XojFZw;J)|#RM9We;$2fO&wl|Hl>F~bl{c-LZtxUpbQ_{+0RNq11 zgEK;HO~$SA3prEQ*3`inElwqjl-8yg_q{HBUFYbn;EWoU)+ZyQIY*5)rE>673zJ@- z(VC>)$$7BzNa<}Z(79{OZDLLn{p+wp2yYzT}PtzrOny+|8@?##*#! zOG8Egb4P>G?A#yRhok!#TqO|8wM~`tKFu66wka(Y#T0E*e$9Rq*OvTt&d*$1(z4N) z;@XnmqA+};Li$}{@}0F%X_uvY@WeMNRm9@BX6Ia~g z%1vB}iz_#Ag)Xk#xSr_KX~%Ir(dUh;IGJzhI*IEvuGaWvT{m>~(DfVF4P8BS+#@Q7))qDZZY8fZ`%;WrU61^bm&XiEF@uvl#aO!XdvlhgfGMt!vls~~ z$^@Uy%qQamXE8gHa$_vdIxg@L*T|JB=99_-8oS%~90SkLo*_@E{wtT3kHi@9nP`YH zFOsussmREP^6!z1x*3$@AQfS3Mgo;AG2>Fq!eo?O7_#3(bs7(3bAOs=^aGuO;c z#za)U#7tFw|6z=;lE=sn+UZ)jt{`w^M`Q?Nto$)1gnl3eaAPw}>9->9HB*)OstP%Z zfrEf@;3A4Eu5mZvli!atiEr+k(0d%Ke4yB7P zGJ{$!BW1)0Jqq%uD+68G&j%{^#EE>$G~Rg%wO(Mu6y9?(wccRBWZr5LH6@#pD$W&+ z|4=}g$eXy&uaM#zvU>r|Y;U|4qf59i*fm)9r^EXCW#HZvvp*>t_Mw>lNqO)-N;R;W-hJtLADCN7&2>d$ zqNH6>QX`O0xyIyZi9^z>D^zkYvkFaNT*WzU*RE)(3r?cM`1I-_YJ{115oSMHtRZDd(K>bsX3h^E1f{$I>^B=dYkPlXfo9 z{0%X4gL>r{uy!W>F~>s=t=vGbIf2?^eh4+R+2F6bfjdN`Y-w%s-)q zHkWfoI*B?6yj2)=|^XUymz2{#~8a zvr0X39$3&HC`HYu?rtCHX93W?JyO&{u(ARu9WA7orAZmRh*AzLr`OmjB|zo%Vu~4? zl*>k2!Izj~#wI1QF;|L!Mf94nsSv3DfEL!6x2b@-*_`xA=nah7o8+%M=Wvqy?nzk* zUFyk@PEX=#yJuQe^c&GHMvbckKe}gKMm=?&=A5nP3`}WW&S*)cJ!fNbhcZS^dd|$u z(tOc4Ka)q4GPZIA*9+pBo@;saj9Ik2IZKd7J8zRy$Y*8%<7_U@<2vZ+2L=uR2c3=f zV~m}t#@tcPRf`yD=dn_bxu&GgVH}6^4ZG-%t6W3r8OAqsWvc)ja9-TRu@6O$BIz*2 zHAeW87JF0F_NBvwGv+gOc4!o3^JrYniWu<$ zK=WR@W~QF5PRou6+9lw88knZ-d{1pbJ^vuSZVOO+I0!zu573<=2f-Eh1-gS|HBdiE zcbTjXdr*vPwhDhqvCDlZW}7^SmOD6_fcjIe3-rB?cN#-(qw(NyeIx(j zTgNp-*AHDejBAK-;1;Y;{b`cddxA-~t3qLHsGhcOG0ITPFxSv3!{a0Bbe^n4GeELkULgW_d5^d zp2kUW|K~v3{h=1$*EMvdbPKJv@WtA~mv_zGHFnq0rLlaVGqiNti1W^YoJr|{sXwMO zEazTgjr8pNOHUN3J2R_PpQ+|d2~bJkJhPbRaK2u{y?X(B(XQo7rhsZn&hVY*>*H9< zv&0oy*I|`CwUh+doBuRRtSh+UWnFl0*L0O@e%CsFBSxLCfs!UdZPL@kKu==>?Tign zGd1vISMR5CO-JCx+Wn?NX&v;;p^O7|a#U`PgSKY_jl&piU;0$3ZNzAdGdVXN9x#hz z7d3Nh&EzQVISX?JCQh2M(p4$#En~pok7cNk-1>_Iuy;ZW{g+;cd5Rj(cO zf4vQs1J(A2Q&s}?kseOjE8yW=pqj|Apm7X?_b#OFjAI!0krz1Q7)DtF?f2qJV@Nn> znNP1WqbB&-$8ZQPf&#~y!*o6A27|m2>QyqNBmsw;{I@Vio092lpPm?>H8q^XE3ma zbM8|pW!J_a+9y#P0^G{c-3LRUJa?3*p^YIRYM`x4&HFNI085|LTuNK_l)Os0%v_>cVaVV^thSkNXnpC?^1o zxzZ4J6{u-$g!{PTpq^rsaQ7gnb#4M4O|KkB*y*wJjF$k~iuoDP&^%t<{q z;y!@c^s1>Ulcb({pb|^!Q9jE1oPR3;yZExkP}b@pKXv|XBzk@Pjk)ZuR{5ZFad*7B z|J4}Hl|Xs4TDg(a-S=utXEi^0pR@B!{z-MkQaFbE*Lj8WH)nlPy0MA1Z5d(TDE#KR zlIpv&U&-s8m+zeY%J`~A{nVyw4FHLh&ix~#ca+i?JCA- z)~e}zBj&w|Ik5D)k`s%?>S9svQd3haiy5zC_N$odDwFq0o{;fAPf^c!f$Qz9zp?(s zS~D~Gt@T9C4RqwMRq#C0i+n$N!^{1hML1v8rr4iRRuX8lZDf??`;Bl1Wvm?ESfGx& ze7^y167`et5TPQ~@ z37l5#K3Ybjg-+;vEZXL@#ElE`LFl|K+TUWX)R;*%THds$XDnw5D)>Q?@zs~GBBW^jtRo?OdNM{_peT9LY& z+PW(uIkeoJ;~pJ(zV~$Rj+%L9-%%E=RN(pQrDdsfI&#*?V=Fl4ek5%Mt^sxDxAJ-2 zUu8}o*K=ICas5W`Ts2aqrBCb*7iFf;w{w;&XAjOZd`f2(JLk9R{sw*pS7KbZ+HM(RlFN1e#Xs2^o^KRPc`SIX!|Q8Q9U zQa_pwUcYnwNNuQ$qLySv1~a%yN9syuw=oZ>x>6=PXhutNEilR`?XH=;pz2C7JLsLLEy)qwm1blfZnY+JFPga`YDs3Zh`LhLk1}~dwx=fRY*2l6 zE>JBu?r2rFjau#7>$88a@rs(PI<2-%by+oB^;uVGV?OoWjaNpWb=3a0KHGD=)Ly&u z2uKm50u^LNY82z8maDgh8LrH4<*2zzpV4G@KVF$Uu8xkQHYALc)EYg_9lPD>v%4R! zU5(TnMlCZ7d3WO_O=YOeHCcBTOJCAdhRTe%Qx)bQ?~J~rrpzqF95k8v$Idek^JGhF zyC1L2>YyA|4P)n#+THvkGg95NkT_n>MKYA-*v0I-JI_3viDX8~G0RZa-)p?2weFEJ z>-+BJi_%nP)~N4tZJ0B^W-szr^v{9et@)$rYutxI?RrTAVLt=u1wRndPg;@5~AR z`^GEI^8ah|`$%7oS~q3wdc2fkyUJ_bQ-1XvFKI2q346}(d&;k#^!2yLD{{iO($_l~ zuV|0yDZk$1huUX$rEf%g%s+=8M&GVX)CYajT}5bH!EiIy4E_yLtzG)?I@2=ojt>bOsqShUym={SXFn z2WOcLKxduKR^vQYZC|UVntTIaS$nB-TD=Rjk*epXk!IRXo!>eRVQ!mtjmJIxVvt^v z&M7i84Sn~V6J+wMI-k&=Qtih(YQ6JGj2p3-adUONg4$BxlAy(z^GIuX%zaKdV zW7l5~G{UqT##quru;Ux`|8R~&upl1}G%nu|tj0$IH*n>-yn7+gIrq8XLJ`n;_PO*n zVAXb>{Xwv-1gI7DgJ5DAu$U{h2OID9VEf%3tijuZCcQn_ink+M=40oMv3RwFUr61^ zNZYAh47`YFMn(d=B-n>9;cnYQG^5LbT_MtudVn#%jQ)Bl@r#T|bQRF3uUDcITncn9 zbY;*Cu0%WNq<$&qujXh(BI9&@m}{;CUP;?L57U9-pwYjsCMJ-Y!L`({0h<587+u#8 z2Pb9_n99+(I8%v<6Qko8v11ZyeS9~g>DA!pzp>IqsX}Y zJBVs@CgXf7cQcazS+s6t1>!8=IUH|gz2O|-o*ZxGx+y?c%5M#8 zURF;|1{!_rUe;tz0UDv~UbxdlppyGu%48xO8vWF`hxY>SLfFO9OA9ZOqX|;*7fL^fbK#fnVhKG-tm^oKbBXUqY@` z1D&6J2`N(pG%v=NIJX06mW(e^yCp;?y$PrVPx36k{xr~tmd{ddAd0C`ERAW}0yLK8m#MV^KSJM^sog~^*?Ym; z=YrgQF398Og3Nv{Nc88B>SH;p4*DErJkZ(ubCi3DS382*SAkz4lC6=0pXXlp1E1sg ze25JCJaq9<>R+Mnd9E}<_E%|r4NM*mH0tTsSOGj1XugE6K|jX^ku6+QgR`fNB zv9~va|6ikgJQa16#qcy&WzGGeH&;SUUgwH$3b+EeJjgG7I^9dY7f=t*6g5{HJD}1I zj;=p;K&!67p9ClG1bWWZ$qwjNug9%OkC{Ndk+&i}W&^vp&Zub}aE(RuolMyZcRQAz z_tRtCI9HNSp%}$}A+>FRF1JxXl{Z>Idvl;y`I4E^%#kLi(j&pPl3V*=isz28nB-}D z!@2fGdbwL^bKri~)wgqkG}G>7j6LO~zVYq@&~w>60%o(?hbL54ZVs|?GaPmwde?Fk z>eFMiF`@oruKEl0`#FdbTbcnM+)k9!EI}=vwqR$|j&I$>S);0FU90W4|q76X( z5cCExuZfZE#!%FN52rQ?I2tT9`rQc1;lSav^rJW&csN(Edx?9uQCg91=^*FS1>MWz z+*f_EJ!q5d)Ca@m>uDQl%e@qO;?yA%gnF~q2Pt7}$DxeMkT5dCfM&9AH_>qF>d20s z^X_Rp$sV*vgt7Ja^bU0-N76GQJk3;|az@|-9UPU$Qv)aH0CsS$JUm@FPiM54dfJsh zX9hk~6)^hD=nJFgj9xcds$3yo7-(n_PK=+o8HFKca(^!lRo1}mhc^%V2k8B0nW@56|y zB_9%Wg+sVzJ!7p_v4L_3qo|&JC}jgYWexwe418Y=lq$siWsJCMCWlcD4VZ6^lZ3v* zDdq+>7UGe>Bj88k`0_vp%LA<}=RcMO{8#JVmvbwi#rFaA3f9L^JzQ@YIhVdG`W1`K zV}Y&}9R-by2TDgr(c1}z>!rDo9x-0J+XxL#0!pE38J*z2*tdz&2o&o#QJR6yR?K~8 z&OBGbHU%o*L~Sbc;!NvkNc-xiPdh*GxqRx*Yv$4J9r#~w>PFq0 zOS=FlW@vjT1d1#Ae-u)Ty)uiM@f>Esi;e7XDja<#Ji3e8DSV?YxOOMClY#Gtvv*S4 z3N3U7tCdQiQ}&vp=4q{FzQI zlNWG0?S4Vq?iaM}enH#r$Nv=}S)2nLOW6{%?|$$^HU7<%W8q`!rpHjG0H@IF?B@eO z^}J$gj+$ER(UfC?Cg|vG=iDZ+XCiPS=StB8OBkmKv^RoVu27y&ulOeRs11~(FO~(~ zdK5h1LfUdmXKiW>m1vL^V7)x_FrYI#^$GLuRYE0WXjh{HRzX$T4>nK^g;!ikulb`k zz%?$TtqsBX;wWG(TA>_&6m6{s2g7lkVbxJ$R@8Oyp(_J7a@HlcTN~z8&e5;poI3Ry zbi%7>H*ho)uKd#3l{+e(zouz5pdWsin$`j5wQWH8q4V5UpuWM*K2`!7xmFr-Cf11N zcx|B91DJ_jM|*!-2SD>HsO=YMTMFL~ieC9fyRV28mu~HGn(HmK()Z;pdB`I)$P=8;yx{0zZY;X+Hs%ELA>4S zAbVDG9Kx4Tnyle(7~f6lv6esmU-g4M7%V9PFU|uG&gZX;@xOpkzmUHQM*AYh^)b7IVa@8Lfx^swWMkYyir?2U3h*dl1)E z2iYcf(92hC&P;I!2A;3xWiB~$#I0gv51>{DR8LXEs|TtRDC_cr9Loz5PWihp+*$e7 zi=t&p+RWw3dSD*M-kj|Pm(Qg?C(vmhdYrE-0}FuemQ;2rqxIn0JMeX-qI$hLvJz8$ zU#(wCQG%y|(rH$pwdj4^CHY3(j|1GOyN zNRRQCjV=9Q+V=vl;dm20Mrby+v{syZfo49rnVy^AJXce{igG`5*Q)~5lAygvs7=8r zQ_Vo>v@b}&+mvsS5ygB--=TaP z9m3gP!d+JY|3DP_gz`t=ABifTQ2vY*|2=0qDG3==%((Pj%6E|Zzo)k=^*fF;fnBNJ z0%ww0#XL*jqkI>Q;kWeshU0ADZ#lk*d_D_!7FWCx^out*Gn?!y=3n|(%8TS(F$>f8 zDgT=K0UE;Tz|(2J#P{C@)GzoY$`6Pk-$rdj&}fun^Wer>DTh-!;Ksk^H%4++o4MM} zNZNA(&sJ0a73W7$Mj}05r!|^l-soZc?@-DNr0whUjv@N}FM+?LCGR(Plo|{Fi|*6B*weV?PG|nDa&|oeEUPadt8tsFq|Vb@%1`g!2R8R;`pn zfo*)JL6m<3rqi#$y^ON|6OKQnyb|tQ%9Ggkw@P_V+x~hfPj1`)F6E7EzeKB)um2Ko zWa76OmG~t_Q6EW`3%}C{a$Ec|HJbiWWUcV4j86Rj;hcXR==UB&&uFq|3{QTQ8bU84cRW&mk0729x>Vx4?FegUEvMTcDWNmJA}3LL24xsn(>8 z3=6H4KcogGtz=&qNcoRcOENGKisPRpC&k3%bL6X-0GyC$8JkF^2Ib?#Wxa?LG)J8~s$OLLXCxg-8`5B`dhg58x)tIkt0F zZBbd>9;A1BknK%mWtf%7y=NvXxw;e?w1Q(}irz#WZ&u=-veF=lnv!&?DQQl$nY(Y% zTyu-zOy356hv!(tc>WP6$67>L42_zh~j=l-}ChdjX z!MKcRvb-#$v?RkhI}EPzji4Qy`)(v!*4Kewr*{-}HEXSHqxj~}!y`(ljRB5^3%I{< z0e5qkTAJEC;C!T`y6_I*4M25d<)|94I`8$=_D3Qf$T{When9tb-9(RaGGgRtPR;?)L9D1E3+23hW9U^wuam@Yq_Ei*=0UL zt{C;5e)JTPJ*H1`C%IzOdWz}kNA4U~>3VVIE}&XZ2|dL~=3dF&sZ#1CGes=mBay74(;*Ipiewp)siSR3@$hR?=UA=8&D- zk7l6;q#hwu12V#ov3z3ADx>|ldTESkqx)oYHV5IJBp(Gnz*wZHJ%EnrPIi5G$DtAS z0UCwE$QsU9_2C_dj*&{r(5IZ!x}G>b=pAK2$C?0CifJb;+@m`s6Hn&J6lweX^NsRRfZ<={bv8&1Q039YbkI z&Y|b*F#l;tu<0b}#5s~MoirxSrW%t>mJfBYBxq+z(AN_5we9q%%_Wrcf$Dt;16dFWlLADnSB^g7iu&V4&YKs{3RS9Sl6J9+ew&~H@_yXe&#{UPFRph>)` znv|>A(eo>_dtBeW=!H2I44A@5Yj1bwk^V{UIMUbF{r=k8&CO>7VJ+)1s*Cwa-0!cq zTJ+-Wr0yPnSE9P$PI|Vv1IoQo?(vU%rSz$v1^0_yaqjVtJFFTx>Yb`S+Qd;mt+)?s zF0wXyZ|Tebj~uVeNV$*6k?T2L`q@P9sCPGBj#T%k?RvcQIOra=cQ;;{kQdrLVRl*K@p-RL)f#wcU-EyXK;wovR=J{PFrn(%0_BEAGqF(_AXs zHGTb08L!>Z*FJDU;|?$5sD)8$i~6sYN7oe8VYNuQ=B9pX_I52bYNiJOwcx0euHr6P zK=XSXNY4R4SHKPoI?{pE_C_O%d-C_;y468*TTPGq?bY$z73|J>^}w|hcirz#ZC%g_ z59aRK=mM)au7_TS1KoqXp4x%H1Gw%G?zIZIit9FTuY-UG(LR*Ab3k>!!+=`h)Oil) zf7Sxm(msN_=Kv4pcqIL59Yd!)U_0Bv+R@zW zP~f4#BB+LT4EHj}uU4wf{AUi5^ho-SrI_{CJ=4chjzqp5#rZ9i&B$PF=f_dDAg#5m zA5S?BS?;>Y36$fJ`bP(=jlLl#arZo+R#wOKTkss*v7eYk$+== zWB848DcjHt%)Y*zJDveNgZ6pcm|mE8Fv;00W9CDM8vGm48j{~?N=UV6J+1vIDkC1IYSPuPdK*QLNq>Ai;k zybO35?Q6Mv0gz0N%!ypXyNv~s~9^dH!zEG z{o+Qh{xI-rdT*kxAD8Q0H}n4mK)u9nK}JmgPT=mhP_6-9!_~KP_Gac!*N6F(>kzkb zmm7kGQ@^cf{d7&@4z9kD*~U%O?&R)$fj4u!i#y!}bgl6&YI=1|r0;Id-U-wOc@NOp zgXje5qwwWPz`JNYz#Z=d z-pO?z_W|#t{SbHW2XqzlA^yJz_yEUGa_{?r zlR18p+9!ann?B50y`9Wq`zh}AG2jFAewuqd2z-$CBh>YQGJEZ#lt-|YXhVOD|18Fm zqQAsvknvN2pX4fRD;z&V?NMwl4|CPyl*h2hJWTBg?)WfJU#rgopI}8pU#rh?^&`Mf z)2q$qQQ)JrwW*W>ALIBG+Qc;AG|oRoc@m4vW1RZ}cX=H6IIS;I{{q&TCxV?uJJFZ8 z?sLG;2Ahq3RL}6=PXeE$_gVhG6x+;G!B#V!<8%Dy7l5A+cAGD7{0cqVZN5nDtK8*_ zSP`D4_B{XpG zhMq((P_zN-N%Sp>HemgVzRmwX5Bw^<-{HT%2K*ZB@A4bvz^`-s9{2nP@Ee@_9$M5M zzz&Wta>uU&zs_|pa>s9CD|&(2_qo>#z!zx$fO~xlXfEy_P}6GrJz6hOwAZ@w@3f;-!_<$s%ZtDlY5$nIc2Bc&|Agy)0Q>>1pHO~`c?0|9YqWk#`3;s!trWlG|EsWEzRsE7bI;d-uW^O8^)9TKzvBEK zD8Ivs`3Cp=56Z8AzoPe#^!x{wuQ!4X>^B_$#DAI})(oV1JX7U@UL<>xk{DEte&AaGla5(J={7*VHfzp_o$el)D z_1D@vk^7ILK7#8eam@taXpWP)*J$8q+EcjW7~nXLQ>aZ&rc$4Rjek7HX_Tp0`X}+f z(-ZC1(-W=Q(`ge?j(d;C_CKEM_TU#M0vBVUp279gvByv5*g=_r4Sou(PVO}YIGNrq z>Ydosr*WJ~>B3&FeSH@H*$mVwKP%C4Ka2mLp3LUn(|}}61y19CW+&zqn#0*yWT~E& zw34k_yZ_uo%l=&Y=aA33gQHojTgh(SL2Vwt+5zn1Xuj(~k~s1)OV=z_5`pxyno){( zR(i5#Y_$k;G|jZ7o7GHB^JM8}HLKEWR=z@-^=Rf7ztnS9sFh8coTUl?g$+)Iyxu0#prxnFmRGFix}%ZTTYWBG09i0Z8wZU8S+wQh&gs78<~T9`>))sBbG2fi z{(wqf(UGgsm1rG+c3ijCCzR%}6IW6KEI|orr3-U*CE4!GRY`{-4WzuMAnkq(rR|&%FBRdC?Wm0I33G|u_|3+ckY5#43KV3TJ`*l z)$-&fHSsOTmwmf93pJXhqnB1y8h+^+wO+GEb{Zp~8Q6?{(meJ8rH#@GlHxpT%06ix zdxIMBVu_CY(cClg^hc@>Biu9Ew5nudO32=}7AQ+DttqLeP=CzzL`hTJkZsGTZOD_P zw}JGP(j7M-*D%h-`d^<^2K(xOdJpKSs~w)Vx;$I;DWT_0X}uq65b7t=)78&fMO9CS zI3L8mq5joKNTWveyT*kq73HZFM@o8n94q32cjT!K?a>I4@0iM|KCyDB2Gyh*kG=f= z^t|G6;tk0~i#i9jtFzE`#VgSjMISV!bZ2$uddtaMTj#GU)w@w=E?yB`T^`c^FP7Ic zp!*hkQTI*vM7^EHn228x^>+M%=>6fd#+8oL*F>Wy_JiIV$$rq0T3zEcY$K8(J%c zC3rV#tuU=_qBTv#b>Au6BfaSpymhqlNwchXyzWS6_KPb~EcZ>rcc4qS4!!#=Zys^o zNB`Hz*{&~u0#B!rAvA%cp>EjG?#WGYEEJiFAqYN;Eefm~LKB7AG zf!BV*=j-wjkn;UtJ#B?O)BYlx0>ycJZ)Ah9t-${L4#dNGI zYfVsp>6@wk()u!5g{D=wvi9NLs=u_>ObK#jRa_$Um%bm714&mSPQCJ>ztkr>_vT!Y z<^Z}f^;cY%K>Wwzeo;?}txsb>SET+DPo8=zuC*-QS#j1kA=Zin@f)qRnB!l1U7gtS z)L)u~#sBu{T(^2kSKpY?*PVUx-)NN7T%B`L#^_0FZbwKr? zz7|4#>mvWL*!gN@^_Tidvjfd;)H~UGO@9r`hNnrrrjZ!?PMjj;LLaHu)L*ghQv0Yy z7=y6~Q+p@1*E*;4k^bK5SyRte%IYJng{@vI0;&h~H0htCdP*w`#J(#`Kd7g~K(4oi zdQW}Vm>%fHcB7P@Qm-`%eG~hrO18eM#vZ*tVy_+Puh=`Wr}V#9PnLQ$wRci`O?{)c zsCrZVr8#pAa$@hqo)SY)ozQps=luKLN%mmuKlNi=k2>k~9#;v_)kN=h&Ddm>pnIjY z0W=@fbDNwI%X417>+)ciue)Y!@~+pjBM)}@vCFevb2U9xdg3~TF{pI{I?^-h$G1!IBnLcU8cxW0%igiH6pYwxBRe@b4RThAkQp~M9l*A zt&;zi{I=3b)#l3L`(9V6Yu1(Peb^{mp{}oNxWdSz5bs*aa1FW=u^}|)9>)7yBI^nx z%Yk}A{Sn{sy3W{Vu{Z0ntt-@fPuE#KtEb~g&}>v!s4r$Jr-H7$5@Sej#5j_o@0qTx zQq~p4tJ9Mu=|ECL9DB)oqU(<%Qg=tsm+oHve~iU;VdUw18}GUN=^~p#9GA(S(qHB{ zBDLmn9EBZ2&n5X1(y~UOd~P%rJ7tXo^}U`ljSP(veKR#K^`+I@Poqd)Uet^DYBp7i zR88(r9#U}yo7$8q#+}SdPEkglSedlqyyjK4=#l&ZH6{xa5e^TaH&iVgjnPa*3)bmMRyJUsb`;%HmGTy)IuRp3M^?d$Y{hn+~qbT*9 zkEN|YTjp5W`rj_|XZzwm>95qblGpX0j*UM$pJVBZ|JM1Www1iD-;bYTY3o?(`9E1E z^_>6cKL5AMq+Zt_J{?(ZOKRJH>Tj!Ik=lA#LSo$=z%z?;2aZBIYw*uP`pXNvS;owN( zcI31K+Y!zsqY0<^GyU2A zEO0t;9ZF{S-jwR&PXc@U797_S>_FVYcO>r5p59<@-^-WsC4C9soctDGC*m>GI1C(3 zJb+TYz+S$mZ^qu{zNjzmi-9GGi*j@cKbEq?d^K9m0P7N0^Yw^Jv$v=p$G)N9SmJa2 zIh^CUgfo3rU!PJ{3Dx{~N(=$V5m)gI*i(g2)u)rL;wP|gFgTw0N`JM#3cQB+JZhN+ zo=fb!^~Rsi)-+#)mWzUAh>Q5L#52g93Z73~n4BX1SEiD`xnFT9NRaj%|EqJAPiD_je+uzZ z>N>?=&-q>nUg@v!_xM@F1ODGdam|H_Fv&|B+T?b zyELC0%+0==$eZbJB3$l&BL8Rilgs1N{Ey&I?q+|PztrE%zRSRyh<_meNB6P&f>u6u zpSn-L&xk*Ee>nXs>>njw>>ndu z>>npy?B@_Krj{lCMb7tW@M-^)e~I`hznyE@;kLW|#M|8g;(6?O%FiRr^>6!y{vGgL z;%)5R?zXvu#4oddu78>Eq~A);Hn-IsB3|uQxs`4U>8o6yNoR@V2*!xBXk7A(n*smS0MlWp1fkOT5&rBlgIVZ+TBx;FplI)GcxA ziE|;_E$~`JOn*i7-*mov-M!{k(ldv_L!8q}zsO~Ri`^n{iCYYA;OLcpquT(!=Qe_y z+=AYSC(BwobXzv(66FY@nFcczn!zsN5n{jPi2z3N^8Un73mz2WAA^V!nB zU#*N*j4LcjC1#BOrMwQ&Ggb_WO`{YGQG4HnO=XI zGrj&RXL|it&h*m5WP0ggGQIRLnO@qPOkW1wMorFH8YpRDuz_qxm(>$?iP15cq{Qu?hbc5cspC-!fK9A zP5(vOl4=IFA(l?QS>i@_CuMJRcM;!6>L%Bo+@?V@-z;&1yPG{X5N>q(&()Ma<>v7oYZ^&Vfv|#Czm_eBf z+zfX)@eDVUILQ>%k22?zGsB(lt{^@MJz#e{9mF1W9y#Z`^W2rh=hFI>;FWCm=Zp?} z`9pNa528C;=dkx&C$EUZ{&Y9lO>**B9g5F^m|Mn^bGjSvCb|jW>BQsR8RW??VJN-` z@^>9YtaS*Z&x8CR#!+Ux8|S7Fk8@Lr<()7DzXW-=uJNn=Ic|-g#-26)Og9ZY%bf|H z?al(HyR*S_+;n%yi<9k;m!HNVFAt4FUcMQJ`~c4Oke9dWAun&$LtdU3W2teR8_UsC zojf5pp7dBZ8XV)s;qh?Dk0L$V$qVz4m!IMxKa!kLP96`3{0Pz`-EeS(lPAO>FHeQ3 ziGgmAJJrckVQON4JH?&s2DpL51KeQt3?K}2;o zOir9Yem~dMb$8vIIG1JyPlB0=wZ6CO<<|N>t~a>G4+oEPeZao%IPiGa7d*io4-Th} zwf;1Bf;;Ht9dXc$)9IiWhvz{rpU#6`o(~7Td>#&Zc{?2RGw=#I=uhV^b#h%?XV;0d z=mPfOTsjfDI{7hNg{Q(*oYl1ic|cr4Ebi3H6CGVo%68-|dxAYUMtn_|@Tk|gb3+@5yyN0fTtIwW>U{m(jCp2>MGY~87y_C71AkT&Sh~;N+XQG~KM%j9< zIdMHw_1%Ny-hn59d>rbMU(eNbEr=f?_jdda9we^gT9Q|XP}kKaUB`(l>2|yj#5lUn z*K#%8I$zt>0$Z_v9cSGNTuZ#px8#_0zPif*Yq;uQO;^Jm@V9Vv2mEYmIN-%%dccdh z^ne%p(g80|h6DalJQ)u7$M9Y_;N`s_#-szj8g*nic^=G7RCJYHCHD+o2XhnUNLO^_ zTm@GitVmqWrIRObgSq$|h*$G@;<=za8RT>DWTGr(%DJ+x3UOIim011<@^g3+FNiYa zlyzlXHDWQr9PlrZI|na>7l})ACe>VN_Lgy_NSAiio&gII`CI{)-^o8ZPu$GR2x9_(l8x1R0a?0Qn-Yu)dECHnr;cWxujN6MseOYr7RMg0*-C$a~>S z^1rfQ+Fyvb1>c5k>{*leJ2_w4zuRAlzX1OZuIK!=-6Yw+psom%0fw0fZ17V-vgWthEzZcJf zeSTj8W(?}v@87q7wSTdPf-k{gJOd6S4%iRu-|PYE{lI>ZkO#sCgneF~0rEkR2ZB5k z*rLnvtb7Q#9@4w*PH>l%C&50ygY-@-KY*_i@7c|Ela4YSpEh-f?pA@u{+qmhOpND z5_}bYq1@+K`2S4&3w{gx{A$XqvESoc@D-i{UvcCr&SZyOMgD3lZ-9M%y?xJawCg#K z&EPuX^`zdj@<{kTv4O3PcB5Zrmx9afGH``m4z9E-z*Tl7xPf@D{|zsNy%_EN1{ypI z_Iiugz+Uh06WHq+=HRcixP&8?+J!dLzH9T~10df3&pvqwc=INEm)He%iCql7NxXp6 zB3qEXg|Ol;M9DWO^QJAr)?PoK^cz;b2Lcr#dIwxYUOvj_H*d4`jxEj+d;P1Ff6cxEzG_S039#2c zY3JFOY!&SLOJhf08XthFrV8;B^p-k8+#*P4-6cW_uHOi@n+I_HD5C-|gFC;lJCr!`6Sd zZ%v)Of|Y+Sto(QT%P4!JmF4|ze>unBU@y0q5noFFWws}l{_U~WZ_oaj_Ii7rok@x7 z!OMv+q0FULmioJW4@&mL#=Z~fi^;#lcE>}Y1AYMV73fB~J68C|vG*eOUTm+Ru4}=W z#21otkv*RMyM1TViLzI-?;3kG`>(YZu=hfHf;pbO{mcpA400~8T`1Qrcn@?mS5fk6 zD<6Vx=1S66*`ek{)6Wd0^f0g=@fjR7!%hazuv6>|dp>vu@g#C4+tbW2$_(MCp=O9V ziFm3#&z@_iQtmu(3h{7r8f8wW{3JV=GDFND)1P<{VX)cEo{4s|-$cC252xfVKf(+* zr&4B+nZTZjcBC0$cKPw7C)iPDB}Wfb(qq6O#AmQ~ikS?a0gfX++nmL*r%-;N zJsCX3PA6}dA3*wKdybh-dJ-ikn_<*7$_}HZ(RKu>k>D`m31&R|hm#&*Cz6_ECYlMv zrxQ;yr;$J0USZCmo-53`#NDZRfbC|t_|3i>>F)MQ_U-gnnk$HV*zR_K?Lp{oXHxzO zGt-<$e3iM7}oX`Ht2{TPE@=mh7?1{D?coOkt?7iGv&Cxr3 z7mn>}FEumByOeO5=}b-+dky<{`c9-f+iT4=q^~pAf*r}}WG|uorRI8b9XTDy>1caX zcR#S7J;C-R7M@^_w-=fVD0?^M?lDblW6IuZ?qRDDsm8XcZ9;q(+jpC0q&nDUe(uUy7o!)5PO~^%r(!NXQ-h9$5ymeZ5>-1tV>*#vUP2F@+;WqD7C{s!BJ0|a^#e^ z&ztASdBHpnmL;d0onvORe-7aZ)0%T{Yg-fA*qhBwT+@r@1xl8oWLevay{+vnx z!W>=37Ph5rDX2&7j@oakb5srcsCk6)j}jg?UvR|V z&0}mmZZgR-0ACtIaRQS!;hWKND|f?_RT=u*ZDFv0s2+n9ogdS}I|S z(^^UUig}sqD@MAweU;Sf=2i0w@oU7do1)|w!wAe;1O8&HU2c}q&Tq7nuq(`R(klq7 z%u3=_=2!B6Gds-=TK$yPJ_kQHpP5fce`o!kWd zbB=al@)nRine3JI2cS0jVs4VYzczc6FRgomSnN*Hy(ewtq&t_TTi)6tW`5JNYxDb@R~teE=%`XLAPEL9diaH^gp3y_^%*cv$W7j zYrqUj=ubns*>%T7AIPyE$gv;z|G)h} zs>gb&Z*{6)zr4HUZ^Jz#%e z57-Yk#%H9(At0uKPr;AqmB{oV=8k$Wj&%74Z%O3!khk!xY`)mhFFNviMAnb!(;a=b z#poekkLJXwKHbq@Tg)A`0^f&NKg0m?I6m8R@F4h0UJLxBV5P~gBh#63Ug_xgwMJKq~TyZ7P~ehcZ_?5*JK_BQYiywLaJuYLz8 z@AbWSw$BD1u@8ff;t9XkKV}~VAGeQz`-me$P%8URb}#SixI*#%i2Y{>aVp!AJiuq- z2QHuS$OII5g5*6eA98u4NAKlJNnd8g5G0_%2}Y+ZpYHSVs1|?ISh%T<@L7!tUdM;w5$XqnRzKK;4hLqT z!>}n0Cq2@Q07toz;Al4r90NDgVHldmfG5yHhXWtf;lKxV7>1~^ZV!IrlVCYG1F!Nu zc;8+-K;JIRJ zk`>R?Vf@ASuq`iW`9hB%PI^+0Vk>fsMcyuPb&0X-2pd;+5AM+%ITL;^v2=-(E9nV7 z7N6`Z$P-JKIJpMnAwI;WGNj2rIq9n`4`KNU_a%;A%$YD^9fmLN3XaVTyjYnqcAZ1| zJXpOl;r6-$yb6A=OfP=3OfP=3%)oD!8TidI1HajBJl@B_S1`ej2PfJI;2z@L_^1yC z<dCc;fYo9C=9(?sgm#{kS7L-rT^Q zCy#FVb$28dU*1D-4T_~uo~|`)WGYtM{iN!3|tgA z0~ZC(z(s*Ga8ck4T*NhH!iy-jyk;>Gy7#EbED zi5KJRlEC=7Brv}2z~4U2?!a6Adpz)Wvb6&*^e;(&jj#C*eBi$Zzr}NY2mbTlg7UeK z-q-T4mY4OX!3SI3-;vcfatQw&K3}o=ehjPam&6~r=p`;cb9tM~Km9BAh!6Ke&PnXI zaM04imsuX{U$ciZCg%e@3SVMr_F9L{1}K>cz^t)c@#y0Q166ywrcsnJ*2D z$4dj_@zTI}yfiQ#FQvqfZaa(>;vLu!I1V-j2876M5cv!uSHU4#69<8q2oBP=xRRIp zb!@FS#eFef)XSHCr77Wyla_bAeC(s=ee}7Pw|^;L(wBgby98w-J9cE}E)zJi#VH_W zfz=!-Zh|$YEUek$&Mx8$dody`37iOPO*vnP*2|Gw2oxK$SQf;!u$^-fYr`TV?&hUl zj1QSc49-h^MPC6FL&UqL5?f2X_yS%tHGFlSo~7juO8Bi4OW!S>~H2f2R`%8fz$jx^6xiY$Xk}hX+Ddb`^<8-mcdosjd(ds z<=wy@#LEL?`SQRXzcui@Y=sx*F0&Qxn7ctS$87cDciGDQo@M$5#(c4s+-i=8H@}Y; zdy6<+?j#ly{qii<`u>5zUL5ygy6?@__0%Cw8F9%Bpwx2sZMKpd8TG}Oe_|HLeq>0A z>@YXNlp-dT$e40FEnmw~*O`;ySYPh1A$_em1*Y}ofoXlYznYwD%&BZG_g9g=8or*b zqz1v~z8vPCt?>Jd@WWxw7f;Q_W~3iMS}Z)`;<=nSl@DKxKIaEcpUX`u2Y!-)e;BO! z=Vmbji6LkLeDTWzNBkgg$Uj)|&w)SaTr=8hEda6hkMYwvlPh2~5+l(>$}abj4@k^A z;@^o(JeRUHilat*ar#_nRsrdr7x@d>JDrse&h%Od;5<<43ta3kB7X#B zMw)TdEgmRwHjT^TZJNy1Ig~uti`Qv_xr8HDz=XAhV@?Byn@jyAt)I%1e*)$EnUyfiUk3m6W$?_eB&>iPY8X6Wo4q)_ zHgjK3gF9@qKf&BW$(4b@|As7X|Et5w2jb5fXl{jxeWmY9$>U9A|BoD7V($`%mw3Le zVT}Z>l%Vwt#JzQjxefmJmHs%6>T9lL&vjlbT_?kXwwc`9;e}u6dz0>C?tmSBWnhP2 z>3fmW+uX(0O1R!W18);GwFEa4 zi+6ri7CU`y@|v4h*jnWyzg`_!_?pAYx5?Kwk;Oi8-HSC(+ynABbt4p03h%zX~3}O_Y0&P|S$0-zJK(Rm|jrRc5s>Lb|9C56@~Z z)j7w0fQ7{6IJ&$^uw~%0 zp+>MEv4bn~J#Prsl!NhRwfFF5z6Xl=(vvD|%ENlI+KcJFOkm9^$geUTlZ*Z0&=e1* zxH1bGvE-KyTsz{`7t4-#=U2nj`JPXhU%}r3`_F3s3+Z2BH>t>8S?HHch)Gj?ngw9O zjO>}>#LQ=k!iZBik%v8bjad7|-CvYg96==#V)M*n>cNdt2{!pk)b=?wi;Z+6_xCf> zpTjS|8rJIi>|gE0R4Tqw@s^6Cz8;uPEEf7T{!@pCK zG4P`PL|hx+`#NyCH{jS$IQCO`kE)U<-u&9|v~DD~5&PHpk4S$E<9j30Vt!xaKP2a) zgn0IA!SCLLoDazPFmSDkarFn-P%{GOl6Xh+NV!h1)$XQjXPDyGz-GGJPZ$7Sd^c)|9P<51t@Yv}-VQhM2EQ^e{)+ck{J)WFKC;uVfel!k z!K;bIQ-2cJllT2EPKX;VtkIi*;Ds!)u6_k-r?S_fse%*83A-N#5X>!TUat zoI%8E;aT3`m%^MMdGp1e-;y;6n#0{I-d-{IzMmKjNBmm9n378ZJMiJG)d*UJl?z(4 z)h2KUAIf6k7eD-3xSKb?+&qrdcsQG1V{1O~20xaZad5=1g#mgZ?D1>isop^8R}$-C zx_txQXW<6gi#*HgxSGu{S+A#@xaHURF&r}%p8CPWksE&=dtVL=@9X@Va7{1%2UGQ8 zc&Q_Yz8LmL!_L0WUkIP~qZ}bl_;ui9;u)kafa80;p9elhd=VV(>-;069)%HnJ*kV~ zb6@A@uzwyr-1FeuPIAsq=J=u1KMDr%_5NYF-Y=%)6Ioo{;_SYK?e+d<@D>>Ar@&D! zp8E6QgTI8ln+P|URV_buq)=02ln_#99HO7wpxW67K~L>rGi~>~{u6b}{dt z8~DD(`ke{?cjT9kD=x$}BR0@K8w0od17Qt@;{%)ahQLsNU10D(CyUKrtmooBf09^y z_F}RZqy1g9DW>@Q;farIaE3lOHVoNIni+!Xgd0JOkd}dl*SnJ4&r%J2IdY)}DSH*Q?yAtQ-P0=-= z*sbEq$eqd43bkT$=|rAZv5o85YAxjsY-!b7v9HB7n%lFbRdVCnxmvwBuJx=no(q%K zD!W>3H?GWEgf&9i@C`{_**UKK8`pF`vhH>Xo^!1X+&u8bX~p2Uo^VOt&*F~Ls>G$i zW^8G7Vy#px?zqN;vY^&x)*8%OcUjzVT4T99sI`f;;<8p*7I%}@QmzPUC1R~EtS?u6 zVy!5wl~eQ`)B3_%DOucKwF&y3)L~1j(#G$L-s}3>#1)rokkYEl;^xyDyBYtr{!(vg zP2jEp#c!t`$_sWOR)4A2lKqwJDfLi+tiDqZ6{PPv5UXzrf$fRaQ(7B2xrTC)&})T$ z*I#1uYeilW`lc1>qxDzpDY5)%{pS+@=&#sQab0QkUb4SpPsJ6b)l=%VGAaF~6|&V+ z$zE$f`p62=73drF+L8W>D`6k$uVhbYWoz}FdP-O&e2rsI)%;z5X*+{58T6j|wHjEB zZS}X-;?X=IuA8knN$oH`;%Yl}IJe}usmw@9j;BhTe;j8TZw>!(Jr%g#I4(6l8)sd= z?n9F>lADCl+>~@2)LAtAF(gCBDAFE)Pt=< zFX}lgN-q~>ThC_^P`$2kP#DzHtC3L%)F{!2DF|xxbPOY^V;EJP!rPz|IUU3J%LnFT z6vox9H7@g#))lzGTj|Z^LA}NFMsuLvZhF&M(6U`U zyaTI~)0>w2(4ywI6?r@BX&A=3JDqti4G;la&$C4V(EMg4#;|RT&TZ|=t0=10ZpDC$0g?Xln_;wjWH5u8l^ z6v8;ZC1PBQIgkbZ|Obmy&xPcro#%q%L4a(2qJU zV~*I5Z}SY=x}4Asyo9Zpl)8W~=w+0-f|@S|&nLc;+>63@^a8%5SCD@-+n0b>5^MdM zi@}RI`r0sOy_WhfV=i$C^z zJ#(a6DR~Fs24*DJQ{SEJxgNZcBkp3)4d4y5a5s53GdsA6HRYHtP3B7TIjvzXW3Lw%1@_8w-j_fp?ul)aZZ>wVPpID776 z?s`8p&0){|i6_W?2z;FQN%9^9ALQt{)c-Ij3F9f+XbC<-{1jy$0v}@QY0Az9XH%=z zxp^3Tm|CAD?@{nkYSjujkAaU-_w(dE4n9sDFOW9}oI@Qi(#l*=l8V;2c?x`<_$69x z0X{`MFU)=CQTl0Q0nPqi=7_nVW__=a`z$z*_*L?rL*96nI$k61S@3ykd7T>OfzJ`Y zPO0aRGzL<~{2&j_N5(l7$>Akhe1jui0wo8%N!fYKL|>%V1(bb}`R6=peTzNwSV8Ay zYSK*gW#+1{aNIlWc_p!s+}FXkiQlE>`OKl4^99MI#2ernY-LjRHKdb;lw3s6>N)eN zX)#C4XKkA|sc8v&-b89!Kut^8vjCayEsk48$OM$ban%1yq5wg~5^4AiUf=em8jy+4jCDgH=Jfuw| zox$K>j^0S_${;~310~sSWVNvy^+mV!aQqy7f>_lSTMSbtHXBYCbv=x%1ccTwr-5v0K;=l1# zO@IlG{(v?bf(M8{p!5OoFT|{cLwz4|#6H%-*-w2R5#9&23eU&vIS3x4?oY^jpS5s4 zCjBYlFKC3`=eW<<^FG=iOKYDK{)R5-Q}%vAdkw%3h`(U_19Ux~QU33Q57GI2PRTC` zAE5#Hm?OSok90L3vh_8&pMYNyOULplT9!{Z`djioL31M(?(djaIM7nl_muh+{FIiy zCo}-1fBJ!AwC2v=spAKZ{tOM%=Rx1}B{luX(VwG#l5Xf{w!TJ#^%Ln|2;Z<0&et6A zD|^09{6<^fA*_8vy$SORdlN?5uY~!YR*d&qmB8MqpbOk`mFhlqZ}*f`~?0) zz25vteI5U-=wck52Bxu9oIUx`TbdRNqjfD}>Lkigsvzk)%(}~vDuOPx5H*$Mh(cgdYAQ!7#lX_U(!LgF zRhweeSAkFpEXP(w_7n$;Q(q9u12aN8uF^NlR>Cps*_jI)F4#}%pk65qkz7fRjH{id#a&5uS2>%sp?=|;s$Kj2y5PCpp%yl zyCE&sL_=SnGL2}bW}*?H23Vb~#+0rNHXv?HN;>|AwAO@BC;UCA4>l&h8F~7XP={8V zlUEc4Vt7``UtSDchA&t@)GFg}vR`Y7e%jt{!ab?@MKj?C;KBxW44~Glh}8`cY3G(uHX6L?h<^6Dd~>Jf8R@%Jl|MAns48 zKCE_g5;+41$AQODN`Kt?gnw&&`SUh_oPlih1^aT`sT`$0c7`9hjcc3&mujUn&Ln2=|=yNrW^e=nogOs$)9E_lCFrXJe_jW z%t_2A`iE~`Lu6fj_lFS%AlVKJIDk2}WM|>Y%z>rn6rRHTbR@BGAhXj^#KKdV-Hj#| z4q_HIhWbwe2QycaK71%Rnys;Xe+{TF@>o*CkY&dPl*BzgNY+}>^)zJE@w7RCFalY2 zLco!^z0^G=gMj zNylfBlGH32SvuQ^;6&;^n;>~P%E*&~ye#Qi^74tGvxl8vtcuOik8u-71)UPBA|A8`#btz_ie2-ktvQMdj( zNOr!Sy7iYq^70KqcD@mv%$?*(n(mA4=Ptg)X&= z)jG4cAj{rM`aXhWXGzuiPjEYUJ9R%mEWCp@Bq1LM>c7N;e2Mdbd1&Dwg5+pP&9g~K zg1(1ZXOnj~lIm>Ij}T^ov#47uzut?~`UvUA2$G#8FF#I7vhxGf|2UyHDA{=q-{8Dp zURrp9Sok1yKS`JkN>ZLnN^-O$W&MeG7<`x(w1%wk5n6bLSokQlK1(dr-x*2Ey}`$b zpW{oP56nk9`kNx0Lklku3!k8c_3Q5S%gZYVHBYqwk_4yz>OP~Nzjs! z7m8=*;(?k{>d%|yQA-voZKB;OuUvaaUoD&Cdrb>UFfUop=M%>;`Jx!PW+()s57xRb?edzenA>h$S^klHN^_?7W%!cN4lG zx$0ZLhi`mQut<=gx6p$A$ZtVT-AW7k7rzw=bsH`0XKNc0?RHwwKk@Czt2=1nAX__- zW+g8lBJ4tH-9;Ocle>Uj&@CTk&o1QGV$`kw(84{`{a1qIXvxTbBNhMX>rejvAUjJs z{*aVpXGzr`k&^5jmxA5(j$AT4(W57E*m!NTGbW+cT)7o)XL34Z}4L2I2^$<%+L z)z68Ae+|;~2h=M23Q5*~3v%=qX-^)u?0HN2v;vMkMk zlB)BOvS40f$;Ryx`Pr5nEvXsFm06tRXxY(}qSa`ZBWYPH-WCL9(-Wj=S}4MnFfGW= zlBA0gu(2T)<_+?4K5CbJl4NJ;r6n`BOOyz6!V+NySb}yXO&6r@l0kwlN&AwiOOjKX zP#Bb?EZMjS@@)}XklmEz=rW|s5hOcHl9q(rHlej;i;dbA>Gx?aHQ)ZKus8px)SktG|~0&5V<>P-@~r0T|m+DNF9p_>pSJ4;@c z{awpMQ&N(k^`EL4Gw=!^f1Qz2>jgPFO3?LbK~{kEkx&~@w`>6$Ak#Jsva_V))}$JP zlB(N~lGNOUHrkNa7-_aCZM9`f60~&G?P#kR(rhzol~mjUlvFKCNXgDEXhZUFD^QZM zBp&eST|xGN~BSrT-!#BpqOMRu)B8^=>; zcTkeF*1DDK+?`tc5qg4>i%%rg3zQ@+n^;NBy{J#NslwjWC+kz8^wN@=n}L0ZPYzP5 zq-Dv`l@pSnPbMu%xF0A4V3=p3|f?pwX{I8xt7#i zom^R6k455@Zb~cbjw3yeHm6cj(yDZ2(~LB7)5x7bj-=yhl$X3bfwPeP_XMyuCC)O^ z6H0cTNO~gYbr$)On(L4&+4*!(+RL*^O$t)8P#V!E+wX$hUjdkb7hUd zNyLU{IDzb{XW1gpR|G4v?a*sf0xPlY=~1zLR%SaF`V{fsrn8-!wCr)J5~qRsE3Uhg z2b5)p?p0n;|Ic;D@`1AK&>hPU$_7VwDL?ljuJV|lxue#JEXXz2Vpdn1R3WadHmGYX z3>IQmRF_l{uB|S!qAj1AMVVzt17DmVyH4GK5`^M>r!{6u5=!uW)5wt> zM@e)N8pEXtrO-p@2`WP<&HG#Lhq8n+yi@g-C`TyE`%mws@`Q5CrSvxLLMYE1t`(`S zd;?lBYt*-(8$osgZAf+Jo7aXJb6Zk9!k^h5eAnACQ*Y09PrmoJ922yJi=i z!QNp;)e%jAbRD{z)xy>OPc$Bu{v8?g6|xo>h~7ckkJ03%S__@JH4H(oS4UxD3?a z|LcN=L|Tp$NFT8uIJ(Wizqb~Mb^_9S+{*Kx2Bro5Mzj!+ZNP0oTOwV@@n{^R1G$|b zjfd<6qRl|kT0nLJ(PrRi)&lzbpWS9aI*NM1rGm)KubRE)&L~DTu z*p{wCI*_AT3;eU4fV2}26Qt#kErGNg$AQv*JQB1e*{ubn{fIUL*{ublu0u8h*{ua+ zClGB0=JJlrhmIj%&~HdX5-kLzJAr63Aic&@Xc|&& z24pP|EeBrYEu0^HL;j%ac%G6k(P}U7DdK1+5N!scg+Qv!z`wQ@NVO1%HUsl{%NIc3 zP$1|!UZNFQ2s{r;Tk-~}m(V&yI|1oHqP0NMPC!-xN3#}qi+pJ}-ayw7tp#KQkhB?) zrs7?K^d7Pbkj+3(@EzhzQa#W;ETp`w1s0%h_-AVYSp{Ub8Hm;bvH_5_fV3RaQLNzm zR2VEoO)IIlJ1FY{X*zm<(u&AtU=bPzX+n~g1F{hKz2(5avKc7C(b=s9q%)DOqdR(s zRBHk0K%&h+(oP`S4E&L`fb0aK&A@iPtVPf<6bV|6XeY3dR(24&g8ytSAPa$LEf8%3 zQmqB{ux|?*2Wdi*b^@{-khQ=TbPUpg?B|;$q~4jdxqk8K8u(^9I1zz5XcIp{dLpmC6$K(rZ1S_?!w0a*wntp#Ko@Cog|56VJ7 zmIH^-G<+QN8=sK#IWv#qVDX^Sh}Hs~(O5(~0oe?64tkA`L0Jn#%YkSu5G@B}E%19g z0a+2qTHs@J45`)vC1~k8<~JqKHzX|tI+2bx1JaWu?F6EQfV3acPC&K+@=%fez|ZJC zz6PcL_+vW({Vn>9aKu{Rd+JZx3}|kXFq+RKZ3d(diIxM|Z3bj5;Lu7)*YVFb1JZaz z%Yif_9YvbaAEh)?info~474Zx&o%?H7LazsgVKs*w;aev{_m{?n}KK{5UmBI?> zMwTb0&30h48IaB-X)_S51!OspYAqm5M+vkMvLcY>Kv6Ue<;aP40?}rm65G;sNc&Nl zR%9(8y~h!ofwou+Xr`L97LaW~(q@43LJuL!fokNHN6R1!foLrtJAv}(8)QF_-C95z ziJG(}U5B&>NoxVkkfrfx1E$&xL~DU)Cm`*J>;$TSvL%qUKvhr{0`*A!-g2NG`3-61 zh_!%b{+W=V(NTbmjl*U6^jy9kqwT`ADtsb!%XqkvM1D%Xy6WI(% z@6nO+N3#=<6@hda9YEIz=JxKe}&q%uLM_aNJkQ8>Jk^CinM|1G^ z)&kOf9ET=C)&;U0=xJm*AdN?=wSepaWHWFaC|iP~Sq@a8RoM(k?{T7OdW_ZrvJ;3l z1JO<(+6*ME1*%{tFv3VW9$_RGN812tH=2@;)&i0`qn$vs8HjcQ(PkiNEg(CAG3Y1; zqgP0^7Lc7lv>C{5El`d2CYb6-h|+kBMr$BBSK5sx;5g!FClGB0CK<`&lZ+(sNgO3R zfeAtTk!mMUlYQB(1!NBp?F6FDz*HkCeyWk=F71bG2F?hY4N2eAjO1?F2{Zu z3;cUK0a*wntpy$?{U|{;_L8Unyq$n71fsP-b~^!C2t;dv{~bF4SqMaHfuq?8L<<2~ z3&>93DgMvPLLgcT{5v}VSqMaHfuq?8$TlFmwSX)HWGx`6`3=(9?F6E2K&rLC|IAK6 zwgK6#1u}!Y{3h)!Mw}?foL<3KvF#x zYk_}nAs~r3+6hG4fM_QWZ3Cj6z#m%(NcPN+#49@iStT6JS|Hj9$U;EY0+Oa>KX5c_ z0oe&8Z3bi~P?W8IWi5~&c{FJ!5G@2GJtu7gWGx^Ifr3b-M=S)&WLXHvQb4u=vJjB9 zKz0j(Xd57_fTXp6BwtwwlmR7!S3vep+6hz)QuCj;7Lc7lv>B*I`?9n@nzexJ1fqpN zv=;cYb^=E%1ftEr(JTa_ZGh|q>LWQv3xN#&&nGPesv|o`3xT9K&qX< z(JTaHiy%9J3W=nhK(r8$wSepdnj;BEJAr5+AZr0x2((0Um9;=;wpt;l{*j%)(Jci2 zjBS9d0-}Y$AKL~<+LeUd986jWR7&&>(sy6vaajvUQcl_o$WA~u1F{y7oj|l1$Zjnl zJAr63aIDq>eUYGLE%4{<1SCC2Yk{NL3CKbqS_=#dl74nO0a*w{Yk@zu6Oe^Kv=)dK z0;AX(gtYpv?F5d+LO@mlsdfTM3xQ}GFp?IM76P&jh;{;#gH$U!fyRkHV<#XBfoLu8 z@9YGkg@EMhXeS^UxmF^(oq#L}l9KX&ZYL0J15&L8WGA41@`acI=)b%E;pYd%$)JD! zc|iT+&rK-6TT>qWWeBB_MaA7Ak9P;kR=`k8VXy$PAypL2&6X?4f57 zN%o|t_obc$7S#Hm)|b?A!J4`c|06AXR*jKsfGGC+n;a}sQ)Sh zxVvefB(?$JkB7XWm7hj@GQE)(9Ka0pWK!~W=)yk)c@_)v5uZY;6My+n38;UG0}1kf z&>w(Px&QgWfg!CK%BgG*wnh} zf;=TOUyvVbJ1hZ)kRBTTgAJtzi;&hgb|~eCU~@2(^f2;=g8Jt(jP2HVO%x*~9}cCZ z!Ick(P=ADm6J(K~Z_WsMyErJVr+hnjFkbyJBE}P4K!;Q7c5Q2 zk&?H@ShmJ9qRWBOe~%9~DdX9eMrIsa6Bxr4K-sOxU!);efp{V#ydo&Q)kIR#-ArKX zbn@lVF_HY!3H8tgNmDzC@m(1_J>*CeHi=wWJfxG7#;7hRz1n0_bx3?FcEKwxJ|@hBHj{ln#>PhviQ2i{splB;3 zD(jg8Wb9*rrDrBaMAjXRCEl8i--O^wVFj8%SBy`Jrf%9MR_jt zw^&a{5uO}9PkN3D^Ni`4(-T*SJ0n&TJ&*YAg?pxFwgAtv?xmh+y`9Bs(ix20C3(U- zAun$Yy-Osm=HcCdolU)7gowUW_!2f{tv-uCOEN4q=RlIjcKku{-C|j##L-qVBLz zZ$;fOPC(NpD5nZSkGyt(fFH z(_2yZxdiuFZ$;hh;@n}q6?LDBacA{b6yKTbI`vl6-7dnN)mu?~XN9@XdMoN~%RW?3 znfT5Ma%c4=(LFD~9oAb>cUyL*ddhUS^KqZ`lvf-iqpJa?;yy2TF5SHNNzAFU>vF zJh?SNj8z(C;qN~EQj*;6VYKRfUzR@7=8?jIF zNo`Pb1xLPQ5!uf=LSuS1jr`n%n)GFLay>m?ou1B3PA<}tU^M?oPmjESNrpM`114Dm z#Xi?M+(A7p`dW*dF7gXTwz2*1*V1mt--_%l&R1 z`aizEl1ztU%+u4QH(N8XOSm5KmUX6o^$VjO7WP&?g9qdUg z`K~9UF1|DMj-V#m{n)Dx{Yq~4QaEY!PHV>9_K)zhY@ zTTfsu`rS~gW|;;wY-^TjLCr=r%XFY-qnc}aP_xm3+{0X;W}|u&6#QL1sv%jMYEYf3 zO*N=a)utL$XZ}z_0mjb%&bj>Gy{0JFt4B3=kFtIu#KK(Md(Gq32e}Ebt&oZhIDHFv81c>)RyF_(f77GPh@FOGvDewbMjCqN2&&2fuf+k zu{C%@6bJPk);q2wZ~PkUEesan+0@rQgXgRQs2M>9+tqoxDv^>*DLzSkZ))@zb4Zw`HLqhwZve93F^TbrLNl+*@?3r~pNwi*Ema`LbhpHaP~_0;OF)CTp& z)|)wvapZ_|g>5}&I$rO#nuOAzzN$3|WkG!_%M+KQl)i(t2*p8tJ!=t4f+g9n*<&rP zpa@ulBPxJ;_tXe)8qEdDbIp49q=S0L=*uQgl)_+Pj;ca_{H|$^p)1cIuPRuBSn~ya z%kq=2H=w>>nuo{-rZ(5EccH#k)wx<}wDg_Q_a}qx_=VE9sXAAyTz!x9RnoR^1`iAN~*pqXYY@l~zkMOqC%ukY@-l#&&9(3hG%?~P&>Jsiq z=Ws8Do%zz}&I%=A>Rt;adFt*9H7ikn2sM`}MXFusr?#MGJ-YjCLQe=K@v3ixl7#g& zYyoN(5$E&jqZZt2%|X;tEx7xdxfEi%S?G!8p;wx6_chbe9HS|BT(X~fqzQLiGlYC> zHwt~xIP^k8?zQF>y8jKi%bJa(v0Xp(LIdt~8acTLb;F&n$6e1w+7s%~8$Mv1QE1ko z9+SSq2Go;bNY$i=4e2J~92W4ckJ%sw9Zn#!>w%Dh; zUy^Imb=M)(rSCL9RS%Wo`ZW4#6Y6kPxk!~}Pn^%T33n#Wo@y};;tW^4@3{UN;a=&P zj5FLgpVc_g9jn23>cBq3NY)decarX*o<@zU@?oTvC#5-ro*2zx#gf{IeVQ@osmfr4 zR}7<8PeD&czeau~ax}g*o-2j%tmmQ!&qI6`x{|A>qdV9&JR5on(!+C6GV2cYCN9OZ z)En&0-6&1Xy}({p78}ra60e&a^8j&C28RCCzphu0iMA z~b`L$J zUea4p-_5R}*VIeuH+>O>aV)9dG`c#`Ka~RNeW>rFP-9zt*MVMA@9A48)X3M@P^hOv zBUh-mqDH?^Pn(_rq27t=DfN%O;rf=Tf7FNSDfN%~P(2krB;^|!C18D{^`0t3|ELeu zQ~5#lp57bkAN8SnO8uiZih4@@qdrtmsejam>M8Y)`cOTk{!t&Qr_?{{L-myUM}4TC zQvawA)l=#p^`Uwy0jdw<^QNaw&qsU;HKuj<)49u)DWNALez&TI`>lJg=UKg|CtTyc zQ+S5-KG0kxz7Hfxb|goAqHnt7j`)5_&?oV|qNh=BXuWCl#)K(j`}KSbk_kjQ)vULfAwzF8&>aHjauo4 z_4d^pxi$A&J(h=%#=R=RUcI&T?$%qpSh$z^Vz$icLp^QkJ-zkgH$Y#5=Jc(4GWKx% zeiRA)Q-J*Z;c3@5Mm?#oO;g5;db=P&|K$pkUx*w%_v(4g*!5&<#-=%Z9_q+Pths$! z7+d06-jtv9;nJ{tF$FKRZVnQMan zc5G|@n&650|JZvAFguF$eY@+7Pux8-6BmfPha^OBcbDMq?ykXE2=4B>xG(PRi@QsJ z@4l<(otcoZVePm7{c@eFo|2Z+Que%3T}0kipHW|m$m^M`?4=bYh1mKFyoJ`JZSjTJ z)(f$%7kKyWDY0ei>0ImeY-{%2S8<<3++*T(_FOqjwC5_~-pu=Mi{c%MmU^F!;{7z{ zJk|#5m-R`>LVlJ6 zt)#h@v#X)BgET9%O{6)S?O-r1z;Q6m+-yI#BIj)OpSCeuTkYITdvnLWG!t`PX{#zhLiBO1}56eMbrTyq_tiH1CU?Tju?hwJGn@oH5ysY+u%UQ=+xFX{?Wy z*bZ%t1rVRD+G~;Lm;LSh_80z(=SV$)|K<5?MV{M!paA+`sSis3;5DbK)n1_KulM3L*m|m~ zQ{DBhi}=<4f8BKcWPDC}xn=I%0JJ9wq+0Rs_AqX1$)5H+UR?|Bx`=d1?4wFZHH&xA zoU6A7^In?9=huWg@p*ecjlnWvpKv4Y-Coh>ZETrivN`v%%p-jV9`A8Jr*v-5mHw%i zfA)%+#VfMMERI)GJHC4DUbj!%o}{*Bq&v6Yc8f>2mwS6}>AcN3Upi|Mv3HfOqbdKN zu7Y)Qxw>?XUaR-!wR;a*e|S&c+k)MrPcFYZ?>GHl{k!vi)Ai+Zh`H~vW9&if`P$QS zw2%D^wtKN()DFcysCDd>oVR!4Z1xfM0nNDsYq@JmH0KUnE5cE)Irm|kZ$Q2kXkXKS zPz5%ktZVEIm5M0kkn49RE$^=;#ag?hY_l>zC6WQO?N!I8Z;xruVc+ZfaCC5XVH+tW zwr8-{sI{u8B(0Xbx_U}{MpL-z$z11TVwpx``e)zU;sn1v(Tvno?m~IL?@I2`m|om> zK8-MyK6o+8ClVTRKP@O7PdttO*mo!!v9_vFR;y&aoenMsR$#H>JJy1w0(%zUy_PNI zSiV?)wSg()9+oCu5-nwlLEr9@#6_U3Nn4u&=-Zt^96;Y|A7XXo<3Zb{GkGQAYSkUl zm72E!NAf1sp|l}CiZ|aDY)gJL=~2{ycBDEG#(?dK#}bdBPIMqOj(9Bfpd%^eT;e$T ze`f&VQ2JygQ+>cbTvPfUiZlF0c$Z3ZdND%uW@H#bs)o0z9z$7nPs(~Rb_^yZ@ArFb zHI%FG=*NgLh*DXA+6*P;-6_+up(|;%5i$WK?A-_hd4kqxEseatcEn2(FU9k9#MIKL zJWS0tC3SL*NnU^s2?b+XiQKm*Mztcsl*-=Z&WKMGwDs- zhnl6tY&_SZrpY;jyh#o`o>UESb(|^GP*a_IID@F69y>E~X3>RuKZ$fVV%wkWp*x`) zb$<$}9>m?L>5G%Q)e#zi&x^z#eeZioVoZf zsctx9aYp9(tvSwLoR>LcabDJ#*yref`}8dJYSOiMO|o3C(QB3EdhOmr-txRRXKT*K zyk}?4J_DbHvo)WM&nUzzP0!AI^S${m{(rg}@80u!t?3{AFRwRm*3{hz{-e*` zfAJrEA3hKN(f5?zSUy8c%+%R(G23i~1)j3|%Iq^xZC%pHsl8KgXI?((7$c*!-e_?v zuatAPqxY6w%0k=HgUd1HrEN0DO#i{TNt(sw^UgHSc7)IQy2m*GcQz&yuouwQ&DJmH zuLd1Wl?!wMlf=gnGox>p6FKIpb4;@?@6MjGKI5==kax)Bt?#)lq723U)n3-ScZ5|+ zpuE6QSXqI2$6?n=Gw*0C7dP+NTHqSZ=Wjo~5#NPe!rE&6Eh4lAl}=b=isIYN`#S4^ zZ^aQX5W0Ylcp;8-%D|OaIl9UIdV)$9e8$!B-qpJL#(ayuOY3aXGo|s&9$sCXwayyo zz50yO)3U_&Z+)=Dnvu#(JIeahrxUAVO4=vq!pgMadIA~_R0Rt8K3f2d9d@razX`fNO?hNoIjS5cJ8d5 zgZieVgR=c8FHk0+_DOj`(vYfeQkU2(zO}qQIG0KCf;69~JKm%=Z_5bmmB07jPyfHA zXHFXCq-|DSZY%EvdXKq=*}GT6{J*AWcI3*n%}LMfIAV`sFKJ(pYnzp<+RAOw_7vTz zQ}fd^Yt3cbx4kP1oWGvgIr!Y#=0B!qPV&Hsv~+vjf0v%Qu7=s!y5s2Z*c<2C=D9V@ zslCswXI5%nU)!uKFzHm(e%apb1AGhpVoU#5>X~y5v*Vp(pFO?OdFOVH=33h;yDyDz z+P9o$n9dj+1)TvqKX6aSCub*V*5K?R&0o?OmgY5Swjt93HM}%(2it(>%>tn*Zk=IG6J}{4eKtj;LNkn)}s` zuFeUaDLO~=?sEBflASxhsIG3sIn=z!7~Hcoo-55JJ+pm+=XLIs=9Kmo{<||1`w*{6 z38ZcvgF=rX20RISXyZlc^-#FkXvu z6J=Bl<8}GIR!Apb-8{!))8ObggzIJ`1VnHUO3j< zQzIdeg@m%Aq+eCL z+BIHT7w$@3jaOEyQ*~aPG^=U;t@TA$o=dIvCf80l;v^kT(&ywF3`Zk%s$;2D)>Lbo z+B&tVYF5Wk!<>U#^O6l%F>hEctGXVgCeDA7e%0EZYgW~ys84aGR9B~}#>G~iYK8T| zwljkFkaVrq&!lm+#Sh~xIUh?lH%XgndmP4_wD#83xHgTo(f(iv@7#Hv?OF>SYivVG z?Cl%{>>Jc2S*w$l)gHpMb$(&HTiEXY)$LB6np)rgb-S~z)op$M$#$14>*}|@q|LSU zEo^rS+ua{&caC&v)Jt{>Y1FGf-u?HqyZMcG+8@-8bc-}pw_GWA+cSC{L_FuTly<;m%4t!QO=b=h3vcgc#j z?&vlz`&k)WZbhp#f3l^O(-lRQr{%vh(Yl;&LF{LfU#x6Szk|f=w5XNwB`aE`IPp}UQ7K2(3E}Un| z=l{3lDoLWEt%}l>TI+S&VqJ^Z+*;OlS=ahC*{!G6m!vC7NtDjlj&Zs5daa~IiHWOh z=p&QnoJvemyDQMPey`oB4b^^BE#bV{og-edURTDVY)pwt-tOwRxPRPkU7PfIS+D1< zPmA@`;*#BZYIn)&$#$9S)>Dg17VEY|W%9PNy!9zhsoMq@^1J^Pe)o@!cmEE5k-Xi_ z?KSeB8Sk`mPorKgMR8VHSGtm9n+wOgg?fa4g&yIbAMbuU&;0FpmwZ9=*~-Vb-}-4S zXuJDYjCal|Yv-A@qh9h0RfAB!_0{#$Qb&+`YuPT-sON06cAl9$w0=9@Inw2RT5_c{ z>ZOrxZf`Aht7*2GJXO>$EFACtm&Ut!%`oeFM#}i)cePr)G~TJdtDRx$aiwlApJ#Su zzL{p5`8?CsH~)6$+%s{yKjI&m>+;&d-g3{#`dYlCzf0P>T#J|5-EX}lZFlusT&)(b z{zxb9Q?@y8|48SPbv1f(dr1zNtHmYHNZVo3(=D85{;%uJ(|Gq=X7|suyZN;^$3ffO z+Fm>f~GrPJT$x2uL|IY7} zrKEL1m8-aF=>OJu_m9X`>Pu7{%hGxP`KVV{uA;Z`ACYHjftZha3(D{2UI`$#TA5p- zqSeZ8$2%=j^0fi-QBQui;N#uzx4XJCOeHOOyHl1j@09=+wmWUYQ@cy+^eWX{*zW4L zyX4uQ=9%?doL>Hk+0AdfQ?^+v&zyU<`M=Tb>Ps?f+nqDa#P9OCWzrp_Ij6GBH1kYc z@4tiJ$vTsC<=j~(qshzkUo2?k%wIA0bSHC1J-u2Yg=QCNnYp$m<``e5Z=S+3mj zkNRUJPb_`1^v4>-9VUM)SIgBG!_@%w%&PB+rKg7T6uq$Y)6y$Tuh`^|<=dRw6KfDp zTU*@vo>=;3>7Su>wq9AT2B>wmKK%M)>8qiCmYU~9K)p8f$I=r^&n)ea`|{rV#Co7t z*1Y_&^flKrBY^s5Eqq@K-`B$SwXl87%RhBte>gvX;)Uba!tpD4fiIkIESzsFoF6Xi z4;S`_3;V-`{A(d!PV3Dq><<_AhYS0|h5h0Get(#+)Zw~KO2UUAA$0|7W#+@s%8VfG zR~6LIDBBK{3bS2o$(VC9~$Fc1hN|yuumhtm!eGYVm*e&o2 z8VinPzfIY1Jg98>1-3p94&XmtAS@lfaXSH=!2dqYnU)8a=PSosa)vEHB_~@F#$->i zWd+bLAiu~NUf?^lquAybb3^tLB`;=AvVBFqsymaCt=YO2sQme5w!V~YLwak_FA;AO zzdZZ|N357V5x=4AmwH3CEnBzA9;a+2&~GSjN6EI}>co#xwlcUfUrOGdlI=jhhWsdH ztAKt<`4P%?09PY^g#2pYqr^KB?~pwV?wI|BSllt&DchNNr|cnc=j=gZap!E8?1$|2 z?2YWl>^0&a2|r{<^Ht)bK)-8zG-3VhdrIHP=47w3*Bru+*)eQAIy;j6)(6+;d&NIx zudw|m!kp|o_I?xmp7;p1Zvbw<*NczksAE9Cr2H*=yam3My$yax?q{CgE8qa)pGp0c z9Ui}Wd^ksMn9bs-W5KnFe_@}Wvu`-=?d-U0AHLyy9Obh>zvlckrGEv#AwHh1$7LsE zdlR2PI6nJ|ZSR0z6Q7vv#g-EZCuCnz_73TtylR3jl;2y-EbL9Kr7sQ=IQ78^op+H`@Xrv8^~%vu9Pfiqb5*mVK@P_s{$&4 z;w!VO*#A2Ayf*8=_R`RSPzIKT^3a8SYQT*6itI}Eyq-O;1NY7L1NS4>m91Su*YHc0 zfdhEr?K!$UT#kmLJi8p7M+N9QfR|@i5Z}PD*MsL0w+rprvmK!#To&~lm!b10$u2|x zQ3|?t&1D={p54g)H)L(uw<5G9RDzYELAZ(X8?&3TbBK%BS3TLK#BJE#Al#gtm7Sg4 zOgINThy8A$_hOw>?80awlv8;W8Xq{adruK3Fj^l zTtjgW-dSUg-woU?+a27Uvc{C20-lnc3Z9z%32ee%7jcF{b|JCrI(@AG~=AE7}Fp$B;7DH0vm> zvv_I^3Aci`W`73%oZSZAmfa5Cp4|c7k=+U2ncbC53cbQ&VN&Q3dV)R4O(ZY&3cbT* z$|r>hLm#kD=o_X`J{jyz+&t?S`h)$$0B}GU2o4N`z(HX!I5-RehXn3`yJ(h; z=Nx^*;v72#>_$8_44__4r9O58yHPqWjAx&5ghj$wVsVkMXc$8*_TyY*Nc9U1cz$UW z~^FQ4MW4mVP;qYTp}zPHXu+p^%YVL5OEa_bQ<7g}b^h2_EJ!wTRE zVMTDouoAdZSQ%V7tOBkV_gsZ*U6*9>ccYlJnyR>b0JVfD}| zTRp4+?i_XjcL}?KyN2Ds-NNqR?qLsbkFZ)eJZuvV1GgqVl$5wl*cRM2Y!{B8{BUq9 z;zKCgE*wev2yjc{gDKk%+%9Y%j-up9aPzPQxCOa`*s?vieb@oqA?z5AX6sSmKyo{V z1Bk^P!%kuUurpV)KRMGok!ziu8TJJCr@VExXV{DMUSV%=@30TJPuLgSH|z)Q$1zug za*ts_3USbvqRhL>~IcvPB<4lH=GCF748P_4)=ifgtNf& zLc8qAa6`B;JW03-e2Ux?#5aYf!*$_$@Ony~COj1$r}Sp<3F2qi`gC}V{4L<)#E+7? z6?}~N5mJ8!A0>X6)NSA+#D5`mJNPhh&+HhUQP1q^a1D4(xE8#Yv-Zq3=S}y_o(a!_ z&xYr~=fd;g^Wg>Xh43PH9aqpZJDO+w67h@SATemQ(YcqM$xd0qlvBL6kvmGB)U--fTqy#l@xUJc(<@?H3n+^gWL z;WhBJ@Ot=x^6$eJq}~9(B>pkzN&92atKr9>55tc^+m;`LmMlNA{}17F_I(3}M#_!)5zN`C@>3O|GW$^An7bNGbqZ-H-xw=qNM zk^K@rCigb@cK9n3h8`^LS^z_#2rLwe!J zkGQ7ply}66q*K8_;xT1Lad`=N%ih6UGiem`^}xauIRgeN$a z{-C;=$qT){E7ul*X-#I=t(@QL#*V3J{WZV8o7R+cZAsVjcHC?n%UlE5H5JntT}|DY zLt1Ixd5-HM`;Td@edj!BMSQ>0;TYun$8&gft|;qV%2hYLUaf=Dn#q9@)1GM@?_Udl z>%lnQ{i0xBVi{5feaXvXGB{RW@-mwY*43B193_K|^(C(kB!jv2C9kDS z#?0Lnn4QIoYEoZ=-Ax6jQs&%zIyfChw{fPe%vsF$ZJH0y2u&?HPA7-+gwL#h1%^YB31IlFzd%=a}F|0oxK`9?FgHVqd?7AdRvk~z5Sx;a~$1$n|(aAjxJa%S-k=G8}2BGY!x zEl<7^bhdpAB}aqK$YsBGfzDa`g&$$pi-tLHV`sHpGTgU)Lg2|vM* zoeTfOTwDG=ApF4IJ$VZ^(@V<2dqzIplYcpebYHggWZNyEte|IP1%1QMa6jkQKQmkZ zKF-_a^|Ic3Kxfa#vG1&`PvnZu`hQ_YFQXq6zT+5K^1X0nXV@}>41Pej1{3eek%M8m z--6$=x2*a;xV5wJ6WDq@=twz)ePjnRV#mxAA`8DCbf!Ku^53Cs9TFT%PhccH0p2d3 zegJ#`zBi10oW0A1d$9dPMyeCx=LfLup~$2kWG>%}8{e_`(5j%_1hr|rV2Y&|71>4#x;Jz$Hcfq#P4^&qu!WG~Ld zyD=x1)vQ8^b8^|X^YreZd}&omWD_!VXYoBi+1F~6tO`~WJIC({%Ewlx#QAv@@p3-n z$OC$jmZ7ZyTdD%9*kjGesMe%p4d(drv$Y6oGQ!F{yGQ2PJu=Vkk$HB9E1pfce7k$( zr&_TcDlQSQ_&N}{?Ujk|g-3U8@ z^5SlhO?PA4!=x`_``R$e$uN@1T%{}LH3#LlT_eBk8u@M4$Zyw)40Rp$UmG?fKV6rw zPUyn>83oGYx*%;B3Ce`Kz@^)QUCFHn+nfkadDyaWmZ_BP4~v=#@7apf z0g+Q32+EBTgW7`BL6K7(49ciBBR&L_du>X5C@3@Ag!r(?Sq~$9D6DNJ`ST$px!3 znO}8w6!ZS-IH#|M8ypLZIfpZxP1ptIB*VOza1qSqY)Z}|>gfCi6-qplc!C+)%j}T6eeC9Ox zjcn~P!lUpQ8JgVYbU2W_?s39na1lA1JZCm+N$&Rq;ctW*z(3xB6UlRaBFupqy-n)p z$c26Ze}*H;phET_&oE?XQhP$SE3GMH^1(nqnq>io_#o-Cs8<12^9d-c3Yp9+WOA{P z$=X8p1y`FD-sHSlLH-uNtPl#X!{!QwcG+v7%&>nM z;Ha#k&v8wVdlZ8eh2CKALLabCp)c6Cun4$FVbKDTT+Y)t8&DWXdSGD?IH)if99$Rz z4k-);hZcr`!wO9bZL|J`0pI}g`VlNzXhTU`m}67Ytx31R<6zN3zk+MSFIs4o^(*uT z`?JmUzyNz13~Hyw-ED}9r}Z!l=L;CD0} z6KlV;>o<1oOBW}&vP1r*UB9uLzDr;0onHSNyLt!ZU)t4kW5K?$>x%33zqIQLV18+L zEWFb%>FA^CYGD7J-`Lep#+BM#0m83q=%=9vhxXI`8IDHK{t)cIma&7$dO=Km#bHBC! z%Woq4c3k17`-}mL4^4+=W@W1Dq$US3g>q(3An~w!@eu1?oZ{L>Mo6sxP2mN>a z!a(xq=}Qgi!&TXG{q9m60HHHMoxU&mLrwp+ceFPx#9%7*n673P$oXXx>$dOG@2J@?`31E$ zpx->P$8Ezqvrn`CZNnS0y_6E#gC*q3NOb^9iG7P5cyF#3;JfU=+p<+w5;}tww2x?9eb~?tkd?_yYv~fi+AbW z`+Yin+6shzpuTPe!T@jpXVbgQuWy%eOnH1(9f;f04*F7_o=kd5`7`l3HHgouVSH9T znNB=?ecfDV(l(a9Ql?K_qxcMcVx4(!u0+|A`|knj57#(8PoH5G^|(8wP2y9{pQO(? zJ+bC&^^2E2-DdF#r>B~psja0;R$c9PTa{TlB5NNLc#?j}RqL1{o}_tgWr}!`fxI54 zMLdT<-umQo^!t21QJkw08MKeNsN_j3=sOSBY-M6YU4OqJs0y0X)5otv*qE zI$M}C@N%B3&)g?!&u9ztc`B3cNXjSKF+MBg=cJWID@C!-vL91MVhiaLpIGPkbp3j> z--P#x`UG8h*XL#pwZ__ly2rX{J+&43jQzs3YtN_~?H-?AlUPrEy0%N#Z0Q!Cw0@?3 z6G*we?bSNom22=VCa=aS%DVGk-O1ZNYIuT7nt5J6(Gt?mhWw`KIJRr!<5zyi62{TD zRB_Zq%Btw2EG=WtQu>*Rl#h<3lSl=6o5hGnQ8Jp|XA&hNNspq>nM`^F>5)7^pSC`o zjyQo_CEEji(G*gyiB(De zT6Z>!^=LD4{gGu`vo@!!AChb9+7{#%MP|JP=`9I;W7}F6TrFD_T%EWx^4`_KHHkYT z2VN6go47Nw+_k}ViMQhDzMylWRVZ7PI%ltEU)Y(tZI9_!)H{G3D6voNOuO*g(e}Ig zF?Z(3R!G`c0#_lnZ(a#p5xF_qYT^b+%eMlTB=#%nD}a4?whbul1Nxn!2ASWsZjkvU z>jp^QmjV4^bpvGV%YiEp`?afWV$JoNT(M~) zIY%Y)*05^O`Z*!iyEI~rk2Ts_={TiV^tf2VwQ1`@J#sXwAWQ=tyZjEiT968GNpK17 zpn_EI*hYHOPP&t}b@b*;T|u=qy$Pd0H9EZsV?eb&y$R#Ed+Y7evEDAt*_NUPjbPg{ zvAq?WEnja--1HXOS(?|xnKST|6I zv2>sgWA#AUwrtf(Z!PlMk=8PAP14(wPS$uWsZD*!tK+Z+trk)1L2H+_bVX`w1H#In zHhT>StAc7d8dCrKQk}K1QPcu82CZ>wieRF|O$f5dzNDIgO{t@ONoCYU^^EEJde&R} zM86`}H)1bhTa#ao?HSP#(bm<2&^x02y}hB#G4-GY(rPJXl!<4iFG&CWeLT`DD2j2d zelq3j_Sk;w*>6ER*69FYS80Rq^Rp z#rv*`_gWR-d=+oM9b4^rs$!j}iuIt18qkRn-@S9pR-oTj>rUG7#wXT2K0QaKDq5Ru zylZUZU1Pg;-0IGK*WRx)NORt?|7Q=EdcM>PI#T-MuuHuDYT`74cHzlY zlgH%P)g_kKUK7Yj}^| zkzZr>OvJyAUsl&VMQ5T}f>Z z?n1mPCA(lduq!3I5q7|`KueC@$?br3v6dWrklPX5iF58j7=_J(^V+>Y?HcwZy*FW3 zaB1>;6P7}Us!hT^Q;-P-D!@whB$#TR;vsLSeqbNUySk%VhSi%wD z5uD*z$}Ewc&x$kt8cR+jcUojJr-RycpT-fh zNvmUDf#YTqP6baVcLwpP=-TzSIg@h?0ktwelP#yBeU}TJ4XTGfi}X39)yA*Lap#a) z5q-S&;^&f^jaFW+cpgU&2DKnRk1c1Qr^u8^N0iH-O4mZl=tV8_3~*w@x|47-cssefDE%{d2l3sM_5<%EzK7D=!Mlj> zC3Pow5AnUE?#Ajxu6`e>e&D^t_s8+=e*X71(zkKG2Z-;$X61p1cW|Z$3HM;1g02!f zlm|&aOzHvfA>v0Uy9d-t=h0{h^C(*$z3T^BnyK@r&34zQ{S=B)kH?LGCS%dJPM;H!1lm zsn@}`h~MF?eL?La-(mYJSk%4F5%047b?of)bb6268(7!9$@cdN?||=-`+)czP$v5U zslHgoIfKMLj&pxREWX8=J|-6b%9%bPya#?v{3-i?h*g>%M4wUi9+qgIQt~&S<~oA3w!< z>)VK*a;EPIUxMEe|3K<1@O$DP+5cPY(X`>2L)lkYrD^x|6I;H;`b_IYy|j9RbIAR| zw(r58h_j$gS{8nxB!nN>9|Y2`RvG4SWC82GIayI~hFug&ICn7?gW`{z zsU-Zw8B4G>{3$EtY#H{8CB$XyUxZyErv*!iE3jlN0*lzUf>45OVL4kXu`NViN2-85 zVF~*-V0#IkH4R8NA{I;8w=w(n!Zxr`Oe<4uOsW!F!8qgRAIm~hj%@%^29}X)M%*AY zCo}|`5w~FfCiv#)x6_ichIr_-;D}c2*$iw#+?s8T!NvhT&t8qNSHd#}#G41Jr8cD7 z5n6(6iQBVpPkgjm61OMSgLFG`_-w&I@cY7Asv|kE1?T8QXai~i)rqoJ*w%F-UB&(# zLN%#&U}xeQj_L?j5qF`i9oRnf$hwefAG)%w6IessjZ|l_D{*&H)nGT`9_$UzCf|iL zfpm9rJ%fy>C;wQ5jan7w=tWr-)@n7Jqc@=&*o#~r;%-@-C)ks{ z7A5q?CX#bw5!s!%AA5Dj=V(#N`xE-$dDI^qNLU0MKs<ANB_7Us27&rD4X11X_JEZfIg+D>fFp=Uu}8OT6x#=3 zi8hk*(S)J+7!Bo!G316~aW;(YW62G}?raqMk0bDHbV^52GM0FJP@goO^N$D<$cZC3 z-vq*FEZ8Q1ixI|v6Nx7gj{(PU^kj}5kG0>p&^4PvejMpZ#EY|KJUE`CrxGTD6FF`w zWfQP4n@V~*VG=lvcm~IJ$!2hLS8x*X47NV0W_&>E$?I7c6h|j9Q*8OMpvojukj|X>j?NUXt93St%*J1hNL$ltOM$$wK4I! zSm3S8aWl!Si%ni*j@*twL3{6KB{4E5IFycP6zhsD0qhlx>6c-p-_VC2SAwLcANtRb{)8 z+n%&?yxmCch#h2;YzI&o%pSx$U@^G^=h&05Gq?xwUZi#b_axpsS_baTd3Gbc7rA{n zcK5I^`OewCl}LmM^JVkwvf&Ek0Uw5Ay`Cemw6PqL$HfHiu5sr!@#47k0o_DcntBZpwwy>#~z8@ zqME_u*m5}OBgh>`>IiHfXK|+E2}j|zbEl=bO$ATxswEk2l1?6EUan4!TCZ5RF zQz$tJoW*gc1SMyuu-7as9gpQdPGzrS!4BEUpqk24Deaj3i9JujO7awr`cu&E;7_DZ zAgu@8X~d#(QhnK4gRR)(bV^SKPv(55v;9QUdc(~QYF1|lb*i(2deYhK(H=}*a;KB4 zu3n9~YKEjEgKsHK5tZJn>k^gWD^n4bGv_N) z*??o~OI9|eWHVT~auE6Y=FIGhz#`7KMU>JgQ!$-OQ)VLNP>zyhD!Cjb$y7Gw4BH?j zP~Ne1OsjF*mRVUbSj?G}tcc2Lw*OV8qHJYe(v+<^HkYX^6(t}_JCv_1jr7F1-p+(= zLFF?_R<=XNu}egyG)azBJ%0G&Y`P3lmjA4*n^B`8Nx z!ZM505#SLVHH)&tk(q9pwU&Z$f#NmG=vC|@}m>4~zH zlL@oHS?sT50+XCdFXkhF4? zDWI~Ni;>hS^|*+VOGxV_bTR2mN$W{;Nla^ra9PwMTo&~TmvQC`q69@u(iHt9l%Pxo zm8M)tJQqA7;;TtbLLSnTvtJt}DAz`5%C)~rR<2;{b!@o;xyE&* zuSeRf#N>L?H;`89aRccaN$WkPCB;oq3vv_Zyawrp{$n>2l&suD?iNyufl6L(jk=Rt z+5aYFAGc7hNrLhb<)09gqbMo)l7h`1!qo=Vt1Amz~8uN3LX&skZNh?KE^5ps+Ya!OOiWaWg>pt2Sv zE5Bq(vQil(E0r8uicCZ~O9SFkq#Mdn8nW-`Oj$}fvJC9ukZd&Ktc?j}NIV)xR9>P4 zr4nosWhZgcOs`WWmHxjWi857+EAiSCYPxwU+IFBqXQC;j%@ErPH9S4(#lV& z!RjzF>&}05Laxz?^D05<6s09KU=2s~q)a(VPtv{P{I@szcSpvdXJH?}6?N>=(2i^^B}6N|mruHQMR%&VOeAxD@WAVa8<(c;3~vPYLetAt8>&!NIK-`Yebofa+IN@)sL;gzAGTt zP>!-Dd#!{7L_)5vWk+zw-$+nuvR#pMbU})?_uu3wgGeh`*_*QuME0Rf zWgqt1HA+*IsVGO;mojB4`;u0UvNxDyDoL8McNmx{Q&F1IB~zNR7e^dKZZBjX2a!IQ zurHF1eWL_L*-Cv0ijv5~IQBrK8EPpHN18GaRI+k7`|gj7Bgs_scs-I_lA|0( zj-pIOY04o;I=XU3~k94r23woLFp;rY~nMCPsPhosr*?%UBOxCHF{=ev*lF$ zXZ2w{hwb=!6K0cE8*>i(oQ3!9*=#+Ra5|_q^;}Z@v-3Ff8TkCFM>>xqW|QvCG3Qfy zCa4DNe9F!s-G@CcphRC`b$1uA$JwOMC%!PKUA!=;3%!uib16BO+=c9^5Ag+*Raa|| z+K)5pdC-Sce{d1v-lPVAeTZ}G)ZUb6H#ZQ}QdN6DQ4a~N|3s};wV)HVUDe`G)KXSU zby3?{?bbytYpaPxEpxTE6SdFPs!-HQSBq#-TU{*!MJ;x<6%@7G)p}6WR#;m?QA^^s zgo&VjHEl>O2DT+`O==R@hPV}}$zW^ZmZYYDt%zHYS{!Ui+?>=@umy25Qq#cZ#7#*} z2b&Q$AvFVRN~|UH3{d-I?K8zCkaK9gD!Q(UU!xM2LRzCWw&;4C+7*h+AaBy{Q(P8_ zo7SI7Udl+95VYe@*8QdAiji_9EB``PUEP%D=hvyKxSGcCY3hTZjkZryUl7;Y@d-AJ z&r~0WMqGo>u>rw#dwhhI6lW> z()u6x9Q8TzIy0V~R*uR3v533S4zxMP`lT)3gch8BamqK*l;FLzjQ7G?1zfxSDUD*S zYDCTQUaVCO3EqXZssX{fuvTfo>0MZ>v?KRkd=BLV@5NeGM({3tCZz=L!lzL}@Lqfx z#RTugI#d*&hF>1@j`V)=E|~ullAozqM!9dvH&!6l2DHEtzQ6guBd=%PZ|d*ABd=}V zZ_2w%Z^x(VJ8BKKj(6wV@qMK?AlffW^xpT^ZyMOK;;S_!L_x4c!F5e8bYQoub1;HllTZ!kN-GjPat!+m$b5nkC9Ti)}*qE zkCB4hMfzI8r%@8~DH5M+NMA+xEXsdAMIv++X;;PhEXsa9LsIf*Bp^2-JyB+JYfRrk z&h=kzLNZjlD$b3R-4yM5K9AC>&yiipX_aDq9_3nJATg8iDogt^S}%PWrFo)k))h3r ziW0l8q9pIDC{I&nb}sTP?TyYt%BL-XGQY2o*_}g)7FSHc9_1uBT4I7Scqev9)`n7J3bcTh*^lE(&CIHtLXzv7=??;+Yf5@Zx3WYSQ>jkdpcI7i?e`!jOlu) z^kfdODCnHPSwPR&1L~z|&!{&IHWK9YziSWb&zX9hG#-@4{xx|XXpOH#sR=>tqJ6w0 zr@B!4^g?ir9P|m89MvVoPc$SB;%$3T6GW7DGT)sR^W~Ngfob{B4@zl(UpdV93aJE+w zx>IK=f-}yFun2R;is1Ya>mX`gMHoQss|?O>kTy9Y2j@VQp%L|=GAIeH3@sTmD?=M< z5!OW19wb-Pm#?`>d!}!Qzao51|6-d`8ko_Kd`DUvsz9HCtd2gwmNkc5pv})At&Fcg z%eDn6<74K5q>Ygp8C(&gk!?r$Y%yb!dF8Xkj9!k z?B$GV_k#}-D!>PbA0n<`+;W8c3%LqfgX84G%>wi@KARcMWMr zxI4i+8Rf1c-x$1>*s<_dTI6+>?BYPR#Qeg=g?XL zH)ZTQm9+Y*X0$@v;OV5AgQpSOGSv%dPkSD*HoK>@RjpO?sH195Yd(|oS%emhLC$UV zByPzFWL`V)mW*Z2g49{IWK`Rm^uENcqWjrDHX(u%Q7Yic!= zt!du}fCmxUfCmz9NUAL()`s8)q&H+N+lcf`LOXC{Vr}@_G3IRo+WvQD4BV8oy}-_( znp!|} z#7fSp8PA4AbmURiSi^{AzoC4zhQ7p}BuZ@=+orNjR^?bXg;+^5tA-J}z{D1(Tp4*6 zdZsa;dInJ@sU}1}GZ|)LtM)$f*Z$-alXVR154V-!7J{~}g`h^F5MHLu78nt}1iz#& zKsHbNFEFAPF<#t5YbpxPNsGcuam4w6)`|3<)>#yuq74=WEsl$V_Ql1FO;3P#Gg=kX zzg-S$&0HL`<1P+bZ5M}2nfDb3=Yz%J30hk*qu5=bv(A#BhPNcB;VlU_(K1ScEu;;dcN2ICV_Zo%mv&IfxYhzxgI^k2P|F=_4h7X!mohdT1FE$y zWrR8wR1;kq)IparP8|m+OFP=*zqKQ3PraxN zN@Oa7vzf}^2vr%Jxl{({N|ix*Mr9oDD#Jj=yDnT=*Esi?0m|C-Lhr&6O6!!|bfF&A zP`8!M)KIUq@=_jCP0i~|dJ#fr>f9m`l_^^TMP=X0ctj=jO0Yz&Ym~H!>OTe%{EoZd zbRSHr4LFE+2&vZKVB(>qTE%wPnwIA1X}fDhOH=D<>+`$a>S%3!vT0W>vGr+P<@cOz zea^&2fwnkjVxvLZn$~k;KwF$veq%w~oz{rsK-*okngpFIXaz9=oCsDhQt^gpwG&B| z5tq}77b8_lTt>^EM5=_iH1-2pyi6f)+t;FIaZp1loFF-0$Wb zoA>OhB|SjwRC(r$@+OiTD@m~I1Dw0+Ywc{r)iC-~7nEnYy754cRg%?%Fo<&~$-;J( zXY8CtbjEG}A}YK)2uPQ3dvPTx3ciC%;&c5u; zMWtEx_@dG*zv`_VOL>;#igK(8Jmc1c#XzN6tw>D*m1?ylH5pW@)q>O%P^ngPQj3F1 zwVIKd3M$oVN@^OYRI3T8>7Y_A$86qW$ApkB-lBOnjze zNRQ?T`y5BcCp(gISJ?4w$(1JXJbha})$yPsjH~WU1RYJR5!R!g@xAu|ty^L@uChQ{ zmgdtR7T?OS_@0LGk0W{GZ7CfA4v%kU1a+egdEbd1|K5#ju(-BWcXGa;q1>MQ3foOkcL4QwlpW$8Q~tu!ooNZaO1`ThO#{Hyj^kn8zZ z?Xw`)Y>iM>n4Xr;&u3TrbbUVhwcB&svnbi+`z563mg(BRWLCHa!r zgVmQYC+V_s<|2A$*9hoJsu25X+gcZTgf8U&c%7MdeaPkOd3*WC@7?=V2U7b4ylY!c zT}{ZpLI<)S@A{AIk$;a?G#Y<-Jzj)|bYv+J0%?b!TamjsXB|Um29Bpp2GflB-B_?WaWm$L z<4Cn2=IdD;?R>|1fB!i9bIryUaSqrY?9cpaAn_o2C>feOz;8NQe@4W4+z9q>8GEh) z)U`C{lV!DGhKWrYTLv&!s{z|mVsA10*ZJ#U`VnW2_RfQOtHa56W*#{d987F)HJEqr zT6rA^SgWyZNbI$T#!+erID~D^pPf59lXC9hsOdN;v$D-Qe<)%P*QIgKKe~TDZ}Hd# zIsby}@0EEz-@Wri=YYk;d8sAtV?A)bIInZMz4lH`rF-)}tlbdV@0gQo@Y* zY?k0yE%|NFGpKWNOZlqniItPCAh<4_D~+X<>SVl&Q0Pp}>-olwru2~=uf&F>5<&9LrQfyz3RT2zBIpwf&Q zP}zu5jxM0~LrOoog4*RM73l`brj(O(2ep+!8b>Vl;e7?tzP}#vU0Xxb%s0*EoN1Qu zChQ+vQP9;H%SgH2Q3IZ`@4az6(zS!qxHT?^_N3mQcWED*uY}}^dfuOR?ETv68*_eJN4oZ6(uq5J_1<%8S?PMb*3|O6 zXZKCa%YEIJx4(4HfAk*y=rbA+>xcEpHMi_tt!LJyfuQxTCaWf{iS^RDH<-Nj)jFx< z+5XVFYM*KSwhj*it@qaL;h^ooIzIxmo!Ayeg0>&q$SBa(WZM}H+RAKGY1QqtcCYL8 z+A3{{<3L-hEp$9+E4JlM04IXB=!u}M-j==?Xm4N-FbTAmuxFSI+I!ezOabjx>`4{} zm4Dg8Oa<+Q?0Kev_EGjo(?Mlk)~g<%GEVDNPtbnPdesZG_wyb129;OZ6V|T1T|`SP zj_uR>ya@Hic56Lwbz0lAHJ~4;Y%N2Qvl^NL_vwd@z-_A&mPbRddPLXo)8|iAAE|ah zR4b`=LDUyeErX~ppdNn9g6qVzzJTizTtUg}SdZWeO6uR&C$~DX<+P5Het;WtepgV^ z15ho?TA==a$+u5ki)l3)Y1O2eoO@Z)YCtyO{Of_<`6jVVY)amBlw4aWUq{JRmC{;@ z>R>jEdKXbUge?iKouu!d+LyF;(lVsASlEjH(7Ugg^C|xpwQbmzSk&f04?l4;v^lPn zB&s3S!%tL0tXH4DeXgFQH=o{puA{V5e3v_M{;i{)NYs~5-#*cAVeLvtetz4c5lDW1 zyAtot`CTaVW8MQ5$vtkQWi=tPb)-T5sjs%Y*K7rIx z;PJ#Kl1ghN9feLuO^kY;qtSV)iP4{Ldenm+1KP?@iS7Ip&OeK^RyyiLk3$!#pP-u2 zL{&Q}xKDD7Ip%c}&?+n5;&>rQ?*r%Myznl`aq@pV*olQude5ayy zs_V(8U*Ea>!)#E$K374SjaK%&i1t|LlX6`oy#p_Z{nrJtN4tRkIui};nf!-Z+cTry zR*=un}jyo^xIqHQA(G>I zx#H?b*P&O}e&sfD*P~b0H&9*s4cQ%}ZUS8qDPJ8)TeG`3=PlqZobxV%9)7NlbaxzY z?&e=^MMrseMD5e=CENzOdXj#8w}bZ*-%l#}_T3&W4_qDT4$h?If#_(aH{W8QI?IRR z*!B?ra(A>v5VfOog`|6R11QPWH)&+61~P(j%b0f6tIgDg@N?tEO*G_te^CzD_FQQSUtc*ha^_8&SV~X$kO6@qizJRW&lzaiTM6C4)oP%y&|G(T9u!MA3(AKaF z@4a8pc{@KX56(qh`z2yIw)>m>J zrIwVr%2G?xuBp@nY{EHPQ)Y>?Z~X$B;hWbXYYI9SZ%d5tA;Gnl+7h=X)dF*IKG3ZWn3@ z?ZJGlCD&c5p`f zElQayF3s&PH~`rUq8+_3?IIJc<%M*OvB0P9q7tS`U?)ki*H24ft+1`!9f`aGaJR3U4u!6Hahwa z>NPkN-#tAE#}K>v(ooJfmfTRh{DyJXapZ>K#W#X;jVC_>%)JJ&z6kQa36$wOC=Z;- z`A6Z!H;VHuM%gI5`9^cTwEB`BgnA9S;!?i)(qz)ErCemONvAfC#ZU609i znWhEh6w`tdifKXF#I&GPVjBND5g$Jp)pSZ+Nhx2a$#Pe5ni1q!X@#a4>^U7DK$+GO zT*+k8`W!C7J~QwKbhRc|ZmRV@?9F~l1=-kAL3zkh9IM}8@?~h%rT#j$^0LIm z(mJ-Xvz(F1oBjwdlaVEMR-c#Ea4$H&c$S8uD?>Bk;%mpFUuKO;$reL8QCGf@~_|WviginE|z%Nycn5WEazqQ*H)2# zoy0%Y=Vf&nnX;Jq^D?> zCL>GitS&FRDl#(HR=EVWl=CtfS>j^X@PCPsC5|R9lZCl@ZO+AHXEL%Y;6{m&-9Rk+ zx(1Y=-4r=mzLLs`aSr*RHM0#bjr-jO>AVFfuvV!*C>-nJca&UiPnJWY0(T zl=CvVSS>rN&&%XviI=&K?Sk>Ld2=yYSkA~~VKOpTVUd4n@h=y9i?r-$3^;#A))Jm1 zdwPev$a$HbaeBbL9@*Ku#IC{eCMZ`+j7%SZH{nQfG}&2N)AnsR(_i_=k0^Cb+t!hV z{g#W#ziJtoEKKH=xLD$4X)TueEG+S|#Kl~HMMma|DhtBMCX2b-CF5SXkm;axuL%zL|@Ex!P?O^ec1q6}&uPU!y>|o?Oh;S=z$IWMuec)?s8t zp*|yXjh6W_GEVh7yv#LRaz>W8m@F(YvIfMpT&%(07?~`rB(BYp*1au*AvKyW7i*t2 zh4IbJ$nckeA>~}mm0ILz`HHu{&&cFriI@F7MkW`_d09Ks^I~Ljv7DE=I!n&W5*Mq> z!sKPLFjr@hk;%ne{dU2*m@H35Hgq103|_|hdcdB<#Kn5>AH4{PkyXQv=FQ0Jv#`X@ zWNGzTn7m9D);+Q?xtP4H?%FMNxtJ`hH#|v3CJPf~d~wYdPD{(P-nOsc%m9GJlSXkm;t_>p#n*!&Omn|LYaOy;&UM=T!d>W*`r zt{PM|WLj>j7cE42coC?ri+a9df|^?AOCi^UN)w26FMW2aR^Y48o+P^Q3d|Z2X?c((+(%xNr zdHs*Hch`=78q#4c-6xQnjy!h)>G6am81KhN)ZSeyaxr=bM@x4t_m^Un##@-DtNnn! zzIyxy?s0UyPc8lR{~gWtQG^o4F0G*S3@AbVr)FP|fl?%bS^^9wS4RKs)6&DB9Eq1t zQO|=4dPm=w9to_BO{yU{gxD|J`c>P(!~^4-*R!D!k`>>c9uJL?h-fFJ9e5KY4O&ZS z1;rP)N%6I9a?Ow_XeFh!RdZw#+WBgw-h!5)^^+D^Es)wHt`wPMr1Le$1hyDCvjw=RTEU{_-8r#gXJs#X)Um8vmaoxT>X4Qo^G zZGP6P{!gt1q1Mk{g)3TULFmd#@Ttsg_iX$2$+=oW zYWK}}@6E_JiC5S-UZGd3g|T<(H78qJZ5;m{*Ev7S>;=EhbcMd3+7&{QMW#>EYo3=S zV*Vs+?P9GX`BU{t`fRlf_6oHRPIlzB8n4YSg4NoQ`yDiUjQn{n*n7|ICV%fbefxjU za<}e#|6|WHzfNmrZ7ubU&+mEWHM91q)~%nZX68>)%j#s|`bVFqPtv-Yo@#+>bDXKY z!esmYdsg7{d+!VKJo7hR+nQQX1Ll6?^J+&6cAdZ9j#5jX-*x6svaX-Q+#U{pzkcSn zVOn}Q_B#V`^s_&Ao=`?f2|;_dQsR6(v?Ps+?&(~>@!9>|)A8B;i?V0KTj8tl9QZ8w zI`K24z6#Hiel9#s?yK+u>F2{!LM%|VlM;bzLd2=|1)P<9XD-f(|-fZR=N`2zeR zd>-y2e-C&+@!iDtgd5rNdANc2^Kd=!=ixfy&%;H;;^%RVs|$%QAbb`sru-uCYGT*R z`Yc>R`eIhnI-m5p#Gi%BDY*o^hWH%HJ`0zTz8t)k_{wk<@!4$oEL=hAGVn^`ONlRI zm9MiYKa22bIFtC(xL((%aW$_`S%qviC9?>wCVwpPajg6`8=Ot)(Ug4(ei}ZBYm~YA z+0mq3NB$GmA9Ee|lL*JhmC`$SUTyK9rVCfVt%t9Ar?x~97;yPraQ0`ZBgu68)( zu4pfQ57OoAIkRxUAf;??mmj^&g}!b;+*U99~9Ta`-oNM4x-dG=UkD_F9U4PmXBC5Z+q}V zV$p9F`1OJhSru@bh##^};QE9QSrKp>O8vURHeo%=K4c}pEy=G-?n72FTsPu};e(LA zw6G~#H;$_neh~c9f~y7kHHOVu`)}*GqTvUu9GJequsQKea+|Q);aZ$w4dM@21#u1V zec}(`1@FTnmSp9`)xp)tx%%V#%>P#-zZ9!2t_JUzL5Zt7$_!lHQSH(D=x(NgvIg<} z@E+?yuEHM6#PuHiD#og?j>Rc=1xUZPu_Cc+Lb|S`-_ckWTrO&n-itb>_o7bfy{L_P z55D(aco%**k$5OUMmdBM+1*5NBBk(AO4Ps&i~RB3sNH)Prl*{9q) z_kZsxd;j)6`g_nk`VQK9*QmXBB6bG$ zZFF|$Q>)3n9qj{eqm4Va+75lbQ?wqu9omw1uGSe=b@MK9=J)OJ7V+E6q;}z2d#MWk;rBknBuTg-xUf>4|bufS?kpOQQRIu$e6g>i13 z)gZ*2XC3Fs8)1nl#S)ZKlG$Y%Qqm~SgO|s-`--G7_L_#+d5VeI;e@m^{(6ai3$}3w zqH=6p-$1oZm199GkG>9H5$pd@jy>(GfA~6lg;nl7O8!bH!@ogWn>$#QMQ@5SY<2oQ z{GE{bT9jeC`yyKK+zmw^hA*)U{)ziPA@y3t2X=Xot zlhWT~^L#7%*py%u)sscv6@6V^Bds@130CK4p!)5IPo9G6&r^(jy*PRxJxP2Ysbc(& zo}^R{q$i^nQ*rb|dNA73i?Ob&VQXVA#>%ZV+_T*t!XxT#%5&CmcOG|du_y4Px{LBh zqg`A}xSmUoa-V)yjhRXKIaFV)#>`x(vtC2abff5PrpJ~u9gUdFxGm0Y=+C8pS|esM zZl&}Ja*d+*ntQF>O6eNrDQ;y>MLpOVmPX8N+(ha1%zSuy-_MwfaQ>wsvl{NLas%P| zIMd-tem9WTcdlXdrqk1IC24o*Z;0QZvsKGuYB^;MnLRs$k`<)&BfNlE|HGo_LFg%t zr;&DctcV#f{R_`we(8ef$5_OS)rE0(%o!}b1TSKaO>bm99-R}@(=a=Q@hsxAqd#N= z<^Y#*k3N$PqIYEj<~AEdf6(KJ4d#z1dN|jQKF{^>_}!9{=>+G1 zrxDMf#Fg~!My4&IKK{&e$WJDf7cCX_qXi=mAM80?n}t91oM_+3!%KS$@|)scy+!oI zo*Qi-d3b2grBpv{J-la=)=uKS3=<*_9S_xlQZL$0>S2o*OL`DN%kMzq!IWsP7)7j2 zq8@gPQRMrPN}>IUwMnGdKt^$Gqv++QWkT!7X!66bzKo7mmNC&vkz!F9L#eiwF<3~3 zlh$IPXL>KFRtk}|zUo>j0=9wfk$Nh(wt|4IpbKTSgc|g))|9xDM{U%`1A49aTy0zr zcWr?k2yLT==Kc~|0oxNi&)l=&)h=A2;(8XX8r`r_xKn_dn>#)>gR1=|=(nB_u11k0 zH8moxBoWsoiO5j9&<9WvX-Gu2ArVD~e`NiPsY z?%I`J;d)3!@M-cpkUaY`a?cCMuRjsL3UW^qvB95^k$+aXn4mA@?>~ z!E2<|4z$O;4pk$lmplMsub14179g#c+z*<6liY(K_Ik;^QQx>1o#Ra~|C?NUh%5Dy zhY5Mmhln2m$>$|cL~Y~=?!OoG{s<+{piex99`Rh%CY~XF7R}>HF#j*O`V_e*(F-0W zt&WhFs28XSJqEo7{9ix07TjJxxtjDfVEV_2SA*N@v$yTzkm3yv2Ur;Bx0sNky{2YDaF7$}IqBik!;ycklZUgh*z}4Hy-G)|hBWbmR z{6vi)KUq#FfSy5oI-14JVEdb6IzRCwr{$p_ISp;&77+d|T=P_@g2a7{3zDGO#T z6ZM6{#676tujm37fbTDe>B3|&s9kOIFi?FVdr_at^@9oSVXfA2IM*AnANAo-(R_pC zILZ%3A5a@P62#wt9idMocRad<)V-fiBJC+$M{@N9a>s|FKA$xl7OKxw1dW2_}xu>_gf$zrEeaN{B`0k|lB-U!WC)9n#8)5OE2AxW9 z9zcy@Dxpy_1FX(ICzLpEupRow6v9GK`3%Zu5*kB2Z%@45IGM{mQ_u(0N!$&-apHdL z+oCnN^ZJ%(7@lgkH7WOpZ=B2{=icqJNxMJ1XX9-SEhcW93`AEbPV~$xP6nV8%mK~M zA*YvKane6(9sSWfwgB^Q!8JYhit(Bo0v$#ufes}e6SWb~9dtHmSSU&KklPr2!V?I` zqJOxP{sdCa43#9~$hkZJaMJ1sC5akAN#abNR10!zv;g)LAUM}Inp`coy)8Ioh%$pAx-p)jIMCUBTse zyn^e&@nClRUK4##^U)O4Mx3cFPxM=@MuYG)&`Pus{Z*ThDiPf$RpdAoBPk(WN*OyX zp&fwq(FrO*?f_nz4b-bU{M-Ta!(k9^YzY#kJ-vpHY zcc>o4??d(Ubsxkg32Yyo+7B>IB18bKw9{AK8G z&@jG)ei_r1lsFc!}^8^egVr)4eizl~4u!9kF{Q>W82n;#o1-nZQ+O8Goeg z4+QmyKN0K4@CVTT@45e7a(_T0c%8J`K^2JqO=wf%D)9STq+F}e6g2-9@dM}?Z-Kra zqU8RlZ`@DG1EgOhcHKf#Q2QfL_ezv1gP)3e$Wz>(`N}lId*oTlo+hYGc#e;22A&4( z|C0ONE!Y!=enndCpc#n&aj2_Jq)PW|qo2&Rr1gG!g4q4snuG7}2zdB<6 zYBYpfNV`W|HOT$eNUO=Mh`vv*CaMN=Yh7MWi7SxQLzWY6i>SQ?nEV{Bx{jy?I>J?4 zTNyPI{nc7T@3AY|O&tpGA5$p*F6IoCbC6qPsKJqJL~dZYzQ-CATGZb)}~-ZpPKE$!&!`usLb< zg4(DH)Pl&}moeM1z}*^MmEgIKg9!LwbH$y`wj@6=Y8?a7JhlXp52ak}p4**q99IXT zD`YdK?yco&v&ji(?vfr)NnD&KP0C&L#t^%!p8IBuCUzcL-AKIRJaj{}AyJ3AQ6uVK ztl$iEV_G6gd~#p_WPd5tUH#nauMFyLf9?V3zJTrmIEa+{1-d)nz$ks3X|A9)l^N=G zO{g_Fzgk@-wI#o{Hmj&F`K?-AQ)*B?sXo_?`c+eMrnxz_Do0XptB!Tt0;?=xLDfTte9>)sUy^#0*mLi{Af+VHD&>iHuT$~{lIAJ$PZJ(PCVoNb-E_DR?t*Hgx|__M zr0+s%+(Y_NKfzUmzasZgl%o%lyFE(W`=O6SDXe6DkkVg7$)mmVR-UP!Z5lq~ z$*+Pg+`;%WWd6HQW&dYU-hUS5{%7EVzfkfjvFo;6!}SMZefYirU3^B#YGhLy^!f9A zH}_Ni8}uWPkLSdFOzC^jPl#Q$^$9pU*3PA{d;hH63!##l>! z&-we7p_Hp-^m4ChWekk8zzEY~85jvI1E)fS8~LrgpzO~JO82~=T+a)aBj1~HPqRcs zs^4V`s4HZzV5GGORmg5-u)f(>Fb+8<4V-Z`C87;i&AK-BQbJy6!__88=}SqkBGiuv zRy#;F*Icn%KeQs<8fktR>HKg$w0UsNOY@*VRrBDg7S3Q}MCqm1it*DtaAFP8UR$41 zza1s*qs%`al%SkHgK$1{WlWzB#@6dTx2LS=BtM8*@Q42zufd1W}8ar9l5d?rj#@Cbdx4@36*;|Ixp&9Z29j?t%Y=E};KY zNf!puf@`-6!SKzv)|4RsZyNf57EY&p0NhR+mh!GYbO78;S=f)ehCl~XdUV7wM@PKk z>h&YhHbff@f;gi=5Lq+`?gHN+9LqBs1kaRp2BJ4qX;T&Y!PCVoN5jXf!Wi()Qqr!8 zUjlEh3hq%^6-L3&s{))qxKDLaaLsyA@Fd!zAQCDHOF%zGJm0l?hw{IAWU?bgP!d-L zC2?hld&W>Y9H~+nhDKy^0Jz1~CtCkzGH>B({)YTYQ4mdN^An5Aj`(9S=w^Qq(Lu!S z5^xY&QDxvX9D{T=2-+|h{N(qC0n)F_CD z8U^j7je>ZnQP>}x*eLA5bDW`JuhQU}k&58@l!~C$vm%IsD!4WsG_pC*olDpfjZNIt zIJjP?ad5p(K$genv z`HI7KV7_9W<9UhYVGFc6F;f|-Ip})ZajhiG2TPTN?Lk;2!TpX)f|ldbAlfVqqR-MG z)+`O45K$WDf-hYaxjA%4?k)}D&zc%{!pywJoaJ}kU#~uSlAcM<3dpG2T}oU@rUkY= z?djMOXSJif9c`{y7roUo{_F#_)T1j4U5Q^qZB8IPkCaqzqe!=cmB9)WM zZKSShmFGxZ=h}tP3=022+PiXBgx3siA#W7bHHCxtwepcF_=w*vSE+=XxF3tWr3u`` znKn601*6zmGks0V8To#xiDU&~cj2_}qx}a6%sAet4v| z{zyU!9YH*bRDh0*ePk5r4&)MKvpvui9K~RS;^6F+sb{!S5`IP6^K*+y#d);AEE@go zaY|gd;mqU{(8r@jTpC^`E)7po@&wrCWzzSO_Do!6|LC#I{RL+L%Yw6hW#NIS>plR= zxE}=d0wtaq`~bMYc{o>Olp*zsu&cNpry;Vhi2TFc^AMWx4V2tO$*|wuHFo8dyeP3V?)Dm4_95MBZs*KRL~IGh*EXx zpF^Fs^Ryk2#_f^1*TQY2Zb60?@kBYPyFxU8z74wjEi_wmpRKd^YdhYCI;ZN24A*@8iS!={e}KA%UYT(T z^pdE17lxI{>%wp;oXOeX%Sf+6W+~^I5~}0uw$v5W^5!bAL}9oL9$7_+d{jSuElnbe z^1zubP&JZr@DaNR2lbWmP|DNo`z6HeeHf(gGa^J#?T+VsBiAb!GEE2w$A zk9>6p4yEknP-is@g7cgO;VPuHnu@FU8$#7%K444~L9>~|3&9K*FftlYauIUdHEhlt zI&XLpRH^T|B4xN3hFx@NF74?Quw1v*b{36l^!#4+zR#*HxytN-RAd~lo?#mqkEOP|(2=G)0?&TB0 zQT(5p#uBi8U+(_|9^MP8{`d)@4^$m<2<4xEB-}-5Pr~j{=Tx;VOhCJF-yfMt_O@!(L{wdE>2T>y)%GF88b?0x@ia!M}%>s|OkNHffCr8a7Oh$Lw zhr86L_JQuo|9nfB57id)Enx?!Gs&OvBsCm0_s~)ZM2(=S_z}hap2g=gDeSV=4Qb{BWq2fzQECW1|kcHPm_L zuL;{iw*|v}!S79hPUXHYNKK8J@@%N{z+VwIhq_1CSA;FlZKv@cYR9H0^FLpbnhW(r ztS<@kpxT_iBuq1 zL+*@@!IX@QD0n30BjB7`-n7EGo1jQ}6k%lKspU|S>}bm69b#&C`Y(-KwhZ~wDsq$7 z(0&oy%6HxAT68;>>)IJb=yGCrA8bQj4DZgReJN=iIcqIt;(Ix1qsVcyRU~Qw3CzJe&j>LJ%U!7bb?)RPfJ(n>RNawn+rEHBEm`jpFSvb|oFd6})Uu9Y%p$*kg9 zU5jPT+F41R)wN#cETT=Q{koRSterC3sb8D3YUV7f<+Nm73un&y>M1Oloinp}YKMJU$o$;L&`S0;&vKav zoyaw@=UAw+H;;1pzp`31Iu1IXeErz#YHGZu70*?0nas$nc*+tbicj0H^#CHj^_^lX z_RF1RD+2s6>p--ZuW$WNZe>N?)eD)N`&ZwxA>aG2))D!ouF|Qynn-)5U;3}sJBd60 z)%u*=SNkowRS?SY+*jA5UDOgb<_IMQkVGdN}(TG-(oB0PVlgm|9L&zhI~t|?XuNw&hU7i z#&_2gKjqhJ4G0+_UcY zs%JVou=cBSEx5Mr{Pqo7JNHwrMa+GRJut^zv(e}Lhav^vs%%sSqGA1BmpS$o3&t2ppK+rAsp z2R7uMb;r*7>vrAete-cod(VbEXZ`oAJ5K*uhGxiC?v%sxIqq6llGa_xUl-MXcRl|< zkJAkA{cFtdXczxNw|Ox;?mxf-s!SByP2SHsy}F&px`T6pxHahI2@-f}hOJ~!FE zH$Pl&xf&A#T7$WI%hi~e(HdOeH)f;E8F71&cBBn|A6sy3YyS9lT;KcT-bAFm;r;o? zw)MaNjdknXUb?pCvtIh2s`I*I$5FF(1ZAVfKJY{D^Pd*EjqPQR-Ajdl6M_tkmE zAN1VF_``wwz|IE5v=>L9P=+!3=*UL}t zEiaM_Xf@oB)(|qdNv7&VM^e<(H zXeK-JOq-#;M&@k=rK=Vf^`Ihb3Tk9pJ@g0D7NRsZ<-5sA#6R9!QzL@WUZQ^N70W~- z&d9i@ocjZnLiKH}7e|H9DCN#89p`3BkVmk?{a%XCTK&bRc9MQ#77x=wiahVd7gKFeNX@Z;@AfRbJZeiTomM-k_ByT9f!=FxwHF6$d)o9`@Vpe7l2;cfg*tNlqH?Gs z$6XI?7sr7XE$ts-T2D4^#k`qg&)KuqyuEWxjw<`3Ycc#D$CTQp`hn+SH{dR3)!NYJ zMU>Z)u8DoCmZxUp#<#Lw>+wy#t-o%G?@-D6c-<3Z^}_T&+|x{7Olw$upgvT~kQhgu zL5)G(Ml>$|D&{RRtw&Ey->ES{`?>F=HBPRQSy`>GB7!zXYoYa%D)qEeS#ypz?Wpk+&>+evV%{!tH5tO?gH+&$r*%1MQif6>bky^04xiH!OhK zVwJpkA+(Tu6<^l?+JOAp9#|Fmm~~miHS4!&tO?)IyX}L%wNJ4R`W-&qK4|Uwi~g=} zV6U;S*k|lb)`We@zGmODk9}W%%<bd%l-FI5$sb54Kfop(d2tCUP>{s-|X(n4d#B;6)YinA)6s zQfNwkGoDxvYP)PkYIA(AY@OMJ&G0+3b!PEa1<-s-H|1>$p@rmU@)ZrB4ajd2zj2fJ zt(#D;rHyAj^CGGJe4pFFEGD&3SlZ9UVic9_^tTP zQ#y%nYyxdU>BjMkH>N}%I!EF}IC)cO71t)fy_-RskslBDZVqiuejGfu8me#0I8x*B z2hfvcEMXiz1A4KHA&kYVK#!Ht@L@e#^ivrH9SyA|9tqVaTCWt>6=tgl+mhDrWH?lR zYW){Bg6e1OI+tNkJ+JjYABLAiC%kw%lNyRAMQ8jlx{w-zw?!AcH1swfOwgNKZ}UM= zy}b1{ABaCo4`>ha`i1m_>R~>B)WGOLqR)7?&QK3?eNFl&H8uTc)qGNpe?83e@w;)% z_a*e>zxz`@fKbT&alsS%Vh0If>GjSLC)d)&G@puF+Y76M!(wW|6YkCT@o=mon zezTqEfup%nK`5tJ*oJ!2cBBW|H<}PC=sB$@ucXh6fsUb6dENoaUeWYM*Dh2MD(P=6 zD5)mcV_nD4lu$*_tfr(n!5%xFQfNn&IL?Eq574dzoXi@up1A?5&-d{+NQ`M3K zOOel~zH6bb)yO9$AGP<_C&)+b{dolWRR>afQgxt*Si5>t$*F9C5PN?hmC_sR{Rtt! zVH^Xq2%hn3>u*Ys@7P0T668DfqD|;sJ)u1!-*F_&Ajo$d1Jeoe9Y?}6f*hwWsj2k& zzEDTP6sYTc90QY~t^l&%PlCEa$6mfM)Dlk$$%X8e<$o|@c(35X+ z-20vGbyQ7hcluK`-zT5&n?1|7Ii>d8ZhX0X#qZCf{aitltu?V{>m}!!lP>hsuCYeM zP)*6ZlXGYKku_65aDLAoqD=2hk8_L`5|rciBISE0dZqQIpP2a0KBlbiNYAxKUCo@$ z|97BwTgwdzMU0qo?qshITF}$e$3n+)P42KU)OPhmb$OF5CpVc0wT+7@kt?x-2{ap{ zBjVc)hmPR8eIxgoa?dE=BHLkVC~51;w-^GoKKMDU=;!7!jh2)`T{U0?|b)LTh@yc&a76sR^`#(iZeMR=^Tk(#z$t z)r1!GZTV|+LUp1%{qK)eM`<=<*Bz^l(rm=8J60W~*@*q=#;T(<8?o6a%|>iCO0yCB z|Mpl7^iygp1U8qRR>`Y^F*IK##Ne_&$qKn@wVi9GFxFtPh+h=$umUj9Rv zSU#R%V(AZK;tUOo3gka>Ninh9N&aa6Ul$XLhUIT^$=*=;o-*~Pz{H~A3>mMBiABR1 zGF}%GyFN2R#_M9@!SJyR8E+USR_-W68dC#56(&~RX2|$|4krHJG5q88+W#HH|9QPu zq@9iA|6lc5HQG$O{a1SJw1^(3QDf?4N@90B(h4MobjKsDKw?ODJktK-u1AxiRCbpm zQLuP&VnmV?No)C0Do-G2`4LZ!CusQ*NxI*WHXo7XSb{bmk>r?&B-IVH{HQOFCX4~W zizi1B+#f?cIg%j87gcIY7zxG~RSu6FbfbtWH=;!3FRC0y*a&_twj4@uwU*e@HCscG z2x7~@5mgQ*H3Zoq#vDW#jC@gRA4t&7qt-rvpoK@>y+6U-Le$;+5&9$7)ZP0MwD`Ev zN*z&MuuYVGO6*=>R%K!>aZjjdQa!#0R0*ow)-I!L$!syA@NQsnWv<#)SEw>r$t|K+ zV^?mAht>M}6SOjEZR$(AX+z2*H-J*@OWL3M(6-u;+>=)+>M29ooqE&$+K^JNDbqcJ zNJ-m^KB5gNa80@Ijt5$wdh%{+uxhtzQ0{@C^~o>DzNS63tlddnt0CXuX~pW$-DwGR zJ7sAjzNalExqYm(IjMj9m9!zGF(|17YP3EQMY@%bx`Ceydo%7WbO%Jtt#Lg1f%e754;k(-r=WJ8f zGCOXP&unug)Tnby)}Z>Cb4%8m^IOg>Sr?56ZJ^GZ>1WvzYQ1Qo($eo2x^BUlGObtN zzgj~cN+w;V-Jg#Q>oPVA=s`J%;w{vyQzj`{Ewc>70 z&MP`U;~bp(E<0!9zD>^9IPYc+Ig7G(9z?sHdWEwL){Pv@c^K=)UvqxOy7Af0+gLaL zTDD_~b?=N)1M-=z-`{ZV(RXM?P@lELU8U7zz3v>QnykFkwF_#pz5}~Mk#82?p;`R( zW|XVn`s>!9v!njHzV%J{K7ZXA759JfU7S7htL37cM-abS8zZ}##;=x_y2p!OEid&e z%cwJF*0PzKY{t!}I&0%hTsCu)`5nW7=^~_f%=gE_sXY)z6Py!E;vks+C z*FZUs9)2O;RikMG-;uw%v!Q#4%c12bt>ISk+QEb&NRr`{k07*!yS1Zq5YNrDrr#+G)?w z9_2oIa%t^RO=FEXE1(3Chh*~HQB4Qf#Ar`bT(Jix_Z_T z@9yr}HoHSzGn+?RndbUlZJXVwkuIdPYH8_mcMC0A%0O2R_k}9=`a;z_m2&+eRYH2A zUVqxn85Z?Psd6vd(MO5qPCoAIQ$#FPUKPcjWiL|J*>~KJ(N(kA4vp^5*eLc9am*;b ze-wFkU?wM$akh30sS@@{*c!Suxzf0ELMbKA*}9`bS=>>fjB;mg-GQN;Fc&(PYZa6@ z8r`3v2~?Y_`!+NoY)<>nCRK^ea29kHxhm3*aQClh3Y9;*r$tl3OnTo8Qq91DGw7+) zNi_!tPNyGFBUKF!oJN12N~#4oa4O?r3aOT$!6}TH$)w!pX)>eA-JaY9Y7!%FV^Z!5 zwJ~GT-JxpenG+d@uKUe)kZMcc&Q_JzGTPj0%Jsoo(cOc}_07udTH zI2+Z6tL~qf?LL}~>uhzjb6Bohw|8daI$KTcY*&9uTz9Rdy@0ra5~aU=*nI;$9a7FD z2Y1HIo}BIKne|P_wKHsTw`}K6$FhCaKI}^L!BE$*D^1*C)IOf=9qL#XpUG2;xl>t^ z?KbN8$ZR5+{B~YLsqP#`$}bJ3Mh21ctcXGM&4Hvg=UoTVa|e)`!`ly_XZI(y1$EL7 z>fQx&N!#Du?`2Dk1Nv%QyI<9txPABL(3_h5qZ!I+Om{% zDW!T4G=?gxHzBy+jl66oVG}rq9B|Xf^){t^CY(i%Ig8-wA@bSTk+*7_odqY73vWi4 zO&`&tp{Ax&?D?Js+LT)Lq)<--Z3gv>Q0>~81-puRcFeH{CD*!8>S?2$i9IE>8tU1h zT`BcM(k{fF8`=U|L)?~ByT}77pyFfqsav~)oo9;53Cf{rkK<^Q@$?zBN;!e&q4pqM zLd-7rT(un?yZR`Mjhw&{;5n+9r-G8#5z!m!xEEXNxzL8-nACrvQ5^Bvei|bvQBEk6 zvNKzY==1%kThDS$xH=SjlH34uTHinp|oq)UlhLJS%@PEf2_}*O^zpSKrTer<=;NJ@a-XbPCiHaQ(6= z@e8HSevKyR0p>e83jF;x&>>LuZShz!E!rL`vJeq;gsQ<7Q<~uiJqx;!mx~w2mQq@F zCtVWT$9CyKT8>;oZTF%#`<2u9?Rrop?X=ih(_*VlqjkqoGMeko!llsh#M2pfuqh%p_#qIeO!W z6LKR-{Vp3%&h-UGPBpc%DPb_ww%#|cLIls#)!>_xL;&zVJOKT3L2 z3$qzP&7sQt*>Q}_jw50=y|*PL_Tt&x(HdIKU7PVgrO;W#?hRfFb@qm;{3Yv>CTxu77CzhV>LDEK)#t{ zN!x(FjrKq70eU#9|LV7@PHexom+3E_`9%8#O8E-vQ^{LOP~TPZmJrkgmAvkAX&otZ z-T6{|w;w6FmAuIFq#M%n`tsyHq>AWmefag>q_hn6<}G@WQrGCkdu5u2vN)eHs%9c? zuMbswQ5K8gW?N`m^6p%!4N@8H?nc@mmCI`-b>@Ah^-=tq@pN}za- z`?;5s)<<`4a=)i)_@lc$Z4~>rJ3}>x@3}|RF#4wZMpZ>V=-yFUAGJF=HU<-h@Ewk~ zoabrgv+Y>2y)*w|eG9c@xW7eZtTWe|`yA`i)!6=ub)0#^YESSTYys^F&G~L|qdVW! zQWLgVEp6zSvn6Y2TV<9ltPMzhVavCsFUUdc5qelFWtDU-={1fj276?otC7s(Ugsy zY#e1HXaqgdUD1>Z?v>^kYR;H)9BIX`JA&-(xpCwu$XW4~G>#_i_l_F5p7wiXk~)y~ zd!^lgILZc4t`%R|(4U|cUtZXkUR?}z&$K@Dc6UT`Z#4Hhb1yWJTQ5e3`=7b{nVinO z%`!{4yPx%-q-W%G?qMbla3?eO;gk!?>D;AEo~{>`-a2wY{dB~(jv)PX+|^7jD9;N} z^(cMz#L99(&#Y5}6{7@l?YXApkyo_i|CMd>inctdmbQ|=*7B>4ba_P$zwJnuSG3_R z9qDq3*1W4DT`r*yqF$7834Igw1}Y+S z6j07fl@6TiM7=4mq&;K%*=n|=Cs3%}HX(Qdg?q7iGDUy-LS>|4AkU<5r#E+Y)0UQL z;C<;yVkV_?A9|TcQR%PUNjtPwXzk0&XKT+DSGJn9CrY+`t-Va{W<1WjyhmxQ?b6oQ za+%3$@3*(u(poTGAz+JYt&~67#vyUNm8EsLrfW%TZ`VL*&Gw1fc(v~OORkx4R~>D% zT4S}z>T%~<4z0Vsm0s)0cz-=xTcCYgNv~hMs~%ltrFGWz*uGu1qTSla-b`fSdIIr= ztFc_c<&zr`oD*=Ry=cQP_6tQJ^`Ji4Z`WT{{9!$61#l0Stj2tD%CmiDLeL`Y_quLB zv$VT%!u3a@7@zH(u87Kh@rQoP=lJY;^nZ1Wb`cvW`8Q@1s6)3Ui15S-nH@@-lwN9D zpyXukVJ^p0&(l9mjZaT>z11@>b@#Mu0asH3y8E4$UL~OWF*b+Vv)tXa8Pp!fT z>bma7>b{WnP%RKugyFQU*uYsy`?Y&YRzU6V?iX1>7)sj?j;-toE#f(CG-9}QQJqLm zPL`p%@8UU;T!!l8TcSAeTu$#4!-?vwVfkBzczJc4TdMdpV|ZqfF%RW5!qA_R3l+8()s5 z+$eK5*77*Uawj3JZ7D6Ja@4H7>gr4CNb71%jx2R2IjZI~ zzVRhmTC3$Mx72C>6+f)oUO7%!x7F6q4}WZXZHWA;+g^3YS6%s)NiJoWIPSac_0RGv zlU#DfY<#V2kN7@*s4V*~C;XxDC2!1)EJssjkH~BjKZX3-5WMlv<4cT@lVWO8IlLjp zXh{%ts7b94Z+v%rsY8v3ctg*D3~&6{_7Zz!GHWd-{Bic9AI2Lwq_MW8{&{@mq?n^D zhcvp=ULubiKm6|aQhVwWN7h=rp_Y=9Vro)iL`R&cKAW!+i)YwZd|pefH3cK8X|^Re zFR7-fXH8ppq*|(4aZ^yHTBkO`cAyaTR&`@%GSoUd5GtU~x3}h6HM9+}bLP&eJG-u) zT+RDAi|)L5DcF%Sy7&s`(w#Hc!XmEJ<}`|L(@t)SyBk`jU8!f;;w>VcbPr(X-ko>v zhAh&v%2|8oHaFs)mXVvbgrg24?bx-g)$gotH4c5b2UDW1;U3*}TSl~@4}qQrqC>qQ z^phCG{rVs1nV=7X-Vl0A=qsVWf}RYS&zaaquLx`2J|fP~eAM)fP`cJ5q)E1J*LAu| zR6U>6DRP>I{y3tcY<~fJh`WSo6;|hP&AGp)Mq7x@z7jkC45-%oN>ZY@O`y(uXY=9C zjn5*T&6CgOX-88-$8aLWP*O)ik4lb!9!afkLw$GU{Df^1Pu1+2%qQ;3Sr7A}o&nXB z(;0Svda_ejPH@->>Pb*tIl*CPXg5xZ*ahlYQ{6bTVmGMgi+1CDians7kJXJkx^k|F z8ubaZb7QD{@dSEE2~_{A6X`*vP<4V6BbPmqo>)P;lslG1OuQ^2=4Bw}iIm8jmPK7? z8M@G9&LCM9PayF$5>HX}Y}IA))DurzJ%hAoqR5-hAS{b#qj*BfSn|swSMsE{6`a%J z=_qG&7R$NNvxv{;>T;-k_H4pvsJ!fKO3&hym$TzpFP`gmKKGmrJ)6?=V?RDW_HR#| z^Hdl)S9Vs+g`{$)&|MtQi@BJq7ji<3z4#L7#ZXV9T}k@|sC{N7jUyg%rMtlYL4TCy! zaz&gcxgySxTnW8`Q*gH6Je;ecp26#!$u-ccIb~=rsnztMZJ>_&)p4Y+j+|>XSFfeS zd6m_1Ze%sH*z-txuG(t;XKT+qq>o=0`}uWz%cZ0*rR;jro{?nFzdrW<>lp!sq_rJf zPbh+3$MrS5`4P}VIs0V|XTBT?^)$FOoc3}!)H8e6L@uxn@rPB;;|jNW@Ysb$blei{L~Eg!kpC6eYM_^p_l)dXP7>3q z@))HZpuZx1jH|zj=VUj9YVCL&In^AhMdWeD)GBCGM%d$wuFIe+i9HW>6;un#6Ue%j zP^~Oaz~x&*J-_k^LPKZ^?tPLma~0InE}tZICG;`gps1NUi21v^DhGr=tXWI?Ai3qjY*Y%A%*E{CPU+=TAoo_H>kQPcs(Q zaIRV}{_|PrGn_tl6aD)+o^>PiY2xQd-2lCTE6;IC=@! zXF>JDNJwo4oeg(N;*4%W>OjWnXh!R3Voz`y&6w3fe+V3X4Ag6$?=+gxt3`h?(qkOd z8S=$Qj|tGR+~-M9qv0CUC_9v}81A+oC5KURC>+G`cR1lN_{daJN5pY?1nDJw*A(*m z#_=j&a&IMfE0R;WlZtsIxAwsVuA1$yB2SwG=bD4`as|S^k^7m}UZkJGWTc*QQu(NV ztA2=jz3Snc$Ni&t$I($%?i*$0zHrzrDBXcrsvm>rHA(es@B}BRGke<+HiFJ4-j>ub z=yt?IiS=&qL?tbJt{&Ki{1CYGHgHaT`vwz+Fe=0xj*%+*(pHoXf~#-EIFYM4YAWez z^CegV{zqIyua6a97%5X1n&UQkcI z8bDYC_2jJqgngj<@WcUxfs6}hs`Q-eK+oTU(w_0esh(hvT}k&K*Ds!})sL&rk?c;s z5411+)AP4_#q+oH#MqTF)r%{=34M@j;$(gG^y?8D>%-^CV13@) zX#>_jx+SAmZ#`*tHndWrrp6YZN4x7eFd3Si;I$?FYF_MB%1iOimh`u+V$V}{s&j1# zRkBW_O{UVb$CI8;S}zbKt4L=q<7%6KjInL_24#F7LT|oyD5-u>ajV*Gf2fF61nv2; zVq3AZn0NqnF`r(t8`L@yAMOs_jXK<()E@M;?fF*mVM2NjsJJm9zat|$p`;5nzW^$3 z>_Q*g1-gJM8U9q$QJ3i)sYt@}a5~dxoTG6azPr>oOWuT_7VeHU>M`x1YAtFh_2`kd zzq(F4s9KKtNj>^=rsb#)shQNH_h$NyI*^))`|xKvjoOd;h`#NaPNT-tg0%ZwIO|{= zx?aGxRm*V3AoE;sZ0F`*5}2~V2|)dyzJ=ryt@JZ(1VnbgW&gs#xd z$nO==*j^Eh?Zx<>L&=_8Ur5`|g^DH@5=KDPq81WHK}Dzw31gsY+Y7mS3&zV{Jb4lS z<@gb~FN#QIQA8?>7#Te&kzX$&^oEK=7xABaK^Mj+^roz)#`RVDJKNLb;Lf$kCG}Tw z9!T6$kKj6oDWvMho?M@_o>Y^`7epRcKw6z<68Q#^_cb7`56H&k8$zvHaegDHwQav| z6vuX%MQ2FC*Xf5~37d#8R7SwoQ)S0)AdRHxcb{6;P%_SFBr`{4e zFX9t9?@aP-xmS*(uGSVzcnMTJOyt*=F*B3<=0LY#M9(Cpmaa$pCeU^fRkn+GvK^@J za!N#i?IJR4$6Z&EUd40t$lDycIe9(vHsPB(^SyG-`TTXGW|Sw}^VfrVb1d(`UoW`t zj@0)~^pZ0A#YyyolliNl{ZFCQPvx(Y);^7PJ)OU%wCWkO;&T3)(}pW(vorZ?K`YhN zc=B#XP+&*mr@(|A!E@#_JotA?A<+Gvgh%MF4^p-;Y6{|jN9d8B5xj^JxtJQqBEkbv2K@pm{@ma|fj}(9rInJ#LS!;+ecN!MC=uy57vF^=(R8OnWo&Ea;}xyys|E5JW}dp-M`$ z%Zb{QZ9CB-+mo-Nb+@No=96kltIvn?ijg`Hc7}SI=2{EgPPE;2+}DhLz8!o)t6X!^ zTJywpNBDw;4@0RdrQJgq-OSrQ>?1coaQcB1A zTx$i*CvL#iLb!Z=%JbqlEuuu(sJ~@Hs8Uk7tJbeq)||-K_0JU3i;uNhiSzB@3YSu{66*QB z=aXLpy?}TXCE8Lv{Z|Xl8mQ+xUq;EQXyv&9s_j7QkW?#zwj!za1b2;T2X&n4Nh^xi zbLA}BeHQd=?l~*!TbNwXY%&n64=X+tNEN??5V$=pDA z)>iQ%yrwX`2;Vu0bGEf@yhM1B^S4hR_Zz}XoXdSYxt9sQ;neBl$h|^%84RK37kKI{ zsOPcw5zzVNKx37nGc`NXdgUgfOpqsaZ9@LKXZ2;nH` zQRLsCwvT{%?(Z9f*Eun}6RBPi(J03z!Hw1FdJ;y%jX&l$dUI8jCA#TNeq!X=qmhiB ze%yy3M)%C*zJxwe`i+K;27~mYT)F!Jr#|;1d=z>AC?xa;LHW_zS7Q@pSJY@kH+-qz8jTJlA_DVF+mCU2?++?l9;%;hp38 z-<{)`-<{)`-|jrWz@s~ zt`6Y$%A%w#i*ofza!-H=%8>m}L!Sa4l#zNCs&%Q1)FzCqSCN9AKJPk#S84xIVRYz} zj1Kk%C2c3dsL+9uG0=|0n{xN>k(V=xJ9CeiPFrUCWK0+v)CR|d8I1bhB7HsMegiWZgCU8D5w8f80c_rmxf_Z}B!b9Xs1XcjTv z)uC+=qgK* ztTnhB!M%rGm|v+#6&i7kQqz z4>kQf^m+1qsPpIG5oM(MLHoi5%1BM&Y3_khLuwLqGSX2jyb^i|RE(?~6#nonvX{DdQ@Tg3F<|5LY0DZ-KUfH@b#NZkp{rrSJS0(pn1j#?og_OQBe00!U^g z=u_*!NU)B2lE`OIaFTOfqNP2+PwGjcsNF$SEl4*fs25ceHzT!6#9_Nee6~x{IP8!# z3JrsprD149u3^}o?{7$I`=l7!I1~kuP7!xqlax?W92!t|ZPI|SIw_^3B$Ng%Ermh6 zQ^@tzNf{-jNan(DT~bcEEaa177KO6wk_t-7Lw(AaT_LPVngp#hO(?Gjc|p9B$MrQy zCFM;(4te1Q5QC_vDrn)UqP!C1P%qpFvJe4KMFAQtsihXV*L!qJq7GnAr7M=2^YY!UV+v<$~kE+R>Y#f>e)euP$G zDJ925JlQJjo3sk8!?BbsMXT92X&v?-A6xfbLK;z)HZNi`*|9?56C*Fs&1<$A0la-O`F?F^Egb*U!i z>6h{bz0BJ{^iBF*{rS-eVKA_%z0J6h=BI>hUQhHQZ^2#~;TNkLd0(FYc zP+QOX{BEl%U+vH87~=F?ALtl+zjFGJfAozGacn517b9U0Wqc@&4@G(&#>i0W9!9TN zLf=maM?&rGN$lJDBiM(<-1buYst7*oMdRrq1CTq)wQZnksiNp@q1zyhwx)cmDC4%H zL_OEN`qWnYBw7OpAcN+Sc8zskq{~3=P>byg6*X^9$$VtQT+*)0)?PA@QfCj;%H=d_ ztIkD?Bj+51db-v{^;Bmk#*!aHymQnw79dB|!?i8$jI>z7mrRKKVFGu1mi*?#6G$Bn z)s8fQFdM3tJ0WVhqxk<_kw&A5N0QnNI*ND%sfo~$#9DeMLe&}M4^rn3)%=f08X5q+Q|V!A)Mk)-;gBYc9k@G<}U2|7i}Z~u+-$H^$J z_W^JBK@<51shUDlu8k(&3p_lE_`@U*+4><@KSF=WBlQ82IuEU-KDx|%(D$MF$mp}s zM!G|L5}(cg_k{K&e>P9*1sy|tCi(8r?r1A#P;xeOEb$7;x)d&Gx;z|~9-fZpKMqgF@jo-e ztgvY~G(C(fhZ0T;7w~^8pey*TCER&~WwWGWh3oF1B<20bmD z9!8{%!9^p|4%RkTN2Vjvj-f*sl{Ns|j7p0@JEPK(#C_5Wcygb#Ga6Q(vEiTs=;`6q(3}75llD$82YBa|8X2)SvZFOxG40Xyk~lRn9P;q3CD%O>CkjYI+*_-nodm%Kxk9bLNMDPo;NHV zL>LSmKyFGpiYrsn(Zo|oO-%<NIO6f7CZ#8Z z}y$EPPiPe@Np+w)Zyh6!AslujUQoOYn>!q6@~hAZs|?bCMY(d4$|4Q7Qcd6(H? zMLLB#SdmT*Q=pTnixt$$3D6V5iD4p7+Bof+c2B!Odk}Zzi9Mhlh>zv26GK~`*)DC% zTbu|zkz5z9_ki}`e>#!wl6EHUlGbuhTj^17+MZ!x-4fofkr*qF~>DFN@{`1WAsBkp&=x|KfhWsq(%&-Y`YjWF=pBdWlUo~l) z^q815T`U0e(mz1o!3yvcrSBvyxW8q(19vZnZcqFq z_vqiURXQ(iMlH30wnHbXi)RHs@*;V$BvJ=lB8)G(j=`%d`Y-CEJ{}r7D5+t=gM#ixo<-~?r>F& z-mdkC^GNL*E)9F6yQi0imBf0E>2IdD*&SGy?m@rPqpM-ESJ*QYB@4q|(7i%Kw8e+H zb`!HX4=1a5#_s7V!fxp;ls<%xuHCCXPv0kqJN6BYl0Cy7(1yhN(>)0OUdXc=B#Xkr z&>-0-EJF8ugeU$C%hV&u*WugnO;A7B1G;sJBY`5>Kl^XsQDXsg5FX3oS|Q&`KkKHZlRb^kbV{NsKu}N z^{>NM)Y!M^(U*l)(B0A-(6v{E-BR_G{PgF3Zg;*Y||;cw8t6RY)n9#gbak?Cs)yRXq^?cg=NCQ*`*7u&WS>+Yw|z)moxDf+`{6x){X^&{#CxZD zz3rXuLwrDbRk$)7kgnm^4@hs|Jr3ac2c-w3H-;NX|18`X_JmDr+IC2w-q zTj7fI%5?wq^7Q6#Q@ETvuT1X>cZQ#by9swd@8J1&hr7tV9^MRZgbUKE)2q_+p%Mw}hL+s`S=yOSq8I{nCfSFTx|?_dNei=$riK@58&~&P}i3|1RUsRq0FN#qdIS zh&vw+zY4z$kA~O6AGzx_!tcXxxb|!4OT^ESdOkeHoex1DC4P+mcr?7q{jY^3;U3;^ z3E@`gt>LnC3E|T8S^n#}@GQ^xHS}fT!?|+_^j_k_!+pf(@Ezx+=kQMFL(e7dj;>pY zCaK@o>B)YnexDceMeZI{iS|-Sf6zaAzw|W9^)bCDy)f;D9^4e2vnhA=Og^P0^sxF2 z`WbEVIPd!q^r7%zSiyhpovy$Vw;y!x^hzvq&UJT1_x21A&-6HzXP$7KaCj7n6S=oW)Zv!@hVX@hQp0=|$-&{Q9Zb8qcDWf{2 zuJ1W0z4_fE!X@d-^oVe2dP#aRPdFtxIa!%roSu{%5mrK1QtGqU z&l|W>{MF!!4EJ*J+@SOL6@6#V<$up3T#VM~N~(6)F|Z_)YL5lMRUmq#Ux1dsf6%|= zfUti!gt}TBjwh|($${YjY(@u?pO*YCOvg^KC^;lxVGqBBPAB%Pn^&Q)2GhR_)399Z z%{>bVi?CMgL%c8H;NXcMzYTRy#hHSZt@nv{@0C2kZ|{{n$?xk;dNB0haA4SzlD*Ja zH{pM05?+D65}pofxt^ml5G{5O?$I9mRCqEtPw+JK>F^Zxvi*4X{RzjR7we(usXLRg zoIDlwK>L0w><-u@DfPr2cam~v zsROyT6nX&hu3X;@O@A{|dXg_iPuHt5JI^OO+h-T9?}`m!bF}=OiFd)yFo)CvVyQNC zy^#)r9)-o^5K>E_OUaGnX%nGZrN@z)fE7Yd&anjjT93revY301#0uf5K+Xd%!EP{| zygs1AqvhV6jpp)8J7B@kZmd0b2g(*;uUX8097Z@C%fm?iOIzq+(MCQ7`^Y@*b51~u z{Z>$IG4r9$5IAozA37gf%YO8v18BX2!$FL>!^2_lo=X`g%g`52f*zS32Vc1Y-n$?C z^a|(FMx!P7^Eqo6C&W5bc5re;Ub<@VsW?LmIq5=(ag-HPe9McZ_q$T^-dpy-__ z*#;c96ThatLM*fZtiFKKtq9`wUC7OYZUr9Ng_IiHgpe0)8Dbd`O`0qTTXJ3PK-`pl z!AO2b&0QULBw;K_VmIy(n=FCKUFTA^B^YIQQd^!m^&6SRm1C?sw1k2&J1cR>Mf@cpUhKFLra~-e|AJmY5{FQu0zzbI#8kp zI}jUImsHJ9ZFUB9I2iu(gt-3xl^&Eog8{|wGXx)?S+H*<=*HBY9aOc;)2v& zc3OfG#J^$&ay+v&*4NI&Eu*!y1!--w+R60HXaT+v>3mCzU4`ay6|69ir`5*-b1Ltk z9cCF64juxvT8OS#$Q^;ZucRa))?#y9Sec^84Qqz71-ld7#U#+~1ARJW(^vOE2bqPC!4^Zr2>kr50!H znqOmIya0LuPw^zV)oFMBuX*wnl1<&{b#M(2tI_*Wc2HT&O zJS~Ak)85H7>9x>a#3ILQq1U2&jKIn`68qgq;!)f?1ghQfQ?xnJvs&F~%7$Q}(<(S7 zTK~q-^1Z?s$_8VJ)8ace?TKYw>s&9W_V!Qs-%o>xO{LslhSt|N zxitNN5;Z_^?FUHvRg|nk-^s^LTL8imeZ0@r55oHqv%Vh&fF0k1z8@xI-qfDe2gVMN+KaA!v`Bf(>gj_fL=3%Xhi+k3qZEM66oc3OB*}SQ@l_nbsDm z^{h0^B$S{Vs*O3Lod)e`B~WetZ&R-J_*b6yHsM|L!@rVxD{7r@@}BRZ&Amtd%^+?a z7w3A$fsvdQ8Vg$bHqmDPEjD{+E40>cfvs#atZ8$IooyMyoQD?cFA}ZYpF^Ds(dIpw ztIoEFDBX*6NJMxeq2jhlTy@t{QL6JM4Z@d%!tfdY>zqepY~<7UKWB2pxt}J**vmhq z{IfXIQpl`JA-3e{;N>@=V(01HJBS&IV($AS*)%N<6ZoZ#BDNd>ww*wF<2a+_9Mdr7 zKE6uwnFY}g@EcO~gYzukL=?I)^BkL|pMdbE^ZXfvH^Rr1{2kmrBY6YVuEy{Rn$GW- z=h!s;nE4Q`nOX|xrlR{d!1ZsSE5FP=uQ2B^EB#xv3eLr9wgq*#RkT`aL)#2XnpVh{ zqF%cV7R!$kZEmx%ylKBw19+YJ5-oWja^<7sMV|RG8u!a+)GwknzZyjSuR~u)+x{TY z+V=tXf0(>L{x!7j*SPQ3q}9Xm8-l6_{5pvK7hv<-0n47Yzvn4YKNs;o5!64PKsR|R zXv5n%eVp_Y*m|@BYO&iHx`6*ZA)Swf@dPY~^PyT6e}!KASjcen@$ru1xp#;3o#+p@ zjJvkO;`sr-YRgD{ko=M-KaSnt@u2nK8FEXx{(iDF+WwbD+y7GX@1be$i=E|OtaH0T zwbI=iEr0itKOQ^z3H;yQ;O~9XHC#D9eKhLYkMhi4hWpW{?**~1p$(0j!g0_WV){7dLhgx{#e4Xzd$Fl#rMQvn$6~cP5Y&HAME(cyyL&Tt zaul;9T4|03^Y6uf9vkjS?@sRw>gad!zuIITAikOZKPJ67y^;7}{&NxZAmXJ#JLb}8 ztz60zj>X!3FjtrGS@TL^cgYO2qNm$2b4O@B>zA^AD)sm(|W#~$3TCaMnid~ytT+!B^B zFQ$!XN$OgR=h2Fv$2RjD=4k%RjLTAHSDbfQiq-#^^!Y?P(&6c?gu~L^d5*qC`cvJ( z^M4-Hzn_C@+j%y*nc8@k|9TD!{!P@2GdO={=0PMaaS?IIj7vULx%N3xv zrMEMOaC>@F`dgm&E^~+PV&mU8(fXy{|BJ8-zql***gaz;>O0-fR%6#Fe{Px4)RIZ+e{rTqP=x__+s1Vm%V|zX{y$M_KEj;P}uy-C{ zS{2E{K0PonluDkc{f0=o@x=)|}`gEwSuCA)?K8cj>$leeCq+B|n6#4L^Ozke9Qp=l2 ze=`yzB?TwqPC_zvT6Sl;lXOoaalQlp#_YFfLvJMIO~|`W=j{o(Y~Tcbbz(LpQvx~# ztodyj``$@+CMoVfLUsneJK!fG%U0W}v(cnI&*I7|nsb8t7$c}NM*Bi$7|8CLduL@pP3kQCE$na?EPq+G(H zRmwyBTHV9Lxn5@~p~G_7(By=nZ32e&~l>z^SSm++QVsK=Q-(d|A(indkVWJs%sbSS?unp^Q64uH00u3P|s)c zl=tR9PYGRukmr#viN83ZmOxL3_Z0a!-7-$Q^u&43yY%dN&!+eM`F@1j0zIkTlkD38 z-N~XgQd`y=+D~bXRLS~8ODe67JUzcRVb7WNgnTWsv@UAT3Q%iGt&2S0TKh_^i#!>> zJ7Lej_Vjx#tf~oh1=iqen?<;~9xbUgnJrh?uV`BqCs2ECPQzUOQ$}kmH_}FMQQI$S z`~P;lZvZ`sQwKb=G%UEZq;xFAnL=U1wFvJQ(VYLE==~zR|DT&{7q$JOw*SA*W6E2G zjdWN^$z9gZ=VFBFi+Idmoxfj1bN=UO&Z4!||6JQI!u$W-ZEyd$SIw1|JJ#F<>5iE? zYZGlfO5Z90GEJ=4BIPehGj|ToLgqX7w-%Ji|}F5xL8CV7SYK?^Tp4f zH`V<(_tyjdJHoD*%vlM6-_Qowc|SNbIkkoTu2THS)4b(8EWLhR`OEVs_i=kaoLT|- zj@ZLhj*hG}?ZSqm9%>Xq^5IDd+A({Qf*gv^o{#E1Ykt$4`AaK;GkNP-rY@x#rk%nZw1FC zCsm2_Jco8XRgu08nni7<+mqItc;&*h?KHj-euumru{+Gejrg5+{WL-cX$y7CTel-Q zv?uHhz8y)g&e9VjJO{ZF=sC#p`(anE22wq(ckIOtx86CYbjX|MY$e;xd+EF(E>5?o zz_(>8fZiq7oRGHxd!lShe%lymE#wGW_FIav89Y1cy`2FFYU)|!%jeH;k@m+AUyw9`sk;ATZ#{U-H|s|R$B z@r-s)C=%;h(WZ`UX`i?KIC7o0TK%&v;|3qcn0J%fPPU!&*ZHU-Z&BO21>xqz&f5+@ zg#)GOe;$qn2VlOXzx{WFqgNdfwu}_k7At1AU&2QO^|c0$7p)V-sA8TJ-)+H|A)PaW zGTY+zkaw$kew2KKnC?ySQeq_{_Mg2Y*WjJ3@(IB;MBj_|@(9joatiiYJ5oCTHRRWh ztrkFehjxV8Flxk}O1@eFbT+OejnqCQH1y!+O<)bZ!dn(g_$=gwPS z?@n-z^$ap+SM8vxcv={K!IH=|cn-Q8L38qnb`TqFmuLrDK?#y4(Y7W{v_o)G!5uj2 zZHuBEn&vgLUba9PFlv|adv9a6?zWSyAqQbw6?{arRqzqk*IL;Q?ehAHm$raBmwcFY zw*`X#s?1x-_L>)ee`>6k((=H`uyc_rI~zI!I%*5<*N~is?QLl+so$9Qy9M2H{uYy* z#f@`*FXnsac;|Y#0r>#=0eORFdH%sgc)yoiMZrr1ClO~1$a9qP?&cpl#262@cfq+h zb6ehpohxGO#%~ukys+Pj`^v1ZBT1guc}m%(^>;MKebO;b9pQ4c;$;h93!ckJA-2kC zd84y@mDp`N+rp(hb+m?OQpsCu-{^g6rjkdKve*x$7}%G%e!O%4eNW=t-Cu(psJEZ=C+9vu$Ah={ zwFS22O@CsWVmF#7?*P(hL)wFydNX1I_UCB;?|Sil)BHFN2W~jJ<-&f58{(e0As#up zq@3lnpL2^nElye&(~m? z_2hfafv)0u67oC%@9Oc~fHI)BnDpe=?mQI3dg1K%3Vz=Q=M6T!^RS$uHo02sw&1Jo zC)8%Q8@{*RBzoFCjD4wzc+v*nJ%rl(HswuU%GHV9PxOO#;D|F~b3cBa=u!KyKdvFL zFZuK*y*K7G#P82@89m;Q^aDum3AysE1E{Um#;ti8KsoyWYl$1cyWaf5Z~ZuKEGSK} z3JgA^m=~n6v0fLKT=hvsoFnGPhj{B#9Uqct{U7onQja=5BvBLlYi>ToS*DnU7tDtw zdbN}f2@WKw1eZtc96>u|2@m! zIn9#D56L-8$E~@e$-8kJS@I!{dP^Bn3TtT#d1Fs-Bl02gYnDDF6P7x-GG`5WFu5|@ zOkPTUBlr+`!Gar+qj%iNiOJ7MpRK!nYTct9Y?F{=l(vIBhwb2KRZnMYDAB0HD?U(4b@234Tfo^-Old|qRwwc!<+PA=O=@Rv#QmbqjCHxm|CW(X zzQ&VTuy#O^Q6i0S4tPHnOv0gINC&7q&!BM znGzc5vnkZ6D&s0B7*cCNY3MluYEX#2e{Jec? zPqiQqc_z=w^=3FZ7RQm?hFW6VL%nhRybekPEsOk&HF0ipg|D7jdfA5G*dDPqR?lp^ zxgxgCayIhswr4w>{7*<3yq(VR=%})l9F?wL>g1dS&u8!09?rJ5fFs}XDtGZvvTdvyxYw+bojF-o< zt%OQzd*prBgOImhSMeoz?56M^wrx*J*cd1-6&zFzPrWFaJCo$Dd*yx6i#G8NY{!u| zVRr=M+F}q_gKmO%A0vVp4cgWZXIH* z*>|q1oQIvOqep}07hJA1!FeGxD#|%5t-WbKIxpCduJ;|Cj75eP2t?b^Yj? z-qB$z%Cmc$pEv7>FXDMCptxkO$phQ-J$MeB@0_=9J)j(~>n1r~+u6P=%lpM1biBFd z@pe_Ygbx`ONE^ol+elV**3v(IAb`wxLOa6 zB4nxJk2EEusI91jGleyAJtXESm2Co4vQ%1kV}6QvT2T5@xoK&dUn{(@eX+3VF=|xRi%=(cO!+D<5IpOr(?;j zf&4;nH_k$~hWtV^pu9=JHOR%d4sgw6OGu+!mn)}~$CtKA`<$iPKz+2->p&S=Kux5i z%5T(Z*dJsrMTW%?LfrQy>4Ur<=ySvhh1x-OrBzjvl__IF%J zo5gll;BwWjrDA=hO+aV^Tq!uRuycuuZne>@@ly%HH5JWwbf&8bDV^<$W@r%k_vSCXI(`*p=H-qG(@)U4ZT0 zohMg3-6?<6QJJGP?M&UV5&~9}qUc+HUEry|EDa~#^(1e3Dfz6B&h;Xd9FJ*xlba_1 zhzWhjT?w*tR^J>i`T;#XK)ewu5f*!eo;KjTDD;+7X^YU)3FN?po?75~Qy8ZiG|kU6 z@IDad2cb8CIAaJs8^Lv`(9;s+R)n6V;8+sIJ-VK^;7WNA&~q4^V^*LSJ*%M|ZY5w_ zo}6P=qDQ@%!*$?F^pZDrw8sqrR`H}>eF!+=-5$;;L%CukPbNMrXlepWWVimY;kSvvpAFG*plTK;@I__av-H#VzeAk zTVQZXO2X8UDgRQpr97$yqbRhTYUhUL*fa#_d1ap2I4sAzVL8TmmTY(Mz9;Wih8pw) z_j?f<3>D}FF4yq=;ryb8QPP{(6?00kBGjNa;oii0-pPvjNhfgz$_n{OCk=p71y4fp zmU^jzXP*oLi-(hEV!R9oj>J!li;+N2&P|Mk(LhhoEp8lZ#4lGRCgmslru?jwW%Ejt?a5mfOr0Ik2oZxCtomd~By00=QRX?CQt1_t50HEh#mqC#h2YLoz8I)*A zpr`OT;^dR0RdP`S`EQbc$(g*Mub~^3gK}Dam)3fe4J8!=b=QN>TK0~DuEVH zlu61DiYf9S&J3GDT-}q3l=>QlF6Vw3tLX9j8w#){AIt5 z@%YPr`^&x?R5;4*8biIJe7-tGUnwBn_>7g#3-D%B3GlLrzD=Z6n|vFEc^TaO8?(4^v2&lrv?F5XbBXq5&KO~t9PQu=K>f30*4~l=%43V&^7GEU>iI%zW7&glN)vqBAyzWx==6NmDcv}ng-XXnmv^t|z@oP1HN}R%~qAh7cvQ?9pUu)oQ zdHG$D7Wh!~K;Q(Q=1uTb_4vKgi<*3;S)H#j)rTwfb497`o98{cqEx4+>`eWewvE=s zHJX-d_Df$v+NOCHeLq5;Ft43roHOs*tvxF@r8BPJs({LCT*p-crAMyj+5uf3yQXUk zlzzFgYXg*$xxQ-+l(u;)y0@<@OY+7ZrA#4XT84IAmgg3%KbNIlmm}mo*4}UJjn>Ur z*$x7FGI&#?O>oj!&jfGGnt3JQio`Y|EWWzBuE5C+yXtO;6PsP1H^7N2uFK1D zj;rB3)yFB5b=6!C=O}dTT!xDt8cE-e#*94_vWJj6IM?^%ME1ov>D{}17vn7U#d!9ddF7@)dkgSl`505qs?@YU zZYjpy>cnTc6w#ZE#}HO#nB~&K3>nGlgq3S3ZOp*#{`^Yn-2nU;Mav#P`503q|OW zL*=x!xIw_~`0^`*fJ$qtaVz9Bae1hMa#|^*5+x~N=%hju(Uo^AK`oToO8Zu%m$eR( z8V;tnrKHlv!9ZoXa+5*rSB8ox*A0t1*O*F1q?mR5iEAtQ9W@JDAxXQnJ5#qPrI+TZ zF_PwMXW`CBX{nk=rFzQuln)D)7)#l;Z+5PdlPgx2&SA0Qbj9n;>2u7ekut_|=z_|~ zub6%1C>Ab#%75*bl`lC96(y2?vV7u1$faTp;fgp?`P=!Gp)|d@n%?)OFNu#CZu8fsnDT|Y$$~(En zbuWyx+jX9Mg`5xMT!ZV3u~ANs${%;gDSPm?&NI%MQg&^%o72B)1EODC*?FtH`er->ZAE9k`Z#;YGMD4T7Zve1AvBPo-I*gd1 z(6YsO9+7heBM1+N(#aK!geEQtT!MF_2#C1EH-;=Tug%U<@>E6)5a7 zIj!}6l+~ba>SyE)yuEHYXqorem5$kv+DKP|8?zVf&!9eG*DCiWm66`qmWdpsIqCz{ z7D#OzIqpYLcOb2CSEn3fVSj5sx$cm&bPeT7L}`Nb$bPOzA8P4f|JS1rwPOqlCAZua zOpy|m(XV2pJgR(zwvy89GF%U!)IDsl3caD4LNT}-&`~7!suiIl(UBJCBRP8O#$${= zWi8ryghh81VMm#IQTZyZGnxY(*Y4BNrnEhNd?mEm#Tb+_sJ-m~6rZ&b6pz)v#t5yY zgyLhARNNMimA{YL7 zxy4>}sE*Kngw&$i2ja8)Y1E|-Afy)6J`QY_d z$lrFwscj!gNFC}(dS?_NwWy=OQT3_nP)E~aYE{*tu0n5*A*2p<3|PBrj=$atY5lY< z(4NhDhs}A6N9_!Jww*#B7voVpa6Ecan7c9@k7ap^I8{RHA~^y3NqLcLbo)jdE?05( zhkINdf7&A1w~0C_;d4ADYUZ9IaY6fMZEYQoF;}|&vbN3@H9%`vFRzlXH*?wWI4NdL7Oc9cl}9o3E%>A!2} z8lDRJ@4P1cSH@IJ$Z;lh>kgFe+sZwF?tTjDuPv^;mSe`fZ|;rjjcb&T8Ri?XO+FbjIA( zcS(6{e|ZCGkuBMrFG-!G2=->2;HHeTx;pwPQI0}a5Il}nW=hMnAJeW{3u$STGG=?g zzOf(VL$p7UW<}fE;#x!7_O`gaV%t08+AEesY_Jb3p*Ue5SaPx6p0GyZhqbi*yXUR# z&NKU?7wyqH?+167H6mmSY5$>I#g-S3$_d%twtet=_Jz_&@jv7};&0Igwt%e>vx)p# z@w?za<#FoxQ1klnG?6-T^^3NvGidazyFA?;5%NmsoakA5ywyK@)*cUyhkY$)7(Hu` zEA6&t?QwSp+OwfGw~Y3+T%TodEIYGCA6tg#^ZC^`__%1Tg6}rnPq#_TXHm=eR?I(^ zCfYS-qY^Q;(`X;j&f7F=yd-HQ;A?Hz-Q+&@-s2?!Duy(bN-1VZpl(g7gckYKN z>_xR~mY;Cs$@5zmxmn90HTIMncW-(sKuG3d*SqvQXoM{&=TpciUHdrRr5tm&mvN@H z)x>RE&DDf7P&u^HXC-x7#x|jx^17DR5?YJcDQ7NHeCOZT(eKxadBAUraX$O?;MdgU z#CpZ|mcjNb`qlQer(Mrfi8q&f6icXNu~TztABDvgYxznM9at@4FWIgIHTZ|v^5LPXho>IoYJqs z9~GR@aApZPBkj(DOIk30q>b5VdVLkJAULDioF@uiN&d*)77kVCTpyZ6C zb!vfXfl|dTxN@MF=qM?upQ}729_|X44u-8$fqP<}oUznfJT%;yr_h#&VM>Qw8Am+bbtP4yN!{lOP z<`oNL{&mh(7NU$!UdS2NT{Kn1I?o0kil>Wkub6ZH`{-UBt&@|M>yxXK|CDDeID2Ve zvFE|v=&nrUNwt1+hiI`UTg*`wE(bF=M#&8;`G_6k$|RL`6cTaQRoZb#&ElLV*UCzg zaPIeT@0GGS_fmyKT_sszrHOnYp8 zRL1%Xe`kBUf8JAs#}U|H2Vm?7a_t zlCq`JGDJAmv&uh|jM&~vaY8!os@=7^5|miUhcvxd;VX41R{lz33Wb_aL27t6;0ERdDZcdwjJGAsY)V zL}<)HI}v+#Qr-{t+|ReSEFBN#?>bRB8&-{eJ$5O^-f8(wsiEI+O=fRc3wOraC)O_Z zWNIIzHJSF4e#700j;@6%Tdc+XwX&XnZ`s5OB^I%+RHk7)l_Waqcu0q z3XW&B5NZ+}K}rll`_L2Ii1DZ&bsSIB;p_^A1_hD!Z{9@uOCMZcFyYm||wRZ&i$3?O6~ zA;Xxr9hCG2RS9~nHdjl*a{i^>!KVhD_IsxGy|l%abPZpp!7(RgCee;XdP`$&vG>kg zExYm;_yjpy^#twY39*#&YM76<+)(EL+opn>l zzwJAFbU|e(t*<#+J4bM#8MjB2!ALV5!AjcwjeYR1w1cf_Ep6q}whEkyT3a4vL?QEW z)L0Yi=tp)dKsqD_*M}LXg zb^TRZm!H$-fvbU;;-wNM>*?qTIbYc2`)$7zSo!mDwY1DdkIjo?3o3JIACRzehlmjdwypCDS`QgRew+d`%d~0^|QXVtC($XN;6`HiWy|?TFa3HW-DQj z8Pz(L_EBj$OY2fvU*n@q7ED_fwy#Uus_23EejV+y$EEYmJW^%XLgHn}!9zM25^(he zay_nS_p}%?Z2QZXc~YNL#IvE4XUR)f(T3U*IU~n8QSOGiCac|%HdUo~ zBCaaoP_pJ|Py#Y9o=9Ch4@PN-7!ugBU_5aI6|!STP=P0o6ZZ>v_P^NWJpiGnT+q04 z^oXl-k2~?*b89W9bqNc9FLUm&s;0v{F+aTAOZHT`D5|sP0sYpX= zvTE>syKGzF_V`)01Adn6h@WLU;b+;-_*u3Kenu&F0Vez`n~;qMZi}z3wy-^PpQqX= z=ZQEGCwT7|Th6#)>FNF>b?=_3qaBe}TUC@wiK(&+*En)L&cDvAayQCPrsE4Y&o%>Y zfj>Rl5`TKO75?;WYy9ciHu%#?Hy${Sr|E>oWp`$G@P)hZ@5^q--I3jvhwdiszU)@q zZNPi+@5$~4o`b6b-h+P&@waA^d8*28CVWeFE>Bh2O@wdGe$P`?b|c}Nvh#SV%BB#$ zF*~29s_X*%s_a7is_Y{Cs_bI?s_YW{s_ao}G(CHmUU>pIoq9b?=w9H4#66sCg#U21 zG5*8ZCio9$o8muAx=pi(@bAq|$4vn~gntJ96yTKXhU_$APS4Kd=?35p+4b33_`>V6 z>#|dMds=o1@YL*V;;sW;n_UCE4*z80Ps#S-=^EfQ+11%e#GIV%%hT1_e)z(xvMYgC z0YP;y7^cwYs#n_|EI@B6f5*(<}XTY{gme&gja99dpj{?nYLo=-N@4m2yR8S@Olo z8zFfZE{U&AB8l}wXd?UkmSW$)%sbJ(6m?= z*9i9S{Oj^_`uFG7McKNRfLi01TG4ASWnYO4T1L5VQ{1tJ?w;0K#r@P$Vx^?YBCNG_ zR%hpG-CQJo~}9UUDqdJ%_7d1_OJQR-7;E67Crmp zI3H~y#=1|cu9uasm*RXOS+aN3C5QvAoVAAy>sWVOyCM_2Jyk}I)YX@@5i{zf@!D93 z6Sk!%T02Ipo$?#;RIC^GZ8=*)sl6@hjRNs2(_63jmFI+ea(JAFZJVjtR2yWCEN7fA z5aqOlwsMryJ;7yJb#-C;FEh@;Sd%&dq7}+?5#5$JOpxTasRgYFHKZ|qB0s7s%K?a!v%{+%ixx# zB|Uw)Ev^P=pSu&gFZdxgh)=?P@Ze&XP;R^pZW*9^pQS_62j?$mDKSIJQAd^RMR7>l zWJ^dN95;?TN0MV|nY@?Vz`tvmvMkR1n^JbQPSH~KlvK^}tz7P>>Av|ZMf@T456S1e zbYJ`tzlu8(yrC_uY_$Ol&6D+VCM`4+(rV>@_GdA^#X9jY=5(>KxNSn5)J7{-`?kK= z;Ye1pBVBS_tGn0Y!JI=|=(an3H^OY0L{ZP z3N3S_C~U<2o$>Z}oz1f)l=67Cv?Z7SuphK+mgdCBa)xr8d3TD~*1r9GX;`3yD91`y>Z=nZ{Q7=}CF|peqxVgYB^9&r0?*+dQGq60heeUca$Kh9;9UQ4* zg0n-+QbEDRBYEeT?X7dMuSY5_Z)n}Dv)qZikzAssom+obj8ALg$dRuu9og1?LG>+0 zNQ^3L9b>Yz4NJ$Y=dpSxn6rWOuM6LDPH>m7<#%Qf)4TFTXNz*2l-Zd07 z$OAevi0{>WSA33JJ-y??`^uW&YeAu$xhXO7Jj%+whrzvHVwSC>EI-z9AuIP}U2!{h zMcN1Ar*u)dQU;72ySBW&;(7Qzh;`q;xGz_ve5wy`q@G%ig&kQ~i%CPJt)880AG?m! zE=sB@o&7PYEq*wYOY^0R)=6p~Czwf5oF|l@R`4J5fz(JoB(#3g=jbUZw%BP8Ny8m$ z1=ib-wt%@yfu+N8A%zA_94a*XQgA7`^jykbr+KWOkFCh5$T7xBP`1!!1|=>hZO~nF zs2g*Z)sl&ot}rdDB{SDjnjMrmY7^tn+>5-V_|7u_IhrkA1l~BJU5UiL54jQd_6EHZ z3kqr(T$Z>b{)uVQR_SC<`c5pZI}J@qy}BJKvsf;rmV$`)juvUUy%LsaS{G^cCeAp< zp(@;gev zY`wVAN)Az5Mdu^wMMyWK>(V{T>v!yJDX3#Rq)K5EP{&_Lsh#6(QOhS!>er>xu8u90 zRN5KB(#n^IoLstXO{%Mlu_PXp;@1x;s(f~|MWmHJ|1gy)f?gN2TVLuNbos~Vy>r=r zYHwjt7t1Qm3(iN_m$C+xaMpA+<32oBzG9G^ZX=xBSn##IdDd!Kdu1({wO!V7S({~T zm$h8(K}g%>pKG}sTzWynrR4HHLA|Bb-eKfC0K#vJ_YmG%cuj zfe*o%1Q%eh#3&FO3!Eu9@!$x=($X~MZN9}f;;C2xSmQ#%W{nHENXXx;cb#<3HCxn4 z+u1^zryNNhU5Ti5D%LC3v5?kin=9|_h>SW$?Tc{KM4mb768xC8u&u07jKgS?()!Mu z#&o9kJEip&Q-fN?To~(QF*(i*uzi(USZ{GW&J+-n#b0;2D}57x#c?rNEEdP*U!?Zp zwNe%-ym&2ls3dF_;ahQBj#Cp4v>5!yBT9Di5bF6eSU zC-fWOZs>$RC$wR%Y2A>gJqYiCPIyDyj=(Q?zaegS^nPCu+8DSIdcQy6Z<2k-S2rQF zG4LP6ZA#20Xav6_v^j7yG@{=T+7h@0IwxV&}TO7^Wy6A>C0B%6+I%tcx2X4>vI%t8nL+`#Vp|ybO<0s&& z^E!ZY-zMaG`tkTfk-jYl^vtxOxaEPKlQtB$B5(-rC*>NwNl5ArBkV~@lW>E9o_;n7 zw+wJ7Z`6@b0x$oP%>mX+WvMBldP$nqG}jbP1P&w30LpRz@BnJmgj8jzNy^gqgcE)f zewot!XnDUwANL)tc0X<_;8y67@5gNe+y)Kuy}Z2-_&xsIT0&`uHwpJ+bg5DC#%XOG zl&AK_xf<~HV5wJe>a1(qCdn17yL{y;%9Gl{@^mn1mDCo}``Uc`dM~kZ-10O49rpK> z<1XNxS!42OlIo{J&^6X4hw{`Qm8aV5b!uNfy@6jpy+-);tb)3J5B#2AR;0VoayKMx zZT11JbO`W}>^0zUo<0PA0Mu6D!`z$|N-pt;>e=B>FU%s8amBWVQa1MISigXS+ z-ji$0?*LY$yU~JHq|38sv-h*-fPc(B0)E8P^E|(wy@&rk`qGM|*0fQoNS6RFMK9in z&>#5jhrkc{-5+ubia!u~HhY2Jy$gIE|3&=19ES|`%DW1qr)Ok94C3`u0nsl!KpTd8J=b6B#@gKyWnd@rD0mtymsrf$hso0yW zN_chrso12f4jd1zPsObP9LLiG_)nm3egLTDz#Ui}Oa|VJRlxaJ3Y^c=O+1~CHNo$R zy9IYMI`he-yMi~9u^>2?H#g#L!Fu3aLKo387o*+RnqUggZ3!-GCKqSe2e(8;-$|9IfZ=-#hE3x7gx4{##z z1T^s1qKiK%w+%QBcoKT>)5zgbEDTNqo`t2rqqx(7)2Q#Gyqktr`z%6_VRdj8HZo@t znt?UKndrNZ#D5$&15NsogsO6VeHD88qX{34RX`Q)Sm3d|slqbgcfcb_UB%arV^*pn zT$9@s)a3RPH9SveHjz^b%a+h$xjWifNxKv|DD@XwohW^ECaU3G6KIGMrbej>r)|bX zv}ILpCn5jUI5kQ&*df&BRt&XZ#Z1C8!MIx7JHU6cw}Fd8vz8$@b;8c{a=^hy_^cFA z&1y(yW&4iCtpe`b{*H(C(7dksXj_ArLPn~--L*?0FAv@*G%C*YvF?%wh!vN!y!??8 zl&<8cU7mN(%D*p#-6y+I=>jvxw zO59Om$wOYSAMI-!h|QjW z=Sf@cXiL291XO0I1*W^(A?g32r-Ztyb$QoKnU7wl*B?zu(l=1fBt^4qL0p(8R6Xi~|aETq} z+OfyoaB}Qot*dJ#qjAH7@;LcEamCs?io!a@T81TpnD1)OHMNq~(1*(>$}v0A#6Yph znL0*~Smt`$(Hb>1_u$2a*1c4IA}qYl=m?wxT9iZ6aw zSGOPjc2Sz5Eu$soZQK6~?K5{BZGjk7N>QDq!dAq!ZCH?ayMprH!ct0mP33r6D>=){ zZ)&Zk6im&dr_yPWCs(M&pL3MW$Oov=wX-UD+g?2Ld zy23t6-M8Fnq4l;5VUHR1ZrZM@HMS&5Tjl#Kh2NEyI3xRYEezx9>c5@Goxv@GbGI{n zeAhB)%jp*_L(vY!%{yw_EkoS76QeKMR_Vt;et|Z#smS-vZ_I_91RD zpf*#Jh&co(?{_G05>O6sZ{808DnmGom_v~;?M>LTuMUGB+>7wxJROG2XfK|RAbdD* z6n@`an$(v!{a7`PBGwb~k7O-164)n~IQ1b-U%1tySX+5c{!y&EMi8z>KJ^>mZ%9>* z>jQT?f_F7YuXY3OMr|R|6IYAVn&c!x-Sbsqhg??UxwxK=>$&lslwcc^Wcus$N+|lr|qem2U{=?b@6iQkqOWtXmdT;0f} zt`2lXqs)B`peuYi$~A%Ba^QMxEueBQrKf8H-G}0eZk-$|r)!B@2N~YRgf_%i_PSvX zH^4t1Iof)_3-B+*T>#t^|2$&H=JJB|av8x`;8=EbT*TW8f$joOMzB6Ilg)U(7^&Z8 zNDek2_sP6jAGkhGmk@t3&>a)!5Z4NM%N9Ieill1`*6rsIa~a`Ff$pTZ9C#Vf{S>b4 zTOm!@n&&Gr_g1tfPC2scde`%jaa4XTFsoob3-H} zr$7x{HMmA@&CZqUShu^6n_qSY+MD`}$?Sc&DrkwJ$ zL2A1rZ+F5?L3Vp1@7(=jcnVLhL*13@n%nh;vUOJ=agL61JXibfep3UZcEU4uTz_f9 zueGUV(au`Uq*qo@7lRgK{bdHc_DsOO(a0ZDpNW!kw?*w($a!|QK={yyh4r!^j z;8N`Pu3z-KO7VZ{yP8r6a9aY!{|o8&t$|zfPD$JrKu5| x??ug!sutc$^%9f3RY z&hh0~a|~VrzU=_qfp?CtO@Z#yxs>=z^6|9^(EU4?QJU?6+w;zmwK34$J>|q-26WWf z@7pn+$_YEh+yitb(6P25qpF;D8}PJYKGrs1bd?jkem-8-Cr+8Y<7F&veJF?{Xg%Cm zD9R~>*3Cyv{d`o`&qt-$brtmK7T&FskCe56QZXfzYXPNhj+9aP2y!;LfjPsGvL^A; z!I62`kusVz-qGTS9-WWJRq~O(3NfRhyw^aP$AEFyKxOL_S`8?@txw2N>o4aXk=29^;ThCdvfPlUXiWEgXdV{r&>D6@_yB6;)85XO^ZQa;1`iln)NaVs+x zl`tp`3vH}tN@+W=G}zw~*phVWXPd$ec!sLBG)Q*M<(z_h zr{o+4GVi&A>InS9;c3)EErlD%Jbwh-g1WvV;B3@VEs0x-*T+XgJHzY@)e)1Tg65#&u z7;-@J8@+N4L0#st@HHn9+b`!gdgq*gGN$9;Xig-yZ_W=WZ#o|S{oXI?o3!}FGsfnaRVsduK8Hsf$;V`?SL*}XZ%^D*%`PSu@j&J1E4^&2s@(< zfbKYljK?|8&Ejcm-VA^~Z4KOtQN1m2Tb?#2ZUEG38$#ZUv=neDez6&Go1-=7pCfh+OUpA>_EOOtjWc?e&_A4q6vM(Q%WbJo5S?0AjXe(1wq z0}kZfgVga=;H$(b-50*jyBqk$ooF*2-p8W2OjQS?PCcJZHaw9s8 z$BCbT>jAxNMvQaqO}X}?2h_AV;hsFHb8pVG8j_w+-WG&=@uXh91<#KV?u8zuCE?yY zsk?85{mx@PYe(p1W}L~uwz+0(GAUlhwPi*-7ylfb+N^dwT}H~6nZw%g?2gBm znbX?w?98S{&wZu)@aARaz;-l1D{6Y*Pfi7g0{bqQ}gHXtB7$=%QI*Zs|h^= zP1zGla{}~jPv(Hwup53?LS2}v-RpWK?kZ-)tC=CM zWk$a`*CZwti&A*RKH(|I~jN~ZC;5x8tDFBci!#}bnkm5?gXGadn@@rjS}`_)b;0ob7)}y zoY(3PJ=%h>JW_vX%_cziulI-IYygxm=?|@07w8JCKNM$8pqeTv`eM|6A24kuShNrD zQ2d!-&Y{4I@MnTC7Xc^Y&je>C0#Cu837(t+JO+OzSaA$+5B!<*>mI-p@n_OgCjzg+ zpGiMm1-vfrFLzSUf{wig9D+X!S~mnZ0)G}Xa0GA_{8`Y(Re-DG&w^&I4qO|57ChYA zz_IwVps{0t8{yA_FWm^Z8U8G0gw23k;m=|Q*$Oxw|8C}mdviKp4s|c**_lGEv$TFH z?k>i<^T&h0hqGIf+{(?#74^-8Z%MbNTTGmXE-_9?(W;Z0)&^M4~O1dLC4({N6x18eK57ffq`lMdy zdQ#qy?o3)h-$~l)Y)*QJw{y}|$~-4I+ufCFps#n4swTTGsV};Y-(H{YPIsl+>{?>3 zOOH{n2cfff6XQPdImvb4wdo#GbDqKJp#j;w#CccOHRWPGOs+6rYC2bM^dwFdU_bx6#og{O^4o;Gv_qm8+QTk0w8#-9*mJ!2)~+MN%ByyBsr#8N$z7-dKLd=a(y_xObvPyekeUi_+k8)3H2eSH@|r; z%}R@Bui=)+W+rF0naO!OM4lN?@7uP1jOzMix-dYxY^k-e1USY9H{%=CP2XCYO6 zI(vb%OJy(e_NDY~nuGr>?!`0{I{7T4>}C8}(B2n;ui?MR9Q_LLt$eP24{MZnu>yG= z8xb||T8g}bRo4etm3)FF)(6-~eT==y7uZOBoPCo%BlJ!Bf*9?$J_mlr^H+pE!{+NN z!u1J%4UaV&OQQPZ_5tuyep{a$J_mlyoBF)_2KWx|>yzSB;K#iGmiXDgFUjXyLSJG{ zR-cpuspV2|W>~AGdc=K8_?z_S^oCEsZ_|swKjS}`C0xKyRh| zAi3iCAj$82kmUD1AmxYYDbg;JJ%w8~d!IBPr1#TJa60d&o8dIxPq)BVJe{<>dYZJ$ zW~(Imm@&zf+L*Ko{%B%WNu!gpkyX=;@I0%gG5DjBvXoK8k4~$lRnwi>NMc5%k;#?a z>crg%^jwV*#EeWMlJcB2((36Bp!P1qi5ZcGCnY~?rZv*-*)YPx)3BsOXf2*^1Fng` zc3Lal2GlNPC~t?Qq3KE}?R%8}{q$bC6)xzR^mJM-TPLl}(>l2K(h$-NO;<2m4M~G| zzg)I%T8Gpt6E`F&uUa_`#$P!N-9P17cXFTg)5+c0ea+$e1bWTl_Z&NfKv1JA-gCtE*_ z1)hyRIU7q!Cui$XR=KdT=~>D%ylKVXwfBEc0!Y8E@lk((K(#gb} zf*TH(cP=SUApS(4eEF&Alr$WutoL|gPDrPvQ`3m-G~CGSIAV@Z$0a%N(|I!zs0_f< zPTo!D;oeEdCVBW{NpoB}Bb}Z`WoO_vz&w>CCiB zb{1|-b~I^@NpGjqiT@qpqtn^EACsMpTQxg}C+{UZ2RJ#Mle`ahat_Z;lhYd6@6)-! zbJObZ1?Q#Tr!|RL18(E=?CrExc78e!cpkBvWk;qX(%RVt>3rb%#46c2B5j@>o(=;Z zkq%Frl191CQRzs+ze`7@EwaPXWx&nxHzCHA(sPt?6WacFX`SrCbOG=Ja@-)hG+mN5 z$SzBl0=K|NrpvqavrE#&DVN5kjrr{+%>Ngq3)6bMU6+~v;&f3OONuz_-&|X-i@@gco?8(AL1MSV_)E&!=q&Zw*KDR(dlj_jxOQnPw1M zgR4zFQf(TSb;lo<&F0NEz@Djhnw@I!XXoj95$>LP;l^dXh^ulc4yhAQ$m4kGfVE(!JZx+Op2lTW_`>$sCsyGaq)Pm8Sv9_}YigIO zah0iCYMZ*GHo$Ia$+UQC1#FdCr^l(wm+33~FVpgAv9ttmIs8G`KQ5c<0SBd%sr{S4 zH`5=1e@uT$CuM(1UjR?WpO8Jy?O!6Av@>C?1RI)*em5x;ZV)!1xT-tU_2nB-1( zx=D)-y!YJ^G@0ByxBS1j`;1<9!VL+ z9=zEp+cwFSZ%h1kX;0qlnC*qz0k|jr1m13&j(~HYkjCRrNPDNf(hl&&djt33X%E&6 zM`YvE;ka?A48O~o0h^^3X;0oON!mB#tumPr$e%>(w4wU`1=y0 zUhTkiKvK`PC2-4hXksnIyZy3*(t%06+@Zij)1Za7-FW87T1vVnw6kFS->2FzI zYV>vLOH8BGpK#yQkEce!MyYWcpY_XOMvINlT7nhh$>ZVPsm%|^u1$>qNa`>j#fG_c14nOrW@Hzg=;lEx0 zKFxnQ9Atfd{SKi9aF5zLODD!NCad{cH%8(3tPSIFeAb##I6hmF@i;zPg7G&#Tb?mE zJ{!cy8=uu<435XXx(qmwF*QE3MiVIY*U*Q5(2BFck?(-b_@B)PXbxPO|JjVfrGWm; zW*pZCF3bOH#`ki-#rU5MC0HETivQWrhPJ>i{LhARbOpBKe>T*mJ+Per+0dam>6`Qs zobg9+gmcm-aE5cz`*4bL(uZ)2bJE*zkaNu{EHuyK9`_zE27oHPs0b542@ zPIOM12}e37Jq6F2B0kwp7z1AMgGKcQthTuV6lN44oqv*HB4)mRgFmzH;DInUPOx@R@S)UuXy#`e~&F~Bjz zb|c2~WJVL}3MZib=O{wn;WdhN=14-FGr0+GKpn}N(_6hd0<|#>ZLpeNHN&1EqK?@6 zn}z_@7<=cc=Sq6psy98Y%(~HgcDxT|C7^o(ytP$}dT%9b1BbIBt+E0kZ+TsTR&k$! zx0@{wTt06xZ-Q+>yb?A!VsA-X1}N{WJl__RGO22EJoUcp2?!J0wg1PJapWqX; zF_Al|$JcdQefVr^x@R-?Zz|37v_p5%%lj1Ej(gRA$meMLCodDcjX7x<7-w6`;b{L7 zJCn63tZOT6R_b={28ZK(t%agi{jq~y>p?9S)%(S1i=O5ZdlV}1l`8k)>&ih}6LP1l zXTm5U?#0)Yk}3)A#n+UfY8%iKzCew&mH<8Yn%eGWJl6ufC0rW-_dUc8*&2N9#%d^o zJ7qly$I}cv=fKl)Ji)-T4Xm^08@T7j({dto=xEI8sgk5Ete|~_C?_DS2&`C&sH9?XpaQHLMH1HWH~0hU?3Py;c4 zJSfEg`@T5ePz(_ddj1F=lwyFr-ZaMyv7t7{fNH)jPKXE9zZee+3=j{*0MAqM^rRod zgV--`+e!y*XQ^SdYS2N)*ss&JmPC%$^^TN5I_16{vD4lcU&NZg5V0lF$3C$5l~_@F zCcyl$qO=zCmfu{pXsg4J*!N>8iuKR@aYM|Ay-QLD@ximBV!u*f+RR<`b7O^cVQxy{ zZu+015rH8=DcnszH*QE5=B5;$bz;v63+fQ3Z`IL=Qrsx8Lfnu#c)pfc<+ACs3DL#0vfjuFnNGAe23_G`I(^WTfYwKtU ze`>{Rzt3;xwtP}C_ZYhNRj=tDP|vbdui24RS|zZc587sX!j~sgsv~r^7(k1~F7Gz@ ztyr=31-8cbY|}o#R`@M)%yG8pLyI}PI9v3lR8ke^iC&aN%#l9yq%6)T&J#T-o0LQ< z(VhBxC$M)%)==+8ITUkj1)=mr3MzD7vCo9!kF6jSTWoouvy11l2M)MvP#l<>J}m4U zY~FG$G5glx!2HLT`wtV}bjPP9bQaJ$-_vaD`}+SZTb5N<*HH@TMNi%&*77|mv+MdY zoLJ&2z8=n*##MZMob<)#F zdSUUrFI>ep!7WZ74ItDEXy3V_Zw|CiUD3Ay+Sjh-#fZQGal{pUs~kh*E#x$$B%a72 zRap&Rt8;No*-Ja1c&Id{5-43#_EH5DSCz)J&!sNy343m@QkM=mu~~UbN1XSID}m{R zbKkS_7G*M>zzQWWU2xi`D0S(YOI^AW?~dt}d9DVk#aH%H1FQxrb*Tlan^z9g9jFzQ z@|Nzo1f~b!?tI%{j>IV$@|W6xRZ|Y_1xDaTQUh~YCI5Zg=5Fb{{ax#W;kXghcolN9 zl*1VtV+cD^wDQ!JVJL3cKQY76qy?zf4MT9slR6UW1(uWnd*ZK5+z{Gb8sMlbqc&0j zcO|S$--v(G{Cd<(y08*%Fu3E$_RJvf=cyt#?jK(Pe?_p#^Mo4E-=1$LR|gW-hOQa$VyqU9&4FU9`&z`-f#|>7A+Z_x z_RO_my?|or7PvmZ&GEGr>;u%g%sm1^@qBB3wHeS-Z9`l?pkrYiaauEO#;=iEQ{VBt z>5nwnk*s~>0H7ml0?xZ6Hs=f5@{7%}ZrOq_Xf3$~x))F5aA&}lXeO2**B$aY?nvx5 zXfn3P--)=bfm`!y?ZU?ccf{W%?|pS8;|WjTX%|8hu6|C-3yw8GXf` zq|`P^s12;QCa@z~IAMpp^_P~y7cYb{!?{`PzZ~$))&T;i%LVFY5 zn;2nv!PP=1o zi#Q4$-!kNVay~9jA@&%wfhXZ>5qK={Wc*VJoq#U&7;^OvjAPIdI}@DFcNzlSSEOCs zacJyMCFPm86M<*opGD{-;7R;WUHysZ<(DPbv-1&p4zZ`9mp==CGO?!u&&EHO*wcaM z;QyXbMXrHY13sBF=i#&n(7ykC+*!c$c=G0uv#=tN8eE7wJG+SIbAT7%U(EAl;Dz{? z5PL50B7DwMfnr?B7b<}64)SIStu-f;>t+06GWHMdf6!+0JZvPiLh#Ox^Rc7Q()P-n zYF$ar7ZVE3X z^|;G{T4rcFcNrEZ*At$?7q7$~xT~>Wxsmvrao1o4axGL&n-;^` zo7_r1*8^`N<*m5uuqnBfnA>qT0B^&;gZ!rewS%~mxEp{skn3H<-UPe@|8Aad2HuH( zPfkhi$tmVNe5VO9?jQ1I81H|%i7$8~%x%ECc=A-B+puuEonPNi=yss@$xP*ocL24p zn95wT61I8wlV%#RcLAs3KgjdlKrOQ$!4EPvd^Q0f4 zHq+1JnggA4ULf_8z-RHb&V35_0=|~FPXk}XpUGD|jpu3ddzm=T>hWZrS8&gw+tkMP zRo*=Zd>MaMKJU%S=R+;mpC{&d;$9>53&2Xd4CAkG88zJT>r@PTfn!-LwmC~uuglEUw?#q5BMQZAM@rN;5+2*DQCiW`R=E@ ze-GQW_sH9m$KJz6?S1mlp6z{X-9F^~7jRC)fS&234ciC656JIJ;ywa?#P4Pk_ebC# z$@?qZC%{k0|108*kwg6|=TpAs7oVbU{*0Xdj5VC$PkH(V|8p$chLh{J@NL6^?gE%Y z?4NRbxz9Oc=L>%Q7v6kV5^7Ie#El2BYSgn5p^vB;}$ug2JHB9a^sK8$3JK%SGsS)-p-=pXMo^LcJ|1w|& zev>2*=&4@p@k1BRo+94WBfc?yQ+}6#iSIPUm7@c13T%#R0BnZeBFQPY;EN5>`d9Ef z?L-;?8}QVM_YHv!$*DDQjnT<#BhZE?!%Y&WR`aeYy75-{?eLodo04}Wt~szBeidJ7 z0hI4(6Y04|O%>`8u0B=@*1!B=|cHcGvK zy~uAV-t-3c=GOy>>jUgVeoNyEU7;+^cRB+5;V(nF0l=m3m&G3d9Kd(9Yg!z*EdC(A zwFJ;T$;%VFBsLdIlAqR3i({KOh;OcdTMCQD<%wSjw={6+)G1pD*BQ7Xaf8W!S>RIm zgZaf$SV|5iW(aOM;L7+z`N|-myL*NayL=kPo8_?L9K}aT?KzN zel-d>hOe!L8;)h^s=QqtHv(%?*OF`Sg|5I6_*$Nhz?yV5ezhiUG&ZGc0<|p_jwaW2 zlDm}F;ag*{_FS8ob#bc#SLN61@qP?&40((tZgs3M$L4U2)D8Q~)%nH-yjv5v9=>*) zYXaBg3tDdq*CN-A`N}##cTH}>^Sao2ZiK%n`L74u7=JV3)&;K17dFSO4_u$GY>unW ztx3mXX}TU?*n(fIhn>>~d|^x6M!+q2()MX1;6~)MHF<6dTpLT%t&=-9x8cnuSY>TZ z{CGl}0k^@Qkg8dEPvC3Sz|HWr?%FJEOWI9=o09i-xGjO(;%`rAE8uqcJCO6%KzC#8 zklX{dL-O{)9Z9iG+L2USVY#+7IqgKMt$|}nu~YI^!ktMm9-Fou@pnnC{k3-+Pj~`P zyAYayJ=-|GxhuaI2i%r#?#gd>0=gGuH=ei0!fjXl-IBY|c1zku?#A0)v2fd-ytRPa z9=H*)TD|QEbbsyc#QX*ew~YyD`?jOjZhU`_`;Xr7W+r8T3O6-N-;2EQ$o zNg3@J+$zk?!-;K;--d5`0$UGgL|DnRX6$z2xfR@kC%1MctbL64Ep_I(B~NOox)4^5 z(~|Mmh36JLwPe-qT~A7IS}<0+^4y#!<&&O#rZlHHxYmtlZ-VLzKe!Sx&EQs*@l+Gz zy*>TlgI6TBDcrO29#{9Zyy*vDtmLN&PCFvk_)0JPvl3XI*v70KmS-KHysi;WJ)G-( z&&OB#q3o^#r#?y9TH?)OtnfX*ts!rf5-QUxBW4NKfy(q6;NrH5C0O+;uhX`EN!F(I z2r2hdrd&S{E9EQ4Elo~Jf#O^dzouo5=kqCrR3_=EV(Kki=@uHQg-LIoq1`lZCD-QZ zSIpmUY5!B?uf+4;Tb_l@-?6kc7$nZeUes+Ub3%f$G5$EjAgJcQ>w*oNamc8*&U8&aTKyv}RR?qa0;Ja#V)1 z8*nH5J)jG5;;!-)B}RMYeY6+3h74y<`{M$xztC3vL~?z@teJYd-HTKc`4gD5L{8VqkLsw z-YLU57`Pw)A>^tgXDxi?Ii7LrEHjC`l|nS z1?S$pWBJNyeE$gGI{2qC_pAdvf>fuI`Z(Zm{QeB$P68^QQEqcAP`Qs1nG=C0l1_=t z2|y(~N@UIeu8V&TGugUGN6sMaWZYRuO-?86xwx~DqpU}Y-{Z~zo{>val)J zC_y@(FEz}iGv@&(^X5Wg&Ig`}ucYQoBqnDQx|rO451dT8iwP;oxqw;nV%&PUyhf>x z5}!-?!nr`@JDjHrZMlpbD}Wc`U(T=21CGU4s&gr_lM8vL^u~QL?wq}nUn;$E7QPC1 zIZ~2Kh`olq8UruGS5|X1P+5_3nQMSo;9o~NWi^-bPPxsc$W5*!b_(I^fmh*AVGdg# zxIRxel8cg@D@k_~xiSCVrz?{4AUb-DEBCg63vzlBsya;c5-oNGyU8|iKU z-oQI0Iky6*;NQ--rT|?{+(DY#ke4X+zKh=|&$*G-_2^;7g=Vnb2FLc^&AQ;%)L$ zlJhd}-r+Y&Z(im3U4GLNsmbfay@z`TsmU9}DYtnSDTz{_4{&b)-yrrw@^i1@n)n~W zt*r@sonQWulpi2Tc?Vy)jdBzTXUIxEAqOQj?q~c6Us=q@KxI&05^9Ac<&#{d@;Uxjyj70! zDWR|Vy|S9&~~XUxyZWj=HGeQTsC%7^}f`xYt7m%L-2 z26-x}`4TzG*M$B~ex8m$0^c+8mA)wd`3E`18To%hzT$cP-|_BS;5WScK9?zdPmb8_ zrN0oH(i~z_Qa)6clm;oINk~wX2GvU=$+sRUGh&p<)KCAQ1ocT-hU`SikdmDG$V!y` zG{|K>4G3}e64DvvIZAmdc-sK!NEyBo8Ko>rT^f^XMtBt8P^!}qd5SV2PgnQM__AEG z(g3LrG8K4!+9(T~jUTyQS`gl-?-M>A|ydo6e-@$v2eVDECn= z<8HGW{9e4TL2gn@S|v3-kehTNZ693ETo%&{*qiu%Jcq=lHxd*jMapeDWCM~i_5qZr z3o;Z=Uj}yJ_lx~M_TB<&k0M*!?&_*eh>;M5gt)sa#Dy3^0wE+wlmrRx0Rjo`3^Fsg zy9I(fL4pK#AKcybzpj2Jhj9KmGT(RBS^vM*tasJDtE=nj_vxy7s(0;u?`l5Pv9#NC z0z2^O?$qxL8t2x7>uJMjPraU$Xh-RY)Na!a)Z&fpgzNU=dL6K;bmJ3RZ+c)y=}7H9 zd{XO8FV6I(elM^aHMHUM0ec|(mo}dPlvb=a{jj8TE^R8^k%PEOcThXddR(C|*q6H6 za0Y+_!jNn|65oaEX}!_bqdi9(PCs%(Lh1YFimV)|IRJ}^_MxF9;$OLLf6z$QVdREj zO&LUP1T}|(TE9nf6)ib~O1q0zqfyjj7d}2;vEGa{*27}skw99Bm8IByw zHHKpy;i{mP9WWaK_G0Bap0i`Iqi8RhfR$$5OdHKeY$zKbCz2Zr%-zva#OIBOrx$goUO2qOs3up{?lZv zAlp(hle7)?k!c*w;@mVWC0dE*P-g~KlBvi!e5&+}|FPKB-M+KDZrHTg`T*5vNdvf*di5uLB++O^*orn+ICA7@;A-@;Vfc^PT`|#PFi2yW$ zabM2v4eo~AkCJ_f^y^RU{exc4g0n|90YaIw0r+7HIL%~BsJ0hfIWgHP?WgNlT!- ztdAr4ZwC=U-JKZaBgq{`O!i`G9Yw7U#9$wcJesR72DSDa&6y71V&pMFJI^se+s-k3 zatS3zB8~d)NXZi9u|W&Zu|XTou|X!uvHag7DL;lY$5Q_o^6q1$B`1Ovi${eW?3y&E z%osS=jB@d`gt$|^>k!{xriG}&({*ic4I|}bhgIU{w9gnlC#%bMw)x2_e6I5UgRcTZIlkFj=dsTbbo@>d&urYBbMgTzZ`kciD~=`KkLOrl z)~91RZpu-AuoI&&pJ$U`>+mV9*-do-_SfQOe7!MXJfnqYc-2#a#xmJ}nQbU(O745ie0!n{^)-=EQ(|J@Qfh~!nZW2@yg=exAx z%s`U+$!YgiQ)|Y3XoVg?8pu@!Q$B>`eQSB{Px8%ELnx6!*o2k~obg>8{rN_63x|;! z)5d{PM}A+vyZaXpC#^%D*-C~jG%lZsS!P&C~>{gi2F($ zYn65+=|^zo;g~8Y@psdMF*TYJeX|W{9cOlbTRj*NV<<7oRF+H&iY{PMNa$P{Vg~l-GOQ=LQw4sJpdKs;97Hg1m2PAizbFU%o{_+}YQ)0xd zoXHBeSzmzO0-2F(lH38P7IIYCU$Q^(0&--Ouzfe0RPl>6<2%}GvOh=Dg7%ACPkEoR zL*;lHg)B2v-lu&bFSJeBcd|b>poi?Awq>uirM%)1k@sou$o_21H?`kne^&e=>+tRE zBiWx7k4T00>3eGIG1;GbMC>m|S>;{p72an@dP7F2e9!e5Q-jFK`;_77^U_|E{V5~V zp6X0*_*;|jIS?FJ_L{Sf{UwuJE@(B5WqisAmGP+u$ltR4CF{7-U-CfLVzl||t}v2i zgw|o4^#$dG%KMbtDKAv6r#K+nZ&9}Y7W6?I ztorD`pgp){*_&IE_w91_<1~`*n6n3`lYG;hbAY=^w!vZ_=#8y8>$~Ud$F0j=+lI4S zVaeBjuq~gT3QpyC26^AErvE_JXN4^)d()X_7N2R0o!@?(&Doh?;EJqHP(2IsPW3&=^W1~n{^f{WSdLcx0DEEM*Y_ZQR8K=kYUmT_1iELSJJEK;7qAbx zgZRAuhJ85J)8LL9?nHQSIsOkRNBtpOc_G$*{TFgV^*VH-#$rC-2|SpQuh&6tr`*&- zLHC!Hn|c^1pK}rNaO!oz3*c`>mZZAA*S33?oj$=Ir`Xr9$IwzOEVrb12o*P+^N+h%cZf*S(Y^XH?I@Wz=+^%L|aQ zMD;*ih`fTc@-{DKrn-tx$P=xJysDhN3h)MaB=B@xC~kGG+av!*`oRw zUq6L>PkjtN@opt81DEj$`J?&{^bp)ex(>XKPu@=H_2Bh<@(#}GU2q1L2ig26Ra=!4YJ-=Obd1?hgQ_3lgf5Vd8C`doOJ8ojXaKR~TVxI)F> zumV4TehHbO%S%iDgW!GCUdiY0!~XC7g{!;{vPs<=WhGvN$0*m6AaC4+DE&3RK0euFtMfEqVMCxhK>+lrvSh?C(xdP^wO%8=j0Zq(#p@(J z3V!kpO7$qX8=*{3y$SA1_$F6)4SbFBdK%uq#{UZEWPrL;;TuT30dHXc_X++^`DB+F z+K2q>$al-<{kzn8oBUeHcgfYo8}K?c^fbsBeVyZqr{M#x`?u25@Bvttx*w8ch`xi) zpnsqqSQq(msbPG=r{BZg?+%Hdkb4Jj!29I%G<*u`SNNQo?r6Ab=R|p;Y9?RsnSP}= zpgvfS8egKv$PN9Z^f!D&4LuE&-4*pI_#WGDz^}3Q*QfrsB)truQR+^K{XsRQ@6nLz zgY`M*?uret_Um1c0jk$wmA~N!^72l90`)pHpzhBky$;_{`U|xOfchAIDYdU(N`38D zG_wZy7aCCSS5iZ~3_nmqW~knTA2`l}{)Pa`=WIx=JowgM{SbN}exrU2zo7l4pe~rG zlb4yldwPeR4VP>WoBKBK3hHdkvvV$Yr6x~#$9Jq>ynpB zINJc9KwYF>hl;0RZLIsUQX5md9$1g#Ce&lq71Yny<bZD0R^EYg;seAG5z zYwZ8c$hGBKdL3FI+mYJh0dQ^6p4vmf*2oTAxfR%oS{=ehtVCpt>W64e?M_^!HQ1Wt z&V0TNsCPoHXlJk;Qs2X{tSf1F){T-bcn0JybmMCJ7v!eO7B>QnvI+WTYv!SF>nZ5_Pq?>Xrd86_?WhBTbmD{-Ip>WvtO zhe12ZgrMbQLeR1@A!v7@oHG--o{ZAX_#d!6;Y!Ia)k~qrLjT0LOor(M`~zBUCIziK zvQEc=?xjjOQXj^K_!GvFa~D%~vnIb0zJ-m-`~*D8a!&PLRQwhb$+#B7rwmk56b z>$OdSyroU}CKE%87TN^WXw?e;(R)|aQ>vg($v|^gF!#>*_wRf0x%c~9UtAZt>h#UC zIV(8dN^6{OUC{Yn8&w86XO9KP(Q3}G#-~=IRmakr&Sx;cDIHzfNMuNkVH`MT7^^y( zapp{5tg5zwCgfb{8?#!m3K+L)lyg%H*48F9kX5R2s#-yeSRKSOLR-iHk`bC(IQo+Y@SM|L)|a(ad$2vn zeaP$i(dN+`)Z?Ue#CHkkgVKW1i*-Y1w7M?je7l4;a;-1El~y~BmYZ?qcW|7vq4oTR zjx_BWe)G!yYg$JtyRB&@@lG9|+E84VJKBw)b-%TdWy|=RZAxoZ+RZ)JDlO@pv&x#~ z%qFL_Vk6ON<;+=mOP4#Z*CC;_7&zg1*``TxgRu0F2RuJtQjtZ?D+B6(9 zKFzgbIHJ@Uv|Xs>X~EEH;n-92(MI9OREyIVp`Aj_(+E{<8EVK{E*#Zr@>(|>=h`|d zvDw;3Dt0a-WVq8wG0Ht3*OKCud(7{cNw zvd6SX*;n>hJ&x@wdrTXYePxdsZ){)LV_KQ)D|<})l6_^5X;ZSV>@j!Ev#;#2njG6# z_LzI;**o@_arN$lr)5%0x4q|^ShN7!d)no-{c2D1oz3o-XHVHK zw?s#aJ19Cf97XP|=$LW8MP~r#19{|HQ!93IXAAdd>{iYp?)l(+;@ncb9Ldf)&Ni!N zBS*3`Qm=B3ss%b8g+#g9S%b z$+;(16{Nk`gg$eIv@e^`Th5|-!J2{9IP!g7&C4G3?OpD7qBr44O8+qM<0>72Y4$(F6dQHvIRXce^s zz2q`b0xcP6S@|H5mh@P@hVdPN;|3fV@ew$7JlTRoc9v~vi~0;H*XOjOt!#Tbq8v-c zmvjNu!!la58>n99Q=Ql;JnEL4&w2y6Wd#YAtScY3hr%Ud{5i(H>Oeti<5hy0vIE+uGK3x3QMArR`?x+VVcN+k*ZI zZDaSIa`f7wwyrI18`q&-E72T|?$&(PU#-2=nr~&FRrXG_Kil$ueQx^Ol`Ub57UV1Y zaOsCt$5tD0Ul?`n;a~<1L+XzmOnbRwmmblK8O+j=%#fze3)pVgU_#(=W1t25{5@s_V#o%PjtumiGs*|ycowylmI$T2jF zWHgHUy0IdC@$U4abY?lK^yc)zkD~@ZgOZt`BWwoWXF%!Y=?&_k-HsZ)N?%V;yg_R7 z#*_5KyEC8s_T|{wp&UoLpH;^wH0XmOS96W)r{KP;x|$oa(@!vl+=vR`fF~+D0BxO=MDF=awZ@umlEgH z#{4dvZ5wdB1?Z}=0l6t)Bg&kcHwRrS*C)3bW4ROUSpy%_&fr9(`{hjrcjinD)}9kV z<4tOmQ6V+TD2y7|2R5ceJ3$RH6+NF8xxqeYY zc2%QI!>5wRj<6P>BiFS|^S?i_9FHv-k&bR+eJLGMj`PwM#5nS4R*fWEqQakWy)}U& z-wsiY+=k#pM$Qm^5gkcwKE0OvL;=bVi=JBcyZpAz*Fb&@KabEd1z1r?ujMWc0hA@!FIq^_VkO9xVS(0RWD zsVC@@r30xq=+mbI$u(+UuIU>{J25UhA@zNBVnllEzBZj0mmd3@=)}16*vKuP7`$Hq zbVnLTnDJAN)Lp=x89}os^U31;xel@kC5|#P&KEI7=pzr$Hqa0U`K;N8E zgS0v58O|`Jbe3~v&hHcXb9P;Q#`apy*!~CO4&`sjTB}A|_?~!webvfV zsK%YwChzaB8p++{{Z+aTtM4?n1y(WT{LcP{{Y81-zA3a3XwNq9}RH)_jW@*UePkz(bUqdw8LY{S;&uec3oTb94TW}wfh)$iB)Ueyj2eP`9o zSD6KUQv1!^G2U@%5BYu9LDobz;LaP8TNA9soi{9dzhT+?4a?qdNE_6n+?fgfJ@@P$ zp?db4m*1)#=yz^IYF^GYe#=(ncWqPNlXsSp8iMQrK`XZ4D3qo4MRR)2W1n+sT^{@7 zYtD%9*gk7c?|JNeK|8hZu6-s}=NtLr(>GqP1v)kpxjN;jT8q!AXF0~)yHO2S zEweUPR-3EJaV^ld1E@V##)ZA>d!qm6{@3dN#sBO7a`dTn{{Fve@E?7;xJK~qDr*Gq z(fg{$J$R4)TIzBS-lO;Bo3Xt|@5}uly+`k;Hvh%{>;GDl|Kk7kf7PPx{LlZBZTa83 zzyFzj```Ru|KA%U|66T1z8o(T$`LeyygH_%Rjr{WdV-^DB8mMeD60Yb``(ap?eUIB z_0x*RQ625T(Q5p?Z+%n~8B>nM(dFpWlDh`FjiXjeZdG(1N3-@^b?A}hI3EG32|50U zm#F@eqxbmhQ2z;_zZ!KOcRuv@+a4(cRUO4&Pp5Lu=tN$7iN7=1XWC1&J-ENA_7dmE zt|Z^1>B^}a$vFH*rOn>iRd#FhQk!z$N!L2+ zXYxB`g*HdaYDtOfq!wjfO-yS|#ZIGjMk{k~`ceyymK<$1T57cBXlYi@_etrhvtq^3 zcH?tVn~;_v-~Hh#p)Pl?y-4ekHcjVq-}s@W)A?L$la@~BbFEMn8)sMgQyoyNRTuhG zOO@6uZCPpzuDV<;uF?%V(tft2PrVM@r4}XMZ&HsIagAuiRXti$9bPtUefr!do($Lq zi~^sAa$g%VI(#l_L2ksT(SD@m$koAcq*fzYtlEz%`-BcG$B}QC&_=D*TI;mC#b&g( zZ+Tgl{&XeRj`2Ma9EjAWCy{Gh_Pe_@``c2pTbq{6OZ1nQk<=$D`?~wfujqZ1b(C6b zYwp4C?0vZ_z2DaRazA>%zxUOWZ|`^ZzPuy9t#{;ZMk>A!kT9-TW zdwNGrxFf&0BfBwo;&*mbdoO-l@6P?`{mzbOccpip$vM^vsO`_Y(|hRCzT!<>WqDAi zb<_v20kQ)%WY^ov?!&D%=6?OMlifqt--4DB^+*}b+CsF}$#J$-Y!CP1uI$X;>hG;$ zYq?{8tFk3*mrASHTG|a;lr3SqR9eN>ayRZ~W!u<7w#2$++t?nqj{Ej&uWUj~RNBLK za(8yy!*ty}WnrIvL;2du&DW+j?IuNq%SVs|Cq#Yd<$9 z`JL_OW+cC@eXA|17FetN=H81Iz@~ghZC6^gs)6=)W0K!oi?A@uuMKE&g6SGeFJFi_nAJ+oCBj<}c{J#C><4JhQDXRNPEAOJf(tkRMH{t4*H;J}qq1 zE{qFphs~(t%4#qspjgHlH57`F;3&XirYBct6hhbY2hi z8PbXpXIGzlK2_aeyB+1u)uQpk#!EOCSA6E~Xk4@WpT2J+qgNcmzKz56mHLYBmT*UK z-!$fG#Fh3ceO>L{6^U;maQ;$XckSt}$L=%l3bYcH;L6q2sQ;t#I|=`*|F^R84*Yj_ zHTOIG&)x5;JN2Cm-nrW3s{8$C{_m<5meXO2|5xq&pZ(v}+xcDi)rY|j^xc*3k=!xz z2y*Ykggye!pv-D_nmi1SpzP=mNbkcte24P4NlV}l%8~w%Bt!9SO5P$Zh9@YG`Xf?h zKg-4N5|82dWBAs`z+`-rI-ihtS4nsGeS@;aun67V_fyg*+3Otd559r?tmImM#@SEd zT)s~E=ahT~kMcG0-Gh59cMI;i+ztNIURjSIv%Lr9a-;Udy3`f+)Sg+-AiupQXM4b) zk~!an^LxP7e3k2T4l?RHb7uFfSCIGKi~6##q|)=xL;aYJHYYUCF>V_%Vj^x`@#b25VZBS2itM9AnPCG z-1n!BtS$Fe9zaR|a1vMivSf;Xfeo)6HFwI|!YCU^9rxvPN9IA~2ZkLf*CyQtPTHUN z%vU9M{7bBWZ8$d@mRsvEJ8KPpZ4P-Yg)Kv?;6BJ-!Ah6YIhPWxi6db@%_TOxW!Nrr z-@WZ9nG1vbYdDx^lD-8`=4f6fmunt%w&U&bvTv6LclB5re4F>u;9k;8gKynj3e)mM z@D*Bnel`rQ)_guYk9X1kOzCwnFn@-FekNBwgY+HmuK$U1*TdfYiTBr^LCG@mzR}*d za4!qr!|GfHtMfSvJqD{@)*3mo@lyy<)p?6Q|g>x1jVCVM$7rJY`;{3Y@S&|a@l z@-pv99}M5@Mbc1kXcz{*MA?hv=JRIrWxV(PRnm>%jeO!&(ktNw&TY?I(6`6N`T}+5 z^EU5goO_M`zbrf-w7fn~tsOu;5;svMy4TfBL0kV#9M9m5=E#bG{m9F3W0CE_d`wnD1+F=2Gxdc=EM^ zdoS0bTt?{{;gYN>>FjJx%H@>0Cv)v^4LteU1-1m4tM(#ZDd_M0x%Nv1>V4L2Q z$zi=ITPHLI8^a;Jn`=zZ?j~)@+r%?I|2TZ$U&;RpfB11&zgf78TAOBfktT!MtnY$1 zxH)eU|AiV)z%p$Cw&3V=SehI0j_QrcodMI5ou_z%^+uq&&zY2*!8@y`VY5C9Jd-zG z|20hF?bm8df96P3pE{efXYuxFZRV$iKZl8+E39)UIh*%OYZ*T^xT-ppw`otv&ZXp> za2|LrsP+7mpw@K?Z{i-Goe#Hg3vi3?!hun9ceo3nM{+}@lug=c$n){MJ9iMNMuz&o+;&O#$Gx;dcmF4lg!~9NS7M=`uaD@xO3&TZWB;~GC zkK>)^BeH9G-}wmgdXlaQ*M{MgjL3#%SBGoDFiK<-UKOqmLn#@C)^mBdBJ|C!2v>sr zkVCR7!&Tr_)EI(&;L6ZHyEI$|UKTC~FAwrNE(w>00hG({xHw!A*uR|PLD@y&;xH(? zgKss6a#eLim^c4HIvjJN}IFYnDLnH<*7Zs&g1r~Z1dK=0%pH>O3N zDjA@6W}8#T{Xg9$d_u@O=>FsG5qdxPK;{mi?nSdp+$W@F*RKAVk$8|#kUW5Wy7 zf1U`8`LJ%?&wD)hba)0F&$oSoa^pa@V_%6UvU%)1;lAgyz*%8-c${)$QD(F2#iPWY z%nnZzJ`=D{$yOY|n*G4T$7Y41_?)cFzJ0NIN zJ%Eyh?AWmzCA*T^vg1Z=O5LNiE&Fb0Sv`o714El^7fN>KOq*;Gmvl~XMY$x^)X+?Q!H0`?CA)y{=ad5xcoxq(qr&V-us83oFT4Xzf z9YOb}bzQq8G$0)snrGXy&q;I6wqT`rDEne)(Ks|Tqg-psvFuBt)#EVmFm~ix1LB5U_w**{5z1PUUj{f~=sf8OU z`6?x^q4$19UVVI@QXk(NR0mfd-xr;`J5qgoFHntLeSAMO>>fz<@jbykIrj=zd$rWZ z@fK5Vw1aP9@5Lw7#P?@S(3>)%Skc3G2k|hYUGGLteS9}`?%rWBxEOt0-T8CybG}<& zbo4{e#CJi9?@(&*{Ww-1?~80txf=N{Wv za8j@KjU(>Q_7wW>LeL1^r})MP@*En(w|^3Sc@Vfh@=3~{0tX^*MF0H>GHCCdD&mcbo-FzjQ_$+4ZXT#~>U$eh}r?ZOq zGt!9NN72Yn1y4is_FW`u;#Y#zk!s?XgKFh9Lyc0~_Dv-+Ay%SwU&cB0@ykkm{A#c! z`gc`I)fweA8uuhhru zl=}BlwCv~5pjYzjafi?4=*|~_z5!-Ay7NV#`+P1($G-&4{XFz}U zTk7c7qgxx*wG54Xn^NOeV^{C4&njnYO77$ToX>NMhaveKc^_BE!Sm7mZ=|O0NNI?U zFAwB3^y`Lb>FV7LSt)Hr$^Gcmzwm_n4gLCluJRjrAM$=Q=N9OaYopiSjBdU*Xf&Am zW@Aw8eKPBXS6PWoE>U*VD`>2nfij?8LARa46Y+ku@CVRHn}IEm>foEAi>r65n{R^7 zeFl2`nWX7xFVPfqI0XM zpF^tX;}g-x)z!~MN8b`{``i*`g{hBE04Gr6Wxnkzp!)jDBz5!iI94|wk8VDmdKaL9 zzl>fzj${3ke?s?rfcv_Ir}hJ&+W0MK;!VgmMJvArO}uHikk7pwPT~`4fgtscfZ6nUIs5lzJykMFZ_40Cb?n_I3Tf#$wzA>x&!PMD;9o%k1+xG21lhCqO zplPo_7uWyxB09J_`c%@rXyOlXZX&oL+V|8_=l1;00DPFQN-Rgx35pX>6&9tB-GkX0G+$c4*4;(ZSWVXMt+qPjFuSdJdZSO3K|`_F+D$Rz4T~Tdn;u&iWRh z$4mWtZkU6Gqz~VdHwmGu6EDtPW#CiTw21*{l6i#V91PeAdQ);Qda{=DdqLT9H=}po z8{|ga!nuOHJH%^W(0_e1TK27I;#D~7{yROf!1N&9gO+_8I(}8oYURI&wY`4ud(gXY zXEn11XXRPlPOckvfxFPcyCbVpVth+C*8VlfyTi_1tXJjs-G%1eg>`gI)_J#sw^KtF z-koU3cW`WU(w*qpd$ShYi=;k&CvsoP?m)-BljHr!sbTMnRQq1D)Vn)^9r^4Y)Y+4L z==MXm-o4bx)xkTUXX|xY$eA_K!PU&w!Rw%HFGTK2$!=)f`UVcd z7uXqGKfUXgN(`YhxRD|HI4e;j&c%BDjnMo(l2ERIp2AA>iL3Mylv3 ztVFTM`KZJb8rh=1uoCqmx5GFX*Isfs>VmG%WOW#OCi6lLhcPt1soEGdW0_=YXr-x5 zvTcn~Gd@R7hjW3<4qMm=o=Oa%tPR`N-)$w5Q0|7FC1ce5-OAvQzfp-4lCL3u(%)(o zl5OtqQ@(~gURk^{HS7bU(<-qN@-|%M8$Ds%QV#l?laa&J#P6p4zxwN6{q?Wk7r&=} z{l3bbHU2dp^4!v9_pj&Izn)+J(l`F+^^O0I4ypdHW+lH&o}e*?Mjgr%G#b&!#7Z=y z3@rI^TD9eu$&b^LE$d2toVIG&f~%q<)rn;dYRy&~mLI34sD3O&u`D?)=W@zq z$!S+t-<2g-;SL%%EL*S=iz91LO;P>39^d;v(!>9#fg2N`UjAR{;cC~vYvVPzx>}w8 zBbF_tE?VJSwxX5($h@qyn{8;j{dYN+l@_xlS1~Vb%Rh21EA6&A^Rm)zwqb>1_(#sA zZRnj;*p{}QE$LmX;#~5+jk5iW5R!u>=gR+Imt?ETNiw>^70ept2wAnRQR}wfR;_F7 zt6Jr^ux%@=8+GsBTT)$kRqW0m|L^Mm(f{TDbrt2e@xQOWp7Q^CuYdgSa-M!)PyO-# zx;m8sDm&IuE+@3oYsSp}_eT5b<9v0dtQ^Y!9!It^&h0^4O{VPXqkZ*p{>NVXV}GsA z6aA0J{Hi|s&(@x{;qR-?L{BA-tC#)d9_z+yIxEN}a|ZCP{pD8}rWFpcGl1i^68T(V zn>r6vV)HAk(n>_StkTLnU_1EBuP{t29Aakx@7iC!+*0GV{eI2>j#$T*BiY}+4F8 z=YJpbf2?nvKYq#x!BxKte-V`kM1PN!U*hV&h=2Th{O5ib+Fu%QZF$vyWX$WSU5iy~ zdr(HbzZ#?aE3xSA3oS=pmig-J`86q#9q){{I(xn*C6ySs>f~CGmr?H>HfK~gq8uAC z<{e}9Q!`pl{(KeEKjzK*l(F?i=R@08badtA=yGiQkvG4pZ7Xx#>T}NOvyK1x-_Lme zey+2ff1l<2-8lEHKG*r(s+QmCKOP(Z>{$A*xTpUS2Xqz7whFx{PoNSx=WJhL*~&eY z8}K^=wK6jP>zInwqbdILvEg{|Y54mHk$LZo@jpK{91p9+#Im!P~X)XIOBdwa}{3icj|G(bjzrX8$ z{(k@YcK$#6zqau2tsSxl^O!x5uK*v+@6R7VK15oP-^WqR9xjiUa}={j%Hw4-wocK-vi#0-<#i* z-%RfE?1}uz{EF=H{0Z=h+;>GjmOq|fNr^i!Kbb$3>-&B(zbadqKL$qRRn)l>ul7^< z)45*nr}C>QzY2fzrPM*XUiWvB-t{-q-_niQyOg|>-c6D3{d#(X zlGjN$fj7a$c#raT(`)JVbV~Lr=~VDF@r4oIU|RNuPp;b97Ype)<6XAbkjan2s#DL!YLjDR+nUL$goQ64Gbs7)oRm zy_eo6ACZf*N7G7hN%k4|S$Z@b0vl&#I+*krcnDI4`(xl^>G5<>_IP>%T!cI@dm=pv zKAD~Z58_DP`cnxeN_rZEi<0)wo=(qza7faA+*uAo=$Z5^`Tdcd3mHkB3pq!fixaa> zMMv`&7rmlqyrmmE9DLND{s+Jsu$gh9$*h@RVP&|B4_#+ zHMqy_V0TJ$j_ZRF8IbkC`bC2RdP#{5iiYGH7LAJEP>328zoy@k*r-^$_$B?C#I=ic zil5UjNnEFB3^p#B6hEb(QAYk_MObqiJ}oMW$tqE?~*uP#`(s8<->CDtoGPpn<2 z=S~YX3M?5#%|g%O=cxhdi=<90ev!UR>Ota{>8s?kQ~WA@oqTqRU#D-tZ_>BPC+N4S zHt9R?yYxL+ha;b$-=|unAHX${L(zdM?&R^*1GE4Kvo zfEqDfd0R=_Yy{=Qu^Q`3(y!Jo8%c>iIz6Bxxi5ECGSX`hDd9;|U)8&o@S?f)89=HE z4&+GhT2)ZJTYsBxV^<&6yS4^iH1%ZtZPl{g`<<5ovwVgRX0rbsE3yPhKj@eG6PT&IMjzzhrO|cVlhhoQ~GpOfo z`$7xb_Qej!`Nj4{S5OcAyh0D)ykb6byFxGFcEvp8++w?;2Phk0R<^J>pqP~%P#jpy zCO->q-u}hHVh;J)u*7C%2Ntr$!~=_iin*LMPG-Mi|6)7P-FWsb_ABI-9Rwa!EGp(v z;*LF$JDf+_w~!aM2wYTbRmiInN#NGSHibN?Z3=hF5w|I}E!-(b+_soeY?;j{W`fg@ zyq~?81@cang7>u-v%#rIdHu7&*~Oe<^K4Er7o38eRJa4sM&P7k!$OAQhLr7;ZCvaC zV{T*0H!3C;av3LbenGZLVSLLbh4C$$P-o*}Q%W`|CKU1`Cs23iY%=#WADo|UT1=)N z=VjxIU5Hf}Ppw_DamDyzA}A|rY%#77WloJPNg53DhS8!& z7+eeid8cR59ro)Ga7Zz<=mtYp99j%3x`u8+999f3HciH2ZJH({H%mraZI+D4+Kl7L zX_GVx{>~<8Q{=`;hW*BrjSibrbF(xh4TBvyh5Y7eqa^cwqqH${3$&D>pz%&yP-jY- zlr{)$!X#?3e>F#Kz&3DNH%x6|!%j>aCb3;;A10)UseKrqCY0EoD7JBFd=fjrza5*# zC9xy%aT}zuN$eClgPn=38muPa&p)%%>y?>ZW`vL`QT*aCSgAJ zW@O9!v=~;{_ON#5!{}K82W&o!A35~0@3)7$V{FEuq$Mzf4x#)oO61kgMIH|0Yc4pK z<3*g?5j+@q5S+Ae;Eu?HDBBU%&K&9;!M)A_BYd(0IWrFalCdHOa5N5flQAp{IT{c5 z$=H_tNgIL-IoglhByfMEu?&;oS?yb*(KP#zHim<>4`^J3=#K2&lFa_@V7JsY9SifZ zYcl$%YwE^Pk0igp2WPvdE}TC;^rWOm>Y3#Ccc$!k&{(Ekl=Mu!k}UsDsdG93JOQ3m zZ%TTl-i*&9$QvQhF?C8ifyOg*NF9@Cv_t!3Oho(C0og9KPq4N~L{B86D%z%Y$Tq2M z+6^@FqIEJZqjhS7Y?X}KXq8$cTP7nrTBcUW(^LO6Ae~Mcn9d-7dipDAAUH4$N@r4X z2G|ez7s>{uv&f$b_C@}gwxQ|#_1HK*f=#wCnKArKOw~?Y29=ZQd~DR1)HX3=|p6+bOKUrmYS#Ikz(`IA{|F+ z2_BDZ6fR6g1zwOYOhyWd7p9BAi_*nu?Qnj&0K9;D#vopt)}h2m!1L1isUF9dfc24$ zDKR$i+;m=Q!q__pJSUwCp3Awq;gWP{stZf{lC)MhG#v)kMb-(2rNhCskhR0%=?L(M zbR<}Zqcvf3ADL>Ajsn+2)`b0i6nIoRIvL9;9-WR!)nSy2$E0JyW4SkDK95UxCL;{* zOf85TxHH|w(H)ev1Y3qy;qGK4-rdPayt_GfSGqmjky?d&D8D=1lZ@88jj~o?tI!&3 z4d?n^%I`_HrrS~$meYexz;!8I&b`7WrZj*7p7$-(%EHa*mXwE^ND;gld1Hz&(r-*R zA#X@VjNXuLL@rAOJoaU&3XJz<=?0FjPe!C(pOzu7OV_70!qRkIiAJzKo;{ErOpj*| zrWHwksJJ3Mlw^xOl%C+M4AT441Btf}rH8?l$R{b0cY0sCKM@I*9swUomx7OS^c3a3 zmFSV|()4t;JlzN0N9jY9U78*uT?Ss3E>9~c6E9C!qz8#!yCTWB6|YEFf>)-ilB`_u zs&sX_56rA9`jwKXym5*0*H4LTi81q zx!o)Fjz4ETNxy)-kbNlc9s9%|vLDGC#oZ$sN!ug-n*9d$=--6zhxa_#}eItpndER#W%CJz_+ruvv#q4d^>9!+m-k>_f|Wu7uS!qNo&Sh;9zh~ zWSuyOGj&L{V@*njfJ5R?uog#aakdUPAPxiva#VwJ>w-0rbtzvfR_AD4aNXE6*5fV* zfCD&Jjk2b34W!sKHj7n}VzbyhRzZr*V~bcI#TKz8*fO??3E3(}q}VF9jyY0n9oxi! z6x+nM@t}O|xK3OI9+WT28^%WD8^yKbf%!rCI`Lpi7Uc(!Ya9>A4@4e9$-(&{d4t$6 zF62yOuyJe>7gKUbzBsQR8^rzdg?SUON&G%vLdjyVUaTMY%lFT}&-Ww!knf8Wf5?B# z_d$w3=0D|oBgLQcpYy#)zkt8wzk+*nv?ub{d=I4fYyMllJ5u~D&*E;R0Pc?bFh3$c zGXIctRQ?h95AzR5N97;qhja8X>7)F8j*kXEKz@=R#+gq@ALs8;dJOnJ^3(iK&U{Mx zB!4%bpKlKygM63s$K;=JXNQ7^QsW)Uw$I;2ireQqmut@QV+ZwS%in9# zAtepKOOb0*b`5xJejIoWvJvGC!Ap>}C_65%i4>2^j|Y#>PsnQ^#S`)q^Xf?P#QdbZ z8uFxk4bq>$YRIbOP6pRNRv~u^SQS~2I~A;gTo{|=>w@d%`^Wvjrulwxf8+s_FN_Do zb@ImK8|O{(ePh$S8Mq(vK*|q@`^08>^L(GUFY+Kt4vYuIM)}(0*Us0;_m0i;pTpkN zYMw8m{Ghm3{5kv*_KJHW_l&=UU%|bQd&FPEZ{VKD-Q#aK#dgOj5Wqb++AZ!LL%u61 z2lG6FyK%Hj+%?90XHo)pK`w}iyIK%;MxGtdiA&d1e|S6tDIOk=i04y&9(XYF^f)KZ1<#=Tbkdx70p;g|i;#b%Y;ODuQk)yN zi+?7~1OI|Njof_j&&X5BZ4aJ?JcZm2;0|#|@KlaYM(!B@gcNs-JH?Zb;!bfv?3Z5> zFOB`detF;g(s)_yn_m_$2m5g}Aip?X0$xImf%%2;qBtmBl0bf;)r}?z76GDgX<%wP&N{5k+%d# zBDbY{8*n}3=9IO}H$#do^H%v}q}VENoo|X1Tjy=SHhJ586J*<=an<6)k zqw_J~n0y0p6OJ~D8^;a64f3)1q_|NWn{OB=l{hvZmrslvMsZv|KA#XLMv(+g$S3CG zBW3xxIKIS*+}kB#Ms$~nZR3o15m9yGj5sr18n%hsg4@PRh=1FL++|_wxJ|r}_`8|l z%s4Av5N5^M;DyM`IeS^SJWP*Uk>4tA9nTLJgxTQiI4oX4`Q=0xo*#zA^GL(N;c-Mf zH;jlQ!Sj&kgmc5lcs6Micn6%cTbZw}Xt_@4U>d2au)JQec)!~{@D_uo&U@h`B(;BH-S{l|MT?bwl zt`AiyyFRR$t_)X!S5dEax`G(N+LWxBs&MYaP$gAG795=jo=D7NN<|V+B5E?FKM_qC zQ%Wa?oOB9!3VWgCDRLB2o=y!J=`=7Pe~YIP>G>PZ{L{j((VbX+jlUs(iGLwJ^q2T6 z^5IY~)lUzH`l&&BguJnM4N}AO5N8^sM=5!Pc%r(gURnu0O3d+Escu>k8m30zL&yh- zAZ(N#qkJXt%C%D+@^#W$=>bZ=jt>x3*(g0u`D4VfejUGw_Y>*)b-XWp6Tb!TM=lTF z#_z!UkoSh~;`iY9@dt1@NB0m1_d~p!^dtCV{0Y2=qr1XS@n`UEL_^b2?= za(R4;i0kF?X=10B$7jO5@gDHma8JA!c^_w&$NRziz$c0KzB@h}o&)be-W8uCj_Q> z3A`P7YrHAk4Bm#kCEgrv0dFB<@0NHgM>j_#cx$*V+!Sw)w}l(yO(otIZVxxa8>4u8 zxFft9AB`*Hd+`zEd!%>cJEWEIeM;T~ABqoy4|DVZ`S;`7oL>p9jE}{)km6(U@%Uj} z!TAqKAH+A~mGLU@Ey~{{T^av|yehtd6t9X`$Ja^MfNvmQBX=!$ZCnbz&e5yLrSTQg zb>MaJdhk__UPfLYUm`67Uq*f!K8v5n&%jT^C*h0uW&9+38a@XdH6Vd8NZ4j^NBBGmTk)%2e&pZf$;hnI#I@I@jEykwHar;)q{CF%Rb?g z@Mq94{i zpS4YveHcFiKZ+lNAIDF?CFq+U@$J5fU-IcM!iVIZh#!WJkY7>qW%z)yC*lXBC*#+Y zd=8bc0N8(fQ>G&;YzX|V#_rlZhUD7l0J4(I{?@;zke24UG{GO8U z!rPQR8{Z~97k{AS`|u<9LwJib&&9V$&&QuA`H?8wEc+>h>;`@tf!NJoV#t=o8^E{1 z^I(>}K=}*A2nV8ZUjknuHacW46PX@}>3$V_m3aA(Js)47{%hfN@-M^}$-f@nApau0 z8?raT-^l+hya~R^_uxA8d%!0w)8~iOv*|$V|fn5Id2c{g(Wj&Ez@4$aoEQKI}#iRF2$AOG}zzQ*ByXBa5 zvR7GygzQvwb@+?uw;@{)3-BbgCU$VmPXagOi5#+VaYOL0VH_pDFz+)~x%%g%&lq{1 zBEKk)9fyIw_1NAI^s2}9d!TPU{-(?^W{_FgGFjO&S=llfE&nzr?87XxZ?nuk&oakC zmN`1I%&}wpX4yIPxti;D;rnndsE+z=_%579`48X^^u2oQ_u)Lg`#0dX)H^SJ6TS^+ z#vj8^;91D?IeT8I$Nm&9Ab&o(=}(Lgb=RN5g_K-S>Z>n=zedNyU!vnd-Sx$wzWNgA z*f=dZHq=^Q4(h9~fR2+>qvJ$<^|f$ve4TH8GP&2upMq3(&1m;Ofogb0Mys_x5-yDo z^OR9XeUy?%c&@0y`V6`>vTquiD*L8!&L_@gaRuq}_!#9ranxoXqm?g=K8Y>|)nFeC zYORk`{us}j2g8x&b4OHby+5e0`t%XiT7CK)Q$BG-_0@ZV8mv#BV|n7JwffvSjwg;< ztIwU|dG4sS-Wg8hUVH|fP(FRK?B4RZb1zS!r^{!J=+kKRXV4#?K0bF=J%fDutp3FD zN#wJ}=a5gFC&&lpC!aSrfWJSFdq|{f^a-V=CptI&mFI1i)hPA4iq==r0M+zr zpxgbf0sc|ztLS^`epUZX>$?v9PEBuh-EVb$Pd#u=w86kL>Yvg5Dq5c!pxWMPr3QEk zx}RE~8sKT@erkPcfPXG^zrXxl>#Jyh??!dMchMW_rFWtl;5$*>PmQ8}dOxc5z0bM# z&=KmA`yi_OsZlgc>Jp-Q;D=Ft??cXhz!Opp@FPlmS_YoUZ$`DgH>291I!2?UcJU3G z#NSF(4}6349h!u?pE|~OrC#wpI)r-QtE3;n*EmwI_z_J)Jy7l9N1iu?qMW!#23 zTeC9s`R@AhE7n>8U0_?vT{)^1Y@Yj+cm4Q8bp7}w=<|KE+$a0w+^4x~$)}^M$Y-J} zN6}}x>qpV2xhqG}C-|h?XRa&9=Xp9!%3lC|^7dn8IES^pE609$e~w(~&&>z0Zk!Fy zrfeW9!&%@gj{9(KyK<#JmzBKh$KIq-U>}YKv2L6R&ZM?0{ZXuhT}!UVJ-RBM!MUE4 zjxN{!qgdg)itIt!0PM+;tNsmG;dd|5wPaV)IItVi_5L`}Rb&@elC1N)fUfsN*OIRH zMOTqi;udiz=-PiOxJ8^AUE^;awF9_D9>#i?b$;A3y54tnJRBU(T7R=Rf;GLXx@8STDQYpUx;UX8wmUXdfe^<)wSRK3eca7YhHL?}}SIQl*54t+8i+yn0sI_ng z=o-0x?uxj6?n=2n=jve*+?rgSd?u@7t%x(DHp5wSu5i3sO4}Z=t{YI?iyM9;i#zPaCBUQGzN5yto?9w zteU$<)_%A_tdhG%)_yn^t*Q!lxUjSeR_urSbF?m&!;1Y-JK-uTVq>g`+6Nfy9)zv%cPnDWa=6NhxXOO`>p!#~RxF2F5w#y?|7Jg| zSPr!!YCp{X&3>rmaFrEtXYTN$T-)GBx%R^kIXX0IpBJ?ye#}|z^B?4g#rH{v$4@Bv z7#sW{SP`|%9}a3i{FIVUu)b>{{502!_!;?6Sx*GkC|c={0JSB)lWSenN-5qgHxRTjJ~a4sl2D4diRN_Cu}oJ4WsEJAqme z&o6EATIj#R;;!vo%e;B*_2-pV{PRjnzLxn5|8A?V*zGSa?e$vbzxcbAzGAUo-77T?`QO>< zwbEBC_7CI_VvT=*bY;m)7q!^mUs~o@Q2rpS^~zLwRtttQgA6;cfEes=6e0E%d3*E2iHJWiPyt; z*XwtEUc_ZE-ivqxTz7qc%X0mFH|F~L#2aD1BcgZ{{QVH~DBjF{_Qu1vcGN$+cI-)7 z2h_W#mv-&ghqHQV^#kgYZHzazA;*33>NUjM+Jlnrq$Z%=y?&JUjs5WLHNbO8tR7gO zW7qlh@yK?kPFJM(J-$9Yv*Hi<`t;0-KjQ1_9Dl;Qr+@b6yd&usuoJRF)c4mR>gm&C z`%A8`_P1RBtf<$o9WTdoo!So6hq)f8uT~GHsIT^5N*3h@=lW_7$@Rk?LjGXKR2CCq>$@-N^F9F>2a9fsfX>+Ep6nqN~|;S3y=f6lq1^KUpSTi|H@m6^WF&tMK5 zoqwAhidXYn&VExe2j=JBvEp9>>eKv=vvLOXcz(k9`T55jZ4c_%{0QcNsDJaLOrPe5 znLbTf1Uuy)z#muu>eGB5{=m-pd!${!_mS^rdN$w9^l82ei(r>r{=jbeUFkfpQVR+ufXWVeuB1z&|fAdlsh?B*nY;AYq?uVwOB zUe9hMy#c-fe?T_N>)8$PSpJqRBfSaUfV@7v33K53^cKv4>*2AynOz5untu%m@v?8s|*+%Sdct32G`ka3_twVlo7)1}m zV5t{mu+)Qz^e}9r`(U;-=IlD`@h5|&2_V->7-jR4IJeIY>W$;+)gv(*D)PaL^ zdC5DvqU0TkSHNSb71j*mm9SaZDL!2d`>0m9x?~@TSEp-W9MuS-JeKO=T6iqgU>_}o zk-1N59`+`+2zzlPwg@f5zLe|(E3+BAqdnnjwgg*-R$)I%_JxVr6jst6urynNtwQUt zKPCIY%4`C^X#cb>tfYnHD=f{{VfT`8w0mleNou!}ceEQ^%@B5ltC@#g;A)CYabSdZ zv@?uNF~K`pkO~+_3*c=QVJEnnRl<&NHN`4$kamEpDat|G9unM8 zujIsoVQiiW+wvgrAkLggIs@L@Auu-oLRwO?;|_rVcOd6v#4UmKb^u3blg@(iHUl>1 zX_U?Y|BO5bF6sf`0n|8^bF;wHkf)HFT{7Zkm0Y;lu-|6G(v%T58{XTTG#C66QWo4? za4uZU6G-#G6OqT0n_n{G=9MhC`QUuGnoCL++!FY2i^Cx$3+|Ax7FG>fO9J#|NKeXgzUYr({jJU%oISeM|IqBSVc*%&9pLt0-sARz%LHXe&GxN}N zV9A9$fTP3G0VNl1VabA9ShC<2!qPlE?GH2a$RsCIJQ6P4z9s){U-+3vrF}~N+di-~ zk4}4+{I|VJ{@dQLG>^fSxi>b(~ zVbAs^-z#-WV`0p8N-}IaQFq6ZcRCKP={VT49a2YR`_v(g2gk#nZJ#E#luz3VuBj-iwpEfz+Y-j zX?@DqV+Y`Va7_nrW}pbObTB3B!_w~y<8(;q1G97p`N6R8dFM&$Pg*ba<4BZWI+XkC z1NO0ASR00E->?qc(!QY|M|~)33^s;a+8dUBlhli}F1Rk-(q6Fio1~ub^P8p~F!RNx zFig9LW^hZphvslfyTjFQmb$^xZ;`r^T7un>6@I?#d^!3fVCJvR$(O4?8P2_&{0cvR zb4oT#^7BW)#vfC1@;3-={?5!_ov|+qzir9MZ}SJP{)X`L+m@Vsv2FOjW9E;6lixXv zA^nk=KP!`&KO3Bt&CIrfdq0yXn61(rN@f!sGYy{p49;u~ZVmT-ZZ;Lh{oHIzxcPHA zJBL`88QC_8cb>q|-wqc3RB$Tiw#j7dgUET5Z&&Uyynfm`TOU^bRvd|gVd78EhNPk3 zR>*0@!VCq6!o;7J4TFilC9yEW(^R5h#NlZ~+JYz;aYP!KrVtAwj!dJ#QTRkQCl+RO z+Ng|qsYJvW1G9jb7$ajgBqC-(84LIu)If9g$PPsYJna;jGb-Q^<8Cnq_lvbB;Q2ZW=g^D3}h^-Lfz) za(dB?I$ens+>Bgz;(InL+Hqz&IGy;HwxoezJ7gPjgTS`P*5uX$+aOz!TOVwVY)Nh~ z*b3Q#+z_xOvN^e-U<+h3a>Kx3#Jn`4Y$)-9&BzZSYOXhET;!1K{~_tD1Fk5#Fn;&m z-MhPYW@nb}lJ0Ji?gr^@6af*CQ~?Q5Q9%(A>F)0C?(XjHhVQrU_s4n8?94gOym!4X z!p?cl7C`A(igC$MsZc)DktI;r6$A^SeJmZygWj=pC@;#$(yW$3L02MF$odp3Y?WcP zG+MgcC?kurQrIfXxD494Knqz6Rb64LC|3!=gs32kprH#e5jx1iDCq)Bj25yGO1c1( zpoJ_HN{R}yAbPrFRsocB0VYEWnI9!xfXPur=0iyrU<$O5c~Q~@m@-ZaSqar+3bb>T z;`EOJRzh2sGE{-NlvwcIxbj>DZ;wlf;;}MHx}-!^M)6n$C0!D(s-TE0M^w=5Gk9-Y zS+3Gx!F$WIprlJoToy11J`p}Ey2q?2=@N4F|1J>0`(v}w`7(HKY>v1-0y$7T=0Hgo zkE|uQpN)M(dq9-$fLa>{a5p7^b)Q(-b3NRDu#&4~(p>$w6)PlXNG@-O8=+biC#mbD@ zu?q^p%xD8mbdH^wGtmZGXdk~qA!wlxjG}t%ghDWiHqb`x_$4|)8*QM2+VKk%f)3h1 z7qw$YD~8UoBWgi6P9Z4J1`5=U?JddYX^&1&aLU@=qOU6|+ zoF+HGW+((hSPSbTAG(G00ZndzEzkzON0S?1OB90d%~ogw-=WM6ur=Diw`g($Y=bKB z4a(fMsBzn(4SbC0bHTA;=q7^lM>7#f5h5DIj- z142*Cr{F-Yeh3W+JvF~aEgs-g^O^Y_I`IIXp~mfxT0Fq#<_ohQYViPHm@mz~ahlw| zXvSZfeb9-&0$-uYy<+|m8X39@UNNtlzoQwy%-l$DWN1|AnmGc6_%-vl(C^^y#9e3R z8hZZA<|wrMqe6dzm+&{3zi!?ze+`WYT`<2!4}QT66yg`mi};%;<9`KzCGNa=!R!_~ zhkXN{$DcL7K`nmPJcmDHc1I_E#_WMY{ET^)tJCHgvnLw=p6J9+nWyn5&2LeQpEOV5 zPnajoUSKcO;wQ}B=){ks^zVZT;;wlQ4aD6zb;KPs{`*n&-v{rb@!!w-J(Li4;#3m1 z(fA(@-R629Dv1ZEAs(0y!F_S#hv@f@gl^Fd;0Q7Q*GKF_2eA*0|8A5K`_Mt`N7uhA zPRqXwWyF4SCz^0)$m;dL5L;3mJWKe&xmDLW+h0)qgWE`lm!+fJ}GQP#Vo5|03 zmOd6?_L>o=#hAg|S$bN8nVrtuDsUAFj77{W4BnE)Xc}{?!PTfSro|~TrsCJqXCh3* zl+aYhQ{vPayqkg9$y}`i*P+Z<#>`UsTuf#>3EM!|iZHV)z~!Nd%xwTSpw(E(%!<%o z;7Y1_f=&vNxQ+@uz-Jak6EP7+qruU1sEA-=z%ikJz<)wx!9G-;L>T?c_+L6vM6mzB z|3c%z@u3Oe1ehY|T#gaB5nV_mP8$-TvSbV6v7CBG;wnQTRJ^>8M5r4%4QA!UDiW$p z#cG5Klgi8l6($iXPdYOWDo-Mz)jXl4A4_C4NNo!9-FPw<30=oWc;a#$W|!v@5$axC zG+HD0H*bWxml0rX{yi0;`lU9QlYfUq;woe!RL+!V98}IksIe)HdO0sX=(3cTnRfhX zAK^2%vx29Kp-}K#F%%kr{eTW481?5VVkk5S8^}|_{`jDxY7ox^`{4)2T?bDHL!sc= zU?}vh*URGxU|?YIbg(z$US4l6cp})-V?Er*3!Vk`VTM_+H(5Qrp3L{adWZXZ!85|X z#1O}NDAdmjo~QNmf+vOjSS5m$P^dri%yPv~?gdZYzGJ4p_dVn9z~C9(_g?UH?gz%- zdjq`SY2E-Yc$znWnIF7?%nb0ZdY!#4-W7a+UA(TIt%9eKQDv*2!q>d7Sigo{^)9pC z)pJ<2m7{`Zl9q}RV`0O=;F+Y$yrWzdJh!|=^w-`c^16E0y-qM)$F6y%veeJv8{U`9 z-N3GUF%{g+7+J20slhzGyhvs@?;_b>gWdRy5oMAU!BB8`UyywhyWw46ojL>X&dB>lnU8%uVl>*AZ{1;AyA9ddKi>W^Q@6z4l%Qume{i6+HP2DFc6p`P<${FL?g> zkrkeWGIPhf>$St*1Mh-u@%Ozp`1{yBFJI&XIr$^+y$|3AuJ43TduO~moPVA6@+8U8@;e)yz!3Oq&rt?)VTymt$Zb6z2`3i6D8koTh(Jlh}SJqRE7PJk!8 zli*2mZidfu?{1QJ-YXn=?Y#ltkQqGN|Iy2Zwe%j6^?-A=3*6!0#O;DtB=X984ZbEi zC$TNPoLDQcmDk#P6h7u12al6kl*r&&`wQ=-S2Xg{d*uaZ1g*Wt;iKL$@ECE$SPh=p zKlfgEPr^sMqu^22f)j++UUsaFSDe*ik*DFq-VyI9F;95z|IB;tead|C$g}Vv@38lb z)u%k`f5vQy$WxE?@Imhoc!;%sz2MAY9Qdy{C9IXNrf^oL)lGSc)4!YYGADsIVpJ`~>$IXOFZ2|7C7kSShWhk^lemK3`1^`zoHg1=~$|9hR%% z>+%MEyce8ljED0-Z@d?rY)lV(N~!5EObh=5?*s22>>)UotJ^X-d%O+LEjcM1PsLZ0 z!jtin!tqrCbq(&T;cJ0~C%`t|n-P}EQ#0V49v%b7LvJGIjS18p8Jt+&krz0R82sOi_Ir0>xFhe%;AC(DjE}qtoLDAM zSL6-;yt)G4jqoILCwh~-43UhH(d6y-Mq>xO@!?0_WAL%}1f0OtJ$UZQ$wW@_CVRnY z$Yd`)Cm{EkzbEg@v*?8WBKv^%ANr#w-V|acgTd*^pUfWg{`CIB|Hbmw6;lpO(o5nQ7j1FAb+Q zkC}fYAIp>BQ=Iom?xqp?l@myVKT)LOe`k0jG=sCs;LLIsIE%AQBNUv08lgFyh*Fcp z8L1Hp&Pk2Xe9k|O&;m|7jZmOV`VBuKoL&8cUMjm9%Sml^^=~+v%I%$#=Vfm1yu1Kj zkh#2#-XGpbZv#HSk=`gTs|rr9vZ|+E3GiP&c~&(p{FM1@T;+iwx0lB|E6>Rs@Ml*! z;khVtdb#kMVB6@e=bk+euZM3G<565?QCZbzk(|WmP&w5YPKEQrkjKm6U6hw(4lgHu zv-dmMo3TyaI`UtH*Lg2ckgbE`c{nrqB_o+t7JM!ka;jV^I6cm#0_|6Jm@die*k$mt zydv{?XXIJ%tjz0e@kV&RfxofC7HqS(mK|P(bF1KdHa9%ER3?>Km5gM3hv|KeB|a;gJYo93qpK*&E0?MJ6vE3_hyaG%BqM z&flkd5}N_e@Me0G;haRh?hb8=+E>9d%;=%Oz(R#vU$UdblxZ6C$Rh*IV2Cuf2kaP z3O<#GWI}inPysO58{)ZL3h#?>@9r=llY689RT4Fu z)mhXp&-LbcBa9SYN-!mH$yp6*780q%Dn-NyB?1$v`~9Mnow(N%RHqYBm+49=bUQ&T+}CFW={b`crWt^}17)rhI8tLfkjYCF{~(a3hp z2JOghuMc~Sq3-IaEXueqSADoXDl6+Mx}WhKwb_40zQg_k|AL*)jj;EQ6!nUELA_Q{ zuM%9)75ow#&PFBKxcrxL}0cW*evzofpU zYAmU@g&p>Sd%am+O&y%A)r6sjuAnRG?~MUeX^*7RY9xxxpc-eEw;7x5)grQ{uBC$$ ztDdkV^MYEkq~1Q5_fnx1RC*7@{s8|Vzc!JzbZs4+d2I^M_U3q-!gIX2;AXD&leLd} znUDA$kz`(SuScXOeh@qZsk8aW+JQLrcO4jN>pD6(K?|yY=6c;D$-NX{4}AAX3cfK1 zi41CXf=ZGfsYf3{-Ps73e#8bv>XKVW*VVzP+#zCu+Ml2n$Wg&Rc7Gwea;}uIEjKqr9GqRnT+boNdf8KGP+&_Eu4+ zq+w8A)C<%HQP0Lly`NAVG$6OW*TCzH3b_WXzZ*5Muc&3`?c$nudBZi=D4{>o4ZWZe zuOX2QJReT&S?~>y%wu&fRpg)Q61utH^<7QKYV0jEit1u|A@K{0 zgv=-K5_&;BSVAwT1Z(OA^@>f2Y~n34is+(x5%CL+M8qWY5_v%tSuk}yu}J(G*WNkAjCDEv$Ym1$cdVK3rs1-GEY;I*ZU4KM69 zH!6Eoz$#uL5?#R$cOQVuk*=tFB3!|3$4?RIG zqHC&VeENDiIJK|pRaX;G9#mH~@Y~_phPv=0kKi}KG&Iu6sOVMlTEWvY?o7X)ZpvM& z57yTWbTu^*#cDNG9ba3GL!D5YU23U~s6U3HHVmppcfhtC{2)Kd*02R9{uR86UQh$j zKsUh(=&Guknq*YPCWDjthSgF38oVDA&f01xxjRsiyp!+c&d7WDL2iJ17`lZrPEEINtx#I{49@eY<z>J19$Mp!|;o5)@0A=i_;4r?E2M|@k({L6S{y>>=fubfwp+|N}# zH3sEEL#h-C>V{Y$-JY0ss40W0*R^D~M@{lZzLk66+#RW}{zmmspR9T+sAnjo8(@X? zUSjs3Q+X}l$PO?BbqA%rGF}5U8pT8dvg)gStnNj>@>0H%`y#L8YuQi*s)~lhG*BIh z52_eSd8NJmkr(o%+)w1b$QR566%8f5QeGn!sBs&S)leNEWZpuSfJ6 zYTVcG$?IVqzz&gSUOlY2*AO09h^?SjV-?kTbpgKfSOc&Dzc=SqVSaNi!GBS$Q)N{- zupG?mu(j%(T8vKloLYiT`5f7cjms*i^0-VqIqcTlYlI?o74`P3sKsB!9+lK8cB`n? z!?sSQJ%Y!mAVc)GGnD@ILjfs-VW?Dr{HO3NoswjjA+!8?g=Qj5-Vd8SD?E zDSDpe)WR=^t2Rs}yxQ1j-Zd4}a$JMwsya=^AI52HBp4{HH>r}Ul-h)q21~=+44$Uc z*9VHBX4taGDe^`cn~B_{uB)I{3hGR1 zqO~vSom8h_IEnpfY*C-Vv<2I&ZW41twTRQzwm`GAB+>$F9@(l&5VaNCqFSPHS`=xC zwTRqO)u>>(Mb=HVO?^t#Hf*bEg)(Ykq!rdOvYq*DYP%|qzpbiL19O|KTdFlNfvO-- zQMCbEqYs$Rs1)DR`H{@J8fu12x;mWzGU*y99y007Ts00KS0_~C@CkKNHDTNs^}=Gc zL?r;@hqI8CS!dKGy)TT6I;iT&s59xBk&IYLFCj4r=zX$CEmn=tbQy*UZR$Q@$t==2^2a<)KSJq)iKpD+(}r_}pl-e(xT zjT**)KjgpDfu80aJBaYtsvCFsYix(w1?z3_wz{Kw!r23?iPGzUkzA+H2VmQ8g#9Q= znlNmJ|5i)XId8RxYUizf$JI__mvKk!#O|tZ$?XZ&KpEB*_MNIL`|MC%7)=Aa;v>F= zA}0c8*gt3_)5-Ng_WHjb_O9At+*P~O8~s+Ra4&eiRlQVo6lNw_$oG5`<;x)>iB75y z8A)|AFd6yVja_QD+HUMtd%zuB^;Xq5|LRR{FV&g7r-NPaeN-%>=)~_f?hAko8qn z(2ezFmp&>Ao8=!h66!?ysF6q~1{3QehV6$?`q;ifk06_vsNav=zRF?V_8tGD5egqO z66l2b7`aD{{;c*>{Z%EDYTtqV)px2Q`ZbqG$3Jew*9r7-;*ZfQBA$+~PcU;FwQf8{ z%M4$~)5{p2G%ENN{pY#@_CiPW79$L9LOmSOo6!^ht;VP?)Zf^b>K||n*b#3M6Va8( zs_0kppXukiykEh80lv^LwV~UE+lLLkSG5Dfuo~D_aI3Lbjppv83Xg{MOU7Svr$%El zDSOz6QrUvp)Rq0G`Wg6)J;t)*KWeOMuR4GoxGLwD_h0IA*em@P*{Q;RVX48?;WXh8 z`?n95^~?FMbXn{*_*%cwRs1LVDfkrLkE(sRL-?cWfKu?I3K1XG>*>Z3)f>=8NBK!C z{ipg%r3wGbzGKxW_0D*2jNq-yfh&hBTRVCk9WzF%_r?cs6#hSQ$Ep8RTl{$N zKd=qnCDPHZUW?wjI?UDl>i$FhNWW9>RfX^$YNYyL#8`E8Os_H48gJD*=HFr!!!`T| z`k}5te0BeK;yxO`t3U7)U>>g~sMdI)R~u^#L2gXfB)*1U)4#7D=!vXOP!m-vd@cW; zzOQRBU(=Vw3oUifGeqiD#%f~{F%#7!)e=8hwZKotCaKzF)$(imclAB(5ih|N#!5qh zp4NJ~vBJ=dmA@GZYLMcAb<_)5K2 zk3*mNCH=>tl71=h30KcT#r;pgPyG^L3I8eeH$y_MKNyRFF<VHaB zakQt;)N_?L+)OnG^Wg`EZtFWbs4TjzN01d%>kL)H)QHe9^^+<={HG{cpQxvdpQ>l- zb*Qjk#D5LvE2@qLhVJM*;k@DIDmT^w%!B`o_!8mY;2A+p(g0$92;J4S{T~?J)o((D z{KEblcwSROG*ktZL_^e2RWkfYJq91EC*TuU-i8YJ1^u_7f_@>e5IKJk8B`<m!qsAl?64OZ`oe-|pld}%bh_tgVc7A%7{ z_dcVv;d|=7dT8W8H~i4Z8O{}cVB`wt1|Q<-Voya?>rfl~8GReo&ROt`Zc9DYchvNL z$I5;Bb>t4;H(Ky}a-UHP71aHHPo-~Anbiub?LUJ5p>bN@LH%=D-$fgATA$(S9BgOx zIUVSJ&gokyfr1L*+I~x{j!(~gsxfMVK$>i#pIPJtO9+@yy5)&KmAWZB`$;;P)ZAStyU6*Kfu?dHmbPKs89+Htygr zk#$jD($}b1`GV@M-e7NXp2P5rZYP<;S;9?2dHsBTQ2CtKzpSr>u7)n_t7wZZlXXeo zGHx4#R8R$-&u@a|2lM;y>1~ra{G2`|fo}RsYRG!gt-lxSH;MjH-J~DNAaw<{%eoUa zXW!E4|63wn8W~Vtzcd2n^-FSJ7*~n8qOa;e-}H*rm&RAbcjAo!J@D6bpohAqFNH3H zmqS-|XKLDdP&eI!h}TAXl-;k%dSzTE@|u2Qe1iJ>4fC(*o{|nd_*-UzUOMR*oifs* z6Ho77Gp-xy{p-dJqm$o|3hqvRP|f{`pWeSg-{!;mh)!Z0(TR;O{Z4-4P&z-T*-Pi& zG=5a+{2%#!Naue-WIF7okpZ^!{uln2M1H}&c@GBF;)!55suQ8KI--*r2lXNFkUk6^ zhW#t{?c}HR)A^%9of&`SclLw&@s8Zt58wy%WgTICAIb=S20x>J#kgu@^smx?CZTau zAJc(i>!?l!b5bJ{s~PT^V=rQ~N=kVQN@;TaAC&xME~xmrQ=3`8uIfz?R%-@1H}_ z)*hB~Ukg*GXCpVO zpUuBuTr}GF7tq$V@!R6t_!mRh^*69}^S|+HQ`!EFUxzn4q&D{Gy*f3Vsf_GoW%IN9 z=jnvgotSU@G^_@CvfX-*&f%Y^#piaIAG2Q*N#xA{ErzIwhk&~Dleop_a zan9)J*QBn#Cy_n;bi|}JaxtIN&*h({Gfyu64BdEgGtT8pFgJM0IBm=gCG(T}bErN{ z?vJq~s<<(hhg$AnsHNY^KNxD|xAy!8zsVYnY2zQ5$5@BpJV;$;Yrl=ZpF4D2@27gRwI5VDcA=IqDVg&_ zN&KY#SmOV&##(_UZ>%Ng5&oAo+R~t=r}#eZ>f|&5`QMVU8zkBlnX)CVwcdraE`V9wEnVu<4-Ie7!OrpP$PO%AA#X86_(BX=KhgT zbH9bZ5S|6pFedU7`$3gswa_>i{TY;;VLS8^7#34U8Q)Lf2bGpJ zsb1X`+M#!1>5K_*j<-&P8u^X=6QRa_6R-&^OGCaN&tDpf=f?-*`%6L-EfbC5L@Ur3 zP9$rBb&{+TRA2f;Ok#DSbt=@*Z{(k1{v`F7+V}nCtS$>pW_6M^*$Nbkr-=#bUK{ug z{T0M4r%u!J6=UUVeOapC2PybWwTku=Im*0(DzSiAzQ1knh z?#x~N3i|~7#7NI8Q-8PqphVxmTkxCFGVlb7jG%TjP-OJ-zah7q{zh-1Qn-`;N~bqI zk~7l!h>Ze6(Lbzc^k?fA@E2Ihl3ONJHm(NsOWle1FLj7c^w?x8nP z&FVydvW8m@xpuUCTpetA;>)2Aspr@Ci;!2(?@442-BSm3upRXmFm%Mih8rDf4YS`<2J@|bv?~N_fr>PKMrq57! zy-Y9X$`|p(WXs2kzpIW64-eDw2s7 zx}{#PbD`8(uXCf+Sx@{rErkb<#0FW5^kPkQI<^K}L)H1=*i-A7br`lov4wgO|NVvd zk>gY$q!?rg>_;m(%*jM@(OkFC8{l8BkHnr>Ppu>59*%9)IZ+F3WPXEAK}>RyLNwFO z_0iZP>#=n-_Skv?J|Q|K^C?71(Ns6no5ikMhqt+ispW+rMCHP(ju=s=yi5M0P-|CHQ7qdHH|*Zi?#ZHZaf)|g{$ zjBNrp#WsVRW45&pwzZ%mT(O$_( z;{K}WDvGByxSFf=@T{}eTefh7X>E;di<#(&w#Hocb*w-M+fRQ+ZVBF6HCxYNJV(#f z8;DrS!u1ZbaW+l&ng60LtO|(Z9iQS zw$F@>Fl?|kTKw@KD5bG>#00r9bQ0@h8)7TSzGnsM+J?Fy)<~B!X6f1BZ1R`0cHdfV zt-wobZERgkTI*u#!S%3gf^#Dn5vJH=nZgpK$t}gZs%Gk0x`5G0HwFvhm%;MDS_ad7 zYcuhic>CX4SON`iW1SysqRWs~8a3?DF+Cbl-V#WF-#Y_Y;30!GAUYbjh0 z!H0ZfmcshLDoa)wG`rLEbY0e%u4ia%t&XjUX&98X6^1QfNEo6VF=dTyjJNXk!qr6h z)~eX*Sb65l8RdNab;^$}57JZoiaRV*GczEy$M@`QTUNMl}If{az|2u`Hd#J7P&R8T5$@nT5+1N>Zn{ln$_bpWS6W(@Lj?#TIXS3 z0xse1oX3vG{?MsK8u14^q!y!fpne|BzJKZ3aT>DPaMnWmS{+T=Wosc!m$6IMIWkYg z&RHj7C&BYv{jGDMnf@Dw(fW7&hfX7^k{3cB8$#h$2e#VQS@KTCuE2BIx?(NBk0I-C zJx1q5WBnUB?_$4^oksko-^Jd?s*r8)hB*U;TwNIIfUnSe)s54%U4`L_b=8`WKVvP6 zEsvdneHnNb{|}sF^glX>k<%EVf79<{pOahHI!)~I*lBD<>>9aOt!vgi{8%FY(PMRX zBZu*;9zp!C*az@K>|?ARxq+JY1xmDf)=SOe)!B^f#z`Vp#!m8WiD#W8V@2!+4A-q2)*O5T;_F-Ei2PTN(^-tH#yFkT z$Y$KMX0v`1yJ7vu{5ajvdWvGMq4f-{Ttl)NShuWMMBTz}TH|$Q-qbdp$p3UBA{$z_ zS-l0$#7|&#yq=&l8kvjs>xAW+F``_oq9x68sFo%1!h96_Ne|bLh<_Nn&;9raK7ivs_6zti zw%z(poaF7F--++x`wly44S@3pF+d!%j$00$BP)Uxd2^s=mf=l+o>|r^2bN=xd+=?y z?qNHu$FX7hC;gZmAI18M@Ay6JkHrV$^S01|;;3~DJO;aMRzi(!o0a({+4LB%WGR?E z^KR^3Y=?Ch+i5+C4bemOlh{x_3>*e;KM}lXw4dmYA0!T2N5CW2QSd0dQTmWqv9wv* zDg%~*@hJ>XVm}f&Nc0u`#3S=gY^OENx)ZyL_leXT8I?kXbUQZ9nhxH+E~nt zU60*}&4|s6!yA0sM$GmSjRLcpiteI^Xo~d&dx|DvGr19Sv)qE;2Ip2eot&B0bnG@b zgR5C^&IGUF8^YAc0@2eqgRQC9BqOG2Zjzhv+hN!yx62RolHV>r(pz*|?2dKUniiWL zyA9s9?pU*9S7Dls&5AV;4Mk(C0oDWzbob50H?TIxnu(3lq{ID2$v>pPOiuh~FdM(3Nx#k-KGG z@{3z_#pn3eFtie_MHl?U*dA-IH8C~`zksayu?4XU_%^Jz7Hvdl{9gH*PN#ce+anjo z&c)8h7Gf8`3q-dirj2MTzQXU5ujrP#kNCZE5s?dH`(@BobwBg_WIJNoiguzCesSz9 z>x;2Pu_dw7u`}Qq=9XZKV@sJ?68i&O3ZBA$W7QFLMR%)~s14Q@b-+5}8!NZDTCS0~ z%{4NYna!FIn;6S(jgL(LC&aR$ivNbs+>KA3$n3_bIB(jmMP^Ro*UFr9hFK%?n5*P! za5XGh>Gm)&mKEDeABVmC=H!4ayOqQGFE&2*H7tqEKx?1K>P_J$YJHQ{*8@`<+R4d{)=_B64SjlQ0pfKgZ{MN z!q(IJ)~X?DitOe(xn5?c|I9j>54OC#{cwd`DKlF?i(f=$`b+#Qa>14p-F{c=S)>

}Yi#V_SZDH|M><>2 z>4V!DzGso%@bp4YUrkgO1z-re!Yq@^WkxHL)lp=`z7ToH%}pPOe_~@}U(qq(MWhe$ zy;0;>71cyRbE#Y=3zAj9%wT1-z7QF(FGXJBgANm8V*kWCk@GUri4FrVB7MmUwEk5@ zRZ)oCf^@7|ESJba<`TJ7rnfR!UyAftCy|fbpgYCiu`#iJRwYqc^s_39Dqt1S*D7o- zl8a?watoRHt-oTUWBIMovA@B;WBKScP>HxA#1u9Qu$rH~1C>O7u%f6Wikb`MB3YEx zB4$DB&)8qFg2WV{E5@IU3Rxp#qhf`uQL#T`g&7y34uJM9#ch;0Y96Ya%x;-`T@ z7m(>9jg{8A#yu9@-94g=+E4ao)9x(m?370R90$hFIjuUUXhMoM_WWzx-4yhJF9s)GEdHz zybVGw0C``8yhrX`dLFl>1H*WBC@02a<;5&`W`aR)kbNR8{e||ywpaYeS_N=Cem1MK zz@V4NCAvT_koV!aM-S%K^m(`+X+wvH{UQzBiuS{>PmB{4#dp>?@+&g_4?l<8*V`^MKyZE$K4xFw%-H z69+{qx+EQh=YW_;%v><&i!x6nr7y}OA|FN$5pz%+5-I4mbV#J6+tPeu=841191@R- zc|>pN7Id*#!2Eo%Km=V@7J>`JLXn8>E5CvZ#jhgh%2HU275|FDSRqkgo~N^Q1F*i# zFE@yM;5xBhWj$G6UWnA= z(-$@CF}fIO2y+A3P@bh*c0+lN{@DfK`_3wWeQy;Ne~U4qDE1Hd54?F~Ubzw6C^m_L za;;bgu7mw^?rbshb9N|dHiE68%r6Rv@2&jU4`9&iqZn*OMQ)i#ZUQ%n&ERISMHGUk zpe!WUh_#}wEJn|(x-#f?RTtJ`W@FeI$;R>wJ-qXY{GzEXhG?q=|X*zrthOLk+ELVxuqOe>o)`+|!AGvw4X4a=L6c?Y0zwkwfDJ*NtI`GuS zl7Y$SsnryoCbFqKML+F4WH+<&V9l)(WPK`1h*9EC@K3Ia!casOl`F(b#w*1tQ47B0 zW;1z$9^K94NqTfQgQuy?Et=ESB)7pz$&z9u>m{+z zL#I%%USS>Beh~MyK!7|_od|I$9_$z*b%q4P*iQoh|QRWai z8Rrza#5gmX{Fi=#S!FhP#jL?6xoTFIHNYBNkEO?8HaQl{F8?ED932F+$gJ`*pZ2i0 z%qLDkFOn*Hk$>oGWiyEYzcVNGJ+iSj==UOtITmf1xPF`1c3 z@*noe4rZ4*~KOR*_ZZ4dSnx3vaBMf%B&)rm~knG7CRi7CbNjFVj2un>t9WAW3OpC+fv%p!}J zYtN>PkaTf72bK-Cq5B#8PAbF$+RM!_=%ahvW_`g{w?o_p!ZB&#&yh>&M5PR^V0c) zj*>5(k#v{5D^Ams<}NXJ#B=8b>(8-2%~!;{bZ+ze@tM5MomeVvi#zz++>sLUo;XGK zntSBl6}7o5tz>Pw;{6T&&E5H&z3Q5un}5mCvKD>tT7j)(Ygvz(&*_6VO8&|CPx+U8 z<~(=)G@oIAnXlRLmGj#9jqaAOo!`wr%vqnVK%AhD&I7XUi<Av$2wg;jCx%GLY{2y|pY+#O*qvSj1SGsM!BloRy zUEB~U<#jBTd?b#U$IVCNJ`~l>QnIwH&Yq=YLvkC?5AS#Rhpc9nmSw;)vMgAgt47Q> zq?g`r@^|^(`GvPXzlZ;wb4^?qspK^*wR{ZoBk@=qrLWEh=V#s){ej5$PF1rS-;u`T zHZre@Ya+G0ilvcH#1ZqT`Gok#qKP>|{wA9c)7bn-?g!_iGn{u%KNW|}!{A}M_dF&3 ziD*h>&;{^UIYNfq;Y5erpXk;3jL4_LaEI|$YlE4P+l-i|^a%V#{wkk~gLDUaPRujW zoS9~H2OKVcmd(wdYCKlFWbRdVHod(qsOr@c3-gO;0MWe0fP+1}~G-NA{If%|6`I`(Rb> zNq?C8ftAe4W(oH*_kmLad+3ycxuh%Mn{G;Mh8a&@6qiIi*nHU=ru$}Z?1A|mx&7sL zvZ7hZ{M0SsK6F0C9yz7myUsoE9$Z4s;O*f;&NK&ulB@Xgg19K+!x>NZk`K&>W-nMD znBU6^bYA=(w(n$d_fz+gQyhB?K6aisW!&4&9q^8G7rYC50(o9s5D8$5FTa&R@1}3z zduYbwU~>p4@IS!$z5GFzH!GOM+~V#Nrz|{WTvx{A5Hq1XC(et6@Fb8udMd73aWnaP^S;=@8We zzWwGv7zW6JvMe1J%fnF4E$`lNZaTJfU z4w7Z)+?Yh35~oEHd0LzS&xpkGN9G5CrRnilk@yO3MfaL>-KpqacWyXIiBBR2v-%@g ziq4RgSgq(LlPAR~k&M-(va);Cx#m=6zLGnHn89+0EJ-KHq4G02Ob%r{L=Iy-6f8mK z$+qAy*_Ll;2|81MBR7EEAyQK{A7W*WbwX+>z&EJ@x|ZE)SaPne8q& znP1CpU^n^yH@UwMo6WBBYq^>EP3EucX}G^)VRxh*k)|BUUVqrH*sZYp3M&E@af`a| z?R;*2Fuz*>EWqBs*uUCg_ZKVzM%+uzC>TcCqwKJZ$d_;wbzfq|+z;fwx7V64#7nW( zd?}8B>$uv&PqNwEVs?>T_2TohUE+UrCrS3 zO8geOb9a_qWXQ?uezZeQ9yhN$oaoEWaQm`z1^k(-zsUO2{>u(YL$0P@_c5^=J1(}7 zyOkc;U&+qWaB{i1UBk)k<^l7#A!n6&T$~WA=;?i2Y$s+LowL7`o#b}2ll)5lWDmEm zIHTeG%N}ii5Ff>8`=bcSFg%76c5=G8+?D1DaZ;?LANUEegWT=rF#9L6hGAEozsVYn zP(Fv7(~S@xc6ORy$S>tiB6pZ$?04e57-PQ|AHWadZyqgYcXPNV@eya2*-?HWcM-qS z{D;Ufw#BOH>^9rW4sy5IL3RW?5;2z5f9$dLTk%fpVRbhh!Q0C{U_04f&H{t(;B93) z`7Qm)SJIVx1>LxN(T#jLxSXq_&LjJ=ebjkuKLMZEN1RUfV0(z&2^$IywZF7`l6g|} z#FELL>R-#gXgI81@Xh|FUT1RR(7knU)WdqjrxMwtIk(2cd~oX z_dA*FfhCuH;OR}@@1^)d&QtrDeaJbCKkhuRAA%36Z@CTh|_H+B7a|nL|w&P9*yCV!8u&Q8HH;dcF9t2+(th4=% z+1-34`jOk0?%Rv;2b|~j3;Td`5PuSe6V6HJzWu;%Z+Eb>xLxgmWOv27*xl$l{z`Pi zUW2d28_^$zpojM&{3++2ecwJs?n$Q|nOWU-aAa}6wg zJKw|ho!Q3D=4N->*lqD`?Ch@Pd_yjo^mboBzw!liE6vY-vV#h=bV9bmY-)1#0Ho>iRobv zVrHN@h`#f4>2W@X(T{YZpJTQJgWl(}@X6gS^k`4x>~{7zX|U8z3b(V_#Z19`a<`4! z+HMWDv|HJ2+*WpLyOrCTInZtcw&C}rEvs$ZROIe;Qjx#MNef#Va2GzAJJ$Z!PUgN9 zW5KTGTanC7j!)@+MGyFt?3Kbz>LzplwNtsB=m(#Q`IK%;w-tA+B^Cvvj_tH#m$q&@ zw}su(PRUODoRsXg*GcE>aCU+_*)1KG)@k9|&NaIQ9JbS*_;zl4x4GTIPC?FoCk1u@ zOv%+J(h{%+HFSkb-S5+-M#@f=c*%F9o&v?Q@fd+!P!P$1}wdk zh#h*{iLgFkAG@!e*6m2IytJ^TaTB_U+`e`?x4qfHOy_o>b9_2h)4EOB;fDQ%+t_Xb zHnE$6P1z$O%o&`F&K74YxRt9+j5C6p@d@DTYbU_^*`L6f&TRtAO}mMElkZRySZ~;0 z!uf@p-fc(k`t-zn;&yTy*^TW^%zx=-h9{Gg!EH;Q`wYaScfVq_6WGvhWM^?Uv7QCX z>||w}1>A_w=(aK2niqWSrSu z8BOf0h^~w#auPdB?fC8zd#N4Ijqjec8@ng$lXfGwvAaCFf~e(K5-^FA)LBLR%IKNP5>^!FXj&QvlrVv?Qg+;_+{+4 z6x6QoF0*|%p1Ul%Jet&54gad>>S%l?fwPF%Z|&v8ECZFR-DBL-3(hh7IQ}%doU%{b z4cvzA(&#dBmtx7lWKMEt4GgQJN9_yFMdzq}(OCx`;N9?2aI_E68XY8|fJ-5EQlB^Z>O51al zyDsWG@tk#Jt&JWgZoPBZUhixGk8pL){@ktSo+In5Js+-m-~#+Aa#w=FmF_BAx}Lip zo^{dnQRQf7eN;QXGmq%{_B=A`*{g|MWgoH++Z&woaGtZz+jZQ!?s>be`?^c10746yhidY4^gLA-c?{skX+Xw9Q z_JZgq;QZ)V@3+hI`8&JiVVTQ#E?4Eb?&4O0 zzoK2qo`p|me*$YdY+*D5%<1h6_Ppr)XgOlLxRvc0_Ds7nHVd3ZPFwcN=CsAKgYCHb zg1tI|d+mL8TKE=5(_)LF8R5xbXSC-;=Q5rfofmCGMs}wS<~Uyx{{^_m-fNe&%duBk ztSi{nt>#u?-^z9x_!dReV2h)f;K^v0A-0;^8V<+lMDCa1ZhMbi)t*j9Rji7gn!Lr) z)Yy_}X0kHbneAE8*^FmL=R{kP={l{j7}%Ptubf@>Zu={EIyt3bukMy+pK5M3d#XLn zu7*tqr^B8Fp3HVBySiJ$EoGO+S0|>L-4dpl)7jZ+@3K3?_LY;>o*A7L%}RV0y9H~) zY2mcQcOj-TxWnFQm$YlRHQkc%)o^RTQ{Ap%Pr+v+H!C5o@Cd;CWDiS{+gJs&ezU1d%K;3nC#%x=(K1Kds=jQv>WqZ zJKdbE_BOjVxwY(^tmd%m*yHU9-~{ICV72YK%+#^-@ZB5_j^}!zQ^NiX{LEh9%ypC5 z$?dsra(j+D*G+0Cv!A-noaW9`x4HAgoy~j-d$yaxP6^K8Y929j-Fa>jJE{HH75tt& zCbEU|*nNV3?6%-8J#(8n&A?``%x9O9_Izgne!f$Z-=Xh38MZl;|tBq0`8DMea*?wzJ9JY|m!5P4+SvmO9Iv!gdkH zMeL&XEN8Z}8Qg4dv6nNy%vlWcB6qPH-%emJb`#hM?R)GnCHmTJ;52kz!~Du!!s=po zrZdagV$a03+AEwwc44qEEO*^|#NWlHM&G#god(Vua$mbEiCN*SbPC#q?4_=6#{=Wp z@xl1^68G)@*t^d#DT=p`_dPSaHPby^GeeM^bIwtaoRbM7B9cTz5iz2Ya~2Q~11cgW z{w7oeGa@1is0d<2R8&MkF%T3u-@9r)A;j@T;u-Z_Dx)n_=honyDxC$d1^YIiLXmEjyIt;iNBOM z;hvx9OYO_J^@)b@M)CEDM)Ahf#*BEGBkL1)CmO^X#_wkPQC-xs(s>79tZ7d*C*ODa}{+J$2ze>N9s!Ys?2@Z zt*WZg*I>=+>Qm+(a6eU_(SOQ!4T&zy?Mz)kUs&HJ)_2WKuH+x^H@7*8VuUPX-)h5xF)!NX` zNpxkkF4TwUE2+wAm0Oz?YN^`les{UMOMSxI8M|mYzDMnIzjybr&R6OzW}cfki*_Eh z4SU^Kp)2)4`a0@9_kOnyE7Vpy)h?yuJ87x-*XlcWpZhiI>`|?mcV419wZW5j+w2PbAF;#qBVUFW_717r?1D{x~iVK$Gz9x zq0;des2{V!4q7_?4eRVxJrnmcwkNGeqQ1J@UFOzT%iMdY_qg@cw`#A;tugW&)r*lm z6TK4m(KldZef6E%<9_Xar@nUgQui{hH)ne#dMEBl+)KTey@qP3d$-$=@eR~I#($^! zaJF~iY-%6sGWt5yv#EE}&rY0~m_=<#KT?%b<<)i6k<>D(EVV3qr_@L4B=rOJA@xJ{ zPOvX^hkC(1!PXAt#6RHNOdcO6-I;uE&QHvwonU(wE6=30O3dL_W>cFdT2NcCcP+P6 zUX9|mu2VA@b<&-iXvX=uv^j}?Sp7x!A8zLbHxl2@?MJv3Cw>icDyVDJwe;6BcNDdh zDoriT-rwp)cdh%kTI=3L{fE71e4E-%P{VfSPv-{5~tiRsMG0>a|?I5vH1IHtBS?9s%_M5tUjOB<|S@m)@XH% z5sTepYO%Y7dYrv1#>e7W@%PmGYHDIy;!F2V#?MdOnP@_PBeQN$H>wi!Q#kjPJ0kXV>#M1M19 zZ&F8?v(!DJj?%067WJM|tdJdF#F&MNMTv&=@%X!Hi;8nr#cyHO&FU6)2K`-}U6i;h z(SSY?e@AWRQl->Q>qq=FnS4R7blh^ z>d`NyE}_T8Dm{J25dSv7Nfj9pL?`{!#4w#p#H(FmT-ott5gY`lwqo@Ge`}l4pu{`L%8jj^Bk{bV$M}+xFRuLT}{23dmAb7 zsuHyvuXbWiC7$+1?+jFfRC&&pbGEqexj(2a?nd=C^#`?4UF!Ao8dDpqj2g^p zgS^4sZ|blrhS(BwcCf-n?hf~k#Ms0RcWh!@qJndU8mKC;W_jllFQW>nOT0p=F!fUQ zhA?-qH^lo@{ie=9dx<&kx?9}0)yJ%`!>#CCt_G-z&H!}<^$J$m?7qv{&9qHwCu2T# zce=MH?nqqhUE&p1Ls@5tH`F_%epN;BV)(wWLPeyQqHMq8Zc^{4ciheNyWHCnw3t^bV>+)I+RQ+3Bw?SCv_zlJki>CUINh6K3slhk3uKgK8Kfuk;GD zb__k{GSy#IVSHt0w|i@1Oky|VKXI>OLA@2IJqeaB^+ z$JkWHZE|NYYdUo!eM?4OsAqDlHLJDqrZCTqPoa77nT(&|&UD|RZ^4W) zss-&fbrvIAduMs)(@%D%xL$lREg7H1$eHdecLRNMuZ4G;YEHXdweimN&hy&P&ZnNw z%t`KKHyNKq`%%qi{4962`-b}_^-cDgdCk4sRWsVfsx5QdcoW@8?vH9BZNHl1zRuV= zwApS`?_za{YU(wkZ|9xuo#VBmol8B}YwJyLC%XI91lmv3pVR?0m$`G?Cf+6LQq{z3 zO5fh=!@TyicHVe*f_p&Cb6;cBJlb5hv3IHJry6@r=sPg7y*Hn;^W6FFtMnbc-W=;l z>)_qVk@@bO?#u2g)K}Q+?m&|9P$dX2p9YMeXX?XG&zcjs#x&XMu_`+KR| z-8JE1-bu9B2sD;d4z}L}_?M7Z>w)=7Kyo=Qqscxz}bGy;5_Ij(^+}qvWtk6r{ z$=IsSowRDsVn*Jj7OVPR1FtJHuBKk?jqv&~zPFmMs$nF}SJknQ<}m#C$xu2;|Nth#$Ws9osK zQMb6ay5}(KY&Dm0+0I;MWI1=MI$mAxZpJTF=Q8FTwM^CWYJ1C6ZLbcs4(B?l&Z>tu zM`hzN&0%)7(~TX7NL%vN*g?_r%~>U@r$N4?3t*`1~M z#gH>g@k?jwZ1(PD%suK}Rnx2G^<~WYs;|1yy~&-aTr8)VY8L%{oV{1wr)qdLy$d+o zS6!fPaBp;HsF})h?&tV@>V8$-tKnV9@e9<2>Uwvyd!ZWb-r!DGGZ-_SmUJ%S_=Rek z@_7cBruYRBbvk_$j$fpjs8R0q?o`gloXK7XHOZUowNvfYWUsyIpeFLwcJ?On75Ai0 z;`~HfM>T~plf4O?>q4DKKh{M?YN2^fB(@*!# zQf<_9&Q9~ja43CTC}Ox3gE>o5l7_ z>Y1vQnoXVM&GuTVGu0gGY;TU&LbX(LsdK!!UNhC4?dGb5n#cBBZ$5P%wW(^RihH+t z#k}I)t=<^w81~NK7OGRLd-tm|I44JL<5&sr7Dknz759pAZn-MTnfp~qj+gL?aBR6M zLVG}!@^0o>DOyRduy=SI!$vU*5Z(zC5j*m-5D|2`c4HP!p+X_B6*PstVpH zMpdAd_k8vzDc{rd6}{^?Q;}A|tHgFi>PY&eH%U!aNybi6o;O)dp(g30j^|CGj$~Za zsl%04)M={bvwdUYCF0c_FTysB8uen-n3qM(^0KMfo}wx*PQAvvmKygG)N8rTsFUzq zs_S{wQEn4%Wh(c~s53=PWxJABnd6l`huTCn<;Z;R8n$2JSueuBM3keux$cWN4S3BQ zaqi=torsg=-bcNH_s7u<_$^Mv8N%-!BPfkS$cml8@5Uoe1wLJbjF7C5Brl#%YDSzp zy`tF>XE&dHk2rUvcT=nI7eo>M3bRTi!e0qL$o5_Is0x|8sJkP6hIOL5Is0>}0$It= zleI+T9Eo5Nr(G<=_|>E<#>n*-MQ9vp>M^Ga+0-#-1qr}0rw0kEG3P}xEn`lK|#j7A7|%<}4(UAm*IpFTP{WCjPpX?-PI9$U6KrSM3=EI~zBl4C14P6LkAPl=VVI9e4e!Evl{VAX?0cn1wr;ukC`AQV`Az9 zg#JVQ4}yj$02%W7HDi2Q6>1d(1~>JD(S;sI-^fA{dW!lK)<$lse>w8}lgz71t;*Ns zr5=yEh(eEHc8D?bSTu$r^mMcc$^V6s?8~A6c%=6S{h+6#QAW&(7UgUatoza=?MrTd zS$v>qYECpln;Vq`{-WFs=OTPKoS7Rf#*s5(lC)nsbxO~}VmQTx=DcVyIln~g-)Z?a z6+hPx5;>@`v4N~5w23>a&AHExi5b)w_2-nHk0m6EP{Y`KOb453FZuS_}>-W+EGA3X758_1t`V+H-7qWBYaP1=85 zW*1FKs(gfm_z2nZK{?1;Lc#R-Iq|o%!;>iP;27^ zSxe~je0WiWTIb}z-=nP^R5Mm9Hs1I_;}L(x{g<;9z!l^rq9F!pY{dIESUnfU@IVREldbx3bL=mb^qWgMQvAOO`QG`mx zmeNYcCb8PY=pOtP?cEK*cc-RjbV*n$#s{ccu99(XKbKj)MKRY ziyV}z2nBQ9Z#CY~ttf2274U;>Lc2|CUxXrbJi3VXH!|B{6ro!X*ADB4jSyu0Ae+r@ zbJ|4?5-5oac1TEv-!Xclp1N3Wv#sYz5m2#Guvafatua#odli@fxRNotoG zA*cOxGw4n7*rVjJN6B@Ug!U{F)+Mdo3UpSZy9rOIP3$J)(^2Vf;(KuxM{YqEdLu^; z`Vif~nnAB>@eafi`a8!G3L18Av;Ia>+$C|{X1U*}+aLtph-%j+7PN%kAmcp?@8?zh zQI2qDwY%3jnyp_a#XSq{XYRj*AjxunJ0=!h+t|y@+!1|Qi@5MID}983H|k$HUT%K- z36tEOjSTQwOmRi=8Y%ACXnEoajYiOGOD%&Cv>rL=ndnfJ&OeNED8LlYeA!QSxll)sCH#ZXqRmEEhc^4 zrnOtM&nkYK0%p*4NO4Kw?e}qO#dKejzTcPiUWo;bLhA(WVXa4vOSnqk%jn`%F%|BO-N)YfWW2wc zlk09X-hT*4g+CaJ@GE9Nio7RskX3}ND0B}_&>w!mboW;=1kNMl{neN_hCkr@O+gO& zk~WR{6?@A}X8tmhrN0a<=nvm2LRJ(CX1wRRhr?Lu3uaG4{&^}-4ziZe-N-?I`MHVi zYshl{$ta1UA`U|)oW}j)b7mKmgDy8o?2_fahAehTfnSOu^cR-UUswRSe&P^gCk|yL z>jyn*grNK^_se7ADjvWET5bHGC$WKSin}!yf58_Ni*GQaL=Jk)Jfin}ouZ_m+#?lL0KV)k;C#?Sbweu|3KSS>9n?l#wbOpgAu z#CSlW8i)jR#1~iS_SpXDbRHr5qd%cFir6?EgK;;vRD=1|(~|Vwn_TxkB*RxtOG5nV za*$1Bw+ZdHvi4S_pRKqEx6-!9g0^E7^5M@h`R!-NenfbD7w7R^ETLN%yFEt*s+>ND zO#RB~D)c`@f5Z{`!B|4I0x9l6|1p@&elx4AHcrrX{GSCVL*tD$B>v+reF!!3V6;;D zT<(jN(v|7IkN$uo^u4i!>I8DygNo3vNRDDWew-&l-o!1e#`{@Ke*V7b_xM8lj4`y& zI6Qn+3JL2`RXGTs}K@!lZ)7svlZ(%Xt-c!c^Fp5FU- zi62wNuZuYE>+k&^{JqidY2Q%4;omA&&}jUh(TG98EO$wA-xAs9e~$(!D&&)TpD%LI zkIenS|Is*-;!*C6o~y+y#nd(lI#AyNp829 z@S;-w=h_WS#!u~$e}Om8OFy+T?% z%KiS?dJu-f*=Rw7(0)V<`qqB}UFci?J9^1)uSouSe%|{5X8q)gNBLFs8(++zZ~SlR zzwu{a1_d+Q`{=>EdmwVqU|gVUQG~20v?=lqYi^=dO8?9{2Ym4;zl`qnzwu|r_R?m> zdTU9`?~NAJE@o5QZKAt1hO9Rf)GELB_xiJPw4k6L)C(=BeXJL)1GNLW{rS1>CCF=+ zq<09lY4UHN~>57F#1of93*N`)MU9wNp^oTB3k8_IFn*t*46b;CPkW@YRsSk zk^a~~J+wGM9b^5CI@CWR=7HqBzez5;~lU;ae@p%0YDyiKfNs z=xHcDb-10WvCAS2(~a~G^U6bB53GFt^-R8PqY_j?<#u6%&Zl-slPl{am2~}K7 z>k3uZHT0FS>a<}o&!n|W(z}ZyRG7^Fix7nhQziXh{K{rp65YLYP!zIerS&VXinK!u zvT~5kZ?}o=E%iqzgjTM!isf)dUX`N=X_DT3lj8nT%5mZeR17ft8_OrZ;~gqoRjcX1+z#U@5X4w{HcSzUk4 z**z&yfi8%MTsavn$jU(%MRw--K|9e7nv(H;oLu+gF0 zoN9zht5pUSp$RyZ{q+Re<+=$e?*EYD{tx;3lHA@R`UUFHu80VgQ*nZJVJdu%7PJd> zazf;CoXX2_g@Tq)W0UmXm_+vzB(LXZya$EK&+vdg!2|jPo1qbz?I%-K4zh~SIMyD3 zYuOrIXdGLuwM}tvWm4H~uKNshND(G0=v=dMEC%6O|5AjWCs+SdETQKklIY%wg!X^u zw4d$-iC;MbM{z8x-9c+ZZG#-N8(rvy$Zpz;)E7zeznxKSwe^FnC3L!9`3a)X+K5eh zZ(}msXB(T+Dwg?K?row!7&FL9LvxHxIfs$65rKN42(>fG?d_?O*?x%p_PLCigIUru zPY#;Lk-3q1k&^g^^CG2C3+G2lASce}$UH>55^VK2O{?sO8FXn>%%EMV+(dWDa=#?H z7N_8ns7|M-A`4w&bRn^U)?!PJ$+IlG8&^ow$+o(?(JF&x(66M#ABy~Ha@Qr-y)N1B z^+=5Wg&g>L_(A_xgu3BZ4o9&Zj#AXks6au>Qu5n>jaETKP4 zHoHxFx2f-)j4sp(`>=bYFIvzqm_fggz<;_HB)RT?AXVn8mmQ4?)DbZr+Pmqhofq_a!ryQH-rjRc(_t5{mm^1}3WM%5dMOL$TGT4ckE(jyV}ny@WC-ZjXH zj~ZoiRY0g*Wqire0W+u)Den6sl}x((V~l?kIdTB)8}1w_nd!+dj_; zI-f_6)q;YGP!(3IoROsWeG$oQ|AG1g3HOh){$td(2$;D!?cb8nzLMMApIT|mpq0k` z5mBf;u26f_grFkyFk=s-f*xfxGTy6ZB+>obNI@-V6wbnRw2o29c>gg{p0=O5pQQg4 zc$5eDP1FHwAnQ?Dn^N-Ie~O4J)G<2J2o1SrP%rc!D+k$JcboD45G!p)AKZ)&WpEfq7 zwJfb4bh{CP#H@Te@{Ca_#SFSVCF$<9Gj&XId(aP(EcZGY@hhK+JZoIS=cvzO?lna= zTw`p+HEcf@xs&ZRsFL>^k8(Nx;y$R9%Og*ayPN=bBI zP4>EE#y@6K^Q|IeU7=q53$BdzG9FMbM9ZNlLW@(!@hFEyJ4JgUR1S-ZN_lRoV6OXP zP8rhOC6E76lKzncnDcjJQA)&xMaV(NBO(V4Lje-CXcfur8S8v^J1+f}SyH?Kb1x=Djaq-A}QEJ|%m90iw`u zv`KL)FED1Mq`N=kSW(F8LfwoI)D7QI6rs<^>c109=rhd8#pshkv+}t>u6tJ;#I8|M zgg!?R8k8E05hRw-MMk9*x$?r4O>wu0?mx`MsuNqt{qa@`AM#I?N0 z_(2b*f@Y=7b+;Msmx{@UuqQfUKkB8ZcMBp5BQ2<6-`yEm5SfnqGtKBh^UxzZVMt1< z`wDX1+fsAo$}Z@T>y2MI)e*5^sv~m2)EqfzK3|>ngM!A8&3kWWvfs~Qy%prMuW%lw zK1|xZn3XT1POfKVu_wDmsfa`CaJt5&Y@)kOch8lBW@83T!4;~P5vQ^f=A_7%FEL|W zO0wTqI+Hn9-sMOKaxH6(H-6=~ z)Fej?hDoeiKNHM#w?gIXMwYZ@ z-bT7>$<|8ln=Pp=*%ujT914&qK~|^~OL7fHrAU=)O$NK9x;G=&eJy$I)(o-TaW-RY4DQwzLwPY#w4@{&7e&5 zAx0Ze<>VE(I%hB6DpI)i<48<53-g}KgKR4 zyIpeKOGh6=pA@IER5WM_1vB2Q7G&k1e6zB2G&j+`Hp%U8m|XXuA7tf9$#s7tT`sx` zcds0lWm(+3NAL>EbEF)`-6KZ2TZwNNbSg!lOh&~A5+z9dAjx(A59#jzA?aNtpruGa z-4P0gXRHl$DJszLjMxU(Fn&Zv44_LK@g^syPNWxL44uHW6x~vcA?saQ`?96Ujc-XN z{8Qw$+cfwm$!xco@Kz48ijbH=J)DT~C=2SAC(;X@7Uao4W3u0$Cbj)Z=0_PBLGHPV zS;J^O|BDCoH!~MGe`8rLbefa;{!F?#?O8I~|DFAgKZ!mW^ee3;bY-R|pScntsHfA6 zjQ3|rdVdyG;CNb$q2pMViyWK!E`DVU>8A$C`Jx5YKmoEs(D_I})(JY69)&1$EPXwq z&@t8+<=E8sb|$~w=D>>_Gz$BtCTaX42i0_}S!or^qd1789m#udhZ8g;Qw#s57772S z3qi^ll;TvzP$)&dJi^QyoFiz9qp4!<1QX!%sSTEFMuLucdaO4_cOYne=r@eP4tSG&oZm<42sJ zTscTwgsnzC_yC`1yCbg9z|4X`GQ5>5tzs!!ZGjp@&HC-|Va)y?-;e@DLW|FG!R@#ZrvMvmMEGUxuc$*?BmfFAD8+&Nfb^_?3M! zrzg5wMd%#kQHp4JcE;wq2Q4AdD$mK-6nC5G9#n+RVA%1hwn2IJ!m5ykQhRn5GAcyDazzwBUc{sW{}oy^W6`6Gs$@WjZxO1JR2wSY|Nja zJ}Gk0!+1Yd5fbUZDng)lKp>x_2!VyJ}ocZ{U8!$-vXB9)wn`k5rw)&szic*(C^GT>`A)&wDeD8 zxz97oVBgFy#vA&@ctF;yJZk*P;aEadBEwCheozz&CcOt$%3MY0HLM?N3H^*^cwy!$ zM4_sPLRBNxBBy7$A25p00iy^Vz-7D;ZBpFHpjIh<&`l^pui^v^Ll>%sE>ta2Jz^8! z^R>$37(uV12p#bzklY^3c(+<*P!W=J_aoj3qZ5iy*#tLFRLh_rWOLnZ#`{Sl9-d_U z37ox#XnS86Kk*B;Phm*@h#gtP2th$n=(Du-D)%E-iZ^+{dDP^t2XozXyqOBC~54g$cKM~_JbERgT$l!5nEDh z%iYEs+HJfcwsX9p7Ote?7=Me6pGLT=@jjbwDl-;XD-g7x-$8ae2W zw5E;41b|MtM|e8Lt}Apo?vK@ltW#;t%8yYG z*E=5@MaWN%C9B^@8XB9HT=&&pGC7VU|0IggxU|SYCGms$iwcCN_%aHm7?fgGek&p+ za-~glx9RTU2bD@1r!sBx+k=VjWjLFw2wA7nnw2)oJ!l5)OMit+C|c#$RIx2>mb=Y$ z|33XC*5UVz*@vh1C0iTQUpQZ)*?oy?Czj+6^vDnMgvy{FWRu%%iu)P3lcG#ao# zI!--~!4NctM55e=Bq_FKVWS8YMyR|!T`jvh9zZqP3ewi|Guwl%(2LoUkpCi<(BD+C z915|<#pyyu6e?sSprBUSz@)F+2atSVEtAZ=w#pVML*Hce2<1@0@CBNNf zxo3aO-$EeDRfI$oiY6;W{(rC zqw#|(GNwYrrnuWgcX5R_W>?~P#YiRdHwKldl_HfRZ{r&})XJ!L8&MZUnoJ{1rXowQ zDm8xP3X|n-linrQeMK@T3f;|^rP-oV>WCz_SIK_pwB+`cCW&3t$+F4C*=3Q279(1w zBccU;?tPj4Eb76R1r#CC5Q4_gU6_^SlBZji50d>}#U#D2%t?L!LL?$D=nCaJmE|yr z7G;-D{^KpetSm=LdzI{}CfB_RS?rSN{y8((cp?ft=UGe0xwT7JB8YvMl%5jBGMMNd^n;R&@p9x! zo8@kE-GhFRZ~V$&io52BuQXca6!en!@)V&IM>N9TB<#X8HHEV$8e>{b#6bL+duUn( z6(O7AZgbtOAG8Iz@)&-lRVm_Xxdjm4p>m=(^B?Vqwq2k$>B>#hI za7m6dB*sC|7<$)OLgGz6YDCMwjc9p{dJNa{V&*-C_HzR&QGcTo-ABfI1G3d6Wj&bm zzS&qpn~^K`<5%v-658sCL1|q}Yh2z-LVJVcy|jkZhNS+lV4a8ji;#w%!UuW^ap5A` z9CV=3dD753#s+!^-SU8OEw_62km%khC!yV@wFh0H3t3}MQvAxlP$&1-L?U(1Awfxk7I4#qW-OtgXxSG_XdeDgz9nQ6-EF%2Mhu}X z#yfl$fAaS{zjBqyV_#+R*lj}l`K&S@lcz6zt|)Y^QG-U}3cZD(Gn2XzSLiKc32l%a76X4&oE; zVtXfs-Y*!1pKxRse%;R)h|hE6lmAf^l3e#Cq^&O@-CY@>GEOC41eDr)Rup8CNI^#d2oSH4>#*mTzEDilZqB?aOkq*{@^uj>+q?JMy=s*C7pczzE7W zhGNDNiXmFgN{VRd8cV1`vX9XK`jF_pjD&TY(=G|^w*-u#sIi2ih?cXHQR4vxUCWC} zbiasf_B%;;zm`=iB(J4aq*hE;!U)ROg(CdD=s(Bh`+Sn# zMXr1Wol-1J2fJ{1(lM^krJTJa>r#`-F3Iil{SmBEIXNO*^8H6(3{^r05+}$SL)IHQ zmE~XxoyxkJ`;PT4t$it?&~4dP7m}p+OSAf!{PwibDucSE6@?_-ywDwbBXENr~O!p18s!nUY-FJLDAn)N)=;;&gRcttQKPiCD$o)p7U{K}JARu?*5 z5wdyjHv7FdV$jfJ?>wP$L^3E>TFY{b$%>bB_Z}wKy%&k>`MK`< z^4o2e`?uW2lc+;a;x2rPJ@iBYdq~pSdz0DT8v&pPe&w)a4_c?BH7l)R8O(4025)Fa z0dJ@~PGP5HcUtFUU!=?Pvqi2vRv^E9FLP!h4b3EPe=pw9i~`<}6)LS+`89sfEc~Fs zm_b$%>V}5cIoXZYB{?yW<=&Nh0`~^w#V*ON(vnuO6w&esI;F^$lT0?d&2OJ%vfTHe z2+cy%nMLORL2l)j*g<0ki7PZXJ6{nx7_-Kuq`Ob@tz2mpOX~;yYHXm~ba%;Yw;AuE zSpI=bDCVVPxlchx8Gt2pDaS9t-#d&~*pGTCdfsoCi7lx8F!X*!QA`?}(pr{D<5~tS zpy&sPCa=nE{N z1fu0wM9Z;QLRPV~qU9^BePd3#yG?rUYXpV9tkEAoNGu{zguWoeDv>n~xpEwekjRxC zsU2BMve|F+UpA@yFPn`2U{3q_=nDhzg9czQh$3`(o+9)qHjuT16pH2eY(=}QfMvO! zwQu&{GP&zEzujiJpNBNmI!kn+ON~c(S$1~TWmrPiwY0{iq_w|=A9Nlg&o#OF=bEJb zpe2-rXxKkHi*`98Wt%+F(i)d0Ml*Z^&MkB>0`ipbSdMPFH%q*s zy@&`?sb}-3+RN5765VfNwHs;cNMX0R?$4P-_BHH%&8TT8Kt1#1pf~U?567%=Y1KEG&Btns7IbL^iDvlltlM+B(tx> z1bEFDL$4YA=QX6u-($g~_pi`}hF}DB#}%^1P%yt;l)(>Un*)mFmnKpFOQfM8_&@o^ zkku;RHFD+YS?*t$O#UzMgNEV)bIFrgQ=Hf@OmyI9vvXO(V zbh*W-m!BI8;B(ZWD{+B3BLoH2A<1yskU-@3ZyL{jHmEu~y=S#Z# z_^h9eA7ou2o8NA;+_(CF8Nu%e(xn(fKWA;@$W{!!KXDbev%L)gPo%}w9NCUnxgLWu z=vV$^Px~P)_jb-_=Zxzc1MxV5cjK0*=rf`rxv2+V80fv9Tw&DNR&a>GUy6@k2LgN*7vl>a#GoCLVHa#!S+~`&ogr$ zy3k|P$4Jx<>Oxklv~s0QZnr7!-(dzlp7kB=3FMz0XhBvEs$tZj8b%$efqmHCuVj+g zE13lNN+iHnbgQE(cEqBzqUCc~mfs=@J%KCq1UdhQjT01fg(S_hT$-K`}QOl}WamO)GC%&e!-3C~2jY>9*SA4J7g961vWZ#BkZ z368WvuB>YO%4#T+n~Y)^RD>jTy$H$fg~)Z6bob}tK{H4!$&UWpNil=oPHti^C{*Tp zL*FK!#2XUtK>HJs4z#g{B+NPU za@~uNwl2x0A5R;Wzk3Qa;6nuM*8^u<>Q8beRVi<0I4G#UTJ zsL!zXBCEYXmb)g8T@u~XuIFDt?!AW@bOpj>zFZkJhBhSMM+n-0VtI%v-q2H|z852x zU9-xY*o0dVCM)DQl`h86zyiilZi>54e)}7Y-j?+SuHja+NwF!dQ<-4SAao&@KIjUq zBlZ0ya@{4NUDDls_jOdoZCS6=wxdmoS!w;sxIc(&|2W3bAatQmF@wYy`kX3Kkz~BD zixvobf`U6R{v#=EtIf?B2ZD<$3i<+wE~gRW38(fuPtOOf=%E8LMRiIcd4 z?T@hXN+2gb!;u|0llekrBcoOZbKQfkkd=lyo9y?_q_sbhlg(~(+C`e&p4AX*>n{|` z?WjSgiACK6;#J*h=t6VpgSwDN zmw)BxmR7p#Xp;LoveJJ@TbG>n`iwYYM9aSlD3-I)7^>q9Rd=(fbJz>2LmkL+f2u%o zdp%#gp?WBmN2sFzf-zKr!Z1%-Q6k2RVp~c9BN0SdS z{(&s(T@E$r`a`jV?nC~WkY@?qg>-m4Y0XOOSH58K*d@`u1&QpE_CCZU_76c3x*rAT z--?jrx4(d}cpOD&5zgZABcO5;?DUs(~gQnbs{EumnRySSDsa}=RfY(Ij(R}RzfQR*rry|P$`Q>c&P z>6JlL6q9mMo?N*AvvM$A&%hir$SOj?y!ZBj{C3H8f2=@?`=1FhgZ@m286@82BD~8* z$U#TZFpngT8h29c%LQ2?5IulHbT0P6Kvx`ufjKgfC`DE#x&lk+JQSdOKd2q4?~mmr zy{|BN?GKap{s+?KJ#ld@kCMIKjxlX%k5eBfzh4sFJEKwFgBJ9ALbM=}F7JsSXZ*2* z7?<<2L>)R0d+0p;g#qsQd%~D zX8Ug#gtx|jqm7}CK?@2Rm;IU35O1g<+57!bhZ+=6hpbj<<;u(OgBrz8_k(hi-j|!y z_6Nv&7yIzGxa7A>iu?Wahd6dy{1EN-c+j})$BK>dbuOc~ijXyftREz~?mZAK#i_Ke zr8O=cqg9Guc`9KQAu9^mTz8xCo}1z>`R$@xIyrujwS=M^iQw!_!!eAxQ}GaEY)5hP zrXVnWotVnLxRQtPBoE?LidK2BK(4!0gsdnuGmytFIqj|gODg+W_&_(sMVh>wdJ`hg zS=@q{m11FvT=@&e(7MEWYCpFz0+4t^JNfRc%W;T;_RtJ+-CO4*y4!U3kD0N)fEm;p z*Yf6gdsc4eTGw(q3GJ=PTW?K5|8$e?Z*$sPVOHK8Z$-N$ZiPy#RqkNLmvMz&Ce?li zy3qOpy3jP%XhYh%q`gZ{d$YuuIF+}Mp(vJ6M_0^CF)M#ce1t1>cL7%@nA6@8m9Q^1 zp_oC|sqDn8j_!xJLU*GJNuvIT@nvM}2aTcJ{PspBm%TA5?w#H55h_Ki{E;f=f<$xoLiC*G2#XiStzx;InfDq?=$;%)$R@hmbayKUSw$%5 zS6b21=DORAck5SLKPV^)*+h4n?rtqh>sne%s0YSncU-=2FbaE8d!XTorC5V|=w9kx zj*30m9CNa1o>>{Rgd~%FGWqM1NPU;=_eqJM9CQr1Qv6EsgO1TgQk&yzS;f+dmP3ty zFf_*@+Lj{_-AlUrHnQGx)7>T4eF#oaZ)$HegrF956uELF+GM^{DcSFn$$_6trvCdT ziT^{A;XiQm)8Hp0ju~?9WVufzRsD{ROOY$<;b8u5 z{Gi`)arWXj{=uFYL-i1K>XG)JD-FGk7G%94o7ryj+r_f1=f+qkYDA%tISK7Htv!pg zylIVMS=Y6SkQIe&Hv4XqxNg(hMYODgs3+!S&=rzY_T8>Z)N*T6MJkLZY9b!SIiisC zYPdD=>uRzu>g4YQPre!S z0n+7Oyvx1VLn2*%oS4k)cS&G>mpuMi%$@0qU-=D+neSVT z7POVT+Bc9Vf6h}Ze=)iDznFylU)+Q21&yJgRyo&XwoAJE8>F^NI=uKnH{<_Yl;;P% zZ@i)Rkr3aEOUCB3BezV3Oh`6aE!+zI@SAM4^A&uM*#56n@3= zFY)pAAu8_S$X6(N-(f7i!jU~Wa-~%)dz!p=$%>c6_;Do0pKb}2HBM!&S@|BOP+8*& zRWOdEl`E}c8O)ZKB>A3sqR;_R3zWzOpXTU7Vi;IgsEiSX${8S9T$beo}!H`dvy=_jln6y@Ud^FHaOI zX)K|Vn1$!&_?6bOltlV5q|Qs0{Z6%x4F8>oLhG=AzRRZ~kQo6*rbpaZJba5@K1tMHSmJm{-4pnJ*hlXgw~FC_>d4Sq+8qP5RvI z`Ws24w+Z&v53-g}4Wm`oK&gB)A*uD}{})B5CNiSfeXldhx|YENd#ec5VoXi6yjSUK z(`upBiL02P)yASc1HaN*mXbT)v49q2{UDoBZ&T|hl1|@|bo!2D^G_kWezGSS_3cq7 z#SeNxi5&Doj(2J8%i?H4r>mDD5WSou5S?Ia0ox)IS&ir)CE|kkK?@4_K@-Tp??l3V z8?x?$N%*2(o^-8xIi3-nm89Z#BJ*C-?p`dOluFxo4p{;qMP;R=u*X`G|D|@M1W&P6R^6FNJCrsRjTMjr~8#h@q5{CiFEj-D_Q+BJuwvbta3m8KcU7)|wg~S`WA42noZnq@%&xPtDL?Q7c`f>Xg=D9+@VE|cONW9DM@h-nd6spG8QZ+8><&(xlh&e$G z;ZoLXg8%ayGt0#{s<-hjf4~?jhkf}2M&-ZN%R=Z0F(;@eT!JFh1WQPafJ=<;5EO;V z;vl|_T`AsW22~;Elr@He)fTM0a4~XFvjTEZP`xa}{7tG1{^HxlVn9t|g|gm7XhF>| zgG8DLnn9)Gn=pn%i`;~4nJ-`l)dnjESw%?HhM1GH|ONtDbIc$(G>$`yq~5fWFZIiip# z9gpE!y6BcJme79~zZ%_AY|R#o;xSB{m!k+-QRq=zOAp=B!xDOmk^gbUxGWwQOK2V@ z&^(-v=Co@Nf&MKDt-`WQB3k~45VXp;LP6KE8S}0|1QJW=5mdtc$|{ytv=l$+8Z@A5 zylYW_{;dd|Zc~bGxF6L}T%nc56>7rFktjh;>4T!s!x)MOl$9$*5gLiTGm@WY2UH+Y zgG3av5~WosMHK4bJ&#bi#ubCIP`nd*i%3DeIAblLT!}J;9%wyE5rsN=FS;rA*HT}k z>Ub)Cm+NCA-o^G>x0*2`gVy9iqX>y5l2g}7nC38GCJbT zMGFinO(VCC5 zRTMd8Hlk1zDX1n+kadMl7as5B>^*9h5@ThS5@Tf+#!$?&!edYonyJKInaS8}v^nt{ zt?ekHkV3G@7lj%j;Wfmg6XS0>=i;7-LJHkY{K3W?Z-f{$UB$g=v;;N5b3%r*;=hSh zXhosZ}8(w@%`4RRt+%IA^MOK?CtBHC$EouA)_=iXxP29TrD96lt%zce7Cs#WyUD zJ(%wmT8q%Sgkv!3#68Qm2yf%a7^Jeo=w`R$*cCq`sfomcZ1YiItem#fh z5oZE_p@F0jnLyphU%N&4i{XvfKn*fqaJxV9_w5nqAMzI>&dSt3oNYm(4H^;YOA)6@ z`c95qLqZt0sINi)c@2Lg=A1{4I;vs%JnE)MC2XLRq^-uBMkHRwoS#S({N+x}xre`%h&g?-?m-T^ z+3%ATbJp`I%9t~nPp`$CVti^S<~+qGD-etL-FM7+BGG}`hTq+Eb1I`DcB6GC5vUS- zU1{CO2dc2)AGWX9$9BJ${H22$v=6>6d$4hOF)FG!No1^5EuvODMrfTqW<G@i+#E8$EY#(<(@8&2YED9 zMfZqMBj%{xtH!>ZlMymj=EzK0L)MZNWo>&)+2+=ixqZdIpcelc`|qklpD_R41pneX z{Oj%4QIFo`YqMXW%hznb`UdpA`F{9(M;h?mvEQdg^r@WhVq^Mr&Ud#7y?n2mn4dt} z`~>9Z(9HZKn$ycqsF3-Y$xqJy3|sOOl%Hr3^D~y8wEWEFXD{~vxi8pzMse;Xa*vVw zh}>g}oBNR5lk9yznZZukiX%UQhjBxjsyAMQE>a6I}b+t6;fG{GYB5eXa%VHMIXfULR)6 z^|)N2Hz{y^SUBe@Uak`5nm+gXP_7K+`cSU@ygm$He}%8V!q;En`y1i=8{zvK;roZ-`-k!lZ2116eMdfg z|4`mX4&Oh_fB!Ii{T06c3g15r-#-k0{}ujzIsE;yTp5JFUk*RN5q^Fn{Qa`LcaZxo zeZlwV!_RMopN|SZ9~FK+D*XIm`1wQm1ZepA!|?OH^66FiT>AgtKHnR@e;B@h7`}fP zzJD0Le;B@h7`}fPzJC~g{xJOga`5wq;q_s7eHdOJhS!JT^%;K+FuXntuMflP!|?hrygm$GABOKAhVLJS*N6Xm*N5TbD|~!~ zkFW6Ym7jtb=G%n%qW^dDqr&$O!}kxv|G)nC{{IReU*Y2`e0+tEukii(@csG!i|@~e z?{9?fZ-oDUh5vtr|9^%5e}(^l+21dR`PiXP6#7J=pAzQVg#MQ}V4{JAeu^j$p`Q}^ zdZDiu`g-B@VR(HQULS_nhvD^Mczu}v$*A!9F!Yy2JO01q>xG}+2tU6O{{Aa`eMfT8`!HsD_1*|cdy-Bir|G(t-CLFo0a&d~Sq*cd}cMJY~WvHB5Tr1Xg zYC2g?HZ`058cvM88nl{DbtlSRby^MHe~++NjaEJ99eL|lhCi?H=hYsGqJyz0dGO}!(kdMBqN;(B==Px893 zpbs1V|5fmvjqvdmKEA@oS9pCGUeAZu8{zA(?p#?^;#woT-UweWhwpEMufM|gqr&Gy z`IJ<6eHdOJhS!JT^%;K+F#LRP6+XXK#R;De!{@{B`7nGw44)6f=fm*tQ^LP@ z2>+hw4F29L{QIxUTpNbhhxsaE`2Jz|{$cq3Vfg-G_aub0E?!|?TT z_7;qzhmd>C_T@Rxbv z^%;K*Fnm62!*7%;K+u#*!$ABN9|C7kg3Fy@5MhvD;K_y7c^JNb7`|Q(uMflL!|?jBuoFHXR&c`W!|?hrygsb%gwKcJ^I>^@ zml8f7hR=uL^I`aW*vtu^55wofq|<;;+Jvu{!`I9I@7ITg`J{4`_t&EIMR@jzIz{QD zq)5xrGuVqdDYIXUy{MzjesPS#sNa6oiJEf>)oYKyEf1O{-d5P_H{>%P) zwqK@|bYAgGF!B|@B=79L!kLoJTEDDQhFXTvulld}QRhX!oKu!s9{24<&aU-e<4n|f zfg>;aud^3*p7$#_<*609@_C-)FZgTNe%^o1ujEv8o@0BB|EyoxspLHCS8*y+D{=H0 zwx9K%_NzKooTu4-#;@tWQcAY3K;ne2X2EVrdrvC3Ph&omMcNklhR?SyB+sSgM^d~rX z(y!ug=6n_ZUHU3)RrTXq=`1I%tCQ;yXRErC&~aVOsmz!vekFekeI;6D-_;3@yR@p* zs(hy^`tNbRBCV2N!GE8<3bcxTd4DT={8q+Y_Fr(e*G{YL(a^o{(b z?7Mm?Yd_8Q687$54&#XKBr#bSBzMuWA{{5WUM%~JH za2{vpQw!@tdY)fI7uHYdR{oj(Q;dI_?KAzB{#=gF^Z&!~r}P}Zs4hY+qUZXnb!)#B z^(?Dsb=}*4(0{=1Oxm~ru(qB-2ck| z(mzH$<{$MdbM#eRIaP_i0<$Wndif7AuNSSif41L;@n`dIFHc=g{{^$Yq#mdL!vC9o z4=Wv|9`%p-RZ^8xuj(qaS9Ez+tB@+6dQ-old-^L_wI{8Ye-0~^rJ?p;_OdR=3guJfQXBM}`dsFf^UtM~^?R^pPk%2n{`5a%ozJQN z&{s=UO}(tE(biMf>!@>{U&e3ipU1qi)UxcAWwmmtvZ=T92Ho9%n3cNwE9twl)x-bB z|HCh?zhUh^+5VHgGK?&nDwEo%-_m7LZ|jZvd{%7ZpU--2{cgn{E(#&)4~_4oP3 z^ci{|KjqnMf5%=)#*|8xOueHwvAtQpqdWVLGNUuCi(i5xB~zXJ$2iu>f1JJ(Tb=#l z950b7o_ber)*U(C$&WZ6`X5j~@;{{R@IRt{?C+rN^gpKV@^?}{@pn<9Jl8~=-To)k zPyOB0&-_oR|L`4;IKTUcsUP^iQ%~>{=&oz0YNfLMAN=qAZ2w349=f}(mHJd)I?lW#$@|Fbq~h$)HPEzsI^ixQ*plH*?yd{-&4P5uNy0O*WGlT zRP9tZT{l%HwOe1}U+nK@%}@2``U1X_pR?ix{^$BL`WP!`QTNlw{GaH1>7Keqsu!(# zsw*pW(_MAFRNYj9TbS)9{8|1?>TLQi^ppAt{RQhisXx(|`j_~ha9g{z%lVmp7iM+U zU3C3ay;PKyV}5VlOIJ_zrd3OQ$-F1@m$b+AF5S<+)ZfJlpJ>l_nd{MJ_q@$0O8V=sU4OXWdCR zNYzj6VU5T19@=~QV||(5&;MBW_b;RNV-=tIPxwA-Jn4VUh%NeS#=fUdC4XV9j;zp0 zchn724N^Op^)XMyPjG)>8hr}`3LS$KGf$!zx)D(T0OzF%yx;QJ8$joQ_oqE3BM}HS<6i?knE0(&B6-N2j z`Gx3jWR(uo8|aHMt9YhZ=0bgeE}JRCI%R2R>v{Tn)|f||uNSjYvD9MP8L5%1aGgKW zFHCgq6-nEuj@n&DB3} z3v>04^mEyor*CGhcK*$**WSO@FTyQc>ldZJmaUO~QC2u3vs5=vHA^kkMN`eGOX%n5 z{j4#EHdo)m>~{Vw{$PI)wH^I6tZ*&$4EnqEQr#?7By)+rSQlZnqM2J6HOQaM3Ul-b z#$4kU=4_En;moD_5lDru%JkEh>Y1!COAq&pb7na0YCpsALYYkFGTl$l&_8p225qLkiZR3e ztNar5Y0hRc=}dopnV!y=8Ps3shjI2Qf0$pAewbg1{z~dFf2d!YekkoqYQ!n+51|hA ztLl68J-VvCkG>lHJ$h)ma;8$|%Jk5*)JmC(nUng2zTH1byUnkn?`LckT2)=08TU|^ z@tCR3)-rvHuX{W7HooRl`Xv1jRvVfglCF}eoEeg?nyHc*mcBAwG4l_rozVa2JN(=I z%B)#M*IyN^jSd^m5jy zM60Z8GW#rjoRNQ1$N6LZNXkiV(-GQMJ&1J%rw660WvXU|r>{y^pjOC~&(va0Yh8=k zXX%Ri0oJQXtE8i;_w^y_R{cITLVtC-Tqf#VogSVppShY=E;EqT2Bin4t7ocZj&X~} z^)Wr(ALk#_6a4Xh1^poFRnQO7S7586uFdVVrnc4t^ijqfqfYcE_*byP!1NXA8ky>u zSSp%2r0Xzh0Cj-ATxYR=kQ$>e&uSI)5oR6L0~mirdO*5nrbebNV=vcrY5jFMy@FBY zXytWwDl2u6dXW3b<%}GVzC2wkQ!{gUx^|{k<}cPcqW{v9{E2>9{V?;&(#q-noV`5V zKV2tNJM$-J|I&Zz$^In&Pd&w-?3ZC=SzSi2q`!qQ7p-qa&SZ zn`y&dYv!JnX`N}H>$BZZH_#t2o|$?iD_lp*rvAdC=sLbnzvydN|608xeQo-h^bS_M zmiiHWJJw5Q+R;*(R;<&S+DJFlqx3XAl{%e%6l+Y^A2Z{c^a$;y5~&fac8%W7Eq;*R zp1z*`OlGypv}dIhHI>nso#~GmzcW1|eKnPt>FZf(s=iu#DK~XB>x|Ib(xaKZEqw$1 zHnz5>J7oM!{Y(ee&{WM{%S>b4NVjDDGc&tbE9&fGJ?^ipbG06>lPNDXnsuk>(X>aY z*R!{kHMgZZvR1uJM^>tzX_0B78|xOV)-rPgqaM{a&{pZISYbHTPbE|Dr*CB5`{|qL z-)C!Ux)by3W;(G(z08fwSf!h1n(8LhCag6~>y)1w#@ws)d(3)2-Hfx%GtDy1bW`1# zd37^4G3OC|lfIFDOZsL;ZK1uFzLL4a^p!f5(y6A5XJ)3kZl>Q&-@>SOXwjR|hLvB788J*->UXL!E2Z>|fT?>F}q`pqrDXJ&M8+ud@b z;U5!>3vRgUZX8lKz_HNbu0*JKXgKZ~;YOjiXlN8}Ck-yH>=SPJ z?8c+xy8G^8g~bf}?qY|<0>42=BVEglb~RlMuoiSwaL3&SZ{zM^u4Jf0XqYP%DhZar zeLv6apeq+D3ziR+1IxlU0j)j29(WJEMbA4oGoplf7mNGFl+$WANiM9zj80Ym*AkVfnm>G{jfnGCH28UVJ}?6&|f^Ocy3xS zHE4i!!%&0JKlj%)2oY$}V6vO!;^H(OI6asa6bp(5lU%W2BA#I}tR}ifp@yM9;2(UV z>W3(D^)U@Xao~^Z;=3uqL5rZXXiywY6I^l3G4Pl>>gpj|KU6Qopt0SI zV0sW64RKrobW9E!hcbsUg&Kz%K??^{++Y|}uC?Rr_ zgM^q#K}oodx{|>WcNjeCj<`Z-C>#_Drn)IEmYW&O2x7Te!Ax)lZmkpI=%^DC&^lPv z4K+o32CxYKYw744;P=V4bH4Ru1zkjnsO2!)4Y zz!}rUaI=G1K@2x1m>m>AsvtPsO>?D@c?On(Hb){n)I3xvR1pk^Mt5_AIYD%!Vz^pp zt{tis@}RXs5?UrG9XxYoFi%~6v=s>Q2Q%Ds*8=H^p_=g23Y86>x+kt|PzD+eZP8sm zc=8ANf|+iHs{v2VP>qm+=EY9FAa5|s&2)K#*>0AL>gEM=gQ#wPFb|v?M03?c8s6%d z8lfm|K`=jvg43uj5Bzz9Y9WL3Y9R})hE?@YWO$;u+`$|-8=MVaRh(7}RRODlKD0{c zx${Gn!78D(u4Sl2Xbrg5t#PeFEwOGLY88rPBAVnb5+<437?caj1{;I&&<)_mAcXyh zCS+2$XLxTTv9L+bbU|(uJu7h=z6R+1e@^L83b-b&nCCfx#BcfM6~B>%dCTwLv&EK)*AAN##aS zFlk(Bw+)U(!8UmN2dj}?16GEv4yr&m!9CAyavPz`(Xaw+A8Hr!Owj;kV z*p7}x!De{pxy_ilZWS6<2g~4J?v}X@q4uF2@GS^-z`GD!5JYy?q;qM(wCGwHR7GNC zPz|~gt5v~L*D=%~v=rH8Zi}0Pch44d&&7H!9<6|LWw69`3Uv%Eah*e*z>aVmlisBR z)1h}cJS&3bL3OA$8C-g&O-7diOb^Fmq?R~^9c`8cHQ-u?SspCH{$jVtbqRG2EplB$ zT|x`NMQ#DO5bPG}8k!F-aPwW|P`A)h9oxh*ErM-st7{Q#ciY^LU{|m+_!<28KX>BU zE`evMZW*))wz^+<92xuxU997n*k&)r_pe3@c zFk8Sacr}{it`@=XAd-vdexorG_zSv7$2D=xA~Y}7%h4Lcd<*uV>07WD`VFh^LF*t_ zkQ2-eZH?~SK{K>92Y0ybZUr*Y%?hMrm_N87qWg;Mw_u@;XX2WL=wGDUAfF>>gLKZI zDN@bAoopDVVDhn?z% z_Pct)L3hB_1?vTMz`EcechJ=d=DS0#HdrU5TY{z0(x0;X8aS)V;!8uk|bKIpN;xcUqbES{e^j zMw(t`gI=$DnT>h_xE^0ee|#0IbrDzCEe(obmIV26Zvpo~zt^4_fb-RQfLVoi+W@Rq z>6cnM&%H$dE8P=4y-Ys%^SgYmYtSVq>Wa7}!3(XNbT71a3Y2hv)WRe;AJHhl572>l z=Q1)7H>}jfkXalQb48&&%qG22_ds(`lNX)&Twd2L=o;j8-GgpHce7b<(%sD#y&2pD z-zRh@H_vg`3!Mj^ye^OH5p)lVyJNvoaB*-9ECzk1jnnR#w$6asJ=fjP)7^YVJ{kB4 zTEZ1~M}rcWBSCKT=4tfQT zbeN0a9>McicQQNlc5pj<*>Re~Wp{mo-a$4nyUXVK27Q98U^bW4^$Yq2S-`9=3*M*w zf^6oi{-Sg0VP>ewsfU|k;82rGXT^Rtlhu6FU-gxsv@7MV23LYoE(bh0br$SrHCfDe z{Y~fAL(E{48>t~+E@*bV7PEAAlMSy+c1%)pEhvfC(<@ zmx7ByIak(Q49dH5?gl#E1R3GXWb&b9Aea}LPY=Y;tGUc{y-Vjp_Y81`o~~~OH{idC zc^za$XEuESJr{#4dbAm3vgk2pG&ss+)wxYBvrA_{b4HWF{MNtpEo7X#h4ky-d{Dua zcjuA45M)Lwi%t(u29w_W(Z6*bBzJgL6SeSHa~qJM|8o*W`g_ z(qqjSlL^#yB!MnkoU@_92%wp5gbO1X+kKxAS z`j~zY+z(E}^-!P2Jkaw@LEJwNGv5rtErZn{Ra6(z!__cV5G<$*=riy>&`Z$N!7RbF zH*-xPq zujim=u9;&BLzkj=61W690I7j$fGVzw=>e*QF0MzaeE6Amq#B{}W1U~;)3Z$xp9GJ=$H8Ge3k|c)EK?M^9Epjh zpDL+K=zgk{E(w;<{ndH2a&sQT%msa3|3`}V#|5mYS%J(1a5=QEDy>WDzR31dGfgqH z&cw_z2XW&eeNaCQo&++5tnEtno!3wPB9*O=9&nz^Dc>uR{Mx~XkanUr8^Xl+vq`VKws)n_$Y zjRMC&KjY>xssWnP>N;?xG&RvvOV`wE%^Fh`ZPmc5`iibKnQ~I!c@Rm{R5yQm@r3H3ixPzOuTBZVYXLRWH>5u2QA}rX*Mr@0F_P ztfs5#jb;PZo6JV@QcXqrrJ4qPiPbAr3AcosDmbmGE1FySCU{d>C-|Cm@f&HE~Dt4mjsJfA9 zXjZ6Zx~X0P=StPf{!~A}p3v^__pr-VbKOiYS1ojNuo-+&bYs)VL_s#Hj;^wxU-3ltecp|CNi8+bPPS!OffO=nVSkmhjz1n)Nj?z{#Ad#-?*u_{jR>L z-u8$34)%gB!;Q}Q`rARGP zk?=J{){%5m)5LVaeplPY{!@QdEchmySUM)OFIv8;zV<8Lb$x9gJX(vs?kXZuk#t1e z%rrGiR4d(5FG1&0)!7pL5B#UP*mdxBSL-mdR7f{B&G1V!%}hkS82%+{v1+YbVckZz z*0FUgJ=w&@Y%`tE(AjpfR1@9FGEMa&)mFCw+raJ66Vgt%FwIRIz13_1x0$VAZ0LI2 zG*hj|owL*i=uB`X-Vqxx&s1C;2k)H#S*HWt(zGxg(cj4~ME@cchMho%=~kwt3Dd1j zE7QSp&2$GVGzXdPXcxe_P%TjHbXz?iT%hKw_PQO`9dvsg0jV(E9{vv2*KJH|EvIFf4@TGZS2HQb)fR3jJ z>H#`F^q@UpH>rbmBc9tqtTw9W@Vqdu%s@N9zCwDS?GNVw-Crkw4nig_I1oAruR=H& z7rGzW19rdNtTw6rc8l7q4%vft1GoXN*fTT44z|zG{M@`Y{cS({+6=J$!B^0JXzs83 z>4eb1x{|I4hC>IVJ6s>O&(u?O*dBuJL-T(71|9wEQ*=HvPt8y}#14VCqV9`^eqbVK zU!53w#6DF|)De3ax)<4fcCX#4wx}maJvC3vFgw(~HE+=N7Sk8(YZ)1et_pgn9s=!y zp1xob=pJPE+C6rg+NzG)C+abH1bWmyR!Toc+Y|HH47bDVF?-Z1-5aSsU{dIAyIpNl zyOG^vhv`nbqaKDkI)Ou>kIV==+&(fR?FewVeQbIm)msn8c}Km=?oiv+E;Q`6$I-3y zaVxb4DlPRxq#l``IvEl@F}?H%-2v~65lD8xdN}k1-YxCy38X!})9zF|)K0rg?F4tA z_kkH@M}nj6C~%~GXnLTnr|zMXLwEe=wD)oPz;xFsu-6^aLvOdc)h@Lir#tLDGscbv zN5j_*p6TZ5l|D);Ve=zUCkLH8vjGiujXaBSL zWU3*3!dAoQrY(2^S{cn%>^Zzn^VB&tPt66-;?ZgJpHZFsFXpr9gluQOyWh=!Z^GfP zY{TstXt+HKt&XlXU^VC|q)w|-YK$JOPpPqbj6RRXIqE!G=c*pazcW41^xkyzznU-L z7qp**^OUNAjyCoJymM3~G>6*`{x|d0bbzy?-_w6*-kP5NTl~LLPrnBqRkY{es%Xzc zD`Hj2*0eRyP!rP{Y;DKc6KFoEPN;EutiFie+3KRY0B!GoH{VQq^mp(tVQ;p&gxRNR zAvexeuouu;0aMW)NA`p|uEy(e`nZ~)$Ln^;w)fllKg@U2&i`qCnDX`_66G-!Y;EMn zg0-N>;6JV|tG#LuxDR?6_v}+`k!t6+^?#Y4rkuTmbU93UTgQ&UyQdEFW3a9by@JFZ zbre0vz=?W-Zi7@?zpTBCTv<#xdj$JO)e$vGPt>jb-{zNT?f)^q!C$70Uk1*ywv4?3 zJ*+0{N%}CHM^r0#TKlE3U&bE7{$X`UP0^F}AvIM`(Fegp>Hv5UoTjJh1FEy0ruTyf zRAB4by7r;}!0+cj#Ps#UY<=v7VFEkXUR77r9B{6kW3Q>JDuQi*^9YzQdmsJ>{(Zkc z)S;!0b;#5O>)^RRLSJA15vGqn8`(K_w!N;dsoD01x~}HoGqlyt!>h6f>pf~4)^qX5 zM}GtxLjJA^q3NEv=MTUQ_b~VU$LQ(}K7!6d&ulv%xvk(7uCfa6!H`NVgY$Kc-jJ1*M9dp}6LiZhW z2Mu@qr|9hoK7r1Ff2N&bZ>gJVA)2<>g_zAYvb}BonaD`rHrh5upT-z_+aHXM+x`&f zZLIG2i|jRf)h?+QUeD1F4(-4SyJP3Y=4|u+4EUYzwHs%Cpz~;W)pJx#3TSXNsL{@2h)? z!z1i9oL={@`6Hl{us_*OvJcdKH4&U-C)$VVftq0Vt4H8N>`t(c)I&8MI}_|oKN_CH z3_rS!21dipN>{o&%~qY zeheEOjA>(l(b4GpFZ}1=OQ?^`OaCxBj~I;};~z6e%@TVIQ`$~LYPvrgO|8IIeoOz5 zSz(vkLuRF20WPWtuPjx5!D1@=u_(qzyyvnST&>9Wrx~8RgGKuDL(Ok8NYwDacOs513VUr9EI) z+g0F7d(e3PJ2ZJ1>7PVP3479IZ%pbRN1!f^(sh{WvzZos7;YzVP28Eij(H zADsuxDO19>vZu^R=zL^G`16q)=}+?G+BkL+vXlLNW{q8K_nEbJ4Y=CwH>XWYybDg7 zR<^-BzyvnF-EG#}b>KR<2|UyvhyC$jLYu(u z!s%|a%WSag?LYek=l|?ypZGh?M!Ui8#QrX`!)&q}?G7{EZUQ%AcRSWQOeTBQoG}&s zg?=T!qQ3~55j&Y|MtjbjH5u)BbIw>6*^lH~W}unzoVd+wGeI-|_uOnap7Aw59QlRd zLOjZVR7P9DUyQyAn2Nq;QT)hYWZy8KMe-y1KC{sB@KgYoKr5r=Di{t;kA@63y}e-0 zoAmagxnQ#3CTg?bW@Z(O>PPVvi{?iKqo6kei|B{^2?y=*R-Y-k}i8zwQB6_3gyTh1@* zFN0R~FZC$ibmk=Uj|b6Q)*UyhD4{t9Rr ztjhY;(DBU|Xz-X|G5qL$X`GhvtK;Mw_|5<7r?ywjWs@2WX>1PkB?1%KgqFiE7-up4 z7(QpQ{Fr_!I8)nH_NuvJa>A9+=ERKiYoO^X_|^Xce!;t>l)n=9l){wu8M2&}#7-%{ zq`wN95)G+rN_)**HI&8nWBHWD@neIr;7)=4ls1LEZmyXU@R#&U_^Y7=9?FtqKZQ+h zZyLWejG3k+{tj7+$OWP%uSONOlFhX?dFzA0w%S4{XKqe zFt^QRpV-=dEx#&_%p$R>vJ{e>Eeg0lQ7uLD({P+1e z@d{L?QCMVFnMP$%z{so$twtlUh^!i|3Vmj4;5B(>YvR>;W}iYI-e?(N4BnC$A6CQfA+ck zYyW`%pa;-0+CPA%G5$_8@A50rXe=tLgwAkU1FeodMD~$=fy5uX1D>7!4nM!mXAdGb z+OG(IC0db2XVKULI3L;vww_!zZ{B6i?2MgK)_Av5m z{KH7E^~)nwf!>4vzP)D~`1SqQHl80Bd<8uM*BXDTU&t1;Tan%7m!q**OjZu5^7JnJ z_v~HU&~MJ9d*_)D{7Y*`i<(_)5c5hTg*IZF|c$@f-Uaak|Oh z;1{>W>;^xHEe;m58~ycIZ}8LlNBwl*G3WtWkJhE>SX%bZro+6o2k8Oqr16jAJdJ+> zng*-1etKk%g2nw};1Rq6>GAjoxCVP^kWI_du=n*Kclm;>|>J&0QlVd~J-xFwCB0ZqmH)M!YhzrevS&N1GBosn{N*_R>AH5p)l23_XfuP4Eab zg?}0yDf~0g6j-J7Goz^pSj2DUr$A3imV$k@pKNB93C)=?@!4+l?4ik#O5taLw;9;X zZ|Wz9GX+b|zSz$;Is0nA*eonFi_fxP;;~({339tIyJ=P=n)+EWP5fl&Ne-TcCPOMY z%ZfxiFdmD`b|STl?xanjN#RN6C-u)klfs#dC1v02SG$8Y!}$)(PMQR#N&O`Ld1w-x zCS^(3cl*t5r_JHoj@dyI<1~q%*uMZxjMF46G5cY^+imb{r`u=?Xd;{@_7nLRp$Wl6 z;3a56yf-iT3BZJY51O52V?AjPnvL}(eaI==7ju$6p*j5Q{!^OW&jvn$_9K1CN!kx{ zf#Ia*m#*J74u22Qot&rVXlMAlfO%MM)|uvId00Q( z(USJVZLR1lbX>Qu=r8*dyl#KlPVjW5{o!Z<_JiI-=Y84@ZQV&Xa)F+wuaWy{yJFpq zbR`$*1=^A3V|iIeWINFT$hDwv;P_$R!28qQrTP54{$2FkqaEPv2c z(3Nx{m*_=$hvxV5`FG&IOWWhL16Yt1V4cZjdWm+1rwh4F3;6l{+i>2YoyZk>8N7_M zc5t?*w`f7XfPV{~+w>;Zx4=SvLH`DLlir|({X+hAn!qm%7RGK?GMEmc+3=kd|KlJ! zkcQD=WGD%s|8Xc8LMpO%^ewH#DzdjU0v%36L+D_dowUHGC_BkU27&|die<-Y0L_fkEF=fM zm)SO&1GAO-xG@4af($1i+&KgsOa_5N$Y4?)H&$Sk@##zihC?kKNk$M0zfa5Iv^*=v zKGF}g3LFVp6}S?yh%`h8kxaNNGdPqEp*hJGx*6O`w}3gIhK?d5i9wsCk>DOkBGHJ@ zvS=&E%Cb-NBQ485(@(T2dK0j!=uXHoqAe52NQTj&G$R>KhtXUlC)rFj+6*|Fj3Szj zA)`qdWXrN@$Rz+1u)-_@{2B2b8b;9JG&jkGRBm#OUIjPPYcxF>Nk@PqXa@Y-Nx8{Y zs?eipY4ns~rP&wynN~+rVOAYeh}D4p$3m=*q> zi(;o3E5feRU$h8ziZUvq(`b~67&JO%f{JK#0m+Z=0lNURkj$aASWPyU&Y?9Kfrkn% z7(5&kmCh#x;GK_IKo-HD7hDKkgjFXp8`(K@Hm%KSvDvf^tIg)&bJUK`qjS+VkJiAe zHxH{C>>rOoiTKB3(il|WhNxf^8X1gAqtJP{Wj>il3PKm7w3sCH1KZLz zU^}QMgosT4qU|65%VW`)bS|><$Xrqgx`cEf?ZJ-FC1~nMX41N>4x5R#S#$w9+E6Jx zG)PP&x)iSVWGQA6`GdB<{11;!W6?Qin@i^4-{UPrX3%=9E}Ma#nRFrYt-%G*-*Eon zzj+)Qo6d%F4w;Sb8dVr93SEZAiQrP`bXuR)W7BB^Rv)Z~u0`l*4UVH@!Pd~_@J=MN zkeyAY!8x5S#>rUvi^rvLz&NR62z=Vh!08+L$$BKhXS>|KRayJUSiD8Dui{r_k@% z`N6;Q1T;SV27c$?ctV?n_zbW))VP? zyepfr@mNowHOVr%6s!TA%6(zQR6Ygzf~+Dd$qTX?`VzX5R42>nGFqLipv%E!v<9g~ zmf{)K!gC!1rY5PdGX|fHTBIgUCi4iw7n6CIhyeOx3ZKTOax11`jChXb7vvRQFHT>f zeFfGpp|7x-K&s)E>ZCTBQjtk$n9QehBea-~4kMl+`ta=!OyEugVge5d2L@<-g6vcBgsg+k>Hiqu12X)+!?6Zm6fpOD97J@g%UO9*|3Nle4Z8oC->jeLD1N|AB!kLTlfL=h5? z$Oa@HVIGtB$R(!lF^OmccuSE6n37~Hk0c_BvG9-MmCzPWDv`Bx4Sk60Bl3`JgnmFe z5&eKkNGpLBm-7fNX;I0oe?FfYn1%0nUoxdb*C@$NmFypKO7S zMrsTn&7+9OqCD9^*VFQ3Bi#V5rxnOOc9456TDunF>6=~Oa>WJSkR za+7~0U%)Tq7Jq=R<1=_4`VjgV{LG_^7HDoMI*M6*Chv&uSv)P;($Q>m3Yko@p>GPg zfu5WE2LDFBlICJDU&Nau)k379%}Fzo2L7}(I}(#gcFZ<%oqs3az;8%C!adQ&BTO`r z1Fmf(2i=Mv)f`xDCD-7*&ad$wljfjX$W^4S@vHnN`9V_AmZSyPinIh-B~K_`^H<w;`5-=@s7Xcam9Q7j_)BwXkoesp1mX?dJ^%3yr1YR;@~tc_<_IY zyW!bG67c?_pGbhygnSn%N{i54*xyZJ!xKlu=L1B4us<9-NikZK?u2I-*+GiaVsr;~ zc9QKR2`x^yV`m4MATo&bVxpMvf2J4dL>HEsXX0I07M_{!;OEIXvXh_1Gug?{k+a|q zXjj&SW#Zd$x`Xe+bNxeh;WKgx>z#Ns9-R}!c##o03Ek7hck?iH?`6s@Y??KyM%y~WrJ!8dGwA2Udi$UNNJnDe9j;tq3kN0R#^rh#U z`DJp6Y(~!(z7H)Q!M)JYXc!|#i!9J-NDmV2k?p|Rvm87-pN_pjVmfA^7zNL0Fe`Ku zzd|mPP3YXr_oM3rxDVQn<>WcQTs$Y3gSTfR;U6VNifqu4B0F>jx(0yLp);_G&)dS^ zj&0;u$rZ8@&71fE^nKtX;2$YA@N48M*?`lHyba6EbAfqyZZH>;!$l6bhGRyE_53=y zM%Kf>fwzXI4I3tM;(QopxM;=l@;tm1_FJ=c{06yB*1^A?uf=*Dc$3^9Yxpg46TC^* z^3{AhxkXlEXALhY4)KG$lsJg5tduATEyv69S)v?frg*^mvA*m9>koYh?aNAt!~760 zA&&6F;34Eo<8u)kJb>p_T9ks`hyMY4ghXGkFYCj~psg$~!)J?Gq70uSW{dKC240`? zxNRoZGx2&AM`sC922HWS*dms=ho1ZF9vc9?#|AKMco~$IFC+3QhNR{H1cpRP|tcYwSOdMVW4Mjx}ahxCH z<0E-(i4HhS)`+iWnj1bRyH5`4axC&H1=&kG|}L=+Y$_;FqViCm%rCa0*( z^YOgAG93B9aOf>I1Rb|9w^?yCl;Fkr0x@4yL?S1c6Yr9nY$#keF}GMDagv|lg~Ta- z5ny)G!%y@4NEHx;;V;7TVJE-HC(iOS zSfAr(d0sG|$SYR!b36~2S9m;JR01oDa3Q(JD}j~p+-9(9yegl;s`F}mCY!;k@-^}m zd&$bQ&~-3gRhit*&DVJ*;R6be9oS+4d{5z=CBs5IoJ|9 z2RFB5bMbf-I0s63HBnViG&63w;X{PQ3>H(+Ih9RewRlawLcU{f*$VWplpEzUymvR^ zhG+Ojj@3mqL3j;O9jt~HA0317TjPVpGBFw1DQq&U&1>;_xNjtzhdW2H%j8G)fra5mzc3Hu zOT`iq#v?!{A~lKqWi>?&@fWFoY$=?}WJFnH=KXicvhd+=XD2zF+YCX5&}`UZ0PH zXFOYk)5UU;{K7u7pRBH^BYv`aqAplR{9-?_{>i?xJffcXj`a`LR5p=|z=inwnqsw( zb>tnm;~g;p&!@J^Ei#|lCbxolp^f2b0xo8YSTj7oYhY7od-yx>_B;e_&m%%Rp(6mp zcwsPr=26?_Hkk)4c~yRuPi>Kn(9;-P!WOgUvYEUFUS(InYwRk^t#-)mGPl|(cYxcG zY=`FdyfgX=gN1n^UH~ndWdZbU0XNG{vY}kcmavBCY$RLA=JE<_i&Q(_mPdkiL8c(s z8JY{txm7_`Ky8u@CWe))MI}tPN6ac^e)X+7-zHU;*9;?1D!*)h@YH z=2W}oE^w#Jr3#^MlPrYUDC?uM0l1tkW3AA78T`h+f|uDh)*78{cxxU7+6{e;z(%|w z&w;j_svc7HWj(oqEoZG|EBTdm$9Y4ZUG0&(Wp;RSs8-0f=B;>CXk9q#$+~hSTfy4k zM}LuQBU>ZY2J?mW;N6k!foZ_Asl9TK%!Z!qswJ|mcuO7)+5&6|Mu)cGF`!xD%%-xc zeR8j?BUiDNtPc9?%Gy}h0avqCthQXkRlDY=+b3 zycv%PZN_6kGsBZbHO0CaZvr+2V?&$p?<_WN3^w6=STEj_?`3;fPrkt`rZ##TyyB{u zx**%ii}HeO2i*~eR!@7u-=Q*K1>h39;pr9dar~kt~Pla(X`1c zs)~TcR8e(awnx)>%msM~uh}B-BAPE@+Q?mK-pzKgKD;;IkM417KO4)&fa9R+yppPf zTIZEgCBYJEy|>xhtS|4w*CM;l+k#vX zwFOgH9YFUOb{45~@(L0Q!3A&N@@gX{pD2Qj1B8n3h}rPiQrt+&-H zjCbKyv=&xpWG6J8!JL&>(J^0cM|KC>&ieCy{1DQk*&)n2wi*pWn-s zJ43G_a|pZ&y)F;R1K=U(b?hCI+t9O}ZDRv?e|{KE>)2tomaPHTL06$|wYSPEtIDWT zXge)W$u7`SvMY3@S5B2xD{;EY+lq#5Y%3ec2k;|EuVE+QIVDfZZqOUJHM6>bI}gY$ z@N8vU*dRWTZ()P^Aie@UE4>w7c~wrGfd8aij`a#}xmQ7zSI1>{>>bCPkelJ(!j@rw zxwp)#s4A#U*xAfBu_1ggKPG#?dkk}2Zp6+ewvi3xL-RD@Ys`o7^;mCU zMZI0#POqr98yZW+RJUX-brWA}EUa$IVmR69jg-gOQ8rSJfEM?PVW&7|hc{dvXUEuZ z?2eG5N}_wa7Y+ADS8>siQ58hCkXO*# z2OT0$v6E~FdWOoe$W@o|;K-ojVZy<k|McMyqunEc*A_y@^IXpXEB zqO}rONmT?Zs%2hYIP-yrpabMNc9so*f1r#Aealzz^T3(c%i|q} z_Lt|`Io2Pk0kWUGz|OON*y%5G<1~+#+dBev>WO?T9kL8CRAE%X{U#hH4_7TLZA6YM>^`i82oM&U_9t(FNsR5Mx$+vH_l6lXF3j@3Dr1nEVRCwEGNnO=xLxDsblh} zY@`~h3E%|0dW}>Me4<8qNmUXx%1fq_f=SRd9-qIZ;5cY(+!#kDkY&8mUIJOxD+9)d z)>BjDWLZy5l~cgUxT7&{I4WbwN?t`TmJIhQffbQYh;(UhB>G2r6TBtfVsI&R0&ZC9 z)kQ-+)da~SvI#nl%9zN;k|Vt2Dw!JLrBKPiWNM^05y@lV1ZW+k>Z&?wnw%<|sw46+ z*aR9wR`$ZZ7_y3284UMg%He1j;Y~vB7eW`$HXk*cMlA{9+WmDRke-VmgQf~i$1RRgCr!C7*q z9PFi0snuZY5AmYF8C6D+)xBz7b)42v)zxe{OGd^{6tIR@-5cbkRcX{9qy~G{a9Uke zQ*-2OSxwEAb7WPpnyRYi$+@x$SXEU~z2!Vv8LXl>sYwIINkaU1aZ(DOeNNKhSDZP) zw+r++If_4l!%0t;j&rh6K8152_BbhxpCdR)gdb^+-;o}Oe-}5gOoa7Q{GTi*Nn~QI zd;0%sjcmp4T+nG{SelgTUI zbZ?q>6*CpQ0{tResg~-i{38EjOVvW%5=mtec}v`cUPtPNxGqx2;p7rL zm%U5g4Cr+)mzNXF4ZV&Va(kc9{8@gIZB%RZ9gP9_4SE%A*Tfw(adOd{iS$LxCGVqb ztJL>alsGCUV@GgrqGPS&n>=kiO+(q_0vKPGb-fZZ5_&>;BaHm(l zURbA8*xHx%< z^(*;QJi+<})-UA?*-dp-&%{&gJjeQle2!05H}zaR!%iVtP~P(jVeWb@yuY#~_)q?o zEj*(B$>v}SuenDRQLVf`GA-B=u2z^oU|M{hTj7&E&?|t3g0g_T@7=@tfp_04EDOoI zU=1&_EG+NfwJMCqcf9;KEg*}?NHQWA8CnGAk!3U7(%ft2F-28tv<~!|V%^MZctw$pD4W39)NA5##Z+7P7I|&q?eFD}M2zlqn_!!MPnc1SGp+F=%YdEn10^T@~EBd<8TnPnq*8hedAPYKl?u7zHE z%mOdBeBwO@A0tyj7KgJ0CX;LkXCtqnCzYovE~3;N2c+TL^NgTAWc{S|*iY55mZO8)RVc^$nUUT5e}Xh-j#_$x}u zf1)J5o_}};o)iD@xTO3I{~z&Nl#!+7cldvJzmVt%cEof0g*oN@!s&1EOO%ym_muY=bJF{Up6_56=uh~63F@5@r$GY!iv4fiSFbDd4-zNA z6W(#~B=iUTKgADGUY3*0quy!p1mH@1lY%FTca{LvZh%cnh8u??49q z4Cfc`v)3K^5AIjsU+6bcQC5)OL?u}ftbn}m-ikLMhkkAe=Oz&GNx_yFfe?}OJ1 z`oZfB{VXcWaQPXjFG6|JdnMju|AY5QRFReCC!Bs3+Eduq-b?WUd?j9rcksOT-g$kX z#?#&lVKC3dTkO2^-gxaEJn75vf6HZ=Z=Z*K;s}0>ExMXsx*dmzR zEQI8sCk4pm7O_oGJg;pyqjH;g;bjN6;?X8}HjC{dyUZrH!J5+2qy!% z0y`^3B5$wQ1MU-h!GzER-hS~P_lbmFVy_B*3=(^ZyglG2@e$mEADQ^x0kL1i_YR5! z;C{H1cpt?Fkpzj4A|CeRdr7?y;=M?UlMf=UcSsxr58^BtPTq?+-eGYFJcQlk*n2OM zV%M51qvVhsVtYCI8 z8yLmQ4!-uBB*e$Nk&w#jIo7rDjwB=k-lK%95X;dS)r*34G%qUnT-F9pifCXud{y`( zE#$ewKE6908t}d92$_%Xw1ggfCmY<3?`T8F@nE+mWHP}n9(=WV@GGZ;e8;Z@5YiaG7Jwf79~U9L@n7Treir8Bzn_IU>453@KdRn3 z?uzRD{+^k0?lXJOz|2hxNOzZXcS?762?z>O0@5Yj-3=loBHfKhcc-)%sDRJ=n#1?= zdp&>bb?v+k=Wz0#wbm89Cx(pf!C2k_L&oQ{?!miT$mkY~<((^J$U9MpN)j?_8S*J* z8S<%S8S;r}86D(v)CfLV4f!m`!<)}|%aBiU%aBi6%aG4li}PLiohR=b@_SEE-i74X zouIrgeadQeens`=7UlO|Kl<_>SdDr41t#w;@+(Wec@Jb6k;Lw*s3jLNK5;V%O6SyhQov*utke%V)~Ux~kcw4hgk&%hR-d={1mEAUqe`J^mI zE6?8^TGK1bJ!k{U=WZGLW%(O`Wt8E!yJeK-c`Uz8iVGkM$1939jBd7z2A)3n2A-Z?2HpjVGENsGzt7Wx>3C-;MlVh9t3FNew}8}OnwZr5?Vv%>r`ify*K4awd6~pT)KkxYR8q}=i2|gF{ z^7&MNHTf*a&1aju`a-;-3W5b#bD7Nr=Hh}DEPtLc8f5P(a z_BSY>?3R&&eu|inWA23IJxaba`!Toa%eQKIPm^!OJ}B=?_rvmDbU!TbRPs&Oi@6n+ zcg0)mydAz7miNY+%-rI8@cnR{m>bNGYA;sx*`zmne2 zJI}p*16s!4e8N28lVum*1D^2du{%KdOy5KAS3ZU08^TV$!8`+>vQIu^9`gzJobh(P z(>w>CGnP-C$Dn-T@25Qk_XU0Vw*M2~!%pxyD&K;BqHX6>_9VR@`DS(!Jjr+~-`Gxp zrx^c0Up~=K6Swfo<}@h3aJJClK8a@1W`$?)DRK-v#&|w! z2f%s61@!iV^N9=Sg^cNZHXMijaGc%K=nIQNJ};(%!qQkxoB~b-*AORz!YPq&1C#lt zuokAtI(ieqNuYdtm;g=$qA=tF5wDtFRu12 z1(&kcm$}8@Vy-*)WL`K>%ZXotJ;4>kFS(Yv0$x&I_VlAIgjLipzy;j9{`3~WR2s&< z9^eb10_5eo^yK~)l1nj_(^gf3zF%oX#D08uh z9i73?Kw*b;0y~4kDX9%Zs1EoIu`WHqfpC-R(i_Ni>A|ej3fLgE=+)+`Z(UYv25gg> z%-7SbBe4SasUz5tae4X`U=hi6 z)tt0kFpT6%Yi@c?;1)Fv7)EkMH4oQl8-jAJHV^BKVQ4kyI%#%V4wznYwKN+oJ8U4i z%AA*74Fhga1F!-2D{EM;pJt_HgRfRBV67D=X6DL&7El-fnZv>i$OL8%X9P2WrHC28 zj9_VEdN2c6hL{da50)jSgLzRloEA(MPQyJb2bN>(z^HM-LPRHE(Zpd~5Uz9qm^^Xl z6@VpOm^B4zPZfI|{P zKLU3@8KW>Q1|>i;dZB>pVu2yF2Okqn&;o^*X26C^0SYV5pl6~ZNJZ~`C^d8M>Hh~~ zKTSAw_#HFvLk~j?yFC1mJM!Ba?Sc!!@7|XqV67spf|Hpt-xk^m z{s>+qZVg=`{s3-;|8|+Uh4uq%>l1Kk=F=9yp*}%x9-NpHaGa0B)mg~waoEkLn41eT z<`j669gA2w1|EaeGl%)Pu$vdrUraj!6ZvOmXT$mWIkbeiBj6G4+Y(yHn8o~T81w6h zGhvFY1J^O05n9h^25lzFf%SoY;Cte<(1y_W;P=c<4Q*sJl{PIjh5l4<6LB((yiMRH z#*?^bo59VD`@#2J0j?tUqt~CS%B$#o4WD=!xPmBGpjU8}eHCkcV3e)`*AV5(@iMO5 zuVE}#e3yaCLQA>&x|Dk&*Kwu4gnRTAdxQrd+}B>9FbqZ$dxFAO7(@IL6!ybd;uoQD zFy_CYFHDPXi9JH&nd?FO0+z&hdY{Ak9}kXa+$}VbQ8(J>@D3(1>PqVd|7a-JQtN{a zz+uFCpzw@_6NR5N1ZLH6#&x+4Ivl=FLuMM$2E*bS5pcOi5*sr&7#z&C;M!az6*ib$ zEp5X63mHwA9Ynt|u@=|)+k$P`QIo!~*4h(m!Ukv$E3N~*8UbUVI#>f%Unku{OFxM3RW*f#i10G00#!X;l79bX+7cz1LERh_n z=7iZ?8YXh~fOC=!6wY*6V%AVOVpdu<7~bU>Wuaw-pg^$FkK3Pg}6TnXd%O4kMOI6C8$ARYo#D6IEyL36pU^93QR?efHs(# z7=f*v8s1wPdSNgIOiK)h(h);o7f%vN>jFBg>;slexOL;;sN$4^2 zzru8TVkHheqW>7Sny^ZqS;B;Q#%v<+De<8ttdfVUK7vQ~%t{z~0Q)I9n4H-c%q0xH zuo7?|U(ibsx(`F@4gAPAFwO44pZXj8oAF)x_rQONcfh;gTjFi-4)~6E3;x$T@Ezlu z^lyRx5pRGuK_m1Z$fc;zb?}CD2o~32P}p1t;pqGh{?7Oav#-I|Fu@MM7WxDHi+F(E zL9WTaf`@jLwO8N~;(k^SaHahy^ZVdVodbnmw2!u*Yv#w8KTdlAzTj%vUiR#RWpaVI z2maOt@H||S-Sqdso4G{XMcWPY<}#z5v|Vs)t}xm`+X)}$3cc+xGOxg6xkmgc;Di1| zZ#(Ri>x`FhJ^K`Rnz#g3*=ZPFOPE>2b?ejMY37!3_5B2RinxsRQ?TXEu)dJC2nOC+ zMhoCvoCVJ?yPRDoVDf#>cm=)V;Bw+TX6Az%i1T1=Y=CRHk=|UG9UI|0ZlX8a+Dx2H zn*-Z&Grd``NH$wD!C9biN@jpF!L7vU;0*9b;xuqNxQ#dnR`6PIE!?L8;6QL4@f+sW zfNNk$ea*}O@H^sQ=2nBN;BgJ6w+i0wcdYdf7&1ecTgf%d^^E%kJe;90bXUTwUCDjx z8*qF2GT#s0`8dXX0`^hwfPK^(R^SA9?c*$f=f8j>S;|T_Jq|q8JxuI zm-KsDUw~hNQ;9vmFTiQU#sTZK32`L4&r!ri0r$00z+G$_@MfE$7afVhb_{FHP>qfN zN5IT&5O6FTFy9ch<#71C%~=_a%2(K)^=S>zP!8i>wP0nKRWIO$)?>B4RX1RV)@7!i zRVQGm)?ucuRom*qs5Y$*8tkr&YSC(=x$efOCasoL!}^?24O&gBI{g}8cVcz!Q+MlA zusS{jZBa)Sq_qYM5DO7o;}g)1mHen2+ktIa`GkIcwEL}5Toz_mYdjh{FqaQiZU?YE zJBqN@5-d#2%X~hoDB~7j5n>)@@`B}wxxqYO1!68RH&~IF6U+rxBIZO%T*=A-<^-z{ zvx7OTY+!bhL93PEtDZFIj2UyZ7LBABr`gqL8$6Y1?GqLpJ zfn|t^m@5I6u!`doQ-)bTP)sLgt~lN;#jRpEvXo`kv(i|p!PJbBuu=>x#yyP7ya%Qw z#sTBvc9f3j(&FHzl#ZTbr6+1D15sNUiJBfZr}VXDg9^+2ia(m$naImK*eT;{$O6yuo-EJ`*>=n~ZnT-v!<#E=Mze4vp_Qyc$+8I)}RV zJaHKs{`07Q&)^iXlC?A73gS}cm!Y`*1y6}p%>9B=`a+W8cPTK5YRC`EB&(;(@Xa z+{SoL;G8lCzm@Iue`0nv_htvUgYhi-v+;*mkEV4fO4Rk>5aKZ6cepidpg)*41kZ~N z^u9rZx&b$Zb*OHKvtu1Nj5vsSansmD9KqaL+&3mN8b}+2N5TkZM$*>c12U1>0Vu5} zf|H3~g9Gp@nH;#5Od<9&rncz&u&CPMbDT5Aa)aEWSJA7`0?>EI1b5gH}Yr(RebnqBj~>opJ1I8Yt77 zfKBnpnLun3=-*qjYZT0#E{xllt?9R+jl}7xD|3x#jd7Cd#;75!5$;so=rssD0qTPd zaKGwKtdB=XcYL*a(5nm91HT~FF~20%q182O)2{>eB-R3JgT2J@B=E5*ii)x$D#=a( zb|x04R|G9%QL_Ws!EBFev@^5C8MO!7o9)n}c4oF<;E_^-aa&Z3#fb%&DF{{~mSnCi z*p~a2pP2$+W#T7+$IB=5^P|_T$|xW06LiAW80DqqLuLFaqdc^{Xo{;d%5Byl=BAg& z%w^VOl#7>5#uso5@J$%rNNJg3E7hf ztUyeNmal@D089v`CnjT8X|Oa(#`w%6!2h5W_bNGarEvO4&ulz&tLgCy$v`g_C2IyS z6VV4_aX-mK&qE!X3AdEY^x~RXh;hKUU{<0F#sRYt9nb}{6E*07If%a*sm#}CvQy(r z@EfY>)M&}m(EA;Qb}I9CT1xW|BPDJLe=wI4m3kU>h~_*EI`?!a)?d(ni558p9t(e> za87}0-VC(!1}gaH?0JFy_+#$dU+nrAg}!BqPTyorwEE9J_yC9tz*Bq#!e+?))ri5% z<5y;$;4~0J?=h|)G3F!iF^c~Py@!U4tH?t`;YIQQe25BP(Yqgbo&1av@-529x9EjW zf~UZD#M6xb0e>cn{_`F9jbS^TEBuk@)^>1~=nTFdQ5KZXu3h zZWFi>uY*zaHsY@{ivDQY_jvI9z^-Aa+hU^IyK4SrZN=nXVx5(j_-!CAzwjoHMnX#?=2noY02F^AX> z&yhLc9L9a=_XFnyoQQ)>D`r~bE-(R4o3_kNz%!sN{dTl*xIav0y(O&` zo)J?RwFsP5TF`5WuRuHYw5NTG14Vb%I?x*nwkI~jv86lMowcTce@jzln&HIpC8H*^ zrnr0bWYieXr=H-K%r>Im7>AIrhz)U>`U>pDYy1FS{N4;H}XsTRFYaLcG=k#wd z;ZXN*4r?@hHpM5|K5(w7v)!m z$tyoOGs$_!HjT2Zm_`eJRhdRPMkanT<-oJ-GI0ZY&7KZqHI3J1680SDx4&t$;d9yK zmd+ZujYP~O2D1=TGiMrUh^CQ{nM7b#V#2@&CIOhxNXxouq$8R} zeB70?fjNlr=_N4Ivtk$1y$*|C9}-@sKk!x+caD#Pf+wH?DKA5H_N;VOt>yyI``hH;s{JsW7k zCxMgrE2d#|E}b*Odj# z!fz_>HNQX%<2K)F4Pz(Y1Px;r-~X9tgJ^s$xuZqdTQX~dI6IW0RShXKmtFIUH5tZ@Y#rYr49 za77%ZYcPJn2#zc5ad3rOuH(yCu6e`lracU|5dB<|5{V^(zeEGq88_ zz_^XFZ%>EwM&xREUgmxVPmx3T!8rq#XUK?hjGDkAPE58iCTzKXgK5)i`Z{8qa zQKVtOwvVzRVq@;Yj1azlgMiDDFw!XC+gl{3-3t?Ks3Dg)#Bel_Eh(bd& z7Oz+rW`?lHf1^bi7}vw1*{BWE?*AAV*8&DchDgmo3sMs`Nb*Qjks^AOnlP18qF<^0 zL60Iz7SX0uM>kU(#?1j@u^8c2{vXeBAM^V^sBsRmUJPACF<3gn*A&*K@Hgwhy!;)O zpRhiJ|Cb?hD5eO!ocUm;W`g?Qvdb5b})7?Wuu zQN7dd4;rdcD3xkNghM0D*P0R0R_#VvRhF0^Ze>~+muVwuV9pBXMtHO}BBJ2hg?_6X zu>k97U~Z;~psQg|^+-WRsX63uvBnrKn z=%!Yp0IG!&ZzUXR;YvS%EnOHcswjXS!;Kb(bRqu5!bwdP$qP3s-v_;4bu!ej^Z$<> z6@k6`m}kbX0fQ~d&%O_zTe#iA)Gh#bN*GizaH8^%Coiapc>?BCZFEh`V`>LVE>R^` zN1M1NW_3)#fJ0S~Ga-1v)nL9o;TEdJ)UlWG|5wLej?SnKDzN47$BS`GxyhCX-D6bs zxEA$eR99IQWu~Y!MPYe_993Z`SA{PpTDYa)Ql1HS$#4&@dT}`GQT|qxp(SiB>jO_K z5ezK@7JQToUjk12oq$7slzdg-Q&)j;Co0gY_Ay44;aFGV|K}LJO0c?w$DKG}dR1mm zl|Z-p9qjv(WI4{RitxOI`z5Te%4h(D<9{orRHP*R(x?JN?ONFurR(|+s@jSlbh)Ch z73IJ!^ar9uxDitZMS`eyE85rT-#{@?79~M>TQs=knXh15hA?L>*mfDfOt9=MBQv}^ z%g6#B&oZ*Y*|UsnF#0SbJDfku$Ptqr%o&pd%oURp%pH>p3|MV^wqRc#aNMFw3{h*G zj9G{t;{+^NVaW;?Rv58K;joEPc@KK!{PzDTmPM1C&tAld6R`X%^2`>le?{;FaX#4= z#6%U*yEwHwB0MMI+9u)IFPz-NVPWMa4HO02K+#Ap4m6meHJSfGc`^?j%g+Hfw{qlI zxDslEV?5TCA_w8lC4&)@YDn^deDnx{Bd=OrhaPUMoF6wd7k&9-%5DNApw&>VJcm55E ztS#s*M3wms8j7tk3nTj@x$T9tkRg1m3K7xs%tg&}hA7PD17Xnx&503iR)xqaTKULe zPH%w;9pyx)gySgM`0Z%ri`qr(A*^kV8G-_2OU&x9s76+Y%cK7gMpyYj>;F?kbW5`X z<qlc8rt;_S}9RgiMC2qQ{o)34gY{*c2RpzI1Sv( zJ!IG$-V;s@15-Q*#EC#W34{f{Cp?3*Ge2m*rqiDRYdkIN&0VbS4*$UZtsh(vrUeQw z(R*D8IOD<`7bd81%y)&wFX0DV6H4N6u!DKwuUkg?nC;*WIC_>LY&{DOpYYe$f$QL^ ziJDF{b;DzZ#Y7z(#N$D(4K9l;jfgfcI~pcYuIC8UccR$Y6eCRc>!5JpiIuOr~t)h;x*R~mq(Vtl#k0}=+UmlX!Z;HemxvH9r+%1 zTuyZI<dWvxM2N14ULjlwRfRvi4tG zzg&#>!D2M*qI(qeqv#;TQR5ZYCRavQL_~!-3QeZyDTOtD6`uH2G-2Y{Ay+R~MOLC1 zD`S^NwN{oWDzdV+s0tL?f(KOqrijua27R7K9-mecMeMgRqJ|Z9>{IqXvqWJl zI@|FvqTLnUt$4b~b?$XIygb1dW?i7$2!mT-X!C3BLR0AUlnEr6dUj{ms7d#FF$oCQyt>oz7 z>htK}iu35eW9JU)=)35oG>pa2 z2WcB3L&!PwgO^it&P)v0_LE``vAzNA^#*)*u5;=Jn8Z$uFTh8*0}KxM2ZLcB46&kG ztX_d0s|DvLz{hV+Jk06u(Q1E>>rYh8CE74ih>5OCTn4U3z6m%D-@tFU#Z_%_w;DwM z8|zDU_Kdm8o@@9MB*mxTiw`QasJ2YhX;<(?NQys#_#_MrI1}Q|HOT6LB1}|gqCXQ? zgJk#`h>ya6fMYR$odd1z?CF78Pt;?d)4HSa6J?m_B;JGXn2qY|><_v-QQC>?L!XHF zK8X9nF{1dBb-}Gne8@D)x(O)mMA5G8mOKg?^85=29o3awva3J>s@ zi#p8p;Oe<>eL8`ic-DR#>d5m}JVAP*LVXlTfjYAtC!<=;Mv?n)V;XV(KG={bjw4@2 z#B=0iMEvu5SOr4jerMVpV%o=;c6(HwzmnzSK-HSU?t$0IDO^&-^`vp6QRJT0n0D6^ z-#u~Pi@Ndkgtzbn*NWumVt*wzVeei3u+V{whTSoyLrm0lr90VrM8x|qe<-Sa{VyVV znS7yM@E`JpgdvfS)lWj=`Eok)`3E-{ae@)O?0;Zqlr`O$|2&eH{rN)gn0X&4Wjn`o z4IE;+vf3>Y^(oB5p1h&A5z*khjflSXU;1xB(c}CB{)^gKbUFV-x}nYa62)&%l)=wX z2uGcC#774XNmv+D;^6oVZ0t1frh1_Yeu_5u39pP^A9TXv{4p4AcB;@|TFQ_(?1<0K zTH-n$HQ}Q);gK0ghCy(;)55kA*B!NeM z5D}l6epXAE=P5!h!ym)iYDw?oP=EG+4dXlmoUs+;5$;T@NK5<%>T;?c?R;dp)f$hd z@i>HNvp@KjuweOT0__!RgNg z`%bj<-B8v4jt+krnU`Dj?elo{)W`GSe4x+oYDfL8mRjus=n?SzaRs&l+fg0HL ziQ=f*7ezs4*nOXotqYz3f8ZUk#A+XD2eykWwR(rMzylQbR+I(`fS4P&MTkRLOIVeY z;T#EHwoQ0BXIF$~vpNU2iN?52MA??DLgH7}iYESL;?F7mO}(voJT6@$^LT8|g5oP7 z{%9@W(zZr7u$qjmLGf0d&%Q2^`RwW%Sr+PmE?`-xBf5ZP+~V@kEc`DT9z_lAlGL&Rm>-f>&7gwDIOf+LA>k(e#e-LpB z8NlhzU}yZsrZYbSY>xAYI6Zd?FDBa(ShK=EYfQE#9~h;j$rxpt<_rzwWXH%ra&(G_ zH?%lJi(~XO@=OohQ<~$Y($a2WM?L!*g=WHSYede*a8ZSmT86CILxafCF*1nOAtKJy z;!iD3)#AM}EmD?U+2H=pv z7f)NejXg2a4hNSB;6&Vi+R+;yX^$_9csG^}Ee)54MJv8J;+``&67|zLZ7pGbDX!t; zJ~)hzLrd^2eCb5YjSUGOQ9O4Baj$>jm9of+>Uox-^eG!!#_L6tKf=@%Hy`oz85$8M zAo2K#`b#b*{}S{H<6&Nl_j!Ww8TgA)F5@C=Ij4Ju#b@Z0l{oNZPRy;22}PYN7vWI3 zIB;8!4+>jbSdRiuyDeCPQ`|QCrii> zXYf%Waa}sWRjJ{TVG;3i5=W5t6wYj7?;LAnSTs@M zVAOSbXx^!g~I=@D#IHX_u@=8G_(ai>d?U5 ztT6X*UZ^lTqi(sQ(D969E{!Q_lr*p<-oV5cAJE}&^fz1LRyGIR48Jv62O^~@wIB*` ziv>{yjUg5Yk0pwG+R#vu@LaSNMYxT*U}0if^Dp!+X<=9V70S=f0^w-AiWH{QtQhe> z_J2M2{ZXH`t*~T2K~W|i#N&vc(94f@Xb!rJq9~8%gwmOR;xnHPuEw9}07NMeRRxR; zGy_rpid)snrwL^J1n-9&>Ec75r(J{>mvMU@weef^l}ABwsp<_Oe}IatjZPQ+?rct9c4Sbam{h1fT= z8y0sTQ1mH#V0ZTh`-FOj_QLx93KZ?hK6v256_A=YF)(401j>sfC@(%jo0I}o*Nc$& zjtjRSY)Tyt3k<`YNs3NmRyZj;#piKWcqV;ueN4)@Mo6mY2=5>Qmqt97XP|wOsvP1= zF7D(niQ;$u0{v4;v|`UuhouaQ4`mWq|DB1#PO!{G^b^DG|BN_}Y{FcyVdIGR`t!i^ zT8DoluL>vQmS=)9!!yFdX0XgDG}BCu9$-fJTTTg=K{z}K$(9J+Ko{cckd4yqbx5Ir zdrdxt3w+cAJ~f&(sbcgkSJX8%jow%@!qagANKUry@Fh&MJIw&OG;1UvTf$I+K!I|a ztPvDvX~L<&v|;hD7w`GMt!Zdi|F)*1X8jw*!SwJi?27?U6UEp5NoWkWB@7aW>$CC6 zmH>@LH)4D=Jl#T4?a48v?$a3KA9M;+!~f8xgwKS+DDuvPV$kTF!IL}&#az0uc=3xX ze>~2{NBbdOsuSnTH=uV))GJ6rr~I{ z2C3EX);MSOf^BjR)@d)J8UOYiC_LF=NzDeS+`ta-Ecf)CA+?R7HObC=sBk9L$JTp-gI zFu5*rMz~*z%=bn@*mv*gC4>Xp+c;yk2sEcHIGHVck=;Fvi!frpFvQ{bKdT{m8in7G z;cu8UJi_y!9W|gO8Nc@r;hOcoZzA1dN1h7l` za#Ct^yn!=v871FlQPTj-w95gH0$uhuZyZV2365( zPW=v>@H(o@Xw{eF<^Xt8$4#jvD4yJP&^Jd=B-IYvsFQv(Zm>^kx!edHGlh3`jQz(= zap0~Umg+9Q8AnawW*ueqm|2tgT4ge= zEBb68=SD;LvRmQ8ZiP*Kit~2^#pbZ6q^q+S^(OO6AjR){k)|2OZ<8UbIPhTEw^fY!yd38hJ4nANUcnh_!ua4ajrCz}S6vCBJzOQEI8e<>*{iuhl1QideqLFXT z{uXAm7S<~EtTy(Bs)qN4ng#s+W~??h_b{_Jv?o*zmHqC}rzq}s)87-?MSnL~9XZH_2K>W{a1Esnnba1Os<%@6R%+pjLZcc=jA}5QD+G+h3hb;1 zGfWtam1#%K%AA=A8+0Rz+Y3~Zkg5_=LEtrzNg-UR8Nws4>v<8$yycthOnux z1eK<)u=2`~>bz2;wtio*^F{^NEM@^|zaRHv%92je#lKLL!jA)JI#OzOEZKJl=Q#h^9 ziQCBc94>FPmdFqAzRGZ0WnuOSKQ#-tbI8nM97MH|h2BB)Cr&&yq&~CgcIv=>|HX*b zGues?yELcD7^Pvj&JTEX2h8m-WuL;3eM+sf?LnP1shaW&oZ}xuQaxo`=*Lht_8u^^ z(e{HMn?SSPf8Cd28V%HTq9A^T1-BOK_T zLfb-8B^w=*u^29{)E<-ygp1gB(%6o=T(b|eq&s(Z`o2Yf7mBOPn8pnR9 z=_u72%W$eJxC@SOc^;uvU^z0Br)>|aKaLGF5>lx#o6*daTI0#79WC|3E0`vv`;Zm~4D2R?Htb1xj`X#I7m zzMj)s2!%{OV}zN>%xEqN>Q0G5;~-r0 z&;O?tX=o;N6?(CRWJu%=WB+iJHlM(%Ey~VfW&&5EFH69lgzix0hoRWX4+}S1>$M1b zL?3bp#(R9%L5~)n{R!M5K@Hf#%ohpjYaODh))Cn9gQ?D104!h(G2^)|DzitiR; zwJ^GnBUCRdXdZ=QU%)&D-@X9-f@Vpp2O5@ADDk?RpHT^{3*6)^W@htu*K`f{HTb*R znHga&XEn1>u`HXJmHJ^)nNzBVEeUwcnVHGVV-c;JD^+t#e$eujM&&2>@egjp0HwnFAN2ln%CIXIjbF58@0TcPq&iyXfcGry=i(oD(#4HG zIrrZAllIPe<%Y=j%B8FZXpue2nHI)$5u=zT8k}O5R1YruKRscrCAHc*!CB63O3gOW zdi>@7>ArJblIN8htxPO+iHljny)FVrIS2bv2g<|LWb&go%-gw5&=k7DtCO&f&F&!sdG@{We(|yob z2`{`5eDFdr!=-wk)bPt=N(Diw>GzaV&)jJ3>Vj53v|0r%sbVcv2HP4>Sbgd~aWzru zW*0<_+8=FKv_fHP_Ovm6W%Y^stLqT+vs%DvW#mIo)XMn8lnRAXm+&#Gzq*fIm)Med zVe;oki`0UCOSt(3&?q%$riCF@6>Av(uL^j2Ydtffb*lxNeZ46R_EGL7_o6$>y-XbG zULlU8jdG>R?qtxT3wkB;a5 z|EIVcYz}v?l5aR|ggb_e7r@cPO@Z=GRCc1Z6Ahl!U;l$j*Z(-ayOuob%wg^|P7k9E zcgJ$_JUE89hSjyO@`bs5iQS$n6|#NzH5sJddlrhR}w(SDd(R z9Pl#n6*cd(TCX_!n-f(7iZW32fs=?*xl}ZhqLdiy-XzCh+7K$J$KhEZRm|hKFP-dY zhhLKCl{1BN{ZU;uFjj#LQCO@r8=j+Z`@nN7fue;$1gbb(vga-E6qX7f8!2v zZxaW(cZkcGUxCWAF?x;X?0?}rcXFa!9?0q-_Zj`?&NC+$y5?od)NPoN5E!aIQP8 z-J8x0ryZ}GN7SEpiBf^y1>3sUn7`&+b^hTN|JDEKZf;jMT9>yKx7Zp@csnxx&HO+5 zZ~eL3&3&)mk^eodv)hWyt=;zIeF(NAwzNc>*^(;4Qdd}N1$Q9FC*UV&$y>U&oSRNd zPPKA7aN?o+pMI}9gPq+@?i=#|t>5VG?&of~K#?x`^StOnX2a^2%ET?LYx+Ok$-PGF z=>Da9xZS}o+#X~ zHLIIiuXQiCr~6ue<@N%5vb%|U-?`^BVP{jfF*}>!VK5)H?{B)d`<43}J74R@>}ldQ zb{{zRokrBSo^Lj?7NQYu#LmXnD|Y^-8?oBhZR9?59ykqIZDcjD7MTmp2J{w$Ae-`3wcxAaZ$w!Q_9CH`erwklC6ypr|CT;o=8E4ypmH33$3E4kyGZ=IX^ zPxkzUuDgm=+4|eeWj%AG7I-fDm2d|58*O+cYm9SO-_c{Zm9frh@~m;!@#^^+yh~h1 zu8QDV;yQYF-G5MyKXd+}J#|KNc8oKgTe_jgJL8B_`CN45RV}H8UJXZqRc=+XuA;4W zzawvda2;`!b5GyZqn!Kt9(Y%ecK$V=I#0lVh*Ej|4|9TZLtobuxP=>fC3#l4E8S|u z_2lU9c5$xjYr2awfjE*pqny{A`W;Qur&cx8_tjCUTr!_HzdE8|f8u=0nSSoKobK#Cf8B1s}8TIeT8=|3?;s)y4ZOSq8g?xc27Ig{Mf z&P4vLsp(C0OS;$5{+D#GnWbEdogrnZFPt7&Hhk%P;l!vgr($TIJ0;jz(k3r!JoHCWIBC4BX z)4Dpv*i+ms>y}|pSy}@(o%2$^(CNtfQh)4Bb*H!=JJZ~$;1oB7bIsCyfigQDaw<{Him{ahPPI%0CNeeArqzjAtky~t98 zokiUu?j3v)Oy`+?s!iv)eg+!EG~}!2CgW6cCz&(doko9#JKcRphWGY6ySMX|^Um($ z^mZ)gseYm@$0R0YPckR1n})M#X?5MgFSU zuv^HzhciVX_dZ?~={Q~2O-HNa{%iMj`Z)jE{hYpFALp%|gtH$xNt{{kOt&EW3%UQW z`mbGpenGc@`vA|2#H=Q95<9cqS?=Gg{$u}b_jmd^iJUp^Y&Q|}iJkoHEa2vMAL5sh z-+hEv#wTEYHy`*3_!w7>eD1I2V>2(9&z)iaYCpDT(jI{`h#ejNZ0dA$Vu&4`4#d-L z1~BPP#x)ZxXPJ1W9&i1qp&Mf<({lK0@#)sfc;&l57w=gR_ZeIk(U~ zOIzTcAlpeWGqH{1kfRN)t<#6y_v}8LxNlb?-yo+FZJ;xSoKx-ZIXU0`o*WC@=b*l{hYXg)AQX8?mTxcIG=co49CH,Qr z+Nnb8@3bOAYiE-Ef^(B-lkJV1nCl*Ov$6N6o1J)+-Z8f-C;B@r+20C`Lu~29B~G+o za(W_dl6{2zN8L^CMlx)o&2d|>r=>H&e#Nc{_HV=q^d{Pe-5l&a?B*mMrgy|0&*}ub zx#Mx7x#JU?(`(@zV$Wf>88gkDarSF=jiZgX54yQnIY>L?9&mFrIzT(Q)tyhBs_JXInyRV>*k9XK)j)fIeU8~`&N=5Sv7A%Z+2WR?ZFZ}$T2+0j zs&V2|T7UZt8O}QA*&{m6gaT z&v=ttnaovGWi`kiXjkVJ`h)%KzF>d5pM8ORZ|q;38r<41PEF!3^v*b?ovrQyx?A1soak$3r}eQblBbf|?EGc_X>aEAU-r*VEi(N~JME?i)G&LfU5-=b z)mGJWlU~ zQH?sf}11?d+8_qu!B0$@R>fV0ot>u$Gya<(}WbRLykP1LznE^q?z zlD??3IG1#0?!zT|nVlW>kIq(boAV>Mop@Pa(wV?a+{eq>cbYll$umKZ*LhVQHAzp@ zxzq*DUep(KRws*dL1%NaIzMrX+wGk^TCc$!#GO2La{%&ROuBKC5#&Ih?ud9%Ikt z+*rH2o}zQ8?zHS`EVuHl9;@@KPt=cOZ%loFtHiBj{?XoQ?{s!JV^|%l$LInozZ#

)cK*=VzVA$qnXqPV14Zjsgp-LTaQgq6(``WZP_SviCZBoK5yVXRkAY z`H}jR&gtnirli%sC7TF8!?&@>mk7}#xrGKRL)a#v{dWZhrS?}!7-PB@x zk=>0QpQ|2fA@{I{TEIQ+!E2;6Gu@fnrhZgC^)}jk0G zFSfh#@9Cz#;Fe2+rBx}ljy&HvU0Cg^x~Qf068lS5N~tetCDmG1*EwsQJ$kp^&@KO7PVddq`uJGX+3mJ&XrU(RS8ubEJ^%KEwh)}pQ+{cGH|KgMa|?y z4?UCCU2jr-bsw+~xh9hLkTa26IP9$97T1D%^&VY|OvP1awZdL*cP7tgY7+YnI+NIY z$XU&vHQ+wIS8r7PbYHM98EdOroT{ygsiI(UVka_mRvT1*-A`{|=SDS|90#4r&H-mX zc#yb?JgdR|dY`VtxuU8gr#gWv?G^S)=YZa?S2_pv0dT)w7jweGLKR|E9d zV1KfAV1Gw&mA%ql&;0jl1*cXzE1X06p#Dw`)C0gldLTGJuUE^NU*WV@tL;^Gdroyw z?dZ1$*VwD=WvniDmN|#@A-&8wq7UnJoc&HMrN7Ks0xkuQ>LYpy&(NcKF}TD@uhZ#y zDm`tkx@k{$ra8Clo3`LIXR5PV*Hd-XX1$5HMb}kzz@j|ww{X9U(%;P7ZC)K4?A!Jf z?&EFymOT}m%6-0J&v2%L)18}kTJopUY4vJ z*V}hl`QA=Vwlq4mUZ@tROgbYuGtp+Lt>hZ2w~}v|zDBm|_BDH^Gs6k%OnR0I(`Ksm zx{+!KHdc+mhGgGE-tX)^)837zD&+5_GNpHGuzqE+8TSmy^r`Yr&8z{>>C75C$7~^ zRTH(AQ|t64_FuLy*>jyaPI7jBtdr|yYN=YIo2jN?bJYxN%I=Hoxny6o=Q(qoWb8?< zlj-GZnYzHtMf-w1-`bPU>J@6aTBTd4=3sNR zTAyR}ynPlt2QG3JI%n<0&LZawc-GGC=km4A?JI4AS}Q$89k8dWDe9noz@DNG*$3@P zdM5X(lAcAZq$?69Ge1R5R)_6F_B6Gh$6*?;k#=gDn#$>EwEcDkJ)4~sXccv3&dmS^ z@tUbjZxH=;YOTu2E#~rb`i|B*kDuGObq@MD{T#ll9i7+D!%SXUL{H+jCadYZ7Tbc; zh~@PhZlOG_g04cowQ3@JCV@xn!}bhzwN*1{ZB#x#uOHF*Xfe8+p3Av%wDP(t=hmvK zv^6R_x0u7v?#I!t?x|Xa_i{U7VQ`y0~6K%-|=`@xl0H8O7>oH4+>J{$iiDM}Q;M2zAE(#r{v_)H$@F|5Jk5 zbv7^uF_Y@6`lw8*A2AcX%xZy`$WQ1m@Dln9y)4}C7Agz#y}=f|60)$Pk9tqG|CGtA z#QkE%JS&GpPRL%RtMh=6Ol{#Qr?*BR>h4nCy$moxopAi|;S-;`{Ny z#l*KNkIt>%lJlJkktvBzPo4}az51G%UJW2-Q(4stJ(q0rymZW@SKoN?{8;}RZwc|1 zN}?0%Tbxd!|0Ua7rP#e(E6%OZb2v5Eo8u+*Kk{#@L^`3qtrF`*;4R`mDzDB1=HX;o zHIUqCY3bB#_RsNVd&&Hy{%kL~pUfwnTCTNPrk8@t^)mhtq194-MCNy`_#gWzSxu$>R0VW?{iiCZ3xN6A zH{DC=r|_qk3 z^pmSDIR} zi|b3}{%wDxH^RH^kMc%(5B#Ct5b!=xliBgL|4=o4g-v&o}qr8qfR{5$U|B_C+8aaxB zMRgI~LB~_EsspPX^;6I1>{BnDpVqg@rohMQkviZ%5V+t&ncV z+4lN6`)~Nqy=Pt;FtwiwOyj5aV>lZDpQv9|4R#mQH8@vDzwn;(TnIBC13pzxRM>x} zo~pKFYp2`lgen33L@J@WM&|4OHUC?0tk;H_wmRfLSI<<4{bBzq^Vh&}-nU+BR@>;- zI4-JK(+a zUVyKNef-|cUt#}Mbw$*IIu8gu*Dzu(*E{YE^<`BeTva=f6Q z%Ae+aWgH%q?USz$*`0*+1pKqJ>Vb2hMYU-H>4f#zw}R%^-Ee$ zeXHNH^ec|s`yEwa>_ClQ_!+EfwZlG6i zZi2Ui{X4-o#2wz>#P0rSPIssE@XxaIoI0x->4y5OYOEXS?d;j%eeVCluFw55#Lww< z_s_6;R(12wGS`jvx&IS8w|hT%{}6xj{w4mxo-^tf)kHVezo@3ViQdNiPhM9}b@NX% z^Nac!JPkI}P4y}8XLX8aXfvHHwyB>zHd|~nzp4Mw+pG4dN8TRp)g$jAv7xupTj4eI zRuLO|4T$x<)d8+z)X2N+U-BEVvV#5uMvdrA@E&`nZ}^YB-8?dny+_2y-V0tu54?S9 zuX^C^SNp)d>Yv#so%hfAg}n>@d9V;MLu?zrHQ3tE7+Zw(bAByvJtu0>YJ11X{noop z<~!hFbx0j&?yYy6_OF*dwyodBPaoUPZws~|OHt0B^^1B%h&9Pm%d6>qPps)}Al~wh zsKe?Od2V|(n5pUA^p2_{>L&BIymaJAADcF|z2DAHOFv!g4eyvbs&267rdQqD$cgH- z8s2s9xH_h;dneR!@EAMN#CGu8`)N3vHuh6*6MH|URrjv3=el>*JE=~ntMspVSG-f| zq`Jb)Rj;mpf_u_5Zj-q2Vw=)pW9#@Qy%Sy?=Ii=%{W*SdZ?0d=D+(6(ig~qJt>f4B zPkAT3dVXF1IQXx(4Lr`HF`GSe{Mmj9uejHkY)#@ejvGHVUTm|tP2Z)B;yLSbBDW4w<4h98}`9nDKd2WRBlP)>J4Ts-Oi7CPD zl${#f7_{}<_&0K%jX^_7Kg!OigW-LGSN&JOSNy&~OOAHQmXMbm%-M#x!LE3+SaL}) zIhYhI;aro!+u<96c79ubL(txD2e#$By@S{MSN-0ctxwP>c+}tJH{y35_16a-{Ptjb z$_?UdgWVukB3V4Slrv2VmO&H2rSKalxjq<3?jSeNl}wgMHVz))IX4b=`Hz5&;Jx^j z-a)V6nE#sJBxoEw?Dq^__m6?c{nx=`lvvIgCxFY~>w=Dc2Y(%Bz9AUEIS0A{u2iyQ zvIpgR2G<9j{Eq(hlvx+_M?b*zccqi1lKsH`uAj?FmQHr3WRIYG@P>cfzb@$PcLKZk zoxx5V*$sVn@J;^>e=Yj!f_#qZ=ki^dWLB~(`ffqj;4S}6zYEwk=n|ap-$H)dKjC)< zy95pWcCM}Ko4hDk5%dB3CL5q>=r8dX`^|zSP}AT-aIt@(-#lm*Eai^$@|QwA!6klE zG);phU=!{}KJQ3QGC$cjxgyAimV-ITY&6TcC%uy^gNwjb!AkHVey={i)xfXsw|DJa zBfqU{12%-`p{eiZ`5jz)*Vu35w*gzbR$v>~+AZQQxzJzaw+NaCi~N>Bi(nalOHaQS zXYQTs$FF54m;1}mEQfmdJ(Cv)tAd{7_Dc3AKO3x&EDvVG>-imB2UpMUK`0XZs zW51PK$e9=U#gJOMV(41A1!xxf3;b3=%b*@dmrwRcUJ_g!^x*tGlXW>mJ%1R#*#qq1 zclYy>^(d1El}mP~WDoGt;F4fIXIS9R_ge?8f;t>k*RSJucAeY>9MjFefTO$n^*N?& zvOY(bOLj|M7F-&1-(&TcqmyZOVRuKql~P0%`+$2sTwU6Ypwmjzvu zR|J=XmvQ6>N_6o@P`0bzfb*6~HsIW4leIWcZNHY^)pc=mIm0}EuHQCj6U_131#Q8$ z!Cb!!=jocP>34HoT}?{X@;fK546X<|Cszkof>#7xlC%BxLAzi!N6qnTP_ic2-F0)F zDAPGv9l3^I-S6SLyIGW+?a%T%1nq;F;4FWp-!bTb+$rc7%m8QlGpL)Lg6ZH4|9Mx+ zFA0|ROM%b9_Xi`nlKsIbeQwCQ1GZ{*uP7IltBy?Cbit zhOTL{NwT49mTU?(p+pOE`nYE}?%Lp);F@3!crE-Ozxb>>=*s$K{DZEXU)Fz--!B0c zr*^)GRNQ}xU*8in;A{=ucK0In^%+;*F9(+6m`$AP>R=P+TNCW2UIjWx9=W_gP ze;>#0caM_$Sg;q(KDXCZ^mF{ZF4wQ<*Kw_rt&(*(s;=8bnMZ?N!4!Y8U)!}wwocY2 zw~pIG$-V9o^t*ybf~o!#|6%Zv;Nf7JKNWepKh1v#d^l+7-RpL`mR<|^+~l3X)?lkE z=gPXRZVP-4nz_l@;2dyUaAz<(c~`J4n3wF7?3kRF+`_fb;~nXQJU6)&d26sGXyvu^ zcDh#3J#Mor&v`bx3h>QHTil(Ty$rY&ekXUWx_>9>9$VX|7N$1^Huk^LDl@3$?d^i!A#1`N-jut zNVW$%!WVEv$K)oL%@LcRJKSBanqSqwi=(UgP5G^6UK_8qcefir+4jj9oM$F@cd$K} zk=zm79h4<+yDLknyIm8?H}#r$54s23#jdJf#lM*IRrPOoIsC%y&?YyKv$RVNOb&og z=L|EFmr%Bfe+g9Czs*&o>}}BPt}*9n;x+ajat|Uu>>hH1IIdlCP_k{Z4cHFe2z_I( zk@tvu*j?%_ah3f`p-TR(oaZ)otILH?<5#99rzP(Rb_7$wY00U{oxwfG_XazI!JMg0 zaxhfeUB)>o`IkYt{w=N&N8bY7>KbzXM&1<4Pfa#JZs;}ecDYB~&6K$XtPGz_?v&)@ zBtQ8FwY;IpbEt&meu_(vm|tIt?n2EW}xBxk6A)_kx$paW6oJy`vmm0j%Ja_fB){ z8TU2k-UIG&Pq|EvtLYNSVVo%er6r%|*cZI#y-M(xIj%fd-Ye&Q?ylnK&!N-qEJyAJ zzlO(?7jSeON+dsXS5xXUw+8+h(&z3u&hxzYoL3osgkzp`M>uY``#i|xcRvqmx*9IV z8RE%Uaya}DC7<&Sc~#(tysGe*+!O9`_Yy}w0Um*$;{2bv(?Jba9sC?_IX0HG$q{gy z90`AxV-I=Hdez`ZIqq?H6ne~^bk}h7N$8Y26PymJgVlKcXOOBn!?8AbkfWaU4tmw$ zFLT^u?qw*?`_x^_(Vs#m-4{Vsw-G!8|2r7PaeoIRlP39zTT7`=pikX1oZ+DNH24fy z1OBvE6aE+F{|^2NMkhxlKX%t~#K+Jl?f|(@dmp*$(R~Dc?EVbKBu6Lzq~u@0AHmq< znB*U5{tSLc{sSDB9Gm=|x;ZZS8~A%*O<8Zdv*uoJr^k)}JT+_X^X>&dO`lrGnuU0j zS>q*#P;w&QFA$aAZ%O$f%%xa!khwlj!cTIZS_K!TS27QH_j{GhgWdyRE_{XiGWa4`;l2vK z3`Tmdx>wvtZv=cfnia0Hsbuc=MtQGruSap$^N>f98pRt~&s*lc4!#POQF6Jv$gSYM zUj%J*70pB5gI-0>o@<7Cuen#H8;ey1K-&#UV#b!UUGgQfh|GPjbadn0%ed4R;)ToimQ2?0Po}y1`xOz6-t$E_B}q-+|u-i(Na8 ztL>dn`JrA~xGO<<^QgDWE6*=hFz0!1x;NZ;-dpZX@C|pqSI#`^_ry;qAG+8(KvH-=K{+!*M3x6u6%d><^N{34eg?i$d6 zQZ>CH-U;`X8^SN1=auDG%CYN0I%gYQr66O zKLtMq^C`2yWtk_vC%i1P+j|mxf^vhrx7`Uh$a}}V4W4j=y?O5E;HO|7N6mMIIEOU@ z$sOdC=BO-#BQKh{l$qz|x?h5ygE{Wk;1}?hV6OAXw`Mk)Ic~Q5E%-HX#zW(?4+J&a z>*#gxwtJo6+r7KsNk8z%xg<2!752w)2MYU1U-I?5w}p|$xNTl%N^XPh^6vHyc>BTa zoab(+CRh`l&lv*W_s6?&&i5y{@y>z1@BE2wf-B;G=so~Havy?);dgpnIP0CzHg5;# z*zavcb0^ppzSZjnzlWUt;C^qP=W!nA7xh1I@4KRY5qPFQ*-Zi`I?vDaC%K94a?0-W zE{FDdTR6j3?;Fa#@2()d$Gd`@z20W8J2{)Z9`MabTfA@Gd+uHLE$4j?{03f#GiUl& za>O3*O6V!?4$5x^d&0k?)VnUjpW-HilPSHLQcroSq21mluNS2@L3eoHQ|=x2z55Pc z(4Xq2fYaPma0*A>PRUJPI+}w1ZC-Cuw|RZww;|o`74WCKX|4dd>He+gZ}Zap8E(2u zLtns8_%q!Mmq3%|$NgDuri=Tt-7Ih>+8A=&U*-MeesmXmKkye^?EUC|09V0_xvRaa zykf2>{1WeC{>n?JT?3H^dIP}k`J0QlHQv=;5lR$w#a(H3NGZ;7S9!(VYOb-k+f7|8 zPI|Ssl3!WnT?DQKe|A5)i@aal&+byrG{CzQ>hBfiY(-pQca68kE5Z3nnG#S*Q__`i zCCv)TU*ugz+5TXEub-EsWMP+d*Lv4@V@cizD1 zb4$@L^BfxAId{Exoj0Ci`her$KXKM#=4YrV_!E2rIeok(-XHFFw}dk+^*oMp&U5R$ z>%GP3mw7m&`ID-t67v z6(zSAI1T=5<}aByfj4;@y&~RpbVZ<|-fx+|W^M#GdN+E7(H8+{zzcgb;lF48mU$z1 zqqo6JqABbJU=o}K_rU<14R@dq&Vf5`F5Cm1mkD~{Joq=>S?|xxZ=gRizvaFbbl-CB z4c@n$Jp=iV%-_*}1OJ*bXT7hzzcT;K{0jWq`^x(}^RLYBC|l5diTsuKrDxz@dKUgY z+I085_Z|EdFWnUYzlVQ8?w8)HUYbj|SG@u*4SWTD2K^V_87~GukJrk)}2ECnRm)70Dpsg zU{#f75)u>d4D4R7R+XgqnH_=ZlE=6jI@S`b;dkRTrhr-{l58o zh!J8;@5El@y+mO!>^aw%Ke{nrY8t*R-i*ANua1lv#CJ!=oZ%Y}c1OaKp7Y?fOi6t1 zI11l8O5)*U%xid)7;`D>^u}bd;>3Aae=_DM^ZQ&cb5zE3W+uRx>C6Zi^AJ`oe<9Yb zVv<|4lvv`{TnH^DlDDK~#0Ix!IUMU2T9mdRl!m1(htG!=5Y1YWF~i`-TtMt?emCs` za0HRCjTuQSXk$jDjRZ%hjRMD{jRwc2jRD7{jRnW2jRO_UcrdZ8XM=O$L*TQ+y?cbS ziCH}e{ou5L{L(ydF6n{%{@k?l$(sqD2Oo+wBixZ^X4(Ks4rEuD8EMnOq454_2CzTO zw6v+BDSX+o+e`=RusR6YLMeqcVOi;>qIYyz)~zFxSqNq4Y2yOfmp*G?tH z;U!6R1+{}oDX2485?(sokES%K&g_^`ntf@q!u@Wt!aZxskm|rr7wx%~LaFL$Md4M`Ja!+c z4c4aIH;JNXzDZPJACqqqRoTZRlPjwO)}cfu*H|~)3#oG2cZtgEc=BE1Tln|ko)OdK+;!r|#1HVF!hI`#V%MS^_?bP2Dx_)8Az=k}#Q2q6g@om} zx?hpXrG1(BB9RWJvp3Ee@QcKmL_v1l`6^L>-EY21dgwk@h)dPP6mY*+e{z{kPI$X`dx5yR3YM{`16ViA;99c`0Gp zTjr%iEX{&P;78f5%cQ-WI2xk%oq2`5xP*VRL(r>m;a}_`q#eA3e!f~9XkV`1z~9&l={RJ}bL?pK3Hz@+7vd-EoOKAzbBPy_J_4VIKbts-?pf#% zyPW6zCu6YqdK;5(7t2JeC2i*y3q3BM110z8p;i~TgTgV_B@Z-V#1AArBX zt`rZ1_y$+_AY{xI_A1#&6xw}>z2Fx3ok)AYt?_{iL_C)5vac4}2S? z_9X6t?*@0X@5rXa)0Eu=-9bFqXGq-+Z33-%hN!T2QRWi3@JV(kxfCvZg8d*ag9{&L zw}{K(!bcOkz{lWMz;}VW*puQ)xbP8n#8?e~IE)Y~e3+dwu7(RA;tCbx{ATdx#7#sg zznRoB;%NWTXQ?8D72%UT#%SgY`_Ji&L_h60^$SCPs|JB z5Y8ty;39PALFW_uZyvFJhm$jp_cO(*tpTO!F$2iw5g!KV=!ZW{5N+mo7> z=zuf@Y!B~{D6qi-llW1mHNIi)m znuV-bqQV|TMJopvb|+4nB8m#T5k;*6)CDXL&xUsa6$>s0F6_(|7E9Dg)J_yl)P)y? ziV?NB7@8tzih_#AS^`~duvVfbSQ}m#y<#}$!IQ*_%>(mDmn6R?5tU1ZSTj*05s;e% zt!V%@Af?!~HNYB)>WQC-nJcWGsFwJdn7l&8OH|}vVbw&H#INyRh?My&R5|fm7<==# z_^Wu#e|0AAD%umJG&1G-Nid@^D@ju{aiDFy`^oWCemdM555Q{Z~h^gNq zD% z;%_2fz5#zL{&)N@B32RylSq?)5fk_XslVbc#y^Xn0zZczfuABG;*k(f#ZM9o@pE)X z(VYZO665d%G>5^{@aMr7z%%fd$^R7mH2w*Z0TttLC-iarIj-vq@C@aii+=&XH;f#Z ziXwO)sgH>C_Yn~U70K>>@I(0hVN5|qyL+D)d+*2JBNE;N;6u>6;Dhjok=_9xf-Cmi zJK#G+#oPrKzReZhMJ&Ll!KaC=e|P)<5&iB)J^*fqZzK0E@F09!{8{*&;5MS$-%ZJT z;KKd!eetd6?*tFQw{jha!szt-Kt%)Gf@UjdiLrPEy1k%cuU!c}1zrJPO^miDLB(oY zjqWL8tFK0LHS`2{6?_f+2~bhyu7Mr{*TAnudKA0{z7|P4on8xHMO^vYz}tvveF=DL z7~T4|_{#Vua#qIgfUiVaMGWdYkS-9%)`--U{``ANEgJH!Y_y~gO8@vB5)y*nnxooWG{iy$iv9J09+1lOL{&y20oN4 zS`IEJuU!}^w;eh2iQPYs7`pAz%_CC&Tw?2XAT^hG`5lluhEaJthB0_Mk(w3n9Pbq3 zOyUD~Mw&^~`Oe6SJ};ckRdq$0PF(q}$SvZE@81$Wh`nuEhB%No->r}a#+$Qmz+iAN z`OT1H6P1Bb$!A~j?0nE~!MWFzN5z1Xp&C-LDcBJ~7w;JNS~>>tvd z>#2m)9n6JShIb>9b^UlAv8WrsOG2fHE?o*uiFiYFCE|_XC6G!IUAi7SL}Zbl2j-C~ z9&b#3ai~PR47$2RhHgx{DA&;#Y#c_4wx&t^mslP4boeD!m%SYnS-LJUqJN3ij{gSL z0)K`79;?Mp1iurFxmNs-SdDmfuqHct{6QS#n(;r0gIqoSSF9R4iTs6B4g3@SH!+B- z5(D_}5UXe(VM2?L@r{}}V*4*UWB9l77L%bTJ_e~bJbd%67> zbMc=bFaC4Pi)VsA!M}+WA*S>C;Rt_VgE*Dh?C@w4c^VFx#BiXs;!`t)(~3xOHL z%RP>i5q~45IJ$4JGgiU)o9xAv9)FA7!G!6=<~_k4VZs7L>wTLY!Gwu;984q9?>p@5 z6_3Bm{#?R1(TU$<*DYa;D||WjB|E6S5_>tsGwgr%3euU_QS>jzUL|!p_7eNHeF{yf^n;8P;~f6V?@kA%BiJ%a9&*e+5Z5mSFxh##@X)??5I z;G^)z*}dyM@B{ec=sqAy{o`ovi9H{Cj=g^l#hwM9gYQK5Tx~J9kiRhQ?3Ko!G%w9J?oI3WS^6D$d|M0 z+ZJ$3Y%{yJZ6S4OY%BcI*q!hz$k`0u!7dqBAlOu5TOrW!=g?6qCrml^wb!Ay0t|Z)O*gDM&Z7d)O4@ zY0yS+DttOSoooO%!l$F#$j)8U(aeMkH^kPn|JBS8*K=)SiDtGOT*e+sW097{MuTI( z74UK4&PwCRSsEL~{%R}0mGDtWsc2(Mh!>_^lSZN+6-EzROx&&u*`cT-+6%!6aP11e z5?o2SPUsfJI)^(Mbw*l<+zH+VzJNGYT|%7Cu2@}><`a*qD{^=C%9;btgLg+ak9bkt z(ez|Tu36w5cu#b5h~(50O`F)T*id3qwh2+Ow_2lV16}}cN6z`+d9fkj`S4b;;pDV} zTE`Tfa!9Nt8by+9kK6$o9Lt6a2NQLx1y?g198S3$bb~;}I8yvZ;Xq;^<-&ynh>uhW zE>t|FN=W^PN>~ZGGSoL#1upDMlqba>>=RS`L1AyMry5f4SaoR5^5w!N$avD^1MEreJe;X{0P74wpk;9%>k?02eC4TPezvCRT6- za%#uo@S3p%R0E8|)8I8gMKAoB=)FaWPgW#W7%Unq0{#sD3H{H+5&MP6qQ5~&@K^Yc zws@=qPrMOVs|e#L{{VJO+LPe~sv0--Pk}zXrb|TGnw&d_{!) z$IzeRe*eg}V(oG-yI?H5EPe>21{h^zH7xvzlV!*`K$20Tq%qg_a+!+7YQ zhw;;eih%SubP9Y7{sjCKc#3#RPr`+t5~Jx!q))>b>z@!S{SzWPJw@u1Fmn3G;KxLi zdceMD4}*$!|AC8nXf!%l}b zfz#kKkZuR3!)Fo`@K*44_)K)S+gb2iiI{t3yERd8)+f2)q5+REi|9#=6yg#ITz07+By(xemFQ1-Vr{WNZKRe zok$G_hZFI-9h&ywD0t^E0(NI|E+8iLP~t{+31eAzA!is-tVdI-Ez~ZIS$#ecsz;M< z!A~M0~!EUhu0*U zc|TB5&1<3?KuqF(Tu&`h{fGx#3pv}iAU1TitpG1i;z5@sPIfC$@v_Szm19qsCYF^l@|)N)=*zMTO(UZ6TC|No1CPNQvWreb zV)@2NHDvFd`Zf=208gN6z|J`dGzFk~U>ZCfsV-OmUJ$7cm=4c?*8%HrZNHn6wuJq| z{BBCv-;jT2?~+osr2UiKPfCC#*d^#!Q`(jSvutUw6y;L;lKd6!RPwhe#!e-Fqbp{A zq0F!B`BC(L?jiCsnqSyGq>RmC2awcmAVq9p`#yVl2n$>7+40ZL9opq0updIc{fJ#I zguZq5WAl*_I(DD=gxx5Fne1-!2~wv0lszK~*^})1AS}eSy~)lV-^HZ^BsrXU#is;aTGFzfSJ)FwXzi<`~!X6ZjL_ ze~;C#c=}%uRsSpaljM9w%=jnKJjKonr@=4aPld7e_rOmR8~(KU9NYunhx8e^7rr0q z6u1w50DcNQWlplE$IC>|e*}J%9XVbh^$_$hdvzQoZvHNEjWgJ;Z(+FPS6Y zF8BlNB=9QuDtV6)HUBVp1pXNLM~wE=ILyu%$0&6_^ZE@qFOfzTpw z0K5xP%*U{AN0$&sn^DMP%xKdYy>|ELil&npN2(K1)yIKj$?HzeC~zc^$GanqWZ#VO zC`N8m3|9WGRy=NfR~Fk(U1KpJLh!iSn#aG_#H*M%xUY zh-F<58U)sb$GB(X!Mhj<;n~375u8y!r1ubDN_Oe%QQ3v!npM1(3HpLvH;QA%Oa;dFq`0E*@T@A z%AiU4TQ+5Y*6=MkD{phU~eJiLN1jZ85YZL44A{lI$EckXjVS zXEGCX@ObDu8OQs|M^3`ycxWX-d1}S+1}g#g6Ra1+ z*>&XvxR&|nxS7U0ZQOKYCNpj-GvkLhG&5sy^Ipt?PcYLGH#aaZ5jV3K#m7xA#=LP; zoe^T(q%od~n~!W7xCdK3ZZ=}y#?3tJz_`iBYKpV_Kt7m3j~u6!&j1g=El=5idfKt@ zImeJKe}6SnaVW-f)w_~__@(e&NekbPH1r9cWlgl{U;$8XOhGUm)Ekol76kRi6aq6q zy)lKtw_8lu!n^IlyX}LHC)R*x7lh9}2?jhp)rZ1h5>#y|0u}~U zmx_kTL(tA-FDn-51 zyORZ#rdH~mDg$LvXZ0SHh00K)_0E=q%2LxikSY(A<2~qrR3UtGv%w0yJ)Pj$v{{{a zpE@H|1arVH@LaGWsP?ZCm>%oIhx;y=A)wdsA&E$nm>%@d!zaJXnsCgPl?u3qV=z6y)s&_jMkT<_2tMP zAoAac{5K+ho59hv<8U==+rD z`;_Q=qUigt==-ned%fs;z3BVO=zG}cd)Vmv<>>q6=zH@hK0p*7Ad2S@#dC<_Z$$A@ zqIfA$e48k~O%#tPiboX1BZ}e?Me&HDctlY=q9`6w6ptv1M-;^)isBJP@ra^$L{U7V zC>~K1k0^>q6vZQo;t@shh@yBzQ9Pn39#IsJD2hiE#UqO15k>KcqIg76JfbKbQ526T ziboX1BZ}e?Me&HDctlY=q9`6w6ptv1M-;^)isBJP@ra^$L{U7VC>~K1k0^>q6vZQo z;t@shh@yBzQ9Pn39#IsJD2hiE#UqO15k>KcqIg76JfbKbQ526TiboX1BZ}e?Me&HD zctlY=q9`6w6ptv1M-;^)isBJP@ra^$L{U7VC>~K1k0^>q6vZQo;t@shh@yBzQ9Pn3 z9#IsJD2hiE#UqO15k>KcqIg76JfbKbQ526TiboX1BZ}e?Me&HDctlY=q9`6w6ptv1 zM-;^)isBJP@ra^$L{U7VC>~K1k0^>q6vZQo;t@shh@yBzQ9Pn39#IsJD2hiE#UuLv z5|1dy#!Ww)4d&PiV79Gjb8J7G3-4#kqp4skk?Lp5A(yw6N%ga3k;~aCr25%Twj-$y zP)FN=blh}C7dKsOXRtk*4z?;~``LC-d)w7^LEkn^S0ksNZ3DHn)onF+>o8q|R6pA) zOxLtE;4Q;+i%@C~wy?WRFY;mxpEdiFYCBf3R6qsd8gJoYF^U0elU*1}0(Z+B!C2>e;$ro~;Mgw|QU#TOVv_8-N#^Rg~;w zdm~>$Dq${#Crn@42hC-q5+>jFMb_V)Fm-G`a&!L11az6XhF{AwD@m;~7lA9ywdnG| zJX6oCg$wJNI$%Bc3d&q$mV+zIb?EAVbxdt@J-oJAhJLwO3NABCz@=s}xWrrtE;i%L zSkoQsZn~K<;8?H+e7xz(UpF3YS8yDBwCPFCXlRTXg*+PU1s`Q&yv=L{?=)M$t!6X0#hfs2nPK2CGt|5Zz6CzW+1`YPnYYOq3Jx{rn|I*C^UM(N zeE1vYAI&|C|Lw+6H1%IFX!Qdb>5F8Bu z06q{LXa<CD}6SpxiVdG$$O@IY#8klYifCX(j*xw#DFMuza!{8C~BKVRy0v%^Ys#6j{AwAftSL{bzpVi8Z?jDWFvnzr6-^G9Ybt`3 zOfFd2R06A*%3xJf1*~SOhS=XeW2*6FEcgt(I^3GQCTRk&Fnq5m0^e(j!uOhD@V%xu ze6J}1KVZ^L0k9zafXRR#Fooa;OeXw*@!$uHgC8(H`~c_m!M*UQcAuGMr+`!KbUO_` z8Jc2eklJTv!uOe3c4mnC%ziW5&a(T>96KAFYv+LT>|AiZod+(k^TCC70l3I61P9s+ z>@Yjf4u=o4Bj5w=NcccI3O>+|h7Yu3-~;Vg_&_@jKG2Sb5402DhI0%92irm55IYz= z&kh04x95RF?fKv^JCsUl%ph=(T?8)T*DZhX0q_9#$3oR95#uQuXdtyAPLCRccB9=* zeUCxE@L#n*P8-tAcB9|uZo7j$Y!9%f?Fsg>y};gB0o||$`qP^?;eS8dl>hx~GyeCp z&CxfpjlssY5!lE!1RL7h&F%DJo6IKg4s!>%nf9t7=j%`2ZQyO@R`6DH3wF%_d&->R zul)@9l*!<{8MYu;khiQK^d$JCDP#+QnKl#j$Sq`RgSBlfu$HaKwf48AOexM<+LQ*f zOcq#%J6p<>1WQtn2HFzTh=F#m*$3`36YWHBlAQ!j<_r^g8drz?!d3LtmLB~oa1ENP z>El-;UxU1czOy&d73eHIWpC1#ld|-by-80D`=kkB|D>L(ci1~k3VWu>^imVhTn}9r z_EJ;m7srzt3-3*jp}aAqdeg%wJ(^T++7hKlk?Kv0qVz~oz3CN4g2UmxsSV5NyBFCN z^y7={MfCWK>`Hq7MRpbT!yf+J&#>PU$f9&NN>K- zE~aN+XqV8-FSJYP@fX@<^!^Ju{~{}UE{^RL$MTX@7Z0tvI5wHIvhCtnX-Ws7Bs(vT z4Hw6PleHHQt-Uz5owOe4cn`{9t&YQzEytTN4tWe*C~I&$`f*?d_ynxr3Sb4&6OkwI z>~i3fLW_73(nLEMc@lMgHvM=EnhVaQmySXGz$|_`0G&6pX*yBRa1`Mp?Z zg~lk?pECXFqj;C-&0^3Xa1gy*3>pHC;cuJ5Z%qbei4W(UkI}~DlAapc;}@Wd(e_j# zJuS4#htWpF%yi^wv_7)Uhw|pf%nan|v_!JO&qo*I{XZWZV$TBy+acf}+J%^DOU=)~ z63>LU1KVP)$9W^#b1yT&OtfvnH>eGH8QALTuUexkh^^ilxg}hv-mE259Xq`x*c>jD zjh`^>84)B*2gVHv(~+@4!gOM+kT9JY86;>qG)736E@A7@HEcb)g{?>Tu=VH>wjMnh z6{sbt3D)2(O_-YWCw;J5%h9s*0sDmgOK+s|w86c3U;ARmmZA6QOOG?lmZ!g&Nqd}y zt=kVQ1J5?i`3tj6Rqj_dcWx#)lhWBnBbCy$7HR{s;5nul*ONo}?674RKwF@;p=8)L zmP9vz7GWT*ZVB#gj21#IMR9nHo~Jli6dt2TDhi%8O=$bhnx^!Y--6BPFPm|8^_orT zO&ik|eodLP^s5bN3%@drXcxai|22K`xAd0ZK^5t}E1KM}FRw^H+<^A-OUi#m&)fj% z2l6U~eS9u`dnNi(_4JkKz4I6yoMEKU0Bk^i{u6msLJOcWJ$xS8pGj8@t$`}^{B;>w ze9kB%56r_B_>3_^U0T_?q<^7Ywa{XyO50lp?I}~6QOU1ptJ5?50zZl76j+N^_BV9Z zv91!NK7~$VZzV{741R(IxxmWaeE|Lt^dOd^r2Eh>XUqAy)w9|d<| z>&-`c9DEErXuf@%_I^H=(Qfcbda3#JT>12C>0mnjem;}|X3+2FLz!SE{eC`wUjguU zEWCWIz28CEfcc>fm>*hy`9^kMerW6En;5oUerW6EhqhjRXzS&3y!y~>SltHN4sOR* zH_#4n2iCrUb~19!ZQyP6e|?}$;3oRNKG0@xGZuRvXe+oCOTG`Z z4VyYYw5VT)zX2V`9+&hM_$C&7KGNIZ3GDKGq<6u0u)On;-Ur{qp3X=55c~lAnCtiu z%12Iw)^h@BE;i(0@GzF@T&&h3;1Tl@_>wsaK4+c>pU0-1jXc-R4tvSj^o+8IWMj;> z2e8~`+o!SMW@FDC1P@}V&cVx$e zP4|Twf(;pY_k|jRjTx8sg_?p*84dS^nuE=aM*H=U+X1tpQ)dlNP z%FsK?-dbcY2Nz&*8J_wAyOWXN0<5oTvYysD81>2=UZfP zMv+*ej2RcA*@&(;BaMyV26$gaQ2EfS;H!+j@}Xm3Uq(%@fJfnddD2HgS-5?f7nx^U zGE*|ow&ID+L(>9XKI6yU&@gZqKiKj!-A+RVuEn zdWiP)9-8q{FVYTd50-_u1>1q@H`+pFsfAfct-&^+dV|(b7S~(~sU_{dA|@+VXba?) zp!$U7VQ23{)IVK!W2gx=Qg@;e)R;P|d(#kV zM6K0*Xb|3$2Iw17oAs?>Uf7!Dh4&{9O?_%&Cfd4TTUQsk9(7c$Umd6}wN~w6ZKw|Q zSS@5Ns5UiQZDviVR#^WEfclE7I<-&VFz5}a7LEX_p{Y)Pps_+#s2aV9B~=BgN*_a` z2`X9`F915_$%0Cy401{mW`l>w0yFr8$*r47P1&vjC9km%~UJe zgcek7W;3WMEvwqh=1?=*TD6%ipyss4>OopUEoh|e4#@54S=45Bgk+_tozx0J0k8nt&S+$-Xx5|) zB#T9DVb`!d?22C2izWR}o7s&gBYQr2UjHf2D{2q_v)aSxc}34Fvibl2v-zX<>p$!L zivMd|X0b=2XZN4=>{27@|8;zQ?s;mIE&1Qa-Ty9Y41TW6zn|yd$L6XNsbkJ@9V4xd z_-7oiGXIS6RaXE0Ie!+GcA3!T&SDJUF(Q!7U78UCf2US@EvR`4|KF}6 z&ivhF{GF?8DRZ%vCr=sHzRIAx1Wjr1V)#mEm6cad8P>-%(zzrocd5O^mNplKCFJ2# zhBdS-@-DNNqF;gjB3qUbg`(Jw*2)XICOEUR!?`PdHI<+q`~%e;!VB=`#a5V_B>^6((JcX9>gz;cv(&A!Ut z{u-+e^X+R$3+%I$JY=^rQ@f72_;r*!M$UYD44P*TlKZUP!YuAA=Idus;&rrh?d#;v zV>MfzLYtv2<~Z6p_Bc6n?H#N$&S9>94tZ~&n`0~BPovSc{AwzMUNjY0{dfdfUNIF| z{m|OSV@Nl^EAR&FvwLkZv)}Fm57_u53&PUSDOLK zGvYieZ>aN_Z=MIvTEQ$(9uqI~SG;2G;`g^(`SN5l%bd+T^ENbh z*}Ls_xcq>!S$R<24s=D$ozOO$Lr!++F_gpVgi0LYin7f;b_eH29 zLdsz^V*}-0WWIZY*-8Fx)=f9D_HsT?V^ioqafj(|-{7z74-Ej{B-P)(1wYQZOAf0d z^3OR8y=d;WJ2}I>(37@^*nfu9q+-@TG4l6IM9CJJJCf0i83o$hGi;$nk?W|iqYIoUw z{Dtzm*aerDSB|-j^0(Vt!P{6fmIu+W(1SvLA-5vm%rE8J$2dBlUwRC@AD&OTAFIy8 zSlhXPm7PPNe2V(o2gvVhAB6Ws%C{9+TROq~kvzpJhF)M5S&@4e`2@dSk#)Hzz}@hQ ztVisoCEj4y+rs8Xy8+y2Zv=0$8^N3HP2er|X7E;f3s?j$|CmE&c1NYAiN{0KR{?OJ$mq&}=HuSLq`Z_w=59(XP*D0}D)*4rDb zW{%d|@6qJ`YZY~@xxucpW68e(90S*iYA&m>d&5=OeemyC<=TgLMUwn+W}Us>%BOK1 zE4=&3lb2O4{uW6}$dB=QE03#O)_wPftG@@}@=d(nPB7Q;*G)jW&W@z~sBn!nm$l;q zls;?Z7j%{@dm8y^bQ8^5u16k?YwZZij||sdbMeUyydrY2^Xg%U(d4;o;h6E^Er8C?}uDo>uFixvVUY#?Rpk^k1?f)suC4`APP) zS|812WqCAt@|o;mHP?0leW^SK16F&6g7PFhjkm*SdzzAGSncY;dcV9Yd)V{HKcBT` z`89n`nbWNE1gr#ohURnpB(xr+IlIB2*0!|r(-)Ngo*#Ps`Jo@6A9@V>_*V=>FHb_v z?)3q+2G)kPvzg4;wFyzaob90LVB1ihj{j0?%Crere!5%DHT7mLuorWHt&n;#pVu8v z1+5Wvw=KzS#e7}|)6KR(Zpr+dJQ*vodip*n|HMkH%6$la46nor_s5`o3@e4J$(6#@ z=}6=dz5Nyv|6NfB1Pk9iTBB5 z{5e{{OX43h9-o_%U~~SmDWJTYo3qY36?qD!T2Xc~UON*gRhn|+LNA^1csF#VTx;?s zfvw=hL;tAalq_MhC^r@?4VUewHL4oSHfJ)wTmzKXZYFcewLp0hXEKjm2b8CACgpmX zHk@@5{uEvDp=iolZ&y6UC-NI*LSF>=f{#TWOR6otE0gf8=!Ta?6V`*fnX;i@f_#Hc z;e|AbctN zP@YHy@u;Z+%8RBT+G;kPUkPW#xg+WL|8xZP-2lFr_`{}${;*i`coL->`Rt|RrI!K9 zHz^&Tq)bpg{ONdlIZ!_Qviv*S>})QVYt=|24rzpuot+wKNTbn)?D^D~*` zBN_n+wKkF!u8PRkuETgit0EdV2(>CAJ6@<&5m}%@`6ZNq8epT92vOb%ve<<3QIKUO zl&6BM3ZeWJ)JF>CwNMypMoX;qk0jKb7F6pW0n~zaQLFN5Rn>ZF{X=b-+B~h=Yu!Vu zA6gI5x`$Rjv>u`r53PH&hDjWN#noD%MU|mN!6^>o2Damrc_GjO_fsV?Cf** zL4O191LgEvx-a_M3qmnaBT(Hv>OOZ;e#n_%2IPZ2c^Tm|$m(;Mv)_bEzxS-Avs}U3coO}ag z^zP}I=?L+E?)m@zj8o6>+`UhoN##?&p?jzE=-$asTW3rMb^lYP^jo?<>GW6XIqE)J z{-@q{J(JYmsiSpXrFB+GDy?f*=~T<88c`_xwL<)&o<^!BtIR+5_`kcms{g5b>>=q{ z>o3%k)sxmW>8a`5x&}RW)iC{a`X&9I@(Y1_p9(^H>vX)HjmJ}`^`j)MAEncgbaoxD z-_bRuYTdcBXJ@DCW$LPx8~@ky(H%PX-so9%<1Lmo)D7$k%9o`p*aeiu(*^7dwxV6= z40ZzL%hCz#2)3Xd=?HcJ^~F#Jusx_Rp4x+DKz;F422^_}8zT#B1j_1Ai`Wp99ikSo zLD&{*C0Jf8Y76T_@?}vgsCH4-iCV#WkbGIx3f6_>%c54W4kTX|wSu)F`Ld|}s|CrI zMeScrNWLs;`D#G&WzqXp9g;7L?tV2$R)~jG6)s;EJ)J60)$nQQ>x2x_m3T%OU8WP>@NYGwtVMgrtLqA$_&D-Tr&pRK-@piieqQ5`7@ zmE)InmTKYg`nz)Y{fhAF9A5#f2Cs}pf1AFisLZjsT$8@JkX2QIzssVl1Xbp`^&7IY z%JYo%W_5uoac^p(uLYImd8@v3hPrV7YN4qOmEqa*uwP8|lEryu8DXELnytRF7|%~NTkT?N>W6Bf`b+hm>P@|{ zuB+W_MU7G2RZm)k+Ms%`RI#*AsURAxUW)V|8Y%|^>eb1sds}lE5 zPegB4E_Y7PQEyg7?p6*@O>b5XcSz4sZ&o(y!>d{N{x9cvek1xevEH5>Ar=@(+6q{ULYR$N#@ytVrv|Gw$qv(ZE2?p_&(e4w zj?Q$nvv18I7QFp>8}GjU{9ycH_xtv?D9AD^Erv zFIkCQcs3fBX~wKG&!+-%d8i}LrhJI1_p%Iys^_u~g{swR4~6Y`ZfXaGYKzql3RPoe z846Wn)fx&@zJzL#)h4#!$rKM!HBhagP;IeVL!s*Gxtc7Wm?Y0j&r0<=Kxzc)S^7wN zRsq~0rThvtKGYj|Zrmu(LbZx{JQ=;sj8x!i8S{8PdVU3=Iw0d0o{U-rwTX3jGHO56 zCdx-vZH!vQT09$h&&sz|&q}S4+QjOh+B3C@LbZ14@v4Tcp-|t2sTWkgs6PFi?WUvk zE9xC(xt%Z{GWI?JX}0VmM&NHEeZ;)lo5*j6p3ZMmMqbhHlX?ewo3Z%&NXIGlF{Ab4 z;JfJFVP@|W#?(ic?>i12Cv^nUw|g(5muK{+%r_n*|0U=Mqwp8d$ZPf(vy{is9wl`w z^rk(^JlhMDkQePyW{pnbJHHRzN$?bNN&A>xd!G5IQ_O#r}v|IjM?NTm}h8 zpP0PVZRoKcWB&YJ^0qOve{bmjzLQz^9i;ApwuOH2cQGftnP(?Y`MY@bcOY*FYs8Ia z6R8`aI2cE}9!fBKy&l{cddY93%#ES%{Ovsb8_?f`ej|7*T%PqeF++a?dGfWtiPad@ zk=3kEtOL`+Z?o3HuLx_9zRN1WYR?tarmHBUueh#*U&|`Ub*#EvNBU|~*Ri5bPL_Zf;8M80j>=%2MPE`ahnBIvqi?GUk&|IoAn7}- zRd9WMwSu*h#pLOGtQE{(>7AR!?E8h_g`{Rdn$emWzMnHdd6RprE$F+f+0ZOz=H=r( zM?T-+LbUUc=P&~|os#;tX%6rHG~}_N$N5-fhwPZm91Z&57`VP4^O?V#LaA}kSmq8V zlNt}{D>Qwh7EsD(-f(VXaQTs+7k*h)n3=<&$VEsMW|pQuQg^5usPC`3A{Pa_!PWm3 zWtJtMoE}hj<^}tb>IwA#`@nmHJ!whRKNo|FGVj+LP0O&YZH2xVEwOs+R!C}(&$Y$p z`q0+os>fANuD-h?t$9b%npf;di{BneJ!}bD{C3Fo!q&YWx)R7GX*uhKy>6Yb2T(s) zl2)@0y+Iy&^_S|0)#o;$b#6ksKB*>QpIe_cwRYHx)B@H2)~DZ650gvlS_`a2Di@Ls zQW3rSvMhQ&^`DiXTzaN#H0nKT&==MSdqsJJs^8SyNH!(ZdsYs6y)t2cr@pNmdbP+J zpQz7O`>fVjeXiPMjk(lLt1VXxZa9ltcYV#PGS!e|&8p4UHx6-7{eb!k^$qIfQ+ z^01dBBhPyEkn%m1RdderQ7{-vPV=0WkYrj?UT+ty9(54SuC<>vUwk5$;i^l;SG_6(~TOSv4boheTkjR73k}P zf9yil({pvbd3Yt~tjT}u%a-9ar0mXC;WeDIN_7ow!fO!9ZcSOSx`uY)UoX^KlCpaB z*PpY7|FMrdhJSs^ZtfKR^(lM0bNJVH3IA@Pu1)s0ylM4)h{i_3ZvU!*s&Q42Rrk)> z87Z4X_D8A)rmT~ASoc%|RX6p$k7}Rlrs|>Uooc0OplY9LrRt&To$Mjiz?99D5!OA` zK-JCqVS6nbOLH`;j~eNmv%nf6owLjuA)T|>8Y8K-RIQXfSD1RHF|RzJ3y0Sx|6yH` zu3jTMSyH+e8qLW@(%sVNP4<`WqDE=DBGng-%;dwYCm__-X*8yBm##?9Mk6hGLAMF7 zOHVN)Y~eJnQs1O8mPS(=O{*4UQpYv7n3`+Um`U@FnsYoiD=80cwTc>9>Du&8$zs*0 z>fBc`^7L-ZRm$sIBNDZNnh#CQjLIU`xT6^NP(I}U%ps(F%Tx2Jnr)Spt#N3|7hUtP zvd2?C>S{U4@ch)GsnyjyuG%)WG@9R)b+49GGrk%_Yy7Oyx5n8TV`qbEQ`LT^M(Y}* z%g0{h_gre5e7QB^5T?Ak?f=#uo@)tXoJB2R^{{rT=Ka$is$Qxd>aS7Tm}&{nwTc=m ztLCXaR7;p@6;mzYxmGdN9%>AxnwJTxUY=_YQ!SxdMb*PpOQ_nYmhu0oJyc8hPpc?j z{8W3WR^*>nQ7xg`67`^|maqi1L@ndF_E0V1Kds__-5#E62{p1(E21%0s#W}_Jya`l zu2s|+JJk}VTE+i2?V;KbJukH(|5g7LJ+D;%6+JJt_|f|ny%X$+ z|4;W{^{@yHZIq#<%EPX(pbc#Rjl$|fvH@guG=MZ3()g<(BpVd+7_X`(E^QZfYi*o7uo=_H)JWw2GA(1 zHKZ|-#$Ro)36o%ewk@*8MDp!z2Wd23cl&UtJ)5kEdR&E2J;+H2&&_MUe%TMq340Hh@N9RUwUGWpz}8Gk$o81hmk$6hz#fE zHzIrfzn_na?2X9YP*jrt8|;m!|N76G-zbB9RyMTSWc4(~#?g9%?4Tx~X5M5UH3l{R zCcCK-D63HRR4Q)6x%s!^*pKqiC%LBEJA#a^}A*#L7%$raao$Mf?>^;rA z3Dx4shsOtN!R5o_z?yImE}xwmNb=#4&rWr?ymtzL)!_2sk(<;ztNE{rj#7Ec^U+MYyazPzm6}mctu|>^ zUs1C(W1E8&-5zR<6|Cplfg|Lx(+=Jdl5H%{1kI+m2W5qJA}u>v&%1M213FVK3%j@j z=`Q4Tz#`72Tvw~D8jZ5AXJ-FMIK+VkeAg%aZ-6-D+ zsTePw!-PplczM5<-~9Tn?w)?S zyQ)r|Q|GQz)ttM8?cy92&=$OiUoodL#|JpG?sEQrF?ca&FGtf(1s(0VoV`nk4p3XU zn);>Sr5vqe{|X`mrgO!5_Sb=zlWyR;*5DPS8^MStxPoYd>0GgiZ5?Q=!6x+lbkL}w zEBTFU#&00KlK*WWM!{%=tNH&%a3<;1>>1-=#L+cbYhA+?b;L}#%KWu#u5|Az^Vf0B z)!$5(*o-0}rN#VTO8~FdV;5A%vBiCOCUYDaRjBdISMqqd1E7W^8u~ooW zOIKguW{!t|&Z0E};|B2h9F1`k|G9-Ln1jk4jM%uDqgyzh4c^F6$=wn;h}h+s96Rdd zDA^29+vh0RbWq!;&YcEo`_$TUA=*B*`4rHxC$;=!P}}FY-y~4m7m-qq1IGGnM!RVN z9VHtNY5^Vb8wY9u9VOch)B-xgf+lyb+bA3T+^dxnq*2JEx zwD#m$*KKvqxO2!^m6-Q%4!NzuUP)`vcBR&A1KJwxn=n6x{2Q%p{I+rXMsi1dy?Vqb zao@!EbI<2j=RQQ_wrAphah2$QLOx@^dKCGN`$Y-IZ@ntYkCl;6n0JliAZ!CZBx zzRg1)wjR8*7S((>%U&C6K8&t)mVJj@O6H&!rPhHGvX|w$wjDw1$GP*qchr|9$|}iO zp6sLa=UC3nNM_@ijXAMZCS=B5lI=GY4Wx;8iPE>+t8eRj`i{=*S8jUbQtgq;xd+eg z%o*##+Uts}HgKPMjym$bL)q`ZetphW%K1#lcOTCCo&{L&|9<({-j2Pt9{i>q*q*%g zV9$KDD=L-o`4{7JUdQJ*9iL0r6+ihZM=nvLAKS2R30B8nExU+w9nPEB-pBLQ3ADZ8 zpnaVQw9k>?aQjmsaO?hmcy8fHT zuKcDBaOB)^^FfqTms~1ca;exxTJzLsC6-DTN~0ZUsdS+{qSe>4uS6-cA^p~@Z)+`u zgxQLfZ}o?>a_li11=@~hC>gE6Hr&HGE^3w5++AIvrm5#{-l;QN2i~z$uD?$CO`ZQz z$8UU7XI!)aebeep8Q;{oGtSI$Mo1?%TeI_L)Y^&rRa>n3M(yW3lF)$O&-Y_p^PHn@ z)K*vOuQxRn(Hm-ut~{|T=X#Px%j?PW+H+jn=FFE8+X?jfwn8P@6)<{%-qAHN)KH$a zHMuHAPmXO+)uPr0|<>PMo_iF1l zY}SGnOa16Gt;0Gtb-!iBs_h&{O*W%VV^2Bl%6-+Wok_d!+>$*dRw;AVl~Nda4C|wmcvVPC?1y&uZ7p%1qjwm7 zqvh@OzJEx$wHC918t)U;7fjx8HwY9#Za;|>y9n~gkmgsXSWxk(sr-b>I%AFEs z3#_i*V;Nae&n3@3A!IrvIb=E{Ib^!!@?2Xlu3co#)obcc}9?R(blZ>v6kKDxrU@?E#4A8PYb`<}J=it|nL)zUJl+PKCtiubCX zkNMB`xzzMp^Nzf;n%>@5ea?mYUyWg&wCADu!&kHqVxLb9VL#HgYyZ;zllSb*W-IWX zK1FueH}EOm-+TI$=n+Ow!TW3ZT2el>*R-rme5;s|~zb^xo|u4&;iiU@OkrtM8J%wyt0u$AfvFI#8WFm_0rJK^*DHbpu+ZD zxjNigukr*#IBMX${6U5DL&>>3yE{4kEHoc(al z%i^>81be-}U^vvcBRMP2F@pcdgY?0Vvd=MwJvow59O+?=!c*!)xjDz751x`9;x24s z@R$7Gu3R??ug1B;yRqpzDJ{+~9t)1;XgvQl)>hw94^e;1m=4(;y)Lz`KAh~27Qy+; zyMg*#&U`f%rxR(V5_Q;z`td#N1^1zjO8(cGJ-t@f$I~C^N4;3Lv0`3lQtPt=*oAZe zd+kB{sQPLhay?qZ12{jB^UmF{)jfR zT5U_MS(6RaOLwrsk@Z-~^=S?F;Mj4L)}VcC>z4IJ*mLcTVVt)fjj&a+Mo@=6!QmWP zcdk-Cg7d*!$zjQ4jpR(s?i`JrI%|6rXRIA-Rhw(wTHC!z$AY~;nK0*h_Xd@TN<|A` z`%><;05N~XzM5^bQ3u%$Lrdrl*`KooI?q4a;iJ@1D`vFWGX2U+9rN5C0i6L?f@PlV z_84a#;LQE3Yje$oTX@3XbPoB42c;Co4(2l#Gg$2qso`G2jMS?4!p9tYnD zxBE2AuQSP>hUtBpV`qsy4ae)Tv%{WdX5WKc{UrDVob%J%!5LvsGt=)u&OXJR9|Rxd z_|5G5ZJmNWXNt9k-F24VM&=3189U!^W1a!HG0zO#m}duW%<}~|=GlaPeQYi4|5{SN zKDHLF-(zQlJSdWTz@wEXEDNY0{iE%?+Cyq_Ev%C!sBmZ?>uldEbj4KGlLP9qd>=HX0ROt zI`T4u?KseRX3jdB0l&YAUpmGkCq9GU&Sd=O5YQ2#nQVt;uGjSpoO|V$VGaVFTQ-Yr zW@dk5cGh&-ytB6CdZ)u;$2Vl0dp4VKDCa>q>r8feDkF6JbL^^9`!iOzUmmgBmvk

nu z`5wdB7J$wJ8P2u{bfhn4(sZU3jzr^(GcVh)bp++$+j6E2^ETzB zuL5rcWvO4u`L>{QG+zZeOVk;guLk{^jdL|$1Nwa%=W5=b#}{sA9N;GQZ{qB0IpbGz zobP!D=v-01+IJ`D98%|nz7BLwsk1}xVtXAkPp@I`ZpJvS$#YWGBe(G;_i*NJw8d>4 zw`XqaZRn7Dv-ar68@s}(n%pszdbWE&XTa98X)g+7u%7LF(D|A5Y)iqV)Kxv(a8T~P zo-MpAEr1+-F!YXN9ER-r)j4Om4(0Dw{_7W{ZbR$55l!+K+rzYQwZ^;H)`5;3y^C!F z_X*C{v268t=y2_};{@vbVdTtr2rI2MiBa_tSzE?vyX$6DN8z=()zNviv${IQ?&S&` z(|1%uyC%kHM;D}34m08bL>Wu%k*M@)cSKv5_Qe^Lj<#tVjao2v!I2%udF%ttBtHW| z?b%FnIRqR?I+H5~(SEfBe#hBwArGd+X0Z(gTXDrK_WWA%O#ZXw+`b8%v90gUHi>pD zqh4Ki!P$PZvsRc*Tc67QWKu`9yizSQo3k^(>AZENBD<;Oa2BO+Vvo@EUSwpnKl-)N z_Y0=X+OVH#P53J>K$8=itc;H|V8zv`29X+hg6(4=#7{i$jD zpcg$mhx+W5^>A-=q|aHvHXki*kHzQ;ql*(~oiE%2be8ZU&bVIAY|boZe-YBNJNrx6 zUz{bX2W{Fpd$!mfNTO|EAew$Z&@XXjJBOq*z19%p3b?`vL(`fcgIpsH4a2l6EGu%v>G-TI9ZAu;4nc#cXY_DFZ>mFwB6+q~TeEF?C|A_84F>gr z^h@=R$I$CgZw>~HEbo|mAsu;ZHK=`&j#MCab&Ju7u#&*}p9|V6K%(7#xKG`uFdk%66kqh5D z-qt+E`&&BdRr9uUo~>_R)l2aP%B$tAMph@s6{4J3mC^Eil^?dYs=TqaRpp4REz1rs zJLktzsn$f1&&8S0^*+5)k<)dwLa#i&Na}wbZ*@g)}PtLj>HVQswDF*xf^SwUBloNuYr=EZiacSpv|?qoXbWK# zWmvSdUg7h6x;&Eat8Dvx^C2&3zJlknHF)QcLM8C|+$Y}7yA{-oX{=T@XSIQYW+Uz^XEn2SnB2}HL%mq(pohxlsDNw(LT=(Rj zS~sI362G*C^yE0=Cmaj#O9u7N)KB#b2eCF<-~8mh+^Hkw=qO4*uI>c(A??o-+klOA z)t}?Ol#y)TK>pJQY)d-unHn3wdB^Abf!2fd(*qpDd3`fIG)I#yXG_+4ZOA!m;64M{ zH@6M!S!3FGIUO0iL8L?Zg*B!I8OA2pBR@2Zy}^{Q?Rq$J(h5|kSa01x>vcH))0dDd zvaL3@ldwuvJEg^_+AmvM)vj6oQ7g8Mw%nt(ji>?qujkaG&sJONQSWY>Rg&8yhFkN<(HKa{a|Iom=pikIC>W2qDBU(VT=!QWM9o-ucWoDzt1ZGhGe3rnK4S z!#AE0wCw4SVfd#a@*w_qh?x6(d64M{RCBtF^U(YW%3NN~I;gi=KhMX?&hJ z3Y+2Gyr=)GRFo$F=kvm+h?27e!{^c#SdN>QUsyu#q`kJ(;#r=FeX+W4o*VZ=9^?PD z=UcL0^@l76%S|h%Hd9YUo-D`4XVvbvV3pAJ~uo87JQh^vzwzqCaS?zA^JXL32@E0m$_(MsQAM%{=Xi4vzI8=V8}m+eWfE zOI99#F58~jJLv}Mjm_b_>kR5`=(lvmR~^E!UdkTic{FGAc>Gpog)V2Vgy=8Hf^`@#cKbVl$#Og^=#T!IS|(;oq-G( zWA6Ho_Lhu#wnV2>x<-_{I;1@?SrqGe8YOQmxvQMm3T1w*bE9&N6K~5FEz?=d#%s6X zyfth5xUFC^IEmxd>`f{vmEc&EOMB$@*?f+=&|le-wG&FJV*uX4F-4zguimTlgKT5= z1NBd%1=|+Y9BS#%k@gO^yk|Ty?i|nc?$K6TdjGh)PicDpxN|jMabNEr&uZEGH@&~5 z5oHmj6S_Fw+_E#@)@DoYAMaeXBj&=pTke+i&bxoSbL~?a%cc7MQCo54v%O(eQhd*l z3uUF{d5=3+Wn#;_#eJ&JwM@LbJb`7@lCrJlv0DEj*VVU;=f*vw%o}UEW%sYj)3e_{ z?i^2vx8K(LN871NwZFCu>}h!KTG=*dwYIxuZKvv=S@P93rxaIPy-#>P?;rQCwzbe1 zTi(B_e?rHYJGGA5M%=n?sl9*Pr#2U%(`xe)&uIDmTk;N3_wn?|X*{>~O{(t@Qf8^f zJJj~s)t#~d>QQ?G_F3#3#K^ai3`R9X3`2}_I|^jHLO*O_FrRvp)%gkfIeIs;aXxn_ z?J|Mt=V4hl56@2=kxSaqXlF}k^+$4FN7nS2MzZzCVk&W?_@AqSk0c$P?W%Tj0QS)_ zurZu*1a34()ma*THDZ@+nVr31bb;1;S2j6bqX>-gHg-U3?<%_u*@kK3>AvV>-DT2|8*s zgEtuq>haCsopu4oax{~DS?U>_pT)l8A&!JNPEw%{AVa-7o9lY)%HC}9u`9iYIpk(8 zB|f3p6ASN*#7VrTV_2@-F^p2*i@gb;zT#f&O`_j3jVtH#Zc{*49h*;HCWG_1#?i`F z^qGe6#tV41D=^O@jg{$Rt@=g0fxWGToL@{?y4s;DJG&O%c=&R?+r8NwSKS-ri!$)- zevM^r=6#of_Qm$6yn2Ci;C}b#cn<9EMD`A3bHvvffX)s)6#msYgGXdG_DJe(JRGg# z#z(SsfRElI&*pPY=VN$>rQlNTDQCR|JRpxl@6Wm8*cQW#I|gt(&)6T_4+h<_?t_YD z?9T;HAYI0>^ZPt|VrHcsT|bchWtp>gg;D45IqPp3zdD8godmj?>#5Xq2e1QgcN*KF zplq_=r#b|l|1|cUv3D3ueot8YSn2gl^0x>3j%}@5M8kh@iE2Y?4qhO5b819%+id6d6%>l#QeAh*YX$8ly2<$NG`AaA^uH|PoW zM5fkKtInYthlH(VTSQcYV;4p}oC-R3&XsnJj<|&5%Zqi4Zmwrr4ql%3m-EXF{N{A< zBGQfI^)S%+i5tn^3h)ThjhsD#aoB^&?IvpYV9=SISCXy-_u%Nte8pAlJ4fzl(yJ+t zqZtoAic+|S+#bb9vEP7n1bI9-o)Wo%?O4!qaTc6sR*~LFNt_R!PZ`_AFS?yFUBUiqIDb3a>5QzeL~343d97q*T^YKA?P^BWovV2#Wp)lD>#Hca z*HLbcvR}*5U6jm?;A$l0F1GWEyD5iTz~hmcyV)*a4E;XFxbHzr+y|<0?qQopyv={pW8huI##-3lpd;>?0=f8nipEq*uaZ1lsy053y9;XDa z0bfV@1oE^Ryo)k?g1x)I8#(tRl5`X3?8qn4Imd%WnmozbeZb=>*(cdxw()K2{ zlR+a1-o&;BG;-lhl=eN~$)rz_(<8yx^Zrk($zXrUMH-9tR z8w>fBgf$M%?j`%bE%rYwfAj*H+W)ZmwY`8B(*A4t=U}lNO`nt7q;`JK+zZ$<+kg87 zu2`bww}ra8mzIBCw)~F9+i%eRYyDf%N6_-`MH}@?8Cw4NSbM)oGe5UmBP-(jGz)3j zvFev&@oi~Ui_jcxu{y5eZErx_1B3qgAehjU#67Qwq5!L|^YU&<4XoeJlS^S5i!B&uy<>X`~cm(NLoH-mkoSZt- zz5#u`5C1ubQe6zXvcoy-Y56CTgLB!mb6V_G*@mxTZvp%JakPrP)!FJD2O5WW9-3VH z@4ECx5IVo!dGT8F{lNYBjq~W8F@JovTj!BpPAOag+BeeXFT-NlLo=G`AT0ShQfITT z2bXcARo9NMCsiAZ2h(>ll1oc|0I4(BJ>y#a*K+1+(1<-P`TpqGn74i?`!`a)eiz^r z(i%J+0|Jn1cz>0zMjAl$;X5VR&<#&$U9N(nEc z>{nuUmb3TrY;F81^Wp3t&e1C+N;^tW(zN_=J<9{JNFvS-%hQp1}`D?i?wUP zOGsbK-WqTXy5E?(3qjXGxRW#Ifp?JJ$r)qp&Z9=}q^>W-X4#*69owDYot(dm+C2eu zt%JKb=NbEXcXKRWh781^=A38zlEuTE zy#Y(E2K0*;T6<$TA7%4v7<18fkLCWzW0b#V?3HNM=YkVC_eM&;0`7&z!$y)mP8&HN zv>*03o7Vn(jrh?veLq9`8RN+ z%|8fB{uJ_Utgzpnwzu;pO5g#|9@(2Y>vyQ%LLT4D8NU)@-^A~NJOn;MuHVYuBg6|I zL+;;(d>sRxOZql)cP{vP(zo%yM?w2NZ|81Lfe(?so#!108lU`j_8ubE_&VjwfsncVKU(${GZZP|F?28U%x|z1)F*kqp8LaA$A_vIfB*G|wFb zYp{a1*naL{1y&=tgB9FmbM8QHq{<+;&e03Y9mpC4gRnVwU>~ZMLD&)8L9hnFAjld7 zgHYuQf;$KvVe8yMum-^(G{+st6f`mj%h{Jf2-YANgl*vt`@fK$c8nlY#||7d zh!KPsHHZ;}>ezv!1~GzAwf0SW0b&0gHHcoo&Kx_4QG*yks2w|qQG*ykh_Qpl@q*fM zgp=`pwET@D2+w8z9W{s%gw4keUTpT?@q+5uf#V3ZqXsdK5Tgb$g3vg2p#9hKM=xM= z`yXQmVfmvk@IsCqG-v-CM-8GEu(|!035pSf&BqR6)F4I>V(h?CgBU^BeC(hl_TN#1 z7(sZpu>&oCj38`n?4WA-pWoO)OYHx)jvZ9(|9xAr|1nZfJ9ZGG35~sg=d%AXY7ip` zkHAAc+t`641=X>G=oi=*Xx{$Es6mV%#MnXYs6mV)G#xw8=GTrO#JIrbBM4#hYex_q zQ>fbf7&VCTf*40|yr9|(a5SMhUJy1v#u1tuJ8;w>Mi5@||NpP}{}Cw=y?|Q(|HTtK z(A4t3@cw^u_P=TDK&}6;=O4X*s^xFF|G#znZ@fS)3$Wv22e#G!Z)*RW#tt~nu)X%b z(efKdupBmdXU7g~pZ#wxc3{Wa|JvAru=dX$LD0PY4;H{xqo1Gu-xxIzaRgQWza_B) z5hKvl|Bsl0t;Y^*&GJ7#|3AF_@cbicAbJ6fyg>8zztQqX1VPJU2Z9BN2!ieN|09B+ zHg+KFfAk29Ab2kSKWzS%5d<&U|NkrYzp3Sa@y8CvD8P>8|F<4H*mC>7_1M83W&d{` z|KF0>!CL;msr_$^8vNhs|L@q?!5wS=Up)T*3uFJA^8Y)^{)guuTtL&zcer4+2#f8 zSZ;r3&kG12zSgS`YabSVM~&@oo!d7$u=#lbwZ46$SHGj@1vJhGh&ci=BOpfjH=hv@ z4FC4c3#hg25i4jU)3ePB*t&1OV{N-L0%CSR%m~<)vHhmDy{T{iZ1V!P#_iXR?brJD zvi&>Xw{On2Z=Kt(_3fPz5Dfpb%?sF8Za@6_+7bSk7ZBt5O?~^8jO{zB?;L^UjO}mV zynvQ)`!TlPI3pm&`R`}Ud3(n8gTs&60ksys>AZm2vHcj;znz>qU!ZYp|9{rDhgEM0 zw;#4W82&~JzqxIH_ECLj3f%kuM)kMVw!btl;Qz+hesh+8$8!5k?SISX1;#AE+Fn3o zgx|Kr_BkUkW(OWcT;LwW|2sRdIxleRv3<2O0=I7eYq|XwKDN&pfiXKUW(3CU!0Nm} zX9ULVz?cyjvjew%USO?n-`u=FX9UJL|MrgUM=zjhY+vJyz~~D!KQGW3fiXL9d*=l@ zBQPTTYNPtLeO{oW`Y}6j^Lc?gHnuO=ek1&zjoWWYY@ag%Bf@XbMUSA?{x>%-uqmq_zP&Mj&(F7aMqtbitj-H;x&3dn z{4qOlOZ#txUsHy^mfNo#+i#p5xVdlt(!9V}5nyM=_Bq$2x+1_tqFbM9U4We(+gEG< zYsdL(?f+Ez>y7IIOl5yt*9EAx|6%!Kb%0nGz!d?SkL_!;_Dxp@h!p`^7TedH{SQ_@ zRtIS81#IsB*RBho=O3#B#99Egs{_O;0JTwl5$9iB5g=mwWC5Nlwy(K$0V1}qxv~A0 z+yCdYEH?CS!w)c=3s?SFG)`_E@xfLi;%t^WU(QT?%Mz~-@ijVl7g8UfE{ z|D9_ZKL6(H0=Oc;bH(;=pZyR2-?ae3^N$GsM*rWn09+x(bpc!*z^MM_*98clzjk$i z=mmu3kJvu@0?!rO*W9`QVfkxU2iTI~fAQJ>@cbjf-$?#y%wO%g0F9A+O(XnYvj1Dg z_CNo1f&O>#|2unZKP55PzcA|p?QH))EdQ1f{yQhO z&pFRA!*BC-fm&k!YyJP``2XhS_C;)ebN>Ge8QWLu|39C(eYN(#c3q$y<^RX5zQ$g_ zbJ_pk0vrX{UjDzib%AQ<_HAoye@oT{3Y*__b)eeV{-(3~YW@G_V*A7X*RBf`o`3WL z>=!&g``=t_f6K@AYv=a0d|jYm{u_P%YA--WU~~IlJGTE4|Nno3{}21$Gzws6kN-a( z`@em$ea-p*&8-XQih!Gs|2Li6*EF{O`N#If$baMNfZH;+Z|na5j#?LRTkZe0#`ZTI z{|^=*)&<oR%lZG>@&BFY|A+mL z@&8yIFxCa!zS#cS@&B#!|JyhIA9gMgAoY(|59xK=5zc1ulfH?Ise)bfgKh9_k7j` zuJ!zD#{zb2Y=0y3Uyc8(UE8PSvHdZhZ%Y=SI=Am6=J>}v|L4d5@7Vai+I4}qb#7lv z#{aj^{|}oVeSyX(z?~ES7b^nC>cG!G{;%n}!2jF*|L4R1Hy8gGY=6@kezkM^n#T5T z&GX-uxqUBu{9mp8Z!Z2X)&-7LeQH++j;Q{|SisH4|AYCjoz>qsE>QLMUyA>Gp}q^S zb^iawHvZq#^AAR#*8hLu$Ny`;3$UfluZ;rO7XH5_{(oaHVDs_+mdF1!=l@6Kf6LeQ z+4}f@bM}Ah{(p1vf6piWzd8H=e8&H4*Y;_&{MEVrJKO)?8TP-C1!zA0ulBnDwf=ug z#{XNw|Ff3^Pqw%Y&N@&EtX`2X7Yznx+KxBMbt ztoFP47XfQ${x`M%O}`81iU74=1dLd~YRrGk0%%;}Z+qAFZ!Z3?CG-En{#T;_o{a@~ zHvhji@-JoqG{*eL7Xde){})jJjWhpah5zao0h?Rfw>AoJ$HxCRjsI)zyMVR+f6V-A z^!(#Xfm`zbuIgWF{~N~ws%!gg>-@h-`D?!u`8r%Dz5&;TqseT3>DKS_PGG)9C+4pC z72qjslUb?V@AHn&-{&3A|2twQ{OzuUK%_Z|!m=DH=En+5t6;U)QAOY$$5 zQgf5}!i_T)mvYTi&^Z3R`R!u9FySxvVQ(Sp@Gs%F`%)sigU+tsm*Y9$?)+vy_OwgdUj+o2h~<6-RW%lF*&<1UAD zydQWN=@A@{2gf0!N3b`JwF8vEBeP^4$=)IC8>M#?+hNQ!Ka5`}c+HLcZ@Z?shEE11FH4 z$lfmCSY-J`_QtY?kl)2VDYwm&xYJSWAH`ix;_Pum930P`PG&oSd50%(7gwS`fpv$D z<@cv@d@SD)IF@9<5b^V_ew3HE`U+P}L@hIk)sVi1yov@N$pUl3$U&-0iS+n2_etlNH*V)`*Ip4@T zlhiLAp2-*UmUEAD@_oU_XOvYUW#^@4>~$<8Jpi$zJR-2&Q^dIadZX0TMPQjE6`VcK=sxY>|Fw0%H7s+ zpG(0@xyQPEuXX67d3-CtZ?doF+-0D5U(en};N|>h1NXTCyn;Jy;CjF3sOH;{wcQ5J z&gIKX>$$^5{^vLT2JpX4S=(*Ox@{BZH*zL%w28e0Zs6P$+I$__s1MWK?HB6%vrPl1@jo@;blyn4+`!({T(Z-VSM$}Gt)wJ6XDqqS z`kqR;bmpwJJ{6qG(|dEKPnN3I)I?{FdxE`?fX?i72YVn}o!M){Rjol~uT7ToHd)Tw z-?fj+pKNcq9fYT>e|w#J7vw& zDQme-S<7|Gy0jBlw&lN_X+7HJuIy`twbhf*j^^EOs}|@@OTZZCgg&+O{6=Vr7PtJh zI<3&(mcRC<4!ysS{RKIPT9-CRUmKpa7h5}UKB;!A9oUXM?8(*voJTsBy?Ss@(mCvP z1m}|Ok#nNe?1)wHt!Hzt6Sl$k*ZOwG_H-c^TIep=uCA1x-@5OLHS0#1&)}#VwcDLq zn9h;?g&x#P^ctqJ*Na-5MmmMP-dU!4Q5L$;jDzB5-?0HS(`~-2$hcS&aQ*%Ddjro|4JQQHT|IEz*&>qYTWFvuz|Czu3 zpe=qTa#DgN{~OD3-<;!q)RESE7Mp!8b&t8XPgTcRbKeJ9s^hpfM}3f`*6g=on++-l zy>hwq;=jF-tu~zLnM5<>ZBwmfugF zmG3_joJENaB%J};t5Y7;hW7K6(`i|9)q`q1C3-5GD@ycbZwh7I7wL!=(1+tmxn)e^ z%w#0V7UOrCl`C7)1h$Dtj4fLD?+pg5Q zEqg56F4VfZYYf|1>QzlJnr#deamsNRcf=y;VW>>cBdVhajJ=z*Za&MuzR%X2m`ov0phaq5v642+dU!w-@z#Y{4^*qNmYOka#CD|S9 z$@5x)ZAg2vSAbnPvaivVTC?T#qkac~w%0!VrvUYH^j>;_wz)o>9R`}CKI{zv2l1au zrH)**%D-*RU0QRG!C(h)5NUs&CHg<#tpmR?$Nkv!T{<9zbI8#Ua0o|zb4m2&ntnOY zb8>s_09t>x$k|9#18JXJT79^_Z!RBoZ5`)&v-yTLA{eq=@cYD(eT$M>?*ew^ujD-n zj?mbZu)W)Eb(QL{y_;KI?QPiJu(x4*!`_DNt=d~_Mtj?V`mqEWt!_QF753H^+Guq< zl6+M*k+ZWqd}IjgIeK9#K}Shc!6sLfid8}?SsqrLSDw(24+S|7?(O{FdCODSu6 zwO{=xcXe8$)$LDxguT`FHd@_*)R|USdn<C#KKax~-qAe&>5j=owMmzFiKW_==?2(0aR?m!M+b!D(nE_ji zJc*WD%@Uk|3_t^Aq$ZlcHa=Sp`GE#n>_pB7Co?h2k8OAX=jClCW?M3ZI=3FwVv{JZ z`B?+lle5Ptdn30a=b)}ozGQ6VZRB>U?8Q9(7wk>2Ip&4qaRy;Ux+>Y#unk{+)>WJWW`fw)rnb}B?tWIwvH<+B=b33!tZEbr~ zqSlOU&M|vy&z`QVhIMOCSB}COUdSdRVsF>JZEH%wc4sSVL(Z)|Tiblf!QQUD+IHm8 zy0W!t;jI~4nHJtUv8Str*H+l()Qy(4Jze<_%hxtHn><*i_H=hA|CXa|ZWg6s+1ci1 zQc_V~_Id5k_5dx%skvNib6R*y#5OmTnzKx7Wm0_ zW)Gk(TN`S}enWTeq)kvmb!Y1Zs++p=n*{bIt>@Yf)Kpv2j%-?Zt!HPpI#AE6Gh6sq z+H`wAdUX1M+Mmu`XFG3f?X^5)ZJV#Be>i7@i%dvEv~l&oV$KE&Ss*dd#?=Gr8tZHksANt7 z)dJDxgNJOOrKolE6r;6A%a?&{$WmHu?V*E)(2f>l8J8Gv#E8t+|WCrgOvH%$c-AO%FU{SLaV5Elz#Qg67n`29G>-r zUYL1SPw1VgXVnu*rnyv4D64AIg}l3YG6(Xo=0omwaDGemgi@?7oChky>PGqB{#j4> zc4|N0PZ?I{sV9_Z^_+S_iB`j@CzM+?p?OvBsVzfK1Rrk6$$(GKGO1szw$MYKN?ix* zZq2EY)$r;GrCBRrZL8UX*`J8?cgzx{z0g8TKuW{Xs4Y5VJz;xMdesxQGVPg`OKH~H zsVD5IYZvtdY>(PbJpt{fmQ`uDeQ9y^1Z;6ivz~x$R{N?aU{76}I+9$e|7^cKDNAct zy)=-wS3=c7YKXy{k^SgQov9ZaD8t^Ma?wCJ_XU-J2CkDMs*oz_4Y}ppBGuw4w~NH@ z)gTR|Y9u`j+n24e%xyJ++KSe>?YHLF?bx>^w&s`Jz%CrMX0HpVc4^J;yJx9W)|MiD z(bDt|hh?c#)@1*~q6hD<)G2YwqpircWPYO+HQH+1Pqm%cT4J0*>5KLd*0?%eVQGXN z4(n>Gi1Ck*y^uF$PkF44vnYwxu^1(>YNKrJN?lhl^nsFSe_j0%y2XA(RsSf7RUM@y zh6ale~E24XixcFN~3(kUjfswS7CKQmq?OSMA}| z_UdYTaxvbdhS%cxtQcd8o?N`i=DOYX5N{h=Jv4l+Zr@z1+mnl2SKpyl!z)pt=WE}p zT6(tC=wDXLHgvoF%h2%E^0&3exKfNUDP2QzomDlw+HUAG_14&vn~L0p^eL6mCy5cL z(CVS#m4%Ru>By#(_0aHJYIVmdZEyAg zx76*S)$M!O%B&lE(zdA3>e0&nCw048Jv98b>h=LyOAp93Y>%&R*6;TD)L^xGz6-fl zn<|4{vPI}ZiSEHK5O{|Y9Cr<3t<1O6}b$ZKbT+0Jjt!JB9%{R`y$lsTEHze{Quu{yEP-%99lj4 z6)n^4_N(+B?0wnO>O(EsHw&*p_D!!tFT_^YGs~oXy*`|^|5Wt|?0eWll%uP#4MxuF zW$D-G-Po%f#(yhFpS`T`aT0g!$$n4%XJ1Oc#r~E3Cs8S`}Wi_SH#p(&3v^3+wq(>Y_>0RXTQjnWe&}k zeJ|hNH}1tf>?f=H`xzt`f&wjO9Vo-knF1)uj(ve^G1+C4F9QOk46-Mr&{N*+K z=ko1~F0gKVTUp-@oNvo!YgYUC#*Q+^dzypRIj602PSpm3d24&BzPsGBo@^ak0h+In zgm`W|#d=Vh%u6r!WrKZA+macY z-+5@39CeuQWV!lw)^#_I%y}Xw)?fuxhLzO{*Xe01`4zT7;84z4A64mUS}#L#UBulQ zTSpH{-Knzf=0vIezB=FYq} zWT}XJb>!?o>P$;jmA%3F?FLhd%9&np@@&-u^BdRaHy@baSs62*)!ZqA zb!_I>8m!Gr)Qj)egL*R;ArI9zH>bXtwoa`O@82os)OOOFnz1dLqslYdpxRzK@g(0~ z{h*vwTTOqSQEfZwgI2j-qSa_ai<}qRj*@2i58}f_bjCj@o(&TT`u_&}qg_ zn3vjIG};ukShS$V+NsuyEl4Y4?I>}Pm#{L`x@camv?J=|#P1rOX*GJ~TFl6uZytHn zj%ZDM|7yOJ;n31*=g`uv^1C{wrnZS3_2;N>ZZlyeBS-ytUo~~pb`;h#@?uWA@lK8H zrK;J?ceIy~D|K^~;nez@FWXMythqB^iC=Wf8bFH>d8y_rEQAthsW_^ah~=_gjv?(s z^p-g?-mDMNUcEVY7)O1Hrm}WUVLPrkk1=0! zr;+Z*wf#Y*WhL$URAR8yS1Z_7!sGA9c_Z-l2KOgDh?u?o!2?N`Q##$j?p(bO*9`>s zCf%2GAW>JVh_pJ3{~N2-jnv4oRp2WAw=m0$QHleJ$x@S_&vq8kT3y*QvT{st3kWrSBSf@|1cOB~i}(hIn9HFyz`Tti@2WNwVd zRB|pL`l>T{320oGagvTG%mIz0nnk(?xCg(fkPe~kbmr<#Y!~A{&f@G9#rne8-s{=Z zr>qdIbumYman;2+hU;?VX*TDLbDE7^xr~S_?a^g;nnr=j8cqX^BbY=wl`orITU=9I z1zwGIFoMXqD7D2T(t4t{Hh@NN*?u<_S8{wUcrCw~2xPyOG*1Hh>%W{Y_kRGqdbo#@>y^b)<5EBfuCn7|p(s?5`?bN%|^!`=en! zZe#zI;LAz1s#k(H6xV}Sk~*HN@~>dI8G;1c^yw}%XVwlB-hdE zcIAI1&lwI5&wP?|%-V3pD{|Ys6&*7sx6a#1Tl2r$z&50|(c8e+GS|G0z1M=bb9Ga% zzsmZ`^~$DI8GtG?tluWHR^@nuH&#~qQDbrh5eFr=EXyai7tDZsbM*YDWqBG%?a3Vk zGp*b^hi6ZYWrwCBm2!t#)hS5(JdT4I4u)Haot&k8NM`LOBU5sa%H*Uh`Hnuy7&|VY zyg8<(q{&+;3&Cj0J1wNvl?~-*0`(&YCHuaJ`crb0it*HwvSgh)3NKG8n>CDjkXv&E zRaQ>!PlnhL4*4!wXBj$~I$2~#MC8ou|H(niKI<1cf+Evams#f+>9y{xM>%PkjM3yd z`fldZzMj5^B^SM5<1%`4AFmE;(<(owRepY}{C4`3_Ro7#kI_H3Cn*vKsa5TXI8qmmZ)NF#6j=INODN`=my_vVGgpT-3O}dd*VQ}f4^=94yotWcAkxMjlN^dX zv2S5Nx)u9vc+arfvM%zNfwNh;@=h@C~cHmT%IQ`}yCHl#Xq-_i#@$% zdzHRnH@3~WPZ^LdyiGyL${%>OvC76NhwK;Z`CgWM$fWJbnv5FtJ(UpO!FO#9+E4a< zHOCPhJ?xtA>R4KP%Fd^B%TH6A8ttHVu-#SpaV11KvDEcx zsxgMP(cql)JJln~jAN_Tg>1O#WM%h4Iz+doU2 zv4ysD*{K2KqyWv`05dZRm$ysZzJE>Mo z?HWvodcoR~o6^qpW>0Hqi?`0K8|6oK+uBgS_T#wP7jYEb8jv|2lUp(P^XI+tx$aqeH}7BjKGmme zdH%WX+1z`!|4XFd0G)l9xm^jp+JY7#Y2NS|e( zEm4|{RJNDf7F2&Y3fczLrWoO73|q;6T9TK|OWtx03;bfsi@H$%%wAD=Sb9^#v*v9a zMN(60A$y}UjG-{*$hbOnl(w@EUZ9%IsK!y0QWwrRH>@xIp|Or*vW6RjzNt`t&LdO1 z_QTH{%>Tw_&AAIWmaecLu_KL{LU8uQ^oQXcMahJQ|$!nMAu)iBtNQ{%_>;J?wQFrI5NY=g1GMox??_M~o&U3G?x@jT-}BTi=98N$>z|_}~02XY<+L3%+3{=c^XZh}o$e8yh%-)X4j($XdyHwcLEz z31iV(B3HHq+eFir;u%{>Xwi_fkn-nho8Ha$@VDA-dv$74TZN-?%DgcG(T}xH>$}@J z+JQc)GkcD(mRu9e{*1;z#f86ao)->Q1-&7dySgjwrWqH0hy`C zvN_&rjDdXs<5BfXI`TjLd1sm^#g5e2a;v_Vw$~n~RD0i*cOC%B8Q7agax31=a_RwkPfNj3X(KBvDd%SR4oa7dhfh?m_5ppaddPmE zPgl#tOcEn<_1|Nh&T%~bcSltQfR64d)g5vfD*uBxwx3~3arE2>H`|mfle|XfTqd^4 z3dfEjuvfXP+%N5)4oH`k`=`sx%gO`NfuskdE6U5u1JgmI2c~u9LFr)d3exrEy7J(( zf$b1*J?X~skaQ@xfpk-OXgUnsNP1;?SUMcsM0!5w!B(V7$I;-?>6oOfh{vR3lQJS6n~qCLjCfo+J}DjI@#%!5tcWM1 zWl6~pm!%Vvk|Ca$PD;wfNlDEvo|H~bN{M)KIwdIq;wkCWq&$eHrqh!0Bc7H{Pu9P9 zdO9QZEY3)0f;~uk6=$a9U{BKC#qzWQ>_ytASdmtOy-BVAm8l=wSzuq%{>548Y_K2c zfa2_Q4%nX*W&=oSRmG14#!LtI}$45UF*(8eE;uOSS;ys>|xIS%2a-8CZv@tnPNZgnU0e_jdVtFO}ZAGPAWTpEqHCZE;$cSye?gz90L%qPd6ml z{~MAs3B?=IjY*DJyfNLB3+p)(;eWxr27|lq&va=NFDRJGabnGI`9C}gNoOsyTAiU4=(OX zcY_C!9#Y($?g0-bbrk9z@Sb#Ua(xH!-gIAbal1Rh0tOz}{97(ANv*y7>z2zU(Xam6F)QSeyO%rqlPbglW-T)p?x~zCZ zdJH^)^u*$^^hR(Q=}E$H{k)BdKo}K_tCOx%yB0UM7LV8;9WO@^LD(UIP zo6=L@X{2WqPo+15r<0ypyg9uEJcD$3@s{*f@J!Mb#aq+cz~!VXi?^k>gDXhSVubDO z>1?)lfM=1O!|2#Mz;~o~rgIr36W^KMl^jVE-<6(Ds~JBNpHA;i=P|A&zB|1qozFO! z_@4CMb(FS#;;_`dZ1ROdm>)ZiydC zA5NDRA5I?uFCo3G_(=LFcq!@S#YfY}z{^OlC_a`x4qi^Wj&ZP$r}b=~0N0UjC_a%s z39cvISbQ>l3fw@tsrXd-G`NxU%Hq@MGvFrDtBTL0&w^KyUR``PeGa^e^qS&x>GR;# zq>hh$9{hazLb{G|uP-D=mc%clFD6Hy#4n~Vr5hQ862FwboE+5>zns33T-jgzO8RPY zeLwN5>1)YRGVyEa>*?i;fQesE-$;%-eIq&UBz_}(Gr2aD_|5dKub_}%oq7IzdsOs`}65qKx* zUB!>mkHOcG-d+4S{RF&=^q%4;>8Ie`r1us-O+N$gA-%8oS^7D6FX{coeZ|kgpQm4> z2l%SMZ^u{W3jNJXnaoOutGGvp%!sb z7UFNy@6sFi5~KLL^!w!3mc-wuKcqME?IrOK>5u90;*G^0(-Xzx8UL96l%6b}D8xUd zKc_bpPZr{z(_hk4tehnNCH*zMnbnfTzox&XxA1L5@o(wx>8-`z(?7tskiM<>NBSrD zR?@c@|4jb^-$we5;_b!1(mUDy4Zef)UB$oCf53N=K3)7L{TF-}>AQ>n(%E`<@iggs z=m4kkJ;l38-&>@z1m8pYzT&+_36^E6^8Lm83b9pLSAL*)e^FO{kgYZN0n!f@t;;sx z2T4C%v?<$yA0quo(Y9;{ewg&5MZ2;+_z}{N746Fo;73V6UUVqy!HjHk7^s_~mvMcx*($5uL%WmLjNk3n7E4zcA zBmF|rz3c&gp7e`FkFqED1=24SJw^+N1d_AkF#e4`NimjlXg72hnx0p-B*+r_sEabP*9{7&)h zLL5{MF27rRrw|91L(1yMVtU{Y|k;xhwc<(%%-lmb-z!A^lykTR9H=E$Q!zapidM zccgzP#+MVo-;@5am{3jx|3Lbu;*Z6|^3QCOz(0}xrTB9(37k|;F8^Bmr4T2VQ_8;; ze=Wo*<<#=;#or2XYB{a^NAdSUoK{XR|5^N_5T}v+A?{wzF6l-madx>!Ns`1p$~k4LR3>pwIk&7!t&%vm+_P+* z>XNu;Ij?M!S|@Q{xmVdXwMl!G?bzmnZAsgw`Q-wz9chQOpj-&HC#_El%SB)Z(vE3S zxfrY`?UWXmOTdn#ozs$XDcFg$OX{4Kf=kQ2%dV+Q+PmzQx@O$F+^6iGx+QU+a^JE? z>Yl`X%l*opsYep`EB7yZrJhOLzdWGqoq8qlfbzhyPwJh-1IvTTzNt?V4=N8X`=!3= z;Ie<}m+|28ka9rkpTtATL(73_KoSov4=V?yfk`~9JiHv71|{+E@`!Rs8l1!<$|K84 z8j{2#%cIJMR7v7d<F9JqxeOddIwmbEPXtGkj!k3IiQtLlN#!o-r1E5NEa|T49n+>TnSDkot{>fXMxj5XQZ>rv%%@4Gt=4SIp7S^S!rfEr`(~wCq3f!G^k2E{2D(9p7MDl@_cYE>AZA)c>%a5>0arAat%0- zbbeY>t_AlZU6AIdwdF##3&91Xi_*e$A$VbVQMouRO5#Q3#pRN;I9*&`LV9tzG%ZP& zlzXS8;H9LOl>4N;)1~FUX&>zg(PMK2M~_aw ztrtF;o}PYNPkc1}K>fBJ_-Oiv`fc6u(exYj+q&VS=}+pnb;VPQQ39hz^v*kh#x}`> z1%J_rXX~l@CLQtM^k97-`3}9@VH~#yjWU-bab*t~lM(E-0f&?7)w!~gp7SU++5M5E zMrk--a1^OA9Y*SmCLPP3@jXW7?808G?_jJ?QCw8&;fa>(ZiS_)pLcONuCP4y^DZgJ z7ni~#=;vKpPAHUx3B_f|h~D01<-|gX(Azt=oKz?UdV8zN$%V3@x3{{SQYZ`heCL%@ z3uR$yp%m!(onKBXlmdOeHRbfe`q$@MTh1shq|NE`U0CY#9Shp>W)`-&S%qy*|L^#6 z_rf-(|93(;yRgma|1B%^|4syLb9)rFxjBWcO<(Zja&BQe(-%CY+_SKq=?k7(&MRzZ z`husGdlj}beZkYq`GxIleqjrnk4Jb$sV}%3w1q7!Y+L$*E6PQMZA*`EWx2SpZRru7 zRW2#cMw96go?Yq-9t^6S_H&@gS_C{-UT=JSy8my~gR~(b*pAHO?rH$@WmMab|fe+pJQrQPdJ1haH?< z>N|?sKz&D18>sInY6DNicNDdOdXS`6t#Y*7TP_%$pz(Ug?3MG za$$LTq21G)TvVP>EG~BePbWPy_cG4R{R@4{UCQOTf1yvgTe%|lFZ3zLl`C`qLZ5Pc zsZTipw3l&K?pf$rPAbpNeG2`{$>lk@PoaM~r98K2D2IYm%7#)eb0}y}N-tBiKc$x` z+Mm+P6zxx4kb6=WP5Mis`uHs zyg2t#^*+0nm*ifm-e{VWo`=@%Jy~}mE zf2t4Kr(93Jv>&*Rly&pU{@{Ajjk!;{G51C{;)(Vz^+5-M_DS_YMf;@sprUbKn2k-0RmXtt+p~y?(vYHs$rX*ROBdw!9(t`t?oQl{e;I|Bbo7uZP;c zyeaqh^-$}}n{$6(54B@?OZIQ{P&={Tsr(1Nsa}qL>Ob*K^>6f3|AmLDf1{uJZ#-1} z8@<*4;Gyc@+=fS!z*{+bWs&e~^jTB+s_fI~vzFzn@o9dFxB4nlz15%Mt?Es_Ci{{4 ztUt$R)q~V$74;qUSw($EeO6K5@y_fu>bd>~|5dM1&sEfG)N>W}8t=h#74;hRTt&Uc z`|w;v{l)vTr>GbEXS`TFMZH*2Pf=f1)Kk=#74;M!#zXuz_z(_oCUshlIvFwHG-TnZNRxe!d_DA@&df|GvKhECmPe56R zC-B6-hIT^Sv{-VfpR%Imy4GdlXdAIA5U z(b4z)XnJpEbo6~cmfn}S96jKVr}t+r=lyuVpGY6bT#g>_C({Qrm-E5Q;(QQ4_*3aa znZ?l${!IFCW^wd`Kb!P`KL^U?=mCqeIC{Y17hulxfJK?Jk7v$IKlttG6PYd34}M4b zWai2AgWs7xm3cC~;diA^XP)fSnIY3Bes}szX2|r3-;+L@8M4o1M(}emWN%3N$L~#_ z&%B`i@nh)=nGw`Keq;J#W(4(*A5UM(jG+GU6Y0yD5&UxI0`-!gOkc@dpkDG*>8qIw z)JuMI`WhVIYrwCPemygNkt`z_WfYGpu^g_onY>hV}b+&-bMtWQJAm`Tq37%&`72bE`kZ zlYSumD08cN(hsE{XKqy=`r-7G%&qD}Kazf$xmA7WN7K*XRBr}sw!){+QW%ed}wIzV)@BY`wm<-;n;2 z8G8Nf8`EDiL$9BGQ~Dd*>ZG47ItKFhJo=%xeSZ1}+XYE)TXZBuZ(DREL~mPkB;?HDW2*Cwwd5~jwZ4<3!FeYiM`#yiKLU+n+;APoxeJ7~*PagQ)9;yf$J=y0J4cU=c5wYIN0^-f@~(+%)w`K#hqAcQSy@xII^`bM>0VumHxm3}hQnIETS?Yg}J-5a*3;F+Qe&bHhQSYX)=1 zSVGs+t8i`vXuOSadqxUY^1ksmm5O8VH{Ymx7n!`&-tRftTa^TQ`@3 zR}e#B48s-RI-&=R*jxv$Cx$@zSPyO>hM)tU^9Hbnq4b;! zu7ashdRBp};V6u4S`D5DM`6U$dEohQ6vii=4_*LAVKmYO;2JmzW0KZ@Yhfyk%v}p! z2vcEAUI-owQ(^5L3mykkVT~OJ9uG%h-5n2}08?Sjo&YX`udw!)fhU&BV4{YR4uzLE zu^fgxoCKa+o>VFsCxfSyCzndYDd4HF7Rte?;K8sKO3cCFA@B)G)gj=aFbT@vq2OWg z3CieU;NkEIO7r315%3Ah^bz2Z@Ci!)k>FAA3AUP}z@uRmY)eOHJO*B2E_{M5ZZ5bd zN4Cd3!Fl-Iw$pjwUijU%<-Nf9_}#Yg`QQS)Z#BRIa3S8eT4Eu%2p?QcvIty^53aUZ z3@*V3S0gO}m%>`8ua<&)!)6$}wKupAJcjXI`+)nxV;BRrFSs8(hHEAA9Vs^O??9CqF95{`A z;ce!CyTEDe2XC_rxGS84-)7hq+^yWTJOHj{H*j3JTX`T{%{Xv;ISvko?=OH8%JFbG zhmal&!!V)riwhIMNpKE+cVQAZxtvt`^@YjclyY);I3D;E@Ceew@xc3*N5I(h1N-Bl z9|>2}9~^*(eiU5I0B~SApgbC`W*|7I99a6Tg+bt8JoIB>X$FHs@X(Kgr5OTN@X(Kk zrKx}oWd+`58R-ed(6XUi21_#(90u2MA}q}?a5yZ-N$@kn!4a?=C&SE)07t@doB}g5 z5*$^IEKh}*83m3mN0q0+%!~%dl%q?(+A{_mTaGEufRh;ub}q-3ekrLl*agPJ@7;6( zyOv$b6)-bh!ER+&7#n89g5Aq*rQbs64)!R!muJJt^ZWzJ!475n@*=pG4q$!Rp}ZLGr5@~9*2BzP3ir?vR;DBSzfYam zyNvWw{Pf?a%iv!A0R9pG{c^aMKZ1Y4f4>6m)>1d3l`;ni4I^sDx6Fz3)q+&NpFDlNU$+Ck=_XFQNqLA zOnMW%M=N-kTS#w){rG9R1&-xs;LqVhUIxeVbMP08uD=|Pm95sJw&p?eHTXgi(1X={sOXJ_MKYF4A|xmV6j4=b%0rXKgllOx65driu z*pmCe`-!*uIBd!N-~+^4eFC=R0q{ZMtv(4`@*wyS@m8OLCwT~bn0TvC!;?G=K0>_J zXW&L20Ussa>a%bokAkl!-s*F3Bd-VFK)luG;YQw&`I9%moP6;a{^T*3lP^8PpS%&~ z)=U#K>B^Sl)KVLx6CUYcGFH}YH3-w+XbDcs2KNPkO2%k3h1%HC~*Z^*XCHOPE$3}1yEWuykJvM%y-s4K}Dp;4l!FXH+UY)Lj1NjH(-{DrSh6DL0=|5msu7Lyj7wJD?SFVKv`8Vmm z;8?DM{rC^*zu{P}hyD03>3`r@Zh-YD(v9FvU;)>06Sx{oa2>0`^S~08<2>+uuoW!F z`QQa$9sI@x;2N+s{Kgt^E!YNrV=Z_g*cN8vLhvH69sI^c;Kg8j_>GIfOTZ5B8<%7} zgY-<8kb1Blreis&*b$Cn1!*VvjTPX^|Bt=54%nl(*T3(TxVyW%yF0<-9^xb+LI@NK z5C{qG2@u@fy|@=`(Ne6qyB6>J`RuSK&(kJA`<~O^X%BzQHM6sO@7}wk*IYB-0V^`T zu>@QSRst(Ax={tcGNU3(301|f!pO)nLe=oAGAgp1&L92WNow8NrwV z&IB7Uf-w`^32ev+#!lcYun{8|v%uM4i`kY?Tl_YR#cW5Y z9e!KJVzwvL9={!pr#P7g}%oswQ@H;XhGnPj3d;AQIYZB zc)}|BT^O|(4yx#PWz=E>sIK3QQHznFx_)=YE=Gas`aKxC*a}qF@5$K3Xi#;(7b6*4 zgG0gIjE@Wjhk%Zl3;_p&j+i*^(GS;`aS%sM924o6jg$0`8aM6~6=1}1p;HtU9CMKe zcLp7Ekq37H9dnTfcLlpeuI+T>#TBXDB6juTKdaz(2YW>7_m01~X2KDeG90;Dp(i0n zVN~#YfsVqc;P(cdS>c+}K49O-`3KIja9vK{s7AqA7S#*Ruc!{Y?GFx!oQ2?A3)eOb zh^iKxalyz7@8&#&L0~1Ya>2P4&OjIp4&fVAEDYtVxH@MjI4qL$4&$4-=5bh5yI}g% zDVQ>{-VtCuux`Qhk?)So&=fLdWW8H~4Z#Kl(?`BL8Z>?6yIX_KzGz%%g5S7cj%!kA zir=JQj+5_h2b$yLyW4~2IQi}lpgB&yyCZ0hlkbiJ&2bsu1UXqT*CCIdb# zT9Wn4WWc9KOS68N4ET&_S=KL;0iPKy&-!ID;IpD#vwoQj`0Qv!)-RI*pA+pyU-z6y z27E4PpH~Ka9%!Fe27EqfpH~Ka0cf9B27DoCpH~Ka5on)x@2s~g559!3yRy7LH{P z^59!R*@HazHc<8;5566gL&$^g0Pl?Mh~&X{g0dxf@Lk~DuqAo$-Jonq9()fdTapLg z3(A({!S{i(C3*1uplnGV{5w##BoBT7lr71F9|RwQEy;r)0%f8bGY%>neuS_bR5tu5 zC3-%7gy|%0cD9&w_GLdGK?f98?}G|GbzZXC1tdv0-N)$mwOne+K3Bvf(iM z;H8WWhuH@&XKXmkK6oW#!_GU9)60fm1LgFx;nzVqy=?dmP)08seiM8vdNX6gZ-I_s z$cEnr9m9|fzXLjkAsc=dbPPi_{2u5ShHUtK&@qhPW}_E!;tvTsdLbwN2z2y9PW&H5yzsm@1 z(^zKQ40NPcX51Wfq*i9!0(7KSX512Vq*i9!3Us7aX51Qdq*i9!26UuWX51ER$4ITr zxE<*Dx6HUb==itHxC7|;x6HUB==itHxD)93x6HUR==k^7*~qv2xGP~tzU9Z=Ku5mi z$KAmmjDO3Idw`Dg%a414j`Yiqdx4Jh%a415j`SDc!+k(U`sK%cK}Y)K$NfM@`sK&{ zK}Y)K#{)n|`sK$1!9k4l%Z~?vswnc~!Qha1a4bI_0uGIb#Lm%orhZv`=jJ<8zZ|}E z^PQ<*9^bk7&eX4f@7#Q6>Q}^fZoV`1E8#ms-`Z-U=hu!@rR2xsKvgOE@pw>G zN`5>6RF#q+PXtw^^OneKoq1@4G%e^$M8dvH7aGT`?3+Y%}ZZil}Op>p81_*)Yy4{n2B0lz%G z>#Ye@#IHcFdo-a@xJsZ3sXg(E^wL#G?V-DCrwXY(_bT-2RY>j8SEaYFLTXRH8Z1DC zR0dETb}*E1SD0CI_)gah|l59yX))ACN$;CQ=vMX6wdr;N|ALG6? zK^e#dTn(@$M-#zXploy^3}z50W0{Dn3DzbKZ3>P$30D`C^Gw1SKaevhRm4pO>wz-W z$uOsWpiF5pt}a-gIJ7HR>l9o=P{uU{XMA7IOeMAvD0iI-W9tRV(57;}A=n##8h&H2 zC;l|JY!lRI#;Bi zd0uO|?#b@gaX(1mzySuWYPQ=a0 z%FP_ED+wQ(h3_uxbKparxMCi8uoF0&GxKnB;YOA$E$fzo8_glKfLM29pNGFQ*UtmH z;Jcst0(g?;Z(&yQ7IJlI!VB;hW#<-i)dJX37yQMfTNlu^3+}DH2_benT#1O$DLd zK<(}BnbjG4a$QB3*6tkdMeOe2Z}9gfr}qMTainG5z2IAWQorm=Xiso&eD_e_2fo#t zqgA+l;ak=~+Sjdw;Z{>i zuHiTc7xq%$pRg8u*JL%>8m_1U4-5OGABew}bF#6%T(_1I-xoZHxOG`=w=S#a)^Wue zV%89M2;p@wGv|^Yij$@Fqz+xKca6 zM-h7*wctQ-F#hpeQLAtQvB!YNaJ-%~$AW|L*AqISupz5Kwe(x7a3aUYgU&HOkM)|0uSb|F{_-bnc5!YQ0T5gdwt3ZadKQ?uIl)U1|0l`HBL zP9yeY@MO-NPU|rg9Lm+F<2HgDId=x<>J`oeWqZy>Ka(@3!S;spi?e8phJ(Y1I}3Lv z%+LD!Y_6^c^K(x6Ik>Z7erFOom+Q|0ou7UlvGqY~^z*VB{d{8Ng6H6$&sFEZ1xMgt zK&^F;x!tz4rs$a(Wi@=LG zzKkm`2A%75Iaf3SZ9T3atYYen^(#4lDYzB>m4sAJM{{%~E%|8pqI1=+%G!{t2sMT^ zUcvD-oWBCx8vhzXSHl{ev3_mV&Rk2VN#VLI_Ij?l2JYw__Um!-$Zd$bA!~DP$XfCn zXvbR+b1iYsRBr*=lHbVH*Mip)=dAUXpe_4NS(|wPq1*mFN0+C5v_7;}tw4Qg|H#_2BDJ7( zlyzt&YBzgH){K>@o9rc7>$$6_y(H_bs?;U+lB|!aQ8(C2vVLJaJ}b-C7d0r^_Ft?K zYEoY9#aP;FQEKh8ScYp;=IpsxlIu|B?59``>rz_G?UuuOlmTKWIKSD7kp0Awd^P(cQ)$<6SSf_RH{Y=`XzQ{! zJ(wz>JzeInkcRv4`?BC(`1^3&545MY4{iWBfHV8jgQ*6(%5q;qRlzFUVPD)1p#AB6 zabrMxORKnlXo>bBychpx6>bn{Uvd?02x#wi6>b=4?|Bt&YtSC{D%`f9z3^3BF#;UH zRr`_uN`bD&+>ifR2DHz(AFdxQQ#GExKY5}WSOcGxPWby1JB}8t1iAeHa&`$&#peKi zR|>T6Y0J1DEtt08SL3>Y_L*1X+JW|)SK~T>_N`ZQMR(9X=4xC|&|d0lTyM};_Q0%{ zc3{@yvOOI~Og0jp^$`!GpEr>h$Gs24O$HsQJ`lGPXrJsr+-%Sh>4SI|+uvIF2a%6! zfpze0Up;HPd=R0zw5*U}Fu`BLJ15|3{?8g>TZ0D>w}wy~unlJprl(a8bWHnTNTZw*+*gdM$Z#CFltATHGF>qsnV>dxG|#)^go) z+VY5+Y90R}0t=Lhby=;rE~^RGW%b^=tlnFfm6t>KKl5qt?MEJh+Zl9??;(`N`t$|% z~?&;*5I}rZAWNZ%7gW-%pnHb;BTMRxH}M=QckRK znL&szmq@_2_&ah=hT5KE*Mz2&B5PxLg&ej${upvyd-AdTbu9U>1K5FBIYvoxm38$v zj!J|{-WPGDEXfJ&{PM%`zJpoq^wEmWdlmR>APb9{?Xew-n0yD9j4=|g1v~FPWkGUF_x+ztB*ljiJ4qc4YZ|@!&C)rF=paqJu`{l zi5N?mt;Z~mYk;z0Sxt42^~#{_$!yT_H;c2gsR>!HOg+Y0W&E1pK>Rs`YJs*jbFvmj zo>QCBG6;Vjp*oW$kWhWfr)}0EVl1z=SF)o9l-NbYFUBz2-lx^F!CB#_PZQqu1+!S1bzmynDzir(z{HCDo-7;Kr(B96ntXwbS z8rv=VTFWToTa)9oBbe`FYbzE}#ww7b%aW7bFGfp*xt&?k>y(50-Ebn#Ba+kG6y{wLCK#4bBSuZr8oOdPM zEz3*YvixH$&^RmYqIt$LFPd8{)ne!i^&)qKzR>XOO84h*myWP^tJnL*nvl!Qt3z?a zvhUWE@9%$b&yS&eFZbhcB}X&T!}8)j!tNU4?!sZeVr%~b>FCbZEwa3!t%d^Wn(skU zk8f%|(RxEfPNT2f5qDH| z?M^j(SN6DLiaV{k2T2F81J}7fN;l9N*j&|v{Adb?-HF{LrE8Y+?62p0oOH_arF(35 z&T_7MrnoaoXV8?_^0jQkujO9EejC4Euy5ghCE6^uW%LUrylZ%Sze#v^ch`2`lXe`t z>$Y#|uE^ni!`p=&ReTrAdic-oNE~)!aW582Sol}&+7kX-_^<93?t6tj!^0PF2j}n| z{0e>xznI_4ujZHZJNh-lcQ$R@r(B!!)*q&mwoOeJ%W5c zGAmn_gRr70taWOZ)gSH_-|WXs zUtwRHkYkFLFTc=$zbR#Y%bzY^eY3B=sg#8><(}4-GHXE7$5i{d^3{%9m#27Mvf7j5 zEOkZ8S13)PWSM`u|CoP5i7Q&B%vs%wl_v9@xzBu2H{`Ym&LOP4i#8J=(H@}K?dxV*KU=_I2!&HhzfK4Rwe3Z)SlyCV#Wu%Xv220WylhkC z^m6vF(c&9kT9i=tKL|S? zlq9`s^MBm=z`f($qtKlX+_})558T7BOqOcye_#*MenmOZ9-?(#c~Jgk&p}Iy@-OSQ zidh{NtSY+4xP4r|apkN>;O|^~ewU@GV+`Er{()tk2snU^CQ?j&k$E)WvBsBM{}9L$F6{hjKiAPF)5*44_H9~P-`IwSzO=n( zQ#SMhEHCPcp{HQlh1$-ZhJAU_a%WFO4D2A(sg_gqOlw?q%+ME7pVJ0q1+r7yKI>3hN%?B%{Rdv4t{a$uUsKI7 zZ~(bus5kA^n+n#Ps&m$f){LgHnqBDG%S}UVXwSj%AL~c^5RQr2ceghYdhT*tbD_1P z;{l#S2%m0EE(f2#uCI=ipdR@K78^X$twBhLS!_8r)R z|I+^|Uk?A?{a}2Xu*a|5IB4IUs1;OBWzC)WI(`!sa9NRG%N~6Af_}}ww^YIH!G|yI z*EbCuy$ih#cO){6RKP>Zg;eZKy2=Vwz^w^QYZY+oL+gB5v-P3mA zNCn*b(A;IO!}`!%rvh$GXl_&iw>~t#s(=UHXl}M&FH<&`Tj#5G2fnO+-8d^1mI&*5 zON(Vj)!R~J39>|u&gvy?_}DUr)RV=9c2G7K(%JMj7nuImK_Oq5N91tk7t_q~!_YGg z%rUgCrl090hF)=KnN2^_&Q{&@3OP9Rv`sHl&EB|tR}8(0kZPevA5tx_YEvy|-j*mw z5%ZE}nUiN&pM_Ew*ncRWrkx`JrkADJax5ncgS)+wi3pJgsO64W+OPlHCJQVx= zmPNU?b5ksxp~T7++|kOMz$#N>LkVZqDaV$1OTKl0dCMBXy21L;Su*CkP=l1tYLQU0 zl*;Nx>qF<=MKWR^SZk%ajzL4`5TSo&2O!#J=x%Cs@Bg>hh0Ec7?Re(vT| zM+?+V@*UyLz204=RUc$`-2^=@HZnOJ5k- zw@&RrdW2C`ORMQ&X_og{rn`|Urkm+u`(^*tnxG4*V!8#T!Tv=j(!(CGwMa+OBlJ|P zRf1w+Tj4Bfl^)wIYbEOZPe60{-fE7Qh$&3eqVF{P~Eave$)B`L^Z<*G_lDkD81*eWDrE@>X&U;Gp-obe2>rOqKc@YrQC~-Tt%XB> zG>k<3G+(wB(;j{pmC8qb|MBtO&IL=QYvV$re&zj9Iz&neVSK(`mczsNd@o8_ zs1dCvgB}|+MiuFx`8A+s3JQ`nm^yZ-Syj>va8{4#j3wvrh|Z~-jhhV4!gt2bWYD=sbGd(Ka84F> z?$KP_H0Ipcn$E*b&t~9=&MR7gn+eXxcLvT((D_5ov=N;lw2;uOY>v%r=FT`P$eA{? znJ=@L@Gd;B3pf{l7mnvLUq)`S1UHWvF-tOZ_K)*tMCZ9J=l%;pXS=!TU;*Zy(}TFxztppjOsgKd_qFeTQbantLCHJ1AQ-a1g5m z)^LB<3>da%J%Z30Rt3m5jwFYd0!#9oqi}1pH3J8;O5iBMN8{G99>7)STBKjcN&we0 zxK7{@Rt7ky&~*ZbvIfBQ=Gvk^j5PtSVK@QTBU>kMIA{yGo@X7&?0;9CYm5F!=KZ_U z{6vnA1~=flD&QDq{JZL0TlB{;%ipyMt^_!idH=3DKLvL}wg%uh=KG&Q_*7g^&>rt; zl;YB0X`XO8ZbP;nU_G<^U4gDe`VGwPcYT7h|4%G9*Z(BYb?9f~HiBp2pF`-BY_9)C zX7;=G{9Nwd8?@a!m*ZaGIh;9W11IzLpEz*mwNw@-c0eCt7m4q(L z=J#K~JbqWEUxm9Eypkhl`Cklbq0Kq{moPiuwFlSY`heGDF}C^F@vO_3o3EWVXX;gB=mJmEIn_28}ew-dSnbbY#Z>91!6xhn*;OMfFP$nPM07Y^I^9AU+c5Vr3*!ipOq zY~OSD{@^Y6_izS_ZnQNOzzRI!J{)%NIl`hFq1!?1tFeyUwdz`@$D$jdJ3*|hv5wre z>RPAA{yjd{@Nw9|#~1BgKFo9agRWkGgchzMSdk}aonCbHx_0SBSFdZAUUc>PW4H%E zSFCH79?SUn53-uv73*50e~{JWPY`|*_b~V{Pka(Lkd@`GSbr+(Ej`6^A7Op@Q^fp{ z`~LxaIt#m!UAy#uU}d?h*R@Ok2UeE5dR>e3kFloQ)$3ZMf1EYt&k=qe_ayivPkA0U z2$ZwGz_XqL?V-Iu=xNrPzX1Lj_ebzW{Fewl1O6HRWkP=fU&4Qd(6gXx*k2*;Ppmb6 zh45>*=fUT>|7*lO$69lHjIZNf0A0_nb@~@sYwmh>t<%5AT65R4zlD1le3PTM3B3Zo zh5rtrSHZXOwNC#ktIXfcQ1!2&#wNd{D>&{)_u8sOP zSa<#*;g4`{fv#}ZM*Z8YJ9mY<*6H77-MMSqwNC#I>&{)L`1#8g1&(L-5KM?womFPbZE<~<&*GBzc3Q^>0_Xs;}UlroW zb?!0i(!VYwk?Y)(=v(fbL^8I7HR|6K(n!9LMslk(s=;$gutr^U{d>vCmG324ss4ST zROHI{Qmj<}p-`G<6%k5n_e-)lH9v8M`9_SP#IT-73!72s`z3V?ph634y>Am z<)+m*9#N zjqz)NwRl1ke6co9Xo9O7HN~$RHN({d>qYc@i8Ce}6XPlMqvnwet_AmRz)F z1Y6*@BGd?MiQk$~W3Ux|8$wOM*7$7+H3i$?w~HKMYsYaj!p%5p$C;+Ae6L$*4muXr zfv2>{R>L=E{d)`U-I1dfSV-$gxD&1w7ScLp*or4~;Ye)F6T0GyZMbVUe9=`l-6B`n zbmN($!M6C_c~*N+rr86(Jr>j2^PHaeVn?3PlTb&jrS&A-8`l}^g|Cf#?c;ah34Ms` zjGZ*CJ(z4xX{B3vw>p(ajM%dL!+Eg2g{WSUYwmfS% z_S1&*gzbnMj{UR|+*_M!Be0(~k|$|XZ6x;7MsaU#s*S>a+Kz3g|8mb8*waY0(aaxx^Xcx|exTQ@H9p?mr`%$8)Dg z^YLe3Z*2zmUck|eXlFt@feY{#5}F0h;@%61+X<^{v$@|Qj%H(ZZ4qIuuZeSb#xA%W z3%lUP6qZDeb}xw>*Ip8-moACqtxNb1^RUL&lF(9~J|A3yzbul&F5`Fs;idS?2<;5E zEG)%Jo7{Fe*DNEvjQCw6x$Ulz3bj_;jMA%h&3N=Y;-A&7ypHPeOq~|1EcRyixAF zJDB3jn)d($k6yviD$dB1_u&5fab^$Dc6@)%><;eEbAB0XmUkb7+Xv$QaB&iiq+jw|*D19z592ktCuJ^CyfHv;vdDaeA%`CM{|`7I%my?z+8*6X4m`&)*Kl0@o?2raN1Hl;RMbc z0c$;+d#oq!aMs9}RQe5_gstpMpCc?z)lZ zoQezFc>{b^R(%>y*1UoHpU!!?v#t3V#LAsd!~bR6Sw?&g?i84-Yx~cI)oz5T2EKd> zcRHW@ZVkG&|9sqNP*!~b=VZ@4} z;bh8}5_36E-3B}#{|aJd&GP6g{);tV2#XD@Iq+qXcdYnDg<9=Cb!99XjqTDJT!D4%{JJR5R?nF7CmDB^M}Noh=b#Mwdt$%H*m7r3ZvA~W`uzh}d%vZ^3VQo}9T$p(M=qheFPs zWz9K*E(LoolQC%7aza=>T^3#(!(9`2a5>@Ls@%UUCkgLVs0LS+gTKn8 zYvL-xU;}rSHRlYv7U95}<;>Lx%cEh?Jg;uXTV>ESV77Je>+`JYpln*!+`Z6%Gcst$ zy&FW1Ld%(J!DR!RuFjGCxi;7kUp8HoLDz%P%BkVZ1=+OhRUX{{X4?cG?#!K3`!*5Bf3|j8olJoW9vMmYAoCAYy41;aVJ><;Iz`&!~#|!4#hM4x;Q@$*BhOHKQ z6=cXg!Djd!GH%_G^D=1paz{dP=Z=K8%$?=JT{D*2m3NUlx8q*jGEUu%=gOMp)ZKCN z`C;(a;oMucJPMRe%biETTxHF2=Fy-$S_VBD z&MGfvPePtFj=0g_XzrA8XSl0udOS|1JdS5fh#c{r5IGhtkM4(M@@;v-#EebLon_Fn z>A;->kIuQXJbG%zj;Ch4bt+GnM~~s&)8M&d;IU)5ldO3nD5svmIT^G(dq(6~v@Ci6 z7R#q|O>rJAcP`GRXJrh!DfZCk!f&U5Q@E2nTE0A$d(4C9PKBG!hz1tsb4KnwJ>$-@ z>dkTIz?x@qKe_WPJLE)4jOc>KFgqk1}%gBTlLu)N4W+)m*?i{v-bCv&_;HK(aM^a z;x?~7t2^gBI;hWb=%7Id-8pE`D|u3q@#GkkJLl@N^XGTRsXlA{p|}RUN5-9H&4EV; z-8pE`#ntDaI|mIqux963ZPK9GC6Ru>?w~WhSJ8HMgVV~L_rv{C^;z9HXwb#gXXkp! znYEk~l<1&7cjpO3)n|FM40hZrUB#dV zeH6U5sQUc(JX-ZRSE5y)RiclB*KW*sv@=9hpG$$N((2Lj=w94gJ9N1Q{g129^5vjG zpUX4KWZbwk7?kM1qgA`lqiya5x;irG&Ow9L>f9y`I#-`%(3^O)+Vk1)*Ned7>a+7@ zHfhjh2nP+i4^JwtJIkbl`m9B{3t+RV&zob=D$Y5N4!ZNDJmp$kIWTC@a%Xw;<)Evm zufwT9Uzc&`&8yGq%|Um*3Qn6d=%7B!po98+El;@xR~`%+v<&)Io+6uet@f?7o&8|6 zvgV*f=NfcSpH-rB9xa0oY`QpumQ@EO`W~KC0oHm8ey&Fc9^IcOY)*Yvcg{8F`w7dL z?*fZz&??Sq(5lZ563*3UXN1a`D}X_LcIMY3xSvv=)t!R|ovY798Fb*zGU=c}=eo0V zx8%tcLHTs9K0BxEDcmOYS;aZ1&w({R!*R}|1A|s|R()1?R)c;V2Ky{w73WHz^T%=x zTJHP;Jq&ecXXU;~DCo{l!D5T*&T7rY8T3oUyaJmQRi9tQ$(QBGuknm3;Pd#o1|8Jr zK|JYoTGm0}Ppi*?JIj~VonL~fzRbPl&bbDitIy8Ux(BFqZ+i_IVjQU&edS9L5X(OU(lmJ=P7|r2L}BiO!sr1s`~t4#+^mk zbgn+lAE>YzdYv+A=prsUCe!Js>j=1JWn zZGr{GIjGM;YtD7&j7h_3H|fqQ&bj)W>(1`SUQ~AuigP!(dp}(LLVup3?yN=D&FRi6 z&Ov?NobD{24(fAIoQGz7d06CXh+KV^HLF2mHI%2wqqQ1XTzyt|4jOcE^;z9HXV8PW zcdkCGI|mJV8%72i7Uaeaz@R|~^?6&Khx+SyHqYFoKFg|u2E94;IWXv4gO)+dn#bZc zsn4zokwG^EgZiv>!|^@~?z%bMSq)lMdUNV?(47N!&ei8JFxXsuZiM>m3Y4HhPmi|G zbZ2cP&fr-=eI5_5Rd-f{mNlz82ku;)F9-Em#d(tkEq88=$~+h5-V~h1QLabJo##br z-t*9icYr~wM5{qhhqG=;gO))DC3+FeIq>M9LCd3q20a({oNLg5FOSPKXf^L8sJ1)8 zmu1Jf;yey^yfo5E{4#JUd^zaO+Gq^wvnulfSaaac+Gt!JP2gOvGHaJH*PSPFZbdYS zV-;r^bYRWeYuqiGoH1qfXSuT)wALAO-FXUEtmNM}Bc>UgSe3ac7}RI2Hm;1c)EH5^ z3Y4nRTr-`vvpU!Se+Ho%8F$tmqpgFixkkpCYl7C>vv9S+o$zN9ssql#pF>`605;%W zbBU`1T2mF*o$K@L+=8NITn)PJPw38pFFSL45l`8qJ3B(9UBsW#on_OT6z7PrO7t($ zox^PHoHaX6wHr>3tl}Kh=c2l^>at8Z=*}|hTzy{3e^7niq&w$|^XBJlJAY#z@_G}n zai%+~HRrms8uTh+WzDM7`|+d{4C?b99Bod0cD8mtbNhh*;>-D*?WWvm%@%cMd9)lk z1%vJ^tIl=jTyg$6)_gcQvMFrU`5T85`YH8Ut@$XPS`rLO^jeN`^;z9HXwZQ>7gwK) z&e?9xlT@6Yv#lyEca|d;RiEY5>drxfE(u>QsynMV2lctQ?(A&sFmwA9-pD!I&Pd4> zXVvGRH3!}Kbe>Tfwz>iTbe^T|EUW&gAVGmx^vK= zi_h71wszpo#pi50i{=ts(4EhQDXT~4y0iN7CiVGTSnT;c_wr1e4vMqtv#j}wEwJXG zJ3AZa8r|OwR#2aV;vCfHTyYMwwF6%+sylav7k`tDRI_gw{!9*W6;|bDrS1L>T`f0 zJMRETE~+@IH9J4M5~%vD)?5h|TXeQ|V9G@m=k7eCZsd4%T~yc}Fy){)t2GDRS#G=o zDzkdDx^p$qnIyT^9CYU`DbB@bZr6i5_vA^<;J2#GfiJ5yx8T@$+70N@t2Ngn?EKFb z^t#6ua@{%1;tn&nRh)AM-HPz$bZ6`s!(AN}59+hrxdp5_%-jx2wED7anc14KU0HK` zV!~|gz@0nuoYttm&eIMWv@^Gzt=$W)xohM|HS?(%sV=TKt2GDRxd(Svan{mr%f+z%eD?yLqK6z8Bmt2>V?1l@T6q49;EQ=gr)9W>}6 z_|DeuTaY9FwC=3dtol42?(7=RTz6J+4(fBRJF7TvZq9aJwC1hRbo&;91}$qI0gwHA z^?3x$2{jnTr0y(V{%PGg%-jyMwS(^5k7tZUNA6cpW8O9@sy?eb2gP|CSu31Ntr^C~ zvt-I!Qk;v<*)GbO`}2&ck>l0HwPy9@pg89$^8`3wt~I+7c4nqT%a$j>nboD`&XfK| zWiC2rdjMMVoXC;tTx(W$F0M7JKC3uShA+#f=M$Pz_(ybS73ZKnyHoZYxTWLOiz7#p z7e_-F-3_|4^S9^2lY{O&gmX(GM}30^t?oPpuDlEWQbJQ$NyGXA^j zbC|g;;|{a6mvdI`?D%BPpohbn^V!-e(fMp`#}Zd$V~Os;{kOXFD9*VDx2#$Hd1W?I zw=x?~lPQmeFFP+<9<3_9l%rsaK>b*IM`1;~HVJZj1=_#KEuLygBDb1U3P$5f>)et~ zZuh{|*xLWnN}X%&wN)3<|8PdDc2`}u?MiO#Cv;#OQ4SUC;spCm&eL^exC|?|l%tI& z=L&22N-mk(XV8L%bCk7$)dYU&oJiNGJ0nY*STbGbOIIRJy93Uf%B|A4(#rMj!5UIG zc>Z8gGg!%TO?*RoCC)^0reJrNy*AyoT$S6~aXud{3%NuaTCT4Tws%~U){8NKU{k?4 z3BejqZb`>^7tUtWHgvGc;QW@{=8m&LoaL5VdB|=0I!7f~?CFzzG3({#T;*4?-fYHs zzl=3bQ%a{_!y2Ip_wy@QVjJ`10fYzQ8uGseX6Pt~c|BOI&n<&%+d+#=TJ6v-Q(eB+ z&T9bh=-ENB1P&n}qV#;@$Na$i{qwT>0SgqIc~yz+@qie$Bnbx*qE3m zq>y>F5l$;c=4UN2G$NI{5Ng2x>_Q54CRCrdaKD63S&C_oq%Loqt=z(|!#Ai)+PL3B zZN86tFgW+47GYD&`62GuV7fVbqy|`%lyQcMJ3O=j-N&ICDdIj4tvEKts*y^jkvm1S zBxT$oqB3bZnv`+p2zMcM|5108aL0*Jq?S8PxD&-l(!^3*9;f{xOK3Tq_KPf)WpUas za=m96oc4<>o27AONF_^LDO_n%#`5J}8QL$hWVw5W_KOB&DQ0O($oZz2B`Cr5C$0Jt z(vpg)XXz_|rdTMC!2*Z&6V17!!O?sHbM#i=Rvg#P-l#S)TH5!G>fmbgrAH8|o4s8< zP_@Cg)1H~5gT9@0OR!*+*ES7#7wzp2CS@CCZ`T-f9NM>Q0y<{wyI7hB{#d@7X73Wp zeRIOrw7!eALO*hx^+d2_X*y}wQqE=h(oUT!YHOT!>SUUhGVRpKa4lupsgqe-zO+*( zqi>IEN8VAFw|s>WO`p-Jjn$Y^sI?|fZ`p-Jjn$Y^sIx_44V_6CN!MGcY zHMgZov|hKgiQ1a66pF4(vvi8K4372ZJJVPnS_|5Ss0z4;jqQx}VQbLZQ7yrpZ)}~a z5wbqCj&y!NzEh61;^?e&iMDc69wa_d8DL2F9OSf~lD1+60;^>&{jdjXa%(cXcjOSA_O6AJqk zHj}xcr=@({Ryv zJ$_^RL*>a;e)T3CS$0erOHf5}p($p+suH==dQ$7a+6dNSup{GDNp+wdx_OWkQHhU8-AUEKR zg6(79u6*_;!N$9`vwS1pu448k+CFYVjPIcB6DvX#H*DZiGlf3NcO zYkK{fUjM4`jh||l|GVqMe{>wc5rEB&Z-kKz$2s!Rn|$2Hn(+T_efZyxxLeEH|bMSpFVe{GllH?_+_aroEkDS5lBs*;b-hdn!NkvFx= z`N(|Hae$xFQ+}>|pwwH`MG?! zCH?FF)p&2w^7T{g@_*`knG64~=&-qN{_m_W|GVYGyq^C#J>}mmAO2tGU;l3DmFL6% zt32i3ExrD)m#=@fdj6m3M}^s6&ScyC{HT21m$Rh8jIW=b&$gxcQDMf{-_K_&%2R%7 zepFF~=s#sX+pp!z8nO8J;eP`ED#=?#%#L(?qf|D#(sdd!^9}9&mLM+S_@BGRJLGpO zMfjh+&wtnd`6c)HSNv!HN0NP+pHl6E_|= zE6XKPenSdJ~pUHFf1NV#f2hZYYB4;PWXK;J~cqaa~ao@O4Jb?e(ADo4M zJ^%Jt@Ywh`@LY~g=h_3n1LD>3X}ANy)A0v#{eZX?_vi!mj$49#@XwELh|dFW#6Oj5 z4~z%JJ8|tG+`xEnJd>lrxIys{!h^vX_}B5Y%r^rufbmru8%jw zSL1JpTl3sj;5PVez}9iExJBGNeuyVu0N#lIP<#`9+jwivx5c%I+YxRHj>c~fwgb1q z?~*Qwmx2ez2Z0C0Yrr+}!QjF1T5xT=4qV4q?vkFuTXjhf;hT3!Pvz}8r%U5y;Ieo* zxIEq!T*%a3{7d4l>4x}3 z@Wl8e@TB-;@Z@+SxG_Ejyga@Fydu65yfVHDyo#^fl{f8@c1^G5Yj;XV@jp7H9paAQ zka#FKG#&;Hi-&{5;}KxzbSgL^9tn=*Uw2Apkh-0Sod!;er-Rc;?P_sP-nAO8YFwRg zwYWyy1HT5YdR&um4X`_Y)3|b6DSjz_l=prKcQbf%d`n!5vo*nP_}@nrQ zZ`X}4(>3ju-p@DemR=HH3SJst23{6l4&D{t4c;B!6L(B&#kIlOaUHNuTo>d^ft}*c zU^o72$Fy_Y1?&=c1-tU!Im=bg^ZYx&JK{Uz=kV{0e~6m!=0ET*-$#EX{6kcTo5X(w z8{+u)yYw?%h>+#3LJr#FPpNgLbpN{_s{xN!5 z0N;q;1mBF`ic2ML#czY9@k=Ie$M1lp@So%!Z$wW~`@IBK7M7=1+iN72XN$I&O?C()vAd0!yQ~bjxqo<<3;6DvM z75x!>8vGLfndl4rXK;Uv{={#-0Kee)S;Bt;+ozvL&w2py#-1Fe`(F@=U(Tm`V z(VxLTM=yad@yvU0cZ2QHm!o^Zd!qZmd!zfo`=Z~0_eZxxzmIN>y73+rlWw?5U=xnI z;#UGIC6&R-NtL7vzE~xxnsmk&t0vWwPWWQAq06i zG-;MxLipn7lIT(VOTkN`9!YoNFN+@G=rY`;(dE&@99@pPEV?3kh@&fTmq)$Q)=8VB zSK20N3${(#f$fs^VEd#4*nwyFN;~rOwrRWccTwB)is(x4%IGTas_1I)chLjj1JQ%v zgWS7q`Ve=&2LI~lTJV}^tE6YrBiRbq3~ZJ(Pp%{W+USDlx6y^sDB_wYqi`+27D>xw zB)-@(X_bt?7h5H*li~PcYyQ(P{9ftMWEeOk849lFZWl!Bqw}K^zzgs2UC+@*+{w|_$!M-Wg_w=eDbaQKGdS*( z%t*FLwg$K6XgbGz!M;g9a0W-y2=xc2;~y8D7abo><#<3cmAL*%Z~keow0Aln8Ay0w zG6)=$3DbcA>oAlJ^H1M?Obnx`(4DgKTOz_O;Ebu!1O&e0xMV5*xMWpyOtfFrhxh26 z_DRPj60UBYwn-0(TH_7{4~-534~q^5508!jkBE+p7A1?h zdSSB2-$(mq7I0VLFXkz$u+ei2p^Yjy(&#AsWuUfskHlXNy7z1A^hm4* zwNACT+d9=cQ0o+nK*{W6PO^Kl5?o2lZqe@G%IFZ{<|K#U=7M{0v<`nRI5(LG&P(Pe zYw^YT$%5oyd~rdtbFv0s+&NhYF693ogx@DUFgXa^Ioby+zZ0-@q}Ak|@h1?oGq#`h z#-E78IuzlF>}|9c{$$)FY&-4A(G=WdY)t)zqp3J|8Tt*OzTCS{+BaR5?3eUS_e=H% z_fHN04@g#ntCIthR%z>W_o!7m4f|592<-vx!LM7Tzu_)3@TW(ICcjDcOlA_Efd#5o z>CEV`!#O&Y(B9zQ$v)s|9GyaFU+`4?jrjY5`zEWvRs4^W z@%yGHB`1R?CMSU#k`uwPScV!Gtxq-(9vqFqZrEUKW{m;o;}65S)I4w=7RrWz^TGL? z8^ZBCEP~DD+;D79&Ba3496}=^_Zl9_f1U--;%Fpp1p867N=HVgCr2blCjHXmlHh#&)~OL^Q)`CBk?ces($IE`2EsLl1ssh zlS{yhl8eC$lZ(Is(T-Rq?-*?#?SP#+EqHgrb;Pb*M`Ah?(+PBs>CXJeZLvb9jk5Nf z-vK*uEz{0ep6ibdymr`a>ksaT-;VP;V#}^&swKIWse6~TOuI$bBxfaOC)Xy|fcGZn zCFdvi;EU%c7bN#3=OpKX=W^yg+`Y-&oVftJAh|HP3tzmD|9n5cKPS1LJDm-l!`0Uj zzCY=o-jUo1-pO_S)4RB`McN(PbuChDythbuVwJ81>Cip8J-LG`ZcAs{Eynz39@($O$g+CzuGiN?dJ}ER$D@30ZDq!>S zQ^Hz1{iIMa`WRO!`iz)Qv4vWR-66DCS}Ah3kIK>K#JjKNhlD@Cv1bH#9gx;d-%Q?0 zn(;;5zoSa@S1h15Bm5=!1$&8nK-~MdAK1a8S^6dROW)_ZuL%DIJEzUkudt^2KCuz^ zshdXW8_Amt?nT@;CLDpUCvQL#UWYg(>1)aB$zM5NH%$pA;48_ic&{d}B|mVcZu&ib z-LwSpDfn{oO7dOuJu#moFC{N0-*Qwp{WST6@Ta&E>1X&QQg?G{1~yB-#tLq;RI9iz z@c*92eS=-w=QI2U+pI5f_Rm6_;;lGCe zDwb@&!(OabbiV_?%XWf!2CR{O!+)xge#^hAp4Q;KYNlT&-y}7OuaQ>cxE@#?zgGHH z@^w;+vo+JI#MMh{r(Y(2NouEmNxlNV;@ls(_uGXkoUfNwPOE@*(l3%PlR8{kJFP@q zy|f~Jy|iTddGbZ_Aph+F_WXGbi@3id{2KTG{zJG2*?Y*nX516#b!;EI*UWt!y-_H| zJ?o^UxW^aCy~MqVm12K$523ffd+|$izE1iG@me)*N~lVK|AZBd%J_G4)mvDYsKCFe z%CU2GEBfC!&-)h2rxm~ooO_Dvo(Av6uU;sdmP@M_%BAJO@?OE!^;4DUdg+r~^HgSg zrGBb5qBH*ej4+C`r@?o(+9sFYpoh%38*pW`eRk55!i_1UYu`` z4!}}NL#zljBvxBk4bp+ku&$4VA#E=W#0|i1Q%~Zx7xSg?3H4fJm?8;qMW;?&Hup$( zzYPoV`*63t*)?Jo{!Tb|OIV5B{@rlLu?vL1cXvkj2Am15;LLHLyWm~SeJ){7iqTxP z05_kocI{?x<-Xv)?7pxo*B)QknfL{umhMjCR~NJQ#SG3)$L+_yi=#NV5KC2~GMje` z3(NW4@!6gm`>_MSa>8r)au;Ejw=?glrP2Mcz}1=KcFcUKi*+sSVrpYcD_rdf@6T2H zu?xir?z@3so(QhNU&h@|!1mP$&aEeA1A8p2AvA^S_s7PSb`FQ&i=DW?R6t#LddImTN(E zgKIL~;~MUFW~RGb6RYAJ$|(Lk@HEt&y}^C)Pa||XGx1lUYa9z6OYF={v)F8Jn$@x^KA9bM7`_=;W9_59y1C=~0#6VV#FpirC$o{U=21%={d@C4qfOS(T_ybELU zm!X&};>&hU7o(1KPIo~O>x_c43%HQ4-8o&2TGcr{5S6NPdQhg(tU=l7jGD6sT#K^P znWuM2oAduiXIe`SPz_=b|86Qc6e2*o5(-o& z)TK$_6qF{lvC-gYw4|2!TcMt9g+|kgqpeWSS`luI8;PRQ1oh#QOmq2!H-CxnBlvAN zKN1{?)>DaVx`P$bAS&USFfRXle(^D?!|%aI`Hfo3r=V)XM`#a!0ROIbSscl3pK!1vG^x}z_=2fm5W(mj2Gx9Y&x=!j-egMZv1t%;`A0hOvI zSQ|B}Ls|#LszcgAg)!}jy4N8^uL3)xTXjggpj&lFtMjH2_luJP7$x6EjZkD%n;N0H zeH%4Ip=yXy^L_Lk{tu{d4ZsE{IDd_Ph{XD6ItBcCC@?A!^?19|=mBaj^?27ZjK_Z! z{{@ZU>-a11FT~bCOZYmjLrh&p?!O^aJNXv%;SF?)vf%5e7H?!KhH8s?LpiWV`fXer z{0>#3NBTXgL=QBA@4>&KMD$1t$zQ=5jI8%S7pMW&LL=ybE>H{X&iVFf#D8s{#%OBo z(*#YbeafqYCD5(frzO#?+NTBHsC`-&rLTQj52dd?U$R45jeAs2-sJz4iPe_M#&4l9 zl|h>-gM#xmN?REes<)%kU}-e3ccW71U++fm;J+7@N;Pb?tFpf^926q=tWOt_&HkAQyht(p)U1AFKDeMfOgO`ZHIQy6TP4v zSeYmFM6;>}R^gdF)2iqjJvpulwn|!ptr^R2m%h(?wM#!hnQMoJ^#S-1YFxYYWAv#~%s~16$w^0f&Mu@dtxLz@BN#M6Kl!lopkgTW~K&BT+HB zC%1C+GCI%8XhXN*zl4g>1Eu12j$T5!dI{y|4t(*?Xi0bCi!Y)s^-BAp81zc}qY?B% z3+N9HWDLI-TEIYXFuFi5G^@c$Ti&l7WBqsW%eLv=s9kN-dr+X-rq7|twMDCX4!o0l zwnede9!=^VLigdfO{Zp>%T$zs9INoSEF#XLA$ydyo`U+25qk`dPDDY2b6~$xcg$l zyPzfXMvGVoE@E`PH|oLyaA(w?W6@8J!<`GB%fC7vU%UY==>+`iQKha&Sz6E0^{7(U zp_Xmn=sHxXYthe6EYna2x{aiu^qBzWDEPp=!YTSX0?$0Nr{&6;%OYd|6 z3cv#5`lRzY*9R3~6}Uf&Kp#|q{n1=bK^<$Io{A>b8pY~V@O0Fx)+kn|gB$sW`*Q6n zM(+C%T7`~sHcHFBXeg^PRb@Yp&qCo@g}*=kS?Ez`p>`d>(OIZcXQF?t=IBgRsnvuJ z#I;Tj!f&0fL7i%y9*i#4I$fLTE$hIwC{qU$vo2Z-Zp>7cjhWiA5pCrVbb>ul3{FOs z*aO@X|0M8aa4-B5!IQwf@i%}cg8Sfa;Q#N#h<+c`g%iN_iOR~6XepJf{@58(31VHo-Jam9y0YQQV9Rvsh?7er26e;#jQI(`Di6Ye{ zOQx(YOR|ckaf|Gk6+3o3@wg@{u9Ij>}AJ&+oVY*t+LFybHVsJiw$E z-dg87=bn4sxqI)gm%aA`oL?cQ^gw~Hkd1nfPr?t7pL&S1@MSVq?g;sQaxNbx>c6@D z5u*N^$tHXR_%Y)Ao5?1840t~0HS}yP8HI;=eofo`A=i-edN1((gukcM;@gZ^vo5?QxDDWHP5;l`v_!{u*{pL}g?fWX%U+Xv5au1o7d&s9; z&G9TbsAtF!xr^vCWM;1B&NUofKf}H2`Q~Zh(`3tT;CK>vJ?9%aKM8z-mfy$~J67^( zP5V1!Jw8jM|10DTwzPkQyup_CSIH-AA!qf~{?+Z9d2ThCshfefl8stT{^?er`-rY? z-^3ff%NxE!#^6h26MliS@C#&Aeu1kmkWcs$_kNzYe~FyIm$~{m-u-1V6Q3i`@{2t6 zd7$~1Uo3f-f6li*M@C^w`=66h*g}rse+K?9MDw?hWB3{1&-R-^xtlE0U43_wY1&!f zon*y!aAzl(r`u`S1$=V{*Y4J`ou}^t-o+EUxwo3E4Lh`yjLYS~%gM!T<1j0d5NDS-|~B0Z*6ZOhp?4w!oLCjTQUo)$Z+i?tKqJ;tH^Ne z1Ma0I|C;ar4e|S}T>S>{H;LMBZU08Uxs%Jt7+pdxY(1H#OMsV@4AXx8^EB@6C);!? z=TrE0eaTI&YOmveE+toUDR{{;Nc zjTrtP1OJ2= z{z}@isy&Y!)!F2SHjzP^OQvcQxuvtooXzK0*`Ckcv&kEs%Qtg4=8{D^m#YPQPtJy% z%6Vj6&g0%Jj@jg=*f+X8ll;qhl++|DMdlf9U`Bz&|8!(AREp{vX``JEHa5+W&)W zjMD4V2gL8U5z+r!;Qvd$WeoY7e)3=|+x_IhmXbs2=Xwm+ z{bY%jaUN@asolr*7;;9-Ik$j)WTMDDwf~{DoX`KzTEV>q#Q*<>T){TZE864u)=bO_ za#iE{R*-!f5Bz(wGb_lqtl)nplC4_NHkb4Ftx064R*-j^1pGVlI)C4qN!H-6`^_@^ zP5%s_nTEe6UoeZSzwVz+*5JPbXK|j+w=>91{AK@tBmeN<`~MO+oAb%spH4<$0l9^_ zC6_Xnr~X_2RPIb8Ut^|a3fEJ~)Xe2mo1>q+%v?VI7jh-;z&Dxp{6FNFR;FQ= z=p?dbe-8W$GDB0ymYJbi(f%{8-REyg-=6`el0W;exCTrmC zBAmHDne4^H_5|`6liCwYHe*uzKa&~yQ`fKJ3D%5nPbAY}_QM?-ICEzLG4zF8%_}*R ze@EtMdHeTiqwudd|2|j$JK3gx$NBfjlKmA~qQBzq?~*0^Yv5n=c|PwmqcWbX&+l;m zcga`%A3XotGS{O(=TxRB6+EQ#gqSnT-7hIbLKB|{qtP^3vwEN%=uTix2&C& z@_&_2%gFPr;n!zz%p_Z|sBL!PT+ZilEFx#HsC`b!x6CR#5G(?^TD-dy2wl@NqZ6D@0-6Z&H^ zLVrxgALe&I!{M&IUcE+J2HLNcePut#_XF*9Jns%a?w9g;vQ7i-&vPto{}9i- zMwaD!oWH;~W+Hx*)}O+Y>&OaxkMBNBe(HPV8y1tRxPzR+;`UwSCKk6p#r;o{&sf~v z3%rZ-?R4JDd5j?zLh6$YrT(OeLs6`-@~_W z;@Csp=>6P#FD(*&k@I`GdLLP(mpR|Uf8E-8g-=V#*F43idx`m9KxSkQ=X-g_9`ZV0 zal>hq%8H*3`#3N*eK13$xt=xZ}!~N2q2fo06y+~f;!#wdL zT)#kWak{{u1*YnK{C8PF9@-1KG+XwlNhsas&BHwZi@M_?FoUa95L(b>p{NKko-d(ay z?*9$@YANH@<_6%STF9=|S=>Z|BZRB|K0`zY^&_6=+V{ zeGX18@^dBB=k8tW*fC-f&>g52_I2Dh2dg|c6T1q@;w}m9HMR;_lC{oP!XLBw zET61`_LZw^i`115vNy*nq^f(>i~;r|q1F}|>%8sNMcS<9YE_XztC@Yewn)*nTq&Ve zBfHmdjlAW0IoB(Yz>B$F!m*~cjAJ?Sc?su%@>yx^-Z*Aj*K!O12Y7BR$8z9u-r%qJ zUNfz0IF#PzVb^f1rA-UDGP|~hmdyvQ<3IXBK&j@*M#X_>v?+*5E8?Nqu>E>ia-;AC2KCT*QkWbza= z$wu0F7N4g9ZMWLR9Rcl|dlj9G26L~cbGVuTbS&HjZbs2*Gl7nm`Sn>vgQ?SIGQOMn zJg4ZcImp#5TyN&CyH|-Bcj|G+D)$$2*S`7iZg#73m$4mucF#d`*k-Wnu6^!I<$hDU zfJ#62omvEyxa*iZAxdS+!=*){4iwot!1Yq7ZEvBwi#RVwpDcsoE-KWwkMl}2&kCUX z8TElJF=d5Bb5E##@FjlaB<+&yB^gYKC8_%cT?*2L1(f+O)J*0P_Y&^m?e>?PLDEm%7b%vcAZ z>=0k#Z8nFP5pUv1Ol>Jxs=G9bsjc8h%U~;*agR3T#WpaL3IlPNJ;TJBdn$@UvF2WI z3k$y79c~GSSQ3Xy2{E-Bj436A=EIk97P|k}a?V0C^4gO^bNAYiLbLpi$24eKOWM6L zHIEws24G5C_(mCjaH5L*jum|%q|97?qDkJ_7u!60hi)fi68v#E;y>xEDogOU`_pK z9m$mMQ?xQko{%%-iSS0Hap~PUiAmt7L+^DDR64Tsi@K zxNoUgnN=`VIaz#Vzdi9Km%9VpIB+5s=N7IJQ_;8Uz=JpxYwko=@KKd8 zVpLmy`vJ)#*2WY})qPgQl$u0o6$vG##EDoHE9zyrPwl+3U`L(_AIU*W3O{yua96=p z^z~p)3?IsmmD~0gN(mP#Eh~3Q4V7#69>BBQd||Daz&(-IMDWq{0asm*MeoSI_m%>hWV&5uV@!U z>$uBcG>>{n`jASrB-B^Z#A?nfc=vMNvVs3Sv(V{Appx)R-hNj3owK>KkzRXu6IW+4 z8tdrgxqMy^R2RCFt2-I0zs}`Y!KnE^=keS|MspqivzgCl0sZC8r7fEawQuG>R&nPn z&RclyY~b1ar~cLX(EfS+-!{Hif@$?_<7y#r6Zf|B{1)K(oOkg2)+Rgz%M;t-n;krDMc4(v3;47T+^qwy3ckAtcoCnj zcOiyP6l4avsd%%RG>cgH9T<%@Dl##TAsg(S}`@Vm0ck}ekz?->u58ToRoWl7Y zzMlfTgY%ns-)+F#c2j0Uc{qDPgck|!(miOMrcWwMe zwfB7-8-Vw6?>?^H1bh>p1_s6#-W|_AJDn(@3mS&-1BL__4#&r)A0ZIGXAR%DX|W!Syd##TIg*J*fnY+o%DfUN8+l|HlrPV(9GqW zujc=*0A9&=S0g!20UFu4ru5|+?)Dc7xdx~ob1mOr1zgYhI$Amws5NvQ|Ir5P*K)od z{GJLF&(hL$z*G6=2A&%aypFRpcmq&e-N@xEb2Gg=cO%K%2L4bvxhQ3e?uTovT}*1nJSJ z(Bwi<*0tWwr#pG(cA(bhok+X0p}Ekk)~nQd60~H*>2AKgv(VLDKyA=_3V%zjQw!Be zt>^IFo49iiP@n8g$is7?uzQdK_ZCTTZ{hO$xG(kH!`=Ikljjvmyobnz-2Z0oPA774 zZ;50`ulMuJeLyYL2MWhOz;`oYq{4$ph1py`z^8|J z<}E-gQ6J*!0iZVP!$n>`%-z{Uc^=~Y2$FUi@Ik(NgsX>$5GhR`E%NeF?#>~iw4LuB zLjrFH>K#7D=ZAq0^W5V_rasQqJYrpbeu8fv1@7eh1af#MQ88uelYBRy7~11pJ;gVV z19x$L3hBNJsAu^!&n*P1ou1~o1w_N1;KZA7NO$6*|o_UsIF_EsPxq6Oo zo(5_KKgaP5F|KF%_N^RCh)O-n)$?eF3xQhD&vW%0&}iD*_-+YM-SxI&IlrAdRxs7S`J*!ck=KgWQ@`&a<9!ZeaMsCT1n`v33ZH6pG`fbhPr}J*MQSLU?0z3%b_OHin)%n_K_C( zbzH?JIt7iQzP_GAn@AmImA!V%wLEttPoG+}i?-5re7XtR=m+-ml)6NCJ^ynH&z%Om zk+YF=@2I_Q<#{!Zw!m#%scY0f+CHZNjTqg|UF{=nnLBv$R-o3xom{D3s=aeMT0zZp z7x!)h>L=gDu>p;teQ`GwI375T|Iqfi6Q~tqMnbFSE}qmHx(jVEfp6~PxCf}M^Jc!; z0Mu81Gsi}t8tBb@e-D~qLeU_4+xJ7q6OsCAod@`IFVOiHY69V#`QHb5=Ki7sg!l8! z!+f(5sNQ&(tFwUWm`C7*Nx(_`&!Zgb2sOrITty3`6YK4OC-1#q*CNzts;qfrvj()th(SiWVEvX?HtPXxAMFa{5hnu`GI%9 zw0gYDpF=Pa28L0kmCa- z`}8uoqE~qGLwtS(_(9Ge;`4TLJ+JcV!~EB)WL!STUGqO5BuDchzWpelJ_IyQ`7z|! z9N-+j|2W4-fFI-h39dd0{3y?Sf_onU8d>=ya&0bfE>C@uQe}@11G&xOY zfBi7WYrxO&>9ah&2lyIibDpn}$23y%Illd2-~!I(Hh-9W;b(dB3tW8`_<7D>= zlq|De(NA+M2QKITewyPa$t4?S{bw9M4g5)-{%2hMBw1u5vfnGV!}qv*Dc7s{&g}C~ z0WaknuwipJZFx~Z2paX(S+8BnG1-m{Sg$^A?(8r%r5y4!fI@h~H=OSu1f%U$v7HAOk7#J=M2VIDVeJy)aaYl;n5V{pcN z&8TYY^_5@log+$i$V^dUcZnA#rl+0p;QrP~6(C zwWURCODoJ;FXqlV&ht4hpkHgbT3PVFvRIERp`9_@Y4Mb}UI}*Fz%^x5%vjIm+6<2K ztLGG3Z6%|+hR>_O_&DG=o}bB`SzzDH{tT{Xf_Jme#&^ZdYM{2%DtOO)w3M(4ep}6F zX}~PBPfz8TR_I|h(9aV}J8k8J(n5WoHrLYOgu)+voNdX#K<@eNSo-4g{+IrgZ;_We z&n9MN?8>K%WyxPY)rnyp{ENNcmv;JVL$$Q~xAjuB`1fv)5`Z*KA)UVW!v_4=1Q2)~E0sT;=%LESVOUzSPZJ^hx9MX3c z&t@jtKq*JBNbgr_*Q2rqL!8McsU}HQLjT#SjN~Lv;On0rzT~OFTsD}$I-C_=>*lX; zR;?G1x8yiEOIa(A8F!Gk)FDP9<{cyclC#2P-TWm_4d$}p@>e%!8Tpal26L8?BKhrb z{3SP4E;HvBE(?Dd;hBk?uoldUr0j#Ceo#tkvsrhhuG3CiL66ja+GWd;5X-=#R@gEm zgc?%&%cz@@aZ-_$Mx~Y_A=J%USc~b$M6RhY224&SfZ%Q5uRefI3VE3o*!?65M2aZ=jO&a67#lg2SjlIA`o|vz8t>V`@i5RDVY%hU zfvzAku|#(!mblJD?*0UK^yw#Zd=$LDm6o)K-8~C5V%I9Mx}Ci15j55g&ihKVZy(RJ z&|pRxck#_5Sf9oMFXGsT6=~eji1?#uPIFItIWEG_adjHw;*VjI8ehDSV=va|6I|^n zF-ZOB$FaO#qetsYd`Le31a$uiVoZ}toM}>tCru)z^l9!GNt(>D9yp1!oWCBZ?>mKK z9q=U1a=zZrRNxvoaVl^spXGTu_+;RnaPA#MlkebsSK<1*xH7VQJLkK(W7gd`<*gj6 zODuXivEUhe_a>yl4B!ktn@L?w6nG||SMf=yU_ARi?ieH1CN}P!ie@9lv$^Y4pcC8EEw#PV124(s6-^5i0pi;+p@2Ue79zzUvUS)>f}8%ktoIo~S1uHd{3xEz^O zR$(H#!-`BibqVrm3D*OBt880ZuFXyil#Il{z+7;>mv-ux%;T^}dN4+Y_R@nr+?@{< z>_KXL4QhG`I(iQ>;_F-+GixC$_VJCe+Fi()T|Dt(v8TSl_bp_}KAv!Xz%FFWPQEkl z)YBe}bPT5a#*$#=uuO382YY#-9${oMZ& zPktFL-pLaSXsuDHm$|=yV>h^)!}qf}zJyFr+8WUt1MlzTe~jhzBMo-)xy`43WW{&5 z8q2wjMEEXOv*7s80gZ6ZLIQmO=zIs`VP67YFY`+akxnlIoh`8tS@a6f84N~^7a~1o z@rH4{PmN$aa0mST9MIhAjuMUEK`Y+I^-j*?c}5N5ESYDyXAFM_R};9SmN9auoX{fr zDCb4|j)cPb2=ZJk8{#Vm}8ovGncc&m5J^?QqqgLyF z3hti9^;C{e0zb(U+v(HOz#W_yBWE51njcw=9C`w1&U-OWJOzA=)-T~%W|nYhQ)rBX?uFoqp!goH$3gBkW=BrjBLsoLW3%Ck+C+FMBUFX-VLTcO% zyp{i00n`GywLD>_N*QuKpYP>LxuR4tUUdu5%-Vh2T?4$A^G)2l8M$^Jcg$3+MXsF3 z-TS#(2YfT<8@O{L66AjFT+j6l$j1k`zK-kbk(}nO)^nVKBzX&0r*dA8?y-X5G>%iz zzWe!fI)~o1`FLY#*8#6VYMhI7xdv#4@eIDzLof$_4szv6pqWa&{;Sc&m++ll$(7g@ zm+<*aWXUB!=TR8}xDse>jcdAHffaHY-x&?K9O#Uzv$#Uu42*XDrq)%biqjbK(Dj@8 zaMrWx#dX(jCOW7uXI#YSh_Wt`L@C9nw$}eh>NgV|Q3E+I%{O~;QCE9 zV`8bb*4Ua(BdUM^nE!qj;TGSI)u0*P}8gwy5|OGqCWj z1z5`c#aQ?YxH4*IHcJ0u3f9~_ptD7%aLh%f>xHz6^`H7py&JPp&PJV3{Mrdz&Et9^ z=RV%L3~23VA6Kp7f0;{6U8jDd_3?=*8*QF|jj1p`0YRQg9{bnjR#f#Cf zx!B~X-%RDEKDxP=)Njtmax&LBTJ@XOEt`?m_p?g5)^A$5X&yIKoW_BjNAO0f-_#!% zSrzA@>NmAz5>ZPnr?Xb9;&kRf>NgKpxoNegm77{B=6O@gS?f2g+)Nc`vs$xR%XvQ( zY|WvyuALLmp`}L3>PTIe$%?m)Nj6x_*k=YGqs%7>%SYBX)Wg9Do*P+-$~Ri z^_y01zR2fy5#^h~)2_==D>suvuyS*Ai3Yv^)UU2Jo7Qg*U9-7`7@mH3r)F~|ku-hr zm+=?gOFXUCZ+e~j%@6RjRh(OaRy)-C&Ds1;$Y1xPU|;Q%V`y7r*hK@O=E1G`pr~s{t)*+ zgUp-{wA!;)Zl-3_Sf`P^9|BtO`B|sNRBjrH?ylK1uVn=JYrtB$c~OZPTg7R-*ecEa#CLmDai)IrTRf90&hGlnPUU85 zIgfAsW-2$E)tb#JPOCeu-?X~Z`pr6PUk$5m?K%l+ShH92N;GQ@(7EDT((~bbV_d1? zJY4;zdO1~`2iI>7uH3Y8&Wg@jzo|Xux)29fah?r*X~UUyT2f+TwSLn~lQCRpZfmJH z$JtzG)>G)N;&k?NvvM;l0vJs*l4g~s+C8f_EH5^nm5iD9q9vu}bUHfUjIi_DSD<^W z;?%mbigOirwYsu`#(JzaGe(*3Y)n2grk#;*R;$)>W_<)JI<*On!X*~xtevc?TkLQ zRkqHOjQ5>6mHOmnk;GxV^{kg=y=~@Vo(-ndj+wJ*y{%QYV$b+SDs7Dm7$304*7`r= z26Z;5@q{`{)au(hd(;|1wbpu|l^WItCSFn3JG1K6wb`r)%uH2lZxi=$Ee>V6Hh(M; zp)1m8gVdF5YEDkMuRT&L{jFyvBNnaQ|kwI}PR^p9LYMSUa2{+d;%w7Y2UAxV?zRVs`kH~ACIU&`46l=+XHfR2HEJry& zDnHcxAF-JEKd~9bnlpc#(;;qV7LKa(f4c2QIZ_T>RO}3MsLleiUTLWLKXSxbg?pW& zp)Dzf&MJJqv|z|tK-G#o6MXF9vvW4AIUIWC&rtTGvZgunr_S?f+K*YoN;^|qQOt-{ z?K|gcXj^JUnyre<8dyP%JCoG;|t3xG=23pwO;SN$;) zdlGOrpRzJf^1B!DUwhC=(&N4&tzAiHD%ZO?X9b?R8jl&=i+SGFc$D;)aLfSiv;O|!Znw}IkULFgin|A*1f>JeCl44XC1lSt9WiU(7dvF+F3wX`nihZ za-eJZ)b)9?GS509pJrU=0Il}AmSZ093hp&m=DD7ho5#JDZ*SmR=btMRZs1q|bXI%T z;mKM(H}Sl4&Rx;Ryz2s>Gt+M_GT~sh7eR-SkMxfv!@_qnmP{am`zRW`kYvWGOH) zPVI%eij24$zB-k7rIy9r94mlEH}B>Ru8Ja$TOG8lH83!GycjN2a`)!N@L!W756z3= zza~cxpBKZ0;mBURIG78=os}0|2kUSgDKCaE<;9(FNRts|zoN zFPj`G=hbzytjBOwqHExY@MU;0e5sa}Q?p{0H5E->3>StYo4lBnv8=|ZTxdRGC|(Q~ zh9jH2*yO_SU$|3E-OYvaXywIlp?QgLVL0*xFRBscr>0))=Ez>!vFb%vuXEM8x`v(n zJ2H;k4Hxv*h?N(sM$Gzj2W!M87s{i<<-)2LFE2W8DD4=H*wm4i9#Sthc`-V&mtH(r zBZecR7qfa@R;g?1#e=ypdQncTtJF1l@$h=lHNb8g8Zo>W?hG%6|DqSe zc}?wjLNC_UBV(f;S}*qE!q}+Y8qt*`N6v-Y(Q$I|P`o&lM%;z2vtqGYr-#yuN6L!_ zYsYY2lNaUAp{&y;7iz&?%i(%Sa^z4NF}$e$>$Xu3&5;M&sL_ZcwNZQNMRnUqw4*a# zs*T#TPQ!mq8}(rAsC9ZmFX}Iz;Kh!=SoPu?g%_K4X>TsP4)1TUr+8cOH0$cEM`NSL zB0ZrOU2XYLv74j!7fBVkN@Zt$xG^0H93@3tGV>d%ZZ3g>@&78(i{^C&CjOsOx zw!hfai@l;Yu};l>G_x6IIj$oPlRXFIu-K~y`-si>s+o%>a#!*l3;t7AT*4>=QX=F#N zX2s13UObUs9I6KHc*aqWMXvv7^NXWVcQaI$zt+GF;s0>h5$|(L{T-S$A`5saK1Sm~4i7e_8F;sliF!L$6U@ayPJpeMjrwtbR)bM<27+ zzzyv+)+)EAznB`h_=w3hp2#n5r&8^WoL|h|k;BdS@29r3clBG1-PHVIc8bhOL*^Q< zppTo!7O9N=T)M^Su@V?Yr~9767g0bIjf|6mT#N@Le> zoeeZj=L~~cKr5DAjcg{+%75n|xDT2&&;8VNIX}U;VSmZcXFZOYyw6!3R?yGnea_^t zK70o6a}I~q@$Q)BybY^bPv(8jQnWgK8gH_1R>w}|-S*9~a7B-k%1Dgi?6^2OR>6DJ zv6@`&Pv+h@`f4An9v??L?1MD~uJd6ZY@54f+J4(MdhMT5T5kJoyDhhUw%wN7TK~M4 z9XVZ7q($w%t8lxfh_%Sh#>tBK&ed5<#j|a8_D=SPcE*T1fVl2=R@!$*x~vNBx^k`) zo|Wdt(@$pzIfLkQD*UAb=M-fgsVmkwr^VS~&OCAslCzTB0iez!b>66RGMvSf-Qvz> z4uH6GwUJF!?Tb@)890Z!eQ}*RQQ48exl-p*&FJhO=TM!Gv~`}4bE`H}`R`mJ=Ui=} z=F#~^&c)hF)syq{ot?Ff+7IX6J9o>oc-f` zlkCi}himKjoez{*WX=J~%s_Y5&HD4pIJ;J~v(BAEl38l5FS49j8rdgeC3i=Puk3h` zSy-;oo_+nY>YuZQ2II?hVS+E$h55(9SKU`))*yUkrA4teJbZ~Q=XEVOM)-0?nBZ$! z7rvZl=)NA}Z8-RnyRydOy24q`m2=kI(cnwYa>oqk?e*d>Im?-V&IueX{*t@00_O1e zOYX`Fo5SO;%#d|A#*y>aXyL0V4}0;KJCB6F#&yZVUi>vud?^jHLg?#59x4r;pS*C8 zJRA}d3t*5R@Azk12TUjA1vdtUF$by8frr^#Qv{I4dy^t)Uc zY#H!)@>f$HHvQ$%vJa0&e>MHDrv7UB%UN+rui4cc4zIudDcOf3#h1~ItclYd-x#U? zH5_|mr16bj{#O%U$C|%JOCC1;<)(djEc92CzeZ|r^y06kJZ$n;Qyw<)bu8pzGal8H zhs}7@v9>pw{M9RdI2?O^IQnZi_F)rW!{M){JRE8Ka5(yFIQC&Ld^O|M?npbHXs>Iq zjVXSv`_>xS))F@+J%%`xailhfYso0d#&WcYZWyN>$Kg8GExtGIJ*h;HT`gq{pN($2 z`hxLiV_dF;VqDs2xNDt^1!}{%KGis&I?-tUc%UttUfMLBr;RVWPwzOOadX$WNfdh= zzdD9%KlkyQUfDt;@V3>KkL5k~!5+CYuzhRB-fegOdlD_RABmNBqW@!PY0V1s)6$wP zXw%Y~MHowaYj$B=i9{#sU<}-R#6*q>yx-9>9`DNG#@mxym`a=c6>|>LN?VhQIJxv8 zIg06}Z^>QED5H^_h8d6X2XY-^ZUX%=2jaLSiz7DD!$ajJdXLY<^54GOH;Ls*<;{*( zKSwep$vQ|Uj@DQX>BP|*$B~SS*%wD?LK&?IT#qmBl7d>i-*<^eabo^LO!%9=O9~RB zp{US~?{&najcMg~91E`;eSaq{kxr%AHt&;urDa<#T}$Kk$lgi&eOx(O^2GRZ<=XH5 z!W5tsEsaV2Qo1dY(xf-rD5Xhnwp~h--ZDPE(>FOfzI`e%)MVC4UXz;4MmdI3lVj!> zs`<@c$p_MsSuOjfWD?WTn3mc^4zaH$nZz*>%WMu;lQ~b~DQV9h`M-{{-0uITt#ZG; z@z#K=^*VmGL@o| z^>cLOIQyoAvmfcLSP4$Vwv-#GAQpo|sY7}Zx6)PmD&;6Si~l0TWuF%M`?cT%zR9XYeOQkElX7FT++k7jYDL;GkJSNgP%W^u)iBWV^_ ztT~cqamAzKIi2wkzmDh0j6*WdV>pKnBgq_b$I21Qc!|+EYGO1JDqJl+Rc?38J31@W zA!i0ta*Y@Xg@ltsA>r^)NH{+f6543W*mh}|?en+9wSBjrzS+Ku>*?hwM_^1DlQE2f zeRHh(Ii!Ebu+1Ts9ow-SzSA)u$003gWsK*Lm&K90P)K`Pg%dgKkyiX94za8iKbb?h z>JDfpaVS@fLQUZi-{vT%awt)?GNy63pY8xxCv%?0Q_|J((O=zp_OWH$q)>C_`5*d8UFJ7!zk(A4|N8tKnoDQl{{ za-3|xGDxYeK9GJLDXpqVr%b*oxY$tulg zfk=B90d>6c{YXc^UzOS&fhG^mD7{$$l*3j4tvgf3EC*WsqKsJvbdHm{McTGzMx7(I zJ7ZBfAs4t7oDxLtaP2tzB-dE?VqfJZ>t1Y)TxQ*i?UMVfdvUbnO6y+4q}*!Vix`%R zt$T6Q4Tyo-K}wO(!Y zraYG}w78^>q3i*%Qmum6-Ev8--jPdcRgYX!?E$$&u81X2ZSU#)P75k%fqh58Dxxt! zN8Re8)D~s*Q*#uoq!uaIN{v#mnA)XaH#JScdTO0Q4XJ?&m83Q*)RUU2P*rNFq&9o# zp5Im0#p-mt;-^(>Bh;Xdled*pR`WQ5!?E*w*C16pL{5$U7u={7W9Q2a{%$OgP@1|? z3t#Q1Zqx#q3e-ZkWlB}GtYfaURm(c&(xh*d1C-9bRnE}*(E4&5^b>uz)HJQ|me#Qn z%U=6NTjr;Dv!h`fG~3+tM~8~=dLw;6C57Xy6{f$UHuV;>BHR8Gx6Ecz6Xy<)28yhj)@~P9J-Zi#fKCp z)jG0LoK&mMlj0oH;rgVGz5nmq9DD!Yw@JNCx^3zyu@?%q<;TY+)Ecaoq1K@Gp_ZZ6 zp!Q)b!;Vd;HCQb}twHU>ScXzUwFw8xNDbv@DJi5;Dbx{noaA>$+;NiM9UnO(Uc7J7 zcZmFO9F-zU0>?M@d+?T6ROFBrh7!eJ(gSd8#h>Hdw8_;*a+ZA9U`kA-osvk2DVIu>BOQm(M(96OUHuzda%B7-&pDoQli!>2b17Jz&e)#} zo|kYIM3dssdM!dwT9HidW!l+>S)JDpDFxgjdJ`&EkSvykIz2uQ|kBB4M)GH zo>=cni6rgmT`7^IM7=8|l2S|WYEEgtt+vgnW7fNxSNdx&?PKbm^{y5$M$&`c^TLAr z$ZBb4WVn+991*3+aB$a@Euq5DUZ^lU7;Zc=ojY1GwrLym(sxbSF82MbjHrH}d|dqz z`S@7K>XG(WsigICC|gKegsZ(eyxpQK)4q%3k$&{BB6;*#l|)VXGnAht&a36G1g^2u zp|zC}HT_HJZhGN@MAsaR=}>y&LQ}Y!$6JjKoy3(I-0FU#jB0kP`xApy$IJWjwYp#4 zm#?)6OlvmN)&bI(c!e0EgcKf-*i;e zdj6hvrgW|*cN`ogHM!#uiPbAko0z|26+6?Bk}_(XcC>wjV-o`z9e;eZ;Qx_2Mff zOFzbhq%b*94s{2ilMZl=zvJ)M+=stkb0YqJ&6W83HHYHw*W8NQwB}rlvdP{4j?uTu z`~LoD*>aAAQc8?CLgHz-@#<)l_|#2((d5}*SB`1!4JgS+$Q(|ea`Fnb#S{7>1ZqKn}D=K}YZYeVsH7j)u0IxKw)BnvP%J^c{}1?6O7X!XjZ((b1GJ z_CwvKzEQtK=V>`=T}%I3j{2(dg_dKoIqEa@mz1QHIJlO>UzKLeFZlR7E8In5u}x zB~ulVcx9?0630wcMB4Wq#Fn zqnR6O+6JTD_sIUCYZ!)O?^XLsJEYoO+9%aU(ry`!e^H-T^Ne=HL%T=ZX$h&5#atpy zBe$uVGFCpZ#=(5Hd?MHM@!5E}Tw`sKadc}7tSvIWZq0$UMaJE&MXGZ`3yU%e8H` zsJ7Xb*1p(-+DCg<`)-fN9T8|_zP zjZ&(1t=6-$PR*|6>oxhIxgKA~Oy}|A)(^)=Zf8 zz5L+#Xz9xj@rvVjH07IAZd6h0Kw(xdFD-(M9TH!wFXf$ zCSYHbrlVi~ApfZm6G@BZHadBS<2hEb0rb112BlZxPKj9<$*@jQ3KD<4YeA(S$Jx2z$aCeEG3d-l zlC~W8?%ec9W1)$tg(kHYYK}72qFj@T=Sqj-U0I-YsT{KfM(mVhhm)~d5@u-hz}_e_ zwy8s#_CvKRG6wcukKpijmlRvAFQs@QlKLdt56N0;!^iij8CXXv@yMfzpEP+kb$5|b z&3g5wj7q#!8Kvek4jXz9`%;D2KM{L5KI^%SR_x_i<7=er2`JMyvg*SWpptzw)_*XD zbADNcuY3JHV>nyNDtz7Rxf#Q$>*4f@l^Mf1+qk!@3{0p#H`nR=jM7H&H2vy zr!$Mx^a(vxW4x~1r>B}(GWw^>7`@D)(Ni_&CB^6!YkSx-y=CQmsxKGA&zYm6cP(G1 zT61CHYok|sp;4;)=Jz#OE4kux>JY~+^Ffj$oN zU}}J)uU8x`yJ%PO@Ad0 zLQ@NYTJ&3>x&=Tj{mszee4rk{`K$#r52$Bw9;*Y*1?n-J%PK*0fO-<=u;$ZjpdQ91 z)>@kd)blvIP=N4kxML&dvkE7$KbcB$C6dlUh#dtTRSH2lQN}I?W*MU z?4$2h|0VaQwPh~QoKZ4mnGj!FC=}GBp*BpLo!5m3POy7QZ_)Qg#Zxu6o5st1Hvuek&)=D*7>aU4av!(vF{1^-y zyGm7%R+ao~jh)t@d~J=LHlh4(jh&voa=;opHQs!BXH{debJkS(c54p5YojM!851 zaUAOW%FIQwP4?Xpu)X@@;@Va_%RX7(ZoK$g-PrLL#nEsn(6LTSVm-&64rgaRf7+9I z{%KEQ2U3TG@9H!4ylHTS~wBSN>XZP1kV%8ST|(V|;%C0(gmjnpUSrgTqC zDDxeah`sfl{TND%R{dG^T~l8eVQ|E)n>jLVCD%`8JmjV6Tss?b5?9u=iKU5L4GbJl z8BpiKD-(N-W$Fq-M@k+?ArXD`cI0ug%aO;C%#p{D%#p{D%#p-RIuf6mZ=ad=$(3dH zNpfYGm6BXpW~(GumRT&x7iD%!@<^HWlKfI;!zAyNSu)8-W%f++RGC$i{8eV#B(G&O zS<65xVSt{S^AcOjz?_~&W;7cSUjg-L!3_s@v45)7bL8^7Ntk zbNlWZ1IE-H6KBU5Yj>=iHDe6kF?2SKv3bYVSvJP(9dl>j7|RzI&dSM5Tx0xlVKM+> z&YXZYinuh6rHx|sfOCAERhOy)rH1#ME8CIN(Lsrx$j4f+>L+!MT&)FnJY`HTJGUug zsyvX!wY-!H(s*hpdt2&Hs5R>O%Fj`r27IwMy2? zAgw1kHC9YGb@(<^I5pOjQs4bVJNnW%cXZ6e@(ZJ5+54NZ?;Q)Xr&5!-(`1^|tE+O}$eO7H3`El~MDdsGWl{?Hy>z{tus+M^5MEBQ(8 zGPjh!IboUxX+`qSpD<1w8?@1<#}S-CB(OXbRK zc|huy=Hv~zLb)x^$Sun4%06g{s#S!0xT@8Kb&YDH zmbDJisAXMq*BZJSi#2Ll_uMdQxt*i#@UV@m8rj{-m3ytYg6tNqY9x3wS9J%8^SP># zBIwj0=PH8gzwj-o(d(_J#f}T@7Wv2-8;q}*we$kJ=#R( z)VIuOTcl=G zE28l|LXMKZW4|1w+FwV>-*E&SC3S)pMIuiAhuTtY;84ylX3BP?Xi8Y<7sQ^INO?xyuX=Wx5w#w?Qgtg$IW*I)4{JT5?hX*E!Eyi)>}*m zzxG6XODjJ8%KQUIA+;NsonlPS=(q7Ay+q@A#*vJf8-q2TVvI#w+qjcaC}Xh3ql``& zWj9V`)XF)U_Drp44E9*iZLhwF>C~av4|`!>?1#OuFZRP;*cba@FYJr`uow2le%K59 zVn6JKeTkFDrIB*wtN@si7hB3qro$sS}J4NN<4Wx{-9KA zd^_t$$lH49{<6HC72K3o`XpJ0Lf*~_Zu&R+Fj==kyEH4fWle^x;FdKRCNs8L{;rIw zZmf6p?CaBd{QA7{{~hnV-3Wm)GVuaOJgqUJP+MuFL0N0-t#z%v($}rM)yp-aug8=T zQ5ze@Z|ca%Gh@Ax){%CR;*o-p?vaj>`o2>=;P3j*RPw1Q)SbrpwF}gpssB^=7%>@+ zd`VTMG#G0_XumU;ccfNJ^jWjN$5M{e_?UWMyFdwUjyJO~ljBu$m{E&HQ9G(*!e=v} zO#7Ye)yZoA^IE1ml;p-H>G38&|j9S zwK)8J=~`P$OlQ^4WU=kD8O$0#upe4PzC+&gH>Fs4P%pp60i@*`A22FV;|4|xYCORx zLX9&RT}aeOizchfxYmp@v_zStLRX_P_9S(>?vk-Hsdgd#Gajm2en;%5PgwIBJq}<#RrO|uYQYdr$h@rGI!1O z<>gItUdg>5F3vN0`ds?yX!2^?>m$iUYFw#AKDGVwW8#%krG1ny6W^C6l#GK-u{yF&``91`f<8HS)6*j>!&6 z#(x$a*jdT=k9*x3^D+M89=Np@&%JSt`56Ck&)gdMaWCB(`Eifk8u@YW-5U9EPhNGS zdxyGLue#Bi!9;wF{3ubggPVKqCFbMKze-eh=W|D3xxmPeI|VCItzLA8Q?<5LjqWV0 z|K-eJcN~`Yjr_P%s=ROH#~q5L7$YR^{HWFBZjkP%rElwu8>`>Jlxa zk@#x%f2def%~K~s9c`w*R;R1U)ob?8UZvhhji!c7R$hIk{nfOEyqC{fm+@bZl`WK! ziXH9PDfxS4wAI?d$57RyvFu_~i^=F~BaN{KVj;QE%WEZ*Ew2?$w!Bt8+45QuWgI1| z3fPZS+oZ-uiQ-7x4_5{hI{MBy$ozvbyj^P1;_K&E9TP3VHmz~2v=GPAR>x4w(QLP~ z9JDAMZ)ZPfX^IDDMVNIIKhBmg8!6tLMWF>GKAl}*4pTfk>%vTq_;)sjIZrv*SsLa- z_1jhe&E(jVl|b!gd$}IEl$z0i!VB0wm*_mPrSN0@zV%CLaCyQxZ*^|_XxpqQ!zL?IH zJ<0kC&N#PcuDB4+5i9!Hj;?mN{FGh_g>Gz9i zDc4AV6d(;7sgfr2%+2siB}y@CPn-Uxqbc2vX5FjU7JpfNE2|~gBB`UVw4mE>8cCcd z5gtcK-5~!SjV5wb2Ir)-0Iclum-IoT%h(8dw_-xu!Dxe+(55ijASSdmMp~Dxv`js7 zY?+FSS|4vO2G8w~gXM4~;_F$4JA(3p5^*^8kD6a^UY)NkpdYUlBo9iT+CR-W zx}T1f{Zq4_HAXRd`r1DFc5UU3{bN70TkPvd>+Y2uj)m4sQ`h^>H%1&%N;!JpLD`d> ztfQ!PuY`6jX=y3GL+C}i>9&i^NFM1tjFI|2T9L}B#O0Ke$v`yQ-^=%D;`dnA+%IcYGaNZSE%T%C)tQ-|r6>YaHosiP@q2q-Ohj%bv8_e#E{XgF5_?*S%^IQAZZuYVdWqbgQR2C^p6?&K zjxDinW2VNvw;qUuZ|8d3fe85yJcaG8M9z2OJM1_RQQw8Xu=7Bq{Q~HG*MSK9Zg^oa z*RBa^e110(;999^TrqRo2e|4rx4qZi&?CWDV%^3}jiXw3*u+jgk%6PAsOT@lb+lo6gFRw3ri79g)VlDhNvB6)*4qsX@ z9jtZmmE2Ip+U5h9qgq9LFn=ZYRJp9fU&&QfE*m+29nCtcN0&Dkex4__*vZcAL~^7e zdw6-C9&>Ru+hbjJcV5nnT(Wah;ahpQJ3BYryj-#c-Pt*P z;;atb%+942+p27(lCsIF?9^koOGfU{d7h)m%Qf?;N0XNuNuFnP@zugOjTug#k_v#F__w~AhQp~P2y)I86~@Ky6Xshv+Yb#1Y_t)RCeUQ5`_TJM z`+YEfReUw`-kIwl1`ozpYCQBy^@meMrnQialJNoaKWZQI8b;^TJ9;8|FM1<-9p)lZ z*`u|Z$cY}9RZ`N2cJc7`;M3NOKW2`@HdU|Ln3$iur*-Qa^`LE=t@S(GW@~L{TBnET z8*QEK)V9`FvYn}&9~d~A_9owFRwk`>URuV|mfH7DyR8**JRO;%YqwF|w7yr{;}_d| zv6YOUxYK6TTXZyW9#$lv%W?OA}a&V(VXL>VI zfOzXoXCvc>UhV7y-|_3ESMlHU>W7b`UhR~-%qB=*sZ283Cyu0oWUf=ml+1N1oRYat z<$JR~`ko{4L#hYT**~D^hjjc#rI~)?(fA>9Z^s)saz7-sP1PIe_#vr@A2?{V=q4>9!Q<}x3s6Pr0_&Jkb!H1X z^=6r4n5wf2@R*Kgy;;?})}3XJVXBypja}Pq(H^eeER{D_4D)SIPt zNlhF(=}7rYskOfRrk23^??+_hvTpv;a)`HYEu9s0YDcXLqchr#H7=ue?0Ea50kJ$9{<2P1szvDMnkI{O^UU8XT{FPa?L;Lxei)%&ZMF-~S9?V}yim%KE9lksi zYr#>uW7@^S1y&mJ9O?=e|n)Te((l9k zE&bJudxpPe9*9;CZ67xER}){o_^TJbjun4p?FsEe_1TfnM>x_rT58*kgm%Y0v##)V zs9DOkelPP82FKB6V})-yL|o=z`!LyubI^9(^AUyoucp0GEe&Vv$Sb3rw`Inqf`OHF>+Np>q*+412NStuu{1-z(2L+Wa*ff4P@Dj3gZX{H#OsS95-rvFUEF zIcxH`N{_bZ(az7R5$dMbZ2YJhq1I20|5NAtWUfzUX}K;>ulYVr{u*t39nbl6gYh-I z_(n6Y&`Ta3&3w9p^FYbi4If{Jl81@?8tpW1U`>nb1ey;pV_^MK@&U%A%_bP7?8K9e zMq5{CJyY@$broa3IryDcJ$Jv^wuSdK zGds(wyRp1s_&I`Pq|8wHw)D;{Ox|0L9Y)yWMt^JL}&%#&rrk|%4v z(_BICJX!Od!|!kHY0cd<$IX0&*feWl_4Scs)5uA1YAvht?3_C;pDQ^WtK+#pmMh!4 z&b@Oen&Ur`d|&7`6jCX+=KCry3@3*eI*~Uj7Yt1&^_`>3Uq_bfJXGI@8qZLUlvE`^ zxNNw6k36Z|k+=DV$|+J$l`6Ka$`(072@~0(ROv;BVygT7Bb8ddxymjn+}~1{T6sQ{ z9IFy+sGNP3V~$TUs*$luM>EQDl2X&V{$@unSO=`0RW9puDe>i6Gt7>C`Wc>9mU%Tg zvSKJ4jdTpdM?>SN$|A8}B~oa>JZfeYt7W8w(104!S-u?_2#(C7cCb@r(XrsKp?INk z!N_VLInPzJT z%k4KB4IeCLq8*w%67Gl<;TTp49PVh2hBW3(_>LSq7GpzMyc-XN@w}W(ME=|R+w{rl)bJXmRXvvyr^Ge&c&4%wW~We zfGapDRkE7Skx3PCk@-8$+VR(ITV@(X3uM*ABc=apX;)j+xm|iqS*21u>WwK09b0FX zcE-)Nbw;l9!{Gz-m=Vm73;p~Bt%KYQagW5ydUgFu&(zcUk)gStt+OO)5PTa}r$k_PJ`at!Z zICea=0yA$kaS|n?Z%DLCt)I07jh2X8CAS*I_laZoo|F4B>iS62dGqk!Z~J_+^UQs- z>)Yg4e6zn&-|z3`{jq6>M>9%ze%!4Z@)Ya67@#6E0;KA773;5PW{ot7N?HZ<2mm2RZ{L$BLl zPo+mWNm{R?ZLhUA9c_Et2iLM!zj&~YtG=63WF#@1rd=BA zHx=jdQujDyE_U~5I6GIo`}E*dB`eiMQb~K=RM#Ah?r|8ZreAvNjD}RFPN|W=IvU0~ zhaXRiO{k5iMcuIpo3?bdqDN*E9&Ag?@Af!;`p_PFFWna(q?exU&`%vVDW@|d!ruzF zI)c5&?cnzui5+-28$&C-6Qi&_QeDTo7>NuY4ZAK{BVKUES*l2E_Hca>qczfUwEAe| zaV_~vj5Z@$O)Gk6`?(iw$W56oQ+-t_HZgx!Eta#C%-P?-6x^cfAEtAt3b$8T09U3}~tCPy?wUbJ1z!a{Xg=7uDRG>EP zDO^n}vqMh?x=Mxh^V6A$vKF|O&ojzA!x`LhzueV)o=IifYT_^Zxtc}A$A023`?#82 zD!JzXT`kOtkhwtDw{pJ2JZe`j1YXGJ`OF311Kh*s1ymvL2JYr_R@Qaa!vd<6t=w3| zu?y&0yNkKwo^V!fEa6zp%n2)_mU3(dxuT-pS>x;wrL{6$YgPREyleKkPL;+Wl-kOjvAeaE8p@sw?z_F#=WzsFx4*M;R=gsi z|D}#m(`d!3W3+75J=OBp!>;ylbWdl+ligq;HF2@7JhP5x zW*~jE15ZKXC|}fWR%A{?K54hC=bP!klexEwyHkOyIlH#sRAke7?yul#O5tPIIkX4z zx9cC;Gx^?i5!FY^1J_F&;Cdow*HK)`)dbG2uegM(@tj?EaWPk}uaor)?L$^HbiGDb zITRe`Reo3!D+t#i3<(&4N!4ztQw%`Uj`4Xz<6E_{Rg zV@tulpP5)&h9oSHJ!!TT?nP7 zvpJs(l#VuWo(`0b&fz=*C>@>4IlCNMy?id?=<4^g(9q{Gf}1(d=FrmE!Y5|}%w|lt za<c?=YWEot_yxC5qY2x-P5{nYv!AyD}xynVn+m`m$y>>$pLsi)H|*^=i1P&E~llV-Q%irS~{-5?3%x^aa>VanWpS=rD}0bX4Xq_3yNPcYN7d%D7D?Tp z&Q5GgTuY_ycbQc*D~$~`&UKC3YKJ$+wt3xbn{6@)i){XGtpWD;NBeh`A=0ZmEV#F0bF8Ei`O01^1C@UEx<<$BwN|r|!Q4pq|91GL zdEYe|>uQ+FMJ+42+T9GYZmsgiG0SS&%0;E5HkQ_ud)H}WX-6p~wXxhQD|^?ucDI&R zw`CQZN*U$;bn=ces#;cBTKZwh--L!E6Xo+rNk^dL6}m2_eYZ7{l}btR-th`!t1BPH zdtEtStIu{QCAG;TE9Gn@qq0(&sAN=n%k#0-m6A&H$Vz2mT@Bhyg|?HjQa(y<#T=IJ z)B_oMty15n?_z#R-mYtvYVnF+ab(RxRteV!Ri5a#h%IHZzotcO-qYXFA~r^(A0)Q) z2>b=HNBKsU#r-nORzZ@%n)k=C}vaX42C8af# zwO{E`?0MH<9jagcPN#RBe);ZB?}qM|W7g?idXzofvZB1bOTVmCO24wJt+9&8PvR^Qu`7pOPm=MSxQ@NLyd&k5=T-QVjHqs@!{mB{9C2B zv5hLXtr0LcW}TUwt0a;I#*?(Sw5+P+ z(0|lIh<&9TODv&!i;lGNLmx3#Ry@bpSIQ4PN9`-+N42t)B-Oss)>4*eUnxKI9OY%L z1^3pF6FRcm$bD)yl59-WOKPk3 zgF9%n7zs!4X!g-qSX$$_jHmx%P>DK${);=uWg`6-caF;>Mno(+E|XgWT)7gnagk+Q zxk9sXk>y;u*MxBqV<7IMp#*jZ4WY8wnchPESa;A68Y>?OZB(i-exSCI#|}jsl`7ON zYMbbmV@DgY&7=)&$k0aYG$}-?Fp4OJ$j{bI3{4wix)Xtv5|1VVSu^`aAhUzDTqk$9 zi^TE$txC^T+B#B7Yy0R(rQ$@+sywBA+vF)n%+Zsxl;cgFIvg!2VXCxIN>y*JDQDu% z>D?t_t;~tE(SnMdax}CQZ>~z4XxuSSvExv8$#EQ{>|+(-Ol&iJEk{@GPHb~@__`@S zo7YWWX0-gQ=KDj>T4hHbXV5RHdqFE9V^wR9)%|d!662D}$xfUh@yhNvgVv&YS8GvA zO20*{*NSCZswHK`axDB*eaE(!Q>%rq6Pm%>Y!>>{7`cWnm8J&U%hlx|b=yldhJQ450;v$#Sa9S@9YfU#WNl)j z_mha`TO(lQfOP_LP3i=knLdT+zw*)w0jmX0g&SV~bpqWL0z0wltQ+XA6KGZlSTSIo zz&7l;)CpJ{P^$$tbJeR(z^sGWh^+Tz9>UziEZ*e0U+0zY9z$NvZ#~v}l=CCVCE+|i zor`Xsbs(oKhKX-Bc5E+%3JZBE$Au=s9OTI<>(@e%g(8Ubyn!|XA{LBnKo5^^Hyv+FXq@UotsP#$Ci&{U(u^9MC&Y$AE zxb$rvS}8Jqi7t3N+vJB;TFh`ZVt_FZ*fWTY3IT zpqBPWxwEA8T(Q8Plxs);P#_@tG)hA>uJuee1)@i zz*DVPTd#2Uc|JV_=3nJ{S?hzGm$g2`S#Ef~^#bSTvHL&7-Q}$hb6(#12YAm={vSPue|&$^hip5KeW_qW~$e3A2**2O$ArgaJDF|A8Ek7-@Tc}(ka z&iz0wmn%5;x31*e-@1zPxYm1HKLC6mXSL1y&`2-Q?sn@voZDPo1-y!<$MW2JiZ1#A z;Cs0H5R|bRXeRU}#_m?&t@L|fz-*v7LAlU%#^)T!8p^fvN;YwG$q$+(+{zs}SUxt( zXs*zVp*h54BE!K8OD0jyI=67@LO9dRrP)NQmCP+BqqzxMol&^c45OTptmoN1(pZ^4;0AABmbuXik%&dH!ysWv}JtcSR*g3Z5bRBEQU%jyF0H(x~*ix#Q8#Y6%6BrKW&6Fp5 zUhy7$npsb_eM7->vhZs04PZ>ou3kR_=_wDJvp*f2$e+pRC(Cb+|5V00xqtDn4t!WA z5KM>%>jc(;C%M=v0&&^T-PPQ&5=WUJj#ndnti`#eVC@>NuSF7BqoZ6}1XyR^ZE8vzFCjXSd8{~7F?@m zo-5Ee(K7|(&v5@)r2kvF^E}5w;6ncY>4N>IdFC0U<@4Nmsz{Hgxc_vKw3i~6)cH?x zJcZtr9-iQMvPh>>k&MdtOE@kqa{dxDyAtDZjwg!DzXS_GjrSPG<3-n8f+Zo%Jj(GH zSiY4$yude?Ks}FQK}bW7!vBw87pUJJK^NW1a~C6iUyciw1L$27AQ--A+r_blSsYsJe+&>#mSK_$N-flQsiE|Ez z^}grwX<)!;uDc`a&8AXJYMckIjoM5H&VX*EJ97|5zGrdP*VgyZFE!Uc3+SHACvjy& z(paT&$pN@*IoJBd#^>~PQwf&%r*U_)K6-i9J2j(9E4Z_Q|J9##JdKu&cZ>kUm)<|uHrd^PYtOD-fyc3F9$(8zO2X9@&_wvmS-ggR5`AesOt)<+NO1Gn>)^UFupSBn766?$O zyac!vYFbk0Lz`j?$5!yXh$|^TA8`RtK3@P_P^ikb57x$O>oG3zIA7*>093vvvv?-g(t|v{p>T(A16o{pAk^Qu3cOy8u4{4iJm;&>iO&O{;e1t*9oGP_ z=KJwHeKk7!8SXy|yb`J~l6?iAt}MD%`~NvUKMlMb?f5kCNzVERPXeC+UWU$l0{9T; z%g{a#0pG$|Z{jV$2Y{ENIUWG2`}C(DE%0%kRo7e!)B|~#ZyqW-=n|lw$-PBS-OHzo z(Kz>_N$%mS=2G+Q<1D<3^F_dYXqLOU(!0A0eX0(*g|j;27U0dm3$Z|M242tk!lH{V z0$#*Zd$@ODv2pgGCGX_UZa(cPHjdnTBcHDWUI5j^Q)$Ygcq;lORzG%Rkus{|wdk)X zpJKf>{S~E<)~&SJltuAW;2 zw@zExBn5APW3~JB1olF~sYBIY(JqPIdm5A#FGYVPGRhiO?Ovr+^;d@Hsf&*I$)W)gW8Imoh*L!nKywabjpIe5?ha1u+{ASNm%<%qn;?PNjXSp4bk)lmKGQ z$hkU14@SSm%2jQP=}0?uoc@hgh<=5-<7Dt*EvpjYL;|5e;e`lY~LQf z)%>@Le~!o7D-SK@pC$g;;lC{WH-scT4|fgUivC+O{xtF5BmT?7KQH{#JMPcaf2a5_ z7k{^k`#JSb82?q{pY;9?t-W>h6azV(C6Zo&>LQs4Mc<*1| zzjqcU-tPwQ-%S0udwfrlBD`Dp_t(Vz7ytGB;r^BV#u9fL`?vO!@ZS#qk$uGzcNF*E zEdQ1LB>W1y+6mt#wfQ#jJB|4-lEi)B{VYveuvnc z@c8~ZxBHi$W50br{Lk$7{IBf4c>DQv`}uXdfBEs^#5ei>{QkkWpI^71U$@`q|M`3Q z_V-ufuC%wmzv8=em*N}QTRO#OC~to+`}yqL2{X!mX8DGlX`)4{pS_EFLh`f7H>{Ww zEtKN6%yFxLObN5h-k*}UG>Ka=$L#_9EVH*s@)iP#R?ObVqMv2X%3QLa{f}EQ$1MbE zk`lL2D$9sKqGj!^_RDeGq#IUAiS__-uTX!rU%u56z+0jGll`){{*BKv7fY}WD4sBX z?5&u+-^;(+0QlLxzgj5$*)}OY>)~geZ?#am;YG{aFW;~Vh4L@>t zV-)dU8$a|r8vEJu_$Xq0{Lou8cq{D?{OkVQG0t23t;5^=B)MrM%3A>Wo>e+we9HH- z(zK}`l`0FBNf?9j(h@S`jJCFmKYyJ^dnI>#t*%Hg8x$X_6hYt z?|0OHHUHE1^3D5m$8Ea*>-{Uy_Rm{&+}g{$HAlRc-Q2(azGvN7CE!QjZ|z^+N<3}> z_&>XUdCQ8py-lJ8;Eh?uTl<%{jax;;E!^VvY~H3m(W*9XXB+njc=O7e_*$H}U%35yWPM3@9SUjXO>^5lGvx>_Ue8mO5AEa@m0h_@tQ&UhiT%r4gx+i~dTTH9Z-(CX+pi<@E8Y@q8{(_n60Ju4y2roTi~8Pn^D4K0 z?q4_7y4~8pZuG2pU%TDE{_pEwH@>+NpIbdLUiP1T ze%)9Va_jT!h9&l`J?n-g_TTla8|z0CpINu|uf%mCiT%qz#s1pA{`} z_VerZ_gDOxmAKyFMqf*OX5Aj&xIMn%*HYdd--!E5|M$iZ{WqEa3j6!@L^t;@|2BAY zFS~hs`s>=p#PLJ#1tI>-x_Ld(U%$3)epgH!)41^zOMF`0?q9e2*Z=(S z`Tv>YhqtaB_9OGR``7L9c|Y^zzswunp8sOR!h5>$UtWHd<^Rt4uiNAEf3?THJ^yuk ze)+~4^S_SRC%z@#?EB)M-Vbm0um4;6*A1@@|CVo=xK|lJ4*zH0GB>c*Zg_QwkI(xN`M9sC8(tm!o4~&}e)#8+!<)wpZ=GNM_x;b^9-sd|YkWS@e#6_G z{Qbzr-}_5R>}9u(awJ-DB#v^#``X{xZzPUy+?Z>w`Ttr*CHii<)qcbGv$%i9|33Q- zKi3=|+3=n>;&WcUmnHVB8zc7Kvqo;_!n`+N|IG5E@o~$IMBh!`FG75-*?*DUyuYBg z;wYRjn|#B5!;i)%dT@&OvbdF0+}C5=ca!%tc)Nf7pVhzqzp&rVMz-^8Xk18~-%F9Djb@7}NM`UrV%!y5URJk1P7!?Yz&_MEi}~^UJBQtGlrh_Wv*T zhktiJ{8!eSC$2OPxHtP%DmUAU-n!oWpX^1wPsNf@39Om^YA@dJQLp--gj9|;^V6x{`>s{{Kx%C-|R^` zzUQyEtccqIdT*SyssF$2Puh==#OKBQIjNpt1s(VN_Gf?6@tup~zW%&_znkrl{k<-6 zrvdL1pd!7@f79Kthm3obE>GV~v>5rf{7HM8`agS>{ z?mFJq$=k(y8;-bFX@4*JulSR`-Cl8fIe$<7KcT&D-4n&H!-(&?72osJTY&qWhWt2> zzlQv-D}I%MzheB(dwvZxeL^gF?* zgs@**;q!WrzJ7-qzjKY>AJOkt=Xc%m-c92>+4+69ybY}1{l@Qo<2Cs34L#m&%I`Fo zlK$=Y)Ajr3`Cao8cMSFSF5fEgy*lGN9Q%Fv{J!mp`)2w5k^C<2en(P&Z}ev%z89$9 z(a(E>^mX;SDS8i(zUF>sF7NRpad$w!?_1(d^M1c1UuVDTaH{`RXCJ;%XWwJ}Irkb8 z&wNDq)^qOXXKy|8mYDcHw*FlCJw*Kq5pR9}&*!{~tSs3@0jex3CWI=06=fHhPIQ&! z30IJv33rj*!1SV<>i^<=qNjYon%Ka z9egoobBS0AWfY4^lCh?j0l=zRKPed;yOUcr9p?E`-wx!@{L_675`ulr3S;m&O zZ-~#yky(61PLDokdRbG}kQrq91gt@+8K8Q$r0j*Zbg~xd>7ev7BU1HjMyRgMf~L&k z3owiL5N#icmDDJc$b?i~n+d98)5_Z9P79@zz0p=uwxKRgH#$Q zt=xmYEMhlWJ``Dys%^7CwQOo+(#X`ZF8l)j?R9Zpl;OXeCwu`cYs=U##UAqRBJXZ+ z6}8y~WfH$4{Tg@y{tJ@l!E&~&y-4f=agmhQ#5qykmb2$X1zR30XMYh{Wi4CNW|djs zcgT8_dQxC^1YyhEDr93XBA(GFS!$Z$-lcy zIrG8!VxBldS!cmYwxX?Wv!QJ}d3OZw2gPME`F`*o{A==N74K8$55P6>ZOCj7wgvrU zU-<#D#lT{+sN5g4k*(!{V1MATwQMD`Q^)EyrEEYQQ$nd^HJhE7E0jG~T%i{8#A!-D z16H<`?7kq4Xe0NbXMgZRa3E+U_Y$)&_>rSl@<*tp+!{2L{lI>5Tkwten!3G5t=<>A zf)9eC@_Xd>20sNYWefQe`C7`WlrvXch31G;qKd6-Pf^xsk%QV*v-jG3GOzqD@b4<$ zk@x%H+n|MPF26-b3wa;udBME=gWbU{^zVj>$a~0juf50Sm-*zUK_l4^Z0KudbD*=N ztwI^y?R~a^><*=r-H^P;ek;DAwmmo>DP#}Z9p07rZnmo}AoI&_g66Ur_$~aips{QO zHbU=*!S0}l{17TEf8&455x+sR#Ys_;QgX^1vZ3v1d)O4RCzM=vL0ebb#TJwW+?qWOJLb9OzGWaUEQ|^J9f=!Xz6MV_h2~h&gxnxe+$eyt4#9DFEuA!Yy za^%BnX|ZgSoK+kr^@KfTPulmyDQKtYO?k;=Z`%vriBdY-PWGdqko+F`Y~mR5$L%ru zf>4k<46^Tn?}~TCaZwzZ z+%lJJY%|#Oc9zHh%@lXrWHPC|+xCX1v%hhk(-EKErn9rfEYZ<^Ooe&G?JMj&br?NA+oIIsm^dnmf_Kf2G50T1dBhM=$8@Ub<&dO0+84{s5h zMIY;EkJi*Bl&v8rLt^^aJ@yOo?t#{e=GI6pn^R&lo03}o1ZIb~vQAprirh}-wEM+A zk&~L|uq|vLjch@#=C&nLRLqQ&7a@#!i2XR0Q zvN3cIg6_B9*spDUm){-~KZ*Rd06ee#QTzb@AoAGet{Hmjxo?okM|@tJ&;BHS6!~m^ z_-QmB3|hG6$kcV;qN^^F^_>5nJRO|l?EYj=1*r(9Abif&L8h+z&VEa%HoT5IN$RO! z4QW^G8k++CiT%#jcD39m;9BCY*tO7Q`?0O%YPyd}ujSTpe95jO<+5EFB;ntz43gR; zU^1H&jPc)A1j%hO(Awl+GGafnHC+w&5t?ecRlxw;->wP<+5zAoI}lt6UmlPFwB-5F zeq?L7525OAbdtLApw58S*v3bR<|4^tD6mnqW128Kt}xEDMy? zgtayHapXtIr^#_7cpCaS*k!A^s&1Fv4gbJabydJ!@Uime;7l+U*`EXdCI7fg35}GS z?FY7s+YD89YbkArT?-AhZwAsTP*G9=cfp>w1>CRp0(jB>YV*7Gobmi_gIy0^BsRah zWG@n4M_X*Mm0cyb#cqZ_MmZzpIC&;G8;p}<;rZM~yTRsjo9sq#19=L%0`9ym2>k;7 zVz1h_Z6#OHy^W?y?iqPDI2SyFjz47!O?x z9;K`ivM?q5W(z~tY##LIb$Q%MyUK32YZN zmj+9MtMDbkZ}1|nu)Ai9K)>7E=*i=9yA^h&oggm+=Yt9I*Wd#9Ec`*c9t~$?Iak)5 zk=t!KcUGQ}Wx=wpojWJnx;9`t*A_erKP`7qr_)HDk-x}uvW@!%YVA(RckB*(O1^8~ z0e2u#)D>~R+oI5Qn~TzOyIgL$U186YueCc5wQ?tsKP6Afo%UV3Ay`js76;e(2aAK> z;fsUo@WmW23H;aWaG63pEFS_Nkq?8zJ$qb6E`>WTQ@E61O8364ORjoB z-C&}8P8M@T-E~_G`UCvKI+v4wlnZ>zF1K}%sTIAa;34oK`?y`iKV2M*ZU+N0z>CXdP_F6NHPq%Mi8g6yK80eNeI17v@>P`)82 z*oDw@_BC?7E?<++*ztCee9le;7s40FarPPT86=9kV$QkZ&bk0}@ErW>oZuVwE&HLI zW~YPG?W=Y-;Sc3*`HG!ps|HmlccFd5=5P&zfpUOsNa+oNkK~8)Rr?V%!|p<}PPEV4`INpu&X;5DID14Ub4lG1{>xF>2t5shM!_ICP<}wJUEn19vi(?o zBxis#>`YrNs7kq;f{mQhO~DBJDEOEi0gkkf*@ZzhQd^>-5qQ5GB$t?r@>jXkEHNH` z<*Hgt%o4NMT#^^%o8|)7*qf%6YY8sp=o9&|oM}ISX4&^C{R8>FoNOoAC33NR9(>8Z z2tIFLvh%3_d^t}(VMh}lZO7V0=v-`CP;SehMKD<2FRN3Zg~2k@(zS5Q%$x9^WpbAc zOvZm+i2Ne6&|H?6WOL+O1fR-TcDDVLTFkQVQSSTlJvqfrwr`nbriFV8$|jb|7wrpn zsayh|E63O;z$d7|8|I3<3|>ZWji5T^&NpwFY@!6M8n_b9I1L8y>~0~gmfbC~3vG6{ z*e(K>*u}OPb!Z+m3x>$S@^!SmVXn$6gg%p>%Gvfa=ry~O`n)H1%BgmWeN!%#FMv~t zeUs2sJ4Zfg$ADv~(_QFk7TgsKl|$qkK@IBj8v0&0pUcnWYxZ+!fqj>JJ0-iG%Aw!` zau~>dsPfK$9Z$ibXz6N_bH2Ko&?R?WO&9nA^P9XX7ohDmvkVRI%Gs1V2YkvtX=lr) z?Nhd!`B@&8-Aq?_4>r*XT@P}0G545m=CB-Kq!Vs{QBHz_wElz#fZ8e7l+y1EzL1~G z1@;R$-_8RU*!lJyxs0;zMaN~9ho8k5md)Pc;e>VHUhwXmzupI^d%+VpUDR>kd zj>IAJs2xstGgp6KQQ2Gz1e6UB(wdKiMDwxKZ zdkvfp-zHa3tDe-TmsxK%m>=YN=zuI2d@1*Udt~{bSWq;`=JuJrW`8Eir2duj8mVdb7IX zl#tDRZT6X0Wf^jn4Ys0tn=BC&53;&dgtyAl!PoLD@GB%r5}U=93`)SiBF}XBmH8Te z#Jn239US3bA26HDH}Y$_$$U+oSNOLJz-jP;2jL<(tHKqjD}5Svso>_k-N+)>ag2vm2ZQ);2#jP%Y0xa$yM@0^S0aq?uNfl%m?Ou zGg(fOd(1TX3iu`bBlDrzB2%kbW~ND_W||pbYWRCdz7I~3ljTt}BX~79%D*^b(yAHe zRWJ?w4mI1%0%w`jYKvJTSIaHbYO~pi#?5l4`3U}nc}2bq?t!OMY1OMH9W))BZswa* zYL1x=&NXwu+30$iGcrGTnX|GW_}EO9Q{>0g;XU&<`nP~<+Vv(hH`+`KGblAoI| z-~~8$nOy*YFmjI(#t>@XYU2DyWL8|8MhL9Pea%WY;mDI4TDGc%YGoI~=M zd5M2NKX?h67bI7&m}w?CI#Z~#$ec6zgUl|I%O4bgCsQw*S4=WwlB+YMo;5F$XKwH! zx#tDLv5Cc>&qE!3)rwU;=zja0v#FblIQ`ZVKtA%oOOP$sS}2 zGPoh=A8dx0)b0+KBgjrnq^6oFCL(uCO%0|5C(Tsogn7YCC3Yy1L(EW<#-(;SgB-}` zgwnfbgQ>v@^DK1S407FqdxC-BAUDu;4Y~ybz=3XnYa4V8?sxYD_kx4qp?U$GgWdh^ z-e53vU(nyR3)+Hh$uo>nhMHj}txMx_1v!KCZUo_BW{A5l=pGDlgW>&<@9+A#_CdSg zQBp^kM@>4H*7YT(A9#1rJ{anTxb9&0phqyA)JIM3AQ#&DklGjQ5ZoOMb3S6bg>l5@qM^9JKgvzNx#wiOHgcqQ-LoieYO#$;FM+MCD@NH;Vr`Dn`6PQV5 zRE3RI0aytBfXN!<4IZHM2hDaQx2gQ(DqxD3!X{7y)gSV@97z0j)tz#CxW2)|)S++i zhkkc3{m9if=obukkGSGSE2WB?V(@-S zBGnJ-ulkePFX$gU>V~_%#P?GrOmU+?srrJ7xM8IB4~7Np-J`Cg>8tvvlBNWFC^5r= zp~2m*z3WX}A63efG`-c3po6>H4IzGL;Aj52yO`+WI)hzZ7qFY_3f|+of%m$5!28_2 zV0U+)%WF!ZVK5qo1cQT)u7kTD930#qbaEXDcXplJAn^WR5V||Nf#9HE05~xCg}!y% zJQ+Mo=&9hz1pLKZF;53q%w_N?_}JjGxdc899~WFQ7s0XcXM$hN1@NNz6&wd2A6zi! z!Drx)(P|HX>4L1mm|%Qx-aJY8F))3QE*JwoX~vigLHb}c>F3Sp;0gE>#Edadn2bS& zU^MuI8ErBJ8G{F??SMcad!C8S^X4je)%*tjX0CzP%=HO$qp%nP9d=o1+Ql?PyB^PB71!O6D0e4jgAnn<;2m5lsfC zM3bUS{I^MjClelRMiI^&WD2H6Q=%2oRA_nh0`wL*75+S_lcI^>^I(=BbMPW*%c2)a ze=B;4(3{|k@RtcK1z&8XQRQ;c<_FB-zZIxHt35?zi0??1b!`--4$=eB2;y}{m5uc$up4Wc_a>IL?SdPWDxGY{Mk|0)_0 zJqkXG)~}$iqlYQ^N$|;NOmr7HdV)Qp9?_Rbeii*d&bizCFZv1DIpCaV zcJxIwk{n+^d!iPk-3vB{e;z$f%IDA*(LrQqM=eRa2W$cVEE+}nXVB--{xDT=M{pqA zA9}nas2?2&>qqsXR>YQCV|{8k9AMqeI|9YEqW}Ue0_^-o4>ZVV$UU^bu^Ylo)cRX+BRn@6@1KH&_^cJggE`29LqFlJm=OE4jZ4SCe-Q zm^4Td)2Lph>i@Bi;-NS7i%4;ARBtJM}I^gM!Tcy;2+>e z@ZZ7f;Ky(g`-4;w+a2wSR-kibxC2dJfM0~4hu4t#J-QZs0+%rn+Xe25K8UiSIU86J z{#(?J>-0D1Q}7d{eEx#a(ouP3w;`z*n82=$iy`K3TLQ2*d9$+psP`4 za%BNO2;UDEQtl$XPzQkt7HS&=!A|mj67EFPr(qD=8NC|?F$2$pd}eT0_(Av{5+8#* z;WqYe^iE`B0X!qAnZVuQu5do-AA=u;FjU+}zhJSPgEDkrM6^}$ziWCu*h6_S63P`yE zUWqP87VhzKbSe5HERDqVFeS3r3I7o~VlPIH^h?q2#9t484^u@cqmbBNK?i@G8or@l z*DkQZ>o^T|!A!kChrzWlb#zB`4f)^0YvCPHswg7Q1u%rq(le2nrBejS!7xY>#7Mai z#h~-iZ{)oeCL#1ol!UnR(bX_blp0J;+H5^bCl9WKX`?jJ72>akNs&7jB}Mj^=r!u_ zy1pEyi_%7yk+~Ai(aXcPz!l+gFj=qyoQ;M#P_p1sm_AAuT|)kHc#+mfA6*Q0!!Htl zDV(d9g>Qmyh0DM>@Z7Pp(U~Y$>|AsfOiH=Ah{+wxNjMjnjC$mWorz9^x#3kz6boZj zOe_|GAuW{ynVhj4vE)&*C~xd^bPCJ^&rVE^SoT|~fC z${#x!odEN}=jk`YrQtk17d}rf4VQ#jW2eHC;OX!bcrwfuD-b&o9ghmc^1}=;u~^Yqy;#~0iIGCxKhn#C(|0*`opkVY?@xcop2h*3&O$3mW&OCO2mf1OT<cG+hm>MtQ4PtMp1eGI%Wb82L~1$GSzVdF*4|GS(vYx&BPoG@nB?%p`qZ?B3WU{R;deT_V;J z97@eTLh@t%ksd+~ztErS8s-aK-Bbf>nCfN)npf%-`te|7Fj?Od>lT}=?~UC9PJ-{z zU+8M)OZ0rCztqEGLt|g+2V%ow%aLE9m+Mi%*(OqIwb>~a^-F}m)8E3s z)8FWq;om^tYF2KWJjSo!_L#@yHZ@r(;W4+#WvY?t*M4U=anku;gX%%piA z#kovvD5t4Hyx++-qse60x!vRdYs1;6-ed$bB2ic5FxgFAcJ|9*@XKs6fEh?*H%61q z)FVB+VgGuQ9!yVKeUZ&%HT6l)X7JT)(t+tnD^Hm9>L#rzFUrB$UBGz%%c)Ho_#MXY zs(gn@4L|69ax2t9Xu0|k{K@_3R;m^1kUQv>gUi)h>IY(ebU(ONYNa~t4!O6$x70F~ z%G_aCyAG8WKfA+jnL2>X5AJ|ltyZc1-~qSatx>C0N>iG34k=A4_&#FxyM69WwMOj) z_qn}psd`hTFr`FEk;0^ee^1O__q|)9ma60?g<+Qh2%lo6geVRshkr-v_pY5OE{chE zCK-IOTB5#l-@3(Md*j#lwKv5?QLr8SZqwcr0sZ>fMQXA7)-8g*aUIOvrm*M$6%q^8 zBK3`12z~83nhvIr=m-@QGu1-%wVMfjXbw*Qm(H_lrtM=-&JLTG|Gw!tOqB;}bPJQUkxOT*}SA$e1)6oo4olPgO zt?3MQGzG;V)d=rBgH&VD2y7x6g9SwsF^6*YxH;+z_c^%7ec{@ot(|JCK5`!t{@8uw zx>80C(N%SU&sB5O=WZ_anQMmbhg37u7TyNQw%{l3W7kb}RXN0iq&%eNsk!Pi*W5HS z52|~J%_;6t-QcZ}Y@=GMPu(Z(0o9z;7N)s*Kn;UGpjw(1W|+EHc|SY%k}s!dg{IG3 zE9g`3Q`cGzMQWI8Wm=k{DmPNOL`!5^sg`O!{62E~71!MfxrmBFb zt9pUG$WuVnQ*{Z~SM^i_RiBU|M`NR)Muu#`q>YdV9yD8Vs(5Zy|N9+u~ZAR%V5}Up=f=xaIK8#B6b!T^rNdtaK~f z!)g=Z&2E#s%d|0-RVDSKt_=O4%TR~1s*KvKHxb^X-_e$uHo+LIiE6A?k@FF7C43`! zH@S`OPIH%8?H*CX)oQm2UPV<_Kjl1TWM8Fy{)(CP&?g7g-}Da4*B)& zE%HCA-g0Z;5$O%VhO}8pwN<~ZOOmUUs-~){qq-V&T3;cpfVhHG1LeXO)l15PF0|nb z>O~cVQ`HOL3&e(@3tv(p^s=gsj?=n2bV`>%b4gV~ZPQx`Z`a$j38$#3%8)k*qwr<* zs*1?{vKky-(O315@T&d|{7qj22Xj;?d|HiFg~PFG99Rf`e|TA6(f1=iI2;-d39spb z;bZD)RS?NSVUe(KI8GITo>7{zOsKSv<^Mc^{xRZNF&=Hj)egN~7w4>&P&GK~r*sW63Z_ zQtRAk5g21elj{jFAUvxt>H(BHFnlmfVq)gO@Bw%}O3xqW3m;b_RdH%D8Jw&pshEC+ zyHV0`x|#+ify?kYH36JJZAJ-e0y7Hzqs4P#0%fH{KBgZR&RFv}siVY1Qr5YLC@p3l zf+EwOIt&Q=hv)QJy@>1aQMCvf0gg~lsl4GR^*H#r$`_Uhi-(g`3FvwCJet-?I!`!S zjZ%3iC2v@g5}sEjp^2&{=kJ6rrZ(yw;115|WHAXni`^pklv)fuss3;iDRqjNOnh>k zjB=AxVhWvHC#N2L(cdq8Bz!mw%_EQlof#=gQQJRUDN38Da#MPqFn9Qb8m+Dq_lN5f zp4Y$VKIH8i4i6s_BgF7e#eb+7POeF40H#u4G8Vz>a|Wy3OP$w7{s;Wby5@F0Cm-=hcVuv0 zGddNy$f@rLQ-vLfJEQyQI;ytnhh%@>oVqOkKPSg!!?)dFald%m4H1LEp<)O)Obi7d5W~O+#RK3&;z96X@eufk zco-Zm9s%zcQ$;rPXV=+u+AvL+OaJDsx?DOZdrQ$ab^I0ll~&2B(}iil zv|%=#TVHioTyC8U-dpEVIaP1|V;`MHpL1tj8vh@49^|uv>BDs4WVB5IyXek(dN?iY z6;6kGhIvWNqx0$vVfwJF?hD@5Sv9`ahF{d%Dm#L5?@AtsCKJN z;fGMhuo^K{b#>h>>>5@lTutXAJ!6jZUk7 zap&9zXxODbP+7w)VOQNnPYN^Z%kGlP%s;s7dU2L|>s~sy%BAY+?%{o5T}r8^E9jBo zV_^l|F&qh&hrf@857hfATbPw__ApzRPM>$bxO9|~RzHvKNns{^$z61rbY^&ZeZidv z&m&P0eUF6|p%Gyn-6QM{cBiB|dItZY4*#Y{m{Dia7hOi^SNERE5oQnHqm=hm2K1!Y z8FWVdtIGggaNTrQ%Iis;d+DA!kIJnkhTVv%q(_9qMI}94yz44a=7?}7dfrnz)iU>{ z+etsm5!R-}I=Z%=8O{iwBiF>Ro$jWe3oGkNv`1y=9rrHsJJq{tpsoqNI5WIY+$$Ekd!TzocX1!QTf%VH;diYM|$abHWBl*3hkW8$CX34LuV!B))-esON=q!&ds4a2(hgUP_nN z+g&NW&20s@yKU|x)nD`zAE^PNKR8ef0Q*s&M&xa%8|lZxd0|UEE*uNCf;T3nk#4L< zg`~KaqJ@~}T8WlmYtag9BU*!PMH{f4XbZL%?ZCT5d$5DJ8|)}LfSp7~(L#?6pAK8- zmhdKebT|qeMH$U?3;lH19C|8js-Fl)gQH1nM#@uRGw8|iPU4&DJN20GiSRB`o&?7b zdl#WGVM$#|Z*?E5L1LizSTz-cz=8a?PY8bu-YJ@jPt;xFPOzD{OO((hkuL%5be|IQ ziTYGE7tO?{s)cASit7@3rz@^^yItT;x7&TD=D8N)Gd17MBisVHV!F8A<%&TcxVyqT z!@1yG_lEl%na|YcYJrSgm!Mos1 zh-n%&51WOryKl(*xhkOZ>-St^;+uqx!}r`A!Uc$F5x#~*3*=rS+#LS3Y8kc&zb5V* zRZuq$8-)dR0eGvhC9w@TY7~B@S`jX!3+jepgRl_Tn)I*Km#Q^bSQpX_!ZyTxsp^M? z3GY#DIo_k%5K}}K*7d_8P`$7&yk6KYY)je~svTHV7twXY_QZXm>V!oJf2;21_*>PU znCEp-T_=1VsvS<$&ufph!&>2YszZ1;csFv->4~~l_#9L-{9aWEJAfTX8>gSsHN$aG zjc_mV->bcP@?2|Zf>q>id5z$4&Ma160i+>?5Yp6aGJk7M)^ zHPszaKdZ^aPjQpoQ~F8$g8Nw=Rxh}z@JYl>c9Y!G`YHXQd%+!6FG7dZ^TbSY&%06j zY5kIW(H&ARK?ju-7pa33m#B?j-9Jo+&`>=Q$>-ff_qZOVUv>x8G4-;03I2*ZrjCOz z!=EE{qI=Gb)Q{^4;B#(*dq9uW)7)`&LQQk8z@H^%f_v6Is2|YN-3fI;O?T7aueuBB zJUAUb-aVur)Z>wP);;4M)(`1th#Bu@xL4hIH3RxZjU)aUH_knxAJ#KT`9;ly&Z)7) zjB{h%aQ%p$DgKf7EO1#}QVzcbL$!m3Xe~~ulS&isJrSH%rwE@^mzBlG zzz}Vr!Qf+h1UOhfri~cs9&<)K?nZ*6+~eSB@)$AO%_2O)%?4+=v&x7w>NI#(odF+n zBU~UxyHVg1ZZtT?Jpn%H#(+<`C&8!PQ{Y(lG-$;L9f;w2Ea6dT48)^)I58viqg)>` zQAib1F;Q3*2H(6lo~_;5^&3Pxcg^gs|HQBY-I{eKl%MdAej9{?G}V$qv1t%hJj z_K)nX8ZhqJTh$j?&9CYT?S7T-nHgN0_fy6(-U!<>22_(2w7F@0@HpWgaw56w&s1Vc^`*) zh40&b2g`i7+l#UG6pY^g*=vyBC+c>4WoBk3(aV$f_jJ2|6{O!4qCaV7F}!c<|9t=Q zcfVWjia8SQg#OOx?}s`5_I~JhtWLZu`kjO0JAKCY0QG*7|J+{w-hZRj{_LCU#+}f6 zZ?2Nyo6Fx16TNb!CG0(R-MA~>?4j#F=9}xE?uWPD3BC7Ze}BC7e(3Lhx84<9!ky6H z1OLu9mw!?wwv=xp-(G(2PxHT8&EF6GJ@C(WMSmQ>JLZGm><`xK@OM(*=3YyDFHt7z zxf*;)-utV+AIED{i2HTCUVe7W-?`)ez~90B44S{QhY9z4f7kajZvGh%|L3uUCxbsL z@m<3GES|p;B~5sq__OHe{!)N`wVR(S^t+z;b+CRG((h#M*H`=5N$*WE{=`a^@J#c2 zqQ^a}Ris6|-?h{Ut?S#kazfktC!v2frcJmS{59d9liu5%-!aMi9`;w0-?`TBdL6$b zct3ak9^tPtfBj{`e@xAU>(bBP`d!vDbIrz|<+V8W&-JWa-|^?Xf8P6Nzu)oFzZdv7 zf_TsHZw7uQ*1s|McL)EL;@>24CA?qww+#RGlGtA56WXgB|4%`ZmMY7C*N|_oG8`Gm zw^wP70?4;l>4f$w$@#QUXsu@M(cQQh5q^NuT8(>rhk$bg(n4l zdljaglR`ylufhrKRhUq6u8P96PoaeNDhN->)#BT$06Y~}Q~|I6$9Hf&<_Gh0oSLwI z6KM!f1Nt7>0G<}~UY6>^(}BJR`@O)^gWexiU3do0X&tZ*M;RdBYPA#Es}?*H1<=0#@NDC*d5lOyz`@ zsszu?_2l3FD#G)CzP&2IJJB`*6i9Z4d(27RE^v>2m-DW0kJ%}!1C*8T{tjS!cvi*( zvQn#d9A)L(x*g$e$Yuk*bPJ9%gU#U`iR-}Vg5P`Hk2Pdwj3E>M-H$kAVx%D>=fsaY zWMsS{182#PK4f6jp$*}5@brAawa+HQy;)X~yhU$Zj;J$~Xrk!hn4T!5x+tlJX75om)er-a&B~o$T ztAoA`QgNkJ1^szX$#ql(tN^9}%fo%&P64LidaDE_11rMI5=xrT6OtzM0q^~^G%^1A z^;fgM!}z;EGB6p^{;rfH;qH`#UR0SFe}{@C^a$@&wFDvGQ~aB1Nkaa*_dc`zJIkH^i0sYb6a|5n^lW?ES2lw}F1^PR0F1W%= z&^oT5_0T%}1FeN`NH|{2krb=&JSD|SxD+ek5)UPN$-NKSi*KOs;rkPgzXkK*)#y9; za^wntE8yP{mk+NbzRUyAe!QnG=jaFM0G_12A@#?E9B zWighRrx|OQ$b8W>&ZYo;+Bjmy>gmKx!wZqZv(QBR5oj?<`nH%v=z07cOoUH>YcZMl zNm9s{sK+1tQI9X{&0-4ilkp!h0U1duAYa7l=eqcVdR~XN2qj;@GDs0G1|7o2$a~z&f_!FUFOanQQR%sx|G5%B^ z&te{*Va%x{>zne5m#D*wcrzI%X9z1NW5Z=BE0AT(r+D2fV?M)MUKwPY7PGH8e5t0pMU8KhAy3n&atvQOnEN=yM6g#Om z@C2BhnrAakPQv=kQLdH6S;>`Gyi9#w!gJUJv^18_GA~*OP0#8&&;(u1e2mY)a+Fxs zG$FOIY$C@qPg`3~U^K3_tOH-8-w|^}F;g6E#h^T*sQCz=fknw%&a5SMjb5vF;FT+f zc^z+jIjB!|vzmN!#A;|RmSkzoyWqR{2Mgt^Ski^m)3I(ipnmJfyA~VBtF+5Hy%c3t>q=}1=Y#Xb0#U?#h&RF_ z)U&9GC^2Nkb0A)kd9iQXDe^+^VUPAYbp6528 zc|F#E3-A!Q0;|IXqOjSGXTrkhFTz+$Uh|&F2fZ(5VAUD1N;?qK@U}IBa1B{gj?p!s zCv+jR3!j9A$XnQKME?fnGcV%FFF!io2j9m#-*WvLby}`-nq1%tjtY{i5Gx2jz|&v> zlOJAyn1ZG{x}U(-WoBaa8j~}jB(gW&&}K0gF_!DF58>Y64EShW zoxHs`o+WxgvzetBEBk;?bJbSEv(G)Xzm?N3Z{BKXBW;2uUwCoE$g_oc{dMuU& zeZfA=bv}iKLSOwfb_YwT$tLV&FW^tHw{D6*y54#mRtCNGGqhiC<~hfSWsHR7GRvUc zrk{QitA&1O=&O5B(qp0rrHx>|;wjk=d=lS9z4V=U!0V-Z!~5$o;z`k;T>Y>wpQ)3` zSx{2hotz_?@96;_K(7Aa82luS(pC9CqjWX?QBQpr-uZem!*-V(pr61JVgTCuW80e> zJ3(*Zo7*hW=kXA^g!(Vl_n~hj^GPGczfbJ+#W19%5|0$)u7(KCQK<&4{>OS~l{R^He7gO#MW~WDq z(P9wV1`@s(na-5r-@QiTDQXV(@W;e`=xZtOgIdW7tX|{24a&`E^u6S~U*Ch?Mfx1x zEf=AAF(bQ`8Cx7leID1H@CG$nc0yZcF&ACO!8!1S$on-EXYqhJSa%cmfcKzr2y<4g zJiICxx~VAQn|K3N~5l#y5rr7=m(X3l6D^9I@$>NoTmykRCI zE~)8&20uGAQa!VA!&a=t!+55)P{sGs2NZ8)*b@DVgz`nR}8!AIo?c`x-D%)D4v z-WHpa+6;Uc4??f&(|Emn9sO_UyV2=qpB|GVK1y;Yb_i+`5W;buQ9#iyByC=Mo+CKw=D1ZF%E2;DbnY z&>DX9#uycuy`axnIAf=;jDm3vJkh!L!8ur$?L?==@>S0(Ubka>oY0BHT#9K>M zY_fBS&ZKl=-r8HsR?yzAwu1K7xE1sc;>v4p+go0z#)_#tQg@ifLg4$QF&dhPipW%8 z26`)2UKOG3;CAB5X>V&(j`{Q?rV^5t%aD+t`#L6q*LYd(ditq#tSjolt#o4ZmJhu#()Vt3Z{R zuk}_*rOEBgS#>{l8fVpD>@?1*A=qi0VMfH`P^>l1sLt36oKanvZ$G1kaYlZVRXH=i zNxwql8b}EJ_4&f^zQ}$j<{B&AE1N2K()ms166e$)tU=DHhnOurM_Ff?_vp%e`)Sn; z+m_SJe{|K?k^h|)>Xl4oJOo`O*A*xyUoyX0|2=aRUuu`}8kAG~fy{OJhdi$k3^49RXJBxbXBZL-($wtn(JU`cn#$Jch@C+`gvQ^s#>Xw*vTmJk{{nsImLNO z{Ds*nZ_{!T`<-_BB=bh?bxm^l@9B$pqSNXcwr85WN?pK{R8GF`F4~&HC~xU!NY&~* zUZrx1YS@ETWfu857ON#8Vf-BQb$vm3Yncm_a-P|0YPs<$QG(O&P zh%#H-oGCZR%_Bm2j2XufP{gZLtEXBUY1Z6~0(9;NkD0Dv1TxMdim{ zF7l6lWsdQF_puC04_i^h)ZpQLQC) z4c<`F;XUImyav@3n~@9g4Y38j3dxmVz}!|1{e|8Q?&d%G`Fd?WC#Hs8hDW2iVi{CV ztj3<#nAOT)0l1o6tMECo8Eu=O!*UI&tJNA+oV;(!ihNtYDgBrCo6>((zbWhS4gDsb zo$86T$gEM@$#)n(4Tt5=c*63dQcLkhRhk(}Kh|_f`LU);oQI3d{~lAVnfq<6o9cDs zU90ZosHt8e{kYZ=a+ks8V!QfT?tqTSchnB$@d&=&7USuwtXK?{6YI&l4*Qc&^rzUL ze5zT+0Hpc;GAG?kOuD`v+=aD zPR@qb%X!4i#e+*~m&VNs*5fy37Cu(i%Ma0a3_OM(y+zceoY;V+!+JFz$$9vTxdRU; zGx4UfLC%CW%H8TibsRj7&%WL21Rekv1ePbn0wm`L{p1hWf%ldDq{joSW|HbLell|q7`Uky&5;v#;g!|)X&f81(Ms^>#Pw&;QpnpMdnR9-L z`CdPUaas8>y(66CyO>w^wjoE9w;VY_JKTw-)^2rDzKZXgP2eWH1`R~#0PvvxN%z7B z_g-)>>tAw9Z;zS>%q{asZxx(Jp24~}m&`3sg5G8|FEM#!UU`;T)_h=InNNBf(VX&x zJ_P214?^=me9;}(2X#;Rz5WvH1usgAtx(g0&3H_jj<=)DGKV~*59=KA|6%W}1FfjG zKR$b(3A!(FxxnQTm+lVfZUjNP6%;HaY(+#A6Hze$5fxEV!UVAcFc3vl3=|8MXFQ+% z`>a`>cjt1ra1k(mk3aU>d-m*^IcHCPSA17l>U1NXpXuzaB204lB_cn?FL8`H$!tSP zq)-{>d3?^waPN!OZIAiFlyP3*-&HbQ@XxHo9@62zPBnPm<5O0~S>-iCOY{J8mG^+x z5Ixf^-gJtIVD&naW0dfJ(FP zkB}e5cE=v{L`(Fbx5}%7tb=}Njdw3s%o=YA*UTFBx!QXiPRlCJ9$V`zhOKZd`&r|af@6GltQ6(rSQXO=&!j5+hRSBQ6)8s8`~FvdRjx*9LPp<#Dsly9Z{(b?kGkm*$uAH^)HS!0LXMnTY&2_DL*-Uw9VnQY@AA)BG*SR(P0|^#3iy_{2HYIL|9>s$bS`9b4($4U^+ae#tsGiF{|S_o(-n_k&I1=q3Fm z|FzhrSdzaZ_FAkY$C(JP{X{tNs_}cO!i1d49`1p+>v3}r<#tn)kxBm39H$K2)jMKE z{bK%`u^q9}jBA4|L;VOx_`xQ#r?X+wKO6qa75s*k-U{z7cp;1XBl*9@*{T>k*V~Eh zTI}6!=E2u@4|OTHm)pcju-zo{FpP^o5a01I@^i0itX*u6CmvyYygsq6$gZ)^;gwxv z?lQ~S^9rv7doB(a_6Rf5e8I>)-WQ(ud3^)3ZM)dL-aIqk-0Ll-{?glRd&jr)fkC=W><7lRN4Af3Kz_s03R@Mgq7`@^t+WrpvH7E2=G|!)nPnVzIZT{CcpYM2 zv9~Y1WR6<`mhItYgjwRvhZ%4Q{Dbq&Qg5NT6L}}we9!2PvG3Wg1F~bR8l0`wOm%ag zx4_(iTta=ncZXSsT*x-}!{d1e46?iJS1{3jgs)B!_MZ&1_b@XY-q!EE>d5M*27Iv} z*}d?&)_|G+J9uDgn6JGL@#OiM{(pIe{h?+UJl?}h5x>0O7H`?|aBjDaee2aUwP11m zj(RyhSyf}p`M)ddXKed5Jp2#we>YNovZbA;Ipd}AIeXd`VsC~0LjDl)Tm0zNGI^2T zQV0GdGuh-o2CzOCC(}X>vN23DJ}lOgk(137lau}&ur?PXSA*yGH76i_e+qJn=?mZX z5K{>D@4;q>$;FtQ@FEu_vxDoOVEQ3F>I(dWvat#je1Bo5&1-(5>%3E0dx{+ikKHxiNIQ!9ew&W3-~IfmrS?hhXZt4d3F;B{ z8ralEF!ma+DqQI0VpS>SWA`!sej)%X;$1l0UJVD^aK>Kk-AT`VwhBDt>~QM4Si8tx#?mbBZrXPdA67nAA@-E_r1z$Min7C& z3jHrjId9nQw71(W$d@?dL+voOyod33+ZoIVS9T-V&Sc zSMrzGO0b(RVXJ%XGi>n|QoIR2@ZQBo@B=xDw~&!bY^`95oos6clkFsAE$SMus!l>m zY+h|5rlugLFs^!VwtdA`hg0`#TZjJIa4Vietk$#MGv3?CxA7p{#r{9=UhecY*(xwaZ?&5k@h);Rb!FDPW*Y<-5Vz8R@%4ij$pP`MeUb8^SIs-! zo?#mX5 z%W5#bx>tp$F@6Ga zfE{R`2;+2LWM4SfBtEBUFpbg--n9l^LzvkbGVV&-3^v6p?KJAM zz51*8WoncD_rIDAjbeWxDOCw9O z&2*xtN;;Pkr&Q9Z>8JY(i5shlyv;Tsd&X_FZzYzi0j=9@J#z8fZtIhOXCCd_ZQ)pL zG8Yw&)gfC^5!!``9Fc4%FLRc5dM{Jn^pfb2*ouZ^3rUJKB5O~fSUt9v7@E4Y>qRrYG+&GstW%x~&TJVrBQ-q_Xl z8k;wEjlC9`kEP~*Gd~$Ngp1*$xPUSZISp>Q3n=G%C1cH5TQb(xZ|>(|>uYTu%5})= z?DcjsJOvlS$}kyuA>{((dDQ13FZ5E_O5##l`($5=wIPdB?%4Hqw#^-zO{8S*SRR(n zVeEylS)7BMLVclED%Q$x?U!P!lvu9V4Mbw*ip?P^GgmA(OWpkTWVGr=>4@y;cS3gZ zJNr2qd!x-sxycUjk0X!K@yG$lcGM@*YJqIwwz9f3qTSO^jrE}&uy6bp=;`HmLG~tpNFUY>r2JwB`M(hNEID3&v4j0V{;&3A%5TWQ z)F+V#=Qlfs;>5=ICsD8WpM-CJJ>@Z2`JbdU+8^UPv5hRP_eaq(u~GCnv5_p9*a(V6 zj-(#WJvi2Tkjx4j$dj;vdbmHrx3NdU-zbytxrQv@fDeLr$Z2 zI(?TQrT1Lwi{J>KPHVe4$vYV?#ybgllD8f1`B`dauCvJrF5Or|+8K-U#FfM!XDT`2e`tg(dYRmV`z1 zCFB-(+WW)9x+RpGVU9lm{`-C~C~tzXzE4orOY`~!X`ZmZr+MYbY;rtxU;6uyS0U9a z>-7rCdF7G4sZXG%FF6^?c+}pD@aXqtKPPzo=sAJBDdoKiUeBNxb&sHeR}tBhx{vn) zjQo8V-`DFNRD`XzJGojadfg_fAPd+bj(!DZBpE_{*1^t7-=?}|j;G77vXy6Qh7c_7N!U!5TgJ1*=oHEQ*0rrp| zmb-RA`=AL&=t&-ho?b6xFRv4Fqv?Ts9~Sf`-UqO+H}Q7C;@-sj5Qgo7UYnq8P|#}| zv_rOIUxmEZL7Siu{q(}(-UQi%{j{-z;WBNDY-8Knz!@C0U~OBkwH*=+4O$cDIV5OD zKhc`(p^(>#=+L1-E6T8-J^k%$JNWt8BhjS8f|iu#K?nNV6SW>V9c&AtdYcC=D8~hz ztoY(|qQ4{2=|rdp$5C1Yovrxp5GBvL=C(!9GH5RAgEr)4XiheY=42jdLuui)rWV

2WUHWc@F;5^ zfs?$MZ52EO%X*Uc5Tz)xDD0^Zxy9g0eF)yvyxwDsc@)<1rmzLv!xL#8`736!|7$3d z{Ppxd=B{@e!*H+Yr-#3z^Mg`K>^lP zw@)(i3HM329&8aWv4{J}PIMoc1zw^o^`D~uNw~c0*t+&9w=O&m%UHA2f0~}B-~_J? zd%`nr0jD;ywtd>&!rEp27Rqwua&mcWp{yiN%NArAJC(cxsr-W}$f+!++9_loC=J8% zImmO!;8WJl;=h$;OsajBJwM~7(Nor@*(=FKQp%RL6Om_;TdEYTv-}iW%AScFM{c7O zTI2k3j7+oT>=oo6d5%3i>z1@B_7uOoy_WnV<>@bHAEf^|w}QQn%peu)_2k;9z}oUQ znQ^E3$+jf*lpuhWZgSwm-8VUyLOqq9DZ$hr2RwC?0?%`ilc_7RhYGf$y_u{TCD_NQ z$WzJ9bavo+F_^0-QJ)j!fkE*cww(&6&m!_We2ClykI!9XdH686o6Hm&0$~Y$9Jzs5 z$sb@3{)qk$;Rf0j-06QnS?I41zIXox_r?b5jf{Dmc*-AP8=e@P9mHVLj=|%5F2_12 zc%SVS`tMWj@OKAm$)mBGy?q30$G_aK;p$jV{RG=?BtrBj*no@M@nn)JZc9+7^It03 zbbAw-P(CIn(OTqMwttVk-r>JTS>Qj(R!hpr!utc86 zFF7~Z%-LT>CaP8B4BAXt?Z3;O79bap)#VfR|1nHFtI2}&2z&VkR*y%ipJLBX22TaX zvoN)P15fgol<$z=!Jqsk0aoCLH6x zxMxy+bzfqOoZe2jk#6yKQf~D><=3r7uI6_<9XN1ZKFtxIf>-2`;2XF@zTrq0u%GjT zGlDaNU)?h(zqv*2Y2@cB3LpMyer1kW$yT;ElAmP@d(Y)<;W#W6~yn54=X3I9HzsFS-{IclILL6D|tA zg6ZQ+_bYcT+%R9k3&RqlzJTj#M=;NSlQQ3bfjvDB_sUvEjHmqqobI#z8~pR!3DoDp z0e=JX2C~U~#kOC<@Un)HFSr*I*Y*M#94>~t{akmBe-7nFe=1z>B5!1tr@EDG6+4=} zOmN4zbN$io%kCw_!M)7Zmykzdu0O_|;!bs|!029u*tV1DImw;uR)wQsvRlpOL{4Gp z6?YnObFZ-VG%|tA^-p$R=8}Wy?QcrSo+FY=#Po{p=y%dh|SKU{r-*sPvyJ;??=K6CfW8Hbk z+k<(*eDV|Rbl-J11v@GC2JbOjFCbrJoA=xoi1vNYJvA6l){lGP)p*C%Q$Sf$QRJa(OHXK49eg?g#ET*!ItMbJ^VXYL4 zT!tcFhI?v{yBuzkw>ZiN?py9ySo=G{j`vEioBloSZg&|m^1|x!N+1kJB42^w>Ld3< zcPVlyarYlFW;g6nUEEiL<0)H%wj8AmjE-A^muSD}ZwWqkR|G4OE1CVz$&s)k=R+XD7jt=&6W=RbbC<&`H#m{iYWE)GHSXP% zYmxU*f9zlDUgv&-{Mi4*zl+{a{JUBEDeX`EPyI#iUG8rGI`?|y$J8JB*SoWkyQx28 z?Wg`{{+;e3_e1|9e>QTqdzJe+J)ilX`wQJWU5Nu&gIwdTbxSxG@oP#r7xQ~|`5*dM zxw|N{+&zr^+~4Cbb{D!|AouuR`1iVt-4Fa-{w(AyxbENguXHa#en9;tYrpWn^p}u1 z>^=W|{}SXSF#CjJ7ig%?tVl6*JN&7PA0Lp{ma}L$aknE;$bavt-H=G z?p)|zguICVCXo{B+#=3>?)}L7-KEHN?tN}C=K?Ym6mw?6-e1hQf;a6}goRs7Yj4-G8EOnEdZ~Sj*e@m{{B$k)avy7~065H{*UzG9& z@(pr^7In7!ZzA6$^Jh_K2U%To`F!z8UQd7$~j$^Rci~oKq{`nSZSuPt!PL!ob zVsXSvJuUPlOrup64^F|u7gj0=D6<-R$E!8R2@TibGtp=q!-Ys%v*QC_I z$3?D&TH(2`MXM%$KXT4$Q)=ODkVLC4^PYs1`L9c>4!$zQXw?s+cIwlvhj&YHmK%gI zJq^PspN6y>;G-btr4gkezBm#a)HsYEYD}w97+chsxr;GF5+@cguQE%9rGVM>nMIjv z?Qxi6nQfVQ!yHR&gv`Ipyv(-Dzs$UBCG&rvIhT2k&%DgD%zTA#&SmBWIadm2TjpP8 zUS?b7UuIrrTjpP8US?b7UuIrrTjpP8US?b7UuIrrTjpP8US?b7UuItJH<|x^=Uiqx zKJz-~MZ-Cl7^#ez7vCd^pprS4nU~0_hT&|>{Oim&WR9bAo^ou?kInh9>-^ZWC48zM zd$#;J&+`MlL+kzi4wWalyies#8hxJ2lU$$b`Xrb4sk}+W&MxoMWAD)YzeE2ibFN=3 z^6e7+V$A%lC|`;C#aMx_l>L9V$QO%zF;@Hwzgx1J^XPX=R@b?FCC0y7;m0mmiYLsvCB7BJpI#L{@$Vk4)4>afUWY3I=ZaMaB$-a&&t8c~V^E|6L zKZc3^*?L9M?24XOw7vmF^t_@2#vPJnkG9YEYhLQ&e68l?o7FHTnNkwOD_2Dd-$*5p z@~u>cUWuPerY_6q5`0URWUOe`g*TxrJ>@8(T`$iUWJQ+B^9>_pFD>_IEZL zANU21XZZvo|Bpus=l2Qx+y2NJ)F;r}7iNWSAp=-9S_A1n0cNjs=3)?~8dA8L26HBa zPpmxiJeb)og{(k5ly&8iZ2#4@u&%g(G2zg)$LvM>jg`YPu0l#q6_H)J zf`rwoH?lWZ$Mw|5JHoG33|Wl*O0E*=NuzHzt$xUUTv4+rY0eF7bse$~^&IM+$Uf9_ zX!USzbZ+8WyO}GjFR~j~+s%{{kTKJW46#80z`ltEtFTm~ZajI;x9YNPQ=DU8GpK?xa-*S&wmd zvi1&GiW+dWEu!4z+|7O704a>bche_54XE$oYH5gsAqm-#-g~(YPerCsFQMEAkCn9U z=c+mdc@|gF{gm;}Qm&#F$QE3QOSv|i!Kl@UD`*+di$=)FTv^MJD_}*tlq+B*Wh!zq zy(?)=hDGf{u89Y@iY`H367sOEqGvT%T?eGF6s+coIS;P3^J%R`u0dW-y^gIOfZ1&t z^@EgkFuhHq^)Qw%WqRvK`!f0-<_f$F*^&BTmLGyiO`hS8girNHc&dA}JJ9zC$LIi` zn#WW9QInXXB!s57|@-UoZqW9Q9xe_+84akjLwKI`dQg7s% zd;&R>`bpMbiIfpfQl5aL>KS;mo`U`98RRVLr?~oN!Qb>e*WPoCcpk2$+4R1^wK^Lq z`Fmbq&2`8ps9#|Ddbpgf;i`O*as%=P)^6e&?T+lu6Lk~UY!757uER}~o8Y3FLu(6i zGkjYoa)rLc)q5gxE?i$Pu{;;~G7Mp_QeK8}Oj=th)nJXQ!PwVW{|fRIdS9bRe>L7u zuTiQa2eSS(S~Z+)T=7GZLwT-lqYOdbLfhuV-UdJ3Ewr|Cy}yYZL%k#9*W1A} zbPVm2sCUrX?!3i4kcv#DPZ;|aAm5>Wi{%~2oh-cz2VW^;#k!M`ABAI1X8mq>*gi&n%w4gYyW%e7J=D8tjdebyq#!?swdhk? zpCdnE-KUhXun2uh{}(Uw+Fw(D zLu(vz9BaPinSVO+bndZlc^909ypKEaTgn8Otzd_OZ|ghc_wa-L2i`GZ3;U60`}fXI zyqjAgf28LpTE`*V()SasACXg8`k6a*3UVsTKQrzJTmtce-dJj8wKvLtPI z8Icci|GMU3?oE&0)yUOy|CvX*_dN56+<(S1+>NaDOkjN4IZRHo9=V=-Fb5oGIZY1s z;39Lgl*a^UC2Z-5wnRqw}{!oJzIoG;VsC`+{H!AO}ul8m>YTb6k)5v#3~QsUQ9BT_~J=2qGwMs zuW}bBnYp}=lFZB8-ASezcXLtL*hV6UbN>}JBX~y@H6!`LDQa%vo-9UGwa9JUr^U?c z+^5ADUzFJF+jvJ6W8Le>Tbn$hQl;R#troT8b z{>9Ba+Vi+Olg)eFmnF^n+@C4tL+-~E_yeT<5%*<^d6zpfg=Ow!c+B=7KjuCwW$xj= zEM-37J}YhZaIckyDPfOO#(c(|SjK$L9a+YtaBroWy-rz^YQEr(OEuqcm!-laA^l~k zQ_a`hW2r2E?WCFSxQo)vx7FHY34retu(WQyRDo_Gyg{Zo4c%>Ig9sSImV=! za%L&-zH;UazQ4+uGkG_bH_dtbl{Y_d_mwxWxFEmhZYyuj=8LPmIgYQc@@5(LR)vt! zvVvL8om9d6%AHfetl%E1U{>;etY|LcomtUb!najLQ^EX(T*D=0(pg@ETulI1x`B$wR6_bl-vsb#RN^kFY+U*()5?L2(N~$4 zYpO6J4>C7BRVV>67fV&C^B{AwRFzT%#)zD>s&NnIMCRZPNe}PEYV_uzCl7tqIlm=M zbMXzS)SxX~2J?B6*MN&+KC&cr4MvqjF5uZ-!@SK?y(Z_ql&NWi zYpte%YYi!E9W~8jp3SvreTFQ{Ij==uX*dqbuvClQGRQ9(U5j;J@=g6$;Wfo*iq{mo z9SE=0<86_;4{9sJ_no4)%y>3P-Ed!}3cKf4v zO^}+Rwm4o>jHY-^v0D_c2~tzkrWh@X+71P;2~tzkmNi}zq^79tV0cY%necP(54HV& z!E1ul6t!iI*A%HKY7?ZUsO?~QO^}+Rwm4oBq^77XYrLiyEsEL_@mdB_Q|xx=cumon zBDE-X%MM=qFhpcgyf&Y2!d;-Xg&|%OG$+_?e@IOcTvm8ZkeZ^l?BO**YKqzphSwCG zDPB|Trl{>m;Wb5Miq{mQMNylgImK&&%d$dk`@?I3)D*P|HWR$Ij<3f!UQ?td7*3Iz zqBf7^1K~AmGVq#Wv?yv5q^79tQ1F@}HAQWT*94u#@tR^cL2ZdhO%dGD!D|^vO|jel z@LCk9DRxu5rie^Yo8mP=XPHr(pt(3wQ;eo~O%a^pHN|C$+7zipvD=~IHN|LA)E32S z?}ivHj@Jaci7q8GUQ?u|s7>*jAT>p8*~4p!)D*Qv@tPtvMQw`I6tyW{Q>3P-P0?8* zYD>gxg3IElEsEC!!Nt*;A~i*Ag47hp9XehUO-LNI#UiL}HF^@oZk4#RGVq$YN1n`o!aTta;J7WwaO*pKE;EHxG!p_Q_G!L>kfwd4s53r3tb%dW#3L0$9-aF z$c?QaZnG0>-J#&VL_3{Y=rRyr+)gJ}xyomPNx<+wbmut>C{4}wz*1ZODcyNlenEu zEO8kYI(oy7NAa3?RF?eRT9;v`J5;~QV|F@;X8LpeDi0s8?dwsgo|gNw)1`+V zmFiu2r2HzQNbSIWl}8V+Mg1zpm-3jM?&$kfW_VPpkLCXCbZV80+UXRpiN9rLJDqw| zivMKXqjGL&rxSlm@y8P1$(Lzm_Nx?c%eY6SA~o^EjC)s#g-(4e<6e}BcujEJ!SI^+ zQpWu%#m6%4Mfu0Tjt&mf~Icck-)LycYGVRBN4}wu9ld?D$nGQd3+O zwa_K{RjQrtkKwhWX{S3}y!PkY>9WFW>QSlQm5F|piq6!dQoSqH(^5Su)n=!5I`yB7 z+UZ^ieJRE2t{#=@bs6`o+}ER0QCr-vQaviwLZ?VA>Rp)?UW@uws%=iaE3?9DYN1o_ z%0I`i@@U{S^`(q@S1Mjp1eam0i`(fWU%2{G#=R@WX7^{=>0E4gVy*l0@Y=rKm2qE6 z#cPV))LNH;)YQ}RNcmMN^I2xQn^^8VirDI$uqE|hVW-PZJl#LtPNx>Sqa9C|i2F2> zE(7tYm*zj;KT{*=G^*~v@pQ-RbQ({0__$Bw=?=#~Q@kz}DHbbG_7y2YWLPGajcl5T(g znHou_QFR(mcQ|&s!@+%Or&IJ7_0RlcxbJA%=`t*I+40ZJh@{ilx_Bhr|AK#};z5nA zQ#;-M5uf70xScMF`_yKaRXp9kk#rhim)TC2VWHEgx_CUD*yG|+by3_WcrYGMcc^wc ziC#_pJ$mlTFt%=A&rFT8JJNPKMSoe@>7wy;f0dmsZlTMFs*^~%qvM~cST7@nF7Bl% zaduhzXGU?KSne|WXMV-Aw5Hh`M%Af*ro`FB{V+9>E*@bg{+a5rDUo;wv(x=C{*&zZ zRUWg`DgVjg*y*DDC&%n`$M{bUmH$MMnp*3G`Q-0vr~7m8+Tqygvg22IjQ=G2cy0d{ zx~%z6_GLa%MwECwU7}xQ)T2^;EVJ^fRJ^7bO?@oYuTrqv!SLFVwbLcW)5Yy{5>+Q( ziSc;4qrrdj=lfM24qi*N)BWA}PmYvdIl+;&wXqtJD}e#cmnimHV^Psf8}luTqg(lm#Vfr;A$X)Mh6hmCA(@$7=_Ur^|?; zi}RldBg&!kpG4#7{v12qz7{%VM2Y)V9$Eeq^`%T?K}qzhRJ^9%m4{=e%N#?O*`rdu zF5~D-QJY59DIdYeDw^R7{ZBPT-bf+70yfX(=5%Ba3-d}*(WTSX^e>SUM3THlN|D1W(W7xWb4el zm&MuRzPy*hl~RY}*QZEk3gJ^}$S)8E73mcYOvy^onBN)ay*wQM%#y$JUY3AEt^{+^ zk^if_mnDgt%MR~l_Wd&z@nx`I?$19{c`wykC+wGlISU!Qmlc@r!IaW`gJd7~i7#cG z_p&&?v2h+1@sf@6sH8-ARLWpC5jK@FMB6tAWf`u9%)FPP9}pguQpghjWxqTW9u;9# zok+=w_p&50bjNrvk1X$H_Hm#1WX5?f#Y;0Y?`4LCE`#^7G(0MC-pdq;Fn}8>Gw)?I zo-WFxl6^Z}D)+xc(xoDm_p($1k4pCKbjNrv|8BgOiRdqp_fq{cmFrT`pT^Uve`fZ1 zFSEjZiuIzAbQwtSV7N~iFV$M7yq9s$%oKbzQ$qI3{qbIwM(baiXKrTROGS3dof7rZ zj7HU|o$g?`uN15)%6nNV8@!jP++oUiDe-ivzcZ+0kN5I$>~vAa%V<1ZBJX8lRGr%C z)MNAS$$J^ceTQbJOXR)$r{KOs-pj0bRMZ})yqAjmqQ06L=r7K4xi8|&+D;cmd}_1H zj(=upXJ6h+#eMU*N8`9pW9T%VPJJ~M2}a}Tvd4SL*EUR>`{%tp+PF_WGoy@`YOUKB z{bgpnR4>h}crT-jml{=<74PMt;=U;R<2d3b-{rOdDh62r2 zpm_?E`6MG-!I9uU$?&d>^ImF(0?k$+845I8LFPOK$9OLfoTorz=n}IP95_!w_VHSx zoi2*kqP&-i%d(TL;IHDn%*wA)Nag~Gr;BDNI2`_yeLX4<#($EPUu7ci z<&lb~i}IXAvlXbFPH|k+uX6v^y1$P9B+7h}6UK#u@m?Nnze?deiRUR07L-HDQ*hvT zIz?xS+SFR7b~?4+shv)u?c#Pi#bt`xl=CFYg(3(pGhU14EQsbQP>dG!uKZ*1bQ(#g zHoFY($~az&$I}VdrDC^4yq4%!dEh(+>PxBKm71qOZF5o7ChV7o=T|ArCz{J3bDn~X z=(#xirJ}Yd@1-KOtoToq`9$&BzDP}T7G#~L;K2MR!VeqIQ=oRbXr6+s_)p?_3WNnE z%6~%Mo_+EZNLGV*o`R@tE`#|*vlV0=Pp7CY!@DwWr;B=2CgL^qt}IJlg1C=mlmk=z zDzjsQ%O3Bg$-+)27COyLC%l&u=Tsd0CG3~QkBFU4ai3y6TJFSJml^j-e!7F_ zJNUEhbXoCUW*_%uSm+LxpDt>rE43dxo#Z>nzMU>LVy9EwC$WvA=*_Ux9eTb4wbMzK zx<6{CJ8*uwV|KcX{B(zk`y?k_JU^Y}sykSIx5dkU%D!3Z5*aTGn8f^a8JX!cS6v+UNd~%je!4^+70F(gIX|89UMibP zVtzWsfXb<&=ueSglt)DoU(`!8%7m%;>7u-s8JP~^JSvL#qB#!4Di`~=7}%B=ZMga>_Rm`{9P)E3WE@IKyLnpHfWPh9;cGvelU;jJu@ zbo*NFGTZ4iLxEcB4mCgBKau|=YN1mr-l6(cY9?{bDt`3xi61Gy%EUYc`y#b?o`NHl zPdpK?X+H7n*y$22bc)(CqUsX!(8akfqfvEHJ6$xMPIHSV+UcUG?O=AgcgRp6Swk}C zDTv~=tm5gSewAvii~3b2+UX9QpH3}wYORaf=At&c!?)8V<|#u{guBG@KtW`?yc?w_find+rEne3}89r4mU=AZeL z^NjPf^OW-}^;6D){WB9iGc(ZN{_J#$@}hRStavZgGgGZ~iUG5epH96r6WLUvcDks4 zrdsGSGSev@%o_J8gGvC{e_o&0o)_@dk?QN*XHFp>B2aQrhD zhm4oPb(s-QSLRQPr_;DOwa{sny6ohqQ#)N^Jl)~sB|mz0y2JO+{QKZO&2*sXFFX0^ zvWlmRdS!Jrb4r&FIyMS0PD2hn`x8c(-_doymWQ%;qv^3!El z=rZ$OD&mV~rc3nCR6AV;`uqFY=@K&?WMIAWM$w<3!g#)eeLXY(XkPL}^p_p~%&2Fk za;ivFT@^CV?LR+VqMfcPdF!f?8}dN@nHo>0h%d^4DZZMA5>Kbzn2Aw!S=s6Kwb0eV zYg2eHv+}Dv+WaSq(G;&K7s`?1KRFz{cKG}!M;5Oo<|#O`{3lU6op7Q26ZlV#;k6@W zr#n=A_aKFlf^Pe2puQEG!x_=h`N%s9J4ZKSaJC`}rkTa+sW_bp38kvh9ft4wS z6y~c(DBkZLm5(^$UHNzQt4zdehni13E4&s(YEk|Z@wCj^uQCy-9hmQUr|Kz~=#FhU(own;QVwC zI_t;*E?LDrGG?ttuI8Tf%%jd@$Va#*edC$Okd`_yKJ6TQQ|2TpC?{Wwl22SBgw}J1 zAGvtCeXVte=T|A7lUe&!s-5mg;WgzviDs$W*P}Add#P5rsCT8JHnH5r^Asd{S0>`M zDC1=!UW@XdWLW3~uVwI`C^|b5cDlcw|3tkjqs%8!)TVeX%6YOcYWw5)#A7Di#LPM; zojb_V)_me?c(YaF-toyr=X3v5rd=t_Os9DYBukxmC&%-NOZM<8+)=raxf!Xs#jA!W zPO^&UB3e$cTQ%AeH<#JFQu2)FF*%$#?`70Bmx$LA^NB|-bkTUaKZe)TLZ?2K;$0b! zr;`kH8CmMwFgIPmw}7Sf*V*ZgUVb`ZR1x;e(nw)Y5%$Z}eRxz3hxao1cizk5d_xrv zc`uWH=eSd@?IwLs3>=e#?wXZbjqNjY$|{Mc)DZ$nMWhvLDWA}qv|reG~>80%A*oxP>K3y zCdSjLo$hGlr&HTp9Q}#SE*ejl6^}}k>oRVwlN<+{rB1#%|7gC0tZ?67>z}E(FDq-^ zRNl)!J5k)XFV>4=z(e)VRL{)p;66oshVRhB!+nbQ{@VO>!kSVL7L^zN%cCNkD*KD4 zd&0Sje)ZCP-jOjHPj_Jd%tOt05M@w_;=T+f%%bMV=BHC@-M(4s;`!Te-7{EzFF$xcDls8}O}T$giUudPU1xKIwpd-=!W=@g?yt#!(Tsd)-{k|0#G-PIgw{MVTGH%D*;0-QS=8g+f%1@UVPj@uzbZVhfq^35z?BKPdou?ox-peTeNmh96Q0;UYTNm}NjPjpE znNOmTbm~_rXiohnvqEigo|8nz%V@TO?Bpp>u1jS;(Wtr%>=wssYNt!gRuGM+%Z^{= z=df3lF~Wk9Y80<&B;B8xPh3%(TI=?Wq*D&exL;*7Kb^+YiT&FN3W|#LeZp%AR4!eWlz9XBLyb3I})t$=7 z8kCyIT40VEv}z&axUU+#msOmqu%6cq883zRvOY!g(}{&nt#$tkcDl^@>8g^`Ad34A zoR_=`^EiT;9FD9;JrX$rlqWd`N6{XMtV#X%zrQ9Ip{&3B-Y zbef%9FyKE2_jSOd;QyC@rt+w$Po_rIDejXvyUlR8ZgRFDH^WS+h%b@%Qv5dKcDi_8 z@~X~jyk`a?Gy7*szxroZDy$Nu{`P_al{+QMrgAiRFQf5v(JXa}{-Sm|%|;jX%v6s} zL4OsEa;GSdie@^9W~qzjr;FR>#7>vUc=>nWQAy;zjN-mTtfxpY1Mw+0=8@vPYzhu4 zfPkkca3xv;P6;CI)OZKtBy8HgNA-J7+? zJ2}9Eb&&O_bFf`KrzpOZ#o#Te#E4$JuPY&|Q0HWQ9cL@QFB$n2^;YvLbuM~qJGoe2 z2gZ{sjP41}tb&fe6~~-Hnd;_mM!tuvgr%nnn?d7DxY`4;tQtUVpsnfe`5&?$g?n|cC0l3%pou+`3-`Q#2p&rlL3C<_xGxMo=#k|bgo1JsXEO#?ooQoVvz1lp$y49@PgM5Yh zCi-u7ZX&*AD9`(0wAQd@k6B|rXHRQreQxH^eQ+hT8BGpS@W4$XV!-DGxLd= zP5&Iw&>ZImqC{JyA2GoQLWA*gQ zqgi(??dzOJShL$aVm>k-B6m~YU~BL_c!L#f#Wjq%7I_l&H6WRjoJSe;p_yZEu+^Q} zHZRx5Y@3JcWH#e(u#cHXS^F4e7k({c+2U%-HO_QKS3_3gN}6uxuymQ7Zo4D9!NYSI zt!~bGw%cXaQ$8@4+8Y^lDP_97ip=n1@st_MzNXQCshwtTqMl*9ayDkz%cvLHd`@0u zekUJtr^)Z!X=mH(?VWZZzwu7WY`cN|zHc^ggb&Oj)?H^8vHp5{345DnXK|FPoIBWd zp}oVt%UQpR5!c$g7}Wd%c{*}5^%z>` z+I99my99YZ^+_zBgB(MBGW9vgbND}FDYKlhlq-=Zv$U4+>+Cptg)`F`XRmawK#rwe zhxKYM@>c3~{GMB#jf`DmA4hIPE@ivNDQoQlgh zWu3F0{tb3L|8Y5TIZKb(jplLln0>-*L_TiT+ck_|>)gnmHk%vGCeFr-wp&H7*jiUouVQ&M za<%h-GdJ9FE_-_3tYF)fSZ=3NFGsF$Zet(Mn%m4X=4s@!)XRu|oK8%aL_sd2wcNR# zHBXy)=JrrNZJshqS-Z?x>Re7e!cMT`?Fc)ZdOqu(H1iqzl)0Z7zudW>vea2%p5Xs4 zVBHgD0qdVMWOw7N+{f9N>D;QgSMYN!H%^3DI<{m z!uAM`_%GIeZBC?hsy&f4M%KhyJz`Pn>TAGV9>x!3uL_Rr=gbBB4<{zQ4i{%97m^rN|x`bSzn znLc)y9cug7I zqkc18SsG%yQU=>@)PrqqwsnvWBXZmC&A&}9WNw?w{>OZ8t~b}2<>q1d>u+;%(v!>P zv_F{tnD(}}?Pc5BcGR;OwcO;lF>7sp>rywhO>767k9K~0zPZQTZO%7~sW*q5O`Dy& zsl|_Qk#hlS?lu=v?m}Kby@~uPccX8(JJdETLSyw3V;4E+nS0sCd6e@_GmhNLHsd%Q zkR4chnQ;r9ml=Dfb1rjquQ``;p1FwqE<#>N{UUqbMBJM&D!k4=dKmeT^B_`U{mx;l zbIrxf{Ex^*)EBeeBJ&E`u?5a6?EMbp%hbvIv%Gc^|9P32WM)%OGG|jyHTScRsg!ff zHuf*LXCCznPB-TH1&;e7?LnOT7o5R%ke$N#sb*`aHQ9=8Zl1H1Bh5#?LOt0mW&LE1 zu@rf~nSz|e(rb*{hPGrYb#wlGFWa2b(_X^w{=r;A$w~WSmY#RIbB>?q=r1_OF{-CM zj?%-HupVco1pgu#=~6ec4Q*T7g7rOY8SmrQIV2v zYtz@tmSt3ZWPMxDrcsNmXY1MujI4-EqAo{YU3-<8Wv(=zhm2Lj%nWmx8E%G!@-j2s zd`7=yEDoVvejpJiFW6I ze(LnF-R%%_Ir|u5W>OEKH5AObhy9FX`@oK5>m2qIw*8b`4J|nH>`gQUx=3WV`n12;#%`9ey)!>-%=iR`k9IJ^kZay66Ez?gpK4VJb$ZOmwn(#DLT&S6^G-A)eE%C@vQ&2Id1CE|9sGr^2Er<&G` zX@fk8x-Huz*|sbfwSlS4l@ORZToVD?YNYN*PA((99IY7N+O#q!Q@2F63S)Oagz;sU z^8r%)^4qb$B-_qZu;r0STsJ;@3rq_$mMvPCanvnnwIt3kxB0+nZ`zsi)?(~nHr5v&x%jxXR zLsq12#>nQTyy;-tBg@M;Y1#bvD(`gi8{vb_&k^1u$}$}dSS5;U%9)OAQI3Kw*-T&` zO)1TYvQ%!IO4Mnl6Qj~7)s-VOCjn;Y}ME_GG|a% zV~-B9Ds>-oJbnLR+zzLV>B>IJP*P2G);mbY{Du#9H`bJ5!l2H>ZY?{HrzC%dbvD#x^qlX5{yHefMBgN;tYC?G#hX zNTfn7^9vCRwb=R>WKHU1)06edl#-@4qkeLF(UWZI(E8D-L*GwM3Db+7-pCTBE^B^t z>YI8j7o+t9(am+K8<_g^G@z6)Md>MqXLh2tn`;QZr4 znFjjbW`s>*8)Gf9G^3ld)&ui5M@qz<4=$EW9j}{G=rmqu%r;PTN&Fw0vMxXdp!ueZ z^+CrejQ9#HzZE2$%$V);yaBrYik`-d%ZVlF z_M4^=<8q_PXiWVU$h-uy1nU~on+IJ;BkI9yD;Wh_ggS|qEQu9557@aVnuoVdF;M^8 zZ2K0d^mCAFeb(hgpOF{jC2?hWK+{DTv5w!k7WozRIy5I=fvA$u1MFn&JEk6^^P|tG zPd$j^RX`4=eisy zApFlvKh{-2ztf-kF?t>aqkckt0)17``iRxOFLhPW>nE&R4}$&}`7uj1Nj41U7h?^*2-2m~&a*23(6vluR9oj3*3Jb>Y@)uEa*L5@(e`M1rch6&)dAT7 zt;=nUxfLw22~=@A*k+TNL~kebK9i~E(Q`Za;RWim>Fb0xs1y2@iPW8)`Si~NKRgGP znNNAaTxJWR+qujZLbr1kqdFrygZj^+bOm=j$G91c5p6SwTzZfKRdp~nz}F8Eup`&9NY1u1?VH`raAp&RV`=oxOXA8@WjlObA<>GaK^ z++gnnYdymk?lT-iG#YczXH27>$o^*9(>X$SG!{>Qq-LXOdBTYHL9`yC{}AMV1@a2C z2!i})hRFYd5c5y8XNH=9tI$b^cH-htYatqrS)s;4^cXjzzYtA^pziaK=Yh+|+Fo2s zWBL74t>9`w+=8|Rd!LIG{5_5_W0At1JkAP(@;KWQjp7*ApBrNJ(|9RAG@_3YUCeCcZ2P3SCDfyc?nE>&*P?+DZOkIH zId`&lA>}FLQ_SK*`!w??x|O@ov53ay4rX@|`V7XJ3qxNJ!Sy$Qw*}`5wwwUgoM4B8 zJmYv%5U8MB!J+-og4~9lM06(eLbN#^Ii7WbIZs6jA{}T?LyI_&|D`x|09p{yuM9#v zGr<{TCpf1ePh-TbXhTE;A$%#fQbstd(VB>MMKmX(Lz#!1hpuHRzi|qPWEJ&PG$*Uf zD%Q*oH8KnAEo?mkeZ~khek(&Qj_7a}p_^Giy@J+V=wR*w!L2}}v&hV4>_|}6O7?XQ zXJQ3%1xq)h85xN_QoLbqri=!!Eoa?%$a9fPsV@NUEJY`I656{9X=$5djizpYG>**bb zCUP9wE%B2c>s-v3i@-4Vnv0Q(sjp+*spu)MrxtWQ3{*V~EIti1yBG|!m~q!KVmx}v z>!>fKe;NqjZt6>!iM!1;tQn6Eay;kb8p>cho&HO~2g{kYb!eUL3$;)8hq%3Ch}HXq z_`MUd4>*2psFxDlJ~Tx1okRTIB}DH-KzI_t*NuG(q907}Ml?-p!5LT6`#4K$MU(Wq z#%U?~%&Wm78|YIl(=zl~SJAVczGcW|=$1skG#y>Z`cO^>2R&vl1E~n=?hV@R4eq~| zZ~be~qI`okMKmf8g=oA9+78jI2r6$HqSN-s_ACkhRIJ*}{)(>TUq;Yq^AL0P1m*Og zC7Kh}nTV!DbSgiGdKA%|JObjL4bGm24(nnxC!$9Y{mG+NaAsR%TTtv|#!NyN@~!y} z`JMT<5&T&V?S|+}hJ%l;L|zHnTZ!&yCi<$GXzfJgkP2v=~k;N0qVH6tHDJ9ZiMP)1x0!W%|CihYhmUQWH7 z{mw%BwSxL#bSt8bxE)0QFy&%r2wPkY;<=pBqnY~|$QdlHVV|qf-brM{8p>r(9{U@g zg9G^2lfi0}!D0i@#>@r<4q*?2Dc72Z*yAN=I3A{6#xZ9hXK}`tfks;(yEFHL7<(;D zEtjC*TSvJRxdvV0I$CR-f#At&L5J6~_kpyoLte+ygN$E?2IV1Y!Ra+ZG~ULJL2vaa z@-aIaH1;T(%BA4hmdIt)g4Sz>_`Ee5C(%oZ_UYf~oc@i*NpOB;uv#ld)TdnqO_b=R zL@V_l6GNk9L!E_anndT6Gt^XxZt4dk+JVycBy=A?f#-hW*vU4p%@=9`svxVdUi1cK z?EUBsTcTqqX;bXUj6cbUUZViIy!+`Ft%&G9MAIXB5*OWpXdFa?P#^7rXgEY4QZUq5 zNIQik(Jhn>wF&h?{fTHtMAssSE-lnb6bkhd>7n+aFtP$#h+?6ZMRX|vm{l|rXMmkf zH!tCfyu@h>T08|jISvfk4xBm8Y(dAh1dZ4dG@EVcJ;l6?K5H?Wsl{yZGUX)@=*f(2 z&;L3ZIhHLq^RHUj%}y(3b~9Vwhj#5g`dYKSVCPf8(5=DCr=ah;hrM)QHh%;w{>b*5 zoZ6t#O>9xyzRFth?zx+~6o5ZKdZ`bW(Rww`BP=&~Pj27SyMK<|mpH%wy=b z7NEJhi*c`^r(1*+@3M~QJ965NXpVjWdH%prk7K*jkf(v#UPNbC$2Mo_4D&i$Y(uYh zC-v*-;}#+%7NZk;=m?f=&X{JDGm&Sadw7E}ucK{ykv;SewF=wmc>}$|0_vuWItz?D z5nV)6S`*QhJjR+gDdJBgd|ypi)87c^*PBGJb^^VobF5D2f9h~n_pt9e_6y`5bTrRX z_XhX%0;P8bp$cm64Ehexj8$T*bo5K*&>?)z=(@E z$gk*^%#F{WL;8yHoKqQ%O<*gd*C>Vz*zad(qR0Olg8NYXn3Bc_iJ=mPvZfRMt@mKPk5EkE!bS>J(6rr^d3c# zxu|o~FKkSovd>h;_CyO))K)>}q|SjRpekCRr`Y2+&J$>@zM(wjydV=~pbXXga8(H!g zRULiDM`)e$8HvKl#~$*6@q42=C`IXmEX~rt+3GvTMITZfZHMGvaVa&?XMDsq-?R4L zctUNUPGO5aApSn+0}7x8`iQ9dkI<@!E} zhQp}ZXgX@63HXhrx@b8hVyTFE56w~$wk8!qQv{vDuTDMm2RqRV z6{RN$y~VF+9~w~CN5`;}-V!VoM@u2z^*>RHp{o$hLo#C;pqcoIo}bZ@B%2@5XcRNC zPz%8iLEDfV>LrrVI5_ALV$>x=pM{dNL}%c#Tng=ji*#8ojb_0^dMuX-{SnHbI|yj| z^rq4-gI+^?3d*7>$cfBBZyN2g=oQ3Ypd2L)ye{4W<-z`Wkh$rtK)XDsJ8y`;#U`5$ z!WR@Smf1>3!Q5g`uLK4w0IDuXs|pyeAhICKRcQ;V7Mp%GFn?iWVV0|-7bt=(!g3At z2ua8!mTRJwD2f!nh?=x&pw$rG-RS)Af@Wq4hBH%;wqf7m(@}_0kiE;y6s8nn?=mw* zD23U(cxoh3im+dqpQ4l`j+28{@o;{Mhx1dMo?;v~7rn{h{3O#Z!K};tl%&X6kXcG$ z7V;wVgl9zNq!cA3oRL!e8aPELtNuqjFwjEa^G+ zS(bAw+9&xxrNVzA=U6ztF`_Y$b6Xf`S(2HNb1WJpIk!pSEENuCM$WNlrSwe8d6ly( zIxaomIm5Fcvm|F)&Vt+zC4N80dBSrc=Qx?OD(6DZZK?1~mkejA6uJ{R7vkws8l8)* zZ9{2`#zfAJc)FBEzmr05>u?X^<5C7qikzud^t49G8SfaLHSumqMKfpUYe{K^_M{_c ztrH~;&4`>k@oPy#Khl|Ym+;()pG0|dA9C)*-$JCEyL9S`{2TF2k}FSqm>lGB{96a< zu-rVHjppWep~jpY@n3Q&G4zau=$G@?kaHw{N*+Z#stVF0=U9BJ#6!uacxVp`&?8rX_*Lac z23#}MkkuHW8pgWR^*Ddk>CM4aRGqVv4-H~oN*&H+4SI8OZPnm9&r44pig--bq&FAZ zoSK~7JoJbclxR=IOR8;n1+_zpACp{PqD^x-b6%)3lY6c;y%yPqxKI(=ZwjH z+=?}pGZ%z9Gr88}oI1!>)SWnX4rC5SbPlh$&h&KREXuRD3#Bt>QLekLlrEe_dA4+; zbY=GQ($Xhye)cEluqAVI9Hk<%1$A>;6_CeKH=|V^*_>K5$K{aCsGHDALpG(Z#Qx;I zmM6GqnA5o08YA`Y);nFf15@cQ%lXqgUG93(DyMQaOAJ$C&Za)ut8m_gaZqBM%5Z(i z6F{E^qC*ysKZ$=5{ctI+DtRX8^C5-4Qk=PZ+%eIoL`nKmxJyJgEboK(6C;@(@re`7 zp1vXE-B62bvo^i*rjWL1|2l^MT{M;DIVbYpMVncUGbaC5^qXm%+p_!%(TbMke9ONQ zJ!xuq_RApU|Hv5^DgQyvvPj9yEoWAw{7N|^BITFK84)SJ<+$)S$$2Rro)MAqtDA=Z zNzO|#W?%ldoR^}^waki~ktAkW=1+9{MVMK6d&l$A3bgm<>w`EnP_wc>`)26<}8-6Zb}mn%-56&1t#MV?ibE7Wj3 z%ahA+rOOjbo@Eu0^8Au(U!H98w(mw;biML4k|&-)`zUr9@iVi?O4QvsN+ooe5-liE z7BQqei+WJHqumrHaP^k#$!`{q$R6~G7iAB$p4DjeVuX+EN!^QoS`Cf7Sa8HQ(??dP zKAt*2%F{=*{i@loj>cb}JALTOft2S@AByA{m*-AjX0;}=4@-S%^})tai`EIO%Z-$$ zkZ@S!!VV$Nr+$>Y$P-xV$6B#Z$aAbe=dlj5A8Y&5>W7`9F0B(;&WDs|As<2GT!>ezC;Jvw0Au5V9eCgShq@V$o?t zOZ-_2VUv*O{SZnKWFvZqaIH2%4ra|zdXtciSr*UBB1rMk9m;jy1Utr1)(+$PZ;EWn z(r}iGhQ5+X$Y%78pe~ARMm>U7F{F44kKk@SQ=_4s6kRwgcl^oWJ3~AvQ_y$HH^5kWL{}=`2;wnW8hvOxTH^Is2CZkiP(Lc)1L6xPJ@VCX z3Qwf==sP>mI+b;0k*83Pr$@A*@;xB_f@P8N)i8nOa!C1>n?PS0vLp2bo_HOR^3|Ze zuM-&2h3j1+CFOh4=UQ{Pa%&@NaShd?U58SGtHzfow&pBJZmjl< zZG}9JEjzGPTcn}x7``1khVP4xY+st5cGMji*Am&1rA~})&lxgo(*U)*MYHJDH1(q*rq$zZgHf%?IfpUFqw=xDLn;EcIloZalZ- zE!r!5`}AT|aoUoHr8gscAiGibW^6Z}ScbX}_hS*Hyqo$kwkWa(TlAsy;yKlm(I+rc zvLMR)s9*So>c=*PY4>1UKSuOG_Mxvot=sSPo6}Er2&lThm^P20QOP<*`JXE zD7}&W=o2=d{ycFE+YF{JKT_fwwy5qTn84rhx&JUQguH-c?)BZpCsVBJ9EK$b@GF0n|<*pZasJVE4(ZWP<( zM2?^yMeh*g5SB)Bm&K6sejLrX02vFPMLuif`I7@Vk}XDu`^po(Bl579-27g7(*DGt)mCr`$bNO`ge#x2FQQi66d))zs_le}2?e3oZ!3EJ|MD@I90%9E-XB@LMt z?or<8hSHGVA@2@3D-HQI^2U*Ql=usIE6E(y=XcB7N}fyg_-`I1EQ*vjxLgM!<&7^_gGhOf$<-rLz7XX46Di*h@(rAh z6tr6?d=|;|oz6ci#B-@IrBis7ifbTJbs>;wLIe&zwd1Rxm5^gx+U3TuU>bZ{ipMXd(J*PoxS%N%=ldd zlp`qrEuj?$b7m-IVH(McXm@#y5~SLre5#S-kS{~xoJYIM-IPS<(fV@37LMlto7qaO zX44ae1m&&LIH5c@r2ls4=?wPe#p(ve&S+UFqm2%Jij-hl|Pbm!&pQr_s6~ z#;fVf0_Pkd>NgE%ThbPs4Hi0z)O7~Z%C`30G!ml4)qB)|v?tgLYEViC zi=jg5RF1hN(3uJBJLZ-E)herLd9^8ZEj7>3LzmJU(I;wLInE9TwzG}?vB!EdTD0y+ zN7asU9NBO7nEIH#XCJD4Nnc0MC+b$Elumjtdexo`y~{pS2eaqwVf#6HSWAsEWCu`s zrp;G-Q#<>uiITM@+9rh$o0ayg0{lK-59FSEf8ty5a1)R3icVW*N$X_u0!g%v6+QjRaR zVs#gJ-wgU&-MNmUo~*UW@uj{jN0O6<=i6j@OwLo2c#*o;Wco_oIc!Kq*k$&kur{gX zji*oSz07JQFA6J_JYDHqYgakNeo=!iql}_g)SXKyBNJ^E%7sce?xJ@~*q4I~m5#N& z_6PdEN2WFync8L~?K6lo^69SBmRjwGvTu8LQ5u0Gxzfbed4n$YhNqSop4w)3YNz2m ze`IP6=K}grqm#NVKzrV?-wbYavTw@_2QxZ3?no`v!8tigCufysI%tvJK)+m>L;SRr z#BH^F+oywnD3*)8uFp})nF`7X+C`kU-9`XCmNzLy$*XKPTSwmF7%Ab-;97CrnisAU z_r>*M{hrS`x6Z|QW3lcpwlr5L^kJ`-y^_=ir9kV8uVp~* z5|5SryjRSw04i;Y7nMM1gV<38RAO?R^a9Ec97Vl>@(J;!8mPoHh;OI?=76@RUt=5l zzv6qug|hTbevcAqNS=OGMfxVcr!VjJoBW=ByxVW`d+K?&-{kl7=iPpj-!p)B`%Qk& zK;G>)`8^H1-*57J-1v^7ilDVLU}H~&N+D{8yj&e@|&5VK+pC@F8~J=U+} zc~z8Z-XZ2V{)(8R{$0+~LIeVO|A?%*0xweS&UTa zm#NK^BK3-|ODRi`HU0N$GbPB$bxFP-!*&K|wQ9~}yBt|>8PcbA(Y|bR$ktjVRv;yg z1&*PHdQ4w>bQ(}g#tO!vn#@2-15)OA&J5tpKx9sR>yZx2)pOlBGEB2$P`=|wtqTU*yvn8V_&XDN&t){S=(LITJgRs4A0vg3Ih_VH^g)8a{ z>w(Ub3}!3b$Te+=8yWe^mC^xaR%x74=MYA_l4mDdrABF-^sEsXQJb%F;t1dfj$3o; zT5ViYc5Gp*T&dlnl_T{M<;oRoV=hm9L``J{XVp~NxL+NsK=BUe^3+X2Qz`IPZ2->I z`yJ|Y>Lq@Wn4$f}Z*`8(dHApdEZ`rgt*DjE1B!iWCtAVOQ`Al7(o1S9>LzpOC1=&u zQD)OW&Z?`M%%V@6RdEl&}G)qd2#xj-sZbJs@WB)J?{+ug;=w;%Ih0 zPYux-J#oZYefTfKoc*=rSL!c&M~%{6a~5`R z>NERm-Y3{!J$uTrt9GeQDYdlMqNmg>)g~{czk2pm*f%fMUp;#&bjo6XMNiph_SdNY z-e1vE_L=?F^_%|s2i#xxKurb`gQ8quevW~}fvH^`rQAbQidvMpE*gjlQ{p>9Ihwnl zvx9;6v3-EOA;A0Deg+J#2i8;X7-xq9A7FbJobCtg$F<{}9R@tc_HJ5^I4jCw{MnWF z%yKb|m@s9cyC`?#P5&V0@8rx~KsmgbDr$%ftL4~y6*WYF)pBfJiW(xiYB@FwMGa9| zwH%uTq=wk3T8^g@Q*n~9Wv&pdHzyfgkFlLX^u=S0z(=V$ookN*r?J)MBV|0z^~n@x zBu}%qgUFL7nE5fA&gB$moc43Ho#JXGuEgey_!Gb{l)! z8A009bI|mez!|)8H}xh0cd^w@m19Ooj_thoM0kQTo>wNW?!5Q}c#iY@jd0k_Kz#rj zIo=8ugNs}DpcXG^(5Iav#wv|G=J5x{Gx;i@WEv%QwRk!kKqx-y^IWzgCA z$x5>hsK>>1)aU|U%hnn6E?^h3iQZESfD5=sOXJ!kku3x+Hk*}3Qd06V8l|wF``NFE@Nh#C>Ll0CRR6kTpR1XikMcCKEHWd~vC3fva z+G8%wzM_=V)5@Y9=+f*f>H*!YETLD0mKFP#_B~2nJ*__4pL*JRwDI)(DtpTQjJejj zbH2oH^Bekr>*DKm)T{tH-+Mj#*D-3;g7iG81b2MW4V3E{OX91sdR2@=@zwahUW^3k z`GVAA%Af<29Mix!ka{mlJ+_EC3mF6U(qhUY#;d)p+@tr5n$}gRfApE@%_#IMmClsd z9N{DRiW`CA=E&reqC9s4qo*HFT*ANYcUD^3$Mu__FShX>o?64GlIAa^ECK6Bg8x@? ztq;)I_GN7Q0Hyz-4K?y*gTZ6DOk?6HjR}_$RPub+|fbYr4TMrDqs#!Aks8|j@ilWY2&T*h`4XVj4NX;Rwmgz6dR zDeb!r8aIP8tGTNFq$iZJ-3Tbo4vt;DY6sNQ=v`^(ekhl+x-;7&pjLWat);Ai_HAcx z9lUcpwAh$pDe~>mwQ1BI&+#3Jb{~MEP2+4kd}|uC-w0^+yE~v|Q#sp~B*uxHJ(PIH zLFm^M&bGo4NwEZIc*+!+*S z(!>zIst^Cm*%I>&`VXZU&a;GPuTV^LzFv*jQQ(|cHLc=Io%&BbE$Cc|++5#BM}hNw zdX+nZ#!$x6i;l9gEVOD^V3;Q?a%>3t>F%4m1JnAFT!24zwIBPLypiy*rHkVVu>w zL;tQJ>@7{W;)>~7Cd8!WK90ubHw<6Og=RBl>K8L+EezA zeVF;F+lTg){UbGW)V0%J_Mw?s>>qp2p0a=JLwm~pu@CL37(b4du?wQ3KD4Lo zAMHDikYQ#guMJ zLB(3BtsWgxSm~@3SIRphQDo_|6k0#_pxrYP)s}Wk#e=5n$)UAUN-rN6n`nrXLk=J( zmDR19-Q5`=cLoNn3;_AuA9o% zo}NZe%b)ZTFnY~+AaP|HSTcg+VF?$)COZr~(h8L4s`~4+gkQmlW`dXUCoys+7%X*d zrpR|3r+SuM29(;0(=);E;nWcOhXaRm?0eNFN_n>0g);^I7r9EzVL6*nnZBTm?Z>I_ z)1B?tf8bYre$1lz1u^sBm#D#gobT!We=qcWEx5JdmzXL}ih(s8i-+<{u}f^O1KX59 z#o#({rJ8+lu{vQ}HMpk7(kPC_Cugok0!PueRqXXm<08h3)@36k<)hjwjVEy|byBk{ z;ZrtN9of!}OQkEpoDQH=#8$TNDmgE9R)QaD_2$ZI2eYLV+P$@Qhx8=2Xa1v7SGnK- zFi{)2R9JkLhL?gh>dDgT9C+3Ul%9(_&Ovp@r82Orl{dC=t(E(fL^}E3wpz%bjQLvpv)#s44*0G3VSM~J$0e5bsMvy&K#anLgkYz+C@vbnzm4RMh#r3oTJQ| zd8RrSr4$tX8h&8POIZw#_IrKGddBNy9%<4u`z~mmGO;rQ&gux2;?%B%YAtHH!tkO~ z`*G$$X;*D2W+bHSdg7^h$(}TJ=Tn`13g5X3{*&LRG*HRE4DG`IM=9q&`}%IQENfWqN?9I zQnlsD*lAPaU*a%~qLGyK7Kt>9<%HQIYx^1bxq_endqEH~4k@sg=KDCRIsE z&Ln>d3ExpYf_<^AA>pMn`(mSb?7XnpD}MK*@5PGDdrl0jp`M<7{n$Dx`teU{IG=g$ zNFk*mgTV=S+JVftepiWulyw2}>&zepV*@)URVG|3Uto$p)F_SUEw7 zP-&qVSV&I~U*qsH4h(fxKf~PcG7gM(RzJLq1J?uZi(bb18apy#v=qIJ9ZQZR$C%J@ z=A3?vz3?&?IwEZ;p<^^gue15tsQy)aje}-{m$9_OzL`!x1$DW&udx!GeWaJM+`*oj zM9az%?4z);WHIc{;Ae5}&frTUrIk`pBju%`;bm-(jG^U!eP82`M=R8f<$sx!5PtU| zJw#MXMk~VKLir+Q@iQ4j3K>xsK{1qFvIvZjW{T3y`DsOXT7-NQ(bRfbbf*rW zEGb4Yj@mgIZDDeAJ%U13Q=iOaxKD>xWL_8Q;nIih5g5v>Qi+gZr5N(>j8#VG6P#UDIh z-rv)U|C1VD;mfbam3j0l3x!OihMvv1T-=vGXnRwlt5S@5{)WWhR zjKT+PucNivpsVJ2aaOLKu_on?>^{=AbE&;^gUV5QI}T0sSWiAFr8LAGG*WVBF8vQu z+%k$fUOQLH6CDpaZyp+R4n-~^IfElH?CCKw!)`t(@$U1>?H88VBjU$(o3x}$sg>Jp znULNaITsR?a=YU>q<7nJYNGW;>D^H+KM4D6NbJs2C>bbMNu#7pA+d+_?ySZn+Oenf zK9QEr+T|xU{ zPzEpRn&CD%Sl;_btE?PCKu)>btDD8=YYF^a)ilCWm^{YF0*|I4S*R-eW*yMJ>Q z0bzW$wymJLw!D<3oMOw{I~5dL-rgZHH?_RIV@5Dr-m%z=V$0h*y(zZ5y;DuG{p}q+ zO^lbZcf#MKPwJOGoU!HYkvfX)FKzEjvE@S_Y2dh?eYuwXqNWn@6azl>zA*MdiYM+W z@rL%H-Bw(1e3?ru#)~6G-f4V*BgIi;+<+s+QDZ!TPjl25XW%m(H6^r}k(kCmpKrVv zLm};T)Hp`8NIG&HBL$!%C(GLA$jLM&bGbQ2nt+ZR$4Dd4kt0_&&c>0G#Z{=M^&BtV zM~eN@hY};Df&bZ%`s<_PMZ0h00r3AA{r~BXm&_h-UuCfZ_E`5m`gmi?|Iw4O88OoR zf0d-(`SfX;)GVWH_KyAK$g+2&Z0FK6$IH2t?U&KCPXeE##R98stMiQ`>nI^On)Ltr zG~WB0KDsc?Ik%5`j-%)uX_S5BX!@l3=wh_41a4$3Tzh)sKOWxnY2bD?rh+SV?0mB|w3WRWW=JG3P_ET2-MkT=Pvlqlp)$`48u@+RenDvG>GKBYtEivV*)z`AykDUZr(X2|}q(DMDEy$JYN= zpNpI$wxIIq$Kw?~<)iX%&#`sseH9YKCnI-fazrL~D@}YFa`)c_kNPzF=C*qdFP~Ob7c^D zvIpm;lWlu2dviF(GEav2LFC>ZOrGtzoNFK__h63aan!)NV1qfH&rw5eVqRZ^iJX~4 z)^PHJ<`-~<%+l;nNNeQ{U|l@tl(yyvu!^2*?hRmdvw<9M25wW@Mv#P~4)EGkMar`PMgULp&Wql1b){=XC2F?gdBQ02+&56Wk+XPhd!5w;mT~Sno?V|?#olVN_Ah5UfV&2gkH3Mlu0_|7YvR5k zxh~4ce1EPEU=@h#xT~K1{^W~q;!0<#K`wUA_67DM6MZx1Mx<*ua0gVMb3@49@7dOT zf$i{g?Ce0_Jn`e?rYFZXS>|im_Q|(VYe=p=)obTyNbW|~X~1sE)mrlE6IahV4>xjV zAKUtz>jKv2?#>h0#5y^L+1|ymupeiSaIRnOPR`uLN(?u%J<7R$xkK#T$qEd&usujQ z#A*t+vPFXb$vap}+?djN+TZu^E?uz{VtgO>F_W)b+P;jQ46>=V6|2SKs6F5^wzI(EblhM8@ zSCX$wHbk=ncfenrl{Y)P8QYIjzm64kj#I}~HS2P&#aV|H@C1gSrd*y(`1sq9x4(%D z`F{idZz8XK6PfS-8^=xL@^9v>tLrt9^}m_p|0mUOO}-{p@N44O_57MxRiK#~{~7pS zShb*;y}t(jC%9TOdo8TN@RvZ>+iYP4g}(y28fKql3DXzY>@(WQ`d|e$W1H4ceWb<$ z%{u=dxZ^Kbr=f*CZE^aWj|Xax?e6IpGymDVfR?~MIW2*Ga#{%cOy4pu8d;bFX z3sx6tWv`9ZP5v3sm44gOdc191`JdTuWn0bjoeS5Bec?DN^O0AlIIZdw#Z^u8z*^22 zM^;Vrzi^Gvw19)a*?(#}1(Jdq(5+CT?Um(5SoK@ThOF z3Qvx;cD@1p7TX+a?tBaA%EdWWc>NBrohRp5spPvr*ILb`)mn3`Jn;keUHdhc`!U-b zYi9fy=z6j_R_6F^pexwsxc{ecMl(M4A|~is;FY|+SI#KDUb(B-_99Z}Dxgt$=90Xc z^@wtO+t-1v37%sw5BwU?HN5kzH}nDUD{S+uvGf(7tB6+-TXY@Jc(tk&uU3`f)v8jw zS{2u{leiLe3G3Rt1ALEd39H_`2Xw{l5?1Q@BJfLWm4m;8^uLd1Ri;?CN@8$sX5Tou zN@8bj1@32CNu0}m-~qOkM6w(J9%Nfdl*&Qioop*p1ZX9ZD0i`cm~ADID2IVZ*j5sk zdIWe6+sYKnTA3nOD|5!FYN2`?=xWZTIahNo&ArC9lyz!e1HQqwlvQuu0KUbxl-h40 zfjq$76)B3fBE_s$qzKiD6qQ<$B2g=-p@)KTrDZ9Kv@Au7mZiAQvJ?qgmZC+=QnY9p ztDZeY%`JjJ;xjh)OD3YQ{JeHwE2`Si(u-12XC$@kaS?JlLi7BZ&u ziK^$I=FYiF+w;(Lbqy(e36$L#BI&%DN3a8K4(X8NG{A4b;}HRM0!|+!}bTmT)<54IEbsxqMe|<53*Rg^Ql?W;q#$G-Cvp z`nr6%Z{oxC@L%WPCQt?>o?M@J@_^hVjt2rKvYpHxk~?J(a1uw(ybXdoYcFti4%wf* zA;76@r?WRS@$Dh-YwZql@1byQ?GeWNH6>0yEOGKCc&_$~S(KKeF)L$eS9G zBtms=XP1RqN#;?E!7yXAxui3nIoIO)MOvxr7jVk|iM@YL`2{@ep9BAOTHi|U`^RuH z*VJ-NuwTH-|A=e<3;g$w5?}u}@R5JY)&CV<{D;6lmvEyGsqr1kx8X(~viIGzBHmwd^-qwWTt)nQocV6zO@9T4a3#DCC|`w|e~_SS z#r;RF|5f5#{}EdMKIgwc`C3~0?5jvrKca>l?JuEUU+0N0aP8~BFR=X&Tyb4>dEJX} z>OTN}kFB)sd&q*WB;~4C%6hIV_16?vfBI{nt7QERve8et|G#qdH_$|RxD@gakc$3K z&PpeLA1H_azmX{aFQm!8Wlzfab7auJ<@o=j{J)78{2VB^&*%S^v-z}&lJaW~S@_@b zw37UPMNTc@ylY}B+4bjq2`f4&-?=ta|FpW)pQ3@dO4PH^b634Q11)!T%BO&?bNK}2 z4DbxsT(|1q0skHMJkIg+aEd3`y4uyB0so9^hx0$-e;&>&3mncX3)~Gn%sQY-1Zo@q z2T+;uGwl6)bc~-;OhW-_bgLk85}4<$ibOU*TWhnOEL% zEya`Yk(1Pam?QUHgYjX?qd?cOJj%*le-2b)Rgd`#^p;n-|4?2odME$jd7x`*nv>yl z;?&OrpGPjZJIM%g?f1}JT&?S#yi%}Q%%20*!w&MCLqNIl!Mxn~aFQ?N^6$dkl{n<} z@1XV6vUdBu+*1p@hwUAC`Su;$buh0a@HTRQ+(4pNV06|M&0ptN>YgZeCI zhN2VQ%hT>dyXy_CVS9jQyoD~MG;tuWEO3D5-+@kwrV1=&tBi2~J+zeL`?<4M(yn@= zdznMycCH^l-)u(zYy}qb?QGjv{jHU~4$ia!TRHCF8O`|-Jf{iR#PJALEh}Y(uQK+g zu^w6(c8hZMrlK2`qpztKKET_0q2=AnoA&3;&apqQj57tzu_8Z(GL?16D%qP%?aKTl z?x+G*aeP}|iRQMvc{y(5uKlcB_5jz6EhdVX{fYSrNi#GidOz}+am%+-4q(4H#XK1&C74$>Q8?5b7l)xkxuHZ;9Ms*q=z`W2}{mH*iYtT zMOx04`B+z$v%i?K5a^nbOF6dytBz-vaI_%5k-IhlwF7Mcx+%Rn0>U_@=xO>l@&^d$=}(;~VpG)tmB@I3rh9J247= zExc8Gin{WRc_ZarYhW$+PNa?;eJ@+1>^CI-dqdtx{0&GR#*I(ls#^I*wgZzDNz2u> z`3A~0c_TkIBCl9at@(!hEXwuy0n{{Vr~#Xot0pKCc^n>&Pyo9=q^dnNR@h?&>wk%H5Bswcqi+WQndak9k7A|D?V!bTAS~i z^!C1-?}wbB4Q&`@HTIG@NIUBBtVMwRZ&$t%o7gJgFt&ZTV!W0%F+D9-VdZn}*gcdh zfjc=;-Y|p29_)QN)`H!W*CJrPyOmteb0&v0rBxujcl1nHnJ=N}0j6B%yo}yG`YME< zPdWQah)RRb=IAjnK1p;&S&yQOMb=Rw(tp&L4I`a8IXezGitPyY#sfRqnzf(?Sc4>` z5BhkdqC%37^yk)V%)G%$S^AI(o0HshDgI>I5`5OVzTL{XexEtN%>7mLI@QBl=~!v+ zT;J{m^t008#r(-GJATYv*|_TmtNh{jEG~qP#j1W4foMCvbuY9pFa+yyKi^*I1v5rjRw&l zzk3`=WYcrB81om=f9J-5=p7vS*|XTeh$YnHFLJMI4bWfM(WsR}Pw$KScB@&%3@P&x z>=~6J{%ZSlEluZAT~X83($uhWz(IWd1h!+iIyO=3f#`DmI93aDbszOF*XkS%A8-XA z@z`vYVoqPK7(wc4o)L4RW*9z|;*j|nT%oQn*yP%vt`}-9N7oBAs#qP@@sel!Ob5zC zdU_a}B~$xr8Kck)9L9`>FXM39UMr-z^If~rheWy4q>_4MEn%MzEklz28XJ-T9zc7T@jUbBaq&sHzr0wck7 zYW)5JUp5SAWPE`=^Nl)!+9(ac;BgIXjb(02{b4>$+uyZv^lo$%>P4rILVLpS0c^81 zOZ7tS&Z9F=dPhy<4c8a3$f?5@QGP84H!HO`mSY*c@xZ_pqyjBWEmEuboSOL zXp$IWE(9|ohy#%yK`xl(LKx1Td1=jFt8^mD_il)%qQKmCx~0)z%^IejL5IZD`DP+z`!i?gjprbEg_wj zT1cm7f_ss@L25RM_LS<1fs<%oDX)1W%pPGLijU@u$g=-L-XHT!m~kRJG^ODmXB{W0 zS8+9`;yO-JyW(n2S+soj+#k;0nExQwankx|Wd9giO6#PNSbsn3I7zY8I3mZ-qQq&; zD5G?$ToZYOBYUvaZUMAVu4C+pHbr@l8HS{tav-zTD4oi~v_)#23_E3ky;#kuxQ>&2 zvbdU4tl%V+t4hU~lTYI!@~nxe{duk~t!4^6v_tX(^1E>U9;>z%ArQmL_QsLL8Z{) ze3NlD#^4NRubsBHXOv6Ls^fY)N~FdcDKm`VJIoQ`2v9nWd^)bJEZtI~c9lXU4dqq5 z9{5*Ayeq>+UIk;I%-5oX=Ujp`%ghE5rDzVFkO-w{A>kU`9Qhl}q?4`TV`hVaw4i!i zCG#x6zX ziO54?CY^|PbY|V`Iz~hq7ip|?L{HnYK`U&vkLK6NBwXW>l%GQWjW%({CCjg&x4!>6 z{^|MiYeWRL-zS{1nlgAI+~38bY*E&-@zEwr1I|7mOaYrDF}N zh)0j!4E-eZl`OMH=rLy7$fDi5=hqPLq!?nG7%I*cX+=cHis?nnjyPK3rRLX&F(Afg znx3)$E4V)!UyiJck1wB*jWQ{gUl!xbkrnjJ@prM2C3ZOWVr0cAyU_Tujm{lqM*LoA ze2GPlFLCUX7+*26BA-fee3`E*G`%s5q3+`=vH^T_ltsn>HTsW^uh1#8QD#hWHr9+Z zD~>GjRV+T=_zF!iTlve@u?2z#UCQ`!beXTfSn;467tddl8zEDnyW-~*1f zEPu_###go$c##7|{u+6XdD^sJU1)q|qwVi&?Q!YKg=6Mz#o$8`rF-%G8kc5Q5mU21 zH=5p-F_=8WdZz2#R~%>4goYmaYCa??ge zrYn$}y*pMQ|9ESUYgaJKcyR^tiD@=Rsm(c^;@ab}-gvA%t_;6D$%DnU$7?tfYmX}> zc3*EiRwLiRSy%McGO+_{=_=#d3gms5tx+p?1@eonJ+Ae_S(|=9CE4B33bXraN6OY7 zSMGHl$JNMPf&5Bni7SmO3p)$a9~di;D>?UEd%XLqUgX`zL+m@#_Cem9-m8JFH00`8Fwv4s#6kMPLDSM z)soJ)>bPr(uiza^fv#S@k|$is3gqWsdwdmm+j9l-bJreU$L!%sW*;xU0=fCKH&N$O zRvljhomvAm%+?-{mBy9Xw-EYKT|zkIugix&El#S0LXD{VlFNUR-s2FSMuznxahS3gof& z_%8N$aevPh$X#{3`#R*;BG;LVUit1?o^UnLyqF(ddps%W#c6{cYdB~8M$90@2mFPY;{KE4{cQXOz0yK^8(HabYD%= zbu`1@M@v<t(b8${I&GQQwllXI+{u#*=m~Frp$yKR$4troC6Ba zAG3YMj8i9LSnIAi-}Er(?o+4Uo#pk7tf|g&^~?hto^|4(Qhj(==uP+Wed^?7#jL59 z#?K-nyz+gPP1&BZm$crf8AKlyed@Ft^~{>8rM$aOUC(@u+O>Lm*4c;lS4J_y!^SyC z{cp6YW&SvkHC0=$Ksew9Q zVU~GyD0L~Llbpd&BN~t_faa`JGPFOkoR!)El@-;4osnotedGEj&M7V6oVn)Jmm}l6 zcEI!Hth`XJ`Af@LDG%+Qxw3o4d8tYCoxD{K;w)#S{%h*t=9({NtF#AWEednZJFo71 z`EYvB88dsOxIUJ>sMR3)&b5TK!)r|_W|_DD?3>Os1~Xf}^I6XEITC$>xeuLL@Ln^z z$^RX*W^^+HqMp!ZSJE@O7hAog&48$_!~7ItO_o2=rk*i~0KN3Ce{1ScYT%9qjNfTiY1fG@z(jru0M9_pq9JdL1?b zo7lE;tr^(DHhjF=sAJY%*GF$-uaS{wUuj>f0=BXpPV2P+wbKn}PtP)WTL&eigkJ3H zpW_&8O|5K>P}|VHv$gGQFW90|#Ryy z^Xus$tTaul7SwF?bql+mV_eL1jEn2WM`RShCuEeNg6HV(D21?oZ`#7=lyRT5L@MVO zme5M(ysD*$!Q!Ks9{5{9TgXZ3(%Uk8mo|y@UJb0*$LUuci{iHbz&7@)q-WAEeWd($ z|CRqj+U38hWUm$|1U&KwU7TVd_|*ud~()GK3{98Z>ml2a(wsVKRALN<^Cga zp^hT0t7K11(I3qJ8eT)n7mgh9%Qauc5iv%}D0Ya0u0ZR!l75OEj#Rm$y)4xm$a$%o zxZoJJxAo>OPgtOZn5;I`(QfSMay&OuhfFnGb96b9$%MkcbBvY(9o5>0hXNhRt}s*v zETeV{_rw?t&tS)>9&xSIag22zqxNAN&nrozvxza5qlTkXU*Q;?wtM)NIXdNsj%c;7 z0&Qns*@w2cUglYLUi(%`FVFHV($CDZSL*5+`KmbSh_x^68?jNGx2IeuS8TUG*`5pM%k9s?zW}$PC2JFePwI`g_Iox(krQS>#O!BMPds$Sw8Xc^mC?9D*> z)vs+f#kDidw>>9e*&Oi7wKJUwox|P?=;7d#?WxCl7Z_!miJ2up z$A#E!eBWs9HQrC`?&L^}?gW#>baAo^%(3kQmovN`$GO1Y$=qSg&_wD_p-cdOLI;&{ zOyvm^fkqu=7#&y~_&b58xEiE5C;kR5_r&5!2`|Ov%hD(ie7k{ULjaAf`lki{6oepkRB|H@q=W<^qP;3v(EfjKKO=O@PK&#n%(q*Md z@mKC*PEG%-wA=N}1AnEq6{!!U^}#8Xu9ODkoyrp-Ig7t?0cDF`>=z2k9rD^Z>(xxo z_O8fM>S&O&#?zHQr0%{osC#^kUlsCke69b%ulHZX+Om#txr*^$e_!tnDNE{5!~au$ zu~%#Oe`;R#OvtGIOWRCID`gd6j@za z>MrHAKc`ZoR~iN5fa4OjDiutpI0`0leFkMJxa*qPGbz)+$Vr@)a!&$lmFQ#Zj}AXH^2{v0X-;#Xu?j@Rp&*9Ehyl)P%Spr;=yhBz|Ya>O!5}&o1J68hrMcKmfD&VT*MY5W+TdB7i|B*G+ z-A37jZ---6&yh;J+tyKI2UoWN`IPrze-L;p+r#YL4!oV~hbecFIpj|6`V3d^2Accg2v4}vJRoe3QvWd7J*1TP@T_w3 zZVcsp_fif3l?U!+?+BSV4pRF*o^mjEKlgtIc!cc(yyFhw9o&D6bDsg;O}%66-Ayiw z!(2a3d4QZ4N4WkF^~%VAag-}3D96dHaxYgN=3Vy!k5KQk)H_C=mItW&2<0I%w%o@Z zk5W#M*X1}@K1X?ktS)D%@(Az|>OIY|d2dc}?hNHA^5dMO z)-#kR$&&Lp&wP%nXUG+ElC#hAwv)g{wl8q}B=AX|@dD*(^87r`JumW<$I0_^iaTH8 z>8Hr;^Au-a<|$7B&A;<`?tOtwH&0OG751J6nuq6AuD+amjpsiPe1>|jB?;~|j-ScB z&exOxpJn?7HD3k3#P-efthcyQLUx#E*}ld5o+Z!BD_nn@@&>tSUgq38Tror5i)`QJ zt~Y_7XZtSi`8*kLUgp|+Joja?A-%$#U!cY-WKnA3`WGqhl27Svp7uWFRp6`C{t{>3 z1ine_54ie1d71Rl`!eUh1Z?8YFH_znQyZJsXWkZh2KwEseX{S_YXMp zJ#tcgkE0*(rr#p#)Q8mgArfyhu$eFWA?3r|kGT4S+>d$dH-X>e_{S;B)lWFvhYU(T zV*3;J>d2$?9j^UOk^+7w@&Di9_(z=i5jB2?Qbz`*?^Elil;0+g(hoWMU8L$3;P*NE zyX^gttVzlXzsDW@fWOT%elI=uXGwN2t5QArm43>VpHY5~98*dYKS#bV01G_j=aioU zf5w%cv-dMHRyj-X`;-P?182=)g~S0*^geYB*9hqc?3bi|`A8c@ZB{9*oua(2ls25A z1}hy_U+4o=Qy#(d2LK09qm#47+e^DT)2KHJzmfe8u5@x%omSnXi=s~3z}`sSN2cJ^ z3!`{n3o?+li_sKipEj#+L2n!#j3tA9H@>lfqmzAy4b4w)&b4Y z>KfI~Aa!wV5>M$u))40>^NwaDlu_(W;kl!bJJgq_^4yU~C+ZT@cRvlM;Ri5Q4Hpr z7)`4jr8K4fF^4Cpzd9b(4%Bg{v7N_p4mg7&y?pY(X>8~7eUpHbxN`wD%-E^~wSen- z^v+93)}E8(qB-o@KJt{g6y;3q2)2x^w@xPKl}-g53;oyOy8_68%tb#c#{)Pl-?N}IOgTFO$SHhrYmv9|!Y zmhF0;yAZgLCn|HUMuJ<(Ii=0@z;zsL;`|2SDz=*w1yKGRgp}u4*aF^<1S;)rp(r_a zakQ1ab;x$>c#4weD&R)8+u7TM47h=3Tu#}H3}}s=oVgshiS4d5(v>_Lko+83yD8zb zyq5j7NtX2K%Af0y;q;AG3f+Nhw~43h;fb4&3!ESaz`T(ZsSeY@#bwvdsp(j>nTd7%BnY{=ib1v zGUhIxdm~TZg_O6KYx@#y+{fAeNQYN*^90?;H_zY zFV9jsy&9-Qdpl3t2Mmc+Y4ZRzZa}t^J}aG)-J7eo1C>_~QbXxfo$gS2$07D^VgDA6 z?&K}E0S~cNUcCu;6HmOGvLCpg`wu4xR(W+F@}k#{@TR`NJJ=rO{9&Ln?LEBZ5bzLB zyqBll1-z5(ecbgK;9YF*=YFMAB~>NTBf!IKl}ME+Ln4*#9p_r#BsCrd9;V)d+;bS| zZ(Nc$@8Q`GK_|xnecuV5e;@Fnw0|#05A(ER!28%LuRe%ec!cLFwH`roJjS_4DW3&C z%+cp~YaifowkN5h?D`tXP9pIs z(>}r8Bfv*EQbv6o_$XT?)jr6D);q%!ltc9dIYW62dC-iA&rnVy>z(F~XDLr24?fNv z&rzO6YJ7rcJWqKFDepZB4rrxDUM#G)>BA|Pq2L{$)Ybq?I$7$DjmN} zc?LLrlu0I5o2HG_)EyXdcB&-v>j*$ zQ}bSXej3}aa&|ayI>%Z?`1T&{Oen%y4sGoTkbj~bE&M=sbMBc4eMEE*rS<>pS zWTREKgQJMdA4jV-v)>Hw(^o0vD{ZqK)YB?E0;rTVk$wHr^pJ1A3i(Yku= z=sBV^rF^AKHHtP0Pb$6ewZSSwX%!BcYC8Sc!hT3uEo_yqoH0;#n#uc=rY5j=8E-N_ zpQAf0PFkO|I4NCeQ#I?|RNgz6q6}a*qIr}#z&Tu<&wG@23T)@o-v!`QYAYS-`JzO% zFi8&Dqm+pBz0oSAS_LO}_IeHH&7G)RwuZey@Ze<}885XAxQ04P8pb|pp<2gRt$^D*x4oV+6u6cn zbLS5Qu4TJ{y0HZY>w*jF~$z}~uCq0o@<-P~VVd$of4{n|gZk@_FCVh>>7 zRfhDc(3YLe5^BrVzO3A-EnAzb)>rMZYGGPuwbN>&)oL5|TdmgWiM@G$DQ|XWCd*;u zi1S=_KK7I{t(R@1mUk6Bn9Xcx9epO15v^Uk>THqo+s^*`b*|4C&vZuLw-*Z8yZs)Y z6tycj@($0LN71=$X~x_IIwR zowu09q@1(E(^+RUoy%ImLg0hB_FV9&WsHL#e=bnYf*F`cK8LObWv%t)4&j7qIA ziaqCioZVD=bI!-vO=T_jheHpfF-U_3v_Q>5u0ukh4nC zo6(GJE#%s^$1omLMNccvt4n!;JV5Bu<}sT6fPpQu*njHWY1)7cAs zPP?|x)$%8`8coaHp0H;bZHrw6celaqmt z%Q@Vq$DUf9`8cId)2MCUO?4ONh32I@)m@}Xj#@pFU6t5)jrr+`^Le)PNX=sb&yixO z?<`DX)SN%Afo}B2LTb(jNOrJQ^bMQ=;}q$8i@B5Ew)o7C0x8qr%y z+{nC2#CyNKH}~nW(~qJrj{X;!Z;mrg&gRzu9ktpMJfjCs=5b+9>2aY~j=mNRJWW5F z@V=2MXsOUcs)DV)Hm>PrOKPdm@1lZjXH#o{wu4+x&wv<5EnIcZUyln%P#fpNr=k}8R@QKCr2uB<*y;^nc0pwaIkt8Y zy)GOBa%?jY$~PSc`h$iawfRnK!C?94DC*0xwTH;J%_SulHS4|pzd4Q^JHpYNab9RN zSeWOEv#EKYbU;r?Ikt3QJoUsXeZbkUbv0G~N5x z{*PXEzFe=F=;i3&eq4=S*4I#v8a=I|XZ3^AqsG3sf5WG+*uVO_*`xNX{)hIj-Z7PI z?OE5NbrjgY&Y8P5y#4D6fZh97EY<7H{*`jtzvg1>-oJXpX=RcYcJJRRdea`YXQiO_ zuhg=Nt^HdL?B2gsT(d``f0e+T2kT0d(4H-)7wv2N*ZJ%!w)V0#GwbE>?^ZgC{w?-w z^mWhvjh?la&)2{9efR#2XjM6ko|=W96^IQ8p^SrOL8yP$D*f(vFA9l z_w-`YqsczeGeOUVp`6qAP%2{o=-pHX6l;vmbu`I0TPXU>h-rm{aY}cd(e|ciLLb^# ze6vSv`vOO8e6t=+VxxUf4U8z@61I9KDl01|v_n(sfMTWAN^^FF<&yQM*f-N=J2mux z&~H*1!~CPpz>1MM{)fkMjvQ^^@!+(VPgE<<_vm@(s@{H^-d6E#`Z2br|0td)6}0nT zU6pzWP+6&tV*40jtX%K+4hKpfZ0Qc5E!GHj*gIm6)XA?Emny-MPGHYfq*~xD$~kgM z$FWo_i#Sr+QHB?HoXIwaPH*;=;YTO@v**P}ad0G18l&W7-nu&4wgu=HSqw>!ht$Uwr-W&Ap{$pl825Yukq3y*z9N zeW*UBN4c3G)g8sd>9l;zyF+jh=N7mS5z;p{|UGut-Kgx|&##*NV~(oB6k z^yFyeXcEv^m_i}LOYzT`k;t8tVQ?nB>RlHRB7yN{w-P@;8ZBZTIisNZpB+oZXpxBX zHM*x5EutTlSSv2ZST)8cqD72m6Fbk17BK^p*lApkv_QHbUQSLp7gR&pEAljH&yr3^ zN0tD)M~Fx#q$6e}$Rb3#fdmRq=@6`1L?1_nR%NXPtr*FtaQOR5jnIJ zRJu5pJ~rOX+=^1+`%@sukICqfSPjtsT0eI%7oN`plxHdcJ$(9bWO-#XJ3Gwa_wt=YMb9 z6W`GDUhm58_lo1%|525oEgPQ4#(+eNDYxl&>=zgdVk>&5Z}vFTla1R6Z*-p@kt5d2 zS|V$itnK{9tWDw@<3DBX>ef2v{uiH@@in*BC{OS4{^)^d72lZEC;>Yi*{hC1gS&`_(3a+}c#0>CO`s!TX z1g_0X)MYNv`L6L$NoT;+EA^w5t7)N<8?FKWJFw5Vih_2Z4y-}L*{)9GW*uicll^7{ zwj+7+D#~iCJ!&qlpV*1Dsg1K6I35XH&vs*?vgQOE$*hg^)y!a{n6KHC=;>ylnZBf? zTYzTwGB5mA;7eF_UuG_5E61+1GJtuW?ZD?b{}Rx3_FQR2e!2sA8awVQz*o5TIQy;? z^e)>cfUbV@4%-*F(^a6fjz7s6*H3zz?Nh)fu>rr$-qUQKVs>Z;&wZ2qr-81lq&52t zb4upcd4v6DfX`sXex0rGS#09YY7NBtt)2We$|-EvuK{CiM>BvaGh6{Q>zA7Rl|WZI zQRdhKyb7pXauv`lUS{Rmo1l5T%!+e0oW)FBC&9SK(s($@{LZzU{TxRpp|(v%%tD#B>t<@mOCHGG&-MZ4 zlAQl?Wyaf}*=Fi$r4-;Et~aC%?&^rH*;v8c(E*@qHdZk6bP(veK^2r%_=>9($#w37 z2E)>KP*}{5Mi8J<;W~KDp?FYP5y^zgkYUqpGX- z2WnZ>-(3yeXba<{%;KwFuCCqytYT}lo*9melrk!6Fi@;j#*0X)A@sA9`8dxn2bQPa zSIT{WJ=e7qD<7mBr&r~i_j9EZ-0}ZBM0t?jvwiO4N>#$T5?~3}?&WN6;C*cGVXqo^ zFWZOtzhYyaz0b0Jm_E9Ps|QnS+>v_n4)$F?$~F;i>cFGggiZFRxY8FW?l`kq1FWHj zxWX#SY=yR)*dVmsK9gF^zV8o4*kaOOMTB7QPYcI`b0`P{!3u z)hJ};TE{l)2vG(>GmSgfC7!f4 zQ3oZvo4B@_bL$ch+sx>fa+uXmsc$ORrX+gboj%CPL3hB6Us?k znQ46w`k-vQ7Y-+lY)dqxEztpG>8s##($V%rRoc1Q#>gDcnQ@dW;c8pBGMu7B7(8bj z=f_g6fbVVPY)9fe@}(=_OH%F;i3^S3dKrh~S!Mr{#KE_K;q%!K&c2DS*bK%m;7le3*e)9>dV-8(uQbW} zrHq9|>?_l|dgv0M+I=Z_z6|Ipp`|=Ysch_q9B<)1t18LVE(WL>ezCj@e_{?p@VKow9>|7znIo ztJbK6e;~EB28)f}W4y1e?d+qok$GCn7;-tZtr(GF&Xvfk!@h3+WYMc(YuCzR8yZul zj-w@B4zG;Ty?^ZG9PhOMO4u5EX^$FtYYedQm`VcX94H0K{f%C6R#Y5tZZt9z7~x{H zjq{@s&nY%|uk(&Z;H!mY&-5Q=Pw+ov_d09o6JplYFZT)FZ8X1cSI#Ksy5FXp;asNQ zT+Na1*E+4tQB5uDnt#J9WzEZ+*E)A9C3f~yPB8)~6_tZ%@6aytEPO}1iMEyr=rPZ7P9F^;JheSO%(>6PtF#QM zMLdTL_8ey)<>)!!bBy56u^kMbnn|6L91TV$J_%Ht&7>jaAZH_$kDT{2mRhQ3y!`;A zXer|<%21&6@)V^JD78IBX$DG#Pf-d$>G&y18&JxAiZUEHoM$VO4+c61rBtQAhZ5Kv zih8hiF!NFA7j=p{X3VHXb3D!d6O?-3<7~|=&Yb!EcWUhq&k=haA!u9|u)TO~)m zPK;{W%Nh0AHEI6 zj*M^ecrat21Na=g?;zro&JR=5#mCxrZ z4+N+1uGowBc0d1dXqev}cEarc6bkM|T&n&(zDZvm{d>$s6B?;rKKcU48}#zgH$dvI zKY<AJ3Kgv|O9>&CGA+ z6myL}wFSRsVrm;_f7Bk7EL^E?5|rFI9&?tdTgd;k+`Cer8R*P(HWf^kyBV3FrlQnk zHni!`b!nox($rj(qFkv@tD>@$EA^?PC@mSOFMV}hMz0s`jY@>(qcZELUNEl8XM}>Y zE#{qybyDZS8JtOR)fs(OTsukM6#Z13G0|H^t=gPm=8w~|>Ws;fobw|~flHuCW}RCG zS8%;PrM~6BWl*`cMC+VaQF>bebOxY_o^rNEPHh$qXRF1dEVs1t+WHXn1=<=dsU2E4 z&at24o&vp90hBK*OP2Fa+ov_POe=fNTO3{x*siBRcR9fJuJ++%MsPgDQ>M32C zZ9?gNIHek>WZRKiRk}1N{R{oKjPUQ^PCZVPS4L1=?NZ%C?}Tdb&Xza&#+gntf9RE> zq%fE}^-a;cOKH^l2fg`x$Oo#YvR8OIxH-V8qwp?3kxzIbxI8xs6|FtJf zZ0B3_brlEOxyPIua`txq(-6Kvd>o!IFx43p)9X0I3 zCcey`8IgL%>;;jJLp@PXTBRIU7glrZOg-a#;sExQ96GtnmT05TyC~sHtM9D+nZ+u_ z9HTxfF(YjBl5$qk6AStV=pi5u`JFkwM@;goq%`7_qetrJ8^n$>o*>@%CFS&?Z*%li z@DAJ0H|qN$me|`>w3pamPxhh>#R>aU{nK8z-^_wy-`jioJ&6I19=&_?v+&FOPNiN~ zjFb}k)lx{QvtOP0WBSzt)7SciWqgfa>lc>uHGZvMs5gmU>lf->;@A3xdYAaMexdrX zU+Wk4=4<>~ztG%Mer@qP)qwm?XCm5>Ewp8I@O{!!v2+c+)CzPAuSuiX*cc-kBjq9n`2wcor zXFZyLO0?@Ki;*h)Pa8O+7wmeDHbAi!B5~*wyD_!IM$WiSiY>7*NuV2{Z3~b*=5f3! zwc@7Kep<%{b4F=(6J;I}iEVH6%s`-4z|E97z&X@#R;2++#eUmDz5c*ioZSLdz6_{E z$=Md?S7x%eHTC?~)aP2k>N%rba4Tgdl8^jg8@N#i)K0aHG95Ub8qUk~MN)DcZ>L@@ za2wn0)Kr4finX0G70F5tbUF2^fm*aKr%VP;riNCt8YHpHsk4L93pkOZ9dNJ-Ksne> zu%{9zpVM~M3pk$b&cp+E!uQ4_H(8cSpkC9SPTs(>H$Va<;puc{y+a+udm# z>;|{ju)l+&E2y^v=xPsFQtNV{F;{!Qy#>GpoV$v;Yk-c0s}fclGo{RY1>38+BVwkm zK%U-1eWRs}++WDiwP5!`pq9GpxO*K?{J$>Y`Sm>IDkN}o09?uyR8ea?&l z#y;JQR(A(`pW!{X0B_;w2=6fuz^$A+$`fw`-p09m(&)J-jl6q!%UzstPU7A~v+o5r zOW41gBcra2@;}Vhn13Uv4ze}&=^(ntA-2bO>LK)wqwF2$DMx{h(c?VzPT&-_5AsCk zVB}5@@@(f_?q>TC&%PT?2J(BqUU;G-Np!8^>;oujf1nnV4=DYB?{f5I zp8hWIJ+@!r>F)vGKEi0o!@X zwPTkfGq4JmI_Se+T$gw%WAoC_^bw4y_C~3MhwO zlg7;&t|`yS>7Aje0G4xYZ5mH&(@0g$8v}1rVpzv$ssbt>tV`5l9cM$H8wcl7+E9j@ z094Lc&+$4qj`GTeB(EsLIRhDUkxDHaxMuvca?i#j_iSWOE+sYHm}s`ro^zYZPn(kb zv?)>XO^H`*;;eGsM$T>Ks&bnW_~s;sDZ@=?Urw?)@v)xrTs>#cmFH%{Wt0oI(x(G~ z%7t5#M56DEd`LNP8&^Yao5Q}c`ZjuR5K#GYTaqu8O6DO$D6wx(66$u2=d-Vbx}CGz zkSmmNFQGu`k9SZOBVp`FP-%N-lD2oUrzEG$y)#Kn z%4$oIJ(SdUF%AmA7S8QTlGLswL+$3g5}SJaZg8sus3x$R<2Il+%-uY!+8n3drI&^sNs|oravwRhiqe5IZ?nxWExh*mue*f<%ika!ecs+XE z*YDrBCgYo=1jZ%}02iCMZX~7tpz0gOAeqz7IFHEQm}O}++k|mP1HmR+V{&SZ$?QdZ z(sh99!3WpN#C}Tg`7b4s4pjJ7=YL&*oib>@vz}PI{l7xaO;qTh8VAW?(d{-CXwc z;5CYBUV5TFX_MJEx5Ip%Jq2i%JY$!p0-Xn6z&W!jm<2!$8^PQR^1x-()mPcI?ewuQPlMEHImI>V%u}(PJtHs8^%ZN; zt>n&HuuWcPMlW-L`9$+7)Ih&VxW`-yOMqq-TTQ(>puEexUh1(cxNkK@9aSA;4cGbs z)f?7Oq<$sbuVvhP4?aaoXwF(K7HUy}o%Yo*zIPIs)Cg>(?X&zPO&m{2*rFeCGws;S zHS-f1s^wi7KsbgMFv1^N#+%tcM$<-C zk~utgJgq4X&ISKnM|n7R&f~i~fLfxAuPyenPcfP{>skBJd~JGr8%L`bdd=B>?4V7} z=DCDoZyF0{){W`3zWGp=Q5MqrbNGhklyS73s}HW=Ip*G2%#j{5OMqh3D(*77o4B-^ zyUdXxKCI!HOMyoA8u_{aXe_O^fcZePb`-N~tcKR>F>H>FaX>S7WPCyTFQ-@mG`e;p zdyAm&D|zZBiuvBm0JoXqnu3w<%_nZ$Ho@mdbT_G zf-%4iYn zncg;|%|*Tq^TnC(&3Tb6++(Jcw^GX%n5fl#k?A3=1>bfgubK(`5B6u z-)+=5!X4&xJHXLVo^TiN4z~Aj=YHUR?!1?`b^#Buy^nX@3A~-B+y_VL54@A3`?*t1 z%&Z&ge`bI?%pK}~_o9W}k#s)w&j+a!8Q|_l8#>B;4^h;+4paLCcdFqjJ3S0_?FGD- zw?9njjrOIa@mb!f<~M-tXW3KdGXtGjH`KVyrST}wIRP|p+~;^!CGZ$eQuBKl_%P>A za_3RtQNG}@bmuAd)co#G8lEzqI-eQiPOv@Ao*Le9?s*(8J`gyNFEAU&akQgHc!oOP zV`xXGxz`LFCxB+{c#0>V0;&Z*&G{#RW|cd`U1sKZimU2qkDzlYAv{A-2Qv?c`Q)BL zKQa&9vy`XNyp&O&;~nL|C)t`YL*49Iw(5Up(2Mj5HdjVj(*K?Ss>!{?RXvcEzFwlJ z<2}PUbGxa7JRq4bsu|v10h*QWHJ~XNn=8O0dsZ(b{YLaP8B87h zgG$(wFKR<81?tH>H2r_I4zZ{)VPkE|6Iv1m! zqn}X=Uy=j*FPyhAGE^=c{>jej3}9c$t%YKiW%VbysdGO1Lm4mX`nB>$CC-R0ac*fj zXN+9S)?ha(#knZsQWmq9t=Xl`@;X(Wy->bMS)(KpUn8q;sYjS)7HTf|;=rqftN z@x&QW!{6;n>g)Kn z_51_1OGkuyWjSy(+YO0_%DG)b-7%v6Sn>a}_ZIMa6j$T_&g?#McS1tkAxH!gLOdiu z@j!rL3Bg;6ySq~yN{hP}r`{sP-HNxkYl{@<|NDK0eeZM04G9I>-}`^>y`MR=J3G72 z?#!GsXU-e}%2l{dYzma4UYinEj`ABbId2YJn|x-K+nGuE+RV*z#p}?*O9E?Ss2fv# zU9K5JT^@MdDj(?D(0J7tymrj! zqscd{;^u~ov;{{}H+uTUj8)^Qt6QWLz5{%N*qY*|Z$kOT92-@AQ%XAnjkLZgBVWxB zad|e$Nb0pQ)Qzg1;-=35U(_H`BdC51bt9{92F|SjpW%+DnkNlMQlHD!&B0dVsjJyt zMo(9Ql47WD!PU*-DWq##g6~FBH->tOr@j@XJ>f@`yKe=RFmk%~8};LqO#(Hf$^=+Y5E5esdr&Q|=Z7)*XbmdR=aJ57%+VhP#(#(#1NpX7}u)C5^#l5KYF?=Dc1~xfUZaM ztvH5Wbw#rRNzWS@_e`kL_6bmq{v7MS!}a8{z;Tq7o;O^TOrpMC1N8+sxk~vb(nGfa9y%I_fO?6y;i%XokkxSL%9#RHnmzes-5P#bqZ}Cs5_n1a18Y+ z)GgPo>OiEp>H6>~BdIqOLw!Y_?25Gq&^7Q6sQ=Aks88n}S0k=q78E^wWvG{43iTGa zDzs|eNa|{h&4lW80lE%ahnn9chWae-NL~rofr72eZ@7AKtrIwNW#m4aYogjn>M4f0 z`)un%i`0tWi2L+P=)9Jqrbiz<2Aor!6X)<0Y0jpc zxfXK&&6&%+xYg)WA0XNgB`v6=`y?l2Y^GAPK`u{yDRtMS zS6Y0jJs=;|kmFD_B-MWJ)I9FI`i)tV#yC$#3+F(j0-Ir4fFKfn#-0 zR-#4p1J;Q&gLctNSZ6S8MWEDJer`otqe~U0NUmB@xUQH+`#EdK_kT5>>m+D}-hkAq z>P{|asc!{mtHg0G#?kmHCpv-FcfOND9Zw(h;{8yuw+E$G*@6~IP_h^iH-x%|L7+9qaaZ#O@oXyoQb}o`03!RH%buLm)qn@&Q z$r;I=F6Z$fB=@_VpNEjT0G*@tt)fR9=W64VsVC|Tug<7?qIy~BNp7^Y!5pdA*$${A zrhk=3=+EtWTHi9xVfsL-lTfMSt{h5z_u5%4`9k`xWK(rg zsWi7WB%50BeAXAt?8Dd?PR|<6$sJ+iIvHz8FS_E?GL&cwY^j#O#^=-5?kMm;|3R+A zjaQ&&OLvm>Z`qet@*daJ?)?qo9(_={j#g)Sxhf{O`t8rL(a_3$K-bq}sqfz3a^S`C zRSY-2Q+JNFd0C$1KAtP+w3=Rl`mUf|Ve5md2hi1ltKUU|qshl}P0yBTHSNlJB6k^= zz}0~szT}n%b6Q!i2<;ohY&Zz+ zYt(0!%Dy4JZu6EB?Z@aFVSD~I>bca>f z&QilwNo|0xt<_7`f3EwEY9#AV*Ii)skKI)q#+_?WyDd=q=-Rjq&^=)H6ITN2c~{G6 z<3z1N9koi@16^mitEcDvRk)&Mwflr=9i3Lt+FYyS+YzYuO;^Qg`YK!0yMFTJ@7|)m zSoGh&F3?r@`qXX)l!~f@Iup1qWv-+3$iEh4Kjg0USl3E>H>}cO_x#jUU7xaY9j#vK zM%?Avc^LO-Q$LK=t#Zgss_q!4f9J{wTm(l_#{hUi04xGakrFl7U3C`wHx&+W@ z0^0M+e+t1GI9{8xb*ZDxoKk5$_~_5aR&>NEd2!ZNLSw`-&)0)? z4F?XVhSC~GUm9_<$km5dTC*g%df;k&JF?UdUy4!TxKuM-ZSXYuT){i;lqjovv?1qe zILjRK^$D<=rPQ)?T2I$yz z|=VlJ6v_Rafiqnp}HjE?XIdiGw$WqQd7n->&P>J*ARlMK4iqpz$+9CyZEN(&4 z8d7QZ7NogIfW>&DmbFLnt4vvY$t{6nINJ(pItF>LxV|-|9gz2qrBrK4?J!-JZv$;y z9;h_gs1==n@^$+BF?NMMe||)rZGf)wjV!S((q6f~A9K_hDenrDZb#Y{sBB=nYK@;% zDdkV9l=3Ik?ZVFWc&=^Fu{Nqo6t;)DP5>%9-l57j>i?%(b?qlgM|X z)*?W8OXE)L1k{FgXRhuDREDuLw0AOl+;X0~RA-xAsMno6@tru|mFqhJr;zUog`dJs z_b$vvyH#hT-6`9J-SAyF-yI4)6*!eLF(r zRp;~lsMm+xaCfct=lVXtmC5(#Xg~JW_XFb(APoS@%^t`VZTvbL7)STuoF`Rh_Hk9||= zml8nVSsP1tFO_UakF=}w{k5@7UI<%2QQYU$y3&17c}%S<W^p#sT0U_oLOmSKB`pQqlrwh#+zn9L=BzLW=uV}3iNd+m z+>*33&|P^opyo0MDBa$QG29&3jQf)Hy*r9(UAY(OeBiONKtkV3QIFr8X%gdGDZX{!K?pB3*1e5Yh z?RVv_JxI#}ofGy1C))sBNAAgynpMsa`uI{mOAU#=IhVHY!I@NhcPMf@uJ23Qt4gUo zb|%=5+GBuwlj|vBZ>X;;S3ThA=dK-h9zZU1R*-rN)z464N_xH@X9rQ=*hYFy(}#fZ zJJqy0gnG*ZrS*r9#-i`!F2bSEg^s`u)IE%JFz{e%97fqeXiOc(@!_Q9f$E4HL47s0 z4&{oTJdEzCSGA)^6gBm_VeC(( z0LPLhpo!ImT1MbJ2HmRTfNE783p|#q`q)r=OIh~`B=xrRoFas;6;4PbNQ=qmzIqQAe*0YI3Pza~c#-e-7QKrJj|ML5=Ha zOi*>OPNj~%B2PiXN~y*fTs0!nBINp!JiV%mH5sV9{}-J945-%Cnb6YiKxHIna&!jz zRcCNTs~YvT+$B(ZYYNclo@bNP;d1xo9Fp2wXL99Sa<#YA&pMBLrUBI=I*&W10@eOH zpS#XMBTKK77jSmYm-<;o_*{`={ZkrI>3pENMHg{o+)$&48Ug7-;Dyw@gfdH%9$!k$ zi-7KET*lGGz)Q)EpJcS8OQ>@>XCABVbUA4y>}D>d>@qB0QiP;F)ViA4p%1V(Wm?r-iJi+;)VzkHtANJ)yoU3Yfm#4xOZ}^XMpC+t+^C}0 zP<}l}*8q(PdOhbqz?w!W_zlcA{ebS_-@y5`*wCntd?QEK0S8ceBT2iR8!5S|%17J; z&oGGNft1}usS!!9=b1N=23O}=_Zifwa>rp_@5<^}>3_MtkL7v2E9-MvnN}ypv2(F= zbayCG@(J$j?@aCfoU^lfSZZVG8GI6D`a_UgQ{ts&mU1v>aOEZPt|KUy^N`b!OLl+C zxm!t?x>|Z&?oC;eq3GGW&d0KT!1XXal^W_IsEMsMm-D`{#r3G1JS~^L#?|jidT;tz zcK1OouUe1F`dC(n!Tkw$Zur2hN!#7swxmT@C&RS=O6|KO z`(t1LoK70 zechkFE`Z5vy#6n`R>y?VF)Ebn)xmf(dWaZM?f(H>F#?D?2puWcOR75y?%}7s`$3F+ z_Z{>=p(h!=PRI|rW8pqUE7Cx4Zy?tk3HsCUTpq=UOTMRX*{u48$zNHs>ieYVQORps zldN}dWl;L~(z}{_63UU3Rn^L+lC0|M>&*L0{<=@|ZN$&I->j8|)p~WS{Y_V4w)o=o z(-PIM)pwFnX2dUk~6wb9frfUfS8O6NeO=Gq!5@m`91lyWQC9!(u%^BRv=8lo22(m-uv)D~0Xt;N*x z)K{|YI&d7RIWS4N$52+vx@&dD25^t@3t9ljk=K`RD?v{>W0QEY+G0{jqazqSLCJP0 z<(|NmQd=zPi46eLrZQ%=f{_kSBN>+=Nx3IeR?51Sm+MbfS@#g`nL)j_K<9v3`L5Ve2dY)JD$ie;^_sKPYNSrURXD3J->%gV z8&X~AxprNX)CIU2ch#42yBgHurPLN%n_tm7MmfAuYP$jJwLhE&&h%CR?~p4N*=vOSA4Bi8DD!FA(?yo2&Y_f7RHq34LC zA*M{*wcnyZXXuTp^KsG^Q%`JNR&(0nC}-3wgKNZ1NIikh(3_BYv4&F~xhYR}eW*mj zm7(!#H{t4RQg5L1u>Q^04i^*t)ncS_omyN>+M0SwR_Y>d zrTwK6FU81&ok?4>VT=?PYq3zgti?j@%NoKz@zTiA%5F+56kijz%?}q#EKK;9aIqE( zhy4#0ijl(_aj|h;WF{^5eHRW3>vn$^1{dA&t(y@W#>HAJYLT!S7yigVWhj}{~j(b43Ao3WZJPvc$si9c@g`jJgT@{pHodUV&YV5 zdDJ@YR1S7_#tc$+sdeN1lHb%x4pLf0J8nJfO*wA{hcBNRS z50%!DS`>Yg^e&{~V86V&VL_(rIP>zW$;PjCMoj$byz^p`+9Zrjt42A}dGRmdveSln)Y{#Qq^)1e zsX9B>m!r;aAERy-td-i-ai&?=QMv_|112)Bd6nIMPb-KfAw} z_7rP(8Ea)XU%yiPIv%z3Lox6EqPr7Gj#|6dSbvvs-u2>I+*7-!QQ~4Pk6MS9^ItF4 za-?5fHP&A*)^ev`n9i$rll(J%b!S6guV1HklV-%EeN#$P$AVePQIihN{CE6o=SB5s7L1Ffb!i<& zt_Xf9BQ0^UR+^eLaq6^h79JPpm7}g+-Oc|xIZonK>u@pQU&DGg4dGv{-c6bvllIM5 z_xej*teqE=998W6zURgH&xj3UVZu=*GV0pQE48V`#m0H@yO5*K%cDBOEu21FEk-84 zY4h%BIBVAVO8ahf;J%JWofj7ugoO*E1NYV0u|9WNi;J~7aN=CKr!lW4T=I{WaPjMA z#8Ts}cGXz7UaY@TY;@Bf6rTpH}LEX2fs0zxdS| z@!#3a_`03NhPczOYNCGKyr_k|JnFo=jPv78=f%P#uc_r!#mM>3i)oFhjHbT!Tf$DI zIrUeK^OM~)yi%+$yJ>i5vA$MnEvMSh{$dw&!?lmnazd@);Xt*(-QiU?yc62m9jhAN zYK12a@ntBPS2x_q80ry^AgLR!R(R47A4Pq2!{_Bu)e27<;z=t!X^89bSl#f2=TY^U zTwgc5PAk0hC#omW$gZq0H>}!^Y>3u*H*m3(7 zTraleIN51vp-~?fM^k?cBeo?_JDK`+8d_*1YmMa@_2QydH{+}8H>e56 z2@B(7e`7q$7B!996ZUQ_%Jk2-~Ss;_sGa8au!qt58l-1s&1y%Ej3*Pk%bHOgw- zxp);LGhlsbs(bwj7qxcKNBL0TYUB%ti`q@jIVSz z;80>`?W!@^?kAg#5+euv4@PQ7C@!jxT8D)t&edXJ+S$;CY$NXJS8rbYs)a^hu&@s_ zWfN-m0e_OzM$F!nRELXNs?DaJb{dImE$7JI;90^*t<&aEuP3la6+35hHV14KFVkNC zO0cdn%(YMa$M2 zRFAL8XWL}nAo+gPYT9_)$!FU{zDutVS^-X=C6isC_JMkq&}vYNK`jWi`_|utalW+# z*Zy3KLv0X^BVb%`ZQ-;H<7OSUAn0>ibX)c=N2*0ruQ>Uj%rQ>)A5u{T9XZ%T=_bMhL=r$>sYuE!63 zBD z)fGv;r*>X}6nQ7D!!lB+{+_?ylHd3D{Ph-``+NR+bI$!ef4v#!9r(Sbz^0t*cclri z3FqyqU!~s_`_6A{OS13$_BJH@&NgXHvhQr6RwUoWQd`t_w6;{vclRmwfZwF27p*S+ zR)5u&unl}0TgcY&Ep0hl&9}EjZB4(*mbR7sTHC!VZ_oGlMk7i6rKfD4WrT0XmA}!9q~{ucyD7^eycrYuh|Cn zl)Yx#*i-ge{rZd&@c4 zx3IUIm3@oa{&E!CHjZ!oG$%VxeNyW4Os|)=U20FC@qLVcd*0EI#=^hfp4wPSyTrop zWBkvrJ#8Ji7JJoxPS}`m#kLn?91-@3nB?fUuf#A%zh5rqIr{BeG1Ad*pNpxEe#e3s z?C5ulh}n*Qzg3KP^y}$eI@Gq>U#ZX2DDZcUPw#v9yT+&YJ^Wqc)B7I&uJP%84}aJA z^uC9`YkYd&!{0SNz3<`g8lT?x(3aZx^uC9)O3UgfbF42?eX|nRzBz6DuEvJF;YfA_ zCu*)AKgWC;<@#XFtH;t;d(k_z&emIBoX zs=wBj){@>y)7sHmQVVHXds@pclcsgxSCTjV7UX(7bTs+kBEjf{|HEc@8+ zve)f~9`ehl%fj6=rJCh=B>KpmidQkIC{hFLF^9%gSf-m;V{Q3$l z;TPK~O=uxo!qze#mMvr}HlsytIa{|mEp3b1>MiI2-^ku*nI&J!@~f@jBK?9sl(mNE z^vmRR+rV}D#q!B|X70yv^4cti+8#dD5!;De=!o^ZZEa`Cg5VbWQHK5V|sVya*Gor{{;{58KxFiA{j^ioYaw+grYY_--%y zX3_zB*Eg0*G_Uq}bBMBjO^_l{`-)A)e+LCp@H2*dfXB-XX+m~%9#Y$XY%WCU6 z7uk}DUv$=zPfIg~^e^$3i7tNAHnjDm#kS-(Z9~7+@si@Mq;X_RG^@6rZRmSP-Zx>B zw7{sm;*t0yHi<{#lh`C4iBDpacqBfFP2!RGBsPgh;*;2vBI1cv36I1lu}M4n$YjH=c(Gy9a)b{er9eYwPTf|nan|+nBqm< z$olqpQQN2XW^;bi-*JWE7y50bk4wL~N%cMb0;3`N1%8=PdHgcJ)Ad2(;C%M{@aX@A z_OvC%jns~o)Ld)k(^ zr0r>2+LE?sS}CW|^xtbw-_*Ca1st7zmEZJzkI!1V{av-EUV>~@akOrRs88n?W_-?% z&e!6*BgI)*tat1vHYRW^(az^Uh{+_leV&?{zkl!;tTFHj}o<_d1)2 z|MIBT5Nd0-bIAt+alxlX1=ecato}-*siX;NMNM7=O3fclNtU z2ITi9UcaI5{ZIa`vWX-^NK#@~D1NWpnOJCRCt7N2>pQNjp$u6b*A=yxCZ4;ZR)(DV z)fKj*B(=Eng`>uKQJJK4#CcKv(9t5tCV!at3OTs+i}tTx0n0s<0r02#Bu#rL?x47` zoeo@>Jrws&(jJQ5(91m(BX^d2DDL7kyoci6iImHzH}l&=>HI%?DC3}s-~AqnJ1An2 z9wlq{P~1V0>(WPg?H-CdD6SCnXd-hKjU7Cdnd|61_6!FWM8?y zPGjclW%9LqD77;Ah1o;-uH=M{PdV4bw>qoKfl4vu>-CW+N9Fib5^h^LK9jusyW;kXf0VgpVso0(m#JK&7XB^$%Pp+ zju=}`uDR|#m7XkEzFJp*{@+!LJ4z93!-d^{{5H6wgrwYmOw>Qo{6zh2-!#Le**(p; z(kp3xqW+2IC+eSQexm-iud|N$l~(Mjr^Sf0r}n===Iq;xr5SKx`nvWTl@_?lb*<~z zOVWgb){xgpYh&kM?-5s09;B) zkTXc!iCz*bB6VHrO4aqM`$~>^amRJ6ttRfczICV0-6Z#w+E?2x z?JIp7Jgt?b*Y2++AInLi?%F2t-;RdFkIQu@?Dgx?&Uxawf6rg@+5VEP;IsWbe=Y5Q`gGTi zi88uhkhCt+u6oiQNW1EORceR8*l{E}0v$!}a61AWMecmtH;y8A#2takJDhtRf&PxN ze*4H#Bsb;=O#In5(c+Lkq#b=@tc$a@le@^aoHKX}zS%ZRd(7=Pa{c9MEbZBdWA2IA zABk@hx04JgNoJEwEpfhyZ?kRF4!LW4X_yh5+&NFX=}Eh$mUh*SnQ!x+%2E=4nIv%w zdQWjyO6BNEIzA=E^&K7C{*`^Ibi&?Eyu`P8&u`kEju3I#mGt+G%eCK_R$_zr=7C?X z(6sd&L|dhGo3Rj*R@_j^hJ2|lH;h&tTGgLRakGY1b?elyvz;AbY2Bz!zhiGn((o@= zm}=_j@7>ju8hlHAxgu4w&v>R{w;F%Te7S;E6L3UTFHr43^#s)yRBKTELG=jLCRDF5 zX&D+lYuPWg4~?F++?QI3M$a1a9{z@zDA=O@6nEtY#QhzN@&y@Yu^vj+~y_O^b zU*BK$mKvJIicj(ecW*I&+#DO&IlXjRfhHEPM?oT;lX#hYJ$iCt>E8e?T)`l}Yd z{*(RXOsMW~*RR2^`Sq9BmE>;o$FJJ{`lk40M7lcNYoqau=6u;|e;S={2Iu0XQTwI? z#aCnMtO#^m80Bvo&^RYX|CG^)V)^cek^bxP#t=8vDLv=tG)x!*}v4?aqr$8 zd$nKO(|0Fdt(e4RyED=kY9w#tj){8a@;L6K^ady7aol0)Rh_Ytc9AktXE1kUdNLwQ zZ6sx+@;L6`EXp`8wU>;`Qff81f-AM1x-m+evDG0mwqvOsrEQn`MV-i9`;>f+I$a*S zF0*#SI=!_rkXren9N0I}=~dI_-_^mE$5NwAK1@!_{b%{Ga=+Vs2BjaavgB`EF}v21 zzft<(T1!4G?Wwz_sxJd^Rhsm5{T=xosfs;O0HrFfd@DdT8WV@(`YyFwlCSs+{$|>X zN$;XO#y65TOcMI^?(*z@f!~z&Cj2eA%EWJeAM(KOqYWKBa>{Be*cJgO?^7#_nBTan zl^NE`JjI;EK_@wdJ@M83eYrh3YlrV|)iAH_x9#9uuG~((*d2V^ z!*P|kXV+GBdh#n(>&&Qr!win~U}3vWC(VE+`pqknrb82Li)o}4p^46AQ%QQRX~NMI zo~cb$Q;sG9ja?@HIEk-s1}$vPk$xbJfo4CAr)63Il`DHvWeoJ*)t3>qmV@5ADoZigMpfy~C`v{{?>j^P zwKYw4rz4^C&TPw&MnLK18<(zfj7xK5+#z|!rAS)1b+6KY_pXPNw5oGvTcXM_F2Rwr zKu^wxL0@|UdsgZHVpaMtH-fz$RM(hT(tjgj4Td`RhTiw7(tr22212`~|MDZwYtn!D zM&Ra{<62>1h-qGXj}$$x>`zF)(pd#&t7}n~|*gG0JVr zGG1N%NOg-dW}T;-R%h<|QS0oF6t6Btu#ItTS%>) zBbEG!lZjfn^U;>CXjz>%)a`fVOHY(2OPif%TGH-D9$SRGCDy6NuC>=&R=wit8`lWy z>vF}oxW->MZi`m4TGQ#x%n0z#y=CNhv2RV15#`nAUz3`~?9Is?*&P|7j$X%NZ(3_n zO8QsFd4EcKaO@biHC@+et0oWP7*^wT5NGP%4&vBW7*K6fSDnVaTAVbn+P+5RN+VM} z-Q_47$Y^v78x5~BW6g1{rCAq7*=UYOk-9P7Mpa=q-q;<|HNnvlKzBvgtkQ-hfJRuB zek@VN0hbbst*1)FIbEAK+1Y8wASgs(aRVl8XgN(K;1yuLd zyC;$h{e69dO=Tq6Yf9*n*4ISFhoi+&qC`#(qaDdPz#R$c@I?B-e(y+0;QPh$aX{Ne zAN5+lN=vnvl?F&ZCvY?xxGb$afg|~~_O!|b&gFt9(8}_?%aEjxQc)$W?dg-Qz!8k^ zra-Cx2+}f)Cs*Gi!GR{gCX_nHx&gaUU+USuI;z@N$6R~*L+tLuS$ld&ZhLXy5{xf7 zH?>*YGnSU3bSThKUfqWci`B4??Kd*Czt*zy)@3b7~O(H$rCw=9DhUv0vtjVp#RdhXRN34#W8tW9|*-jr8X=n3_xSj;%RL`VzgW z-_@)76}_tO>^w7&?`ci$DnQ=fn2buh+XI~|lWwp**y+pOw70s_`i`r`7&&c$t|08S zMS$u<^x*z>K*xp==A{Zxe};>)pG&A~hLMEgirc_?~^p)$Qn0eP?GmsmTDY z8UJwr_xpv5R(p3K(0+6^HIR0ZvMfPz)|F=1R*TYVwv8>Te+g&p)WWv!@M=2?hf`CG zSd^ZV8h5OIccRaUGMBn_YP`F1qE(BU%E_ulxwdWRsBceluRt6~qu)8FJ1yY2PCFFN zJl(--ZC{k9i{rLyt7^L@dn%>Pwz5x7HS8JbzV+-EdDJxW9BXP5E1UKmx{=xfeTSqI zYyXH_sjs?m)fI!^TKko1CfiF&o!#NJ-P>ZroD)%eHqdD0voo!w^)RW;v@y~3MQP0U z2vn1K6#d!@*o%8tueR~(T#59Sb{=v%J%RT1&}v@~t&Yv1)xI8D?en4Z-vF+PWAa0T zfQ#|O4S0vyz}fuj1|;Xa)hTm6(T=?hzq2N-oGgypf>&}JYf+Nsgm%n%?KyX5XvYlL zo^$7icFd0LIbVvS_Q0jdm*Qw0M$b}JxDIosGlI~l@y-##S3uguA4P!XY08Zk%6n-MDA`P~WU5`q4rA3Y=siS*=wd+y$ z1Y9wGbv^3dt2=^XMDyxh>bLtW>#IrQv%Je4Td8l-tSRquoVauCeC4c^^dr(bKkdUN ztqIpB?m0+VeUdsk-skh=svPs~k*DXEx+KvT!V-%9JAq>5_e+#GTTRLlzPi{ zlWS12V2ep#(rQ1+09?^JPf2sqYCp*U(rRDXg=>6wnq4!x4=4pn`~L1pxyBUJwMlX} zPCWr7DDK9oKcM}MyK(9jBrDUTZ;&*T+zU&)a|^dGS0_iQ9lf=3l)BNIAT8Z$GZK-w9{AaIyU@WQscT^NBQi!zEkF7-`Q(o zSL(sKzEg5zuZg$HlFGibZR{`QHOijsH6>BXQ)=Z6r46WimD={YH>p%dy@TW-z}a8= zkn}{7URlx;Ng5%3v-_>~s(mh>X*;_+D?M?1+KTpzBQoiUEF8@dU+Sn$q8s*|&n)SN z&rG&K^`GfmeU+L?i{|%CpYzox+YjI0ICrkLy&Vh0)k=iy^M$8Hj+Q!# zqz3l9_eweIsHkH}Dp7Y=Nk6~My$dI|voF3X0kx0pU&ni$1T@hyDOr-+)gQx-*oH^) zg2!yKe23cjtD_GPan8D8p5ajMicNPX>Fieu6_`8V;(o&Q8V zq=hB56q`yNheS(#tAtmH2TSkgFDpAtazo!D>3Ai*gF1}19n!B!Yt;))niq1Uwt#r8 zrnWsIMvKe-T8YtRYlzYIg?OD>BlVwBLS==HD`!mQhvoQDvRc2teA@;2BPrjoj`Dol z_q4av(-6PxJKN5lDqGM#N^e&7nshK}Xq3HXPbF&T``LDBc1!(L+f!*av;}MX>zlX3 z{Alm|#%&rSUq^fGDfJ_qAr`K`z72krBdTtWs2x|%u5}}-cBWX^aaE4|Qi5KN{Q9$) zIA^ccjr_WCRe$8yz30NtWed}uwK_x#Q@_66UmAUWkv128g`+Z!#D?_#`~~TlyElGM z{TVsU#bWfldVjU=={nxkydE9&;?M@@8ecCCt$})UaJ}0Ks7D9AIJly9?W-3Dy@0r$ z)r*7PL0r{p=cU&WJvt=&FIS>cE%B*yl~N>ou}+jowfvTjB){5`(}Co-`~K}oQY|S` z^5x(+ON*pJ-suQ;2K3HS_h(_+zqTE||Gx13zp9Cub^{lLr?vZ63-?_M#{F6yOzr0E ze{JZrr?dan#MI8t{#O%I`#bwzP0Z3(&ykQkd?f!4+VR={$~lr34|Omd1?poa9Za<^ zohj7BtkuC(`_leb6H|$t{jVlweH~1_dL&KEIz85si%4spIvXQ7L)$m;&81C}Jae6` zlDx8JMZhw z$2|u31C&d(;3)AT;<+=dttFm2!`gP@xihT2E}pwGa&8mP<%Mi9@!Vdt-NbX--o6*l zliiDb;s_AiBdxYDW8Pm+`_}enTHCrRN~54$J-O2LcO4gLytpPV*I#m?X{W{Ct-o(v zj)$+KIlgbkTf0-^7iiZnjgdQ$KD&2Xu9%d+Is4hpO5sWgjL%PA100P?mz#1fH?QTR zdm|mIk};)}gJ{2`2jbp}-dp+u)d$h5OFy8RAZ@D>Hf3S`_%-FLVte0eANS#RmA>jP zrZ=!PxqYn;NYVgNPAi`Gs`j-yAj)-Z?Vh}u@cZ%jsn}qjp}_NIND^y^cPmtK$T`gJ->{T;_=b)k$C7VYN;7=JQnHuc(_Nza?-XCCOtilC zZEa8Kwym1_U25)l`F8!jaPOIVympkP9uyG`~)iMvhqM2Wji_C$%hP4+~IudUs!OZG&LFlnF^&wiB0mA;9y zrKh^&|3Yj{UY-(Pt6h=Wjmc|<7~$OZ-yLJ$tndCW<7`O-ze`&E{~pf%=V;*nmiGL2 z-}CEebwhZR=9DCB{daf?xx)d_LHU1qMY%-ze`#ZX=%6}T(#C#JMfrbeV_&GEG*jBx zhj~q!DQ$EWAkCCE>RU2#iE4(c0iHbb$R)}dy83f1AWvvprL}u3eQ?DIre#3+|CQf0g#Q&TAb>a^TX;4kTq$@)fT0+5lTq z>Z(=QgzuSjjr~&hul+^8H0{VVBsuThdsN&qjEtk=7GcY9N4PUg2_xc2%0`g33Zp3> z6-UR-!xrJsT$>EMgZwVioncwZN5^I2h`3d_yIOiX*C&VDNt42Iaco6xw9$LdnBnNE{kB4J&f|2=I~cDDcs6P1uAhn*s;L z!Euu?I1Y&$bG%8I&h=};4AQm0>Es)QfpJjWh^rfil_q{Fdz<$8*+7{&@PUT z6JmQ{JKzfB?Rozd;yLm6yyrP_Y&e_a-|^mUsWBmT;A;DLE+yy0v*OuY??_39*e15+ zY8%qTcpg{J1^y=dHk=oK8-5qgr0&?TR2UwX44tUoF}9}eMBv0YDV|Tw^MJn&zX`vH zXHv5jS0=?)q{U)q>UWAir*!G?^Y{z$3#fU1>_U0x*peE(fUU^Spw`mi!uYH3Yv8Y` zw=!RRUHBp2yJ6@`{VuTuwR;0wl3zs43xPL>UxlA>_tK#`S9-_hq(1TV_%li_jyHvy zfj5VXVl%Gv0rrV~<0bLNa8tO1s~5-9sJnDngw(vY8-O>28-Yj0qvERJsCYE+Mt*5k(xt#l<7L3h z;^n~0;}yUw;*oK^5Ml(zm;>`z0E<`wR$>!ilh_p4l(%0m^o{+1{bGM$|G0iwFErze z2J=3H!Vuu#Fcdf>3#$6kb){p0f z^Xc~sx$6SpDe=_!L;A5Ruq!pz<<1_!S>)%2^Qd_dbuI*+98ZbsaHR*ZN9-9lmF)b$bGP#!tgW)ZZ|kP2FX}CDge%EW+D%3u|-j zpTL>q8&hYacvd)@I+s%C65#Rigm`HT!+uuh4_%EE=xj>Xl(N&a=2$T%G)CO0EK~8jg-v zla7h2VuT!kA+8rzrB)Vy$%73dgNNi_kK(4$VSy zU~|q|lUju~l(Y_Sh1qdVe3N`myeTVw2rN=e_ZbH2~;;G>@;AzzRBQ-{aKT>xja1`zJDzzuaSGjNV zcxOB%oEq+={vGiT)a?=eKqEZ z@G`Zg#Ft4^MF z;Iz16{0+5wh2M~RhkL1cPrNst5KavD0q>13gcrk#z!l?k;Pf~nw&zXTh5NaBU%Ws5 zG#t?#6_kr(+4}c$p4?`1bR)GC&zbc=n z9(b1R6aOCm5%!Mz#D9eS`M%!31H!N4{-oc;eR}bl5 z3P*>l;??o!aCQ7;+<{t8haE`I0G|oZhGV#Tbl9FN&*E_Lv+N57!aun?;~D>gzm)%0 zUZ=LXQZUG82q6c?(3cT#aC|-6lW%-I+db?7+=Fj^Eqgs{3T(=g3Toz|;LPKH@?7PM zN*OcO3hpM$*{XjmC!2OG-F;P}sRS~zis;L)^dTJrJR}|(-{7}i&)&#(3%iHj*`e{U z*qd61#y2T>BYQL3CF~mB%ytdC1vTyui@ivP0}qc!#J94Y!!F@1>bwcZe?;6Os#knO ze4FyOvbVFH!p@;*wnf}B_RO}7TLBm2>>bMA&fdv(2s?&%vK_-tp+~k=+&XHjv{igJ z+dk|N-sS2$tPr-2+r&k)ZQ{1T9-O_$)pxV^vhBi8!h6|I!uFwiwr%`T)Glh<_U5js2$FaR{;YZ;^u71GkV!Qa0 zsGZ7o@$Zy>nEgH5CTtu2o*fgm30<=1!1ONJPvZ8mOSV1z+a-H8JO}Jb**~(Y;xXYL z*{b16j<1YY0gvI%k0|*^_Hy<@_9F1b?4|6L>~EaCLVB51pB6R!Nm|~hH?K96P@jGM zNbR$ysQW7LQ|^0;^h#ChxdYIZ^{DJgu0IZZJbME8MD`cpBa|(T{`Rn{F7~p( zWjVW-@+Z+-UYhdzvcGb6AL(B7p4Fk&W_nn5fA(DVJn(t0-%q*^-DtJ3wWeM?dw{F= zXa9_!##OS%;^Xm;*(V%*8b66Eqmlht{3mChk$#Xp8Xx28qohA&PXHf}PsBfDf6P9Q zpT!?!A5;I6_!ml^h>yfa%Ac|)sq>fkWc+>hhwNYRi#P$O zz0g0X^HKaqTnS5`r{X=??}5Lk_CwtFr|copEi4!R6(<5GW|M&Gc4xVo;#sb}d6sK| zp5@cf3ST5&i6=fC@5=7Zo{o2C_Wcl+cV}M$icg^*A(3P6q@@L~i*~8hh)PE*^ zK;2ui4@kFWc^-4@4yoBSe~voO#`n2?YgSOYJTNEk%+)UW^YOv#q3n6;JQv@i)~#73 zFY@JqS}S&8Q&sb6AOZN`L8+qRn^|0UH%)6 ze~l%=8kGN*qYcpY`F zt=c2B%x7gS^A`E_*~{^jcs*CI!$xCMtR}SHn3-LfU7B46yezvMczJe3b`>R8X2!Rh z3EU8?4x`8#pLt`-&g1&kz)Q)uqQ*Kv?IE_}`poS7>_)DfPdYE#lCpJyT1Z@wU7y_m zyn*W%kj~Gx;L0rEtgJ+0V0IWIyI?PIeZ@XJ*@GKjQox zj?V&~m7SfP%keqc*4Z{(+nQ^0fZLLvO!>LMOUQSnYz}Y^HY>Z5=4Pi*elqZ4@?9vK zo1Mz>DcR1P%>~ZQHqTDWE~4x-(y7_r**@9!*$LUP*>S+*vY!HfnjN3*k?oo7m7PfW z3E6Jc*a5gZrMpqOH*gQ~-8kAl+m|{g0#D3N0-nLyF^G9IY1i%k~HE zpB(@^AUhCvV0IAjpzL7a!Pz0eL$X7GFUFVRYT>2$GVrwQbV^Roeg^y*&s#0L94`c3 z$QP^@F5(+zh0Sf{um$ZrE9{W%$nlQZPQab`+F9Yy>@eVA+2O#$vm<~zNmM`&GjW@x?eRG|O2P=S_i4^CrM1IW{ywtD5z~aAuVCf_e_?1?@i9 z3$sG=yjk9fV>L^Z8g^nP)!s}gqf);`fXX2CHkK>~dsJnZJ>XW9%C%vB(vC`Plr~jK zT_5<3UhpD4c!GW~dNAkp<)|O$oq&DF%ZPEx{L~Y0=T@1YIt1$Y1URCc)DI|^7PO30g;X;eGuI-@Y5~<+pX@ymM8i*&XONr7vn%eSf90 z>gM@H>bM#^N-Iw7J=N>*i~I)n_I+o+NIj13)KyEzFOYLplSH|vntbUieEWW1zJC*b zLkX@DS0%XmnDF~5l=vlQ`E3eI)bhWR9nhdcm2vPFjXEf|k>tQ*UP6DYR4@O7(uUG;KPS(mu?=Q)$-) z+n;NPWh9m9z*@`mWRJcCWy9%#7R+eL{=6ASi__B0$!l%VYc0>^@E51u)%S^TbOV6{ zsGW1H_M?{P1;=vd+RUjtFcdhL^JICh=b<70(_i*f>b2UQs`VXE+edYMw+OwVWp?Vd z)L+Rvz-ZcEZvb+M_MP6e?!+BA6)iVZBN;E`s31HK&__$eFx~9>#IHjQs3!&sn%1#boxt=0`u=L z`)FQI0rt+YYJUs?YPo8!={vw)w5Lk%0A&xRezPA3Rq4zie!0FMw;|lEJ+ijT_PjAp zwS^qU^Nf8et`6fUd2_4p$IZB@Mo-l{*mv#6P3lzV&27Pc+@yM?H#cdZk!F)Ox3N$X zY5x5Ef=M~+yt!%RC^dDA>Afv^2a}5G%{_T@`#L{Ur5`uFgGo#EXQYx+!1h%vnh4Ds#kttz+QNB68(3+c zlv12>wc!jSu1WdCLR(=9&^1Wu2TqGw+h;24#HA^4in=D-CwOG;X>yTE91rH^KK%+J3<|Ij!S90^xLuMNKF1-9A{ekCpzu8b0j(6O0yG{cHB&@ zju_`wX>+2+eHjyu7H7|XRcq${Ku3o*&GvU=fBoO?FXt`!CB2f?;+OtMr6ta3wfLp~ zQGEvKn{kU>poBb#8tFgbNijDo%h+p5&{MCqGjri3#e>L)ljr@G$`m1sM)wo`6 zTrW4uHyY(pjq<2Q`C+5{uu4aexnh;8u61^yZYFrCU!${wZBh&Y}a86 zimR=4jByiFbnS-YYOB4RqHEWWtF4A}U9{%WkKC9yaRtE?!Sxv{4_sQ6IZee_oriMtg@wdxu8*l<&em<(u$_TI$tV?P;l}&EDcw zJ0-jwaHNGp6JWB})8e7D*VBe~Ny?3ks>Or04K08zI9~=^hn7I?9!6mC(5fnXY7J~f z=}6>IdgIW}tIkrdZPj+D9Z>r{t%l?WwJXwUNd8c}qA^vA2W|8^Vl|}Y-tzE;ooYD4 zud~;aQ=EY9P&c5KdyV{Iqy1O1%w2fh~CnbB6x4`E`p!5_xzpR26ij_G!87sDx z@iTD>C8v^pfR~7sC_M?=ww3VTa4IFIkygcj#0*ML#9C(tULW)$aynO5#s9=~N>8X- zS)Rb!Xgb~?@Cu<%2>gy5Px%QzV^g0&+3G-jll+vDKuZ#UCnZ((lz^UXJ-X-P&w;<1Gr!A^heOuz$;;ruSX@wKywz335AoD-RdFTx`IKBxTwUyo zUy!SdtH{rz4aN1q6UpD>OV0(K&iQ-A&&b~^&LDrU_&ND| z#V^R;E6yZ;uQ-eRz2a>0_lk4K-=m$*DZ2As#MtG1I#ecA4#v;Pq{>9{Wq6+vl@ECC z^~DFY@jlrH#V^S}D6S#@ptzR&gW@{!52$fn@h)%j9&k;@%A%F-JabXf%&Z+xZeM9v zG1~oPe&L|3M`h8<%&aXX?J8|62QrdA;=i+2j6+`m(-jbERh zl^)#HhWif$PN__;v>_eD@qs+6b!94Ltx0Vvtt!(vYei~Z`FrtU(IR`BC%jX?V?v@u}aIzirmqX)T+{gTt9+q!z)J=hm-$>vc>R8)q@&G z7Dp7rD@T%+s62@Wti`eiqy8KojC$dCkU9^=qlzPoB`Ob4{vdu1_3v>s=Zja4E{-C< zKk8-T{;2nl`?>l+9GC51>{pD-4k-2q9#|XzJg7JjxB_`E{8&91d*PAlDd3a*;=Wwj zuQ;YyyfUnEOmQ^%GkCh{mE9NhE^=Sg_sD(x%KhV}@?o&L^d2jqnJx9J*p$DqHDBrvIYkWTT&i15auc8mWqW&8DWWUF^R3AJ{ z^@iKoqu9L|%k@2g%aixzY9BbDvDxm$oAlaSz^w8wV5nr3H*pXffO#cW`elE>CuKkC z_l1udL;dAQyA}N@*RJ`G__ka&+pXBO(B6NyVs`P<;<#cC=~&?G>hZCB-8JzZd|Y0` zx7-8#CHZEQ4y|lPtznf-xodWDEm!Wwk6`EQmvL^fSuwP-NpU<^HX&_VT*tM$@MU-{ z`Bl`pI=0L{D*jPyOr1@DCy;N>Jwqy+7jwz4q|Q}%J-iD~o!4{UU2&sg`{F0XMx+yf zCveXe#gNM2$`;%=q;f?xI{6jcbtPUH?}&c}-bsD~ci$PeECyEwRkq}g!Ice*9eC1) zq>YNpx$6o%JKjM30klScxXxv>U5l-XEsH^wA5wF};wG-$j)%w_$uFb+<#B7S52|cX z?8x;ENIxttrTj8{Pu_+H)0?S%8}KIb^^2XTwLWQs;u7jyif783sWXt@(u=^K@I0#L zgk6hKq+N>pijRtx*}cH~if6K-@+_Y1DwU#g4<+{&_fy&u?{`fqmCDnUKZ75#XQ}lZ zDX$FTX#?T0M`gPdcT@kK;sNexnLSUfyz&%xJ)M0_`Q61EjEy&e&r^O^@i8S2QnzLH zSL(h|JW0)`@PXH~(xmbbS6XIwQs=JXFO)oqx4yqp=i%ZZ%I~23&f*2i-YA~PnpK)s zo}kWOvOiOPNAU=?TH*#q z9+B-#dyn8~XW&k>`-p7qVlCjzVr}3$#Z2J3#X7~Kyj{!ecHZ;P#Y^}we4}`bH+&qA zfc>D1k8!P2_87HVX17u2_Tpu{9KKQ9%JFT*D|k74qqv3RTZ>omUHC@vCys9^Uc;y1 z8^ub&6^b6JJ7(jHZHsM+@x=<{$I$zi;EVT?cyT^Rd!7L0l(BC(+73OY&y@J5tc80 z%zev~#uXEJ-oVOH)I1uG!pHFhy;66`Rt%37oq(OVXDs!XFUA(zkx!!bfXXE98(2A> zJ1&gJ#|z^5zzfNb)=F_n9#;niz3o;IcE&%89H=vR4+?ma(J@%OEH;yr-aeeU$z)stVVt)cO8b`=#!{>2EBa zEJjgtG;nqDL#Tf!eyPuiX9G_rUz^(P@I|&3`9$hZ!mIsF#f`e^UIW_%-mix}L6 zVsN%JzrIYd8~)V?XG?Lsbg?_$ZU<*ea=cX0y;!lB2Aod52(WvxbyN7dx7Sd=WoE4-*46b}S$OWu>(k7hl&@3E{4HMJ^-)k_u>O{5Psh81>Qqjbmo~|fP;%cz(JfX zRy>OL(8Y?LilKbV zYsE0U*1uLPj@SCviY4$@KRhhK(at=3FFYOZg zewugTXph*2I&F(K#c=XA#ggPp;m7~AVpp#3ju+tY$a%)eIrBkx!AE&dMtM?Q`3osAFg+4w475r5ya`QVqo!U{z=|5d`jvOCdFm(Mn8#~lko+<68El*XZ;@nHzNOM{%PJL{FAh3 zcsDPKym&XS6a_FZ-pf~^)(`O)|3m!tPmIgq`F|o$n-o9G|CuiuJ|lGx?@<5U{0G$9 zfJhQ!!g65(H7CZ;^Uw0`;d9a=;ce=?lfRueDJsRP_@dtc-}D<0DPVm3v=|e{bJv9U zPe#r7_-fG>fBUb}53d!k7VYp){%X-4U+AwE9q?HGYSED>2Co*Kh+^<+(V6%KZ}H5x z^SAP*MU&#Kyjjt-_#*#2UnG1%>W1h1Rr!_Gh*K~NxIX#nKyJP+(anu0{>a`h=aLfS>R}5)ePonbi9lDcjtfMj#rBA z)Lb+U;mW9ZC*^nLcjhmUKgso1ibc5EoyaSrh-@>ITBC@|GL++CM6Ou|IFkGh>ff2) zk-td3IAzNa&1D%P$o!d-JMus0FOe@n+0yZLj{ltBp1({!ob#pPaN@!&9dD!L_WZW| z74nw!^Wdx{*OnwI$#C*pDZeehmEL|OzaoD+e=5I{w|k|yk~5E=;_UPA8SnZ9aU+D? zh=%b6N8RF8Tz{pwoV%{bKcmj)#EbZX*e6%#S5bZ$<(KD|<CGUYcK$|C;<7YP?)rL)}-3NWD%mQnxeS z^FJ#-#gG2y#b?E})OxwNnEIFG7w5kr&tpfT$mG=S2#n+(Q}dH>QT|)5Uqre%zb?O) zy9(;Hj|H_l;KBd%;^S~3buP*;%zsCIJ+)pgD%5BfE7WRFB!JJ0kHQ7{@40>f>B9U5 zYQ0=E;d(nF2Yg=qg9s>Xi9FMk^R~byCelF>}yai>g;yIL@o1c^4LjFo< zLCGtj6@C0lXi1NsO%LCapG`U^KQcdp=Rb*0|IdrV^PBUV^20el0(cYoQKXlEN0L85 zjlU2d;EUq(;wgOk3qLPDz_0%Y#925xKPrEzI4u7a&p3>9c>XvwpTLX%Q(Qfi^273D z@}sHq80C-Sx&LX(pCL}eyTJF!56MrZ)*+-r^JA&|Qt>D?AH%!NFN%l4-#B|S9FU(u-2?KUlOMp*f%ysf@jT%H z>O2@;AP&guz&FWX;Ep%L{`oJcyFclG{6y-$RJ_QQ*TajX*TQ~W-9LYcv)95)q*uef z`I(gMOWH4gnX*^IKKWUc?L*o(za_j($t|Q;!rt`TS^3_iee$P@FL;Beiu;KW^%O_< zhZl>J_`Mg4lk<~+C-S?SlW&pVKzyI4iY@akIGan_Jin1xKTj3ck**J0Cy`DUaSi)*VjZsO_p5^?B8&Tb;z7q-r~;_4h~ZkFH7m3xW!^c1zX$+xC_cD@r= zW|QXRzv9|G#5lT{{Fl_ZCTz;p+4-jV&g7fsyO3|2Z^K=`rq(?~Pr93^UBBk&ZeqVY zRs1qMT|8A>9bPE5rOqbQ-!%Ubcf3$s#g(gx+VpGcZ%p|n`NsLK$isWDcK-jKi`Y|EaG|H8qOl!64s++{d_%o zd#`+QK8gCr^PCgHM2;rqQ-FUfrf}tj;zXjVJYD=WJW~jtrruPp|E-w7@4Ntfp_rJT zMERvecR7*#IBNbhOv|TIXFPQ#BE9En&eVi$wyPNY(6?)m;6j(Eu9t4`69WoLzvl#I$p z(qpso3o92?o+~b@TnId$bV233>e0oOi^wmjTns#ybYA7s$|dBNkqe(Io-Hn~TvmCu zxT117@UF_am2)b0QhqM*+{#^*J1Wl?&lPu2a%bgk&d&j!Q#rfxXUgxW+{4+~z_Tl7 zRqiF73A~5=cCP-pav$fv0NzV}KSw_Y-belbM`r-gfe(_u%`O{Lf*=BtbIv&mN(KpvBIc|p=A1KNBCD8l7BP{`@l{Y!;r{;J zJ_~rmJ^G$|&iU@Q?t0eVRb5rxPj`h~yY~K9_g43$`+}4&-S-?l34hW(;r>P_{)Btn z{Xi)GxZC1>BoyD`HoLvhCistp`-p9X?bKEffS3=M~e z!@|$qaOg9)f-^6LpH6r(*F41yrp%CV1f@Q6BcM;+NRGrmb)UFFDlINq9V0o9@lzN@v2)^v>}1 zbES1|KlGRz6OImd!*{z~?rg4gA^a@DMebp)x5zz0xQN(dH#Qs-?t<@fJ6%DL&%adS z`jvx9K`+8-{LArton|K2p9QV(PU74}?i{XnA^bwO+Kmf$x*hPbgbUrH5pJc{G~@D_v%xRZr$0d?^xd_Q4J^7@4> z$?qSwBGwn)lCT2zQ!$vs|19TAkoUT&@cZ1oZi;umyU(?zT%WKtW&4J0i1miICOn$3 zH@tV)E6fe*agAK4LNM8Tz}@dAbM6$r1vH0i&V^3%+ETVx*cR#;o*aJUK6FdN@!`kt zkKD=OQeq#uQ^@%c{-OK8EeR)(za*SUxP;i!a53>E;j-|Q@B_CDdf#P*jl)J^COiwi z!+vZtsfQ-Sn~>Iyf9nbF8TJUvQKAvNQP?mnOUcaeRIc>CI~CgQ7KM|z_9AF;m_csY zusr1&z{?S46RQs|Pgo`_q@~JGCWCkpEq5AM+U`z+-g75$okihEVF$uv_~#z*9%1(| zC#X*ic&7BUt>lSdjv)@ zb`4WGD-B*fC=M!cPMxpdob%;&C8$OsV#~aV-g)%+i9FpT;;Y?*#LuPwSLCX7!irGsur&Xb3a=4V59V>r`Qb=6*UfRG z+{lQ}akJeBQbxk(5soHjHhi|597)4stvClmW0D8Gr|pb^9jdLY8HH!o9X6q z<$2-UunXZZ`u==33>psK&(T;)oCqI7SedKT3M+HHl5nVdhy0<`*E{h2lpaU96X0VB z=TK)|!#QC!!a2mcz`O7t3wZidyamw7-URP_cb=O-Jxuh<2MwvM@=$hAGbk0Ngf)X2 zgbBiwunPZK3tlU%84lqehr03n&k67o+zdB6%;$e*LvzABO4Wqd3~PiF$e-aRK-1kU z%FGUDg$0CF$*%#g5mpZ;l0V%|gpPMJ!$R_BLbJk!+~dh!xu6mERSqg2)Z)GpVJ#>O ze|1$k_g7avEDlfPteN2?&cDD-;!4N6-&}E66#nLZCA=v-gZ^<-cqZYE@SDQPl)Av( z5T3=+4bY9@&Geoj?q>2<5MRO3_2k|VULT%Kczt*d;VtA0akoH&-K`vn4|apxb>vq&kO09yf4DSy6 zx<2l1&gko|2xpLUMR)??6~tDBmlMAtTnWD%ej?%1VQ<&VJr(wGz2SEgK1IsY;Zxx~ z9BqX^6+T0$UhWyFr+bo=t>Kg5y@bz_)6+c*^>EK|B;LbycTbS}WcWmQAK~NhC*bE2 zJ|A{>-Q4rxbA(&M^GMqQJs!Rgc5_|b3*>imn@QgiZVt~Ud@=0my0{m~@9JI(ySUEq z7YR3o7m&XxypV7cvCZK|;+w*k!!RJ;a}E=d%{Zy_duV7-%x4|d`-AI{FYFBb@*VoJG_)qyP-YdcceWCe=vL?+(r6s z_+^AU;k)1~3BM=*0r&&q{o&sT#qSSa4}TzhJ^aP@LoeL#d!d2vXq zlNmui(qjT&1@s7i_Jhz5fA(z{z@j>`L{C&!$5>JDF7=93zO=Kjt!MBC)hNTl9g&)E{ z3{w-CiFdf!hP^;!XG&6N8pYJ{RE#QPb9)b3g3eq&6h$)d!xKx z&ED|G@K>(zoB10hf8aZ9rGrv@6V4@U!VAKLgB!w9lpe{KXj2IHn|-lcne)#_Im+%o%9_3qTAz!h3gm2#+B;{auAl$(J?lT+s|Gn^E!k(7+9iCm@G1Ds zgpE0?1pWnI$7{^D^S*$8#dq`?^98@J;CGVWm@m`a3BQ}LF<-m88-6cgW4?HIFZ_N& zzO4~_P5H8Xp|3H|az80enNu5a_1Z??J1GHQuP;>UizbaCtbJ{e_(JOID<*Z|`o507 z=CKbX;6A$-bWMqQ(gS0IJyYLO`HU-nhE2M$*@|_uG4|;t@Fmz$8k-@^-ue0S5ZTVm zhtETUN+5O@5TB3Uu3ZB97OFD~y%bQ)3&~x;ddGrV)>lxiIms&pmiZ*Fv?&Eop~P&4 zsvmv-G~jEeK6pue5!E+~D033ES(=!>g=)+a;)_|^&Llp-oe00wfnN6dqtzI58SzWe zbx!mK!1V>xfll8?y~OFuyO%h9ulEvG`b)fiXgJ2Kr2J)QS2HL#$mz?d7qdD)8GbUF zYhUykV=kx6O0==*-XQq#d?ocFR^O+<^>yJs=r+b&L7B_Z?T+^b!>96<)FDn^Oudkm z^)k4=UVNcDmG#W|l)M71r4MKIqT~=}xC`BBUQbqqQ{hv+URX{pAY~Oa+Ur4jPjraM ztUWsu?-AK{MtfJe(a3Juf<}8?$nA{IG0B_kUGK&)16}XNGGASfjcAP56|H*`d=llZ z!|pWByAB%fJ?wgc#d!q&FspJQX&!Pt_3e2q06o1&NqK}7avu;g-MB(mbf5{WUmhdn zQP#|TLBp)YPS6A10~FDok$_7@94-(%* ze532k+WGz3+quS1(9dW;Ln(72=O4>DZ6@LO zl)f4MIpJrN{|-yqZJeE zkb+f?e;-fUKrby!C#Ar40IytVXR!7wBwk<(?FsyEzU>GuIUig^M^|L0v+66NOrb3% zUL;hC?c}OK?N~XE=W5kSFSga~@vQx-lHU&A&b4(lNU3gX*x9V)YFMqX^K4spG`uR| zSk4~k)g-+Jm>jLetJtGm3wR!3EmCTNq&bPTcxBtd9R;sK_=y{VuJ8%Z@~JDa3$b;T zP^K2xq@!F*R|)*lQLZ-WC7_gAg2JyzPD@vZl-l517GRgEKu#-Hmv|izDf3yE=YmRV z1s86AyBm%^v7LYU1S`*QVjsZYcO5;;%CDp6ShIHYLRQlqsl`rSM=!w&yQ7y9mV%eU z!qCwxjb)>wmx^uVL(csGJFw+=8hC>=I}J*Qr-Njf24%oAz{O1CPU^zzf`6F?)rZ&T zjA?cr7KEv`HG2l8QZ5q|VkTIgsZcq1InYB>p=@|ID5t4VEN;1Wc!U94W>=rw@&JOIJ!@Ql?QiplFu-tFu|DKJk&(Ed6IPu`$HQ(4StzX7#RX3#zZ3_q~12J@3A-ue#^p&$;i}CGb3cg74UY z@Vxt$qZi;W;3r6Bo?Z%Hie)<0oQzdF)trK*Jk>12rk-j}#fF}0PQzmU4SNG#gum!s zg1>|p;cM{yFS{A`4D7`-c$VoPHB-%U;>)p;&#klzGN4}4}?DwdzQ0~;T{ii)XLkzb#~&1JxKg_!d5~) zz&|D(n>{r!1MK$@Z>TpBWcLs+4L#@t@FKraW8;Tzq?@pdcQH zjrdnfTxZgcvmI?GknS72VsNz^@X!{!&6M2ab+Ki@#&)4hXWM~NGwl|yCTRLC-gwZ* zTPU*`|8J2ibnEf=7J=dIK$)(b)y1y!3SEI)M}DDuobp?|_F#2q+HT}_wU2oP>?wH+ zpL2nGg51Zw?xc4EQQV#~Pm=Nke(lG+eD^3+&GoQ3;6Qs&raM^WV<__o`PJMbP*t~; z@=tm_DboW)bUSjNB4sNc_D8&`?qMj;9Zk+mkht2J(TkEj?bDQb3cvirULHGZ9)kBK zx0h`Lj(R4Z`G>qJ?itEF?ezf#oo)J%+uOD#f2Mtw^k=-vZjHAVzLt`Gt-cf6my&(# zbL2kj^&_P(yNgzPYrIO7tjs>62l3QbB&Cw8&AyNfQyWxiiC^A5fOoz;xfNX<_M_yQ zI^@;{r=;)b)dGu@Vd|1z2V_x2_N>$-r>v;~Wx{I`)?<%LMR-NZWxMmE}SZ+A>|wR zMU>4ljo9;&2hSt5kmGWuken=&%egtOF*{cHLL+4w`2~JCP{sw6DrXA(eqbe=klPrn zS%Kex-4Ly*!&$bWZ3J%w4tW;T1l|Pv@+_zsycy`}Sx^gj3y|8gpqB8K;Kye{t=U&H zp1K}qZ^yqq&fbBye4M=#Z}~X_*Gy z4K7VUcICs%kygPKn5H1V3QRs>7AfUip(!xU*c;OfG+B`;G~&%cFlCaP<%&%?a7@Lf zh_JdT4+g5bDJD!KH`CQH)lD`#F0w&U)igOEu4wMPo}Qx>UF&1Or8hQvNubMm)`>JD;+p;2t}Qd}5v}O>QYrVHheLoG_J?(jdw_KX3<8 z7sY{ex&xkd4t|huw$;A!+1%+Y_6wzgoEmG>Kw6EZwNt@bjkW3i@8H^;`yC3M*15B7 z2I*x$bd4pJ2`}qwMLZik@Xw&p>OlM9`@LV`VBO%qfuF16g)ZUhcnS8M)bUc-7gdMU z&^0x+Ikzt7)&WDj&-)4f6G!!k*M$@<`@e(>r;Kf-?`uK_9by*aiy zJ8kAz?W&w(k6{nb9QN?cW~WmFuc0>vRBA=L2HBR_5yZyQoYBrB zGWsC72f)+*9@GMLTMHa{5OiQ?Z9qvM>zVd<87yHfjIk{#{VQc_dcQ(7uwZp$pRJ{Q zfQ`-sM;Xr^1v=ZKqyZ^h1MK^L&ZyxX@U@HVfPawC1)bPW>o^yy7v(+s3rOMW-Y-zG z7n1Av#`XbE7$r3%XDk=3pCf}dwWUm#_s9TSPZ+tf5!4X*CseO1hKt008tNm`^TV~_apJ{ z?7vP8xtWKc{Pkc@c3P0$al!_pyzYM+#vb?XrOZPK<%{P8O=v(-=*hR~cn+2}=^Wcl1ocBfW zWiZryhply}`5v3?P}7g2^5m8Sb^R$g*Ye(H!RNscGZee-5a~iz0&qm@WY={ zVz3!ve)I=Jd;M*}XzK1g__p9f|0n-vc2NFIeSQdi;OB5wwzr+!_dxt6Yzi3RZG`W$ z=W?$7i1HtTI8FhJ{SH{{((rdVdY|&!gYE3yoNGVkKlZWLavx;vX>p0gUn#FgYqA}UVNPbWoI>lZ+F zk2KG)3v;9yL6}C0?B36V+8$+|WnbnfGm!_p0{1kE% z-dfPdqwFKl!@;BM=A38OL+kwc_EEx-R(X#GBjIZ(vj@Ib<=GE9-)@LXZ=lxaSrF7g zinlu0L%5n!dqDP%w2uZ4v(t3G-N+rh&W^{4>~G#kYy*6PnP?uQY>Kyzl8*%sv2S(0 z-9-9Ee?2Mdg0<{+oo`Ed4}jh-lo+=IL?<9Kt6KOMT&|J~dQa{PC45AaTn>E>2{26UUh&)f{|d!M-lg!n$n z{LVW#W|-Uj6QJASxBGYa{p|xhV}E0l%JdbJ(ri-_BtV^1c2X&bY_F7zFePyOKSH{q25A{$gfR zs=vJm4D|?5$|LM0!DZ}9>~F7tF8414ojn31v+`C&sh6_TvAv$ZL62V$>^B#)7qh>;irg#xS^Vc!@T=Ix`>Q#R62F@BDRVBE z^k3QAJIh?{&*V)h*TAn~pW<)i{EE-;9B}Q|k#?@{bBrypQ1=6?s+v)P3@z@Fou3qO~gumkLQ?5Z8WKHCf67qHWH06S(c zf?vdr)8Y1VaP7nG6=2qf+f|^~hubT`nh&>EfjS>_ z{J)VRAK2-^ir{;=ykg6P(}R=DLUW3L612?!jud&qP79U?i_A%8nZF1+)&G_h`MpjJ zP74;BQ`wie*eoJkViudz;HR;#afw;(pYDG~nQz&Hd{Nw%Ux;`m$gJ~QMwBMM?l=;R?0=s{*S?HhSpUhii7Wxx|Nx?T}J|*V`i%2_( z{i@R_KZS6hT|oN$V6s1j_(I|ff=|u(U;=zXFcChHbC;S$>{MK87PBXEDQ|jNe~&Ud%sFP1KiWUXjP}RC&*o^m849L;yBP-Jemmvg;93%ILZ!PE8`+lwpoWY@rP!H1?F>3!L`xxsFWIA%rN2U{Joo_DS%=4lCejm#BW?w@`@;b9~bdw!GPJe%^eaiL;HnUrG zlkFR9C4L-xPdD@Khz^we*c{6_=W(S0{&~C|TTR*;`>K6~`0d13+YaoEz1hEw~li+Sj-o;y?+OaG4ZPSK*8*g*g zJ4Wx-8s=XHwea6Et=X&b7P)Vmm8J#zA@w${7XF*26}vRvB=;?IIXOr9mqRW6H%v?R zXS_k~o8}5~TKZQ&t^5~F3-(yNXpUm<#fy}A!>lr`*bBPKv}Vt!-t5)Nf5|jsFU3oy zdC&shf^yeWs*Qg=bTs^E_KUs@`k-0xvU$fgg*T(zb(CuBUuW9+ciZcTwew#wZ}ZNE zS19wcxt9F9?X}Q7@OyZtRrO$@U0`d#s|PiLlX!2<4)0cbi{0tnW^aYx%JHjQ;T3kg zzsdVGUNvv=-iT|s(!KC|dGA$muz+`t6bID_YX*yW=S@wnQzO{L6?S^Nya(-V_G9lB zdoz3oVG+pQ*Wj=5Mv_{=V!H^wh;u&jKK5?5A3-Q!7?GjrMykXyj7ZQHpedyf?ztP@c zKcVCv?-TDn-qMvH6a;VDI>E_yDSRpCzwh0^TdCgnJ|O&*GM{*_nS9E;Mh(1buI626 z_t~qVPrbUFRR@ImDfVPrEyxdEGuzq8cfH*XU1vY@t~Q@~^@3&g6kCrnb%Xc3?cR0v zJ?L8dx~WF_*G*M+5nRPpKl84FKKJTVz8-kyQ|&T#JX8%{H`}~x?KO6r_a5OFl=|Fj zKyLluUG^zn!yA!KwGD!c*cfFPJLqc({^xynW$a z34ICwlAU?yb4H`!e6GfSKbZK*WP)y5eU@t zcz;r(;8Mz8VlTCCd2f5?+QuMa&gHF3jf2Zbxzt`}-}K({p5qG7^Ja>Q>?*j?++e=; zZiK$^R+4*}UCBp z>Zu%9<4vYKIOy9z7QO7<2E77*#e3D;OztML*<^yW-E6Wz_}&Zd=vD7t=r#Cj-s|2L zayOeT;D9oNE#@3sHn_*U!BgF1?lrG__dsuWkCVOyWYpQb_v&tQk68&{X)m`|dKcK` z@C$ik(^cL@ys_yj;#Yc4Q1WrGQfKmZttZS`yiw~ebGNx1emU=2yUSd`yVh2D%kAm# zD+#amuI4>WS967{*q?Qkz1p&Wi{mT2(|PmP72Ybs%Q;#BU%}hHuBFU1?A5xG_pz;H z7up%{GkDwAb);O&j;&R^t?e>)u$^hICw`sxq`8dvlibe};G$NMdZ)RI@CL%`**A9? zCAOMNBYp|TcbFU42X+T#Z}2W=2i{h56Gu0C8_mVUH<}B*i-=!D-tFcN@@|K2hTrVn z;%y*T=(P*H3%&cyE#9s0+X>f`B81!d?76$&+{%tOp|EcC){!E-+p?;%ozty^o(Bz`9Qh3a_5wSxBITQuOPSlq%f+`?1g zsrU>nlnxIF9kDWSOBfQ%fIGqjv9j=xFojqqJV98BSQcFV9U-?e@ky5=?m-4#Itu@1 z{#Q?`=MA_M2lu1r3g8%_qq}o>x*X3`DJoHsSOU*jg6F76T8Q^d&su?_6#Q&udG=h6 z%HkEwpiXi)%D~qrzo$HfW$@|A2P^+yI?pZdvHW~#)Q)`hs-x6DYDl$K+T`aS-X2O)SFM-Hd5(A@`qxBsA8NfUo+QCN zm5T0CEmofU(A}%uvbjG!RciE{y5}73UeB**sSrI~MeeC0_vmp{k^9g+mx0pxf8BEi zREB%fotA|%{P^&XaLLC;gz0ce z$;O2LmEWRnjkoI17vI(A+u(7^g>o2wM{`sG%4OuW<)|W50ZG-4qe}P<+ritCsxOmN z!XMwB@Xvocyc(XhjwT;o%@n}%;qtZ>!VBQ?rxn2q;qsUj!;9eZgL$-*+N(v>UV7)D z52?MH;mHgjwUpi^Xd$(i-mvE&wO5m&E(K44%QLOFg{yt! zpN_wKkxE?cRWE8U`GnK)^s2q&@ht<_tR^onC<Xw;{|mt8f(&L zvT05A!>)umQP0eYdS`CbGjpTfSt06~6{6l*G3uEWquyDGxbz%7b!E8Th^ro31zs7h z{uzJ$SN*U(arN7(QNOGPugcS?m*&IuTJ+f-^JNjrUYAeM%jKP3yBM{{b6NJ>d_k)BwJyG@6ubDY9cl!2GwSbB8^ zT$;ADfwFMv-qPo!F-Ui?TrUeQZ7-k)l!KS!*rzX)hnMHr;~ui%*&Itc{!jd`q*osI zQABUh{So@(#{LPxm*xKF5=Fo!yj)}-1>z+>%52({9j zSq1J0OLJTiuKLmwSETM#Z)Kwz%Yc`SYCn~_E*I5$I_0FhmxHVJ$}r}0;X==qAx~Ov zE;-V}q&G`DQ@L16)yhEkrTf!eN^h;ee_OcjR@Vx-hGvCI(UVpp&2pDoOXyy6x%V8x zyr_oqq8iGJY9@~}0-i}Ss48VEP&cZ%YMfD#8pUX8FQ zs?}o3=QFkn$gNIZ0lbi~24xE2MT9jeQ3Nk0tVQ`^Mx3D*ODJpLg@h%PEoAf+5!R+` z5i+}&unuPwN76h8p2JZ+@@v3LxI#T*C5*P3q-mE?O-5TS!UmM({hp-NhHD;gNUR=X zP`i<|N2v~DPQABr)NYMw4e4QZ$!QEpQ_y_EJ3%>@w}f(56R060Qe&zq?VSOa*47ki z#OPFSXcqN~W}K5nTwfPy29<_4jmnfI%+F7*Z`5mZqZZftLv619muz9RzuH-=N3BSb z?W|s))^@bP;jOJ+nQUP_joQ2n{P5ORd&X_95tL5b9NzM!X?3-BI$SMW@JDN_FBH;t zRcMtA?xhIIr&ZKLipi-)`{hTis6L_gFQ#2GC|8qfrNIjbYZ6n77IUOFO@j-mSVFnD z{fnZOl@^u3`D*zzcy+=$l&Vg9NFT2k)qTCFzUxKxU61l=|GH6MP^+phq`^xF8&F2y zg;Bq0z&Oi-YrHk!xGpWKU1|+UkyfD**pOb94cDqwdb`R_Njj%M30f;4 zR+^d)-~q>}w5e87l8#z+Ypv~ZTs10FH9EIybe*a^haa_u{IV7SK8#&rw8)GH~g+>IEL$&;~_N7F_x)2vp9IR8HroI?-6s6X*(+ zqC2S+{bMEm(Idt1yp^C#xUN$MbvN-n{5}^C+*{twP$7^{-JPzZH zn!U6h*EKcbWl@txE9svOrExbQF`c9T(9HbrUNd<$S%`FXt+2GR(sgwop2^Rby(>;P z|Mvg<{k{LQ|4BYWTqAn6(vWII_Y{vS)rIVesv*^dT0}Jz&*bql99}Pn-+TN_nbFnC za85eCuOcld>3Ya=CtF@+>Nf$`NK^j{=|Q@mDv;!;#$Fy&8m@k;SyE%O3Sl*RYbIRM zrW$8Sf@TutQyNJErNL#@$>(g1(mZ04xAA;inK2|8r4gtxDG8zRDLJfpIynyWxk3@= zNg7LP71Mt;ziI>*b51Out0Fr!lT_zPE5LKf(~K>-D`{MvSOz?Ud@pMAOyXs^s_H~K zQwUd`6hw7W5YjLv~=J@<5l@dduDuvWGRhumD9D7BS!zAG=<{HxJo4B@fDM0 z;?%=elkvSJ^L5^GkVXsP3qcJnhZeyXfeu;@feeC{!i6?j4uOTC{BpAlIt3Ju5IaKo zECVxgI(U*Zz=)iVH(Mw;d9`PNyf}gIV(?EV;GGtBPCo1zASq5H^&&7^C*q?P)=u8* z>EI@2k#-?;5r~qNq+b9&Y!-YLspk{F06vHCyy)v#=MmTUp5}3ME~KwM%_BAvF1*P| z_!aQ8@pz9U);3z98se9O5*k)QiwA6z)AneB2 zXaKKA-W1L#51&k^G1CpiZZ)_xo)I7}B{PM{EYIkX#v`pkT+%}$S!*7xiiRUw^5OZM zHH~w!;8O{QkuKD*^q=0OWx+L;dq-orH)rP&ugpmAOZA@rc2x(<+z(mOAF2hax(2BO zkyJInLCZ=#02&DI&ruWFwrgbZ=n`3JS`qI`+VPB@Gx^PDj2usR79;0$jx-LFV^Y#w z(juPal`1)|5idy*mx{F)jcetoY%E#+)wxL-BT4bE&rQmgBmXP@SIHpVV^S8y5=dP4 zeqAo(nZ%dsP`f9QE74TC?f8b;UDf5>wtjV*ruWF5xO zs5^`6@$h;}-oqientZ0X{^O@n9si@ujB6l%2A!XL_CNQ($=cIB$M=;yKYr#T(^WTm zj<~gT?w|kP!`u2_J#R-wWj>NjHoXpzY=Y7UVvm5Ve%kvZEn6M|`2}QQmQCktaxAkfV_k@`cC`WTWvGAYtV%(P-2hD_@XSQSzP0uM&HR4)+d8?#SQL3R`0$ zk_HLJeuzwJ`G;M#B@((GIkE4k9H}jkJ>>~yIjjfQ7ftm&(dO`Sg!+PM(l4QJj>_7Q zMHqh{GnL%Zku+@vmxPY}OKHf})JV?CY9Wb!q{k_Pl*9c_noZhJvt1%Ci*i>|H&3UW@tf7Het4T1(EQ&m5bto4zCvbzj~1~CiOsx~FoFRGuu@P1J}N;)@32G@lrCHRV{7fH)7$W8Se=^P%jj^zGi zTC*+^RXs;?)kiZ?Z;^fyM0$$)$*H7BYmx4}3@%)+))S||rQal&3+r&LN%WvPw6-*# z6i7A&=|ZI-tqG+a>1&yqo%O}ciImqYD;;+NeX;~z!tr?G6X?mch>as0PoJ(yEDgE8 z7`~YE$C5UVF;Ih;5aC+=EPx9Ip3a!5PI@skhF-Cd6d}L0z9=T82pUZOSB`YN%9N?X2$5E%S$rO2T{>YUNH&4FXl>F7<}%u)8CHZU zF*c>wX&o|$(Jsxf0wimyG(fGRW;4Qbi048x;WH_bpWlpjuSd_3hp8FV04}RhGe{Od zSq+;(vDL2*@ur-?-d$R_IelN>2R@3}y-^L`6V?O9(wx48Es; z)VrcK6Edng_?`k%?~Gbk*rXb0r3Iwk5w*RLNHx)13rM{^>K(!z)k32!AXRUYstwn> zq;4ga55JA@7Q%dxWVgU?A{3WKB`#EmN8%c_t!T3wNT~_}^9IK7 zv7~5Jw~EGoEBa+K{&@ob52BeP#S1u^M7nk^Ns^5x?_&4_!pWpeqK}RzWeV}h^u}?- z$3mAxa;6pXq$N3>pegjpOVIMikgqSjwj^~l$Cts!5K2*CWYp>y(&@lKg(q1C}8n_Uq50d*PTs!+7gog0- zrk6;65xNd8tm|rWAB1af+-hhbT)X;SAg?N1sM$5-u7>wT&aHv^gKX4V^Lg^Cg5~N< z>RO~(A9x>*o+Gac{CUEMNM8%r_i~>ltqNRP@H2$6ggg`RrwI-9*$pn4Z=fFVUYu!& z^@K|%8;&1_Kg_$`3~kbik@hrK@i=}IZU`%oBJKPsLTM$B!XE|GmP?9s_pO9yftA|` zKb!Cz@NwcBIFf$55y|Td14sHf@O6Y*BW{Fm1p9a%Dd$G(#!bkdfRa;%q=P?3DCxcl zE(GK>a;HXeeKTBmN6Gaqkz5xSx>1_dH25@RlZB=uE4Ff%IY#I}$MFpK3}lUiPJ~<1 zvdNWfd4e#D)R}NcSU#F3%5&|k*TUU-DJRCLt=cqAh`BZ;?$#wpAf3WV@Ber402WAA{^|hwyP(q?G5L zO2dVZldKmaP5u?Nfp{sdqnW50GBk&Hji?1{MEyB^6t2v`W#FR*ULAlYi7aCM{N1 zJKQ?2rs6JGie`^r+(fY&!dYW3IJ~0OuZm2#n*-&Mpl%-TQM|qf3 z!}5MfqgK0QK44G*r4NoJjkhsIBXc2jauPGSY)}iRk1Ti=dGo1@a`18-&m%q`$-^5SnFX?= z*+%sw416~7KbutH;JjvP0w@9+o60Uv}|BcKu<=!ttNWb?W8}B z{xT6hkvzR&GoKklTK*R3ar&LKQ%T4Z&>}oyo6%w>!zWWhbJG;KbmUFMHZylgH{J+s zqVLL{UINKmdM8IE=zn)I2TD)g0BwwP6GPw8`#fu-LEa75`#fuNT!JQfFR}I9!F0GG zTu*ERV?!fWYl-TS=3>xI40%I2Qe3F>p^;`IZDlCq>^`m|Nv$y_bb4Jh(EH)SpVvk2 zcn~gZxip=1aN*PIky1C(YlfhW3?ZdIM~X{#k=8w&_33{g*k78-tZ73K^}N% z*$pCnr$1Wi!yMg=?(i`B=_8T$D*anKA{wEkK0@k^=n#*f+ulO@4gAkzaA`s}kbWav zZ=uy*h{otk{WxCEQDgLgJTEBNi~zpf5wezmS}E&@rqM zWP{gQ;Zij23rTH@E`K2_23h2_ins*5?;=u#HN6-vi@fGTjmFp-mb54N^tjl{s5w&B zHQC7Ihtz1%8F5MJ8OiexPgj1NEq=DQ78BD!N{&=vwl=%5(3Nr~gQS zvdLa3%gZnOd2EY}t%f02kS|r*jxhHz+CFKo{NI<+KkEMCf7cb{ zE7sNY9C{jES5KjPR+`G|Up%-hpu#8US@hp}PLp59} zy5`|=J%K!}s!ie1EnN2_KdR79noqQ=LmH&+G=u+%vHL>otF1MEYL3*rq#4z~g@(!? zPyTV?AA)EW42WxH)+}cs&Cis@-a)>tQO69nj2!xQ*(b(gHx}m z4#~?Zy+9h5bTsLF^0k&n?rX-ZNvT3+0BL`d-b8u6|Jms)dwSi)enR377UOpK1jpyD&Y{#iZS+XG!~#4i=D8pSqE5Cf%n&)V>X( z7LRc{^0HQB2GEbs*KDbWEX6weC^RuNOUCTzkoytW8dga#Ag5 z231X~u3}8P?8fS2!brW#v{AFiI+oa1WDIGR6OP^vLpJ+lSW zj2TCL@+k6Rds$QB%{l8Rs1PpAPT1rY*l^T`Wt)zD0rC=P=YaeL@+8P-AfJME9>}lI zkyz3LA^TPAk*LaSC;xmW3#N-8#cR)`e%YV!0X`~U$LSBxi)k;=-9kQs87*p7sFo`&n zg}({?uuN3<8PuQTuJn^Kw1XtDw4ij_Ofp$xB8?W3yp^R=$T&%0^$wvYHG`)9JY@-eGUgzQw$RbBB#V~&O6Ooyj)+$^fwW~8VOYJH>HFAL8gPpy&( zR|_2#wOLErOsI0TW=mr7wX2m|K`m)@wSAkY540iPnqH#5aWo_}fO<>OMOoJZz__i-5c_gs5fe-fcz%vrRuwRaN+9Jr>nx{RqGV>cI~<8NblDe=nU7W z(1_63C}6Z`%yflo6vT$)Qkk@jS}xgMaZ9PyT173VmMR~OQnixWPp$UP+ejd&MoK zR_hqGT&Jkb)Kc<-YPXcytJ)Fm)rHoQbc!6iaZ4QJiavEk|XP%x7Xq0OLLM&*59{Ryvt3qSl4JgY7d;s#6IxY>#b2NZ@K2P*q5$Z ztP}sQaUJ{B5BH)U?m0i)TYk8Q{BW=M;hyl=`>h$PLNp5ESxi13X^fi1T1Qe&`v@h| zG*@Y+mXwoJl$TobnWUvW)0)pTS7pK_E#-k0`d$8M%~kR}tMxTk$p@|ZEZz;NS*&q1 zSIK{^`RtGmBdtaHux2r7iqcp#i%IX14x?F2x{>q{&0^9)rPFE_6NX$ms%A0iThdxJ zi%FxEHmF%l+MBdK&0^B(r1fhSQ|h5rnbuZXQ)!izT#aeeXhswoMe7sg>Kv`J{_44^ zHQj}3O#7XM9gf#eS|bVbE5xf-U_$H0JMHz9LJCW3)S6Ih60mbSD?&j5$i(Ol~O*j&V*f}rw~%ba;*Oln#I927YgeV!u3oVvkAC*jgT)XaA_?< zyOe@UYiZ9sUm7m0MW~ikxU?48RMOy*t+Jz}!!;MmqEZGf*(ys*23)dL)|j$zNmW^F zGU1Y~vg$}*k=7F9PGU_|SQF{hng!*R&4x>Jl@B`yF0Dnnd@fvCi!c@y;F=4C!>9p~j2)ri$GngQjX7UH&mummoo zjb=dMf8|e+T-81yq2l88tX5_6PGASlZ%=z2OWk!PJO*k{-AT`B2OUG*X+CWWwWIE0 zWJ_m`+YnccY8DpCQZ*_BODni)R4a#;aMh@^ucP3qQCTTkz*VDKt2L)4D#0s7Qc$bm zW{{*{g{Vd)Wt&i=sz=pmV`@4Fp2Kk?S|A&q&2hs>%4&Ctq@bj%cCbhaO3K!UBn36f zwI4=xDVb3hQe8@FXm_%tpyY*iDN70_SEZ7Ik{8-%BPpnrVogX=P*PTyY)L^$+3Jv1 zwvw{NkaQ1?)FMb0_b_S?jjRHCz1m6RFFzVh!ja2Pp>b9Xl66C)S9@aQwa}>3J~g~? z`O;{#2RznDHA^NnAI+*s4OX*cQd80_sWysd=NO$3YsK;EPI|IXWZC&ueKY1GoL zD4|w60T6kJojv-mdvk>$-SG{447^>7JSwrRV%lt?RUM(!40mJYLbo ztGmP3b$HZ`yjX*l`_Ji}l92K0?(lWOzh2kLHW9Dx8qrVxv+KHl zwN8j-V{)~i72Q9s6aI|e`Txarf;>EY zjfppnMx*AJ%8U+;M$J2tppu&{pbBtF)uW;@DLGpqlDx98Xl{~3j!~If1xR0&?9OKN zYDSYx&t^QU9W{HFXSBB^ehicaZ%5dkSSI`!Le0pT$al@2nyE99Fdc|@gffsd9pReg z#WnMGhWJJaM|^pNFdg}&nOfRHIvaA^@~k*_Be&y9Mo{5z?5Z+Z~#1(kyLBTELn8XzDIno(~RZPKeBwa$d@dUoCe#8er4&I+|ATbLcKq%z61w$k)OXzZow@o8j zxXJ*}+z{f!AP+v2a5ymoA4XVAXiR?o*r>II!YVMrS>?mk=0aFiqvwo{xMZ(zQQ~TO z;h*xjg3x`#p(w39<^uD7HFjIXA|8%J#}o1xDbRGZ6Y=rJ}8?Jk?4Va!Sr zG~l=h-jJ|9$2H*%2!*N;!a_T*>qgR~E)qpHAE7R!V`zVsq=sf2G`alBQLRW%N~eug zE7FtFXkFEcv?aX@O7$UaDfZXI-W*|d)cd6^X^*^WLfVp$4(j*PmV_cu9cWFeHyY^a zr7h{5ReE}9OL|9?`nt3wt*!Lj(w5>?k>MU={E+-W@&Kt1#c$ur;NP+-tG9BMje1`E zwyw;mM`n^Dl!s(g7No1IH~WzOReDAMXy~8zVc~FCTrKAd|L7irSdF=(GzK(^0DOPM?J8BzNc%b2j^RalW@jGBjM}0DteyF~s-dLLcsIevuNEk5nE!nhF=(Flu(tQ&2YxSp^ z96PvtVzOyldb#?RbRWx@P~VcLCt#GQZ^@6OJ&j(}9z}#&<;ohMf01=Sy+Hpi|EPL_ ztO^d&dN%eNE7U4ko?mIqI$M22=Ssh}yjS*Pvje`vyldWp?}Wcg_%`8A^PbTgZ{LHq zneDu>_apd69P919+s#{)+G%zX?lgMq@OJQ^yUcDdqi>S-BD4#>i&P;+cY~sN9{y5< zTYZT#FY>nM=SUGM_6=~WZ$#+T*9e84eHnbtbCeJ!_GR!Zdw6H`X43Y+KLNwCIYRYp zB>riH%lriN$wuN^NEg;pm{MUqp9U-QG{=u~^fU;Yt;B@*{FFC`uZIgm`8X&Oy*GR{ zTxi(!gsVZCtOtYgAnErLeh!Xg9jR-;daR>P`4%sT5Fty~LPEekLMUYFT2L(aQ$kqP zwID{cCb^X~12-Js3U=l`uqA3yA*DU=B{vhljdY=?h2s`N`yNn0cSZajQiagI-3USL zg9W;ic)*bl9z$)q$_P)r3JTysgwnWzbYYP#Xb@qluY^`b*x&1E{gtF&MY?du*Afab zd=+SnmE;L$d=>Z)^^tQyVq6Ay9G^?fff!K_I-BDVY{}Wg&!ddqN-PAm5ZIT1@wkNJ z^EtW%^u|TRgsn}0@z9RQ6pj*L#e}Op8PaYA?ORv^kM}GHBc`1Sr$k8GQz)t3oI=-X zAA@jbDX-|Xpb}j>VB{?<=oY*4xB93N3LS@Y)ov+Zrg{Dmdm8D&z zv!Pia#1a0Nh);~r zyb~!o0SuP#y^|mz)u$3>P^t{Ltf?GJ7s>#&HHG*fVr9`<#t;sMq`^o(lJ=t6W*}TB z?M(EW(c}$@^d{*@qtJdvaV(_Os7PNL8fiG0k)|{hS=gVmy1`>DMS6*}o-Q1hi}aJM zNHdWpBR!}))Gg9{`l8wNjr5z|gwld~AakX;l!szns0T7#v!^T|(vhXnNH><|EPYuv z-{cy%ExDQ%r0+<#(e9p((VQXAljfIp(Oi%d%`fec%bKqnlBTz42kz|&I zQj%Ym%cOl*BT6z{a{5172kYEJUe4IF8KWj*PuV|T2g|eh&-^d{xDM8=cgV{b`+()& zlr8-~@^Ai`b+B|ISq=Z*zbVb=keBn2zbv+#B)y#fzJK#@|4Zz7k&iRB_H?4vs?ld- z|E6@F&X9IRAM%$S?%zDzUnbvx=62ct>mlKVNHN5OHqkp{ghG)%EKH(Og?`Y^WJ78b zj_bf>3u_Wdza|{(Z9%fHG>y(_N;&NkGMppKLn*jyYRw}l*PJT|7a^;j`g=pT-Yvw} z&p4-LB=1@xv(kxcm!EtrP2s{^w1k?Yb!l9*f?81jhBMnxS~g%={o0V)65f)uqbb=6 zeiUI_N^0-907nq*OzNbYnYwG;79 zq;;jFkc*Ns-6+`^sV3RdJ(48dDV0O~IL_!!spH@sNb5nlj_{78_2jH>$UsSuUXk4B zMQV5A-ANOEQZlm}XY_`8ux|87>x;ao43`v;1g!+`!Fhe5UT{fNVK{puk3G&AKw1^J z~<|A2mBvq0~8?8Px zBgs;$RY?+=qt!|hv7@z263L@Aj^-&@g0=QZB7d|dN+NN|{DKwMAPK6);-Pl6WHbE(}@Xh}Vn+B0b>k<}!X zHrI2h{Zr`?l9cKfY4j0ELG_n(WSO3=RrD-cvz9>~$}4tM^hCmg$OqOkdPaH0;@#GI ztD<~hF#=1g)uvE3TpE$|k@D1C?7NX~OzYHK>Q{P==3Qw$k~9q?Nh8gs0<9vinBFF% z_rM6(m_+kQ!_XYBcS=ZFNYlxSW|OMXOe8Kjp%tpQG!^XxkRMDoS&b=ijci$MWzUrr zSL0D!BUmVKdFItt%^`W_)mF_Q`J~iVO(A*a)mBX)=~!y3#*lnc8X=7!%~c(UHH=!X z0bG4f?N%SIzNmJq2Uj0eyVZrO?`nM3fy*A$mRRkm#cD@wSVCN5KNDDP zC2y4al2E$xMyYq@L3)#u`kvka8NcDF6s=T>Vx>INh+zI=SDq0 zmv{yGh(<&Xq&GQgq+~-m^dpTRy;(DxKBqCIcXG=Mt6te0Y6aI!t{J>FT=RZYVr}5f z2%AK8D2=!cEu+z(-gq?a)0lW8NSb(~h^sBs55?6+>WAWLJM}N)C%;_6ZAjpFKQ>W8r;>_&U(>C`6`*N#zHO=K@o4ajyP3raCZ>cIi+ zqZ*5Si0at^t)yC2zjx6Xkj+f3ps^v#nc70*NAG%*^w79c%cuo4gO{Rx)Uq0ZNqeJg zkI6UDSBUz9#&9~Vq<*3iF0TF~>t9*8`k16Z2CbA$JeG%&7wp{2mn1Yivk(K4gt3ei zzDKjNWTfytnjIx0J5!U=KP4lD?@3|>Bps7j0ZB($jwBWJj)WvuAcYo`Jxfwio^9Ds zWkr@}TPp!cMQL-gi%BZVvn_j>q~g)^8`;q$4~6fMeN8e__#WBaBoBq}kv&c_Qo5(? zbdraXB3cPZMoNlk&Xzos6w#b587V0u3!r4Aq=@EhNkvH!jSk5}NfFK2l9AGZHD^mI zN@v!bEqN#%TywV2%JOV$&X$anXIpYoSOH1LYQ%&UkaWx^CaI|Rj1~}+2TRg1_GxM6 zj=fwl0$wwA4U?b$U-`acjV`TWgx8ekxhh=!R3oq&T>V!gGaoM5t`Yn1zVBEvG5OZx zEMj`sxZXIf_aEyWhcdSu#=uO8l!d#eJjk+Y}R--ZbzGIEjLvK3Pd)Y&d^`>LJ z?^y3_|JUz3mUKAursG&XYBrNJkuAh9qW-EDqEQ#?B9d@nG}_`3rqLyYj@m2*9%~_z zAZo2rw2YozttH=$WQSTyx`^fyN#C?+glSx9>}iB)Txskb(n2z#5vFk!>mo@lBt{5m zT*bObQVS^;jWCU?SQklZA=%Lg)3}PY5Xr8jE+YLyb3lb?glSx9>?QY8#JY&2qUHeY zEJ$i0RiY7gq!yylCNz%5n?{@T4~@6OwGfRq=^q+zhif4kZIbjFZ~qUI^M5NQ=f6`v z#&3m}eAJHS|Gj+FC`-N-z74TI_dfU|-vs~vNBQ{w^!@+4^!>lSmr0tBu;58+g=VsU zzL!bb)S(?se|9g^Av=rqEy=*Gwr((%}gHe~#VP>?^yJbVKQiN$kGXDnck$ zLCX+UQP{-zTRhV3HOI$qv5QgrF@j(1B};$f<@73zvuuoQ=(BxH1KGEcNOMcPhflHp#B;%;pkS8liH(Jjt z4_A_Rw31hzucY77dS3a$lHN<}d1YH#KHD_M6Gjj6Atm2Z@+Ku8QqsGWC6+I^rljQ0 zM7uBKXR0)@c425oMoWTLskI<(MM~?|wBuhpv!!E^-x}?G3v)awMa}L=-!7Vx#zlH~ ztuK>@Db4XnyCPqA(y;{XO0eXez!{`>)ErMt-y?mbW_m1rko1(A>4~U+dDm+M2K|b( zE7EC7Z>c#R=`^Lc)Etj=n$lZpjz>C8X)iU$BkhW`m)RVT^p;_!M=e5n%%EM7-cnjj z=~bj(k#VS-H}`- z-MV}QY&^#!ZKm{=(yoNr9m#sqt=Faj$ zTA)z<*FB}Lu!}BRiLEx)Go`PdY1`{X zE6gM^%%mic0{dR{YKE~YyY1pVgMoA9XOCwwreo6haj37z#(blwy^EtdtHRhgLPn4*yVcQ~NQ8EUpzAX;!){S zM)6FocF>B6QR%miqP6vBwSqXwX#S@Hs|rNtV+h5;;{3;0!Z2_cPaI1*cL!D8W7B?m zEN6SMu0iW3f?fP^v|(Ap*QyEG%hwtQ(dqb+;5k|^p|unfxhe~08fQ!-j7irzbOXgmJ4vYrTY4=}qFQRyk;u zURa~2RyKv_PXI+>Q&QTR0_8R%J%Kx?@|3EeIP+AFtFX#J{o_t)K%S`*=jr_rK2 zf#QBzDbaZ2(d$f(r?3ujI{9Z2s0E()1=Ik_9G>X3Gq?A3E`)jcFQT^Clo>v{5PCS?Y zna(Om@q>Bkv*z*C8KfiP`8=ruD6TR;rQ-!@f3Sd_pe^e*TXFX;{KHnD`juTcp37=Z zahiqPJ0CPWYawB0R(#IqIg98ewgJ^!EF!gl^`5PH#^SWsS4$N`18)p}Qdg4;wxOFml5(nJ!KjB7PA6XW0XAz^}%Hv$;#nwV142}NG*dl^wruuE~#04j@E~3 zWw>~~)`x3VVF^-_p~X)n3rn_gP}=}nbU%WqQMA{Wl&G{HvG}j(R=b0?CmsPM_aW7r zFdRDTouYOYi3m!`>l-?Q;>-HJPN4X*zFQXWr6p2d+X2*Ux8#{^LGfkvva%{9zO1ojm@kqH zqrEIKElWMExU;1#XkSY``p^25Z#hzV#Pw3XtoxvB?kp6)t3g~78f%eqIoVul235!|maI2rzKLYvO7@_tfbv?DSw)qlsLbn;>~B@% zs1p5JBT}+8CBJFG;*{1FY8Or$zQcgx1od-yd1?otMW`Lf>YQx&YW!4|vXr!~)*((3 zY_G{8o5oh9I99vTnpL&7;>4ltsg?aZo+(*QtypiX|4_@-ctGza+i`j?c_Wo2KJCs| zi}u9Y>k{5kZ!79x?@ONc2bHGeOH&K^e&e*-LUN*J@3rPa|EZlrvXZKAl%+SVxzM+3 z=aAN1X!nr*N%FktNjryB6Y7_>b4W71`bzB_(wx3_4{6+^Jwujb?H1BlRb!)I3r;>9 z%l^mTQEwOC^N+k^bG|%``DN!t`k7{wi*~(;2DRHoYmh}>*?Ke4mpF@bH=^05gl15R zs7<}Mg@V*Z#Wf<@yJ%eg9kqYF1i8bSY0cpq>Mlneh>mh89hZVKY5L{XO!=E4q}GMzvVcK{i6xIuflK(W(-SR^%H^R_Ek#S8Y*cpwV|F z{y~}*wMBUn)IaM~Vc$}mzNMZeYbPoVQJ>yP{`-{rGykc5f~qa` z0b#99bFEt(hg>n&8yqI|uBN>yJ{kszAa8_NoNpn2^U zR3A`~@>TL0X=vYILCXJcdpGr&;>_C9*f-@UeQD)=kP0NZ^drayn52^a1g(*moDx>b z4WQcfvI(MC1{s}T9$U{%8Hv$Wg)e%?rH1lPV16YFtx581lezkNr~DdcUiD^N^8AI z_o6>jD{D;XO}{7&Yg6hmvyi8?a~jdh!+BR?Y0Na!y&bXsU3J=xpmq7G)3AQ1M_QXb zIHP~pOuAM**X7?d%M@mtv?fV1q3SevXz!EOX7JqJH?7TnpkzzcY5%k~`;%7tQEd(& z$cCJJ!VgO8bP#E+tyi6DoxVn{s?#9^`To)VYuPZ7zg_LiZk^VtYFYKGI#n&JepRQc zW!10hRJ9!TvZy{av(Y}S)67<%>QuF?`jyn7T2}q4Haikj%jzqF{Mk9J&CZqRJX>H0$03QAHJg$@CSrgbSvU6d(mm832@ z9SBNNSDg+3rLh!+_6N24P!!sapw)+}Q`NF&P(-KFjB19m8mV4s{q`cQb%&zXo`hbs zBh_pVg4P{YCMBy1vaL{=9Ew)kr!=b?*L;civg%ml!;+v@xoe!My4LDkC!a zS~0Kng{o_}}Sr=P~R?9?S7)j>hD!FxpRjrMbcg<(uGiuMzxt zeqHW-{}AUMX3zCHj@J^O=g;t``%$?w2qSYB`e)f)eW8Dj-PafT=h>lsp?`s0+!uQ7 z{=U#Z!`|UP3&8 z<4eH)Tp4JtGFO5Z5f9|tMW(O0fcyHI3yJ%Z>SqRV^q$}()6+be zTW+uP2ivRsm43OMXeM#yAbYUA#t$~9^Z$bhz0BcUUv7t)6F4`FFxVW%nZxaY_8@W| zkQ>SW%7exzb0Fyh*xNkHOfd4xGs+xF&cp1X_7Z=UAIcMknS;oqea+kR#`5hp!JL@x zia#;kCx2pYBJXer`46>+*h~E-{tkb=zt|7q-l67pf4RTR-|nvG&v zAnXB-Fx#68a>LCCaC>ub?g;KW(q5PwVuqUwIe$U!RxgYHxB8R#ul-5i>i75Z4Y0pI zfj#Gkm?7jl)EojH%$pA}2NMo4hnYh;a~R>`+(Dc_*c{Hei*tvYi?n;3)J3@iIe(Bj z(40uTpOK%1{gf+r0A~&~XQVsB&q()^pTSq0#?JN&c;_<-dxF{{ekMWt;I%`3U!HL& z`{BjrjJzhy;q0-w z5~jFWZc3Qr&2ivzVnga!umtg4IYauc+%e{8@K|$#+h4c&dcmC}r>?}+-)6AW@ z8D=^-)64*8nVH~hGs~>ZO*T`^`}Q^as(s(SPW--oh4|*&kGY?)u<%pvXYl9TFW@h^ zU%_8xOi-QGx13b%~2_9|F zvNnm55A56A`;Il_j1rT4WIsfu^%2LpEJlx-{X(D=d1Y3_*458;WPUdIoH{*kB zc-{n_`fEIa)NkZU*qlLFYQ-$`}iySH24(H+CF~TK1KQ)u1x2y8S%jQ zbbFc|7!M$x#C<=)3`c49!}2f!EcF&$KMeTkH06LOpYJHNyIx6{}>O8f8fe6 z!ti(s>0#iH#8bHbW4sejn-)(6cZzogr-E>$4BRC^NnPxQOT zd&JA)-QzupdvN9?-^0to$hqV?&o1Ts?(x!iFXFOBc1FsXvgWqjZt>on+l{a^E^o?l zrh+LCmN6B;2-#G6HO;fiLQ`u{{^3iSGF)A4@3E`wYI`rSMj2b>mhiOQ;iN5f;;P_|#I-nI z+te~Oi4TbPur78KTzDisF z@n`X`_80pZIX{mpaCb#;hM(^D=iLs7KjrFY@mTH}=g0a%ejqrIqc^y_b^Hcl>-ZD$ zd>a2|f3=^)Z*sg9_y+M9@{jdn{9xiSehBdxKa_ZkA4WXJ4=4VZ`#y=^;+|IEo5a7{ z-|WY6dETJ{IMdJYv;0h7K5ohNR&h7e-SqY!k?Z3)$5)zo9p_udeSHVBt?BDKnhszm z(-G`!I)PnGXRxd30&Zuzg6++A;I^il8O=M4@uU6r#H0NPV#~O#A>%rY-(>w#E88^3 z8}@2zoF8^+Yy2-wxir2lb3fUS;t%7W?C->H^F}S>4>Xa7C0@>52gP68Z)}&iHgT7@4sn{W<(m9 zz5Gk@%keAmUjF6yRqz#XPrsL69p4+bkJrS#;-2w?;2N+U@m-{Pf<5CN@qO`X^4w3{ zK7N4E4s1uh2RPS0zMEV1t{f&$xG&FZ|u3LO~wItodM3UGr^g57C6h!21{{$ zTi4#Ta~<5aU`Jx%Hm)t$j<^YNTd=Kb*{xL3rQ_-yMQZ_5pJTpGnwcn zfGddaNJhF5;0U)OxjLEPc5qiGcM@NdjCEtcac(R)-i-ryaO1(NiM#loXuZ1luEe(| zqufY$dotRM0!Q+!?tZSD#FK^T9c8fx9gk=0<~~$$eWg+zoT>x!T>I zpInsOkepArKDi3KD7g~6Dp}_yk>f454!kkBBDp-dktMegQ9^^XCJ%Yliw1WEOE>e64$|Z zB*$Q`clK}dE$iH)?lI1O<}OU$c6;#;`y_k0oAq3`PqHt#Z?a$VDOW#pdvkriWN*U$ z;Qq-0$)4og%k2T~>Gt9J0f}{xhO_SH#DF;$yJcM6!yTCH!_|Gsbzrie+ZSveJ?tKF zwl#-QE6fKaLxdUg|#P`X}ztWPi>az?DOjMsBIw z%{6k3i9d2@B&R1Ik>_KV7d^^%x0pgRCO$Q=kCz&|!5*CVcRny*osY7{jjJ~KHZ`Ov-LUU#p# z7u`$larXh|K6DNEk3+zQ#BXx_HSjg}syiz=Gx@;1;9e&03xpTl`<(m0J;C)?-SeD( z!5z&19+DiK9PAEqPjdDZ@CoAO$#Kc?$qC7F@Huim@1EkyE3QTKkZT@2OX_9!Ea5p< zpZ`7>JeX(I=PeF#Pm}i*cXsl=dk;K|crC}zx@WlZ3it}g^>jyaPI7kgo;!!|t~-MN zIw3iibMLzI2=9RB5}%a3U6&5{R`larH@@7>ACx9%J8 zJNGU4z5CA9b#=&h3fI4Jrx3n&4U^{NZ%B9`$>aJ#$%)Ak{BJdvN4h%USg;y#4OiVA zo2=oBTSkqzArB^CO?tu+vH>7Z%KWZH0F)&PfC%$w733C_kgqhEArmQmHU&DoG;}|`pT}V`!e|= z`8>HQdcdu5SMly!M^{B{qSjzr;;W)rz;n#6g*#suCr!xTpZo*B!NjYR+MFrt%lX*%ONMZ+AEAG8Q&hp<7}eqG>f~s*CV4SA z#vSd1FC@={FD5S}Hr}8)A=j$GGQ{V+qeCw~+JZ z=s0(*doDSS@NBY@`^xzv$$yj^M*gApcz2w8Hn}re$@y8y%gIa0tmGBqS;?!!vy#_{ zXC0p@fA@|;w#9}GuoB6T9WLVoa9b)yCx^QliVIW@8M(*!gBW$U-oA5 zliQhZ`^n8ob_UncK7Mj>gZ?Q?I-uMo14r@es=Scx#0X{9=ITxpIl4MYohZ0*623y zw&-^7_UMi%kMesenH_bGIz_XiF2u7buP)In%BCyWmE#%7^kkPr>kb-N{0!QLU_;vo zY-AgQjcpSnqRW-^2P^GPp=>LqzRe;(=i(KBYPxh{H^u+}u?z9#l*^9)DN zrDvZ{Q`3@}+&hi109?S^FO7DOE{~d#zp1UC)Z=Np@U(f+ZqZWCzi!?zZ<^N$Z-H-_ zb>?m2b!H)Xc8MA!^~v9ydz;zUIRCa;!hM%Vi@3TFyqtK~XbJJ+^z34eE|1A`x;Xm9{A@0cel@?CF&teQjUkMUesdGJ_c!w^*M2v@fi3(*p4h@qNPc4( z+{NU}apmI3keUkSh+j58x*uG`(bVW&^D1xnlZi-wW?nJxnoq&c%qQTdrgE;iZDA|t zTG*CgOWO);Ww!#ivRi{&+ty%f+Xif7+k$QFHee<0`6Tf2a6J)}M|_e39=55b2y`hfUD^FH{2xi>O?b@XEN zT=XpXJn@Us3&d-QpN(Du*GA6}uZ`}G-ZP(@yQ9y|7iLxTh4~S@oA}jeRrI5IEqXP@ zAI%TumFTrd_`UfK{K0&09^qf^jUHi9p7BqBk3?_s)V0wY#A~C+Ir9YA%;)@DoPRTV zowF~4ZxFAGp5oj(!dubDoO?NXjGT{0Z*zWK^bzM?j><-_MBkaRgl|ntUp^_9RN(9@ zQ3XQT=p62N6l~@niz;!xLR1l~1bz^G2!6;@DiU6f&L-ERQ8nMvSNGL;PD@{dR7+o# zbTzPKQa-62Jwzz((}h(!*2lPSlW-(<>1<-oGhx8^4Ejrkhy5{cbIlOx{s?X z%zdU<jL7K>J!I^HM6k~+RvQXDLvlt_+` zjw8=Kjy>mn^I9puw?Xrd5rY^=225RDiu9S`Z3Zc^YlmgpVHAO z(aEGvB^Ewv9x`vy`Q=fK+!2x18844&+EZ>VqPngXMnPtSew=O)4&?GI-4HaGopS;MYZ$ zL{FQix&D-S3Vf1Y?jCx(_vj(tH%Hi`n9qE}e!{%QcxFI$K+E~FZ3H%ow}~G@1GL1` z-_TdgLaKV2-x4G%MnFkT#v(NtlPpgTXWTQ%?ab)=LFDPr`8|N_y~aJ{H1c_vvCm_S zyWV0n^%n6D$U9|x8Kj#M{ulSFo0j}S_}M`m^wq1Q$ln*;2mXj;p7;|JOE?WYEjblD zm63_{rzBr<^=tPPPb%wQqQuJj7tM>{3+4szdGkDY9p7HoUyBr3-mi#OAdlQZsNipn zZbh1vL>nVDS0LOF-9WDEIdemFBjsBeifjjdNe7L&?{C*wkCHgzcpbizYWj$EZT<9hIAX>*0=ZDqNjMvZR;N+bO1a0PUr`^ z`R?dnx)HYXJ<+|-;n%~@W!|B;mo~Q#n#}&_LMNgTok+aI?@Bxo>`&MYT0guR%(JzFOmT-piDoSncd&~c=W^Os`1{WyOKXD-cMmOIIx>`TTc z5z2w(;<8}bxC~e(-i4WmUHk%Y0W%Tj`3qQ?a1pchH}kug)d;)gF80^6^5AM#ARKJ3 z_Sg7pIlhkH^~~zuM6RW|n+P|MzQNxJ9o@z(`~Kj*;J$u8Qn&k~>T1WnOSut~$KiQmQ?((OYlfhHXDPR}g=`MeoIhFLC{u=Na zb1itSISu?U_Yrp`=0mV8>&))*&Lo`o#(~9*2aB6x;ECn{a5;1GcliU%{^0)1$=~Hq zV%@>rth*VRyW8Jt_qBKX+w862HJrQKA7HNmwX5cCzpveo^ZVKT!Ts$4c9s7q_i=8O z|2X#v_(|?l@JnW@SNX4UUxHufz5+kZeGO`j+A6PAYpc9=HLdd6FSW{R-{UI2?<4Sw zTs5=GS2b0@YNjgKmhZX8A8p6R_xNM&G4>vRoIMsi-W~@&%e?$O{senG=@ab<;7RsG z@ML=uc#1t4Jj$K|j%FtO9$M2;;B(CA-{YUL&w*p&(L8x0?7FJC+& zcQ55|x4+llVsGZmW%d^Ec6%FmhrJzKVebI%v@5`s_D=9FyApiRJ^l;`52D$oR2flx`*Y32{Uc1v)d+m^0?d!5KbG2`5 zVz9EQWLEnsrZQOH)B`J-`d|~&7_4WSfUCHEpP$d{%YA+UGcfo0UE&4c!gv>OQM?db z94`Xr#f!m%neVvI9}*u7?iU{dp2l41eg5?LH1Lf0bnwjh4DhV@Oz?>KEbvt3Qt$Hz zF~f4dzuaDC@Ap^O%fWm7@ZA0WN_z!qt=hbw<6+=sl*I$Swb|M{;MAm-#(Nw=m5~yIezX58?-WOVfgME7KC(%CrKvHd~no{ljpz2mK@Q z!{DRwBj984qu}H5W8f3<V(=<^C3v;H3cSW%4PI-n0k5;yg4f&Yz#HuK;EnbM@FsgBc#*vcypp)iF=_3j4n26rQPqq_;b$=&Q8=RF_xk8{u9+~a-_t9&0PH3&S% zoy*m8ndN!hU+69ZFLD=y7rRTqOWdX4dCUYo?k{zhftR__hF{!3BSbdM*5=oLeB4Imy*6XzKHZvyF2Mi;)_XN z8eanLZkKUpncV~2!|n<0Y4-xJim&AAUUqNNd)s}$o8y}}b7g#U{3IpzsDIMm6yHMn zj`())miUhNDN5`y{}iS8kbm0W;%;?M`&->@;BD@9@G;Ik?QeH?fOohR;0kvqc&A$l zu5@>S_q+SRyWIWYQ{3?kr8qG64CVGXY1w*shT{R?8SYH?j6c(z1)k;32G4fqxV4nS z6Mn6qZFjb7{mym{ILFQf=h}JTJUbtJf_Go*=i3FOZ{qFO`UQ3u(!1D&;6l3yTx1u6 zi|wxVS*}0npY`8G-$u{+@1yU)AENKUAEO_@pQ0bZM|t08eK}i}{N-&qu!1cQej8N) zpXB;;#ZE?^n6I!F${)@LqQhxZ2$d-se_>XYf_e`_tVSq@U*83zR|s z+zY-R>%dtFQRPxYeL&XX7U-?H{aUphA%ENM%C zrEE!^v8BK=wlrAQmI2q2_a(w};7@$pOaANVo9HF~bMzDVOY}4NYxE2FTl6dVd-NOl zP4qih(|!%sVg~UgU)$EQFZ1Tl`0%yIx=)*Bk8X`hfjhUvQ`!0(Nmj-K)L{GmNiN0x$SieN$!}U-ivg zQ?R*f2DWg`!IrKC*oT$#ull~MrGM48ajiMi*>wV2yUySXTzSoFXVGiEJgcN%qYPj4 zuldLt`uB@;R_JrSrP4Y^!j- zimeJ(wbj6CwmMkd)&T3++F)H<2h6i|!5TKtzCjtj;@=<)ac}U%=lz?^r7m`F`o(Tn za96iA*p+i{@};kGwHJE<-t?_pOV0FWkHDLLE7ywj)^01XXRa%GUggSLz5=Vk-}2hw z_Ld)l9{Mfb@OA$dCGZ;fnm6_>LJrK?ieN=s39Mu*+jYKW(jr;sTO}>QcF8ti`=lMX zZPFg>kZcQfOgey_l8#{Kq!ZXB=?u0=x`1zR_c}`DWxtN_hJV`+a@)JNeY2!#^0wb9 zX$3Y-wgOuvx;mVh+PD2}$*tgB$x86n?aR^U)kU6Ng z{a`nU^bj`~+};g$@A%2gf4<{)bd$j;Zbxvcn*#3Srh?PlPT+Jm4V>YogV!Wuz?p6a zILplhXS-S87&jZdfZ5`A{DsK{;I+v$;C0Eh;PuIM;M>fgzT?klHu)Vt$-V8~^*wTZ zqjwpPb@A^KdgR{qeWN~{8O+S=yM73BwD0<%(GYN0G!z^j4Fk82hJz!b?ZJ`J2yj$1 z5*!_k0{cXxqxXF4Wb5QT-zI4dwoTfA+aztl9=4}_&-b*wz+SdD*xU92``Er<2^sf4kkU=4grVI4&I~g)`4#kzwduZeoo%^zb3zc-zUF< z?=oZdzAxv>y7zr~R}QS;%7YbM1+bE<2u7|FSk}Em&i9yKd*8pGya)cAM4bO1d7t!$ z39&lk^7rCVjwR%=7T%WEePaT9L)yjL_33Xqd8y)O6OxgBbrP41K&0G zv7gQC$;ZB9)B)@ib&Nhi6H(WH;$@%d6W=X~lTUp2q#Ib5bDy9yti#o+l-DPeZg-^N; zYHk5Co`3MyJ8pQQ-3qs(NFzX=1Xv5G=cMzqKV+-XcD+% zG&%arH$h|gnXm8b`Oka<;?I0T;?H~|;?K|kHUjIB>odPcw2Yj4MtgvJMSFsKM|*+$ zM0 z_@7*(kx@R;am@X+WO@Qmnm@XY88@Tlla@O0il`_r`ZSNqqh6KbO~)gCwP zRnuN^?Pt_3#5z!qcE)L!T3xj8(sfqmI0sfC&ipJ?=6prg>}ij+ye?#W{c1pbT?3@k@nhLm0xV6eU1=q9@@dnMk*>zDe|>vr zjVUkLkeAgnS(E=G_Ri#mzBFqkW%aBjslx1?$(no#)-lWKSyA@Rw2RNDYoUvwL-Evx z_V{@;DOw>Xy^5pewjnL;N=%K)N{DnU7Tt=awxwxV-`-hfk4aX~WTWY?Z0{`dX(Ov= zvYnM#-z{kGOnw?<^(@$t*RD<3RjCAxv?DEx2%?~TduN6Dw2{3t*^`$w`J#N<1aCH? zS6Nh%&jZ<1(f(NZYiN<8XgBj_BdcdkIg-7zJhVaDb1STePN)H~?430s^?%LYnQYl< z_oV7{OYEI>OX*9JNom&hX?3Pn`sI6`-juyFc|a(}h@}@a)hDGdjbA+DK+%^*F^uG2`TZDT>ktr1Yh+vxSaiB~T-1SrRnRl>A}+_3WJm8)w1ZnZ7kxItzBtHfQgw zC`)I-4q8$6&a@*uSUoGu-kI#E1si9X)w8kG?muVmELb`dkNj)eJChs`te(wIx%zC{ z--hJYhN7F5g#+1+7)Csl-bB6}W%F=2z0ANAhcmYz%V@&wnWgDRER;{&euPo< zT%uvwN*hgI);Gn`?9A>%7)wvrCq;Sg&2c0gN3Ye3v}}p>0(*ke*YpH?fYN#O0A(vp zGER3;_R%Ecs3#6~OM`b9S?iFD(-o8z59wHgRS{Vjk=+T|p^!}qPb|A=ozgzIBPjc5 z>VrFgvRNbVOC30t|EWqTHm6eB#%t8T^c;p1s_cEz9g?O z;^mUF#m!~cQ?@>3+f$yHWc_n%V%Y%=R?>pSG;wxG+~V)@zogn1f0zFyaqZ?Q=N7M* z?NM=V*-C2wUzgo8@%n~v^hPOPm;YVKXThplu=6Hsw6c&SdAt%d{jaxG_V4rmDw|SU z^EL7uyE!kgvTf3Vn%TVn*L=^f!56HojLR$BmV1GfWt;W=zXs2*!3*ra*8i(oX4nJ?z8$zQZD=HPi*BlgS}bMVf*p)Y3H zoM{V{ZS0Xb&|>h*EMLqSMauHf=6o@WYJ*4Sj1~jsNyD(dN9Lk@G0XF^IMMnZnKNI^ zqNhLak-7I~Xi*k~dP6OJpxdG;GV{p1z87Y3@&54d!hA93(_-+*EUQtQqQ8y3Fb{&u z%j$9Fi}{bzV(`CQkRoLld2_TVz88Ek%Ui-T}6h|za3gtgNctn?X^mb68{G12B=vzXO@{6AD z5q)DS>9U* zBfJgAEx>|&QGB#$z8JV*LB1F`<%WE*Fpd~_VZMyIdAU>`i}NWm&|jd%j4y7?5ydG* zg&o0e#642_?aB9cgMJEf#0_b&7qnR}rN|!eF2fyt2tA>qKz{`(^3Tv>;Dv!N7AB)+ z95ItrH%E(s3I{^rK}IcFIvvKSZA3bL8cy{y+VRYfgq{>x0ri1nMlv z7iEQihd;y}Cn2eBnT%SHFK$eQfl{}OFaGCgQPOD#D7{^wGHPKISvX%5FWfR(+;F^@ z(W1C$(Nq{X<)%4eVN|#s)G1yX#)#Q?QIhAT#)}zu6fO2cB9z~njd|hVly`6Qq_|~Tn|!{QNvhJ_1bKCR?pPQ_Zi*H~h55X&3mkFN(y64` zK!ussM&rw(Wz^pAMf*5W>Jh$BP+v9Q=o=P!@LO-$wK+ ziW~&(7^r7-s_XpcbT>g#4Wq`wC~`v?Reo(UTGaS&eeM|eVo{Q+eA#5DR9b-H8_Fh3d*P()8&@&#s3-I&6d&Prgf)!xW@){r}= z@@nA}DSO=+Es6@mcyWE{w4hunUZ|0xC^BeJ11*Xp{xOQ&Qobnq%V@En?xx@vG03R- z<4Ezv!gV*&vIe`O@i@^2PtWjQU5U)3#8HB-+9?sQEIg z<|~38r|3~*#uxwCcyWF1D2fz?6-|-(w3sic7Op|vm@kTEH#c7Fo$7I<<;ke9AV&;T zm`{0{6W!ABqPXCnA2n{N?k32qMRCM1It=5*phpce8{(ry)8fWdxbbX8(4Yow>V_0q zG%beN3~|%KIHEXcptEW4Q2AsliY~W|FaGbK#ZKuww|L>7)!j%JQ}ozzLy8nF7Nxbx zB-MiB#cZS)bf;SJCZDeI>{^f_i_)WNHQeBI);!ECYSgGXjeNdX*lb27oo=2MHS3;f zZGs*rpGR)_crnx6Y^+T!$QLtO3|gDbj~4@7hB=L*`C{SYMRC)h!TBRHYM5Uvs7Do@ z6)mF{q{u*v>vPAQpwYi+QU3ZioLMZWN8PmUW_|k8c=6B7FNz}b`Qjg=#ewNqa8r7m zFw3~OrHOf4W$;x$vd@HX; z@`5DG*Rp{v??^EyFG%v2lz{S%BtJ@838-BetBt8qlK&p${t&1Qk@uIRwmUIDX=nFnd9w{@v4B@akd>Pc~z@M zsynme)j(Nk>P|{DCM!)n2=b~{lThc!W2X6i*soK9XVgKxDyqUsRM2HWwlow zP_{4nfqkKrJW}$?mxo+gkJJF>z~q%r)-VRLMzR6efa6A_2U1gJqxw=!HRXI0>PObf zv-(m^WwoZ7Qr(4GTfe^K4@*99wenOoCBInmkCoL|R#PRYANkYztJPOlQ#Gg=)m&lq zB`3N@uVQ+;XY%EtAT)zshg_1B=Uzw7I-)gKmBUj_Ta&=aap3|y=r z|0=9M)N1{#SJWzg^^IG~zr?xnxme-+E8|?{;aB2ZVfUW6SU&&CI9Db3l{i+63+R57$3BEL_9lc#rO;i`o$d7qhj%Axc9?PYPk~ed$@GDO$ z(@II6m!3*~%%zEv1rF^jlPwNe-KYdgo^MC0J-RO0;?PdrDxh}p%HBp*Q2TeaQ@0wZ z{kvPIS}E<<)vjIb;+546?UIu|O8a%SYgfB?WqU)O&86RHk?NpYkdl9M?c9|O4*9i{ zJTL1T%|J=@vcAz2ls-zfH)MlD8jZ%OW<&Z7*@OAd)R$^1tF=&HB{r(BP*bY4tiDu# z>(`fRDyy|nU%~JEKT}_-sr*{YuP@b9R%@ax)m^ByP*XLi8P(KQY5isORcoXA3N=-S zno@n$*`oStOl_&ARBMgE#{bYq{ZG_as43N2Mqi@0_30~6mZ&VNFVUNP$8WyA0%eKH zGWrs|Z5e%uvN9?Q^;PX3RF+R)8D*)yL}{C&uRl{?1?lU5y1t5{uYaaLlzu+z6+?e0 z9YKU{CuwZ>${upBiL>P!5rL#mGwFH?PGH6<_b^P&TBBqOXi|ZCGESrv6&};g-l7Tf)EosJu~BeFb?V)LK#e>z|P~ z0)1sthbSw*zM7|!hUAUrMamoht@QQpkPnOEUxB_dDY0<+`lJ0}))PuT+*0}~s=kWq z5C2=`!!6-o1?7#R`opXzl)RBi8tM-v*>6ss|7Ys!&&c!5Qb}I&d^6<1e0lz_Okdf^ ztIYqG56h&Zuq~12i|P-zgnt#)9~Q;GimI;-<-`9=^i>r9DkvWoq^~eu&ZsP(zKW6$ z3(6aRw7&jb{o#MBJpa$g8(UIeMe(m7Z)8$^{&=}yeTDIIrsc>VFBcqt6|665Ix_u6 zQS?<0i6fIbHtY|J8h_P90H?6S} zichs5lmS~3%f4Z1veP1KNvd7#2dIheuqSaJ zf>r@ZW7wCwwC_&3l)fBmSGih%_6*cO6Db>J+O4X+It|D%fFN6DnwuLyN~|r6v7}`?aTKw3+{t#Lw1?ve+GQ|?{IXa&KHXiX zm67sLHi4Ge3~a{H1dg?PPWDbGrtN+rsS2z&*3MY%lhaO~3B;4ROM4BZ1)I#VEIdqv zE~bzQJ7Hy;Ox_Hql4o+dUU>@Gk|XUPC=ZHib|O^{)cWUX;7+;eCjy(d@Jt6T{F|21T#s`NbQYI1Ggf_EY8owBB&^FHrL96Gl_Rj&(0ywEG(nX;%E+G zXK-uI%_Vnfa5k}QiOvOOQ++=EY{)Mq?1pVnX=Pt@iMN++NZAV!Cgzir5x``zGC3+ z#CvhPJGeW?d(%(01KW{rZ^ANg8Q1n9w+Htm-WS{l+>3ZWuI~lz#qoahx9!39oZFw= z4%~u;ran!N8&?B z9gKfW%{3g#wIp{K#|MFj5FbYBP<&^07h*mCm4_$xe& z_z1#sycQnL(UIgl96XG(N2Pt*QCy31M{~R!Jd*fmQb*;EA?K0cksKd`yxSSpWFNe%CwBV~yr zzNQnYm{^w6JCc$e(wMT81yV+;(gj(*#H#ps}9eQ zrBv}g`6Q@ETD-3&r6{YZ;(awKU0J&l@2f>wii;V_LL5u2I^z4q>%`+M-!C3moMTxy zEdiF`I3XSL?z&n&y{mkBm%gt!->RqSyXBQYEmIx}INnAM93wPL;=u}~`x zCA|qHZ%G;xYQ=nzv?M=;b=N}Kh?ayT97Jo^9tW+|XiTit@>(;m)!EwPpp{TfiM3i@ zYv#3%UV9w0K2)pewZ}pG8?=I6D@C*%$+K|PyR)2okD zPp1{5TEnKD4eIg4S;I~T?Qzh)2dxp+9*1@*ih{MrK`TSG`$61GI~_##6$$F!G^?DK zHz1|<0cl=Y-7m+tE7zcu+6Sdi9h}}F+bZRe3{_6D#aRX{!_m<6y(CvwNTo>G!j*J7 zJbg3mDlLT+7_2&!A|8?cyQIqsNPdz(N2c#RGJV&P+!Z9s!AOSs@=@tGk4nE;c2S0K zrgbV`N=h9?*amq~Wi~o3t=M~iq~Z%}JOBoX%q<seVYd>LGR|1i5$)={e+D!n5jt3yGKTl!f3T zVoAz`ur7mvAI2`jVO(kXsV8 z?CML}*n=DeE$Z*anIKv3&J|hRU&g!sEnoaC$NV+qzl^tws|OArxOzQ~q+=0R4;(&l z^}yi+R}UOs^#9l3?UJ(thYwsmaCq%s)UHKw`1N_a_;uj$S|uS3xOltvFKX9^=Hs<< zQTrFQCqz3xwEsgp8?}E?>o2vZQ9Bp4e^Glv)Pq+A#cR}$3)Ro7pB1VP?@1hX#cBVd zc7tgDqP#U}k6akX{Oje5AX%u#mBwlyygA4hk}QIhvA%rKKb0m__nE9A4j_${$rLlVU-E@yjUZVBDPtDWljI9Y&eEN=f?EffVmi;6ownvozK|TT zzLXK<3&|RiDLR9qia9Ag6fIv!`!+9?2j`{o;Jj2C4HC!vls@OD60YQnj__$w;DVI) zGWjA%7D39`w0zMfl`kaQOUh^q7Z;r`=85gW1;p#i7m_TbeVc;}P?UVpE|n}6^PKhN ziy&D9DI>@i8_E;~C5}v{2=YacH8z$nf=m(Q3u*BFmM{L+ll-;xOJ$+xc8q+bft04d z9UN4eN$LCB!$GC7)XZ8~#TNEic7TIQ!>O5#j&RUQq=N<|Xgz`kBxpT?1|(=bf(9gL zJ%R>AGeZBjbRW`s1P#a^)qRvnH4|l04akP_g(RV%#VA^TA)Q4*Eym{b7eRB8FJ-JR zU#Op6Uvm*O8bQ7Y+KP>}7=KQG5wsNr^%t6x3wn*h^cT`x1T98k`ir2s2wIGS`U~kS z3TiPjnPO8~j7+i!Qiik`nf^kWiy&nbEnjR}eqInz5*Tfvl^Lh>HKstfioYCB-%1@dB&DX@7)f|pi+*IZH^0Us@ zkg5R6Z(}{qi}Le0pRFNExTij$E;`P7oNvH?Xs)#?M-549*0mO~bUvjRe`{VvYm`cW zT8Y#stXAfaYJ0_r)nYVTtM^fEtxeLXTlKECrFmPO*K;+$t9~i0ZqoBbyLwW1 zo{mLFn$4B2NcC6-REuz&krbpkUeSwcR5Vrzl<#`gUPRE-)WX7>s-MvNiqb@Hq9}O_ z)jO!=s(;Wsm*6M5R^Je4LC?{h`aVP1s0@Pl=7H(+wMI$1FZFNI+GzKs{!j$FxrEuvJKv(d-K2YE*ytHp6+ifI?KkU8?`;LP2AJ&z&rxdoO9JHFW9dUa~ zt}>~xn@>`|ba-0BS8xxe=tT11hI?2gIde2+ALU)szL2V zQf-Fyrun;&vbFaG>rpkRy|k*$g7ui~9aC+phm(#*d&jn<9>e}I?fA>zJGNmxswb3W z9lYS?*JDw8X&e9ldaR%Jaba&}6&JU^u*9Zskai3R6nI&tXTSN^=g}bUXZbLZ}?BWkLcT^l&$}gL?Y_X z%PT=jEl@PCf6yJFuhhR~>t96qS`njXlpv*kNAjQES?gl-K0yl9d#caUJF4eWU#4eg z5~1EnT(@{ycHw^IQXbu-H_(6R>G}`l6&92y^?s5KBv0z!^ltiQNhP{d?~~oVCGYX~ zw}|KbT`&LMHYTY=ZBKEOpCzk{xN>u-@(Ss;b9K0B) zk`YHJ4(c09aZjKy^?0G5k@O@PO_ZoN)Up02P-Z5*sZUXl6Xdr1-bVkRULdRw*Sb1A zLG4ng|5P6!X-oH);*4Y@^)Qm>OMv>nygaR)+}hbCYf9^w`BYZ z>338hPg%-HlAT6I#VI>Uc$LUihBB2*Uzs2|y%={?A!sBfnO?GVaj+b5HF8t}CD~Ue zM`f@IaSh(C7+8#>n&d74YW!D|+>+v}5!WJjHLyByZSqwIYY+;c^% z7)yZFh$Tf=%jI#8q<0emRp*7 zQ(IQMR$48(99PRwM`bymjos8j!s^PfZd0v6(!9oNm3S}JrszX;>p_k0RJRpDjq0kB zM|H3FR|{~UMt2&)Ris8L5o_#Li5e-9*1Fn8O@eA&V?2$cs!}6r@3jdvs1wmy9dfAF z)lTY?FVuH+>PMqL)wfo;s-#rkIZ$K2dgQISL9Lf0Z>al*Y5A#E4YgF4xFLD#{-f4I zJ7}ENf$Bb@9yNNCG^CN5%33Wz7Dm(pRO?!=tG3aUdW%8Th1!9v+-l8kUS6o_Ait<~ zGN~r?gQ9uWuG)&|I%omZ;xg(Fw60oL52`*u{efCjUY>dnwHwutT93v~>U$&)NJdc4 z5~K+A6za#+!$#f}(&$j_DfE8ozb(J4kJp#$ef0i%XXVn@Nt+Rq zU($Yv3dB`ZGm?wcCrfTr?;ChdkdpKdq9XOjCAcq>wL%H$38F#OPF`LZ^QtEFCMrR3 zr66JHT|{r9P0^e@1SXy+dT2bArht_k$8|lBo3Tsic-dRu7 zw}rY<-HE1EL*grC2-07vt&~mwMVgu%X_bnoyaeT~np2&WOzS4}{Hin6X9b?4+EPEC z(Yk6YqjCM${^>r#o)nduC z4eLoN8?}dmWux*?OVyK9H(BqelE{BviL`|D&8k7QVU?E7iU$T=mcCZ4US$)fWusCN z_ftz&t5%MTD@u-5dzRj@9QoCr%klsE0==gwPL!v&)wk;VRC{WVfjZUJN^@52LA9s< zmflXeC1(x-)BK;w5VDDnCgBf$xNI zP|(3j22+byEvl`ntpyEZj&u5Ny`f4~y@B3Y^{V!x@>CA3;g^ggt)bqw1gLu?S%mit zWvi0Zo2XQ!71BGGPw!W6AW2N$rt(xT5&8|?BP#gUv;lqD=30VELuH!-)dtiyvR0uI zRt;rRooYZ_S*=k0fW9uHV?9S@8d^f=BZAIMqcOD+^)(vvDUW(am7<=fItX7Jo|^pQ zsRb!b)S&uPucdw|9)SZ%M^c~8tQVqI-p#PCZ zF!Y>d(ti|HXs<|UZR+jHkzci?_Y@_l&O+PLlgsng+JB<2R4Y=?rrt&UoBBHSfNE`J z(q2rX0?G60>w?^?ey{ zKHZ^bsGrw2s>}no4tIo+fJ#9%SM=9s->ov(_`B88^S`?^UlP7sz1#ZVEq=AB@77!B zJ=H2CORAP6gX(M4cGZ4V!|E%-NKW6QlF=8dO{wP8s@0a`KT#gV(|;C4s*c6e)a$Ai z)$UYdl1A0DsGd}FDiiT1p`?t;LffgOW}q zyOsi_bI#@+q}9>vLlq=VeQOPZW*em4)?9?-Sk+I>^y_Q#tTLpaMQSOMc!SPfoLt;Yy{x#0q%QS58NU}jsrQmzUTr^{b5V}at~H7)#+Qit zEB&KP)XS?hO7Yf}NlSXy%$sk#|<9)*=)KRra-bqY|JvRc-#I z5-1734r#3xmxPi>kQ`o(=hY)<&P3&tOJn{kjK!Lgl7|qD&!pFs6}mi9(phU4UVZ+hC2wLu z%TY^?tD^7L&N*3{X#iH|jaqSB9W2MWt@yqwp!VNwO{kM<&z08PkoM4cQ1X9kLUGXZ zUv2o;CZOyVN(-+uT0_}}v+_+L-FaI=bFewBWgD;s*n+#;@sC@9+FRI;P#3IAiE2G= zZM4Rc_uKP?wqRS1+H;)841wbr+Y+{6CSe<%qxBoxpqbY0M_I*^zmX1{*Q`SaG}-E} zI}>EPy%R^W2-%7H51c{$l7i?=@@(ka^7}-6x2~#>SFaZMfO@&mBTCMaB&wF2_0i=x zBmOUWO8tb!o2pN>uB=~{gcE2v(6#1Wvw0#>v}R#N(SgRRP$s3R8)+}rr|Uq`YT;o_ zT0Q-a>a?yh)UEoK>ZC;1qT-CA4M#Q8Z_cOdh%*}9W>jp*9cWo}C@NGr1m3FNL_Ltc zU2>BoyTH#RJxb=Wpn6QnKI)D2?SXzXYOPF8eUT_s(pMFprf(D-i*nU>i91#$Xck+t zRz|bx2}QGIp%9JsYY{|4lICjhUK(Gk%xd!-(d_?Y?>)e@tg=1d?<=Sx7CFbSid+Rn z&KSr!iIHFi6%j-fvjT!(Km{|33L@r=4d&41)ZMnJ^Xcw$&YijU&dj}YX71d%XXecO zetY?z`Ul^Sv`qc9J=FhKNpj7pQo^2V@6ig>liyqpReJR#*?(;eXhNTsLb!jh<_N zau&pX+8Zh+v1jI>&e0A|vcsNhpRK0UK5Ne%#FZiB?5#PDL*XU+nbO6c+b{LjuBo@$ zbGxUWt30$XyIQV_C+w~EP$Q(y|uKhI6 z*%*?mA4hR!&mBeGSRR_%eyBE9i#rB#G%qj8f8r;5oTyv9A%<69h?zuI*_cr7ZB5dq z=N1w6ZGY-PEqU#roj8+YwFub@wFqg=6ODA|N)D>!Q0tJEJ-NLpzevOxv3>O|O@*u8OcakgO-~wuZH_YJszE zTSI-aR(2g+w@Rtnx(#U%);2Azj_tI!YG;djw$8PiYID;*r=?Zvs&cM^WS!YEvAW!v zY(hQRCR$ysH>II9sm-h@_i208r$USDcg4%%=3;*cIbN<-3yE9hZ4rBnI>haH+DBxi z{t6pT$Y!lsA+bgK4fqnrQrW22F|Za=QI@}7EoR>lO=UgE7PQZZQ61N7Td^Pc-|a^Y zX$h?a+Q{{UaReeN6PL;*%5n3ytWw>+qg_}GrpJ_6NROh>U$(UzYrB^~!?td1*h6f0 z`(oDmT3)rUYFU+^Z9jdF^pw#{yeTR;Xvbs@@#OP4{Y+YCjVVMp5Z|zzxXUkK{9mfdD^pHDB zbH}7&3oR}3uJ#r=GDgGVgIcSs<6yPB7|SnI2ec*M80xsn+E4~5>#Pa=@~k_**zuAz zp@&urs7NitRocr!D#?-ZqVoX7^E_fErHbuu%n7;E5t-bnthasSLT3W>xlduH6}JLF3(Al8|6DStU;4_jm=6YOi&x!h}e_@3Hlwe|Xju(pSV zOlzJ0)wvga3d1wb_R%V)B(SBzYVH^|xKj(6{A~XZYpgQB-z)Z0qh_-$)^Chk?XzkG zdw;Z&<6K)tS&@0lsehFT>Rd-~p?@8#I<}QB9cen=R36si0^k1Kf(#A-uV9= z9jImP>Du4@pSF((#PYEDD7S5$sDE>gg1uW5>$A#npR`vfKdfgFaO3nf&NSMRep_Ss z$hvT>u9UOiIK$KgY7bHl%6pj{Y!8nG?}eljZ+9iB`TV8bc+NRSd9NEuJkg3f3S4t+ zC6Z7JiYnBPj$=g<@}_9G6|~h?S}o?8oK+HO^yG=sgneUn(Rn7dUvEn5Lwj;G{&@w| zXZj>==)*fBezWsQ&Pnx6&-A0T7iiOH_f>G3@nl+XR-Ib6n!DWf(wQi+b1$%R6<7O{ z`hkq)!T}@^b6d{D%~hae>s!B}e$Z;pYRFZCVBLk$IO0{%wj2kgRvMIA$*2+iDe2GM zgScu;oE%4E;5inuSA|Tojcrp~+<6XVy}dT9MDmaQ(*7#n#0->n`;hla{*b~VBax78 zt)`R{l-SC0`-tNlWx4*Q%53jz&UJZ8jIp)k28)6 z)FB^fxsZ!&agkT>Rg_z*1hm(Mq*6A8WRm;jJ^O+8SRNA3dqR3z8nRB?p0hD>xEfjM zuZ&V7hx8A$A`d&t%B-3GSH}s?-6-=SnvY&7S_J%$>Tdl~949z3P=l*y)f~;q#c%X? zeEm20pT6xkXoZo_omcWV6#sXB&o})Be`VcY;%|t4EKXB*##~d_fW_g?OW60tG+A#J z=_%=Bwkhh+nznumg=j@JuQmg}PY-jyPgL&wmR>AkL+jGt456vvUc`YQPGY>u?-;0FRm2y~cn{#h+oIOVVP;+K2BtJOv z5WmGNhPBX!JM@TZ$+50Q&3@$9#fVe%8{-e_-Y?EW>)OcuR;|aGu2m+hYqbG|pS~k_ z{X3dK&CmIb*|%ix%;bo5VCw`&_uNdc*i|WNrqFEG zrP#baR17aZ(pKOdVsJ-=)@|T!EiK|6ag){+ttO5i3w&o8)D<%7raYQPZCIH!TaTm# zwas-$Ls=(1Nn#&u0=-Bg9c>A{NqUM`@CIYFhxM-q*u%Q)N9u`o(N3Vxaxe6XSgM-T z8!e+xR)0#h1XfcrfH(Ao>Zen~wLH2+%ruZxg;r_A8wc?Qt$O`94yII#pBPEY-T-WH z;-sM@EqDWXdKgIy{1DEDQ>xXjif2YpT7^AM+u=x(Ry*zfqj-b%_Q4!SQ#veJ?S^2Z z8_LsTNW<|R*P=g`G=jAOV<;I%%Hw-Jg69q+jlu`L5pO)4G@6wLqj>rV(wN+loDYKz z`a-*Q5cxE#99|>*5yC#!HvkGDiPfp?580aL9Q+dM# z=#dygk#9A}Z6N`#E@T%XOg z@kF99qU>DGXFz9joJW~)G^X?PJkm_ol+NItM{)mb=uD0acxn!G7RLp=*@zg%j6H_Z zd8`+m%M-_v=BM?hGodqi@_5ektOYe1*9n}@W?kt5o><5m7C`6lysJy+Lg(`QV%}ve ztYbJX;e0-HK5sdZXHS40$MGcIn1deA@nlMmh8jid6yCWI>I&3TNJh0fmgi69+Ofo& zSj^L>kxnGKgt0G9C!Iu$i4%FpQqsvpdpLWfh z#6G={r>`IxQS~y;uB7ym+&a$Bhn~;#>v`7rsh4ovzUI3Djl?kB#Bw?G?n+`&_~Lhqn_2kC~~U0k~ndLwVSn`^h{c9Po$-Ns$_aGuNEOKwN* zKHhLA^cL>EkK8S}U0m4#y_F|-k-Igwn`d`I@8Wnr&)x&w#nt;sx99foo_nD?Iqu=E zow*0NBbVDt>8{*^y!9?gx)-{a z=bz;~m)l3~A?QOq`5bS10{R3`{(z^RhCa!0KTkaaeTw4&o_ZGgG{@&DeH^-<!g;sH+aL#&=)!WkY`_kHs<&yr3at~c*|RqJ`a7Kx4g|Wt)SXP-sWwu zLto|iHo2C$cevw4=!?AZ9iDhC_b%^w6Z!_n_jva!(8e6!BllMBeV%I#eUo>*PkKA| z0j2Li-{bfpxi_G1@cf6Ay_5Th+?&uhx%*?@^B(j)uKXxr&>vCSI`?DFKZJhF@h9Zo zg}%!(KcVcy+$Uhxwop;&Cp^~%`Vr54Li!Q(C!GD1H-8NMm?u8vDE%>4J|les6;*%6 z^Ua~3aQvKmK7}^s_(i(!3(kK+{xk0Uf>aLuoU$)LqK%=BLB6E4DfA1DUsC!x^mEP% z1+AsdIg8o#F>uCK|A@}idP}IIdVMYei^aT6SU;PCjkG3oBZ;d-VS&i>gVxrdb*qA} z*S?@lLM)~yg>y4?5t%3~EDL&1L}cNwBQotxmAs)JPj`ok<*LAm?V$QW)Wu?=unduj zsse=tBGV!uq7v7M%S2>-d2@!vv^8ajtbIaPTAf5>&bW%}#AS66nOJNPm}emG$?%t0 zERfeIey1o(EH;|wMPVYiVie}w=}-_)F%}!nJI9emf_990=AMir5(*mv9l~4Or)(sc zseM9M&c+^$$cBS^M0Db^Kx9Vk7f*@HnuC)9k%`6J1N3kZPkY{2jLQOxWw>lI|3gGJ z5!6%{i%m`_tT_m2azb8WuGzdzEF}sPe@%dj;zVH+p%Xz)--N=%Z}Yh>uA0I7jJ7YX zn#pf2Mr23x{)l)w4J$eiOY(y*dpF}G>Atm z7Pzb~A`^=RE)$Cx6YK=uSr>n`PbfF0*eLm3KVu}LUE$7RbZP7 zc-!Tm9`TnbP87Bpgj9^ew2fRr3M{q;v?QX-5SiF2!(}3}Kxg8z%fURC@&3A4tP$@L zk*x#k)S|Fr{Ixlus=D|~L?;Tn9K>@K?-Yey3B8iHh{D8QjlRNP>%mFlw{JsX;;)V1 zrHwo<{%Qt73gjgU3(R#hZxcm{!o*)&pj$voxAN>wP_bL!ufSsBuj{}%*YPe_yd;)87>nHr+PQ;w2L1{xwu@gV3KM??77P3pSS*lNV6hB& ziNZu)cS1#U;;&{<@l+tMz+w;aW>J&~?xBR@#9}+aOgj%kWMZ+sAf5+!+he2$K|3NT zu~;+kQZ4>^g6j{0dm1G~C60TN6o_mO_-7B#9gN5Vi#-9_d7QUB2mT2Z_AvQ}c_zbR zjS{Z_>`dyL;OMLMj?=6SE z!SQ|GBjyr?eZae4g*M{&K|)?1Cgk-|LUJGRyTnW%aQ1P+EFUM#BHC(7iMZ@z(tBX0 zcX{8BNbiG@-sc@ZCVdF{X~fe%A$8Dp z2%IF6`!v1rvxM0`t+v_BP8$(3wC0NN zYHii}C^$DCUd&|)tLbl`eNG&v1zK+vEztTeJA2=ey!P0z&4xWT^SaXewv=m`&$70S z%+Jx7GWsl+f(`X`be>Zypta$wd_AZ&(3Nu|taRZlY};YC)wbzuZ)Qb}H9NLytnJlq z>%5J%tk+GdI^0roRt+39oyXK*Gp2wE4u6=XZaGf{S&g1l0iW_}?tgWwF6^CWt;#LS7$#LTH&>e^|! zR=?Bmh0%-M-`0WTT!%9v`gw#GlJoA)e8^XAq0TpT<}G@pI;)^Bh$EQRly&9~XXULI z*MPQz>Z#s^r2mIsq>ri`=uB%@#vsnY>#<}M5^c}cZv`oQ&Dt?yaYUm}pCyer_Tb(; zRC~DlqBzeQUaNYlYoFFH)%jb!R$bv)$(eqsTAZ~&8_!pta{WVH32KBMWk?^Aeyfhd zTm|f&^saU8%Xueg14{J(w@=EK_7B&_IH#bWgL7wcf^x-K$vk(({9HC0XUpq{=ortF89G~Csx@^Boo4>L`FJkN0I*>nYGd(o@3hn>O4ClG@jE=S2 zF-q0z#`#CRcJ%sp-df3^ADP#>kt>0g@a@qu5o5`yOZBLGXXPqL*={tI@KQPT>xi|I zoV(NLN1<1sao8NQTHm&d_1_atu=e%1&_g0-47C31PiW1TK%Eop!(FzEUI2YaZJ=!^ z>zlZ%FMQ>CT<0L%SEn)5_)E@pP@aW>O-P^wt__GKlf{WE4u zeV@NpnPcAHp3Q5?Q%WI!Z+JKPHL*J9(D+c^sQZ3ptZz`}DyeG!ms}SA%l{I;Df3IS zuKX?~kh5)>j8bzdqq5m$C6An1ug}tFFIJ%{iIg3#>`@=-<)MdhJxaBDgy){# z@%l~4)B3B~R&u_cBK0|D^S7>{vM(sjoHMr<=&KT6;Fnmpwcl%hwFdlN5rMvBuA2*K zZ;i<(F*j+;dY^4+n|jrHum*fezhG@`wyNJ-KYf+*Rdk@Ao$}V&_Is6xe!FrozSM8@ zyYy&rWq>}}dW`xF>ID0~{a4G9J-VD8ro^+y#u|Zg`lp)AH9hKjWxhSya{Iczclw0t zq0p72N0eWx-;=U9W(D;b)e_Ybs`o;7lD$?Rm;$wzhbr-0TabgQ5eocXR~v{=^b^Z- z#kvh_<=m?6pY=ccN?@<7FV^koWSJ{nJ_zH7H-?2>Hx2 zdCQq-ulr7ai+o^fi(BG%*%E%G-f>DJzcPMf$emczuRKv(h_GCHnqd|BE#vdRE$X4H zNBeGTJmci7mZNt3{~`Uv8P-K0nUH?=nW%C9W3eZS5=*D`dcT+X+L$^Y)PR-c?GMZb9K zT<`dH(E5~Ckc>{DH?fGt^)%{BwW0kY>jlw1_Kpn8`v2t>YdCxt{4MgZZKIr)d#rtV zJUn7!t!n1~Q@r-%UGMP6*TH*V{ETO$-9!x)oVsubfrrp zXb+BKsIMN-9-JFpuOYOO<2Z5+pkq0XOSL+Va;>oyoEx970an+;67}m2r`(;vY!{>Y zl|c&}k4)cnBzboRvo($XSB7P^JGt?sQY@?LnF*A{E@9otkEd)RT;N_|6Sz8wR1fN| zVUv>lH14302)lA_JVGNBD)**P;_hK0En^lMzpx8AV;LIP&^|W}&glZ}LTSW1oKA`R zWKH9$bLlx~4j!C|ZF?xxh=DW7jl>#jZ<$4Hwuibla5h(GLS1n*hq89qbKUcBF3FuI z<|jL_y-u64d$t-EdI9CJTSZ&!wnuSxG*4*>b{E!T$h*Vp0-kbrtHIF0lpaTNhW!Mt z9nZBk&|^6+&}s2X)8N^SRp@@0Qp@*Fe{D z#dyO5IId-mVgR;O<)FJCw1m17sXLHf1ntl95~w?nI{)piqb;y|UJAW}`Hue3{@meC zqwXfEY`v1}EwHFoQ@S3y4ohk57kVXEH*(e-+o)^nHgVlq>}rlzQ`!s~yMu1z%$-0t zL#sGm!yHW&w2JdI4gKnejHp1ztSOevdnwyRi8IcQ;C55m1bQFG-B=>;!vfix zYkNrdW6#{p)d#R*?#62Q0QrX)H}r-+OxZ)^9>#X5UVMb>O`wl*e2goPLVIz19Qqjc z%15~83G9`~rRcD5yI+zrguiteWnI{37W%=zRM6i=<5%d-M^2?MS4|TVgS1DNpUCi-Sa!a7@I`TYqb zlRF8E<>}(q9eViL(B(*icS)&}TXRJ*7Rt1tQzwq+#F%5$*_**kNQU5n~uxK-!6;2+dh{$D5C8sBy-IrnZI!=U^1-@lejhjI+5cf z&L@J&T9XsA4M+%W04S^g+7gd-g*rN(MjB4ti_@l4OG@QwsYKj1gEvfuit}djmj2Kw z9A|Otk5m?6&nC@)&fv-%N~@u>IL<-x&H{P0;+lJr%|+IV)aR2#X3ndN&#IBp$0W&p z6nT9cmCY?Vx-(cca<^rY-y;4KNMf?%c|r_U4Rw|KLgcXikuA99jvGqlg_JKr{w_qq zwxCoTR)q}K-~1Gkd(_8n_3i|7OoQY&@MouK=o|?!#%MlyZf-a`}(z{UdYA9Tyr0G_g-&I?gr%KwNP!RH<0UwQiTW2h%Y75&w@|VjIqKN*R?b9XjX2)M^`6k%Io?LD2U7J;a(9q=AVbAw zJ9z3=Wa=H1+)aK5($f+DPR{OxHsq+By$gC5_uNCOM7Anv?;}+rLw9n0H&5+EzTQX4 z9`d`9rjBhN;A|JP0mr?_()*!~miLmYM5YE3+e^tK+^=__(pYI*flMvq{BcHQWzaIt zm9q~gB=#t@f*$+?_f{ZDpC%_ZD2u+}_|;;uPRM^Fdojq{+6rJkp+9s^y#@p*dUvCv~UK2L5z zLR`l|9bLUZpIii8M2~!dbPR~gU3FiiWFd4h$Co&Yxfaq>Um~3ZJ&CfH$uEIAT6zU4 z4ii(oLOKn48f9WM(U+*{Rr>2`ATIa96N#M)T}JPGJ>jC)>5XTS7eT#FS_)mtl{e^* ztDugC-XM1l^c>FK;Cwka%l&14NFQ7U6&L-GbS`uaWp6^ygX&HECjD~_)KSr!r1QaF zYw2rm(f2Ndig4cI{4(f;TzQ+GbusiJdfwZlE1`~r-lp^-(Absq!gomPp&K}RhhDY; zx}M{^&~?yt^tE?Mo1u=4-X*sQbS8#*kG^&tRFB^G$Xx@yhAZ!rzZR-D@B8F#gkDeC z`Gg!Cv>#PSL0VUXdo^pu}c z@&xn=`qNK2e-ipMS3ZS41p+K3@BF*-_S!waB$Ys?a`q*;=b+Dl*uEr91)FL0`Z?({ z=x03l3+|~0)vopn($As$DEkGueIT0VaPBYR)aKCB;oM)sxo1HgMf{3iP=J2Q@z>B_ zK@0qsUz0wE{))3-llv63_H?3-zelx&9pX zEp1xGR<1v0-_o)bR<3WdZ)w>IE7$jD-_o)bR<64CEiqJBxxUH1rDZFuTz?+>R#>*e z$`$sluxy2u>kr$viY;4V>k9jpmaVXIW%jMGW`&h2>|0v4!s1oezNKX=tX!F8E38~v zw!+HwI*9Bf@YE?B!^&0HzNKX=tX$t@-zv6jg{|vPw{L}IE391KX5R|Sme#Dy)>Uie z$}C%9<@&mPOUqVRxxNqkme#Dy$`$r4ZC$Pb(X!|0^$3j3C5@%ylEY0dh&l`FGsg_Y~u>{|z0w!-4|FWJ6TY}pE1 z*VpY^VbcoxR@l1!wb{2OV8;q8*S}W#R#>*e%Ju!)x3p}9mFq9bzNJm8*vj?Y?OR&5 z!pfD|x3p}9mFv6Px3p}9mFxSqZ)w?be(?rI*N0-?(y|p+uFSF(R<1vveM`$$Sh@a~ zeJdE*zNKX=tX!F8>q*Aw-(=s4`9`f=hi2ajYnE2)x>l}lvu|nH z3M<$5ZQs(GmD#t#)}@uJu6;{8R%X*GwsL9r`t#ejv}S$X$`y93Z?ke`_ARYhU$=7A zwQPm0>(K36Va@uwmFxSmZ-q@O>|0^$3j0>rw2G}<#rCbRY=xC8EL&ma3j0>EWh-o5 zTDHQ|Wo+zNKX=tX%(c>|5HjGW(Xcu0Lkqs*Rkgr=Rl;#v3+DlQ#V<4ri=?G4_()J^GO8 z3#BKSaSXNn8JWo_fBKslrBi>hJhsA!bE6-izP|eR8jUleycsjqRo40h8edrdHhm(b zddcYR=WM3le|iBnXYNi97-#UD%j=v<^a?Z%uImO|+oPwe(QuPbB_(==xmsIKKfT;p ztpas5w!ZAmpsu|(vW=eY`otIsTTix1&eS!oIM5HNC)ZjtQ`3;=jge!-YF9DzrlwqH z5UUSd%dIE8(ckpLa~?^r+*pV5r}%d2LzsD(hHqzhb%uv$t#7BEx_YhZV`tmwZK^dk zTf^d8^nrJOqKJ>_Y92k_jawSgT=j`Jf|ovs`pp>WEF#3~VU?|oawb$?dE-_Y!^(9H z`aHX?LGNc{UPg3eBeH6B)4MI&y*6U5p7Tcc%U0aW5yp}>(pM+mYXnH6T^Xy&^(n4Q z(o@s@>GT$rPr_GOu9Rc}pQLYQKJlNv%KFZRH*I*{N7Opk@#y!j$7_6Lcv|Y` zt!JQ-(Ouk+KyyS>7-KSql-cCa<6ue*J~NWu~8P=9d!-}PFx2K2GiOI#0k zJt|%MBM-Yq$6D9Z+qGZ%hPxKW-k_Iw7oKzlm_D1X@G?@caSe?YEeBh_M&h=A*l+9^ zEui-E?pzJ;Z_D*aw@27lT<@d5tMLisf(lY=sId_%DberMmZ;?1Seg|aYyFk=fwj(y zy_Ub(Us;aS2iDsB`kJfY>ELG9Y3Sdrzp`BJJ{qo3a+TEA*GK77taq|?Yy`?!D`iQx zRw}$=_1CwBv$axr>ewAB^@O#DD#eV|FCQ6OP2XiblU;YC@4hje<-y>{hz+5PGFEuD zPR|I?nar{cx}~q}#y!U0QoiYN9C6XDbz@ByIM?&OZK_#UQ7NsgZ>5;4q?AxfG3Au; z{B7SJT#Yq3MvG|3xzegD@`}RXS1KV~r(l{QKd+e+U+WxVT5 zVrK=v)YVgZmb>=E9&bcE|ARXl8VgTpV?;bXn!Te|_e2XeNZ%7ZEVPkYCtA}L0$m*BbIc4 z+K-eA#xODNwEIiw8*l$Gmb|;fMATGecMpEQJ5IR1O3rKswQmIf_JkMe!LxdH_9Uma zbq7(kFl*Hcu}aA`I>oCK?9qOQzVEh(TUf1x#K)EIr&-C3kV zqSmH8THj2$)88iIaL*B?q0-gWj@E0$UN@G$YlmI!s5CV~yme_@VfWZEB5`Y|HRSq7 zYt*`T^_uJNtQFVFxz~>MRKeB2Bg)lM&Xum#kbGo4wSksWDh{!q+Z(N|`cT&(+2>tH zSD#}qYSJBdjHsJMj*(wojpu%-a({1f`o`+dtVC!Dbq5aDG$>=`O8c~&EsxuiXNk{*u z{UG+yig?`ez1mLg<$4;WVi(#Z>d$^)&35H08bI}F?n=&{pgyxdC|B&K*)AXUz3%+B zkS#g#N=A2@un))^1yU=htKkad)OKP#rAkYvve6x=B0iF`MLux#jeR5Jj4f74ij~6l z5cf~%!5wNv+uc6Xi5eAQ^rQwGLyf%Z+TqwonAL3s^-x3rR<_t?uJSYnuiPM7l8@z4 zYudbPa+Kn(^i}%!n~l;hH@gNW5QYdaq5@bSahUkv+y}p=u6mqFbsbrLvOGmEf+S62o-l&GrO)hnz2B5sy@m6So-KT0LS9h~0aQ zGHP$=#eeGr6*Czj+cA>d?`)_st$J~_FLmO&UlFP6fsLo$mwZ3Uow;?@coliqJQ)9~ znzxiedvmN#D8`i+eel|}U5t+Iu3@b?x+jsbuJqY-y@_$Fs(DtgR3lc^kRQxb1E2%A z)4jlqbtRq|!aeQ_Hk9KKa%Fgxwc?Ipr2hDr$rZy%!;-(5CB|mg4>$G?8bW>u?-|9N zv47A&d~NmA9Zf35!`9J&ez@k1EUMq_NPKEr^2|8WKhiW>$0V za~0H7s3W?08x4JG?5WCt|Y3G`9afx`(*w5ltv7XVKGuw#0+R?EXMM-4;ch$e^ zAk}xVpP{>F*<-W4xYdsl>%-Ok%4PMOSj4@Rtb1i|J*axYwY}nx?wl!gmA8)nEBKY} zl%SNWq&)PP5>@@7MAa5zTy1v`3vDJ&Q=0UoT&swyG_{$i)08pVMmj>3D!s^cfQp_R zk!UT^lGB@#PEc1OJLYH(ja>m_w=wldUy>0U#7p}BHis&0vZ&?C80{gkPjT(KUnOru zp%>RGxg1F6;9WaEjz0=AgH!7m8Z<*3Yv z6rr=k#`(mFt{--stp3unV*A1u1xGCPd4u2Pm%AT|wdgxU73v({;YxqsEC*}h&_>fb zy*Wd1A`E%jQL}5}V<(>2?LiK9^?q=$C`LXu=7?<(v8=@$#uf?GEq~b4?2Bq4@tA1K zIu?VmKAN0JqI)WjJ*^xw$ic464GylLL_T(B4tZQY7Fz`$Yta*%W!#+cad5D@SDqG+ z1s~g^G7c6E$$mW6lYi!2QD$&(@U(p3T4>wUaY^jeBQg`g+HcHz zhZ0xh9xaQC-RQ`=9)296}Ob&3Iv?x8(Fe|DpF_@#|Gy1$A0npn5$>ev^h zEgILFsOBDbL2;L{{`W64nNRD+L(j^;gT z@G)p**F>wkhbOJw>Yuf?SaUpQt)OaZS2C+b8*ukT(s1Z--Y|(PEupTNaShA_w61-8 z3TYyABKH`@@^JK`D`cjUT0)I6F_okSFXN7Bq{Gq1W#p!lGdiW3dIlU;1})=!2Bof& zG2-P+%4a~eNX{f@q)KJTEZ&(#mxubv3C2F~M4CqpN4#T6){p|+$ef?bcYn&SmrTMcz($_3nORP8Ao*HULwpsw-0 zkmtrg#cLOF-?>oz=#7HyjK1FSm+*}1R9we$DNn71TCbO;TD&yXoGXaOGM_J|zAW|2 z%jg9?$jd#KkqXT9ui-A^Wv^kDU*CD-GF||6Rq{ICYqUpWM6M%uCG+_+Ia^QC8^F3> z52BidH>Rk21Mj*FYX9CqavjX&lx?822cGuEm^23WMNpCVRh+w?(0Jd*bTm@;I*wOE zH$m5P+zbYr4RtNWW^mVB=xnZR;SH{p*}#9n7;6T)Bz&UI)FNqw5?uL$6OB3`Vcq&ijo4E?V5qx{n1=*MHoM z>~K!i_>!)h9td^Ra5HHz)Rot++_?#Q6D7BhhCr1}xAI2U^ynXP8*keVJ(lBbtSLDb zdOSzh9c+U-lk3Xsq0pg7r`wYxyB#^uh_wc;5_0v=cIIP`=XfXHkjF#yirm2+jiJhL zXLgNC>H6(hC#2V!t1(?YQT}NV~by^+tMH z?oOVTyIJ9K3SO~l%=?qZ)K8-sUb4G5I&-`S>MZjEq+P6xIF+-#X|2p&e1A@3_E;?R zAgL8}4^QdC(E{oki-&k_4|EUb#?X8K>YDOLST}Pz)HO7Zu!3e8^mMK~%3E4PALOW~ zhil3o;HZbk19)vXi~TtF?!~*qwaZVi#^KE5fBQJ}46f+;(HiP#_bHw<+PUk}pXSNO zpw4JN!@YWdoW=23R_L4sb*0X;X$8--$jcS1WpD=ENabyyj_&u7+ChzW{v7Xm3TlK+ zV`M%Dbv^qJc=zM@ia1)>PkI*m1ZDflJ%MM4>sb$Q_ft^ED+f4l$C{_-$UV=~&#}VE zQREAx{m^G9dx6|Dcz+z={ufCdpd!JSc;W!`0Ov2GC+b7%bGK1DpNGD{@fGgt1a+kI z3iow{x>o8{G)^h>dCp!Xr+>)HoV|vQD1&O7dW~ngKt+$QQR+&PS15apXI_E6%CS(0 zSjg@!aSVFlX!M52RBR>Q8i5WPj)d(_?i}u!3$^E+lX~7csSmBBbRJsa9FD6f(c{)$ zwJP-wbA=g9HoJ^#Mh|D2z+fc|F1TIf>F)~9~6p8ul$vHz)6#zNI*>KQeU z5nnbW43y~^5l(0xHH`6x)nl8`ESEr){Z}V#rnYex2>a#c)Gs%uex@#P1;J8|TfhnG z9QD=~@WT;MR~~QS+`S_hcUgo>rEOZrWn;|>z8H&Y`RUBf=T zHTBD_Opzv9JNhoo_o=24bcLQ z9q%O$R5bMvob1q%lvbO-l z^^ZGV?B*C+XfIl+9J%jkeJ?rVl8BxjBvnE0=S=~EufA79^qV_^B`|{ zG+~)c=R_QnV$GxWsH=Y*uRM{)Lr;)X^N54gKh?;0BOR!1+*`wyxax(cp{^BqHjUn% zMe?^L@5uOB!8RjG^mqalhl&ofEqsDDDkWZI?^@7j;7?u2#- zZL<$Fb|4|L&_bEEQMY7z#yN@?Nc+(c2f$b_CY<$R!dYsY*sr5j=cr*aZKEaXWzq{t z&kX)b&%Bbb*eeN(W!lD(eQ29k$-VrQCV34#(Ve_w>(>(g%Jhu3Up3EAXg8j8uEBA> z_MYM$$Bh-L7K~_uS~Bd7l!F`r+uC z;}}Xij@A|1YCnD!M1FKC@j}jv%>iJSh-sq@$zC@I`hhabzs5_15-T?Of{(8pdoi!cLP)1IRibAUpA2U z3__apggP5Kh<@H1+LJ3<9^Lz*FH{?Z76*G{4Zo-rR0~5*YLlAuRW-b?9VNcE1xI)6 zbZ@ifpVD2OQOC%vBREm5sgcj<85V7V?66w)0Csq)LCOKw?=2yCR!Um**zGwW@@$d zmm0O($j<&!XTOZt>MzY~y8cpaxkgUZcBwTrVnLRZ_r1oW_BZ*>nC`tQ?*v@>a|V>dU4jK6+mCIX#DJ`<&mUhl&yPe6#cMa<22+`mFfI2IL}g zc+9D5Kh-+wm$rd=?%cc2M}$^uQeP_fG}X48#fHryn)*Fi6mR{NtPf-HMN9bA_ITgs z|1d70Z?H~{f2qCNx7+IWMy-i@78=!3uJAp+)0ux~5&bpRoh=}ZNVf6Lcz^MmeKy`K zFEj+%)JrnemN1q~J>=pL@MkSEf5HE+ zk9NO@vb*?3X$g0HPWcz;^?NzHFQM-H$eqOMv0+^M6>lkn{*vPko^s@RAIN-H!tOoSe<@e<`5edp0oKpu|0!Yqes`TtA)zvli6NPazZJ?H-q`Ts({ z-3W$PmtKXW7O^X_uckL{=Gd02Y9SH6GW=?&_M|o>XT&$~7Dt9xLA6eG;QT)$DU6fV zf}}6NmLx;AkZT6k-+~;thFnvS{58;Pl4QD;Tw_X<8?G!g`pb3D97m%JG=e(w{5$0T zK&X3E{+?qEk)eJM9Y74IzlHuS`M)PWAoss<9FY4r90%n7Ek`31{qN-Z=l&0l{d4~( z$Nss0$FV=9?uz;EIU9}#{J)3(J4#1z?9bSD1k@dw+@Hy)P}Pk1Mnj!du4Y^|7CMr9 z>gVg_=Q7GN%F{B&ONT+naZO7|bsBM16Z67(*N@W}#7JjTSuHw;@+NlWwf^B?5O@}+rWpG{{~sN{u3?ypNU2Cf93uIv~m6&=zrk&KpN{mzRE*L3h7mlMkTqIK|MX7qM?_`X@Lno8bS19RPZ<@uEXfZ*y2g3QAI@m;;3g5?ZfkZ!Trxbjh@&SyuJ^r zRjDtS{s+(l9Q%Ug4?vA}I1C%e;_lpxjwqZ?>UtB$A6AHi|>!$62DK}AY!*ZT9fpeS5xUT z<*cmrAsTXI;_q~RT}kRM7pIEJtPS63Jy;vQ*?O=x{LP|Mailm=Z0P%&rnd#wbZ*_9 zKSFx5clv#r+n) z%N7s(ZQEwJO`h?8d56^RD{i}D9{48S4!)MdYdzg!*55Xi!)yIrY*T+>cqaa@@pj;N zJp&vyYIAm-g6$|mcTI`EQgm(q^V_wY>q+XjYmJxB6`SJu=Y<7fXv@N{r;@N{r;@bsbcb8)-4e#S3%WaIcF_7c!bD3d&n zP5zYDkt3p?MN8Sw^RKP~>v-&LOfDYD{F*`1#*l3MQ-$+{ukfxJN+-d-|zFkD3KgJA4>fc-*aen;;)il^}_cz z`)i8zw|uAXa_0GEy~PTXZ08cuMrN7tYqV83{?R(27nc?g|BD`6u9s2Qx^hpiM0>UJ zSFhyo7uVBEe`MD{`Kz2iD+QD4W$davJrvd4dUomGrOfI=axI0PO!`!H0F{b(T+8Gh zMfz>)_oZL4-{=|@y`|i>s=%H4FXe8b(Hn3&zvOlSWT@BQU_ZO&{gX=qL*HwgB9c%NcBw5F5zT(<-M1i+|!9FDJ z4&E)c!CAxh9?`kArBs!xwJ~J~JaC$F)Se~M_HD{xdBeK5--(56vsi7Mt?aU%v>j_f z)`Pwize3*A*Ur7MT$SW^yJpY1X2087jCBvLGq$!|ZS3wk)|R$%`Ov*~++!rxRJntQ z*dp6qq?_N(FVw%zwImgZZ}d%cmo4mkP}f;iQXZbRde^FL^i$L;v5aeu!}P0dK+dsP ztT}d#o>-?B<@)NlmZUdduE&nP^nIv}hETClACjy1L=Jr@b?&M+SDb-z|7N+*ouZwK z>dTqqH~sKjr>$pRd&d0U*PlAn8tt_K+}9TyM1RWl!YjvGq0}45m1<};XM?z^mtCIY zAZk93#ZPx7jFwsT{s-l$s08$sRmE?eK?Oq=cO`j!?PUELLa z)eUJ)dDGQhwstqpY+w6{E5B^*2DGRxsdu%lT}UOacdWV z&ZSUSd-Wn$AL=}h?OdAL*Yy#-D0j`4K9z01YSsF*irm_lq|bC8&iavS3KcurvgOcr z9IK#hp>l{V?@r@B3anPkg)X%>X4=jkXdkyXs&%z04@tE#n40NM z8+Ye?C^b-#tiA=>*ZLepa?ON2KnrjMoL~svhR1|yo9qnyxEbw7A`rcBj@!vE8*)qkk{rFD}Af@ zhB4%$muLlZ-H!dF6kC`zZGCDNb2lC9+J4rTx*A7`)-iY7iN0nXH=xYjYuw4k-WomF zUaQ5TA;~d|ZEWxFMa^o@Xhdp=rA!&nlB52atvEJL_Kn8eqgK=RP}wt;n%DEO3CX#e z7L+$9O{Vqrg=|W4w#9wTn~^5L4HGFqQ#>1id(EKwVAEx z8l&QNi#D_M>b9FL7OnTk+AUhlwu*MM63GH=y$unb91O)Cf&zd%1N(5U&ESNPI?3S2G-AV(wopXv7&C{D1DC^ zh;8KFhQ3YI=xwBTq3?3V=<=JGA=$)nHD{Zc8}Zyo?iXPDUCnVVXZl;6Oa4OgYq9rk z;x`+^eiL&a<-E(Ca5ge4vXMJ3PPt1c+sGV<{;-#(84~@BJ2Jnqo%0pgdOI?Yv7PfP zpvE=aPHr7kzg+j$Sx;I=e_e((eG2JJs1f$3kd{M@us?;g0=j~?8M|x>^AY7dc@=a6 zGh<6B(UYhnb2{aePR*Un+}KposZitl>)A9JzR@Rq8dvocG9uG7(#c2^*LUd^H5r+7 z1XPdo$ynk~i!7MKFx#9MJDJi(V66q6|R$W--=OCeYQK3#z6I{?o1j7)mLl?PtS+yGdF~^ z0O~B-kTf?oB+Y|$L9Yx$Zw%v^uH@C`L&!8@UM za{eeYfp6cG}}4cQ?9~vnNQ8Gvl#`-%!F)OX^U*&~^8{pyEkaiT8o( z7uJ;AEl@RiQ)+$)+N3GvPm7A+^xt(OGOg5CMo$O(z5|2rTiC10Z(zP4|P0S zMtME*B9|vQs*mRJR}No@Qk@YS$WhO@)1XG~+eO_C;%_%s+y~%(q=?eQNMr60uUD&) zO}9d~GMo4w=|<>{NQOM$*_Aeti^P8Ny14B~QU%;EUKvkv6{O?936$7p#48gx?+U*k z$(<8PmGJ*~&L)xUQI01jlk8z?VpmPNI#L|tnu|)l!POV8ws5_qI(S<8@@eGkiOzhx zQnCkB%ma9d=d9Ff?nC0*$?2TWp>9i|?oKj?CuTrh zmEn5HUQpY29(lc3T?H_oHY$Ubao>DO>|1*8AC-9EDDLY`?{YR}0m)drBH^PcvClQ& zZg-TMN3WB^-P5EGGtTao;LZp~(Vp&XavWUI5UQX2apaCh2H4K-Y0?+jpg*qBd)>3j zeH9kMQH`LDD9iSpvyZy_TtDQEyHvU7$?-@dXU&&zzx&a-6Uq{JvM~~C5%-^%`nCHn zEJD&P;@n;7VqX*`pK}Q(la?SWPecNol4QfFl*K-ECn7!Fz3wzPvne$8uxrZEol^Qk zl_X2aD~0t=UxxlFhn91qLOpAy*fX#zF1*S?^v%$zuAyeS9(bCFJehqIvg8kt$hE zB)Qw9=>H^2?Bhxw{pH8fQ;#8cGS@~!PvUqo(&rd@>e1v*p>zTCWR9nhJDR?_fG<21 znRXOZba5KzBcby-w?B`f_s%DGI;A6^r*S+z$<3uu<-qBbFHI758C1l!l#*qn;q>8U ziHd~IAi1lhqun!+y2^wzI6E`R?z5mG!85sf7Ls~4efli&%gKuk9Xs34rL#DmO>QPs z9JT^F1gg)(IphXIS8zNB9WetsgR_<7MXT=LwGzED9eNIDtH_IbS5m%;G!?3rIu|++ zD$+ccG&RYBfzZjEujX0}J%2Je`@eZ{;u@&<`#eh4kOt7(Cy_fJo|yz)lS&3~b^*Pk z1GGcRPlT)7d$Stao>Kjp`qT3r*C`#Uq3t{$1xRqQf@SLp)SyR9JeLxwvF=Gr?d-WCud}~ zbEPx1gyYRgD&Cx=;>}!j%(k7gn~_HOzsj+{%CW!7vA@bOB-6iaIW`IzTL7~-deur= z0E2W-IK`2ySf?W4A*mzQ5lCIpisM=FQza-voBMFmh=jc=p^jL!nhXc2^#Hqx+q8ga zM;VF??E-@6Ozwz;>$G9#zzbSJ29t&$U6sb#u=C)CP6=6P&mB)$3HZPn9_@?+k>=wm z5lz-Z+fRVjaAjaZ05xcZiIli6ySTDF*Bmp4Eq(ynVlw&u==a#+Q(L?kplw16>i+&{ znkn4pC|ZlWI=xN80BZdz+I}kK4Zt*0(dz1Sb$?$p*|fwLuF7vkY44=9WK zR`HSF@A@6r{^$`X@|#SJi!1aa(hor&uCS*#)|f!vHIrH-r=*dGRLrS;QYs>K3?mi0 zj!SK%eb9Yf( z@Ny0L0i<5=?|?+L)o82i4R30Z(^hFr70<(7X@Ao@K~9J`jrzCB1=`r;ibLavL*bc2 zxhM0h)rRJrzCMZm9%u9Q2K5)|Kjqw^zt8#nSa;$qVxDi&|KeZAvkMZRCqQtSN5zw5^u-{IB zI~=_>riToH8r`RT(hKdmV^ZqLli?!uQxp2pFz8V3Ylrk04^_9=!=3RQ&b6lW$Kk1; zkB5#&zLZma->uj&vJEY4fCY9TOgoJX24$phU^1 z?rni&7?UL5VbHOh8;Nf$H0Fr^xO_g8eyzQ1IIR+19Lk1KoJWKrWtCD#JB@pND|M6_ z$`9?dAy?edTe+qDQq~wzN!jBb-NItmdnM>MSIRy0xtdQsDfFlwwYI&wF?=QTZ&gPcoi^s+oATbT^Fzq+Otb%0 zhX1ANjtqwf0+&kzhbsjN^dY6RvOxS$7lBv6ukvRg@Id2Ahq^f2`O7XzzVv{q7sTO4 zF8ewT7l8*FKQifs42RpR0*#NSSN>(;a1nT*@o&fBt&v!P#=kob7lCJJTupm08ec$f z6jui(FGl0`QzM6py~W_tT73RZeKzZ@84f=b8U9^ycwq0q;opS7L%L*Ar&*G82jg%N zc%bob!{Kdtt|7dl)GkKj;US>x&g8gKJCopwHOIVxz}0E$IoIc_^ZJu|p)=Ks)uc>=)}rwYhaU<*6yFnw{SRaHL%Am#10Jj| z{My7eFPEhAM&!)uLC}$_nrdN)Fst;Gt zi`zn-GhM-b?V)FLT)|cSo79slkQrm4YQl4%dQdrEd=5{xfr_-VIFKtSbH=JQ)H&{z z$hDSG=c8AGFrC{{2d+#we`OjGtU{_cV?N6{bZ5An8IOpO+L~4&*(O0JaK(8py}_LK zKbL39p^i$N1#|vu6=lwaH-%2+xH@slYR;RGSFf!`_DzFoH98NjXb9EfaUQ8Y)N!vf zWsRXTIGzW-oB`F2v?gJ~HQZN9UhKIh;Y8=r>XV)~A0&)jG(O}Hj^ip@tr zYbdwhXnm4jjqKitb6diQ@FOXagIm+*8d73A^@rC+Q6lfQp+`2L#Bpsk95}5Wh}_+Akb;N$n}!NoehY5&L`ci}g07Euj!}I}HObWlMgZ>5dyHe#jhyjny3sa9vC;QipKyJ@!v}m2U!i^vdvkc=iEW2a zOC6yd;fSH+9r0SX!&1!;BkxF995I|U3?6WtKZ0c3UdMkUN#X->k?n3YU-`$_yrXDS zdCc+rXj)TFbVNUf7L;4Zk@T*Re-9&#qjlum!%2tHB68~yB;)qVp+}O8!7o4RvF$in zUYtN0Pp!&-6G;=OXL)WCNgO7hO(r>pmba#mCew~ubf%Jw+AH_yO*R#YBgaf9O@lvz zOY)rm%Wp5+=-^hfy=2R|rRzCsV+@p$w>PQxEqCpw*ezC>TC4u5sIR|- z-{x=exB0tb&2jN+V`q1a-=Iv;`fu&|HQJc0L+d14l_Oqt&w|<+f^xFV?5cJHd7z{SRTQl^#C9@d|&WQ#TA%yzR?91TZ=uB`R6`ul6M zS&Nvf@VC2~*I(~yaHC#`%xl;BMyv-TV?>+#D{T4LF+q-K%9TQ4dHO9P)e`V*3CFW} zcYWw`j%TFO6`YrXF3;w;jHgPVC0sj)(lY1@j!P+D1`@O;#F=FvrUsOX8*|{H2Aqon zb0DJzoQno?V4wz^kKinaoN|TIaIo5H=xWYlozgH$MBJjep-_>Ho=`(TQ|Cj^=X`L& zR)Z;Vm7ExA5NUAobQ*-m&tm+DHiDuSLq$^qldsc2t`EZNM<1n4$uG%xsYXyWl4?!z zfvVxofp`?1NZE#j!8YXdjN8C3KLvUUXY0vtKnv?3HGou;e2_MxqxFjFPjc1YCeEr! z{qbSiM6QaX_ULuwCZox_qLmyqh@0I>%@KjS{&Yf%Ir^AHQinOd5Rr6&x;N3poMRbL zhMv+>DVadYMD*7*@)hK@?pHv?)@`6+x!05XNH9kQ2wHtFo^Fe_t)%n_a7kst*5a{Q zT-BZ?o^os@k~Z4ndVag(y7l0P*_0f{Rk4^@OPt-|E53I9x16rjlHb>%mF93&6y7@F z?A8fqx5nd1{B}K>w>PvG@46nmpeLszo$EOtmoRth^J705~(&8pi;rs2(3`8 zZ@v$?S@(VZmO`OeSJX`2km!yYpDK z^NQ=t-DlSI<=S_gb8x=G_5IeZaR`kc>i9UK5jo2daXE}D=z4v9Cgf-1iMqnyy)+$# z8$Z+N1xnahy_wC%hQ_t#)q^3?{Ytg3+8~qV#>Vg){aWoFuFf@@hyP6p9kEpWKYoYp ztG2d2jfLd*W~=6%L-AMZ0U&aA4_#+uB4((#&QN|XARiAXNOm>g|P2C)8 za>W3)so!oK$LLY=kG1D4yPDD7r5^OEyc!tCyCSEKSGR|z5A5atmjl)7zSmhPwQ=-8 zTTgzl#cjvBIyo?zkv?m`&HtVK?)b%iiN8B`V6OEG(0Z2rZuv;8Voh5o)}kC^O_h@K zifBP8q5ifOtQ&uQ)MR)YL@bPQt{OGT)vv~Bum@QS_MO^@7{%Yx%N@c-SX%U-A5tCrW4p2b`y-?`G=x~${sDhE0rw~ zmnw-JE%-IYtuk71e0Rh{G8(S!u59+(TahzvioHbnRRUFF%S}c~b{@Dk_J>|)N=P}& zXdX(t=#BEW-{VqhxRgZTo{`3%}hcC!vMZW$GQ{Ju7pS#1ZjC zz2wZf{Y9Cs1h*cH2~w<2ZGWYfz0Ud%NuYO-eb!$XQEUAk|Fd7`_xfE*&WICbKeAS` z(Mz$kiE)x|@;}w*|J#PSbhJLh;;(Fpci4ZdSAS*3rM8td9d8I}?Jti1qa5{(N@JyE zw1Q~F|7x#^_{7T0Kq@#RmhuQyX zzdh5SN)vUY64jjT89Xi*e*e4^2vJ?39M(eM7(KH}*qiL#a+LB*JB|I@cFHiMzfk!i z57{>Ixc$vvD=+(2`@NFh_sdn57{^*EXC2#;?yBg25Czy4zR7pj#=X-Hr1Y${8fiE2 z&I}#NLG~c+RQ^U=F`}KwaY`$HoBduph&5{e2sxvC4=m+x^8T#9dB49peqD?g{Ehx% z`?)r%;1?saYsZpD{2gjoC8~YjUf}G$nmF`}u@CJZYFhVejFEzzBDXqT2;^fgv4-1_ z94lB?A;&@*`umlDww6x@qRsMIc_tG@rPfy_6V+YTLG(Rwoch`_ajdm#pYu0nJx-|@ z+COleIN7IzV*|wm&XaR9-Kg)VBMI?beW=eypN~PRXa7<+6 zEk_VWIRvURd>%49^q1VNoYPttHLmQC$8A6RZD0tgeOJ^Vui7VqW38PG zTf|5J++n9?yMan*~}Uqea%|P!8^8Z z$ZGYza@%i>TC(1P_vE_Z%uF7|=)`{Jo2*%%ih2%?^?skq&`~*jWB<)YvrReAG?V

WcjcvKFIaCQ>m+zET?g4Tz-({m&_oZ*kvvs-8-{#mN#<#WHXUn)lX#K=@?(P^I zXHS;zjA$m8I%;(U>-W0XqI@TJ)$*MqUimK57uI&jgun;Zvo&Q8l{1wTfz9o$ewFp^ z9Z~zr32|7gDp2k!?UZNAFeRB1%e`jpyK+H0j_!1#Ob-i+Qr!Qg?38!>#n!P>+4gb_ z8x|#bN2%<&zdDd)DgQrg)}lS%;`2&gHL=gfs360~)~3Ae?167|zj%MQT(5OZO&+#0 zWxTcSc++cgyAnycsC+T6oXXIOzehfoie%c6Qz9v6wB8tj(Jz%Va&Un4Ym7Vh)-^(! za!HGZ^&5JW4Ve%Y{6Qc;x9Miu480J zy-JJNg(lW-*f(R>d-u+;Rkg7+hpKmt6KQ-l`+#;Dcek}pjB(fss>JQcxuaoauRJSH z>nW>TZTS_iJA!Tk_qrc$>|3wR*w}|n_%+6wYy<7gSr>B3-{8OK#bG7!ciOLGp2Hea zs)RM6Ze4ljx7V21T-@qtu(-zjg_%vuTFQ``Qo^=w2DNrFiJ*3mJ;3eFYNBX;>ql!= zIaHl*G(&d*wl=IEqva_ZtP3M@x_5AjgsbkfRO|2m4}hsp>{eY zM(Jna}G%K(KJA4V} zTK|{O(kCbWHKKsgo2N&F{$4^Lv|&i{{MTEZ|&E4!vO(B%cU9bp~UF zH-h5PGGT0sJ z?c4TdrIC_IpUFH)+rY7$<&&*HpS*nXX?{Y!lsmOn*>}}QTDV%0#5y7!M|&NTY%*8E z4A}_iNd6*n-w58cF!A1EsL`e5K-<#wDtg(^AWXK|dH-Z3|o&VbgVjc0P4NBLYh zV+JMj$e0@6r`Dr>^OU;QU@^6r=UkuG#nfM(b7!I!L*fDd zIu6eBzgtoh zBcZP3Xvz68P@`J3BpnAeE=Ehz3D6U`SFa%bfArDqL~`fyp1fIKBISY}xq1{G4!13$ z4xN=+MBR_0v;+J-7OK~*^Him@v0k?ANyeeozgCGe3Obt7kX>cmt0Zu?sVvPl=?T>j zj?rT8Y+#JnjZ>~)qyAIk|Ni9kwCYbE*2hslEJuhnr z0Z?Vi)Ks5S$qk14hrq+rNZp~zjcKVBT)j1fe1W@_%!BAN-6)w(&A8^vzC4}O4XR9; zk?MX%s{a{@+h-(hpTXB0$<+y5pP6Ln%+yvhQ%{+hddf_C$`r1)pllYsAO{sq+PCXL zV+E?3Xjb9}_Y`-3aW#xylT)Btq6!6dRlW4AwHCHx$BnTP$2t@3$R*+)tp|=IMJB;L zTFQJU2k=Db#;Yv zPMve=l&vd=;3`-8BhTqIfcpG8kS{HPCI7X{+#L$H2WeUc81KRLAYyw!ReM%Y z-#CZRCOv^YD_W}u9sTF*Rar-bw;bbQug$cE786=Z=rd;{v|QcrVFayK#cg`d*@(?W zAL55sGw*O>bFs_l!+&j_=K5dlZy{(= zd_4cQ5Yuwl`F=t*(@&u1mtgtfYT-nJcETqx=T9OC9=QpIX_Dtimoto?5?K zr&Ts2tFZ!+3h5!o_!{n?PIwj89@4Hesu`)boHbZ`$f>@%qHkJ+tR)^kbL3XF2w4Xl z!SyUKoZfPzjoP5B!}dfj{%pcol|9P#*r7;YwMsEQitD++bAVE!b1OV^F1Thr@pJfh z9_jkYk&2y1Y(17K((?0332!;;u}+bry?_wjayDSwashc>L%M#tHh}3bBp%*!jJra( zu%ZJO5!X-7g;0Qtz+~fq(u9kNhtC}2Qie-N(Ob^NRa}a%EyYye1g@7>SoSjFdhWUu zYXuYy@HtM z)Hf5;PmXbU4o{k&h4qJg#_I`s@w&1~aj(o(q=(NOym#h50wo788g|JLSP!z+qB`o%r7d+`!d+#QH6i znugy(adsPV_Y`Y^GYL4B>n`-;SfI3e7lM4VR8}6`_!zG8)^gaRD?GO=|8`^aj0V1p z^xcTP3~V*3!fo>ByH|a>2Pxt(d06*-O##}odop@Q0;Q9C5)-%W!N0w#zT1ntVzoW_ zw~>)Q0=O4+bR)67z)%~Bzr3QWFX!$?u(%X`@2WTVCML)Ba{leZ>>CcW2lpW+54Sh} zHdTGMiMxUGXM)$I`tBQ<1sulp74+IrpuPDDV)DZK@^3#d!cgE)()X)+cE5@a%T3C& z?g#$dAAB+doIbe1`EoR3{<&cE!4WTB`RoGrAUOfnWbs%_Ms(3K}<^x^-xF29X za3I%1DvatHZ6G*3)@$NbcMIqnO@5{JkS3n~5J*;n>5-vl+}TPotl-#lZet z#rBJV;@Bg&>pmChwwQkjP#k+C|Hb@L?=H;0l(<}$m|rN4J(@h)0ZO~I16&U5!&PkW zE)zMgW4WszMX9_ve+5uX>wc3}z}}>34cH6Vi~mxDRTbtJif^}YSNt!}pk?4{U{9{% z{MA75?TOsg%c9(cn12nh2UqucxTizht6kul3jc2hl*c%kpvOhm6WR#sEzR8>r$X-w z;3=e^O6(M{dtTvu*CJXCt_7pJvU(LEF#kI6eB%G<%q8v`Cs!|f)tnA)1lO3T- z;+2Og|5ws95}c;IWjw)M>ehAw!80^GUBa^>#)2~)xt>%K-bXyA#FIMQ?>H9d$ta#` z;@(FsZaihfb4omsqor!$7TVM^OvduBg_t`dJrkvs*6szA*K8%F573hcT6w+!)Dxq! zLwQ%fMQ-hH={FPkW6!9qE&p2U{FQCn=1R50=1ggk@+?nxRsv-^>!BgqS-EE2+G;^u zOZK7dLedxQ{KC^r>^n6j$_d7B9beU2`E;-9Yix66hkAAyQ?;|ZM*S*JY0$^BvTe^o z<|GNqQ2wDe7*CJ!lo zZX^BHOb^U0@La8=%H_3Xdb@7HUv)D%&L{mmc)&ABznzq~S01ig;J;eAcLsObDsR^< zc(ZOM$7@Kx0L*g+>35Q%x9giIP2YujSwEe0y^3`*njHdd+TyJ8R{h+;JP8up8XdgLW&>dzW&(1Z;W=cTXl{c*t&$ zPtV$yf_G0Qqb+Zzm+ed8+O8)q&dw??+n3|_T24+c+n3{gejV|)f7BC6{Q~gwl^6Soc(j+N(yzTzCH?NpX?+1d{1b@l^}YeT2S3@LAa+ltH~f3? z(LaG4AFI4)>m~nQPFS5l>KB2J;(h;P_{e^s@{|1lzOvtgSN;cpAK@x|55BWwjqDm% zNv^V8af8;4U*yEq@q{k}zs#wr;|X5@eua}a#}gg{P9WDq$ukEYO8>$)Ka}3Uw?CX7 zN<#V9hm+juBkAEJlv{ly$(4SAryfdQNc!vkLh>wvSMcV2Ikk2i=hwQr?FrY?lhpmF zPfyOUm6QA__r`Ii?Ktx7Pr6=WH*xowD)lGS>1&*Y`%`lMgz#9!TlIve5%(QHaJ739 z|9(OKXE;0eC**%L$rC@C%gbD9z-5j$JcUo9ov%=U&oQ}N96bh@W))gnDj*X#q=oG2h&Gr{|9-?=hK79 z^BEpYdNFsM+>?`jzrm^1KO{U3{1N};J$rH*@DE8DOWD5y{))3><)nXE@v1#JH+C#3 zUrN_di!Y^Xsm+(t7y0+4q#XQn=?Tt$_+0uRCp>(PH$IqtOa9+*;_X<@oc(h8QaTtY zKlj=6I45O)Hhqf|u0P9DpG*ImzMKxp{*`bj(AE2A()T!__%rGI)af(n2h{2_JoVZ1 zmE=nPD@l*HU*WmU*{9QYvnPR1X5RyTk9>0WzXK2dj`Nhq5PlE*J!dwLA^ZXO2TpVz zL--T$Pn`GM3$9C^OnytwYYWhQxxEOx0F`_6s@4F#;P`hVt~5ixe+?Q|UXLul*@%`04am`f55d`y}a~N(*^T9`;zS1Jj>5oq7;(U>Zc- zpCj%{WKepJ)2Zi^qj$vt_kx#o&$D}-l@=V!^8?aA&buB={y|B8x;MP6yQPPaGC1{5 z1Gw9t@K@kp8K&~(y(`}KD4>#yB?R^$l7C3*#}gSaqmIhidc)&BMxEt?mvBz;x2b(! z?teQQM*gA6HC}Ic-^bEYPDSpUKADD-J}kL@P+Rg?k}v)mU*4O0p8)pZ+C-k=X$9%a zt2GHUmph+GBS>#bE3>bsuK~YC4%aYf&$#z-&S>t%btHL4q*dfuS*?8F1G)3@w3?Jv zoca9m^fAtQ?!nb{+DIS)I4X@!V@yk9fn(A*;Mf#W;Xc*stWUKr>r<`8`c&(zok^F^ zz>XrJ`Ag%0UqfZzX5wTdi#SvSQspO8ERy z7B?r!Y0m}DNptyvHN@r2Z{j5EGQAae6ENpGJIzUJvw7+3K90Pkb!hNO&NQ2D#Yj%u@@}o4Ef#8j-y%-3lDZby0dhcNP&ArrSun zHNBBs4*(xXA5Dw7yC~hjzmKN3bN9B?FPlMW{jzCkI`Qe0zJxrBQ)imS|J%v)_H;c@ zd^AlZtzUKrDYvI7{Ogz9N&Jq~!M}dlUBvH9?fmPPP3Ec=^se-d)Res=-3`1uy%YG( z^e*5C?%c!mUFlxnJ*j`TE^QCoKJ5V9A?*mD>EpI+J>T1b98yGl{)A?M3dTz@=#!a3lXV zr4RDNCc-}HRXp<{;OSh?O4sq+S%fpwp5$H*+>7hJD|D0r}qHglimw_Z+ai_ed#J-6S;n za~+VaOsjya(rV!9vwxQMch2gdv;!z(|MW6S9gw|}_yOr8!hyh7 zay^Laf$2oxL1|caHSbXNaW(L~bUyI>bOG>!^cvu6(uKea(?#iGt{0_&*@m@D zE)B|#NJj#XOh*BaN=E~aPR9U`p%l(lpd95XuS-L+9vuQkC*?CU9qki!ltFx18LJzuej9)Y15K;PAg=sUDq(1uX1ugk(a?3vWuxtbWpQ`&iJX*sM~>v+m#*nDe&tM#N7POiDFZ4<$j zcUWqvOHpsA?Urv`0~4D`gz z|81{-c6-I>a+Lk=_;P&x?_BD_J^wp4w#GgGH;oM?RIwwc-u+PT#gPlp+Ft8=Ehx2| zRf?cBf)q$g4ZR;xBy`VwElu~usWvXBB6mD%8lv;`H-63Py?u^lNFSokUParu0bbory@Wnn`U#F4l~EubuP`!uV`9DQ!S? zgj4uG4%op}Z?0O_WL&j*84H}kRU00C?#NfnB+O#9qMmho?sx)gB2}-x`tRMI>vVc5 z0TcIjBy|*U2d>kgD>*Rd-g;6;0(a!P5FVod7TjAvd?72a_1qo7RSU?H)cIT&pn=&? zaStmi=x+X=+?faL!F71HIt#zOO^g%0DJbWj2gjnHfMEpfAGH^fpO_1`qi>_31f|$> z(DKL+&4Clqo^c348Mju3eF^&Z)v9qYA@*r6XY{&n-!oN}7rS3yzrgDlr~OFpPgu(M z?O#E6`)e;CbZ`Ga0;iKVJYBX2DV{Cs`LUiN>&dd7Mq2_si`KVzN~v>7d&2_g*|l*F zsdei`t2xiYV$PFewT#qCQr{B^sLzR2q-tBKo#lMeZP!+=wp;ii(uZ<=?rtkB&JCALq&{)0|zk+d#&Rrvb+av~f1A5>73- zJgYX&MAg@mo}aY*Qo1;cw%&nz%Kr2PrKQ+VQsmCtxO(dEG~hU{o}KG?*q)=Sd`bUZ zllVWJ*)XXZf1V-hdBC2^I~nM#@C0S~P0s`N9ALe8byS?GC(4c_?wZ*d;#t^JXm{JW ztXkEc3%eitN;@FssLJ|H4LPcFp(p*kt^2*I`{r`@#fz8m_vHCo@2T&Lm1|3;y0+Fd zz9qgRz9H%#`J)Dbd!5COFZF(*#c=-i3kd72Eq==5a}bFsr6iO zR_M*lQR@g6CpmxARK%#AR*hV7n6u8gC{7g*#;kRgihUiIj%j_##5_-oMMv`#!c_2q zGrxlrN2oZ$5#0ff5L2}CuYQS_cj2<=Yfs7pKU#~!vC(<*E0$NH?8K{ z{j}>i&pOVw4h-SidWQ-tiJQbh;*R>X>-tn{F?e7g`HFSK#of-XylUCd$~n#)O^(}= z@jH}yOEcW@poUYr;;u{eoYEn8Y-qRVGp=4;>8d{w$IG2qk~luRVW>&8WOqGCAJn3| z&qd9qR%%ia?Faj259g2MW%elHk^I5@VXhD64{`lUmHJiSSMq=5-=q0s#J`$YP?C-QHS`y0T=x&BN3!TdwO59J@upUl6Ve+T%T{JVLP zJ)VCH_^td2;1k>_vM2NJ0l$}jANXzZy)OSjenoyI|9=21vhM?bKnRWO6CmL{Qbc9=N|xmfcL$g{8#2z0bif1yLi86y>jm(*}HiXJy!m1;C+^|wubclBf0vqj!LHak-R;9l$LByAE8a(Ky9xAUPbA5 z@cw&q^=TdHAvAt!_dK2YA;N<|Pp7_){BOvgK;!f+GT~gkgzbC(>RHOGD?tVLKLnhju-kiTNe^dTu!i{+=66E%DaY^3n zV#0lBqCDOE$GqiXpqj)V6Fv!4|M=5NZ`gt~xjj9_UA0?3MU(hcbq=@MwWqQhDF4m5 zI;}^tW+dzF=`HyUq)bWbs-~nLk$w{?Z^>`XZ_D2fe0zR-{#H_M%BNO(ps7ji(bP(N zG!^a94~hSfCtp+EhgR%0<;7e()6g_5HI>bj-&88oZz`4PHM? z|8f2l*B=qu(~tN!y!>fCtP~C}f0F+&{}H`AvQ$?wvQ$?wvQ%F&l5$3rQo{?%z65Qr zFDSnY?9KIO`OtD0a2TcZL<2T8^`yp6f>C;L<%G`ivhsD=t+dSRvODujiQkpqN&NQw zuDoA4s_a{8t35q?Iv-RHE}zZ^mqUOuiNIA5WUQSJNjlxd!Hp_^0rv5zJuN+to zBKJVT&+{92+hyeqgfmO|%%+6xIr^Mu@&V*~hFm|-e?k12{8`{H@_EoSJ+7)_IynDh z{-^wxq(7StJ2djOrvrH6hxr1i-gM~QOv+jSU7HHjGH(H?Gl1%z z)ps+`~cv7TweivW&Sq4 z=e+W5<+VI@68{g#kH~+^6GspZ&-W$QEAw%11uf8hxqxwmHlVu@#t|k1UB!(fbO5zL zb$zw~s5bJ*{5O<$B;kns7T$Dzc?)kluhdRR4nqz_&O|F0EsErf7ovZ^fw^}DBTZfW zTl1TV-<;n9yd{4d@NLY`qbT{ve209;{G@z+eqser;@|e9os@4NWqp1nLj&6Sw&wLUM)`x%}LLc@?!bgA~A;*UDx7qq~ z$8rmA*pc`a;Cik*5jK>+pgzxF9dtY8d#?TM*a~dQ|26Gg<#-mJaVKmib|TlagkNA! z^y&1ObSAa~pG`YZ>Iu0vMxRZuCVUR~Icz9);n|(bH&Wt`*zCNW>+gB;nab+u!E^@p z4xdNEzbXGp+P>U@63(JbEto!)KAoOGH~0bI2hj07LHHo>lj&2y4{}{sZcqO2qE)*; zeVd$50KZ$s@8_SkLziXWA?4fYTip8;@Kfn5?0-DT`8H~^9{5JC&m?Vwp20Ha=jmzS z8QIh6=UmUpzL_3R=VXub1TXxd(xuoTWNmzn`~Y=rr54r3tU^SD@PY6(Ced% zb$r+8Vhq=@+#OSlE!LFVmA6pe^;mU1i)G0zm95DwSbp6`Tpjr>glDr+#pq(6d=z0* zzJT)Qm*aSLY%#7_U9Krd7Nd$y`JecjXVXINE-0T%TFpO4%AeA6eB&?DABjDiw61?H zjpwOx#rR@Xxw;&|lV43EijiDL6ko+U;m_oHE}c(n#L3)R{6B^j!uePsd_CP<*}>dQ zy?&Mbfl{AMe<1u4_{;Pw;IGoJfxk|_N!qmCQtbt}F#Ai=-v2L@{O2@*_l_@qpMINu zmwr$9w{&fJGnO>hmcPb6=HE&GefoFG_zmzk{QE(AD*Xiblk`*IPigC>Vnp#+`ab`D zmi|h~e@T7wetG}AFJVCbmwZAovG^ye4lj(cusIo`?Bz6WviravLiy=ipIeF2)7*GrZ4lD*0H}T8` znYI?^XV;Y1GMcU-EG(}n7nX~Fi^|32(UfyksinmQ*d7cn-kxqx{dxBGG^iL{^rNKP z(=la9TO32qqf0F3!?mU{vBDmMZ*l6G8KX8f9Cq9ZOrT#Y-DcP0Cxi+g!GkujG0?^|_+d8mmX~9HA$$XVI%@&9!W4<=M8p zwLFQut%R2H^lU~s6F9S+1)NpR2F|AK+R78j)kbJ7rNIXKrIW-z6-=0kFA zEQaLo#o}cM>4Wn;T}KW2(KheI_DcJeeprU}D*Dk@cc;z8gnVMYxtN$YfDOKFbJ3h{ zDUYY@(WN%5$7hEYTgns4LyOH^hvr&x4CO6D@}0A(WoNl_)>%#~wd;CU>PxsM4a>Fp z7)H*a`7Y#fw@iE4QSOp;lv99H%BiJ0|8~oU=ar2J`G@7ZVKvg|>#L76OA z;l)wJk4!_b2ppVFDo!c(%uXuyqOKTkMYw&Ap`DQ@o2- z*#~$JSM7oJO80U1-r~MOd!YLYt$9u?PAc}zP9(ensO9WCd19a9orFzAiJi+a*r93T zvJo4gz0!3&dtY%~u`jkncav*Vp>5E{^s3_Y;;7;{@*Z1R_H4vTNV}<12z#e@6nB&J z9fbXh>x+G`bGp9Rggw*slyhBiDmk@IdKuT_DdD(u7kT$Dwh%u)-C5j4{A5bmr?NfT zJKaDD*B3XCwof{~IJP*hcw?a*(Hlv*p*VwY+AljJxrgbDr1kEbxckQ9O@;PF+HW0@ zolZC~yOESP6_*yTDvk!ey|^8CdvOQwj^a+>oxJx_!U4boiqn9nk@w9!bt6y`t=d`B0T5RNG>=6X!gS!fT|S)85@%sLCL zfIEwWvV*g!+z}p(P3_g>+frQ36UP9z6ej>rD9%b(6V3)+SX@NPMcjW4@vDnzl-XHK z2TlWOOLhTwt}f0c_c`e@YV_9PGQ!Qkn~Ph3w-j#!zOA?wcx!PR@HT3C9=2uEiy2&} z7q2ePFU|v=!Szh8=K;?v&MjV_rW8|wQ;S0?Yo|9b4jI*KX9)x@t#vx}LNa2>-50b4b6Ycx~~z;u^vg zz$=O?fmar11J5qb0$$Gjhj?OU@dd(c;6q$5#M0`@bZzm5;`PPnNt<0f$aQwHD8Dit zk}b+F#>W-c_G$g+Gbr$xF{{m7v+a!*HspEi^;Pnf3&!ka;_)O#px34_AX9O z6`!NTCEQ({|Cn;;6hAJWBIU<~*~L$a&vO4Kgr|xh724xn7%oN}it- zKP^7Pbt&a6$(QEZwEcj4*8zXX^=I7uY4Nk-(_Ft_{GhllEhEp;yl2^~>|K7n=m~t9 zyFV+QEie0i>&+&9Sc_2TEn*SP<4!qdf*L5>h{)^(PZ_-=*FkCtR9-#Z$j5epP&#>mQ516n_Q&waCgp5)v?#IWR8^ zU_ovENWGpY{!Gq47JuUU$KuyK`zzp=xIRb9pNfxB_T}j}#TQBY4dK^Cs;tISb||YO zw4jU!;-sN#JoK;`vY%!qWCanU!Fcpn3jKt zf5K_`^!x$RKU}=O_)sxDzrUE1&jwD<=K$Z&^%K(-WHDfwH98Ts6N zCvtAUT6iI;I}_h2H5V<#+`O4EFQ3nymSPvucg6zqeZ-~#cTH`@Y%HJK3hkqJD0VEG zi}i#Zi|vaYxK1jxL!MO3#A10;F$#K=F?AWiOtV|E>$+@)v-?h4$s zcv-O<*OwI+ z#e0drw|F1$;{1|4&)!G>5trX z??+A;K#F@P@C6Fzgdb-32=wnzVoHF*<=JJ>jXb*?`jKbXfZg-#+Tu~*qu_u%`y%rX zbb^NJ@x08wmTPN27HO}#)YGx?p9YUV4PIZr1mCK50$quu=1oYC-VS_c_GW5(BT~G( zvm44A_^SKL`+)Z%IlDW%yX2R>qkISOF7y@eMsx8V!n@H$+>ajTTfoQp-OnzbZvwx; z?|yaxx!dW3?3wx?*N?KF>>gwczs=^9bC6%{!pe3|ITtv$oL9O(=J&|#evcIEcZ8qO zBF|<0;8y#k{;aFqH9tA$iZm!p2mpuiE&I+W2n+RV@$0L6{j^7sKoF^dZ-3ho8Qp}4O z%gc&ojESYiQs5Hi$};9mgIT#VxTCe0pI#0(FGs%*TivNGRb1GC@LvZN2eY0y zgm7@Nxj3vC&B|zWJ_a}@9}66tj{}a&#{BQnp?C?)4UY$-VUI~AFGU1i*;-|r_U(NWqfZsL6IsC4H=Q$U6CckUoJ>J6{_#`vn z{$hJ}8Qfp2!^-{sVr^Or+zw3Vu7md#?mGA&c>V+YJ_L6EFqr!R=*=gf4o?98KpF3* ztVbAsuP>U=GL1tA<-U|rWgoOTXP|jf`*bFHpR>xd%X5L}BE3Hccs5e<3(%qrLT@w> z&G7~005r)Ll>N~wUr_c#SFDEVHRXk9#x5dUh(7Pq@(y%=cc5FmwtNHfs+*ZjHvw;A z&*j_7ThT&X%Y3{Vcs0Au8V#+#!{_24^a3o*nFSd!y?y0C<{r@5@?vKusngQyp?;^w z@x&OO)u&`eOxtbkBemJqSEGA>Gh*(_ZbA>C&ztd;PTdn=h7oti_8>~~`_zZ48}G|c zkGA2p*`3?w(GpBwf%*{Cnk>BP58~Z=Th&f&5ao>njzH(3roF-2-0!QGYyE?(lNZye zk4N|gRGY7riWV?x{Iyi+1=Iq}6EU)Ai@No zwsnn$+BI8t8B%NWE+cg*S9Md?atTmvmGxc>RDb1{ECMbBYDX6yr509St7oZ^l?H4i z8X#L&4V$Of*~asTHKC)M$JeR%$t&H@a8jBo-CcP6ZDh@SL4$UmLyM}})2_cD)qUm7 ze9LT7)Ys{0uq3sWYYX2yixjna`kd}j>8g4HJ!jD~6=xE&_1e%}^#TqeZE&TX(}QNO zN}tsmIFPhKl_ql_dM(?yoiLeRnZ~_N-~cpTwt5Glo%Zb{Wop&-YW(`60kb!z5Y&iG z<)5}2Mb*+;7TMD7gK#&5UPi60d+5!j#gV=X>|HI6^hIDD^cC6{sP_U(*K)Pasb#%i z;MpjBs(a?QG)vHzX!x!6>wQ+QqP|IcR;`v|e8rg3g37)0zTfh-Rn>yY65{k5ZC-tg zHcr+fXB_>rzR5D(7w)|E?S8HAiaOLbxYne$>GkUz8eY3?g_qhl zpv|1`&$wE$-}vHbao1UDZejGaPe-h0mEH?zOIs6r&VJE?t_Q(3_kGUy`knf#x5mzB zM?-w0Uca&X7L6ic>0 ztg9n6My++R?)H;US*m3^`ousncEc~f^|u@`xhGgynl?^hBdsTM&$#mh4^O+(^K9Vq zAyn$h}-GyQ^SZ`;i8jrv;en33@fw!YTc z*3**2zSi1j^p&rVHb+dHBh!zV9wZ!z&Z4jaccl7eTd~oIeMov*j{QgBt#&A1*q?IU zXC#)6z6eb3Tf!5E{&o9<{iHUvF9|KX#!)+ca_dz>Yc4Ik^w**1-F_8z?Ez+XWa!CT ze;p%8A49$R0QKzcUM2S}jpQnQ>I>}4J?F4@9B(n3^$PFXob8S@$DX6EC(wQl+z}%y zMpC2Ey+!MhVeann?s>Y$x0R=Rdc>p0|NitC+uieT>%HCcbbnX({El{O;P{EL6XU;o z`nH~ZVfj&3_wu{PyXW6ldiQsA&)+@$g>`%3d%Hi|{axMT-Sc!W|E2T9yS9GT_LB*wb*85@1kMQ@-K?`y7rE}p{Jq1;Bm&Cr8y1@pk>>q_N;B>xUw&_!qqpd_PFi?k*}971nrGIxblc{ zYVv@-E9O${k#w8}CDY@(_*`1={#voUzG$UtjYd$(p!?R#aT5H66d?Em$CxxzE;jg@ zn9Z(F;(5o0^w_Z@|0Ay{CNg)>WM{S`RZ1PcOdTVBq3s!`6vWvwG50)Q&vllg)ZMn> z*S#;T;C!{0`vC1@=W~pNuCp+l>oNaF^FI7GP`@5Paf541SD1c-7(_hcm+QUCeBRx< z->p}yQSD`GYn|<7y-K;C*cxhiEe*DYQs|Lft)bY*85i|*ba^g<{pG0hoHa*?Sgkp8XH@fW7SO#k9fSoy&o_5&&aCFiT$lT2=qq>uAx5z=_10iEEAN z8S^8#ZU=1UI*QmD;7G2ciLC~X;_3?7y}Mr*Xfha8F5#fh-bNCE%#RXKIfdfHyyK%WzVXzK2k6xLDtKY?p!grM%AOX@({_1o5pruGFW4%g#f zV78cXwv0WSS8Wu0Z{63@+=+~_an&f2x;f(X1L#=`N@>J4p4g+WxdHr>Cc6LCww%Zp z+M<4qJ>*DteW%AiB~Z41tg0vQ<(`b?+g+U~yKx6*gSK#d#>sA;swY)aBG%5`4(9cE zVvb}f^mzWa0iFNOtrpt205)@#zUzlh4|V#kn^28yIWcLRCqdyouwg%C|Iv?*KSzKR zC3@4*X^)soT4PVydZtLB{Z8-sO^z@}h~K0fAXagfD0gXZTec(D5{<=5$XVcu$hqL1 z7$uey{F>#tMvR?ep6%tS8J1U{)M7cdPOVv|rL;jBBtNA`K_#400(~w@3#9}4U9{~d6K|nkl!|s#&)b(hz^Qt8 zoXWdKfawLS8)-s-oW`)il?TC-K86|DRVJl7Ep?@m~jQ4AhUjdsPPk$ipevWyYbGYv&*)Hs{#cx+vF}VTDxRV3}R&(;=Ffq1eSPSc7?^!$fdHd3u+Zs|r_wuPJ@jKni=UPlE<0>L3 znX3aSV#otc>!OH3|9r~vAnlCxgkNcodpe@^kzP0!q!IEe)=m6m`*}}kyc&pDx!A6* zfy8lf{;ae{&55{A8tLrult0&x^$N)^cBLa_5KK@Ab4TTfug* zEnG+0UVdkHDW0{q&X(>fDZbF2v(4=XH6{~)j{2sonX6Pv&$-IoMi5$=ovtD0fbrUa zt|I4vHKqXNOXpNr!r4BJ(L93u;&Lh8D4=7%1q?KueD1rQU5)e>Fq(L2692>mV~9D@ zCsjCDEr+{r#KbfCrZ!*>luK(P=ALp_-$Th0yUgYDY!iFLc9qYFIqgW3|8Pb+kL@*k z!ZGDokruhyR?ZRUPw4x|xvs2MKFA(uG?c-+2CnrAj#POj$GGyq-^)#ghFQ}$0gsTpOqLT%8-oN z!g6cQQE^J(?V2vx10gA>F}W)Sd)_{?^`pl^8xiUDha97AEeC6zmFUZ<+7>bTY)xC% z@*P=X#29~$Lr;;89o2C*?EvPwR89U_$|P4kh7vsU(%z9LQ@8AiQPNxW#p8g|Lh;9F zYA}(f^z1B^)9>&7#8#W!udYXmTMvX9_-cfXGUN)sm&larG- znoN14D~_NQ*hWshs)XipC~@bWTzKrxlP`D9bx^-vK(){Ef5U)!WSPp_+kiPWn@St@ z1u9vY%6~nqNcr92-vVxP-QG$2s{ix^qE2G!KU?^gPTH#{}_B^E2eV;==GJF6FXhsgM-jl7na0 zYl}R0$bB7iju+*?&XnBF}lXV$g)lS<0XMuBGUdI#klsYM&vG(;E+xb%a5OUS# zNOdm6+B;U=v97i>-xxBtSQFV&mKHNM)<~xLw0YxA;ykHpa00Pfj?*h$M~R!n4YrCH zS*l=5IPR5^+Y+{lJdiD6tH?w87F$J{>bq=}I5Dzk)hf#4t(jcBa(e5c>87o1tUufOszT{m) zE>mL=afx0SF_EpH#8Qqy`mgsETMrMrRUf;;^Tb2tjnZswRm33rn;%bG z;vKeX-wDL@wlBw^#RwWZ=A>&mag7+n)wJg$wo-z7bo=sr8{em_T)fuCGlPM8mY+na z%Fq4wNtB}RCFLf1XL3ic5^rVV`krys-p+f)Ea9_5PG<_C31~k~AvOYNU8fKxF^`?+ zQ+b!zq?xNTyB#>0f6m|plp_~AIN!xRojfg05&wt_#18hUSVQa}W}C+M_XmnCr}4$& z0e2@)I{(EZL2;x@!K=TJ-bi0U z?&TMl%bDzx@(fZgr6gMMI08+tIU+}?@+jwrV>{&OK|h1L785x$LMG;X@t^ra7Ex2+ zm!jc*cgzRzNl^2cy8-PLSAILQE5s8BcdaC(p7*#Ddu=>#a5=J3C5r3Wk+K`9o7h?7 z*@G)cQA)WZyIFQ8RY~t6pidJH#P|2tg;x)8* zoMz)WH}cE7)4!fz(@yB9M#1j%-|oE6b@uK^23GR+`INE}sQ0e`S))&joR{=dy#dB4*aH_z@YEEn<&&%oI zGsw}0(3f%C%)OIH=>zoKD$iSaHM^F?C7!X;hkZ=qn3MU}n_W>S6Zb5YUhK(nRk0Ug zBQxPJQb!Sbv5V+1Vy|Epw*p(qF_N@V>@7N+*uJEDDvzrg&xza@=$dE0YQ~Qs*GTpv z9Z})0BP;xMB(wbhaL8!jXz~r?{&03JiM@^@K8)QjW4PzZkz?4)4?dlldd?mv~b>v z@47T}au{OjSeeFo$gWO9pAz&mD73RODD8{M$p8MC9V5#c#;=U=aBD?g0A=40# zDZ@~15V$V*mXIx3SGfjPB-TZ28Ef#Muw6PzIikR6YAer zQrtL$T^g)xA#~x^NUG?n#hF{L`<-EOQsGHS4#@H4w<{lV^dzgysq-4Xp5t-nW{W`Af+;4d_f-$nyh$3%H7b^x37%VG*h0fq3Qz zi#nge7IO))r4-YlOTmW)zuCn}#>fk*^Uve2gO7YZXB|9s z@Xn6Pu=}X_YxyHrZSq;tMy;eAA8{VJ-w`9-Rb@SIOmTF?D0T)oYRwyz+_~i1+Bdt( zaI`r_gFlofjI&&Y!x=B0J8rEV72*+VD0iX^a~!?o+RhVx)ZY%RdQAMHeXDj4)>amCZLj4M?-Jm7_Q2% zw7YHLy-M|m0*CT%4yi*JAFlA`@kU3ejkI}`+hF`VX6BQw&F>sam`@Ex1E+Ca zz`gcr7EA`VlYaqu)D5@-T}b`a>Zr3p|{dv!EF`m2X@`Y$i~<5;e<1 zfpfXDh}3yNkCv|66dReAk%p!|qh1GyCGg0p4-a3E<~Ham|zYr<2v3!wf)m(fmR zfb&Vyf93#SLE186C71VnM@#XwmK`rJ1<@r6eVgekGv&|EA=K|G1t|YbyxQLwUBYFeXwJVF0XI2_p z%Rg$GXBm!WX`V7SF|U2Bmarf zN6Y8>{+P`*Zy)%}*>2wYe&h^F8Fe;AeW&_WPvsf~6jRsQ2Q?b5&c*_rzn+(-j#G-_ zy2{Z$nYh@s%UVg^QJF>G|CrOxT+dE(W!J*j_6JG{w0CM{W;kPK)8^X2OV6B#&Pivx zczihH(6#g|g7z0;95K6g@N$VW39}d%QZMnlcJRGPok3rCo^_mNE%)H;9n5G{wlbAg z9tiYou?3_K0(u&?X9BxQ)3a6Z!mfa((U!KA^geX^auK$7qtU%xYnh+VNP~k%l2+Ic zjrj(D-Ja#F|I zKPq*N_tvASu0z)-vOeAEVE1@vmaU0%L%EDKafXD%%5Sh`oXfUR@OQS5GbA+IN@?Ze zkSsQ8u1EUPi!rO@No%-Tm+nZi=jBix(@LT20Y{bcG3S5CpR|xtBA^sX3#ph<%AK{2 z3OlK=u?S6pvU@pCbwTpmYI~F$*ODUl%-CCD=OLY}bx_J~Ufi0(b_r{bZP|H*ZHFyW zTYEGb)->AKSXV!Ujog2aeY%`ce5;lRf6ur6ZJU-C`_}IB>%a5+{JOjvZ^q<_oM~cr zF}nTfypxv?9if<94qwdfd{a&*UmtQ1*A8mu9KV()7cNecA9qeD`H=Gr8Jsi2^|*7y z)sAJxI^5ae`|7b8n8h&=*nvVRKibR@(lu9Olyupcbd4HUNp&l4ZHHqC@uugOb6CRbQa;RwXV%>9*(Fj|IA0U_EKWk&=SG0E?r{xv6oj*#Q6JXy{n5}*7z^RZTEM*unzWLJ-(wpQTs@f_Q)l=;&&E> z>_UnfvIFP6oK%;6gEKayq_&_KJnRc%4P_bT?OvyNzjJ15IvIJQeqA-Jzaa8=FK6p| zcg;;HtMtG7UL?Ojy`Ws@-)mFY9sjDARw|&jU3rssd+O1>4&(cx*Mn!NWh!z=wx6TK z)^lxF+l~drm-5RQiT7+%b4Odcx_mKvvalo*r-rUd8)_|)rNiojm3zeQPvu>;Wwg}P zvy28a@1@>a;i!|;>cUfJ#S?v)2U^*&JWkra2V_93P&P?@`PQ=LO^ptH7xS?cW6 zf~TF(gL$a!&lE~fZ>Z(dRC4zLs`pfD*c<5HB=v@qn1h4JEnn(P)%t8E`I?#a?UXi) zlG~Z>TA0lt=QOaMddGRhT}#T%E&z&8UF|NQ{(XRQ@C*2_cTu&M3wdS|P;0h@{GSO_ z|FDqqI)PfPE#%&0pq9vscykZnY~H(wSWlq4O&9TPLx3Gzm3mJDs;P7hslA#qr^S5v zXrQ}R7ZY<`DwcAEHwRp<6nzQrSpbyFUP8L7)j?ccvo?V4-Ce@H89-OTODep)q{3y| zx{V-3T(^|IXaUY8&r)*g4P6<}QvNRjDy0nBU+5aP<~g0~$~7F5j%?>l=rZIpgHx?F z`k~jTXQfg|shoOJwS($VJd*i2zzLM!zZz|hJJ(e1 zRqI2KjiEN~PxFoLV^fZ!9#FZCys7#@HL1#d)Emmts##Q%DDNvDtcFoc<$Q9r`lVT!ucM15M3{erPcSjN(jDGJ|?VJVm%So7PeaKbc_{9V4bj}^-bOv zAKCWu@PFGfCTw4Pr)za*x^=M?yR2lo>@9{>{SchE{bB3X);so*wpHq;QIDr8q}>F>Bg^?L48pY7$U-?ha}t z!Opop1mys&#Kat8KX-TcBiJ^sd))=(sz=F^yMtU+xa&b%3Z(+>6q5SeAI@+0N&0nS zChahkzG<1EM%1ONre!s0? zdqhjwZt?)~{4o#em5$?H>L87XzE@9P&l2ZE%oX`p$6Oa}dp<3zY4qQdXX|I{Cqg6X zh_$s{nbo=w@p0%s{(bRj_LYn1liZ{6X%CB_gtPIR`am+qf41Rsx zBKC3jc=vV-9g;02=G)dxb?jLq$6c2^?WJdGP<_`cT75fGoQ;kgYZdYjfOewF`rVGHKHm@{$MEoW8~G+9_K?? zu7t!Tc2SCxr1oN8$52Qx#BsrQIj3V6N9_I%+ds#hQW^27t%whdM$H?!2JFr~Iseqc z$_+(7*>mC}>lgF3mIj#?^Vag5waOe~eHtrq>u!l5TXJ0*>q);-op0y>T)8Leq+CP_ zrxq)$Y`dhB;?B@S1t)3$g`COW^Q+Vkh;0M6%KO%H+0nOkJY-t-rr%;M<)D45axd%b zIyN|4HO+qae~&z)`%JMu)^Y1KfxRi!uuh>R3cP5(dX|NyUVMq)?tk05`^>9zN87kN z-975kdpQF6Qn`SBj5qDUrS;-gcYVsYy6@e$yKYsxC-s+yb-Qst#x%kG}T#q-uydGoL&hZoD*>81TC>e27I`;fh zu|hrGo)WxJtyMd)_JyW*XWV0^LKx*eH5cEctXcvZTaFXl-|YY z7C$-4?afA`dp)|>H^yyzN%!}3&-3@xcU#YPPw)ON>!_Sa93WN*TR=I#kUm=X_%h#a zZ5)e^ZbxQUo7FMzcCTmm__n@f>pXQyThIM%C(Z9tK|Y~8$4;88dz5&p3Li7LQJg|Py8~Lf8#2O zSnsLoN7}?{?yHw=hF{fsNK4!tE>~I8RPw7SlzL99R*%yw&R6}vR{H(mQ)g2C7@)Xf zCNXt0aXwzrc8c?UfuNV=A4%cQ%fyA4Nq^b z`CXlfabj1DyXxIbZx6adwggJKm9BtS31X54uo);9&?14{qJBWj8#RkK`wJnD?KMfD6kF^i`8FZ{GY$M+%|LOBm87aSQ_EJ`HA;ER!E?u!! z&-Yj%wXuEw8NMp~s^@#G_(yzIXnhp*bY3av^>lkB!g>YN(}=6Wfy8Wor6HbKFMZTs zl$1y+8J?o#u$9A&<0{9klx{p%x$NG=CUBL@?nTTw)U%pH`mX3ftijb;hIIh52Av=M z5Wf9#{@W``gc7g~*jn{X8*Q0Yb4A`?nIdzr5&T5-d-QDg-nUfiX^GvfwHgiA3@^4< z-gz{Fnu{@9Gq}4?FI(Mr03tsnC1$^})@I_)b?q_4Gq$ciB-?p!RzYVso|>80Vwp)m zXTAINY8&~Yn(11&PoY%`=DM=A8MKzVDsj*Z+EB}8G0}9|wI}gTuG47mUc}~eb zr07FKYQ6!uU1g8H9Jq}CJCkD>P;VW(psCyesQ->#NL!DFau-t80k@~sVpcmQVs$Fd z9~`T5yp~=%(}O}gE?vQz%O~6+Q`<1Qj;(DQeL{RD9 zbFduek6iDz?HvBL?%&Z|TR4OsN__7({v-Y@q~gvE=X%JeU+AIFmT}LVD_+|w{PZc? zsdv5jerICrnYMn;QYmT3)s<$2SPFZa*sdo}C>#Qb_{ z^@QZfRnL0PYY*bi0cFZcn;rMDk6am+GAn1}NMc$*I)dF=h`sJ6WVsQ zyd-)n*42&-d)0MJj2KrlVbNp1*kZLr(0svn+2*m%30NnjwDG+mI_N{g6l{$5zj~ zQ%P?|jua*KQVUyDUn1&(CeUUrJnf$7R<3Fa+zYAQ@nlLHL(h12U4vTAvr5W9X^KT7jxv(B`!TsMJcFY`QzX)lRCTR9C5e zh;Mwc0r94Ga&r15g&_YBFqbIpLuJx4B1eChy`C@W~ zchwc@O=Af`zZm+zP}?{gsCN-xBVMbKc9FPoNf#eP@>QD|9nqrzCZg!&8r>Hw$Hg z^7hU=`A#M0%KNltv(DXZi?lWJ8{(_vAN^V}r4+_*S4!auqYK+5Qp49o*bBIOTg%lK z_cb9;79J;pCdiXneptsUEtir=Pn0vOdDmu7jPQStuL-~3m6W>JZTXszMuo=-wIb@B zyL*{X3-`BtO{fj&?s1~g_&@Dy!ZGh2M)v@SMfKyO-GvlVt$9#KvE?wZnY%@$H|jSh z0>yBS{}yUJ94KEeH5vqz`ZY6BoLf>1zhp2eA)EF*_&6_qDtJN9KXQtCu8YPi`3ui=cFq9rIW)b9V#ezzDq|DARN37Jyd8(e=`J``xu=!J)5*(E_tgasQEHo2L zr*|Otg^Nkuuh~hN?g(w;zcw3fS)&oWizC10teh3n%+S2}?$F4Kdtye_7QSMl7xSgy z+;uO3V=DYDxV}itWoKV)Eg`*BVyT=l=xS=}E&SE>T0iGV$ho)OQetNHi+*{u z&i_1r6SiTE&+U)c#SolN?2fh7)%V0#`yKJ^!Q<4jIkjs4ReuxqnQIK`oBd^Nl#|8G z5EH+czX|0NHQy{f{LlNFaL-wnzlnm`9$b`IN>4P(hr-i@)KST@{w6&4!2RBy1t349 zg>S;o|46Qb`%hYRy ze3RZKrf{vjPJ{;vPa>E~yLI`PNYqjv6MA2D@4EZPwGy-5U7jY4clR#Q%oo+(D8d89 zB)-U<3<;QczRS~uUMJ)&-AnGC@$fg{T-4u$yTzT6U7jZNJs}RPeNt%MC6%{q@lDK6 zwGE-WSJn_ZCV6dft>ZE*NafMxrX4kM-~YV*aQ|F?6M?g=cW9l(Dy~hGtc6C}+2|@J zTkk*9bypih`hsi`oJ}roJH(wa_^a(ad@3@RO@GERE0tGN;QsWTX@1V;ZrqR#l5wU z31tRt{CBmij~jPH>1iT-Oz2}$uM>K-avx*hi`w6WeslCU5xW~lGvi!OI}6pexpvpn z#6+N4qVPje%hI$y4Sb>32{FiI-q2Z%rcTCHm%oXr{Oj&@LX6O;FhZBtiSRVh!k5a8 zxTjLTmD9-QzC9&&Tl<>`?-FtxweN{e+GaZc^*0e7DE?>qn>eZRCvYO30#3%?z{&U- zIHB?zZ~`fMEI6G1O_d*j;XwPK37-JN{$szt`~OG&hd%*528<&A7NC9x95Y*JHFxZ{ z5Qed*U%vKu`eh7oG64j z$T*1Wv7{YGe;-6@Yj!Z#Rzi3hJr*AV6UZ@z^j6@$T=g`53{d|J1Bkr}YE1#onn`;y`Rayq>SEnDV{{6_ke`rf{tiiAP#e7ptLJI(Mg|`Z@!dm-GAK|M94g)he02ucyh5p z{a#w`9P0$_ilnx|>q>9^mRNzv^#-pST(7HzurUl7;@18lq-^T{TyTQ)?Y3#&Kn3n7$qrk!{P&NuB7JLUFkQi3F!J+p9^|p&;yh_qjC!6 z7Op~LWV?=29ul6U)Jxh=+F98*)>chww1Lu;m(tF~+DZQ0m0Ps1Jc(cVkNB(z$*ga* z_5A{S!q$&9m;3%*YdEgDG?k%8kXv%iYwsvaay{q{@}<;9y@vB;9dlGYh_iJCP~FNx z=H)7&Gj$=eL!FAVWFfiN0+;jr!b#$0w~?=08eVlnYrE3|~T zvd7RAxi>=H(JX@dgcop~&6o86Dq(m2^{VDy53q`@DvnVvCC}je*5|-n(xryOfWt`Z z+mPo_<1X$UTX7X*!S)@* z?oNvjxjBr`Z8Y}@$Tdq1{7~8Vb_zi-o}L$&I4L)u1ayCj zG_MV)_p+sost%xh=u%=@E=}Zp+9T<0+8z8_D``8V?0+Ty^v=APx2zgw)}jFue;4WO8E1LbTF6x(m0EcMAfsNV+0N;A+sup7v+1h|x*+5q>m z0NBi(4g4PuT)@*Cct-v64!lJUM=iAYerM|37pN|JXL9ZYTu-i@$*0y@{;bgm9wYb) zaYuL^tvzi>xut;NW8*)!m!i9m4R;K|oPS!=hd+--qdR@ic|uw*6}Mj2 zQyMIWk$+H|;>?$lX@g@;!9wzM=Lz+IE5+~DM>LI1AlZmM_ zRK^~jIl=?SB-+lkt@LXWJv0EQ4BGXtcud?olR2Z!h4TIxz?sb4PU=v5j*^PWUu(xW zk{q_)q^jp?z4_d#FSXy)$Bq^y>KOIdqsRT1-megSYd_1UMc->j<%n=JI3~8^n!D zHMP}V920F_$CtuH+pc5uV%^WyM11YY?Op>%kt12o-jNbBMIQd8>=D%|+1HMS?%ww6 z?~PGVf43Mfc*@X8i-WC+Zw?)seQjHajeW26aeZMQZOeB?SKEhGi8JA!>qo;{*S0)$ zpF6X(m<_&6oZ0{n%?9efOAJ0GYv%tfpjt-x`LKCcpVwJoc>UdLA+PPam{A|l%IuZ9 ztNGL4nf@HqAn37kJaKu68PIBZ4?RT)=kmR4suo*A+w~-Fo37!G^6E9Tp1vkrova4t zKAE@=m z5K^Rm+QK_>E3kv1icCFAZ@*9v2M-rR*< zx1KL`dKc~soalUV1tGo-Y9IPBsY|UT2+e_((f2% zlRoo*st)d%ba$jUTCTR9QLcPqZ?yAQzi2VX{8sl}iXEi~?%9+gx-U#FFla;U&Grlw zy;y4>?5;5}kP;F5f9r3oTO#med~wjS$fq=!fy7z+e)z5~O#I6J zSzuwmQVJ&yls1|gG}M1vTN?W2*oWi0EYDF}<0hq0p+A>0E3>g)wdIboCwHhjN7as7 z5Ak1M|DXoi7+4Q+j&Jb0rv? z38TQdp4Ss+V@@Hi7f`)&XlJZORhzBpU^2a#dS=%Qp4En92+z+V{}gb&I5bWL^c44b z74}!cq`%Sm^7QC4)+exLc&dJqdkyk+Rm!97{hN>?M=0V_ERe;Z?nyK6;^ z7T!3tUQ-4rx9l2Tdr0$kc zwDJvl7Ey}WM!oelqSuj0#FZt6HxfrmJKxz8D1LXfFRqizSI^hZC>9f_)4-~@Ax2g+ z5!l(*l+Oy?oY+{3@AWZKsCXq5Wup+Qd?QG@WX zAwMF2VEw}Hi&CWU_h75~4dEw78IZmdq_s+gLbp{@n&3)8auoaaw50KDBPo}3%x`se z`LsP8x}rFpB(z7ii+$qUk>1A&$=bi+cn1lu7vUWwytjvUknrm6=$4oGd;Nm=1&%w%kuxOPto9Ngt=iqs$BX&R{m;qt zY=^D=qtskm%&nULdp-|Wr#p7K;@#VG>-74c98{gZfI7^DGKr71^m1gk5ymiA1`?Cz zx>|Frw-DUrAm#{*(prC`73oCUIrc&-tsBaJN5A&)O1zZ2&!xxWJfzrBrG=L?PN;q+ z_FeQR|2*15`r&>Id8(1bGlCwW)Bw0!BX~b0Dthkf18wa9c5pA}zw)xgwKwV7C#fCq zn`ba1rjXhT>N$mRq-9r0a95QSwI@O9pe#ssxS7Ow7@?oVo?AugBO zbi4!?AG>LS?{wVAkHxrAI_ruke8{VrjJ^|_T9=UQ=t0F19=mL64=iz3y*^fASBth5 z!)PVt>|zPe!3*9$tgZrwG#b9a+2*~7IjUj|)UkRlMqcM+*I0>X>T-OCrI{MBx}=b{ z`Bv}971z(iyQQ^$l~gw{ovRFa412>~bC!l2TD%f7P>D*MM=z!o$2sr)UbWEj4DxjL zi>GC~t3+(-oz zozTIkaI`sU+@aT0jW@kZ&LI3h?45~!UR9a+Z}uilm$YfqrcL^$X_~I-zBeu13$&$_ zr7V^mkxe#-MNwo?L0MD~5l|LEKyg7(bVfzdnQ@(Q+{V!v$C zb!hUr&pr3t``&w&=RDha&U4(mdI_am%;D%!rx#lsXWBm;ZLX|W_H~tjnla^Ss$FyP@+1SmahOxzjo1*Z9vD>ZtC8Sr-jny zDb#8vz7x(~oeJCw+{gJe>fQ;IL!L&^zU!S#j z_h`wugkv>O8TC@0xe(~w)}={;zm#X!kiL-fyLtW+e2z}wx0i8TjDM1n{(Jc4di;%? zox7al1iXtjBRyZiu>p^ttH`;MV}%@J>+~W z`#A6(;Dww&PRm{dyojq$kiHvu8RvWHflGkBwD`TGdb9gz)ysezINwj+d$I@UffIly z(CQClpXBOOoUh70O`BhlJxJ=^yzzn@8$Xtdhwd6NIePs0_Uf=eiHaT&QH;E@5`Ph_a@*? z^ywGr&l`a^a_^b!S+1TT_Z;9CIX^?{S>Ok_`V#P2;6Bb@q8Il8pXK}<&zuc>mh*F@ z?gZY+)${cBS-`VW`dRW`09$Sa-U?p4z;RplWzNFez>BYN{&4mpzj_{cCwTE9l=^ny z^IUzE`yU40PTp5Z-JX4oJ9hx9IDd`QUD?-3e+~Gxl)ejm`UW`pL0}K(m!N)&fQ!JY zm!OmLvTri#CuJ{#LkF@~fG-2@;ruP|=3?N*VA8iZ?g8Gzy>Ejtp8(#+`BgCL-t0S^ z@6Emo7TpKDk9&Vl-o4pBaNH04`;`6;=kI}G>wx!j{vLPk&%O`V`~c`$;qQY>4*~U~ z`99ZMfIr~Q_qqOb_8Qn!0hFV>25*^?{g9m3fa)thBsDer5fq^jcs1uAarcM7X-r*-~JT%1m|CH?+M_~ zIsby(pJ%^>9?b>L<;h=iJPv%E@BfPNa5L~J&c6b)p8`4(ensxnz^A$T7oPnI@F!r; zzkow$0>8oeUr7Bj`&Tfn68Hi*`>z~d0akMLYx4gU_!V&U*QCCZ{Tn&I2L76yf8(gi zegigs1NcpF?>D^v$G~rJ{teeXz#r49zXgjw0<7ZvTPWi~;72(Bj`Kp`OPqfP4!;C+ z9l-B6=4Zd>*LMRa^6uYr{069($REJ$1Hh$R|AEv};O}|z-^u?2@DC~d3RnLQroRHb zoAV#xS?>m(2M_!soNy)Ze9nI)_toq_7zuX+zs>nS!2NG$e_|AT7x-zY<)65BHSlUM z_)i?427Z_4{={)N@Cu&&GjI70@H>o#KXZI9`%jK_z(1$-CprHYSL=YE~$JXqxoVNk>2l*>wa|iG>^8U*8&g_3k{}rg8-2af;k^L_t z^fllQ7}5XB(E{AgSpHv9lYy`C-2Za@1K|H~$GIx)%gWnYvX!&NE@g5hS*=&D&QLB5 zTei}pc5Uso{iXeF5_PnEQ6{e|DVsJu-(gL)fN8<^ z32Un~9$Hk`&(&nKNn0uR5d#Z>wBCvc=R;v}uGbMv1y?=da;6 z-V=XpOP}{i`zyzjNL6viyJbx)zaQ)O!s1h#ey_$7^JKAZPdjS(^J=Sf9>e|+Hv@mP z-h|aLyoj8eQv1|4qDJVP@njCY0>m`sCs*RDd%AW^>zli-M~pLlXtcG7QF>YFo2dq` zuT=*ybfVCR)CIcvhSo5#Y7R#&P;4>wfxa@9bq=}4OfZs+Yx46bM#eC5-oPF()_yzC znPAsaxS}HbM2+RGwl18{Gy1FPt)^bp18p_>ne)S;PdT69Y^YXlSF}4{5PML@+Iaor z*Ko(x@@iUYS?X451n#+{9p0E5rwr zrR3?2e;V+#l&<3HOj1jM?ry)IepmriBh}CUbfA&w_LJHNR8Ll`YzMC3YCq4dLB?H! zh?7q36BgS7t27lAibz|ASWj`Kyd%M#$ZeDfl5X9Le9?;@T%6S$f?7lB>X zK&@#P@$_n>=bfZ3;jL?cd+7a3c>je!J!RcnvkR!cb_q}HK~vtz)ukMlAYtqz<({Bw z%}U6Z@%s~jmvFv}>vsdy>5RMJ{#Fs2K|1WbjvforVONStZS(bG+V_Hz7&p;bnx;fe z%9>` zq^8;kwc<&KwA9G!<^pq@U-+cQYO$a>t_pLVsH;8~kkVdQ0d?*H>KUk=Njh38X=#fY ze)&@D=xk&GX9e^vl-kLs)Eu-+oka^w0t3$iPERelpPaM6QRhd*SS_GhIJKbb6QI5D zOpYdC6ZkJ)w=ja7c{n58(}vRt9!s~y@D^YTSEuvL8MK!cNp1e48H3uhPvg*%6P7J0 z`T>4911Jq}M7R#hr>_8Bi3B*Blo3z5fKq*D7L-#)b5E``nz7Ttz4Q2e2k-#r_i*QO zG|BVGzl`*I&>8O}J%@A5vWQVN+|x&T9vbEy+`E*VcPD)_>}t^y!9C@$&UN%~UrU=> zY!9iqKy6Dsq@-3gyhVN_9~R@Q5?-tS_CQIh$l1qn5me@bXvK>-dKf4B$hnoAMd;hN z0*#Qem~pa?dwbHz-$UvGsL(CwD=RoY02lE&*GrgoK6@ppMNmp<<6e$E&@cBil%DQ^ z_uRs>%h7voVGQ1!c#(FW-O!b*fO|Nv#x`&h@Ft$vLGIPStFcP#;J603n>;;?cSDu5 zG4yiW2)vQs$X#|pXRbpp+`w@I@CKgRz@aDfHE569Ij&2b>l)y7+|zeiUnRYo-J{SM zc6p=R&{bY~GzX8=Q+p#6Z3Fa7o1=c)o1k{;(b^*Q-_~b*D_HAziFqPNyCd5%ArDdp zc2$6sA!f&7Zp@KwY$!*RBU?GfG3ChCzd@PNksV%)`5q2>I_7&j=m)7~Ja&GFogf^q zVvf7UEB`88`IeXq_F3g8zb74bUfXhrKg!#dPg>yWsXP|5BS{;-BTI=)X+D?Bl!2Ab zBFcsJ_Iu70+X{ZonPOYPuj%_~EBLjL=Z*NU{Os41qW!f}ddvtYZCiGqSCUshQF>RN zcMj2Y?NW;Qd}};#e4=sM$sJ)$j1H;N0uJrg%8QO3N&=S`uxTOxr}X+%9sJ6s2g=Aa|~pKNyopd%7#Y+}Wd@ za~tK?OIx~PtU&3JYh#tTrEXFjqi#x}j0UJaBjr;1F3}PlTvr2~Ymf#>CrVkV)K}&% z>tz1EinrT-#dOH)>UlW@@l8IZW>?M^qtp}4ujD(P?WLHvjeb)ajwzd=&90)F{Mj@wpld(1S`0x3Bbj)2m6!V4pjquMVO% zs-C8PW*u6A>T|6?y`;-~fOI6Rok8oXCyKWn)Tx6jwVd$V4L<;(_d?6{9NuChF^Yp? z=*Jxxq&{og+J=sHeWb+&sem3`_OjGLziLOgR3l>I>Z`H(cB#DIGm^h$vK(3o zLT`<-S`SNak6SIOTU({dQzU^eYXa{h%+4eG`znZN*WUQ|Y==jpFMZOi* zAWN>lgTJukzGVzY#G10t^mR}N(;HhoUH^vgTi0%+uTj{4oX>PEW`Cb!!#?nrgqS{h?mkAh1}Rg4x_2Q)Uft2OnKTg7<|&(#3krOI-vX-S9GkHvmH zhm8d4T(&z4uH~sUl(CwWGnI`<02yi9WF2K%Mvilsv6rGNR@I%yk~aoPNou^9!}<2b z3A(OzQIZ_oiOX@Wgyg*HVxUx7U0#nmedfk;`9ZACuwT_#iZp&G=_0=?ri;JrpD)+4RQh#=zku>alp*Y0Ij`*d+qm-G zjvwo5PTyz5*|3Th^NZ>JWfS9~?eg!2zfkBgTIDRSegbkhOKw@^8GbF=-mjKQ#qSi; z{@z;44YlirToqAyl&kd6jkn34?JJ*m1Q#i>{Koz|{B;@m8ggYeDO^wrxs~)ooba7u zN30XiDUWMTavQF6$d)=Bo*r^dv~S-wwti)qDB8-{#Ok%PIh61mIj*ZyhHK`^QKDQp zn{#Ixi?PPeaTJ+A;wDnAz>am-Mock6x_fDdN3wQFcbry&jc85wqjp;9 zw)-|IyUyc0pONH#)K%QECerf27Oe_O?qj%X>?hZnl*p0NssFp%w!X!&-e3-`uOE@# zLV5_*1C6XKW~ui}XBPo`xORVro;NTfFs_JGwyLsVS^m&DBD^Y*dwCg$)UXtFXphXJId7sZBu!_JtZY@hQw5~ zkNx7?%K6S5*(@oYx_uJ07)F{sg4M0uQ_4ay{ z>G|on*DmD9jM)?=E2F+T%QBv{l9!y(nG|P{eD{&HSzcDDoGl|C6Z32tsjn?)i&$4% zP%0wsMXk%YeWY!s)zDgqdDg`h4C0Kn)tf*(u@#gYqjeg&j`j)-KHAZ~4o)2HEH2pk zmORF$qdPc(eJD1@*oj`V^`f60#g4R)#l+C)XWu11iJIHPVunxoexDOdoHGhcQttGw zSK`Kze9xAT89dA5H+`e!^qYPU?YQLG@7Po31~!DO8}n7(krVn{`Mz}?{0s5!BArqm z>&leel;4!(l)GjFjn$=msO+cYr$nYDL77X*OQ}nlOUY{vrBD-a4?*QFmn|C*}pTqI+X&7?J!unNb6&ygp6~zvWQeHMwz%57A>(jc!8r- z`N4JyP7&iED4}iQNC>GTr!Rre(!Mg57pYmPy~l3{g^*)e z26>hmj<_Y|autOm(K;yo#2b8@GTz|wPw+nFpcs3;M=BKKX1H>cQhBUuu&mB|TVv}W z@3rif%oepy);ZcaXo0*ps7SHzm65b`DLXkPj7%e)R;JRMRJ@(dVbr?`q>ON)ykuM( zqn#^RHIeVg5lcJXz|n3-koFB@(RYK@#^6(H67!8pFV;G4j1@c`=zcIWNEz*5Zo*?{ z2#tg@pR0M)RcT84>3C=aNlkSkot&GgJZ~Gl5Jp! z`mbLO&AV(#4!cc6)$|#A#Ptg5$o7a92gj`ZTmOEo50*lYf2|Of$M|VlA?z)^C$vIH zMZ{XEPDHG7wT0^nqUW_qD65GVN}%F}-?SD=FMijuC>!}r%c6&u-?SZE_2D-yi|gwA zre)FE={GHlQL&7dB@MGQmLTYzxaT@NeI+W<+^zY_^!=6T%PUej+}BGF^p%`frBbX) z-*^45bKcr$L(A_>wdkZKO5_uGdKvdxlg95H)iTnvQv1*1$=v6M@+20Biay2Lm+Ro^m|Wi7GvSTDP}oK`kUwDV{{B>Y_tIz zan(7Th>jsHYRPoeh=1ab^FP|7)i=Z*aZ9a3>~Vx?$#hgY^0Z_+S{;#EG9AT^R4ti~ zAxCiR-|381lrh#mg=N!c9fMjjeTTo%lIgpBmy)R8^czZ|mc?&74xGc1I_ZI9*)6M< zOzUJlv}9UW>!!3~8#t1*WZE{ig_ca)%r?@J>DoA{wrv@-$yG{0p)7;6$$A8ZRJW5h z_Kz)TT`YsN$+}nuX;V-|siU+p*1!);o7_h&%3)ny#blrQn@XVN^<7GL*28a91FfIm z4ti`9Byl^+Vp)TJE0yUR7iE|F2Bi-#sNe&xnC{`%Mxm3pF5+p|-8OM8ZD#`cjpVk|6R|SLIS!@T8T3kfqI|J`mNcoJTz83zU9?Kj%xg*!@D9SBjlGMceT3>Pt zLEmTW&;GWGzR#3tQvODNQGDh|?Rsxl*^A$Or*3oik+OA+BTG=M zdof-9mTy#kjJaUHs663&tVMX5T2|}pvyqdJPoq9aOFH?wG{>3LnVe^ltLCo!QQ|Q2 zcL!HeEUB8&yOkTeXj^3~=V$dAkWxtnjeFKkt}D3piI_#6RBIM=&bd4FpKfTedj;qx z78We^A9JOzvw`YN?&0N{M|c0x-^vw_dJd~)$xXB&$SvD|a?sfA)7Eg_)Ez&SHewyM zoYPrBIjOA~w9azbpZ2jW5L#x?t>R2WvHgqb!TPJ1Urakbf-(oq&HHjVdcGD3b$t1; zRttHfo+?U`!84UT!mHc;Si<5Vj}=P~MTA zcOA}{vpn`j^o{M{sMR9oov?}xX5sTmxOFM$SE&@^-d_&QMiVp1(Ob^^I}@aZVL0{a zEB`oF7I3rx9ZAYR#vLrnPD)7nTRZZ?cBbYurH@P%aT1k?jGe2*)WtC#sJ_=lY7yg5 z|L!GRxet(X(`*i7cPTfyr-#v8yLh6TyV3w9sCMqQL2uMDJ2~7{$o1gH4U@XK`;ath zX`(&My^=Ee!%WWZR1_3y4lN!tJ6hEp$x?9p&#@hPnd43x;Fy;?Ip)Ha7u4-G{rI6T)v=MRrIWnjmoUKU{^h)95G3WSn97oIvA|{u@I%2uPYGMQitteV9V$RSv#2lhyH*ABJ&M$_|Ew|PX z$*1HUYZKN#Z9LKm-zhb;tbR+2x4*Y7ZQD|5F0hhbu`TCvxF$eaIfp|JT-#TDUjH8{ zlU~EF;jbW1?cc~7b2uA8Q$OBrQh7W8=jbE4rrbo{(*<-d3U^~QT0p)-mi|b32^(>< zi|6bcIh6J>BN^zg<{lD8E-<=*u?^gb!X0H=Nx4U}GblzdGPk|y8oP-6e8^FMLoPo^NZ;s?M!N#KatgTm^9tjyr=}9Rn>>binJt4J0=^dzb-4Sl=jq_nc^%RL74jJe0{D%UM z?2q`ay?rFJWx*Sis6&Sc`7GxeT1mx(z+}BO#Om;}w6?ZYc+A>nwuN$>(ods9 z5vp8?+SiBkNbt{E%FCT^))s1ysckxoV-Jff+D9EvM(T3@MoXu5OlN?c>(M@{Rdg}u z7E+VJ9c!)iGc23VAt@0~LFQcyboNB+ZSYj(8KdY<Qf%#eKPQD|gkk=X2JB z%JE>-L&v}vr1=GDv@8T_51kHl4Cv7$6vK_!pzJN4E1$=HeeQ4U{tE8e<(eTSBIonn z&p_FGcEV)mDV5KhofNOicv7T2MO{ewKs=9et{>B(=dO$IDcYFALL)vYq1xjir;67~ z^U_r{xqmqJzhma~OiHk?!izsc+M@pIUJ6B}OI#R4jjFgbFq`kh& zH^z98ri5N}cr?Ya8hsWTMD*q1)0ASr6#KYu-&p6c!NmHr*_2sLp^F--GpISt<~)n* zE-*W2yn2MIQCxkZ^yflH0qKKU{9-7JtDl=Wf@3YFl;Qtl&-ZQ5f$^{S%uv#U;c+p)n2zz~ zn;nPcG8EIcoj4scB=&_CtFp!-wu|fbmgCX>7W3s0QsLmCfgf)s=Y%E|&qk?ArD!Q_ z0&$mBM5SW+is`}Hs7OBsdSCH(L0_aE*35e677FP}UQ7E??9*l}w%c}6AGw=t*GW=Rr}Wj^*C5wlM;V?Nm$` z%h5mWllHIgI5ZuMQd)I{w-n62#Oe1j-bHef_1mGq;vYxs)jL$x0~t zEXu_kEn1o#+acj7uf%*o?9k%aSI&_VS(4*xdXKN^bsfmtx2Cr^j*98N_#bjcK0e+| zCMdo~ERRuH{ljShG@mo>LkcW!D4H-ongf)}@DQ!huR_kHCi?l^O$6ADL@_(l; z#WpFn+fdSj{kE82Oc&o7(wG{v5{S}>Qd{VyVW*Ft4cR&RFYjy5@)qA6lA5?6o{1G| zYWAm?>igvsW&ANlfwoF#1GQHM2Qi|)Z*_Lq-}!E}8*MVVBq~2~J+s!w@Rk?v1K&f- z&*gjPnu^~n);s3Em9Q+OvX^5kq_Oak2w6=DF!X(&v=&~4?yn7?ICm8iZ?s|YTgO@% ziscCzQ|VkOH)K%hMpy*G3tjs_%3PT+3HE_1mO=bby8Pg?zXF4xXG&*i($FlvWV zJ`uaZvo^O8bdw+6auGq=IV|V>q+`w#>OUtf>)>$qPb%%);HYHfst4);qYkgeZ_2pl zJJ9-1EyK7gQfZjhT+2*tpYIU24g+P7X*lSt~jEeBL z;%oZ1;=6k+_{1IyWzf>4$ETxcRvLq|$T6;#lzJvdczo3`9vpq)->L~midgDC8YJ-b?43S-qoKaJbm@>l}qW7 z5+1DS0lf^kJOL92!Xy9bDVc4Ku zx8q!CM7MPvk91p!&viVmpL4%8J?31!6KkZ@OI*z(2QZqB{6U_l@0qj0dfK!kzUa)Y zu_x4NlvU+Ca!uE;$ek?76yQ{zus1`OH_lbWkkTG+nZ=6!e%<*jUd)$;EU#XqY_E-7 zo+D3Hb5^=9&g#X?xAfQNozDx8iI@csFF)t)#JHHx8>zLdeevEh4&P2~d+Ehk0kpj$ zvXXrfF^=-Ne0wX_4M$8QYaTIC)HT90z>!#PuTn{_9W(zvV=LO0wp!?((fZ*5skeQs z=Jma{ogR~=QjumXLmqL@BWDGdau^dyscAX6oxo+BS0U-N1KW9G1@}6D%Q>^}J9k!c z7=?HR`9?^J)sY>Pays`jj+IIF&yYjZQo?UmA5&wEE+R+SsRGHVhqQ7_HzjQ)N2y7i z6f@m>Mh!@*M_d(e#a^RfDq-ol8`_dstrRHEi}{WPM}*@-td3Enr)un(m-{CesZS3B zN0MX86|FJ;Ty^Uh)I(KY1Zkq9P>%&Y7mDp!#HYd1!C#~l>YA1{bW8P2^?5C7>X|VE zB!!Xk+Q0U;T4(fm1z*;q(f4QpQ6mjIhb5BNNvEZd&ZmV%L|aJyba+F?Q{EMuLdT7{ zCf_JN1s;ioe!=<4Qpxv4z5CMnVx29M{iNrA&}pf?b+*iw!}F2TOk=L;>!cLy-g|$` z@%qlDJ?e;&dp7VK+NBm)%hi6aM*+{`d@lLt5Fyw8Ka;#s#GrM297wHvAhq-Xo;jDu zuV?biMH~&li#eZ1OIHFbdD`8B8i;^v6zS1iiO)uDHq!Tb#6qn|@I0=J0Dc~^QKgF~ zGV(HD1y3~cyuKe7kTPQQ7^0iGSCbJ`&nL#Jqx2+>6NzZHg*;=Zolo3WN9oBNCuOm_ z(^zuH5Wm;B)8jadv!+kZ(lnNrrbw?#Qykc(DRS&m-f(i}-cZJ2HCmc+SvNqXqyft~ zmVyz!Ye|YmyCg-aU6LZzHu0VF8L{W{L=&-r&wygh;WsN1U0DfS0sZNQT20_?Q=(NX z;l8JH-3*i~8~a;}%1W^9G_EHDCqW52p@8a=tDrYah=|)lzO=^(;#yQzfuHJb`aHEH zdbt`{B7Z9RVO?1bwKL*-E5}qQu@P$3A>HA%hg>ZxYk@t9ny%$6_4KVq-aQ3q9A4MI z8yT+?sExxC<}>|Dl0hM)1=1{OU``YJTH-BTP#1Zb z_CP(Ud~;QLixk?jC>exgWHd(0BQ1{@oKd!rsGI||{MILzx1`M0)_qj1yF9@!IO3#J zQC7d`sFa3DZ>>=UWw+IofNfjfqixT-N~y|{AvybtBA?L@*tOeo^@u_xJ(K6iZ7iSO zvzAb9qeq;z3%O9K(3qQkF{ruJHSf`(^ku{m^6PmoMwB7T;J55id(w5_MzORV<$cCo z8n|Ek_Gmm4Z6u%5wrhRuGh4`Zwe<29e;GX-?}$6m!(nk(ZjA_{`QEg~3~;@d>${Yd z)Lra3ant!<{l?y|eks~&?L}qrzza(xjyV3TpEC-f%S0Q=@vTMFQc2nR#ms}$%i4us zjF=P}fqmkrwEv>_9FcPD7+a2*=x5jN=W|$=$Fhl?(M!tqj!^p~Mxdp6E9r%};TW@Q z(iN$TwGPaS(JUs4kK$!sU*i)DR7YzUV^`VU@$I}`$RFWvB;JHI-_fHyU6kntOZ%?C zvCf(YIyUZz#Vl&Xrjf zDX(8HmbLiZq8vBacZS{uJMmO|r^%@P$e7*gta4j>Bld1kgEgXzKFF;=J(5eMV!sS0U99VH(#0~wthsoY zW1vx`f&%I{XWi`Wzys}+p&^FXc<6PZ8_H>+6lmZ8aO0F9$^zx8jXTFX7iM zJ+vI^cRm}o9ko0;M#MG?%Y>y19^u-AQYm6pIj&uo;Tx%^cm+djkx0K1Ea%8QKSKK3aNzA zto*7gQpW@3c&>jjDviB5CDnHd?=hyk{6Q_!wFizEBhF4*on1IZwTXL z7;nS1MvG``XACl)*hbzopz#ZO$X|q2(ijKsIM<4mQCZQw%X+X_8V$jHQ>S8OR0>_d zu@H;p4)R+#PkCdXh}GO(fPHc&xvRhpcbTXrHJLnPE}X=9C3&mB0r$SrX06rlq$E>p zcoHbF7SdP@Pi8~WHwCpUyMpw_V0XT}Q328^E2|S~Wrw{+X7ZLkTaTNJtJZ(x#O_!Z3UA@lheqt4lG_n?pUmTYrt!F zw-`g(xifcvER~MSF(WI-9G8>(@~St(uj9PEZ+pFyc>8hOI6T_(PQs0mm(h;Pe9kTm zS9Tr=nNMjiB)`FAzM`}j@}Cl4S=uwsL&$t@hqR|`H;JRa%xA1$CA_{epZkO=`3)@d zDd#EqIkQ)m^O}-`rxd77tSsk^N5)ms+lmxel=H@sAM)R}|1ak$;T7dSrM}}b-*H>t z+ie>?mSjHXM8l#yG+T05k;9@qQnuuG5??Qbc z@Xb$FzM_S1C6>G@taZjS3Jc!~a~h4olnVceX{1Q z`~Ma`cc~x85q7?H$)>k9$$UcXe9C#kHCQpnau_pr9d)hYZZ&ql^`vT(bMs7-GWE1( zCwEqGtW1(|15ghT{l)bs@8sTQt{Z`yI4{FmJQJwL`4)1=05@|s#DHgek&jG31O!<%(5fL~GTa$l(fCqs_UymA(VUwWfWdze4!u*njqqv-@Rl9Cf);dKu=XJVRx(kb^AYvy`XqD?!wI+0N+?bjP@C%q)qs!xfmBL3l z_bd*opbuxzkf0keV_8Xg{Ejo2#qkp3%Q28+zg}heYFJl<>2+tH#;P#!!ZPdSht#fMfPg_kd^@tFmPjD6QDC;540O$TrG3t#^6SN?r$osxnF%`7Q z`Q}RAk?U>tulFM+Y{dADb!mEdxk}9z(#u<^!JgH3SD!rFPdXFce$HwiuiNo{lOrBW zIO$H4daFAQBhrXbR3oCap4j^KIfCSkdP4@~lB4RwDWwU?C1{?sC&sPv%JFy02l}>& z977smd(Ne;++#vo7m|yzl75$Zqr^_{?(i-JvYkgKnR7H8+<10fTs3g$cPS+tpJY^b zE74<8KaFu5dPypUj^)rxQ-6&y9PTi!_eL{^-j}Wejh!I$<52!}O{hC+YC&t~sww5V zLxsMU`hrYGdT}>a_nVl+;hu7)^z3kt3irgA0(2JC-Q_Bd*Zp|Ezr%1|pBz1Oq^WC> zcE=*ws`;+xScjCnmi+OY$05N=gL^sFBT=s*w~6z3q+BWV2991N@YUqH$88gmtzJXw z;SEUa?vCr+R6S6c*p-13fXZH*5)InK-4oCPl&W1hI1wpV`E)bKCbWj-xtL^AEi?~+O+yMpYAw7$$9q2Z$fRy97m)b(ot}vYjC2}>U7Kd3-6ZLjim`;ao zxzaphxVMp~Z`pikSO>Y?z?qzl1RpVa=0TY{$S-lsfqF%3cq78k;FwFF91HzrPerdq zPerc{t-tK4=(WG){)%Y*_FCWmD)&_Mo%>ld)8}#_IhPzr-qZp9O$O=-=-%Q}fcg=3 z@Ps=fmC`fr8Lr$j2E39RYPalQ{Df|y+^=@04&ds7N>Uxb4zBVQ^vZI%-lxQGG(qKm zHM`jR)pZW;2J7A%a(4A4B`xJZt&S0`*0me+8Hu&vwDQ3M4lPVRAwJhK2K?4Sjs@VU z+Kg>f!)THF_i!vs7#urQRWZ66$X%4`(w(TT7+=L`98KujZ)#-@^+3H zw5wE8Y*-B*IDXnVlv1R!_TL(M`-Fret|f0t^jIue3-)Z}-n2wd#h7*Ai?-BOa>T4& z&f?H|U~j@BSHDk7I5sWem^+P6NzW?x_%+`btJtiY+@ zlfEotp!O&+!hTV=)EioyaTS%8HhWMRT+Ko)RLlsuQ{1tAYiNboLo(JdxdWo>bKIk) z9hmXdk>Z|M7Z@n@d~@6r>jDG&;-0k&416=(6YBy41M30)UMPmTueiFJX2 zeQ{5$3k>Xwdx3RT`jtI+VImK;lDY5cQi;JbT{Kn$5v=h>Z zFw$!!>AbYAqSwY15ssqFmeR;Gmd#P?7`8@H7t85Rtd48<;j^?Ie4zze*9lY(X(1)2 zF@^xEPI<~2u_Ir}84UMz^cT)-ECFZT$x*wlmS0;}YOB@PcT17mp_0yzL{uJWcN=5N z5;@bNBw$ZE-lhXBuQM|%z|;!Pt2kD|8s~F$bQHiM)I%wNCFSI)G z7UwOjr87uXKxd2G{X5?a-1()oiMJSG$5|$4Hr%7WhP1X_XO+atN#xslaujDp=FrQ| zH`Q@$pp|Bm>ui(rN_Cu_X>ooS zqZQG)CoQ#M!`)6=i?0@5XP6wpj(|-Gi?rp+VYKH4=5M8>!BK4iE#cLa-uiWO%%Ock zSD(k-*{M#(W9_Cr=h2E?*&>aqho=pn~>tC`efH1{n3c5r7AInEr&JsZh!TxKpb^ z6K64T1#kuV8_3&8zfB+&vk9%-odyO>B*&503${6%FqNYfylEz966bZmX3nnL5Fedc z5Szp|{oPu~5i4`rxhB(IEbf;|MQ#{*;<)_L`@toPY3Zaq(>&*2O0>3;rsH`gwNP7# z9nhTblQKBFGL>8{8$K2Z(Im1L1Cp+pX?tiA-5(e7gmFt%81H*#?%snl_P6_ z%9M^yXLxL_1>{Q`9IeWHMnUc7th8ANR33GVDiccgddQa!IZjU`Zx&FhsLWXpR36<) zUMEoMEyr&FHgHee?f~xOEXN-WR3>mVOCgm5N(s}&?4@AxcCMF!&0?&WJ_EcKzonF7 zxfm;^x2I991iB)PYjM?)-^L++D|3qFVyT!u9h`O@j=Wwh7fUyhI}ME9M87C!ir-?X zRH-##x|qG19#z_$O1^Yeiq_2aTHwTlr6Dg$^(K)Um@NkPCJdHV=9s-cVYD=KN$Q=Y zsqdWetD#kDIWMChtAI;6+e422I^gouvyM_Nv32CyFN>(3ed;KU_1;n!dn9K3obQVj z;Ld(GaL*aP;2)i-pPWk^%{|9xC(s_$=BVXS8>HiMCeVJgkED)cfNQxf0oQO&E09v} z%ms>tGstuQDD9EsI9xThF7=ut-x4$vpEjlbYbJMl>LYziHgQjivmNOAvMJ<9cl1`UceVkY z4{RYP=#FW97Fx*NLYq2f9qZa)Vm+Y}Ow6rmA&K$pp0LgtJ6jZE+qgyA8Kgq)dYF+e zm9%+Oa(1>$`7LBT=l!HH%6Zb1h*+ZiIOEwOO&dyD3$xOpQBQnh%-)CfUMvfHzR&ch znL~O1V9!`XXAGjo);y?NMDI~nwT`xnlrC0$#ySDZYVD&sj!>`e9OOf~38W$oZ8 z_oEbB)zUk`t&U8YOj_8^@706cpHk~UNVTL>%bK$!!%MxH5a#9`Q|8~ zw5^qXYyghp32{gJgSwR3y|D%yB~!RB9=VTa3w1H7fOJavcPvocYT-}{Zsa*@C%>?! zwnEHA28Xi0DruFx&n%%m=RAw87F;Zz@jY24PI$*Wd&4#tr{YQb+TP*(^ukK{e^XCFjV+Hs@#a**qUh9B%meV4F0tOTe-J0)lSa{S15?P zn>aQ@6K#Pm?(4HAw+risv~&WL)VA6PmP<3$LAp~*N_(52uI=P*Nc34+JsvtdgKN2O zFEyV-j#Padbh|`O2XH-YGM60r!B}W|2RV+#bwK%nJi>9H)ZCf)gkyCrJt)U%B_}c(i`+=rV>K--N0W2KEWP@VJWR<$nM8YpJ)$3rJWrk|9>_PV5?_?I zt)Tanm*u3|@Z_WR`EvS4?kndF3cQT|Tgr7!;=!eoa+*{~X-$00y$>7_J|!;dT_K*! z3&i~JTyQ+R`B?Yu;;QfO|IYYgyxCg%bw{Rk8tVJw?S7^I`{T`dz2d#TKfX1z^7ntg ztr2Yztz%g&v2Tt#*p5<(H*cRPv#nzrSqtB8yW7@B@BLBc;#bP;B2~5gfdTR4KqZV; zjB*BEh$};{d%QWvvxDCj@5#SwoA~zdmywRYdE4f7%=_QIDVH|B8}E!ZFZRJu-kSdxtZ2g5t!8&wnQt=c8Wy8&3J-{rOmn zF@5m+bNUlB#@b1Bq&9Efzs2{*dy2KlX-EM-4jU4LQeri{QaQ_gqTNH?z0#+_t+ZE$E;h8R>>W8otxDvVI*2-1hr1G%VH?~? zEfyn-%tB7toZ8yi=T6d{Ty5sgV&E*!n@KH2?$PU9>y_T*%emS@-z)=e;;AhhRme=n zE8ohuwH&ZM5~w7yoiDEgu1nIEHiaFuWmqM&P`HxdB(Cd#b;v;{bKXd7;*CTm-o@2M z;_sfqQ+tvuwuknbM7kOIXb;CJL?T{7YA?sB#05T`$iVxEL3}!qn$IA$A9yBFp0$RY zmEs1U#S;xgfbJ#c^Vz(imuSt}PtN5y1^6zm&Lw3W=RM>d;4psksa&0xVkVzQ$<8Nz zK6w|A-UvLO^95X=pIw+@BO42PFKM5+ki%%v8)?gnNpA#R#Q74QxCrRIOX=wbU<0Ll zH^=F~OHk-j{d$4DTwO)&&dRRlSOi=|?cPiMgy(Q| z4e9r0*OJ-^+)3@O<2VI)3T<#bHS7Q$;CutAlYl2>@5}yL_M1DtOm_3rFe(zgIV$oWIrhqK$V+c~ZTUdeB6 zC-1iG4xYOVcnjw{sp}cQD>&at9WMu-!TC;7S7dk5qx*pSIp0O|Ty{0d1Fi$us9V&iBz0?*qP% zHn^WQIT`pq&iB(Q@5>$l-k*IE_(1k4+U64ACG_T}X`Ssrt!WQZ=MMsJ=K4Wene%6;|INUM$oUMZhk&<}_b}%V0&nO1FsWOCw`QLOewNmHnB(^B5nA#?z*}gw zN65bw_#w`Zkh&%N9Csf9-p2WJr0&QbrG4K6yo2+jq^*4P021a0yKj_a}~z>^z**K>Y?)P32Lw8JNXdpJMI_}G&@m3=XL z8n}t`Q;Fg{1x?wMJwsc45x5CT@(h%42~h3f8FIb5g!|9ZUL~M5_GdX(WnUuaS>S`5 zzr=XC6u64>muS@ofzPIAF6HVu>UJgYN^1Wc$LD~LlJ^{`N3-Xt?_@ojioWD%!h3rLIWD)T5oWBbGd;++L^H)iI4frBgUnTWo z_I2PVfOm8LI;k%JH*ocJQX8^wfKS&0@8kRp+V4K#^_*Vq{I@X5R$YE(YGn`J1%v)4-=`zi)Ef2)vl~{wBv$*~`@QEZ_^AU#4C!03YZ4 za_a9_DAVV&S19G(z!y2c!u5-pwu6e}{Qnr>{|9sakO)SO{|C2M;_52}%o-v7zl||m zlmZT)|I6nG;{VD8L*xJM7?4W=!T;s_AqC|8zs&hV76{HCQo!Nx|KRz1;r+Q3aJc+G zIDbe1{rSJ#K9>T5|0@gR{9n!=Qb2J2kOBtc|8oA20)q306fiXYADlm=0C|2<3J9KG zlmZ6l|8oA20tV;*^8BI{5Inyq1q{yr<@_N948;HC{2>J#4*!?)hZJz6{9n!=Qb5l0 zga3ytFc|+2&L2`h@PGMy&htYS2q{2`Am{&b{*VH4&L2|1Tgm^`HF7E7aQVNS|Jfu3 zfAIX^{~-$uo&U@8 zbN;U^kaPZ!0)qbs=a=W_vVc-RU;aNZ=MT9c=lQ|^Ll!9Vf4O~sDd0H&KUVbrw}$@* zx9=|n96kMC&0pVyMd(wnc zYW`sb2+cpN0J-KLR)C@F|DpMZ6`;TVf3W5s7Js0x0YcBuHUFY5Kr6sN{QqFi z9}+=m{$T|e3H@KqKdb<`{y!Z4U)29Y&o65JAq$i>|F99{`u|}3KX|@6e=Y?C{|`Ms z^#9=h>ik7pz(D+eWcB~h{QL9&(EP&|5c+>;{$T~^um7w0hZP{#|3mW+DWJ&zkL&+$ zt^Hq1S8n-Vg5B%Q?Egob{|D#qZ~qTjAozb+{#Rg~)Be8#ICT4efBio=e|Z*QX#9U* zE5Ok7|FHk7`Nu3kSpNI!|6%{v@*lGReeM6du<++rfTI0BEdMbJFjDsaL+k&Cw*Mbm z|JU*#vjAcF&-MSJ{r_ z$^xPPhZLYi;9&i~ugzc0Kjs3Se#6e6O94gxuSC#S^AB5qvjE5S|D&b<$DDuB3*gZ6 z|HJ41&iscLfa`-6WA~lKEVMiQDw)gYPe}9sC#3m*{Q@?SBj(F$E(RdlUd2DNnb;I z?f`0CxrQ3;2kzv2EiJhVxQjYmN9*(ecXPgu{<$8gCI32(t?2&;sFicy2Y_Yt1X3ifVbsc>E27Yxb#|N2-J|EluhiH%Ufgk34J8iTNcn9Y@x&AQl z4zBMcbq90yx2IYCeOO}E#`XdCF@y3k<|UoU|7c2|!qvyp6Zg=^rzGqB9^fhD#+?4W zwCWz_Q%^^Ozc2Y$+(#>)j>Z0BTJe6`_hO(P6%TOz9^hqMt8Xm=>SOUq+Vl*dt^Y}m ztAJOL_bJk60`)Q6V;q&_wyprB{h;&%{O>%%9dg)z2Wzo;lH(P;Q8Cj3e6MqN1KF#z09lh~6($4cg zLi$nCa=Xu^^atpXM>(!%-uF>*9;25Y1>Qt2KF0Al@Ns(YF^&%~=X(P^_j&Sf06xz7 z^Yrq~z?-@H0_R(S@8|pl`uqLZt#6}epWy0Npc38_9JitQJE!v`X*t$yoS&k9KLq>` z*H6*YABOwiMgKodkKYBn01SAV<90aK1>}5@-n;<#5&HUz9H#*9;_4at_(I^b^!GCy zA7jp6Z<{Z1bzz$Se+EA9sFTA#2fUZ_^I*Zfz>7FPPwqwN^HRVsL&svC|3%WSD*7tN zN}&D-U*(=T*K+#+ZypDh2*?LS2;y+kWL1w56rv;C*S?e%>4CdbRbd${^0 zsZRj)$asbHw}9WGey=32gjdLaIr}!(F92Vl1-{Ll=dxG9sdIrZQmopj22mO5qi@pQHu^oihV0aLQ?_hWhh6mwbzJo{4b}+ElK=>5)^%pE!5VR@u z^&N~EgqS-hdJPum4$2;cZ)Q8tYal!b2l5@%YcMJ-h?Us{@AS7x-54_TkJ61Xmw;b->~9_L21qI5OT|_6W%51&Zqe zhT<1+FjpUFUZ6Z95bFgF$1h+g>jH+(+l%u8gRKh)|Nne-fGYxqGA|Gw0pT4`^av<> z1RjoGK>u|Chnf)>iFE-(;qAqFf$$Cp-X1)^$lHs40Y$&S@CXP`0aphMHX|_5x`5;J z0*z)0!#;T>@3bpeOw|3la9kA`1B zQMY$R;M?IBFnry<|GK~<^9wliy1-Zw7_z`%>jDmz0{Z#|^ymMvA~045#=5{*5qPk7 z;Lz3u_UHeDtqU9}{$KV8h&6(J*98`R1dHAQMZbXZTEL>GV6NNu_X`X!!2aHW<<$Xi zrrRHSU0{FyA1eZ5bzrOuEb{-No*z=cq4|IC{8$&*-!E_|>jIDS|6?yM!0`P74jmUD z_;Hq<_TNgsKqCS~bbuq}|Jw8O zxB$umd0c>@^Z)*F0m341XurU)>K9iBhW=k(9guVTVqAc-cVN!{L;o+@_QQrB+&*mk zVeJozVEAzX2IK#+I`Giz0?R7`B04}G5g^tD6!rg*0*d_Kcn^6jfa2=F{(gbS;{uF? z{vQ#6B05n2xIo9I{l94WFG>W#|Br_L?~1^X1tKC)tPaTI0vQn~q60u|CgU#(55h$VqMJ%9Vbf7#IP{ai=B0xk3xENn2BLYQqpo_SA zv$#Nq=Kn`#|1ZV`8Z0irvB3X>=Z6%~e_g=P`TwEy|HF+7aJ2dVU~vHs*8Kb0|6^9a z7#C=;bpgZC|NF-U8Vdi9x&2rd7^?${>jL_(2)Gds!NJ!B^tb;HJj0*!|H0M;2InuX z4ve||;Qam91s3P_jR+K0fIKcx%;y*50%!#oXl{S7xIpFT0E5Q`2+hAN1@v7P5UT)! z=Rb{4XC4>G`InsYhZNAC{|C?SKezu*jSFHwhz`&a0Nk?H?Kj|)5${(ofp|6u-q zM`QkfIQIWzlmC}3|A!wJa47u$$n^h%HUGi=|Axc=k8J*bWcB}|=U-_4VG%f33OJhj z|8U|07w!L{^B)`?c%Znz{6A&^28#>a-~L~m|1bLg9~u82Df@qL{)3|f<@5i= zwSDdgFtoV9MgBjOeF27|{}0FiZ>0GDq38b(*ZzMr_rN0$G) zBS1t49Ep7aMwb8gxBu(ym-_{lrGUO``(oxlECNGW+jnp*z|Iv>Ncf4ga3!;U+Di~5eO-u z$p4Sb{vVeA@B#=aAZGr{UVwx1|MHFi!&}=wbpQY2zCcBuUz7zx|L;HZA8~<0{|}wN zIRCFK@XqD`M|=MNaP9v`d;NcZ&R_Hh7{2|#KmRXt{(N76W7GbBWd46K=U?0xDCYn5 z`OE$Pv;_?A|99N}-+$$QSOi=JQ1tviIev|Dxyr(D{E^=g)Ts)D|$1|KCvT|HUXW4utc zDPyOf0d(Kh^T~;QQujgQjF5T(9@(d+_^D?C&t%jZ!O=ZZjooq~$KDi=bw6-F5mzrF zUq5N1zg~>r_io^Bt}h{)=`P?dt}i8h2~aECyMdPy!}BCkm!%l8%|x4>%>KR23A$JB z1g?bc*!v_=HMgahi`&=(cmg?7IZwe>@)Y@BBxdba;8vb{jJ$2YZLC)NGWlO*ci|?U zevZ_W?33si$~Z0up2$^}V%WN)<#X&&Jf0_CVAcE<;1+&Aj+|DaI2y6?S&lCeCGs)e z{0PSmqD*b(x#x+pyP5rp$EN+1$MO6VJo5<9$em9RiSzLk_j3nOerb%(C)go)48NG3 zc49UX=uTGi?4&eb;cd?Yp9cfm*duuia175G3G(YH?vzmMe2}LrfRA$iCcpX$(2?5C zuiA+B>%P-f9JR#zZ6tRF`z|*Ur}6}zE0K0*=LXIl?2p_4Y~cEnys;AaAm^EB_vD$} z?I7N;yGeI)i~^40-e-B{lR)F6f0k&d4*|7$euMYF1T=23QHN`Rwfv@w^ekepx?A+8 z_+@2^#99S(_vmjC&GOrLx^Co`FQ+J`CK>(0KPy_Wre7?}5v z{vPS?v*+~3N&f@s?*Z5I>_6~}*MPm8@8s^B>~-@00XyPdTpQo^E}*{0?%Vu2@b&CR z>{op!Pkxv?cLML^`iI>45ph#LO!^-kP-QPj#wzT@*D6O}W{t)MzIe&niq<@_KJnbp{W8lxTpRwcg2Y7ydiWU2->|e8g z$$km^RrZVQr<{Mm@k{oi{wXPUrT!W4XI$NcpWqEZbz|es{v8ptZs8pZu+QECyqPy% z%bgpt-)H}x{UQ4u@b}qovtM)mEywSer?`q(y2dp&-tl`$ui_iO0j}o!-`QWX{~|8e zwY*^=$NPcr=e_^Qo&QSlbg#(%oc)ojKXd#ikzD_ccdz94{{~#e*%-*z0cm+=^BlnLfPWFEgDfX}2S(5z^ z=Ov_+mH*7uQl9uTa2e;NTrUAzD;Q;!9PU5wxHG3JUFD;!I*k!`Y_H{s@V>52=lF%c zY)!vyP4AeNemyPaPG_`MG0Ll;BW;Y?YG5_j?Yyf7Si|)U-sM=X<+{WetOM3@?f4x9 z9L4oaMsYpRF*}j5-2iOhx|xwb8aSHkNzjupw9CPP`>9exT& zOQN*W#qnHENVHVl(l)3|^%#}vF^Y5@-?bj~9HUanZIf!QrFG+gV!Uj^dsC8-t+KS`& zinScic^vP~I8WnBepSs`?lLWvCt9;LmD5)BT70SoR`axV8BYzpXC21_y%vKe@Lr#t zn69iN$o{FU{Qp z26aMJy0|v7dnd3HYQ7sRn+cpr-dyg^Ln`PZwU_&|fU~&T#WU^@U*f!gyt%+R(Afo~ z<}g~j8I#8A>jrjneKJoP;a%=@QsP=CkvmFd$k)I#+sIi=eXD@h zdog!vz^yj!)uw)^O)XZNT5Jb*b~2(JrAv6$5jP#aT*p-{TzwkprKIcVuW4M5;;Ig5 zqLuVA(xd3BR<7&08im9$mGpAbVyBVxl}xtMdhQ+6z)?@XZ9zUzirGSYYdsjv(LkTJ zkUyDY6Ro~7^~EaA%0Zieo3az=hgGRxR&(A+-U(pFBvSeSZlK>*^Tb%__-cAyFT05x zz4Z1Pa>v0<)_@fg$(g{h9z0k}?sz!O+Ju$sf$O+#;@&z+WZyUNMloBA9?j7}TL%7! zo<0y$EQJF9N!2 zz!KmRTDpfER}+d8V%<`pG}(C_cLi7o6w~x=*b7`hj+Ti9KvxvX2TldfC&wKO=L5wY zBbDs~$|c>=U>;ChT1oj%1I{I9JH0v=cse;!y3>Jk$k|5U&Ha$_z~=## z7{!!!;Q8c8E6xWx2F0v4pt}Z0H!c7=;>5)1zzfL{GcN=>zQo^YKvz?WnHK>aU#pN8 zT7mAqAZA_+bbKjAOa)#-j`(>A(2=E#F$L)U4ARw0fsQP_DO!NWTM*;l4Rm~6ft)`X zXmn*qi2DXKbI1kVv%#@;Iq*H?&P_F&lj?0>w}S`PX&%R1`qFl?uV;Wa)@eS+Jo?gh zwXaLynRQyg5p=VI9Iq>nw8ILqpgJj`eV7A^4~!V0|3}Q-IqO z7OHb(slJYx7Vd3JSg5X3k?QMsn#{ee2@BPkDpMUDPm{Q(o+KW+FPK`6ywWixRapwI zZ6-%;rY5!4GN7ZYmb@CUZxbn7cRA3}RYzVe*mnY{rZleXlNI2aar#Gb)X{IsZ}#Cz za7}r=o_aWd}L-Vn!LKa&LX=x31J*UEGQOT2DW8(MRj(we?_27uVva<7+aoJM~vL zccQ=6(jShoYVfTa*iC=gM{9tNu^KRP4sZ_l=8?9)9Ao16YWidzIrh{lpgd&-=auw^ zzUXxvwW+_B1EarOH9v~O{*s&7U-B+Fb3ORC5V#=qnmo{6TSm|Hkn3n(N^kU}o?67& zo>~f&i#CFz(v2}Gy_l;;QevrGW(iMvXDR1pyhrG7z2C_9EC5F8^)!oA>&cruM^@lt%tz$kG`Tsk4)tFpBF0qsawD898N>=nly365rQT>O=O zh{c_ZjkYvqqyZh=oyo{(Pvb)hQA#7jeS%C&MJjl&Qm4F4Db#B@dZa4fxbhk0Xz!Lv z>PPvL@oTTk8dMeOc(2dKZ;Q`GI)6TYlW!=em6zi^)#NKbmrC+YX`Fgllp)IM{VMJk ze?M5d;*EFs`;0gF#rQ%E*VfT@hg|7>wH)tcq$;>CHdzYgQ6)|9iE~-PFQ3ZWLJTdp zgE-ohFtUknj^rDY>$=wp6kV;)E?-%^}{{zBL?5xYe9TrFz$K z)j*3iq@Gf~9nNq4s&q;{)31)F1wvbtww22>p08PohV(=Osqv`<+7B$3lDM=_>Aapk zSJSqP)~WIhY^vZ5S{`cnQsAcJD#k+Kao}hfn@go4{(DzE4&3ZNu3|)~^Q-xbzjZt< zc89G)%zv}*+4_zg>ss+fS$&i3?6+-wZ6`j}Nd6eEDu8117>*2#a2%OluF7yp2Ko)Bh{4X z@dTi}TWUQKD6f~6Hv^Rcr21-*$_(;>$v~-tvRVsJ*+Z@}1t?vR=g4uCIps^Oi9@x* z*Vd7igH0pd%E(_!N_l<_P+6>vwDe$gq6hL*cbQXnkmr`*&?|u}x$c0EF9#|)c5rB| zT1Ki9j=v1JjO$rR8kj|nV_i9*i^CCL&(&-WN4y$MH^*%FspDe~M|a}Mb-+5Vm4B3i zYPp_IztjM0xLyEWRRgQJUYPoEA$?gzx{BN$a+Ddwxdx6N+C#oB$DT}EN_i)6o=A$%uW!0J{56kN{lPhZ!_AqTxma~>$SSl%* z^ed=>G`T*N)%K~T{Ea|sWa-BOD>ysG>cMXLz-A72I+inR;ZWXJqTkBlE{5_JW&Ev- zA9>Dpj%|#q8Kibl@)?Y`c2e4qv@2;bI+41!fmzc@%}%)94V06}CFcN@ z6TVF$HIKHK0%ke7=5vT|j=BXL;+vy!A%~deDDB}`2qkdzF5>6`za7Af#OKt-mf6PhNA=6!L#D+Ov(|o)8C8ZGiWtO;wY}C1M4_X zB&V4=h|%JfGK@Ihz;!FIo^umV1=V*1ivNw=nM!*#k`~W|jxTwKJi_rZmfWz3Pb95< zwamXAVdb&xz47TAO_a$}$f4^gsT9MxP3^doILl*|;QYN--ZAM*aw5mHCDZEO!d=U* zCDNL7rZ#I!HL~W;6tr@;ox?c+$C9Jic>%|iW3&TkYnQlJ3AF8JkPbR!o_#9+l`F?} z1wFH$x5%^VlI5xvC?06tssZ{NEnwBa)A(gIu$t?Ayr~LU#r3JYuM$|v_1=UDd&xN! zdtJu0GOsqhdf;yARu8P_dKXyQ0Bqp;GobP z#|B1#xUrt2myw}PZ=b2ntM9D=s=eEjt5ff-CcTC+*UGgRsZOr-%U)awZI}+UPt`!% zfcB%hYCF&|qdq$WXuqlLmVoxHx^M^3o|aqA1lr%~)SWT%eT2Sq`a?lw}-!CN0Xia_&S*C9Wu8Nx{Uqn1gWMMa%Cb&dp$k zG*HY|Z;>`SuGLf=1C9jgXf04Yma?k3jN&{kjUlCuQKVyBw{Z>)MVhTvBE~QyR_aJ! zotesEdsI?)%NNvU7AbA4T57sT)ui^QrtV_4?NO6jL!9p>$My)>LYYDdqn`7q)Hc%4 zd0cBvk+#kUYC)0aE&ysZvBeewwVl|KJwUA^w&^0Ewh*a#(D=oim!{U$YNB<;*45Uc z9mdwxDxUt+dd_F&!N1Ce_Zl4Q!iDY6ke&1?(cN?5l39l~|d0CjHS#s#IE< z@VbK1S0;=QruT}KNYEtrjWdXT= zL!wxtf%cM=EVr^cHxT`!b<>`)zno#PXPkv{7Q&v{2y~`GDscjE6VN`{1a!v3J_&jo zTFMr#waSXcTY*w(vDlrbrQTxkcA(Z*dt(RCnH+m#CvY}UES8G3a!jSg9kZ8)YFDcddw}#OW@?*AX;s&PEA5dd)zTIdQ(rX$owv8Iv`{E* zIGdi&)YbD%dB-$*du6KOiUb`2?O=oW<_MSpw1$p=63`kt3apD#a?U%fp`)M^Xbsgq zJ2@6nyKSUq(L>v)?N(CGUu^+O51i2wr=M zfpin|X=f+=I}51CnlxcQa1v1b)5mQxQ2f&;t_3Lm={Gk8DE_%;=TxBhrw?5#Q2cYh z?6JUBB%4!7jo~cRORf=Uf9W?j8fXvdC8vZFvW}9E5>Gu6j*`yFq(*VBN3uDIR2}D0 zVET!qYB>wlS*n22WGyh_nKW5RPW;O)OO{UCp5wq$Poo}=18Wofp*_{Ije56(yVky) z_7ID0741Xnq;hw?3z|904jeVj#tRICGLt3L1 zM@k~C2`Spy=A4IDfRWk^JNU9%acB(MzK6oYgM-iJ`|nI1KA(P37Ml;0%GrhsfKoZz zZy``BCk^TWO6lyqML?;X?Pt_ushs_%FN9KwG)Rf0o!PV6{gRASAAlDIp^huEGh*$b3$almy{TL=fyIeb` z)Y8o12=3r&5{LX;tkL!|32LR)rG@ikFsC!&{4Ahyuwy})Zz_lUd|(dJo_I(*cqAv6 zhd2|gbwn<*=8bkNu;jZ6@VRsI*}VP!20?P->III!Cn) zs2_toQcl|qoC7`Co?2oDP(Eu5?F8yoVXK`8RR6LyPXg+lVJn{u>;T&KdUBMYZF>CZ z`!fStw;Q;d>vqyJpo4ozwQ*LjIfc}8&TR=N)rWexo|dq(HQ{3`>1p)TV)|)n!b-7G z-D)XNj8ykp1{4?7%a#Kt0oB*UNpVqaZY5A$Y-S{^0*Z@{kk!C>K;`)0-&+4{Z>gS^ zUa7WJuMud^ICiv4X=l^(MXQ^hFw#8ztE76;Kxv*1-_POc_%NF9_*?tSH`xDv&#&7D(Szz_&K~-G-;jG+`dfcf zn||T9)ZhG~eHdDtwjICe@1o>laLiTMTQ&4q_;!WeSZ~4HOVD{Hy&lUJt?2jM|IqhM z-lJw2m+yB^nOVS3ZjkT4QiRso;icqFmQmaPZATP_Qj_;EONYi~^ zP@GE6jvPy4Iphn{9!p@EGByW?4*{8v8rHeUj@ax_W`e3bW)lw8*}3$EqH5 z{w}=F{3^KMp*WoFF&I}91EM#E%iE;jwy-jg7;lNh`zW7d(iWBLit8a$+0Wv=RKUKD z*-|OHltBx3;J$AaAH@UT8CdVzlmO*h%7J=3tHWy3k(W63oU3%)+p|)X|Hs~2huv9R z```CWh`T#^k^nK{?(VL{m5>l1I7Eq&;Ov06s^z}{e3<&?3ZxP z>1oe7zxTS%^}hLIzH9D#?`J=I-?L_|^<88BM_W^iua4B?byq8BQ?#Rw*4mG>okl_S zMfD}md&&`kI%Q0dwK-b=d!GH#*vvlVfA%TZ>;2|F9sk1k&K_h>%B|<`&i%F2+w>29 ziccf^HX~a<%ctVADb2QUEy2#dEsq1_*%ST`{fLpkf9~7#wfeS-{CY9BPXW(ko$4u|>m|=;73!&=t0&!a?KIF8%onnX z^>olxn-{T`^$hS#@H?#hJQKVa`JJ>5^kUYwp3U`I@DkRzt_58`cxiDN@={hNuA_E2 z^0Ks^@p9JcZs6Kgjh-vB5p-?im8`ct26Uz4cUgD43ET``#roUL;1=*|R^x5~T`74D zt7W%>+rVpCk-H6ah30jv;5`;}o#yqdkKGQsTJr{0)9wIWyLlt4Y26p@cPpZR1Gloeb$`&61-G%1b`|LAgWFk;dI0DOg*#ZWdLZa3hC5lm zdJyQ!$h%nMx*9wfyqguR2ZM)z_prY75YQEl_p(CuP|#J4_pz?^Fz|5je%75H4!TbB z0amCU0lHfAd#qeN5_HYxgRE#h3UmeM_gT4mG`I$QsCXFp5ER3UmqR3Xo@5gSr%S)yK1}OsP0Ot}J?mRj$)OR}=k)b*$4tR}j5gyoP+0k%Sr4UPr#h2*XTj1@d*WQ?sZAWRY@J zde2^5o2xR0=?$8z(wg)E9ktW0xIVzlqc)=-X#P}N;tU?Mjas+?pt(kE+(6Jgqt?}R z80HuCmyXQl45OLGs$>&~B!B6;G;@naI>SJ-in7q*pjkyDoe`i}MdKakTbNZewrvZV zT{QM-2bw)~o_+g-#zJP^jBWP@%}pEOIy=hTv>dS$Xl~kkj-#>WrsaQKKy%Z2P4j?e z10Ch)2AU1juXYE`2I@0=fNem>!W@BhY|61PM_?VZaxBbISVy$-Y-C4Xos;YcSj*zG z;_t<$#oxfsiqDas6@LXkFTOy2UVH+6QGAK~qWBB=W$_jA%i_=AS2XIM!9Q_Tgg;UO z_$TDY#UHtd$Phj%J}zP?hm7IF;-jKm*bP}Od{BH?>=w!+cMIM2)=`Si&_BRMi$6W{2nw;`91hM(Ag=! z1K$K?>2HF+1&w)r3%&uGZ+!!N9W-uz9aOK4qh15mck`{Ug7yRBuHS(6596^{K>Lju zonM3YCnJepf%Y>atzUxnKclo?fc8tH(Vv6%S0nhJf%aoP{!c;sx6$d#p#9zm;U!Re zVC3*3sGX>UCjA7|eyCwT2DK|{-V31iMveRts2x&Mp9i&1YVdQQc1xXp7Sx`p>(7AN zImexz2DN{VEIb8j7tN>t5Y%3pPk$2Bj+#&Z0jPa7pZ)}>-8G;7IH)~tiEcgyYNs9h zcofurJCoxPP`hqc{b5jhZyw|!P(RR&zWRMo|6m_}5Y%tjx4#GKPlnRx9{}|;+JgH* z{f{={K2X1;?YI}zUujeB0rg|rn!7>$n>Oe!P`{^bx)anNYP0SD^^@AN+d=)OHtsf1 zziOWTR#1Oy-u@O)KWtCF8Pq@9!*2rh+xGk$LH)TF;RaAY-v!@xJ*fY8<>hstae+4X zTF`hwTYL>@9HEWA8Z^Gpc3%Y=cWBeU3mT7T>#qcjQ}h8>fW|NShRZ?Y8hyrPpz)5r zBHO)SP=Ds0DXO7gk^N3NKHupTx zXl?{C$GM0nCTdBBWNtO z5!?V8V{HJ}gT`L#LC<+GCR+!t1&!6#f@?ryxHaH`;6Yg53RvH=vOTauu2|7C+N<-b z>^;!w>PgdOo_q0HtI zI+{B@&;~vGD9Y$$kLrSY*OAHlkL1-+$!6(k^|vFqukIKpXxH?*`rhGq4d-?_Ua0MJ zUAp6k*&7>exQ1PyJQSZYEZI$WByhcG_RmAO8cMIzOB=Ne!CUC7ogX|T^-ot6X-|xA zTyOb}_b!rc!7(Ct_T;X%9Dp?}klCw`NnTygJOIn6<#GMLGq}g_4t;iiP%D&Ybh~T7 z*yPvyfm);%+|mD+rMmsG1-0?~Z@F1nS+2F^jw^|@&D!m8^k04F1b$froyjtR(jE-F z*FN4h_4@XpzIP(eY&XyuViPHQgXMVNB%X13Q2m)i&DkImd36${Bj|jy$+TNVP_H$a znzKhHrTflIn@s6~{n5Woq1F|2Card<3pT0>wW-MyPEEd1+trmj&iI*1>5fgSMr|6J zSq;>$YU{l3Y@unCp4dQr?{svtCRl^J)4AIVbY+KjvL`lEzdZwOtPMIRX9lG&Sc`XP zS9>Q*+ZWXH&rGqvOy1Fty7PQya(4zc*?3_V+T~1~dfc7GYXd-M2x+(bW5bO#_Ccc> zg3ce>hcXy+-i~&DAU2^9HMz}T(3oX*iehGSJ%qY*lIC#7*+8>X-FRmXwPDHHh-PBu zQk+4g7oE#%!$Idc%}YLZ9vZVd_2%5wUU}bnQS&IHk~I_c((}>9GOz`&&F8hzpmTQ? zpig^(u4h|-&b9>g{0peLW0yM`FQAMCodwh;X=fWW)HN^aVOxr8Uev~R6xY0{b?qt6 zrc(DhP+WuH>X*Hf)^$u;*O9vOsMN7e6xSfAX`LyqL8zScOYQ2Kw8+)CRjF6uwQkg1 zgP`Vgr?>_|{c$CNYY^0#o)kyj)tp`w*C41T&e3uWg4&X2Z}v@E;ac0e=tLdv_M`3^ z1ofdm#We_O#Q=(H5Yz$JDK!M0fjx-2YY=Sfyq;-DYH?S`Hc2*UFsl9maoh^oI zH1acX9kWl%wHvN&&MP(YJemAdo%!2^SB+ru6ElX@6S&s77I!;;{q$@R<0V&K*XC}g zub-rCXH4aKZF^ZqN++J8?Q7gsiPo;mUG2XdtS;B>(-Usboen%>ZIQOoxz6=@%_rWD z=dGp6tgIxO)M@Dr|Uz#jh!{*~*R)Qubdj;sY5C47pk1Vif9Um)v&dipPs^+87vzogax#`z^!gs*6WBFLpfC_*DpE*)W^>^H=9V_0Sk z%&_3P2`sZ*U__Q{Mr7fj%|N+y1vn@fX|5Szg@dx*gzFYXrBE@jCl%LaaKbmhH@H_u zan9_U+-pg370U0pYDIBg^Y6K8O>ySzTU_lyasKSvTyL-W4-vQs@x(&?s zUGUvx{r*6$Es@tB(8u?vwSx)2ht9rFtvx*XeKh(5Y8~LuAE4%vMUVmdGL9zx>B@(FL19LMN8;TW!))SLia1{LD3Sv z$W>2@mhdI6dcjCv0$)t_@TXk$rf3h{QLPWfHCaFBsxL)L=uTz*DB44JGwV;$9{!4} z0Tk`wuellsm;N>QEA9@0W4{8v!u4Rd_iw=8a6JT0{wnw?*F&l6313GJ1NDCQBV~g3 z({CQ2CPRFHzVbb4BjAePqklX|Z6qA>L3+mbsf~hLexH8w5Vg^8&WFH9kYhl-oV($T z1+|cmA;*DwGxxk34?5TN3FHLO211PKDJnm+BAmsqKk9%4kL^%*PvDBlf9|aqenXaK64NH@muBEJjy~#$`C4Rb&`)lELa?6YS~@g<`({f1*(d3-5*jO;7) z8+mL?FX0Rf=S5V*&N(uz@2H+EUv=*2E3|wyDEbO*UQLSg2HvAqJ6XQk$>!DOj&oGB zd37lIiVvyP1N9Qxzxtp&P%GE~bmra1)EXvR*a*}=XbT&I`Uh=c6Hx!4Eo=(vA3i}g z1DzN93AN_QzwHj1W!1m6z;68w{2SM0)b$D4vz8Qng7&NxMW3KOYfaH7XwUYb=o7SR zds6fUuOvU9ZEHg@3f8u@r5FWk+uBi#g0*VxDMrC>aMgig6s(Who8oE$y;DbuQSh78 zI)mDNJyjP_+pnkU3d*naRNX)sl%A?PD35v)*#p$xKS`};vQ@o6nUWT(Hz;4yV!0FM z)8Ny|(rdB$Qnd8XCL6Ea>QB+eKaaH$9$NLhd_)>kZ|EW{S;D;850VT<(@ODOIYe?7Hjc!%r3>$%=H`HFqH zo*)(+#hRu8#PB3Z^PQ&PR)_U z+p)HHP;+GQ4s7n7)Ers76PtTivcYE~55e{yjGa9@*nK`TeZqQ*R#tDYfufbw z8*HR#WiLziRnM@AqJ7mfY^G>mub{Ri`G>8bnLho)HqZ>_T_1ABl2XPG4owx z=DWtsca53v8Z+NDX1;68{QusVxqJB3fH|7`Hp+149>>Y^em-XT-Qmg+a>tm)z>dv~ zJ4)+lNmcGTO5P2o+?V@#)v)7Ju1>B3OV4YE9l59te|H?qQSvS@=)4lw9J-@jUEt9J zsGHsIOm1W#bw|WH!>L_m>?nCB@+5<(J8ISme(i2Rj+J)=^GJE#ncZFW9CzEBjE*C2 z4dLI8mb>GgV{;wI{5T%hhs5D6%v?kj<&(F>`0T zIfCR~oPEgH<*pE2{iqub7Vx#=aU;T`k}?tiuN67c&Ze?&h(tY5xr;e7p7m+sCvGLMqwIk=w{;8BKt>-ehv#N6v+|$Ov_a=45hVvQn zesb;)?)W1+xQlD{1J1K_uU25um|fC zc8!_u8Z+NDX1;68eAk%yt}*jnW9GZY%y*5M?;11THD><*{V{Xbth;jE_3o~ecNZ=q?$qI46z;L%Stst};Q4}8xR-Z%$g^!dIlx^n z{10+FcYktc4s%iYtO57(aGz>FPv+>}N`8*J8@c<6pDJgp4g++?mb)T-dp{)iW^(>i zZT`xAFP%l@u1KYQlH6Y;?~Nq?i|{%5rF&DktGm0kG)lj}v>%c?Tz`94Bu`E#?HQ4G zzAo*GdwyAT*@@}E-RpmaR?uKJ7 z(A`4a5zJ?29yIR^>YhsO4q~3QGSVGR%+yw+Zp%4y+C6YQ%f;4l*0a*Ra%>^r=f3&w zDOTEtR2_5g1i!1FUfMCi=azRx@mu-bOYiah{*^QHN;^5Y>|d5?XcsXNB`?A=w$HfJt0*X~s1$ph}3;@(w0`DS2Kew*jp`s|yg-{-C%o_y>1 z-|jq8mlid@-6Z|)CcNr?hw58niYFqfVU4ND@;yPo+4cFXCwETwSMK~9-J9Yc?{nw( zc1EJVE$_ZzyE>2EXJv0x8`KGVlsb}kys>YZ$8blOy!)a5*JtE2^l8}=<l zD+@l)y8l7F^*y$%pW?62xeA|x-^=ggJN%1m!TigLUw>kLZY68xH}Y5dyFC-gZ<_(FNG zG19g6&A?_{yIQ6^SvU7UcZEoKvTE+|+J;&^(7xfRUUfiM>^tsZJNevmJFEHXfqmMY z(R_-wp}V-K$F``J+TK^%zsXs*`FtsL#GQ0(F(!vZ|M8x$*$4cO>R;9twZZ@6 zC#d~pWol5?b~VetbMLlnTU;CB=af8F{KzTPi+rzrQTW{z&)%w1&GW)8%!rztuPpKF9f9$b-N8gio!O17| zsFUtD*_zD53`{2cu}|I-+BIG^I0 zPXqOYMNf0}#6{POdFG<05V_LGbz~!`d9vb2q$iSk?xN?Ey5_<&OZC*Q$Po1)uGA3i z&#q$3rk(bC=2}HhB=tPby^)^ge?8`PD8@~-dak(LtastS5f8_m3b9qUQwA>QRWqu zMhE^{e{*RqWoZ?q+8nbBFrVvvdEppO<=nX&r1nJ=POrv$gR2;*u39 zt%J>$MO%}tj;F!4_}UKTw##R~x&qdA61860qUDohbF1m)OBQesYMy1C*TC9-d39{7 zbT_wj%hcLg1Im&XN(x?XVWnr{~l3$@+X~Rv`5}y!``RIvS->W^;P*S zy&m*oqo}+>+qSWX+q?Bu*^70hJ&aql3SE+~(tl|s^jO)8bxOWU|D`{(ZL$}0#kDbo zUd%Q!E_GbEJ*{D+(l*&ETSa?jWYH#BGyRq$(MBs;LC?JTSKtndb;E$7ZF- zPurJ$Nv~w5a+H{3#GX9IlGn)*WVZS}xLfi}rB=7EYOOqZOy89w(X1z>oeO;S=JMry zYLe0Gh}26w&CC{P$-NPvHryWLiD$NkUSlMv2eJ2fDw=&r-;vK38lBq27V5-(XDW;a zJ=5G?C7X~d<`}@Iyhmy)TQ0Yo?U|puy-oI|g|lru2PU_tZJ6T$ThW-ocC%G86S8ir z{(EaMzEw@ptLAT}1@{+a>z;pC{_Xl@eRuW*X3Dac z$WPMwHF^%$?`E&!Y#O6^+st^t{%7ksgT`3Gwl|6>onohEs2^%a)*<)t(8IaMyz_eW ze(w0-+#kK7*`chV&K}aTm?_dG>r>Uo>}%Co{jO(0sdwt5yANlL({g0}l6{&_&N`(( zSHJZ0>QvSxBLMrmdZI2F&*!K?JyBcC0=dhE@r6-_bGhulrM~=MkLPW@QdFOLq3vcQ zU$O=}$Mb5V_C9mX%sXwjo#T1+-&T@^Wd@t$d82t-$#&a0p10NXOSaoTiswsw+9>j$ z#q-&7+LAd+EyeSh+1rLWs{Kdtd?{OC8-6>UxAn5m&lv|>trW?(q_wokww|qK%qI)8 z)k+aYj_1{7ZAR&-Xjgnv*=A_vyMC?BS--!Dk+dB4j8gRFbIkElN#nJ6+V_&p$QCi{ zz3r*Bu>a*gkRv_&sGizBTC&FW4fVn-f!3oGEBf?}vOEV|t;zNy=R)iw{jdRA{mdY9 zz9d_Et&X-t`{B&H9G?zIwo5ys#WHR+dbNKUx9ypFlRKDc?bUK^o>tJPN*g~k*>!uJ zy}_rg10@=>nnnP)!+^g(mIm*tKK4*_?Q~RSmF~{h(REeFI;w9V8ma;W$ z&yq&lmfA3Fx_u)1>r(WkmCF4`eJ}A>d9o3dy~>sY4CuVjCmy|w;0&zF?{%FeXmW{I`t_7{7NOfGx$?DcaNET3d=t7MN* zF7+dOlM$<}5>rdr8n&S=VVtdPlB4K>bMDQaXR8=@+oDFyLsP40;cUemN7-t_zV1=l zL-QTBVb1OC95v;hXsfyZ!T&D4Y#u0EBImDu!oB?`YIFe7O$om-(_> zEbsKCj_k~rb0*83!E*laKjO|ORBnJ?$q{y)kh?#!1}KOKd%iQEjos}3#v3E4 zYblHYM}gXunpkwB4Lxy9e6aDPp4fO}EOk$KbA%<2w(Ny$ODon(cG2A?<=Vzi+E_Wb z@sqnr%F2zLj5J*DV*Jzy%b=|^a`OCK?W5McF)d{DYy9N7ZpOgIPfclEqg*4WX0)++ z1LLRWw7t=WzQ!Fyx>MJ`XyaU!V&tS{>Yo*C8GrM0vfnT2KMm95~n`IqrQW?|pvU)tBq!g7{B=lnDC z$}B81ugt=B=3hJ8keqqUmcAuVWM}3j_tnmSn|Wo{m7^fN_qX|1W?tC_YU?r!(*qmN z=iI!OKk$k( z^)LN%KRQ-X1Q0Py{{#0FamqT-`W>d|xnjeA|-DcL=>mwmQA`eA!H65x5_W(>L}OQ`p9 z_j-4`?VQ@n9@se9K~KBXE_O`q)iGH@dsY!4AA5=b#GS(F^TvjWj=RRzS-b zxSLl(deXXfCFklRcYC1wp6gJKT6ZuaE71C$vfG*WX$iZ7S{F~>&6z0c+M)8??aHq; z-uTz;VTaVea`wcL%AD88YgJ43P-|HF4URJyOKBB%wugQL?V_#Ir?w{L3cYSq~QmgoFd#EMMRxxue<9A1@w1jGVwuGX+ zOl#;UrI`&ap_u!Z@7IIN&~l`&Z`RAp1Y~ceu@&QgGkP)ynS%dCo9ibVOEd>%hnXwN zKZ?||>_f7X(zt-$THa~T(hHc2Hn$>|$sASQ<8G^Rq0DRZ$YEx-r7;NeWqEYbc*%2A zm9rYT7@4SfdTaYvo@B>_D;U91$7ROb~n$VD!sEJcYICM5|{3m|4;Ax&VTlqJAay=zw`Gg{g;1x|DS#4 zKl+~k%J=!t{`TL0AD@eJul%cu>B$%|`)u_c=E$8jmVcA}%HJ2$>)IHftLOigXL$KP{7>KfQvb8F^ZbVY`TsS$@AolV zWk$jI$7aCtj9I^*zsR|Dp0elsI=`zqHTiXAuAJZGIlMlzJp1ln`7Pgm^0uST&gc5S z>$fyWmcls^^^>3T3?%)UQL>pF?X+jvHUvEjxDBtlN3$_z8{WG|vcv8Qt{*faZNpRY z6z3Y0MtF-d?zT(bFh{U*DrdFo$Bl1|ZuN;qzs79UxnC`LcFzwsHr6v56C0g5x7yj% zo+96jyO|LfXLh7s6*-VvCvXsQFs<&%SD8o1A7l!hzHSL;0d&V28kNf$I^kor<8qL} z_&p={ew40Yf3Aim-H@#e!M66}eqTyAJb49PE3q3{jr^h;{>nLCJ-O;e`^#O`g5h|( zKHOEqhof}?G}~Z2sc!t|ebaZ?4|3n!xuaC9(3Mn?k_S?XA>CVHzf*k&awH7CTK_*XguD8 zT2u5umeB~UYXuthG@|DD(dK9yQk==-@AmX-XGQz_J)ycm>ZMiDOZ%5A23##5e{n@Z zeZGm`yGHuft^hG+@LShTzqEGxrFoXNr?;x-{_0v3nTpS#R{D+dlgdR|nS96RR2TGr z_!L|L;eYf=`OV~3_VWgy%*!6%5R`vuhm5lPwOScx^ZVP?IZqb#>}ywjG~v2RdU{p3 z;}dVjwa-)i_e5-;sy$_Q&}VC(aH7MQ5n~@L26|i12-YJ#LaP9*h-lWZb5E~)58pKEArSlBg_Q1A-BhwVHS8S za!1@AXVFx%!am>*>Y>;t%mxc&EM|u}U_jbpbHZ+vxnMb@+BX-R8|DRdP@EU$2iruP z9~K1LL|hOS2DMLI7#0QfQd|@k2isX(9F_!ay|^SS4O;Z2L7fnnhGju*5SN90gKaGC z8p*`Qbz4gl*T8x{wI1HlGJ z+yB7Om~s%<2-&1KD69q>Bbyeh!@*z^WV7Pna0u8G*}OO;911o=?p_=k4g;GbZS%vx z!@}XgUL_tLjtKUlBf%rXQNf-h9u)_Xyy7uoQ;;Q#o5JQ`%qwmVTY@pKxFu{2#^&PIuq_z# zird1mK~8*ZFxnN54cmiJzqmc@2)&9O;W)4-vUhP@I3DbU>{A>cP5^r&jdo7}PY5Rl zIg5B=I4Q_r#FN6w!Cc$P!7Q72ayTUz^NOd0Q-gd;JT;sa%w~wEh10`O?7et;I3t)9 z5zh!`23e(eW;iRDWfRW|XNQr++2I^;1kyP7oG_YlE;tG~rZ_j82aZOLEzS$)gJY26 ziu1z-;8^7N;(~A?I1V|XxG-D-`E(+fPCm<&k-w79k6Oo=5ba9wMxdfbyoLXEG zE(NC`rxllm%fP9~>BVK?a&Q{b6MHTPFArA)Pe>E52v-JA;1RD3-wmF$BYrnr6+CH2 zyeeEBJW=QBFqd)-I0reexF%c+&PC2It_|0L^N%#TmeB{F7`fvld0J*5RA>0Tq zL@q9F3^##`kV}f2!p-1fq-T!Z9F|dT0hc28Ep7?7g3FN0i(A8O;J(QHird2N;Bw@O z;`VR{xF2$5aYwilT!GxbxHH@Zu0*aX?h1E<`y&r1?hf~WtB?m4_k?@F1CXBRdT&@w zxeq)D>G@#yf%k>`gXe~c_lF09=ZT3Agzp8<856%39t@s8CO#OxA3T>#{C;>ScwU+K zP2Oz~v+A-EB_srX@d3Ooks>AFvaEtIFh&B(3A)8QF#3vyfWOn4UDiafS> zHarJzLvAmg3(tecB6k$ehaZ94k;fH33NL^=kjEDO)UN_{5*IzvH0`wi{RPB z;xEE4gXbgsGI%C}_{;FC;4awWufnf`yI_mI4zC1v!4_W$zX_g+ApR!28r%z8d^Nll zJQG2DExaDw1zUVQyb;_5TYMw@Hn&H^GaMmlkh^-+`APFDrf*eh*%XyuA2* zcniD?c}4M7cpJPNd1di-cn7=!>7Li`fbWENgJ&YV8{DZ}d^h|dxKp|Khwxr-r*iSV z@P2Toa`FA}L2##X@q_STaF25F!|+k?JPYxo@NsaDa`EHv$Ka_J;vd7Gg1eLdDY!4W z_^0sa;J)PIpTl2*JCcik37-UaBo{vke+}+PF8($AEx04O__y%)aCh21wMd$u=t8#%N^vu3g0IH z4$&Rti}+9xVg$dBbno~G##k;sQaoIU<>GG9z2kR_k5S5lk0Kv0%Et=eW5_3p3b7*i zIPwQY#aIb^0{LW7DOLu5fc#-mIaUFmL_SqiiB-WLBA+g*#%kbG$Y+Xbu{!uP^4X$# ztN}iQbeI1c@p(#3@HymWo#8aeL-v$TSraA~_8x?g{=5$!S1wFYx!sw~M`E8}KdUJ4Kt=7JM7| zZqYWj1K&Ypy&|y200rjat=`J2y!-1;`f+Q1m2>ZeX|AJ$lBI*gf`$o`E6u zh&`jHJBdAGujuJcVz1acdd8F3JNAj5@g(+%eWRy4^^KnEB=(K{q9;0u{bGND<*y2{ ze;g1Aqk}jg4vdH(4vd3hInH$w2gSj0H_mku2gf0?Jm)%zL*md_fpeY2p>bHO$hl6# zVkOFOup+W@7#>G}m5^1!h&U3gjI0_)#!+AuWVJ9Vjs~kDtB28X3|I|WBaDe-!RpAG zp+*=Bj*a7Dtxz+Ji?u_ogyZ7)SSQpD;`lfr)(v%nI3Z4q^+MesPK=Xc{ZKE6lj7vq zAk+`y@)8h2lG&Bj~^f)6n3r&MKBhHM? zL$e^xjI-kIp?MHz#eHInuzL{qiL+x_Xc5HOaZYR*%7Qp2&W)`?%OK8;^J44JD$I*} zgw_e?#rbj1utyN*#|3e(uxAh##D%dxWUp{QJP_=O>>Un_2Z6nieZoO;HP{>3H>{2a zgME$3>`yra?1vl>4vB|?{gDI1fN*FW6b2?dG#(ZQhr{CG;2`9XaCkfd9E=Djp3ELyic;!_jdhWeqq2IVy|{Yrr*eZ5$m&1#xX$7srIr zVO?C0To=cNF=2fi7si4ckn7|4FfMF}6T*1#xL8&k5sr&ThE~OKv1L&PwkleJM}#9o zS(%KjJ{(O(CvS5#zD!TvRu7IQ50tmng`>$22NJ?p1-u$${l|?r|tLmfKZ?$L&eo z`P9yrlS|9(@`z5J8||#UEYT_z~-E1(E&zYfbEeTsI84MJkjUcvGA$N^VY>q zh0jx-w?1|*Hjqb<=WU2x3U#4Nu@N1S?QM)*3pGNvcS!73s0FgULu2s#38`W5y$ z`QO6Wzp&5A{}#mog?&!`w>ZlGmVoxTfrWi;P+@PA3oeU;3;UT|aNjtju%F2Vm&c)n z{Y);nUmRB0&*XwD;_$+LHoUNh4Tlk~jB>$MpgnA4Vc(Jq9uP+r_AMFVfpK(U-;xm? z6vq^+v1BsB)ln`u4b+m2Ewo`WLQxwgBNVk^GD1-sCLmAE`d9W`al_^s1IBQgB10F%L=`pJW|yAEid$YvdIx~ze2w!n;aQe6#6~c z;f8P9F!sp znPs=QI>i+7%kJ^u6jR7Ad&EPEma!GsBesmP%vPY0lq^#;o|0vX##6FP(Rk{}6iFSK zVkjBsUh$|DL&-SX#-mg8B=2k&*AO+;0FOqlO|k0Q6s5{OYs7UaN|k-qitAI9D*LP* zH>4<4-dQJZOi}8_6rajI>&9bJd@B2_A2+4=RQA~*Zcg#39JFEFl48;=#b)Hz6qCw9 z8^>)aCf$~z(QPo%CQ%OB3^XQ{gNnwaa!}EjR1PW{lgdHGvbbA3A;tbDq^Mt3x?4Ok zMg6kU3h|^A^~+5w#*Y}i{6?Po1q@YwBU}9vhAO`~2SyXXv$;CA2rwHtYl!D1 zP9tZH@q9SVTd>vhkh0acV5_pp3lfi%v%Ujol|jl`MY*G#Rg^o*Sw*?y#fde_Tt9%n z${J;^qO4KoD#{u!hq;QfMwzQ9YrGQXD#{nHOiWQ0`xjWOOi>mq$`s|YqD)aPE6NnF zg(1EIUW1g&z5>e2uS<;l`ozWMwXecu<>K<%*Wj|R!^P#buft{K;x{E0F1vjLMk@=K z-M$I0m4(Z0e+RF<1^#_&$~xRi?M2w_t>hhUOSuO*?#pmoa}RP{(cFU^S2Xt^#}&;z z+?BEpa@=3Sbj>%&aYgeDa$ND(;bEArd7b-GMn~5BFnrgHj;!}l_^ufpS?^=;T{Ake z-p66R=5-!S86COr6L4QMI&$A9!$T>fBlrDbcsS*9WWY~_M^Y~55g72(;n9@KkpVvw z9!t5L$5IyOF?jH^;qjEkkq18?o=907dGL>d4EP1mT#gJ_G>anx7JowKOa?5PIeRMQ z%;drMhNn}uOdfn+cqZk^4Urktz1`J(Wvlyj9ge<%Dp zWn1OV7l&6;w)K^iXO%r)66DR7fo5Cf&EnThAvSA{oIZdE3IP552Pt;(UV4ZlyhRXOx^;jNTgl|x@2-X^Dd8u%7c z_Iw&>Ci|U~!T|<~ zDQ_*SJ}-PkzIr?OA@ZY?t^YV>>*dxv!XHz%UT%F{_*2T(%dL+Oa_bX7v-NUo(QN%+ zQl4I(eRB9DW$5MEr-Z+z481)2)bKaTVL_fPItKFhH2NXiJ|cWdIWow$MMpwp+oB^O zvTf0kkT230h|GI!_%e-w$h_CVxE%wLd5eyL1f=K~h|F7b^rIY7bo8SfWiyPsT*A#^ z3ygcWgj>Q^7`G!Hvhb}iZbv+1;oD%`$1<8E3qKad?U+(!$||rDSF-R`pkqq1aM3X( zS-9wEk}O^n>Br zy+JwskkB8t=}c)ykDcLA9bV)J^8ku#)t$%TJck#9?Y=Y-*#us^H|TtA=W%;FOW@UlG6v@FtnH>0 zPiJwjsJtGw87#X!xq$Y(=3LLbj?9&S?YP?-&7Ncj+H%*k*z&BJJ&Q8# z?nS1c4R>2`W!?EVWo3@RpBztO^!;SU-jAhrBJ!l@Nc@TM1mub2J9bbj$ZwnwkLSwo zd_1_8D}UEoa2?qcpTIhBJ*?m7vmV?4_xDL|05`(@ebyVnW8nU_%`xC6<`CGfo50P? z9&pahW^fC02-J@);8x}kRDn5f1*;;fz?}DsYTF8MCCpk~TnX+EvsNSb2Uo$Y)xuTa z0q|>e?f~#Wn6)#M4g?Q^U#npUfve%yYSn7+VEDCKbuf4cc?q@W5b#hk6>86+;9=w_ zoZEC5csMxcMhw8d(c9W*Ru1e1cjv9h^ZXLH(Nn&Lp3pj?M&Ukxx*Y zXMy{WPf(}#0cVp>Q2S?tbI2#yYvzD+$tu{F<|dp+USTl#1bf_Ia0plS$06WQc(?s@ zC^!t>ZC@S+4u^N!$A^O>VBhxr5#UJJxAtKqI0_D~B^d>dhJ$NuMuTJE;M$@w;8?O2 z+N-hPIIWoH?B5Tnnx+118 z*e~`at1}ikhTKIz@;T#>W653gC!aGOIgZ@LfHFLtj9arUh6ALtjXirVMNu%icvNWy1J;-t_B|ozVxF=bTWn^ad1otA#u`ijKy}&kcuehAdOdGImY!f|Y zxh>c(wvC>$+zxCX+eJ@VZV%Ro?W5=2*8pph@$jtWnqaM1GkVr?EwFa1MaJeJ*BUj79B z8UDVB+{>TAzrf!&lY99K_zB~^TgbY60{#^i?-|U01^)(%_YCI0fq#d^dj|90!B1iF z+sVCr3Vz0@uV*lS27b<{uV*lS4t_yC#50(`0KX(3;u*|ef?tsjIgxzJS6~spVs^mE z$dkx=6l7ygL7q(3Ban?b6?qC-k4PToG~}t|J<5@XIURW#*^jq^=Rv;>zC%95Q=#7h z-(_^&Go#-H|3FscEV3(q0N*1kayHqO_rUkbikw4s<$dr2vLfe_UHJg~kP-Fs$gz9~ zenf8Me6lMafv=Doxq$4-E8uU)U0g_Z_(pdvnX}J!0EsXvJaxB*) zuY=M5I9yLIvM4WsFNc@NvD}QjiLA)WWLIuM-b_~Hr({=d zMczVI5<@EYb@ zJxiYC8t_`?TRlgfjF8mNF-|Gt=s4t6z{0xf8sLnO46fA95FX0W+8E+tR$TjU$$QZ6G;@+R`P zWKu3CLvk9~l{d+RoCcmw_TzVCLQV(IAn);eG9hPxXNEJ#le~?5i!8^PWJumYzD;)H zEOI07BHtn7aW=V;KOo;F({T>Dk@t{)Ak%R!xsmsg?~&;^FT79o<9u*KIG^0ehsY0@ z5xIff$VbQznGv~>e8|VhkBUuX2tFq7u?gHvp5TvUKQ@C~$QAsF?8g>xE4hL{llRyP zZX-+Z7xEt4z+=f0d_vyiSa3U8g1?gY*beR>>+&};9y`F}!VYpEpCbQGZsj;~AfF*W zCA)GwIgrnhpOIZTfgH#e$j`~KoJjWLOXL^iSWY7Q@fGq*ax5p4^(ewA;Hh9iuH#hj zFffqoI1D@-jAS_u2af>Dk>xl7JQCcE{Kk>sQDAxU8%KdhgB8ec91X4kE0Wn*1Fi)t zk>6Mgt^+HR-&hB(2dj|ZSf6kua(^-*Rl%xcI#waYYUDT$KvpNeaR7KAScCk=f#5-4 zO|T}}joQdsWJM05RtH&|%*bkLb&++*iX2SsP-I;)8;623!FpsfW`eW8`eZX^f%||B z$Y$&V&ITKj$CwSy0UMFWm;=rQ8?D%g>%#Z+(_*ol0_G;liDnS8}`a0b|ge8q5TT`672i43RK4cV2P$OvlPk=@9N zjHK2B*`1uoC~7^CJ;;fSrq&DDlWfQsYQ2%Y$dHVs)(6>}{L46MeUW`qe#VT+P_Bo7 zW=za`^r!SA4`SBDoJjwaCm9gR$~uPvMjVUIAr$6Z^!S4;4g>eMG59rK_3b4|? zV87t}17}&dE~j5$-5%eZ{Q~&T^gdyNiomeOv8;D4Xg`+q&I9eo^48WBKkP(0(l6T@2cf<-1G3rSxO@ z?o!ZxEZyPB|TWyyAsqo%6j()wT`mhRiM^U)_VY` zb(HlU2x=W=y$6BXMOp7^P`fDWJs8w3%6bn0wT`mhL&3wajdKM_i#`@AnQE> z)DOsd^#NnK8dK;20pz~xKs|umcRjcP`!Dz10P0=kz8gWk ztK9b(Q12@D-301g<-VIiy{p`J3%C{UD)-$A>Rsi&+d#dmtoK+@?<(uv4(eTHy*m=> zU-heU-{V33s@(SkP`@hoJrUHe%6(4)^{aB(QFfyOLy-?Kqu7P;>^pfQWw_gv7JMeb|7vOiZViO0^T zwhFm_ipylc7lu_SE|URY6b?vnnGE zFAImHxJ(9oc{nu1WisF^!ePX^R|FaGm7p=N4EVdCF|Q2xD$tl$27EPW%qs)F1~lfC z0bdIm^R7+Nt~~g9>PEZr;2S`rU3u`0;7#F1xbH^f2BO@X5(B;&yd~V681OCNt>Ko$ zfNuqF3%4c)d>d%AD+9hAG}@H`-vJu!%7E_#jdo?gcY$|@yAlJw82*$Ngn(tC|i;TKL*N{XJ5|k~;gMSFhmgK=tfltGh zh(=XG2; z>)_Xk4LkclPA?n&4JfCV4d>YhuO>E}XCJ(l*l?bG@Oomy&O4CP%Z7go%IRgpZ-R1q z+3@c`8NF=y_uyOM_lXU^1)9T<4ZjVV!;lTX1DeB-4ZjPT!;lUC0W^mp8-5QohjCxZ zUdV|*plg;y;3BhUCP50?iD`iT@0m8IlwK1vE1x zC;kL9GbAVeD`;j&PW(5}%#fV;@1U6>Iq|2UnISpxXP}uO+3@F}nIYNm7oeG;r&3Nx zPW%;hb3$_BB0imRLUQ5|pGi3(IdP27rks$RxLkaW3|qM##e67s53244nPTUkUUn?hW2AZ#x6E_FV*UE`^2hG>YiCci?Yu_P5TL!+1 zd?#gUWyY=IyJTovMVWDH&`hn&cn{D_t;~2&&`hn&crVaQt<1O$Xr@+X+!i!bD>H5f znyHl;w+B0rsg)Ub0L_2PjQ0l3f6I(Jg66+v#+^X(-!kLQp!si^aTn11_uo_ITYlV) zx|whJad*(nxBR#V*pvLX{J1A*reA*C3pCR&Kkf~h>6ah(0nPLm@Zr9onSS|kKhR9S z{J1}8reA(M05sDtKOP90>6af50tb`nmmd!X9Yv8J4*`e9AyIxj6dV?ZM(5}|Q@;w* zx%tl2uZnbTzBBc!A)TA=O#SLe=jJ<8zXsB|`Oeg@iFAg(GxcjBouNNA%95S0@A!!< zc|7R&i7a^n==h2Jcp~WdiTrpH==h2JcrxhtiTrp9==h2Jcq%w8I#b`-`Hh03Qu5>J zprcaq;~Ai%Qu5=Oprcaq<5{4iQu5<{Ku4wI$Fo64rR2wRKu4v@;KOr4$E4)P^T7FW zUX<2OWizA1?sggYx6{TsuN9KkfiJLN7nw8+3$Te%ujsgkFB!37k=6o;U-xXj~~z zoDLdq$`hx7#-Z}Wsi5&`dC)P_$&`xV6r}O26>QTJGCqbW5(M@WstYY?S7LTZFwi|E}EQX}`;MD>o48qwDw z+INK1NWU&Dz!6dzfct+9qwYEJd%$UA2A~XNCZ#^ufU8+xLr^w43kEY7l(EdBGyvV5hOsF)>OPbvpqytPiuc{a zl#wd#%?6u-GS%5Ir~aT!X*Q(^*o=FOUBO!CP<97pTyrSi@5d{1x!VGiyUvBN^#)~V zb9sGtun%$`vJC8noClZf0m^UZQCfkrzIl{h@PZ!Pna`8#2Fi8kQ|k`O63fck(!y=f z3N>pAEnlEB6RAx_BPOCtlc-JOxwQi)b2W|HWc1B^#dO{m(8H<78Ihm1lQI20Yi`raXo5gQ( z9l$)wY;d3S>t`e9^N!s>HGctj=YVs#Uda3Bft`>Gsm%rF^4cO^D-YT;7NwrCn7i{~ zMf15{!uuD33%R$1B17uTy`{WX5mvN_+A{7gf)#bs{D#4bPQ`?{SEr%zqK(3<2x`M7+SVe6G zxF7F0AobS+cz0!()BeZ|cx--Prq`Pa;_g?U=qqtg2?I`d_UR%ezYQnVEAlFmY z!L(e5v4P&x2kg!JHc-}pYk0@TWQ{iRzM9n6Bah*g^`Nh9;;%M<8@S$_Y}Mvur8e_g ztzrwf89WBL6_ky+s$(m?xgY3U@~vENf|+U0w(;&dFtg3nj^*8+MZOieo%e4Aw{pFM z*XqK|woyBdd&h##D?gt1YzJK(ay%Ag0JxpkPT+lYL2cxTT<-vPaD5W59|sOZoG7NM!`o)y*6qh8cd`Ys(m+%)&ic7hB5qJ@=U55V|4i4wt zmvLVf=q&Zid94}fob)Te%VB<(Qo9o0H3A&L`>v#13JbiPcYZh7_3tLTeiiS#97cFK zcdzFCSAth?eKkICBzPrP*YMizptIDk1+Re-I!paJ-g7m06?d=0e~tpjAg|{gyMy|N z>yv-Dfp=U3Q@n=j8+q5Y;27kM)NUwlqFfJNk8ij+UEjj1Hx{>0ZUArK?k#xlG4REk zc+aiLhuq5Dn_!JMbA3Cn-wcjL-cC&hIgYE_i3P^NAoVtP@V=JCoxFA{cq`X;QI|)K z=Y4lkZUZN9bvLiI0`)?7Q}zJ$>UZ<*JK&dhQoASlcIUD03Cp|(-+piM^7rDUCQx_& z`@Pie0`KJYHpz3j)~vwa>y_Ga?;r2q`|bTIJ#8oNTA6q5)w@){(rdl-8Sb#DW!Cz; zU#0tg=UprFPL`}gj=U!|vbjo@#_ z&N-)n;;m;VUu|wv?{f%fmd|Y9!Ps}lJJ#T7s)03-Yp`pB zu>OuUuu=%Q7JFU`tifw*iCt=gM!L*jp&i%p_f^0($aP%z2aVL$Q3iqod1XDZOI^@a zmg}k20c-OK>nW2#4U}P^k?sbbz*x|DdIM!V zXw1EVLhhM&j08vWu8rtlMbPz_8~L7Ydly8QQJu={nv`bbtfA&=qibbM5K zBBM=cc6rbdpH2K-MbOw&Kd7(k#53Pa=?)q*Z>Dqrjhi=9I)cX5n|VhM&=_+wr59+F zx|z}k?87H+N%7eh+He8&WB3kRC}hGZGeNW8TPXX0#(Z0N-$KwF^%lxv(5Pz*WhuV1 z0iUrIFVX;Pgk-H2Qvd3!**hDPZKMAOupDw5zquT^neVfWyKTWu+}lR29oUXnjwQxw z3YybC7O&74Y>L!(F9RDRkEOOR{@9poJ7pDU)_Qx2w6+s99Yozc^LEM+pt+8x;nQI56yrKfw5jl-oMNq3Ouc!caL{8^!C2$&Y zIB4_YgWpFx@If&ewL6N7(bZ1hkf-|_9$*VKaNUiuRuBw7vk+P1epcZ}~ zN_DUs_x7O|bVGBEmSrH-!S2X8)M|jn#&ft=9qfUWlhgoZ$+EhhU{CIqIGntB9zCcR zXiO_tsfp$5L(LVbwLtmw0`54%Ge6a3)e9(fL1SQ6sv_krb-{kfMbzqn3z3VsV-GWe zUCiD3pfRURrXI+8W%`@^cnSCIf5xIqsMV*Rv0fRJB`>Ac05phqSC-o}0*wjx#qJFO2Xk*ZuQdVpMK0(5zG$|*c|YoEy78X;rwN)UlU{)(WX*Gm z(_}F~%7wt}u-9MqR)2b9Zt>RUCv+>xf6lJ+u zwv1jq8hHS{Ldy2Tbq2^sX-96U54c+HZy)Eqs>e<}xF6hpO z?(H~-cNFN_9B^)W|6K0OK`Uo-XC8eof|1wM-vS-dLe8hmL(^w*rw3ZH7kXKjn)}Xs zW@QiVbfUpcNXaH(X3no2T)P{@4PoLrdDtD551g zT8Ve)FV*I$ykh`%L~GKC_jIJRKu;_4>Ok)6^Y!NXIj!T~pizQer3yHRSB)?9`+7v} zs5|5j=8hgd+dKCVHL6$!>NSRNU(c^Mcm0JnTi;rZ*Or4-kwbaaxIn+pNH}sB#j_Oj zQ%xz&&<}fsT4JBjJ2as*rQP)iMnC(}liF~%F}mfB_4WiKp%qvSdxG)MO8TN}OKK;* zH#XWI+o7)4Nt#_J=`<@D_!dSytLV++_?w1k?Kpb;SZWQ>{;}ADG1Tg(2(BLQWkxb} zRJ8U6hrnrw!0abyK_80MxGR!yWTF+7j)b`8f7(M7Ojh zTERx>Sm3T}bJW%X4b_$wXrp$nJEcdmq6HeNUF=5bj<#uUw3?04w!o*TrvWs7rM)fC zJ*{b1N;foAYor}*g8r$^YO6j)8{CD`70uH!X<3^lJyi?U=FU9nT3{{Sx0rV{2Nxl= zy3>-jGGm^WsR`EPeM@-VOyCkwYdke+tKLvg(vf23X$kMp8c#{u%3OS2?T9{9Pnx=v zSGB$^&_(rFZDsC0ukVeHRimbro|Lq8BKqe!1ZDh%IYw=?_IYB`R`b18c}EqBtAe!A zEh%Maqe4ld_!Dsi_BSQ*(GJ=_o6kJl=4cN|y=xd%GA z0$jmsd!mgi!IfO=>&IbpwAy=7_C&X|&h^pI13+zVeRS<0a24+`k2em~z8Y7E+G%4C zQ7ayKzdNLsOLco%OkO3Tp~I=`D_ngw5=^Y7Odjc3O#kTYcCDxTm$cBK-!r~3BU?e=lc ziRn%+aJTk+I&|s8Ku?TumwQi$ahH2fgXxWy%49qtrVlzPXYf2CPl)lv7;KE%)DTFWHXgSPV`cX9#^-cHxOW?kKIl z@&t=v^o`tJwvp#p*lM26nOkZUZDU*6cIE)I^E(T18O%;xDO?enTa`wU)@=P>FA; zwepv+t1`8!px)jckE*3#Qk8G2ZS^@ z1j_R}{k=W`e|uBv{?5w(&u{nl`r9j~-&r;N_A2~pf3JH!RZmYK?*Qem_LutG{nf3g z`+qVdxbDlXRL(mdWjQEev7c>&o zmJQ^Id;WxdDBHjO$rfr6jXHNeUr-C`IZay7Z=WxiEv|8hJ^BB}`GTJ0p@%Sz&Gts0 z;m+trp4pdpwvIf(v&TG-Ec>4h=#5@TyVf3U$~$fuN1Fdo?;J7pe4n;x++NgVD*uPQ zvjFp>x*qn9#NBnXyKzr8?!-fIDee>~?uFt6m*NlzF2UX13KX{>34!7+ZE=V1edjXY z{x+Kp8@SQ``r9;a$90Lq5M?PWQR;l&Rx)R zcjr096Xqv1x1f1*LT15`Ww3I7K`~{>sG^+Jl6M+*h&g{<&E~{$tyiDlJ!AoPzg3^# z{pa%wx~JX8<|8W1FQ`lyqQy^QJ-NrtMq^gVkYCU|aUq9n$S}Hw{?f(^%crXBKqjn~%qRV66W<%b>d?&n)PU6Jwj3*S+KX$;YW1HO8G8i`-xC zxe)ix{6uCJ47on@+`!5=&YHN#H7=*WH1fMErK>fP%D9WfjLIb;pV7kdyPLnLd<$0S7nTgoZARl%ajkKWM($Y`A}(9 z$dD{vk=Iiv5!SI;%O^7;eiBQ`bI4T)<$mQegyKNC3ZZQkfK;5sxzm-FR1Y{JYaXSfc< zq0X19G2}B2I8-dDbm=+_8O-v0_2xPYJV(flChn8p2$;@wm~$Gg#=vRhnT*AM#`hEh zDqn@ntIkyq`hnXJ%bLYiJi9pg&!mZBSNEx0jaWBOQ1Poa1Mk!fOBMOg0xb?%SA*Tw zCsy0K@cd`NZfpKCb*a8F->6ioBLA81T#V^E7ki33beznb3vg=u1B+vY3razzFOnheM6LW=~(jj|8 zf$JEN?W2&LvqSd&3aMCS`ej~1BiZ`yee&X;W+Oa#Rr(d4+&5x&XZgD@p9@khXIt*B zjQ0}gmszddKY@yM<{gO*eOKn|b^o}R0(LQu&eV+4Fkhf_P0rA@X7)gNk1jy5lIzn< zgxa^{5Bp`ipes=B#7utXDR#ewEQ;niRxa*N-~D7%-8$J0kY>3faw_I-a8I~T+#|hs z5^>HX=H}<~tt#{QY^`{!;;{*oiQKO|q0g4*TMaq_pQHtMERG6%M!<>6d(AVt(u}!w zM#Y=sxa(XNZpsQMW<=aNmV1}t_*6faZ&ge^nwgQpnQ65ruqX5Ba~iX_a@N(VnO1u< zAL`nD`^GXh-)hLcYSz^T*?g$QasEQ4)sS_yGCwbNG^^?mpu0Ze+>m>@L`S#%=;93Jd40%`OAk0A*@}kQ5nRQxjNsjR6_<5gC?5N~b6%)$)h!5K>fC=Rz zd?qoW^doTf?j@snOJ{uMfE9;jI8YiOw-q>f^Sck_Nu>n7h06SVb@)))AYG6;NcR?w z4_y@jE7lAjR$xN+l{(X^_;BHvP>f+V$3WS|n&QLCm@vc=R|=B{aMkA=Lf8%RBkqo# zKjFhs^b_Vpu0?sd7PF#kHilx1Irpx*o`hMc&FEOJX--*pwp>}ve96I%qbN1I`{mFg z=0mQ@NOQ)R(}FafC#?rGeunlV`7N0AJwV||TR$Y5-Df;+3W9=yNw^L}f&(>`Rp!m<()8?S` z7<9kl@F0@~{ML#6GlBUY&n%ZPZ{t}7%h4)jA1=pQ7)Ps&y*iG)G?rFp_W2l~d%Fv5 z;~b98@VWS)8}sG5cHV;CKFG}K?nm;}YV&(CH_d>}==Wl_ngW~B@6Fsa0XCuEC&Qq9 z7}548zU)is!(2#Nwbb@ycH|J%fAq`dNv_d3Q-c`3E7j^JRx78}1^UhDAV#$M$?FZK zXhjmo4WVdDk|P{S(TXI$IE2WGc7+K zsF<@=LCfUl$1#%YqXN}hm{uxiVgn~%NX3RS-+_KDsE_h36TOe)(sE}#a3$5zufWAD z$kog5$mvw3VpTO!74*xU)R&p@n=`3cWeru%)hjc*Cl;Tdmtwj1s&e&#pLb_&o!P*5 z$gJO5y|=^Wy)C1gWnUF+NUbl6Un=OivN7Kt>NT-DU;piagoR`RX+DpjwEy(qi$ z^@HEb`Q6)^d{ePm_GN`%82FW)-`wfBvr}fV*XQF;d<(lfUpDT|uXpF0Nx!;WpKlHP zLc?zkR^@!Z+ViV9eJpkZ>f>=J-&pGTpofG04+m!a(=_64_)Wn|kzWd|6#4bRiqTGd z8L(ocSILTuuN1Aq)%=3NukTil{>Xn?nMfUf1p2Mr%8_5ztsMF7$O_Red=b;lCS~|3IK$e@^BCt|CZ#zBG>x0}a zT$v9p%D@OAdisUqUj%Hx$c9`erQ86{Zu5vjr7MD%JE^DPsM3Kg zoLbaB(yG!wQhMr-CnK>ox!P1BxtxOshn^EtBJra8%zf9F>kKG5k0Zn{W|xQd@5=!u-EF>v`tjrcr0iY9UHTE_an1F!tMfcN3qKLKxh@&w?6 zZ@z$gIdTW^cKY|yx*cd1fWgEjYEm>FZ~O_-c>M71!yo^C`bPF2AL&KfP-@0G^=UVN z+STU&)uH$$QuAGk3rXc>fE{Ebszleo;Hl zY)>q_=jpel-Hupzb7^;Av@?Fqoue|mp@(y%4W(`L4p$!oe3{y~{A2KU?!Y-Elv1M3 zy~{`^#>#+>zE6KN@IC6rT&GP`%+XHK+e8I;887~qxke*mMh(Z;dpKt_q}>RA@Da2= z#b1APWQ6_E#E<(dgQJNcWmNr9Q4`K?18jrm_FF|}B6y4Pc2P{csS)_FkKihJwbLpB zMiF`FsDH%geiU#dqpuTz;8mgxyvi@%AOgXwL>qX6_9y&bqx+jvpeg^Mb<~v73San` zYbKQX#I5@RU-}>L+W)br1;<-OEhsIc=CoVjhu)Od$HW!*fcO9(aIKWz)yIRrKA!O3 z-Ho}r5&vT=;KtOGBmE!5i@O2!f|wlX1u;3=gR4y7 zzf6oKL>qCwU$9Sz{IY#QM3?EBUE)pF4BRcZS*@N$t~3>(|#1nB2fuBarl63{Ptk7nd3D5P<4^n^SSXpEba zGa9d)voah9UtLC1XsrU>RzguS84ry$!p^kF*gDf9{W7JxM}r%taK4iKxJX%O95i@Z zbSxD3Sgxx?Lo6@Iu*~z<)hQ!6yP`_CDyUgxm-aXNaN$2OF0Kxt7hUnDE%40GZ>v78Er@IW)|>t zMv3_k=P(BTU^r0i$QZ6S78*Pq3VZ?Ze5kt8s(ivApz`hjT0@}0)1wQZ`~w*2PZ<-b zi5Qbn?MvXljHug|PdMUboT6b+{n|jK<6)8U3#I9gK?_&qsL^yDftDMo=P79U z6Tqjl5h?q#obwF4z*CGrNBdc5^sp?_WG$|x%$&keuS(q6zLe*ShH^|g+ym-8l+p`& zj&%j7+^t-l0{MO?;|qqu3`qT7;nz}eqx1ZO_Vd7(sf#&lD6kuKKhAm;PWn|Sm|XWO za4^LjeSzQ1gD3b0bw@^qz#F_odp<>)-jNYw_RKHp#C3|JPVg4pqV`b-#$V@3ufZ7` z8Al%beK@4{jF)guC-{Ia)E{!>gQ7B8()-TTA2IS_Q9I5Y4E>klzsGf6hu*(W-4seV z7*4l8=fTO*hZkg|G3`Oomqi1h<;1$7B|n_Sx&bzi+Hp>EN;7y2;{h4V=k=mm{H8qm zC+B}ultK@QX9-O#hbqhM#`MbJ1dJKX(wSs1roJ`w%lV+xzltHy76EgjZ z+P%7&PSCHA!na7;uE$XtWctVYXbt@)K|Q2dHPySQNi^rCnwim==0@$Jxj9Fp#WCMz zQ=l3fwS{KiRL`T%F!;s!g&pm{R=x_Drw)$fgREMsXa3)LkX}i zJvD(PXzSF;slO{h!`F*;$ZM%Kune7`I=mi~E}4cn{hU^K5Yfiuw(?}(0h z25<)2`qMH^<7sFcja_#jqbH%8K9IO;Ml-*Jaxj`{wfpN))f4PSeh5&l`$d^nT%G1&=>AXS95tjy zdcP33OQwt7h4G!yuc`r8i+TiB@e??%uK6XU<1oJY2XBnA}NY#OlNY$2)NR1RYB2`a5B2`ard?q8p z{DJ2zr|lO|Yi8I%OVMB~J7NtjJi$lmJDz?Xx;J%=-%;j*SytzaA=qzL2WN;ILatoD zvF(d)&N%7cQs!qmyLs5|jIaG6} z>1zCsF==M?;MhvEwF-?%we^fiwIYp4wIU5qjio+3RrfnQRrfnQHFEm!R2}K?^bKZV zc$#U^d3z($;i>WHho|bmzsj`2YFJ;w?)ViNV!yho@C5Ojt71mPf@1VeK(U}0y#&|^ ztS7#0hPL-3pi#w}p_lv+3u!a-u}vxe1R5t@J+II>>A6>yzV><+v?*#F88clC@V`-% zwnSUn0vMq;Z5(}EG&UW>{~Mc%X~(9e;MB3Hcy(+lULBi?OUI_#hQ_9uttrjyPN@`T zY?|4!(lHz#mZ~)$mNw#=!%`!&4@-^7J}g!LIxJOdJ1kWnJS;W#`Y_(@@N`)EC2vL@ z?yyw-?6A~tr~JmzuNmvm_KSjEw2Vs93p+&5j9N+o>Vx~GkXnZt0P91mq|x1Zwium# z3+nEf##s%1jNV<1b+=51-4#7{Ewt&~sJl?t0;-R$mrCF3rBe2Ksb2oAu_Cm}YzeKS z_Gx$iQ~OjZ+&-25woj$J?NelC3`>Wm#wZ_}mPTbjwf;lX&fH%obp4!{N}cO-Z}rj!wCkr0 zQ>k`C+6~f1snom?BMsBWskFW^BaPA~X?uE2D2>ymw40>u(%NaAbTm)a8mpYT_R*Q$ zWK^bgAC+n8M={n08~!LX_9H3nu|R3N7(uT+Hlq==KTq0mozIgxXSD9wSqMPT!^ z1+Ych64)|r1#FeJPKTuBSPh1xgRoZ&Nh!b~*kXpHL$Ur0Nr!P~L(<{eSkg|su_0+@ zheoxB5lCwVs+oKC@NJvg0;wRvzl4V&=bbb0Kw zgVX7JjW;-5fqNaCuE^cK$1mPZ-Uq&yY{}hBh_)nu)*8Sy=zYNW`^i6&e`TX1Y* zv;}1na7%iBq%|411@-3ClYx`5*l$KHByU@~DfQrVlW0@m#^k*koIc9c{*gRNc^UX} z@<{R+BaZ_AMZGooxz>svr~O#+1n_a-KdGMtJ^}oQ`YGU(zz?ba6m8Af3?00gKbQz`6AHi?)fjjqYIN_T*0B9m!q5JCl9M zkhLv2rS{F>w$XO9_n~(z^>)DRqV0j(M>~*@>evkK5ba2ws$(*^W3&_bt9Byy*U^ma zL|&_-X7kF>-H{jor`;u~=bx>NK?o7t8^7JTv zTb>?H)~xdM2=Zl>r$=(d!^o&ro*qhFo}QOnpWKj~M>!YxcY5b14^W>^IWM_@_W8+d z;03_@sV@Z12Hr<~5%5A_r}Vz$V&Fx|CBTc5OM#apCz2iP0CH%Z2)vAuOOwlimnF05 zA4vA86R2mCZ|elIQq5-M0?G{FjOZY8R$Y+6gQA0@^XLf=CQI14)WSoeLxG2K|L0Jb zr)QI)6qsC_oR$1FIXgKAcusOO@LGDuB-cSO43gBO42JiV_-Uqys87!)5)khFg=4@ssqzA z$)Y+iJ&XLQ1G%sA^kmLGDY=-eVJAnY&^|et2|Ojai0oP?N2k)BncV6z@>5+%_N`kf zCzG@46mp2&LOB(9E4`a(od&#x`X*YlfHza$L~CGrBlW=a2J&GIOs^+H*1+^Sa%K%o zk4(-?j!3R0m)5{^PufQ&ds2=99+m8o?46vRoB=!|*(>=A@J!%d)PJG1XR=Q+i{txH z_D=RqPNTOkWuIifV!`U(1vlQHWNjy^;^AbpTrS_9I*lU-{- z`T+U12Bi0sfonjzdvbWPTe4+xXmVJx6>v-7A=F#YIxP7U_j@q#5JvyR-5-+tkt2rz z594=RbM#Ni=CpPP?wlzve(?t7buxQB zMXM~`F4;aQOSeyU0Pc|N2rOl+fBG`N>Yu(uey#rLKe)<^WZmkY&Zq95zCcc{{^>lj zboEa+Np?*(PF7ELN_I|GqZaO*?2@d(m39Q~#Ml~Kcc)}kj_i`G$@m({D)e>%?!vGC zz{r}(TEIUfE7RWuxJj}pa20whQE!^8&C#`zb%1Lp>jKwF-j3#wZR~S0h|MFr)$`O} zP|ScekGuMe);uy@J6d;)p00lBKgrP5FZ~y}x%#F5=J#Wh^^*0IF_aB}W2wh6 zG8WjG-;U#c*GoooWCP#^$%e@&>J5|SI65v_A=xOIo{VH{L*Rz=#xuTLGJ+#30ym-_ z!I6!U35<_VCITlU!x>vKnM8YHG8s52sUP=C>yi8F!|0=^e*6)4)_`_>GGKi`wz0Zo z$m*9ijNc<8S;P2!a*;J;yaD;N>M~xNx?lP&8O`1$6aBknFl)q_4dZXJ{x{_RdN-;? z9DOcjYZUk7KTk<|^4}*Xy?{NF9`vUIds6piq*v0N-c;b!WLnaVdRo$l z@!m;SdeeZ@lI4>wY3H<0(l>>viu>{(`lUk|9g_6rNS~x1kQV21CS_>SpOJpaFnU9i z0kr!k1AzmQ&WsF8I+1feAv0FOwTh|xrX^&gkI9b}(<`N20xY8LNG`3uX<7V3^kY;; z=CY!=jPX)3Z*^q6J$2u-bNqeuL)4jb%E;8!o{^^UcjP^5ORsO*giK-IM@=Z5$s*Py z?i{z^P6j3|l9tr1C@qub^acV4Cgn*pYGHXYC~2LY(UjhxqzPp(uqkyL##<+Cfo+nm zX_vGuux-*VX;0lQDdoJ9q%r3X1`eiQM$IVs#oCe|t1Wjmh`MiDPUb9O-?UFUgiK^@ z$e7iJBSXnh)*9HF{=m3A?voB9msv~lX0_zVFv`%l5!WnB25`Jj+MoPfebV9NK5Icf ztrncokL+E2(!SJv(r)BOYaSPIZ$HLA#9h<&$q(_5)IY@SlMYG5cv12_M>+sIBps9Q z;*Lo%@O$d6aW{V3l`=g3HvTRyPGZiFl5gl01B;VRNf(X}j}yk@Bn2kP^8D9n-T1tamz*yj{K1ui~%chRK9@BJGv<)rw@;>OuWM+%4^z zzR%O9$@}zdr%A2kL&iUd-;3XmYbEbdYA5f;wUau)_o&~A-;L`4>m+rPk2v$g`0ea(NBTTP=CpFzKCDooO$tl;0y879QibUgYhrp7a5r!KSlpD;M3H*kW;Kz zx(j9Jc&B)0>RlPxCEk_1W9!7bk%??=;M(+e_Hy*IumzL)xLYT=9VOYz;bUX1Sp{*63pt8)G- zl+EJ%8MzPGBki8v#d-gT@8aB-;s+SHKYo&X|BM`Lt8nI>9D5mf7xf|hr=IB{@uAd* zQ4Wpo;K9^zdx-V9x599uyx8+=F}mbG!%H+17}Uh_~geBPfT*xAU7~7TXT)0C`ZPZ@yiE+ms6h>&*H2zD5uA#((9R?O6ifl#Fg`Q;{V5!|Hoh)C1$YU^9tK`Y{W{lqEk29;>Y1KJIg|DQ^iJl? z>wwqA*T)xg?!)ofjGqPEpZW=Y^?G~~$FB!oAKwt46Ys~7b0}xW`_euqzKGvF9G}SX z8{$XkJsjW0n|mcbn&&+#K7k`Q#9PrmI^Keec&o>Mr0fCQf_ii6J>nZV>xTGTu6IuS z7{7cJcpLSFTA0G$2Al80zF&31QsSm^g zaw6~m>dUZG+yT6l`a;G|1nMDo8)shxJcW8Y>=gR}x24u^?KZUU`t%*o*nU_q{8m_R zra9ONF5_xXQf|kJa~Z7}TvM;I8Ngey>&yh|>2@ov+t9(AZRi%tt=NKQaNf;~+=2yV z7A<`pX9M*qy9w*b>A=$&KZO4Iz=Nr8WL%#vJ?5U^f9jp22iX(YQ?9_Sb3V2J{Uy&w zFMcNH-GCkCOe{QyGJY84T(s#|a`xlcL9WCuqIahrp~nODD}0k@dkT0r^_$q0?#32$ z7{5B4at`|VtN7((SWm9P7IZixkJ8rnNzXEUOOL}&V+>|JIknqt&HvC^@;2}p>PI+J zKPtW0cI511fjdw?%!r;>`nT=G=rO<@sduLJSKv<6yU;osxHI*xw2lJqLj4B!srSyk z)Nf#sxfhGdt{i=x_8UMw&0Yh(4%CnARp4tt{mIth{`Lm0P5lZZ`V#43_A*c}B|X3N z7u_2xjvlXHV|98K_%=3>uW7xFMQdG-u1DDmYn48-`jqa4B}#8uJzW2S#br%?KLLBh zn!xeY8**$9;0Dy%9KHp%Y}F(%+~t-*J`-h*bqImK2r4~y`$>WZh)3rAE|nb)JJdq zZ(4QH^8XwAOkb{VHjmY?>6-0BUr?cb#RI8@`UC4_D%8_f?@*z>w`0)hJ`wRjj|uau)@ zQ7PK~7)wC&sC(3nx;r}bgwYc8{t233eY`qRO87Rv7Oi4*^tB>mFc~>Quikdlqp?G^ z%b;Gq9q0-5)$K?b0qj6sOlvr>BXuWQ!+^!qA;yMrE`}A2;2yf^$3Z=UR#$Y@da(^h z1K$eRlF?zbga2P^wAyXazz?OM*`}>`V>@ai5F1Och}!6SJ&Fc1u6Jd7YW*2Uqa)Wx zU=Vun_Gs{XGGa7{?$|es@s?0`$3~=wEQ~RAEm~cHDRpgHU4XTy>(Da#du?j{Iy(b9 zV<*xtqzqd}TPzGK^B?qB=}EmZ7L%UnyL-`EDe6tV5}NbgXq5ZVS`qDeA9T!pX{`|H zOEDd&kB~kP%LDaL(t}|ddh-Fm0rcx&KWK}cp*D3LTFr{o$&W$vu6DjI{ia2AInoTP zNZl0gm9$<4n_`z~km{Y<0Lw`ets+=$8e%!2#&&}Z2m1*&94sfqk)t#yYJ%mYK@p5J zwu#O0EFFusT3?pUX|0Mr>@4tmd3qgqvpm%sxIEPh7)=$}8I2jZe;_vEvw>%EY+!l> z7<)4`{NvDc>!r3Ct-gnWEO(YX|=-s^BMIQNh@qPUnHMXf0?wzs`Djwp_W*FT43k- zD*2N7>!dmMpRchIHOD6NbLVcT7?2uU4G z(T_V+H=?J1zf?c{J+Yyzfo^>btPp!r{uuoW3qg#&{SO@30~^2}fNOH>&*=Zx0Il?Z7rCFk z-&fhzFgZ}r)8;t#syh-aj;2YF$QGb_c zX&i{XQ6I`-*np-2r?5VTF*+^klj^zMhn-L#*c6Ll9}4*=xZA$zU%CEX==Zm#{wuA& zpyl71*3sA$wgzrXeH8F$;C9sWu|Ry397+2qwD{XoAA#jyd*Jr;565z_18@iWhha0= z5x67$;aE&|0S?1jG90_f`oImbp$x}HuyfQKi`_R#Z!C7-0-JG`DD+RVp7 z@?d5sna_WJnDQa;A?in{Kg6c=NCrQ|F7y~Z;Ro2d9;X(*pS+i72iYfjg5G=Bm)^s6 z_9V6NU94$OQNNQM%Q?rP+1EyL9@dk6fyZJG@r!_+fjjX$BWUdeJQUski1aXY|Gmg#FE!)kJU2IpZBx{=;o ztVwgRUfo1*F4m-*Xx~hE4x7@=8GH^q*RAw~&tmzyjav8&wy=@d5oSdru_K%g9FZOZ zJcR$~?-J2RMhmmXzbMmz;nV?$AA5k7m7B1?oPbr} zL|QjugE$d*GW88u6ix=7O#gbU45t83p?@9Lg_*#a^smLba4PUr`qyx0rvXo+e+~CF z3;q2_H22qFH@Pnvg(m;1$S-}aj(Vhba1TAwJCi%Gye$$gRE7Tw3l{gL*UGqAWE zk=b6(;OJkmAzcAHn))dE!Xv4VqIER3sVlIP9mDY}uuxr|Tn0Rb`Z!vb0*|FWp4KJ6 zYLjpf-`)u!Lw4c^ON=U04zB#K!Uptvi7)Q~v{t!`;BU z>AghzAHaL5U*%Vi1Mi@ImDXdxSLnTnt>Rwby_`3n_KU##sOR(4_hCgCja^|L@P+6w z>?pIaBb|o5=r5F+z&)w=U}R71Of!>HGP~1EtR}M<`!hwG)G5iyz`dw<$IdbfIE!Oi zY7PVLM!gSboCMsPdS6=I(|zfkgf&X-)_#n2Pxq(SEwhz8iG@V_$fsBWp20%!EUizl zAUuox;8R9E!}{T& ziu_vYHIBcIZD9;ng^z&$jCR3>qUGoyY+;)N{|G#odJ9@JfHSa^ZN|vv*qpYYy(Q%U z>?8*>x+%Xr80*uPjBG{OA3N0kJlCJ-?T=+;7mjPS*#&qAXK$R@T(;({ZrGi=q1D_5 zJ5@JqB5z>@se`@XJuC=yunE+qyc^YKqz?9g53nZG!-DWG@EvR^^=Q3=rQie3sD<_6 z13s4ckbWAE!E%yfmG}@Fi&m9{krW+0UqYqzu}!>(qAGfwsq9v<7x*^nge~AZU@>(&EDjNNg0X1~j5x0??RIe^>?&VJCGoddQA+sT zx0$7-QQQ#A#5YkJ&S{IL-mjS&Fw!s{h1F|qEJkZ%AsdaIXl<-P>rjuxuCxwTrM0l1 zjp4{z*o4+&Yy@Q_7NYfNjpfK6fL*a9jHT5z9foykJ?tdwamF<4GTN%fVr^KCx(k+< zX^ae|48ztkjn5rzqecBHzL{ls$LpahD`$-e*C}o)?rHrvAaVfAY z?vCwiJQkyg)ZHjrmBwQ~>p^QgmZ3=;=}PH_1!yw8E|jiGPtNF)S*5VFG2R86#uVx@ zN@pxqJvrKoqCHCc)gbILQ?R8>;fzu&F;lRw46=`fpqDm+%u>)BE5RhK48T5&PU0#0 zVsGe$MPMq&dSRL98TSBArJfl3UDZU+nG`S2SPx+LxErtsbxCHynZP*{u~aP2_;iXE zkFIf-xEU6(K3I(UU`uO`ov07?p?-`tr8L8;)SU4anVqc(HnD!#g!*x;F*dRO!2a}y zalNisY`kJ4#v5aoYQd8>#2PgqX-H|54CNfGJ{;+su7`zSIqU)JWpFv{1M6~c6M*9x zTNi7>cx)pB`Q-+jH4b~jIJElfaL&3|BQ~JDA!STljHPEFcAkM)TsC5C3|5HI*e*7r zH5wg#hjbmF-%oYotOnR*w9RbH@ljYRMq$DDK5m_~!cNp0yU}-X8?0qNaF3nSAL7nw z8Ss00-!lFkwxYJ!%)SABi#4bnmb0(1J+%Y2V^phD85W%O^ox=oX@7|ws(tb$BVS=B z85xhjp0hFaikaPHN2~>Zz$(x&T^qO-c7q+b)3vZD?8x{|lr^yvbWC@^g0wNe*_p95 zfor0f--TMZ1{&jCsfDXyE7+CRYUt~W`7UWYe!D$(j}F|yyK$5hVF`+`484QVGD_ZK ztO!_yeY-C9voEj$)uDcyqwio7O0bZ=4^v4LF3cZLnBujgI_KdRwEFFHUE~htb~(cqsMZ=(@K6Zbf}KV_RYOSOxpXGx3Mq z!L!uD54e*#j68$A=OgN;<9|{=O__rw=~<3$npsRXOSVAMe+2iwMSMD=`vPZCKhF7206(U_n>#8=?~3PA-$l7QK7;f20iI5M z5B-w#PHbOuvFOa@jC&d58zBC}$=F>wrKbQdr#=%s|6W)__MtwLU+;qz=LLRu2jxyI zCHL~H%P4&P#Mzf)*SUf#TuC_zOUb>QacTTF>Q8wOuK_=yzJ!rWv5wqFeLGgQ7l1Et z#jE(;Nx+k^a$L;OOR!koN9#7uxgGc-^=Dk;wfJhzIuUpxwu_762RQE{%EeeTUgW%M zIC28;1S}7)X7-*7u?anZ-QoexyOz=8fY(qTOMM*Hj2HRkY|gn5o7ju=ALAW9j@{-= zp8W#GXJZRFi?)`Q&9QMELH%dS9$4y*p!Fc>tQTRF9Bc5tS=7(Z^HU=GuD-3u(F(! z*;&rvn#W)@x{m%0*peOuKFD=%q&^?pi#8Z_fGHZi6kVNJXKQEry;^AW^fOY+r!KEK zdOE*Fu4xVtHDi@CiI^d#at;yo1C=w0n5WEqA$5Ri2le(blZaW)j6Et;rx@~ym^;MW zaCs(?n&l8N8mgIU)qXCUXGb&0vxodC>H{lhQ7K`h@>BaB{EEM3`BU0vZ@{Onjh5Lr zpbu58>|6i*4OEvuW$~X~y=djxS0mbmv8L#7)r)qf*Mz4vTby}f7C!H4ffhFVof!Ao zo%g~SS6f^;gN#}4@)>sxXAf(>@C}4DpRzxleV^T(>U&7g=&PaE?=EJQ ztKVPzd0!U$-8Z0z%7QtA7QNqn8`ZCQ-$0oCrMKo6_t^{gyR+|%FTH$8)j#`xe$5x| z_ptKAt}k5eg>PU<)_mb=FWm3TYRxZfzXvSmt{2OhC+k1I-@{I?4$p_3?%sF5n=R{? z?DvH|dm*kXocA!})vfuecs^jc>S$b5Tvy$^SH<&7=h<@%U%2b5&bx0w8fSjAn$x&N zKf8EO-llSXw4bAK0nfV&mK@LL^B$<1lupXNU~agjyXFJ750tJZeBH9z@0Gcl>YlxD z-m6>lQh7bkmn<*de-h9C{_G2rWdfEf#P*BEbxUjBgA`Lp;|g(I;eHPsop?_?A1@=m zuIhdd^u3U>7e0G+a@=o=pI`hnUmc!b^s`sx=c~i>g)<(oTp^WTy8Qg2<+vcrEH19A zI`4~q_8`Sb@q;X%OYVhFz4Uq7h0*sy-sYD*dv&r*P1gKxZQiTf@2>NO=`O0ydsX?p zaLxa>%zM@S9^OEZ-+!6j=C}FmfzlP~ZI%{qQyo8FxaOX!-XnkE(88%@1fbpv8=WBxJ3+H{&&%U%|nX2<1 zc6!xkUlRIWNZAYL-Cdt+Y^u_@LS5z3T=R>sulv8Z-wW6L{|cU8oc&(N+bk}PtE#gK z)U9ykS4ZQjuKBRj3$gt#vBUl^ulb+TT@>;*RqZlW@%*Cob&HGV3#pq}E|+C~3-eyx zvoEfmwh+(PoW?CFegC<6Uv~QWsyn^#4FpOTc-m#R-xn>zF8bN4oA*Kqu254~6Z*dB zc@HvdA(s2)JniDodv&}`P2~5*efGlr9&}cLrwts=lJa$nkLRmd0%o|SE#!P9G!0?|LP{} z_rTQ@N^@21@71mO@YIF7KIo{I{Mnau-WSH#{V(&hzqMyCq;bDZTvy$iFI??~c-}p} zuy4p~zTX$M=9kZQ?ecstXI^Q)51mF?p4d9-V5U;05pzdBfGL!z#OU$6;K`IJ#O^7f zH7WZVdQyhJC(@ooe4pYh%8z(!JlJajP#*}R{*MQ$g&GGmLXQ&p*z7C#v9!k#YsN3Z zjXGm)Xyea}&bZW3nMH9F?a{=T@w=gslu^W((FbA#Wh60XjQT#DGJ-f0&FGocWjL`V zn$jCe8Afajqtg$e3?-gUV|s%rLx{6O^b=rX`sI8B*9h2%{y->GLtsPt1Nid00k8r6 z{(R?OA6TD$KX7zCU_JVM(X!PA)}`NvnX3b=L*F?5M)R*tzZV+zT0rv>^rUUwXKlr7jo@9Ffu}X46>n-9y*8BAyt}FN+EUD^ zYzCfol(xL-DcSp;Ox=N*a~>v9cLX{=6PUG*6lZh-EoW~6^E#eZ2~Y|>j#(?AjAsRm zqg4iUb(p(>YzeeFGiPI2Lt|)lVYbGwwno$H%5071DMr!i#%zt^X-3lO&K!;8DV?t# z6!Tg;Up*;3csI^hFG^3|mh;t{(u=p~eD$I9=IuIPeJOo->&{m{O5bdD8UP#6ACS$L zGuWTmbG`;r%+TR{l~c^q;d~9El(Pz)ufY_vd^Tf2KCcH)Y0W+U8=IzQ0mD6j) zTbK7UQ&PihXStu;bIy%(<-FCUc7OG!<<4?Hx#!$j?kD%0JInp#o=d6SU%hF$zY?H( zE~a*W^`zy_azDA}+*w80N;D#r?H&}@q386ZxDKTzy(q3jui2a8I+WMyLvbB?4}B@F z!`j(hdWYU|xcjgU>+)1S(?FiEVjW5s$|>QE_;!3pgR^%vn6~TCcQ}ON3iRC$rMM1# z=ffzjL+4^Rg(zFu9GUBC_)qgUGMmFu%xDW{*SU4RTLN3sAHxc01#~TpWo5Jmx<a;!pE-2}>bR;R0RB4t8`OT;hYmC4!aoy@wO#QJt^PobFM zs3cqcuKa1Ndv}F9VtJsu#ho%8D7JG4bpuWZy0gN}i5;EMFrUt=bJruAGgm;Ef7d}+ z7tUFjyRdHZl_a)yZMnk2thxHc?9QLFC3ICfTS8ZBSiw?>d}T{L@)a*t$#;U(Cf^}a zA!(93N9vUCDEF2$Ov)8@o3ka>cNe-l-IwmquwR|CQ9tct=WKMg%iZ7Z^L+P9Pjjr` z+~wFpD(u_^3?fbm*hOj}zLBm=%}Z!W`^85AL&*i?m`m;;$7pg5Ii{1F$T48opXM*j zoAVcDv~xDAVW!Kn*$yk9G+PB>Wt4Eu(rm4`Vq81LKdmP3Do`v}SaG)QTzx);xY1P^ zuwq!PV#T)E`fbZwSdMoTR<}6P_3j%KJ4&}IV?}pJc>B(WSW&tau%db7!fq2gI)Bcq z_|QG+&UBAD-|kxRq3giiEIxE^yTje<4YHNffRV7CTxU5xlwyf9#2sP~abv(M;+MKV zVVv5u>tr}cOe9VcKe^(?jsYu*xx|M7tGPSGb7DKOqr1p`B@a?Pe<;;okV}+5luM}0 zCA!C@T*iFVb8d0?L%*)A;1Yice<)A5AeZPI$zv?YB`zs{C{MT`m$)eYP#$AJF0oHW zU&K?+Sl|o;msk`2FyC!8=QrHbmAMY*FzkHi%YBt|9W~`QT$@z`2qYAkW@w#|C=QrF-?x=wK&W?yu%imOj_&L+Wt<$3=Wj`#Of2u4@hyqV#Yy3<%FzW%Fd}eSbS1}zV#&a>1r9RslS4Ah6)01f_rPloX20ar%N67LkSiUO zVYEQu0?m^;NF&6|(m}2H(h7N7>4lUc;5PZ2Mj3UV3f>D;HE@5@R4M&bV4x<`p!UvB z1KydkM8JH39!K;857(8M3-cx&ms{+YVYO~RIRxo@UAO`}WmYzmM`#Xo7AG(!eO5wqzKr-NHVfEwVuoMkIOM>kI^tciub5e` zL~h)SC;54d}zX~~xn#f;a?}v4?tnp#sG~B1k zUP@j;!pOPTMaf^4F=2)LrGyhWX7@;#6*&!ekwse1WK-b)TlUaV053jCUUTj1vdKUZ1)3VfgZU-j}=;2)L37GM5S@{)g*dtDat zm$*8}UsKsT3zxs#$wB@y|FiqMs{B=fU3+AEQ*I{5sICs>uYhR-1r3sXSWRJt1?;WN zAJ$*c1q3N<@#U|=SqmD9UnYNrS(9IJ#|HjoS;=4O;Q|fLH9-Lz1^g7GFy||$szIZ) zSsH&5{c_z!&|T{H5fj2E<)hD1Rw=sWDLs6CbKcaa~j=e<^vXktqig1P-yP{1r4ib-*Uo z%U|*nfm<{lQP3WVBde3Y)IYhejsHImwFHf34XHzg*0-|0*O_vD++#V{v7o-Uvizlvx3U!Gp31dWRrS4rLKbR$ zrJwQ^($Ye$Z;-;=S-IpDD09%UDMRP_UMWLmt#9BqoXN1Wa(*Ll8-Y&`{6^4d$UEd* zhdZlK->c><;PH^_Kp5mN-&K&pa>>iLnZFTWAgj*?&C5{6!`h( z%#$-1&vaq{Y_oY^3G1t}~@UV#D>%3nD(a6cEyU#^%*yk~j*Kpleo6*$^J zDHfExl?rcbL3uUe%&X%i}-&Yf#OIv|j=MtGRmzd1#2})jt z8d|w`=hit4GvxfqEjU;1K<8P$K9|3oXQ{68SD+Au@>gyX3{vx`3}1=0l*OF2k<5lO z8MH}C%I2w1E(?-ZkivrGrPSOa!-6?htX}?7@(NN|ki3EvRw#eDkAwEBvizm(G)P|h zCo7AI;mV=9x%@Smd04poRax><_v%b2FDr#9U-ipoEtkTSx%y=@VfG5;tRQo_8@e(_ z&Sk)fLE3Vrg47%_4?*Tq+H!`v1Lfa?%;kI~%#kzcOjXEV;!tP5ru?Dvn{$ckz5-_$ zR!DXHq0b_gS0`GipLfMd6>@uuD>_)2+#k6Nq&!rJvvLiG7OcP@=60>1&6Tex#EFZq zpU-(5we;Fkay?nV+5w9Pj2^V~(&Aj}CQlVGhVz ztr4&h@7F!oB->|Xm7#9J(@6j8P-0+1dgi(?C&p30BdGsMto|c_=Ci(-oDhct&0>9V zmJj-3GBg}Q`ylFz$ue>gc}2|oeG$1Xb^-3rsPG`_-D&McZjys&nQPn30XqTBzI`Ei zG!rqgZvQ((LRW?&Dnh+nNIenzh{q`eypRkX#-I(BCUE*Ti1Y z3~IB4Ur08Q8T4nBj=LuXDa>W$fz=vY)nHK8BcpTGQws1AzlMMwW1nP9lTPbl`N(D`Bh?*>TJUQcUX{GU61|E~Qlxm2ri0falQf zz>%}b1=RuAj{5AVGe^sSy~)wknbM!kQtcS;!boReAL_2aF60zx!?Cj{XOo?(4XtjB zcLnyP?v~|oYQ>SW$Y9k9*qsscZMCG`ocb&>QuSlB2brPzk$LOPEO%E-T}1w_Gs(bZ z){>NS&jOyw8MSDq-R+v%KpM)VG~S?J7j@)mjMPLJNCH!FIV);r{EJDt{hWP&?AdV}nE zv!d6@g*PjDjVySx$h`Ii$KEHi(#OD$>Agxuyjf&tGuzS!l=sQO_9?B?qE{I|EqaAB zUM_lt{zr^|NLIGbs6QgR+-Ky4dYSQ;s81tD+vkkFNdBhNqWRRPk*V!-vbX(<9BrSI z`R~-oEPszsKSX_M^cZId=TkpM|55S_&L^YbgJhLDHTpZXIaK}*e1J@RGovT6YUkh(G~Pg zj;^6~H8~4Up>-`eAy0`eB@g4t(Pd*IBlyU0m-Ipfze zavk})Zl}Hhczw}H(It$Z6kW_27m{%Ck6kCgl_|FCNGEspJtmo2-^+GkP>*Cq$<)aw=KAj;1|} z_Gx6aG-KqfqVuSa9l8&xAHu)TAo2x%JYhjkB(&g_~&jjdtRUW22opXGgP6M*C%1HuuXiXzs^3`;wcI zER@mq)W=5qGj3kc?P+gIeQb0<(SeK|K-r&6j>kl1eq5h=UFu_^4LL)2Otb-+9Ji&n z5oJR%W3J1X88VNFuBAREGXLbY(Z*SB#*N9uxGh=Dw&gc}AoJw4(I({R+=>imTQRyO zW7kHTGO`KTDA%ODS(d|dvn=c8W{hu24#YJWUyb_OXmiFlBUj@V)PJOGUUUsd%saFS z*$}UZRwX~;a@6vWQbX7E*qgO>r<5xv;_sZW_MN>Iv z3jE>_+R6x5MSjP!GJN358Fy&Dpe~H6aqV1mWmHOiWz?0CE^vl}sJl_R!l9Qku2$#D zNUhG5QFo3i6)T^0rwl5(f+JT(9pPH9hSvNqeK_&faDA=$jeOx{Q3H7R=5T(^8GR^97-`5zgQ5qs z+)IsU%U7$jZG`mD627n%txL(iWUi(M$hmYWMNVjGgkZuFs8r`1dJGwo~adbN)w~+(s zK1S~(chY^p`{>I@`(A=P8#r*eSUG1S$rn*aJe%*O!B6cXp09rPF6uL)mP8rWx8s*O zYB1_j>Twm{ykF+jE#TMF?3xKzEG^w8+fBQIJO0AXci-*EuK5#qWG}FbdvHs3*pAej zQZ@lYm_K$iMm7bCEoLw#4%!XOG=pF5mSLQ|*x_rjcMoLr&%hbf8!%=@*bRUOWY|u8 z@@H_#0bssE!K+7u#r{fbWzJfos8fb@Iz?ijP8m+>1P0rdw)t^8feUvA?!bL?0(Rf$2sLXMUoXis(4m^hEIGJ)7R7pH96*?Ts zbQ0|oDbNAxBf%MJWW*$s!7JjFKue@Ir-5-MAft|Ed;)L+{V}xFqbfZYM+bxHi=#up z+{MueT&)=Tauo0=@Op7Z1B;<}$J3q(Eh~nO%>+t~iX$mfadalMt~fdiT2{;(>jYJm zewBdHR|j^YF3GTCNhH230dMjxHdt~bP#s=Lqzx4!}9_&P@S!T&q}r*${*e(F|Stpgad3$51Bi!NZnR*bYM zl6thE_|3jFq%EZlIK3rDOC#}WX@=cPqjuoWQYb|!uq(8pG*WL@8kPD>BphQalt#_L zMWseYxfNWMf{5mV@d8JiaOKv>OJ&rJsape;{OU2%1c|FL?M9hYSeKD{$XI2_Rt+-=vLQ#> zX8D)vWKvZ-az?+)^_54;knPGi_8HPi8Cj&?W$a^el)sCl@);vvP?sV3dER%(NM+F{ z9Q_#S=xyreNR(!CZbz+rSB4bm*`IRs6J#T0GG)E8NXbs<8MUcvWwKp6U^{-VjMpGi zuB(mwr3`0|>^FgLah0Z-M5rwGPoys8GqYp=6Dc%`%s*W_ijYN>4b7qbC9pQ5KhQ@O z&1SU`GcJ8}O*EwVeXG>50Y$1Qb*xX3YDyjJQKXvEO6{pqQE6>L@q1M@T&1O6$E&Hi zb(N`UN~opC4LL_DEM1NGy{k@5chIt_)slXz(N?$R%9R_EqN^2*C{2J(__bH@zsSA# zA0y87|7dTFxuP`RD<@pbZ_2!;+(T`k*Yr8P2gkfxpz%wGcQC_E{$KpRY4$w+$J+ca zpLtonf8T?174r_X>4bOSb31d+bzRz<1vyJI6QLD0{oE z60%Tpt-3(pabrp&p3T|uc^hYM*x%J+#5df8|LPiW_QUM?=6`?xzrX*bkAHq&|G(oO zG5qiN=Xd-sz5kv5{%_IWWyMzno;Aoxa=U@QRA;0f$#o{zC4VPhTPu^G>LT~aAve!7 zY|W7?TOv)i;8<(MS|ClzkF{ak9Bay*Z5eF|Y)ajhD>X%X*q&qUC^2$pJw`jyi;;$v z>-4E>4>Y%3Cq^S+NhU3Kq*uxjrBZXEm2o5jcBa-YUW$Y&hpp#^deH{7lvL>Ym&~dtgiIp4>-Ept{eVl(y&t^!w|@|1JUQ2h)qv5m-#GH~+5$sGhYq zr87`jyEmm2y+IlG)`!vz=(i4iI9dkO&!i8dUD25qfz$iaE&_I^R=c2lZ=cU6&1I_U^uGW7GL>Iv)MafdQ#GL|Q@LWrEoy0$ zuzU}G^P$A%dsZq|)(*PwWg&YnY%Z6MoLn)dK|Zh0<=6S?d48W$XLsrAQ+}V*|Es!> z|AjsETh=}O{{E#?zn<*<`}?oS`(G9`r4E#;kT+G&EJd%dxNBPq{G+=6n((GdTS`=g z+G(W#xzk1&7u1mdDIcVzK;E&CH`R)fYybWFRX)m*rGKBl*87yF4mO&az0Y6kJ{Nc1 zYa-{!89CoIT}w5&rdL}W*=bpL zyPA8iw6rGraODT(z+jJ1rUX1GhPK#oFOCEm4Ni@Fzjz}7&&(F|X2_CnJc zG@EKZ)pM#bZ4OkQ+cnePcFi=oUHPq%G1XoA#bnn^PudY^WSE|mPQYGVrG&Z@TF{=f zx@DNN8P?I!%HjPX+Lr4fDga^28ws>Rh0vkd)c587hkZW%`I#?$v;v^%|SJbyh} z#tjSpgZc&bpfA4GPp}955N{{V`o59wJb8ECKuvt5jYg42A(+fv=DuyY$6M|t9emsK z=yk!D)+lhncP@{1_se2q7RF{Ni~^VY0*6>|`nvhGam`|5R*eD|VzX5Cl9o*qFhK(+CN{OWbcV_1x4t5&Sr- zkBu4pH$#+<5KZGh6C2an)|=4z?nNC|fKd;^>R424mYT%IG$uoc(30CXg72+(&-JYb zu5kfEgv=02N9gzVg|S(}tc8d=A=+$+VdfqSQ3>?G53w}vHfHX7s~>odU4G5jn1!)f^zSux>QwNeFHi4SWMo5fhIAvWd& z-a{T6b37|IL>SV$x4PJv#)u7(B*s98em*u!z=}qaXwLlVWwCT)vjjXLzVLg5UmhEC z$zrnv5Bv~2y%d@y-O{f(kDzXBOk?%9)AIg2l(aaxQ-5cceZjCwU;Ww>U-`Y4Re zQW2G95^HVYu`!K+UKpn$#Kz1cv{XdMtQ;FNM8ym-N~@31(ieUzkIE9_v4nZkQ_T0C zN5~Aky1YR}R7__wL}dw_Vs)`uq_k}_s#_7EMOnri4sD^&Mvkb6kXaEM)2~uO9EpI_ zD#vC~3JMWgLR6N;iH%tpn?-48BJ)|yOgVqSOd&RAh|S`Bs$J~IN;hVU5p}v`n9oQ#6_Fw;M`$q? zg!r)!Gt`ZF3vpUPJQn#nXDvj-H!eho&63Ay$zw+ZPA|p7Lr-UYn;*iP`2nE*%=7VK zxgV%6%lsn!TIS<9axd@&>iL-;$qSix%M19q+{Ne})Gy!{a|du9^$U30+)hicn|Yb1 z&AiOVW?tqUJP#k}n;5?lI5+bzo}2mU%*AKtdPekCo{MM6wLtxvpU-@Bp3l5?p3gjZ zp2z<~KcD9)&u1P*&*5WqIsHqipTiI7QsA@H&*9y42`&AZpUwQ2p2c7JLfZN*KZ{?; z1wg%*pTXDaeBim%&)^GnF7RyXXYe068+aCQ4qjSk0rl3Jllc+P$vmj$;Kx0S5&e#z z#(V2D;7sbL@$;GqJem4wJZ4S?>U;K7=6m*3=5_WI9$_ai@+9?Bc&!~z>sab1@mf0; z_*d#DGe2kjZ;qy|pYs#=mmLMvckPMHr|pT%*X;>BdJbdcP~hYEogE51nEG*i(+&pC zpne?hpBX^?03XBK??9kle~;m#w?A-S>c{X3+84MF@KHPp_W|xj{V1M^djTJz7Vb%{ zx8Ea~2jL@`f8isU_o1HlyD`2i@L@awcLnZD{V?8wI|KE3ei;0^BT&!9=J*xv0Mx&* zIevxP0k@$R6K@0D8rTe9$gP1}Q8&XEax35#)Z*hUfO-u!#f$KdK)nf@7U>t+6i>-b zfla8J;!(H>t&OOg;Cr|ca0BWlnNOjb(e-KTQ`k83BW#S9;<~igrf!T6<=VhT)Q$0) zT#J?-(Ty@+=tlVHtwCE4MCF{-fchsk%sdtw;=Q;E?UksN=~v3&iqtFMnb!dS!4-h| z5jFq|EDx+t-2k4%SWa^J^}$3_fKrb7;HgQ#ders7XcKA4b=1rFjd~dmUoVqw)D4Vf zT%YQ?VBs-9`HH&W;ZZ;-rjqvvpj>*Lj61KB(Y`tvjjNN-P2^7kfA)Z%GQPeY};4(Erejg}}=?XNGRRTus0+f?Z zpqphtzc!RUl>p_W{Z7&E66K!#e$lTIr5RGS_CUGhDATD$8GVW}U0VdrY0Y>Mb(Cq- ziZabwQIX%(X{+!nGj&@2FLihN`S@j+{7kTj}W*ZS>}JnxeHc46z3{d|HH z6uhRC<&=i8^0(kQL5lJm@3E%m_>F4tDheK4N__eMTAb@Bo$B)!t`@Fgzwmx4 zpOYWWpDx_9|KFId6?YY$I+tt1S1U{NoWeKhcZA+g#XBs#pKvEi)Xt7~RCv!}eyUz= zS)7yKW5pV%dOtNkCx6@FPQ#lHa~WpL=U((V`LpNG>WcDB`kvJBR$M1vQ~sB5&9KrJ zc1~CW;mjquj#tRnxYr5yQ1~CiiVtryoLTrp`I-4wrr{bvXW_Lgp6)+$oqX2A|IP0= zU$d3(C&wecYoDp`x$^6Tx$-*h;fm{o^}gU0eywxzyUllDKC6ZIlb_?W_#FAU%i^4{ zx?Ndf&ISLMZ@NO8<?XSUfBONxlVX*0hd;Hotm5z{#SUn`TJRLE~>tts_(Gk?fB~) zLsWi;RnMu(b$;D*{Pw`z5U_CYB=xNayrt)?PrKkbt_jca`D=cTS8*-4Mto{D(?5S5 z|4Zfj3BN78TDaSAX1Jf4ob&(Kd+#tSitPXYcEi9B28PTKXNDPuoIx@SIf{ZJA|gr5 z8FND2Ro5)$oB(r9Ygh$cU31O>b6zovV&M0BRe5&?1wXjD`|R_3zJJuaLig=^Z+CUo zd7nCUPW%PGew{z|oXU67f2CAfaStnhSNuouUd8_(|5xR6{AB#k-be3h<#Vz}E1q5a z#@~8Q_E)Zb9W7zwsO3}K@N=?vJAOX)A%A)NU-3G>eopp(#Vf=f<>%t>t9%`QpTE*? ziP!X-tXKZczxSNAe~-T;+sl2g;%}(@jqyKwEc-tzU!mem-^t&9PV5)<4}X<&wg0!` zTkL1{q4j-NY|oyb9VgcPzv6erf8{l^-(@e&zV{VJ<1>ioWWObz8T+)~Rr#FQH-7y( z|IKr`a4^INYIpI5w7@&06caK(3R$T`3KJ(cfmyk;DquM@w^JK(CM z-~aF3!|ZRVxK8}8%Fpzd=lt?n{O_G(ANhCJnzKB@H%Ix(C*>Ws9_82#`M>M8i_}Ao zHVDO;-?I-x+XU^XwT{#xQq(#!MmwsAR;QJo){)sb*hU^&J6hfP>>?{$L~7HgEyEud zGu+s9(SqIhXxe7P*i!4ai(L0UjP=FHt!x)*?C@xxFN-MSIcguFH194Ott7A&B;^gAvwm#@xu7Q8p2B3FeKe7!${ZAP|q!H-T z(g$v1Q0vw_z2$;hz3NN1Dd_XAO9YYvQ2W??e9|@p?H~2}|-_*z7Z3|F4OyjAv z1hu_1&Ppp#tII}s=4}mXud9#VLa>OQ+XOGX_*G8q%}w!pTMX*;$>=X_K)pd352ggv zKa~+;Ns|(<@4f$%_)B zR~IK*^ohkun?wu1Hc1J2n?(D-lBATpB+;I*G-*p-nrKznmPj$(L8HQz5i_O-*c0oU zc0{S^32MdIp6E2aK%;&tOp7Ok?~E0ku%?O&p-1U^#EP zk%7uV?JkWNGz`?r(%3@7L9HwM5pie)sAYVAq701$jm>4ep;4gmxCSPJ$Oq!Pd~{|| zGMIc&G8Q|j!O0MEq77j=H6$5IJ|uWNA4=4q@tL8)?|C`VfhJ_ilZjYc4I^66L~vv5 zu!a+V!U#f>u*@1xT#6AyE7}B`tr7T1-y}1VI7OR+ld>pnmX26QO7dsPFtS zL>}4<)VKavA{}iG>S^D&N>f22YZz&13ve11WJX|`25yN>nK7BR1dZBZ+@|T^R@j{x z(`hSkhCc3z`7{I6OTKZTwg&Z;Z=|T1;5JyX89Qnla29rLn-OPf7C1XID`Ui|+29;3 z;HDC9Y7RITo475AH#HZWhn3tkqD##Kx5aMGI8)n##u%7REUEdR5eT*-e$;m0_SoFb zAad09pm7SeCR)@E;Evek%_MphQA3Cguw%w(Qagb=W5G8onN2<`*#(=v*~uL8*~zY0 z`OQh@lFvzY!|rb`QL1(WjUq5FF^YgVk7!iJRS~x(`jydD<`ZXYFK_`Cg+|<30Pc;& zp>enN294QbjIMpaeX&Y3j@Q26e%L1(-)le6$O=aP+8;asOGYDv9RM0f!I)tOf<{#^ zme@hy!Pr0UPSml3!9%c%G!EGz;GtMb?n&gaL&1gEPVPngv4!AaSW_+_!Wa=2@Zf(~ zW^W^ofyM?f*4PoC5d!ulw%DJ*KVzF|l(9d9M`EqHKheX89g`e|{ibomjslOyzVpE3 zAo2r=C~$P`(thEVh$DqxTqNzE#5!+5Ph63^1 zP6Lf+a5ORAP6v%@@R#Hm^1mc!Vgq|jaxD2V$yr#%8u{%k@NDd4k4ugxKQ1{3JKE!u z6UdJz{=qrKs5z1R1fn3EOJtmr$WKg+19VbyGWkh~u^3J!g3tw^F@A_CM7}7w2#Z~! z36UF(=prH+oko6YatT(wrxC^J5^yngzNZuMX)(A2``o zS;V~}HUe=CE+vB1Ipk-D=mzHygX?mlUm0KNTq1N`0UBlLJfeYJ30{Q_^7+IVy9&G- z3*`%v3&}4?jNNo0anh~k}BI2lB3toq1^TkAOyAHe_TjxuN26sJZe1yfsm%9Np zlED%p+T92m%U~%{?`{Hb#&Y^nA`@In^pjh#rM{GC1eX~V1*>Y}pBL#x}TyI6Qv?@4~YCTH^KG1>TLV z_jSY!x*J@E75MeUURee%&n(Lrg=IN-4|d|lXt@Wx7t3*Dx7-W<9b597iPrLW(3l9f z5Uu4t&}an4ZMh#b;(&2m{sBIKW%_MIXn6p95WDo-iPQ2Rs8#VD#A$g5)c*KR;@j)ZThI@nDF>MSQL&GWQVuZq6~-+CJ%*Z z0uLn*lRuQaj1~RE$s^4 z67S&kx~;O^kyNiIuQA;D^aa zL{<1M^HK6o@{f`qh@tS$1#2Kr4@w7;4@w85 zHIb+XP#&1}PirAj_orn*+Apn*MBR^;{%PMd4~e=jE&bAs(mF`g8`07??L&DZ&?tYs z!9Hp4G#|OT7uY-Pl^WU47!SSDo@ss1h!H*09^^e!<45#JyOWEJkf^(X-P3MqV1uH4Oo)4 zN!uV%7lYK(66ENjv=k}2h;ngSn6^cVE~KR>ZJm}OMYpD0a>~^*dlG7c0`tL1~yNdrJaza3&3V+LE0Hvx+z$YHch)AOE&?VrcKhW z$kL6|Zb;FMDK|+QrQMOD8`07@%^)Xt=lOT1o**appg;7Wo+2mrq@VPpUIjV17yYLf z^{U9pz3ErIsplXk_o3JIp5gQ@3Jc30F;h+PF%VB)Os5d}n9tPtZPQ4N69k~P+yQ2{1x&9K zvh)@(ylF7L&dAc!;CEY6?}9A7CH!tW^{&X$)8ThpQSXKcQ^}qyAS9N#o5T)8-ebso`byI7gYN(7kRrM=nfC#!S)CH z!RCw#JAks$tL7tR52VFi@!KI~529rtY;Job?ZLDRg3axKq&LZb;cY)LGLVXkx^{#NbU8#?ztY&HV zWH;E{?y$Qt$kn^U=JudI4s=h9k$=a7?vmLH*?R)$u9*eNUhudD)F&ccFM!YOO?_je z>%HM~`%s^RbiEIJZeQw~g6_-NFWDC!w;#N2GBWml@VNb{PeI1sA0BrA_05p64}ixV zNPTl;>;vI(2T`AjjC~M1?qKTEKz9Wlk{k?!I|N3zC6e|bFt|ghPe;-|6b84D`c_EV z3t@1FBZ1GLY$V1bkifU5Wd_{sPe|Z1Y1ta?_9sfSK=&&B8EJerI1BD}B+~dC(EUtD zA&t)k-QjdJGWa~uJx_l@4&N4ZFO;#C=Y!kA*N&mI9rE@uu(o4iaoZzr9}8gEO)O`xP&1j{2Qr-i;W>nL?XxS6KW=z!uwCn|6JA=|bNZn_^+RlK*?TgfX zCampD>iZ#ep9O0>i~9aZ-Dktv&Zd3Uqaz8I#q80K~)68I9B+7jwVA$u={sV${`G_v=lFttmm{{`9mGML(B)Q>^- zz8t1@IrU>H9|JEl#^Q05kA;_Ag?xTIEyuyju0}pTftKUpWyYC2k(LwSWyYyIi56m@ zB7t8EN4u8#A|&wZ;Aq!TKZWulc-aj|>8DaY1zvU|Qu=AMoC+_y2`T+_T26zP-9+gO zr16_zXE(#v&O{o&8FqFH^|O%1Z-JfNO8p$r7U#J-f4C2+BOk=QS#WohOzWb%9AW%p9QobqL`u=|kPub_N6EbM;d_A6<* z0v7fUUScgKLZPUmiph2(w~KeJxBd6r1a-tVb4>) z8!7#HSlA2HmxIf|7m?)e0mIH+Bzbo6Qok2j{U!L<%hdmlto}0m>s4g<`zZe%=JhJ2 z`;paOg@3Jpk3E2_z5@QWg8GBV>aW4SUZegHvij@ruh*$RjI90!{Ob+sk07hR3IBSN z`lFPMIQKU4{A1vwu&uW#J&xS|Hk|7nIM@@&?eD<3-lhH|a{Ie*uJ@=vh1~ugoa=q+ zPb0U#59j)T`ZLJwAHcajr2Z@t`-gC@kElNnJ_r62iT(xfd3F|mj8y+3_yRkTS0dHF z1ilF8`UI)|Wzg8rpCZ-20vav)Go<=g!B^l}pHW(Y4F4Hy>vP!GYsm1Q!?wPl{yLKU z7qG1_slSo=3JL#B(5Tj5Ctty~zNY?GW>xYvY-<(uw=>@)t6*E-P=6ORD%-coH}I_0 z$+zIQu&?(s-zBSITdS#mkoi9O4z~3j^$#;YB;UifzNh|C=Evj**wzo!|4I2HxYe5E zM|jqc@UE4JlxyHwYp8#cL6A&8p=Bl9DovC0Q(8WOTUANZ^fOvMglzzIrTJ+>3x6T0pVs5=)T3U7a+)+q>!($Sc-H`Im^MgV$7l#v z19RY8NoEKV_|S9+vUf_JWXjW_sVr?+TAo&+ro=rw9hO$5MTxs_Iy}vxMTxsFrD~ae zFt6&MYqI@eWbB=#&OTb0S`AR&X9Hz$pgZ~HbhSWzrOEYb2bs4vW%vJ&g8AhI$v2O7 zWpE|mI7 zJg%JEh!$gkDCah&MR|NOr6xhzZ5rgfDT9n6?ZCeDX zwgv6V=1R3KX;C(xPN`LpZCiux%T=~51l_NzY+D2tBB3kQ7K85TRjO?Ry31FowghzF zuTpI(=ziciNVRQ2*S?f$+Xi{I40L5odA1#>M=Ryo_Mjd{lxI7DdLB`p?HDB4j+B+w zm1H~7(h)gb8MZSmM(wW!P>(dhJHL9?5nKGP}}ik07`9K!#Ov zS7Pl+OAlmrCDvZF^h9RgD@g9jt$l*T+6U=Xk7RoX$z8d%FLJAryK-wkP|011wO^1` z`-AS;R#qJVx{F&`bs*@zZe`U$pgX;lRR@E5w^B+S0=m|!lsXi24OS_&92}Y{4^rwd z(4FMUs>4Bdm@BIe4^rv~(4FT>rXxZ3qAQt>0^OaiWI7sDqE|8<11ixgnT`eB*{)zo3k{Gbj&G#@r>ymAg>hIkRh! zD|e+uHlSR&8!fxS1C%Itr)4*IfD+{%wCtYQGf0$s(jpsBmfR~yk$cfDC%BFJf*?!o z9i+&;Da#C$BKM(1W}pM7T4V-Fkq6QuGf;{=D9Dco z(Jntwems~KS;F4~OHh716q!+97|M?eLA_%rKOP1ygexdN9uDe9L;3LtP|q65kADL7 zwW0j@XHf4O%8W;X!5;@QBfdG17LNjrOs%wdG-ym}rNzI1dh}3QJOB+8cw&$ZPo!P;@B;Odf^2v)^5BcGg%<;RP%2zR zi|j$E@DwCOIfSy|skF!;lnPIyMGmoo(&<4qJOh+NC>x#$${~~u&jRHT%7$kJsqk#j zNYl!L=YaAFCBbt+`Gk_-d7ykkN$`A7KA|Ld0VtnP61)(UPbdjq1j;9r1TO~l-l7b6 z38+68Wxz{<^tTw)+l$iQ5>WpyN`Fg1BU&r{T?*uAwZ?P}aMa7I}uU-gUIdGnDnNr$x4* ztak$~*Jo}FQr?ZU+yKu|%Dagc<5?@^-Av0(@C<~Z^p+ss-9r1#unpzATWPr^^VcBX z{goD(hmzfGwEPv$p=5VEEw^Rv2$J0$wA`M#Ge~xK(sBo!L&@%MwA`7wD@b;C(ek&< z-9fUuJIHi*(|%WGS&-(I(IN{`np;lGvdldhrMY`(Sq}eDn!A^ld*B~RbAPAh-pqX& zCAs@(k%cJ9-A~JXnSW5$KT)H!Vfp~5r=rH_S04l)fRQvw8&g&X`w(d4YIU;@gGRJg zXZr|fq-%A#kAgB1b-YBerv6w)-S6WWwZV^5ehfy^8eQ=dv^)+YDMW|-BrQ+CNQ%%c zKb0v?i@-u!pQbE3Q49S{M!obil%Ix|sIPvOmSgQhr zhs?K-vs3=t^<%2!++cpH?jxN7hYXe8)9tR}pZaed)kQ0_94 z)rR*n+DyEc(OTj?T4XRHr?kjvv@ZD!jd)+MFRh=WJMY5^QXlGH zpi}S73Q}+CUsC=8)MDi;bnrdFo~$T+9c){^rbT|E{mZIg`Lc?3S&r5*-_S10=|bt- zU^}xKG^(~XHQ#~8+1A$Pd(c?i+Ti>Eeh=5tHs?q12N;j`J3j`?oi&tyg!gFOlVP1= z4ZKIIp9F;Vu%b~4<0+w(vc^#Y<7q>w3Tq#2U_8Z?sf+p26VbZxG*-)aPEi>3Wm!?5nukdl^K^^>yH^(EJp%INQnLD!Yq(chbZt}C^t zzc&S4SLy(7D*#3Upt}Dsl zj4of~-GRXsfyLZ48C)^ghPx?)YXiEjB!epfU0ss9m4dD=>E*30=<1UGFUvqzm-HXk z4s>0~^^^9X>q@SlbO2pfa{Z(u=(>{YC!Ijom5j#N8FXFARg^BE>q`13>I#O{C0HA4 zO7zQa@U^DoP3X1V;cErtP3g@&;A_pu3o@=Q>Hnw~=<1Rlk$Qu!F6kqw59sQWd~GAp zbtU;)U(j_W`C32Fb)`c1T7S@WCHdL_&~+vG+Cb2CCHdMQ&=n>5+F;NXCHdMA(6ywt zj0i&m%Gri7Mu>7YSCK?Ho9jpNwGp7JNctTd3A&2p>dGk4RU}teMuV;*xw$_?KD3^APWg;k-c8z6Y(DftNSSEooYS&mc0cF&#v1|&; zsAX!CL067sYEwX0j^t>Yfih}2+UB5)T8=gqlu^skwg6?+a9T8=gYlu^skwgzR?va^|>j9PZK4Jf0Qoy`JgC$j=On+?u^QOnNefHG>? z*<8?dBH7tIP+l!N+ZL2p%gg42@@je6cA&gkUba2xI+46=2T*n`FWV86UCYaM0%h0o zvYkQMwQDcCfU;}XUUmgtA#&|yH&Ax%+RN^sYeRZr+XIwiy8^Q(D93gMW-m~7?F!5S z&{ZKq*m}_W3n<5SW#$-Aj_u0Kv7j8=m6_u}*M0QI zcRVQ5)7aaDe}ZR#@@@SLo(a0*<0{QrpesJ|ud_i}xBTlIP}aRLa~S!;z`EsM z=Ou>))-C@!KRG*urOJ-{Odwc)-C_K2)r29E%UkQvuaVb*a&I};^`I*|a;_UdS9auFH-a*7IagfGxhb%%xSDfw zU|VrD=a#^>ZUy6N&Uxh7)tvL;;Mvuj3t->b)tn1q-`Ulii(uc`)trlA-`UlixP}u~ zbK)9KT+LYm`(6y+b~R@y`I5lHmj)g#%DCj=qKr!hF3PxM;IggzK^eGg>mQ&DT(9XC zJORqXUDbIKl!v>j^Aso#cU9+UP#%6OJnI=y9`4%Cv!LrWuI)Sr%En#Wc^-7V#wW$=XFpv zu1D85K-st}Ja2-o)X1&g0_Eg#tG7Wpx!mda!e_dz+itm*?$ zPA;qZ5R{X<+Vc@8CwH~ypP-!F)t-+**JWJoSqaL_eGk4ABD^OK^eO&sSPM^mnD^e@^)ELDJXAee+#*LT^i8p-V^t_ z)Cb*@;$D|}pj^kjF8QDwNUl^DlpEzG*!;mj;vTtNIEq|Dei9>48z0C>g|*0ypH_uZ zZF1ua8K2EaX)%6b9+I(=u(n2nkeJ(pO3tEtGL)!A_i89}i|*l278l*yp^V-S`Mpg* zcYY|%i|z_$+u@Lr`8ei_{6+1SxkGrA@#|9G?xxs}IWQW+M$x1SgTtralR2QEoVgq-SFJ z;2e%j1nZH{L8=}PP9&cjp88y#d>zVlXq`(M4~|nlr-WqAIZB%H(|MuC%%eV*@|etM za4h+@p{H$2->OM@9_`ywQYIY*FW8p)C}h$RJem3Q#%iFwbUrB;%;k*v9LoVma@Kt6 zBUwYRw{92u?{*xUOnDk@+fmvAR2nZV^nNx8ccTI5ovRn_oOd9f|K-2WBQ*;DF`r&% zuPO@ttSIz6-+?^-m(Q(Mcy6`A6RyQ)n$VI*?*B5fyU*PBNAJG&<|Op*B=mJX-MjzM zcTOA0=KM!{s{gb(|HA&{9!b}ItI?hldUFoHr--uqCvzwznZm+Mc&B1qf`n_f&M|_HyY^y~19xG@7!@74MpfS2YUD;jkik|b7iF;S-xFo9?%xw-u5agV$9rfj4r4pSxKc7$ckzibSa

GFW%d-crw{&7|nRkjb$&Fib#Xu$th@L`8Ej$UG@eg} zUYTJu*^*q8drl`8<(^xSi*nBy;fc=RQ_~ndwxVTg(&mg6j!rW?gLj7NwY!w$o7=Fz!vcnJAIN(aI(T`N3{;|IVm7t(SBwS(Z4 z2lKZ5iPRHx_3%#|KM;O-1V{f&Is|^{`+OwnQ26DaX*r6t5M0Q)M|0#*Pb~;7KkU)b_`rotHVX4Uf@a87E$UA@6-^apX97 zr|XHQbL4nEl1>3nr*;;{7J-Yn@>yZjIg4{o%AC#dQ!?j-vFsea z<EJo!=TSP7bwBMB&*%7QnG2|&4W37SVHmwG>w44fVe8)T=r3I<9ji=xBaj7{{-pbUAEQ+s5lT>oVBtb)0h}SGWe$w(&-e zTmf5kZSf|KUkPgGcr$1818*e1IgIGHaK`oU*PF<1yLMH{1*7D z>x|22y$!sJd^yK%2VHYq&RKtj%ev-x56AC-%R1-W%dr9Aa`L}(nw?f)PxgUjAe%Y)RGfy?;ZL$oaiox2|5dILdMBp>GZJ)kR+kA!*g5w3q9 zjMlZtM>+C$7_DoOk8%7y7_D}Zk8|XH80}-UKS6pB)E4r|Fdsh284po@h}x5!`v4sG z364G;=Gv#jEc-Oy^#~kSOUY+QkAqK9dzRM6z^BQdqwR4xuIrM|)Akq~*LBGkNQ1%W zsJ#$o-4{9IDOm6Gy>YjR=|K=seGH` zFSC~T7A@~me+_(_{9Q`ru-_GY`aO=Xfc+|Ayia-q_WL@Y`+y^_gKzSQ4>|G%_y$+{ zh_<)kz8_NlC+QvV9nSrjBX5IB86Q)67kro6N{+t=4_0dVg!Dc<*pjL1nBT zXuR+%-lC0rqnrM}ovcmW+_#HAxKdhfTX) zDW}Fi1t}M#(-71LMM0wE+KgijSeI-{-ki3EtVK59 z8ZAgoz-H81(%KkoPTq>vF|1CuAa6x!EUS}^`E+ZJH%_q^;Tf3WNfCC<9M&2G>)<>IP8Pt6Ky%WHCRHZ5>#(>_)i6$;)Y-m?`H-f6A_ll_#!<4daXfta1(|AI=p9gYuT)iHv1rwQazeXNc3eg zf$MGpZUT>;!1qi7$8-J!(ipGQ(Q~^C-{X|vJPpNIn0cG3jpQ?efZ8cBTLBGccNx1>bnbZ6= zqIxKQrKko%p|8P!gv-H1}3FpqA;Y^0venXeBshI%$rx<6yYs=|>$X zcO=bWESyQJJbNsCsv|99sEvg~ccLtlo*j7j7+CLY_^x`o+3?gZl+`(kv*5>S0Jq`S zOy~E^AfLcD&EUIcl8@t;W#~=*@(jOB9gx2^;g_iiQjZhkiKgM#R^@l72l97T4Zq5$ zR_cq4ajEV`O^)%a)!i5u+4$A!Zq!iu+j7Hii;=6<-53|S2fa((jd4q~-j5}Mvd!q);H>Wx8liFY3trp>J zGvctiyliY+bvwSD#wJ#y>|5J9yu*cHA^lE$rKsjkt)-}bx|Cd0V_lW!q=qg-sT$A8 zF(vvj*JD~PE$a3XN{$k~+ZnJrsODY$pSnCh;V0Gl<#4^|9WDA`{cYF(t-t3#eZIdw z<-a)=`rrJAey4ZFI}z`S=ft~IGo0zlgL+fXuSIfyxT9umQZ4RTHA=2s*wf<*MqIb3 zL5q9LeM`KO*NE#Du3)Th?c$I5Eq}!SseBFljQ_+r$-Coya0Mp*6YorIlKN)vOdhFr zxHEZtuJU#My?Z+{eA@`F>b&I)R(Wn49=}Mhk z<~?mkiz7M~VB8VB36KV53TZ0}<0V#Nv=3y=%A?epw!$!WVo63@oHHGf>QZkN#?w|D zZ_QZd$mJ~Bk5R)>wI!()<60cu9P3(y5w- zk(x6GI&M1a_F**ZMr%PBg&T#jRVM39>$+9bFd{n-_hK}36vn=eR%c_&j?smMgMS(^ zv!mzWa1IuD+#kIbHs*fBan|#lsU1TdaUFLZk-c&=&{5SfTKU28+OfVl=m_hW?R|1g z_xHB|9c@R15q|{j{rI23dXFP58GoG>hLc8wJLbK0<*pMoBi=fH3?mJvAJnDPnPY|F zKDQ3@Oga6a4#%9s9GSa-&R#`4$2uI#BMsr%dtZx5MLhRBT56NV(Q};F+K`IrC$3aE zzm21(m2#wn)P^4A2=A)R*w8ym=zBG3sX?*_+dK7b=*U%rmfSF3qzRrx0i)y*%tJ9xt7xabiLJQSqgRzPpmWTox;EOS>j7DJT=#N z>T$+sT6~tH!LGEZ%lGNYnSG+8K%bXuKXpMz2A}0fuzPq~-D&T}lXgBeIIWQQd^ zy(;a_DQf(DV*SAZ;fbkTybcZIjo|e`b9o)*Ye_eNdc9JYsb*7c=C#ysN8fpEK)qgF zL+Lh9?^f5KEyS-Ct$#y5dJQdCqdB|_TteoD6?@3Z zucCfG_;+-ESE8qT82kshHc7VVxeCi9@+&y@5O^i|73l9C1@%F71+9;RkD{Hs9Btkc zpnj(=M<4ezsDG);X^qj0pF;0@IqjFBqk9h2ztm;aUjU8Bd>O4Tp+`=53YT)16VO@d zQtH*f7pZAm^&%Q*=bNRp=77!_OL>mDpmVvlSk=%>I|nSGpVR`YlP{rO7hFnhF?}o# zl>IEG*XDzc#*1mK4=&-zCA=LCKu6b0IHM8hIC=@KO~J*qT}-_(=y-fFZ%8w+G5N*R zTY;Bw{370j7NBg#y*;f!dCW!h-9oSh`Gw@IL1(WEd9&Jpt;sK>UWV5G!hnu07f@;o zIyPJoMuH1y?Z6tq1+<*c8`}|d?m3@&XVB5^d|JD)HgG=W^GIDlCHM1qi+X@v$j_tR zhZTkM0y>VLOQ|>L>~$_Zyf4^`{G2e_pA+VSb2v7T7G>>o=(c3~}R0jr89vM#s}xF7k6)b|7TVbxEY&IPQ1 z9l)C53Dge&4`vPU1lIcw2KOh|2J}Ey%oeiZr)}s#;9=B`r*s&o56I&=_9s@@j$qaA zI9Bdl={t)2IO<1%$8*FLKJ8ES`>2mc*YR8rR6bW?b-q+%;v4U{YjhOH0B1z~_d6;$ zrrP2;wmUC+j_q1Oc#iX<{l}l z)(H3AyN`e9aPM=%-S-*zRD2%ZBWI!bf4uMBeV>Q-J=(p=!|b2&c|`4@@<_sU*Y{nr z*6g=9zr|<&d%jEV>s9^6YM~FP&#Xz=xlw(D|3e<+zww{QqW9xB)?>Wb58R*fevBCV zQa*t4{){iqncC9V2N-g&zQ1+(w<@N-ILGm#W=Gdj5v-rj!W7oI2vgav5>LP`FRhLRve8eIj?nN z7H&knGqrA@GhXK~6Y3|S6Z2(fX2cF0?F>2x?#3r}53{-BY!m9veR!khsPeXaM}1YV zFdOzl0&rAT9>DW&7~|W8v)geTA7`{_OEa4}!7<-?LVcmEY5=lfsYKS*RmeLNfh*XSpr9_~tH4&UZt8Z3)(6>CF)G)lW zbwS^=JnCBX$)fT|czCC^A-zmybSStm^u*@$y=K%8r`DVvDK|ctbO>*bY|OE^2|Zfg zWWR1sA1??!_Xt|DR)3BPxtv`9)(GX=)SUYYzydzw9GBtkk!QKzqy_I#)EhbvI{S%g ze`OsxymK-ycd4}G9X)`u+(iF)eFMruT63fo{aB78FA}w@>q%)KX#aNqi)?H^&=H`J z9wrBpkKs9;G>9IiPrdR`Dhgvm5$6_$ex}uy{X_;g2pq(D_QIWmoU=>lmpk)(eA9|~ z>vjXRttuvI5ogaF1KKO?QDZ`n@@?6Lci8@;6=6AVm$sm@!`q|uNXF|}c2*^~0_e5)LFQ_vNFuJrXupz8)(@_l=QN^@J1b_ws_-t=Cj zsuGSZ0Qcf5vfqtC`(BsO>$-$KS;{B&rq}!CmWDUClzIuHP8ZJXOd1D{<1J~+Q8~D8 zbldRuwGE?&_LY+vv3!rpXpz5bqgocE&N51~7|A+uv}1UW+Hq9Y@0-#gyi;0SZ^j7b zo2C8r=HOJ$uD1xAcci5~_pv7E%u^Zo4@t)2ZGyQ_f8YLiGCGk!ZKZo;qb5XSVXU^*$}G;hlX;6Bb2p_ng?cVHnS2WEj>Jlno6%YWoI<`Cqd^z2 z3$@K@tqH1kapk%O*p+-Lt+l{z)Tc7GbOSf1Z3|j!gGvpqgVzF;VYlE3_5i!nHjO+F zbme?YN_9XbQf0tAuqXL+TI+&JGSlf5y}(`^Q)aBg4Ah&_R*ZqY!)%n#Jky8L49>0x zDi_UQ%q_z!X zcE2!7x#L7>b{0vQSovypkgsObK8vza@oe6kfuOrn=1_JOs8_3YN2a!*oM`iJ%@y+eQN9ge9V@5R&Z$ z1G`b{8$P4t*n=mWq0jW^8a+YZ*8btG>>u95{(PbXEpn#;oZlCeLk;9p{dl%A2X}w9 z1qX0+5UDrVo6ig)mGLC|aAYuN_u+YF_~cOjT^mp?F_dFb7A@r&4&K7lhv zFt+JAdSlKU&xoaLGl{dCf#W!il@hf{lqN8Gjpy7=ND~>Y93?074&Wb=&ol)mkx%BB zGUhmHlR0-HqtwQHZVG7=My7;MZXP6}&G}?w%9F`A=h$R$3i(vd*cjZH+7_I@8RLy3 z-851o(0OWFkea4ZZ^($V8J}>U%2Y<3gwMD)Wg4jLv=wL91E-O1#Tio=V>aXL8Jy?- zmFeVL^Qq~KBT7~?IcF=-y>&Aw{Y6J)1Eu4|E=!%~^FpIr41MOmG`& zb2u;VVv(OKgSkh|eQ2}EW$7{sXRdjqS>P-_;ZBx0j1%fl+<#UBREl$_OD%8?pWBu+ zmodW`a6a>dd(o6<=2LgHQR;QfabKFdW#)$~78XYCrX;0Q?99`KKB&gXxl79ibv4d2 z?h|wVP@ChpQOy5z-l!Aijn-joaD*x5?l=$RbF@wv!CHZiRkFvbpw<8__#XVv(AtKl zIxZHF+{;#rV@*izVRICBOfCQmIFj(oo!?7&*HcoT@N_of zzd7f4SNrhY&P(2<-uyRbFvq7}{Hq+w)xtPbjZ%+r54-bUt1~L)lDdWaFFLRK6h!CY zXrbg2=^UP^=!jLDdZ+MwvvRm{d56$LL?s1#m#7?3FN|LH&vx7e$0U1cS?Jqs!M41e z@&eHj*M2TKHp?bN$8X;t(J{U$X+(G*M{9>sK<83NEzubmUpM5Af&IeBDLP{- zP1z&teQFY-Wl|1zTrGo7Q=P7|wf)o{YD*Q+&lMKNT0G*}RsI8Q8z$3x7uJ^ST~q$g z$n=h_>OX!ho};~_U+5ok2cjHR%Z|#@ynQR~VO(3Lcl=sgve$NQZJFMY%N6np$zB`0 z-!9WTPE|D(cfho|K@=bVzY$cz@61!0799*I^-q9a_iO^TMD z74}Hc`bczCbFLDzRz}(yIksgjuCy!7r_X3-s;!mtqIRgxLUk!=pXw~+j2Z1#wPclj zXt5&Vfv)y?<&O*+?-G7>eoRPcnOyqvf(Or2)&PejbF5GYDALn$XaAzK^Zrw|* z-L3O`2cD4cn-;q=WoINuSaow+^d_XNrEi8(TaG(Fw-5ijJ^#HCW#{2&3#1K@wm{y? zcBE#Y_q$zq4nFm!Je77llU86$p1t>@B;1=4?oWNn^*PJCQNlm30}>yUr(Q-X1c?($ zKPaQ@ohhNulu<7Ycc_#$C3EfVyi29r5&X{4tF_8=zj;}>OZI2kzIUlK^xC+}t6s}q z9W@43L&Hn$C(d9A*NQQrowfW#yx#iGteDf{=Y0mweqOiY)A6e7 zI@j~EbLHCKU2(n2=d5c!jasW3{MM)~&2XpuZdc`^4QG`8v_|#!Wow8|m_dfrx zJ+D9Nx&Kku`G5E4*WdR)>OTKb*IC!|T6-jv2WLmK|NJ<%uHW-}#^?3D?>QSdKL1ho z`G4&?f7E^c|Lgzyqwddt@;dQ7_3g;Mp;?KgveXeJmaM$-+n-lpM!VhijN|1yd%j1|+K)QAe`2@2D)} zk2(OoN4b8goP(!<4_wE z*L*Acj*{IrC#k1sMxI?kmj7l~mR)Oh1)v;WC3{w@C#t(r{~)SiC?XftEmZa$rB*L$ z6|$PL5*Yi~%udP9cp~13v@2ekr{KYPDrs{(5AQ_F?xfxD{5*x$P4W6X1uw)q(Ygm7 zj(5UO?~(ZA-GpOXfSZyJWFPndyc6%h@jXd<;E(suoO4WKg!N-69St6h$KFYNW*WE& z`Ih9<@MAnLnG4S4(|eKjWPf>I_K&;UygxXQJ>nZt8i=Rjd7N=9*E|Lf#@kZcFPTri zAEo`-*S#e^pvQ8}E%9|cpH}yJZv*NldLLT!hrAuRd%b6}cUxc5?&h9}PwWYlCz58c z1AY)Y%lq)1gYX{wC%*4Ed=>u*FS{4wQMWh8hJfyqznHd*@G5*T$B!o+hiBk}DV>5} z%Iyuox@=2f(eGVh<8ur*1CPnxe=tgY_IFfzn-6)M@_kK6Z zi}{v|L8GlNrgRDW`-iiKy$8pJgWbt{k`Kdw@A;gugy=lyOJWAVx`{1Rz5!WaIOYp1E zm|QHy??K&kG&}3-rg|!`n~uRpdEHcR;C0i9Je|6HR~e}gn_^NKgl{$hQ@vCr0Vr=!M)H;A2@V-z$F1E){Lw;JG3&wEl^)I$t3~~AP@mCva^*XS($M^Cm#=@J$V-O z($4sAsF|LChv=H=srZJjnVyDM=$h&2L{h5BwNC`~LtPE8AGyT!xsy0QcX7=-iR*J4 zrMrndc^lqh3;3NY@%&IPU5Ph|wv^kEucXuo?8K28sXn7?r04KFYNYyQu7PjVbCYFU z!HDqJ6N6|O>96=5sfrJhDx_*)EIIcFK(hV{Ap57KhH5Z^%Qeta$8fOp~> zDcwi3qZ{#9Tfnz|f`^a>U;})8e1g}G0F=cb@Rg!R6@9DJ#8*oauqIwih^U9Z5o4Fv!%NHe0rT-s@&l!O ze6{?LsSDP{lgS#qx75LdE|K-XJiMNKN^2fin_v1V>64^-YK*4pc$2*aG`?o_RFBNn z)0_Dn89w_devFMJPn>go)!WffWUiJzkUR()^}bsA zQ1S#`j*UA10?8=zPgB!h?MnO~8@>KT($nD69Q&MaF`~K=;6G1{{hpKRkvRuHxKH2} z`AN=u88j08!{l$^(fMKUVd}3_ego9Y^J}1erH zo77g}ljzNW#-)E7A3embr}Py_j7WSHy-mwIq|cLg$wmG#zL%?}ZzZqev*-)_Cs$41 zPV_tcMG|9BR>3#$he;LE2gwVW6|}!V`Z9TuonT)k?gTU5{KtqKDVQ+J>%ln>pUv+k zwZS~3h&((yS0{ax)S^YnKyS|MgHAsH->0=EzMS7r+zp|m_Hhz-jC_<-!W^dIdjG4{`hzcFVoQe|ebtOJN7y%VC$@m&qfvewE~N&ARNJdyY@u&ylZ^ z#2T;D9=N)5q;Yn4zcMY>QvDk3!j%c!wZoT}+f z(l$tT8N5HEnNEw5YSb{hF3<#2^W2`J?SiJbDSH=}v)A$3u0*Ng!E0al-f7R z&B34B%^cNZx*pNpjj3n2TPY33H+Ci+%y)IAtmfZU+Ahd{YZ4=itMea9y)!t3d?4-G zKdbpKr>zq*V>#tvv=2ni`!QLQ45vJdU204D_7SuUXFuB+luu_T<5G5}Ev2@I`nSm< zj(n4x#xBT9*^PE7$HsB~2zHuXPTQ%Z(~$mtOvZ&hV&5jGumkaO_LW`EvHpB(cW?l? zyTiUsjv@axIhM2Po+i6232))zk{Q<1riAgR@PPb@LEqzhxuBM5`_t~em%S)2AkAj4+h1taPJA{v8+#J> zX7D{b3>LPo$HRZc&@HZxhhGdT1s_5SF~KYBwj6fUHY6WU-mpA)rR#i`)EF6qN`wzjM3gB z+J7_*qh$j|zcR+iwb$L+(c-#YW8NxPEIWpg(AB=i;hk^FNZ<(8ndHv;PShM7^y}c- zoZcNAySh;8MyVy(mArcx)m(9G$=l_a=c;5Y-kTnjU9%Kjm2)jqbR_OgDyB#G4ye7L zYoB6V>D`D?-rte6>v82P>p$8t)R9zMA7@|ZU{|^vZ3{q0Vc-1T%$GhvXU(caf2fd% z;w(_e`NUx2Jl}I!wr_iH=3Sq1oPD$Ni!+BZnUdMF$qPwYn0uUc^abRo(vQ@aC*u6o zmV51U(K_dy#NMI=;HsgsnDbg&WCf)IB?fKf8_}xVp!A@Wp!85X$O^TP53*81En;CP zvpq$6G3n3uI`+lU(vi?NXA-e9UQCqRl=I@dGax)+$J74wOGoy#$Nx^WItL65GlcVm z&-r1l5@o)ZeqsemelI7Fklsj?`NTJn`tIQPU5VCvTHCNM0nzki*=SI8sbtyl~WroI&n!HzVQrFxEH{#xXIDx6^q?;`lp?F?#e*BlYNv zJY#ua8p{~r^=sw$J_gBF?MP0VPoK|0R$wPWkSD69>UFB7xx9Z>k)P^Vv>))KcW>R}is`O_ByV zIYlOZi}G81UoISB5Ya0f!*bJsj6k`mnw;EJy-jX9f>}A?vnjHY+#v~4dlKaTB=87% z{^BG%-fA!GNa}d%xa#=3GZ8Vya(`>^ZR0?#duyc5u9?7YGJ)M>0#6}=rW_}*l?>mQ zq>lLW8TTFiqh>>0h8hiZ4bCObD0igQ(*zv4_*6K1ysQ8~0uubEC| zF0Ywt6<#yd`nzW8-o`a>!fTOb zH5BS8E=3~|bs1_d)L9s3C~7X$P^hO+bD?fR4TYMETB-APt<=5nwNhv6T5#lfpf=$@ za@G|{E3(%gDP0cAVSgm8fv=xK$r<=nsWOwUF8AYk&c&@0#?u*XMm_2IHRwq|+wJS5~N!6CBH&v(h zE&M1yz3N|jU3Il;cXtokSaq^dJG&F@*N2!l*K__2nb~~$Tl99b!Re%Lz**#K^u9sg zwiUSiCzd8#la-0r!n~Go9XXraZ5bTxy1>fxK66cAXjj9b?&ci5VAo6UhIy_;i)Aca zyV1=Gmz3zClgA-}rn6xUnpX=P0 z$?AdC{L0F1f}6?HZYSLe%GcB?u7YK+U3e?L#F@Bl< zi?rxZTD`z4K{xOMEieA0M^I~^?m$mFQID{Kqk69XBxp>GBc;yq>*RHGSg+wlwkPGR zmUtL7wUb|iMvChGFRk%#%4(b6RHYC5U!~9;t4cf*{D~KqXYX4O_*A+ zPm?c6@1R3cd!$C`ouG~T9NmgK4>c^02W^uYCN)iJ>GS{{b#+G1QXBQwPueN`?zeqkq$EE&D?U!1xH-q-) zsf@bCFM_sFG*TDQUHQDa=Jx;6N`4-+l6f3$OncN#cR-6-2i>Jw?~drcJ8~>)G}UkF z?K(e+TF&n?uB;6F*E)!vdZSjfR-$IKUsxIG7tT;m_g*Hho#-h!YS>HBr>aYhy49%T zQ`;A{e(z_Ze`U4#C5hU=4>Iau)yArqRa5w3rX@$?nn4@%nJZ~icc@=*J&qS9MM-hc zCa0kK-PY9OszdQlD-dd(^?02dG|pt%eG3{)ArjNj83)UsL~p8GZ2p`bUnrs2O9fUY;T zrC!FpXimu$M(tz=f8r$48qGwRgm4Q_F57O?yUy}p6_gs&e@%QM%IeyO1 zXZIM#>&EZ#`}`GtzrVxZWuK`YT7KJa@E7=7{C2P6FY(*Gy8pp%@LS`5tM*eZ{^#}m z2LHdGjGy!K@t?)(W-TuKKEK;HAl`@g8{*yg_21yHi@z)TORCYbVfP{XFDssizu`Y| zAAW0pSl4fePhoxi;rHAJKl}UpWVY|eU*g_)d(7I;VqN{gzO%mfVqN#)*ZRY{euGar z`%AP*{;j_u+b92X@1}Qb?NK7W5%HVzgnB8}G#*-5=tN`M>-u>`iOW;Et2oSv%WGCNksnPNlw zWc+sfM(kl(DItFIzcWs5$ZuHt&0Y8J+^}=}?AmAkd>mN&==#3vkGal&^S^J%cWuZy z|IPceA>;Oj{hrEW@4DZ$4Y^MA*AwkN*WSk}7hC^sR-=yozJ08&d_^nOxPvwBW{o>o zqb2LwJ6L6NuFB;H&gLpaYt|!NIjal0o7fesI+?Y1v+99+ByH|s)v~n0sy2`H5Up(8 zL7v^sTFiRTXn3moRo&Sd_q2|N=XIf;;aCai-qvWr8|`;1?_I6Dr!~8eHQEEm-K<&` zXZN&fU0m6&Sj*u!PgLwiBKdXJRza;L2me=@gKaXwe z=$Exm_TN=_Ac*^X-3MCPJ~{5qjy}xwOW_lU&qOax*(VlvB>%d7vXKCym9lG}G5(Ib zrL*?Q_QhY?Cr8WVxKCYcW%pFOvpQ>^JO~ZJ`s|a-=|AcXv{H^yZS7TR4~B(4_V3y! zw_&9)8{5`C*@*k7PQy6XjX`x9U8u($){VHwzH8p!M*Q=xLD$ihQiq`H=n(!vhoI}| zz-PPg44ZST6R3~R=9Jolox^`=AO4HJJoVw$GiX10QmPmJSNrfp+$Zd_amCsl!tN9H z*~A_B>PFm&uRf$bSfL?_x{)H_T2-JtY62>5Ux&G_bu?*r`9#J1qp*`48IiyPXJ$_!sQTbE0WhDoX{*v=n{_MJB z(aOxI@)gt@{9m8-e7{|`>mAEVFHz@E@qe@5>zuGQE3EvDULophD&MQ@XT4gM5&hct zsvmU6ueK{{t!nV>jY?o_f?A-l3iN>@8oMBRcB#v;+Vnwng4%M_;{DJ=iXORYF}CY7 zMcbQNU@gw;MvGQnMkmqsMsLwt9prGND_D(OO{{lNn;dlpIrKK8nsla?1LkmkC(8QB zO(=B$J2Jx$5gKjZxW*U*otOBhVOe#yB;` zo-xXdv1yDqW0V>1yQ6#^o~v=%^lG4w1NF(;;5l{~Gs}G~(LaU}V~ma7o4aF_m_Fpa z!hLW|tMGm4J?Rndi}O?CAT2bdk7)DLE!;)-+cc%`7I%4 zMf)N5^R%SD7`w%pRaASgC5NaE-}zY7X2}s!KLSSOaoiNOTvDg+m};z_-)duKk9KS` z4u?Ip!p6+8GFqBN>#}HRR?gEgx{yz;Cb>3dMi8lNV^*75EuQ*to>3loZTi6oN?9AT zXkF&>(#EU~J;|rGejBr~JiV+nllD#RNDV>t`Hjf6G;0^0m_8oXwlRy=W%g$6N}F)U zqm5a#F0=1zV^$EJP>e66b(v4iQJ^_b)TgF(Sqq-NPfhExmh=Fhls0Cq=q>BEF)OD3 z6w#lwF>6C!9L6QrU$ipQn~3Wp&g}j_=U63|dbBj;jzmu^jme!sTXO%LU-g$9eJXIq?X)cr2@Sw=W*{{57iGKJ}mbNU^6o#)*#l6>*v>e55!_RCr2p>~KC=+f#}=&VIr2Jz%9zCY4?H$Fw$da%)s z(pgIM4RGEPeKQ=pMQ4W!PbqEr_l{{5d-b9ZR{gQc>Xe-ugG$ZbwF2&nBcz^)^c?72 zcf`<}u6?jAm$kKTv8bB?r*zkPT@K0}|Ak*~amdhKcv#^~PRS+?Y!c|U!| z%F(`Y%9?s^&F7f%wY&cGOC(o_+^r{Xg3`7;ZFsoz?s@cX>vzbpGg`UIGxShnA@`@gRL-#I@kr7FqCU-k3fpWWFhckA83xR$|`X;>3_qov3$+9&z-XFm{nHs?TO4)-H7j$j5c~Sb}sNe zs_=y7=%Z(*|Jw&zW$$N^dHW7zdASTLGIOOAd$IR9yU(}_ElMf&Q~Q;&iXM#}`|ZE# z0MrO5vDj0cC87qwzN{9Z9l4{9mIuxw$}LfUp$+^m$DcUzIL@p+{y45X3N;OP>F48* z_b!e?j{EBxe||plL?38~);G(M(s9ud(3#ya&yi7dMD%Tn^0Va%4Xw{D zN@+6xD79&Om6hh&alNdRr^Djz%8S11*;v&|C`vF!toDEEA2!OM zHMoz;IF3yfv8o-VqO>ZsjHcE9XMkXc6I6}pU)yjPOaCE$ujf%>M z?%Y^ctZHW|xtgFund6-MG5p?t^+>&oonpI{sf{u5?s5uS7oz3SP94U*# zxBEQgZa#&YoYw^OJ8DvI$PDeXOX$UHao`hez&6x<-ugzC)n)hd>hHKJDN2?4&TAcd zjas4{Qfp9-xPG16&$Vq)t5%DVKpmSpIT@!~H@%{$g{u>0;|7 z>O`b}^Gm2Ept+R0r9?Z>4hu_)IG1D0n3ZF9fcoe?TS--oe9V{S9$h(~UQ(+WjOkg_ zGMa%>tK3F9wlkxB7NydkY2dutvWz4(n+DgBrcHwqNNw_xuIMFQP1H=z3X(J7&YbBb zT`j#_R}9MeiB+C^R?ACUVtqmz*INDh{I>AoN%rk8a+K^rj6<(SvDJQg!Y9B)e3VA3rkW~+be`Z%EqW`K{N%U*Wxk>%3q$9e= z7+G@Yh!PO8U`wrINQ;~MXO7Wbd1mgY?y>dUM0q}Rc4}TK4P8^I*V8UTY2UtBMlV%* zx@Ja~I>DG1+m~aYjPmI46Xt4G=;p@I50##AIMi5;oObobFL!({A}xkeN(t1>rSy*@ z+136v%NY~Wq4_Tvu3Hk8Xf6qrR&p*LP^p7wx>h) z7kX5=bLWyn7)jl>?Luk*KP!!fJHwrK$*-pX)i%c3RZSyl99Ho@w5&l194E6%TCDAf z^BVOFq2=5Odf_;cY8abFJByysS!s-8Lz?1DOaJX^G^Eneexb>Xwz2&xy`^ndud57= zL1-{5ZKt#`zBlv|p`i#3YG|Hfj^ezmqKonpDWV!$H6|5Z3{7s#QG7$+Q@ZGv`1bL2 z;)Si@YKl}bTFKd}EhTlV+F3jcil}7bx{^Jm7E1Zv-i-d!M#R2X7Zp9NN4uD#IEEH6 zB7!2uyjklIXUoCE$umSojh5JB!zO7C$Pl%iqeQU5f~ta z(_%#1BDI}H3^fj7yX=BzBvm9A7%Q32DfjAW-Fh*?PRN$9m(-B(3tQfc3 zx^DZw;Tz=ntlR3LqVl0sziwOk1_`eqQb#q61EGEPtrSwPAmWuPwL^fhdOL;u)N)K! zE9|j)>q>jIZtKXcR&T>Ah@7P68^qPy=i?ise%&@!n~ZuPJ_VLmm{sww)|{)tuL`ro zTXA@F$;CpxUjlyBb1~^hP~PBT!MTEqwd7x7S#YsfMT%9Wmi$Ytd|+8U|Ee&nB^Q(a zN%LA`nU+)bkLv((E;Tx#uWyN2HU8C-bBS+`i8)|a+xQi$ZZ#~6J%FyI1{aWv)nl0) zOFe9GF{R~-F9a8pJEZ)h{9her#yA@Q98mHvS7CCJ{L8iVg5;dS_4H08BN(`z-kBu- z8bYoCnr1ZO(3_|u?aKI5u6HH98&Lk`8hUr2{L2;m9zgk*8qS_T-_zA7ZBFH1%^Z6( z8k&L4ocCcQ7^P}7=Y7j@(U%hKh8zp-lT@CUBhMv8Bqrz6M!}w6($V?kBg&jsGLtA> zSmN12@(apd)T(9&N*9+HwwQd)H`f$OmzI6B6dJe$&S1|hBN_M2zF1CL#^|>PR*;s% zos<@KC9Np2OnaaioUa5rhn6qz4s>Ns?z{(3Ye%IQC7nG=xo0*#({Xu2$`LCUN*(r> zl14}!_40=6T1rpVJWRS?#UoKZayC{kZ-h?Nd6=55+PHEargWst^g`qfV;_k-&c;I0 z2&p3^jgUGjc|(~}Nke=V&y_okCKlYZTJ_TFTgV%gq#@^4D__YQA!)?=x$_(4Y$Xk4 zk65=--jI@Qo4gT{hbypq(6>R^lu9ZZsI*ea`D#>R=H)D4SN=Kv-}eZ~B-Z^y+7Eq4 zNFcF_r|jWZh9qCjKb77?M;sEnyu;S2W?r^n%)i3!!*!5qopB!h;EXtWLs?Mzq-+?H zq7-WmBQ#`cWdS+7d|v4?Bu=GiW$BQZ9UU=ZYL1aD<=uf%A5yk+4{5h@k`h!USxM_F9-+>#;v=rYO8*^a(JIoq zkZ0>H_N97S+ByFT{ajn|r)sN0u~t;A4cUH5R{ctvs8yfxVp!}){3+?{uJ-_^rO31fw*t+gTPp(~$32g7@?|MnthZM2-NZ2Io@=k|;a6>6 zOyF0AS+%uS=~Qbhlb*H2FX>re*|y?W{o1RTCG8XAlTtzHU(G8* ztXW7A>+wrkSi>ysUe)-H+X8;M>KZGsu{xstO3Ss^ZIL&mvMu!+ZOa=kwtge#nW61z zU%wIDOldqc8zHf`rQZ;@YFdu=<&8?e5j+0LD^w@;a5w}B`=eI;qAA?udr$mzbanV9{&pa ztiY*yTnkHv;9~W54qAW39*>HPsikRY;qb!vS9`V%a<1TF!MU`b4b5Q{{kEQeg(UC% zM62Ak`ImhcRz7Oj+vZ=6kgx_;PLy*g$7?aXW&YKkZ9`Z!$iQEl;V}~mBW!Qdb!?;(s{izV6BwvZ7Jo6VzoUN7M1p(7%TNu z#+M`7_sXAQskkanRGwG25PK6tbLZ-t{7kOqSPD$5tSIGSVqNGBmEXlTCHZO%Ub#=Z zoqCH(B{cCU^qbml2ai&gYiUbaZ$+7c+w#8@kELoi_Abx%rX(S+#J>-v8E^vU`@r)i z0QaVBUrKY}J{$rLVU#1A z;+fU?+ClX74B!k(_0`%FPp-l3u9O&xCu_XOu zA4A!3l#T$Zi9HV5unc%CWyg`zldDwgc*>6hs*5ao!9(k>g2}=pk0!>d73Nfv%UFOo=|bT`M_-^D#izGftswG;nv0r=Y*s z9jF)CQ}Fh?CvYssDU3Py`>9>p8SI+MI7-Ml%byAq<7ZMbozdV(n^j($P037p+ugKt zO5B-KV#gfLr%^JEGkwCV`%-t{D!^>|Q=P)R5?e!iH?PFRdE7CX@);cGQ-2qrnurD5 zrA3CCK-X2q1Lt#fA!!zH7WXV9O`sPSP}AANeBfM;i@A3JJ*Nz=rg|sH(h}yeRZxL`gWh<$% z7`T`_cjvBMX>aHId(g8ZfpU{QsM`cw%2BP-3g8OP_N4YQ;4;eg;@;h%X!4Q0OU|-4 zwMLL%$#Ea9?+)CZJN6;%2_;J@TgCNZK)K8+azlZ8a>pvt-q0}p#qUSWeW6dQsI#Wz zJ8Q@_lHZ5AYe=i0Py13=Kl7`hLn-&H1IGpe~*9y(4qaf;{ekB(4Lfg z)^l|oP~Nn@t!07{c`=OL7@2g<(=;m*Fm^&AhO#{N*5 zwbb4~y|vJllzR@NUT>f@>M-gY0z8Q0VbnSZDsnJ&4<~JacF12gk`9Gl$n}ok&R)R7 zI37Wb!=M?5a>tRR!=VcD!K0|x19$|-qbS_~+`!o;xJU*(l-irfZ3J%Q>}Y6r7ofcI zXzuR@Jc{Gd)YId#&pifQ%YkyqW2oH#+{E=`D3$&kP1!MAD}YCG*3@La6JtwGIGUtw zq+D(^NgK#9T#*hK887tk(u|RucLut~YRu+>Hj*dwA@!zBrRc+`(EyZpg`R&{$(L#t zg2vq#NiF>hDg~;gmzEBr7yEE7bsYwjk2R9(R?=j5+NxW2N1r~y-L*G}98pVnS65G6 zbIM5CJf$49ewqc;QmP=Q%~Q@%>!%qdebQ#C6M6SLyX#qwXB+NZwxLk|Y5NQ1sP=+T zt{Za(?FDu$dsZkv@4@*L-m(XIM}<&Xz_B4zQgDn3l_SDiqT_QSEg?;El)7V63pH)v z_Mlbzmr#o9m={W$#UP>dTRaj<;~PmUfP*;>A-BB5#}%}){6t({PRq)9#AvO4mqMYW z3^7MrT+)Xn^pkS7)MhcgF87n>EGlWvLZF!9x0dMxE5asL4VF^8)=>4kq|}x=iw^C)b7J*Uq1g=^|B&NDvJV|p z*zI;irVkxQ?Ba0FGmp_2It?w4>NWM@rKHl-+ghQo-&}`SuQ!YtSIoEC(s9J>$aZ!O z#y$GZ++vQjH62IH{KTuU7v5GKhwDaKy0}(U^QTj362-zwN3ZTs@3En&51mF$$D!_H zY}re#b%-$|i~Sol9b&y+qtbW8E;e=dmG-dO?^eyxq``VEX>b3tl&soQpgp2|C+6is zXf0pO8+y(8rj2<~^`=8}Pa>EyDgD4l0?{EA5D18n0hg-?7 zD|-~%Myu_?K<7vkNkf40@`Z%LGborEyT7Za{Z-DaW{{NL`mQg0p=k z6ZaUa3kdrUC6;mU9>;b;3Oi}Xu;=ooke7lRDJ{u=Ql90$+TdE&G3OeUTur{!vSy8^ z)$^~YUAsG;+E(3qUfJ@$YtO5%Q@vR|KRtji8izDH4(fX#d1w1d9P4S}3BU=QA4E?~ z1Wx4qU}{VON-GYb{2-w6%LdAw$*VU|Zcc!cxprtN=^V=W4oJUh4-O-3KuTRt?r`p3 zk5nto*~tAnBKICb*%73}kxVyGrmVaXnN}I@DAJ)oBX=D|QcB)HjZHjj19Ge}LX?0H zL#~zE9K)ScnIkI~A4~1SnHg`S^f>O>$hyTp3kmC+57za@`16Co`iXABi7=Gi>yWZ=ovJDc-Ui6n9w zHO}SybfA$%&LwvmQAOm;FX8^3iRN)8rN#(5vy2^f2Jj57y_E6U3D}7%FD0EvWRJ7B zb^%X0i})Vra=egq0nth1MK9x?>BI>+m(rJ0``qLrYQF?%{E~|q>z#p}dDg|G^MFPc zxr90w0WaYA3hulBcmd~^a?cE)+QL^-??T{(T)T{NW1L*X@p5pp0r+yRT~6*|;KiI> zLA^`LC?=NyFQM+0lw3g!l1q8oRVAk-771lnlddFA$)%LOs*Id+4bONbu}hRmu7NUi z1-_Dc*KmG0kxee6-m7`mWkfu=g50&-e+7|BjBs)tX%GSNcRHY&b0@~y`313@8J5oN%s>udv0 z<$a|05Od^yt~^M3FOfi;xxJtC0Pq27y`N-s$9GffA<~0H2YC-?50f4$gYoHg4oY93O=b_5t?ciI0-r2Q*&fhq(F(F;O1o_+ic;20ldTV?1#Y z@BjhEY05td{5Z$Y06z_U zoa1M?X9@8=KEc_Oq|XrL!^oshQTqv^a(s#_pW`{70va#mb4VEdiS+SFYCO$TK1uwJ z&v1N(^fZw?KFiZSUrN}YN6KDCT#YBW{soe;O+Q=4`gn@tm&$q2mw4Wj%#|-v_I1)%iL&BM`&rVLfM4SJv!t&P zdF6}L_y+fXk!UMlCihKBjkxj^&c4N+%Yd%ze4FxbCf}jmcj@B7^O4d6F8{{hch0sI!nA8_qk#5(yV*M3OtZvwx|@kf;Z zfOs8^oc);eLn3#4kFuYTenb=wBk=x|WIT@_a`rQ7uK>Cx^>a#$)$t?BenI*f@F$%8 zk|+HT=&b6Or3T@boEy)hkt_d0onMrZK#T?a6V89lox1{E^ZE_-ehM^Z@NX&qHSiZ4 zf5&rv3H&+Nen;--L~b!U$nQzNB~Ht)IQs+X_rzxTHP87YX(iEAe#4bNk^VrGm)~;b z&!j&Bi5W~}m!UlCFQs0CC@<9e3+KNf*30jy@i*@IJ@EIO|DAhQ0=2LF2lf5{`~%ni zN%`M_f9Cj4>is$S7n18R;4q%`FKYe+_!o{z`d4bC>EEc8k|#i0`gfj|rP^ucl&8cl z`3KJ|D9?yyVw{!&(ea;2r_>o@r&Qfar*t?^?3DhCCwHQLPLz{`+6}~0Nq|Wi1!WKP zsK!bmW*bj6+KLfUjJeW4^p%1u-AG-C+%l4!njH_*9iKd$y6)=iHx;!RJE z1GsaqWB_SzqSW-}X#+|9%Q!W?fW4?On7exeM-h*EFu8$1=evzOr4Mm%`cQ8O_w)k} zBRP&Gw_h@rv?dux$=GxpPZlS z{>g;Y`TB&koX=2aJn@mx#sc|Ipix{Wr0bj?an1F-|1Ei5Nj{|d_T_mc`HXqk1wpX6N@Ht67r23A@^Gfm|)wh)AmE=RJZ%dw6 z_U^b;e`P7j*UR=w;j@vuU%8oV-<9W9624M>d-D9XrSz^mACi1X?^hv7E9EQ0cLgfj z-$=S1=scl4dH&{7Zf{GfzaH5;WcZNhTTAlSBY$6C%JVfzK4kmbO1ZsWs#lV~4QX20 z{tcwfCHY&Bzi+9N=auAZQvI8dtXoR*w;@~K)=Hj#ODVBeQoRy*TeAI|kiFkV&9ROcu4gj;oo0M?==Zu*6Ik-j(5v4yaVG^j?$gmFgelyprUVz}uGR zA4JwRl3^v)*UR%t;5DiKVI*rM{?@X6`||w9sr@13Y~^;P`i~=JKgKha6 zwMvF}b)%B%L!MWX|1$NI;-8|nQvLRk=au2>rTUQML#l5n&(}-xZOQOoN7`264;en> z`L-nakl~f*Ycl*`Gkq_dy;&}`O5R*<5)awL=z+j(d(6# z6>3HLl)3_~AM}1ME;!nT!&%izHF3{ipey>$sYU{|wP@nJ5w5P4M!iR4y~V3-Rq|;l z^^Faso>2XGtj`;X(79E?eOi0C>Y-%Z1XTCiiKq4e4(8dND0LU879pJ|ZQ$KqGt#H} zAfW3+qezWF*NH}vh5}tD8b#8-mTPz6`O7sRcXqn^8ssySoemdZ&>%bAHiKfYLk?l+$C9W3E=pN zJu@w>dmUqHrSzAa;4WCg~V(?ZI99u32uojjv;=vIlT{ zg*`yn2E_WY`$+W69IMCfVRcQ=H9W^^mu)`W+0v4RVC=HWEG%+~YC4q)}VW-c1T8+qO+=(IIk&e-ZIs%KP2*^YxZ_6LHp+Nd#f;;qCCzyH*wRVmn3+t;M8=C&Ge)i&3Up-e zKr(ifd)%j#_ZUrOG9yvBLhmqoirInVRPNmYIEmv<)R+jI$UXXo*%53oqLz_c1_LK? zwlmiz(RP!mH=P=jX-hrI%mn`j0+mK)Qfn}9C+f~5Y4Pt4fmx*K^pIFOhuZoVa%aFC zO5Fo6ld@g7HVrt9+HgD}+4{S8 zQ49XC^$)v$qbO+WuNcW!Z0Bn6Ty#%l^H1rZ)Xr z3uw*X9jNvH-Xv}M>#g~lS?gH^o#_Hp=C8No*UG;e>mKd_SWVKVznL`=ZThkQY zOPku+tuRb(C!QI9svg7iu(O!4A#TYXmy|TOhFje!agR)eVd7TcS%qP8<>g%O3DoCK z+gR1R4y)Wd<35_Ua7*5>2dOV`H*mck!&>f_3EXlXD{l4ODsDO7T~$gk;#0pC7}geU z#qJm}W(|~VAkdvM;@kj6wL4{E*UVa4uZCgDR_jRams!JI;#}+fGVZDgd^(U^BY80_ zFsUVO#eNxasKTcMsece@2vDi*VDLn&3LFZ2Qfd>=yed`&wuxIAxaCo+!=|S27G<2B zfsEyt%PGCoe7S4=?_91kNv(o&xdxKHxwR42R&zXXJf&Ts24jF)4|gT$y}OCF=|)o8 z8cnJGqecP6&F&<9IVul^N2#8?_i)CMnueYveQ^&X*NZP1##k6iu6Oy>eSnS>+o3Pe z@nTE%1FB6JOs;>~3&x-e-{$=jzk2}Ry(9JYAS_qVcCt6PEJxAbuwH890nT`PK?CGT zJCUZ+N>Y61z0RfOaMMUT(QfhsThCd7Ja1>xG+Io$uYIlZ%K%Dk$!h=R8f%CL%^|b7bwCtsntBx1Pa#FT#Qnq(e_CQkhNmBNhQThf^ zXE;yUe2nR#%zeNE_{Z2Y;9lTPWov}LpU!0qIMN(r@zu6~83%DHB|Da_kT7ym z&K(m8qb22hXId%+rkqcwjWS@y`3zbv2j=BCvV8`WBShcZdgY$L6Wl*l?VEC}3}A%F zdu+P_v|=aDXLB@?n|eCO)oh^JB}bf4%SXp!#36NeN;5V4mu=X;Y+*HqO_T&)8^yF+ zIl8)+t>JjLB}Py~Z%HF)Co#G&sb7gDgMhYVpR&#SaJ4V3Zaa%xw)9Z0MK9PRV*F4_ z#mL6;JD-1Ci5KoWNd6es{?13*_r369`VOl1y_D<|Dt9ECIDbBV>Ami$_HTH6J#P@1s=RRCzctI*ZSi=F1O+mgKy(l(7dR%t(ylrF%aI1C7>bM2|th?i{<48whk) zXcux3<6|IiD;-hNl@>`I+>6m4sw96^V(th1k_RhitJ9Z5E1mb@9eS57p1e`7=UOoEE5<-IK5bFIK>w(=v)`el zVXOBeDbtF(u9La8;JjRUO36dsK9J<`i;$ zc6XfmHui_T@7qL#AmulyjlHGhrVdO@3dwCK@8?_FlDXrH-w^LWJjT` z7zT7i zI8uz+Zo=6I*w!2H?Y`I?s#vF z#eH}~F{A!H|F>z5ZQGji*n+mKI~rXdaNl0+Xmn*%Po_pda~|YssjH)|q`FobvmxgU z?#dNwlvE=Inx2-VL#|P5+23!(Ky#HtI;WJXtSbFeR&~uJbm^79-_X0e`&s*h@B*tB zhVXOgsN=+@oFS#^3t`Lg1@zRSE_b)YIZAjXHv*cwmG$~xlU4Qb>r6=xIqF1| zxMFq3zH$X8_MnCze|xa~xDajoO|0)X*O}xr;VIm8r^-)-9xGyX%C)I#j#1xlvFhbo zroE?sjLrM4J->-nzvA%{_w6i{Y&pC!Y7AtzrE?kwZ;zD%9 zPjh?yrcO#tl$fGEO3lJVN+yxisHk6O|?3vh}Bw?e1D% zH^xLKuI*Uji+HDpU9~Jz!J=Me|LJ*mD*4_Vd(me`A?d@hcZqi)!;WS&iFx`~a&DoQ zC3`M`cIaP8j+vnMb4Ib2G!nQ!$2FAbRjirg8veN%s1|1(HAVo}a@0@Q2%vT z$rASXZlL5)(g0?e1*Hq2Vg<0^d_S%X0LuCIBiA3?&$%`qxB$A4lT-7gcj}y+-e2@c zZ8R)>4XHbE&Y6-E2gTsD#9e(Ntt9Wbt5GQOn7#uJxnOO1^-F4dMAs~weUOOuUGuC!&W zpvfg=-hpu&H@@aPET`-mlKZT$ru-_>DeUjKs)Tx)do^{gVK26x>8{|)$?TP0PU*Fbh~@N} zd-cb$kLPIMk^Iv*_V*tN)Dz$3+;bxE3Xa!N|5|okEF*Ur`|pnjx)1*{uAj)BlFKN$ zfveX8-BWra@CNpNEG2g{@Fw6Aj^o+Ye+*E6eB-(2IN&k--}rJ*%y@RdTuS~@o;aR# zJh=Wc_O4GLT?D*{o$M1xmjExJ#zgk$ycGCS_UlX}T?o98J0_B(66cef#6O=8T*7e* zJ)rkG^}pIbB~S=0@+XrfftR~bVoVAnQ!J)bt(B1krFUv(6L3O{!BM0|K%-fx znLxEr>V~HSwd7M@tkzi13Ndf&2Sre(?oAp1?8V6IO>Q7idAv7Ib%v__VQAzd|1+Pp{_x>Z>a4fO@P- zYoM;c`I*`TbqLPe)H0}Ba6YH@L7jv1Jhc+)B5Jy!(5v<2UtC4-iMqAg{LERh#bQoxi2!e>GB~{?M7+5c2vlapsni(?5!RVmoD| z=tWy)SlKrAr`mvmpLWLjGU@#9_6tqhGVaR2P&ur!UItd`K~dhGfd>ia^7af2NH|wI z&lu?m=kj@ZJNt8aazd%G>=ppkYR~7WB$1NyedhtSWZQ+K@=O1v?L4BtUoqd9++PjxOar!ym@7kNi>XU0z-pqNu> zH^o5XCU*tO^|TGw!n!lZPF(Y8YQaJe=18BxJ1EWC$uBDZb8-1^&I~&2otLub=?_Z&UGDiJs4q1?T)&hj4)+(M_n(*nKHYhP8$Pf^x6>g1Mbe5Uj6j; zCq1=y`q9#2r9GmjC8?^dKY;d^w%QBZ7W2z-vJ>NGSUFaP(%Vv4`+gYxES=q%G!i(C zGy8sI+3rHuI-N@h9n;R+g~|Zh)CryOI&T-cI#VC>YeiWz>?&Q;P(D-E(B{2$%rEba z8MU*yD)N_YIEMc4J*$|N5mRprW5IcR6;m%})sA&>+8N@OV}3c$4$Dc$jB7w@4u&vN z#0A^GU<_$vuXdra?1d_(o*Zl*BT21F$6|hk#zH#c+|LoG-#hgiVehJBZHww}yNdQz zS&XWYal{x`JZAN-&N!0vD`x+=_B506SZ{yodXFPdN#EIiMAOrjby_((+ls08V(2E~ zOVuf9{km^c6B4z?c?wjQS(dsTecup+Op%t%Y^AW$+D_w0j-lNjhzPK@os0VNsy0xsq`m76s}6#4q*F;*y+28lgpj(xW_0ZB|$sNIB%kYQ?oT=mI9F z8?W}Gv~5=)m2j@7lp2Z>D!_#o|+KxPRw!^D8^Ozr4?c9rBwInT1V`? ztYMb8Hkm71=3lNhs>O~K$Gm*%e}aF>U**R})>E#n?Be9iO2)nD{qVsnCy)I>YO!O@ z%9yZ9hf3$}CUO2%aW1)-{HqpIuRZ=H=c>3^cokMMQhG9)p7N5iRYzkIZ7=>MHr4N{ zj6IZkViecZPl<7A=Qod8S+k2%(i{35eu+!YQp7lUnVQB5%apFftP0CqK@hWCTNTS9 z+SiuxYg_H&c72Y28CS`f&hw91DW3|S75Ei)arJzvBQf>rajM=%E-0PPlZ(j9+Y)nG$u}Y|SFu{E$jh!0IRkJ`&@$$-`svAx zvdN6mt;JkcZm&gN-crnEqb*0|<=vng(qQRFeaz*RCFL;YvT;$`j=8L@rqR39W+-v_ zOm!p9znYN0)MG?^-YTlE76W30kyv8>RYfze={KaY&cBqQHrH~v7cev%G5?azSJniv zmo|3Uw$yJ(okGhI8oki?g=QnP98!t-jG)?{(U^bLW?o8Lj?|cc#V%fXN-eUvJN4@4 zT=Hc3ZcWP}&r-)0+5oi~^)oW{8(mAfJgW_D#^xH2&}@X3BQzV8u0X4lmevf)$Gg!| zu5-BuA=Z0$EjgO2z(&m3opN=tM%A(JR&doAIQH+JWnZhSb+s|!+62m)fcE$V(r9|M zfh)^M%W206luRspIXvAjE%9?Ht*EB4fqIVku|Q>JcW{n}M#?>19q$C}L_O!f;~DwR z5EqlQewa*&yB%EPnOxFfbB%??qF1(CFffJZuDtV@qU@lz5{hf_qk@H=9T&}ze<8C^o zJ<5@wwsa1hWICloON{FR3_H}>^tfEw9V?CyIk~e|wO%th??w*oW7F1TeA`qRCah?* z6ATT4y1LLGNTD6GuCXf_Ip0tl_u}cO>g}G|v!AK3$5ehm9SI^Nq_s;t5lXMp{c6bt0+NNRx8TO>ZZbKW!vmk zv{O^69|6>IrQTjeslliw%CPnJDq@t@7FuM~+pFvWZn@GThB@Lhp!`8EMxB7Jvbx4r z0K0PRPA)Iow_sGLXX(Lttb)6G?MkkzoqC!GduGe}ko0}jn`7VdZfD2c8FM~WIlmh` z#eZ`~&=rp49MgG0SX^tJ>q?#$x}AVp=IR@&01o2VSiY6*TR@q7pI9$)tHWBu3pG`}aJbX4D1-)?@P9;95;_6xg}U){a@LUFARC4Qm!*q5VU z=;}>Bj(%a-pSvpWyZP1HB>Sa)wVttTf4{omt9>`WTKfRs&9BxL!7p{EpzE2f=WX?K zwfZ?+rE%PR_EsMYy?(}4(~hVYF;;W^ekQ-QUON)=wwS{?Z_@&!(u*twA8UF?>Aajn zi8rF4Z+Smcd-JyT^dfQwWn$wPwcg28X&E~#A->UAXT&)eKNx&8DaN_I*lYDcu@ z4UK-K-B%(}YE!RYi`6XU)TU1PEEB3caKHk-)E(nAM)%aqIZCt$N3nal&ePM|F(d zpTn=fHL`pu5T@N+wDpT8C;$>xx<1 z>t>Z+WOI#3y|nKW+Oqg)TQ3sQe`~$S62_VOaP_N;ONl77Ba0bd^()fiX6Qw>UFL78 z5s}VG^PEf8YeZb*bSBVJBO=w5V$Nl3#Y|J{k7}-`y|45lA@e&+ zb|g7tc9d2&AkG5nCI8q%?pRbO9ySwlhR~H)wiT{Vzc9Ui4Zmu8h_?T_bUl7)v94Wu z>>=v?Z~W43eS7QmJF+hA*jx&YSGzA=kNAT%{Cd9pOYCZEzxz%lCQdDJP`cgBoJq`@ zR^se5uI|L>nabU+u?l^Tt3N_@is3h6SKifK_|gIABh$b~zhyVlu8eMFWcAW&!iQ11 zvcxlW*D07klyfZ@+%++j^F5$DLm5l10_{nD4{$KFkn#iR)SmQCBTx>Zo@-nQQ9c6*#*Hzn7J5LH*ii zta?iA>Sd6YGJb9Cvtu$yZSAu?8QC?Hoa*3-kJsF+qk7^bMJsFK{uYI;B zgVf9Qo3DCGS+zC}d8D#4(0@z4q_2*=l0oXFj~BzXK+X`hvr07W>mBR&?S(9&wS;?p zmGL{iZ?7Y^aofJ%vfegM?iPHn+P9}pIW%DEL)_^d9JbzjSgoBFZ~cpzk%Qza^HbX?NWy z_PA9ZW!0prE2&u+Y)uB)vTa;V25Dc$59wa~a);cOY~xr=NJt-YZ|BQ38Q-y{#<4A*JMGE%O89|S?aTP~hr8?bxKQo3$;rE0BXnz> zOYUwRM?h86tLiE{Q!^{`J?W9~{SrHAijtG6sq`M#fI@@Wx$L#jY`V_ojuN$jj>!h< zcKm&|{Lbzb@=dz%L`OnF@=fIL?pu(a`&Qv2-goH6|95-tP2@zrnQ!A;#kUt6-I>(# z+pBlpQv2k*$F{vs)iU*O)v@-e-Z|dZxALD`_i20YQ}tARE7=BHZl5jvSM@$yZo~H8 zXWRO#>WeLnjTiPlo41cGQ;p|pBv<37Bk$9ZI%<~1FZZa`Fspu4cWgYj{I3|v^&>=F zZds@PYKi^OAsp@QL{A}%gTsx^zo*LFySXR-Wj{H|g z>TK$`R*u={^FAHvuWhG4ZR2~#{>v7sI7NML*2YiA-lxK>T7PYM{IvaF9qF%* zz0cP9MMv7FdY>)P%#OX!_GzE$oddsua&FG!wv|3tBe`wDK6B(C4kUPt_MO ze(JeKO&0CQ`?TLa_43B%_*J#iw(yJUed@>j3&*b)mp*T;zp7ERJ@{A0`gB|APuuO& zvH!BxmigCzYx`94n6n;7@{2M5>R20YpZ=)x zxNXI+w%e!ruPyh5wYE$TTaKTK^0c0xRwJit?|9;uPxPS>wQ{k4%?WL{XQM*({07Cw(-5? ze{K1FUO2vQj$aklSMqAhzNqgh-%VX^P2U^+)n1+L(>_PC3OWZrUs_lkSz2BkS=wbB z!P%VT2-0l)f6eFYs8XkXRH;)xs$8WyidEf3l)FB)k-D?-6}E))O|0ZD0qX5+6KN^_ z%QkY=m4jvY7u$oay#$iBrax4exGsZRO?Lk11Eok71R3ck;V)=b_X$ zT7vt8+^e;s)KKk;AFd zhnKO0y#C-^rA|0Mf#dO|7dfqx4x(JU))Vk_)*Yy)xfwuh1b61>TJ3sr+QFWPue2V( zohZ=`N)L5Yf!Y)tNKRYYlkmdU6F7wuBbgjXZZc4tM!nm)0(>&-z6WrA3TG#?qHqA` zqk*n1=nbzoSM~z-;y8v9Z4}mW919%7s(Np(_95-f+S1x`b+?SJi-)~&tiS66&y_a4 zEv;d7qaWw{0{e1wwPOu%4Rr?rjXS#^N7qI62ky^Wuq!1(Z4|VR-501Yzk$?r1zz8O zuB;n{XEo;o$gM8zA0|9!<)F2Lwh%*rS~pB$#YR6dm9MYxXQc(Rey;3Gt(3I-6}P=x zYhcHLcWWi==D9gJJr8Tn_ z2ihyRYcG7PI}Wq}*JoFE#)=eF>u9aOD?ezVEw*n8l62kv=tOefX1nX_Nj$g3jqCu#Lw0X+>``vtAF^wQ zuF~tlCRPx&#NGDw`D$feyYClkUr<}?^IF1Jd;jaLVB8DP)(+*caj&<3scdkELYHg1 z{`Fnj+R}YXdz0Il86NT(=M38WFw2ReJHM<^jMF z-_rV4tK0El+~$!x!v3YU_uoBo`Zjh2zZSDY8{Alv4@=zGr|jx|VD9#%58a?(QY?3o z7};k4P@3lZ4+IY6+=yOAU~>0`oWqz*?!M3#wF{Kpx7Sj&0h+Hxfp&168Ml6ie4rC_ zUh92nzkVXMJ(l+CqcQfGNT+-7k9tY;pQX%cNt2C6B`wv%p;3eMYdEN+sIJuaUe32jR~5y}Z|%YwI-6S{*&j_2+f z+fw^IB`bNIyhcgP7WK`PS>1!=J{{l5)^-<UCTbwKS;uxiw)gK;$Q3$%Q<((r2bEQa=hr*N>7dAoug6Dk9qkV@7Fu1{T{I% zjQ*f+Q+=Hp6+%C%dQ{b`slH8(9-&uLeVh6;qe|#8-k#R0sl6|*+xPnT*UPD1P4#VR z)C#?t>f6*&Z8Qrl&m7fyI5nD@JE-d4ZCk##`ckpNcN0J2t9$YVexu)|e^kHG*bIJ` z-&lQ}Ut4{V-)IC1zssjNw*4Z%(TEj(mtSfmi;hN3@k@=G5pm@rV%acwV-xe4#Xw`x zF5akJB}X!D;2=1%xITxp3v-+maH?HN z3EbI8g5vvZ+Son$?hDXg@c>GUS2&Bd-i?wB?x(K?qZ8(({c+CBY9)QJJLd&6wB2cO zcj;21FPXBVYBPE$Ze>t;}l1!sl+{xdWWJD+rm7VD4*dsEL zYh94>Co;N?I0-n3((u_YwV6u)^eVZv^Pz5}uJl_^N_vo{FmiXGR61qeeF05P zTN|fhkMt|BGceL|T8+>OFM|?^-%8(G#_#&^zOB#c`1^=A9iul}dY^in?p3y)v16Ro z$On3pl&9qneMr(CIf=YdULg5+~(0(jjS2#5Z#M=<`+_m0t}aiKC9X!6ah} z`Yq0rP`H2y-WKh{=4tvoA~d( zPrQle_HW8DLr)>!KAhC6)LQgLuOat7g0vC6gET{}MK3fW^06aHN1$bpjvmUj9;J4o zCt8qxT-!itw^9qy9i2x%N)O?@YpHqYh9;vQr3Z7~rPMieMSG!Ka17~aGz(HV{nvLv zSJ9tRwG9pEC;D@)HlYE{M1RiJ6f~fX=+C(tfd;e={W(_)(17pywZH+TK4L(raZp-3 z5pBT$^a%qwo(en_FY-!`r_d?`$#=$={29PA@Lu1UbQbU|yxn&uodZ0F=XNG(k0<4> z_Zn_H+M3$E?Z|V&$D+|RPvdMV|8N@cbgqRzWTUJb9bF98&$%-#=P=qp>qR}Lc&N7;s-dJ6K($XpNxK1ua3ywjxO2dLAH$%g!%4ft z3-ppQf~3zAeWHvc=?7(G35`n-ey+#yKhC?g_a9g4Nye4>lX0ciWn8I;8Hd(o8azdx z*v25=8}6`*+G9(ti!-9V;VEi$#!%w^_R(cttxm`Ay(OkAEsFoGF}=oG*GB|h9a$d?Xf;1eQmon&8egx0*zm(TwCZSxfH17;UZlRQ4%>(2g z&J5%$%6rO!;()mCKdB+gDEV)ob-suCDKXSY;R}JvIz|lFZ@bdYEb{ZggeBzkA|dZr z!#NF%m;v6*BsY~LZp|d8X9~5KMou3CbZ?XxJqA3T$rzkRZY;PtkJj;jgIT)$jY-f5X@eAFN=ZYeLQ{;lEoGSkl(x+HH_h1@3NnMMGr`>nK<5nZ-<<%I%ggEH zcVhXzz@P!mP!-pej5RSE=o;55t_D?*9>^D0lU70L=2A2K4+U-5ujHHiQD=2Y38jZh z1affWdyR!cxHEbja0y50L^Cv0F6{hq9B?f4^h4v0Zz+ZQzGLs6R7SscQiAaHp^ssA zYq{H`(wX)tDM{}Vw|bZOPJ1r{pcYI}8fAv80FtDH&AKzow?}mbE)=zem~H>VKVI>+fWDdco*Sm1jXC4(bKN zzHoMLkL+6Z!iusNLSJwEglZ2^c;D2&puPa~P!ap`^i)y#3s95p{9XBV5pCp*KIBj}CS+zUe9kZhC zJsm3|`YUm*L_ND}k?taOKdHW<^k(Ibc6H+Jd)H4??2?>HiEEQmDEFzUCwDKKUR31n z$~-%e+^OcyHNCFv06tcJSoFEByfqOzW#k7vvAb_sDO~x--OCfe4dsvUwP<|p@Y(Ad z$p?K~-^WoC`|V;EY~=~ZFHw6RJMFshea_bW>gl|Z?;AVn+{xOdY?&G5+xq5yhpne{ zFSl~nUFWiG!$Wvq-q$f0J6S9LthRfl&G%dFqu9%6q!F<~$-?**_MBsLE?;Wwi&!Iw z^%p(u8x1E`6>N#{nW9%&$Aq({!<$X6$2jWH&!YaUAK&B;iZNUD)ASC3YT%k6Bk`q)d7!5(A`4QmFrjU;nr8 zYg&m@;<%XI64%5s@hDcuDl7~9k{X|(q%0`~o3$C1wZ<>$eqdQWeu-J)mvekEOUfdaiBW2Hq@fj-RXf9*AFZ zGS~g|)g0ae=9m0It|ey0%4v8LZwt$$?7_uj=Y9BX7R%HYyF0(aEd8hiUl+6FF>)C3 z%lJFtDLpVNxc)L~gdbV?LU^0@9o2fs9sD-GqT(;UefUHPzldr^d<$2NVh6dJ;L2mH zGdw-G%TvNrio8n>rqPReu)AE9K;?5glw-*`g0f`zw2{NPY8&1M9AmEJ zM&w#KK+TU$JgxE?>=PWBKF#_y@2TD)KMYP8p4{a#t{BQ!eINhTcYYzh48&er(;0hv zz6|U$doO(8M4#LDjsT^M@Shpdhoi?aq*S5|9iDl_G<7jb%b3%4=eo@|xqvQRG;1?8L~CC%W<HLIQ{Mp0~cK3nOS0!^A)jQO9@+f zIJjraE+Q>1@oYFy%$ieTlPx|1ycYYE($#6s;Y;-_Y<$UG$g3+c@?)QpA{Ym99%u6z zZR5(;7!Oqbn^%rw+hhVQBi@CFaMz$FQtIq!bU8-m(M~NK+USgG%W4Dv1eg6S;#>%Al+z zv_+-=La}~8*#iSOn?PS`$YwW+hNDJtlPUMW=yZ|V7GK#ZMYG5p9q5iv!y(pA! z7}r_oxZaPW&{4mJqfq)|3~iwpvnOc=aDR>s^p|pma*Dp?8tBWAM5?Gb+7C>l-@>D> z{u-U<7{hrX_e&9LK82)>!Ecm!7IL+UD<$_Auf!txu3o*xH|2-EK(SL9UQZNavvP=X zO3c#a#LgI8XPrZ@1Jw+wxmGrCy&L{!qdG;)Bv5_={{}{*FSW-mdZ04;! z7yG1eV(cVx5o@rSr;E?xte7mGi_2oTGNm{!=1(Eti=#eg9RsdeX~&~YPuRq0t)u0P zJua4NvEmwO#0ONGa1Fz6)zgOdGp?p;L+_eE=gG#YeP$;UM(~@ayI2;rDZu@y$sk9d)facKl<`3XB{C4h6nx7J#@^EzWP09 z3u;>1lL3>GekilMLKiZ7J$}j0mEX5_+=K9w6nrUsq1s>eT1e}`mt19Y)~yvpX!PWS z9g*2122*gPkk&(Te=%kD_WEmc{Hn?9fn{69ull$L|F6Hc-yG{d(O<51E78}lV8uSN zSU2BRJK4%Ywk`WmW!SLY5pMp!{-eCtnRnO)hkb5X2Uk|Q(px3$Ku(>NQP?8tF&GLw>7c>~XDOg8Z3L-J+$a>|;y)|5}lcjP#S^O^Zlt_(^>bKabH z=8neXQ0i~Ucc2!wo?M%gFQL|;WDMt{^T}L6hr#(Sc_;2@Ob(;|q4{EJ4NAsxZA?Ci zT4)nFpPMh@%AjN%=VSAUTw&dT^LhC~t_(`Xb3QJgz?H$t1k(6?0au7`N1C4({6k}M zIL|*U&pBh&j{M>IAF{t@jmZh*Pt5;9?yuQN`H7tUnfza}!K``QNf*^W!-CQ}##BP9b+H$d*#)DDp?<|Dg2m z*)jRCoc#*~Y)m$hJ1YMt<^Rb3nf;67(fKiy9ZlMl|CaM1$#1hiaXdM9UUo9&r{urO zewz(R&Y}iaO8%Akx5<4cyDWbtXWz@d%h@Z) zU7CN3+_$sK^UFB1x>zk>W%v#)S=4Y^D5XUTmd zyDGnuv#*nXHv4+^8;%#}S5a~?>9qW7*;grf75QuOr?Rh+znc83^3P>Yk$(;OtMjL` z&yl~G{A==GWxwVb-zR-NyC}anKP~^C>{pzK$$cOA{p=^%`P_3(etv!d$MeaZ2Ye}Kx8|?TZ^=KMeJ1;C_G!|S+0f*f>}lZV zvuA)`$UYDJV)g~#m$EMcznpyu_%vVIKe;ZyHt(NYpI-;OA-^7YV}1khru;_W&G}8h z0USTYv!Bdf$G^QczYX}h{1e$HvrlEWlfNy0g4~nY6WJ#?zMhiX^N(d8&mPY{MtTDH z1XtgbzdnCM{wC5Jfwyw@X!d2^<8J=p+WbS=qvYR4{_gw{YJWLF{cLLwS{ck4S3cQso zAIKi&Irs9Mx8@(rK0y8+^7rNsW*;Q~cJlY+@6R42e;@g`=kLkho4qf)KYvI5uKeBE zd&oaP{{H+7$MsPp0c4P1R=_9$20k-sN@Ab)p$dv+UFKgHD#Vo3b0J`3yBbpWjQ(d$N18cTj#W z>3zWWQT7o3^1l3`{9*2Th}?s~2lMv>c}jjW&lr|G%@dx(p{eogl3?Aq)a(skLZI9`{1g)3jmze4&l@Y9@K&6Vr2uaf^teigavv#YYJ zIev|jujW^Bc7672{%L~yNui`N!MrJ%D<6+GasJZ!aEF4 zZq07V)NwqO_a!}=hg@BKNxNyFCBd{JZ&QIDVHp z-vK_$@nWvOF1t8;ZFVd0bsT>{o$uy9$Un>R2R!|=`6XN%o?OE9TeI&|@`L>Q{PUCf zh1n&Pe~pS_&?56S;1e`$6;`Ja*hVSYjOQu03~ z|Fitu>?PTG*)Q{-=fB9$&d$ls&Cbfs2L3Al31z>^f0_Re@aG)Qr&tNRG%h0uRWJ0G^N?4?H|O0eC$BJ|a0VJAnN9>_Ff_*?Qo? z*+IZVvV*fe$=~w7=6!g_zX6LPFWA9c6u`gcoq*koZonQzcVN$=2e4Ps6POphfPJ}d zLv{$y>dINS;?QgZ`7Y$U7Kderl5Zg2rC668M!qxohGPG0ZMH7!S9C6V7yU?mfPIR- z#p-N-%2#LmWov+II2%Bne#HP%|6<>46{Q0y8Bpw#?Mr?i(z-N=t5KdQjC!hEtgTa=AVmSl^83$rD_W!X~T z@@yG!QMNo&6FssZQf$!-98-)2jx5Fi#}#9NeiHeK#oTNj`N`xb6}x0}$?rgZaxo{{h5QuqI~23CIplXFKc$$J%_cvU{Eo%U zY!>;Q$WJY1WHZT6BfnEIJ)1#(XY$jEowMoWr<32gn3zoBUau#%DWa(>TtgWJWQwn8k5&Hi?q?6r++c4hy8(AERs#1Zb_ecR z>;YU{>;>Gb*c-Tau@7*cVqf6C#VX*cVl{Aev0u?Q>&F|c;cUO6Pu7?G{^Zvb zy|X^#*OKQv>rH+g`L#vQtQYwM$geAUWIf3rNdADLd)9;edh!PrU9#@v4`d(?5_umHa8i@6z9sKaKpU#m~~;kw2aM zX~oaepOHVG{OQFn(w~z*kNo+?FVkO;e+l{XivLM}N&Z~&FDZVN{tx+c$e&yMI{g*- zv&o-R{3iW1`LoEMUHmrv4f!+4pH=)g{Vn-3$e&sKB>ge@3(22R{51Uu`3uNjSbQt} zDfyR@zo2MNK9@e7HYZP~&j6oEKM(wT`UT(@(k}wPn0^WPrS!|dFQ;DtekJ`X@T=+9 zfL}|$4*YuhEb!U%8^CYzJYT&DjYk}7m*8#69t_NOU+yK0x zxDj|`aTBm7&;D%sIo|AM&TcB6Og~HhR`NF&Po+Kb$@We2lZZD1S?F7kAuQJVM#y=_Bc*96!kM@$_!W?<(#ly%qS@;%&vl z=?A#>FzNC19+j$(B31n)dL zc^CCYC-1n`sTCxDNqp9J2=)4C_G=Skg@Hx#c2zP5M+@OGZnJ$Ya8 zUf_ep`+z;T(mi=+@nG@p^a1XC4`=T!-jlwY{JY7&r+9Dr9`X;6e|Pb|^u6ToC;ve4 zVER7t?;?MHac}w{`TNMft9VCxFZqYb-&eddeFyo6$Uj`%nZA?!`^i64yg9v-{71>Z zzj#afX7V2)|Iy-(^tSZ&^bXSNfv->B0DMFGM&KLMH>IB{K2UtD_!Q~mz>gP?10OG* z06tNC0{DsIlf`S(*YS*7Np}EW%keW@`E>DF;Ae{0q_1N=~)VPjx2k?&cp7a^+{cQ0J>2tu(6;A^{K-n|J2RU9(t$WfhkbkDQJiQ{l zGIgJuJ8rJ0d`xmz`WE0@)4PCgOWz8-JAE7Q?djdXd(yW9-$DzFNv=+>BLC|28sN3* ztASUg*8*=yuLoX}-jH@n9xWazx+Nbf9tD25_z>{1;={m?6psNvUra#j`Gw;1|%g zCFv`Gui$JtSKNc-p12w0rzbDx%H`?H(~CH2_dGMXFnt;47m_YdXHznZb@>^rx@$SD zt?o{oox%0X(=$j{0$-Y50K9;*xm6QxI``b*N1e--fH^pJEzdNAow;HLCw z;Gxtyn6xQ%EqXCJV{I|IvRXPHsMSVStPYIYq-94}RyvmhUGeNny8Jr#I*dK&PU^mO34={dlc zq~`+9OJ4#!KRpk4YI=TpFkf>}atQF?~|9>*?NeSV!tIw4s}>E7u|uJ4te#NLQw*(-Z2*G?vXQnDi5HQg;;L0XwE zr`|rm6=i-UXUjO-C+)%>-J{XmAHh)zfjxnHB!>gFmg++8FyN8pZik~dcH#V}Bu!SO z`=)8KI$Z@^lkNxHKV1XdH{Bn2BCUo^MS1}FlhPA`2k=E_l>2tiDEIB2QSPf0AEpT#jHtDQn4(F@WIb7KXxSF?l8Q*ajt$90$;*Kkb8MjWV&E&N)sS4u zu_1XS$A;uGjt$A>92=4=I5s3#a%@Ph;@H6bR{^{5yoThqM-1P9hqQDE zaA5lXvG*QuUKB~(_e}S6FFEJ9OAfo_oO2Q-OA;lhpdu)sqJUz;fH|OIKoraY%vsD? z5fcUw3}6;>MBeXj+W+mssRy2S-t)ZA?x(A3dV1zR(_PhF(^Xwn1=u)l1k8;a1M}is zV3Rlx*feeu+vun0$H+!MliO%3xs84yx6w9o3(0K*a(il;I0k-4ZgmaN#tATq9ni%d z=;JJ4R$K^JC@u^v92Wr=iHib@#>Ife;^M&KaS33FxFoP-Tnbn!E)6UjmjRZG%K}Ts z<$&dRR{RIV<-se)6@X>pim{I_i!MdmwS?T$noEF7qsxI;kbBNu0lYlA5_n~_47e;> z4qP5x1-vS{8hCYd4e*-iTHv+Ob-?SQ>w(utHvn&lZUo*K-2}WTx*2$Lv;w#yS_!;0 zx&?R}xsPrq_t72XKDv`!HjImbcX8ySyUBfY54q>cd(hmy5xovv7rg~sPo8kR9{5)D zHt_9e18_sM5x6mW2l!6(F7VyxJ>YxM`@r|3O~6gjX5i-N1K*Jc+&_Pogi$ljtk*B>I{>iM}CEqHoC)uK5=DJ-wYoKaeL}{{!$l zdcs9dMNb2tj-CNN6Fm!jHhK>DT=YEf`RE1U3(;!e>gYw_i_se3n&>6qOVP`~m!nsJ zuSKr{*OEJq*8<<9Z5*X<0zED4IF>EdebK$Z`^g=p_X8h{9ssT)chN)SE_#^UMURlX z=uvVPJx1=L$H^VnKMs5#dII=F^d#^}-a|HR+7+f4@Y+Wss}b#Qkqt?({FilcP9)nP zSpmsDNY+BKIL^fHlT}05xtG6hPkUx$$JQ;iWswz9h+8Ze_6ca8j_mY9Y_zafEbJ1K zwUg}owGTk{)v|X|d`4LS$QxZba#>$@0F%X`tUY9lo!P4-OKsWsYj2pWt-?Mh*&>!^ z^&zwONtPvHZ-*?wGdn+m|2659lC)Jx|_LYSgZjwr+*B8{=hZd2w zRc5!EtgSLFC~GUVq9jtaulD81KVklkGxdjhBlM6g?$t|@P-PLE=~4BqdR6@_>zz!` z%W^TZS1eFUpc2_TYUhgffyv@telg@bLlh>OldY&M?qye{eTuTMQfxC>l!{U_ySrq6 zsa+^x_gBwHXSqwmomsner~_Gq$C?9kfuJ){+z}3s}8D8_L?Iv>|T=dcUx* zr8Q-3Qc7ygTPmiTtY>AR&s>^PTPxmG{y)Ng`<9exFN@kz7SxsKOHpPEQcK>yC*`80 z7C_l+RiI3EyxL13>vVZPl5Ki<%CM3EmWN_I<>G{<^kyGQB)OJ@TV&I$ol{Nd_r8>9 z1d{JQS)+@inm`S8D3L{TE>Kh{yYV`}I-Dy7-PZ-mdaV?g{I$t?P_&wxQfXtLEJ9iN zr3P!h8YLtb0u z$wPiS=jKWg{eStigYvyjW>I*W1e1kR&+0vplRxy4O3)D}}zg^uF@V zqbSL%N9fTru!hVm|;Iah5cZ!5AOQX9$x znk;jhShfdFpCWxoXw4OZH$%a}UQ`CC0c#>x?Svo0> zT47)b@?v0mp5o~fiemIjqPq+w${%)C+79|HwW-GXOgrx!t(M>kMXPFI(XA*}EiAef z#j1rxxB7jxu;^C(sumXAiefV@94I!QR@K7!6#L(!RkcKhV%5?aT2(t|C{{LXzelT~ zHAS61ZBJ3GT3QtAQwkLx`XZF6)z$ii_;bsRqG11vnVA{_1{C!qU3z4 z{`2%4C^@vYs5|%p5+%#8p;}v%oCWQOszu59V}htVw4%6Q?HbxJwBDbm=l@g2-atPZ zZDkoLD$-~h{F=xEuJ~Cau*QlEJ!=dReQBljZ2D9-|HGl5&2__`u)$z5@CD} z62B~j#$&zb=<5`|_!$rYNrHEu|*2olBivc%s-&ta_nbK`SC zdj7NWhT1t_>iF04h9r%AsUu(BP&?;K9r^NxB#nHjW7p)3U8Uz8$LGu(m!VUQ(wR9< z(w8Vk=Ym`(O8#xxSpF#$7eJDRB;=BeYk!rz@q6^FcFs_Bpy#R_XDB(y#(|zQ67u%+ ztTFk2OEwPUbHTpYQTEHo8$r@gYyW-nb3u9z@g~Vvg4CgJJxLmR zx$fxrWsMN(*WZ?(|L^|R`*+9QoslInV{ecpBv<@( zvc%4;ON6mEtWNwpvcwVJA&VrOWzU|)o_8FE`J4M=hiO%jS?i!$11%`s>3)(`MHlLqjJ)x8$II=EDke zkT=5j;2+Wa|H2raq4|R2k6O6kdfmSo!warI7hK=StZe)@)}I5-XI7#AyEOk>ZMfqY zo{>p{H1gZugMY;szN@;Df@63=dM>Cd`6Kx`y!-a+bp_?;%or|iEx2A+aQ*qO)Rhz* ze=;)3&Wzz<{W)k=f=r_EQvR8>UiZf`iJ}MQulE0IndHytQ$jocXU6cLNeMcson3$4 znKAsYpyz@ziDLHrmhP{hKIQk;H-1kh$$Sa^9lF0Tll}4cU_pBRz4>%k#^?W2^n)5V zGFn278`=f-XV*7&rVTUn{7380|4DfxtUOE7&esh7k&GQyo<-H$>#~Eqk>9{lt?w@Q%~)^^WLL-M9p&d;kvHV6C1YJ6=_8}>-dTBL zXU6C7JQ`v0b+tS8#eZ`BS?!!}#qrnKZ~Wc#{Ac9n|K#}m-=t^J&)>BM@>_G|j`Un` zeEuzc_wUKi1@+xwO;52#^Cdb-(Se?&i!Ge$VP%^nst#))RZ93IDgq8-LaMM#1mF%=(7xH)N5UvEtZK z-q0BFuk1H=W^CD&@4>%IpOVp}Wa#;SRo?g`d!)Z&{drgQDgW-?lRqnO6x65u9zAE) z>ol^-9w{>>h^l{o@5#S!|NQTa&;RdxFtfKptKg!J?RDZBlY-2xFKJn<{W%-yf_5PP zr_g+6je1vX{&!{!FQ58?D~~_8a`3ZFW)vpKjR+{@U>5w~1>%u$#%>pw8-2jgng2-w{3muRZZ$sw;Hf2-uXVE{7L-w$!p&a zz#nP6I5GG-G|4vm6dn?vv<;}|k_KGCpZ~>fwTa(mf3ePQ%6-o*x-@6~kOHxwCm-Jikp}5VJ;_lm= zJOmc;-{JAF2*2~4E$d79Pl2EEmft#um%eZL#qV4Rt}5wE_%HCh_>(J)-@>2V_vA(W zH~32|>c7QXZMpUlKf063M`6u#A5zyygL^2Mahd%v$)^NZ~fx7 zx}ROKWGkt7Qr?&IPuudOXY7~!$~W#y*C=V2RPyEhGxjU+FI`1n3A`fdS^KqXoHRi+C670fafNSlP_GGq+QZBc@+PvkK?EHaeTP8rld_$*;nw-*)1-Y zI?vn6;CV@Ivc-Mwnk0G2=PnPtim&XSw^c|l*wy4O*rrJn&Sm=?|BB5fJ!(I8t?}IV zv1^rlzH)FFW^Y-)s-|1I4l_f9Fgpq+{Bg3Qct@#0B_)^j<4-k z0axK!_Fb;s2#dtox7!S!y$mI)p zG5J3D;M*&a55959MmLcAY;^KW*udBI_u2-ed+d15@0E-vjZT(w-Q{>SUV?Aqi5!o@ zSKkEAO(cy@7V>+G?LyKL;1cRJ^!MOZx1n!9zJWV$bQ|0N{2%tm6XFJU7iaFalekMa zy!}lip9I!DIgR@)w5Ra~SK3Ctp}z}w7yfwPcKx~PZP$Fwc?Z@-IM#);&!k>(@RRX;eyW|7%t#JRW+gMpPonHp`+}QF zofq7}$<*WpH!V3h>EO?|i);tK2%q5{e0z?bchi$;$@83j!FBW(;2XQ6??CBevIu2JQ?qYkGewSPH;T!Q0_pm!D zg$wYP*w^>*N87%ndH8~#W)B8VCqEF6{Ri2F_)I(0PZVG1(u;)@fCz%O8 z#m>d+;+*6mcOqx|`M!QGe&PE8Pr$?DLvEEjA%(}``*D>!9^a4seLp|P_V-8OL%u)Q zQTBplQF4AV!R~GMu@gw+?M2B2lw6ctNdBNZ7VnV{y5qQhfbZ{*v;#=9?R{=Oz9sMD z?1OGMKN}zRyZHg+_q${8Jb6E7?{jSDdbCNtGRfMJdb<{wa!cKar5w*c@NKUuN&kC`oruX z(kwfKYX<{okzY>Txp*a&?sk`R_HMV7dPDqB;$#f* zgURop;jS@pCzrvN85L{9Ueed)R?Q z3%NPLJ7hB2kMd*fXwqJGg}WYamn+ zXU5*XAEkTyeaNqN@>O!Rv(%sD_x8Q*HI!WKdf5qnqVHuV`boe^l$VdLao4)?(Y5X> zV8T&P>hvOFMEU3{x38bzd)no$9C#1AFSw#7EO-0)eSHtRAE~=t=J56JmO1TR>qc33 zJe3nI!0qq%^WE%~t~7X8yFa+BysmVUeOIE3O!oVeU*Y5p;tE%a^3IfXvD!y}g==G5 z5l5wsZB4Ey#)|qUfAp0})q(Pn-IRzcimK9ryeYLq?3JcOPiezZ9;pd&N)&fS@!~22 zYw!(Cgcfyts9(5W~($LC>OHNdlh%mK?)>E6PFJ-~VDa}rOzT`yZc)!NP>}gA0j^Azz zY)n1H*DQ>`7d}H@d`K>~g7n39vDF1>>V8ugG?bT~pEp zt}-Q+tRmZ8;AZ+md}X`HH3P3=XM)Sy<I<&-7L7`K~#5RXYn@etFJ!)xfJ-#Zf!o z9p-2GYW6(W61=)S3|!IF&U1(R!+dpnIH`s`*R`VLT&K9BH7ToM+u$MSTz7;&+}E^6 zkh1MLPSHxwacw9sV@ui6#1<-L%UDI>ZJ&BH>JZKLNBC?zo0MbEbc%F(CRd%~=J?q@ z$DT#WneHgCQuZi6hx}}($f##iewI7ZD_YT!{wVS@C_mes;W}~Wxn9wY=K3SaPp9Mz zce<0GqFJb4AirdpDIo+M+wq_v@b^K z(S9EJDNf#!PH|ni>R5lYFKkbxcxLUz7C)(?qJbqn2)XrVh9*o~ts z&K9!rReG{J&L88m>`87gxVOiF%V+6H?s$Kk_x5;_vkTlHN)|XpC`~AHR`E#}xD)*G zKCvgd-NCIr0em37M^AJodP_v06a5L~CpbkbJ;4p6Jf_T8MJzqRE$}DedT@c<58C71 z07{N`{qePVl3&0Oc@k-xneXJ|Z9e74yPkL*9TT1EPx9N$sia@bv7DXnj&<^0^_}^_ zd{2C!AIasPv}bgRKh^(Yj^pgH?pw;gGbeMr6?h8yF_a(Yj&bsW^)*q7z9C}JkK`lp zV%jtH-zqPz^4$6bafQAl7LMWzeLsICF0RX)U~kdAg!Nb}qq zoPFIKK-oNZxCf_SnzQ`r{y@C59_0=s%>mAFbKP6!41cD7 zi#l(bgYeus*BwMU(ycRR`!oDH&c0=);<@!mHT?=ifE6+zjyd%=zFm@xeOFE%N94_sk;F`{qzL3;(N!x|x(; z=3R zbHNUB&zej9W&T-nnO_22!ZoLJeyTg2bTIH>cc6QQI?o#UdOgrx?l1Mvm;>Bt;7^;& z!R4X#0Jqd%?w>YO+(PiD%u?`E@!dMbJqiAlIR$U3Q`{APsejT;cBgqPsb|#{{pt=iq5~QFN`p%0FbTC9N{!-LZIt z9q*3g+B>OvH_?{vCSH=_I^Ags`tp^>-bK;v-1%PO58X=*`SV?b58p+2oV|_m+ll$~ zAo&Fx&&TWS8RWN8a+|r3qxq>X+KZx_(r8ACWu%Bkig$Er>Yw%!YTjzD#2@bb=u)0; z74efEB=XXw<~o0^zm#Wv&@AKJvG`ZLl6)CYy^mYQ@pyMJ^=>6@)2-b53jEt%h)>oF zsin9~Hxrpjahh)7oZ>cJOnwX4O0zWe?7B4d?7B3%oO~(IcoFbY@}*!`M3_~St z_*Ld6Jk5@DxB6TB)n-q36ZkdeR`8qgJ-es7%_|nwZT?pBVQvMUXotC*DZkU-=C3uw zDH-PO@OOfb03YryG`IUZ{DtNYN>)ZA+)%d?zqKRW1;kjoi1p>Rf1U!=LKP z)Q{~gz?IQZcbC82Utor~+rSr@yTIk&c8DA7ZU>%k?)G>2^C@3s9OMSNGtC43UVkPv&oc7gI?z2y+RdFo`I$z3U3YU2`Um_O zW`KJF{B-jm_~Uqd9pFv_KixcrAJ_qIm4DEmX8OCwz!#cT;E&=Zw!eGGFC=Q#Lw*%` zKldml{oEsXkv)a7Q_aJ8mF?#q_7C|}Okejf_{rvB@Q3g@+t)qfAND7kM@T1`UhW}E zdbw5jqv;HaIQ+}d(C+gz5x_6?kt{ZS8M-zCD z6U+qjq<_LsFcZl)aP7uu1O9xwyM4LCB(tx1+CSspjk>wc?p^#IcXQ);hS_F3=?LHi z+F?BDc=I+-aUZ^t@8|lr!S0U^N#kMdXP)y<`~A4jzUIBCv+LyE!*g)GZ{d0bQ)6u;TKG{4Ez6l@B z9o-c0$!2r33H$~Byq{t^xXs`Pm>0l5z_)V;x7xqp4>0ZB2jB;q)!-lE?YX@>2>d|v z5k8;WyBGaxe~@YCJ_4U=UIhObFVOAW8b6gtU~Bw~&8;Pml;cxu5rL|MCICoN9a#ekJ6t3 zKaE@EMgPvRyn&&g|f6E~ESVMcz;^V~ZB zmLFcJkE84!H1YQHsI_1IzQMnb}{%MvmPAh=y7BBwqNfDnYT%Mm`0dh zGLHXMBJPT3yj7rd!AavS{Hes|N*{Q^GFYyjVikM)Lbqu<~MnvJC0Og;BA-q-87 zt(3p#H~QU7eM;)N0p=b5t{-6D_3r`Sqx`3+zH8uqiW<1Oz@ItlZ{GLs`2N%!V1A71 zx;pMhyt>zQ{V4Bme!ypY9kTth) zz;;^+N)ixFJ+FuFZ_VV7}nzOA;1#tPiFHK$n&-kT*@{r$#+AWC3){a~; z+S&nI5Rgb7DR>i8k7x^3-RJ%@-_%rb z^}w5%&%x`*_2MdSi~rm=GZkHZ@aE=A|CMiUzVcguTPSZ3*N-c@2Bb>BO0KfYrcQH{ zZNBhd`i8_%sO%b&D!5vd5e?0J?Z5CfIjcBn*`}7sC00QNmrE)SY{XG6@d+BmHK?hG zYTx*;eI8}yT^^~Nt4>J`(}cJM9{RKis< z-}&!-CG)-i0a%fv?$qx_Y>YCltm__^b){T+uB~9Y5aFVPtH%8m)$LpVjc-a^gmSJa zskEz1Nj2iX{oud#m5B!TgKx$ix)YzFv@7G95v`%LtHSweM2D+JY`Er>G$U?93-WT@ zzr5*8goYCCXaAEgXNtSd;APFv;GKxyP~2_xKl`$#nCk>y#%u-eNW_X_t~7WV(}CC) z#oRA`t1oSex(?u_%rD^WiGNYlZS%kQQl^k=4_?x2120KPv~9i}kunOocBI0t1SKVj zy!$M^ zC0Ut_!=!9m@+tAiRsvThE0Vn^8AlwN*hTJh>U>5Fn{n~B!3j83;C#Xm*?9 zZNzmMNXby*=_m?~;_B?d@d)7VKN=F=C+ zmgF_+uO%MQk@4rrJKS?4@#yX)%9UaoeV4o$uOimfn?$x-mCTL5Ouhhq!S#zg8IUIal{2&p&*2Qm;Pvs8ti1YJR@^!L-JG>ijh}XsU zfZszDt%KrkldphZQBM(=zD*QwZynM0)=_U7*BuNzi2UXFQSN^jzxFB7%N|W$jz3Bc z1Ai%glH-@+$0(Ua*~iH&YJEifwHJvvc5%Eh*^t~y{I%7|V(^QJzP5&lW4CkmHsYmi zNZw8^A==r7X>@wt^^f&n6edo04~d?{eR};+Kg;b{ALONffvB$(zX%u3MkHNIbX4fsgY`Gx(hk zlNqEBlAGh_h{$#`@!6gMuHa}<{9f`t@cm>Ha1-~vJAO5JjhK3`B`*VC=I)orZzgXg zm&b1<>wrr*x+#8!xNkQRC-0f$eD1J_xNe)1_mb7|)5LCD&9A>0AIdL(kX#eLlDrCh zm3uAaPV0z6w=Q`jjZ(Li=xtY0x-5Ppd7W5wOUbV$a@)1UaJ!cHZdb=^lUFEth3l8c zuP1Ah<QiI-JV` z)+NuOPW`AhM|tR6YXkKp=tj}h%2r;xvCF33K+B?imbYP9S(i=wl&G@Q%trT_m1;n< z(H=`fTmwyKA@tCS#ZjHR6af~dRC|@Ri%1bK)a%uN+REs{pK+ z?n#kmy#iYIE@&I2mFxmk1ecaTX)imaQAIkX(MA*%s0CUgMea}>m1aO`M~Ct5jew0f zHxzsrP+HlcymKy^xje8TX;hKHT+tMrToaB5gEavvvP`!$`b<|~H*|#E&`5SCwNE3{ zbVXm-9lR&01F#2qFR;PDp5$fG4b=eFpasg3%AwsEj9#NR=Le^Hsj}#)dQ&okd?s45 zK48*Rl||du7yMB28EEJFfgM7AXc{N)5ZY%S>Xbo;wGVIt`E<@4f?jF@$Gd?~M;|C% z%|MQ(qc4;WN0AGs(Tj>eSDLzIfRo5eb36%Mqx3(DYj`jkNNI-#aWoamkOnE@=%AGI z4+Ki%#OFQGk_$>tm5?R_EqSR_KURw4{lWL+Hymds11EFr$wgDefTB5KqC+u6JBMb7 za}FgD;T#GhwmEfGQxPcw&1C3Dw4?nJ<@gtc)u6R&lBA;_m(r*-b2+41DI7~a7VTy& zQtcFuCLfLVu{LQWaAdS6a8LL`a0K}X_(gCy`Ea;Mus->4YzgWEWm8ZddXRNUfAR|S zRDWQ9jw{lG{eb;Au0+rF1@`5*GCkf0*oWgP;IikC?yo9PmL1Y;Rs+huL$R|Ib4XSm z(oho*9jpdA>25$#WKD2I>+V9H4J6VwFdHadsRhgdia%-t#qHvcIzaKiD7-FEYrtBx&614W?L7y@2Y$>fjpj)MuF(QtCm)k*Y@DhWJwIwaWCJ{KTl& z6oaZ8w4m5jib~Z58c~e13c!j$^;dnRpe5NQ}#Yl?$qUc>kN%F*_s9r@# ziYlRKU+OVMeo+*#LL~VsQ>-(^ZBk?b%{ZQ<$O4*=94Qx=OKC!hqYoN^h51Y~nfgSt zT@2Ltq9|sX%^J{u_0m2IzW2)WJn~Z~3$5~8<#_XapGdO2@+9pM5lLx67g{n^vmD6IV=mUY1@t;I$}~-B-lZN4!gUjv`u1 zBd%I7?2c2kCPkvsE>J~rQnV(uR(J=sT^Nb=R@!|h?_?Us<#kB=u(ZQeZ6{wY>QQ+` zG(g2O$l8nTb8}R#{kDL zM~nkk99_-9il#d}<%m`(FSJUzpcT|Ez7ZF+N@>0+^eK9;M_Fs2#<%)lZGiR2HD9!0 zX79%x8-le3HXxV8(w6yqZ)Wld!0~972Q$}R%rg%LioY)gy95pIC6r&9&dQ4^SDaLh z0Ta1uLaG5c~iB_CWs$%SZ-F9%ezQMNlF%&DVbJFyYz4}4%_3kK z@|kGQuK->_jTx!NeFh~nq3ZL9-&>B_=K;%-AIe$DR?>@?=iE8Ka^#1g@m>yG&bjGm zxvv6V#ql(7$x_mMS0GC8S-^A1C7qswv~*1>T}caGF^zp%ks7yxS0JxMehW~V#ZG%^LIPr_$eiH1-FBPvtHV zXY{R?#TX>6l)n>6?i!b?VZ$Kp{;{O_SWTP>Umr(_EHk9(Ur3oxqY0l5RMh0-DVM#6 z^!+DO=7F+PIhnK&`x1>P3pnyX*`%Dn=wN`d12}`pA0>{1+1ikvjwKKo9Gj%f06Iw5{wpv)N9b%)Yg+n{5PNuar52!CP?W{W6x1M_Fx9_tv{k5yl z6X+v6mFPN3pILdn=L78(R}J;G-Y)ZA;dwF?mQO{xPlh(ayN7q&@waxS&d#>;j%^rv zA)n^|>~HOOpUk@#?9)H{I ztYFFm%aTjSSsjg0f(EG~N7d07B^+0yX1P?yRN7>7raGFTgmcniW=ls09;X_d+UQkl zq5Z9kcDXiKUGoE48v~5d>@?RYrm(jI*qe;I#)hOUKaW}2ru=$63d=%PR3%ocQHThNPj;A{)?F-KpaOK*)X{X=v~ zo8yk)oy;cmU7KTX%kVzlmgb$jmG;zI=}Nt=ini2S=}WyWO#5^}d)*q?8r`_GIh)bx zY>q#Vo&5>Dk+VkcZKZQ_R=O`|rL}XmxG4s-w2QMp@}`cvdD{c)f}ZAGG&&pOZ)u0d zSYt~I{Vh+B4fM7Wu#ss9Y)sxAn}lw_ZrD4#nQE2ZjNc{y4l9QGSbH}l|Bkv1O=5pW z@0HlC=)DsA3mUD&eoeb2_G8*1;c1;s>?i0W6Z;jd*`GUiH_`~b7k|&anx>ZJ^|35( zO8d#qyeY65x_?=l3wFR7U^gr>1{&$C*2V+CcQdb{iCP=WGQ2$&)$P&t?@svuU~lqQ zB-0r*oz+)@WNPJr2A5t>z5uH+ln4CqI@F*}Z*0ekNtTfxT&?`IHQ4$K(6a zhCC8~%oX#n(U-lRzB;p_2RQS1{0U`q%_pQK<`^p*sH5#!Jjv1E$FR%uY@Y0By9a$U zpS_@a0%axjDOW53E-{yxc~*9q^Q`PK=TZM?d#s&rN0?(t!_8dE=h?aTJnS{++Vip3 zJdX3jfx~#iL~ChtY;_3jW=bNv0^MO` zSE7TAXswt%EqC%9k$o8LT4e9ysj5=HT67CK&&XMQrMISf!|UVPl-J^0y$)aM+J&Yy(K;M2iKRPSf@bk5;Bs`0dFl679`&U=(Hf#O zoY%y;{CZVZ0jg5E%`8Q8xy?v3xy@Y8*=^=l^t;>4wfy2Xa|=&c%3gu~vXouQaY=h+ zd_`Q6l2W!QD+A3~LuS* zUWDfFZ18hPMQs;Uu|AAt4$&MJS8u%kD_S0H>)kb zD$PsVXdxQN^W%kRAy1FBH@bZ^lhiI+!*zx18d8>hj;o$$AI3RxQE=%zUovYu!vQ_(4(8b8V2q1Q}R`-C|T zyoy~5K7g9i_#Dn}A5X0(*jKccbB~+j!TU!?us^#$XW9LQF8Xovm^lGh*}g%&%Jy|? z_M?tgRu_+}$3kfY7J1N(jb*4Ne73>`9Z8CGHwb_)jZ=3bN^_>}pGn@nlymtmLVJ7%MqZ1$)AWYUrBDSeln zPmL%qZO3zm31+<6pWW3kU7wdjt(M?iuR(;I8%@E`nH}u3=5J2@iwrRnQ9I)qoT3qK=6^#RPci- z8yVH5PCZ-K9**tHL3l72YYrlfF?&YSu%6zNS|g)6oUO~=+as`{ITZVZ>9N*OwdZXF z`83L=$5Zi{Fvd(JjW)IIbS!&nQ@>8?Az`#R*p9|td2i~EWwmcQ7Uz3&|2@H_hm)nw zbnJDeb4@LKFmRe3g>C*ct{!Ffi4HN-fz!E0Rz0}DBt&S$87DAJ-Kgz*x!%PSg_gVfap+c-w)sy z_hH>lE4KS$N0!5G`6IA@-^-3ApAyZ$GJXm*4~X`|ZY#%*vxi|VKh7SGmHasB9&RQ_ zGqIbWOwB2gthsXR-gcImY4)b>EF%lA9K1B_ZD*Q&tTd?mfK86Z+x=Nz9nYElqlu~Y z-ht^_-+`>mPL0OJ6XWsm1bjQ}#~R**6z1dqyE9HVotPphrsr*i5-J2VH2yh&*`jyYPD25{ANVMu{&&Hhhwui2D>-eF3#qv zX{=*TqsHuL5*{365!b{X0X{pDU0f4;cr?sT0#2e-)^ttmVU!%sO6@SPJUa^8x;!h( z!#q2ZvqP{`%(F+adOIhQjopy=NbsYg!C-lIFm`uC;<;QsleN#8tf0>2KC_}hSkC3y zJ+Pk3v-2pK8|{Y8U7qcY9iO1=`Ff|;d&i_Jr^m2fIiHozqsjYlCeNP4Rr6SXoJZ+N z(Qte`^o{#az5x8Bs2?_rdG}2g|knD9N?`v2+}Om13?vp7Il-9vtP`Q&{ml zHR>MsjC){R+l#zASgt*p@>3#N+~(SatY#j^3g~dITnKh@BwO8Fdm1GRqb^v&c8c4O zx&pgW-Ugf5PVpJ+0@SMNS**OC0d`i@mh-uGQ8dC12cAahBJOZn)GlsI`T3MDiW=K? z;O((;ZEVk@*8^{0cUy1U%id^iFg<}iZ4Y~$>0^5XdsE{k)5CVRH<=sB zuQh$~xNt3JuQMI6sBLV|n48HvVxQaC zoc z1*x%Z5w|A4Ak}JIz>54u(Q+d%2+O&{RqUla{Q5a)NVJB( zm~=t3%(TF3!ZNO1Zf-N3@NIA#S9h|qS8fMvhbMrGxoUBAB{i3s4xI0Zj|1%=yu!4^ z*TNN)Uul|RADtK1Cp7~$i`&}zSUcy%+MOp2j#M{_qluJjkryYT>gxmSm_Vy0;EH=U>ytQpaYGtqF?6RnF+{(7Jjj5IJC09p-IXeVDDfh6)vR2HMz+CcL)XR-)QMXQfJ$GBmy8cqGxSn)Xl*5^& z?El--ULOsz+RZtLI}Em!*cDMDt`uu`L?y7C_=Z%Ea6_uyxB+d#O_A*UbK=URrKU3J za&sGXZeX9?p7y$^N_@F_#Ap}5<>uB1e<=1=%5RIR#*dhXO;z>+JYsI4{MJZ&4<0tv zNDr~kZ=}5?svcL1A2QWRtIP^YR-RV&zeCr!;=q}!u1vG$La;rxTHf zBHG(f7_1Di47)P!WzXE*>>1NOzkAuGbsz8^@}iu(-xMX?XCCGbk3_}T!Ev7{M!MHL zM9IVKof~CG+T!sb{IV2}@1=c)kjw@fK#`DqV?AaP) z*Mq;!4z)3MwEcv7pRzk|17)v~UX5PkXtdSttNy_L)L55ZvxTe2*w;Dx8oS88W>?r+ z_Pf2tPOh&x&g_2EPPi{Q)~>EE$Tzb)O}p5%OYI$Y!o3T8i+mHMTYy`*=O)g7z;3v8 zoOz$JG4_41cfiNkby0S9{d9%4KC3IT(J>q~Ajw9@a@3F{8y&5`G$J)*WkGfqvc!;$ zPO!(2mOyqI(q3!DTJ{^V;*jQ0b{(?r&`OMSh|+hkP$#vMP~viEK<{Z6ezfS)i2UxNWKfZc9m#ewwUy-Bh=2v$JSk@sb7L6%)P%0getYo%Az<{r9AcdEs&ZXk1XV9jIOw zv(j<|8(Q&4eUbq-Ag`D5j;xIg{T0JcvVUVJB4^M7ubb9YJ(XLo()Fq@yW9pq-A8<- z-_x&no(zMN_LIg@Cem$s^Z$$Qq^zx!x~W#K|5`?^`tGw&p-t(23{NPO_09-qdbk}utks(G zB(210&89-y@8TUpf##eEc_)C=W+x(@Gx)}5%T53wtST5?4U8bl|RF?-P>J&8=JmF1jf2vM(W=EBUOUJ`A~a!zxM zMo0CUMnUm{RO)yxYAn?Js~K9Oh-}t1mNcb*G`55>CX71Lrv%H( z#`Kcref669N@J9CyOI^udy*O?Lr8LvG$GkS5`}gQXnYJuItq~**T`d_T+)vaH zMnjwahO9m%cjzhfEPAf+l#(~XI|RE?y@6;?_N971y{9A%y|><9_NZ#3%s5!|*OpUz zg?0>*hT2u_D@jA`t#+5Bp?=7WgQe1bQlDuwRL_<9N3Uv*3;nEKFZT~B5YGm>&^TD( zA5ys4R?wl0+nRgwas)Mxf3>t&%}9R4lp{9am2&TNEGYJu?nU>d;6S zI7CuMhI7P2ftLiuTcTEtGos=Sq%itu?ABx-c<5{q=M3EZ)oHS^MU4o8uVkB z!8D46xk00FP5M={T$mxkycgyO@k{fxm9n7>&5dEc5M_vNG|~lmN^?i=lx~{RE|Ru1 zgYAd@~uVEj*0eQb%5e6&C=qcN}MamUmYnC zXGwAv?`8N)-1J*q)|v9{`AZ{)cu5>3nW7+`gZ@!UtzC^_$zRhBye$D zO;L7lt^iXWGviO*Io~e%06`Nldh$xk)3jI7;oKu}G4tKK>Uh4}z=JQlRUMt8`8D0}-1qnUK-rIAQBy#ar{dA6z+%2AxG@juyNm?4+ z+Ch8Tr6a1-&K>R25!Gq`j&|vY>a>4HyL7ZeNBegq+w}&jJtXr92I(S59il#cgN3g# zQC(bLsrdAMV>ibLYUkXmu_m^h_ z4I~$ad08{EUK=4c$# zIH$ci8s9Rpmo)B4O4h8E;WF{)pW`p}d*HIbQ~x}FX~t@k_KjvSai93>_vf!2XRZu? zg*hwCUz)ix{1xV}{F&>w`AcmXxNQ5GE1$naowfeKW%>@%{M96#x%vV%ixuRx{IAU1 zbbiUqWxvH=n#;o1aG1q*mA_(sU-t-K&*6Jo(xdLC@8htORkCCFRuFHBPbGhfV#4=w zm@6g0N>UVs32HtHUnb$}KYX!dW-iU-qSMR@LioxNWj9a9tjrgYzKt>~5#ehotWbon zsIYP&=_IqFA)3&)ver4Y&mi-KCVC2A%9644^(@a ztMMfBg{-gU{ycHPnM+)jFB$GQf9adQpnRw~ydBTJy_6{VFw9?J=F+Sm=C2?h=5tww zzryU?J$>7P@?n_2Bv}M0F(V)DDu0DlG|gYVQfl~Z{t~@}S?u@Z!~7MRykEIYvSMFo zeMiYKNOAcqJ&hUF@@2)0d>ACdutp^LFiH6&%wJ(mNnc9hj{G$xai^q2&1$ks7k|oP zUVNt!RNrt~Z4xhO_ePSACEAmvomm=-5|Y-zB>CBNefxF$gDt&-H(6s#QmR+iG{q&%R`wV&-YI0q<2au zy{XZelFppz%@y4kL9{Y1`KTA8Mj!BgDLwRq9!i1t=BOW~y%|w@QMW&-4;D$1pmw81 zX`uLiH%j{f`%yNKbG?AQsJ%Ni2Vh0C8+G;|RRij4aSzVPx~LCl22mqe4-Le6rXtr2 zp+*g$z7U5{t2%HXR}3NTfxXTEt{F$Th<`Qxhmze>f=zIEX8TlZIerGMKs} zNJFtXsmL`WIXfIE8FwT}`@@G)rago?Skerp_9*HN#{Q<_uloo`V6~&2LHYZ*rEvD6!eWlTk`*(;qB_DZG8an!1Vt;|^Jj3bQ!%KmU%I+Mx@Ms_iy$@c*p z2OP(UvJa^~P;={e?z0zAQtEiH(ZJDMGl5)iZ?2m_lFiCK)Sr;f#S_x`cOr9Z6>MV0 zQ#uh$_A&a(n@Gw9PT(jzTdP4D@p5^qy!5%60L5>53h`n+xT9{$Q7R1_*@BWCc~Ltf zTc%Ill6&sRi*-|84E$G+BgKV*Be&%u3!=z+R$j%2>y;y-a`pOkaOg@8qqs5Wp#fB*_YTn+1RPI;)%W!Al zNb%YB9NCa7hoqzOkaVmSN0y^xV9JZ)!VE`>&xY|Ufg>xxO_D)|lPUqX=ScBlLuzMu zQ7cs=NmYR2F!5p~p!hQIV&KcsT&118BdIA~90`p1F&=f+TH9H|;m zBanD;1iVv_|HPr1Y%xKO)pHQt1sz2d@Pv6e%LzSFX^HGf*TQ5N_C*IXAdu4?uyMKX-Isw0WkFs6!= z%A|9f_Sjl_R=gsK*3nOz!=z{R^quA>NwkU$qFG83Z6SI`vyr}#3)AAFaY?jA=nF{? z`a&*B3yX?10x4#+WDZHR#hE3lf){+|AgN@efbb5Px6xOjqyk+pp9H#E_X~Hgn*L7s z)hg-lho`BWK38~3#kAIw>gg+{?-AarLi&E;ZOfx)HtKJDEN&sdssMbo}62240tCjIp?>92=3P_*ZWa(zRUq2(0$ zSsEa{XHlSNCG?1%UT>-P`0qbM!FJfyHZ1u3YH`WRS}_gf+1cV5(N^da;k(j5>T}&e zoTj@6irv*`)YW>1aF6_ZhNsQWE>53F(<{CzK`+TaMG=n0mxWV`kWU8jhWvSiUJ~_a zbyxSuf`%n+Nn0;1ZV8SmkjetfQYuY^YqKnXmp*2GrhSm&i z7+N#alA#SXzqBTWHmpp`sZ9&EWV^H_+odhp9{!4u<|4}4lk`m$gJoy81!^5o>!)pz z>-0UP6%R>|oq+lx%l9Xw^-6sUw&H376wkLJwWeQ1`})Gvz8dY7Z9!_un~9d2lk~Ni zSs4v>RAI$bn$ECtrS;UXrl1wpBDA}DH63$lX45ta%1{fJ=ZYpU9IVsgc`KI zn_2&r7DlVT^4X-7;JPVA*QG@Jnl!`LAxSqV?ypTM2P{WvEvU5;uoA~P&~*i%#);rT zCL3xkPcN6}xMoVfHPiN1k5;3k3g@&kg-nxOaBNhIsV~BeoFbyujLmL5Ckv$Zm*QU8zadZca0SocU5Ase4y-Lt)2kJcomnd(liHA~GMLC+Re z!=;7V-mWLC)@kiKtbG5oU61TKv|1?*jMgbNBghV^nelH#g zYnH*@O+1lVtt^v{HKn1uaO>2TW@oF;MHg(qGF~N$n$VaS@a%O6-;RRm}v!idFgnS(a!%2sW;wE@>7t2V`^&vc{6;LH1Xg4T9CIwDh~;2TxjhSzxKp zrKOkcRnVApfl7iOJn2$odnG!Ob|vEnPg)mQU}fxtGk)--pOLLku*MPvN|PgNEKy*v zLYAIKHdh5b;K^cHc0(GOH6BY}l)X#Zfu{ zT6e6z>`r-qaQW;KKgg@6flkFI{Yd?JqCu4ON0-Rb47jW;nx8V%~=Sk)i z*EON6PRa}7!`jeZ4&_=;YzmacPCfdl8Bptv8fBXU#RWA}%CAYk%HE+lHR^M9M7zp@ zP3MPQqxwQ=UnHgcuWsNBly_z=OQJmp8wceEpAr;8hE>|XVt5_bv>XS-6Oh3*XY~< z_1r#DqdV59#hdj$=8-jOVKbz+GmgEzqjL9c>9xmJB}wXQ&&Frq+0#X7O*)mSYS6iRWO*xCxQAW&FiuqJ6< zCl)I%<}#`Rb0f$sv`C^c8% z!K9A$qS&VBImQdV$1zdXJ(Ie^t2M6Ki{CsG{?{2@v%BprdU9*{zszI9nzx4a8_akc zMDdn+HoHw%V`1JK)x5Pw z5k0B%fiOQF&|G;+*N1ezAV?AT?d!uF2L-iop^ihE4F~lb%y)-0Ka;1$e1~2;r2o&X z$9TF}6dMB+Hnn%L-RYx2UAa;j5`C2#O zyB${#W95T2MK+OpR{hMqJ4Mm-dnM1zp9{LWRJ5uyn*NyRG4X`@FWW@X)0-u&_!aOz zZr1&rC^NxkUF{a#rQb(x(e!B9=*MOZ#8?LN)+Y5h9&EHVo^9loc222($3)TDRJEt? z9PdC*W7Gp#n%05-N3XMDVZN^D%#1K7O7(mDCiwq@`YVigDhuOFAJwz?cHX$@g*PJe zY3+R8KCCAjb>{E$MyxyLW@_;=E~v{(Wn<on zj2zc$STh^dGw=((<0*!3*f)5dnOE^cV{!18s6V0(;F%Wbf{||jf{DXRnNGz){ zz6(D#?Sr55I{0c=q(h_b)O*K8$MrL;C~T>Xy2swan@US&bx?JCQdjJ9kKY@q!<&s1 z(!#BJf`m=#Oq=;uDAA$A&c)6p#71MjjR}gf~2hk+h>nGID_C4UyG@g@QJFY%=P6xhEB%YZUE#a!+Mw1#B zinV)8eUF|4zfQ~y?-!%*63K-=tsc>LGv6H%MGMlmhegqe=$%8N zwD6$%?x5~xbaybc4U6{z-EY@BFA(MZAZ+jw^WAXiGWFw8{cJX9-r1mY=R)h|bZx}w zCF)nc44n^dhxN@4{qN(V=+PaaFLvmPIUHOM$Y6T>q|OnY&dP~wIFNoI|L~pRK?C!L zJYqE%e+?=d8N{-P8B@gZV$TvsDH4~P2F=)uQyPsM4p;iG|qN*T=_(fw!!MrBNtIi3nG}#ai0>U#xi=C z-7ePX41KMh9Fp9CURbMde@OrT!K_*({~8|}l)kZMBpFtzA?!AM3DOlU1OJ_MJ9E?MWlOEkn&Bsf{VyHXf)&ZmhutQAQOO;DTiTPK~F#bhRs3 zfV)K*Nl5=5QAQH-UO#IwCYZN8OM}s5jp`T%S7%(WYI&ri{icmVLDGT-4D zz;lJ& z?=TZD>6KkN@b>S})gDo}O3&>LeYscHcz9-Yzh4w>M6VwZ-5+ED56+D48Id!h==8(7 z#tuf3j_43tM%PC&)-0@lm|tQKnD_1z_kjDvyia?>zH0ZzQu+bA+18tF8P^|YO@)3y zcEE~YEzuk68+rg4pPvANg5%CAZ zUFs!LACa1e>^8AWd}V(LxVue#x>Z;6LEd(XVw)gYJAEF*wn1w*K(e!mh?yDKVv-h!WLbb=kA3ap%37{M>w*JRGHgo1Z0F> zz!w2#oW8)GhSTuey%3Q?V8+YvAI`&n{0=X6{ujwVTDFn@9@}XznDeQe(;w(l`oewW z9*KQ{_! z@t0sZMB5KLjaUJ;17BxP#?~+sj*DW?4F@@+{j7zsk;qWxmBYv;n=-!F%rG@keHZ^=nIgoyPe0x0y(BSyK;0ZG6zQT$?gJ7MI zONB1SA~6yZZzL-(B-YqmB$}s4tUZ|U)p@SyYqSI_A^dBWe7_4|%U4h2fEzYbH1(UHy*SmvM=tC|ex=@$oZKkxW)?>FSwvGcuX4o>?~|hqbHcXf-j9Fy7bbK%bB5s&>8B zUH&6yalKY=uNLzk?P8tETEK_~JV5kC>alQ-ME>WTw}iugW&(RI&_>pE?uA~;edYQH~vsY98vqod3oUYp1uh&xfPx)WJUM|CbY$UW8tJ{?G?w6GF?w!bUb2{g| zdunm=4+;)To_S%9TC!erz3z9bO(UWsx+m&AEIO?F1&xLwQR3sE@0b$?bw95@0HMe1 z0D6Qd50R*tmjHfbE{rmElP0D`bZb^mi1I|uze(4d^wgT)vw-zKnwWSFy-!vIGE9%> znjhUerl(Q=qk+?2u>USPnq-XBlm^JNE!X#FaE=G zqj=!Iqik>*y*H~P#@gWdr1;NF4Ck4DCv+eA56@#S)Xuz}^WU7eF7iz3QIJZ$`y%om zJ;MqDOalF4&bt>D$Nyq~UDW)k*RGY{G}S-M0=51+G*7+PjuF?mUR#{Mu2KKDmw)r$ zb1Ph>)z&JkY*_c8^;27jo-xneFYbk<@ITJKo_Uc*5ODTb=bT3l>%FGJk&e}(x^ zTr>BY*85BG)YW@U(Rk?m=rtv$qAJPTD&2;^ZeChvi*y_IkG-b$mwEO9cIseV!I0{%{F)kQ^*!;}WL>SOf-Q#~5`zQ87Y6YdeP;dY6MY$D}a=y90y1V>O zBL=wzTFZHJI_G?}GwG8k|MY`(lk3)0`FERR-_y}_s zJ}Y7=_)(S*SO7)bNLv!Q0Uzw|D(1%G zT2e0$_R*zn@EcR9z>_(xZ>9gERPc7ohTGW*H`=$sl4fq$PZ+Vcyx;F4wu79~UV8~G zlWtF^l9}?sZ?|mt?S5n02EQw|A(tGt$8UE_nvIT}1NN6TzTJO6ZG%Uk|8m+A|NSUA z^*r&YbW4iHW>FjbF4munY{s~`;gr!8@7{g%iXddF?Ej&Vz@8PgF_+XnXlTFURW zKiO||d!ig#8__>;q#%`XTw9Z&VTydn_&~|GV`a>`i`))o>ML1v`Fgd%F!a=TJdq^_VzB_5yQvQv!9nda&kfzM9I7ZCsGxqI)HH^U{pbe?9{!n z@1R1+_%YTPU-Le#Gw}vvdl(gRK-XZJ9Wmdot7`Q@AQ~zfsp`g;rw!t=n{*4SR9jCd|^Cb$@%T zGkcr%$GS6nyUus&>JIIs^}P1UdQQ7tJujN+e3yO-&hHtW@6z5~&xr5O>Ri!IThEHV zLr?G4`7ZTbMOWaR?pDu%_`65vm#OF0>FTJ?_oydX?GcY6Zw@5OMLMY5jdzOJ!m!Y2 z`21X-n7Zb}0h0z!jddegcjVrIUc*|T#)-4@$bAOeOTHd;1L=LT`DR7wce4DbqKoB2 z-XC&(nGQ1l$=;&&^)?~b$R2i0QSu1Mc0sz4bFvGm@r_m?BW6kzJIOgq^YT@Jp9aak zQ&JAj4TLNRPEc@@T8HlzC1;6IK$Z=Nz-uL$`$YHZ>9so8c?4YGNku5g0@$yor-WBJ zC<+#k{LjOp2lX?m0~`ssKdNbwAqwvAlzQ$t^~Q7RBM|DKr>a#Wm5o{ktxQHHn!u># z>%^7jcx8~vMlILkl|hmlwcLnNP7%y0MmfbU$9e>ymQ%d4k;+Cbui}-f)m7Z+OA|M` z64qAKJ|d$8E2g3Y%re!Gs8dDO5cz6obP)JtXn;-}mabt{PVNSJo%%$0`ml1aA+Ywq z4{X!#lWT(4WSjodI#K@Ow(u8?Uq!zU2R%=w*pPn4iX0C;-av9Pwn@)AC&Rl)+qxk# zOQvV0wqQBXZd%Q|h?0_p#=BUvxy|I7fOU18H481L#rRXPg=jkwesH*8n~7x^w`O~e zXaaRGsFyUa`C&?wcCw0|7NwRF8k5D{D3~FkK*L< zn==FK*G3VD-`B=(;6om{8C9PU$?xyCr?D$+p!x_FGEp0~N~0!u)Cvw1 z$4=lz@wfBU#I8n5eS4I>Ui+<5zd4zz^%2wDZFtgp}qy~bFlF`M$= z-r8q}#ae`!DD&<8>i616N$>sjoqT)iSP^3|u3gc&sLZ$bCPv;ZJ>PncV|J@YDqxp@QCq%mXRdFC&sh2#$0#d<4=D5P#WK$r zuk~1AY1N{#=$Dw&L@zW)2w`=VpW_;1V^Q1h3evtHn#YDCHme>RROZ`zspre%(qcq5 zpXDP5TICTfb&f0U_tZyOr03IqM;hDZP?d>^rnXJ&@!Y~mV{-N1o?-&Z^m}i<9jmey z4_991%YQqPA7y?qdcN~-r?2ZreTqUzd!LaGAL4kAGhHj2HcES*I~RLDj(6K~j>yJu zU(9&#{M%F8ro7CzwrLy3J9S2L1kAZD^F=moV+_8r-xrfJxqRcD`K}g!7NtG63D|^?bdO*v|Ij-f9l@1N7PYj)u*VVe3p->>-ukRE%W7bH5vQOuowN&b^RRgjs4!u zZ(m71NM;2_3Vu{Pns`O=E#gzevpAwN{z^QdSj~7v@q`lT#VZOn56>!I(OA_VKPWyx zkh6F~@q*$X#ScoR0~zf2L7gc=#TvYz)vBYx_FASf=VC-m_i-q0L%Fx-Xo48iUd7`O zfoz6LS{w=nJzmroDHg^uV|0m;3&lOMxRzi^r}(TC31XS?8&~l-=Ef=>$M}~QD;~$A z(s`w|m>|$VSo1{R_#I?U+r95f2p$_z!=wN8=D(x&M|skdmS&3f#8?pHnkdny0X<8QBbzjN;@@@N!|g4$ki6#-i7+*9{TZ*m`t z`2S+V6FB>=k^gD#yS0#IJ{<*EGhPRDKlitu|K;>gr*Xb0`KcEe`DYfWuaekV?FZHo zDW)OK{Y^0q<@w*=-1mC^7u%oMxb+nv(8kz8vGxONxOyw7dF_Wr`xC1?Rvn;!K@FxT zy0WzgQu~K~H+HZL|IK-if|%*s>)H?H`QP2z8!7+ce5?S`Y3&Vc&J^3>3QT#`rJVoy z{F`T9JLeRiF)M86??(RT^?qDSAnJc~Q1@z|)boF7`Uh?_!;>MC?P705wP&K`lgFDE z6L(BCe-Z!9XM7_4tNl~Y|HaxrAgOcYbo=;UW9+kt|E*)6Wn*B){I~RDg<7inTl=b> z|4WnqPVN76{w<09!&|T-sGWbEQ-If}QT|<_XE|!W^@smu?4OkXovy#I zg5t`{n9dvl5Nn^*^WV9(wm(zOyPktr1lC1q9V~oh8|>moG~2bDL6{Ji2J1mQ4ul8sT4HPY?q{qniB=OUra}#~Fl#+xs?6+p z?c471zf=3OQUAwL;EMH&ul-qXf41X)_iLrYeI$aoXLlhW z$vd|Fn6APxVk6xH!x z3G;a)A9~?aF$c_zMwx8K2XJyA9I*#_Wml$F?Q*RxR>JynCHQz&f}dk0D3Il~JtT5os?f^`OOAkFkR?t0MgGnesl^&GM{jzr8|r-fq>I{Vrdj^Q~d;(_2-& z?qOZCKk8kocXy{M-aQg(yS+-3T~w*<_Da!P^!x0aNzJ@lbUdW$bPwq2jOyv#CrX99 zGogy!qk3{ib?>MI_o$A0RoU)QJ)ssJ`*KnX&-L$?RI4Pll>_*Q!R|+f*Cx z9jcP|X3;mR9^N&fhTb*$`L(J+_Oxo?U9ID7qHohruGVplYP`KgKe_Q3URrnH6uJ7YAqcobNgi zzKh*I$Mt*cbiF@(`=RiShx9uK^|#;+dxlQvufl=DI@lSMZ#<%dcT=B^+I*YTA~j9H=SgPiiyQTmsf07}joMzVfN^pt+KMo%vZGIz1~ za;<){UB`@c#3hmnB=Qn*>)OCGY7u67dZ{Qi6Y;7XQ(s;!`JdB4W3ck3tYQcd;4 z9XjUJbJS9#XHTf7uhP?<8Uxft+@jhDEoSqk@Mj&-9cZyP7i#nL><9oZ>a#mOD@_SY- zWtU%e|GiaT!|uQA4a|>X#=d`Za ztN65fkNt_+$(TKh=@)i5J}Jtc##6e+iiFSXi_8wl@Rll&R1||_lR7p@65-W^4tDm1 zOYE|Ig(!O}vlH`WqL=BOy_rvlvLExPuCZ|GLH2JxF4;Y%E2?H5le|(dlU<)Lk&Irf ztC1i@>*{fzkl1JTA zYSd2Xihj4oIuLpsj-kWoakSBx4tg97G^zuS>YmWo)EJ;nAJyxy1(^4#B8NqQb$~_5 zN^>~$9QFFBB}b1E!JuxR`R#0*G!L(zb<&&pbe+w>{E3wCHRboyipXNu#B(Kw6xoqh zazI*{2jYGbj;T7MzkF>j=JR&>>_~OYWM>a#V%qF7#N1WH`E)eID(&6R%`L*FQ5F!Xhx1{jmQq>?T9RBhN(|$7NwZh zv~~>=fIe$J3Tk^H=RY$>tDO=$>xEAE-)l^Fw`z$r##EcvNh{)iKl8B5@V|5Y!z!m) z4Id;e)@~}&KaDZHGC3tFrn39|XN7`Ck|?ONz|*}4h`}4CUsEW>6d;YYH3QSSdF3&E-NAH};XnRxR(`$O z2c-=EyJ7!$Ki6LHztR50S5u~@Q!)Q7`~BDhrVRhf$$z&nm7QYx;5KOPd=-{rnpk-i z<Il%-7>#B?|&|hkO?sgI@!$8&T0&QM_*Of4eCDHrBi|!AhCYHFNir?zhRZaTO~( zZFpW!$fI?sJZ6{a>X;6E-dF34Ck=1+RigON@Ni!lC|;R6eR-mREX+46(T>gdQNW=HJS}kBQ)ug zl8I5#?fTsZMPD9znHbUb5M@G(J*ggkQa_)Oq>YFo`!l-7=ek}$Nvobw;cQq>hV?V- zTxzN?^MIMb1Bb1+MF)6}HM-gy#?xlWU#4qTh13ec1GiCE?5wa+(&QZ+CUifpryC_1 z7fB+{s8?aadqmL|Gdh?tiAcog#1Y*Qqd+%S zqyyPE^ROsUnk_nrR1g`6x)FO}TH}4K=$fD>vFxXG5U;>eAX{lrbU;t3I7Y=u@|Py0 zx7nG8J<_oijP719O}SpzSP57G*a^fcHfGf-ert0Xns<`fJ-3`Ifqm*N0n31vV%4)k>*XRUg~w z4gZ;+YipC2_pPRD>vUDYD#Kpwv|fY#*|k|KL<6@3c{S&;X}zZ{h&yDKwURBFHIi~{ z9lQryH14o?z&E;@o^heImE+QyajqhVebTIMTA8)QxyJu=ZQW{ZXZ~XmZhk@j-3#VC zHOHu82+z?c^Zco_4A=!-O8dL`6P><#~snz;W@>f0+5TUfepBgPh3 zoo|soS}gyO{9f1bEW>~77S_`hQEU~~)7UBCNe;<6!dk)80saeX1y9ETjjRD(?bCU` zM&h8Z_UgP(V{S-SRNNaD9o9A03jUAvqG(H2(i=pvS@3)?Vi$Dm5-+h}syY@l;>UHx zPJK|Uot>hrp;=At5M}ku+H!~VJXjCbo3RGUw65@c;NxJG8vP%{F!6V672T?*BcVlj zH^E3VSFryWC=GNKb{9GXjm5q+pf;k9xh%SY-T#bkux?weNzRUsXv&pz65G4mmB8tdGA(fg)HZ*2aR8Qz#y0db7GAy$jt}%A9$cmketYj?qG>NI zS6r}68+siZD{e#o;zMpj?_(rr6>FEq7)d)@vLCigBOm(jduqprd`*MDB(7t;zVT|t z>zmru3^pwJbA!PeVI_$rOBUTwm?>*lmdmlOs$bo%gthfb@NcaIA5TB?{XxW!NlsY@ zc$aSMVRmR@4FJ-a3h3Cz?BWfwf^~rNqt*oJWHtX%LVaEMD+8junRl@6U(K~I%BpUb;m&-8g@>JoXC&s#GP2P=u_l-OUCys%)kP&i zw7avCn`Kqgi=DKD{!3fpmZ9qggLGLFvNFcMLrb=*1?5|U{NO#pr-T$CKe0-sWyas0 zwgE0!3tKbi`Ng!$E$nU^%xC%o{_~xY1GK>JqE+xJ&v18NxIOK9q!l0hc5}mT_Z!nT z_+7CLx#YM#e!E-JOe*rX(+8Hw*b9EU|9;vA`gr06NlRPezhB#u)m(cttL4@s+CAhR z!SjJF!q`L~`@`_~qZg{xc5Q?Q@Mtynz4x`%a*eTk^$k}- z?mM=>_q~SaW4gvl8WSa&i!5VfvGyT8J1D6J*Mp_SSj7e-6AkMMjew=angbiGT7}24 zaurda1mA%6Kx<%4qB&x_Xbt=M@MgY~aY{?7RkG{JwdYN=z#}?Zg6l$y$W${=M)W&G zuCXb}+vlr2{)q$et>p1D{>%8sJtKjq+oZM-C!=Z)k+AhTs8O>;PvIarg7Ax)F?<<0i)({V8-2AyEuYhwFB}rZKTQu!sr`H} zQ6*c**iKk@tMUGF`$5Mns(cUhrPc>s32VVJ^1Slm&5WI0VKnX1Xd;(waq&)ipcnCe zN1JOS%~)R8L&S5i;ThG_L9^7?M_hWm8QZE|yptKCS$+Ec;a!%)F9rYka%RBp#{1#< zfR6fH5@ey={s4>1C27RFtj7BnC;zSaU!?zg$Nzr#$jj*eQOPwn#Hc718g>R1VRNf- zjiesSX;PyKj36}*KpuiR9ML`gBJYij6@-<@Y8@*GE2KB`OObvngXd_RUl>zymLXRq z&6O^~bD(Qtt$^B?7?!W2wX7eoEQw3O2W&R-wm?vVqs({0jPYA+Imhv^ZLy_e9A>e( zD&5G{idwF|RzsRA$J(NH|E086K;!s|z0hiYZ-pl-=0EET_d&1Yfn~;5vHV9I2}obi zCCo3_@kRO#nePNomhwNvvqsM6`_Gh-e^x6-ReJx2GW=f&xuV6n(r7R;uBe=V1|ts( zX+(p?{jV6iRUM$a7`yX2n(u$r|6E<qw(P|M%5^b1h?O@+TTL_y8>j#e^_NQxTcn0x2ZfnYRl(S08$baO2FVLLP zqe`T@D4!vsy2&ApR#10p_2l-aHGebC_ZBBuhX1|MKaumPm!p;anc6?}Lhf10v($_7 zNw7k_3P|zvjWcgrrOlc@q9ff4%Tp_?U-IwuwMRieYPFfet$U%9T4B~WXd$o4T5BHU zkM%8a2v&G8ib7nqBHe|3;#zs+66X1XY33lggxhqqs%w~5G^EDiv<~vAsbWZ7!+BBa z9BxvcysH}$jiqMfqz+=TREwO@!8-kjuBfa^RA9aE{Zv>zA`AGi?nZ>}Kdi4pmkjHA zMBhhT280hQ{6l&=B-H;Qec?e}4Tug3`F~JXWB?FRAv=I9N_+_WMX5cxCS*}o#G!q< zCw2qB!0>?GAu>ZO365cdM?4U*DD$+Rn0&WvGJG?uvw9>GF?M22>%>`BX^weM1x|rV zV14EYI{YOzwN_sNPnjS1qAA_Mi`vSY@WU}EF&_j2GZB`lv@P?!N(1k=_ zrZoOpZQz;Ote;`MMT`=b46VTK!YZ>B#>$*l(uy^rj4WC~i?Bg>Bl8P39@ZR{JZKp$ z;@z~#nwS<*m1|RI0c}E`qbX?<-aXBehu6;f-L3ymeX}9m@6z8J6s7jr zLTKNDo{;amPWSVn{qv#a_}uZf^Ibc2;ODLAiuEN(sEY2vVP&FVpSG+0n?yJ1ekOdy zO!%%DJ*QU7#<14ni@=jprG>hfps|W;l13!k2Jw9**wlOqH@k7(-Q^!N3J%9KG+=kVmgc@_|00E`5W0iclbZ2H9wNc zYCo?3S?zDvfn-uMDDG=Otu6fDcmaq(Q$t`ubV2v|z6Mwy>5c{?x{Lc7FxD8uto#{q zjA2%$j5x+HD}VZ$F-(M>zGg2^BJ}k2m=4yC^fmE+qDqW7R;=I@>1$&C8`L7~g`$;Z zw7+a`*+YUA7Hu?eIcPar0zv?EKUSRgho^P6uUls_l#%~gai5HTdI1EPIZwSNS8*!h zKb()ffVYLdpcmjgeL*k4dHMp$g!5=q{4a1GZAve|`BanFTi>F!o5(;|9-A(%kY1(@}KhGoR9l@EJpq#=krmpbpBV=Cq<*6wilS& z=|kogMuA5~%wr*I28r)Huc=@BUzzgXod1o!1nZoX|IUqx`iEIR=YJ_%hwJ5qnVr8|43&2Dxlu}XHJZ(04#sj0@zwu{;UO91z>ry7D!hC zjJSyQz}6ZMwpNk-kL5`=M(hQwQ23wQKSlntrR6cU_u-Y{|H{@ssr?x(pVSI1XMYy) zzt{fDGW>66|9D5Uv~p-a^?%C$#oPb2{O_OdwhaGQhWt0$pSJvq_#Z9*bQRWY{e@4- zx$L$6dwczRy-#)-{B2=o3+B zRv?}5zsUc5uG*g~p*}}9_`lNZpIXmzZhyvEAo`!%@xS}H1w0;|%YQ#HgZ+)G(j$AN zAJ}V}NG?0ofGo%Rv0DexRlFa&bP!!7lDnXT=qmcCs)HCS5x03AcvtXH#~q}wI(O(G z#!8fZPR9n(4Z+7kykk}eK9=F&T_NhhPC|HBu=j{;<6R-%&KdIDnY|$AA`a4NXv3;Ii1Sf&5siRUuQL zYpFrQT$%SHBc;=RqzB!b?m_ov?7@7Dw3gLWs?lPM-R{e6Gv1o3aCk6q8GddT7vVDe zoDqe~@Dq#*T!x?cH{mk;#QuQG@RNPL;4)gl9qnTRz-%!@Ps zJK^n0)3=^6Q=7y(AWYw8V&W zr8XEALbSxNzOWgv#IOyp$FRhr4F<9Z+aOwE%&3gxXeX56t+{IHb@d8MW4iab^QPk7 z=e4p;oigyUmgL5K&SKv7!oKBeqGh`j8!U1)x5OHGn`_$IS|NF@3iB=HEq@mu4;)K5 zY`#U!j5bDZV6md5ogZrs^HmWAANB2W=>%KRW%_aPc0v(v%|k{4D_D4H={1MVv6RE^ z1#>S-G8{I~t*y;rkD8d{ij|8^+u2+eE!*4@OYPfQ%Qm;f;yT5aSh_-Ku7A8j=@xIT z36Ng%6ODtc@%`p=oWGV@<7R2RUFr6%>oYdWtvQKKk2`2auEKfCt!;x;Zc|yc3^z(_ zsuRwA-ZK7bR}ieMZP}*0Wu}b#Tc%u1ce%_tjKziSUCLgU%dKyFwdQ5T&{K}w?_%K9r^|I z91$S!zLB@J^+0RoHhL0rYvEk-gQaWUl~C)mmbXPVSoALD-mvBLG1mIwo6lt{VUMA5 zygm1PjO}>4QfhR@m?JCap|IKm1yEaOWc7Ez`K(Ofl{MpmyQcXck8^Mt7D?ObSAgrnCP+W68RddfnJhbtTn@YpeM59 zy1qC&A**4huBpEdJ)T_}*7eX!vnzs+8hS-`xx8%K1HC-EOkTH{KrhR#mKAqZcBSam zIy1{$E&FP#o@~}}GFV$z%HG*?&;>>AONI#229wCJ?XSjnelJ)h353o)$IiaB1F zoeHtY>lAZ5mE9O(k*8#V+?d@Ux>4sbU0pAFeRf84TzA+bXJng<26`sDS-o>}c9ZA^ zoh#X`*)5{Cg?_tT=ZfxcSO2Zo?~G(;_45&3omCHx=z5I~JWj(pyH{CJ;Yp;DK-#PL ztz2io8OiiExybea4urpgM}v41d4^lUJJ}C`xaElMc_X}|stxagzeJgd6%r$K9Fdp- z?`75>5Jjfwxpkt{hhz^0Dn*i2Odj#t(D&pM6S+VprbOX3QnE>uSUS?f!_yoyFh74?=zMMrf{ZpUGLCps&lD&UQG zs$j3PxOWAuW&FTzI5nJAtL&9ArvC}<5g)U&&K=1icaXnoJ>VR0{ulEGf0dC)RFCmV zRU-J#nl96QMSr`ZD{BybkLnQoEk-JTi#LK|My`k@lF!I@lEpZopV1@qwOh}eLjr7y zuabvGtpX|&jO&V3*ZR;_DmcMQ{t}eG0Jqtpi8t`Y^apo*qsNuM2|m)$A~mPW0dM;^O^z96CKhSimo2g0a}2$U{J>q(Ia{~ zpeIPFYmuS-U5{*C7?-gk**-m88|DjU3;J$Ppp0xrI(?eys-gq_84H|d{4`?jdtb+j z`N7_-#yBm0l}&1I`4~8|gbc7N(30^h*ygv-P*`0&_#rTu>_s^*Obk z^Ov6YkEK)&vy&o9&}+>xJIn%$t+!leE-?0=*_Em%X$HJCz;5XQs-RGBqcc4adq1y$ zg4GpkZw%?Gxb{hzxqz>0R{Ny64D_@1K#>eI;$M1)Eh?i2dOsI*Dg)h`3(Cqs@9H0v zmjPRPjsP3)kj9D~iAy8K#*f%0wB9JP49my>b-$0} z46D^&8Nd&a_kL$}$ncPKw+>ut39zcH&BONC?{yuB)Fy1ikGS{Uzo`s(1?X{|N`hB^ z))i46+GEPf$UyO2fNhYk2o`S-l&OV=o~gGAx>pOWNCtXci=vDSxUZT2SlM?U`&LE< zdbuvBt;Ckwgs#NKywj{6UbpN4yhg5vS1SYktA|l61J(ik!045cf!^zZMw_s;4AgoC z(rQ?FH5zP>`pSs4H95+BJHFiLKes>KzIA)jQr|o%Uhu8tT zNMs_mF1|nd+oKxpky?nZjwN!o8 zSF}QrZextrR(+-4i|UPHFMw-9$6!Yg*J3=lt^pPWRu%dH=_kU*2ubT8;GqNwj^3ab zuqp97k$J*;llUu$M`FL^F<`5bAxzd8(MsZPy~0HDWyI(3%^A0cv^B#-t_&GS?cC_` zY83-%v~kb_vF5CE{*i~)HGh!+#xT9_9*?=1NP_#_@?c3|+^u^-66k$q6YqH2UIyrW zWB{LKDg(X4ZZ^sQUe;E7xiem(=B$r{^pmChfkqjqtvH-pI<7d(*ERY+ zEd$G2_hdORruCB08$Ce$yWR_)R-IvSpuXoK>#zZw5%0knZ7!P>wY zAl3P{39SumJ$YWR-YA+8JPV}rLZdclhu6e9!b&6J;aUOCW+$tiXdSz3pI{Mr?BhPs{W>2J-KR7Du>wke*gdPz_l9d4Ts4$OUd7u{xQ%TMN6wKpxU0os%+;&}q<$+!-lqKs8=tV+3 z!h0zA$IUv9iEhz(T345gZq|89h{qG6;2*KpF4wFyr6;Tzp(liYoDk;m3Q-V|tgNom z2)sgQM@H)vvPm}TdQ8VPqT@P`>gsCIF`YLA%;N^#U#II)ow4#yY4$snofJJOgd?lg zQ_@W%x@J5;K|$UwB;y%T5RQYoKP@_>Gvnd3C@9DQUEM6y|*X8lvCsXRtDLt*-`=luD!LBD; z1CObI%nEHx_h5{ucnrV24+r?f&1w_h0>{9gA;tD6L>wHe`(A%L$WV}Cd^=dO^`gdy zGM|7e+oEq`jRNXytK^t93cJ66O=CZx?Yf>3myBLxUINQDA)XN<+9AqlVU1$^8>6*`ROZoO9J#SrSZNFT)u3O)Zmdj_ll{?3EtKU;S?{CKfLEE?g z_E!DgEnU~nu3JjKr{5mGx|MCyO3!y|ekb<h*m5cE(qT zukZIxW#0LZ%yI1LyYxA3DSDpSEuZN+pX2ZhIsUY_>vJ4qFrVd{&+qBC$Jwpy{GNWh z=eVse%<{!^96PCcS3Ue=oz3q=D;)VGf{6sK(}4|x1P%n7#;AosJ;8=S^EgI;^)jIu z9GeE~Wl|KIhDbG$PLMRjJVDryW$Ro^d}nwN*XkL$tC{+Ul`=WB_$xtOfF+??A9=oL z4SaG)CioigHXtFu02x6N_kzYk+N$rz{=ov64Yt#iD4d+vfi*R&JLF?tRuy&-)u-q6 zZ&ZJOUVoR`)O;fu(G&8pULzmu)jF<|rxw5KRlx^)rOv11!Nu=-MaW{mB6wdf51!S_ zgU9u9{p1FDf-jd>^+fQmo(TTc6MA-9e&iGKr(PPote5KUCi#!?wI0*68|95Yrt3>| z+#*jjp4*FccZ)pH_;4@M-5GhbFVgkV;H$kbcxEru-EHz^Uno!P1=(HMouX%TK40fM zD{7tXZOn^e@K*!Qs{lzy`uN)ykF;g z<(=Oj=)KuPvbFXF`cU?ubo|~xAIu(*MY<=@S7Z*<Wo+aHR|)%WRHu^=)5(1ZT6Jt<2vKve_Z-ztDbDu@ucXJ*&9T+=nk*`8${obyqK9dy-9RRclh?-BuRNw_D0c3oj2<0TSO;x9?zc6-Xi)fI^$*j7Rm0oo{Z{v zv*?)48+7&dAmeYAw7)%jo9G6eM|Aa8(YI#LimulkUj1h^Lf(-*Bl@h)jF@LNc82t1 zAbVH#oai$;v>_)d-c=d*7W{nqT;L@T<(hxKjQf7TiL zZP~YH|BKGhZ_nN>`tIyIvj16U=yzoA$^J&?_hf&oGxR;#cZz;z_II-XsN=gt|5oS! zr1N)Wf2}k0yRz>V{qF3&*;s~Isk?up^9QnT==i&$|3>HkNmt)5`u*7lMZclDKiBz#+5f2H zL!uwb{+{Tc>+Uaf{(IS<==iYchqI4}{)O)TROgRmf2QLHME_Lhuj}duMgL6aKi1Vp zMZd1|zt;Jqq94tEDEn7BLw_jy;p}TVLw`8?k?fCjhW<$QG0~4@AJ6`U&L7YIrOwcg zXP?OaP-o~TvLDTUPiN?lWI7%&vb_V{p=^Q zf37q1C$gW+{;AH;pUnP2_CM$h{Ri1kWna}9`cv6YXJ69sGooMB`OCWcS(OxS+mQDOZJ}qp z>jhkg_htFu@1}oJZuGYeep~aFpxtZx!o8pN2r`PjWgfr{%b!tzX*4qSaQ(ZAWd>$-y@p)yX8c=e8|>9X5+XPJe%67O0=J}m8=CPU z=Rn#9*Uo9ihu8*s#5_Q2EVd0EowR{*jHR6Oq0=_RQPo`D+`?K8w12zx1Nt%69%<~0 z*6(fP($d?|`i-%LmXpR&V@X7l#Fij|Xj9e`^}UelN%Nug+g+h0wjoMOy~Mf=M(?FHV>SSZsMjeKAQ%B)z=hei(Y{a%sA zZ#S>Jn>Ak@Ibbd^3cwG-A9KTeDANYN-8}-jn{_esHM|=PJwbK_y-@#lGV$p_zuhfa zdK=v1_3vUmPOIEPq=8j4Uu|BwC5>&Muh+l8t;X4hH8%ef?GZ;rw7QCCG|xwt1T3AU z$pg~Bx`uHPEid=4d5(npOJl!)XoMTi(-{nX<}rikfF3F013n2x240V7`SEwK9BoBn zG2)wucu!_GM}!!6Xn*WX@?nNWiR5_4FFYUQ$k1BqXyK_N6J=7A3~s7$u?`yxE4ImC zSK2guMjZG+-huYxjeH4hK_9wZ%pde78U;@cRtvrk>^!~@ zDMkXQK?eeq5o8YzJ&z15wGF(9_oZ!ctB{d$Z7@y?4!AYufO*jg9~xT%H~QNKG*~m9 z(2~Z!KyNV$kqY++T%cEwGIIktfD1?l{YNk2yQFuUy{lMe=oi|-h(oF^6-8~pg0g(@ ze%?+S_}}f@z`V)38l{&NM=HUw4VK1~8*l)g&<3}F6-W6tG=F>KK-vbzhG*3JzHl4d zBTH`sykk_bV@&->?z9c9Wx!mj=oLu^AnBFeVG@`y!=b;)-yqL?+YFOeeVD&|r2FX#&7 z2us100kEh%H!?>$R}oudB8({4FtkO9MqyTggJg{139;4Ongh+GrKm69O6-MP8q4%W zBOkCJutDni(8vL1h1zd7ulQbc8QKu*k~joh^0zbE8TW9*d??cfzui58wZePp3#<>U z6xy1^gId_-I=K4+$g zKdtgcQkhTjM&0RBztX&; zmDFEFau_9$@l~%6QyZY@yHbC7H?WngHC96Yz;b*SYwJ8aqIq6K+1!94++?%y6*XZu za+sUVU#Xr?^L)zA%c&fu^KvJ)XfN!s^t;me%ik5XM|)eeK3_4_8~w7iI<-lPzCC_* zyWH%e9Nl((+Kag$o#T4-U1^^-8-xA)u5=8>6;n5Ct%z0Y7S6sGa{>72m{B&Pt2Cdg zNM|;i3mETtrd;zJIqaW2Q?7lE9Nx{CDd)L>`h8@|HJ=O0=ExO&S3mLbony_Z>k(1r zRP+FAe!XzzRPo4B<~IvnPIZr3tU1W?dc=8qtU2{RBI5jLK$#nB9#Q6C&B2$SAJFF@ z&hH3F^Lql~yclZ^%KUC&%t4$-ta(J4gEa?t4$}OgfH=>w=HScs>ZuXuIo3R)%)y$2 zFW)89xe@0tm){7qc~waBSBZiDD#Lo|AwyrJRr`&m47H8&c8pwnt!McYi^V|h;y*!AMOd(9F+OTgfTbb z9F#eT^Kw{okmjEZi1Vdk%|V*~bU>VgH3wyG#Cbol<{-^K8xZHKSo7vs^IC*=#1R|! zPUNl(&U+PWZvPh6G3XfcWAS+R=7>z=e2v*8@*Z*j&G5~%g6O%CL91BvdgLznq%wGS z;>`7V8eprK$)_|AE*|F%s%J56uoTdSMwIg^*4!Mx_92@($Gd~u0Q=T_WW^N>-kD~j z2A(@lBg#WroVVN1`t3%G#5SC}SaUFOa2ZU{D%Kpl&eCz-ph{M;=Faddp3$t0K?Ye{ zuVT$NYt~xDnm5B$Gw&Kz+h3gbD%KplUqo{@VmOWerf*iU<|&G?Q=GSv++{HLwS5ss z#VXdkm;*#_sOt`D%}DMdY%3Nc`v=85jpi8|@O%|(Zrt!H*4#Mz{$S0Ga&C_}2MN83 zHD_+Zo+{3(TWMHxs_wH#1HO7{Em2J=)?ymbHIt*}=VO*+qt5=S9cHLLnYH!Ipg<)b+rL|lkiofRb#LmX;{j=50% zh{`~B=xV2q9U=Zi-5}~8&FdgCcvpz=+^usp)HzxZB@RTjqXos4?oov3UR~`9k)~at z!qLNu0TDH#_Rzy2TC`iwiHAO*^KQkQ9#G8ZL0vr>B2bSimh_NN$B*jCYecDm^cvB} zMX8PSxag}zshRX@(Z^J2=n2tR>;8bQ9}|5{*RKopiHHL|rHB|ci4KN%&_P`h8+*N; z9a1HsH;5AbIi#zDsv$&#=*>E)-t=bC=S2@I?)JRsyF{t^^e)loM2XD3Q&;EfI8W7~ zp4Ht2I?h+^sAqL`p`ts_D$?@~T^-f=Le(RBMpqZC>W@NDh&;w@4BPMX~UX>HM_l)B5S9lFeaJ@XVKLeqAp*te;=1 z9{UP?PgIT&L{Pp5kQ48^&W25^2fUc{0eud~28h2xQHZF;->Uu%PW#SpUX4IU;&Qzd?T= zQ*W_%$FPo(APvVvkEv&eBv0pyp0A%FAD4)->&Bp@>H^UV^fM#}DPq?RBnQfl9Rs>L zDtck)F}PCE_wEzjr+2OiU%y6A@NOT_{o25Zwc$(GiQ)_3dj~|(Z+zpRD4LP>4~90= zHnb$|91iUn4s9C|#m7!dMnX&0i&Be=c5V>G0_0mpMX?F_-qFCTF;Oxe;208mTon05 zPVtbz`Hi7p*!Sad_3h=lr_ZktWrq;t;!07p>n2^1txzuI>vV?{gR@0jBjePMM(Vc(8Q&J0s!Xi?MV}eSLlyzl_$XLl~jxxD%3&;~I}c8nb*Y+G8k;)}b&48EGdp zrun_$FxG}O*4UTl$}rLyYa=>_!$@PKGs@QMV0WEs!+1ygZ_u$mj4?(%<7-q0d7#W5 zV_{^C>56KVH|Tymj4#I3c(814(pbMK=z%jj-==3oC2kWvD@xYqS`b=zXG$`ujvd z%wStR7U;ct3Z8~h|7y|4MH%(fXWXr0SFnm+Bl?=40kD7e=-4e8S|hE0tG@ph{oQJ? z+P3Ixx;>9GgL^hFn#a?*+q1c6cF)?L!P7b2bGPSl&*`4WJ$HK^_nclkgEOZyj~@v0 z*_gOhJDbzxtp2V zGdT12#p(%WIvTy|%{cgXs~(Q53%xDOe*vaYg11ba++oj7v4 z?@BTJ&XeUkV}>jiRKCL&xpmHyjajAnUQ;RFyC|nJ#YMNu)k<;fX>LM0ym#7P>3791 zV&6Evs9*a?IakXWK=rv=Mc-9M=CO}fdhT<5o?6^*pgu1n%}prt?PY$a6PZtCBW6$6 z%Y2mfxTj#Ve4H{e-zqOGmHDE)ux8)I{F(2V*gWqt{jN0sH_dsEyDZe_hNs`vt9-X< zSs**4tMFBA)^SMmko4DA*h6 za-pg}`+!q-ZKJNK8^;`hcYHvUy`m>|&8i%o!_GBS^`q_|6<4Wu5C7Q}cq*$_*Xw)p zS}@akPDTlu9Gy-K2|Z6u1nSEXQDP2YMqpl`%J4+s--P(btU)D$$-uu!J*O3LaFY&v zNc(h^>AWd$kF^)Ptmt5c3>Vkvs08k@T3*mS{A2~@S&-Ta1LE1bz)8F#J9Up`&nk*N z;js8wGtC9cT3|#R#yi3qp_wd~(ceX~?8*&rG}domzGbBD71!_%<~xGb=lXYZUOE?b zb5SnfV&~hX*b&CWMr$I^`7YY4w3SXxzpF^6Mg$%2J=b$>(|t@{Oy8C6QPPRtSc)7* z3GBAsD3Zf&d{;WRr}{8z!d7#8nekO`&lcHqsoq$%*Lt_NbwBOU)K2e)tfslqMQh5U zxgfPeJIxCxhL-Mkmdfh1Y#!`TY{t#O3finE*rC`y?4ZbegyqQYKvhw8S;PX}DY{el z?47tr6uWf0tSojD+^hRp*gv=P-Nup)0H!IYxjdg)gp7w|$Tdi_*V|Fe%x{oMYfpkIB z{h){@>`?5&yF#%ORLs$ROfr>b=dvpla`uE|tNeaY-U*6bp^&*JHO|-(D$Uf5Il8sk zx$FuBKEr!MvG>!{8c!2CGuock$ZO2eWhbb(E7Yj2+4bqIqUo+saX+ZHN>05WRAY{= zvvbp(pq!n{4pEG`cWI=u6BN5bk*S;My3Br1>;}b7Q2$x9TRFOa_09dDzWbXyL9r_o zJ3+-v-FEvyc_%1#g<0D2VOOZ){h*eTqg%8e6uUwFMA#Loct0q1gZinkD-^VKjxIYv#a*Gktm|Iv z2ep(OU3P=|$6;5f)%~EzXGrrx({&^J1yCbC&rqdWJUMM3lhJCR8}SK&3a8dMb1~VC z-pzo$7KlvOW($*V1A=*VKd9QBsnGGYePPb0J+itVROALS2sc)9bj=6y-10rC@DCSf zt~!gjcI39t5N^zmZS0HI?@e3Stv0lNV{D=2#Ci*U@piP=YL4#eeo(9XK{4yFUx3F_ z@Arcurs&;?@BtK!O>7NT@!m_tR!0AFbgAP{ERVYV!Japh)glaXioY`M-urHO$1NmwY54@{x2JsyDt0#X>ul)X zZhd8EF_taQMk8DI zMyX!>o?3Af*Y6upKbFhjS{Eya>3791svoD8! zDN$B}WMZMOsV@N5c3ud}Sv^@0C39|8S7gjBNJ>H5;@Oyy%x)1So<5_$G94&5Nmh{H zd#7|}Jy{j4%2J)s0X~@AGjPMZMRyBV47zcT=OlnJgO_u$)lp6 zmJf+ib!bFa2SwNGJgh4!@r>w9&KcE%s0cy@g7bpsf$AVfLPY_p`A}QnLQ(1qWV*UQ z^a9oX0Nr?D;Lk;xp)Lw_3o1I}zqnWw^enZAjtQ;0Rut4K^q3I14+RwNeL5dkEsOgC z1*7|bj>|;v*ZE~SUna`FJ5;KHQWNbS9ao0>6woVGPvlOWp;xJP&yA`ba!T}+Du&#s zKf{L#X6&wJ1nq>UdnE+8`(OvooqmaZT zv#MjX z=n|sWt*~*fJlz~2*Eu$hsFkbGGp@_F0gn!Qb+kh18A+641k2#kj72iaC#_b{`i;dL zBgSkbzgtq&2IIou1bi@FvFx4+Mgui#18-0FZHR5~%z#}M<#VaHwDN7}bl--h^#vSQ z-8-U)1C7|Y<-(=0YRYT>TVJEW$$42TDMcqw>YRzuOBr2~m8%=>LuS|LAS|e69DH1z5>3LohcCgg221zd`S!VmI@O z5jIBGl)<94+Ao5dZ&WX()*JDL=xcY>p;~QhBQ5m&728XB)AD>kHjpOX+xV{9 z-orxhd&}UXipB>KTD}4O9(5{Owl(s3`EX+N4*W4%jJ~lIgxr+j!&TXpZKq84 zRGr|fJ-3h-xKZ~bqHqN%VDw-w*+#=lLMx0rqi3pBtX9@=%w5PgF>kau=195Q*~N;jduXV+Vrv+9--HSf{6x;V*B}-@{9T_hw3To$h!mYYoOF zkw9u)(6f9IH8mVh?mxaD=K!sWoS`Z${A$+5#+Wx+i}frvD%__Juz=yg2Jwg9K{lwq zfh?dAkb88DaSyIyZrnp!|HBxFMm{yRA&tAIZAjnl_B6iTt@7L5lBKkvUDO{5gFlQ6 zxZ?M^ZEi_p8*E<{VL|wPc5DI*fO9V$#tN8cW5j^^gGF)3^t-m{xA5>%cYa0(h>}cq+jW4d$aJ+?XR2b% z>MF05Mm39BJ;iEiUcn;PN?WUT!Jm!dlTGu@5cppb`c)C{@`;HL{|IlG$=Ve+T=G8I<+XkbZ-CbW(4?Hc9)Jo?Ro) zcu~xRzqX*aEVXVX7E-(T9@cjr<*UWHq;i|$9nx`aYsu@tBD)G7R4?}-Dx)_#;eX^j z^*vX*UQPL5k?eY98*>g?_Xu81e3{M(Ae%Dcnvrw-$@n7h^C6K`J;^g37&)#K%Nnu0 zE!PSEmm>eR@FUW#c`UT-yjDj3(O6zr<*NnI=W)%DbGUV1z`33Wn!!7J>nG2^PG_R+Oa@ZTG1#dBmWV%V*d+unwY)tSF0*eC9Q)!A` zfb;YPy#UYY3wpt|PvJcLrx)Nn{NGc@f9w8q6j=V9KatD-()e%Q(+iDSs0{x*(LZJM zztg((=xKqdZqUVcC)DJ%*O9#z4uLJvMNLSUML8nEl;tyjv_X@%# ztQXh$j%doX2V>uLf{>-RsGvz-R;%`v6T`w6j)xqK625nOjGB@aQIJcHwlB8EBo^ba z-brka_dBv=3%#huByEbT8QTz^<)UWohfLMB!K+;Kda7644zx=bfH&%XuQUCM(x{akLS3?wLX$r&epDNL)5gz9+&cMXuZaD3p;(g z?H!Ls_eUHf`I@iwd%NXxO54!-jj@GZkJ=`o-_RQ94tQ=&61jnWZ4X$zeHbln^TB?H z<;5K|wxKbmzw&Sepc;tT8(9Xjg=lr2-=3oyKs+#S#cB@BqS!V0-X`>G)Cy@|H1Z+E zHnc+*&_XozDy{%d5a}@5q71I!cA?lG5C$AH`yDz!h~KU!x9NC=Fz65I>7Bx_KO|K6 zZF+K6$HPLJ->;|aIQg(B`y{i6<6Xj=-xuh;I^Uw7yj+y3%=ZY@#^r&mIwd zM0J^O6x#e|;n;5!1p}(qls&bN>1S^WSpsiV#sC$a$s2g1@(8Hk zd{LI)N(#Q)N(#w&)y#FJ z^IK&@Q_GoMyPuV9{SNK9O)d9#$l9iI^FiIeOZ1S=)OCMOmh`u(a&tBNHl3?F$ou$? z?A@Zz>rA!m=VkZ5Q$JtOQI$phZdGu`E`PUddTK&b6aG1^2lnfFmyQM5$KRg)9nl>+ zQ_mZJ@IKL5J^fD6Ii0B)k5_W9C|M=nDV^OupJYnE_a5nv?K*=!dyh2Bra<4Lde0N8 z1N~j1@6{Qd^j?ks2|d}U<9*Uj8%04RLf@Btug1h!px>)1(W5#(5cJRoWT|{#_I}Y1 z=*%qn0a^9$SFLB_f$tCY{0F61KBx-NSoa^)==%Qb?}`rTJfN!&iw^3%PSv14B>G{U zLCt(vcKL_0kBF|*nR)FavNJxC{eb8XWIq^e7><6=IWv!l6D?gZhRP>{&1ietH zR(>ekQCSF-%FsJ2J1Wp0&VEGnN3xG)^Oc>Ik7e5{^MQUW`?#(@o_!*lt!%G+BActs z2KtHYN3*S!xeD}0vmeX0Rkl{3KbHM?HdEPFf&O^*$!xkZQ-OX`^`NIK)P!DNq3ZL9 z==#b?<)=ic0KK8|)7j5t!+Jha8Ls?9_LJFYWkcm>M1Lmx*=%!VTF-`b z3|EFKn{^(mj8=YDl={$vdNNcQtZdPFyz&pTPi5nkF`Xy%WU#WSGATNx^I&B_=fTQG z{nn?lwUsrMiOM=18%5XZ{NJ*Tdj8+Cb$XKN?o$d2e=7UAtWx>8?B_)@o&R5*e_r(G zvtP*mKb@h!kbOG)|8<6bI{QV@U(7y}{a-qNCi}m2hJGgdZ1(@?4E=2OOWFUfGxV3T zUl#r4>~q=wq4Vdm|5In^=Tukvf7KaEh3WrIXDGF%|Etc>f0F%*YN7wvKz}9sRbBsT z_G_U&`mbgGMQ7-*WxuXk>Hj6rU(bF+*T0edX7)EaLw_^-eD=3Ge?I$Srt(x0^t@H0>f2HFKqJORPzt{N-qF>0qs9Nb?%)S&VrhhT}w>p1G^h>JR z{jamHX1|;Lv1)vORrIU6{}Ua*EBd>t5dN3?tuKpyIr~cX_3WSOx4y39k5%>jpJo4C z^iOpDBR&7R=)cqN{gIBZh<-)S{!G8|d!m1;^VdSv^{?r7{z$dee=qxe(LdAq8+!gV z)ms0C=)cnWYpS{a=lbct%>IR{tpB0Tf06w`sJH$H`pNI>`VVzyuS%^gfwsWb!unth zkHuk3`=s;&BO81GI>Ir3khS0^S#N``Wpsl{Abv9zM)R2NCiEAb$AsU==v+sHVs2C| z`X0|wj_l3<4tROuNmx+ias0I-e8I6C#79|!W67J037*E9FWX|q9ZsnDxJ#k*A6IsMl z#0t%;^sT|pB|glGhqVq!0WjFC-&`SPo37R=8bNGfn~o{bb^5(+x+0foQdg`?K!R-) zwPhTwW-_kGwa1=j9ZS_BBBlKOAz3)a3^}hHj{$X&Ht4s(C&d~W_z4Gez&Z2)mbLBW za+MG9AF{#)OKz(w3*#r^9j5hj*4z17+z7EPddio>C9lH4ln>~jC7{U%bv_q7d)1x7}G@4a)9@TSV!c|?3D`r#`t?GWGuHot~ zohL-$^KPBJfAFLtM!VG`dqUq(L#(#X>F3&>hrjkYl<`y6?o1ecaqe^G9sC=OKEg76 z9rJ=0E)rIZrRJ7K8Kjf_F8B=QH2rKmCz&epdX3^CO`@)(6hh7w(0e z|B>_a;x|1J`47)yFYMBlIqzO*&3_Oy=#-`NpV3v@3-%ntr={>8xv-xaZbv@j%fah} zgty{$IINeU#~331d8Z*UW!3iFMx6eB{k~ zVQKugcO1@BAq1IUrvuI-`O$MhFQAvvFv$E+kb8JOBTggt@O--{J%NUq6{RQ8Fms~l z9dyeMQS=THzEgB(kaIN8xDM-?syL6{LBi2C^aQ(=^Y!SQO`^;J=$t80IB%V^S6A?# zUPxm#-QvF`y?HMzPXD}E<-eIfo)OT@)7-20Od0+EVv_$<{}l1x))u|c`?`Cb^51hV z^X$2!|5N=_%l};SM_pvzJKkc8)|Lh~?qcJUt>SWJ_#f>b^gkAPuk26TKej@d1)}}K zEPyS_>|pzIKFkiO{aIxHp#P&4MAh2V{%j`yk^k00d8BJ``lo$NvJC$jg+!}ZMSCvr z*o^k)%CU$#v;W)iKbQY#xi_C%S^MP?NY-v?4Y|fRq$AQqL|7-4S?kgJy|;h7+Oidd z%;)Q@dTW32_Gd+QPqcrqH%B$9Y<1ceit@i+ys@>?oae@lL^)hu{@ea{%$XH$JNwi2 zf3!lE&;CsL-H_P^&}uL8QY{<5E;fA+um--je|%> zL0KF`8U8Pa{b~IZS7G=Wy#87UtFE{T%hzA5x#B8}8P_YXO<~RDwV2nxss3rr`E+!& zlmA)-3XuV9p13k?g+nRB|0w_V_N<)Qb}{~kGW;jP0xqL*b|}(6=6`POM9++M@>2Pq z%6~WPe|vrw=YQy?{I3K&$4goMi};_`xprj0C>f)v8WB_}?h4#-C$*DbEd0mYpZeb# zz5R{)zf=Aj*%mQO-NBZfYy6LK7W|*q|IrIt%l|U|&ocbC)=}j${NEhB57<4K z{vY|e#2TsZMvNItm&zK%iXCeu;xZtQKam+CE<_)RgE8+CeIyP>q>Jby5wN(YEm2P* zUUORe;;-MSV~0Hc`0?j;P(Ok%W+x)*XR$KH_fP#Sz7HKl{j70a?N*#%Tz>yCUF{Vm zTMb_B)iEYd$_8C^Qr7{zvSZum_q?tH`ksmolcH33h;<$6_h#znK2XtG#=Gcm%y;Mm zF$&(98fV0)y+a>yYH*!Mouk$MUNTPkYQEPMEU0`&jWfOve^jhDhi|Z1y)#!jW3?FT zow@2|XEAH| zR`XYx?_%c4tET4lQmyA*HI;guW#+F`4r85hET~v*91Dt?R^_w!&_8aKdpn7epkEt+Ufk|?}}BP;UQmFu5LcFf2^R_Y6 z3I*{T_s>NtVtws%QE#MG&yacc2=><%*R3nkhiP5-#r9Y1sX<9xy3c{-uysAwqW)UU zcNNt`@Ah}aFB+EZ+3B9YD`9*U_1EfmA&s#jB%`c&-|fZhw~@+WxAi=`r|i{%wl{iY zz3!=&*u37l$5)iba(d&%G`>=On0{BP56^YGx9Gc4IqYO!E~_`9-v)^UzX_%j56-Mc z6#IvO=-jS3YgBYp_i*AB(DsZk(Alh^nWMLeVso)h-z-YZjTJif20jKn5B>cv zJW+Ex@~@)~toOubmu$WZPt=T#Nzus{zApbRd{cPf_%6Is#MRh!liUe*>*KrdP4&wk zh$qll!HxdF#+r6msLli-)124{*~08Iitn*;$2`3B)LO-7=}K>SCMQDQVYA`IbnXak z*!aTNJCDTC_A)+6_BMoP@Q(irH{olH&cJC)6_s;|Q)97{_ko`rO!B09j$WkS=tbI$ zuW3rhCav)CIjspj&t5<~f}M^w-=U}2=){+ai4W+&Z?>R2?bN7ytn&p?toY$zzhk5C z(lux_bT@v&J-R}7lLxU^R~7jb@J`m(C2)>+8k4e5xX~NjEuVa&3^*T%^+~M^H1@u0 z)TRAyIibht2lqbxZV7R}H|B?xkpbpBj~}q&i<5!a`;26IpIz@Q3C(37_Wn-s0%?dc zK=0?0P%Hx@k^pKoSQ6-cWPnVc&Sb#7Z%ODyT&#=?q%|G!s&+d+Z?Q69JsY(_t_RQn zQ5&EE&b{ggL&Gx}IfZpxs=6 zZ9%J$1j_(+N8bC)1*sm08i2WgSs=~`%mT~{V2gIXFbkjum<4ieP;M?*iVUEQ`&I9w zNCx_u8`^Cdh`nEL52P|sG#6L~kcna$@LYf=FV_Ig?15AUQhNZeu5-kSQMmoYXccAc zGlR!HdwZRuTt)_J_oATk2%`jR4cm$_LzREx*W?Z}cd!1=Dt}h4Y|t`f7AZz@$wp^a ziV?~3TG@^4S1}yqnLR7WglDhlYBl|T-r2&tS@6GyRrQ(wOy&#Y*#*WIY9KC{NXL3d-S z1I^m^M%|68#xtwrQ#vL^Z`9p&I!~%LH299wx|>vWXI9(S=x&p$K9m1(t&Yv2*XZt~ z&YM;1ncYFI4C{$2^=z|hKwl|6bhVCcqF3pBnXYC;XJpM^rf1t!`%3ExTFM7ytM3)1`tiX~8~I?UpL~gaR#i>t zs;s?B^t2i`o^J9Wqeqam;<%LM?~SqD^ze$u>t_n_i{ZO6&=-2AJR|9M3K9Pg2X+f`ic~RuzgbsGxozc(km5gl{-LC67$pW%> zspRY)oo7X7^|O~rf-VugL_dF-jych}P-mSg<9F+LnWW?*UEL+wIVyTo*VGulOBLLy zEPkhsyFzvGJ5}rbJl)?R={iqi{D`h@4>iSamqZXG-eLEg^>dB0Up&X zJFc(Nm^`E78fk#5bag6JaKBmSGtw>Sg`0HTEG>avxKYPVL8F`&J+1ppGFA~^7^`#Q z;D2ZDt>e6^_O}1MViPkkL)Q$<3^jBN-JJsr-Q6IeA_#~eC8=O5NZSPlsVImADt0R( zU<(#$KJROP@A-k}9MAE&pL5^$@AZ0~Ki0Kkul@b*Sb44Mvvz&1RV__L-dzHiKs-Ha zZ?waCB6pTIx<9p2+SNQC_n#+v5^BSAhxtI2jVhF%crczEv7IVZ>+|#c;z+GZNmE-W zd-C>CnW;vKzIdeevRzbuvk(NQ7@q`?%HYKkW>BV?rt*BQjIkHx(O_|fq z`o(d@cv>oNV!G>4{`9U&;EMAkRRYC1sXf%YO2SE>*Njkd^p46zPq+-Z)Fw71wPf@L zOY__tL}f)Kz6q(NqW72rz!Ys~v= zNGLA4#@wJ<58X#DP_2rdN3Q6Oa}rjYqbHXmdagML=j4s(sfV~6yam-py%D{aTBJJO zU`;1plZK*qb{K8z1~5WsK$3Dth%nZ z(+O1lRvVTXz3a^A&1RC)iTbHh(GizP{ZyaY0jFB49=AQN1Xv=fyDF3IaH_jv|Jvf( z{ePvt2=Ua^?2)*}JTwX$^XROgk$mFGS^ zp;G*U=Hs5YzB?vfE+nq6kBOnx*T~YMH>+8h6c&2#;%B9>Pm_4|v;_GEgzP z*NTKIap$^MeUnXN58Y)tPR}EZo`mkT98OO{_gWUGuQW(i5mS!nF3WJAx???q(%gS; zLb_}57;&I#N6hA0JIus(0g^3hGO?0T%~F4rm$+)2`m_WvcGqImw7R1^7Tcy(5Z$*{ zchp~MhZx;^Y+XloTG{J5g}GL>nc~XS%IbS;Y7=A3xayKh!})oj#=0sk+RNAQw4`d) zj=oA&s~&Jw`W@{Gtnb@MH7bTmyTj)uuK&`ARR1c5O4=c@ROfegM_HVzu~lqjrM6Q! zG<%d?c&wai4w=2TynabqQ|&OU{pIz4`nJ8kDr}j~*sRMYg1^nA6Wz9DR*Yu6K%HH+nXb*(XdZG3b!dH6lmOU*6x@9J}6S03Ba1W`aR{)_2@q|hE^_JzsAJxoH%SfulzVM*}6Mv+w`WTcvd+m zKrgHN(^nS@MlD-zP#W$(Yv1(Vw4NsIfa<|{t>ORFUQv3M|I>Tzp0D>RS9;Pa_kY|Q z?tf=p>cTaN?A3^W#z$YcHhCczsrLFjBYA#Z>aVU%{uvi};kwix%Yf={Z07*kg8b*d z>7Y^f-|iar=lfOtu?(o4|99*&9P6RfFUf{gtfqRVKl|qDUnv9sm1`0gmVs<0TIki771jLh-x}p68)WXZ=Ew-nCR^4??v6Apt%E13l zJMd@gQh!CKa$#TaXKRybf$F`+5dXP#sSEppKPv;V{bOSL!o>FPiS5qwSIR(a7me&M ziD)dRccJGm8^gc z{JXSDe^v(mtR48PeZhrmlYcA&8p;2$B*fnTf8YLP`lr}9S&;PbQm;uB|Hrql@(>#d zp6?O<>-SLmN9{nY45(!MJIa8{O{^EVuvdt+1ON49;LpYev3{XMH0Kk$lwAh&_Rp7u z^JPG9U;33;Nr<=;N<_An@gJ7~*?MS%Ad3$%N7-c{rechZ68}{h`0v=q?XQ=Ce?A6? zwGw}90si&dk9}w1-!UHev%cWMG2!37_kX2Zy>MReXMI8Tj6k(MEqd2_>oMKxUzr=K zru|RvB^R3w#`=Tok>UBi;Ge(uzi%b}|6K;MYyID97GrufS@@n;s{QTU@V}!BsLj%R z>L1VSvgZzewx3jNB>2Z&y~Jtgo&5cNj@suUH=}#a(k?6m|NM<-myp;v;qPY+s`atC zLv~5f2=KxY;e{iCf5+TVHAwd$TYNukEA7BvX#-`is&Rz)Q+<0{ z-VgWtc3J-=Wi0c(wse6>Q zn0Rm9yOa!K^7Tw)Us^qSDtbD4dg8pLE6`IF+pX1ZJ#DQ6Y86v&K`X*qztr2&DzMfs z_10p#nM%A{txD>>myh18m~5?U>b>i2t1Rff>uu|;Ywb9lHAG!i2hIvuL)0&{$4M2S zGulPJ+KzOsFP4s07Ij`5oKyn(mDad6tRw6HTH#u=o~&zXiEG7rvaYoSt|jZqB?&c; z?qsYPW0Hc=xG`p&8H+zEijOk7|AwR`1tSTMGL1|_!XpTeG>wTR1;YuCFvGy%W+*t! z3;~Cl!Qc=x2pnt%f`iNeaG>cA4lw<|{-!V3&-4NNn&Lq>(-rJ)x`91Rcd)1F0roOI z!QQ49*vIq+(UX{FT)9+IdMkOjj%HwE{5+-!ejdKZ-Gr}hH;u3vegdJqeBnC}XC|6v z#N&uH3-S?8ZS%*!_)+8nhY?*)BQ>uENjYv+$p|seiHu-EsjvBKaiHlchD1ve@`rt@2Mvc|BhH9-&0Q@ z{xkR!-(pW7^egxaUtUij^gH+)RXBl=0Rz7H&X)rD)_X!=`Q|%&H}FMx)&-6F?hw=$ z%Jbqr1Vg?QpOHO9|MmOTYy^_%qL|*FpsaL9|eyRpBo(J3+i)mN5CVbUPa2>U=CkPKMWowKASJC z9|8}NHXAnw_1;H>W`S3NAL3^Ow{lGx!EN{%!7BWWU^RY5a65iRum(RPSc{(#ti#U; z*5hXc8}KuNjrbYCCj5-x4*ZPZPW%jhu@(v!>8Wb+FSEcaP!!fAbOo4~w3@+PMN0vbt2XfiknU8Ey)33xGjM@MK1cqy7lM`$W|8U3rY zkv7s#+DJcXBORtihuM*I$8k$Yy4y??HWm1PX*xW2@)Rn@A;BI}Du7Q#;UUDHB>gFH z5dL0{R0wtxei9sr|1@b8f+q;?4)zhN5Il}@aUeL5)MrSm5bQ#;*dOfAkzKgQgJ(HX zA=pX!uHZRh6@ndvcY=M;H15Fl3!djlg%{AlnnTBL4ZH)0Rt9tpOP@^G*j+yZ9dKLl^b%>e#fiz*drOpzK>p~e)cf7GI?jf^Q$V=B~` zBK5CnQKdqSDN_GTiyBj*s*TNH^n6~6dZGSQbB%0WYD{?=Q=zJzt4-~YI`u;R>4mz~ znDR8HLcLIz`bRCQRH!jU>i?M*HPW9lrqbLXQlzGawEa@6>kdcbVtvJE`VL22cOcEW zW=$h;qv&B6(tw8e2z)8ma}v@la5#NPE>QEoVYJwq?+wKb`wxx!5K@NzhemxcZ+-}U zW**|ws}E*0l$X#z{6UnE1VRJw2U1oN3H8SxKxxQFs2{%c=u$28jYf)n3B^?D1!$Qy zUhISGOPj1wV{e>P>KZi`$MvSQW;Q{~T!N68#h$d&NfByAp*!;lY0bqeRRg<&T2YYJ zT#9qe1~m(esmz6%2dXs3wB|x7%cU=u=2UaMnBrV&@;~a!Yew&)W;AoVP+uNXoHJ5q zd?0;q4f;vV^fGbhwdOTRlj64qeW?_<9dS~e>)m$5H3l1Vqyy!rJ}Av^2V6r?n)LRR z%(|fTzwL3FXR5Te!?mYO*Cx~!UnsS2Tjp39)R<<`Y_mC`*3k^I6)4quOZ*&^2F=a; z@lKez@pPM!uX&J~su7GBt$(I_l@?f~O=@8&LiJpw2o*yiM#O>tCyG$5>S&Ee?EZy{ z&{C9Bu`aoJ)2UI(l}0p$(js+eObMH<8j}*BC?!`Mf|O#~qbd*gsuC8E4)9Pj0KS?v0ttgasGPXZO$W@6c)V0L+(UoOD z4xW~-s{&5?SzTQ^PWstILb3oz1l2C9rOgM*EMl+ z)O<0EE|m2x>#4if zdCI4|)&IuURiw?;GnEB*VXi=TDBerjE4?j)(|gfV(3^^>3}cE)alNrGnM(f|Q}C$- z$G#b_w{@uRxBm`Wq|j-}Pm)6QmPb&a}~m^Mw{ zyos#@>nc@_vac()W+@e{6vEQA=>Pe;V5%Yh&#q6lSLc667Fkm9N|CBn(Ac+OWBdN9 z)MbAmR=d*5dRnC~wp*d@QZ0cLoqGCe8}x3qQm5b4dakZXrKUtw$6}>Lkx)GHt z?S)tpREd&CRBzuA&sK`+`JUH{o>z)yYec0A7Mqx@6xDk>uNVEJQdIY&T{pC&i+VS0Ps|9dB0D24+QVVHT}kE86?!q_&BA4z-uv=_T6GcgUur3#k5}7b#sqSrE#y zqcbRbgr21IirW89pzIXY+6&dn$J%$b^lHr;MJPK(weQ0AwA*U&g=)d;;d(|rLEEUs z?+L2sQy(CdEms{veWO00Pt^VkWyPh|U)Y;oSk@mx^~5!!zFB=wzo@Sg_M>}QDG;P>;X0v68j|a=*tM42~%QcQsk9yN_v|MAE*@`zEOUpHp zxvs`W6KT0*MOX@VF_=PZ4s+Z~z$y48Nu3Oq!k^8YcnUa$W67jW0!!jgg}1m0oQFS^ zIq^J7?Q9qdv6Yj+NyHX%oUvYQs#* zU{O+v;AT+Yi$pksS++(w!s*Pr)jA3<=T{5ztMkEW_-X~`Q{M_iI3K=7?Wb@NOieyQ zi>OEW2q(Y;Ed{T}S9^PP)DkVFCWsSKd$g4Lump}tBl#t?0`Y|7V3?MJ*W#;fUrw8` z91coj_2tyJT!eE*3{{SZxl-+4N$ptyObw zb06*=@E+Ko;;^|Jzzy(9#mz=|rTfW$AAE6fvkBZp>@oO*ZSci~%pKtU%&!X*x*yKr zG14Cew+BVwj~@UZfD70`+IHCL2Vn~G!y-QjPyG-KLIL>chv23Qn9V@~ZVOltKhbP~ zaY%&u-U93WFdRfanD2*!c=IT~6>lEl_u|bC7?61Q??+(LFO0cxCoBn^q!I3d zJ;@D2DSRA;B@Uia_yqh*2!}4*4Lg$qwo~{d+)Yl{P2p3pHx`alxCh?Gn!PYK4yN>J zcu^PO(=ax_6BF)(r3uXM5k3P;V@zO#&%(_7f-igy7UNfZ;q!1Azrko60Dq0bFAzIN z>;RnY0T`2?h#i2reG%T|XJRkH`o08ja+=snu)Z(Do}3}}GOX`GIFz%*4#En*0+aG1 zu~*=XevP2KXka;zz}!9s_@fc;O#7@&P>SF;c~$egT6kmh(8rKZNTQA9{k=M=-!* zMZYC>2)0(7=~u))hTj#h`Zck`u)JbdzajPs%&oZBFL7dVzadtYmb?ZSv&*i6UzND5 zyQ_k-?x+pQ=36ry@sG0ERx4dSYMHCkCZ`kDoL;Dv$g;RvQJY*XYKLoqvNBg|ER@~3 zT4SN?(Npn-vQSrREYv!H+F_wA+ST?7W$B(wpV%1G`h(iurcoQ)IBHRaE$C@WkVCeg znuiy|HH+HP=Cq-*yw@1M8EvR$Fh!!7j9OP&W)>l(5Uvd50Wc_Q&-G#ZLCe^##RXYQ)wZ6eB6Ssvh*&Jvlajn8M;H zwbCoTRO6+AxB;}VIS3j2fl=!^Flt=~2C;dZT5_qQLi{*TmTU3&e`~p>@sW042tkdQ zx)6%zF4S9SZXC~3P%omVqbH*K)i@`CC!qdDqo4$yq()e`l8{l{S^DSP4|gQ@Ly!l~k3+Sou_`jWI5=4OU53nU0lmS)bR%sr1*4P_;sA zPuZwm2sN6i64k3JQ5~xi)we294UF*)s!ipno8_aCRjnwj8mM}zdaK%74L??wt3`FZ zT2#k1PRrof7xr!YmVMWLY2N|A!ry1#v`>R?;qS9w;QwmB=E$$OckSn-?6c3{@3X%U ze-Hc>|G53leq-OTd+i?kto@AR&*Gl3Ka=Bq@E80K@ZYxu+;8MA;C| zMclpi7JIX;NVurG$=*wNy!+681b$=>frsqJ;K%kbc+#E%PubJpX?q4d#}gax&e*fy zS)ScE_q=@pe8KJq_uB*D0sA8OqJ0S*?+$~|$oUtky7yX`&TJ;W|@3GRFFd;0_UgZ&Zw(VhfzyEu0d zE*^|`dB8j_FPN7zF5-^HyRq&i`?4MDUbY9pgS@e^ZX9W2-7CDgvF;K3DEO#-41COP z1-II5;5NJ6Hsp$mxrVsn?rN@Qp>05{xNCqb;TGAuNLz%v+SVtngsYEB0+U>_TWs&J zciP3cyTH51SC1pfZVBm&?F6p;A~%6ImlMqCa)G%>o51_b0hV;7z)~&+OmV4Ts!IdY zTxqa0xyHDiyy-D+tz8GMv+Ke2b_2M6_J91TV7n3sCwk2N8wI!{pyTo2k z+9kM)Z5vXnyEYuD<}S6@apY3mCAKxGHC$_sRCiPCN{&pyU1}$CrxV;nm*HxGwOnnm zwyOiyadpAEt{zyA=Qa^n(v5a^*d=x}cfSc-VwZwT?J{tgT@Eg{*MQg9Yr$*n3UCw8 zyA}Uk)3xINYq-n!_bK)=j;*wL=$~>06YLy2(Xy&e51N<0DmI%}|0B!Z{`Ml<&-S+y z@cWZgd!r zcXXQhbaa~e$hz5q;yVVD`wBZ4Hw&C)2iXD~>*zE#alsINW2PNKp21e^Qb(6YpH(vG zW5?URwl~8Q7ALwax92G`n_q0dXAml6jfwRFj#tsTelwzxJ{O1Gq- zogHJx+IF~c;5d$rbVKY=aHt&y4zt6-;dTUw14r6X;3#rsI*qh4okm)jP8?UJ6PK9j z#3E+8f?Tr{bxHJfVusrDU+rwnI$8F}#e)uZG-(}h?QJ^oV)UKm@zV)qx{mrE+mZhp z4UQ(C)=o2BCg~k*UHZ+8pr!3)TUoIq89@ueEv*zK8T8H?9oM5*trOHBy@joTt8O)p ztr^rLrG~9(d)S^}Phun7NPc$&t`peFb_P4!E?^g%1!mc-N{wp3L7vUug-+mS52!?arK}U;S5{LcE@i-zuw6;ipJm? zbyN>(lU~c#w%zchvgzdN@c&(H9a3t8UGX)R?&Ru{UdL(-)5+B%T-RnY;%XOEwaslc zJDjxoV13&FY+xIL4Q(T^k!=i);CN>z{ZMD8v36(Ig0WO*r}cr(PGhdlt|`B)kzPAS zcp8^=VieaA)JQprf2nGdY!zDqtctI3U|Yt28q+1)W*kq(C0Vg&ZGw`dB-@g4E3PAjlu|Z@t8Q$ymebj#5>ByN>FMm! z2&Y=D26c9&38&ei5vNtmR<^~hbO{54qJ)dtVQx4%hT+P9Wo%intStwYv*p3^Hr;k{ zJ@}n2POMuO*Nbs?7pK*zE>0X<7bgZzt7YQIq=Lx7FBi2raG}-e+CVrjt&8Qfl{k_U zm&1w&8vrAwHL_f!=d`(O1zQoUNKCw0f7mmvj*TS5Y=EP=Y;LZmg4NnyUwE;;{C6BF zxosR*nr_9Rb#d{8TySTiB^H_0cU0ed;ymo5DjX7JydOMV~L@?3j z1M}JZV18Qw9LA9>Cr&QQX@{;XCyp)4iFM0zH$|+o+I4GM z@SXYISSv2;5*V#Z;NE^Ph564P$n(9K9&vBeBW6zA*Tun)9R0!kXbRcFR?OI>;3VN6 z%}GogsYMh_B0X zX9=G%;`FlIIl^bn95}r!_Y>iBW(fYz;Lqk4@E7wdIFz)m?kbqVu5K>OUsoq~u&bNH zSxY1C?SwJ*TeAdK?dsq-;S**#OyGjxBS>armyx;Z@$1Q|Q`;a`x&4=bAd~t3I zfO2^?d0fW|j?WJcbFIIb z!(8vL;BVxUx~!}Fgp|WZy0WhB2;onRbY)%LQNl-zIJ&Ox7~!Kv++A1qDdA&gup2^X zFzz$(GxNFW=5FL@Hz$2rHz!TmI+(ZB!F%Q#^M1s$tq$HL{2nZsv|IblSLSPYvsEx> zFPQy=H<5a4q|mx8IKa{U=79MUe?7ml3RZ3{{(3?ig6H|2cg^$W1~{C*UfgW^$qY1eoH*z*5G0C?t}f?Ma~`M*$(^nIN_aycfkHVp&UUkyhMKKp``iR$gl1;8_jOc-iX^^Ug69hPU@&V!CJG9{A+Q0 z!M*&_i<~7zm2_d7ICrCwf~tpGV>X+I%o=iR2G`rg z-0kFg$cTqL5Zp=n9Y*S_9_}u}cN%H1dbqm@-({r4>f!Doe7BJvtB1S6++*%FH{k9w zM&*Z+&|Oddd(1I-ySLy2d$^wN7@;2SMsnO|j*$Ooa2+|XH=lC6 zr@P7ANcv5<`@#Fo1Ll)R-}MPOj|3~pd7b$T-m#~24wSgXR`!pqG$ILn@Hmg(;XfCESsciYqb zgzM#In=8$7GaI+eoQ?R+vk|j-mb13$o`r&; zY9sCONi_NW-54|4^mF}PKGVzf1{3k6*zXVacbCKG|IS$nq$ZkCa}8j3|iPy95_LhEiCbG!k^8e(nGgm8Vr4N&Lz zb)C`9S0vV(bB18S&zd&@nR?`_4_3m@clc|wXk?-MOr&tTkH=qNNG(9a92!Df1OoSg4 zGxsG-<4^FB;{U$HCBTS?&nv_6e6T-Xk|GYVj1y~_7sljw!g+}0g_$b=b9OG`A;n$h zfmQk4mIlQ)*5`Oxm>RKe^>O9ho8&wP-}weCb7{ABPoyHv^u!D?j6$3 zz`ve`oqLDSXY2t@rg7@Ng za8*d_fa~b?k#-nncVC2u?Z>tW%w89`HZhrEEnk5{u-t#?!0`-92Ob`@bP&RNVq*`N zSvp8^CBS5t1eSEkU@2D;OmU@PBu>B&rv=}_@umge!Q7?=-^1Ld1wX*YVzUc-mKGf6 zsipO1}EV*Q-f1*o2lGUS}-(X=Z116!`uU0 z$IB51eb5eZ%{el}wZI=jXsCOTV=uvxKY%~jwdBZP+z|H=sV~BUKZrkw^uca3@dGg2 z58;;$s_^E@232{7tjM{lV0BjwZ0%ZsZCq=xt!o3eb8W%)aDHWj4se0ubE>T}zTCKHI55%J08F8j}+FGPYU85Bm*_YG+#V=jO z@jKyV=iqDoMrusyX2jLr31fQ)tnXYxcfe3piMS}KP{sCcg7e)3GaLkc=|lBhg}&fu zXW$FRz#s;}SXk8{=);xOg<}%KrM2AooVU@I3|6xqQ8KulHHebI8rB+025VVmC>gAS zg)SMahlMW5-H9(;#T{u+(sbCzboeXnQ(6%gOl!mSaCL(P@YL(!_&4G&fc@VHOJ+G< zKgzd|V!c{L1wafvZmrmcltF z2g_ia9ei3txKb&r9Ii3g7(UG5nu3<&nf$W&DrvbgaV>&L@XOc2sb2#}J&DjYwi8D) zgUQ5}!(ugq$CA2B8ZU=`F{#U7(~NRhpZ z*dA%C1_Zrf7{|cLUIClin-Huod1NJ{72rOk&9q6ur7-hJ!4!D-q~J1G@uXlX9CA`H z4bC}6ph>&j4(A_+1p^38gFEk!KY$PxrliAm5ySG7 z@CbPFfx1>$nn{7!)zKFFQW$J(P2sY!JGDc>;dU4}h@9A+!h46DJqnh66g*al8v~Ak zyOQ#K9H`ybFXcD2gS%8+Qh8k*w17Vy4XfK6rnE)GrcQyYnt;k{0(qz4E)80eV-&1# z3;fGCIwfcYi#-C)cocpsj*NmC8_$ucxXXgpq>ZrC_}B4pSmQ~Z#{Z8C+K@UN*1R=- z8$u;uuR@NsB~}97DkRp;nu|_sF2@(+7QqZxA$Yhku) z5nc^Pb88^pv#~8knppojFx$m~y0F{Df_kw-$8g&kOG%o3}z}P@l;rCt(K%lm}XOL(V(!G_%j^K>6fQb>+6Fx(!0E7x)l+>#V?TXB!U zftTTmb8x(j-NwuF36?^j(S~98CPMG|#*(XdsxY_-ri0_fQ zZ9ncQcD>w1eu-Zl7r*acNV@?w;j4wQE&KN15Uu8{Hinf@3O|0v$ zFtR_JpTJ-64@D}rLy>0f5Ny>)!3P}q2_{EcwhwV{N6NG};c|cFjQ4Qw!wbC*1N0&J z&cQ@~fG@80S0gUzJs2hFi37dvH)v)g8u3#}-HIBXiai20!F?KEjC8pZRQr*NNxpYvPKaMrVMuAk#S!!Ldg=Oa67F+X1h z`#G-=JX1Wm_irH$2&|!48fU z1P|ixFgx+%IGP*G!x?cVo-=oG)=sm_yo$feyoR5P-}n^{d50+&u=fJ_9w&WQ#M}HD z%J;C=^x4+6N_r(mEx{FH&u-o{z*Rh+q-{7-;y z;D?+Sz~}BEwimY>{wXAd0WfEZLC1E4v+}|S@8ziFsDt%>jPyj(6Cw`0AlleG#5WNu z7^D!+2ZyZH@{Ocn`C_CRNF_bR+(DjA;1=^RC|jz1lPd&)FG`lt{hD3a+5!(N6xxt zg%KmZ0(UJOPdWIxTI4MU-@1%E^~qDutb`H19lV`-xbb%0eRYR zPE)Wg{%CTJ0>#LRMeGLKzJPqQ&3ydU4O(cs1S;u^bw-C%0PuFr=DYz9L) zkI-yzE`CeSYX&ys*ksNc15-bbqb*2p$v!ocN$Jn|J-`9@<(lXXc)=$Pjj7PO8;j zVJ34}t?&vvGGD$9*B)Gne?6gg;C1*nMDuQ~^R{E0DkX;2dD}9QmA*o&xosE?OL3t! z-PVkWZzg;Tu4T05Ds0IdS!=f~7)MJPqH%UJ#?DfjXjhIVjDOcM&t8XX6s^+M1M3BK z8K>S6Vcnn(qg82IwE|m*F>CFh7I+u_J%lpAyYcTO6x)3xgHfh<6|KP5WE5K?s1DwT zuT|3OjCQ3`*IH?H)>);r(Q0co#;VfZXg`LkjB};N(Wtjdv_@MQluG9je4%tZkKzlZ zME4}NIOQ9XRNv{Lg|$T5)+DT(u`gxzHKnBG&l%<2%$7^F#b?Nso)U& zVQ_4vKyhuuNK0kLEM8_fu~N*K#dM4yR+2fc^jaf{B{LJ&+;|i*c6^GIQKKWplvE!j zm>X-(Ak{}PX2=>hOZ8Edd8$T=QhgL*?y7N;lpKYb*{V;xhH>v+{Um*czoyAr{AcTI2W2 zh~;J`t=Y^}V!4<%Yi>7PGI*aAmRpmZhm| zgk#@?kp-p{__{BBt0aymC~iX*m{K|FIk3MFaXlR=ATRtKJ%Q|B(=Wun$Ra(z&Xx^p z_BYU_-q$ZM@=5*UZ~RYRi);{NEgbt+r0f#(RT$lgu3vT!+O0kN=`h73uKkl`0jsal z{QK@l-#(OuxxRZ=lh&XTEm1{6Vs|Tn;#zByl0oaGRA~xp(zaD3wI1=xU>Vwgdbo0+ zc-?w9S`59WM%kvUcf<%LVo#tuOhyGUDjTIsG_8c0N_{2aqE-C~F;A{PYF;k_LZFY#=%M z(bH5Vx4tQ(>eaJnOoP$91mBXTXG>jUQm$3HrkWR55C_CVo znsGR}`_m8g=ll^-eH%gUfbcN<5u^^IHTnRF6E8_;C6p)zwi^-PNunp73za z(C$_S)Gw+p8%~cUJEPIK9N;KoqY2dj)#H!GjReI8tFEgB&Hj?C+Pv6Tr($1}(l?TH zR4rX zJWst-Y~PDmUl)5*x>{YK?o#c$T6R6nxackXPh4lIX#7-)R-riUqQ+I)mo*90*ef*} zKc&*rz{1l0X>XBI#I)0C0)2$WOr>eJ3V|A3X_S`=#&#Uh7$~6CFU>p9h$?&E3GKpR zI8vG?r16kShsuaXS}JkcMNsnJF4 znbwaqlGb+|yMdMQdyyjqRVwwZM^9^0g=1;~dw?2+_m0{cwN<@nfm9m%5Xup?dRpgF zd(juy8`Ny7UsPVz0_LRE(cG&)d1Mi(wm>bJ_JY%_K;O4jJ9xf*92oV-YQtm^saf1W za%#Ozt>GY?+Q$Ke29t9js9DEgLIY@xG^!ZFvG}Mx(|VZZCqwC3YlF4Or#+Ac(c;Bg zOxZoEmCO^hYQsQ{?T3?pD5%-ah^R+VTbU5Gb80Jxkvfv2!$HlCM$#YGqh%YxyB&qg z2dZ}&9kq_5IT~yGMv$U0tjb-g7IDzp&W3Vx46QiDcBB_O$0W=|X67C{U zGr&oNw9laW^~q7cKACtC<^)YSc5!sfN)~@S1b%QbqyI zLG4yJCF=F35Gu|rLGjBtatYW1|1w4iEkMmwr$)X0RO)at;VHzXfm*B6Tw@w}q(#>( z_i|E`L5-rOlQtEcN_;wFh}K|h(q<4Z32Njtldx9bGzXcrZd}^L7ppc zDWJwovq;ejoo3*($Tb6Ohkqr<(!eY5XET0j4{F{%o6sy!O7+>eE8!=uB3YsU1+;;;8eg@0vY(YPM>OYwI;NVXI+=$$r}|YpszIuUFqXs;sWGY} zb)!0>I+jT7QH@Ytf|0~8Kn>6sOSPo{Z>Xr00`C=ezraZMeq}0Y0C-H_dNUw>@$J0qBRkMd=-eOHs zYTy!iZn3W|s~6P{XzDGigUz_#QlM(kNY#>q6pbJ?fAhrkHD8CXZ`x{P zqwo2K(L69URr<6pVODrQDEs8Buq%F6C?#0eP`a?DBY6k=cAz1ORArbfzmLker^S&no`Z&21;3_@!)n)8Z6b%9iWt0 zs-HVSskl@>cY%+i=~DfC9DD-3o$BWk;BHics-L^TCs7S*=JX^e?V{@EQ=sg?)syW3 z_o7%-E!_)Bk*NClG`J5fqUz^9P>Mv=&u2jC)l@&91*KY3{d^9Tc1`v3c~A;A^&BsN z(y?iFxF3|>OY^@2pj33~4_*YNu~Yqg36u^`_48#=iapiLgP`<?ZXO0d zLF=jd`w4giJ*aB;5%8!zV$}j11*J4qTX78h6y2%XlTX3V(9^25`3(FVovn5x{2cs( z{Q>IJntTCD>#KIpM{TQMCo%gHn;I{{H|P*$`Q=nA2s?VoEX>(P3&w$eM zYNwC0ptQfzo1FuHLJ2Hw*iYcksF$_V$Isv|Xqcq|`vv?Jt+RIe_!X4qS=y`LKcBDDMsuw3wE?9n?#_7Ff)0JHM%E6L%2o<24~A%Mdodmk!5k=VwKGT# zP}*6Insb8E&PrvL3zULZ4U%HA1WiN~d?GMR$HRt59{pdZ^VGu?kfWtdF8yc82xA2I%0W^=be% zM71t`S3|H7s`O>7LNx*#qf=kbDpX@oit%e$g=zveMWuZ$t58ir?NcCSRx?oQXX&$= zgDqThcOC0bEx?v&o~6}l3ARGZD-~5Mur+FCsjFIpZO}ApkFYkNl+D^HtSu;gvy@`( zK&hOyJ6L;AT4(JJ)&cB@T3Wk0T#a-*d1N;MmYWMU=MW8+W)Hu*b{xT_7Up|_Cn7r zeO529HyUQ`Db^e8gQ8eFi}eBfqVbhlsxR0NHM4Y8{lNZcnx)(74-P=tEcMm^Q2J&m zyas|&Icx8*LEvCi&e}U{FgQfoaaOyAfJ0H1OXW2b9ESQ_daq&Na5v1!4sbX)!VPz_ zBOC#aMB%M{%tnHv(0FS{vr*t^H_B~et!p$m1{LylR#w@yBGMvjrFE>^5sX8Ttd-Vr z;CM9CT4@~*UW9sE`mBq<2`Id!hnfIRL=i3>)dv0WWh?oOT(z44mpNb5e6n1*f^GPP(pX z;N@*eiPJ4}A0nTz)IPEny3%t_J za@uR`N^rKj(rK@;+29;E+i9<{Ip9@pj*}+qDsZm5%1IS97o6wjI_)Vo51jAjIqf4h zA6($(JE^f2fD7FMCr#Eu@M^cvX;-qV!A0(Br@hG*fs5TDrya@`gG=0E_a17jCE!xG z#7UR66kO((Iw`c4fy>=8C(FI%;5BZ!lXc%U;I-}=7uorNE8MkCs;w2^O1HutMvb)+ zyw0t3pPJpx*oj2UGKEB*$v>0?gpnl&~5~8ayL5dhISKpv%ASjIdwC5 zi@VuLhjj~htGmTXZ*?npo4eIXKXn_p%H8IqkXi+YXi8^ZE(_iZ3H*DjZWIIP2e4F zlRJrG>kjZvcZWNL4(m?vE_bIpjrQs;@NRdPJA?M>Ztxy=w>yjW>K^c3caJ-V_Uc~n zK6kJC2}RX?;Qj7CCmq)P-~;Y{CpFds;Dhb~C;ile;6v^~C!N$o;AZ!blUiysxW#RT z6f|ZF_^{jJ40@-B!AIP~&Z2vI1boyz;vCwjN5RM3qt2s9}086KxcIr z{KOr0HPK~#0v>UnIO(*GfJfaCR|`egQSg{M>ZAiZ27c;}xjNVyehPl(K6Q1mQ2Y%1 z+%6*9)Wh4BC=4zbn%`VRcwedk)B8~Psn!F}&q znpXHN&5!N}*9t|^kKjr7qmx$YBzVf5bW%8-0#CbBP8zAx;2C$?No#cmJnPOlX|~RS z=iFH*rPn#|CwIbNgIgda2xCoX_p0sfq*ReVmtCD;~__>Ub?cvU=d%~OF32qEb5E+F(|x>g2jAMKNj6qF|fEV=EtGq zDh`(L#r=3xUnRgKU&3F6-YW@A_DOyMO0Q(Fq)+xzgOvnJ`I27Ru~J})FXg2+O94}T zikDg~6-@J~UK+PFu(VI}Qq+|O%lOh>%DggQSzpFW+gBDW=gWF&0n35qeK{`$VR3g4eW8y3T*9L`5V!3wg%hy*8V0`oo&FjzKy>b z{bgIQop0-<+H425_wBsYpzXm9zP*=vv;)}DckruFnsx*;eMc{KY9`ppXL_kwJAs{j zC%*=@ZD+8H@9d?!?E+@`E?%15EU>H3^6OFeb_Kinu3l>3ZeVxc&2L0C+#T%UyL;(} zdw@NC4=;sqPq3Ho>F-4C+Y9XNdwJ=8dxL#^Z+|z++&*Am-^Xjmh`wMy-`8v3h<;#y z-_L8mhyLII-`{K3hXLR~Kfr6xhJoN9KhR4@JO~`@2YIQ92ZKZWU@wL85OAm;;-zaI z3J&u_z0}Raz~O$F*IpsR!4ZDAmwtK#IMR>s(pZlKNBNOnD(z9=Xg|tJ=RF!6<41cb z!pDGP{TMGb`B-qAAM2$a9|w;2pPx9J3WHNZMpX~Rb^S&6o#9!?9ny2yinoIp9{%O?lmx5FLrG6j!`YGUL zeu{qvRsLn*RDYR&7IptraGIa$wJ*#x@Nz%RYfqWW!Rh{TuU%=TgERbeuf1qyfHVCJ ze*m5ROz;Xn(`(@609OZ;O09u^x*z@>hPe;;d&rQkBZ)PI28#WHZYU*@&n z&~oq^zubR>mBlsSwf-7^2rG+g!4>{m|1nk;E5Mb0g+Gjy#Y*rxztVq#mBn@7_5M14 z1gnVa!5jSb{wOvQH-I<#8~ibBDQ*OB@;7?z8*~$Rv%kq}_n@1>Tl~#lJNMiI-s*4h z+P~*k@HT&|mu<;y;3|Kcmj%lzaJ66MwfE0z@OHo2e}iq!?cf@JyFYGD;2$?@{ThD) z8=ke`I=|L`i#5(VaJ^sWwe!?^aD!j(zsJ&M1Gv#|@Y-E!Be=)d~{GI+Zb~bl`cl*2i8SGc?2Ji8A`?FZH+ymb0@A2obkGU7T&)@5{ zgVcTC{r*0$eWdOOAMp2k?I!gA_@IBlYpH-lUJX2dAQ zZUGS6E^|FE~%Wjz8u>L2kA`>RL6$NZz-V{P>qxYa-AL#(Z~g4_I7p95>F zZQypl&F940YCE{YZ}-|yYzMg0@9^3~Y$v$O@APq4Ts%=J^m@5538v?;9kGS=f^f{FZi_I>kD8@ z_B6Q9KkW-*tF{k(#_#j8UV8?7)<5G5vqRXk;B)?2Ujz%i=fLOvbG|6HdC!9{_~(5w zEb(3d_xl%oaV+lkg9rS6UjmD}1K^APfKS5W?nUq=|DsRE;_fBzW&e^diN)Q^;6eYg zFNMY3LGTrS(5Ki`{1p4Df5oTTH2hTint#=&+0yuF_I3Z7FO5yx>);#ybzjDo#V=#u z^l$jGwj6$0`<8#xm&2OwE%0ssmM@QW-P_YN@B7NwXMO;F=s)mPu+RJu{K$Xkt74P+5qQXd_7I}&+st#i9hUXVs-fmc*K9=GqAcm0v`28d@bxOkAlbiQC}Nt%VXfD{+O?W z&E==yXZ}-P7t71fz|Z|>UONbW4u0W3_u5DB3-C+-g>QhBx2M3<{*-TvOn{ZBp<>)W5fU;NL$6Sl3t zfWP`*d}l0Oe+7T@zxpm%#{LHW?tk-HSkL|r2I23%D>k=5*cC&iAnb-UvH@*q!tPip zThN6z?14qJ1AXYip4fzYFbsXz3k&cN%n^oRZ>+U*fH}h)VIS|J<_!m9hn)Z> zh6&*iI~0G2%@-zyL+vp9p*DY*FC1ov;}5e1!u;WII|6^WEf^LEN7#}0BW$6tV5ogS z3xS2hLg6T^s|$lg!ouNb?AwcgMZ+TD80_JTg2lq3;aDu>i-E<%V&OP;1Sk%c2#bf~ z*%6=wm=u->FT(ym2}}-?!UEb>?B&4n zVYzS`*6roN^ssz*IX3a>V1+O}oQ`FD1+ZdRA)J9NeMPWRSTUT5HGd_ra#$(6f_)Au zgH^)H;VgEWtpZjJtAtmwS3*^=T39ul&2ACZ!0KVOaE`qSe~zsYRu8YTbMddTHNzU= zTssecuFVK*hV$%v{CT!km=Vsm3-IUL+F`9wdotGs>x8w#h4yOvg|=>3C%oD&!oS+q z3+sl9>|*>ywtiSITx^%%FSZTB`r#706n}|r7&Zu(+GY4lZKJSZs9k#-fsMmPq4w@= z3^oZHhuXon3D`7j5^5jcreL$MX{cR$n}N;4X5mVE9sWw&B5WRNr{NZ0%dkbLeKcBv zt-_X}b}w!Pwhmi`H`<% zue&|iA#5LNkM0g&$FM`V%C5#=Wi!K$;c9z3{%YGP%nWb0Yw&Nkox@Jy8oL&M4Lfmk z4%gas_-on6V6?ydiE?4KA|$8bB*)@Y!bx3~Iu~LS(;Y#I zEMg^sWLC*^LAF99s>Sh3uo==@rPl@63X-mtz{!tOfOORu2QA5{PdgV^qs+TBu8Wpp z)F+^ey-_Y+23P$rN;BpmKTnUQ=WF6zLdIhZkuob;&&`&HG`1{mE*x<_<(Mmh&qXp@ zj&)8}`dr)c%$3sTB&99SItQzqCLTF$G#ZVgJU@qtPg+|6t$>?~b$0Y4#snm{717F! z37Ex)5D<-&lJCfdreaJ;idz}2%y)<&$Z8Vdh))nbBfcOjnuQELIkPM#F}{ce@ifVB zYoPjUv?Ms97sS?xR?z1;RA-%(S#=W@=I}~p6Fx~(xxCk zvyyrdHHG+%l+-6@RhU;mNqq`dMR+V2;2AWi&@2f-*AKCodj@ z2+D+$k^M(R(8oBL*k?opeS-5b`^@*u{-?85m{DJ=Fe5G~+=vJYXD&ipL{J1yID3MK zph%nu_6QL{Q8fbCGocNT5q_JC|4&gao<_w{w|wAxNMra64C67ls773b%8WbrB;Xs0dDBjshZr zisI-zBqFF7PEp?fHv^967FtYM0H%a0~b^Z)p6l2Tu^CL$Ax=vL1j=K z5yS5s^e7Sy(c2522OR}iz0$*;;1{h zh@e_HH8~oH2&#=!i(`U_pgK6Ud8dmAs*58oUPMqmoVvWDMFiEy5iS3kSp#^W*KR{d zpf~6nw*kkox6B&B1HE+{qvCkP1vNp%@rVm*ii+bA7t{=>x zg4(089Mi-FbwJy51QQn&7Z5>l%tfAy2Oh%Ofq)CEU`xrm^y zIO4}e1VNay?#^5skGLR6@{l+laX~#%aXjLJ;Ko@)gu?~(M#b@n3xfP+-6!CJ`l8}^ z#0B+3#qo#>>W_-!5f?N76~`kkXdo(%M_kY#R2+}Epuwm(p72muXb38fCn6Lc8j6bJ z5f?NJ6~_}5iVO`$#brk^8xhb!BT*4NqJu`EB6vgxK~=LJ9ne8z0xoC_^U<(7;)2HF zjDg(|7c>rMEbNZBpz%24V0Ur{1dr&Ti2)Zh5kg44oWuo9!kGxWBQ9t%&Lr3!aY0jX zCd2NC3z~|f&f(&Mrr}J5-4Pcw9cLQsj<}#1IMZQw#0Aa7nE|^aE@&3cOxPW9L9=mY z!S09)nu9YNc1K*$T%0+uJK}=o;mn2I5f?NcXCCa1xS$0%^I>@9W?euBtw-0H^#L8U0Tsa` zI%p#*f=6`FCR7BE=%7zg5j>)U)EB%SS`Sy9!0SWo)MvdV;DXeLd$ZXZa6wyfw!rR) z3)+UW6?R8l(C0YYV0Xj?ZO8c>c1K*$7dYzEBra$N&KIyd;(~VK?10@77qkm!C+v>6 zpxrp?>@6;64~{-{P+ZVnoIS8R;)1@!*$cbVHXwLJ2Yn42B!VXfI%pp%f+rR_Xg?}~ zM|99Ps0f}8&_M@K5j=6wLEoYxcti(%hl=149dr;C!P7a^309{w>q7w@bQnDZ!6Q28 z2znTTM|99p^auox=%8b$2p-Wv$59bHqJzFiMev9Y`T-TeBRc2=DuPFJ(8+)cI?4P5 z?2fpgA8}5??uZNe3Fk-H9dSWFBQEF{oS$KL#0C9|^9$_Gpn%{J9drsdNCc1Q zpwp-b9??N(P!T+$gU+HNcti)CLq+h24myvD;1L~k0Tsa`I_M%Qf=6`FB~%2@80etO zs0g01&_P#F5j>)UuA(A%#zO~PLq+gRfDXEjir^6)bOXI^ZlYp$#0cF&Z^G_~5xR}u zg541#bSI#L?l8X%wKJ9V-GC9ghl<@1BXl1XyCX*EK|lvRV16HJM|99boCi=lqJw_N zc?h*LJ79Oj2>l5aGzXmnyYm-R&|FxZxvc+&3YrJ2GmrH@P(kxyb>_2v1QoOZR%Ze0 z$525FVRaU=egYM=2v%ni>!(mbi(z#Zvwj8@v;MUpd5-Ml~tj-G7uL3&g70yej9nnGm;k<&{SpyyP8s|T#owd+GZ*X2i?T8L~ zi}MC*XFYV#JDj&rI~$;b-s8N3+7TV}0p~q8|@gIpZP2|1#J zLO8DDF%O|)ge)p{M~skl9EyU&88q$vP!e&{wcJ zU$IUF74$W%&eyCzf(qIPtFw=FYN(+7usZu$r-2Ik23F@A)@h-F4#4UhV4W_YgVN!s z|F!6#^f>9Db`C)YWxz=fwR0FcC?ie=sGTFwL78weLhT%3_Hn=neS(VJIR+z?85O%D zMkovwyCX&@91U~A14bwU4R;~}Mko@Ea3TXnC<={)-4P>{1r@s^Mkp&Pc1Mg*HdO46 z7@_Q_*c~xKIZ&}XVuW&{Vt2#{FLW++tlSV1!DeVt4L@ZbRwZf!Zk(FhXTf zu{-xdccFCdLG6?a7@_j0*c~xK(P()mI$(qfqFN>IRHZU7R{jJ?5fzL<-dp7@_*i>p2YqMyLT!eWzi-2sOlM;4}&tp+-0joyGwp z)EK9c(P%q)^v@ z5$ejki_?v{s2!0)-BD3HB87UOqIN_I^+ZMOh!pA-FhaeU_k`C;9Z)+Wh5En=iP{k< z)E5=CBT}dzDr!fhQ2&4t>d(9%yp9;50XY4gfdL~l5N80qju@dqI0NBz#0U+>8RQHJ z7@;9JgPoxPBQz9eh%+o;gofb^h1ZGj!l87+p>{?DjL-<2;qW?9UL=%GB-GBRfDsyn zGZJ1$jL>MDQSdrqgvQ{EhS$l)Y-~UZjSCo|am>fU>xdB=k24NlCnvKB0Vy;Q6}2N$ zXc8)FN2JhXRMd`0p(&`S9g#v)QBgZ0g{GmRc0>wIM@8+36q_NTJ!Ns2!0)b5Kz`B8BFnqIN_I%|k`)h!mQSirNt=v>;%F7BHU=uTv_Zc0>v- z3K*e9&_WC0b;JlQ##scfBSvTm&SH2SF+xjmmcZ*o!w4xdWn6cw){Ug$GaypDLG&8T=C@j_cr@jBv#wxZ&7#0zah#p{R{`WzLn zBVK4bDqcst&=;t99q~dtQ1LqAg?6Iib;Jwp3P_<{%y&ZSh!on5vkOv3q|hFm-HV@3@j|Ci@jBv# zPNU*=#0#B4#p{R{I*W?e5ifKO6|W;+=sYT3N4(GlRJ@LOp^K<^9q~e!0#fJ_^NWx= zB84vFT!PdQDRc$rGNjHJNTI7ZS0Hu9LJD2OxeBQxQs_F)HAtQDkU}?bu0!fffE2ok za|2RGq|hy#n~*vpg>K{Ag47WybO+})q>f0TyEu0sbwmo?!?_EoBU0!-&OJySkwOn} z?nCNKXZ8?IXu9`1Dqcst&>yIH9q~ecqT+SL3;l(P*AXxDH!5C7ywE?WcpdRVk5KVC z;)Ncg;&sFeJwe6mh!=W_iq{b@^b8fRBVOn^Dqcst(7&j79q~dhQ1LqAgBWfs-`*}d>h#E=^GbB<+)KC&sq>iYeq^L+8QA5d4 zkvgJ=lA|JZL=B}tMe2weN{Ncp5jB(w6{#a?=p$65j;Nv3s7M`ALupWvI--Wsq9S!f z4W&ax>WCUjAMirynWux%5igVhCq0agc%h6q8DMn83uVH|2%~cdUg%?-OfWi!y+e>W zhgfG0c%jTVpTOuGg%=9L$qb`&3|=T4Ck#eMyif#AIE;>Xp-7wvH!9$TqHrSJECDZ+ z1t$tdN4!v0oGdUp;)Sx|WQEZYFO(f88;p*4p&U5bVRXa`<;2MWqa$7@7fwzX9q~fB zadN@vh!@I(lN&}yyii`8JTN-qh4SI#h0zf&lpiM_jE;Dr0yz0$bi@l4#3=xyBVMQw zPC*!*3jwJkYN!azkVqX-Lq$=MI--V(p(1re4HXY~q2kPo!RTCNT_T`{N}?ilL=BZf zMe2weDvgTN5j9i>6{&N}y9twX+q;F{!Y${D7b=HS7Dnf;cgHJ_Qw~Pw9=uRAPI(v| z@j?}FqG5Ez3suCa0HY&bs1i;^7#;CKm2oP;=!h4pf>RkrN4!u~oGLIn;)SZ=RE5zI zFH{|;8jOy3p&B^VVRXa`)x@a*qa$9Z7EVnVoyW{-Lkm6j>c9y-L7#ZFVRXa`)y1g; zqw|beJ!qk4UVT)gj;Nsqs7M`ALk&@pI--Uep(1re4K+qZ>WCU@f{N4;HPjRpsUvEr z87fjo)KGI&q>iYe7N|%aQ9~_JkvgJ=TA?C!L=Ck@Md~`)(6jE>l$zNi=-u|xe(F*;(0`lDiW#10KW#ps9~8ip>a54-SGi0G(I4O#^aB3Cj_L>1f22i z#DEl>R6p%uba3;Ew15#)*&LnqAKnhL4ne0vtNTI1XQ`~6*DKrgdsyjU(g{I?7 zb7usk(2Rf)nt?yvof$AfGjV3PvjRqF7S2p}cEAYD#+l{L2^gU{IJ4ck0V6aQXO25B zV1(x3%ys7njL>|XdG3OM5n6yV-(46mLJM&gxQhZtXc5jrcX7Z7Eyh{oE(sW+B{+-S zr2!+f6laOMjJc?tXh@;usHmL^kU}d^Q9B}qR-&SIDnSaZLPhOVh7?+jirNt=v^rpf z)}X6lb;Jm*Mc24%14d{aDt1SV(0X*8yFOrqHUxCg2IlLbernkbs2HJ5bnK{&*0vj= ze(Ksf_EVfqP(O8Gmq1Lq5OC-WU{GuzbebayfCba$h> z+`(44;ShAN9b#Q_!=dO9JJc#S9EJ|H!>n?{;pi|s+*)$O5$JF`!YVf$VU-w;L`T?> zR*B&#bfg_+l^BjjN7>OjuW7>-59*s)fL;aIDzaGX{5fN{*n+VNId;dq>J zc7jz_I00w8ooJO6PQ;mDCs}2MlW->5$;>CAN(`r1Wrb6$^1&%MlkHUIQ&6RZ)6l7Q znpH|T9i3*UTcw0E(CK!DRZ2J$ondEMbq|<@&a|_vQo`BjEIZpOC7grKwsWjf!nx=i zJJ%{DoQKY}^Q=9HiCR`A-cdWw8{q;p$qLI8$~|27+qu+ z+bp4|&=Pd9U1F6CE=8BvrB=z{GIXh3X4N-fxmCx2<;<7a6;{dM3Y_J3rByPx5@&^7 zWt9xB!dYooTV;Z)aaP$iRviP@;HiSj{+uaGfrkPo^zjtK?%Ujp-Pkwro>5MQU&>7 zDx8#1B^AgAKf+06QZpA@qLeTVDz>B&DPdYvY)NHO!gQ$E5~YOcQ891I2Q#1|Oq361 zL`BUhAIyY`wNv+ik5Tb>>K^b(kPLppT!cw2)|rERFf2$0!1aYUFXAIyOx!bJIC zP8<;?$_I1dh%iw;m>WlgiSj{ug0jvV(5?rj)P%Dhf?0VL?1G!ag{EY%II4azN(M`y z;!Knb(v6OF$sidlg^Dv#GDxSnkT?@1gJn>0CQ1g&qT)=H43SzIvkE~nSTRTjD>4^nqGYfVjyMw~gOzc_nJ5{of+NmE$zW9+aV7(qRSWXL z>Zn*SC4)6k@n1>?Yoh8GqhzoaS`*qt$zW}?7PN_y!8&MdXcHxaby4+;Q8HK$RlgV| zgZ0sR&?ZU-8=&G$#*hp)L>rifW^8Cos1Yj8M9E-dRGi6pl0mxCv!)|G$spb7SvNIG z2AiScOq2;WN5z>a6KsKsGf^hk5*24MH8cgTWNN^fsBb`PGcDjulnJ&m(*w>#nP6L^ zjsb1W4BU1kfHR>>X0nbU2b=|6GK+OA3E*t#lG&`=2bo}doLC4GWr7`W+MBo_6O6+V zXQE87BaS!|WrCe>#F;1)?2IGMM44b09C0Sf1iRvhGf^hk4M&`bGQsXR>PM(dum_HM z6)F?#iK8xs$^?7is57BD2K2^JuR&#keQ?x)a1EJYUmSHDTuUa{4@dn5l?nF8QD?#R zWP$^5)K_o=nczSi^$}DiI0$DTgo!f2!8qz5xGCUFlnf4~Yk)WtC4<9IaVAOzhokBj zqfBrFD%wPu;7C-oi88@asAv;qf}>H&vaYUOa6P$u0+C-V)R2453W4*{I6I^7J1};X`HAWo+mZ0hyqmBVf zQFVKdaoa5XCCL}}m}RLqIe zz_qBD6QzOcP%$S;1J|QsPLu|2Fvo=Bj!YD;AR{#C+Zcj1xL)u6=qw_)zB5_lB>`r+l(^7&rx-axgNR(U2>iE zcB3@#3shZWlm_lV)ivf;=q7Z@E!I2D?a(dglH06z8Kr@{QFV>E8@dBsa+mcUb1!rk zy5t_~y+$1azC_hEMrq(zsJh0eW5Cy_m=ooI`%p0_$^rMIVosC;euIiRQ4V+j6?38- z@LN>OiE_a2P%$UU0S}^LPLu;4LdBdY2Rw|5IZ+OH#5@Zm=ooIznb>}bD~}Wzv27}ZQ^*wJ7tXb8?=e* zIo@fUQ_v>L0ngx^hBooMkarg6477>$JntONS!fgW3OJ8*4%#H1=X)1$_;fC#UI7jL`9w?_mX+H(3_Aa$^mbqw;)fH1KvSzn>$81;9c|%fbAiFyV6g(LDr zIpE(oB2Sb9{(~d(B(wL4_XtPiiFyS*#u0fE?uB_za73O&c;Vht9FZrHUWE4yN90MA z7wJ965qXlui}L=(5qY8<@CA;@ldQ~M8l{1+P<4$_$AJG(b&XNSfd7ngz}KjH$K>*I zdT&tmj!^>m7FF*UC4lcx^^Q>j_#Rd77$txoQ1y;c0%%A8)jLKBpo1F6A^R)fxhM~( z$^Hs@A=HIJQ3B|pA;%;8E9_ZR{D~4k9~FP11TY>d{zM62d{q3262JtgddDaMOi1ci z5-o|Fh`g_qmk5W?79;N~?Ip%ZN$ezLo&;46m@G&DlQ9>6Ql52kvcK|P z3N*Qsg6uEaONpj{LQw*k3QY-xQi%lcBQzBhN@Wtj)aXZ0C`tg+psArylmMnh(?Fpp z0ZfOgcZ?Fi^k_OKeUJcVK+{8^s8>KnGy@chvcF7dMko|ze;=dbPn7+Af{H&;_LmtI zf1>O!3>AN(>@OS*bHan{F9H>RqUtW;BT;34Sy1sO%KoyV;!l+QWec*u zY|OJlo+$gvj*|`Yq&c%3K?0aF$o_IN&jER&?2k`}_i{p>v|^S!NC5K$*6#GiB^`zwSa{v?juzam1e}`zwZ16!JvbUvZpbkSEIiO5hZSJW=*n5~l>@iL$>^I3*!Zl>L>) zDFu0=?5_+?X~+|0e`RsXK%OZ3D~D4S@TP9LQ(ct6BUJ`?5|dk z`qg4y)2SU~f3pJxvWq4AYk(sPWjxtm zLmW{k6UhD=;fO*}_SYCk6pFIHCOD!{l>Ifu5rs0DSu^s!$#jWP_Sc-bC=_LXEpSAk zOk>uP)NdN>iBi8-Bz-f`83BtjlUZx>zL`)bv!GDgkoV1kI+@M7EqUK;sFOLY+mZLp zfjXJXI)=P&F4W09*0JP$^Po=Vvu;n`Hy`R`0qYLreG8yY7P5{b?^_6UvWRs@^1ek- zCyQBkBJW!ad$NReXY#%!P$x?R7DcIFS5iN9kWuQ_4Hb)`)UP`#7DcIF4^%9QQoo)g zeXGz_xV^~uRzsky4pT?;#R8;PoejPkxws5;0f?;DM(gN*XNG3aP#jHA47EGia7dEYp6EFEN& z_l-x#L8K_}n}CW%QQkKZ6^o+0Z<3>=ZxZu~P$*wBo9rm>n}Ui(QQkKd6^o+0ZImgKR=HbkRLQ&o~A7>uDW0dzTz!8h0{s0Sc7SKCJ{Q(x?h(%G}w-`q( zit@fCIAT$h_btT{i=w=58ID*K<$cR>mO-H??^}Vh912Bw-%6YnP$B z%KJWbE(Ju2^1jcU%K?$1yl=B}B_LANC18tlH6T*dC19&_Eg({q_ib~o2SkeUzR#T- z0gH7s$9~p8!9eEN#7|{T#851cN!I!V(AZX#_{P4 zaEAG5h!iD#XK~Izq^L8%Ih?Z)De4Sx9_JiHNXkBl2pi`9b-9yz!Mj79IRDEQW@jXD*M@AXnLsVRf`UCuq zic85ve}F$waVg69{zS#4DC7GJ6_=un?{8FGiZZ@`P;n{YqRK%QPTGq z=Mh9o6dB(WoW~F;S?CP#6z2&7%8j<}S9bO!iHYP0-X4C zkSRlFfP^>+=pa*;&H#yU62hgFqccEaoJ4Rb<(MUL)gK@!Dmo>a)Grw-I;8@sUvgA* zic-H6sOXeRq<$$;(J7Tl{ZgT#Qx;q>qteVqq0MbGn-x_z znHILW&4#L*OiSu{v!m)J(~1h;9H_dd)lH_ojkWnvb(85}+uH)Dy2-@Z4z?hwZZaKhoGpZ^n@lI$ z(H2J4O{TN$WQ(9;RJz#CwkRq_rK{~?i@DuwSF|f`aksneW{cy9QR!j3+Y&g%p;LO= z9=0S-3Fwqwwx=zHQxZC*x9w$10^7_GB~B_Bh!ajS+}q4W6PoHCezRMwdGND zlj(2!*=V#pq{;x>-&R1Q-3snNJHS>%E4UTiL3W_6gjR%9dGCHeKd`FIyb`?1JH{%g zddj?Itct3q%p1mPsCvr0W~6%zv+C4~zJ^qJ#Yj&X)-~OitZK4}RC&Rw7Mn<{MjbK#%V%3DLF^tMz%$mA?GB!g+s{Fy&92KeZJ7Wt}q{>6amS_v;l!we( zxepjyqheI#H(9l3i-k_P z$t=#j!5GITI^_nlj?^&Ua67rz7(20bgiE=~sxw__*rocGnuP*%vX%FQ1y=al5sYw-Z6U_ z=b-8xvxjjms@^fX8Rwzu9kYvZKC0d^Vj~uy>K(I#aUrVSF<&q)Le)EFJL6(hy<e9CM! zJz~@!W)riG=o*-lji^|XwJ;|e(Dmp#{$kn#v`38KFF6nu$26S3@BmbM&@le;+N*}L z4P!6s$7~4WQ1-qd5NhJ2hCr?LVJ?13*S5V;aaFqV?S+cB(iL$}R2-JBlzX7!vvdXB z9Tm5wYwB*OdM@c&yDKWfOV{9CP?2A{Ht&pz2-7utCsd@EuHrkQdXMTFKMw7{J66~J z9nki?hjmZT9*yO_t$T%7G=_J(?jd5(b{qwCSHW?@6Vax7j<%?dBDc8F%mA zDzZ=aUX4%@f4V1Yh>8T%y;=iQgrM%>>Z2kDb#GS>6;Y^rzPhM-g6Uqc4ys;Zx<{;y zicHkKV=c5MM||B=)7)mc&Z*5y&1Ep@kD4%J!oF!$nRQJr0N zk6s298LE5t(x`}0-P4ysMUv`Xza%QcRL=lPpdwH8RG>Jj-f?onAJx^0o_6FzbrqwhAbC+; z-RS8^9#mI7dTNpz)zy%mrsP6(m87REIZ<6b>FG-jR997cDw7@6)s~*tWJ7forl&Yr zQC*$s=}s0@S8aOg6NN@{O{b?pk!S?hdU{qAfrfJpsAovwXc+vmo-Ku;x?0rJrp%~% z60YT0)F-HV73vw)$EbQ3>e*E$RJ{%LG%F*jo`-tMl>tr9m8_nArAO5xQBTFvp(3*N zv@9(uQd>{a(x4)^^>i&Ys%vLGb^8d_HMO3`r9ySBt*3M;QC)-U>0Js`*XDYvmmJkK zyPozXLv<~$r+`UOUE}NNU=mc<{(5Sd7!|Rur-_MB^_vP?tL%JtcKfhdUuXJ#|n+k4-&Q zHRuP&xO&?9!5IhL|G^o{Q`qU>q6L z7O3XqKc4ui=0MMbU!kf+&~xIKsA?4S{P+c`+66sV{ufnEgPu1(M^)>f=g`kk-D~Rk z^ix!|5qfU@1Xaz1o@YNsRZF4g+>cPzSm-JEKdA0;^>qAiRQJAmYW^3hdtyCJ{}a`{ zvYxX4f$APwPv3t>b#JYw@()qnbL(mS1623odWwG^)jhhN?%zXo@2;o*cTwHbD-F1V z>Rw+d!EN*w&j8}Q4vcYBtK4#wD%?c%%s^?w4OGt(V!ar~SgKyGlSQ;+jG-FlT98^? zMfFTVX~q>)&ni^mbQ#q%3{^f|LiKDzsmMiCwK%Gjx`3)iM-^1(QPu7!T{(xUrboS* z&!VdJQ4VtkRSl5xnbWAA!6>&mh3eUiYPo(x^~^>&&#$PS<*4@S7gW!9lnecg>e-L- zqMuMb6H<=!BdTXb%9l=}dWNLj=>)20OUk2uK=sT?Io0>5o<*sG?KrAuRLZrEp?Y?u zyz3~cXIjd^j-YzhrF`r#dWdIWmAy)gm4jzv%F_;#r+vqhvx?+w-=XTsT!H-UTU5Q8 zmCGGK)x%kJd*7hy?W`PcKdPS3O8NGo>IJRz?`u>&qLm7Mh3d(l(!wuM^^{hAxEEEg zY2}K0Q1zfz-nbi8Z))X`yHNG4RzA5C)ssl&mOD_@%qh?O0#z-Ya?b6jYV4GMevYd4 zPPyndR5f|ZOSht`)l-hT1yv27^3~0#YWtMCeuk>%PkHR8sA>U~({4glBdGj#BdXd# zCAu3>^#E7WyB=M~^Iavt>(I44_f8A_^-fn# zz6e!MbtUHuQT19^uD$?O4|e74^HEiKDueQV@N`*=P}wKArVh8+VO(qM4ZJa zCln+quIDhiLDC{FV}#=b35h`CM&q6(&UR1q5VSF0u;q;^?{xRc|kPgHnl*TJ1yvZaFy{|sF~9|=#J0~RsJbXswvvUX-Wr$ON^I8jh!a+RJh1^Db&bm zOs|Ctj2A-E=R@_K20{OZ`e;3;J{=v-FrE#mi+~8Px~Otp zkzaMt+N8dxAi`>+wMc_Siq%5Zr9cE(O;owD$g&!!@?;Tb)luclBGIa$%AZB3RYjFc zi(IRMDz6sNRvA@}Ez+$LT9JHP1YAW_x%Y9HxC&@AdH69{xoEUJY57qYy7H*{HynYm zD~FbK$~lK&?#iO-_aGLp3|iVLL$8kS7!QU@Ii-WH9;HzAjS$&a5-s7BbVU4>K#Myi z9Fc&<(PB<hR}M(4WTe6+*u!5$GAQueq>!}E#tb7xRSM@HH>RR;!Q-PevFDk5viI9 z6`vx4H6to+MPzFRR6L7_*Yv137m={(Q1LG!WYePJVnoiSLB-36s7;NEqY-KQ5h}h$ z1a2x++>OZGl&E+d5xXf+aXRxu^BCuc#P5jkO@=0Qk~woja~S7_#QTT{PJ*frjY#3d zsQS~0AWnp;Z;i;}gsA%2h&4`tiZc>}93K^bBsMu7DlSRPvX6>a63c8+aZF;IJv8Ka zj@aiAD(-1wXaeKJkmI<{gwS}#2_fS+&iK$c#_@FSG0wQqSjKU5^!Z@MhQ=_CrPI%Q zBNqD|Dh^AG_FGhZme}n#sJJaL-LFycTw=ZdLq&Uu0e^*x0uvkl5)~aLX8Z;EFYK6D z@_*6iFlA!QpQF!U&D5Lf8Tu3kO=S90^a*U5i1jDvW0*CO?2pk$uxujSAEE!ixb@|; z^8P{phJEWpm#n|hzhL4-%KwG_2`i_rT7RN{m_Gxi{tr}Coml(d(T6a1V(=fL4`A`c z=08C1n+E~2e;*aK*M-jjyocU}<`d(87rg`JC-(miD*8_~0k_dxP=RsO3fw|(LJM}F zyVy-s6k&V1j@>{-7sgU;a2*wO7(wKw zsuP%MHBO=G5T+WA-_T#_AEw%lU(sJ+JXQ1Y3;Hwt##9UPGx`%usA@!hLVu(`nQBLV zL{Gwys@vR2^aO0Fy3n0Ke}Fly#b;OkfPN2)s;ZRlQFTO9waRf+ozhgratu962Q^i< z97T^nxvJ{r2zr=~YpRAhj2?oDtxT27A@m@$Y$d8^4x*xHRaNsHD!R4;H8g~556}_vTfBR5Tz3K({H7eRyJp#W%MFFce=u1>|uxf_(qN0XX zOSA_SO{^ND-KZ#I)gJ9aMIWmsX(uWwS-lK*prV!4v03R-fW=bV>ZU@0p+dQuXQF{K!2+yY^})}P~llZQH)svT0ANg$ru$- zjv!j|hb`Mg-J(cqoi9JfP84ownSB1(dp~)|S!RQuMm2*_NWB+EwMY1QqSB z>bJ$HD0o%HEkeb}t6FX$Dt2B~bPG^1^{TF$kLt5oRdqKH6@#y8yt$~@eAVjBL1#nm zt9oxXIt!v-^?b9?nUMaf_M3^$paMWufHTnPR0gOza5_4TiUCy(PD7_sNuX-Nspu3c z3{+n@1)WUgfhrCsqm!seP$l9dbRv}ss!*JWPN0H8m5US5@l-abqH#Prj*16WI*vof znsG+8k7Lm>)JE8l$7q9^2`?04^nzN75H*yeOemFHaHAb4aa-3!J(*XJKm8E4nfsh^ex%oU{pOv-;fOsLe-1(HR<3$bO043|B((3 zK>Jf!@``k@KdPRlFUbY_q3U(|f~2r7svfBSk`eYn)f@FW8DVd<7Zokf$OwC(J*jkg zN=DcdRgcvtWQ09X^)NZ?eHIXlE*K{vsRf zjCP_T=TEZ1PH0Ed$^1b!*b$909nJ5gf^ldE6K5W}4;UZ1?M(;sz`f7-z>PKS&3*SC z<9#>A#F~5VUB-KEI}>B>y5xdrThq?mac?u;an;NAwtI{5wyPeux7?eIw_NqUy-6O} z3RO?s8zh1)QPnVAClPFcs9%g}Oo_*c4Tb)MXOECa7wsE|CZ} zMjKI6b&*7{5vp3N3nYRKQPp6bCkt$Vsy6E!SzvusHCt!N0_&lwsM}Ko(dDtw_b&_hf+;(F*iXKTZ}{0ga|M?ig8M zG+Lg@xuc|j*R|<1RA5e5fiNce*n%sO{1<2qNBrfc0bjBDMG%_nA!yP9#0tIE{X z?kdLBt}0enxhol0xvFGc>8@a0>8iqYg}a<_g{#WfH+b^O0HPE@WKfs>}OAcLC!y2#IU=P=H7)m?s$JDYKio7f~Vv)x&Yv)x1{v6h zb|*1Tc0 z3fgasJDPEf`w|LpG`adq^aXU_DDw6fDBsS%ZBf-zJB&V?>Zu)O@ln-KJIq`(0pIn% z`~LWRe**pu!@r<^IUfJE{xAAJ`uuASGj3m)>EGAy{J;D6|F_?-e_j8LUTOUl`knRH z(C?|=R(~=5p89F@6YA$Ptn^>G!GA@Ali>UG_5b<41bo#E{yWu}d#n<&sm9#0O2nob zbDvdWwnY4&d}d)``v3iZ|2OnI=(W|~NxxMBHvJs>iS^Uy=g`leDEPUw-)PTuQ0+JW z&!0oDf&Ob3)o-Pr|Nr{0_49lDH~OuT1iw)doW#Lzl!X88|Bv72|Nd|MzyDdX1;1T3 zj%|kHo__1>9P=EGhk7k?uyQ$0>NU#AD#Y-O^rny;Jj<>m)=Luflyum(_ zmsLED&)QS+vFWo=^0La$n2_VSjs^Nu6n!E}epUq;6Lb96v7->H#GDs&OexGN3FiwP zYl^T+%6UY`prWjjaemRUsTix|oOg80D$Xhe=OZ1It>svy@_7^OPX zROjbQ&2O8Qu_#-0e%rLnit+QM<-e)USBvxWr9;!<>S`i2nwsCV1isGH85pauPK8!w zEQzDDc}B*{xGB*pj8Qlx`MFc_dg_WJB|k$Zyew={{8lM=&2{ym&*%A=uViJ*!f&3O zzl*L!lCvj$!dJ4fW#!eWfS;5x8GBV`zLK3S8?RtAZVsI6yb?MqhcVB=-@H725?<}{ zydpYthqL8I!&oKeFH#OI$9F{F=0U?56Y&=;gX(G~5nEzjHC-7*^7TCIWxAS4$fkF7 zBtG3Wg1xg8ZUU~z^r=d^!f@CMp!)2k_*}KsKx^o_@H?aR{8ji!udJ0SL9{W|34p2o?vgugP)iGhxQ7+ zQ}kPEzsk*)hyS1U5WROIcy+Yza9{2Y4k>;2{McgTR7oxLOjdsY$r5Tnc9RFqjZ_N(-0dcMQM3$afXW0sZuFCChW zuVrDLmEW#7zGdIiXAz~v_1T|Fpe1lqvyMX3Flw)j;x*GdG9KIie5zD+{!XP>$7j^1 zN`1ulrDA`sit7E50AEKJy=xQjw=TmTs`r!L`BnLQ>Rp?V?SDR1stSK|y>}C_C1l@B z!FMKStIR%99yc-jVR`n=b@@H? z4$aPAJsbB3b@*C6Hivr$y|(p(*RejH!<~gbf20BbU0qan7Y%~HPy^O=xChbkwjpka zdz1Ri8u1s+g*IT-h*<;fU-Zg0X7ka8teWsWjnGD{ny_c&Ms*Bs!n!f{K|1p_W#)5# zq;)g)vAk$rzM~miWA35!TI=(S;&E@)jIjmZ(+q8j+alO2TLk-H%iwiy$t%m}5b?G6 z+@rN%Y{jPgHSLeB*jjKO*OKpP&6bG!yOzw_@RgRR_RThIt+)r&tKXKdB{J>s)pJ67 zXuDv4Y{$Aa^VWPvOz@Y8310me)`_{tlpD);wnMeI#xiTmeW?Cc?fF_#?oVSGJMh(5 zRNX2%1p9J_V9$+Xos9cg{pI6={h}jZZ_nMX`d4)1d(^u^`*0`rnUrW8V`o%%${iUy z^Hue+(7w$lrLgyP;cF?mzorKY+L=|?VBhW4lbO?8{6~9`s)57aRflu};r33U$fo&sX}O(Tx3r zcSQf-T`(Xxh71UfFa!9$3_R;l_l$vjS3k5OqF40 zjKi7fb6s?d9lbI*^9GP3 zI)~K5sSi1#^G02qdXOVJSJd%z&ZvW57k(r-yWrG;9|_JzIJMzN67Wu}iBk)HBsibp z)Px^N#QU#0P7U~x#JtO@c}aNhRKu?hMWVB8Rh(*2BsxP^!Kn&GqVsrVoGMTxI@edi zsSHKJ)c~ri0;;vy&nqym2t|^LS+u9?it?VWH_9`QhA7b$OF2(hEajM&hb7UqN?Dw8 zuq3)xDT7lMmPA)3rE$u@lIUur6i#Va5?yta#3=o5%b1yNqLzy_jDX?4r$a7YAGMH7M{-kEzuS*O*-edLR-Q*>A2b&Z3P1r96!<4 zuu(c%w)J%OZp*w46jc#s?K~Y1W6*XmRyupfdOBCfGLM1A(lM<)PArs`j$Iva+Cy*Y zEF6c^0jf)9;Ep(P&|W$&b;9Wg1*YRqXPi#ZVP%BLwlgzVbFB;?1}b(P1D)77upkMO~--WXfIecot^ujyNec>6&dIIsmp#@4G?hK$tsSl?_G*!Q$y0Jp>&Lqo*_PP;?0F zUOmpk!_c8HeL7HIqa9S#H7khAbebOdam&bgz!#+-XcF(2uT_H;fSjWY_m zunDsbE>n_BAkV=sJ%EhEyh^{qpEYz5}d`bt9>{V zEyY;^)7ppGGEe87>vtE6x@e)M0N48P#FthrA=q52H&-u#S4m$h3|!KjIzp zmXmcI!#V05_g0wY<~YtV?|W~hSz*4%Iqv=7tuiak4>;d@C%n~Wl{ta)1MK`7v)Y`* zIpO{2tu<@Rk2oh`?bn&L<|mvVVer?Rb>?TBpS)j~|BP-h>&>s|FW#@-MiRc?&|kgZ zyiFv3r_kTLQ{JZ}f~V0_-f8bMlEO3SX(|IYlOUc&&v<9OEhLNQ(6in-Z!3x8dGwrj z-rGhJc>z7|UGP39p}dG*pdw*A$>k;VqIb#rf<*H&dWi~#9VDGs(97NxZzl=pRrHE? z)!RifdJVlwCB$wL)9dIpDkS!hq~1WUdpEqjB&;{l8{SRtOOn@H=uPjI_Z5lkZSgBP&2jS>edIm%ejp2ffOJ>K0DmpCtY-us*R)x5%a$#dXS z<~Q>n&MWV=ciNmXuW|nK-gsxsY4Zl>wfELLYtERrIB&dn-Z^vDyu*3xz4y+WbLKtH zJMV*c!JIcAaNcv9cF|nm5$Xlj4s%28_a$@DxTr(z_hoa*gix2-?pwUNraP-s_(nzj!BG@h^p^<=B`PClbEXS`{tfWij#z@?+50-Nrsb@s_%#9fk}>& zjH>V7%|nv{CplH$f0*A*N}Lo_egA3xFsX1-QuY0p`O|!alZvYEzs+AJHO@y=eg9+r zHfeBDQ}zAG{A1GMq@n8jv3X?D;iRSN`-ypM(&MC~>iY?^4ECvcVltu`sQrFso|;T( zMryyGn`h=@G!wPo|C;CK6ZB(hzh9VtO=k2HYQJBa7bXnNY{Tp;^U{Q)VK&_UXI_~I zG~7nm*XBPHiALB+`^LOBQD`I;;BU*{Kj7xDj$@o0IN7QFcA<`P;^d(AI|PlC3nwSF-yW1wZk$}yep~3JJUF?j{q~`n z^5W#7_B$T5Q$C!$)PBc@g36DRkJ|49&`||&@>Bbr5NfI*P62Aa6EZ7g6Tws!Mhj5^ zo*34u2wIp5@FXx;MbRQufG35`Dux!N0z4VaR&lf#72wHXxk{kLsQ^y_<5dzZK?Qh9 z*soG(Nh-io!Gx7YOHl#-5v*7lv@{jqsbR>~RsoHs_B#XYT1B)1wcisA@9MD6#-FmP4S%G7>;0vlHq ztwQa0W|+BZXjMKNJ`9$wI$Dhi@Ng&0sex9f0zASAcWT;5XuO)tYf$?g$*h)*g4L^y z)}jJD3k+W!n-!|B4)fa7erIJ?*JgwHt7o%A0oG$)m)h^_%<9`5FoN}MPN=~KXnndr z=Yl3|h&G`6b8aZZMrcF2Kj(oyY>YOd8ayvlViUA6)!_M{6`R`p@QY2EH=zQ&09<1; zoTgNO7le0gj?;_^@Ir8qEpVDs0bUqBvL#LnD!_}tO}4^mNda;7`g=+AM(5T(e zu2h3pf>P~nE5ogJXWorE@G9`EJ#e~H2VNDcFePzxKlENga4~xY*t}y{G`M z0WaGJr#BVgHQ{Lc;`E^cycT?IKb*c)fY*k*?T^!s3h+AcxC3zdQvqHVPIn;A06WOm zgWny5GtdsU_2GI4;|!wTb_00dAvlBSx7`p9cqq;g`fWF4Hq17H5*}_F!wnB-K8$|b zjhT(GO`wWLq9f?H-4xn*6grZA+s&YmN28$*j{#0pnt2>L z){e8Spq$5}y+ZI}S5<1aNvhAR#C!>?>WEj7+Y3&8ATT6B$FYllJeuS3_`b#^$E|9W(tU2jJ?!<`N2db`1nbVfKE(G7N^9p#L4HlZ8s zCOg_0<$Q{6vY*;9&S>W|^i%tp9ZO%P&FE)#vmHk@!WMM1-D1a6rLYyW;M7UzKd&Mu)Mzu&(!JcG(0$uN{bACim+8^x(>UMrYf3!c@jnwn}jQ(VQwwtK)`33#i{$f9+{^wWp z7yGOIjJlxT>}D#3eq;WtJ!Q90L39e|H+$M{rLyQW&MAAwZlmJp49;nL)_zVU(pj7{ z_MF{Lh0-~kv-Z6Gg36`yIOpsIyMv0R3pnTPMZ1$qr;9ij>?OO43aCps7wu)co64xm zIG5}dyN8OYD>#?!RlAo;s;f9x>^1u(6;{`9uG;JND=M$9<6N^h?AKIe-N3nSZ!*7u z?xSAomfcSU*DdBZ?QQ!Fm0h=SZrMBb02N<%aBkbX%?3=Ey12*aBm3B%q+afc{gDc~C(Iw) zr}if*>z?8~vCr(!RNOtod1{|Ce}?`-J>I|eS1R=WW&Yg0u)k5c_X6i%`_i7GqVFZn z3;W8Rrqb^f&P)5BJwpZHe>kt~YkQW;z}Gnc**DBzqvxm_e2c!ZZ|!;N3E!b_?K^vc zI>YzqJNw>Vr2g;&`rdx9m#9lL{w3DNzf8TNgBsuQuTaP6qK@zSSE+9dp{^hDuTl5t zp&{S%uRGTqi+aBGZ#dT-AGN;k-*j#`@lfB7=ihQ}I`PqXetiG7bIVD9#`hEWcbwZ! zLNtM&(7)^4aT1{k{Y3sf>NXRjiTuR=ed;-rpo#q?{sZbflcGudr2a$dKa-(J{bc^{ z)P*KTlljU0Kd2W?fhPA;_j~Q~0U;zo|G)g_F|%$p42*)Q@md`Kg(I zgg&B9HMRek%GESzYCnztgo@U*{!?mP(=t!vr(>QLeMSXrdNiG%-hWPIYz8#FpTYl^ zirI{420x?!f=b#qZaoQ<{$f+{nym!X2$u%5A)y9 zg((atvmfrirKUF=C(MuV-%;xuffMdW`tPX$j>L)Zqx=ul21nsU`dNJAesHqjMEO~L z$2D$NoGgAe-=)Sl8%|a~yC0(VI6F=@KZoy8lbi!5yPwmy)GFu1$>HbneQKC<;pFsl z`|+r4&W)4H&*R6Z<~a{eZa=S|fLiFhIC=bh%=4lNsg%x-=JWIWiKw71fadoL_=%~k zE{GQJ3;Ic@xGsbi^b7e(sl+bqC!;pIF!Mrw5$1)_`oHBknKLa)D<#5XS<^7D*u9wFt=STaQsA-SJDeqVCKc?2b0#3AF z(f@=R_=-3c{7QaiYU3;6RP-zRVbsi5#;N32@x$FPw+c>Wzbf-8XoMT?Rzs`$)%-{| z!mW;0^Q-$&ZlqfSt?t+Gv$#=iO|*tz)6eQ=aciM9{aSuDH>+D4t>xGDv%A^cI%sXb zj-P{$0CmwieqBE&odW8ib^UsNE;5t`#P z^IP~u=#|g{r@7zKFG>%EmN+f^R(>&hE40FC>9_Wa({rIUPAk8SUxHo?ZE#xqZT*t; zXlRSm#&5^GEn12W4l!suKgKUjXNOoc#*g*O(D9)?8tb?B%hCy=1KQs2;FqIAL>$_| zkMqmZIie#P=Xdm@=_t_&?dW&%E6{18Gup}T>{p}%MHjTQ-^H&)XNs<97r(1tnT{3R z(5`+rzY3i!x})9v?tWD|T=YP@`#t<>biU|`_V9c9)#-@Q3+?Im@@vp3qc_^i@9o#5 zgGL{;x8KLFMQ4q^=>K8ttpcpL)@a?eR;`+|aCd9m-QC^Y32w;_2?PxgoDd}NhP z4N2(e4?i*eO(T*!2AIZVc?{sXzZqznknu6lG$r+8AoT%e5Z41?GcrL2!$D@SX--zi z5YvM6kRe*(SGKR`%GuCv9bc~Fp zGRBNEog}y(ex%AW+IiZ%{S(KQe(cMGSPf%J|Ioz zTPoj}@67*5nfZ>&x8{5EA?Y*UQ~A#P!1edA57{(7!XM0!<|8s|eu6)mpUlT(+58ND zGC!NXWZe7$e>T6Eeq`VL3V$)bnomf^`OWkvCFeJ;e>K0G0i@^rPUSZ<$qXb_XA+g) z&15r(w4KRRCYe9XVA6N~pfcG^F+<4FnL_0cGu3=bzRpxCQ_M6ol-!+ZRHmBgW*DhF z)2U1|Gt6+(dS+0WZf2U#(0|UPGQ-R=BhZD;qB7IWHY3rC&ZaWU%rT?Tk>R(jmnZLRI3yw#>Iv@UR<{Rl+7r^;u zfsx*IAzWY<8tGvFfeXz)M*7%A@E^0tNH@C}E;5Ua^t4OhVzb0ZXS)?Fw*_5G*SYuZMP;Q~ zZKNDtO=Xo?W27ivLuIvDYos(@OJ$8&XQV)0M`f*9Z=_6KPi39iV5C^yKxMtzXryG` zNM(cBWTbH3L}jDdY@~eNOl6bV!u4h-UG!GC#cVax(MxZGTg^5j9rbp&&1^T)SMPw^ z%?=~o^-j3M>@>3@vm(3TPP5C*L8rYN?lQa0T=d&};BK?WNY}j=?lF6f^xpg6UbD|g z2fiQfGy9G7;RoP;bHGS9eh?lo2aWXPhu}eT$Vg{?7#=c*jr8Y7;9+ybNSA&T9x+Fa z^yRA-+@NyZ+%(%G+afoq+%UI{ybQOf+%&h1JPx<1+%k8JybpJ%+%|WOJP~)P+%flz zyb|}Q+%@-&JQVk-+%pf1ycG|q+&2%6JQokCJTQ-pycmzDJT#AuJQ|OwJTgy=yc$lB7e)?|m+*yoY2+Mv1z(z1Mvju#@RfOO zo|Ly-zcKH)ehcMT30ZkqLiSAL9cEW~Tf$UAHe%&@iBJh!&&mtq zQHj{7y%@O=iBj>bZ{?lwsYI=@mm`-VhKg^kmDk2nF*dNVkt>mainVd<)kth44wb;h zlRfJ%Iu(8?2(kV*oZ$jU2}h)P16nCnDP zPNF0*u}xy-FiHxO*rZm@qhv6tO=jgtN)D6RVdY>-2~*gVR?enWFr`gp z<#O5ykps^WV1P}ho>wDmFzaBjp8-SNhOEPWqmwoxv1o{xw*~-4Gy(DFt^QPEzY&P zFpte^0~~GnU|yTg%ITIL=Ck>2TpVx(V18S`${AM>7O(|vd>nIyU_o2R%1Kuk7P5tH zLL7EQU}0Ot%6V557O_QbVjOwJU{PDl%Bfcz7PG}|QXG6GU~yZ*%Gp;EmarvlavXo9 zU`bob$_ZE+ma?U7N*sb^U};;%$~jmTma%1RY8-`StvrV1U|Czvrp0?$9+tD^tvrbp zV0l}?rpK#T5mvAjtvrmCY(`v-mAI~GD_gl8D^satt8iTz#^8ml3ai+vHnSJwRfAP+ zHJioD>{W-=Y;~IzPh|~Q-PW+#@LJY{HEd0r9S>$LSkub5rH-v<^WgfdN2RWo zWDDRbZA7J^ZEOqTHf>C$k!@n-LTy5&v2AJ#<4$c#rHO53i{M&qMy083ZslfePNkV` zVT<8%Z9%2EZE59xZAqntZDmW~ifu)urEP8HmTgU?m2G27;i7FrrL}Eq<*sc@rHyUJ zbz4{l?`?b7&bGJm16OiS zDm`p3TNAf(FDgB4Z(GZ&>Gh`4%f4@G<8FSRN^kptt%K|N11j&^|Jk~@q5nta1N)(^ zhfDfHD*v;6Y<=9*eW-kBKjOL%Y=F1=W7`n7^~YR)Wc%7ixUlRF{)9?D+n?)CU{gHZ17LqUz&69{JrEAC18s9W;Dg{mJIJ=c8$K8gvV(0)JmW*) zU^~RN!b|=s9AZDUt?`%-g`e7?whi9%VQ{D&X4~RP9}b7v;kF%K_0QmN`_~5f zHxtgVGwmo+BWA&wc9tDYn#624%g(lANST;p$C5iShwIsPF4uG5I8rJ8gmdkmc06en z^WdL$p8cE@i@)GJ`o@LmfHX9kK}v&N9A9;%>G2~$1*Da+2!_U@<5hTS!P$*U&skrL1npJX@4a@WF?gq zc9s2&T#;2&R@&9}ck)J7Q(0x#*h%D&tf8{nuC4m9=)gokE_; zdMfMe20N9UlMPhX+l^drfJ#Bx1UK4EcDgss+YC3^&2|Qe;Cefp>&@|Y+CROyaIUw*?y~d9b=gH_r`>J;BJX84 zm0fm^{hJ(^Jydqvy>>qNFng)&vHR=-a%1*U*=zUPh2+WXr?Sr;u>X)VbAZZzd(bW- zf94>S1NM+zOfJnKDhKUhyM(-&!&DC0BX%h{HbO39|B-uhjLK1a z+%6*z=Qx#P_JmzdPR>v)_E7<1$)tMAO+|Wyl5}kjiduz zhL`MRyUE+=U4fVF6}y=_D*?k;A{KFp7Bn5Z{ZvJ)}Hmwc<su6nVag(k4UHSekyKpOPHhAg1@X}IA6Qm1Xc`vP#vmpLMc;WbR5AsbgD{D3nW@AC zS%L^jaapKj4zdOw336GfWC^kbQIh4dQOO!)=Q6ZNAxVU8eYV9BY= z1#gR?=COQ6XXrzk%N~nh)*(JKCbfy`GW)`=H;i7 zFDMWsBuTFTmHa`$AQ1_B1*sGW3I&Nt-YZ0ai8Z1MlbWk=(M*?A4DrJIlL3)x2%TXyCln*kHSXiD)xu62qC#h_9UL;hi9SShF+WRAu}tH8=Zl^{zrbF?a~5>yScMzch#!Ky*E zAX_wRv}2H;M8}Rn0Wuz|Q>hkI53)zIMQgz7L5(0sG<&pWkTaSC=Ac@O>zXiEG-tGS zkehVJ+FaKP>I8X6eXK*Jc2Jk=IxsJpkoAI&K|Yu_S~sZ2Ro-a*pcA$FeANpY1f98S zz*qgCVbF!UhI};$8gbn)XdHB9Y|K}qph?h;yC!@!4w?qtxogT-lb~79gS%#YH4T~v zJ-KVnSF@l6*Uf{LK`+LZe6#&$s;*gojM*gkjNC<1HsJfN&rSnapPz(2 zQ}tmzenR@J)r0y;>N8ju>gTLaXdPIaPk}zUwPCHGw);fag8IDZlU@_n2x_|DfErMr zFa2gzhx**MiYXH&mJRiQq!`VFfB^;y<$US+7yxPBumL4Ef1n_3a-cS66x6`+1s z^qXBCmg6@`zwzZ@S$@OxBq$5Z@SCS6L>X9`-$*?B*WO=Hp4GCvHBNH^}Fn#Cf5fd3r+UfqE9|$(dlZH>KUvzMmCt0C$!!qSz#8Q+&=rH#_*)q8z}~6 z;tilTRVJ8`H-p|?8DR$A7<#8=fa!UY=v|i{rsEBxcVIf0mN$>yjcH*T-bi|9rh%z> zQ|Vor8m8h6rZ;UWn36Y}-n}Vd3f_2nC#QhPc@yegog60P4XJl{GMJP%XDsjbq%cX4 z)V=eQK)qu%7f1~C?$sP25!5?bbBBab?`q8{5cAFn1^b1d=K7beyUmXU3iCit7g-8;BDr!nq}XHx0vT@_I(T9Wd5sJ`Av9( zd9h~eH{f;V%bLYshu4@#Yj%GPUbWZUtp6(1j9aULSg4t})(TgkX6RZ&T!xytYi)4} zYDTX$$3>`_zSbfapjH4{qnw9Y8EEZt4r;}qHO*P5m4wzhXP{OXS_7SiT6t(~bP8%k zqBYY=sFjM=QYYYX)-hUR9f!wQ-)QZ13?60Oqcz!4c!c$kR%u7zVb)1n!ySf)SU+i1 zcL*M2U8U9DL3n`mmR5lW;C|L&S{?3(`&gf8)wmDtW!Ga-?qpr4HS12e!|rrz*&R?TNUd?V!)T# z(3_!Fu3B4ff?CmP&Akz7rK`302DqMeu-547;X2mGTDz}M`SzqL283a(^buHAx_a0Tmi?INsz%UQ>3cVRhP#`<2n4$I(wtoyYa@gMw` z{Q&J!{0o<|PoUk4rEm%R2in_M0vEHdpxutea1r|r+67qz|6w0OyCeU=h3rpg*JL4F zU>CaGlm$>b8QNu;54FRg-Iu?ic0RN#^B2^Pi1umbLG6@i|K?Aq9Te^B%!S%n(SFYy zINQ!~`#`gyc4D+YGz)5nM*BuH;S6?ew4XEsYDY)=Ow*xudbIyE4QdBS`%+V(c80WH zH3e$lNc&iSK^^EAbSxahuB7%y$H39-R%+jLG#q6|yZzKrQ2UzNXB`Q(->LoA z5m5V}+MWFjYJXI_w!@+JO|_dl3~E1BySzi8_F1*>`zh4^t9FHlK<&$Fw|Fqreyw(q z2SM%QYIk`c)c&q^od-be`)W73Kh%D(cBwys{p=@h_qreKYx}uf?Y{71c9*MpRT-fbZK6+`jw!u(y5R z?Z@|qy=-r{Pu~mnw7uN^eNWiK_H_IDJz#g+!|nQahuzqH*J(gE*wuD(rvzPL7u(gH z9&~}7Z5MZ{&>3o9U#AV7p!WN93egej96+ZN??Igp=+vSE)VYC9GulI)C+L);9n?94 zPCwehHny!h6=?%o+cxgBq%~~CsfA8aTEUjKl{;N&30v5f?$o6PY;Ie))0pP4nQiXQ zXPUvLwwXJ(X$qUzrkvztW6aKpN)t|avNC4lq@}St|7ipp+D7hNs3B}%8@ltN2C%+u z;Lefi!+N&9J7uZ|>)Lwm^rezAYD1kD>HMk|)H#yQwQ9l|wx&Dp zssVNGq!X~}Q0GxP8LI|$PNfsGs<4W!>Q2(CK%Hypgsn2HWGlOqw@R?0t>jMRDngx) z>7=d#)VY~X@XAA-r|D#`9Mn0RPW;M3ox7=m))ajp2Ad5qt3hHFC7}RN@PArQ;og(Tyvk27bV$|~(qwdsE=bwc*^VDgi&P5AC zol@$&v;frUrOr|FL!D~sd^I1`X{XLz^Fp11>O3|N)aj_sX>&uJn(F*E7tCpMxf9)- zFb8L?I_b>;v)df*1UNg)X0yAK;cPIg&E`&wv%)Mkt2;@~0yEnz?u0orjIo*B$#V?M zWMkZkbS9Y5W^yOh8DR#S(VbvtfI3yy$##0E)8@OJc&CFpg}%c{cv`5_>D!!>r-3@P zzQy@@YN*rfo1Cksf;#2C!FhX1sMGK3oWrMpIu*ah$$WCC)AFmF+b4rMMUUk?KPlAd z`W4RklR%xiU*`NjG1O`NC3FFaU_zV7=>-zP1U8}55hQ@|Iom&vz92q~XX88FK|C1O z#&ddvxKQeVGbj||z`(|_(k}$i+Q6Pd(O{vm)=KGMpl^*mfdayZQR~~|C?lfKvr&5t z#e@eV*0V=ZQbb@Fjl&Ui7GW5&VS5<;MF_q#A$tg2#yfM!sU!}f*LZ6VqMLYY4xr$%`*o}VVIh2}X7rK&X@F`l4o#;)T z!Y61zcA!If0w1Fd*^WNtF?@t(WE;AbNAMw9lC9`j9>ND`OtzqNc>wRDJ=u)@40LPR5?-xU4c^TNHKI7UNV=RhUgNMx<}fg zi%_Z`X^t*Hsez)Uk9KxS<-^-htg_EBeoAp!zJz5UMOvslx2IMG+$Dj?S|5VNr|=#N+TwP z+D<6#n3QWf;C3`+QnYP{+t8Xx>9!4SMS~^<+*T-Unv`){pfqbz%x#97P_#)&w+U`U z=_YO6Mz{e5oHTbE;ChsC(&DX$>rl)|qqh#OMM)>^-deZ@g`G5gYv5{>chdT;hO1EI zNdveFu0*LPZQx3{!mMIF zB^-;AaS4>ha108^#ZcPA(I_7mL1_}Di2Mgit0<-9LMRQR6qE~~w2e|$&WF-GN^$u& zlonD-%)j6~l#)_t&VzrVpp%cx zsWh#V;Utu&QoK%rzoST%683la8%k9vWPgLdn%|sq_E#uPs}!}rKxtijp|t%ON&_ne z?oUwK*d8cze}vM^O0oL`l$N#|O5X3`cPMSUqVW9=ev1OP3(DVb;WsFAr3n58PDHUQ zrSL@fHA-G7h`)wkq41Tm_$&A&%3mptzl2|)2$lx<3pfF#u(Zh&;O8iarCI(Qjz?K6 zE%SId4#lxF&g0-%l*rOPkA-7UC`%JP298F#EXDL_I0{9xG}NQuNHfZ5t4Bg3;-wbf7^Zrl@@tTnuj5VEdTq^Z`sMMt>uO6w!Slubjt3|3Z zR&xsUs*x&;Rh=?jD)>IA;H6lXI{rf_C3~evMaD`_;Vw1(2dL?#e3#1peJDk|)c3ui zl=4#L_kvQ;ORe7%N?9*0e-GH*^l%#g?y#Hb?zI2ipcMM@1ayU6OjqX>=mI;NF3v;H z8Fn(AowuM9lmkGXgN{(n0C^GKgB{F!&YjQ!w#QE(??QXn&a`)KhIX*6Y3E!HZDAYJ z*0~?rz}EN`c~)vcIZNbasR?VCn$F`=16DURocEp5RbXXP#d&Kg!%C*I^W0Q|6-_1Q#iZb~@s zQE@1Tkc}8di)W~q^C}gEauoTID5LM3M$w4J7uw#ay!pfE|}Bga$c^SFo((M zJYG3qc9X-ozOut?CcATkWrJBwHs=z{3bUB3&OMd|W;R)zt1L5&F`1p)ECyyWG0uyY z31&2zoI5Qe%wRG)*IEWBhuJ-RZ0Vt#XLoVArGs*$-NF5q7Rsr18&_N!C+;y?|_L9ORCaLrDC4utc zUB>5^7|Ne_3IAUrDBs>ie1Qp}{CpSi3nqZ_`JKl{7$3_2cMgAHJSbn_S$v0aVH^|J z`4Qv5z{GJr#Q@4*cnbfbg~nJMjVBmShJ9m<{Ej}9Pw_ZD$S9P5@fiL{4@Qh<xGKX?KFGtkEkp2~A2NqS?pdvn>PCFAccJ{O z8}Q5Cf%3Vo$47e`%Ky3!f9)+OU+h}kw>P2uvTJbV-hlGauEwo<9m-$33jgjkcopC6 zO5D9yVJv>!6}Wz5p?tc_aRXn0^6xIgC43oP!rl8H?%_-DBCg+maTQ;L7yOIPZF~Wq z#~-`|7xH;{4)^e4+{x$QSzN`7a4nyOXK)+;gPZvbJdF!^Aui|B@D%Rk1-PG2!IQX_ z=i`b#2~Xf={u{US33wcr^Iy2AkHcfQpXcGLJ_e8CivAP7^-*{PxAa_m*hk=DT-0;$ zXCH=#a97X9w|xj6#C1IjKled+05|qb+};P^e*b_!0~h#yxDVg}vw_U&*R?(^Sp zw{L@6aiz=kz7=l4tu8nG7PuJ~yIk^{;U<5xFZcW=xDnU8T=g5_2Hf!S*>8aBammYn zzaFl`JuhGWI=B{Bz5M!X;Tqib-{9k416Sk1pNPMIHC%-||7(2ztKdq1mH!n<04w1N zeEeUM5U>I+$KU@2`2ow}GJO9NNEBEG|056JbMglMga48fFrFNOf8kQ{1ICe0uoNyK zU0^JU1xw&!QU}J6WUv@6@)!G~NjO*pl~OQ@(h-J{xbPQLYQj*G80JBxDSS#o!=G?2DGNhLZkP+_kiMWqhdFRI zsSJZidYBDok=CFDh*@wZDGo}8mF3;$spira+}id_+>kA8;~h6Me|Bm<%V8Lh&K_7L(xbq*EyO;&=EPsTIn@_znI_ zn#KDhWc&)1a?zXoj9;MAFM5%y@iY91Yz*aX`~-g_GoweiJ7W*>GkzqEqZ?y)ay5Q% zxgFm_rEYW$cVX;G4##&c;p1EQ4OtzX!<`sAliTr)O9Yt+zb4zGBS|4&!>`Evc#i~; zui%&dS1wuPOQ>{^_9Tvc0hJokjwF%^P-!AjwZ#V1<5F*;V9Bgl$$aNjwJP@8A&Q5;Rw=Dnv%0J0xBh?Nw_g% z6PKRSINXS_u}f8H6mH1a$fd0`3^!nGNdC%Dm+$f^96~xv{ct_T`sB3?ad|L<;UIso z%ZV8T2l|6te#}5Pz#r&xWd^|h{s5OZ(;t4~_a}9x24hX~V?J^DH2q*-zn{yk=?g#h z`;uN$m9ZK*G#`^~Q-!fA`7|H77_E;rDd;Jw0G|zlY29=?=U3-Cf>KH`vwh z=5m0#!Y+PSmk-nhcJ{lt+@Q{|li%6p33Y-U{Z1}ts3UyO@96S}-h&LtUHDHZkNrL3+D85 zxy-hlFo&PhWx3^m+5H?Y<1IVP=4W@=Z`q)-+@6vNmlbC5v%0LfEHJa5#bwB4hB1C- zmn|0qGx;$tb1oCi=x1_?bQxg=Kch>k%K+2+8C-&0dYH~n?~?7(!L)ulmw1;Jrt#Cd zB)l{*wV%c%F0;@=<6D9Z ziykDA@hyBq!r}pv8sEUzBronK!SOYGMIz%qk{w^cmn1drCGqhkd_jWa9+Dtmz~>}8 z?j|AfIebRq<1UgTpTVajLGC0=@+o{mLgWrICZE8^Bu8#1d-5@SM55$2(kLInha^pI zC8hEqd=PyY-9mch19+cI%FU!&-iPc$1{ewPbDHgg2r$T?Xe3sASF6q;g(|O59vUX6H3{HG0jZcwU9E z(W@@qGZtQn#=6wcD^Q7^%SZ#g3@=45yOhvN@M83mOAoyWFGMf8RM89YeDs1#8$A!t zktDj96w-6>ED58FNGClD&yYO&52>YR;As*`7m{Xr8lEDlbO9-+r=Su{=aYVV5-QpB zZ&FcDz~dyI{zY2qad?a*)On<+9)m|oNd1#^)uZqT$*FTmT|EL1lc+j}G}goL5J{`E zNohRw^(6Q^ zN!9-&>-u;28#&e=kb(Uh{FQv`_sPco75+l*b#F4We}O-fhuw=T?VsUK_g_;qxm%LV@$ens;4d!Y`D$_f9<<%oX?zaTHXeW)Fya>c)Jx#JVy=j4mG z4YgrZ4*BOUr+hpdM;>|WP%B2|mXCAk=40WQ=vbF`J_e2^*StljIivE=N4u2tQE+5* zl*>&Y2}h8R-Za#NQ90@(T+aGuaCr1Hm%lz74vP+Vx$MK>(C9Fi*FF?}8Xf9#+&_gw zqMy2a_aSg_bcoA+9}EXY2fIA@L2zJnkjsf52nR$5y8QS7uzz%b%a!jBKZ*7yX}$)d za^^oFfxbGU^5^@xeEPod<7i(J>#H&BSv@4J-!-mq7+w@cse1(mN~HbgfO*dyB0rSu4L-{h&2$ z6>aVMA+&-mqpkj5w*>V^P|t*1jJfHD(86_BXbzi2o6}<<2V>4q(`Yk#FJx!TL6?lC zu0KN)*f`pR{tQ_ev(Y7^G2I)oFlMDcMkBg9WM<4le~gB%|3d>`*$RDk896A#G5iRL@hLnKCqa|D~k>aozeKTyxFxrq04V^KHxjrOCVUcK2*Po;a zEF3LDmlAql!9vl(bT6TE7AzPowK8QH@A5!2&h{Hc6&x8IS$?!_V zrJ54ILR>r)@wiHjk0Bn6$9)?74e?=o?$dIe246-(#&mq8#jlZwyYzge!^e?`s|_R`<8fN+nA)8-IU4 zl#NQ(Xm+l%L49{}xbIgEuCqsTa-9Rl2?e2CFek2-xS=?q-0u6Ho9kToU*d=2h4N6z zjV~raD1Im}l|1-m5^$B@{S@<`b4aq)sg9__URCzb)mcl;sndF_eK% zX$C%>72I!E1uEtF1ZQ%eWBu+`;&)G<@64eXKL45B=U%_7Rrp=i?}L7at3v&r=y$ss z)bCIBP&R(Qvb*0aJqv2^EYRrwrmdyD^%$_KnD8@Tsn!%zd>r;S1lVME@c zAGz7UM^yUo#%&U6%-gpyZ{5CJ>wT;_L_etabhA)X-rvpK`@4Cl8SnSz?!B(L$N=Ud zdf&GUwO~Hb(#-=}g<3LCXyxVyn$rwsPNR84n^0@!6>Z#nLUW)`nFDE_(Js`Mc}P1q z|InOi7;`4gOFD$wGjHkO<|~?Gea0M1^O%mI_n6;wbn_d{$wo3K)4WG>wNX&>A`7%-^TEwZ}9nQ<>{)O){OzG}ZuGtIVJ>owb41Ff*ylV9hX^t66S^GaG6} zF*Y=YmBv`N($I=%E-NCfK(tc&6KZ9m71TVa6^m9@e?hHewBq_3YK5bf*nFs!k5*_4 zpjJd$xh;fRDQQLbk6YvY!}Y@GBDeNiMCBjWT3Qn>rm~1NnAVC*sHhi=){sl7EQ$W> z)|UTLS;|`Or_hhA>waWCx6G|Ymr?nTwV&3g%c(45O{lf&3M$K4D{4)tCjW!sFkf&;2WVidkb`bd zh@fYQaKVm=JsNaQ8~)q$1=AA zvOKhmoskux<#0LsA}6`lj>*c<3U*RfvV(HU?f9IA+F{X7&>5(mmo;>0ISaKTqn)F3 zP&+l+Q92K`gQK0M3s5^d+JU+Vwd1pqovBMuJ3-p9x(u~Lq@AoQ@N)Eu+u@3Z+ELmX z+QN?0R=3ln9kFZdh-n8(J7w3QcBZt0b^~h1N;_*e-Co;GuGI@hdvLd?+>G9Kdvmv` z++r_Gdvq>4s4i8$dC9JLl@Wyy}-TaYsc2367i${<X+cVz2nN+atacy3OA49k+LUH*|-+<-2ZA`CjNQd(HRUUi1CXJ@%sS zyFKU!q5JGnKX7}~4?_>wyME~QtRICQvZwtx^awtpn$mv~ddyDuWA0P27ypEv@F(1- zW{>_UJLFHfPvbuiJ!9wm8TV<~(|^v6`g88n`7c8+*lB;keR|FSUa|xKlKTw)>(DE9 z=3jB2ku!tW?AX8NJ`-mNZ`jFy!+nf9X^5eciCuo3KxC#8!|s1L913Tll9^Khomgb0 zl7-WP2v^zMc}8}ajkAPk*bC=?I%DuT|Huh-_Mmf-Tu^5cIxoo$bylHslsr&p7&>3c z3w5@kbC-NjXC69_$q#iFqH~%8P-i4MzbOcHcA|5gLQrQaI`1hAb=IPDpdwIbFghP9 z3XAwfIWbDYnN3pei*b^aG+Z1O^NVxBlq_5V7WYeV@|2vjpA_7ebmvl~U`fA}JFhCu z*;Oh|j8bt@RE9IH)SM)x=Dw^u@hVHDj9-p3u(X^!rRBt_JlEx*&dDmk@_q$(epV4y z@GEknmVq;^jGSdv;-oDjXI+`Nuk6m@s=&&A6?Z;Y6;|=9x^uf~uqtO}I?t;Pt8td5 zbG{m|x?h8nzigbn=|r$5*EKke%i+%CbY57S^TJwwZFi1X2kHzjcQ_Ykd%4}&UY>An z&iwMYGrzpyJe&pQb!UP3!g)C(%;(Ms^M~_shM3=-9To`Z=S;C+xBx6bwXr(^ZA_(+ z-^87aHlfnkZ|Y7=n^I}wH*+Vc&8Rfx6tgI2m@V8nYYVQMbKY6Zoq84z7vog4M7TIC z?s~qI442@{v;_BU+&OL=&TiH7rIb5WEgde!scV^VX;|9zd?_0)!I!%ekH}6~g5?+bz$1Cr+0;!iwPvoC50{x--|EI1jGO`E(a5o&B!v+`223 zE}S3hJi8l}uAD3DoVz=fZk#t)4_D(1x*GRA-MM&ADm^%#)_Hj^Dm^*3t`)AyS$0kC z-*@Nh?^Ef`Id`3KZO*=HyPhv~!*w_dufzR^?wtNZ&gRwgMd$Z@sHo>leRrDPAY7kQ z_6F{hU8nwiIrZ1+yVL;vpibqb68Hq_v|j3g{!pj*QWXqlcWe7S0=^lnsQO_6YA%;;I>JN81iQ!a+`JXxc#Aj57 zqhshm$CeRPK11Iiy~Ri>BhWoahcSxENc0e$!X42@bmV@F(`}5QG8+9vmvHCsSSn-C zRdhw?F^tSQ8riqv=$p z`7^kl4y8t#31|2-(I<@v&w?}kSx&t)8_x1)J5|#hD0Pw4PIIADM`OcdP$P}y{!f1# z>Zo~8DkZ6={(@33Nlo=Pl&VQ8tNHM6f4);+Er9d=1x}T<5K0{-wbnmSswt_s7CBwl zBCh}O7jrF@l~i9#pww4VgDr(pWl1IWFO*tK>aqWzR9sS(Eps}vWnBN~FL(O0wRCCH#;td1 zx%FJD&x=%a8>pzyi_~=+sci5!In~`JDjQM4NsYIe$|iq{Q|WD?vf1Ct^%giIJRM!# z%FR%_M#M=k6Lj*m3{sJr(!%nMSWftqHa7$MSWhRdOSo$ zeO{!7JWNG>UKWQJp;lbP{ZX!^UtAJijIMEs(={#)FG26Pl>6gOb9n+v2PrM)Nhp1! zG@7TNbd%CO4E4;N@ppp=UFKIr8J=DpmdqihMtGgYf3YE!Kp|uaD5(Sr_`kv zsa)_cIo0VUDi{6BPK|n*$|V${8^asISEyX}W6`Z{498Nrf}(VDcvJW)m016pQ@dWH zauo&Y*6-ar?-6_x5%?r%EP>`f{+P_jx*dyC3V6s}U)-llTPzvI-mcc|P( z5xdLjVx`T!hc;JwS!s6fL+NOx<$VC9ua(C4A(ZY`+TTY|dR%FOA4BPMr4@bxrQel? z_$idGSK8udP5QdyegmaHmInGQ zlrH&n_!N5O(@w8^CVUzl^BJdOmXp!pQC(l=KHyq9?AY)XblR~_pM5nPi*Ea>(``#T9?x8J zdTwdT#OAiskxR>-#N2WEa%tR? zn!8SSF710VbI<9~?}zW9Q@`(Y>JP%|=<>kn*B^$}%jKcdwLc20qst?wcYhpKN0-M= z2md6jjxJA}KK^M~9bKL}-Tbq#I=VdLUR_@gnNz5*MFDA?MjpZY#Cbf_ z+odobj6@Oja!H5}L%m((&`2Cfgo7hVM7>-RWI3!q;}4eG!b=mN#h(TX>r1+ zw@U?_D(P^@sJDw8Ea`F1sJBZcoGlq})TphNE!;j?@!@3UzP9rM)uvJluTGALI=W=XuT$4~ zht%7p4&I(zc#729r7oVI+!1wj$;EvG=Rs0$m-={w@UF6g%i$hFZUF6`Bb4*=bI^yh-qfA|0~h}r>-u2%ty|-r>-s^nU9^L zPhDL;HhrDbPhDO5;>2qhX%P9uc>>kjr5~QXM%?#zjzRTyk)uyeLiKhTfYVP7!~btr z7kLr?Z*Q0X+t20y_ICOI-__+ae2?-d$`3gLeuj5ZKFN`A1fE9uCr81Ncpc@dR414A zQ2kxh$)y7hN%eOb>ztWmsf@uz*(uU7GLFhv+?Abia*n4m4%cOuNM{_Fow=XjoSze@ zsGm!>NLL)2>hGdXF5Pf)s=tdmxpc?jss1kNe9XQ2xu~m4U+&e(MO|I`xqdGFape9^Mg3d`;MARjJ6HW&#_>Caiu$<>!3jK-iu$>zvy1w<42evK)9~~T#Xmd)PRHvjU-3*h0}t?U z{Km83OuWIL;X|GcXWgw_(_v+`Ot}b73uYNA->hd-B>gS@aE)%&|KNod%`G$M-b5U29Z@E`L7j<>{ zj(hcUQCFAmxnIfk3Ml{iD!3A_xP0lW;VL}j@~f|btMQi0$G#S>!E-Ku`#QK5FS>m1 z>)|>)>hi;Hfby=(C%+MHFzV+rDY6M}H0tLv84tWVyQrVbACWC^vr$)gqC=d-ZcsSC>DzS3ehZb(zP#`njm9%U|59pNqP>{LQ`kxu~nl zeC`i(eF!S=;0QcSHi2>wj>02GU0wbm%U}`r>guwHjDy84<6uc-G1&)8xK~$~C1fHj zbMplr~u+n8T ztRfHM0(lV1Zct9dMR>tnbomjN;6-y8D*a(?WKHA>ylk$x)QMPl#l*TaimNczTs2Cm zxCWIju`#lN)QOGUUpJc~8%d+s9N7dnQN2m>#b&Z9HgkW=Y>jLo!(t2fx4FIrw?(#+ zcCkIO4Q?ar;x5;B;Eu?4(lK^McEBBEW88On9QUcHhs*BBE;2QCxgIWiBD=}j*vaOo-+BNs?rx#&_?E=4Yq#&XG}v0RQ^BCX}JOKG_hxlD@7 z6_?%;8@WQNORP(Exf+Qj_2sHdd$|_5N*c^HmjZJ=a*cGD>nxt z?5)U6GG%UZpVZ!t+#+k{7Wc{Qoycu6Xl`?#+}@4cA)Dq7_bKeX$XzmP?sA{f-jCcP z%jO>UsqBNueKKzDbD!Eij65Lw<^lI{r3GbynQa!A zB9s+ou~}WZP&Sy=W^<`S*#r4&U;LCOo2UgVRGln*M^$dHr|9V5%QRn_f(8ZQF59RkpoqnN-^@A5|a;A zf=Y36osy6nRgy{x@}81#Rm!DGm4>BAgG%Nl^~$*XsWM!bCO0ZM_hnr=RXJFeRH>At zR+WcJn@UBRRRvg{6spvuTvdchr%L0cCcP?+ORY*vDpqAuu_}>fm5#KmDzGvsSLwZU zq+g|X=~o%N^rT{CaH&`sy$qyfW#qmFtPV4I8OhbkbIbb)Vo-w6Z2t)VC$C%N@(-Z??iC|dtr++1U20o$1vCoQhKOQY*fr5lNImAs0i z%vE%KTPl-Y*ON*Q66mUsYS)V-yPhP|RVD4NHU=6b=Ani`+zLG_sO%X?o}i2 zuDZ*)tKn5A|E`A1zpF{6ULP{`J|q{f7Fl~A!9MmQm%;Zj{D>UAI%M`b=f7jOdkj9til z{1SdaZev%nAisiNlIPfsjL5IySL8f)Cp&T?{F?m79%M>>11FLTsjSIw;Wy+(_9BDw zJNPX*lD)~M{2qQszU2F4R{j9LCwEd=mOsKD$fNup8J9o7AIYgy_T|s;C-N(miTR65 z$^3=upGmq@dgiZGejx!cLN$0{jcCO1R{S(f$^WdLwq&I?O(vdEibd)!e#L`jR z|Lu}b=fl74e3yv20M54y>{xFM$){so^65BlEQzS&xc|qF_r{TwI-dJQE^&1+Tx1u! zB-SNxv0dU4T9?8lcBxBl{TD8^|GGri|6IoFe_X3q%S7*M@>{= z^}d1Mkn_6IWyr3iqFycEd*6`{`yIKktGQkUfAGF1N%lwY2lxXyvTI#N?OH18)$+6V z6Zx}0kvqHIW!kQ%qFyb(dcTlY`wKa>8(jwOMk*WZCayQa-@V^Ryq!eop!o6jU3)-u2;(p zZ#wzB)4AVmXOj85+s@#AkDcYsB+qvy_j~PZGJ^L~QLmOcWC!n~qFya?y*cCp&*A=n z%NjmFMZH@7bP2-qygx}6p68N<|MKRMIQ*AO9RAz;izMQ|xj*6(jgP`3Bor?o>G&8t zN^-hqe^Y)_4fWAoO0-4UMyp`lT zuO!#`vdfIVOyv?8&}+QaE#77luD5W1$8PnukbJ$> zC0}pzwvvdw%_U-Q_qLIgy`B5}E^+$-yibDmPHzXv+B;pc_AYNHiQBulf8>(8AHzrX zu}k!R0w3EaF6sLzd}5!v1n_6@seR^>!Jort_PI+8e*vG{7cNQsC46CDk}ZCa#PCBd zG5oN1h$QhN-eGu{>KoVjhpB|f zG*>oygi4sK^V8lba?ek3ALZJEXS~xSq@QsK>1Vw&B&VNs$?503vm~mYbBXHby>le3 zpLa>?7rgT%uwQTq>=(TYB(q<1$?TWBizK#R;yyl9hWlmj64~yTUAFrb?=qS1S6t?M ztapVh_*j<(f7Od6BmSz(h`;7tB}4w2%Z|V9T_aQey33Tm;aw+d{)Wq%zvqm z>>op#zxuO0bJ_jRy=P?lzwn;J=Op@PAj!_z$@=1d`Sm@?5?9gb}HHEzF?w0 zofvG?(3?eF2XgSgW)E_@ZUi~0TUEk0cn3h>|bVbt|PsLEYI`a!5;OI5B4(I=uR zeH5y3Rha$})#$HKovWfyeHUsl7K7@?P?NDZRG)@gj3r=kdO6f)EXkL;wAA6Q6kqDn zQkT2Ze5p%IU9QT~^P(=S%Y8X|Vbp{5xGztSjQX%X_Z7GA(xUfIix(gRU+GczX9#5sB@89Pp%4>FiKifjuhcL#|7;9j8DIwfx%i<3{Bzm3 z%M3GzvcN2%tf3GdhGZ}q4w(>NDPRizO(DKwU=06UoKRdm6cO&iA&>u35}1VlpT}1S zhWOun>K^n$QONQf@(T+C{{KGz|M)OIe+Hkg#4rxEm>AU)@bA~3PXCnz)b;n#e={Nf zU;WMWZ%D+yP5)*6I}`Ko*MDFCl_dO|^f%CdGb#UV{XO(2NXDN;e;fUIlJn=&-zmaf z3jPie_niv6zh#*3SB_A2JPJAZDj&+pS2>u2F&9^5VNS-}jAd~Gg1^*xslAqHlG#Y4pyi}RDq#Fc)6Vlf;H=^4eM_`>w_6^r0_ z&`(?}94h2K17aZ@5~=wr;C|Kx`FqGqp`U&M{$}|@`P|)py_727Hg@63}MlO-Y}SDD-%`q@YiT2O~Un zlG7(70>eCwlF=t53`5ayG%0;TLhv0Q#U%6zdB+p~t@n<1KqAJ(JoDc2Zb-ObZ!7-jT%4?N=S=rKllKRo2E8DaEzdpzJh8fJ{} zR=LmnHN+U^ZF7(J?mK%I-r=3|j(7GQc$;_8Ti)fj;Vs@#Z|rNvH})p)uGjVz<7<0^ zciJmv12^Dx-gPgTC0vKscn7{<_HYee<=yz4S;bWt%RBQKvyE7Ig?H&wW+7MLW!|w* zn4MgPmw5L+X4Y~EUgVwph&~|~;RW8<51Hj$faiIWKVbHA9-iY3f8X9?yiYHdbO z660m&PzRYuUSzz)-0A@H%L|MbnRD%D-g%z!0&}r_%ty~Lo@b7>mwD=0#&gWw_Aq}v z!+4fC-EQW!ry0*M*W1N>_Y~u4=72ky2cKj-#oTZQ^WzhYCz&&DXZC!Y@dR_pZOp2V zF&<}*xs}=WQO0A;J-09mKf-vFIq7C*=Z6`OFjw8gto;zxznav+$JoJCqyX!bR zigkVTt5>g?Nha=|Ox%^YySob^5ZpqL;I4t-65QQ39vnh&Nsu7HCAjX*#`S*Ro}CZu zWA~hUfATr!lRxTts%rI`>D68O)>}^*)vh+me-1xywELjZ|Fifxqu>Y32iD6MO<`B1-M?Hks zm|NUzmbDr`WX^F@y4u|AFYrcZvOH+cb|bvOjN}1xxf|g1W-9lW+=uTsr@7v|?p}PK zxz2Uwd-vdb&4I2p8@wCeV^(yH`QcsoZnLGU%^UB;cbP?9Wj?tI-)VMrrP<~kc$Hb# z73QC}<2%g8E;lc|4c~5-c9~i0t@t*xw@b}tZ^5^k)m>tido#YpZ0};T-<$BwW`P%( z75@d_WOjI=+47C}FXoOHm_^@!Z#0`c-|YH&e1o~>d1l?$;p@#l&ovvr7GGypdX8E8 zHTYVy)w9jsug2Gy#jZ4;zY1S%c6*k2{+0MDv)(h!|F6JTniHSFE^s-%!Yui8_JYgs zJKF2EO> z)30FBI3HhNu73hc$9edCHh|+Fk^PQ|COd>qE^ za|%9{MdVQSpp)?_EG37q6P<)lW`E)}i7YM$vNxT8SFpq!zz%gh zK7oa1fA*>6_;{9^{n)LJ!^_!n_GQmH79YpPvy7eV7?ZVP`AU=pCY-bk01Mq(IopxNa6i01i`ot> ziTmRHO15KH+t)cE+re$w+m^9QZVMN)!|hYDH{OTEZZUi1UU=`4t=aANV&B{vE@IEy zvt%jWljUy_yXPKwDU0A%?4e8W9xR0m*-3ZDOV|##WIx>v@6M*UfL(Q0yc=8NeD>B| z@UCo-^Vnf`#=Edh&Sjb13Gd8iIfun|N4yhT=4_VS9q^89oU>SXx5qoMea>Y0-41Wh zCOU&fcw4+3Tj_N6;>CDdHq>b>$lKt>Y^zgQmbb>+u(?iQabASCW{aK761^2(#8Nwn zg?b_0iUoHf%k`FcAK|EblY%EH>#8Eb=q(Ot$LbEcMgz3^wdx?D*60bhhoG zEc;XOG&b)cEdEpQRJQQJRstsDDJ!|@1f2;Hrq48y~%Fm$uBG87N9=FruO%Md)&T0|EsF@y0CYZRTW z&Zg2gno)x>cxSe&ax>oYq;I`Jg>R91xjoVlOtDUwk zX@y%`AFGwNDrt#ZSvRYhwk&CZTUtr0k+vvlj$2q^tDZJ5DZ|aJyj4rftVC9YRnn?y zGwYO9VCA$*+O(tzZfXUua@wS%F>YdIuTt8$q!Dgx-LEulRMHSPvL0A5ZCKI(H?&Sz zA#G4nA2+amSd!K+sfX)ZS1eBJmDI)ctTz^=bxZ2ty4E2JX`PbVxQ_M7G_74y3)i-8 znNMq#)Wo%{XC`UQk{YeD#uQxVm-G-}2Q;s^V(aOMlH*EvbU5 zT1WjQU!|lnu3~-l=X~XoO1QFh*Prs0N=k7h>#;xPOG_%^QY*ASwH?0$ElU%zvc5K z3C>$#{%bxd$>GGx^H=#?$?wHq!Y`~v|8AZB3;4M;>ffy2e-1yhcKxe${m5hIioGR`vhJ@8NCumeu~h z7Jr5RTKpz2fUkH+yb0gnBk*PM7x>HK*Yj`iocJ7nQT!U8g3tL|yar#*zsA$zQ~X)+ z24}K-TKozAwD=Xi37_!Tcm=-9XW?U>952I{_%eLN!{a6RA|Hnjd49YI*Ykb&fJexB z_yV7Z_j!uE0H5b8v9b6)ys`K>J{0fqDR~Y)%eUfPz9!GYb$l+~DSjKj!y{uIAC$N7 z+dMVa@=bXYzr};&89pm-;5T`8Jk6Kob^Hd8kEi&!yoO)r3GyW0msjy?{6wDM6SD!o z%5&s#zA~@i4g5+T<3sZ@eubyWqkL;#!Y}hcd4$i+i})p;DG&3-S&v`jx3Y$h&I@>b z@oL^HFYxSH4Ikvy@;r~92jK&}U7q6!^Z>j+{{Ziwb@*BSGWYWeT8r25rn!%|&@*@~ zFPnRL5j~Bc;eB%t@1m#h)4X!-=6m!ceu}rwU3`+Bz)$kxxs$KbYW`rbqE(yn$}#^YjRQl$X$Le4!r3kMJJ4m5RP^EcjJ5bNnOJy>@Iva|Ea6_irtCt;$3wW@3B?*&f+WhSgqoDb_Kkg@6{bV(k_RW z@yWWKr`l!kQodTZ@nE|YUc!g#R-SE_z>E2I-NNJTVt5gsubX+oT?8-W3w9F^xeMV1 ze8m33bM69oKHsq$dDNW`&*M{e15dm2;JJLwu6Itzx$qo5XxH({I|rW4H|<)!dS}Cx zeAcev!?zNi#h2}BzI|uGGx@k(#pmx#cn06MEBOMR0Z-=>cLg88)8T16<}T+ucp5yF zC*5Uy3QvWn@UXj-ui+{1WS)1I@I*Wrp2Q>XVjhYo!4rAvUBq+oM7V+n--SFHSHKf^ z_Fcf!@dS80kH7Ps6LLIU&J*xFo{`JpaXbXi{?;UBs; zFW95-(fmgD;vIV=K8io-p1fv{z(?{kUCO8SaC`(W)IIpx9)=I+m%4-x?xFZF{;Iq4 z%{>Gk%A0k!{2|2$<3sqj?wUWi_#k{Rzt>&z2NfTP58@BIbN;~M1Mq?TWOw2hygxpG z|Ll&uhWEq!^Q+x~H}SrBKmNAc^D173_vMGX9dF}(@G}0n+wwx*8}Gw!cQL=@z3|@r zdAH%UyeHm^pYPVZnU~@{`Ts8B<-7-8$}e~;-p@<$9=wJZ@`~OaFX2tRC2#57@b0{f z7x1Fq74OFTcs{@CUGT0>U75$m7c*1d|SL7AL{A6!x!Ui`BqQkHNFjA%-eb@Z}P42Hhi(C z@G@V7x8|cgnfLitcoE<2Nxae*;;r~}Pvot>C0@wadjc=^1$aw7;Ny9>&&Lb+hL7X* zJ`d05Ek2ev{9HVb7x@@o@^kQ9-sPit&(Fqlc%6^pRX+>Q=8Zm*xBW~!i5dQsB@KiqXgZceW##8vt53(O%5}wSb zexQ8<6Y(Uz_5Ykx=|+}G}kHujD5#(nI%Xl*}9FWlR1j8=A= z^u)dF(r9V_$riY$-5V|JPU(TSu&blF{VLsY4|_h!>|^PMyW0!W%>I_HxSKs9P3?Q> zg1g!~(!_q4&bW&`C5`Qq>4ZDmYtqR6nU1)VJtz(BtLcC{+MCkAew+5VgFP$t?Zat@ z+uPSt&;FdYxSicCb?x41gWKBmQpbLt*0_z`FtzRTX@y(cB~#1(pO(0lJv24*EsI;= zmUh+D$hRnNj$7DsQ$63jxC}S93#VGXthgC2vpc71zFBco+{~_>D*2|xO>k4Yc`E0d z6gS3A?DDCUZ(Q66H@5qyG~cMWA#P+>P{n-1;s&^(-9i=e4T|gI26hpZarX*j}IUzat zdy>o7D6Woc*bDW0QoXnuu5NeKZ%MV{s<@iHQ@u(Oc2oV5R4J~EtJr1rb5gmu z60U6b)lW&K;!<46uB;!EQs;#H0Kd0St735lT+xoM?~@9}CAfl}Uf(4p#l^V94zO>N z;^HD)Y-iXvNl|eD7uhlP_oPsq;)0!IUngmC9;bGg{VmBCCpd5C*|^`Y{=LuOr}nq~Vqf2<@DuyqezxE56ZodrKd`Uvd;1ALfbZLH_nm!)@57Du;eBiW;YRqL zU3%Zxm-rrh*Y3T)+pqX8e8;Z7ukB-e2fl5$-{0(Sd>g)H7vNv*dwdJNX?NgPc16Ak z->_@&OS>iCfUny}_=R1Rufx~uFZ|r@%Gcnl_8op^*X65lgZ+q~+KssZzG9!^Cw6JR z0$;X&@ngF;UxqK)*Z7fLoiD)`?RWgpZqFCtdix+hunTlOe8K+6_w5dS0X}cvI$u&?zg_@sTGuiNkXBzz)y(tg)h@oV;sK4Bm12K=hMq>tMl`wHG*kLhFf z&AyCZvG?>*`)OaoFWZy)h<&y%;+O1Iec1ln_4q}5Sl8H*`vP8XZ|g&L>OPNOu;+EP z9lX!s=k0}k(9Ygx@pJabK48c1I{d7?v-jHxycVysv-UnagrC7{?YOui;>YX^ zzTFPzNARO|4Buw|^TYTNJBe?#BYF*f*xuq>?38{8ud(O&W;>`?};zRAw&2k~lq zl>cJK^#k}pdzWvt6Z?MrfIZDO*r$CTzTaNw>+RgW7vEslB?|uzZ2h8bfw+ZcNVR}cNSe?*Yzqp%&&l#+lPIJo#&Us%k0v= z-H!Cj;H7qN-)5)!rSKB_xo@?D{StU_a)}-6H{)B1F0u>!W;@<5f)_fIo%83z^PI_YgB|tf!E^09zur#!bKyD8WVy}`{Bz*h&SbgP&iu3C zO1s#vv15NFJS$n5Tx}=+S@29}vRq|{|C#U%XR=&r=l>b-bZ4?$K@s3|c$(ewms1Kj z4W4RO{bh6nPKBq~ZGS0!fm7hgcHv(_ci?1rlHK_i(<3+up6E=Li|7=b2v^w6f1z_i zR=^YN^1pzh!3pqqXR@46>EL*{+?g!rQ9xJ@kE0fFE@gz{;IUK$&Y_raEIfv~z}b`( zj)6y09au?W;b?diHG;D!FB}Drq*8DuMTR5c5y_Dh8BWJ%&^b7QQp0KZbovK}Q*byH zpGFbkFv_?g6IJ}(R!@jgCj>X5(fmlYv;uw4^eTaQ%TO5s# zp&PL`&5NV((exztqJ?oJK8nu7o-{I!z(>-bSV}wNaC`(^ials*9EK04SFwcF#-aEy zIu^Ur;5Y;yO5b8P+8hVtL+D=YO0(l2d@wzXU1)h6h!3KZu``X21Mq?LGj^i=u|Gb5 zuEvg(LH5J@Q`*>pV#vODKMEY%QxaK*_od9S9fgs7@G^=W+fp9c8}CEOV=+aNz3|=? zKDMD$vM1h)^2gQ`OqSw3DS|AbY_bPlN-1P3iYH6(9u!0t(m>fAFQF{5C2f@5@a_~x z7SK%D74JrgWIipGUGT0HO6Jj6*%|LbxnwTwm7Va;bWP^aWZ4n#MDJuat(G0|j&x9F z(Qw%w??4}ACT*AP@b+|5X3%`u7H>ySWjZaG#dupfE7NGiY=almUztifW^23+U6v`7 zWftMB>9tIzHM137M8Rbe4Vr~`E6OetY13?p7gBtgK(l56-jWi`cv?2|@d64l<0#$C z!}BS}jHP`u7tf<8GlnM496XoO%xGFUv+*1XG@~f#%)+xN(~P98GZW9ESTlm=&I~-0 zlFe``Jk#+E3OB>3^Gw6jDc=mG+A|eTql+_yn$HwGl~T@NDnFC)6bd?nXaG&ZlPT*A zqzyC?PolUpfM(DHJdqMle_BH0@dP?O{b&r0!{aIU^rbyC7LTLo(}yO}7(ABJPw!+* z(P%t|4p1-ZMWgU&%0NAnQAH#1D7ryg&^#J}N757OK?`X(9zkcQdosLe7#>c4s2lC1 zp?DZwqOQr%q9J%F)uJx6mImV?)QmdQU>bx6Q#tBHn`s~(ME$5E&87i(AXTIeRGj+b z0o0P(Q+Miz`%_VBNA;;M?nhmzEj6eHngI8<37}wTGNo~g?m$JYDHVBC+hzHS4-TAs#Z-}U@dSS85H{i1rfKGm_}q+U^7T#p)AQBt?4 z4z5e3tdP_xs*USVFH4i!MYV8kdS>~gR#8n{i_Te+)GVrjYtlcS0av8!_I<8GQ3Nl`H_p#%4AuDGZO7t@FPCRarH?(gtx zigAUa6c?zMr~4|GEBd|gCH#U$-S3q6zJQ<8 zuKSHb-{4!IU%pY4HODLrMkEQzCyY16KagFz?Uf+eq8tne_VKp(&0yi5AjEZ z7bzfqSoi>cNFVV zd=ft4OqSQEUOoXIryTjJb3z`6k5QD|Kr8bx_$Z~xS7>NH3Ll|B`7&+IN8rPhDPM9< z$ir|=?qNEc>+y?)hbURDr_uQkTutHfg~Idr1zMP^>2*GbpQn-eARW(V@pH5@AE5HN z4nIp%^M2}|YwX{cTyvL96v$za}|}+$MEBY+jDnNFMSk0MkVxis-}(wnKKuEr11D7}fA>VtSS?b5$cS$zOMNYnI2>Z|wT2WXw%K$Z1A zd_N7;>#4Qgi|?b2dL8}Nd+@!5Ybd1NL;Lj_cs1qJyJ^B+4X>i8dKazOtKgNCR_~-C zdnLSr0_!T;vRA;%DYM=|bM|t08O7GyY0+K=FQw#q8;#ma;UyGaZ>3#(3A~u{>n${G zFNPOUguU50As4|5DaGDI{q{n50R`E=P{q9fo}asbD((&V#=?1YXK$dQdmcQO9_{ti zbh3x4Z2Gm=QsX@vuB2;w4VB)N@GN?_S34)F7O#LOQ2f1smhlPjcuK(M(>OjJE~gND9_{1h@HooB z=h8$z4jxNU_#9fv$HHSM4WCUz`51UK1>%*om5+u;Q6@f%=JHYS$lOtMme0Uv7LK52 zd%-4P@Uc%?nl4*cxu%9!F}mEFQ-zyFI-0N z`8ev;%iunAppT_$y${@*KJ+op3E3O&MK}6r`qz8GJ?TjwMHhQdxRlQHk@T{c!ae9u zAK{#kJ>U{&vK(GG3?ELxdI^2)L-Apht#_xpeF#33*7a`mxDUpM(7@i6PWM6hVA|Nb z(C$hOR;-9 zdgA-wWt6=lNh(R?nw z^_}p}l+NeSVc!w&L;-zvZpXq7ct^_UvvNB)CuAm^k(-&@zOWtMo|5{E+;)X+@piP; zr{}gUEXLc?T%VR(T-XLLro}!rw@qPdybY!HDY>l+i}2R8+b7eP-wH3H={||>{6f4H z#rKKy=(ofRDZx*mQ@;RjNg;kb{rdTM0p<8{bnWNi`4r{H(z~CF=TVv;LkE8jo=bs# zG-dqRcn)RyQ55rM;n@`HM^e(CiDyx=A33BwADDUj)g=u&?Mf{{-NtE~pI3ZvHo=Bm;zmo&T z;|VnT`#Diy93D^0zpwKK#^P}_{`)wGU<@8h`@eT?Okp%0<4k~FxzUADc(k(udgewI zM&eP<5ZEF&vM>UVbhbc`+=#+(Ji?g+-E+eW!|-rt5p>H9D-6ZMoKes-Cqbbf?(al} zc20Wei~Bigp{)}j`ry7!U})oHh~Bu5lNnk&F`^gl?Zk#wPLk+}dpXIWr4uH$z&)Mt z(89?RJ@6JzerWDQitf0F6Cui+RM8E0cSb}rCs=gF-JBiK)X5fIa93waG;!iZXWYeE z6OEmO(Fu2U21O$$WOT%xoK4Zt$r&ARM`u@y(CQwO>k2uepJpiaV|+E7`qS}7aHNl z&Iu{aH7Yd3jhr7+G1sur05^1^NQGR3LVeu8c_Ssc`h|M9ej#U1LcKy=T(6MWS5UW5 z2iJ9mNu5G%nBZEtc6PQ&twK#)%NZuAGfs-^Td3*k*4ci9HaPFiwt;PYFZIUT!nV={ zC7~VcfD2-&-47kaieVA#h)ZDHStncp#vOOY6_miven}UxQW(FmE3O3Nmv_UJvb`gf zVeGN#?%7nyc9v9y@dUTP)nGi?p17Kt($f>~B~}B*o9K;e!gxb{a7{I?k2lv>tTv1{ z+7H)JL;Jyg(sk6_{z||Av3hFs060LpzM4J|4#xGx>M2Qs#TsfE2E(Dap;!YYZ>U(~ zY@bJC@!0z`T&juCSlJyR)im2R(o`(=I*pWWmhCAigU!@|QObVvY{y9p7&T-JZlT2+ zqvnhiYXzf5jl;2@DfND0Z&QVgD~MP0yyI<`2o=1CRLa7RbiCzwUul+G$YMp=)y1xj zE8@Bo$6rpew;JDx{P+*t!-Rs*DoW*r*i)5A#ee05RZ3JS*a|BF}|)Wl)@N^Ru*!` zn-#>WW+R}gMm`n9D@(J>%DKb+ibSmY_{8Mo~wpMf3w|Yv)yL1-DdMT z$maE8)XzY<<6<(?`-_@@lZyi~$}CA?Pt|M{yl|A(i_7+xza#lzF9 z+-oH~Rl;ATrKj~@wJC)K>0euxHrtdo+mxatZT3^z?BBK7_iVGz-ezCN&3>4h{Z}{p z{r-3MN&eqG=i2=DH`}Z>+pIR*tp2Ckto~QolzLO%?n{-sH|&Y~QrzwdLwUO|#qb`m zCAIAyu!nRjYTMmmcj*?waLU)+q?<_%Pve}@;c0U`oO*S0*oE?TH>%uSU?^G-r?MT2 z-JxhboceYL@ldoLPL;cxztu@zH|pD+#6yLUt5Ujd1cy_Vt_+94 zD!7{bs+6NE%PGafs7sf^3V0Y5?0PO3_4EuV^qs`JqFce>MsG*q33rlIFNG|lEh3QbD4%O+O;d|7cho0Feq7#=^a%>aL((T{8V^Zdrn+?G)Am0l^2{}}c?}nF99v+llLUZ^=@j>auRDCbTm&&<> zdhbQz7vMqZg>-!frRP!l9h6>2fA|L4#Mi;l^&OO6C3OS!;j7>^!lm$Pd?mh=;_#L5 zavUndm&1YSxxO_p4fWrFY3KnTmp@zVI3ZMYLkTz(bO)x(#gC(ndyM!|cwl-o)!c#U z5p;A1re{(BUP&GJOn7+y2sx)pt)!ECxcF)LQ^ilG2E3B;?@CI&r%0`&{CkRcC;%^~ z_InZx)!*e5epkRy`dywMkRIkQEcKTLz);@Z6Na*FDDQ@%oCOqP=ZVk3{nNR$Wc#PH zsLS?Gx2Ji#BR$;hVQ9%ZYglSW>ajD$7w5MT4=vgL>9%59QpH`2x5isiyxkgx@@=Tx zZUslVZX^uF*-=9ObOcS;!2Zrv7%hKPekf(ve(5mWFC9+JwO=}fzH7g93f0+Z6ltfx zP;+$}gVZ$ot%JoU(wm(|zjcuKB(c$SX(!_Gcr?w~@o+32O=os2?CRQnX;&eXRYUnT zR8{+>-Nd`nOYJP)kG|`G{KB+@_`#jWxOKj{&=8j4EnU0NnIfTSx@8(Fr(33> zd)n0J4e72ng`vM1TC0s=O5?OTtnRv0$kP(dEES(q~Q6X_%{?sf22nGO@=?x5dB)}OM0VU!_XZKjnTitmwjVF`ZBf852$LsFZ~L& z&-W>5zAXPGVSc(n&MR~?UrOeu>+$^bMT(m9)8}by&QIS>-tqZ+$-6KVHRq>qN^PW} z`JDJ$G(R`e(0o?>ZLtlsLEpk};0<&?-+-b28CsvO!G~yUu7m4b|B$enmgQ=^M*c%I zD<2e}m)3YYWJ`{X}Odvh&a&Zl8$TFy%!ms(53@*eRgsBW&MVtKcC zs9DZSpQOpTmPY4VnwpQ{HS{+hgOA`fG&diC*SqdII+EAn8|YpJ&P%VS8hI_g8qZ6w zNv?)hQka~V-a+^BPMVl^z+3R0^e%6Kw+T1ETk+iVGK!LO)5~d0&P}hNIyu+3=cPCM z{07>WH^b1t486<0z_aK~UIs67-C4q!^c>H`E9IX>xA6?|)9~E%bc&91(^F_X&P^{) zF7o*$$;B`f9p|R!OI=EL@_cw94!o3pS{bT#+0n91f4gN8`h3J{}E^#G&(eB;3h2ocu#^aX-q2`%3RjadBU2 zhI8T+An7^jE^>CJUASX1JKY}7PIsVcI6K{z&f)BIZ|aN7C^PO27gIHyo$evEjE>=A z@uhSZmnETUI6K`_Y!~{BOYsuC3+=@vFf0kdDCM;fFT*p_<}~zX zrcJ5p%}l${`s+pqunP1gsYuFLD$E~URwTEqSDEhU9Gtwr$H6snB zy%}j}?^U6*HzTbIL)9)+_d?NbMp{k0Dy_Q8;-z>-T8WC?jI;t>yBTSHYI_YS@zsZ+ zVmBkLE!B{2U5R)dI(rRi@HM2FSC{@?Lt1-v#Y1zi8hyQ*Fm(2+CEw>l>+btpv2Xp5 z3$42!Ec2k(-`=O<8Vwnx}VHpoN!*p(8gv z{VkV@hmPFz^mj^kg(P(3rju7FBtP0h_`956@sHH*ex+s?s&}Dq_cMHt%G~tyJ>gyP z(3}fBx9RCd@%JdTy(2y?eM@Xw`Zg7}Y3ZAC-k|L^E&ZJ0+?UkoK8K;?HZA>F>Py;f zuZw>|YwpWjD7j5bL&I%a`l<9r%5z<~b_B39b+mPY3 z^ch-dPl-Q)r=?F)QJa=NMptcG`ZBe*4Y^n7zipuD7W#1O@dmnY>oeRyt!=7nr#aax z)YPV?p|3VI4aK$RUA30t+w(A#-$Lc>S-6VQ+SGIvjkSlxr>1vMF}nlbDQ6Y6vfIUP z#Z%MU=$K7SZ>DTEHC;__Z4E89)i89-rl$8vt)aGdAACT#6W)*S#dlIzyBCJiTBxes z4X30x`PP&))Xt`)p?`KUt+OfVB~;FC%v~Z}Oh@cuIhV@0gkIQ1;uqj4>4lWUrljZ5 z7Mqe@NAc_iYG~KNP!gMxUL|z{?XYvjug+a1ehu}rz#FKSU5PKHbao}Y9EZBu%WHCaG6tXgR?;Io z6COp&YjS$3)XLnEQj^ousEw`69U(P2JzZ=CRkG9YDR>3Nu~T3ukA=$ENpK(PUPr(q zT)&U7Hx;eD@iO`QP|Mm&d{VkpY*M->C9O&69&(n@*P4_bO7-h-ieQJrP}7=}9w>D< z{jA-^52E*VIQ^{M#6w4GQhKoTGU{Ll;REn8%3lY-Pyh?Hul?Xwu3JdKY9U@EgyPjM zc%HmT>3q6XlhOs0tR|&%Xi5So`lCyxtat+?JAV5CPX|9t*HrV zs83BuhxrRVaOgUP?oCnF=s*=YBixxGZ2QF z(}c9I)L=?H9mT_cXfQva!F-WI?`AN+qWs9mPMGd^u4)`VYBOWYjC`QObmRh&2nJaloI@Wu+grD9=xS}eqVgd$ubznBME zL3~`Ah>c70e9FdI1|6S$?wa;=*W^`F3CA9{N-*}f#a_2qUHjR8`^ibhKjB||FL0a_kH3>Q&Pm4K z!5{EArx*VKD>$9G)XB{iU;&ppmAL?majBD-OAEg+a}{HTEb*~UH2yn`6OYFV-@TcmKC+v=KGUT0NW1PtQsNCD7Mmu5mcDM?UcB<|w_^=a!A9Y&r!!S&4@g-YcBQdo{cgU*W{rQBIm&A&hbo?YS9_lDk~qDCf&AhbQ1s z&Xhd?p6xu`bDfoYHar8L>m1xO;90`S@Ju|?wWHwC&YK-691D+?ce>9{b|&uW@Kk)V zb8t_E`}sW1d_5ZP=PcTzo%6b{`2OPiInQ;O_}+M=Ghg?Hd*YGKraj!}N8+QL?YgI& zL!^#!9_=CUFkydqC_WhP?+n_5;emL6=guAoNBG`IxWsv|BZQ^tHh62e1aIRs*djT_nD%6JU3DI_$1+N4&d}Uw4E%3ya}Scn7@LX|FrL?eJnJylw~oEg!{b z8UIjJ`@g59_Mh=h{r9xg%Dqy{JyicaEwxR)snIX};i3A6mfD|vQ$tnle}$G>^vvao zYUNsLWqR#VdX&-nm48o5t))JAlW%I<%qO|6z9jmt=uN_7I1dwVt-W|Vy<+Tt51qTv zzf0wI6z`zNEz0`c@Luk$X9{)2(0B=*yAl{`X#f6^IQ)hy!iv(Nb61+_+=cR8 zcoz4_yotkaxUxPu`lT(zdg!CWn>cjts=}($;Wu0jh6Y}rtgq`Mr?>t-dcM9wAN_qT zseVFVy?$+}{z5-*rjFDAp}%oMU8#60bzvys4HA#hMD*~3g+ZC$aD5m`c%gIGAoCp# z{k!ll4)5Wi#z2knaABCyQWL2W!thMzu1WTOLjSIb+)>_2DBr~!i#HV7oz3x>?2V0u zF%oNmL+!4G_Y~g5LjTU316XV5(#(=ZMV=TxoIte}3CP_V4H%US>vPlx7 z$R^3Q#-5FnP=0NkgcfY$B-CLWC!rVHIEm3|%$B#$HBDkP)YNyIm@CKVxKR=#M&Y z8UUlT)Ko&slFqIvOJb~8mc&T2EQzsaSrVl`X7$tHOi!(Q1x$Qu0Gmlzhz_a z-;}ly;-UHan=lGS*{YX>VrVG;Hx5O6|Bbr6|N6Ucg~ol1w|^Ig!WfOOb8VAsCR;Cg zPCRC`>->f1#bd4;=LS3@-PBxrEq+1H^XA*n$XPG`LN@zuYHnONS#OU0l>8^NQSD1| zUNrZ9QrUl5{3WyTC&WX^yqQ_`V=$LgcOP|m+xo|J8k`%(p{3HD=sp!Xq%|=}A(}r?pvB?#k5`?uIdAuARi}xporz<+YPg zG>?-G0z>J%RubChwUSUnZ;k`k_>0Y@AA&I}KiA*RC+Ft!$vN39H=mp*=UlVTv*n#H zeqJ_H%_kSQ#{?#FLt8taT&M-BW~N=uockj23(d)^ilxb!K24KQ+D?7CGmN=^A&I$vAqgu&Aqjo-LK2GUq1$vRjQM$$ zY>r+fo3B^N=I$;0x8~ZLur?JXH~LOd5}N2mNzDC=lCUAfSq9aUIK`lP@>4EsQa_1> zMW~usSf8pVzli_L()6A9w?d8NRXM+~Kz-|Pzb5`Fo76Yrp>KMn_C3_oD+^b{P*{(X z4r(N?yYe+{pVKAa*Z2)Nud`BpEgh#z#7O{EVOXwOvMp6j-egy*n!Ls8R5f{<9ja>b zPA;r;VVkM~H^TQ=imD_V&GIWIOU&{su+=RU-y@sXS4{Slvy^3FcX@k>@5zpEs(9>l zxkit5oo7)=>{{{AiQn5bd$BT9WbF%^L&c<(I|`lBuw}IpzJg&<+sBoAXBLUlWLYk( zfXn3UlUXN9lYQkZ%WM^;$$sMdvWu+9l_vX((+d}?l!OJPGzt4jr6jb_Du4Bhk+;V>hHDhYRmT-ZvB zGs{V6sT^jca5#HRv2Y{|yH0`qr&2Nwx1&QpJR+NLhC)$SdN0nx}vPC zN75_lo@@bou;TU->nQYuop5K?@?Nl)R0p};U`O0me&?heY@4))?UI(TebNfHOj^TM zNgLQY3F~p#ki%x&L{6K`mONDtGnGv_dbu{RP0~V}9Jvix>8I)irbHVJ8)|>1h}DI4 zw4PJM>ce{akjB1MCN$41yi?#5pVffXmD_6KRfXE#{S>*CVI@y+idYG(VpU*@*kqvs zjIvycE2_g)eXFKWi@i55FA++$E|aBlV#P4Qzvd>({SE%A<((|{BmA9xce0vYa9xqs zC5I=e<3Hyn`3pa(zmwGRsK6O)hB>4{mL zo~Ta0DZWt~FfnTbCT4BGL~X#wz7v+@_i^+l6ZI(*wF~S&({HZQx837g4+sxx z&Hp0zMq!oSVw^rBTKH9PmA>LyIX7wD#wFM41IFnIu7uZXrN<>#YNf{|SLt1DaOKUy zExB0txmwRO7G9jS;&GP6)%u#TdajGKmsh}x@%eHt)$@(jA6^JA&|{9(C!Pb()~}A$ zqn-!P)k9sOf4a=~uE_epvB_!j&(k}OO`?w+W3?$xpEytZe4d{7BsphjiN_=-X@|#X zjgNzf8h?*6%8t?aQn=K}dTTj57}<|Xwl-=Xm26{nFv_TXA>7iqd^cn8on5;d+)a8X z@tuv}w-p;{rEVdN6Bp*-t;_}Hh|d-lnJJ7+=9m}E7M~?7FuEO?%r&|lX^cA)&M>wf znS>>Hq!IR1IK^CJmMiB8^NsjNCR4NdOkj+=$LB^^DI701(DjJc+sH@FeD%!;_xb+%K%l{rrVaa(ZR++u=zU@y^-2 zw-@YX9@0)u7i0V3Nz9dpn;W!(9dg5r23o`6cvuo+{IbxHR`V`9(L$q=2XpH(E>KXL(S6a!(q4vu5WA{GsPJ5 z*Ei!BYTi*zx(=+4E6ZUahN1L1G^wK39-34&IvARS!r4$`gIcbRnR7Lq&&BF&UVeC- zmMfgam?M>+H&zInvEeo@$VqcoGf%X!PKlz#z#wZX|s-fV-Dv-y|}PR`+(HaIz* zXWHQ83_fXtlQa3wo$LAwg^T!`4NlI=yw3(FCySrN_v|d5YT=1?7XP!zJsyTv+Ti5) z{GjA$K5&DQ6ZpNwD)b4w;|3+i@QoXk9Lt|AeBDm*?b9+}wL!_D@{i*MHz+xbZ`pBt z=E867I6i5ElEe9=4N4B=jW#Gbh`-sOoU__$fm7q%1+zcn6l$$(_GoLQOI+d{aIx7<|uvw4{H zPo{<^TQZHmS^s1@e=}zW@>T1fOyaB7Kbg#%ZiegU2y=O!^-re2F?g&nhR54z*NqY; z@N5~zoZXOvwlf;UT6K19^v7ZY!NVv zyy(J*u7hhk<@+RM`R1@MZit)ngA4Dq20{y7X?>E0JmMON*B6@df9sPp;{VnsslzX> zPg0j>Tc4yJ&$d2E4W4a%lA1i(>btVB(1d4NpQIMAv&ufJB-G}m7AG}UkzbilT5Y~= zr9P?68?Cq83b2IVTJNL+kGI}QMc!$>la!xYZ%a4Du!wJ4b-rv>eXn}{*Q9q+41dGF zC-XDxE%l4seC7>Toc~e&?|j(i^E>+){>1BSzSwv0TfS=Z#eRU_YlQMV?sC4D&xa@4 zeEw+jefBpPeraEce<^&!|82h9&*5kM;pU6YgI~Ze_`Q9MKjIfRPwZ3pN#^194GbT+ zcjbHv-@_Y)_xP&4E9V{IL!N1o`xbnYH`+Y0SK-_I(B_H7>7%c~@J^eXd8)nddmr+R z`!M-{|J#dl*9&j(i<>JIr%b;A!=vq4IWO^ln=AG_e2!1rT(M{1(>&{5aLvoYE6JS9 zLoIxHp5c2ohcDWr!aDdEeq7FD{Lt3%Y*;j1&uytI_Ys!yOq(uu8@y|>wXhr91}~Pg zO|nROC%841A#ERq0=?ZZ2vAEo>O^qu_9MEtI=G~xsCW4mZrDhJNOx&y<^@Nji7}shL(b3U)oaa;e}=E(r?Tke3pl6rD_?Og;ldQt{I~=7KJ+aNh7!tSmN)N`lN=DT3k`j=M~xFN?Fmu6Ro0I zZQe-jS${9js#fZ=26COQn^gr<>Yuj|z_&o6q-Yi)`-G!aQt&c=-IZFrQjz2DO#g zdb6V4;CRgbfYuWFJK`73;&z1L zC-kCgcZTb6b60E!xA7O6%iA6WH5irj~UHD=?d zh{dWvnOS!=SL`nDAr_gJ7y zR~K7tp1lFQxL(C~}a+;VKc7-uR94&v0S!#FbRZ^qi9XL(|i`B(da(YU|`r<0-ntsDFxXiDM z_0WA`*nC2HDNg2EmCc2Fi4PNxwaeb(jjez6hJA5kbKbr%yrvqPP4|bfrX4G))<%Q} z*qZLmRw8c4w+i9ScpnZgynES%?vp-4>RvXY`=rkly9b_u8~MMnavGjnjjTZpf}zzE zYpJ2nG|>Osq|$V!Yj5%wZf31H(_i?D_)VGZ<{lQS`=rm7vZ~|09)RH`8LKk)uqK@Y z8?uny3Geh5V>Wv~yp|=Z4*S-%FgzXWuw`8jZ^U){%^P8OUS5r_F;~9J_ZzUW-DUP& zM{eEBGF3OTP}OA{yF$)YxUSExGTT1a|E=%(@DMvss=oBy=IrN*#ai=a@O-IyEMe!v z@V~6b(sdyWFU@+aXBWduaXnXGnky^&uWLv}dmKvip-Wz_ClxdIL^+CidX%SpR)+H8 zan{`y(rH$b3NX$~>!}|t%F0bK47+>ic9p=e-$!|=0K?uNrKTbb%RyhU(yRnkf?*?w za#R_{DoT{5Dlpc6qD)nVp%gYytXftgs>85RM7fBy%CKNW>8J^7c*{e?YGoy*HjEYF zVYrTxJPZz#t}7m=*^R*Ugz&%!KgRk(oMSgqtbtlH(t8~x)+no0jl{#s5+~0!7D5*+ zl)RbkaS?7E3!tuh-`YZz9c$+!&+ zt5A4OwuNCI3eU-QFnlkjinZ7KOx40n6YHR#nx<`;p0zsRf!Rqf)=_&hL#(r&ZHD$_ zrdXG(pX&-^9X$HEZm_FzwE6vSe*gcu`d`Rue$@YH1)}Ch{f|~4YJSxJP!0T-^}k|P z^P~PpD-bn5>VLEXQS+nz$N853vi?`iYJSxJXa%C?NBxhJE&pZxXUWt8ME#FeAZmWp z|FBg4x&BAZ|DzQM&z17}KQgQTQS-}7LBp)(|IrHkNA*AI{H9i5T-FLi&5!yYCs_VR z^*=_46SMl?QhopLQvWx<|9@`(|7X1a-un8SS{pOKK0>U5#Jsn!5MFaJ$L=SD*IYrY zzZzdqUyH;Bs_{jzNP3WXcrb+pf3S9-1eQn-QSU3j3erQx!$&UWp~Hk&xrtffa3R)j zVxBcZ2v50~(To(rN3M$4Xe~h%SVek_mY^!EDm_-qPz_d-9;bb%4y#L#7mr;AG2)#d zj924gygE^c)u9+4P7)^SYhxTZS(v1+jS<}xA=azvicQl()P;4Wr)T4}>2jv&o9j!r z)o#>>^`+Zoqr!G_qOWe4_0_Rwpo5V^^wlwj?FeIr5aa7kF#75ySzjGv{22RZK4+M> znshf9K5OA6*j=mQL}(#=Bb$r$FqUv?bT+5lLOj;1T1xlQwm4;4=&5~i>U6HGtb6vJ zW2_h7j<+47yzZ`!w;f}>_;!r?Vw9KqPK^3ulvhwD;yp)OAO4l`hNG>Ik`nK^uMj0A z-g7@8N=m%p{zCXy#v2|WM0tr;e^BLX?y`Ss979Jzj{C67P9} z5G5tXxUM#99E{eho>puu94lR4>ox|Ck&b!nXgFHBd>q?Q zn>b3_6tmm#N*@8kFE~8XV@?|upRoPJsqAq|dsD6LFzwJ#v1VG~p<1FLVrAOpA=;tA zV$HL@zPVO=u$E|`bW0e%nFDYu81vikyl4$$ej6i)HZbP5;fLQ=TU`^@%zDn4)3+0% z=Zv|2dm(%$V)WlZh#dyuvD#6HRxzvvorLH=!-~*Zh_*527+r))uu|4SmhUr&eQTTc z8H9bJyAb_g*e!Yp(GSK@^Mp)wi0i+AO7>`sgJxQ8=obfeT<>X z$5XLqG3OcghC}_{7)!<2Dt0kO{}6ruFi#-HReU$Hp1g%O93!k4a}CS-`4%vGmNML2 znTWnPMq$G}gDvDne>?(4X=x^}d=%2dlj|-Wee*~drK_pD@{vkYZ?2l0>RCA~w_c8s z8tv^?S3(o{!;;ZZXrvxQ>4_e_wGtlv zVgsR}+7OnKIzsHWtSwdFr_p0apITq&sFu|6XD8W3R>t@t8+Oof(nUmf_+t*DSA5QNxCc4};;SAGXYx ztwuc@48w{Q`!HhfPw3J&kdECa^V8i-vC}o`*A_xgZ#U{!4K%{rn=VEyNUYMS?J<@ME&X{giln|uZ}_|?;z?|2ce^<9`!3uAn4$I zMEz(kL|HL>g z%0UO;D=!yON;-M^QK}mHthMJBr722Pl(0_!D0!{q*7U~8OJ!r9jqyoM7^O8va#4z7 z#2zhgjenHx7}dpSJx1?Q1EL;`#@(~}5p^c^{gl_6QMkN5#h5;x{z%V0>f1=AChB5y zxlu36aMZ~v%2CwdsI@&|jQpb}S5{JEq#pIYXIA5*-bWjrlN&8W%mpg`qwR?HJX(ve z{YER2_&n^kgXKnhR^AfDD8IZNDxcFuJ6}F4jG16RZ*ib2%IAigW`*VLT(o^LH;i^L z`hxH#i*_YScx9ogdyW!bNr*G1qimN7aZ+lO_KHHBrx|@-1tInuM+q+xLghV5cW zyPH&q9h`B3cv1GI<23O&S0vthu@GK;QRYj8unHX>!KJKH`=3^G(g<(nNn+{u|5v8vps1#(l-v=T%_&uMS1s;_N>bXa6yNd;IG7za>Ka>KbBk zj%<{`sGsG3bJJglzxmJ4E$;u1r}u9^w|HWIJiWN*cp7>CEy{Du$K(Dt{gx>2<#!f$ zpZEW&z^Z<)-5Q=s`SVV2ZFzOF=TX};O2p#L)bvZ@{Y0s>&k9D(ieD2J+$alCKBIOt zfKf)HcGQPaXQE!zgHbx8G}eVtTcR$Pm&Q8cQBpV6k*F^PA?irfmsE&467?l7L>-Cx z5_c2zJo>WoI`i+}&!#&2=esH|Z{>C5kGqPp^hceoEgpBdsm}h_?kDO;l;3DE6Mv-y z#v97{tHrQb`k(K4Q#HqbJiR~ec2hg^=O_7}dxrm+d;ZsT^IzA@mfmrR z9w_R0E1?v&#L+j$=&qHV=#NXY-nKOBTTAtmP2^OR8S(E$WOv#MwvyjO$Y*yQH6+FcHHCckfAZP?$!Gs3?{33uI>q_y-qY-U zQ_rEk+;|?*b5#|qCd8;Hdad{!aT0IzX7MDWrHNK0YImGS9c^N?C()9GuXTCr6t%Od zRMheKO|kA9zcJeCxFRpa8gH~>c4JA$e~Wgks&rBIUyHK;T%0|<_@B|D#V?F@E!v}a zk`;uwmw2AxA0F$y@l;ENipDjCYz)%_cN4lBpKO7TLSndy?{#+p*WSgS}n z&Y&uSv6DQ;kuidd)@{=WvLqWjmSkhTl5D(Kl8qEgjOF5uR)FzzV$C~R`S|U*?6*ft zQAIp{Z!3SZb@ppxlvEG(1Xq3Zz_AcXn$5Z|D z8;!D^W+f)gN=cfP?KCT8X;#Xj97J0X?=#lV3PNvK;?o$XG{+@bng6%?r}B3iqq*o& z;ysp^fPb%lD({)1R7I~`-ZMo{9A)bNR{v2xT8jJrKil8O9)$|ZMU>j;e~V$X&Xt8| zkIU;%^vh8zqHe^~E${WBZdUcwV$4><+lvwtB_sN#>RGv~p}eR6DF3PQA9cT*P+kjC zwIDAYwIEgA^U_iNQ{_D`9c3U@>f>*A5@L?kM@~mMQ5O=i_Aq8piCEl0=xXG$x{%B2 zLTEU&lG9p=4iC8&u%+^p6Dxzw{pP40@e6slWhJM`uZl5S)Q(N z5UpLjsTf&A8yn-Yh{aQk+`vuooZng7r!h{6F;G)nU5GhIjO|MNmZmT)9~Jz%Ca{Tg zMZdQ(Y%E>s2{eL@vOAACeRV&8~1IKEfxuA-NX zdu!mXqHiwmabvaQu>cM|s&cNKRM_g3Hkk2{Hbi@S~HNr?9x*4oNK zyyvhPR1xAm$BJgv%uW#2f*8YwJ*|3XCx|t!k?v%KbdAg^P!qgP}$fnlxce z>X?h}lV88?_>412Izn@75NS zTQ@e%KB6XUvVKGjiFP8MMESfo+S<4>erdEQab=NDBVFDi#;4IjL|%Lvnn3a7+6wUw z+Tk{G+Ir^kMq0Z*g{j=|i!FGwdFk+oEqLScS6d3L)SXUpTF7bXZ+8|Czt|$>B>s1d zz*{H(_FdAiA7Hxy>^U@qX&<^AUtKu&mpZWR-~+jJu|#xV^$D0z3NJ9V;HlH z>i$x++&SD3(`kXxK8M;+CGWcijB#rvv7YK0y*xEK+W$>s-RSkA<%w3XmQSM%kCr>e zfmQsqm={O86g}%E%S1&ry;S-8b36R!{wHxq@tn(B?<5qBZ4u(V3Nr>2WMl9VS|nDz3;vG_N!CX)z!5<)m5iX zo%+`~weg6T)R^O12zjkKwf5AQm&C4dp5=ZUsK&drfYL8~bv$Yn{#AWMhMwD!o}&?- zXc;7LNa~QDOI)HQRGi|g`UT0>l5oU9BNBqUvhV_sgY zW4wwhNv=1mLM0-8;Q0)s{GL-|%rUVIMs8Qq;ccl*WUkl>htWvmNnR z{YJ?$--Uc8oq+HZ9ia7ugb$0?iWiC-iw}z@iw}$MX2}&FmaZVn^^W*tmV1rycaq#D zeL|WXac9YDX|Bbe^%c`xOSfUud!_LZ_f5F8zNOBbh*u|jBGT}RS7#{IhMwG${3@1~@g&|W{hBy%EBchMj9Rs6?It;`8RJBnZ|Nq4W|ZzR;lSeOE_Ibc zrLho~*6zeV=E)}h#d>e`(5-p$j^#6KLo*gy#XP4KX`#u*bE*hhO^N3SQ>=BAI7}OY z)=^_g$tvVnT1vJdg*OoQVmv^#Cai;sn`x)GEmX3f)`Zv7P=@sHR+D(_#D4x@iAgNJOS|@^}MoDR%30g;q=X4 zBZ!ZQ=j0Kn9;pF*OAn6ak`f9>yU^+tg9zed`g(&2;$z}DLkL;}>x)(phFCQ<|F5s{ zB)>^_lxU8mDN=9NUg7o|ChDbK+;>D;E7oIA@K0X=r;xd&R$1Tq3_qBh9Tt|1O4#S2(1!`W2V>XWC3R z<~%KVrlv+Msy_8i`NOv@pO>i;ZI?#Mj&yJu9ouW-{#_lMepQq9EidD3s}syicU!;J ze@Z8~q%>a%Rx&|J4&ho@ z$svq^|0%4b`pmY7$#l%I_3ec262}(T{qMm_7QWX%!?ynK`d(izi)%bKN#W8CN^AOm z+dP^eErqd^wRRyd^Jq+=FB80_jLTu)sIqp@H*9P7! z9H)?{!s#X$PN6w#$V=o$AqpjZbtl$IqC}R|$wx_I-Qi5h`dIb^gzpr}Q@T{0eopYP zlJPZPt4|8^DQ=-%#hsu+%Zi8Ok)T301Qzme`(I8p8O3qLB|vNX{i`O@`Es*^OL-%!mj6ed@1FKJn_vRXlHrQfc%7j9Sh z-4W#G`L^CT!TOG+#U(u?TwSXkt^f6#BsuFlNwUz}Cwi-Pd{H5JCD~WD3?f#U-Ulzb;*{`bUqr=LuD;-l{!(N%-nx>TT+a(g>?ZCi|0W zN3BHEE@~ZV2h}3_!fLN%A3?38-5u#t)Eep!+TGFbOn$GZ^w;{G>UHuepkF5{jY{%c z^v21Xize@^-krR;-c@T5c@@xVB=2QFZ>wJ<-vUBPh^jTT4=$RtR`a;c@-3-$mTv)l z1>v*xjU-X(o5;6-zNYw#zM;_E;w<7YNx#s#R=p(YJL+HRF+=E6@+u%}7($SXk0kw6 znDWHSK+<=`1JvKuzmwjtzORv?5h9wbAT>fX67r)$9wG80LH%AjFzLml2^$x`b=g+$ zt9Q+F!cu;re$)1xP;41>5t(CQcaf zUBw&KA9utL#R0Xd7U#(C8mae+4@zDW=lCZ4P<&82kvvz-^Fwh!VSB_6C0R*BBJKCq zJWyjnJ7pRhTXVvMHzqtV;fDz))ObktJ~cY>JD(k?L1i_Ln)LPmNSCDk*&6FXCD3JY zKV260&}DJoTt@zKdb@D&I-gjB%^}S}D+txlGc;SMWe=H!ikRF!hxMyk;F~&5HBrx$C%IPuw%MP}9N*j5pK(db(?)FyvIY*R{hNANDkDb_iR%UvlqfG4^^4gW5?iI33YD#qS&Z^sDJ@$gv#=;KEvB+wHHdt1HQCS_g*_3Sg^`skjj7$? zLwj&Nmb-)E(X=~MmPbaAuW>6IT7$_O1aI4u>v7aQ6FQ!FTx=t282Q8DBzwa5hQ@Zb z#Fh49q|M-3+)8QL+!{hWl%8Vq>yueUyHJS-8)>#QCNw^z+0xvS%qn@`HR>symyJBwNJFpQ(VHO6mgbiK9lmSwUTd%{%xKj)YmL*d_g#~C ztVJi{-Gp?NG8^Nm_IQmsjUy8FJo3xTW^9+%n8HLGoBxNk`_1C4A_I9vvQgT zyAyO)PIF(kc<$>)N+;$tvUJ8#t0y5VWC22UAauU0GyO^SAY=`q6KSn}G`?gXK;KGo z9R7ev$xmbrRO^}ssLsmCyJUSl8%q1CzMxSyDt;=F0{_|iNUNb8uadMr(yCKyA)Q~; zJFE6&mDHB6A*t=(TOVm3COAIZ&T=__$KQkt%!t5)cmeh zgLXHxUT?wI)wj>f^TM+?t(cNEk$R*gykvc$mBqHJB(0Bkv_8_xLNe&Kt0ZxOWPPMQ zt2sh*mgX<5mOI3wOz4Rn&tG}3Yt8rtLcHbi@)}cJXeZ5LO=}~0U`xENrFchqVaxko z)5ywe`y}UTXGZf^e&%Z0nfce|uVht}_rTWVdo5WN2XS!i;Awm%nukOS zp|#&vM_HnCkfft|AXzVJ4OvOAN!HWb>mS6^wYJteL#t3>K*hnn?fBYW^N_50wePU) z$ja*2lWtktD|&^OO(A>`#SuYXXl$!j6<`Umx+t@RI@2l847+2c%fX_^nT z3QzP8nr)hTzch1_6s332ZgyTz_x1XR1eK%yk9Uy&n!hv;?nuj*{2xhV`T7zq-&e<1 zGJhpA*Vf~!Nxvt~tMh32QI=@=^7=jLs}jwgq)@fW*Nv}a{>p3i)S}5K%j@@&Sxk7L zM8B8JU(yzp(x0T`(pM{GmikBfz5Fbe*YZhD`Re$RT=Q-9dx^FynXR^-%hXq;JC?>T z>7AMnw$<{f4gVGWo^*Q2%$}^oG_vygy{{WzU#H*G945T4=C7^C*Vg*It;g5b>G!1F zla5p~m&TN6(&~vmHTgdJZrhHpuhZ{sJ-#%PRT8u-AkFcP^m~b1{O!4fTBBF#%zBwa!t2k(;>3S8Ju?f2-+tEB$~_4)0v;X*ZTyzp8N!vR74LFhFtP*5hGFW?~cF1(>mm&=QKbEx``P~SRxr1eEE?k~BR2j^lbR(^TP z$d`nZql9o-7FRVjJ8D1m>;{6Q{vuLpzs!IAf2|XQzbN8f@-CgZPRDI2M26Znc^9>) z5L@~JZ3#)c3b*BQt@add%jG)R@zG4CvEL1v>>=gPZmAWU#e7<=T|?R>t|As{OQ*f$ zd0sP@S|S&>vG%Tdl2#ihJ6t(x)k##H5zC*2O?FpwnlgX7QZ1yfQ3ll zs1n*uEv#>%v%JE8NcQeYEL5{N27QaQOQg!~$;uq^ws`lV4e!FnS(o0+PHNBHg zCM4(Ygp$*#JZX+}{!W@C$x_lSCA(MBF=@7t)e^~G$$5viq;>vIryXjcb+nWrrIWep zVfv~kSdi>t>O~Aj2n*t zm$noSNY2G*)aNZA)KE@ywi}NXofTBe>g1iy(@L9NM9_H$?d4?&I?*HzgRDL1KQsmsFQbURiX5flXtROChp(gl^qRX;dj(e zboN#9M+g36N5-DGqjna>BgHq8GYR678n+s;nq|5$)-~oevNhHvi}WLQ2|8`xkCd!k z$|g=?>0FuuAraNu)p;BcrcrOUUu&Ibq~v8&8n(wt)e`FPb@DhVdGV~p zw!iwx<@B2_So>H1x{RLG5vm?_8FxD4r{pJ;yds`Wui)!;CEduKODWv|y^Q!u@~^<6 zzqEIkkk^2BfNtb!racdDC67|W#oYT5^b+EWN!@8(M7RrjF|j;l%NA^R%FD~{n@?gq!8R>HT*!+~5OG%emZxOeI;#r+h`xa@9J-nV0&cv^Z ze5}aRiu^#IOZ+Ayzd2OW)|)(041J6Ec{-Uirg(uZ1yLl29`|KU)1Z5~HB5|1t8pvO@1SbV#T zjvfuc}n*QUqZhmUmntZ{5bsqDu3ucyXO-rxs)C0y`f8pCy}=tx}070 zNraWqmF$mCBCLi^Br~&vqiGBYv>=V-LDBIi2ju)V>BTyN2EJ$%K8O`?8m<-Qv~I{U|q?(8cB~ z8s3$#5@35)DL$qX?^7-8I=oC3LyPfC)ePTLIcN!SGxAF8T4*!d#ygX1)o|6!t|7R1 zbgGG|izlclRyTZXYfrihvZr&x`6-kxH0#RE4o0MEAJ2@h{jp6%OYkSlLY?d&}W zv5zMFc58oFw4L4F#)A|0a@0Q}8~OK-$8 zTwm)TyuOKw{~t~MG5C@@$nIlpBJN`yf={_V)=}gijqf;d^+WL_*T*^xUvzz}Bgr|+ z7MDK~dSvXkZlEO(b_1=`@L4J8qS{E_XhXUh-;&aawJ}1(wK0-3PNC$fc8wVh7p*ap zQflyeiC&zNZSX|dn|Y(w)EIWBNw>y7rDm&QQ%er=4fJGcI0f&Phw(nG%;EN7r2A01 zl5{KR5%%Hu=Nm{lo{_b$IoU7*DVPXpc5FcEzLy6 zP)j2j20QZx8{+uSD>YM~Q}Kg0mGorNQ}Cy^3+YLuC*#L&8tI9oC*d=2I_U|dC*rGc zSJG3dX9`}v*W*Kcck)Wj9>k?)Pdqf1ni+V4EHy{PGyYM`?8n(hl0FLldK^9kk0y1T zeFQn;*x$qZ;4$36*C09arKQ!gkLS>-P|0TUXML=F82N|O*L|}KGtaT)97@h%Rtis` z)2wCqs2+oVz@3Pf;g@?S=s4nK_#ht#U4oy#Wq1)>0v$tquEKIx@Mb;nC%BAfyOZu=_u~3kIKi=8_vY$YdlOPqcV@8e)Y6q&kA+*Pgk)Ku!l+ zyAYeK!Q}3bN8drjS$wtb1*bn4K7XyX5^sywTC4Ejc#X9;o)oXK_QAK}HP#B+QF7c0 z=yKY#J>~0dX<;`Z$F0WK<8{^=d_7)gt;NIRb<}VzlG-)aV*6@qp}hdQ2(OG+bG^vc zKFKCzzkTr?dA+qCUL>#Qsq2vLuC^A~R}tnz=kwlIS@K+aJW_8*>v+N@q{aOxz1bSV z+i&J~><`@^UzAr`olHk_r6oVNS5i}FqgCATNIF9(ae_4zU&$xnReC6NIG&+TutwO! z?JJO*JDMx327KdQVRgWl?iE~jFbk{@zqR1BXqmMZKEmy_)@VF`uVv;L4Luk>z1FH_ z<^dnZT(lMrUI%T*ys(yg?eGEW;luVE=(+ZZ)<}B~mX3e$4=i@=tHD{53HoivBCw(UAv+zKA0qHYHpULdIuXUnzA$hL3 zot!i5<5&;Kubxiv9Y?5#)|2-G{FJ)pHp<){dmweqt@sM|pdPs=SwfwiL^zQ(Mq6?( zv)bWRSgVqDMm|eja|?O5;zc*Y6YpQ_kkjg^F0j6| zFXE{$?Td-O#8+^RbPK!(e@Si&XpU$8X8)Cvmr&+QJof&L^rd)V{nEC~-$`GFFV-*d z)_NKAWaP7T$k+0&cQUDySoz$DN7zfPoA3yGsdY0RVK23A!OyE!Nw?tL^>Ut)7rv93 z=WKlZ&bJJ{e&?fDSYSE${hf~tz5$8r6lBf~&;u!XiFE@$U$v^b0q?^OWmY2xw}EQ? zxtdS|t+8sMT5YZ-w1sMgxtegC^*PVYN75?cdL?v~^`U(wZ}TDEWUqu?P5dFAX|IM} zOZ*{zX0L_H-|UC{@9XjFdx^Cfx|!=!c{i;Th6)H}93p`M1!yO7+LNR~^X%ZXdYXwR0k z!3xqP#DBo|^1Rqv>S@T?3wh=(YIxh0oye54MdGvQ&zezqmQtcm7 z`VG=}O(p%Nt@Y^}&^Pd!{6{3%(~*qjr}B%~@8lP(=3XEz|Bqj=9()lhPptBc`Z@Hu zSd#vIELs1NXTKzz5qn8J16f?FB>7oA16k@1u|)L+9;4-R^-QGpzd%c4SzD{DrAV>z zi|HUaFNVI%e{*bkZ*}ZfS$jJ6Ypg#VTb^GXe!=U|g{)DWSoV&PvB9YFtYiO;de35Q z@K@r{7P2+uZiLV0SMcWiGQah8=xbcP%x``T56Z7XUn2iyd??>R`bAqS^%u!`3E8uh z)j*bdLi{QJh`T@M?u)j3qMl{FK>FwSPQH`;B1&fQ9DO0Vca!%TQtIC+W7%5eJxBiY z_>|U~U7nU-L*6V!wtbeI=a4|LZeiOzakjOK(Hedl{@E|Erjp*pOeghyYdXH#FR=b- ze}RNLh5V@|;Hk8|tNFh5EOa{YWOE)GfXUpQf?xHg@i0B!{0y(v+3oAlPyEymOt5Z(1aMu$#?BJP_1(x zBvb1ymfp;LH@^gX2SwLZeD_C5F(zmNDMJZIkreSr8QdkgVL_}|`Q z%WrO1BagOSjXcqIHM6NztB6nVM?Ty76mR3Rtx`uzr=U>Q1c+q52e)~ zhdxA2L(Ri@@*Zj)!E^Ue^JDyd4>gbC|9hzU2|mAv8u|1dO6kXJ?G`j+wN?%tW`>%N z?BQk@bc7im(~t0eKGKXZqVj`2%8WFkzr!#3EdIOJIirlyqs=HY%lZ|*)@ND2#_Rel z>o@pcpJn|PpX=I!4jpiowc#Y;}ba#zL9z+|>t?26- z&28xG8jbv%mhjv_Q)1uFb%`x+pe43EdY0Jo$5~>_vu24c-=Zb9{ErTx)Iigm|JlOs zZ(6eU>`%@B)6bORCAl9t{mo3?S!=d2W;E%sW(;&EGZwnD*~w_{q`BSKl-Z@wQl81# zmE>Um!f1CoMeGv>87yQNX?=&7!A83vgG`3B^xr#Emt~DJI~$AKaYh>DLB=L%7qN=f z9QFWM&9!1}*cw{R8W1~GtZubu!`c}g^dMv6XQZVbWH`ajHONQ)2m798h(VuhwExnL zlyp?A4z0eXkEvn}SVp>n^<0#v^~PvwOp7KBCWm z$t-wnJAmcw&PNy%PcF>x8R6up&xa|?p(4iuByoE&Mj^s8jSE3v>Yi>0#P zojjK&UfSO*LG35~aY)G0&e9yq zex#`M%@IMiK&7u0ZdTt#wj{OdC)~MEA=-b)TRxh|mBp%0y5Wfgo3)=b#FGf}JSHtN zdK9kFZE%I2gX^iJ<#|l|u)7fCc})7_X@p(SUrF0LomfwOZdrm_|yd*8AKsgwP(AR=2LvahQ>ELjQAcbENy#0rQ@%uwb!v4^#- zjZ*#oChMe4JEi)Mc^jpPbyEG`{2rcEKl6lLu+G9?v|0V7Db-$|zbtZeHE`83Wm#HVY^gLawC&_BF@H?{6m+Ym>j-SVM z9xLZ@EnJWG&vgPy7M-<=Zjnm%>>5aG|Gde5?N{yCi|aMnv6dEDR-ZI(g+7udS-b2) zbJaoH#;vG6Bn~3W4zeV#UoYO0d|Q2Q$$#70dXOCm*#r^hK>SKLk4mVxP=W)Ijcp-A z#BJ=D&)Ae!zo_Bbg16K_#b<=Ck);alC2Dl3{R-Fwwe5F>O(^uw@49~$Y*(v)epj}u zE%c4TCP?pS6Et5)uW1N6^*NoC!|Xl{Dy?TT(&A3ixw=sCb?t|HQ1N@|k3GT^c<3Zj zKJvsQILt&+Ddzu)aP2(nH*hLn5~ z$tLk=Qi&I^h}m6do;3H%8|NrEsbqp2L38VHQu59&Z_Lu`w;;$rd*Z2G`u<{qunF1$ zC?RNuO;D6V$jZBwun9s}>V&bd2|`_#5hO46BUR39(-$g4Mg?gh6okU4gbJG={6#Bh zVyUzzY0XnmTH85cOfO4sq(}rU8iiR zc81D7r_SEU%Bt+Gwng@n^;MnAk@Y}XWo?M(p~81BeD}h5FO2sBpZ|ZE&!^Z)tY>!B zj$%NN&xhUO*;X@thFM;-t!DO2Jnt8g)|{&uKMU1ttGPaeYPQwP9>z0%L|SvMX8asf zRuDATH-~Dr)yys*=M$M%<@LNpJmVKbWo; zs4PNiW-p6Z^5yYdUrvsE%Z`X=Tg~|S^9!2mb#A=3S7qZb$i z6$fZdkhM$ogf;}>0X5fG6XZ3Ze>~f2X0M6o{aR*u?a*k(mseBm(`c@j$3yMbXs&Mu z)t-&8mhIxXzCCH}nQ5*U=DR&qJHs|q+5*k>c0AY1uZmW~n(Kw@mJFu3UMIeEu2PuL zycHUq2lL_?Ke0n3e?uLRw&aUIc4`aX|NrOjuQ4y%m>U0Sf^hL544@kSMNo})jsK!} z{AWpP%xnCIP>p$w{|KtlE?GYZ)o4#fzBod2(i-y`|1F>z?Hc*TP>puU`o%FvC?Tye zukkO;phml7{Zgn#douFH5z0tw%xnCYLnUELhgT7EfeO;{4w8&{$^DfCjdqQEol=rj zTS@teMKg`?A&hJFh1LX(c8&Zt@#wFPc|kQf$!H(I=oT-iA;?~0|9G@Z;;&=;YqX0O z$j`AxySPBRc=T(`YvhX;v?s06E-7C+6^(ZB0y`f48uJ?Y;suEvVtH5U#<-TxC3#!Y z*$<8X#IAgT`qnu-;lRZUG}@DspR(63iQgy4bC$+`D&_$-HHGj0|M&No?lG}HQx8_D z!Ri^~lNvx3HgMe=+QAY^sR2}@a)mbPUS{5c4jlsEW5fL z*!j&uBRhoVKp^5R-OfQ<*v+BZPwT+GOEFZZjuIO<_4Lyca+41Vgu1_gc zdqN%KJ)w^Ao>0elPv}Iu(e7fO06h`fz}uW)Yga?axGv!5x`2v0o}3fxley{)?F@$W zIC74+PvNQ)v=a!^Q;9`8f;s&jcaH-pbSmj%Nq-L{(jwA}?FPFZ+JX2O@{a|Zw3wW| z3GMBp$vFnBp#gCy)KdExr_?USj)@ALvy@O5HU(Qu;P*ImduO#jblIu$7)x^EQz+4R#7N)m#FmZ2d6LD{ldz+xb0gAUDMyii> zIB}mCjR@A17$hn&I91|4;1Q389!mMVtwEjjUCmpZ2ma+e_VU+obsp#)opM-3SPj(~ z=C#~87kVxjfR*H|0)cf7$N^!t&H?KZk}Fi!+0e5=Q7k8CMU1XG3wjpVj%DO52f?&I z>2-uNz>tLG3g2`F^bD{lpf<=A*6DQU>0n|&gODpc(`nGtK;#I!Bzh_cq46<-X*{Wu znbpU~^kgtn!jX%f1g>imv8d4hlL^N|ClODH@nTcBIv)993K*uTgzq6&2&E}x^Y@T9 zgy9rw`B)ukdalRbq^E#Gd|4(%RdPVhdqWY*8!%K{S_~`NR>J!26(Z(OgFfQSK zuviu3dbSG!#v|MZ-o^v_;uG$*gwPSamvdFZ>4*xS@d~l15F5f+i3-CZq?M>p9l~3Q z3g;ozm8g&(ZxU{UzCjGGjC3WqxsRYi(^bX@y2=aSuZ8U$Zp|W$uy&7gh4UR@?PlM? zm)ngTVX=i@*%i7QNNu55cD3K)J%t4xVF?R7!V(sE1PIxA&;|B_|(9*pV?JcBCal>_}^bJsc{m>PVg#fuvqZ%d`Ti z_cruh;#Sss#I3*vz6TXvuobw%51=0r-@^M&w{PKXd3)mNP@&Low%?|$Zzlg1`!@2X zL4{PmiG1NUTT%b*v~XZlR&x)-!=(!Wh?7CkZTh`x(nYn5mdtBr+2GMfL(d{Uhtw$O z*~I4(kFw7LJ3P`7##iZ4Tvb`Z(^gp*gNv<-v9DDz>a{AyyH;7kyH;7kuU1(?j#gPh zj%o+_TBz`&RhIChRa{?Vx3+{6Zfyx6+}aX0xV0rbaO)WH+uHh}{R7gx1uLs6uJSfl zwzv73x4DwHwlap5l-7INi5AtWPly-MCd&}Qz342bbSbhBA+guT@s`)e~jIR`z3LYegsQv}==C$d=Vu zS$ET(j(DDIylFiuJ2kTLCN3_%E~~U!#mZ`mY`kf8tKA}5chjm@Hog)YZ<;eSNA!)? z%6aQ@lC1z)3X=^WVIO22NHUoGSPSuxARr{QNvEW>rgros2`1JAWFtm0UPG*# zk}NO8k?ad-g(1rVFmtHvJ{hPiAV`ZP9~Oyk>IByyU*m~)8~NiER#N{5v?8r3%hEov zM=O`d?^pp9$J4u4Ld7xko8+@rJyyT93aY-RHjtkl;UDCkL+v9Jgit5dq=mUsTh>5p zp=#q=sCuB;n3;vIA5|X9$e;ue~WBp%wIu|lU|5tVhgfkJ2NdGsn zF(TjIY6;mL5Ryecz_rJkSPqbN4xK?)yGZU8ibpLkiB}%t)Gm^HwZa!tM;IN>(Z%&R zaXm@Aub5Ub5Iscv5a@MHaemrU#BMFnQ%_=Q1Q>i3gZaA&-ULd;i7r|DbAU2(QWzX*57N}FZJ#Cr^d4+ z`mMRB_~%!@*S24(iHm;qd#V3#&qcTApZYr6a?w2h6prkx{Bvv0sWB`5Dg8)dpG9^S zg%s3?ZB1Mhx3D;y@Prx*iPy0v@7)@inythk(~MNjQz?SH25X)YN0o0nwX-;_{J5!| zWn)E_lr%{B5y?EIMV6b1Ot~*3nz9;#1-`m5^kiFIFbCLsm-eh zvbUqr(TV`hmv@(sGlF#vS-c^1f<+)NG&*ULH;953d*Oa=?c|>SQ zVJ0=3h~sNE(HyY#Jo4SW^R{m*tg3#4W=qW+t%&t)VFOdTKGX zp;}KZrZ!Ak@0+%p+G_jO)997#p%J09+ET5owpOdF_4N((HS|^VZS~m>Tj}8);j+3 z34U2EtMQwlm-GI7Rexf^Cy%#Pk4+>UNl&uRq}n7sX^&KO3&X5EQjK4s@?~>Ll8#SG zGL^>r|8)DPW%8|*w2yjF>-e`cwUScehvI{h4pmZoP`@{k86`U=UMtm)g-1?gOv$T~ zJ=F`uiMDQA@u_6w3$>j{l4@hMU?NG1BdCXn^XW^ehp6q;zG`o^rMRcsSQvJ-r&?M) zLw&AkUMPd^>RFH$}FR(XqON&iuAO1^Ef^3$ml zNidRQB+(?6=d?!DsFXD#Nvs-`I(L$I2$AQUM0!e4_xe>jeWJCgeyvWQ$S!oUY884V zk;QcGMEeBEDp&nBSpn+|iln(j9@pAfXH6untKTLvyG{sbZLP1R69SSJ^%Zs6M0#C) zW1-=-M%UNYDHE;RwR+czLF);v>UFY2@~L>EFrtYTKr0V%MV&Lz%0%+6q+Q9r;)+_m z2&E#fn0S|w+^l_TamYlTmNr7NwRWkct&m1Vm=tL-q&<;bE`5fy8`_^vG#_J$6KmY3=0HjIL8eJpuKlQz&V@RatWPeA!`I~+(={7W4^wqxY_mZEZM604% zELqznUoH7wS_|q+C0>vI_3xE@DSfp>W0b6dWC2xQN$VkfHGQu{=hXDo{_*#cPD`4t z`iJW z6Q6ORn&BiJ>&%yCKFNTxrKuTFvY~vaYNnLT7{q)=d|5J>IE?tUWH8Ccl079K$cM0` zAjyP!C#`-Y^XZ)=DdtZgX`YtMr+1QUsP~Z6r1MC68_7;OWuI8~)EmgEy53IzoAb^D z@n`Aq((&8r4J5Bi%FX-5);mg0u7pY|)*DG0RXgczBtNK~^fr=F)lPbwFXN_=!nQWZB=Ye{miq_y;piHwxYaXYddsW#4A zkkqsPO#W2+H%Xz1^&rpw)%&s@l_tu-}9duew?~}ZVdW62T{(tg5>X~}0 zrar0v-qbVoKHt1gN~4_bnd*)D>PgQ`B;aJ#pY>TFPR95*8{PVj`7xffq*i_!J$gfpCygGBD2*ra7>y{6C-E4K zD7B%+yS}pCO=~=TUrDeUNor56`J@AqCP*tkt?cvbyZ`BTPTqFwudg@PDpYT(-=H_& z_MQJ79e%QIlMdfQCRRH%5WbyH74f|$&nnyd1e3Q(`Bd?dx5WLvnNJmQmAq#aafv3+ zU_15+rV-kg(b@-TOH#9R>GD^k5h^c6{g8SMzQO+HohrJ6je43FjG@4_dTq^??|ElJH^=M${(y$au}E90s# zzD6PuYkze#VH7LQf9`Ydn~X1MCbVBHnJdv%XihS41nC|$CpmBk=_JH2n!y*OH4xX3 zEqQ4T#4kKJM4}_nu5qF}5!Xn;(G#7Dv@D5+Mf=3sQ;{a}tNX<@@ImQpB*!NjoLb_% zmZy%CG(Cy#rw*PceUPYR`hPY@hewYTxi=f-H`mLe5FFe`{!K za)mfdfgRKi*NKFaKqX3#AZ%g^6ruF$ClF4I@rwaiLTT5JC!7#t90M?g6VgLG$mvQDg#yTeUCbYlllSi?lH<$$i>S*SRO;^ zDg54JKradvy9Wr^OJYRhrJyh?xc4qk32F61VqqLFhF)x41j11mTj3oq0`K@kN(lA% z!x(w_E{H^F)?{<4C`Mtv8(W*wSb36sS(^$$d{*#3BCf(1(-@%%sUWwSFcI9D(4#kV zH4!=?MidG|dJ{P}gG9T9ySEa?fk(SFrqYDm$laS_T;0x4X-IA$=f)Usw-Z$QuFd4! zKrera|9w4aAsK}^zn)MXqx8l?$09=ry(cP++;x<>KF0QqfC|BOE&8!~Xg&9Y{~HNP zQYSgCAzT|HGjnjhyU7<)a1@B)cH9#_Nf_d`(9zt{SrwrQrO~+xJ}I=}7=rW(!X4Mf zxMQK0u3~IH&3g}{jI7-VqbMZP705pKb3GJXhS@_W({{O!sSpQDyG;vGljgW4)6s_H_Yq z+(^6v8MYI2Iq?co?|?gQdC@I)6q=-v0*j6?IZldh|hjTY1SzwCOrCAdfg*p`XE9%Ar~{ zd_EyhU&c5gYdWx&<@;_*M}}pos4*# zcaRSU$tkkwJ{qbsZx2ykz7BMbR^A{Qp^g0Bhv9zXpgL3cFySG1&^_e8%QIu4?-4%& zKinC*GbMgZTHY9hu6&gHW1(ZY{t4+v;pCEro*+EVO!+RkPm=RQEEhcq2XD>wUHk_t zmXYLJpbfb`dBU{G-@_)T50wXqL!g_WcMu;6Jp_6?v8?*558lr8Ves|a>1_v-BMbgM zGu&Wa*k%SXq~%`yb#V?P5nZ;V?mnu7-lwEpD!Y0nRAXs zau5RkSY}*VqR$YD;0ybax|w^&L2n{Xlb3-nS5xD4mq7L8A0M!Aag zm4s866(n8B?(iwh1d^#_1^85Elp1Q0z1!59kpM%yBzk>vIHdG!L z+L8M_v@P)rq@44S2V@O%FM_0m8RX2Q+_}(qh-Z@83mzdq2eSw>kuCP5%pQab;7Mj+RhSAwef9%Sq|HtgtxR zClwM~i1Gxxo1D?q&ZEwoB^EWbS0z+b3aS&S@?Mm9G4j}n6V_fka&ElS<&xI9)LO2Z z5p)($drA&L=Xtf8WC%hMX$MKW4DFz8$rbWdI&9es85i$$j3Wo1RHS9&r33L!F|J@I zQnK`-Q)6QZvh*T7+Zci@y=bptG(nbLx{w;lK4}+d7p_Odh=LL1jATz&r;vuTkK7H~ zm3zZT%cg`hHbdEq?g8yi?hw+#T1bu>3>AVx7=S@gAt-ceY#>w!3hmtwfXb#sUsB@l zvgcCxUWM;f7+;0)Rp5sOepr~l3i3ul-YCe21^G}o;etG0Sbr7PUxoE@VZB_?Zxr-V z1$|UOe^}5T7WBOZ{d_?`U)WD6?57m=zY6=6h5gFH{&Hb|xqt^K;5Q2RjRM}LfVU~& zqY8Mo0-mjaKP=!63wY52zPEtyE#R>Wc@s{;P0a zuW(+kaK5r|9=32Ews3yAaDKUP-n?KR;D57yfPdAWR5NTIbiw9=3za9ZM$)n(FS`so z@=qjd4ozObx?$l!z6E;_x?|fwmLT$;zhohz7ojJ%4P+g?H=)V@mn^RLA-^}a4dgXf zp1*QXdH(80D)9oAc>ZdE6$Dv77{J}c3z$5A$#TUYLgM+WC3Y0#3GAQw|I)e9CNE&a zu-PDM6(a~c_WvbMKBKT+k$5TE)<4mh*k*++ERW#~nk+8w6kD#?87h1EI;s6#`~NC@ zufq4rFy7=-uQ0v}KJ0{d>Hk9sDfV!`hSdp4JTO$zT@cpA3G=-6sjNtY^6U zv*20iGtk|wJ*+2!Cj-ZNj`Xv^bHQ%b?$+bM6XZNk`nllwU{`B5>#^W*a$X?)eDFdr z-P+aqIrN3#=fN~3g)Zfpk+jzmY)%a3sRl~c`wjk<;K87cU+p_sjZo=<+?xm;MBIV94Somz{@{V2 zga1IVB^bb+iP*K6Xic&@lHbAa&($QXTuibiTb;=1=y&q(3+@m4kvAF37?Z6jR%id- z;J%8C3rRH$WtA>c3vyL%5UejC$6M?MY=NG14|&4>7H0F=tP;0UMH`mU+Q=A zO8qjwn3`S<+Im%fYric|SNW|dUzu)^E+)SP;YUGd%6IbWyw-jjzs_q*T<5i+ovSF> zDqWTCj#Y#%lf1ne;H~ z>gEqi4JY0^sPHPiy{T<+P{z{}tTxo&8akSIZZI#X@#Ye0y`89GY-(s~SgM;plu+dF z!?Sw_bAme0vE~GGgIaG6q0TF{%BZK5(7_tQ6Gi?ILe}3o<)>5Wol~iF01eVRrCL&= zBX(g*iI)WBUWK=WI`;_%r-r1m{$N7rk4t%JKRu3TcTO!0%Di%KDJ7Q#B|O&=`!XGo zV8&BsTxxvEO?&BOlvx@q3rf8*ub6wC*%2ur9+VoK3jINZ$e%#T@u>-^W@$IQJZR~a zddn%lESQ*b(#_Hn$)Au~5fpnR-in~aYYA;hiAmg@m|98xiooKuhHF{ykWtV!RyDMm zy?BdI3$4Yvj74Y*ZELlIwzJwp+gtU}daD82KphtC+y**|*dunWOEb;c!MP-JX{LoW zCEP2R98L-M3}ysV!WqF{!B~GlYG7(7=vaRzzkg~#YEn3vQj-WXp)-S7!NojTY+an` zY}KYO&eW#spqG$$ai*Bom`ZI^!pkx_Ecsl<|GG3YhE|FEG5%P8U}_Al)59A>=m{N| z8kE|Z|FV<63r|fAcL{e7_6T+f_Xze3F3&{R0lJ)eF3Vh$xj0jozKGB^J&y7_`{Vq6 zss5>n;iPa@Fq*o1dRJsZYzke$Q5{}}@Ufw9bmzRT%=4v|m)57WDZo%%smDG7f=E_VF)>f{}WU*KDgUkXW*fr>@FeoylP1Wj8$=PV#%EdZi}$y;8lQy;BqY z;eK@RilSyNXY4>oKU|O(yI4zhCogVBKPWF4GdZs2* z+a&*jj7dA`3o_p)9_F|3ioIdf+QQp|r*;qb2&V?S1lML#SbVxR6JX)#TI#$eGld!^ z`&0bxsUE58xO;78PfAjnoGJeG8Q)4-*OPx;W(N6thBLw`0X6yEQr%O#P-d#XIpbkp zYBMFT&uq?E^vfHdn=>auZ^)bkJu&kq|NP7anLqpIWzL75&-FRsV1Ed7h(8oM)IU2s z)Qk?tK*xk*!$ZuWW^DK+zsX5|>HmrNOW#RPO8vz@H*;R*FVypA|E#dsTN#|iv%^TA zO?+0kGFU~b28^<{z`4sMagr+^TL7t zAku^U!TulpNvX-HKl)!1pBbJNt_lvPp2N)HW>h#jJec}+hVC4W3;#wvfA#<7pPe}; z^MyY-H6`^0Pft#rPi^OgXM|_+>=}gB(AB}j;2?9b85bTwJ%^hk%*b$5_;>%z%vqVg z`)6g&hMt}IoBs!YN~%lh5B?X#r&Gto;7Btf92p)-`6J8);Q)W2e*yKMA8w?s@z8^a zt<;%3|GD2K)tLI+Z%lQC{(-CShyDEl{`Yz6g77rzniQNCP6{SNPv`0=YCh5&Wrl|% zLOXRv=FE&uJyz=X)YLU~Vc6I2=U*81^ZP^lQ_HE;F*!Jz@<*AY&9HEIXn4v_nbhf- zGcrG*{Dt8U!ajaq|9AfHso{5oZmDA^d9*pk3<-yZ$C#nvu<#UWnjD-$m=ZWVYf?_? z)XZraCv{rp^vn;#-hLndht%_f@K`fA90DD}lg%jOq%I13`Mv#%DD%Vcd)z(NxT%vf zr)1pJDVbBDr)HX^E~d;y;c;eAI2byZavo*el%F~&b8^Nf?UA;ulQQr5mgT2bN5A%e zbfYTbxrEA6uL$!HjT=^B_-eA)FFEObrh?Yxpm#qmFJTcfILIIKXsq_c!aH>r7|& z5z0L5JmMT5o)A9boDiNEKHzL|W@A?GfjG=K*JC*x(*$Hkbyt1M$AmFa2Nn`||ACsH?lL z+0S&P=0F>u=`$qRs-^}nnLjSOvyVmS$ zx=}+{x8B`gHkx|3fp}Ro-S6%%iVMSv ziSxbixUjps#;i5nsk58AH0tj6@RvqC{GQNdT&;^f@jr!rN-d93{wL03&N1P!;bYFR z;rGHG?rO8f^q_|B?mf7%JqUSA->zW#~BnJ5Pjr->>t40^-(XL>ghf~J&!w2I7f%agik`B zaGrFI3XcvCj6U=~@(-l^0a0&vg;{BOQ@)q`Q|>cD7Y^uGUrzmc2`(LvFB{`>wxaWq56v8wsdj7JP1M^K+SY9c zJ%p=lc0sf-%2IPt_D=71=MLvi?+%COc=ktLDjQ@k4pW3n!o#WIu*|LAaprh)t9Kjm z!I^e$d-veXCgNMXTfO7WErb({pS>i!H1xA6;*k2Y*}JIuPVb=1!I}2%5!7>d=7>xi zx7v-k8)l>I{AfXRH)Zbf?)GkTZg;%wrQu|x>I;gOU-B6DP>wcEzM**n23 zF*kd+5O2&JM4cN6^=^)OqHHcZFPa~@SucBd=n{?y@9}PRZgcLT=DWR{yd`F-xyiek z_$X>SGILa>%5Cj7=c!z_d3J6zFKU)`vqyyY^3*-vz242vEzZ5(EzYgZjownT%-rZL zGs~ejadkA$9+f#dQ|Y#HkIuAmtK1gU&^+5BJ3E>awaCti=0^8d5dIo;^BqgLk91+!XUvi|n!F9FsXVQ|?x{$7U+rO80*6M&~Bye(Jf; zE1^trwj?_%njJkr{{7zfD0ytAB{?P8mf5|cnNiE^%xG4$#k;||(b+A+JBQTwPq+U&KDZs0ez zkCroj+H-w_cW1ahb3o?K@Gjze!u>PrpzAW!7yca~ZymMmAFc`4(pGB-PeGq@o_0D? zXNRa`bgg%tcW<~~X8+8+JbO>rF6!g%#Tn zUyJ@$v_AY>(cg>OMt$9WZri9Gaoeb$TjF-2&W=&1=o;@@?~d?C;enYu2pgaqG8;4Z zh5KgqgYL)wJAiuDhpWQX)Vzvtozt18Iz^qMtG#Qy`@^-FeKYq{{=Tp-Y8#cfw}*Fx z8#61z>zwPIl{|Nyb09Sw5FQx*rRc9k4}@znYcmh<)cs)>YUmtwiLUal_G)>urCS@- z5pSU6f#HVm&qaSJ+CupU!Y$#d%<9aRaCK%)W<|I%yxv(s*z7d&Y?r7py288CYmBb+ zuJUT4+Nh;lLnw7OQp1LDWB6s!pNckye=7QO(Sy{pC44YknOT)t9&UDSaF&NFh`Ull zV^kfLx@B&4R6|@HmAS`d4&vF3;X{;vFziN|u2Hw>a_Qm=nqA+Ld*I+^z))a!&%|)i#{*vkRePUL5tG%1U&rDU+I{J+KPtC{XxXkgHkGWeNeQZ7<{@7GU$7Oo( z>u+#+&r*I!f=4onYu6aersArrO|IG{~NR3yE?okTu*K5 zym!reW_f0iGcTMU4&vE?&H>zA?;YS>60>TswDci$skheMm)h16_VM=T zf9>b)?=JKfkzV92_ImR~kEl1HC$wkOD{39QVcs;YgE!4v(6{&>15AU{!5P4R>2Jz| zir~lLI%?S8UE}WKE%Da4Yl(ZA-lkX7i;#;3QhtCLXxcmV&OlS|G&p5JIZu@l9u3=2 zf9qhiyTn`St#+4s%b;txTJJ9K7D5+#>)b&+JJ76hSG&u+YRb0>s)N_f8>Xk}WpYtz zP!>EImJ%)t4{+yu3%mn(cD*~8rv{n9rk&H?sR>>)ubUd4st$VaO!KG*Pv@eRL1}PV z*phI0cp%Rn;2!AC_2zj8y7RpGUU$rzxx0`7Z6-V7ncjBRx9Abu=TBpt#YU-S}P90Cx1{*24!QJT2 z@#cEP!4=_^VR2AGJj~QMwazfg^JMU{c?J54sS6HrXM1zJgDAhz9Zs2Hrd{xoc^UdL zB@T9Hdb7NP-C5pj=xoZ3pv-VH!c;poPW#|R^O9*#`F6o3N*?TvB!7e%Y1%l|&M4?e zGs?7f+Bh}PQKrUJIjx;H-7colyy3p-iZ+_A(5|MNsmry^Ep_V%%iMRe?`E3^?+{u9 zZ&ChD_jR|J@$kC)2CeWqp*VVvyYFV-%jSaSK|7vmn`@U_;x2XH&bA1OgSWHq5Wk(h zGTh+3oh=To3~O_Bxn*uGVY&M@b-o4dY`U15Ty1W-TSHjkwx@=6x%Rnz+$HW?*$v)C z@2%|H#P9Q8-pjt9je=b88t?MCd5!P~=pW1%<{j#J+kMCFWICHy-PhbNOg%NU&(-Jl zcK2~V;HmesA7sNI3aWE8xfO0TVI_2>yUKktyU{zydo%kM@hk4DJo^gadGoH@(R6}# zqV_hq>f9=~f!gYG4Y|ec-tLFg_CfZ;Y*CO6KFnr=FnA+-khiDzM)pnO_uK~4!Mx{o zFdd;CspVz&dGmsK*?ooh_3WPB4Da>q8^j%`ts&PTx5!=Wenf2_W;^B?$6DO=0*1<;!e5w?gF@sDLOma6Kgk9`I`|};4l=>3+1Ii&y$^Zz1NTF> zooR1AblaPH)0w9_>deME+Kp6vzQ+so@g!22O zmZY9{UvRUOc{Q7LW_p`Qhg@ZySNV-uXOnw~JHzZ{DswXkt#Y%dd8V0V%5vqT%X1aE zobyulRIIQ!s(rACP!FvS z8iFDx>m1@Xr=FbC+<7tkQg&ggA!rsXOf4c_Mr}(|dzd{`d8Rm5lAC8r zaxI}PsU>jI)DRG6Lub2l+!E*c>MV9vrk-|x=B}j96{-0=%QMb%+2^w@DO2Li z<3CU*fp6~2ap$@zCm>#x`lx<7TxoM*DnX3Hp9>Z~DWb!ri17MevSmusFY zcb?AvEL-mUEc*=f8Okjtf00>iqFgRl!QFCaEl;gUtxY}QKI!fYU7OlB^|^I*|I&aBkz)JA7^Y7TTxYA*C3t~RG` zNKG?aiW+lWb6bk$x{Xku-?fFOd}mA1gTxP0&qGBI7d3NS=X#!)X09hphfX)Unj86F zH>7S%O*OligZVE9IUAf`WPh36;P}BWpc|dJsSN}_xGr^lYFBd;C2vgKl$v6ung@!u z6m`vQ;;Dn3P0q~Jtkfe#j?>I}g#Yz$(Sg+T%k2G>=$5;`=mFv%7a7NKeoUE1ivABr zXBi+jjznS0l5JUFIoV{h;VcC=%*@Qpj2qZ6Gcz+YGcz+YGjk?P6S&v+<9#KSs-CCk zdiF9NS-qUEfZKAYGFaKJVy}beTE32#vCG=MXboPI_kw3n+L?BNPiH7fFXPL36}vaB z#;fz*v^uW=)g34T%fh_Wc5 zN3eQW?Nln%;ZCK)0NjPy1~{ze8+a+ZwA}~S>P9{K@{)Eb`>6V1 z{{(;97Cj2jBWefyg0L^G%B%6d=GO}_9kA!E@}6pm3bB3 zk5=JT!K&!l4v!$*4w>*6{Ew<*>bw2JZck6?)4DzUPU+*w98;U&vx#r!#q8pCe_DxG z=KbN;kDgG`_BZ>4`euIzzuU*v7SwF!TX<2sm_2}2^( z^5=3PU&Nou=W-E0C>z^N?1S=<+@=mf+rjP1ga@Sw8{0?Vb66gcThvzd#((R#r*Hhz zIxg5AKRxf^{LX*xx1nw6Q~3;TPoc%&V!njGkn{NhZ~?A&KpvD$?AQJqKQ4U@#iJkm z|7dHlHEjd7q3`{pxXKZERBl#V)D!tsF5xfX@IvlKXH$DWJet_YuzFM;lbh6L73IgH z@oAL*8u26CKKPH(vy?xUOZhVJ31+Y0@KU~#^Z0zePd2p++56zv)c%C}kNzjW75$GM zmmAe4bsV0@(U-zy8*h3&m^AL0qQL2Xng(0g3I z^k4a(?U&FO`!hU0`Jerkv=x1gt|<9h&gOIYYdMF{pZhQTX!|QFzxZGMe`$02 z)o)H)(A{#6ENY*U>(qL63fDR*-=hAFJdMmLaIIRWqEY|VkM^6APmns@TOoX%(P_i_fG$aIGl)L13vrCRM)7V{k zPflag5yzU{cr9biR=$moHAU^M;4Zlv`EiI7&^6vnFgxT_yk^4*nRmxPGM6KXToO&8*Rp*el)b5ulClUYc+IQZ9?xx zZxTEwnn`A>+$JZPZF0Mug|3-w7P~2LVSG#8mXp~O_5ge!AIiz7oMbk85B!JzX78c@ z2z=yk@+Pr|cy~@>lMzRm?R*L!Wkw^e@=mK2YL&MdaW*_>u_{tJQLE1>$mVHQp=Ryu1EA zf17vDzYpF==WsK^Oyk3$>3kl$Ca=qRxXN6%-Mi!8^|zybn>QVv)69H!RbG?xQ8SOt zFdO7XIRp9WW(O*_dkfeVc~vez&3v}gyY1iccOt*Tn`zd|4RR*xXPAZTvb-V}qH+P- z<=ygc`@2xN)7$Oc^l$mQk=fHLFi2B&kf75rOzt-QsEci=ak-GL^s zhwyv=jzUZiw{$wa9&Cn~e{^d7Q8x9Op|>e?UjB#PR^ET!BE;M1p1^KH6WJs5K4hu% zKd4UyeF8tp3o-+I((4R*pc!N`=s{+%X^r0hyw=_VZy~r4vs>t&#BRZ9B5UF`_0G#C z&>H!ejfCrC=n+e)Q|SvbC3I0{gj)ukQ4cT!O&j>M_8NO@wd}3Oo3TLuaUQ2w)5tC^SpM@d~iNGpTXxTONNfiG7B6s>nysj>1Wz| zb5PqJYUe#?L)cLE92y1=W6xMt)MU{eyxFMg0JZnB={}~f$%cGZ{Q~vRSx2mP@Lpp4 zg1uye5wq*wrjN;v%51umHw){XppIT=j5~od5i5b6!5N4pOi5E8tnW1d8+Z*p>i(tw z*3|u5Ck2yg+wD)Tu&b;;xyr7wexyIS#)_K~rlD6HKM^xcag5f>QgA3~N|}0IeUHI` zy2QPVpAZ6vWSY3i@Y;!MW7Ze_*I8fE4{-pT`;*e>DrHKWx?Vl682o0MV$dvO!DAt_ zphe7qCvzS5PyLtfL$0$MtPkmnIFMXsSHLUqDvG{YrYJNUoNam-*Zo8PsaZ z7qOqtBDR>7!L>@8GNz7K*XvFCkQ=NwbQ8RZcitd!kzE2WvCH6PxR*7xy*gf5)R!?u z;N8RgaDFVKla2P}iqpqhZ4D|wwU{(%3Wx-lrZI7eg zbGe&D|E|9~Kb!&VJ2a3DA?Miz@B+ICUW8Y9)R!~mO--+s=evn?V(q($brLX%=58T) z_cGs{fou@_=6pvS3Wp(NC^^T@vx25K-VFs&(c2U>g%B&4>Rt`6f~n!v1Z#TbO|MNLvrkYpXlUNn*aB_y7Wy8r?b`Ctph7pClbd{Sx zC)AZtS<#F@&2UoLRPm~Ml}%Nz8d%M%WHf4&tKIlIfgVXtvomZYDo2nirm|PXtAct| zN5&=-SQV_~RrYr4d?vq{?0j~v+bwpRv z4Xlee(HV@Njftp_b|yM6*(;1EVKx!-!E6dVCp&xKzgzFryYQXb31!!{MIF(N)P}l) z-ANBp56*SPUR3VUdv#uu&rE>FD>fAlQ=F;JC&V2(yUw9^KsmvknAH-sMGsO7>PhOu zp`NHOI+HGBn)4AI)1ax&cxM89#zRqTJNk0!?a*&}AFi?&%wzJJnxdBINgANHzGxsi zkL$(NJ_Goyb_{ z1Ut#bqWc7!;k<|63~0Ku6+LnFRwy304YLDq+Yjb4xlJR{o^&9ML}R36X=bxxDZY=KLBy#-G3^cd$PJH^I0V-Xv}r;%tZ+L88Tv~!A`W}}_c zcsGo8#$Yzfc>~v3&`jr$&Tev;Lpq1a3Fb5h^=A0R*GJbqz!2%+K{$nt`mjYxzHTvC~A)AqdJSp zYL4oxCY$*emCeL4WRB`%If$z(RO=q7wkv%y((Hr=QZ(U>2$o&PZ^iW7G^flWKPc6u5KYFo({i>-7e$&^MAOXcUQ|hC3si z80ZSs3{_QB6EoCI#JQ@Xs03ERm8R3cHSTme192W4=F)j|onEh}t7@XUn2x?`VxB55 zDu5M4MX(||rBZ4Xk7IWg5RXE-<<*PBn*>UDZPeCE+aXvifDFLU^L_jUcFYt+}rqUPAOJ^#5>AV7`VYUEn^XUS*Mz7TiR9R6@EKub{ zd9XZOe0a1ZKGcfDQiGi#PAoOV843<{eo<5CRQk$UNLTAMdLbMZ(1oguC@U7iXMy7A zZbdlsABm0LSZXq=qnycf3gToMh4;rIx>B#wi|8u78e9#RMQ~WCJaqp@Jg7DKRSk3o zIlrnw&R}q`6I(4t*CM)@uFxy>VpU3%7K>GBQ3fm{7O6O>|5Yu)>SDTtF4rscZ^*<^ zzo`MvKxc_6DN2bY=vu6nVs#0Pi~MgYuIld$aF$|qiCTvIQo4*T)64a8x>O@#yo?T^ zOY~Ab1exXZhdYT*ra!?S?oW3jokV|{iE5JiX(p*3X0YWbR}HpYHOR8UiO5>v1T|4v z-UK?4THZu-es||O^PKPQWI7l8f%qN0lht?g1970`sn%qm)tdY(2ExZfW)R{Kizx?m z;7+`8bUY>Acsc=`0N-zLo#zl-%L++2PK{S29Iqy*Z|1w13{F;4)Bx*W(Oe9$1|klH z+YoE0MHN#v>PZ;weuG0aG#{Mr^l@xlg?Q2Co0+1bp{d|hHBI%mnu`{qzcm1Hm_?MW zhFP|vAXRYm#?o<=qSyAmy3uYQ=c|b}(-g&3?2v|I)L4wis&Q&KdWTv4to~LD(GMyn z7*=V>!qIAs`r>{??-!`A!@MzcEM;(}USF%2C@%V!-BT2+LALeRjXN zeVxxxKd_(E-*LRrbPRRiz&r=eEbL?TwTg>APzkVvC@Dr-Kjcq25UksSC~#Dy2bH5Nj#V$@;czuVanyJo_lDCEbd2>)ewSlVGurZz!L38o@NldZEx*aJ zSRG>t=(hxI;02;truhX=nD)bYh*^2lLT*K`+Yj*ieL@RRv$y0G`=1NgyoW|`$DH?GPov&fHbX6Tcf z4GvkQ6S(kpf~9Jiaxm(RaY?Zhz4xBQ^H)dTEd@t{4tzL@sxi}?z6z^ogbyRwWj zlZ>Y_Lh-@)>a)xN&+OnE_pM9ewOr9)xf%j8%tX-D>ShV}`$0R_o_#gl*&Fi~d<(~% z=*l58$c*x{v;!IpQ4;kc=)qo_H>L+FyR-CI`y$grU%?ER<&shEYd4pC?Y;ruxH%;W zZ1fUnC^%FNQ!40Ub+r`SWY80CJy=in%0!u-EXuq#RzQMbN(Y^+&Xx{3TV22|s7{A# zM9Xxz&R3ZmSIH%Np{plLi(ItKgG_GlrTfawBVV~u?oVyO=cgW~hN}Q>I_S+_npdVb zx_U8#Oc0o$qt(gEi>^Gf4|`!=nm(xM&GI3WSLTy1+?Q?`w6{7~VbHuJ3{-|e0c7&a0`jT*%q<|FxzF8#7#EO9z=Gft_o@4ce%C+r zBl<)C)aQ9C_8&XX|6}L)W8@#vJboIPR^|os_<8+*WNM64%QW&VYFe|iyfteBp2O?{ zZ^>GLt0Tc`Uta!)DK0N+mFUiQEoqvpH}9E zqGdi@C9i*mpXF`XMR;D|7kP8m0^=5}C3{N0>S+BG{!i!wxQZ~BpW7d6<$}h6f1@)Kt3;Ica)-UL1{RRAj&b#P)V(vmu!Kdb#$&Q}3R(8Lw)eg*oSs_2U zOd$)wxuAcQH)YM(Rd`i;GGmN$4K)|lPE>UI8_zSHmZYx-V)06*v`S`0Ns{hPcYYs7A%@&8hTaz8H7IY$JNJ`Wx~6Xm4#an=spGVgxaRji$X7BiMqgY&Kg=Mn99^ zMRisESWjG~hw7=W(;KuE{9A^t!bAKpZxtTqM|iXF-|#qioSy(s@RNM2$>3-7x58nI z*Z>l(E3_><+k|by{rmvmiLM=Hr%CIl^Vgv7t!@|Y<@Jq(7SDQ8HT@Ag{yG$BCt-lMNJ57Jo^i%!S z1$vRT5BKoBygmHeg}co^erkWWN$sZr)1Z0)YWk}Vs6ic8cbkskZoY?iM5aSHP@Sh2 z=s?sAPynPZasDf~GY?>C)vJJntl30Im` zrYKk>?2Jq&-C4I$ZB=L8R<%>V*!9B(;V*WBFs2;?Y#7F{8-|U*n3%=F>MwRIyIxp7 zECz?7;0m+S6b_4otH5{q4J{n5Ht%#{%vYO^`X;}{JL>l8CfEtF3$E2!chDX6E#4L5 zF1o93t=gy%S8Ei8P~$K*{A1a%?Yd#TusHmSfy>PbQz(2x-_k;1VMJqxcH{6@)Wo)b zwd;g+!-C;k`i>S13n7+3eetkFxXdg!?QykRyghUqyv=v;Zn$Ds-A(_eTB`sqO~Sx7 zh;iWas~yL#9o7j;qPGON)GRXv!gurxEr2V$qwREiy@Pkxt<-<2I~=;{-|Sjp?eI5r z#j#7FzGPS`Tw<1*{9%Fc49yRnrESr(leg77`7W>>W<7LE)k^h%Pj_89Tx^z@(&#D` z_S7v@OVtyrJ#-u0R`23*?V4e&FfOk0o1HJrAD*T8pmQ{yT|KN3#9g!pTLiNuU|As)2z;%DXv zoDbU{_!{($d7$M6IHh}j2xKX&uayrpiXKjSK&_yKeeR0p6z>ZqMF%oQF*?-Bbw z|A4OdP^a(?L5_O>|TJ18(2>PmF(njdc?}8a|`^({`pXb9ma$9A*Ktgr{uFZ>)cE%WtR~ zY0Gb<8|yKs9PN+sEt}Y9?2KWi@C>?6+hhHo!~!jQjDHsSGd4k&<)5=Ngc-wg$egv$ z+v&p$;dx}v*=y`{Vft_lGUx4MWS70$J`Nru$H@+RC&oMNUAApr@>kq8uXq%v7~7_- z)6?(emvwsiWt`GrZ@;wD+wTLG!K|Fq!|w_9M8#2ZjO@0LlD@j1K8jIaeFDzM34;$c z%)H<)IWbYZYDi4gFriJ1jTtcs?L>Adr;p#)FNG`g@yk2i{O(|PzX#X@?nlT`(odg+ z+X-@#Y`1sVmLVpQ?ZA^6$2{jRcuA*})7P(n-tx|2RQK11$q~d;s6R+;1Ehi8Pa0~1aRc2@pM(Eda*k}WH`~#{5Au^l2j36{dhx)z zdB`7eVIJ|vT$%^`A@~sUs&K2~RCPM|9sTp@Jx9)y4faO+JlSY(vM*qKo?Ia7?G1J{ z)Kqm8dZkh3K7YWgBU8<(?zHzi_!m)gfm|f(?De+Bsxp@_zDO>Em%z35I(q|nnQS0y z?6vkWv5)L0$HiW<58OwNiE-|i;A=3>{Tf6EyIB!u7u(GWJ4KxF$d7Y(vR%mSgo-+Q zSRtn{SlHRkj*9(+_(#Pt#1mpS*#qt&d%?Z%9qW$u$N6L3=-?+A>yASl>tf_jfaiF3 zg8Mo666|0_onp=oR?I05?!;^_E8r9a3p$0sLb%cx7v26u)K73Hx}Sp2!4Yv(5dR2d z`zLYT6Jk3n?v!x0vmJ>0;INk+7Dt5bABL!ZO6(%L$thHx6rI$NO#kQSNBO z$?k{XV=x(RliUL=pOfD?0Jr_@pg1J%@-yf?Ek?Sd+&2D5sI5N*^^@Hx?)%_FaFFG7 z@;L|5b%32kI`?L8x_0`E+KzWToRkeW^x(4Brc1MWE0sSHjs_rMr4QaePX{D z&i9Ia;6BW&(qV2DT9poUhq-U9jcgNpYi(ki**lEiTGi+fcc@zptEk}n@p^~id!fxx zJ`A%Fe2>@*?uA!nS_Mv(X?wrAQ<+wGYJkJs;m8bk+xu^5Z3M4GE7KZIbzHX^txgBKL)_Qa8}z=0wy+QAeQ$lR*0T+4Fb|9| zgZU7|QE(W^NAX=^x2TBznodPp)5!)_!mI`zPJA=3}FM>gQFybKoB6t~$<~zkMF&ftz#cRU32CYd4x`W(T zR+P1keS+IZYak!QUj}3N4zW{=LH%f6o>rjQom!}@No&yo?m+i5DnD7Dtu<^d8^8ym zegO0;7|XYd9bznc$MACK$>EfvP6s}`+I`?~|&FX;MgeX&-t)$EJ4nyq2|`2hYZ z=nq8&()^fIj)u+APK5l(<)uWU6Cb3yeLd`@znQs)E#AIY9@eUmCP0<0F$y~C2TrkP{ z@V*%L<^A|#QHCxOi$y6~nl2WlX&L%hJ++=$kJU5lk$MO|w;rlTh)>iL>nZpYYd#Zj z@}d4=;`h79uVc zC21+T6!|6MfqHJeupX!v)=TgqW>3{4>oNG)!u9brJW<&8%VxQn_2zxJ#$!SpJpv!W%Vi#$?YgXo+Y_Aa_HYe+0%llG-iyx@^TiUj91hFGa#5U?pfAw-T)j{a ztcRAvT-MVKQE6Dndhninu9%1VxzJK@DO<)?h+?!jU4h=^A_i(g7K3%?J@_0kS1e;I zvARO66h&z<`VyWm)Jt{Gx^KNy_pJvOV-EZo)XRN^{7Xd{W4&Ao^>$;jZoE5>3AY$* zwwMFA+0b&f3T`XKDp8mgp{qm@T9mHFc$HW!3emzeO5L^YSy6C%rG8;uc{lzGd}6X# ztTXSzW3ev0E7%p;HK<=LUZXxry;gUuyVe_Z+qwhZv0kg#tP}6dW1}k;TPq6ELUb+a z*N9({kImw+j=U3(gYmEIJ?)6md)k3_wn9hxm_!M~=w0;l@)3e8 zs=5YVL;ofBvYU_I##L^)Rb*9p!>Ws}I`Sg2`RPSBKP>=W!t9RwjeZBeqdFZN(gx{* zE9$DMjGmiTWmyHW9(wD_dUA@GDlWJe-2(Kk8%@7~-_Th}R+cxdO3*E+& z5F5a!zHA6K04It`;=cQZex>(Of6vW``V2wF;DWlSG6ombCDlld7ZXGyIYCSWCyIvh zf%}PmrVrfD^b7a}otaRdF?fjl12;3qnS#v0d38ZGMsFke2>FNZBljcyL?62!=tuA) zedHc+-_sBD05Xr=I^>*t-mMGPA$7@F_nf=kDJRRz?M``F0jwamITiIEK?Pk={~r7i z)Fx}iI#HX{A?MxNP(fOo6vR(LJ@nQk^~h=Wj9ZVKanHJ2or?0dwbi+epP#MpsVKKP z+Yq-pZ`51016RQ{bOm^qhyDcr4E_o#;VKn%C7mSrJ=o%Gb>6C-sNCV~bjr$dvKFaL z)`|MKN%|zb7G@2|DfhJ70A2OTW@igL zH$(5hcj}DV1?Qd4E~m6CBX>DvWLa4jzJCX0_1{5KupDMp;9ptSAT`Mt(U6>UPq_`@ z*???vHaln3ZuFv4m(@vws;I1@tLlV7qM$mdf%@vuSa7TuCmN9x?n$>192%01=sc@7 zI%m~6a1&;G;IrG=cd)zx%@AYss$9CuH+jnUhPY;ZO@=hR-Oge)odIwfT( zu$0{6R3p{NI8hz-)pT_oFNhyh*YSe{K~+)>`Kr)((F8t?NfUC+J?^e|Ho#{+bYAU) z+g_&zx~l6MI&Kgz*pJLUXTMWimXJ-!5%;LulpJ-Bfydk?q$X-==w{@wd&F&q)u!Zt zQ%n|@2T;G?sil7l;s&))Q&azonr7r6Ru4D_ouaastc}%Ly0(rJ{1!APhup(%bJYAx zT9AY8A-4rG%}FtGz&+>|L#72;=2szA$#QU+zud1(s*vkuopa4xH*1}B&S!p5GGF~k8mmx0o$BV{tsoz*Okt_U4 zq%v6n|K)UWhc`4vb-av6?UgUcps5DUD5*)2HVG`GwuXSFlT8}60Sz27>E}K}v1k{iBCU}K(VZG2_WN-KT?j0sCwLdkMe}QL7hQMEU9-$t?%XxYofXakf1zJkE`W;2N$8sB&G#4hMdW;_ zs9XoY9@PAynH&pet@p~=7Cx4EO8!~CC*Z3D)Ljjsa{^4PjB=~l2T+Nx;FR^QS-oT z@=K7CWE1im{mp)HQi5zoW|Kd`FGh-!3CL{rU1y#@-}juk{ycCV=C^~h=A5}5oHMtA z3~G=!*vqH}dV|10UIyjhr{JLDIIc6_cknZD2;=#FQOTV-{#>8K$8+ukXUti12R^rh z^eTfI>}65|yn*0AxZH&Ed2&?g!eL?$7Wwx|CzVWf4dauLM_vJo+Ij9|RABT8H;2lpdV0OQ(3#>-^+VJc=SgtH95qi+^Ek+b z)toAq>hAUMa;Y9(PcMcu*`MOaKz-=sMn0E%8XPu9%u{qd31VV3h7;47<7y!QmPyxr%0hvs`;pyXJ;2V zkjoCG0#m7fR4%OM6uCq)l^o;bDutSB=haiax%NE!QZU!P9OTt=F}fTqfWv%yfqfyk z7!-GZvWKR)TLQ5Zu2s@4NbkH{|;^cD~WMH2P9Dky$ef2if?T4q|A~MOMJAz$&u*ZUHwA$sm3uaY#CmUc@2kMFtT? zrr1;MC^FTa22QhIk@D;?-uLBM1@x7N3W5dQ!=@4(DzZu}uba=U#PYfM-Pq(;_{D}Y zir?TFhrA@YRUY+{boX+D)9mT?OY#cwC7Et__g>>#QKTFz&z=V5pl3m4xK(1YNNkc( z#DX%3xbXRn#3gA&T8z_*bm9eE^QbpuvOUFq1Bch-7ZQtP62Cy1!OS9yD9g&RXF*x$ zc~AwOm01;*$Ia`;gHK%Y9Q}FKbCOpj0AFDCmQ1oI+i&6dhQx$l7Ey*B362J3*z@2B zSQfD=%kAcItHP%Wiw~c8BtA(k(uim9OQ4=X3DrCJye03*M0=85njH;}1*KUT#A@iR z%BrzkZf-XLy5f@rVkE^%x)Gp7g(3&!aFpxd)X_&E_s)|;;aPgCjw%~bp41-)6?|>@(|;P zn-}ArZ*IW3_|5VF-Z7Ckjc7;C@LoFqT(-b z3TCtPJ#wGSg8xi?9{sEB^WFu-Yw)@1UGs{tqHHjF2Z>2~vi?iVM*S>3Ti+%3$T{!4 zx7t4Ejj%_8tL+i?b<|(;u6u=95jI3{;*%lh9V{m5N$8yj{SE#tl8QNSn62mN+vE$a;pB{W77k~iQQ#|GVwb}$j9qsA_*U($Lb_-OUz@)nDVq20~&3|kfZG{B$hnxo$zAG z6W&SiB))N9rzLHSJ zK#UEySkks);=gjX^$+T8tB2?b_7uIqUZOWR48P;pRvI>p-Z8Q`Cu#pen5A0$5XC-^6^$RB*99;N@_qx5KSG`=z;zmjNTWQh1Ht{z+dDvx=` zy_75!d@{l(1Ix%dicTUPkIyagCmjCZfs7_sNFWVjAg_?CBo4ZMm2u<|@2D3?9`%lS zDOgH4WMUmeN0A8*8ChKP6B3sbVuSH8`-_jzBlTbK{F7@L$gAWxIK+{^@wnV3fAisb zg#H^ffAQoj1>7>jEfdSk+KKieGixt8h`92wcf^Z}uHU4R8V(A&Mv}4QsLz7R%q$N7 z4Q_EDN|N$ndbmys=fAl`$2B6M>m(k0;>vjPkayTihMJ^286T>L>8x&~HA@GnFPbTMs^$?w$579%xp*k7QhWe~58*3xliUg>SFaKsq(fb$s z8_dpHi#8%VRlYhLqP(i02I^YK z)Ks+;la73f?v~;y)JnWZ%{$QWkiQopkHKrBrk1L$Y)NHpMJ1C@Q1_pBf{s?=11jHx z0XMvyDi7y!&>(P-9<0l%a%!-ygWlTeF*^PekD=D$BkDhZng{$7_)*kFO&wKN5oybM zU|m%Y9|cL|XCb-bpM~NY)TsV~%x6&_tMycU^+Wu`_@}UB1B~mdhU&ZcAsS-bK;^@@ zA^1&v7pJU;;*mIQJrEDUhnO!SWmH+U7+gdalhUe;I%z$|*LKo6Wjz8P;cGowH)=!$WiMUDvv^O*<3P@a6T9EL7xkL z!MY>viVNsHZ>=E3RB^Qez01iFD=v%2j#x(#=a9KX@QcL^%=TLc5Z9q*Em=njsDf%ARuZ#)P!cc+{yVUqsU6_Ev1(IPKa^N`HsinuB=W95p- zN2VZ`56Vk2k*ngG$V9G*>tJTg@{`F}&kyAz8L@s{6d;q3D*)vu1<6Fr3PJ@)Au<88 zLQp|cn2g7)FjNQ}hglJ@FewTa0mmXPx6+dgU>$WLAU!kkn)Wa$Bth&^Bu=GHbw83C&Bgx5ZBi3K! zZ}|UBl18qJD-gVM$6`DSGYd5Y%!J=bEbBFXBeARrxTj-T#c==8vJT)bInLt5-*POg z1Ak8~YXkl+4r2F)Wv#&;Bg;yMJ#dya2Rk(_D>?QPTUHX89KBE6Bsf!k2%aOdtR;BP z4OcNsv}INDGNEP$o^Q9T8#sT#vKry65X&lu6KyQ(h*J*!N$ewzWhKB#c9vBuNI-3? zL_qPq>1LM*Y%8hL&Bjv*4Ueq+vyH=cY0u#P>KKaY+fgFf?*Dvl18l@Sm}vzX{)YZ?k|OiB^MPe>GCJ>BMkf>a0r4X;A8>ywlatwb z$1>x@b}(t+u)_J&2yI*!~C%j$eV z{xgf*7mI~Ex3Tc*zOpn?Cr(I2Z5_QUxkUgW5Td zlNcmMC-D04Sz4%gjqypuOUPfuSrI<|x^Rg_{z7mW<4ZV^!pGq{uZ$Ur+&P^ z9;N5lYqT7C0Y=XLScMZqo`cV^wi>66JOiI$z6@)xz~zWbF^U4C@YP3ly1c?Js>mrP zYoOKGeX|t#wJdT@%35d*_J}>kXdQcmxE_q`7kh}ffjvOn0IkQqw)>cEgf?I&UF2k% zP0)StKC+vU*@Rtek+Wg8KzG5r$Zkbu3)==p_M_cG9Lgel0f$0EaQewXb_hI#+%RY; z&ZRiQj)IXLN|94ej^JFD1E?Af4a2z?gOMMB%y68a5!p>N5LyBb!fYh+Bf$NL1CU#S z6J+*bHVPVv6K?jfz2IKtMnj`;lFlBC#$vzf9uT`lan4R;zv?(>H@F+w@z@u-6WodU z1QyvPIsqDw6Kl3(GzpBHVH4Q_+KA0(3-BD+e2ki~d5BG*#(0{i5%LY8g?I{W9mj!oT#Q%sFEY*W)ZJ{1nzLDmEx_hr zELu^TO;!yo>`oVQ5&2MH3f{EP1P3THh4yG zGDhw2$|mDpQ6Jpx$N4p2Vi^Fn>WzId9fAnSpuf=~h64a$p5 zA!G{TZcyZ@uG~;PFb`&hS$C`yh6>>xW^Uw*ux`i|fePb}T^H6B?224bs0i*UcEPAP z7`e098L6du_T_l?Fe?ntRz$d_jB7LR|+bL`@-!pDg#FDEJvQKO@Mp1weWBM z$UWSIPy+lLzXnF}k*y6TKunB#&(*=|SV;^e!tX1!SsgHP2R8ECNNxPPK5~aT36vPW z{Y37@Mt-ZQi{JUHA{+UQC>QPsRKe^I=y%*NsDja-EOKxCFYr&W65`+BUtr{K14+Ti zU5Uuw861g{ap$EhMk(={%7SGv|BO91S;5FXj>s;Y2(z*5 z>?<-~u!|=%%Yt#_zDZ=aO?EKyTVyoyU$NKbBhA4+Ksmw4Z;RiMkH(&($eo?YUYy_9 zcZ|Pb?@~sViTwb-V@FlwKGaX}2liE^XBn7VU#{Ipt z*lU&sBZ_-sslmuSKZg5S|A7Bs?qJNYhc9xk%Y__vk^X|6a2N1wTP$`SiVenQzk(Mq zyF_EMU%+2bcbUduG1+BgF5wxb^YmAC4vNFB(8vzID_FgZ=cUfkIP47c9?xB!MZ8KQ zI|Z+z<_ew^jO;SJhRjtwaTwXZcpaH*c)C$zbb~6U*-h{Up2d_*v0LCxJdqjM-+7xx zc4*$l_!gcijqHWILnFH;?;w90JC-J_AcjrTCVi%)5YqOb9(3v2(+*YpiO`5_9k zb@UbDYOK7$3H@*IRN5-&9k?2^^;lg8zMwC`mzZt9cs=+WaV6@`fU6K!AfCZzSv<$u zCU7J83~@8K34DsU1>6iircb~pm~F*)3qE7yF-F_)obqFQLdZkJ?a(%SO3HmaCA{PR zPaf|;emg#MJgWdvp?a4NtEj7QO9SQ!P4#MuDDkr@V^ z!np;u?C8 z@!&Y{06tk~Jah=BP#nN$B0kmU0C)iNNf=KA_u>mHyD^%ESGF7H8ZO599nEkC;$oaxxP&eRm*P~8rpPV9d5VjWZw~#7QxzA` zh2TQuT0qTlqTw>S9Bhi%7;!nyYg~Y}Mwl%Jm*cgyLZ&4+kIo0@WA-1$t#Ib$9Gv#j z8kz^rL$(bvt#N|p9E{rHG@3a$t#dX;?QlxWEN~WP?J;imKa$QeK&qqZ!dIrR&J`d8 zcXxMpcXxMp4<00FaCdiicL{_fknlo+ySpXuJ-y$LI^A7eU9+>hvpc(8bq?&J^Wb{v zjV%Bd;O&E_H~gn_8T(>=s6QQ{j|4~Rqo^1y1D0ZxI7%N4j)q0FEHP!MS{=cxoIadU z))f8-{s^OJ2}X%ycqZl9m6fx@7>na;O{MJ*`cQBvz6w}*Dt3QhRtc8bAHW}2S7u%b z9L!h+l$Ftg7^{M^K3ekQRs&^4bAOmAF|L)JM1}Lk^`!Uu8Yk++jQ|Qg~=6Z6* z=CGS5kHO}83q2+N6rijcPl+|tQ!!5o>v=MElVUAlJx>~gEvX<)f)&?O6O#&*)#{1y z71z_~vPwP;));KeURpe9^mMwc@=u2~1RLT_k0+g;fsTawV13pZ=`5%R)?=NC?tr>r zUDlbY?XLsYVV#AF{n}t{)>(N@wZK}e|I-TTh4p{6!g>+#KgKWc!xquMY6bN|U?C#D zG5-n{&#lT`bH&xH8=L7SxqhgA# z;ZfoG&8_DF^RUt}4Q}Av%!HncQD6}mj&q=cVPLtyTzE}92JFn)87<6&(>WU}8$&jc z=adc1#`>!Ey&eyYr^na-(ynUp^*^x$;9rdYWA`d7<_YwK`V~0J6X@6Q{14v!xcc|{ zWp)yR3H3x^BA&^0{MW!Z`gi(u?K>TgX&BW%q5u$w^*`X>U~D~(egpgmeS=tfZ2cy9 z1C@gi4(?mvO%xRZJ=AZ5w@_p7;03>}`Ffz=VSXF+2#?ua{%IZ6?`lyvyzeo;i|&QX z?7rscuD+e_tT*&yz0ux+Z?$)HTx|z;;@JVdX57m9J@{Vx0B&QoOMAu6E^H^=SCU~~ zc4U2^Bkd(SyRlvL4{pJ~2hVQs1>;_D5BQvMANnEB!RM^^YfoA2$M(@#_=ME~Y(M>l zkI*wYh&=(H;5~%rAYGIXP!2haJpv!$J%Z=3c9iGz0DQoDs&Z(QkwoQQ1(C$XB&uDp{!&o}|!W^VP*v6_KR zr#j#)tC`pg>JCn8XTUS~W??g_YdD2(Ha3e|j8n|!(w}<@JjHq*U9l&?6Zqy~bE!u; zhHpMLk6M;v%og&Tj)BKmccF@;Gq_e;2g;g~uFSh=o$#&)*J~Rr4$9h{9@uJh)mAd=1@;7GJy3737r30U57--A z#@H9^11@Fk2lfSJl~aGPAGnxt0N5Xt6-EQW0pLQ$3h45U0mo=#!Le{hSHx2Rp5U?C zIIuipS;leTICQ%zq5JnE_#<&;SpNk6#B(Ua{&?83N3mZStE832*B*B55!y&_Bs*2G z%J6oNU{*~VhMrz0Z*@G?U??BTSOcpLKl%{V8f#)h!J&9-;i(Cu`4DEc(NY`& zv-n_Uby?RX9;*l&vtLv!}iW9iVpNP$0t)(l?;EIkSjO<85cGN2vNgjFUiBiNW# zW-t?48I74`L4%+%S{aR)Wkoxn5sDcNnPo!@pdpGN4VYzz&%Xi6BK4W&fSZ;wqqn%2Rvav@DfBlNW2T`WQcROQ#>K(nsCwvlG_VNcS2{>bfF;oL_^Osf$s>Ya z2MaU)M~7-Ddb%I9I_Vh$bid6-2}e#t|hdM-u}i)wz1PK%Gn)BaWyX^Fwa+I8v_5^9OGfAIXx zeQ#nq{AEQ#V(ovb>_L`yz)7?lY62}Gn2@-us_YKF%3X3&?WP)EO8_Qd?=MyM3(Gt2 zWZEq?o)#aB&)#iSGC15;CG)~<{I{qUiOcLRcn6eB5cgEcI&qKrT`FbbFuSixMvD7t zY%PxVfcbrDfFvixLsc?KJjC;WilTtoV^y*{JZAogzQ&LAFz%uD=Oew3ADHb`WhKxq z)}O%Lj60cq26r*;V|Oq3j&TRxFQB}^-@*Q8`Z(XQx1ai^cXZ(Hz<+@Ge((+BLGS?h zn(+{L5PYe=0$;H@%={4eg7FA=n4aAi%#Kn^_JS_nr&NR;!=8iB@gB!>j85jK%uZ09 z^^_jzC(KUr{GM=^^E(~IGqCC0@%+wgCSA+FbD#4E{ln9+D={}cf5hDJT;WdWHzH=K zml&twy8_CN;@NoQJ<_j?Q&?{Yr!vmLGaJ0fI2W7)USOOD&IQlYVLlJLz#Z3lW(&ai z;5o*Hbhw`b&#_)acljCc48BF!LT(37;aiL?;+F9gv!yXz<4c(@ffaI-x*6OIOJq-V zBdeZR4;cP7t6RYCj9r;+1-mi!B1SS1t*JxFuchDmWHC*=pE$D#t70uYgSkC0k>4cB|3#P=R?3=GDP5j5XCC8EaxS=mYqXSuJ&x zIvO0!sy6dlbS;cztb^62H(~^y~0CPpx;rw&txgTqJ34c<;* zC!UGC&FaX_UTgMJvntQ+Un^Ewu*}>Lwq%tR%fek^OJ>>B7L3_JdF$AmF$XAbCS_Mr z4y-vhnX>CBCzgYo%qGlo)7{eqY{EJZy*Z7+#;o%)mp88s83p&IrNC0$lL{;#x6B?^7%Ys}$Kz2~DDR>J%%^@(-a?01K#iWf zd5(pJDm7B9Vq>w?TS{{ErgBS3rY2W!E3%&Qwvv=u$=i5t(Q|f_{To;cFol{@{Rdx4 z^$wA@>4f`-`QKP7P*zFZ#eawX%f!@lUT0rX?3cZKtE}f$ZsV=>b=N^5l37I`m z5~vB)hu{NxSY<`*Bk&>JwDHvV>SOQ`9k;TU_X+rzj$2tp`$Um7xlfrtp(9q-$vy+0 za#t6J*>fc}wXO%0e`D@-zc3zDJ}Y0qFWl(LTj77ff9Vt6i+zo`E&h+&+)qRu!VYq; z{FUy)J=pb_JLa#-VdVq;(uc86;3wjCvvZwW)(@f#0C8SFIG8_!vt#m;a;{1^A? zbCf?B=U}tBC%(dJE;c9T7WpbS%2&BzpBZ!8J`>+n?vMXaE`yheorlehxqH6Gjq)F? zr^npCPsewS+vVT!Ex_h;bNm~th1de_wlA?-ge_DSE5EW@j4k4({35F**kbO^FR)sQ zEm4+H_i_Qez9C(g(A8z1#gIl?w?}Keu`ZDhW-&=3y zy|5kN4(`2sGVX-wa5K05{jjazR-${bvlHCOt$2@^oALg{^n)j_2hVT-^ZuZ$As7e_ z05>uY0tbQ{7zcxc!1atnz`@{JWgWPV)ep>vz*V`H+0dBUhhgAQcsy58(J(Bg>R~wZ zVaf<_IJlCrhB8H|4o*@ggOgd+WL`t5hIa}$MVYEp#eN2>G1h{SbRsyBs9IP}r3!n~ zK*{)5g{YsE+QigSDzoaY)KSJOKY>5ttAo{6>f))R)PtXOJUE_pePt}G`dB@s0erAy zz%lq5VD*)Tcp4~;V0Qfx{E>BI*jYz|qggj$-WVLo*c5C6j$q89bW%Elot4Z=R;44W ztXLK$6P_+$X2y)nx`LS)vnd^j%7$fCGT`k7W@OB+v}Y$fmQBf_v{l-H?eOKmvMV|9 z ziUpQqbU+&{%V^>)50+OdC@vlcEUlCQ%dj%osQ^|`DpC*7jjw^m*I+tm#CS5`(^&5Y z)AI~9X4k=rN+qxoK8-Wo6+yhFM9J(b5muVwDWzC>SX4=ePg8t65OOLd83WJK21r*NJT83SYT1cIACnB2xCh2H6;b3rhJDd4p^8m zIX-G88D)*ib6%q=J8{7geC<_c--F*P@xXXWd@#O}08F4H1QRNWz(h)7FtL&ZOrj(O zlaf*86)^%VOg@#bLqV{hQV1-BPbES=;#s0pzD5PWri=<7g9^r0pM!b%y`?A(`38a|$q5eRZ#6|($ls%ia+JTb73DtvOHdR? zzYk{Re_M)DlmBulN?-nmrzmsz-=v}(a_^xiJ-O9U zs5a>d?&U5{q2@%^ik#0xaHK8=G+WwRNyoR<8$AnQE3w&{8fKT#mjpB z|F2O$vmR{Cf0#9;IRB5;sER2Lenj0-Q~uz8Vj6Wge}EJCuZyO%=YJHMQkuW$H6=NJ z|5DScCI|mg|E1PtJAaAD%C+raXWr#%N_pNBQbo%|&2^A)8of_ajdud&Y8My};oU00H0$zr|_^qB7qT^T{wLM%{zpN(+jci1TABb`x> z{Ei$>7egFnH1ko;XeZ#ibeQuUIfgmI@ejkkQ+{;h_xF$Nj;2z37+;VvPL%KeF^+r< zjA8dj>bQsEAB%qsmEAuuALqEdUdG`W>x_5gYk0gPU$NuykE5>MW;Vf*ujvVne6>%& zBP-`kW?v0i)BeqnRqo%Ie>IB5ykg|*B(nAlR zUuQ*PUVs0>p*_g?7aQ!TrmRj^Ijfi@VqRe-I8{96)x|5-lojk6G4NxUm;*X2{nPKRejf&4?+h z#|y;#bdj$#e#+p9n8K75;KGy@;Q3>I4#}U0{5--h%zQCF;qviQlBaIU%54+B0n4))Ld(9EcPQbS%0wrDosXZI3DCpMrzE!J z&+Ej*C$i^zZ()<3Pux8EPu{~0J;(b1Tej?Kd2b}KbMg~DiJgm|@JTq87$w>S_CzN> zHi=%9x13zyy@C08w)YXNlXfRsrMYF<)!$S zpr0!1pW~n;+to=$OiFv1_Y5}XWyCD?QsYTwr?xZmTXi}9Wpsi(gB=lTGlN;d1UeB=qoO}T zYFFvX>_B!3%noD^!fbYD1#|Gs24!DB%b4G}^7nK(rK}kXE!uKmS+hJ?4h&JAEn~(; zZMF>GX|`F$EX%5l8OQGCw2t{5-I|lFVt%ie2jy?-3Y;o$Rxo|kU@Mpbda|YYK6T8} zoVGy+uJbmWmG2|u@A2j_zrmZw{9cyt68L@2*$QS`cICSa`5V6!=Uh|1SE!^^Vz;7M z$@I{KEoqj*UlPXjM@C6z4-NTSsuI7e$(<7q<_SmRGOl7l*>7d+N#dOhxEpC=D9~<)hS4O3n`NUY^6=VIx zC}tLCtZLdQy;dc@irFaUeO4pht7TN?@#u4dd4a6GpBKc`-V<5XtPWNKEtFp8vpX-S z!MwUzgBP_$Wu|=hMHM3Nyr@Ft9T`=KykDaVk#}}fA@YunDn#DPQH97mH>wbMw?hpg z?`RZ$7L@`^lS5%v8kFx(t1?zmez)rL4)ZtbcS~Xe-eFcU3Y$gDN=6a0C|K02XdH`< z4UR^SMaQ6Tbty)1^%8vD4V6n)CMAu1iCH7&jd(Bl2ibnNjz^_x)p6pFMJto7l5qs( z&9T7|Y#jZo25|mvSS2%Uqx?(@RHw&26 z$ySXn-?GLiuM9TYyUN+WtgBW{{&u)()#5LOGvqlPJ#QIkxt@pj*|2LEdCh!g4I`hK zAIwjdv(b?#bDbsfO!R-8y=t9D| zo{Nq^rRy9S&PK1Zd(FCT$-jH9TkT*SG4 z9VO^2z8;jMQ@C@u2NllF;a*fVJCmmq4B8!0LhXS41Ybu9;{Fbb(>weZITi+8!rka> zcHvZKc(i{)A5U^_{{-_!aYOQN6s3pvpFnmTcMW%k6kA1#QELs0B*S z?TNunPTc?t(o1_YC`2D__i!u9lHJ2?s91IjMK{~+QAm^CglrZdi3X^nKo8Q9L#8>itgPtQD^k;X9X8fF?JE&FMVbA0Ed zVRp{SU`X!q3`C|kQWI6fOpVn9YnrvpRQPI{8I2RLg=aJ*S9wO_GZ>kS<8Xjy!k^Jd zX`~`1C6?X19ps}Y_jZt<9^Tu0w6}tu;U=^!dxo3QzU;}z+#~#*k98=F7gCq)cRuPL zg3M&gWTY^%n>oxBMh-J4n37d;d^yc5>}EEy7)N3M&SD&cAv`PdEJiZ+a+%5ao~*+> zIjcK7`fa#G^3d~pC&){WaIbI!I*h%-ji@E|;v?x9{>Ebt3$l?RtC7t(0Fq@Ix zkj&oMjl=MP-zCGHpf_iGg*gn#)trOf>_$%JIY7xBoeRuqMy8xfYQ{ta!)rqV|Wpg4UvGItLmjZdm z{A(~ul}y^Bh(`}jBs1z5RmhVJtjZ|=|JytqjB-SefO26?KB(VQKnRu*;W z*sn|#bRAAFTuk-$g@ zCNvU(iHsWJx%LYT9?yBKXWEadoXJtMbKk*e%^#!Kxy{2nhk`$DTtd@V6nl|0^Ki5#O= z5P6KdK?Q2ka~l<~JjOk3Jqnw$USNH62!C_73SW`or8bUJW8t2SXT&$^kf$~^?RNuM zCa7w^8@$%e!3y%4$X8l9ctGw4<=DR$P^)glGwO1xju@{>e(&+*8K=I{&cgfghEuP# zdLpjzy-|`Hd`o78ZW#@83lc3J09F_aY^74cVqbzO2|m%?g;rCC)9 zuTvvZDU{VAm58qh(|Rd(OJa3kU%!sGawzLgDu=SZqy*l&FsGMftP)<;{-;%8w=xXr zl54s+J9Wc$R%yBw+F51jQ)r7uy~MKgDHzm<4^RzkpxU08cBsO)waSS$*!{r5Z&F>} zk6R&2$eSS{26FEsI5$x3V3nd9q64SeqY!@|=8)E$z8^%WEFYvsu)*M9?t^SHSfZ8n z0EUoO#6Ac*a<+rj(JDcQMMtY79TqxO=|fZV4+4mGSz=!!nvXSqZ=qG~9sb*hH4ey1v*jsNG0uNQXaY$vM)3i8K;7TAd( z$|;u`{NCJ%HD~8U&>TA%bg_!j8`6dN&X&h+lnVV`+?_SEnp-D>uIzTPx>`l)EAjDr zpuCf-7Rm~sYT*?sgR1c{RE6bTvd2rV_Il{Q7okg~8>hNj0r5Uv0zJ6P>uwdIm!-Q^ znBJD|#B{Sl`~kfM-MI&>PR?p!4`RBb_Fj;_mRR^hP~HvpvMbRdxy)VMEFj~u#-0zaFu5j4N{2J+q60GF9Sxn?2 zG~1f-Oc$UH*UVZFJsH3pLcC<0lU(jKI8y|y$=KQam;Q>*ob80#YezD5z`jM6L>r;r zzJzRxqjfk{+nXPiY&`SHeJYTwbVb50ob8OVt7N=sZ+_#C`1a)Z7MX_z-05H*_CZ@3 zmAdUq$+jd~jWb2VYF<%3tCDf92w0z2Z#7Te57zZ0GkjehtB%(W^;ku;!&FeEbE7Md z(gh9J&vc0_i`GZ&eOa`D)evk*_PJ46nKc)kxDTMLbgD!HcMoNQ$DB-?y_PSx|~kngfK2df@-C$byLt{>sCkt}AN)hbvQ zwE^+!S4Hbsb*)C8OvzxgI$8@2_tnwbXuhu|a#gf3k&RG>m3=(DiRopoiPl8JeGQSTqfI=?PTz!> z#$F%uP2?>qv2Tf68?Axb`&uH`M4J-R#9N1FZM2yuIqjR_Y3hxQR<~+cWAU#;drJ1q zol~cy1b0rI5uF*8x9KyZ`83Hymrs+Nb@{Z4US6t=TAH%vs0A9bXVh8In&BDZW<}*) z`^@NhGMrQMXqCKfU^g|E$it~ho~#S02=mfXPA|b)najzrj5?-f=)f-5nxiC}pU27< zQ!f%r}eO}EZ3XYOOGPC@TPJg|ZSQjwnb5S=AzW@D@=W)fyJ2)~Eq5(%PUQypjyE z_Npn0u@}i8YY?WQ2Um!ASr;Rj>rPTRkUh*v9ZMXM6MGq1NM%)9b0O9yT*cXyRCF~# zN%mLH%8G_5=*ku5tgN^x4U63g&gTeaZ3QF$L4Fy@fxQA>MP5f%b9NOKVU5s%U9B}n zLzY^JsH~WngyP#JbutQcvR3GIWDPN^wd1N(6OdIKIl?03mz6#xVYe%ym4e;wH%?tr zvl0C!BCCyFM~bp5YlTX{N_UKEkDTFJtsyG0Yst0-=J-ibS=liGow(oCi73q#BeEzp za1GFtT}R|v?GN=Q6yp9M=66|vBmIGfx`VaZCb6jmncyQ)W| z?n8AtF>-}wDbUz>Yt7f*U<<$n+%J5#W>V$&narQ8dJ$OzRF4dG zWBNb}!`P95YP3|GO^MRR8*8B^8A58CU#uC_Nq*t%XRAJ^>e00#tBdMKWJOVGPNlNo z^PsA&3YiLfRj?wU_Qn8z| z+k~DUS(DWaY|0(W4rYZTvL`kg0l`J2U`6I5? z#3{yWpb3h@6(dcYN|9oy4_Bl+seV-Qfz&6WUUWBkb{V^kr>Ju5FrK6LvBTKO*qofr zU=pQm?=8t6vQevrZPFS>B|}I<9=$YeS&PRD*8Yo8&RMkZ)Au!&mZsN@o9OtwZbinb}WCQ->T(gc6wXd9;_{b+5-)7m*; z+(%jCfFX4{4v=lXQ9UXvktMsxM6E56ZBXcy6{Gb~(oLxyB>sR=Ejo!>=4$YbOwyW0 zC9g=+sN^JR%A+)iw&PS=r=3%r{RRA$4jYN&D(Q%)1G=fQqplO! z5uMT^%*s23>8R^!Y%n$&4`TF)@5d+<-;X|E?1sOqA*)fVL>ppNquudzGrAk=8N0Bz z5!`5OG9GgFL9{V3vW``9kK98`IF)uUM!EQ2^giRgXa@L3?nP7anrXo2MYUyZYt?82 ztQuG?I$3)ZqdxqIY!9PN$Rq1yCDTX~O|qKE`d8Jik7=NW?nY-Gf0NM}+idjUqv{T> zW4z1bXSD7_@5W$8I85$DB{Rw67`5WZF>1w+d8|j#p2YVsdKzmPJCSKKxY^hOZZWnR zO?mVtF}1e3-4WkbL)O~rc3tfz${lr?-L!gfwx`j{Si^WbdM9dGPk5Ba(Po-tK50gV zrrNFOZTz<|8zaYc&Xe+G@j3})*)l%z6WM8A7v4Zhs zv=U0hFJttJUlRW!+8=*Eqrb77v9(qjHkH<#ZKbu*O2LKF22X2k0K5H-0md@MSJ8^7 z*1jUoOZc-ZGJ6xPfSTX9>wFKNDSciIOY6q1(ufYkzPX?LvIJmM@=+$AIZ3~__k&jMM6{+xV;Z~xa zzc$SCON|BW&PTIdGR!X!l3{*`*UV^c3?ai{^xvn7lF?f5$uBi(xy$&@sKsoV(ULqZ z+{x^fLgRc2<3chl5I=ZLjb_FVWEkSLBBmwG^A+egSj6r^bloM}{30RQ=7$pb16p#8 zjV8uWuZhvrXia1*x3ycIE{0)VBcrh~jNPH$Vi>Xih%V;rA~d~!XSO7UMZ67>t=%@R z>~$DU{4j4R{w1hhONR4h;8OIZCFl7t=F7yq$OIJF=S3!>^FB8+34Qjt^iWR{E79(# z;jYALx;dj=P?5_8=8Ue!v&vcRREM2@4n5bC#T=|ubWWrcua@~_n}hq zat9bWqFqsr%YlYocQ7Zb+|f>Gz~zp1Mma7wnR7*FM`ZuPZ2Gj@Xv>`e#z14avx0Gr zQx!J&HBL2{=hyJKtDOar@hGz|i2Q^W`~n_venj#oclYv;Gk0`WMD{z(qT{=*w#*r5 z3^JCX$1%`YOP)2(Le4ITWFxwVmo3_Z?>5Pz+}+C??TAiXUNYo~E_IeUgN&tEePd>% z9rYnI=@oAWmZl42QDhwI@QcW^5QUB^@YSy)^I9igv;%r``N)$OHr#B{p5EffSajPL z6Tc{?lfH~LBT_~yt1WTr8x4#lXm->$);pEqnO{$ybxwXVmQEJCxRA=tOaxfLpMg`=%eky}B`a{B*AqVvAR zDF^fX7UDNMMTjXJU5S4Mi~u9h3SR}Tgau$Y>fxinRaE^9Lw`JzKLw_OO#W2KS>Q>9 zjzgYQ=#Z)%a2a@qyoJt5dZ02yPhuIP8T@IHa#{xVrbRON<+L_#2Glx!X5I#d`OIX? zU8YmF-LmG z@ErBBkteI4&7TPKLt6AZ+PP`5((X~Zy|SWdn1(ESiEi%g_4YCDW!A#WPJA}BIVQj$ zkp`88(ry~83|Iy>_&r3m@Q!=4QRq0%qa5?jlSlTerG{@ghyN3N6gfDX-9JIhaqomD zwK;ZsdpNZlYZ;^8P}cp0`15qUrGi&EC#Q1wIsNf)T%J6 zlio~}K6a6#rMC-f1-9~vpmLZB^~4KW%4n+SDI!mLxyX|fwT^MHXI#X8f!@3nuqfyD z$HKOe8-FhUS3DQ#&r1%+@@Y@1c%0_!DKC#d1_q8iMCSI-;6Lr1@ubqnB_e;-^7^A; z-N@_z2q#BgBJ;rgKbqNhpi}@D1p~(_H3do>E9qZI>FWk6hK6qJr@K%$4$xh=%-!zo z@Rqqdyq(@scbU7>TTT2b`W}*_sj(tPzhi}3j@QEq&Zok&l5vHa$}i_e$fFyop^;U^ z4r$BDw#;4P?&9;X#9d0ZCD<-+Ib9N4oi*fKO@Bo)bTVBqASU~!d>ZZ@wR#^-L2j>Zz(+*Q=E0=k=-FugJU6aiK7eM zMT`qw$%<@}%`i+uc5<%b>`Hf)yV={~ttVb~lSsvlB{7;EOQ=np;#fqQhGobu&;{;7 zH%W9g@vGboM6RbJB@rqcYw)ag*SMR!&7MspSMtVAdPr?!7u}4%x>ERInCSsbIp zG2dN4p7~f(nDY|(8|ZqGnjMSiqM7D6oVAU4Zqn!_ZJs-yaV?qGxNF@F-bQb&yV2X^ zZBpZ-vav~(Y8{(6yHRyH#AlH@{4BnJUx-Ui)DbN?c2r9f zeiWZX8e&q1X~Xy8gGd{G5Ff#hc$0-k`FWBo%*t=KWSl#yr3>GRcOqT*PP_--6PG@G zE#8Rq;T!Q5e2X^&p7h`=@mg#(7tpn|)!fFIQOt4Yx*0_##>`^2D{+pSNo+S|@6&c7 zwwYVZY0epMi@A{grY+`H#x3R|zB(DiJol28LCkgMxfx(wn(OW`=g~8@gR|Ss&73>q zZN|=mXT5V?dU1&k-1Oo%`f<~X46L$@;N;)=o0)FgJ1foR?0d7r$#+ z#Y}gWo0Z5cVwWkqwssM@)7(hZId7x6+FJvj^HzIliQcTG73mn$3fZ-sP0Vm-y4lE( zRb&ibh?n3?@d|t;GK9O$*>r*JCg(151Nqi?X+&DFMa#~qY$Cgu?#^&?h-vP0aJrja z>@j6u*&a^qHrI1vjkg|K>!lWHIF%aPs_ivr(tWm<$UWvdbDhU`lDXDf=dI(!S}&E@ zrg=sxv6bHIR3bHFPVuul&CSW9Az`^dc4%q6C} zKfAd&l~e3zcb}PCOmU~Wx$)-`naPkTJYY_vhwcEo`^^L9&veb@5tH31ZXP0Yi-UL$ zmJf*FDuqOq^QBEC!gDEMDXHso*lY4>4Uz`ihN^_N2%qmWNF)U$NmQ!V{ zvR2&i`*3gMsdy&#!nG6_d$FhD7#WVj?vw;BHL0_?$vufpa4$M5%$4RvvR!b>aki{g z)GB5r42xok!aY<`KNH6}bquDc#IUiQKxcD;djgy2{^~3@SD3$&;i6NXv*oPv)^}mt z@C1>^VWCO{tJ@`KskzL&Wry{!*tcq5g@VoF7yC-44N&wf~@9aw5%q8Yhvl6=%tx8txFiv=y-BYk( z#fO#d4`;Et#QcMp-<`_rRrXsaoNCOgTGgyDj1_Ko=9>%5?fCz6X8DDz!qzOmuvNsG>Cf^d z7U8q`E!YLG*SBCdyk1{}J$ydD2HzOJ2G95|SHfNFDd7${!IW?(JYX~YnSN1g29_wC z;U@|chqK8%%b)ERunJnU{eo5@>%Sm#m?iu#_{ykqRspxeE%tAaCCnQB8~n#O-Jjtn z4(Is!tpe5@&d&C~1X;su;g{fF#%ca^cBf%U!nwrE@#p$^t$fy8KcAJ~(#S^ZZnzaT zGcDW(kD1OKdWUc`>}Pto1>UoH#LxBT`MIq;);vFtmDl>&pXMhCf5wuApMz{+6#T*% z;S^*+;YJwMBH<=j)aG+)o}R%+G}*lB0(CF}{C}>xWS$Jx=5?*li9o zJE2RB(ZhNknEejxdExFm40lZ)aR?rpeBz`oH9b%22hk5bN#uzb7MpzHAba15Q|zA9 z7y8+(?AAg*yOjgX!AJ8U_!#)%2P_DUa2@<}Mz|ivIfIW`ga^p+oj8ES6{q$6D1n|P z&ndWh_Mz{21`l4CfZ~e%*!SYBE>%0vvP%Rz--~@%Jh8~nVr8`!`B|-OU^X7xH z8?=kr1$~FJ)48Bajn0eAFVG3G9bL}#%rC;+v^R#gX%D);LehU``hiyg(4j2?NS;4YY#DwAWPUxTyN{ZaHuy$i;1YOG?y zCv^@!s-5sP`9yk=N`7S`D`AuTn#9)t$1#qipXyyO5_=E6=hHV*3BzjEc;!{_Iv7v3 zarB&=qkqJJi|QP>8eYI4vIADAfc$=>B3UQ-6|u>FEppcMf8y+TWrR}A%505LGFw@| zk*ox#*T9~&9d@aZ3_+v<=O+8LIaLcB%Q&2KS*!_Ukey^NgI7T;;zJm@w!utQhnU*_ zMEnz!*mz>W;I$P#tGfOecIskv{7LLiq+{(x@G?LH6OODnku9)b#UV0wq#luV{d)e7 zjFXk;!HZxrk&~3~h>R1dkH4Nj1^;9vZe$azT5<7z7ioaMzTdzf%{Wzg7CaB85;H~l zKC%J!tnVWmVcYti__&dV#5C}KCT6Myv>fV;`F zE7%b%_LulOf}M@yUB0{5CAJ`yOXv^(LpV5z^%-^Pih{$67C1bc&l^e65OWRIc|e1*-;2)^k`#Nez{ zW=9Yq{6-s%6YdN8)8V);kX?@ZIJGy}8Z7gN`CEf+j9>kS!K2`-?}iV-Z;WQ}FPw2^ z@E>e(CYg<3f6$lS$^Ah;x+eFNZC|j39K-xA*l=*TKY}Zj&nQ${!50|lEHZGO+>gLV z!Q)^vCr0=Ofg2XVAAepx?`R@RRVXG2-PoF5BLhqC^6 zT4}!wScbijopOGNmG|RnCH+!hDZeyWnuvh?@_v9-04wla9cYvNDgO6F#-#%+(5Co4 zHr0=(mGDb~CE44=M>oRXgpKr_-~&8-PVf-1nC`%w?_@gE4jp!xn7 zd>lLhp9D{X_*!wlgdd-r@!+>8&Mbje)Gy{I(2DuR{e;XDXotviFgO&*&eTIePx@Bf z;2j)(Ztxy%KbOaKf{nqZV5Gkh8--5$7yoIHNGswO^%IdHAq*Ua{UUy1Jc+c!! z{9AbbqU3RdBw8WAu%CpO#Hhndt~@W;09T$zOcagl4XpiOJq&X}FrRk}L9m^lssSE9 zh^Jbxg2dxW#{nJfdo|G41?z)AUmy5-EBga#>@Dq9_D4T1yRH^j{hl#Cr{bv|F&hF8 zmZkMUsILvyf$KQg!fr`?3+$8MnhdS%*7kc8*uPUH+sJonT*d_aQ@{jG_(>9wExsCs zk7+{?i#(y;+-_li^4oB#wH=4P?x+?A^FWWUWkSv-P+eG@HUzHT$j|S)`o>@sxPi~3 ztB>N<9-BO|;D}litPPskpZR6k!Hg;S49jflJRbQJ5#$ilE z8I%DUJdy(^RDM4Wd1CABh-_;&wPgoxQ@a^sVqVrlOH6zs)h4chZ|ep8f}q3dJ5I%c z(Q0+DCTL>I{^KT`?yj^aPdmH4{T5yLB&x1Ov?Sz7tXlAD74+j0|DE1}-S&1;Rf7{I zDKSY@lf6Q|2@h96|9fKM!lbn-SRHgEvV+~xeuHX!GL-{bG9alMkKOO#=vo=93Ocdd z(e7lwMg=~(s=!W@oXBKqe0JmMo$+_FQ@}{0XeqGdY65*lurf%%ZhXB9yPfSW_A7Mc z6XH*xcV*tiPQ*MR3|`BF6+t&VUF~l6OEl#xgWc@P_6ro@yYjqyC|&uEJsfmn-W6J$W7h@i648;JW8kr1anJ!<0(NBV9n`dI*}a2W zc5SdW(S3p%c1^nv{@y`*qLzS5f~7%T*MJEvADGw8=SJX3%jXJs(k|M*dcnSEdvGk| zar3&So(C)B=Wz@1YRpe$KKB><0#UzUf%+?v7wuo|DEth$-6U}4lzk?ZWDi%gya3)pB9UK*^s|kW&TRg02Ru+d2C@zi`fBvDDv) zzhwVrJFr6(Vz;1M$mJVI&*|oJ|5eZ0=j>QuY;~%CmRW4|cOrkYf46NoCHnFi=o9n} zs@c`;zCm@nhTV?O!P1}|wk*iO`Tx`$?tico<#2PdDoo}=Zedq}aqbT?{BHkYQ;eZz zcXPO3)gtaUP0@?6TiCs9OVy;y?EYbAWAB@q&CSkO)cp$cT~Q*7xL1g|Y+tbjEE!j9 z17?hVK^42I-7lzWR|Bi@F|`er2Z{8yd_>EbFJo1V3`N~y?!U0>6?6a7zG{Ek5g0lC zB+nJQIR0YpUwHns`;)C-&_AebSFuarFYcCbzreXN_RoTP#5nJ^?!hOh(XvQdKT|eqK4_X9w-FvR4zH-yL z>D*UXdN4ibJ$9qM;;a5A8tFg5q&R~-)6E&?A^Wg>$JP0&-{GXL-f{0Tz9z#f)MF3Y zhwPce%rL)sU$heLH}5mNjNfQM{;c`r^nBlM7BmmuxT)PV?i(yEnAUym27c3^SrD-6 z`?Jgg_Cb3V*=Cw=iG1UR><0d9{Ik%I-DmGdPjTlbxtig6D9*=8&vLqC?^ zBxoAM24negz}R5pph@u3YaGP!UwVy##=$G_rMF1`&-)5~^%m-%&0FqmH}u54@Hm(3$;Uel-7Qf55JR*X-T)SMwkDhWnMA|Cw{)O-=4DBhONJ zT0eQ8y>I5^i>|K#o*EQPzAv&-Ol z{pfx26zjVCx2srxlO;cA^Xc!*_r$-$_JDirz4i+Iz4yUep?~l`f*-x*Fw~}SQ@XR^ zs7>Lj*8kjV;5GL;c%57Y^dHcHEuarI(Tyc%e*LZa&fIIy(o^z%F^khF-GamvfTQ+3 z88tGf)*B-B*>B9ZjH~o_-g|EqyDN3wy6XPV)rrxpLYyiH+vpHfVpr>Ly?5SfB3J1V z>reMDH)8$eUInibU6`0c@RbfmCAJ7y7}nB3=*F(m-*|7mHJn|o3rwRj|-?rZOj zw@z=wci}qymG>Ha?X86&w_(sI7z;|S+y+6z;EFjDp57ZGgPsx0sQ)9fdaunlC?QUV zx$nVQdMfY=<6k`1pC}GqHs8Bf&1odsa|*1>*U4}VCBn<@757&Z3@^KXo0H*Z{+r$F<~_3A7579+ zJ(Ye>q|#IC>Aeiz05d%{(9GjKF`t4@$$p=hdm^2e-WzD9!v>joy~pMg@CgwY%`5Jo zDE$4(c+vdR71lrIBzU3!;j#Wk*>EBZ(l_w@V?H3yeepmf*Hh>ZL<&8np3i$|J~H!p zkIcv5V=~?}C%{2{lT$a$heSRQ`H3Nd`9twYB-4}Y1-u95L$d(>{HPyJAo`X$9@gqx z=1;I$-)4TxyaV0_$H7#6*lfUe=V9h|%){nbn5u91e~Q1*+Wt#i7614*e2G`Z|HR)Y zVoSUxvgm&^yC!ZDdBeZyUlv!GUlD(b>wXqJt9~7I>@4~%{5Snu{vYD9xW+rIsi;$5 z_p|EP{PE^l`x>+H=52Ow`M3Sw#P8y^|GW4@++lv(zvKTZE-}9(eiL_@-|_GI7sN&8 z7sapQ9`n1XOaCG+h`l1Mm(J_y|AJ!UK9R;t>+Qp{SM+Le0vJ^c%25A34Zo3p+A-u`)X7PJK}FS&PwQ-?)o|DJi@?Cjq+AAnt04IsY1Kfpg}o-((I?INkZ4NImU6-m8h-cimT z5uN>d|G@DKKf_{YrS<`4c6^C)=KJO&;!hxkMB{NOkC z8w7{V#>|H@KWrW`o2niCPX17BtM~y{)-7VIXr^}XJNnJ=H&r)TfA|}%P1f(IU=M-2 zb*mVnZR6E5gxNOc$@E8Jn6_DL0k?>uS`(P@I{8ho2WAuX0k5v+YJ0zf-<+Jy)D6}~ z@@>E_`8`#Eg z>#w!eSy#X-D35O=&sJ-Ic1Aq(2f!9|MvNlENNtq1UThEz)c9TkuK}z>@x9iZZ3PQq zYrl=Z##(Fr>2K%kHfy`}D{9^S;q!e6KJ*{?qd7YY2Hv$|ofxgH6YE8N*b)!>#MoB4Z**<Y=XDE+8}7`XN#<~vZ5@p!dhwlWYty2gLUARTxa)&EqR^Y z2cG10c3*9+odvatl~xvPm6e_NY-m(0w^mqd*zKpSvHNL{{WbPlR_i&t&K_rtC*L@% z9+-&N(m3mcI0@EM6L}M?+VEIT;IV#+QIcH+uCi8xtF1Lw4l-v)0b{APjQKKaxi!`r zXPp!ity(Z)PUP$aYqh<`e(bNtp7Hh_0W|fmXIU=j< z)%FvA6?WR+X!nF8dLySc*kj0jQjEb)fv3cBG0Cb4_vR!XYoe7A9gV;IjM!B_7kP4` z+Ofo1YW--9v6hRK_A2|dzlm%c?M-$MIH)Icc9J#OssW#8ZX$D`__5epVyz(VjK9KO z$++3>uJzD16TitGO_mj6H2Ic`DOPp3K&NnavXzHZxzP__;Py%;}*NC)=k@DcY`Z?3y-zg&P$#=XqYUp7Fr{% zm130`NxqfhXYx$7mf6egv;J02ZL#walNX(n`PKq!npFjM(`m%~Y;ChUYhAQ$b{DNH z*j3wV=O-o~dMWd)`POu+GAyaniJxX|Cvuxz0Du0-467n+sWYrfFsIHSX1cY*?xc0r zb`Z1Op2_YEYnD|3&eU1VXIj0P&jQQCmfANmf{(Qy*cYXmVb*Zw!>tikA!o6@#4hA4 zv6q5N?Sf7(ks9TfULp;eFTF(CNKerxvWnMCpU6mS74yD~{mIZTQh@knb^+%s+T{hD zWjyNwPCkPGqS^1p;&N)9n zcHS@IEV38dMaWRt>5ghzx=42{eWZ^_iB3%)kqU*HK4j}HdPT;=0^Td~lhz*W&1xXo z2B6dPgEiF3=bZQVf%~l4V18CborU%yyD0gKINeZWOCRZmWr*}8b05(YJ)ZX3AkGd% z`)7#tgO%6G=ghW>IScHCb}`Ntb-JQRmm$(sWQ<((yE4ld=_gX4q|=WKeMJw>chGu7 zI%plio~#CwXAs&#gRLP}9<=RegR`wUR&i&(y}&L`=3-8NksL*y{^aQ=x}$j1Q5!-$ zCnE!`LDrDSAZxId+sWh10q0nAtrE^$d!AjwnP<-j=aXfCNQ&;y0Fex>p8;g+FS?PX zlhzFtrHd@{%gOD`wQ^zetde9a;S43_2egz1SOcw6cuG2@oH_Pf zdyq(s8qpw;1l6HIWEd!hMfzI4o70bTokc&a3)ltS!yh;`1nru;!Gt$P_>FfDHG+EKXMEHYcXref6&5s^1sIk*;DWd8FD&8?+an=pE4KdP0WB`rk2n zP=CiLME#8#TKvdEGCTk?J6W7z#1BOorL|}yZjo_@eG4U>>Go5-eWXL=DS4jg*CT(U zF7=4`hhRo0lk+H&$;s?I)7zpK_DpYwI@mMfpQ5|cQnV7o^;V)a*jfzJuc14a5FNUN z=vH0BhKR>xcoZ3-w-7DG2;zsMBh;4jPa+wdjLs8wA4gu`d5#iM8amSDbo@ zno&#C&tBtsg-%fm)X(1Fd97CpZs<3`o2VsK3@QZ@XV^3Cip*x%6@r=eEU+SDWg;sD zm4m<0UaB1Yqu=Er zLmOshW@cu_hB;}tO*w6fzmx+_nueK~8fI#knclDbdHPQt? z7k{0gZg2`#r@Fyun4GEwRb@3b)C#_Sg&aivhI%D;N+2@SaA5Nc(>NNkoE^_vC z@bzs1)3dR7CDYE?YfdV!F)POV%yoZ>n4B zP~>pr3jWL16{|bUO}FvfQn%FsxFv6^gD_1tCR?MRac~f>u&cyev94O(V0^km%x%>q z2>G^}1ReMeZbD4splQ$^*1o2Angq>)!TcY#8J?!tErRNLGi0zc)-4y555~IXgE6kF zPO4MNMWjlUhpfX^qC9LR$kFUp2u8bO(Bp_7>yC5F2IT@lDX;z*( zK_(AzRXiDvSn)Ceok||G4uOZrJIWpHRtUzEXPoPBZnEhhQ@|;3Hz{?T918JNN_oUO zYNeF%=p?z{IshK94uS{CHPWpZ+>4BK?=gvVq&te7Baw>11Tv3zC%9#TvVpA}HPy6{ z&Ze*aCAW_#6(^5c$E-M+5}lgNN%8}Cq`NmVky8^~OWCTk8K`5N2oPVTkjJcltrRj2 zoks4p_JRAX{osDikKp9K$O!iX^dz@*P$rl}o{4UhEM3f~>H^mmrH`y))KRj=Ac0Ct zo-}f}yALkV;qD0ZWX?`^*oVG^MK% zY?Exr5zN-e7kKIE2@ZabsOdTaZ{8?@H-{F0VA)yQA)^ z;ob=JXm6l9$Q{kuQQmF+s&&n}4Tr^5>jAHIAKr_1o~8nqOfrEC@$M~nEUsC%kn7-e zYpeB;m%@K9q5kb)EF-n@riCK*O5ZrAa0v=L*Hg?2XC@^tiSf&c#k>tNFU-2_4cYE z$UZgB>+cS5$B}2OH_q$l_IH!WkP5VO>U&xm;nZ^;YqrI(hNH0~t)6TL}ZZ?}*89RD+zOrCo$ zymYQ9BQhN^Y2C@}PVy#uz1-gJ3wDXqpLx%{DR?G>J=~t|6tAb-%bn^K4T=R*y<$NR z>>hYKkGZ3zHa|Y6N z-K;^ZOd+!d+0eQ0=L~WMjw{?OLDnFJ%n}SWPx@JcfBF5Dh4sHyZgz78xdY3!-Q0og zI&L29+(Dio;zqHfuI1*%&J*Mf4A;b_(9g|>oj1rAP;%n#a0hq;y&djAZ@XIxKAEeq zCWQPkrI3>PHvY>TP}|%C{FH7ZW{|hd-HzVr_V)&W12|bizpn4FN+6kJ2~J&yQ=uff zG}%h&Titk-ptiaRDiPeqYM0y3>+kI%!%nw2v6*CXB(p37v&|K~3{qO(;%;>l)ovnp zxx3xIUO%rG>I~w+VRyKJlJ#b*V8+|+5K)MVk*M7 zaTa~h?e6vP4zhc|t&FDD zkb49?40iFldP~3~?h?1N*9E&s(Af*T_h17Fy!T-P3A}>3?|p2ocR#W|w${1p-A7uQ zAZ_qSOB+1Y6uX6V&D)+gTDo6^RbM~3$c<%-82aYGu@x-U}W?Hj|pNX6TPw`*%3r>A*ePOM1 z|8ZY%_PJ(z?*|0~+jGzfoQn4nyxe*oeTFsDI<0?6V=j_ zOoEr_<O(kRU+!D{Z(tTl8N>(gu-|G6 z@qc42w3fQd+)>sNcPY5kU1;5v)2$D!-{3;I3ID`Rcqi`Rxhu2SQP1+S*p`>s{ssT7 zWG;%EFjV|U?C;2LS|;1}3I>^ovAs-oW^`6N;zhwIC-2A^d`<4i53L#29eEn2nmh6? ztNU`QH4U6*O$Vo2_vFuHzn#o%aSKk2|H%FaEH2l<>#T0eDzMqymUqw(ID20{kW;Lw zRz^FMT`@aPw&_JYgGv4w0%qfr6NZ5xBld0W4tB;M6LzK`GkAxnMZ_2| za$Mt;GT0gILO}*3Cdf{nY<70r@J#QPtO|3^EqNRLkk@@6|HnB)yD4wUYWhtiE0|T! zrZ3j6l4&vWru*``AAN(CR>l>WNV7`6AT1Q+vn6`@CrH| zXJUhNc6xM9Tk~`;CueimH{?y3O@GYUNAgElObqQmc>~XXNOt`R{>So(oM=t5mTH%@ z%dnMPCf`zIiI&!m4N?SY?R4l|Yyh&*XS(g7u7;r}8iOd@jMEa)~T?h{{s%H z9A%BR7QicGXywE;Syq%2SLHSNNF>>*?MEWD{ZKp-sq7@Xj3~=~8RR;6UFOish#Y#7 zSDyHCqP(~wugV9+r?DT16hU0@Ks;piK&0X8^Oy{eL}^h*BzdKg)LsSR%Zm!)vb-Yi ziw7buxR0a^o)Gz1JQ0a@D!Y_O?WOTbaW1u2k;n?7qPQe4%X=avKe6}3ee_czpNOX- z-cGQeiUd2+E-BJ@&)t%u6uJ`e6-6a+L0*)V#6@{Y-WB)6JMAuVMtjDor=o-?DW1C} zkQZ)cA}fi?;=H^d?})qNjCKb(t34<3nRqVZ?3DI%k^QqByH!M0aZa9>w}?8Y-9pZ5FWG$|s)@7moUF!fRq+bXOEA_>VOPgrO;i`B zArGT`K!@u{UV~MSnC%R#lT`j{Nu0kU%CJI z`Rx4mKUn$fb$(${M64rnt-szcC<=-7ej!m9ER1)hpWiNEujE{Q`)|L1?SU)NfBT-T z>sU;TVfyFMmND*;yj-7{Dd4N@<1}n(F$+{ zOhkw990ae6|HK}Af5Ub3H{3*flKF`aYuCheahTmh$xKM|VOqK>u8AY~4{Lwi z7yr69VzZw|w3-T50SX+|uE7+zsBZjt(vs?Xbel3wxZ1Yd@y|sxQL)(tM&EM{ykSFC1aJ#?5 zA7!1uE)pzpclb;AtvOXJ_Lulm#S(vtm<%rUCyOcQY2r_RF}Rq$N$f23r{kF>CSon~ zC-Pq3VNYW9q4>l96a15i3HaWD@5C7~1OJC&Jl0uo0(z$S-T%X%iGPL|hxZ(KPMinF zvzo>3Ofi<#c`;l3=Kt=`#xqOI5x@Gs`E&5h7IU%Zhi_}Tx( z{}}rt(I5L`aFPGB-^?5(MvG?VXfXyHBbvfLJ%-n4VxH$K+XQCnG1y~y#pdQnF$x?- zTx0VjJYbE9J*l<8-yC-8#^x!l5pr5j86LVO@v z5z{i6uX~l&+8i!Mh}QU9!LU6{3>R(iv`%LBUZvGHSHY%Mk5!1PVOeWSOdHs{hl*jM z9oQBg?;&ESs0$de&hJ5D zu;^$G6obG)qC+wp`FgFExgJKgn&t+$*lOb20AEl|b0hep|C6t4Kl%Ry|K~3P%bOKU zU8`VL1S`Uhu4|RxQP*K^Gl;JYf4Z(!fj?c>s=|=2Yt>*v*R|>}q3c==IM8)%k>6kF zT1WWCb*&Q|Jvy(tiL?F10Q>{QKyV=cK8;t0hDh7t|LAL4;b4bfI4A;YTC<>VplQu{ z+Sr`ujm@xc`^~|C%3@7hUFIj!f_!6i!Sj(Ht{*aW(9q`jANd(# zmNE0q&`!}KbBd~^d3bsv8*47YuK~>T|2q1MI=N4&I(% zc-z&0JE!hoclK&?7iDU-+3AHH-b^**UZ*SAm8gbD1Ez%6CZ-YohS8d=Osz4uHC>{O zkw#4Su8F4!p2pE8+~stRHsxleBN*Q7G)0<3o8f61Z4NdA+oM~6&B5@tr6vFJwqQHf zEqNd9qOI_>OrEXXiuuIhq~bixkFFBUjSjI2v#Imq$rH_mRSm2btq$g9m5&M0mBGqH zAwO1gVM2lWy8uH7?HRKieiiq=g_2k=9Eqa~Z zYur%s{$L$DAJL=d5F`2@{_wu?Ir;_|-aA&Yfhh#x z4c8`QBl88qd(Lo1!D%K1g!iT4%z-mZ8wl^SHY1yu7!clMZ9z6O3n09S4W|m6Wg0+u z549E9LZ^Rt)3goQO8&i22VBenu-0r(ZT9Q_6BzrnC;{tM)v$k+H6fPbMs$M;X< z8|<&aW$4fF{R4)b_@5ymQ`~3ZLUz9am!iJ~7lKRB-+|wPi_zbM-+_Oke*nJ+|3Lo; z{s8`t{t5gM412);2mS>9ie3c%5Bvo^30wsJj2_A?s*k90nTItT90txs55fB}I21hs zPgs942R#_?d~iOKy29#|kEtPT$&BeW))VLd;)&LdkbqtKBY=z7JH+>u*PF1 zdNeo+oPiz#js~YQ^=J$-gZhf;SmVI4;577ja2z;=`900x8MpgA!Je$^vOkciyxs9NN18=iaPQs?3~%;ZAk8B!@wAAv;@-V0*p+o_ z?$JAgo$<9sT1DF6Y0bpij_9^Xn@BtEBRhf}S%*x49l#E(3oxTLteUIN#M%N#O={t) zV}&(xHNl$9r+pt!Si@Egofls%uom-r^CESqD$5HNWcPir3Nu{`BGsratAZ6)oz(&B z@ZJjJ39HB|ql8zdJ7dB=fXJ`;3jm4=cwq|ihm1u2ECE>1u(1( z*~tERW?!6PZyU85r@^qIV*@)E!LW8_JN|88Sj({kWC{j5m&~11Y@7s7;@yS46AWuP zb|ELs-PpUpu$E&F7*3f8>lyYUd(3^{IVL!MJ3~LMyfcwF)>fm?q02o#aEHuN( z65pU#)5{dji};$=YV%wC3&C)9!~(o)!LQNZ;rSK}Cp>(I{6m+~0(QSb)`9DI58t!< z9X&_ktcD+u@98G`3jdExQdj}5!21*Sk6<`O;U{D{-95{&7BM$r8Mut~&rCO10xrS# zGqTA11<%iP-z>)Zl?e!o>A3j={TuQt9XG$Tnuh#FU02vy^MN@MJp$`9Fzh7?E51IZ z)@wfgQOL;T>a5SH$O=1CMkDjV`Rs-DSD%BQ)3-E+-O*H|e8D>jYpA}UdTJiNvB(%| zqUN$1hm57JX%4IL$T)KX_IPkMdLq3Xv%%S{C()ZR3!KGz65SdzsXm&4H3bYS9X>=) z1*d@1(VfAm;52kIYHkLAVSP?h^guq@HciH`N~Z}j*lbQr_{p~kb_?w0U|6fui1m=< z&%cAgA-t28)W`G#`w`KKik3cLSToZKX~`$zM#QwnAAZ{Hg>Hki=JRYXthUst^y2eu zSg+C!Y0KxnszbxA(`Rt3XPz9o?o^o~`*D$OV4Dqt1XW%$fo z8LZ5@ET5t)ft6U7<8yUIup;Y_xwZmWfwfQXR&FprE37=AkB%|JuC5p)Fg?6^L4}Sr z!#=E7B*t{{<^%Kb9>T8wyk-h^W5KXLD-KKnW;L^cVds=2D!-W$Pn;PKrUbK~6Tq-* zJ`;UL2}l;Y<1=BU0u#ZolPDFE$xOmdWu^v`z_9xx4VW4X`$wJ|>99gZ-gM?IBSJs; zO<1==jM5c;1OBWKEz>q{vwJI<8_PETGs52eI|l!o2P5oVXU8$GBf`9E==5mcHP{AC zBCZ*NcXEv=Vcui+u5ll{2ZmkM_YvKEfPLS12tEMcq91_|!8ho~;3M!AJO*c{%&L!llivb*#mFWIq)3bz3?-g0ngyui|k>> z=4q_`@H3qTPqRJ%N6{(p6zhZV2Au#;;5&#MFb?54$W*+4(T9;k%*H#$>Iia}X?90h zEkTaJin1PtlOLFFxgKVdbyz<#S#llRB;Vut4%uLQiwcx%7JCU8tC$1$P`l@T>&f)Rzp_=D}YtemB5N%6?8`4Qx&iZ z>o{0j@`L%A-;)wM4$O;=#Zv%GfsR2J01Lo!6N9{O#1oSe%!3Z_y>BF7$Ah`iKI@Rh zJwPYoNdR-9Q-O(KPIM9&&fdv^P7Nl3*X|Tg7I$6Hb`HjB()X4WB-dL}Rv>wCIjLe4#kV(wBe=P)zpKAwBjv`MDo+@Z2g8n<4r(vBN8g)V8MO=VHF%q@QRB1|9pZIr({>^^V0yYj z+`i;0rXBchz_fIO_p=|*KJXHHJHDH+GF@VQAh{ChU~(PNLF@x?Bwc`S=}>aj(4pk2 zp~KjR^ux(@K1aaA`cd!*cm{nexz6Vp_EC6pqGN- z)ZCB(XBoUTE5Vhl{|Xsvz`t3~;iBB(PQy`4~|1mVGit9;8*O8!S}sB70(p#b7s0uMZVOhVNcbk zGmrIi@N?E5GDr0@@H5sk^!dzIoq>D`eu{S{o*DWq=B3UD=d+%TJq!E@JqMf(&O`SG zLq58>=(hR@coo|sBlULJZNcH__Fy}DN892Ldq_hZ30qQ4gd$R>V|Zs zN3uUw53oDf7q++_NPoH@`(pJ1dxCw?)xogau{XLD-GfcQu*0zwQj&_l##kk=n}K0B zXIMknl$yV=AGA2D=G6K%Caw$}eT~3ItctPM5-g4`i@yw2dd2XR!wxI`!tTHF^yW1H z8?df`9aiPlrE9MOQlA>Sx>%LKieMddWqRc5fOS|`p(Cyq81~IoK`K+xQxmHieQ`Cx znyj<(o@#(KSSL~;mjH(Ka*0SmJr#B$v%M0qvOA!_|nq6_Ou)QuGY!%DU!Bo&jk z3R6EA$9`cwHM>d7A}YeWN`bG4o(4~9FswRDgXGuKVyDs5foZ|8rYjwiS5J?fPR{_Q z2Xj)Fl>y1EXT;8+X96>VVdYFFB&VJkJCmM84=Z!BAeos}lMPGbon_M>YCe;i9)Sz2$vzs1JtrzI`sk;j?U{ce4Er!WUPl$O;^;<0O;T|=0vHDX@ z>MrQAcbA{M?PYZk!QYZA;&vq0t%bOQdWWBp zT~w28O|D_vf?kAg7ZqV!@cv1S!4|5%cJY3~DzaTver?9Pn48_r)M{-?t_0hNUdnCn z5-_}LUIs1&*KtF=4B0>x)jF)@;9uZc^a^k}xSHGW706oZKUQO{1pfwCq344u!GF+G zskxd0eoNKWROEYY8unCXj84IxjQjxpK#kZWbcjDvcQ&2cs)gV}Vy7e1nEN>i|3u_} z+K22;XTIk|>>1b}f?uO&g5k8!1?XAeOz=zUF=inPnB@5-)*Ns)_yu|{I0yV3JrA4< zeun-CoCkhFRmn%m6(%2Jf5f!BPnfycKeOx(kylM}i}X>VkCE+Oant9M3yxN7Oj2D=}TPwyY*--I!B30vv&_8`4$lj;EW} zgDIB7!QrfXGKq2+IE-~KCOi%Shv4gl^wfIe>814ndxHa+*4PIbto6n2qxEBo-#~C6 z>)O1h0pI}E<+SEn3$TUOQY(vYsg=i5PAkKzCD>AHrB%RF9&D;L1Dmlb%}y(@mDXCT zh`)kXidAc{wbn+fgr_3dSZe|{VO1Hsl2!$*3^vpnfsI&I#jc`N1FM1!(AB|eV10BA zusT=|T@$PU)Yl3yqX|$qRYOn}8Etm!@j84K^6fCM0(^8>BET$FL(y^NsET|O% z3$Zfz>i-W+#jb(18!W}UFj$uWOK2s*lK2ev?t*POVGz+)OXL(a3S>*CWdPHI@1qmg zF|>@>8Nm0@@%Riala^mA02aWP3CXCXWQXbm{F$^kR)&@ZJ2RLModTbs#i9)@E1oQ1 zUUUpTL(8V+VU-QZss;EAExVQ*Uv?y$=HoLog$^r2B3cxTY8Gf|Hh6}gR~^d%9Zi5j zlc3ZXWQKU4$9XD4_+HWZYS#j@YdOFiWS z=5v~+b>|bCrp@H@sHQF9bGD`({Yffrg4=Ve6V|A-2Y=>9PSf^s(`axn9oC|(4sWToPr30l zw1M0V8d_a$&&y#;c`;zD6hBlPv%m!6RL&5w!y)-n*lRZPb zW=L=|&yfu68=krt+6O$NFtnz8qBpdHeEu~wpU;d`0qZ`volhc$_C0^S8`>ED$~Cl> z{7qH|O<@+NjwjLr=H*-9ZSK`u!km7GJN4#Za~Q5~;?Lg9Of?lBO;m9z-~R5nd=kTAf`u5cd#e=Q|AEp z>YqBFpyxS9xRamf9OX`a9%nyt8WPnV2KGLju7lK#`OMkR`}xfI6#bdAkM}j#ImWI2 zTu#k%8WG(MCgFzY+MKEb_C?oD{<;rlqJyT*A%3p&9#P$367ELTQ!RFD$IN#ArBYxv zyK|iP@pggH_dRq$bQiD-{OPlt<5U^Ua!ycpFpK!v&P?oCPNA4iF?7xo)fukZ&a7rQ zC#heU;hdtzVFocXnK^O_Yr1oqYKQ6AA37QJ;dJh2&_~eYpF#hCX#g4UWYmXQMPQ*F zW)+SZZl%W`{&kAi8EO@U@p&k_!(d=5%qxw6rLQnph*!@{)G#M=80VzZM>2mPoj!`W z2kFQ_7VBc=OfLLbCE%u9c-n> zpGI$CouewF1sr4NA_J|GuzL@*O2IHbkeESme6_I7Mp`0gB1!sKrbZ;`v!#Xr;oRq_^V4nMf<-G>&N3erc%~6~w566Os z&QIJV_yqEyM{{-zH;OKwhDMtnpOt)~%EKkniIb!7j5Z4}lOzIde_&R?t_TlGH>;~}4 zegzV1Y9U9Fsbzto$kejNWC63qWCgRwWCL@+LS$+=V{*i#F?w=0nAYgQtzcT7MfNbO zi}!eM)y4bpJ8ZOKcn=$`SeO*5;i)b*U~jb2@w~FTnGWe@rY1ugqXyOb1)Lg4yk0}Z z^GUiY@ztpOF9<_KRZ$4WiuIh`V6C@Oz!s|P(BazIhc*@&{8`ngmFSoKeMJ=Wm=R{)lO606ehec6%K)$tl!rJ*Q*?WRp z&}+!K)=J`%qlPytUYm@O39P*0o+Z;83Vb~F2||z^um;Y52c(a35&`~ zBL9KGItl)u6vV_CW$~AzE2b38EPvx)3IB9z_<&;B4X5Z2;x@btyJf`+{C~qOod%|! z6;@ifb(VuGV2L)hv@w5y%c=7IBcqhnXkzq0|eUz#3{k(%+|Z z$RDEUe2kFly$n1r@QDTet{9Vw0gs{_R^{yy0i-a{%%Ij=IWtdke-x>WO&50 z>J$19vyLbWcTXMWrk8cPa<&_D>3@ZtxU2XLUgM_9;x3>mXPc>0oET!B(g#!Ha0+X% zSy$8%Wt_UAH0(Teu}V7+^g?vIJm6Ix>RrgtRWwmH_X|zP(^Q@2S@|IIzFwGan)^gP z(CaZ}yOh(J$S%z4{~a#o&f*VvoEs~L+lt1VZNi*@BJ|zd+ob^`x|rMjV#+?6y`F1IHQiEqUGfns$1+#&L=-hr5o%=%vpi**BH z8mji#9hlU=1WxI8!qk?6ORV-x+g}PVbXz>_L~}SoDyZguc{u2sW0hBXytCX4?D5WV zQ?S?DqtdaLA8KKq@3DKz=NO!+>hQ#o?TuqS&HtlUa~aZX1&N)T689J7ui`hX0m;8 zzlKtr6K8`@ee!Jm1*iUDPk=JG@KW#_S;5POrM`B}UJ-|lVmE^}YB&AY<=Q3tYhlpSPq zrv2CFR0BA6s;g?MzF$LCSBpK@XaN3+-b(y7c&uy6VxksuM{m!m4zeDR_5CgEZuPc! zSGlulhrhjSCtJWBP}i@iYN)z?Emae&q3ZdYiP_?9_O5Xc)|QxdvaM_h`#>FH>iV1T zZ}v8M*SQmGBU`~%(1zW%vNd)aurzq7B$uw3aQU30Fi*JgsD2yEcs5 zi)9(uIu^^aFnTOuRoc&E*MZAB54(Bo<6^0|#5*pQc}u}1-U*T0t}E-v+{EOu^VzlJ z9X+3&7rm5|rTnFG3Hnd6Etdas>bN+`sm0z&vDj;%PKpz(PKpMqzFHt$jQqjbKV^P$-_i3UxAjw^zN)8Ak*U7QW!Hm?JeOS`HuGHkOLE)C#9!Vr z@0eKb{RJ-b{uKr6+uUImpl9#4o|DL2_FroS)t#r?VPcb4#flNDf8`Hh^v%YT^k zT~{3;&rz5QR(Q+3BjRswg{SBM#Lk{UR&D9rFu$ewByB zO7Cy)5N8k53F&h-u&?Wzya4OEo|Qb=?4ODM1&-;;u+^+#CU`Bi2C3s8qK{bEz`xjW33hCj9B_T%NZ%?2F>Z@a6XYak@>PbwE{7A zcI+HZcIQ)gX>&RACA^kSPIOn!cH{PJJyY&`=xg{{>cRcl8d1TZyV9#bZ9$A(0SWA~ zWG-iP(Kj$NzYFnQxlgO(*JhGv4|HzlWBHNH?c_pd<5jXd*__Yd*e%1UveYlc(ZO2A zNJ;l=MPrk<(W^+M!X__|liT@7=5gln{gel5p6pEiF5LKSWWs+hUZJ+%ORweE1Z(@X z{H)~6=45p~hqpJY^93xxrO8=_x`vJ32Coto4;#Je-0jt5=Ich$nOnq7@CZ0g9tU1m zMANcxDyx%`6C1pY$a=378A?-m5l{DS4W7`|^tn-krKqF68AgMSWavbNK}KV}mkC+t zWp=)Vr#LftvN$Cb0C5#O0W^^(*U&9=o!TAOb>vrt6*Nd@R+$d%w(Kp=|Pdn~w zx5HkMo|p_yQ6n`S+(p?fX0*|Fi0z^cyKVI%MjE=ji?CbNNarks3p*Y0>7BwxTKc#P zvs;8(mUQ&E7s6AR=XrbrvkMyO>6I^tzmSnqDaUhCGJQ!oKdL%k{@Uv4T~b<9eKW2 z|KoLjk|6x;ig@2wehw;Al%JF8loaqh>=P-Fy&{nbGSW#zgtLfqKgvbw2l&+&Vf`Ru z$Q;Y0s~9J6z9s*6D$Y;g?-g;#9^sKq`H#IsC7j2e!;_rH9^ahKB(+F=F9Q|pa89Lg zV!;?EMlDngxEEfi8ggU2kZj*Fz$YiX8m^yP;sLTtNKP?+%Fj(Tj`Z_TpEHFM-^nS+xAGyeyTn7a6MmD2SUZIxrytH3 zb5b~8t47>kf2|sG*Znn_zfpn=(ieVS>VKGU=EOOkig!|iagI_`)fDxuoQf<27xI0x zfU{r2MetDV5RRXZIwFU&!gp1I6Ynr(jgw!gCfuZdMdSiy6XW=jT~~dnnsPt?CA(iK z%g;}>lI0hmPRSz1_JvAx5*$IKR9`TCxvBmI@n5PaF&3OC1&k>89@R`H7=iWVeQKHv z(1fR?AT>*a?Lqc*H5i$uzOr62i>b5Q$$g?aBahVrW{te?7Ff@jma_osxz`bYC%2>f z6sCqD_F#J&IF0u_#Gb0sIbGZx{QPurAMUMG4=v|T4`T*hw+5_wv>O(cu9%83+h9YU5Z>+D$ z@D1|R`+_`QGG*lzGp5>;p#yyHUES7tH@6kf&%0r@(udhY?X=D?JB^bXOzWg^`jc~j z-QS+6W~hZsJ$dRaM4ot`ljjTOy}V|&Rb?`@)EnEw?9@&>GPifzxi8?$7-c=CuXPmD zP@Z_BkjGv>^7Oa+*|XG4^%-YBw?4DpFjK3o`w~8mww!9`R)HtJrCtSTp*OJ`ld}nu zOh! z?Y@QyrM3G8CY07>Xyf)KXCHe$XFsv#Tbg>ulp#&cXUdSSG}VjU-gYm0o|>y#ajLc3 z6T6q))BZ@!Q!U-MaJ96Ak>)M;Wl?Q|D9?EHg}uxz)ka;x&{n6O|hG~XPnc{c zZJi+hNoTQPGiz|M;V{K;F*UW0`k9=+7;*G)ex~A(PnE}6MTcl@x0busIq!_J)*_mA zoD3(N$0p&cDu7rp?Ua9xkf>XSB21+W#Ydk@0{o%TLt<v5!A^xcI1G_&`G2PMbVB7c| z`g9w(^<6vK&~4xzCgzB9*!hsDLEjVe0~OVs?2fj@t{pw(%wUSqA$AWt-{Jq>h(;T^ z4c%z8vD*l2=vs8`HpYrXo4Ac#6O7Qc+th918lV}?Dzb=8PF7^2bCkNkCy}H2V>(ig zVm*$GQ}d`O9;e2lvx%%?qmvEU;AAE~i^wcCJDZ#_>LV(U#}F}AjaPH{YK&Lo)Ldgc zG6yvIIXR|(ta{kTs4{#MIfi_!4wL@~)re2&jm;#sIGdeJWXmkFiw(|tC%edoKE&=} zsu!QpOZzWXi9PIpk?!^cUSXa!0hw!!Rv%LfJ(_>R7?ne;bJjXJ#Cm5Pm>r!_Y<0GP z+nlZ77GC2Z*$z=7`J7(eiE0kBvL>pz%-ou&CZLZ~_1N7$j&!p}srgh~k0SqQ6%lLs zy&n-d(9891c2|2jHId!y3}ntI+N+6bwsnA<2dTk)K}YaN&W=(e)hE<%k5r#h-@QWb zYIm_$aC6+%?m+Y`tAlEf-mkx;n|QzeieBXXoIRkY7u%g}PI@wD5Fe<|s0#mp3?tRw zR4R6{|JFO(oxm=3XS<{7pk`Se)l4Q$b;O!!r4u`x?M^x}q!;_hxnCbah7Z(U?0wXh zzNXhXt=Q@8aMFrh&Q5R#(JQHk>|}RRGx$#Gq&lL9b83Vdu0E$;Jq?j*#W3{+)$GIY z3|D*fH*{3*A=_R(HM?m^Apx=dOH#M*C z=*vzbGPM|jf2bOwzM_tPC;na3ylT;RksZ1o)uKCegO2PScy@+2%vgKOuBwZwq)Q>h zUb@k`sJ&)q)d}pPIx|Of71f>@nI!rTb#|3>Au1z|*k>Mc4m$hjTkE9uA%~pZjq{ z+S)X7JvFy!$e&jJL0!Ur=MQ9`vz=@^Or6PzUmH5Iz$nY9a(Zgw)5t%~ea>FzPx|Bb zIc4ydrJ6DjJ_X*oTwrW7d#Rpk8yU8nNpb@fzDb-)Ef<@6ojuNCI_&m3Tg~38m)dIf zQN6)lM4Qs!tciRDeq{_%rO8=_D$W=Yh*acBlBwiIs)$p`O;i_`!e1JU6)|E9dA6E~ z_*20r-dFWeo6UZzFW5(IF-z)kB84bPWGU)IQ;1lRKx88Gf;Usoyot!oW(i_S>hW?5 z^~~{dE7i^M>?Sa`cPmyLm=fGZg>#(TPW5sMFisvYa#JaJkp7tvbLu(3TzXD@M`S6z zhC3q5=r!C)&-@ZIoI4uM4GpJ|?&nn4adXhfq0=$%B#B)_EH-!1QNILSZ0>Qkb9P50 zojXJgR^i0aaMoiuoiv<5Iz*)=TN*ckqqP*q{4ZyHuGEsb6iuAKgnG}r%*P1i4j)SEWygE z?;+b>I+OBIak|IIujkW$W=24Q*b-Sm&*m1GxL1J7$@^LkQUld%nSspVeA-m*ZleJ8 ztGhY1$M}Ua@!}UMV-mz>PHl<2kptBL^+vu%ClH_Lh7)lG(``|57iV`HzeZAuIPq&F zUZeznLBEy#RX_Ds4p9BUH|R}~mGqcyf}MON__w(^67PEdKbtqf-D$k17tnW-ZI|&I zvjF16Mj|&w!ui1Q?mH%L_ES5I_o>X?LF7(jLu3^_ts98h7zyVOr(_DTVxI7JqafA3 z+lky^tS4pzQyx~+8yij^R?I36m{FX9$T)YKQHUzwZNzUk))BLwSr2RIs12tRr(p7L z43mmuuvsTh6Aq`u#z-H8*3nJDY~lOfJ#U3^A6ahnrY28!dn20rntIqjBCnC(BX`-o z=iT-Grf2G|w~{WZ2i|>eIk=o|sh7mO(q3wRG9lp&m9xKtC8(i(qs565;BR~#-r)T$ z(v!@+sQxpUkJ?i+nHJked&k$L4^@B~c0aYr?1S}A-r-g5dUw2k=-zth{Y4+vL+=5) zFV%sY%)Z)2dYAiRZ8Uq3rzbUr5vI|;rB=7N{(^tWOX_}EIhilDx+8T3Rq#o89vorBs zsPuH0^m|?_OcnWgs(uSoTm2X3A8X5*r*WOL|9RKFb@b(3_tw+F_Xz)EYPMG}f1{Ho zm=D~E44t)W>|Xae;_0My)Fcyz9}@G38t%WD<8hVUYu;6F1D$^z*zHKwDL;7b19l%$ z;k}XxAMG`ddByED#jNA@>~^5iRAIH%c)Z}Y#ikC`yg=*LuYqPQEFd6J$@0d4R9QXe9=7}TTVQ? z=(gkv`-r#ERoTHjuNBfe&`W%tSy+X_pDywj@{9QOv~`gpeqnMJLF#F3%*)hPw=u6! zdEJIQZRs}dU~V;L@hY>KFg8yd_TJ}gLH~Wf5%r=){k6Wf``3BUTZS9F=vu(7BkRJc*ni>$n(Dcp5K^?)M9>7e@&zqvN}@U z+(Lz3c{-f8fSc)??9XhogI<3`(^{EVsS0mpUZYyP6**g*GsH>ngg1knGet_jn7=ww zfSm971^gydx>lebag))K_*QggU#9~7L*i$M55+0(q?ezV0)BqKDb=$1{bp3m#``JB z5bv*I@=83`sz^opkvAC?k&VW5aoRiOP3P=~Og_7=wKNm_c>kYB0s zG%6t*jON6&ppX1NYTl=bGu~-$nmFs70Z)@9(NFMKM)GnhpP$!nPK9q?zXeskQ;C_z z47UHY=JccApr$?#{=9xu^CmU;P0d@>-Z#bH%$y?5d1t*T#7`BuiOJ*V_FGa@oZD|j z1#uH1o0^lwdGDMznaC+37yjISF26Mu#5uuSehx4v*oF$?9DZA>YqNtn{28(ez1lP7 z3|Sc-#UwwKf8I{*C;1oPV@%~YXD-zc(Ht2pX2}i4Rd1H8WNt8K5naigC9ir{@XTcO zp{z>(_lIPgAurl1BM-ET_60IrL=wS7z5?gSeBN$Kwq{Jd8p;f}rqN+cduzeOtHIzP zW}~&h8YHHZ?L#?TR-@N^wwxuec$e%4bWU7?zwv=~mOSU|vvwLkwSU%5>!6+HeF7W)y-l?>D5R9SJ~G>O(ie9(hkYO@=de zab|S&7sV0oRXN)@+DG>0R3GG`H$~PoYnW3wJ5_G7H`;f#O~@VX6lYJ{r|k58I=^A` z17_$ojE-csUPCf8iuRQkyz^dPdC|K7_CZf3&lEXX)-r3Fo9#PvU~INGp-+ZEA@=bqSR1Kd@eO4D$x-5mP@pftZPMf~?CFf(f#o zSr@+6O#X4$RWtjU{JKQei;l-XK_0{NFHEah{LFrx=vZbI)?v49^eCQVaG+-Ov-n5t zY<^b%2zV5x(rj3V?d*Ow|3{`8ZL@zww%X5Sf7y>IwFA)45v~m9<*32zqI?;3y&npxjg|G=QiXnhnDo zl%n?IYk3Nee&MH1NBEu+&zwYA80EM`S&N*=_msV9vNT$5RpISo)&hdW!r6wx`Y$rxUq~EQ11E6&R|@L1y((wa_55MyNVCkbK7Ji?-z% zv^e{QXTmcJy{m)xbI0`d^UTVMXy{F0 zekzJxf8mQd8JvPv*WdWrPBxF?nmY-cY(8~|n9uO^9*QPaZ}U8=xxLK`sOI+J>YQ_m zvrNhIl$KxS1CwQb`NSQDp4AiTpW;sZjPB=dwNPK@Iitah2lHw4f}uC+R%e~hL|^kW zbO-ywb=K)?_96cR&q>Zp6_CmDG$*6-$;WU$!LfWe>RB&f?d!ZC`Zzt|>4mn|MU;N~ z!S|^+qve%J@(ewB!PDduT0vO=EF=qp1>`^4OZ<}iI4_Cb&LejOdR&iSe(d&urzfgi zm(UaL4_8&uAMLGA#aT{dCCTGjVOa<)1j}(8j(a=DiC)e_cO)8L58Y9yem#Wkkz3!a zg5qF(vnq;-_0j68D!QAO(K_x9a}RS9T#0fMXS$N)F*uKFC)}P+59fs2%jpRoCqIDg zq1%8n29-qvqLSzaLw7XBuAs4eR4XD2%cJxj)BeHpxQBC}`Um*ik4B%YAv#)>L|5}F zI?P?E?`Hn36_rKg-*g?-PP*OEFF%Pdau2Wv--vs3-FNS~V^B7`=Z-}Kt&v$#l$VWQ zsVEx3S4ng+ub~Lt1myo8SwbG6o-=!_-f?fc<56Sl$Z99>Ci>WisX3zE zawnj}c8k^9?oD?h+H5zOx#iwqd=s365?e*io^9hK(68i57DN$5w46)%Ts1)SYyf;Vga{JWXeq`bK6rQeKvm zVO}c!z_^iFURseKQ8=?AO;A3wV3v{cuvOr^QDxYw5L>jRIG~?#m*Rka7CZyvDt9G! zSw-A)M5HNdY61oevzc(DoGb@Jc}_n4MlQ!0yx%xUQw5%?#Aa;?JWJix?mcwhSHpDA ziT+wyPP#-{X~HHVW$7x%398@8Iq2C0RwXaS&HbFam{{VDaPOk#J_4q@PAJk0Ew>Q8 zX5^MCE6d1R{IW`hp{%wD7y0wB{{3Mmt2CAl6$pz)XaD1xmU>VR4cUf-ck8p6=$`CHrKt%%3Svvc`l=Q z?tiK^>U#fC`A*GYey%&)y-uFZH}N`n&7I@UVm#a3=jYP?@b~$-wOpF3#<^qNA?SnL zS3`_@>MnR+-BX?#>yB|f<&yXNf6%d?h}ZV|30iJ2x3Bx-7+#uKnqeSvR-B*K*hw6bEY8>V~>rmsaDk+B=CFNnpL%7=G=g|_hJ@D`K z5BU52c9%LM(FQ;~ph|_la ziCP{o4~$B+=d6>Wx;+?>ZFs`URukO`?f~PldZY%xGZ592gPe^U&ixL8!^lhgIKHDx z{Db6OeiCQhcEP;cm-O1IDIEt;4OXh1+244g9;^Pa4KRN9^Kw@1cj|Zf7L`(2YLYwA zwbW#Hl6yaBhsNRk;2yad{rk0MoCG_d^)sHTC#oMj{f(V4{O<4c^KlBVIf^Cw!Tp?_ zeGs%kJ@G-%7Inl2!F_UHy80OcW=jb*#hvW_=I7@`;BWNq^dANfg4SjWqq*^i)`Hll z^`X8msx!~jQ)N;wz^U#OcZZ+MDZ(9o0WBHKPk)GcQ-#ztcdFZ)`abB{JXg=uuhi`D z4dz3tm+?Y92cN6n#&*9T=M=ZI`m3+AYA9Vzcc;0!n&D1&dm1m*3)PeQUWUeuuHFYT z-5KutV3s=*oZ)Kf9pm@G67MIJTb6h&QFB@1Ehg^@R{1Oa-N8zK1-OfxXyvgU2Z_X^ zV3F4f4VXpLE%ugrEsTBIQm;7YIG1|+IN!O{Tf*G$!D@e%|2sUpP&HrfFZ1^VEBxi) zZgP_KkWVSe`cM6tpl}JwDE_tj3>q+pK@zdZ*u+VFb0?k6N4f-?- zx%(n-8FwzG?F`oVtNoqa>vuHL_XNxQy~I*KH(d!*|IE_!oYLs&10#&i)*a}HrtM4M0V0&l+8 z4h5YBa4qo{pvb<|-w~|!*MMvM--3vh4~7WwM#aOE%Zj(22hW0`-Vm>_Hjm!<-aM~8 z>N~#%>-@F;uk`K+Qdn=)Yn8%^kaJQWZ{@UJ1kZzE-cY)Rd4)KKI*d^vZ7#j@yzTV< z8f*{N`|JFaRtoF2N=dv@adhRh;;fg!iy+Q=6}$|Fd&9hf+HhjKKga8UO3)k_=6c)c z-5zWUe)iY;hE#b zQj^1)#msDPme(0=qAgTz#qHo1e}lgz*y#V_XQw9C%5J?0UI#O&ndNO}eoGL;Om-{A zdKt_NsRrnWw^?uS0MQd|4PA{5&9QM)Mk zO{_p0|2G(RiikPJ8|_74PJy!KM=+-*w)#(D>25qlo3e*-4~F}p1!5uk>I-nxUKs2U zD^c3tAy%QxzXP`4_$OuzEXo|~jq#p^Qkz@-XQ8eB7XL34ExQ|k5#5Zt@Z1aC4W+R@ zw(f?~T4}6b#cEsteuZa;28tRHp)ln2DyBfEtyo0W1IxDT^vFf8~I>8(7y+n0$ zlmC*~=x-Bi@GRH{+jemb&B`vuF`~0^E0o?!XWgRrc4(_ui{HUkD!1{7c%nDKbInQK zL~w%Vp);DEx|^X-tn`+{ylZX|>+nR_Lf2MtgZY~%lV-3!u{MkK_#kX%bqg=@CVP{- zF!c_~r5UXZ)^%!bph=pM(X~(}E2DKSl-bH;T?Ma&u7t8!nXM~~uZBiz|DeG+291Cy z9!GU^45Q;H>b*i+G&Q=TufR9t)Qmn3h3us`&WG$J!n6&>A#fS~^@5qjph+GD=V;Ug z#%RYvV~NhjSgo@$(@PWDjQd9#SYD#lx6$9s_$B!x_)~{;d%0L9bl41gBn+caGB}A| z=t%7p8lvOio9T@sW_W4o-V|84cP|o_Ey$_RO?`u2;2RVIHG73vE;M_kSOG4FQQ8)6 z=8{+_M!+^w8=;*>m2^CM2Q$3!#B}dNG+5uFKKK@vbg*v>(xD-^DR?he!ZMut5uCW* zh$qP_BVA}?a7`}63;vpv_^r1=F=4vbhM4AkfU@hqXc_(s*D$(su5B*9RPRGvA}#_#U0cf9d^C4rX8x1GN6yWt3?9bGrO;s2|v0n=Jn|rpU?iKQs~hd$;8++26Y(Z_CtP zM|2)O#s{o}HUNLcTXG++iXfxhdq3w^(c@!WTU953~d78)-NbSZmz59EE>3x?ia zO0OGg94Wo-sBxr(;RElrD@@aT?OLV)Uy-}Q^o!_9Y!KsM7%#iYpT&C7O>PiBgI&pE znI9*|$`Cr4Z*WU8&7R&v`9SvMUcI~&@Tc^~usT+bktQmdZ>b2GZ*d_q&F*|pUd!&V zt``xn2Wlb_uP16E5xP=%J-kQqq3i)$Pp`Z8SU!^7ndyNWU@vq^6qONgv=r!ej)r-R z93?F@KSxQ4+UF?dN6T*B6Zsf?DxZLl=?~~tc=+{3&%|dO;EMW`wUKm-{Zye_;p+yYO=U${dPunGQ&L-pRWmmCWJFf_eJ z>aXNx*tUS0_ul;#K0ov;;f2=FyEeQg{1aY~Yr-w@j@*c&{Ey&|crWgdze+E(gK$Gb z^ggn;90K!Dw837=7jiVbFTqjdO)zhk6L5TQ>`fqk@K(bHFSRe^49WI_&D?q(g^nS80*kASo`_eg6hS6)CDIL^V zXTt4-et~DB`~}ZA-D{;klTT$U{kePwwj{3%x5kBYCH$+x1K}B@&yq8x9om3bo#Abu z>le9#nw8-d;WoH@w$`7@u3#(j0O|*#%{D;xm$T(8x@HqH^fSF1N?=WcnpEncF_ z>0J@-uMd>e>VxD!Z~*=5rNCKlJ(WMpe$4mRmr=hwye!-f_tJH&u9xeih4;Hwj;sE>~qpr9+CgK(UhC99uXV&J+ zc`~!MK+Xr}$t+rSEk+wDvlAoaJDke8c(18^gFjk(wA^xY#{@iKXN0GR^TIL-Od@B3 zA+web$NGuke7HzX3dd?A^Dm>env8ZpCU25pgC2rib3z=blSc0Sw@58?B$cLdLoUvQU~xY2b&*X}~N z0}i$q@Sy78J!j?xu6CVKzq8P;87eJeh>YW2IdR>c9iA2b1m+B=*bI?_rPK!Vosj6; z43QUcvuf`>qxX6ES-1;&d+D_$aCq5c zDwoJuH8(sb9INJq=Yn&nenQPt{Q0_}@0V6vCYQ>z+H$!JTq@IP*{O_GX_!f?#i;q= zdEpplva83`Kf$Z7I~su>vzi9YpcQhtOs%byE5H@`)e!Z2J67xpjmX%xo2c`4&U%w2)=s@0QTsr3w`)>rQt^x!JlzZ$+0PWG?i!j=qA z0l$d9G`u8S#4k*~Y^BB(^s@Ca?xL4rxPm|Sb?XCl!%B(2nO)CK;o!N)Ky3SXr6l9kWDj$2$l`1AX_;Ygu&6A|@YK)2qRt}a0u z|6}UY5DUY3sn6%<^>5%hcfm@FbL#~w9qzFgV7qA54ZfqRZqO4&#=4Ap>YZTd9CQi- z&DS~wN(;2Kej0yaI4!XtoaEoc^DYUty#9H3E?D0Ob%P%I_e6KSBlVqvbbeZYK{y>T zADquOBhkNwcU~gBNq)WH`=Gmi&PtDe?l~CFTOH`?7<33CXgGBUQlRa0*7^hw-?P-5 zv-0@2@#D(_L!#e4NQo9yduloa?HIQY68t;({U!K!@%u}lGLL_T-m}&jD+7+bxtUM! zPg@!B%stJ_8LMsZ0s2yHgAdV~Y70ZVpiPhpC8{>ev<+G_ZWFW$K0>Fe730>y5O+U* z@q@u3?oIKDpWeSI()+iBlnsLVfi0zsV*Q|AFvvZCr~Du)2fIVvKX3^j>JA}?r7i0P zVO%aBg~N=x>tWele;mFcGWehPH{iS}Zo`?*zb(@FG3vIs#gzrWl$LB5GzbQ|2l28W z=pM2Tf(N+AFn2Gm=)>H7xS|i^Zu_k3u-y>XMMgh^e_dqqGx~Q#jLN3&z#XH6Y!oyM z1ZBkWJ~> zV>KmqTm9X`)*hJCse^9@l$gHl2EPiJH3YAyIZRgOI1`$cATfXJjSi>!VY|1xY>#2xFlbuX;bYe-!-34RRv(AC#HC^F%Ld{7)9 zUlQ5;to|jsE{nTV-wofj?vORvG-wiNvRTj+Y!c|QxBIvCm(|-nYW)rVW%Y62Tg_Oz z2*V|DQN;M!{EH&HALI9;rnh^6@kQ~@Y92HT-ckA9>ggV{j)F(6Uha8TFNpIZ*3a($ zN6kCyKdVL1Jop#<&-&N;DQFSA1^>0)S}lX0f;Zq>>y6baXc?4sTH*^|)@g->rQN&M-7px=&A1d-dBvaHIWLh< zQ`%{b>wN{MywluGVl^+WVyCTBRslT5PFuy@ht>n|k@XOKV3lyoxVijzzYKTC<(Hzj zv{TAy**Q`Ska0J#{<#odxl zTel6^#x3P!b1FJb-Ar`H`2#QB+t9DXV~PgtpNNc+c1pf?ZBY)8pO=q>6Nai3U^ts?GI>xos| z>EO0^i^EgG$xTfH-fqXpxy5nvN8-43%=$>2u#SVN$XVRXZVtaNy+z!tjAH$)ZWeNC zYL8jPU@PwA5+~@+MdTKRs4VOja-UgGtwQc|>zP%Qnqp2-r=#1!E$Vb~JG$}I=Mn{3 zE#ww-Us%trBFq0nZQzW}Dtru1@s|DQr zjFZ7v)=MkD``UVC1{daE>u^+$qYq z7!L3;ZZ`K%@GrLrGex~3UQQ>@Dee{XVx6N@9s|?j=61sA>Gp6>IH~yrPB_QOC!Aya z6dj@WPcS?AZ@998S>0IwZy2*Nj`h!rf1DFe54SMPMZCgZypz)@?B#Oeof2Mg?oz_b z?!EVcR3c^;%E9m8RaydUc z-Q2G3&rWx@8+elZC!BvdYhXGf4!Uu4A0!UB1*k9R74Q#Q`@b-3N$+?k`k#0XL8jQ+dQmhNpm+?B#J1oOSq`pBC%fQ~b@Z zV{}UFr}u!n-;F14bh@~m!C%OSoXjGVI0VCC=a7>Lcfb5FBzyV2L?@4v-%D~5o%QZX zybagmn0`|H0mFXx4>uP%AFKJjgD@O&_A&E^yU)!{KHy{#nZ*I-4?20N$>-(u@;XV3 z^Er8)y>0?kdx?E+Qgp`K?_?EO#D2OCID1&#>+W&$koUNW9oS9IMmw{Y$=hgW@;2Es)X%uUPX}kH>1qRh@zd2WxXJ%Q z%|`ndJBydu+e~Ffa1(h$wBJE5mY<#tT4#QKHlQcF2`uasa%QUaZk(8@W{{`BGhMCY zzUxt?-Rf*{)-qm)%IpTMkh1~iU+fKbRxgXU#olaZ1T%UWys30eQ&ZJOT<>S893ocC zQgOIM&QdeUKU2TK{@KpvW%ah&TkH&A2JaJZjke9%>a5YWJKMmm+-W2CDdcP<3OZ9@ zo2sU$P3}f_wwk44#T0w1{fRe)Nbjw;W4vr&Ht%P9wf3vC-B}IK8Wb)!Y6YDML;(JG32GHJtL;^GPA|?|WygCty=7D`N7eXuXQwlc z%JFKP`qka;u4HwUy;R%f{O&Aeb(uDn`EhEj+Ts4{jseH2G3qyWhdUY^qeiQp?r-iW zaI_kwes_1eYxF7T^{&yUqTJgffLH8X4UC855mk6H{a3H8Kvb%xzjOt+_j zGwkVhH!8d1%R0-RX|JMwHLCX0Py=48Pv+0Q7DfBXjFY@XZ>^rsN%9uKvlu6dZ^#1wlBn)`XYF+_s59EKGr{m(=dc}Qrl zv&R_{+UM*Amy_p*2C4ySKAa0eo#5##I*EDqTzjmZ;N|wlqQ{!xEz@VAvAj&5jq36; zc$Vu!LqkG)oT0>SXI^NK8mQ*MGe6Xk-cF*Um~YRs$Dxm(+Z(6n^5VhVUM_Db49oOk z_+agJ=7t8VL253&^FrfM)sOd<=yOnjUZT%M0eT6QOZDN@?Q(|Wp|#uT0B1+hK`gN6 z+jBxg)L=CShPk2k%yhuVccHz&UQ92Ytj@vxY^WNdW`~BUp=yyn4=w6N`h4`K7g4iV zpT+#_P&>NXtLy zT4wQLuriFAACsMFY{u7>P$%BV!bfVLup+j1i%`{zM!G z?oxlxFF;K}{00lrSJ;(fn@A_3%(b*cusk z{7E<%+=1<`f8QU^XL#R__g32X{d-*9_gC60>}2>0;D6XiG!)6^52BGM!ri_X4UEya znKdxR;BM9cwuZ)!Mq^`%_9L-adjQ`G`vI}szU@!OA>lUny5r}EAsPR}A}|y+>++o| z%BZfW4^IQ5iLn?3EcsSgI^Om2NF5DlDg=mMDM-h0T_PsF< z_qOlpt!Ete5BbaN!^BeihCdB2h#U0Y^pE(5{iXI1e~G;qTxu_|lguW#B`3j#qa-dc z3$zNve622Q-{Z719(TCw{&c(~uETS~PozExr^=?HiKuAI*B0s(agmv?{R#JC`_si+ zTr?92ROT_S__OfGxZ=;o7vl;wSN(74s$=9fTZrZ&H)f~mnt{~yMu{F8nL z9NOmU8HhQ0GHeAx$)Rd^A@vLT1}#ND;wN!A$ZBRWF9+GotY8-NN{}%$2hWs@q1pOn zKO=r`bM*XlCF8JH9e<_%LBHT9(Vu7`rf`?3!6kYx2l-gdk4Ik(yqP8kr~Om@WLBpH z7g@ao#+cd6i$QiX#=HPt4DwQ$4{yJkctGV1)xz;d=P79H_y|1AxLC335UNg@P1qTBy zoCy!Rr^diwK=73LXGSgNzfiT*;owkEOC1Rg2k-4nAuasg&K$}VdT(b5We(M3zLu)3 zzEB5)cg(!Us3Idj8+!P%e+ksMdIIND9OniF1A`~V;9yYjoKL8Qc+UO%Gj74p*b9Ez za)HmuHPoNMk)Q_5HPx4J9}K=E4g~+f|IYr;&Kk-R`p?c5${I4ldiaw67|tg~b-HS( z>guoH&)_Ti4uA)O{lULf{%42629+V=qW{Pk5)2L=8AF31;Najfj&?7MT;@w6-mIqn z4*m+N!BbsbqVJ-A$-d}c@ZZAoul?4J31tf%H*%VB=5Zt5%n80EKZNa(@z59+3=KYq zp_=+!9S#0wd@MK`T(&Rx=l#p}CGr~>-r8^M?4g*@3AEJX%m;Km#D(qz<9~=8<`w(A zf6l*RUnbvY^?`BU7#<7@K7;LZ^_t!{_G>#fls$CSKIfnHui970C*jCpo+M(;d(_`I z?inM3;lZcscyJ6nM*k~2M<_P*ir&|DRpvicRn>{$cu-aS6PyTM+HtrkzO-}VwfK_C zSN2^P?%`ZGG8hru0q^2mI4T$!RH44AdSS=o&-jA+mv&`!GWaK`%zPE~ocR~_Z7S~= zw~f)ksNk8M3&+N1%s;oEGJXc;#-;Izoq%WK6UI+%ojr_E9s8#4ZcEn|1WSBf+igV@ ziud6kyr>3#R7HP*SPweR>HL)X4i`{|0P31MB!ufC%GWBwOY*Zv4THrv>zaSm)_w~x~8s@>zY^XvwmIkEI)yD&1?2myDo0c*X%2-T~$|95%LvPlzg3@ zg5WiBEBg$dgsot2ZMU^g;YQfjK54|7ZS6K(wY6jU8UB|0)-hXB*~)HdpT*U%oqaAi z8?>{}2j{@H+9miABfIouR~vd`nS*xo)HoC(_7?a1}a@6GYx_+VV{HFx|5 z|LR-zP5UAYmsAVtf3l02^~`a>ZuoSqy4~JB6MSXfwr|;AQTerbfy#^Of+|5SZjKGc z1jVTy3l<~qQM>7?VOOWC25~xQ4rdFyxqSh@$L97$d?3Fx@7TBPFX8;ktZCPui69Kc~z3TohP^}UeaTN62$1Bq&YgcZIr}mdUUW)?WMAo zUDG}l)Ur?V4X(xLWYE;UgcoH~`!ar&P2q25e*trCoWSqdckOd9pI7HpDe^g0nq14g zZ{M?PvHFGihuR0{S?15FCNMO$_p3jc`H^uG`$zkVaoPCMzKToc8EVd|GpY>vj4Dg6 zX+E&;+cjaUWgbxb={n8)8P%BjAMF~f*2IbYq5XjIBm1FU9jsv6cb*@(l5{{gpj~%9&!msHiHa`E*tU=aH*ZU&E?y zmBUH=E9*<^mhqK!6E}yi7~M4b&{0867vI=l+tcBhA@W;aSvQPo)K|BvS>^E}?<@LH z)0Zf(ripLuZ|rHJj{Pn84L!+Le(IC0>&7+k1|FoJ(^bv-+^T@5c|Xxtlvn+Ta%w7F z(?kI)*}7(Y#_H$RXI4dg(ff;jqMYhalm*MG(`pKpQ^geVon6PCBI?@T*#+sjY812z zkUypCGwV~U5{~MVS)C%PGXB)6YE{OKeUkXzu4_+XezK^-OjWCjRRtIKiK3qUy*-iD zNun|{tXWm@a<6QCigSAOyZbY)bK z@l~U-y28yuZmm6 ztT}Z5qrPFbf&C5Z4efT!w^!{{39Go(PL;GuSaYd3q2{VNTcxblbhS|nS^FDYK>kII5+lVg zRBlwQsA&zBu}WJl!B(oJDr=Ro7OB6~pK1|3e}N0h8`NkqN^GF_7xj}WXO*>nqOzr0 zOx+Q15xE8PKY`_~a@G>&j;JMst~F<-g=(%USmmvy%;833)m7gq&-#u(t!KGphZ)y$ ztnXD_HY+1r;q#CM+T#ptHi4BY& zaAjIQs7A`P8mk|`MoL&A>qpgCg_todgK@~xttRS6r871x&1$NeD2*B2dM}!(rs}Ov3Mlvd-c3W;(PCjcnm%k^}GgLKNJnThupD&SD&i}-UjuvYRJmZs;>7`JP~!N z|K9tKab574cq$rs4OwkOtXHMHMqU)xt97c5_gp*^b*TByEA5r?)~V9oTD1mTr`D=( zy%*xS_?DVFUK!Tcs4~QA^^NyZyb#~8`mI-%mDTEN@0EBdzGnU#ubj6^tyJZhT?LjU zf91Uvuf$i>eC?HIeWfZ-tWaNiZ^UcyC97X~6}%N{xvIeW3RT;CE8d9O-oN54_=bv# z-g31}RitXU`hxk|UM1$1DMNc=M;&=8{eRqCHDjiN)f}u$g`rjPDuY$MD&VJHRq#LY zuQ0UFyiXaw6aO*(-2062d-0BOHScrA)xBz9GyWzFt%g^faZRrVSj(#ke&N*um-78I zw134HjF+jU-0^e%rNibLKcA?l4-(j#5!I^G2zU$;b@SPamJJR*=!W3NNDF5%nZW;Q#41;|;5!wIG`FUbh+f zr~h9!;mXij{{Q+%-uoI_W8M}=*`u?q|3CU6`UaXk0tR~n46|L(KG50o8pZbPUrl6#JJ_AQEw9-T-7R>< z?(H664|b-!WEXeOU?4lm9CIMyn&r_Qu8*E^efAg(W@Zq(ifl7%4whllF$YMOo$dqJ zyXKnZsA_=zaRYV{RHVKFSdTn}`oZjm^Gx6D&t5mrti+)sjP&;Ze4Oe>6?Ms4<_F%!;S$%D??u+RGb@e)tB9Vf!UW(<}iAP z%F?XxEobjaT~vYV!qSI*fy(SdM9iwpS3xJZH@UZrm?_NO>@tj)pE6Swt>RwMoiglS zOkwsSQktLf+4KxP<1^|7_M)PvOv#Cjp6r`UY4%`W<_F*hoV4gJKjh>@cXoDu$aAaD zgK9xDo=<%q+}1|P(ek!7nq958wL4thWmj7iN69-{3r-lk47CuS1)uXf_sh^{;O9Ye zo{%*Y)qnCxaooXXc9T-9NkD>;O@IQ*0K`pQeS5Xhhak4Q_0BZ%;8I70MwHxGC;u)tO zTEWwjr$ni73Tw?wE1p)?Lf!rc@kLM@Y|Pa)Z9IFIqn?rDWh2&W^E~Mz&U>_>tF^eQ zUDGDWtHeZbBKxh|vf73x%&9mL(va#egNEWuJOLW=Oty9q^_!d|8}O9&tDph#b#R&M z$?~#xg&cL7oD5E8r}ian3OlUp^JMw!pdL?|qxdz7{!#DAsdAi(I(A0iw?r}O=Q&2#74-+5pvH4GR^3M(Vl4I1_b=+!XWAsuz8-u8MMoxq~Q5bQIZ8kS`i!BeJ3)Q38$k zjP#WVN>g7-#-K7^1QmxOR1~4FqbNdj0y~M$A_LW>P_4*FE<=53S%$seU1ecTVs{qV zQF|{OWG7<4I$TXtQODD1D(ZC_eLwkDE6bkqF0w39Mi!#4vnWJ#5wUnE)CppV>_I_R zx`={ASFkH@s&cRz8))cI@@6_^%@;5oDacL zD9`I!Y5r}|wG4a$y7nPTGrE=v%@|$#2<;SION}ZEPbyGl(X})|S}-k|C%Tpn#S)&1 zpc$fTpYYkO6LCS#V5c5^ce4}4w;^gRryz0$Yl--vuw6k`l!bAHsUUah(RVkysQ4Yt zxt;o8^&2rrt>N@Ve6WVd1?CEJ2kUuL5(mb?Ueu0yuokta^63<{FKSak)Dgf6vIvee zh3$&65K&3)hJV-p-LeO%pJ7=-Z_|ucBln6^FAJPAO3z*aC1@kx?J+ zfodhET=E2a_2@gMy|C@kOW0AD*b-D0w}0VY8$>eIRb?{XKUL&5dIqSdWA{L{k=0+K zCmzTvI60FiSV1HPCGDttZb^7b;9OJ{RgV1l3{~ZHL~p7$@rJRt*oq3_0JWUH#9%p* z6y&o%m7mFc_GjpcqDQ*-vdG`l>uQOI4S7h#F{eZq)m#MIsrMrbVIv->OBNvq}y&Fxy9MKx4D7 zTF5!5=<~RR;66?zMW1+-#82m}DuqAR8OG5k8_^vHXNdRO8KR`!JhE5cr?-ggLm#t6 z@}70z=eeF!~lU`W&kQ&%P?)d3I4%#7(Vr zBQfx* zuJB)7)jr1i`(FGu+>76)8`0a4=K-})@c5c%F*|r_vqSvG)1R;HDE=mPiXZHnXwv*Z zO(VOpT?18{#?1V{I1g7}^0a6tPn33w-^Eq+8IE>W)#v!mMW3^NX19-=K<~DFUW-Y?c!|f7d+eAB|1dfM^5U|XSvmQ9`=R3 zo2Oj6#U4?Ut0?Z_ylG8)FK0$;*!%c~*WfwfK2e=#kJ#Y(Q4dWWHSPM5sc!VQ@~NC8 z|4Su@f3%y}$v7DOXovi$t7eD_!=J(#^*=ey9{sI+x*PrdeLB_C+=Ai8JQFO4M_Xg? zN4o$XN=@vhc7A-4n%J5jb?wwp?yeV^LDzKGgfrw%<~;lnRfw*F;X>gAKB4!X=6@f_ z7j9}dv-82x)Sl@^pDoOE`|v5ubT{aIz@Jgxoe9qjw{SSOonRNHw@_I4QO8dKv*}NQ z_b^%jlgW9*&3FQvH=K|B&WpN;zVqIb|3lNfZe$j0GhNG%`h;3A2)_uNg~LU{x$NBb zM05lWtE6yqyM>*E*Hm+RwtEuI;Mr~mKJ(f1&O+ND`h;=^D~A@vr8_wOQk!inLZ>^wwEu%+F~E*6eH zYcB>*(Qxr_^eK38W{QQ!(Q^=WhVkS#=*xc>c|+8RB!pY>ygwnFhdkDeK2IHsn!`br z8+WnR_G>TdyZRb+`#OLXZt`fZ_oFT`hWrwZ{%<2MiEkqD z;auT1c0AG6eu0AjH<3~3Q0!MZ!)`_*$QzK%RcRsWkvT(}+2 z(c^H7YiH*Ox9912j&OCpdpW{!Tvfn-cD7sL|30))H_F*=MPd#(2W^e0mt+*@qP$Tl zG7qJW@>Ev9&2c`O9+mN!obQ%nCh8j*^{}lHS%5Z3mB>QWMWVis3*55*_p>d_YB`)z zt3(#LRf)ymVpLGd;Az_#kH^mVMSdDtg0jk|k)B z+%1KdZEai_YqR!=RRRaQPdGVT0{t+@cm1BIfH{8eaM+Kc~Y3VMF(v?IvzAwFf7&nSY#!+|IZg2#CS3-f^$XV#k z%vta(xa_$mC()JFUm zX0mZ&KDAXo{1H(BMZFY$O21P$CH^O!(6CG4SHnqnrCW_y1+GHFrUc)$ukk+pn*WYe zbXN$cA}WFvagXc>#|M4~;zO`wG;^N6QaI}UyW0H#?SM+*4~WWW^?iu9Nqh7GKlD?g z1yDJhlBfb!!H+QoItf+75i1Ap+aio|Fit^E(xdLKN$9{9i(JPyE4y`_hy`P<999}R zC_FfvMh*@S0n>7IlhqrzC+$@+)=fRe$__@~;iQuT!UMzUujg5f6Gw~2a@NPbrH>FHrhC$G{UXI<6f zteoIAu2R#FiX$F2L&8^ZAj@f8A>yrMJ?b-?tUvckfW=|Ct&fN*{=k2W@ksX%l>mF; zNCNjM68T6DMUV0$IV?OJOwH9NvOgMhpK#ywGB;Ylg(H{oIg7XMz;heT*XLd`_zZW9 zRCxRh4`-15P=w1M8}kjzK<_8GWUY=W6H$K$udV9*?G&WG07|i`{b%^M#ap?oOL{IV zH+VUE#XSl|a_PCrAHs;1CLTh=!|~`B7m8febE7A65eK;3);&Gy-h2M9@C6*~60G}l-P7;uQ77lZbQRJI>+Qp-{G6~C zjO0Xlxlkmf{6LNhpU3wu!8%Xm0rQ|}5~oLfisMjxE*MEc#prMf+?z&)&*9#eXhq~` z)K4S0OpOlbK%crm%CXC6crF{3Tkk%qB--(W)*GQF07wrV4MWG2t_~_vN*+ z>#=%rX*Jj`pwFq=OTgSvEb^`R(iMK!c;SIpYeTs5HGn| zWj1-qy-fa;=b^>)YA}4xbI`)5cvthA> z6xT1h*<_5o=w2dMr@k6bPurrOxskg*);Hn}_DJ8xeYfKN6!pj64sOFmD(ZuM!HtpG z8e1<}dh=J=T9Ap6DBJHH+dC{i$A))f#wM zCBl2&%`Ri*dGx8W%NuS6oWpLwbKSk+HjZSFmAw+^vsdQ1a0z{f7j@X)LD#R|IX713 zkmuYSG7db?RV{BE`meRnk!=IE3D?BEZG-nz|CxBESMo~grNGMM^{hMtpXtx_vuJb0 z$=|%FYxi&P@9@4rC3jr-3)pJ$ZpT&vLa62fOF`I^u<18{f9E;o5M1!4vZeURnJ#ie&L}Enaso^tHrG{S?=^zRvq5x)W@&7 zj@JU7=J*CD;7r)U%7d3+F3vyf;{?S%?+@?~Ts((}hwdYHh_5TN!Wzum&Bty%>pQQmSI??XF6@-`%Ik%xFXRm3jp<`|5b?xq zN&QcFGv}5G@_XF7>w4cugR>?3y#ru8xvup+@2@~|oO1xD(>UiKE~asuJUQSE6i?8j z94MZmE;*1lxKG>xya|2=K0_Na2d7^SdEenvUJtCto38Jy`n=&OfXtmt*r#3wUyiWlgcBgX-*WAL^k%o6?0+&^I7J*n19Y;;0Z*(MZ?v)6TJc6Ma-#7MDus#k z<}v<~6U0RE7x(>BW@QInF()fg+&L(xh^gWrTB1`#7Iyv>cd`&AoH(--@8#mm(!7O> zgE@zpWSl@1G6~K^yu6O1D|tXp71P846i%m#oJL!#ot4vwC;u(S@&5B~IiB~Ve{8d5u5hbTLExA!mr0;C`<5 zp%Ob&WMt=MDJLUQ+R0@$;O%8D7~;)XIy+jiMhMTjlJmM&J=rzSt7g9(duMnH#%9J!C0N6rRkv-c#uS(fvH>Dk*_*2!kX7+tJ%W;ssyrDN}GIcJxg z!>*HEXaUa=S&eM0W+l2>Y0dJS;Y({)-~?V;cFLA_(y)`YqVqAkTBBHzGf;6}L8Fk7 z6O7|5MY2(VaRGb^XX*)N9&;vpf)mVCxV!x$QxPZS3_TC~l4t0NW)e7)tJ!)3FE?0+ zpNQFdZZm;#f;mf1P5no>gdLYBWNP~a3dkSgGj|d^iMDbM&TkYl;`w=c?#6T9oL;>5 z+)ZYtAA2z7=-*m(tT}Mb)<1?JwLP7^%SmP|=R*n^u|#1b7nSke2RPoHk{=MK!P6*5 zr=k91Jk5@wp*)R!(n;ntA}^Siz2LdMKJ0DD?e%5%N^Tf(d2{t|tZ%Kk+;NVc5*NKQ zGCOBf3LDvpB1T$x(%{&3R34Kl@ZmcHo{?w4vnXXxWyf|tGXc)r-aP$l>luW0; z=XQ!23z(VDNsPJd2}<RqjF)P^iWajKs39tmtr4!ka zU%;G56f}KYAuq}aoCGLnP9O@Ip6xT^5tn2pFSA$D$V8Mf#_NUH`#+wu2Zc=6_Uud2 zB`(X1UM8=Uk&!5EjN=SLVRIZl*^VbA_pPG=M`$LK}b?L3Av9YxK!5GT*PoM2q& zKD)ja>Gz4nx~~U%2HPhxf*I{hw#Qs1_Mk1+m+1G{L$+9dNaX|eh%M9?G0tjqwI14C z`4kjg0hr$Y#8&zzb_Vu(#)a~EIf(pTJon1UZq2zOiSaHuSHy>sI0g5}&TM2c9@$xp ztYB8-A^YH#=u7px+;fQ@%g)jKUM!L9PcNDgB!4Myca4)61{P$(HT|Kj% z1@yRbn9IU`y`}mx{SJIf_1yI43O(jtkJ#rL8%p-F69v2!dRiO<80zA1xDd|d~Kf!G^v+)GZ$MzGutdYrxVef1KFNP@S z*?Lwxo6W{$@-2Hgr+{v89%v{V<$0_7)lCVMtlA_mCx+wc4?er zvxJIxMZGMctf9hSVa}sky3}KAi^$F%&y}2^y1{9x)!S|6|U1Rs^YCRKswTpSCF7#O2By!kDYUxqTVaM4SSu5^k3}qr;wbyW_ z>MGr9^egsS&O%+`l+}9hDp!};X}n&)M2rD1lkbF|+b`@IMr!?I{dV|;{nEZ2erdk~ z?{HPq_()H!*JQPZah{#*`OxdSK(5Y?_K)>itkz_I`iFWd#;Np=^jqjDyt2z@LdeK_GS46Jhj+;UmfOZL>m1j+6}Ml zo5XAT9=&%t)Bg!48SjNNaBA`__ee&Q>>T-0D2zAjrI2IuQwkgGAsc_y%gkTmR6sQ& zjs7{27EG(B)9=G`?|&qnWq=e%*M+;QU8;LYjr(KyoS^&y(e6RMsvKOYt?7HQ`3iT{Ie?eRB9PyEpgSy^F&L31zJ|h1^6gzH^?K*f5 zzvmA9V<$V+!;e|{$SFV#Mhf*Bt3KG*d6aAD-kl}e4cgb?O!imy6YlY6_n)xqv2&Wa zUs1^WRr?J-L+>gICLipp;G>Z`kB;J0Hs#bs3#cBj$YtN;$?QIsL!a} z?!Scgii(!aCE6E(hThG^&&;iVd$U(gloy-5@}hz$r#wZ2rkwH&wVHBxW;}H^Q4d)` z>{f1|a=2T$i4x*2)Quy)rQO!b;;!-Bsi36Np1@B~rK!N4^2!!+Zl-#&EOkM9luY&w zZI2>UP2HntY9@OR*>)=%sl%)wHiC+9MJkS66-4}+fjVJ zqiqLwwe_s6EJ`ac(E2IOBfN07k!LG4ou#Q(+NbdF>ON>MccD_Szp|2?I+$(bxC`Ia z?rHm3vrkz^mMUT$)vc99DdnZ}$|3C%MXUu?#a3mTa!=a|?rR5>v}!u_fRc_Qlmk4?R1PV5L>l#wl15Fd zuJ)>l>S8r@#nr@S)W9ETo54e^xbg-~sNy`%8>g7^7A2};$~&~9is5kc*4c!b`9p0J zc%-fJs*4(871hqwMNu4j-a9M38lt9HNey-lu@SZON7_d4SS!NZ2d9Yg0d1!uIQqPI zHlU#XSla-eXe+#$qLx@e{dP@J7~h?bP9gk^BL0Z-Qz7LO|56L$i}bJ4&E8F2c{jT| z@jr1yIjUS0hf#;WO8Y-?$*-=|P%im3l#6(PRHt>>KcQ7qF8kG#>dL>k!qk9k;EL4M z-a|cmSGybW8d}zem22d=%1z`v^sZ4!mxo*J|B0hY4|^9C>pgh9?siYwJ>VVGs`s>a zQn!AcO1<3NkIv1`D?HX^Tt|+fFnYy5&i}y6>_4VlCeu-+i`~`U>vaM9ybFF!{G2Y} zc~evQkM&pl|NNtxgBMX<){i28por0${l|8 zwW)%s&7Su5A(R~2+Z~AK#VLFm&Qoh~N;xM^;{|b!8jsUTJG;Go*lP!lz(-J$IOW&J z+3b|x0H3i_J^j``YPZeeHgBTH5JiX=A!HBpWPqsZx683FrGG+Cf3XDO?!ve%T5iaiKUKhN8cbrY=Aw`&Jasa{34biHV__Y z4}u5TgY8tYTCw9+s#s~U-AfgVtCkk2=qF`-yO%naDwfoat7eQ1wujgmV?*qr@E7z_ zvMW_AWvn(aC1>lkV_(LG+QaNGW5ev>a7KEW7#j``w@29JojcSlm3Qt^#Z=BI@7xo| z%^Utr{}?(r5#Pii?1Z^Nd7__gCsB4;i{n6P=Ye=AN;_qUrJRRUmz8o#6DzZ;l2h4P zicZF9R-Qur=&*U$KLqaiU&S)TM%Z70k?=@+lwF0Dm7OZiaWp)tI498LILMBB{y}ix zKVzQ9PveYvff}hZWIJt^bV@moL`m=%ek`7d5>83yiKt43Do$1B7@8sn%=`G;9YB5Q zzJJy{hs(!V@|-cNF__@V#EFHWwfqPX)^JcCQn%N+YE zHp^3RXw`-A)Z>m$TccPF$y*H!qm$ zv@Scgwv%-=oSmSivsPQD{cElT7tIaYIn=&3XgpK+yt!W6|eTiLDcHQHM3 zqPdakz|&%*cADz2jpW~;?cniiIy*ouxRz7f`GYEggt1&?$Z76l?_Os$J1?25@prsv zZlX@{l-NX`joNm0)OK=ErI0X|10;z3!>(N1`cE2565H>zv|HKx$*|8^rCl;Fo2#_T z<`sA~z0KMy>J&GVZIiam*-oBqpblKesq18?z9K;^x0x)K6i!Ost<2PQ4v=#{JjQNm zuhdp)SIjNs*{uCeRYro??;w6`i?fxLTR=T$1uOnDS7zfVi=Zj5TmJf`-mg)?GK3YRicKqXs5!Y>Bp1yKXK4H_Q#JYUpeL zjht-E#ffEORovKO?FL$Ui?y5R;Vssd(EFJ>nK-dU+G6b%RYO11{t3il3+eAP7vd^= z%ls4`a1J`3!h_BsXH1aC%xjJb@>1I~n)aArbdcN3V}1QDA4QFITpv6S&xTAp+@CoOnGa)EKWmi;_T^KG* zz1G{%k7bR$W$(KXdFR+kM+c|iQ_g8;Vo;R&v57%3s?H`-7hV+AexKEEI3D+7Z^9rZ zV+g^=PCEuTTSP*;7_?vK2P@Jl^Nx?+oHoS9pXmAwWBF;8=n-;YTJ4KuwjBZDB zWt+Q0+X{ASTil)6E_f?(Cu??~=TXQh?Chew6Frz++HP$#iZHvhP3~?yi8nE}8`Y0O ztk~@qbP72pU)LGzs35@wL4UCkG{{oSPh!q!Mm&Fp1tC*6&7Nq={3|+34=U zHF=}E7eD5WsNU?+HlUuf5B-rQ&K}fI8aqv#eehm)pWDc3?5sy&XP>qn?1%T`COsu6 zMa|rlpfpu+Q-aC#te6=)=UCu8eBQa>ybNQpF!qwK=T*244WI+sT6BmaK7hZp9kXH= zoJg;rjJd`=h$HkGw2BUDtI-%b1Rv54!-usa+A6e|B0i!m)K;SDv`}l$*R|jMNr|eD z+u^FUA6KpY?g95_Mt)L0$mjTae2^cBZJ9ZMFV_L|n>z4Z_QCtu(ZSsi{V!wv&v-aQ z)yF?7Q3dpmIDZTXKFJq&e0*a6NBLfUkk7*R;Az-~EQjzAYfJ1%h7RyLXT8(WUC;m9 z|B)vft|LDx{R1U%7I;;mq zAehxc!3V)zToo4hyhPqpYeOS2gS8Z-S@0Tq$i;`}NGx5FY z>6)My+{^9lt_UODixp&ENll_1IKleR30!y`y$vDdO0XCB@OpY5$@3{#&aM@q752t; z(hB?FVQJyp)7$+J+`&ca18Y9=k+v1~b#2fO?&tP*H->&7gN>mK0(b+xWnrX{u`G;K zE|!sVdFbFZ)ZcZ$0Cy?l%fd}z5QM>|a3k@3a2LO+_dLpnpqc*%{!q>R9JoO>r`-${ z;T*JD;AoRWX^NKgpGp((7u=NClJOSk5dVhXO-npuvMY`KzwozejKcL_N-M@&qE9>| z_>Fc{o!tnH?7x*pAg9urkydCYN7dpkU*iDR1q0!Mc!9nP?%`PVF1U{;)H}Yy_rVgr z@~B#_2MQcZ!bsg>GtVQ0c`<-vL7bo=>fSk(h9H;H0G;uObKx4+!2bvLvHIwb<7yUe z4&ww{KwLO(5HIjTHyq@8U@$xw|IfEP?z>?Rk|tAfF<`hWz`MVI%&9M_yD7-5@-JmR{r=b;jjO4p+hpwVh^2 zYoXQ(Rm6p1E3hDJB-^7z-$-^qo4zsaMly{NIoG6x(-5OKKG{vjD4JzFAWdqsSZ^z!YXbSe^JJrsMsubIK znUtPEb5tqkht0vfFeS=;FN2ieMUa6!>5UA=6L}v6wfo^)Mj{`a=HzUKYx=ODwclK} zMoGIF%9!)Q_THCDCZ#<&+j;e5eIBtM=;Eh9fAB@{h4ENEkzbH4gV7W{&3R!{FgNVL zuJ))T=EvKugI54;iMq0$?Bdr2UH#-J7`_OSgXcj;GJJv7-Bx~f8I5?sW7z~{&$(eo z_I5xOG9UhOb!1)H)vp7(`N>dVd>+)6b!0ccHt6nmVogUBNu#>k#^{R94U?kP_&i7o zo&}AVnG-ewv%^}lw(RcL0zKd!cuFKe3-Vcz1UwBIqP03ZtSM{Bo_=CfDW3)n=+6op zpu{>mtRZVMUIX;<6QO$fG)M%V1ocr?ofRfT4f9D*53SW%VLdQ2On{!}lOO?j9K=WY zGvdfkstG!JUm8u&_se87rZzkyoRNN0H2%J#-uWvOJDXC$oXKd!Y*dvTRggCeGo$bs zRYGSr8Zy#|O5~^_yy55C?gnsFeH_(lHxIuyzA>7I-xyioX7pNwSOM@Mz)o! z_13Zt+(xd_3u%S5&R!wV1@7W?^;Y8Q-BzyATgldNYt|LSt+p#(o1MMF_?LF_I@8Xl zbb{;n`S28PE8EExxQ4ftYxNegCEQZBf?Kh_06V*R1#rgg>J?>u5xh@pA%kVz$AlK{7Wea#1|KiuPejPrn zHE}>F&iZ0F26y**c=@#a#Ma>t=;O8ye?-?ds=5EcsKfUms%)M?TuQEvaw-1n9b^eI z6vvsi4{iu~wH{tiFE5#TcqJJrfmdyBoH~~19c3rE1ef=YGLP2N>*eLa)wrj(Snnh| z%f)!fcao)8SyC&d^}-J%x7N$+?d8TnxtCX)e@`>0uCC|JglF&-v>?N8YTsG@qxJUsc>id9(5U_gU+3OlF6|$!ueVU|BD>0k`XXZ6FdOQ&k#<2g zV}agPc9RSAg~Xh!>*wXfsk*P%E{tzH3L=ey_(uEiQSdN`bOs&;k#4|4_#y6dkzzo^ z5Ad>kVQ$v9=r7DI`c}P@64i`%hC3Ahs-3v;X(hoAQZ(aSFd zm(ohZrM2;5f~X;T`4dESSwnVFqN?*Qt2>Z-zJPFU^ih4Jy_<;t^6K z?8?e6_=o=ZzAhaY-KqDrl3*Gf7MqRb@5V4i}bc;S+PazC(Xv?$CF_PwBlS=Nt5&*W&`; zL+OtWcMoL%+Q>b~)?FDXMu`gANKjFmBD%{Sa*F67tHM>~WYHFXmug{KP&IsvHt|lq zCmDJuk7(`EADO%K-SA_2ZE&Nh8jcVZwMyCuF_Jh{bd%lXRB}!cy_A0Fh4*4_Pi43m zAu4IZL1k?kYo>~a<|A{r-Wpe%s$pwTB^)LyYgM#iqKZ}(9!~E8>d(9N2Vf7pN8hWr zQX&O|R(SSQ30vadQ#l+es%q7=p<)>EK3dg#^&w)YsHWYcwNJl?hV@>(1wKHP!xo@Y z*c{KEN?|il5pGUwiaSz8I8sp7(3mZxV~6+g;2n?tL^rnf=Wfq8~h6 z%n*Iee)Rf+nea?8OAKJVzd691CZ^L~pm&o4%x-d;D8b(1UJ36#n%yP559UYny4wej zrR#2Ar5}8QUQw?Yk5d#V)-Al+`{8@}x0X}8<@Vz{c+2gDf6^_!nw$93UU&N`x0$`= z7V(ODid6)tR!Q=g@cNj2%~@g~k3PU0XwKIc=!4*a<{)#PK3^~F74cN7Fc8)q_b=^l z?GAZvyQSD$(ktb?LrJ_h`)7;ZW*_2J9<85p74(PuD+83f?7HLLb^p}<(gvFc^tt+A zG7mBbn{)Mfc=uj)2PlQS!k(}S0nI8+&Qe}!be`Xty~sUV^a684PkIs05p&_WVxAa6 zw!!8-GT+7VwTAYmc7y+XwM%-(bFyVbQC+GYHP2P&7rAfj&Ti`Vey%BSX#no`GV1e$PaeKfhOi-X(XCGFZ8U zBk~~S0h#Z+58NUAD|+Bo)2eIT%^qay4(5w|UVhKAx|#FE0@2OvPQ2(2#vAP--pqrQ zf88N?n*ED!^bjSlmyeZsfo*j)yO|3_SFliAz*~B#asdp3hv6`m$II*4RvzG3UCf1I zk?3M}C7#DCdbn~9jDXL7Zja#K=Q%f0H#v(>cf^q<%51xWHw%T%a$b3Fwq4$<;FVTK zn5ERx>Tq*}xyW2>K6Dp>NAM%}u{#rG&kEj5P!X=^Rr2PrcQzW3WxaAM)eN5`{l@7R-I4or*3g|lsVcgu9hG!XYVq2pco{kp}1Pvn+B?Q z<<;A0{Fi5MIdvX;p1JeP`NU#sados=42&^XuxmNISS%4M%q3!=n2PFa6>lo2>J?Rs zsbkEdU@Sb=9A{P_XL+@P>RO&vLG`TL=3H~0`OKXQp1VcVqUt!aBC{3LIp%Xb;^#2` z++9ij73LI_ZL4}yKsC6USKV7>E)t8yDrQ%jlTp8|?p0!MMYR%M5Uw@boMXOlXM>k+ zVe*bQ3#&zlh1A08czC=y0iIw^G-sK!&6n;h@XDQp0&jJ15~$%#MBz8$8eUDWpjt?s zXwEcWxv$-s=4-s}XR_~=I|0?;n%)FZ%bUUc8+QhH>lRQ8vc3SAWKK6{m~Y)_#E9SG zT0hl1>y`_rn$ygv{SN2(OTm0pQZEOWf`}KOxq3NRXfLv_1dGr_z7j09m%x|lU1a4Y z6cNktGrkziL)Y|Q+L3lzX|Ig;U$6u%=Ks)TTw-4hmfFkUWvE484gRBd0adc~`UUXT zyukWMckQiN+PfAkw^!KLf)(goUqfkfIXY#-m^+Uq+OXhya4lGAUk9t;RVZ}d2v*x` z;OoSFc4f7Sx*y(W$5mFFYs|RH8Z!=lBWujHW=vUYu7l&y+iO=*tEzk1QAIsq=kXlt zfL%$gOxv+4!MVLW-U0ILx8o_R%++Q*Wf4E!cuE(3&hf|`7blaLvd-LN@3pI{dq6ey zAiECO@s-YI7c)L9<0-rCJ$5y9H>j>2vj6dNdxuza&`zLqGCP|ISQ#Jpm38KNGf>u> z8{m*$LZzeG3GT#-gvu1Nqq)o8ZC6)!fg0*z@*J`c+qt}dJjw12=FMOY+T=Hbwdjc7 zL|b%?z0=-h*HCwYn(7f&9=4Czb-Y|&BC;h^5-F3-DJF%C?DfG$c%!+=+`+z@>JCs# zJ<9qc_EEdGSI0}t`b3I{SIs7KyIo7It!}q>5RWl?)IMg{@@ji7bDK?rouPg>vdTdz)Qbt)p(U>!@|%?erY{bvBz0*kW#FzOHI3v`kys zYHouadXbLn2HV0VXq&mk-pZOSpdLO-+sy4IFTO-W*>3KDO`@*sFsH&(&2piR*U}C% zgG{C*SMXFor|~p=3TKX_cq4tmcm`?srhnWvzzG}A2J|FP;+JqDIAcW0jb~VY+R%OG zY~4R;pMni~mS4*|1|PS%vhE+VkJFyO_anW`Ad@Q@WfCPRJc;i}Mjq=6nNb!{Cz4{&;{AvO9OU5(G6L>uw56<$4XABJ&u~W89Hm*JT<52vz{qZP%A7{m};CSRN z5u7t3J;`&dKWjLwv3-F**(qCq)9`8gjGam5Q}e5tc$6i48;er+S2C}fPyLF$nWReAGjKz6Exe9|cgaa%bY9Kd-c;z+Oc9nOCj?PT}{rB{-H49b4vfN>~D zDl;fw;H>lo4r592{>h;1WAtFK&)82)f`d{e{X z=X4HW{PVQW>80JvMk%+nd(pULly)!SLvvO?r^o!WAdY_l{a^`8{0=X${=8m>m8IR1 zZYlPa1Xs|hdcz~U2H(ne#%6nq{m%GCW}%%$zD19!p85^#Ep|QimGQ0oPQGHtxAHwJ z-x+80vw9r=U;Q51!~gPF7xWV3zG9RB|H1zmSBU<=iv;dn)Hf%8=#U3wUt6G`_>v>Lm(X z-^o*YTtA+FN$zLzKQ z%#81!)K3vFv-gsIS&tM=KN*+pjrJ!pd^C!>#mH6^Tt_+V2l=CXZu}^Jf?v=p;udwU z8%4kkRL7nhKS{;B%udC;WM8&V=<)po{t5jg@ru45McgaozpNkEPv{B!;~*iN5J%Jh zn7yK_>{3kCyl7vt3%fMmdDtg$Ug=W`-R-X?oFc*xP@NY&oY~Q z!rGtZV=*d}owr}%U-2Tlk0M;ezu_|$$EoaAaRXO11=@($&`Zp(UnRz6 zJdPt>ffAf_HB*NJdU;uK4YkE<`gPP3|6^?d{Q%m+1$gfN(Z0(5cupm^vKx;Kah;e` z#jVOm{c(uCD_z|T-M9E%hVDgMrLCHLEbYGIe_0+f-ay$gFR>sw3&4@CGRFl@RX)0| z>Q-~(I~CnZa3!*PbLZSPI6r1zAJ>iNCiRo~@!Vv%!^Wo_&&^4u+bDY8*6-*=^}D!r6(wg8+IR5# z@*Ll(>3X1+YeiYjVvH9>H#8^f{|0yAyZSxdbv&n*>w?;@$vU1mI~+5Cn*{gT1nv?3 zT_xZV$(QtEYCF9?V7slp=+qSKFWnUGagE&_w@THq5eg* z9mlEb{z3l%`lf#pE&BB^F|&!9D^WMpT%9QB1*Qr@SP&IgbwfBb?;F#dVtR3Xx>H;) z0hiFHIg{N)?j(1zn~>;wNu6Yl>m_p>Zz{7T^{Kcame6N71>8Hv4E9dP(e92>OrOY} zMD9e87*6aaai@@BGJIG+qEF$uC!n2xF`I139out=o|o830w-~j!by3gDR?fH)Te+_ za4EgCKGVtX7I0_sh%=lC!a4gRz`d%U@F`Sqz)7(S)VSO5FrnlVcsXGoNa}6)0lgcqXlNfjjokVaVas}SGAR$heWl$oXgg<2&eTMr;KL{Tr z??h(G>T{g>ZUc9Y)4jLp^|S)I(PQyCt)P!&CY3u9q=r+wX?W|J&Pnem zo=P0SSQ__}o8HObd}1a&zNurKiuxE(NgwWxV0Ji2>kcDEoYqa}76@m!GvS%;EH^*x z0%88}q5eqEA3oyym5+A*FkkpUf2bD>XS;LUNEdt-Jj1-<9o;qT}% z=VnbF)OjnT8~qRCxzTT5=q_@LhKti z#$`5oEcVPFNrq;-`T|8T;&TVqcfM4bMVhu<}7!{H#dp*Hy*U3oxgdkocIDPbC4a_abM3p>C;g82^S#(HiDPjsWT4bgtr-2^IIg5vl!0?fXVz*;rp;HPRdF%dHhw zdv(6DKrysPquYcHtsTCw3zUX>BUUv8E3GE1Y^*oYm*ITe7O&X_N?WiHUZ^ZmI;a`= zE_6`m;jYwyZ0&Iw{p4nFbiBR)2z8Jnw8(7Y!yIXVYxsZX2yNPy)i=)gaTv_9UjrfgE~?XceGLbgzB+>ja5&tPi(F)#+$i0*_!E{ z$VmaaOWcB&C@sNKrHh)% zd+&B3PiIwO-R~jg4n&VUE{^ny_Iub>P3fiby0Ws1>ND=)@4XsF?mGHfoWJYnb%`z1 zrFf6E!1H*iQd_U1ud`}{_3(PU%Dbs4yp&!y@^r+BR=Fc^qRybcu}uZnt)ZxJMo^`ci@-st#~JX3EzmfpE=V1e=QJTgm9?EG*7JJ zIe6^lWkifoRym#+jrW!(Bv)NV`lHA<67*EZ_>*zF9^+53Qg~y?KiVIIM|XF|Q}F$2 zsx{-$nu4})TfLob30uT83&errXmK@PjKY7+C%-2~_#^$E>Il$F9qUiRS9~n_$M{XO zrdm6_rPfk!1-IfWmSQBXXp+6YFoh-JYU5Zx)^E(Z_IhKjz1{(CLa&w9LT4X)TWZ7o z5q>XqIOq-cR{N+1yW?sGh^GbQl!*4OQAR3_w8mNoeY`&rNA&Sz9_Nq8^?jl>%pdOe zQA5@sZi}dIJWU7jwW0nn#)pEw>I7Df_Zzamqux+!MASrlErF)7Bfi!^>!^3q8)yxQ zG4g~WCRX7=7Za=TksIO<_4}$rKtFXNc_#Q1{Y|*dPxLqA5+8?^F(HH|5@-S>)Fv@I z(XUU|PI`UNSs&~V@%yQRL4Q?cZ9+{2iQq(9Vr`H=*zd0n0t3`~T4%kBUQeq}RD>!L zYXkj3{s47g1huZ#MenND)w=54;Cl2vsfo2D+9y?EWgV@q)=eMa5A+ABusTTnsD4tD zXdgjR?Sq<3%NBl6BbSE{%tRwewPf0RHS)rEuYMqA4BKdJwTxj~t)2D-?Tq0UVQa08 zmLY7xPb&lMFTxCAE3LKmC2QNk?X>oAd#!_(K5VYH(9^RrLzpT2GVGvb0v)xl=tbO7 z>jZbwI&0~|b3x#xV}1HCT^R7Xl`dS&Z=cLzXRV8tIqaf!g}Mn2Ir$!KyI=o!8P zenDAHudWxA)%6;14ZVOY#7IH8o^=VudUhlb+gQI9Zm2d=w~0n-V>LHBr~A2O9^!V! zw~4~Cs$NYm%-%wB9Xk_=b?i;EbLB7PfY4f|*-7)>Eo zFrQrfA?Nz@{6FNM#N~{p6w5&>cm=&>#8hG_c&{!6KZQ#fOC?&160#LsT$Yf-WaQ;N z93Cd0TD!#_@zmNQo>(nKD^|4xCE=2?lx)NL)}oE*rWd1KhyP7&L@`-h4waE3`A{+? z3rEPv`+Ef0hRes~*()AfPl(T~U1B#pz#pVOvj(ZVX!rLA_|JI6r&bHmQk0S{Kxx@l z)aL(cTk^LNkF337AG}ZOhab~>&aP+HbE}`<-ygywCk;pPh$Cb>QA?|>wPSBvF__UL z;b1w0I7&uN;-gqIQZ^SYL}|FREF&LUkF5RT1$mxZ?b+K-v==qCTG}8vSSATa%gA$l zG zE;u6ISbxZQ{u{Erwi=1XqP%PbD#$z5UF(SGC;Q7pVLy;CY$zIu3bG-nDErEOGGTa| z6-UKw>khFG{RCkjW)g-CL_<+gHUO36E$g;*RNMl`;A7&rxM>|1C*WJe-m;HO5cUG` z;oig>)(QTN-mq>GuUj{)r9xANb0(xIsrVUaO62sdDQUvgaO5+tDe1zr@Mt-P*)eh~ zd@e}GNaT8RUXGLFar7E5C%_YM`x>Rawcc5yaGrZ>Rku2eE~2{CMO3pcuyY*lPvcm3 zmUR>0338$wslBt_TO;wkduNT&-dJzpx7KJp>;8~$tg7toDymvtMK`z_y&6_0(HZ`p zpFs`sSGUfPWfIa(5Fo ztslbg!{^+a#Q3~T)#Bsk{pV2;U{Y-Q0$?aVypH9vW?d&T0KNhQIQ-yL>((m7z^u= zp|*8`ozw8Lnliy{;NW+h zSk5YM^$}Oe^Pe1~30t!VX@iMJSuqn|!DGa0%wClPalX{-fk3y*TIJYP7W5TIST_qV z!K1|Mth^=%Xu56K1GIs}GFD&FPn5CB68mcgALI4M`O>g&u=2XR3EzWcSwqQ3T#V zZ!P2Ng0(?utBkcaC}Z^#n}Ur&5n~f5YOG;=ZLlUNWtFxz2Stry#^zuXadS}2C~m9{ zN?N6?)y%F5RtIgYlGc`>xKYB`5|l7X!kg)>VtjS5DrjxBv9<cD}z>6YinCj+9+de3$_wh%L)1_xmu3bC+I8XDtaryM12juqDSN!Fbkd~ z$1yTa9}kb$SIZT0qCQDqAy*RDvT}`Fi^J(*xm-@tC+o|ZpQNv2WUXAr*kpYfn4+&| zWSv}(N9rNDJt$+8HMR$3jdJiddMkq7dLMlSU+2nTDf_1AOTkoq1OBa#W^`fj zT7N^-7!k%R#uf%TZOzb)+4>y)CH)1#OZ^qm;CnDjH;h^OYKTT~$O35?nZ2()8@3I{_?FqM_{qJMT+oJmX8?!@ePnADI2#`@!2U56B<919Gm+$SP@M1cC7* z<3D&mdi&&l`GuF!3yhy=|LA4#zM!1}gvQT|{N(-Y?UnmvdS*f+J%}0E82Q=D=Ixey zWHxV)+$+<0>Ajed4#YA3=k1ca<^Pz?=B4%0d2x)iAg=KXlp5Pf^l( zaScV;NncTB1v3LhnH|i6=LECi)Lt6K(~w0`9_w=$(Ucuh!9j8l?O(m$82`=t9sb?R z4rljrz&X4>;6J=S;Xl2<;J>`T;lI6{a855Z9M_1)k1inlJh=F`1gYlAEGdf zTq<``MXXXaUl7lRf+#qs;0pT8S8xSam7!{4J@S?Of3M1gtX$}yWn59phWGi}BEK>P z_sMd&R+fRwa37=`Baw?`nJ}^BVU<0>PdI!G=iQ`GQc_Xb91jnnv;-~iH)&36^|{}a zo={qU?l-|FSSW2i_Z#D^f`bs=x;PEthRX+ZWNKq*_+VCoE8(r6(Qga4#S24I+Tn$v zDedvF(3HrxLc{yL6Wj@J0!@h=4KyY4K`4y-Oap%F<3R)0BNjF45{rT&yh;>iwh(B@ z@A%r04-BXa<1E7~NkhJp=(VIFzx8p9fol6;8i|Q!y!qK~mj6f(^c@OZnkriYyqM8z+e9No(pVU1>?+(5NS*du4Ug5t3-%|IG zgVy)Fg6E*hAv>)fdDYGiXQ%%YuiC%EztjJj*Y4lo-{@!KdHf1%$}jM*jK-&(jo&e; zjWlo?BQ2bk-zo;24mOE4vlhQsQqyv%$4Sj^zjQ`=*dV%$M8929P*vlCREEY}23RM0 zjJy0s&A_t~5pdqp==qFCziFbH7$2nI_f0ZdlB$+u{B}u7D}E z;OO^6RJjrdB<6QRLR#_Q=>KI@zw%g5K8qFZ#boXMe8mcomWS%40pjRPLf~Hy2q=-3(k})+0DNor_*K4#Lr?X7svokmvZA3Wjs~c`6LHz?+B>pVu$I7xaIrY&gfv zR&K?dqn_XlaU0l5HNYljw{u73419*s4fHR<7kO4uwZOmJ_dmt_4zOKc&!|wMyZ)D` z0Eq67>;$LaQ>@s<$WHF;ALAy-?$38gb~CbzJN3~mk3C>FH|vkk+Y9z^YyJqW{hab1 zhNE-p{a_z=s1MPa%QHI!AEG~(=Xj8JUc66(SLv&H_se@Qc(uNUcWSGcnMfthD&CQ; zq{aI(V)Pz)4ZKEQ%R90ajPfpwdK%uH(Tm<|uZ7p@>)>@fx9Gk3dfuZgW5rZzUY5bj z=ue{^z1xcFU3kw$Z#wO1yklBSYX+4mi+Pu{h}KN1Q5Nw&Xd$gx+=*YvJAwtYW^-qK zK0Ke^9NM#amobl4PoCL4P5`36hguVd^T~Sa&m8>~)Rw$ejoj% z(hdxThq9tQBklMswk5MIz$iHSD<%4Tb~K;C4`xLN{vH|3XW@frb>we~L45u_kX9%D zQWyY7e`j>&FNOYafBIc$cjmL_ezdysuCy;4{Uy_e+N?=1W9sbTaEvj^zT z=aIc=RppuW;$A~^>Q(|S&dr7B?5iYb1UF)|7;{bF;>1#%Ni~2QFjth(rf@N05n9dQ zqQugyDa9Ru==`b-D9sI)W<0~f%s1n-KRTN#3(9a}ADtbQ19joLjFxAl9Ov!P`A-E< zo^$n@^eTc1oRCMK*qU0-_p*if5T`2bU^c>2>Km&Y4X5%=zYyh0XVt?^ff4i7VFpW_pJF24bI%Oe&AkB zZv87}3c=AGogW$b0nSDI3H}j|Zod2ka-nVcH?3^&&+uQw|9!rn@;}|qGxx;cH~ja~qp<4|BhG+pyaO`AF41S!({1`+!e8o{ zV27S$+=tVmhATmO`~hud14bmAh8V(uZZi56Y!PGV%BF$SFc*h*3{FLi3&(*|662xl zni5V)KR)eva5A)A4Ag5DMQ3Yvynz*ST$E-<(Iv)175&&q{+XrpDp{8f}E&Y@+o z_p_SdzRy~K`)Kb)TjDgm{a_yo6DLvTI{;3@rx`uS$N^L$P7n`)gXlvXr*{|}LM7rj zts|&_9Y-bN7_EgovtxWp6shS<2J7J|#OU**_3(Oa1D^w}Wo#m?jqoJmG!$vpz>!AI zG%!_*K8M=~Z`3yNS9&F~5n3asqf@i{!-pp+DVOGE^ z=+B`YeXq{;q3}@p-T8!Y2t0&-4?Yzf3=gK?lTZ8x!Gq}cqTLgY zJ_YOzM`t_HCx3n5=!7Tw%&#Wg2aZ1Ni|Qns!O?kkR1X<(bFBq+lg*eZ%c*fQ>Pbs6 zQWCVJx-mLQE(gj|f67TR9Gx(hV7?{wi%pm-&&h8SY7nE7+X|pD+?dg*Vzo8ZgbnFe zf}@JS=oGgy=cf(e2K1}Yjw<}3Gu5ha6}T?38XVQ|)ge}gtHIH^Obxg?T#NW89My!? zB>q74ZXxY^V#I~082%mNci^0YC zy0fyXC@P-$nae`2ILe-RskqGs^27O=`yV6O(9Vo1Xnz5D;k=Cg%E&KhUgn}A_BW6l z&duoWjQobuVNPOp@H>i$Q8ixt~&y_NyaK+k0^ z3+xf&Gaiq#_w=+9Xz7Rv;ppT%jg}TpOD_@agq)41p_Leo%hYgcdP!&}<}^DMt)wVm zrs4!UC9Py=Q>NsOMG9K4MRI!g1Ru|6chPi<*w9Svj)-pI+(GNj)b2BT4{bJn!E3jL zrP*+FKjt<%ZkG0d@%yOvMR#9rp~~lI4>{o1V2!z(%(&VkMjoQL7Ttw;3`bgM(LI+Z z@M9FwqI)h+;Yi6Wx^?mtd_vFcJ-uh(Df(pZX}y4-!_i%mm+%WXx=Zp3ehEi6N=}OC z7RgEQiZjMN=rZmGS2=;bitb``?s%1R$p4tx`&qSdC!^On=iNozCoVI#5A5ZP@iMLb zXc%6CFVWkIQdDcLD{C%|#e#7@#%3Qkblx|s^r8Jxmz7Sm`& z9G%3^WMl>$oxRWed`dry_DnIA`7Q7k&f}*LBi_m>`xLO9TG9>F#?JnH0za9t?NooR zr$6WOx%ymq4mF@_iSyvO@EYQLcpkipGwS)DPq`P+o=^4UD(Ws5em;?2`1$O55$%Q4 z%&nkma`ET0=q2!Cs`r)=2f|Se-%?^1s>P!dxu|M9Iz@{(st@l3CUVX;j=8SXdXEzw z8Jh@C6q7i4i|W6-fv%jlc4VXjn9LbkRNLJhbmKg?10y}CfF1=$wc0&Ech0Fs(&`2G zgrf@S-f(nw6xBobfqTQlh<)Mc<5PO$^Bqj1K{X0{z1gLJf}g? z`3C(8oM^X#qf_<@pgbD4(b;)9TCLHtZOLdQ&ZAqxE$NqKt}R@SScXnB=$M3m(QxwKQLBO`~XU!i(iD%U(s+bf-l1ljC>DDqjq1I(ce&1 zE(8~%_dD(1P^m9SD?8fA1<{xW>Uy7}@oF}mrJ1q`y&~|7qq{imrP`!m0YAJCI`v5(~WClp@{d8y{(jsYDu) z7Ea6Pdo?w^_i7sY4^>CFaC9r~ks95Yd&I~?{FiK64^&V1;sIVtp1802Lc$M-Pt@qv z+Y{D2#tG}bD#cSZx_9{Tk^V>PD4twb;4Acw(LRa?=_TTEa12k;e{t420WQIp z7(L0z30yrd5Kn=VxNBaZbsC?n3wUgvr*#I0tn)ZJo};yrXLb&sf$i!J+zGbRnuDA0 zcDx9-(VF|&TX+_uJJgwAC%jYL1<#^4kJ-8K7UB%XcHsuFh5mfJcQ?bE=}l*57rcw- zwg5-nP4Fh>7SdjTTK@*(BCrsR{Ppw}gGDIiucx&HKiu`|QoL^0!RzQRqrDVfLtKuV z?HYIu{S~yA!>foxc}}a~RrI^#12ToXoD*^U=m93flNs&FNDs9etto0(Fct1b?1k^f zM0g@Ax-dEo?n>;9U&aJ@0&|@ioep;)_F+7_9XS?Hj6PsIw;IRL>kImDGjR;9{`gRg zfydAvfUm?Tcobs;K!5HJj$mvc7{J}Y5wr%w(Ot0N#3Artco?xE9NiZiO03MC=l0Yk zx1&`Rt^!B*pexaD4@WniD-t8_z#Zjk+!JmCw_#N^P?ak6ii}qPov0*k&1iLQ3%6Fw z)9(ydAl6`{I`zJ-Xw~G#Z!4;Jqno_7KufqKqqP~SMfGhnVjWPM8r-Jz>Vi5{(>A45 zkGpzJshDg+t3EgFnozIVm{tSs-ZiFbvk|SlJhMjlu$4lm;5YCqZfvD!{Z18sNw_4v zUl=a~mqAD17gm(U)vl~s4*rFhoyz?Za0ymtW2_v0XvOLOOshPcjra#6IpAW%KdF~5 z3KymKC-_7Ci;+L^7Ar&z{okMnT!hh_RJ#{~3(?O-JE!^&oC_{M%uO|H0k{DDJk+@6 zhx5}<&vVKL=cAtppTvalxA++*0^j4h@GY$bjD8P)ul|7Nzz^z=Z~|fyH7oN;Kw=yT zepG*g;}esrS(r%*lBjVR{TYr&OvZRp_#0w!I2rskF$J6){tDN=6yR&r{lB7>3Qh@s zsb+#R(MwG`6`YZn22QP}h10-a5YxeF;S59tP6wwaK2;=sCePrf%5%lX$>cfhXUY@h zsS>D9K&U=eLNx}*)Hv`HdM_x6@nN6UkCews9QCE*;0N+jaq$&-$?OZ|A)|5Chs?)O zUorbqd97G@alBS+96w$&@=AHb$ZO>-{027h+;|7SRo*EEej4xLcR0-Rk-z!@evi*Q zA26vO;SYGf^XGy33I2!!JTD3Azi{LVPEZdkca*y*xZfro0f&{Nw2z=ve^^4lwfoe!%lNuH0b$I5?*4XY8SJf|272%H_n9;DmBY zxvE@)uQ7HCoK#LTa!NU){6{CeZ-U^l#5*+Y%RE?NuW1@I1h2^NA~$~;E*D07Js?@{)`dzF3ERqSBJqR)N> za~Ru4HN$rLi%H@-K}T8&Qk2JU^Yr?m!^?e*L}Uq@>s&ukqEJ=0Oe=|kPn zbkuaF(dtVr&s2CSytul%8NFJX4tk_oCO2x}GWU6jt|OY!(VPlNjs&f9#zF zm>tFP_PcxL>~1!jjchh98+UhicXtmVK!D&92o@l?ySux)1$PJ+cXxODe(&_1yC((- zaxeey>E!9Rx_f5NX{oBNwmO7^@VT@fIr|dM$LGyy)LioLZ-qaoW#BU2oEzDNnaJrd+ zAIhoZ_Tv{TrhrpO_2kJ6a0b7$(UUL>Ze= z;+dcYxsCAw+X5dV<;f`r)v1XXZyAP=1LojY!w~YoJp6DNLOz&}pASPQ01Nm_{-Kc# zpVtIz!e^e;IU7sZn&sG#)=bCN zvZgckiG`m!+lX50985#T*T@XD4Z$VY5fNunmVnn{{YBlK>4K*^CvO*l0Cs+lK z%vY@LN1S~53hc?AQ)K3{`xKcK?5#!SLiP+R!6!xZdNH&jp%Q&xg;WJXMS8s|sq%yh z^nEo_g@p3-P<2w}2!-@+bz%kZd3E}`2C;mwELam-2FwR*LG!>eU~Om~oLw8fsY5IW z%mwR0Gw^g>urBG0sYfaXGqhoSDCf6HJJW!agKHar^~tqxYD2IgX+zv1-;JTe2nOkI zLTV_S)C6oy?hv@HDcF?sV7RUs*o^cb;)BsHEuaIDhZbOSat9C}h&E~k?N1nB`XNiL zz&6l+#QLM#+7Ro5G`0cTknWAFwguag?nS&e*dE#o*=~=H>p-k0dY}Uur6aK(=!=f% zmrlgGf!)E*(5_%NunRQwSLm-GUqQZtJ`DOWj94}*Oe?D;VN3iGcpUk>x- zu)Y!2qr!SrSU(Kwhhe=ptj~w_`LLf7_EWxKJz;eKVf4;${ohWpFm{&Ki)9{d9Y{{X?CL-6Mi{BHz*DZyV#@NX0R+XR0^!5>lZ zM-==K1%E`rA5ri}6#Nkde?-9_QSe6;{1F9zM8O|X@JAH<5e0ul!5>lZM-==K1%E`r zA5ri}6#Nkde?-9_QSe6;{1F9zM8O|X@JAH<5e0ul!5>lZM-==K1%E`rA5ri}6#Nkd ze?-9_QSe6;{1F9zM8O|X@JAH<5e0ul!5>lZM-==K1%E`rA5ri}6#Nkde?-9_QSe6; z{1F9zM8O|X@JAH<5e0ul!5>lZM-==K1%E`rA5ri}6#Nkde?-9_QSe6;{1F9zM8O|X z@JAH<5e0ul!5>lZM-==K1%E`rA5ri}6#Nkde?-9_QSe6;{1F9zM8O|X@JAH<5e0ul z!5>lZNA&-bKO$ptOvV_3HI9%mF*IW$XfEiW5$_l<7rIAg8L#h|*#q32uq?AYvnO=7 zB)w}A+lxG7W@h#RcOmSWnU$Fdoeed7hjOjiI`^!29Wy(CJ7snRch2kt?vmL#GbJ-WGcPk0Dx8;@o0$d`&dJOM=Rzm*&Xmk_(#A|D zZ+2!7``@+W4xWx5g{PkcgVd}a}J95^1_ z96A;p2QG$=&1?Z31C9l^gpLNsWJZCb!L6Vp!BL5%D6s(YqgrVpuhnZD3=#M)=t5^tC3!n1B*XJ{8< z##DwH(r6}Htuie#gP<)kgP|>mwahdp z-U1u~Z3Z^aG|dc!Hl+qb!6D=}p)SL~VWb-qZ;~mWsh+6@)__)kR?Ad`3ae(SfYqRd zJT0H8M5;=r9PvW1CbR%72iAfXWNJf;c&iFnB~zUFEUrwwK8uTzcyXq3rY!FifOVkx zVA)I=FdwW7%>&DTCD7bVJ!mc=FO!q0Pb!Cyo5^GvkjfBpGI6FMsW{UJ8WYQ8BI?u# zY(&~oyT)K+(jUcN$6v)C#UDaHj=zk*0KbBMOx{=V2k|%Le?a&!{)D_Q;`hn<0Q?sE zUi=;OJ;M9(r#$-{`~><){8?o!+wo7( zx4^gKH{+k7Z^pks-z4@{{08wijh@Xs~h#!dWhdvlT9zO;?0ez6XC*u3!r^vsLaDV&|d5^{Sl5-#UG;~$G8oDZe z2D*yaz462GqtxnQ-g^{$2znuDV=g51NPG`(u8QxD{{_99a8GQjp^sM+w=$YVI z@dZ4;2)u~8t$x@ozGr+WbWdW-<2{J)8Slp%E5LoBbD=BZW#sPx9tK?&9}e9e zTo&&Z9|7HsuzS2K@!h~9p}T;)f=5AjiI0Zv4DJ%|1nvwT1Klw`7P@169CSxwJHcn;6!#Z%%f$eTi#8uuhU7n}o~9B;{!$%HBKqE`&3Hnj=GxQ^3A4gwCUq@eo-$1|Q-EX2NpkGBF z^3F%m2hlIk4+tMd??=CqdY|w?^d9l|K@bw2tEgWoF`9$Pg0*tp-)8jlm7ttJoNtP1?YX?{n5SP zec+4GRnbe(RfKz^d!m;~-9uOv-A()+@D=D?(W}tA2zN(!62A+44SHwvI`j_k&ggb( z_B!}F=?kMPqbs5dzze~vpch0}LoXtIMRY##3!;ljT>)MmT?SqOJ&*kJ!E2!Bg6DzP zLeGt^gI>a0mw}g2x0TRKqjShVH#$4I9(p$6oaij#XM;CD&x&q@o(Y~6oe|vxJ%ey& zbUN`fz?-3`MYljtBb*+c8r@3j)aW+osl-l;P9c73bTW0i4ZMx?e$nC4VbKc0q2PYd zeaYD`+Mm>+;GxkW(E(85!O=nBA<%uIBY0~c!oJbo(UGL~ChQX($n%4ug;3!^)M_uD z?hPIV-77j8x*Xgq+A}%^x@UAObWdW-qdkc487+&BgD#7Xhb|+wN3=WfWzlZY3DDgL zyGOf5Cz9GVItjWfvE8Cwi0>NhOr1^wPa-`xniFjSZV@exW`lFUEur(sTMRCaHjm~* zg_}oaJfB6F9nFlEkeW%D6)oWTB5+Z(S=5)X5L^JA!8pP^s4U!Y$QzI0!c`xE%1`vLq3`VI64_qqF(w?20!`W5_z zx4$L#d+;0RXXJkl+Q>w!$^Fi)=E?W&Q*u6YpEwuU=o8|fx{qBHx#(jTM-k}A{fPL- z?n9S};^;%-AGr^Re+cG8ndp7+1NXkmjdG&*Twat5=92p^@%O+oQC{>8_^x}$T}A9(cMtJZ?r!iN@Ez!-?h1CHQ?3mD)1WUh2&oZ-Uz*dysO-yP~lb7?E>;I1aE>~ z;BJPV4_@HT1J4IEIdQ-OvNwQSM0aNVn1*1RepdgdRZtf#A{5gULGrJlq`y9s%8-`~$#apofrmm|NkF zCAEUEzgtZDQ1B4we(pG)?B|Y$?ni8e+n4x$ZXb67bRWXLZf|!Ysl5sNxV_v-r1m20 z?UuWfNi8Sr<@O}L96SZO2e>DADs&Hb8gv=B2Y5PkcW{|o=$5#xz^$PR-2&)*w@rfE zLgy1(;5OsQR&JhK>b3>9C3lhA(rp251zp7Rt=wFm&U2fS+QJPaECx4+&T-rEWDa4j zo9(tIHJdQU&2l@Cn&ozc<G3%_Kg{&2T$GXAow(>BMJ%J42_rU7*tl)7@0!)4*M! zQ{8URDd1E$8Jq&{4(;oPx*^~&Xdkez>qi*kdK2#h4u|$9ZwNTp4FZQidy(H89046b z-XPc0jU?66je_q5M% z>kM`Q$3r{03D8c2&aNZzPT)jnM>h%D0qp47Q>RJbB+|89L)XC71Z#nfptXrLa5Y?G zQZ)!QT^(27)dL$q>+rmRtL~ccygH$VtIM+zunx2u`PIRu&}yz3^e0=Fr&Wnp1Divu zfK^>FSOshWtqc}}EulqVWv~^r$hC%60*k;l(28IsR{^XDwuM%3?V#ns3a*ekwFBFc z{?1xwz;B`7Sm%V+eQUqBzuI3w<9-FdgMMuz=fK!SpyRzCc;jdAd+1l>e{Fvx^|O7B z@DunW^h=v@vHQ~IxC|J(uk07ZzqFs*T$kfMC;o-~%;vdV_Zc~#+fQv7m*+mU`K}C@ zNA4%YKeZp*vM%3!O#Bn#1+J|72>jT7Xv?_*_n|Fx<-h`RKOp|0U2R{oFWRTU)!@s} zXNbLMpCbM=_zLu2`_7>=6gv;&KJih_F!Cr4KCI2$; zR_LYnHt03>I_h%`&#nWnh8_vM)?UKXOYOzrCE)GQi|ifHi|n1yi-=upFC>1Ey};fD zy};fLy@1$-_I%OWKZPDL4PVfnRZX;3~(m6 z96BAGVF%h#b|g3eItV%v9BD_`{&qAu{RsnXKRbq0KSF;ynCBzF;dU4}0@~M(<#}I1 zKRblHVYZJQM_wO7U)zxMP;dyeH~D?Q@zCCO0<;&{+xD~*p*;z`Y!5q$R1ZQ=+ucqk z)t%78cC%ARbt81QUF}p-T?yT67dwqq7iu#NoJwwI;$3WA+tikT&7gH{b7(!%O~IzN ziLFCUU0WNh1Ga$Hwk@IcdENwUVjJ69eLDBMEXaQV>9+A6Wa*P*cki~`m_1TMD_=s{%C$N&RY8mX$Src{odr-959DB ze&xBf-3ce0~&O8f!9{Q^J7f+ux&zLu%&k+7)ULf}s@OkKq&{x2hsl$uJUN)=E zTfDp4ybWDV>>2Yk@zv%=p1)+CGVhRj%DfAGirCZUN#aj|??ImcpEQq~_o0uQ51@|| zd%`?M{BiTB`4IXj;W6`w`H0jbgh$Q8=3`P1Q=5;$kH~$9_`~KJbDO!GCxd(a~csaNVdMS9Bxdglvycc?jxet0Vc!{|PycoP6dLeib_yF`m^C0vB z@IrGwb$Sqdkn|DeBy*xU5_+OJ3MxFo91ordJ=~nk^TP>8n8VB|qz*HuLJuQ$xH+1) zjt7r7$C+cG$C*QUdYCx`JQO?)x|G~w!DFBYo72fVm~e zE5Wm%2b!~?2Y?5f{mnVh{Rsz{73N%0E6jP&6~y*8`w?GZ_67F?&xbBCJDDB9t)N>& zcLaAdJD4ra&g5)qc7bk5Y%8+`@h#0ZW_z<8xC3+>-rd10HoNj0-0U><(RImO&R0+uUqMe34mb_JA%VY-SdiJxMJv%b^R1Ej06qFEI1W zUeI}j`DQNhdEnmAxn>{e9B{6g4bB1gg$^}C%s6nI8Eb|?g=5VaGnkwq;CSe8^2UIp z%_wjTbP)N2!3oeoW+HSTILM6P`6x4h_&{(Hw7;1Q?N1nB`VsFBPJ#9{Q=xs$G-zL9 z{Y)R?eZlF_-e4co3+xTffc6A?fis~!%`9jSuqS)^OW}veG&4=X=Fo`rjo?dc)JK$P z6!9BLMZ7Tr97S74gr%mTX=Pf14WNynEy0$ig{f~^lT+Wcfz~J1z| z)0hyM67uVTZJ{Nm9kdBgB2$-miHS)?$$5mx)FG!X*dCgboKC21I*_VOsFR#ah)gZh zk-S=j+9oeKyHL|~BCjT)mMKGCWNMhsfHqd~g;|9DhHH6BL!K13NQ%Su>q+%$ntl&(@rc z^*SGH$l7vb`m!ENf3kWR zneSXJa5ZaUk-3r;q{tk~dP`&$vqlk_fz0S5Q^K4#GC$c8@HysIk-3&RNMw%0R*%dQ zEZfKo#TtxEL#(C<&TeS4&%Nlxi-q5G`h^XXgm)Y?``pV=(*PbHN*IP@*C#cEFcdki zM`|!(2ohXEY7k*C5?q(mK*At1fVd>O4zxcw0IUt|2TG!ALHmOJz#4F7UqUS;xCXJ_ zU>~p=+}N8?139intS3BF4Xj4G2l1X@6=-*Ot{5yP)t%4-o~lf&D;!xFtW3HKJX!=6 zk?suFRst)L?gSrK1S^v62xnISE0FF0Hx`10>{%Nw-GI^1*!4t&qVoU>VXaY2`dHk8}%UIv30(-JCwi0dq(;8j|%HiVf`?yABOebus$Ew=fi%A_ISg7O4$Dj`;}q8GVCww^hwZ% z;XFV%zY)%Fg!4AxyiGVC70$DT^K9Y#VK{#n&Wncgz2SUsIFB99V~6we;l4w-?-1^% zg!?JsK2f;;74Cn9`+DKNUbtTw?!$)ru;Ko4xW63kn+N{@!9PIo=Melk1pgbsUrO+o z68zf)|2DxNQScuX{6__UU%}s3@Xr?f=>>m!!T(|Ke;E8#27i^ozi99W8~nir|GmL~ zZ}7Jq{9_0I*ukH9@Mj+U&xhX&2)`E)e%~SdzC-vuj_~^_;rCO*@7)A{M8O|X@JAH< z5e0ul!5>lZM-==K1%E`rA5ri}6#Nkde?-9_QSe6;{1F9zM8O|X@JAH<5e0ul!5>lZ zM-==K1%E`rA5ri}6#Nkde?-9_QSe6;{1F9zM8O|X@JAH<5e0ul!5>lZM-==K1%E`r zA5ri}6#Nkde?-9_QSe6;{1F9zM8O|X@JAH<5e0ul!5>lZM-==K1%E`rA5ri}6#Nkd ze?-9_QSe6;{1F9zM8O|X@JAH<5e0ul!5>lZM-==K1%E`rA5ri}6#Nkde?-9_QSe6; z{1F9zM8O|X@JAH<5e0ul!5>lZM-==K1%E`rA5ri}6#Nlwx<4Xoni^vonwF-4X=NIj z#-=sc%CsTY1Z)LuOHOOkF3D|2td(g`PFvH#SmQuvBCrXc)PcWf0ygDIN8V@+>MuL- zetXlI_hK+M8L$oSbtXihc()60v<2JpH(hzZlj+8LIbe>-1v``K#;mn@8=b&T{7rA(?_v6o-xDlj^1+_aK0NDU`tqzR z*p;{Y@n&z+pEt^aWlaIto%i|^^1)uD2Jn7gus3ud@Am_nK?m`)KUiSOf#pmg*q6LP z{UU{&*sQ?ZlHI!$4!M>!1@y1{?oHvJ<5xh|mtY|8M zLrIO`*#K|=sS&(8*o@@eA>a`HZX{ut8O7fYH>3HRBCyC*21k$@&9f0^49`ZIvAi?N zjN@4`SZu0*qe+e9*)VVzsd2nJ(v0W5;oxvm6ZosKW+G3jfK^OYu&SvBjv;RnZ;l7Y zLMQX)1T%&FiC{HT9jtC@fD=hg;k_|tDsPMh$MQE*`HKl=8h{BgwExYXM!!D^T?e6&f%STgc7jC)C1@8WFF7vnEA+6OR%1)57s9&pTC_8 z&LeL=&suLrMakt1-kAzYUe}bx z-;zQvsa^`bL~d9Xy%c(hES1H%i6o^G>E&--x!jOMO8z8^saytGTysSHZ_1+fx%$HY zzdbGvU@Tl$7InvV;6_PgIyw$PihqAZ9Dly(J>tnC8KMOiyAZ69UX%#N)|Q3W!tD5Cy}X*+6S4Eb-L-}qU_RC7B%Mm zIUCj6rG8x0c)785Y4(UHS(HV)F;ci;8#P-ZWu5vFaeeaVZB%cUW{->BM)lUIw^Xxj zR4;{V+o;}lU7w}uN5{2gF_l8usB@4q$)BWcT`5eh(+!P_r55SB66xhNmCI~PHH?dE z&KLieHtL@l7yk)1>c+`pIy!2;sF~uLW1*KtjdL5GHI_OVmi|M*NXmB>w>FM8|L&l>%>SZb-JvbgT7(T|9JbS#y{wO4I4B1)>#F>>7%ob}Hd z)3I#f@7#Ewxc)ooXF*$VSSeKXq?AOiZyhz2MK6WfqoW@e|4v!_|7Wk?udM#wE@Q9%?D%hZumA7fUtD)* z(eF5F6#cu`QGZVs(^Z@75iy-9ru!HhT1WM(Icu+`t~okty{2@Rf5N{dGJAh9mBQ?? zP;!>N*Y9`#*Pc7BZ%<>*9sle-jdd+mZ=+_*U$%9cJzp%9$Y7)XaT`@9X#BaGP1*6+ zi5s21>HnYIjK6Q~X5IPXZ`-IEM>l>?BU={Nv{AG7G$c>yE`RA>Q0`t~%m%m3T+ z#nOF$ziR47$81?#^W4pEpSbz0Jq^F6v!R`hbnPbFI@L%S)^1AAz=d-+>&jyGOffz8 zR%)I8@%dspQ_PmaQpx+h{l(v3yV>v=xNJ*x-7|2%Jx5&g^xN;Rqn6sGYo3H#cU<(c zxS??|`wU!IyZI;VY5bY}#c=LsI^*X5Z|80*a)!4O`=vEFDcdSJDcl;=*>If;*4gmN zoYpQ%PI&87xIZD@o*bPGufPfB4xCM{0O|y>&W0C*RmfZOYPKf6xXT!@v)3f2- z_=M6E;yN2%#M|jvoAiWu9yvN2zP|Zl5r5O4)8;u~9#qz;KOvsS8fW&|@Tz?FKtexk z(f+(Yh%@amm;+7EhReELbM2-oe>0SG@(zrlS~ZP9od?%1jcEp`9Y=p2)t^lr&dFBI zCCAxw#B>F97Vo4hIPCZluW#ysnq|)A^m;Y0TGl$MUpt+XoC^258Fe{LK96)=Y}6Y3 z#eB|~*8=N6=M$>|R_9Yv3w9n)=2I5_hO^;S=nctY%ReBC+4nTolttas&)NQ<^F=R(x~njbP!}A{UuECZ$eu4wp#1)ZMqOl1GpC7!dWrm% zuH9tc)5w-Zt@KYJGyo^^SE($ndru>k#RmVDzf>X{BoZkJOV7Y%OJus&FS%@p9M2*& zUau^sCs7+Cf4ZkMhtPB_S@h>oC1+kP)18e}E}J4(P0>B`2+jW^b1f4otdU5ew@aI& z&vYtPw>akUW=V;(kwK$223?|+G>Pj_8;1 zGK>^0h~*}lS3a;M6|JE1eW*K38dKYV;`=tB?mFupQd?*{P`8oVf%?^1@osx)A*h>1 z9iSS2#i<>k@~NpCMV+9XL9Hfs26cyC_lLSb^;_lKmdK+VYHhVpF6C1TspWDgw^~k|n4vyuQMGhT zJ=N0U+=&0`G1X5!rO#1M|UTB){bE!9@7pw?0=s6EtL>L=e{D$^hDFMYS#Nxi1;R!P)r`fim( zy{7M0Nz`lE{iRkAN2{i}w17B4Euj8a3##olmH#)jJ;i6@I!VEw;s1?kPjSEaL;Wo7 zSKZXl;(pau{k*CCuf9~zdMS`5l}`22kV=L)Ae9(#Mk-0-m{h{VNvY(iEz%N+=hBjj z7tKW-x zja90d^rq^mx~tyeAyMBt%9rkxW>A^M4_?2j1*I)4-=V({mpV#U5v-W}waOY1q(j8# zF+o~Ib;}U+nUaefg0!{dD3>5TCVtH$NRNq+%Mhf;WRc|)WY1_mQ&RA9^Y9=tS+>K zvXo28UI2Z&>yLRDAQ zxg1n=Rh%7e zRdtS_s;lbkpsK6ttWOm`mjU%{l7)OQO3EP_6+f$dUUntf1$?SxTC!dal&nh!6oQ3G zTJ2VjAlpnfnl!iPHubvrOeGRGNKRE!af#$tx>p)k@-4ZSCYBzSu9k+@_^+`=np=8X zttIKu_^;j%hwvfD3L^dQpl9!6ehU7=`QUTde z86+>#Xexu`MVd~1DS43wR9{M7q#4zhk{4-A)lBjtO{yA8UZi2w5|S5bUbT?qMH*Qx zCwY;kmbR!uh-n*ftK>zRUGk%ri;_=VpX{gv;-s>mN+u2ypQ*&+Jn>&?Ypy9f;yy{D z;nVf^($ijV>wCou(%UMJ#*0r^2L$8d=nb<)M;`JYtg3zd|nZl5%Pu zp|;dFNV3(I`UXk7$|A`V7psio8tHSDU6Ln#t~yEbq|Z03i#D}AOS#s|kv?4-POYhL z_1~FVAu3C1o&0s}ss2cNTc4hCfxb264)wEoTjj}aPv3iL&pbXwZL0Rn0$o5dLZ;HHUx2L2_T%ykw$E5nR z9%E7^#v+YOB~Xn;8ky=sH5PeWyD%AxybWG18H>DaUXYAM-exbGj78p-&ril8Z{wFq z#v*U~=Ots2Mka5w$|CS~oJOM@#wBmFY9#S?oW>-LQW}?vzzC{2oZ7-cvvteg(Rb>( z)NU-*ZW}lDW$PA|cYS^L=X8rC){j$vm0neAYfi1%o$9T5wr1NZyDZVNNt^q*tLCt> zy<~~yL1mL^PUYvYvUAj@-VW9%uJK#;u|{`|>$00Q>Pwr*BJ_RgZNhX8yD{IZS-Mv9 zG;f!k{YSr7GvIXHU}L`b&(v3Kt5rjdGyjC|mGz*W_B<|4uhCp(Qy*!R_bU#*=foZ2 zZohV`K9*)tyQ?SEAL0Y?gw|2SAAY^VuMPWk3BNw`PuN2#_|G0nTWY&$dno!n3TaR6 zrEJU|igr+BVRr}rsy&o`$?l1EQZ~GYQa9N}smrd)pW8$6`a%8w_pHfp>Kd~2bGjxk zt}Wd|(TOIMb+pU0HW9X4c3sC{M2tDO}0Z7$2S zw9VDxDuHaE>^4`6tHgemQmPfwbxG}KXkAjAru9noVY*M3ZL9xPbII)Ti(5R0Zye9W zNsFq^ny;t^8jsYPs)71Qbx>{7m1-|RzE-9CkLnlMz*<@QU#+oAD%6jDoyd;}YVUNe zr}j>5Y;j7uexkX1x~`(JL8E}ULSutQ0j;fTY{*`h{=c~9yfJ;P_EYbBJ4UN)(momo zHR8*r)Ec32(2AM%8aJkn;^yDmPxtnDT3n2|3`1KTVQURZ>mdGV&tuWOslBD04&1~JWCcpjhzF1#Eu(W|JVD+5zf-GZ6i@w9}#i`fSgVN~Uy7hZ^>NUS_q@L62m*4ACulao@wYFv( zp3|g@H^gaLVNpwq)70{7wt05DZ45tX=SX!|c{MlFeo-aTnzL!YNb@(%<+NXuV%cO_o~(YsGRy;Nx#3gA^q=XIH@Fy1H3$Y z4)F6L&jDVZy+!S9YtI3Ge&snpt?W-Lq1`$1OnyJy+fsg?TzsrOPL1c{W9@N@OT@?8LqvbAJsDNpSv+d)q?x=J$D-Wpw{2h|Va z2x&z>l4@?HF;=?V?_q0K+wW;>rj@Rf=yZ;_O@FC#G-@k-qI9a~TS>Q{@29#en`g4i zDQ)4`=>1NKU!(WCP=3wMufl7bS82tgeotNewf=I7Q~a*HN+c=tR-U)}G{SgGP^%HL ztTx2kf2N$WOw#r&LriA@RNCzJ%r57q%Cgtyl4b2*`85*t=Z0k2pQw^7%RW%ANWygH zTYE}F3A$^cJ*6Q8o&MII(qO`nf1ipQM9$j33!^=y0fd3c**cxD)6SC4-09?+{w}9xVmb-fGdUNi(}9}f`WdfI4tD?d zX~M3^PB-fA&lpxB*PlM@Ox|z(u9@UPcLF;8`*dS_WTQjEkvj8OK(0Rx*_Qam{SJa8 zS!XSCL4OLf1@V^2xlEnT)HzL^+0@BRZ@v2yoe}9K^vU1(J9O$TfA(?B{!%~r{_6i< z?Js{Sv`f-!f2P0u3QIfm$foy~KONgL=`~4_JpJT=vXykAHnUcL>D=x5eiugaq8Ii66c%hhd zFL)w!pnZ{PtZtEi`alf!|1%V zPG8q1JqTS?2dqO{*7G2EU#GB#fP=w$P@R4nf&^&{8U_vpbvmjMI1JRODfR2`o$0mo zX1WHVQBPXmTbi0L`EzjUQH|I-U85e=i0wyK&6oVS8ujU>oaxP8Kg?bOQBO->Xgyr- zNbAeiRZpuvvfb3vs+nvz^|kbo#(HnP`}J`3w8k619LY&+LiP50i{9#!5fb`02`3*fy~wi>yz$jG_v(1NT28|QZIt^NnK*Sk^Q=8 zjyj1xk=@uA&CmywJtFJT>l5h@X_EeEn3`yg8i_uU-8c|kR2{6I=#y&12BD*>p+7XT z4JJsR=q%C@g6=13WE)D5K9M93BMe2;OTu+daTuCkTA&G`5~$OQP04A3rkAE@Mv(p& zr#4UeuQ~Y|12L9%?cBc-uMoTgo=ipdD(Ym`r&q}w#U<@0ToctbaS zWOo-4(~X~^WF#yDY7Qh@y$dZQuGj6Synl~EvNyWYijoE0jnZ6LcY|c}ccYCZF}hKe zLl4M;*7(#N)aWIPEJH78wAWbG1MC5($(oMg56vhvx9CNS=w6p>wFnLp7itXaMSJN^ znCvzOmuZC4eInf=(j6oHl9k#~=kheR^@Z0pN@=#FQK%u$G}rOtU0=9gw}vzm(w!r5 zv*u13&os_y&s#XlOa-xvadcg3c7oj)pt5#Mk8Cu_xmh4reW%Qof%D@?xXX0tC%Sn@#;|F8@T3 zSv(;n>xgULJK|^j|KCuE=fpi}}uOe76>GL9Dy~xoo(H9ZxoYY_Qc(sUhoaQ3Z z2Kp5@wUpYc2UIQBopw@hwIj5LFN#RjAm}z@4N&J=YlGspnuNNb#-o~qdSE@?s!wPO zO5z(q+a~?)t;|OBuKHNL+k`%oHc-zsga^a{;scEW`i(pFyY!c=e~kmJ6A6(HS1`FsEDx6FiGHt7 z+}RK+Zfu^EMZd+T9%+#1VQH-v#8t)yNu3(-ovn!*Xal}kdudt&)(wURNqf};HNL9_ z>(iR`;SsfI{iH7|fSzY`f5G2!@GY;AyEfb-UaCT@5~y?P)e?>p@6{l#H*~YJwkavm zr`Ap0t_n&biwTley<1GE3F^~}lfErZ%2%B9XK_--VoKG3rz%M?pIMjsYPO>u)vi<{ zP})MWAsr(5)f$Z2tqGw8DCunp6-tg<5@az;A4!6>nkP-8o+t!0&g(?IR{PW&{zj0j zY^{#V-WCst6FSh+l5U~;+YoD&w0vt&W2&rm@rU%QMssnAw5xhhHm5XzcqoV4!}HAo zbp2>F_#AE+&r5D=kL8}T{5#G{{5;Nt&SM0TR|WY-&}cFqUkB64T>$FWbu^011Q#%> zOy>C{zG*sfLztS391}r}LL-vVV+13J?vYO+rBY1=r;xV9rX(dDk+i+n99nzS8I|Fb z*@3eDhf}v0)Yv|pT>qPc(hEgNi>jS7y>m?^Ig3lEl()*Y~dZjk0|7+1cN_DRob4t?^u~;P2r0y05SN>M6hf zlD3{|vF`aJze=E86KO743flFNWXWz&U&(q>?X*iIDO0`tT7>qHq$M@a_b2-Nyjzxp zdO^BKds4dPD*fko=X6&_+FmxG_K{^l$STy%pvDE2L9{7v@3}7Dst3IVDjqB4E^$=KW2*Ot&PS*9QVsnbUEP#c zy;PUAYxigC=!)QrxbDagJXo%Wr$H`P48?^Iru+wW?s2Yug(H^r&qSKotP z=ZK^I`JnVORo7IHZHOPd-0723ouf}yORuTN{GDyx=w6#2{(F4BwiYVYfxoYd{<^=_ zcdcIouV43;uG@(pC6ycMS-;Ad_OE2q_kv&d^!@ACJ^hJbtzKsH@ZY&+Chqm8W5mg_ z`LqV%@AsGbjnE8B?W1z*T!7>;)ojvge!Whs%YMC1r!J)rWjo8SMz(H|)|3=Uo2J@T z-=}i;@Aej~yb5UE`@dN`%x(vp$eUj!)M%KV63`mGw7YiS|B7<@*77TzT47TAX{FQa z9JQi9MUiSAwN`1biTk7%(vd}aG97U=&Xo3-b^{;oCu_^QTERwH?$`YoCvhg|wmm z+LSTEms8~yr>lf2?V4-S8#_j6|wtsqNQ)9X6 zm})t3Pr4@{&PjI${A!QqT;Kj)Qq&`9FUaOfM`uaUx@R_3K3`6uKFy!S^XKyZc_;Gx zSv;*9dS4D3*S3CFLz+tO%brg8O0wqpDs2ZxJIEUG8tnJ_!uNutSUYKw0=1!b*z~!+ zFVbH4z4NmhQooiR`_5qM^rh|| z>LjK{O`XHi87$3tH1km}Xp~jkd+S0rqn`_<7N)mDWMiiGr>tsmiDXe6AigQfCn%;F zpP&6{yi55fJzpjZ#rs7louz7QEVZC?A5JsZ9H{q1qrcdA{qXxd{CDuiKkfYE#`J|B z`O}*SzCYDp-YWI059wT3v#4~AteHkS^U|z9cCNTe{G`_3wEpt;u+|M_A(r~Z(R!Dx z4~_U*KTP*{{m!`byY~^0uC8b;%-?m_?5Zp!DoeUbQX2X7l=l+VQMN~f%&Df5#s~?N zH6}TXS?dz-YfUV}3YctBt%2vT7N$CCzbltDGSyb6Ir7l2k}B=nlwnOx-z%M)Z%T;C zPmBDr)FUSUEhW(U#N^kd9#nfNg`jGuy%eEp-7skft<6?U*4%{JgY|o}T7lIbgx`&5 z0@XZLGiLeX@IEHwi$(%xmNz5*|?Rt8K*t>izn} z)%V&bP+y1>Kj=;vWTU7{MqKz{t@q`r-`-yrM0@!l{9f| z4nZStnIxvRT2l{bUYf3YX-!~#dO*^lvB95>(Px$FfsHGtcuAv-N~kiYYYu4%HKwTC zf3BRrt*_LQvgFl@-W!|xOKt1dTU0u&u}LrbR{gu$^S@nA^}4?!m3l8yPka5ZkzUe~ zjslVnzbYh+pL$1Qls`4e zuXLugrTSDlQ~uW^LDHGhmf`{FO!;e*#7SpLTS^k8Ep>lLTCpA}?IKDyRwAXD*I&sl14E#c)|R$@9Y_}|%w-ZB&qOV^d#pnWLIaLw7ly7r+# zb4o+%#E2zG$7|2u5oFJ3Pd_5ap3x3}OpraJGbEbvXhxtNf6al^Ryt=QpLd!O=;TSd zQlT?qT6fosK<8M}^<qnf=-mkb}dKn=M^eZSDixBc@fCHNB{DoboiN?N)W&YD)PCD`1F^O_TD;hH&(Kh4N#?pnK66gAH6Bv>xb8eJ~eVhIEN5L#m$3A)V{;N!JC-Kr`gzxU!_`x|n#z6%eZf z)^Yv7vZNyNc?L$V9C`g*AynAU^>vnf=gO1n3-)z=Tm`7GkL&F!LWR9uFSohv=sJL% zTt~ME+}tj*on0rl*lun+fbFU8Vq)#xX5=rjo7pa|Gx4sji`&93w$>~pzL{NUySc6` z0B%9f0^$qp0^8kna|>(_*WJyx75T3Dwi4eu-xj$_U}aYX7Q4z|6;}*abydKgt_RqI zznpJ-xt?x}`_=wp$3lOx^$&RA-#*Lx{ENI+l zH-X$A?F63xWJi)e%8dX=x{2;b`-7dx^B?Ub_k*qNCXx4p9nRAcZnCTGYJroWQ=qlL zTCS#>N~i%&flh-XS&6z0T7&?CW-z8|q#IU$?JO(qY6oFXY~} z@9@sMc7W>-4s-+Dd-h%1-@VGy*X;ZDJ>u^ZHgg}?&D=upedvdFp<4ic0R6}=aPz?r zp%ZXWm%^b_S(ero5sIp8PI&+HsG8~hZyqkF+VZ+CDn+84kV?2c}G_mX|l zZcok*ZYTG=ea`O0ThH5_Nj+z`b1&PMz?XPq7q>GxyAYnWOUd8PEp@Nhm+h`Rc@})u z{>$#>{$;-hcZKfmzPI0jyFr(^-Q9QKclKMmhg;@^-`a2No^B5({KkH5m%BZk@N4^( z9cs6BOWZKK#BBu*g$}XXxUIph-B3H+Zt1pg!|hgXOK=!;u-(>e18&0`BkUG#u^Yi# zTev}#bX)Kh=pb77RXfPON@@`A54I!i=5CQ2X&1ZA!4c4byfes-vWwh7ZWPZKxzTo| zI}kj`tprCw$Jhhi0pMupSi8Sl0UqG?2gg9i*|Bzo>uvkmKDHOw+fK9-?0DOQR8KpJ z)Og#CRClm1dEE#-Y**slz<$ulyfxl-vHeMPA#}B!?Eq4p30>?wxN<(Yms{@U*}dIf z;CMTZoPFHh#P@akfcv?9!4+;laJl=6r{hS?v!C(T^X%u)dG-tFJo_bd9xeW*ooc7> z-E&CIwbMyW2FH_{PHa3ljl9{U=h&Hc2I-lkW`UFloDOYe+t}8&rELpsY1=_t5^H5! z*!HAa5L(*iwgai=gci1$?MSMb?F4N`thsGUyqS%o#x{!LsEKWCGhiHLqNcWqby36< zM`&bo$jL-GQD^=lC+fss+Q>zXz(%&A&5fKH2o9v>a-#vXT`q6t@Z$+KYRF((&z6Ao zZ9TAotq(S|4Qw8Nl^fM1RbuOab-`az+_k|vwzmDn{pxDjpWM&j&+ZrS7gyWXB&Qbm zz5Bt{v_H5X!5`gEu7>@_eG7i;z5~B=--F-tth%ilRg0=y0$4rz##QId8n&9P92G~^ zY;jZttP=4SZ}K+z#B8OgD5`3UqRLSf;#F-GTQRB>6@yi5v8@nQj4Ff0wg{|jD}hC} zB1jCZXv>2Y!17Urs1Ph~3vFRkJ}L(m+H$raDo4CrR2UT~ZVPPLs30mUv}J96R5r@k zT$^JvHV+zu8Ee59jI0A=s3C`;#g>8oYRVA%)#Q`<#qbG2(!Ur!&wgvZH{Y3W%@5G8 zq2GW%K)(XNHeZ5YnJ>UE!5^Vtn4h4ZgI}1>%+Juz2%nqx%m?Ou@I&ak;Ctq6=sVy? zq~10kL*FL$u6c|2+t@T86Dv!26a0i!S@S8hET8u&m>*F-%J?&w7nO-PX%ta*(w~_( z$a~Yg4!&Vt17A0SiKX%_r4c2fmVGv$}Dq6)zR z^SpTud;wZuUW68ym!JhadkHKDeHQwh`4{-CdD1*>o-$8>PnyS|kAtg8J!YPPK1S>b z^C<5=0~SCZCH9zkg!rT8Vek?25csgU$J}dHf%if02JZpyhu#U^4c=|;GItQa6MO)A zJAd~e_#mm<33r&=$hjRXfZht;W^OPynH$Zu;0@sQ<~r~O=+)$03tnrkF;@}48oU{L zC3qEh3-n4p;}&xTc%}K=oo&8wU%D@#UlPtTpMjsd&)hlYZ1XAjnfr?8XPK{|XPHmP z`P6;l&Nb(lr%0a(ehvNDooCJk&*hDeh<^;8Z_YCxxeLts;DzP_@FH^|c(J(%yu@5= zo_0^UGtGy@KXM+r^R|1Dywl8!gj3B+q=cuMQ_RWGQ_M-=$>v1xBy$3IqB-8Y>|S!m6F#e@D*~8F|WJV+%e=FYmPQ=xYym$BNjTUXXpSOvAYmmZxAn`!`n4*Zx1Ir=N8W660H1vncogsL&$k>6 z9!*;JgQg_6fu@=j=1up8Tfx))%|gzD&jS}g7ZRIoHiORQwD%-VZ%^PaCUN3dzu2VT zWa|X#SDM;$;l1i_PZH#l&WVvpGRNj=vob>bB81&Wg|A?67{xsU0^k zx`DbSlitM8nd5dmYoDAvZfBO6JCtNw+h*n*DfdSHf;)7vj5uE1_HgA8EpN&RBO&@4+8a@Qmsk1 zF?;gX7;p^d=(p!@cd*;pZOt}jJL22h<#seD?3dd;p-b&jvn{wS&-UWUD608?$-l|n;cj=s%^iec<_7X_bT_#D?FxG*PllO02}8~G zkhIj?KR-FZWXyL%qn*e^lEahaaX&8?LqcxcZfaMUIkw5t^}_F54DHbE8SuCPhob0?91vOS%= z7Upz9b9177z}@dolKiW{$Csx<}kG_A&P;_z2I=U5Es;gF144~Bgr|+9pNssm)axT<@Pf0QgY99 zXYkJ9PEsZ2cH(!~yNJ~@ zcUj$Ey35{4>Nb0hJKNpH)7$OcR=0)jwz@-dH}BRrxAOEhd#gRyo#XDYx_@;KZ#6Wx zkaMfO#h&NRb*rpyg{`u>{kO{AL+WOGzB|v|%+p)!y>^vtVs0YmW_y#pz@6{zBd>|M z(O&2-a5s{3lWl75xA%efk$(gEH`*KQMeagZm;9!zWj$c;w{^{f_5tuA`=EW;K1A#h zXkGKDeFQ8vm%ArjG1_h?;#b)#ZLvArUIo7Cb|&X~dmZr`?DgOw?qJ?L)Exp|;!)){ASDa7 z@ZYuYdqG;o(~h%BqH`bejipsbe=+OZPX={VjBV|6CrJ%3#aL zf3j|&S7Hp&FJEfMZ_S(M{w}(|dG39oG^fSV`{&tr&UFi2{-$&zUAuzWH_zqCNjK8v zRYy0^e|Jp6i@NPq?HBx&9XVhVGwB*XY)>Zl3$Q=(>~LkallKzV;RS zfV!Qo`{(Q4JRd?&=x(}p8vB8|h3;>j`&;PRbu7JqzV^*?e6bJ08<~Un z3_a8RbbqT|chl-%%hcz|;N%UG{Xo7EK9Bt3H&dmN?)lL#Xa)Ck?qG#J>>nk zsi(62xJfs9Z*FV)aZCM7$yxFn-YvdSc}OtQ-)!%ULQB-2c?%_QMQvd&`3XKC=!7)E_#5=Q4`)pJIP zmM3|8=TV0wOHFds)NAW3zT~Z`e^-w!Ic)leswZck6PKj!m8R@V;gaOGQs>I+KeW6~ zZdsE0CYf)4uYIXarL;2r&Hk!=sZFJ{GD#&(Xd&(#<}tQx%t<*`PaGm^11bm zbL$)D)}u6EKDQoqZvF7&QT^Xtk2<&B`_HZSo?KGr)(_*q*tzw?Kif|^x88ehy;r-V z|8D>5-1_{#?pK~$?>)EPdv3k=93S8uAK)B+;~anE9N*>~-{u@Y>Kvc#9G~qR|L_F= z@NDz3V<@cUv>T$`vKL9oCrwF^k1M7Aw2tIlkzBC|~p(f8!i~7JLbFM+7DYdVQFc&j!(s`mP7>%ZMlBhC9qbZ#vs)Uie4xJ&Yh>;FS&ABeb=yY3s zTon>0i6rkrdi}IYUmlbeK%KulAC&e%ohmvHlw<{+wk!vp2lu}guCj~}Yl7MlD}!5d z2z2V9G^i6@Vgi%`HIAx=t7PIlQ3+6|wREm1mg6ot-q~XWmyIXMI>{PRF z##PGPiT@q$Ca3y+6X7MzUHIJTZp5#IxzXuN;ElM7o4fJ9%MEop4L#Hqqizo+RxvXK zzhrZR8v?d-*Si~BJB-}P=4#j84aToMrk%UWU5#G{eA>IVTqT<}*vY1&yVhOjI${Qc zgIx#L+O@&I6aF1tXRs6as2dB8<*F6o$)*cFon1?=l1*3KU0hf92zEEHEBG*Wcd#2c z2Kz#PkGt1Z@E3aFz3x7Dfxpk)58m${04s1+kvJFnihiWK$CdXN_y@oT+=H&5spu>D zg5<$S+(obpnvujl-#_R^x%2%f_Yhc~tIEWx4;68>bQcqPk-HGTWOE7bi`^xzxoqBhkuU3exSp=8@9BDh<+!Rq++2W2(6tZXj1RFxA~9Jo92-#`ki)T^XL;%hhxP z2(O8$;cB`5T-CzVbhTYSu4-dyxzfJ3>jRd-F6B%6K42f$7wk){QobMYO8Qb>SliVB z>$tkEgfHoZbzMDI+?Vjedak}J=8OCKE~_i+%DF7q!gB6Bmkpn+E;Fw4!7SLBu+In2 zcjaAnLbHKouycUf!P3|n2`>*`Kn`TYb%D!?e-5w|b_PO{O)lIyT`t!QJ2#jMY>J)V zT;i+x{HCg}23GUc!Ro#SSi{!@Yx-JXEngcfK-@gsmD}ZUO|bKVdBDcl`M|tjBkcTO zKCmHn0Wd$<0DGHFa%sRc?svNtOzXDV-?6vb$R&YEggt~zuDoW8P3zLREyPOeb`ZMV z?y%lPZVZ2-yvXs&ORQ1I@XBj8+jK6y+icU5&dqiUS38Nh!|t@sdG{c(@*>kq>o5;< z?-;YmZnhcRCQP!~MVy^>7vdS6dxX%3kp%W2G4IFDhiosM=6@9Ph}lh?U3RxE>8u;e zUosQYzH}CMEH23a(+bah+?UVnAke)J@#H=)b{rhD?c*Ir0?i4 z%viI}7IVejK4R{*kK_LslEiBJI{qG{iPiSfNcFh+gE;%_AGW9~=0*};$B)F+_2c-P zKW_Hp|A*aglU-4Fx2fyv`MZ(0Ro7=nQrZ)VQ^n)>TRwp#HJvtoB60qBJUAW+YdV)K zd=i;!I{@&_#ATW(qoyU-rzY9ZzayT~5nY7u6kO~A1U*FAyBEhmqBJ&>jL0*#f}}+%eC-fceC}Y~QyZfFJPGmoZZ;QabGsumE2f!jO*%c0w-G1B$h&PER&bO0z_9u2KPktFWokz)! zyxe^h>7j*P5m$t}3J1>`U%1N3 z)3W%SNDN(qe9$F!shvUStM)Z;2KX~}HsWOUi%lU{*ewAUBQ>(1E991%w7h+(Dc}m? zZa}ZJ)YPYET55{X8!si!5+qJ8Hig}fm?FWCrbv(+EaR@F$f``k*DoSGIaq`#8Z5_W z8ImlMd>X$HDV9Zpg_vT&56H3<77L08KM}edDVRzACou9!{(B@^77xD1lnA~vC6EgH z9a1k#1S<&rIWdyX=F^yLKD++~pB2ct{LYjNzQvRZzTv7=kc05--V^?-@jk-NiBAsi z{I5vtbbh7z4fI@Xaut!0y2<4XmfB4YnW?z5AV+nR%Zg0ZO)eYqRX4e%b{V1BgB-YX zAboX{TV|Kr&8|H1Za2FNkbJw@RY2bDW_KZyZa4GHO>VO*i_F{2t{hTuH@owYi@VvK zkGx##e>1BL9WeHtc7lD{-idhze8%2k@3K$fcNgYPI|83)!8@?;#{Vumoa^Vn5!fT` zllYCq+-+~i?>X=}JJD(`k<+7r)#vi}5ND*l$BxIojqr)!L~7?2_a!nsx45s63%bR9 zjf~JOZWB^fw>S*A1^J&_+&ARp7E-aZLxVy!bMq2L{R|d(wTigO11fIm~)HoE2ZC-5ig-A1>GtK58DE`P6mm+!h4bC10b_r2gd z*!P3?fp25yA!csB!M$N;+YN5EodeFXZ-Q^yx4^fFx52$-=Yn&&V}sjB+zsx2`vCZW zeGq)mjx{Z=8iwNRXAhKqi zW@vdlvoW6+%~~B620jEsZ$ayMqI<}Ww(H$!I|dwM9|j+`kARQZ zN5Mz!Sa7U;4BX&Gfurn0wv)Zl-efys3vaSF+YXppz>e6R3GHONfStji*zF0q1-!-H zYTIE8Z?(g0S3}h*}y=-r= zx9tP=v3V&2D}8jnr%r)HB41|5x#A~i?OTQ zD+#HNsb;I-*A{GRud+343ws541>rR?)oo=$t^%(j7itn(!`1?8g4bi$25W(Xv9~*l z(`#cztZVCo_3RF(nfngMZxwXBZ;h*O8`w3jfo%vjw2i<e<0lg5ahq<4o~O)3l8)tEwHAzK(MY>R+JY%-W^i-JXMF}pL|6{ZIzk9r3( zfQ6D)y&Ioh$Ox8f>OG(&21{1+_Haj-5tJPgkz|H9i<)9z%GL3(0sal629e~1mo-_)+p?xI^{}kDjefW+ zV}xYZt2T#Q2;GA8;j+jV{vG^1+y-7vn=OkJ;|Q7O_;KPqWU+1_CN=(4DJWb9>_z+TQ(U|U3&g9D--QTJ$I zGyv=$_2jBQWu%sc?0)$72YX@ni+W>ULs(aE5O%SsWprg!Jh~!k0bYq+9KS20 zYYFcPc8NNJU9tOeZ$Gdk-_$oMVN2Sg+*>Rv!FM3jo%@mM&fP7dn)Xq^Kp3@gx$#(2bUmg+R4-~v+*A^x-M~HV!RxVS zASb#kQnS~E>%%!bf3_(XmF2EFQ9JIagQ*)0A#VGqHa>NtSCKtk7OC57!*$`C+%?Ax zC9GXE6jK``AOX7m7P;Q%MdhNo#v_G)E_c0!PdUErZT#mV1^oQzyl5KIw9B%NTQRY&E7@QV zNB2edMvp`fgO6eh?}M+vO$` z`l5R(dJ>3~`m7)++G3smjvC3<4T^L#XDn>_$dDI{ARijIy z{)F{I7Pe$d^+8T`U=HJd#2@z6qN}g(dQ(RA6FS$WHVW62Ey%J52=0vl>H?f7&qiN9__|FDk z#ZDWgiQY45G4GpM_`DI#ie_NXqO@m3Z*j*oa9T7qDo-g~VCLd_Ihu>#)MzI4;Wh9z zVyELt@0+LG1iq~Y-!cW9;$C*w@FjzgY~2d`b>h#A-sb)(;9TtV-1oj&g#YW&JNQij zUy3G!Q?TE~o(xWoUW~dU)%<1G9W&Kk%hRqwDz;>rzeo6s(R-K|qW7_1h_1sQiP=Un z&$}TBeX8q*ndaX1&qdEhbHTU$Tt6{-E_%nm?Vkmojh>0#^3O*T!HL9p6Zc!-r0DtR zUH^`M27D%ZI$GiLNBO{f(J%fz|E_;JdJi)pnnTPt{T%;7G%5O((7fO;*gq40h5y;# z8Wq4jjMDqr7l`slgZZ}WkkT!A>|M^qbEe17aNV9};p1v&^q1EN8TuSh=Fb{-fwa@I&IQ@j0U$(Hg>YMhE>z z+;I?d$af(H(_I(LEAB`Car9C2BX=$KYkiI=d$gAOazqFG$J}uMbI>o3zK_0(mPgC5 z7ZLwQzsS#vK92Si=YZeu=V7n&*`sXHI-Zd|S{nU8%%zxR(NEF0(Kq0C*gx@%@1pY( zJ6lVlg~VEdSsMLJ$T!gn%-7)0*o&h@gfGS{0av+2QD@}szv4P$UUduoC(*oUA>Xjb z|H0e$gP&lp_t~PX(R#imTXYp=bv+XIuSbHqLj@!)v(B={t;cDuKT^_%-6+86!ievJMAS7DbUKP5f=W!iceT{g?g={}}i<_!ag6LJvmA3Ev6sjCMq0@qf&Z^3g`I5q<-=nQjm=s_?Mc7XN z6ydx48^nJY{2sd{kmvvG?SRKyeDik3rY?<7jbeYJ>$3gZT=bJZ3mym z&WV4nq-VL>=5yfAnRLKpiZVtAOy($4bPzm%zM2g_3+^mYW^f}dWWUK6Wr+5p&n9DZ z2%m%KtJ&l?`u3z}XhIXl5cJz*;1BT!8g4Rx>G@L}Ce9&nv)|+on=O8`-$$(X(SGwj zx>Syst$vF?g8yN2Dc`<1YVI%f!p+g9XfLroKts+4Xkgik`3U_qzx%EJsM+R!2e)!( zGw!<7H}g@FPrA%+iZ(`<`R3S7eNs}C)YPX*N&=v-2nco;)j@b}h=dbmz`|B{T z`6k3^>RS-LA!>nH9}UKLh96A$YyKMITno;`zJ`3B=?8(=fa{}m(e=cd;jhQM>KpT% zCScm6G)Xu3SNwE;1HP|-*JBSP{vfag_CS9H_8!vo5t@HKLi@}y^DJd?jC38v{hWW+ z_xI_N(kAuiX^s5=;tvF`#2&))ru&xU_>JiIxDovsEipHPH=A3)ThPJL5;F`OW^M!9 z6Sp5v>+k#d^hxQG#_*g0evEI4J=9P0Q^D!jLwWXe-`8hIN}tr%XH3cfrcdhUZzN=@ zAMIOl$7swLznicA*c>+#{d4{}Uwh2-A%0(f6Y*XKZ^VAcx8{zAFr$5MLi>Q3k}@WZ z!v7&Z%D2J3nb=dno3MKk+8fNAlqu;!-Kn(#L4+F~ReG zqBp@L|2#O6@94?By?jrfB`I^#t=u!&-^zV2`3L+}JnsR_gT9B)nv^A}2XT7(VZ?Y5 zycPR?e>Ji0$2{Qg^X<604|BiY$=l|k6KNirf_7r&n;>|>Px1lpHNm~aywBh3+hgAY z-V1iX9tqw9cEsMnee=x@%%>&{Ui2^cFc`*rL!J|$OKKP{8{EcsY$rxJvz@q~8i$V! zTyVR;&AVW@zuj*m1UZnnUGTfvhI^~|9n2JL1^3Vg&vbj}#dm`<-7IjHdjovK%?4+? zIp7?^SMm?Zk+jlv_uc$T*TZ)Qvyvk#UACmG_-9Yb2Iff0p42nA%irmHfjxs>!QK8Y z+#~(nzDIDUzXR-v-8<+=I(rA5NNaCGdj;Kt9>E>HdoaQe2k-DBd>=x42YrIhzLW1p z_;7Hz_vmZv;ye4kL08`e>`c6_fk*dN*Pt7AKm7ZG-F#QyAM6+O4_3Nvz6;?|&;^qO zCZU0=GbSzA1$zK-`Ujo3N{cR)m2Lo9+dARyh)IX0m6dK_&;eI^Fg@D8IuMdBxCZ}0 zXm{&?PkT(ppdGd_Bl^Rx#ujD@%9*RM%bC6IHgh|8JNdrXwWO8(O1@r$K9gS)cujCE z+Dm?Q(tL71?)xy;p~>V|_W&AE?!!F__k-w8xfl06n8D!S;Ci&0{OU%bYvmr?BQZCi z;pJEN5V~1z2!?*e@4aS0FgU5o$u^&U9&2VDgj=2T>H@7G77If*{ zhPeu@IkzS7D)M9o@ud~yRqWR=Gtd_DcrXt9#XSzbg8h0TY#LYN(0#Fjch5}tPUZRu z^piXhj0dN2HH*-h=#*IDW}&@gD*m%^zkzO(@xhbe%h+@9nT`IFCxfTJr-BLK6s{&? zPe7B#3O5H$8Y|qJ=vkS7PM8-l&w!J;nv4Hi=w*2kpGlZ!!DrF>G6}zDg0~5si+-2q zNa6GNJ%{#}VWe>)SHsYoam=l73qfhp_<^{Ka4$r+#`n0tCAJGExE$(kH?}G25n`8<8i_sDC4eq75m!LJ|J#?9Th4}#dnyY2_FGZus2f>Hn zSJ=z(Sq2_;$J`hAeTc@(qi#7GNWQ?m0P_*}5xP@;#{Va@UmkToqrGGSKA&Ueq1|L2 zI#NF4Y96{zJ|Tsla`g$CQ6`eo`CLs5K63}$r*1yxfcqTtnfrvR1K6r*1gNsLGYkEwb8iwwyTYK$JGmdazBGVbALYKunXa}uHoE*dm(X|_*IXDM#1GL&6b_LMEYtb>B9Y2e9 z;lr+ASe-i#xkfypA^Li=6IvMmLSZ%Zi5_xAa2H04uM0hx4ZA8jM-RCxOrxMN+PoU0 zRrLxqmMz6+DNo5lya;{6S+ScE(j>^tbrRZ$vtVb!P6CtAgq#tR7EFuYfdyIxpD zdRU3iJ@}OZONFJu(&(CnXoMSfh(cmv;m>Sz^^R&ge!4fiL0_; zS+rqS#1@uAC-#My^TCP<_xb3)uE16Ku(@d!v<{l1O|4aM0eb+r!?x&F?T&vp^Z++TD{*H+8izf?HbGl-2)8Ay6TVHsreQO%Ggm#s z)J z?u4q`wtc7odH&AG(0=;c5NA{^;br8yoPoqT{!zxi7qf>ubPk&>egSA%oBc+|=BUuH8HEc`y{)`9XXhKnL%& zXh9y184Ql#Y80UlqRDtTKDT48N1s;{G*;b)>jv<4?9uoQV5~a4fp8nxGwPMpzrB_KRFUhJLWe!pFhMT)l?> z4D`pKc##GZsb4jdOgfxfxg=5=(KO~O43_e^w~J&$`LW;{3^t!r=KKMTER z6LCL_EqoH)Yv17iM))oG4Z7gIA>P-R+30zzZN3Gi6XUzEE*$Ug!+NGJSRWqv_xOB= zHo32f`4wgkI0s#NUt+(BF1Y%{_#tcni~I}x-b6#)o9N;D0y7ugVhzj>U_+SZ3qxrz zTtLX&Z~^A+a1lNW!_T>TJNyy%qVO}W-Ui=BBj9J4cf-c$1zij_!u}M$cf(rf1ziFz z373LP(ePOduKVI}Irg&fCvZ7BJ8PlWv$FXF4Sto;^7kot0exjI_RDS-$j36Wi%PS55A9>E8#rC zs^OX!mV@g*pFeqJvys1fOa9D%Fs|O`iWJEKhfcb+a>1F)1II2Gti0^lV!G!|uH0C$m}LGe)1YW|rCH@cG~%=I{xvYCaEN zoP($20JF>XV%g-tWCzhr#(qi;CT^CehV13!V6*HPs9l}h*q^bwmf0M|eas*Ad9aUw z+Of%teHhgKOg`*SiI>TI${m@_A$$(ATAd&J3qmrPgSZc|9$f%i>x7w1LEHyfgDwba zwJ?*JfyrpJdXv$-ieDyBD}}En!nE3x(agjc@OA802-O;mRt={o*8isC*4m9$_-3){ zW6ZR~y4^H^Riz8PJwUoCO+D|@a84_rufC+OE7NU!e_333)f`)Uh+SJlVJzV#pgw?CbJtd zm+M8iUxe%RHtsY=dn60FegRyBoz`eaBrX1F%n$fZ@;?yr0=zrzh@>Mltyzxm^XxbL zfc+D$`QUQw^hWy?>4_=bb=r%_V6^jqCSQDiCf0m*OXjmuu3eK){61TW_ORDhWan=$ zZn0DM*~;b*Ocgk=74h9;FJzB&H@FApYz1~r_Y#`7X{=#Ss5EhOE+TY+ z9U7dR1-)~i#dklgL%TGEu>SzHTT&Q%HTyiBf|A56#R-bYdAARL?Ryl#P6qd} zZ;=ex<#mN_ufzyD@wGLi>ZQZx&+enMLqs`KRIj z0cLJ9{#qS_)x38X@wIwh0{dv-V2~XR@*C%mfJcMxi1|HyUX5IS$gBJ9J29${{C z6h7fGOz4kuB@E%C9U}B_@GWzeJHLMXx7cM0BikT{2Ew#S3Oe?y#a zVGrvp*Af_~bwT}&1I=JO%HF;42Z93dvJY_A!C)16)-m{+_}{=wZp2@3DNNKlU~Q8Q zwxs^&<#^Y2A2Opcpl0VGF3mp+@RVhgUs_m{OR>MQ4f)G{#dE&4e+1Gk^#^hGLk0=M zW6mO9KOU-96ikpMdw7Qk`l&$dZ zW(DhD&dnm`8$nv`-{;aYJ3HX!6Z2C$lThhZ-3edq9ads~2gTWwR#)LRxNWZ!D($no z+)j6ynGe@o+L`Cu_k!(ihkK7zneD7#?IKg2(-W0A=tovVTVAw zA{_$lft2FpM;WjTxg?FVJKX!2wXA~eW`A!6PkSxs<}xrQ>gF;sd+g>iF`w+_GBdaA z=CUyJ?B=pE3+?K%F+1(*b}-xR>WXl-rmIUfML?ZZ>gtM_qF`2HcXc~ir|9Z-v5L{v z6{ZZjQX0E7?=&0i2fZj@fT_rx|Z|CtbnaoiqS+Ze^X2AEp(#*hIVP1pveT8`i_p30) zuVxisI`|4~@~hCr{yH4pE5Iw5lTX8EI=u6?>}$@1)7!$d540=QKG0rMd&;*1tHI}! zC+!36Vzm#ni!}@0ZwoUEbGezyz0+X2w_&Hb2Wx}Ba1KiAsy#5QvAf^!>p}kh27Vl@ z0_U*?*Ta3n+FK7dpH;UW?o-B)J=|xkyY+CNvl7?CEnsb~2djGvKxq~3K`wq7bS4M7 zxXzq+SZO=ERh)U~>{fF+qO)6LSA%Qq8gLzFFFL#Rb{&l5S@v@C24(~94V<`mneUtm zwuZ|vo9oVSjNibXg3rrfD_9tF;2w8&FX5hIU$QM>ZA=DVf`vQ>|F^I^yBG19Y}+yB zeGxA5Tll=d)r)o#_=0WE9_J+3e(k}D;PbYFnaD|k4(vxwv^~j#m7LwWkh5w%Iem5^ zSc%hWJzZr^r}cDId}Z(=PM`H8-bKEXdz*K3a__)*?&RKuCEdxr2XDHQd!Mrfo!keU zH0b0$C(Y?Ait8Ii=Q)vTGka0BgF7c>vSd+-G~6E?^gPKWym-Y-ckH zTiDrjGWXhE@ObVe&VBYC-1mY#;p;qPN7+thB<_3Qmy0noTI^-8lj&&g#%Cm~bg^E> z*wMD5xeNE*@Yls?xf8q#cDq<3y*Qy)-uH49IF;9nZ@fC_<;wGwy~vLWz9Wq3F}5R& z>4(9OIUUlGefLkmdG=%Q6Ha<`B#oV1M;O)}O-J_cJD59o@||$3A0cckc1Je?pF3?mTaU$OI9DTJEkB0)cHF~lUpP>=!?x@Tjw7U_8;1Kf7}4W!_k%w*%=UIy2Ui8X zIbnBo(82YGUDd&jCq@VNBrNt0?kQOI9oz&M`5oNTF!(#TXJGbsaL>Zu@8F(;v)_TI zJ_q*WX&u}XJh_)01lOq-eCa`^x9w#InjUtD83Yb8J;ly8LriykdcdC^2(PLSZ0dog zo4uaBb9mf@^(AD0>1qeV@aT$vH`vt!U~=^%WPs^n#ntITXjk~waIQ^%Ob6H5ie=Q9 z&@M2r`|~veu{*d-Zfz6PK6Ty=n9&aStW zF7I}5TWnq!lxa)J8 zs&!BspE{hes*k&t@8jBlZSZY~U+bVIKD9U>)ev_L+%^5rt_?i;TUqNCwuVWs)5EQ- z&J7D&!J)s|wX`?6VeU$J^TTjo3EqVL6Zihis&`u$_qVw#;LG1etSf9^SB*1~eO-0V zMD}$xI1|~Iv!6A5JNW5MZ9BN%&A{ex!P~)GZ_mnjCD{4PdCpJncGm*V`0egC>`S<> zs$b?t!irwzD#JQo=I${g%`)OIcf*N$xgCzV%r3=$nY)-#)@Q#zL^wIhTk# zKfLybIm=iWj{5!J{hUR-i@V#wQ7>%oGet0qU0&kkg9kr`(~!w_F}oAVwg`3}eDcDW zAI%xcyWL&fRn-2-4n|S?2+zn?&?Px zFZMaDPG;sLPA*&A7PAZ4cPb9vL#%c#2cbD(eiyf&yX?4g*he{+ncXgc|NJ@oPbCS< zhF^A={EwP!_6vL#up?Eq?_c5bC3{h2;lh87 z&sXe4m4h$;4L)DH#?-9V!ME-_P6B+3|2OQxoX`1y@9_DS{hRY~eecS1mY^T$fM>z^ z-+umTzPcTIXBTo-;WJl(GYX$^Rl)w?F5oo655(85&u3iCcNICQFrS#8x=&nYPA7bV z&wSUHC-wL9@cD#2wZ}LWI?rW+<3G=F%G7@B9_Li($N0~4ee_QM5k4Pt4*VWYr+aC9yW8j~lZxoZq4t{J<%hPSeJJkC6X&uDhDC!3edxZp$g zfg8te@Q3b+-~;zQI1YPMAhy~l;ylFO_=~t63|=rVn(@K=?mai2-Qf4xFMq*2$X@y+ zPH8^Lp6`3?ay`cE{^ zWB12@0Nj9U@V^$*93*dpLOivHFNEppv-6f5aPyvF_xdf~JlFN(uKq#4Ky09XL2Fn% z*YS)?gKWgi&dJ6?uB$JM5v!sl{F}Z(E4Vg&iP;a1!F9xZj#IGrg7?BRDB{Gz;1nlz zR-TXzj>xm@fxpQc-*SC|HZXqr@SMJ|5h!_ZFm~@i44vMD_JNV0{jM7bX&z+Z30YmT z6W1fz6~Uh4o?~Zy4$tJdoWZ>(cos7fj)L~bhH&3yuuH_y>BTd92SvHNlb`J-2G0ev zxp$5mO1u{E7=~c?BxbMR8O|Ax1V_SwxRH<+!PDmMU<&vQ_7(WGfDt5C&cp;C=Q(g9 zoT?7+m7Yzoat3hS4i=P{J`>CoF$OrrJSBL>7v=5G@bw+Rj>H!4>T1|tSNWd7AWRQX zTp@9}u7*ul)QMA9%oTMy9}N!yGdZ}%_XxU!gRuLPCs|y7&Y`CVGh+AWTz*C{Gj@N% zGK1&4^T6`h{fSo|nG*NWlCQ#C?VdC*!b^D4Oop$Z6WK5rd~sLIP4FdLaj=+s+Fwbk zwYPT@_LcB8ZVImT-GZ)Qclb17uyqfnnn^GirkWSvG)(1e_Y1*zU(%Iu<9W^m*lu0n z(1;n=HJE0e4<>>WDT8TdDpxlU-X(aF_~YTT-GKXg%w54?uI>t+@}*o!_Y|Q|`j)(1 z`-`_=PdC%dY&YG!0UK#Lt~cBh#C!_YWocK+4e@uvM;QW#4$cbZ&R`t=VsDmlrJeX_ z@K`V-U^=|uUWCW6JP^Lf>4R6ybTbQ_1>0#Eq03=O%-|Hm&oCh-gOfRN(28$p89eUG zx-#x@U(S^U%eZlVDKVG9ws;MG?uy{&;3ZH@{3ZA-4VDD2!;1YSSP@JC#fTRJ4i*h& zc(9nzCE!e$u)o4Gco`JK{V|>|*6Mk#ococ`#lcG02UFcj%ry5Zr%7glGYJzvZa8>* za2q&0xSjpuTY^^Lt=P?AnA{59hCP<2iR;>*y0IvD)%*xAVP!DQ{f3$D#GAV!~77uX1<5N@*1x1gXi5k!k%|)2^|J+u37M=dChzWeh05*qFW!V z1J@Ble70r@_FA*xIs7MbW@JOKKA6L~oo~T!;k!KRHU=BO4aAtu`JZos*_f|`H#lV^ z{2K0sPBaO(2it-Hr0fwtfcEjQZ_8I-g~XKyu-hWlhvw?zWUXr~iX z+k%;x--Fl9Oe5S1Gvjq!TZ6aE>t+kMIoJelfu%8*(?OfSjeOZ$TpNS8IrHW~-5?Z4yCHkt!pD&0(h%2U?j25&OaPzZyvIA74tmDb568pmuFqW!*tu>Pj&=3I zCt-Eh!@oZJ(~a`XTfA9YPIkGMMc*JW>i0vzzB;Uh?YX-fDb z?oo2$5nmhsI_yd}4Ig&RFk{@iW`e67zRQWA39tsf2*1%@tk?G8N0@fu zD109B;`g=-Kg3)eeqgR*NBjeGHM`?t|6Uz_3JbU`*oM9EPjR&gALOo4{xkL!TZW&R z*6cKX26M7?_yGP7!rdI`9`K*Tc5fMej=3@vi?UhJkA3vcL_IE;Pz zuW=0v7jbI-R`3?~au?ycCH#?n-5bH1*}whKEW%#Qe(zB5N9@IBDDNH(GoZCwg6xFW zZWOME!ZGagw{{O=MuiV^)!IFfxPFAI*6#jr2{G?a_&&<6ervZB84dS`OELGsaaam- zVHvE3d%&gGBeCxZTe-39_qTG7v8&(8J<46J+~e%@w{qjy&u`_PU@w0>JNB*Ia&vch zSGe4a4DSY)VLwSoEB6$3EBBkZE4(xO4cQHMg)8Aq+yNr5ApF(b0q;Rl6z&LrF(cpy zNXEj5aE1BBya2ucKj3Gx!U!k950Fd;;Y8Q~KjE4ft};KF=fG##JU4#cua% z_Pr;7&#<$-#;j&9d=2I)@F~8haWKe@^o@gSkWbV&!KiJVVAM8FFmM|u__>V}%-qHa zX6{VxxzWvnwQ!?bYu1=n?sa@-!aA6R&uh3}hf(kb?isjWgBh`wICJp3(Y=a$23&$U zxZlFQ(XBIUVNa~XyaIpVEqtbP^$Ki(xwzLONnm=o9y1Mw#(LNp8_dhFF*cZ~@G~|b zVPI-F)V)p2q3#{-8S37JVKCIa$Nv9N_dYxP+sqWW8rzUUFeMbD`6cirm>J?V3n#vl+XdtBcP@Ge7(!+-N=x=YyND2jg2EnO&E-i@~bcgIzW3!T44~3e{lz z>m#q}I=3B}37>@9%{&+Z+i}ecs}OpTYe4vQZU;>5kHa1C1wI5nhF?&b&?>GW;n%rJ zxGTGzu)IGEcVa#WE8;i{Wm(kG&{yy^N5dt^)Bd zbPK~>#9T<|BJcz3jr?w>G2TvKwgNzgR74yj{JgGPK!)1V>W(==#| zG^VCO6W7@N%pF7AZaD8hgu5}{!&2D|-(&?0k0I_C>>+NC`3_FY9+>#w!D-n8ljT>~ z7em}i>>+Ni`5K)p46#CP)bK~vWRK3_A}6ui_m1Dm@`-68WOd>5TI z`7$gK6b}Z&8obOk2QPP*fz64RkLTnEhalPQARL+nq0X^<5jG%B!=ORX!d(te@e0?% zl?+Pogp!yFE-&%(1v(Y8AUuHC64ob9gP?wJrMtrI=M?+qP$y%ygr$NC$k{3tl*G=% zU3r5)%w|q(>rBk%P-kB@fg3qRy${#MupUpSAJhw4x+~og&bw>~kC^qGY(9c(eRz}; zGV8##;TmvVxHdcnV`VjX6gxR=>FNc^;RUXxE5e&E0Fm_-770rSrGf)6VTQPaobVS8 z;cJd_wq!L7%F;oRuqbb?8x-Xk^@9DdWmX~&U?p)6g?W&(a|l@gd4fX3EDRH~402G4 zaYx zAa0$Y0CyD(_Y!9xQU;EMxsa|>2H#^`@)0wCScwo=uWP7 zg@HBJ24%S8ydY0lPWQuVJP$@|9yqVHxI0hiIIf{H8KDjA`9WDi%Mt5*Hi~y3e<9>a zJHP$tqrZ`2@YOs%^+7;1CuknAUGcu2H+ksVROQV%?UfU0`Vn(r#uYG?7=oyU%J39e@qVv0X{5m#w>zD{l=akf57kO^5AS-3lsO&6p=MnyXO(;}rPBl0jZBcUjx zO&_F1vPF7A({UCfbCAJi!lbtuf^;@5n3gb|*GO+O;-ga>>5-Em&J=P-k+78CH0In% zGpayntdWe4SYoI#k{+54c2+u*7R-(f>k1}KR<4jLg)0fEz9me2t4(~PO{BpkzFjF(N|Yw0SSeIm zl@m(2@<2JH98ung&!(JGp5=z&mX7P(iF_3MO+2@pn0#P9-kzQqIl*+;23G*4$1YMN zb>4)D{0n)5BL;^y!6d%e@GTJ-ah(@qKtl@hU?hbuFLrKR>A^hMx&F_aawp!QvK1ds zU#KtE_v!nUsyIDLOPo5TQz=)fl@H1h<%TC;RJO_`<(KkN zqx?8g&XRK4hgC~b*Y1q?q^{R#NM}kNP_0m&Do2%z z%0JZ{)gtAe@>R7<`KNr1>z;B{X;fO2qe`9HPh4MBM>3F_41b!&f41$OI&c5k_ZBlH z;71gL%Txm9hd50|F_OzH{!ucf3D^YRBKSxyb0b`Z;RQ8MU|NjYpqPVcFlvKh2qs}vKgAG?Fsh$AJ%6$W@v@2f zSvJuEN+XZhV#-oKrKuzk>kcf1Z9uiQlGxc2sm)5tbC9|mTxUt-OBQ^xk`CopW{gso zJCQEsrur?VOS!C`OzFytD}AC2(t+w*@?)n3RpV4Vgu3D6A1+XG^EnKy!cNKBfpe9rVD`VHdC9OG?aaE`0RHoil!BrI$ zcl#o2$#NH`TdeQmiPRNKq^KC~;^c+WRTQIErgSA^ijrSSk>paVl__0?F_L~>4p*T> z>I#A?2c@n6sPa*|@`Ea|3$XKnDoLd-FQ`_gbmak6{z_eLQ1wFT$_1*{D0MkOwKAnE z2dG-66lDk1%9J9tFSRnIFDs}TcnPj7i8NzkF14~cxYAHUb-+4YCsA^B!Ma>Wlxsb(UZNh>$K@&S`d~wB z2de*Xgl#dZfsJs5)SgCQ6YKyC6E!XXn007@EIt|w>PsBPlD71?#NOA)K=)-xJV#@NB*Ij~G**a+ zt$dJ_Ue8mMOKB5NNrOx8NSm;g&#GS<&&ZvDD~&ufQq?F&BNC05GbNs&aY;tfq$g{< zl8Kb*jT*;fCROqHSmQ;Ft~3(TxH&uT()c)K1g4RhMl(u*-lyEtdz5PBp+-bXwQ^7I zQL2@PdXM9M%0rE;JWp4S>OB!pSNqp{G``e0R-;{wJ2lGHcw6I9jea#cPRAYkg7jdV zXUefSuar97;kjG+rYAX`s@%}&0?Qq;^-hfol?si^HBwYPQTx;kL#3v6nx6YqyEHaU z$2-#|-mKC-8+jh*wsKy%pxjo@D;MJNuEwVE>?D3~I^M1?Q{SQY>x=beDhZ`TU#yZ> zsVF5Xd6kM%sFGKyDE%sVm5OpgC9l$pYf@aN^bgf_oJQrdW(X&0mtw2d>do;8TW^ZT z*_u)4%_Cn`01r)sKFqj##NDm8kWo~YF5ZF-_o zqqpgaN{!y8nyPu8-liFn=6R~og%fWo%+s^bljz<;_+_Eb&@&5irT<7l+yy|rzW|sY zR4(TS^MP@{qW(m^OIqx7^dfn2rNLG$&4UXGxS-}yN_j3&^C;y=PEhkG)zciHW>Ct( z?4afz%Gqq7<{nDB(q8Wpt_@KyUu5GE!=kd&<|ie~bINf7i>! zEhX;j;ufUYRZ7cJ{fO5WRI`-2l%7K6o*6%tgi^vuEZ&wSk+!U$N>OQ6Zm1NM7s@5| z6sph4J@pl;&&pNx6{^q5ZS@su`6>nV@#+y&IvSyQR(Z<)C_UrBta_zoL{X)p0MNFIB!OwfcJHt5T~}DPQ9g6e`6^hyG;B3Dp?=$&^F!SVKLw+P>1NTB-V| zbn1VhQdVy252eyqZmRcIZB%PiE!96xC9gCpch&M#E^2dOqP400sUE7esr{)Qs1k?hYJaNXYHiYylo!l{uV#Om14?U>Mrj(WX&xwzO9eoUMl-=o7`3Kkt}qBm=TV$9aUR7v6X#K! zKgu1A%hbZoRy$2yZ_j2sJ(Dylb?TE;8&0kRDQz=e5j)#$Q#Cc^J5>tmK~-y23hF^s zYva*`T7Fzh|J`@0Ow@ZOkp_*Gm7WNf#(%nBV`z=I<6cC)jOxGIj>b@G7jfHBeOLdd z@=xh4^(A_;YIubEzjJ(|{Lz0T9=+?`s&}gS`YMg8RrB?=s_&}#Do2f~HF{TV)u>vd zca`d&k0+Hnjf>UKC|@)#R&S%Zg~k}_ZBqXG8aHdDI$pK@d+XI&L)Lg!E5=$q);KqN z;@jiz&6Y@0oDQuUYYkcH(~7ZHkK^@L^?ZN7pI5y}{ohQT|H^%hZ~uI^A^tM`jgLH*W$K?2=c@XFxSgDOCL6am zwZM2*8@IzVnG@-o|4toN8RXxGt^Zv->eTqtQ)4yi)c7+>{0HOlCps~>ipQU6692(?{FyfKAB@MJ=@S3J zc>Ec!h{og342i#C%J@@%Lybb!-t{-sEJP~>D$h8DO5b12TTiFoi}xW?W^?LuPBl}| zcvW>gE~&VVtG1uXT7i02{XNyIsCNC;3Q1hAG;&dmQva?R7XO(vThNm-gPOsprD@cw zeV6!et=RGZEv}dG|3ptydsF$VMyTDzbwT6fGaGB^OEi*EE&KBkm%b<-fvZ)-D;E0V zls-0|bt_L&TA6a^#7dFYFjSuUV%2ob$zxmB8k6Ztqf@Qg%P$8eJM~d_NYkWbcIbX- zpv+0_)b~gyrKEc3>!h(VH?>n=B^{QMl%f31hsm25nMu2)MsO)BY#PC7WF~Ex8o_B~ zCS92t!D(bB9hw@!X=Endni|1rd?uZn8o{Zhss3mLr?;wZ#3S0chNRAul-$sNO63;+ z*HiLDcgCv}>ismgQE#p`uN>ANJtfcM8I4woPQQORlYZ>)wh^uSX%rqM@-^;Fl}e>M zUW1D3i0YjBG4%=hJFDkY4fs!(lg8f~vlik$?Zo$=jWMBeNVyS@@J`I5&vagydOQ&K zT&gp1D?ahZRQpnSLAps*_x@}it=>mtNwrdq@igAmQ~qDq(3IX2>ofoCdaPDr#W~Q( zO)IfEL9NPaB~}~-t;(u2Q#dKHTdgx?&s*Q8@%`B!Q>mo&RT^2T$59;+pFlm1zC$Z4 z@jqT8$@ovNGSkYEMqBDRw6df>y-HO7c>U?sBDJ!llX z$8U~T$Kx-GSIy%u)yO0z1sbuWq)aPmDJj+nM`LQ`gjU`(3Q`WGjEj_W`tlQN3;Oe( z-r7R^Cr(*m$jE&uV}O)Vdpx#`TWLHuQ#;kys8#4r&E@{<7~s$PkiY5!mE&q_n)9k8 zVy2T;&oqkG_+8@&jjr{zsx>L=?do;oUPQHAPtiB3HtQ)GUud?fr)b=vH^gJ~l+|gC z)=yrY*68VU`WBU@R$$X6zVF1!LCU-I%_-lYH>Z4?z9{9J^`$9u*m$Mw#Q!30k#Tsu z>KWgsG-wWSx@(vzD|uSUPkHZ|=2e_as)s3gr7}s`n>f+8=(&2IQgODvUyLs84vWc^ z13TVvQX7iE z+Eod7oBBq*H9c=v->SE2UYNp6i#dI&m)gZR!DQ3CFrN3vdo1x>Dqdrb*9qeK5w9P_ z<*DyD)ApzuuT-h7$Md~-u9wn3#65$0ca_eWujiy552SA6XQK`NS-pzu(&^PArTlbe zL#hAEr?bX>I{yfbD^gaa{#{#B`NVDe%y-S={W8^I@#&HhC8+wSvP_vF#^aQDRqC&M zhIsuWu95NjN4)E&oY7vA+Ce-vNL|(nO&Pzb1t^}%=S;_MCwfWkVw~vf;@TPKlhUIW zuf8$$e?fIcGu^nX^=J6k{hCwt$@-J%{&>zB{|Dm#Sp0v`pG|)_eS!XXs`E;p^5AUo z0nXMMb?Py2+(!PjzdcnRp3c8jWf9M2mHN0o$aN;|@!yx!U)8;oambmkMV#F4sitbb zB(Bq9SjRP8tw?K?@km0uaq-HaRwv>SM?Ct7*C^uJr6Q;qad|8wHu9s^aoVC z(I`m0ibg^4_~*pFy#AyocIUPFq5O>J@|tVuO699Q&x1Y@syx+5Ij%itf4rwUp3>jM zJ*x6JPIH{nIL&cN<21)9jnf>bG)}X|F!3ls{e{L2ahf%f(5PQ;Qe9N}sI)bfP`N3E z>O(YQP(9N6sF(;^4^;ipzL?etRe!W!rrk8vAMK-QmreCY`)iszD2L*GH|>FImJ;uZ z>x;BIr`e3&t6e*dd-PuI=4srczrA+(^wk=}X!lQJ9<^2N3dVbdnoVh?Ic9IGj;U-k zcGh<*J(_W8wMXgHj7xhHDp}3A#C1{mYR0AYE0wQiTw1@<2t_k4tzW5)X~w1XEBzTX zg7{rGiuZEx{Z3b_&YWG`RChj z{1?@i#N&UpT>X9Y=D$BqNd50l-G{3-sJ7`}bf$ZJstqUhTaoX}Q`DYP>YhdqDRnaD z#>911`_n0PSo_l{bzA$>DRo}^(=ii7wO@0pxQ%FkI;HK1!;{jc#O+CGYvTN*v_Wx! zGO@lXmXKPe_NUcWwKIJ>?fP`)8tNUjGp3&7?9DY)GXFh$iz)w(_^zWfuK!xykH^jGdDSDU7gmp~+OOVO zJ+*pp_1fye)w8QNSI-_ZGh#kQ%*=?H7^?khr}{(a&!N9X%+6QMS1UNV{_78g&dmCwrIKVMb&^YNSZQFS6A2Q1>OnBrhI>@2v7fmyLL<0=Yf!OnzByAGMLGvd;2 zg!Un{Pf;Y18ns^SSm+k7l zJfG7DRbw`_9ks>(sXSC~dp5?X$`$>&w5Is~*ZTk8$*XpWj zs`c@VG2SIUllGXp&xzY)Joh;pW5v{eZMEfp`o9p*LDbs+-gye0PEp;^sg;m(EG5B` ziT+FHTP#MiU7dSz7>zk~9>!xd=F~Zv2%|A)Ib2DJQ#5Hn^}RY>qtiAjN1feE2dW%( zqAES8a?~lE44}$Ur+0LcO8u(N24(`)>*+*QW>9}Mov6wJs+ZJ>DxIWK@2Rth*+BKG zI#H#QRO&l)mMRCRzo^cS>9k{2uqxNN5~q!F;iGw$&Qj&Zh$o=aMtLye3Fx#@UW|AG zI%kv*Bc6cH8Rf@_Cs3EG0vMgltc$B4ws--^IyuZ;hScyi`tc zd1+pJqP(*H-}0(*QhDhdTwGok|F0-7l~jF7Nu_qG@=`g)<(2#&UtVY0zW%4mOD(G| z?MbaHb^A(PUOL4Ww=bQnPHA67PHJCjS8@9)dRpyEE$eLbhiBTp&Q^c;zq!0px3B;7 z@;X(2c&hf5x1L;byU@=7QA|B3%s>h_hoyi)(aPSqdkzZL(#ik$En5}XWG6_RbKz}|Lbg(*O~T*smm+%c;ig_!~bpLjZ?L+ zQ;iSLw0)he@!^@4*Z)+1sMGNAcwRH{zaGzP93PM8wT5@lklR?dw$i;pvR$Pt_luYW{Vq@=DzwYTgykzqIC`QeG#| zzfzZ%=3VjpOZ!|YK}=Fke2? z{xEfUovMBPo$xXCBzD_khO#T1*r~AXy*#XRALv)ACBa-g`RZjZ>A^e`kMqrsZ|2@y6+l5C4hsI@NeytMigjBgu!S zTAxqdzD}pSQja%IH9kDKeVy3<2o7hB(o*bQVbL;r5LCk2JH+N1+`No7E3ay9Y3*KB+o@V z6=H0NO{X0~F*zjvMKf3N$YTC$eEvA*zsBd1WB#jnI^yMs)fAs&j`^?g`R17a8lQWP z`LE*X#B#VKn@fyWaY}RsM~qjMhgMc};x>ghp3tNTyRS2w&T@zP9uoiX=Tm`_I*wu06 z2Wwzg!<7%LjxAZY`9Lw8B;{84|FL)00e2MF-@kYF?#%2H7vk>j?kiU+Me&F=uvXXJ>ch$ecNI1`8+r z-U6|3;#_+m7EXA-1!CbeK%t=^zCHWvs(~QBKKtpazF>dFeT!oPzqj=@duL4G_qLw2 zFpLTO-a;9A>l(kewWS4MOyKvnwzLC`3H;vHl2(qE<`nyy(urf~iVxfx(vm}U@pW6F zl`6&r-fvT_S<#btybW5{$F2sCx9q&u`SDuw@1&~^3I)NAietrvqP89%m5c|*FcwW! z+X<|U9vCYD)7w|J6IdC&$A40<_+#t@%IDFmDu*m<9dlXp=w- zBSUT3MQ;|}>{7)(7GDxZZ)@lp`*L>W(_>h48-0e4f!~a{s=W;1xqz?OUb}2x4kHd5 z6~1h~36MMB>pa1tk6i$a3vBuLPxDZZ4GsGxu$99e4vScL4)$=^g+a5ihlAH(D~F9G zyoQ|$*u!DpisdCz0kQzLa<l%CUW2=Ta0dcn4Kr=Apon`+rl0eEM(d90;k79mc1}Y09eT4Ka#yL>^oua40~kQ zcfy_;b`O}pPuh#U{>U0o0=x{P#h|b8B#GZp`ntLP6)PzEx`pasen#0nfEQBykK%_k zuPa7VUB%`b)uhT*Z4+9A+A{8F5t|KEZj<|W!NpRxiMxl4k#4Zx^~AH`+J}c z)Q4Kyua7ZCPrxr|X?h4RMYOxwEP^An64Dd;}V~y3_#51J&pM8z?X%VRt>FnYjt{j?oO| zDS2AU=rjB^qucP;jGlufwwD(yfuBOvz>jjjAMg(53~kylI-p5L6`=)28K4#HFM@7B zL)d)*J%P5cD}z0K&>VJaK!2b`=3f)MF`vTFD`=Pb;{^YpZR`sHBf&HFi_mZ28I+K} zfY!3VivFi{@xzOMsS<6@`k(Pi9ic3=1$Bh7&=%+!XkXgGC~jT-WrfOu7ve*N*(Ll8 zzqiKKG}mjB@jP05)!W)ynfB&?!EV#BFb>iK%}FzIA(w)e$f!uCTtO{t46jYPge@9pGH_Z0C-ZO;52y8TCJ*QHaAr>%U2!T8r}dZ> zDS8?^p9dRmPU}IcnIMRzFwzbXoib7okhK9Q9dK-Jj9QIzdN`$Lv|5dGdN`%WW{#uO zc4oK7IXz~{2c;XKw!>Bo8};F8JF|D;oF3@iP_-K8^l(ZK=Y?>B2OCx0j%a38v`{4uySK;4A2-ro6p$juQ7ntDPyCb#sJ!X#ztT1B{;2zv0*3k zVAIc;JyAjvs3!)yyvC+LaDuCz$7!^R)0vQ!Rb{KS4+@&}wIu}O> zkR1uj(mni`HQ`lV16kEID_WTrr`^lfKvs2)(R!Yp3d`Q3P_BDemW>SKk8!!OYxt{b z(^S3&vNmxS`T&(cwy=HEaJdzEz|16g#x7JgQVEP*YWK@0E!0EaMn7>`ZNC78b<88eq)UdIfB`6}~0 zW*E#@*(u3BNz+~6lK_bZDuAy7BpRqdNisH#2l=fvXqlzwHs&`Bu344W51Ug#QFxQt z6cmLLkshfzJ!ySGznCP&bL(I8K!_~9^0HW|93-;k$zo=aJVl&;3Qm(+_eImaR6! z3(P{1T}PaRMbEPvX+)9kvqK3Az@8;`F2Mtg`eO&lxk>aqCrB9&FdD;YO7#3dg+b~g z+b;#(H%q?$O5=1k+g}CUH%qdKoXLJ7C=qNd(Zdn9T&7}OqF8vKIVqd8{;K<&|*GBTj{%s#0%dJyI*)Ej*a zGkx?TP-bfZquBI`&4sP6pvcUZpv%mkjQWF}Hs7_iRhtJJ-?US1_zpS;8>?uNO{;8v zD_CE!86~`iIT!p53YKXFp<$VBgi&Q$WcwS_F0cHIowj4vXSxnrkJ``zw4TkK8HI2y zn>*8bviooczc4QP<%i7u_@&ytsnnoLU$OoKzfHY{5A*+61EIbLFrma2l9on3AL%zfJ zSwY}C&|A~?+bXL0^+iUs^(Z?tFsL51B|1&>+RYy?y-v1jG{(5A@l@lk##4>E8c#Lu zYCP4rYq@?KSr^S{Ha9Gf*S<_Wtn#om^Olw+Ony%Q| z7;X*^hhLa|hxG{_jIaTLN7L6CAA=IE9IhMhV7yh;CtU%B)-)ea61JPY(Xo|+#M`JD~=wQ)r2pbobC2n`7~R{4H}Y^JK>=s3%ubSa$?PZT<;<>q1~|9DX1p2Czd>kYC=0>;p0>j+MhYIS527RF=w_j;qkzRWsvz~qqi$m6Z#j+ zq8h3R{f@;^P1S=D(N=f0R1aio^ZnLdSJa8RnwPi^y3f4Fb<~yllLIpDR%Q*JS*D%& zgg%9liv|QUe=9xYhjLQ1UJc10;$gZr<{cq?mFwOS!b^Dhl*R;AT(_hB>Gma0P z%yco7%1n06*qvmu%$k~$FF9{PnnT7yu44{>jAa&NXpT&~No_JOkt?Gs$^QAr%U_ix zuWYVWE=MnG?poOjZpC^8=sDEYXuZurj0e~p#CU_vL5ydZ?VIrun}ZmSfx07IfhSOX zq%Kl$&x40x zBl0{J!{8?JJS#>>VrDChr7*KGFs7wi1l%d_UpPM!r0q$ldS4N3xpI`4nHrRWdN6*` zH<*rr8bH^5>=hr8Knbe9yFhj0yHG z^2fH~VtOOyxs~@pncm1&T=;8j3GH9)zp3%+{xRBDx0e1p(;cmicDA;)@nK^;(`Ye6 z$TVHd5Hc(QJ2K4}GX%I5dIhk_>;ciEfrXi#!L)3QfYRz9y<1wf;`>llC;)3$P}S^Y zRc!K1k72S6Exqz~fuX)^^>gWI&#W39kf6RUu z^B50RGu;I($84WXBpi47afprigu{1K_^3*9? zRfXpxrBHuH=6~{kXg#Pme@iPO2O=MuJpwIlauaeOdC-jpV~LK3u7CE4YM9GR_}Td7cqOnbl=(Mhf>t)NC3#h{MR4X}e+oArj-Z6J?A zLrm8IuR%tJJHY3xRnSSmTWA$9m0qJwkdAGQh5oaDMd!ian{^Ab1Zq|Jj8gESbW$n2 z%OniG%_>f|I|aIhYzW^on;O#?v)&68V@?CEBg-(Ssp?($CU1col(MXM4UaOOXtVZm zf753B!_1x;KIJUS-?Uj1VMAK(k7-%9oY6uUGg8@>6Wdywnd7gM z8GGi11Z!M0FDv#>XTB^luhS*}bfyE!yiTv!pN09d$h_iK_IHM@vRSTiE_LP)ciH}? zv4u8GN_+KtiT{~(5)_D@Vr;`L=`TjONu_A(89DGDTX!<46zx7EnK8}!7Pj<^YLm6? zj3}EYnbh}V=mzsP=8sSh=5x#+kyn}LF@Ho}W&X$f5qXt)A@fJ52U-XC6V$_2+`wrh zHl)90*FCE>QW`urt9w>!){v0Uv${iXOfI(_1(_`y7`h_dRdC+gHQ79IJ`!w_&|5+lRwCUba7n^}W)*9h05y>>gIXpj@^>Sla)??pjtk>nUcH zuGAVv-_{&uWAs3YXbI$^YI;)nY>EGVUT?Y((}I{}m|>sU1A;Fr#=&yD&h#rQQ>N)x zGVF$8l^HEV00SxLg~P=k`#h`h-_eXFRQCt zFZS(@!K6vk0o%7AR{In{U{vsL3U!hesNtg)+?vEmW>AEN_z) z^&_Jqn?aa{jNV+DK35(a&{cHh&Q*7yX@3M=K9c7 z=rc4G?EpFgbOXqG=-i;G=p^ZDGz;h?S@|~Gb+isfP0fnkG!$mVp4Y4-r`5$CT4U^~ zRmV=6Rdm!?C+P9e6S64l?hoYlW`>Q^YAT+VR@^%))8&7|Qyk-^b zs2EUubD;9~(|n@0o()p&f*?IONcXWI`!EICUQel|(C3e(1ql**}4E zdSiNSBfYg@Ze!iACy4%hV}&MyGjzAHQfK5gQI46pO_g(_+-7>#R1hutW_oL5!I_FT z(^Zq)=E||5;D&l<3+3N5x22vm6P&4dOIDfkt8!7kJ%DIIgYq#6z>6U_9 zD(5zOwuvB``E3+h=C;*aTM2HVcspHfF1Wd#ZKu#u5ZjyW6k6xDS9x0qZlT=UtK_W( znWyidx3&|+8fOQEwu0L#Z3m^c&dt*G4uab&o+a$+A;|u#Sqkk1yX(m;rFIwGK~KET^%kj@J68tk<1PiANAEuY# zqTydTMuLTgk%omCMuKe_MuLACUK&P%onU0uxM)~t7zxfT8zaFa@N!i!a{D4a8U8Ja zm)i-?mW7LksXdAqS&fTpjxSc@qH)A(T&&C^t8wu^FQcvwF0vndjQAq*?ee(ee@;e) zkD8>qs(i7sj9QM7CY_deWMvuE_@eQ`a_)$vTFw_WBBw<=1TCa;!Ds#_Q3$xKo; zskJ1jX0j{%5_xrbe6f2`IyFfZskK}pt;`WAr7}k}E?6z2uKoGq>fqvvvGD(XzPPqz z)J=+W!EDyJd`Wd9$+eYn5t*|p8FhIW3C@+~jwM_y;os`a7nv7k7+KB{m&V0%EHu2V zo-eK)-OcLY;!m9~&JgcfPcyfY2B)f7W5yRvYqR#}i^d(x`C`TqOZb=RbinD#xM*4% z)8LfrZc4ncvhJoF7nv7U%^lI;RO@d3Q+m|Z!NniL7x9lYK^n}J)26Ph9@S)2aBI~h z)eXeu*3^7)_4KI55z+6IV__zpn!cu7gR>-Fnl^RYqQ2DhtIN~ipiM0Yfz)r!QLSkw41xX4Py^5%<6OR6ikrZKI!Ua_7qYvr}6tZb|) zJ!-}gS>LeL4Av-?txZKcYO5KQ*E($OST3pB%0{-Pfd-XziDj>BtOyIi9OH$yva#}O z8paoSe`!gz@_eycM*S)9#cEu%`C>ILR zRpXB3tN$fQHIq&=J?irHI7`Z?w!Xi#?xuW>ST3EG>uyYrWyQaGt^faCMqPWjxGK_V z$@*qZ$*84ujGxY0zpe7yivQA*>hd)><+!+QaZO`cxM&(w!@}zM;+n95!bOjoH1GTf&vwz^(rJVpY1ECFhG9Yd*Mv=8MakHI}b0 zX4W?wYaUlVQ#6Ykn<6OK7?a(Z4mRwn^Yy(%d^_$toE!zgpIHJuLZSGjY z$m;oG$sQH^(v`DH9j1KcHaM9*D!8?5t5mZ`HQQ9PN*$%#t7eG`E-rt*h$U*dZ7No& zCEZQAC92t`mh4e8-OchP)v2;XHQQ9PL|wK9)vVvl5^hO*)T(gN_@ZHCW{JAGYZ{f; z7fV=ZR;iiprfO|!wx+QpE*hq0YZ@z~yD3?snr&*PM=i(5AA^gLEW>TD3zqG+hY6oL z>=b0T0(Q+<=i45p(yk+R8?axN{YKci;57iNc07obm&qPtcGXahdA2E)yeef@{+u6*wvR$EkEAyJc zx9przZ1nNf&$*-J<*#ntvzE;M8Gj<|W63DdAs|$Z>GTyK7g~d+)3tNE=Em)@IO zPJgIZReQgdq(AJZEqTFV#}cEj+|M7pf!)H4Cw!d1S)nED|Am4w3M-$vu)4GnK392v z;o7AYYnv9WXxtjdS(*+nZ-3$HmbrY|Zn%Jl6eJn`i@&0u;gaT0!Z3?+GG1&x6_%#S z(ACn;Y$T<%+m9>S2MJGInLV;qwe8B#uJZm`T25Hobzj?b%s9S%g}P)TBpVwg`MI3- z+IU-&+ zEI%Ur)ynu#S#$Kzyb-QyyP0g0wO*;+Ot#597$Max?Yn5{c3YZOENdjJ46Rtwf5V!f z6^xvcmk1;`ddmDmtf{_OHs54_aEW6=cc7R5t$cH3`e;ddp2;@l{GxmeFg{D3Jj{Cs z@)y{h`5iGIJoHqFQ)GR_eA`aXWd?3%$g%g@JnX=iC>{C3ya7T**eTAuf*Cnynllfm zp*~NGcR`SIG>~mLRl)0?e_@m$ab%wPm{;NN3$I_$9(>WU=N-RbrL%GIEXB7t|AX^D z@JIij{TBPh`64Yqji|Btr!@JE+L@;T+Pma)o!U_&>PYR7<;?4-aVccEdMee*r{o$6 ze1*2+TYQC*=}*2wTk$QvLdkrKuTV1I;w!Wj-?DRH%-fWC`lP3s=~EuQe9=XKEqKXe zrcXcP%a@rx(ujE~;4f{S%)f%yc&^IMCc{@SS_LRG^ch)%ex-ag4E!(UXBq~|&-6lZ z@n6j+Ghemxvy$<}z?YURnX%0GR;GNsL*Va*QEc;$%nOc5Tt?e7Z(hhPhN0k2rm-pa z<5lj<3Oc_mUqNU}=t-!&oil=_hn~&o6+KIDntaEMnVv)kQ|>#EUgktO^fy1QOh!nl zG-NOQ6J}mO@WYjP2f;sA<~4*KC}Ar-K@Zb5cnsyAOSNDYgI1~J1(2Rbwl!aXYl_aS zZaEpHf+s<_R<7<~VyV`Q?4?g-p&g*X)SY%N)tWKKh^tE0U6wupJOo3*OGYC&Yg&cM zI*MigKmT002a)FJwblRs<`Wf0_yEwTZfl1@YR*StOAl9>6CnjgQ?UTI*a6kA7k2<6-&Gpo3}}N1l<$=P21Xxu&V!G zvhVD4OuVkr0_EOYc{}rqOxgH|kA>Cj$XW8VqLn>&-p(mv=boKGKTdstXRW2royYcN zj6w_1tY*3ztv+uide&4|qcjSdimo-$)w0i>$JVv{v?9D2vj?WrzV=;SWZyHt1Q$V8P7b%;!oD-I`kg?0Y%4eEM8RGP7KCmB=a?)+2w@7q;p{edr(X9SsJji{U9AY2VHv!xxU7Ze)GVh@dWT zNjnXRx%rakVZsyb3Zl?}&#tJisOoK#EW**;J=gf2+ zP`$L+KFF+fRbN_)b+|fe6EFtMqGxRl1U#&#d$g(aczp%dEYNs2P~ePNXktSJPQx&I zRYUi7P6@LS@Cs@M-Zv_?BK~{v`h0`!NNx5`JG56)Pj&rYRJ?MeyRge#ia?ozJ8i5WPdpal$J&sO0TSJ87 zmQHem_R~+3{13NrTTMVmcUrm?)kX~Ogvf5&OUj1{;)rwN<4_<~x37Jy17|85^n zQieWywE=vJ(}eLEZzl|MhH^^<&K9Qq;rg5~OuxYOYp8wbFSvfq99+MaI6b`yzb~CF z45nu%47byDdj-x*ZZFtTF_014P;qv)Fk?77S&4C;&0<*#g439UQ<}x%?|FIBj!8JB zSuCSuNomI1y||om7C$(+}0!$$~8S~rU_?;3*Uuf z(%0t8d__LO`Es_#!Q6UPrIGS)Ej^xTy{g;IT8!3%nuB#!w_ACcRgI-=6mhDTNzO>p z8TCVk<^*$aucQ&dcR1KtK9+10Aw_5Y!oerx5ZcqmQZ|Y>t;{56v?g|n*|NqGxNIkf zgVFRj|4}+KJi}{F4mXUZ9r%wme`Yusot+$xJl{@%GsBm}>kj|M>$=Ot>&pFNG9&m> zF8`yuS#thmGcRgwbT(TVr~g-O{skr?r7><9T}U5{TO@jC+zeNBn7K{c933|C>q0 z;H&BIN;beq#r8-1X=UqQde%(}&ul)BRQv2wziN*!HSy@tZ-Nw$*0>Iv&9wvvMUjLtDzLt#y&@)`=OC)r90 zt0%0d*h&iXj`8YU)=IrKo`P|<6_u9Er6>16Y zt@t#>wQ}=|csgHC_s*TJ`7FXO4=8A?sHmkZ2TUr$nb zn_FMkGnGC=@D#-x3C@%!o#{&7Sl1hA_t$#5URQC@KFL#*I#pL*a9zclDrFOCn5Qab zGhJ_*TTtYT3-tXxv`_LBrS7ihUfy#~(fw|^^YY_(itcySozLy3{0rn)=M<&xtLy!W z^k`r8!!Ehmg0pjT1m`HXQ}DUPdcJRNAHl_Z_ggMxx+y$K`g?-Ej(u z;MVe3ew@O#g6u~=PGNh&?d4DBIE7h)vvNBM?x^>mdW!@X36#;j`ajN`$WYj3C7a$c2jyU1y1c~thjgazKfnLlm@tqAghs$1sm&G zUtRYRhIdvvtCD@S4#_Gdbhf`>e`!RUDhw1HDE)R*g~1w!C+S;J?qtPL?q`adDRqe8 z5MfX=g<*ojwBCqpF<5Z8uqLmZQEq=xl#YU9gbVvCj1wHEF~7gU1i=X!?fWZC5}c$} z!u=IGpuel{+|hkl-PTk)aRKOyO`nX{*q# zC`lhAcwp`T!GjbdbsQjgfO54_XsdSJU-ez6&`EuHibmUU3R|nC!O*^H>)L8%aJIif zKlKK9*Qbb~ee}GRS|1L}$^z%AfN{O`yoUM%xtMha&Q%KuDB@rbJxSGDoa4v|jtw-Pz^v|i9@KyEWmZ6jXgtA%7;j!ZicH5^$xw|as1@VQ zw6w!Cp6GE_8@dXz3c;Go@ZzXrHrH79vF-}R@fK@j(3_035gHer^o%x&)T8t-BWI*~ zwWCr>eLYHj$oR=ATpVGYReC4YkTuUP3Y}F?FrlkL7qtc0*iE6U+6xNa zU7?%WG%2<$E!I=*MeEb5y#(nYTE2I&U+6_n^9)MuqiZmf9`CErN27zW(N6(9g@!X` zY6;d<>VV=H8dw}l19d$>z0JsBRIoP1$`l-Lkb0F70-qbKo@8_kRT!fFV;UVYF?R}+iX$0(+2|*TYTfit8Z#PFGk@B{92)v(yupVurcC!gPHH z{ncbWsjq)Qi^U%`DDtxk!3yP@sMK|ef89`g52+h2xPiDF()bL84OKt%W7KjTaXd7C zGZkj2_UOhJa!O^4Hdecg6U-}RBk{nzAat{(xL;oPHr5&CEsNuF6LG>w&y4o% zQsh3n6uHkXMeehUxX(!Or)|Wqb{1dULU0Rlz?~Jg5`;SKT;yD{RYnVOL3(p`u{UQI zdvLbi9H|uWbhg51@h-4nr{ehEsW|d?Qpr0jCDPyQq_CObW=h+!NH=y=o}F|(LU(gi zdK1AW>iIb;uc>(L99_@S(;e0GyXqSLF-tsqSKaTRyIC3qyXhK=vxE5hZn{5Gclh(z zUDt4+BP9jwuKOc&ccezi9=e7<9U(bo58WTGyCXDG_S7|0@Nh{qd+Po$-5stmG*{P9 z&BG-7%+>v&x;spxYo4y5vWH4any33iba$wz!d|+DQywCDYA@X%th+-*A?EA4v!t&1 z!c({jJoR8viv>#SqR?5m3-9QsCkKggEYy>(3SETda29yPfubTv1#tJSq67zstH2!& z5M4nI>8{XC)M9_hFmQ+cMPnB0Ne_kYq9yxDZh=SaCwjB5p7d0J3iZ-mn>Jts+DtHp z(T)}qjA>ZJ18k2N>&yfjD%GqGn6EL?nZ=u>2Uz4TviwA zK#iz{)yp(Rm1~5amzq|t5i>aS&D5(&u|`dbb+H*)vtr$-Q4?Vwe?`5}oS^G%u7JLl zTA+JuuD?egMjdj3=ty77myS<%^In|G`r=JLZVhgMrcyRaHIn)7O+=XQaZqTp|hSXDIIiDYa%sZ{ee{2 zOjntVfaF-Uq)?I(OgezeEGZ+5Ri8j-Gf9DSq|u#@SMMM#luHN53lmjOd7?yM{8YmP#Qe1m97~>SkbiO2YqSsq+pxE5CWvj!^`&eOYk#_*cijyHb0kP*nYNAh>ZSSXeq-fTDf{PW86n$GPh%_}?5c$yS z3VWY@l)gxinFqE|!*w@8^mCD}hAAE{8oN+eLq&rZ2rkg|d|eL}^`0*{Pcasj^912A z^91MVeh-DgMcy(*`~rJS_z9;9&Ji9lXB;5@I9rfe;Q;ZuodxIW*&IPEI^i>%cDR$$ znfLV6Yz6*kc|GDNQ;f9F&#ylwSV8kVdx6*C*}DS2RPl?Wb!xybq8 zUO^D~9(-m_07ip*u^_nHU8&3=zvgjf~eu#SsiX z+6)V>i-m9BVhyZ*)U%E104<@8ZPX&Ils2H)as!HONFCd%?WkXGg+9evwO3oWEVejQ zWKgjes2gX3LQ#4u^ipl;U+R`q|1~f6B6Z^bd#FD2J9W;hzndzBx^&mSGg_!~q*2mD zDZ`56idr#iYEm3k)GW~xMjyCJ{kjTbuiaU37mcss#W6^&X_d}uIb=z%7(Fvo6X~S0 zMp;8$hhp0XJvDoVjv8lB3G{P#R~n@p^_91SU<1YI@Yt!uD1X0cD(696OUV;>If#nmE2V${2?eisKM!S#2W;j{S6O?yCE%y1%Mz zkm1%nMY)aFd(rkx9&k!U_g8I${Qry1IQrHp3i#hdDnn*lH5-3qF6LP9PvnrQ@C&H} zT|c}U83XAF?v1R0bw5%P($ffCBL^Tq3@=Iz!;6wp)zetCJ7?}_b6f((z0RMlK6!jUKz`foX}4*Lq@(rRyRw3GG_g2?Hr)a`12lc;|Hl7Ie^AZ8s`*#7yiqN0RLh5^Ppzhh z)%38M9#+%C{{?!;N-tEc?Z2cxtdp=jLK>VPeFdw*Sm?Bt)&dJATP0zPrD;~2vt#9!R~l<)d1*D!d5lzOs?`iu z)X;R;8hMlAeBb8&or?MnTTO2)9RT)dtf*tB#>yQlN37;zH^UmMt<85W>OpMfewefm ztlp#F>!!66vkzpYpS3FXfU?HTdTaNhzJwhG=m1&yLSur(40;px?wXY$Rwmf}_9$vl z@a>0|1Dy(XX;{OUr2@7IX5ZMWs8hkl0h^ebN@X<?tXU0Iz($XCszC}^=V50v zSix-cGP?_W`;=_-z^q{k*yy2~8m@qi9{Q*eMSau=rDLgwCJO6xEcLKc$E#0G!J4{f z9gEd0y#I_c#4ODwyhiyn2?kde-PC6xZ7(6m?S*lnyRntv*qsDA9^nL06MC z(h7putmE4UFCek*u}hBx@%vNKM@>~3hF@4%nngv1U(B+Wk6-8;E8|o-#%1_bj#=1- zn9VT%up;~#p&n#?6)Z!awzlwVS(s(^x?mrpU}-F?8o$iqhjr)-%UGqx)(49p#x9!5 z471Q&4$x>Y{9=`TNzB3y+3b%P-_`i_)50$_6<9Qw)e_o^49g6^;92mmR>CCs+9ZXE zMZVQS5Pf{rScc713A4bp=9RdW;g{i>*<=~dGX7<}tQ@Bd%M9b-SXhB!Yl2-E)?w)N z;aKb&go~Lq8CLm`sSh6EaPSi)C1bG>EL&K%5Ebs)SiRif)E}qyozfzr5xoSV~srT-hwl_G%dy ztIWR)vzDBTRgGm!@-OhKD$ZpRqv2OI|EivURqHp_jD91N4{hcJW-e;;%k;n%YC^Ciu^;o7R>S4nfo zysS^PenT^H><@ox`uVkoU(4cOE7s5dFRp);Yw4@`7xvh!e&D0xe|!DwKaXEa%ZKJ~ zg;nPN-Sy>a{QCcEeL2$~malx7{YLrvS7}DZ{$lj;=r@>ml~%#p7q#?bm9lL8e2JHp zwDg8eCH;KKilegru(Z}(ZnIIo{#AM9t7OGddF9JIG_fXDS$|ksWzJTunOQlNdoMFDCF~bt$2mR?SpDj%wPmcOY%SXM z*|Rd8c`~!rHS?F8HD zeuUm@E7(@|BUN4-!8W=drEBVkebi_{G)>q?v36wdEOtC3(M-A_@^ts}UO?x#u`Y$(`J_np-H z4FntLzOzP7eZl&=@1jvvPq3cuyK3y!6|AfKZW@ub1(|5^;Sbx>jRZp!q z))cI%d)6een5m)r(yl$cvSA<9M*-h#*hlqMz&9Ivi25mbL9f*QO2I1|_E7^Au=~P3 zYM=skU)V$qQiug(rQ$1LkVZ_lUvIG5W=+~}&@&~=jl90ItAMnm|1b4 zGt5?&OFF~ltt@9&h~+xN<#Ddk%JP!dhD-A=v*IXmu}p7Y&A)zH{HvNCR;GtW388_| z!&-vSN2ucJ(8J1<(24#*A1l*Cs9$BO7!@g@`Idn~;%(NbB6@)TCH@7^T9S*cE&c`1 zT9S*wzv!c?xmbyR!MUv01{S$hRsB`Dr_AruU~%amzuz1g0}DlDnq{2*ow(l|u z@m}xsWzLDID3-(N7g(S(7CB9ZSsS#TQwccdp0`OUm4jT4$9+y+<)jhLuHnR*>?Aa1 zMPLzU+u%Wzv#L0^gfnkA{m)K)_`RXZb@lR$%VN=$fLy+>Nn^$7P$l)ho{3;DC5w?p$pD z&gug=ApYC1gKH?re7&o#n8DGr-4vL+(ZAgln7h&Yc$h<0!Pgw;a5oifTAaI~mt*G+ z`*oTrwU4gheT*?Y=Cu@LKTkhh!}VI}s=xS6D^c>+Mc&6OY@p_1XeZh#9wdkkj9EAS z@$esvuVDO74;ExzRh7SRdaC3#oEp(zcu&Ghc;+>n8m-u0xb3Ner<JejRq_;$UwL{8n^|V2%yKe+;hCrKx~dJH!>jTa4!)GUhOZfa;hCrKW*Uch z4qsJ&;rME3t#OBchH`)5Q`Ap*?WVtwN!n?|;iqV7v8U*-sj5r98oz!*_{D4hPff^b zgB0-8gs;ef3ixQkGvojTBr$wK^;f{tAU-zxDd4GTl&<=U_KgyjjMh~jjk(dH4P$iG zTVrsHaBHltdTAt%6)hR3tDd5L!gu~-+Im#$krF2@a848y{JY9jajHiyCTJCrz3mD2v=XI*&bLs&<2F1R&(-+l#$z?-q2t37 z>cQEgc)PY!m!KYvMJu4YQ2WM3>d{EBu_$z%BAtfXuT!M+4F%UJa#qertS9>2{$F&F zdg8TzsvuZsmBu8?yApxJoI=llSuINDCm6@bQ@&Ji6X z6lAPwVW$zGuY|sgQ4P@2a&7^2Veb(q7mQL3(DHK50X&EOMx1vrLjTVEfO8Ry<_(iv zV5cUaonjrt&Jp4~1t=vH6QAR73n(ckFF;w*7jZ@dbQhY-Ih=4Bs4^!Au@1uN4xA%| z4hmY%xerirW^bJRil#g$a4I8qJ6?ekgjmgS3P@t;#}Wm6nA<57=+@vc-HSX1o`ZfH zUc{I}!_7$+j5v0TFbWxa|C{GNVFO2hSx-SjN+&)IRnI^}>Zo7s^e1`>N|K%U1SP4d zKz~6=*geZRPwchj^d~#<36HX4HPY}gORphYan{pVL8yn<6}<-aa0>JqJ8Kh-Z%%w- zXKgG)D>!D+FRi#-J;$q8%nMcP4ZGAgp`iq6?)d~zdJx7o>ooVUpd+pPuLD&{OoJ8ip8 z?#__r?h1E@yA%iA-4U3-+!^jsTAI6EcXx!_1aA-bDlN_3s_WareY&d1-KVrPcfal` za<41>)_~0adUzn*uawtx_j-6$@U_s{SLC|*mV!DR)OS(b$v>bxopjaNzoI;^hK~M0 zz1dOeoqQ|ht&!`Xl#afGe<(Z{+6#8@t@T8wi7M30wet^$heA80xA$#z-A?e4@Nj6T zTsmb`*KPfy;gQhBuj3mkWdrYXuY?W#2KwHH3NMHCm9l}K;a?6fg&BTB#nU~rs_9B! z-_O*OmqH`GSu58_W$1(wJ)Q2ms?;|AvG8c<>Nir37sE!%`%-A^8~Iwfjs1(^g|M-n zycoLq$HQZSk11yp-&jwl`4__TVVd7qaZ{z$%01~GSB`c4^WnL$uAioOGtb;^Gkt44 z|2y|Ycs%@0d7gAr{d3{jFjaY<3s1P;g(n1`(6jM=s(&_2@Z*c{+3-wwoTu(__hk58 zsFT-xE?-x$j$l)Lu@)(UwG~hF6Z|t_qQcXmW?pHzddgEbUoYRxH}&=N&3!Y$X1-p& zM!u$=KBh7sca!`?|8$t7@KmVKliIlk%2_|Zss4O3pXMu+(lFn`H}?&d-XQ;|dn!B` z9@V>#xygQ#e=4k#Z{S<_b(E)JKIBv7pW-JgeTu@P?h!Y|Kk6DO&pP==`TD+r_sUf} z*I3t$@-FXnJp`;eMFn*hfCe#|lo+>Cb;~dFA`Tb;#%QHGECq zQm|#dRleY3Upx1`(tmK@yY~4G`4Rpl_o5r&hbvBeK~F1u4c{tXq0l<-eEa*d)D;`&%5UYUvSS0j`T0Mp5YnywBWPu8NnWkyDPm%=pIJ-k-mEv?MDfY z@uPjO@U(l`^$I-|f2^{1^dBqivg-7Btl=%u(@80*LQZege&D>z1PqIvjU@VoG> z;P>IXu(RIV$$t_)*400i_HF1BUU9FwKB2ebu6nmy=o*Ijq5c~^{b$(4|1o?b_=)oO z4X?V_TwlHMs_PO4`ysxIa&`@~m1h?}+kYDV80HAh_H+Da;nUDByyjka{X$>G)0DqU zm=*^4!G540#o1T8*be& zP;c$4^!@w*m9cI>m-3C^SK&*+zlW~`zYc#F{73j&@SE_Du-N}4d@lI8-rPsmiv|B0 z{t^bL>^I!hFhJ$J=?3U}k<$0^-BtF~@K^VptDXD8{Z(+F^1kV&gzie85_%{{Pv65& z32(W9N>9?ig)c%uFi8vPm*H>0rC)@<3jQ@L@-9tu=h8)fp^x>nkj7~~_htA{@4n@H z>e7YYD=hGl(&IFwK3(90!roqlBp0QF!a(I7r0{{89D3>7lS6OcOR$gcE!b0k@_Rl1 zz@>V7Z=Wj6_h^^$I)+&xtw_^!zOP94^791e`@MX74roqm=*c`^Lt(COrFyD~yY3!Wj>+M1J@2FI$zf7>Lh+>Vw4OfVpZ0qweoOFa!95lK&Of22tyO-T^i8F_ z<=^zR^u;IjWKwuiVPbegDR25Wd~N;BQ+hHnv{L@o=}qok_l~>C-Kh8m)dcvi?ruru?t_x@n#C zHGi#Au5;H2UMn~>3<2mGri|S}E7KSCsOqf5q2J>!uI+hy8@`kiz)zvQl30 zFZ=pwz4RsDAgwQ0KYiKXthcUqH@jhBXn4>+M0K_YWw~{R(5l zy-K;&{YE+dDEMo|_bBCF!I5D^_^tcIee8a#XP*fEM)7_Aem^$cr!XdTO`r46`mX8o z{yEH|J8Q(c=m^Mf|E4--d7yS!@FDUnIeoPo0Zu9pk z?w)o_pYh!l-u9i+b@WCjh0f`f`trx_c7K~69qv-ece^`uH7eZUZ&%zS?Vi5vdnml) zJL;`YX~(pY;ye8vepI;JU8#33SNMawQ}5m-I4X<`J<}fPJHDsFyS_u(SZ{Pt=$PK+ z@6=m&`#aqo?rvS(DR`ISUTM$tUEfRLJwG{ZqBkZhbV%>UTlhb?k>~?przen+Hif?zn(0}|{@XzjZ!OL}btH0OZ=K7?))A#+vw3*(Xs4yx0 zz3-!xzG)v_O-P&T$pnRo=?6;ty?;CTyZg$$oqX;7?%qk>PQDWS%6;kHQp(%OyU9Dr zm+nnnzm>e1{KI|i-qZcx1m9KsM)HmOhu}ZmH-i6AzJ6(6l{;QvnUKDpyqEmVy|3_v z;1{BJuP5KSf4bL||Bd8B-%mMTN#0Lt=Uz+x;=XmS>FMi9|FmEFp?_5=uO+W0pS!=f zk9>cnT(7#_=dSm+DjtybPe1a1@B;*I@b|fg-3@wvpBtDCNdMqJ_5%e6r32HC{U?e) z_J8z)(?RJUb^VDyC*0s4cISkL+=GG-yNBGl;hgZG;Dhb~cXqf@C7vB_@;3_Jpxoz$ z2i*Pcyl}4K50hW0wLeTQb(aZV=6){tbG815`qSShA1Ztx__=#EIX~R*rn&R=_Wgp> z+EQHJ{na1+#qJV!sr$?iO^2kPDg9G_K{!9G=Ppo~?#@*H zv%;C-7Jsw=m{^ZYb7wcQ+D14ZFt^EJ+U;EMNsPw{cL748&&{xh3XM}70b^eTSoxjDe?=DpO zxyt=na<1O{F!{S5la5aRuD8DS=ef_4Pm}ZX{IldMrT^W3<;SLD(u=}{VSRUt$~hxk zPa2M(6mwsG2HvLlhzw#Hj^W7hl3lu&{E)Exk4cyIo@0M`2 zzsBDj{-)71F8!PGf9W@L7whST?gIBoa-qV<$tB_9u%Ww2d2bG1_!b&>U-;(fc){^{ z=OX3(IJrpS56M;jYJXFh;Vx1BzxtMGi}bI`|AoIaT%yz)!&Q2Ew!6svAvs&&qvT3| zmA^6k#kWdZrhifXzxtW(QsulXTpDJ&8^V=(`dfdczaea-w3+Vb;WAxaue2M&Z~Sll z_2D|j*N2VuWFxn+`$hP9__hCyzb;&>_`0x(QZ{y*xXZ&Y!e##2aE;)v6>qJSP2AS* zm*Mj8bAOq?CTykat=(4citx+u3*BEW_;bZuDrGBoxxYGG6)yL`Q2a}OxxXqb48IM( z35yg1e-nNk7AR$*;FXH^QQEHse;s}m_EyRQ!K)N6R(V^v#o-FYi}n0hO8J%U=7%f% zFa3O#eU+}SQto}j7H)I5ubyw=_6oo9SNOe@XMWf(Z00s~`-RQjW`g@F-d|~(y3@m@ z{#X8V<=iW5qqI%k0bze#ou>5D!)f6Xf2rSAY1_C1!vSGicdAlO3#W#Q{Uv@orETjD z3I~Sm+$l;qHC*H`_NRpHmA0KbI2@#_la+Q#xX@qZPYydMZF_e}I9OK~_zRVCfx<~) zmeO``v)rNKkZ``gz@H>|QaCZ}sFYc5M|W5_G@R$p_a_RT7)}T~xx>R@f`=)`x&DN3 zd^p#ir+8;~L^xdVa6LQSA0Lhjr~7jipW%-SKNCD%@hR@3zmku#4W> z+1;wN+mb!pQQ^q2hthX(XZkbz&%&7s$A(kgDax_Cp6=n!@@M*E!)dy|B{|KVs(3f0 z@9uVUM~9=r+5Rj&JzL?Ju&YvbbGy1@!qMS$cbdB;IbGrAgKp}^wt^fbazv-L0Ti!3>&2DD_%GK z-hb!UO@Hv;3x4OPNxAV{@@$f?$W;KJO`b_+yVLwRezr=O<2FodhFW36bOXgxr8fD& zPu076KYcFARs4`XpFEfRkiL*SpF|b;if59zA}YdXl2?-N(-)H$1Yb~&8ELIhJIqKo zR6IrHOiibx`H&0WDbM%mcj-&Xi%Fs474eZmMXY$H-l!dBD%1(PE9aDS_cRLmkW>^Z zYUjRH{_oOn)0dN%l8w@tX`QfN^6Z}Omc}8{bs@x|b;Zlcw`uE&r;?|W))h}D zFDDzP8>Mx_#tQYqu4xhqf(7MnRq<%@NYbj}k>p9iCzGcHpVB+`Mb{^{C-+6SC-+AW zME5JcS1I>J_Xyq_J*c$Xle?oElIsPpPwt5x()}IDLwa(1a-2U+?f9_L?nv%Zp1Y%W z1n&~OF}WdmBzjosd%EM4=h5g9UB9jLccRClM|J&}!ktOWipP>i1s~PlY?5xA)(dk| z7ZSll|NXe~-kH=7n<#yeJKi7X7pb&8T?@U{vZ6)BQQB+K`MSP9@J9XX z`O(|DTi{MqIUhv7i=K!+RCrwQasAbY(FeM_RPVehc!}ck^w#-;XJ|~G7u}THD0rqj z!+oST?o56kJ*hH&ukb3>kTD`{TwMDn=c<4KE(%c57Jm!r#6?kj?q zDn3``oF{meJJW5JZkjd-AM5SAlJ}ygRMLA2??*pZ-j}00mFL{(ljvhTeOFK4i{6c% zR{U=CjN)HJFGVj3zO48cdgJBj4&}cyD#Xty#~=0HT}i{RnaclES9d3$D($W$j-S=r zar|8Ltl%@seYxI#G5Rd}G`c&9;^(91qDW8U_?Jq3A^K%>x#GOiqxetCb$4<_^t|q` z(6i^GEA;$@X!CTlw4n|!yh7=JR*r{~KSzI3{3|`r#h*uijvh*Wh<>H(Ukm;a{U!Qb zDSuITF!?_EP4w&NdxamOb;9N<=R2i*AAJ}7R`C|;=IJ_Nzv#B;)@c7|KfwbO18<3L z7Q9vQzIwW!;O&YJRNBqaVqNbmc(OaoEmoV{q3b)8c95RkBzU0Wee`s3)F^DB@()(p zP0_&$H%5z;zK`HZ?qqj}(r%0nQMe&GM=6U0Pjn}_LzQ+zbZB&abe-T0iqBU1Inkqq z-zAR~9xXha{4ROC(7d8q#p8v?l=irSMnvHWjfunb#&yx*(P2e+U36{qM4?$l(~2hw zk1IYxPp*xQP`D;)tbc118iy^@Ez%=(e|2=Eo?H|CuJA;mX+;`;9sND3h|?JO_vovr zM*LOurC^2P5dS0kTJY;Ajcdj=;xD6`3V(}y{7v)^!GGvkEj{^LR7>HD$i@GRz7hOJ z&uYhCM1PHH>-iT^qI4H0@wd@GqbCc$(|4a#Xi`x}x&9i}iT@HknAFkLU!pF`lf+%( z@1k#Y{af{4ldx5~W!gml-#E+&C;1co4B_ztHzVxr<_j)xd%F$8$^In2VK~K~EO@Fv zMero$s~gveA51!{oGx+a_)3k1dU0K))KhpM>7QD|IIKdu))kZcf+ z^*{3)grE6S1y5C3Gxg>9Zf4la%@dsO_Hs?b*6CJhQ~g_$ut{`gbVjskw29zmih-v` zrwN{+c;o0SJ>OVilc+&lU*&J4UOqe8NWFcQ;8}XMx$>SC&5TZPC%Tz>x>2-+(oPdR zEjl%t5gqSNa5MCDX0)Z!P8B>gIwk5Hwn?{6JL^xHhKCD{D;iZiTzEwBR(gI)v{iI+ zbdumHiWjPc8G^^TxI#fq*g`EiuJ=W{#d`hYP~_&D9m$n-9}-q+edJw z?uI5qlA0Am6>3xrR{kN$;G}j%t%_|_%8Ai7(bkHGB{eE4DuyLP6?f8Kbq<}vw&^zM zw#sorw5@WT7!6A5RMf5*q<04=4;3CRG^!Y$3`;61o+{jvJe)kG(f(**pz;h#X2d^> zj*VuyB}UcoV&GRJ4i0kX-Gy#$g|~*lnzy*~fKL$=%~_@urIVs-(7pZR0laUh#Hn<-Jte^mss0x1vtP0JY@6 zq^ojvi@U~~Dek9ytp)okzPE5sVV#P56&hCbNxBk@~kJgh2jos;f|q0 z*goAZ-7}sQ?GWv$oO9!W@c`u5 zDekW__KJE71NIg?&Mgq!Tlog)$=v9Y5>!qB%qk+n? zr{Dm^yT?04I|}Zo|CkbQtuIeem>Lh(zqAl+9yb$gp}40?=oJmpn|lZjRJ>cfbF`D- zPI`Zcay5%5$J?lk$qG~A!OFLLG+24}h&I%_Jq3?+N4WNC!wz9ry}MhyYrIReb2Ls?4+p3I73X|je3-=WoR18rmyG27(((cg)Dq+K@UsAuKUPV8(ZU1DwaFjpV zucwhVJ!}#dyM5gz8f%N)M3plso)~YZc&OgrH5#fic8i`>n><%|wy;jzFn+esC|)NX zre|}aVS2u6G+bA+1&1kqpm4vw{(wULiV;fPB^se8v!lNHdcUM^@<5?}#WO15*}^l0 z#&M(gnL?AealBW$V>&CHpYBzJv(g>Xy>$oNA>BTmm+qwJ^Az?^_6m@+aUUV z{C>P{w5Pr}H{CPcMe)LPf&OP<+Ag#eY#-W%Me$DYj`2PUvji6@eoLjj9e)u2UhjUO zFg04JJd5Im@y?1DE8h-+`zT%z@1nE?3Jc?Xm9~T64)ON!-Gv7WeUcC3DbeKU!+2^m zMeqZ~Z^lQvquiS+|E+lMc(&f&TVX-GpZarx;J$iyKlSWH!R;0IPVQDYAH^TWlcSFm zCPlfz(RzP=JV$TOSJ*q=UwJ3Qe~3SdCq+M~{9NIO_!xJzJ3vn+#0MyhkI&F}oFh0# z?|iJhlcJB~iO~eXNzugUK;;-0AE>;J=A)8rhBBb z6)#HLhBjf5+OlnUsW43A`=!EAjqsP$n@<-$(HAB}pD2uv4vNRdW8#BU`dGmO6`!V( zPZt~&jg0;ne-e+64%U+~@gec(c$DB6#fQWPD?U{5sCXZJtxecRp>;Sp^}z|w)_KhU>S8OOSo?ilw&+)`J^xR(pV<6-g3s^d$AR(kS7+{%3)e<%1u{C&JQ zZ5>*L#pynZPtw1goSu|^>wReLzK#DGw|3vf-wL);d{_KO)%33TQ^j}dZhUmN!no)j z-2ul%W1~Cu^se~c_?~!dbg#mg=nkda8Q&3qrue-0l=x)9Qx%^VpR4$GrQad=C&jnN ze^z{--X0U(r!YD?M{Rs+e2&7of}^6-;`8<1$?@6o=x9`Qwo=ZCFVOu-g6Au~O(onO zzfu?x4;LJ+I-jMSXUAv7_p98q6h=oED(^}0h4G2;34$jnenW5FCiuDHGnMl!!3Pvy zq~|BZZQM8UKLr07es92m7C^q+{ZrD;yo) z7(c4=ZdAA_ZsMA{zsJAOlcVDslzyY&V~QIq^((<9iZ9pmqXmzSkBYC4AJ_Bi6>f<4 zOZQD%hW*kOp}Ano&?20m6{S|`32LPi)4J}f_{+GiYpnP!)$#4ZTZK{aNL?Q)oO-Kp zn6T?Qm3F=06N;}DyiV|Uimws8R`5y1_1u?gm3pqO;(G3HYMpxS<@hDRSK^oB{nP!@ z=Ao@{t(oiU4p7`xp{=X$>baNV`tHT}1;Ll%7vnDOKt1oG(ADh`4)urlJ;GuBP{Bjg zMxE7y2fEH`zk>u1RK5o8`S`iGfqNl-Ua-F6PHu~^dFZ4(on1#=cXAEgbMdorL*;!g z?x2*8u2X)0-!b1Q-z@C!JLeBb_fI?Px>LS$et-RE=X~?fEbN=_s9gIh9N@PMTZ9g7 zasB{*gkPNBS8*4;)j7XU{s@1#-zUFVaeKF=@^sA~m>!UJ)zdEdMft=1VSbTv9WHp7 z>Tsso^R2>}YU4Kr504Lv&nz4fA0D3}cxK^@!jbV2@mYHEX5lP_Hwvd0E>~}!UihW@ z^>jTwLn%kaN5)-p$EL@mU9{ABg5b~6V+D^(eGA2p{2pQVuuy-oM>t#M zy;10vKPWvg?WRBMns2ASZSO8CTpeE(Uskv#zB;~C@Up_Cg(uacmlmEc5K%&&JQh=N4WoyjnO{-+N8)9L0O*7pVLmdbfN2qCz9Lj=M773;Jv8mD^j`U`!&af2o2Pen4fFK&ZlSx|S}EIvt##EocT{?0+BtW0 zdX!)n#b@fhKKV1#KKZ`+Gt$F!cZR~5>D>ITVNRHvpQrfr^l&{nUEz%Mth8^wU;Zq; z*EfH5+ArT<@GQlrrAH{&X$q&OJ>0foo6tkw?Cwt0caBU?)mM)YJVH6nN&DvqEAbU|a;_o~^cAjRSpGu2by0d@IxK&U z-n};6Ex&ty=di27PJ+8B?xS~myCH5?*dYwjbsu-Na$b|p$?uxqDGbkFoL-a;R~f_d zgOz89o2}Fx!|ePV#fx%x=->9qjZMY~E>b*5c?P?MN?(*)n7gxZM`3YpOfouIoZCn7 z2$eQGzaV#4;m*PWJzbdFH@7%9I=LjhI31C{O5eRY-6cOezhl@tcT3@}!rsccAh(}# zjZXGc7?likJBC?dpuRH5jm%%7xAxDCN+u-xE7z!GzTVn9H$QiC;g-VA`CU}b0Jn1y z?x=ST$W2HlCI{s9SA2%@%+H;XyQy$C&Z zmb;;FW8t9Ofw@V^K?;+Tek!5A>*sdN@09a+(C*@ z)w`$Vt}onBI5js`dB)^V(cP)JLvjb_rX+pcto)AozAC4mo0=S=ltcAoYI0rSl-$Yx zkG=DN^P1TD{!B8HkSx7-7IrC12PuN|-h1yw5CsH5P*gf7O^OY%peP-rSh1mC?_Cia zUFo2rh=uoilDiMfb1y!6<<-ag?CxiNGdWX|%zx_1IcL;H^B{f;J6TNvCqds}Hkx^A z18%Nr3B84FX{V^kYQ34OZUi^ruQWHRIpBKyR(7hI0!|_IDznneQLAvXk?&m|EDMs= zieNdoGFSnw3RZ%vgH>R0{El{-nyNZdLMvN_n#!um*wXkly#9KCuECR6@>ZMKYL;4U zR^j*4{h@ZS)73Q9fxI2<0o6n|)dy8$-2`l+52*d>fNHAuw5jj z`xWuc^jEm%`Y`lE>ac348|gJ>mYS*7nAQ00?e%IpIGuZZslHOp^_RF7`Uoixt9|NA z)k5#XwbVyd1Kkj8NZejxTI#*HR{9vfLj$k@amUos;Qrv4x<9C|_o!C7HMkf5IP_y` zw`#51=-p}${w~!u>S&+m#9#=`~xcVCWT73h4qrL@~1xte`gC~Mo-jleCyhpj$W5J_A zPu)vD8uZe=^$yiew+DCPpCHG#Y8iKHW0&Dt+YQ`hz22Z#n04lnpsVht9|^kY?qGM_ z1MH!Df;}ngDeiNT_Y|(Cw^T3Ft?g1=C%cin8}vrK+^jHPs2!@k{sPxQf5*K}sQYy% z+u7c)m*PK2nvME%^@Zx7zbE!P^)PpQBzQRJqPyy+xkF9wX& z8R7f%{kpR~Nv`iz7keM!9|)gRONi-WHwRA#^}Nlv`rb#B_Hgh~&`EdJ9|fIt7roRx zq#p*C;h!Sc4@h2@rR1)533>0;OLSNJOihVK-mMpdi}gL=J*0RxcqVAzeGqie9rXv4_F?cr z@Hy|^(0dm8F7ue)q<5K}_`S*7$M&|*>bv!Bvq?V=?!w;^JR3Ch-VZ)gpR4!D`$5pl zKBJ%2y-3;HHuAO*yT?4PpU`{E6Z%PTH&;FFX8jEK4C%H8TY^U3d%%&8D7**2H@!_*wm; z-XZ0?K~wK}C@%!h6M7r^JHgw*PwHp&7Wj71jF_fgGw;RVg`hdu%xmtw6ucPBHaD3a zX0|zE4uePWXLEhjWLM?5OAFF8_gZ)_2QLM4h&gQL;0~En_T`|3cgnsJyd2yJ?U1<< zchLL*<&-^XUkzRfP7?mX&V_ow%q9My`5yX7`@MZFcs2MA{N8?NUk_djirR8EyE;Mm zJ6p^aC0xikZVEbuoMYy=Dc}_3sxaX~&am(){j?q)4hsdJ)|Li)l^5vQ9yX1=B56ZTvCM(}ztloE!8L&JS$uNfNdHBafw!{K2MdpWMV&FAEI zzBY;ED&pjI@)6F9`^H=rerfiB`^YmQygck~N8q~IJf!-@B=OYQ)sQgJDe4Rfi#o-? zZZ;7dfq!ZEmHEl-yb&ZrNpf-#_pQn0<8!ZJ2emIn|a_ou8)!OxIJc*)G2k$o>D)m zaw?O}Y|G;dX0};uvv7f#Z<>*-d03X%a_G-ww3)2veq{l(*sQjUO0XHhjJ7PAIazHs zD_UY%?NLfTW=pHkCV&Z~s6>1=TM3ulHl^fdVbgG?nPr-Wv&;fhS!K65tZ1HPw<+W* ztx{BALwkgBj@k>*0LlU8usLlj=qaj|QZ}$nD4}WCB%Ew!m?q&2Gt;z$-b%Gp+A3QG z9ip6IPFu+4P{}q4EN+v*61F&)#4kJ11l}mqg7huXN~)p?*{ZmLwsAPcOg4=vxk)%6 z44lvz5Qa_ynBZgtGdh{TOipGnvy%nP;$#K0I@!Q%PIfRmzw3aotP_AaoD-%RcPMD9 z;R;wzf3q#n^>VDX6L^M+W`YU5z?)zaywDrSJx`c{xbI9Oo}_WuD4c4h7|xF)C+Ejm z$5uyws(`&X92kCQUR0%QN&AvYv8BLL_C@uADrrmD7u1XRFRMhG0;Uj$wv25C8td8% z(fKI=7O?s4^W-RDUm@ko>J^pC7A9QS76FUcM0>qHX}&i%fY<9+iG4-As&d<0_Brz8 zP|vC7@u%zW&Ch1K{@MHjUeDDG{ew9Po+Rg>@M4~G5bh^4Q=c+FfIkp7O;6Xqm}$7v zrU_5gRJ}&YuY!4OZo8GTbEv7LI&G%nGT2$B-u+lW?B>n3A^#9|u2K>+J}}o9oOD?l9h55)KY;)Nhja4fUqVXY<-; zC?kiONN&&0)t3;vE%@2~WVey`<6viSow?TR40hmeR?m=f0_m)speN$bBmG?6KfENI zr(1^8%v95o_R}bw4{e^_6g_GkMel-2W_dXhql=&aH(Bo>!W?P$~HjHY?W<@#@Q;{ z2tBh^wlVr;t85c=%T`f?hLnb@b=0M`>!7Rx$Lk4tPjI!l%IpbtH5%v!k=pMM6z?<~VdT(%*8Ef_id+<;4);|O%1IN?eYI~O+r&n{YH8$C_58H*w zCJDcR8KEv$4Y z;c5f1>umwkE^HeXFvTxtyH`8Bo5_$rBLOlsSsh$F#Qcr_V6FM~W!G{P^>Qfmp4YarDTlGMDtG*4qjZzlbkJL7`h>|{1ci3&}V{j4v z0DH5(MGvq&!ye%P+atW0@GazNY_2q;O=B|#zcHcOrX|1A7;qnT)sj$Sb0Romf3zop zAFc6D@KoOg7n#e{rRpM63%>$SQr=WBeN=DNf?O@lo%Un3UEOK#!0&H+g+0Um+;@O& zZoUlm1e zYW915lC-CAKj?4SX&tfO@@yx9n&wh9MAbAG;aB8IDwv9R^e&gguG2r7;A+&mR5wDm96{!#rAH>Y)zV0rn(ud z2C3?#9jq=Owz9dv3{d@58*?DoAG9G&Yttb-tdHmp;SqflJgSd@$MkXVxc(aaT7Lt6 zqrU~e)hBc{Ge}*ms!{eJRfW|zcD z2ZJueb~T*|cQKvJ;owlviEw9=ml|@MyvA`{FdtV#$a{$$V*7=C!y&eN*e~p8js%B; zj^yfOIuPy%9u1BJd5r5ACyz0X1+C+Od7)iOt|9hP+cE4O=2G|Cdu%Rsi@g`Thxcu7 zjs-`9_LR`Uv@^$pV?jG8?M++4?ZB^t<3VQQIlhzG=?Bsfr68G!3 zbPki+p)_FbLJ&TVp;_n^G1U)8Vak@i*G2>S|GBkcRczNbIXnM`i;0pa)c%TO=3FY8zEU*hU= z`=QQgGMNua^MM`??Q)x2-O5|Ps9)mxBVs?)AL#^>(S+tBy-kNE0sl68E9u7C7xasI ztbLJ`f!U@%)&Z%u>8tGX`UUU>;xd?z^>&@X1o&4&zsg>1pVQB4*JLo;!R`7JJILYoT9bueE#h7JVIft-a3f)_b&P ztoa=LTz{b_L%GgQwmbDM!n^ctJ&EvSJIU_QJM~0xlAUP3&^riw<_kRm)lJV#u#WLT z&rG!A2~V(j)Ixh3cpGn>SKVwE+PqNmC~X`w-cGTX7;UE5A?6bBQZod+%v@^jQv=P# z=6*H63%sC&1%)#^a6VkcLy=U%^KCm^aguFU90+< zK4vYHHR=J?&-679Kv}ESscxp9SqJ3-HPzls9j%A5P9=v6?0lOX4&w=mhx6?`Fd07y zN^+PK4mZP0Qg{b-S zs@qjjVvB{P!Z~)fEfto;PYiEWx2eSNHnk93NQ#tjww+~DNHyD*4rkgK;4C{6Ou=tR z`oyqdxJlir%7ioQ4Yo{J8ovRQhGB#7QT3Q=5I&|hsj}e>_Ig`3EQ4PkdV{cj_=tK` zl?%&;*V}Tq>9$_@ka}3v3m;aGfRCv9VfnCJINg@VO|x~0tryk}A5;&i3dBsa6>w8+ z9Vm6fV$|4rRZKmo>JVP9HW1#RHi8?W6;rjsi=fvIYk_sb+F?FwTC4?E2&dY7s$y6H zN~N$OSUIc&UJzCei<0jm@S?D0m>-JR|Em&S5GJakswP-7tPvJ~k{??GiK<3e1b1Or z5J~~;g;WizgoQvk-Mv~^H55C87lPHG7FN~6YJ@Kgt0UEpl{B6T{%G(Gv-!6{F+yL1 zUk7bXG1b;|V?{E_v{&uf33O1S3AF>;skUHSR=pp?kGd)9Pntb&7IxyJ_#Sr!GggQ2 z1oQU^{hb~V4hhS!gD&Hgbq-?JAW#QD;gBCByr1v^_}w9)!_WeC1V4b^9YWm)eyNT^ z3*c!V1@~g(AOu6=j&q#>Jchpq`d+xb$Dv$C&q<&+ioKWqgoe_yFT)>#p8zlTYtjrL zwm-c;ft;7n{}br1yWuVmHhbWO4<=?0{XY|y5C)QR0As)|wKMATyBG;}svXg|u#?|D z6Dcy79dK$hFm~*qw`YRd!(at~UY&{SLrw;D7+LDW_y=(!!~HGKanSjOCkfyLe-38A zKT50*9>G80oPhs)fRqQFo|M+Zhzz!`_Cr5_H2HUMj6+80&%w{tXX-2Gd$`13LErE6 zB7IM@7s^-2wx5I#+#5BYdYlguisMF#rCdvfzGJS0Ry|S&7uPU}o+*#>s*`gfWE2 zA`$-+e5&2#-Gel27O3N#-i%A*kn`?su5tP>E?onyj~Pwul}O6}3^!~Sxpqeq<9*F2 z=%bN~&tiU7J6SbkF*`}K3rXkWj;F38RbO)*uAjMrl%vpk$V`eIP9|0p}yP7U$0&?SB%?KzX(Jshjc7QU&irjb?b2;=8=p1A;UpSqibup8W8}H2e zYBDn5ow(|3ki5n=g2-EYO60Ju>S(4Q8{UyLos39qTP0H6R&_8U8{UD~j;tv%n$MB` z{tkM3GYzTm_QZBDpE=o~w=>g`dTj^2Jv#uANNi$6g0TtV#_U5bL+X#+2$F$~h#%^F z>g1=yPs#h4)0C7=OjDkHIN>bna;KrW6iL^H7I_P*b{k!`L?8HHWpyi@8#2A+fikZ;%Cji`&43k*<>xZZCI9f!k5i zq}Y;hc5WqB^c6&N;$BiIwFEsTrEY;DS`MN=@s%t4?5|we{qHCI6%v`U-`(%ZF8MyR zla#udl%oA08WmrXqn7y+R~xJiU+RD>d*1`(+V4({q<^PHlDg9fPlZb@Qo&Q;Ip%Ri zgGs6B#7={gcOmsP-PEx8kaNWPmpMqSR|l(8);{i2$Lzz^1?$3>x}NmY&8$dbc~&H` zJd3h(yGzk>Qfg5o{ftGbuI0R7d+^2C+Aoy>3-@)O+1} z?40*_<__r9*2f4+}M<3)Cq{ZetW#F@A zN4_nmSB5>z9=9wzn6mI>eO!5D#zep4X5`D}I+M`MsAebe43k-H-E3}jZo+MFJknKQ z_aodEk9_6L0^&C~3vlb50+e0G7QmIY6DeVmnP{rms&+o9);sfY>l_$L>ZJ(aQH_v^9g=g@ko(q3r4%d72Y%|B~(Rc7Qbr0da?DM}Oc0X<& zy!N8rI53fWFobiz1H{iW2lRZi&N)D6KH+uF1I}(r*u&2CPNeG&!c%y_Ifz^9?1HkJ zeeGSy(p^hA*MLQkGYu#&^manu#UA%=Wa|#W5nAgU!mV*eljd61;f0a0Jq*8SjdK{c z+S#EOo4d^p((i;*by%-bKx$_`9L( zvb*h3WPLxepW1KTCFWlC`k(40;5O*H(aJr7{P1?-PJo}_mq2QIwE5U>w#q}YjL zx`}(=XO_T4xDWS<9%f3A=6<9WKS7q@6F3s=HN9c%bjx^Uz2T;;SHjyv{_os9SW!6P zddO@m<58OLT~3u@7kTAf1TT_NFp8e0oL zAn$#^9>gE7Mdw8mLuH+ zeFb~P33@!frhLV>hy(VNJ62cl%6nr;c@?1HUZF?o98hxd&HQ@4pjP!p>JeZS{OnM2 z@QwWjzQI=Wsv@^q4R^UtfRdfB@iX)dy0&*YGMlx%YWTIi;d;K#2wlG9&(t$?E##%< zgY)$~oe7G3^Pi<>>Wh%3ng`C)b9H9Eqs{_nk)kHDP;=qu-Kgilx4V(hR#Myumu@bh zExIPL&qJL9id@0-gk}?-&D9I|SwN8`c$Sn~khrOV)YFUb6SKl+6p4aopgfC|&4peK z?{C#lMg~VD z%AN$DLVl;7SJ!(LzGwgkHLw}rwZ6(1-PdrweS+90b$z6xo@~u7ptE^^H~f}<8u=6jpqdsu$h&i6LK_p$Bp5wY9&n)eR& zB0k}J*azST_Cvnxy+hoG>TPULEYh!{+r5Y~??CGAex#X~;+`^}st>W-@G0NGuo9t; zxNn1RlXIDV3c259qJALl#SM|{IPjGoT>r2l}gl8-}qLcN7mhbIWV z#rMV6NWD;t=J#@B0-rW*sI_mvX82E%<4yaddIO6PPZD~=eoM?ZW(DasgUj)6)1tk7 z8zn5%UA#8lx8^DJ61Ezi;_K&2e1m+0xRrV{+NCRzjofTHdtFG=8F#`wtzO15!_#~r zec8Tg-Y~cFHS$exGha(zv72$P+D=|)?}X`u`_8;&ZsDu(Tjovtx4F6*yqT}b@0hpE zP5L1;;a|58Vo^fybu@?{hVl^jD*hvs_bT`**N-3vfqVmcs?VW4{2aCdp258UzJS)P zXf)oW-^DG^kCO5cY>+&QG{j@zqgXN7f(*rb=3S&2-orht8`$rWNNHeCB7f4r{(u}v zL)*dY=ryz*y-whFNVzm5O#>v{J9*!kjg;`1-DtNW%~9Wejl^1gdkP7(`bf8*GL39I zuf5mEw)Z-K9mxMavWpMt_tC6hhdbU1(W82kh>oum#M#you_1byZlS3BdB~reKCABw@P`P9ScHDdA26@Qtx7K5Eg6(d4s{h z-X-8A*r0j9KI^Zw&tTK+0i-^j0XJj)Y#nmzJ+M>Mj1rpK{*-#e^v4}GD~VrcFC+I5 z?`dqQaqWD8O!6}hvdrLS{HLAI%@^ir=$oBq9i*Q1v)E!;tA~?kpf?=*Iz!Ofzl_i@ zu6u&R@tbqUX12NQ=k+Jt-x~l9@OpUt>|V3a^s|S}Ua&v@7H18z)mtcgjeg4c%zSR1 z;*L){BPjE7tQ}m2-Gi-;$YgJIw%|WWnx~wh&_{aDInS79&2!Ewdj50HO8pGstz13f zd}=;3PmuCS?7}>2wwULg=kOnQJ~5wypAxsp*={~Do1i?7y_n~nEvAL- zq4j$O{usXXjkQ;E-5Xu!ark}gS4cMYvHOv7?8AM&GV(oejJ=XCgk$Vgr0av`{nhwa z5o%$_;#z`N;mcRVEA1GpB(${SxVqAA^`7=NV{vUWb^}L4yV73ijUl$Y`+@n;l*eAc z2d08s-u)2#(0pW`CG9g_S$7Y14ayQ%&TU1GmbQ$0$m}s?pqF(kx*wTsrlPxzcdO`D z;Hskg2zEqDlSb?S97L{mw0EV~%2p!n!%ijKLr#j@#~v^##Fj>1{{XVJTe#P=o>q^s za?t8U>RPLpu*9R)7PA!-w=ZLfN2{%9g=qB(mUy&!6)QVhy@pjAtzO5bjaF}9rADha zu`8q13;a^0xJwF_I(pkawz6BveaNYdd(au>jplhq@$TS8-C7z+OWyWU?8sfK&kxdy8ut!;I5`QLS_sII+k$OvJ39u-m1ui+M>4sKuIbiryXr1l zP_+3w>x<9`?hL()?xw4|?>OCbSAC(|4OiXmuHV7xPIqG70pI3MopdcUYCDmuv%b$h z&FFETeGPk!qVd?yj>omP9d$#rP&<;clkTCr>r$$NZh$T}vh7fNLMw%A)oZ>;LA`^u z(e}DNn$+z{(?O5rIme)j-VOQZrNrJ3zKzApcDf!q*X>BzUYAt8D5a$8jTS>m)sxah zXSKbZfa_q}lCm8d9(B>V?t_LyNo3pJ_Lqw68dfo{qU5n?ws%Edx(#XCqMy-+G!xNx z>1ZdS_1Xd1|HG_lvLXTY9{3(3em_!`RCUnhZlmkqTI*4ifPTF02mK1dqtHa}V!PT& zXk~Y_GjN^2N%$k7UxBV_9k;cvjccWEKo`4{9RYo$JHqX3yV&d8xBO*xy!$3rSjQ8- z&b=OO?N0VucNr3M*P>~@%uaCMz&7dx(u_w3zLjpN8&PU2JrVi@bmNyJ2X_rR@5`}| z(V5aGL7xb|j(yf~#ILa9a7*lT%IyqZkKfpBsaxpAl-E*Ujo$qddo}J}JDFUQ(EEHB zo3Fzu?Q(aT*VzsSr{hn7J{f&bu|aw#I{x?CJ8}2eCTjuN!O@3DDwuBm>`|A>FpdJ8TtOtUF^u^#{JqYYi4L8L? zM04E~H%u>bMY3rT+TV-qG|Hcfrs)S*H=TmTiec^)+)!*<3`4K38I~!A>FLByLqGLH z{{#Paw8ur(>UQvYDAUm&M{nFt_J+Ebxs%baAL@SOf9PM2Zu3Xro%S|T+-Vn*W*fF+ zZ*aHaX1I6QThR@_gIFZbur)iw{TMgXU1V=T*LxAMci5Zk&Da^Z3Cbe7-T&C1>2Al( za&NXbVT0giVsEm=dB+l}xN7DO)y35%dN4RdUjkl=K3{QlnZ6VpieBJOf4e`+-HDs+ zKJI6uT|Q3jZSrS&mtoIfCi?%ExwqH_XvyCq<=Y|9E_HWcYjrj_8%^{MPG`4`+cB~N z(-GT0ZQS-wC$}@$nYd0^25Rkg!nJbeVP#;5+m6`wSOV$jl8X3NU@NyJHX7y;d#jy~ zF8;0D@fQ1qKL_3UFZ><&ZJiESyJ<_Vc9Dgmme{apkL{c`(A#2lsHNM&6`MsZU9nVk z3DzR!f~~QY(;jS3Ih0EZnXkZa(_Kx7yq68q&@qJfEu-#I8hRc#V6T zeE_!*T#LUP`U-S~Kf?xcbEliz6^j>Lx$83bQ*0tHgT5S%YZh z#YRuEYC@W(&OE!3*e7T?kNXdz8$Zu3A+kXJb*rNBdog&i+uyB7`by{=i>0Z1+`YtBAY4&b(6g`^RZaJE`?}S1e|G>l zz#Rw<#DYjQT@~5{`!E&*CfG-?Fff59nQP1I`C>DNycKkH-Pi5oR@c?=u^Nj#hJ)Py z9=9B6%Ik7^0rn#=Bvl`GA|*^fw(3!A7aZ^xW8>if7H}84HHhmCUWi|o^yPF}eG}Ft zCy{a@a#@dIIiU=cvbv1E8C#Mybq(Fyt%>X9P9}B|(p+M@p)|2&^hLUt+ta;B*TlaC zTal%8ioOM`r5ig#oLa>9bZg-nJBNI+)q4oHAKZ^k-b4P~*r+(*!0I!A>1r8^5luqX#=j{KNj^?h$_z?{I|BCc=}E8$04pLGtH_Kh;jNw|S*>Nqrj@ z088m7{p|d*3$ayKQZK}n&`162kxDx1-(Y8eNBn8vG-QpA`qPm|x*a>8CG_pM;(C!+ zTsH%6$3N!Juruv3f2N%U&O$!wn12-7rTDYK*>(;%2brr&apS@9thaK|vYy1UZZq9f z-+^V_W_k$eFU59lQ{6=0i3Q!JdIk1!n}AJpW4+vKtQ&zV@Q?eK*unO=Kg3=F9>ZVe zHPQ|BGH*HlAZUZJU))eP&`Z5#`0M=~-0NcKgY5lY16^O=?=8jO0DZkb5c#taN#ogdna2~}Db9v_x>_3+$T)`>lJd6eD za!|@+ZR;_t8dt>f)?=JJu?frIA5iKhuc>OLZt|PrZuT#v%<5=qti-x-S@M>{j@Mf3 z2Ul_)z@6p&9iE)gumkrA_zCAG z?7)2ne#SWwGqGfg9b2(m>tEn3#SZZW*autcm!_OD&igzUR=b^LSP~ZdV9Wdz=%t-m zJRg>G#R{%p3QCG2Ho=zrV%emDCih%M>N zfj-+`pq|9;{sJ{0f1Y{*yX*4^%||=_5p4C}q!!?#FOSv!j%u6NL3IKSppi(=mtiH)2EJ7PZQ|0=L@ROUgZ1**`*w zhjCrhY*Nkv-{EwRQKVfBuJ+b=`$)ML`}&8yF6t1jtD3;?Tm!6u4$cH$P6wOd%jsYf zd^tgEf-fhCP4MfWgEPUetLlL($uX6Bn}b!AIaq_7iUpi{Q0l4rV13m9Y@ix~4OJts zk!q~2C*54EolV7`$ZxX}TuHu({8lT#>eyPF#naAKqtz(2#v6@W>rE%eT&&1khy}Gt zq?yPmFl|&@PIys%TXm54=n8g47v^)`Yo9j_n__c0Gp3DFU~APzO(yRothv;{g4$%i zCYI71eMc%4nL*x}N-RmN^~T^H;3NFyXyO=hx!4D~$e9Ax!ur~N%I=}|<9eza z$U8%cJ&FgsvAA`f^@pJ^WBuW1+*nF5SgWe#h|Q|n*y;L;vjcjnuW-FM-Kv;V)XAli zoMK?IgGQ<-Z%r@>w{R6H z$NE2dm!Q4!Bk6zQ%z>}HzMQnuSM^gF{OQiz03ETjcmAI*37W|Xm#cB{Zh;-kPYJmC< zH&BhEoU8rsp$$~uljbC+D-2W@t9<@c>|NyJl%=UEuRjIL7oLCoX;=c;zHS9b!A-`A)YT~z|jAs5T z&|k$yR3py95<5_h{FmKU&|ilB3Ra^Ua{|$O#5eX|a$Az;C1PL39@TqpUH?TWFJYDH zeZn8$>Tsr4OQ?Bx?-BkBZVSR6x^+0uNNiWt;RL1+-P+(sP)GWCNYjo~&%5o&_kw#7 z^je$|wGE3{?TL9Fd>-3nHKAO@8B`x*HLC+>nLP(Shi$Z~P-=1-(01&Mb@V&nW|{Aa;u-Q8{%zq2p6+uh|} zNNjb^IQrcE%0X;EKb>##fNFC^T9t8P%M zaAs6@{I2*_{JflsHxeAl89n*XlMuYZAI>RkU5V|5Um7gU8AH8rWx=wX_>)%4Im?2dQJ3;df+dN|rjt0cEF1AjeuBP$bLtX^&8X!Z zw1S*(mJNRxrI!bL;fK01=kV*Pgme1AP>5)J!lm;>#T^M25{YbqOa?EmfCM?owqr>1?UGpR0SJFH!fZ!JJvO3~?A&FH=kL(Ip}79yQ1x>@Qb{ zcIxG78UA8*u|LRP4E-Lp0N5IGM6Vc^(5PXnyMF=N?591dh#lvVx6v8izlT#fJ zyIHx;N;jEpP2B*w*S2y=3ue>JmBis(%iPyZg z=uN!loyPAMyFjkq zyo97RKHP+WWX7*4=ReaT4W;$-ZRYaP9X=1nYN8IR;n319*-GJ3_M z*nfYQGtU`6Yy4KJ?of2RJ={YLW4sqZEA_OISfM{g%B zN8U@?c>G>x-Y9;@-}7F-<&EU+<98_#)kFM_Y2Qown9M@bF63=xo{DEFY2T94=hu=L z`OO?qepBfSF29HTvYg68ZW$$9-b!ji-pxk8ghxHfTg$lYQPc9PNxl2jxBPZe`x&Tx z`32=S2%^}mgtBr^iOovQ9iL0mb!o771* zu3Vm7o**k%h9`?_CM$mCs7~Z*WmJhrlg#)TqdJl2JX0qbc^-K~IoDq5L(a0#K~AYr zPAMiN?<2p5oOz!SC-0b(PzcIcAZ<^2SNv`nqBoQGlXr?o16j4mh#{k(v;+xD4aK8Y z7`?yL5_(|&h?f>3CyPtH$*3bEri>pl4#`R2@kk`-Ms%*~vhooks7b2HP+iR>~H=4Ngx0Vd<;j_SGwDC>qC(HbI0w4TVv zRV{uE(a+6=D*_f#iC`jgA$%QXL3lsRfAD@N3*HZ<$%vI7lzA>Et{^D0p!}Bkz(S-; zOiVjhNb8FG-~Yxj^|y>Y@n|aJXzJJ_qftE5NN<++`t@1j*GJP|pDU!!W&F4>uv;kSs$ao^_ z8(G2RC7e5|mt6Q#C%M2J_%1z8+LVpjl#SYyjoOrr+Ni7#KgDC2{06dvkx^V`hYX;M+_HX> z-Y)B>)U|@N*tBznlr3|GjEFKq$vrX=&VsX`%p5WvdZ3JtsdI(gC3VJ-d&zH*fp^PJ zIPF}Kb`6r+TT=UwLwdP;JaCsgqHa)9(g5iJS)krQm#<`;4M;TZ~3icUXSOlxQ1oEkSEKBlU0$l zKB-&It;d%(Aft}FPiCG=o?K>H`ORdNCT}e>e!l3=QcCJ-P-Y-$RkA*odX{yw?33k} zOcoxiDEEkdbV|UD1lNFO;{ZtAR zj+^x*5|qq+}s9W1Fj1bF2w4$VYFLngkJ>iZ6nsUjR_^f zA#ThHw+W$QpzNQ7Yg{bi7bk(mSnW28*1f_t&d>7+Cr8#UvPRFx9c1NPkSket=f*FL zAMei!QmX9HWPeteT9g`;y39(cvbIj57G$3$_m&-7Vl;Eh>Op=3+26-|=OkK$)U3wI zicrd{eo-!hudCwg7xx;o-*I-eM8Y zyBPFDxV<@`#$T;<#KS$C!g?78H-gUC0?S7G5V zi+qDfeu)HI{LT0b7g%`8XTFf7{a%qa9H;r8zg?WqveNs+->XmjdT%Hcwf!PdpO7}0 zl@>4GV5CnJidu5!|LPgiyF_L!_kZ=0GyOxpaEQc>e4YCBULxN-M8;V9g!B)QWf2Jo z=@VyqL#!ha%W{a+i0Dqla;2J{AuT>_KS&$?t$iZB9jCYB)X_e@9jAYn{_DO=r(K== zy~gA8G4$^>hRWP6dL?IgzOv@c#k?yr3q>Nih$4|pMA{WW=17)7Bt1n!T4X|GrWP4{ zSNp*9aDh$VMlDNm0%->tmVorL0)COG-OKL8dxUu4RoO)PKD``0Zt-edf5Vcs&wp zf27L^{oUk*MD{<{78A`NY2zZNFPdQ@!4vNp3qzAtae@Dm4H6CGL|U?}m@`KGCu6jK z6bbIUP(%ku`bQReLJ|5yynhUd6Kw~Pijw_d-hb>FHK{~$NP0lLXB64(0)%6EAZgJe z2P9HuvD|drKZ=k~+h$S|q2MCWsdPeHrPPFbsdNY-W7fWo$W39CM zGkiN4%SB&1OEl_=RHpPp(b^OZA?YiksVr?@TDS1+;@%KTZ_27A*5iz&Iz>|?z3u(I z+Fm^K7l}sGBGD>YT30?=kVp)l-S%V-PozDFEU>g$;g}VP=KOd~oCRK(v?v*Uv(U=U ztc=g*AID>`%>2?C6G2%=$1=n5THtK{v5dZ=l_n#ztSVx?VM|CfAS;$n_j%uyCDaSmp5;a#LkT;w2CEOC)Yj?{0=!l4igHL_xkcWyDqEaqAW zry^b%r}8Myy*?J3K%#Xov%c*04A(J#OmyvJtc_R6=W`4_pJk=5kN;llXjdrI#6&^aQwmQ}Vq9nq z8^s6CN*zQ@X zeaQ^ar7eriPHEL~o6f?u$XkoW4r#TrKakchy9BY!A=22wSyxfZ)zR-RZCb2kXNQ^u zX2X{@i&ma*xrbI84!yjA|);@TiSGbJN~=24uS?RlW#lSEYn3)FZ8x?>Bianoo>NC+Y2UFO9Qi_8l(sBwS6Xz^f3@#;Y>r!V zPSV6}SK6_BBNN{L`52GmkyyrL8IK$B{D01PEMsu$s9b~4ZyS%#9*MIs{$}~jPM@%i_U$7hekhVfU%=if3O$8As60`W-$V%Jw%PCSMd<4RhA%>S}F5R1-d##7d&{>-#caq+M71&uax%!|d$ZIrG@Zu~uLaV_&_8bs{dd>2vi|)wp098cM5|i% zWJ#n=<^RggPIR(T`3>>;RRMb|SwWoPHwf=R&a#U4f5Kyk`MiR{dysGWvab`agGj~} zWAwXZ^mOd zpY8a3mX((8CL9Yn?d)IoiBwLU^qiO{(W!kRofrLk`^3M` zcT4{ck}ebR*UChkAD-{|ACJ@5D5>Ld`Wof;j>rE#|M+~i<8&V0*<*WpJO1<9aXfm) zEijh26b^%EpPc#nmX-%6+yy!FDVF?^FLg2BE#@l}jyPq)Zxd}qIb%Lmwnw;dIk=9` zFpYU_@tN2b4x4b}L}o(t!%`*B#P*YL;6#Q;td9uyEf3rVu^J*08+o`c494H!gb#5( zzQLuhX@76q`}fzh=W`4_pJk=5wa*@p)BD8VvrnY2E7IHX|K>fTeAyFe=a zM=D)k`uyrkpP#WkEf@ONWk5w=UHHKwwV9UlEV}*<6ogG& z0EF8u+W)Z(s94@h*9ZAK>6ym%Ct`j?diZ~TJ;b&b3<{~w^wPmshrT5^O@TFL{B31zQ2~{k32(a`O=Tl zhT|(K+5Jb%uZRE0GyIXfX`lJ`hST0RZQiu>bA?mK7|9o>iS2%+4W~_$HXP@O)2GcH zr%4^f&Xja6dfL3dKP>wov8my(4w5yK=(WnaDG@9fQ42&Nv8!PIvD%UoH#F-bX`%UX z1)_DBVKpRnI`V?@rCt%r4d!9(l}rkY)u3ds1ir;`Pzf-JGINn8Hx`0Qa-EZKF6>g2 zA}scJa-u_$LbwdR*v%;e#yUZA-i)l^L=M4=R%NjskQc4-yl9Q*MQc4TTGvTFvA*MT zl?}|!zt25#fbt$^>iJyZbJu@*9j4b|dOJ+-%jx4`Je#GDhre|^Jl9+!v;V)Em*W{Z zo}K?M%**GVbI;7z=T4JehtdwuT|en{D7?VmvOfGRb@=OjSytF`Cf=DfcG|w2c6A;1 z>+`$Dj#t<5N;_U%$1CkWbB&$04%3FuU2kXFXZm>f&-;|$TZb`^EZ$fC-n?mlqyOJ| z&sF~UqNjbAbA``!uXCkOOaHxje{cG<_xdB@KXTtclJ}21^SScI95ZR#@^^-Zl{S2a zcNTNGWVJ5o<9CT|{hlj*NIJT}2WQlCwDiRbtGt5{i2wf5V9 zP@%~7y2ueUfOq=a?XJfb*TwdFvB=iCSYNLVH}oQ||Co%}AF=a$zU;35`?8MJBMbS} zA`AJ|2v^5Ouvo~iimQgLV3CNff~$%(cd?Lv0j>(R-bEg@GVTIwz>6$YC0u1J6gMPP zF|v(c0j!ASV)>=YgB3urkY5fgkJb5lgvv&?@ykZm^2-n|3%^-@snVcupyfA80fi@h z5q>F9R?}i3za&@+o_5WMvn@87#ah1by2Va@GMwmapqvw#j4RG>ot02A_8)S7R93Ew zA~%p3lyjwu;)jq>6=(2Mx>CgRu2o;f!z4}C}adoG;FI7knZ^Mpk+PsWG% z1n%_y^?U4S|MmSVp4H;9SVm$Qcg1F4JPIe^%SuLg*%?65{gf3>23!KIM07%9E3N7M z^zYSANASD(YJ?hze+6!&x|}Otjf$>^bLFeigh#1iYB=Gc_`YffWwdG!wo{iu^Hm4J z?bW4R`Klw~4r&NjzUoA{qq>AEIfbK>>daW%iBM%+XRx#C!r0tJbp?#Y^1JMgQ=0LapTlgY7kdf;jUI=)x}(m#a*Sw z5FQH-#MkN?QfhTAzE;=aYx2sM)^Ye(l4cCpUkv~Ua5bJZT1~*$Y9aJ1)kLnex{WvJ z2lj`08=?Mc5;0m$#@A{JzO0X?5>jd!zEacimAW2ZLDlL8!b;7+S867{QnT-Ui-ETxmkLGUF{!^TFcyGPl+OWj@Wo zEL$6tc~;JxnGeoa^B95Z5)&{x*9Gg4LQbcd2hLSDg7ffY4Rs?URy|TA5}E@R#ZQ1D zb7Ot{B2Z_8iTD{=0n`WU6DMcm%m!!khBCLwY0Yv@se_aAo8>HZ2Pa>-<(vok)-8Oy zg3Pn>#ay_0v#1&2>dj)5lo{NOW^l2zmzA*0`))MvyUhDJ2+P@%E>33Fc#bu+7#G(7 zY(N>Az>I|DcZ$dAc!U;>d_#*6tC@15wCoNne#|RO9nT%E(}u+|W$N55R;uN#UIXx70{R!Xk$n+f1;ODyO5!i70XH z#}cgpv@oh4CwlvUdXl#@(Tda1XHp2us#H!DDg%mqgsk35f>J*&y(}4&HK+@<1enCL zN_!AV3yUxHAd(hxE%jh|SGktdJ}g%8BYq>axr~>RI}qtaWpN(j(*AkkePCcS>y- z-dOsp)P}sP^k8Wf(*NQ!Youq}s1C$_g}k?%%_Q|8zp+@}lzNa~-T6m7NIP)2miLsF z;czYOMt*IFYw01vM{>B9Hy7Sg+%BY#$h%4{Nefred#UKXRP&KdL1^swF?FrFcyzD?aIg@|(vtKjbYFxVMT>o>ayn!+*^ElHW0w)lN+%qf$at zJMv4%Ut|P6=U519qzGzOa8FgF6uWcIF?`A~hD&8!9 zb=Sa#T)`XQHLxLG?i)0)E_VlVFH)a-i<;bhJP6k2?xqHJFV(>ZxT06(&Y=o;A6NTI zT;Jt6vohE7ySU2B(_=-hQg^HJU|D=Au1uxDJMhK154jV(lY0%h_bCaMalm7UfTIG|9K=O7N#R%I*a3;7@Vvl>^K2r#L3> z2Jhleam3yWR^m@_Bv%8g@~1e$?+0t}r#SL!fi?M4oDucFy8J25lty4f{uF0ZQ?Lp9 zL4J8T7UXGAjs-a)lHx~1z;7?dNci4Tjv+Y;<<3QpK{?{&8X!-Va=nmmdWb$y5_?a+ zr7g2BeD#WlMA1pqe#xDy!gT# zMRJ}M#24b2DZoA~LQ38z-3rQA1MlRRxeb&rP?h7DxgETny;+uHrZoGo0;#(=X3EF! z?(bqBR^d3R23BJ4Rp&UmAFImVdywO(7FL73SBK-M9#)fm*ns1x5m=XFsXjfF^hWi; z#`Iy*V@dzioL)=ATF0LNTF3jjR`hVv+cl(4efIoAq*_w5G1!=2p#`;@arU+*)rNYl z=p);cQdnECUAzaCCpJYp?ZCFwlzvv~$g@Lu&dQlB=WOh!vo$<(!?QI!bHlSWJafad zH9T{}vo$<(!?QI!bHlSWJafadH9T{}vo$<(!?QI!bHlSWJafadH9T{}vo$<(!?QI! zbHlSWJafadH9T{}vo$<(8*r5UUq4U7E2-RZ$yq1oVt6kn?|bCB9zI)${=UNG{FHla zxkiNJTaL<>P0rs?3ryP4DUt83Nx9sc$o;9#QsEOwc(s?FAzQY@`V#vyalFXgZ{mFT z-_*Z^Z@R-COZv5x?)H@4tJ0Ca!;p>wDsU>Hp6Cpgc8%Z`x$8qoh;%^FJmYURS~~*Z)NO|LOlf z+#|9TzuZ5vMe<(q=lJ#Ma34y!j9AFif;?5oRa35?@^&D+f=c|?_j6*|#J>8^92;_m zhsSDo~ z>g8Qm*sk0^+8p(AM=8(Ua^IM8&nWkraz82aS!KQ95@EY3|3SDe`9H$-%d@=2a^ZTz zC;0IBK5RGTKalmv{j0Pc{tvSLY}x+o?fbLW_h;|VKYM-QTN`16$}cO=BPmCX9Eyx3=Qh4T&x^!%szkdi--Gsv>?6Qy#CM+G{p@~XC zsO=yOv;VF-zx;3I{}=w8yuttP-md>`ztnD5N@i_`-!(Df^Vj9OCNhit22j3hqQ%D$>0vdBJ3H$UgDSfKL4ryA>0pP4;k)_@JI;v zMq)oC_Cw-$NSqgm{vpv%hWC?+{gBuX;q!$s*+d^p-eCwQRurDXCw_VIm$w_?EVo3R z|DOG$sd4JfI0sEvZ;%$2Rmfd^1Md)%c~ftYvOxKT-ymgxrW%V+21R#hEarov8aEb; zfNxM9#YbSWjwO`}6veNxq|$(?(Yoz{CT%agpeW+@iYwxZ9&WF==4~%@YP*u|9oN3? z9ap^-h1=dJ+jaw=!S_bN_DPg=`(RIlPZRBf^+qN4Nm7sF`=ECGIM^3Ous{0CoxoQ3{-}qw0voc12I$K+B0Yd~L$EQq0dWnn z0Vsk!M7k+{fNF*x5LXo&fYMiU(k<}=;tFD~sn^wLRDoXu<;}$?o@7Shh2K0197Q~P zJStr0(eZZ~qj^U#is(pC?f^!DSt%LKyNr?KN1&^AE0_mAf=C`z*G3Q-L#@#$u8oMR zu#F%kdWK_o3o?ecAEE;|hPNY<7e(DMyiJk3XzY&R{fgv8^Kc9(`Qa$J6#z%z^W#ND zad=$oZ8)hxsIuJ$ikjabtOi&Eb+)R+2cg$i6%^IKK`6OZ2IVUPgHU{{1ipgO+g)Hq z{41!vRRl}pUj<)5HLf(NqO2<~io#{6KbYuUpy(A3Mlr4|DC)$6(Tgh&inj1D>K6q? zb9xwxa-~2~m>w2aof}H4ucD4D8rVb8qq_|hP3xiP(v<*3wR$LZZ%5tu6#M{eL*?qddH6^`K8BD79KIZ@o&bLdXpvJAT4LMoMF8| zX`v^nf&9jDjEus@fN!$aQKa5v{i8@9RY$0I7(1elk?W}r#q-C>^;E~PLF!;UdLq83 zP7oWU4iGu0PO1}Zhl+2>ej*3dDPn`c!5lRq$NMz7k?J%yg1$tazD51iRA-2d07YN= zEM8DFsKfVO(i_R#Ez#RON69cyRH?(cEXi?==w$Zf5F(;JExdb~3H>tuJavbHqFH?b z|0;dfMN*#n0Pm5Pp6o(AzK)ou)~j{=2J15uZwJ!l%Mg)3)l zFQ^6N7pmpdh=MXJVL5fTsJDqPQ16isz~%V)MBb+Flb*W^HlIGUOC0B`dGxA}#&NEi zLwcT?OP~7~>Bq6z^un{%Ebwu>sGH9MXQ`R=+B4ORxH9@odf2*ZCAd8zr2cQZM7ON8jJ7K-!+J%%&ln1e;R=A<7-hzv|m?~s;S;mfSCOaVI9*MPtL1m5=N7$u>AySEvx|PMC@^-W z#}_@u)>u1G6!%+`>P*i)k=7fLe+GPpb{eTk#2Tr|_(p09zLA=WZ$#Ntt^uv7+X`z$ zPcQoRqT$$z-n|7V`jDc1+lrEA@fyvDhZ}RHD&qOQL$z`H{uTENYT`SRZR|G5I1?3w(qWxNlUb#FdI=!OrS&noumMaR%6`&Y> zXASTHd@=G5(AP^1(U7e~Z(WR@S-$L28Z1ptzCR<1vnA-CMRWEJ@D5_PVjZ`$x7>Q1*{(si5rbvhh7H+nh1J?HNG%MM}qi9of1Y*ecPzmTgPVHl(8m zlPyihR;8sMlWj}Oc1e#WTbhO~PE8Lc+nt(im2n5z3#r&2G9yWJk7Miw=_OeTYR19^(^IAY}p2vw`) zTMaS;PmV~Lf9HWR%Pxo?m-6hA%n>Wcr991uriLslN0!X_lVewOj72?N)+S#Mkh>CD zn~ccGlaj1QRP*I|N!BKM`SR2x>yc+7c|Mf&h)%q;F6+@S`ETVpO6CfNic~4r56GFA7L+G*`47^P7hPphS(fp^080a=A?mX}QKA=RdePxGL6f}b)W{QDsM9P8 zBB9!=++E3*iqeSeUD8}crmT!!C@qR4q;e7hHTiG7z`2zaABA|Q&Clc=u!=5rqKUs|ZB0Xq~ z{_{5WkMyjm=vRxgf27AvO@CX0y(CWuVSk*Ko>{(bC;fCfdhAl5^xx^}$?y27UzcA0 z&Y${wxek=(N+8z(xk{9YUmrwQTb^Pv#jhK3Jt@Z(MXn@rohc8>6-KT<@^w48^2l{b zzIG>9B)L+_H&o>5DZGMZYQ}e4jqf+Y zG4`Ci>yVKc8578X$v4boOdva!BmU0hUQosb!ZCrH;_pwg#zzFgk%1d|w<2Q#GUAa1 z{CP}3MhP;<-_K+MWlTWE2Qq>(CLrSj89*76k&%HLKp7K|v61xg5rOo)7b?RW2pJIw zM+VZyM+Cx=fi&?EfpBC%zGt5@G7ydlq>7IV#Ns0Y^8QLj17v(aMh0TM>5_NL5lr4h z%9uca$$P$V96&|}{P^2285xjwkTNEajLEw^853~h@6+T?SVjY6WFQF>eQkLQ7mfzl zyp=0Rx*$<`k0ZOz;mAe9;8IH^J{s@Uato>;!*4G2bCE z-ytzSB{4rGF`ppMVJfRQpKdTQADh1?@ zs|AD#0(s&p0->@%-nhCzs5p=>t~wAZ5#*1n5eOI3f)Oby1u}zBc;cdITqv$*APNUg zT-`v%ghEwhc_%8$$fCk63bmq+aBEyc*#kv2L9~@cLqT+wMO#5;s0!CiG#7+v5vnxH zNTX;o6#q%7Aw|_$-ZqJ{bIG5S9a2=FMg3WnpiBLv1aW74_H(EZQ97;?AzIS%zB1I3 zkTD$5l@P6MQJM(#sLPQm8`q&I_meV3g}6F}%$mx~yeUzw2$d{Cz3aQ~URYQ}e(f`6FcizfKJPQv|4Pi)lP_K;=IbTqSLTa<8zk|(oVY(s%wJCQhl&0$(H~|)58%&!Ue1IHf#Q9o z!e?adO5GUGXCSB0AdvhG=olyz2qd4LoI(L1J(w1+P=7E{bkIoM1m1)`fre!Vvva4T zVL8E^s1aybE-;t61-vD$O^}f*j zHA)jr3#Mhwr72Itdxi+*cVQJ^@RlZiH(C%8FhcYWVoFs+DIx#^qNRu_G!;Bz_h1## zSa4C8sDyc-7uQ>GNmV8;N()K&DyUQ>fl1`6lCA>U_^ND$t*U`lm1tsAQ+dHWswEl| zEx_AQpJ<7dP_0O}RLzN&085}g(V9prP`(-0j95vqBpMXWuu`fGIu}L3qLjD6TC1j% zlmbif|F@;IjcP(psdl8>f`w7ZXonS1?Mb&&9l-WrLG&~_V1-pj(j8Q%xCTcj(jC>q zsB#nl3lQzB@{#L|J**yKEAoPQi9LdKR`(HkMD)Up`l{Zf8i9>e zW3Ugo{>1x%byYpE9=TqWGzJ^1htvS#{lPl;p2Qwf14$16YvX$mdkAd8*7YFOL=7T7 zPz?qLfi+bvuok(ONe@;-z?Z=X@vneG!28t$-~;4dCH;yTs;a9RU=4CZu~*eFB12Ud za2R+Wz6;xUpPH#&P+h^U>P0mJ|Du{jWTu)<>LqXneztm^*lcW;nntu6*iCf@r<0qb zo>k9*&rxd*Hd{@ltOqy^KLy_d?7`N}rRE$pPd%-k0iPi^51Xsz6Pc&p2IqrMs;9uG z$SolKwpys3z%RrWs72~=a*MEq>K*l{dJKGw*gM!FwV22|YB*c=DEKJ(;cR0UwN1UH zCaCS;HnjuX4vxofB|ib2peCxF>P=!hu^nm)v5DYBHA!v83r-7>Kga~{xk4XaE)3Et|j*gW$VCoYCX7K zZBU<6`Wd(y|1q%*>I>4JtE*}wTXL1y25aT6!R6$>C;grJ0sJ0Zs+NJv$o)wA2XzGe5nO^#uU%A^ z)D2*IEuD5rT~_I|^!N-!ZqPDl7t}?S5zL@v)Xu5%q|d7hDlK&{gO}BZDwB3rodeHN zmPSjfeW=o4S5#)=nY7f}6}BohC0A4yBAK-;+8K3L-3VsUZq!bzGb*cgQk?=%sng(T z%5EZ(Rm-LwS0_|9?SwiBo>Vt!*@&9y>WVX!bI z&9P=$W6Ev=Z_|o{50Ps@o#tRcd?TVIz{dE7_!3%6;w`jRU`wz7zBSki%#Uvawg&Uz z+k$Pty!dutTQCp4J=hM+jqd=q2Xkq+fVYtANVw@V{R)yHh z*kEl4>6f)m;1IAfeyaAY_MA2a|C}}%dmfyEpGJHt_zZp$(HFoMw65S}a?`b^DVdH< z(96tw~4L*jS3(f%_#m@uh zf?e?Q!Fk{#__x9N;KN#Hurs*@q~F$F0T+Os@SC+av~k)d>`ibpek1-(ZHqRRk}cR~ zZ3Fr7;CSsVa3i^`+8D~WVq3KJL??h7@Y}T4wb9^c%C})#wRMzC(6$rbrtQ#P!|%Yh zYdf`3w@RB^Wb^yf|iy#Y4mhpTJV&1T1%&&*3M`#J(Yezi|VmBUeGRT=_yU8 zNA#$EQHx-gv>S+|*Kg2IXeUXZ)J|y`NZ+7m1T%ogwG&zUbU8#y2J^*}GBJH$$1x9i2oN5I?gcjz`HcVMOTqQoNl zow})8phd}@*d2OlB6sR#bOT=oE3KE+b#i5~GI}{(BUcV9tC!amx$;;!y#nd-;1Al5 zS_S<_P3d=$uAtuy-UWWI{h(!Io4yCX*Y4IE=>_#ddP966y#ZdZkX~4CtQVl9G1f@0 zPpmLlSie<&h3axx)qoc-$u`YZ-ceg+v?fLwZ+=#74>Z7Dq?N* zm-Gkqn)-`)!J2w4y(_+!-i`Q6;Qjgo-~;4dAX*#jitkRmo8CjOf$xEJ*Po}PHdtG) zqd$iiti!hTq)rd;KD|0vom?-{J@wvTFR-d!4Xj4459!`|U$75Y1>X}hZ!{w-3^fD`bO^d~5vgiX}P6MYtZ z3qM(ZoRZ1dB>hdI&w=CdQ}o9unSxE$#}Ru@pQ=AfY$`TIpQd*qHw~MrPuCwIHyxX% z&(J%Qn}JQ&XOf-)K8&BGchoz9oyg6?X6mzv%+lxR9q@Co+4@|)J-NBq9DNYm)E;b4 zex1Hve;s^XAFY3Y7aXmR0mtZL^$o<=gRkM&5*rJS)!)!J>Z6El#5U+_$d3cp;x`fB z2#&;W)<@tsW1IBVl#kQ5=);L^!8Yq#NpAs%;kW5S@!PPi`gYRWz*q4*!0q5G_?_Sm z@MV1nIE36TeK5IQ*iL;n>0SCfwrMapnEYk^J^g+C5?=6qeTDuZk;~w_`f_kNxr>yn z&@bQxSLiGCE0lhypC`8xT&b@DSMlF}MEnZ4R9^-zBX^FH)%sN;AL$>1SHZ>l5^xE* zPe^|ZzJtF8exiR0UIQ25KLbAn7vet$KLg*^7k~@MeL?zja6bM^@C$tp_$4?GA2m+u zr@&Ks#E2Ou^pkpwNYn_3oYn*5w0;JRkn@S1(Nj?;W~4HX>nC*2@QHZXSv|FJOg|1D zr$!p%h<;R0V;t3wfyam@8=i4iPsYyaX(>%(q%{ufNAz@HS|gotNI$Hn2h$npjf46j z{RS|-k-<2iAJj9DzQM?7?AH(I8Hr>tG8y~y{dy)M8I8=wUVWdQnMfw%E4FE`{uP$l zC}x<31zLt}6vf-dZA6M0MMybdQT(l>lE5PP;)X$aaqKpuFi{u06$b;LS!Z zFc-PTq#GFzfsMf&Mous%xhA9^GMa)-!0h;DU{f#~zB$+oyb0d|Yz}6{w={0Vx5Qc) z^$v*4dMsv9-H8pdY@)s7$OI_L9+^bT{x`d=IcYc#lyDtVFIS=^jQeuqRj% z-`ltw-y7>?^fB%t*9Yru^ffAw>x=a;@CJ=cG?2I2x{wZ(_exmU(v5D9OV-o3!U`L}9 z*ooX^(vyrS;AF4^ekwQxY>%G?P6gWgd5ACbOdTs7w7uVNn=9~<+?eT-c-J~8H!`vm*gxMs{Y=74jEUBf;xJ|%L^ z*ugf<24|D^%wtBf>6u53V}=iUrf(iGjvB6+Oo@vfH>?OU|*k`0AoyJTDrUiE!dyMp8Iy1ew%h+w)0H!x@Fn1cejL(dn zGr&-Iq*~|szGH(HIF>9K&iPSP5B%K?qiGKi}8_aFyG3!uT8_Z$m1ap$RpJ-k% zFI#dywepyCDXnAHAeYaqXJ#i?536g|H?xtekJU39kggBjgl`Bo0JGv7fepbd=8fQu zPx1Iv-?LAtxy6YK$& z!8ZeYf~E0e%!kd+=4gCpbFA5k+*oXk`8xSWz|r{ENOb{U$G>5Aq}ChQSaTH7N5Mz= zk4I77#T;jLpnM$mhWV!1p4^+*ICCWBkD24mwq`r99VO$jH_f-qHpJe-#+wsJzhzDY zCxET-lfa2!EBs`$C4MqC$(&*~H(P)$h)uyJn^TEQF?+F1&B5m6-#1s7uY#|dL(P@o z3h)*Dd&Gu;ZK>1%y+*bynuowcrfnq=aV(4UVbii~ zJkB}{9yX7dE~QD9Ywa`lliqJ0;I{dQc@#X#e{WbOxnxRR%L9|az2-h%aTwMy)3^4R zd%?Y?X9d=7bB`Gi@vVrp%iL{7hy+%YbOhXC?lhy;PIH$TBOSF;fiZBqxx-8irm|97 zTg`2xx0&0`G^A5oAG1wc&5yA(R(|UTGavY!`MsIn`riD(EI>NHmDkEgNnY$nGmrJ7 zsjNK2el!bO-3d@Zmhn8msgypddO(zUEQU~Mpyl^M)Tt}f|1 zRy`{tz8+TBs!zHem;v7atPkFRZwNL3)8iX~4Z(Ey$E=u4x*NQkoS}4%B}3(6zZ26M4>h-YSD{Z*?H@0_o?i7p&6wuGXFSuGkA!JIW2! z7H_B*tve`r5$kHTvDy-8jb{s0FV0R~eavsKtJ|$oU@7YAY757=uI^wNT{W_92OC=t zfe%?tz$R8xu&LDyY-TkFTgO{#ZnYrY!fFY&v|53!tk&Q(&KO;#<(JV_I({LY|L7&~ zC9AQe@jvK{xi+K!(^P5tcui&C+NG(_j11ro?yEF4i@PdK_2bS_Q?0lo)>L`!_cfJ; zXBtg?#j~iU_VA3Ysd+qYYiba05j53~Hzk^?$a^5z7rfun)OWm>)YJj(J55sydGo5N zS9rUusZP8#*HmT31mI&Z;sJ9*yBR!!*BD_u!hbj%Z!mVNz)g6A5y4GhYV9Mi1fyw& zYRIS)`hkuIUzm4&h8oA4F+;89-I1Zr z@xH}S$;LUb5Kr`ms>$;&M-$J9h8oQimZ9F~>BCT`xO+F0&0Vgc@^MdSs2bcs8R{|a zE(|r2EAsyy9!t46kEL9k%ToSd_w+N4==wEm&h5y1}2{|n(JeERm zS3)*R$2gazW1PVvY?eZCHjD6BguxQBS^j7qi*Q#$HcPKKgJnRR(Gqf3gvU}(^^CJx zdd8V8A&(`6yAtwPQWz|CV6W7l3f&S0qpgGG2OwSE_m<<*}UEHz-Tgq)VY&tsYK z7amL3-^pY7Ee1z@K~Pt3y&p*!SWQm z6=Ae2j5An5Hp{=pW7)1Iz*yNH=dK8wMYtM+C2#;mOuku)y#~CcbWf30Bau_Qi zk7Ze$!6IB1;jt|HO&-hj+?DG&Eh#*fkil{p?uxKgu7JX3$po_{qxLhKxjhgGCrE+2h<5VY8fow{lEn*Mz}x4Bm?HT7Hek;>TGk0UQ=# zt=tJi<*zv{!d>xUtO&0qg~1|>7U8jYe}~5+43?11^80u!!e9y6EEVIdm5RS$vly^h zD*eP`(c=sj;j-Kdb48c?g1_)sn!;0QavhJQ=wEm&!e9y6EdQ9nQW%zsFkMo3EFptM z*et?hDgGbgvD~7C43=Bqtq7y#_wZPRvr-?fO6}`-EW%Xj2Af5AEW&XSHcRa|Yo!5P zm7h5+!eD8@J&|x)Qg|%FVELKN^4B~TVX%a3mfz;F2zMpqu?Tmi8oU+ZwFrZyDkzMW zkiinNS$@f55e7@hX89$LMYt>1vspq0OUP!K_&>&D2^lQHWf2}r=bsoXA)6(I#}YDF z#=%h$9?Q6Y$YU8DXQ_;V$@2HuEL(qKu!L-uU-DRlyYfpmi!fM((-N{-{vMA-xGN!# zWq+K}B0QF%f5l^26=$%7+?CaERj$POEW%(}1xrOZE+K>E!#JBIWV5vS9Xu9cusjHJMc6FDU=b8HOA3!AWUvT#CFHSmkMmlD$MV20xGTb3srwVB zCFHjVo8=$#SV9Jia9R4qxhukEsTSw4^!c}VEE9g>u?U~#tvH+IXCBK_f5l_@TLz0T zTYl!TJoBqO7Gbc2Y?gnX$0FR7>)9;-Dv#x72203k`CA^#FBvStYFQI!wuEe!U-DRl z!4k4rR{z9f5e7@hW(gTAA)6&+u!L-ukiinNSwaTOjyRhoN+;dzsF;_28-nr*ei?T92ViU2#@93@8Yq1 z35(^6IFIG+U+`EWaUM&=5I)O4;<228uad%M5gtp(X%RNdKjyIrgC%6M{5Fr}APkm} z&GJX^SVI1a`4=`z3Xeq?EFqgEg~uYSl@vCM@K}n&N)g_Q0jnkCu?VNdg}0&;P2sWp z%wP#QEh#*fAO6B%2{|pl#$)*o?n>!6o23jqmePjsSiaLk2203h`8_-qVX@TxJ3JO) zt^69BC56XQ@PC}gA`F(0&GMh&u?T}DWV8HxJeG72Xi4F*gbWtpvIvi*&A-fJ5!TADu~|}hEU*7*JQiWFglv}I;<22I^H|Qs`79xW zC1kUN+?DIuEN9|87GbWu_cv^ozvi(BgC%6M{AYM9bAG{KnFDV{crE`9k42a(Cyl>m zv;1%8v8XtEC56rMzl+Br43<)H?n=mM5gtn^^Izq$2zMog%_4ji;k5iZnJeKPjEW%&8 zFV15T28(c4gvU}DtPGpwf11Z443?11ay^elcq)(l#AXpL%V_v1!c_Ssr)4yCQrIlQ zUHO^QB5alv9?PSDIFF?j43{yvZ8beySj3g(J%SbpZT z2!rMH-(j!_$3=K73;#eKi*Q#`*etV2{Th!&SSu-PmKmh3#-Ary8btCaCZU$F$R5FlH3ueS;b%lSDmC_sC8z^TDuJBTBBA(Sv zPfV$7u8)#RHsUwA>4+(n-StpX$xb|*o5M{;LnQ~1>~2oiMO7syksR*LZW1~wHxtR} z=5igBRB{oy*=?ewcGI{`K^bRE<)(IzM{=SWb1ZT^B6u^(G0liKW#lpH#@uFF%uVIW z4Ei+g32GjXoQUL5In~j~u}Cg37aB9osVTGR)3|Bf##&nbOPNid#yv^R6OogV?C8@R zi5!jG0*WF{3+l`0WWF!Bjkq#` zsnlueoQfQxJhwW8nW`0~Et!k&xxU*<^WDHb7%@@2IY=#2wI<$5I}ou@k2w%Ih;Ktg zX6q-rp1VIH%$)s^1NgQ?Wahr>CcEu4$4vs0To-iRw#?UeNUiqwMfOM5_&EpJ>S${zUE{CvSNr=Tt1w5c@*RGI((%#E((w_`($o*ftm`szE%W+6 z@OMY{L_T2IwSF0DmeyAKx!haamHsVmZg3U3+v8)VGL~IWTj%eL?24@OcSUxCyIFFD zztYd`mStHP|@ZnqpY%Q8MJW2rJqtl*!O zB)5T@>-`P>j>yhP`M5qnd1{u^-eYOgeGjuh%eCE&)Y;%~^tVN}M>hJ~BRe7$s9zq9 z2T>AO?!V{T?j}k%`kVZ%k!_K?;(7viQCdNJ*I!QQyO`r{rgW2kH>Gzmo-R5ATZnA- zxA>bQTOwQhEs?E}ip1|`M7&|?(_BiEB5vd?{-R%qk@<^$ zVe}_1(!vFQ5^L_Do$-sILUG1Fi-$-|`zCfdGDBPBzvIu)-tiZMi)m5Di#vcF7-hdi zYZv`XenHeK43@YYNoFlBcm{vkzm2i})BYL!Oxl?NbFd?$@)KCPqjs64F8O-IU@0Bj z5IN-wL*SHu8h^?!!7(t4r9?Slfxpn7r7iRq`ESM58{VP~IE^f~A);X$BOlV*W&cCJ z0Gb%HwYU8R{%n?-g~ox5n~z7!po(^d(hvPBetxtv6w7RiD3;zBnL~ZiVVLi~?SDk+ z6)+zf8gH^>HE=xsM>@q#kspIikR34b_w|fCj`$znTSfk8~|2Ft8cs7vn`e$k9ncxDmdQbTE^=D$5W{w)7_*798N z7;WFIeXQ^I5BMMJ2mFKJLH{bFoL|wFj2+JQUkF}98{-A)KOa2G5;tp)V!5>D`j^31 zL33(0V|->mOLh%}b&adX=%3Kg8I!F7yTmmGPp*48PnP8@AI$e z`~3a>i-GVHUZjPtK`nibKi99t?E5+Xr}`d$FSwU_E%ncW&x4lw=fM}?7eNdCrC>NZ z951o#i@|5q{FG7G&nW9g{H5S?BA+pvdAGmEZ>@hCd=|8(w3XgH5Y>+E)ae$q(XR!c zf}c{>1`hJIpe@)Y&Pr~}%zNP}AC5i}bO{beyRiL-qKBh`x!~p;B9%)!5`8%692|*u z4jus?q29shq3A8zK`gg+G}=bF8?I)6Va2=)9*OSq*&orp_#WupJgE1;YJxJpJX4)u zPWMc8l3Cs}&<;DL_oB2X>>(L(?yl9+=lb300p`Oi>OpQgHBN)4nfE;%g|SomELxbU zdQ)E*M=~DWjk@z;B8le9Y)WULD<T}dFW{b~ZsoAQpb|1P6eYNUnFZ5-pJ}{R=HAYxW3$(fFsD4bJOZ_>pJ!SMwc%EnV zQ|y70(NocuL95_Yv{leL*d6_xk-^>3J@|gK**C6w^9m?BEnVY`mwD<4Gt=kM=3LdE zI{nb^sfMB*=c80=K5*?Vgm5lDatq$pj!Nb%( z&Hr#JdOF%XXc3%_wg_4VyP`5exhuLGKads%paxW#QTKsb6-M0`r~}MuUqCx=t3kvE zY72=hP-kf2baXJ0LGY?7p&c<;yBAf7MU*Z?K~3hrzf4>>SCvQ&(e6Q0VhF7Hdvsyb z57ABs+oL<8r-L2QQ$aD~8I*!#=DVP13Kca(O=xr=+|)7P=-@W$6f@2Q+oIc}XIS=h zaFS(rMo$K(@G?jKd98>sjPt4psbSjd!RTOudL5gn#s=eIxsIisF~M0{I1{`sY;UZT#$;0{Vlp%3sV+Da3s^Hwk+5C-prKp4Dt62Al8fG(&l zO(Z@cxEySXZjN52g-gMQq%Q}hDHSDwM^Is!M4gGjq~JB!zE^^c(M{1S)cG)&90=og zGVw`48AG^jWvE};_=q}Jg0hA%+{zL!V_Xe3L^npS68|VDN4%`jF(yg^9b+;A+aY!) zdN$f2)-fjOf=2V8L#%mlCYm#LI5-mIj2&T*!34BJsj&C6HSA*EO##27CR4~kFJg065AK- z4{nL=4-S9_XzM0gdPm)aEmn`PROi?uv73!t#v?INKWGzc8(SM~gMARq9orM^4RXi! z2K&H$ET1(t9Id~sF;O$jN=u7X7nXe_)+Lt1$Z2$miMq*LxZ}0J%4CW-yagZ0=`1Dj$fBZ9c&mlEEpa%ptQbU+aDf` z2x?P4Jg7x(M9|QGIT!*Cp++NraPV@_h)6@freBNFn%KzTG5)JZV~@o|&*8C{C_Lng zZ4Y(?`C>bQo#0OX*OsyM(GAg-{J-nKbLBZhQA%8$H z5F8i`0tZpngvdkwp=ZNc^+KkLdD%OBesYztbjo(<7VvCOe4 zK_+Z!(A4i2^auL~1Hb`66Tcaerv4MO^LXrun2gRBVA=e!=6>IxU(lS=X8x1JpNKsf z6J?DjV-IWPjHkdSV^768!TNkECUcdZ2A_)62A__t_nO7ldF#EVv1YNCyc=Q}VlR3x zc^P68yy|`pe*1w~rH{SojrSh#-^3mSALIy_!Wt)gQ@pBvHGebhZ}L`qSA#9VYHtnxIq!L|SJ0DX zdw5g5Dt=XeDmABgK z#d-(5Xs4&w%S#(e7u(8GTfFIBCI4Q3x_7T%8LZ4Qy(#VGJ>&Hb`UKCgbnjrB*C^IF zwvGB*y&2S>4&LKe^7~M;x7Wu@6H6O=+Upba4W4GXK44#tfbCwxSfki>mfhy{rA{9( zbu3M6Cdh|Tlr#p;9gW4pZ{qbt0X;7V_m_e1o@ zsNgDZYw$yKYfvEeeY8NVAXqR~2>gMZimjlwioNH(@2S}P-U?46tzueix%Zy;UG)2C zp_on@8MfFm?_E!iz3VOaz9m{X_HFb#yb)XCE%l7pQg0c!j2hoW3&(u$Tl_asKNiHy z*gM{0&x|ehmVisB_jUA}XaEMWNX(*?>ASH--aFn`JOV~zUq!#hf9k&OjrO*yC%vb@ zr@U?In)|6c+S{R?@SX&pB)XOO)81C~wAb9Ry7#HOQ$6lI;q9cg9qMyRKXX5JKXJ!;A7gKLTWGt5ze_#lJ?`zI=1ykIY$384 zYw2I5?i=1!Y@GLnJJK5kj`BWtKXR|SAF>g2R>{4I4!@UvS zm+lB}Bsh{~Y_{5p*|7!QLeGvZ^cHzvM!$+iV_#yi*dEozd(_)Q3%k*3E$>(GH!^pz zy#E#LeCh6`bPp=CoxMlAz3LIKi}$rV)Efp4^M-@Ny|3I2s)B!)zd_yQ-wkdgw~zXJ znaA_6*V$W-2JGGbH}0$6Q12U-{n~Z-PwbczoA15tIkC6B1>P6YFZoyYQ-2?twVk|& zy>H!DyjQ_jS>^zd{pvd+-?~XG<;0RW66bpdi63BQP)Dzm_dTWGx!=1(yjMIoR*!NQ zONu3vcELKax?o*$9=&57unzeP(b}Z$k9->aELtOSf8?`h)8vcpCAXZrPL%~^CQ*~* zrpcGw@}$dwGLz_m$hGLF(Fa)S{zw`3ZqBGOZdsNnto6 z58cMe58+F@W!yPlb6RMYd?&d%-ksQ7?=F_A;8u&oID4x_272wl`&hOb_67I_d$=ZR zc`#Bl@=5esv{7>7!M^%gDbMATYyxTmv7IkVysz$0s+Ie@lce-=Ix!xeJ zVRED7kKDUi*InQ$W=ge8KI@)yTe576{X=Z-EKv9 zC3?SAXtkYJ1#9oMNP0G(zSphn z%Dk<1$;aIjZoA|Y?n&?@%QT2wiGCDqK+XD*_LR0uu0qYqZWUMNb~U85L8KAb5d1KD zC3<`0a`Z#+!)T*ODblw`R+tqd_e9<|?}=0bD@E=FSCGr$6n9IwIh>sMmz^O_o#dCX zy2&f4zXA=5dm|ma_sou*3Bn4vH!|3H*{Pd67^|233N?o~uQ;`n>m+A)ayTX2>{v;# zBxgx>X9(xa&CYFZaj>|X(^+NS9jO>uMawJAK~BBo`pJWw!T495TFJG++O(L>`QH7( z&E{ms=W>d{{k!-9EY~o3jaeab zS7Z$>uQqc#x4K2#+)fdB>a9eR7B7RmO3*ee!#> zw%mHp5%->0?rtaa4?0ET3G=LTnt(a-4*_ICz=W64c0dN@77o~&a9%Xds( zVRTHc46Y>ij!@C;P0R^%&PFiQVQ8l?*vhXRZCabR+?dstD7`GO7Fzk;DaMP=OU@M9oQz^w8fPPz+DYSxzF4*7HPl~it+8gI05g@E zQ_yMa>b&S|rp_i*%~Cn3owby%v9^%jjKW#ei8))0n3KwxM$M_PUte&#I@7^vuwkEf zUT{93{#xq;OO#}`Qh$rFj`RoCI!ib?>%n!_dP{gXldOvzos%rllbJ+hy>;H0XU(^c zTO&|)d&gdEF9k&>?HI9t=Ei`mgvi!q|OOzp}oi+?JTuLlWi$$Sz=!_=34Wti!61)SU}kr zXMw#CzsweWwq?{@YF{$uSaYpQ)VydMrp4DmVfG%jj*vTLi9+2e)^gH1Z4`0}JEvKH zA?Iy-jPne*0Dsw-WzDuO8?&uB;2hdIWF59f8>g*TQL{Tu3#Y7iZBc%Em-Q~QPZ@+H=vXTWQaWtJqDordc0T=c;jmrOsOytbu6st)k9K z`y%NJ)+fePYFslWTT`rS#uRHRIF;z9M1&PQ$(n5KApI%ni_uBeoTRx)v+X%z_Aq;o zwbvSE@3r<>x7fMuqsA@RG4L2lcS9-PXU(JL+@yI)v+UXS?4;@N!)GTw&p9(YX|Dae zGdpQc(j4M*?74O>JL+sTa@n`A&AG6slZV!F+j;CGXy^@RUBm3*_HJvB^{PFTmS4s8 zgZr%m)_mHZmoz_VrajA^l{7nPhH*3PZ3TtHo!35uhF)I#FgkmAX)TXEf_8@6uh_5J z2dtUYo@vZXnuUKmX@))1ew%jYC*`znwznBMvF%1aTF7gUw0Bv%t&uD{!XCoX2dp93 zLGYk;$eNKPx{V-y0qwk<7^J;Tm#A4I7yKP}|5UuL;ORt`I-z1_%x%`!&O=16;# zz0=xdO;4JU)X$iX^*0u>?1H3)Nz?4*H~(l{hGbq z+F`wB@33}Si>SXaX;IQtdz$?^@z=m@)^;nKJsXyHHe0yg*=TRJQIHl2*adCT44jrU zJ*ht^I*rqkM8EMSI~&Ky)TC)i1C4iRZBf!YNmJ~pb|LB)1oxsPSjgUo#^7k$f88!j zq!73VrNPD2d?#sf(qwyzJ%-ZJ;8ts!wS>sxq$Np{?8)}6)GQ2&0^wLn$Jk@-&DIuc zti8qBYAvPClBA_c6YWWM5$fD(zd`9(yQnQHg++-Jv5S!|3hqR!Fa{R0W434&c66pB zb#OX5lar<-^>J^sv)X;!toBV{Uvh=a{`LT{Fuu3D%3clL#FqAU=WqK;xp--swQw?XjugMeCB)iM4ceIysY)CMOj%2iOB`(Lx+x-)i=? z`+@!J{$PK*u-VJ)?XI@_({ewzznjU zV1w);v~#Q3lO@;KJ>6dT0W90!ZOby3t+q}(d}o$@*y-%Nl{6u#voj%SVv^`94zlxO zgYBZUPz0^T-gY0-eeAyWBh>8d40JQt8SQ~?MmrOjiFWg$#5mZ_hrMj~aM#%5!Jhaw zPFv@))dt&O6{DS^W_P!TJKpY&y#>ByPp}8k+CaCp)5h6gwZ=ADU0BN_P8a9Rr142z zobgF-CEdod#ZY(bY4@^kGke*+?c$_wGrPIn-3j(!_Xaxyn1QxhIUB7_Rx779{!v=! z;=JT`qs~j%L~x?LH0fnGot@r(*-dZX0N%ioEuB`*CaWd3*?P=*BWYaHW6rpwH^DcP z9(78XJ?x%#3D#KL9O9<6)7e94;bpfZ@e=4scDH-jkF(Tc&MTA-ai1XlxbuWFHtCI| z+s$rvcl&nglr&#;)7WY4SE=)gTgrUN?q-*w^mg+}YChpS>5NGln>3UUjQ69FNJ1v~Ub_?f_J)N?p zNz<`q;0$uJ+!v@h3!CX4v|Boxt%KBT=^W%tdBZ-)88Z(2e@wk)m=(tt?cH*^ySiHH z;O+_T?oJ5q?!kk*y9R#y!MHaCdiicenS~^MCGr?}xpryK3*%Gm|rr!`XYS z6YQOW=cIkgZtJvj{x=2iKYh!F2@00~Q@s4j{o4IoeD4l}^?TwwH<}U1_J4IRv;1G( z%hT|jvQOJ>oVLy}p0LzytP$*b(PTcd2{CS?VqWk8;=EeV>_(_HHzn z@d0<$W5=8?+%Mf@oE>!z^II?gT*mi)*g3*_p5K%b^vNHv58CJHpg#Z}$r2m zS?n%x+qiArnz1%SEwC2)W1V2@=yr0eFkjNieUJH)1MoF;PLh8DT;wix&%l@xHOI58 zS7W>FJ@!@juf$rzS3B03+D`6%=KxjviAG=}r?GR&S?DfuPr-1~iL@Y7(q*3#4cBY2 zUG{GK8a!8HUEE42sdjNIqq^D!p3d%RXMwvATu9~h*baNAeLc3*-UaTWW*^)zCuqY) zUHhqGU18|rc6BSF$-38R;#{`(lF`K3>+EAa<9zPUch5NU-38zRcuywG=|tWCshKd? zZtt*f@RaMZ4`Jx)-el)S>?~DhoU_h6_j9)!`yYbk(RS_TRzTnN7CAS;ZT5Ei964v5 z?wodWZ^yRU+w9xy--?}Q|D1E)`OKZ`o_FTD^V}Y8IW%BN2yyxER1EMHlxTSb~?M9wBoXT#ZD`(*jK@H+!e<0q@`P!XyukL znz&8Drf|)Lr44gE^H>+dwg^1Jni-x~zwIwBo9rhS+2m!W*TPTM~v6C`&YU zo4B7*UmESkxvWdj3_SuKfh7yInMD?{-Pz%!7HPyLyCAw0t=xh{Yqylq$ZZTZhHDPh zrO}Wrjn?iLFf0Kh_0d$+Y_?O0&Gr^BHFxibZO(S*9XPXy(nbTfpvDMk;l!2!-ZY}lQ25we%-W6HJ zW@n3&Rcvv#ISIWXJ*V0MAGvQi`p1S!&A|%h+EU%SLThQI4Im zIK9+!>$}U@U&drpG*ObB(`+KU*yL<>%5z%IC~wqp>$>HQx^6vp1?s5#n0DGnb`El~ ziyUHuv(d>RHaeS}3S^cya{*&%nzWMT)A984}!h(i7+ zOh+wEaFAJM z;%g%-9A6V(870Up?&tPvxwYNgeje71Wbch_l$%&L%Duck4p6mU9*}_u#Q_-#CBA{- zYa6^rxV*e31MD@}TrZAigF48}u{YLG|QYBCAn~%#!{g z=?PyPBIls|j?-^Z*vP_Kn$uE#X@4?m%!kQ2B)@0>JEM$02{q<2?3ebBNGUvVgww-t;{0q;T@ZT_-pWUy4Lhs604Pq6zin+x4Ff-p|F2v)e zfw_p+Rs$3c78=drY-auu{ux#@{vawD|Ap`RS^fXQtbR5yoBwavfZ9mi_h0#+j1+QV z!?|Oz(ZZaK6HW_r4h}gj;Aw8I4*v)%8LNqm##(s(3#*YmAr`6Yj*m5jp#gfpYvjMO zCABT^_lVqceh)L^y!3mxnspsjYr}P67XKZ8UHFdwuHT6KhG+)=BiG1Qq{B_~_FteYjie!}o)B5TB3h|2Z2-ErL{hINzs2A6aM+(L@sj3mL6)%HEaV_?_ zkEi!D_~qjn{LNwccm?iK=(Ww{dJ4T3{wX)TU&0&SP4B1h=kTWYbNEY`4DZg`W-_7< zSO-s)lw_vB$Frtc%e?O0pyIlh1;3~3T>Z-Rul)DA?tPEz(=B*zdP&hjtZSwsKP8Tz z)y*1Q*D!0E*SzcA55{eBZh5!8AHpBQ+uo1iPhk?&5$l>shw02Wdg-fV+jr^;` zkKm8!3E!dWws*(-KKvm}j2~!yGmT!&tPWPE=8AXK``Eb4=^d|jyc9~zwd19kX{*go zqgK3Jd~>)ZEXU7dbC{N@G`NVqkKfB>YNi>Ny=my;T=uSTchCDS{64$~&s{GaIcf12 zeb20Frqd%wm`mPeZ@O{c`zHK0yzhM*eg}R>c6xH~BK0nDdXbo6JRs-3SBI~pcDzo! z1lrDZ;w906F3Z=lB`iy94KwIfaFxkGZF>Eo_jUM9_>igxUPiq#nj9H9&7eQ>R)t@M zkG!wKufea$s2eYiUUXeJ>%=qZm2jTPM1Ds7F`19NdYsmc*NaEm(e>iL%NACBuwJ}= z{5Sc#Y!F}P2+<%e__MVEJN4rawDaBt?}2u~yXfsqa68?JM&u6tA^Q)syL##P9hBZm z#Y@L`ak>*-JD+uXf*0!c1TWM`?=IBuYcq^?=6&s=H^aEEwZqLPQUtx|J<`s4=fHE` zdGNgVP`izeTZK48L!K`Rr*O!MY!s}Eo4+EMSA z_ewkF9S4tlFSTdnJVhzcnBwjTBoYTlVvIti%^}_KY@t0gjYI}v^ zh2zKAL48lH2v>%y)pdPE_y@RJ{h_Yn6#0j`h708HYGt@8{9UbP{Zn1mujqfOEBaON zDjC12-_@${H}%+i;{C?eWA86@30=Ow$oy0N&Gld41zaZoRu^%Z{FRC)-mk<{?;rO6 zR{yATDDVBF&ZEWmi+buE@_tdjvi_nDd5689)nV@l_zUYAGXGI))ES&5*Qm27_5Gxd zct^dT)X%IxsiWR&?O#sUsDIUI94ABn20v>BhQ9Kz;c=||>-ZoKGuNYjZL zD?ji<|E3lYmCV4e#P4e0XVNq4L&(_(4rLuqRpf8A4pl{;ip+W<|0*uYiC~EPgUuo4 zMtv}`3EYGu=m;_+m#hD94IN>wMUm0-eX2Yn3z!83*u*d-@)P@4@LV2b4mLOIBgr3O zO5gJ}J&AuA&*dbXCiVxKgE$>XY|%%N6FFr4i^u4He5e1a|I|rbHUCqmaMk=#{iI%N zKN4>=Mk-Nbb$uOOR@ax@CG{`i%bXPEB>re~4W6W<;TdHL-}MbWnST+d=49j~^~ae1 z;7>Y+oYAJ^3r-#1(0<4_16 zU`}EGBV6u#n!U`8#wK_+5=X(v*LDYN+tH{qeA92@{h;1zO}wTsG$DRat>J0qwf4SN z->9)Djt?-$5(CYtuuVZzya!%n8_>1;P2UMaq;#kIhTqt0;=R=x6Q{H`)VB6MCUYt} z-nObMGsb*?ja9jI?>zUeqGWQuB z$?4#A^j4^qsuS4J>kM`Rm#Y=3GT7Ox>@8EvRTZ$Zmn*F6)dTB!^}+gH&QJ#b;!Byt z7^x)&M`$B8j~y8#!nb#%mWUVyj?zYJNsZxXu_q-biIIca240S^ftSk95$5DBH_W+0 zH;}=9h8wIk{?Ogv4}L>j?$;VVoL=AuYw)|w9_9#B`PqroejciFhk3#}UR^Ja|LJ4F1APGYtO5Pcwvjtd_zUtPKH&XhXrF z@MaCOg=ze(#4|5nSj(#o*7ov-cHjgZOa((2q@*f^@otzkeCEANJooaGnJ>&A*7Ry& zbz_rh5goyf=!wOtqAfP~6Q|C1!sp%#@15{n)&k_`4-16Vy&7EC@M?OgU`~m<@j%q* zQyGI$q>lww(8){`{DIGBA{gR9YGVMJ^r^{7Wn>9ocrU#y;Y)8n*Y9vw5ViuLNlj(vhK0iSy=q>eu$ouhOTua5AW85$ii>HD{;1ujB{PkY zl$|6&(%@HoLX!r+p~6_0szPDmu&VdIm(J*?_1DsopVlbCPT?>anMs49To(z8hVOY* zy<%Y%?>%s-TBeGH%XoDbW4~yal$~N>zc6E%3Ct8`4*L>Wz<#WusRu?7nnqv-gJLe8 z%Y$Ol7#LIRhvopTJ!3%3!+UuE>PpfWOwJ%QlLWraadMOyH?=?y`h@$@x9kJ&ey}fV zf1cPc4EWvpR13_IpHV<`HUoZMpJ@GKKFYWKaTfE9Au$`@<{>c$SLY!x4~`9>wtqMv z%)shX@u`-Gr^L-f=38G2dWU_&14cjeoC0GgwL@Y9$s7<44AZmr;_RT&E9}kcnLf21 zF$ApKBbkLe^dM>nhJ(U%tUbenD0TLP=^*$M-mKE}%-&iO zsuJU=`r3cv50AxgmL5*+uviZ&el`Y&X{jDe3<_Pc`)IByS(B2V#7t_w@?ZNy$Qc|C z3DdBSh#B}!kBFH#QICLacubgmw7!}!UDjmeCpD9qFa1~k$e4~R^+@tZ#D-EkBpe#1 zW_8TIT0hOf8?~>NoXliqa`Uvi-e*BkxSN&rA3T9=^4o^0fU3CpV46~~b!*1bh)g#t3He2;X|7tc* zoTX-}PgG#cBtm13>W=5z9CBu>cT}<>TD) zox?6*7j|c;kUy_xz!w@b_V!w!Jk=TRxOvph zRhd*~_1MouJn?g@55o3gZq+{Q0Cs@obJY?5xX-DYr!uOiekwDgdg4FzGg9}&&!gIf zAB1_R%B^x*mT8+gEgLW0TwLe0a#-o`V$Wgq<4=$rmSgtQBCjsT%*|;oE4LLx(KI_* z>5V*G=eF`#COW0rxX)ljx<=`ZyzJz$@>&K8rdh4X!9A;$jWr)Tc~LsjO;*(=Y#ZiP zZNqk8JHDFvsy*&@^Hm3Q!she!f37m9RAy>31K&X^^Ihu|p6TyeSy}VLkPn|P4gcPE ztk*cIzhk}2T7aGWIDfr0G&76!j`c>*LcG-rvJ>ehy~fG6p!EiQ)CH;?N@EMu2e{`g z;JNcvKE9s3V5_iom`}A1+l1+Perhv4fh#e!1@R7hg>GtLu#lBswG3N@`N_|x7Q(hb z6=Af?u-6!9w5{toed8 zDy_;J$>gjl6%10T)L?3!af9l%u^U9YSYkOvO;w3`&J>jf{?syO z@C+yAoI$Q2jhT~pW;}%RfqW>_;gwbho`OLlnOII$Y2|n|0h~bPb=fYqP+gZdSRax3 zP(G4raaYR`|Gz!c;?ZeFBPQX zI%VL+-U;3X-wm>YSpymCEJE2ybQXaOWexk1ybNBJSHLT>y4_K9;=CiFWEbJf01RYj z;i5QJ)N*0S7Pzr&!Arx9y)=rjBiZwLiWjS9UzLkhHF&PdYIb$jn()`KJBW@#$qqyu zjLSr_tB}$IJ?Vo!&v@UiW-nIn6H8Pr`=Y!gYf)R%7C7M+wSrid;GH1gDSoWINW|-* zy_l*#20L)~A#7cRLtZhrz$6PDD=R#+xC?81$gF zyXYZo>Bt_!kwR9sN2rmivR#F>9#wVidiGg)PR8)YO=iW2>e=<})AEe0Z=aE8WiMe#8?Ps;|J*0+* zBrqh7C5@#C(gsOmX@hiNI(B=Dn6zYXYI})>R5h^s2vf#nANG5TWU|%GV@10+Pw8dva(BDWl zyE~}bP8^qq+*f!gAA;ea+tvP%{H}y9`%~4=?r)c7JxtCa_ptjCZ)IIH7EOdsGzFW& z*v0N@>#_@B$N}W{w+GlI?NVSV?hNvEam0OrJM$434!fQ0F18^%6Q&$U<^bCi4Mihi z5{<#e!VpK@=lC@rrRs<~h@64;AiD%>j7(D;bD!efe9V1@v-2@BkGg~HVs>$RFi`?5 zLAE6tkZTb!ah&{P?htYY+b7&7xICX==eT>)eT>)hNp?=SrrPRm1Gl-`T|=2F!sGIU zG`Ko0b!Dg%;0bwB#>g~POl@|zxG}ZG-Rf$pk=@wVl&(%njc8FIr7U& z$@l9jss3@-xKgcg|8-x6L+qjU%kUNJ`{I^!+j*bbs-g%r^}u?fK3J5y^0KYn&Mps6 zIayd1k@ZCd+1hSnSCDP&wqRS%s)-xUO{bc;>D&Tu!Bt&ccWyY<*{>!FQPTh{%vzD! z3i3txG8}5ZAcol_0-?)KW-)2%5H5}BD12b0Z(;NS+=xW*_GL^Bx{Om z&UL3I`!$45m8X35r~8*%OI&rXIkh;gDXPd8c1yboRh4DHsjmX{m{)V4PP%`(p?ZXO zdB{$nLY0_1#$i<=rHI5}Vs>vaD6EueKMM`pw4a90!hTjs(HFPa5~8H|)hQ@{aej3Q z$bzyD?y)6BAEFdkN|YA;$?1o4Y%x)s>*At>_>Ih8o!^}NvVhcW16G}Q9>!oc?U?-} zd>a1j6p{_Z&(1G!|Lj=8=DGpDr9X3DNcP5;wzL=kXMg--i;806ci4V&es}W8{PHK~ zXU7(rt=rE-3$~aYsdSbWy@)bk8BtaYq-ub*n*86L)lOcSPrkKYgv0E&*7NX1_}0>> zwW+mi+kPBA34esq5kESPxa9ok{KQ>PTx-jULGTR3pSFl7D&APb?56e`>n*E8m2Lk4 z^J?c0Cy&f4f1vJ?GnmXlxYrgIMZ}-%|Ka@U z>ox08s)krEt>$(M`=#}YRZ{DM55q^{w`5;+zNPMp^EYgNIm5^wig#`SQBeHD&fm^I zP7awU_;QRdmJgcPjf+#28scz9+}XvGS!ghSz@;u3uU$?D6uM_1qc{&p7!$ zRaKq$ov&Cw5>rGs>th(EijPGXoPn$Gv#2Gi@bkFpRN)!lfZuR88m9N;1o_l@W=()? zysS)KZBd!?TB4e>3chN@`_5$X5uB5W?qGNPil@Q+v6v=0S)IA=jPvj)xT?xg#5>?< z?k377)>CUD{1fCPFsNMpFHboFpGxPpnBW zOq3O!N=|MuQA~niBGJ>D0ncRN;3Pc_-kH{-(QdPsL=`3gcNItY4Sszg~Sq`T@D>#C+yi>u+D{48* z$f`xubUqR7aXtP7&Y5BuSy|;UnN9xd4C5-BoFX4s53MP%eI!2>AK;SwDfyp>a!z@8 z$`ScQZP;o#wVf}WrQlNTrpo))18XX^Q)C_XYdf>3{Zz~n?QmQESl+YlgZIg(>wLj^ zU80UNo6}ihwrGP#^K8);kLGFeu5}N*NA?`{XN!8y5-REub)D(*j&;|XPR=wrL*BOT zSTop}&h?$}Za72U<(1l<>lw1UydB;NZEGmsn_~@;L&2fawi0_~oU+bSF-D9PPl+cY z2|J0s$6SvSkBRZ%6Yido^AsEM!Xe+#Sm}^cWF3H?J29b z>?4)cNA?B#!lk)`$%wPBth8Psr?8XOE9?{ji#TaKom0)#-9a!VvU zy~I{e*-Iv7KarKh>LGi|BR#*O>CuHC11zh#EN;+E9w>Vgy(`TcPr%E*b--jT*B|?3b~Tp6~x=vSMp`- z75FOl8hjmFC5w2T*TyPB%n?PrIpQ<0C=5ji&npgRF>kr7=hSzW%N49&!|;_X%=u@c z1gFKl5}w1lOfHx8on=G==NtJV_A>SjnP1C7USTo|5p%)0qQ59fehIInXR|Jq`JDpJ zQn^ev02?^@oo}iAMt&=w$6mw=dWF3Hq98Fqlp?>RSIVEa-eMpT?fWz9;iL zncpkm4HRWKE$x-@_^<;sxm!YBA!mvFg7pXaB=$7+16AM4d|rO?^AUqYS@O$xgZO#| zszK_!xF80p3*w^qk^CRzkMeQsNvs?>WxaBq&ia#l6nh-|iTxjCd3MTq<-NC312ygj z!!StwOwLd8XZZlV`k&>)*rQkla>{$Zu=BJ0Ro;(1i2cg-FLEY-qTY+mY$eR9n@lf4!0;5r(TfxxCz-&c5c%w&qyrz0cu?-CyK)RA0jRg+Ghk4Bjkj zHtT$AzFZ*ZlS3XEozwz-?bHYAB~LKimxKwL?m1!b6x}hLoL(;PQ)`x$ z0nFgNlAl_yE!TodL|5p^NIDT^;#|@ ze}T2onkPS(%gJ2kFZbK3cIr9V=f!jTyco>&3+`f0HZQvubFzCmz#OnFqH3YF$ofpq zm5Z#oa-Mu<4^~6eGy6HKMSjegX??;|W)g3}H}b7q0snG;hBecAD;HC{$XdzH3V)^F zMzvK>?PvB7aEKbJY$vOi&9mXL9EWQge8+p&bDVd*tlko87h6lL*>a9tV$G4C$yG3{ z^jG<3r*mrUU-wLX=z zd4hDL;{;*~A!L*ip=8aNI1dO>}->jh8kp{gENPwj@mBl|J<*lrNi4Th>=s%}t^ zwGsObgGRwa`;ondC(rZO2cP=0z*+uma5hifC-#d9-aewDcbI1#5~kK!by23)MRf(c zst>_6)SB9SzcbhK{Li`m+@J6N6RZhLZ3CR^gS}#(sOaq_DtSlXIV_HdDb`f04qwqQ zRflM*8uOJj3K|FZ?FV+_;DPwhK(?62sQ?v_@DZF#9mR!+aof1nZQb3M(?PY zY<*-M6(3nsz$w-dQ9Gy;G*wODX&n3&{0+kp&{%)~HWb%$tbyU;}YLi)u zXr`Ky-y~=n+_Uf7$HgRTvUQxCW1?nID`=)_63tb!;I4hoZbnYi;7_=x`a54KXf1)Szj_fLum)qm%tX{GNUb4rU!m{s@1hUnO`i80o(kR1JpW#OgUi zjcfLGdni}e>~S!RHO3j6#TGG;y2<`1@<;kZjG@MLd%UqpY!>4=9cK*i2XZ=q_{bkk z&M2@_P&pXwR}QKK6UZEock2eRQA{v4icO+FxgYuci7EaVGDm|IgG#|fawZu4IGN)2 zBc}Re*&hQ|2r34XjP+uJm_*J*V;nnU{mI5Uv0hAOf08lYFBg;##{1=i3Sfm`od1#W zpI9qCGS-T9;5zaqkTc$&!v06bRO4UqpP0(^6r+Y3WDEue7pKL8MYpSZ8w+^Zj zZGzgWuhGw_t@;`L!Tw~t$9bFJJykj=1GWiD2X$0$qmNNX^)dQ_eaWjrR+*p*Q8uWn zdK$fqx~iAa8|+O+J=MeLY1CuCuBuFK*`P8}4lEZ;@ITP{_0~zUv)QnfIawHTao>B&`N8~ z+C}T`_wc(=+gWR=eI0xgwA5O$cGW)gyZK$UZhm*LI~gssZ-Q@w7G!-Be5iHxKlDE& zr>oXLbu~UT8mJGAZeTZ_QBhS=6a9+BB)?mfsWqqi+n_n|9r#`FebAl#Zd!M(i{I66 z#`*U_GvbG!q3U9EH5$U%KsD8xX+H!#$my>2&^r5F{3hK07&OtEvNqP5Xg`8K@#jEe zu6_y{si{U6qmlZTS5+f;8mdN|aH`gbe??>V8>uF0CVxjZ;cv?|qKUd4&Xi3!ZLH>o z<<)25+_0P~ujYiGaW{vkpyq{TRXMO68MDJVVFmR$JM+R>VMR5`pT&JeHH(u9YJONo zl?BU^@hRt%{7;Dv{sQ*rho7+5!T*Hl=r0UQt1@aK`wPOEVMo7{KQrv)cLqPET4}O+XcgJ108R;~hNal;rIq5Or&fubir`1#l&~bbHMNqQ^wKJ`Qwf|LeiW8q zuclUlsHIh5r!qJxoE#Qsua;JvsI9%nP8D!sI4LZ~UTv)yQ3tG})zzwMYP^73b9uo ztgkfy8)yx+f~*ZSgEhipYIJC5jd=YST6Qf5m_y46j-}q1?ykK4} zADBKbyJY>#8?1 z@YhuwrH1QjAF3jzHeG4N3~+`TXlir}ZNa!<3)2glmRPUPPJO1rG;J}ni<(x@XpN6d zYv#Q*t#&LYm@_urh5^kNO*?@~k*3W@T}wk3uDR5-=I9b?+8vZJVL;0jHvh9gLos_L z?hq@rD{z|HG&P<7fBTS6v_Irs`!xEfX7TmRCT7tW^(pI|g!`yVirR$xsK-gu<|f?# z@9UqJa367LTJ-6-rrj{6(6ez9yn#zZ)E{yke}}2+mJ#)+++yb@t__p9x@|<=EZ2;W zsk%nS$6Q}$y<<$IgXIpVxA9B3##ejS7*8+9U1I_rCU-f#gO>bN_V2NO7sdMMJGyT~ zJs9`dxrdiQ)E)7_i25iVuzw$y>M>kBGNMmr9~q!^ESAE(i@ z%PExeJI068Q4r}@4_EuyiKbUhpoG6)KZ$aFq*FaYbs$En1MKhD+sC6%z#~QIk?Np+ z9Oe9j>>psVM0ONaHzYn2WnB2@@7qP#9aU=Lp-! zN2wg)DD{}W<(%B*4kLBt+~nm7uO-Y=TqEx)j<(UX#pQ$k<3_@)#Epbm zj2q-%N4@J3vlJH-<|*=pkpgo*s`Ao39BIyHrTVFHld2mic16FT7pT~x=MN)Q!eDnEU|?}kT=+X+(@x5>O^ z77Qa@;(}xr2=64!P2A!1wwZ<8BXkZQK~udDIR(SJoZd0-CQMiqW+&?PjTDLRv2)kF zmoPn1gq^}+kucIIzMn83ai9HrW@;^s)-Rr#=$|kpmMOfWXQG?8L2wEctOmhp^tGaQ zsAtT3?BCVz=^5$#jpn~HgPG~hy{%^nj~ci6FMe203r`v?trqEhr_xeu{lQ3&yCG~1 zc(+*}o_fSt^FBQH^!s|$XM10dx^r*wsyV_OS2VK_O@|%U)4`KgONWMf-*`$bl{Ns3 zw7gTI-#sYa2+rtzYoxLjy^}o)o<+Uv0i5tsl}<~Kc6%Qt#csiwLQ9F_cVqIScbCV} z$Z8y%K&LBu?|BY9ho^9z;5`3DAL>!>?n8K@>9A;i;f8(_h8x6hdU7oVJjscM@h0#z z4w?kVP{)eiZ(aZ|@Tcx07#`}6^r(+F8Gq(CiYL<|ecfbQa_*R#Vj3cv9s6BxN^O(i zF`19_$9mL@`&f^9dZXE@)p|2dn+DB-qo`&j#f_~oQ(sZ%?GrK|Gi9}!NeAYv^!w&j zCbCxR&B<&QG!KrTl$8YEwZ`!zL=z^!Qc=@_{pP%{jMTKAvGY`arbpepE!k-iv^4K)1T{62X8BOS_Z9xNHt5xbbu}88tzYUwc8K>J~yD&XEGsrcP^-_5u6XBIkoe!ox`o| zK1z0{!Uw3=ox<_$zPXe7V&P8uc8Z1v61?pWBzWE(fOEea%{bI#CL#K_1c%_Y0^9lU zLKscAT?nH&xR56XOg%*JJx}t4hxF9YsIDD^?EpPD#puG{LB~$9Q1MQ(N}!1M!1t)R z81W=bJ=A8Np*DZBpP+u9c>?FShjicguxy7TX}Fz821Z@had=d4iQ357DVnxBj*Hwr z^Ek1eDTc~SK_udRW+gCs_j)+NgYR&HE8k%_57F}y^>S~6J2_5VXPCdc97gkZmtnhv z&)o5Fzj=%}07i;xiD63=9D(OBoiE$m6!^;>3lExC!qd#)~)Q zaU@L61hyU|Cyd}LPFLw)>6_@)S)p&`J6geS&~tqSu4-G@*~0hv1yxJTFU&*u=q*CQ z^$2*B?|KnGkygPX?vI8kVN1cJb~Fc(j5%%tjOHnp^BegBFSHl>OK=5uU-PW5z>V|* zeF^6m=9lIHeDS_C58|n}5Y|?~LZUSoy~|Fj$Cye<%4D|*MpGuKcuGp?6zCP+TWURx{+c<6@8J0s z@3d%|?@QtYxRkr)=05!RmczLW{m%JjnIJ9sX_)?g#T>-F zp|7B7xw*pJgG1j6b1x2k^QbHv%!8v$kdE54Ooc}?5lfghydEyWdF=##Vkfx!0k-e; z^qi&xpEC!MUXSJ=BHhxm!CazTuoC7K=1Oxn?tVY&QJ2(@RQ;f@VrL~Y-_NP}iTxkJ zsGH~~eGT12Uzxjb^!tjORZM$7_cQ1j^=HgY{7lYIcrQg=JztwU@&5ao%&(X zGwIRv#4nuwjNek!|MM&O3rt0#)Pn?g?`f(WivTf@8RADcrRb z^WCSF$Bg)Co_iS@H&p25S*WoCRNPE|L9|+F?H3i?bxp-I2Wp^0WJHrd`oX0IInj-Ja97iTFn&XK6 zUH*wbNPUcI>mW4^-Pb`d3{+F`VEYW$s?T7#NYw@Wtt@8H2a`ES4OUZ8YW)~TsM-3* z#2j!A*_Tu_SAL1ii+o};)f|kQ)hx~~vwsQiplGgqIy=+APjJ(kp5Ul8gX`&fK&m)bgEj4G3k$>=jIoyer?RCZGRt-W|=^|$und)1%%e)NPLz_}~x zKs$iC{~#Q!>cLPK_5ZI?h^-0t*QUj1Y3-FobO1Z3n9^X)gdJiu>)qQrhznV7>kyu7 zQIFX{HGrq|x9W!jaHOgq4#dZ*KFsy-1Na7g*BWqtW7=?9D(cnDtiKJT$?jg(VVvKh zuCv2xptT2=u7U6juo}QqKWq^8$C1jR%BG()`gE^)7^%EghxJ=Bey z0{X$&IP8m0mW)0#qoXqV>};sDL+u22QvWiH=EPqzG-Ia#kg#5-~lduoYSswXP z4YRi6cr}cwp;ptd7k*ex!`?V&H6^D>=#%5o(-?iqHr(2V%hho5hgr?YY#KHTd*X@} zaO%_3nDB{!wG}6$5o8Xxnuk4b$ZAebp{$$8 z+~{xeqi)9a{>$*PT8~@q%doc{b(Hm{wpT(Y`G-~y*t%IG%u09-jDT&pxtXd>{$@Yw zu8fofhN^Y`W&F0*`B(73T8B^WWqQk_Ub3jqyqnbr&ZxsY>LMFyR>WUmBy1zl2#7xQ zi_P6*^N99^Sa?x7ruVd{?Rn#jU^`S*QN^y6@7{~(2PD!`wzd}O{yPkedz>``pTky@}AZ<^0(r& z8}%`cHp}5VFdF7j%(xFUo2mX}Mt$Q^H`>2=?`~565}Va_^0(o-8}$}$_oKeVXeyq3 zqPZFa&uDW1RZ;hN)JwJoAKuMs4Y5UyHOt~JFqWJ#<_;LP`_Zg^bJdS%p$3vafDZAf zuk0WEdAF#4h^=azSq2}0anz1AcT%;(-|0u)iG%E@e{2x>1MTtTj5EiZrEnG)Z7+%@$ilM6$jf<|JY#i2iX(M$W34Znd8mfe$>IZo19(#5ON07c^&neO*Bj3GBA0BMR{P4_E7s1Z{LU7Uw8pO)c*D#XbWOd zxAuZqCwqQuw-(T;yBl?a7GR`Quv=@vZ^dprdit9CVB4#GPG)EObMy&2*$ZP)C-%Zv z2fHKK5tjSfKmJyAALf7j``T81i|(Tg^SA$q=RU-bXSWurd#JmNuGGz&srEeK+b;cK!SF`PPmlX32Uh4qEFbxo=bEE zquGMRu@C6zUQE@Z*j?0MMp;j^)%XQJf&Z~~5QYO_q*t&*Q~ay!4%~l~+QGlp-VUE? zzvD0bl>8^!XXqAwXx~8-W|Vb@XlX5pwWDKv3H*y=hhR9U9ZJwK*pAoF?QlDBCwvCO zQ|+1d8}7hgkRK@)wxPTGi&$HFzi*=w)6%+4v;w0}v%@eP!W-yA)CmqJC>VT6{ui<5 z+Ap{UKi7W6Yxp^A|5J%+ZEeFF=uWtexEmg!>TrS@Ol#|=7Il%m(0=xR@n2B;9Os;E z+TCzzEb1^{3g?%xmz=)98z@pCIGUh}a1@3k+Ok;GCBBTzrLkk29@UN|=oKuFMZMz7 zIb9ZerTygp?7xBmeHl)VfzdSjidfVizJkoeGiAJA$AU)m|f*i8*veerh51I zr{Rgzh9gbFW2grgbSyT{K$>;?Dw-}!gls6YR%8})ccj#NVv z)P`rrj@q-)p*(8OLFe)bU&CYf49t=K@O1PEbHNtP_O919Xwf|Hcm7jyp14ol%jmkC zwWpzEc$UmFXa^s)Ka1VL)2gYRoBUiVw_2;M({ihIxCK2U|Ec@Tjg(t5sm$0obPJFZ&C>pjJIrNrF4?cye}&6cqytls{Q}I<{)O*MA+R8y&-}$z zT>Xio&03~g)2X#VI%ZD)3)Tkdakkoz3UM2Gz-}#%IFZZM5%h$^y;v415c~N&P{hk z>@XU|H{A8)uM5^QSDRL~lY3DWZU>E*E?$X};YMa%Q>%?+ZU~y=V|9eyn@HUy>cDx6kJTR7+soak z4IiLx6}rT$P(D2AT*lw(B%CLlsMF?@_7`y)JdI9E2e}Jv;SN-_mzxsiTQ@P^no4cr zSsR1>XcUi+?I$M0PC1uwxjF?K>cq}Pe6LQkbIR!`cc3}kQSL-@xFc*GWYl$YhOV3B zOu}x4b5pR-nSiq2KD3A@#QxyytQK|MoT2L`IT@W`=qUF(6H)xziwg0?*csk3n}>69&N(}RL`=`@;B-5^1Btl$Du^>x z^A*=SgRB1P;EI3MkNR}3`cco$SRASvGqEs^bzp2zY_~Iz*y9WaBMpsRXc1o{|Eho4 ze~tgtW&a8smx({Xv)XHR{s_)$r9GWhx3|$-H*C~F2ViA?N8nnyMOEo3d51+#$|g5Pahl`65D}d@Q~O}REQ_wV%3m2 zh=x3AG|y-Xj$xgM*HiN$#(IG<85gU1Oghw~vQKO?D#VfA#AbVVY#S=X z!(kW}8^QH(Fj5l!NY2C_TN49N=&uY=j^jDZi~=fStO~3h>G@j={4b7c@2Py}ymx{(F$PjO z056VXI2DhDdR4(1ON_C`aXgk>j`ahT@0|}$@LtCUXC3c#45EIZGDta!|L|b)AZ4&} z1aIMwPVn}~M=C!!b=SG)1k{W6 zN*khsati<9d(J81zB9%cYxHIYCzx(%$8KAQ6@iDwNw{wh^^Sk;bi*``gDIPi%q(1?l4|R+bH(YV2QDAoQ0uB+wJtfA zovXoltGga}fOKcKn?9YcX?P4@bS~jPe2I$d90#7m7o3aEHjb}bb?t-r2G_L@;W=E# zK8*ix9sJx5TTLJcG}fC0p$8auc+efS; zLFV_THok2~ta|9z<^9`BOyyjRp3}J)J*RU8wadnp=n0)G(Gxn&%?6Mrnwt$_STskU zYd{bfZ#5z&SheiHg`*aJZiAKj_FuRY*S8PgPFx@Tdc1Rck*S=ks9iA{n!!v_L%Jte zEzoRk*2KeYh*Fansx+XtKJV5JV_xGtF@k)7PuHSnd9I;w)o1`6V4~H4XlFIF_v1F) zkgf)}um!FfHSEBVqXw>SLvj6Yptmqvn)M-NTu0%WaXorMCwTLAgi+sY$K*(T{M_4F zt*B{fwleF%!l-Ts-YM15YpgV~_u)d^h^sW@J=^~D--w>mX-#D-=m2$LUeq&#nUs2X z)3>)8+k5dJZcJAr`zDn)jGNI@IX9!Ha;o9>)%{FEo zxENKbXsT4j)vbxr#NLBPaT7Ef^PX)VwAxbB25LZU_!mv>T{sdqwRc;4$a|=}O-=AV zZ7_+`j+(Y+JF^y?i)K_dweK+J(95_JJ*{(xn%hQucH2P^s0rtyxxLfcWi_X=nSGba zJ4Oq82ad!oI3IYvZO4naC1+aT_O=ZN*J7M$X%{sr;r3S4sEpfN5u>P4#ZG3_f*p{| zs0}+HAPdwnU)d*lllB$X=FR z4o&B{4(x#BXeKjW+QHklFY*38WxTP2H)h}1!F#rE(0y$eLc0f3)D`TCc5$O3Zg0g= zD~9`j5@R|!n2SkF%!D#f6M{erG?N=|(RqWz?`hs;et|RaX(p=+p;M6P$y{{>RGvq_ z0sY(#-nM>D?HR}dHR(@jREGkP(x?GPAQ9R#jd!TM#ThtwtM;88yrY|nnv_OKbV`uR zKT`R@{%8m9=%%4QH924q z#HYFkB!C3Lgbwq}HT1khP3Ex6+NGK7E`vv0JSuwP#~+_H9!Gbf3{*AKkSoIoNNZGq zKJdv7-U0rE{ztnkUGy7)!&?|NX^qeJA>Qx(OwA{|9Oug#<&09e!2M$%5XD`al5LLn+fhJuz~Uz6ZP0|0Ve8k;0wsw1AKsG?IE7S5;NbA>)CxII4q)ljPn)h8EI-XcAZZISuzN4A2RtW83HA}rMj=#1Cn z@m(6vQ9Pp(RGvgi3`kbKeh$piLGk)a2r;&`?wRU=qTDaH0~PXhCYhVUy)AhR4 z*HP*!nV9LWt7K;SdnPqAbX&WD=di8a#Ld`7&C=>oQ&({~Z)>x32l~J)Drf5Tm5j`K z*Jrn$;%b3ku}h5uSJE~dV>Xqu^aj+_hfI=zY2pS-6tlezIc@+cBt28c`8aN*&M*K_u7iZ(y>QK0@v$^6d^(1O1aBDp# z{e;U`Qkf3*uLQ)OiP|JB(wNE=*jJ{&hQLvsL)UEe2z9^6M_ErvUzq7WB?VLAr_ebm z&7^k*bid+|gQhU~^_9u5z%zM@dIh)S3ED(7Cujy-h6x-Q#$0tUtkt>b&ruIcfz!ZY zTwZ^vr%^s7%|d4;yuV_QfX2gVGmXj2f?c)ese|CF&ZBp(dPe%peD@jYAEv_3&~;jx zuMUL4I-i<(>Nt8VV;p2S)0mCUEck#$p$kny<(fT-nXjw(vj&shXVEz$&C!a$44OmD zZ0L42KMiBGahhd}C2S_0uHolAk%_Qt$0EKmnPTwTBw=d0(?IV;W83PA;$s}+U{ zG#9lw+CplA`LF)4R?kbp#P@kAmejF>@HLnsr}%qUZCc@G@tYHpqdqc z{4!rF2q$PUyNj3z>kD`Fq7=-7U!?Maw1ArVu*LF2iCIWq00}G~m z1(rppj9!%qt}#$B#-LsVtzI|_6lKjzZyqTxPON))?>Q@)rRjbP=VBBc)rhKUVQPEf zDbNezYB_xvyuWfNm(}ypl~>A#6YFlNI@4C8;9QKNrxg9~$fa4!Q(q3}fFUsZ%IiZR z1{Ol8H_igRA-5JH`a%oZffs9jVi$QAiZz(R8mZPGs;dR5>Z_MT@jdK__xxm(MEjju z0nPGy0ebUGHJQ{Jq1Gg7s1^0W5CAK(TR|_#ZomxM&RUC_nrbbku!gIZ^g(a{D^Xby zX3%yj3gKe8jl7LdwW+D4)@Ckim|9sM0Nt#z9`FGx(^Uy(&{pcI=>6fsRbjU>bIJWV z%B1&$7nh0Ss`_IkKb`}Rl*dYt3*Ztk$1M*3VvakPb%B!s?$1K<0%xI<9(K?}rLVqN zeW(=VPx?@K#QH=D+ykDV^H`bhM8Wx)?*y!$`Ao=0NsH)O=*)IY@Ew`$&S9PHmgGA# z&n*T=V;poB(@_Y4wSV9iwC!eDEM0u(NZUeL2+3rPY7I8_M?-qr%F`wRf?mVVt zGf9ilU*s%yBBk`wedU3&RDGrd&H&Gpz*XQG3Qv`}Ov`4H<`S97nfd8i;zUU4$mt*l zEunX@Gt<3<%j-;c7V848GT&X`7KYiez%2sf;~u($$oE;FqyJ1<$nFAnh8sA$&Twb4 z&Tu#3>^g@j+APvi^p`kyVXF;N?-GO67j!*`uoid@EMqsAoDGK;G#!o2(jvDY)Q?4O zAy^@cP+sW1r1FLGQVHA!?!Z$UtllApsLP#z7PQ<6lfud2(lTc;y^Gvw?sRmf5nH6& z${l5hdYc%kzET38fmi6fR94Wt+?h)47HKN6mAq9dEG=>K!x>rP7Jxsp1hvKPYbEd& zc&!9Z1+P(frL3fP1=F&r;RUU9(!dN_O4kzi4VABzRh(bxta4I83tGncrS38}FXWD8 zZa&BzZaqJH;*OPjV-dC%Ywll|S)NJSlF$Ra0@pxJ4ey?}kd$ z!42aE+%^L>UG0ZLU#A~)t<#wm?1NfwVkUVeGq%P3DehFaxIfh`EER_fGsP{%RZ99M z3WjQ`*Ws-xDAvW{LS^lbPCsT0r!XzspP0rBVQ+K-c1&TZ7*Rwj?N4+kxuwx5<;(Qd zRV{Q(@-=8{!PMa_W(a37Ejs|6{?P=PB2rPGkjnVu-3e|Pe}X%aJP{RJy$WN^rq{yf zA{Pu13B_DwnY9N>vza-Z&D8Bc)CQ0zG3z>zm;#k%JSs)}@5>3${LlF|`&aFBq z+vF?o*9OrQ%qmV~4LCI^q;mc^cf4B;g|fb@UWT#eQt7AyJ{Y;lxnZLSL|%0;U4xwR z{#bXMTb{0fUy}lsP(ZFpA^qVc;=Jk*YJ%y-@l3N0AtpK=ny%`pmteRBgqM_3K_Zn@ z0iE)G1%I?V#;xFwamO;hIG&!N%&d-gLh1$BY9aL^Otuic9yFEF)cKqbsl%ul>I`G9 zZ=6%fALWjAE3sSAkD;DdE+{dm@zvq%4s$B|Bi&JMWojzeYzqbRpxfYUbai%zf_cN;p)o%x*wz$?OJ1nAo_sF2}odxx0eA!d>ZZ4Fz+kTSLM0>Q;Ch-JCt>@5YyP4fC>* z?po$qBi;0T%HjsRl`N=bc4Oi7y3$P;?Oc&C+5saWUqb?G3$%_N&R!G(mParPna+)L zM>$#P&Em$y!F45hr8~?`L~lZCA2oZSc(h~wF~UtpWdt#rJlYxKWOD-^N;Ws(tz<(X zE1s^y+~LvAuEX5KC?v8HM|)rFM`0hNk2cIp?hmzPUNQ;i6I)55T`$7j2zQK=9kpz( zZw+@xkYlj^Mg9Iz2zSvDZipD^CZ#^`aSgmL!sr?6gt_6YIoyDslEV!MEIH80?jE4` zFBlfBnZe8%?7GS5N{VZ1;CGQM+6Uucs1=iy2dOy_O3wMfwKbrw^{z7E~c?0Z@{`7{dV1nBtkL35KzZ9}Yx`R+2$Q-w0xt8d!fodW8 zYq_$Bg5c*8gXz~?Vs6&_TqU3Q6Rl05pQvt(p6ssd_mcwFQ9r4QU)3Kh*_LAsMs1Lk zQ_LlfaB>nO$-xw70Wl@+tOd}?FG^fX^nakWIrM|rLjK98VEVhNKSZ+di5-I4U@3=~ zQ*7oG6jQh<-GV3-5WiEq1q1puA*|^A)le{oQa^+#Zxc7yKJ;hugGunJes(bjz1fN8 zu^cO$8|Ve!z7J*)z|zLFe$Rq)6&T*W@9ZP zCUuj!MNlX#_LKt3Nieyc#UFvfaH*)682{CxViJ5=i&9xc)KSoU-CquwVx+`>OstWT ziks_5>PJY$#K5(+7+pn0!(Rrg!k|+3M^QOaGX15YWg(OEhF_e@V&Z5?#=&(oyQ8Er zl8A@r7)iqSaSZ22Gf^&b)QTL;0Sowo_HeU^S;d}iCNVQPvzUdPMeN}&mA-`j4K0=a z4K0zf$~~kka#pz;Gvit1?o5|=ce9Euo$hWA*6wag=TN8@3O(J$)PD^vhEw@(Xqog+ z=nMG^Dw*XhXk?aqN?HBP9QEWlH{QpY<*dQ)63SWSY;sqo&U?EV#Y|#v)Oxwy-0u7y zb|Vgl7D-=2|B)B7E=PG8~{9ou>Xax$(p-p}YeGX+rC9j)N&cvES?#yg^4m7jNeNpS<_H{Fe zQDPVL7KIi_-$LKX3t3mvy8_ze$Iz!xl$_U%??%ZPS#zR*ira`hISIH&RS5c5*wr zOG2xq_n{Bu5A>&(Gsp?u+;T@I?sLa0j~KVuU!*jS$m`Yo#}#x1qK4u95P} z?UP>%UN7wrspbQayVle;q<#oS~*NMl;UCu(LkxVSWPy4 z%df_jO~1C>)@|q3=8CoCU>1I^G>w=i%|;C^Zze3us*orxzbaw-b>uc~Tel8fwPg=w zSJ9OcVo5RZyDlM4Womw&G?kby&7pU;H^-X+6H`-4im647+LB@w*p#+kg?JIFE4Oyr zxOLI2BZpAqrEDdQoK_BI?dMBVhy~JI6y|tyy?|m_89LyLP-WsJ`DN%;s2&P+;Z(MA zTjOJ$1{GgPC8y?JpsD3F{4cYnq!v{ojX2Mn1`Tr_I&-}k)c8szh=Z>}_35oA*Oyzk zE#3NZOShHF|E4QxM1@Ez&ZldhH{Y8I2UAwU`1z0(MM*2lM3@*8oft|?C54<)j;W-S zQ$bC9&Cg9mbYF)mLQi}ZYJhTmc>xN+)c+J1m$9gisl-x}%PF8(wr~TMWiz+A+fZ)q zws04Elc8ZQq;i25o0?ckBX%3gi@b>tEf;x{pk6MbW}z2{-PlSTC8?ZDj-w=#lgo{% zY(#GAHggwKzsQTrZs2{LRE|qdA}5vqk(0>raJ^2<+E5g6x^5^+N&~TrR~{l{S8^Bc zfHJ}ROF5v7!%yIVG9HJ4`qaoueX#*+eg5==-9`-ciAp0B8jAaszv$RcO!N-YbwCN& zD;4CCb_p=@`#BGdPBeAjg8&~Sa;vZR1_9^?7 ziQYb9l6OcMi)+Clln*Kab!ENOiP#`@N3EMzR~+IFb?b^l-A3ekd}@MDV{tDUlf1pe zWOCrva2TCK%3);;UIzi0WdnSc4e%v9dI4XuhgSw#We+sFdv(ORVk5UHI!(l;;x8Pt z0}jhLX^*m3nc^Km;jnT<8HESJ5oI(E2|c~ikSKei(8H@uXJfavSckQl_!D>QW+*fj zk5YdGO3OHilkL6n5GUJv9r)DCD+P(N7YaSST4HUnv0IC1;x-q*<5}HY{DJFrb99=C z$51$`98*T%rEp9ciPJ(mue~=x>g|<)P}$on38At#YQ4OgVlAh#YqOzrU zf||dT6Us1r8~S-gp-=Ynib1RFM`d5{B)pnmYaJmJXb0NgVKdeQ%H_4RT3+U@zIGV zt+O^q`~GcGHY@w(zv$Xe4E9dQ&AjI1=BPMQVYvv|WlbPe6f21dP>3(Bw>BsnarN7% zY$9*M4{)EnUmoo3BZhb<<)*M>PNH){wxuFaDQy@|MaV_v{$4_=>Zh*|<^13K%i zz4AVJh_{y*>YbwZqYX1If+z8EGs6F%8KR4<*3-q?k3y<*DC9jvvR^-d zl;3Cfo_b&1E$@+Yb7mn<<#|~1QJL4etKL)h%6HY1$|>b8M?<~4>QH`v9;mzI-SPvv z?yDK1xmOwBUiJ4fC{cXM6ivL!#1%6t>ER#^@X{+8STjent1?Hkt1?rQNy)|47UFEa z5dX#eTrnSc4t{|7iFwu?^{#qKd8qD`cgYXA;sZ4&wTo~wUxdG7PGX5wfcpH_ZR$=d zx79nWkJKIVPWcgC57kJnKfsG5V9;>&%y@_lgi4c6iDb=z#uBR_3I)i4Ti`AAw6aRM zrQT+JtZtWg$d6Hbq-KpKSY?f-Uu8uni&6-Wzu8tHqM&tCU8Ss6ZmPFfpQzj9?eY_P zAFB~cJt#R5T(h2+Et*}G4V|n?xKba^PPozl&Q7=z!Kduee5>r#WK#;GT*xYnli)1t zhI&(7t=u5iC{NX`@;3P?`cKp%>=w3);Pf}s3PZ1mo8-;%b9J-4Mb4!NFtBn_pHnGDO;M{D z{(#f17t}mgi*sBIcj>@0Fn2WTDmV4Hl$Y$jP+zJW8utYKX(G~}m$ose2dqpU+=E!@)U>RQEh*5aJ$Ivz?cab5LM3pu`XMZKzS*LG-G ztnEZrYZsb3wN=7u;jFxhI47@1ZJn@QNTsA!9A~q&#d08=Znk1Lm(?q33>184o3>rc zYHcI3S-Vl#rR~--;<&z2I47T%R|>0GH=wXy*dU}-QYp5x1s_k_*@}aw4f%A771Oz- zURGnG8N=DC1rGXKwZK__tG10#d$bHVrSH+A@MGVD@@~z7f;!2vh{;wgdSg1VoQvuu zb%n4}I4`dt*2x>W)&^mtkU~kRY|*xAIjp_t?9rCvcC$`iPOO(V3CWcd$|hbIz*g)B{>LKI#Xw2;A2XQ2&>< zjry&^HX*T+M2SyjJm(-a2ebsvY4wbnfHU!(?Ls0Yv9g_-ZNedT4{C?BFkIPp2nm%$ z$_{q73p+X9K~A6~RHg~>l?3Dj%1)uKv_z;Q)s+?tON4>;25o>n&|a@?(Eeze^P9|# zVdsygLQ3s#4`9DPu~8dD%|LsQy-r(?BkFHze`&fi)%wMe&hb=!a|B(Xv$nKU*eKVQ zHp(y6+EN{^R-0H#eyP4v>q(1*#X>!q-6W{`N+#AF+wN zN!zRq=8A*t!S)($EyruMb@-(g$4&hwUqx|?zxFtSF6#U>%js+Pvo~vfi7na?>Id6D zv=aEQ|Ih*t_8;_>u)qsKP?e|`^_pD!wOUhpt)3v);!^`@fv`|$z}Hh>sv*^sPN;qC zzV;SvC~8COq4sKR4IZgKwA7ZYix5<0)FizjT@9p$(tKfoFpQd^_Aq;uwiADOSNU1L5;4D=6ICdT$&-w6q-vjg<0fTRGaz_=&L3* zhTekR=2A;?3-WYfhER;$QYt1*6Q&F4)GAU{DUzH{jZ`a1l{u~~Rgw0p-R$o6UbVa3 zgWSX3qo&gT)l%xI^nY+hO{IUqg*AddIZC({>cVRWU{!}O0hvZkT)o1I4e1`#!lnwC$QP{;^zubfm~ zI;eKCJKG0QIG`rclhT`nSgeK98>WZrA8=Jot)@}G+nK4)1dp$bR2KeTS*e_Kh~9(h zA+>|u(LSVhv^&{}^~Kr}EwP@2H9~)fGirqX9_Q5vbi(yiYHD;+5kKrK=wwz8(|brw zq$k#wXo-lWmFe_s zYALBSyuQ+~{Ekv{L`~0bq@G@Xjkjug{SDr#*{R6}(XXUbN;*c(QT3SG)^2BKpeDVZ zgY(&;oRyGDN;%0n;E5HNN=UKEIn~%|F{!w;#7?QEQghk~^n`j&JE5KfukrYL0)45S zLQSbIWp|1Fx4lI@PTs6;!KFN*o=DGbC*n6GJ1*r3^<32Fv={T|H}%DQCw_3egmp2W zEq$4tTuq@aLv5*j%s!6NF=DHF0=2*G6ZR%`vziU1(Rh@Pw#Sgi*kkb~kB@F{JDwh2 zUxc2eFGpvYz1&WwCRdN5w3WP7-KL&I;e>tC-k@&ec%!;W%}ReOT+6eu=0PFwIghKy z(-+!{&{;^>xx^Xe;SjVXw54!1X(9AK|C=w7p*4K;A%SX8Kx@TiLD2t?f2An#a-el4I*}^!fGz z6y_5z$uIFTU4_m{dzGCS>faf3PTObfb?SOG6Wwj_HIJ?5BgfQZ>G|zgdTf23J>Pz% zt)_mJz1mI)zi+jj2oB&`dyTr5yjERDUWZmjyRCgp&1h#rCnM1o2lSYz%%%UeHrJlV zx(0>S_BngCx<);R!dcwVW9kLSG4z=FT6WjiYwZMTLiIc~=kQ4P^%!~~b_?3;IKP%0 zA3op(dzHGHyqdbg)D$9f!(Ly{?mBzD9S;KFMSG>XioA-t4V+m|jtlE;BYA_p(T)QN zZX9`|J4&W1=5}m`k3^ zPHcOoJqt?3EUp}zh-Ei}0C-GoMjTgL8{D8K2r1>Fh|m4LYrjlFP1wGiBj zC_O}Egg7w+^(K)1mZ@#&ZDX`GBJ6Y!CNk=d?!l+XsF#52ci65-Zw0u1yX`%8JbOBQ z@rbx~W5{aD)W*be@^W>B+Rg~KBkXqQv^6SeyX@U|CAunVE~<|11_6CyI{oqOsrEGT zG(I&l8XGIr_C{Je%x-Ul+2Q1HR2+yEu1?lHh!az(uB`2_canG7yU4pxufmziT0{C* zssVp)1q8sf^xL+lhxCA3;X$I93h^SLJ%zQSk;YC-PHT5C5^*M>oyeZdS{0otT2*bk zy~FNgq_R_!Q`>3CX{b(2O(Hw7J&Cm%HC450+BSQ;U7cJ_tFCRex7nTP>SQFbCsLJ! zNQ@u6w* z+9;Gqnxo7@5C!9#3CtpP5_A%qNlXoIYzQA`_+&M0%VSpX{EXtN+pz<4MYwd0vZ?d0V6d`gOP67wshzsvSlVv`+^{_4W+ z3wVJ;&0%ISZ75M(8-vbhGp-rWOm6>=?)N{^UosSun#oKRe#F0U{WjS{%%Ns+Z3t09 z8%x(1bF7&UPTyEFKZL;lOZtn0Rth@~s>$u-C?qqJn=)*OWrZ7{Q5|I*Nv+MLYpBr~n~3qnC! z^EZTow46_4hH)mXsgT3SKOrn^G-8??jEzPNGp3o<`3Na5tMf_E;)LXWW`8pz_csTS z2bi9m+4-z*wKKE(Saj6_=y7EAC5ZU9CFZVV3k^7;t zo@>Q2*Bhz$U0QE!;L~~|mYK@l#ML(%n=o(j%}s`H#xU2h-`QA4bTKw_eiPX_8O0vN@?_>5gV{ly`e)(W?h-u3XYepxNQ$x#0 z)FcPY!5q#zn0-0u%?{zb4?SzSURPr+SMFkL;fkA$HGHl_Udw8sH^hu`GCJ9`oX%UQ zd^u6b0q4B8*~g59LQHupU0aN;hHH9e1}BQj3`BNvc9@2_oHtPUa?zU;&Ur7hw;7w> zSn_JFQQ26{bt)O#=-o=TO~>5EU({W56?;{TRqR(bwsU@)k>1JR;SCIblpp)C# z$?gtgr(v3wnb&ybUcm3mM}1!C z=-sGDK#ouDYIZYsQ?tw1ZRn<9=69Y$^vh3uK4%YSb{l(mT}?Ch7@Db@dpX`?%p&h4 zE2e6GHCDiq`f4m^9VsXQ1DSQ>#u)HmjqU&Z$mBI<-))>HLGD1~rPm z^hJ}WRLD`wqRCTBS%(S3q0tYECen{aZIm!tkRgdzb0(Wp%xWl2HfuX!DAguvIiJzc zAxAAm<-4(jb*L~*Fyx_xNj7Cm9wSIF$H$;ETBzzwF{heUovCIgay35Hanhn!hp6p* zLhFhC3D%JgU1~9UKZx(f5Miib$zuf(M)_FO#^9e^)#+qbAv&9NQK;k8b<(hYr2nb@ z(Rd0k?;|XwC;Crxen6U9#5xX}WlM27Q`zZa)~B+bQ{PGHq#~!{(|dZJ>+c~sJ<}&pKVFz1{Dx`% z8--u+rWUYPbSlwX(dlX?kSlW3)og%5ediCmzadS{XPrpb1Yx4^6Q=n@;TLT5hE58q z8WIg0!JJQ>V9uj<5;YTrM(j3p8ac_F1|Cr_&66~5;#%$vOA)BfEenNjCmET_&Af)sM2m{HfSi`h;Mp`XQ zdkckXt6t72?`+k}I~B+koGtJjD?+s2%yC6$GmOXz&Ngbc>M8t`{y-r$nyLIWT7IX1 zlSWI6QX1kt`8`z3G}?21i^8?naH+zzH*l=Nxk{LpT1%r9a3Zun@nLkJvEF|-jv!?ZX3w_9a=uE}63p%OzDhfF1_!=U#blOV@St+%GPGTpemWnl{ zme@(+Y=9&ApR`ji<&<`I>ZP4B}7Y49_e=%dI*uIrSmgUlTpj0J%NF>PcP~ebN1=Q zoZ{r-RHvsh(ogSq6S@l-{H{VbayKEppILhhIV&?=nY8_M?bEYxCbO1Bdjz#AD>;jn z6`s)}!zX9e{Aj{a0W*n~R4XVX^b6qHpTJM(7vxL5ZGw|@cj@)L>t{AMz~Gx^N|W>PIbk&K+o zY3vj-6KRRHLS|wu2|0;Y&@3#(_2c=4g?N5^a(u3r&ur{8aq^k@SqoEN$SiCo)DmgC zyvf28VVAd?bwAhL=k51a!k^41B=Qsc`Ctbm@?}T?iOECwH=E4Q-w+(&E&huv3nlnl zjLcpVc9Zx?$w~cWZg@v8o6k#fP7wcc>@Av-lRzRN2i?S@_HS?KG zoV-L+rwCtFVY4V*MW7PI@#Fe=%tB6KCy$xeY)WqG6moWWQ-w~#4sR#x0d)TI4tUF9 zQ09SLAPYrNC}I{h<7)}DqGkdup;io?qOc5N`*Hl-unc5jySKyZMD8SXCU+LP2nW4o zkSGtLbHK}O<}nL9#ZV|}7N@Hiyn~p2EWfxA%a85nVy}pk%goJM+>EEi*NRhF%*+K1 z0d9`B-RmM8@|MD@JcQ;!SO+ob%n1`g7IK=o%py)sqNr2CjH|`dN}y2O+)7VZVXL=| z^{}@DD&=7m4tXW%Edf0th9A=}Nqq^kq!~wxs~w@{uy@2;48bx7+A<6U-;d#!qOzn= z%8aeW(MnNS(md)dgg<%ITLiW8DD_9Y>~I!jI13@)_e;|ia2B!$XUteyY^^lCrOab= z9rem^rnFhcjG@KU%9t^=SXx$UmetkXl>&*3LR@Mh@20zMw;67x1O63#xsk_nJ z!P`jQ=sk5;m@CZ#`U+y6 zzLBmC=0-D@3TIq_nEugoCjZWxw(RMlbMm)O~gj?uIu=&f7iXo z`odl7t@B>E>%8^k_1<%LnK>U`Z#B1> zk!E^wdOp2j_qF@RUFEIzwwvkL*-mUT-?}TkRo+|9zj1e%5$x&oOK$p z(|l(wHkX+1$?vSD!VUMP+f=ye-Xh;}n+R{Mch(Z~EwPlml&}0P)Wu`o2Wz3Z$oya} zG8dB<)8Cl-+fa3GyCJ_ZY@J&ihxi$7hGtXYjdjdB?!B?zvVOD{mz1P+o)=$)bv>H-X2I5W`*c}a{`5i5UYwmTo1zpXB zSJpCbx%bNY+gnC{&HCAzXU;c2Tl38Ymt`ImfIM zO*W|$O*RSGJ&{6N;i7xVZA)bv;XiAZIote?%CAb_Ys z%~|F*D*v-;u^$CJ=Dd3Wn$HC)zFX7H8RmCuhB=cwle(HPeWD=xM8Qs}5zSAj0Y4=m z`_$yq59+^LH^@K8)6D5+^=Pt>?me?KPxqc!Pc7YhYCQwps&P&wo|B(jD?ODz|6A9f zM)wqs-nk0r-tt$xCzj!v-ec>DCA0I6zw*9w-@BIg$a-v9oHsqmd+(m%6&RV-=Dg+E z-b3q=C9-qI6^XMv=zeI~p5xuO9$1d|zH$h<9Z?Qu654}amMp}jzi=-)?F(G+4o|2x2)S7-?r{pF*%Om#UjTf-?VO7WkbK+ zGVrl}y1(4Ap(k`{vn^|J67xPgk12IBq1O!NkSe-Op=fnHj^aegXkm)`5{0_LM-nCY7h9oy8qF9 zBnVVBIUmq`B*E9hO^8DLTTi4Wp#03@?;*U>XwD-4v=q*d;oP7e9Jd5wFEv{1$3B{L4a2eAH#( z8vfO?&;d7K*gZI`$~auMfhcqh=Rg_q&ozz*;Ep8=BXAayg>$&L$ig!`G-Tno`i%e6 zJ1qUCD+|-L0mCs1xd(G(vap5u9a;Du%tyc-`c9tWEns&KZ&Av^5^E3oIe1fuO5U%K zg+4s*mW3TW`9_ncGYyRTh9ERF8j$M|^|^By95pf;veqH$axc3PYZF#Ms2zQ_Dfh_* zp;q+gX54QVgmZdJo;I8%pTnQ51>Bh=Pq)5Qg3UtF-~&k6s~rcICFwCCvo;_$Nl}k_4Y

0=igxN zHx9uYs5m~b8(Bh)pTFcR~wi4)2-&{vOb*Z zO85i~V;w;KKyoeC0ny+0#dIyBqr*Q=wsFKIFXH2Cm7=cqALB7 z_Ga#)M$(&}=R8}uXPVC5%6-gqoR74}P&ro3jNUpp%j>wKIaxi7uh(Qe3J$}*-AdhP zb)qo=F6ks(z(!L)1`mbF>LGm!aZt}&((k8rej$aix(M-QRo?w}{Fy_0*F!>Jj;#Q9X5ywY$ctvw9F{ZyEsQ`t*x@8aHN zYI`^LB~!DT#vaPytOF5N<#iGM~5tvTx#tv8-YU$j1W zCVkO*8UJc6wdv|yqoprirrK8R^O-Hl@Cq)>NB~qeoM1jyhXy#Wm*| zt%y0sXS)934T!$DJbl*s;VktZsy)d)@#kqmeN!#Fn2jgTWY*SND{YR^nwV`wp`THV z67%qMJW9;Vv+ZwM51fC#@g__U;}dG1wKm!;W3SOhYpu;D&*pAc1}dYN8OzFZ=^V^? zWhG~Uzt&iT!>l&uicNU4r#qfS-+2$GyU|wL%iY_yDD5@U)0;s|FXrRmM_>BI=JAkVPt;g+#b zt;hNLS~zDS#Bi|?Pprep;bNFrn5Wcrsi}uM>|#7MME=dukN={*)L!u4xK})R7lqe6 zd556Kb8u03%R3dK@Q!yXMBzQ}VDMi_-t-WKkG$z23ZHmmg#UV?!GA0HE{lTAyA7i7 zf`@HwygbYiw(;^Zzu1Piz4MA&c&FiywnhETyIos2`mJ3Ib<{eLJ7||et-O59L$;!> zwbz#S&U1?wLY=gZ+J#VOtrNK;b(g7ZuU!u9<|q3y1cDA6x7T(Xn^4=#I}U>WN86-| zx}b06=YJ^gQ~c7V8(VolBlVT{-{pWFB@2s8YE4dKbi2f$EJ#YBu6kB)&#Qfy^sGOtbJp6$aJQ=(SjUWYY zOKhWeJ1zr*$U|5+(7TZ=@lIQFub@~!Z0;2j3z7?<(gDRBVh681YX>g}-`E}W4dQ(V zN#8)`eKh@AD7g)tnd>CC&*I(QMLUZldslK7?OdoCYR$c!^ep9Vp&hK(;TaUQ&rowV zv<`*!yaA!;vc67Lc~h;aS6D10HuZ{#g~^4)X5I~|i`X|HZWOgohq~kQewyAhpq3NpL*efa)5gVh^#5>9EsnBZ9uTdL$#l)gwBX%2mCqlinp4tg^Pli^hhQ3;D z$ZjLvJ}xd66aQxS1Wxe1wO-mvc31Jt+|&(y1wYpo+0<9^4BygCeK}`V@MeK1Eaxo) zQCOzV;f=FBYG-C}1C%B_&Z%*}0hDYMy~BXwf>rK{J8n$A4nxETs#GDo6H zCT@lVOS?4 zd^dC_^annSz&uqjGo=z~#O^rfcl3U<`-iETd!f6b-}3#?z0iEA4qnsqnLVqc%|Kx$ z^Im_c`_&F8cf^sshu7T;rnyQoM;6RyX+&yqIyEzx>pGzRrT#+aHw=L8==UHxkUMw* z@3J=D+6$yw_-rp=GOf1Oo=KY?UVG+bdXjs19e6D=m{D8EyjfrEr~Ckp%TM`X=mGhD z=$G7%%J%X!>7aT*oyNOn2gwK2>Cz8se#(oOtn8~TBKl~-6kKuU>`F#Y+XeG(ZRu@? zgL`kU7c*do=nQ7?8hR!ZbH&BQOn3It78AX-@A4z~F5l7oA-7@nrnlFIuD0?Nx~4J{ zc9{3uzESg?S)9kPTUt}o2EX>cULWSc4y#j`3_HSmY^^xcT5iR>O<%7SQx^Ta|Kum| zTK=Q!n>`mmYw4>?-={WDDP2hMU6H9;d z&dhlJ7V7Aua@+@V(_J-RJ z0>%x_-{fA-Ew{IPo9G39&rxjU4mx)s`aEojduxA(YKlvk zrme{=&=RI`mNFGoOor=+&VKE_2^#h&))XFFu3f zQ=gf;XQ2wzS7b(KE%Uk;*}cSlqoMK;`Jy{a9ts;UCjD2LW{jznr>25%T;SLCwddTAZgI~%0+Bx_{e;iJZ zU~2Y>``C@oZUUZ=ypW&EFX(!S_kSa?p%^Krqa#v&$X($`jvl(Nh59gPAS^J;_!>Sz z1M*XTmlF9;`MxFMNzXHm`+F_P&mf4Vmm}o|ZeqWs+(J&wlbe?EbCh2|7-%du660~j z_&lF^DZh~8`LE!Qz7f7MCHDsA!B?hupSn-nF!>pGuEY2`! zd4!x=e&IfMQ_C;i7v$$|8u>jP@s!vo$KjdD8~L^T1huEo1DY{unVhFYBjn`7a5)yc zv3a`kR(`|rJNd2r0pdnH+k8nNW!W@aqWNb?L zmHX07DZh4Kkzcy0by)3Z)d}?9{K2L>H`PaS7cmQ1Id}i`B)+=5%ybrEWf7Od6q~LoJONfbD zEMd5O-i^gk3cn;=qEA9e@1qb$Dap}Cj^ikoVGUh|v{=mh2P#Z4?~Cvc`Lj^m3vn%9 z2=PQYwIAYna2o#x#KBB(MbC3DG`0|nwJ7z)AUTx`IE`L*{1Gnmm0W@5mqX4D+b=tx z;|Q^Zb8Z~stb3FGjF2L4uzF~Qgd*O*!WZ%vp(r$|OAsVWqjyPm+4bO9hWTlIm*>G@ z5LDv`XWh8M8Sd`J<>-ui(aS04fb*AwE0uvh`5EHXMfjCvP`U`kG9xYpx1dR8BuDY@ z#=^Ab*u* zwW)Ljo9ENvuw~;>AD?*Vo=4{b)S&-_Lga67UlIuK+_!E5NV4zT0^WDwn^1uB1wD&i zTd;U09pPI%bx!A(hYI>pE)NCl6Qsc05D3qCdF0%%f_@0!h5Ymu@JuQ#;jEWe&I1uJ z4|Qj}d~#mMe|h{LZ2|uA(X5iVj&aNTkd2qr9|+1A3?TGC_LwLz)5|^8gNeoKI=p80Xg8YKBgjp@K{P9ymcQ#%TCDgTYi5Q z36)^HEkb#*@IXooXZQh{52dACrM$OPC=V}nDHB8$IR40Q+EShedH!RRpTN3)EG3hl zNJ*J+f5K5x`30obJ5X_-vn~`WdzHwQP+!JekmoNWT>m~-c>p&%2?XMMQc}pl_c*=} zH~Wc{M1CpWfrI)IPVOCVIeo6boN)Yry!tR;ufkz{#MK{*3xq0OWp4pjSttZlRL;UN zeeB(plEJ^di}F3@ZK`@zJf>}6w#}!0f$)s`yanZFTrCMX3Dfy2m=SaQSCD*fd#{LF z;u#uiqD~w7nJXyc^A%ha+ta+g^WDkTuDzx@(R{@=+77KQ~w~Es`>=3>N6Ot ztAr>&gTIQ7D1WX{-K*x!6>50Z$<@4h!fh#qker-cxC14rxts!83$9FxzHOIg<&VIvhUwp&>HM_T^`?=h3ssopc`sHW-idX1dbO6PTx*$n zECNyfrBnod{41$2nP(N$RA$cRgZN&oMNMs;03JFzP9RxAps{&($`t)?k)#1J4obpOVXsxEYVTdQd%82pJ*U>H$~m6b zIBHi>-pJRoOi(&F=T~N2MX60y9qw5+CciK}i*Q%urSgLFW3`nhvX1hY-viWP^jOv+ zvo?2Tw!yW;cDNE9DswvLt$ZUZDev&KF3UZpbADOkiC>65g}Kx6N_nX?rF&ZLp*Ddl zl39t9J@4_fu1TL-+}kP}Jn_pBkNsw3r4`NahE5Hpg$vT55O=?#{dmg^EmUwWvU!ib{dtwekvlr4-~&(su48)!>xmc2SzSJ zdUc|PD5reF>$)5{uf{#G-Edi|$|-r7 z&llvypZ={7Aj1uu)nN+abY z_tjg8lf)?;#m=(JIpVhRr~8Ln53I*2#sqXoh%ZnT_@3KDX{_9%_P%>Uw4wS0aT4dL zWWha|Jop*M-sFsamgmJ!$}Q!*xUKvIo`ZjOn<`DfCe+8LTLN5ws>1PuYVZU1Pq(h} zz^$VQ@qkestv_n?%;I6!YKiVxN9{KTuyKXbiOx~sE&+akq!?zX3M0@xc zqvN=A-Nk=6Wsm~CNX-Z3B0g@nl(^K!!!@WnoGSQ&qjIVsC49$i&iTnZZVOIJ-l6kd z_Y%%=ACybPd*vvdkBQr?-ocOTGycn|gHN)olA0c$WgNQ24dQSIwK|@9m&AMJGVu<4 z$EW8Ack?L zmdY)vesT|ya~MagPVh~)wbDwt$?7dP7Wq-Q4Aq7YazDQlURa&TJHQ>~&R}P*_j50~ z3)qG0eSA*4f?c^TZv5kx;2gsv{DKZESMdWptXvUCl>KU&-~bv1X@fMuel=Z?HYmwy zihtaa#zS0sN-}!r7Ne>-=N0~SAG!O;*{>d@_Odw2>&_b-MUnW5IHX(?SHY|FJ&1-v zn&2Rj8cZFORff(PhxP$^sW(7&j07*&cg%3-3k za$L#7-Q?r!kSExqW(d-Q>Di+&`9(Mb@x*=XmN6cRIHtByS}VuMZUY{LPbqbSI>9OBB)n729ApAB z1-sO}bla!wRer*=@Hna?t(5}wDag5p=k7Cik8&Fi!ac0+MQ6MYpOn*dsuS#>!%kEU zvILof{A3p3+`|j^xx1a29cUh84YCBgl{@0L*iDB$$~I=UqhXLO$QtA`UgAiUkNo_` zF6A!1gS*Jwt>k4sAJ4zP!hdL|^0T-rcCxyQv)tK&ZJc+{j<4GezSstCSH62E&|f)jS1?ZC;!=^*W8b`!sJwh*{<~L2J;N)hqMlXGfR*8| z-YNB@`jwn--ZAozsA!zT{iOm}p3_|?8I?DxqLFkOeW%)dXR0!)9aK`!DQA^R zbg8WV@LKb|`oVJ>#~B~zofJGFa?=(5O}u6*s^^t+N=5Q3sYmU~oMb!7F30RI-f0wP zzVI{fbKo>n&NxMsHL9sGarLUE#=`BZ8ahg`0_oqtp+@=wK8?dpS);ld14p{*C{4u( zDySEf^GXGFsi=OY=NF#oIHR6ckFeKK+*+z|lI<{f1ZS11Mit|XUB(dN46Z$88JFcO zkK$iU%nTKt(MFu70)ov}{G=tQJ=X>>5UO;{ZDzw9BYhl`BdaI+s=7QT3juQ7)n~v)``C z*|z;;9!X>^aSDOZ)fc5P0k?PYbJ{f5l9 zJhyULy@bxqb>$iwH`kO>sOH>IuA_N#o$KQ2P4uXXtJ_eGF3x-jw0yQP`qMG|2RLJx zJnK{*Rk#XXc{Jeas2j`+xK3>_FXDW)foFd&+JBJqr}Kvs;u)#GaM3V8gQuVVa&$kh zQI4weUOCj<>Z;|?Xsf5Lqh>wN?OwuVYa`DYp9jz5NmbFSz&;g;+F)(IUBA=w4?Hm} zpC_yE*vN~2MIKJd{LLtjQOVna-bE#EEBY0cyozvH`j_+8nwRZM_F5dSE`yisbv%>3 z5tpooPHs;0JaqnsD|?&K)2QrKf`4;tp3wS@U4C~qlY7qIOq{jLpaEB3Ekn<;-Ws~C z#ib<|CxiZR9>TwJywLW4bzGj-`jrm9Ia|!LI96@px$(2$8C!@dUS$tm4t%k$*sJNV z#w?9CTm!W$}{OVLC`>I;is{*ewui01aRn)FFOHozYD}^dt zL$wszZH?6Xj>pqr_Z{E&K-d2TH<~(}Li`sWnL0)_?}~a^t>#@t?WCGl6)s6tDQ_h` zSMkK|b)2_W;)QkH{*Sua#(%_KySi76PfB&-jd#xpeBZxE|NG7gGFO@<=upxtfi_%Y z^=DS^;g1pK*|O!hW8JWqle5Asjw)OewKzE?yt}Oa>=a|BxK|7fxTb0`^st(#%gkFi zX)U8_xp{}2yLceP;EA-NtQPZ@;*oWWXD)A%QG}VIUJw6*Ys+5{h1$NCt^M^PoO`= zgQ%Zf%d6@2vuk^`z?x*Vq}Mjwv0A{*%w2SAMl?5*(&s-XDeu!>J1Ni2KXwN4ZoTma z@(p_p4&W-8u?H`tWW0}iz@%_Oj(XdAj_i^TO#x zRd2l4>Unj&hU7QG$!b5`lbK%ls@3=Ed2z{%#}nnRa4ky3iI3YjCJyD9!{Kl=#^kBQ z;XH|W$4SlFPj+e}6`b1miBCoYx-|q3z;TS%_!z}8-Z-zpS591`2mO2E#@4{A@Aa@7 zdJVkTtj00wlivXUtAlWT^AOyf)gE?~@z#0cL>ce!ABrL~wo#AO`erv)yW`~6$ZP0z z1-sc@?Z#dsudaER^}0koGZs}*Mi=J0;`-IZYwUFfyV#xWrd|^dM>4KE*@e8OUTVDh zI+|&;)LJxl#Ov>TXoP(M$EuO|RrYq$7=2LkNXrSHRAi>s(rWF^c4k_w1HON0QBCS# zo(qk_HoS9fqQxkT?fsCT5JS5GIsk2?zp$T|aCZ%UG^oqKh-OQx;|8+O7;S={B_qzAa zJM=sZ7@1Kht0u6UGoI} zPlmcs)zwLiBVZ3RG5&u&!5(H3?KrC^aKW0017>F@tC7X%OlB7+5jlyqW6U4N^J)^# zn4MVdj6O#;BdgKL$vgybYb>!`Qc3&*3$xLzI&O|d6~lk8)mj^uQ5jxci+H>WA~ z5pb$K#XcPBWKXpZfrmpCw5(bd+=t4;DfA)EU^F|1qIi@XOrckHZ{iJD*}V~};+7+$ zJYGQA;Bs1axFU5~z$|FLCDVtYpp=ZN?FbMKUXK!t5v91FN|)Il)oQjm3$N zYMhRXg%V3$oY7LTXI-;0)fsUO%8vI?87&7~M#~AO)>G+q%+y3}Gl@O|9i=36PO4XM zZ{sIe!M%esUcTbY}W;O6^XlJZIGIhVF!FQWrLA5;=`T z`Y4o@5>cC2FRA6GqNJ7wF3G5rmQWv!no>e?5}})umOkn9K4x#QFRpoI-JkIpEKARF zoC2-s<}_*%Iq(fa2~JC|_cjxP>EHzV7*vxI=wnetNTD+U&K>)17LQL7Es!S}bOR)cXZT;1wh8T1DD4Q52;D2H8#Gqu_6x}4L^Zr9^{ zZgysJ;MrTpuCCQ0zqVb^%A{x1>ycmI%0^ChwBmBuwcVUVM<=J<5sj0EI2UHn8xrZk zgy@Dfw9@MdwVHIOh3{`|9N=o&b?|blNAK!jbv)VXTAB4sdR;4vo*B%<9*wL7sEswk zzc7K8i+wscxrp{oR=Yl@eY3KAHk^a&+10fAc2z!M^%+&wYS6hRu9S_e_*!ms=-NBE ziFQsFy8)+qvrwDWuEQ>Mt?G7NT;HnO^>A*hPE`$_jIM82(Ham!)V8wfS@hagHq?=7 zlV1m)%lIhtHNmGcJ{S+pzRY$*PWxuI8*yScGySumRM!sOn>^^&wR5W3_3?76M*r%l zDCV&zI<@Fl+sZ_KW*j`5SOvAJQ3w{q$^^y*~Ru+o#00Vm+bS|hCzIhE~d zRxY%Ys#&@9TwqS}(vg$iPG>jcpt&9Q9NPp(fdBp9Myz^^crLp zLcMdSmERuk47JAdy&8%lLw;uBqJeXV+PnDZ6v4ym7v9Gr;C=WnyE(i4Mf}aVokn&; z@DV(aZi7%qD2zVmFq9hN=);KE`hTo9K@oF;RlTVvTxJ>4lXWjtk%|Td{*07 zzp_JNZ8-W4vGoD;8Hn;h5p+BMr0M}@kQ(yoe9RdlT;9pQjki!CttnU-{tbtq!didw z2cUdV6s^t?C^*E{M-Wl^A9VPW6ELmdKkU}7t#wOlk8kVm^lE~?(Qj}+ zI`l{LpcuNHBdxqBSdFxz(5@PZ;zN{vll)saEj7^^gTF^t(en?xFZumYM<|Xm=O`-= zs#v2?7s;dlX18JeH{y5u2DLZwY3YFT>kX|Vj;(*vqcQ$ZjkSvQXf#Z6>!XRPs34R; zy|WM9`dZh?yn)9{CwyCfrQ2_u!f6Zlwo0PX*_+Hh)-_hISX=G>aU#3X$SYR zN}g-8QFHYWVfteRgMQ*26qe!E*adhsKR7GAz`eQ!cXqMuu~Av?U(ph{iVGm{}rkp zugQNy{0aWaE6s=o!f2EtM&sC+&K-wNO*-n+yUD0c?kD5q+zUIUpTd6*KI42_N=DD@ zw>U3X0N=nb=>HOpjfdLbS|+y&4w9MNs<=RALR+D#m6Q(2{G^AoVR;rzem5N99YioXg{O&ISL$)w12eJ?nG;XmD-(znoMf?q;a#jnW@b}RI(CN zo5WAd*}KbFS`Ty9)3!YOCV|oXgGW)^x7oh*T4mn$A{Dr?YjHaSg6! z(Q~#sOU>+O^5?2^=scH5@0X-=DctYM>i6w(#67!~a|Pd|T6h&-(W=t38a~6h-CS-} zCy$%kok@pT>P$6@pV^HTzm3Hp@8hwZ!h4PWV6&SkB`ITu0m~9 zr;3x;&Ew9XcBVRCP3Nce=d1JJ3i{8SNUVUn-_PJ(`-@#%|6zVNi_@)yUYV*YcvN4; z)2R-=(wDXAbeN$|SF`$A`~_-SKMgn^E~bmn53`sqLn2g+4#n{-te}6fE775{Q_0Ea z=5^~jm$VmJUHVyXZ0(QOD6HzE=q@DdPVXpITfA!Za%l3^Fn*B)x&H1 zg*KJ^Y3fupyPwUkjK|_RWRCS7)!_V#))>U+r3R7D|FVAWPr@T|pE#Q`S3b_T{$!ab?r$3p@De7c3r=P@gUA-=FC-&;>b@Hm=t+~){>@;!~vdbbgvj0J$Wtsg5g_dRZQn;g6 z9XHI5WOl;EB(5LF?}qI?MM0Dy*Pesup2y|+6DG}oY9*&E2#h5T!CKqLvsXO z7N{e{aJUC`QGS1V4nUJ*rMd#2jG8!Ow)bk`ciEo)9lUvVGpDID&u;EC1DiVY(UCXN z)LCi&ZJOW;xF5Cs(cxI7u2g$^dHpE`8>qWxvukLT#CE zhm%bnKeyit51KrFU$I(UrS_#yKQV{Qx%M2ph11-bW4Cl#IIF2MLaPZq)JLpQSF3%< z?)nX4}2QI(4nuORQJdfosWb#cFGBCabgTnRaWZl{3?BGm|vShjVJ<4dr{J}%eTC**FgFaAP%yxm|PF%~tWJm@Ek z702W{d#!y;uE%xY82QKLNm&rTyOVOYt%pv^6I7p+I^UL)j8@yZ#5k&Q5xK=)diD19 z5);+E^zP&B^7^sQE@HQrmpw+K@{k8UO8;Z>6uk@RJH7s7?eqq~I~ncr_R(Xax{sKk z<`m=EA*YxC=VX)%1&X}%$%pFENN_ZKgl?B-~9S%c7VwmiN3=G z>UXfqPH#UuOi=fGt~33dUi39itI!Vv7M?N-gbP726zXk z9;X(d;|Mf3^23MZCVQiONN%=q6QIvwc~<7r8|r82mrp| zC&AgoWOy5%MFYKU#CGqTY>40DIeIkI57P6HJmekpHmF;1C>rE#CAN84#T4qY64}Ig zc}_Oa&lC0a19FSK**+k*+FL;U3FH>Mi3WRHh^<~0RF0;IEJRju*gHhe!^C=Uz1mak zr-~X}iH3NaynE18JQVz1n8Z?pH3vrlFe z(^<(#WD*<6+~jTahQoX04txvt$en1a?;(G$+|788+$E=>j=qcWZkbsrhT_Z?T-%O% zTZkiG7A3P%RAf<#px}~)Q4x{GyC^TnG`O{0l$prStYlTPD1}8@?}9v!uiJT9Ur&n< z+y%z<`BtRzF3F3yyIq!-z>7G%ZN<~=2zVGxj;)Lidz;v6Grn!dyrW)9GE;f!aFuHb zw)9$f8=2pPx7%^=n71wHf!4~lpeI@@+i-E~DKhdiWKuFJ#YHj3B}8$Nji06vm=(^z zOhzR;PO*hVcA}t2;a!oJabmkFuYi~FbK4M{@Q#DW*(p7Hw!pEkxz`MA0dL3Gtve@^ zyQ3Ae1FyH}aW_k%1jRSDF_zibD7+`Ca>bqc9lIc(5acXo?SNJ z(st52;iV%#y^@iYW?n{bB#t&28IAOkQI#CLF0aX*oPwSyb`mqhI;z&=-ge46>8%S+ zd#Aizcpc6VNy$v+tz~9ikd~h5l(b4|6lyZjaX7w-8R0a{q*c-=Wl*0LEyJMCpAYq+;Nn9e6=Hyx*gyWk{rPKt-y4S8LrrYen+S}BKuOk(e*yn(yh4ZPh} z(_sycZD+kR-YRf4UTx>Rvy9Js=e$(pr&bb?pBRU?Tk@t%$xJFGrBWW1nU&SF!r?tZ5xgt+;&@p&yboVY3r}iW zv2dZzqbOchFN>#m5_Xu)qc}K9=K}M}%)%>Ix!wR~W<_|}s1o>9W&^X* zBScS23E@SZ7t9YAV#mUGX%^w9C>q`!WE4di?G9Xa$c0#Ye)5WiGl~qN7+D!bLGlaX zez`x`7ZeO12=)g*-0XDM*mHwtkZ&pmZqxad@AzA0_rA0G!}XA9&xLPFF5IVeZ@st9 z)5%^BYH$Ji6vW>&gGeum<6fFUl;A2om|mn4K6N?qYsrcGuuf+KEC_#db9yw>*Y-=0`F=xj$qvMJPXHan?UD^U?j_ z=J)b>AKU_7v=`>FAQujY$Ae?RduBek@4)w9LEQb`x$*GSdkemEeOVS4UtfCgXaAEQ zOZiO1RN4fs1IKGa*k0Sf;&rtRY+hm8pbgxXZ^6poi~re=seJKc;P&%{Q4HlHwV(Wt zeiWWYt*C7svT1I-h~z&Y-!1g;R@lHGP#mWi7AsQCBYb6z4hZMal!aXJTNXD zn+0Jn@S4%BdC-v_%fOR(DRyLZG6=~^;fmpqtQ@WcRt#G*mMn=&ax57Wj^e5WSVAeT zbfV%!(1|!6nB<4#8+Li?Hw|KVVXrB>Gz(rc^TvOT2T^>bGkH0~ovAn;7_v&Za@e5C zl(A(LpQ9#JH4T~sF})a`F00}wtdnENSJb}tU*S!ZKxrJr@?v_8$!QX3vRb%mSR+%H zFL5GDsJtZSmES0c@?v?7$ZQn*V7}pQ>yK0~W2V6cR;C^^~5Ld>L6W};9)r`;{Ncz`$y>d!=Dm-LtkY|@D=~2DZyl}Hv2t; z9>HdI*@EudZa-UiH2uc}ql1Jpf!yVW0yEe}x83euzb3A-d&#H??t!NUQ-Y+*R3eG8 z$?p~P3^w__gI-`yI*y{l=wMWkNG6oif+R{}Wm+&5-bv40?oQVVLcuS}~X28m@N zIWkBh6N8E5s9+;~Hu*bTJFtQst`pdx73_5PlU+T$AFaF^;SuDI45kOug2c)O@;9R6 z)hFm3YuwZDATqcuiSzYI^@dpI`gEfrTqKq{#7!a&xW)1pS^@4%H zDrQ#uv)x(2%wUc?GnfI+h9~={+>`DU|D<~YoD6q&5BNR6gD4$N^{4nJ+^NKIoTv|> zirCFP>>mOT`rUCypB2o;4Z8;wJ@MRDWlu)?8SnS2hbPf_vOm|I&bu)ePxcwXTsJY_ zuDOh+2Q#Uig~R&nU{){>ul5)IJmR_EmHyrE!S3m*vKOJqiT-K#lsl1blW-lJ>K}Kf z5y#vK%umGS?~HpIFZ9`ToZ-$1W(PCexxpN~uB8;Rx2s4A_JZfT&-|zUeD}Hk44emd zagU&%*u_1HzF`;k?dneVkGV&|X>e!eyWp7J+ZA#;J!hbuGv9sckN3~IXWa4ZJHemf zALY|L!=DcKC0EG4Zc3Q~6f&jk|23f~oYGh6DC7`gU}W`^Rt{JWtJ7|AKqo z9RrT_`{O~MTrQ@EA1o$3&529w;y!6KZkPoZhpj{NrSC~`*QE_lhkh=cKI z|CHaB)pqVgGAFqsnIGkk^e?-Ya92L#pZ43hXHkc1LuOlCm(Mb41-1rPp#nGEn~R6) z3~#zO$A6Fe?^5?YvBYg29_S7L2e>W5GrbwC&Ln30)5xFhP4njA=K6uxy4C%F>+lkA ziM!Zs79Qjd1P4;tGCVXG60{8W=ly9(pZ;#kaB?}6nHF5V4VJk}!KLoIV5&FYpXX1d z=QMAYH`AN#&x#KJO|aZu=DrD5xXZz1WPjwH-Qs@4v3RT7l)ajTn}!FwgWOi^HYAwh zEx@sLinkEg)hYCx>dmI#EFbh|`mgEpCTLCGV6YY3Bs|0&>^7l8)9@#HZ*e~bo83*| z7I(8dnLbmzIrNz6&mm^`pMy>ARrfPK#GBm4)HVq>4i9yQxNX9%!-Io1#31~ESGp_Q zSM2pVnB*E1huenRga-v}!%KrD;GkeB{=lo;mF~-6 zwYv&jNtZ9dRriYf1^42s?pLm^xb3K05=^A$B<}^8FN22kY!q%79_|ivCwNQnYMsF9 zM6Z3g9hvQk#kdEraaX&~gSGA&aJBmazwpa^R=(l!eZ~DoTy`7Kp<%c|c!WEg@kn=s zJKkH0W9xW&PVnk8(;!?wJjxyEJ`2{lYr(bj8s{zZm-^$#9Pd44{#j6uociIh_^&SW z$Fe%kdlIa7*SSwveHzqdwO+Vxc(gmptpnB#*9nhtN4vGbI^o*kvF;eR7Fau6E8NN* z>*{L9aEGw2b_#b48)$8J06T09=0a}_vB1;F)X}=`9PSi0)y2U? z*F>AUJ>!Y)1jg;di-S>Qjy6Y`i@b&2SaX3l9~=WOqT6D*2(hpq!BY7x80jyS-+8B& z$|bN$PfZP>(>=jmC}miL7m~S1E|Vkid0Zx!!XwSa-Xd?Lxx`xxF7ig1iZ zpnlyo+$C&NJ>Ip6aqbE^%wOrRAa^)8+#lu-r`rf~xVh9@;!U9ITyQR*=J`?$E8+R{ zUmyj2q$<>I;jUpv9p`Rz9hAPuxx>t5-coNEwZqMMvVIPnbVqKPB-&elgx==UbrVcdnx^J zd4Cf0BOV97wNY-6KHUObD8_iBz1Z{{_>Ckns$tchk1s(LCtl$dG^wZHOT@Ndvx zd5kl4e>y!5;!ro*i$jb8M|o>KkDfmIurtjWW_J4IKuvg}Il(MIzlmmd`t(q`E3s6Z z50w7Ozky4>hv&d1xly{-X1Phm#YbbUm(7}G&NQ>pC%e^+{O(FOB}$E@4patEHBfPI z_a4Z|3CF|BW33m@TH~z-*LrI_hd!<~NU_6Kc#tv>&PumzD8ZbO1Xl9h8J+Ij=_7hBGz7_u+>RR zgl9}Ax^&jMY68f>syK3>Rf#x(iOxI>=Gql0V%;=CE$?v3f)Dq(s(@{%;%S$)v z2AbW70p?En@4`K}xK+&Bsg*!?dmp9aQbaH+Y{`(CR?{j#_uEn>N7guJt$jfdkC`<`iv&GF+LWjZ{W}!*eZr9q8*;CyYn?5LagcYLMx zoA!f>!`ddJpVk-bt8K!)oqGN9c_!j+E-2Jhj2$1`eE%5_=A1h(54(p5$xU!$pK4@p)4~#x)-Ssq9YOA~64Svu32d#y^LR$_l*IMdps9lRU z<`8YLw#FE$4bgU^sJ;>01ve+Nh2C6WsjbkO>#MYt+G=vv81LxwUVEpVg_|+Y8uP1h zzZ|9w)m9n9wPD&@yxGr!=i#@E-f3?bztx)RtF=|&Dk@i!xyoq5OjEsyzD8TEHPP2< zYqZ8-6TK1G7#yXo)pR$co4SD~Ycvvi0&_2ZzX|Xf+-ux0t{Xk|8%7VkJJ?h2p=;!m zi+ih~o35^FprPyfHCC@1*Nk3zPyHr!-NDp+XKpe|ZN)S9;YJ*fj`49R+=Cl%LUXsV zQA>!s;T}V!r-pB;rE`0j-kKiQ+;8kN;!+h4zs7{-MlF%K0iWnZj5cUj+2xvX)#$DF z(ytnQ^xpa{qovkDyJg&j75b>Sr`kFnM>j+_i%|6|WL`CXGHw|yw4aFPS{(BLKE!d@ zD=sdQiOls{Vq%>psa5b$b#z;|T~${=Y>)7}Ol+>xF4O0VaoOmr_t7sK{q(;2ZKJu? zOuJ3*=2~p?pmD&6P3JiHq&m8Eh3o2$eu>P>#vP-XHd4D|+=ipfL&iZPiu~C4Xs**P zYDw|LT&E>7FYwVUe<$+?PO84{=|3BHjSfV{6xSP%3tGcnAtdCWL! zoFnJF@rC)Xcu&UAS;qzSm=UlVHqWwp&Nyof)(7clz_Z2~V~9SO@lbt;ei}SuoH82e zL-kXPPvfw1-?(Qy$8F`F@z@G*sD5ny2OoA);mmr(Nx^G4;-tiF^$31}Db1&$UyS>> zv;1oO0^X3j9xB(R+pQj}_C6;r>JCN7ggT#lQL) zy^H9eMt%W-jiXvK14x)15|kM-PgaI1b! zC&xWOtQVYZRjMPwr|NjX`Es%7LK2>^qBgi(4WR1c(?q4>&stM{cZha#l|Ol zuan+PXYQrLKIdKN1WwZLLdW?uyu+30gz>x}Ul_;KW9Sdb{0EPhzm30)Kk4?s`qPT*#&LI3wa59J z`G=uDnEBKC!-|JD_Acgk<1U!V%xLbySu&G};|qQ-e}x_z^a%Z9JT!i{;=A$O-^u^O z+DXnX=K=G7h5igZGXBB$gtNA63@BVJf@$eD{j_6H zf3z{mxa3@PrWy%xQl4r|fu|W$jRar?J$IUD_)h>lck~zv4X$5eT`58D{3hPH`I8`Hz;l@>*T!(?fjbX+$=c*%|uhth!INz+V z;1^5ca4DiI?QdKUC1;p1)VS_k!{<_1(?DqnYYI3O|4Rk;tSOFaDb{3g3a+ew;EFYg z@nnZX>HPOoM1V&q+V%L3D#CMKpkP18n}Le{3;uLa!~!)9;}NhTj=0|$&)`0a!qX51 z1Rb~^t%wQc98~ceaQ0Ra-+iB%0#qnCW;8%`|A1D2KF=+isx&xfa9dVCpecfDolI+j z>De=l8HR6r_6(zl857^uB4#XnT#J~6;m`Uf+=oBoWV{?)i92y2GYS{iLaY@wi{khi zc8Z!sV3$6g?b@@9nMOdb>ELv}rGf2p^^w|7`bT_-S2|ztH_mK+(KF+m_(lKBm1EB~ zW*H8(t{t|2vwpS0_V3njU;r1y6*kH#$i9WlVrH0ksu(+moeww=uL9TLZTx}GAN8;L z7k#JmmDu4F!0R=4)63IRBv;B5I3DD`-k=2iX!WWRmv<$ ztx0XjHtqSwJj1jX81oHb{LpVY!nlb)XV(XU+Ej24bCfaUh8G(s)({?8Bk+Yw>5i_vCz=$#l|8d7qz*~m-;4Wqw^BS;!WU2 zDs!5N@rupKYA&;!S(aLre9eAA&P%;Kb9`!XHQwwzXXb@o!7R_rGiILa&u}>2;#4#% zF!Pl0GySPP3IF3tW<_R}TbiL7D=gJez~%65{U<%HeVd4bpN(cL$LmHhq_NT(Y77A- z-{6&afEQ|tG$l(rN%mIiLn@5YAi7pT9y$4L)2f@6WfXG zt9lYUF__4{rvIWR!Nd0#Jt-c(zv%bj1(t1C#saDq;_$T2T5Mb)|EhjPPiiNzf2AU^ zGv9Iy+n8^;h6CDUUuN}+K98CC)+NT5^-Fp(JE?t1Pi`l}tH$G>D|1<$XI*6Gl0Ju- zxwzT*hG)#S0>cM=V-EfvPxZi<#msCgPAGQhcRfz%H~m-ecl|g0G!9i8tTWbWFp8Pj zp{URw`tN$&P+~r9aYJ!JzcT)npYRl!r>#?XQ*E@)@)}h8EOi?gZ{Ss(B^Dd8sErE6 z3jL}7p~nlw4dpcBg>snL!JK9e^CY#WtdsauZL-c;s;$`Ps8j8jTZ zg|eIRiEQQxGEZ73@TuBtowuYd?DLjlOYj^VgZ!AG7@@!P2YP}~{7^RYINnrStmAl1 zZ3VYbd4W1%hslW%3WxsI|I!nN5|EjYsA(P}^SE`g>Pwj5^MkQ4e(|5r~IN*bzaCJR+DD}zTIZ|&o=v)39R`^&4~RqKk? z59}}d$!peCYoNSrCASC4^f=|jcI z$`H!VOb&3OoFGdun=Vv>mGq%(%wz{A$%(QgvuQ&mSxFbl%1kzJvYaGKh0=slhf1-Q z1}q7ehEs>Ku$mQ|A}7l-%%u*MAyVP0Geu?r%ZJK=6+-2~ilGW%rBFq1lJgX|oyws~ zjH`qygH=OSz)Yd4;C-tzx3yC8*;8>x+J_rsXW5CFRH2ltW)5WnvxG8(PxV=>PL)$w z?IfpyW&XE&S$+D&vkQ<53%rXYW+;)~$z6P(7X_ zQN=316*H~4C#s5C;g9U~k>Ba7q8-0KRmCW+5${7IeixvMQ~X;?#eHd#W10p!{3a2? z>mjue{PbyH<$r2{{9Tl5oCII66FqMx+X2vz7J`Z-LUXJ<2j>6tYc>!>hhWQ1ZW z90E-+Gi-ra)ru^z4f01G&w^(Gv%wB%3m0_2=qJ=Y&;@hA9#7Bb5I*RktecZjz_a){ z(e=&6D9qFUxljSl%_zqIP7=ffW1!?4{k(sy|2?xGi*Za8b)%ohk0N5BiW~g|eQY8M z?b_()mg5ky(WNcKRa_zt`m@nbQ^zCXqP<##tN27b6kDU822Vi5M{l(lR|$y(A`wqu z7XyoNotS5%i-X0vPQnw?CBPC~CuN)jjDBi58JH9-4JYI29^6#(6 zzn3HbUXJ{JBl7#G$nT>fzdwxp{xI_U-pKFgBfp=I+)s(zPl??BirlY^+^>w>Uyj^g zjyw+#d441E{6^$?o5=Gvk>{f#&$C6IXNx?47s-J)(#nQACd@qDK_bBZ}w|Mf8XwdPEUDqKF<* zM2{$TfB6>s-J)(#nQACd@qDK_bBZ}w|Mf8XwdPEUDqKF<*M2{$TfB6>s- zJ)(#nQACd@qDK_bBZ}w|Mf8XwdPEUDqKF<*M2{$TfB6>s-J)(#nQACd@qDK_b zBZ}w|{r}S=N+6_2C=wA;#3vGn#9T=c?|;`xxRN67|E`mYBygPnUB~|4C<=@%gwTZs z8n6&anG+%zEJSixh!n68DPbW}!9t{lg-8Pnkro!zrxis+ED=)_C1QX@;9`uzU{ScR zh+@4kQA89Mf$+gFT%7f=D8#N&U=$f8So6T*a6#q^iIQA-q5$K9q7)++ED7glrhq8T zwF8!d%P_LR(r{Tu7FY%@$0!7rh08NC!E$f~Mg~|OuE0o$im(vrU?I}OLbMbuL>@4Y z$SqpI(U@E063v-u0p^8UGnWg@C31>p%rpn{!ELzC0k(#l^7G~cCES!zGtri{>|h(X z3G+=wJFc>W*+f<_JKP@53T72qL*dFc(XBM5{Xv{1!iOxhuuoK*cQ3kLx+?CfM zzzlF#<}!#%un=R#7|{T%FY18};Bjz0F`DrhupvC2xq4tdQCEy&W;ECcp1@pPu#Tt= z)`dqhKMHINPh_sP7{M!Q0ybuL1f#}c5-YXATB0Uc8=ef;1Z#>KVhUVCOogMdhNv#4 z!O>VamYvgig!V`W}pH$sSwVz3wl4uLm{4e)v~^nW-E zUe9QQ*u=^pu~`fh1HeJ>X66Qobz-;}1`Z={E#q}!3o8S}8eYwCP{L~%trc6D?GJ8& zw~2nDFW4X6#$11~9quc3z|q)8^alIFI~nx?cfh;gUShZCDSCjt;N8si5_{ktVlUAh z+yl>I)D7GV&tfFRRdGeE09T0R;xc#zTnS$mtKe(QE(5Q^mzcRMu5-N3+;Aou1tJ}wDmUtsxi!~-3p298LU2AACMzG2Ulw7`mU)@U2gZQ&$e3^*BCjmUx((XW zlEsJ+SQIWUO=*B3xHxkmSpqg>NjMq}smoGuH0n~5rQv8)r2=Yj8CU@oDP>t$%2aSP zN-1O$nN#MFO=WhO4a@;IWiE$o24|CvS#2Vl%d9dBmvwvVd7+X4wjk#>_I4Yz;?aMwtQ31h;`R$hL4aW{~M+J2)EC z%XG3m9F1vZ8ZaH)0Zt=35~;xsa5+Y)z>e@pSzFeUBfybh9eB8`3lAqo$WhGJlEY*@ z=7!1o@GwThcZHr`!TZV-MLK>bWUjQ%4OI$AmFT&^LQs&OfW$<}M7vyDD7RqzX zoR??ia`-Gi^>T0-vsdH-IUigIUm^aQ(QeIp2=78s5}B5gI}?JOg>@tDR>%w&D;_B29CzV@(_3ge$46< z@C^KxxkK_D9F2$MLHQnz#)I;J{2=$sec%E319J!DM|hw7MC=7W!k-!K0YAZC80`i> z!*}7`;BH=9Oy!}BrNmVJkq>1IFs2eic_jalQA#XUqKLm`Y$ZyG#=rlMin9#V+GzfE z?&v1jO@h0-d!faxKyfJU?(SZoxRp9pplE^e)C;t@7N}6%-QAu4mGgdjKg{*p%+Abx z?qeL1*-4yBMC>NhBmHvXQX+(r9_m*Tmswv;TuG$XQ|ag6*~A%mE^#&y;1BgQdTRYl zA`Nyrk(R5|iFA6}B%V&3N~G7*=`l|wP9`$w>GhZ=6DJZG^$dE<6N%%AOnOE==JCX_ zL}opc9`jh@Xd;WAS&w-%aU}5^jd_Ik_L}bLuKpTUS}&#hT$RFJ)63uyuryjym+X|p zO6jlTbzm8^gs#{rp$BLQRweZ}*t6m5XmR`{^s>68o6ttfvSaJzP*X3D8L%8$ft3!+ zqZL^tU9o@RPG zJ)fQz=11GHlV5L-=G8msdGy>cFWLcLUcDolTkoXj(sRPxXeWHR_0DKcy$hBDc1F9h z$_~4r-B@LVUD0Z2HkeJ%s*lwh>f>M|bPOB|8>3_Nx6yalYX}?Y^!A~gt*5_>*3l=SG3)5H^~q?=xAa=DHaZ2Z zrB6j;*3@gjTIe*ihCUsQSwnwQpMl1FQ?IUfM`Kp!y?vt()raT{^>GUn>xKFv zeXu?V4nY^;9iq?IhqE&uTc9t-H%R|lAA#>{-oXesoV_J@2g1eZSNOlymvTJ-EJOKq%USh<%g}Gpez2e3S6_j~?5p?DS7N>43Un2#UT`J)9jl&j6}p;L5BMEAlT~-P z8r`nX(|5qn&~0!#{2bkhcOIOlf2wcAvkiWM?&A6rxD(xiXDj>?-NO6$QvZ{kPvFP; zNAMGLH~NvjncXe=9#$X1-RNFcAHY56U##ATd(pqq_u>2cT>T&YJ$(+Gi~fUeuKq7N zN8g9dhX11fv6=<y$M^ai?4zs&9x zxDmaHZyj8xuhlQ%xePa9fAY2C*!jpW8D{iL3pol|-WKF8sMhfEuJgy&uC-mcbDkG(F3?9>u>Zy%X#!)?ukvfS-^&@&(8CMGHA?%p&75EF*W0r{stQJ zmHtvMYrN2(!rw~dzg^1wVs zZle+JsSqs0UMqaLVJ;&l%#F52a~f^Xm^qCcMq4yy4kNqK4vm@J$Y!)hV`eq7z-(v- zG>g#@jhV&BY;?jh!H#GpRvBR@bd*ugs0&A;qtUvsu2IJrVbsSn0vl-zXFUQoK!+O* z(J@5Tfpv`9#xOj?jj>$ShHn|QU~P09TFV&9?l9O0eFtAHSktHhYoX)O8pZ_UO`|%j zflk0z!hb6bTht1V|FvT8Y|G4U5zfrR5WH6 z-rE-ABjZE(F}m6K1l^2nF}7kK8k_KJHZ~fcq8qVI#x}ekz^&*8V;(yju#Luc<9%Z; z`~cm~{s+bmbgr?UcQy~sBW|bho-qf`MR&44*Vu*5G5*A6!(HfZW0o-!&PI3Rn{Dht zXBvCam@|zT#$VWUxEKAK)in4Qx)PlRr}5q{8taU;#wBbGyog>#*T6N#Z^i|7FB<3J z1^7F9-uMH(!v1gYH{)019G>&WRjz)8zZgHmU(vJp&%yQRHGDtApN*f4>*!C$4K(IY z#*fBL><4%Qy~XN#coV(N>VNPSdWY3&cpJTou7<0P?~HrcDtH(Dht*1W5B1Db#!16B zJu~JB<2XENoG_&6o5u~8UC$KIg{O^EhB767g&i{-Ji>I$GsbBnFqL@>9y5*_HXg^c z&9lZCBQyi^C_G{uhDVJfMr4NOVR+a$WF#{q^N^9;OqRq$#z7;6ncR$dz}OED8V8J& zW(spZ+;9A6q%u>Q{~4*VeJ~Z8#!PMQgZqqsjr(ZKe|c|(P2EhGMa;smD5k+8Xd%;J zrw~@yENGfs6~qde#mra6OQRTZuV7KMfN8N`04rz~H(werjN(MSH1hM#EHgh=z%0Se z3!^0V9F{;!na_-;@VW5}mPB7OOPNoN(%2LD8d}DDVmyYW(bvt##v@n;eZzd+d;}jE z4~??sL*oH_15Il_;9aFP%c70V+-5GbvDpZH8_flCnmJ%Dw4s>?e?v1b+K^Qvvw@k9 zs|Hv@vk6f-U=B08Ss#A`vnf~E&3dfs!~AG7eA!`kGn?5QjhWTV0<)nl&@5(4G-hTq z6U>6PLNmckW=69$n$c{7#>{ADFx#RrGnnbkc33*t7A?mrEo_GlGi#YO;aliXILsW5 z)ij5&9tvxtgW(WZ2OYs)4LBSfgl90Ui;l!s1J*F#G)JK^-!!Y61KAw}>!G9ZRfpBh zYUUU;W>vEatcH$7tC-`^n3c^+unPJPS_xJ%E1Kicisl5Y0vwM{L@U4wW_hzc8nZm_ z?K88l*$4J9KR3UCz2WERJhLA=^RUm%PtE>ZeQFLsKV>z~{F1m{@C)=4{GXa%nLW)O zuowCjJH5=W(H`c}GZ~zd>VmHM^LL(3oA! z&gNpQ6I_HYVbu{XMwhbc0GFWevT6^Pq8rS)=6mLPxB_}zK5>E|2zB`-Hdk@+=Q;hv(DVY)hu%>8grI8)7)mxFsH+r=r(*a z&F$!Pa|bpJZbx^b)8I67s<{h|In|tE{)tV7yU^X}WH{NJWG+KvPU5|tHGeUGhQFfc z(4WooXw09?AK}mF8FtT_r_JBc)8-oVG^;b_1@?c0Kbk+7r|_RPFLLz*{K5R*yo7#l zp2U9&u0=27`yT$!Tn)cRub`{Vt7y#c%vEqTdJSD=UPoiDG*`e?=nZs*c@vGf!u-~} zg~t5WTyE|`V=m{tIo4702((dQIo1()*gOP}n1@ZvI%Xb)M@`!@SzGY9dCWAe6XtQ# zwGNpFp+F5hrsY`&%>$-qxv0<80aLe5nkV21A|%)QO=+csL;^b zXZ{NVG_w9R|A8Tz%=*Xt8%Ahy>u>Wfm<&x}{blZj$^IQ3>SLRDIuce`Rtpu8vRX(ebRnU577Q&vIdGP183gdff7Qvpt z!f0+wXD2t7$0}+Sv7VSkt;gmg_{4l{7Q^=lJ~AJg#jRr2L$d_-02W6}S|zLp@PT>X zEM=9nV%|6JnXg%;teE%AyJl(YH7n*_^NyL)Ds9EQ!+Wc5Ww)|f^{skn16EmKeYCEX z15aJ7o>j-n$yFUI7g~o^U8^BcSz#6{Gt7$CX19*jh^x$2V>D(aD&daD^4Grg70YL3QCXQj1TpfS^0X{?rL%rsVNs}&kEwUx>;w1NBt8(MB& z-_UaLaTwZ3Q-`&zno#F+YG`j+wP0=QEx4AS3PbytpNxT4b!(6{(0UUcXw^Umb6p)) zx2jnK@C>y2!vU}++Mn#2))4lq!D?1js~?{J)=;jh!YWo}SQYJyzn?XXtIAd%)_twv zTvdjZtxDDitRfta_GY(_HInNJa0J>5Pj9Oy>}8Fz%3I}N1#}eq6|5fkds?HpDrb$s z%EHlTclH>(TmYU$cCe)H&BO6xX!-716U4eNFIF28Se?Ka=- zx@Kry@RZ^6t7~Jaqib!f*08PB2DY=>!uD1>*uiQKJ6auJC#xguY;}TNtj=%`zYTOP zm6eipE51^?Hja-;*IHZSEKQ>ZEfnqfmrK*i@vpO{r8Vyxns%SRsWj~${%+K?mHa)d zX;b-YU(-7CKN?M|#Q)bcEu-;R*R;p{Ut81ma}Pn&{>L2>O`FMGAWiGe-7QV4#=SdD z%c?(5Xxek`yK35D?ka2APuw%twD))-plQ8%>Y-^hd8R|32G6Q^c$(mO9M9x_u+caxi4;L+qpk(Xji$jY-j=ZEDfzVclZpg zDfhz+Z6tS$4DBoKuNc~9?z0%$Mea=)n#ccr4XrT$FEq49{Ey1ehVnlTL;H-s(+zDs zf3F+bS^m;BG@HMh3@tx@Sr}S9{xwd}ePSnl&{k46iVpe2^3gi13@rXyCWs*yUjonn zi;s8sgeP^e#4!#l1N;BuODjVwqh42K(ATii>J6?8tyI!=S*{GNWYTqsq*Yo~7EPzp z!s1v7m0qPopShV-M)l0itTMrj>bd*E&A{FZ)*0Y)^eMZ~+?Q^8;$O0#UOjQMsLU`k zd#~6rw8w5%l|?;vv#G2w3ww`PKX#9^Z)hh_Lwktlk^9iiuCl3zZVr`QJ%A70`)*E^ zL)~Znz`f_@QaRN*A`IdPLj__mTe)edM3ueckrYyXV~7yGux%gOL^;dh#gJr>LZ&~m^ueLbiANFgD!+ss{J)Wh(_ul`|@4cl# z9`(JKhtGRmb`SY=MIH1z@7rK`@EsLadvA%O{t^EzD%2J~c;9<>+#j&p?kaCZ@NKY) z$nU&*;*fvPuP5rFwZt+1C_L^TgGb5y(fh%>?f!_}a_ftO{sF(fsE4lfRt77AmENjg zC0s$Rnq<`yD`JoLo_EW=>AvUvh}IA%{NsKNane5lkNY*nT<@lP!<|diP4`>xyI@uD zt+zV(4z3DTcyAI}L%i?J^=`QDW7pl~?0)N27pMG_esy-=6d!ok-D~a#-uvh>?|;GS zU>PyXy=vmLf6A{$WOcFB`#$(zu$0|pURC_nL{)LdKkZi)XZ8^v4P~|8A3*%TXh2k46cfXup%MQEvK|oik4lK*qJLCU zln`%6!|?ZuN{N!9U-X(N1xvEmmvui_TD&IuMrA~4(FgX8`b4jbGGe9wk@umu0=6ec~T8{2c5g^A~sx z?ah1a6ZMYX5U-2gQCabZm_^1#e-?JZ-$nFK!7gHd4wg`1slUYk%$w&e@jv%I^A^J; z{-5ms6wD_2yg!?~3;rBd=iqE~H+w$@yRpUI?%+?Z7Lm2sU*vz`eeNytzx2NFdhxow zqh3)tQC9Sd%8PR18~ls>h435rmG`CB6MwI00qceS0{?68D^KTl$@)Oo)(7Wd{F_DB zjs%C{(clO?7954ggJbYSa2%ctPQX*aNq9Oq1G0`e&866WX zqvIltu{YQgq%rmc+;f-j`DtYuIoE&BPlsoB5Z`;>19$W8P7vQBIw6ju>10}B(_wSq zIlr<0~8wN}MF?6xKY7p8_oM zG8o@@3*jQ~8!v-QPfP}^qDV=d_<6%W!QVkjDwT=$+ibq6BYNnFEi{??Y z=y$3%j}EbWSfn5_rSaI$AS;T;ennA1#LpKNdMV^b{)c`FvQo-}L>>|cMcb%N^n`o# z3%w`U0xvna@l%j}!N0*1|FK^|Ji*F~N9u&!ljGv(V7wik- z`~C~Or`UWi8Ij3l{8V7R_YC{mi;Vrje?dfKGGjlv2gH8SE@~S^L?)Aw{M7%%kK{c6 zQ$Hj!etvTxAVai|+C~2nxnG3rMlzJ2`Sbk1I2arV0%AgAA2I)l0DmY0`MLj@|1X|> z;$P7rY9A>g149{yf`fr#H<16}|5r#n%8p9{~1&;4iq+3G zCVc6?@Xru)HngJ6Vw13_V@H?5i(z-zE$RxpN8KWyoF>piPlvDkm;UKclds@Q^37c^fqgs3a7|A9i9pkQj@1bT_&VKmKhn*HnCM0 z(RQ&-Y$LNvv@P6DK0M57&IyU?SZVh7wF=Y(CN&Tt!gf|!%xiO`a! zOhmiHPLUu|kIKrVCr~o!36y-Umy_k?*WLoZJl|Pgd*$))97>i$-yo)}tRUz6U;7p0 z0)IX%kG_uo4f(o^pJ!EM|7*Vt>(^x&89(hRE&21?D9yTz%qT0en-TlU-w|#PJ4ZXP zPLUS-Dwmd}Wc(zq z6rR^)W|>KT>1W2i@Uw6g^9%oTza%lGWJwu6*V`HH2s=ePv5wKPP)J7}3tcIo!z;ZC z_lVu%Rk&B|fxG!=N|04jmXH=t1B=5Fvbc<&9v&s@Soo62S79+c#bq%WKS?YKi^-xg z>A9hdpA{B?MP(7GYdj@{MPv%KJNz?Dq5ce0svYW9cr)CgZiYKmJDE*pmF=+hG8MbK z!c;0H+JT=bB|G5H0^6e*2L<8F|;kkUEj7L`6?lqP8zv$y{W&!dlA*@-MMhJdpR%<>Xxp zH>>UZK5Op+cfv2TxA@iUu zWL{K}6{t;A-mIkhJNzq@c$BItkA#QAs$?GtH?q4)ZB+NdyJ2&(TFB-yAL^@r!oNeG zEU7lIyAj?G?}g3SZ7w}_eYGCX2GtZ#Guc$;M_u)A_)qAv>#0A~gYbU%2Qlka6Ly=* zCb9tfJN`eEAktND<7pz_mIYBq?F;`69sEKymWA*&#@?3e)Wh&WxQ?vfRU`b3Wh1`# z3d6#2RJ2#T3=2jN7q(N6*5%tn)>Aqi6D|%o{zI&!mis;Fs9b zFb|%*QJ(09d@l1uFXaoVA{jjm74{^|jVDi(J9;Hw%G{BrUdbR*(UUNU9*2+Mlkjnv z3xDn?SCmkidgN7?)#M|untbeyvR0{;YLxYzS_N0C(bg0ERpk?}syrM%@g8$E2LB2b z-=A5j9(r%e>hd8K9(g0l8f8884u^-rr`{9vfmcJmDIXB?(2MWetWaaIZ`BAQT_zXK3-uG(C8uC8554>^Ka=uH)S=Yj=@LRQ9#dll2Rl~^|VIB6K zc?ZMz&dXJJHM|nu^J>YO@}BpWtOaXQWf+n1U8?WZ|5O+S(W5XY?>bkMGtyN;<%|ra zt0UfF>Kwrigm=lk=M5!3zR&f8`d;0^bJx4$)s}C`quzmVe|Xe8f)25MR6nR8)=%n3 z_=6g19rKQQ`@`E_9a&r6CjO2$nBDl!+Ry4I6-6Ph9$^o|9Fe6=m4jE$8RdvfWvE+T zU0Fxo^6JUDunzfytY6g6Y7n`Dt(*97c?0nbva*w#Bf8<$m-XZg{5QP;_y=-7?^pGU zy6!cQ_2qT1p==Aw%cfL?J*Lr<{qcf`WWvq;qDLrgU7vN-b>XA4{a}z z?cg4Cfap)<0a&u=PwMP8`tpkXL|>6IN)hSqf8oARcN6G9F+e1XUWilPN$-U??VW-r zsT)62Zfo@+zOUG2#P{NMQRh!%kcgs(;UF=PtU*`=AM&$mxQ?>nK7O7JS4W>y?S*(Q z&UmN2_^EVT>u;=$)tj1qL~oHQN*V1m;`@6$slSV-;PG9)9e8#c4a7RNRy7cV&}US5 zE_xB)Tbve#Ypaz;YwJoFKjUs=t;AYe4aHiuMl}=-&@;kT7Ceof5thmxJ*C1k@l>4k z&UjD7Iq$63lWM(0PmwxG6>aBr<0tf8xu^Mr-KXM-IPVc9&WP;MSu9)BNHi2{R3q`5 z`W3EGzo~7+$4~dWaX+*Nb$W_(;;hIPox`$5kE!rPG!~7-uc|w{Jw$hrCQ2P`C4L(n z1Kqi=`iPjv;*q%Eo%bGzi{1sV8!_EQH<30<6Kx?T?mXzheb|TWJ`!E=cN3fOY@rjO zC--eP8@;%z`#@asE_x5dW$zNa=sgr&i0lf}MQNi=#B4V1v-?1F#?wXIV|^c9@h*G! z#8vN#*GZ(0(nX!v?JVx%xd(Oas`rh$AkK?#)J1Uto)?Rh;qt8*f2)CPZJ(MC1q^U#LR-2khNYK?CpHNR1=BdFtIs}0+U zy8>+LJ5Eb#wo;zsI;#!OiJ$&^tiChaQe%MCR`usDd0STftrkSKR4r69(Nrv;=0deV zT@n|0OceJUSk$zgB`Rx_C0fEqmo-|dmZ&T+OO!eC9nV>1_}EHgzPc_HCbhhz99EY^@X}Fu8E55_p;trZA5GFHd#%S=ES`pniF@4Xw*+QjoE!$ zeNOxr@P@c9UfFBdduhkLB`;aOvOiNd#SQTpyPvB@s;y`v8j;mly&&eL{lboWQRb;z z;-;8KG&L1YRqx7nc-kA2SWi)t9;C&)Y0xl7mME&Hb3iHHqJonsq~DYBF3 zD5l8t{2We^lTmsm?K|{J-nMVqkMt|{Wq8%T0w1F9P;IwBPCftEpWnBlwXTCR3P)^|%u#?)=Q+ z^^o0V7O$u50lUkr-gB)weRuKswdzJTJl$kAubXVBvUv?v1DF+GX5zDWaRH+`pQPS4nQBF%R%uERA`PUevf}>7bs`>n(f9 zj6`PgA~WuNjfhWX=J2vpGly4S)q@RGef5gdcF*ls+B5qpd~QFpAM;vIIMEk(DrWHd z$lfvo)iQd=wWszIJ3g29)DF!Pbkc@Yj?70|+|Bri_{W?HjC&w8FNar8-RFDuN*MP| z?bp*&Cxe&X>nr=n6Fh5sVh2=+`?un*-N20dcoUvRR>G^R>cD!cu6jtdN1RK1%XkRm zzRHu@WBZYPlKjW;1gd*=RBfeu2~<%hFw=ScWM7$%*Gli5;tbv++wgR+wo2>um;Gc~ zcGG#%JguM7CGpCj?VkM$^%YI#(kmp@Z8tZkd@X;;|-AgrEkWa$v(M~ zp0+crJTvZOPVEhp17vDq(s*~ty{DzZliEw=4Uz+;Yo4RS*(K65?`Uyn=^bM3YALzaO$vuQy*O;YO5y38sZIajWBrEYs7C{{X(5z#V^A4EY^-^doAe|dt$VtW-B_V z;y$r9bX7ez>QTAA)6i+)oYERPkL)XYLspOMwW0|fylcf8^k*vkBHAYPlEwX3kBqv` zInGGdCAXf_$hktdc_V6E(OV>SthL~^TAJ&`+w}Ub6Km0SNgZhI=+t^>G*9YhYffYf z^Cv3*EPfKgbG)B~>j|&1bBQOXjh)MMsyC+gWxbAbo|Bk$c*VL-xuov3xXbH-@gwm+ ziDpUta?PmO-27BD<{9g!VjWu4Y3y9oYm-~YsqI|gbZ2enB4cxYdhZy-}Aihh4g&rc|VBaPBG_#UfelP zH+ykb=k?FTJkh{tlGFj%B&h?i39r)BtmRzdbZRZmW5xPg5xu2L=TO!`WEDfUtGKhDd&=9F>{ zP`3m;$4}IOL*DUxgNeBJ^dM*MTyqv5;cQOV$K86fw76SuCY+_kT~D{P%T%~R2i1J>wTRE< zIpzmi+=KT4uTdVpkN!jbe>wG6#wqR0Aa^Dw`QtvoOJv3USPR5_amidL7Koq7x6SxW zpF{t}P0l0JPesQ;+*Nf;`#bTvQ^xt5I{zg4b6UTgIh{H)m=_Rt8~&V#dq;mx#GRr) z)8Akxbu8V`{vzvd&LY0yyzX2yzYz4`)8;a<6fPIb;8Jmh-nZqf zPQthg?pv{3T(;tluZsE_P9Vl-+HDSO?__8Gi zF@+#oVlXobvL&*j+3^kJ6!|b_8f2n!=0tgY9VaErQ@;Wy>niIF%_@2WdS$DyYG7VS z>Sw#aM{?1+YE^TpI#;dgPBnN1t*Xa8wN=ThZw=Y)Gkx{U42coUWXM2d#za~D z56*g))z@%h1JHhp3w^BmGAMlt6h zJ=HQK-k?HReV0|)spRY;zcSp3o=xiXJDb!2c$RACtUs+?Rwd_8tfG@$&!*Qg(S~v)1cWdxO)D8#txvU3g;%Ta#vC<^s*%xUN@$8E^p(K70-)G1DZcoyY=>z9 zXY6>AK;NXvCVi8ppY-MRCuw=8u_Mu4%d6+nyOY~P%c}ij{cUCCRkCT9>;(N+mu#Jx z0hjEH=xOSlvHNKgwFz23X0S|5n!z%GX)k%n@22JBq-Q)sX9xcj?x6qbl z?JQKz$~>Nbt$(a6+CJ-FYpZ>U)+bBb#u;aePOWXwMC(#@0@F{%Ywy4b=t=6FvQOIF zzDr~#Hw&|7@^j|2E3ep1v$d_9qPFRk+M3A3Zf2$h{b%j7>XH2pGi&k_*F`J9>C_Wc zIBB1-eI_nA+LlBq-64BRqCRosl4i2J1IO{5(V6%zOv5S28Q9KRA-$lUk(!y9NwnYk z&pK{P<~$sy&I!8{yPcU^wBO1I4_N!H4BA2KfOX7P%!N2c9Ca+ z9Pqa^{icX!9ILE2YnKKILkx`KP_h9!rIB=5%srB+V;mpv~g5m5Ox(K2ziAgx_IL zFt^*=;0}8`9FI;*#FKEQku{xJ1}PIMU@CMrd8rbgIVCw0{h3pWv(lgO%BA!%=5G5> zdkn8Q*8IrvHBbA9kL_dUbEgD7d!IX>p`(e3`}OzOyX}ee+i$a{@+#Aqx$rh~cjiz# z1+x-TFkRzADtzR8=t!m~eds9WDGjGmaeX*eOdnnz7uFl8%do}=47&_B>Iq% zEHRSUqWTE)Z~HHM1iK^6xlYIosJX9zV8OaiTu_!Uh8A;YCtcV^@ zOo$TwurTo+xpSTOoQN4y!_9x}zwO~v9$~&qg-OhR%+9cE4-ej-ybS~4+dHoJ42A?APfK6?neL(N%E z3MOC8a#AwsY8Jb*o$*9YU|L2i<|)m@Kg*c`XTns>yP6JXIMbcfOyX(~b)a*#e$CFKQfV{EOB&+RAT?#u0Y|!^Tm6{_biV-RIt5}jCCfkJCRd@W1TTh zDJx7Iu}fJ;?8C4>U)NGrKfbbYPk8@CaVp3C;scqRF`1Kt9kj_tdnRa2X4PIRhCl8s zkEd%-k}C{IQ^s&+f*#!dBX7<6UQ>GuoKsybC81UC z$7cpcGDju9HHx_@Z<1Rh8bQoRBOjjp)^KC0GsPK>X9Qo#<|CwYJb5zcr~tK7(I6dM(Q6XYgN((i4+`DHXjqRT)pE=nh+H z;}e-!bz?oAIWw8`ZoJ=ZWT&;Z@&1RH+mgELx6xPspS_uyTdd7Vefa6AoWW1;mx)S8 znW$b0W<=9bKRvT8GU@Ly>Eaz`)NH5H5Occ~pN!hhYOuM93Y)D>Nxl7>lDhrVQ765h z+0W#ciqcXc9aA=Xa~?DcmBuk0V;tSoJFM;2Aaf(}o2)Fvm5j2GLA?KZR0fub()nq~ zO3R#%KAbI0qsM1a7m+j2Tx9J)<2f5+nMg5~`7;}+v(eg+bOvEV(iw#3UdgCL^xVth zmyFU-Gp(PR3TgDk)*@@5x!4+Dz8NiMHNad?{08d2v&5^FK~2l4BzKax&E{E>7T;$_l=oR{Q}W^%?0G!=DH`%A6rQMG8PwFG^| z{2WeXOl==Y9+oq&`D*bor{9&c^%SLZRDalRcr(idwzAovE#yWO?w^Fd1 z(of-+i^@jH_4u4`a$-{GYdN)%&03puf@3YKbyjj>QuxV;NzNRV_$=@mcGp_T@F(|^ z`Q@W>QG`F9pc0=2j`Sg%0*>$}^F!8=9{Lrc@==H<@&h~}(?;U+zZ=4r-V1L-_{w|f zZ45VrFW?LBxwk3Y7{+|=m5A1dn*YjMA0~XwUr*$Q@DJAOq3$RA&0&eCc(gg(gl-9o z@f&kXSUf5QH>1B3^GEo5X!yGSduaNGKR?_O7LC@i{ykh5TE6M83vJ)>*TQw-+R*WB z*1~uEHE?aXCUkw_53>_YG8txT`f&TOyWCo49d-|)Bk;URjIi@@DrbZ}oU0M`E50s6 z?RYNAP_l;E2i!>54lI&rB=1*h`Y>MY8`P8qeEovsOg3q9ZUe+zxz^IO=t zITzD{?A+Es+h!)rKs%loGmy%I>@`%W9IbJGL-)C>t?#UTRQt~zK+Hh9r5&I5X=%4W z*SeLXO3_+(4f-#U``lJ`d?u(BQ8}&t#1F9h+kz=H{cV>?HS659Zl&lS_kY%E>mT=f z>wj>y^{@MDD1G1mHB`QYJ|AU2;``fw6Z4PT*N$i7^u^Q9{tM6F?qBW?*7w$5?vK_F z)-PoJ8uqb$=H>Juvah`t|6guzJD!%)+g41(>CJ8*yO$j>A*UCf-gZycy=+4)4VQ#( z+pXcktu5+;!rwm58Lw94pt3G(sxA&2+U=;< z5Nl*NrN$bosr{SvD_mp!W{n_gWH2Jw;I4Pa1{I?U(b!-Ns!<^!G_gEf7CKZ}1Z}hd z)f(Cj?Dl9g>iudBCwD|JJlN=NaK{A|__-Yyj73Yb|EpCJ`^9?YEDtqN-|j$OeY+!C zpH&0c;4S>M z?WcI2IRo(w3I+z--EHo`V28Witz~y(zn0w{t;Oms`w5XxohQz!aAi1vn1Mk}c5B&> z@jP*A*gd$afz`AhIp2k=!bkWYJ8$y6*~5Mlt6`5*SDeevICa&z0xvu7sGM&5pk1(x z*$A)O%dj$b4m>&C9Bzl8eK1yCbFMmLi65uN6MxAWuiinkvzx=s?sg111i5&}KZUv6 zoahoNEM@Y-8}{q=5~HmBhP~VXLI2jz_b(oq~=*HtJ`0bGy0RpTgYOkKtl!E@4u`9(T7JPjA@cPE_B73&V-(0^bi4 zsdT{^t*$%Q;5BEA%IbCwIt5v&md(xM{uurc=Aqt?;Rp{19fLLRL46+a>56#B(8byHl}0-EWNYb~*bSDl9Tas+-OYXC%3! zl;xUaS=jesX18n5CCKb{3%bHCK^Au*S>G_jqJmxCp2n%OKiz5AE_VbKMye6&mUGh? zp>8|3oaszy*yT>gcDf6QUuY~aD%urn+qK;9LmT^Fn2E}n-Ar!xpj$AUtP#p_ZTElS z3}!v-bZ1~Y+>GpIa_1YB?27h$Dl9OD5jk89Q+J%(&MV^u{W<)C86MT`YW8RFbIzZ=X;-(ypo{9P!l0|_qHas!I&Kt% zL1%S~^=)}ex~_0%c(dZk7T!!_rWX(y20_qGbyYXny(Mo-&vo6K(sw=gj&%48+>y7@ zJMw?w>M&UlQ7u`}Np*ysRVOven@Ocv-V9@hJIfmo^bclvJKO<~*D$7g@obIhyy6V+ z1~qTWyYh})9p1&h3l*;$1S;sRx~b$rvY?}y=FMRW$279Y^k#YegV|WW;5xZC~By~mV~snnz{_4)<>$VbjY=O1|w zy+$4Ck|l%Q?DvEHg1*5NZ!R-Krg-s;kttM|>Ulv=)kAqi`oUGQuF0!1aFu&ihHl{g zD<3%boqy#+=K=f&?c??K`UZVs3nqIXFr{QN)uwp+eS_*9rQl-pUF3sy?tcwI&k(u6I$UaFe?iiMb?g zcAa2?_c0S%Ca^ovyTI;6X$AdMUuCgt2jjg@nA$Sl`;-|i+iM->V0sk^FZct_oaMbKhlil7558s3Jt`I;3brbt*gysz%5 z!r=pTUlj@;st51^*TutPVFy(lYY*G=8>R%mtro!IXupgaKg%lF(~ zZhx;g9N_i$X5*jZ&gG|eu$s&6e{!z-A77)n?md2n=eqCV>*)^k26#P*@8$O4r#UU` zO^rTSKiH42P9J{8)48*#HX9z22j%-z9jtn|gS>%W4|lLP2o9u5U$WD>AFww_ec-;2 z&Ln=8JJUTZ56OP)rE&WamDcS}Ru8woJ4g*w{mB@lX1GV>VL5}ynQk58Qp0{|HzK>k zA>LpwFYh{Em^XZ>UZ}j`EA>(hpvFLmsp(Xh;ZApt$|JHa`KjEx)JW}ib%%OGyslK} z<_>fRsQwC~)7)e7sGLUpbhjSSDPdi-3-MjyFmI^W#U1Vq^9H&7RX;U|?EY#hS<~F9 z?s0ic)+Z;0TOYf?x*k`ZiSOd(3ANyr%EQf0Ey%;inKzt5{8V>}dqN(UQ{0pCgzV&w z@P>Pxi0|x9#xuq3=#KP8cpdR~a&wcLC!FM-k|*UPb|_0uLCh1-S(_Iz|r0) zuN`dfwsXgLqrJAUo!izO>y7d9h(>NhH?PPeVm9ET%*(2QThkrv4sxgXX~NWD4c0Z? z8txFZhC39U>QC`ghi|g3;nrer5FF(8Q?)QF$W6^WBDZMlHgfZc`n>CWA}>14pGwv= zELAv}%2WKwe%dfin2X5VBEQHdF39}Yd0CyxZ@SgpVdz_~6_~+Wyn+=>B7U+z-Jj;C z3JZ{NUKYU4$!hL!Vyj`*-P&ZBL2b+ka#A^$$SK}-8@un4JIR07PZy>QXHX**OckaK zg(x7-Nr9b}dC4|{yqF$Tbw^OODpt+SL4}+mhiKxy?RNK5hAG1C{tR>?)!y}8A;ekf ziZk*wJS)%0e6AiOf_!dXG@qLYa)(vik<_c=jzX)js_JH^S`Lw2GZss<1d-&b` z6yXGFPV^`E>BDrPCtPt_W@9(I$R?V*&D{KMKECStv0Pzgs#S5v6FI^6i902I;h_cG zTw%_z0I|8ktYl>qmE6(9R>CT~@Aw(Q^x->XjrX&#n^j~HE!^gAMRyEQ72UCDMOKyE zael@yLpYB3cl^x6WD%J~OSgraS+sInx)t1U#8$w_A#$8w9!~`~6T6v3Cehk$<&N<) zg&D&!>=J<|lNgO>jGuvZMv+0Zaa+3?L|eCwJIc=-W(r5KJK9f=CxfWu7jg@_mHdk6 zQmKR#OQjUcWECVQjZ8}{~l`Q>?) z3Vsz{A!k?x%MmW7+7kJ#TrS^r{~&(7{fFJp@9S^2H`%>lFTbZ>)z1-T537=wBP{0^ zb&I&=s8ilwMDAj_NJb(Qi)1npi4|0t=&qpNyYBDQ`NRI*?(g^Wx7aDd(2j3f8 z?9FyhJU#s$epYH{52wnB?gV$LT!EJLi@8N%QC{O4YA%xV?JailaGgEC@9(dp+V6HY za%_d_FOVrjaksSeIPy(IsF{|MH|VUfbW;9jVjF@8Wl+b{Bt!Ebn$w&q!KoFR_;}^=P5pjs0?N zH>|AtiTGG#4nM(0`SXccz)YoO_ELMkx!gvXjIz`Q7}o zZZ+%;cd!`ckMswNPtdQ)oo}`yzP;bhpDX#eL_R;SKZo4+M0Njlw~Slef5UwpRzrt~ z5&m$0h#2XQfP>Mms1Q$p`qo}=t-h`YrrV6Pr%_?LXpX0a-wZZ~^W>+pDQxC9^*@vIq#sUZo|7L=VZxIP{csYT#FP~k$}r|q zbAhc`Ej7JxD)XSca2hkBJmUS(4W~0Z%EjY_0l#IEK@~2rgK$2-Hv(4kZ9$A1if{(= zrbIZCX;dLQ$-?VFGX5UD9)zr&aF#jKbi&z8u5ySGp&iaKXPb8T9+R(Z{7z`Gw&7f+ zVeK$Sh~XlhUNu~tc53-G{nO4VbUXfdveig2LhLeswtupBnZx**+(q0lJj28=e;0GE zhKrNVTYfG7q*L2}3)b>aIcJ>HPEG%eQ`#*BYw%NkhU*&sHmb#wvqp)LBA$r#lYN4$ zlg?SEq+h~6>y+|K!ZYYrV&X|#qs1r@PtE$t-i`feA9w2bwf*BxUB3>j?VoVYkzK;y zh!uzD(0H=ekM=U`2YZV-MvN9)sI%2PM%Ho1UF{mgaUbB}Bm5}Liw%yo$(!NOqCV3FY0qJFR* z*dSORtQY)7Y-IHgXCrO9bHW-HH8ko3YfoAy#R*Y3c%PYHi%sZaZFe@&wmGN7N%E&? z@xiYcy)V8J4TBAW$F1Q}!=jF}!wJjetFojiXQNQ9kWJ64Ualzjf@%r4rksy zR(&PziAKSO!K37lS$B!=iMyh4uu<@?XcBB3G+1lOBaA9-v{6wbqwbKuD{g~#z^1__ z!CT;MaZ5A{HVxhcZ;6{CDcCIdEPPg+5oOHZyf>cGhJE8b51$dI#q;npI96;y2P{@> zwhD^U%qfG0>|5_Qubf$yndNA&y#maM6$QjrG{XvrZRm-`iEYjTa1%daabf}ba&hdi z2`mWz$}2t#Cx_$tNlOl&7N_nbCWoKXd&=mq;iutq;;eYVtO-#sXyc<2dEL@x zd9-R@dojF90Z~ZAiTPF`+B~ZiqlswXzVqIC6`1uJeC@sR;+Zwi`Xzi`oD;vW=hN`Z z@Qd*HsF$>HQTf>?M&uXUQ9;WucA$`!#eC(x^px`LE3YKGl`=1f$3=~ey3D$9T;`pJ z>QqR?!%xB&#Ch?Aoqq}EV{Lw+RApa!C0JF`EMflcz4O9ij%CQOn2Y*cScKrmta=iD z9KI+nh%4bSQKO@-gvUmW0WZUO*(aaKD|VvRb~St@JUZ$TGarW^g)fPV!V`wnr6 ziUxP1CznU;L3i#U`JclN!&k&*k-$F1%mnkj_lK98(LCa(@KtdIydoZkbCJm{atWnn zmrE!uyQ0igTF39bqTrw2d+!1Be+oYcUlUhFPUhqig~=B&eCiKKpiIifaky@k@TMQ{Qxdj#R6vQcn6h)lEPImLAdoz3^e3M;nxp&;_;cMYL zu2K@bFbf4yz2{?EI|UWcrE z?0VR`?%odH3SZ~7Zny>6A;xl9;NlP zB8}MX-g6IGyJ-ilSk@MFuDN%@x5L-i`MR6JNpN0xDQL;w6juHNPKMXAb{)Fy=|ozw z$KCB7wD!;rSXbS<;XC20?!E9`@D95aV9!{mfRopZHut)F+ymBL+J5T_bFR8mjVZ=I z-c;J(-WqmWi#mLIkxs-gzkn0tDCOsAsGR@p?Q{3KXdJ3$t!B;|ROT~?^kTJUUF9&nMEeCl2xmWyiNi1tMf85pR~Y5`Drnj%TNH z(t>IEAGpg7K_~3w6gfng*V*TWY5OeD$|*WTl;=CJb4Q#Ex)^_XU1=Y@u$|sX=Y-kE zL)kF3lgd$QhpC-_bI3jD2H4YeJST_9EF zJ0W%p+h`;@DIKMhn97NA4!eikDCdZK7(B#|lKrxasz$t7$gGN=LcAGdZ3wN#j7|pU zxt(2P6VGkQoObNr9xsPE@GC2Ylk6$Q#gxt~E2Wdd5$qY|R5J>hab`7?-3pm)BWnC@ zncvQE*)51JWF{x0lWb=bSw*t_9Cn?fO zr!5W>^WXqGxTs8Kb}~6Os~o2WjtQ}54O+C*hB+VMS1})M6LAoTva>jud6bu#vcKgV zcaOOit8Aw=qiqbqD3==TtWFk3*x8({j_I6mkGm!_Eyo}>!ISO@*Kkg`C*4-8YK=?A zLfB!xuvCLm@~!=wy^LAQjb*ACU&>`t;ZhtEh*7$mC*Rp`?RoNd z`yKd}HACc=a)~j7w%C|Uex95w|FD0z=gRl?ANEkW2v3lq%vuaC=H1UBKUdC?f7|EjpP?n7PzmV%Nc0V~JfChmDo?3OkRpfcXoZrOp!P zjkT2a+FC_6x3kJ#3D0MA0r=kf!&=6y*VbazF0mKe^>FPNZs&G#Im7K$@RxiqCwpHq zKtay zwddGP@KTu}|Fi$KXUH?|f8f9NOgUYib1D zHSwk#jauj^IZ`&aN6HrVEAyo}!g)m-?$pw<^Fvchvr(9>rH$gJrxyN|qlrh`qwMP1 zSbGdO#;&0yu|sndNJq<2vL*YB09(MX(Ka9MyrvCvUa;p&^MyIm8R1mZ#@S=-YT9^v z95|L;YU74!*|ljVs-~l5QbetEgiL1s3p3dq<&1Qa&C$*%=Z!hc84A9JtFlA2h67`PtR9^J|9Enk6z&Ume5l&&)B-Xy+NbJx6782;Y}Vn|+8=S({`}v@5ei zm53^6l96a9;Z4(+RZY-x9V^Gk7{FEnczGo|HLfMstQ^?dx9J<>oHp2E~ibir-D=M^4cS2J~khjlbnf8UFOt7L3V_1WNokxs#BQ7QIjo=J%)!HQsx#8~8YTac>@dpM%FJyzh8Bfq zpyE2i-l$hbPj@40H|cY6y`19ArA>BbGB(`?;SG8f^msQgbE7_j-9{QCjBoG`*up+r zaVJfH=i#O~*_lV1#`V({jOgY7JRx;@RFg$vtsd%a%Ot^!tJ z_jSbU!D^@i4`YYn_(FY$$H696ZN@RR1iX>9Nn6XDb$IAiM`L&>bB5t4^*ufaL%^Xp zNBw|H!UpDV#6z_tyoQ-;@!6|kSGQN|HSHQ;E!2otlUbv$B3=znmXqWveG=cJEA=UI zvRp}Km3~i~gNxi(_=nEccLzQ;dKtR|z41}n9oPkbDi+`?`lq4;1sXNzOnq$$4ZB6!ZC08z?@72Z~4L&*siRAEURiGtk%Q z1NJs{1@3Bd@wU6m*Kki8AQs|hI)GRDMBLHl;dXaNn~w|L9p>DPIGL6O%i>nNgB^AT z_VU&AH1-De!2QJ{d{O(e!vHZz3=}_`gJ=)UZ&*?aoEv)WHA!GpCQJNFmc0t4`++Q!=L0p+7w8uj1O zI1b;^7U0=;i?z44reZK_n~I;z2jD~VC$ld*^b-e|o2YGNhi!qI+Cu#PZnEl@)=V@N z56nKy=_~q(rP>nwVi(~Rc!N1NwJm{9aK+lfs;z;8_!^hQ=`;~Oh{I{3mL!_7Hc9-5 z3q}&rk7jSN3=i4f?9)daVpd6QbKp~)wl=fRmcVs(zJWLGVq6HDizM-b`LS4zJMG7; z>Mb?}2IAzkiTRrY*R&;g9bVIx;(>UL`Pa2x%=}pN5-V`F-53~z+td_9cV1)2j+nb0`tLn%xEU} z1$r3Gd6&><=}Gq-Ss2* z(;gNrMGMi5xVwIc_^>!ATEPcJYxp41A#sF1{UOE?<~1j7PVWfwT8OT!>ZW(qkK%dT zRX>IcZV&wse~&%%lKh2iM^~+>2UAe(^2oBpTbResaPUDHq zGxmsftk^@_E0&4RaG6^smcn)LC0(VpXMP90y?z=O;@!;LBX*1Sa2>w3y0VU39at5p zBi9602X>L)Ep~|xYMlA)@s~Y=n{ivP9Uil1aXj8BIx@bKwoBAzRUP>e`L?*rp2Hb= zhv>xk4%$x9hRjDe&7Q{@xs84SzvI@Ra-O}2`*ADc*2GifMXeO>D)sbIw7L(930`SgO)l1^|QXi++;$R7! zU>e{9Tij}>H_%I4-94_?6Q0%=%XN~WQel=19Y*h{b);b5D`*b{t-Cf5t*;HN0oMd-%RICWjUDdu!MUdy{=H?{p&YngtP}BM3R`9L4Pw10L#C`A%i4lotXEN1kcF%y zJc0``C*CT}oH95(ZxkCu0Y+oJ7_b0XNmi6`R&zXr%!5*tM#^GoXm zt(Le67i2Wf%Fp~5FCUm6tSl?ZSgRGj!LiIKXcZuiwKOdSXO=YWxt9VgE{lOBWO1;$ zO!hR5zZv3^vILmcOG74|mljO+o`c0C|DFb~1!MH(t{b{KlH44 z@BE=>vEJ)9g8B5C@yt@Kv# zDl5Hoe8nq?(s}Rn?6?KJW6$695Bd(VU3}30gfFwtmEf)5&0r0Ai&kAOW}hYAVlNB4 zial^3&~xB5^p+jo>3^|$yZDQ?O)O&0VsDX`75+-!Dz=EP^lf4*_!qpLU8~DW?0-3U zDHw<2^l6|dLApcbv{@a zKkoCvBKUEi=XEax&k>&w&STYlZ=RPE9_@`{pO?&krN7jptvuEka+>yn_@(|r&uc|n zXM;ucBKld@o(s*4L6^c zhnCmdZj`|Pd^--ICG-lct>|7d9_T;nmsoq*h<5Y1dA(@Wyz-1zaLc;~g9n1;-9y2H z!5w&J6xS~@{}OJdKjDd-*Nt|gJk}2nw zbq@y*197FKhsa;etb>;C%=%Vga4zQ3bv5{lL}7;Pk^U_Cxf3b=TrHKJb)+a zC-NXJsV!v-c_P@7c04$M%qMbyJcO(20C^bC)mE~lJRWRCI|d#LCc6FQ5qw(vGde)F z@S1xuZVOs|HwkR+C3ywh7`G*V-nqS&UVi@cTY4?vmi+0@Av4FD?KSga-2!eiW+r*9 z$jt_4d$YWz?e=n zAKOnJ!&Nqsbu+z0Z-zG=oC!B(RTHp~8|RiLH{EOG#k+;vMr0a$WxUd4%Fw2H4ZXr{ zyxWk`MqV3P$}Q=(k*(pr?A%ZGmB(?U?JG|h$BnYAnC6wGP4yahMcl$}1J*Y5%8{E2 zPVpv#Q{noIHUNvdMch8D?JN7plg0_7JmZtS^0Y}_Jx1$;32srh0=Y?EMXy2xC-Uz= zMWTsbZ+Qv_mfrFy-&?)ep^vP@ESzA-^p+pXU-hSYFYsg8OBS$xC2qyPDBaw4vaRgy zc5~axuEgEku5NqTPWEuSlj%YGNOmF9)$Qr_a6giriMzO+-43$7?8Un;>GmSqhPWqO zlU_-;rdz@-4wi&FF|)Hh!WiP zZYSAMwpa7rc5Y|cNwy=?-fc_V&i%;kB0I~Eh}*hth(B^$yIo}$*_ybG+sf@GyUJE% zTDzA+_1wDPCHP{fzN@gFdnt4!RF~Jg5~}Cb^{#|2)4LL?!>eBiHE`>@7npf5bTw4h ztK(f&bG`GShHeA*Jfjyv*BGheZKl-*ufgX+jogOrIp&-XZ3%4-)%Lc8YI!xm+FmX1 zY^br@$UPfs;x+~wG4D*MsoTUoL*{H~YpAAI!`sTbn%*{gHN4Y|o(XLys_tzMZG%sR znz>EgQ{+#Fc7&>VRlOad>RvT)JA5*fDu1V9`?h=rDLRbObyWItm^S z9Rs`Z_oQo;_+Hhu7JPlWW@uC8RB33_sE`}lO-^wbS`w#{3~eDNym+j7zv zA1BVwljmlKp;hP3k)ieE_K|^4k!Kh<4hW+r?CQ9ckn8LfB!cR*tBIS#uY0J6qzMLDHnb;>YDi)dHjI>NzhDel^ zoS|hyIm19%!XTTSo_b}~PaBESfN3=ooekw=Do~7&2qgmuXEj8eM?a+5|>gfGtp{m`6L8U7)g{TR7WmAZ!(HenM z;puQAuo2oOGhl@cwEAE}SgDQGN2_aQ1ncpxW)amxjcFEfKblD;cql4Eo2c^+r9wOe z-J#9&hENR}MrH$TBQ>Gn^w!fhP={99N2(hAC3S11r=+Ua|D(n;f?4Z$2P44Y%-+V> z=aEYJ7u119l3mNY8%eGGbM3Q8#r<>Y_ey(e2mQg3TK;D|2iQSoCv9Nl8O1=JObkQ? zYd5`tJRA5F^(ytW;!~ak3_ww8FZ}`F9#}mc=uf?VUj+N}4rkL$?J70F6`-mOUM0Fl zl~Pq2uM@4%u8_Y<&2SabWhz9gsFA9=rK)8v*KShrTmq`f=S_0Us3@vB(k0quP}QJr zF|ve;qCxK>?UHtz{$lVJddq;Fi`yD>1z2tpd0534_4{|5L6IAE^AUdJFVDu$woPUt{6IQ6| zeji|ks;>AKtWZ@f{~|hq#^_(f|G)}Wb@5+Vp{h6kOLPz&&wq)Po~J@p)lR2B(|$$Q z>R0V4m=4aMr`Ml?PqklA<$1=8G+o2rqFqwIo^+(#zD1klJ9)X$QRE(z9voP{AYGhd=__Ov9U9_ya!iU;VsINWHeguEg z9)Q{49O$$C7*SMH_#^6H^N zg{j+w(M>8#FRUk$DGf?EF`|c4Dx#KCia1eMHJ%U{LW`+9%>~QBB_p~$C7D@@&uXdY zS70mvmWM0C0Wg3vRV7rh954#5L@tWTUL`V>X|}HFe0HRMsL)2^s~W7()D6&rRi)0L znpQo621;3ZXc|}pZpUZr!l3%B-4<*|)wCU%kNEsk6f8=%4WF74zy$go7>ftn!>#!w zSqv=3SVyvjzz%RL-cxa~IAf~HTL@J33RN>!sA@8ui3;kf0v$_zyGsOBou?~N0bSL+ zW2kF)i=e6?^`NIv)reGmTcN7DsoJ$dRiCRFsRgQfb+kTGZ-(B`NGf8@^wC5LRpo62 z)v+WniLv2S#F~T6>5pN&DX40F!*o?E8^$|m3ASLySVo$FsvbC${4lhb#uAUCHA3G> z)g;H$Yot$r8-l8WI+0pxJ+J{hkz50mttOJ0Osfk{f~OGG0Vl&#sa@9sRSkP8xjJY( zsd~9mj;f_A#iyD)EBqX7nYEyL8mLra)}jOQg}$EtXFTuwAN|$f8t_Ya1KGjgdUzF? z)!-0#RYdJ%BZ@Wy^^MFJ1a5#=l3%57qBl_A3@aRn4$l@?;iqWzY=spn&7W=`=dv+16J5i?;Clhtgw&X8|(|KXTH687P~8gy?JjJc`~#FR8NR55?w+iatTkJ zE)y-$FOa{8hTL-aJkNxdgUiTXVa6ixGJKA&eFeCJv8!Ykf>+?P%E)H+jA|2UO1)Z<3pb0_jaMw`sG%TksvCS>SE>E<6iVPmJ#p%|wgy zF0s<&RH&Xdzd+0H1b7O5LG+R;*$ET{Ro&}^o=jfVsZJ3+M`P|3cm`IrwBz7${h0oY z%yaN8{D#~y@Th(SJO=*;AEADAmKkq}4uikJ@8HAWA@m{N5gnpZ`i@vtOcfqPk@7vP z@Bqq|f5Hlt7Nx3rD%^|4=Le#_k$UDHYKwb#SE_EgM^8;n=4U+>nA%819p(}76a6uY zG^wfOq$Ey-Cd?C}6x3m!=qVyKnY4^O)YBSiU`Zy0kq%v)hk82NPr64&^2tJdnoiHi zPv8S;Q|XBw=o!%O`BBe^0+7NV^zT7c@5*Fkq@tD?1tW#u>ED8?!j=Wqqi<0z$`ZkE z^>5G}%1RY3o1rS5*@(VI_a~ciAHAOJ5meRF5{8SGNC{d=v>yX#l9VC}pvo9zq&Tev zns7=vq!_I@8j?|{mn1SP3dOiEBMG!(MrpDRm(w;?LX8M=7-El`e&2jl6hbBhJRf<`Q7xQZ~+oYsPq zkFiF9$oa=u&JYzLo5VXS!kNmpho(p*MPFgM(lTyD;Tb|q7lmILet59JJ*It$SlR;MQv zsuO5K$f$D>>YUgJat*--oNXIH)PQH9O&I%43by}F#(8ACjlQ-HNVbsA8e;;9AJ;>_WAxF%<4#z(LQ z=R+qD)!=;01mcObYMghO2&!{03e|bll{`%!2o5w>87p|YIS3p?e>Is;!By~bo`Vhs z2Q#*Y>?h!Aco|PyKLgcM*JVV@IhCzW4y-N9|}xyWhN zv*0-@w+pH2o{5}URn^}GRD&0ATJ|&AA+G$SL2GjGm$%eu>k*mm?>HuS8BGs~Y)iD)3i0m3%dFj{0ikE z&!9#>gA>`R=0Ag4{B`0RoU5J+s&m?^K0lSZ`OOHbQ|hXUu5b$P?HM)D!}tpvA^Md{ z=n>;7_$#RDqED$>9>cld8FQY~4jIYtAvDg9GxmbsAyCzRpOETp3 zfG1%*Bgnj>?Z;!{RRmT2`3*gVs$TtuXfNIwZ;0Q*3RQjk9js7QynlxkstWnJODj7Y(7MVK5YJMJOqC-JTry)05$s*_%uE+Lgpj1%0rBX@q+vj zZTyssqjgU{gq!3K=<}yyf(#{0+G+rSLDjG|O{?N#O^aHY;#b=}$x5Hd6Q}?=6WN2r*_7XVwdV zF*sy2BTm9cBZk`zE$GLf!LQD=H#OtnrbNx~=E%?eh?b1!M_)gVY%6;Cz`WeiXhoFQ zYz;@7jd_1@U>x(>kc$SRxn1%RtS}EZR@%Y}b8+XTEm1DB9h}o_4=c>cU7HTD!W`Vb z=?E*#&JCANw5(u9xFS&&uoL`+*}$xC{*P7<`~v=*%opaD^y-0i%{pK`_%rgKgAL&! z+Gplavo`J$L&??#hrojv9Sk;xhmosg4u=)iGHaS6V1+f!8mMKCh+qwT zG)B>?fg|D3czaXs>CeFzXFj>( zXtm4-=P~093Nkan+3*==&BoPc0b^(B&BQxwCVDvM=*`4$W&vYId6x^!^JJ%k=im!O z)4=oaMRa_ofYacM;Fp!A5*$L3Rd`@#JPV}@y8n^9x}xF7t;nL`0a;fL^mlZPI&zBV0Vfk(kl<^xk&_c;|T z$=(M&IE5vxugsLRdteGUm35Ev#;L57aBAxgC#6$ccR354+DZj0cb(g2TKsVos&mL` ziEf$caJ{){rpL2J;Z05{E58_pH+XOH5f6)as}LL)@u!F*D#SS)9WRW+RyJV{E>K7hsHk`d38lAOBwV3vxwv8a<^f0~IA|CB_|alJQ7N1RPcN4!x=bN=cN zvkWJu-kBL9P9^HB)H|~Yej9o5<;ZJA;~S8dULz|X+>~527;WW=IDRP1W97yTK%IhU z$SH^XU_NFyAZ`e%lMhK&E-NRP8%|VOCD~d;}}Z!ug!GutIg-sx46_JXhKhm!)L@+rfizZm0>?h6jOz zt%2Ymuns&Bhk!cPXJl)l7h9M9=lDic2W!HgGg1>Z*}9Bh!ea61TSECA84gQjmYSs|AiZv8gSOpi4VX(qVc$5qys$>m^E21GjJc1SR9~ntc zVFesXM!^cpIR#=Yrwh$HIJ}33+@Z{ zhvyS5;Er;CqNON7_W*mrOPSltS_b#vR`CGF=hEg`%h8hV2KIoLGu{L3h~;Ef!V0^g zKD~<81zZWQhP!}W(70X$E9{Kw^;&eXJAj?wwd6XXMzEI5Xj*%49ek9V=QFu=el&tJ zPzg9jG{ZVV{-|}F-gN5(Z5ntSK1}`yI2%61t>)R_Z2Bh|p9W4vi{K>DRO=Kxg&U}I znRSqMh&%q1(J?qpb~1PhJ_AnzCs`BGA2%3BCK#6 z+6$LxW5A2BQUe$Rj^VvMqO zeoEVlf6Y_y8LV(CcjTYL3b$~xJ{eZH3FUxfqD?r>Bon`c6>dazKsmxF+`xMi5jP59 zJFp$`p|B&q5;lFuj^g&=eJd*BTM@ADS$C~~{grhOjDoF*>x9L8n;T2t(RaD~c-IQj z?tm_AkTh2o_))@X?b=SmbQmKiKN}IQbc@J)VAOXlua40nqDv+{GhNwf3QV(d6u-C~Qg3&Q!-ttYz>xxcJJ_6Kgp z6(agz#gqHf%FBDwQPR~>;w@~yxBjpSlYI}y!$rvbVHKtQ4i2>!qU_vDie{`ay=-7M^sSq~S-C;h zB!XE`-EJCDy>13)=3ZN~2xdl;yE#3D8PWW19#Q#j0cWsVa^Fp122{XX!3xu%q~3}s z9XHKd5o=mrURl#P5da$e32Is`?xAQ}G+&dZ)wXMab+{{~X$Sdv(6qVyOlaBw^)DKC zT|Th~aD$~94!@s7uo^dI`jZ&|)`0tg{XuoZr5}6LvZ1)6v+5aO~ z9xTs|svcx|;@Mn|TU}q0D`$5n(*sxLvfRKLLawacjZAm^mCJCOZ78`ic2_dp>@Hwe zTi4d}FOROJv0s6Sb}2HY?L=@i|K94_P*&;ME584AP2J?vwU2Pc)wQq$?gbtwmX4c?9Sk2{x#6GwCLsQT5JBMbZr=4lddVZXa1&m zW~k9#fG@OEY?+FuI-CLK>4(Ni_MzZVD(jlIlG?L|C(5tjuexVwnny)Y(~43p)3hY2 zO`7%v^%zZCO7%k1PEy6tw8wn%*EE+;lbTkD&t96=m`^PlXG#`=3;8Wr(~k1nu%`XQ z?~$73@SBLH72yBdnpU6x*O{DWX%DvN|E;E0mfs&tEdveJ8MwW`z@IX7bb z&4>5DsSKOiS5&`EZ8ueYQ=85+3sd`;Co-m1lV@q1B;lDFU#|Ww&v?J(NoY+ix0VOY z!zqj!S}uAuXf-*#k&|9^S`E%~Jy99X&ZOtONgB?~ zl%}Nv(~(UiQ<}3Kso_$zM9zSuqF0huinAdp>6M_B0*Hv{d{~stCKw@{k(kV7@$Evn(uBM)amxX{5*RRj}^?Cn!ivK*tfBxk^uk@c+`p=jB=gaqq(eQNG@nulMEav-x^@zMh`1f9UHU`g)bVUZt;B>FZVcdX>IjrLR}%>s9)C zmA+o3uUF~oRr-3BzFwuTSLy3j`g)bVUZt;B>FZVcdX>IjrLR}%>s9)CmA+o3uUF~o zRr-3BzFwuTSLy3j`g)bVUZt;B>FZVcdX>IjrLR}%>s9)CmA+o3?{Dt=(ffY%*|#4`yAkYe)?>tcC=21UD$+P#|EDf=I!V1-*?Q$#3ANaL?Z# zS&WD=a*mv_=G=k~FK@B--eYHE)PEHD@Bfc~{m=iGKmF-X|M&m*fBotI`G1dp`WOG| zU;c0Z?YF=Fo4@(vAOG_{`24d?H~W?-~8Pl|L1Rib@=md|L(v3 z(;xrxZ~yim|M(~SpMUcY|KUIW!{7h$_y6>-|LcGJ;J-64!<7`r_1s5?EhRZmp}i7A0HpL)A4Y<-;U4of6rI+ z`}LXgq5pGxl&?Gw*Z#A^;b=cx{nqpI!k7NZj``ca`Dg#@`M3Z6=UwU^kB3NkP2cf& z3k^a z<#MeA`IDUvcl&Alz4vouoPPDxsk|0uAJ5O*@p`^pZnwt~;VFzeKJVAt?Qp!E_%G-C zSt5{N-1&lV?GkxLNEgZEWS1&}_vaHi8OxNUFaFl&N;ciEJ`RWLdHfv{-omuHg1 z$KCYowQ#{Vw<0gp1F{MEmOw&*$ORpq`wDVuX}bB6H4$r z!N1%2#^2IO{LA(C+v9S+93PL{;lcl%#F;&L2qc!*!Z|Hsar|4 z-x^3vbMbn(zD?rxWbaFAIhb?z*hwey)oW}?+)C>8@JPCi>kE4WDznQzP|Em7TSB_68H93Ar3P$HR zT)0=_r}|IzXzSnkKZc(B)Inb&J7g%^$%zxjR>C;I?_3<+{jA8r8HscF(6vM}8_6vK z7k+EjKR?d1NRljQkvBzI*Cz7Mdu7hndWpoS>)t`@S3ir_67KnNnOVU=p*+sQm`TR- zDv)dhzH?RI2qYg@(#BoiwV~08X$d5^OniB=BB&`M^_!33y2$Qww()U$J0tkY(VRNI zDXd>`agX~$s+dN$~yIJp}s(W07RP2TpBnq}Zu za(3W(oH^YX90E826|{fuhJadtxc-H1#!Nofzq+eB>))KD=r$F$5bpA~dEEV0?ecwz zfC2d5Bhh{5e5v1w_Pt$3_?~Bz^;qsGpn1b_cx`GdPbJQ`z(_V5q;$0^HLJV!}EN+pHFv? zjVu2Sd{z#8e_p7@0i6;c-7l-uGhPcNkMf6Jeaqk14;YyX1XpJ(qIw}qe|8z8wqrz| zB%n`>`}uJ_Q%viO9Pms;!r$@-uh-M#irYP?G;nw%A$@YkRCG9I+=e7c-w!A{=tGa@ za-N`7FE1yhe(%SOMQyx-)XN?mO}{tZ{;GyJV!v4{e>E^&=v{`M)B7RgOM2`axzn2@ zPFejUdZvE7d4MrJ{bW&g^qU7)?UIxYhx(Uh8hTIWEyq(XbljW_VqPl4TNK5+F+wB% z)3)O@k0@XB4X)1eyB*%F4BQ>(QtjpX`L;#@Ih;H343wguH9@n>!pvDB-^D$7J)!@pPV5 zlR{#%lFoMj(L3BMz&_-NTt4NmvBhEGTS!Qr%-aOW`3Wy2Wa0j=mwiw0l1Q^yUMLRF zL)trBt`m8Ehm}DsEf(9T(z~J9M)qIaSIPxm50k86#Yi6s593WUJw~Gs5q(Hqj7iYG zop5t=UAH8DOmEs@BCIP$dKzn9G`#zpH;8X=QKSTU=yx@c`V<#$7udAdP_p8pw+SsU zi?*nye&JyIW))==fy0{$_U0$L2m-WE;0_C$m<|aXoov@ZnmmTo8T)J^9X?gPP>PH9 zSwqQBxcKsDQz|!{v`+uP+5JCn^qifaprFs|{qR_IED*Cjsia?Mt|St9)=+2s zDIrE@fdO|s9qnw{l$Wo5LM2d+bZL7wej1N<-X-!<`+nnxaBKQ{xUJ(QS@Jp3O_m~& zNE=4dsZ8bSK_R^0XYpi5;%Oa?i2QuL!OG*|aHpv_#H>JFe2MtyaG^{1ajHT7>Pxk~ zO+AyR8~p%JF7EM2HU}Ti=t@Rf-zBn`3xBrzEpl>2Wo?}uh=hGATo`^PneCq+&k30z z&|WF8k2|Gn5{uh|F7-=^!dDz;1-eaP~*~-mjRUqRFdIH3eV)<|LUC znSE}a&w)%DMW3fD`QGV4D=i4ZKr0)W$1~!Efw>~*SN)G5v}l|ER7*i4ot)0NdA^$-OO4BzDtNK*NTV5zPOz4d4go9+Y_v;m_$|V&rIG#;L)~F9><5qq|roI#}EDup} z(UZt-S7;kO(UnvK6abD|n(RHD!r>0(5VCY$3g zs|FSs!%7q}F|2{a_}Af>mxMI{TYU3eX07diHB(6m#tBW)Ty~#w~XHb0^kr9Q3 ziEE1z%uW2zg*M7g;Yu4fR_>NoMnwBvdm|dd-P2;VL*iNzJB?e}J1>#WfWnY|oXs|8 z

lIuDQ{DhGS#gMif@B5iaBMTpXjm6Hh%%um*ZaYjYMaCmws()aYE%m)#2(GxXO% zo(aD^1EX_A?7E0XJ7d--eCT$5W=lD@^Q;}PTbd0AAE(m38Y%2qa#D6%Wniw`(zR{wY+2V z_YLElnkdJUofdK39((zWXC$Hi_P3@fBu1Rso6GI~nnE4|_;*g>$nFnT_kGDJc!0G%TGewP4Oq-&OJrN#v---h-?C499 zj6pXVte25+?q-K=9}_wAhMmZMv}LkOa}r}J?WeE!*1z;Nk%Rlnuo9?wW<{NaX(X+b zL?mq`YRM(&%>#Pu>EC0)76%{tn4p=9?`+etqd?Jx&`5Nqu0~fcDICjqlg#ahKBe%O zZ2a;nvrAz-*kftCY&SLJVI;7S9pu|SloHA*&L4Of(P%JTQ?Y`O)9_@FCr#w6oY9H2g9j>c z!y^yhdHIUU!IuDgyTm%B?2+21WKy}?=j96Lk96vEKatsLP&{_8v7W)FhJuloS(V53 z>5S}*nklofJ=@g&7(LODIe2*GCiR;?wLedazi(10aza`2Ffy@SVsC_Yw0o-^oFz(z zLM(B20Qu>d9x<|A)}1azkoU{=KpF39rJsx!c^+q=TePs@Xl#EPu(8vq3WUH2tFHlG z2MZg1k&D=+(HH7UNhC!h@Nj~Q;YQDp|5{SRZTMP^{zzak?VfuS2FamgC23sQmynRt zXv)w0(Jh6|9!5`irU((ZxH7z*#DOlZzQmrGG?6pNCW>l28)eTQQyD{raWK&IF&Mhr z<({mE)1)x#;p~PLdZK|lkM*&c{BSht2{9U2M}0$Hw$wNnVdhzKtfVP86Y;Ewq@&c|~M!ME2m;9zZ*Tt^3K@^UzFJlYt@DPA%L z2XxhR9W-LXMKOCi6w+!-Kc(@e`13um%FY%QNFbA}|0{ptFgY)#g=IcixsEgc@5t$i zMX>usb~(+`_}bdM_);M~6z)`wD(=-?m%(0{(B?!{EJI|l^tiemK5k-!D6YZx&@|k| zb!%{f%P0s!ipJ@J#mLC`*Rfc7PgY%QQ@Xp0Ni~Lr8=x%LNgM=l@nW->BYksk=TdgG z;0uP`HdTqD=HlA}7dL|3N!)TVeCe3(L_MpAG9#*M8#iKOO*De(WUgUFqjxN7so&AY zXw6IFnUYmCT z@U=F@S#DCC&d6*$`cPyWmGMT_JNd)8J2f$?z>E!UB#l+k!#y!RtAVO;Ho3QfVsO5^JG)W^K_|0Wag@-GZxwEFvFCe@8H}@EJdI0N}Tbj z;YH|eOn1Yd*~^&XWCTr>B#qTldKU-auB&Y8Wy9Ep##P#OO3oRbd8HypV-Or`yL?S# z6i6#nEK0eO<`=yIg_A2&kPcw+)NfNMa-yOQksVd%#K=hFsumC~%X;h0T|_5RRq|6B z*?pCwF~}Hmnj>MYG`!>SG1?;2JeESizWE`_0e(+%Y6 zJJE`?arnr?YH*@oP8R0QmudgXVpAo0t3$tLV7vRuTNnQza?=*oJOZN4v%t6-D# zKO&93ECj;bnK+;^Sf%1$Q#7jTw3|gnF^v{-Ok>L;!_mS-qshZ7BBNV0`3=`~PFKk_ zx0|9e$SN%)FJ#ru7KF?r0!HM@N_I{Ti1boV9X6XO)6bEjF&dnglVV2W+G=`fjV1@E zc8|tj#tH4SRjV5-AQIvlZ6)sv?J;s~Is=j61~fjy7HwX(Mdy5z0eREJ8ll0WXrG2ylVzuUDN4p{R^>B(vg6=wGDT3Z>B@h1$y_;$ zpqo)J{H*FP;HGxV?{iZPS$$v5@l0Rv<$gt(ct(=ulf&;kdGzE}wg*cAc$SN8fD%3y z!7?k(|6;)jZRW?N4T)bov+bR=mX{;%rLlC^u8MsxybOo36KFCfRDy)djRlJQI&Y5g zTUmd>J!N!~zjuPqO^M^l1KKwWadi9?+Mx8R^Ws-|O>qf!UeU%L$H$o~G1^qB)(u_n zWJTn-bRVK2*;;a9OFe(tkp)~w(>$KfJ8+S_>A>~{-ta7EfkmwC?G$x!6hYYkqg$h{ z;Ni$3qzA1>TJ&fmLJ^G;C0k1ti!Q+C2n>r)VEyfr0p4@< z3p_r{?xAMUlLE-2v6&VVr%1fH#VA!fOEKdt_hP2J8Q=wX=tj@f=vPoNZzA!g?s#FP z{Ni&heM_5he;0GUB#rk)yU+FwLoaJ8R*H{`(1&3^)(E4=4IT+>M;@@fC@W&pAVh!-A5GML;2 z_u)$g?j8NHY+EP{4e32^3V| zT;~r`*BG)8<@&G3^t_NdzLblBgpyBUpia)u zNj(b%e<2^4L!9)kF2ai3uz;04wu*sH7zn2G*v3gL$GD$$RdHi_(T~@DsYI|YH^zhI z&o;kc&;OigV>>Nhu^5aodQH-|k7UD+^L?6Eb;%S(KnUz#*iux+FIE(JS*(Au)1yz! z$w}(jWorEwA^eP*|1sQQx8%D);ffp{l3?KVTEwji%8`lmE+{r0(qp75sewBr9#7U4 z>e;L(kcXu({Dj!hkQlm3?pbNOPG8aJHe#Wt9m?htNQSnQJ?^}bCisxGs?X4C@jhMK z%gI>3>nYO;z0!qBSiEivxz9PufTckU*_~ZDW~JWMC(;~y|4EQn9DCzb!BDJJ%M1lT zCl7)(ajv5HAkc9_vEKevb3RW2p^TZ%qYu4zBh3xZaPUL-Fn`o3>k-wIa4 z^0H5@#rzGEJHdY2YeL^Kp7p|X{~4F4b!H$aPxhWsDY)Kg_c|BQ;(p+HwG((W*)2Ti zvWG)r&mkQWpanD$^1BSZ01>@Wv*myDn9%KMN~NvyNC8vG{DiiNoSR}T@@$)cFR`=P zniuL>=FRj1DW|C7n1qAi`S%AzRHUD!f*5KBtXSW!P5gl{XrP*T<88egkG&VdaOL1R zyoPys^00P+sDw$A6GFfKfW1JMu!C&Xo~8I5mf^aobWpToi8d;4a|EooKHqq$5f)PA zvWZUC$BUoZvrG(ilKpCF2^YidGha&_!PCmR7#^ag_yOSqrpGC4U~Uq@$-!#8g~CM&66cco6>iK^=>M3Aav(=ITHlvC2NyE{5W{!1Fbr+2D4uC z8TgVzv2h*=3XB@v3PcfFi2XQkp66_2;k+0TrJ)yUvt-?;1&|)hiY{q-qYKd}lwlb( zD0*dybeXq>CagQk!(#_}jVCD9_HO7}N7%$2 zzt1n8Z$Msn#`eKxzAA$UL=cVda|B=G^sRSfm+1m=WS4|pGBMburd zi##9-b*$!H))Jbqf+%RUg1omyNs(LE&5Pd|i@`lj$O<+P1B@rZ#h^)QDW(pL_0pb4 z*1a(JRRsuh{KTTjf}wOvF<5fEy%-q8HG$$%2`<-y?BW`zTk3%iu#qfLi15AyMqW|o zk`=(ea*je3^2BB0iuGJC!Q$nC_rZ#>gpqp>Q{kxQ=2o~>3gJB6@MKPb_bl`U>pzVI>a7#fR8GqDqQEbb*xUeU}>U&_;l_qFj&o zTu&07?u3!Y^}XPc`PUuBTv^pvtD>bCe1P&k?=wn%apzV1ZW27+E3(>MQv3+JCw9WC6#T#qqZMq5Qfy`d2zY~? zzDl=IiYkD_sBCe?0_79*9V$w6K{tw;38?vPM;*p#@F);csA`7b^4`1Z%bK5!Ny`{*hTY1BzQJh1Q$&h;pLC&%KBRPV>S{3qQ*Q*<&=;S5(S!E@?b76z)X~C z#wqe-tT>pV>TQ)I;7jVH0263oBxx(ZfEb_vcd!s(f(8cDEytbU76I+D0~MI{SxVw# z!GY-HNZQ&Nz-quIGE%S*K_jM6gwX`iJO)dlEW2?Rl4e!!kPr`)oH!C(k4h^=NpOh5 zD14AWFydYXiC*?(`!I(IBz;|eqdFI7E)#EvenyIy{1rjPC~1RC?s8^IVKt|bGbfuBySMAWE3RKaVgAj{y; zs5^^xi}TcX??@A78U!+wvsNy=xCJJih%$hv>vHzX18feE+g$rGjSk-LGe{;FKOX^F zc?5WdGBCjdK~Jr1AYioqaClrNUS{c|0~y?ge+VI9Bex=mo`#ts!QdeW;gA}vOZ#4I zZ_4;>LQ+avpyOz{=EPXLQqDw}Nc<*W24)_qa*0gw-eM9~j=H_x=x!kixhc>pU?~WR zL^vaVMFS_?Xu1nQ zKzh;GJWb3S?wg4a`fan|Cpr#0kUeUIlpYJC2))#tL^VYn7Mj!V0mU{ACbNbd+}ahN ziGi>3hg1`jz&!p$npK&#xZJb@Eevna3-Ltg0BNl7xYr^mZ%Q+#Z0#g)D;U55WPype zXbO`;7Lk5q)`Qf#Q7-Jye@ccHe92Np!aO}qLeYal1_iZp)07a@HiNpT7!Y{1 zftUER$R18j^CdOTA{C*!N+W>A#I3%P(keZ{yIacl=5GslS<-{IlD|dTs!3M`8(c$A zr`5WK6TmGTNO_2(6Y$FxGRj&m<|c3$14KQRza_bCf+SSz*lPff>>8ky=rfQB*e5Xq z1+B_1wxkm1!bjmY!3u6+Z6#nA@=BG+ZWJ{uVG?iLm`azVo=G_*`kD~t?cm@{s1&tR z#D%uBhN2L^(;@)P)~IJQq%kYsgL&EW$kHZwtR+}V>g z=s1#zm59pJ4&&*e+Kx{KoaR|Z(B(prxOE_WQs)JcYOsF35L=>R1&we6KH;|8Cx}QC z*n-fgMx5=ZBhH#o7VKX*6JrwqwwUD831>@aK=V>_!7rOSV{N#&J7iA+NPlTF5v(4e z0SC;Ntcr?sPWo(QWncOtyL`18CRM6Z?CPx>H7Nc%r%1wQv654%vpck z+$Cij=hV16F%4de28T+<4}&hVUl2dgzcOoGau#oNCc)f^h;Psj7~;K}v-oK5l61EO z#j`Qn$SMNM*t)q2&6@ze3eCaxeCwudu!ymF-Ohns{~$W2;Z5h>3u1#-De`HJw#7H) z5-G?c0P=0NA&qK*(a)182%6zyzU+(iZCj#ODQ`X0>y%f`WJ_OlfyYRBsmcSxQa(nU zODsa{`_tr*Om&911V(L6v_dE9iC&@;bb!0QehVVLk4}KA&X%D^t=gOksumcjGU_FW zG#bD7I*LT& zMHya$vZ87;yhD4pcvWH9GEck$W|ILDz}AGWpizJyP$$0&}$A9Aaoy4Y;T2j ziEkt51T8bH#iM;-1K`JLIvG;wPoi(Z7pA^L)XY(>)M|64ELD_dz=&Y4W-*Obv4U7)5(YtB z1u>~pR4uV?d*OsPe)LPNPZY|$ol~z0y~FuMTBd!ew{|BHjs3XR%kHIF4nN~ntjagL z{HiK1y4E-2s`9LVDE5ZAo}c#`Fqbt;KcWHLXu5Bppk1W~Ij_1xMr!4WvOoSQMY9S{ z4E{#;&l5#fJR@pr09UOp)m9(?z11aK#Zi05PhC}MAq!1OO?Y0nCBdro1TOPgt|_T~ z;*+){jU*sod&WW!fV$>5W~*rHrEml6PxFPKF?=z$8C}tyH{%tTb)+sRbRHPmchh3m z7{O#`CHDQsdNjKlWrY|-nj`_HS*B2=kV+MhAq6Y>=qxzKi6(W#B0j1~pwKV3O(Kn_mbISvRVKpygEPnBX(A=u80ZV{{M{mrXTAjG3n+ z4F!`2M5H91wC$AoC+u2w!Ke-mx7Jj#5R7^0N>$B@G*3y#3mG=;2&XAw)H#67D`5?y zC6S5$LWgdT}F! zB^yBd0s6U#5a43>NaW@FNZzTrnAM>gLR}4mL0sFaiBu=)j=b_WQqIeYAZ^<3lSO|H zJ7MU&gaW!ten1xIN0I0!Q4vZ7)L%pvW^A7mpQvWb#7-y*dbLq?(<)?9ts<@Mg%$!8 z6w!2AQ|Zug;y2XHW-jnzYILgZp_mITEnsI>)&$~sCTbNKwbgZw{ywLqml{UJ9W(gs zjm1}aMXT|?^ubDRD%MA$D2a*gdfto$)|)wVtNNC5V5|9#%#Hdkq5#v}Nfn&9k&472 zy>UdN;1h42H@d+Y8nh9uQVh*=iKs-Cmn>aE4vxZ%oSYV<;%PrDt1gKffI%=b0;e?P1-^*0d-^eW2aQ;^WWNx`@8H7t zvRXLr*@6fiK@*SV_(gI^D6i=t$|$UVDPHu7y=Nw!{X6*FMi=JGR^mWDghgA(F^Pm= z8od*x36L1fMhECv;F)aessP)do=saCcpWiu(h;+BVxnDi6{z#TeEQmy^v0MxGv_GH_rS?ncf)^O-uy{n1iyQSs ziI~>v>e+&K$R@aF4u3Sd;vkH0R~${UCZ8-O9W0dw9O!lNYjPp6squYl%yd=uV}7p z#+es>r0o`Ts8a`al`hiei?tF5d>17o-><9DXl(2P+#oc(g%&>u;nUk3$*u$p%*-1{ zGw3Z?%dx3uqV4!L%KdAs?l%#2$N|WGbZ#3+_1Q=-(sKN5xuqpT}t{(J=QAC-yx6E;t3DhQv~ZS2$*PO^U3})-2ehCfx~L zfmaB+9>u|&W1(w!A1kVQk7)+qqpf*DpB zuqpMCY(<9GYHiq3F`iAy!Wb_w|HD9W8@v3n-sm`Aki_M3E`)A9pqgq({^4-cr@t3bu*lF(Pejk9PXx2#d^+mF~vnd z6TR=YN06C{Y}iDiKC$mH#2~iCJF0n}|EwvAB35}bkl4~T2F#`j9<^@~jIS&P^MdJ~{cK`=D#L!t%l0~lQ1tfo{!DhzxGq@cYBS)#b* zeWEnpm8ufm`Vz z&b?YdB$pl|Vs@%V`E*1+bf2imDa;(2MWTo1lsbayTf|W?1rt$O1>cCn5lBssuJlR~ z1fA7be(V4PGNxI0K%xua0z|RTX5u*D9117Tl{SN!3b>|v8K1-qpa)d~ak6MS=eM}6 zd0}}O<`UJFO1|aIAOYy=Y8bI%M4(?yHSUB}OwkCj!waTma9RNm(FH&eQmBQS8aOK9 zAZ`__WAR*~RL6MK$cZND zZcW>|QJkAv)!4(Od@xNFfa1O_Tv4_1IXEqC45{|H2@n>*hNd|E3i8~#2(%CBD{il5 zS;9)`3c!`Hxjs8fMn}aAoem_CiXeAb4AS!AhiSbhtWkjhDJju~rVy!X5FhZvD0`cr zA3gy773r;!g;HZO83dgiJ1ck0uI_UvdMmI@$+!AMil5Q6HO`mNfF6=&yRgJWPpnI# z=D&(7P?3|3!C?=|wo7b}Hc=^sQZ2}?1c(&g5PxWG6D|B%sZ^1Wb`zTDHVLa7)W+WYvLL!D47qVnqm1cCpB4nY=R12-eFO$+AT@0xpCC z7pw^YAIJb#r2=022+D-D1)9jsS#Bl-OnqE|R~zLdumYaP+mZVgg0x44(h4`F&@8D|KtK~G6@9OU zW+hl;RCTj0u@itKxhgP5?5IcCH_d}|+(WVjgR0F>g@}_Ab zf!^m)q=}dgVO0QxDpkk=8>gq}1cPCOoA1@z6{sEqj;L0|VK(9`45W*1ThBrC$PAHU zNI;(KbUJNhvy5?N16Srt{AfykZAmNwO+^&Kxb&4m3F}o|N)H87vnwW$Yg&wGwKf=v z2h2iv)ozzfgoSMF^J_)c+TGx=x>>FwsFEmVnmHz-g&=_=&tPC*_jvUaz&OYQ8>-+r zDREY@s9+|D;`WJ)uoU7&G3%=H)<7FJ6thldE;t&N5MRWwViWF@d~s1#hTC#LCHDl# zT$lDna3Mj~43AVsHK$C%+SPKJfSv!H~OsEP01>!+% zQmqoeN5&`kA!rs`g;i_57guUkUT{xDH7tfAWGyxJ0J>kL=>4OYE~1D9vB5D zTBpXQHEjim)<&1*P>oq?{198g@(6%~T5Z@(2tkmAmXQOHj8qZCDRAQgrue07WI@(9 zVb%^^CW1AJwVt<5IMEzIUbueJuz z8)TILx~79nHVepl6q|_<1{GK(6RN=-vSWoI#RQ_8)r7Xj1k43E6ZB(r3V@Tbfkd8@ z^kYU9;@_-t2a-88a1gfHS}x{Pkw;f&2Nc&$yGmmv4#`TOqT+pX5vbA}8%B_;ARI3O zNb0?W+l5sq2zHX#0<0N93{-6ce!Nx};Yt!K=V|*UT!G)&TCh3{_9=?K%4d1n<|hY? zm&Dl+6H$+9R+$C~VKRhCYC~FiD*`B*97_sp@<*GJ<+v)IwC+MK3P^__m{5++udG%P ziR{xAI5iAQ0aNKJ#@&)D6jo{Q2o*zjh?rvOo*HS7_fesuSLm6ZIs;$VJVIrcoSuDL5PBB`(M~02Tkh7|Vj4=vR^;12Q9G=1z zh8(Q3*g;7)kQLztjic#IL0xQC~$lR#OfeQ76M99U&-+A;#u*5L*h1 zfP$nX#1l0cv4}$n4%uUgC^LRbMT`t#TLVp6f;L%`kE)AR!}LBVmH-I@IgB>mqf`QX zO~W*+N;XANh;fo?IFLo|oyx3s>tzi+yQ3x=wlaw8G@okeqVz2yq@k8OCMskJJF$Jx zF>h0w*;pA=0y?#7U=fL-jNK_-AyxalT9MQZbj6dUN8LKtq7z|}>fwfdmR9>kxjZ6M zYz7A2xxQ}T38cwW0D<{h(h^eJ$OKN?5QAXD#od)EGAVFRs&fQ>C81cT+K4a)0i)MN zxPTvI1SD;A{9qo_MG@S}M606P+SI8rRK#o~gv=tUBeU2r!eENsfHvyfjK*S6!3VOI zFQ{Yl)#Zlx76PkX8Deb z`m_`|8^umS6NWGnCWpvn%-HQ3YPHlg2-Y3W#`% zc~@V7a1D?ax)h=y4(^6}sTxJK5s1FJio#(*WkZo?VqTb;6huxmF&lw0UxBAtRxXET z=dK;4j0(!6Nnjugg$|Ldt%kD9i?!KI9%wkN-V1#sT4Mn7tV2Fc)2uQagN$uw0z@$Y zT@O{`10F0E=0pmq;iMSs4z7i08DxY`Nn*)rcKD-UXkhj>kB}v5+M*SS+5*eqO4Po& zQk1?yPN*3LV`{!w!lLhs$rwm65=ayQV5U|fkaAN_BEe z+73-l+ZRhnd@6f^x`mf`h1L>22vcm`YZweX#M+o*Fvv&Xo*H@6VG|xa6E=DCT*j90 zTv&x_o?%6^@F*;>Joj8*5?}Zg`bdgyDwJs656NwoQ2jMp2?CgvhI7fPGr^OukfaG(16+%;c5JBP1*%Uhl$AqmFx!{I;JbWhut79P z8>tafBPa*8?{d{thPZa3ZzdO3o$adplMTy4sExy%AB8^9G)BSIDp<6O#28*t?uF-| z-)XA2kA14Vc7?v+GF1v3OIS#wh17_5lp0+Gi{wt~YKjJ)dm;A)YN9+tkAKNZ^!xNY z0RC%%X+SsBh>Pwaj(Ngh_C8^OU0mKW>r>+&x(u{rMKK*k#HwK81u}`)QXRL=s9nLh zon_WXMKF0k{F9W7z+cbMR}Dky_@5@ylwqrP zdsHJ>HP#JoM=y0-%cJ&uH}j+Y-6$&25OBPdG?R7#Gfpgr4>g3WE84*rSc8k*Hp<=g zqk+4?E9&4O%Oq%skTu^x@-PN{EQU~v;1*~by`;yaIA(N=sx5sBXdanPnygvLI5=i? zT#%9gBnwV1>_WkpLltI$8KEr1d1~B@Feu)3HEMweho>N^BqWtp{Dl4p(y=nqnWbsk zwiRfCL#v4x%$+v=sOd`LQ}qHc6GH-Bz)1y(=*s0MV!9Y(W9aPA9v$Ww%Dn*6ftaeW zkO!@)Kh4s~l{MVzyUI`~J?J12c-1TNFZ>zt17J<8+KmjVWz*fDw$M<(7_NX4D@@CA z3-Qii))7(F zLdI6zohl>t_#1(0tRf&pA~g)WLJ7AbtY&fz&!`;T(@6bkqJ4oJYN^R`3ein?Er?Pr zt8P>%2{HnR{GsQ7xVXU5M`4pk7&AxBJ&Q*Z*3 zm@M%FMa)oL&n(D6(Chw-(liKBm_RZsJ?qd*ZsoqLpO#0wtwcku`W?%2}%EF1sR-D3!R% ziRgDKQixH;rP4s7vF?@28e9xc%g`QLz^N2h7Xd&+lMMwGWJ+VAS^b(eIt9WMcXJB( z16Wjq2rPx$4$6V4C=JONc+>cWS5!)<{Ltg1zMrC>U{@3=<>Rq2ZN3W*63hUAisXXh zCn6`nh*|kKxMNlezzBRl@L=5+p(ezBs%i|iX2tw4*i(E5b-ONtl%HHtcq!3ovG2fi z+#ZraX^|^RM!7U9%@X8D6A?w+>jC10`a`GWr@9poRe2 zzZtxcC6)an)BqZ0hY4YQQv66KGTGKf(`5$1r5S!v?YsBBa7e;lhDQK>qZ{5@Qj8$2 zQQeXjRwLZxrixsURjX*Gq>pp%JFRHlsq3sPvwT*w%o?2QUWa>jo46Z0$l9F{cUw?Tu8UQsS$u5;*D{O@5_hR? zN#H01yb2+aJ87}-scanxzcQ?;vKPgK^GRP7&oTimqq^1p_QL7V(F}?lNK9eQ`;58Kyf+)qUkV$5# z;El}_Fr}ftU&JbG`-H0ChyDIdg-DXYGH=o3r)GcZEYnO2!72z%C>!I-S2qLqH1WfV z95T@sR1%+%`fH31UzUY1h%aYgwWDjO7g@UW5mlARS%~-zY5XO0&5Fm~84u1x-#%~f z*1N9ppbFXGefVS`7w@+SOx(so^*YF4&`(XruM7|U#x2Sv3sm$^d`7-?&c+xT)ZVuk zo~*%=q7+#~@@|i8mE&JR7T#f>tl+jb3SSK&Mvp+3jH|fgY6|g**vy!cY)omfgWW?^ zUrfKE6<9U=p6))TUXp^U2i7@F*TDDv63V9CT!CMkU0Zag;Y365O&Oe78HWEfRTr6s zX(WVo>yRaagtVZf;8Pmfu^7tnFpTs+^XGF{)Yx5F=VaYK~Ox1(DK1QnN>o zVbq-DBLqW}N&6&4Mj>T_FaRvbc3U&*KHwBu-*qd*|}$V|;4KSO3H?oND`cg4eFr4oL=pyomv>GiA=LnB2Fzn=1=yc2#!x+vR&TF`sI zAfM__7V0Lj852YRX!QV)YE`DpT86-KjI`Hs;9v$1h}5aj?G_-EeuBY;M}J;AI&@STY;klL*b|B4s`TyLUU(RERj z!4*?4p`tH5S*jIk{FPU)OZ@Z)0^zGsl>{HiwgC9C#9zVFk4pTEaLfSRAcll^cw`V{ zqQF|<4_z4*P@~sl+?7EyCx8s46@os6IJ%ixPX@SL7XBmyoP2fzvyIEhzj7 zO*9qN6-S-37N6&sK!Q0fD*gQjJXANA0vS8hU9h&3?HI3Kzb3IJ$i`M!nP zH5a-Tg2|v>O1Pr36{`q}41T|D0mNR+cylGjSTSOkNz<-ZT_$YwP)!2u)I#wVh50s< z+CBP7lZgru6UP<(@#svkccCgg!O@G}1qh=tl%_&Z4&ZEK_^fjw*)OhnhY7bLS#)2h zLaYft1hME==rU==h1Y#1XqP%?=s>|B680AL@{J~4y9b|TCT&U45 z=3?BoV1IsPNWa~;Ky&a!{-R~y*k$62rNN{^%v5<_wU|KD!0ovnlX@xC8GhbiLSJPj zY8ph|u~Je6XQx&ISz8JI1=SK-H79x%T^8jY<&6lKI;3zosz3@#;XmmyY;*Y7))(^% z41j9i9#sT}Mu0obTEu~c$}x3}_JM`$1fj-VCWHk!)Zav9hYo8mFm`5}Jm4YGQ@NEm zg3&tdKAFLQsu@P@sTwE+t_PR+U28k2b{6W{TH{phpc}-fH;u*U zV;He@0h2K>rRpV7HC<-8^#rMq-sdo^y)x63p>EUt@O?$s+B(OvnI?s#9)wh7Y$mj_ zimsLG3u80YLEyCd&Y{$Jdx1ilszZc~6kW;#1yozy z=7r|>!sdl+HwL->geuP~h+;B^k~>6MbU;X}7Q(tEqit(`y(a?;uh>KjtQbFN)s|&T zM)eSGM+OOYwtY}|@xJ`6I7Ow6D2JJv9oYWqieH#eEVL+zI<6 z(vTBQabht7WgErNvPYS`_x69FSx6Ny7x@stu5n8pMt~W_nd*0_c9i-zVGH#@y14Rf zgjnE-&x)RSb0}10*(Fi#S+V_#O%jaDVcao%wCK@8Zd6ev1Aiio#v$kpA%WD|X#%x% zk3`nC(?LJsR3vIEKgi&+_@i1uFg6OTgS8(BpnAIS{+g@-#3-s27JsyeQ0=ZiUHn1h zI?Eu}c90AT`N95`o%0wB%z*9svB4KzH6~-(CJ{z2WCyz?CABF+=+{ZqREw%tUnW6R zmGs1vwI?FDqH1NEW!||{t)$jk*&;yJBRAgqVdlMiy*dG_KfSn!ikte)AL;%r)IAY3 zjUsPQz-4%~3E`{JRfG@{FfR-+0mYdJ`q9;D0zVpD1&5fG!lTo|5-^7VVvav9u2^l3 zZ98J?YQ!Q^1|DvWRKF_aTznpR3@-zznh>@|_RycsFS>HUWPh+Xl3~jkk{d)&WC18~ z5>;dsHPLATrCcsO)lA@;4bz$guzii7dh<%%rPA;U_kIMpW2YT4++B$YAkyV`(I*O_CF2 zSml_0ysxY*r9*j^GY*WOUJGRQr{L0<3C#}Lc4C6}X8m65!K~KLy9F#MeV_O{9EJ8* z7fzw2g6+$WuC)B|xqbPYQbnvsfu7^G?ZjC07aL2*G@+NxCp3x(3bmu}2kS~n+Gdz^ zplB0lYk1v>PKijhr~k#)EfYTmT`-QCx_~S4zJBi(eQt%Wuy-rXDZaVSspzKkJi;my zUcGQp?fUB%F5rtxhKsQPa_Xz^yKC_8TO`LV@KrPXHt@^E+9g!d>xL9#>tiHUtB5Dy zNPUbXK%5@4u$V+^Puf!?#r6>&Ef0~T$LP4^SpvLb)COFlnj=NGcVk)t%Oi&h-c^ZI z6*PqiyaU&!=VE~ z8&wF;s&ri?gO@s>Xq(P!i-vovqhRw|KlAg)IyluV@r`tC1xMixeIVNNL5F5#m6Bkr z27zx^JccN5o@#c>Zy*H$rt<@tJh787R4LHp}g?N z4|OQ{L}A`76$mt0!7kxdm4-iK$?2Cz2=T1Z>TNs$uE}|VM$;!Rst^arR=-WtR&c1? zxGmvTA6~Bs9|jXNCohY_RY^7IPmM%G9KdPmr56m?OJ(-R3NDHS!`1B#G|}h>Q7CP$ zG+&gfrk1AZE=?2D8nZ4{t*iE^B#ys5%GV^2U|r8V+9RCV0vry12GV+!3ROWf$O<== z-<2m*n*fsV@>9XatXK#$(N=(q9Tq6i@@Q&-#|UjdcrukU&C=c#t6WX6a4J4-Th&4t z#PD@njD_olDKQ`0-uTT(o?f@TS0N^`!6eaE&a1A&5F`0+gkl0U*~k~PO$`ve7KXIHL~$cgZrvP|C;>AIHA9{~S%~?nl?APm zSfW1~*D*b}Mwsyamw{g(PXSdFYv^!N1`^;g8<^c`V+7SJdT(uxzLeX8kDl zwo8qa&_Yl1Rh`176H*XZ{^U_J;=fr@JNhbS2$pFBD@e2c282^PrqJtFAy7a7zNGis za6lml4C4kC7gI6N7EA(u`X1Z6K=6(BNLw3A6I*hKLbbh#vG9!2kzz+P>jG$=rB4m_ zgjN++aUkp=2A>88uygOL)IZ!uL+YFy?BlEIOr&sAVG3H%)b@G8SI~`;w1BwtR0tS) znhVH9jSb31UE<_P-@KZML$wvon$uQIzijvnetl+MtF-z?~WSo|G zCD#e^SI)5KK-6H~ganq6hyJhq*!_=Ci2NIPAF7i|A?DFq*#4}02V&cfv(ngf+u3StgXPUPsj?4 z+HAOhA)pfiCpb^_!L*TZ67&OiwVCPm1JtHZ{D4MtLJ5vi<4B@f=FHfdMc!YXX7(8 zK2mwf?x^EQj2RpqC<8cY+dBx3i^F0!JAMpEkRYLI7BrD7k^9kd5H-u~?f?fgBZ@`u z%2`PwT;>f68Bu;EYt-pHn)s^dg#8RXLT6_p4%g~bw3^}UZZI@jradzh@mGc&vX)H{ zBvpz~*vH@RMU6S;uF4K@*8FHjCfj36xpI~eN74o|#EwCp-QYtgf?jp0Dn?7H(j@YH zOj__+gAqbHoMvf!$4W=LZ;(c+jByAe&Hw`5fa@lGpSrhrxZ^*{`P)sBi$ z7x-dhd4Mg{y+8uVh*NdLm@_;BfFh}Jx^ELTO`+1k<&>x5W#OIEscuWNN6h|_trPtE z#j3c0^%f+kA}I?#f`Hj}ZqqnIjUwraX&;;f?txJQ(P8O7G6K-59a!j66F)iw=`S@* zW5p`9RwjgVJsa7N`U`~(X zxkfqUK#Uf%F^HBym^zU09VCOeWnv8@Wuqe98h0n{EpBqpA<< zC?{qkP()kXpoMAMqp$@n7pmT?$YNTU$0Gky0X!W$;XNl2d?c&%MTgcvHT5j7ncGzZ zw!{LjBMP@g=|hKRoVY~0qpmd!AiqPt1B^F2+^t5GjL8^rYcTafZ?SuPGK3g|zKd;Z zKgsY1vmsh!k}?-TsmjDU!QWuNfJ)(H#l#9Mw7Z88KB$%eCTkE>(nVe3OOMeJ_Rm1- zAcRD24tuvim8y+;tYDDNgOiP z-McNEnBBAHDM&0*&ErRY4mhO=Ok? zQat1p2=k#v-SJBp$ae^%)SbuUOlEqNULu+-szjh~$xy@EIueFMvwrJ$1d=Qh=FcP( zv{O|sP3^ycVcUc1_f)+n*|N?b_1Q$NJV^)E~;4JmO;XxQ9pTC z3jF^(OS-(_z(TN830z&f*vhEe${rRGf@WtAA3p2iX2d6TS_s#?TMULPTkIiOba8=T z8F*wA#j=&G@c=zY7!Tph?Ayd+l9^m;hbBML{$w?qNMRI*M+fHg3z&eu6N+(wyYzEn z-HdxhhlM2FA?ppv0$qhP*$Mjd~J zu2+%#P`&VXK9;YUR|w{l@EYAApxzm}Huew?OO*iC&@MyQAXx#X zTb_z#fxWqAJg=T2q3TDw|14Xf2I-#Ytl5et>9ntkue8U4a+DE1WGEZtm!Kq?hgOk+ zo2ryS*UR;FzO}HWmtY4=dfDdBPQ)i+@lJ{~;M#<}N7%OL&2TJ^AEIbj1k8w*T)U8J zFp2@zO+knRh4PtATA7olk&3S{0HY_4lNDI%0+inqOtZ0cbjr_mj#~6Fb=rbU_+`nJ zkAYtuKY^UQCo@GG+V#R6c9GB4QD$$j-0)#@&R*kI%OUCV9 z)nW(L2O-&;xQaBLtWVV$!W449WSXgmyAsx80OSywWAllV$UkZNE+LVMV1!B58Htj3 zqZp!(S~8-CjZUFnGHT^q!YtY-L4yzz10_?&<4m6SzAO%a9JFrXSnqat$+JNu{7X2d zzSRU>TO?;ycr3BrYZV)&E>X#foBveF5c!1h7-2cyCR$AO+8_=SP23_`T`L;Zhpc1} zKQM_vE{VWn01N~VCe+GehSxr91q{@FqF>>~G>?;!!~o{hZO7bBD;>3lg_m*12+I-l z_Vu_!b&V8ZYwRtAip#*o%TRI1vsJKI8UInR$Rqceve-b!VtmhQ+m^b#4)BM1roOl( zz^~cQC*eJhlx8Yp9BKn^$CRv|>19SXG>S1NE1&o*BV!sNQy3dKv1A54aAIt{{c8S9 za5gK8-LFe9HH30l`bMz~A;Nmp?i(iesRMy_P_+mz*ik{=0y)&5X$G!9PV3+yt)YjM zF#+CPaFfO~)y@eSB_gNGhU}lPi5161v#^NR?ZnhZ}E@`fv?L{8{aG8NA)B3;w>*ZiVyU~o0R zhGSD3zfTxAA_Yk*%hWb2w*XGH6bQ3N+1Q2ik*c!g&T5%FVUHlzfmuYHA}0$vXvw~( zlP@jMn|NbSkH6*;WF+VrYNZZ9cY&&*n3u|DG9E?@NXZ!d$YM6yWIKzT7LrD1N|CfR z6oEyptM@Y|vA$x$Bx*lBMIKu9F+fj*NRu8|3t3|9svH@19x>HZpc*Ow*Ke=7e}vHM z-GYe#3W00cKSN~z)ciaDs6`Z^$2en?vGdDMC7G+AIkn>Vxo+kR< z=y}@^NgOl$X?D(t4O@(n?JHs=QspP3u?VZlB|siMa){zE_EqqbgTNVF}A3m*rnhklDuK}EZu>R0?HI(hN;7c;v3NJ>PR#!Z=; z<=Rb53mG?N{f!>}3ymNBAK#y293w{T{}kS^m7PCpHbwu9JIEX#J2``J7U4Vo4r&SN z#|#Nmoyef{UmYIYb~rb4OYNr~NjxmaT>e}3z;wM#9I-Dedog$St@R9cLj4ynHsxIQ z%XX#p*Hc$Y-FqhNE~|KPLh;fRz?7VzuHLfyVMz^Izrrht_a9P!?sD_}^H~;X`{qQO zUl3^Cb)dQbvuHCR(X3MZO1c)(R%Z7dTg;;N?ziM`j7i};U$eywOig2>z&(F9`BYQ* za5gR9mwc{%xbipJ#DDSGq7wB zp_EL%(r6*b~rp>8IAZ2gZl%^37)~wMAr#b8* z&o)N@>}K+u<{0?iOcb4#4NsM#3ll=8CK{=vb>RzX1dsDjjnX%*)@I8B+wPK z%QPcP)#_?Yy|h^1+jQZ8CWhW?SD&>>A5Gcbno zRHLk9!F2Ti6{@&E=^yuIK>`}3zB9a!nl0@8PGB|mb1eTj^w&NF)P+A*FE{N^JaJ(k z;>j^oOeHfwV|u+UJfn{X$Eb=1y}M{mno12q?Q^g9f7#K96aX9P31zBAYwrq;8q(48 z7i^uQExmvpdg7gbF!4+^GJCTCq=iNvRm7lhA=nPhaFxr_3q%5K^=vflDV8rSG_qRi znl1FvemaXpAfrcFz%_J|GBmCi65&~?^Z?^f_u-Kct+K*GT3yq#QNZwXF)Bu){}4)Y zF4!Tf`EW=)X$r>(Wvq>bFL^%lsU+CIisYHJ^4N4G(hkS&3>t#8&)-@iPX%ySm08aN z%ik#hD*)*tts^oobF{iubUZ1Jm8n8WI$-2k=^PT z8=I}5=bCZ!DyoaoQCX}?s7uasOxy0W;;?VRy0*4!=p1{P2$gVk?y?- ziB1>IBG7K5g_e}y$=kSABN8bk+{AHVifGK%%3N5r?;puZNrhDqMO#P>YORo-Te@6` zW?`rXr@x|)WG?SYsu8J9XhvYP#)o};?PxzBlE#vDUBo+3Tdzw)S&~^=m-O`8SEy8A zF=J+TkwzwmAirUvjs<;;ndthpCPN1S#GGV;%l?6#693IK-F5I{uL7Gt$N!<+C?L$+OkSUq};wX*zs@^ zV$AG2+Ct3EF1JDeR{Nc;rgh3`W1GlGL;Hcy1KyAgRIw4**^WMCk=nfg2D*t-&P8 zGKpUy5>GH8()md-AgECd!n`(8R-9;~vC(O@`YsC_Nz;&e7VxXa0$ zm#pyH?jo>Q}9VlhiF6y@zc;M{ta^ z&(#FxQxd0BVm@_jm(My)I-T&-g~Aq(uej)wN81?PyGC3HM_f-UlX)Jbf()A#En1a? zWnIasHZ>v2bl{Vzf&LP({JVs4Bp$Nc>Um zs69n9Ra~IerizyE@uVr!5ThiU#bf+(YfAU^kjx^mQ2LB?T-KK6 zM{20&^JZ!oJYoz@TRNebvS)bRTkJ$`+l*6U?L%B5fv*@Ea+nYNVOiRt1s|jQ&PnNp zhwFq>X2v^J0-aHon2u>wka#ys)E$T1j&U+mlyPde!@n4LE7uf#G1WYNi9V+1_v4wM zgdr@oyv|PM(mF;~t7JL;t*wlYO35=>_M^|lG_$#zU}f?Q1XG_7=(0o0#64VNiJchh z^Ey37ZH!&2Hmji2zOza*^%bvzC=+ZhTrNPSRJDW696nbAs$WU)8P?)Z} z;mu}Jx+*Tlw2o4eUB1&pP{OSqZYT`;Y-y&x6BMy$nSsQ-B7)n^GN;8C8W&qySIQZ+ zThhm*pl&u$xf7HYHWF=Ho=H0tb$yHSdQ_^i2>py44$?nO^HG>-TV<~<>TG&NY=KT| zmKq%*)#ELc5iF|RR>(A)XZ1c22=*&c4e0D_uD2(McCwy9wTg}Cw$QtkS=g#tkG5-Z z7J*S^VqHT-NBCpPXuV632i&%u3HJ^rjl3`hJCi@auu94zXOmYq!C+7mG6Pk?9n!m}nL`blX_pjz|n`JF5BXhaY15 z%!bUIem69Bv~D7(CGt{9x#(tTtV^aikkH^4nr-YeAflzgPfa_N>`Iusm>So#(_^gqY_uN&HzKSdFWtGc!T-+KP*SEu>jDk!07CL%Cs!i@B{s^kk zV^T8`y{S=$Aw@qnb5M|{0biuB>6f6pm3^7-t|#jRjubI`h`PSTK`MRJIXwLtQuHFG zdc$$~Cu?mOtC%$RaRa6C&6ucNN0c(@1%gm@#SVykBN0Y-ZB-3(G8BDjU-71KKO?o z-NS8JcJLXET9i6b#yJ~{K2)zGW5lSYJ#(S8r-3 z&tgI2_F^PxK?3xv1uI%|6;)w!K)a6L7>l_#!)qd==qRF zCi4#(E1+SGEf8&d`rDXGg14|i z?^jn+nSJ3MR@&U?=hlFRnBO=G{y-lX_3qA4qqNF~uo>J8d9_`dv6L+nWWnqtQ)mBI z2z{zOVE3^NqLfCd4i6d3i}SdtCbrJC-Bb+=T8$*zaU%@tECtJ^HpS91>woTa>O%nS z%&i~>JS@zA;L}B?B~CO>BJ>QTT#@H*kg4I7iR4ChYUTeKA?3aeqpmz4e??yPzVaRY zDu4^ztb$8)z;5Jag3Y)|Er+Lyc}#?a9V1cuP5C3N>)|iqbwx9=NmXRnaW-M-_+|(3 z_s!#xrSYXPjv#}0TcZ?JKnvsGFeT69vWnflBoUy?U!l5QJ1?Rh83&5@CC;fMcV9qx zywPhSoS`^DQzDb1)|^+_K+~&|0>)POZ+7Qh5oKDDI2Ltx3AI0@Sruk)U^@SfX|o?P zYf7oY-d7fON@K=XBvkKg?$f#0)^a#Xarh6a{tUm~%gYBqZ14r^E(?UoDJg~M+_SB` zB?L6XOTV;zLul(Y(bN}_uHO97;>s^M5qk=7pU}uqy(5Obp@s`(nETpLqd7I!WUI?Z z%gCGDnyV~^l}dPECm{}<)%+PW8XMKxqR6o*+|XXYTi_(VNb^_tsebf*GMTOSf=k~Q zbFd(`ytAUMfu-YzZWTg$pE51VFU`FS4^V;5)gMX{Dby@{@Rn+oD%et9a{-4$qh|eWgBI z2{qK~zOu%ZBy3`HR>l?Jq#cC>hXWN;@rtM& z?P5ZZC5n80Vqg}%lMr=n8S#n243P*AUo>&t2~mRrYxb|u6!fmN-)2dYV(g3FVlzcj zuybl;HACu6Cb4Ocx}C|y%=pKe0U*5bZS!F?;Vu@Fsbh=w(lkwbn**D$hXWr)YyRTx zh&}_Cu#QZ)5Nbz~@S93X?1}q6{8ODBn1n(!Ihn5*NA76?OE?9CbJ7YzVMWGxT#eot z=c;}wV?eCRu!oF>vyFJPu&XU`QzTNRbc?QN?|-n(g{K z9JHsY$%_fMpU*%3k_G4?a<&pNGA_EJx*0*k>BXr*3({FS*E-)eL8o0;b&fpB1VzP! zKrnhqFSx?-JJ9iWq!UU434c&0l^) z1({NwCVoDbkG7MUN2A9ZJPQ$FmGj!lb;t;NTv|5eXkx2X$`#?mz0;Pjm(MyVFDvoh? zQy^o3#2WBu(S&N!6HMbfRLao3Z8?j4mdKH1b%vprW|tZ`GOwzNLUr^Df;7y;>9|!e z3z|qkOJq@mLa{6Wgr1E4k`6-R^p)~mSf!fv9y#inE83UsysraL6NunR70F_qx(B4C zPodja3=JYPT}T$qDV-{=`cQm9sR8wZ!BS<}v8JsoRZ0&u{TYqDDy8*|dT{0&ZXPk2 zt{z{ksT@Hp01<}R;bQ$~q4HJoZgL+!Wpyd>GM1%^;OERKL``@2F6LB3^*SKs1Vid{ z5G(bldIuhhD`>)LjC+y12LS-dEPXt1u2i3hK>4e_164DUhfb%AX{_}CK#C;9oR@)G zrH8#~jZPPZo|fF*7}ttVTnp8<+AvdVPql>cHA};seBftgtm72|~SDR`e zg^PR~N;AJ|8oS7?bBa1zEBvsw7d+OeiCk3Kr;_*r{iZQ&lc~)SuPp+GSU`ke$|^FVO{p z_azb7gAFpm15uOliXwG*2aWR$>qj=05aifrjL;Vs5rYx@tLrn;uPpK{il}Wm|s}7 zSM~;Y;x>K{{VuJF%L|=$HNn=U?OF&1(ot2eBc4&HO{<8+K5UAR`kgCL6Cs4@f z+dhR04^5i9Q$G6;ZDC?tK}!AHn8<(9H?g<~`wqguzvw0*C)9p%(bKqC+Fh1%)IuY* zYWq-%Mv7GvueWf~&K5Y(<9_4gDpBf;1X2P@d@Pb`AL{bp8`j|@Jqc{21@XU9Oxtqu zC!(rV+3zxvtCk*8_Bl(U_#gaPi5}Z_R5+q5fNuInpR;|fjIB(Djv@?xJ46{#WBU=? z%mx(xh>!D3&}(DI{M7A#J=QWw01wfqf=~y2#MAk3ChnqX6N1AP7&T_E76*Vj`-VEz z%jsIjMIog!^ah&I;r@}O3b@loMhT8AL)l{Qf_Lh8UbImk8IIqtQF{r<2;a%*qV~{D z#B|X`{e=PjYkdU0`l-YRNXcwRW8p><^%+J@C<$u;23ia}Y!W$IpAaehfg-9>Iq?}g z3}k_3Da$UG-z%Tk8n1{;v)!75HdHSAqjo~>3L${#_H0UE;g1NMW=nf4tle?`?)?U) z#Vf9~u&|K2G$|8qMSX)}Y!`)XA-rngPuwEd^vq=hCYm(`rD4G;Eeot%EQfQmx>z8V zT311Jiiiykwx+_#*i$;b>D#NhrL)VlH}&Lsag4R=DW!`v5KJUBFmkb{3PpHd!4WxF zHD#O}DPy#!%Wf~ZS!ekb!_Qx+! z8?D~eU3SB2k!mMV_9cY7vHQFQyn_JlC)&tX`-!9mZ3L&SxklI-9)indW7tb&jM>IA zd(o4YHW{MJ_}F!*^z&|zDgkTZC7qJkcO1P*oinR6j>sG7w{|A3bH<{3F5D%C-}PF)fTVB5@pp<-LJQzfXH{kuGtx4~14t^`+Q##fZ1O2C!n~Pb@2G z=)`+0>R8C661?5t+X5X`##-OAt}K*6J}$}UiSt+~B>p7rV2SobP9qm%nAy_yU<|?E zOzK{yjwYzVs**pNGz219%5CEN1tO;l1CH={DMh)ZF#i1)GJ2c}(x9e5u0F@4 zZcEo1Y_jUUvpf(*XB?G0rVE(X1FRavIX{Y5DdA4yIJ9*kk%n#ZCE_>oIi@|$r%`XL zZ}^Zt;BM_`l|*7My>Cyx8v;3-)U$Fap=_U;3CknOXB-nL$1+J{L2phQrw_ujW5tn3 z#dr8r4p2FGiQdm7gWv3g8}TuG$+m!)2*>V+Qgn87{tO+b^gIi6IwMWUj0JQo$6?9N z%FT03#!0lV^U=Q2X}xpXG3OGj=0V^kel+rO*)c~TPm4>*Jw{V@ zD_;IcD|L@1ID7M|-G66%t*T5)epnvY1!Bi_|%(4|S0Ud)s}ZJQ;3@@Es=!*0oq69k}X! zhY2UUTIzH!M)UkOYii7;t?gyV!-wdTA|$L2t&nw8BQ|NemZSWUyb?$4QyF+!?c#do z%NyAK5J?x;l~RhvV5oU#r--Y!ukFc}z)6A#GFgNo74(q2&p7#7C+l-4UXzG>=4`}S zIE`!>h*#{kcHL3Q_wsK^VaJM}~*ps!~3@ zVPox{y)DFEHu!O|sf3_Q&?>9dZK_|v?``v_Oio(_jSFce$`bEO>5@X4`wA)~r=}Bo zO>90ba&etQ#)wr;R?_QLv2A_+0v7?x_i60*)JW|2?>FhX*u?sajqb%~U?sdN+IKcV zj!1NTq;ukHPymIBNt(PUqYf9;$UK^UIC5zFe2iM%XNbIqZ7X@dz(|0r1S6wI(*!&; zhJ;~nJG>hQ3zU)$O0dCEP>#b#Ch!& zf9m*Inl{O*7FCqeZBZD}7(tjag0ioQ@k7flR*wsnxZ(?3R7AO(Qgtqh#D4!Bh4E}O z5Tk7eKD6vl>^*XWmgQ6kr{^)>WTPF!Q`vWwR!_J`74AR_-j3vNI6&sx zYDzt)iluOx*2z&dom=Rv8&D;3R-0kVeNQ;IrI8QW$728d&nTMprF4pPde0_XR`x@Z z{C7ILM?#IdeJYCV+{{=Mf7`4&DYiRmN$+HQA(@+-vX!#mV;T_U#190fjVKzZR!oLG zhX6>m689CaS3LTO7~ZENCR9^gse&bc<&P=QW-2EVft3M`VGVfQovIr2~_RuyXP8O1F&Dij6|ez=NE*5!%K zcM1;&A99Xc=s0DAr1fVKW`>?=nB*r!uFl57(hz0J1jgGMQ~8w%Ay&i80N*aCW)g;R zwC__K4N$b6^d%Rn6R9+CFpI(=N+eCQod!wE3R7Y{$w`)P?4g^O%Ro@?FQw~-+Ey*J zkFs>fHbQ!KHM%7m;)@>|*u@Q@`BTd658NJV)Y%G*Eb(#VUcq+FGI!FPac) zeYWq9p>TwYTNVQH^+F<%zUzY0RrN(XymF+z2$OmbzLi2mB@ykRvJAeL-&Y2S2+_Wq z=p@=H>gAV>7`8ZDED0?_!v?L^jJ~K}6Ns`Cqxt)`maS~pfN|fMbOutI4JULuMNl7B zr>aCxMJ=^g+hDDxJa6FZU4@mDpKeR3S08%OebL9>OD}E{)(eurZl&wvC&J3i%|0g? zjPcHbEQU#W00^z^DJ2JGHuY!B($^XNmrvhFAXa~(?xNrRl;7$dEAdgfWXAs8SzN6~ zsilDiD3{&0l+;-ls9_;<`M5O<7pt>b4M3m4y0=H3dhHFV@3{|YuXp*<3RC)uGo-b7 zwr^-5(oBA63vKO$+H23AF5*@GoA6Z0;!-9VQOW8U;0HaLO|vrN1I4cT!8rBe=tD_& zs1<}W$@F}S2VvE${!ZJ}-zZ|6me;*nT?u@%KQfpQ8&3MA38If|qH3=Rs!tGvgA7Jn z)-2i()F-Aky#A6Ps#k0m7uyp=wH=zn@B%bwHD8lyHYG@+wpI=W;7erAo7O!q2ezOb zd1VYZ@k-xH{J;3W_$8UA@}aeT`VN_RTgcd3LhZ68C1nH^{2wDWb(tZ(ldQ!iy`}d} z39fMkfRi3Y)})Y4m-qGxeTUyE2w`)1BZ-CsOuve- z1TZ}~RA5+L=DcE9B#RWu>Yqx0N-N1PB8-UseOcVz_Dw4WSoCwH508oM!Y^t)Bt(om zX}Hqh&DxaA_Cn_285>Va@K(E2^-puz_Afw3;wWHQt~Dv zEHI1>id&ZD>6)c?i-+S>?-I7X?QRsWBNZE2pO1~=bQYWW@g-Jft*KgW6&Pdm^h@Hx z6AMRGpF$)Vdu1B#90?*P$GS6_7R;iwl4&!h@7a4{TL%zC8S{5a9 zI2wkyZBm;OHh~Qww)ZQ72Yh{uW|5u{qEIacFb`a{><*>^(9QG<|53Dz#Q{uT!Epk4 zHZNxN3@18?BqPUoSBST{*mA~#IUYr{a}hdl_ttQq^~dykAsh9)E^0C%2elK!6;90Yhw>jL0zIij_wC(1W-dtnc3&I>>F3L zzF>styhNwdT*FLF(zi$%PmK^}(A&V@Spr!W3Tn)VrOrSDHU1#EA#A{$+$B@Xyf~H= zsE9BU^a9ID>07z0*7;HXAX-7U(7^f;Y9UC1o;=f{fh^BhO)xPaQPF5%QG`z?GD^gf zT^);P7d00t9IYuDx6fljM9BOJgfa*uKNZLTZM@5A4^>M~`P0nq2zaJoRv1ro&HgL4 z-}09cIj4!^M)q|rSV!tiJU&i;8#^=j|3aIddqDiO%ZS9K9P7xW69Ox|9BUp)3-?pL z!4gt<4j&mawiH(@D2ckL@6elpP^+q$3a?l&JuxDYYY!f(Q4<1FZnWhZ&nRi}1B^Tt zv6F>*0Cm9$ymj*oyUBYq;K&JCLCbJjI5GB! z$RIX;fs3GWm^LtcJtQXk!GW&&TrQ0JRf*Mky}j z_@xJATA9X)0J8z#oYV=Sve zuC*l(5ioX(MV(nTN}XaBZgVvh5ktvZ*4xfSRE1|n zEEO-mrU?swBZxr>wQ#PonlA&)VjeBEOCug^N1V{)Eg_mMcfy0YJb6?WtdB!`Og=)2 zDWn-btlXv4=x@dDq$CBl>!n`3QEgI03RIB!lU#C{niI8Xm0cEt``N#`ZfPBT1dK=h~3Vi%4E7&i_ zh>GT~Mi`&jKXSs^E`h)(loz`|rlbePs;PK5kJY33*B*-~X}Oo?iKEY|%JrGgg0xv` z8I=pOi8hm}08Vso?4yjP^cIDW!wi87(plfre$?85_^Dm$R_f+e1Ql_=Qg< zPzP|^Musi?c^w#ne{ZiR1cn&s5<-0x8WN+<^2@+Ba0tauAe;2-<8w??<^la7BrC)F zi2;2j?z4cN+NN4T1XmjtY%s+n@?53mkEnOSNX)r|C>SzD5SmNM4TmZ3@uKvjdp9e`?k zJ06{SRC)dgo&qnK1;4>ClEexxBp;^kMKGq=*8_^cgvF}8#uT;Lw_lB%y1qeMTE`TL z5bYblL7!lX0_`S2)rw^@9CYsjsL?G|ETcz(>mW1(4X;sP=56pC!hDs=h_rwKliO6% zJPMozaa04HP!`PM=1g>&T4M{z341wPDi3JEQ!08Mh&arrD?-s|8-(X(e~jxSl{^*+ zE=AtTlIkMN6vi$@`yfHUZ)t1_vSxiPYDDYkHtOMyWn!ewn?Rg^oEihF8iofa*;V~Q zpniZkc)G}aqF7c^IGD$uR&`eihrBce4L#^X+@(@)GH=l(C90X)=EJ{OBBIhtRWcG> zI_RiuK!q|i3mqtsgHi(;l6?Zs1)gm#=aY))2ywntY3a!Q^} z)smN$usV%jdViXTm;w|dIBAAWcM=4v2>!6Ci~&ap64nAHT0I-Xpj=oW$mgnI03BN0 z4K)ZvmgU@76Gnxr;oy(a7^rF)qM3!Y@nJG~do3Q(ByJBy6Dj{9fd?vR)(pQ3tWV1Z z5DvIb5W|5i76IIz$<&uA+JW;LvjlM#a5{W=4;AVB~ z%<`svSqv=OI5D<83H8Iz;5cd%16~SxLGA$%C^H2~962#SM{q3ll~bQ+rUNLFJmN`7 zN?s%jkzUlwv`<&mF@lM8*uh^6V4&t4szKUOZyKV|pZ`HVO41z7;`VZgJBaeN9g7IG zeF1jyWGQw75jXrel|!SK6T*T~9E6HgH_3{Lh-vp!eW$rrsy+mQa%87yJ$$Ix8pL>F zj+!2xn>SWE&p>0JL?850tK}yPEK+%!HAb&^=0ezZE*i7ZRYDkI>dG~M;5G_zEdTLj0HVR%3u z35(oP1H~#$g?b)a1FU}nQ_x^o$>M*5d0VB;IG&P2?spRXvdzbZiKAm_DxQdm+KTY` zdMxT=dSgPM4~ug=yOcd|NmE5kKP9Itbg?sug$74_Adbw;PmVCYwQo6sMO>pDGzXBB z-KfRUg8_6^&P2MVH%n+HARviFz7gC(anQP0D4h|;S2;wlsGAYeqqg*SgLMSoFrO)vplTIbbe z1o=!G`^BWY}_`__u>eh^~QBP05A4a%6i!r?Y3x(!-EKDAl z28)Nu;Yn?)E2S9Dq&dxd^gj^v2HG~IW+(#&p>2=Vn`l%uf1k9F;<08O9KmI6%in2^ zwH}Zne!qZK>Z#qAzo1I~JXuxpe-^ys>#9TsF^QC7ZP}kkHV)*1*WF~RD%2cI+&MIB zXz%;F?dX@7I+Zxz=g;U^!7o)sdg+yb;8smy!6%WjRA1|TQrhTI{LUD??V(}}VMn@# z2qM@${N|>oZxuq6088z>KMx`3@|jTOt={NRtEjJr5U-;?f?nTBPF3{!c6w9~u z+V%)sT1c>pmVTOG5hTy-p-+j4f|f3GQgpc-LL;9NHyGWe#IYze>Qtxd(^F!e6s#yn z$cpm!|rUbx23aSS3Hj{Y_nKRnh9 zbc%}R2OjD;$O?C=68#zOgxX993)XRTsw7aTgkzagF>&@VVG9Y>w7I~9={9T|CCPAX zFjusKc5C<%pxqVENDkLyMFHF`Hs~{GmqOyiegq{0Euq6kRcLl$+ieFdz9qx~jSuiA zASrqpC$0$IJs4lrG=TAzu%*&R%_#44ER;_)aI&Jzl~0%vs_0B83q{I+J6B%_wUZja zd{jBX>`Z)g;MVp;S(<<&zys7CPtC5hMTH_B?yGvjkBWHobxx!(#vY?%#rk9|yZZX1 z&m^&dK<$)!X!TRBZ=xKFcwZq5gmOYyFo=Uw3C45fgJjmA*0rz zBo#DO1i@Qsne-2&>6(I5-i4u0NDVy(ObXgkEw!6d(f|SHf2)XC?wa-nfLne@8zS+b z7ezk7f_}9-P$~kR6JZpzna2bErayu@MPZm$tWf(?BP+pT)*_O|&KMR6V;c6L(lMnc zJJSycLvJ*@i`da;YVq?gA#7?B<-L11rIugPNuz#3rVGn`UxD7~UO=Hppj(i~Fc%#{ z8mXtMjF$~e({4UuK&n49Gn7b?(m#bv4T&In)L4r+GULnE65C9mMZQ^ag#D8cI1)!0 zi7p>dV+5t{3&;~krGznj(sl${@F)_wBCbfJ2ACJ((&ciMye2jz#8q@Dalxn%)*q8$ z=aN(kXR_|B)=okiskWIXK7l;Px@7t?grKpi{7K#Zf8Oq8&5|6)7W2ED@#*^V5}B2$ zSJ6lV4K>%}>t7_zHeqJI>2!}!ba!>7XM}~p00IjO7y4W&-D+iH8AETrVAAL;p55;G zlKieHk9yc97tr&}eJ?Vd*RlVmA2!{hs?b?^75CVkhIvw?XruZ*ZCQ zeegk8R>;Nog=PNjY^na&G+O0qMk6uX9zRiKL#&5Wzc1Ls5&ac{t+JMKx*mKr$e?ow zjhlrdqyFQohvi3V_|^q_@C#vljZbS`>-(~=4)N!BdjVqM?W;rNe4(E}sPqK3S_$Uf zDq24^xL`8YnH5fS)#&hz?X1j}B0pty6Y_HXVt{uE^J0E^IXO_1M2Id(I*tB@j zNOS!tT08~&(W#T~W#YgS3A}&KGNk|hoK>xX!k~tT!zIZE_gTJ_Yh07x!>Zq znh7i5Lq$&mx^ja*kp!ZJFrD`B8VsqRKl&zkB;6EgBGpv1AH+1@F61h1(X_m8noca= z`-sl4h%Q|0Q~Hia4JZtoQ5&Hl9q?t~QWGc$)fTSnI~pp}E!G~=sNeQ+baudHSr`GM zZm%jzZ_Ebk0pdV^XP%saFP(6+)I1ujCj5UlBhOmYo8rQ0m4X)?L++b~6uL0)E! zSB7<}DVA^33v9531T2=9W|8h(^~re%L`J7_zJ1@Z?7k^-F(Y$ONg^R(`E%15_ak4- z(oJoY<9o}mWR6&ZED))iMjSGQQCncBLVRxrH9Hc080}xOBJpDwqkdYE+CKyS+kNy7 z{3=WrzgS!v)9Zebfl^~Q0;5u=1Cc8WTxzBlt<4??v})!ETSFNTy>*_vNP9*cqaW%z z&A`!iA=<~@$~osq#EOP!1QN?M0drx8WSK3pN2Kk%x<<3axg%`!_5mGX|F8m`uZDR> z<0;Ydv2quqd8BP@#iK1CV^P|JEma6|1hWD{>QUn^uBqKG$;#5hz7fu3_*^k7i{bF| zO>0>p%ZcbgPU=7WBe#&=HO^lv=pQAY#@7h$LKRha9wiwaKcr!pWgkZ^DXEifOevkF z+ng2nwvcRAns?F+&jsl9M4t4#OvEOWxU0FEukZFqF0GefyMfF(P^b0Uk2%ex2kn%Z zNZ|q#fP9VNK!A}n#M)~Dp!v_;q-=d}LBSv1ic=6hr7LX!EFJ`dmhER*E1&`XluHZ_ zoyMuqOcBk{TV0cE~z-Wh7hJ!bcXB0>%k-qj5n1Jc`8oT)W zDF%%b#@|Ev*hJ)DAW3r`*`vq7`4slBR!f{?hV-lH3|Q3j0a;-Z$3h)~(XFu~k$?}~ zK4Io~HUukXG*qU@B{1_J)}^FHstHCMWI-wV-eKdgyKHIF0rZqvl1&!S7SzPXWAK3xF_=hv3t$}3U;Y_3uG z@={*aD5>Xl$-FdJlB%atL}dzaCk~`DWR8*J>7vDfIImoe4B+sNVp#SUiie1r?UC6G zDJ?)_3Dd%pG$VCN?8HdVTH=9u3*I=+Nm~F5R|Yo{vz#?(EXd3#8Mu2m5kxXEWZ?Y8 zfvxyTHkkn{jsDwBV?>x?ow)1vB~sbkqX}JCrqWNr`g%H{dpI>AeG~g5~XfNpfX%L1#fYd@A(! zqjrxWOq`n!on{eV;-a!FXwe>!yi~?80vhucQygM?KWx!QNJBFEoGEPkeMe=Lb(UCd zLC@8(rAQ?I04F6_X>w~JjmmfxS&h9omoe@KH-tkaM-nluaz}pW4@zuUs^hjFtObf4 z-uo#QCFO9+eEOKq}>K?3El(^4Fe`?}6Er=_EtTLEWJm zQyAU>SF;^OIX!(b%9}M3z_5YzE*Tqy{aZP<&mNwo+ma|~WNGJ&W^ussG<|@F3yND5 z`E$uyx`B2j^Gz4%s)REq$GMJg48_^`VVIH8gh?UVNX$YQup@&zY_VN{`jU*R$;ui* zLm|4!)fQFx2RfvZhpav+3^>NuG1BU^DK(`}P;nz`=$8__L8+}kRHZ{B;x zqO!(nDlR!^@&9~>SwNdC`YH3OvJbd0BdJxc zFg}-WBL*NEY%t_0xSfuuJyi#n4$#07S-`f=mYr6!U@5r^y((Pk$rzw9hQ|>ifVt^rz8E0&(h#QjwRfz66x+pR(m7V2RQS5&=&zVET=Q##j_X z%#Ib#ZP+5gqyu`zWFZ)*lEIX(ll$h{Ig1tItY8psa45~%&)lh+jsi073%6|6EW)Av znkfQ|9SMBE))=?j_nM{X6nAT@vte zs0iMFx7W%!Sf!rTJ>FeghQxKH%GmxI=S-avvl_{=^0`u|>QVTb@FO-vb;Uc5GRy=5 zhw50G%r|oQd{%h#ec$MBStKx3tT_}NUSI0Os-#&Gy{IcbpIPCJX|^6R-e(FM-4KPs z6n&j3dVCq82oSnRrnJj|D1fg&TI%}p znK?8*zwsL0>I~7CURZ-)MM`3gJI$EdHttcMLYkUJ_F}(aHYj9M1hd_C9odNWUbI5)JQ2W85dp@fK*z6mEFJ2yucv)I;d8}X9b0jga77?xjX7NZ71Kr_H6;47g)bhK|1 z8ZWDsKF%p6)${i%Dz*m87V;$sDk{q&c`z1@$}0}v zA>n|4!x0GSMQ8KJX(ue@ju?4b2e|yMFzKpGH5h|jZM$=w0j&7$A{777vL?&`XVryD z?Oy>ItkTwT;Es4_hebM;{HwV7dQ68ch9%|i{pO=df|{HyaV;tOU&Uwt#f+>BB5wy&4(c=$N-AO{@*o7*GK(o1W!3vj{Z?MG%G zc2T0Jl7V#I*}wyB^a+S~GsQZGKV`H57!UwpUy|amP}SQrt;v|1Eh?$e3|FrzdYn>} zA}__bIV<0P8wB$LixXCz;@zil9=XdhRiRh!x;Pz5C&UMM(M;*3G=#nIsos~AYdHMu zuVRht!TDtiEhpnlScb@;|6?C_NI(|mSVfz{P@s7C_dEv|FBl8a-KXUr0cL2zDXbU5 zJ;e;o;_7R(%p^sv;TPp|N!I-+VSd-;bGaLcN;<+ge8;wqEaG+-C#@vXV4bMN9}B-+N%xK^+iFdW z<$?I!iAdd;XX<`D-qksVvXjZR6rpQAkdVeSUxjHL5m9CUzWB{}ao=rMYdqaTv|^9` zB9O^Plr=YFbW~KfG8ch37?>#CdTH+9$(_NA2T2QG>#n0y!sQ{-Np>8(l?-U)2w7kn z#82xf8f?qO?YwvURb?Cl7^JJpJ0Afpjc!zi=|E2%-Z3q}gjdP{CTpC=fG5JI#Eop| z{E5mu$;5vC<1lH@hiecklA=Cj?oAs^X^NTDQpV zM8+Md{SDRSsF4%zO z+`kzmZcC>1_q}A*E8cyY4nJou9x!SfzB>KwU?69JDd<%73xKqY&8ak?)y0V?tu;YreVu`k+kjdKlT3Jwy(&@Y4W1Q57t;Y|`e=G}~sB(sJl zMDGhhklJ}bDjASTiOymFS)te{2p(pbgwfB@U-Ip3q6&Upc#dL)-pQPBcrtOQW5p~R zO%l&hszr3S!42lnIr(5m^@dW)a3W}WC$LN91Epys8>0@cl)Ffjz>Bc(7TmY|p~mS2 zma3`}qSP8VG%0g)hEP!2=n?mTP?rg!a9mQ^$}81#MW`@QAOy;|2_J{GX!4X&rD(L^Ef%u@11-Vj7{YZE`L>@F4{a;^T7lzn!Zqxu!<8W zvY$q%CMA}s>VT5|#kMcxYTk==!5Z)b_a=SsJ?6liV~}^^o(FzH%pt6}4dLm+x)Gs% z77+3m2*r4|gz5|#ctn^E>R2IPrjo+vOC(1MCg%7N?h{vWq1}ol_v7U(;6x>Il%}54 ztiAoe&b!}t|OmptQQhJ)bl8oatzcdkJKUHy!VI~piyFSYr=u)fx?vjxctQFs4Lqd z=#HP4ZPZyEG4_Qnh3#g8EtmFT)SZs@M&+6;v*G%`!1n5tSa|x2To(ZK1sl9!D7<(k zVsKR`uEWp!NI`~}N6kq4N6R4Ydv#r%Va)@nTdtA(B&qW7&^(9J-b!Z9T;8epi>o^g zi6(EOY1I7)%b~+1I2Z%~Y9GZbr!B1TBGv^#@$k@tNTU}o$E=&6$`1xpNRygza2L5= zY1b=yWzIkJ;?WG^iQ=@{Cr6#pvu#hfYy>NE<>DbmgSV2W_Y{|F&|k_pQ{4-**?l1= zpc2bNd)G_NAynd=3Z(TR6+A^VV_1UZ{Q5a@k%(BSlKpcmbij`@?hvwA@8KW%U_H9F$X*lGaiG>Qu3=7dq1#mPBBn4M$c# zPD)2%MYjQ>>|!BV3Cwf3VQ}h-4Gw)%BD=$sSns%m$0ksWl?3yIX8Iross0a?*;vZU;5oJ--^{f>#?v zf}<<_NfPFnUl3|lVy=<76dXE5re7l<7oHbihZ$x-LsgTRQ&$!0UTlb8PdiVtYn=q$ zsd726BVQ7$ZHBx>9I8_+lvU+=$P8nLD#1`*CcDPL=S9-l7Wp*uUhME*A4*j+qjYj? z4A5zZ2>G@pGX&9oc8OkD9I>lgtj9k67Xk39Lk5Jp843YDGqix8Z{+jj5nr{2!>!_2 zlEf(_@fAl7r{faiCd!MKUkGEt2k(zpmFn)N@in2L(0_@w|JAcNSP^mrs;0I|Wb6cjkM>N+wYb@Y&SvEmxEN~Ms&-*lgtT`~@xt~r_O zexcF{U%;uVFMsc==eM(E9HG}zc!Qg~*-%;Pse&@_D2UY<){#W)?!_8s3eyyl<_OsA zAR_@_04uhLx7(-at?yXKR)h1s+0y4%7J^fSI7ohYk4%YapwxhY+bMx;{yMr1yVe@B z1>Yw{8Em!^WrhMXU<=mlAF^emR1xgfO^5+hGjhDt9ssP)Q>5XVW607bUCS4`Z91mj zxdX*?EoaYyZ1vTXq%Xy{L3&A(_S2TkFTMBoHA2^3%f?f1-aHuh2UxMDf$me1psgg2 zT6wu}c@nY|`Btq0MkM8Cm3>x({*SGTr2mrIXv&+3}3QZi{1f@r=nM`soh}Z?2JB zOz&}8ibU2S7uV$2rKdZM!bNGty>>T*t%t@_kOy zYpUpid3~@mu6azaXzVkEjrm0@Lc>+6sX2CRF$|2>Cnge7(NSwwModqLFQrntjqed> zD809H9!0K3968og8;4>8%>b<7U3#I}aml@xMmM5_i~E>uIX*DlKq?TPgI9IRMn-3R zTRdlu@|JY(ZJVOV|6Z~Z&Ahv^Ht&V)>?7*@kFF`{lcS(O+#S9o1|YHPIXyv_B1;-h zUXz&r?c9Kn9^jkN4$N_XNbB!#$dv2FrCpa#^D7p3))@y6VnDqapAEz1gM(S(Xi5%g z+dER|AQTi_6xuh@oj};fA+LXz@!6y)QJTDqIc7-)o@1ahW{L_){NWa9UD85>A@=@^ z1KM&Qm_IssH%?We^uvs))K~R^6SPGD7$3+gF)1rPoRvsD%Xa%XuIz68L&yL=^i){V zo{$b=|8}bsYgjSdvs^Jn|3?fMF=iK2l#r!F=Pcy|cW0f3*0CknZ?81f{h+2pfI%nf zp>4Xi=X@mAAuZbmv2A@x$KUI#fRD>~X(K$-ZXX-uwbR_y6~@EBSva-i))<0WVZMwL zS?5bNyzulHdJz--{zEuvG(Lyg+M>TbQ(QKJ715p={&UQ9cImQHEE2zZjHW^9qBy{R z5N{Su*;B5=<4r@;%rR4AP8f$fntqvP7!|F zo=3`=?jnIYEI}F_W}Pw6*I2O7+LEIVw&dMwpg>bm?e*7bmb z^d@57#_Ssaq8%omtX13`JSh>HOLb?vtRy>Fb%<51(GFsh@q>z8XF*z+5M87`{Sni= zNnQ~qmQdC*V5X*8g|D^Tc9k_-bg(oM92`hk{UmpZ;6mlL#<<}3PNW3uv_h~1K#ZPyr6*^o+v z@fjQi+G&R)Wg917Munw_pNj=$1B~;40~_fMzrT>N;iP%iu69RCbaUg*|LX zN;AFJ2XP#;GwYOeD+!Ay8AjTk&H;Z`>2#GX!}r`(UyarzlkI}UUX09iI&3jRV;WW{ zHx93eR?N8{F*#>k4=jqu862t^*0k%WkMiDM5Dd@xUTGyzmveudvCJ(3cA}SQqz)fa zYRW*Bcl}Ytax&pbjs+4Me$`n7<^?Xq0%~AnFzBi*qX&uw#_gOlTUs{cdhpbkDa1?W z3n7c-q3xU{NGb05=3?K)7N=l%R4D|q`~iV1g!(C&0IkZ%h3@l=PWOuSE*g6P>AYe( zWl)0uuD9o87k;ruv5a_S z1T0Sk+- z|BUfl3(1PcfFv0w@((B<9v|DS^fS)*;qWsl0k5fy0g0aLL*G`{X5 z)Kl^E4<9C-Q;HE#R@&j<=>LBG2tok1x1l%3Ol zJ@^5E7HQ33!LAFTLp#cd6y{$xDWWm$6PfB}vb1)@F!O-PLD?b~^2fgC@W}U))!>W; zh`Eu5t~&P-FA-K)B<8#N2@7$WbtRmO6t3o)4h(852}-J=O|UplW%{H7qDFfJ{rf#_ zDpz%88&Gj<3yoE|I0U(=SM`@2#A$paHYQL%y$oG4?hOqPfP!MXtaQFvH2tPX+L$|` zcqE!iF!A=%gV^J)EwcHYTx>q~BeMr|(-!YJ<|c=$mv4dVO4aE83r@WGR9*(?pjag( z*t2C}VRpjn=j8d0+d`>jzc<6`=C58lN5zp~SwY_?_~r6|VK_uBI$nBmhxZ7W_?7OQ z{C|Prkc+uv96?0;AGXC>wuu$79uRpFE?_W~KbCp;#KvEsvo&2{7>i)Vkh`PjbRZ7= zVKSLRU%3CYe_wS(knE)z12QUC}1HZ#>mC6dg%+%{gnyt z;_Y=^BB>Bq!5G?{yX#=ds11r&em;DnvXZ>stzbyUUXt2kO@-El@0hiwX(jx1zx}6E z0#3Z8A<3u_XoG@j`8?(TC&#lDonPPRVD*V!;Ds%G+TBOC;TU-Ej*NCHqw=JdgXVdV38v7dC1aa3+sw*q=;W{zP>9^ z3loz2Sg0l=qeGzH+0!bsd(3>Ag=lklZnK11IlxzTt4SF+3F$=F;U?M{ zL5^jk0Gx+pIB2tMK;}iV-UD(dzR@$N67J}0Ke|C?U@*_1%)=nHWZ@n84BVrTKh`YDULLglee& zu{sJ7b^L)8^EeM?IVYVj$w!t#5sTiF=jM1XGfxTbNsKcD2#On zDWZqW=ZQqYBV2>r37u(z{;_@1yv^rzrr+&?&pE)%eK=Msdq-boxSj0Pl2E31r#Q!I z&)qeqvRLYItwh51Hzn$Q-g>3>kS@ zYiY>-1Te7nKXZX8Zw6HGoLyZ$Znn{c2*|RNhK5_2!ZBq7fZMLV;=SGrR?e7$x>5tr z&TEZ+jr68q?Xw<79q^w~ZHZe~mKD9F$SumgyhkV5kfD6TKvo2EJp(EJKGelkwy@w& zx1QClK*m-UsH&>V=~j6T^THt+TYUvymRK3;==NK-)XTtwoc z(hz6<0Do4xBGfJfd4Q9r3xVAA#r+9|w2b>`o&$t-j@wi`c3|5j0tyRHUnPUWg_bfbe%k%lPqI9DH$#x0BzUqDYL4ONQA#xC{-BO`RfR zSk)FE9ILSYbG;(UVquF_tX2z|-1H}ex;T!9F!=MOax^xS6;Puj4m^pfBQkHB;mee9 zQQaTV@fHeo#M7UrOXj)|s{ z>m8C!G}Sgr1RxfYmC!8uAlcH921AV?R*8WleV&Pdi|+u%vhh(ez>Rjb3uiB8029ze z`zAFIKJ2|Q&Z6B9NM&={8)?gI{KXTO;{o6@OU$Z|Zij`*>Du}xk3(CF_*Fu4eWy=T z0wr_Cq@^`c%A#D`YBd)^;K21WA+U`(lz0}(DuU@@Xw8G#QiAJy8aDGdJl)XP8y<%t z8t}*nX8ODbMK$v{1Co80$jKw$TjCs^>%s5&1~)l#0)sQv+;wsSmF_666*qUdj|C^N zuePm)Tg6!exp}KXakFoaD@`8CF2fS% zCXfB5f$XN(QCA{VCWP~Hsw4e~?KI`29bfq@%wva|sbtDTM@P;f)Tr1+I9iS7UWno}G>BNfoz_NbJN#kkgy^R$4Gn_ghYQq4h@p7m~4T9fz zbwUhfwaQ;_gxGJhS0P-OVHIh1&;$I=O)JSghLeA_t<+81_vlyJRz?T#+_oZN+hyw0 zrm&%@g2x9uthJS+0x{QC>dXhrdfD+w{La;tuCMRaR`dcb4p)U5s&RyCwH19$-OoGP z(_qAK9B&3Ags#klA%e17WlRg>Z4_;e(TI^aw_b`b&qn0w3*m|}Lf)uBC48ChDcdy7 zk`{tyjJjOUX%^M462($jY2yNFLTBstG|qBx{%U;ZILmIEqN4CBZ?0O?QmFdobF(A= zzeQ(W^)-St4%s|`bdk$Y0Xi)W0K!xrQ09+LS3k`k^^V&e(BY7+Qp^&X8IM=eyq$U3 zL3K=nAF7Q*VP){+62-VcOFq-hrf?gSp+61eS!TUQs`+;=K#Oo8q^`$s^naP^V4e?08t6snEHS?0B2`V1=H~y z);Q07bfuN4k4=vsvSZ=#i(r78I$u_;YMM&VZj@FBb&hmp8q^^}aUQMZHZ8N7I5c2% zYn&!^Xt0a+y-6KY7OMpF;utSyA6p{(A7dZfSDaEVPE!y4=hGj}Q2PA2`-S92LlUIfO7g zYs_p%#;y3(^quxcWDZwY8`~lH>Xx-|N@;iGWyJBeLvAaUrDgZ?kdZ+C7Lkmn_g)=X z%?myHOQoC{JcRH`<+TWASW3mg`%0om6J}ZGaWwRlbspQT&Zxds`dn4US+g7TlCy16 zy+Tm~Xx#|NujYK&&UksKj8{`i+ZesNhzKE{GoEOFW@ z3q`;BTDq6_HeWcU8Y)zhi>8Y??EHVGDJ4~@ri(eh61^8CQ^%~8P&(iu-#O!$+HRMcw9qTcjl=fb2D&$y? zS=;W@>j>g!4owJaa%nDmEyq0Y2Yy61_g9x=!VxP%xaf>kWGw=3YS=d~h0{qNu&AV1 zF=U!{nbws#>1fm{(8hl?4K$VKb{!vPtTR1);CWj9p{X2HF9ICERU=iCX+$yE_&$ zvqO~oxuSI#B2;lMXssyNioy)xWDC`wEmkPNE5Ym94&gS~V5PIycGm6qrB8Q(5^G>C zuS79jDDQAA`s{HzZ|T4}bhKCZT(suXENIHL5~Ek39oN^U&yi-P0~r48n?84o>fqff zgRYXz7Bonvx}KGXOfCgfOzT-I;7*@o(;c>|d987<0 zd)Tl+NpWNIA*{=&y0(7dD}%qLZyTe#@cZTYno-uZZeL*gL7Vp(n!H5znY0W!w$GfjWq0Md$fFNB!e7)(+7)5evWU^oQmAAu?~|C|dzY*Jg% zz(rq(4z1|fET}PPl==Za{~S!7FFe9mYa#<=+N#sK$_`r-Y60lC>7vP{pA%l8Hg(R9 z!hlba75m;=!S`{mlD+qS#|K>0l}fn1H=MYp{=AeyFea6XBvLThOLK=7UxcDbUvd(* z;x-I88*~HyagjZMc>;ZjP)XN5H?-(D(Wg^9qp^Y;F4ed9(GXMdG0SFw^KU2Le{LUVwP z$aLOAQ+w*^2zR2}xJ`6K?w z4(Wy7aDR+w)o&wbwXzWaKG7vo)6by7RK_V)W`R$EF8ze8mnX%FJ11T z87OMLhX%T+Qr#oqd=ZUt$Z^If76Sx7qZU=~b{!%_umhwr4R!$XLAHmJ$0~`mEIXa| z&DBFhA8k!%j4~_nUH2wdy9Z}|d`>AZ^z*i+V=Go=^%};k*lcs9X)8Ut|L1E?kBMgk za4PoX%{8Z&q**GOeSI)a=9XJdO}%w%bXtKTSxu&qxA89|xA6GI8Z&=l zR6|M|LZBnyHiU$UhsZ#Aoy#I^;t(|FUHYS>c4>} zYQWMuJK(m>aoHMnRhhRJIi)D=olJTKN@Xs<`9Gwh40uRnqFJnBIcVAXolO^6ARth8 z!Td(?K@)!d-%wbpRK66iX}|av4w|p^KAP1SeSa-DU8yV}FA(Xd`6*7wt8#ESx{DLZ z=y@B%%``!WANmHw!_{lEzO`h+?s*(EkQiR%-%fccXi=gD*(T?_j!cq%p zH@S9Xmdw?+VGELp{WF$P-7T>uD@rjn@IDI}v&YVx@ByPJRxaMXnqsDpFrVP0!e!G~ zI+${m6>vF_6}j6Wvdp=$;#<%|6W8K^U0q`J9P>r42Ux^kNT%Z-Lh%;AF}u{H|IHx= z`*IQt;lD#9O2SwrG%5gY6I1@^!U8WcU0k#TEcJ3qf~JnO6e)9^m+oFR4$4?wF;H2l zi-lQ4EoNF^>_o~?@pLBFiy?@daY!~jG{*TOBu%b%vCQA)PWG~dWA{a>dfG?UF@s1YZ1UMaN{1A?Tt>! zL0$rdCqHYZC|LUu$DsqIHV8k!LEkH z`knFE5zKLb)-=yhpM#cks|IH@c!g2F!VE*rxA}m)dsMW|450vnom(T&iyOU4;!9FAbSgf21k>hI{pBH7i1xC-k_(~+7E%#m3F z;MqcjR+FG~5B-YFo}h4!Bef155fOlh4aaxMaXcm(Y+hbI+3w4*;fn9s_8Q{+d$DTx zg1JK!cCLPS#4IOaiYX5hrW>NMDL?b^Gapxx@66Qqx^AMMdR|t{(DU$z@K_?CT9mfn z?LEN2rVsRaea$pr@45q6xoJ{Z(ZuYASfEt~+ziI5I~TdGg_SHpPdj{;l4hi{YpbPQ z>@ZAe>qOm3QtYf;ps0(sCK@n4A}}hw+Ho9;5Dv&87p`5b)e+kEvAwMDM)reH(4{Ls z{rOWU-#Ub^V<(~9K3dkuEu^YJ`Bs|4XLxzLsUf>@FHk!2yn9cluEfTT>Q7@*Fh-hO zfXPAGkVig{Win9ae$$QW*}`KKu}ZP1p9^^sa|^8!!44mvc~}k-(o+<#0|TXEG#skK zg`a^mwBjfPbf(VX%EfXXuWW>n+I1UPvIRD*F?p^+h`7xVQHR>5v~H)Zs~<0*h{Lmh zFWGoQcP~qh+aWnCC3hU*rSbqaWj!va7jpZs z!LYQ7vFc*}MfLA<@jVsk1TLWrQiQ!^kn+j#(-B**$JDp@D!%ta@euL?45 z702vN5xAU-a8ARyLqUmH*&ywmK4vyrnl1jaUb^;dmGlNNko1zulp9F5pZlj)`d(Kx zYQbsO?n4%cz({SC2pM5%XjkU~?WqPOA+94vrTuX9`sEhqIE%DFN4oY9d0UzSgk#?R z3u%{=y%4Ub49YtiMj_vBirhIz%yG3Tk>Luhv$b_E2A08;;xgv0(Uz085(=rrWZz>@ z`g3vJ*Al2p$iYW5Uhmd+e@Jhbq%%762$I-gW?Nk6pC&(8tJS zB&v&WVAF8{C7h39OH-M?+5Idz<-qrctcdl{3X4o4dO^0Lz@>RGM z(Rus&CTDzAHLpP|t&!){<)0l7vHn~lrv8Qv7#};8NQflXB;3~MJP%#USy~)ZN>McD z?iCpZ>>y57^bjg-ja0tl7Mb>n>@C`g(*j`Im~1>?Fu5=6v*H2r$;S<*39}(f#W>-% z9s5@THc!eX7$-o}xoQzKrDgMIvb69*9X1!3z`=C4E!(mQtSSu(Jf@okupwOQRuPM& z&gr9Ra1oXW=Z$CAcvxX@z~5!OIg43oMssY|u8y#giwQGbq_hHSZG(?AUr@|D7O_O> zhu1Qpk*OMWhSWh1B%JG3z}Vy{|J26VGP&7x#u~G~m9hUZjM1SLF~G9K>20QiRI5&@ zBGtnQ;pbTk9te|zf*DC~1}-Hnfl5e^;ua}g);7)m0{m%P7b@VG;X4p8nu}zLQs+)5 zY#lO?&U?R8R*lc|?A;h8P5eUtiOn_uaYxM%rBG`8nFmn$yVPUrC}}@rs?ks(TnL5u zLOnh^c}gwTrKjg*KS1XqkR91>W)!%QqGQ^`)15qym>zj5BQEaq(!+5ZH^>RgbPk1w zDDIDN!Wv1E8zcfIcfE&XesRL8XPm}Khf{O9QdMc4VdmzCU@=P;>ddRKUrq7!KmC9i zyA?6q29eV=vX-n#z;|ir31ZupDs=x_Q>;?GhJQ!145kf_-h9@-qm-&a4Qh=cBCIai za|sy3(+llDeRwGBLN`L55Qy@<92J3NTPn_ZL#kpxogrmDYX7h|at+~fIC|JfF;%?1sf-HSFSYreO_T+iM_Pd zVC*qg#Ah=i=M3-}*RH_%I=Gz)KS$~n@awRNM!BgAt&c@$hNz&z<}z@fO!e@FGB%Ns zn?w+8t4kN_B6qIp^8Jo=ZoFM1abQ*nl%SNOq^Gi3k(TQ;tjW(3n(J+tWnUGJwaF%T z&i*6mWG)~ZhYZTk#sq-V-FEv~rWUz{a3wg;Tjm6vrZp)PtCLP4N7+}GO@<6@A?h=K zR6XLnMQb#-NvV@(r$CW)P2-dSSAqzhCoyb$90!7pUfu=hSv2(^&<(iA~1r1fN@I7>foI>*q zeX($LH8a5k-4|-v2Q~|pYS(E+gU3nwp?N-)edWuSx@0gwL|7|2ob?rAChaS!hQXFS zn5C>68kK_Dy6$$&m|+Gfv~UJlZR<-C_}+cgV8->OI5+lccee-^hTs;C(WWD5Ar_>U zVfS!vCCOxK)Qb-R=M#aO2T86SH6yEp`++(D1{|7EypV2jJVQ9rfhBfxg6J)qdbxezP*RXudscNc;v}i2_}2(G zef|So(QHPoz^-&dY|BRJ?+vm<>G`b!HUb+V|Kz!Xwa|K$#Jy+ErD%|{`h3)2e}H~o z9ZoKVH2fEw&rF9kX84GM%|eN|qJ6YlMSdogz@%_Ouq43A%_9_M^&Ti1v2amg7$cmb4MGX7)dhBS zmX@IR##kjQmNa|_4TU{RBh_)rcp8y_Pr)PRfV@;TFO?iaR01EHMJn@-$z6Lu^JTKb zB$HU&@wQy>+k3gHYfOs_3Md_WKYTD zTZ27=&J9srG97dxoNy@sZV#~pvM+40N;ZX}BRA7%5}u5A7RHBPRK1g^v2#p8)mRA| z%?^3|x>}=Z9Upz~~u9vzk%Md`y5v!9SLM~(YF(Klb5Fe^F#*Z=c> z{lEX~|M)*y4DuN!WGk_~qqQb^Mr(KFuTyjDrl?E8Y6yXemDLgjr$Vq)WYYZB-J$|L zVCkcA6$%|A%=0pi7boBZZuh}881!CaRkjDWn4HUZ&4$yL$A?Eg4A3{VKX^rGi^FzM zlwUgD+)6aVN^FSrlxU`d8wgIBDWg#%lJRpN^B$5?^qdDQP=IACwKMQFGT?9lzSL2ys1WhY#<66F(Fiu z9*IpHOfHUkL#|7RZYfm`N%~1)51y?bGbF0+Oy>*;fiO#bv(yqbnKgUtO3#eA_5}Su zL7h5UQejeT0{q3tU7cmlX-76a%~y;bATFq-c!D+SZxx%${0mmj*h6Kj9!N^XFkiyK z#GNvu{)|QhCzY0WZ;Pe&zaduP2S#Z^KB+%Xb}R$%<%cn%bW}l=EU%UURWh`6(QAj4VeigqN-frm&K#bfvKOZ--Ec8Q+jB=&#rsQRNhd>5 zZ7v#n%3dToc*tzJMR0e0fgMakML74HZt}qdTef|a2%T0GwPEKv9nUPMQ0oGbRvci&M5+ zFxK{U$_X0;rIMm-^ovIf2;cD>8P3qCYn}nG@!%6jRiQY=x)Z{mL#uHQpc#MJ_b*hR zcz22WhM0oahPLpBX?N2E#=#?Cx~HC_*Z?0jj@1*Ek0T_@bkZ=5{0%Z=-O5qv2yV?F zO|}}!{@kP&v%_)KHC9epdil%`>EaTjGN+#Rn&HO@9kLNf0_yD3NTGE^`8J~Jk4eG* z?y`X%x>gVP(T~}8;YTJ7cN7N>plOuELMRT|)~Ipz_&g?#G__bA4x0j~aJJ zCsIaUc4y9BUor->%8x?}^p~1Z{sH$2%r8YidY6?bssj6eH}Ju@XPDnz{&!)13XoeG zyND&?POEM@YVB#as%(&U}CqLvFQQsl-R?Jgm-=1AQ}^}%5!wbY+t z&_X@7SucpbpV-h43`r{wG6b7_2AgT8OnxOKSorN>U0ZV`^VJi_Y5av(`{F zBGPSH_~{;RrI^RL<||;f_)amvUK1`mtQ} zt+cI!aNbuI;v6?35;%Cf;|9L8II$yFF~jcEn2$AFnCo~Px&GcNq|C`L zyEKbvrNA^^>tW@GZ4zx^oGdz9Gio#|4!?7$Lf?I;i=X|*ss&{ja}65?Swl7Wnr{ve z-=>ST+UnK}^O}aT!t#_zJ&H_0Xt#E86DD$r#O|+*bdt>p-jVI0$P|cx>92E32(Dld z%)i>hrHy?CSYx6h$o|@omdW=o4~n2?u>c#A6yVDIi&Cdg^thC(Jrbbe9M$}_et1$z#un7D|t0!&`w&_S%)BRl=hTaSEUW?S=F|U zi4BNt5ygcK8N+?`q)7sj7{57b_gYguXQQz5&4VV-*l{71!MZ!gQ2=}694md*BmTuX zc5|%Gaho%M0{7_R2i_6In9#+^Pm8SHMYSj5@eg1>J@HM2oGZsf7vRKQ5L#`M>o z>)uLYUFqU}$?FA+jD~g&1=*5T{;U>C(BC0Mbo}qp#iiQR`-^t*V`ceAx#{O4NWo-_ zExuQq3gGX#)yHuEUX}R--rv=hF0dW~WJMz9Xwj5s&4k-=c`a zD(_@41r4YBBVx_O{;}i)Z2yqhFK~GD%v56EMXQ0Gc<1jB`)Q9}z>j66Dc1=}UNS-z zDlBi61yR=R;I%S1Sm4J)ohkQcV6M`6tSEDgKSJv0({#Yds{gyoeJjPU1d|O;EYD*N z4eg;Db(Sn+KBDipDrgWN*Pq1{qSI~#O}ELC;+e#fPh$mqLRAP1;V2D?aOtMXB$m0i zZb-S8Fr8gcF2b;8)QH6l&!`6G{>=6ejH8;M-u^sYmt=bgiXRb@UEt|Z-cHV131pFY z&a$<2rv4hQtd`JQ=CZo!CEKW1ypiqc1EuGWhh#zu8G~h3r-;MqlI<1;3AQ9tXTh}Z zp%9Jd9Vzs}&UiqeifYu{E{SnT%%_)0bwr^p~hGh%h@DEFQ+E3&(RU7;fK#s40D^A`!FGjAc(Q~}OZh7J)x$JVk;C-&fwJBa`))hRV?^n0^e z9XvSQ{BlnLuQOpXvw5aYvQ`6GuM#>OlT1kwE0tqMhI?vI+JC!0XiIO|A+#Z4?zz&9 zB|}JeU6&(M>@7SZTG(@Ji-#bYe-S{t5!}v1D?Py~=|5X8jV~M7}Ma zMzS68+Df)8-jT30Iv>o^nm|cv-I~dVPUqLUOV^S+shs6(X&C8dkiM-9_mSL;LpzD{ zQ-%@j=uV7WI?vfW^#JP2$z*DBOxZ!cyOG@Nu#Gx%bz)<*s#THipBFmIACWKEsTG4% zB{hiCp5q^}%zBJyPy1eDRO*AiB;p#L6%kDtA~`Z;&c2+Z_G(t2r!H(JjhCXFW^ePy zzo}5>EqC%uDOt+j?A+2ehgx4l_!x{#W7Mw_Za2%P4|T`KAOmz*nUMluH2Z}<$Xq4M z%9SD(qMH8eNM;uB>SDMJwSFdGBbZfbdO?~gWMyJPK};9n^kk)95Ks@}#u3zp?gQIB zC$GyL&fOx(N-nL0tqqUK-gI~qkwxnS0rNtBvCj5Y_$ljrvY#mT)Q-Skztp~jKGvt5 zOgs4X)ew7;rivJj!w;YQ`vkAcw>kvWfT->wa_B95l(2=HEl(5X@v}M{t}WZUkdSc^ z{7$p4Vy3aLtAO5>X~~;Yla<(HtM1PU7M}C@rl|IEyaaYjAXny!cW+XD z!rS~)lR@S@c`YBIJx80Nx>#Fa4LXRDpBQ(})XfhM9;>FiiZ;8bV+^hw11&g#1d4$kSo8^d6T z^~p&0J*t;mCGsb*=?10;P1IKAVop7nk-F`SFajD((!HjF!VgmJ`<_e*?WppS4fRU_ za2<0#WUlol<^5dVkxmn{K&GF>Y}gF(`6jIKSuZ(JSHYYVJ>^z+DX%$N-=_bNru__U zBAhD-&t}a1(5D%Ig^?n zUEORsn)#RYa~;gor-a;gKoXFhZY{0t7d9YY`jQmuzjA{U?0Sz8dA*t7R9>CqERzuIa|)^NrB zTh%Di*WiB}_MmI`nByA7`BDN-tc~)^Y1b9Pd!aNP?lodraK+kc6=Qi{tM@6Eh2 zPl>E}kZ^9V1lZ1ESN0BcU1btD_hx9y&TS4iaPw6GSI)Eun48_&c&l3D$R8*7kQDz> ze^t8EA?s#5CgyxCl$;tIz~qX8Eb_Tn=ojT%c4`;-9NKJQN71Kr*j{1s@NV_f4f~|N zVxV(WRh2rBgLWd_XxR&)GZTmWB;X&rO^NEyD|A`}w4uTP9MF|J7JKqKRpPu|XGkYE z+P-^L;EOi4f$exmcFyZ%NDuIlMwX{U{LLmQb=p-bH4CRW=nv>;)mfOUG`sp z4+lN^@Lp$tnDdi#caP+r!P`Hiuon|J0%Lv77mU+K+mLV0cvR4OKk}T`S-U#A66QA> zmNk{9K7NpENwPP?W{-X;Z!x#(Wdk;e&A7!zW+5w+=Z;xpu>I`#8Qvj zQ-HZ1ln|e~pRLLG$_{gcc$RsEndT54ouJ6ydm7SR z<4&`y7K^iKk0}m0S4p*>Dhj>#rsF|dU`BcBv)-n?#FQN7o`UgeuM$-*xxI1!=OKC> zM>a4;)vO?HkFW9YUZ={F_FaxD~g70&3WDll&?C z>?v~Dj9FYxg_DOOr$QB2YAM%~ko7cP@NE~S;!<}@{UjNeDR7Z-$`4bKdq{ge&MvBu zHA^|4^h!1zy{9%f&39iwIN8Cs;aRJg*)kLlQ{D~8x!db4dQ>UfO%QzVtE}g1!QoG; z{KAp6wPQoZYOblyN5*1is;)O{y@`0SRy=H;^UC!{G8QlJ{S&zyP%hT`sw^c10><-d zH3N#X_~6YZ&pLY@Y)%*P=DmK7h?<#pv{<4?lAwrKeZCy%LBx6-@4=%z=j@FfIoX4V zUog~Vsj+JD0s-=3bKo{2bjNX@KmhGI6Ou@i$kR#O$8lKf9dC0_h4O0GOvul!=clUh zl9w@~_L#FdQeGA?_@KfsNC-A9Qh0(Y{*x#A3K4Y`br>lS?%ro zl{k^lbcv@evfR1JpCsVdNnr=633$tVVuP0hSPZmcqFcXUrhp$~#24J>vJgC!oPsUZ|Y87tVX|LS!uh;uM9e$(@{BA7enY=RDIAhr?_pQ8ZK7> zepAB7n$zp}-Nifd-kW^UYL4;onNU`{`?|G`tjgQipjX}S|Nq(U*-vSx+ud7|HG&I( zwkhCi?76;LE2+Hl!TXnL@!*$?J+r`7GV!}Gc~*bJE-2EUzs3-s^~jm(QY^Jb#fF0J z0*T$z2)Tz~3VaK-!aD^7XG*_iWK5i~C;|M-uE zFhV&?K4iSa{N%eCBV8%; z=}Ch+y~z2~)VYiuFFBu0t-bRHw)UabJ_$N1+#guRH_cXE{nPr);kh5qugUqxe{vf~ zrXeyfY+SINfG+;?N&l{(fBXzDRP}itst@(~@X3yjjQXgbWw&-eE%Z4fo(FZdH-6T@ zhf?laZF|(|Z5x2v^0rxYyl_JW8QjhGjhya!>%9+Jv~AiuL&_Vs{fm^jY-{-al=98X zedIYl5c64^`Ce7Z)B3-AGM6LNsQrNt_TOz5^6yuw_26l=$aG$#iuu9G+-<;te^*1e zlbCPZ<412d3pyF?^A~#%ABcKF2)lA-0m{Myy^Qw3J@(shuD144LJ{+|mg0Zje6ec( zKTS?UiwhTYn(f`$jG5F;Wj=hbUm8xZY%7Lf-WaLEXk9>OKC(C9{56Bm39Q$|GJp7w z1IPRS2MthvoH}T%_X1?M%{0pvR_dEpMoMNmV+H%;*I?r64+q9J=n2;!zw;txo}&bJ z{5qK8#|Kr9}5Dqrk6V+=6?G_LN_#?L9%(49U0rlG6LCu?dDyXcwOi*bF8oI zGCN(yW*dLwu-5v+VR-JXc_(B0GiRR4n40AEr~U4B&+()a?I`|jCYKCvRp+RRtn$1Q zGW*hVx9#}#&kOB5h%?GkRmMR^ep|-BWU%iKWQ_SEMIO71igt%0f0~T#L9caX+e;=f zA*-t6E2}(weM#(_QtmD=4>*4ZoM*?cJT0gF69cTX z;kQ59qPwq%+5XHO=l36%geC~!r^snP*K$@#(CMafm2V-L(FyiMvnpR_WJ<4NCE zr*8eviur77k+PUt?qF&vr~&Rt%G1MQ+B-#7zgLjqsmzy;-FC4qoByRuf@!dO`9J)sU+V2B&pfcrfm$1C~|UHAN$3k zf)Ap|%VIxJ=9|y;T_H^uE`+R{!1Y)*{mxqXK*mXvAAhXRD01IiT?(@h@zi6N#_}I~ zt8zE8yTNQ_e)IWD3GP)@Z_n|m9?s-vWK43pXRFKN&!?(r(RL4>?w|!cId#^dQ~B89_@|XNT?W#gRMnrh^k1kpcmFO- z^HkfrmvaS>3?x=-M)R++Ci`Mjt><#mp}mFZ7Q39W(*EpN$#Aps{Iy?G;SZ0055KAk zZ!eTX^cl&n8qAHAI+mb8}K@-i9&Zho_VD*!CU-ISy%>nbz81>Il z-f}xgQQqamu|M6U~g3R&xbFxl&q@k5y)Naau=rL4&e8a{db0zbY>fnB881Lnoq`n zxHQ_|pxyOtc*o_agwCnZC5BR}XG=EA8;&Dy$o_JkGP4`pr;5yYAcY=U~*4 z=NaF#Io?|JZSm}!S%`PW@K~SWz|8LmyFUFN1nMvKuO7G`mLwSXvCgLB=|8OVw!ZNE zRi(=(amSz!;C2lc7z_;V$HZzIUh*GfhV&G#`={-iwdUqk4FC7P)ci^j8WjR#xLH;S zG30Ng_frGft|_7BW7U$J;iW~FvRpbW+RAqK`MInGj-bt^dil3C6jo6i_Hu25s(1Ub zygVx^k6)Yp2Uc}1i=DZNtcYo5!krezAmJ&!>xY=q;_RAtYmGZnJ3uai-p!SuxwFy= zWwv2_Y{)rrM_EGDAN5T+e_!)RS>f{uZ9a+lz6s$Yef|vTUH3=9EQSZeP(@phdUOw-tJMBJruDlPf4Kk54Qm8y z-^%v9T;K;j==9~Kb|tjgYY{D zyLG33|Fpa@(zqzU^GQhi4NVTnZ-_G;$G;W5_@aX|&*d_?kI}PTy|_DxYKfCuh4E2A=!bnIZd3PwxUiS^$4T;w3vY+qZG@_{N2ahxkV``MR`4K>(4I7b#c6>IC<0s z#@EUPmyI~-*2?*-I^-6t-wdd>M{Uq>5Q;PL1x3bqKqZ)Gayk}dxa0;F=qJ)4^7dlg zKR^85AN7u~5hWztb|DK22M`!i{w3$K6Sv1lyKP;5D55XKoV3TyN78~u*x2-R zhfEBAvuPH*KuL(73rWn`1a-#PfezWoqrb&9K-(k;demc_XH2r!Ck~> zCPe8rx5?R1?TXwcxeUS>AdcmC&WrB1g#?rqLjGBK5OTnidNpGNV}qSz)LzZUX29<1 z?e8W;<|wxPF5p0w^1^1FyAFfGEw^=24d6O}<52*|+1oD5+|?yJScrKc2m+ls5|G}# zZ{tq-h)JF-X@|w!^wr;u#4SQ3VZz+pJ&)l5<5=p!klV36%d`Amzx!Wl8`pJwvcJQC z8NClE-tA-iVI*{wfjo*yIm$1V&>g;qn5~5EQdEe&ag(y*T$2j$I8b*;M@9(EXLhmC z%kv00zl(+x>iiv_3xai#vxmuI+g*-3A;eaumFsyDkvoA=a(reHZMf%;yvO+Z*?KQ6 zrY*Qr`dlrR%1G%R6axJ7CvCP5lh8uUjHzHJZPy+~k-i^LT|P;_zwLTh5ouMhdK5GH zlc0z}9|;Ie!ZtW#0dClyHaA#SoDu*S-rd2vp_-*DqdMR=h#j~t|4hE$0Exp~{~LH{ zDV|{j}JS zb39K%TmSyFE#U$>@i?&Hqm;5q|MEANE)@5JN&o_w`*36MZx+n^Tp)y#vMnWq@gBiG zN-5LIx-F(TNhznu3y;v(bs@INuif4J7)JQ_Fhqr(RxGI*HbBq3WBZ(k@U|} zvTq1BImGa>dOU625qx=G_-9v@tYQJwAEj(fl|M){9n4(Vz-s{N!}maj0vslecX7q? zVop zr}E%GymNbgDVw1uH%qihd{*3K;nL>{v|2GN+XDJjHx|J07?JW)SG~~86J!_mv%dO( z2Crha0DPA+yUaJu*3~jg#9qjB(JYBZD@5ncu+!1rlCPsQ-YxthBd4Xh!hMReqQr42 z^F+!cIY&BvuV?QdSq8QOKTt?bFqzp|oplFtmvO2z>M&^eeYI9%`1;jc&(bVgKW_0! zjk}h4n@LRN>@O%1Gq@7-;%2L-83lv-!(n6bK4(^_o#G;8@jgeGeeh(Fa&~0WfK6-V zdNwg$wn^MQ&zDsBf#-QpL_F@vh3=Ty)SS&YqU01bq67O3+ z)=SAE-plx|k>I$Q;>r0`g9X`slJnU=mkO!NUDah2$94Cax?x11M9RbX(N?Hx&;Wgk zuuNf9N0}pk%Ef#Y2#!A~ZwwJ&Q%#7>UK>$qPznlbAo0kp<9kOhG}+RP&H!!_1S9G~ zL2V9VH_z9yJq@UmSt$c%J+0{+R)6{RCP@2BCa|Qb z<_^e}B;U}6m811LRLkl``bCu(D6m6 z=Aj>6ZNiV`NfH}JW+mqfrv2F0UEIstKy}L5UcS6uQ^TX6et2rH{kfv_@D;ySs8!+q zjZmH6z3Yxh=)jv*O{)8>jQ!*6nd9f@V)CA!*HRPdVnCBf%aZq@75w- z|Bh{$fb8$e^nAXqVpJb;{kIQ+<49hSIM2P73rH&pvbzk>ka z02Hb8ok~||FBKs@edIE9;QGNqCX7__{$C#fkfOM#+U}^1cibArhWvTS2bm}te$I8dZ z?c!1|r*C(DiKdoC0Ex({DS=Pr2ItvY7(-}0yNjJurK?r_?)WOh{*cNFVZUqYKu}}w zH^Z5F%rZp3q(TsBAxR%Y)DvPKGIRd%)~af$0km`FFfmGpPg7qCcdteOf8h3Eq%SF^ z9~L~0rfQtOhaR;AA(FSna$0xJmF!9@DQNMpmf&VYDrjLPT4hkG-;GE+OMJ3q5fRbe z>hu?Pm(z&@VMd3}4{cf93`5)LRn^g=Y_prOv`a7-a?R?Z2`wjoIRgS$js_R5Hk~Fu zEeb!{(c;#nkiw5%@1(O;Te*Hj;8JN->CY3=5SGxCimC6?rJ{XJxjc*G#^G*j%Y@;3 zsp{Ffz7$5uE4A)LN5QB?A6fuhdoE zU3XqYDp}N#G~Z=viSqjtvpgxYyuVUN;pdY=wl}}NTh#JaZ|zT&Bre3jFO_I@$WFC= zQldWh^OJai|M}}bB0Qgz-UhQ8Z71$7`sLJCoZ>0u^TGK@Zwo1}>VK0&KRs#h{4Kfc zB4e?!K@>ci=F^KE4)cjs`M_9x!Cn6^q^vxO_;8?LkmYCa1k#dsG~D&?*p_KIv-e{u z)3cg3ljyre_eAsl8FxjL2QGZ%nkV?ah`(5mI>r{*WIk<%WhbHv{7aS5d+h&JZ6ObEnlIrcEwgr2kZImFYnoVxvLSjA;HsEJiUCdbdMLiR;Ez0 zKv2cXRE8w`=eO?dI+wTYZG-?g0DJyQj&X_rXlG#U{Pi(s-}I{>sFyrx z5z&C=EMn(L;}mDpTg#Y>0IB8t^`Srf86v{vJH8^^(WFJ=&3TC`VmHKhT4emQ7E>ww zz~%o85q04%JVh9nR~Y;7v{f}eZn~XqRYiQVRQ1r-Kk>i+=c7Nk>^525#wPE0`<^-5o!m&*$xa1c|s1IZ1GZshejhC)5 z;9{S5Px!{+?;bQf+QJ@ZBzW=4h^WJTRrh}Pgg2Q!aE06Nzie5XS++pX`Ar9u{pdW^ zm)2-#SmQ(%qi6btf`86|N}X)sCnks9C)TjFhA3<{X}eLhXsHV!IW^^*kn9x)Q|lIz z;MZ|wfBZ4~3j}bsbsdkOS0t;s0-q~8I4l`!RBv{$`DaUTG_LKAR{(RWGz+mNd;7Fl zh+oG6!u*#a;1<2x|7S~HDX93<+sF21!G4n5H9oiU0W$wp|X`ql^k>y8j0@< zgHwJmkd<-C|kfcJ1j**|xh~*P)!YaD7EG=Z5vFsTk^P&|T28he+Vdz6CmKVwu9qwDVs- z{09(OH0H++B{Mac)T(D1m@Oz!sx_vjy56RtR8>;2pl!8UkJ;^|R5M$G+gV|X8{(xI zZ7UF|hPwRKN(_o!zP@T>E0w3btfFGUh2m~6T^(tqK~F2AJVp~IkJDVLN2pcmb~aGLys) zXKcI{&Hnwt8Ov&tjIU;|Rk}2CPJh86bB-5rtVqUB=p;!+7S!l+rK32-aH}I#U5D@J zBUDO0ihQMSgLB}E(@kwjiD2F3vi-sjPz*XXM$58drS@6JG%Gz!2km+f2DIZn5|-mD zem6W5(8MWDf^lq1!7>43!-D!A|K4>@{!^~*e!eZ$8s*N;Bm3rrP`xCPX9S_$Q8*qN)c>kzDOwvDx%`+tjfe#xxwI4T|H@J)+FqjJX7|J|Xw*KxT4z%XNrZdY-Jd z12Y=yz?QXOWW`h>>@nt`X(6iz^{hpX5~2MuoOb%dvh=^3bEMQ1AaFQs14a7>{yw8T zu+?@T!&C6LZ)?pLmE8r)6b5$)w5sn9=MmuVun1M4(r?u(J_zRI!Z84pE(o~!2=j^C zFqz(h4y1R$qWoypWOQ4Z$;rZ(?k_ZE!_N z%vNKW*^h+RmuR!Y*EZR{j;_A+vjkIR8)fsZ>1xxO$t!rRzPL2mz(ykGD$vCy0$&U5T}5r#c_9tJqhEg zoKmHlu%aZeh3H+uX0$l8^(zF!wrtoTTf4&hT{EoczN0E2Ycj;ql87OiEOFa=m}lKV zAL#+V1R{Q_?f674{b2hO9!XXmwf zjyLgH3+0RTxW{KH%>dFRK<|2byvl-rE3QLIDf7c)fWm{z*+f*FIX5TVW%o&2b1OZV z0o9OdhEv-@VH0-TMiFWxV@m|w{qz}|t6Xiha8kPo0uNjMCI(LT>3i8`9=L&|wE2p* zCK7r!mL~DvlGWKfGdh_82)U%h9tqm}#$STncrFWy4LBGE&tA4{M{BfXnx?bv4Cu`A zm~EYTp&hyWMI=g3ed}dTGM2V+tW8Q^FNkLojq!5G+)K@&`F=tr)Qj|+ca z3{oY9w@aac#~9ST!j=TrcePKAih6YB;*-B-MKD7x-s6tP!iO>*)|{IH#uGY4Zu*G3 z*-tUiEjtHIrezbJv_kEx@wd`0g&rielgEE`p$M%SW4goYE7nw`lASp`$OuGBw?n^6 zP@qdp1Kr0-usVgh^^=-$wFs4)lD+VagLXK-U&NGP)x@v z2Q?T~AVgIWtth>tM4wk^AdF{e5NUwSB?l-0K1j(5`?c#nkU|TGUo5eB>k*v=YAqA; zvcSK?eNaP2K{HB;tE!UC<+a0oq^y^@$Lyeg5jm-riP&7retfnUXy=TDoH=nv``lsv z41rlY2@@S;N476!M8_O$3Y0}-Gwwifw1;p-sczC(u9+R?h_4E-ktc-1Qa$c@V7P zk0X?Q4}WOKTO70E8|zz*ShkMRC6;AUQ)hq`r?&MC#-qgO5zK^!Z$)WnX5sdWF_t3G zIR0xNQYFKR+Oe2bQ@M4b^Hj47;bptq|E3GcNZy7$&V`_~b>x&(w?AI1xcyp~XpWrE z3xy4*v}dfm{x)P(-d~)vi!~;?TwZGSjT$ui_pZLN#4|1nsK>Gb%x0Vi^Raf0yS@=( zUAX;Xj=qHEl&qk``*xibcqJF@qP@XaAfN)heSO*ZWQRdh+OI%ZYIi$FZ7wVHmzv?Q z29++^$8gvZhj9Js^jL+~eqcM-Plv+-{Nj{JkYCw!eW{Un?&3x&lm6$n4;9YVMV#U& zlp$%8dFHCz{&Btu9NmzzIB7*R-4I!%ZlQ&CkH+RI_Nc3JBY&v-oVXE2(&u65oI&su zGrpQTMvf{#+OMQRYEtPC9)4eq4JJuL3|0at-aTlN!bM0cqLq@#anN>U1H(XQX@GK{ z(oxG@e~D--9}+hF7*+IP@2{0~O&XwlmpvRKZTtfkh8Z<5=O(1W@L=(-sz=575$eu~ zqq>2L0~nJEVe~ZA?Y8M;%leK%-dzaT2km31vKf5zWpWO>47drIwkE%_x#Q`$`ZU-) z0U=D!;fI6=xu@16u;2e|gJSf>jy*m&ek`4AOnaPzg_3CwKuV*B4}g-$*s@YZoBe(Z zXcUe`7v=n4;~*N^|2q%BqVk;-x397#T~MvDIPKvd^(acG; z8g&FRKE4OT$5G^@rE?AoXN`mwgY-4DXYed(BakDdA!J*&lpMZ_u-fsj^zeviDgHmx z!{Yo4%7jjiV1*z)c<=8q#0+4^7z-$Fa_y1%0Q7{2n@}Rzi_9PW11aU6Wd7gV1hHDk z0$P0x8^^ca*wp6z9S9CpFdx|!<|Ac4u6ot?;QTUru|FYy^_M>gcW1td2y&0w(%pcD4b#A?T-1Y z`1|^Kn$C((91)|s#9dhR&vHz7wne}D+6BvN>%-A~lzC;$cef+(!a(s4t;E-XkO%Za z<+ywgKyhU$+b~5DUWcQg;3RH44uP10mU=}f=$Xddh&DeMUTvyF!UNI2iSkKO%WiO z7rtJ^pD}RhHXW(UQ&W|Z2*jt7kXQRrK*w{bUG0c;>G5OMhb4ZiRb7g=a*9NMq5JTG zM+bf5nhcPso~7qkXI@&F+xNDgIcw112KP=DzUrZW$#@KL`Ip>t+!+RWX9Bh#sbTeE zz)tyvP^+Y6mWmqyN5?3~AU@2Zs2eBu^&*257Kn2Fq?51a^+(~V*cU8G=v3i5{B1k0 zb6*(Z?L4Ac`XZx~>N?D|45Xbbr53JB3({X^JGnAmRT7y3DnX2Pj};z|$*&SJ{nR9=A%Fi%541q$fpsxs!$uRg^B2 z4#qU6D|IU9)y{!3MKVm#&Sd{BL#CeJpCA%w4ChFR+iwxy@)tg@_kOqGt%${!a~Ql< z=5$6@nfJk@#aSrZjpR!`i*wP~ot~HC2esS0W-VgDe$f@N@`S8u@1ak^&F%O;vbAl0 zp+>d986S()-YH|VG}X%e%3a5|&dmX|*Z7I*FlMRx1c`QNQx+(i4A-505RqeBDY_$9 zyY0&*9sj(#9^HGf!$V!g4vV^qfA5uupKpZA+j5GwN+>=+#^f&!b$#qH9%AvY@EPoR zk$25<)t=DKYp%~$bs7$(oW+<(a3rPvvh$VJnoqlpB3Yl(Yjf$x0XxQN|4fVg2M6p) zvR`t-;N|y{&G)HE)6yK}|BR||;rZUJ143J$wo8*&M>B+Qji^;x03c*#Gg+U3)wFA7 zrd_{8p22kWWAQ(RU~H-FbCA4Fy0c^lVe$XjrP*|WE=8Nc{O3i3i!?a=sS!#;%2G0{ zqTi=d2K&1~DBk|Nl1U2|=4diyLi0^DJZ>PajHzqQKQq7#++<^H_xNF`HEqz0wuiE} zEgc>Hu+Xc3qBZ4XtpO)!S9h^gFRcn^E*iJ>Uur&(prQPk$y zYL1PS%50Xd4DdJ8?;}$&uutuR95|(%v`KLQW-Gzo>Z~d41JNK9%o@O!QSNGwMQ0sA zOS_Z7p~h9l22qmz*2)0EW}1<9MawyO??Yz458>oM>kMLl$9T8@=0K_HWr;vXL@=$! zK2(nuoIXweLcqB*3zBPt?PKCNEsvN6>9zknYBVVystmAj_^ow4?x01R-Bv`$MKJ7( zia=HnX9TXLD^@*hipDqUm8Fb6a9jl&M8|gpYuE9;gTa~Tnb-iG*PKO&x3-9$!%l*b z=}={dgpdYe(^ko`+bex%1B}|{J_vq6n$kW^+h?tbm?|}f_eZEr|EAYU4L5W7+hrrw z!Bsu13dZI%5Mqn6Vx{}EJ;5-1+I&+k!w_~#`n%qH4vKYK)S-Op(A92qqh5s}F48U289Gm<)l&$hbxvjFGPzpcRog7hF&_pyNtv#OCGozlq3apy_gys6{#<70SsK_W7JMI+Y3 zrJoD_@(%hX*;x)p4z=2f$_{!>Ie$0~FWGiHw40_&9gHi0`+vY#9LN#fL9T2gK>M^C z8V}E*E|Jb|^Sj&k=Hwcf4ay^LjaBatz05FeY3I1fc2FC&)P0E=2U97Z9;(EN-4A9A}`T>kA9TX8h-? zcZLC`9n3FDN0AEc2tmmNpjxR=kQlTQO>6yE4RY@{3q$i_$-Wlj_hpClKOI532FAVSozl{vNnY z=Dj`AlGc}n()X&(p&^9p>*;0Gu{CN%iVtBdj@KGBM`oGZzj8%PMna0h?jJ{_ zfl^a8Q}#N7mzhF;SV~5`U6NGfTk#xKu&jPmU&@6*?62ElHjkWEbl9Qu?|h_9vVZPZ z{^eZeZX+O&`)*I5mRFn@j3inPs0x_p)N~^3YRt!29IrWg@c|c4mI>aMCp!$0_&_lp zfWND!>*jQL1+xT)(>V|?SEy|keTC=S_wVUoeQ$;rp{A(QoQA(sJ6djyQyV_~GcU)v z#}dS}OHeK`;&Ab8%&5nRk-c&88FUim)SQ~%+46fiCJwOr<>lm z^08#w{xkjd zyAIJP?n1T_nRWKVs?vTdm;|O~j=<0HR>2-!YoHPU*s^$9sGapTq)Aoc?M1hyGo`#N z&J5Qh?v2hgEt=ft_<0t|J*2*&H&F{4m3SMM;?_WwLg+WQ28HC6*Vr z`0{9HJCQu>^k`mn=*%=xm@~lr?}~nl|LHo@9)5Tqq+}kDRK_f>52zz)KQ`Npu>+)T z5eQk&SBTD7PDg(9e#OZPWDqHgw|oj33$TBlo<>RdRwRm#Gb=CN&MgdLSuH500&Ko3wYI#1{1y-mrwQY;DfY zJnstxw(~_z;X2YMqlhxRJlo^6eKft-fBl#-NA|aM4nZg1k?V-kfQJVeIX(7cNQn?P zegaqPY}@sRu=GN(Sz~!CZi4rMG`inVK(IwdL4`3Y6!gQz4P*%r7ZdisfGLlVMkhnk zBf#M_mHijdhz&pvKv?||94BOgltQKOuiJ9r!rohARapLNrk4dI$HJd5pRx)@ld9Jt zSa1kD$wgK}bQ&?+&||t=WZz9LQ_rY*Qi7TN2{KI6ZX7C~i)Q4I0+WfJPe4guIup-$oM4%uK_Q5HPWd;rT9Mnn-WJV${W zKy47JxQh$u=gZN~p<^!Dv(nXtnt~J9RpCF zDMpw@fHb$YrB!Z6Du^$A{LYN+oMY{3_L~nY!m^By?PVH2s5Jxht9E!dWf&~u;64{G z#w~SA%y=Ak?Htxumbn+ zxa3Jl=M!ww5rIFP4^^1X*pL=Yvl6`O>EbZUS~pI+z7zENX_FXMwijNhZ7(3b+?9GZ zPLvk+vG9l1QZ=FY18_6sZfJSo1L{TCcFnFp6QMq>`?BsUH!il@(2#sx(q=A;*aNSz}2j zOb8mp8Ox#StTL>%R}bfmv%X!Ij^PRBxLmRC+w_YL(Pl;`!#F%!GLn*0%X*eI$G_l|G zbi`cm(RAqvSSh+8)HY!UBaLDz0_i5j@c>m)_{+3tVAoNEi1-jpJVo9}it82O@ZY_L6B?a&(=tiuumzqmB zZfcceqyC1BsI+Tx4Dqx;Kx;`SF;_r?6az9$tSrIL7nez6Zs@I3ad6AX zoz{!0VGvp5)uL)Gj^$U#g4fsV3S=D&4$4KA8pI3RTlvH*|kjPBg-Rja*{7L-jJbYY)~ej$OHNbHzjrQ`tzG)tS$fr#pV zVcw|y<1Rl?d?gInWq1R(4iywtrU+^o;=*jz6}Yx)SmVgRd>m+7)lVQwy<_l}<}YER zyOmgUd`;9=E>yPCVCA!G-HHr5l)Ti5OWdziCWY++Wa^cq60Cwc+=^njD0yiFQC@`_ zHux!Eh;dM*QymZ(k)(QAcI%q3XpiSo0~I06lsYS54eo`DAsH7f!=s3=VVMXULov`R z4eD3phrf=R;@K94X>x^09TZIBou_M;xDIqJN<&ByX*8S+Vr7+9ih?mpqUIZ77`PcI z3rcFnj}DfuqV<|MwInjph+CpLy}Tsiyj(LZn&d^bL0+Mn?xYLqDJ+z6`l?sahECWK zDI2N{$`vVZKxS|_ox*n+5Gcb4plRtCg+$*jQjWA8;z6X50bMc_WOfM)EJPuoCkd<~ ztnTUybRDWgl$9vnviyJ$uot}uCb?V&gQ0$cbb5`(o?SdSV`8s$n_U)mG(_`g(9j>f z&@s>4I)JJWv13nBFU|>W*4QRNi_~=GF$yZhJ~{7P3go(vZvJMP1<5SQm1` zE_kTMq7JPieF!pH4Na(fxjj>RrJsNR?$VhL+*+hH2reM52~lMjFGYryS|RnFDRq62 zW3^^X;Q*`Y=;p^8Cg@2o;9!c46TYM>*soRBp>4=u-k3r+-c(J4(uP7l1LH$3d&ZxqbPnCrCb%45FaJQ4SKW%=93HnPe#_$gl(I>0?&>egV3cbj{$otpcX;I zURx3u?5CMBlwNtw-rMUiPgIJhfj+9ZT=y??PMiuZ2OGB@U>H8@HN%2wJ~mSl8B^Mux1@B2@}r}=cI7k6EzaWTcbg-^_2k) zOfMc2w{`#@#iCNnr?Z19q|8qoW~1MFYJJsI6mfA?(ZX;%7B~f(qF(9ALl9?IQw}zH z)lP{}DW(9|c?Ht4e%`ucTuntBHl@a3n4#>@Pic*8?RY#`0sbZ0+Ivi?Gu^qN-C-N7 z540Vt-Ml+V7mZizZk+eRGx-|0j8u?Fw?z{+GzNQmgkm|>WNIifRz;Fk3Z(4@Uq(lh zg$<&dje1RZIH^3Sp=RX@WeqieW(=#{1Qfi(h^S5#DPkfO3P>=gQ^ipcwkWZgPV>@c zoJn8vPQCM0$!ewLLHTNX3O=hWq;xvj7P0`r+t3rpCCZH?x$VnfmHcjYf*W@#Zcv}W zS>Xa8B33;l1sovG#-AVAMW8tKY(N&djw(V$FOl%* zQj0G>1=V2no)q9v+@&QC_^)EcL>K(@k!9?jIUM*&xEj<6)mlKF-_M3%lf;J=<<;w7N|SMid-#H>lV&-b>_&Vihd~h@39X zYU(~TwWoNgGlhs4zKsD3R+%>)=0zRqHPobf0R?VmFC6VbczV;&JYIQLurTdsM}w>l zM^juD70l&rF!QYusWivP`CN-(BrJ6E7b9kaLQL`!`jU9|^X7~tNlavulMYGxg(y=x z>7rb46-z-29KJksF}0MYi!9s9Gcvi_$;{@$qIIloQbP!jl3I)2iPXjox zzO?CZAl^?vP6}I}CJm1zMcNG1T6oedP+=EvhzP1(Ys%3FGgzDs08!dhjYaWXB-TXD zY_cqO?dCLW+wc__w(`dDTeU48g;ESy2xF3pY7OBsv0*HMVOuCbsQ;!-WVwOdbc32{awJu{M$$(*5(uF;OgI%XrMn*Lee2!IgFI_`Mu*-*4J?a)=dI*`+2Fem;=mTUAlg&x{1W@PH@njgk8BV5n zV#-7*K>(i8-I7H@uxisk6v$dA#Yk5jfxV;)KqurZTiu*rBVo0+CwKZO!gj+^(JC+A zN-hWnm@EdYqgh-EPwEeClez72cG97#2+9@p6oDC1g(@%2@ z5x5q_NSNlMdDXsa4v%7_%Yp2QE|u&^eGJRyc>mYaMJ#Yl*Mx<$(i;+1bgs6`fRJPx zv4U3(x_+(D)DT{YQAUSRwgKZ+e!&0yPP>NyYsQU=_?)L{wtK%p(YDzuaO&uVuPjHgiD|-0hGzXd!REfwB{+~m_(Rw_eh}d8vMr)ll$Yu(?e`pEVEIoV7F{TgL;Fs zhElVx3cRwBvM$1eG;J#;o$r?G7vf~vKsKa}{DLy&hM0K5b$=+ap|eq*O+!=Gs-d$1 zUwbG}k?^_H2DOWg_Y_&C&`+TU2A9rn=h&EzDgb|;jDj%DaOt*R0-F-Lg=AD~$$Tyu z#n!V8WusLlb43D^&K})3L^8=J3rT=N*_Z-|Rag}h6m2U0CC5>W*DquNG}d&D@`19T zAceAI)`n^&&M@vg0T=x^u4S97O}-mIJ29^53RZdbQrjFr07X0pi6L2Hia_P!3PR*v z79ii5LOylFu}B$`-*++kaVPUOR@u_covaHf6T)hw?TMS>Mm?9d0dqGxHlgBC^;21Z zfUCOU-cj-8SpZ_?jU-NV9kF_wwuuQ};XU>_+QMzxCLgPiT}gOS(HpOVxN|&W^+7d- zF3bggg6~lq$ewdPgiqJ#5iJ>E2;E+U9}EmSW!atpb)RbkfOYvv6v_9zyd{9b`-ZF_ ziquoIMVCqrH=tLtGA$frKuOLs>C9#n+(@%xztO@$y>R1DP3)pyglR)gTQ@dI?_u~* z(Jx6&CC*NoZghE=c4*W;QA|f#N~&$Cih(T#dAS z>v^E;M^35bIe?A`^Hxc35)KqawVIc2H>l>K+wb z244JX4lK|$`sEJx$)bu90taCZMU`IP8;dI0L?UH_jgCbth8n1MgJeg!r92Ej(1_;h zaX$PY(?Hjb?!9DO&oJ>9MjtS=8?pksNaAX!f%t;p*-Y3tt0FA%c5~)1$owvbRRj-Y z-)S^eLqypvFb=D6(e7_p)1(t!%Jl+I%tg3+#%ISd@1H4Oc3$(+e`;$(wY9` zOa}w&8{ilTi`r3RjocUx2~`rPlv(KtB{wGPyr05JS0IQwHWn-x=lD`3Yqpu_2u*vc zs!%m1#X{x8cX#XuI`UL)8^8ipL5h_8ky{@oa4JgU%@Q51CUAg5dKak z0w)Xfn&iI*jtLRzwN^U~`9Q~w{Y-~WyL%iXrqY~jWbKDK@?8PA4I4p>gdKr8&frwN z7f!;PGKCYG+l2Pf3hu^m@+EWy7|{2!OQle8y;=v>z|7;1A=_LO{d zLB!BLns)0M3E3cGG-23fVtH}`wE3!OL;5jpbs+uW?ZttfSO!rN6Z6*x8JG zI0$6iJd@QQ7ICCUNp+{jHDNQ))a1_E1x~#r1;))ObvahtoD%RueWutg>ZSq>CydsP zHp1?*sJjsQ=9DztON_3`ipF_HEGBjk3n8${2de>Z*!_tbva=>R?TalK-ZKqVA zD`Zk*F};qxNN_|IzP7xKs~ zzIJJa#9;&Vk*dO~)dJti4hzCVx!pp%iR49-9Sunn8AT^b6bd&oNrAMcY_eyr6Mk z<;HaV!nR7BnO)v@R;`0#j0;BV`d;RW=q%Te2gn!K+%9|#prdc(D`O!9)Wd$!2UKg@ z12*$()(lE0Dj{jkjXFtb@F!rUynw7}A8bgDF1^EXA*{PllxrT}2CI3Ojca&rk_(Qd z$r_AuO>yj3Ri^a|$8G}}fwH4tCj&!>VXItgCm7;5tWAx9O7x-x8l>EY#i`D&ur@U> zg|rIt+E-AxHOeFkX=tnKT>Y&GR{Q?VSbB&y*-{+lKDRB3xG+jX(%06va3(!Nt)$s7 zE0T3|?6MnES-dyG`rT zi2^uN9DW^#(g~*WWTQzRuCC)a=I1r;*YCZs@5jqH(ozV%Zm0^b#+doj=%Kti%r1g; zaeE2~K5}eTP_YGD^|}G?#D}GHRM50Y4wdSBR=ohyP2@GP>yY;&gzC55l$a@8b`xgy zLV6!*HQObL#67mlZt74HbhXQFNaSZ{+vo|{g_O}Ik2Sf{SVGuK&8OZoQnWtYGos_} zDt4$k*o23oEZU>7gC!9aZW&4QYuh3c}#40 zqIX(oUY&V74q*1dh2{jgySjO_V8p)UGQ111R^`SkN9%qoc62K7r~X-h&J0k4`p}1H zX*x_GPo=k>Z!vW1q_HTFK`efma+7)6tYXh~05-BLG&nKc>K-191SFW-6J~oJ0K#Nx zb;}DGr+8IXXdShvKuI*Mszeb_E{V;H;CaCd>j#$-=PY~yW<;gQBA|fwmT|Nb?Ah}c`(akvk$eLr&Trtn=}L94o_e> zcEbMFjkh}Hjo}IwIkuviV%e%EzlQhD9jdq`ho(w0!WcTLdlz@8X4%DxCirnXXA|3V zJ^Kta_A9PjwJ0%Qy%1MQA-I6NR7b+l3hPn`<}tF&q$rS7M)BDY4g`|6A_8L8J55$< zKh_b%P%Ufmr_j-F))W2#8h(RnRINipC4d3AG$8fROZ&@!&~9}w-}>eU3VKyM44(7zEf85>$aB{-sZWrZTJdy>mWgv%xo966(Ce?k3#?I zo;EVey=}uI%JH5ycPe4la7$a-W)TH$6f4@SFl1RSSR-`&gB&U&Ut)I-iujw7EdHa- z>UO;vXDrQ@Lpgd#E>4hI@3N;KK&!MRRWng)fc`O!CmGcT<7mCe-BZ5VA$;hj9Mf%C-w*S9L_MK2@UZXk;-U{v}7#E+AsWnvFSB&(|}TFL@D%c#J! zyn|FLdAjtPC0ciOJyC(K#jG#>DIi}I1W0h(r59v{jnV>iE(E$zx_Q`_N)D!iY&~qJ zC8-cb=MbwNbfqBDp6wjcg27GhFghDy*v@P+xngY{t8Y~)LtoH-J>Ji|OCpp}fE*`B z2~EfqNUJyslA%r+AF-B$;XaHt_baAlQQ6sqw=oKmS9jDd*2Jh9Fi?_m78_%M5N}NA zlpV$jaBr2(hc$Hj6|x8k`6_WC;+VExy1?q1s0k7~qWK+&zy-s1+UtPJ(2*WEVO3A5*vZA)%Y=911eUnbIBWC8s}k8fOBkxh)lU@Cpvirx%KHKh^+P8l~W>Ri)0l3 zA-}&QH?V1b;8)p=g9E*cEMfXA(J7`;huwI2C9zkxfZM)~7#gGq)55}p znh7gNAC=DD(j5f|_DhsXa{cNO)nh$(-ROWDGbLDaq+wehCe5RkV>23=%!{tdL#xB8 zU6er&W%pTljDb!&_pX&|=v^$m z4SQkA>5v&c>|W-6PXv+q4qovsyVQ(ecGv6>2s>J6_3G+OHLk4&2LpQ)Lj&{dM)*q_ zA^3`6wVuTWFkQPVr(JDaSAuM6`4MeppJ}>iPs-rNa{p;ym^-l-{6ZtOdyK`enl_Y2 zMRD=v{NkN5$U$m`4Oh6QIJY!PSXv+|S%vzbWYG`SdRwmf;szLPb*D0<+`E%` zzvSHC>TuuCl?}6qSbKhL_Qv_OH)3f}WbJy!?V!12CM!4{&Mpp%^wj#^b_M#8tl)FF zpZT1_L5#4?;*257Q3fX;v7|bpj~KF3D=}O)aXjfJqP^S1TOe)34s)fVV_!m+3%@=B zM~PKeHKXX+rv;H6pBcYn1@_r!?1=Wu{L~bUW!(-+2$_gwVV!Xdnsp{y>pG@&Hri6m z)H0dri}=~B7?rcZJUiD}9YZPL(N(J4JhQDdkCGU}XLlM_tLUijO`Aj4X}7v%j|5lu zr(99BCgF*zEJ!2mn!p0oYb=T+P3`6I^IomHiEGz`M-_r+cY(<&kg3C?0!K7b>V44K zs;%wq+6bT4F^Y^C$AgBTxhs~J!k24v$mP6M9qISj1YkTyEvwli(l_vvr{H)&U{=LA zk_>jNVrL93ngl@fbPdzJsDub*P#9=hj9m(pl6v! zMy3f|xy*vG6Q=Ex`bAv#M5fgHIaXy%=E?z1NaCu5e_sJMV&Gi74!eV^7LQE7P^@Q4 zM|6>-5~WAm47=1!PbZJ%wmmORZI$X4t%odF;=lvHj-j&}lWJ<4InqKGs)|EJVUrTF zTGul<9PPx&;70VNELKUfD|%88AwhgSyC@L?3|DU+WV!G}u4*T+zJrVOH{5-uhtgH59pCP=9!S{O(!{$M$ZJB3eA?kVTS%o3f3=~SiSFS+e8rWBKVh7- z{=B_sagCwPoy5%~4ZqJac57IkDC$jjrvw?RWwHFnV#?*gq*Tgo8N5`fFHj`#>>&cb z`e4Q>g|A^5`Rlv5hnSFwtJ0x=DwLZKm0W;6wAG9K?}o(;x)Q50M*pNp{J-A*;{tP> z3X*^P3eqbe9_@Qy|1s4@QJraE0D#BpDwXuM6;Pr%&o;^HF07sF&VDa2mknXD|~o}%3t(| zNty3L>9>b0^QD8uD$ddSpuDms(PZ{X7n0VwtyNQ7fQM?tSm+J?la{TdftR}i{!%Pv zvl9JO{3%_dA7~}DZls=$`35Han+;8@dy;WA-8HL462vm7+@JrrH0C{p&~F^cS)jUt&aN*b@G$oBSKQ`CXc4!RLU>m12jI;$x=vV`2Hm8p+V zo!7;&G>;6;)@M8-s^n&o_7LYY9wbw<xcux6rLf8%smj?L%}-HyNEB-amtHpk*QiGP=ua7&|%R-0FlF;-&eCr7@TboUJr& zuqpkTHbv3bj9WNQ$G5tc$$Kc2;u_kvNhp$RE|j_Z$);=V1<}$t3dU9`MbC&}lu)Ji ztF@@+*2BP|ECWb3-_Ra}-DCJm%Pg>XS}Uec8Q_LRKq7m&VYoE_qv6=ICMn23HZ^QW zea*j4C1N$b2hDc&atsl5+Dq!=oJf04I2g>9KW8M}n(6HCK2If;fE1N1%FvAr%AeAQ zrK+1~SJRI+r!Wo4zCSt??9&aQip*&mkX(>8V?IVtV%7T_7f8~w44ZLL1jMi4ChH+m zbcXj}D#6Jd-fh#(I1Ep|pxf2%2^Ur|ox z5N<<|2@oTbY)xUIHtsvUMRu(XbbjHWVfnQyjA+}Lywa(Lv0#-DO5Ora0nhRJ2ulv} z%2Y7#ChngXAWmNiyw0;k<~1{6W7(=C%wM$qaDAeOU|T zv206S3r zI+&&L{5JmRp_bpc&s0-00GO6(JD>uY8B5HMZ0*F&0e35qk zY}=+TYzdS9{u<*evs2R1_Zn!!!8Axc!1!zYSrV-&3<@$;bu&axGLtuW8N{66+K=mi z<1eC;z3>^$3IY5^gNle)z7m4Ia6R`<@__J!;{0)Qywv`pjRl5z-Z`lX4hw;Q6d2(Oi-6Z%)r%CVFc z11U;_l*%nNLW4-RJl5*%21+BuHm@V(m#Rds9+e`L%+76>$Vdtp+XLVuP8FVBN$=5L zwqLOZ_vcB~qRPuIJWR|?|q(9IVG2rBHS$@O)8GdpH+_I z{wZP&DY@P*pp>3i=)B_SQQ_@NZ2MqE0k=B>mHdJi!4apok=;lpi6I&tCBW=!Vs_fS zAaa}(*Jw~A*ZhxnyoI|5br+d-?L5OLSZV5HUbB7Pn`b-3E(OM~3hdPV1vGDSp{Dwe zi%UE6;0`y}2c~sYx-*H!U(xw0>w=HD(a%Vx%04ujeCnB%_@NIt?V^+i7jc4Tc^Gb-?{49MT5vYf9xf4M1eKz!HEm zz(tz^;&9-D7F$ml!BTQqdoy}uOu(@3?Aahq;nIKo2k{6f=ZgeDu=atYa$z97v zI5M+cM*q{Uf+Et483Gaz`tY!LnO1Gmj&12BJpIEFTow!1 zI6()wcoCi39{Rw}aM~78+iL{s8JWL9W^gO`4<|E-i+tn8&V!?za&B2ql7ZQvJFN^9 z^z2@7aBUq&)wjY_<>j+P?vf@^X4fwlD%B0SO&rv7n~0n<;u>3JC&2!ZS!eR&G>TajJOwbr{e=HKl$&O+qj)w;ZfbLpA< z(P8AKjaRXfLE8k8quuU((?L^l-fnO*s9*CWMi-A9|Esbi+RJuLWCYkX2Z9u98$c!V zf|o%ySu2ERu|H$RX?jUp$p402t=PvqtL z<+5bjyT=o&0|UQC=MH}&%&zG?yjn8<=_=}Mv zKtsdEnnW@g2YzFpsup@MZCcZIY`FiSUrkj$R_gb>$iW5-Q3;dAUo1P}Zfl!<_u4lt z`Ltcr!@zhXw3b%Er~P%77jJ+zQu&WOmR9-v;l5}%=)9!3&vh>}S+Ge=du}T)uZSf3 z$1YFyz_5Y)tIX{DW%P#sW8{wo5gOusmBcbfdJRC4NUmDulo?SZmBC7!5=)Y$)TQkV z8NG8MGebhR$YdV_?Bq_(4+g!<7$C>RO?{ek)y+cO#PzDwEQ+@AW+y_mQ-`^0miK;W zsH!-e%$G1O25)H3r$4qidYAmkn#p(rBqP#*R1#mpE>ky(hv+&Go= z7oqJo*%b*T_C+0;>tuzb@S-`_r0qW$uGU53ykQgGgDn_2~f4{KTFtX3(l`uo9+LHNB#gM8xnc z;K-SW@?r+`6pf(2ilv~)T{se*XI!8>u;l28mfE96;b7Lc2AIFaP@LujLxWvOHI<<(s<97|DBj&PU zKg5@#l@sNDX*wS@1ipDIb}mFL}anCtV3Qt{{GMT*H}|IWXi$ix)_2*FZrXwu3j zW6Z(%_5(Rmf3IRE&f^AWCqfCIiBta4C=I=>SRKuPT<<-hXC|2Ip)sBWXEsDY z%ld0r`b7fl8fqs>c?leLIwQ2qP?P2-c70FjnO8-lCwn1SOo2MEj_5@`A27Cag(gaa zAAjYl?MaQ!ZF7|0*|ftD0gd+BuJ@|;Ag!R=SeAiOV_$r~=6oNV(rZfXQQ_2j^dnM< z3D6U|m)LFdBKbv8cdo)r>xtL}&y*5G3q(&qsfxYQ5G00hF@`x-iLkaf!c#({SB*BX z+h>;$n~4o*(jw)6ODqZ8z><+Fg!{l%M&}vYAnGfM4=(A7J&ib^wXe#GaV_$0DrY8j zv=F3>N)9Y-Y>Zgltw&yn`{%WcvxY&(_`px*$#y;veU~#j&^lWEBC5ep)n&JLxN2?) zWqIxGfsth|_%HbnpCpNsz!bbVaKmU~9nT-u4^e_9wM7~17NukpwStb6BKdDF5-VQs zkT>-x;WaG%AlG%HBZH3Vp-Qiv#-|ZgM^PF2OJnx@H6Nrvxm(#@;8cuG!FO3b1~XG&~fkUZS6HVOK%J z(;mapFk!5vJmSsr!}GAzUOjxLy9~#V^$U2`5Pp9rZwqEPm8&kVVJJ^#^A5wijVmT| zbiRb4@-6QsI_($Q%OAGSeF-=j%;9bk`ZF5Z4m>!}8Fmn?7yq@@Mk~?C1mIjkwG-P0 zwnimR%wnA+wF7P5BNsy60^5H_JHvN~%1hlL&74s`^^Q7I2Z_Vq>MX%XSQij(g*2Mg!PA=%KjQb_NYwXNfm|f z3>&uw?UpvYh?U!G%mbMR(X_V+(x>b~W#)xe2KF~7jS8Xm%}VCsQ8|fa&N!i$flT}q zqbI!E8#|dRl?P?&`OQdWDfoxuvekw!B9iRdO(N|VMnTh7;^W5^FIP5hC};=qmmTpZ zb+9I1T|ZqtD#uJ(WHNMy^Bz`sjp$gHYev^>L?ELm$Uxt=73AfG7_`l8Hs!Rpi_%ti zAO-RTn+0hP8a41U5F`b-qW)=ya$y66-0wL#&?$-nYh+~}A@g8ny0|<~C3lisQ%S10 z^!MpK=(HdnZa+$ra0LUa;6HI=xi^6LU7N*N`u& z9|d(q-_JV>8gS~IKI;MFY8irw{+Q%-1uQ$-l^OcoG-u3PllL0#Jx3j#q8rPBgZB%`}H`6IkJ$GC8`f%q8mv&5gDdP2WL+%6h!tXmLQU?mD>;oON}E}pWG%VH3ol}kk@ zmrjdPSFK&2mTqofQB8yCD3#o3EwKybyb_Lz@S&QP7Z=L;SF0x=Q_1CTq>B49>{u}W z)Uw($vZ6?GcO#0Cpni$rM3BW1GeNpwrrB+(7PIrnIwD4L{j$NH5yEJp+Yy? zU}Jf&1(TLE1(F_PQl28L&_?W^)uEe{Ac<4L}4+x|w<79yD??I@7(3GZdB;90^z+zogH!qo3V zS(8o|Htd)v#n)Q$tULKIZFM$Lrpxsuk+MJ8>&R#*+ofxFl*QNDtJ;FJJ1Fu1X%sr{ zBEF8CP@F+I3eh+jSXje1puYhLH?|%i5--1BjLJiR^Y##BAxZ|cKZH&}4WH_-4y+@I z@bi`S@IN%vcj-xm)WK~6P9;7{INW7Opzj(Vl?T99z?CBn!llD;dy)c2o zzx)g&dP~yu;rsvj_dkk!YKCRnT*E_uK8VC3iT0gNW68p=l# z;D$W^$ac4%ay=L$48w1)%2Gp6lrnKFf~Ac_4T7|tB2C}mTe=npTO!pbxq zR3q-=2pS;&0b!%oMzMxrsy9l+bRl?hl7iYhh6`b))J89I;EL)DNl;-5@UapSGkj5+oQx_uSkEBkHbN!0B-~#-Rj?`HI`O>?wHYgQH4{* zMQbm3ueXka%70TOwmX!mLDJi!X&nlOb+(=V_QVn&e$Zo|EX%MYMk_lmL(+f<8sMhR zSxHi=gt-j}QWVZWgJ$cTByL{O-jly{?9of!SOkEumX4xTe1;0D?BgLd&NqJk_%rxD zRITWsrUpfxk7p#}H6?I&)xwc9W;^~MGLe-4v3g&j01MWM6*j>S51J-JD5iiMf7daeWc0(}=M;ZT(f620l5w)EkF(3p?C}5St zxsHz!gLpTSD zrYb^m$Ox!)kbow6GyoQNL17a$`IMez;&rfm?28gLAT2&+@eHWZHb>{9gPOkjrb^Pl zV(ZXCPbfsuV+DH9cTzM@T}-5C=;p;_ry*NiC<$vcznA>enL2}B#@a{fx*ylhrOU7J z{04DiKWT>|G2NcuR~ zPC;4}N0s7yX{AuZ9sk+8L{jFKR;dK^AtR_qH@El-dNDRY;Dz%)EXtt1?`Tc|w4?cZ z#|@L}$bGZ zkEKWeW})njkvaZWF}|Za;gorMCu_T5g!W>=qauKy;b45T3}RgIe#3x3O$?eT0w&mr z_5O`QsX5N|i+Hd*NFSp+vE&tNMl^~Hm_k@-!BNLqbClAQ$or7e^Z^noGw!y!So_T@t;F!O~$bA)nMJL^n zGq~thNy-2p!Rl@}uLEDCC`N-$5nj&7qu@6!Bd{13*49xXm?t7b#XuQ=7`QYAgvB_W zM1*!6t1$T&f%J! zF{Z|gZF(-LObgD=omdmJPH=}reRIf>q%k$VNbo9;kSkY*RuQG|*hAaKMHPSsT zSUgM5E-f+AL$*yVsthbq2cyr@(j_mUY*HXUo~S_SoXb16GxGLV^Lv3fJZLseX^ah5 zjz%77wowbuiA4!~6!wZW*g9+|S$+HoB99ot$20OHitz9%>UO2Gzb#S5OEWe^tUmr2 zdCRg>sG?bwqL)D9DVbOjF-tG%8I=qbJw!yCg!arAk_1V@9}L(m?m^aKl> zS2eXj+z1>xAsd8Pmli`UE*li`a=Uy>=N9x#r(E7EK~FgoVfpW{hkWEs-QraSouJNS zlOlqVL1;FLbvzPL7EptPkw+ZrF|TGf-CLkp)lGmn$X!eyyDI=uE&p7nSV!|q+g4AC z#j~N~)cTntVMnScx~0`=8yQmO94PBn6oliN4N~5WJ~FuAm(7xrBx{00027(8u+hhc z5#_tVbm7bp9y8cRk&&IAp5tQ#f{|a!sFbqEza(j*T(`sbQ<|7&8fhx&aQ3`0^+-NR z%ien9@rgAi%`=kZ&!Ak&d2x3c!;g@Zg*`xX2YVsjt(A9u4~wkfYix}d379(JQdwY` zR!$n^KfBb4pjOP{>Lu!Fj9l}+)We(%I!{O^VGFtYrC7L3*scYC8+c%)W2@po1*ujF z6bv1sJ2Fgbp*vv^fBzGYm8>R1y%3@YP!I%a*waLooQT`QO4cn=!(nXTo%o%@NlM%| z`>QtK(7B^`ShN&qBRvUAy42}v@LiqS52))xIDXxbGNvqtIGJ8Wx@T39Qg*pi+qi(k zr<-Xzq&TIorud}F#5IhM1kJIjSC&YIsGmW-{nX?Qtv)|~Fs5WPnT}Crme;EB(=tdV z7ffRM56wH=egV|jLnOF34qy%dMCv(9o0R!JZOilzg9X&t850&Vm)AmHbQ=cCkx`Mi zky%5chI1t#MgM3je%C}2Do6QR{Rt3icjsis#Sxs;u>VAmdul9^qp_6brJD656ROvu zQH7eTbcJ-sr?$RTUJV54ZX)nOZZLjzQ74wfa6FIVHv+O7?;nM4qQ@#wRHT>#0&Xd4 zQi$<>Ja$G<{9(zlWAIqh7zm}yW~H^sbNKsfSbncc}zQ!`6}8W+rGX`yDH2LRa)R6z>{Fn~1F z)~+vPs;hnI`f{n#MPUA8_J?RfVItiwv=PuiW!wP*Mg&MA8clSWlJrtx&|fU%*XI{S zK=l~dYf)(J2!KghLIBY?c9aGjG7hR1c&&_b$}d0pw5cZG?Zhd5&dIWN4^UaeawVBny%&>IEPfz>V9_gG1OuOVRW151 z&rrV+@jR+T@`dZmwAt66z^~DsCUOi!6+dan#;eL;1m#(J0#ntOHJ0*UXBd? z`cfNSYA84nDn*7_!zk>dCm2c8hLu7W-B3IaZx6>63D43c1WP~%Hf3O#ANL!$u8T6H z4B&(-2#wf^l<5-JrM4r>xZ^|Hk}CXo;6<%lc*x(U6~~|O4>ZO33vnvM9nLD!R{o4vHFn9R%?RiC+7B3K4M^wkgZNFCsYM zd2u>S!IUlq?CCSq5T#o%91ftMAR?w<fDqi5kwV0Fjk&qc^p8ry?T4ugRGzVo0Xt33p1pmz>dMWh!tiLZYh&fv*;!F>isd z#aNfTDdoAk5gStzD@4RECclTZV4V9FPcxG~9cdI-;iA z@Bu^0iy3aDXwrAr?b5$MlwCG;TNvj_PoMlEbxWp?GpCu9rc75fl7PZnC64PbPAi{zYGvmA9fOtUm#g?V4jV864a6b;6&UXK(nvog%Qht+eZWX>w-AK9D zAQMq*0BM}JPG$nw0LZ#~mV-eLPz|C*JYH8buJanw z93NxeX=n(B-MTAHV-jTF3Zr1zMeTl*uv<6C(`CfV3w?w?rnx>1+}Nl9K@D=tdw%Ly+MsleP7zr)juXwF#V| z#i9+Jm8H~Sub%V?~cdz~kg@HdMn5s`1%ss9^* zK`!eyU_hQ{X+6mnss;rn&Z-9X)kPa^EFhF7MkO^`@-XXOFsgY!8yYAgwRXQybw*SywzCC4MpIR zTRW=)>#NI3^6Lx2?64+Hl0m{U9xj_jI%HD_9#Yp3HCK~;eDn2{U?Kpb_5@M2BsCSX zJc77ts#uo8Vqt65Uy*kI$X@PppfIt`$o8cfY-Gk;Qv;`Jz2#l_jD#pLlGaD#tq*R+ zqA>$sRvAT&yven9PoGM=hO=wkG#l!xw6t+5*7R`WK!2ImY=s}ny46yk7YMg{_Nvu+ zYU6Q&p6X2EI&m&UycW0vJwtD%lxf*76`PA<-|4dHYSp3iENR=Wibk4{xXT{-a%Op` zv=P{|9K7UW$hLQ0HCFX+B9QiD?F$pDN~_W{O=Pf&Eci`U8DGFG-jQW<38vWHT4)s_qAi7E>}um8u3*Ym;QIoBTvCD&(c`}3Dd!1i{$16_FU65 z97E)YrwgCu$F^uS@+0;)11J)cs5(VVPE_Z3ATk0$b3jthI*q76FrMbqcJO+jjC=`* zO#>;3X6>x=@M*+5a!CGKBa)BVK1dsmha{184F=MhH5f@tUOx(wZ{xv{u+T8-E$J8% zYlAB-qaGp9?nW;Of16C72H-jF>P}3DbKuyE$O3*h$bbQB7dntxeJ>{r=QI{aA%!5` z<&QR7mN2UWk(#P?OE@vYNUZ^>=2ri-9WOMY0BMv<>8V2wTm(tNakCZkMW46}=BHuV6N<<{6CF7#2c0NiT)S&?M9HQgp<31!+#wAjhSm#in- zk=kRjN~IfIu9*~5Erm%ZBqf++6s?)`97R%wYl@mS8IM>sMiYseuvL{30Fo~z?~2nv z;}U;X*!A{L)d0yF!$Hy37VCtxl2+CQJ=*L?snQul^Q%5Wsi@hf%K+T;vn$m{dg?4t zmI(TKsGqf4s0#Bp*A$_;>ZWMDB=$E0_Hilh`Nw8E4o9`m-`QY zw0{p0`;wyp@{Z)-0wJQ5cPSvyXI}tM{Yyx95x#VMOR;AI4^j9I%9N(8>e4Tfvvc(} zlMUSioZ+|s48vIzwE0T@&V{M!iUD!ycja&3` z(nm$pk#q|~id6Nh0l$XK`M>|Db7~_aN`%k#=dbpzqhCB2Jpw_vTag+hQfLNC_bF)i zY5U36MVYYKW%>f0_A0lins(-%9MA<-RAb7|hYl#^TOcO4xhIa;+x6TFV_{ck9@%$I zC`C8p`NThVq_`-Ee@{_L8*D;OSMSnfDMJ^opFitF7@np}rRb#oMFtvQPvq;I(zOD* zjI5RUX-c;%D}n}2iX{2EfQLxvfHZ5NUz}Nx)TfYU8*$=k)@-$FV`e!pfWQc+9U87l4IA)fTYnQy8S32`j!{$> zJiP?LKj*o9odd4;q9dC%F<7%XmD-UP{Yd=cJ60po4+Pkr(UD>hn z6B1+VZ>&FkI?_-J__asZlVeM2mLEEa>}zO@{OPmH`olFf>rWXK<*cZx`%k*~LCs{t zM)fK+Gs&bogEZaAQ6hyrtv+n7>{kgHnKM5paru?$>D*z)oaif<}6N z89c5(6C3{rX(VLdHFzs8^$;IlMq_-?cQ)|1y%^W(xC=W>yP`*+P!buQuwvLb!XKVl ze|^t<@3vq%Tl+zJc14m-(}lr~Gzpq7X|i)T=70R-V04uLdIg!^J0$I7wwG&&!rdfi z*^P(ET%Xvp+@xxCS3=j^gq|q{r!eFZD)ppDWEJ%%iKMV`n@A();7mV2Bwx`f{1Qdz z?_IW4inrlKg%|jSX~o&k<6$x#=xM8W_&XP_Fk%(vOgEO z3>{Z|R2oiMOtdleJ!(91vc20{Z(>T~zKLMcWXgbKvNO7dYU84X?2H?$NI?~$QwmNn z_rf3qq8JoP=DR6X?aH*BQzvgH21Yt7!fogb7EWR1h1Nwnzq1uIO31rr|HwU)%J70! z%Qi$Ut2rmfGYaGbyi=j)8cI6vs+Jv%`5H@3spLTy79g<6vWzJmV?ETSX&`V36HPBN ziwV@LNJsL&vw{~d{Q?Wn#Cqi014M2MFZc2i!=w$Vs~gVAA;Dq#7C&9Otm*o@E|uEl z($Z-OntG0W9N^!mS!OaUX79a8T%@B1Jr}am&~<-$gI_njLlM>Zx`o2{VneF1J|^UE z8reqzL*$Au38a;4V=|z>CtQg1wf2=( zKNc9$xm;?|z9EKP9Sk(na^^^L%0$RlBP5q>>gI_tAcd%I&~GW2Iq2csa80D_*ky!Q=M8%mbZKEYx4> zu=+dP+|K>AI+MLce7PpGjCQl`K+>%KTE;8Ps$J8`!e!8iy}WFhW@gyM6E{-(k&5)& ziRt%F*pm(dS>v$r0U|r&yU`&gQ4U0^Y4{G2Y=dL}CL5=icZb{(R~(LOL1Z3a5xb2O zzGJ4yJaV8ipjnZF%-%e&*HFn_jn|ek@-nEVp`%fWIwb+vZxg9VLwrQ8lVG)9WVc>Kb}JRc87Wl(L;`5oK=*{)?Za51V8khp#`K8;@8sE_)} z`lup)v1IBsT%@J*n#90GHep3T)ceLaTO#Y|xauqMsCNY5xJ{We2w0#dh4|{jfDo-47MYfuyRiTyA|1D%kFou7SYhV zsd=9L!Jo`q+lt*Ojx>4IG>jHA(qZrBmd#i!k*D{a@6q}5*Ig>L6>H?LVE0!Rb?8Rk zwbpzEfz{SDtqNz*m&zRDV@4+#INh$mpK-k=K76GU;%n&_mwuvChr{+RCcU+xls#W| zH~fh`!YnMlmvfXsd$z05@x z{KV~xjyf$8Y-Xl+oqcYIh93>& zc)}T@kE~M0?37-X3xBj&^p31T9LR}>i;Joy&4qHojh?U&MsZ06{J0i zJmuPgwuKu#RAo;1c1jvSYyHXgwsZO8c9Ck(LPmUhOAEu!MK%wg8WQRffcj=!Sul$y zU+PNA_OHUi@T^adE+66`d$>0hrP{c;1P=|09jDs^>%|m;B}zP?pKp( z0?YwSw+k3TR!XyH8jC@l(_e_#_{uI29Lh8>YR8>K{6~>U{*AW5I*`K&mUH6Ku%Y~9 zR~WNia>v5YpOH?znI^BahK>X$Zz0d*X#e;$I;9NNPSVM@xPIiD8>9&P{bC*cT4L&jcJup*5+I3k93bD_{K-j0uaN?I} zuc*Hoc3(HVb73B<5a%RSc@TL!ZcgG>l9JUZA7lEoOTOlT7!AcnbGq8>$`;QomGp?> zcV?;7^cBAhv))}cwm~u}&So>MnlUn2u+0Wch=g)oxpZJ9=OxR)PE&NbK&YJ;^RCPy zBP%6A0>{Y-v5MiF8RfrOOF_fs){R-Pl4}P@FCl3*`fXCC7sfEKY7Id)`++||zLfkE z{tQ0;!B7}EY5x;SLhP z_J4SbK3j`5`$k|ZPvhZ8c6v=AlfJtW$C5}*E((rQ z62{w5LIG+KYjA%NKEW~8BYfzFty<A1X~Dxx^9~WAzRjLS$;zRO(JO&I&Y^M^lfBVISR#=QJ`5j!Y1o zYRSz{))64{wJRF0WR=jB5qT7ZxNdkcHdB+Kkrnad=is$b3D*|olrJ`VsgA2GBf*cs zhW0QRh15!Hmz{B!5gqZFI<&-F?h|9r_w zq!Jboh&1ql5Ut?ifjB45N*195hce?_Kn$HLBH1WUT3w4qx+Q^3vXC$zFToc-lVn9) z*$9PIm4;@00z8vlWAU0yW$Cptu$fEcvcI?|8DEX$httXG5L_NyRQc~5!IDnK##qor zLyUc=i0nJT2@Cb`p$d>;qvQt@ngHFHnyg|H4sG1KC7nd|pa5^z*{MV$-~&BQB|(y| z8q+c^nTCZ|@PXn2J~)`vutqASlf;hN5N0ZlcciR4rv-3(mOYUK0b$>Eea1^7S@pt7 ztKtB-C6PzYiE;iVSBK95@BlwB60c>!N!%GSV;Byw+U#WkACymC6H%)ZiObG|b+Ih? z##XuBc3N034T};tEb5zd3112zIuuWlJ)x4-*e`u$Qulzy`$$7e1UZoFqO~ z@d?~KI_tVygDeOhKXFTtSR_;#Sd`G1sa19uE*5C158A{cC9pT{V~Ca{r0h3Ef#(zF z`UR$#V_%b^>a5JFetRvmAjDL_8cK7zJKF&WpvRKn7Jw6EvGk!;ENXI?1&Whu_R^e; zehZ<88Xr|xcm2njEm1-eV|6#{E;||W>0><^*R{ymPz2VBDEH!PX|yyqTC?pCl?)C$ zNg;t?1)yG<2BeQv>Vn85FBK_mq7n*BL+mw{ljT-6OR|W)ya0ScC3uR8VN5Zxm`mF` z7V`2WIZHH7_2Kb~0Z@;v+KKBtCNR`nQIHapsJ`5O>YRXTq)lE)ksJiJm0J;ZQr6B( z9@R>>c-fv<871}sUb6FXN9Y8yhjN>RnBh~5q^aeI8C+U3J3j{`b21MfOT$MbqY|Bz zSW=`(A8%|6=-BfZGizhOgg!@R8kJMSVaAv+O}2IMV%;FHO=aQA%t3b?G$O_xW%j_e z3ucbBYV}=Yxk)B;qnwsdSXX56W?6D6I%USWBoSK34R9lZIr5QCoPemC_8ry2@QtRD zY%T8MRvcmW0b?SF+eFf&u|}B1WutcB)mbtgZZPG&lMS!ELnV(F;n9*AgEiqhK&=;N z-w53tfb^tV=fy=Y$;$YoWb{P|BXM<870%enP(R&>?7=O_NbCqdY8FaLEcb0}J@%oS zj@#U%iDWzQb9ASN{}>z8%S9R$&s;eg^2AL(bz1}00>6~6QdcHHUcXtF_tI!XzO#Ha zO9LL*MjXc$4`{&i?>|y5Od*jF*(K741XhwN`XNXF^R77Tyx4-A-mq+ELhBDcQGJ9L zC<(c>S~EN(gPTCm7B`RV;nxWQXk8%HOs9@Tu(~LbWCtA#M1n*ROYU%!5a~74seDrh zL2iqXg}kDFF?+>3G1fkfv7musu5R0-3Dim-3UO!7W|aPTH6Fg}x|L1hiT8P&|2-CHhqyZkkR=Be@2#?IDJe3KGZ# zg@>ew6LzMETLHGy1LFq3K1ksyTq|EQz;*VjM@pUhvdV-A&0g>?@*ePvtXd{DYVaT{ zLr(!YBC;sTLoZ1puZ7-_vGlK6sK$R#mPQqaZ>G2cuIAA}+Do2`^bfzBgsLTz)oG;* zvs5RdJN7_AR3F`XM0vJ7!lG-wj#jBeWRFPh9OIX6H`HaGv4H82yCqJQ1fmXV`1mQny&VumeOo3##fY-78L|wkxL?HZcT3wg^CHMIf?8w-nJnfv! z(y6E?aW2nD3L@0t18l&KZm1S$H1CvpD$NW0UU~uupv0a}bVPuznj(;~c7JeSDIHrV zK{J{Lr0tu}$eW0G#B)%aC%Gggz3Jp2o5-7}iGvM1gi^W>dAMYy+8;w~RT&N_(IJ{voC83$TUgz$`_3Q5`fG~)URdh z*KmOe-HkR(E}L2s zs*qfRKO#FfB68ARfFd=dha7<9L-nq5M-)yKu?>ZpPn_-VGohmMm7t)0)07(r76JhH z{>_|b0D5`DkMD?f)0w6#XK1M^JfRTD0V8Gf41OMoh%Dh=P4Tcj!@O_Ep~u25#nCge zo*7J0DLn07a=iroKxno)TQL_VAN161!3v#JM@;=<;U=l&0jzWoDV_-8A5e8Q0CHqF zRCbMI)f0+v6|II_g{qnuT2c8&!Rj}Qa!`k?U}fLSk$^Nmpz69x3kMhzK?GKuE>Z!= z_HD6Jt3MgG_6&==xz9>P?<$&UhFD|vWo!HjxHJNw_HD37*r#))T|+&DbaYzB#xZjC zm_@yTc#Pv06+{cH{ENwCAYCnZ4tYH%b3z)4=6=e%SY_99K$GZ+C{RO(T;y`FA5qVR z-S|)K8K&omB#;LJ_Gjeei|{q6=FPL?U*rO-7TA6Ma^odpOH&is8X$~jq8(|pR^er} zAJ6e%q6i%7BWy!XjyBXTul_`Zl*8ykpj8P+L&Am&$WSf)ZAct-`6HtwY~F|8zE_|e zzgJDb<(t{76cIPg0Hk2}n4Q7yD|Vs*50gmMP$cPQRiP4dpxE<;2RX~0nzr!V;xj06 zGp8{;BgY?_{dPs#Df&0N&l%%S(cGilpC_9zb}B012%u9;Kp*7Iok^O6>2N9EG}h7y zL=IaW!|jVX8icSZ{g6VR(Xqn}t$qv)R zR9^ia3uwmBG}idVr&(~L>ubWT0}HGX4aq1!7J_K-$pG4I<}geYn1Kl*FKEml9YsyJ zG9#<)%4PP#kWhX%}fUavwvK`d8RBF=!w1M-(gd%%_<|>h}R0pb=Y_&etFF zWoErOvHqI;_6Y(i0;Aqo-7N=V$VATSAM7Okte60*6c|HVTiqE^Ek(234E^$oI}ZT= z*d__eBRpm%$;wm7QuSx#NTa&=Bq)&SBOOnVEwLi6Bc!6+99Ip;OA8Ub0sbn7%p?iZ zhtwbZ37&0ZZ4KUz(uej8olcH2e8fB~C{;!lRn>5EmsG<=j^>xJ;P{Tr_)=jySpNue zirX~VQ=Ua)m!#Id?W&-Or(fdtubB8JAH8?uM9+DY>c9Zl^t28qW>$}|9*N#h(v zk7UR|*-c(eYQ@Hfku+D$XSqgV_yLqqVhGH_*(YB3a7IN{+A@kxYtq2=5gunSjP#@? z(VCHSB91~xd1hdh(MFA%@7aGgf)D)Rv!aB8E4jb z)n`1w9)gz~HYg#2l^uW%t0?G3=%~juAv+jZlQFG+Yw$+G-@nM%Ok)YwDGhKO<`YSzsrUxNBiR%_B10{&6m`CF(SGIg@&x2OiqD$>Cfs3o?kv*U~rao3e_dRAR9|= zffrptgJ9YBo`xjnrW(!c@A7P8&U5>P3pjm#8>4j$&#X-1LH4=)eY2+LRtMt3c70m)X_QoeaS zha?R|Vb>m~+?-4PP|qRdP6+^p(UWSRL?aF9Cf=742}#cHUAV)-ET%DNcFQU+ zj>nQDjvT;-xNF*$uSJ86Y%1=BUYbts1G}PP5tzeqH9u+rQ9U5^LbEXVvKo=kC*!nL zWP^F^P6(Vsh}Q2y7>+1Y>%q{fmt{xLvaycXodhabVJ+HWv1)R(hs35@EmG_fL9__* z%P8N{;3*iC;IOWg;yl@0rn-UVBRWW*RCc42OPL|1Aeg7oHy1~dlR0Z@yA0v_J&*Dq z7l5b!8C+s*S^*{OwaCu*-Rl3*;7puGc+?Tuz{>C*8alH}khUP};bKdzZVMUa33cT)|r z>^9MBU3YG`!8JNV=y9eDivUuO@EXM7C~_3h4gd$Pc7{$2LMNETB_~d{A0?%5@1laf z(%Xas$+!wFkY`2275S76v=;}zMoYQ#c9H7%CTO0RVl*tq1CB2eiv^OaCGn)-aI*>1 za1dyhN&_tNxsj_C7giJ;UL;ZwJuk+Im@z^_wCt6|GA4`|ReIitYko*y<4`|9%+B!= zy9VSsCTVZJ*EMb0+@%$6xRe^zk)o-SO&1e=LN`MpdD4jT^4fCiMXqSU|GhO&kW~Fd zAyn9@v-Ant8^gEVuG?1|hE2n_9t>ethiR_7VJA-A81|l-?UYpS%eK!ZA9V^kK#g!N_y8oa7IaP9=B663firC+`Jtnal5fXE2731qb!{n z$X!!MW^f$Hb>UOPB5n`vPoL_|!5ta>XF+0`$@TPdoXK6`UO1sRl4~l7=R>O=1oo-k zBx#AVsGa#Gk}Gem$yAauTBFdSh0ZMyV&0LX>to zKQYRSNB)TCV0pqg&Rb^0ammzP=tH@5@t>#+sf2N$*J}~a4fJALA9WX|pIPX2`<~EtXV^E}vIlXA-l|5NRTARB zZ|QFh6TfRjxHIva_SCdE{Q*P>Y8?lDB|6i%?}DE209Km~)4u+Ir)GT_+F?liL7>yb zV4wH(mYcJA-!5_j20CAcfnTHJxp`lzoB+#%bi|ooFY=tt{B}A5W2Tv3KMPhI5!gLA z^GgJ{EqbkhZhWmfGrzd~8>#b|U$CzJxNUxJ=$CFm{OrdV7Ki5~J!IZb#(q1$BzLQc zxo0PT8T;Jdsc_5`Oz?eY^f%Jtv%i(y?)Fd!duj^Uc5gli2gixiyIeVrnm*4Hx{~v7 zF!5xX1-9sAo@wm8Zjn2u!@%jX5C)W~w!EfP$?)>sZX9@+HtmGOM;r#WpB)IMl`h26vjm zGp5O4^U|N33?`?}Cc!+P!h3BegEv0HG#G3i-E(8XWYD>iAWxP!6-R^14CC2o@Cm1; z(O`oM?87so!5TE!b(8H}y5$^@Ryqs=S@9xR)f|R$go$#T0}{95Kx1}iEA~ub%?iZ$m=`Gy$F0VApU_A_=y1hv&R2V>|Eb$7JvR#L1 zhE1{T+-V6C92iBkBt}gWkm=MA zcj4{^xlUS)og7J9z`QnSJkAS~ z4#_&`^knXOZO=H9ni-CygryaAwl(r3y<7ONTJ#@?HFUJO(cw-@P@L#8yhw4#XFljO z#QEXn?t^~4O()5YBMcBb;7_=ghX7VD=kpDwG1C;WWf>6l1|Bjb6G=;vb>6df5;Jc#j{8ZT^3gSJP;^luvXrXlKd zBa^Q7-1tBIvCrsTa-nK~E_c>nJef4MXIP$2{8-KOPABjHKen}sBR?i_pWe$9c$zg{ zrhi0J7&oRvYH=F*-Z{L(9kTU-<1;?3Ms7Dv_Kj0FMvm=7QW(JQoSpC;StSLSW^XMj zI-fg^GPgQ~Y2G(2bGlw+lfpl0krT3--93y!FR*NN1k?2K17t7+e2vLx{8*6@N09Y4 zGaVH)ELT6x`buw}96?67x4X*w2y#=KW+86A)|Rj^_iJ=LHGT|PRD~bo(~VcTV$wW- zY-z>Cd_)okw)NNUw&6U|0izuv_HVQ_{UIqp+)W_=^=U{As&L)fPjA-z`yUsr5#}-n zt3?pZf&TCR#Q=yNz(QSic(E#&-VAo&c%LJiula8+@+v>+WsCMXUr07I-DasJ??>{zsQL=mg zCjZK1VqZTdz4xg~_pCFJx9itf5he02nNvk=ki&W;gMaA5p!1_xmuHNekmCW`wzp>D zXw;nUP;)+8H#mqsvOz%eSnk!Kc`4ZA~b&%Z{#Ns6;lAF!F0M8RrKyolE&UkYUC|j{Vf?UIVLW~9d#XR3nLzwn3UEp_4I_uCVc*%`Gy;e4_{+n=wsQOShv zs$jOcL8}TXQY3QYhkjSfk}~^?T?eh!aQXH6i|Bd+v~u1Hi>fz36PXsNxF${aAym0! zvswq#b{zjxRI>JKBbpj5xWmBq#(voz49rkz>AS+q<&&C_68WcjNx#B|%2lv%w29m# zWFqSxeq$RB9{Z?Cce8X__w0Qr{3(&@(G0@lo}9?ZB=`N?rsM5DZJgIFEv%p5{@I_; z{!+ovpAh9v%9X$J3?XzJUE@Y)$nYXkkMQoSlQ&B@gNy)_Tdva3v^jwS}$50p^oXxNa3k?t72W7Xn)T0Xck+Lbc+ z)(T-dIcW{jT?QNeM902EQ(#bpv!>ERLMIQ`Q#_u%N{lw(ZEI#o7o1v?3rd?c8u0Rh zOOd3vyiKK>ahKg`{2E?K+7YO@3*kZ5Sc~F0)9|Ry`WVOM;hg!IoiMf_`hOPABj3Ir zAdM_-Ue65F0t>3TUjX}=nF~zo{0~f1(ko}NxTAb0kd0?f4h5o5%^or}^bHDIFmm#4 zA!{+1V0#cqv;+Gy(acl1tx!Ca7=Vt+L=S*z>O18HyqRv17pPC_QF{7z3o4A?yCU== zFW?M}fjx0@eW4ya&!kQHgJP_wPuJz#5~4@TR* z;fT2;OKF78u(W;q;3|_%((x(}fZmF%7(tT<5a%qx(XIHDteP?cCFVMP&@&|JzJzPs zyo!`Z5*tX+qKIU3c|xCss*Q(Cfp{0+;_#1=2o<4$r?j` zk;t7N)A+b}H&WaM4s)!uM@5+^X~WNfY`VD%k?VO(k6EMcWO#bxTxn zI4_;8Wi+27bGrcbikT%}@F$>;cyN5TSut;(*NdoRr{}e$jLe*&QM^28(~-uw?3%pm zgw*z!gLc1&#I3*67^&BY6c#6L#{NBp@iAV>)IkN5?gXZtQ)X8;QEy|MsEP;fneim! zP7mj|_{MQvi)P^4Qf-3z-825nlRCoHGpyU*3ldnz#mpV{fO$bk7C-fsctEB9DL%-| zO{c88^68WlnSx#I|AKoZHVCJ_H-$$z=N{aJ=kP*Ps66-OFzVOnpEBc5-UO%ii{OT7 zdgCOmq+FHAML6%2q-b{ah?d1DGzrjP^TAfpPnHz}5JRA0`b;{6<%G1z=yp0Th;-_3-toj)KF#H+KgCPc28e$g3lWh1$8Sckj@;+SWKeX&&Y!PPVYNI9 z%E`@$-=A-#MVSv-NAgLEi+1?G?xh5FvelS~n50btAP~GZ9ZyEpPs=tA*Zg2`*1! zB?|r?0U39j7CMK97_KjY364R5&h(B2YDl}plnhJ{AJ4eCpwivTNmfsoc!#)jH^(x>Z@d=%IjU=JBD|m7j%*al`K3Dvb>iGI5Tfs3D z_w0+LCANc?$7mRH0`?qD2~V=`&Xl%e!SEF!k%M$5^00aZ{3T_rl1clm_XB0j=|68wx^7N%85vAZD%b1T`Tn6Z4v3Z zFkGQMW{v{6$ONPCV$cjcB_wm|toHA4btk?6du^&Eu_v+4j)Eua3q9F~~s=NU)N zMTf;53Cw|W^NSxL%q6+W=3?XmrK*85HOb#;fk*88iEAza>jeX;a1+K{L;TJ=etW_rpVI{is z5;+Aa{&0&7(uOy_CK6e;1=|&Nkyh*omvO^5pk2>FtNA)Z+r$flI8Gx$3h%0WLAk+ji9MfO60P~hQ6Vv(1e_|VxNdW=imvO0I%XM& z)6ygoy8qM0FbF$rF2?v_TTiL>R)(Xnv;ysJ^(uk*}1mm8x!7T6=R4r z>2h(ST{qY1k~%I*0*$yZX2nUnGziAQ?@?g6`xE<*9y*o(I0bwPg_g`5q-oSOrq`V0 za+%rVA>~16Z;;rNKHAT0cgAoL!?)`a>rPNd;%V#$mQNfQay|mlWiEvCpxTL>&uJBx zA2$}rmj5SflEzl9f7_J>-eMv|??w`Yd;qM|2u0zgy&K03iSNbZMilYgaYE50MHUk? zV`_^_*`1mA?j()m41SOhg*^K>_`(d3JU}ToJzg_(N)pJC22OMbOovx8QF4X2&yqxt zzZv(7K{nYhtS2HjQ3*4-MuUyKGW!HFO=1E3A0(IY)XU~fYcdOw$Q_`>i{F|TDJi(=|#HE_0>6S#?o z1L9!n3TTp6GI=EB_{odDuf!JAQl0=F(N$W#AN@B=?oa{U=IMkI{D_fi*`s8e*G&+8 zV>XuzMK%=}m7KUsEnx+c%jK|su_i$yi^F(7V3P@W{%yffUT%GL6JIQMDGiTdo8K&}ZT$%BkyS_aVtCUFC>dNnPMFmpu!&Z=Db&(EV(5uh^a zg&(2Y-~y$RRpL(|z$yJArp75m1=v+eZ%i7A@Kzo`BHmu17G|Rx7MyGJ>JvFF_<_0- z9|ESpE)Ls|U^1Fd{sJ*3e<gY2cT&eYpLUqpK@a{*~EzUI;78 zrz&O1bS$Kn4nnpP;$RSS4S0)7uPiO9=={XjI^L`~4xE$A^UTa?eEU7-wv zbp>Lu7ezydVmBCD(m`B^GnKki`pI*4{t$jij6RXIR=CAz6f%dBBpBjjvZ1O>Icmb8 zp>B)F7Z?f^;BUsFW|@72m6R=ZWKL!!!jLCM97Q&;4PU4T?dhXx$(zJ(8fdA=>^y{v3NC)@Siw~^(aNqSYa^jVUr}u31gPp; zE4anys~=l2SdBOb?R>PsfuVBTTLBlxTW?|Bd@Q;ea;SB`^7GH++43Bm zJ}=*rtS|19JxRC-wer^qJ?oPiJ1xVMLR!M09XBr<53V8Tl9>~1jTlrt9!{t#0Ae%w zR5?273){E{AjH5;GR)&bW?2q3tJBT(sr4<|uxADkP$C~ls+^Pqb>-orK#4OC;ScMN zPb&~mdi@rO{_CLvoMlJ-{B zfwzk%x71-JhzQY+Z`@a>jq(5>2w4KSD?l+;1X6Zof*MxKz|L48JA=SY$6 zbS^;Wig6UT{*5Z+#F0`V+XWQRMoKcZ8^IIuFb$+ND$1z1F80%EMe3?PCCxdS9d`3t zSL7L@C=0=juVglakoH#8(n(_|J&RC%b<1}`8tFX5lKx(ML`i_5Fl3-D$E$}tK$>|d zSC!bEOe#@9GLxz~$s0u6t2FHTMSJ)o%qm%!?sOOG2E-*h%ZDpe`udx|Hmq z1P}Qr<5MJ;YB!MYRXiP|EuPRLwCyG%_p}|~YUh0&D3jl<`9Yj4TrM&xW+|ztDOIcd zDut2<__j;QTxgtI@aer=o>b|J?-hjdNStmFDHKs1=s)T51)2Aqzr1Ca-Dz_6Hi3{) zN99Fg+Ht6v5m3I0C~!s716-mof30188gL;tieV(FriulrRa%bH z`<7@Rr<`(4-i~9pUo4O}OW|~d5=C>9frYc3g#P>Y;lVvRFJwO{opGe}6Ihoq?L-tX z`wx!N$A6TTD0QnWL0bEd)}94VnI<|ZAu%=`<#-}8+ad^fe8>H456c%rDUR>*Vk5^^ zFR~!$CQt3(2(88`p-Yvxe#!tu+i3*b+^VH2>A8HT>y-)~b%LpJakP z|K+qGa$oMwAcex?{O(ffwJ6Si^FU=huJW7-`O9&I14+{eOaW+Dkz@#x5Bzz8#_;05 z%SjrIcloy=q9lDWyj$50r5<)lh3!X#A5Nq3kw4@q0~eLD`7-y5njAO2A{b_>EeW3I z8d;HRt~D#=Z*rt3YKKSjJ9>^!p~swI6n@78B>IQW7*r zQO9U}8b$(mO&S?BBGGr2M?Ng^j zo^g`UL$mYs=a(6&zVB;L2{fv^d(cSpar1nn0czwUb&cO-BUP$RiJRo(&JrBhxDUZt zCQ)^je=?hYL1q?Y0D_$YK0*{=IdSt%Ed|}bWEP|fCjUgI5mv2Ivn2c~Kl_!+Tf|G?;=YbTsRZ1bKHG4Vu9<$vg)XGSYPgtDMbIKn|wj(`DattT33Peg^mmCb_ z(26~heErbyqt4)jQAn z0MwPKd*zuyIEG;9c2^e%HOI7sF=V$PPQ$F;UvhY@KTeyf?abLw=Y9hkXcyuy(p?Cl z6!xhR<3#aZZaD23Og?ZvHQ?9rsFuZuxhATqAp3$V239G<(YB`z7MxF>w(UmzR(Lxl zExwnXIq$`5(zHN(0ZzI~P1m$hZm_yCXTvN!o>Xpw2|hxjwf#LZG17> z)0}VN#dfsOcLPZp=1|CJt)<%QMs)983bYvI*+!TAHE9j>PT8h*ZzdvCxZxj8S$wZO zWvZ>hXWBLZ9p@U&4YZVeGirfJ`1c5DyJ$kKY#VK3=uEoxh2qntSI#`V*q%08H~J&W z@i27LX-jeqcbYoblUzfY7OzFeE|5nE#QK@ft+KHNhYmLcl5qpS@sAEZ&Dc`==FH&f z1C;H&@x7|8UW;J~a!G1k134$~KO!W8URW2Dikuuk*ACr`ZdqC z06D#u)#9i3+Daq)jcByQipV?nZCx-;Em9aZhQe5plqcU zE?(>s{F%n&A@p4`jmIdZP4Ux@iFw3~&_1Qv!#r_x7G3jgi;yI71s@!_p@R5c9Dl&KmdOyt z;kVFknr0cMe3r83JrNc&^cSPG=j6z*i30?+NQp^5 z%>tEYs7q4*G9yFyp?S8E{kRs$Jwk@}a_5-z#`Ib{(ninU?KN{A%+KQB5INAMoF{EN z6mSP2N4`02$M@RNc4Qm*6*@{O5lh=1Fl;o1Jr9rv3|j2Ck(dW)qR4qo(}j|G)W3hN3zA0Xqmsma9<8p>u&(b-$n>X>f&g%? zNjir_r)czKHDIQ60lC`Ytu81UeZ^wIY>|xE$0jM@KaGT3=)JMcTPB65qaL*O+qBm@ zCuuwmnmqkD*ixdg1`v>C9NCo=*#J-vyUlP+7!DG0W@vl!-KK@8{4%W&^8qb4G zdj4J3SoZJc1&=)!8!+E+Nj>U^JcpKR_P4sAXp!Jhu@P5ENe|jjAE9X1c(PL^3|!Ba z)udE>tqYP4*(ka_Ss0H^Vhb7P!dG)>N9W>3kv3=-GMgHX2JMb7wHCT?7A12?a}&NJ zYnNEtK>qLnJ<`z5B{XbV6!X1?SiBaYIwQ{bYucZ5%A;@|^iBJDkmJE=ptBdc9x$`o zyLnC1PLW77us9G;^n-25z8s70ZO)hMCd+|iTS^BB@przgB(Mz*YAq$04zyiko?(snqQ zByrS?o@5xM5Y{*A79!^NSm5n=zPC~%ZSj0u6c465Nf{7)P1%KZ6`806k@Ve8UH(?ZgH?*DmgOzV8 zI(|}fq&!dijHi?Lp;eGbf>sIi&WdEMY zUNCIBk;og`2Kv*`s2!fSjNiBkfH9<#O ze>=qUm2G_u?uJORGykz`!-+61j^m||Tnk68tQ?wuf*0GAy<`o&jV7fu`5=HbZp0nk-#Wq<_IYYBGE~6*kET8(LCpx28J6{*BW2 z_Z^aSG@{*_k9kHNQ*U1pi~!WC_AyDCzn-dS!#9$A`-N^K7)zyStnVP5F0X&zkQQiIg5^Z5OGPaL1_^9t9hgQVh&c^!V_2k$F<}YyB7u=dVSZ$CGpoBcz{PpB* zKY)RNwhJcGiBnOx5pc1l&8eH&BKL*#%L!Dv=+>+aNer_A72O-SqA3K-9sVbjNDwt7 z>Uz^qV_Ov))pPz1ZEQ+d({_Pt6MyTmQPX1Zxo2xAO?N#vBr<#k>w>nqXyg=aw-!m~ z`D;KjUQo`IFnkn5B(at3qevFy6=fMfl55)fFtX%E9*daW{R=*tw&PkPFR*QLtQ>$8 zh22x5v#Uw6EL>_F>zX@N4g9H>WH7(%Z`_m7`WWqF)Gyl=pWDd(U~F?Q^5~%2u^~~W zEkHdF&e4e~pAb}=<%jI~)n@8+ASvMKS|DS-&B`M=ggpS1y*yG08}244kRdSkf~HMs zS}NW7X^piF>1$e5)gBE+0EP?Ofw6UTr>bd9a+bxFX_;s;aU5?a#Wf=IsP1!tYpz6E z%XPUKBv)Op1?0mFQdZMgP!q++v8MHP?N;>nqfud?)%Qdi9tW%}+k4r7c59Xei42>$ z7c%YsU^VhrnPfXwSQ>|hzAsn9P@q%(8%co-+l3+54(BR01bg3B)3!v({$+^hH2Z##-po;2pO9$6B`e}beYHj?em>&l8EQ2t=Cy7gclGVBsYJ~Wfe z>jfcl%(wnrB~r?{Hix}xEy$;?jXm;#KmzOS=a7VKA-NJbpFg&wR&RJP-36wNwgz^| ztN;t)Kq#~NmfgwDLh=;E{(%C(<#7v;47SFDf863@23Z&zfx7Y#UOMon4H>mF7_saL z<5^6-i+3Q5E)t6ePR&AqTPpRCC;ep)-BD6P0K0kQW7;t9m@w1zrCCos~czQ68<<=wQ z0lS>1zCc-#L=q&yzvCDDuWgtqe93h+-__Ov4PVlA^T7qV%ECV6 zJ*7^s5bB8`2HL1!6~2A*t~9gf%zW`6tL+Tv9NLUJzz0kv3E0XzN;O$yU<|4lL8Yd^ zSMt<_jhZxdW*adkOm8s0!Ehp5BVyL|#BI%R3^AFy=0B<5oZm)M0vDGgt<9kJx^jVSz0NY1e`1lcv_&AaSm6YU z0qvuO=e$f^i=?E^+&Zmo_CXv+mS$|zJKexCc>DvSSTRxFm)wxaa0>8(#{CgQmrVfx zwkmCCn%-f;8L)BRKkEE83r=KL*`K5>Ms)fc=!fuvF%rUOz(4sGBC8Ri(Tk9AKoLj@ z_!91S+a3dPwm3$-`%sL#_5yr^Ab>4HK!-rcR9iwp5lj-j0PZM1{iD6Mfx=zj8%sxc zYLVW9mCCEOP|inE@t|7myKl2pv_0n>TTBe4O&g$%{1cg&oPP5zaTzeosT^@mK-~p% z!U6%DEM-x)uN6a}=U1o>Gb9KbuGmR;Kb3LZf+8`>2_!oCxC;PjCfS}wCV;KDYLtWf zRivYw6hZBj1eJsnoPy03O0s!os#142*jndM z(EW-w{3wYNopW(w3)J;Symn+c> z+;rqjC}k--J5Z6IgB@72?O<-J+B$Q4gKc3=;ffpRO?Z{b!Gwpz5#Xv%^Y#AP?&s(x zlXf!PvlEiW`m-@K5#rJ3Uu)9%$R3(BjASp<`Rto&RbVG$2lr;H#z>M$RT#jphEiL{ zfym?ENWo%5$*4SYvP4~kZVb290v`DR$tr;fF#h!OeQf!n7`#peLdH?D0WuD0A8di3 zV_)nfGYSmJvDyxk9>>dkEG^LDMIO%5pm1m>bwi4=@r+C~*Jc7X3c>_agTVY`ylQ7bCm;+>s6~D=%Dyd3?+_8z}9bO_#Did8WCtk3ty+sMN{FSFk$bZwZiFPLh z3U|p=?uKBSpFbLcNGhGZ-JD5hZ_^6LlHF9Rdm4Co8(yGeC{w|SlCK~c2pOkgOOjKvIM5+9m#U@g!}yT4gJd_MJW6(wHdY+3{r3eQM~tO; zOTd@76ti;R16ZI*p@EK(YB_;KzAFv*P!^BpsGlIej6uhg{m_Rcsgqh4|0oU`*1fXrkEEzw4|~*^w`ZrLJqMoT*=Lk_ zU*H*)R-U>hKc#qH114@vFW=Bc#LT_C#+^7Wh<#AhTo{q!LE`Ep+46z)=g#Oezud4S zxhDSHlF;Pl!5Z8(v~8E(pX)+g;%}%4HqA@ciJIc3pWam`DQe`$K^HO!kN#*$JKgDe z>4UaJ8mBGU;G&2?1#v23NmYrCp0>eK%gb|)%qehivHPa(@s9I!|^m3s+?oG*}ua^ar1Z<3m_3fh+PczFs)W6Aa=+0~Y) zoJ-Q9Jx2BxY?3lHbC+1BD|T`>12sEUEJ#%kOF*ao^GXKijcqfO2VD;~zIo^p)&rYR?kqRcf7omvnWV)%eKC)FhflvoplQM$yo z;7Ri8hM2F3yWrvU`Za(%nMwYu-a7SQUY^DbsPVLL0%boRX@J5=7JjS6T=b3JCwIn5 zu@9byxIr3Cmo;fI--tb^{oA8>dV;5%i*h`1s$kI6ycU$f5dm@d2l?k!4Px54eL+xH z8lYBfN;6Gi&YH3dOp^!F|EQmc|E>qaco3DL$loCLrL$c^ZRCmk(~!2W}uM=IeO z5Vkzmh~5I)V!uuIh5~}>Q+RDCs5f_mv=G#FPMT>6HGiC% z%60Tgo4*~j02r}+z7U0%W5=y6m$+jnktBl;RE)g+7;W_8CZ7GR4a5eu(@DF z_3g*RbvB!1t(~hg+vhUb_~zYWmFvMRCTYtp6qx30Wchp0zNIyN*nWX=TAH~@c2(Jz zH=zRb$}^gmmPzgETeEH9)ruV;krXl&B%z+VtXv~@0Ca}0X0`1KS5iLlA%HVZ9~^LN zlwFGW|z(zUfGmQdL<`_g*A-8}c@FazDe9g3Whq}xx{T%MT32QB_vx|AkEMV(vW(8jQ zm3L#mt)upb%(#Ug?o{Wtqwve!Or?q<9jF^(4@!79lq&>nMN~P(sN8ZyEsRD}Ep7OP z3IMV-`1p886&1fVuNFRfa;Ro9hGU(0=<*3Y`3Dw5kGYkVY8VVUkR;R$d?*slo5B!= z7SctLm=~g$8Bs5#8TlMtPL8V-KBLRPem7I;a@W1aZ?R%Eh1x?z)D|h%nJw+DPR=Rg zPy;cH>^lhK%|O>j>&T?!xPaPSBdhm)C$=<8RaE?rsN$)cEiA8a15~3A%OhSnDQ+SN zyn@LHRKyDBNup>9uPsLCws_DOg`%^ItWmQlr^3TuN}P)ngIHDM4undHT(yNmf|{g^ znV~gh5xW2yG5G@0gxAV8-MU)rD1;Guzf$(mN>B*g!uc+2&PPw6X*v0-{uZ)~oq&Wr zM7?@+^Rw2vT_hd}A~7M(i-(43x76PciFcA;?7mu)6?tTh9Rd*6&SOHudfCINmaYqY z1OX(d8P$MV5$It>fS@2qzaqk}smGEqz4VR<>fOE9)^mAQz2TiQ&b<=D&?jFx)S4=I zt3LQOkQIAKmW@x6@Y9^c1X&F3L@3fNZGI-Yr1nGSsL8Q&6M3V-ZvH^K zVrw{PJQiaw+eTFN)^zLpIh%8Xs_@BykgCo=bK}){T`bx(8^8NMA=8cFgPX`1Lvrhf z5!5UQ?<0*cJDEr^YW5)1;9cxMvm(FsLP-<9!+UE47uCLB1r8Xm@C&SHpc>9x4YRQ| z&~UJU8$yU(U0aMm21dlYA@)4Fiu14i9h; zjXX`q?*VInsz|>CG}nG6JXTe(BcNs#YETjcL}&OE?fGvC_6z|5h$gV|A!P~`P%hT$Yh6$) zg&xr~OUf9)W7`A-D(L-a$=9*`o%3HB5_)PACwe~^v^8NZ*(!}SrDT)$wkdUZHjRyqtUKb7lPI)pz0WwtQUS(ea!F0-T@2h z01;ume$XwiDu!4Bp$cbts){kT3ByRUX=|3a9$Ftw@<3QLgcW*c>TKPyESln2N8J39 zWp9kxf^FfJ1uVC?LzF$52hkRfwUULDU6Z6GWdP7g|J7DzK#i+5VH_}kIW7BU6kttR zY!-P58beR{MitU#Jq|`~N!W>H-6uiv84J*~hw;>ju|7DVfUeyUR&2__W85Gt#DIki zn+E2`aj+#}O#W-jHr+V#?`H2G0!b0>K*vHyhF|4CAPSkf*hKN_Zi!+SHTlWzt}kZC z-l}2k=gDsXWKo2Gu83hEBe7*%&nK0NX6}ap^(Di&8O`ldA!%=Rxk2)L*rDKTZ8u_W zQC$<-mwEtY+iL5t?r|kqT`&GkQ|)imUtE<@31irp z;2s?#=Pq%Fwrw2tQDg~=D%ufY6Xm$N-lS?5Gtj)z^$D7h_KJm5p!^;!H^JBQp=Dsd z@XZxw$;|hDu(oXf>V}L$8ZM9`I8n5wa+;C~ztJ{id}>H5$*~ajwIFR2q*@J}2-4Da z(61Cw4@@_UmD*EXZmmh)e9#9ClrGmev7Fe{!vd)!yI4ZHmc*E- z-AvcAoAyZVdyQ7RBMQTNAGmEJ8=OUwun_wd5jGFX`-qeI++--NFVioF(0b&#cQwE3~c$<}SY?dx8L69;6K>Le@UnptyO8yAdg#Muq0gY=>4?pir{wzd)6Oq4}uSyv>A3HpShliNyr!m=igD#3ZmMs-b6hJjt%k%gl!JHJ7-cBg9Z zVqM?bYu5wFoG>3u4*dxNE0gH)dXlt-u&^a5J}-+_;w=QfRXW1_AB zO+rgd6#41Tcb;+KGOLyEu1;X6t#K+4%=m5|Z=eNrfv`!Q&PRl^;`bkvf^<7cwuLaO zn6#;`0C#yUYu|_|FK`W1%U1Mhxw=={JH$m(Ru{bY^k6iaxO2L)3@b^V0)_Kcgi`IJ zad5byBwEe+stkqeybeF@gJ#9hOx?HqBejd+~BbyjX>;$p7x zfvuw6stKbtN)q;bM;9G*Y?-V6c+Yf!XWosJTL0)qlB9)jvXy(QA^cuPoQu+mYb^`t zf|BYWT_%y9*3=w)5OH1bZCa{x1R5x2M#)|^Z_E7tia1+_p=Bx?)}VIv^+pM>N86GJ z1T$|XL8t}Pt@u{F+pLMHbJ2@td!+W=ULkIR5Mex5pd5gz?ElU;ph)4PwEGI{2278R z1w4mff{Ee_TTJK{?x>ztN&;8G$RoS4wZ$r5A=hs8AfAkUw?9`&E448l^nez&^5;Te z;(-e_^X7EKH$S*faK`yy8Bk)7z{SK(wT1fK8w8q@J3P5H*^9^2(hh=Y&5==UbC!}m zN#Na|oeTrja0zektk_+Y^tfsMhj$LrLO7tl0(PrV^!Dcg>(_>(2L;9Bu-J zA%oB^DSB`ug!#dJ+I3Nadc|0FNVw{I2QwE$ls(L_p({qCl;j-x^0cr(vNix>Mh6uV zw}TC-+m?vZd6OIVBm|ztjGHxbyg*$rma|q4YXrM|BJaY%NCd|6f|sLkdYrz%$ze|P zb_Xy1*|T5)=luLdu_v_hnQdch5_@g5Ya=I=6cq!~V!rhgGp&0jfB~@=kPEhN#VbVJ z$c!otLiS>A@!&*FKjle=YrwJi8{7?l zhjDGX4SB|etF2-O-k+;=JoL;dwG_Yw)VeI(4P>$(=csJ!Zzr#9wB0%SssI~PHW>-B z5+37E-?nKd-nQ>%f+&s^+ML4Pp)FeeeZhP8V2B6-qC;h#rbBchcnryf9W_={a$_<&d- zCzw|8?T}35M3Oz}ftifG8=(Gv_e4<@y#>aeQ`_Ud$l$D#&;EjL5WNCaD8z6y( zJin2QT}4q{Ih07wHLMH4zF}Q}(*Q0eFAuq<3Bzq)NF7J#8w}~NW|Ptc`^r7zvd2Qyu@(nA3*g9h6(vP7+;|mwZZ<~@+h^q5Ky*^Y z1Lea;;S01K7i{o}lq!mq>EJWc6MLL~SPw5gOYYV28PfQk~@QGes^@${5 zyhpG${|m2ODbow(ZN)~}QpT|a6M}211T9>4BaG<9FWH#fO^z_ec?09WAgng>fdx`z zZJSy)O|#vSSOjGNaUeOH#yp60o^5oGp5|>A?c3UK^O0`hMvakG(u19tV1zy`kyz+J zBCnYLD{d(wt@9yuNy@>8+~8Y?Q;Uh4O!p#B%!`va@v!Xcg^p>QLfqgRxz*Z|TySmV z(`2P}?PiTf)W4^y$hOMwMJ1tF68(5vx>>;~jO+1|1(gn*2aC<}0vYc3ih0)W^&@z! zilTFITtJZ2fnv8t__8hHt6twoJ~q>&6EY8QCcE%$3%X|diJu3;<)%iLaD zH0>GJ)WThhW8|^jsY)RkPI1+g1Hmk_z3ZH1MH<<=xh)kfo4yVglNUzHPC>dBku_}2 zHFn~>i14Dj$Q3(&+L5Rk%{R*uVQQH3|R}S27M3Q^VIBAd#J>XM&j~J~1Fo6s4!Tt`=DQ z)9Q{b`dhMW;i@<4wBZCiRQH^U(lY&}%e4X~di&RbYM$WAUwMyB(i5<5L0ywbnw2Ex zdIg6U11FX{RJ3v3HZplEf90|lN_v5&T`-Rm%XTbZ2NLP6P|NL(7B)%RgB@T^AbXEg zZDU`(jv+qYcQlXosJO#EhT8#Fwb)LOsy`#7O++Dmt^hz`F3mZ9scOA8`WM_85$*9Y zR@y|zZh9b%{xR0pi+ct(pk)$J7b_aij%=^!wo`Q&kxOqwBEH~N1iQdY)`aLGNQCK$ z=kcR^*%9w==oJSQI5&^YueryMIa5Kv_#SFfCc~XsvC9@1etTuM(#1T?2BTP%KsLg< zH)d-U#a&Il214&GFd{KwBv{)Es<^az-A9x_ple=X8_#-$%_lTkLc6vk3vb;_KXJ$Y z#%ycJBw-ZvWBMzq1;+s%l#)sC_)&s=fjaj%@W&P;X{XIq01RFI{hhJBxPKJwByps& zYt~&blg`GqOZR3VkV9RQOK zkLe3Uc(V(nb<#vQSgc8^CF5UXtRLtxU1>8ZM;VyO3o!|Ba6Q5CO5X}tV4-Y8LI-T4 zSfGhDy;1j4hajE}XV?n!r>dqB2D7+8yTDYpL1u@8zEByFx@w&tn6t0q_;ouEW@@M& zM49#lw%OagS_S(JTBSOGajqg_8(X%4nQA+vG3L<3OzZ< zj(y;>#qILfGJ_{{r(cBLsuxsz$aq0X+9=zsg)*iMG&og%6(oq>8sm}^L*PU@r8QfE z75RxJ2{@e4Grm+beth{{X$4c1YGT1#c@-<*}(yg+XW;sl3)lsQGT4zN%|n~y_` zNya_c9=65Gy>qI`+i1fB#yMY71)C7u%`hfO!|*<38{3zmL>nx>>vBC0UA@4xK9M+) z=_FlrTGw>N?hOPd^LcDj1@giJ5GBNQv*Q=?QtiBCK{}`qg4-t3&sJFw-w;PE3(2vr zaV~B5;XyFcnK}yNhQ}AZ?3QygQY47a7qnHk-R~c<0f8LX*va!amJ|YqLeeK(ap zgM*39G1{Q^3Hp|rgi6tM7`EFSgF8u^e@gZNaiQPFw-J7jO0aKa1Hp_tDArcQT@X&Z z*b#R@cZiFMxA)=)V^5YqOhRpX=$9~6#MLMXKL>z?w}1eQlWj<&pKstNO8z}L0} z+Ilxq6Zd}EQ+}5P3$UVMdB`{HK3L3Gj0vzT_8^oyckz4d-wv5X`^cjy-*-(8uYLFX z5Ac@%{O^DJKmS2-o>_Hj1-x=(& zcnl|QAHm}>zVbts!FLTTnseYJyn$S@T`;7sGnFjtti0>5{esTT9QZ?9`OYJR0qbJo ze0Ex7ic32TX$4w`AsI_14{KdWSrndx)KSLiIs(Qx?mSm9myZ*sQo+~OpnB9;Bp!?~ zlCf0IDyOOG6aNx;k!td}eG)2<+~SqQC=rMWBa~%)j#U~25~KpP&%x5H4~FyJUwIko zbuqu_EFhTk6Zdc9{MkzDYrhc}e`s;2Y?NqNekI=Q6I zHk);8O}8gQ{Nj+%x4p!>`uIl9Z<9s@6@{3z*%IOJt3ip`5z2O?BghZ}z>|rSh$Nqw z(n)@7Mku&%%V^F+zp~;;@*ibxA!QQ-iMJ#^0cgUs%=gP{H09;(V=3KzQtCtkD7Z2w#zLJu zWo#n5ZTzdVJ^C~rZQ)R~&xn~&oki$hJ}_}=6vq&8mf%pM(5uU7x-_Hukgh%su|$%~ zX2_1#8%xM}uzP_dtQW&(if_6$76{9DK-DMN47^qa$aZ?9%%WOjkB!F|IA;0PM~)Sa zaNt*(U5t)AjzN5|Uka_)Rjk#J9U#pLV~=(0jXwKrS!^k`&(lg&eEAXBMx4vjzU(89 zZKF0$Jf?1}MqYJijkH;Xob6zpLrV)K$wpv9xWc}8z|PgKG@|&*;{93~sUa<`+#fBYxa?|%;wc1Gt8$DJ~Vn*0Q7F<5DG`yc0*K)OkzsX6!GjpidSGdEbFbs z9y?bYR{2Vn`$qBdKCGI>Rp|;O#mt<+cgLy^hIC=ozT@8&j^&7UejUD1R%pi2aNe6C z2r0WiJ=iR^T2*?cADKi~ychUr*&oTn1X3qYqcsG3=4E z{xj-)-Jtdm{jw1sWx0=>Mp-1bUA-r7PUzM?F(;-kuG~}cBd*xv_c}}n>x(`01JCAR z$$lck@56m}s0Og0AU+O8ofmuDHwwr4IE$IcBGNs_@)bH>K#O{Z7f5qe)poF?u2JLb z3#*lJ&+0u&TvK7ByY$MqLzkr$qRuPgvyZR?rmKjTNb9McBvK0-_IQcCRWm!-tnZuj za0f6#;oQT%FOf}zw2S4EHWahWZ(w%y)I&`aNvAT?>A@zB?od%!Xx*u&J5&_XF*BiDuF2+TtH`;(%S+-%vcWbxR^NlVP#2$kVv@N%t^H7;$o1FUv8uy8G&8E{Kfd^Pl60G%x(3wt zQn;)ACtfHHX;YGR%J^u6?Qh!C>|jHB*Zs4Gk8IHftfyxI zzE~NZjzJiTi5%I2S%sw4X?F1o2w}oQLqqJ=VLecKB!hNi*ozP8D9jiRa-9SXI`giy zCg0G4JTGXC1O?%U2K*CKN}Gh$2B*8)3*uET;wd>=T(|_chuShFhrV(r^1ggC6SCFro9XC=O6k4 ztOTLSxcw1H8vFYL)E8tnf2&q(cun~gOfoYG^ewtK8TAo10AtO!KlTl(58pgE2L9?3 zctGtyy|Y>rL&0NedaxvGD^w*33N{yr2D4%v!`*<9pWFfsNJ6dl+_-I;bV4@17aQ1h$(BSz79nC3&EUyyZa#L-ub@7swZQYms&uG*1QQ(&GQ zoKa-IoQbigsqpJDN#9Z7X+lzW*Po^v84)}s?;wsf*n23CUns)beO;l?*^jc$;tXXxpLDIt(TKktmyq|JtQ9A9OV6ie!17wjn7-^H2JqeOL-^7a~@Hf3u)ZS?t*&quLC$p=aA4*eg?=86EgTD+Z$i(Ie2CP3^3Dp z3@>-2#P9kst$#c#hu24l#)Xa5rUqUOC}TV9!`G58~1Fhrs0HZ zV%o-Uu-zT2Y8v>EQ=oJcT2$#V1I{)Ky_n7`^^8~6`5ZDJSg*Mhwi37isgMDS>K~K6 z&o7%%A^imj`CSO&?=y|e56ArBbG`7ZI^CtF?!A*AFK+dlFF$NXwgdf4eP9XD~=62an9Jg;hU zc*3jEP*`2%Z}1APU-q=fSGsv+o|9okTR`k}pBZpxQqE&ja zk`jVEqX$SVr76Kg`5XDzj>tFyG41qlfAu(A zM%Wj86p@aKc!eZ{v9^F*D*ikk_n#p4=CdCkuiAb8%0xFP|3Vj8B;^(*l;GLZ7*^06 zk&)OE4G!Rw1RW`rXB=-v&rgc1IL%0xnTbN8xO^)!a|8x-!6|D^4U0F-UCPJs4F+An zFTGdI(lWGnIxVlf0@~$Ie8AmIrAyg5+Z_2IF%n%SV;Db1mRN*=&tlPc)?aCsD{#3z z!!#Pt3R$=$17(*@y%OK66j-%NI}?Zd!xkKDAIX`^IwlvRt?LLNbRddFJr(p(@IwHR z&pR}+nPy#y=y;_*O$|Yn;AlGy`2u5BwPO5>~xqAdoBLk+`k=$lwpzb)Y~p9Hq9RGq_WgK$Q9|LdS!y zGQF&zEaxJe(D*pRPGqk;{)lg2D|m&22SX{=eVL2;JCyPI?PW$C4rLAosuVKl&f&yc zl|f2lug5ONCZMScF+^;WKF?c?}^ta{F_`>V=6$r&M+< z%QG&}(~|>+vrE0K1}4A&@gCt2tF&HAmWz=@Cn@~=QTA}dHO0WwP5@_zI?z?ZYtN^i zE|y53OYF-c@}>J$bgO4mTMq+}qGQvIXo6zuS^}MJ9nNJjj?*nVhkTM_wC+vsEm+U6*moGVS64E|o6Do*1s zSV%VU1>H7BnVo86m6?tct0+cI+;Y#Rk6K0aMltWZXom-G`K1Sl_+!;sQ?Fi2n<&bB z&@vj1@`0y{Mfklo_Kr#JOxkIsb0$qHIrc>jc{C*}(Z#JV-uIgZYUthK;5j^8E^SXt|8Y>@t*`l=ZT+QMuAMmoUAB9;x z)JMB>kDhjgIz-=fJoenAU)QHWax+~6GDvcwh@!3z(@}H?-AkH3W)wSg_N3gg>EI*F zpgl0*5c|#m^&L6+M^3J^rn;lZc)!#vuwAiTv6}gipR=KceT0g0(+i*$x5JgdyHu zQRg7MKnf0`xknx%Xh$FEnH;TkJy=~tv!jFC8%OO^6RxHdhbl;>ha)NK31Z7zUp-2VLgzh3?!)T8mig$c8WC`;Nl8apX}$wCfTQjAYrTL;HAs#`sgifT-$<}~8A z>YoE5Q(CjrNb>YoY5e+*Y`UXS**ROomXsYdWfMmLR6S*w%)d$*V7(w#a+K-uA*w3d zpL;YixzVc}b@_nC-GZ8J&1oV1q9AiLyVHuGr)GbU(B8_E;qT(86;!`z=b5*TaQ8IlQ6@d5 zWxPF`lx$Tl?bpxZ|0;@|CGeplZG&DE|EeU?GR$CYd4B*7?Aq3`Zbo8f`@K-otzf}yFnvtaYn zRE@5G1nvZU)&dfh{D6#cgBtAPAr_J=;GCK*=5H~bfGNWF(`jPt&99vW@vzw!{tuZ% zI>>@S=nWjUATx_$AJOw6^j3J>Qs@p<6mp!R{T}!)0)n0(Iwsaeh9V#d+Ox=pSgh(s z5}^S;#F^hZ-11~9Vn`k`P?x>#~@c;fe@ybvoiG)Zw>3|0gY6UGeD4- z3!w%kyc59s($fNyn|kwMm>#eX@C6Y$vbAm`7UJz6*%w*khw&V$Cz<#a$(uAPHxjc_d z=*D9elVCy@(pIj=-Zy#C!!Q7itcH-}RlGQNE_6T|5%q)6r74=-ie7AaL{XHLOqeCn znNk#r-}uXFQpUSTawc9#dWkb8Y8S16XGb+8Ppv^%f#LnIef&*G#A=-KmU^Nz-ue8F zsb-`rlrcxsZmT^_xZLJY&%96hsW&E`rp=)~azB8=A|tm&K4!J)nV>Ydbv<Y?CXm zCL3Ux5LGA?8x?nqnc21Gh3$6$Oj-X-f>Amr6ct%1K*^4bnU7^-0+7cMTP~1LfQeKA z={=}ZOR@RrKG!thgYY#30aO8R&=6wN9ezifK8z1UWgo<3Y|c@rSz;^#9k9(DgB}Q< z_0F>qK`xAj6M!mqDJWCgF3f{zFB?G#5k;C2z_l^5s~+KXB0wL4cVne15gTt+Tp*%) zMsg8G-he+crkd_^LUo9g6<}u@+uazUHwUOsfhMHivnfO;*K-OcdPKZUY%Eoxbe4uD zLO}>2Jy!?dcQhp{&RsR}gHU&oN)x1_(V)|{6$JjuvZ2ujQ;>3k>b?Y_SVIKry&DK${# z00~SltR-pA1+32(mIp4-AFM~A^Tk^?R9Bd^|Jh*`E>ePaCM0-QiJA)&GL?IjCBFXH z++%)72O8)ztZA5QG)d;mH#?m4HcvG!+TG6#5vXn8B;ACfqruT$gA9HMQ`mDs2$SCv zCmJHy&Xfk^-UcJT80>20AH>KD^+XrE5>;!4R^aKiY=fsd@`ja#B0<4>9w#vrN=(3T zHRskRzoK@A#2r&w_7O;vaN;xAFIaa4AU=_}bbiO-XPrdXuAL@IO(8SOD|>jls!48RpJ`O;D)W)2=VG{TAS(F1_Vr*pi(oN zt2iga_e~z?d$CvOMac_JV=hQ6ZU+&h5!`PoW~C0G?XRRzTH6E+DsPdr7H%y_b0)Cq z51$H7mD=WaWdf@N$p4XYJ&$){kRYCAdn`575b#C=OSWEFz6RQ#-2iDmAin_(Q}2dH zp@~Jx0Xtf}Dzb>0C}rR?P7>%T>C^=@MhvQsPR$JpqTFptffg7LU(-X-iiW8~&-9?z zpC*4KpU|x;4q%5HEC{=qbH~P*hayrI^l<6b#|}rC(a=-g#E5;3UySMC(-nV*iYL>D(&h=A@H%_)+_@^Xdb>JV>ENN@sJE8J9=I|;m@&!mcL5(c-h)!q3&te1^mC_-i2 zk+C*P0%o5CKO#S+T1QIVt=MWQ(Eb(c9?P|{?~&1LrZdQl$~Q1~ILTK^<~$Obx3+`< z0dYqe+fTL8hWn<(3XYnXq6r*8JFPKb!vw_)UApJi{*^+TcD&MVrEIRGyrfCGA8t!a zp~!&qR!o)jB;%|tN57X*Z?aP=f3*}Vw1J-YVPKWlw0GctW0n0*C3O9ga7@bzDv!0v zMzNT6JJOaI@d#*`c|)!KqPK#yAusS?a+HB1Bk8qhzSr~i8p!G)4n5qE* zZxeIA6cdlCWNOj7oNSup>}=J7!OnX2>|d$UcFC9JXk+`ttyo9T84#^gfnsl4yJa8x zdSWIr+HS#WV<;l2=M8-!mk#XQg)jkYkJkfHhALBEFSdY}Nmz0u6cX9pm`fhnLo|)$ zr#r3~xatul5`fhLdU0KOTR=7&(00_L{ZLKv2rYSrl5z!Y&dMtCdx9U5XDGv9gl3LV ziFiWuhkyhceu3NJ11!zOJLN67)^D$M>H^njYEU@gY-H^`cu=_}Y@N1TlF?nE?S~~{ z!1mdE%Lc9H1@thFEIaLpJ0cmsk$q@Ik8A@0KvS2T0J#AfS)9}HSYE~Uj}&_`y&l?I zKm|c_f*!abkRj?M4l2|}AVJ0|Q%9OO&g~HDZ}9H?^^m=%2!EC z7(Pop_}%@&o3cS0%@Gx}@SBBc?pUF!F^WXsE?gv4!FoA*wnEvxmg3z&cVN;26Mum) zB!)UU=v2}LF22g+L6+7`a}vEV4Gl)nY0*Nqu*o^5eQ`@`Gjhd1PAq^V3G}mKBRo^c zHfLlTZG)9f(x$@f!?43!?wXGrE%%yj*IZ+gG#u(v(#ZHO#NKP#rc#Z0#C6bX#!RK> zk0~rft=ibJk@wM2lg~!}Hv2}c0gMw)ig#)}ieFgy-4>bg$M;bO$3GMJvbDMTHSl3< z!J|jPUiTZ;Ux#_fHoA|(sR`EuE$v)Jny|Z+SPp3Z32AsnQZ~_siEOS>mji49$i$x; z#c#eC1X?lIxMfwEaAkzV6k@B5OmU6gEWl1$bm%BsQmO~(xR$n%d@rCZ_Sp0k2=~E| z5F|CH)QeJR9;Y`0vWo!io3a3jW}dDPToclDQAd_0gh+%|6AVLJiHB?E;7H3yS$s3_ zYO%+@aIlDNdJ94YHJ+0qS7`CIRtf>r)VerkXYzbgsb%TaV%oHHnJ5G-3fpMw(svRQ zFHTFgp{t!p{}yTCqds9UB5=lN0IGQuG!p<=$Tn|c=VmD9uX(pK5XcLZomp+to2!I5 zw^-xrqgzZ;7NU|u%7}~mn7z7M7qmw#n+r5G1M*J_i`vYSS2T*yYekD)8c%zY$})bZ zMgYy|B1@Y4y`EtUlnAgAyc14)Yr)`1o@CgZCLk_k8#(AF0X_zfU}*ETL(IN3Bis+` zyydTTO|7_njIVPNsV4v*^Nr#yT^NQuu#>Q`@-0=*;(lc0S(XlbZEFp=L_IB&@v|7Q z(*_#Kya~4s7_`39&R}R?XN$Cr(l${VN=q2JbKd3Yd3E~eb)qJ?;AcBlNwxlpVS3sH;_Y+wYc2F*;k(Pk059$X7x_KCl(Br3(3`Ci# z4;{=_`R%Jw7bKD}T@S`-Pc*x*tlW2WAxS$z!Dwwqu9(P)2{@X!HP^hAt(U_md}TdL z+T*hLiRJFAJ|WY*b8NoxP+3n=Miw8H#bc)VsJ&$*eGM_B%u9529|Zmn;t}c%QAhnk zJffL!9v@&{ji9So$Os~ED2xbnO(pV!*Ex8BvSQnLt+7K3a6L(`2^F%mA~DxW$AXqW zAjFNbW8ZSEYLLeG2jdB>`ri!X&|^%J7Q(qMaE(ln_z|QE8wf$%6ism;oKPZxqFFkM z4Dw(}3;mBsgd}auS*_U?yKDdqdf^4rPo=E|$T@@r9eb?^#;alZw; zwu7cL?9@S1mLe&2)i@RZOXCWS^F6NR4rx)#I*vy!94rz^bAz&pFplS58`kF$aDrE} zqeMHVjqMVkYslDWMgiq+b;urZqf1{h4(S62D9Kc7wT(H<%VaQ+tJJbf4IZPHmg3 zXH&D%EzWg7T(3z3Im`eh&(?7zwC2k(OKeghddon6RmitS4m#H3OOfk^*C-aI2)ERLFGicc*4RYDAsv*kSV?e0Q*Vn5pvIy!`vPtBGdgi9k9Yy*JWTqmiIe%E<4Y~W`vsxbnS|Lv|%MWP*mt^COKHQHD%7kHnt6hC};X9Z$1sP=63twkOInPesS;~ zNy*%hX7h(pv)l(mAc9_!#Ku06e}BjqBi{nw}#nfc86N4 zwmG#}giwC9v*1YF2Pjd7#sID2{I}&3{funcFpS7rb_Ou9!3pgi<{q4QfExad$$JZ6QW0rfjMwZns8A8G#3t1B?+n zo3{w^*_I7h9?f1|@Y&OY1*;y8c7!oxQc>_3V8-66vOQb+Kq3((*%xTTHg@7vL;qkG z$B{M$%LIni5FtZaH6R(rB$F~3?wyK#8{jOk@ZiswMCcX=t+qoPNt>J5efLl?Mmf@G z^goWZrndX&mDUl-)I0V|iSje&$W3WvmF0DKi6e7e|ezaPV~0;HrL!iGae+i?H|T;sMq=ED(L z+%;vfs);br2Q1X3uCX5r&s29wPIh!1NwdoVIWGMGUTFadR(9XOm!7_76GoJ2-((ur z$*=lc%cJL73ALWBM`X%5%0@3Z?TIi&EAEb5)AJJA+QHltf2(kfhRE}S>-ip z($3^5;M+hNqij#sscNU!mYUnQHDNRVF_@wx)4+2)K6JR>#yLzf1Cl04OJQm4LqLQ8EoZ8_KY% zc6e)5(wu}oUTzaaI6q3U?7dZ(YdwypdzNfd z^WdpWAQRlfXMS@USd=K6yx?KW4Ywj;19t|}`XWG;H8KKf@9c=v{-%6< z3qUH!w~myZNGxs%GNwRnLOUw!KkZ6`-ByAqnDa>tvZ=9Dt zB`#n2IJ-{h57~nZIU=-uYE8tEKPK+JDOhEUs(^5Y_!Mx0a}pfbqNxc{i&;M)uVk$J zFiAp)**f7v*Zw2sD0+gzQhWKKoTGh_b0TJae#U%xixfnH=1^YJTLOqiqdaZy5GSx4 zHoVZOW9%4_uYJ)spR%U1*%QNo?;6Dk)RnK=Rs;0~DG5!)yuA z3EH4~plT{eSgjrVizhKYP=UjSfegUO@fdvCzv<_BK5!K6mnsnA)@jpGpzNCh2)jdc zl#vhGdAQGL6bWPqQR`N)0_mKgmHp~7qb~v zR&9Yzw)u^LN|l39Y3kqRM`5KTbpeSyVd#_(Q~du(e9|a|7@ipoU8Yu06ImAbKk%@pVnC7Co< z>*bdPQM|fS@jMv$lKhNDenNvc$)$)hn&c!KLZHx$4Sq7H8F?^yByd{jYg?s83aCr> zxWeieU7VY*oNH;%T9D?>!7mUf`5Ps3Tr{~43$jQc<|^&C22^W?5o3cU;W%S5c^^%& zE1+S<1;5{+a)Esa6pQIcfss5(eGZesrKrn{7ouPwG$u4}kPxDK=4|LkjCqZ$T&LDc z@uHXT-k&Fi)ol{kd;>3JY8fDFI9T(ZjWZ|!M~$_jRTx;JsQPCc39>uRw`qn#4Ct=26(?nJ2L5)&I2^yj|Yo-p4YVo+H zfSFYcHRHlSspiFT{$<^2f>IY7Nl#J`0&wOOIEknl%~~0~hQ*VI+W$7UNwe`Y0{DXn zCTU2oM6#gGFN`@eE~9gBn|L-$py3thpddx7=!Q0=mmd`x++vs$6F(!tE!?R!rNJU6 z*$^UUroLe=5%h`Jxq<6riK}jNLW7^Jt@gMNbZ>A0@m<@bsc-P>25Xs-$QgCE{jr*` znbY8Rj8#7Hgc6&ywI-TQSvm=&FdJ)xP%dd0X5(~T4{LB*<4j@`4jymzBiA87Q93mk+C*CJ|r zJfdFa5VDPeM21ZRzdjj(g=#_KlO$U2Y~2c!{08&pq5E3KoD1$jkGjsELco(+2K}3; zaW!+$L^R!-30tfeC!qWge|mT+!Pjx1J?GwdxffYUJ7~B5za?*d4mM|kSD{)DbSjkh z476MW&oFn;eqDSmid{%Ru>&l2YL9s|_B~8M(W-zAb0XXm6}64)$^a+*1}X&On%k$9 z06N%#O3%%bvo2LA2F;wBrT(3tY6=E>meYr~^nx6PJO>*;vygLza3;CQ(!)XkO}`*w zow8vr5wVY+N4i}l>V}J^pc|;e+(i?$?T-$&EbKxT6yLVJI;i&)iidmF1^raIU#|1-u^^l>s0i3h`fs-dSti&pNrlTA~bYN(3N`{&mV0_w<#fZXpwcI1sk1IstOw1U$kNmj4CX8;OX<}y=A^xmuMyv1AZIiOrA;N;k2;Q&8`)Kg2Rhn1EwR%1h7GC_cnD6Anj-s0=Htk`KL~|^BV1r zC7wL>1`*!(Ps4&A zVV5~kLX!d#X8w(-6HsXU@Tl~87u0J}gMdDRrL)yHTIo9VZXhtIE3sdYt|h^96NwlP{XV6h>f{4F^d~kV zV8omVtw>~p4?`KqGC{AlNHWhD;?l24VNM@38?qLrxmoJ1OU0M?sh1Otrs{z)mo?z^ z`OPZrBPwRjk|d;esZ5M~ox$v(Q$uNeJO3b1w9+DL1>y2#ll)xkn{A<^eGDqG4)BEv?ss+Pmd%S@7-2o~C( zje~=HjZ&WzlQgp|-71Rt*qAI5$r3NFX>OIqANo#PBvt^RuW1SxBVmC#T~MZU+Hy^@(L>BRA;CwvrJD9|=t>Qv&-~l7H3%#&iRzOyjb}v63G?x31_9WZb^9T6WGzviG#01@A%7^5Q`f{+AXVpV z4FHXqp|*9PZR(`}4)GifRdA4!FX{RUUDBu_7?L&%9p3b;h3eWDA7%GZM6n}09q^+) zKNN_`xzey_=7geZc1+r=f0^XkG|GF(HCi@N{x%IQ4ycBv_^cr!!=vRu!6_0#A9{1c zstP<+Fx+F>c33_-OM)U}Xg{2E6TJaU+je0yv-YnPyM%~5RLQ)r8ZCqUaFUHabx_}5 zQ5WmW6)VZWOJP7uGPc4%gDo-T%-a;2PlkHH9jJmWg0$TYPawg5)F)K&NA1tOe3EGD6^Lk z8VN4iDU9?>bkY$4W-Mom8wGx3rgEXry^k^_-c3WAhlw|>j+`Z~6wKn7KZ_E`MmWVN z-u`2a8s&p#`kqxlzIoj4j$$85Q59;|GvR>CZ=_E_*nK4`U;m)i9d(U-{8i6#h*2s` z#+5&2lH}u(U#SREyod%1<`np-q;g?_>DVa$^~x-;wFo&nC&87-TQ}Odh^b8_-0wTU zwOjG5*a1E!!UxT1(28<8*c23SEbkRxvM6vgHqfQ}?Op}%FNZiS7qPdqI6l-Cst*o* zA*20n#)pT&Atl{hzonhUsY5NKEFL#*Kl}9%ow+f5{K1f{BDRLy?y$f zyoqQ%*LRs8Y=Y5U<+#(2cn4CFLRXncS6u`IdK|gWeEO<3F{6!@4x@wj#ff~Bg<;M* z_(7x&HKk%~vz(hoV9&}EV&Ggp&g3n2*;)2pmJ0iYVK`fEWQbdy*(>$uzfqEiOSlJf#B8KN|PRW)l=U>nduce z*=z-GEK{RB!u%F15?r8Ne%i>ghatcVgLFK6L&Fjp_S(OZlRewS+EZkocuLP3aV8 z6%}-LeL5ixbeA5_bEMI2qI{!y`42Wu?^(z|n$_so>&%!&p{$PYFbu;DsKbLy(4otE zV*1TdPPNNng0RaxGs31Udq@}!@F4Pagdv3>^qMg0RDgYPO~A>4p?}jvliCB!rrEd2 zqGuSxVcQpka^)L5iSWjwd%TcE5?wy<^Z8~kZy3Mi!*hoHnL2i~2v70>#S@aIr_m4tlNe0EYh>@wzW42fB#Ni6D6fDNnWvyYz_Kkc7o>p zS31Sg6DdK8HRlpVR0>DHp4elKkuP(WM1b15&*B}8nsrsw6O!13D$C6oz#Qq%}GCV3Qv%RwU~`I;EV>R#T}gQM9Ahm;pLxq<~F~1{^yJL;1xUNn4%Y7 z))Wm)u~7NsIQ{*0Po$mDbg+z8w*%C}OD0$XA~_x&e9308#E=B}mr44gH4E&Q(0i<; z-Jh@K6e)HwlfYjne~jYJu3;#M7)XLx_e!SD2(SGUQZ;gU6phUr^-ub7B|(Kl4ASmr z4o9)#f(EV*=ig2So%PSFE1ev^^XnvC&gJZ+)9YEk9*j)7mvFlvnb?XZj&fiMDeXOy z+IM#Q(Wrk$BU7qDP|%0dBQqu*=QfSM#5Qe$TZ^J_i%k@Pzr3(7>r*{=Eh~l~UY=%q z8a*^-eZHCE*0~rARPw+QB;fwq=(|aw_({@6>6sa495HVtabNpUw0W%XeB_Q%>OE4ee$>S9`P$-{3A}MtL z>7(o;dCWgL(HTMhS(c0GB^!tYj#!#n zT2)1@lpqF`seL4B_B1uYF;Ew#;<4}4hj;pic%HF-MBh;Vfn8H{L`hJ20IDQ;bo!|D zQH|sqjGyFPF3(^^kzFU2@PeAOcJ2@vXiG|=ZYG#%&V7Bc&W>S6R{T-$E?sLCFv(*H zy|_)JJkPoq_0=hzCXo48Rq6o0NG$ah0%&+-ir}?uG=2L4KR`=}QaF`{?gcV&&fkzY zNA;W$J?Q(O<@8oUa;o0wClyz|P+mUHc>(INfoFRQ6i#4qy>wcSRSTq4BIyTF!sBGx zcHJ2iB#?J^d4?V8={Y0Cr~3BLoN!%3YN6{CZeu)Pk_-zWif#G#im zFpW4P4bg+gY&paDP~xeU5@vE~WQd4nRvsk>ft^(4vU!1{8Q=_(NaTtB64nIMUaR9Y zirCD8uwuz+PxOQlRf7fi1~o%X40SiQQHLhd0WK{V6#16XhQ*`?rL{@2pJtF!LP-N8 zs=M}v(k5=Ca3mY-h&A&~cB&!KaxOYYCKIvU$}LYS&D z?u^SQ%Elro8)4&$XquXr%n}wNsXMkYZLA$k@;Q_gL1M`UVCSh47VBM)h54t>pe0Xu zCWNZv+RN;6APB?}m+(c?K!(j+HxDY{a|m=Lr|HV2!i=C=K~ty~NouBjaA&PbeD@z* z5CZwd`_E9&Ea)Oxe!b9-9TMSXH0%Dv1`I& zwgJhf~FlE*EKsdE;Wcfz;|J;ZW z+Y&RV?hTTZ?7-9nOcEQn1Ww{Tgg+}?Guniu)mDf4jk2qb?T3J_+BeeXUlJ17kfl(X z=N4jzaFkvgu@wn-u>s%2EW}$()pGYM#uY{p13 z@u%;h#~|j`yY;z_zO4{9i%JYE$t~gIl(VLFjs|o<+rqU~OF$&4O?Jv?DBFlM^|Y}g z{jttSvv16<=V`#Db$?Mk;XIhMV^Qj1-JxnzME9T7n1CNscU&Mj7_!p0^XqvSOOiuz z&r1&%agD^9+~iX@QsRmV%-3r%6jFFjTJIktOG~C5Zl~zlcsn^mqRoM8$`IE*DfMwA zbp|D+QZrQ|sYtbDsoFjwW~zAJEyf?sh^2lPE+_8*6o9TN3wWlo#WqY3HCrX^RDf8lk+%Ire}S%X{BvcKUjvM(oi=1$z?H~k zCg*a+gt=q8kR0U%GJcQZ5NuJypnIXErI>n?NKUG%DzUKEnSwjDUYp7X)K18_R0^iM|#wMh1N%!cf_-Sb0ZDzm`BIj zE}sf49My|$BsX;9>}Wd=6%qFZJy!5g@~8aByD>HtS(%73gE3-?MS%gHVW+V1Fi&6@ zr~LHBlQ=K)rZ%WP#A927xrlh!+Zrs#E3F&Sa44d&T3OiJ8ddvdw#K(sIX|5*J;a3JsyBt$ z7E6Oa)h@7(zG7)q$IogaRv!sjnwoD%Ax9wL!I-N+R7VyLnn-nSW^0b+6*|J2>>`R{ zio4RdD8KusD44IP#6OGB;exuF~ApwzH@fbKH%0Jd`CxW0UIiWDEi!}ZM0-aZ+1HuTY7T+L4RG#hT zos1HwEa{UpIzdnbpJ)^GYA4e8Ve(7QTN*>C z*$QeSYzi|JU#g}kXxk!Zr-nwN9-mcHm1q;ARX@X5^xOgg6S+SH>R(}@j=MIe&LyHA z#FOf{)8CR!t(UK{I6D18UQi!A66j=91Zs&YEp#G2paaF8z*jm79}Jt|7eQ}SL3kE= z)Af!x=!^^_V>C=Cv7&*RMJW6u<|bxS_Jj&*5pQ+X3l8d$BBD^PNNr?gOGOei@BFT} zh50uW{eCQ@y0SF~y%K^mq4@&ZO-*uI%f>;iX5&9pzj2o!-_~YEEM#{+6(}|Bz*!;k z^{S8q$~fN|1_EVD6|Ts_LpG9~2fo59A|`-Tf{Y2Ga2NG(P7g7$)yki<5qE&e(nk>X z7JF-RCsKkTQxkL=wxtazrMy53docxmC^;hZCQ{(`Yt-h%6pUg>9?fgK4T2~v{|oEs zCqfGFWx~Ncfwbh-Lh4*0Q(D*z5cAY^QDFn25Qp@h5Ey1;X0)prhe{};A&n{o&Jilk zGGqKuK1qH8@|+I7YQrT96~5H&DhaBXw`<_0H@j>eZ72kxf`}m{3xeX3`eIi){R8<& zJ$$4u%{?V@0ry;uM$c30-_2MtEG#L~7OK(SqvTUO$I1&*>fp6Jyg3$>ct&*iNR(>9 zgt&Ctix&#Rv_2~&#HK$*#6h)?#+;o&HgETUz!B}z9rJwUg5Z~5V?Y=MS247FrFVf~ zc_-9mSqC5^VqI@p>YWP!hBq&cdBHej&usZ@81zq|%o|ccH|f6c(*WtF_QP zJPt@g1lU}-I@)|<5yC|Y6z$=G2ZhQzar273_jD!s$7WLXFpMOIb5=jg%OqiN#?Lv8 zs}iXW4=`fdtF$C2N*^S0scFDI`zk52NO3k~IIWQp0gW0AQ~Xr;ugcx9ByqsIBb63bt>PvH}i z-q=B;5{LfU)67-R8wY&zD(A~9yUHO^#1&vYG>A}6wu>d4dv&#H6)*Pc3hhGsMXz=A zReps&jAdXgd%2{guooX#fml3RCz!CW9c)EjUwWWDYOJCi+=(WYmtUeU%*y+&pQ~?D z${bxC&E|Ttoj@m^V|}yKFSLSfb9M}JOvp=X9)+O5W;)HIf6~`g%(5YAo$6ib75TCX zX{#t9n(mbEcSzIqK9Vv9?g&%a+q&^c>MEi^r(BGm@6Q=99rBgxK0Rj^WK2)b^n$Yhn#Bj-aphdk3 zx&vJvR8j?4sEBGy&Rx5`_0a^!!X7ZgOyKe>yyKjKZ|{8{F-Pq~Q~5({Dx0Vv2*9q9 z7ltc#*3C0Kx}2>Ets&s@5sEbwsHs5#y`b4pd`Jca1CWv`xumEy&m1A2qNKhPE*!fd%Z~$ zJ!sM(idvM-No3-l9zct|xlS3wsM8ObU0|-1UK+9ZL@d+P5e5Yjnb$ZEHWT~?HG~tL z#)UbaA zIx1E=e$JMV3U##ABBtReQwUGPFs|9=6wV{dXy51%ox;&UXGnJ^Z(c9b%=rc@Qz6>E z;uP+e!c1`Op^tm%$|_hsMiLM!L$H?ci7o)m*bTtigvv?g4%V?Clj<2Jg&wD%224F# zXA8J7@NjCOq_A32UHJzlq1_TVi?rSeycRI9+Zv!<2Cww47&~JXDX5^t!Z7d6dQMYf`N6<@04Ce8_=_a>k zJP$IecS67l=o`OaqI;k*{bVd7td#%PTy*h@4X_cFumS+0>h0qfEC6AWfk~nZJS1V1 z7E(~*LMji{O{Wq-v5f*C$&iG!lE($9lSy$gE2NMYxpi#fj(p_i>D#Fgh9s%i+{9E~ z1IB6(49j&bmJti-vf?-a599NDDa963zNVQAfRnq~r4%&;Jc4OONP7|ukA6=|DNu&K zy$6zGG>I#v`6#3ow3XB0AGF|y)i(SG5LLNSC6te752)lS|8*rl|w@P-m%y#hz?18anoqKcl@P{OW*u_!@}ON~3D zDW$mEQ>WR|o_B;~2q6XrrIOjTZy>c4r!{6kksrj?gt$Ar3nS}8?1{*Mf?$k{MI8h{ z<=%^Q0-XYpiI^UwQ&^6J4W&^Hu8=^6#-(-}lw0bh6ZbNqFl}NuXW%8AiQ!nlRB2VR z^9Mv=If61Y%!2093C&7^yV)1gLM^;=!l^l5Ni+*+lrI!N4+;V#EOiY&Llc{SM>SOY zunPZLij7b!a`SkJb*c?=9p z>6K8}Vz4kE3h_7K>#8NjX$T38?Go0$U6$kF4I6{V1#ZHNsm4f=I&3(O3=>}pdMF<` zp!)167m&rq$j%Xh{c}W8^d!Ioa3{k{PrdvG$4OX3C@XwnyDUfJ4MysG_;q-8*8ks;D#mwsQ3F$TSLLr;v@R!V~ zb~UYObi&%-zQD7ldf3%D8(T=~ouOR{i!fw^$sus(Lj3Ah=+r8N5FnD-_|IyV9UE<- zK`!o&cjP&DDA!K43yXoqX#Gr8J)sE{<}ggG$zAi*yE z8Zc%g;uubCH*2u#ZvO9H)W#54U~@XJcw~Tv#Vmk1V`LLmWE&r`sbis1h6NNQH6cZU zrMPbce#8Tm9pP>5zdVlH*a#Q(lIUjc;Wq&rq#=Z`5wuE?up+9^!QaxPPT}L0A>!w3 zciNUA5(2?1Ej?6VT4cdl8=PeMh?CQ-TSSt=np&S7QWMn1G>`zm>q~#jxkZpm)68&V z9(0pXkUOi5t05I5!ns6I{wt(~1021Lp}T+$SEWzk<6W*9>t#i#QWYx9xQM+>1W@bk zjZ4i48CgxUO*VaPKb;@MaFge;JOYWde7)RyAFnYwR4%=iEx_JtpQUs4a0YurC4fbH zT8&yvOO4k66fl*m37_9!9>GUwS^9jCg?{*FqAh{i@l`s*W>XTzj&lz;h@|EkMBL8#c}rtvl)#1# zGbaYQiD}>I+pD9Ff&4@8oH!da0XmG5$Y~J%(5qlXm9(=>(mi+W%D4j-p1Z$l9uPE! zZ@DH_Ei}_Tis*++CcFbIriyX^v${+J5ruN7U-9iEWkDh_H!#G;RQq)4G`HxnP$k7L za_>XfLj3Jnw;31W*a9xVg}`*}LZEnU>7j|YiDfH^>UL7WH9>6DE_42G7LsXTT16)K zru`6`)=4Vm{4ib4tVnjZfUGvTElaXi4Cp#i=E{1fb7|U;qWfm0PG)H31&tStm~iLK zjV(RjW>n~Aa4A&);GBTtTH!pe^`^=D3A?yXDz~tVJGQ2RAFM)Ckw1tz=3c_Gw&1tsmoZDPopXgyIws?#^ zn4lHJ=}qSd)%6-<{fN`Kyq_awjP~L>i^3v(ul%4Gykc9(WH2k>dp5VQ5vcm-M&D4;ASx@bG;KnyuQ(CST2Bp=Uw3@N-Q&lL z#(5*dymqCqm6Oy2>?)tFoJ1R2OM37Sh+@hARRfiiFeXw=n-F=!($JL(BI@1&xA;kgyt5U(WRox31+Av7oM?^>@mPgMsr|Ugf zi_5VXTXG31LqIo5p~dMRbnb?00MQa?ov$c?JljzQwy6%2r)`m+N|y9G4FTpx;EsXm z+@EZu7VywG?nW2*tCimEaUt!sfo>oqy~%oC`3LBjU|lc(ULb~|~4hT27nNvIIj zbahqf+Q{1y_apyypqAW0<)3!>AfQ|t3o07a#K>z^35sl4vq?T0#h}jjf!66TFlOE8 zMCt_^Yfe*UZ{(f$J#kOv3mK#ef-wmI6p3U|$Dy53GTz6+NoglcZk^9lV-9b`GdtgG zhvkUIy|r+T#ZHIMqJ~s1sR*YYHY2BM_fK;1|wB71Nj#DJvtkE8mjG}CNt-tNm<$v)Gd%@pcV(`Fh&Og#4=?> z2}ez%E&u50%Uc$`))$c1bMMSEblhv3z9?Q8_ZW2mNsHcWO=$WK#A+~=Vw4uMSu}7V zLNEwol6xWO#c^*IP)(xEjdkR?kn!pYX95J(RlWPD0Ywt(zeu}kRE$$K@7Xi&GrjDD zj(3zVINc*aq5T1d7YHFGpwp_J=<8I^)#9h6v&q_xL*96UcX*f}EOWdo#dtNz_j0T& zoE3UE-bwA)fZPkF-{MmWNM)x8N=M6xJug$v-61aQ(mKwK)mTt)L-irH+#fekYbb$B0@ryU-qIdFK6ZL`kathXcDtUymWM@ztZzEKU{8%$rTGtr>otx%bFf84ibbkb@>{x_9o?q zU;>y8(%1$2V4R)eWM@_3AN3%Zb>ttYEh0f4HId{7Fod4OJ0S~`6%ma+6U}T2Geu%2 z_^Rm|=3u(Ks&jgd#?5Ye2uJ`!sCD6-)1xX9`Sd-w`fuFP4Nuk^#7*4LWEDFWH@aMktA4 zHT}WD+#xWmb2CI@=IjqFH$^3f3m?XE z920LCnHY=gyq|IghB-)J$x2nU-MM%eirTqo9?+5KQoem8r{m$)aCk}|&lhAu7b;3^ zNS%DUSwDtY=qO;{0r*f*D|v3?p(0Oe7d;DoMR6Ok6AKaG(?erdhmr0e zy0SCOD_~94#I$nI&cj3ESE})3N?_br75&2rs?+PN=mgDtFY%*!2LY=EQce#wxPM$< zY(8QmuiGHLJ3?Gu&%?fb7!3qC4&Df5NWdckHx3eoC<&jfFP;qq>?|}j{5sG$K+=t~ zIAyBD%t25+MeHk9$x(U7*;8POoPF;NIWSKjXa_PItrUn30S%_e+GQfLi%1WX9j>{# z%^+QvgSp`{V!XUFr;d|t8YxhV+aVH?3EO;*oub{l${+|PpX_qfpepJF3?+ zX}uIjVZFUyATW&E7)R|2g(olEjH9X|P*6gx&Oj!6ccCFkO5pg={@pA7Dh3pAER)pq zHyco)&zjOk1_pv6UHe1+_Fe}C15V?IV-SeYjf|c~u}bJHsM)(L-8ek84WXVW$83+t zR0dL9)51KKkR+{)6(hsudru+pT}#zth?ucGdfBO&(Vc;;FK{e$`%?CYfaV(w zoFToVh1C77GtoD42Nntr-#s(66|-rWxWJp4G%f-Jr9m_E_jklJ zgljo9WW>^n(K-T6&`n$Vt@0%XIH=*v&c$L&wIM*84T#rqHYG)&5=?KIz?|MN{p?wZ zCR>6+PML?f&O>r~3Y{7Z;ErKKy?i)A;6`po6xcssv6~vAX7BJ%26C-bOx31)$K+s4 z?{JYG?3zZ;McN@`51avH72wcz8Q?oXXhbE>V>~I;!H=(AJs*b{RenFY*0=E99LOwK8oj%*7?nTq_uD&UN zgYQ-+QwHv+tD46ZrXx^fBf~kbd8@H8&phw-dfltr!To|%JS{9fSj;>AfG*v2-t86> zd?vvFN0?6Nh_pTOJoIxnli5A*pkDR7om+HHyZ!P(871-z>s;8mt-W??H(4m_-Q5^= zGFV~vG+BIoVBZbZqZ*K4pH`Q20ZZM;Z6j8PF^FC^o#7ng6<~u#A8@B_L-9O+&ohv0 zEyX|=an_v>(>a!&K4Ad&yg^#khn)KyOaB}Ojl+rl-C-ae=(_&7ya8D(rTN}^R)lg- zpW~m%b2&pd9?)6O4M_OZvolVZ;oyAdG4K(pL~2L?TrKd_o+A zf_V{cW7%$T8Q*kM?FgUuygMi#fzr6D7C@<74^D*@PUAjGBs`7N0-nQrL~G)D)=`SB zwKLVP3o>)&O9M6U9A@yZ| zE4=Hru+q)m%4X&nE+brfm@JKfbW{euG$_y0gmwh#G2OPU*0hY4kv(lhxAUF)R83_J zSPYt)Wjw4|=2e6e=?`NlJ!nXu8b@JGe zMDd5kp9q!Oe0n3ToQ8@E@BmK2upZU=Ud`%{q1pbJFe80(9|$=0ZAvw^C*(OzA)a8M z>2TK+#x%VLd8}d6!k&B7p$^D9i8s(_YNYj!o^lLfSxaF=-CP{CCisOyF3nE-^ImmF z%4V$NBg~hHI%Az(5X+RAH`8O{taxMjYhD_|>7s}>&$+sC^<39Zh=c1B&Y`OGgV>=V zRNNm~p_F&i6jtEf2I?xVniNHg4~sM!WDM8W^UImUPEF@V<2j$gSH0(y%&o?$B|PKK z)M`BD4ik54z3O9+a>qxr@kJ+b|AQ-+iN^6_3W>FNh@*qAoDqk5cYhdav2Rec+`sXX z*DMNzf$Z(RYd={D>od-4|7|0}4EKzrqGC#kyOUKtsd zGyV+Pm@^IW#Qi|YQTCk4Vh@cS>nz6DX>x43qMv!YN4SDHSi#>S;ttN{qbh~7$1{d` z;+#|8T*Fh&X???Q5?2^EdeUu;z|0%Z-JU@GdpLH(YA`(<*u;o)-ji0b^m-o#iStnN zVHl+cGLn2VXMAEiVt$<)kLPTn$ak3*&^Ou)@C8nd#6wt9olLvvo3`-ZWhwo}8T|ur zl9CUA0b(@7f~oC)ef*={2Ov~P&-lB4UjOS~%-3RDREz|rglbLvmcY=i4BE&ojU;I`0rEJZ2Yt@4Px-O3B6pn zS`s>n=~UP@b2*oH-C8<;*NU%;yqarFVO5?2FO!w&#`s^*Gn6+$)F3rCXqsQniTLpk z=NU!SET9QSwn_~RN$p#j>x|v9{e7=JciT zz16@Z7Teu^lRP-(t@WMv`BS^|{K0?!$|-mUQOi^I`544=;5&C~VckjIU5eUp7vzwh>PZ1#twLob; zoSFm3IVzYt?cewn0n;x1Ks|N=J2@Ax-gojvE6fzd$=5DmC*Sb$ z#T?=wUp7dZk}&QoLZY8=i|TOq2Qf8@s0=Vb9;tq1i#CJ0e>it^-dqTj!`0v>T2Bz) z)$oh;*8&k?wY1iOD()evo_z#}>{i0Bm~(m&o!Z}Ei-u#?z9gcJ4dh(~ANy|7lBJEd z{Z_!QuRK1dEqwGLq;0BAWM)`wnhjtMtP!-i{JF#80hXd#Mu^;;n;T5$v)*;h<1s% zHnk*KuFVXI=UTe-D6}?bUzHyB2;z}9-b0VS;)Cren!*y`F&1Y3mif>Xi#FV!fKVLNCAyP;wrc7HA-R5z~m9MkAeNns zt0ZOCDbuTGo%;!y<_P0mrxPEaWZHX_3`V4B7v&Z;u(q-stB;66%BJ@8X;AeZPL+m~ z&1^`LX;UxggU%cBNHV^bM;FEup%-M17Mln|-2N2&37aihqd|i}JA`~*(jYxR`pAhb z2hpQhERbmbc;5ce`wPs(c=)bvW7P!KcWEGAT>SZ0A}3Dg}GoYpqP^}hoV%oKF}U78c%n1XcigcCfD!9W6+4omD!ZpjvAn!f@w zBw-2bIkyA`-bJ3%yj{3*K2Sj_>b zuzUg>u|B~)=$7gy(!LeUaI}+__rbRsayyyl5*|^H)#4ff{o6&O6j)~fT{6#58`7o* z6I)?;uZ6iP5czgLtiz@OPcNQw4ez+5iNmKwUg=1jDN<7d6Tz4`XCU-}1K&Jt1rPO< zv~R8`9TQn!1x^v#Z6ubm7JCVJtz)dqHhz1GSa+udeGMN_3NEMRl$@Ye?=RJ$SBbZURA+!F&M;%5w>GA;&vBWHpx4544>#3s`krgLZ`I` zx8evY?G!#~Dxu{>KBcgHO*qg#Qm#UK6q%+epU7k9XyDU zp@PEmK$+Gt{;83*Dq?zr88rdr-0cvXTVk52V&w4~1l2Um>o@XK1~}a)D46REeSK|X zM^t$Nm?YVf1+C=iOjtMb(rB`Lmde&Q?+vz}T5^qjmb==FSYG>?A-(4&SpcS94KWv) zPOW2TS>k5I-cF1dqaA2l`(a711qs}(nEf)R{OlD9eB+!Utd$T2m>vo>R0K?M`F|54 zMqEcCL||4vVP60$-w7C2Fhvd3q-Z(82{l?+qt+hQ2zU&SZOPN?A!TeMFTkKOHZSTe zS@HA$GWC9V{bda=$t`5S_FpFH2wwy^qeHXX!fx<(4a>UBBx6g-wn!W`8piD6;9HIs z87Ml71KT$WMdSu#qy0B>6k$v9PJfFfRcOO@?9nBUo53N>GIFTb$XJFnDHk3HQ~U&| zru{J{%WtVWQ$LZSj6xRa4mTBPGZ8VW&=fsZ%`e z+SvAKOO(5B43RH=NQMVzbp+B zYL5J%{W9IvVpC#-J2^26ED*=PV4`3%Ofbfv4gg9G$9}tJ}XTLB{eYHPDrIfqc8+G=T zbZbQU#VyOgigX4!A&QA~V$4#UqK?k$9FkG(7FQTB&}8liw@kHn`>6#xxL779NyEFJ z<`@+Zmrn$*F-64=q71!|WJa43yv*L2(Ka%e+a=Goe;ksrcI_WGx|4^;DrTk34x!fo zIkcv`soIw8_aYlWKj>+!`ctFhF%$4p`E#AGQ_JrZJm)d)Mbzwx^M_P`Vps|Ba;A-5KYtVsh`L$Ad-sa zJBmf(O+gxOO!P@_H0i(H^u9X7xtd*9Fk=|>O;?iknBXoPs2kP%z?hloN;76=#GbPT z7kJMO@Y155H)ww>Zak{ZNf@BFortRxs~*%Q>-~wKLabQC9ky5E0t6~&2L~%mbgmCI zV(2o_jDO>ZQ5-2o9B?u#kUdT7qbrN})fXf?rRk$oo zA~dT%Eq6h@hSav7<_U?%Qbt3u_ic*sX$A9kEX!V~p99y~Su_xI;E-NO>_{`K`OX55 zjz@eV7dbFS{?txT9qC9j6A1XG=T)dyEQ{+YtNeb(G{Tm9^+W<5t&UO9ucwttt4Z-o z&#O`T4$RUlvT9c4BSj;fI%Qdf$GlNkY%bRNqx5rnPMH8vPFE?bSMsqYN47&_<)Brn zN_3)^u3fXDBHV2>Q7dVa=a7lqn_hxg(Gl{8^0iX={w7koM6euf@HivKX;7&Iu)vzy z0{)g$AxpPZNIqKcVbyQk;1Jz_w0Wq`wzGGw6bJO6W6@yl?1#?C(Gr&C&_lukZ=5mo zUye1xrrZh|oF}SXl8`l{BdQ|m*pYTavi|8n!Or5tgDPNNVM0hH(cCdWc&ssOMYxqf zu&0Y1mCcp)NMIQ_A(iN+|N)_AASp#39sb|M4K z`FYocHUp6;zq7cMo@IA8=_PDhoEsU0kuU^L?;xQB?B*tyVwska!*vsMQ>#%A=zYxX zWJo|0f!f6q(EoxhwR}HbM3O)80(8W2#UFxwit#iE;2Id!5*dRrfPfjD%q8E^3P5|Ik#A&4i_9L+P#)Qa5Y10RW)7;CR*+gtz+EDeJW>xsDj_DFr>aV& z7y%XNI154m(ZK%lb)YcvOEgiH;NM4+7s#mWpq&PI0i|H9pDfU5Af!=h&Dm&{Mipe@ z?1z)fNb)AE(7yyKCBzQxUDhK}XJhl0or|*l*d;ltk-v!o4)HgU_DJY;1Vb3v(yI~O z5i*!_8eFnYxZ2ac{i=Pi)bvsefq)2k)IalAeQNs`TE7P~*4A|BuNQfz>a>?pC#6O+ z+Mf3IQT{t!jHm1ur8pxWescF^b>`|$MC}HJg z=0vEdNOMG6@!!X)KqW%nQnlbuuvQh9;Hkf%5@Bm$WJTkB6{zu4FY3-BFTxCKfa-)G z-qB*&GuRIzwYNH~2w=aziF~ptFbPLq4JNT5Y{?+c3Rei*>cWrs_QA0ji>MdU zXkryLvPgHrJml;$l3I^*UQ;yk2z7b2y*o4jFj}mhD*{6x1N@2bk?|KnWJV8ZgdDD* zmmtsH4L`S?wWJXCa6D%i$YvY*c!K;FfBeNmk&}*65=!-=*QS_zWwl`<@&gIL2 z$8UUqkcNG`+17_CH*b(q7v0T@;dfS$-BtD?lU*p z2deh6wh_RvO{p=DJ*7>qIuIz{>L8v^=hbcOZL~U`FBq~{mF2;o$dUeC6Id4-yrapIOsn^{UFc5Oc5`k zf&OH_B%(zSk{%+i@AV$yiUTBq!V0M#tUq**HCNjwD;Gu7zC$ow{^&cJ>d&)~TH0^R z=y)`NRq|Rme&-&E;ik8|o%vNRI%$B!ysMx>@awMdS4nh&TBRYUip)p`#x(5>jY1OV z@&|CGAh9>a6hv?Lna_NU2VmsiQAB^T|3v~RHT@M!^Gh7`pSi=qaLJC7P@4y>p&04Q zmgx9U>+i{^NkUQwGc6$!AD=LNDY_Oen=a}0#~z@hlT4(oKQzQOOzD)6&vYpTkm@n- z0(z>y2%vqtP+e)-8?p%}P(sJTy98RW+=>&I63a^9`vB z|6ZDD&>Z`#OvA2#*DVbDKZ=C`GY_EG0{5f_0(n_8@K-4O@M-;Z0UhrtNnbbu`#(hA z+|&F50~vDvD-3i;(^^9(qnA18K66h*!-p8|*%(ZIb7;+^y)dJc~0o`Czsv-by*5}6V!fBh8J@#;Q%?P@^lHb%R6LLllnT+56QX5XgnNn@m2eKGxnv!9iz zYOwMC8~FGQji1UUiI3|Px9WR;mye~4ovY?ni}YkRY&)s{m83HCNZ8!Iw)qsW4<>%4 zZ?c%kU;j6PN?JD5L9uDpVI>UIhpo&8|oj2vmhvgJNOKs4LGtf@23}DHjl!)G^HQD)&GKH9vP$>n1|Dp?D~gN`_>rpU@;Vi2KgP`)I8eJ1 z%nSanaNfy!T~t$rFk9?Lvfh|=DUQ_B7UuMK&%hsIZBp2&s?{6f_=(vCg&*R`y*(5s z)7Rd4cvm!Od;Xq>n2FEWQOFyMFIV+JIV%l+uYZgI4jPX&2Lsu{#=mL|AGhP|; zf!d}4{~+nVrvF4EOH7`mTA%ghvCw>b$m~fuOn`ARUSE^-5}hg~5TC>x)?yg9C4)J^ zxX)Yn2XD6HIJ0?|T~qBvjrsSlFbhAT2?x~>Yn__yWx{AZzgL@G9*xOoHFji}19J-O z4?v9Hr1R@q1lM1FfBSv?F{-lawsc}H%)Foy1<}#uLR4 zBIz%#v+^MFng^=@Ze&JN8(qlM>wl6N{Cd%O!63f!FPRxzkm__+Uh2&Vev{Z$(^Wb7 zF3j<~eICrlfA0bg3`YBsn)Rr!Fu@QmZr~?9ie=c-6_&kUR{Q>utQYV1A)0Y<$_sz+ zth|4pzj-K``0R}KQ&|P$$`95%Yx0cA19hGq>vUA?Y;+QhgW?nYq%hYk*mQ{ zBK@n&w*SW#m|G9#1jw)EXJoy7sg6H5Y~prJMh4rl7brFv&HG`+ zJwEZIkkbZBeT~ zB=vkyp-27O$SA%q30x2V61NXYeW#Gg-bV>ejfwa-$GR@=;w6P|PsD{O@OBS3C3`-J zT@pMFPIL=@DWo6gxqCvNil)lIzmF-FtepOBs=B-t{+k$1Tb;lNN4#=XL>A6oT@3IE zY8Z}l3RrD#JRKCL2kzAV6%+#J{3#u)7jU*}Mn?7FTfP3RRmmO`X&4uA%JW#g!0n30 zODR=EUI8i(D~m|xwFpVQ!^l+{F;-4;w`L2^;g-KRdCvGf?WDpZSy!A{tYol+GjRQD zR(?h1AH4h*WX47JZso;oVi7|z+hyC%Mj)@aPiwzn!Ojah1JwC1>{f5VO@9~+TUb>D zhM2KZK3Qbe!V{$@eS=bZQiNIleml>{y{pFyN<;aUI%s?kRbMHycYbbK{6a9i+sVi* zrGswq^Cp$+lkziBM6LxCxHRw>XcUc*a^qXGfHh)>GNsB-LO$R%JBsM4gxRE zej8D+aiZbdv7FA-fSELpS3(OE>vIBeGC znN43r3*l^#cz!_kxPJ-AP9KppP}a>2CT=;@LKeR#lHrMGKEBTNxEp?CgIx*AQhhP< zuUk~;8qA2@l`UCbS2z1qj<<(pkNF3n-)LlfRNb~YSoyWW`M9_;>$1x#BiEh^hrLys zUGqDMEW4?bSUMc5@A~p^h>Kr1Lz`38)7kL)MOLsC@u>(Z9`6i>-qy_eX1i@~Jz>I= z;X2vj8zyQiHh$3fiQ9+cxbhL)PTu5cJXU=A9g!O&Ijz&*^ke$eMkwzX?QybDKk}O^ zBd0eyTFh6a*yb??^;hLsiB)Ed99A(#i>#nv)vq@yaiaz=IDYw6>()V) zx^?GquInkEbmBfXix+x(3>ccR3*#kfUoh(=kCYa!iuR~2d~w~QG1ha`HOtu>jKOZF zCuueQ&n46wi7RH+SsIt}__bWS6e=#3viUWISA$vv7q3Yy$7%S(CSom=QIB>#o$mv+ zxI^{%V2X>|HD0BmnA@{YaWdH`8&clcc)E-G1i}-Ihl)83pL>X_|D%2%=2*a&oUjUPF86CP!>I}U^WRP*|eA*WSWmgzS z!DX1D>js9{V8HW+Cf%1aAO}6wqeNL4oZs334C)_cXzffJgY22L{8D#;*Bfp77L9_m zBZtT&*%icLhKCXG4QY0woATPP{rV?b;U-WK8q3dP;|-C4eHJnG2{AnuNoQazQS_JR z5ZiHr-*3DkZbE#5263KC^z9nJrwWv>;)@gLVbZDHo(Mt8jV}f?Z@jv}p$mf8v`#-g z)+zCC))wrWCs=tmv2%pJO-6ThaVXx!;yA?()pGPWOk`{Xm(iH{Lr%3ytEM%_~oQ)oams9IHv%!REN9rntCK+M_AeWN) z;QR8Ij}!4EkAe3h#_-owA{$Ckz&MRmc5mxI=q-o>UbF)%!{}cY1X0Yx_IU0xZytLV zw-fnPFD5-?X@%fja_0?~HKvDdVoyoz-oyM^Z*_T*R*lWNka)M&4Xd$RD6S70Z((jd zlUDI$IUZXd5NuZZ;Pd*#`|+l3udtCS8!w#2K+N_cdX5LS2JBD>F@+!J7curDAS`ZG zuj@&{Vbd{2lm1zj*YZcl)uxFxifDaIzLQwRNDV@|9Y)TGDDlwzpWT0kfx+MF#yXst zN3(VtZ1#R1yAYrM*409uaIui+`>X$k8;UEC-^h64KpFJrB(d-4lukYE2wD*@h-A4h zaE`D2NYU4k;!jNQw6@5_%9=AxXD+SZD;Ubg_>zR9Fk_|MWQyFX^%5;bLSV%vkQysK z2>CgYpci4!5twduvT++u#i*V^n&;Nmj81nx!Io3v~S?ekm^vTMRVPw0lN zO?pD9w?jz_ZLsp|lBz(pxH+r5UX%4-N&J#Su+OWgq6y+;FE2Px*VqLm@4x!ef-Cdh zKRxajpBye2Rmb*Q6bsFS45AdDrre6?=?`wngHNq@kEHz(xFp#pOwMjAQxD}y<`TB4 z^YSm;;MIg7^)0VBMD$aKhmNq|>%~HoeSaf1_G-qkZ;+)r&;5;OiQB*V)cLD3(qhKG zK;R3lAQ=BSA0T{3f>mtl$$d#*P}H%I1mk!Ou-ZhuzP!;Dxd(_kQ{a|uq9N%-(-~Mx{k42`)}E^6_`bvK+#$=3;~4~D!Uv{o^cl$@5;#kUWQNUaG=Nm&843RenCaF_40 z&q(NowcW5w z@Dz;Sf@w%l6#w;Po_SEqVhcuaZ(rUObUZmk9B2eO{%yBtS(yG&0I{eV9(tr(Nfohp z_O-7M=?$`;-`>dBA|;wEJ5oZ3Mya{-EsYez4`kirmQPmHK^PaSq$(nmM5*_GoAzEX z{Y&vVF4j{9R{(~&lc>3MlwL_qdAu7!-%ZEMu2b_( zu9#3EhI5$nID%n=MXHEUG-(F*Rrl-E$c-pIx=hy**r%t7BI%Cg+%rRl*}}s?>V#1g z>rfu=@{oZMEg;liM_V}EiC5?V-(Z`?u% z$jW!Did~QTrKtbn7J)ocE`T7X6meZRjw^`SgnP(8SnR((vFWugi5I!Zpom(94<4;s z$oZh5#%MgexxeW77YvGLSkUwI>`Dfau?sB>j~>K^<1)b>lB`oGW>(IxtCIcO#20z5 zV{{EmW$pOl(96`&MF#Szw$~^e*E=qBOWud<=r+6aO;40}=~7XAbvmA&=)ZrT3Qk=K z9=sxKwBQ4@kp@;b>EcK}MAs!oK2Mi9N&INGjn4#hmYHPl>r%7gmXd?myk6`MxYpuV zdV#W*sLZBxk;^#S6+Z(pqg#sZik|f*Eek_2aRnJt@u?ZsC@X4%>$h|ROUntTY+2^G zKgCgae4%evr~`d}O0-t1G_*L8lC|~+w{tl90iU{VrKr^UPo;9!`Sw)cA-0YS1y{JL zub2&w%&Vp|G{k1qk%6a8>gj$TMI)gAkFUla?De^!5)J3;`Rl&xHg@0VO9BNBnxo#s z2QL2SFGIm|8ElmE?iTH@)R4cd^P=>x&j|g-jeJ^SKW?3t!VN7+DSYZJMqTq34#CFDskc{8q^$4a#65T|QWe!Ur(0yjz7o#^cq_(0=|8E5vbQ!9T6 zlF{-c-tj}zuB8n;y<6Kx{O7#w8j9R!%$Mvs3=Mv|m4kN_OTH{-D%y^>9OXb1?fv68 zfhcc1zyoTv3f5mP{;VAgWJR&K?=iCTR8T<08Dzcwt?@5La$r#&eQbF5cx-g_6~9a6 z!plxxDJ?&K?4U5mqKurX@g|`1eDA-^ZZK+<$=XplLPeTOD&JKP&T^Yj5}bHD(Yb^1 zNJ#rdXdDC8){mnm<~d*P;>?==P`vnU{C-*)DVdLHfC`+x6+zW9bzat9cGyKwt$Eu@*_f!}AU+sU$Fj6N< z+=Qa?el1qqM{<9XwaRw_RVo($qUsOyp3JJywW3;F#lN}rK^AeJxV9#<@XG3H{~+s$ zUAT_hziAzA_9=opDlgSvlfh$L!M^sbDR@Pl!VRL7Yj+TJElRit;{PwB~icrln`%uW*5KvutSq0uaHnGrAbyIx2Ddwcdh*3 zJDNUECx<9{8HD{6n)ImWjLGD?MTrqfxMDr>PwOzm^z^%7Bo?uj;?pok8B7@zeL`C4 zya441DQ1MlJgnftu-zo<;|i^}@!ep4yN&N3?{vPK<}01=f7aHfv^xlXmNmzvEZ!GV z4q`i^cYrnpOWKcjbgBd&d) zPct*gB^arjts7)FN&OSQuW0=+XG*4`8-4MWuSDVHea+KV0!s8w89F5&AB6sHw~caB zPC@9;0=F^Lx~6}fnR!jANUqCn`R-G46m9m;fBWQ%s6fU%p2jUO&)o7=Arb#NOrhrE ziM)oy6TB(g@=wuNZHp^Y)WyYY7$$qtw=@8s!$-p!!R9q@A0#fG|27YbIYMv03wq~! z$;YQhb{{25eFq*g|4EvVJtGY4+t^tAGC>ZT)Ol24iBe$Sk>8K}l295ZqB59L5VCjl zDZU6@<&~eD&aB-jx;iqSC^-YP^qxM50>M=hA7uZ@zGFWSEhN%)SlU6t2PgkHj9m|% zL80M%s^pCGFR5a#M8|xI=oF%^VLHt*y?!|UAZz8~#Q}MWgpw8U-oL2&1G^`){wC{n zS56_`>K!flev4T+TXp^TBI|`+dF`KMUE%VkFTNq`LI`mQZ6PGH^)+1;e*KBfUCK)4 z)9-wPGSz?m;@I`&4~AXPwMoxT*B?i+e(gi`tv^j5Oj^`$Q5U))sW>^JE_*CuEvk7& zT?Q`x_E;CcJicvYq2lNgR@c(n@O&7lK72ly@4xMGk%=?%JwtvEPYF6tLpEv6*;z=L z79$%Nt3^0^X4Kb8>&GvH-brBNalW(oqN2$rrX4iWD7N`r;+G7?acH)w~?EVz&PHOU7vzha?FB=tu z!gIS#R;la1C1TSdzq3n@a=s;&e`0rH*SB)H!75yf8)n$VSRG+tzBm{c@LN7?!nBd) zT--lT$h>aUP1N0iG9AReju;O`;VNYVl*_KR799fTAFhuZ()VDV&6&Qn2*;vtWy}?ne?y=i8*w6V z#qH|wZ3-{tprkMi$`l^XVba&fQy(eI3lfLDzN!!~M&#AyGyr{489yx#tKZ=KDycCG zLFktgBja2@WNgLQC-MytYIQa2N-A?$$%qkE9$pgp#(>S?yB0G~;e7HjiNcObtgnT2 zWg|6zjDp-1>Nc8&f;IX`UO(LG`$*&?W)KjkofRi+H=kVCZAnNF|x?i)FOlURNAKZ%K3 z`1#Wy@dA+JDl$%17XKIV!vB5>FQmbvaFWh&K_R0JFw&@w#1+Pt*|z{N{dS#Qy(&K> zpB=c*-zZvtBf!gu+eb%Pd5mJ-o)v~lpZw;%o1uha7b7#nbW+i$8eyAF6O7pRFB;+$KF)K6?0U;rIzhJkY{tKR90n*@&(CobDt?0#Wm!y49Ep_lQQ5u%V$yq*T+lSlJ$y`qTY1gQerb}{c(@DacK%N` z?wK;1i@S*Lx|MwLN@5Admr|CMsnm2yA!TZCXM~F+oN&Vfi{>#gQp3G{*G3`gJVwWN1&iyqOw8Z)M2P&d6ZE z@p=z?j~MgV(7OAto-^36IRi5V-r zq-)D~yvY|jmAER+Z~O0^`u&1JBpF@PMJa3di0pJocR)Fv)ZW5EEBgV5jxx6dYi5gs z3f7Q*K2p|%8hFJJP54h?70zWKcPXoECqbt^f0KiG%7Se0e)F!lSUem|S1Bos1uAHC%DWZ06rZvTq1>VNX zlPXBuwb|8Cc~>#sR6$|EMF!#VvNQXL)es!)-}Vh9#q_?=62PdF26-*HczsX>iQBY% zK%ALK0NySAq+F3!&woPWC2q&dacwIVL_S5eVB~Hrd5k2Vq(rq~mBieitt8GK z3X#7>pp3Z@usSF#6vf;ePujb>Da1>t)Plm-IbBG?y}L*+h`5UdiPwtaO-zHa<>9|G zu{f#c9f@5d^id z;o~^jI+ceG;#^J>-&R0ltO_~KYp*3PT{9v?+l{nCQw?!JVYV@WW@lgg4d%4OlC|ei zJ`cEzee#ufE+}=zv3%m*9IA9BEb_`su4EKDe(^r$hS@h0|2t;0Q!O56zS6YrF;C)N!XsiICtY zez!@Y%_1ADQOKkBO-Vz5?7{0%wG)Hv<%fKUH+hxSiqhUlY4&i^*`%%gNZ!)LMo z1t9DFZ_)a~X*_rtVt7&#Aj#^3D=P6rwa5}SSP$qQagX4Os?X?Nml15^Q6yW@#ncWQ zu;;_|@tg%=?`rX7yaho8ATl^Bm6R@UlbLEwtql_wo(hLIlISETsQGN(h|5Zhv-6rnZ7>XP+%KJr9X8EX==9f-O! z<|{?rM4y0AH!mWCIn0qps)?jBXo%9L4GV0P?lBM_r<;Z1&D|KQ*fz|1jUC7Yi_xKQ zZ>0r9;)GDwOk`tw#*^+(INl}X;SrbcMd5m+C2l(#3lez_|19M?*jSzwrB-z+4^h3P zPl@>p8{kOs2bmbDbPFFswp$-zryiJ)U)8$i(op@hcay|bZ+kuu3VOrsWQ-d`ew^06 zEgB8YX}xSCVwpSqpC3m`1%-OWseS66(2C^TFk;wbO)(#~{K-^3&|@ghH_SXk+V6L$ zv;C{bvE7nVa9qVeR4W zl14n`Cyl>dLrTk~zkkv$r9BcEyOoiJVZ(s>I*lLlz}GL%D&}V-$!f2>{li^+=i^^O zrcCdE!-!a>*t1cF(Wv`E1%61C5g7wUwsG;Fotqc;+OlkzoujIx3lbTUdG=#p775{& z!yyJs$;daIgCbjb_T~}qZ680oikOJy<26z$D%cyFy=3@?IzN&%0gna(=0` zA01-M>Zr=7mf5~CQ|k>WOz{^pX&+&17h@3#x>2(91(DaMbvEhIu`liVqvna01B=R1 zW{GocjCpqzq<(#KIi6;HDf@@d@hh3cQobcKP%nKB;>kCt3^>=PRT6pd^2e8wsyt!x zga&?P8s9YIPGcdjXvDg}291T>|KWn>(I}hrF&54-fWmcu&XNfe<%l|Q;p$Yb%rAlf z+`v^N-l7S^ws#{;#9swgmTH&SO(vNupzD}INoPp^%H-eKNex$>okxA# zie6&cgT>~kKWblNCDAG1cwF;mKIhlGN0b{1!yr7*LkE>HkLPKZ?34+}IIjp}LL;Uu zWq_3C?sk6}w5513iJf#@3U-D$eY_`u-jQf!(A8GBB$M6OQe9vDEuoq9y}$Mgb@ zh(%d)lRQI*Y@%zU zU1ZPqeAI2P%xqcyO=Ag(-Ih?OJ>8S4TiT$-d-5`ZE|~d}*-g}TH38zQv3J3RBZ&8h z(3agI{VvKEkUV~J7es`s6x!%s;2CIPDv>rOLX=7UCkE1jD8Vt+KYhzcG{G z2g$JQQ#K+7n2&yujhAOQBZ>(?9+7$x-Zw;kbZCSw@rYdMdCzHXH=+P^i%KdR#MO+T z!eJXkiw4g*Zw44KJ^pV_a&;NN%X39v6-kcq7}6R9MbF5LMX-O2PyZB&)9bkFp8^um z7`r?v3jM{S`Nm6F#7nytypaTcCWJ#fp3vJ$urRLH&K^R{*bHw}qLnaL8Sxq)J_AW_ z+UKcd&u~V2%p_@3dPIcwDa<^w=nOSu)fRz8jM3_Y$#@5{&?s6uU!bYHmE37|=sZ8& z_c~n*ED_8D(2af%x;0gB{pf{Q<&2Cui=a>`;7)S+`Ocl|-)Tk)=_4<2dPy+M*G)Jl z9m{Q_zJ0(xWK9*iet(sUCv&HM6Iq(P28z>$VO=}qsUMdn=cQq=CFn2D%cPRBsJhI)Sq7K5otgQfvBe&JP}eq) z`Y9Jbt?DP{O4B>Sr1qW%<(idoRtcPxd4x9_3H@E*RuGA7{Ds^}V5#Yj)$RKkJd;1~ ztX$uhf|t7$WwKIM*S(SX$8{>`d>VOITsRT>hrM`pGpXe`$;G-2#-x)QRu|c~2XnZ( zmml@wU);-UQ}((lySU*uOxcC%+&YyulCvI`=A<|LCCp0(BIl?om0i%~WHvJA&0M zsI0KbpU519M7*4gAB47;b)@x!I>H=Oy5eMk1-%5THTV3gNr%kVl^IFqgG8HsMDnAd ze?teOpRjk+Gv;uOaa<8X=!0t9m_|jp9K-6i7*AMh;T7{e61vf(c$*`XzlvB?g%XCL zY;s>9giR4<=ksJ=O!=f`y&mN;Y{eYU?|NKWyDYw}Y(O4j5Az{i2*-Yh&r(9&*cB;^ z>3@^2m6TF6w~+8k$`%b?|1#)y#`l`GH6)7n?y{wpfwD3ODcD{_B` z*;zvA4U$B@N&4%xDl}=9xT0{s)+noFeyF&W^uJWfwZN``KD6u#=uiFflfY8EDcrk~ zm2b+Aq*c5~1#Y22K+1+mmL+mPNjwS2Ozeq){7)OAQ_oNlR2pLQQP z7*3t>DHtf!m3~mQev`6j(pi1P&xm2KuKU}0Y&&G{J?S0p+P5+ooFGn!bw_xU|DtDd zGnXPr!B`bwF_eo5_E&_IDl&Szf;xH}Vlq+Gf)O9v>Vs|)LLrAk2r0@Kna^L17FzPR zfewK>x*4$;3E{If`cuy02nr2xX={d}K_YJwqFt`nOTD7=PRNB)Uj2+GI)}YjQnH(8 z4A!t({JzIN@Sr6S}yL2Twy<<-Kzq-!70?y zGdXuwDroy8r-roY*9zv7$Z)RXj-7F1+QIV~t}wEEJ2o4!IH~gk@EaRx|FYOv%IcO+ zEhKDx=|a9L^nEDeIHt3_^W8NcnINZ8bopgSVU@^I=RED9lRl*U_UU`S*@u4^VP|a> zaXbFZy+?u)cA;4K_()-tw$#4Np*ZH%BC0(R`;9|!(^*64i!||GrSu`xPpWK~Zr!{n1d^E~ClX)J``LJ;i0Q?--)OX2>fT;xMjWq-^YevPYGhqYYjl4pb2o0R`_>7sF@szBbS z+iiu3EZt5WC zDsz9*hrr#_V}c*V%WGo zA1qlVu{>D@Gt`9cgFlf73@{~YBS!wD>L;N?KYXhoR$@M6$0u?9#`&n$Oke!;U(pz` zz3-IZiUkr?id8VBkg7FWTVvw}r;zNuJiCCiN;bdyyTwbr?bn`JkV68J%3T`KWBJ6q zYQhL4v`k=%IsX*MzFd~W-i&^cou!b)ETdQF$z` zToDr?cFE*EBAGFPITi`8V#G@HiE>Z|WH(d+KK;v*keOgB*}%w;Gq4??@lCWUnP&EJ zv*C>ab*tHR&uovrsJhUVbkMTW(BnV_cGT8x?@Ui+J+-JYtb2)Q=B_ykIwGt{mkX0! zh@bNH&HD_0h8aoBPh=@Uv_bvAkoo(>P#j@F2z@xK_FAoj5}}Ki>64bYM?|vE$H1{Z zZ;UNmu_VM{N-12=rtnfo@Lg(}AP6W$ZEMxVvp5MUYp|X~{iMzr>;Hoq*vo-&2+p^8 zo$&v+E46aytQ24SG$ZG&k9ZZtcCeg$^3L5G3mcn zI4g3O+PuW=^$t{GZG{phwI7e$n-0eA&bg8^ttJj9-_+s$@)kmNyxA2RKZG?dWTBg5 zZy%@nyLC0w<7kn1Z6y^d@xs0e33#*2w$iaTeYK5sNFWQ(zD`y#@SwE)*8V8$3x-QD zzj$gfve$;Or@8b>2*x;|o_&om;u5QB4@s7)^HdpNKkA|U3@Vt&HBpmC-W#ux?)B>IH1;7fxrS9PFL|@cSg^YtGH5@F`Ixa#ni{dq ziKploY?#SQ%og50;~S;Hc&QuCDkgmCALxj(+N!rz2odSwv#)>lH19Y#|DP^o3YHN%`qfBIxaq^>*!_@rXj1 zh3Qj!ctf$3Y5?bKqp{E+)b(VL$X1~5bwZr<8*-teRt8u^u7FC-|Fk#%4Utrae=D9V zHHDDvvj|HKMnhwjk1LpKF)vlX+LOX+#V4tu6>aDA=N4J$QW_qvQ#Ks_J{oqx1&IycIDn_To162$WXyKM9T4>FCycl zzj>aS1SBur8=%)yN?{~LWe*zfCw%#B7WVJDGp4E5-@r4GOwoOlu{i%XM$#|7Yjq69 zmlyNqHe4HbC)T;f<`|>#Z&R|>XOwSwcq3mC@_7W?a@MCOXB9OvHC`FbXO6r{OIU@V z!+h$qu&g11CpPDlbKzLNzWe5qJ};Ba5mrM9EwKh8x7wS)`r<+Tq~wIoLCVKhLoWaR z?oTfjLxzQVzeCo$q^$(JAIJq&>#D2Z?Yq{rq%Pv#-`<`;;w{RuR+*4MapK-9m@@FX zgDFEB1kRp zS>X^7E{AW%QN@ta7Z`TIZ%MSDrxTOomZJLFPZ-#}trc9Gg_&7atQFkc4+@`YrF#Bj z)Zxn{T;ar`Lx!pE|Mt@=seI1M4M@MNC&VIB!g@?O3mQL`3I+$Fw&38vj&QkF?6jP4 zJ*p_qTGj3!bRFP02Fy15Nnpf*$OMAtG4hl`7lzIqgLGG?zFaCu!NN-HU%LtUkadC7 zhD2K#vj}myHg=cCvjrnLv`;wRQ^6=>VR0P+o)vMd;$xxUZrf8GckC04QJ3+X7lT-j z*8-33v_yu%2|;&630~_B8AG<}*Wa%oFRUQ3kWSEeUaI)-jl|D2dy2%*<%WDCWTzK zgNw|xzDFa``V+^NnVGNw=nqDofAgH`j(H65U7ZNa8 zHb>pe4>`%@!#FJ#3I^F9`vj{L1`jdfPwNdCE)*w)iF?{^I59+J{ncN`*HbL#cuFN| zu|vowF(@oIjXcXKPXul)T9+@6rB7pnqj>fs`tk~{l$I$L+$yDElN?tLFL9IInwS<# z2)02)@0RJ)X8WCoY#^(vn*KGie%18_a(J$Hh+MVJ+jj6^?X~^(GmR8X2z6T9*|)XY zVMTAGUcAyrkc{7YTVwc1*0GZEw^xF&fodVFlC|EPm8`$Cflt>C=_KzrHWAKLz6eY0 zr8?tyFOA4zeITQ;>bGvi`x;JR)2{Vsp;>-pT`V=O-?|rtff|v0#zgG<12L>O)yd0s zS|7O9++8ZYgN@|_ND^y1mGe8g?lb&LAUySn+bLAbi^!m{*tLkE5kD(PlpD`JPwJJT zd$SaBoI+73=Xd2!x$A6qq6_c$ z8590l;V@zGYZ^bV(T-ZdMxqjRof=>YX^8Rj@xy|PDEp_V{`hLli*hNVocm?1mAEn5 zXOq;Er3^ls5A^4gA2+oyxVyclwAcxU;jmxEA1Pe0E$WxCpzzXCF2w7rRhgxfZW^`p zOsG?RQuyP$Nc>S~)PutBuTZe*Padvdu6&9Q=WA!;uOu?_{aYrkf3Xm-`0{$OPI4;u z)d!eT+@t?BeptvUN0i0JQ92dpn^-Oi-2JBFK_i+P`2NksAf^Pf2MI86PYmNdO5!5v z+&UNe_%!mO#BH6dh$qWR3#ziC>O4|`!ZTdCSisp{{*uBW%`+tXA@1Va(=Tz`tbxCo zxKdd7m)Fj3T3QCfLJd(kXbcf6ky~w45>jXXo)^!R)Kj3~5Y1o$+6o&75C}r5NNM5`sA3HZavk>1B#!U=ke7*d|RzNP{idq@x zR0%|6;Vs&;0x9Dcc`T%3Rj}}LvEXa(A)O>EiI)N4>a+N{pD=Xr^?JgRwSGjH5(wq= zf9@4L(YTX%+672@YEK=NxLs@&yvhSJwwZ#CV+Z5@ZdfK9k+c8%|NYL{0z2?Id zZAVp|<-$|);=!XkLfjA+p5liIPpSkLo|0$t0yE4-2%rg&A{oVEQ)x9!vKCB^3JOEZ zuunyajSW$Dxq6C*mbBcP+)xmhdX)jF812b6S4DBf1}KHwlN$y>r>fV6^hz#MS|HXH zwkd}+{VN4wo}sMzaxsj7(}`~s6{yO6bupA}2(Dm{s;JDxP&Ng-7=BaF@2Kon`p7PZ zy5z!qRfrx6K@9ET5Z%cUw>CuCrfEZz1307T-=Ug0d3>YhD3h=BAkxz#AeuNb|BowH z#nFX0Bx~*=cD_|nG?m1_?8aPx-xLQqk~4f$i{kbOFk|s|_$&g;AW4sDV4%W}o0i(#)+q8S;Y#z*-;Hbj}j za3P{0geck&3D>=PFv?TNXs^&%6; zOxd@Hj(*YlwKm`X*o|5TXrhRLlI!j>>{?wI8^vUYgLPKnP}Hn>7sXhARfp&?I#zI| zN)7;Xy*6wKb%-v>a$lJXP(G?QKzW^!D?=-?kWAh_6CxWdpsFU@W@Q(XKc${Eaiq#$ z3AYK6j$#qCbg3rMn|q_9OS{e(QyK?3>)!>KTt&n#VfE&_7)rOz1}I|^lUEKx&4G%@ zn`ZLRu&}Q#Ii6XCk>)xf zIv%3|s9sc)(c?odIdM^xZB6zm%8F#~MzbPJg%@2E8R(YFXz~T>M)UeO(yjNXnT%#B zvY^>LMZJ#8WOOUjE;fpC_=0(gt!|6Qs&)eJ87KoVgTSeoM##+jV2^x$}!p=qo;>_ z3tWKo#ntb#3vf|!C-b&U41p1nW1`6H+}sO2HH7%&2ASW zZ7<>!O-7S5=Nq-h$^|IRZWkcEdvy%m+tLmy1mmJOD#dN1m~6*S+-I&sjnC$7X%|&9 z=E^obAOb}jB1!W)(I%t2URlU4z(H9hF2FI_;+{y@3AVT>E=qB`w}q+MLPeOuP2B-R zCEgb54umASvfb07Qb*B-D5vw7jArAgAld~;-la~n3vf{;yeo<<0}*U7QN(N#*Uv_A zP~FvjHlL+m-EEx|24>d zdXqMal)%(4v?<(+^!{vs%Hnoq8;e^=jtP;H0~M3@7>!m`p$!+HbSGVaGMQ+K;!ORg zV2g{Q^d@Z-7ZtYigqzw*<^7oen}>=6y0YC!chZI^vy&#H*`y_umHXONRRYJAZDuhD$+00OCllu(Ihja1ud+%^Q5+^^!n>k4 z$Yi34;wZgI7sXNL{!HOULGX>d?BpD~vg-g{*&d}kX+um-CeCAWGI3^2B(hdxiz$k@ zErQRkDDn~rh%SoKo3v3xbn2&Q-j+#ve>Omsz;R`JlJ2AnQMY-TjAn6ju9rVcchbd> z2~l;yaYb>K$wU`L=}o#QvS>$KXj8Zs>HWC?<$?uQwioG6+7OeIiL>6YU`h`AL36L) zl0B0ENmNFJNAsdLESR@td2}lG=Lt6emG|cYlr3haY%fg06p~{@Oim^)Y*^r!@(d?- zx`bq80&L=tY5-kPY-BRgye*CNCT$c)6}B^lyOG|X4NzI!u535bopd3#$;rf}O-?2* zSa!MBua%vNt|+!LnP}b?R+=SW=uYPTOyTaN_vZp+B0*h=xw4H3FC@o?n4C;xP+787 z(n)vH6h+oDibHg7OD~g&CW^f*O|?;!%P39Z?xpu<15_5bE8D$vCvAwy$;72kP9`pc zbSF(wWU?*as99pYH;#Y-{>nh^c`A&4Z6^3Dv&4ottGKxfagu{*ZHRjKpm~mSuO4X^ zN5(@b=`nF!^h!JrBHMVY8JNS>Z#_He^hnV*eiE4TaDAio$XZwgV< zWgC`kj?K0#0hw)DHca}EfkXE!hiv1LfNr*R*)&*L*|%p(w=bJn+LzN{IXq0Ck#3&n zeFIUZ4Sk4`IWE<*P144(RRvc*M0poosype6E|Ukd9ps+hc#jPqylEL$EbgKWa(bu$ zst;{eZICP=QF3YCaqgq?^=vGA zIY`?EIZR3u*&qq1Dp7aOl9d42?3sI6FE*PGF8eK|>2E5`SRW}4)10B&^r&FYzZQgW zS>EdwACu#Z`ibO44M`uOk|7)7q;9wmQHGqn2N%~whBR!5>Lp`Lp$W5>`vpzcgn}J) zZyNV@lPMA+IlH%8m-72($(RuF;D$svR$D*GMTjnYs5ub|-B!M|B?*xJSuQe`V-h}4 z8LF@}<&rKPMYwyG1b`)$o#{;w!pfFQ{1cTVblLO8ynB~Dba5z-yZUk%q@m#wP7jd6 z(j|OY6ydg9j=Ch@mdhDD>z0PAFNayi7+vEQu zN7}#y;jVo-&T_G;FPDp~MsoEfGy7Hlx2ZOO7=fyqB68(2rnw7{w!WNNS$pjguKhh% zE*Vm-2%o*hFb!o+%Fp%Ba=>b>v)q=;VN@|9mpzO^QFq)lv!+p6Zu~{Z-J=#jN%FkjVKQh; z8Eqz(v+i*6vD9nlW|wdZ+mcz15GmzrW7$jP+ce(7y@tYUg{I4L){hh9tzI8nFj44& zKlWj=4mkO7oM#z>u(4!-jfk+?_h+G`PcX=2IS^HL*vFDFHiB~ZFzK<8Die`#41=Yc zvIP?rECtiO<*YqZXu2%N!58fDS*|NXZI;in3(9@V8J?oj_wHN1d@*a*RGG1VDVOCy zlr`$^^V2?BnJ_e2-aZJpDarJ1IUr?~fyr{l#i5OIU&)pZdQ}DD-Etu6flIbvPP57p zdtOERVBWlV%3X-eYF74!^-xe-Oks7M-!_h|d>~yMTlI|FILZp!))h%Kx;V(j#&S_c zmW?IN>Ov%KEU7FOGU;QfRi%5DIzQ}Ui3_P-GWRT-$DoAB$5N^_8%xG?3n8+xY&vNI zn;fT%UcI+Ima?tIK1(!k^6kNkQVQ6|l2ly%m9Wo}oS7ip#>jI4V6U6NDeaZ zYM`6nq$+iWCd!pxRQ zMkovW%0-fxztHCPNsh9$!$wlu)2>WXnj`48k<=L(_r)0pWdhnr>Y0W1N$S3H^I06F zV`7udAnv;TXG4?`93P_cN?eGHc1yMeriU_mZ5(Bksq4&Z(>6o_>)c*z;T==09UjV5 zTTIgFj!{{y#w>7(%|y!4F{4*4g#g0O@gXX$Wl>3d_$Ia;V=o^LjLn3$7mQg&qPb4@ECs$v&Y z_fk@;w3-i5Jvuf-S@`QiR3?Tk}Du-vNC6Tw0Ohp zlVljG0O_)u;gi|yCK4||y6j$L$jW7R|Bze!OeBG*qUJ8U`-cpRnCxcggEG~8B<1P_ z`y}OVK%3o7^04TZdDhB8wNJ8<)16&*H&XN3NRkxGz1_qomERP(cE@HR{h&&?T$!ZD zT#)Ubq|6q$>~7~kqGqGoNOo*>uY+_?Qg^M}?CyHi^kpMCC@|QaM|54r>o8z z8%aj^2$1ecGQme&oX%^EAOR}NT5KfgjL1GonM8Nl-OB-%HoJ#LX*KsG2U%TbvwM&& z@HUdN8^k|Jxe424w{HKjksMp~(z+)(N;BFv)#!g0chN?YiEPQYdt6kO#AWwH$TJy9 zCLsxs?nzG4jJ9w0G^t0-Msm)MU@)FbJz_4q$@~ht%D&x9VHP0Wlf;o1SJ5`rX4yhz zBgwd#bOTa%BiA0 zl5*RZc^!vwNw(I2sH`>jASvb%c94CL%$X4&Z6v$w>5@&}SKLG& zNmoypf)~4U*nP!5o*}E$csXrM#6?|dTRF$Q4aa`ou7h5D3nWeOm zl&+_bq|7P0Qocw}(S|5X^<5#y5>URU4>CJTi7Ak5umDl{o~B4L#Z=k(u1K=dNtI&S zNJ`h!Mv`$NU{UiuO(|y$QHWeFL}iuRLeA1}fus*IJ4?wd?qq{yYNYS!ie$rPjXJk& zkz|6j0O=yxO4rjzQsxxhd(%o!(S|5HhixHmrSIv3%+69$r={W{t^jq?_p~9(wduA< zb}~z8BPm@^A4%Dl;Yv9U6JN=EZ#ubB!WQyg`kp?>>@4NfXJ;v=US=s>ktD(^xNVDM zFSC?3lG63GksM@B(Y-f=^b~!F$||>oe2~7U4>CJTiAKvdSO)2Px*|Eu%Fee%GHQ3~ ziq}Pw;`i*!jR`G4x>7z$Ptk@b8_#Vak6pcW-uNK1vy=plL*{BPw<|z6pUJMn)T#iB zeQze2rL@VGuBVTr+@$78c`Wj*bK8fgGD5bH&(inwL1t$u;~+Vz%zHCS-_sSzc~Ais zTO?WhuBVOUB6EtalrPd#v?0p1zqXJs()aX1W@jmC*(YUrw27dFK7=FFKf_yS4$-Z0EN*BhDJ>?|ciPE?lC z70FhPo3ureiFATDHj>iyw2`E3O3iBZE-Juci)1gelrECJbUl3}WlqtR@?Lt1HpKMi%(<7or+pRs>@4LBYm#pwvjUUf z#GzGozAci2%u>4dW{|F@kEF~gx>7#KsXIPI)n{)D`6zu)A7plxlJ!~H221*2AnId7 zkMXgQoU*rRvddW6EAG9~gMn-zpQP{UgUrrS&Wv#s#-uAilk`1p zh>ZG3zBlP(e3*}@Tu=Mn%rd9wO8G23MH^yzbLKot-_yP~dXA4PlS_7%k~D_OQrb9D z@|JvW(#QDBdW?^KZ!pS*zHp^{k)EOtQCa1#kS`DEd-@==vy{stJ4;FXjmlD*_hxxu z`sLmmhAk!s{g#JxJ>7f5^ju{_n^F!$O9IVc<2m2y_^3Qy68s4_yfkhjwJv_a}QKCVo5*;z^~0p)wz zICg59ge{WkV|*4p#>Yoe<`i8iCs`-7qzh3G2C{{mG8=)U4>CJT$;z5+gQb_gr+aVu z^rd(UR14m?Na`^@_PrV8z*kqw2k9yL5S3MK3;7@`WPOm?S;}R|&QdOe^gUgX93Rro zr;f{+^}md=DyDZqPPz)y1}PPWjU@#ls^-nba@J+rF33e%7&hU0x2p*1T4kW4spWRhN$kH#}FJ8UAw zauXu+%LL)*J|leDb!?hc+;Jf`(tNQYN*l|C*h)jthNwic=cV&lGo_QQ?Ozv3ia*tJ zYmz-{i`s>lyk@-X^qO(^9?n`zx>OI@US3D(l~NXbZV5S|JEhS~kUevGl-jjH>Z|C2 zZ1lykLC#W_yCB-$Hxm)G}WwwKovrOv)RRCHzEp0UmL@~D5v z_VW6v%l7hUyUh0TXspTh^7`eG?dA0p11PJ&yyIBk*P$-&w}*3atSnGebo&q$zio&znqfnf2_74w z)N3|GauW61Z9|;YJ7zW3~k_ z$&|lMwX}3?h_qDazOD?-6nBOx0G@R=PQ3~Y*f7cdD&u*A4#$XOUV`$#Y>+cW9(DdS zyulWhGiw{NK{8_{8>AE?oA5VyyuD+a^EvP6r6L`!{ zSLTq7B})#)eRLm+dFqsvW$VjHcC`9fj!L)rSkB4{_OX;!miv0P**A+EF>RhE>OyXTGhc_ESh8{>*4bhX(o7o^4_Ag!v8{{bcJR2nQ zz_Zyy;z%e=HbI%z8!;#K?wa<-)X1TolWA{EOkojvy?L0ym!7Sh3aHC;7?gb{iQvgQ ziJUn$CL`8WY|OP=3DL_*AEw<3NLk@-TI^K)%1Q_`ki}HGPO{v)k^=?Q@=5cYa;TQ2 zH1=7-Afez~B!}d<6Yyl*$;Ppf1-jO41jpn^RzOs?piOnF>T}J0M3Btx9;5(YHbL1! z&dL=Lt~CP@nEqsk>z29=l1b}uv}XLf3}-EapgT+vb$2Bb)kC_ zJtP}84lCZ6C)wcME08Xdqw1-$PZ9wVVs6T0(=df3Rmwpz`yd(ApDW}I(>sOHZ=a*I zSZs*0Xv%#a8uYFrn}c=~5Y1GI+wSwwbh7%_JxcQRif)r^BL3nc+GO|A9I!#MU6G@z zJz+M;@uBXbn_Q=RPA+)$VY0AD=(Y7Rc4WQ9k``j*9%sutmMljsrBJCt8_Q0rbpJ3Z zs1TH!x4hNO+wObIz$PW_@wp{LOw1O7X|qRnTH7Ee+C=J_qk(%C;kwh>202SJ&<81> z3LoU4Oe`OyY{RfY>S2LCNUb(pA)>TGs9+yU9R{_rl--yvmdw*qB_%#c>Dl`rWh%-C zDO*~6kYvnqm0QQcMe&;1ST>9>%EnT5nE6=BB##Y}(Zt#8K@nxM2XiBvJ*_OD^3PJw zeDI#}uGQlQZHOv{)pX4ho~M1pKRIlXd{_iN6mZ~Sx0S?J#;F=?2=8124AU#NqmUP!tlwK-NH7K z>2Jdz--gaba+KpUY>3IDCaKJpL7XsX9A}weva*3}veVy&QN9f}*;97tx5Il#*5qtu z6Sky%wW~b{uJpPljY=WRXD_k zxK^H4*#ixZeLA$Xt_Y6XAf*={KDmdb9Gu}EWh=|DeI(^t3)2c3TD@1)JV-JHLT9)K z*)=MWV;>|zKOvJglCp2mN0Q!v`o(d%%}i{;8yh0klyw|~2J0r`a|7#MP=gH-%e*d;wvdkm zC$mAyu|hVxWv{jiaeAoanhjC5pxO6^S*n6JHj>is_K}ps7+fizq^D>@WXDyqkTbYZ zsB-%%&TVqIY9Kcv=ynBYmib;AqTEhzi{v~h^TI|_W(jO0**_*Ow=3m~^b~!FvX;*E zZx-o$+V^H*%~Sn$yX;=ZY=ecZyU90kkrP>6ksKd#VvTu_Kvb@$k7Raz5rJdnDVq0Y zd<-&vYTldZCJ_SU-kb5U#8+y5oy%_84Rdee*ht^g#<5j)zAcgz*9+d*NJ`h!N0Qum zo!hRIH_}t|Au6lf7IIeHbNDqO_d&KQ!s4>Km6cjHMCp6l5M`R%7D@Jq3*OjBO4rjy zl0qACxm_vmq^D>@lu2Y;$UEtK`XFVB)@3&vzlBcoAu5B#hA6X?wn+9er93vo)>XL=QCa1-koVH}^g+tJr^{{%8#t=kqi92vzNZb5(MEL~ZIK*gmeNL2 zx}H9gGNs!&4nHwM$0|k@ zE4M|mlUYieZ0UOXNX|;}x>C+YBf%RVqO!_uA!jD4K+*@9ouwppk!`S~H{(uBFA@i7 zizG|$1W5PZ^wRaTkz{F%2>Q8FK1ff|hA3NIZ6RmhGlySOygtb6Eaf!F3Rzcx2I+g+ z5M?iAZ{`T5QNA}e$VpdWx>)KVy*8G!G*Eqzx@_Aee32H0jpZUeS{Eb(M3iOagOo0b z4U$zcLJipO0}_^M`c;sAQv57a|vH$?#0D&dC1MeK1gX2*&ubHun$s? zFfiG(v^sz1f+Rqa{Pr*$UipspS&}tKetQ;O4rXIHblIlC@+tNbafbKKc-)oLeI%I7hwv%!a6%@68Q7Ba00s*`&{m(Hel96}Qdp596aF zgq6$gPA)8P1&HbBLigHaGYCU?CpO3-d)+2O2ju*&CdAf~A^N#ih+vK?Lb8#R z8zoxP+-UWTZyQOu%|4!G>m)fyA(ZAOjge*P$|mwbPU<%LAnC}jTW&T;y{*>=DMx7g zAm#d2AEdM}ZIH9JiCj^ir5^IJB$JygM6+}teJtfNQyU~RXR~k5A{{;-OSw7G2RW$# zs|%8(nTn11AoWg9^Y$>;R6V&qmNY-*-X0=jDtlyONokj`1bvWloWBopkeN8oGU(Fd zcVzZd;L==rg7HF7ur5NTjRiy{K{mv7b;<7KSbHC$dK_%Bdl?|HkxYLZ zSV^7D?OtxgvdNa-vI~)Wm`(Q3Cx=_8$yUKIn{2tO))w+%QGs6@Nx7=lg@{JW<~H*K zz@laf*hosV+=nPtnhkPRZn6zg?uPdvD%RLSu9v;IPFNJ9*X75CC^fkaQEmyhA@AvNKE5n-_F>|03n}+u;>rpw>BF2x^@RB_7rF4xhRM1qoz^h<&T*$w$fZ zNehdLFWGofNTEDsA7V;E}17#!0rR*_2c2tvo0nW-DhGj%L{= z>1EkZ=fj*9k<*Vyby~u788={^$Y^Ds@V6O^2+!EbIj{`8Eui5;R1Smi+N1ti)$w*3fNe7a{Qc)W&coD+{Th@sN%SHAsJvuK)J5k zY%KNeNJ28!6V3!W*|ToLq-7_YLG7#=}?3k~^Nv9ugfYdtzfr(`54P=~*wBe0zHQz2w`|>k0k#S*$|WGt53{GRCY#VTB|6v+&J3=MD>pONXq_Y zlQ#poETMXRh)VM|YweQ}4xC6}%0d7eC}|kQa#yd-qjYl{^E_#TQDJWzON>hq_qIXK ztzwW3lFqc`$8mYcq=btlyT4Vbf(^2fGeK>T47o$@G7Vsw{IV^73h$K0v$5#21$umHhX6Ip4nIuu1Pj67d=1D#FEh&qk4aAkU00b?4g82Ru$M-c5-l@4N@-? zwLuOt=W2tbyg!>gqckvWEGN0O+XgwywIMdhWk@y+=7tTW$?R#GF4;67=_-r5+_PlV zQ?hA5*>`s0Y-Y$+vS~0kLw4ef^?TWgv$>hF6K8WX>%k+;%cV?H*+(ce2?KlZ(ZmI=NU3 zh%!K8Q=MEaM(j#@5Vp1;wkU+$2PvN$A7rOITOXv{gYJWrsU07rRJ}w%Uyi$c9WCM|o}RbCe-@8%H*j)gMM1$3?YcnmFRtE2H1U5s1nT z@@8^isj*6|evXq%wjOl5Or~iSqyNQAOJA~gaYp@!MJnIXlH(w!rnsj$GC4%pYp!Q9 zQUo*%q>`HlkOu1YJHBrsQa-n5Q=nWer9gl)NO+R>)Gk#IsNOP$R zV>x6Kva8n@TFwQ_ZIFXZp4cG2aCgiHjol_nFl{XL{23c0yP$H}1G{DWsEH+0PIUj9 z#~$XzNI%cU@{6(|7t3DOJ!3L@*4xrx#0bUi*&6{-skh0qHx~LO)b(i|X7B~8NY1Qv znNBaetW!3bP6SWhNzc?;m<_K=XjaW{*sV)H$O-nQ-3rL;Dmm0!c9k6agr!Sv`V}$h zMY7y;czJiTtK=4Dud6%h5*}GirHf3$*`BA&Hyca6JKG1TO)Z!3eh%$bE6=g99AxE7 z!^{NBa9t)XnKn?W7#TPqtag)nU{XdetRr(vP{7Q-M8F)fZxJxZ>}v$fiT_KL(14kJ zk$^d8-y~q-5aepQ=D}b+)#z-?JkxenX3mG%_R3ZDVRq#7lVz!4%5pl7hKI@;`?NDG zEc+fcqf86DhM z9#PDbZZmY996IgusF&ewALhU)pk$kY3ZZnHfdFc{&Ct>0mTfc8A)rbLd>$>bNx+85 z25)6ExYr$!ibbJbjer{MwvA+w4^oebK`Kl%3HR1-k&mV{6wOh!oMtO`6xe8nVN<8v zET#=KrElb;*{i20OjD2Px~$YkQ+mW+m^%(LxeF>l$~LIZMw56vr&Wv8*@xLl)62&) zxw(_W>~wdh7flS9$+Ov3km)u&BXW|1=io^OM#z!>R*q7Te3+A*uI0nTo)Nm(he_#2 zwtd)>(#qx$_cGmvr~WQI?l-j3hQAT%=haXN9v>UBbyu zze_l;>30d3>30bwntqp>2Qi>zUyD$`yi2aWivo&le>fyQ+aGR-petv~rk#tF?GHB$ zQ_1#+ftl_PQx+}#VgEe4DLaPFB$+WghE94*TD3myWA?~**gol+H}^ein4OfI=RiDl zV}*_9l0Ehvk$+@2$pMq&Ot$S9XD0jIZTW1w?9uPg-e=E#2PVxb$@X`{ac0}!P0K2m z?0eKs+4J8y&pCU#4lozlUu?@~hYHEQM_rS>(uCoKOxek{>!?~vw;6~9W#`=+REUb9 z`+OhdB2XXZDCb`JFsJN@chl+82seMwAe@Rt?n?|vWqF6E$MjPvWx@O25kkX*@4^vi)yZM8Lt`JpE z=b{NnWqP@X+3Q9iA4^$O6`?^(9kDu48Hhfb(uTM1IZLLLe|-a{jD6jJDeJU+m=OW0 z=gV%ul=aOwV9FYF+#63ix$KBvEmdevwIQm)oM&~Mw#e)BfjQ78@MLAWpxql#2h3Kw zZvJ`d5#&DYj4>6oo852F9-U?CJR4U)ne&pIhocpGlDSe_&C_9(?Ys4qdJ5X3t;@Uc zxGw^xua}rNkPow0e7}L`pnTyQFzEmkLhtiv{s%l-6p!q;gI;VQ^1fbLWN5+HpL$gO z4Ls!}kQ;c8QsnLTh)$05_nqxL;(fQ@4w5DcraR!2R19;G1@U&QX858H(0x1DH>V5{ zTh9-@9Gd0Rt{04>3a#g8807p8*Hi?gx<)pZ#E*p_*;tO!=kT$VWfne`a;KS(rF3F^ zEM?r>$5Pg~`dG?pIv-0Nmvk?ro;2-E??4TY^a9mQBy;u}Fd4DUY1RBzca$Cb$1oHW zP;-`Dl-$dgExaa6Ym#SIgj({ zQ4SdO@g#_x&Z8OP>pXIY+fi9V6R`klPPYq~gF@8R^lUrR0QFes=e_(o`Z}p_%KIZmTA*I>Jbb!%t`hX`n0o3Bb`TIlmNN3x6GRn3e=u-*R=Fm zspr@LB9-5q#G zC1J}JnYzAn4O?KQm%g=QCrjU&*_$>C@q?U-djlwws)f1i*6mPDmp)*t4aZZ6lk0m? zLn;%{K1{vN^#)8iV2h)1Jj8Hhm2v0xMFErQ;riwD(Uh%LH$bY`=M9kRK|;Hl{E-U8 z$5M_Jb5nb;Tu#mO(af&&1WP^Jz~+xM>U_dwDUc5`J9WTW%GALPEYK2SMLr+^uqw5i}_f_c;w@rX$va)Q)HD;M77GaK>%-=wBR%r>F?Tb`) z;VL_72}Q>~q&n#)ngLRoOYUg`Q||CFnGVQN1r~0gDHFy1X)b|AO*T6lCT)t@Os8Ef z`3f)O^|FkqQhHI?w@AMqNO^THq)`Y zg}D1@qCW&o`!qY+jOvv8Oz&jE-A7YawBI;QMp@KJx0&9}Djw^j**}!GVV@=wJ%zaY zOz&m3-A7X3Y|akEZO0xpA5df2yCR z&2&Zt2)*f}Im%tL_Gyl-Qb<12@!5nR`Dn^zrZ-MgcInwnAMq{ga^#~qwZVZ@3yF74 zh`Z19X-t2Grhi}-v&2c9rpOa(|?j(nGGo>ZlVkESeg^iOkn zs4HYMopM>hpc`n)dJ_9ImtMtte5SKF4Lnj6(jp@i_GvOFQQ5FA)2Z!L58DkiWjm_N zbVh@!P?xRVsbN!3hL5If9Q99=UJG$8ZKhK~B*gs&nhd4Ny+YLUs)x;IdLwOEo9RqA z7L+%GS%%m#nMs*l1ntZibTeo*hb3XfwHt!F+2T1;%v={GTjELG3iB`?6_avl%iVyv zs9WUU%t`hx*vH9eCUKlM(3I&W`)1NhCuH*mNELqf4^swWZycuVeX`MunFB^i{?TGtIi-_G?!K-34Am=WzXC| zb5M4IE$$5V7Yw=qQu+SAv{MQ#(6nKa4b0Ao(TbUEzPGwz)D_Jr0vCsAizaPED!1yR zDI0!npqcIwv=8YKxHpJ~Nfqz$rJVui+3#A*q&T69ZKgLQhU(hg2Pwn(KFBHEa%UZ| zGCXWFDQHW-=uAKrFl})sK>%r)0l8LB@$+vGHiAI&2FyvRVxQ@Awk^}P=}89`Ix1(t zSMG?BV32*7ohxBEF$*x2J(??VKsW;G+LqBYBAEZ}#1EdPP`!{Hij_M7VGJ|6?eUODsK1k`P z`XJ>TB40FzB|BtDqq_1_eKf~TX<}R4S+gp%rVo;B-*pw|OS>LNd;_M;`P;I|6gNS- z4^ld+Hb|Ow1jE>VuT&PhT`=S<2?4Dg9I*O+6*szCk2ZAuaU=Ee~b6`_fL~h(PlOOqo%& znXVi7e2~&n^+D$Mq0ok+3=bDg`mU66w{KAQkhx0t1_4rel|D$>En`bNiwl*bdIM&9 z`m9$NK9aUR2SyUhn(-%!PxCxjxn!WT>Z=flg{B3dXrB`_a zq>4iN(%wr)^#;uJ^e0n2(`^~*=aIeCXKj#`zrJV=GW}`aph5bnH_(*1N?Y7xk4BwA zK1eyc#+P=gt^}GlV5X-(yHVEZ+Hy2XN7V^MXM>n$l18Z_t!JgQ1(GS83m% zNzQ@xrJb3P!hXF0Gd=x@iI8r~Owv)cMRQ`|WnF9fqB+a-r;R3xSX{~*Xv$orE$({e zyAM(}?)lO_OGotv%=GjpJ$5RHV#^T=g0dY9hB^wb-xp2YMD0^9{nQ(1%3P%_?(7N? z47veQS?;#9$An>l<_(zX>Cc`>k5HSg9O0p>T1X$H?EbVxvwz6+r;n!eQ++fWnX7cg zok3bE*?$A1N-_D;P75`7)coliFy;JGo9Rt@`m^V~0F4^uK9+JKsxO-Kv-XtvT% zy@968RodcC*Q;QV4>G@>v}eY@K-0fLZF>5XA>x5Xs<@N?6i$mRnq&sVVfOBjh@S0< zg7Tivt*Him-zj6}228zu!p3vxm6Pt{N$5;yq#G~?)qCT^oS0oxm-rhnzZgsI%F-;? zD*1S_EFzspjE+ygN6Zk<<`Is1JYO|UXP@WrSX2_nhuO&O-9F3~gFBmcR=%b4sAG$D zHl7^?(Ah9q5+d%AyVju_h9+N@24>A<(>^k&IvpnS4YOfRq`=c*>NS7vTRhC{qRhsV z0f*^4S_Wx%yR?t2+Ro+?J93pfZ0k>!uS&1oroG9xKSwsOX5S-HjWXtE)86IVpX77W z?a#5#w?D@r-~Oa^M)r!?JYq|%csD0=(++qp9oEvtgTGQ_modI-)+zf$^i+FtwZQ<2lNCnLf;EQs$QrlSZs` z9xYPE+juenT$u|#%!cyVx-4-tmg<}vx$DqJvz5^RAEsU;=fmu2C8;0h4Va`yvtbT0 z65``I%0<3DOae>7i}7JH<}sZ|?Dx#(5zdy1DB83yO{1dIK1|G-Y#uGGj)0kJX^F*R z^=ss6Izp7{A$AR$hT)NwaJ zs%OXtIVt1##$oEXm(3sfSo&y^ycZ9KeVVuh*>|#Ul@;q_DXp%?b+Q;rk$!=CS;y;B zo<72N>C;PtmtK|z`-JPgbp7OAO0=+CElsrA1R4`ap{|;E^FbzG^q#Dny6CRK#gH5s z>bn7RQPNR=V%+{dFE zq|I&b2cq&z?nbir1N9wGXYw=GEiwRN^N1{NHrp3n2;vIoGRhhQ8>B9U@Ik64u161A zuTlTd)fGNW8H#tWCB0dSK|V+sNpc;+o@#p)q`3hTom79_!jSa1jt&zr?c;1@8N>}V zv%>&zNQMDi6-R(qW%BI9Bo!`nyMLH%r)1MdvsVGc8)#0-JoXth$to510=2T3#=qz- zOLFQL-G`|Q9Brm|^2P8$cIsjCLG~)><%=d`a|DBYG|Ao8dG4c0SVh3JZ;;Mj`XHr0 z;7fZibJjOt%JOKN>HQc?tp%ujkd!55gPc`8mM@yaLwV{p<@l9+r*@b((Cm~Zw#9wu zWreK!1~G|8+;d;r2k8jifGJA~e5SMZuFiBDBz3&mmvU_KEqBJ|WMA~LS2;od293H2 z!WH*XdX@I29Az7TFYS}8Cb$7pmd4uRKFLJA4^n2;eUO8427J++WWL%*b5_dTN0YHR z;-cH)&Vw$r<_(a_a`&a3!xU)VfGMjkZKltxDNlZbX6dN@%x{YQh{nQ(1>egNN4eF#ZGIU-=I!rRBfhHLLf-@K}tu}2Pw-f zebMY?`qM{K`l&b2l(|Y<+=)C3t$72avfO=X$21gZ-hi2&{v3w%^e6j!m7{8lCXy)* z(-%#O!vstpP3folXpS;hX^Z6&~4d&?p^M{|1fe=})p&fkw^Dw&iG)j;arm zz*!wjUo!8)(X0r7iB0^eS(FRK=>kv`^Aey#X^l{fQ!0K@?k#X6dN< zAX^od@kMi%=}#X`>8IX6Q|2mdai67E>4RKUipiIDdeen+zX3Bn{W;Kq!*Qj)L5p-$ zZP8q0<*zTAi%fs|Xi7iTMw8)hDp%=>`}mMv@d`L(22F&#I=lDoZf3iAJ z*)pzZj*l-|?aYYO*vRy!jbvE`_hj;aq*PP6qz6T?t2$VXH9sW;G+xk_8ynU@J^HM`>mNL9G#OM53B)f+I= z)1PCPp8gy=>8RSG$wEfKb6+$&nf~~^|6%QpT1}gGW}_zIY>YC2AVQgX^ZX4&AybA953Wf z0J{OSle0hW)aEP& zX|msprBTM5&Gtpddu`Ge?F+l7xlBqEckXF64_RX1o+cpWyXKx|LnSZYsYc|@(*&fl zJzOJ+ZK+brt(A(_C2D#(Lh%OBS$4A822C@|5*S;S7CHRRN0Y1`)AEvI!^DodS*RM8>xpHS{_1YOT4FO1*&T|+40aIR~#pe4g z!+rjFvL{xVAQ2j}tcC7DQ9xbhT^@B0?ol1&Y{P5@mCn0yo~1b zUrZ3S-=n^Hs63f1p9JHTci{2}kSe8R>(9RJRMx?EGj%{ z%V*CMC$47GnA>O>nIuQe`SLl+&Ip@Fqhz~(o|ANlZ=5H57f~Ra_C>#&wtOy=^GBZpJ8?r2u!b#j)&{RGQC38-@81D zffzz9E$(rSt+eZW8w?GStwTr_DwEdMAtMW|#CiJno$`AXT=SU(rrA1V)O`ZBeA2lk zbcj#-B+D#r@Mw9c8ef}sozeB>bCC%IpZ4i7$w0cRKk0vz52vd?Ct|-s=3O35ENJID zwNSb(pA#;u)FEz+niRRZ?>6ndY$CShbLwSl%nkX}V`c64ooJnWJZ$;YwemKPCfQ=< z%O^b&LgsJqXpx4pP5T1O`rWkUGg_h)OgkRJ{7%(pWix4}|5GUuS3Vhxse)@Rj{vFE zl23XkTOfV;oQF;Y8f@AJ84vO0bC4~NH)x;oAGtZ2_Qd71<#U!nE1O4iCv#G+e>5+0 z^p($}SQRG>WtVm=T6NuR`CJ+~IPV7SlwCkv%?R^@0!t_70Jrvu_Hw>`7`;|v8(~t4 z=?0$CL%M;dtQ7F^WEPB!9uJmp{{ z|2zq%3q!=klMtY+#&_`qro5YOA_16`+|*@>kDccokY5<|Hq7jGqo65W!yBi$C=KGD zrVa_1<~-BxvwPP9q>eJUOm8TGOqR_?&UWybPU~wrnsP4i4K(F=16wwmNxECUY|0Wq zA5B?I>Yrx&Pzh}tOCY>kwXv)-{f10v-`UcbGG!Gw5xskx_7{JSt zyJ5NsW6yilXX(6Ab7%tP8B!s&Xh5_OZS*vGm-dF@6>*DvklFL;M;3mo#Ga3(e209H zvJ%|~$y&O)onYS~S~bDU}Vf z%ifGS(hQ{f(0weW!{&pOSr`8X^)h1W>UX@0Z2jKqxm-S$onpBUQZ5|50aCgBK1k`O z`nm{%7-`PcZ{t7E?U-DgS1z72{V8iSl(uVb6Hf%>tK2IVEs>095 zvy)CB?P0D(GiV9D0d;0YYWDq%!RNx3btieSD<%If&29c&nsv>OEl+cwf0t%vKxf~j zdCb2{4F6UE75_Y`Y)zN>m@J*Fo5+HzFsDsB6?rP=<-^pC7Cy{Yc2@Z?JK5mv!_-X? zKFlF~1|<^{rRnYCNxf6{Jz8{H!^e|!W45ka78(6=@thtH{(r6xnI4U-o%8WzI9sx= zqdZ*BhxPH)%VK?)EcZy~k={$`OK&oaMpK$$}+d?Eu zn0>-!KHLVWM~m2J$;=AAQ?uKBkkY;I372KoH$bMpkqpX9KTB;9x}r|jKKs>er8Dgd zk(?-EKjf_}IrXuW-Euxi87RL2QpF{FkTP`SvqyFb`dG?j=natR&lz1IA2EQ;FBC461*lM6E6<wS|h>+Ju{)*B2<7m;C~a5?(Z2Pu~W+yI$w4fb-*nvZ3#;s!p*A>A5eZ93{J zRR_~8l>JilvR&65N`NYoW5#@#gWP;$^PE1Z?9-$y6f|l)zd^a&3+cm*u>^HI?b93| z>DKi~da{n?4a$3Ug>Jx{RJ7GU%_&_GQ*4-inv;Ca{nLzrtaYy2r#Zi$LJMxi*BGvVR8Kyxk`y58TAI=KvT{N_AmR$=HEK$K1@cn z3DavG9c20G-69=9CjFQ`aL*oTp+f8&Ww_PiL|tL(secv+dIO}iW$n|9I#{X`-^spEy9y(Q#b(P=FFyD%PQ zlrNilPOg8Nz3i2;;+6VK3Gtp9(5nf^lA|zXz6!y zU=>gO1+r@kiOR{)hwBazmQy^ptuA)YE5q2QT{i>YfGH)(r=5wJ**ATWeS!8JTI6E5 z8z9q-%|&h;^Rbk*<33210Vdz{;h|Ht?oA)?FobrurJbUY?0^Cwvm=rN<)3i17A<#~ z4#@1((4gBueJthJ86Tt`w1m%TIn)HD)LUtL1N4Aqt0QtQ()V=@LsmwsG=a?_#wPNe znzY+yHt%_M+7gg5ZE2t8ApJG_G>1+_ko?meq`cd<3|oiNZA0?P>9*l8P0}`W)ra2b zZF7A}FL@p&S@P^-DF<-e0GX~f^IOuVLARvSnPSQjL*JEXnmaTnI+N9{bmNeWLsl=w z4Uo#@@c=tid1vWOw7%Nr3KsP|9vxmiz0!#lHnpoH* zlD`Xo)Y9$~19k+W_O&G1qk=Qx$a{FUi(N3v@+_YI)Kq*VP4po~|_XVfgSV>d8eWaP^S%9E@dgd0FxIh64RP-32fQEUFt zc|l{rsmhGr0LnTAfvNi}&&+Adu4JaNF?}{6qle{eLN_P?OnL9^^K2fYV!RKNO+g~* z>Q+a?bh%>9H5-ActId&L>moJXB-3T4(>b#rO6n#bCQ)?pFxj;Ci=w@;@f_r?;2SVo zr9p4Nl+gy$tC^cYKb~e14w!Q8gFCJan6k#=227cSy8&}io~I9Ul*0vXz?92LI{Rvl zayi&+Urk&a5pnRJ4rV9{wKSV<-P|m4d}IU)JvE;{BAFz9z8TWyk4T=W-d7nZyTyWd zrCj-GMhE~YXD|66rI+A?)Ps^->7?~Z-J;&yl{~Z8NyV<(&b^xLEH~5mKxs@==BLY~ zj`m5uQ*+~ekg^NL2id8NhYwPBO1siYLP~`%Y<*1QsFY3{&sO#|$NOi!8%+68f^-9> z99wY%rrx&h(=Ma*u36Ky(&Ml}(x`-_)ULWOov8SHm?-%=o|9|QvD8`J%+Rc!#P_nY zxn11Hh($z7#dmJs?95KU^iT*J{1l?LjT{*t!Fk(#?P+n%w&i=~EeKoQr(IWP`Y=Z+ zp>}AAtyap{^zoeK2GIDM*6r-SsMT{dD4PmYO41H}5(!b&uD;B(npepD4Vco`ya7{A zmT{lro?+ukh48s2N{d!YE=&^9>fyA*E5n0Ti}i=|2245F?FP&~oks(U1{LkDEYZ58 zGBURLIXtAP=)-It%0;*VQw}7%0aF@wH(-wHIl2K;W>0*WY{FD3*_KcIY~j1#z!QT> z=nx;z|Bt=5-IeS(t_5G^pzj|EAnDp4`NjD~Q}#%JB@&WwbuVmV&>|11hRANB*|ek) z^zO5=x~ZxNb?vodo!qzsqYO(BPoG|lof(lC5xF8FGgncNlM(^rm}n+7e2I zV~(GeP+>#tgpZR^Q4uuym_zXn^OB;bS@{440g@ea{iX_CM7=(M#DifnDnd7wi;nX~ zQLD&W$O)i@QgOqZROoO>0g~-|7!n#kI6qe_9lIFzw$VH9v+ z`9}Y%3+8p_z@3;kx>a2;rTiULnodD$*gCJOZooL>LTTQDXrM~;f3pF@MuH1=zH(Sir)WlA46XdQ9l88BSbA=DEZb@&+yc37>sqe%%EzF652L;}^*AO5T{Ta6uG=eE*~Q1u`z= z`%{e<#JG?&ybTL^qaE6lgk*t9Tu64LrAxwT-+hBV+2mS`LzefyrCgRW4taxN_7un) zt?Dk2U28*5YMIz+-hdv1yg`S0ij+5|qCW*PQ-3WQ=)kigAw>AlKnOupU4R^Zw3Yh) zqM*z6#HGA3+vh2eHy$^i1j+o2_=n#pig|*R^+qoJNs#Y<(0&pmyTqrpr?5k35&H76 z>j$XO^aEP147VZlWMoDZJ=+2Kej3MRmjpv>Els+F>kb)xu{Wm&(|BHp)Z(mG3gVR z0Lk)r!k6FZ7x|PgztI`@Ns!F(5VXC%pJehBF)I@@zUMc3u3n^!e>up##LEtg*_&95 z&5}*&M(N6vzWfFy;({6f@*C9~Pl9AGNO3z)Hzv_MMa*@$BZC>I!!`3p!{(=a_ziaa zlOS1MBCeR25fI1+o>3@5ixtHYj=1Wf9+3z#>G4K6z*U{Z%Tj+v+T z)3cr;XTH&*`$?ELx*|LY^9H;1NtlVbhQc1*m_qR+Id7DcJqh#1=$R*BHg>ng*R$Mc z=lB#k%Z*kBPr|&x7Jd@ujlMrm!UP9l`+^hph=xM~Ce4$dAB1CxKG5!or=);pc8Y|( z5cDG>n{=Kf68!iZUCu7r6qgedKev@hkn>j4%_qo-@&NYe(yb!4o{ipe;q`0_OYbV{ ziTGf9lj3sTsKS2A7Tst!`Xos9SRj1(@HA(;(MjnkAAVy*$^|k`Gn-mv&U_qn#-kH4 z%s6=sofp~jgCgmTLdvJC>5Q3W>^=$?NTB!k=tl_5USa2F)RF)>I(7%-=-3^QqmzDs z938s@lEv=RdeyaeAAtsA>e%ra_UdMIQYRVD@LTwdashI`333ki>1OmoA!3H}lPDNx zpB}bL6eyA-Nm$LsK3&-L8{Hf(=W$$4G;1c>8D35d{UaA#cPK)R=gs*=mrsvFF2ke3 zIo)Vvc@Zqy9x9TIkZxHCJWmn9KX*!AJHCo^dN(3CBfwy>JC(n{EMTK^Z96Ai@3 zaU3=x6k3s^Gk(J7;Z%S*Q!0S4nzRTdzUz4zubsGq$#ERtbxu3Qi5ENJ(RE?Cn3Rns z>^kKp3A=uP|BTp!QKE7f+!ya`@4ScG4s) zi2Ly9he9yJ%GoH9Ilk-d#>9<_!pC>L9pHa7>VL$Sb7rS;{9bQ2+D=}UGcG2LUW8r0 zF$d@(rm*V=_#ch>AMxcZEG;S6dSmBDT+GJqOU&pDMwoE7nZ~0tNfZ>c8gjG8AKviD z&XTfW1zo^-BPX(g$u8m*VN)m%u-qE>b}>!?lX48ghX{s3(~ZY^2frQ7b_TnN%Y37~ z@MS%t)(J@Fb;ltoBS6s3@wCKcrnE#s&cZ6L1?{Zkx9CO>)2ApBO>)O=9j!h{aG+qa z9g6SzLTMlhCd<$%m`s!6+PTn92!fn69WThaGH)q-&@C(5A_0;mCk2hCd?EoekH0aO z8;yW3hmxR4H%1~q4U=h-pq;djsqpPI?-!R7jBes0hgBY}2}nL(fMm41xWD#a%=lF8Mg>%!wDxYYlFaeU~YT_E7XwjpB z$zp@}t|ywSQ7~DNo`897x-|6ZaY;7@99&LMK~7o<6SwwsV|?I6&bZ3on7Z;LNcJo) zXgp;k3Ya&>99}+M*maug7BFeHM!{rtD{<}2v>!-ZPL!b&A4HIIco(H*JarO~tUfQU z@p)m7*a9Xk92Rzc9ZmpRZVhXHinZtQ1}A^pNcNf;w<5IgB)cwP9>A=@F-PPSG%2%ejerUFYx`6ZtO#8GZA?MV@r}tA5P*p1 z8CUtnwn%_vubFX;Z?t`yfH|=!GrsF>8lOFHG+QIcIWtX)TT!Ehu7aGjH@6^XV$nfZ zH$AZRFLc4%@0JEl1M!TR%g=K35Ow^Ta-y4E*pqrUHCY)x0%ZbgtZ(c(u1lxG0rpO5-75^O7y(&@kgXy(L__~&Oj z+C-6*hjW6Yyj~yfYN#<<@0$^AC@%XJ&E|waY;c|Whr|Fl)v=~pWj%@O^_6gSV$DE zfN~0O{PU5z9)6&J;LruxI#7hqM;ZbV(r8dRwLp=S^SR<1)qBki|NLcP*-YW{7hdKg zd_HYREJ(UeEIOH|7WDZsTZ5ga(Lf)NO!ecCl*1`NGCGO?$qo_$lI^(w$?`B5CKe6y z(e;AeA#txPRZ5#tKE4~Wn%mBwz{ZjX11?@ zQm;%{(@Y7d(R(lFGTJRc#}3xsEG{Kw$qJC{a26m(yCqmlX7A_uNHHs_Xr{bl+3dv#*byqrhbG{JF7F$aQQWz!7I$SkaYcoWnZWR@!GezDsa%*)H`k zHMXK~a@m0&-g+>#$Q2r>V@8{ zQ5RsE7TSa>t^w0}V$`y@6EJ~C!%&rF&Eo?!Oz@x)nxd?n|E?Go#&r|D5;TBkCln26 zGm9z&4M6*2mO_l50rQFGd=yb9dbEZ^i>YTQhyo~}l?5ykD5J$mpv<*UKvAu*?XO6n z?7_4@R>izv0$6E6fw`7BXEQa<@p zk#uJMv?A%!|I%QKTGs>aDAZ~kASrdwlr@EmzP+Y%2_JoUNFaHda4RB3m!4D8>Skw3i?#O{OXUi%@bP$(*!CY3O!my9V6se%g2^;gz@$Zg3MNe$ox(*6)67Rmy?wC_#?6hU;+G}* z%HJP2*c!x3zu=b8D=(hj1t?R036$xo0!j&u5@?+7TVcNz@%?53MQ+sQZQM5L&0QE zMG7YKqZDPLHCuR2k2a71@0R+e;m)W4rOm42uUY`@xy!A)M3Iyxc;efiX}jvqPYvEA zg?8XlFd0!+SW#3gl6;}C_l5dqilnsvn6RX@U{Tq7I=@^Hl(zX$R+PTJD0@%KEfh&< z`LD2~bS##z_jq?5or7H}&A|#Qii#j2sId2#9gBS!eCAh-dff(%?|og^QL5}ceR&cD zrPU_N-c#>c+55uSk&2{rRFbfyw2Ntr=Qz+9cDRx@+Q3*?Q5>X1P+{*;wnq*VMN(Q+ z9pC##+cztFPwD1@pm@yNKJ=6or6Ycny{9R7MN-=KKv+`rQrKS7hC$y!KflpAn1Z0R zeQkV2cTB>J?|tXQ47dCBgn2jH`xIVMU@~tfzW10vc7UKO6I9uI+L1@ud)gCKku^FMxE9)vDX(tQ4?htDxkDaW_UIm zKA%Rp5-4+{1UpSM%vIJDb>-W}uShzcX@&|++5jLLJOXokg&tboum>GwMQJ^eviG!m zvmz-SXdAyxaGDN}NE3a@6zo2untt1w6i`}BCG35s@1qJRsvfsLUjk)@FK8)TQ?gNt zq)75?f4(9qFL(~0dw3rug2rt$^P0DC5$(!5DJk|;*fuG9&!X1aZqD3a3h7e!J^E*EtFfNWHu*(gQz3%f`aP)aXV_P(-r4GEOJ=qaGI#fPA! z=sHeLeL>QC06$4+)?ls;%mpiH3@ zd!n6K6iMm)L`72gJli*^p!<{ru3)kQT2X!4cU%Fb&!o!UH^$$RK-tTN0NUt-uArs3 z^T?^MNJ<}c6-hA}VzfPh2uyD0xIH!AEhwIkXbW?A1bb?f1F!5o+IwtolLAU}JQ65V zC`C&%+bBg+IxAg~ly*uLbicAru?i+TpcU1pB>-_yypl2MW_<4f${NN&_NIH-AOwlZeg%Dxg2PWGm1(O}nit1CskpfDql9j!ubrljQd(4(VnL@=+{d6kK z<547~+$cp-T1PABKIKL!nCyTSR3F0(hUX*Fgg(}zT{D1=XYl}(<#+@wMHgEV>Ihmo z(H^#nq;#^qBI(LJ)41+~ATT;611pTZk}CE@IqM4O0W6+0Q5KJ)P_zk^1j-aj(NfyQ zQjwHSmlGtNF;8^+G>zL6TGx-xM}Tp`4roF3XF3Q@0X=}llV%J)-QFfap*VS00bQ6v zDOyTfBr1}w2Y99!COcmD6QjclHkujDQc-2$C+SQrteH1WEZcw7Bl0y*?3C!DI)tU{B!Nki$d)J%GiN7FtuLC=~5-p@5zn z>ur@)DO#G?Mk$ig&bW%CbTGM~`h`4<*M0ODCxR-NjAkjQ{<^S>Q~^DJ#go>Ry_F~mMRPn7 zC{rj!OKC-!A}Ofw+p4cfT9{`l=>GV|*yu>XUP%?zr(GEoP+F-a?0upv9to7?cqCA! zP=c1GiFrJVq%(UhQ6#0UEaUc+=wuBAlO524>f_ia7pVez0E;K3#8^CvLeU(L1j<4k zMN13YC`Hn8fM=TO_*`5<_r2|lRIn#nQ6{K9NC)J`mq6Jz344#K8X~C#%5ppsC{rlG zp7O#rN|6*vo^3T%Bwbku5!d~Eo;SUf;!!Z!0j;QhVh)c2N-MRLy+`Br?Y&n(X^uw% zWeTNeDedE`NLml@OwkRV7-?MhQSeRNCpFsH4~u z?HZ&=N(YMwlGcfNrg7b`6U)UZnCvlIP<_;@kc(6TWdVe+_o#p&l1iW~$D@EA&^0Jk z+BHa#6zQmK??kbu@xxkDrNdeTd!iL(is~13kt(1^uz29=kIzR`n&VNl^nk8GNN}-@ z5+rS>13Xi3Y>AP^b-&H5VnM-V2ehF2ZDALw1j@Ea*?Y?3kw96FM*%&cYY-YbvW-$C z%?Egb!P@`?6a4(mQJ**+@hp8`gqP{7pVez0E;J|XkTbWp$_O8gqFK3CROZ-b`4TK zzp&R5MbgSVQ$hFX=vW1l9ngyE)5g#OC?BpO?EQ2apM=jy8;w8pQJqX8JwZz`m|%E1 zCQo#9t|BQ|w%bXLxb9=j1lcDAlRaiDs!tn3E1(CkcryGQqNR$F(j1QhO1lP~$IHfA zL+6Rks8dk!sK-{ddqqK6XBt6DveF<*L0xFa2MKkiDFk6%(bw{T-CAhRKxG9mu#H^+ z!U|x}4mqqPS#i2-UjY&-&!7q`kZ38OA}gxF4%n^4IXKD+&}K5q3Sd&}0k)NS6^F0_ zSk?n}3q+g)Y^(4-0Ky6&usUG33gzD_nuYG(2kcg*nQuu}TEQuy@?PYE4m8T0Qe?&9 za=>o2+&^%O;5kn%>SuxF#wawx3X~IN%}S`e|65!KK*ywMPyrQT_IMpA6Yn6d$VwSc z%5F`xbB}^L^BGja3e2=-Mw0c2D6Y&$L~(_8T~JnFIUJ+w)J|c=MNRb_|Tlt76uH+-4I5b{5Ac`yH zh$s#O;3K?@LZdjv)2y7mf~Lt)2e!fr$Wa*1lLM2bh!jlbW-6Gh3yXruj%xvvzBVhE z?9D|OY~6<*jed0jCfg-N(gS)}f~h^;mUs`#_}*nZ>T-nZQpg^#fyIxeZ^er18fV^R7nC`l9jfPQcy7! z*ABXDCK~p%$Yz|FD@(Qu8@F2fJG9BW){xH-61Cx zs5GKbP$xQPv&URPQ78IVC4n-3S^>pWm+iAk0%b0R0-F0@+T^bZ8^yD$$T>uJpN@9u z_d^tvl2#N@np9e%FRJrtqL+#U%2Z1De7si?xi*gAngmLZu;vgu267!N&yGHPI?T;Q-{6B?Xjrf|5X)T}hxUp`d`$_EHikjj7_7 zN}}(p!dZnwh1{vasfzZGB>Yh%rQAYAQkwf$ByB8C6(mKw39_cjrGnG{fJ+72Pf(SE z8iD!&m&y)OS-;DI$A6_Gvy>HR<8!|=Mn1cs#Zl=b4SY@%6>~(`^N)mz4u&KFCdfKX?6Ov5o#<>L1r@WtNVp=Qg8ndm zU6++5tQ1*Sq}IpFx@KmvimZ49AiIU)wy&&7!1(P}2 z3MNZoE12w|Nx>YR5zQ;lh|YqfiS1InFm%oY zEqD>y)>8qKda4R0qi!mgEdEh2nSZ8WvLujl?(Y~cDcn(o_6AdK6TAqJ+a$iK~_ z|2Q48Cw)B+(FE_j(!OAdtaxN3JB5^H^foETRFIQTL7iv^ucf=2u~@1gzfM*_Sl5ET zLsmdSP3-hnP?r<)QIw8S`mPnU%bA5vCzUD)j}q0;fK3Mv8>lBf|3 zE78=d0=lv&RRK**trSrDXrq7@W~vG(8Ut-xssc*qI0~ScX+^wW1@s&*Z51vkp!{(y zepO|>To2!A76BAUxq)B<@0AsH zJ4z}qN{AQc0F)i15-2O46+n?IXR8{{>(qsgf0ra>N~M7Eu}8w^)5u5JRU_-%(~xpqZCOo)Mp!1(0$q@Tft;$K1KB#b9e;MMw>$jdyi(WBzK^IPK;(K zfii^>v=sf(4)}c99#oNZW!%NM?l(GcNWo+Ww4(a7Yf5h z$ImNTN;v|Gq?M)O6iI0xPeJ!-jg5lI4(Pb*qazY?coa}x0~>xa!I-7-&rq0%#Bw}w zE$w5L$Z-36{s0yad?=RVktAiIj-sXLE8ut-Qd*iV*b^qTZ-2dl$qr~m^=TQ10!mBB z6)mMK9to7?cmz=1mP63eNj?g3ZQ7n zJ>EA#V=S!M))6Hr)Jk(a3Mj1w5wvtYpuz&Lqz8DWyuVXi_t%Bx;si`OMoLkAI+;!Z zJ%Gi7IZ_8C;W35Qkw4nNMqR8GW zpa-ycFz$@Kl?Yc!qB$M~ln#v%w3IisQzTsu@J!L#hn!Jy-A^ma#R-_GsoS=DMfGW; zOa+v7GgtPWvUns=mgA8?nL;V{L@UY^NgGST3zG5?zj56MfsN?Cg2@hOLG^jdeFgLg z7Eh)u9zmga<3$OS#iZw4U93{A}ogBNYjizCkLe zyuX=*y0XJcLgn|Lps&1Hx*{vy&4`ySq4Er>umWJR4!132x@imc_zLuKtjw*HP-!Dd z36;ja3MzLQ1q zgv$vJR3v1TWTo6G3AM3Qt%ADFEV(41(&`%tm3A0WP;nU^a1tikzd@2UvAm6hN*~oG zs7cU;M{#s!3LA|zfmv7umV(J>;|eAVG!#tc3@VuH!d5Wpp&FhWwVY7b15q}gDHT*& z%^7b623ZTctm3QMXxO4)vf2jW>!%Z~>XK0DECvO2qA%)ejwUabX`-({3M%?`k&7xm z;|lC7`Ut43YahqGZLJdO0dvllX{9xoimZvc?8M^sRnWD^9XwU`Cg5fzkX0s8R}1m*J>6;S#npn%TIo)l2p97+M@jhuvy zqV;%+q?A~tfYN|c0YxwLZSO|{WjSjFlqQt~Pz;eF*Qo+ZE4>s@UX>MB{+W_%6iIo< zVnNcx?ovh4%));Kl#b3)Kxvm41(cTi2%u;WHQu5S`H1cLV6x1svh%b#M3|He*PaeARzNE|og`2eFG--x6<0vV z_p!i6(ZE)cl=-*Vv%(@I-ZUqEexcs?h?Px=R=p}(n@XZ9+ZJqTER%}rKh{8F zQed&TOugc=CfYhFt_3-9Ef6H7`DsZ~dM5~y(mvjbq>1JH6;NLOD11KUqezlcn-U}) z-*SA(X?)A^4oaPjIDr^%9xNd+DX24hqYy}5Igd{+0+YGL;p7D{nFp_64kx-pPIjIs zavRIpqA5ez;40oVY{WsI#H&Jgi2e6 zDyTDkO_xy7MQYn#CDg`zKLvH61NJ1;%JM)8Dmqeu=|f$#Vq(!U@K2n2y0MN zWA~tfn(4qT3AHl*i-KBcvr`Eb`P<<(TkFKAN{XzNKHy5IbTnYN|JPD6d5cgN6j2*} z8IVwExrcy?S#}2~7KkecC{~+j6`isI6D3nCs59n|4L8^Z-(~zU(2%(&Zn3fg3vJmY zq0&}83My~WA))32++s9qJ-{t)c)S>Y61LP>QXm`}0+U%*91{sn46i zuM_8lc7A8*X|;p0BT5oAkH7pujX90K{DBIZ!M3d`D*z23CxC)l7J6890#Q&03T@J_ z$XXA05m={sz>B~-AqqHPw|cYs@tW1z_?#H%1`5Nx@_{f1DkIZ9?8=I|`IgDcexFOBR|9imxgT zy}=3Vb%C0aXCOt+(FyA==lDAW3Wbl`iYS$DXLm^VGlNIT!W|O@lpUmsq@21VNQ%*) z+xw(QO6ztcP^MA+1dHx|VlG5HTfKm{PtH;Wlm=1D694?dyd4FUhNjBr)4`{Lq$@`C z5akcg5LlO$hGplxSWr`W7YF4kMI{{0jICo@LCwnn&o$uHutdr^ZVRq!nb@11a8~W$ zti_LNRIRYR5wtg_P-UDymF0m;zL{g8~QRtBjGd%PI{ z3#ju-10Vr)q3?3a3M`pMfP$=@RW*KHS2|5oS%I|B9H_7YiI*1%sF}XgC@X-7jqDb9 z0b$!JlmpoB;Gn@){_q*U3(&%Vs(^rs#^vmAQBdiWGT}DNJE~&ivZ9ck`GbP25Ry;r=6p0-KI9yni8TYme`o%JfUBa$Q zX~>9dUxuJbgwNNygIO5gE)48sk&$2qwQ%n(?rhg`h+Ev2Bi!PK@=c~&@v?}v9#L%3 z;Ajzz6%vCmE=GuuQ0a54f{MXy2kaKyHBt-!pZI%fMqj4Lce#r)p!sOiL>2o+h6=oXXE z@1DKqDY72XEheFYfd)t6>oB2$fd(83DtF=q)FZmZpr6G7-C}@x08u2(@QH?Bhd`x7 z5y1+U(@awYaUEDrJYz1PB03y@5-t-D4;5KyaHQ-Ot{C#VC846#ZQ$bQXMfKbOEf&J}25;n85hP9Y z3J{hwGfz+ul)jmVduL*J3cXeZK?`$O!`!JZC`%3tg3<<;XG&#IN%8aqQMT9}aY+#f zlGM1cq=*BDAEl^{Cm+8=U)|EWO!RyXA9~9XF$La5*a5BFd2lAiM}UYZ4u~m06JQFU ztU#hyl!QtTKLr&{{tnnJ4A3FQs>lki1Tj|$mBtjxTLW5#vV~P(QQ~-j#-gbWbE@J` z7+^IVpaf+BeRTW65|jWBdCdP+P*+MImr%hJ7{3B|b{%iBCDB2G$_iiR9@&E z4_7g)^nk#!Km`uit%4G|@tRe6{iv|6l?E+}4zv@C1|-z=fb=yuQ_OW2WJTWYfb@0U z!AFei0C*AyxSACQ;dtA^V4(vp?uv=f<4?khp~WO~p=cJ~TgKm86`AG(b_;2y@h2g& z*9UkRH61WgC1F_40bT}%^&H@3)FZknBzS}ecp0@E@kov^_5d#f!+H+zGAdN-0NbiZ zJd)RT#3MOGJ;2LA2h9V#42&ycUIsQZmUQeRkjSkSf5JcnJ3QSEOm<}nPZ$lg@8o)o zFDWRK0BFxs>*MHM9F<)66FgBmr_&R>F{==i)H4aJ`@+C;BaK~Rjp*cLRNZ-<~P zIjjiEZYkjjqk${TPLsGk(LtcflA?xgd!K|QrHQNf6Gp?c_4pO#F@<3E{L+tuVuk|Q zrhYC24=5D-5*t-OdFyyVQp&woBt4hKZ9Oyg>npmZw2?^P$S5eytVy7Z#T)L;lt3+E zv6KQz?2r`GX=c7zyo(en(rL&O?;?eo1KOKMNT{?m(}OCWRKq0E1CkUN_Q!nQ zcyFqNh91o47tX3gAHyV2cJ~XQm?1d+Qpr389=}vDNRNa(%I8y7gm9_w2XW!7%CwD^ zaH?jURom{QA}K9tR3xR{i4;i_W34HY;#%EaQ{_@AbOeQRsT`7>Lu!g1RKlggvvbPv z-;Q{z0&#;yzC!HR@T|10SaDaCS8+*#GOtn*l)Zf^f?_!L@D-(eZAnn(qzEfY*+pSN z;YtqIXUkEedZmmg3m!*GtbCPZI8ltXPFfbrIZK;?|BaBD(Pb?|@Nvc{XT z0X4CEML|W!UvjZXsPxTCK}9tT(E$ndZ0B3qIt3LyN^vZYMn%`_19l5kK#~DhRv=Bx zVkJ~maBi<_yfq<)uv30r|CZRzHD_8EBiseOqXkoeaI3dG7uwoJkrhE3*(?c_PkR+s z0A;bv2ozMB3{X}8%^BI@5|O(iCd}&&)?Pd`SQ8Ho;;Mzqka}<7)`S_aS1jUE+~PDJ;THGC zQS5w)M+PVqV>X*gbY@vbi8ynM6;wP7GL!9BTg)Tq`btpaFJl>1Cr9koj&7oY4jeJ3 zJflpUC9=aQ5-1G|Ho{e65ELWkwvSgq(BW*bE+}#~f7D0IiuS@IkBguMdwvzj1yrlP`DHVpcv1vy{d8Vx14A%KS5Hw;u5b1VFjhZDl1yp<)rLAbE7MY8@2STx>^^*I&tw?%6=mc^DaY}_45B+M%Q7Y^`oo1=5Xk+h2!rmv&mVjjh!{$W8ocNL^T9_#8 zeWF}6K~UP?McDg9`)DeAzcNOLBI)>-NO%zJC>759M5nk4dr#Y@C@V^PQYw3ov8cmu zC)B%;^Etkx8I7&B1r_%GZJX$=yIBx)W~ukJM29%zMFUMvwm*L@C44~dpo-4%6{ytX z5frsjYO@5&5>YFZE_mxzI!8nS%`C_lP875@B<`-VrgWBuA}Q?~A*g9%Z?6g_%W5kt z+E}0`tSA}<;`6qSK0#8n-y?^#A}O8Q9p9%$%UTpnme~~S9f77jdD1Zy~o6l z@d`z|dn=OC?iPxc(t&J>q?sMiillHRwl_-9eOh*-V6w18u_s!7sep232uvg9M&K45 z|D*#@#(WysrNtXz-N&Q=woeKsJD}sLj|TC~;ZZ;_ zFlGCMQudybcqLF4Kq#PSX|?_Nik8yJHj1S50Y;IO4h|D^zp{N2Fex2QQT@h9mI5fo zx(;{EDmrZwEfo|BEx$?TNCIV{j-aIz?Fg?(N~wE_q$>*{;<`Uk_P&D2Qjv=4Cw7r4 zptOI3viCH@BY}>8E2uuaAQ6(>J|1Ca(k$R3B+*viAxo z9h52TJ+ekbQVEphcqCA!P=c1CRR4g_rv*ETq~mKik8wD3yP%e0M8T?lF9DJb$>areG)LwMOa(O7(w+pZ&d+B z!>Zx-v{2%zpim3#+AD!Fg%a#(p%hz1QdDVfZXGm zrM0Qb-cuHj0E)>!<4=7QDiMVe?1}TXmCvV5e-%l`w|A@PMo9K4ZchmfM7Ql;uqO;l zA$u=@vH(Kad&=UGKpD+a0%b{fMN1E;_yu$I0M8U{W5(+~t@st}iFPDYRG;$e1yD4k zB9<>`DJR$~pftxLfii^>?1`5GD3a2qQHrDs3nAjVk1RAvoG6%#U#+Mpv>xD@=J5sJHPeD`!Jg<`Dna$ji8(w9=n*WQLOX8@ z3RP%jx&+E%Qo)`IZNQ~Sx*Xt{7CMeLuKOjiT%3Z*UP%?zr^9U|P_|9V-cuHj1j=$e z3g`h9Wwp?XGDT9_fK0IbN{0r=b-$k2J}H>&l~hoDRH%;6N1&hGc;5tXT0~Mop(@Ss zNT4jat7z!~oe9uA;{eYTbIr-_3%XA`6DXMMFxG%Oy~@O^TLM7LNpa0298R zCxULh=?V7KPHdxu&xfES%vU6({paGkk5(5%Pz946(1PkW-t8e=pIiCtZDsHI>?SOE zut>4t;eGo!Q6#0qET=WxL8CVMOgi<)+1LVr9>OjY33X=bFQHPRt%OSZ=P0NsSz?MM z>=q;;SHC1{qUl3L*2=szMb>#@kA@N|C!h!`fTQ(*-I{seC&;?+5(Wizr4Ky{Dt|gu zP-w!MOND4R2V$cFxdEj6-bzL>5+{o@lyOLFEqs3MwyURZwZ)Q$=4J zZT%^s@@7cF3N$+5T#}U+A%$gyGcb>jVSvg<5Kk=_ZvmBhZ_&g+$7DgQg4s7>D<`C2 zvKvdmWbeNUCW~GbOqRUC;Se3Zg$t0$#E|~ZnLPgeTVK=sfN?YtIsPn`g+$2=m!csw9XeL)er5T*K zUM-Yc8h*^^a}(Lwst8I`!{PH9g0ei5AZTW}00omhj4GJyT_F54h@Hn2*6piG5R}df zRxsJYr(m*BMOjdqtq}yJu8$&UW9lRbN{hx7Oy>J5nC#(h2}k{)6OTVc*Wt9f0y$Zh zGQObe_(tszltxm5pcB*j8AG(Aam3Upv24b?>nJRu-r-jhFo$1Fz@)3%(*m*JY)&&v z`v^`MFqsRXpkl-!iB2U{+74JkrR`gDcuWm=+6z5a1XK`W$dgK5mZ)Ye6XmT5>$;%d zD3Mh{Jt9T1%txdsmidSj1$t1i*6qr=E;L1{l2W#+uurs-R=}jws0F)6zbvx%3Md_UsO&v0 zrIkQgAR&P=!&kJlu#HkArP%~UQra#}(0y7-t6;LEhoJf>sbao3m+v=mgP{iw6cv-ByHn8Q*<Dks zo@gm;T%pzzuSO6grPCSX_SE}#lZ{e7AJ1IdyRS$(o+*Nd)8T1IV6rr%qWWm^;r!NTB1XN8q%wP)E_y#x_d${OQEFGJ>Rh=wbXWnI^VR3MPAo6jUFP&hUK1 z%DJ4%-Y+a=sDRQOj|9p>9YsqM+bBg+GzZ>3O%+Kq^GpTZM^(qRpb91{=uqs5@>(QN zwoS_3)3PfGl;wCNP^M6Vmd^B%Sdes{Sg4~&N-L$~x<69_l7h(&XhHSogT8Bypl(vIAOB{e?D5Q$T6alCt*) zuy}BfvK)^hDP{2}_C&h_DUyP5vwiFbj{-`kGYVR|Qku0Q>2iQ)%7-4tb$?yiJ}H>&FBsMr(wVsD?&%IDVuJX1dOFs}RQ#By;8COe=7)lal?PXcAzBSVDYR8 zZF;tsR8f7Jp_LMd9x`^(1d39JKh=?Ri%I`lBE`@9HN!DNrwg6ijU!QfWoI|cLz z77uC=v1VJ63aXzMmg7-CY1c1BOB3^W6iI1SwIXR|o~fYwneCH;$qr~m^$WX56;R$= zUN}oBi$_tY11ic^KAlm}QWR+tk4O0YGO;AQA}Jku7}xzWvs|2l$qr~i^-)VnZhQsw z2o?|8GZ0A?g<4sTM**eN85J$%ovGtzRLKW;riJ$S6LcS-+s=uC$zDkn)vxR#RX`it zCPhoz0ZI6JVmTf`Qa+tgu%}8}eJGO7?6pLZlnypq6bk=t3pWCygM`gLU&sRDWg zi>K1Q$%;ZHmg7-C>2${UKrv)^=rd`&#eZ2*rOC29J!+42q**biji|pQD<#@WsQmDc zuRuD@%ckx)4SMOlH$qA5kznFoG?tTSy#EyxOU7hVLfpf1b_R@Qal}8TjjF7`%86LQ3ZUm3Sph}X zghs97R{%%W_?sI~b2P0atZSkzJCt?Jv@N}aN*lmRsD=625^6i*bSdc9I$mE3e*h3P ztMF1*0Tmbb0k*}5i6}Zyc{3zs1<(X`ybd&8ge1s{R^y`F$|b^EhWBH zsUC4$XUZ>$D?mp4x^1Y!=Vv-lOAwUyh*1R1Oi=|vX<3efIhgCtLmH^+a(2+^B|NnekHX{DFRyoBeq6pOOn!FUJB|;A4Mfp8lfntX=daV36&;671TU2_D=U@f`*mp zWQn-4at649$zE3!Oy;D2@m3?oO_(c766YF%uVe?B=}KQ6=Oh%1_-)}&m-rm zuvKeg8~|liL4-Nr1i)lfvRA?apoIVtRnXN!yKO70%1>)WSKG?2Ye82VpY|TU0xR^N zZB_hSMaMLDuL!H!$AOR&Ag-$bWunG)wSl=#Bo%bE@zeU8$%8Rqnq5(Jwc#arJ7N)Zbw?R%*aw)}%956XuA+H5I{}5g!UGZu z1LC?0(5{PHY5TaY&J)^~Y=bJ_KhvzOvR9b5J6u=ig_i<_brmeHzQ3DW754#VoYv$D zQ1&WM%wH396-{Br>niBK2k0uA^fFO}y{fcH415^NPcv6v5Zb`pZJ&h$C3Q*eWzD61idb-3kBMGVMJ07X(- zXst*}=Y1%W(r`_Ylv2SJNhxPnk(Azlf~4#C)_rwZY3n{kQtGM;Ysv={D3WG&`zw;t z7X6B(lm)6tO1)n}Qr=KrkTlV5JBp;VP*stXPR&y!rR*X_QcBiUB&8`OMN-PxS>VG3 z@BMu0j_p?HgFg;qGQT(OO!tXY%tMU}dTvCp_3_GzPK;A7tSEJ)loh2trW8S$$E&O; z_4ouq>C?ZmqBQ3x2)eS2kFuhar6mYT8=ojEdQLrWS*Rc=b<33%rOgf$LHpIS_3_Gz z(wJNjln&ujR+JMS;s<_Z$s=V&X~#-oMd_PNyy^jzXIe%#;oT;@s_>slq7Uz(_>Gtw zu}(D4F?IS<5Ot;v1j1E6Xf8`{C<&ADtza@L zhJwjnw-rqG1`%(a0Tu$y!%3(#XQrH^7|lUWJP8$D>bK8P<#bLo%vWShl!>6AqH!M7 zaVwBeRse0Y2&yD&WyvGq+Rya>R|;*~iMA?|@;2>pr!SA6(SZl^@iRI)C_4icokIVA zqN(xIy3pYd3MSJi1(ThA3g&o^uM8iT3T>jzXcTQig$J>F36hZgkPPBSnk#(X~eiAB;&LvbjmoT6EYsbSN_2pi(PmmtsI0(DM|eu8l>Vonq6zQ;y9IR} ze{Z2ok?~=a6+q5$yqD1uZC4Ray8)9~Ru({KW>^X)yRzbq#nA+e9@v7UiMc{&+G#9_ zfd)8CQ3Xj0d&1~7tWiPf)0iM=Wy#?<_qio{tqOwDYWn#54TvDjV~-1(X?g0@5AopM zXFBvrkn}t-VJo&$mUKK%xeq-f*It~l*fM2-2`fr@$_gesp5kSh_;?nmDWH_CCVV}8 zXi+fPnJ0ZbODRa8>}nRiemtAJWy&U3KAz9N4p+`XQubu6tSHMUDwyoZQ&#j`7QK1k z3oAN&$`xLJXg3aFMaOggAtyVV6*-yfs9@6LUT{h9pthZw6$GUze+830rYV^0v{x`$ zY^S(mG;1UXO6xKdOqPRCFxeZTg30a=Ws}C&q_j+HQiPAEGcpxS_Q0cHveb*TN$gw( zAtW5vmFa+czR(T{(HYSdg968&_9*5i$-Ma9V@^E&(w2{-V2(fSL7yT?S4Gb8;X>hk zq2fxvFv5iJ?Udc4V2;0(Fdc5V*Mz6c@pi;}q6+)Y4!iD72Qy=ZCWRHyJU*lY=YV9f z1Pv`LfvJ2v%?T@@v=w0d>p8bq!R&$c*8L%Te5KO>70}@WyKAeI$R(^Oom!}TJRJhA zfYSVk@byR32(?CQgp|kChJjeyx-X&9%9}VU0w#KoN~rwZZi@QO4G%)BW33|Vw1d7A zmvyGC1*105PV@Q2Yv`E@&@;1qG$?%+5x$<1Ho`|0zJB=J;*QDONJUWE0a4NYWn!MW zgqr#XZmHB#qIpuVVrgWuh7$)k|9Lm8xT=D)F*uNbpy!>~T2w_&#t03w79c348plu5 zMB7RVA5W)iDVU?P5q&*bHUf=Ug5e%eX;VoB6&!2g`NY>01Ot-ci4#HEDG#r_?3gUS z6=#3}wXjDgVNFrMvVB4;Yl`CN;m2N~ts0dzXT z?U)B>6TO?_eL)~8?bj!v9zZ8XQ30hBE3%@KHnDsOwXp1=;+-Ol9&S^O_9%|qX&e4h z)G(xR^h;649Q{(%G1*P3tS9r$6di3eZ7!ki$e)B)0Pm`!--{YBhkJazApr6Cly4vX zUev#x1^SAd?95XznHM4W`V+1_h_V%sDyTfi7ytfgX50wDhs0kQzxxxN$RqgW(}c>; z?VS?Vlok+4YuZM$Bie+aY|J+a7ZQLJL_4eq=RT?k*{hj^3Lfb8{tJH8#E0j^wQ8Xm zZUu96f2oE(4de9`xmdDG%D1yKTES$#nWRm$KY4s|WScOKk*w)FMN?-0WeX5aZ~~KE z(E=vzrJ-OlcTd4&G(!dRfIXtblXHps}vatvaVrDY@5*Rf-HanN~>HYP-a%bd0HsNS^{M^pK?ppg&ostPGJLp z(@T^}Sb#>!jPX;o(T*GfCT-HKV6tmp!DQ~4g2^0n1(WgXgvY^2whwQqUR|NvNpa8NULBGBFfcYhgi^f{KO* z<9BNTw`u%tA)UfH^Z92FB;Cm30l|-eaED4pC%*=5zIxL6!Sn*s4 zCS9|{@;rw#ENh|%fwBULb}Lzyuwo_JT3XQ7L@EA?q;!U|1j?T36j176gqxtWp0H*o z0RB99tR(vW*N>erC?kFdpqUPWkw9rCH2(Q0#u~p-d19_`ck6>21?Q4V8b47o$Z6a6 zpK_^ynaO0$;isjwP+o4FkiR0oN}P6O0V>T1NvK$X@tcKA6H$S4y;4kF6Pg|p6^N%9 z07{crVJ8@%>|9YKrEP@cT|`^r^@w2eL{FA6jT&s5)%+MYoVUC z1j?Kh1r%K>w@&~Gl-(@xb2Tlr;jIEn2a716Gy+<~K?S-BG8aGrr4{}PDCLtXpySIE z5}(o$cB+8M5`lt3t#rDU0!r&I!IO@qgR_%!y9dR6rZce+Zy_NSOjk=dviEwB}I(rEL-w z(3PE15-4*k6;Mi7S3q&~Z6DGKC>k)12d(TpRV1ZD8YNKns4RejTs?lH$^lV2TEH{M zSNVJzr7NJ6v?hVFWSRn+n1il>(g^?xDD7CUfYJ`@@myjCUyDT33Mg$|E`hT1R03rO ziU5iZq{EZGn4QSd9+ITYK~q3cqPu4ow$>7AVKKUb%3E9t99rakSeP2OR)DfNO#)?}x&nHp$Zqw}6F9ULEtAQ? zB5-Icd?1pe6WFeJoMA813Mx3XL{?$5V64M$>t6N9_6lDTd+rD5_}dzw%m<2}s}+MF z$mc7dl^uWzXd9pVLWgJe`SFxWUD2vybe^WJGdoiiNf%b_h%8o6_rZ51U$0<}4^+X) zWZNWY>B=cd@mklK=q(-R&{lMQATQGjhqm(3YwzXI{^tkJo`3)SPWb1?KfihX{QHjj$q#S-aE8QBKYRV+>lZJd zzj^WU>xb|E^8K5~Z~MRMSHJoBC!hbz!$1G;htGfe>BBF6_2~x>(?|1ZKL3TUpTB(Z z|Ke|)vGJ2nUw!-S$eNpL{;A^MAbj^pih-_=|si`1Ru#AASD%`4``R z^x=me{`&E|*N@-hm(PFw;rYuiA3neS!K<(E&#%7x;fps9zkL4khp(Q0@#cruU9?}k z{OZ-~Z{Pl{pM3tyU;Gqc>qjU2_k5bx52w?I)AIg*E-ip@tOUH|4-M#?|%RKmyd6r zfAh_YFMj>%hp+$e5_{8i^7qfbfBX~*{rX?A=UqAf{qzx9Tuk6~PD`s8vU*zE2l!dZ zXihNA2w0X0-;N*Q(JF%l)6lXN62Oi7VEX6;IbQ#W|0Cq-Bm6}qI^mU~6tk^M#$JB; z>WANd^Y|NV#+T1Ne)IZ=$G!nqLU)ab2#q;Tb4F2eMp6k4e@_b}-1oDQQg=&@NWE07 zOFm7lsnFlk^Oy3|WhXe0x>(~6Be)e3b; zeW`c-Y~)g}QK>QQsiG5fEgAaJMJ7KODQt=gThL)-Nf>Gl9|0HTS>9bg8!2@TO8uTg z;{D2eLQztIQ_(Qf3>z|3n@dn=bSYnPsFfAmL&$VK+7>W;=7#@=pfFE_l2Dg5=bTQk z!ga<`IFFUO2BpRn`4if2;Km2TY03SJKzxq%oEN;PVQ5e~%QtjoTTsR{muX749a6=d z1iVL|KHBr6ks3Tj@4nO068cQzm~9DnT`hfO_x^CG@ET|`(5-z?I+=$ahxD;!KAKwbD zJ$NF6U5n_2_r7!OAN`?!_^qMp5WVj5X~Co?Tp>uYqXkxXhxYtvsLat@4>dX`9LEdB zsw~jsE;G6O@SJcW&p7eMDs=SDgKLYU7(K=+lI}=4c4uhc z&xS5_^wz^L)$ZHFcV8fN9|;Dln=s1=o;=PzjGpS_i{a!W<~2uewNu~X^M6Ke;vBuUknDh$SP{C;3I2FDgnqy7 z`{7W@qjy*Dt={^7VfztZp3l@BKYE(XJsa`({U07pD&jY8=EZ-#`@7HIAYt?SAKvtT{Ohw{efH~Le)4a~ z*ucg4;MwP&{pJ_H{l#a$LIMa0g%>ZseDOv9wX(p6_{0Ejm57eM5fjD&d7`7vL!TS9!*1#oeIXkHTr#8+Jau{zfhPDq%A0r6EAz~lhY z3@Z$Xuet#Cw9(Zr_Y__fus@4l0E+{JPK5#SRTseO0HIT1Kz!8&usJ~JR2a}$%H&L? zvxLKl)>NFWOoFZSkqMWNo}97tm)fw5##kn2E&T-~jA*Q7a^})Y48w@VTqb8Py_b3z z(b&u645oKth$8l8BUd})ET%W&3L_eenViXVj%^sxn9SsCW)^Iw7@L`$&CIuK=0C4; z*uVMi`4^9`AAa)btCwHB`1*&}&ynr^X-}Z+yWfhjvDw)el22Ew)D?waaK+fz>};&F zB`)i}6Vce%>};&JQwt*+8=IYt_4yKEL}O#Kv$4h4*v_vuHa0sO>(ALy89M{uVq>$j zvED!}+f?Hg<)0Z4t{q)&F?*@bkw%KfHPMF#Xevf521J zOFRIbfB4Cl&%eV1*27QU{?YG#_S1)-qz^xT{>2~hKYsV==N}?9v;-`u8XI1m4R?CX zWmWs8aSQ77ugj_~&L$UQlRFWOO)kzRksXW6Xl!zEHn|v^+$p26$;H`ZuhQ=iO80vyXSmXl(NQzIf#*c3w&pvC|o@_S)HGC(wowjZH4jCOc&%jEL{LlF`}Z zYHV`fIwIwEg}6GKSp}QHOWQS~vzb+}nPzNebvDyEO5t@hHnTdL!Si<<(b&xDY$gdd z(+3}1_Ihm5$c_B#FS@~wR->3wyc&wSaB z0dGd%|omeJTub~aN4o9Q{5tG#wM)0yc} z8GFv=3enk2&jExHjm>0dGd-pcBO05@&SrW{A4W7bQ=HB8Zb4y0V>89sOc89R=WH%J zQ=H8d!Df2S<_gi-3|JoVuQoPQoXzx@KD>^`W{R_!D%ecV!CZZ{vzZ>#M`i3em@7nQ zGd<=GBO042&SrYd9Y!=ZQ=HA@^ zIvSg)&SpTAiz6DF0d3hl==7L7ETgfR>TIS7Hq&z?S3BcurdKRPW$ZbUD@12AJ?0K0 z8k?!kW_rvWMl?24oz3)^JB(;-ra7DGrBq==V>8X!44&lUh{k4`vzZ=qhh;Q2)11vT z!Df1n9%`|H> z=MmI8>}YcuOfuo=s0K({4xK(3b8(AR(`0eX_;vXIlsS`E6w3oB`?25sY=l!Dpx z^v1Q6)^1jClj8er>;`NmE2ZT(>|9G@IMc~lPLG(wI%F&dTxlnzU^{BAgb#P>d)sh`{ zLR#x_YzMHag%7vZ!h(kKU!{n^TG9LDAPtSH- z>!q_EOL^D{X|2a`9#+eF*a?YWyOPq89>59~*3w#!V=-WMhyZEt9!Fz1_tA{%Wlwor zf4IAQERSL5T3YLIL*!W-!`weUIJQ4DV`4?rer`DR(vls*B*H^2FMm&G78w-ZtmD zBCR^OX0I9E*$n4?7k4(pyH+1)Ar|+j?res)N_1y4yzLirXEXG+!F!M3JDcIH_1xJE z@2uy}W(Zi%|4-Qr_ugDr-NOujwNrKIV?b}*eH9*B1`#?bUi&CJ0S$x5a#zu`Q2;dj zAF*s8k=!6 zRSZ+Op*`1}hnn6zq;J1{_~*xO-t2D4g;uHNQ(Q+Ov+Lr$ zk(WOMn=!nn_!0B(vq0C4!e$FGr}_H++=*zjg*I8Z{I^N*KW+R* zv5n9t*9m>KozS}%L(@0Kc0!+4`!u)OR_Hq+ZLZ%XM=vLMI^{%!d`c6pv+BKv# z-_>?Rzk<9@%>Vpf{?}5{!#fMX*vC0Nym-0$9jx|tZr3un#{rvE=`RJ;Hu_x8Ye?7p z95X1d_j4yCUOKL%bluM}a#nz}=H?29SKI!4rtac_CMbVY0b?wKwoVG^qr8_ z+*}9r)z%E}gtX@7TA*XFYkYfb3-l>DbF)3rucW-TjeC%E50dUd5}TE2d-vJ%f3cnW z_Bo~ZAn6_?y&c_ZTlVeKo_mmlM?hEkzKaJnpWZzD{I@@Q`22@&zIpu1L;EN#U`74z z1%~DB9aLEDn2^cM30Z|XA=P%)z`SZpXb}d5)LtfZaA&=fNUzt@vMpC(T1f3I(rZZjPOu8&LNL(W zLfY)*D$EPPoOuiB986(gNbOBeuRq+ybHc=s+E37HNM}95$dKCeOjnSu%f>2n*{HV5 z#^l;;tisTcYKMkQZfeLXObw}aYRFWa^$24_YHxaay_U{;giaf^&u+bjbk-vb4ykr< z$W)y52$Msqog6Y1XFbB`kZPN4Om23_Ds*LhH%Md^28q`t3DZQXohCB51{_Ifz)|}f!}W(->q#fWy5F~!{f*%o(ppav28vWW zP-J!kMUpU3q}mo7vl}Rqgn=TpKN(y;e0Bpx(g`{i)k|BDIiIZcBwLcXb9>C)GrNHz z$rfeqgf!MOyMZFfmSygQG;z=D28txh+Smta2a3#Yphyy0a8%oZV?H_S5eAA>o0ObS z&U$QGa_5KR*RJ%^)n_JKpScs#+&!~v!I5l%=1xd!J+4AC*$T~_kml~09e*R)63v~E z)_UAPkz{K$cS2h0aRWt?Fi@oSe8}~VySv9`C-+Hdvy-zMD3UCPV<)7!d*;bmk0o*J zgfw^0>;{S?Td27c62Eq}mM%k?Y=&|tq_rN`f+Gn7MQYE7TuW&^x71_n=-p!nip;aS zdxU`^wdX^wrL=KR5?XN7o)5W(be@|qP^9*J$Tg(1o*r9A*U}CYncYBrM2?}W70b#yN3F+J8_%xVIN56B zeNy&($d!$|f{@f>>#&se?s3(|$yOWhloG#oC8gu3BOKt@SuMUb1w&osiag933xNI^I4=OUIiX9WPlr z-cCqsJ&tRT1g=4|T!Yzh4U)h$XqIa*JFYPHp%QcuC*B}dAgJ!t~bF&XJwpjocL;PHp%QaXW*B}dAgJ!t~i{lz(fosq#*8mN^O@%@hxCYIZK%vFAgG6R3m{)JM z7c`oDJ4onQ7}Dh2&;!IlLdU|8Cg-*|u0a;K2F67o@V=ddE>sEn{5e=e%}r<{@&AUPiS-lagfllu$1_itL<@I zgDh|jTF-}ELptjbxCYH~4VKwikH9r(mTQ2HAZ{&@*A1_wy?bUG_hf-<&@9(rncdwZ za1EN}8ldmD{cwS6&@9(raa@Bea1EN}8Z3@$kOi(mvs{D4aSgJ-HE5P=usE(k7Ptn@ zat#*8HOK;6oA)WOIT!Ys0A=i-3dIYXPa}AUo*B}dAgVysQ z*HSv`5x54;at#*8HOKl-vcNTHwpY;NxCU9^8Z_H02tBgx z;U;hmn(aTiIIck!xCX7~L#~v_aSgJ-HE2B_at-OMN8lQ?o)5W(ba#)yHE2B_at-OM zC(bokPnK)2IIcmCa}5A#UP~9pHOO(U0U!<6U~yc79OoJU(t2)=Yj7T{6mwtzX+1Z` zHOO(U0U+(&)_NS*Aji1|fV9@*xCS}SH2|cw9>+DvajpR%t@SvrL5_0`0BNnq zaSd{uYXC@VJ&tRT<6HwkTI+FKgB<4?0Mc5I;~L~R*8q^#dK}jv$GHaU$#M-A$2G`t zt^pve^*F9Uj<FX|2a`4RV}o07z>+j%$$PTmwK_>v3Fz9OoJU(prz>8ss?F0Fc&t z9M>Snxdwo=*5kMaInFfzq_rN$HOO(U0U)jQIIcmCa}Cy$+B(ajpR%t@SvrL5Xt>0BNiT zF{Me6l{nV`kj8r8Xgf&gSoCnSTmyI?4iY*RhBVfLBiTVh$HI`tdZ4EkGR`%?S{m!Y zKRZb1SXfG9J*(pylsMM_5T>8o>bM3a&NTp}v7Xg&4N9DA07zp!tK%A!IM)D>)_NS* zpv3zc0Mc5I;~JEBUjsmzyJvM=gA(s+07z>+j%!fjTmwK_>v3Fz66YEK(prz>8k9KK z0Fc&t9M_=4xdyNnYdwx@P~v?J0BNnqaSckmuK^&f^*F9UiT5=Cq_rN$H7Iee0U)jQ zxV{D@&NTp}wI0VcC~>X+B(ajpR%t@SvrL5Xt>0BNnqaSckG zYk-TvT94xzlsMM_kk)z}*Pz6?27t8Inj zTI+FKgA(T&0Mc5I>uXTrTmwK_>v4SzN}Ou|NNYWgYf$1`13+5qaeWO+oNE9d$Xbu% z8k9KK0Fc&t9M_=4xdwo=*5kMaCC)Vfq`i9_*Pz6?27t8IX< zAg%Q{u0e@&4FGAa$MrQRajpR%t@XIR1|`ll0Hn1Z*Vmv3T!YDS4KR7iMrQ)oV6t2T zOrCO((6L~^H(9O$CQmuY_}w#Et^p=bIY{VOSW0U>j%!c^uEAuv2ADkMq=b%zrL@-L zxCTYw8cddJfXP!_9 zgCcMZCd)OzASoxMU_F*=fI(6YQm`J&HNYS#2Z<9pyq5Ovaa@BUa1AEQHCP?jpa@)p z$#M-aCBuHWz%`gG*I;#AgCcMZCd)Ozlnf`OU_F*=usW_m5x54Ez_aV`QaBod-w=V zN*_M^*~7nn^Ze!4k6%9g^W*c^FJ6BA@DntX{Sf^z+E4e6Yg#AEU05A=p;+!hKagM*a>OlD92qWwok%7NXuQo)D3Gombj^sULb2S1osjso3-Nz- z+=XJf3p*jL^*HXrd4_O!$F21^?n1TPg`HAb>v7zL^GM*Rl$N`IsT;<6&Le@tkk)z} zccEJD!qtagpTGYw9eG&;(~;N7k{wn@cBq!@(EUh$z*@2c#&o!q>Rb4)I7ldE_`{94VN8dGv}A{!QW|r^m<|UCr3_1H z%nf5Y9Ha@n_DN~U4j9wnAdTyI1$k{7_vy&@>BxUSXz&C>&#vWM#&j`ZtH)>`acvs= z0IeQdEk^SQ0nl6;HvB>B2m#PITsC!ZpN{;^vyXRfv^o48RR>KYgpDz0zhmkwmZ`H- zMsxH#qRwK8Iy(`~$?teN=ok_IYRl7cG#xaI5D<;UIF`<0Svvc^+Ol*UNeAsB1Q|_; z;y60!7I6dde%t-xx4-!8SC}Vl+ygXCy0KulCs>?IcP~f3_1(}iNdPqVYdtqKOcDT% z`C7jX?UDpQW4-s=&XQC2oduSh>bR-sk`&(+%T0CER5VEv5OE@1RNFCA(IZJfyx(>o z-*3BTAA?Nzf9AHk=bb-BD%)HLnD%UL!F%5M^^525-}@2FvsSidZoTK7zj*u}_I=Mg zhm^=TRG9W`4D!EI-g*9yXZ?+D`ltRs`orHpzk2=n@ad~>zx(FJ^OtWPe)osR$8R2% z^vT0do`3t{vgSGP>SxQ6Fi_Vnqs?-3e~6p6Ela{cT?c7yv7L}6X2U>T2Wectosc%q z?R>v#eZQTM#`nWOT_>e+{&qqd=MMvQ9i)ksc0%IUE*@%f$&PB19Xlb-<(OQyquOl8 zPDo?k7^rJM+@?GBLE3Z&2I@LUlkeCGY4RNysOun2j&LWW$q{0pu7eb;$Cf2wpss@y ztjCrmVW6&q?BDwLeDKZ>x7OpzlBz9B+6if`$CV|49wA7HfAf{~xU!^b%aV3VX|2bV zB~@FNv=h==k1I>6wk&BMq%BLrKwZ1zwk&BUq_rMbmQ-z7(oRTgJ+3UN+OnjbkoN9z zWl7bRCGCW?caJMes6wk&BUq_rMbmQ-z7(oRTg zJ+3UN+Onjbkk)!!SyHuSNjo8}^|-R6YRi&#LR#x_Wl7bRCGCX7uU%P>D@&@jENLgC zwH{ZNRBc((PDpD#t}LnAvZP&*vn@-)KwWD+wk&BUq_rMbmQ-yE)SZyldR$pjwJlJ0 zLR#x_Wl7bJTipq1t;dxmRa=&{6Vh6bD@&@j1?o;nYdx+ksoJunosjsoE9-G(N!6Am z?S!<}P|>&J+3UN+Onjbkk)!!SyHtv zPv3gC)wV$032Cjzl_gc%0(B>(wH{ZNRBc((PDpD#t}LnAvZS4m__ZtRab-!> zmL=_kwASOwlBz9B+6if`$CV{j+X8hTq%BLrKwWD+wk&BUq_rMbmQ-yE)SZyldR$o& zsszH3?rh7Fk}FH9wgu`=DXsOmvZQKTpzegU*5k^Os%?R~6Vh6bD@&@jENLese(lP7 zTv<}JWl1|Bt@XIFq-x8Oc0yX~ab-!>mL=_jv}H*csB5jqwm{tpX|2bVB~{x3btj~? z9#@uBZCTPzNPG9VvZQLul6FE`>v3gC)s`jggtXS<%95%rOWFx(t;dxSRa-{16B566 zWj(HpsM<23osiag+;eWVWkfq6t@XGvqH4>C_CeY*A`H~E)?>?vc0yX~ab-l+wm{tp zX|2aS=T=)rv=h==k1Hdpwv1>eq_rMbMpSJX(N0KfJ+6$X+A^Y@kk)!!8Bw)mL^~nz zYgg9e%7~h6fw~jYT8}FuYPO7MC#1C=_ng~o3)Fp(wu}e^b&d5j+X8hbq_rMbM$~K> z(N0KfJ+3OK*{YzOkj8p2P}hApbS(HdGusxZ7^v$YyI`^Rp4qlQ#XwyL2^|YV8tcJ8 zT?Yvr3q#_|F4lvAx)#!MOLuOMu^tT6b&$}pu$0DnFi_V)LdT+zwweM1bsZ#hEDUL^ z2Lp8-Bu?lsq_G|h)OCN+U}>#;3RF;Le* z3f5y=pkkn|g%r33vu%Njfw~S-upZk2H9M|B6SxMm+CkmT$Tf(%wCeYtU?Y#ZE}$xnZEL+wqPPynAd5)abseN&J+=iZ2I@M7^rI@1+Kxl&h{!1 z;kX7(;2NAOZLcAn^$1*pbFJ+)q`P|ruEDw5_8QVzkH9rJcbB+^bk-wq4bJ@~t{@%P zpb1=qbBBp*NO$)LT!V9uiEBugH4wN4=d#;tNM}6)*Wg@tdkyKVN8lQq3vaI>-Q6Q_ z4bFWgt|6WE2wa16qls%sXFUSf;M{5A8q!&hz%@9xnz)8^)+2BY&b=nCARX7B30#A7 zvx#d+XFUSf;9P%u4e6{$;2NCUOk+sHi*135fx7nYxyd!SZg6ogIh$-6_+E1M z;%$*?we59wW$-4O2ELb^{kWDw8hEm4;Csp0-`6r8icdBToLn0CUUK%f9($jS+ca=; zY2bUwS!6A38aTN$@V(?Lw3blci-(n58u(sv7FkQ122L&wd@nf*t)(T8xis*-n+gt`RezQv$rSFz2xkjPjoLi3*6(DYj7_) z`|$|Amz)KZ=w5R6_6WY0oV`1O?$#Vly|o_4HE2S6+k45`+h>n^$=Q$hxX|AA zUUK%M61k$8d&$}UQ~h3Y_D+dhd)sy|ISVLJANO;~SZCMXw%tq4B5P@wI@z_iZU2o* z&VKXii$6ZTdHBQQ^DiI1c>dkP_g}nz{L{n#m`)!q^TVGXP9K%@?1N|Dy?*iSi#IR+ zs}Ick_rE@S{^rf=7r+1EP5;NgKKs>Yzy9SX|Mu)-%$7G@h-?>?bG`SaVbH$Ov$p@8 zttC8Py#JR#d3}}u*`*e4{Y{P)2W0$SG zJy&;!0ga`&W_S0Q%1G$%(?wh2=o;Of3%kQRW7 z@7_GVe)!4Tp`X9|*-sySl0N+W`4@l0|M=afpMQ8dVvC($wiD41`duyAVq1#sL^M|JI*KiJ zdf84yW92TpyV&7n`w(qIG1pIQv9rr|A{r}qb!3YjUA7Yuzjg^aTsN`BrgnECnw!xz z6T_6<>#mbK5sl5bUSf-#TecI?*o>*XqNyl~R6t2s4n%zXMW+!s>CcG@l z0;KUvvYW`&Yv0pgnw`kC6Vh6bo5JCO^J z(6KP2wH`Z>3y{#UFeJY0vX)2=T%VVKgpP$Fjr9~ekqeN}u`r~uo?<6*0n)hPJ9pez zPq7oZ04dx(y=(aOTAI73p6o=fol+X>DRv?kAO-8`6s~J2o%KwD^|;qbJCO@g3f9xR zhF?o*UMK-6SdT4_Dt00lAO-8OtyqhFqy(g3J$52ju@kufDOiu4$W`n_EcX>&Z^!+Gjm>B3H35m4Fni$CgJG`&0=?!FuddWwCFSfE299wqh;z zu@aDi_4KacR|aWcD*-83PwyIj1!*U80aCD@PT{(SG<+C93f5y=u@>8k6_A4U*oj=l zPUQOk*n7JkJB~9;_pfYJ-^hR^RenTd2Jd9)^s#|%i?Dp40mkQ|OqMOe6iLw3v>V3! z_p@S?X63WGIrYXn#`HmV-bt^C7Ey!%cC~lqf0X39(Lr~c#*!}@*+L>Uh2sX^EhwPC7Ey!J92Hjf{^6++_Um3 zedAraB*)#evLn~V%XCSOyJuxbu8p_pk{ox>$|%;2QLK_2chAa>TpK%bNpjphD?4&+ z?8qg_ardn3$hEN}mn6sCv$7-C#wgbPmL0i5?pgbJ$iY4A$R){f_pJRq`gzDfk{!7unQ%`(4>?NOzK2n) z!LLV8c9cXVfJT{cPd^ViO5(mpk_q?p^N^#Yt=w216?|~Ir`pPmQLI5px`$D$`z5{XFC-Y3^Z1 zuHY!?9+pRGlnM9r^N`~x%{}bM6&xkq!;W10Ejw}rCFvfr29iw7J!B0wvIde&tlY>N zY-9~2*`IanzGv;{A;+)B+>>ApL|IVM+>>ApRz|UIWDWG-3HS8#ki&zMHIQUt<<`$b zj*>R_Bv^yBpNAYJ%{_f@J^YQ+J!B2`+XQQ{_VbYAC~fXZum)>C4>?NO$}PbftYi%~ zvIctagnN2D!Eu!4o&;;K_VbXVq`4=-8m#?1E$r^0N8cYe+ zU}Y5RW~{-KU=7xO9&-FF>7FUU8mz2+)*U;JM5hF6u(JAD7mp^Ha1WzcbsJ-niIrPF z4|(`3bwq8FiMfZYfzItHnP3gpejaihrMV};8mwduw8OJeCRT1_4YZOr$;8}4)<7#3 zlT4f%kTuZHxJl|4dUUlx)?hc*U`ntCD_MixSc56S8mwduc4G~u1Z%L8HQ0?cm=dhP zO4eXE)?iAo1}j;E-B^Pu!5XY&4R&J4W{jWw7OtiejwK#hI*swY^3m8`*TtihCE4OX%SyRimS zf;Cvl8tldzObOOtC2OF@zV=xrR&Hbsc4G~u1Z%L8HQ0?cm=dhPO4eXE)?i|-eqSIx zTHmvhHBe(;ewGQ=U?pp?8*4BnSc8?U!EUUE$r|j&8cYe+U?pp?8*4BnSc8?Ufg1brvrMoCYd;S;?0bwgm=dhPO4eXE z)?iAo28FD_ZmhwSU=0dc12y)w&vJa9%ZS2yp^z)Fz++(c4lwb`C+rI9`8cYe+ppZ4#tGOq^ z8Wcvc?u=s9XPKCL`gzFlvo!Z4ScB5fLk^P08cYe+ppZ4#H*-&dH7NZ&!6n>7)?jC@fh5OItP5F#-B^Pu!5S2@2D`BaQ-U=pWDR!a8tB0ja}QaAow){* zOt^<_Uw2~-rUYwH$Qta-HPE5!IH^;}8tlw9kmUG%Pa$it8*4BnSc5{=U}vs@MwxIA zS%aOq29iv;hpfSFtihCE4GLL<-B^Pu!5S2@20L>N^xz5ikTuwuYaq#ld&nB>mTNF4 zSc5{=V7FX@Il&qfvIe`c26KWnC}a(GV-4m6Yf#70*)}R?{Feh>i3R#0@tihbfH7H~anz06RBG;ghHE6~f%n8<@kTqzQYcMBR zgF@Dz8EY^nat#VugJ!J3oX9mOWDT0J26H0UppZ3a#v06tT!TW^pc!j0Cs>0*)}R?{ zFeg}pLe`)eYcMBRgF@Dz8EY^nSc5{=K#hI*OO#*@3R#0@tihaM4GLLNqvs{BY!5UPu2F+N5Il&rKvIc7G z%g-{w8dS0d%~*pu!5UPu2F+N5Il&rKvIfmqgE_$(RI&zY>}#Lp_-$z=YtW1}m=ml) zC2P=(HJB5uK_zRTE*bXVXKoS0@ z)<9h{?7B%t)Pdq!%ts0Apb|Tfruitr9aM4$(lj3>z=KNgK$_;G1bI+N z9!S%Clt2$E(F19kj}q)bC3_%E^HBmmsDuxsX+BEO2bJ`JG|fi|{Gbv)kf!-4!5>ue z2g)ciA0+^UN&rEc=A#6Gpgx4hiU4Vvj}i!i8WEbN`6$64s1u=SnvW6?f?5%pruisA zA*dIjX_}7`7(yk6pzp|hl;9B5jnKwvK1zTHYDZ|A=A#6OpninZG!$V;pa^P6Xqx7u z1dC9~A}B!2e3XC@Dq#d^nvW7Rf_f6#vzw0+I6@_kpmCay5Cf- z(|nZR64afLJ~A+2Nq`BJV1mYJK1z@Ym1Kf6%|{6|K@AG++091@HbETRo7>=A#6*pyq|9X+BDD3+i5In&zVfxS;lhrfEJ(kPGTxXqx7u zL`;Gj7@DT}D8VkMgCR8yURVhNfvgN>B{yWk^lK z7?uRapk{`qX+BD1CT!#wrdtCUmPBZR+8Nq7%}0sU1obmCP5S8C{%|nxN(~K7lRmok zKOELH9~sPWZGbqcNti+35q)&+fHHfnu+tAnv{q1l5`Ky1r zd7_pT+-gmRMqFDhJ`Asa_m9TzZ-z#wTxwf^8cPc$MnPD3LmLnBtA5kXD!k)aVQ(TJd?`N+_SYv0A;&(nNl zXvDSg;;^Rq$k2#u=fz=7^O2zu*Vc=}n&u-zBd)y{hc)$89(`nJ#I^b2u%`LQ(1>gI z#X(K=Q?zlKkBCNu-cL1DG)jaZ3B1U1b^hDNMJBZ8Xd zBg<~M_Fx?T-pxmbMqHaP4r`i^42@WcMg*T-e|Gedp%E+5h@htV$nqOjq7gAoLnG7< zg!2*6h@htV$Pyf`oft>IBSRz95X8obtyXZH<|9KRuDuwC$7w#Y5Ql3s#$iqKk)=3X zyD<)HnvX2T;o6RISkruDIS$u;jKiAxDvv(0Act#1#$iqKk)aXSj*O$4hDJ<=MqFDm z4r`i^42`(2U4MII3xA#AKlk*XE4Fn&u-*b+~qC z9M&`+S**jgJ>#&Z`N+_Sm1sn4jx#huZ9+J25{(FInvX2m;o6~b_}R@z7VU6t(KxJW zKC*0wYmdfZP4kh3J6xMI4r`i^EZyPSrEyf#&rm5fT;c=Re zEa2hVsBu`+d}L_EwNvA;rp-qd@o;U`IIL+tGBo1at8rMi>AK|L*l= z`f}DO|8HLZ^y>Nj^XqByt~&~|NH;+{Wm|md{#bxdiU&4`iJkoe)_oz_?Phc z|6=8VJOLNer?>85#Ip3Gr~gufqj>%;MZI&witrOpzopoJdiB6DeCunSP>rLiMJFn6UDx3 z76bCUTZ($OhR29`h^O6BOn8QcfIRD#V!|^l1LR4!6ce6d5g^aGrI_#xO8|MwElxM# z85RKYj9ZEc&#?TDC)`pT_ly<)F_u`0bjxCjvPk=pKgaZ_Q&@)Dpxb zg}svm;kTe5<|r@|5`^7?f}Em`s}l*rZ9zfIP@pALWY9G}{`dz4F+t&8R)X+aP!RJI zcq0kIYB51_dsyK~5KapUVs^qdNrEt1P*6|xa14sGZwbO@K|#z-g!QDDu!_Tad=rW4 z1;+@l5Y*Ec6J{|`4|tIj6K*j~&+I}-FZk533lTk48TTzv9KZY45NmEV}xf2=4p(d@(gCXAMXC}E;^s-5D~T)Ux=sJ3!4S@*Y~k0 zO`3QL@r9TsrHSVVYI2%XL&&51rHPp`sA=vu;Jt9N3~FMs)U)FkK;!H(AE&pVCgw|N z;x}L~oHB!&{0&f3NPeE2HG`V^vxg}}` zzXd@}`bdo-O%pR{P}6+GIaJS{@R7}-Y7J@QO!&xvclCxeP0XXgXEz@i@Lo8R1~tt` z2D}%}r9n;e5oc5Vyka&DYUespQ`I8U z#+mSu0q-;CRgE*@BMb0TlSmt9!bb+Yt4pM5CVXVTyV^vWX8)=O=OY8&)hCjg1m1)1 zlKIGh_rd_bpr-!p=pzH(3j_ROnntOsRir(8Vm>lTUA-brGvOl(@Kdu$(@glt0{ql1 z(lir3;u*c_G0aCir4N2bwyxtjy_Tm5A6bB(8b;c)_n{5?$O8P-F_M}*s}DZA`G}|W zd*Nw)P*Z<)^bybNrI}dQ@w{H&yZMMG_SY5e;~Njd)YUf9K2R7bDrze`p4;o`;iRaj zE$w)8FHu-2Dyqjjeos8Tmni0>sHmBV2lx_&nWCb$y5kwXMB%2Ws4ee!jK3Ei<3~l! zPdv$&DAspTQ8N?|^Cb#H#YCI&>S`p(m!IePQBhms@kn1IO*pDqn4g+S+DPH3&~H?; zFh6yZG))*PsA+yOV!e=94{Dm7j94!W^9yR4n~Yd54D$PzIh86W(4?h;%8cGqTEU~BVKPU%9 z%(_zSB7;xOly`0mr6?y2E8{HeJi{D!?)0RX@C;Mjxy@6Ibiy;t zaOWORiV4p!!JQjCDJDF_{T+9AQcQS;>FwOwNipFWX18-+C&h$knB2}yofH$EVR15d zbW%)shN=($3wR6ce6dMmzUzQcQS;3GFOGmSVy)%x7l_vJ?}Z zVLCetkktkt;TdMLv;0_!3C~!UdEm8DOn8RH$1FXTV!|`lV;%&C6ce5yqE0|viV4pc zpiVwrk_ppT85i+%NhVy=i`yP{T^7eK$%JkC@y1aS2ZxeO_@Vk_q=%A9+&fl1#YADRi5A#=FSt zu!nOG8FY;@v2b$+-R2$!r5_A=yak$-H~-7uesg*H)619l|9WX(l;y`CFWGMF%5G7i!BOf+8kD4a?8M#T zL4%TXj~%&NI%rUm?y)m>3kMBK(mi(QZrPwgNiDaJ-?(k*5~uDvPu(pURK524zy{sJ zWB19<-7Oe2_TW5spX}h>azTTV`m@7lX(#U%3mTN9d+g|aO&q=NJbIt(?A<~^gQKK- z?C{+(L4%TXkDb0-Bxq2Q?y=){O9Tx{(mi(mZh@dNNuIx39_Y3v4&Zklz*`)sB*zz} zJ5S&zJA$_~(BOmX&kpXfGk6OF4NB5Ib_j1-pg~E_J$4FjQJ_Idy2p;;EeSLzN%z<} zyaj;#klH&&= zmKI}SF_P3fHvHglk7dP3Qt#NXB-}GIDn^oe$A%^09!rXmMirFkECiq^$ zJ(d$A$?*e`orm!j6C=s-1CgDF@s<)J$%K1&7;hmll1#XVT~RF~Mv@8l@GxE-_i#{W z5izlEoQLt25Tj8h+{43o3y6_q!aY2UpY1T-@?nAxj=5*H!+48_2};sEOo!Pl9VRG= zxo5V+cngP#N%An>vSBpJt};0H@GyR6G>jw@?%`p)CBsNE;T|5wTQH0y6LSv_<1H6P zk_q?lFy3NeB$;pz592KrMv{rShllYN3bU2OVf@a+_}LEQEfXgAs?$Ao7;lj{D?9OI}!ALUU z9)`hK7K|hl?qL>;MZs)^Q82;xl5-D}U?iDXxpf%v_*wGI&4OTJqht__<-ll^3HLAt z#!_G;nQ#xI+h=CLNHXD`ejal8ESUf!$%K0t-aa$`MUn~kFui?d`imqJ?qPiU%mk>t308hez^Oni~#xO*({ z#qwSxIqn|Id$G6|Nshax_4AN}A+3xe>dy{8!NwX`oJ&xW z?lIQD!d!xqbdRwH7UdF@q~c5sie2A0+ml%#u%HL$Rjpd{U6tU*as{54km&Bhv(M9E)c z$=__OK~2>BHP-yi#v0T_(O+ZH-)yWwO;r6gvIeu2{nZ3((8wCh#v0TFYtYCV%vShU z6RbgF;oo9~e>K4xG#36XR`^#FtU+Vp-(svmO|S-yg?|gX(x{Y8ztE#UZe$G>Hld=S#@tR-_8d(GN=rhUw6FE5dkTp=3K9fw$J!B2kr_Uty z3q3qa%suMVXOddq3`=6}QLjFe96zycWDV4<&m^_J86G88ZtB-(k_q>)@J}84D48hy zYb^Xz&pwkJKe28s{8Q6DlhpcV^s^*uuvp<=O|S-ytbyA0*(ek4A#0$%eI}W34_SkS zO=z~7U=12s19k4RQ6}6&)?i@^8jUjH9go;U2OE3%k#3HNhG*vIdJ4{?!C)(8wAr>^-AVCfq~TU}5VSNhanVvIYw~ z&qy-i91~tJNG_nSZ zu?9848Z@#7i?IeZ!5TEO28*!>MfZyAkpc<#|Cx$m*e;5yD4NRs;=V-4zfXs{&p zWQWhvQiJO_YamJPdn`7%j>iT|68Aleu?BTKH&~LKdyF-xlI}6qppLT!lB9bq*PxE43QLmiG1j1t z#|lf5?lIP&j^_$1vXt(zVBtE>8c34vv1H*o&KgLP?lIP&jz!;*B5u?E|C$gsW+y2n_9Z9LaNl5~%;2HSY9 zfh6f3V-2?PkYP#EJ;oYrqxWy&Pu^BuV!e zYp{*y8c34vG1g!k&oz)F-D9l5HqIJIlI}6qU>nahkR;t>tid+U8c34vG1g!kXALAt z_ZVxijk5-lq zpL@s}C`Ot;8{@2jMoIS=YoN|piBZx$#u}(`P(qUKG1fqRRT7ePkFf@7Igya0dyF+u z4u3+D?lIOtdFSJjWDQnh4HT%IkfeKzHQ2^k1Fh8P9%Bu*an?YRoO_Hl*v44{Nzy&W z8YtE{@mbP6#u_N=H6cm&7;B)k%7i4{W2}KP;u4Z{kFf^I;z~%;J;oX+O=wthB5SZ3 zYoLggge2W#tbuYT5|VU}u?DK|Pe{@|#u}*FJ0VH;7;B(H-Gn6FW2}Ly7ZZ|nkFf@- zze-5bJ;oYb8~6-vODD1htFZ>x20p`*bdTj4h>snAaIyxgu?B($6Owd~u?7O&5|VU} zu?9kQ5|VU}u?Aa$HJHd6ti~E_3D#gDYp@z?uq9Z7iLAkDtihIG4JNV%>XN}#aDp|M z$Qr0ihDnakJrh|2b;&TvgnP&us7r=PCfq~TKwUCSGT|Pw2I`Vwk_q>aHBgrflT6G# zWDQnh4XzD*Mt?8K8mLQ#jWRL!kTp=343kXEJ!B2kC4-U))?gxQpe`9EnQ#wT19izT z$%K2z8mLQ#NhaJw)<9h{OfumfvIgpsVUh{=kTp=343kW_hpd6RWSC@P~*`PpaRfBp3HX_}{>MZcHjdKLQsz1q%W8Q*zG5jzjtcr4=^ z4=L&+IgF9N{mb~iLyCBFY}>JnZ#$%j_r`V|%Q)dIMZ7h(=~%`AXDMRSVSA2ce9y6L z+;iBLV;SFaND*5O+i@)8I}Ryg$6*_eWqiXSMQk{1zp;$(H>3#9*mh$X-)=||p0VA= zGQQi8B0OW8jb(hZAw_t`_8NL!N4J7fglBB4q5qsvglBB0v5ZsA`hU@LJ^Y&4Mq?R= znxzQO*gj(!XPTu5&)7C&8AqC>2+!CqLrsv!zZvc_Y?Gljp$SEJ#`YL$mYGn5XKahH zjN{Du9N`(;VJzc23@O4hw!u)-%fwT|Gq%52##v^W0-mw$#WIdEOA(&2-NiCaGD{Jj zvCYLY4l+v-p0T~fGR`qe5%Y{~EtYYNS&HzC?JSm0?kqmtWpyLPY!LG@4l!$t@Qg9c z%Q(X*#=4BjVmLfc31oJXZFzaU@o-u%V83&l92+tV5yo~e9QiNv=UtY%XWhufl zMlUbp^s*G;8H1OXad=sZ@C1aiUP2P4nG9MM zxs;HEYbJx1McX7Ku{@g$S{8zkkc4k0gO=BEXj!XmOg582%WEPa?Rv5Lum_n8T3!&5C(l1IR6q8Z!uV)ZD=Bj7dBjO}`{dXO||c^!wAwHu;)3|bb_ zI{sb~TGk;UJw6UCYm{`4LCfnnv@A)w$DrkP99otn-DA-5Iu0#M5^FVG!}7BnhnBTl z#bQm@uqK(9c?d1*8rCEeQxBnKUBjAWV(uZdJQ=jSjzi1(Ea@JDme+A;S(2Q43|d~t zp=C+ZJq9hW<4{B}tbzgzUnuT6jR z`lnaV@1I|JOZ{Lar6knH6#CLBs14^$;C}QbnB?AhtODN*^(<%m( zT{o`CiUBJaP;^~FQP1_TAF+A?CD$bs@yluD0t&86D8e&VEuh@Ggd#j+#R7`0ODMuK zRx7ZuRv_kU<`P<|fI{mMV}xg{Qea`FKyZxkj1>wjEEEVT!ZTJUu&_=bqY3Xz{*}D#OxFsA)6j> zSEWGw#0d3N4==X)jOTg55n^t#<2n8nWW6osEq zgj?(=Pf7R*McBno@)U%hP=sIXAWu2?8Tu#BDJDFi?9 z)bNZQ;wc0F6N<;#?%cJ#yZ`gelfT~l`rF_9^H=|L^F;eVxcuC;-8>P%0+)A#KE713 zP3V#mYEWF^#dDb$$e~FBMIBS_kUZS&>>HSM|)-rvV&dyqNM=jHN3v}KB zeY}m-?FGo5*mCkrw9_5pc?+a7pfk}fdIrSs>@(5sdiRyMIX!QI&Rd|)(I^ZIoOo>J zI&Xo_Tc8hb4{9rdZ_jxP^yEym>%To`qFr>|b0*s9?u+$E=PgkD(D}Rt`fziBh6v{^ z(EZ4vGpk?ETcGzOx?Uo!XGRlB&s(7L7U<_U4+n@VOJQRR>GKxoyamEbblw8}AHD@T z>%Pyr@AuX2NOw5Xy87<^OzR5QR3j_lOzY}z&zaU0e0%;LXe(KWo1_UQQkq?6R8!9eO^n))+nB0x==*boOb@e?>H z@5{b-#6kr%Ef$KwP#PyLFM^u5ywEstqO?~=Lmf1aaY1J|-rwr@)f@|7Y%Bw+clLaE z0j-$t495%n(5lg+KI(_h5Wk3LINr^Z*o)}BE{?xh`V{dy7*yo%Abtg|cEF^ce?rHcwH#f_$7J8`2KqaM%F#qK-aG@JpJQ5T-2i)ZQLS-SW))+P3f+uN5u ztb5MV#s2$ymM%tranI7lvvl!8N)=mm#(sRx(#5lM5k)SfHDfQ)S-SY4+zzDXS-Ln@ z|4K;d46yw0tA3U)4pg1>6OV_r^mGPTo&lD}OQ6_v_V);|JZXlLW;khvlV&*F1ooZ! z;C*yGX@-+#cz>SSH|m3L&)fT|T?}@$+S^^UuN+juZEdg++eb&LY3=p2yJdb*j8XzU7VB&Kkdhv$Zk9LjX_DeXEOK9 zxK9pB(mht~KHuo%;ZetJ5ePfx;Jxjtp zJKeLeKx|(UbI(rqEao28TLmAS?pat?xi1O#^sbMGSA8+}ED87QbkAb$>DREs?PY;b49wpsl?D^i~WQQf`o@(ytu@S?PbWb(+)P#HbdC1|j ztmYo#=dqWlpNAYJ%{?{Yo_-#3lr;DBz4h>CN%vH9&o;htn@OM->z=dsIN8xr_VbYA zgPVJ{gnRmV$WhYVvnAZq&qI!qHusQ1kG({s(934->3i$p&yw!h%sqW?JuFH0Z04RV zG57TIki%zbB>GMgJ@{GDJ)60w@2!U)obK7oJ$-LIEXlcNv$=E|IwNpnx%TMs`t-Lso}`rdk2lJ42fJ$-LIDoHH87?-~Hz4fpp-Lso} z`rdk2lJ42fJ^lW4Sd#8(<{qNyv0tKo9&&hznz^U%t%pZR_cU`)-&+q$(ml=G(-Q6> zon9K<)B4_ec$9QcqkCH4TMtXpJ&o>ZeQ!M~+0R3c-#F)<*7w%Kl5|g_ds^RH4@=TL zjqYiEZ#^st_taaur;$;QxrdB;y`_6v-&+rl67H$DbWdYyW^j~nPrapk8gny)lKQiU zm#E&Fd-~pb_`%_x%1q&{F;h4=O1P&oQdp7+_b@%PGErEP3HOjSsKy$!1ZyypHK@iK zv;=D~_w$g$H*Ty!ORxqrLo}5djoQ|hU=3!r*HLJ+NhanV#%L-t+9VTmPd^ViewOB* z1Zyz&^N^#Y%{>X$VD9H3M@gG|60E^Y)C&3!bY_FrVXd7i> z?&;?thfx}9&=Rb{+|NUflIETSYcP{huf`g*1ZyypHK@iKv;=D~lQpQu8ngs!F!%G2 z<7a8^Nw5ZUKMy%dntKwg!A#bm8f(xJtiepypc-q?60E^Y)}R_|&=Rb{OxBS`;u1ZyypHK@iKv;=D~lQpQu8ngs!F!%G2gL{lMXbIL}A!|^L zHE0ReU?FQzjWuWq)?guPP>nTc3D#gCYfz0fXbIL}A!|^LHE0ReKplASjT>ulZP+uo zA6Ek&N}78TtbzLPP}2523D)4+Mda|R8*9)KtijUHLynR*_as<@g{(m})}SR=gN3X? zEw=ATum)9rR}Njq~(um%fRgKDfnORxq@KMy&M z(%kb&)&T9h-rPOAe|!1t>({UT@Zyg@y}kSW%lmjy+4XniVF+p=2D_<+7%qtVzdTx1 z)_6!KP0Uu(#2I%?lc#jjgyE!#L++ra{tV9!$4L`+L_tl=R~jcQCrupG1vN2YP5SLQ z9{x#FtD=XMR8SM1lP0DtY4+QUk8o*F6Q+|UTqjMObO$xD;*%yOEoo|D^zV)n9(n!j zPxtRGKiuCvzdXBpbNTbLxA*^Y`G@KD^JTvL<#PMQR-$E?OYPf=hqne_g&N4=tLQgQ zkJ&|n{3?#$tpxEs1O@Ru;7d4L+y$Gd^{vFiw~QY!bw0xnSnNyTB^`df&K7rPi@X2% z^S|EQy?gie#qWRmH&GzGnq!mCv&G$=BGY3QL(nk+VJKdVMpP>w}7z zT{zQA@l(^wake|dbpDNlcnxB=APa9n`fvN=lQwTb>=I<*B}h;an*qB6S$GE$RKy*K zm0K>n0tqT&RlDuRVf_@QmGhEWGsyD(cT3JY$z03oktmipP2EyZ^nD zjs8A8j9}8u+i_>Li()*wEVdgZrz%aXBVm?1@td_IQ`3ok9>-4UQAPUDCwq z-(Jb99yE_0c}SXi_xiGY^Yrr7^Sd_+)W3W-eYq-(>ichg_SyGeKmB}~<|%wCxNN*& zwEM+{_ly0Ne{{XH@qW>+7Z+YH1{Lu=+wJ1QO6H&<<|iv;UU<0}RK#~|b<7Lz7K4hI zpX_S!Y@c-_l^2#P2Nm^a55Bf)<%QMC zK}D>>typCPaqZwQZa+snd^5O7 zmttSSk1E15R;RqMPC53}tW&l!<%MO+K}C4Rs+1R2DF+qd87op=Sfm_O)So?kGghN~ zw$BQ$dsv`s^~o#ilY`$3JY(g_E6bCEitr3ieYTaSJ~2g}`tZz0id|&T*Zmyv@IG>$ zS$X0U93wo#^B#>6=RHA1{n^79Cm#1m630D3NlY{oPkSV(U*zFW5;M)j!yZZM^%|DM zR5S6cN0NHKh9xoAOg!pQ=cB}A(+@a~Uk_)Sm8HqSuLsVVtTcHg^$?RJ^)Oj!^2*ZW zpd`FAS!wdh(&V5d%rjYO^2*ZWprron@by?}vXa-wUm}(!Pga_|vNSn3O1j5NlUK%| z2PNqqD@|S*gC3NmdklbBS(+S_q_!1Al1=nJ$VMVU+?8b)+yx6PA>=|3%T}!Qo z#|XFB^6pw`HLM7`*y`?DXf><|zu4mLT4yz?Xp1|$@!{Go_RZMZj;9L$dHB{}|Mc$i zok;07(VC6*T0(Z%jp?&EI%`*Y$8qBB3)aVo25Isg6YXo7IPVQ=@+}kZYns?Z#59@E zq6!+kX?k|-B7&OSgD=czktS{zgPPogFI)*pv&($k?F2RTY{&1NDJ{~(Haw`wjl{y3 z7HMK95!BS5VVwA#mZsjd;b-SYd?BMOO}%Twn*60+NGb2i@knTzkH{%YGvOmfwM+|1 zWoagSL{eFr<|DGohwuHkQa{=Jlg_k6;l5~%;A3NEPm?YT`?fQ=!@@*&l5tO8RSnnfA?41vi$KT&`A93y@&V9tMe*3F$ zf34k=ophcxzF4RlWDJk3WeQI@9OwP8*3 z5sQ?iIqV}nyZMM^%6lCzQNt$}6a8KH{C%UU}yg)HEOQ(o32NAMw&l&u%{AtygTE9Yn(SZa(6*S5VV@ z#CtD2d%{N@L^_U>7hlp$?2q~x3N&p#;>}m^+0941`qDTPKI&&E7^nG&cVEGA+I+;z zul*XwH@c7OXDApa&lxt}eg(&AKH~M4#+mRDufL{+_g~WNLmND2VDYmw>7#2@*s!Mg zhy~CZXTnDedY@F@j`?UCuYfMMmi4XzchgMFNBs=t@Ghyu-82(EVnvLeoj%%F6cc+t z`xy$x$@yqwT})7uK2o7OpMAUxTHg_Uq)KP;(?QMJ20dtyGaLK&62n`XjC?9)7{-rY14KC)sNVMwN_cWwCdG#{~G zX5Yr^q4m9+k61Dz&BXr5+Q6vhozFgA5nXPrXhucvrkU`OmCdN?-88lK8U2o|CR%0h zrkR+JtSDM_@1~jX5gRs7DttH1gpaH&T9xmnneY)?Hfx;bBesEw%^mF7EKQq_SQHf0 zG#^<}kV-2P?~=_&RurVJ0OOig6r}QZen%_{iak5~HtX{=AF(JXsL6HRYDGc1TTeW@ z{-=-Y5Gx8&4rW4=`=iy0f|L`O(6n_O+ZOCfJxgeEf3#XrkW$JLnl>LgPkE|$284%-|Rur^aQP9Sspx8TaJi}@{!#2({lw0E&R^u7Aah^e%<|E@7 zwsD?8n&uk>S} z#D31xYCOZ1;2D%LX5+MVU4my&$e3x`x-P*pC}qqv?VKUOGbm=vG;M#B;29?48CK&N zwgk_hpfMY#`6$6Ns2zc6nvW7Z!(=?eYCOZ1;29=1cAi$_8MXw^Fd5IV8qcsLc!r6s zoi$GLQG#cfjAvMlXV?-v!_)&uj%#n@8MXw^pujQHG#@2+1|^P}rtOasJcBxLn5OwC z!80gx%rwnM37%mxo?$hfVN37~lkp6z@eEsnXPDUId0LHU*b+R$WIV%aJj0gY87AWy zR^u5|@iV;dn2cvwjc3>rJcFXg_%0dGuqAi~b+s`~^HG9lP)}vkG#@2+2Bo5yruitr zGYA@|rtu70f@cswYnryMOYjT=6iw64>k>SJU@g^{x$%(|lw+gB9}z$7w!dHSccKyg^O#k?{;x z&KuJ-p26yQHO?+G#xqRDGpxolSV3=aoaQ6r8TJIvFd5GvNFQhZdxB?}jAsy3Zkh=n z8P6bi(=_$24Sz@Uk-$LHO!&xnhQd_$eNXTVlcl-~M&LLTJi}x>gD!hbQ}5d7=V?5H zE@n+L;UnW2it!A4f@heFXVBrLjZ?qb!_Tf~JM3YL@eKQTwtJb3XDG%q?Bn6?(&T(p zjAz&x{u%pSGM=Fr&#;fjyK9`BkBadOdxB?}jAtmuGwcbTVKSaU1LwPx;29?48H(`? zJ7Yj&-;wbQ#dwB&JmX!%;(Sz$XV}L>-lb_iGM-@{PkEOn_eaHehJ8HdU7F@2;~Dn8 z7a#o%F`l6q&!DuVgr@n(c!oW}GfWn8T8wAd6FkGz&rpuPpT;xn37%mxo}n1euqSwi z$#{lhJj0&g87516FUB+M37%oy=bzOpIm@MS97|*aLc!tS%hGIO!p5PfK;~9$a z410oSn2cvA#xv{*o?$Ycp%~AwCwPX*c!pv;!=B(7CgT~3@eF%{XPAsHlCqaKEs~i8D`@disdux z37%m#o}n1euqSwi*?5Lx`3!r4XPAv=D8@7F37%m#o}pMi!=B(7X5$%(x^emkyt{L=ibG5hCRVE%*Hbm z%V$tA#`rjmXDF7>AecCz$@`;X`3!<|6Po5D%V$u;a6;33WIV&3;2CD)8H(`?dxB?} zjb|vvGwcbTVK$zj7|);!q{QcGJ~Ey`mnaEM^O5lkI!sS!+Bt*q410oSn2l#Bmd~&! zc!t?{hGO{)dxB?}jb|v9&#)(WhS_+AVm!m1;2CD)8H(jI>Hl9Jz<2u@ z48`&p_5{x`8_!TIpJ7k%472eJ#qt^U1kW%V&rmF%VNdW3v+)eY@)`C7&oCR$P#85!XDG%q> zW>b1yck;ZhF`T?FbRO##P-e?#D8@6iL_WjZ&rpu%ipDdvL_Wi8JVUX3hL+$NX5$%( z@eGXt<+0DRpP}H{c@NtXJi}}}Lp7eEC3uF}c!p{`LmO{VuPYPokE-zuZM;XlG`T;j z#xt};KErH0Lp7eEC3uF}c!p{`Lrd@sv+)eoc!oCKr@qX_GgRXl+IXXSX>xy5jb~^H zo?$kgp&HN7##_~EoZKH(;~83lXPAv=sKzt21kW%V&rpqLXbGNSHlCpx&(IP)!)!c5 zHJ+g*c!t?{hH5-ROYjV{@eI{?hL+$NX5$&E@eD1&Gt9;_RO1<1f@heGXQ;+Av;@yE z8_!UUXJ`qYVK$zj8qd%YJi}}}Lp7eEC3uF}c!p{`Lrd@sv*j~X;~83lXPAv=sKzt2 z1kW%V&rpqLXbGNSHlCpx&(IP)!)!c5HJ+g*c!t?{hH5-ROYjV{@eFFti~V~`@C>u@ z4At@(T7qYojc2Hq&(IP)!)!c*n)BMTC(i4PXHauqY9@Gw*?0yu=QYhwo!6oH!&sVu4>UK+&oV4yI9Zg_ECW$ z!?z|<#H|VM9;Grqtb@=jZ*B}-J$vbDPkYM+eRr4pGrv)yJ_AvN^$s( zM2heXZyKeT@C+-bdCw@tglAYc&09t(COpHcY2GnPG2t23O!J0OAwUVwuwt6`i&9K@ zhWCrSU6f+NGrV2o-J%o|o?)#tZx*GP@C+-Zd9NtNglAYM&09q&COpGiMcye&G2t2B zDe^{9iV4r~Mv?c4QcQS;_0hadRLE7rGpvs0U7{2do?&e?ZxW@L@C*`tnUjIol;U2sGJdp zW>8U|+d&chvJ_#>prU?s4vM%{lp>rNRMc}F6mh4xskiy@o+PNK=Q=3jMp26JWl&Mi zbx=fJhZMWW$Ge=EBI~1B9W6z;GN`EMI*bt+Y*K_NgNpjIgCa;vDZ-OMMLpMpBI}~1 zhzTvI2+y!8T8atJuqv80(Nau!hBeWwh?Zi)GpvYaJ+$s<6P{r`G^?SdnD7j%p;-$p z#s2k1nn#bEYrS{(f4+J0*PCB|`Yr|&X!VHi zpA6Z#*1LOo^W^Y*`)LxW^7oU!o|>(@$k@D9`RmEwPATHIGd4yh;qaGJiumOWD(cT3 zemR+fBSrjf1{LwU$zM$=o@>3}`*^PPZk{mp=3MK&|IJ^o^Y4Re6}*p~sRCWPRX_e( z9p=(c{{F4k`4^g8>#0I4p{f6AXmYKm3bBMHezElITX2~Do` z7T)*iJHj3{_#I)c*EqS>Q-xS!oLuWIyz$dGhu3;~m$=qjc;%;XpmVKvp6kU|X6L!y zlXI`n{7Vl4L;7L}z>35?q0Y9$UV=h0>EOY{f^}jwxtp8)5Ba?g2GmGn7d(LCA zlbZi3_fzlDinH4G$ysgNe;>|jTg^S1vLCxeJ*#cM{q@b0v)ZT`>aEl`YeI3#6HWj+V)rdJV23r$H2d{+V=kKi}?QLthW8| z5^;}nR@;ueL}#__`?$a!rQQQ7yW0MHW7<_rl4)0~#a(TTy9!DI=v^)EYGdA2P*S_3c!@0pWMK$MP!aF2Wq>Tq z00}DM6}Cmm!U&LxITSgI323qi`IQm!K}i^QvJCl^8S+6%ICnCvWo3wbP!iUiEJc20ihNKK z-kmH)er1e&P!i^yEJuDN*%Fk5dnXH$Ul}AHlVp(mWJ&TXljIMQM{j)h`q`iE-(7yV zzk7apcK7D;=Vx#4|K;)z)9vTWeEG}e_KU5AjZ&G3h!Ux7;Tdf|WPH>n)e;eLAhhs= zHYli%;lav0VOn@T8x+L*%;nU=)7hXP-e#1*Zwt?6gMxUME%Sysh(STT$tWz;2yvwm z6J!b^stP68Pfb7Gkpu-X3)v*ZGufaZCLwM>7UmxY1^N4LR$=^MP?10X$c@masJCkP zQ-oLSICf$9VQ`Evi)9}!%svb%!YvkkxG?%Ks0h1Q^5Med!=NJkV!?+CgAZeh7JO)q zVeVm25stCg!-cVjK}A@`QV$oV9tIWR84EpJ7Yp1(&D+&Pb(^VnH2`m5hw?`O~CgX`>#9bVssKYqM&&SU31 zb_Lb`qmmEK)5llOU%ZDa&eO-kp8b<4WNJN%)0Fe{@jQLJc@lebto4eW)t{%2(a-Tb zebi3RPVCRqN8RoxR-k7#@p=0Aeg%4-J_gT^>bYw>cWwWnyS9_?ej;cb_rxdR{b3t> z65j7CY(zRddH|>LKp++;;r-zyItlN8^Aa5?hBIgF!^yt^sSAPB4vsx~2EKJH@qq|5 z9(5s)8dL<6WH{W=1X4f^nx$mfAuf;lij>f+B-n+w!U|%=G#e47FVMWX{ zXU*vy%!dG2NmHNtMgu1=N(gIowt>F zFD&y8D#9~X<-M@VJE#cH?6x*zk#|s0fA;W8VKv?hYrKPsSesdi_renIpd!|0R^h#{ z!aJyld8XMs!vgQ1BIX&Z?_OEo9aMy8th{?=d3R6|p0VogGiNQlLt+KrnX~rcKPW8HJXmj$5&Ln;`ZUUe7fZ#?aWyl`g$}oHe{eOf@;YM8{j8U;p&(@|^-p-bC{m%G~!8hgr0;hHG!E;p)fX zkKLb06D#kjt~le7CeC<5n(D4=@pv- z3xb+@w&QoiXc%eYP9dm?ed|=24I@q5Dg-t4XBa2WNTrGMo}ec7t{NwHuhP`JHvD;F z_bN@ClkSc8alvt#k9Z>|O}%Tw<1`;JAV!)AA6Y<5WkQTJ6F%yRA^6_SM>XLi-plDb zG9U3~?(iKQe-F=^$g?K$tcg5pA|DpxXE$h_`}Jw#u~pnsxiaLsP<@dxp9K{$pK(?8n4`CqbM#?< z@#(s|-R5Xc(UR=5^2eoaP|}vVq-WLyJ+t?4ujA^3_{^HXXZBuTca+3BR}YSLZt%fv zor`6zB(cm5O4>3PtK4nvHCw}9kFRnOzqck3n!Oj<9Y0I#6*WryD#RYVXM7zcu~n30 zR~dXS`$6DQ(%jP%a)%}LWJgIXa5c(=dwR^*L2@(q^h2fLQPMq|xo5*RG5Gb+Jx0>3 z36f?fNi!KrvnEiQy~i3KKTC5@f~DE}LEur6FwL5PX_S*sNpnwvrrAl;Oq;nUfz#|g z+W7e3=AHykv-fP{qolbf(YSE$;l>Ba-Q2S$+|$#IkCNt|J>i~y5O|cdxhKKY>||;t zgKE|URI?MRnT)Dg6I9L4>YB;08l~%x|F|u5k8w4sy%?7yS2Gz{vnIfreWiPhtXUIe z&A!q-hSsbJv}RxF9%F0P1Y5KB`p?6wZg7p#^%GwY-D7mknxJcTb}^g`uUQj#&AxK( zF}|iG_?ms?++%=ENdPwcO7|FHQ`kQtwlrY>gvt6R6!uRDO42>nKcTRHLQsFg-gcN%vTMc42@`P?GMk{OrQ~?4Tsw zV*%PF0om+?Y-UT)E=nI;eaSviV;eg7@=~ z!#BRz+|&2gqi1gYJme^8a}Pt6f)7sjEIc(ReQ!NHO3pnCPpnJdTMtXpJ&U=g@2!U= z=^l%9FMV%4EJ^n)wsPxx>ru&m9&-G~ZSLuN>tRW{#}aW1vz1~mQ9lnkj?z|cJ-K3d zlyuK(?&*8$VM)4YHTU$r^{^z}vzmMQ-g;P)?pe(}eQ!N1N%ySgp1!vpmZW>^61eaZ zIQSCLJ$4IRcnchoY-9uH)!aigFepj)kPO@k$-tl_-9s=?lH=}aY#BF`3zX!zds;sa zIe45{pd`oL)B1VHQPSK)Dlqt2(mjL%HOg`Kw0<6P9HqI3Oki-7bPtihtq=(eO421$UGLYtYCV%$D3y60AWZYcLyYP!g;` zBWo~Qc1KCD292!2Y~dXx!5TEO2D7mSCBYgrvIg^R`u?8i<8Z@#7v#|yx!5TEO2D7mSCBYgrvIeuU z1|`87G_nS>u?8i<8Z@#7v#|yx!5TCsdCtZflmu(g$QsPX8k7WU(8wCh#v0TFYtYCV z%*Gnj1Z&X98qCHT)C6nL$QsPX8q@@9a4nWRtTv1_s0r5KS}S>!*payNpnwvHE8`jX$ppi9D zi!T0bBv^yi&qI!*H1{M}gGSb1S?MjdlIZcV=Je{ zSOaC$Bt}X17;B)2nuH|XW2`|Nsm4NxH{a14Yv$9-J#T>jqNCSp$ud?lIQj z+I)8Geq54t5A%n%I?ftMl5>x-26db@kR;t>tU(=T4HV-`_ZVwX$5{hO(mlo+)N$58 zl5~%;26db@kR;t>tU(=T4J1kT7;8|+Sp!MZJ;oZ;an?YRbdRwHb(}SjB;8YO=x-)N$58l5~%;26db@kR;t>tU(=T4J1kT7;8|+ zSp!MZJ;oZ;an?YRbdTj4)N$58l5~%;26db@kR;t>tU(=T4J1kT7;8|+Sp!MZJ;oZ; zan@kHC2O!4Yf#5o14+_7#v0Ud)IcIO-#BZaQPMre8q{&tK$3Kiu?E*Hx8Vn;dyF-x zm3{Y#`}55! z!;)~1-cw4Bvj+Nl;2!tid+U8c34vv0Q^~oHdXn-D9~1+c;|=NxH{agKeBOkR;t>tid+U8c34vv0Q^~ zoHdXn-D9~1+c;~WiGl7h)?gcF4J1kTSgye~&KgLP?y+10Wh;-*J!B15V-2=()tHBg@O_DSdBH< z#&Zo;wc5l>WURrKU=7r2lah97kYEiavIeWM23vwPn8+He#u{u1)?gxQuo`QyC0GNs z+T>?xrv?euU?OX<8fzfDWZXSu4OU|fwghW1ku_M2HP{lY!9>mkg8CJ2omw)<9h{Oj7HcVM(ssj5XL2tieRqKwUCy zl!>{Atbw{@m}J5|WDV3M!z9O7ZWCDpb;&Tv@qN!k)<9h{Oj7Hc;cuLCkFf?@f;E`P z8mLPKN10#^Cb9;ru?Aa$HJHd6ti~E_3D#gDYoIO}_TXCIjD9_24b&yWBopo-Yp@z? zuq9Z7iL8OTWY{PZ?jdWi8f&n9k~KJc3u^xR>&@Le^_czrPiJqzv$x>cTkz~Hs8foE znWrx`&)$On?(gFjMmb#Pat2>`_7eIWuPn+zkrVjBqnCr?aUT2bhr2(#i?$J5cQPW{ zdEkF@x8@gp&G^{cAWa;WPS*WGnpkrOHF4e}O)MLviDg4j6UU{}#Hw4GSakTlP56k=h{kC?A~g~lC#ex>nvaN$1U1b^ zN$}ZiJ|aea#%c2r zIg;Qw%|`@Dc59Fk)YP9H*ES?cq?uUPktETxn~#W+Tv_PHHy&h3Bx(yg!X!~qTiFpO z(bMBtH7aUWB2XexSSc!Mdn6(y5`~wdqBbcJDv>BArKqU6iCBq5;ijmlO-lqz_Cl~E zDr$ZrS|U-*OHolX6yXwy!cZ|$>zXlH+YE{7m3#Pwii+CQM8HI%n3|%Z<|ra25{08e zzfsmYL-%R8=aVK371T685i*e`{1ntQJCQPxChQc{G&d15k!F_}o13hChCWZ5o5-02 z$7x<-sKss#G=iG?v*X-E(nOlDQcSbI#?Z96iKt0X(~LycMB~gDiLi;jBwOT>HVL|u zxQVWj%}L}786)TSnKCwn1x5*0N& zkvx%TVrsIM8v6Ea&%~UI;7AFdNYo6)q>HGiIg0#=9zWwK0w@}(If`i)(UIC>j|_@N zin%E&YK|g>BGHVah@ng~ITVRz97PaCqILwq)Qjljo1@60?ABu=Dr$}*jUv&EqllyE z@y$`>QGz2SkRnlY6p56ms5y#EiXK1XC_*V3sX2-X7}1fMqsXObq!~vMOc9x6M|w=b zh>q0eD6%OUDI67BOE3pR12sc22qUOzeqs{FZe2Hmnr0_PVMr5p3To=lj%zb!VMr6} zz2KL`FbsX5<|d|L#0JVV3~Aa~1miG*nznIb9)=!1v2kJ^hTu6{?lBM}I8K|Jn24cq zVs1KU9xt+&FZbWwTz+}~m&?1?m+8w{|MHvHKfQW>|NQ!Y{ObALn|JqbFQ2{tPv3v@ zv&(1Y^QU*u{-l5S{_CfoE9h_eS@a@&x#k5uyjVQiR9PT?Q2IOe*lCm$@hR|NQ;PTu zf{OSt;jyL^@lz61#A=s^no{gv&BwKFP!T^QJknGxB(4U6iuf7ffuPq6p|i%+mPvG%jVZa|9XJa+f;=1Fj7 z)Sn&ZT3h?^!tJ1V+>d?t`q`iE-(7yVzk7apcK7D;=Vx#4|K;)z)9vTWeEG}e_KU5= zcUwe+vE@|w3>J?4t$BR2)hG9d2efq~;ozVk_F5oFG(s#JgM!>@ag9eTI4Fpn7VhVi zw$n8}ZeoIhSTvf~2m}WOvCpz4BWd86AZcKn(&&+~%L)o&#fT#s31Yz*6ok>tXM})* zg4kmb0oD)`Rxt$Fyg~ptI7WDd_^-y8Fbf0Y2>(hEd#vCX;TEF5N|Nd#gLYwD9Kl~H zVviLZBm6?_SBm|Id2oz|{hDJ4{l><~tT-aS8e_sThWwgm2>b@e2+t7r)fhkJnRB-L zuu4B?yK}Y+t-6?zYR)}pyPGGm->Y-ByLocXb~jHnH{ldM_VzFrH8tCvXO!m|<#|SV zo>87>l>I07;~wj96867{Njc9bZ=U@BMy}x|@`o}jfU);TV zclrK@`}>!drF?by?C!_UbwfRe36XVTj{&6v;0SN$X;Htae(cmzk~l3=IDkoFH4v1< z-dEWGCW*~&P!eaWiUu&ruJX|{K}nn#DH*^daby&f#QCa%0ZbBSMnOsa*~6i-asepG zL!+Q1&sgo$Xy>U>P!gv`N(Hb{;@BuA$zvmh0+=LDT7!}}X)ShewDaI7C`tFQR9rc4 z3HNXXF8FUYO3>4OhOETde)`=IEiAyr!9`+be8USA+R*45c zOS*?e;)>zJnQKsz?qQ9%Boppojd)>+xFi$qVUGbN0oZ4WW7pV&vqHSEKwP6txQ9Ik zlmlR+Ow2umC=~->k_q>)JiHi2xf7!dewLhjjHBGiQ3fUTXNS4RK+2sUWl)mtF_Lm8 zNg0%+dsrF1?L;YKl0+#L0KjjYEM-uVbC1E4J7LP8Bf>%a9`j?X>HS;Ht< z{w>LI_b6tKlI9*(e+M6&a}SHZHOg`KC}fSJw3Qoczk{QsdszCd9N}^I%u(R+xC`tFQ?pqH&zH(E(8b@jFVbynVlynbkzBS5(d)Q+@#r^j6 z^ns1dJu`a@sJ7oE$LAhptKqX`wYMHT;U4xFP-QOw2tj>Q)6mzaG|f z#|+7mZq@IbWWqh{F`(*wlT5gW<=lnU-1;mN?qQDsRqop;6YgOtx9avyGT|Qf7$~gc z)`KV9!#eK5GHyvG+|#Q{5AIaZkNZq4p{dcESXq@L_JO0L|l32VcWbWfvuTHjj_OVT}!b5HAg>ru&m z9&&te&OO&~wP8uF+#21}`rdk2lI~$t{nq;4dRP+fskfYa8Y@v^hGZp5Wl+6FnQ%`( z4|(`{Ds$>3nQ%`(4>?NGJ&pA!!3T$XDpTsW#)_1nB-~ROQZLDbd-{3E@xjeKtV)TE zl2s{{5%n5nV(uYpP>nTc3D#gHYfz0fXry(64^HCDWPc_z{C0GL`q4B}Fa%&0JKsjiTG}fRcSc93V^wn5{mS7ELvIf;ygO*?olz_$u zx49?58YusalD2Y7um*EK4>?Q}#u~H)YoP2iO4{6$U=3!n2Gv-DmS7E(d&W`P%8hCC zF+-9ysKy$!1Z$wsGmO$$gT}z7;3zrw7;Dg&*c6oH++(akORxrW&$c_fm&O{j1Z$wY zGfJ9!60CvZ&M0a7o&;+!_w$hBgPVI2tbxMLC~5ni1Zyxex2YOy&=Rb{+|NUf4{mc$ zf;E`Q8dPHqT7os08QoNkHE0ReU?yu&jWuWtZ;Ba`tU)!_pe0y?nXExI)}SR=gPBNq zHP)adSc94QP1RU~mS7DQvIf;ygO*?o7P1D_u=18*4HmKnm0|N+ORxsZE$1F%4O)UV zSjZYwV+~q@HCV_RR3^>q!N*SxuE`vSUm{}-T7orL$Qo4U%x^8h8eG#kj-#}>C&3yl zWDTmZ1}(uFToXEuqqMmv!5S?6Jme^8E4Kt|u#h#VOqkc#Gk)fF&FMId(pZC*U=6NG z9Y;yt_cW%Tj5TNp*5Df2aTuks z28~Jb!BKMGW2`|-um;!Ij^ilp)F8ncEMyI;u?FpvtidrT9chDES&~h z(l4POtAAZ8_qn#sJ!6XhPsTf*^Vm6$o%7f^kDc?_Igdp{g>l?uXSHYCzT&)i3mIDz zvEtb-Aw8x#K=ar$c)k7wJM=;!!frESd9pI*Ma z|JTcR@9thbfBlC)T%NuZavu%YS55|wiKoh27L^6)ZG1o!uORJX+jWTokdY|vStQyI zhd)*ZL`88_EK$@3NEG*!QBjypqBt#N^?WuRa`sVV*uK$yw@c!}T-K#&U zW#TXH@7}(6^~cL+^R#`g>a{iye8)Pq)#}t#5On(qjhu+VCCY8&g+f|4N4R`wayX9@oVC1Ib{ z>eNIMjDJ0>Q(LW0ZDXBUaFm#g)`q!A501GgD5*btm^D_bQ`=al7L>$9v^LB`+upgX zhacjgB;8|mYCG%Hf|7KP)v4{QQ;SKmPHk*fr65BkJYK|tW!Hk9)Ew&*wLxu zN)K=O89Vyo+5Mjt=)SX6O`pvlpBz~VbjFVU?Xygj0!?gJbHmI9SCcJ#x0nJ5LCSPE3E6zGf{ zefy#}Fpa&JECo7aNB`#WL@Ch3QlMg`Kxgdez1^A^jYes;IN0ZQlLFi z3N-gf%Zfx(9Bz^!b_?%c699Pp?i2ar7T7q3Wg@#xksZM z+{3FWN#aO7D2YSC!iy z`rBW9`|F!0XYA<5m#BO2)Ej?pL zKg^J4?C8j=e#VYof7R<5JNo{P;*1>~anBh$`rbWf?C1ygoUx$o#^^!?dJJ!3~d zxaW)=9dOSXJNka^Ib%mZxaW)=jl1WJ9sMx(7;A9Gjt(sU&)Ctwy+kabXlLx`z%LQ& zVXYiiB~AS>aO}S4j2->(UK(p)Ww4=B)-!hWZ=a=|ShM^!_F1yUX=U-NO6_`O)ZnYm z+E*)mm1M#_Y;juu6UUD3KmK_6?#;^=ukQcbcb9jsFUvQVrz-G$clql1-J5s!Z!e!s zU#`EqxqSc4&n};p&!65s`;-3R`>&sVKHbh!xcIj${76-yjFL!ID5E5@<2#QPI7t(C zXwtOmd}g@@HTAkY+|o!Bw`jWR1OF7%1pg#W;Dgcx02R~(03}T;&1dV_m?m4tN)wa1 z#)-Pfpe8QTq=}m}Y2qd=sHs20cZ44%Y2qp^sEMnzsj_{nH1W$6)C2`3P0P9HMG_Cc zc0o;47E9B7#0IiKP4f{e^Y!c~010ZEk64WIBS+ZayN^p>ZaB)cf5Wf9qJJFQ_Boqu%fan(&b{6Z26&dV(hABWd=JaL`9A z)7N(dA4xMY9}(=3Cgvk)CVWJ)Lz?iBG!yet?|O6iJQY`UY#S}jgpb%#cG}oeR+c}q zze^-M^m&?(*jYBH$@yqwYgv7s2_Lbwtj1|RVsF{tIL$|-JT%UPk9q@~;S$m` zAF=X^AX$5#x%))Xq@IF zhD`)DZ9Zb!gg(#2e8lKyjnn2McAgE6)8->GAR1@FM{GSiZR|ZO&4iB_I3Z1&kJx-R z`0O?xF$7xUOswnJeOBYN`H1ajgX6UMh>dwv@sL>8F?2%XG#{}6ZD^b;8_-JAe8dj4 zK~3`!+ZyQE$9=T21+B(uK4K5r;5f}kq(L;!aUZR0LOcC`?7dx&Wyf)){Z|gkHxxip zwZC`v9mO6)0xXgsHNyd6L5820v+Nfj1z z?~`k1X5)jDOEcjk_M?@i`G{rGgU@b0VwH4_GvOn4q}4dhN325;9H;q+a7ejkA&Q`; z`G}P$q*-P9&POvVQRvytN34(@8z;NcO4EGA0_j0b{aNcH)<@T~_n(hu0wTjkLPVMg zACVA|rk#(7hy(QG`!MxH^M2_LaHt)AU{l;9cW8bfJ+ck&G7`hz?} zTkQCo*Wdl=_Wtz4?ahnRcQv!9GQT_`U`O zxlb{x@HQl4%r3kI362qV;T^~}@eU-Y z2*2O~zyYSQ+x6Fq7ZN&Ygi4R~<6CXfr zH}DOVCVtSMrk?GxFi8_XsWkB!3~J&h9n|xooyyY0j~dkEhfqcPO%tEOpr-z;eRkr0 z8YgxRK}~)PH{yQM#OE-miOqxFCq9TO$Wfj4esyj%Taz4H!dEXIOPCy6!q}&|hUhN- zIJShxmhkFXZ06K}+-2q*TS8S(KemLbBOjYRH3WB=J*h3>(e3Hz_Vkchx7gR`==Ri+ zf-Ow6wc|Gw+o*v#M;XA#{#M(pn?&$XP&f^5{g7cDV54pST==RjHWj(q* zJ)V0A+-VZ^uRSAyyM?@+djHh(eBYM!==SvP=dp7SS-a3@V?4S&JuGMB>@+WNaT9!( z2w5(~>?E0R4>7xil-<$osjG7q5xa$io!(`C)L^W4^v&U!fSn}!&pjgnyM=t6BysT> zo0sJ4j&4uywpnEBg6|R($U?Mk+lkf%CAo7WIv`1)12IXW0}IIkN%o(6#u^W4raHj^ zNhaJ=a}!%ha08M|xTmHjHj=~!B$;qe%}i`1K@CW<{vw?ln4{a%!=lRqLEF*osppWw z>Oc#N1L<8R+*9Kr%~WS?AW0_N!`eU#O9M$V;U1O-T38uKl8K$$(e3HMkcEVXQvCZr zZmbHluqcrFC?(b&76n>Z6X@vn)U^v{L7{`S#u}6a zYcP^ESXt{wqfEGmwSHEX`jKQ}=T^%lH-==TA4w+M!%9D^u?8i<8jNHOR@V8^C=>3f z@sRexndDno<|j7QS>|VDm7lG!%1=;|?qQK1NhaLGB0sCK28A_#LZdvoJv}z@V0|C` zJpJyOSl?%5c^^sEU!-sCnONRuWpy7(_Pght_TRY2Sc8&a4UTS4?>ApCb9-cx2H!ipsy6=;H6ioYw|{+TgZ945go_iX6sdp4?L@RVbu$mva7 zWa8#KsHj)c%x>N}Ox$}16*;+iaGkjI4k~hPGiExG@(n6-YIEx_v8HBFku#e+hlv$6 zV~VV($$FaG#Cn=RMO@agnx+&H@d+v-Ub=AGph{}(*EXoAKfBCFR?^fM6P{ruP1|x$ ztfLtmBRpet??k#cs0hy(+&dBO4JyJj#`fw%lK5rd8P?BK`Ei7Lf@6edSUppUh?B+? zZMV&%>cq`IJE#cH7}l#oQT@LRx7tSaPNaH+W5hbcnwk1#u!{;R!ZWOx zDMih#%f2kA2+y!yrW7@|x)tFW+htEAdV^zxXAJ0_2=oRO;Thw3C-S^8Me@9c^G?Kh zgNpEs(YzCB-k>5p!y;hYM3^_Is6V@`Gsf~xWO;*%@C*xpX^aWa5anh0FDWKGQ*Rra zr?$Nri+=^58lGY4FEx8etTXKNX&CRsKA*uc!ZYmhsWB$j8Fu+(k54JqVZA?P#>QAL z8k=8+F`bDWK7)$zj3K-e5#FGp{_HYFBX}ngyg@~H#sJ=l0B=wc>x}Wc6ZzesB0R&s zp8Bm5>kRvPva9EI?nu!+d$7(Fo@ZwE^b9^VJY($cxf@0A7|HG$x;qoyjg67$u93Uv zP88i^gl8_ z;BHV7<{1p!RRpqxI43Ibx@M- zVe?M)rb=wpYN(_6xLMumnRTm!qojMRaP`c>)iFteyMuwd=dKgI-%EnKgMqsB~-cb_V9Sq!^3GT*5NpN>CaCauS8l(noi9&a$7x3c2me>TAw3G#9tCS3D+AeH^e9-{0RSEaYab_( z?M07*wOx}4d(p-AqI)8VOier5qrzf)(VctIdPIJDabyzNQLy%1WgzZFWAE}PSo=^z z!jj1LL=xG+B(lYl$o51M*}$gpizSimi6pY2-o;(c?u#Xn?TI9^fk|YGC6OHkYkNMy zOd?w>iR>s?+x0HF_E-|xo=74am_)W%64_C(w&UkH3f4YuSuKg|C|KJwi40~nnsq15 z8rl<$^=__NAq{8UiL(YJ5k*{#XWhxO1|=20Y({B7>rS9GD2W*SVnpjsqBSUq82n;L z>rt?_YpQeSW?1V^tTp!Y5Nlm5iEJm=8kD4a3~W6L*7p43^=_{5xWTPE;nv{KgBz^H z=+>QdYfw^u){c^C6g%}#NxH{K*P~!HOWApMTSbG$#{rKwceLw2L-0s*U zVs7_p+-o8C8kEGjXEpA%FtiJjX~u=ZV%0&=gxcZqY)QLy&?yR0n9`)rWdyCnCz z8uxk>tnJwv)Og6{+_M_@TFAWye;(}IR^wg^x!0g1-DBKqA@>@SB=>q0tbJ$5qhRgb zjhdYYCz1ZFagVVECBYhuWDSmjweRL7x!2gwa}=yS@70fjweKcTf;AY)8mz_|90hB8 zb{j{*+6P0<%q>3()^<#yqhRg3TBFyz|CfGVV-$m z-K?M_&pitZXB8ICib;|+SdBF}3fA^aA}gL{tU*bz22;%gZYGhj28HFbg1Xcbn_3QE#F#u}6aYcP>DI11Lj+gP)VR_y0tbKKSH zXcgAc3QE#F#u}6aYcSP#NHf)qHTZv4u=Z2cLOcELho4@(xP4nobN=S}=~Hz*K7IN8 z^p7uZUVVT2;`FQAo40qbzCV354%;WoK9*lxeSG!i?cI-e_jiA}{qxnc-~W7dbASK# z?vFp+*MI!^>WeSG{_SV~boER%6Y$it-4UzRV;i;A-v%-sYU7p5i=6F_Sk3AZlK5uK zc1Nr}V+l!oGiED?q_#%=k}QWbTRkN8dPzuvPnvfYL{d+Uge2&`*(xHb(Lh2Hbl+?x zkyOwHhSMzMXHv z-_-Mhc6r~!#AvZ7U;KvEZ%?L?omVty;?N;Yd;)`-_z^WuoI0e5Z(vN*>Lg4olpsxf z1cRFR88uFP1*M7KF{p{JpfpjmSDIDk{dHwf6Q99hVv{pz)+yGjiSM8^QS4fp_z(ui zsXuGy65E_f6JNrhrk)L&2z*Hs8;PJMHWGSvoIZrMCw#;lHEEiU7&s1&(|p9pvBsJ3 z5wp}ZP89K#=7)ULe!Grx1xLApqg(-kr+We+ILZ|q!u_Bm>sH|X-YqDJ{oumwpd_&!3`$}5qd{@J6+flBdz91M8`d*GTT-Lrz#3HtR>0f(}as@}Z0&ZCo2*F5%U@?S1L7nd1 z#!;@|ab6liaFi?P*cy!NdAk@wuqP0Lkv(r0LkNy?1wB6x8*wexiEB?F1S1iG#Snr$ zfe?&Gxq^qy;8CvNap%U4T(OrkD(|#QIw!0V{V3`>_kz5l8m_-in0?$2}&~NW+=)|6eTFh zn46&}J5iLNr2ed#mxiJgq9{R0Mhy%_DMV3%l5~%uD1|6WOp++dVkk->iV~EhdkjS> zL{Wm0bdR;^I?5IFe1dBi^2=0TtxZ>9o37x`qd#jU0WSzy1iTQGgnL$N(^Zag1sxf^ zH6GIbJdC*&w&{xfJV&{Lhom=ajZoO8EBG$yo}*mB!y%>AvvubU-^eyytF`GWY||C{ zd1^{U;~s0%RoJF0D2bihYON8X={vD2U=cW$IkmBs;jJ1B{B&rz=6U5476 zxGg1XAh6heam}&bMVG9>YON7UP4noMMASf7v5iu5tXq=qIm#70ZnGBcZ#v)QQLf>efEW33U&(ocy_wR~ecN?Uu5 zas}~S@Wj>#tF=ZbiPi{HZCl>{JQg)bv__a}+ww-zS|gN1YlP`2SMadET+Ka4xq=S& z)bfq(yhPHS5^(!Dx2fh{w36nYt$*h>ku_M2H7E(zKZ7?d#XIc)^SFzx?dQ&71q%x2KOD{--~CDd&$pj{ z^~v@1I)%#@Oe;GA8eu739d_cKc;XEz;>2qQ-iZg^pdt>uOtRc2CRxT5nPkZnODQ7M8dStbbK*C1n(@sH zD(cTJ-^_`h%!!BHpdvOLcGjK9)dv;f89VAuJn9A&;Tb#WPPL%HWv?DoglFuaJI&at z2NmHNW9la|^+82=#*q4n9RP!h@QgJ8oOsF&DQ@-F|1uwEq$O`tt#{w~%WU=1zfm;L zkf#rhQGeDbnrDd9H;U~#cBD=psnd_Bwq0i)o!r1iv`ZDl)u_vxG2VQ3` zcAdE=t}_Q-XD)V~xhJkOhuV$q@(o(-I`ioC-ZhD^(jKYPN9uHcNO|DF?ns?}H;H(- ztLNLN4$1S;>HTqQUUN!Zbb9ZZ>PPDI`3i2a>&&Cm zd)Fl5+GE$5d*V9tNS%KCULKv^AG2PM)am%0_&6d!zZ|L4N9uHY-x1rg)>3lKHtR^8 zew;+C;vamMxZhfi)aiHcvLB@x>wR}KFOSseckdE+!?AhED*nrnI{ol2kJRa&?SGAj zTnu@1dViPUaimUnY*}kJx^@yV=2j{yd;vCMAGafQ`T;KN^R21lp&ci+n+b-Lqwd8AH1eB9W$M>*pl`(g_P%e1dY>h$9-m=t;NT_S35bb5dH zaU)3{e3ytC9I4aq-(@0daHLK@d@qeCKRUg4?A(sj>4#gXBX#=Sm*_~Hj&E5fvIa+| z_ji-%NS*GPMA|wvaUx?4j!y4A%h{1S{jeuGQl}pee6=g?-;E5mDQ8FOv~{OfGBysq zN9weih#jfZFRz|8Nt++cJ)2gN^#;}-snhZIh&u{9=pL!l(f9b@C3X6tw8vu!km>nX zr>5w~ta>0S`f)DxF%07nFZHq2s_T~xsudZVSY)ims-MbYnzmYWy-{S1v57Utf{IwL zjLDzKtWfoK9 z8QD6SP3&YARK&%)6&IUWTr8-_OfV~3z}jL#Mg7@jh8v4N@q8RqglDXa*|gU9`}_X0 zK}C3G<(;~=fC)u-W}R&I0Otyh5uUNLu|6b;F~T#}!E9m&v)~xv8EarR)eQIEUuHz9 zkCmzWQ%!L1R)lAa!Jk-CEcVn^Qp`NVief=U{n^DcR#0qWL9w7BJY$FAi2#035uVx1 zGqqHA_b&s_Z04CQ;h7Ph*=(KRi8%Pw@QlItQ@w2NerkATvvsDH>F!mmrPZ6+W1gwy z%DNTdnT`C`#HMAj_sFJYn|Y?5xx2@x|M2ChcNT!1YKiV{MR;bny;-f$-K_}E7a?MklXZD0=Dj3ixnrCXcvhJsbXLj405xEb}9(cxx`-#oUVv1~5X1&TL_9_c1 z!ZX&YY+|djpd$8W)~Re_r?Q};{_OHw8*M+aQCUzCp0Pe<6Z@0}72z3cQ#P?pSx^z4 zu`Xp3yOaeL;Ta?CXErGdD#A0?qikl6vY;Y7V=c;NwkV4!vPGG7D4W@#ET{<2Sc9^e z4a$Ow@Qn2*n`=Gp-mh6LFL&|GaLt8gt_kejk}%D1&6Q@Z^|-qw;hN!^+q3yPvDC0X z*wtFh?tC?imv9sd0{0(%eJH zKKS5RbOwX$XZ9xxO42>npKPv2=k7^F_YB;t&Gk~bTaxY>%sut++$%}Qez1amGYk5~ z-X#nA4OY-^WdCr+f&9QDty2tvH&FoJWe3x|3XzrO3?x|6a_7^wz)MIq-gV(S}D`{&FA^X^a z6S5x+vY*+XEGS9$jJEdF1oprC;4RJY&6}I=YN7YfU%&e2yYGK`d-KPax8d8K`HauD zFN%BSedV6H{?n&#C{^U+; z;GT4`J?YLpX;2cIqQ&;4JNKkPN$iOh>mIbTdr(jkTcV@L^t(xP6q$~vVhr_G?y^^3 zjv~{Kg_zh#C}zldGuOOJ>m;qnVTz6uwK}plKQj8J%+v(qOU!fX7XB;8~DYvC<^P!jH0 zd5NzF*BtA9aJc6vGX1#QD7?TA{ycDxIE|LE*b4dApd{QQOv5BK$9jKp@~@&aOfun~ zqsa7QMQFy{3i;RAFHZh-J&H^}*3cpU8hn>@kMXaC{A)~-tie%a`rY@E{A=)Ca_uqx zwUB=eN@C}>8vk0zzXm0-b6bsnE#zN=lKQjD&TTdRwUB=eN^Jx7u0_?7!u;~|Y9C)>FlMW#F6CChHDR(Go;8d{G> zk?Etz^v73suU@>{Z7lugo}|(~ShLES*N?(e$$qMSi|>`4HIHJ=;rCbzPhGxccFsJCHOJp0zO{D7 zJc>1k-=iHcvASiZzFQeH3fHdd73)b`)z4&z>2PG=tWUV$JdQ zh;@c%;O!{Z9Da}WM*XrX7_5F2Yks(yi7l{4vF0cFK=Fb zfBWL}tJ|Bmcdx!beKZc+C(AyTcroXJjgn@|9N(BZUak4mrGuI@AYe6H=D1QJTZ0EB zagvyMmAff@FCmGmk(oESlEh7JY?Qpoo$Ua=@gg@UiHqEs_qZA*?s0>XI8Dr!IleJ- zJSZuLUG@dDWsYym91lw3lRn!ad}HQ#P!gZ?nfK9pmzrajg(oPfKWiTx*U^&1b#zdY z?%{3pw(~YRC`tF&L44=@|y+8eMd-LM--OZcRpTB#1`!A<|7_L8=#?xO<*Pm`nlu4OZHc3LA_ibW|c>PK~ z^{tg4Y{Grd8Hm2j=%64>Vi)hM@E#P@d%akM2ANpiJt#5;U#G=ANSQ8r}1qHFBSU;qR{g8r+ zw2FC!>EJ;{c*U~8Cw4;$D#9#Qcz$9tq@W_)V!e5M*i&qnygGQrQ} zbFZQuuFWxQgcN&fYlLK$VIQQRA}nKVkj~h1_fx|&)&=QIJ^x+BW3_wa%#PLWSnWc) zE;ax>Ry*+%$7*-=EcV^6$yt{T@v+)f`i4#aV()SLkFRz|Z0(uCb=c1xv9-sGh$FW4 z5RY%dA|Fo77?|vF#MT}s(Ggqwn@Mz>HjdNALuI8Swiesy9H)(EM{Mo9OU5;4aPl0d zjb}$}?YK$$+YE7Co*_1lv|j}@s=qp~RTdnjj+><8CMg;dI&PAl9XCnmH6BDyY>nUk zGu|W}4b+bY>W}3c>>m4Qp#BgP(eC5Pec608P=8kggtXMrK)q`cVW)dEP=6PmB_|#; zBsuY;f%^M*Szq7#15@x_V&A(=Brx`RHPtN%gld^c9PYJ(SGOeHGx4Oj9}U#w708bU z>W|CWO#W~`8mRY7BF0%}Mq2g-anjhAsG|B8Dr1>R?e2-9=3_daZ8xub!4$6kG8t+~aD%^eNYyWS;tZdP#a zXrSKnE?IN#XrTV?+>|3!1ZyyoHCRVR4GP&sQxmn$fVbI&@F)G4*ZTyF&C zXrTVE=o)KK60E_|K>gv;aGlIOwak0(ygVAHKXyB}bI;sQ>WsB4VDlxK?c6gb&ONm( zU@K|oo?2qA`xocV%~*qyU=2pH2CK0KCBYgT4b&e!zS!DR&(@v4_*BaRHj~I$gOXqk zrfWtG7IRO{8|oe<-Lsf`jt1)SE$h)h{n0(f8XOJOJK{t~1NC>4h_|Jso~?U7Ze$IP z2I}w5kO|h{zflAAqhapRF!%1&i$}9e1R3jB=*fD@N5kANuAVJc&~Vk}_3{Cay+=Zf zwy!uE=7w8;)w0CRS%l}=qhW6NJ=%tXk)WetZu~vsAZy&>(J(ju9sw;HvpA7ijD2y* zEE=*n5m^i>0vp-PGb9#+inx0?8s?rG47d5xWVAWnQ&rkN)k>S3{IR0Ck7?4)(i$G&MdqZl!S4HYbFHGY-9RhK=N~ zj)sjoy9TEYPe*p+!`zdgA{QvGPe;SX@Grx>6H7b!f7QZj`sMzIt5agKyY>Hqom^RGU+zFwzryZC9X_XwB! zNF)6xlKyp<^7L{;(tl!Mr>XXmzif4ainyb)nt~H+3I-JsZ?}?y6H5vP72$HD{3lZW zK}EQHGMCTTg$5O|3!S(Lo#ra?zT9I>vECyzvxlJARMY3X6>&#pg#SdsKR8DHSu;js zA!?ti?lHnMv#pFX2<6}yaeT89I&-#Np#YyF2Wo|(-v%ZEJE zwgNlYy@TC5*gbeJ7Rnpoy@TDWOhwJMzkI`j?-A?OYH^R+w6|Lk>y_0WJlMVPZSKMD zX-?a@h=~BP8P1}E2fKHsuW&93zDMlw4tDSS9%=w?Oeo4gF!{CGY7j@XV1azT|JA<9+nui3WHP4sPEmS9PHk~?%n=bE}XCH z6nr1ii_J%t7PQKObIqjhR>XOxFqSaaMEY(;J<4UB8Lqj|%-0Fi)F4SK$(3flPOLOF zO43SlsX5ra9_*?XKWN`2L)UXXGWSj*-sle3jKj?}->q8`ak$}{fw-B?Q)6~ytMK94 z+%qKHv(i0-xo1eYXQg`vb5G5A>wcGXkM#?mheSZ&VD}DoudVwyv#?;ykO#Z>Fo{OS z)8;V|PpdJH=BqyP0%$(iy$+_7g#`yIEI6~UU~HzLAC2^XVcW#Kbf(=nnQcrgI49#{1-*^TON@7Da7jB5QTGg)mU1CEt z7ak|Jf(=n{l=`#w!TCwwYE`@LQPMq@L$@=BE;vfM$CBvwYXp3Ql5|huabmBx-@OlB zX@&M(@;I^cC>|RnkK(hP#dn^?8_D+j`^}r1??MNo>NE*e~5jQ`6GL_}} zG=4fRU!1=D%kA6WzJ6KhO6^qY4(0RLKfZZ+ck}B0^z9F~w=YlsYrXpT>do7`AMft( z{!-&=zyJB_=KlWe-5-CtumAY-)fZoW{oBv}No98CiqKsic+mdi-;qJr-cyQmF& zsBNkN&hFnDo;kp-1MKR#bY^hbV#`NSwlMC?z_P`akD_ex_lR|dXLccXIJ3vTxHb9h zvKI2hE=8Q!gNit@^SmxaoY#YjIIr`xF2pIZ&eY_$=Bc^P97Wl}^YJLkb`)j1xgpn8!IKZy1Nrdywa1>?x?g4y0z^)E*sD?Z)+o8cOP!F)H$B?{39qbZy z<|S%u|NEa5?E3o4|M|u9(<5Fme7co%55Z~bgze4Pje6T@rUnTYta^H zB0?%nL`Y+rJh|#V7co+4)}Qcw{4uDB7^yT7C6y+kq>W~K2X_<+vb%R>i0f5de*dFL zP>uB+MS`xLRog##H@DWWLo<8qp5Z7G6n>A`OdLgmstb=IL6|-5I`$vJ6X#NkPF-9p zLLF=VzLJrtn~JBt1hddE)5MxDO|1DrO|JPPQBG-M%@1ngi=}7BH%ppz>+pVW64cbQ zHSbeRs9V-dnz$VeY9eYqOxIw|q=~q7P!nstG!aCQCL-5CO?V3k$K~3{7 z3wlZu{tasC&)V+{ck9xGe}kIlUl#S0Cj1-JH2<=!=f1M6XHe68#KNA^te=72-`#w~ z(w@>x_=u%F2NiDR{A6*@=GohC*Rj5f5ZBs)??dyQ|98H(yj?ri_sdPwf3fv_yuLsE z`ghMyU;Xs*CD6upJ zN6DqhiV@CRKNqprnhNbGvBBHs4GU9nlw6pMTAdTr>P~8PFl=>BV5>Xp5e~+!&IxXH zulnWo9!RemO z+_NRzQ!^LacZqY^HrF#m_bBNe!&m17zN%DsjuO!gjS{=M*d(eazxKhgsgq71AK z;MYpp+LLH2yw`JID{1bjq5kes(mht3Pzm%2NxH|X6Dol|A<4DJ$`dMqJ|Ri>7{;mu z`h+CiV;G9=gYPR)vNVl5~#&t#bls-D@|8<`*}jbx9Dd zJBikT>8IPm^wZcvVWD+K)+L#6k44s*d@9L=dsrf2U|e023HR8!n_+cHCfrkdI$VD7 zkx_L?Cfvh%g(HLNl1#XV^$JJE)Fqj44?E9|45>>pvGy!*&&Y`SwlJa|o9YYJp3!;@ zFNt2mJL?sW*W9@+iF$ ztXDW%ui+)pYk0S!KvorKVO5~mB=V|2xX;}dmIVq*V&^s**1E7RP*9TY;jQYn@K!Y_ zN%!zlRgww!)ObiUFL|db$;8f$cd8?=R3%xTwKHnKE7g%Vs*+5&hxH0aUZ_ekv2$a0 z#F6)@l1%K}*dB4@b*dy2J2#?_BX3hBnb^72ct|sec$q56#M)EiA+4mXJ-kbexu?cM zT1i`bc$FHIqu~=Bopqb@sRexZS7&3#Na5o_DqbqEkq!LlKQh| zl-4M5VWY&LBzJDsDRE(^#GoX1Zq_PsVXMTTB;8{ehH&tm7EdbaMCqANpnwvH7H~aM(caHBv^w|<00)R%{>X$ppZ2fS94E-H7G2Q zH5zNMBv^w&)?hT&U`enBg{;A7tih6C4GLL<(TZd(3D%&HH5iRGSQ4y3A!{%iYp^6( zgF@C|G}d5Aum+{ZLz<~>tih6C4GLLsR+h^0_b(J= z4aUvZo&;-9$Qq2BoqH0jK_P1}Zg%cTum**F5JzJTmIP~1YCNR*#f>#s60AX~@sL*1 z)}91wP*^c*G}d5Aum*+g7)E0amIP~1n0-7NYp^6(gTmzF(O82e!5S2@2BWbCOM*2h zWDQ1R4VDCJP{zYp60AWXYcLvXuq0T6!qQozu?9@u1Z!Yve3r$xSr%XH@J!ZVG}ge9_=1u=_ZVwnjDJv) zQ3GQQEQK#9sXx0+BFo^@yG%q4$QoDzpCl7e1F{B|zbDB=)PSskrSC~H5j7xdVA*?{ zW$y)l9_-vEV-3~>Yf#7H6GG@FO4-=6RbfYYcLHw_pAxlppZ3~2A+G?1Zz-gJfwYao_p2=Yf#7X$pwxIs zD{1aYum+{ZLt065Pl7clH6GGRntKwgK_P1}&E}p2Yfx%Dq#Y%1OV@tZK*hvyTRP3Q zbL(dfB#EfOWURs3&l*UQYmc!8Yd>osNxH{agSDSEkR;u+n0xwJ14+_7#u}{stbruy z9%BvGe%3&ebdRwHYd>osNk$EfHCX#u14+_7#u}{stbq#W(>;s1r=K;DB;8}I!P?In zNRsX`)?n>t4J1kT7;CWhvj&o+dyF+$`&k1?(mht!VC`oOBuV!eYq0jS29l(EtggY@ z&l*UQ?lIP2?Pm=nN%t6Qu=cYC^EFumHOl4wvY$1OB;8}I!MV9_-?>MUbdRwH=kC7U zl5~%;25UcSpi$C2#u}{stbruy9%BvGe%3&ebdRwHYd>osNxH{agSDSEkR;t>bq&^j z)t4Kzx+ z$5?~4pEZyq-D7nP)_&GNl5~%;25UcSAW6E%ScA2nHIO9TW30j2&l*UQ?lIQjT*

t4J666$5?~4pEZyq-D9l5+RqwDlI}6q zVC`oOBuV!eYq0jS29l(Ej5XN$Sp!MZJ;oYr{j7l`=^m?Vu=Uq9n6Jqis1X}>Zd-p{ z14(l2G1g$~uWKMly2n_9t-r2;B;g*NDeb{E$9lg+WDT^@Hc8E~Zb`UDyAPAp9P5^Z zd-O>*NzJitNw`Pzl#=~*4fONCJ^E*p)Ew&`CEPO`YjEyx-787fU^doZ>t_u#D!6Ah z)?n*r4I~No%*GmQ{j7l`=^kSZwtm(?l307xkj;MagnP&u%*GmQ{j7mTN%t6Qu=TSB zlB9c#HQ4%D14+_7#u{w>tbruy9%Bu*e%3&4LCkG7)?n*r4J1kT7;CWgvj&o+d#tX( z*3TM9lI}6qVC!cMBuV!eYq0gR29o63W30i}&l*UQ?lIP2>t_ulN%vS?gRQ@=fh6f3 zt81|Jvj&o+d#tX(*3TMfVW4}guEEyN8c34vvAPCo$p6teS2CEuHK9e$95{g()EsUsc zgb77_5G;zQe3pbF_M#RqEIPU!mgUp_zm>Zd>daQEu_ zk59jP`})=YcYFG19JWss@7#Y8ZDXbylX&uBrAUJiJ7)kB}%I zzfOUGC=Rj1&bx1k;#(LUDLxw##n(`x{BQ(Es>i#`CW+$PAyIxif};3%NEG`CiSqLi z6vg*LqS%j@^O>*z*T*MBqS#YNlpm4cNbwbsD0USRtupVE6obD$FTy2?eT78%DT$4g zSK$)H*F>WHnlz%V`KMp*GI@3V{p-`im*DHy^-J*L{4YOyar5T>_U-AThyUr@=f608 zw0!c_&3Av&|MTtVUwxu9iz)mWn9j83Wy;#+#Kg;qX2c(CrYS`@%kCzWCD;C3K}Fcg zt|pWumr#VK>}F!(%|vjFFqBm4Zv9xtUS2&5zQg2)rFyTtcGF~a(Osz)nnPO zUcbFPeg68#H!tsQUfrL*{o(fZicJs*zyJ?@u^VX zKa)h{B`B#syX>sg_m7gKr-PE%^s4WlNh0bJl*F!Aeg90derY>@9@5k5`)87fxWqlJ2pKkDV7EK}ovDZa&T(*LxqFHy`Tz$EnV%kJu?@V(nq2 zHue3ZB!iT}NksS9>27C~GAK#+SeSBWm@+2GFs1tb*@Gw69@5k5`)85~_wazHzJDf} za1ZI}#X^-kLzTgI$+gE~mFJG@z3ySGQhopI!4vLbr8f2bGs%Q|SgCEXaOKW$W$<0n zJr=Lr8LtdV(mi(2+ZnJ7NvelB7F~;2?u=LlB@wYy-#`953|R&xxpOmmdgoa$D9N3h z(bGHW>7XRtWAyY+dO9e{otx3qJL&15BzJB`PoF!kcY1szJ*~cf{KZL62S-Ww7(IRN zxZXWVy2t40bI0{wNz&7c(bMOS>)n!ckI~cTj_ci$bdS-~=Z@>$l5~&J)8~%s-I8>V z(bGHW>DVM9J-rw`y_22}O42<>Pw%9sgOd8Q=GicJ-?BBVmhdO?7qo;RPY70I%-DC9h z&Pr`TNv=IcPw%YM7L=rWjGo?EsVyj}KWp4$^z=@8Iw(o^7(Km{o(@XVJyxl0Cp{gL zBt5OZf1H=3r-PDokI~aRE42kBx%L=6y_22}O42<>Pw%YM7L=rWjGo?EsVyi;_ZU6B zvr=17lJ2oeZ96Nq1ts-ojeD$8+s;aDK}ovDDz)vb)E1Pad#qC1UeDIOUv*Y$Q{O+j zhn3o5qhzJF#VWP!tkf2iqwe76b z7L=rWtWw*~N^L<&{aNE4tJHSxxZXW4=^m@pR#>SmI7+(5Dzz0>YKuv-Qk(kz!99hQ z+Jcf?dq}Kr=Z@>W?~=f}`u^D{6FWCnYE$1olhhpR9wpqPzJDfJUteFudaUt~%e++I zKaz0Ij)c4OMHOIOo^ajmvE2z{+VQA?IED9zJDgE zFLdv_Bx|6)eVWl?p{WHmgdswMW zeg8}{;T~3MQ{O*ICRhXYP=_InH8^)%@18_-kFf^lj_bXWWDV5!&mKJC9?@!ac0iroMkBnQ#yDE7kYUBoppor8f2bGs%Q|SgB2Y|4cIB9#(2o-#%Ed>4b=C~9z5Y5vIgq=XOao`kTp=>Ka)(jhpd76 z{+VRLJ!B2k_s=8~?jdWSzJDf}a1U7n_5Cx+gnP&usP7*o6Rd%HsKY(R8k{?>cTaV? z$5?}N$Ms%GvIeWM2Ir3J-I6%>ti~FgJFa(2a_45O!MWplw>j_ci$JogxD zaPGL?Ey;6_u?FXk>)nz(_ZVw%?zrA9sqaE_?lIP&Bv^xyUE$RCkA_UJ1|z$|sqddj z_MdyyL!A$9YfpkTP!DxV+S-#~4b(%OlD76FSOfJ?horFvCBYh~hdL!~?Mbi(>Y+|a zTYD0$fqJM@($*eUYOBlTlL)+es8iC`o&;;49_o}d_pnl1aFkqoj5RoST<`pBsE0a7 zY3^aAw%90HsZD+V=y6tR3rf;G#u}VEu6I8;-D9l5x#N1bB;8}I!MWplwY)xp z8f$RwxZXWVy2n_9bI0{=NxH{agLB9AZb`bwSc7xN^=?VJ$5?}sU=7qm9Y2q;1|`87 zoC{7hJ2ztu$_H74BXwG<^pQGk3FG)~+JW~d0TNI7#W&LqyGQDD{5|4(X$Re-1W5Ef z{&y(>a>NyETc*YLL6G8mo7~vT^8|y=o7$ZDmM`OL_gd#j+C*z3}e(b63WXyx{ z#Dj5Akq2W&m8N>7Ekrcxm!{H;frVNR6LQu4~`L@u|u&MX(z@A&)AuG z;+Z%&MtH`K#1oIiK}C4RPQ>b>op@?^#^C#j@O^NM@Qktd6WRNiBH4RG?G4~Uh`=BB`W61qPhD&@c9j6S7x0+#WpP9zynmLH08X`UOYH zwZ|ZPHOub*suQwTgEu}nA^YGcx%L=jKeM1;P?BqpLH09S8O0e--)Z>u!%Z4GMb&!CB|i8Qe_32O4=s%~cXKJj%8YI0|< zerD8U7DiB$pI3D>GtGpLYJ?2$(|p95kFjww4`Wc{Asgq1eAIrszIpxKpKk9@KiuBD zIDL2X=Je<9-roMp=^uvcPp0v)C0q2XrfWOQZtl6y81%(1_51eJCryH!+U@ggX9&7m zP_Op#J77{v5R*DMLQHDRXbECQ2L&;sF`c(F{@ne@n9i8X62x2%ju3Mh6Ip^-5MqKn zrD7IK5VJTah}8f~fdsJ>1O>4aU>%TPwd?zJASei@*zt6#-Ko13X%(yi8Y9+#;27Z* zJDg6nH+AS*RKi&1O)c)chU*5d> zUM&cJb$jzxokt%!jxMU<9_F^@q3+%;tIKTHWE-!^s>h#N0VRnEKHEK+O2V|iOi&Ut ze71|SjTdD>NlfwCZpt>^l*J@@Q#RXG*~Y7~pd=>wYX znC-S~<84_`5^KY3*JT^8%Yu?v9A>*OQ?K3rd0A_9H}0_uGj-ZcNYXuaW2Qd42}!!g zuFTYBHz7&)*qxbr?Dk9Y&P?$JY@O9%Hz7&)*sYoR>wZA8{r*nZ_orX~?)mAfpI*Ma z{nyh_KAnF2@$~K8i`(cSL!l`A0P1CqM=Skoj3n^`tOm!FemG`6Hz>bM=GEw!(oe@o z5E~l4iO<(+fK2HJWF(2t*J^}J=_h0)iO<(+h)n56WF(2t zm)Z{7yu|0L`tQlb|J+KrnMAhu7cTxmNxH`t|H8#TC`tF&;$OJ<$0WJ|U%2=OCG}^`FK&x};o={ZqhzEdDV`F8(VQe@RxA_wkCLB;CWsUy@k- zgOYR)nHfoHj&+Yx|K*E&l!VlNf+bnEw!IGy_iSWlB&j*pEeZE*WM(9(Io2%+_b7kJ z9z3!3)SRI9T_O^xZEnInWM(!Nrj%sDJvA$+9VMcXl1#YAqLE}~B$;pznVF5uj3g88 zAv3d)nUQ3|J!EE-M#M?Ppk&PBWM(!pGa6;WJ!ED!h9xDLa1WUoWfIwgC)`73MyW)U zWMDG*F0uA(j7;i~m~ao7nT?@INhaLG(BwvDMv@8lkeS&SoRnn3J!ED!Mkghia1W!C z8^e>5OsqX*W;QZ2l1#XV%*;k+Mv@8lurTFDW=4_;_mG*{434-a91(L53sY`nW)u%e zxTj_cHEWNd5!XZ`VxuG)u^Ab0%_f*ZN$lJ<10$~M*}8YPL1tz%F5#Bdk92q#zS1sbzq&_{~8Zz=OylvHOhp0YCNQs#BH)96Yi<;kVcY) zDJ7X$dulwSmBf9rBopqb@sL&$^o1l7?y2#RR?>EEbHY6}9@0wM&W(jBV^f`lDK{3T z+^<=fGAK#+urQ@0``vR+A8H>QR|b;och5P0sFgJLurOul!Osaqt)#h!g(-uQ`m;uo z%-{q8xZ5Vex#p8k3p^Erp8l{EMC7u=8}-NT9-dhmYtoO6iUQJQ=DOKxbCTzgn^ zW54dNxgklqhebCenQ#w_ZfvZ&A<2Y$SaoA#*$qkduRU{(hqOPBxu?JG#wGcsFk#xTYnV}Nzy$m!?9oYm*J2k-9y$ulKoMG za}H7a;1;n?um-ai;;@}tf;Bkj5VfPUom+x6IOh*oDAxZZbYoO{42}!!gSc4(K8qCaf(zU%kc)~r*cG6v@Nha1FHo??wj7cWeo*ECi z%u7YRO)}vgvIYtTQZm6B%w!D|%rMD>d&nB-glCco_mDNv=G-I`?jdWSy?{w3+(Xtt zD}zZU&OKxe^ffcdgnP&u?8X|XdPDzbgRH@BtbwXGBqZq`V+~ZjAt8yiXE)YhNU#Po z>vQbJ8mM|hVw6~Wc4G}xy`f){tif)q!H{4LX0ismu?DK%kQgP_p50i3A;B8VWDRy> z4Tc13Fq1XdjWtm9hQxy-YOot?py~|?NxH{a166NGNYXvV8Vm{6U?yv@8*4BmSc93Y z!EUU9Y7_K7I9Y?;SOcY#CnT|R+l@6C60E^Y))?j86%-vXnA;B6fH6GHOA!l<>f;Cub zJfxL0_as<@rN%>ANpnwvHCSpqq>(h%U`VhAOO1!LlD76FSc8R4Fn2ch(7fz-&qCH< zH`ZWCum%g8VD4=1p#w(0dls?=yRimCf;Cvk8tldz3<=g?A#1Q3YcM2OgN3ZYZmhwO zU=0?s20MFv=;!H=8Z2ZDc4G~O1Z%L6HQ0?c7!s_(Le^k6)?i4m1`AmOmEYnnIKdh$ zWDRyU`p{WA;U2OEyRimCf;Cvk8tldz3<=g?A#1Q3YcM2OgN3ZYZmhwOU=0?s2D`Ba zLxMF}$Qta%8Vm{6U?FR;8*4BmSc8SE!On&snwN>ShfOedcKncJ|ITe8Yp@$@FeF%m zg{*<9($M1x)?i^>gPnB^6x`~M8Z2ZDcGfkJWPj9PVO@irbqyrhA9Gt+*I;K|14$;< z9aHP~6#K#~dfkTuv@*Fcg9_mDN%jWrk&tieLo zU}s$ejj}&#u#h#_jWrk&tieLoU^muaNYpi0$QtZc*I-Pr1`An(-Rc^Q3D#h#@sQ?N zYOKMSU=0?s2D`BaV}dnUYCNPJC8Gvof;CubJfxLm)L=}o1`An(VywZKsB5s0H7Ld! zjETAi3t59=tihP5Yp{?tD8?F$tgl)>o=?`)S;!g`V-3axYp{?tD8?F$iMj?0S%YG% z!I-FPu#hz<#u|)?x&{kbgJP_~n5b*8kTodA8jOj$1`An(VywZKsB5s0H7Ld!j0x6Y zA!|^KH5e1D!NR%*#aM$e!5S>AYfy|e7!$0)Le`)dYcM8QgN1bsim?V`f;Cvk8Wdv< z#sq7ykTodA8jK0nU}0T@VywZKU=0?s2E|x|F~J%vWDSb324jLXSXkGf7;7*lSc8Ri z4T`Y_V}dnUSl6H!YcM8QgN3X?G1g#Aum%fRgJP_~m|zVSvIfOigE7GxEHxf-*=7}E z4aNj(pklw2w4GamHCV_R6k`p>L|uc0tUeMg6Rg2P)}R<`FeX@og{(m_)?iGq1`An( zVywZKU=0?s2E|x|F~J(FWDSb324jLXSjifc+1!(04OX%SWj6ODSc8?UK{3`~Ot1zk zS%b2WH5e1D!AjPk7;7*lSc8?UK{3`~Ot1zkS%YG%!I)qTRU`((ED_MhL ztihOI4OX%S#aM$e!5XY&4T`Y_V}dnU$r==64aNj(u#z<>#u|(X)?g)TP>eMg6Rg2X z)}R<`FeX@om8?NA)?iGq1}j;EVywZKU=3EX2E|x|F~J(FWDSb324jLXSjid`V-3ax zYp{|vD8?F$3D#gGYfy|e7!$0)O4gtlYcM8QgL4zi=7?{s!I)qT&OI<&N!z(4Sc7v5 z%vRENZVA?4C2LTOH5e1D!AjOZT{1wIj0x6YC2OEA87A3J>YUqOHt*6{gE7GxoV#DP zlFU#T6Rg3x`DH6fQfExC1}j+ub;;nnOt1zkSp#*+Fv)(_U?ppyE*U1-&l;>`4T`Y_ zV}dnU$r`9jhK;g6w{#_Ipe`9E+0PoRWDV3M!z2^#A#0#687A4!xvgXk)FlIwQ-U>E z$r`9jhDj=}+nIi~k~L7543q39byl(l>XKoS3HOjSP?rpoOt^=vfx2XvWIw56JzQ0} zg7&dCuAw`3Z{w;y88*&@e@Gi>oHUR%a}ACY33Ae;gRGxxP*cx#SuCV!7D@mID}e)P znuij^!Ajylnr5N|a|iB! zAWid8f;(8r9Z1uBlmHJ_f(OzxA0^0xmE?gm%|{9JU?qAWP4iKLJy^*eNYi|jfDcx} z2hubjCFp~d^no{df(lj3>xCC`4v}ZRTCBTH0V1mYJ zK1z@YE6D_DnvW7_f*KUsvzw0+Y=Sxznx^?E0Vk+Mp=p|r5_E!k6jIahgeie1Y{U~( z*3s6Z1fQTTg*Hy}Q36od2qLxp=p|r5|Dyg z6`H2`C_yQxSD|T|j}n-IniZO+`6$6Ds9Pa54OEyCpn}>Jnx^?EK`N+Up=p|r5~zY2 z7MiB{D8VYIW1(r9j}owgS{9n7`6xjvsAr*RnvW8=f|?eZruitrE2wLsX_}7`z=GNq znx^?EK`f|mAvFzIm=ef>8W)qXfOMkzN?C4PTfNr4lxlN|2`cD8VnNi=jQc`6vM}Y%G?bahi`31j9yx zL7L{H1j4WpVUVWzC{ZtABf}s~^HHK;!bXTen&zVf#jufL7}S7+-{eHegpC-3G|fke znhEM=$oXj?!;~nRun}a?IL$|istFrO25Hhq=k|x4@z0GYgEZ-*bN|C`OMw&sI^wGHmV)r<0Ju;r*+yk*&lk1T#cj2RR6U1&!u1C7)GEIH6 zyEW+}UG|u!_CDR3JRd0lYMPpB-I`pF6bPecf@e@`LwrLNyf96jA-cy&9}UJcoLeFG zY8ua=O_+^SbFEvG=OZm1rm4Bstw|rroTjO{)~#tiGM?ew4zXL)d}KVsoZuNY;~56y z8O{w6yT@rhGM?ew5wTm-d}KVsoZuPMM(uRgwd^Y-q?yZgJp-2VCM+3$b8y1Bo9d-unm?(0AP zeD%ebU;p;Af4X|6Vq{zxtd)=I*kD4R@w}%hDoKMvFi-SZlsiUG?9jvL3ssrf@dYLUzQ7#YG)<>e4)=^Qe57yX6qL|k~ zQClFawU0!x(Ta+4r=>EWtpg>BomN!T9K|INHpUpTPdvBk3=($GW5;b{YW(9C}ZEO z;g3W!jxzYoTK-5h<0zxwcG7PW%{a>Nx1IQ#L^F;u{%t4!Cee(e41n7Sz)3XYC?nu@ z7UWTFxQwF=f!m3|Ni^dqW8ii&a1zZp${@I%5S&Cajxq{vCj}?bjH3*L+lj$RG~+1a z;H(jlL^F;u5YAcwNi^dqBjKzWkVG?%G8E3*0ZBCDC}ZKQA&^QVW*lWOoV5g!XvR@S z!&y@xiGI*g?Q!OJuivE4GS)*#W#SP;&=3;-vo1mswLK!~x!4}j`UpuBVFZmd;Xmsn zq>}cCBS6Ot$*2@*~C&-w{T6rlu(Cj4g|g(Qktg6fDS{AWFd zB#K~yL=*nAu0j$;G(n;t^q+zWABYZEUm=N_qlnQ3C%=p-O{{3vTSy}{M-ilp zj#M9vCR5Ye3u&YoM;S_I4TdC|ag?!i)?!Ga8AlmRXHAAAnsJoTbk=4_Wpp!+GMvsD z4M{ZPDC6m@)sRFpjxwOmnhi-bvql+FXYGb0nsJmNb=Gi5qM0?ym^y1YB+-nc463uH zLlVt6%BVVPJ0#JJqYSIF#zPX#ILf#>YdxeY(iuk?SZB?LB${!Qk#*L7NTL}>8Cquz zh$NbEl(BWzf=HqnM;TmaO^76#ag@<@)`m!;8AlmjXN`y?nsJozb=HbVq8UdSU}w#U zB${!Q5q8#&NJZ2$jxxl~8WKq~<0xb7tR;~|GmbLI&YBWQG~+0v?5r)3L^F;u%+4AU zNi^dq6=|dyM;ULoled#-#!;*vq{rtu%9<5LA778xoTIE= zkw%(v6#EtFo6N|BH7sgJ+6J74UygscI{o_guc!Ohr|J1ur_Wy8yt%)9d-`bj<*fhZ z+vmUd=-bb~`b5;w@QdiR`eeC`jKl~u$Me?T{;4~4DeBj}yhDazq=?T)P*ESpMiDU> zDdO7^RMc}diU`0+5g(4AqMoZ!MD#^)J-!-2MLk!eh|r4^@yQ4(>bV+4d@rPk6*#8I z>_rA$q*z4+dAz;5d3p6LsHo>^#)ufE6!E19D(bl!MSLcth=n((s6V?XGHX$a3C}Rp z!s^OWOn8QI78X~QV!|^Fvaq(Y6ce6dgoUM*l{}L048tp|tSrTZXBb;yVPz>MJj1{W z>ncmJPQgykFsj0`%2G^th9MPJRhDAHGmNJ&Ls5ze&oG$6n#xj4c!rS_mQhH(>SBuX*i83s+* zw^@n_&oE-bY(yz0Ji~AaD=AAc;TgtCn29LGgl8BiVIHCs6P{s|ge{wu{Fm?yLnO>W zlw!g&jE^t_QHlxAFgU{eLn$Ua!^jA;52cv!48tPKJ(Oa?GmMEa^H7Qj&oCguyhAA_ zJi}-Rvks-0@C-vC%sG@|!ZVD6Fym0ktqIRC2*P|rDJDF_2ngdJQcQS;;Sc5-N-^OX z#y%MNkYd6!416%`A;pAe*rVCf3?-Q`jm10|@{nZ0HC{EDVSu^6N3-^^da}zw&TBopqjJQ1des47Ro zJ(eZHY(hyUc5Rj;!el~8Cfs8gBJ9yD$%K0>KZHG+C7IZ`S$4>1?qPCB3igQ-7u22&5$OMO-c9qy9?$ zk_`E%_P33)`#04z(34%hH7fmWlHI?lB(a}R^0G7f}z6-S}#uAN5yCjFRrL*pK=vB_!z{3;w9T zQokgFKdSi6ciA8P(HD>IvG9-jDU^7IV(noZ zNM*iFGT|Nuf>h<(BoppoBuGWRO)}vgMuJr1+awe2VI)W;zD+XW9!7#h#h7HmJ&Xhi zi=kwHBxpXPE|*1D^}S6p;T}eURNmVp6YgOoNY%YfGT|OZf>hkwBoppoBuKTrO)}vg zMuJq@+awe2VI)YEy-hOV9!7#x*xMu%?qSm`)%7;XgnJkXQdw_G_D6!|GxXB9$0|&z zlT!b3#tKs^>TRP;xQCG-)$}&WgnJkXQb})$%K1YIYb4$O)}vgMuJq& z+awe2VI)Z9yiGFU9!7#x&D$gs?qMWI#k?um9|@Yz_)Fs+MuK+rPwICMBS9+VZKF)M zhmjyv@;1qYdl(5)A#amRxQCG-)$umTgnL*eL}k29GT|Q92vHSplT5gW6+%?R+awe2 zVSNzQ@HWYWdsrPrCA=xg;vjWKJ#|SmpFx<$JuD5fU$ZnwP*P9UN}79E7$hdix*!77 z?7GBSu@qGCzg68^{+jw0;00rHp>3B=M2TPqcr!hs7L6*&s0n+ zY3^Z3kD#QUtd%tPu%Jg!Qh(M+GKplr?oT3_&tOa|Y3}LIB9WxN3$3KNr$3EElKL*R zlIEWNJQ7LjyUyKbb_5bPtPnXq5eH&zX#AM#*#%N%pTjXELUhH23u9ljyKYZnT%;i zY3}LIDA6eC9;TG+*ZnCalB9c>QzFU!wdYL6v=44;Pk&O$d?sUBNn3mRvq~hXCu=3m zJ^g7VlB9c>SE6^BaF6AcFtJ3E3HMlH2{TJ1*}rp}EwhBFC6Y|I$5Km}TO!H+o!gm= zX?}4gm+aU5$tC*5=^nBMl1#XVtieXsK$3~IhpfRy)$wt;dk_q>aHQ2}+s9bsf zZK=Wr_ym(RkYvI=%rn`@8b~tX9tvqE8tBky zk_q>aHPE)#Bopo-YoNV=NhaJw)<7RflT5gWtbsKyQOl8pd&nAC+Ya zHL%7bl1#XVtbw&1kz~R>WDTt8h<05G_tbbu;~rxTtmR0|J!B26;fO}r?;h(QVhuzj z+3z0fA7br8B-!sC>mFjwLnPVn9_t-qtwSW)?;h(MVvR#2+3z0f8)9ukB-!sC>l$KB zLnPVn9_txmEkks`=y#8G46%kGlI-8PS-%i#7b3}od&nACvk*xp+{0cW)+$7j3HOjS zutp)0Ot`03;b=Z?#u`|gkkH3%Vd+Y15~5Ki+(XvDT7*b4;T{&Rv<4xPOt^=vfwc$G zSvuh!vIf>1M3M>juzsbr29adKJuF~pjX@-ta1U7nYYQUDgnP&uSW^&5Cfq~Tz*>Sx zGO_lMHL!*tl1#XVtbw%ykz~R>WDTqth$Iv4VI50r1){J~!aZaStPzML6Ye2vU~NDo znQ#wT18V{z$%K2z8dwVuNhaLGx(3z&M3M>jkTtOOACgSChpd4$|Bz(DJ!B26^@k)A z?jdVnjXxxra1U7nYx|)HX~I2Z4Xo*hBopo-YhW!uB$;pzSp#eMA<2Y$$QoF?4@oB6 zL)O5WeMmCl9O+zV_mDNPMjw()xQDEPwfT@_!aZaStjUKY6Ye2vU@bm$8IW)f zSp#eEA<2Y$Sl7VXdq^_j9Kcp*)?j5_gJN|J#sq7yk~Jt+*I-Pr1}j;EvY2}ktiejwpjcglF~J(F zWDSb324kYG!AjPkuurC#-h_L|8WgK*FeX@om8?Nwr%a8qKVrR-H7HisU`((ED_MhL zbq&S@Yp{|vC~TG~KDs|@u#z<>?3O9X{;0u9)}XLmrX>5L1}j;EVs#D11Z%L8H7His zU`((ED_MhLbq&S@Yp{|vC|1{COt1zkS%YGA4aNj(u#z<>R@Y!mum&qxgJN|J#sq7y zk~Jt+*I-Pr1}j;EVs#D11Z%L8H7HisU`((ED_MiW9tz5V=#ROrWDSbdH5e1D!AjOZ zT{0NPORxqjSp#*+FvV1t#gfi&r#DM1^oqz$A=15F9sU?pxK zO-2r;1aGjCH;|@TC;=R-1P-KW9!d}gD~SVXnu!v~!Aj&nn&zSebFh**kfzxv0UfM_ z4y0*5N>B$YsRNa3F&`zcgO%8UG|fi|?qDT%AWid80z6m=9!S%ClpqgQk_XZ>A0^O( zmFR&q%}0qk2P@eFX_}7`g$`E22hubjB`O`Pqz|NNK1!52ScxA<(|pw5VRK%|AE-u= z`6yBBU?qScP4iKLKu{mTHrg&t^HBmpP$NRqG#@1x1a%@bP4iI#LQpG0(=;C?C6&u%Eflt2;GkkB;EM+p{T zC5xZ}V&^5U(lj3> zh=i3yf;7!X2_#`9k|0g=N6q=^_D8VMEL!oJ!j}mZ#S`?b5 z`6xjrs7E0+4NsU7c!HV~nx^?E!6&Fop=p|r5`co*6q=^3M+rhfeF{y}e3U>G)Tq!j z%|{7FL7fUs(|nYG6x6EFG|fi|N==BLTVbaFeQ)$H7+zw^HG9X*vKrXD6sh`0WGL? zp^ejgl%N*WyU;YvM+s~}%?nM_e3al8)VDTEkeUWBObK{FEeuW5e3YOUHqr~Kgl#@bluFo$FG$mTl;9WC#n7JJe3Sqf z)W*;>%|{7>L46EO(|nXb7}UtnG|fi|hC!VSP1AgoD43vDhNfvgN>B{yWk^lK7^XzY z1T`}>P4iKrX2M2}LFM1gM~R{dYG-KUG#@2MhK(eH#z`NY+aGqORBuEXq)8v0`yX~| znvV=-m=lE)Ho^=VCw(+0Dkp5D8Kg-com(LGK09#+Y0^jM9*EtV^pP%i!AP8&Aa-lg zN4n@TO?|VwH5q46(BCxm&FYLp?PWng( zPSeykyI0eA25r7gQ**6blk1T-4W_BN)~(6)NJcWvelBP;o`g53OVm&gRK@B=gGqD~S z&!7$+rkPlejAu}b4r(TN2DLlH{!=|VOf#__8PA|59j5uA_2~cn+s8j&y}J4F_UhTy z@XPTJSEpa!{`GYK`ZPWN>h#%*n>Y8jZ%-c$znt~IeEa+tAAS4zSDy@;0>8NW`0CBu zyC3iF@BVW8=c{MG|M}|X{{HRVAAh>9|M>IO7hit;+t2>#>e*y>F}#V2*i3~y7I2`a^eXLy&wn-nP~Jj0t5-lIq{;ThheFb!0f7YWbs7KK@$ zQcQS;cPLB(m14p(yg^|Os1y^P;r$6yK&6=Q3~x`E0V>6WXLxtQn-eJ}Jj0t4=6^~t z;ThhW@YY0%3D5A>gxQ}`On8QOCcH7x9l3~x(#S0crP zXLwh_n-VD|Jj0t3-jhf%;hDe5`)tD#l1!M!(>@WEl4Qa)p7n{Klq3_j@uW}0q$HW} zjpuwKB&8eZgmLVOgf}FTOgP6gKFvD)37^`*>&Y%9$LxMYqfB_m^F0yPm1M#^p6-dL zt|Sxg@!JsubtRc_k0pEZZbXs^_gJncuSO)9aF3;W@@7Pm3HMm0Coe|CS|r?KiJrU{ zkz~R>mgmW95lJQ%9={gBt%xKO?(tg@b5DPgr_R)Rvc}`Q6VWIW?y)-&UWrID;U2pZ z;f;tS6YjAa5nhN$GT|P(5aE4@Bopqj`w(7-h$>3B$F4(o8zRYsd+auZmm!i&xW|$^ zSz}s~3HMlTCsR8mnOJ))wUe2hlKhZ++FPJs|BwHz@Z0H|H#gtu>gW2?Y1~eCucFsI zi~bJ|woV-?@s62XNAy%ndP&No%~!!%bx0FaIjAX)YP-JzY#ZH(oFcsHeM2GV-xzvgpX|JW$itrSs(ZPcPsep z<|FRC^q)xh$o5{=;6s`TAKB*1I($eI>s9R8ZTDp@KBSrOk!`=M$A>f%KC=CnHTjTc z!betG!@7J(GvOmEtzm6Gq?z!MmDaF6AJRqD9eA6aP)YxW_{gpaJWhIRXpX2M5STEp6XNHgIhE3IMuKBSrOk(Ji4 zh9A;Q_{d6YSjP`(CVXV2HLT@_G!s6u(i+zDLrY1*M^;+Hntn(#;Ug=pVO>9@+3zFk z`k^+s2&PH1-$&N=Lz;GeVrh-gx@mnsq={g(#t9#tPrOeaJgoDF8ulU_Em0ULDr!4B zLY)$YlcJ(}ymq@tu2Z70QdCrr2T@$vxa_5`~e1?j#5* zQF9Ve(5R?ci8QE2THoUPutQYTyhI>W$7XmbDr#mT6Dm=dDJrVRYgZ9sp%TSTFDObb zR6ms2iDYP0)ciy^R3n9-qM~Lf@}Uxip`xPZC?cW~%{YpT=wSUqB${y)F;R({qX>#d zAKx5BR#YR+IEt{SMrt=t#6_bcHAj&cRU|6oC?ca8sjW|hMuQ_IH7Zea6uHr;s5y%0 zs2)G#D6*p(sU4q4k48sojv_#+k!Bo4f^@JRA`;CwiV&$p%~8ZiqmOTnB1x)|W*kM7 zR3oLMtdmInFFbwBB}^(!o}MP+q(M#nS-V29{DwliSfOH?1WGkd+G!$E8q_p55h~R< zGj1YPs)5o?6S>mhKw+lQ`iW?uFjG)d4|n;Iq{;oB^%DtdA`&4@TFLr}1U2C#X)+LD z{X`ng_9FYp`TfoBe)HuQf(P)6967%gsF1my{7@b_zvtP5Z<%scvDc2hM@E4d1Ck=X zWI;uI$ru2VBK8D9MSRB?{*j{gpqKMyP!V4-27jbjKU?oltU*N_SQ+|JMkJ1_K}GDX z8TgSRcGf{fJ=bN8Vc18C*apND8TMh&M~YRX^F1CpzgN!~>(P5mc!r@K2708J@XV3( zt6v63QDto=Jj2)yBRf(|c;?9Yy?S=!{AzX{Iltlk_$noL?Q; ztupG7^ZS?w5j!v(Ilt$)kCjAKQYm7av3Ggo{64(PBj@+KTK!PDm5G?Zk@NdFi5N>e za(*AO+hSiL%RD)9ejg3VtdrQgw5*f=!a2YDa(`NW{PFaw+n3?2Mn$gl8ZSZ2fjwW9 zZH$O@T~(jDbd@9`*29FWH%TJ=7L-KDdSJ&_Nh1Chltj#WV8d5QB4{0yM9_MeaDlDX z8i-m4B@wkA*zQ%5SfYZG2wM;A_9{ul;9`=NlEP-MlB`yJAGi)m^7fj&UL{#odL{K_ z?NqlViuowbDBG*n$Bg=qK7ak{pYOi^>Fv!QU*5*cC|g@`W^=prGn7^eU=}RarU>WSYd8G zm~K>iJ!MIOCExq_+UA$f%ouqr@J!5h3@Yl+E)&>lO-#&n3@XABR%&8mrsF~J=!gy< zbok)K>*p^%tkHVG@$m6qFF1bnsKW>KnyJGFQB0{99M^m?$gRT%;n{;VUWX6rw}%NO zu``uka9n@{K;2$&JdT<&b%co{LN0Jt5Sx!3KIrhlhbx<2a6B3dJABaLgUhzP7aVW7 zpX&w3KVI_M%?>MI#$vZs!0hlrhYyZ7JF!XB3yyyTF)3wsKx z-W*Ez>3$9nT<|>#AiA&`Jq7iA*8tKd_#Q#}u*8^7-4k)9x1H5*VR5G40!7bFd)ryv zeOcNzD~QE>-EV<(XJc`ORl|bs5pkxcpz7P!Q&7XJ=6(y*Z-M$Pkn%Mw$`OZa!wm|;DeQ%- zXU6GuP?1(KuaNTzD#9y<`AqC{8&rf@*yUDFt$B4>(FYab7WTMRE^QTQw2Lk8%r7i3 z5*#D^GMHi5-!`Ub{cX)L>~0%Wgk#v-R__r@yPzU0!_Kx+L~IHw!ZYk^E5*-wrboMv z*{(g>^=KDbb+N2gk9Nwr>e24%QS2*i<+OUV)9m@56z!&O%3rQd-{1avx_fi_Q1s!a zH}79RzkPoGhu=QGd3$&J?)1fnfA#e7m!~h5ub$jI`@8qb$z`~4V6+@m&nQz zO)N`PF_(w8e=JL6Rf#56B?>BHO>0GoCKe?MDq>A*HHjwHBnm2GO=~5ICYB@$Dq;(0 z6^SNRBnm2GO=|^-CKe=$DY77u)gzi%k0_{!HLaB+npln~sHi`?>?Y8stE^&=V^@z34*K11S2uTe?_T`%{lA$#mHs-+ z9`j_6W8wGMm;tHq!s zBGX{Y#hJ^+pd@TI*m`m1dNC-8_2OU)#+eJopd=QIgRK~6t{8)oSTPP}wV6xCkYwSK zaj-Sx%r#?BQh#=wM7(dCxoA8{_9dRSDW4D0eTk=qu5G*e5-+?o=}Wvv7JDYfp5Rg$ zvByHs#LyE|MCh@|Gcoc66%lzX@JtLmK}7@}i#rqJPDrsIRrDkGGwRrnD*92yhq4r* z@5b7XDz17QtG%6i98-!|$TQou{_L_Lo9%cnbX3ug-2cs?Y2T0a{n)u=X}>y-eu>r{ zhk<=R*5g>i+ONm4deMs$`i?-IcTbf>yvO=OYofK_jHI6{p5J3T&e8W{sy@);SdU}> zKgY3eU!MN(`tIiMx2K<9Jik3Xd8yA|G%s^m7aTc{*Vo|Vc1tTfXGuH+=Smb`REgrQ zMxynq@BS+t6~)1`L_x_(w0`YdMVVhHQ6x-B6rfyiq^u<&QCxdU6d%{9D0c1=#ok?_ zT2Hq>KDdGLn%RaD)fGp(DApws1v(&6O}TbaY!@U7)>NXJa_yqH!I3C%Q;BNIwTqgg zn0dHc=3(^LH%ATTC?+39Ma@ynKh#Jwj$#6$-l;i?DTu+5)}CsYV=IZ8qnL#l6*WgO z5mAqyanxpxVlJXYGmhHKQEW9U(Tt-ua}>*sOElvsHaj1$*>F~(8AomADE6G)z31$K zBl#>tv8=Vx+Hp#;?W{yIF^W~k_4pQ}tn+Maq}F=&n$2f5(oBr1wKnni<|ykw8yu-Q ziY;h0(u|{+J2YN1dq|=gM{(~gQHxPbAPRm^cnmC2i&4xWii%o{Vj7ViKjWxkj$$U! zZka^Uk(#5pla^@4QN>~u^NA#yiBU`_(hp@ZiYZ0G$KTCS%qr4IGpjz{acZQt>LZXH z9jV1A;-VU9#!=)&$7`k+Ni-9qct|W!a}=?i=;NECNbYE)8At8rD8f6t!8_5Bnxn|? zNHpW9-5f=PN1_Qw8N;I=${c0zXegX)*XAhZ9BHHpN7>1-Mrw}Y9cb)_+OEw}3$pbz z(uAY7Yg_d#7NhFcy>)kD{Vm4p#T-?)?(L%HsKxeCOTtmxwK;0BlZm=@Zy%{Simfho zYjqL*_03U>t@>)wgyxafdQQg$+G37c6RWF#~8AsKF7l@jpYSp0j$2Ui@1%~En#!>a)1tT>_)vbH`NX=2JolLMD zdeBkz-~}T!N7dqx%_C(qjPZIkN7b!+yQn#8HAmI0d%LI}507t-s$2JVQF9dgV(iuz zBlttrgO}q-*&0Kl8AsKF7l@jp*dskUQghU1F{*Ce+ux}^2AH!>g9>(FLRJ(`}CzNKwNA(N^n&zWD;iGze4Ndb= zy#Q@~pXQ^TK04ojHfx%XcKYai{n@N(KH3?N&bObfn)M6??~^_{Uw$@gnvZt+=zRCt ztZ6>l>7(=2XR{`Kq-K=Z%WUjiQ$HvVohvTa^$g|kKId!3qw~dQ^Em0F`IBErvayRzP?J8INt;VE5s&H_3VtK=5n=P#ILVr;NSpbHta(tA zKAMS|>)8|Wh&BE-PV*5-^WZr3XUF$R&|Kq8#G`tK0!{M~IrHE+%}2z{HO@pls%Iz| zr}>DKd2pQOBSPk7V|$yRrum4Bxik|#vXcKZ5p!wko89`YBVj(wB+R8*AGhgzez_)K zE=`L^1k7Xa(>fT= zT;oiv>xherl<*FNMJ|a{e9H;q+Ou5FH@DY)6jnjNYq&zrI^AU-1jWgjR0_7T~ z`G~D4g5xwFktZ+e^W5$u;^Z2qt?P)B$HqyTT$<)1(&Rx+Th|%Su(k6H%eCx^gE5s9_jc3>r zJi}l-!)!dmmf#r%LgOmmZazxz3`0FbInGbx8MXw^Fc{A;8_%#Mc!r^#pKO{2-F%eb8HRd>0!{N#f@c`&8Ol-9c!n*(GYrNv z%*Hcp37%mvo?$kgVN37~Lp?*mv)g%Hf@c_vXP60!mo33F4D}2J<1`;7c!t4vhS_+A zEx|Jk#xu;uGi(W-VW?*)cy{wqf@c_vXP7thQG#a>G|q7v&#)zU20^)|Y3sTK&mid0 zG%X$_cm@GrrfEJ(@C<@sOw-nN37$bStQaY^tDgYgWD@eHNz#hb@T9|^RyacZtLYtlyo7)`VN+Qfz|V*$#_%}Ji}l-!@}Zur6hQU!FUE;qVjzvc!q(c^YrXo*Odg%Fc{CE z!%G`y!bkNClHeIe;~5s?8A^g@7>#FGjAtkbo?$eeVKJVe zBzT6=c!tGz1{I@eK3^J*XIPA9P+^XQruoQt1{EntXqu0VXHdd+LeqR?JcE*}6Po5D z;~A82n9#Iy2ICn@f@c_wXHfeKo-ZYMhS7M2#drq6?(NTRJcCN0+c@iIxGisDG@fCx z`V4|}6Pgx}tUg0Y@C>8z42$s$CBZX{#xpF&Gn53+FdEOW7|$S3An`uUM^>MqBzT6= zc!tGzhLYeJM&lV4tIwc=#l*Ao{%A3tp(J>Q(RhZ%c!rYT8Ajt77OT%t5lHeIe;~5sK&rlLP!)QFivfKVB!844;Gc3F9j}kn?XgtGW^%?fM7jIqL)H9Uh z?`}N9p5PhAdWHf`o_p^Jo?$eeVKJUzPw)(5Jww4bdCssWc!sf_p+J*9+7mp(SkF)n znyc{)dxB>ejb~VmXV?=w!&uKyFi!etPt<1^>lq3(>7zYSpJ6nfVKts%Pw)(*@eHf+ z410oS7>#FGjc3>sJi}-_!)iRkp5Pfq;~7@t8TJIvFdEOW8qcsN>NAYSGpxol> zG@fBKo?%b$45RT3tJP=N6FkFcJi}@{!=B(7M&lV)tIx0}c!tqG@fBK zo?%b$45RT3tMLqbf@c_wXIPDA*b_X%XgtGeJj0&g8Ajt7R^u7=1kW%U&#)TLuqSwi z(RhZ{c!oW}GmOSFtj06!37%mzo?$hfVNdW3qwx%@@eFGF*}hgZo?$hfL5&aFHH~Lj zjb~8nw}d9wb*u3VYJQc_WP!gIv_g;->P_v4JrmgFYXHZ{- zgr=?QjAz&rJi}-_!)iRkp5Pfq;~7@t8TQZe49DgVKfihQ_uISEFSj?(PtR`Np8oOd z-R-}e{%N@WY8p?!p02;%mS`7~&2Nh`*oZ)JW39r~%-^{|5esGL1 z3)lG?W5O-A&NsVol^+}xoxZ>Q^>p{5Jv7CpXXjuK)4$yC+|%_s8^QJRXt?w@&`EWoa6Ur5o z6yfrqA|fK!Pf|ok3@XCqTs=tSr+xSaf_6yfrqA|fN{PbnrmL;92K zrxX*OA^S=4Q;G@Cko+X~sgiy51KBzs;Tck&QcQS;)F+uwDb}C2ZH(3jnZ&0Q+dX4V zkXgS>n_@pGR159T8?8G0N$zsDZO9);E{|GUJoe){Yl=aic zM~6N8fAC!;dC*TE`|0CVaON0iU}yFH^fCG#`|0D=qtxkRk9IxU-JfUlX!n_oJn=fa zH|WtW`jzg{?&=X~I^7ZBL^0;T9_^CR?!z70$Gf)a@srcxc5T+hn{L<6cWSCbKE&_T z&fN|#HxA5e*Xb$l2kLR}gLi7@UWW%oyE$*qYM;)X4iAcUbKaiQE=Am_u|mI|8s{p( zr^cNc^VzqlJ)d1;#QgxX*`+D=Ja#GK zejuo*=Q_+Di-7G}>}p)D|L{eTIqVu^!ZWPN&kS}c;!Z92)VPOc{<;)#rxsL%XPCV% z#e`>Aji0&eYA=O5wcr@x8D_3aG2t0zt}}04iV4p!Z=G4|QmhZ!=ox0MGiP0j3D4BX zewg9rnf8ozy(m4`MUnaH8e_sU%vWc&x)c+hVYWJR)uov53~TQ*Q(cM)&oEP+dFtEL zo~N!~2A*M-x)c+hVby)+s7o>78Rn=nLtTmq&oD!s`RP(jc!v4u%ubgg?!01OGiIkV zH(iPe&oDQgndwqYc!rtj%uAPI!ZXZEXI8ot6P{sKI&;$19xxGSn3K+obSWl0!;Ez1 zqf0U28Rnxi8(oSC&oCREx#&_%c!s&?tgJ7^glCwE&OCG}COpGDbY`JTG2t0zp)&_v ziV4p!2b~${QcQS;8R*PE-_$q0eU-xeb7r4QG2t0zpR<;}6ce6d?m08hrI_#xGtXH^ zUy2FOFz=jI^re{a4D(FXxDZJ7%uJJ5=(0=`=A3Jk3D;Q8IZNnEGGQA_IcEiZNhW+_ z8RtwmSC7|(aV+7S`R0;LIES~s1JlhVnXnGCPSmlGlZbgIu}Ngv=1ex%C==%4X}J0o z+9(t5v0QVenroDakYlOl%ruu|!abIK!bEdPCfs93;+B7+{_yQF!tzg;X1=LCd_q!B zcG-BUQz3tGW}pP;rJn34NoqpP;oC=P$KuQ}*Mlb_kL8$K5{g>GCq}6!J3hF%hgm4G zcWD{sb`d-?4J9b4Cp(Oi`Q>_-3HMljIn&D}nQ)J#movLuk_q=%b~%&FH#LP%{Ni*E zbIT=}h&`5D&eU>ACfsAG<;*OXWWqgGDW8eul1#YA3gt7eT#}!QJx5Z#-va&N&wu#w zhpR{I)T}$3ga!L8klrJMSHA^%sq6=RCm+7&?6*KykNPc8MUDF{P}DR17O2h_>_GZ0 zQ22}6Z-K5J^;@9opneM!{o?jppsPpy7N~lr-vUKF({F*q`u1C(4~c~R7Uhdo zfucL)3N>92i+&5#Z-H7iiTxI+-vWL3;`Usi=oh!=0_pC{Zch6xP;~b6TcCam^x=!! zZ-Jto>9;`r7U;gfR=)*mS>X3upnePVyQ>!$_w-w!hI8zG3)F9c;GTX9)Zm`~eQtqz z{nPsZ(|Zlp+`b2MR#xVHTj~$9zGH%1=`rWK_Zo~=(q_V{RZL{IckpLXF5%^V#*)1! zCVK}JapPmT-o4kL0J+$Ew8fn{hI!sWMdjcgers#b$u#evBGbH?1XvSdK>K*xQw-u&gH*4tn9H>cJ|n+>9-GkL8Zyu|CL>~q>1$9kmgjY z>0q3g71Biha!`}AVr8c-X(E9+sL6S;ve%Y0tIR!p5!A%Y7*& zrHKjvK~4SH@i$`ru{4o?9Mt4DRsEiinPJjI4S=Ago(D2N32I18)vPqgZGK=tHzn|QC(<36JJ~!`ub=OeGw%|w^ltRA;tQ4NB5x)=PC} zFV&zVU1rTxXEswkNFGhrx7dA)eg7ejEp_`A`?!cv8+rt@*gLe6YOF^%v7%Z~Q3gLm z6f6ieMl1+}ii}a#l%Q|1qZ{H{IR5a<*qIb-sl|SozQsxi4Yv}Rca~!vMiyi(D+{vLJ;Otb%Xue+Ax$pnSC(WAYI3ciV}j!sOXIAI zf%~t1P?L)d9TS))zJftbU#sIgsBvOz9Mt4@aAILrY2r&5)Z~|NVr5ooVrv}KwBR?9K~Ao63sY@t0O%=9cAU} zgCphgNTPIt)8KbO{eRQN;^;s=@z0=I9k0&pq)iIH1#!)P1FHv(8k6)sXZ;m45 zppj-A#gg_KsX2-qYjmXMC|0%Kt*U)g)EvdS_7crFif1u;d~*~}V}c{)ag0RGQDh#X zqKr`ktJ~}GGcl^xaXp5U!D1B2hv-NxMiG9{NHdPAJ^hX&WsQ4@YRWaQq*>&C99ZRE zq8UfA%)La-QDj@A@6;T{O82`}x{r#Qqgd-+q8UfA*u5U#9K~w)!I2Vim8dz2_3oph z<|tOY*W+g##gg|LsX2-@@1r9%NAVI{Bh5I9x7g#rYix;T990iqjyB~*wnQ_Iss}F+ zHAnF(JNiz|QM}CF?J_$mYL4P{wnQ_Iss}H4d~*~pw1Xq%jkbP$a}=+%qoU?0UTW*{ zGmfeUFL-=&6tA_TBQ;0OIBC{MGmfeUFUOJ2w(6@L=9*(vJ$QjA&-&)tWUgJ*95tJx z>ejto)EqVQtZ%Mc_jXZp6p6-tCeaxE_03U48YP-I>nmg$$6+={k!g&LwA6za{Q9>I!{^< zaCM`F&qGX*r!4q1NKoFnd>Mm+_%h(LAVCD$pdh{q2(l8yCm|?^FM`#F?MzEJfx=n@ zBC6^pwEh^4vwKBQE;q1x;yyH{$ZaS$ zp&BDx9#lkJa?PpLCk&$~(jS(&nD#A0|cuFzh8SXo0>^h~G z@Jzk!zr06oIi-j#XYi@v8SXdLAQ6!-n%rhe zvE4HpcbQC_lVZDPwn{!8ersDza)Wtz>K@0my8G?w=1ys!e|>*f3z+?O^}~-p{ps63 zs)*Oh)72iwYEjW1$HYE|)>S-6?Q!fpdwLv;&K|7&dK{~>Cltr}>0>{AykFrR_U!*b zobRWP$6S(r`dGV>#byq1F2Y=TkJw`c6|u)6$)yu1?6HE1*kkq6#~Mlg)0{qjI92?3 z`Zzs)aypzh_C`JTaiDI}A3O=&dZV7+sHZpT(QQRTHO$_q=jzdF7uNNj>T=2$`}Wkx zemTKg?Z&#^Q#C8%WPY{#w+i?+E8>)KwNu7Q_ckl)xh_w=fePEEiuN`u;$(gUz#>JQ z%m;rN+-7ZdGQZ(OBdCaz`3*3b#)ws8P!X%f&F-u#&fEMRv1;6q^0`d~C-cEE;zVOJ z&-6w;(Y6u2QBQBw^Rd-RBF->HnhDaIB}m77&HQL)M@umgXP6w#)MzOt;tVsRnHMd^ zM4Vw-G?SvGn20m=X8RHgnGr3;M4VwlG}ED_n20m=X8SNk#u>|n4$dCL874w+mIxhG zM4Vw3v=kGbVG=Y`pru%c)wt8FH`|Bz$hDc}KgXV$>Ca4l))*6>sW;n~FJl!S9E z-C2?e>yX2>WM@g%fi-%Exz3jAEXhQ`skLB_KM!{{mgpRNm&|jvG-r)6;T~o=TavRR z6Yi;nU=I(@6lX~$f{q=D+nM;xGx6ZNqX<<8`CgOd8Q!@M*w*HW5;k~kO`n9!^TPq>Hq%$Ck9 z$%K2D&1}icl1#*&dggI_mlk`b#Nj|a^f*fLbifjsgFg@5!!+h?W*T!$l3C1_#4O3G z(inT{xySLrZQ;fg=HMvl9wsnrl%HF<9ofB61p1GUKho#*GU)ej-rb(Qd-Lk;%NIAV z?@mvDxxIaPnwD=*U);Rx-UcP<9+nZ=3NNCAl5~&7+roGol%#ts z-WDdp1SRPni?@aGHYiE=uzZN#CE{&RlI~&g5J@851|{`p2ludai25TS-UcP<9u^Lf zq~=)bmxy&k7K^uq@isO}#@mHOLo`an+n^-f!;&GA#9l8bN%vU1EsVE8NxH|9vI>*3 zf|7KPWn~p+Wd$Ya9>duS)3Sn+bdTj_73O6HCG}?q_gG?9VPaNLlJ2q0tU{taD9PAk zsab`oSushbW-XSRRhXL^|pd{VHLLgfq-yW2tdsqfUlA2?UOM{VBKo&MPlVlxO+rDS4 z_Ya48$=+s?Y+t#J2J5l4nIzj+ZmMg}QQE$Toy~$j58cDYW}8aFC*CF9!@g#c)EsO5 zdDz!%VOujvwy)e&g^}-)Cnbel&0_D8UCoxoP7T=9EGS9$tOSrsJmyA6t38Yf1 zOEgQ;JuC0HN-ZzZEXmljl0ho9PG_^Ep6uZ9)!b9}*3FW1&&qSgQY%a}OVT}t?iHeY zu}MU9Z!vbSklhPP(me+66~cQ#NyZ+d_X_E~pd{U6_+BBt7nG!XjNdEd_kxmij{$sz z0AEm&?lFR|kl+hS>dy}DF@&!W;R{OAJ;v}AGJHWvy2l{CLWnOWS6>B&~u^d$J;bPrpeNHVc+PWKqpR|xe5CFvfc z`U?M5<+iiINpO^OkAZzV!M>Oz!M?@FzMW)WP?9S* zwl>kbOvE0deT%VuJK4VAC=q+sYwmk?vVB2GxMyWk6FqoUX^cH&`_$eKY05iWngmA) z_o%y{NhV?s**-P*qa@kB;3(mqmCa1Hoy|;wl5me&``IWHv4?D*I{TSqV&z8GK#l!O zGT|Pw2I}i)l8M+uwoh&SOfnIB$o8$q8te(yU?khO8f&m8Sc8#l-)gMEo?s0|R@+>S z?b{Qq!N_u(tFZ=qf;AY~w`4WeU{A0HBUyvhSc5&m8jP&Cxf*M*Cs>1#B{x@N4fX_U zFtX<6YOKMYU=2ogD_M;-*b}V5NVab^)?iPt1|!+N)mVc)!5WNY`&MHO_5^D%lI>fK zHP{oZ!ARC%HP&EHum&SpgVk7rJ;54`WcyZQ4fX_UFtR(zYOKMYU=2pre_f3=*b}V5 z$O5pdu?BmBH5gerZ#C9H%}v`EgX~JO8f&1IkqJpHoi3Y{)mQ`d%u7gekIk?AIgL7l`W=XooSc5&m8mLb?M``<> z1ZyynHCT-`*b}UQx}25OQ{N!#}%Sc8c@M^3D)4;dE_W*XKo4B z;M{uTC~0SI3D#h$=OIT)b5DXbnCf}RQPNJV6Rg3x{@+p3+>>Ap&IJIEl6K~nU=7aw zM~;%_o&;-fZa{LBH1{M}gL4OxgQT$rdxAAM7Xds}q`Bv_tidtmthYVs<>EgS$;WroHoU!Dyh_Q|4f;blk<;4C#a}(Loo;V? z5}!R-s2fq=+n(?}9^=^0zuf%u-PP}|-oAVB>c!oQ|5ht&{nyX61ewpd3761047`k2 zf&~tx^rJlJd}-oPYEUl2@jg+SxK9jf;x=BISlmccOMuJiOi&Xri!`yik)|R+vnI}^ zq>1H?H0#jrv4P+?vAmHc);G#n!MScw6H!i@*d9m|2fIN{{n=qIDWieEJL~PlG7aQneY*>#^aGVy8ctfvoCgKrq=v6Am;t{XtgX6S##5;P8 zGZBw?N3U^OJmMvNaGVy8cuTMFpNL1irPnwu9`Tw!I8Oc9F&^=rUgNAAnZ|Dj@98y8 z^ARuVW8>sSy)-Qz@uohgY4M0x^?LS1JmOWoYB^av;$3}koEDFGS+8*>;t?ov|Q(>j;TN4&3BLTPD0n|OUMQMf58YIfoUzLL>lr>Lm;iC6d%g`c9LW+)zSNECr7CVI|lI8J_E z<4Y7frKqSa@mMrKqFCZZMa@wx8z50QD)c=$r#2j)o_G1ugrS0(<|kg}OA~$yYMPyR zn=eh+DX3{~;&r|>t4v#LI;S__ecE1$_xZtbnwNN?uhI_iQczQWhH+YK;*EYxvrc1Z zT5RH#eo)hl#5;XGd&WpCATW%qARti~Dd^66qH=tC-s?*gPKt_}l~_eUqOej_)V#zx z0uqInqM~LdRuYhC{k`wa6cx45#99KXK#~Ye=Y$9RP_|{_4S#f`<|oz@&`2|(i3J4) zgkhlE7k=BzHJiaaVc+Vddwa~<>0($(6qw3kpaiqNKmuSXO^>78Eb^yWK{^;YI zqgY!&Bh5If9X*y%~xH2ZEaBr()|pRvZXwnw?m3KozYL>%Dr;f@in&9%~K+e-!`tt#QI<(!|CpI8OLXnz)3LX0y+h!floA z^l*4C&1RoT6F!qBB9=5i=d=G{&ex0T<8Q=Gl{6DRVoz0#(|p7|Rq!`5A8|{iG^K=( zh)ipo<|FQ?g5%Vm;eDEqxS@(^azCYUnvb}j3Tk3IB~9}Yw^Kn)^AUGb`i&Ak;$}+s z*ybZ{rh?-%AF)cC#+mR@y{JC^?%YaAGvOodr1b3OBkrVv&u%{AMoPJP2_JDErE!{% zxQ_~sQ-6l{X+GjMDyGR@l*Va3;w~zvX+Gj6O7AlfkLpD=p55XR_fWxcV%;|m+(K!b ziFm{vlr$|KaR(I~r}>B*D2+4WBW|EHPV-Uw25LE1us{Ar+(0QIHQ}RrQ4LM=QTql; z*% zQVrAs5;ss9C<0Pc)SSfPZ4!l(qN27%V)-_S)){oaMT&}AOkx2yWn#liQBgA!TeC_O zo200yxrs&GB&r$L{P?WmrYS``EiB^}94R}rN|b(DSja6ZYK9^`uE&R=qN0pUhL1}W zktr%lM;SjZ(Tt;5&uuh-T%vGP>|0tdst?~i1IVQbLj^VICj-b;h5&vFYSK;ykV_MG z3To=l@a&9DYA<$lQ%sWpxqc%vQ#(Me(`Byl3?SFDC)Ri@>!xvXjh6t(HBNI90dkEK zP71zHGZF!EX=aQ>f?O~yPRS(-BLywb;%*Y+$qa(EtMW$RM%{Yn$;FR;ga|naV zqa)?^$*6LTG!vs(1WqHh7)7i+I#P>K7srQI4X7D}Yi^=b$6!Em`-=4m>dG*yKLg>qI z9TK4{$MNap^tiF!&ZNubCDs+kL!XIx;E9?JPE8We9F)ZRO6R5~iRD#L63Z(co0?=* zxu1_gNvy7PYHE`BR0JjQsZiAolf<_oD5*cY%t)P?Qj!O0K}mcpbYyCh_*w)d@wL#2 zsYzC^H2yq1L(_q&N#c7E8zmbh=(yA*@xcg6;)9{XQj<)$ho@&cDmBT3dsv1+2c;%i zpSAVpp?i36wiOYsz!(%f^CfvhQGaZrg!C8VKI7+&QM`l~$ky%iZ?%{!%Bopr8 zd6^DJ?ZFf7Vf_V_*)Yk3dw5o+gHe-AxQEpjbS!F;3HR`vOoyT-nQ#wlFQ~+ZNhV?s z&&U=Yk!cbo+*3iML+s%J*;ZJ1AvV=nctQ0w_~1Mq3rf;GJRQ?06Yk;Zm<~d1lnM9n za7@RbCYf*#OGm1)`ftqB(J#3Vq15lGpxQC4r7Te?%Zt`N2h>a2!+vOGR z@`953vx9qVo2MFg?LoJ)M@LC>5BGV&QPMrO(Ni_0=2417;V8{L-06izDGr5_<{obK zf|6XhvAV*hasY`3=e~!<6(rg29x*6*aMo6kWPR4Qm75S0N?Pn;22k)_a^=PZAdRv; z_6R`XC~f7&{GZ?`=^m#4Y-e1h`CZaI%>I#N!aen(>ELl|lyHVsT1Uy`9~IBwCz!cE zv3JRu3aXu9k_q=P^=Dz`kKSd%J={YWz5 z9yUr)*$h57vwniVINigfpRF+ICn!nxu!w>r6YgQoj|yhkgSW5TMDOtDG50XzC-&eK zDmr+a2|s%9gnO9qqf#06;0gDzcEZARAB{5M9;W-KOoojz;T~rDEKK&%C=>2sqlAUI zKI&B8zH(EsLj2-P^^s)znVY~8O4^wlGks$7l9@gW6MZzwgnL*mL8USHi!;wBI7+&Q zr4lsCgnL*iL211<%7lBE<)bWAlT5g$qC<(^u$>DUw#IQL_y_{#gEPM;HcICAEKKjwC=>2sd4z@45hU4uYA`apMSp5Q1MdzjC&?ab$iNiv;B#V_!SpDP!(J~)$k7UuG3lnM9L^N{1a zq;WOkMC_^O zA;$+d_naZl)(3}sR(62cb|&xye{r~HWdjIFCiXqd-&vWyBgsVUA#1Q2Yp^qWC-&fE z4OU|fc6NUVO42>X8tly72};sE#v1HQ-3dw}_N>MloNE-e8j^WCtFZ<ql*FmQYOKM|WSyWSV$W)< z!Om2jpd{U6tijGiouDM$W30i>G@YO%-D9l5o?s0|Hhfr(HP{oZfr<-asvB#tCs+fO z7Nn%PC&3zw%+6VjHP{oZ!ARC%HP&EfYEJAICu^`8Yp^phCn!nx7;CUIEhi{R_ZVxi zGbtx1N%t6Qu(QuYP?GL3)?jBsPEZp2p4C``J;55Nm>{OQu?BmBHBc=)mVc)!5U0t4OUhg-Sz})FtOU` zYOKMYU=1d+1}kfgZhL|?nCf}RVc%n{!Ol{np-=F{QlqP}277`vn8+He#v1G_G#VQv zS%cMBgFV3-Ok@pKV-0qe84Zq-?lIP2Pp}3PS%cMBgPlc2gQH~ZG1g#Dum%%ZgVk7r zJ;54GWDQnh4fX_UFtNhuYOKMYU=5~v9&#|Gu?BmBHJHd6ti~GbEH4`S#mO41tS-9k z3D#gDYp@z?uqRl9iLAkDtijIOqQM8}%FS4VJ;54GWDQnh4R%%*4UUp4H)9R<1Zyyn zHCT-`*gwk}98=DE>U2+??y1u~b^68Y=P#bsPWDPmt{=4fo36UCdMFcA3FBC9*iN^n zPQSc*6nu|ZYS=Efr%v-d_Bf_H>ff$z?(W{b`0M)~$9f#=ajeHNoYw}U4o;lxxVD!7 zVbuBj7k8`d+U20Yj%s5iK>qaN`RU0^t-e(IUwt7v@>!I=0FRpb$ORyrugsr#Ag zd1zfHQLINK3f5Jkb%Ncm6=R~-M_Hoa^(2au_oyh2-X#iJT%tI8kBZ_4l_;1!iQ@D< zDvATdapd{CL~(l+6~!TlL_xhu6pQ+(C|30nMb3ppHRalWeH?^H6y&Q!HRakx^>`QO zNfh*+t~Bsfj6S|OiYM_BO*ra|CSs)KD4xX!N6N!^J-#`Lr}0rya}>|x_4pY_@jzZ9 zHAnG8J~~o!6wl-}($6~TxP|!n?ai~>cc(ADd-M9AU;OR;yPLnhyp7jaIv=TDe%N7R zZ5-uua<&Av)${pG9h#Ud(&Xniq)A{+j><8_xbo4+~B8UMX}$Min&&5>sFH%FTI=13FY9BDRxbEJuH zjx_Pjk>=;VIY*CN%J<#9IZcnBoW6a2^Y*Srmf@ROh5epB{_=~b-#z(i7{(zSU#6}0 zq`AC9E*e!|5MQqPIv-lxOA&75icyO2Vo(uY3Oe_KsR79My8W0m}Km--_XO}o*B_Jj?dJQVVGgbj&Vw=~XB0OUSASM=o z2r9xeR{vpQi`SqcJi`XB+r;t@K}C4Rsy|F@?;2EuXRP?c#NrPzMHYXs+7Ak`J*lvgCtRe3;q4HK+*B zSiy&x1s{Tn@C-Y*>OCgbX7y(5@*W4P_b{{GLvWBV&0zH&X4ZQMO2RdR)q9v(?;$7& z+YDCkVP?IDpd@@VT$^!N?;$7&;|x~sVP?IDpd_3#SiOgt^&Vo9toJZjy@&aH=hC>Z zVZDdJ>OIV?_YfQ<%rjWMhne*rf|B~PgL|yrgW6fNZ|LeV$59gJ+1t!|55ZB=Jy!2w zW~0`iB;8~69%j~i2ujjDR_|eEy@#MA-NXB{ZRY)1P?GMkdJi+N&tj5xea71}jk2mV zx~HCY948SDvL&fG)+|Z)@a{~KiP*#55(BT!B$;qeJ@7a@IB(7*sX5mC;B*f!&LpWh z)+|Z)@ZL<4i8UMRJq%XwVP?ID;Jl=JthdC>dJjQKy2t80%&hkilVrVz!RkHCtoIO< zqOIV?_i&Ir-U9vfywxZ znIqkA;p$uMw{TGxvJiW}g{!lt-@-*_4=b?uTe$P=Nu24h`Z{;QnvaRK8F#|m2lrdJ z8zsEOqHDi}yL!}b;XW3Q=(lk1Uc{}_Z{hy%;}3FAzlHlycBS9KwYaC>!hLX0zlHng zo_-705PSajxrOVuK>ZfzP!gu!0!4Rr{TArzQP0JyCpJA7E9#k^i>3L3?0e0g#OWN{ z^7dPx>cXCj6?Gx|@%CJ-^Xy67oU#{h&&8_mvFBn%UC1W9Jr_%}r{`kD@0Gyx_FSxU zVeX!b)p9~yi_IJW>Yj`B>6#&tO~T&0Js0cKg=f#jYB+SRb!QHS?73KTDd=51;KGpmiAHSYO%I8{Yp(E4$9Ac24#1 z4eOk0lr!j@YUflxw5{%(YSc5GQ&ptzoNA>?>$dv-WGt5RUC&@H=K#HDKwUNVo&nKs z&xG^6-ZP-ip58McI(uet54~r=dG;ijhu$;b>QV0*@DEL&-ZP*HD#cw=?-_6pLgI!s zwvOyQ13nf&={*BJ;O)INvHNjY1~zKt#Wf|5A0nyqKw z#{G9pl0ExoYudLlQ8XwCz-G33p&PsQ1tl>lXKUNHv29;a5?k=u_TU@)_5~%urOlQs zy0LLzP!eF;Y&AnS)(j0w>d!6)pRH)<#^xD8NxFx~{gU^E z{gNx>`4CkpP542YSmQ`j)8=w&AJl{)q>1|vX=>gyYw9]f5AYnLWYrh?;yC8UXd zGW){5$w5tcLYm95uDmp1il8P;Ax*eKniavhzgdZCvUjpHk&z=!?6QNJu!S_iZAud) zb5IjeMVh<4&nnaU>W%-o`h#Qk=2Q;k422Ganu$2 zoYl0o%dymOjT2)*UO4FrO5&tzxaRU~zQ#dUP!b2m!!>==`$x5G8G8SykNDK}@$h+@ zhlG1px@R!=3<>wFbkAV!>6HT;FqK|8@Z(hH9%mlw(e?eENbD25>CX;^%+ z5sS+VR$b;lQ{}+%`tJ1opC6x|ynp%f_Fqr?*UR+k)#>Sr=eKc0fNg+v9c5Rr1bZSj zUiR6pU`h7q+N}B0AWeK4#*t``G@B!)iO?#|=FlolgjQ)Hwo0>kWhzaqOr?pX zsWh9nbkejdSmHhVO1vldyW=24<0Q(klJ5y>;wVI#L>X2BJ~2%KKGNhB>`KBXsA(tz z5g)zJ=F2MC#C)_P#7Z;aqgrn65@N^c8Y@(3CVa&GoiypAwS9x9XQz)Q?(j6ugpU^b zXyO)6nh75*^wD%pBxoI)4;1z6^wGrf@cTM6A1O+cKANu0NA+T~ZMmjTuAU8Z$$T_a z>ohF^rAZ%6*NjK&knj;J#A|+qKH^SqoVeAKW+EPOt0zsyqqTjn zr{BnYG%y~mL&8U^`Did7wddbxoaUp!;?bD!5x0AKpXQ@_S=u`1*)Ld{=A(*nHfx%X z2J=zHIGZ&YkEX$V)V}4@63cwVJ>S08c5BV!x`DivDvD|y?8&c0uj=#}tKAICgs%I$BG#||g zAJsDyXqu1eUcC8znvYl&1N4- z(|pA8@6v4cku=Rmi}|ST#oK;&X_}7~^HJT4H*1=Y7V}Zvi#KbUj~4S$-HSJCnvWLq zQQeC-YnqQ1i%0E+KJ^=!j~0tZbuZpJ&U%J&{Dv$RkLq5$S<`&9SUjqG@n%i)(PHta z?!}um%}1;GsP4s^HO)t>`Ka#2n>EcxY)`KvgM^Rj8Orf@U(H8#FWx*(^U-QPs(bNf zP4m%eK58%isiSi9(P}>057 zRM?fNu=Pbev@h1xgZao(VOOTY1~tt`1kd-Csjxv!^O2>(u1tjuYMPHM6?SDRY*5pD zWT~(#Q(=Re<|9jmU6~3S)3j9B$x>lgrosj_%}16ByD}9vsA)bThOXn$gpb(3ew-{7 zc4aDTaGd5NONCvT3LDfkA6Y8w%2e2(rum3Cy546Z9uY^^`?Pq}4y5b)(tJcDeP7#= zbZMH82&GFi5sxetcCu91m8r0?-^h4|$#{mfooCS1t@+4!hP9n%kft8z7&nb)Slf99 zX_}9WXIR^L25Fj)jAuBv>1d6`#xqRDGn`wnHEUWtGM?ewgsoZAd}KVs*3L8NeVUJq zXV}_#24MiUt}~utYv&oHY4ON-hOM1vkf!;_c!sT=XOJd+G#k&bwet+pq>pCf8Mbzw zL7Mc@Y&^r(&NE1p@n|-lVQc3Zq)8vm#xrc~JcBgpquF?dt(|9(CViwzu}9K+-`aTw zp)d525)(|bhM*>%L7McDG80TwbFEpEK2mCeX(rZn#xu;uGi>cVgPz@dWIV&x&NE2U zd}KVs*3L6X(|lw+!`99-NYi{|Jj2$`Gf2~XWIV&x&NE2Ud}KVs*3L5s_c9+D&#<-g z4AL|o8PBk_^9<579~sZEwet+pw0LAZ!`99-NYi{|Jj2$`Gf2~XWIV&x&NE2Ud}KVs z*3L6X(|lw+!`99-NYi}8(xO6AG}l_c$@L87u%4fdXV}_#1|g2-BjXvicAi0+=A+T# zQ9I8dP4kiQ4C-6g{yvRon2l%H+Ia?z(|k1X+*?&065})<8PA{`^@OJRXyUoIa(EM( z<|E@7l!cklG#?qypmeu{ruoQthOM1v5Y}rxnrvOy&NE2Ud}KVs*3L6X(|lw+!`99- zNYmnx@eEr#&mc|nk?{;$JI^3Z^O5lkTRYDnP4m%gK5FL~q-j2yd0w}*^9<579~sZE zwet+pG#?qyuqAkg!FYz*c!n*(GbkCHanpE)Ex|J=8{9N)f0W=Elnzc!;~BOD&!7$+ zrfKmg!7~i?4CS~EF`i*d@C-veLxHCGD8Vxf^$Z1?=A#79Fw`>?X!0I*OYjVX@eH%^ z3|oR{7>s9_jc3>rJi}1WQ1I-wu1oL?1B>O2v+)dDf@c_NPRMbb#xraQo?)mtA<#4* zC3uFR=7d0#T+o)_83yASX5$&Q1kW(kGZc)|e3alBhI)nqP4iKLXBdoUn2l%H5p&#)zU zhM}IJ;MvVb37%o7XDHCLbzOpI7>s9_jc3>rJi}1WP>$m?o?%Py41<;So{eYN5%0s9FjAtkbo?$SaVKJVeBzT6wc!tGzhLYeJ2ICnP;~7eV zXBdoUSd3>V37%mvo?$Vbp(J>Q!FYznc!ttmpFw2}=%dAWhSFZ2L7Mc@Vmw1>ug@S& zS@;l-7ULO8f@c_vXIPA9C<&fnFrHyCo}naohQWA-#dwC2;28$v85ZLiN`hw?jAvMk zXDA7tVKAOyF`l6$c!t4vhQ)Y>lHeHz;~5s?8A^g@7>s9FjAtkbo?$SaVKJVeBzT6w zc!tGzhLYeJ2ICnP;~7eVXBdoUSd3>-f6Ml@xA6>%@eC!wGYrNvEXFgG1kW%S&#)NJ zP!c@DU_8TOJVQzF41@6ui}4I4!7~iTGc3k4lmyQ(7|*a6&rlLP!(cqaVmw1h@C-ve zLpjDx;~7eVXBezL!(u!`N$?CqJww4bdCpK0Ji}1WP@u{4x{}}-hME%sO`g}41kW%S z&#)NJP!c@DU_8TOJVQzF41@6ui}4I4!7~iTGc3k4lmyQ(7|*a6&rlLP!(cqaVmw1h z@C<|T42$s$CBZWc#xpF&Gn53+Fc{CU7|&1=Ji}l-!(u!`N$?D#@eGUc3?;!cjK(u8 z#xs-z&oCO#uvmSDlHeIe;~5s?8A^g@7>#FGtUg0Y@C>8z42$s$CBZX{#xpEdpP?jp zhS7M2#p*MZ1kW%U&#+j1hLYeJM&lV4;~7eVXBdrVSd3>V37%mzo?)^23?;!cjK(u8 z#xs-z&oCO#uo%x!5#FGtUg0Y@C>8z42$s$CBZX{#xpEdpP?jp zhS7M2#p*MZ1kW%U&#)NJP!c@DXgtGWJVQzF45RT3i}4I4!844;Gc3k4lmyQ(8qcs8 z&rlLP!)QFiVmw1h@C>8z42$s$CBZX{#xpF&Gn53+puX4KcUXOflHeIs9Nsi-f0W=E zRD9bsZGV*D8C2lcG|2^(1ka$Ntfonxp(J<)6{s{#@(d-xGmOSFs3kpe151Ku7>#F8 zOM27PTx-089*t*EOM27PTx-_kJ*-;Nn`ZlY-Dve0)RLZ>37$bk9{9UkeTI^#&oEkj z2DPNOacZu$zE9&B)RNvb>osW`&oCO#pqBKe+0HYJR-a)po}nb_GmKWBK`rTRoSJLR z&rY5}E$K}&;UlZhpqBKenedU-XIPA9DDC|w*3tS+r~w7WxwrS5kf!;_c!oVupJBB6 z3@RdS<4pL-cm@@{HqC^OtUiPKikN1?M^>LfeML-DXTz;?-gpKT2sF)vkBnzfu{6_6 z_{ew$756gDgpZ78P!S!|OvEGO8B|b&nhBm^G@e1l6--lWpXT44>pCTxn`XjC#xp39 z*EAD8GM+(6qNbVfk?{;l#xl)>kBnzfUlG$x_{ew$^%XJAgpZ78SdC}cKg%=xKmYxA zzg@k)d3AgB=<4as%a^C$zkl`i_Fc4-l^O+b^|u=Ju#Dt{jDOh4KSV|KQNcSkM-hOCikhR0 zfY?buL`BU}hCu8@AcCUCK&Tf9=P4P8sHi#0Ac&n1L{!uqWfa6t3L+|Mjxr2lCk7D} zHAfi-v6F*{ikhPggxCo}L`BU}Mndc)A)=z@C@bx-6NQM1nxm|?!%h|=Dr%0h;tuD= zk(Y&LP}FFM)o6%w=g4+ZbClr_=hl(!qUI>$Akp-#kPOkr zMeO7vVk1>kNE5YHAHj&Is5#2Wh;tXo_Qy9z85*$@jfjra9A#|8PBtPcYK}5E;@n8G z{qfCFMn{}GNw$lcqYRHYw~}lZHAfjAaqcDAE^3Z4Ktf&Fj)x(^AIb=c)d&f-{K|-$ zqYRPQiAY38YK}5SLd{?@BQ-}EBynyi`S1Tw$5Vmt|BwHB+LqJLZ*QL6zB^ritvuV) zi`UTuf_dQa=FHR0&9b%XV?J~|AW1x!C2L7iR=PY_P!b;s%hi&kjMOZN&xECFNm4dy zmc&QGGPNWr6E#cX6Jd#3neoRnwF&{Nqid) zl1Fd+@c!=f^WD1_Z=-ftr}{xSZp4i;Qmcv9wY;7Kw~9+DRD&HSxXH>8_oklQIfwnvaY! z+DRD&HT7plZyIH!(hTk1G|Ff-%1EUI5}M{Cql}cQozOHNSr?d{lu__~nvbjt%udQE zrfHOsy8ZAZkCahR(|lxIV0KbQK~3|Kb%EJQ867l_@n!gC{L9tp``cencW+M9<0q$Y zpWnQ_(=zOf;hS0i=IP@vzj*rHldn`WZ1^%7gQjz5g3CPTMoVR5v3#mw@Szo%6yZkh zvZRQZ7F5(LIgAkzO^R@0P!SQ0`ztBJhe1X7kee%&%7qJqif|!!R#L>uDX0h!a$6-u zESzGB+*NT;CB-VzL?=z>P6UVF8b=gT)ZA)Tg!{Ogl47-6>lpQ1moaiHCB=kixDw<# zP>Ko9a2?21pcE6H;VO`8Kq)3XL(-fpK$U_{c!r!g*MCw>c!rcYSASAWc!sM#uKlE# z@C?^}T=_{c;TiJfT=z*a;Th89T=hvY;Tf{!T=PjW;Te+UT=7XU;Tf*@xZaau!ZW1G zx!O~y^Mq%}lyj{o#e`=_lyjvg#e`?L(&IW$iV4q+h@C*rZ^5ZJypYRO%anj>bOn8R$IN5P2 zCOkuSoaDF^6P_VCPHtR^3D1xlCp9j`gl9;NlNpy{!ZYmYM`B!x3D1xiCoe9=glEW$ zlNOg^!ZW1B$%?C0MZz;=#Yu`wG2t1K;^f4onD7iaaZ=(^On8QrI2my%COpGS6uU!F zXSeqK4DV3XWZ-y=qCqB1LqJ?T223*H8uH<4F<_Dj+Yk>|hXIpJ_=a@28Vpdf9S+xO zTTgZgi0Ut3k_qRq)}7i5m}J5_yhBlU0h3I4hh(^#3z%fWJOsnlTfig}?jaYh)&eG( za1XI?brvwmgnLMZ>yXeS6Ye4It-b;#nQ#wbZ?zSmBw6n|qaHqvWQjX<6)?$!dsyL4 zO$AIc;T~e%>M3B73HPwRomvW*WWqfxZ>Np|CYf*#tJ|refJr9Y!{T;24mZh!dsy2} z?F39R;U1Q@Q#S#VOt^=Y?bJ+wlH|H$?qOj&^%5}2gnL-mPOSt?GT|N~-RdM@k_q>) zs+}4Mm}J5|ENZ7d0w(!6_Z)A5>K)LJk58A&px?iFcYFHo&8xRBU);RDJ3am7_V(pz zTE0Dfar5e{XaXw^mj* zD5)nqO7e?gRb_*cda|P=zZh0jHYllY;Zc%b467*{l+>RcCHcj$lCnWbtX8d}>}C~Z zgOd6d9!JS9h82{JNiyDAJz0$sUyPunzJR!TM~N%vU1wMw!jN)oHp;Jc)Im^mfMs&aon9h9Vd zm^UR!tX6}PbPuzpB#G5(P*Q((a1V2)HY*<+l%#u@F(pZ?R)dms5A&rYiPdUMlIc=b zJ64hj_po-Xm5!BU!aXbX>#bPDd?j9=^Yqeq}+3p^z6>Ftp z)o~8jTOs#YsaUHNE6H~ESfyAi6f4Pudkok!V$bTt#vYt?Vy#T9MwxIA%fwohSV<<_ z!z!^>Bvz6M_Ym5%8nKd0xQEo9m57yO!acpJ@>xOHprpPFM@c)eCdn6+)OX=1 zX(!f1`GS)AE*vH8#F{K$P*Q((l(Z9T!hAtV?t6^pvs$o0NxH{yzCxTYCP|#nD#5Bz za3c1Q=d(hvl1#)N0)18oR+5R>L!!^hz)CU^dx-Q|6pOt{!tORUuUeZ0r^;rejpd{U6VBb!#FD6N_&+5PG!4vKw*=OZnC7Ey! z(LSsGD#?U<$o5(BS4k$^L$=Rqze+OU9Rk_q>a?X!Zfl1#XVY@bzfm1M#_Wc#d+>$a2ai+$C}_E{BINhaJwwohG*0qIx` z*Vrh@8dwEajWXdLvVB&+Rgww!knOYTt&&W*hisqKZk1%hJ!Jc=a;qd0?jhS}bz3Ew za1YtO)mQ_o+8Ufh`m@WvN0s+EFUj@=C9!f_jWw`}twBkw+*A?TMwy5`WDTrZ>$WFY zgORMkYHXj?YK=WOS%cNsKC9Fkl+<_O@Qbrfs~$Yzo_Zc~l;o*_RcQ^5Qs0H6Bu@>j zMr%+~Pj-~#sex5!4NB_Ij*{jc)@Kb$(mlo+SasH*B;8}Ifz@V>Ns=|N%B-7JW(`W> z%xz^|R!Jse4_SkiRaqsOh&^NtR@P*dWWqgU4OUiUm1KQ=ji&}=4OZ4;m1H9JkTqCY zja8C~l^a=um9&hyul5AhOSrOKi&1ogs z?w*OwX;)TYm1MhnCibRXtt^n$Uk&{{6UzdvRu{;suLdOo8mv|*$Vx=UCJ|YK)hY#9g~*^J z-D9PK_5^D%ku_MYR*=<)433iSv0_119x^D&eUDWOvg(jQN&VR&_84nm#UT%p$CR^6 zu30ZU_`9nYub;noRtx0z!h<(2uO8K}&_h{(s^o^ng{>`m;lc2GB*bXzie7jy{vP>R z*kf?w%x3a2Ny3T$nF|m0TcAJu`42z-aP`P2liq$Ryd&wi zK$<;FC+_X1!n22UEPDH?da6XOBo?xaD`BbJ-hL`PAIX#$QqtQ`#or@XMk`&>+fRkx zV{bpDI~!)7^!8Kn*@L~2)vM^YK;ieuVimpp)cNi!aURD)6}|n``R=PO@EXsL`Yn*Q z?7jWer(-jgsEBPCSfZl0pSpjSNH&SROO~kU?WgYFB~rD5?-ICtZ$I_vUDlM0)-b^m z6}|n`{ku$HJ1kMr+fRLZmn=~c^LTGRb-r`>U#9)k^i5F%s_$=qJt-IH!iT+}!VRgWmF+gH0>;D& z81<|7U?$4S3K-UGV`8(7pdxN)t=GoHUK>G01U756F|pM~P!V*4b=sI%{UWG{Q#&hu zF|pA`P!T5(R{LUNpN*IzYhO%u(#46s5L5(*YGp4bmc0ln!ZTL&Vq(>cpdvhDMK2~6y$CA8Ggk9rs`Vr#m` zJYyv-08?O_K&4UG_GL9|3VIZP?o=HhkQA8^uqPh{aTT8^xAM)Y~Y2NL5)E)L-vy6k8?{ zOB?n!il3GSy^Ui0fNUJO@3E3Zy^UgvAz77Z>1`B0o>=!biVcQjaiZQv@zYnmw^3}F zL_D!JJiWJ3Z278_Q15LNKN_;PQEZw-Kr4D1#ZQx{w^3~Ps`oaE=Tn2;M)8w-dK<+C z_w+W3AKcU1D1O+M_BM(w3mCEntFZ>XjbhWg#F^V_tU+(1*zzvP8uT`bpOyv*)?g%S z(Ay|}dY1{-ptn){a82CXD1MqmD-tq7z{+&ZQ-j_{@#D&^w^5AmdnU35Yj30YaT4`5 ziVc&9tU+(1`01;jU=5}bsetSMDs2>hcz<{L`R?6|w^zTrdi(Chs~2}K{#)%y@Lzws zy1COo|Lgm^`v3lR^}~-p{ps63UOk%6eJL-AZiCub9&w(sGNWF!`okGJ=f;%K1R^9& zbUzJhV#B3zt~Sn^g?C@LD5hzZm8TJ@h#F@tAkeCbR78yvjGZ)5(Iq%eBqK@_>4?&- zGOgo83hyv6@m-oo;th@yNxae=>^G`Qrq*%lKYg4_Jhjj`wZ3ZBgnKp4$;PR<)~t!^ zT4|b(m;fJqpIAFe(|p7f_@Jiwh$k09KodS<61>J~K4KdDVVuWw*`MD$`}^(P>6hD^ z=ci{kZ%_Yt_U`syPX9Dqe>IJ#Ur*OxZ%g#6ri#ay-PgyTcRTlAzx=#)P5)35q69g$ zO%U@sD2RD&H6`n&p?QRu)R@tFWX$N`2r;8EowtcazJh|7&X~&*L`(<@VlE>fNDvb_ zCRjIkmyZo*u>=tff`W(!2n7;ECruv+W>`x+F4Q!GRK+-$vBkyb$r&=?b5 z;ic(dW~r^#o5u*V4Ca>FX}wtyZW+ujwIFu0BJ47lUus*_W<~gAFvGB>S8Vn$H+wM0 zu(3-}5sn$mGQ2GfD#9{@d1g#_W`k!&3omtV@bCUI$7nZR-<`hy^W)Q#_b*@G{_APj zzrJ2xy*fR8@%%O#<+MEII9AfC`(7}T`uTb&&`A^S9oGW?N)!GKYBJWXETJq-I5?;Y z2Wy=0ur%S}pe8&lO}Kd9>pJK1%LX;!Vrjz1(u9wLn((nS;bdtd^u;vEtV$DJmS&Z? zk1at>cv+fovosL^gPL%&G~s7y!p}iX{n;h#k1I`^+ z#+mR@E!Ko_nveE`k62h)?-M>6uJwP3hc_ebFj5swIH_K-;pyR|Dw?oTt=j}qSgDHE zY1!x{BCL9+@KO~`n5kB8!boAJDw=Q;_gcDDKgMqWZIgO*ih+G^J|aqSg;ey?}$LJBmBC;7A#vHtyBx zNE41)%~9O0Rndf_R&x}0Y!c;`E%^A1Q5!dHRWuQ!R&x~hZB;Z8qquP!H*VdkXno?w z7{#WX5_Ly$`xbkrwf_|6sXK~0xS**1>?q1TTz&k6qga%A+(viQn21qCUM1==YD_q4 zGe?acqiRZN^RI7?;!Tp?DX)@(Ka@F&hkxqj;MXdwiDK zlBhe1*GWN9a}=+W>fd4tveY{W#j?`ilFO=#?6OJMVtC6~+c%>8^sX2;Q zN_C_ON7b{I<5!AzN)qLzQgEc^C|)X6(S)PwX$wZ`t3F;U#YW0&CH+wDDBddtMQzo` z0?YOB6Z@!o;DX2Z7{wyX!IA3Ej-o8HTt}LSQT50Lq8_7IYB@MkTlKNnavfojv^)-6g5Y& z{BnK#c1O+i+y#&Cj$#Ss;7IjnN72P&RNcEbE_>#B?gCMFRNcEbi<+a@5W2q8c1O+i z+yx_bM=k9!YOd!l5cQJ@LbJgi${a;%R*%27J8EWY=y6-zQMGYW>kn1WUGVtss9FNM zS=1c0_^OZaZ0w!Za~F)%9aV2xn@4JnTHR4~@7^qGj#}MOb?@FRYK|g9Tc=dQQS28z zZtNIcMH7yy=Pt(|YIR4|y?gWHo1<8@OCu#p8=O)WqgHoRd+%uRN9L&29aV2%TOYrk zyWpL=qw3zhS=1c0x})mey;;;8wYj6}-o07W9K}x3_18~0s-C+X-|6Q2D1x=IDMhe$ z+(_2ektQ5f&s{K5cU0ZGH@{PJ6uU}mq;>D!ENYHoEw3t?h*9<21&{BJs(bg=k=An; zh`OU{7o=uUbJXUJs(bflQF9b2iTX|xjxtPQBPLNr6OO9qF2{FDPNIq?VpKhMfvB(g z5~Rdj&s`wuj!K{sb3J!~sNY8=Sc$owyFk=qR05Wm4VKslOX!D6&=PY!cfm;AQ3+gP zuIDZgbw?$5iJ1+k$Bn#1ef)%@44Bw+0uQHD%xyE`huOw7hi zY|cz*tnHt^dhUY9H%F;yaYED_wVR`c1T!%kGqLR!qlN@CF&i_nIWsXNn2Fh#iETGW zsd;hxJ2hsaI5ROMn2Fh#iQ>$}kYFZeV^U5U?yf`CWb*EK zF(jCY*_esq%*2pjCT3$MiZc^xb=*FsjF~9TObiKTVy@>d$I0)^#E@VnW;V1Qi!&2L zf|;0&nNasRn^Fm8Vm4-?I5VMC!uB7^n2F-d#E@Vn=6ddeAIcq-U?yf`Ce($_-)UkW z#qQH%ab{vjFcY&e6UCW{A;C<{_1xw7PMw(;63oPG%tUc!Vn{F(b3J##NPQobU?yf` zCJHlgwKYpH6SFZB#hHmA!A#8c+y#&CtG)y?F&i^c*q6FKeqtZRQetCqW@1P%6SFZB zh25#^NE55RdhT+3r_M|a31(t8W}>i1bscG9AH|YldZ%{QHzb&ext_b=@!e4gW@0vG zqOe)D9zVfMEXGU}XC{UOGqKcj7d*Z@D#1)F#!QsiV^o5fSn9dUaiq>n3<+jpF=nE$ zn_2y#+8wpja~F)%?xThTGqD&mQ5HMv8xqXKV$4KY+))W;Vqu}Nu{bj^B$$cCn2F-d z#E@Vn)CSysC_n2raYrSXiKU*q97pQR#E@VnmU`|2Q9qeT zFcS;Qj*Z2ci6OyEEXGWzf{QJB6U>B~g4^S}qY})-QqNuRPCZ5?n2DvHyFk?UQ3+;Z zF=nDTGchEXiN%5pJUHs01^y7&B3v znHUnx#A3`uab{vjFcXV06J>KpC721d3b%Laj!G~S3)`QK#hHmA!Ava1Oq9)IRDzjU zjF~8#J1W6UsAaglQ+HH?nOLl{L~&+fNH7zNF%!j^i6OyEEXGWz+nt4z1T&%5;e4ko zE}`{lf|*#1nJBC-A<+agu^2N^SYD!vwx6Ca#!M8}m#CtebB!2|T8P^_bw?$biN%aV$4KgiHR!OeloEbGf|wG7!u5cT8Z$}kYFYjVrCKh8Rc4sEW1T(Q1Gok)?Hl-5G#A3|E?sX={1T(Q1GqF1} zF(#Oa#h8iRnTavMOf1Gs?9NP#31(tpMZj@)W@1b*6N@nuyE7AGf|*#1nb@6~7!%CI zV$8(u%*2>rCe(Z!i;3Nti7~-UEXGXi&PCdLFau^2P4J2NpR>P#%g zOzh4~jGtvDjx{}h`tiT~@c8ue+nZ;%?@q(%#p`e-&&BwP-T8`HFJXPj_!l)8i+nZ=c`1 zz0+^;#qiCnfAjS5mtQ>n?#WleX@@VPzs;lqZb!rM{&Sn!uRo=TZ96YNrPzG;DMh`K z%LzEM#igj%+xC@}B96d#?J31(jzEf-IlS}SruHjODPr32!c&UPCtp&;8i==@Qfxl< znpCR|zYI1MQqx@C@%Sd3!0vglBkp$*W5# zCOpHNOWs>`DaC|mcsNhu~g!@Eh|Om0*A#iTyc@C>gd zrI_#xZzXvrDaC|mcqPdsZYd@_!~00yMoKZ^8D2*6DpHCG&+sOa_mEOdc!t-Iyo8iu z!ZW;sH|hlT5gWH;T%*H_3#1c%P_zdrG$7CTeF% z_wX`to7?XaC8;O7oJT6x-bR^l4{s8cX>XDV_wXK3dG;oma1U=0m1S>|3HR_0Q91S| znQ#wp5Oo}Gk_q?l{!sb#CYf*#Zx5ASZ;}c3@a|B#^^|PCIn*f%-NTE+ZEn9elqB85 zYePvU+{0T#W!2k*C)~q3L*>+)WWqhXF;qsqNq){f$6KJ@NA~sekFCuo*5awB#Sh&Y z>a<_qlgp=@p6h*NWABhFJ$kM8k$n_=iTZ$CCZetIdLP-BSJC�L8u0#MNE!mtlP3 z;%*`)7E`pvojHb#SWr=WzQgQcaGD5+1r-%`4~mRU6X~#^qN46a(H3?S(XfN!G1`GS zx&HckZ^KUTLyo(bpcq+#;>?sj6hYR-YEbN6gJNV2il{1nP>mHosSZ0>gd(bnA62UO zS*t4697omT&+z2t-Q8)LqELz65r6vK3ssCPRB;Ax18*Lm%yIWh6(cKEL{;?)4%2k^ zQWYahRYX;>&d^w~)TnPB>-(sxwk{YeR`^n7v5KfFKA{>bKB83>CrnXQbDx*17+J0& zrn*|airwo~jI37?RW&bsX#QTlo=?{NlSeumAbQ-`>Bw`RmKu zFpjsbguXNi_aeEkYRm^eoGZC6iDFGt9}Ro%m?+UNiDFq(MX~D+ikcD0e^pWJyMvqF9wnP^l+S=p8$aBPrcUXtz=I?&H zy1Bc1_u{Yb?{5Eb_2{>&AAbDlPv8FW>X8KTYw#3tVy0YBkiP_ufBI=g@Eu}Vfe+a> zF)J=6*iSReD(A>{Ps9daBCTRxVGdkS5ni$Ds)-43K}CGB?6zuR_FGU9%W=D`ns`|i zRK!x;?yCA}M)*|7E~>EYRZCRF``9nTd#coF#`I0OWN>^)=lJQ(``6EJpP$n@4*484 z(?j_jr!SVTp4>e9yZ%Sb>`=q4DZG>v;*EI7OrmXKB2iucJ+zLLB3#ZiA}L~R5>$lC znHMBQEKGuma50vNwM8C8_THjNJ@&I^UQJAHeKJH#_Q*APv5?L|LVo-_peTu$oBg;?`}{3 z*X@nc5>@&@+qmI69I{l}T@&MCXhBLiQ&7QQyuv!u9|~I1#F2tDak4H=yu_d;K0MOI z0z;a3jX_O(dPGxUSuRa{e1e+z_(&5Ab7|u96Vyb=mL^yjX;ztg;{-Jkw55sDa%tid z6x2l6mL|^1Rp%KWp`fPz>^MIex}}NFP*4-0TjRu@R+{(_#WWebrD;B5_zr5Cj~Ku; z&V-LxC0*k*A2Ean$7w!d5Z5>pK4Oh@VTtA=hVkGy%|{I68fTSh^brHO#%VrcC=ZU) ze8ga0&b`f=$EpAH(MJsD(oFb>;atydK4L%*J-Zr}**MKd4Cz5l^AUr(p1s{iYEx$8 zG#@dn2ghkX;yshb+3q7XDdRYK%OuVAc%&X>rfKnrS4_cYw|K-GCXKT_9;ri_jnm>0 zua|=3)Sn%F#M>fu2x#|_`jeTa`G|K#v2pUQNFC42N4zQuYMPIDRitN6_=u$fG*0so zFN%WWG#~MzNaIZSh~)wVpj$lRHBoS!<|AGcX`EH2EgqG6lzg0@yd{!m!bdC`pl3H9 zv1~x_+4W}_CvIKU6eHmy77oxj%||R95E~~;2T0R=#Nq)#P4f}U2k6-oK4SR*jnjO@ z0s_HtnvYmQK;umKh$RG+bzweY5rN=1%||RFpmA22Mjx?^fW~R-Iu;TLj?>~1O9_;7 z_p;`3>OXz-5sL{(GvOl^6VS7pk62D1_UtStAWicT3kn1^%||RLpl46`h$RIyPV*6q z3IxY#K4Mt`jWgjRmK9K{k@<*)1%l%=AF;H6##v<=eZesk8c=?n`G~~^g5xwFvD|>hS!Ei1#Bu`~r}>Bl2ZG}?AF<>> zId>{+9;g1($9Tk|1JX>yBNiRdvoju@`;@hglVt~_$#`^bQ`W3$@rb1d^z5IDN5`Z7 zdJ+BO`tJ1fm)qNyr)l~2^u^7quXI5+#!vgtExRtij#_*H zh*JOMh9CMcNEu#1lS}&=`{`5HzV$dT8P{wRzq8W{`?npW_C_JA+IMZ?GHBW(v?IF zg4J~@sam=FBzvs9duKcC;3)NH4STG-Tm6+2qa=H* zyj$Is6Od$&m3OPRaz7-Wh1I-^zc^ooV{^$@VYTiu$OL;>-mS)62AN zP{XCBT?SdFuaiBrcUH?TgG{i8=FV!^Wsr%phpn^Ku8WX-4h}9NvWKt1XLV9e%q7{w z$6!Gw*u%$QHR`etPn?Duy!Y_+SCIYexwO`5KAZ)H zg6wC{rLk5EY3$+KZ*VU4XDy_$hflvjNS-}>`91G^`3*wy>|vFlAQSB2!><}}k&t}% zjg8U_;`!{WQTCrbmu6b+&tvT2t8Z|WWDg&GHOd5g_~@&~TQ-+rHxke;e7Jd zC==}Aldqa?*(m$Zo=Xd@c9g~*KKKTI9V>c%ODf%;bX5FZ5d>LeXB(*u$q@HQBOJCfGx}c(vFv$OL=% z(5nVp2ANuzueMq? zmkIXpiC0av3^KtU+QzG;mO&=i!v|h9)H28fduSZ5c3K9RU=N>n)lADE6YQaNyjp1y zl8?JF_V966&9MwJ!5*5&t2LHECfLKL-IXu9XLUI4=Qv+>S3c|tGQl1`?5=#*6=Z@v zG?16wlg(v<$JCm6YQap{L1HCK_=KkC;8Q^$v9i->KiV}~xSib;8mMP+VlK%Z z(;BE_aRQR;F|C366(=Cc9y8}qx8ejO*<Q$V8BzsJ2piadJNV3PY2I^DX4@s@T zW?BPvDNaD@%bK0Yve0ZI0l)<7MG6Oj6{hLEN;ka=zblI$_9ft+&_kYtZ(4P={}fFyfNYaq|u1SHvG zS_9ePCLqZk(;CPNHvviZnASi>xc!jS8f>ODkPB`ClI$_9!NIcg*cME!!DdYtj~y8S5jV zHMq1|X(5@hJ`!4kLao7OT7x5@H7L{?Y^F6h5?X_cMQQutcJE1O4K6KL8c5R`90{#K zq1IqCt--&kmU{!f=lw^--4GtES2O$}`nbzQ7O?ePff7X7uvFD>&gSO=CKV_i5TmsJP5ai4T zZtNRhbLy?>Nej74#0gB0LzuYM1Tk@~(Kx{lVIndMVj?RbOdKx4L}(Vo1U=+RhZh}T zA~p+RA~q8yQ&^x&YqYzJGHQcEqk%iR&JQO>y|Z&pVw!5w%uOgss7mVym7HUh66-cIzOh{;d6cUhFC;0@olY0#}U`folatVr4yMP!PcJ)y{vH(?tT4fl@^n_EJWBVR(!B`yNP{o^6w6+3i? z`^P=UO_3wR$M%XAoJ;-L_2M(!KR$3gp~xBTAHTg{m!`-W?jIci%*;07>u~@0wl;4b z?jJoT@y#!~LTp7_3^h<~SSf9}kOYxPNpkB6b?thWp2d zMFgc}EVsc=XGNCmX?jQFre4A+v zhWkgyy=S<8d{{&%b~z9CkDf&|+&}I!Fs3y)5?X`d{_#La7K)vR`$rEU*=b~Bftcp9 zKXNPVG_sl2;Q0UF{iEpL*#?hh*LoS?wK}o!R`~f}p55Hty?^t&pYE!T>@Uy0`10$2 z`0VeWy%Zu6HkPj`bZZSFvNjKudFMj2)*vE6W~&S-^lA+vBG+kFt%b>&AR?sg=G0o~ z)EYyiQ>z)Z78^bBDiNEccI~4 z5E0xnzr8}gy&xjEXLfsqc6&iYaBoGC`MJ<-FNg^4nY6diY%hoi?pa^ILa)6TBE9y^ zYOm00FNg^4nbTgO(_Rn}+*?squ3tuL>v|Rh5%p(R&X~`h%sdi^;EdVq>F`M)f-~09 zuh3;L_|@Qynd}vs>;)0Q85%R3wUH#g8l15pyD-QOjuD(OJ#V2SLky9Q4D@5rS67fn z=Y$|4I72fAA!==PBZ4y)U>6!O1jnd9yK=^~yoD|dK}2wd9t`^G1ZUXDj|L1v#H&JZ zjNps~*M-4#5D}cQ*t#&b4kCgx*2J%{iC+*AoUtB$g+2UYi0t8KE&K{ayg@{8#ya?w zJ;51v@UsSfrIyF`vXBk@tbbprFIL@%;Ec8JD|>=7Y~N?y`^ui+47>MP^S)9`W4pf^ zoH6xoVeh`+>H%l0bzeDZ2;aGfvvr?!?km-)z88_5`>b(ap>#L))ok2neftXg_5~4f z&RE;N!nS=uME%+IoUyKbKI7Y-~*0Zm$XI~Hz=Zv-ND@TGeY}sd; z-Gv?df@1_{tYP26hJ8UqoHKNIJuh^4jUlpMpS9~-=HP}WwyMl&}VI-v1{&i$fF-o$>n)NMg))yQl*<;Q67B=e(LXth! ztZ!knz91yoV{+Yv&H93nWRErLTiC2G21#qM$(r>oY}OZqBzvq`-$J==5E9|qWWJya zoAm`D^=A!xtXbbeYp@_B*<-Ii3!C)?A;}(l{#p3^6NDsttXbc}_n#mn*<%kt3m<@j zkYta&04;n03PO@S_5`%>2`C21C!opRfEK<11tG~Edjwke2o!`Qd+Zfx;VV!B*}ejO zb@Tr2RHnH7Egxg0szX4cD2geg%bEJr8_%}Y1%G9&P~HEQX`?7AR)$dFdsWAZYj6;i zxg(*v11{4?QBMHR0JqdR4u0V*J38Aq9VeNqGFp>;|g?d zsHg~2qNvzug^Do0qH5_~L$oL=Hd~?MwY{Qh>Gh*xzZI%;i>amPSdClEE@`YxFGW#} zTg)(3)C{+nW6}&bx0q%Mj+J>Pp*pviYKo#7x0r3JGmzm{ZDrYViy5bin&B36PHN!d z++x}(Is?WnW}fO;KgzB43>tRO!w&kvGRf|I!w$MbdN=H#9~P0_`F7s=zK*Hcbx(7sxO_C3*{ePW5`Y9*R`qCxvqZzIhwZVlS^ zM1%IJUPW3+T!Li)jyOHGxz&3}3yB-BAaMZ>Lh|gf63so)pnYP4_SG7+?}-NOQ+@qz zKO9M=^PXtXKC?mlY7N@=M2Y6GgMJ7GO)oy|pgV39!w&kxB0|Dw*g3Ha%nAxCxHSPFL?RXH9XOD@;cZ$b@kc`|+JwEK9dv+o=^IJ_pzEeRS`+0^P^!@G3 zROCBV&6~6J$l{olD+(`1mKt z{(H|%Ir++$KSB22d*<36tGQ9|+3&pb)h{@gWDno`1estD73C`*`~;a`51;#1zV-<+ z!5+T#t$gYeWP&}_va0=g@P;nP1bg_(xAKuskO}tiiErf#pCA+LsriuR!}+`?$OL<8 zKBR@TtO1qfv87IB`D)VggVORKB-vxy@`Kv)ASBNo6PF(pm&YI}E?-SuKJ1`-;!Enw zhaL2=gHD`1!w!1bLI3>Oo42n&u!s8c*sfmlA=eXf*g-$eWg>E`<@D`bGIBepFOU5^ zwVu9#G_Apr&>GCt8f>ODI1*ZeneIZHX$_8q)?ltB_3ei@j`$L4A1; zlI$rjY?O(6PtAuki^#MFN22xgMHJma^0o9RiF?nmgT4<93SUc)VFw+TFU-^$3_Iu# zp+Q1xpi&5I8>Tfl5?X_c+PT>_Olxo?v<4DtbCkxOgw~)?Yp|Kt;7Di+%0)}T;pu$k82NN5d8t+#J}9@82e39Uh?_4X|!>L+Ep+yCA(?4TbAXy5jnSJAHPUYT{6(^U76PPG{6ebeVK}`J_FmbjB6FIdY zCe9XpJCbU`#B*p66Nk&B7}e$zd4V7%P8VUKW#ui(em%XcQ2-+(Cc#h+4c8-l0p-86pQI7 z&eTx^A#tuQrlUAhM-ha?=CPQL;!GVy43avE#dH+Pr1sAxbrg%~D9+ST1V@RTV`07Y z`Ai)}5E2{5Vmb=-Qb~L`_Kn4K6bhvhkk~dB(@~tMqX>Su{_MK5FXqs9rj8;AiA_U? zT)PLKcj_pDkYtbPD0b>7f{svc$W51HOQ@l-wWsd}}i>OJvPJ+X7~YERXB;;DM7(*5fZ zzS>juUav3LKqJO+K2@*wRJ|vjs;4U5Z%2s>>3L5)RZo1XUafQSUS;6jAFlanM`@wu zD2tCj0#EhI+0LbfmQ@Dc`}2&l`1?wz#n>~-;(OL5E@tb3l;|jn?<$$KCTiA2ZD$v? z(AhIv7qw9q|8S#7JXMdf_=jt$byM3DPt`M@s#kle-V;yNbG3$VPDp#I-V;yNb2UV4 zA@PR`;vaS*_En25qEQxqzlf~2+Rol;!MW6puHpD7i+@;` zqbxoi19c;T6 zgv7mPGp)hFwrfF1{aLdvt?k+|%Hlh26ji$4&L!V_j)c}=9%b?OgdAn@_qVfA7T*&L zQfsi8)?k#ycg-cw9@82e39Z4UOIWjC7K_{xT7yfAuoluHw}b`%r9W5;$=A|R7T>do zMp^v*akijxL=yc(&TW*%Kg^}wdq!D&JY-e55kgke8XUEydFLIn)O<*@U#?W@94iX1 zLYI_M^C2yyv8UdxyGO};&uV8+LTfO};vcGTO>1x@v<8J*gUz%Cqb$DT&>dy*59@NX z$gSS3d$*064{3Iy&CZ^xeo-sXzJ6B=fL~w!;b*UJe!RPVe|moZe|_`nXQ$`uCtuxs`$zqkZ$AI(lNT?x z5-tHQ8zuIpurE~DS6V$)>mx)&9wx9a6xat55qK2F9fkV(AR^)pyYd!Zd4q@uJM6|= zc;gKs;;q7Z&J|vGgNS&lFdMi+8@L!^E$6=OnuVKYsSfMcO*4pyO|x*%EL7G95%p)y z7-5xgF6=iKM8qSXwVNw!Hy1<%XRO;?VYj&;A~<8J`a)HG5D}cQi*DgXH;4$%nEhL! z{aX+boH6&eLie{IA~<7;`a<)!5aOBUZ|410c*zYSf-{S8roJC{vhZ9>xUZa9j5Dj& z*1wC`mQMfX$D42KIraIwx4(b$-B0gte)s)t$GJp9Ui0HE^yAg%2hJt>@!GpXp&f4! z5sa|TzlCnRK}0ZO=H0c>j5mk~Mwl0Gp%-ru5sWY^-a;$h7$U8B&55_LyfKKVKfA79 zt8Of;ZVV!V5%%CvSlrkkf)Ve&{p0Q3=?}LzuTS6J{CN7)x9@NN?esU(i%-gY`t#|< zr|0$A&!7GH{>=|>?%w?C?Vp~#{O7+syScl2|K@i;-PQm3muFvm`Sm}1_V>?TmaXm+ z*Dr)u&-s#8xe`=obbua|nNVC`Xw(w~#0g|U8(n&WfS?;wMTHhUK|rw0$VPcd5D;YJ z6GfTovUn^|2m*p@yyjj~DZPM{mRP)2i#ECe!8AL1YRN`7Ac$rsPc7K!1_V_$YiW|ESNvtTzOxMGTui?LugBFJKbl8dikHzL?#dXhptNo;kq&BA1SnG<}ePLS7K zaWcZtxgs`3I#-x+MWJy;5D|`OEZm;>wET6IVzll+Ux`2eD!X;?ja-BcbP{-kFj~A zuw~@>F7v3hbv^%s^N8qinnK=+9k_W;>@*s%GtI+WR`2%4he-Omfw_OiDjT0#ZVOE&lZ^v~= z_D@J62op(!W}LVX{o&^KcTrBr<(S_wu{v#ES)EoF^HZD;sxa#mcJiot_W;v)#N=Y|H!>bEy{PRq z!6QpAYTxJjWP&j^PD?P##osU!JYv1tG&9MlZ%^=u1#7~@xhl*AkLZp&%}g{3Gr=Q1 z919aqS;9>4h)>7DG#>HsIQY98kNAA7aVB^~hg^-*c*FJr;|LT_S zd_)#z;ymIbvcBDT#AoE#x6>t8n06lVAvuU?=MkTh_3a5BQN%aRl<^5O!6VA}glRmY zkT3Y{b{;Xkr*S6EBU4Ul=Q{M zNlBkDjYkyqT_W74FCH|^6{r!3y1po=F{#*zL}_0X)IvLE{PZ({N>NaY?I`dQD9)rP zsF8^pKY@ZwQBXUTDDx9&T||%3T@=*l#O&X`Qt1~3H9k@7Cs6Py3aZa*4<_pU1d4+x z270mi0jM#GX}~C`J`bSAD60OVpvEW)|MdC&XOr@794L)+g$Y81_Na^5Py6w#ZWAW> z6vQ+-vAj)~pi>aj*tFW&#QL@%rjdySZt^9rFZ_=T4PqLXR^%Xs2`&XO^=J5v>}=XV zr5I*i#=tZtZT)wpqvlh9X+&a?TaZYsa+_wBxoJW{q$sE{iKe;&1(Twnb~LdAtUy7f zD5!CXJzxb2E=56&OzZ+H(7J{m7k(7f*u*}t`^rABQBb23?R5nTIz>T^Pb_*9DEJfv zW!2j>v+PZvAXF687{$Ujfg<}51+}AzrEdbwFsjP8TJE2b*B5ApQ8l>&P`fzQOM3S@ zt=ScTS_XmzaM3w6M$v9ppPyk=&97jjmV>DG^#0E`MxE_|su%TsP-E2DPAHo02IsV< zSn&CFMAfT$_eg7w1)z3D)w_B>s4?nn*Qct)=?67N(R_Db>utRs)EKoJqxKA=YM!N? z)7==gF8lTuvbzj+0HHc|+VoOzFf=)q9{Tb%d*u0D?5rwGFsZ?8 zAF_wqqZZ@n)gLEW{e_>}A#{Nz^M=~vQQG^zOzpAHcc=A-AJm@v`>^O^+v+3lb#GEn zdjwC@i<$S4dh9>7<^+m0Cr|`W6%^Zj5LBB3MvCpeg5o|B1Lbu@BgJ-KK@mL#L9yQp z6#IPztvHVt#~>&+e1Rf(s-W2MgP_>)=Y!Xg3W_a12&zA8f2cEprwWQaKM0E8Nh3w@ zR6!9v1wnBg5h$`{6|^2m|K1PPo=!tkKQ#513fUUKUl%@~+lHq8=KE(a>kj?Y@liH* zrsN~r@XzR&M{I9=SkpXWZwvl1h!*&&CUrT&(;y-^!zVQ%B2EY*B2M6Ynh-0<*YZZ+?8jjP5vcB$kV z=U5v}w)Zj57QQ%dJ+)y=)xlnu+jQnDjY@_v^`R`>VvjWEGx7|=M4BOpi8O=8i8O;S zv1J7@^=8YhZ4`bYT(hLvR)X*#JMtl+bWhkK^7ov+11>%a}JR+_b7oyAcWhD06>&wqSYPd(eGTgNNn^<<(cGrrp7!P6%puaA|Tdss1=_CVgfN3M)|b z2!Z8Yhxz2A*qQB>Sbri!tnMHpS2u3ELd4<@B64x#t}8^W?I0r8Hg3A-!pf5%B9}H- zc46H~5RogJ3%juDB!*Zid%a<W`MM2lOP|p<{BRE4f zmk@Cp1QEd*R+b16hd~UHN-pZSgjhj3*JJhTXnt#CSA~e|YH*C;3>92LOmK$vB$RIn zF~J!YlTf=Q!~|zpNkZY45EJK2b?LbNGE{8|F~J$ukeuzDVFgL>w+3feK5{NB9|?V(YddH79ub?z>dSFOm2 zA+kVZx7dv3Awfi(GrOHLEDi}Gf-@`)(L5&3nVLVm{?;rE5n_TfRZ!6&8fRD*68vg# z=CIi8NN}cFZ!}}H`^=HxO!eJp5XqUPHfrjPQmUY$LF9dAd69_CsxYuYBxjb|sHu01 zRT$VHk~2%aD|aJ;GY2`d)Vp#wA~<6?u7x?S*m`7+YqA{I!W>r+5~P_d$F(rW6@&z9 zqp~+RbOTHr=|%OE7r z9=coV!#~EJ_7&*U+DzcLf2d8b-`BUGU%xtiy6Yc(`Rep{-`~9bPOY$id3*Ez&D-xz z&*hi<$-2)+_%%p}G#2Gzm+vz#-<6tAJqHOATlzu`;Q7qkcMuYbQr_)gSfS-8*4?-d!TI>dX<_$auiAA~C75vOAco0%_xCTUv-NDbig9jmT zomlA2phbj$CciTePjkwlRq#wJz3=F1%boms`M7`>#;3 zf`ox3q&qLyP!tu5NT^sv6;+dcjaZ|oSVuy|LaL|;4uYs$NfB=LCyEMg3Dvp9>`xTcxW)XB)+-Z0QB>m=Q$Q6p!!0I(v`0I)mXe_(WrMZZR1Y9jkGR=^%}j`JgDOaf=zDikdmMm=n?rIJcM;3XYX&A)z|A zm>7zp8n>7lsxy!|x0oE#>F?(j(?ij*8n@U6rH(bjEvASxR_7LzMA5Mtx0oiXW6f}j zi6V{Fxy4jbbgafLCW|yyW{aYz#x3THDr$yX%ou3~oLkHp1;@&ykx-pmOdCZ}jay6{ z)fvcei;Ynf13S0a86`Sa;}%<^)Ujr`Wu1?;>f4M@Ma{&7R?sCBN6m1nifGzMlMPZd zR(42<&Z}{Yo=p`sbKk1@JdD+2LUu_Bjy9$a!RZA( zoGNODTkMRio1k;cTBTG@Jbja|>AiMd*(#-uHN&l%;RC93i$)mHU(3!ddSTSDX1G=J zd>E^rTQqixj@7tDZzqkF=1x&m;}-p$Dr(}~GKVLvEa#SWObM;5b4}J@Uj5v%mMKA0 zJGa;}rOrTtTUM~5e28<4H7l`S%ZgTn>bVTotwd3cTWp+CXCQHIoolkD{k7OSrJ^Rd zb*{-8pgOl$!xEhV;}+YeXsoPbiJ}^}RzJ5`%MwIoF^krKbBpyXQB>m=OIqp-B+jif zyQpZap37ieOLVN3%V23s9jlgJ?-_e$af@<|&MnrrM8|5}Vk4D0)(p35vZiGL%UmjI zhFkTMfa=_0txI$Uj9V;s(O6mU5=Av`vE-$qX3i}Zy=VK3}m>)LK(dfIk#9V6CJB@i`HFrtQl^xxr)Z>++xj4bgafLDtGEwGu)zfM`Lwv zQN0r#t8t6^9gUR&o+zquixQrSn&B2jJemRL7G*rav9iyKP@P*;@|z3 zTdvEnI-4k}am#fXR%;VPr7lA=VBE5Ln<%Q?w_KNDH8)XIp?mX+iLXP_o)fNHr6tICO@8n;}R zVTCzSRGwRt>oTl1CyL5*OBO!Hf{ZTXT$45Jyt*#KDs-Y_HEy{s!-{mGs64kO*JW6p zP88L+<+=Rt&A??T$44JS3kEhx(pd_6V-JYOGcL=>up1|9Q=~eWt>fy zF}W^d$>=i9rpuUIm$4Kry>1qmE<@ImcE)CO8E5OHHMuTh$>=gJbyn@lD)zp$WONyq zQY)bPeJi8OxKvvK)wz|?Wn2obfa=`J=rS%fS1qdRGM0=k<5G47ROePkmvO1Q0;F-@gg>cO2H>&t8f@ zPtr_@E`;gB8vM<-wV(X32EV;$TeFDT81Ji__jji<#Vd`enNT}vy9>>xnb4|ya`A3k zO{82SR-sycd^XKQ5EXd_q1s(&HqAr~m6{2m+FfWi%|s9tc?O}{U1&DVL=Y8u2BF$r zXg1A65EXfb`Ebp|Y?_H6s{X891Fo5vO*0WhMf9Pu+FfWi%|s9tIXt1-+tX~Ci6AO+ zctUka+WGf8eR{k-Ne!5OOOshvNYbUqfPjP?}IUQ#Qs zc}$!$?7>Q%ybu$y*=SGk>o31}_R_TRn#%-l*n-uB@#-v)IBY13H&whK6A@Z9Fu3l! zCW#khB1EGg-t_Q-OvGqZ!;kh9507;wfsgIJbS5+byndcUpho%oMD@EM6YQZU;Y8`X zJo^*usi}@;sZ;kZ$OL<8uA_y-gP9-`?4jh{6z_seu!lZ`6XouLOdLIyd1nO^`d|U{E>d)}`E+63gLJ$;pSdA37*!uYh$%CL;Qte3j$WTF%F%5!h%Ll0G zsAoPj1VQo8podqN4)CoZ2#WixKwUY&=Y|HfeKP&xr@PZ{?%u!oF)G|q7X&;>sNMnz z)_vn1T7TH5ma;HGI$?rz!mPu8OkV~u!8u`qbHYRn62oL^kT5|xVIl|#V(QzjOHPn4nv5oS>U9K{sLISucpGKWpcc1wq0@Bof2~ z*)&d&O_&Hpf|$l576a`YYk`88#v_&j2{XYX8no)$jYq5lij9-@tim)Nu?nccZ1=8F zRx-*;Mp?-yD;Z@axV6@>=BbEFS`?fVv>TRS4Ch1;5%CtShJ}b|D}-o9!?YO|B4Vu| zB4Vutk(LkE1Yf+ei;apJ@X0mWdTQwi5}&-Xg^eKb%|S@q-kGeI1L z#BQ^zhi6Ths7qL+?LA+XmcxQq*2ub$P3`L_%u!k*bRyv^wGQl49 zFJ5VbBFOr!y+04xV+rD&3F6>fl0B9nR@>RcDD`h{*u&(8j4=}IVRB<-ZbOhbYl9z7 z_As>}$OL|ug6YOC^V`V-= zkO}tGYN}=@Vy_uNCfLJHGbCfGykfYrPMcG{T4 zw%}Sm)%-kcE~8N<*u&N`>tc}`8_NVo$;i#_c{}fUK}eoGcG25;(F;M&wf%29m&gXn z;i;cJGuz3mcGcT?)eDZ2k(=H1cHZ@ZkovOb!`VkhAKuTNx$5OwNMzInSqIh^xy@BD z*Fxg?N|60$&&>WYE8E8ivY$OOo5!rHv4^c=f3?*g!P|2Ghc#NJ_HN0|LmFh z4!rUiSdaS0A2WPtAw4qcrxgIZSYrWDi@zoOgDH2}1JhVP6$i5YhmBrV zt3BIUdlsBavd4a!pu*<iN@SOsID6<)veKkP zkcqR0ZCzG6ln62rxv>Imr9Fut6YOC_mzCZmf=sZd=0loAL}L;`)*rc(J#6K&(v?Jz ziL-}&TvjVX+gXMdTbC?DTdfZ5sCVn`4<~!rz(pRuiF;4YhqONrL_~s2u!p@{R<>>t zWP&|4AJUGJ_nw2bXtAG%wP>pqqa7?p3qm4t+g?D3rw>oCho*nq3uX-tc54Za68D~s zy;?NN1bb>e?bo2(9ID2Y7q*+9!H8>JlgSqBIT1aD0LThkQ z#J7;l8XO6&!9@?>LPEo;pC`c{7Nc!ejCLfn1~ZG%Hq#m$39Z4*VzkY)21i0`FjH%= znbzP)Xbom+4K~vn90{$#%wn|7v<62)YcNx5u$k82NN5daY7I8i8XO6&!Cdnp%~Ch5 z!I97!%q&LROlxo?v<5RPDK^s@90{$#Os&CYT7x5@HJEEYq@7DUdlFiMi?wSDX=hJD zYjE*(Z6WRKNoWl&rmiidojnPy!Nt+Ffi$hbk|9$&J9`pZgNv7I3u$LhLThj_ za%~~)>`7=1E-tPuq(yECt--~@wS`0#l6q_;A~$LcR3yUyCZRQ$sWniIj6o*uJ=7Yg zM8+T!ksGxJs*o|rMC3-TfeK^{GI8&r)pDY39Uh))?hQOfr^n6AFh3& zol9d+LTjJ~+=MjtB(w(VW=u$9PeN;;hO>mUvnQc7DAXEk=4X2(v<8J*gUz%CM?z~* zs5MYUKM#t8)}T;pu$k82NN5cTwFYX3V598Mxs{p^X_mTa4UUA?pipbDnXB!Q&>EDQ z4{1kf>`7=1O3jC~kj9>b)}T;pu$k82NN5cTwFaAM4b)Yme{-YOU^A_OT52R9dG?sr zK>ailkj%N6*5Kk&&>6YObpXG(X$>wW1>KNjk7*6mMkDdzJbO%QpdK0@fox08M(Ok@ zogSsrqjY+dPGh&MkI+xmzmC%BY6NO`-2bl9>HC`LuiyRj_Vw-S)30v-e0u)%-~Qvz zPS5AzxY z6xF!JvX6?I;MUG$jAp>O#dJ(?tjxy<)w#utOp7}11KNrI^6chL_IJPgY1{|KePG-N z#(iMi2VRD5L1#XCG5Y#%vr_uayKnz^dw2T7?ak}cw>LkY{`Bqp+kZR#&Gh1vGN1l@ zdhzLbjT)V*?H!^vgly-_qtZ1QSXa$cR{;ScU_-PfKm=<+K*VYY)C7n)EeOak4X+26 z=cMjWMudi|&-wD0)D4K>47VNuA}|YnGVVMG$^?k}P7IL3TEt@l#8oEa!57og7HVl@tA|=zlhPJSX@iJhj45elSlzym1Q9_Q6VhHD zj(X>jLR!<&%B=b$V;r}(acleQyDC_27Dmp`XdDq^=H>7f0Ha0+9L%KaWa}>QC6NU%Y%prB2BPZXpR&_#K~xS#X`Me5D_OM z^XTWoGsiAI1y*t6N0{;bN$&rEO0Dq2m5lQE`EbqT-|y zDlTyq6(MO9RUddgt%Qo3Tt&rIE{ba0^0%rv^H!z0T8`Dm0p<^#6;9BOhnznM9|$}w)21O zNpkn@R9<~``t0@1k9W1Z=Jbn2ZA-p+^|R;SeE!uZYL+~Om3HOKQZz=Gx+!ahuU}i^ z?WcYfAtJtHbSXq!+=7Ujl52EL6_gOMa)O9hIaELi5$h(1h;>8t)44F93?gFHQ28W8 zteGGp?rBs#2@#jH7$P-KR6Gf>f;{F~f{3`ESp`~Q1zHdhcQY$M(@St-jQST}*Q3>+ z71o~x#|X|?`B`E4Sr8GNvFfuzr`sSRIAg_Ul42+35uCBwGi@XZL~zDzZVOA#f?o~J zn9FTp*AHISV3!Ggfg{SaB9a1ZT|Lw$R)*hzQP@w{4-fZ48m# zwq|WxXl)xr1ZT|Iw$Rx&hzQP@v2CHTZ4gm^cIAxu+7|lS1`)v-v$ZX>wGASIGv;br z=xQ581ZT|Dw$RizhzQQ?i0IFSp0+_maK$6#t`XfYlgOkhPFXO zaK`*>3;k?^h~SLb*%sQ_1`+jVSI(H5ZK0cO5D}a)GuuKl+aMx1!<(?yqt;e$)XbYO z@4-S$#AdXz8z(Um8>i%kQ=D@3y5Vf{?5$mH`vw9etEwr(XeRX|M zYY_3;q%mr3b&nC8F%#Q`Cbq#b>d&rYoXo^_p^0q}5~P{T#CD;=HV6sU=uHjT^MxAQ zAS8~O$xLh)n%D**an`6piKC>6Z4eT~nasp?q0%-83Fb^@V!QAqA_hsV?PMml3)Qwk zNN{H|6WfJ)+aM&!Gnt9)Ld9(mQh(O4#~viqqqm>pF1dyJ;k?kqHaJSM$3(XaO>BdZ zWRIzC7rsdZA;}(llvrqD8-yf#On1A`#5M>?_L%T?q3|{aX~J7m-Y$HX2ttxQCcRxK zy$wQ=J*K@~Xkr_L)Sor%G4bs}@of;2XOEfKE;O+XLXtgZV!P19HV8@fn2GH|6Wbsp z*<&WQ3r%c;kYtaU*e*1&4MLJV)-ZRWiERv$4Ra@Jn7h!#HV8@fSi{_fCbmIHvd0?c zE;O-iAlp} zv{(*;auFXaR;ZwL${*kF8qjwBXT3dt`Ra6ip8n;#_qV6d-~I68_it|A-krYr!|m<& zr?P%_dVcf6C(_x^;r&XnGgjPcH-Mct0L{^pzmFiX@SSl09|<*m(m8LXtgp1K4>32ttxQ z7U%4YbApg$j|DnA1Dzlw*<+E;&PXQ+sXuGjW1-H@P$vjU_E@a5Gu8=0l06pe>i;0oe z%0TP9GtLTrIN8H6OOS}Nf{^;N_QUP$VT=`oBzqWQop(l9K}fR43PN`lgvKCQ5V~4L z=+27JASBsiC80Y@LW7WGkJW_ktO*T5l07V5)6b(db`5}okYo=l*92Kn9%JetB+nj} ztqD?VtQ(T-Va=K#6YQb8;>v=x^Uiv;;D?hvtX31G)>!w4lRYd|6QtHyC*;gRwUu>h zg47!8h9rAfq$WtMv2IARhZSmqtk=7~bvc`M*u=v-#lxXrd^Yj0sfTx}hl7x0kI9F3 z%7=rHWRK~GB|J~erT)#$*<%7?X~YwdWREF`cPfa3A5Qj|gm|ZfI0k7FV$%@s)DQ@hvD+@bq7x0(-WesL2N?-UdVM@jaWqIjpGI0#Ahn51~8q&Nsk_L!!4r=~avsXuGy z((XMJ6$c^79#a+XR22sy$sUsx@01nCASo+eO;@~AR~&>SdrVloQ&=2?BzsI*yi-{m zgd}@RTD((Q9E2o$Ok2EDTO5QWdrVxsQ(PQ`BzsI@j)qPI++g(aSW0Iw% zNUgEnpNDE=Irt`7=1=9&*_A&or= zt-(yK!Dd>6BcU~zYd)kMrJX$qt-)OLAuS|4)y_vkYcSL4cQdWQkJl zgPEGj&9nwbLTfPBd`L5wrZqScT7$XfLt02XdlFg$dCCyd*ptv2%rzgGCt z8f>ODkl?TX?5X*Xc9h1Rgw|lL`H&XU*ptv2%rzgD)|fa3r(_bIpgeb7|~JXbt9?4{0HdJqfMBOz-KOD zkb7zZlI$_9fvi&#kYtZ(4K8k0z40ZTayQc&T+FPxA$jjHt$`d<6CcjV&9nxxOHDxX z>@lr@yiya8WRGbLj)c}=uKAFLJ*G7{5?X_~=0jRYJ9`pZgF>yrW?F+Ip*1M%9<-U( z;7DiLG_Apr z&>CF&8?}&j_9V0h7ys85($1cQ*5K0PsD(84B(w&XE=Mh-WepNqgG-;I7SbZOgx28F z>8OP?_9V0hmtIE=q-hO~gx28F?Wl#coLfR`aOro{Lb5{PNN5c%4Ubw#%NiuK2A7UU zEu^t0p*6U)JZd40JqfMB#SylJH1;I42A8HsEu^t0p*6U4J!&D1JqfMBrR`A*Y3xa8 z4KA**4Wwxej)d0W()g%_H1;I42A9r9Eu^t0p*6U)K58M2JqfMBrN*>{H1>Q{YtWXQ zU2DyT73$BQHH|_UU(}maz^)b1xrG$VFKF+1q*!A%^HkTA94lC5hxzrl#o=Y4$lNlimE7bRI;`=4ViIa&FhZSnq zT=MKOapJH-?V3xTJ!XV7tWbOAlHx>l#Djc4W`#P82PYN-4CBFvBYYSS-gB|a|DJjP zl$ktwUJT>G4~r;K3^1`6V72ph7!P)>OPsf>owvhyuxBoL-mZ4u4&%YDxx`&>wPJu_ zJlHdrECv|HgCEYGVLW(A7{mgYVLbTjFTZ&9au^SOU{9hLU>Fbn_I?o!%!hM`#E+j0Yb!w_!Zkv52ZULbHg5@!AY)i556#h29f4dcOwm}nRe_UuH%c<_?O+pNjqF^mU0VxnO@c)y5- z@!-QbK8y!D*h8(sW?BPv8SamXhVkG%Ax&#Aj0bx{18NP1@!*H}GNCn?Ya@nh)?gdP zgAWJAFdmE_6vKG%{>gn94}RE*hVftrduk(wW(&3^hsQ7;?3qiN-ddBxVLaFoW)0)P zhh5#Y2FEZS>>wny2AgROj{h#>!Saj!U!I+Qb^GU&j0f*s2)};!)7#g#uP^`bv)4C2 z-rc@GJ-`3IzIpYt)ARL{uWr8mqyEb`pMUkqix*q@*|VQN`|y`U+A_UM8wu< zX8VO^`$0tLOzg^A=(Qh2#6x+ZS4Ep)UBemK-_sYp} zj$Kv{G{(Vs9Ou}}agNp16FSE}mH+PPw|}TNu=n*=_Ul)tPj~&JFJGPh?)#g!-|1fV z%iEjxZ{B`)dOlC*Pu6`t!uPLbsyD1Fs~2k)erB_9{q2(%FhMe`GR^L}#_U(YSP+tN zl{s*#GiCykft582SL?-oNHz;!tXcS(n%&rk*K1b$^RRiuna#q3kl4o;bKyL*S$GhV z7ZPh0erB`qAS7=jrrABSS$Gf<;m=~t!q03L9)#4NH9wCzah};MJP1klShMh*&BB9_ zWREoq-`OlY2ub!>v+$kG!efv$<6O**b7!;gASBsin%$kv!W+o;9x*JKh6U3@-LP36 z4hyD^H&)_dYnt7 z2^8Q3Zc*&VJS><#%q5?RVspu7qG7@GIF~i%?W^6ID2rU}t!U?4QSj%%#cZ|5qMeUL zK}dbs^t9u`a;cgSJE^l*pV?Ccp9OdUH>Efa0d@r^0?-5IOT!-DC4UG6W?dto0IOdb0rpL17x&fWQ(8@o|d z$!xO)+jH*D=iDG9?>+XMyYo3W2Fd5#)t+;AKIaA@dG_pf_V7732#M$1)t+;AKIaA@ z@tnKbbMDUP+#n>Lb60!L-T9mwgk;vho^y9T=LR8}HL&O0ozJ;JNc~x})a^NUSTOa3 z|HFdmzC`{78^#~?ZrvLiRPE7qU2ZQJxg9V1GuCs>hqRCdhwkx0J9PIb!Jh2}?>z_G zE5-;pESMe^5zn4s!PK)84GX6GMKmm!9!wEt#W%g1+pu7|Uqr)#X;?7zvxi!PVZrq9 zDs`|NH5L<5Yp_{8>abwy2@R+<7#2())+NhQW9yPygJHq+VJ;I|gSqBIn%kLa4UUA? zV6OR)7Lpn3BcU}Y)EaD7oqDi3HMEF^1=Ib5!mwcaz@A~j6wm&bVZn5NNwIcM$5uC= zKIvSUm~$HzOb_>-vtC8I=aOg7W@k^mTlYfFXcE0`XXY=@dKKx0#Cy+XT7x5@H7L{? zY{P=-!y@X>SeO5y7EHhT+kdJ>zrXqM=36-}z4&yR*VCJ~VNaz?_1!ftn-IrCVe3NM!77WnZbepcGVICXra(9)tlDJQ zlW`u~bL=6wd;a;mx4(b$-B0gte)s)t+_vSY1x(lVJIyp;*rn%aL!Em3KeZDq2Mrj6 ziSt>QIG=-M2s86WQ<#=+}SrOcN)z9GLDq3-mb6fWX9~D z%iKNtLd5LbyLFkn=U#}I`x!H@F?P?q5Ha&sAzxS_-^}}e5FxNae&*exuy0Th5xdvS zt3@f@dzVaqakZGSbDc}+-noRRPia;U_AMcH?^{B|zGXdw3VQ}M^Y~xJ2z?U1N%=^8 z)%0Saqkc1pk1h{^;xZa(^wn zQg9uzhE@M*hcF$?eI7G&pEc?5RB$IqT(pIWi?%Rv&kkbZo-It=v(=^^2IxUdEMs9J zAQL76vLGe`GGXGDEzG(y9&he3%qm{EE)!uQ6DLe$;)0m^Hee!aB}^>mASRZx#)+hr zFe^;&w+e6>)?6;K;CpBb-)b+1W*)(IHNpYg zV~DJE8SU3DzYJI&oJS<4%~Ep&dn4HUkM_rN?cZ?a_5YCeYhV0yclwQ5e*PGht**z6 z^K+ihJU`d^R@!+cAGI#~Iyb_^lh3i%*V1lGoJYdMi;pnz;M1J*AHAmN+YyHflX2+E zZm>a2#G%4u9JP(>+e(5#7%;p9vn-_wII_yYXmG@Tk6c1Jii4CwRnmR`bk$ zR{Hk-``keTG+`Q#=ztdECLPd(X*{9@S`gECL=Ut>n@s;&q6eDBX*{9{S~JdZr}>Z0 z>}}j>)chN3ezfAeiO0D(HAXAW%e@PyMcwM2%Kj-ijHt_+1dNu_(e?O$rKR-OU;e)@ zUR}%bUK}0i>+KSHG~v!s5av!VW@cb68OW!W@FsIk1W^iB+N5JeMWh==WvDAt8AnB| z8%4#oHOp7VQELG4n00MY+i+s~MeWH~d!gRFJC#>ooj!Yg^W&W=C7(~fSoHsV^Xg~M zzxn*DPo`;}!jk%OuJZQl?_(8?g%yr28#=_dh7$R#MSFrG0SlSpw1P3YA z6(R^2LRf7bg@`L= zaE#y#g}G;KB<;2sLy9Cs;ev67ehWcFaK`Kw3hfqx zh~SL5EvQOA@zwelUpd1hr{*!i874WI;uKniX!GVHbxWqWYj!5t~^Lhr%8XK}4K0*21B%g+mY#_ZjQpP}spCh=_B>8aOP~u&{T>tqm=kUxsPW zr9S6&BZ4z520t$>29JF;i@{k6F2oAbdCstV0}H{0m^f#u!DKU!(r5#-2;^t#_3AH#d;f zKkCC1?5Syv781|Sf=sZ7y&IGyY?F|JOt7aWI@(b}ydlU0dupbmg*5imt8@1vB73ZN z!&3Vqc0-aq6E8SR^(yRztjUh{!>=>(^w>!_<;9O$I zSSOyh7yF3rQDVnfC!V)E&)eWAv16=u-tIhagOJ!URy%KZp0_bbp1147^LFQX8-yf# z?7ZE1-UcDb9y@P$p0`0rvd7Nbo#$;3lI*ebcISB;gd}_Hyxn=;1|i8FJ8yTMw?Rn# zS+f(_dAswx4MLJVcHZthZ-bCzkDa$W&)XOz&)e0`+nwia5R&Y%^LFQX8-yf#?7ZE1 z-UcDbp2BE#uc_fR%*;8}Z-H>FD)sF3nUP%*sC9T#gX|LJq?osN?+7Gw0 zr>3vFA;}(-TJAM}-3>|hP`-5Dsa}dLB8rz*YL^6AL%+uyL=ckfp>Ro%T4UXiWDiwK zg47!8h9r9yV^5-2(!^d#s}+&$OM*RgzFEyBcdu#e?hohLW0K3g+M0Gll0A#DC($cu zqG`Ztt^qsUZ-VQR>@oYBJ<%&^X0N2xdL`|NUP&`c$yTc++iNbn^XHjq9I%>mz|Lj_ zp}Cw*sb^BXol?CZB+nkx>h09(1tEF%STlm1V!a?F*<)(Gooc-xr2ecqdrYn;^Vh^L z&a=n#dh&ivK$1Ns*xM=Ci+#8W_Dr$2Q?VC>;)lt_LyjI zr)Vz-N%oj(Z>MT62ub#sY;UJ*F9=EYm~L;UZZ8O_KWo@y!o8isy&xpnW6Hgq%Do^Y z*<;eZozlG+B&B<+^-9{Q-3vmJJtp4UDc%c0l0By0+o|3QLXtfu-`gqQ3qq1Trr+DC z-wQ&LJtpAWDc}o2l0By2+o|9SLh8>N_OL$ryi>v#gd}@R!?#nz7lb5xSe>jkC4XJqLAt2X%cxNV3O-eR9C--!CcbTTR&~1H1$z*<;c^ z`QIfV$)1Dkk^Nl)671Pb+b8$C1SHtAnYK^ncL_+aM}2&7LLSui#TF5@eQM)lkXmEC zhc2~!>f%F4YWsqt1bfuP#~`)Fxhf`~y4n8)@1be78 zPy-)>Ot7csL$3R!`u7-Qf<4ssZKgFisO<~RCD~(IgCn6en5pgCOlxpZ+ZP~gi4*5F8J4P@elxiqbT zj5PW~18NO6(;8eXzj_HtOQ+4W2C~pdjFRjzt%3YA5|Ct1G4>?126N4aG)vvI21i0` zFw?4bGp)gq&>GCt8f>ODI1*Zex#mOK54W=?p*5ImKBR@TvnQc7kj)ApO>1x@v<5S^ z2AgROj)c}=rq*CHt-+Dd8mK2KKitlqgw{YUQ3+}6NoWn!5tWb@xh1p)bIpe|i^#MF zM?!0$eyD`B$St8YP&-sY8ha9219d|sq_HQVHBd8DK$_OzNN5ez3zd-6xye7adsiZJ zgw{YUD+y_5PeN-@*uHZ!t-+Dd8kCw3X_mTa4UUA?ps;o4W?F+Ip*1Mf8f>ODI1*Ze zQu870hZ}nmT7y#aAuXh_C!sYcG(_J_Yj7mA28C8Zn`sS>gw~+YD`+#V!I97!6q*HX zrZqScT7yfw@8;(*t-nqh~u@M0Jb%6m07 zkBluWv>3*N@p)ua&Y*l4560(_F$DwiVLTX~M~f#IP7LG0_&nmAu~1?d4~FNFnnjZ= z4&%Z2JmQ=&x#BP$jL##^8Ivjw?Cl2Gm@I2NBlxuoo z7!N))Iv>V^@88t6K(SN+#fg)N6Nm9&*IXh@n@pTIj0d~s5~12;Mo7bWuxBnQP8`OA z9}WtN6Jz@&#fg&{Ar0ffo^?ra;{Rsj!Saj!+J5T(N$Bf$KfQf@`})$8s%b`5Eeh3) z>hyg5n(HIqFS${vG=xJ{Yru~79GL!|1_M304{#~>n} z&dpz`Q1ci>)Sq4NK4z~}D0vJbf-|OgloeoCxLSVW1UwwXn3!$9}LL6InGn_1MhT2b3D(Cs-W>O1=N zF=ibGx(^($ckA8&W*F$+N5R8D_hAtY1Ko~jgTnN680dajMB1TyccPjPX?FEtpnE@; z!$7wuG@wR(80bEPtVg|D_Y!g#=w3pDVW9hA5!JhO?;;uoy7!C7n)M#TK(`~z8V0)e zi)a|=KEy=BK(~WE!$9|*J*G7n2D&|g^)S$VSVU&SMlpHl6@M7$-oHE#1KkgS^)S$l zA7{fr_klg8H5dlE9mm-)(EYH8=-G87vh5=<`^8be(6Dy&c|DzuzYRFu04 z70sn8DxNi?sCd^DDty)}D&A(IsQSS6*Wy|iD&3-^s8H5utguF{s9Jj0Cx9p_iVB2^ zb_Er+7QH?yZ-b~bdlag3i!G|7sKzZesjg$qaEmG%jn%nTYgqbcz_`U$)pe{HZq~x>sT|~szpc`D_ZCXm3^zDV>NEk4zi+tlv}OA z``_RG{_gbE=cix4y}SA2?dhxU#hYh8fA-`1H$S|&d-JcgB<-L7^6cjB?){tJ{d8CV z=U<+E@#WY5@Y&x#dnuz1qau4<*FlhqT47I?m&&XIop;o-!Kui8*Ov~YPakvDodQ1t zQg3yvq+)QacFa+;Q&CC9AgWQ3eXlDjsTf2xDzf!;MI{x3s76IPOIB1Kb3s(2BK12J zl~fF(8Wq_CdwQ|533ha485P+EyP}ec!Lb^*=rmbTGu&b?Z1pZNZmsNw9h`xhacsH8 ze%N)a8E)0CT|l*CZe>sG=vX!V4eHFU*mbNKZq?phK(!EZWoPW@SjnxKy|L?9Gu&c# zY&Dy)5OSrwCpuPgYi5URjg>93qp0MTDx}&LO%*l6t=h^9zm|oNYi$hG1W+-?(u`8` z>fE|~^EEIHqLN!PyJgoI$Z(7OvNcxcR_zegKLf@s_ROwh&2WpNA9XTvZn1B6aAnop zWV;5~IlGQE!!7pC)>xfe?4BJRt8t6+AB~mzpD3zvi!PNFHN!17(bfz&x7bEII96JY z2-Ue&J4bb|S1N&oYB8Z)DKe-$x8}*Y#eUk+88B|KqjvqZGTf@Uot6dE1Xa{bOvtv{ zY7}PIvz6YJ(HUS&IMcndjx`e#vbna#YS*)s>Y(UYjazK6t+BGhb`;glE%w;1sF`z% zMwXfZ=N9{H2ggdCkWiglY_%OlHEyxlcAbIDxn+)%Gd(9OYKB`hCsA)ZKeuR45}g4% zw`fpO$C^2}YHp|92k1XpQ8V1CxgDT7w`f8codM$(eJC|n8c{}3jaxJ;si+xlnH%Ly zKgx=lIk(t`TPw@CMIBLa2H1&PsD5tIm@I`JKMe7p1Q8~A0P#GPoaf=?6 zb*vd~u`9R6>Mg!5*8MSLYTxcn8PI z7T!X2Zn24X6xF!JHr{mxJ{l9YPa&VG#o+0;f2h9Z?|*gs=hLrWoj%?5kG_0$`n&IM z-hL;y^IzWHynpldJH6gd=TFvsKEjXpYDIzwYvJ3{`OK%KO53NNGz5uds<*^8H+DYr zT`35OHM;OsNs!101R=3N^@?bt#PWff7!7z_2Eba1R=35^>}Eb z#HtKJV#C+Vp+Q!Z#{^>#5*YwJ8yck6ST`iLdOZRfBsTisDD`L8o5aHBApJaAW8I@9 zd-xV~-uV<193|Pqhaf>F*i&P}_QT1ZosU4VQSuE)uYUM>cD?`wA;})T|LDU%#-4Wn z{ng+8Q{91o^W)98x9?9cKAq-O@~G%zbh%8$b*3gpSm%WSR^{GP8>}Efw~67EAnW8j z(k%!Hx=oC&1PQtYAwjo^ft4UZw;-gxteHzjRe}WFf{>uw#E|N|Fro@Vf^HMzDM5m6 zK}gVTVlX9099A(%hEfwFDM8|}Y9L!~+&5jRQOVuAQ+f5(sp+}0-1l6$bXu9Fc?!oQ z>PV0EZOglGdDme+$(S?m4z{`rS9cImQ*vF3wzvxycMuVa+tzmB+72ROZQIf=T-rfI zENxrag)2LVh?Q*%yKrI05V^2zT^FwFAR>+t-VV-%mxCZ8VldtegjnhJxPb=|^=H@h zxG@4N_5H6K5l6zt0IX~{5rSg`XEw%PYOs_TBRFHV35B%@!7+j}8}BaKni69KXExlf z&!xWgb^kKp%*NQO&;&8|)s%2kz^yS>kk0i;`8LJdLPX>h93wbG;kFPHoT-nqSI$th zEyM(8Xn;t;wh$AXsgJVF7>zU3Y6s^LoS{%#V?+!ULf>uOM&9)cHQB*2f-@9kYm5ob)JNCr7%9dUVuCZ2 zVpE7M!~|z3!#2~yLJf9s9>Ez)k`*S&f{5UZ<;V(iWI;r5#!_U3DY76UIAa;ILJ@Tg zkr^^ekQEB3gNWda<;M#1V?ji4#?oVj!s#HQ{_M&b%Z?R_rh|xx%`7=qD3}f+;+(PE zSfN-thzQPDYOF9d7DNPREHkz+GZsVyXDl(cFfkTH1ZSv@J}=CR#Sobnv$WX4v{(=k zoUyFf!mL;j5u7=gQeG&C4kGH$uAG@Dht@!qsy z=czf4c3m<^Tc~;tjuPaVsCm{X6HyxbDNYnT3o^kT%AF^wodubQ)2MY;lF$}Wf;|*E zPt-YUlnM6KOh@yJQ{;SJsBsSd;$#mM&Vo#^hx+D;@@7G5jrHzC6gN-QHVZPr9x9tB z3Y!I)NDI_-NBi^G*+Wrt?B}WZjs}vFW{onz9txV34(C#*oH;m3o;?&ZYm^E0)Rag2 z;ZUszGQl3|m?z4Z&kI$|!4D^Us9_dlf;~0s(SEp{J=8D9MoIbdMD?;pSy4Lk1Jo{0 zlr9T0!JeAbhQx7~s#f3!p@Mi76;WRl)wso!c16u_i%IP= zGp$`wGu&cgTd2-0=C-3VVBBJQyN)%(t$IASdlpmNLS>FSI#%Nr)7%v`!!0JdHLuPs z=DIHt@zeV&lifmfZZY2-MKx}@56Q}$cNEpQ#k6;wS8}Vah`fc~uA z2bdDCs64k~s7#8NnQ8Hg%5y7-YTROKyrS~l3Zfdfm>#dF8E(~Tqjp}IBCn_!Zq;fd zpn6QmJb7?s)oLT4`nknic@)*S#dLX{f%^OOa;sJwVXPJts&z~T)wsp9xe|BGn@49r zABeHqxwSEO9z0{2JTEiT=XI>)R^1n$J`2oPWM&GzqLN!dRO1%Y=oOXR3Zjx*g_-n< zN^S*F$*sayd3ZA`HT=hciwWQ}Yqi&^$4 zs&R{X_BsO@ZZXqd3RCSBHN!0?+lA`fx_omlx0r7is^v1a%kJNeYTRPZT{FO>d-T^b zZZYj%Q8V0P;$1V~=N41%!Lc&;E>yd3ZOpz$Q5h4;!_HX11bh^g=a$^N95r)pF$rJf z1>~q1ZZQupREr5WX5ynWVCNQd@pWa@9krJQ%*Jc1&MoHSqhmF0F(a?BG9@2HHEuB} zUr{sMVp?7^;M`(jJ~&op=7s9qVs1W)YTROWzRo};iv&@P zTW&0}nXyO&_58w&MT#4XY-TJHM749vjYT#y773ynw^;V7(~xzqp>sVV&W&p3xdS72O%-*6N3doV$Oq**v=+K z3g?A^LJ(44cHPS+h6#d11RjLMMkce6HlhL8VFKr?B9iKNj9qjS}rZuBI#egdw+ZS{M`>fe*fm??cM2{KiuAae=6%| zr{_06d{R`!9j=jIb~8 zav3cfWJP)Wv4fDaR@aNH=HSA&5OOXv8LW7WG4^v)(Ot6Ou zFL@{P=V7`lHcDo@WSne}3HDHjD%WI#Ot6P}E?FiUWP&}6R^^v$kO}rMT9sL{LDpZS zlRZ_7)T~R3R(D3L!C#zbk43AO?l|3})W5kMrJX&DR)eD?dn{Vr8Lb8(dG=Vex-(jh zK{8rhEn3}~%?d*D?6GKdXS5oGdt622+7EeSu9=K66~QluI!M>9%itDqa=Hn zztSiZXAf<0WrS>_Oq@McXVkEVnXB{8#8vRa$sVSy1erK{s=}xprJX%YS%pTaCN_k$ zvxoVrASBttY?VH||Ljrw8jjM=9%ib7qa=Hnr_w0<*`vla7$uWbf~*7UJA2f%hLCpe zVS+07;XHeop3*4$*`t0n9HpH-w6O|~lI$@btDQbpK}fR4jI4GVS;ZjD$jY3ob~;%F zA;})Ivf6276@(;v%*$%0msJpw>|uq_d1rx85R&X+d5|D0N+)}&VyM|KSsNtC{|sgJd1pmX5R&X+J&+)^#(IAqRs*U2i|06NfnuYi zrAD%dSSoot-FOHIBKf#}e>|xQ*d1uW}5R&X+#g8Bp>|wo+D!lB&wZ?jXak^Wr zto6|-6YQz^koFfh_OQ+;Hkb6bQel^Uc!E7NxKdS@K_=KkhbvjW8)Sk#G=g7Q+@qf- z!5$jHtC)+UWMNP6=OKGo)+4w2{(F!5$zTz&rbmzo_OPNyHC*=L3HH={NVC*g&7)B! z*i-W%Eu^uBl{~SZhlM;U-Lel)u!mJVs@pQi1bbM*qoOT?Ot7csLz=l{`Hp^`1bbM# zqjD{b^3rCecMGohkamNH&r|au*PlnlSq7P44?V9`nPrd(_SAexJ4&+WV2Ms_+o0!_YO-vU3HH$Q zN(EVjWN}V#lwgmlu?#Z79(rD>6w4qJ>|s@o>aYwl!5(T2RD@-a3HDHHpb9L5Ot6QZ zS1P|U$OL;>iKE&pgG{i8WjHFlGRVZ)!x|h_T^VG8J@mX%$rT}4eiLI)&4)DGhG`9s zgw{Z&8H6@lsukJl zgPB?b)l%^nXI)Kf+o0A!g;WNaID4oy*i371u%ae7N=9y`H8`k@4MOV6nqSGCu?xcmZ$St8Ym}@?yg|xFLp*5JP zHP}pRa3r(_GYe-_Dn<4rv<5TV@v2VBAQO>W^*3qe(zFIgLTfNnYoH1#8)aRJof+$z z4{1kfky}D*FjH%w+9(@kB66eFK!s6+OlS?{Zov;X_9V0hGqnaPiLz1l-+Sb1!BN`T zlh7K-)Pj)4o`lvwjuwP8_9V0hvaDkNCEd2KUo15>Sy%ckw-Yh4+5szl!4~u9t3;(M{)b78(dH3xfZ|_cj zxV?FO`u66>)1SV5fBSEzznNZqQs&d2)jj;YhRf|Qb`IBs0~7L>%g;4~QLERU3INnr z7S}pn>MmEGZa^HYywY7RKHY#gRvD6Bu07p=I8=G0UM@Y|fH+(jj$W=j-GB^7aqqfZ zczOZ(0L)PIa^2|$L@3HY^m5th2E;Xvm$=JSryCGqsJ;ANZaUqFq>6Ec28=QC@!{9r zeJ}T%?lFQa_UwDP=5!;1E%xerx#e^tf-d&xd%5IvBZ4nhUw*mc^dj=j*PeVYSDbD{ zFvebdFE^ZSL{P?x%L^ZTW9yL*zV_ZLr@b~o-XON8-PPIR?%k=p`s(!A>zg0%Zr`7t zPrq1Xe(}w#pFRKP^RGTpXRj%2ZJ{39V6){j3-g)!)29!qqonw zFq;`f1e>jJsxX-uL{wRnD&RA_!Ve6wHBF-5rjVdgS3L=6tRvA@T85KkX zXRI))urMl!2+mktRAF6I43TwFRu)y*<|v2=&RA7cVO3NR5u9OvqjO0C+3L=6tRuWa%)+mSw&R9iMVN0VRA~<6OQH2FjK}2xI>Y*04G72JsGwfreR_j_@ zz0n@ap{yEeVGESPB({#L+WZW_)30JP4^jYuIC{@r9}JASBsi zrBDl-4h12}9xH`fSPB({M94N-Db&JJs30WSW45acOQC|0WRI0XEi8o!LXtgJ3bn8l zDhA0?sL4v97M4NTq|gu?Z?wE2#N(FP`uSw z(2COwiX|dYyw_JyZA9Im`nu~DTM8d6Dkwsf;OFbl0E$=p3aT~NJyLA58YxsR6;x}k z8x$L@K%sQ0pjvbPE@(@<(O+O<&Hv~x@Ij@=K({XYr_^D(6ktbQEzlkP1@47^vAJZ; z|7wBm=r7PUm)LG;9N52W*XX^8rmQv-aJNsfe%ZaI@;J=Qb#-b3p~zc zB61u31@5;E)6yo0{(O=-hTvAjUn@fsnM}L9GxlBZEqrbrYp=+YrgQD8ty5!koqT114peGm{ z{RQsV<>)VP|7duO{sI@{#n?_X`U~8%XMxc8e2o4AJ&OoBx6xnVLzp%C3&a=E=r3?D zU)W4*a3r(_qrbqzT$#}{S+;c0A4QlThcH2o zASPsN!bBmZFp-fCVnW9zOw>^d6GFBiCdw!$^}w?EL{=?`2_>5_QAMe7)@$5j4QUV) zaspxEZX--&rGuEz69^MEl)^*_We`)}c71^nCOlK6+l2pPgZW>^5gBV@{>>@i(j=sB z_JxSqH=}?;qk!g{e*TwdH+OgM-~8^UyV^hEFVDXC^6P*2?C+nw6e8x{d;$u60)mK` zdCO=PW;BC{$Y@$Zv#@w7h=@z2nFJJ?1jG<&5?~$yg&qMxME%)y1)D`cp+!It5&M=o z1gISRBfCM%h*79K3YG7}t<@ZP_ED%DPe@FBJY3C@XQv}iDBC)XLgh=gb+vPLrz1~r zE^*F|Lgj~~`zTcI z2w>Qpe6{A}`zTb7&*jYK*uqx zpHC1{e|EjwuXM~)*(#D#K}aM?)={YZa6*nk<&K?*&B<3f}>H9oJ*wVSL^Y!v&T;mQh(N* zJ=WxBXOo{GB-vwKes*^G2|_Y!U~PVOw)u%cvdzzGeSY>)sN8W-)aQq05sgCShy9Z6 zeuC?g?6H17JNx|vA;}(V__L2f<&LGk;AMWbrawEI{=|NsQK)=>LXJY^`)%W(vL&{N zMxpX$5sgCS4~lR~T7ruRXU`~9ew<6l!eVnd3YG5(Y2AMgcK->^CGI_=Q2E2U9EHjq zky{m0UoR<}b^kfo{U^3ADe2oxYj7mA1~WB%n~C}kiu!`1BzsKNcTm+Agw&t4a|t=+ zc@!%5yiwGANIRE&?>Q*#i~T&KQ2GAs8HLIZH;PfH+;LEhLgjn*j6&rH_SC!eRhu8% zf@>e-W>;TO5OY4(ep_c1fe;e)FoHxqOlXv<0U@NFJ!}8HMF(WW z`bDik`}*BaZ(rZOzWl?_Uf=w9R|}c%|F3Ue{p|F7{p72gZ~v(O^3CU8ee&YPR>FnN zWuwHtaPL%q&-T}^A>C7D%|gVlUl@3lg1{q)`2Vr@w!L;8SCZymIbeN}0g*oYJ-09z zK$bj^fwCo7?va72`fyENTZH){P*j&|jQZ~rc}U)qPmt1GxyG*PcI^flu&z#pa%X1b z%gR_QaPY7@?=&fM8t zk8i#^egF8??Z2P?X*fTe#?xO;=SSP};Nu71y?Xlm>FcNev*zjl%a5n+*Iv1D*fyyu zSidd`b)~(3ld7F^1vI{~P(%wY-5RtARu-q+o1TE9s~s0Y=0UM zQVIfsYqmWNb)MZtEMkB)vEVw&#;?qWY;zhwv|tPMRo508&#FAVyMQ7A74^_%_Cc7h^NS!a+o^*`mS| zqryQ%u-OvOCMKW-5y585Kbx3;7DNP_E&XhwPi7DiY_^E-#L|^9#JZ_p*9UXSoamAn zL@dXKIAG zm)Et(T{C;^)L3w847O1}yCN35X%)?_?lyummSi^34KvtAaK_9qCz@df5y6>aafzb2 z)&14rOtHWOGt7c*1ZOP4Y+{005D}cQ{IZGpWidn=VHVqG_6l-$zYHRRGsQTwCpc4I z1ezIcoT(A!?l$UEu85XfHZiv>_|@RdZuglQVeW1tIJ4V6vnS4G^+llhYU4~5Qgycx zoUy#Jxki|~5y6?A(TTarsJaos85T_5W)@72jWr7bX780Ks5)VR>Jr)z6850jel06m_ zS23#o1-OPf+Tk(wFe)BwCD~(P@tI-q7^H>8EiOJYE*^v=dn_6Bzr6}J~J{N zgw)TP;jz&8%+PoclI*dRvY9DmK}fR4Qp#qglm#Kl9!n{knNk*nBzvq<{LD)6K}fR4 zO2yACUmJuZd#qOc%v$j=NY;uUtXTZaV(~#pvd5~$&rB%`LXtgJE`DaY_y)3l1v)ej zFP^+j-90o9bvL~CJ#MY9S=SYoC%uU$y%-=*dOYV{r1IB0QVN4y{+Hz}U*E+YBvUbH<5D(ge@@a(}S!I1%9>~J^na2G?g!<{jP zXS*OG7-L7fe>Ba*@4l_#^jB5-@TVYo)1B5pq@&&-9kR{Ow!P4x45YAy`f2vqd# zZznHRZZNxt9-xVH<(gbLd^jGx+&co6_u-g@GG^YRY{Wv_0w`X)5n|i`7TO zYsVgGDi1z6(o}AAu&Kj!2Yb?l9ZCI&9Vv*24e3Zzxy(oGLcxB-CUm5!)PDSj zNmDt5yT5vCaK{(BL%6GzyB@FZUAeb^X$H(b-eO zQ`fcU5bj=P56*b8HM~AMHvLFl$RXSf?}hcrvFS&9EjWa`QC`>Q#%n(w!rjX2L%18A zJ%@1j!6%1sSDZP7yWyRSZ$f+#Qa>X87CTe0XvHDieX9&Pgu8DF^2H{RJpu6rXgh?v zU46;N)I+%YrY_wf-0hh}HBI??G9OIcaR_(2`VzOC;Slb=CFCL8y;QT0?U3|>7*fLB z-~90U^!4jkPrr+nB%Ak|!rrU{l6AF`zOqu!U5}6Vy(9>e%9M$MZec>162!#o#GrCE z*3S9}dZ!_YVVa_QqNH2xtRvTp$#r$2rdybhr3BlFH+6kGUe$$JVS3xCZ)?Y$B~yh7 znOCr#JeW)@nkr1qweEK6KaFN~Hv=|;4yO-L_8}mtHBlEvxp~YGcU#SIG+14*!zPdeq z_VW36&z|1Aczycj+uPe`r)l~0^wG`phbqQBhLa7H430DCLS^(;sEn>>vU`v816@)V zOKC4mcM3w{1iDzhQ(?YS5E2K_#Uf*cDeXZ>9apX^#bPP#g(>YpNGv{!rL-5Ov`HZFr_^RiL>WoSx<#oPccYlJuQ~fUYPb2gd}?`GFG?*1tD>P zTP&r$Fr_^RN%mMudtpj@5R&Y%l=i}u_8=tLW0A4Kl=dJb*<&f~g(>YpNd2r~4?`eZ zVF)A$N%k-TB1qiaf{jPtt5LaBd0JUCkRRQ zSV~Tzb4(DD>@n+@LhG0yB-vx$F@@eSK}fR4%wr18V}g+SS;HPn%PDk^2||)RW*<{% z9}|S+-edkTh5j)i$dUdriy6oiX66JTx%ZfZOre8J5R&XM3zJ^aFY_(4dr#|q*X7Q_!i>SqmmtRjA?s*}!5cdS|CEhI~M6_&&g zwvz0z)SAMY_%TSUiEl;m^@P#?;Wb~p{cziRSQS6mO0vhw;umJu1R=>DtBYS)7e5F| z_E=&3!ov7LNV3N&;}=%O4?>bXmSIy^8b1iBpEV$#p1@eQCWRE4<6jsO&LXtgJBEPUi zeh`xE+3@76;n5uHUDazmq?zhgB)_moez2ALSqo_~H&)3HLXtgJCcm&ueh`xEu{!yM zb@F47tdqZ3q5Q%^`9Vms$13F)Cfo!e$({|GiLJ0yeh`xEv0C|sweo|IWRDfgFD#ZH zgd}?`>87w+eh`xEv2yu^$XJxh^B-vwGI6Jd&f{Y(?pEr{T1cMURO2lH3HGe4#kQ#$SppL5Sy_oqkeXw?AI>bC z)v|DQ)?tgyOKJ^P(;Dmvt-(mG!D?EAJ)t!iYdoYGanl;?39Z3c;~_01i>vMlt-)C1 zAuS~DJ$piHFjDBWn$}=XXbr|14{2Lz>`7=1MwZWCO>3|xv<4$hWmnT0>D=)w^&VUuqU(zBhxKb(;Dmvt-)C1A?=4lB);tlt-(mG!D?EA zJ)t!iYdoZFC1Y-TLTfNG3uiU0!Jg0>j5Qw8w9>Q&dqQh4)_6z@X?ssXYcR6v=W1Gm zJ)t!iYdoZFrLiZWH5h9=q=mG-C!sYMYdoZdD=?8Yq`7=1#u^W4A&or=t-)C1AuXh_C!sYMYdoZdH1;I41{1Xgt7#4Pgw|lH z@sPHa#-4=MV5;$u7Sh<0&>BoN9@0RX)?iO)4W=3oX(4UzNoWnG8V_k9jXepi!BpcR zEu^t0p*5IlJfwv*_9V0h7ju~w(%6&G8ceL>xti8sPiPG$Y7JJ?8te(J!9=aWx)^&B zT7!$pOxu^no`lxmVl&e~n$}=XXbmn#GcBaCC!saCWPP=e#-4=M;NmsYLK=G#T7!$( zObco3NoWl&ZZj>Uu_vK5m})$vg|xjVp*6UqezlNxa!Y6prWy}vA&or=t--}{riC>2 zB(w$-YkIDxHP{ncgNx@((@N7CTxuC~o-b9K0DWm%gG(ucZbNK35zK9ly(DIB<8g>6~5B9@(U$zBi>zpy(!n zVwI_&BIC91gP`arfug4b$}3_J6o*`aVx_5|2=6zbZU0|${a(L3O`m^t`t-@ocds=T z9}PdBl@9pL=Rf=Co6o*_D36sPoa{GkJmT32Z{i8B-V*Q2^%EjacqS&Dc)$xHs!OiC zH7)5;qCH&PkB2)u+f6*%#YTo_J3HD96D1R8iXW!tPs^qacB?{0fJnK_P6hEAAR=n#UG#k>4#T0e|UBqf9+YR zn>N|><(crhuc!m=f9+W*n>J#oe0jT51rb3Ex`D61+T8pOYmGtz{^6;yh$A8xUsPCoc^E!1fh;nRGV^36L>*E3pq8i%@ zzo{5{J5E7F>{fhj-zGk`2NA(ZKD7%GoD3p@lYD32CO)$V5y445vI`NM3?hP)ro*17 z!;T?Rhix+Ki6!5Hi2APU?ZZ^q6Dz(25%seMkvF7?1>b^*T5GO|romQm;{F*<4YouAP1Iip5y2TN^)^v{9Yh3YtkT;=^>qkw zqx#y!*AvCpK}2xI>byM;IeiRhTqClb86DST7QBY$P^;ZJTFp2^!wbU3z z30APBl-CQ?7)2FU6x0|+A(lQr!>Ib-Zn;m5y+D7IQSH+E^vS$Om)rGH=HU9@l#>_& zzQfu7qm?T6t+zr2jfDytS5)#ihzcGH6+Et}BytcHL>4NDTv5s7AS#$FR4`en6!~Au z83g)O|8a~Ks9aIWy6FZ{aoQ0o*j!P$K?YGl zXQ5()tf=I35EXn@K+3sAp;&MZP$?!<=N83cQB>m=^Nj_fmT`-kv5K1E783x} z1I{g`07QF0AJ}q>1qanuRve6?8n;+;u%eP%wLk7(2UvAbJ>cA8-N8#`lK`r5iSrxuS&^`!X1K+ggbMmQw^)@h*aJ0Uhqn5@ z#lnP9RO1#)6V@KcaH~e{+P1PfVMWbwt48mD>iZTe6h?c%xWyWUwXGR$)hHg?>SsdM zDU7z&xW!6^!&!yw5{#|UJhau$gsNqiK{al%USVx3xmA1l{vC!D3-$bE+)_n5v^9uo z++x+j+E(scK~&=w3l~;Yaw~{RZmAkWD+;No-s+)_aXN9Dd1L?yRWlfh9d&UJ?g zqLN!G%iySW_3uU{w^W(IP+7<@czUamp@v&3&fuuzRU> z)C{*MVp9(|w=O$X_Z%>8QOKsYQppzW0pk|6Y!x-bEtWb|4>-4|XA8EKf;OQ#ww7sdFH+Z&Aggw)(zhLY~;F z&H9Hzb#9rMCx~j?qMk=RV1k|?s&R{&o{E~`77HP&2b^0b?1{CN${wLQw@lmMQm>9+&CPq=1SRsX3VeXdQASTvFVdCr|-&urugP8iZX52?c zqlAgYF^H+30TXMZFmddNVKNe>Z^z0gOwG04{$w0Vm^gC?6U$<-omdrxiPO9=6Fg!J zO4ZAZM+`v)+i5&v1WN5p@QC&rYNzq&vSD}5c}AavX*^=^DfsQiBgUSz6ef5?hYht8 zQC(psc*MAqFpWnHJH@`8Q72&<3>(|E){Q?Q-JBgUDu{U>-tuMM@+c*G!6u$}r@ zyB{&eq;@9uBSx6iPU8^+OtE${drX+dBZilPn8qVUm-Ouk9x=m9iMh5PF|-tHr|n0K zEUBG|{fKcTwbS+^hLwWtv~wM!N@{0?>D=QOQ&KzaT*r`7u$^|UV??Pe3@8OL^|O{o zj3)^*!6QbK^zFtY3ntYS<^GEYgGmB4B3Udc2x?4XEJHcVoQpG z8kZPJ5-7M71+`6yfh2)qQ;LEbn;1tDDA*JQwQY%Eq_S8PDLDGZCq|J3it}BxrA8{KSMk1 zuEgA-7-pTuz_h)IsY5|bBN8)*^z9iU)qn~bYC#9f915*?mc=tz7LQsACIuS;}i3D z)Y8n>#Pl7Fz7fi@cVaE2S%*OFuxH6TK~Q59lXvv_*qVZ)&kD~f!ejR)OWg^!)HWxk z?x>~MoT4o?Mlo|opczKh@JhQ%F>yzr8AdU0M}2Dhlcnth`_vf4w4LHvJ3&xm6ti{& znqd@^cJ%qiD9hQ2wY0`qFi^%QOW6s68l#x9qtDMUszzDbmNH{UpqV|YhFJh=dz9tt z1V7&x#e5yL6pX4&xcBmSaW+LmEvCn0ogk*|P|VdSmZ}rPG&(U;N0_)f1u^wAe7l|Z zEKMgiNKDfiEKNrZ#nma+P$uaJ)5ydeogk)hi77g2C%6>EG%7JcN0^{e5Yw2n8S9l!BU-!n*Ujs`bCkTnaOPwJTC>9zjH0JXn@Qh`4tI5pnNem}5IEufm*Re1p*q^<#oFhvn5_d39J`$+-GyeCJ}2 z%VJzJV_dQIkuk2pVq7z0TtP@|G=s&sX2!UJkl1Ms%d2-5E{t&n`w}rOB^n_hH8aK) zgJg{Bu)Mk(p2RV&DnqV^s>AZ?U0*U=BRDS+AwDdx?)oxuT&qfuc3v`;HZxHpHawoF z0iDD)GfyK3N%k;JLy(DE4oiYauFv(7SsKAs;+iAjvOy;9IaUAB3=eZOw!`wO=al6M z8hFZ8UnbbY>K{4FtK${ucm;a;;>p`Zd}8hW*urzX0v)eFZ{qkA%f@EU@d|Xj0v)eF zeGwa~VX1}H+gIYGcf0~U_=Ngby$sX^>`p!uTg{GFpa-8EuRxkh$1BkB3Z!&`zdpEm z{rc6@Km72z?s0#8@S87x`|D5t`N1dC#`5!2w`%qzVhS~h_HfhVw+iSK8T2L+)lmb%v$q7M8vXLXkKlETr-BqGV?4lFT@JcxzE&; z;iexgn85n-!8Rfkcf0~Ue*27=piRvaz7Eb{O6QqM=iumoH-jmiXDXe8kRXnnDHtz2 zUV%EEP+32IVBxM!c?A6ox58bl+a<{36)66~T{D9lLb7I;0{At#X8 zYEvpVw=>r1ia~mvE@s)xEYlT)Bzst;>v#ova{J(upS(4(7%z*dD03%qYhoeZBNwQ~ zE{<0q-O#l)-k*iQ>M2Jq&}H@{u1v=((D4d%yaFAsK=-e>wb<l_~Jpt6>ve)@|Cjro+c8kXSe$uR!tn zQ_IC(SMehk=v^f4cm+CMf$l$(n|TYpTl7|y2nd*W3$0rOnb5c$uRw2}8ID(=w{QDL zE>OqfcH{!ReWd%xeFYl-^}*@O&rjEspkKUvb$j~k<@4{JJ-vDH`t;4Wx3|wu)AH%* zqnqasWm`G^ENl`u&@fHDczB;H^h>MnIQMNkl0ZPRBwIX#gz6#)shjKd94J>jgM{iL z2#M@Lnc^8_MY+2x2O)7#1j`&T@qkYbSe{d%IZfZDHn3oR9yri z$sSW(6sj&_kW^hPG)Ge_6YOE`tvv8JiI{sEY$e%4Yc#bo!5&(p$pOz=nP5*XJJw7h z8l$O|^;Ow5LXti7 zL=z+)vtp3+M3eO$hliGEK}haBG(=M?k+~j(BztIwCddSPYJK%)#A${m$OL<80kRg- z_8wZH1wWi8HyWX-l?nFL;_7WHjXktM3${`}Yaxw2G(ihOl0CFQ+vFMCzY^8_leU#q z{K@LH8&WRggf#Zh{w(z2G8reN?L9O<3qq1Tv_4Z`_OnM8<7g$F&ji`e9yyE?(%3_- zUhu=o9uw=y2qQ7#WDjl6^x>LgojauL#rfgJ9=e_dKb-8L>DgAO*9$_DJ&Uo2o@X)0 znuXF3axwPM@+=5R_R#T6AKt(B$XT4Nw5S37&VsEZdsaKS(d{e1hR|K1}*akkR-9=e+aTS@lN+f1!Y>^-dHEgw4`S?O#RY$e%4Uo*9`qI9yS z#zUGBr>mJD6YOCbhsEkR6xMMFez<^@(pGEn-dkvS2I8o??3s-OFN-G%s6< zv4`GeK}fR4ihCCp_YOjmJ#;SH3Z2V>kYo>y%LJLY_pq>o4C=TNv9d$3m1K{Vb|@_E z5QHRqthPg8ZHFMFe%4I&oqNy4TfCP&l=aD*4t=?^xT7x~IHIVZ+A?@Ur&>D<29@4hb*ptv2j5Qw8Lh|0TC$t75wFawc4fcfAV5HVy zHLby(&>D=a^SzqZU{7cbMrsXK(;8gd!Fx9fY7JJ?8te(J!APyaYFdN6-mSY^N%l;9 zE!`7Z137(TUQWiIgw{Yt--I;wB(w%&jfXVsF|EO#&>D=?8my)@*b`cVvBpE%R@%KM zp*0w5Jfwx>d(WQG8jRE$tfn>C6Iz3jT7z|F)L>6&4aOP|X+GSv275wlFj8x<&c>dE z)?lphkhYb^o`lw5tnrW*(%6&G8jRE$th4Ps39Z3It-(6m$t|HZn5Z>aXJb!7YcSP# zNZXgjo`lw5qSjzFt-+qq8cft0tX3CjPiPG$)&*KkYp^G@22+iPG<|7WgFT@&n5Z>a z7h_LCYcSP#NZU$dPeN-j(IH|rt-+qq8cft0tfn>C6Iz3*#zWcaO>3|xv<4Hk2J33+-f7bQe7#R<^4*(*CPa+BU3w>8dV`2Kw%eU| z;+;2$h;xTsc_&_ZgNQh^+l_bPjW>vhb<@Q46ED0$L|l07zB}>08$;xM*RH!0ue(7+ z963x`Kk>F3MAXl&tC0!oCth}gh&XWAT~|q<{hZ-l*RHw~ue!lDf-`p0op{p?B7!q^ z(VckF4I+XwGf(Oh@3}!laKA;gWhT)X5>yyONE!5O>bPQ2p= z5%sexXG~5%@rv6Z9{ZT)@Q)gttPI{B`&ccEcI;yhK4}>A6SId=+hZTQ%pR@xz2{R# zY>$1c_T#aSfrafp_Vsr+kL!KwvzIUa`1DUdyt?_rv)l0fYCAKaq6-yHIm1~O?sf`m zC%^ZKB~To51d5nS1+6%Da{eGFPC5cbRHcH}b*dATVHJTQre8sImhJ|{c}Jj#tW;24 zLAyb5TXcn6m0UPCw9^T@>KkvgC5E0iNd1S#xw#@QMYO)RgpSQ{dlkXLBR>nQJ3&Nn#@gqyVx6P)2*&7E3^3C{2(gxj{=ygrOw5eLhxoS9h}gal~@%dDKMlCbxbd$=aNsR?bFl`}Id zgTsScjY3dJb)K178G~eI#KC@v2bwBp=FpM#*{==Js>%`o0WDky@xK~SvW0`-Sj#;O|7v@y{dl~Y${`&x4fSK< ziezbI*ldM}y*4;9;LP!6T4(t2W*YU6KHf|e&UIvX7CoHi;~vF_)BJ-^tTOGy%Cxchc)Xb&PV=|l*IlP3r(N&X z!P$d-=6Ex`^dkZvv3@+>OuziigHH~p`FC;aK>KZy(EgyL8sxP?2m3!N7*0gZuKgDugXD> zHHt=Fcip4xPn|tS*`MI-kw^x!$0FUKvOli<8K${I`!f#=g3RX0Q>Ywo6cs;OI7N^+ zi7uubFI0{PA#oC2OgUbt91lW*xr=%76ngRmA(5oCm?ux6Cr=O(FT0C*@)UaV1R)VV zTueD$7zGJJLP52da=cJE9)qNEd@<#Cp>n)|Y|nV(`St0G-+g}i>W62~ZvW%7KU${e z&rjbxeR3Ps#_81#lB>b&f9Hgb;?f=0J!7!s^Er`xe(8<|(n|8qiR|;jlDvbZpU;W( z^TLw6gJ~(|gqEUEOEFji`kW9`6jqQKOieK-GSCa_#|)N&J||Mp3rq42mV-Vga?lHN z&<9IGpA&+L!X)&8g=4lkk%eAZl6SB)^f{4+UYLeHSRVSE$U`sGR1B7gJ|_~<3lq@? z%S4|OndpVW-+{Vc4Nt!msZjPin66?@=qd_z6@v*Y=7g}KP*^cg@w?3w{5BDUA3gOb z-CQqu%@Rz#uOKVRorpFF$-ReaUqSZ2d6g=pZ(GSD=bR8%6pAYbQ&-Fs`UXE7$Gw3% zUwya^McsX=GeYy>mXkgwa?(pJ*4#o;$TugF(hCI^gJq@9wEqqEC60STfnt7}Y5yC9 z#Bpyh``?-NzcEPK{|+Xym=hw4LXpK__P=u?Grce~eK7mqIgy%Pn3_IVZu*?aO)s?n z9V|J0ru}blc*q{J|D9?78-yf#%>Gvw(SDBCy3GwC&Hh&x(F7#fV`2+kL=%u?kJEDSXSA;F%}lGK+(l6s-wVl?~Th4#O}R_bTXBr^Noh4#NeNV3Q5e;3;S1|i8F zv;SRa{~LrPd(8fKq5W?VlI$`2-=*HIdylL&9?}jEPi_nCe}k zq`uJpH`dA;4{1LfS&rLM@7BG2S>qusB=0>-LU2(ixEM`vu_Oc+rN%>=R+`{qNeC`V zjfb?5%wJk){~H`0vd8Ry7ux>@A<3SR*%%A$e}j-@j|nc8gy5pk{&%z_^(B#{UYMjl zT9W!g``_4y)Bblf``?B3zd=Z{#{?J4j|wh+B3wcrq|uC!78)T1TS@kq6VgH_q#z{O zV-^w%t&oC{WRH0vE%ZVPLXtgZhP2QODF{jSm@HzUi$oBTdym;6Ewn?5LDCLsG(V(; zen>$`?mcFRw9pVK2ub#slf*(tq#&ez)~xDgiL}rXDF{jSm?zRgPoy9u*<zuq3nwI}6>9rZrd+T7#WhgVD4GOG0a~Q)@7q)?i6!4R&e`M$;NB39Z3S zt-)wogC(Ig*r_!bO>3|uv<5r12BT>WmW0+|r`BLJt-+Ge8tl{>jHWeM5?X_uT7%KF z21`O~uv2R=n$}=RXbpC14Mx)%ED5c_POZUcT7xB_HQ1>&7)@)iB(w%QwFaYU4VHw~ zV5in#G_Aps&>HO28jPkjSQ1);omzv@v<6E;Yp~aNNOLAKt-+Ge8tl{>j8@2DNoWmr zY7Iuy8Y~H|!CvDb&4-)TU`c2Vc9y>%O>3|uv<5r12BQ_gUlLk_omzv@v<6E;Yp~aN zNZXedu})|W_8JdqAyJ!eTM}A>omzv@v<6E;Yp_#mFq+n2NoWmrY7Iuy8Y~H|!A`Bg zXj+3Mp*7g4H5g56uq3nwdyR)QBW_xQC80IgYdoZdwAa#v)?laBU^K14n$Q~TH6GHo zlI&R%T7$jDLt03(XH94gc4`eq(;BP^t-)U7A#E%9-m@mO20POlM$;Os39Z4-w1&yF z25UlVu-ACV^}{FA8mtMe!OnvClW7gsgw|lE)?l)2bUgIGx zq_HQVHP~xBq=hv0B(w%QwFZ-E4c3I#U}r)6$+QM*LTj*7YcQGCU`=QZ_8Jdq`qH!p zYeH+V*LX+^$@KI!p*7fRJfwx>Yw4QM8tg3YFqzh1O=u1F8V_k(Y3xa84R&e`roq^g z&>HMD9@4hb*ptv2?9>`erZrd-T7#WhgK4n6C!saisWq4eY7N$e)?laBU^1=2n$Q~T z)EZ2tHCPi`gPmG~X*BjEv<7>PhcuJOv<7QJYp~aNNDFD~NoWmr7I&CTYp^D?20OI| zlW7gsgw|lE)?hNN!J5z-?9>`erZrd-T7#X%9VXKntO>2bPOZUYT7xyAHP~xBq?tsf zHCPi`gT2N>T1aD0LTj+sct{J$d(WEC8tgS5(n1=05?X`3#zR_2+j|mPgT2N>T1eY_ z5?X_uS_75IM=_i=p*7fRJfv-CX${td)?lykkQUNT zZV9cy&O!{6X${td)?lykkhYb^o`lw5uknx;(%6&G8tgS5(n1=05?X`3#zR_2V^6=< zKxHnG9XFZQVC~l$2$JkEt-;!_H4r4(V_Ji?Uuz&pvd6RrYrob&kYtZ(4c30Gfgri} znATwJ*BS_t>@lsu+OIVbB-vwHgSB64AV{*uv<7Rx)R8L6SYDHCX$#27)AeOlz?AYYhZR_L$aS?bjLzlI$_9f!UdKheAG2-k*BZ=cY7NZAOpuymefd3tBzsJ2 zU>0V<4<~y}YhVUuK}fR4v<7Rx)<7Rl_L$aS?bjLzlI$_9!P>7i5G2`ST7$J;YamFn z$Lboa{aOP-l08<}VC~l$%x7v1Ces?M{aOP-a_=#%!P>7i5G2`ST7yfG!(KvCYcQGC zVC~l$sFh@oX${tXt$`rP9@84E{aOP-l08<}VC~l$2$JkEt-;o>H4r4(V|5L-eyxEZ z$sVg~aH)0JJBg?@m`rQ1^=l30Gqnbj)iv1qwFZJDdrWI^F7^=l2( zO0Y)ux33qtk~$YL0b7f<0Q24N`Ng8xri%JSAkm)KbhQS_45KYA~DDVC&Z!2oihGY+8e@Uuz&puxB={!Pc)e5G2`ST7#`$YamFn$Lbnv z{aOP-l08<}VC&Z!2$JkEt-;o>H4r4(V|5L-eyxEZ$sW@hZ2ejTL6SXI*I?_{8i*}q zk7*6IeyxEZ$sW@hZ2ejTL6SYDHQ4&K27)AeOlz?9YYhZR_L$aS>(?3xlI$_9!Pc)e z5G2`ST7#`$YamFn$Lbnv{aOP-l0Bw1*!r~wf+TxPYq0fe4YVx{ga4VgW0qOs!y7LBzvr`fy#6yAjux9Yq0fe4b+!p zkJUBU`n3jvBzvr`fr>qKfA~PH!E9QCEul3Ss5O{PYp^A>2C`jjMHaJZ4Yq{VV4&7u zHm$*y&>9TX8qB6O*b-WUfm(yvv<6#3YcNo2Fq_suSz?JvME020U`uEX25Jpv(;93E zt$}P8F^NoTuqCtx1GNUTX$`i7)?lF4U^cD6me3ju)EdmDHP{kbgMnIu*|Y{*LTfNk zYcQMEU`uEX25Jpv(;DdUtbeLgYcQMEU`uEX25JrDlEDC3LTfNkYao{lgVgz^Gv+o> zYao{lgG}r_)EdYo!yt9O>1`#o26D+T$o_lJK&^pXG7Pf+-ZM~ZAeRh-?7#O6)EdYo z!yx-lZn9m(dTCmNEul3Ss5OvFhP5)W_fTsfmkdHCv<3sU26D+T$OL<+HIPe&K_=Kk zt$|!J3^KtUY7OL)VUP*-P-`HU41-Lthjk6)l3|bu_OPyjTrvzY!5(T2p#bNtr_r!PN04L`5{(e*i-rhbtP0OdJk8YknoODt9S=4lJmf2o=OqD?dHrk6d z-}M$zH}d-yM?q?Ry5{uAAi^MVXbD0hSSy1FgT$dF2#H{=3?d8?hn65Dj{Gu+Fi0F) zf{+N-${@lZapVs|>SxXH*faaZny-7rvBAn9g018;d$5(*VPz0ukl12lkbGvBL4-l# z$RC6xd+eG0V$IjvmwaZIL4>t3!5%)d%OJua6YSwLy9^=>vUcB{1zoT&$sT)VzgY8i zLy|rA%zm-v>xR_FH0-fw_KP)NHze6(&+LWI?7_Yyd+eG0V$IjvNpV@WLMyV!^GnOz1E z2ANvhtKRXh%m^+$&D%fGKet9#L0~* z{W6FkB%j%XlZfoGXZFHp_8=tLW6$h`&+H*cneAcOuxIwdXZ9c@Pj2?iUii!&gyi01 z&+LWI>_JHGJ@(9A_{<)JabN%q(?d*L&C5R&Y%XZDLVU+3aB@|j%*5nML-%pPkcpV?&)VUYcM&&X$X8AKRl z|K2n5nOz1E2HC&&jC^L7L4-lp?(5roMn1F4Ai^N~_nwi@>@tWj$o{=YW_w_dJ+oh| z`MN)x?6GI|!j%5tyd-<My_SiFf zVM>1xlI*c(_CouB7$l$BWe{N>-XC)t`OGeZ2!l-QJ$z=DL4-jj*u!Ub8AKRlf<1g@ zmqCO6bx-K_=M4lztgR5RxhV!FfscSW16kN`DZN?6H*o!j%3P zBvblj5MdvlU=LIJWe{PI3HC6hUj`8dnP3l7`ehJdkO}rMrGK%M{=$_0;PB|nnj3|s z^cSY|2O;%kEu^uBDg8l6{j7x~doI>|y_+sm`ehJ-;n|teA8aMrV=4VR?E_+vOzD?F zgtaok9;WomAi^LM>|sj(Vk!MQ?E``zj;MhQBCM4O_AsSi1`!5X8`gPpqkVu3A`CLI z_s~8-1`!6C*n4OnAcF`(GNnH_JlK0=5MhwI9d!34*dv1ogY17TmDygqY{($OAQSAN z)<6ak2ANOd(Jxu9eO>1zm=Ib4Cru46-HMm&wbwgtBkwJug zc!E7l>6bwSA(_%2V-HjMWe{PI3HC6hUj`8dnP3mK1~P~+$OL1zm=Ie$edrWI^vF7WB6eF%Dx7D-; z7i+$5NbWtRHMm&wbwhIRF|EPHny(j~1|ziwt7#1`)_mQq#CwknBCM4O z_Rv0HHLbzLnyBqC8pt5RAp7q<6SW31h%m_hy+>wyST;;+aIxm=?n|=Av<4SzzHUge$Fv3) zYrbwsvd6Rr7i+$5NV3PY1{Z6-Zb-7nv<4SzzHUge$Fv3)YrbAcY7Jx%!Fid`8pv#q z^U~Nu`+(5NO=f$9H1^OwAP7nJnAYH8&DY(RWRGbLF4lbAkYtZ(4KCJv-H>FDX$>yc zeBF>_k7*4q)_fm?Y*VL?l(T_h;3MVi>Eqk)AAGVER(1{1dtexNu`uwFa`x)!jS@;@ zeaSHJVqxGT<*chOv7j#&20l{Gy805wp~b?$N6J}GUos55SQz+7IqT|69ETPQ10N}8 zJ$=bA@R4%%?o7nWuCaamNICn}m%n-N$zoyPBjv1vkRvO*E*1tpQqH>i5?ArX!oWw$ zSx;Xw41A=Vz1t{Q*)_CL94TkNd$Unk82Csz>mek=z{`)tOYk(h@+0N!?Mg%!+1O!_T7x6y>~3Caj`hwWum<8NEg}Fv<64YS~3Br_8z*(uBJ6O zQqFqjCA9{tmABoGl(UX-3AG06k#hF-tez-uJJLmVJyOoz^<^SyhAy(}k#hE~FZ=hN z>8vwpb00ra&ffOrk#ZK_C?=M-U5}Krx08r2vZ2fKL>JlhNI84gmx+YUBjxN(#QGmN zywzG5#p3KJa>|5GqPzRaDf*3Zk;CsZf#U zT2WCRD~gItSD_-+wW4C-iJ~IeRj9~zt*AKnMp2RPI!!EaT2VFiK0IIBG|jJHKK}FV z>(jTlH&0HFZ@xQy|M=DIzn}hTI6s`m(_h4+ZHaPdTC0o3b*x$SZaSkqDv@!o51;^% zfy;`Km*eX71A~A_*J8cM=?sPk0ZDLVTTf?@I|vAFgV@`|T9H9O&>EZ;ASfLK1fxM` z0fNmjK-P%_lLZJO2LZujkXV4=a1am_27d(z`UU~P6e|!pRr7`3nau)`Rv&Vz-V5D` z;EI)pyqrzD5kVHK4mmL`IM|P1i)95*m!#+n}8xfqbvXE1?T=*bjyW1Up?(h4MgXLC; zPluJZSL@n--3s`P-_;gT7AcE!gCNk0TFW5$~+^X;$e(q6k>dWE%dg8MReA5h; z$3}(~_^be*oT>X~56%9p{@%pI%U~P98G8$vYH9oHN)$u{XRP|(G$%Mir#~ycH__-X z*hX;1k}eNF_b6xn7Jly2`St0G-+g}i>W62~ZvW#n?2o4B&rjbxeR3PUtj*Ji;an{h zW2gI1J%r!4@(U6toz>ibcDnz>AnE?In)}aQr3Y881tD=eSk3)sXDUVzQVhB-gR8m! z>;>y!5K=#DAkF<}ubXW5hvPQAn)}aQr3c-RSP54K&9lI&ruOpv%&2O-HG2Fe6kSLwUUObn7?vXxOXK~|JrNV10^GC|_15Nsvc z!}ypW6YQb;kK&;S%nETI8_n#mn*<+~~JKcYRkYvw}c(eL4!Jc|TYF45h zF{yH{)o!~d5!plcA3-MAQ_o0kD-o9xWP&|(|5@q&Bgi@;o$R6e&r0_nK_=M4RE(AG zKY~oKhjHAE?mvP|>^+R+Zgl?3!6=Z@v4DN1>?g}!&9=iW*4DSju!Jb;0qM4VB?+P-(9;RY!4DgmS1H3Wz(EVp) zgjbLW_R#%jV~AIf3HC6=yD`Qq$OL;B@%DLXHdw0l3HH=@NZXfo@2O=D zdO1$_pN;N6YGr~wOvTukiXq4Zd+7eN@$Es73HI>qVdLY2AQSB2^(Ie(o7=0KL|3x9=<8+fe)h~Y9@2g|6fJ`6XV1*Cj~mNA3bLO)GgC1(reX-PpFMMphcq8f_a8y_vuCdH zkQUPRo_e?LTrcMu4{0GSYEbXi-H<%FF%_en>)pB=lI)@Tk0ATmGgp0E`{B0t)VpS@R2r|JQy8mo+{}E(@J#_!s=>8+f1bdi@u`v}xkO}tGct|ti zbpH`#f;}}J(n1=0>fO3~5|KSD`&iCQ#R%;^GgC1(reX*(!JZlqX+PZ9Q}5QjA70}j zEhMy*YGr~wEc>{z?4uwP>|rX#w%Wai?mw~Nsqv8J!|DE`Rwmd};~_01)W?EMu!m(I zH>P3;GQpl24{2Lz?5TI_?ny-U(EX>J>)pB=l6w!e27*kmhgyS;S_45Q*h8(sMy-J$ z6YQz+kal?NY3xa84Q6KOY}6X4l?nDR zJ!hlVK#&Rc)Obky;r3dZ&>GA&9@0YEy(ghHm}@+wg|xjVp*5JPHQ1;%DCdOMV6O3y zww1=7gw|kY*~g7q1GO@7a--H@qt-x>3HH=@Nb}*;8VEA6_tbbu3u*VBgw|lL@sJkM z_MU{+V5Zh!Gp)gp&>GA&9@4gw>=_bTgPB@`Z6|w%gw|lD)?hQO!I01z%+wl4IfcjU zA)z&xsWp(C#2^#wq1Hgp_6C_?548q*cr?fad#E+gYm7lA_MRFKxz0<4s0}i)_fTt~ zxE&!AT7#Kd1BF}+GI4UF)$YcNx5P)utuB(w%IwFbqs217z?FjH$#OlvSC zv<5S^2F0`nLqcmXQ)^I6YcM3V1~at=#k2-PLTfNnYakO*vL~T6n5i|8iKsy)_8w{t zifIjogw|lD)}WZyU`S{UW@-(JX$^*i)?lXAKqjK>%Y@corq-aC)?i3z4Q6T$ifIjo zgw|lD)}WZyU`S{UW@-&&B5Hk^*n6loD5J3_p*5JPH7KSv7!q28nOcKlT7w~>HJGV2 zkcp`EW#Z&UtwAxZ!I01z%+wkb(;5s3t-)O5A$YcNx5AQMscWkPE(Q)^I6 zYcM3V1~at=#k2-PLTfNnYfwyUFeJ1FGqnaX5w*Td>^;;P6w?|E39Z3QtwAxZ!I01z z%+wkb(;5s3t-(yKK{2htkkA^;)EX3KJL({pxc5+NP)utuB(w$#wFbqs217z?uuyAI zX4`ubT7!jJgJN2PA)z%`s5L02H5d|FgN0fHnTV2*39Z3GtwC9A?@4G47HSO&EhaTD z`=bU6%RUy<8Vm`o!BTTCn!U%g217z?uuyAI7TbFgT7!jJgJN2PA)z%`s5L02H5d|F zgN0fHnTT>;CbR|%wFbqs217z?uuyAIOlvSCv<3^c2F0`nLqcn?P-{?Di@7DV21|{H zG*jKQ217z?uuyAIOlvSCv<3^c24yw&B(w$#wFYIim|H??uuyAIOlvSCv<3^c2F0`n zLqcn?P-`F)Q4%ttHCU)MD4Xp)39Z3GtwAxZ!I01zEYup5&DfLB8Z0#)(y+(0217z? zu&}N{F|EOn&>Ae%8WhtS3<<5lLajkDt-+Ac8Z6Wr6xKCR2(CYBuuyAISl2+1{SoVh zT7zO*gCU_cSg189tZSfF_P_Tm)EX4i8Vm`o!9uM;F|EOn&>Ae%8Wh$wP=vH!sk2aP zP*~SMkp1_bg<6Bcx(0&mfA3kSH7KSv7!q28g<6Bcx&~@xf<4q46w?|E39Z3GtwAxZ z!I01zEYunl(;5s3t-(UAL1A43^<{s|ZK2knu&#k16Zal!4T@SU4t>9 zHCU)MD5f2FFBQgN0gy-LwW{qOQS0t-)?ugOPP=>tp%7wVoDg4R+HSj0vs5Lao7WT7xlB z*I=R6U^lJ7n5b*8P;0Q8)?iH3HCU)M*iCCNCh8h2)EexjH5e0h4Hjw*cGDV+39Z3G zt$|EL$)1GPV4>DvH?6^#&>Ae%8tkSu7!z89g<6B%v<72BYp_sju$$IkOlS=jY7KVN z8jK08!9uOUZd!vep*2{jHP}sSFebDH3$+HjX${7N)?lI5U^lJ7n5b*8P;0Q8)?iF% z4Hjw*cGDV+39Z3Gt-)?ugE65sSg1AFO=~bFv<3^c2D@nu#)Q^jq1IqGt-+Yk8Z6Wr z?4~ss6Iz3XT7%uR24kYG!9uOUZd!vep*2{jHP}sSFebDH3$+HjX${7N)?lI5KqjKx z&JuME7HSQ4(;AEkt-(UA!ERcEF`+eBs5RJ4YcM9X1`D+YyJ-!^gw|l8)?hcS!I;n* zEYuq8rZpH7T7!jJgWa?SV?t}NP-`F)QO?UmU4w;MgWa?SV?t}NP;0Q8)?iF%4Hjw* zcGDV+39Z3Gt$|EL*_R2e!9uOUZd!vep*2{jHP}sSFebDHE42o@X${7N)?lU9U^lJ7 zn9v%m)EexjH5e0GgOyr?-LwW{LTj*6Yp|QvU`%KYR%#7)(;AEkt-(sI!ERcEF`+eB zsWsS5YcM9X1}n7&yJ-!^gw|lC)?hcS!I;n*tkfFprZpH7T7#8ZgWa?SV?t}NQfsiA z)?iF%4OVImcGDV+39Z3Ot-)?ugE65sSgAGGO=~bFv<54+2D@nu#)Q^jrPg3Kt-+Yk z8m!bB?4~ss6Iz3nT7%uR24g~Nuu^NVo7P}VXbo0s4R+HSj0vs5O0B_eT7xm6HCU-N z*iCCNCbR}CwFbLs4aS7lV5QbzH?6^#&>F1N8tkSu7!z89m0E+{v<72BYp_ylu$$Ik zOlS>OY7KVN8jK08!Ah;cZd!vep*2{kHP}sSFebDHE42o@X${7N)?lU9U^lJ7n9v%m z)EdYogUA1b)?lU9KrR^u+5cL)QfnZW41?@{EnTTKkV^(36Iz3nS_8Rc7-YZJV5QbT zE*S>duQgbyHIPe&LH6gCuGAXHCBq>5wFWD-26D+T$bO~HO09uhG7PdmLt&-XKrR^u z*{{@DsWp&GhCwFSL#=^aG7K`o9%>Ebk^#smp*2{kHIPe&K_=Kkt$|!J3^KtUY7OL) zVUP*-P-`HU41-Lthgt)$Il0oK+8^nZCRG3Dggy3MM;6Rwhp@iaKrQ$%CMxun|V5Q_hn8u=n=3u4fK$u3O zgy>+U=s=jpqlD^UrRqTCT8u{t*}+QLfiR6n3Eja;-GMNTM+xDA_0rfiR6n3GKm3?SU|jM+x!4O7Vd(jYkRf!AkXkFpWnE`N2y0fiR6n3H`xJ z{efx}8IKYIgp~pWVH%GT3IzEOwiyA!G#(`+2r?oxOyf~PgCHkD!!#ZxLaB@_uO6$xsm@hBllFqdax8jlj1gq4~ERim^0C?QH%DM}Eg@hG86SgA@7rtv5t zOIRsO5T@}cp-YfEA?K0_6U^~BcITonLG3giC6o#BC$x4Nj}p=Z85A0(@hG89kVBzi z8jlj<1ap2?e;SVx>I8WdvYjSRm=f{?nG_nP@hG8BkV~Oq8jlhJ1=$oDrtv7DP}rzY z7-X)&7)wH;AfrNSr|~GEQIJ!iVH%GTA_Z9$8m93mp;C}np zs8bkZv0>xhAMTc2A=_z6g(;y_kYAx;8jliE1sN6^rtv7DRghz$VH%GTVg*?i8m93m zp;nM*pM??S^g9wlT8GA}et<55Dluu-?5{xlvXgbT7S zw00Vg63T^*$_2I4c$APXY?Lkt(|DB7F37=<-)`cCDIs2vg`r^@j}q#Ijp~I##v9~& zqEy00`GPQQKT6a}kc**xyYVO?V33WWVH%GT)e_`mXqd*MM7abR85*YXC{Zs#PKJhQ zJW3Qykd>if8jlhc6E>Oc?ZcOe+dfdf2e=$Mq#w3sQ&}EpKYu%W(X+l@yFJ%d~h4bym(&@*hNXOK4s=VwCCu$i7g<{XBp zHM@7*P0t{A4#Q0F$n*@d=P*poweEJ>eq?%vIiY9ROwS;L4r^y(KQcXo96Ag$u^*Y9 zK^7gvOz0Ul(=!ZKRbfu(88*{13|3a*VvqR2asRjf{P?dAUfevteelVHufMx_eEaJ3 z(PuAT{PF3Zet32BhiA7xd+_mt?_NE9{`B?J|9SiUgHQhDuMciszkc=f4?n!F|M=Gj zzxndFzy9=}wI7-8g|kG#0GwLtmV4jsB}A;YoFhWS90?*~t>p|6B4$Vs5hoVT4}~jq z$GrA?5E1JvXNM3g$lWO*h=^5|b3=$YtHcngb)nKlh&ZVP5%sfc%~KZK5F*ysAR^BD zthXUVtga1W%ZTacGjLg@bgjs@Y|O^ym)f^^VsR5H~;FJ z&wqCMXnFY6&Er4oe|+=VR}ZCgojMpq6%92sYBARCI%xMZh#DGJ^AI998AJppsh<%d zI2l9)C#jwhA~+dD1SeU_L*YJfGKdIHQaK~UI(_aq8AJppshbgE1?fbjZiaO{ga}T? z+DO$5H8Vm4CxeLk*_Gu~%m@*j3?ky@K)s9*6P%%5hH4ohCOAX247D;sOmK!;87gIj znBWYRGStZ^oSondbuv`R2rCGOXSq#D310LWadVgxJp+)5lO9 zBg7x$OuLVL{qpgjZ(pCjy}fyIdVKTU>HEj8ZvXxCPs91)G@kx)IzQT$_&JX`Jh))! zZ3={|v*!Lyiq%39?GhmP76il|g{y@CLAM|vx2X0GAV9D!2#6gDmkPbbRgAld90bG$ zg`2qm!L=YD_9tA+1qiCe02$uGom_xmS`biQb=^yFAr~Ns76ioRgxk0P!LuMB_9n)( zgqWa;$Fw*T8PN*15nN$BOKnV$#qx7-3m0O7Ef&o(x-ga%{A$pJnK`-#Cir5JEF%o# zSg|%*9LpHPC{_>=jA0B*U!9H>zxn+1HkvU! zQl*X4(-+bGZC0hRc3qL}CpHjS4S^GNS-5YD6DBqgVS*LH1S^7=*h7Q~UdX?wcKF>k z62v4gMtgI-)F%5NX50VU`Sode{`~Zd+h?z%-7a;lrr&ir*S!x10ll#B{kTrn`}$p= z7)ya-EGsAmGYE>o6etF>f?_m-pcqYoVl?#_#NiBrVmJkggFywwN*4sh$v~i3>nbQt z2Qg4SA`2ADT?NGnAqa}~PM|m>RM3iZN0A^XP6-0VqE|sH)p|j(>M2BlV|4|^!q>F4 zCEgLPdM_x=gs&r9_23hQ2SEBt*83LH$r8PeaMh(BLG)NZGQsNzS6%uM+hwpHv0WbF zs@jkLFyX3WA3OH3%abxwmXBwb%W8=;YjCyH&zidxPOLf)9Q)WO!G6Te?|62(>^imU z?yftbe*Ew9>|%kar6UX_Pea_@Wlf8_yS%G#imw#D?-VagT-}9`=232=#A1{Q72uBc8-`2EqGO7Hf zuzq(t^=-gJ$WZM>#4y-S>>K)aL=1(A8&D7vHy~jmU?{J7gnt{%mLp&M^7qrWyo;5e zA4!bZu}DpY#u9@)PS1RtZg?uu;g84&i3}1R=RC(O5!|b)wy^3_(b)v^16wBo^8jq}6Po zv4kM8&Nh(7jfNQ0&_N8vfHCD1(6!f$OGS;ojuNO^dR>|XilwPWiMywrKr!tEinXbN zc27KkV&VxDi<3aPIyEEkqbq|zG4%wB6Hx{2o_qqu07q`YBkCeO{p0=PT%s zO~9Y{eCF~96o;Y;ik&{zr%dJ%D0cb^T5&!^=$0yP^+k`Rjg=nu`yXEX*|kQ)&*z8Z z`Jy!nOO4czI5Q}4jWa`S9d?7doZWW_6R1&>c|jEv`#})Ys7WD31qC&Ophit*231f{ zGYD$bWNMH=`}Gv+Q==vo6%`cJ47Sv$$zrD!6x57?QdOZT<<#sKR%k8P*R=~Xr4_ZM zpk}b8IE1UEPR)LKg<5KiqQIiIG{GoVJe7FaH#;VO1V7&x#q^Kb(gdTJBczu4X2%qe zU`vfrOaf6$nFSIAHAXQHq=F_G#WW#(zHfHS1&OtkxgY{{Mll^E2x^RCLP-7m1fy8_ zR4sKzF)5^J>9N^eGrhFh8#Ry3?&AkfUp#sGxTeI_l_^0@>Ib#jJ2j8Zt~rM`)clDP z^Re0CRB~)~r0KEQeV9>wn_ZJdBFnqD-qVsDXQn&W9X@dqwR}hAQnx|o3YxgvnTAZs z)DD_BiPFMc>3Mz zKvqzMU1BY@BuKr>+2}J5G6-sSJ7z-GmLlvD1hu;z)nyel!6;@!D(TZ1#e~RUOYH#3 zl*roB1f!S}sg^pUm=+mqsom|UG*e5N85smMMlmqk)f8Vo)rTd z%#f@t?Prtt32oVm%+XJ6oC)?+nLw$F<4hCCBZq zo2JKh$0_A6cgOASli0cGxZPnQ9oyZp-8C<_M=-O0XF7tJZD@lP-)h{k{{X4-{EV06 zZg*eZyiy^S@Qa)Z`18L?>3#haydPXt4)@9}Rl?s;{Q-gU`zWdfDJj6OZAC~WimDH6 z2a_87iVDGH6xH4kD8m;jb@)+K;~kaw6%~&NQB-@EqZq%UYHD6%H9=I$@s)7u5-|$$ zqp0?du=qOyT@<6J#=XUln)FeOq8hhoq*(hk!!24Vs@kb@i(ZP+wi>rqzrWE`^}MC#wqm=mRt7QU;f_@$Km0)lp!9ss|mYp)N1wUO3j05Vm38`bAQ~fUO$2A z(UqF@*^g?`mDQsw)$^+#)uJn#=ZV+6&wf;kTy7p+sqS$7s1{w>Ji1c-;rdZ6y0ZCp zUQ<8&QEm0vJi1bIKl@Sb_PTj=r7&_CoUayL**v;Zvp>7rT2psh7HrO~n#R(PYTVkK zTQ!fRAJw?EIk)QDZ$GMWt2no6CQCo6ajQ7DYAQ=Vs&T70w`$;|AJw>3oLeQst*TXP zXI61;)ohmjwi>rsHBND6mW{h4mEOM>ux^|jtDIXb92Z1od~7i4$j2t5LW=!VJhUe0;%4p96_yWg@0CBE!#dQ06hQUpN_BbezOUDc z6fNrR(Ur=gepHLDxR>5WFTH3FSaikB^fsF5MNuuf;%<5y-SncU7F}^Wy+S*^D5^zQ z+)uC2PcMpUkxN#ZAI_I5+ud`3wdUmsZqb!Xq3wQD;})yU*S2ONm$ftnSYX^LEI1$R zR~l8z!`!%4SaLp!N^UJ)*}2fMI*LkeEneEWu(Wd&mE2mqwsT=^=O`+duALoujDa*5c)z3(GqPQLVo7;`N;i>pMqL$*si;JQo&tj-rxVi&uCqtneH~ z<-WCeW#+=l%u!V1mX~HOEX^E6HEwyi%EH>rQB>oW3up=jG*MLJmRDyktj-)oHEwx% z=5o;*-&OgJq8hh6L|QI5y{IOlSzJU@SfDxBR;$pwc!lP|3e8beAv#QS%Yj;wAhDYc-ea z*pxcLTDYnmVJ$K$6xKTYQjQYxV38llj}r3zdwtEGY=cOC7~gmpkFEAc33>GCQ9_=p z{ZT^x!{?{=ZkKw)F|Ewv6R*&yr@dGH#2Zc(Y&T29;@K31PCZdni>|m;PoY&$6qQ$( z#pN=Eb1#T$W<86W^%N#lL{Tkr>25uRZaq;{F6fKf^%N>*qNo;Kao>SL-+?HqMOWN- zps+M$6xE_DUW&O;=@Lb?$fa8k6j~2NQH@*fJy7U95Jfd^d8T_|HRdR)am&L3h3*4E zRI?vg+oDuxeKn)wtyz z1cg;9qo~F$Hz6oAA!t$CJ@dFA9v8&+q%t2DL>|2PTob&@am_mnHO=pQlxf zi$3*C;G>|`hog)?5$XG1*kdde4?Q&PHO$en%%Gn`aNA#!z;?_808KT(SRVf7EHmmCc{7H$GhlBT)8=<1g3S5!ULBmYfew zJLc)3Y3F0>p=sCBAE=l|Mak@E@{M_>vE}Zl(++BSj_Gz$(A?#i#`@G!OlMCq-I!t; z1f@=E_6*bQkSuiXOSKqu8}s$-((RBe^!KT~in^|NJ0uGq?$bVf-XU2yBnycPqmk2v z$s2{qv7O0u$+PQ{H|mmuptju|cRQY$sYwp@scm;IN!}<)4uYCO&lSlV70E%+L$c7G zOJ=LBwbjy7*VFe0_R&I?dbD7pITzgnQ%pXK{BfQ+F=2sXGhR zotMzly|KojmRfB#xn(vFrLyRJeqB7GsGL8G2f|A&)Y*$V)>5lztDTk#PfM}3j;8Qj zW~=gB7M%n7+sfCaW%f#>jD<(rO4anT*g2;xI;8ivl?R<=F%PA(=#<`%%9GBrn1@nX zH1+yXc?($<^H3^_rd~fPuOZ9g+^U5-`%#Tsi*svDaBHlkR$CS<=Al&947X~jRiHYz zR@_8_^R<>*1*&tap0T_8wU$~1s&lL6eD3BTM|&6TlE#Czh8}8t8=Rs>g-1~ZmrI(S{tYv)qFJ<_th-st67QH@*0_bqc(38EUe zik}J1RV9e3pS9d_SCwL}DnV4^mS><9b5#kV8n@h4rI@Qq5Y@Qlt}4Y`Rf4F-EzdyP z%~d6cYTR;HmEBxbf~dwVcU9TXnKPlesw|#?wx4V3?(|5(`&JFsV7?l+c5_vU^?M)s(#kAb@dFi-CR|IsN~k_t}45^ssvHVt<_ysc5_t;qLN#yXQ1uosuDyc zw^nym+09iYh)Qm)?y9nzt4a`++*&;YZ8uky7^=CdtnR9^o2yC?mE2n0Rb@9yb+HH0)gMH6K8Qw9ja&XAx>M~MMKx}@tIBS!D#3m= zZn>+9fn9Hp-tupo6KO=0hufYa;`6d?b>u~cgJ@3 z;>pv;x8FbbWH@h>`v#}fvE8+da;fh|sc+M#ZAA2br;cO0JGQ%HyF0eKS5M=`*sAIU zYm*6uk4)fxMjf|1PAOA^9NS&EQlgR5UviG^uAiJoFcaiFZgY<66kMnw~Pr_{08VM-mF9jDZ>*?pK%?PizBWEg94ism-3dX4X$HNG#I8utqM z##)>Ls1}*sxkN-!dBt2utBbOaO0~HzJW*83(;KZW%0B8A){n}F>gsjAch>oiw$*Zp ze3{r;3@(bwYv$_J;C5Dni=y(Lxq3Oco#o)7sJv*dUJq{PN)bdgfAV#-nnU|k^QZ0} z{GzDFtpBe&PdL*? zd%(CgSfTwa zJBn)D^1PFsModvu~vy^q8hi{VSJx6+^WSXS{BT{Z?Rr?w5`T1FW9|PgdIgS zZh6J-ofW&IsKza?L%CZWN)7J)NeH9Wp-eV#iP?Q(~{K#NMqA zWvB-xt3$bZ9m?J6PzF(rTmF2pQ=As<0ppg}q1>$wWw5QrEw4klTOGn}FyFM^Vm&F(l>kn_cDwXE3X}*{$j}v#M*v5gNR&|?M)df*0ZJFJwZZoU8ASz{Jvs=||W>ptNrEF|= ztGdms>Vl}0WX^6?x0zL45Y={cx2oIBsxF3VR&}#m)oo@~7euw=wp-P0W>ptN)z8{9 zja$`iW>ptNHEy|8-DXyGK~&?GTh(o5RTo4xZn;(6W>$4URO6Og)ou0J0>HRTuqsBi5Y7+n1CH@;F{y|XNPF&%?QQ;p172VqP$zMV@3jBkhwwbuTf1|!X z2x@zY%lkLV`-7mimH0F0QG~CbQAZIzFv?~9u_An5-Mo5zidP#NswZX3W0(DJCi~Y~ za)0W_P(3MuYAH3F$^L_=Mmm@MZzlT>qT2awv2?X<;rT6yYUj7b($%)=XxN+zgQ#|X zTfF4ZT5+!Fl|fY7%9hn)GiyCt^`cf!O3VRE1>I_)tA12{5>PD_bgPbr{iwE^EtU$p zt(toMsK%|;QbD)+q}-2c+*+Mmwb)fZs&Q+zRM4$fyXr?ZZmrI(8ffoFHEylWt?Fpl zk80dnom(}-zaQ1OwK}(IhX03A|Ls5j?c)b8R3kuT-2dgT4<3K}^x2bFw=eV$L;V*w z&u<@m^5E0&zrTI{hiCtB8Xo+o!gbA$#*e3u=Z}|<*N?Z4%g6i2;-d^*<-RJbRQa09 zgj9~9viFo1r;IZdB~(aHms6QNs#1Yovn7^R!oEV?(hMukp(JyKX!Uxiw?4hhDT`TG zR0%1S%&VK4^n^O^>U65Jq)vW1r|DFs3`eCSDtAzce#**I3Z3%Zl$@q5MeDy7YptwW z2DN5sfzfIp>WXI~g=Vm(o92cFQoXJ&QjAgoMMeJ;J1;WY#-ex=p{U9anpd!$PS}*;Bx^z&V4(ilFy*j8{2leZqjvdsqgSvK5 z-wx{BLA^Vudk6LJpbj3?!-KkbP#+KKg++iJ*c|} z_4l9-AJpT6x_nTd59;(my*{Yh2le})jvv(XgSviD-w*2iLA^hy`v>*^paB>(0)vKN z&=?FFgh8V)Xcz{K!=Ql}G!lb`V$fI&8jL}sF=#jjjmN0*7&RWF#$(iYj2e$o<1uPH zMvcd)@fbB8qsC*@JRUV3qsC*@c#Im4QR6XcJVuSjSm$${(3csl-_YCJ}b$EfibH6EkJW7K$z8jn%qF={+UjmN0* z7&RWF#$(iY)Y>Ao63D3W7&RWF#$(iYj2e$o<1uPHMvcd)@fbB8qsC*@c#Im4QR6Xc zJVuR274VK4k5S_>YCJ}b$EfibH6EkJW7K%mtld%LQ8Qv|{_3Rhm^2=f#$(cWOd5|# z<1uMGCXL6W@t8Colg4AxcuX3PN#ikTJSL6Dr16+E9+Spn(s)eb$E5L?G#-=2W72p` z8jnfiG1Zl(E;V(nxhyvNU0rVKdQ%siy5iI&N8>SRJSL6Dr16+E9+Spn(s)c7k4fV( zX*?#4$E5L?G#-=2W72p`8jnfiF=;#|jmM<%m^2=f#$(cWOd5|#<1uMGCXL6W@t8Co zlg4AxcuX3PN#ikTJSL6Dr16-x7(&yr~hO4KQ9aOtCz2DUO#x|Y$Db0vHwX8IzQ6%*X+>b*ksGBi0Ah4!}tC;&iXIEes%NW`)5~peRI(qC^}(@ zzC}>#iK3NF$L?}o^!~9_sIxe)Wkw^suX4QKh4lRP`)@C$uHWu1Z`Bpw-rhVpJ-+$w z^!?*kxBq@>0%qIdUnk&IIZf1dw*P}_dZX* z5w};Z8)vQ48iq~q3J#vnqR%>O>{tEatTj?Dc$=1Att8`i_ift4-+kM6H;->$oj&^P z<%>T){nHPxZvOD>_GcgXnq^Vz=CcT1mh+-ks+ueQBnGMlnzXwrerj#p&bub7|7jlI z`xJG7x_v$i|2k63TvT$Qj)<1~H{+!7JeRp>)@TyD zgRE{*$H}$+13jQUXnwB;v?=RNZr#px$I*bFr*bapU;Rh5ubrcQc?4}EW}>VK3Yy1X~+S|Hw=2_KxU`U?F=)fZYr)F1W#Oe^Q2 zlY*S!Maj!wG}>o%>$2*PtNwnjP;W+A=l%bGM|u44Fqbtx%paWS%`j^c{lqZqZt}Mo zW-h69PpQiZ)>*AZ8X#Mtr}zF;>XOfeS5Vr0wC21WYVA6jMRQ%}HL!KHEBl+3SBF1Q zzUW-G>^g+rjkIn{Z@)9Q@aheE+Sjelvt`%+`*?h`YGu)CqNBmCe)4W>QS&uVYuC&=5~-w%4!YVK>u0MYw9A&F zs%Kh4*1Ip%&F$?MmPK)@=g&{SxPA8ezj)RC;F@#Ks(YoQu8Dt7I{Lyh|LxWy4WEwC zdXs*$-{>UOxf1Cv`}h5HquqbO!AR$HUCHKo*|xKerF9k3Rj}wVA;WELL36pAyE^H< z`}`a|>k@Ex;3;+ERR6bsTZ>Mk`XdfdvrgRhCo%UuZq}CT+_z}E)}2nPiVpIcOZOa% zuFMo|@4hZ_GCDuf_N;@6E(}^n&Nc2-!tKoxd>7pfb z)$vrzQ9TgVkJHJ6s)6>%zzT&*M3;b7X4chtD6S`fg3oobSvm`W{ce;yeB&VW_+ns?MOQi%i292_U7|V6*tHY(! z+FmypO~|@0T?TB{iB2~eMPIZX4b6aE4>{xc_34Y>eSZ4thiA`j|KqejS|)81-#mSC z>x1^*e5;qf_b1%@Gp+_ud|s~apH3_Oht6)|m{_Klk*VI@>aXg$dS0}7YWQ@5YpxsD zqsyZ@4S)A-J(Rzy=hR<)etJ~&r!PN0{a?>+Ui?W%^wwj||A2)aJf<~3`{R!8r;mW*#FsAjSvQaVka^>4P} z{TZrHPzYeH7q>Tet$J>e;j*rg+pMXmN|l%Mny%yujp?K|?Yc5w*4eidydGUr6tq+3 zf5rNu*j(AwEk$ddLKPY^T_3fCDt$&A`L_%!PlR|E`k!vB;pZF^UxBOSj2iF{h zH?%P*0H=f6W!t-F55KN9im|;L#u@?8%5uFH|KjDV+tX(+pMUr4>CKDRr*FQ!y?u6? zmQPO~-8_FN(u^NiYdB{`$J)(2qbWqDzu6Dpzd@}Zz8P!x+b*Gl+EtftZLdoTPu4k$ z%hGkr(2n^x{aAk2e??GE?*R($i=!%E^yUJrfR@;)T|pu3dV{;0!c{exzZ&{pr?{=? z!lRnvx&E_Dgu{OJ;ghGXyi1uCTe*Zd>fF~Bx$7Ubq$}2;)>js5V^OGBZ>c&M>i?oN zpLadq{9Phh7O2q@SZ5Z)cnZVlZ;blrcKhDnwt8lM@A#vbxsGgadtj-r73u@T^4^9x z+E`w508%*o-2nfcdf@MUaHt)n+SED9dLFP z)&CSlr7Ivs$`V>=akKrsw@fNkM5Kx+5XxU2qsLND>&<5WrL*x zrDP=FjX3#DPy%7SM8@v2x=2C{tOp&$;<5~#LS2O4M<^o<>X0xfBf*mgJ*aqkixN>S zFsrFP>GY~$F(efRO+Q%XxJPQO5iww{8D2NEd~qB3c!+NT)eX z))qWr?66PMNDr+#2d@oxFf=yUYn$q@r}4LjqND+ZSGRDFrp`o1XB!NX_%7P!Clm!wmfoj64i0J;vSY}O)P_#=;jpDXUYAvPg z5JaXLnim)=v`U1?h^sRpw#$C(NNk6grC55K-0D5BX_2gql-5(<9GQ5D|Ftu@6+V-q zT@F@AMJ6MDm%U{~_!($PPK8$yi|QKizGXGMS&-VQ5krE*3ClrdtZS{3~+p4T38|42|z z6Y8?uKk32~mpb?ZxIZ>5VrC$e3qOHC0OtgiX~eT3rl80bi!w}aX>BKLrM&OFk|7da zu{0qPFdf90B2G%zuUDA%YdVZTFhw$xGn&0T1p1mVyGL&HYB)>apoi89t2aFAl!zEk z1G8B*{tx0_aZ4i*PUoPmwqxIV+JM&whA!|Du(77bT1erbLgXdX&2c6XGz5jYwx~cM zl24K75id!aZ~B$2fB;2BEu%e}8S)en$~nTi6U3CUq=X@MLWtM6e2>Uf-2m@nN}RE@ zl(qm>*eQYLb4`c|hp!X*HB5VS9w()x)oM4eaOxUYzym{SpHSKmz+6&>09cfzw6;?B zQ$2O(q}iHuxS^WiTrly#_!$LRbX}E0eMPpbqG6v0J~x2n;884GtH7!v?j2JFJ`1le z)g20ojYVw^q2e({lQB3}T=d^^%_?-M3jA)gzMH1pjsprw{gJcuyjckP%w%vv;m$=wb#R5J9zWRep{f=wnF#V%{0=*7O4X55CXYKk9qCjuxYF^iIU^Wu z(kKF1k(Hzqy7FOO3GXe8n&QE(7i$-^E_kXV9UE*i*Mu8N)XEUl7VFr!N2D`QkpL5H zs^rG&S57{}s4BLZtv4^g;ARNo%X2tE*kP#|K_C~&zrA$RBvA&q+k`7!xSfaC!v=)c zmmFA_!|HKa41Q@`Ny81ID1sfPF;E69EE)l&B7jhwys)Cuod(~1nP zSL^!slJz8AiIt5*2K7yZIZAvRV#;Bchm9W5$dD67(8tA%x+b~30zm`vMNv+~9dbpq zQgULFw^aD9HEkt`ZDa616*Cy{yTEXYnj556MYl^t3L1B|SBiLPN2y;217 zD;jr4w~BD}U-2oq*wDePqCRooBS!+vTwVdKXXX;{5`=RhR|9Sm;lJgQCj9rfjEVom zr(vjK68)kO+~op6!K|bzgEP}xj~Y{AJ#I~-3{<6(gLG32U4=e{n=dFqeinr6;IbWV1faKK*gOoU ziff0K(M*{S8ZRgE*$ge^ZgmVU8h4pjf2}{HiEAB@VXjpdYgBy9+$T2ks}OQ zK5C1)4DJo+vUYF_AR!d?Lw6|OX2|wzW@ZT`Y3*e|4lY?|jQtw$Dk6~r0zNVAINk^) zBX0rAs)H*IISp#z{EI~gFgr!RN0Q;1Q|yoy3yK}`2P0h`lK25fD0a9<3Kfuiw6++} zfUxae;Ml)Oa8V4(hy*8hZ{@>`a0v@pFmNLgf)~sV-Ln27MU^gW1)_{n>U)2r)R{|B z{he3wVTdewRi=j>jrUTFM&MSa=&ynJZl5|0lC-(n<@7$m1u;u1q$(VUKGAw|4LvSrqGH;9b(t_eb1 zBmfU)8QdYpl@ccDfQTWKs1X_K5RZpM!4Rus=^1t##W3v&!G0-o{dNr)ijgCZ_Y{44 zH4&77LovOY2{A;fJVmER3zl@kRhsNDODL>vh*mV1Ya$^9Uq&G!$Dl!px4mec}T ziL_i)Y+Ij@GT8pzX}OiMw=P?AAS4&9tJK^_6Z~S8*$?5xOxl;^ICv48+6^ zS1}QYj&q2RIlO&UJc$Se?8Roy(%b`01A!H=_aOHjoKy;4xyA5!SL+ zDzHq6gXyoeF!za?CjDBP1Y;&^GaowDrR*isTr>OwS)q~q8OjEeMgtja+j>}j@c;_0 z?&GqE7355c>K>iSlyyp6EcOnw1lFe1XpSgZ)L5EKAIGoM8QZN?mM~(+>$tWm$i3go zMVY8qdl~PpLI1(Mn?{6K<088E6eQ*P=m9A6v<|c;ygafGp5a0E2>2Zsa)~T8NNmpU z%ULZEsfm>4#hX90c6Lt+G#RTa!d9^aS*w>|C3v*RtCwsh5^M8!4$P&s=d! zW$tQ6Cy)tviv=tv2dNc_CS)n`N-gr^;l+doP$c1~Ooa@4G*bWJ)`WF@nUvOi&?8r0 zT~#xvrv9+1&wXvo!f+el@*bW!!{b^0bp&hzyuJkq5fVS_=S7(bAt%acyI@7Y5+=DuCGD|g*-hfL zi*h%`-o;RBr^aP58_tPT+glAoNApndYH~D>dql9wF@O#y3)dghi?VwEmrZ5e74FdYWCM>PMz?wG z4IDnTBeG=T3XZW2m>kyKx`UH3E5}3Gh<{dAj=jg_vdmm;SV>c{;pN>;O^xl5K!`pe z?t8N#@p>PM6151N_iC&FC)KgPQz#PV(qzaW}257vj25Ih7 zb#hA%%2rG}vf>8)8~>uiDii!uTe_kz)?xLT)DGe(?vuhgS-R)b8y*C@xZzFO>IxW4 zQv19g-etgpI+^eFwCrAKM|4LgzRNZvlMB0-VtY~misFEiN4<;ygbj#2nXD%9XQc!k zPrDYq4HPFjj|wV=$>J@Zc&$5>iEuXi+N}Vti^Pj36Q_(iZA?cOW!4J3On&O4CY|0HQds?d&j(CK>R$4J z>=zJ^?;#_odY&Z)Byr%%JZ@BwGVdPSnFQe8e@pAA;mHco9@D)+M)bE#-_7vC>K`NPi?Y2blC3@CX+q7Lnuy zPJ70AFl!s)K#cR;q?>N4@A#!3Ad@g;;QdhUDQpyYG#JSalLnIea1U7%2;MF)Q&?Z> zbHsl$u$spYWWe7W%*%)D_#j97CoFg7bDQbK+ zQ*=)rLh0|sLy@+&gw7nxig-ZlR&x=JLX&l5CehjcWxTb*KpXMS&}$)lUlb zmA8A5T++Od@V{H57rc;>K`)UT#zcph3~-kZ^hwt&?2rT^>hzTDVTRMMS2dlPO|h=sn3;_&WDbgiK4n( zY2pzy23&Z@#M^2lij-kAu;=3%5^jdEL&Ph9+2Orfyj$ClGeTceF>Yuz@da56uaMsm z!i>m7#e!o-Ob`rOaNr_m9?a*W)aM#;TLCl`cfxAz)kTv_dUXcvv_qs1cpg&R#P5_M z0hcTWa^Dr-DK+Ap$tT@|-G+mmvV=tW_)~=tDp50O#HWoRSyFmg1P&%lJ+2cl8*&|1 z2H$iiT-l_H?vlME`xpowM5+zC>v|L_VA4PzG47PHQ#y01uYoOy1Q;M}(3KGJ3p*E= zAKoTJkRsBh8ha5JK@7#~m0XgNsr#edvZ)xWlZjl7+09O`pjy$JhX%~KJbE%1n)<=3&7T4B0we$Tz*0xKD*0{GEC1XZCd*7pMFG>^tqR! zT2hV=gAWa|L36`}YwxNt`n}!gv(`=`i5tZ@{|%h;m`5 zLWLg>;Tg8?Paq{8mb?}@0bv3|?o4KOj0^;bF~ySvh$zLCMhwOrVw3&3Y}iRjisCE~ zDG?%|_5u-H9m3U=2FTlu^-(kgavUQk0G@}2Y>s4WM#(U#ojbszKila{lID!IV^T7$ zWO7_?LgZ4#jTe}1kbD}U%-n{Zg`gNSj>*(q0m6f>6VAU1T4d7)4r06%7cK8qM|Jh=cJbi z@-e0=@qz$?y^NM>QbK=r+(}V9bX624UFH^eQu{=#CmK(dAy5%z$wOXWMk6KVPkO!a zS?|)7)|h0^T~bO*1}bmBrp7Lp1(G=8YD6jG$gx@$B|MVVgdFO)Pl50RT$=5iAQe}K zCI9P(<0K>q(~kWUa{J48ezh>zMoyanOi;;%S9< z2yYQL!B~NzAS}ChTunyj4jo;6z+2EoSuMl}LuI_L2932y6hag{vZx|SGd2UR3;Sn( zVctWoN`%`YhAYx<69H+4!kR?RUC%kvCpuKG-A34^F{wRv)cEmL!_S&<`k2XO^rz%) zA~>y6*NGrMmb*<47mV0>~6X|wRUD{wXUEcxbza=~6uiZy+st;S?$?iC|TUo5P=?H`*A_ENZNc)?!O z-9#3w)h1l30sGL^s(=Bm-*N!U$towIq@}U`sXCg(&Ar;mX(~g*e43#2_yz_VFU#1w zp2G;?74cTiM4?I>*(z*F2UjPfhwuf1jqr@l?C6Hqn{>_B7@+ry3?8{3s2Bkr%}{ljONW9+M`# zeR7u(p;m~9$>D7Z+{}%#p5O{$6HQsT%8URYi$qa|>46hHdqE9H63Ryt;sltr1z}j# z-X2$cFt^_48BdtI2N!*FkXz$3nUX<~<)peEuaX{%8xm=`EqmOES|WByZpY!JF$6N= zK6Mkf8}j*M3V4+t57$H3W^#4Ad__4YX=*H!gaGZNc}1nI#2pdP)oVr;pQ1sgS8QSp zhOi*#Btlql7aotW#g{*j!kI61;BHG(@ftDcY`ighbogMR#;d$dOcB5UFkG6%mTE$< zOhc}wp%DpWYfu4Y$(y(mO$zr>4k8=89uSHg45)QhTSrC$fcM36oAcb)6VtwUmcd587i^VJzAen>ta;!OGCRuV9ZJulD zwt8p5U_}=`c5%EaJvd2Nv7|~`NuiQ5WpBd$5CR_KmWfCS>^n-L5Z-Ujn7`A}uq2eSU zQ&~;*NvBs08-Lb>aTCv)P*t3k;gcqhsXB1XsL4?pR3tm8E=hx$mdPrw3}eATfe||d z$po?1IMm4?>(y(+CWUeZ#OM-ggl9`dqyUYAJF*6bJ@|AXZLly!drGKLsZE!ghua&^ zP2tIAxJ|o_ZBc^hA~{NiG4_c>U5BS&@SqJ;0zMJqcPiK&?rq@lg&eN57S#fiWw{5W zsPDNTBHXafOf?U&6UqVdjo=2ZY!SQ~*2L`dkUVjA4T?p%rKzUl)I;h0R9RgWL#2cT zakv`k%Da;I!KkVT`B2%UGG{D#aw_cQ#3ADYBDfpvb1aDmrjr!eX1z>eEukRvOy&DSEyS_8}g(Aa1=K${0l93$b$zCLbG~Na3|hhfQRhPw>@Cg#@Q<#IFlYZ5;_N`h0bixTCcLKfGNaF zRhh$<6t64G(7?|i?JxlWBBwzMOZk~tR1(6qNezV;USnjtbk@?^8B+3a!&ohDF!V$o zNto8T@h~b}bd+0Y$y()K2TF!$!=3 zOTvogVX$E4?HumY!a5~FOgFrQCh>6>7b{6IivKk0*Dg7qBNLq-XZ)MkCR2(W=E-Xp)$rNFdcc&Q7YY( zv7w6>f^hwaDO*V(($QdD#}%|BfL7#bwFYR z*sY;y;Q9*aS>rxUgJ3wp^)RIE$G9Mb5zP{L8nbTQCWvt%C4spGh8(2TMDQAO{bPEW zaRASeuv^3`6{TsD>Uj0)Yl3z6$6!yW?#jP1A|R>o9q##L5p|iwJmDae6qR|aR1Oa= zD1wMGObMO}iGIX#b@?t+jY)x=3Hp6@M(uvaB}tG^Od)s){47WkTZ^DxnN*MTjWyy8UFaD+k=^0;MGH+AxqWh9R`A*# z=Bo7WOJ|%OjL*2BO>X2hwo`i@WXMf}Yh=tnAxAdKypo7ABw6n;%Ftv@PVdt4QHJO+ zZHMZg(M={*a<7b0KsYI&!f9Ma^)J=^K@>3aX+gFO>nyXAZNNEPyFTg#oEgMM%)(&P zMN(t3CRfBB0F=}67_(tF;6ZLis^oBs6@P~yP~v^UbGTj%N=byJVi4!Gmrv^=_$TJI zy?Or3uP_I zCPi`wmgF)-Hx(wd#>1jbqT}9@+oTkPP;!#nWT6;HlXk2w-)zP!8=#&MyF_XftX5J6 z!jsSJFlkLTstN)TRKV|v6a>o=n@`H;f}$0c@PaR;vt+F@+15ETFdZYB#PI)QSbh|3 zm<-D|1`m^-cr_uDc5Fy`MGTTfJ=Hld{@x05ka=`LG9is=i)kf&rkKZS_^!ZNb9J~f zS6OaHUbWu3sdPgq7myX;AVJXmbvU0>=O7WLM>Bq`45NcU~Tii86qD=NGOO|Xq207;|-cnuI< zg{P!yVPTV3#JrKO*IA6yjH85?^!P$XS%Tf2Coy=3A!B--vcYB%KF|R7PaHk~!*WvQ zLwu*idnRN)8{?1Z*E#4QWEETo`vl4#UV%l9JsR!PMWBRf*DV6a$eT-ccZu4`N{paV z!2x~`tSoZE@{%uH*$Atk;Q-1e1A1_tVe}eojp?{bs2KFXv6VfM1%kDM5#U(OfNB^s z#p{e~3&orvh=3P4rlXu8CP{H3SbFfFF6In@2_h|~M*%8OrV%~ah&LE;XBQ^&hA5r| z>kDH%BwYlWR3jtoVEPf0w=g>(uCPub4jh4E5Fet{%TTRzd_ow=F*#b%SYR>}_f}9( z3gDFwu)_Tq5Juo7kJwSb@9gFi-A0~-LQ0GG=jo$H(@{QR(!`U;opRRXQC}TDrVK~S znrh%QCD}fr_=RxP;)sDYAaN`rB#?5ETNgHWg#IB(Uk=V$1UwnUilIBnZCS>qoTdbo zkE?|t9C-=6_8~+hsZFguuGS=nrkYsy!~G_$vOw}S}+4exh5mQJ#A1YwM-i5dmfsHmh6=X&|?Z%-H6PCkf8^= zB9{1!O%GtO2*|4ikHJL&arSnD!I~t<860ky_A9usIsJmtHFxiYV;fk4}kH!;Gl@d^h$k%RU;OK({ z$9)sHm(btD)7M$xo^c$RG{&IP26gRvGd#Kk~2W`$6!`m?nGYz7JNAP6x6x*iEEuzE?UZnd|BU;vHLtbjfO zu9sY!#nOX2aU5s%r7dEL>_dB02Xm5;ZM${?kF{!Yf z6h;I-6ODsR*%wc+ba!hPJ!Tcy+I>Wdd-(z!(;pSs{?1jy$~_W@Y-8bJrWi*z-(k6zO1cu z{^PXCv$7b2%HxVH-t1GmP^7FPIcpa!L%0|aFJM}zM~rNF%TSuJ^veKhI8S5Ddc|F+ zoF_b(udhWpP+4WM!;oLPo?YP!ccUajSI&)|!0B72t6gPSPn*@u>ZT zr@$vqqA>tT*O2V7(Pu+uEyVW0&V`h0kmSv>6-Al~xeBt+3C3B)eltNMa@vpq5rGFt zr-yThC=o0?LROHdt`>I=VFyI|8iRIGl<7g(2nLWQo@vcW6sxov))-ydOb1w$5z5Q+ zK>MhUkfrLxE8f-~U=k2ott7 zb(h$hl*nDRuP4p^6%O`+f`m65ag)t^KxonE%oS;fipg@^C3G^5n*jZbvO!Wdu14Nw zlEm(qGE5rd3hYMoZL%>}G3Cm1wmk}4L^3IeYe)+U zk`&n@kw%IRuNu1WU`saFg|YSHS;&Mhu6b)!O;OPIYe3OJ$#J7a2x#+?|_SzV^Xbq1V%Y;OenUCn;kyU3`K|ZUm{?dS|&yB>>D`$=! zH}RBxs)kRVH1XUqQT9(fhT2pn^fGDH=zsP{lQ%gN8ij@F?{ck4vfQiV8woGPeApD& zuz6G3nj|Ah?h4tf$)Y;yQ^_rk(^B%F6&|R8H4)lB?k*!)V057nb^t^o;E5h+E>NqD z7szB|UX4euPl=FFfy5gEQHr?48v-@OTYV6v;)B`)c9OY#gnWKT0Ru|`pQss34^{UB zB$I!+A_7vM+lr$geLCzKnOzyLDBz-ns9KUr40b9!Qj5F9Ma9`C@eb`RJxTCF zyw{zyZHri!G;P;Nx{zeGvL^5{4?|#}3?DRd9qDPp2+l`HfnrByaFcwwycs-|&jXW_ z8wC3Utkeid#F?wjd3QJn4JN>}Qf*z==zah6DVe0ny(Ri- zdAXk=Ty!s08sSQFbP^FfAKDaO=AsQX`JQ|k)3;F$O`7Fi;hMeliM%t&Q;$?ea1NH5 zPFEjhWRfpeMD*CLb>Ycj_d&h*5^S zn~oX7OjG6*p(-CX*M}ZDlajfYbSi7L5tE77X2?>}O$xwJo5ihY#2a*@K>hin9x zDa2dx32eNj*aV>&uY44>ER(Z2y?4tesLUQK3>eSyK$Y^h-jU`3+ZFmv6O$EygWx^L z$ZZZABW@Jp$xmeHtTvL8$>E%O{Sr!5ZHJFvCXQAmlW+l}Uc2#32Iq`+Ysz;MJ;Rwa z!{Qkit`724g5x0y2i&|78BxF|6aJxwQZocv8n_PHWr zVS=&a+6jh}kQ1Qm6D_1R!N!9zBZt3=Aw5}365b{)YKPo!dEkCWDQYxNL|Rt!UFS zsSzxF2vi1}5$1{8z^IDnk(lx)v1d(o=URkk9dy*ls>9D3KYq+PRd{8&BR&KAkRmIU zHK>F9Ad(efq8;6KmeZN=K-U=ZWAZw8$({~$vXk;al*@TRI#Dl8@>c|m#$+WUwwZnO z3#J%3fDqOasVRIw1RSLv;tH;BA`2B#8AXyGLP2R9=GxcSns?h#63;@9=uuzr5JqAn zdta1HOp;|F78XG~2`4p{I-gBJ z)GkZ}kZ7sCCD~%>6L{tkcf1oDqqMr{&;EV_v$ybMM}RQ531zwmYNpBDoDl`e`gEpw zWl!>{;&GgKGpEjH2e){Vf_7yie4)cY8ODQLi0p#0EZIW4qm7uP&Rt@XFxn+vGOYM5 zD~9(V)F#Tlg9sfmh#X{7rcTGZo_IUWr}@T>fm%fA0Oxw3UzAu)lIIdTK-qg%eL_Ez z);TS<@Nys!f!Bs zHTc!ySBGCceyE3hWK0Ok_yVfsu31gTzYQmTS`2pi5P8oIDn5r}BfvsvD?9%rE z$axZ)t2js#C8btyJUvfwH+AevE#9nCKNv|Ia9fIeSklkHR8xm7SdX+p(3aT_giu80 zLSjMkT_mP4JFO^@d0Axiq_ZaCrNuMPns{2(*fFC{sv14&^r|yQPagAiJj+uHO*Xu<$oc{{AsY$lkMXoq4fP0{*8)^fCF->jRV3+P=I@#&aP}xaS`Bc-T|wx+ zD6+RyO}gmbqFPFDydgC~e#JzVqC%uGDY8xdCP|psJTGA-bU_3sMQ%-ORuC=G{Bc-K zysF72E%~tf$H}8m#O%Aw`vbElaKo)eycY^4g5(>>%@REa3Y3T(IFv5!j2^t3of*M9ZBVZGgS}|`lBB+a*uPFs~ zoi46!g-Wtc1RRW^61WY;_CT& z>5{Jby=d%39q+~TdO(X!7gcnhBy1%PS%!l1AYw5@OHs?11%nnDolM zN44)MX9CkmOXvVox*WPrP&!-GKF2g^i$-_~2tY@+XnIyEh-%*o+}+{&bRTsc(bX}D zG^H<D%82{ zyl4)i@4RA&rbOa?p_?->KoMN+UhG?XA(B_ZY8gph39Dr>#FU{8ibd!9u~T^@!K7g? zDbZ$1k77CR8=Yk(_H)=Eje^rP0}7)y6g~B|q3ttAkC}+r4WKU2nTRzxZ@|P!CygOg z{pAb3d_mQ1TOGX4@PiLqXT=8V1$S&Zr)|nFM>-2{E1%7eh^{xD|4$JsA!mP`02(t~gMVM_*`otyI5@w$$&uKa8=e0iC z5t!|ueSz6Negd;k{7qo?i9Q5opXj5&cGxHS5ZL3T zUswnKc)SV*--4M3w$sWw?9!Tfk*$&zlnC;^yF#E*c3Q;?AThWKW>=S(m%s$bFz?@f8o-_6H zrk%WLKX3ZYoADIPI16U{vUVOXmMgxj-|F!ynE5G~d1Jp)hkX)fk5}Hzf8MN1&aM}6 z{K;Q-TFCuL90{|3;z*eN6Gy`ApEwd`|Ll)2`zMZs**|e4%>IcZVfN3pBkb31p_a1` ztIWu_4nrgY32d-V7<(y0QL6~#NA7Pg9Z-iNweGq0FW?gc2z4osfDEo#u z9=7?;h3_{N77#w^^4+BTwaZ>zIRD)p1pe`QC%3Mg^>Kmsuezc2?mw*~@Ws14-ilwI z-=QqP-vmb80N)6VHUhMj^KA$GH~&HZESEV(pRC`?a@J=bgxL=JAk6mpBg``XjWFx- z8^UaZZ4qYM?1M1>G37Z^KX2N}oA&dj-+~!W!HlzD#xLv0emJiNU)I-oU^@b%&w`n^ z0{SiRTbA)}Q9C!}F;0QmhFO+pTFZ@3vW4YYk_w>?n|w?^EVRsu+6V( z{qa4^^IYq~W)HXGCosxd@i&1{H^4Unqm2M<AB0I;OnJ`K&zpAgrv1F>H*dyMFykzk@ypsptBmHg`K~)yTDtw{Vz{=udm#ed-Fp}1-{{`!TDdl z@T|aWW5An#5O~DvKg;vS`Yhw$2(vD~A1uXVfcK z2|Ry;2lG!J9}0Zw{G0P_m;F=VQxCd4f8Fv|1wQZCQTaK$t`zvft+vhIH+r3bZSL{N z>>Tgd7xg!lI@M#2YrXB#y%(^~g=5xj9ev9zsdK@QN%;1{9QWiug7aFRn0NR> z)_L@yHy3Wc@zGM}-y25BMVvQ z(T66q-ZJXnQfIsBuP;3C#&s65&VJk6jc-5Q$~xz7GNkp_A77`HeciU=#sx2Yefw6{ z+2Q!#;M~;- zbBJ%_HO-qnlQV09Z{xj@H|vP{@m|WAJ&-qhCLzNc+5Q8a3;GfDu>PiVS=rCXgdfQ2 zUY739vO3p}dKq~#brZr~=MvcKTmn;P1U zp%3(BnV(+i%SQHq+!e_-JG?n96M2cU1lF~H_936dF#8p`QOhaASb37;vGuv`Q9E0S z{KxuHoub^xI#KynXe&`a@MFl^Ivvde`i<)wnBx~Y(2p&a2~D}wQGBDbLEN_rl67Jk zwUu@Jm_;x2II?~`Z?=w=@mR;tL+eGikCFPE!!7e)6?piMcWPa==vaYo9njMH$F~m< z_@diiY#q4j(*g%KY!TomFvIV2mV6+jSErHRtoI%z>pDgFOEwG$@5N3V$ zq3y5_!fc;E!YpGSgjtv05M~=}i!j?}AA~(#TAnxc^QN7=XIF zyw_LiAfHbW_=c-)f!uzgz}!az-aJ6y5wGta;3qK3WY4f2)D7@Wo-o=7(3ZexTh@-{ z=#%BGgjvo$v_AVF%y!rZVYbg7VV3c4gjtt;5M~=}i!j?}AB4GfraW)zLpO}ukv>?T zIGKK>50;~@^g)<&W5zFQ$8yf4!I$-Q9@tJn+hHGsIhXtqW*Pg4+F4inAj~!}eko_$ zcD)Gme0m%O=D0XMmUB+nCShGW!o-jL5$3#dY=k)n046)VUCk)N0@C}JC(6tePCC_ z{Ltpt-|UJXoUdp~Y^aCE}c@XI&=St}$VWpFVIcKE*ggKX_ zWm--er}atu2(um1M8ZlZ2`il>taOsF(n-Q>+sY?KZuvl-g#6YYBWV@*D$omWU?A`U`k;Wqb!_{DQCQN0qaO zm)G60u;Ft}&0Go0bum*o?@y1nj=$~`0zY=q(ZQE?|41{(j98Okn{ECh-`+g$fdD^& zQ5N8DviDK94c|yP+Gs;tIB)A;i?+q4#(vNz%jG$4BSY=?aiX8ZgRW*Pq$ zwKFH+H-y;++hQHI%|2Mpe@uDa)GwHJ3a0%6``~vdV;qpcsN2jwSdKQD&G<1lk^aKD zH2AW<&O~g08{@HX;K#!{0{d?T_H7F6`w|%A z;TRO=*t8DEEbyZ*%n1hVSzloL9+qf4q;n|aKX=mz-G=1X3h&{&e^Wc zxx(^qGw1rPl$$x%zNFmDdBNi=4|P2Ht(Mz53J089`>lsrZtG}Yw!XlAJObOZ zW?;@U&$zT{VfLZ4#q1^0BJM+}Z`-l3`L@G-=<5{tZv)GJYrm!)(!=i1A8m*K);%w9 zN9V}nF5em0ew!Er>U4*G>O9LB%(vXnN_%y0>zGOZWjw%LVLcZ*&Ug&OQ)#cEMO-iP zj*@n4o90`kbutF?t^BuHmvS^PFzs-zIA)gV7zFlX6WG_6?<{P-CEerrrH=Vl=Rw-> z^C@-AxA7QW-{1xO?eM~XzB;Jw!=HIc;F&w@+qTswUlsWF>3g^RlPYbK7ii)N$-$8wxjG zk(cuNQ-4|5@NW^k>341}j93`KBW}2@@QDK>_>tc%DE#K4=-aP+udU$w4cMfz~HFm#9ixiY}yXTtnCvQ?Uy*}c!;}>lXIfu=UgdXoWo$j&+g-y3Z{Me z9fb>o`Qy6t?+0DBOyC1wzB?Fx;(rAG<}P;y_y6B30-t-zoxw$yKQD0of;)rHAF@c` zA8c`VF!=C)3S4{oy}`PFAwN32@UigzVDd{33e11=zgf<|vmRl7$L|TVJ+@1j{jfj6 z?4RQx%yDsiggIV6e!p`OM8C&(vKg%^zX+nLPaVP8e1CIZh$F^g6aO1HHTE~A+#vkl=`W>x` z`#Bpt*g9vfd>ia{=aa4b)kvE`!!B>NeyAXQ1)n{1y(gWGnDb`-^JZNN2FHTIyCvDX6lV+{lL_x3}e47m^KThFB!KV zL&3-fTAyudefFjGIR+UwzomR==A_x<&NiCO946#RU!Qnued4Y4Ire6*6WhnSHFKQ^ zV{HlN6y`c<9bZ2%^#fC1U|(PAU~C0`%f5&wVUB@#66V;5Ct>2~>&w`DeHpW_FSz*n z0qgU}Z&}8+2(vExAj~${H(|Ez>&x8w`ZDLfzO03>FET3e`;GIU{Clf~Oy|;7OQkXmFHyLAmTbGiI$%T(mxMlyR^=#?|K6lxswoYb~%@ z(>4!tKM>Y+*KZ5vTY;&kah%j?JPj9`N1cu3)T^ko5vE>6osBT{D(Y;6saH{FBTT)D zIvZi?Rn*xCQ?H`VMwogP=0srPh;iyx`K{aj`cQ!;T{HDk!q8Kjsh4Vf>ZOFCFE&#zB@8{XnR+Q<=$FmZOQrmQjhd;K z5{91Id=>Ok!q8KjuYz8x<rG(k9jv2J4nRJ%rph?Z7vxGsb znn`B~gN8Me&JqS~YbKo~44T(WI!hR|u$gq0Flb~m=`3N;&St~wDerYE`{CQXev38* zW}E0sVD^PE2+T2HYyxv^7_-0}GjI`@xBy3ii6d|qn7AvBZjRcl8TK=iH9BUfa$65=_cCZIzJZv9(LtyrcJtHv3gS{j$ z_Y(G)z_5jIPf9!7lccR2Kldtal!Up5X}cuMy-k}YVeWa_ItlYE&<0AFXN0ypT3+(O8 z0@Kb6S|l)NZ8LRvj)D3we}q{^9hfk6OzOadse4ifCQO}_Ixu1Cs?>oAQ-`GvOqjYY zbzs8Od8q>v=D+#hg!y;YBh2skJz=)Tb_uf|_D7iga~y;@E{=~d$4h*q9QYAW!jNyt zYXpXTOCBUJ}}}+dt17|-j*(~x1|g0ZRrAY|8gI*eeP@Sd%`@IJfDPlUSW?CnD!jl zsRX8-2lgw0Y5##;OJLfCVDA!`_9EE91g0Gc_A!BJUxM9CVA`EvPZOB-DA?Hqrkx7* zH-Txtf?ZBv+O=S>6PWfc*zp9W9Srt8foUHjtgm^6&Ej4){% zX&hnFJkmbGq=lr3gh?YwX9<&bdfiZDSID$dPMyrasvEKnWn=x8GPAZxSz2Jycrymd z-cnAUV8%>YUCPNr434b^_g1rxwAo61@>0?}j-Nb=bdWH47wIEmv9*HE5+<)Boh3{j zNIENUWV4N6@J!fv1tu@mcEtAU+b8eUe#w({Jml4+vuu+*oOG5jdAr%4^s`7gWdzb$ z*71H8fxVwaVDD!U*!x)o_I?(Dy`M#3$}-*6+0D5Ye;&s}eb&$c@#nFe`mdoI;?H9_ z^<_h6#Gl7<>eq%YQ3n@#MPHAhy}_P$MRe@2J(dL@dMBcFr+)9P;FDkV@NF;0<)=OS zY+V1l!=8-W8M@KmgFUB3Hk_9yJQUz3eW5JC-{OApO;mo@-2vJX7<~q(-uAM<=rcgy zaXH2m*EhVQjkJ|GQhq0GB}}=Vw3RUBebQFK)B{Lc2~$5HZ6!>-fwYw{^$ElKXjhbS z>K}$zwizDUW_W9x;kj*w7q=N6-DY@qo8jqghS#?l8KBL`25m-WXfrZTn~{aujEvD{ zWREr@le8IGrOn7NZAP|fGcr#b1OE9E@1 zv;*>6+6+if3GNOO!%-9~!K_G#nvK4|gh7{3qw zH&O?(B>gu6L&l{4MqtRE^xp^!nUww;fg!8XeM@dPGK^0rg@Ak>a3{s=P$wR3Vl)&3cH8Ccs?duiZhU@0ffCVgbTUIrGJG~3`p z8Cc3mv(4JA^*(EJ7N~m*j+7Tj%Qz=q7Zcd)Vgh?zOkl5z3G8(-fxRv!u-C-|ro7snTMKP2glU7JEru{{GqlkVrp<=7 z8^W~Z(56F}HXhn~2-EgM8xUdIglHQgOj{9cMucfYqAiIqZA)H1lKt=XGC3DsFOz-i z^)lJdUN4hlXK+tGC5yfAC&Xx^+Y+RUVjw&;PqCa8(wb} z9o_4#qPu&&Rdjlu1rs?b=k?+fkqdbH^7UcVNd z-s|0>>wA4%%DtX0^}YTs?RdRjbbYVyi>~kO38L$JdqTiAygfm5eQ!??U0=&N7Ol@Q zdV7WNCU57IcnohR35ct=iw2wnZzl;jH{OmKaL&A)B;Z_nyKBHX_I8qhbMNi6!uv>D zxtF+x-i}%l@8Ru8607X(ND@oz?MM=1OxntJxOYff33E@8wi4!EBW)$jJxJP0n0wRP zX+<_5ZDl#nCC?{eo>yJg^|c-9`r1BqeeIXJKIxZ^+1oZL)2hvrGOgM|1JWnb zDb^?5BK;yvdPcfNm~_tDEk({G9b`G_qPJU$TIhZ)PpjcFHv>mKSZO5+AGW zkgw_*k>6^+x-l;t@4YC9!O5PHgT&QHYMT`twJ*?DwVlcu@$Lb~z&L&0Ng&KPecn|d%s74CVIa&neco*#%s74Cc_7R< zecpv2%s74Cks!=CecqiQ%s74CsUXZaecrVo%s74C!63{yecsI=%s74C*&xg~ect6D z%s73cyQ!U1&V|vr)GjLf+1pEHpOdz-9qxZ`UzKxVbUn4l$~p3OS~*|djw=|CDp>?V@ttNn1Gv?{g8@`&5}N-li%x zOK(#ZTc)?Eij9-DPL9FYRK+IhZK`4`^)^+pp?aID*jBwwRcx-_rYg2rZ&MW;t+%O) z?bh2=#ina)7iv?L@fsV8%p=D}n*s48O#3wPCrn<$c_B<5#Q7pj-o$w%OrFL0CCvFI zoh8h5Fg6^avn=O&lFkz5I(u7g0J|=2wgr~c#_MgrfZJIvbLi_R%se-{M)li876)A5 z-k_{Z*wA*$&Pv-0r0tg1`1-5m1$JznAJ#@b zs5tt)8somU_(T2t>)DLg!t-}IkCxXP`;6)r1@b#%15vm@9mnb&9xkj+I!H(Ot}XE= z9nHVD?-j`NjjgW@`?#63n)}+r1;RMDak+=39OqWbxsN z{XR~tqxtuCKgKtTeVJ=Y*wiP@<=Sz*c+O=VQAc5Zo3!IadxPt~*4Xqq!gp|3iJHt&Dkf77I}>H%$)Z`Y_p+tq|s8J-x-@sp+DQo&+!tJX;%i{>&1pIJ3(q|3^L%(%=)v0PNAq}<;O=cuV&nI=sRDVC zw^@l#z}vFKS771;dH+TB41EhGo{;xtq@2D5`Xo5dv|H0xL744(o164Y-v-M$&nCW+ ze&=Y7;CJq5El7X)Eorldg_fg!fO1_s!qPtKNV%^s<%BUmt*r0&17X=47(-Ov&wbw= z;p@j=Fuwc#da^$ayk2str))$;@Y9=961=8m@(78 zthi`gqTJ0fxN97v+~uMFgSdPDvcQbTF?+0F?5+i4k1ZHGE#naQt;8W1yDsAvq?~aJ z#tvLC_F=KH@>|+a%^ucr?rp8lya(D2?~iEv%#*;l2pPYRixAkyMF{NUA_Vqv5dt$- z#qvSpJ7~@#uFS`HOWcm{SNOGw{ciR?5s8(cznN>q7z*zbk=P3F6Oot;?-P+&4DS;u zFh;|Vzd--9$E(1Y4&%>i=KkjVXBH3UWeMzM?U%VVRK^fq=KW}y-Sg%7A&wja_c!6J z;?0b|GM1}7?(A1^$D9l7=UiYPgC{U!E_|Gu+-3IhZw1DQ__#Q^`|RW8f)&2R8FO69(O49!P;1E5Y;6a?ma2jT9Jki}@r42K`{3Nr6GPn151W&@INk3Jki{ zY{tT}�i|Bl~v3b zabx?OV;`3yG})JnJjpSk4&@CQD`Cz(aUjgOCvJo}_r#en=bm#x*z*X1Irknfq50ff zs1tCnWgU}d;(uiCa%}9^mlwFleOypxca2FOi7#mhX#`=?4AKa~m5e1LZDN~V#vm** zhA$U+-p8I%zRKiYuo*++Dc1?U)De6+ao5;3%2yimCNd%EGUtb~qK}ai8Ip9F z<&-UbOr6M_K7Nn#mEt8bs@Y=_v&;D>&o^~0#u#Zm=*vBUbOx?=RK%vXT3w>rD zduDi_#vzbSQ=cWzB5%@IHS!LPVG~*2^F)#5Jx>%_-t$C}sXb2=S=;kOk-%D z3f!ZZ!=i4&HDx=pre0@}wKlT7#xBYl8C^hQ9c4|8?x3-evIi(Puzil-=pb!>owP?- zyZ(l5^!zu&jb9iL4*cAP?z9Wv41a#kj^XdBH*!DP_Ra9!qqhq`eAUM8pHtol8)kko ze17Vt?vQD(hm*g&MYz-dZSHQp__gq%aPx4T`?qjs41YEJdeoorC@~}PJrQdm0 z+P`3%z1(LG{Fn5*@EiNM+iIVY@l2mG$PGN|X&L8>|NgX_{Od(B{waT`c2^v-C?sBE zKQY){IdD<5%JQsBfi(X zzOnoIk#7jT7GAmMAoty~o(|vHWKMYGtNXgsFMm3m@m5Rt#Xa|RhrIH1`2Abvg)jVP zZ+GsLXTlv1zA8NPfW6%BYyK53x#8+?Rc@gB%nr|n$Nu4(aP*VAx%KybE}T2_+Hhcg z7kBM(&xa>(dtLb32~}>B*)N3mjJz(!o#iiIznyCz^pey+^Qo=fag$z_cA5%Xxp%I7 zMcTjSsZY3DfAOmHJMiJn-LUDe$#@p-wwe3ZQLoE5hrO|hyY<=EW&8*2vx&Q`;SE_| z#p}GE>=J7Eh=+Fywf+eQZy#zq_1kS5YWqL>;wMAx_uieh40Sy9=Y1m7asKR_kH_PG zeZa?KyjZUIvcAp(+tK-9`#NvzSLc)C(Rt=Lb^bYiT^Fw7L;qUeEgAfptfRs_n|JU1 zA@|N^ugRYO{3aiE+hg8%Hs@ckfjfDFSLKXcaK=a7le@nnXJ_FP8@dr&yd0gWYc_G~ z{{2NcYiBIn+}%GpI)lyYZ|Oe&-{<9Qjy+{-x7pX8le0PX!R_2%+W#f>zp~Yi?$~pl zk#-vP-r4Q2&C}BU*2{KrPd)yW^n28ocXuQ2ds47c4o{+P- z={0+~T^2nqYq$P?_Hui-J}x*a%)PC3xaaj-o&{}_XGHtr+0ilZOzGHo)^yA~gNh5! zrsBwQ#hvwaPUMXHxnlb|hwNA9mgCVm=QwpOIDTCtuA_Tk1NV^^UkSOsFMRYPZpQ~+ z3Ayfz9{7kGIr){4`{Bs-KIXQ3>E)37&@H` z_kA(se%o}x$K7k|{5#}6y!cyNx{L38KIHyXyjcFZL$-4*dp|4n@A>2ouKx9Bq@DME zx0Aafd|KMS;*$g1Q@>gy{cgI;uI{t5Pt(bVkQddZKud z&M3Yt*Lh%logcQN^TzgdKH0C%GsmOz&vELyaQwPnTt}rd#8F|EE4~(Y!pe8vue^ph zDqSM{em%d67uQ zpXecRR~qYKgrw4_pGNBe%J6yA$sR} zsldGN!gsE52j&{Q&%A5uE$pCJ-+mjvvCcQL<*trzN9srL6#K2z@$YN%&d)Xa{<3es zz;+00JN!5QG2=&_cnpNKeSwQ@T3jrSiEpJJj={bc%y)s=r@re=m~UD0y=lUHN1Jcu zqOV=}zBb>YW;x2_U2npCbDM8b6V`XVIX1N2#xnkcKKb5vtCq75mg~FTgxL=JU>&y4 zAIn+BzY*4Vy*VDXp?&DP-u#yJOnJ$B?)+BYcV=DU#6AcUSN6enI0x*5FvcnGdb5ts z8DY*P-`>`8GY|5vH_O=$`ykBr`QsQ^#=o(g<6$3!*#`Syzid0TA7nhyUb6deij3dy zH|Z;ai+h7(<$mLyXZwUXZ|s*aapiaja}GF8!kin9l`zU=-3grR++Y35Vbo#ndjgxN;4x1#fI*NZUs1JA65S>NxI56&;q`+ps9M%?fBUppfn&&?N1j>q}%W0T|Y4_rPu#*5{P zU%g+(!}|9Ri(t0%-Zg)aa<>1~tso~bCI{p{GGbYCC?qkQg8$S}wIpJ;gh{k{3 zstGZC?4M4L>$9Bozf^ToyzYeAKG&VFt~+5}cfz{vgmv8s>$(%xbtkOrPFUBSu&z5{ zU3bE|?u2#S3G2EO)^#VW>rPnLov^OEmUG^;KIfCLt~+5}cfz{vgmv8s>$(%xbtkOr zPFUBSu&z5{U3bE|?u2#S3G2EO)^#VW>rPnLny_6*-49xadqC?bZ1=zi=Y8!u@48-G z(~jT|&Tq8m`|J57Z`CtPSkI%LQ>DpTZtLi`>9efgmZSN~3v3<2TFy2t+z}1Ya@M!7 zrA1n%;b^WB_#@X=*qcB;F)FN*|$w|+Z>#8x4gM5-1N?AZqr?JZuoo4!rkvjop+nutD7wkfAGg?ZqeVG z+)e|QOZjfUXmUr@EtmSgxTMLwyZ>@&XZ{II?nlQgm-ctxugQIT%yQ{>NL7=YJb8K8 zyx!D!%%7Nlh1>Yxyvv`rEd0XNSGd{Lc{lJo%fe%>zrt;?ZQlLrC(FWDeszW0dHuY* zX!f%3u?1JS(f`T0Bd=K&K6&pIZrn3D_u7ri!YluJh5OYbIk(v@%fjD1cZHkwhn&0o zx68ucw_oAL-kEbpFIW~XZ@I#qcvaplJTijsS(SG+`z#ANhOLh%xZivz8pHQbEx3DD zEtN5B{>_4O|5++ySZ`**O?YvsjN#5-6x^&uOJxkLZ3VaPKbFcE&iYfqJ^j#98N+3N zFSz6Wv{c3rJXvrv?q4dnKfI{me*TB0vUUn{eUH9;Klk2xOT&--WSaZV`TMy$HeMQj z^Xh5tU!(SOH*T{u{Oc{#+}0!Za}#%88vgY6)7-i{@8@o+Um8xlZ<_n|yUp&s{g;My zSfe@rY<7!}SsFg@z%=)no15L1W0!`5?w#gl{Gi#jpS?8vb}-F-^JJ8Ne`)y9Ur%%E z@89e;o4GXHWZpFQzulYNdDkrs*Zt8nH+&PcdGpfnzlF}-d*PDscSlck zPhR8PFTaQKuS|7M{Mfmh9ZXsC(jx#o_F`rn(7*q3-0rE)Ku-@KpDwgNC~C ze_kAh&rEgaA2HN@@`1(SV{c7$g)aMpSx_=!v)ID(T;_z>qO>@T|JJh{` z^80t1=I%axs9S{kcMqE8MjSBIUHX^B;S<%<-GH$}+`p@rgungB3^)FUq3-&t7KfkN zVul-a$xzqyo5kTt+s$wni5!HY1`5|ucs>RaI z(%%npmu$Esd}qaUcg~z4?)+_+gfss=-CY6P#{&0V9xC>G$Zw~+MaK+rbDNfg56zzL z4mxy*J8r)v;e{7XcMA?0;@aJkaL`G`@>>rs*1vV~bhqc8!`;kf?P1;J)7{WFhr5?r z+QVJGJ>6~d%y4(pwe8`GbEdoJ9~|!f`pfokoinDpU2Y%lw*6gu_>EJiyUFv1yCHYB zhu5AA_i5k``e`9?!AAshlNw7y916L?p8kA9^P=;ba&B^;qJ=U+rzKj zJKgQN{RsEg_u9jUf#cB!jc|LN)gBJoXNJ4)j1lhYueOKZD$H=3oj1arcS3vktIuFQ zzcIpX_oeo*@k=w@)Qd;BpB&#FUO#?@n}6X5_dLqKef|u0<=02J4NhziPyFEwcl-De z?!}YZ!v|;1a3f9_;l6ZQdpPFW8SaKdN4Ub7?cozQ&2T3-jc|vY-ySX+KGXgD_F?Xe z0~d#18avCqxX*C+#*+4M_{p=}ts4w?>wb7~xc-T=+;^WF=C0amarnohXSowX)ZcA! z_|$>3+@5oXxw~r@hcg;xxqB}j=B5l?9G*2`mTMn3%x(Xf#o@af&2mQ`JIqZwa&h>; zl9}$*Lx#Ef;}(Y(JUP={He#4N;7e%p&YAA5;ltczfRDd^rn~f@VQ!-@E)Ji&Y^FQl zsA2BUM_~+S&vbtrGt8|#ba8mX=$WqNeDpgU?Rf z+y&>2bbopM?eIgto#nPWd!+mPn{S7O>t?wdP9N#6d;9J1o6~2x6UU5nw=8=*9QplO z?x)9$bcetDcKF-{s55e;JK{s_;V-7la(h&dbQf;Y9=yneDE*aHJda+S}o>LJ_Y2`s{cNSAKVPJcg5I%#O#f!_Q{NV>tfS+3^^{ z5Ow?*mfk-*9z*LxXy1?FnZM4C$1vjWsN-=btm}Bssw?C59q{^<@mvji;>vgque|rl zcy7a+u8ik=pmGK_<=muBDd*j}v zv*SJU&zEM$duh(1+3_Cx@;_(Cd+!gI&58Hw8JoAnXXI1sw!~+o{p~sN85#TRocN5a ze0WZLMz*_iPJBj&+%hLVBY(eUPJBl4Gv~x-wBjU`E3H`ZNJ~sB-uPonOru__Yl&&> zA2ymB)86kbZE<%TJH$1C20rpsi_3j>h|kOTwRgy~VwB;t*F=wdYv4OAySKQi{|s^8Ub;A}-nqq1+j6M8?}f$Tn>)3*MS1W7 z@SUdzw79oU9O~xZwK#lZ&lY$8w}-mjZbA7b^I|@7%1`IT{Hyu9^J4z>;q&Ij{OeN_ z=EeN$xi8O)`PT!Vofq@3k^9Yy`PZNKnHTe~$G4vs^RGoW&x`ry#ShJk`RQk0n-}x( z@4Y=Q=HuHfofq@*R{$#?e{=D?n2$HUH81Aluf8-d=Hrb|&x`r^DUZ&J`S_#v%yTL~ zEWB%OEDN2m`8=mG(jCj^#`4C)PtT3zklY{U#`4MBo9D)I%jGR|V|ixArE_CBXS<8% z#`4b@XU~o0qQ}mh8_P?l0aiI`@Ym2Tz;tRL;Ep()mv1%m*%+?^Mpb@9XoO%9-n*I^U_B`RW(v zJC!q^KV-gBIrHap=R<~#Z*vSPZ*vSPZ*vSPZ*vSPZ*vSPZ*vSPZ*vSP zZ*vSPZxeUbO}LHG!QI}lBIFs_?;8#7f_+wmJR`@z!F?y$F(hdd+Gwr_No zzqCB$+5Ft68r)UKtq6H$?|G=+Ejn*SNLumOCH3xvmK7ms#R;d^yDfgUA|$Q&-B;?} zcWzn{l2#mdM7{gQtt&#(it7)mcmKS7MMzrl%J6zOwsl2FS}}51z1uZd5t3FsFrwal z2<4;|qYkNeo1;Ey)U!v`yRZCaMM!$PZf%46=;v01q{Fu_u5)maC zSrHaM>zaquyN%n>4rt(#Q|jGgKaa|9{7JpLdPY=#w*~d?zu%79`SjEEZroWb!fU~6 zZhWuaoqqC)@FQPnaX$g>-vaLEPi%?%J^H&X?!b`^?yv(_gpXd;;+{IJ!Cf(YMY!|t zTij_!G`M$$t_aU~yjcFm;$nUBk^i1i>yG-t%8>l)g_~;J2G6ey$-g%GeT{QZtqjS( zhCN*4w)@-4ko;?%f7iIb{c&YT{&mZLYurtDtPIJ&Zuvy5Yrkz}Nd9&B-nH(npRWwb zzn&gZ>z2-48Ipfpdwi|?{M3~p`R4yFta0xxUm230K6FHlyKBQ$A^G?Td)Bx^c32gX zk8fF3k3@LA%KDE}pe(uVUa>$&8weB;gt_&%k+_wnzzqm4_-16UdYu#Rlt_&&9 zd}Z4@clMB#A?2K!!FBGDx|Jd2pGQX2;asc?DHkm~yw2Ue`^u2=(zIji+;zL4O~_I8 zU#N2@0H%C3{fIjE+-@sF%3V(%Q0I2qdu2#@?2GkvZfVWRkaF60cC2%I?T265CNq~ z4}tVLsU!hK6cND!3M$2dh)7qIrYHzW2ni(x6u}0fhy@QIQWP7AQUnwQEMV$Qy#aso z?3?HQHsA8Dk9RG@x8DC|owd)Iz4zI5=9y0Mw!7Rjywbrr^T90Db#J9P-%f4b zU1lw)H0NH*IB&BKIB&BKIB&BKIB&BKIB&BKIB&BKIB&BKIB&BKIB&BKxTmn~kog~R zm*M}#y?}j%`vUtA_Xzea?icKH+&lO$a3A46!aarm4)+)SQ`~F#uW{eu7{EPGLBW;2RTP@ALJateUNhm_d(7P+y^;Fa3ACx!F`Z(1ouJC z5!?qkM{p12+{FEqa~Ahvt`)c!bFIL=m}>>@#at_JFXmc-dokAv+>5zZ;9ktN0{3FB z6}XRcjeUmI|=s=*k`zB!9K%13-%fAS+LJ=&w_o1dlu|7+_PYx z;hqKi4EHS9XSipB|Q*rN(xi>@Re-$BRF{RG-=uEkJMT|6QTw>(Cu3-6or0$QW7YpV4ep>1+kLN6J z*BNrljS+J7@=9Z8tIhh`HfP8WPmPpiH+%HDzmJd~Gb@dK@9KQ5&)iC5-}|Uuq%_pE z6#W))eWYAFUiUBUw_idcWyYhG#=dt^??}lWs?W9GF1|lf-n^^Q*!OOKB2o%<4Y$V$ z(N(M8C&I(>%!&ewN=Je*<@w79KOEF*eV}XdwyWsDr2i$kr^&q+f^A` z<#`Lk<=OUC##T8qD_ri^=a>sOcTp6i}wE!?SHH@!}~?Z*Sjl? zo%64N2-$w5(%4IXy(~iREY|&6*OTGL!{zVuwJo~Nyz@!81YJ{Qo>!%Z%g7E@ru@`L z!=+I~mHE!tlyF(rtIF78xxW3ktdsUS51DPjUhu*8P+42%X(RUndyla9CdkXq50#;} zxQ+exT5%@!xGjWn7Hg*o~d=Q0W%pHg@Atw}wjnE^cEt9yL5v z`m}NzyK%#3L*?dc+{SLaI4e|cyVPy$#zWo-mDP3J#y-sR0L})@p9zuIUT_;5^8dDX z+x>&R{-u>6a{V~Bu|+$3LgenDZetVX*#qa0NgssB-=ogdTifRlyIs(=du)h&J;!Zq z;8PzD5&wB^V*~F!Dnve18E2ljCqiV{%Wh)>Pnr-S2`{;g4ZQR85P4vh+t|RfQ$ysh zscvHf4}T>@8cy)EmuUyPT%YG~MUY}ZJY~8N6!sO$ZtBei&c9qYcS7mJD<5q;p z)oE46Wz|>L@>`X$?N@IJm3u3yjLrYQ`J8N@`ORIRrd^Ofx+p|0-RL&$ z<-Nd^sktlJ_Y}wvj188_b*hbz;9TBWSWn!Qc8m{}iqksx^{x~?HCSG8yNz$+*%yN) zv&?OL6Spo3mdXOR@lAxk87$?$xs7k)qfNoG^RV0aCS-50e7MJLd=qU7f~Ec!?lbO& zxF@o`@Kf;a2LADOV+OO<-LNE76*v+^5q2}~kFc9@ ze}vtP`y=dT+#g{#^8!N%(JfD54LUDE(1F=&-}16 z^DY28Gw%p^&btH3^G<>9@U8(nGw&d613NSCIIuJG?gKkBpTo|~ z^01ThJ9bm+GT7Xf$f`s%=`Pf^i$aNgkIjS;UD4s8vYU9ui+oz z{Tlue-ml>w;r$x^5#F!iAL0Gl_6I?xedcU@H+KJ^JZ%*4_0V=<`<@`v4rA-BZ9kOV zF6g5D2R<*_f8g_?{RciT+JE5lqWuRxFWP_L^P>F+J}=sT>^8!0_|l*#x#^FJGkkEi zKhZ9e_(ryz9vda!9ur`lB0eQd}nWVv@}#d2)=*Yrf6w= zllm`IZ`h$|=_nNr>a)tFIK99MC-p$K6kI6cQeQ^H(rlS_g-BTY3J1Q?tF9KwQ-6ou zmj6cIsO{&q+XY`R+h~`ueZ;nJ8uAy}A`5>jch04s+O8+`4wxx2v$))We|*UX;I<8KYn|2k-}CL4*cWo zt`T{+ZG~gw0U&?>T8vyiy4*P%-@V;GDF1Aq7@3#pdADV`NRv(F4%$NO1mrmZu~ILv z{0zOdjYF{81zpLTVx*P&bJ3q)?~RegcYFGC(_b;N^EUNIYkxjnH&)71%1wWczcN+^ z$CaD@47wp!A|usTuKjs)r&!~2M}JP}7Ar1om)%B;F}Bz42Rvt=*k$0~UmdKNobKhu z?|)iibV-XL~E ztc))8;1KTkIaY2t=D{aiQcv-Cdpx*>ySv0mpDi9dLqgv;xqGb#=dkgqIH|wPgMauz z@q0T{J-CRaibcF=Mwx>(A#t~22q%=8wc@JZ_1#frW({Gx{u^;JSoes3hRk+h{SVp} zFBdlOw3lV@oOmJZN5mULes)%Z!G51h%#vMC=zZn!1o=|2_t+C(9FQPsUnq`U6w6a`T>eS%0Bo zLi8L(Y%}Egk0#2=TS^Tkg!pG)I4-+?aIR?CI#C{dywqSz(!NiSm8qp?;Lvb(s=Fjn zPK0Y6EWNdjNweDpUDKu}N=Qek&rX!j!%7XNC1Pcwj0q|=n3l@7 z66HwuQiEw(x;jzXsf;t*wfa0MpwwVmrmjeo@L*4S*+!gWfBqyv;+LM;4|q;ow_OJ3 z{6%jji2IdNgEOhOEJ5C1Rci1jPh}^_EpI4ZNbd`Lj(Y^l<9 zG3}5~$0ti-eV4)f5Z_+gm{q%;xL^Mem@Jnzav7{qZmVSJcCE``jecp6EaO_c4A!Vy zS&}U6;xbsHZika(K&Z=LjplDnlDp$w25WS|TS?Ntx65FSq8B7d#hosLDI$Iz_J?WP zlcml#iiy=RMvT2L9IxF!D1TLUvOIsJ#Nd~H8J#RQm6jMB5i#?y!`wJGSyujDa)#d8 z#w6SAg08Q=O_qIMlo;I9^*?AI?$G!Vwg2?pn=JX;OAKym@SbFe{k+8BrUrhMEDwBH zVsKMqKTVc|T_pxLRrkGQ`EYNE!A(81ELpOC^0b$2giUPNWl6F=-E~Gk;5lOl>@u() z9{sC_e6vhrfA%kyyLb1H8&+%FklGt(ecVIt_|RqWP8Yo1Lpo`E4eXOQW%rQb8Y=|5 z<(rv3u6|SPtIe-Yk`Ly)48E&JXp)?M)@5*CPu!CvgGRdy9&Gt@Nz&^+ zm%)j#UH^@kdDv-*|A)+WK|U@ivLvg-wAU`f*a6tm88-nra#xCU9#CR%WsIRX7x4?M zC+zwAzDkkR14|5^ZP>OHIq%*QgJ)~`af&n?QeyCIecnuww}+P)Jln8EDYEAA5`$+u zJ|jgrBufmQ?fy|I^4GKygJ+v^XNoMHTXII62z(!G@7ct3*!_d@_wPxOPy3e`j2vb7 zp4hjL*)Hf}Ki77Airp^gVt>Nl#Qp>}kNpX39{Us6JoYEBdF)SM^Vpxj=CMERHbUmu z`=9;5v1gY77LM}~eoW3&_%}I!fvMxX2G)-A9T+^W1Hk5SeE?>U>jtoVTu*@U<2nQX zEY}}k0=X^$E6DW<7(%XN@c(jsgI}0yBih1t{Wr!>p)FkZ>~_H?&b`1cgXi26?f5mw z+<(tyESp_V=;i(h%p~_mU?#ag0zbh05tvEtkHAcFe*|Wd`y()u+#i9d;Q0zN&sS#? z-)Hv^%JYl?YzEIBz?SeV2bt$RTW@X0D%$OWE}q|j|K#}%_)nhSfdAzA4fs!<-+=$* z`3?9_p5K7~*6{40nd5XwaWl|$@4!jRJ<1eL&f_7p7S1o^1NT*JG^%Q zqs99Ouv@&R0Mo_$3$R|i*8pqE`wlRuyaxfB%ICmhu{$dvxb6NydD<(0?W7$8*i_nuAk%ha>#gmWbh};9MOzSX#k2(h zS4>+F@UgT70Ut|S5OBq`1pyyRTM%%?v<2C11cw0aW_CZ=+yZtPa6v5lHcs}cEfHK0 zAHN$XpUw1eIK-vK$tMdu+zug+#>p)!Je&_3dc;ZTdJh-Gg)QQw^B11yx42^EzJs3f z-+dV?7i;ViI3+%REmks5d%l0m%vhO!S-IhY7(OCao^DodxGBnSi0eCYQO9#c2061!c{MSm0e zll~_3C;d(6Px_nCpY3b>P3TYho6w*1H=#f2Z?fBnF~;`V{eb7}6T1xNBmI@&mZ2XL z^O62dtS9t)Vm+Zh6zc%}q~MmJ{}kLZ^s9nfhW=JOrymyOz5ZGK4*j%xUjZmJUuE~rheup2fi+MzN(ia zgNJvOc^bA{k%cF}JR z=SlgBVCj_Na;E%}CmEjy%jz(fbL?22^f(zTT{^m)9_4v*sBWlS^j3+HS2Ycj0o_VW znYgYRgYcg6Z0Ng%w<>SaE5+uUFOLbA;047-SBs2r**rt}WV8;~uZWQ54T??Ol2%7* zoM4fubMopaso$o^v}NtrQF8j~BGbmd{)&=%7ZsVdS2l>2wv~mZPqtP^%kepdrmt>4 zEOJrDLeqzDua1#nI}1$TZr%|i-8L1NKA(LgMw+cFF#qD>su*eadV%>z?bpW2H+L48 ze^;-6oXl)kVE$?J(KtEzb-wx6(_L}$>h^py1|GX0US@5|H)Esfs(4BJFyD-sq0hxj z!1MWLEY02*FK^tRZ^qa=jT5AAQob2`>DML5nuL5aCa-9fAW?Do4#sNRb_r50`OfZ1 zi==*Rf(!}FcfQ<|<&_uI%kq}F%atiVDL2a}Gyg(<6S?NWPSPr`!WlVNV@1Ast{S#w!|4XWSLy}O_=6RDt0zs zvP|AR79roo6geM1nJ4caijv0$6*_xf%aw~)ij19K;Iv(pBUgmRO5LCGotUZF^5@fW zGUVobrz&`<>>V2~rHB4CitxUYYQhW4E`j-nHYl#7qB= z|8hcaQJ$R2IQg(~z7wG5>bB}%ejqL1dF!flX*e}T_IE3At_n<(6~9Ew$A9QQot7#O zUKJ(3eNgBG*H4x9*GEWpW|8Cf#eDhtsxW!|xnk$Gt@Gulzk_A&6A4z4F>L;kT=$@h>mlmEbrN;s`iVMoT}4~C-lC0MhtYPf&*&4b+vqE<=jcPO^XOZy z|LAk>3-}k@FYu4JkKo^Nf5AWHzJq_w{Rm@#`xM3o_b-eY?rRuJ-0v{PxDR6Naeu^^ z;Du{8Qi0m5{XuQvHjSt1xJ9Hvk zIivI(qGR%c(g^u>OofB7TJORr>0DLrU~K>LNR)iAv)sYh4(t^rkw2C@7~ARXqvZWR z%N@*xiO)q#nsQS>PRbHFw!6%{d-&}b*`)l0_~u8~C_YE|L-1}FSB!ibT4ugEXIG3w zCzqKzY-krJE8i|Pbvx=GFIOwx0Bt$upCAj>?}j#J%+Wn=vCFjO#m5wXvdU%J*r!i| z%vK*9`ef)7_0e~8nZ7CXsxWkCvD|UokOB*50ffMB2CQha|~scb1qw zAJj8RHmFYr|LC)TWVySl*!;WY>fgNbonrH^4?K_}6GrQKL&w0v^c1;XdBgCpFI8X9 zRYQx-7-%&%MY@kHHe;sF`8~zyRP10Zbr{%FLN6$GF!pZA=qZPPFEVTO<`q3<+L0m$ zWAClJp0eZDA_rr#`;wj#b-c)#GBisH-tQ^N2a3#ier;1v$yc5??9s=z^pr_^Jo05B zH)%Xhk<<6}OnKqLn`DZs$XOP*P{xhzB`1T5o#2865<0u5w8}1a`hAiv1-(+_&n_iS z&vm-qZcdV-gC)*&Kc&im%0xM|(&gM7mn!?~B*?_srOt|<=S%0`Vx@3mnRDHy`LcY2 zNd6P$=6Q3)e4bRSCdxlLK0=1vt=t;=oq}h=q)v2|`Mzs?h@80CZS)T48Z5;+M^K+D z3Ib(AaG$S&>vOw1&s)#RyO#;;KV8ouY!{xhy(rIqz<1a`_&)m$dfA_-5BnMQ zWdEc7{4e--{9pEe#5s-sxAp!--v5p@kmCgR3yvS$J2*~oAL01Hy@TTo_YRIj+&egK zalhbr#=V2%7WWa3XWTnD{&DZ%yuiJK^9c6~&M(|MIFE22;rznAgYyyh4$f2DJ2kRHATz_!y;Ccm_>lohUx`%Ia zJ;b|Q_wY@who}SBPt=X;D%!$z7;WVGjJ9wcMjN?4qffY=qp!Hmqi?w{pwGEqpl`V^ zpwGEq;2&{+!N23agMZC^3S)r#7ydQ(DU1Q`Ul=po?=Y6Q4`Qs2Jl#<~9#&!IV}938 za*3WlG0y93>?DgD>3u=Rf9&g><)M}34(7%4e{_+h*Ooh&FKx$km5dQ(4(8GIk=^8V z#eiXcEe#A%{vwxyd3ST~AX%vEHs<4Z<3c3!yJGYF?qy-J=*J>c{*nz5a-;Gq;yceP z&V1G-h35OyCW|bNE--qpuNN!nbMj4nhV@XK=jp#pJy&##my88}nfiaYDPB6<;koZb z7sboin7_>W!{=B(Ssv>Zzk~IY-^cn%y;%2HAFPM0C)Q8aAL}REh39N9%CjHv9rh2t z&whhm_9yDYenvgn|5*R|U%-Pg_tr@HaAlzbehlgb-vyt82g82eG^e|aKkYKS8I*%> zTqHxgr^uA&bstfA+nP8jJeKd=&{ny9R4!6^iY4z?`LmkmD082_`?S7`GL%u~{+e$- z)Aav8hsBZ=wu!MeAe_9IX3n-D0O%LY6!>x~JSzse5j8 zmUMWoryMCNa{Pm{WX`;vGFrJ(n|02TBa3^=eY*cHxIRl3EZ05v7v*ccO0fa2^^_Fd zuW_E_nrz>>pesXpT+0XL8(rTP#>=<;^Np?->n6w@ee#X20>z^qOVKi_D^c(7d-VPe zT@|hMo*tWTbiJnc_YHb~x7YuNJ8HaSO&u<2q5MuYb(_&>vA52TU!?q*HErqrx88Yc z+BlvN9vz>HWab#diadUAv8mh1^(oR< z`Cw7!H-1TxpzvbTmhZ3VDKEFx^42(yy+LE2b(~Mu@jtlv|CfD@d3#RbUCuSUOZl>% zS>FDH%>InNHA`5B$L`7U)~&B%W?1KEo>RW8nzoEuoaJrf^z~W7wqN!`mbXt*$`sR5 z(^r^}oNM;ngkJtf=;eQeUj9eu<$r`;{zvHLe}rECN9g5$^x0l(uGw?k9?xftH*3t> zW73|#XJa$5=f1CVyM4}oK2qZ)`=-dk3B?ZNt2Msh(!Kf4Yn_%#-`C=#)1SJ2HeMPdWm$rFHTNfQs7KcT;+7#zkY9A;FN7%BAdI%iPN&c*^swH2HhAZDQyd! z#Z#Ba>o>&7&~^pR(7{@!O`O!dvB3FVmdL!Wanj`mkLiN$S@vuzHo69_O_pApb=}rFwAz*|PkvBr>bC9YWSRY@KG!^)3b%tKQ2jeAvLB7$uGB93-zmaeBhMylVjW*{Sy^VCeTBqw3^xpA$ob3Kx*C^F{ z)$};Yugo`kqld=H(u)g>-et;1J?(1W?H##lvE2Gzyc`~_=Ny&ugL=xtR~I|O6-ylR zSDYOCBL9r>hUW(#O_9-$dd4Bgq-MYTKVCYjeIB~5I}tDU4%EF~b(Y4|tT`T6P{GrO%s%+0?l$omYI!)&_%Jf%x zh01pS;7&?AGw!6cKilUDyKjBnVeK=|lfgOix!P(5sjUWbmtSIJ_j?7-3(a#RWpj)? zzoo#LP)B2>SH#GZ-xN3{N3!LI)EMc#ufX|8W1SwI86yV{6*yVB*|PT87%Bg$z!{>P zw_B#iNao=J=lCFvdwn@Zw(i$=W3uIoyck)!tH8OrO}1S8ag5x)%_F}WnIu0c))!@l zwN8?bnoj}mcDy1<`c78+l792P3zMYnv&wy~y84`#B-5T#46xRr{zXah&{Ta_>o(@9 zB-uZ)#MC*meUj9DqQtc2SX`1^{ZNVXaO-Tzh)R+tRaejJHO4k3N%Hl1yXM*QKths? zc(BAd@7iqHo|GiVhI-_V+cXEk<^uC>h1U7^tp(=Y`!~kO{ht+>cei~SBL_b%a2`0Q zaSHpAC321CL{Ry-^5n0+tiZYM8;zrRL;vq*YS-GP^Lk>kG(4cTtS!pL-7{I*78X0% zTh(9LG+BDqD{+4KQu$+lOOoR2N}S90FO}&ZCdmTz-&OswRCdlyQlC_bb%D`)e^snJ7g}KS{=Gx-Exikj-bo8% z<&&WWMsI^*vGU*q^}(s$-@+6RGq=F#?bELNs!+o3C}QLJpsDKNT@UlA)ORfevi4PvE8%RtwO^JC>> zeb;XLyg!%9YTXAX={`8=r23$nq)5kf9RnwnYeM(R&vdW+^*5EHbg!SL=Z7Op<^G#f zWaQ*x=TiL_A$O%n<{!4*?kUOjcWEj=z1eV_r9Whqigi4I0^eB-{>0s zvErbP6oUzsvVI7wj?isE)TUb&g!IxxiVk@l}JwI38x-440 zt0;6DkIt2ty3sP^bfM$wqcOtOQSw}!B4%4nh`C7w-h?f*D1&ND;oRr zW{Hu1YNNRi)CSccNA1tg^pM7%XbjgJott;`kewO}c2wcCG#!c?R|HPu4!R0@?xDr2lBWNdq|VznwMv@ za@YGuOZFdyXN)&Izj=-3oq5SK4ml=mJMgZ0d2*eOfsHx_W}i|XfK>@n|7Dl6usBzu z-c67Lvt7>gnR9Fm%OtjFu@U3yrRvfN1IcyV@94SIe+y*>|ka=o%j$Ezv4N*OHKEnW1CeZu`ca zIa0p8hjLw&IFId89L_%NlLaNt*gZLN>4_e4;-wPjZIut6>LJfg*ZfU7cart|kf`T} zZ@*No`&LPkqvs0St`3?0al6lHUUC%im=s5?vw&cdhRl5s(&INmnU7_=32mMJ(p3Yp3du=bzY;)LS0Xu zR@v?!*u#k{fSsIp1AE`J`_`Aw!rs%CUJ@apeT$tjI(|wz zL`aiFy_>Ahl{U9T$k;&LXJ5^g^VN^`@eO+a%FLD7uSUpVy~{vuuYS@K@RMqpyoy*! z-coAb-Tbv;U=*)~Z_Zm4E6b0U8eLT{#L5!G=u*^A6b**k6CsC?vS4OV*`^CvNjkC^HPKnie2ftP0uScfmieFfq z99-d%UtS*}eJ&_A?_T*@gsi?){h|79>YK_5e2JbL_1#8mBjmGs#m=_6dD45W-uq5z zT&K!wx<^T{=9X%5Onn4d@p9fJrOxo3xoR(omzGU5r{20;8PzXdHncBwCN0mEj85?~ zCZg1d(C=TZcfhZ1DRoZF$(2jKij$rXlsa2x=gNx3aWZ&fsq_6yxzc)MoJ`j|ch_j0 z-w#)Nh}IeMwI4=Ej@}KScUIFV8T(L?(Oadt*ycZ3Wc2R-E>gP9C^C90Rz=Eh3yX~2 zrzS^A+?z#4?;|%y$|swPjNVJGi)@oy6$D=N$i1e={cUcCsumv_ibHv zeV~i@8R+V?GF(~YPrrn+w16)wp-N1$uizHn(iT#-jdzo)hWyX~u5=1KPF@zSrv<-F8h=h_cyEB?#ngml$8bv#~zj=P+G0eSLih2}v! z>~h`?%#-n#Cdd)Z4;ZY^JGM-a8DF^!_K*HV_~VERvilsm>hz3~9k&)4U4#2a$ydFK zjIO&LijtKHMMl?+xl^g4PvBxCJ1ct}SLpnZDW{u9TJeBRaZ?6fMr<`joReo79kbmmDi&VLR%58Ps zu;(($bkTYJl+J6Ed0p3&H7eWv1HUBkRPa|4XJzl3XXC52_w?O)`tQDpk`X!O4&=M~ zgvi0_66f}3^Q6&TA#!Df#?lVSljui6q^O|8S=}Q~9+?p$Z|iyKye@fi>Xi_g_k+fj zH`f3AMTit`Rjk4V>YsImNa(v7S6h}VFSZJmgV`lcTE4Cuw}r}mFO)c=PUK3}bD`36 zj7QEqU*!A7<)%!~?r1sLx!kYr_4*rQ*_T|9yxzOsC+ZB#Jsz3dZ^4(n*iP&JUdj}qdao^d7<*4;#km!pWmeW z{p$*8}IjoxMp!eniQjziV^!q_nRR_zA(kN4afCXYAq{Kse7g-M4_ zp8x2s2$gB#`HuxVLZyz{4Scot*gE~rH(~P1;bI4JRUf@`JzHkvjyGuzpwpgrIo?oa z`_3py$@7duj!E0^AAMZM|1(i?%a(HIvtRS1z2aLg`?%a$bU06QqDIMJ&F@o3*S&#j zqvW+W%bfvVDSp6FeAH{@&h?+>sXZ`C?pt1N>Ofu4%lg>(XXt9IxX@2;P~HI5^+KZ% zdA6y`=vvo0M83O1F`}w#L-!E5uD;9YIuxz*;sWKYP+gOfLS#=J#Z+5u$Mco_)OPVq znJJ%iui~sGm6`7h8xbSB#+I4yKQ=x_t{qio^k%&fBM%QNb5Ng#n)|ZTVC_T2LJ&s* znRrO(VxL1-{XLqC_F%Emwd!D)yt7Z&bFK5|zlTW=_1&Z2zAe`>U#d+>+gN>ZxE%hh z*ytL4UASa#C^lpMpXLI_KgZZ(Dxat0tzXR?8K0p!n^Z;_j!BfsX(IBoj!(?N#wxee z`Gqo^`;fUNpbY04u zTVEIzdr!w1Y0QXlS>IOk3aR|V?*Y>Jxl(g(`MYkQ{HfeEI4`}_Dp0;2?l~{LmlP=7 z26)a(a~=8cu{S+> ze~@h2?~&{O5+S`OSD3R+_B#>cny_a8X?!NtT5kPujg2Qr^1|(-f9^kZ+xfu zp7hMtxhPyN{Jp}Qscze@IUuSkOr1MwF0i{U)jSt^23zu6xIA@jrP)u@e~pl(8aIJ+ zM%h$3H7`;U-MtAeX7FjYmHnH68)q{esWBZtkD<*oJ-4w1j!XzXT1C5@E}?I zgUh_@dNfGd?QxkiRr_s`(({@MBhT)kc*`*^a|X`W{KD<7t}tigKek88Ga8G5^L&?2 zBBgh;3UijOdOcDeZ(U)|*xTku$~wOabN240IW@kItT1QtI=v%hoZ{qhR==T5q;wx# zVfOJX#aqr%ye0PWYK@zyt98ab;L~6`i#ry?bs+-I=-lO13mMn6$MGpESJ$csx;@W&l1Ds`rt|j=dm_@!=5w&Ps7Zeyf$zP7@gS2uhbDc>sJAkMM7KaZ4Gb!^~#yF_zO?@~@e zoU!Nq5-I7IR5&;fR~AP~^m!E~K85%(%w^)h?LLRDCNUZ>qy3+?Hcwi{2TS5um(dm6 zGgzAH7=W(7Zx5CpkGhPm;`@W;;$dnlQ(gBw5iIWvcKMtO_87x?Z-S1uNF8rD2bSx6 zc}iuJ;h033COSTM==emLbe&)4>HNYvz`1X)3HDsWd3B7=yPI_0;T&72>&8r#QHFCF zWg6+c-mCK(W#;I5a;2^(cK>{%`vvjySR09}$C^pJJ<79hQU0H>c_>dTAMACBiY5Dd zY?ZOsy;kNgW4fG5ue+XK^?arFx~D_B%ZS7>V>iotpu24MFEh50J73oPWz9XZ>+&#( z*jQ=G$gxnleRrjK_qz3=Qg*!3eDm#@p^{y#Ia!`my?2DlmMg1F9k#a#mHi#6Ox>K4 z5a}mXrp__jLNpg!m1)a}B_T5O!75|VNo=I&BB#>WEejfl$(#+9#-6#PS(rTaQKhk~ z+;n}I4En$$zm?rxb~P?D@2;5FU7Bc}VK2RHL3gR!O#4dhsHZg-+n-Go%dIx#l@r3m z^>U?=FVz^9;hNVTHrS`;gvqtDDvfRSsOFNG{jBD9Q+x8O*n%woTPM zdTQg{J1gy6Z_d+UvSCi8u?Y`*Q1eq{RT^9Imp#Jd#@8y19ciKFxc_{;N3K$= zTC~;~diOO5kU1J>1Uq)}wE=SKaH-LIamxTXbg1|5nXUcY*Kr!mhaY&+hVRNvW|nj(u3qz!{as9{A=Ff7x?T z@8CN2INo5p>op`q?tjKJ4ml=ak0Q>~*Z`}7W&c}M#$Gq!(hvz+QDy9S$6AC)`BKfz zp*FquyM@S{1y#oG=Z@EJ&Z%->5B%cx5IHoX%G80npqKT5F2;!%8{h8-gkVTU|8 z+h10mUv6|IFZGv)-DO5s(>4B5r=-m28uY2ZeE(;e(beTUf4S|~vNPHayXdS3!ep5K zJJ@F5xIau*FRCJL+~_Hzui!GMvjOv*(I1`CjKW$~>U*MY^8Y z{ewF@F^OpCj?3K6K>-#&i&L+)_kM)W44-5LJk3Ga55s-YUMx?l0eN4mI@Aj9|P0Ni>xm@$HHrrWcSjy(43@Cd&VKhq>XQf z5BkN;ffD_u+xUwIe-kJTSGbKIdF@YuvN>DFfcmo676r64@|(U3{{`a(AT#dI?sMo`e2u@n8d`32wQ1-tqau|f zT6N`IqGzP&a-*x4%8OKnu6CFC%g#Xw*e*BMg-MCd{l;K=P znN>Qk*Xz7SnLAZJsIuKZXA?(n_pPs340}%pUNQZGK-pNQ+Taz-r*)CQK@|o!IAC2D zX^~Q4aD#`Acae(j%4e>4#okT)q)&6bV=7*8Y!5$q{h|tk8|?nLpUl;<1l-^l9Y0U# z_yJzA=XxDid&&)N@aQf-IkcnPV8a$4^OH+AdE~H%f+TZ@+mv~>Z;*_5*lpfD9;)Mi zoW^A7H?Pp~e_F>sFp6In21>JqZc~RVw*^Y*>uyuGKNkkdkB-~adD5^znXb8?fPpLv z4wO}Yx(%M~Bh@uXbpf|IRqx=b_qz?Av)9NV*><1X;L5IfBuFX-d*lfx{N#~OG{#VI zYb}oZ$*zs%=G|X^^OJfi14sJiAASlYZ3(-+1ww0GZpa+Tb3?Z4Qu6HBJ_I z$ohM<%r(`f4%7v`tPgZCE*QEx)bAp1rdJqUgRbf#bLUkUU4LKSMSh>HwiLxuKJ4E` z&YP}$8j7(z5ZgsU^v(!fkKV3j^sZ{R9T?O)YU66XL31)HUUc)kK)L)=w*wsMw=)Cf z*=?GeZ{$*WdupKKdff(h`ufv>((Vhl13cw)-5qhPLpN47C+N zSKBN6WZLz5pH*Ff%J1Q7Q(<&9s^cf`wo{vr;%OV4?jnoY>wi&QG5S1Pp95q0PjkT@ zW58Q}rQCV)bcKVsgIi{Ik$dm1a1eJe{sZNsNUCrUcM$rk_H$r`gSdk!m-xwKwbvo;U_d87 z*?CokgSdl=L_hgO*Hy$Fyf?s4F8{mSLEJ&32mNGLWx0bGhfO2=WK_9FzW2{Ssm^kn zGH)LXl&hDx&AWZ~2g>3+xB2FRt${L1*GcFqeLYa_eBW*A&}?>~T)fq7>b7U7j<+A& zrp}GS110efw`t3X`hoJtDJ_rKCDm1>x)AqqkIK-Cco51a#-yeULW z1-%#`7wH;{7_`i+09n{g%V=!c?XL$&^NyZ6P?udF=pttVbR90~EU#oM?}x^Y%`NXN zrz^pVx6IjZGkSf5xUrRUvt48V~97z zyue&Gv5GbG#U7I=Gg#-8Tj!dIRjip`SO++6?KQ!kYbGYK=9`E^q%M0do0!C!Z=wu! z+5K}iyi#`GqC7b(fTbswg}tXYsk_j7UV_Z?QbnVM-g8Uq_6vpQmdj%ode1GbmA97X zmQ@oM3ePRSE?Ve4w_LDcq43-ibx6z9oLknPTIf9^LFPV%GCWh^U7oe@O`gG^i)S;` zfoC?KFIK%!IHLS2+wAFc4c_aY+DXxc+YZ^ zf6wrq@x~Noc+Y;eF1tQ9cMWv$3WvA=#V(|h)|IcgyD%xw2Lbny%fT|65@7thSl#j`YY z@r(^!JbU|^3-%a$TE`pDgzZ%3Shd}WP#Ui7X8Tr*-~RS`|!{Lq227w>IGiA+3nY6cUX(vG$+Vt=) zZGHIWeKj^f=%Q^9b)d}4w%NZ$hS%mf;f4&MEp%xc~4|~(Sw#24K(}gz1K?Uhv+oP?^u8++j23@oPLKkg=&_$aebkUXw zU9>Sm7j2Jr+b`EXY^3`jY_M%_%@EpV8{C%Rwb^dyr*e%g_kz1Kgf`xE{THolnZ2if^HQ4EUksW4 z;=XUBdHuGtcPe*ZjobXN|himyJ5p$Bnko_uYF@y4RnWx+Gne z)cD*FWGnAhV~;PsO_x9q-Z?KTSE}=sSi?|8m;WbRh=dsnzL1 zY{17G(uJ6ThFjBxSc1qM>0XRMmu@(3g{({0(yy~fL`J#e6{!F_;jyd8#4Xfe@;yE`sMBMhUfIr z+hfw^(EB=A|8I>Cx^YaJ&^LW?uQadE`nvvULSOc~L(;rHZog4!Uf;K^%dU^jdP)6hkqHFVLJ4PEqcLzmb0ZMFU9$J4zSfbI{c3$X#6hNpWm14YA>8^47IOYr>2 zbRovzn^EaUBnDP7qJA;MT`M-ZK=T?_?ip$7<*aA z8-3yfRi>}p9+N0TpE%0US8mUJdrh$CS`(dj^y&YsYXyD%_FP68`t(tTzJ9xZ&W3x_ z?pt4ckM^E^>3Zdrt-&ioCSI}gzEm%6aA;+!7dLoBxgUue+#8nW#SK1pN16~f*hR+= zaf5*~(uBCd1`E@?xWS}X(!3Z&$i#`E3^9#(msm%9lNdLRxD>sQmfn9sV(*-k8I@X9nVt_(6UpLmy8P`pdbC*CC%bbmye7f%bBc-mQa zrg<@_p`*30YOtw^v(ki^)wWq_UM%Z_E7F7**Z1B|6JlQvzLVy~#D1|lO^B6!LF-8z z9b{r_p_e#b=p~L9dWqwOUgCJ6mpESNC5{(*iQ|P{;&^?vH>X3I7gq_Hc+1AimCv&V z7iy0;JSR@l9+NhA=p7HHdNGjG9!~XQBdf=xdNGszo=){*DeKKn6=EzWXQXCdv@2Y0rIoO|a+MvpVmHDSbd?VomM2j55TOq71R7cK@6W2eRF_ zzIbl!J^iaisor=Q$c&e{`Qub?+)CnsRBzl$VOgp$Ze{5en)_p{CvN4nc4^+YmFc>s zF>YmZk2GQ2N`qU{luOAIx6f$c%%4%vdCpXUq{~#v-8)89M`+@inLeW1vts z#zvvejG01P7)ymVGR6vRXY3XFgfUs@E5>S}4vgb~%s39{WgHpwGL8&-8Ak@aj3a|y z#*slUSfiA}K zKo?_tpo_6T_&(c?=Zt|udB#TJJB*pa_ZdqCy^OI!eHeR%dJ?}4nb>dWVk{MOF$M~{ z7#js$8){;vpo_6o(8U-l=wj@Zueo54vFxAc=%a9qaVcay%EsUGS zxrK4lIJYov8s`?qP2=3cxM`eQ7&nb`3*)A-H!(&VGGn(*o^V-GAhj*`;Rj@IRS81CszRW?)L3G z90HKZEdagbF@Rq37(g$144{`h2GC0$1L!4>0rZl`0D8$|;H$kj*D=l=GGp6uMq*sN zJ>Kw~G4l49#Cd?R-Z&RA1{~)l#)jh@#h7uNuNX^?a~EUGaUNsrxvk5t4|Fk>9J&|- z4qc25hc3p9Llh|2X*93d6;k?S2dYoe!Yj4kGlwnLg$}ra6?w_;C31auHue=6WW4Wipenq|@ z$m9!x-Rz?p-X7S^j_&dB_P}mN-X7S^$lC+E8F_nPHzRKk>}KTcf!&O}J+O_CBM36N zgHVQ?LU@;4L--~+h@gwyM5qHfi%>Um8KKVPI6_;jPcnGBP&6Tn`5kbdj3~y2x1sUF0%?E^-_}7rBq@w!R#Ww^0*ot#q<~fk1O<&#}#_XtCQs^Q#DRhyu6uQV|3SHzlg)VZR`kD*&7=yo?oSg83ldIDnlPE(@PLv^6 zr#<)WHNl>1@Yj=56n=bijoNb=WymRtGUOVy`v-Zc$XN&95V`E^ebeq+UwN$TJstQx z@})y2UpjDuNe*`CA~!qgK+bm5ja=@iGdbST7IMD>&qi)};5NxQ4?HKi=z%LEM?GZn zVB=kK(c@im&f{Hj(F40k?sUlH^9Kf%9QeSdk{chGRdVJ7%StYNU|h+u59}+s_koEe zCqJ;V5dy}(tH zXC5;7-hojhFTFk9@SGg=_Lu}7k2$S?OC$$7@QUPS2ab`P?Z7vZ%N@8!a=Zf%N$z)B zmt7y|B9}XKk%Jw&$juI2f?y*-yvhMe{&L#}(ff6gXXsol4}^7q+$ zI`H<)^@F&Be>?w=_uSfE+mTzA`5Emzq4xSy8+Qu( z{$ihR&*k0L*LfKCR_3|zb>}^sbGv=-tL?jOZQr4M<)yXH`L$uYv+abo9qC-!kbT*m z&c?QUHuf>wzFONh?d)RoP+QvlHHulC> zo_F{_$-!6~m`}_#VxBQK|1Yq|zVM1?gGt63NUX0fTqV{_a;Vle_81rj;(KcY>DLjo1q8-Q=RgUjKg)Z5}q{l_swX_#4UhQX3qMzIfZthMVzh_~mRq z#@gm!tZlBp21l28*APGDxZ~Pl^U>7?$E?k`c~3-BkC?*hEanL)1$JzXBC_GwKlli?OX;nuQ>9A zGEN`)2pGSQyrPWj|F?1q_~Ic)z5wzYAYTA^4{Uz*v*Am(^9$5=P66=AlM|pexa;S> zo$I~h;uadTr!Pv2zC5`8$vgk@3j2ox8_ZzK^rX>2o%DN$k8f$f3jdapcfp zT=~D1y9aq&82elsIb!y{qj?xL_sX}*XWL-B=6O63E)V`$VRB0`4z4zGlOeYnV>#_S zS;(WuxJ%@NV?1VUKCoad^(yI$!y}?EG=aRmV8l+Q^Yt+qu|! zlxxnWEM4k%mpPCpJ{K)%eacM^9mf0AMh;Lr2QKC&VB7aRy^NS8eBfukGC8IFl3(>LF=6OB|e4hE7S8C%U;zP6Xn&k?VoDZsdR<-h23H z&Hp|>N&3c@n4A&BhtC?2`gp5&g8_{<1WA$1l%1M7l1Q7;{|ZGXB>e!^Vh@| z;4Z+p1Kbf9kAS-a;}meGVEh8^8jNdrSo2CSZUQ+bi19}531Yu-$6=fW?mon#AeRK= zGH^#@JP2}05X+4_6fxeo(=kQ>xpElafxI(}`@kKI@gTUnF-`<`I>wLSuE)3%+yNPH zg1aH(P>`d9u?fgy!Z?CSCpBM5lN9NguDQiE7YXAIe*I15s1#X0t=Qx)VVnZ)wv1oE zotJS9xZ^DUAz7|`r`W;W=d*xhxx1>^aKA51Pm$~IDK?z;#IJ(up14-LLpZIgwe29AoXFf5j zu*ne13L6pe`N*R|9Q%8(EcW8tkrRZtcjN>i9v*o*h?9ryi1>Nfl!&W`t%-PhpiKO8)8;Z8B|c@z*a__Hf(6bZ^LHNVPH=Qy`b2E zErr;&J}no?Wg$1o&cj7c-`6wcg$r+zDXt=CS=>SyH@26Y3@Ubl3l>P|?4HspyV&XX ziE`!jN|8UilsG-trOEA^lceaN<_rEQRR&Zh%Au7m=jOOn*$+7*!yAdN0M<@DD6;qy~f zON8Y|_RjWx=cZ?Jgx~K!E7z-c`n`F=`rPi$6V|ix?q$OIPoKQZ+b%q3dr_YKfbXz> z@O}0h^s+xuANDiq$^J+E`Csh+1^L4zH%Ygq#is4SkK81``W2f#X>+ib-1eB~-~C$H zQ)ce<{JX{Pq)4BKJpbG^j%Dx#$CE1rMX?57CXp6>Z~i;suNgHL(>U2e-zxh>xF?=H~%M+1sI|8Bz_ zLDK43&%c{8GEn;e>G^jfHJ8L^olcp5cYIZVJQeHtcYKaMVR`fwzk@#H_tCf1i#}(4 z@Gn?T{3F&M|Bmg#bG8@d*$?;*`v>1=zd^`+wC2-@eUP|3C9b z)Mg%sv*GjqPjg}T;_bJ2{?Et(QOh|;YCG2hd>@k!Xr72w6%KqNl;Njij-G#uR~%S( z@|MHrX!GRPCSN^#pybAf5A>gS%Mn-dpK$)eC;LzQz-avw4=s2S{u2&oV8;H5 zZx$Ff=9~q#?ObtX1DDQR#=z_`-|oM~Q4FltrWW00VxKYx7_h*oZZc5Md%z_!xBI`v zhY74ZbHoE+$Dik;fvak6=kuy@Omh2Sk&8MOIykFrt&W!Ca|)f>;H$CuUT_z%`Il;w2MKo&axVGe!}(9Sqn-2swqI1PfRNI^|u$j!>7q7Wt@(nJ1=yUNB@O-|>Et_#TUdjjM zn;fj)7RJlB{qs$3))(t0$Q^z1P0rSW%M;{Sik9h|C5hK1$ex6JljF6bb%G3u&3Axl zf301DY!H2}IbqwXT&^-~m8&+z%fLrem)a`B=EckT&*ht3!wrYT%gT&=lY_WVXuND& zm2YwrU(zUEj((JHau#!RJUGF!&tF0|uWXdBEUvBo7#Tj^qJ@&yhS}@HvtP z3_eHlfWZe!9x(Vo$?XFlC^>)NGbQg9e6Qr=f{&HFTkx@xj|)CoauC5MOKu|gh`Dyb zcg!^tzFn@F@cEJ>3%+1-WKH>biI*b_zGHG^!KX})Eclwqkp&+#IkMohCKnd+o0G2z zdEUvh1fMwhm*5j8FB5#?(Y)XNzNzdyMI;rA!UATSKvyMbXK-zG2&fqa|5FpzH(7zXlf z0>ePQO<)+vw+Rdb`8I*6;F$rK3UcTHQ$cP$U@*vU2`mSBFM-)0za=mm@pA3Htui@yo9xckaf@p9Dymrf4b z$tsga8u)YaO9KN&9%XYl` zeBRJC*UR}F(=gY|`P{1@$IJP=O#7Cc&%nr$^BK5waytXFNB&`8_Q)GN`&6!%Pk3Q* zu9s(c`te*Z|M1EExn5pk;M>Vp46GOLIKY7M?gLyRx%XGK%=2>8ztld@%UvJRHP6dw z-!CA~%XR;DV4jx)ADDJ>;{)qX&U|1jX*@OrJYSAOUI z-ko~)k5{+udo@!vm5-Hmy4UX2^7Xg-q~F9B-mNf8=8NuDm~t$>@NNY-b4zzCz`1m~ zL*daM359>>AI<>N-{-funNaw5`?p?5DExc=-L!j*?~q zXG%#+fpgBJ@74b;q3|x4fmag>?}#yzG0@#HQBM*I@09udg>0WvuI$P0=^C7Ar#om~ zy-Fz53E|8(X_athd(J5r=JP6DgEQNm_qwp@Y3bU&j`FNUs0%xoldcu9PAI&mDW|%O zt)~n7rKUVDR4k$Jo+dcQPWLpy`F6Ue3C@s{Mha)h>FyOcXHJ?bV7eCxFln>!S-KYq zFx{5~K6FP6lt~&d_>lGs&q$gxJR@n&@Qiea5j-Q^VFb@ecNoDl(j7+djC6+)JR{v< z1kXr!7(u@1-W+IW(!HVm=^h-&3*CeXsliyI`w(HQ4YPD)Fa0t#7;AJNB8)Y<4-v*1-G>NcEikbS+a@wK7~}NL z1;#$zaRze&y`zCSgzg`NxrN^Kz#KyN55n9+_Y%TfMDK=Rj-q!)Fn7_rB$zYl9Tv=) z^bQN=Ou8!&=1jUP5avv}D-h;Px+@UoOu8!&=1jUP5avv}D-h;?dLIY#HoZrK`JC>X zgL$6rp@aFK?x%xwf$pt?^@8rRgLQ=Nxq~@`-s!;HLhpKDy`%S!uuc`;Z7SCFU_O?rbiisG{<-axWm}+p#lc4I1o0=u8OgP3X>U*t5_X64>Je54U6U zYZ^4z`_New*yH>WpgF=(*&X*$G?eXnKEV6Q}Xi^Cp@&a}YZiq5*go{rAgz@CoI z*ub8yNdsHQJ>BwNw(P=sg9dxLvO%_NtFJ+WJ)Q3%Tb4K4puwIl?wKtcAisYE zd%A(;?3k(=G}zOHIoPpARt63Br*vKj_LX$b2lktEe>&_#>0Wi%pVEEnuy3V%*kM0Q z_p`%3m+ozcJr12YfxQo%MS=Y|osWWj^ys=aEUb2p2K(zKm26m0{TvPU-K|U5u*}9e z8tlg_o7u2K&2lu@r2% zv|*1g7&Oqk==>q*RCI0-^s5$Stl93(IU49%!>d}ebsKUt(7S%rw`Olw=V+jVO}4XU zMV97hppX6GZq1w)n2@7QS{Kd2He0e6 zYjU)Z4B1u?a9_cdL^)a zLH2B)TvLvIO<)J*`S8Ofva}BU6WPIKZP?!0nVPFS1H5sE6Wh@wL!0+=A}fB~g?+V6 z*G`vCWQSh4vD@vwYJ7GAJM>s((}sW1?rfLqQ3_*oLOyFvcEqtt&hE_o=_jq7e=K{y zq&@rD`;(UE7{l(*@nBhx)3g?MqM2W{4$M3}P3t)}inZw9fhGB-X@fH(*i)Ad?Bwz^ zt#?E?Yk$Ur_2+4tvrianlG~o0sQyWFs2|Fj{N>KZZ2F|_sk)g}@NXw|x6fMD*7AP6 z=WQ8(_gPB_+Q`OMRoR>4Uo^)u^6#_NcVn>;Up1RcA?#XJ7q&AnUF&r=ggyP?$kzRm zp`FPOVfE5mvpqvHHM1!jS)<%mY-!sp?R^z_$7myacBNvr_Uwba3v7`s+kYind-7#7 zJ6YL=rB5?xN%BsU)gP@`<#dDgX=FI7Q{9S9>YbzQPmN&XLM&O&;2b=^O}T?SPWs-G z@$p7GVK^84$<~sUmY;?5(q_L}vgpb(*YX^-`%Wu1F2$h1`RbMLtXYhl=i%ISlUcSb zY+|+s=dtT6_H1WNmImjvV_G|~a*_wa`EBp+ZCJSc&J>*MzCF*0MchtD`;bHz7WL;> z^e-*kSkn(*u$+~LRkot^7c4($5o6J9KV!Z1OSrSm!BR_?@r>`-o?ZT)hH)m_d$6$3 zH2hA%3909|=$D4i+xDvmo6}C_ac2Z0JA8+N{NXzbR1SQHg35>QI8eRt9SVvEzC%HA z!gnYre)tXrJr~&NdBLCB0m`BFf%2){pk8WEh=v+eWZjajn?=@0l9l z`1Y%I?RuWfcbJXcbO{vMauAS)BYHQ?v7- ztatCW%uB9ut1pJK=$38SqIE|53$wQDV7$?P;zL#5xoa$Egq(lg|7I-zrTjkBi<`!J zzt2(GjVH!<)(%%$w|6<(HFqqRy*IOZzq+w%TXVIV-kVweT{re;M6R~1 z^JZ4yboxU!gdeN)m-GAZhdAd>`QNncgZ^kAG$JLI!`;ZW-|+D;>O(G=4$n(ZD!?X zxUuhNbG6Y&HZzNJu53n?JT2<1HY_mLV$PamUVYn*`Xr8Ctt{BReN4m06(tcj9eGTGW*|f%a+Hbb<{;8d= zOw`NM9@@*hJXX4~u{>8h)J6XNy(l-f`%tcCJ0^@pCb_Y%dvmoVe)8|prMR&{dvdjF zQU9`cJ@POA#@GH;PQ=SF<|CiwnS7RfLl~RT*Nt7fm8%^o8P3ui|zyXw#6%7Gx*9oN}4#cdF}Ewvl(Gb zb9H9+PWhVuq%bzUr!y;Kov$U0lX!wN>(MY@TQgSPT@~QWyldoZ%J?uA9Vx$iRW@Hs znJn)gIpECpndNJ?*5S;;&xvhcm9Jfw&$u?liPfK%ug(2kmVd{I4H=!UEmgwVtvOEY zT5!I$x0}2xT;=wm4k&ne7p* zZ;A_Rw=qw!5Q*PbnwKD!;6;Z44_Yjz|{ zJ>@9Bo0+e@ni|R2eMffUPQG?(VkB$)*^!mGB)?BLFRHMvEG3Gyo9W12nHOj~&Hja> zS40)YFeW^zFowFxQH3!KITTeGgQiIzJ%-HlQH3$2UW+P>;mNJ2!WcT-kv{sf1Ew|^ zc2B<3*V}5#qo~3*y!Se)ux)?Oj4EvNQYE4bb75I0x-dsu?d7_!=k9*z=)#;f`Z>BV z*Z1V!g!+JIXmnxU(Dp5eq$H)Y^m!vV0bA3zU7^!n=OW_!4cVJ857`d}`OW_!Ci`Y^) zMkeo!DV!5p&W|Y^n>Xa%na1qGV=;wuMapmTJ+D4j#9fyD`dm@}R!resk#|>OeXgi> zUw+42pDV^lJIxh_8}c2uK39Ca7*jY$y>BDmiR*J$-<{p&Xh^ljO6|99wc=OyS(SXqx=Kxjwh|TM<(@x8F>NDV*CIo{TA++h;uZ zm;GbaYjV&zaae4W^SYJEFhr|`GW$KE!!ZoY-!nndU>!+!4g=^NcVe;LmzGhvJ zx)!Zjo^7SxsIOU9tm6vTtOpixg=<##_i=@5bilQ^!nN|z{2U%SUk?T*&&n`hz*Il~F5i4m9Z+$H~( zg3d9Xg~u}D9?e(AGU6m5i{#%=Ag(e;e!o@cFx6+p7IK^U(oUQQ{D})eImD5meBw?} zFL5e}hq%_pKVl0xScRP2IAIr=~yR#v64cf+-Sax!eJ9}8!poIs=veQxSY)UbMRwqF2yM;TOk(I5@ zm>zY;Cf{L#*4g9%r((R`X(6hu-bkkb~J;1wW~I&TY@i zBxY+@SIhGl5puu0Fi&yPBu*kbv8jOpv%{#E* zzp^wK7boS}yhb0gG#D2VxgM-^mbA-p5%J1{<$uf4U|e|L@nFY_XKOGIl$q+uKKf*7 zFdpkQ@?=wg$B+wzPM0kb7h~KlmqmGFQhe4dx~DEuQRy zYnBG{)n6w&Fb}C|z&sYUy93Kl%F&MJaQgBSk;sLH8)Fx`T3-aC+j&bOM`jad88*x=_})u z^ZBQh@^8*~8135*c(S(kM*sQ`Jy~cyV>y=JJz4PzGG@76yjjwTWsSd+CpN?*Q-gJ?*q%rc)~U9komkF*ObyoMpz~hL?0SX<>toeeFShboh6d~A z^BG>OTb6v+EZ6I+H@w(`OBouh*Y)M!OPO~eLxc6Y_kAz+>3oI;>-C5`Ud;Vsh6d~P zpsQYN%#{oc*6TUHd9e;RGc;JQ%@2FA6ZbPTSg*$=da=l-85;0}rt7>|%3GP#c0Dmu1HLijR!7!gU#12;WCicY`kj#PKqWsZwzDI%Je{clZ|N4> zkxe+4sR5ta9nq0}ydcYwJjXk-BTJGP_)m*?`FDZNW@^BTs_f~=uKt>-0bknpYe(jL zEK>s>6?nfRyR|!01Ag@;qa&*yFUyp?%c5E*c043g13uQ#xfA;ykf{Mrn>n--8!q3^ z0)N{Y*ok!=X~eHtXSO9W19_%$voo_An4tlmd~mfh+czjf13o$aTxV8fScV3CvL5d& z&w6HPz$bg`?#%X1$k2dKj*sfh_Dk&%_~h$lo!Oth85;1(QPVrKw4e+P_~haNomtGf z4CK#L7x36ocRI7*`e$gsZwUjhrWk-%Qw+eXDF)!x6a(;TiUD{v#Q?mTVgO!EF#xxx zX9rAe0{oxa3ibumhOl3twuOBJwK?oBC>OBrpd7(|gmMS_6v`>=UntkGuc1Bw`yJ{V zun(d>1N$TDOR#UEJ_h?K>U*%yqCN@xFY2qXAEdDZ`#u^Yu-3N>uK(SeLc--u&<}N4)*ml2ZEjEM)0RO6Uw2v6m$cc zV?j@#xfgT>nv+3)pt%}!37W$}ub{adbPTeCzCr$=dr&!`htS#q`V6gQpu^Cb1v(6^ zS)jwvngu!xty!SM(3%B046Rw9!_b-qIt;B@pgYkT4f+qQm7ojJ8VY(8t=*tU(b^4q z6s_H$N7331dK9hQphwZ#4SE!<-JnO&+6_7waR$)qh)aN8mw2N+yDvEg=ym*1d-nVC zY}D)8Z*0#_hDxp?^*X1i?U_$P-0sdI zXVWB4109n1n_6UZA+8d?sgP$5Ox(nXPxjxwi4mWCyH|c+Tj!Jak8fhcC;#|ee$Q0r zlhL;}G2)X)pKW5qCr^Ie#E4HqUBsWWV>U73v4Dx+LJY*KAqL{r5CidQh=F)D#6Y|n zVjx}(F%YkY7>HNHvy&d1dFs6D^eRD3&U-gf0cXyA=CM@i5nb=cJ{5fE~9K?G0h@l?& zZ^U{$0{rzj5$o|IhI(XuWKWfGkUy94A(rKES)b9Ke1lW@@Ke@D@d)tK;}o(!#8}?k zXBa=!GrdaDB=FJg_`FaLwFA^c?W32kVEo2<5$o}&`g1{?h~;xZ{D|SXR@8Wi{yQ#) zxw&1si`dz(nv(ndGU63A1}T|l0&(o>HOhMLWW?|j{te~B@6k_U_#Av5>`)$*3mEEw z`b_Njyt+R(DF?A$K4QII#Ckl4^*9mh@gs(QDC;A8s*HpDxvUSdEQiau5zF$qtPe5# zgn#StaP%`i7nk*+9m;IG$q87bWqs%mzXv}(P9f{#5CfD4P4)_qk=!w1MLV{j~{&s=R?^hh4Z1r`aFX^FpgoK zg7Wow3G0>P8s|f3D}5eAd*OU2{c#+_d?<0@eE2VWD%f>@4p=XTLz#N{XfK=(u^fy? zU_8co8*$-$D1G$jBD--uly;cUV4gC@qtAz6r}Cw0jBW<7{(XWXJY3j{)qK*5bNa&@S*W#EXO#$0MqyatjCZ3 zG`@5@jxXIG#}{C|KU4WQzQC^cf3)l4g5t#S1wJ&sjO7@|mx)~g4C5H$1FV;WSTA1% zJB(v^PQWz20MqyaOydhMv|pRbPUwI8V}aXG-CHAWTHROaQ^N{zo61L()4S^;-dgd! za$KEyI!F6%=q%jdE_#PAdTt;Zw4Pmfc``Vd2TvObJoK9>-)t0sYu zZpY_^dZ-)Gd#fVAtCjW6;|lG35(lrOMTz5r9c08_pI z>+!3A;kjU40Zi)`U|PQb)B1&WozDZN^$ReqUx4-X2xFu53+%Lh0oLu9FWn#8fz~hZ zq4f(etzX7+jO!QL_4NxdtzUrk=fd{a=YPbse(B{PpT~0a^$ReqUw~=-0!-@{U|PQb z)B0s%$Nov{7uae20!-@{U|PQb)B1&Wef(}x1j}+n?fGJ;qDPMpoUuf6!1(@;$ znDPaf@&%ak1(@<>Vox>k=YT0+fGJ;qDPMr~cm&$@d;z9>0Vcko+mUbR{>V1~>+NGK zN6#17DPMpoUw|oJfGJ;qAzvONUu`w9yP5bafGJ;qDPMpoUw|oJXxH-v*fd|z4`E*f zc76YXSl`zm#(jg_UxAOl4??W(j}X)T3w-qb6xwP31$Nqh0oLu9FWsMmT`vc*UOr;I zUc`Dli1j!T>+vIoe8Ij5%GCESV#oQA@&$Iv7huX4V9FO@$`@eD7huX4VEwspj-`C*{+KVovK-tm z1EzcdrhEaG@o?}1O!)##`2r06B01V~tBD=wL&_J}^>T2HpnQRy@?|W?m@mMTFTkex ziv7GDpAGB_e%_|^?KTnH@a?r2<;SnD5Z|31qQrh~jxjIZ=C5SE9DrEgdx{4>M{z=V6hG7>H6m<7 z-HvUj`yXGFlmSZ^y+7ZgppO^fh9T4m7gII4j#Ijy! zPsB1FXlKOmIcP_dydamS@g?hQOydh|G`@_#H|kN~L*olDjW6(_@db7oUtp*41sKMc z?1zm_?5QUHvVDUZ)A#}(8ef2Ee1Q**FR;`20!-rzeB}Q)9|ETFrTgRf(#yf|1$G)= zfN6Yz4~;Ld)A#~AjW1(44>|na#ExxC;|qRA;|qLfe1VHCU!Ryf5bGtz>mfk_~`X2VAtb;Hfl`c z3$PwP`WXGN9l;Ls3Hjsr(#wJQ2km;hA*S&KK6*Q2nKZt@uIB~E8jNGGnT)$sz?3h* zdN~|01MR5W|CtYEn^3->O(prbD&?dCj7~ALn%;lheKsy2_|2s^a0epxv=-eJSC4N?4 zyJ;_gTp4`ywI1!n8Ng1Q!B~#*9hQmxpFNcE-5Iu3t1gs1wG& zi9OZCp97}%HGt`T4Pbg-16Yqo0M_F~tjCWS<`!8W+423F?ho&+(5}B9K}_#!z=z(~ z0H!3t1gs0ZG!nb_S-{1w1@If&_f4cO^@4Pbg-1DM{|0H*gfU1H2&&P=jc z=AZ)Z^~2zH{hA%(t8TNEAE%llwpeyh=^a%Ev9tdxrTXboh~X#v8$Jua2S32@Iruza zC=bd74D~?1Ozf#9{v5Dg4r0B0#CpBLSPsU6SdSC29zSBJN7hI7R2c{Pa~U6E884Uh zA(rKHSs!Bf3IEpP5#XoCDP(jk|xwT3H--|5L}BX};jyH{=e^a{&J5+(;cfhwwlB+z8|g z&i_#E{vA^u!A|FY0Mq#&z;ylxFq~U~e*>oTKY;1{4`4d~0~qR;DoRie^DBFbg>Cis3Pls_t=N16dxdpvFIkY2S zI=6s!{oDdzI=29Q2IfrA;sBF|1DG@%!1{YJ^dSug?4;oUCJhHLX*hsM!vRd%sfqoc zbK|<^W^5m$b_$p@H^8L10j7MxPxueoRE|IS?()CyU7=~c)Mvm(ea86vf8OmvJLvCf zIpm1m?Gn#~Jpy3bBLJrTIAGe31E&2rV12)g=Qe3S4tCm)1E&2rV5kRTF|q%1-qm={ z7Tcfph46*iW8$%~eubN{j3# zx*no}&z1$VlmfLm`n)f8SUK|gC-eaw0(2JeNys^%>}XI2ed4FSQEI&@jXt{Gf<7^q zUn=wZl|mo*J@`Rgx;~>oIq-Y%gP5Tns1JOg9;gp|pdP3Xd>~$k8+=GF0w0JM;szgh zZg_t10sRA>AAI1s;rYP_#)q8q8i5b#OW*_J1ICg`IjJV)q?(kIY7!4OiHDoS!@);? zF7(l#3w`wGLLa?-&_{0{^wHY~ee`w~P?z4$0_xJ+Ss0%S^MyWozR*X{7y9UVM;|@! z=%eQyef0i=K6?K_AHDye5AbT)j_3nz26`6616Z~rm6Iy-LFJ&H20pT!RGANohs(TD zJgBpQkBo=QyrPfn7hJX@`sjKWJr|elh(5A?xNJxC(e*L(k?q4}JE9N#9{ivUNw0&t z;P>FC=Sx6+;6q~{e4rlLj_3pN%63E_U9Y3O3y2%af#;U(Nc{(OKPU&D8=l{ouQsRw zLS3W>f)BJGXoDu@P=AJUs6RtF*q`-y6ex%ELnsH@kH!VGpUL<_UD4#Z6sSvYA1sIT zM)1+w2YvK*R-rD^A;Cv)XVv&zm@o9v^QD3hv>)_)@PYP&@eJjVZV5hm-q8oz&tx7$ zJrjKN{-fTS-kg1zZ^dj^rfUZ-wP5SlTd_(@(zW70S+dkyR;*V3FwWPfoLJJLG>pGWF=rMvJWYe=I#9=%E$*A9Wmap( z$R7856Gr~!S2bo-&Yj7P7?mG8ry-+y-|T6?D4tVw8Ze48;Z%J_@pnnAU-(>Lr{@KK zY6mEX+6T&~c7uAUJs}=yXNZ&9AL6IHz;n6Czcu~#+E;B%PiwZ+-j2mR`J%O7-{?Q! zx}#gmzu)}{+hO7&NA_F!Pv~!IuhqOIb5g%zyB%xWlGSqfitYK_za^_s?JKr($fuUf z{KXe+|EWQiY+C#m%*z)yD>l^U3+8KOMQhgOvoVjq=2^4a%Z>S+CjX}Qx9XoU?>Por zHZ1WI<~=CSj%l`^Fz*go_AF6L!*VA6)r!rKf8!VWmDv#oHaz!rhWzUHuX0cU(^p_-lqNu^EUNcn764v!@N!X9PHHp!Jozjltbg?pYdy) zKmUFFn$EqZbMoJfQ}ThaZ2DOm%cf)8)CaKXxot~`}o*TNW zk5A|G;yWUQ`Q;v})i483>=7ZB$9GqQ0(1Fgw(@A2Q_e$DM*jp0rP# zoWo~DuNC`3yQ^M3zw;XD!NOhoOl_IVPmc^1abdC@F6Q#k=IcaYcz4y$^9T2cTrXxx zpO}UPeB+aK;%1tUx@-LpUVGXGv0B=@+$!K*7ihLCURNA}N&F8(JZ4{}|-PJJrAAC{xX7NJ$Y)i}IjEvCErsi%8SN|21xlI4;Yn^)-z0~^kG=4YSN4k&C*-pq^m)(MgvN^F^0|&^@A$9{@#38H zc`@)UFVQAWcuIS6x7YmY)j08+Y@eHrUvcZR2_jzlg!{eXV-LrRHnN;ChoAHQ0}{m= zY5(ofUp(zjg4if?cO&f?UyvRzHp#pUwEK(y`XW)xmOgu8pK|lX3F5WPU1{YpuUsTi zSV=tl%^%$F{Z`Rl`qX{>C$IN3QQVV#qj|Fj{FgCFqN%iRPq@dY-rOpF$i8Rm`hb_q zPZYtjU-j&Lm*2UcBuYu2sax*yh-q8JPTBWrf4ap#{JB+}ko~jT-0QsQ&TZm??Ek~7 z-{jqQCW(r&9A)|yzPnViNS5~YUYB|63EM;oId+mqT;-Nqlf*$eF24C+;)e^8M6?_) zJ=&h-n@T5(mvXGx^v~h@KCc$5r2k0AJnpo3tym_@yd0g+t5#VjCd&95tSaD@cdr+% zWt&v^R=~45hluAAdl?G&>em~^T-k;T<`wXWz|G>b#Df;+^H+7kL|2)+9sZyByfrbx zTjI?ZKkyolW5rkLb9mnyu3E&41rnEVeZhx#C5Sh&%vF=0@OMKKg^R>$_lJDQkgZ~x zjG^w!+q`l6B(Yk?X6bZ|AD8odu#CC-tj+vle|ND&&bPkD!Z_R44(GJ#+oSn#4Ux--YR`3&ZY8us@rPE??x=`3fWEP zf73Nf_9dCV9D1Wkt^p{xL6|$Q?yM5?d z{&c^a@T}^szRL>a`DYwOT6J%=+WF~x(Ee6pQcZ8Q$G`!+MVPJFBXN;-ZTX3{*5ZI% z7e+K_#BH}&iNI>!>cR6B_|sS`(W#2J`Z_&3)x*IWpDUy4*Hn)>Eile1b+S^|y|w(` z+WGLQP26RX3;JBOUCqNs!QZ#&saER0gqN#qhxo*&v3zWLHGcsu)+h|T)i z^Hyh?BTgJujb9mS#HKkdTC*g-X3oUOV*vhn^@Y52XY*}-a3T0+-@sgNNklol6Q5r6_sT_{B>$5 z4{4%e`G52Y;nmf)!exDT^-`4*Jbi_waF^qy%$CZ0OAkwNR$@=HsyzK&3o%*7W6`u0 z|L~%Pm@o1BjX&`gUY5f0y^p%jwGvNow-T>qIW6i`=XD*eL?5}{4NPvzBh6ciFzLT& zYYX0Cwx!r2{ii*s$Gu&xM4gcC>Ym}&yoA)gwo0E1YEyo!hm}|_?LER<^QU85iv7~= zUDuiq^tBS^a$K*z9K}QVjH#mnct(61u~j}x%8=FEXPu*nl|D`G2Jue297PXl z*G4brB_245H?j@C6(r4Y8)qF{;vzP*H)h2{n_Hq?7r2XrQb$m;8H}OU0 z`fQsue8fOk@m1!oRkvV1JH$;)mH6HFjXdLqDh5iQ7s+-!J6X1&EN6gyR~}r=S`3ph zzbv4i@Rq}@T?rIZ3CaEFm6ml-J8hLnqhXSR_Y9l|dSSDMUo@nIlbeOFU3oPe?+3d*bFTrP|Z2Vy~Rv zY|j6o?E177Ic>Y3drGCdTaowfS#notF>|Ykl^i3q&I85lM~+tA{%a=JvKXdpRHK(SZKy-NwmY2!}*rBwYRK?KXS+sXf_ zQYJ6~`E7$6&y)qp!)4J__r}!?5L*84t-CL!bTO9J+rB3gaYFlE(0m=8eo%pKU`Wl1$ z_DxipGNo-S^4sLa8A|iEMlL$_QJUh`I|eyzzg3@=oa8OYY4aL>Rl;9vLEd}NJyXf? zjYfWZt9GtZcToiL+r5|bl$bQhhb5ocF!!6%qlS?)w`%!a$?6z}{C38-9HqjoFmXb1 z+I`8n%Ib1q$ZyZt{ZO99Z$^G=C{dvF85k-W%W`XkDPYo9|g*|pbcV^%$cjaJSF!I}))&)wtH|vn!PCN8XS==HR`R&U)xr%1D4ms__ z4+YBk0c(-d&Mlg+obd@3X0k7RYLlxhnh=cqw%oiNB{^}eNR@r{ctM`>m9IvA>pxPC zL9qt;ZMl27%E+&)kl(s>Feu|&tww&kDj{3xYOx0S?YmW3O4p&Qk>955%2e*|Uy1zo zLfvahwTj!2-&&l%tqk)_LVlZV^H3QxVk`37^lnd-!=n;~gM9XVbzUeByc3Y$UflFX z8Qdry`R(KVAC%u;#EMU{{Z~)^tR!rVL4F%QKVLcCI1Ksip}7Uh{xzFLy7U>ESD;+_ zyb<|rV$pAkP45uow<|UlC}v02BfqV@JztqvXC3m}j_vc5kfm#p-!>bSqr_&dMt&Y30$-CT$cS%0xMtsban@ySDF!j%cmdK+db|Y-c*-Uv|)$vW;4kg+m$CEgfaKkoD zQsd9!@^FQCxa4w*2|xc&?WSd#KBMG>3UNZo6&2!& zl0z!QAtkp|h+9g|sSxLsTvQ=0Dmkh`9QE(o*5gGDW#D=%F?YIIcMjdiE7#Dn*~1l=l6E3V zVlSuON*^yPaa(>irQ$%PMHd_4C(B%ax|=fRj3x5bqI}u`zq;Zm?Z9Ino~f?*cCkbrn|{thx$bO*Ja*;48p=w! z9|0aau3jnS>jF#UvFZ8CluIKVk;h(IG*{W<+6sB>tcc-COpc9MF5AcFT`y(HQEM?v zV&zXyW!6zEqZ~ZCoKmSU(TupqJK(+b$+d3gDoZ=7?nR z`u9m3^wQs^Y!jpE^yQ$J`W@OTiVbPUK`+e?PY{)g*l^HGKQ)gNCr8%hpqGB0xka2j zS&4&Q8niM}oF7q=gI;PkKTHG%n{&`hm-N~s*8cP(72*W^{_bOWR<0-Fms>MaA?D?^ zcZ#RIqcP?lEp`e+U@&5z13QGvNk7Ea$5KR9_pyloaNjQ6TY4kz+kcy=Ue^(^qxn|R z^Kb*i%X`I(zJn?v{xC2`e4J#CxIv33ad`13jKTd%m>5z1IpR@fp`vNp`&7_xGv93% zwtc^)f_^(@&sMQ5)Ru#OJLYzxXn3U!2mN;P=_KKG+J%FDd($~d?5(GA&~M8=+$!>? zGYLCy!zr^xGpWT6{lSf&;&uUm`|$ zRV~SZ-wr;pMLaH2j)Q)?<7%|nu&W#g{dV{7F=Det84mhwzhzs*_5Kw(=(jsvV?;OS zDjf9N0LM7NZdc-<-wtUOE9Ta&!a=`Hd=n?;E~&;rzdaKaCuW=1=AhpW4UZKsH`U^x z-zuT;!hcvT4*D%~j}tlNEjZ}6cVEVdHYe(H&~NWPOAsdyHsGM&Zn+*W0wf0gwx55Z zxYVpE2mSVI$wcARq$LOa*1AE0s2bOtgMK^XXoA>%--?5NyVh!}_}1BhgMRy@#Wvv| z+lhmIoB4g4_`JOr2Y&l7JXwTh`(T+41<7K}y}lgu+j-&JMC^h-9Q50e>}{fJxj`KC z+kyMGi+3MJa?o!l$-UR7X2Uq>x8G$y8CG{Z2Y!2V&~`Do;zSPm?SS}XQ8Qo+2mRKg zV~Y5F>{Jf=?c?{!!e-#(_zs>%6ho}`1%t61cekesO`z@G*emmScMcg~Q znuC5jamo&H^6Lf;`t3b6MO1$p%t60RmCseTTnGpKw)prRV#|(j4*Kmd`79khHgnK# zOAXv1juemPpx;(ZNfFh~Msd(@ece;U!b#yA^jkZJ6mcaoii3W;ab}9x;gP^WzwJ6K zTvT<-PX+yU&esUhG}MfPe*1h;l(@FA7zh1!%eQE8pmS*s`t9BsF=Bp31rGXc!~3z~ z+N|mv^jkCQcrpC61qc1M|Fi^g>vj_k`fc-($--&S01o=?j`G_@iHf5+=(jgww~KPk zrgPA5OIA%0$AcGg&~J}UOc5vREajlzdL^caQOj3z&~F=y6yawc!a=`1bTmcW2ny$* z-(KI_t#FP7O!F#W)A`mElaJ~AoX=;9<9!z*?=5lq7jfOo7xl@052lO1`p-vxYr5`e z<>N)j0CTi2@Cy~S~ESQf36_+f0I3oTzcusm11AterPX}+(4w>7>{%N?7oeK=f26f4z60?M5N7` zitD3kI}|e$=PA z_)>%yW{5}=zXPr8WiGklzL3a(D(L^lF7|B6*{p&ze;kv9p2i-L#rHL53tTzYU zwQT36@|>Ly2iuu4WHyMAJ5nIq0qnWFPUF?!ZB7y*=Mnq%E`IptWwAVlS#Jtiyo=ACI;Z&w4lE zpv{(S=^(rsT5#aN%g(hDgD2JCz=0#nwi2g%G~uAf#(K3D13jvsy=r#{QKNqY4jg#V zq1K|hhXn@?>~7;E{$yo2aNwCW9YqV;>G~4KOXYuY>c@A3ch708vXqPPJ64&4mRmp6RrHRoz(LF1HCGjG8-JvNmV3RWBF>*I z$wA9?uFOQY7Wt{5>(U6?$NS%QO> z`}Au&QS3u84q9%}`W?ifZC_GB%RREaz4&eQ_f*hweJ^>6q8^`8fddcw%Trt%l$#1# z?*5(~MA^;e9JJhNuRO(u31%EP@F~yE!mmPhDrmXSw3cGFU0V)X?rv{e(XV1l4qEQn zsMexMsahO3aGt-^lJ8aGz=0iCyNX(oWjJWObq=UvSHI#MG+v)C?L=r*a}FBsJdX|{ z^iX~(XuRyRtuQ!G$9bmZRU0wm>2#d0Z2MV>Ufwfs4*7kxgGiY>8#UgnXHH^xMPJl- z2i;Rdv9F6z<6YdPz3?pVj~eeg3okLHX#i@xEgZUwUv328nSrX4`iL(-0#M^UnK(!| z91TE?cj<`{BFW&78t>&bW5whUKh$`?WKR-1hAcvj*L42;yE*nnM>}Crc^<}my+HQ2 zx{DB38|x~H+WR9;7}ri@y$C=Y^Qfbk*f0q3w^(n{^r;a~Ue-s{uCWyDL&gmj56>Iz zSv5zA`Z34o?;Rjx9iqx8F=#adpxx zv>zE{FWlrNIW=lS9OuA}v2 zF=yK%)MIP@IZ;$uwHWo-GANAOr2IIx{7JjJ5 zZee2u>lc7}ENeVYlp5-fdTf;wV@02reyGPLbsZyGb@4|%HmBLo;#qb8>aiB~qeVuE z0MuhkZW<|K)j-r^I}aTtRzCMfJ$8KFaPfFSAnLJ8n~fCHLIY5b9rJjEIM5^j_1Fr7 zhl^7q0#J|badL>*@K+$}vAoPM@u)-~>am||4;GI~2B99?xbqO(JCY>-G89Ef^sMCu^1_EiAtu?H;&ieHKbq8|HG<9;H_CkXY}zXYIM6Rhl#x94+3Y?dH8~LV*zz;`h;+L^)M?Wm_Y%Gm zr%BGae4&r{rUZ#9(!ap1r??vvD551-NxAJUwlxY8Ri*vQQ6JH$W}vW*?XEVq?Iv=} zjQ+00x{Eur1H~@sU$1F*VIjwelk`~@+D+I#4G?w`Pe}6;9kvBxJc0MRh^kRT1S&_@gF#`(9fSd)N;(;U0b5#MmZ& zs0m;Ctct-km!KwmN$Nlo?3SP=+^eP{e9fd?a=F>jiilPgqb98Oa1)*SEJ96qU>_%O zq~0Rbgp2#Sh(BvBLQQyNWk(TQbRlZOc{iNJi(v~;6Mp`%wQzgni<jRa zyT^zkNBmI}{$tN5aZ%b%YM63_LKBjAMtZ=px7?)xyjvxL*GD=BJoSP)^yL8V^HFGwjIUwpa9g6 zovl5@)ldGYAwOx~P7G-)=V!^Wo6S;1-DgWsL%wjvRb*FLj2iM{XJ;|F%0kqTf81;% zwmqAV8gj{S$;|@iqK0gJptuO$@eKK-!+~OALGDxJnM;F;i00mpkO%$;F1o*#sAwLE z_Oyr!A|;z6{yUEPp>h@ByZRKCKXihHNK4&<_@_=kiK-D&8<86F!y=W1Wz$~~+aJy6 z2`d`myj``AnK)giA+CMR=a>txSq*Sa{I9H!|CQ%@bktl-fAtZ0?EI0+*^errmRq%bKKEE(6Sds=>%Q}{KUtubYZ~X@JHw;pQ9o}10Zx3Cw;tNV8^DxMvF&4E9^&i}^$TviV? z%#@S z&u?{5L(V^)#RtaJL=D+5*T54d*FX(y$bFZkbGK3DQA4g6YT((OE1`z`$_UIzRK?^NuDJ)P1CI_W zjT-WkN%D;1#geEYyIN%O%gu_ShWxmGHh(j@IBLj6?q>2be&(nlzwdA06CH}6hP+}> z4sSHL7;4BbPi66@vwk3dzMq@J^Uf7P4SAP5bI59%qlVn!zJYK3k;8#M*J~rsLk53C z{%oj}%QNq0ap2F|lziT4xB>Zd?c4I)=GuJZ&wnh-qR@Qwq2-gL@L)NTBM1AmU#YbH+B z`HcK|$^vt-uE$5@&$Z)=h`%Pk;=rHVwJ>nU!_`nj9z7t7ug@!w8gj^trH-c7F1M|5lL3fj>)Ls?xq* z?)O#N?@NxVk`A!u(=tX$uw)T>-YC*Igp1J*&GD5vp;E!i+TZIf#vrowNS8BqC z2li2CnFk_&_G>70!|O)=T&BF2x~ZX&KOb~!ug?4Khi7hmE-LEk=Zo;n?UDOV>M!QL zc;@!xQU}#_>TEo7E9Wtlc)sNJDsg+s`BmclgNIC22VOGr*mBdytA<@hetWIrD0OD8 zk@qegG+0f(VC2JFX7^FwR5$YE9c#VSKOYT!N z9&+-=Z5`Bk+h!vtU+K|WwSPPZ&j4S#-dgQ_-51XQcSvrn*4jM}IeF(2j%w5F1<1)i zW;&{$(|wV9*PQOCR<@asXMhKKIjNN^FG7CaFVsoh?&*tXfTPbktC>9)ASZA8#zie? zxCA+Q^b{90sq7-;8Q_RrikkAn5Bd4G zU`6$`Ta29i{4-SzF1rNJ0I%G@)VsI+k&_p>&{l1`!w=5@n^$mG$F>eYPVSK8t{&U$ zkKDUzd^>e#j34rI>y7QzD{BIfpYJT)UY*<0A31rnuZQZr*dNaTC+_xC1DgdRCm#~k zK`rANfSf$LeJ6F<1S6+SP41*llAIqjbza@dHLD*0OZ5dyho|e zUi;%2;GTA4)uw|3kPokFFj|c$D>=N>KOY_(r%w9rk9@d)^>OOuk^XoFxT!iuz2Ds* zx$#cB3F??=f8%+HU1Q}LZa?J1)o8F)(BaQeE4bO$!gHS@d z$cNo7v{4(~osWF@sg<+Zy7)rm!#j?;s#(Ps;~C()V^p>L-6hC};~d(lm0kRi4|`g8 zs8ini;~8MHdL7lt{sG8`^M3SId&UPMzg^)pP<31wh-ZM$jUA#ca1KO%yJppJHR)~u z^4sk(qg1#40myH^#EemYJK>M~)_M7O^^BQ6^4p%hC#fq3EJ1!N`It()QSwQZ_@v}! z3h~Upn|n>?XZik7rT33g`&H?^q|}X7dS7X}?ntdzC9PO$$SP^bQd?F@TmHMXNovI^ zX~j}QR!Kva+OkU8veb%I(u$>qtdfQ-wPlsGWy#@H;_#B&tHkXkH&%)Bo3?}GlM3-k z$ukw=nUa4h#6Kl3Rfv~LzN!#kl{{7<9xM5+Lj3mc+P`MyZ;F#k9Xv;IbzrX2IJ_#J zqZoS2pqTwu4!O7Qx*X-m`{G9K9h|ScTJjw=<`qK16>d=b@U<~!7oFNc_` z`=gCqckb(=YUzrvP(zMtk*_43GjikowSOoV*3`vw6xTl%QJaOmL=E|IS95jC(08aI z+ur=4IE1`K4SB`l@5;!t?@>eEU(8HBo|J|f@(Zsbs{P@2s3AW}kbUgz2h@-gdgd!N z#23_%2UnHntQKUThJ0|UnHpsN1vTWmuXE+G{0!8P8%_M7EP0fU8giw;9OX<)18T?? zx!;tTX4$AAm-Nn7#ENgIAs-x_r<5?uLk-z&bdIw2Co|;0cSd9>PkuH-4xGL?U-|M& z0cyzomS!qnn-@V2?65pf`FYU~)R3!h$yFLoFh>rY-7`b!vYE#<5l(8+PkJOFZ_cJI5URFR3{OEFqa;R-pJV){7OP2CSy~=ow;_Qq}<;k0B zc#fibX@gRJXf-@XaosXUiRxbk&rxJ{&Qf~r|6h#VcXZTM_bzZCg)Y5=fb^OM%uLP> zz4wk%rFZEa1W|hLH9#5(2qHy<>L_~b{nHG+pFPdf@I+3~5QKa|1G!q`@Q%7-r|DUGh@jU7%vVQod zxjVgpI*KC~@VmX2UmeBD0k2HQr+L*;d_M8DX+A2yI*R2p|1rg~ysM6)`Nmf!WakUb zkjsDa((L*vweG-M20b_XXQa~|IMVyvY<-eZci_L~JU3H1WYHbC-@q4U&))3nC|3OX z(wxbiTOCD(eSeu&o%5-q!0TU>!Y5FQ*Tv{Atb%<%+QA7+Y2m!oY@Kj{1uJM^@3d^4 z@Tl>t>CfX?**f8K!E5Q%xI%25aLu(*w7yIQbrhR-#ZadCNsi*^pg4-`*jgP$-o5K7 zF>8OePWbyZ@zim_Cv2VY>r4qW+crER-I9F8 zm%9^a|DYsy5xQ*y?Z1@dF}j!DNKz{bK`gR># zN3q3k37z;o$yellxR~~|`6tnuhnqtZsA97yw&o#Md;*m^zmlza2yC~3CKg=9);zrF zxq%vfzfAwW3lB-a`xRHJdHA?m0v*6>pw{%x>%W0oXJ5e9^!Aeks@-KVTl3Jk+XgzC zIESryxK}%YQkPr6*7W9Uv4OVtoXOTX4BD1JMQ_Ye3sH#@=&!eP*qYv#t5 zh>ok`$g``J`iBRV_2)4C{COspI(H$q8S<%%F%+6mm2HOHpmPju!22s~hJ37W49$97 zM(@uz!7J zC;ZE^b;a3BMbYZRrPN*2id;vdKFh1_BHfvFRPKBcwyrqUI;Xmep%2zl(MyHZ zT9mK4mL5ONs@CGtthH33cs{nSxI+E4^dzVtTUWej?HangEiYSF{N3?Lx?LrMx{KEp z*HGFj+0|VnWQn8^Wz(v=s8=(RO!Mq&E&gb-nyR$*S8GxIyVcYvUnaI0a)!C9Y5#yM z>MpvSUPUYSW@77#*MGZ`hJE!W(YlN2^;Xfm(}C(PWa^T}c>n>IW zEvI8?-XvOgk$&q^`Zd?@iPl}bw{$7hN%dEvbr)@$EF-R!THQs#&z4fw(y7#46o0Xp zy1saxXx+uOuM#Leav589(UcP?ThRsTE-pqT(2NZ;)m_}{n?PSw`;2Xd{7;Sq^8PkX z-No8<@pR>*LFz6#WR0iUt-G^z#k;z%r%@~0sk^9&f2-$OG-jJ2fAV!KJ(^X6ZH64Q zJBCts@UYF0$3{of@Lwvh&5*l~h@wVsi>uQ(6t<4?-!913Ay2)$hDI*R#Wq78KQ@w{ zWXhsWV`|`PD&8@@I*m`KtfaLw{MBi+_-i@+8JS9*#_{gUXj-jTiPmYrBv7(RKn_gF zRsp#&B^!p6yC`yF`cH2BWnN0olmBf;MQ%*VxiRu&O3ss!8&h&_j69i=^W>DzeJ~8P zs^Hs1`yN31@&DKJp#2>CoM_(gICJt?_+4ZC*<>+8Sgl5-G(goAF?Pb(pw47L( zZk5lc2IHf7hW?tJN%!Zz*=o}Htp2(`NBvrtW^YZU`}3iC^{L;3Bx|uNya6@5_d3xU zjBnZ&qe2amY{tRaC8$WT4>d!+d9XgcE6)?H!3e)yhjwQFGtnB15zXsR>iG{7t-<&p zV{NJt@+i?7jKHC_s7vctiPm5|>rhxekD&3#sf2>KZU#8amc|@UVv~u{LiPm8JQLP5G8SJO~bHlC?RQSs4L~AgzF0Dpa z8wTk9{JROKF?IZOf6jNCDBWNFx<6mN>Z4-6r&og!xy?%jG6t%_XxoZt>W}H!I^?C< zJoItn^lC67&xTWj8kux|URB>mtx9H5gR!=FB^sSBs~U`KQiXOj$*Kk;_a9-DwMZT{ z7~>N|>6PSAYwpc4LT-Pd5fn532U_2QbM!jDq8H_JhRir|b zi>SdkncW z6hyu)W!O4oT&amRjI5{zW9`8*RJCp;&5)<%DNldo4Al&I$k(N*?mVAn$hH40Lx}}R zGvw@7%TeuhUd@pG)|Da|QcW}Ddgsehouv_)Ay@pd4D~KlOEcv3-#i_^%@n`?$VBcvp4xZF}R9ExtGf4w>MP!<|DWIOK5WkSSe>RK_`EfJ?wZ9ohfHwD#yMnyLpIJK)2MvejdREZhisffCOBl{95TTn8|RP-4%s+|OmN7? zIb?!EHqIf_-fcyUbI1gTY@9=;qa{li=a2~w**J$xaLC3vWP(FB&LPvA`k}@-WP(FB z&LI;VvT+WX;E?q;;gAUq**J$xaLC3vWP(FB&LPvi`yU$TkO>aiIEPGd$i_KjfgN<{@1cz*#Lnb(6;~X-MPjdREZhisffCOBl{95TTn8|RP-4%s+|OmN7?Ib?!EHqIdv9I|l^ znc$F(bI1gTY@9MPjdREZhisffCOBl{95TTn8|RP- z4%s+|OmN7?Ib?!EHqIdv9I|l^nc$F(bI5jw47WR^+Yfc7x&1KQ?u{wuv)eQEbL=^J z9=g{b$~OyX_iLQ{CAeSX+%LiX8s~lq?$aiIEPGd$l=Z*6C855bI1gTY@9aiIEPGd$i_KjfMPjdREZhisff zCOBl{95TTn8|RP-4%s+|OmN8haX4gxLpIJK6CAQ}4w>MPjdREZhisffCOBl{95TTn z8|RP-4%s+|OmN7?Ib?!EHqIdv9I|l^nc$GaokJ!#WaAt%!6An`hfHwD#yMnyLpIJK z6C855bI7>PaiDPync$F(bI1gT9PS)4!6An`hfHwD;m#ow9CEmG$OMOMoI@r!WaAt% zO?u}=xO2z^hisffCOBl{95TTn8|RP-4%s+|OnFyiFwP+p9I|l^nc$F(bI1gT9PS*l z^$9v>oJr7mMP$!5rK$OMN>cISjc zCOBlWJ0~16!6B2~IpL5A4w-C*42Mi`$Ye8QIAnrDCYvF{Arl-j*$g@5{QS2W3x`Z_ z$aZ1&v3{DhpcBfWP(H1GaNF(A?q0q8P^U=I>R9o9I}2K4w>MP^$dqhaL9Uw zLnb(6J;Nar9I~F_kO>Z%>|P3oOmN6#cVIYVfMP$?mIg$OMN> zc3*`MP$?mIg$OMN> zc3*`v83x`Z_$Ye8QIAnrDCcCe~Arl-j*?kobnc$Gg z?yGRf1cyv^Uxh;^IApRJG8{6&A(P!v;gAUqnQVp(hfHwDWcO7#WP(E`n<2v?6C5(x zeH9Lw;E>5?$Z*I6hfH=~g+nGdWU@Od95TTnlig9_kO>Z%>>dk;OmN6#_fo zA;TdP95UH`6%Lu;kjd_=aL5FQOm<&|Lnb(6vO6jqGQlB}bI1gTOm>fjLqZ%>@E$5OmN6#Gh{eqf|Gs7Vh z95UIR84el$o<1R)A;TdP95OkFOmN6#_hdL^f|C&M8V95UGq84j7?kjZAqaL5FQ zOg2M?Lnb(6vO6;zGQlB}-I?K#2@aX;&J2f4aL8o$WH@AkLngZ?!yywKGC7A#aL8nL zW;kSmLnfOc!yywKGTEIO4w>MP$?nW>$OMN>c4vk|COBlWdomm{!6B2~li`pF4w-C* z42Mi`$YghBIAnrDCYvF{Arl-j*_{~MP$?nW>$OMN>&LI;VGC7A#aLD8wGQlB}bI1gTOm@eH zLnb(6vKcZQGQlB}-Lc`22@aX;jtz%QaL8nLY&c|sLngap!yywKGT9v)4w>MP$?n+B zB|PCrY~YZ|?$s&p=fC|d&S~iH&G`*IJJ+EVhC?=R$Yl3tIAjBdOm=^ULpE^8WcOz{WCMpxc7KLLHgL#f_h&d{1BXm@e}+Rg zaL8o$XEVhC?=R$Yl3tIAjBdOm=^ULpE^8WcOz{WCMpxc7KLLHgL#f_h&d{ z1BXm@e}+RgaL8mcWH@94hfH>VhC?=R$Yl3tIAjBdOm=^ULpE^8WcOz{WCMpxc7KLL zHgL$~9I}B!Cc8hwAsaYkvima}vVlX^kHaAwIApT>GaRykLngaF!yy|uWU~7+9I}B! zCc8hwAsaYkvima}vVlV;yFbGr8#rXL`!gJ}fkW2)84lUNA(PFJ;gAg+GTHqZ4%xsV z8@oTlAsaYk-Jju*4IHwu`!gJ}fkW2)84lUNA?yAOhiu@GjdREb4q5kSIAjBdtot(@ zvVlW3&LJB(WaAvNfkQUVArl<3aSoZ_kad5CLnb(6-Jju*2@csfhiu@G$?nf^$OaCX z?EVagY~YZ|?$2<@1`e6*{tSm~;E>7g&v3{F4q5kSIAjBdtot(@vVlW3&LP|P7wdd* z?>p8Rf*sYqA6XwSaL59OOg6KHLl!t>vY9O$vcMse&1~V21rC{-Jju*1rAyF zXE{Wu)5z#;1y4q4!k^$dqBaL9Uw zLl!t>J;Naj9I~F_kOdA|&v3{Bhpc-t9J0V6>;4RfEO5wVGh{eqfkP(ekOdAI*ML-q zEO5wVGh{eqfkP&nA;TdH9I}2b9J0V6lXJ)dhpgWV4q4!kbti{I7C2ER%4q10{ zIAnoC)}0&TX$Cx=58IAq<);gAImnQVp(hb(Z&WHV$qWPwB0og5BX;E;7EheH-P zWZk{tkOdBzY=#VnEO5xWpTi*w95UGq84g+CkaZ`ALl!t>-O1sQ1rAwvayVpxL)M)f z4q4!k$!5rK$O4BTY#X2@{J z0*9=-F&whMA?t1ohb(Z&WHV$qWPw8_=a2;sS@&T$WPwB0eHac|;E;76hC>!OWU?7D z9J0V6>uwB(EO5xW8^a+B9J21iaL59OOg2M?Ll!t>-G||j1rAyFVK`)gL)Lv54q4!k z$!5rK$O4C~yD=QHz#;2yJo59N0*9>oFdVYLA(PFJ;gAImS@&T$WPwB0eHac|;E;76 zhC>!OWZj41kOdA|_hC3>fkW1P7!FzBkaZu1Ll!t>-G||j1rAyFVK`)gL)Lv54q4!k z$!5rK$O4C~`!F1`z#;2C42KN6H;HV942LXm$hr^1AqyO`?zeEr0*6dCLxw{ZIApT> zEgZ7IA?tn%hb(Z&y5GVf3mmfUw{XY;hphW89J0V6>wb%U%)Wn3XRLc)o6c42X7>GV zI^X_n_NJWA$aw8_kaSOT*Pzfn8M(2&Zj$b_$V2|~yo0RRUb8~Kue+9op4~Mr^!#tn zP41c%df(i&EcEQIaiM2-&5Gm<*J~%zQ_s8kky>Cv>?)`N7y|CZf_u1+B-+upa$P9-}Hq(YfW;kTBnKm3U z!y)VL4TsEd$Vt2R99+Np<2RaV!yyYCvS!+F$O4C~nKm4E#k6=pYV~bX~|xT_}P#r9GN4de%wFbOU~am1KDd42d;R@^{xhzy%urlsn5Co z$+TpzMGVi(@XWen!!t8HGud4lo>}0THH(I47I{YKcxHxY)+`#HS>Ty9 zi-u{YKcxHxY)?FG_ znPHW6Pljz~*k;Y8VVfDYS@-I+>0fZi&jZL_ix_U1;g)r0UWfPk_1~U>?6rttj~Vt@ z_g9y9DQ+1wcRm|>5}?!BdrUSrhCOE3W3qcM>@mY0Yi-EZ;Qmc2et@@xH){93>LIIhW~ugky~3yiUG z##msCjWfpb=kct@8DoJlHqICejIo*o7-NAkR+9i@EHK7u5@3u4#@IMxEHK8#8DoJl zHqICejInXX_&>Ap-{vQbu|#A^vKBDL0%NTAAI4aojY+Z@FvbF7tn&oMSYV9x3}Y<) z+9eqe7-QMeEy;es7z>QCeh!SWz!>Wp##la^on%O0j0MJ6KMrFoFvjW@V2lOE*f?V> zFve;pV2lOEINTXyfiX7D7z>QCvH38JvA`G`XN(2LSpRl|F%}qO^$ak^0%L5PF%}qO zQCamH9+jMX#17z>QC zdIlI{fiYIk0AnmACQVY$0AnmL#>N?AfiYIY0AnmL#>N?AfiYIk0AnnNz8!CzF%}qO z^$ak^0%L5PF%}qO^$ak^0%NR(0mfK1hILiL0AnmL#_Akkj0MJ6Jp+uf6g<$wIAbiF zuZ?;J7-Q+#uakNP7-NAkR(k+rEHK7u7+{R$((nex8DoJlR_6d?EHK7u8(@qD#@IMx zjO)c!HO?3djInXXSYV8eGsXgAY@9I`7-Ri>7-NAkHqICejInXXSYV8eGsXgAtoH}T zSYV8eGse=lZIZ`;F%}qOv$A2&KL`fv2n&&ZdJ*k zrUJ%T0;^PXxXp)Qj0MJ69R-ZBz!--+V=OSn#u;Pm&jD&GV2lOE*f?V> zFvj7|7z>PXxHHBAV;t^`vA`II+k61PV}UU?&KL`fv6>1PW4Zj%AT<>*#sXt(oH3S>E8D55fH9V{EgBnV zjOF)PHHbj=Dq z|J(lQu1%r0@2**)XLoH1&4k@GEA$LA@So>6drp4tv*(o0i7C&?pOfrdkSYLtlRd)gFE3m%mE?|8H)>n5_SYLtl)g2YqS73d0M@@M@|LtdS z*MigEo4ZDwp53+M^z5!Fr)PJqIX$~;(CKriyEdJkVT=XFSRDn7vA`IIJ7X*`#=0}Z z7z>QC=EE??Qb?YMJ7X*`#^KHw3yg8N&4*!(1;#ks=EE??0%IKRjIqENhdW~|Fvhym z!WavTak$NgVT=XFSa(_&V}UW&ofgJeV2s0UJ`7_lFvhym!WavTak$NgVT=XFSa(_& zV}UW&ofgJeV2pLAg)tTwWAzm<#sXukz5>QrV2q73#sXukz5>QrV2pK-g)tTwWAzm< z#sXukz5>QrV2ssQz!(dRvHA)aV}UVNM*(9jFvjXDV2lOESU(P9EHK9ED`1QT##ns? zjIqENtFM4D78qmo6)?sEW30Xc##msC)mOk63yiV)3K(O7G1eUe##msCjWfmqW30Xc z##msCH6MmC78qmAhhdBb##r-V7-NAk)_fSoSYV7bABHg&7-P+cVT=XFSo2{RV}UW& zd>F=9V2m{%hA|cxW6g(Qj0MJ6^I;fcfic#67{*v&j5QyIF%}qO&4*!(1;$wOVHjh9 zG1fg9##msC)mOk63yiV)3K(O7F;-szV=OSn>MLN31;$wOVHjh9G1hz-##msCH6M1p z82WcBy6OzN>hz4RI)kn{J)^76psP;L=&Cd5s?#&N>I}N-^o*`LgRVL~qpOb4Ri|fk z)e*Yt^o*`LLRX!h(N#z2s?#&N>I}N-^z1rB$aU4(ZX?YHT<4MI73iun=&IAa8eMe; zU3HpQqpQxKt4{N3bk!Mj)oEUht~!IRI?b!mRcFvur+GEH>I}N-G_OWiok3Tf=GEw` zGw7<*yc%6~23>WUSEH-WpsP;vYImJ^y>IT?@_OIURcFvurI}N-G#^G+ok3Tf zX1wUCGw7<*d>CDI23>WU52LHjpsP;v;q&IXL06sT!|19re&4RruSHj#=^3#~^I>$= z8Fba@_d-{lL06sT!|19r=&I9v7+rM+U3HodqpQxKt4{M_bk!Mj)#=}r=&Cd5s?&TJ zU3CUsb(#;OtInXSPV-@O)fsfvX+DguI)kn{&4ddZP z^E4kuSDisuo#w;nsx#=S(|j0Rbp~B^nh&F^&Y-JK^I>$=8FbZYK8&t9gRVNwhtXAM z&{e1TFuLjty6Q9^MpvCdSDog==&Cd5s?&TJU3CUsb(#;OtInLGrJ4_;tInXSPV-@O z)tN4tmuZ%Zt~!IRI?adCRcFvur};3t>I}N-G#^G+ok3Tf=ELZ!Gw7<*d>CDI23>WU z52LFN*Fulf+eB9#=1QdI!=BZT%r|RSYd(ywI)kn{&4I}N-G#^G+ok3Tf z=ELZ!Gw7<*d>CDI23>WU52LHjpsP;vVRY3Qbk%7-jIKI^t~$+!(N$;ARj2tdy6OzN z>NFolSDisuo#w;nsx#=S(|j0Rbp~B^nh)bm@djOWnh&F^4xKe|nh&F^&Y-JK^I>$= z8FbZYK8&t9gRVNwhtXAM&{e1TFuLjty6Q9^MpvCdSDog==&Cc>HqFy~_?>@V8+6ra zK8&t9gRVNwhtXAM&{e1TFuLjty6Q9^MpvCdSDog==&Cd5s?&TJU3CUsb!7Kjbk!Mj z)oDJAt~!IRI?adCRcFvur};3t>I}N-G#^G+ok3Tf=EJVrf?QXf?ZVKR<~lOSb=BF9 zC!NnJ=U&Qr=(^-|p1Y1Yy&cz2r!&)aGwIoN(&-spawX7Jm;7%oH!%ojBe|B`$8FbZY9*eFzgRVNwW6@P- z&{d~-EV}9py6QBKMOU5KJ-fVG2z1pMbk(VaKv$hXSDji2*X5xjBZvas42AcD*5bc6}mA=cJwyJ-hx9J-c2KJ-dDr{a)y*Gw7<*{1*Lm2K{uJ{i2`F zpr1}NVf51(^wa6b(NAa4Pp6qM`sob%=`<5YKb=88oo2%5r!xzRlinu!=?wbmG!sS- zok0(sItujD8T8Ysuc+tCXlDFTmS)vO|7?l82K{vEEAA~UV9-yez5@Mp2K{vEE6`78 z&`+nn0{wIb{dDRp&`)R3Pp7^D{d5NXbm}Y6PiN3ir@jLHbO!x&>MPJsXV6clz5@Mp z2K{vEE6`78&`+nn0{wIb{dDRp&`)R1ttzLPF#72X`sp+iMn9cFKOMP#I)i>X&4kfU zXV6clnK1h44EpKRTA-iKL>?}$nK1h4%-hZtG!sTYok2gHX2R&FGw7$&Oc?!i2K{uJ z38SCRpr1}NVf51(^wa5cH~Q%e`sp+i{(HkHgMK>AgwaoD&`+nCF#72X`sp+iMn9cF zKb>a6=%+L2r_)Rr{d5NXbeajHpU$A4PBUTj(;4*BX(o(*I)i>X&4kfUXV6clnK1h4 z4EpIb6GlIsK|h^l!sw?n=%>?682xkx{dAfMqo2;8pH4Gj^wSyi(`hD*emaAGI<*k! zr!#YMme))e{d5NXbeajHpU$A4PBUTj(;4*BX(o(*I)i>X&4e+FY>%)$)?A;a{+o9_ zn>xGDPsiw|Q!|WyIz~U8nqlGX_#Iz~U8p3zUo=%>>&`so<`bb3ZV9iyL4&*-OP z^wa4X{dA0eIz6MGj?qu2dnWqn82xm*)1se_(NCv)Df;Oc{dBt1qMwe@Pp3OA`so<` zbh^``pN`Q_r#mhB=@|WV`nBk%WAxMMPK$mzMn9c?FZ9zf`ssA1ML!**pH6pL^wTl= z>2#+>KOLi=PIp@L(=qz#^l^cHIz~U8?zHHqWAxLhLq@27X5ULemdP_(ND+dr_((a{dA0eI^A{APsiw|)14Om zbc}vFb;#(aWAxMMPK$mzMn9eIwCJZ}^wa77iGDf`ZyBk3Ec)pf{dBs=qMweJU0gr(^WfsR2em9iyL4cUtt*G5YCrr$s*gr(^Wf=}wD& zIz~U88esI(G5YCrr$s*3{# z->(_{bYyp0^wTl=>2#+>KOLi=PIp@L(=qz#bf-l>9iyL4cUtt*G5YCrr*&O&`dr{T z=JdJ1b<*j4OSzA^PCEU#>#Eap$~`URF6TPw^!8m>ot|AMo$i*dt4_};pPR6A+HPpw zxBu;V%JoF+?(MpUlXpeiAN_xQJmqbs{25(mvHmQs%UI9or?VZ$N#~^QV?Dc0WIemC zWIekMWj+7f?-u=ZjD9-ZpV3dp=%>^D8U1vOemdQs(ND+dr_=oz{dA0eI^CbqPsiw| z)BPF!bc}vF-Jj7<$3u!H?Uv}LWAxLh=|w*sqn}Q9PW00;`ssA%L_Zy)pH59L`so<` zbh>k*pN`Q_r@JWn=@|WVx^tqRj?qu2J16?-82xm*bE2P)(NCv4C;I6a{dBr>qMwe@ zPp3O4`so<`bh>k*pN`Q_r#mP5=@|WVx^tqRj?qu2J16?-82xm*bE2P)(NCv4C;I6a z{dBr>qMwe@Pp3O4`so<`bh>k*pN`Q_r=}PEbc}vF-8tLPct$^+?wRPPWAxMMo{4@s zMn9dJUi8y3`ss8pML!**pH59L`so<`bZU3ePsiw|(_Iw(bc}vF{W$vR82xl=deKkE z=%-WDi+(yrKb@Lh^wTl=>D2V1pN`Q_r~4}U=@|WVy2qlQj?qu2rWgHmjD9+OzD7SC zqn}PqFZ${D&W`fB$D*H((NCv)Ec)pf{dBs=qMwe@Pp5k<`so<`bh^i)pN`Q_r+X~= z=@|WVy2qlQj?qu2do23t82xm*$Bw;IfYDE3;jCud(^`;+Lk`y+*VoLo>6a$#%2u zJiJHgmgZEdoo2yz@ZqQ17;o@yeH{d6PCnyvIQet%wVeF5xJ^#J&BmusG5(g0weJx= zQ2J+1h5zhrF3E60KW@L*pT1-IaeE*B&#(P&zSl8hZ!_uspD>xy%-fiB|9{qV()~YW zlJ7&xpXI;&+3nBEN%voWUQW9I`tx$q{nwwDlkWfj{#pLJpIv|d`nB%&uea%b|N6b$ zeb)Pc+x*YZg5TSJ@w4mi@V~zQDZiKd{rr#jZC2$uCUZc2seW>X@4=)grth$tGNH~) z-#g7mn?kE1B=fSFz79WjGf&Zx)BgLJzR>3l&DRsENUCEqeV?=nF*AErk~N!W`nIge zZEmy=lSTbz`gSbzGns3LN%fL5eSIol4d1mpOtRzlTW7ftekL+V?EmjpJ1&R!nHnk! z4kdW6_g!qFAJ>uI9~=vr^v5i7@|SA*Idj*4VpdHI*K@C^{^m+Hd|&+6eozb3KOt1l zgIZNKecK1ipzMCJZBykn+rpA={~LclQ@B9Vc}DYjW<=k5vKrs(Q0kfHYN|T&OL&m) z@6&V4gw3@i{AjGF`TeKit;>eV^&&yOS9zXr(v9ylt_)Bd+% zW@u}YLb-!|!@G|&?|nmZc3+IQVfl%sUkJ~>%4*w?e+N2Yc+uUz^e&Qo@NCzJ4rR~|GB_T{bD z(|i%>m9~Dd-fJ!Un7Zib>hyD*r$kscb9h`88GbI#6FjShdGC)ZvcGw-uTcFDOrM)o zl6qI-JRQ>2F?-ilmZ|lFeXI81F*2aC9DOI& z`v%v>*pk1JJiHj^Y15>>`Ef{?Wce-5)3vbIL@%r)?}rBaF72&mmR6}GiEm@PTV{nA z!E230-V62>-4t#%wGNfX`{Fz=ZF z6~B|O%bWQhhe*{mah{VS3Yii$!erRRAYbS2iksTYLnZI-7;n}sxy`OTVdDR7knfvY z*-YwyFzLD>$akPzX45-os61#D<9+fZx49S+D&;1}cq>kQ*L?CgSQ-wD^BnG+$Ncnt zusm%R=ZS5R&P4qcD!oSq`O0_oGt={j%Jjl9-nuQbn><^CrMoZAb9yQs7pcP}PsbqN zf=cO3$+%!yoHougs)U~j+#D<&AH;e_Re2h|qIRehxEby3lxd22+^f2b{V2x!MZ_di z=w5`>-Vo#U6dGwFql{EI6XPwPxxbk_-zQIB#&`?2?_$pF_Q(er@&6@zE5k*qNa1X; z-g=GdnmmUq$*XiY7x0;)U*YliG{#$WWjXWP%~08SBF3BMav@_nhKgAmrB8oJo(&W zXRgGilPk&JanW9!!;{aL4{Yayy?s2E**=!--1xro9DeOzKY6zN=e||hmXWV#PkQV( zs8WV;g-89`n-}WvM{|?zXQf9U@=AO!dp}QnH->Xf_v+^~yE=_$e;T1@&ziX$G^2)| z|Lu2DWlcsd93CcM|cQv-qFWxNU~oQWZ0^Xu8*lcXEWu&zMmi6aG&8``cg%#f&Qc zMFVb@ql&y(ALRSd(}bJe4U;EFV?1GgZTZJ>9(jy^w>|!9#dAGXr0MG@@0L0pICmM3 z9KqwRQAB%w+_SP=|1rk%xcDso=eIg?4YRI(hIt&fptf|xtV=)XRpOosp|StlpS&3OUza?j^%^Nu#$(ovT~w0uE)0_yn032y73GVmLu3eMUA(6PZ@nHSMKSA6 zS1iS^zX+9!n01#+l;(SNLZl{U-SN^voOX4H9KozB)*_tu?ye+FG3)Yet;B_Uhl#J<=O%qROWufB{N#{(XOOE~7${I4f+xwlni5a!j-K@)gMnFz^&dG&%O^M)$b zz_S71g8^W>nSVQ+f5k8gdu2>+>R?a+M@-cT&pEHF|SfD zpUI6st|9X=ull?@Ho42nc`7p1-7i8yx?}p09m{(0cD8g9=hDv?R ztGO>LaMv_=uMy@|fe#GlxfmudFt3g_?aDL!yz&?3(!)OnaOT@S$%45Q@njT_4oOgXkn&ksJmW!7z8uIDT-?wLQ^F46O|77xv#OAB-+M9h6?dUu?w=l-$x z&9s{{^*m(7ZBt>!G(8s@anCP(`zFWgjOuk|o4I^7 zT6%1s>6;n4*JSP@q}gU7WyXZrz8PuGnr53QSZ01d+xO1X8)hgkkkE;vA>m4WZf_B|bN z-HhlmOAZa6F zz^owO#aUmN8DGZA#@un9w|vo@{${FFn2qPD$5&02YE$KSo;Xi~sLiIbU#y&O660-j zaJyO4FGh0SkMSpZE}dm@JJHESnDN$Z*+ zzEef_nX6f%=QA z@}Om?uhi}z&AUIZk@4R3-cuom&ENjGZ)4*T966-^K zz03V#Uag6g>YuLn?rZs@DRB?Cb0OZ-|HMhNwRNPtJRIsfclH)lY_l87^A zTD#TKeeZhj!Ti6N%U`dNT)_#RdL2%gA-UJcwN?q9E3s$Hr2(sCP@yp2+dJn>(|=Y< z$GhvjPbQx+-wleCJ;M?_KX*TCLieqd3?X5@mub(NrrB1?N7ci8PfA`gmlv#%wSMv5 z=AWH6{d26A58@L%bvs@(Wjn8u7l{d;xvwvpn7HNAsAZUsA73#Cb1#>eO!3}_c`lm~ zvG`s`5Q~W%3z5e`2-kX2aa2lG8uld#cJcGq(5&p$iF~ z_RFuE)t#5iqDu*$pC(;1%h#jlyGEGrRMwkj?d!$T;@*1it+O{w$0f^T1U^5w&2_Wm z%3|>g4fCDJaKk*#yI3~78|M3}$1QWa+afvp&3bR_t6OIA-%BL>(FD(_^S4cOnI-Z& zCwN}uyJ;?bwovBY5B23Ux6QZv7f8h^>%9wC-7!1bE|!G}37&z&ZkhtS7s!L7p}x{z z+%yXx%$Jr4p}tp(ZkxVE=gW!k_1-PJ@0xcuEtC->52gIV!VNG*>YfVh_B`5 zn`TGEEcq-=oHuoPeE!NgGJQh4XVHV}ra;?SlDAHXuXD(C6ESC|Jn;+h-OF;rWQm(0 zoj#8B?k#-RG=4BkGG>nV^c#D}?9Dw(K0dMD^JV9&=3=TDGGbJ)@A9*&W@ygo68JF2 zyJp92v$f_-89#Tu$6N1;xf?NEs+JG-t;Ww=Z{2ihpJu(M_qrQq!q3yB{nz*#q2py! zXzo<`r)i8AGlcC7v46*5hOnI>b_c@@WIF@xZuZ~oY5&dbY~6pEGu53g!!R@7biK~` z-k&AMFf+FoxXE=V&y{|dnNg2#@bRq+WEE!SiYwRn_AiTN6J}=r`9LdXjrpj+7#pne~?);&Y?cN?Xj#I?eX-|vD3-mlH z^?feUbcucLC|-2&Ee?oXuIB;oUf~wsCp|aq|K$vSxH{=M>*L4A*_S`*xh(XH?|5E? zr02M=h%Ga3T5Atm05X|+xwa7BhTLsq4I8>P+c_8NM^-CO4@vOMb@;&%O61C$5|>p_t)iuV3d2 zO=rnS%MOJ0HV5XNFOitx^HSgA9~R7!KQO~j*1gBa`_7fqnBfIC-{jiY=Sv;T@GIsvS4>UZMSE9)2}xh9AguiTxs%%Ore$fbSC5 zoUuYOVTPx@bAunvS|-&oli$W)=eBKCn%~#8JnBl(im-*i)uImq$ug%`5H64T&<&ADZ^T6 zh8f-`;}LYEtd)G2;a_-uVb9hz@-Alh)60i=_@cE^1~WXg&ky`}?sd`-GyLX*@A>lM zb#e+byy}o2x#f+u(g-vBxBIxw5$hxrGu%^kA7{%HB~h5+*Cu_#YcEAfH_Y$@%@1?> zR8i6$GkpG>yOmJXQVJ#+8mcQ!;zd(3dZbKCiOpBQ=cAjaFS;9fp*51)e>exvwy&i6K2N@0d? z%e9La?~IYEnBf)v-oc%+#Y!#A@V`Ib%)QgZ$`j1+uJ_Z+@lr)~hQGO(PTK4*sx!Pr zi$Ezw#dJoc4ooZGq${8qV7{^eGIV}U%>dJN@t5CjX4VWa=O%x-ACy)zz@M@P%9drR zGy_~WF`YDA^o(r=`2O(>k|*K;+YGSU!pxFs{0+9x9h=%@kYhD3YhGM_T_)-H{2JTm zk%;1c^5f)!dLL%wOD)npm!8Y|Qpuf6@96o}%v4f$Q=pzFXGtTGm);I(O)Rw z553J(wbRPh)3^1!vp_o8QuAH;34cdVNEIj-Y7~|r{2jghUPjsR*KM|0-?4xUa;4@? zwpm}kMrox_+`F;~fB!~54v;QG3ux9i@KB(&xl&mpUu6Xx8`51V72pBb#P@ zSquA1v3r>{>-*j7Cp(^G)=V$!&D1jUP!`SorsnaN{Ju<@`$Zo~Ev-|%qgmg^?@~)? zbWPfLC|Pc~1;pjqFYe*SX2Bz{Nu8+qVVKPi?Wt!8>t?xmIivFSAT zYq8N^(vAtx+;2<%G&1o*pk{rsozlpG+yR>Peby;J29`{dl=bEFmwRjcH0%5ErvP~} zIhAI8e?0Y<9W_#ErgtH~pBzAMsLlPZw+@tvhyG!k`z>GWCug_6Wt;V7E8;IT>%V53 z^$nhzR!$6h$u{d-lRZ$7;$=6Slcu zwMFTqTjfV=bH9@4#w@S|uZ81p=ZLa_(zE#!wpm}`^YrppQ+0zt@p>*=Bv2gEGp=2e;T}eUCZ@ zNQR&CY1Ws&ufHUY&#hVC7m0pyI$sXW`bM_&lcJllXx3LP#829LGila$s-2(I+n-Le zzL0}{@@}gD&HBPV_LnNZr`D|R)Yt$iS?M3PSzksDlp(ubu+91&>?$MOUryG?=GRM0 z%dk9?_3^muObOZl$3%S`rF_h;e=nDKM(oqaU6;1+%D0Q7^qlgsobvI$FT;B>zhj)< z{=Kz%<@u`vdVZU#sB~-+%Qov<8J9<@fBn6lYfWt~4^C##?`zMWEYGd?$Da2NFQ8wW z^1dz1Sw;?*?Wv!itz8AF_@J?#n@$Rq^51#%JYtAfzVw#V^T@Q-WcvQRdY=RH)|CpI zv*`JcnvLYwOquljZ@-fZ8_Ua*nFHBoeJ`d5%lt|0*k*mReU;_22DRB{ednXY<#ne@ zY_q=YxZcR7Vx`$;eYbMdlQ)+Ov(5T8f8R*L78PWh^-VloRt^S?VVm_e*i%}n{yCg& z);Ft2Q`zxlezqB1&o@nEVYh5-GrA3dW#z-+qu6G2V>XtPah3YB&FDTDQeJka9mqDL z3u#k9eyQG@ZAN$Zqq35$A=1LY{?4|CSBeW_0P^sVo)d)MA^_9Sp zSL5IDdc@h0m2mx>>TI(+&(tt!`Wdm!>;Ab>N%BAP@CeMPMmc?wrkscE>k%GgoMAy; zeva280zL_s%HzY>=6Kg|{h6*qg4n(u(d4C(fDFNGGrhBE!{x65!EAHU$8~*@X>K{T z`ChJ{!zJ-vDYp6E(SNE+>C0u<=6iE9M@a9eGHmm`*xA*kMd?y(^Syn3Rpm|ZqHOcM z=I_;%AGQ`}o9}&Hsk+?#wHVuc?{q>nnKtuXw)tM+HZ|ng;{t5+z205wh?!A@ZN9gE zR4wt#QkZSNHzJ^(+kEd?aDCZ$vJl&Rukgvb649;z+kEfmDh*_0mwasVy@B7> zmJjFTfnP*!GXWj$2Xe8^_j1i?D0#~iWSj3@if$xFpQ85xGpb@@J!!usC)<24VoxJk zJiP$heD8&)q4a;0oo&AN&X`70q;7V$`CjWBP31!FJZ$s5x{J!owI)5;=6ebAD@wQ5 zA8-TYd*2=imQx*?vCa271cgc5*g9nnYHW<10(D&HeKKQbRU2FUmIeOZ8qIxskOH+uZM+szYU2!2!CroG3Uwu3ciEBdOpY}z|abGB}UyGeY*k(#rueAz+5ACJ@nzQY}YoXWn57C^h*DSn-c6OlV zY<`6*$@igslX5m(b1CvlcfFs#pDr&ipY_z7a8>spDKWl>-sfUB2g$Z=!}LCnf7Mr( zj2xxsb4$9*<62|&-1}rl*`H;+p5=5Kx%^Yox!K94GV|l4^XLclWM|HC`Z@Vq)eyhv z(Rxl5Y-A6*XzkzQZ8uhy?|&bx=X>XZrRLB5_5KXVF<5d;`ABm=U*r(+))}n1-`tN| z%6nHv%lg<*-@V4oWW}n{^7ZCW-cNsh2lbeY5khX`@fHs zDTmj4+6Fh1xKGB&@~5%h?3)@%=dNSrAAJ6-=ONO0e=n(sze6L_2g}`@edH(n9h&g@ zU}+vYNVCKX`96|{wT5VxxOUz^DK=}cW{JD14Uq9;hiI0#ty_N?`0g;x62E)?k<{!n zRI|ioQ~S!>;9;62PMz6DKKyRDW{KWK10_w*VVWfle76rS**8qH#Ohmm$g^`*icHZ7ka#tFmSz<*`U&$6YQnSRr_jH%2KSyYm7&X0{v_+q<%@P-F?=6E5 zkJK#j8FiC)r=jx~e}`uN`a>y@c9dp`F}=IU`Zl9AOYF3~hr|~fty$uY)ZL|I;%Lnh zzg^Qw9-JGcSz>-qN9mDejAn^7dUchyHO3@miJ3b}|B9nEOZ;F=d)YU1v}TFjU%f9? zW{uG-@%y5kC1=sGnk8l&+ff>f8LL@h;YRJG{_)Y8C0^LoMh+YtqgmpB6YXW(zOkAm zX4uw7ieDeCS>m2y?W9=Iahe&P*xyE~dB+%z{PY4p`}0Q9_T^})^D@p` z|8RZzt^8=s_kK&;Kz?mLN;ACylj_OWXGUtKx8aLA(zxU(&GaVrs4pYujnN!$|D@WI zVfP5l@ltK9DX*@N&>YWuu&&I-@4@DHlXz?>sA$D6*qhTQ*fxaN2v-&B(#eTHj} zw`+ARIeul7=6IiEttrz(M`?~X>u6P(eR8Pgc<((S`E$om&GBB%tS;R~jMN-&_}~cn z<@pfJ@m3eY>+P9`XpXn5ZaDt`57rzn{n7}DIx$>xyfvtoS#f)q=6G`!;&t_0gEYrG z^Q}j=Zv9Aeyu16t<@_H*HOFh%!7GQ-exx~G#fly|`*48fcs+YmmUO)aXpR??-7DQL z4b~hl*O4j`v2T#(c+H+wl3vUDX^vN~a+suf&{uQ38nY|Q%w-?RIQ$Jb`A(P&?9f+p zyhEXwy@dy8j#nygsHFY5pXPX7Jt13azV>l3Ym~e{Zz$UwugCk*((Vqr|B&PLMjjUIUBEWS%P=cO);@}4o8t{1 z5F=R*Ze*L|9XW>AA4Yzydt)eGFKWMQx9))-cZ-q8!n<_0Jkw&K9DIu&CH&{*B{Fb8 z4n41Uxm-SdP)N_`{#+$h8kN`c^v!GJVuh-DZs!*z?SotCdB@#o`R!^yJ>O^>D=nK% z*7KE`aZ>vHJU#DOA18nBi`4V0iE+~4(C2#2*n7Uzdz_zbj+gD@`I0Fv8`~UjdlO`M zwYIX&@gj!C%DD2|*yebD44N;~-p|7}$Ge+-pCmu-&cO}$W3eO!=jj#uK?Lb(@H zh;5D+w`Gwm!E?RM@v;Ril=Ss;u+8y?cU&x!6N<3S@ru=6BDeDuW}D+R4p<})CgfzB z-rLDvAQ_h9IxAtOC|5BVr+A~d!H|s)0^_J&G8P7TOzAt^0CeF zUUgX}M@E)mo8x`hc)9fTE5kO&OWk0p^#82@+Z?ZRzU6Y(Q=V;(SLeiX=@b;iHpeR{ zE2L1vAhtQ)$LE$w^vfb}b@3irvs?~cF2**;TNAWWChV!qHpg31V3iE-RfTPi*SPZv zT$i#G+Z=E4*_HC5g^z8Hmv!PQS)Dh6ZH{-i&uaOySyi?axx8W>i`&KYUr4ZH{MJM#}GV8?epsx?GQx6*-!+ z&G9;ZkAEjUo3qXFPE3vzZ|$mVbG%=Ru8~K-)nuFFHF>s1Iz+c)o8#^JajmrYq&?f$ zVsh~sDZZv2+Z=DjFyvSpJFZwZV)YP>Wycc@w(;P*=%#XZo^__PV@O}bG+8;Vr0{vm27jo zG=*bj=#5CWIi6V_D-YrqvCZ-7Y>JVOo<*|F@%nrjBQ+~TvCZ*j;qxbrjb)qT9XT8; zWqPe-o8xsj9V>^9M6%8C(nQ6``E~JZbG(GNG14jP=WKJlE$3ooen=GC9Ix%17@2r> zBikIW?U7h1m^y)NjyL72SXtZqbGA9&5&Z0JBe$~6@i3pM`iKH-&EBXV8qkJ~h1imqLrn1G^n!PpIBWU2a71^4-5Bqwkf+vEl+1uJPl=_=yY|UQdQWfb{?H-!f1#Bxv zX_pSyybgc=QgSAMzqKhj2S7eR$@xG{+z0!7(GOe0k~IoX=MrH5)$hq6W4n!Pe% zbt&vt0k&puR=HYKBeWP>vlmvhHud-9Wo!1TEv`W)$CY4f_R?Of3GZB(ZN67*U`;B~ zF+W?gSL~bWVGM!&jovqpX^{XoM=?ouRvp49s%Jl7@ zmDrlSzXn&L;sbna&0fczVf4$F4cMB!CFv{C_Rclgn!Vj&p;UTWQ?_RB#(@xud|Q)k zb{F+d2<4mGO0&BovqNYuoVPW5RX+_T{{rKD*wS0GyWmUZ=Noz-o0LrmUYO_*6jT;tv1d1su14i5aWGSqXrc! z{2p7gw=Y*!`fNcdwr1~OT0^MZhrXhq79s-xz3$lNG7V@DQ8$+D<+AY55PYLb))!NN^tP-==zlTn@CANx~Nt>c;0=@tK9?7exs zkJb18ZPp+usc;UC@tngk6V_^rh$4za8HxsFCdp7qC<#qu$UJK<8rZw5qEC|{jWm6H z=r}kB4WxnU_gd?{uJ`wSf4{f;{(K*gyWhio-`~G1*V*rV?Q38AT6?c`J@@sxtQg-= zyNq&rt1c$16Bem^bt-qs-nNxbN>jR92b2 zH5g;(WuL2@-rB)MxZV$CmD8Ivyf}aJ&H2jdZL3|3Kf9%za(ch#73Z7pyHGj3L1z@_ zj+-u2Ht*$2OYn=!%PX_jXnS#fvs^{x^e(86J|A&`a(dOCEy~k!$}6Y$MY)oEB)6h+ zdiT6mg6sB5S5B`~>0(@|Uj^m#vK}tUg9@c9r}uL~F&@4#O*y@<`r{k1htieP+w*2g zo;$O0sEj<`uZK%=yIDVK9Xi*Sd_PRIXy@oZ%o6YJm-T_%I|%0V^O~Tk}}HgP5q)MU;R>9<@d%tUW_-K ze}VFQh`%_Fzb1`e!M}f$h<(PcT)};|C1RqNFI~aY4kluym#$mRr{9){p;jDT%1>7r zs6JuY>DUW9A`x@FwRRyNyg3nzo$=>WTz^O+MtkJ=9By+W5xZR$LF;pPBBuMe>*IV= zp~PARF|4j(c7oqSoXByUh}e+h*zm4_%edE9PkZ6_8ckisUzc9!h2NW*vy3n9{g@Yi zukQ6rxm)SUUiiJ)=Plu*pO5gu@7>gQ5f>Sqh+)rcw}1~$xxx#-H}lhZJnF_4UiiKJ z=g;9!uE_Di?|olo7B`q#%?rObvoO9@GbP;%zbEaKcOSyzwWiGT!td4Uyo~?s z`k0rTTlpHx_}Th1yzqM!aqsFZnCgY!TRvww&))Kc7k;n)$mLvS)T3Vby=Viz4O3`} zSAH*VDc9^h$qT>tal7Tbuf}vQ{NAHum-3;XCwbxbsx?~5um3#33%_^4l}owLBX@h@ z_h#-`#$6UX;Dz7Y@x(H2+<&4Me((JmOZd|UqrLEZ&p)|@`)nTOh2OiQ{W3m}@AJa% z{nlU!|9STaFZ^EZZHsyR-a%gYz2`SA=Jfk+@xt#NnYWa;pFh$IzxP|SrF?CfAzt{s z%|9;Uxfk~H!tc%fY!MH7GZ8b+`)CQ5&AQDCzjytZMVz)T5i|DueIe7g-M#R8-+YMg z`YgK23%_?bZ!zEgb}ujd-p2lmd2!oB%y<^QC-lbUoxJdSU#?!jvl_JX!tXu3dl5f> z-@AXIoed~+8@O$r8dy31=XzGREn=o|&-*lJrlJ}dtdmg_vy15sAZ`(!lc=x}W zc;WYEzcZKL9Z=5;zxO`R=a%0#@xt%5nei02`nG`=esA%PIh@y_o)>;E@0vMWDLu;z zzjyqrdEDsSy51pXd^KYZ|8-RzFZ>?gHk%hu%kskSE&Jk0uKs*AFZ^ER{&V^9%C)@k zduOhi!(D%`=7ryTs9+ZFd8WD-e($Xgvv^m{%3k=rCg08G=SpXI;rBkwoW<)OtLlZ{ z8*Lf7qd{7k)xUTfBx1m<@e^@--OFg8>0MP*EgH;<*y7?es4(`=4pk8E5BDNmwC{d5z6m< zUZNS-{A8H&d(ZT{m?!5CSAMU^8;FJ99ijZ*a(ruQa_^DK?=@N1f>-Pvq5NK%^2}?# zzC-!F7pAo0tnMR~-)k|qHAi3Fsr=qc4_wUY?~GJ_ugq_)`S=-kD!=#n&^G+ui+3u& zw|{0+%@gtXW>)*#Hzn9jcGhZ`jv@+OTKDmk~Z^E;H z@^{?Wg%52Uqx{|jt*_*JpB}6HULSlP;i>~;mBGHY_%+<|z-Z<7#;@qcpS_RwO7P(~ zExd~J&mX7!-g%3KxV z`8ehG_Css($x)+~-+R1zFK%+)80GhN+|ZqyR~x7NUi;%cxoV@)%I}?+)|*G;9gXDu zj&{3&FT}M=-tVZto*(?jSmpQj-r9@X+&fnJy>=^aQOfU4yQVL{)_zQa-}|8-SKT;T z`Mv2&Zsm^aM=HPf#67ohvCSiu-zz)iW=_ZZEXn(AJm)sPywFJH_ezhuom)1)L;1Z1 zJqGfSns+F_R|$!fn?4z({N6`dxAR}6M=8JeNz+06{Dk4k?{zwN2#3puE5Fxp)d1eg zcPhWvV#;71@z^ls_da`QFus+4hw^(z4-MgiLq;gS_vET!T&?L)<@d~Qv&7Ee^cb8T zOWqHh9)r_k$@_uRV{m#bc|UM^3{HkHP7Yae9(NAmj8T zZ$RQREuTQb>Dj!%w;}HbW{0M}dkkhz>jbmM zVD{7ov&Ufe)CQL*xdN740r))zzsHjI1HZ@M_gM0N;P)8(9vQ#K;P=S*JqEwWlJ^6@ z$9+arWXb!1-{YUFRAkBff!|~Bdn|cB@Oun?k0tL1eh=D*60?{U{c zrCIWR;P)8(9vi>M;P+VA81Q=xevc*Z2Y!#i@3G|l!0hqB<)^W*F<|x>%pObL4_qHt zJ)t5aR#gJDl%98g3zsKPBSn_^g_880_ z8?(n?_DGmLaD5D}k0tLncV&GWb0*eviTLk@0&Bevgdb zWAJ-q{2qhfBjNYJ=`lDx5>5{+AA{v1WBC{?A4%S?=>v@z{2mFvcOthjgWn_L_Za*h ziH~ZUbrCnN*Nlwc5{+AA{v1WBC{?9|_9`eviTLk@0&Bevgdb zWAJ-q{2qhfBjfkDOJ*$+eh-`;gVQ77^uY2lSUxhAkHPYhuzcY682la?zsKPB$oM_x zhpLeAdklV$jNfDMdnEiGm^}uwN5brZVK3Y z67t$41SM{-(&E5Wc(g~d;SF^c|Y)b41SM{-(&E5 zBzZsZdklV$jNfDMdu03`gWn_L_Za*h8NbKi_sIA?2ERwf@9{HNWsvcE41SM<-?R9O z#TS8pWAJZkgMVZ2Z)$^oWAJZkgMVZ2Z)(5sMK=cjrt62RKJLWe-_!>G#^B%7uGqB| zgMU*S{2NEmK$JBJ_%{asruBe-WAJZkTb#?XZ`a~PmNgI9LWvDo);Zt_89X6N-VZz> zgC}Ik`++B9@PsURKk$SMo{%N)2cD3@6SCy}z!NffLKb!fJRyT8WXb!1CuH!1EO|fh zgbbdLCGQ8GkiiqO$Kdza_&uysMzisI41SM|-(&E5Z2TUB-(%zV82lbfE)o15gWqGxC4%2$ z@Ovz|MDTkIevc)W2!4;j@3G_(!S6w1V>nAL5&Ry5-($%og5P8Cdn~y`@Oun?k0qA~ zeviTLvE&lL?=kp2mRutEJqEwWl1l`?$Kdx^a*5#g82lbfE)o15gWqGxC4%2$@Ovz| zMDTkIevc)W2!4;j@3HZF41SL#mk553!SAv0dklV$C6@?(kHPP;5zsHit1HZ@M_gM0H;P)8(9!nk%{2qhfW8?Q2{2ogl5Bwg3-($(+f!|~B zdn|c8@Oun?k0p->eviTLvE=cU9byg7s4W69%z-(&E5EO|WedklV$ zC65PwkHPP;V|FWAJ+{dAtuAHe&F5EO|Wedwkj_16cBS;P)8(9!nn2-UX2O zgw!>ay%!+y4`PGOpsnz4CtHuD)^oDog5P8Cdu03`gWn_L_Za*h8NbKi_sIA?2ERwf z?=kp2GJcQ2?~(C)41SM{-(&E5Wc(h3-y`Gq82la?zbEfybS-D^k93V^?`U+b3x1Em z@9FX8einn@QycsqgWppd{2qhfQycsqgWppd{2qhfQycsqgWppd{2qhfQycsqXMO#M z+TiyX{GQt2_Za-1+TiyX{2oaj5Bwg3-y_N6f!|~Bdu03`gWn_L_Za*hNgfaU9)sT_ zvT60G5x8NOF4M_X7AmGJY?B-y`Gq0{A^LelLLEBjfi1 z_&t(59yq;F@Ju#Iz78y30Lw?l@&&MbBso3sdjb3&8NV06?~(C)0sNlE$l&*|PqqOW zzZZ~pCduQ0(+lAANb+@H`2tuzjgi6f1+aW1IX&=u0sI~rzZa?vYEH)Q1@L=h{9XXR zN5=03@OxzZUI4#G#_t92dz!}szZa&L>PW`#1@L>C#{<6?!0%}u5By#Lzo&UT@OuIL zp62nu?*;ICn#Tjb7r^gn9uNFp0KcbsJn(w~{GR6V!0!d{dz!}szZbyoX&w*!UI4$R zc|7oY0sNlk@xbo|@Ozra1HTu*?`a+n{9XXRr+GZ^djb5O=JCMq1@L>C#{<6?!0(aq zdjb3&8NV06?~&y3HkNY%{2m#<7r^h4@q1zWolVI2y#RiXjNc33_sICY0De#Nc;NQ} z_&v?z*`8T_Hf=AhK99EdR-dEPXV&)K>T%nXt9I(Mocg@m-dnBT_T;KJx9BtnU(74#XA)xVcYTLl?1@L>?2Jm|U{GQt2_d@Q1q8fLD-vdW|hT7ow0{A_( z!S4m|dwMSLd*S%xN@}01Pr&a5@Ozra1HTu*?`a+n{9XXR$CAebzZbyovE=cekEAG zxp!mDV&VC+XRv&8Z%e15VP>JzS-!akRxN;4W64>)yS;EIdE|7KZ|;Eu4B!A+_Va=R z4B!A+_Va=R4B!AY9|#UGfCJQgAUMDP4p8%f-~a}Z$ z01i;|f#3iGI6%z@f&&cT05u;7_Ah|_(;Oh!zX0}6bAaFj!{D;VHBSf*Fn|Npd>}Z$ z01i;|f#3iGI6#(sAUMDP4v-}u2o5lS17yhuf&&cT09o>Z-~arw4v7fZt=u-rO!ARxd29vjFAgq zBAW-ox*BV+ag zm_3qxvS9WCm_3qxvS9WCm_0IPFM!!2WA*}=Ju+r5fZ3zE31%<6G;=u_vlqbZkuiG# z%pMuD7r^Y1F?#{b9vQP2!0eGRdjZTI8M7C_?2$2h0n8p5vlqbZkuiIr=RGsYn7sgI zkBr$1VD`wEy#Qv9jM)od_Q;sM0A`Pj*$ZIy$e6tVW{-^73t;xhn7sgIkBr$1VD`wE zy#Qv9jM)od_Q;sM0A`Pj*$ZIy$e6tVW{-^73t;xhn7sgIkBr$1VD`wEy#Qv9jM)od z_Q;sM0A`Pj*$W??Kaz~u3t;xhn7sgIkBr$11K&);*7;WXxW;?d@J<%wAa3HW4R+*$ZIyCPTpyUd0A`OR*9T@VfZ1co^?}(7VD?yYefFIP zyf-~a_Dj z4v-~(2o5lS17yh`f&&cT09o>f-~hvCZw+I~AA$o6-~d_jhh5%m8o&Xvg$=!j$3t;fL z5_~ckyZ{D|C3gn~FMz>g$=!j$3t;eAa(7_x0vJ5jZ|MEdFMz>g$=!j$3t;eAa(7_x z0vJ4&+#MLa00xhZ!3$vUSaNq@@B$b-mfRf}yZ{D|C3gn~FMz=VbGGUtFn9qB9!u^H z3|;_($CA4PgBQTyvE=T+-~}*vEV(-{cmWI^OYRN~UI2r~lDh+g7r@}Lv`=v{CY0?KEJjB+8G|&8G0Pr86MghYC}82Lpwu# zUC*Ic`$4N4stxT75A6&s1MLhC?F_ZwELPM*J40>gWq9aiu;lKbm*Jt8!IHa!Ud9IK zWw0=K(975Wy$lux4|*AX<~?m#a(5SB`JjhhhBA22%kT}ZXsrw$^fEm3GL*r)b>c%F zdKt>#K`+BYFGCqT=w*25WhjFOy$lb%3}x`3m*I~O1UHP_9dt1~bTO2*gLa08c82nJ z(9ZB9uED!NcWm!S+E^fEm3GL*rq|M1lwdKt>#K`+BY zFGCr;W8FJ==w&E_2VD#gT?}RIpq=5NouND)v@<-kGnB`JUWSKWhBA22%ka?4PzJAG zF>_dKn&i z8EkqP9(oyUdKt3+gN4C^UWSKW1`C4+y$lb%3>F3tx)>h17%Z$Ev@<-kGuX51BB6Ww7aGc<5!YFnBqAi+bo~u<2!Z=w-0!Wq9aiu<2!Z=w-0!Wq9ai zurPSg%h&+D3^u(C54{X!@SvCBp_icy9`rK&f+eI3Ud~wqJ@hh^!Gm6ghhByE#n!9^p!8n3mhUV@bd2KvFFGF*8(90m`WoYgWdKm=049(p^BZHukq4_#!XArbA zG>-?p41!*U=I)@ELD0+4+}-QTCKL2BGmqF0WVAIPW z=w)c`?!!)f>7k;{Gr7tr|{6HP|gkd6dw8%%DEjG^qq%3g>r7tr+|jtlmzFN__n;Z)4nIKK4eqkJM-FR z=zVzTeQ2AZ_u--Up*HkBJoG-a{IN|tJoG-)hTeytwB;$aq4(jT_n|iQK0Ne3^taIa z@X-5E`{EggJoG-)hTeyV-iMZl-iL?YhuYA~@X*Up?(UxtKkuQJq1+wxGCcG$SaNrd z{;=CaFM}m_2fYjry$ogKpqJsHm!XUt^fEm3GL(^nUWSKWhB9){%ka?4P(}`V86J8W z%E&=4!$U7a89C@>c<5y)BL}?<54{X!dK`+BYFGCqQ=w*25Whf&Dy$lb%3}xh?m*Jt8p^O~# zGCcG$l#zp8hX1V?+J+bndKn&i8Oq2(FT+DGLm4^fWq9aiC?f~G3=h4G1S9v+#~yka z%E&=4!$U7a89C@>_y@bsS4Iwc86J8W%E&=4!$U7a89C@>c<5y)BL}?<54{X!dKn&i87#Rw=w*25 zWw7aGc<5!Y>1BB6Ww7aGc<5!Y>1BB6Ww7aGc<5!Y>1BB6Ww7aGc<5zdU!Uq_c<5y) zj|aUB-*eV%HoXiFy$ogZpqJsHm!WJP^fEm3GL+4OUWSKW2Af`nUy?OTIX&oQc<5y) zr&pf#dFW**rw6?Z54{YQ+#U2XJoGY@(}P}yhhBzqddH#L3%v~G^q`mFp_ieY9`rIi z^fHvwgI; zK`+BYFGD#!=w*25Whkcyy$lb%4CVBom*Jt8p`0G{GCcG$l+%M=hKF8;a(d9q@X*Up zP7it+9(ozd=|L~ULoY))J?Le4=w&FU2fYjry$t2_pqJsHm!X{Af_3{m^fFk!vj@El z54{ZK^q`mFFIzl?uS1*&y$lb%4CVBom*Jt8!J50fL^XGm-A!G0!KaD-j&i)FAH78uNX4*Yk&&hrZy$ph0hUV^|mqF0W(A*vLG6;GZn!AHu20<@Fb9d0oAn0Xi?hbkx z1icLP;n2$<=w)c`4tf~`y$sFWK`(=#m!Y{k=w%S}GBkGwy$ph0hUV@}|44nf=`^X& zG%Y0c;n2$<=w;|}=w%S}GSr4%20<@FZRlkX^fJ_jUIsxgLwz#zG6;GZYC|uBpqHUG z^fCx~8EQi>gP@n8HuN$GdKp>|^fCx~8EQi>gP@ne!s$UTgP@ne!s$UTgP@n8c{b=} z5cD!M&j!5=TK4b*ESw(nG6;GZnrDMv20<@F^K8(|An0Xio(*~#1icK+vq3L|KHvJF z=GmZ^LD0+4JR9^f2znWsXM_y$sE>K`(=#m!Ww!=w%S} zGBnQyy$ph0hUVFzmqF0W&^#OTG6;GZnrG{I{sDqshUVFzmqF0W&^#OTG6;GZnrDMv z20<@F^K8(|p!Xh|u6Z`-Wze?Up-YZD8}u>=dKsE$gI)$fFGKTe(90m`WoVwQ?#R6a zy$sE>K`(=#m!Ww!=w%S}GBnQyy$ph0hUVFzmqDj(#=TDHWf1f-G|vXT41!*U=GmZ^ zLD0+4JR9^f2znWsXMZUIsxgLvwx5%OL1wXs!=>83ery&Gijlu!EqNp}9Wj zWf1f-G}i~c41!*U=K7$QLD0+4Tp#o@2znWs>w{hfK`%pdebCDw=w)cG4|*8{y$sFu zK`(=#myyWz6`;;L7i+E$dKm=049)dHFN2_$p}9WjWf1f-G}i~c41!*U=K7$QLD0+4 zTp#o@2znWs>w{hfK`%pdebCDw=w)cG4|*8{y$sFuK`(=#m!Y{n=w%S}GBno*y$ph0 zhUWU9mq9aMU8cD{=w%S}GBno*y$ph0hUWTAE7=Q=XIjZV)L(j$X(js+#pXBrHKCR4 zJJp`t9JXjNs~u|rOPN>;SbiJp^UAyFSpQdk3q57kJ5H2OXdfraC-j1){QvQ{|IWD* z+RgG?(QXzE%E~$RjNC`Hs60j-29~)>>;LZGT=xX;#r92mt zhfnHwxar=be#FMacqmqI*iU+RzK(}|FYoi0U$}_BK>6aQ?efQaF5$7Lr)S#d{?p5s zaX#wblkuTH9p74Nf%9T~`gnY%<_b==oB;0EhWLK9{_cF=k+Ji#a+TF6(})FL_OU9S?(Uy~j5$)L6&ETf3+DF;6tp@$g}VM?609q2mGL&Bx;{ z_5IG@{T^rgy{mX(xm6_op;YnJyz7B^B>tgV>D63k&vX+1P+`$3zHPt+694dPSjlek$#+ z7UCbOf7*tZ?v&ZR~PZk>&ue(hpW;X@|NeSlK6+2=jU)*lO`no zVaT3Lp1l1E694ern3{a%?4Bh4;h{&W^PxKj>wQVxOa6E4A5Y!G<-V`Wzg#p_{n9&A z8}jN=Bh^3ryt^s)!G1dN57&J`TK`Vpzk!$ka-aH#%@5zg10Nf&{^5sX19(l(yVXB* z+c}i~b?sfq$8Gq8571Pu|)Vi}Ux4WZ?_QU_q zZ?IVZ2YDVJK0JWWx#{j8{-ON6xA2Ll#s~2af2_WNx1G2zh<|AC*mZnt{e&R?VO@`| zd`IE?gZhVzE4l4Q6N31MGtO$qPh?C8;vZga(TeZ-b9@m0(CGu>seA4Y;vZhw(UgZ3 z9uveryfLXEHy=DQh<~v0sqIPq4%n&oy)V08+Rh8k`GcA^s}RILZ0+$IRhwNlh=1ty z$uCrBW2qqiVa$wQ>6QHALHxtY>BnjBy?=V~57%B_h|6#P(Tjh0`@JIEY{UUC{=vqZ zm-~|XjoH8ByRxa@YBT@5LC*W$Jx}uEj}-Q@eyE82<>3A$z4(W_?w-%TZY|?w{qR-& zMf~}=bT8|N){B<#%B&nOk@o-_Zk~fqY=w#+%5)(%%%W_VdY{8)4~e=>ibm-U0qU)m3;-_JbNzL{x0_J7Ow(rxb0K6!R% zEgnDO8ZTq-zAJ0+4@b#IpPbC_(J^y;tP-XLj42c3y=6h{R83)kN86U z1L6yh_(J^y;tP-XLj42c3y=6h{R83)kN86U1L6yh_(J^y;tP-XLj42c3y=6h{e!J< z6aFDZFZfi`^R@L}u=v6wzEJ;w_`)N;Q2&7V!Xv&=|A6?yBfe1ofcV0%pH?SWeBlva z1dA^`;)`JMg{)V#AM8DTknc+%zVLYW9qiq=$Gh)f@4h|WeFxdMf_L8@@4ofB(|Gso z@$Or{JB@eW9`C;OyVH30?XNwfjed99)~i~-#dmsM#25Ic$kbr*1tGo&7GDtJi(v5u zA-(`puJHvSzR>Z2_<|5$=y*VUL5MGOJRrUx#23Nh3qpJmEWRMb7s28SLVOV{zL5A= z+hh4*Z71Rj!aGOR>cTrm!aGOR>cTrm!aGOR>cTrm!aK(x`vvgMk?_tj$bJF5b0oZT z46?5r?;Hv59963e?;Hv59963e?;Hv59963e?;Hv59963e?;Hv591~hyiTu2N57Xj7 zZ71RjLVTg)0r3SPzR>Z2_yYUDa&$Z(z97UGIvx;T5aJ6R4~Q=a@r8~D#21A4LdS!} zvpU`^9@OujBfcPTVyd+YPK>~bsn#kuF#;#1TC3p12%MN|t%4IHaAHCBc!ConaALtY zF#;zRj1y}CPE7k5{y8ANP+x@jA|Sr-7GDI!7vAEFfcU~&d=U^|c#AIr;tQQG5MKnu z7dl@cz6gjfbiP1*5fEQ^i!TD=3vcm7Kz!jXz6gjfyu}v*@rBM`h%aQnhL`8!RMQE9 zk4?4{@kKyL^J{<8yKzyM-9Pvd!e4#!Z@kKyL^J{<8yKzyM- z9CJiKe4+Qn_ULIp{2ls|vZpxiXRO}>;tL(;h%W--3-u3(F9PBV^$&&bz?dc+s%9}r)7#24xx5MOx27wR9dUJZyZv>#G6n*VMsX6t{p_#z;_(EKFgi-7n- z^OJ}#0^$qJPa?huh%YohiTDEgO82wH7Xk4FTYM1^U$Dg&0r3S}d=U^|Xnqp$ML>MP z7GDI!7n+~6@u}@e-Lr72?M<-zrR_v~;Spc3#TOp&h32CWUwFh9Z1IIhe8Co9c*GZ) ze?WW@5MOBi0r5pZe4+UV8*gOsg=lB%{=2_p-)riAUc?vT_cZ^5_#z;_Ad4>o;tR6) zA|SpXi!TD=3$pkkAimIi6yl43_(Jnhh%W--3(ZF%z6gjf$l{BD_<}6H2#7Dp;){Uz zf-Js}`AhpDbsyrXw%^eFxwaE){(v>V<{z-;4_NbS{sC+LfHlA7qp;==So3Q>3Tys= zHNTDrtoZ}h{5l@6<_}o&>v*vFNbigJa~%(V_ctO^Ke)3Q|LM^b$y$< zrn3C7o;P*94Q^IgSv{9Av}#+cq)DM?bt{`l| ziq8i()OL#9rcUE@PSvlfTPx);{-jvYTMlwX{P9p;{fwd%BM z^myuAY0rYL8B*uXfybtX9y>14>)MOGs3qH$QTwYCPlPqQv$f49n`_M9YWdW4!pYVu zC)4$|J^R|W)OoYuoO8pNsc-2V+UvHoaA?DPwWk&>A8vW!MK67u^+1L2`QVqmjDZhM zOABr4tn<>h=9m7=hS{k&1s-NIqpyN zGspdmzU8=YQ}Ya#KUd9;)Vxh<{C=`L(#f=zEElbPo0?}pe{$TP=x2`m8GXwseak6* z%W>bP=9g0QW+%(_SzoEIvp!^*r>t+)wmw(e?uFXcpX$3(^U2nqEU|#~v)b0TEaM?H z?`pY6WumN|TEDelZR;OxXKD`rWZ$#3Jf61A?u-7``crM|XSJOdY|Q9)aZ}f0_U!Amm`_mKe1+QPL$p2S2ejW(=SuSfdffa&+_&Nr zv~N!~zgUc>eUiF1INAE-WZxLE7)R?#oh!``#QiM(A?{o8331zUMbn$1nxZ#HMCjd`aA=Cb&>%yDYl+^4q9U)paruc>YGS8U6?ruNFG-l>7PO#9a6 z1$~#D`fd^Pn$PPqSlV)LEWWAmW?*5Wh-Gm!dTJLXaX# zi8BAyPN`pcjF`-y{9kSSol#E8 zEXVH{zt`ia58u=JP>Knznn+P%Wvg8aXoULxPJLJKCk>;%E@o#cX2zV zK52iVo~@`ad0lc`zj0yZS$=Evu#~s@^|+l^ZEKH~v3BZlIgj+0)FbDSeiYlTS8eMD z`7N$n`$y}sev8j5{i)^A9_eSb(N5`qwdFk4{_4iB200h@9T4^%sEvIGgnb8UW8VQ` z-+|gcZ`wiFcc3=*9nj=0PpOT42ZVhGYGdC4Vc&t;*mpqKcMzmcuk zP#gOW2>TAyHcmLm_lj-rhSu|D`R_KoviRxPZXveRX?rO2IG9@x=2nk`x%FUf)dq9x z!Q5&YFt;Aet=eF2J(yc5Qyt8$2Xm`7m|G9#R?C37^^sxrop(Rz zvF}Xnix$rC*mtJ3?Q2up_SVJrhU1eOXg$VShyK_fhdr}|J+oQ{du9oHX4S@?S;C%K zwXYv~H4R+dP;Km)CG45ida!4fuxD0}W6vyM&#c<^?Et|DA7y+I*^G`0x1MZ|eTyQ(@n3>Yn1%y=hoK%bHoojIE_v*1f6w z@=k?4YpHt!|L*TL*!o=izc}btMhOD zp^4aWP1&pXUp?RBBJ-z_*#B%Eam_Jju-FZ+dV%W?y+ZA8&wYxotbD)P@~`|~%E;fP zoY?X^`MuaupVTY1#NBc}JMQD-C?DeTs3*krp#BiokAFjaUi>}8?ZNLt+)mUN;`ZY_ zLFOMhmmT+FTlpZi)uXo6ueP06ZEKI()=sr?9%;YYcpg^B`RuyndgJnXJ~?jvqsOh^ z)Rya$^I3bOoZ8YKay~hZ`lKJV{R3vbMKga`rN_gV*3`T3b84e+SKP7g`S`exkE6Vg z%ir?CR-e0mrIx9==}Z4gsTFF^TaoL_|A_B+;#^N>;Y)_Y7OP#a!ZCmLQw!8S(ei}9 zcfvfi&uLmHeA;BT+E=$P9G={QcPIGmw_OW|)v|8H@mx;mf2c&s-NArk=kXhz1NpIr=HsD58vX4 zF0Y-i*LUzO>u0H5=$iVz!KPYjFYSAt-*QXBK2r9_4XrC=>hVFNGd6rZE<3hc#5T&b zh|A!&6#o`=Qe5Zy^&Kca7urB^8_+h2+lDq%+-6)0#n*ysr1%9rT=$nmUyZt^Ft@%T(TDF`R+x)?n&{hw4GQt$ixYibx#0;qcWUBZoPEYI8oD%b zk4jZIOdsEwxOd;o$)#V8B<^WR|0Vr$R^nb)e0D3f+>jUp$Nh-#`ZeRUPbxn9Q0S1> zUG4ij&JK61tE+a`<4eM@ydrA%n7AhFxp0k+!w1Sg9d>njO6|^>PlsRbpRRVNm)3-4 zZ;V&F&TFef*-LIw`>RV)Y}npk z?U65D7|t#{SM5V{N{7|QyxNl{774XFexvrZohSU+EBC4W+C9g7zx1PO&r18rhqZ;Y zKl^_4y}w~zNwssAeec`MEv8(La3gbfTWky#|MNAB@-I7#kdq z4U8F%#|*|2$72a&jN>tevB&Y)yT0dO?(t!wo>D{m^DoaN>fd&DUmo#W;=GftyPj9R zpJ>ngkzILTxkNkHOzX&Bf15ad-Ilg|dF6z?;rf<5aCf4f-+DLa1v!a+==WPAE?Obc zKbzas;}_3P^c(t<Yj9 zXX}40WA{aEyI)$T-AA?U{;F;FU2Pi=YTGzb+s2RDHm=mR@us$oL$z&us%_&|`_sm= z+BVMBw(+mFJr`=*^P;vrM{2__G5nI+@JkH8q&EB#!!M}~zr^rMYQrxv{F2)6OANoH zHvAI9FR2Z`#PCaM!!I%XlG^Y~48No{{1U@2scmzXUZc%rdfetXwQcTG+vY^I;g+vZKRZ9Y}o=2^9E{#D!NWgY)EU#o5NxY{xW+o@JnjLFNFc!6VEmLQh1?X;(3Q(3h+x>27W2PFR2Z`6edke z_zn1_0KcTiZ7r>Rh_$z@vDL=fy9UWmZ9T6x*50ztPuPj|zuFcTsBQ6r+7?HsZSjR(qs1M1?O1zzti81i*4_bYZ?&=Z z4p@7ujkR~c+FNa`y#vS6eu!5j(bE zP4cKRGu7_g#AmlJt&GRms_XdnLRTd?lWQ08z_kg6ME+fg|I2UX?@~@|`JMb;Y^hJ` z6rLNTpsm=xE|CW;`;G#h|i0^hqyiXU5ML>`a;}(oJa4YoXd`Tv8{X% z+v-u<>Q~#&tG2aAZEL66IFGbnZRuAzpIw(+Z(LsbL2c_FwXNUOmg|%AS$m|P)t3H{ z^T~14C-+6$pL)Mec2DiTd%4#(9)j35PSm#XqqdDJwQanqZR1dF8AqsBZ5y}oaT(8X zc^T(w+xS=8o(r{cUU^>BMtkHrQd@o}&xy2C>XYY0?BeA%@w6X{2N|n5?=0mjZn#J7 z?-uptGoO7{?J-mEos*y5Q~Q(Fr}-t*x2nB(T@CD`32JY9>EZC)o3qtEa?2~>P`5T} ze>!|~cy9B9%72=z+?SPMIj{XzZL3plJD1wl2DPniYFnGtwrf%QfB2j$CGY+J8a^lW zel-Z&)R*?{yXGPu_>ub0<13an>-lZMu9ce&fA}AMHPyCf`G0(D!ndn`JJo#bzjJ?U z&DqQw=R899U<^FeW(#*e_fgfbJG5>K&+q#v)xa1S(`F;L8*mm&nVhWa! zW$gLVGWMKm8GBB(j6J7XM#ic1qqJGZX-YrK^R8uNyh}ey85!>>_e=bSmXYU1`qA#Y z_#Zu&JU8)u$90Pzi^q@nv3UH5AJg%Z`Ys#agZ1()*~g&yp30M_a^@$~C`n~1#Ev!c z#7@;FPPOAQsr*3dz6|Jua<@$xsx^?xs2C5%!mrM|sUFw3`)2+AZR$P_+XtcF=nxy{ z^7C~SuO^?54mXqs6;`zN8LrE^^B9$V8k)iTCu=(C-= z2hB7Tg0v@<9W_osxm?@}`L1t}_N4Av`~O1>n;QH4e<|L%X!mAaPp;YD3Gc4|gC$6{ z?ftdpH0-^$=0M~3R3T5`}g1H zk_(Xk#66uk>rK9N)R`>ysz+bsi*|QVyKCL~TMi}1g@=k8?s zxyIh>*h%FWj}Ln|44%+R+wIr>((~4tqr=4 zvbL#h{Hiiw*5_KM?Tggho!vWa+sXD#+r8Fnu`v+0;s12sgxw=;gWWr|Q}^uHnAAFL zFQK-<#zA9dT9?n<0i!$p7Xi#q<2?&h6a!xcTgFOuK>t6B|r`H_9mfo_%D z)l|c6-M=q-;qFSVS&tfS_t*QPYV#|(m&ep_`?u_iI3{}W_4Gg%Km8g@(S*@PpiAjF4!OK4;5U$-0JT6v-d{>c2;odKUH^APv0LcK32gs zJyG42D84^>{``urUy&NFO_BXk<)IbafQ;&H*R2Wrv=6GeTW9Q#qz&taRdf4ZNwlGL zk81Aow-RmemsE2-Hz(Tges(oi=kr7x&b*+SEA-Dq8_JZZ=4S6rw4vLtRb41ZwBh2z zRb9&;5^X56zp5*8WWQefiM>_b53uFl#kSm|QS~$2Q?DJ+d$g}zhO7MC0li0CZ_aQH z7a!1j)c%1C*Zi>qdXKt3li}9fcR=sa)=x5A;h_ig9!)x);kNWj9H;74-IG@&%D>W~ zs{6iKqMo;gRdszb6ZO;MRoyM+6X(r%p{g5Q>VS@!$KS2$P82?%V`=A(s_xR?6Ju=9 zo~mxj&--;8cI#5b{Zt`8+OeaeJMFQ`?&jh7QQyrK-QHD|U3UNc$h}k1{rM)2_sWl! zZmj5*@2u?lT%8}ydAFjg{$pi#`(^o2(d`x8meZ=Z&nQ1y{LhN+$4XV)p$7R;v7cZ! ztm2Mm;Y{mvcBjdj5wr*LheaH}R+ZXm^=( z_sD=suH4W0QGSDTcks4K?qk?rc1d@`23B$}9nFv48j{%2+PYnL?lRBl1E zrf?NEX<(XL@?}9Z@r)|2}idJs3UmaE2>> zbw&3}_k$5Vo#8^eimpZE4uN04n|80GF;PE7;`rqjP5H{)n&J-=w9u8 zFmiROy80a|x+ktb7#+F1sypx6if&!EgV6^!W6a)M(Oum6VD!hhs;=6oimp$)gHhg$ zs_y2g62Av{1yPG?)m@R^>2As3g6QyX)m+`naNfI6&llC)^6Ye1Yf_^9%f77O zuAhD|DiPImo!V7!TehJ;7u0kwT~Wcc-+C~5`ktDuYL^P`=m!U*W;fP!1AA9+``P%*af(VLeLvXbZBRXi)%o|g}2x(o8s-1eo?o=mqON^^Iu zD~R5_s!nozmb)e=`CQ!IBq#Y?oL4R<`CJq|S||BjRR6S2^10~0wodZ7cxhIhif1MZKioD^GwV#^&iLo*{W``e4R3Nll8RvE+^?%$Kl#ze=FyW{qWb5b6o77pS~-{#eRFw zh@7N9m*cUYm-4ayKh&u~a=s{hZNua|^=zw#$$83UHB8P^x1H56IZqus+#oqmZQ9l# zIZyfL8YJhb&C?nr=c(L54U+Rz{>+BS`LW6NhRJzzYsp5*`TElH8YSoJTPrq7&euiL z8ztxKv&uJ0&eu!MZj_v_ixqB^oUa!jYM7j_i+s^AIbVOip`nY{2`gW%pIqmB-?c$< z{nI(Ufs5A_J@(gk@p?nb$LkRPP<@j6QCiPu+Bf4uIJ^TzA3-&QqBwz=b=#>sW#+x;86c-{Dq-i=+n zZd}r-v5VJ@@3d&_;&tO2RU5l_-PodJV;8R*iydg>;&tP(_Zzu*-T1(;#x7p3iXE?G zr48}=S=tbro2d=g$b|KaviqhMe-~(U0KVO z_$)7yXYlS-neNvc^CEdROCHU1Z@9cje8Lfz5@G1M?#Bb?0r*a@TybH!AgDjvM-1miwe&Z*+Kc zj(c)Smb>!A-sr45a@@pzD1-Jqac7RZn6uo7N_o+c`*PfS=V!Tw_41;wPvp4jM>1Wt zmU+>}=W<-zPcq#XSLQ{>ZI8$$atgRkdB)`gsZF_&%$t7bpQkQ>Q-J$P;%*Lgv1B=hxaOY6AIxw(shz9 zd%oq~Xwbn-SMT)NuG3X}qg{ovT!}oCzj1Hm)3V(5e`LF%L-t0kTV}a|YqDL&xV_Po z{#kDBW7+P5$$O(QGqc?Bd$V2IjJ?sGce32MBeLC|C-z2n{gUOH4$O8(o2W= zY)7+EXYXv+WLUO)ZRXzS`5D>n@VIO@=8?V8fROEmP0w~K9^4zfx;NXkS&sAGgL=@e zZEt3~%EJ@w|ENrkE9jpa$r`f8vK%+IW^N>F$hQ~exIb&|}Vr7myw??k6X=7W~(s3JPEgiQ(*3xksWGx-HLD$mO23bqTZIHEe+y+@o$8C_c zble7sLE>u{JHC$+r^NSH*8Fi_Nh}cep~MJr-%9Kd_qoIr@x72(BfduxgT(hvVw3ou zO3V`9Yl&szF(5HcJT@fuiN}n@MDbXXSScQ35<|sfPhzfktV*mGKO++B#m|Vudhs(N zv0nU)NURq>BNFSy&xpi&@iQW^Ui^$mtQS8c5@W{Cro^7{Gb=G~>?;PN58t?{a?+=Le6(`X z*X5!;u@7w7vr5u8-Z#BU(q~@%MwO&59eAKh(#I|;lachjdm3aUee%^EGm^f#=?xi4 zAAZh&jHGX$jeJGy^Iy9)BRLn$>5-9~BP1UZ&nc3JiRUuO!^Cr$bGqcC;yGRNQSqEEx#Bp#otldlJI<3!emJ)Ob3Q!IU8lBL>}QK2 zM|?r9=F|Sp_NV5P#lEq1HTTQl#CbnDSj|Nlxthm&^|NYja-CewWuTrFlfRLVddP15YBK&4H4$tLt9)4f{@j1u;=G?RQzIOM{?9NVGnz!taJz&)# zL)-CAP4K`UJuK&e`=f`=7Ba} zkPZ2Iy0#6f&YoCPmac7d!jsIOfp%WFzc&2^+<%%sjpJghon)8x{U%-8Bzx5J!uMaL zYn$XgT5}JtN!K>XA)a0svNB!UB)$B-aO2Z-ZIe77-~~IPSr%IOc_C(by0%GfbN52P zXBFd>G4gs+C)N{@&t9Ad<2qw(!)wmBex8_DJwx%D^U;Uo0c+Kh9pKS7l>5A8!kEVKJ zQfj*5HD|~=Pn@Cu#cNKj6Q20_WV+%tXS&G~R(sMFuQ_Mxdf_*kA6|2Q3HQQ-Ptp~y zIlFs$VZ!uuZENlRz84;jN!K>mfAjij+zXhNaq)g(`G+^MPNnJb%6?(oM~wRy(|*T% z&}d|uw%`7*_A+BXc@M3;%LjjsOVf7aOY3~#J|#`tjqA<#!HC&u+HU;%I3IknI8ED) z`}Xlc+tq2>ZhWMv4?1j0({|%fKOeN-nWpW=!!3M}dnirYhec;#{b6TwUzCKVX&dtY zYkxP+59XdZuZcu;?eOt8}VOXN|Tm;{MaRig8?w^{BlsE(WG) z8+h9;z8K-3rfuNUy80r;FHPIP7j*JPctD!AfzNK^iypyg+6Mj=d=V9qrfuMXp}yGG zI8EEYmpS|5j2jH%b3&FxDFuRp^_ff3{lUjjg3=+EzbyuQwi~ zr)eAhy4$3G-$>K8{VPws5r2~Cf4MIG!nuIX2+zkww8ddxEdC=^kN5f6!EmN9o@JOG z+QAP_Kcs3O!T<7HBmLy_RMobASbsQG`zDq(^Fz5x)xL=~(SE3OI#v57ruh2dtBa}H zH?fRt4jZngYTtxK6+c}5HC6j27UuaPIWtxJCce2rc7q40FPtCwEGgq}_^$TFXNMwaNBIEj3 z+Et7;BEz`Y-z0m1(T>E=WluEPwV0Ou_kU^QGWL^kWq)Mbn(U8kTa*2fZELbWvTaTF zN4BlW{>Zj9*&o@qCi|n&mdLc|SAWOuXPh5yFFFR>2}SoX+AWzDeb0#dPunn!<6vAtCEH@26G{$?B_+nhz$HO_<47X3mSvP+Bp z&vt1!7qDGg&I@dpmU9H#rR99Vc4;|xuw7ctBW#zJa|+v~<@~~SX*t)hU0TjNY?qdE z5Zk5Ye8hHXIXAIgTFz5!W0$j-aa{jK8@th8U>q0w6y)q_Y-98_7=0W}%X$BQ>F+T1 zlX2xd&VCj-kF%de&g1N7k@GnFS>!yUc|mLu@|xLOzcJMI}>{m`_9B(#J)4J z7qRb5>_x^gvX2jB=k0JULmB76=!-PAVgKOe_U^dwYldRKVOEGc_Gf1(_9u?4?~a`h zGZgz7-^_7ClbV@|{f}8E+>q5UQ?Xw%bhR6t0xO#EOvV26tsl4|XKSWnfBL4yuIRimQ?Wn2|L3jKV zpFU{|#pv=xAEOW-@xh6ec86)$U(8hV- z=Q1b8HY|hREp&$ee3O<<`&rH~Ei!2tyh$;lU#=kEI?3{&-p+9N%A{p{YP>UQ?l5WD zuj1g0N=Hn3O?X)Dgr(&7=QZSmD^6&fWYTNM+09NE{h;Ex*#}P8R3%HdU*6pb?X0r& zcNT;?;htxf{=S)+6Ml}!(zt#ljyTyQOZVsCT}LFe%hGFwjOE`FKf`O9#5pr9W8pP? z=5rY5@XDC+c*auW}f!=X=b*Lds%9453jk| zI_~9~l|2s3%hqu(!It(IKR;W?z3jHOM^}2z`dB+hdkmOUF!^9v9MIG0#d+Z8 z63cCD!}@#&YX?-d$=2~FH(bbHXpybsQX)Ma(3^4)_*~G{-2tKI**cCT-k$u6mf1SK z#k;Np9PG1o+{^e!_Q-S3*6}dkB-^8MaJG(<8FSJemT}ac&M8aQ+v9ATY#moq@PR${ z_s-VwHt+Sa$9r#O>o}aSaC@wv`QdYrb6tC^U6`%oc3NgNgw48a9nZ7=bVDrPo~`42 zWL*E2m`Oe>Ni03nG8R53rZ>04rd~OEjM9dmOB_3&XC;oE>C4k?(S28rjs=pK_J2BN z)!0uyQGrrgS7UNEuJjO(J@GCGHlWG!yFxh z6#J(wFeyjJAf2_gL-SENItFQRkR8?!%+aw%5;M;>hgN^sV0B)Ojz^NX`j^G=8s~@Y z5(hkOVR0u%$2H}2vPFk8IWNQ^v+ZR|q%DfCy@>ly$0Qra#aK^^ZE(CON5@lb&$oeF zNsf-Env`dQZA7!pXJnxbdKc&Dc&c&bHi#(;9DQP)6o@%hG zEh_z5F95xdU=_Y}?=`)>!#Qu8wWnQNsocdgbca zwkb9?$m^V|W7`J%+90P*u8wWXjJLtjCb>Gc?X9jP3ypGhY+J{-ZSW)@_l0~A_HoE~ z|4#0Paelb{TZPv6Wl*k;mlK+OQZlzp%eWXz=J}t_Lotqvv1C3uPEY2OWL=9A;}WIj1gPv+A&My7@L{_i{pe;V6xT%5=t$IFRqvL91qmi?O|%N%zn zGS2aMBKsVtCu;)xPi3v(xIS4!INndz7LEgyHHYH^Wi8^kL0O|Xo>0~<_Vdb`#y(S7 z4|yyyu772o6pcmJaO1ex?=R~=KbJPfd@*C58q>1p{x5UZjQwO>*%LW_QuaiSpOih3 z<0oZLMt@8t0r=ZD*iUcoUKqHk~viRf=k zi;ic+{ikyhjpJf0(b+f_RCG3u1r?o*V?jk{<5*D9**F$dbT*C!6`hS^K}BaXj*(-2 zM87r813wr2_JuYS2PJww$480&&v8?7F5q}7IWKUWm7F6u{z}dl9G4~M4vyE7^9aXr z$vK7NyX5@BabI$-;dn4P?{J)$oP#)iOwLCfS0?8sjyIDtmvLPGmONSRznr0rW8v6B zIaeCn7;}U<4p7eWOv_oGV*>wIdCJCqGOnDpIWAYu+8mcFXKjwlm9sX-<;q!`<8tM! z&9R7b*5254RV41;=@c9fRXk#V*9O*p7_2|8yR@aa@cg zwjho%7F!U<7>g~4V~oWX#Idqs3*s1Ku?2CAvDkt*R#t35#xZiO0I{1H=fPM*z}SXs zK8XF0Yd(lwk!wDPy^(7^h#hhU*2?4pb-_EPST z*ipGQh1gfQW`)>YxgLVpY>i{#?@0a~e_!(Q7+3Q3xIdD|$NiN2KJLHd{qb|j2jupW zC&=HC{6YS{IK)=ZwK&99&$T$jR?oFK#8z*t z`@yvMdj3w04&(fAd+~QLEq)MVjS;5B_hiKVr|XRv$HiFUOXB$yUlPx!_>y=&#h1kM zDZV70Pw^%3e2OoL=Tm%1#xXLF$#{+Pz|SRT)7Yj|IpOYZS1cp{a9JM3|7#rAzoiBa_g`{m zjbq{UT>SXPHvC-jRTr=F!?9I~_|Sp!H?R3&`|?EepuEwP+WrV%LbQuXl{WWBmyZ)M z+s&jdQ!e8N0~2vB!lZUI3_>TrMD(J3%;p~iqe=?kMtPU!`-0(n14tQfQhOQm?dL~Dr){1znr+PuxYBj>J(m3Rj@8cWqXsmA$ z2g^EC8>e$LTKUG|1l9Q&HkF>&iNi8avXyO##*V^R%nr*|dw0a(a!@SJew3}2ZfcBi zZ#IU1dbS#~AQpWV#NhSjIcnqfSdxn*fIw3WG_8j6pPXBG5GnN9OZL3 z4%HH(G5R*uVj3Thq>hbH*eqAQXO}>=JEBlVHCVcaCcqRHh5jdV)$UdaIA1#oNjGxU zl70!8nI4HTnYn6VW&)O{Ma zYUL#$ct#jHjmTG(Zv)Xi!eBKuUv05U#KTv~*I1sf8pS1IN>m7Tk10@#+a=-@#Uw4t zEl_st6H)Ro2z&pmpj|Hq;f{HsZu8m(%5(H6)bFnRBoM!TQK-LZPr0jp4U06^ucQ6( z-m)Uyhx8Wyh~HeK`&QY(9}f={={`pl`{A35MS3jNvwX3)=>t8+X_W8$?fwUP>`PO< z;pA7W=cLUK-uN!ISkG0!r``x`U##aaW~4V(y-}>^HgcjD*8Nzl=e+(rPdGO!(f?x8 z1`izgyhQ(_Q`0@rX?uzOcP?*Ge&gX1{Z9|ZdLZ=268*2g8sv_F0i~J;T72e)vvW%| zZw$WWikkOJHP5_r$Q6%sN;NNCBwzf+-%2%)jh#XHa#hPT?`^y0g7uxtG*8wHbwTdx zGR>tmPCtV%wT>EraHnj(F>QSh&#jf&!6x)=g*3^l{@Tv)Lp;}?> zY-3UNb}VL6Ju9a*@mSC$1_5<*)ux%iv^i1urG1_<9ZSThIpOHGDPNsw*93irhv3JW zg$iy>;Mg({RmT>o`Ark?L%1LITz#O-_9j5JqI?0T5|uDB4og;h;HyrhD)2}Q?!~!b zX8$r3GARmA5?!#NS-Fb89EKVDXl`j-@wbAYHaVi^sNY@~W6A_CRI{SF-SL~UY3qiN zRgTy)?l<*AJ12y!cY?>0a@BcNL-g};!KM!7DzcpoCb_sFVq}^6ajGSX-uFP)ex>Sq zQw#L+^~R-u5_M*)8L}2CA%G_Kqq+Sz*e`Zph8+)J@{Ug_S(+mH!t*dvT}j&^PhvA zA$(q9=>*~b<(KHZ^OszFvc>@-FIR^0=^a9V^*Gqe_GoWIai+u!5{JIYpL`_2&am zOUSzP%E$(g^(yF`1!NuTywd`*zLkDv0a^E~W?Dej!-kK|A?u{gJafqUIXS=_vaVKg zF^8+q%;=8*OI=|wZhx;=W68Du@TS#Abd=NEoz23h}^mVJTS$bP}^%09y1 zl>LRVWZ&UF$bQ6qlYNT&Ec+LaMfNowqwIG)cG(AcPGo=NxsrX8=TP=jo?F>xdCq13 z<$odjGXEplule7}KF z-yRl%gElFOdEmksihb{&qL??T+6KdaM~Y%zGCM&vo^GTl=A|l0LHPD;ieg^+_Hhty zA4*Zodm)vAaNjRgF;Cuz2t?C4sfu~^aNhuoqg*8B?W<+}$hS;W%-g$c1JJcvnquDW z78`({%Tg7~!ca4R%y~aev5Yiv^TR8dX^LehKEM}sx~40ZwY2YjF!!T$#j@sq-v{Lr zD6f`et#vhDOdOo9ST=wA-W!i850_xls8OvSRl zq>Cqp)yY&W`{O8AciSU6XVF^GyP*fwHON%FhTN~=j`J2K#cPXKxhpm;te|(j>k6B* zCdKQ|tS?>hU{3|zmClbBzohyw^zNfKT~I@IKyy;Mw;>{b%+YhT z8V#}YS&p8QMMD~*Ir;s0uC^^~h%@(c^xUp!ZHIlMa`l{#>0^s1svF7wsQLsOTtS}x zclPyc&}vkk{zo%IY>-Jc-}v8ob+N&)j(PfDS7~I8$(Qpq4{RA>h5NqwnrF^_V+oh( z`I?umcd^7LoAWi#1dg#pD%HwkUb^wIB`g-^Yu>B7sR0g_=4+mOt4ae@jxW$WJae=K ze5Ms>-fk6afs{1`numKdx4?v@1)8^y^&+15s6flYdpl_!Zxm=5`6AIAYhNkUGUb_U zh7+NMTGqxLFvHAdg<7WCoi@YC_(CmfbFZ1e7Alr; z_qt|q{-jW`?C*P8AFeA370dYfDrV^LX`y1-Z(4)srGv9*1tWZ56PwR3K>ufQ-cCOatPR+AN5Y-lDUC#8m6ZXHJrFFSqPr9O2X{OfY z`lWlI)uIfo%XQB3M!m>%t;>x(=tn;CRISS;H4TKz)fBDEnZ^dg>E~pv%MFYQ#mU;q zT9<1wD-4+vlC&)}Jr`5`GcRqNq>9(!X!0Oh}v9^U$~2Wozpq4n^n z`>vRlm8tdchlgmq9ka9^zVd5(4EZiw>*1@9*y7zMIa&`NS>GC6L+GqZdia4|r1v0S z>*2rbGe>u~0M<3DBlgYXI4C4?W?ULkzKb_wAt zwo3@Vv0Xy=lkE?}w``XX{$zWF@GaXVgwNS7A^gvF36U4JKZqQ$T|(rA?G++NY?lzZ zW4naNBikiJe%byYa?N%Lkzck~h+MN>Le>GcOUU}bb_rQe*#02v4BI7SJz;x=tTSwv zkadae60%;gT|(A3wm--`HLu>mJ)BWSwNYgsh)zmyq?A?GLgJvt2^g+s$-F zk#(5u60&ZyT|(A#woAzR&$R3dY@?9%pJ~|__+8mY_?xo7a35qp;=ai~#eI-`KX$WOh>|^)RVACj;OV-xO|C zlkJ<55M&N%g2G#58%&LWea%F?F+NM}9vzK0f)cQu_VLW=v2e(U#qbUkqey3B^77$} zskzGKIw+qe3N~ann_HZS8KL3in=DYTb!mb}4}hC==PonrxTuzaA~|MsOXHccwl z-}!mB7o5(Q=6R&o5cdc;i~R?q}TvR8yDi3EcmidmXX* za)r%gH`Ob?SMZx!?d0+N`ICIA_xxA;0^KO z)0y@|>3@$!^`DQ6pUZf;z03oDN9KpWFZ0H@GN0TZnP={&%s=;E{tMTfAK5(svztB8 zwdiF&xz4;i=lb);=X2Ij?ZPSrir*F5d65t1Of$#(IR%PokL^wv)T&%9o9BZtqTe9e zW`Pev|DxA??1Mm}`~THu8NK^1y~}Nc<~EDy`9yl&pyz*{GcDho+vPu4wY&Z2n~S^u z2aDTC-?)u@liLW^mnW!hb2~HqG>-I{BUJxB#taTq3RTxVUiiw#3^!&Ks@fa9FyGFM z^1Tby7oSkAX3}}8lFn0`YUH1+N_z0JLN#uH7hIp!$AjfB>Ow}F3}e-q?1)1@m20f& zLmg4=PPxWHcSjsaDc4v&uR3B%R=LJ{O18fIe0ok;1Hv4sK4H1WQe@w|Q&M5;6WuAC z>N`pw)(rJ~-nZ&hpFsM&CZ6g({xy~^K~y{8uQ8Uo`#m4~E6#q;=Y(nLv(c`|Skec^ zlD;vP^qH|_EQ}>%WGoqbUk9osImis|!wVJD`AZy8=WMx}YVL>nCmqpXSGn^0!xxEU zgL*_Z(qf9+eAUSbtv)JOoA&zR&lY4~olveie&~xghEaXyq2(%+>Z8p1kZQR1E>{Q5 ze6e#C*`zv^Q;l>V^xEQt$8E}A;8i0JbDJL~k-a0oK)-A8wmE`I3iLPAyPIRn9|aog zSYvas1xeBwP z8mfg9m*ZEiM&AwuDm$Z_8@>BkAXe0MMpMUfb*Nh)o|-x1uzk6TXb^}2b)0dDo-=*o zKG_^qfo{`3%^cT{6zF#!CYhrbJ?C$JdBYrUpDNH;8;_eK`^N&^hnZW`J;}tIX2soZ2s&I z&t}wzYK5xBA9PM3KDQ&;@8(CgnNMiXPAyPN`vqY54s*=9S)f+04!{qm&0%$s?#;O! zfE_o@Q9^xYx?L4#{7QXh-1c-wfc=JYjeDvAtv?@^Yuv5P$ks8D8J5$!S5`9^cdwYCc1)qF^q6=x$qZ3p6@3saV}BS+{0@xuG0oeb z>&rD(i!}0)5zSa(S&o?aWx2+(qPVmV)|P9mNl&QO-}-Ag&8hPpnZR(Kej}eVcZ9_cYov$cAw`M@^3 zTw{%)egE|=+Sdrnmb5(Eyz-aIf|1Ai-VMMf#BWE5-+uWu06!7^712hXU%h2j?nvSDthpc@xjpjOKQ-KOrJ78s5K{cfFV z4bUpCK!3AF)do0BG-K6#Y=IMr1-cKdb1ab9szCQG`kDo*bScn%p0LLPr}`J@v0Pn5 zcE7O&s!9J)WaL|5Jz<4+3dOHkWb31MU7He3X9MT91*&FvDAMm+plACEdS)HE|7B~L zes>n-l`q&>rr(`x?Sda^?ELOza~IV3rc7<_8-iy8%<1T$7xWmaX;zejNhJ=Y20-)=uDSgrg3X-bHUAL;XKCJCiGH{%9MAkL$j4cr&d_#(E{~9Ezo@sEMtEdOZ=^j^;tJ()T23JtbU!HG40PXjWvYksut0V zwXUZ#_C7AtSf>X#W9@Hc8f(xfis^h%_QKfjjimn@ZH_v%3e^>&YkHYux<#R~r1@Fb zz#K;!7OF?D6J441bhkoPr+o-aC1%L;DO3(IA!w9EeuAJv9Sb3LJhnfGAK5tPjJ0@( z6Us=RXRIw_wNR4}X z?QxCp`Y226UY)O){(TMQEs&jLdb36-r&#~;tWs5@ZX;Z}>k6}9OI7`!qHy#9-Mw|K zRJkpQLi97rXSi6Zayvxf&MR)XdahKt*NMV=)u@*D`BL@ag-AI3;fl{Mm8w$QLXL=ba+4{u>W*aPSH2-+_J>%x9Dyr z!iv3Z2@}OiaUWJ)v&8+8`MPh;r!3K9e7^2;&<;y@e~_=o(sPL=*=zFE#rBaf+d#gU zS@~*mVk9oFu|&T)`N}0c5}$r*i8b@`)iKXV3|MH1>mOIpPbtRWFvSk>yWi10TQyTk z^}8d_lfNLnRKFW`f@vLLfuq0CziV2c>DN8!Uw>Jqx_lLZrXCH@C8$8XzAyr3 zyEK4>U4hD&6@dn`8{m~H1uAHE1b+R#0Z!!QtH31@xNT~HJ3r^EWm_U}(%KS9$Ep8k z=?;#jmgr0OE49PxVbi8Il4un=K@O{CjSxBJkvR#MHA z-(No7k}DBNF>^tC+EbWrMtjpB+M8bas1a_=bH%}Dr7!RsKaYH!e4^_s_)vJ#Xm7u2 z5skX7EiqtgzH0Wk5vtQX%%ORRNNohlmd6c>y~#Y+2%{4%5l8ffosCf3!V;&q<*SXW z8=-GUODz66U-v<MO+BDh~qiO7nb?|Lh9I0ETvFeR-g(uOB zwPc(tcGN1^Ahuab8 zx!MBH-YQV)68)EX7MMS-K+QN3fwIXKs5!Yn$E1n>g6+T(KVzJ8#@bJM&hMn>Fjf@V z0TU0FX{?TSXw5%P`V3)}Q%rpJ`7(`Vx8E7#ek#*g%f5C-@vX9#%7T%{UZYw!TMoLS zJMr5bk4SVQd8t9PktexLP4aJ!B>vo+ovWL6hMgxUs)PwX=&sVK)y33iAvB4*A=IL*4h_yj(uRM*_{Z$+6?3$!tcz3&fq^v^2M@4C=knU24f=y%KOc_1peM8A8z8jUNx zL`ANQ#+WcGRBlFh3ld$Aa@BIbELGD+Mx%Q#E36I8SKqgb#-R_b5a~qs%|%9I@*XR+ zubHnJ_(r3Dx)ny1*Wp8V11l*(h@`9r=>s6W`y1(zWX5^cjXpM8b^3;z0(J*bW z#@WyFREN3InD?VK)-0%?y?=MdhuI|>w``6ZW-q4LQNr!Hn`(beDb={PDQ<`wTB>oM znp4gs#V#`L>1K4-U~H+zb$izxl{`x|?!}Gn*j2w&Wn>p`FP{DM`KL~Hyr%B zR5AUBixsZ6$yX(LjS)#x0UBUI#?>jcWqSsmR*sZPECRgEtc1E>;t~$q(C~a_hvpu{KGOSoFNRLH}rrx+bwpi^Y|LhG;n` zF>JXVF15>5`y0pN%zQg6>Qq4wI^czg-_e}VyFGsKLf}`$`rU1pyil^KSik!U)dl$e z+hR5DP%PXZ*&v`=o~BQD(H#l{OVp(~u{dN)F~@Z0>{q=>t`n%{3FRqRHKKVKW{dZ) z=PGN*SU9h+#lxeys#D!q%sOL>uHWRUz#6geeP|2kWx47yJwNAbM|TM2s(MbbuszJf@sC{0zu(Md>_H5~ivaTf>ckf%CNNirBaqlnp#Gud;jeGPY z#V9+JXk6D)x^JR-iN-zaN%yBdDAu?`dU)ZNJH;Az&s;AgoPPOu@7;(+Lpx7|3@=ek zPsz2xtF`k~{aNvt(wy#68dLlNzwz_?R7b^RQNf48lg9Xp4s{YRHn<^js^_XNevd~Q z@$K(*b5-Yzc&xK&h$Zyy`ZzFg>47 z&y8a*Hc^~Ok_~Q~<*6&>vDkOT277Gs)ShRtXm`{GQ=RjaQ?)qk*lL5T-g)X)l{ozP znGKp!EKtE8u~;+527{w%O)$i(FfH-Y#yMxKO?5nRVpNI7>hi<`Yu_!=SUI^K7&5g) zW3{{OfrGP4G}eeS9`IjOqOoH3dZ5FKl9$SYk;h_UV)6F(Ug$;qR!;Qr{a!GUycl_s z+g$$04r7Qvxy{9ScKDOzi`M~>edC&7l(m?yvFLo;3rD^zR+XrIn>*xVBibm-+-A>K zJKSiRtJ`ebW{1H<8|R1PLnO|e<3=R@+_-NV=k{f>K*l}Yr5;c~Ipp)H1{%{JAD}z< zGKy4#9}`gRm>=v@i&TqwlxwB@(39wQUgg*r^2=rxsn=>GVC!Z-ypvy~J|teMzSs}d z9u}!(pT%R#7`o%F+5>feL_E5+^P`&S57hD&@u)(++b%v2)K1@coTU2-7spl5p648} z`F^%;GpNh~BQ9j?clSFvqHuq<{$`D4j@Y#&TVo9$;0TA+*}4yPCplu?;%wcwUh^D* zkFs^2lgJl5`onBJmZ3`>5k_>BPdtiFIlwwOTlu=jBle&JI%iM}n^QdIZFj)J9IAO1`>ro0w0fX2s!={yfIU86 zk)!Ehy(xyE^nv>1LOgafquk4nb5!A{@fa|`9=6jck8B9VtIW2C<7kRCO^iqBc6;1@ zJx4X6zTLWGk29@u)Bv-1tgS_J5}u=K*N8_|s#Vy@F-J|TMe;k+0cO>6)TcJoW}O2X zQ*H>;jen$jjyqQ1wi`?Lp5#2xxKAm@qSCzw8uy3YK6vHQ1C6`%t`ANedZ2M9)bPc3 zn;&T0#?ij$vgCor-7uW)QGWk{#vQVT?wuU;^6}1hPk=`!A8dX2KrubX-5w`a=cp0n zTCBIn4_T(77x;~zk0F1@Q>wFPpCw4hAel) zU8?DKX(Gj#EpS9P;^*uAC=ZUlX*)k#t!@c~&!X=WZNxJ6hp{A|g0cE0`(e}dB8}De zsvj=hDbiTgPSRbO$weBg@Kb_%z8AG0r(-<-F>Hi+?=OSaGpFm{_@3V;%PQ!Qh(38Y`-y58}*=HP(Xa zl;34ntg*J2dZU_K@k?dF$YYgBUS7N8i_IM#sPRM(y6g*oqK!PsZFYa*fFniOy3Ls{ z9nh3$UI#?>jcWqSsmR)QM1NJ{iw{Ze0;&C;QeV_0+9=E1rpg%ytVzn&Z7iuif(y~c z`QbP{$*R>h)U!z6%LLvz~>@<7fiP>5hR@0}EBmf&?5a4@B@gg({o=>6NQ=e>TMq zb&F3x_~t-_QC##Oj|5bDFA#UXEmViB67cq`fmnX5g1%(uf^BbR={9e+aX~TFbme!K zzvqJ1(OLSNAseWU4Ap~WEc^2=Xla?H`_MDn1$V1u>Asm)aYgUnO}fu($c|@LOtJSg zmdP%z2+udEAi^C(exJZWS!zau1Vq$w!RFyv>a2MJ9zAh})95T!$&B*y$Um}z;`EsA z>l}z_*9!H!_2_O>>l20g-D`~kvG{DEes`sRAgW&~RQE}a7JuV}KGkXcCpz#J`CJFn zzT*s>_}&TQD`l&FsR@{Nk?vr7n57zTrI<{U6He!5sdpwPpc(n}7yU|gP&*}HX9)S} zE>P|;{p+ceN7j9RmddiHwP=Ae+ON-2gQ;)J$j8_B<1DqhegfVoaE9%K3i^qCAS&G` z)VTfA$~9sc(dv8Wn(vjf*sHhc_tx&!VL5cSY|j7Bc&7p1U-L(^q4a&CZ8nk5y=Jz0^ENP@;x=lwp}a@~zwz@F zH&?jiRq&zkq%oehck4tHz3Ga{S4`@*O4a>WRWt2`2xh(1kRF^%%Cr??~{Ho_He zq?^>ST8WtK=ZZsFCbg*;Smoi0KE&rnEMtEdOY+DVYtbh`7#LWnv95kVcdAAfYOLQ! z1z}iRp~kvBAPBEEE!0?cJ%g~JCHcw;t5N45G$%PSj(z(|$`$>B>I>A)R_nG?h{_5l z*qLQ3?_)s2c}_^O%2vHDQylLkCprsct0}iA?|i5ePI+W2ySwxox;eoukZRJ>TuFQ~ z(~=*@STg5~<#fp(r-m14tS?Xcqw=UCjdkFA^8Jr1(pYuLPk(-Lk;WRa+#lO#7HO=JjrdQ6*^-j<+*d4FN&ODO*F3q zBKyWQf#p%-r z=7s^iO?oewHq#BsRL_C;h{NmMFd@;T_m0iy+%O~9r1zAjR9j;l)r;W$=v`O32cf!2 z^I@&d?zCTIYWnMGA++CB;68pY81I}e(0j_=S;4etk1a>CjZtLUC?UR!F@ovIIm>HY;; zbA}ar;4al9;kD>Ust4{RWa@R}Cf#$op?Rj_^`z&I9!P0L{9wQ`_J^?~f0nTZG!Mhf z+4&ml+t4tikiUbmUU3P-spa_^tB+Y2&XE6(*TZpD!mxn+UyN1$C=?ecN6a{OURM)d zr5bQl8=u$qzD?XvneJ-mHGgd*H@q>XVlSBDM|ULCo$0(sY;Nd=&Qnc_*K<=1s=+dw za>;3(m%I$7B`=t7u-uPg&K3kx%9*+t}?)id>{e@z)UcFqP_kxB!$tO+uWsKFl zRWM>HCyTLWN73C#Y2?$Sb?Lv!04r*-?=zlY|LKKo?KAYd*Qx<a7aGH)E+r zYG>CBjrHskZ;A=a(0xcd;*Heb=pI`-3m?k#ruC5Sf21?=gjzn>a5G(x#n;CNea_L{ zwRDd7^Sl?z24(1TcZZ{12p*B4&*N(;Utn{7UOrwv7gw_k z$7Y{=eO?}#N%!+!$k6B6qIV;aMs`2uJ>fS#dv$kkZ$R3sji=W49`+al5VX|BfVu_h8e)$=sgFBD&5U61^FgylOe z5+@pvkCNs=#?Cf`jaf7g=QH$q{|lOvjWj20a~MZFGlY1CZ4qOC_C)ee8QN}Ocit1f z+{#dFPp~`aiD&mSbUhr&M`K+`>LD2CoUxi()BJnqYpi(s7YpfMFqQ@JWJlsj#;RX6 z9Or}cHP-&}FdUD}*I4^A!;l@9|591tv$pUUpQ#623&)4VZ+wm(cRd`nh~_rJlicP6 z<*}@JH$%6%v5E3kh~_iC$Uf7uCa|1}tg%htyNBTzNOH$^fK!jcVWM@zD9hZ&{Gt~o zlU#Ef&mX<;C#@&O`C*+?>PWC|DfK0c`zE)Sx#jl%E!U6R%bw2uj=k^rV{ykc?eFMJ zKI!+i=V-sf;px#>MYb3Acl7HMjSiF#&i;GLUJ6HHSc8qR>?;|Vx9sSV=ueGi4acnkkgp>U$=<4adxKk-z`zB6M?#j^o zH0`sf-<0f5x6-sPW5+l@tUaElvAS;Z!?3Msx(^3#l09m9n(o`mD*i~Ek*526JkTG5 zN2TepICk;J&c12d9&VoEi$J>HmVHK}fA&RT^>pnII)Bj@yX&NDyR_4B%KbO5pbr;N zt*X%#zNDS?8o`=siSxVlsy4!{!4-a}p^u`lW<-VW;~3o+Jfvm1_K);?FA5zuR`{?Y zV|;-Q>Dsr|KbZ3DI;U%&*Q`KaOzx7dePLU}eR1%$bnPSC(Zm<;wn^8%vydLXxRsc$ zeQN8+`NAn8UHjTvtnkH`bQdt&-Xo9t;uPH%%=C@iC~O~7fqQ*O6nwT-_|*P-x_JzgJ zT=_Lk*M6(g*1kAFyu|*jA#uLA)-GMw0h2sjw#7*u7~`BX)^{I8q3Y)qezbM-qu{l+ z!oSvzo`=wL#=12l3Jt!j@W(Bi7=^9GtBh53L==Abw!+`~-(eHZR(`@;z(usKG8MPe9?|*aonATvliIR2`3TY;6EqTu9Y%M;n#}py%aO9gj4PY<;7zrRund zZZiV#(a#lhDdlgEjmXjOzHuQ2K|VS9-6qE=PAh-nJMljI6+& z_f8BZbj;DXr{9P{`<^)(cXj6&9POKML%Y^D1_!A<<9d#b zfz@j{8h0htRBS>u6?u&RZM+;8l)fegzs2R~c%hb~0#GlB?h~iAbJBaUxH&ZY1%Bh_ zciRLZuVw`w3Qux8iR8<34A0>`L8y8+MaSDzq1uMiQd4vs&QY>eZp}&2@j17r2EnN$ zMaS*5ek%xXJx);^&-1ib5WK2X^g*zU{b4Mr6UA74Qeu%GovpFfU#0kr#B7cA`q5Z? zN_p!XcQkP;$$zJ8jb-{Q7F~N~Ypl=b#?l?h*)NQpmikx5IcKb; zn_{pbI!9ym+ZuyfQ8^l`()Jj!d(v7A@MAR>Y8si8Qc z|0WB}Z^C07FVvd88BE{gI3h=qm!C*pj6BJ0w$d0|(ipkTwCMrJBKhJNCy{-oWli81 zLXkC&cZ#|ggG;nla2%8wts8F>&22=Mxy@&v2Oxvi5N`9%x&X`~+BiRdr~W6mm$`je zZ3p9?&hg%M<3ljRB1Ol0@Bbw%UOFG6?Q zaoqK))HtM`&eCz$Yj;sR6WtBR@!q?s9^#pzEFE`k(IXD6s%GoB>!jc~TqQd>$JRR4 zi$gZq#+ja$Om#lbr06zHDhI=~KSjSg-ZvQiHmB%sT6PP@y`?D{>rb-drA|%JeR#Y# z7>|ag=)RrG4931rDZ0;QwsiklY>FPs@>fGJ+$%-L15dagglwvL#WC~EsQ!y9)uQ28 z`kGgR@cL!Kr8xPs=Yp{2rwV#7#hQE=oUPxrq}r|5sCFyAn^H9nwS1}86TQ3T3B_y$ zWb2sl_n(k|s(1ip~*OyEF(lvr}~Lz>{S`XhbyUBlP+_2-P!EbgseJ9YJ{W9zCZxThmon#&F{d#H$LQ|4;9Qd@K zLU1@MS;vQasSp$uCF{6xYzx7lN6Cug$&aoI!PZI@eGn|hmHsf6)W>72=}rk)L%vIn zWB;9OY7LR4v7Da9V^hm4jdePY&YT^xG}gV_@o3*8OJnst8;?)>WxX(Vj^Ur|5RAZW zwB}R1eTHW+e%q3wjd4%se8XEc!%(Mhvd%Z0&?YoH0iv*svF5h{D(>B{e3tt0V^!Bbl%^)EvVMCcb3lkt3`fdpT=1_@2_uJJSw%# z(s_TwZpNcsFY>2Tj^WcE;_(gn!I>VgC_fd^y{1G3_PE#`;gfp6x;Vw9YV^595NvkPu3;tK3jbqiqjt@>#=-uI~1$lNmiVj zS@JP`zj}(!yL>!11ZzoVIhXVC%n;nJouc!?ilIS2OhSLj<;lQkV1k%07|ES*DI{T|gnOiR|er2`I-jlCpU z=bU~)a($5Gn)6{7k?nm-ofMs;dU;F;es7SXb62knrF>4Ri^%z~7l(vkylslkb-ge$ z1YN9BbROL2Q)q3WK64&i+_&*qLw)8v+)cH}e^0gkI1l$Jo!L@4Wog`alJWH<0Ix^lof`ykCJq~i#gVbi0EO`btlfIll^q0N!OitZ4a#-@)7$5z^x{*o#ITm-bJ0<1i0NZ>ADk#u2YNS=R&U zLa_vcmL==D1cw)fV&SJ1bnhP$FoEKrxUR@6)aM$7CjIX8W8^0&GU<1Vk5F6%-N((f zF9r_^!@>yCk%+Fc6jWE!q-&T|i=ugMovdq{_|*=>yRTFISgLtalpcyjBS|h^3qrS3 zp>Ug$tZSr%e;bNxbCY%LltwE<@fyt!*JDXq5Q;aKC+k`(6F&+?_KIX(hrx>a{0sG& z>oDv&lz`*ZXRZUYVIUB(#iVi1QR>GVv_CQ~l?1@Vi&R&Qa7!N~p!OY;#{KD50)EJ# zI;&K(<>o1hDW`wLxKj@%plu2H`pI@;^?d@amA-tuT$iKlYr_4=q-%zBf1k$gm#k}v zv#&UDA~g(O`E z!LD}MA9E8i z!Na7nHcq2>DIcm&OEovXAD4)^fhLW0We`25yD+#$$Br(ExD#vASYb^P;ne)av2zWR z{U3+XJsMQovt}^qN&m0I;ANexxIRg`qyNv^AsTyvWYqD>?(#`*a>_mUXr z_GL8;je9!RkD5n5+0Sy56w}_3RA;cYNpan(YE>zIt{=r$WO(7m4PZInheCC$E|FZc zAi3bWRaP^AnyXEU>sIZ1gW^cOF)6NFwWKMnvHMJl>sAe-b#(%*t6aD05XBNLJ#A84 zBdf>`@Hw0?43F}qD;<{n&iEc(T*Ao+( z>x?~bLv$+jGlcrdb;*S0cXR1^06(X9h348>GM`M#d~!WE=>ykulfH4yH0d+fQj@W8 zJvSL6*K?Dxb3Hei6Ry=JbHz2>WDc2@xn*4WkBlq-k#XfeGOqkb#+CobxbhzvSNc)6Zfb*giEJ;9`y9_}2Doa7|MwaDbTk>B{av@!A|*AtVP>Re;+`?tbzk?OQ_ zJwVH$6bo@IN!JOSK(*NqP;GXuRoI@^RUcYcxrSj>vv6cxrFE5R8jLE1t2s(Y-=@DNc;Bc7K|PGfpOrW%Y3)zM{K?7%Pv~RdXMc#=1Es5kCddx=L8f z`X%C{s29i1b^oLfTn|wC#&rUv&s;xH#=><4WsF>JP{z*ne`HRWmOdNjoUx=2j3s?z zEa@|2$ygXm#>iMQ_Ls?mk;m3hy-E|wLLkWk*Rf0^I+$o9PjZ{qBx}t{*0>GJS4*OK z9T2`Xt_en2<9e0yO|D}pSlmYBl-tNRxs6~M=jZR-4`rNNZZEa^xptG(@Hg)1Cc67e z^d+W6UxJ0(bG@ZSgd0R}vF_*gTyI&i#O=A>GX8=aL~n_vy7Hp8v}o=ATyM!+KzY@F z=`HVEc7LuTF)jNPw-KF+-xXbpzbQHxV~K9YeGr|E`zE>^_gQp29*gLH+1K2k@254> z+#xz=V2L|K7wuBT>!MJjcc-eU48+$(2>zEdOZ)1_`bG_8aZ~R?1H915F+p^phqMLc_aDA?`eRRqdqRZ`~`=dn1+mz}0T=z3#8T(_rvxBij z2V*SJ%@|8`HpUWNjDM3+t&=?T%X zD}CtsT=zEK&B3(j%*HuqEYX1(OLSw#5}lc`M3-hP(XkmzbnlnRf|18sze4=^mri)O zs>gF((a4kBMsz}MBf6qd_Kj|mo*L97u%xy%c zd+!}xRkekEQ&dodBoGov4+$xd1kwnk%+M62sh|`UM8QrIFM<_mcEExK6h%Z-1Vurm zxfHM>7K#ceHRPm+R8U0x=CgC2^=`+w86S7NH{S1$&wpITea_r_pS@R^Yd*inn>V}f zBW-*0W|y2&Zk9K1HZeQQ=FQUYQ*Tpmjt*_+NpK8vdiX4JefUo101=D1L7W3~hB!Co z5^>JVG2&X7dmN{1Hs&^`EC{nX&$%ya+nWo0X?2**k)q8!3_iE9I5-6bbIKW$_utRz~4@*2G^S#92gKH%o)Cu6ry!rb-BdD zeM5vf#%;qxZ0^w=%Y8m>?MT3=xaDM8sl_5wVzibYJ^dQ}p-s=3sx; zHgmI2>HT5Oc9lLe%;hf9-;O!nN8bpyxnH*@k=x73ea{h#IatJEZWghavqdcCauJI; zUc_SVx4w75{fv!XqyDPioaC8z!fdY6{Y>H*<|J_pbCvFQ-`yv;-?hdw!fa0UrTdky z>CLse-(?)boGOlCuGM{i&c^G?eQ)dYdvcHIizl=b?iZuY{o@A8!W6Dn08IDu$Ex@ zWx>K4gVsHQg|!F!+XV}25>^}!64oj_VuEZ91KO-@7@~1mM}fGkqd;8NQ6MhsC=i!* z6o|_@3dCg{1>&-fqQ2{W-&cLuz5DEFbHDqQ5$){0y!&~>-?>NcekR@CVLyHwX!oFR z$PX0mO;0%!DBQFDBv8HQynESAySB4?+)XZSXZOC{vE1k5_OL@N?m;6K_ofkxd)A1> zy==td9yelf@7sOtKIaA78i1c0sgJq0Hehh$U}4R`#Ad<5T7rVs!NMAY=%`>@d*JqB zb9?H!?>S89*%75+D|93=oU82lc%R?q}?(kAv)jrE83J}%}c1Q`d^&y*-!W!3i)+mR`Tl;#|67?DM*2JEi z5h$#c9X>M9*3qHOIy%H<9WUatju&xR$BVeE<3(K7@ggqkcoCO%yok#>-ukZhw$wmd z=ZQA!E#I&9w{@ZJ=M8^nji~#XbbBT)y2;!QNpO4#16tP$XiCCHSGh1 zwW(2U1BErKO#%XiwX6?^sK2DQ#`W4b9V5K8uWk=Yv{|$2zUPR=8dSt$Z7O21W)-nm z%Zga6aYZcFzSj3HxSz3WN2n*Jw~~)@r(+NgTtPOdP{nP4~O+?i1YaTDLTP zU%WM?N%}0Y*3|tj;~3VI;uzMNy6?}~c)z;uZGHZp?lJw%ds++iGH6pT(`7?zp>AdM zsn$Z>${jgvgu0cFXSA`pm3^PI5$aZgPqz{3Rw`5cg}RlB8}!}r>Q?qW=5IAJXj40b zW2mXYXQ{QpcT$6cSk&g=9H`mBxlzl5bEd`z*Fx=2mwEm|J;k_Z{e_yNq-5mRclymYO4cmRh8g7=NqhLYw-UeIxya8mMy~()Ze{je7Def1ze-!8U)P zmg=hA{z8q_^u7MNW~|d*{k+RxsL6VMtG`gI)$vXBiu7u@(58+9aj7FiTc|k6Ix@tij;y}x{kny})%BoFz0Y%_T3cO``+39Psnc;klWwor5qtcs z2IoAFdZc=_IYa+YKWndMr&F8OLM_kmgw|H$^Ylfnt@g(q%Y8m>PiMrU1_!aI%|R?` zb`XnN9>k)?2eGLAabNq|-;@vS)j<7J)JCX{syfuhYNj6krHxQa_1&*+gc_^$dCG+L zYOmbhyKawZ_dQ3f30@5pVo@7~Skz1*7PVA}MU53=QF~S2yWoDt#=qfjH9>1u_*<=z z`4(C6H%X?p!}f2(zJzsop=nkF1Wt&{uyoQ(&!``*^) zYwRA==k8J;A+KH=ZR)k3_E#SXuWtJK;p&s%)lH`=8=Jc6tM>W{b<-X6S)y*b^(C#X zZu-lqt*vg__r=yi-SmkMTU-4s+SJM77;3ulS!%uUoz#FM7Pa9x2WrM~Zq$dbREMecW28d4G0mYoQi?)0aA4cs259Q-_PsQVWmIQuB__QVYLjzuq^g z;|ZWmeRtb{)IR=PJjsfD5V}Q8i7$7b=28c_JL4DU7{IQ?a zm7`5ZP;_heC?UDU+s`^2#uhW2E(@Wc4ZTQfk>TTuKjPJcg{j$AU z@?8)53N_{}7W-Q5xjUBod=QITa>Swr9I>bkM=WZ_5sO-K#G=L=v8X+FU;D`wepZ7Y zyU@>S^Iw_kXEpo5_o)|+SIZwb-A}0T|5DlW)c(6Y$I+%{-+j*!iyC~yqBb9~sM$v> zYWWe18h^y1_P@S&!TpRa|Ejgsq^D?`T6Om`iDRfq$1&8ZyWf3xpWuGiPJGnbYU-zJ zn_7GKyNqL~smC$Y+Pm)$JjcJfAYBgbR_&_#vwMLWC!j=6O3JAIbCET-i@_*q61+T_6Cvt%*hvt%yevt%)SrSB2hL1>d_mAXZJ z-n9jaqe_0n@A ztEz?iLXcsFHrZB)OO6)elB0#VJ<^}d#~l&WpA zmHIUEwTvM5^M=2Z(d2$60~V_1k8;tMKjAS0pZBp0qLxd2ESsoswU3Zl)ag?n%QDLU z(Z@258kPH4_K`c5`+N|KEF;7sg9x$6CPFMSix4YQYbC)lLM$?l5R2?1_qG3aiT>_h z22?ZcpUH-LAVR&5j?^)u2DbLKEUEbOeJx|^iF17|duqAfEAlJQCNm1L$hJZ(GN2HP zY$(JcGYYZDl0qyprVxwlsrudp_cK#eHEz1^Esm!@IF2Vv z#670t`6sUuZSpGd-jN%L_m131ym#bA;=Lm`67L`EL%rX@a0)+N64zH90jn27bRmyL;YATtx^MwTYdnT$PBtd`0WveuKaiz~euIon z^d}E^*_${A#&VwzVv(hZSY%)#7TK7HMP?>qk)?@PWNac9*_-ZbN54u2Df(NoNu7S! z%Pd9zOqMD7Z8A>LpObxxexCd^w8<=W-*dzwgA}pICPgeVOA(7KQ^X?U6tT!Yt?ylM zKV#^x$mB#nMpmc$nZz+7m*E(W z=~#b}myR}h=~(xXTaI<#8Li0%w;by}a?7#qBexvuK61;k?jyGx>ppVJvF;{j_)Lc9kIw}$2pMMj&mc+9p_BOJFbQ7cdSRqmdCoA%z3QG$)d-) zfQ)*y$-%~F$)d++$(+Y$$)d;FlRSU4$@51Jfed`)7Rbg&&VkH)jNH_2wlI+VwZjC)K+{-1t5Xw$C;`wsNY!M+21 zbFl9~-yG~a&^HJB4)o2zz5{)8u4lcE`6*Jmp)dAOCKx5rH>Wj(#HyM>0^bs^s%b%da*AIN*AoL8v{s_H8wj!J8H8B$5<)C`3?UZ1huqhWeIDlDI=ZHlQCd8sQ6JpV`39;zqgjn==LM(be)%PyA zpE2y$(31%JIP@xVKa)6yo2Zl`q4y=~G3c#{x+8jSq8^D}oT!VSM&%2D^Z_AFH6+z(Bl&IJoLVF z$8w(!V$sVIvFJgGSoEeuEP7TV7QHMHiyoJVMej@ZwWF?y9-ydqqBkh&py(Nj`Y3vd zqHc;Fqo}8%_bB#%gIWeizX>G*(E^oN0k^H-*HHQ+&s9%xW{zVKhv)qZR=OA zb=UL_N8L4j!%=rl-*D7j(>EM-*YpiX-8Fr~QFl$>aMWGXHypLK^e9K0-sL!kp62*0 zz0UES^gu@}dZXhU=$VdlqnA3)nI7w?A*c5`>VfI)j=FbxzM~$VUht^PrAIv4^nAx> z=>?C^((@gkr58MEzv*3$_V0@$Wbw&rgBpH%(4)4W-t?&Xr)NF10Q9nlMt~mo&<^bT zsg2CJP5tgwQ*i&cZDj4lQUk5QjhoxZh`aRf3xceVHrlW5jF9+4b#ZGyj*!}dYJ<2t z_Nyn!|UjFTDGC!{6xq?&w9k7mpx+9;~ufzo*E&SHm@=Dy$kMV4E5^tWJeu4z1rQ+ zB#xmcJC31OyZhaD_X+NI4fXc)lt&#tz2@ETGLE6AJdUB)Jnj|m&+&OWmwQQbm?x?Y zYCGv=>>fAW_ZG(|Oll)XUMO{r->shYe(K@k9@C+}`)iEuC7e({5p6G-A1cpZS!L+3S%MA3GzZB?tNj;393p-ZoC$C;q*Pay= zE|0xd<9v2zi*V_w=Zw$Z?Hex5-mGyxdw1J#`R4T+1MOjtaengYtTLzl^HZufJ6vO+ zA^m=y?h8&XGtib!ecw;ET~}tHInB`hvnE5z478}16lwj6o&z+h%}@EsmfSJ}?P{~8 zt!0yXMM2Zr;+)pfPutMCUihb<+#+QL+P5C%TF0R0jP}pL;Zn7%F7Cul+9!NhPR}24SHySB6EF8|V|4=pN7J_T>h;#pWG# zAIq=YK+jl_;VUi9FL%y?vE1i_SX(a)m6h{romhMPL#5T@wN9)#5uvhYZmkn5yGy9# z&Zu=_W%Ue|*QeDwu~rOGt@5N=C)WHML#5`X+P_^pbe*5)Y7X}qeI`}!8I$TK@4rxH zpacCY-cR4{G6Q|+7y3L$=<^KS=%-OyJE(2wNq>*=ljxVr4D>JklC-X6aa}uK_f^0C zt?oYao+H-S31M=wqQ;5!*_be`!>e&(Eg7zT{;3)#){Xl9p8sc!6KnJpVe){s5$pLY z!=$CY*Y&*%?q>{o$y@b#i_&)lI?CVleHo^0_cMuOzA5vQOnp9a%t&od&^G!3zWeSz z0q-f_HRwHC=zBL+-@DPO1AR*SjaAxqzsopgyuQ~@=zEQ0sT-kj zymv!n?&AriE#)_^;)t#zoJ(q{?WiIu%WW&T~Y2Hc6QlR{@BN(W!9cD=R1ck(Ed>SK*Z{GyY4Gjl{x1S-P>30J*V6`w-#-E<@I*u z&N+9?_mS2~<<7ONUh5;teaj7a2$O#Fm6tRYxF0n?>u0x=8Sp@6@7H(mQ}s<#PDs!J zUrGF=uD#)cFbN2)bw1m&X_(B_bH-<%J~vFph1WWtja1*v+^|{$_Qf6N>1V^sowjdU zs07?!YrrtsnWlA$7nB>YO;%l}`RJ2n2Fw%BTs_`XX23$3xx!ao__@r0k@DK7TATY# znE^ZHmEFE_`?fLzrpn2KzB0m;8L(EaJL)UDHkTQ&7q;j*=jq?k9@8RBc7)W$opghG zU*1yd#2qj%RFbZ$b>hxltLN6Y)`=UwCsbyp*E(@~m50jC_*y5fG!Bz1BlWWy_t^`> zq?djt;-2vdlTAVOUoW^EVWArL;aY?CgU9t5i!V1|Tzvg}h@9G5`?u!}fA4ggkNDkK z_Z;$>1ka(vg+3Ct0R3vTj#)mEG_Tx%cd@gbk4$;A+<=2&qJ1QEPPqXeV@0a|{r++T zZpN2=edOz@4jtiIRl-+!rfV%<0;MBd+B>%=-TN4>MZ`TMnlD-wRtN79qa4R|B_zw?m` zx|bVpNbcI|BMWoX(^mN;&uq~BZ}s#9x8(J8KC-n>xdG3lRG(pgeTJdGp7N28%%0G_w(ENr+|L+z9SQop<>|8ljz^8YFQ>KbekO6uJbgY->GO$WhH1NvzF+7E z`0l&=1iYtw*T5V3LHmlO`rd&f3ip0xL3SC3p+*WXr-@;~qEN_ZG(w_)PDAcDZx>Lp!y0pYifPuDgy4GNomKm_o{Iowz z)cz36w7jc)WyK$51}wEtdT9MhbM=H(#@cm(zVc$AUW>BV-q81Pw7!pEvc0;^M|||z z1FLP4))vGMDL3G5J*~0+rLn-vVjCQ-dHVOe^zY!#J*w^L+6Iq~ZE&%8JeXQMXK=Cj zS@5!W40vn2MzHdD4q)i<+`#?gIfMJhYXOUo*9b-*uN~Y!-V<>Dc(1@)RBrmmsaKD;-O&A*dmMMa zQy6pqsqwVFckpb+*|X^@++%A)kEiZ2t0DUBlb=UQ)I=ZYKepWLO^T8eXSxzpX0*h z+kY-`6Iq ztu*PTd$-?~n9Ae;S#hh@GsS66wSntQ+%+xknumX~-l@JCiL4>7g)mS!!Zo;k6aM$qvllqqS4!hTz8{2St7|a#sHfj&XhL)3f0lBR5Fz~4j~w{_!Y=@IFaM4) zel|V=*lVE2>*zKAo`vpa={K}r0P3d5@2y{^*TeC2GbYXFrGjqS{&)3xW}S^M-r0D2xxL{U+W*e& zG1m}2Yp5mIbZ?3zet6KJ#(-_N7g$61d%FE?-CmQ67In7XRq&{#r&UAv%+}{kIlZj2 z_56D2&(78h%*@2z6!oAF_`mmaug?QIqL=!yd%cb7 z^LalTuWGlqJABpYsRUnjdM#a?mux+l{%`!;-Ja@ zFOuzFq*{-Xr&pv}?~;TkQ>~{-;+$0Lb#iQ0s`Ws*=8076jWT3us$FY*5}jr}S>{Hi zS^tR3I;8y{Ux}17>)~>DZkqLW**-AMdcMrQJk74rdS8}ieIm{soM!zaE|}8IuIXm< z?qDe-L_V2rJ!pytrCV>B4lUBHXU*)d)2x@xw#U+}$IZD9ceB1H zuPy3kJxZ3n+s%5H1Mr7dY|fMJy5>)%dp-kZ^mQ@*StH=?`GFH!w;p| zwa=y%8RD}gQC{4A*j(~ahGpZ2ZOgFC{AFKfSeE|G?HQJ_zvlA{%ibTqDZ?`PvsPu; zHGbN288){t=%Eaoi&%YKhV@*ytapa>VmOhMVLck6_5A7G&^j)|dOEC2%dlP#9}LK_ z9uNMQ10Kz=-V>KRl3_Xdmp+_f`T3(4W>~L^TVKhr9u~K)%&^`TvsP!=oX=f) zUF6|Ud|Qv7(OC+9JYufh)x+k9+Ar>5Ju<$$wukl3I1}8%dTLDA*WG$;eE(c`>%npG zs_xdCV?ev^*0bZ?LmAe~qpGBb^>_HVai;ZRIMP1TdNjnOW?Jutiw0&|Plw;eW?HX@ z3-8Xf9uSir%M|9&o?70+=1kVAR{(PjmTA9qq~0Gd>wd@FOv}Lkut%n4?ALbBv^?+Z|6o&~LDWm}GY>&4lYIX`%9wq?=Zvm@Iw z>aS2=M6&B&{yp0=?FY5Uv8?-P?Q(=U`B(1DwmI0?O<6WK`{d{xIr>4YJoIp$IdEf+ zWgXAEIma@PA03-x*~sT!onx8F_YcUiEalbRbL6qhV`cBUJo9LW9J>c`?3^6C_wh_X zw%sea>-=oX(7vEqwqf?60}Xe@jH49 zxyRux#qMFX{wBvV&-*@-V_E2TT%2PW>6bOj5wg=~>u*Y?`qR&6Th{u4TeB^LePQ2h z%VxhdK`gI((M4j}+Pg-JWp3}dODv1~iYLS}y8FK@mfijB+uHUry%W}naF1{PaIt$j zPvqy=y`IK<#j;!5?H9{*z4s@vtk)6WstJHo^=jT`Cr2j1O5Iv&b5`!p{3t{-Zf+}AIBb1Y-|!PYsJy`1QuW0}kwv`rTD zTy2x%I!xQ-yUKd8d*V+_70Y(MI!!F|dBlkv%Yu&jIL9)gyFZp=+0lji&XOs8Wp<8b zO^=Pru?*_#_4gu|czLB*hVUon=UTS#z2Ui*IlMVJ*RqJ8&&{=r;*po+T6XdL0lAic z*exs9?h&u>&$WBUIEIW$e3tA=d?%Tfh(*>V&LPvwz{I(cjfrz6GZWWBjwtRSIjgwm zWS`>N$wb9HAuAR4iVRiUL$XzIZ^>N6JtvD5zXchs_>IVJ#cxeEEPhjREb&{DZ;5Av zELl7=znu<~(1`^G&zPyGW6$E*Ci5207ekz@eGq~i)Wk6TRii< zRR=fkmjZ)#fs9__ymWJ03vB`XqrG8vNStI3u`A5P{Z`gXD?(dUyv5dSvjICslV(cTU6JsJ7o)|01_QV)U z<|oEhvOqEBk`aornCwuD(PWBZOebd&V?CLWm;;a%iMat8l9)4)Es41VnUk1fkVT2P z2N{(ZYgogEF^IKon8T1chPe${WSH}iQHHq?*=3j`k!gmx6Io}NQ;~s&xfZ!_nB$R~ zhdCixc9@%yafdk@*>{-Bk%@;n9$9&q`;noCIU(74m@AUGhdCr!e3*-p^@lkpxn!7& zl2?YgE7^dU(~=p8IWSp*n0u39h&eF%W0)J0ONO~RS&NuUlSzm^IeFN# zb!9G)yh%^rO}$i%~1gRDHPLCDa<+JtO9tXat1 z!&-(cKFnQN6N@=5Yh|$}B3lV-B{G+=h9ZjzYb!FEu;wDW32QMjov=nD>j`T&@~^OF zBp(cGOftK$)+5UcYd|u-ur?(73u{I)!LXJjD-3H)GQ_aYI2sa)+T=mYkxB3ur?=q4QqBX*|3%;s|{;> zGTgBCC)*7<0W#l^DH4l=}$10h=s zxe+qQuoh;GJ=Vyqy+@9P3>oBJ$d*A)hRhk{YRIBN4u^~y`9Thf z93?7o+$V5WUimW8$vdB(b)d4-%LSy;$nl8=PkCRs+vd6IF2TqxN`$dQtXgxo1v zNyw>^p@dv3*-FT*QL}@b8?`*XZBi{OW~gPb`TGCi;BY8f@Jjp=H68qII$YB?Lo)stz196nh$%~QHs1`hTb$ltiQOIORy zz+M1(8rYj4kL9xgU4$&185eaCGIsvFw2P3v(_v&6A(IDt6J+&Z&w>me>}8PcgFOyv zCq-*R$Y%Lp z@Tm>#bAOU$0t{DA6|w@(^iQ%3fte{umMst(l4O|!HO-SOivW94WE5bpirfb5k&$bG zJvFi>He8ut85ColPq1u?iF*?)vm!Yl(XuRjFH5wH3+$bjYo*1F+Xg?!+apbP_T{ zPOa!9WQk;L=p0^s zN!xzdgz7x@#xLXLVDS;Ne5T0Nr()!>&Uwc3Nv>RSDoUEqK4v~2&{NV6M92dL`9>mp z%E=9(^5NhD^JuSJdF~Bm=e<*CeAeo`dUK%s>vWOHnVBWyTeX#;T}n*C=I-**8udMu zQqyI6y8OJ(SFVaIGuhuJ%eC=7lCn$NKPAed_N`>ofO6AsO}tz^uch4iSh>M9ZtI*P zUv52MT5RnsOSL~bKktBfv#N{S+%j2y?tRes9!ZrY?{<-k4jnY_P0WzPdlF^g+CwIP zMy9;{cxSm{!(p@gbhf;bA14nL9x>s&MD9P?QO;!KnTINKrRm-d^2m~7=CUC@<=$7q z<)T&|=kL`wg-FvG1lNC1zJI_0~}q@Qe$J&F3rC zqw0|$N!(m$#%*gQo|p8Qyr#g6e!7+XvNb~bRp*<~_C7K?FG~8&J7zu}>MK_i#7N7u zJQLSLeJ$6=%afJ5ceBY~4)#ir@b3?s@4i&#@Z=;3{qc~g?WfGl^sch?fCw6JaJt9gf$W)-D?cQ998O5d1G(ZG z>v8xY{*UL%(n$Tgaz);ICRaWW^*FqdD__W!wZR?(4#_9lo~>=vy~L#D%7d499Hz%P zO*Nl2+T*Z3cJCHhc&EoHXhYjNYph)vY9)}sSZj`Qj-}E>vktchJ{JGBK zFh<5|USq0JErzm3HfTQRsn0wPljL|ik@zq5+>{OC(RPBi!3;U7?Idl3C2~aDU9=50 z2-~RhDb~Mt#^04C!ZzxH_*pPR_?@UzVl31z@fyJl;WdI8!fOOGgx3gW2(J;$5MCqd zns|+lo$;qL-w2!AiIMEE;`F~Z*$>=FL%sOK5^ zR;~p2dmLs6+o(OeG%;769^i49LdiXICA5#nVGXSwk}LZ%Jr0BDyRn+nO!YWyq7SCz z%0merhgtNRK0jS!Jr2w0kB4$)YLv%-Lo!64r8)X6p^k2D+gwQzP`xQeEoQj z!_KN}6a>}pY* zBay#)9G2IHU7DlxcpT2pms@jWO_|5x^UTur_u2+Cq_?(9wGE!nx!P`4?s2$7BRA&A z)Jl)T*Q(r{BLgcu4tHzDCpi*#+~aVB!t|IY^%(GlJR5T4Ep4Oj@qKN7s%_LmHhD^) z+owDZgKOChBB?7p4h!o`U2=}v;Bi=3iZ+zHwtE~FR&_;=T(HmMu&{pkDMvOQ^EfQ5 zJ==1myPhXlSof{Zk^WU4hlS<;L5}RK_BfoY8hxiyAJ+S$+@U6iMItA99G=p{dT;0J zy#>?hyQ3mUv<=qN;R7OVCwUw$)0sUYt@Pal8*0&4y3a9P-%aH>UAaMI!VHg7A9#6u zu8bJuahM_Z-;gU`>hF$P);5Dgety^Eu={3Tr#b64JPyKO#C;LmeJ3ZC;g z48WhB6&bX^`pC>Z& zdym7Ye1A`ltj_m1?8>IEsR2gF8|dxN0MR+90un3n*WXMQQ)vK zudT_JM*RyMX6DU%vSq-C0*9w}W@EOzIad4RHOkP__F-*<8PZJK0pkiBZr)QH^muK9 z@3&xOwlu!Iz~NZF@UHHS-BRH2Ef=lJmN_>SIJ~|fJ*Jx;1CHNYZ)sjt+o+??()MC) zqrN&bHAnIi3mn$v^7A!kty)E}F3)IQ@9^aX4s$a53(cL4E^wHW3GZafxLXSx=H&P# z*>YrZfy0~}zc5=0|5e~HCvVXl=(SVzdb4%x(>YVtlmdsTn0<-n(4z~Sy77ctb7WiF z0;g{L-pTs+)&&mFaP6JCXQ}rPOvTlDKWA$jti^v#$dSEm3LGxtpm8};5m;cr9(i}T z-t*7`r{4H zQ}?qH&HoP4b5_=F=$UL;eo=wL`~6+_2HH!3!{(h4nj?!d3LFkeRh-_dlmde~{|}dD z%dL|N4C?$-|CKFQ%q}osL9f<)_tP&F7%-x5Xrp=3cM1&H(Jvgyk|UoL7%-(@T$3f+ z_ZJwjrr*=K;OEB+3>egY!?L7b(?SFG$ibv6`QE?KKz9(@GD`}h3Jr7z<1fsTjOaoG zW{7E#C3Cb5K5ZLq@6y#yx0fi1zI;2^aJRei&u$?b1&XoI73mvxeReLgJ zU{0aKcK+pa&6D;iblA>4KFO4iFV?>++j;S)nG&vTFr`m?ohiqA6*_F^R=;FQ|4cm} zPLXUXnXg^mv8)xKGJJ%t83l$$ThlHTX(c`7$}g5IAny+7ayj~uD@r*WYHXZYL^ zS#nF0LIeKrtRY!)=$t|WE^*+cSLJtj6dHIsR9@ag9xv8sK<9V;B74ZMe-#?A zN9NUZmji8z40KE--*lJeF+~PCCLe9zu5B* zPjr_ly^9Q(A&=bAU8W8$GVoCNY*cp{IK0TfLt)Vs-R0wJiwryzMhxmMuZ=D;@K6ZT zzt`yB;i0he+U~MmkB5gs^yKd1e_4@%hr)A@>G||2a=86@i@VE-EIl{n`CqMnzefKK zU0c`-S{sy8WWeWtZCQ7j(Y?rk+kgFA-R0i&A_Ja(BR&7i^qj%@AHA}>oUeZe|Np7w znmf)Ya`aGBuJ0k8^7MC6oz%C9nexTMg$CNa-!*@F?TR7;?cRh98M1w8k%1S?Ctqbq z#iAkukC?dq84~++k%4#2m!+CBeYD8HQ|8UTGUSGtMUJn{KELjgdv}q;A(_~ryZm@Z zk%12J3e71`TUBJBL)28m$k%Z*E^18O+xAJbwZqjy4v4JnlrZV-9o>*+4yS(YQbXk0Bu>nh@Wz%l* z(>VPe^?BJ+nl9h#G4Ox+x+GmU28#`Jqq~dKWtFy}CmlU4T?W6V->F_jyKYRE*td%f zyo&z3CS7@~#RgtQ5m%?n4Qq-GyoxRvlP<5W*6;bGjSQTaE~DNkHt;I?Zg#qSvZUC+ zt0;GAx}5h^v4K}n-qv(^WM;7eGvv9M>9YCdzk6OoC)@PablLb;v4IcH(|4uINg-R~s^o`AlurATH$ zi2*a@oHi-)dhFl5eWAPmFh5xevq}y8=02=VmQT}44SeWYHBFJPl1dHy>HPFO2kUvl zw=P@1=L!8D_}TSptKS(@>gcsEJeVT;^gckxy)Z9T@`jffum%3>{>$pAN`Gf?65M{` z4e9F*ZUa5U!EN|={?70Z{ZG8n!IAiPKF;7;yzxL6`E9WB$(48UPkGRT8S>23B$@O1 z-#twKTi)N`Kir$%Mc$iK<}gD}Uffm2)|Q%v@R@b{wBjDReUlr~zZkzAy^`zmvHedy zpzHIib^F`mUHGTGwj0{x7|f8M2Rci9`{NEX7&FJ>~Ye?TctX1jpSD*hH*24dZcVT@#Yi?gQto{Ef zkI07h=EGXJ@AHxJ#Y5H38hPp14st{1YA0_)@2&rq50u+S2{|aYuUSL-i=BkOQ&ZOa_s-kPY1dB|HO-`KHnU$MCiTsPkMeewAT`tA=wi`WzN`ICx;(! zAXH`~H;k``+ZO|SWNx3DhV+ZU-WhleO=g5EJxl^A%h}%!(pY%3rXiph1L!P}s zy}0(*I(vd!UJQ}cEwu*w)Gh7~kqtl88tgC6&{~vp_SG8fJIhreviWeW!G3h?#UXO9 zdf8x~`i%PBl$Pq>b^m%yvU+z_)Eew-n}iVAS5@n9NQP?r{A%@H(LMLlCqtyg7qtd^ z?ya_lNb5DV27B(g>Z|hG;#z|}_lrYArJwr#V9))}zWO{*tu@$lA9Zu6M60J5_S|R9 z4wVHXYYq0?-+e)Sh%T=+*mEDTLVcz#tu@%|k6INfWBcj3X$?Svwy)DRY6H4zdz7|O zOOWhsqsD-3)Dpz%->=tWP-DP0Y7+Qa)GF{h!4hFC)K2gk!3^Ow!Y75-2>%pbBYahO zjqqFHHNuC5*9dh(BR#fI4@r+L)Jf7~3-y!q*g{<;J+@GXNna<_dD71ab)NKTLY*i5n^5OT zUnkUg((eg%p7eo2ohSXFP#?%X1a*V#TTshNuS3+b(i0H1tn>;*Eh{|)QOiniLDaI+ za}c$x^ddwpD?JKPmrK7+)aBBz6Lq=t>qK2{s}6O3ov6!QFr?0}6Lq=t>qK2H{W?*X zOTSLk<-T1}=hulkVa^#)Crl4M)Ctp@4|T=#>_dGr=PIZ}rava?km;L=x@CF=qHdXU z9@J5DE`<7O&cRUs%sCk9qUmLcdTDxDqK=wgmZ-0$mnG`1>1By}Y9>fwar!W#-k5U| z)FIosiq^){Qy8`J^xj2nJUw|)8$WoTe*dR62DS0EUJqZ?#?#vuwej@)MQwceOLbnr zsPngL0j=|=FE;A@>5GjzfBIsh&Y!;6sPm^UHtPK8i;X&e`eLKbpT5}89dHc--2uIB zp*!H31v&-#P($xPe`@F&=tB)%1O2I?gPvfO$R*%*L2WX&@&qP z3wlOFmqE{H=r!mW4IKwPqoMDhXEbyl^o)j1gzHo2Q0UJK9SVJip+lh`F?1;ODTWS( z{>9Lt(AO9`6#5-QzrZyPbPZhlKx?yjP^7GXquM}gLyvoCZ4weArN@WW23nh!f+FQ1 zQ*EHN`KVc>{QgC?f!5}Z+6d|ReYL|IS$`}-UiqooKx;Ej>!q3>s5a0IF}DESP|e&( znKQrIKsPk}y+{eYx7t8A6nHpN(r>CZ&<&mORWG{Bs||ERpY>K=US_p{ZYc6!9i&lo zwSjJE`)eI!O{;1H-Oyb1u6y@Xm4S{a=6CgsEUYrnG0{^VIwpF}L-(}q5A|p)s4~z` zF_!|JRBg*BNk3F&pp)8lj(TC{RT=22P6S5D=KWO$x~i|+Mad{_L+8a@4fJ2k5ka5D z91(O|gKv(Ko*z{i=(+B`GfKXHugXB@wP9M66uw(!p#Q4TzrUb=hc2w=Em5-j!zu&4 zSoxJvGX0Y(10C6YnR-6oR2k^bk~&4nbGxbxbZzVP?_Krp(6!YhM9IjVRR+4Yi5=9d z@24sQUE7-ADDm4@WuR;GQ;v6zomi`^OwwV!8Qmn^A55=4bbW+TvK)ctz zU9@z$rOH6Nx4cEPY?)AHpxqmCI!a#rSCxTwuc$amZoIF`K)W|!Z_gIUHPNphJwPj+X56stk09UqpA5W)+nNI>Z}?b(Ej?RT}6J-+!p1 z_;8tE^R}PIqc_-lCZSW zKzI4}j*e2bywX5-dG6MZ^1)mBJwr3)ioG3W^DC7GI?YS>sehifp&MoH7kX0WoT2w* z&KWw;wztN}U!yAx^r4lv#YiV@LpQp8T#OWt(eF_`=@-Ldq|42f20GKey<+6s$(08B z)7{ZAGWY&U16^vDCNa`J$e^eM~fwMAW<*vq+23p`vonmEN^GX9PaC-Y#$?~l<&;mbpUaTx^ zSLyIZR#nHyIgynHTHvRS#7Jm-rGc)Qdmqp>511UQ8m9^aUGo`TGc@|O!a&!&@x53% zcSnW826<|KtZdm(;V?s{Hj9&YUav6FHTTGflOa!580eap-4Z7~?x`@)HQ%^6PJSC( zVW6|_@lBj`7+hhXv%YLcoV-4$!a!#|_S-n=q;2T3r+ueuiGdXc`tEs^y7tJfFwk-D zRh>d+?+ODQcg+4cncA|bG^b8n(+k|D7b2D*6e$3b_WUKuZMZa;3IyTA5Oye!{!+(37K?f3DrW8ZND-TgUR z<7L~S<7S8I?i*|Eea^AtW|!*je|#@q8WkKj(B1ERH(m;~4ZSw^bfDwrUJuv;AMETT zy>B{hRy`*Yx~RB5LeQg~6<~1OfRhllzO$tNRc^pZ zNG|Fu7Zs`QLu)Wk2PH_O-Q@<{hLDg1nX#+fVTNRf>Y8Dv`sC{I*M=p?1KI{JqGg{1 zX}hJ|fD5s+TY}90qTGNB@m!|_Id4a~0Y@USZ-OlRwA_FrG4P@U@z*xE7TlW#?}B^c z;8Ac-{A%S?bnl(0wFl(}{EBzFBuek$>SL>1i`uq{vh9X)1K!2@+5}0uquhXl@!j_c z5~ZG};A5n`o*>EUoeFM7qiG4U|1I^j)q6Wb*GtVWEjQqJT(&Gx{)#F$;CReikSI4K zlpAn7zP~?FhNP7na6EpWkSI52l^bw8_Kr!Ei`73D9FKOx6J^;&>VH}(((Q^w>2rzt z0xSQ4d&J;EaPJs#SnGUxjd_h3bck zdpPddB)RmXGUpzKzMCXpy=5ONv-#=Z*7v?`hpeUi-bJptyUe+V ztp|6J_s5kvza48r@SA=yql-+}`VjoqtRca(aqg@xa@U|T=b2$G3Z9Mo7I#sOSef(8 z^qQ~hzbwgX?{$@f zpO-rCLh^#H67XZG^DcaLb65GuQ|i16zh!lm!KX@{ccJ{kt}@)G%y}1%{L)4GbyT10 z2ef{_x~p9JW~uW&vd#zZ>6kvrGILI;^ZvfoHCYZnQR=+c=Y}WCwuPn6`+l`gvV8tx zsnZWkX_73Dy;|z@54FE_m9JkfHF!2ybAo4vwJ7MvSRaM{hjmTpmsszF{)%-_=*L(e zh5n6oQ|R|tPlf*Q!0u$p>r-mbC$rWIeKKpk&?mFj3w<(cz0fDK)(d?yYrW7Xv(^iJ zGHboiC$rWIV*zW-Fh-2onIf~b-V9?0Ytk^*u!ap|5Nq2o*06>RV-RcGFlMn94r3W> z^+ zGaq=wq{(l!#m+q8z}snZ#Tl(>)cM1(#c2|IUWqfW_*vIcZCjQ&^NqL%(qv2P5`(dZ zHEbAzSlfnq5$i26pJAOO<~gjN#QcYKm6#W?-V*aA)?s2E#rjOlulA2fml~}F#T<{d zqnP8db`*0w){bJ1$J$ZM@mM>GIUZ|AF~?)=DCT&q9mO1vwWF9@vSt-?PS&zwF3K8L z%w1U%i#aW8WifYUO)TcLtd+$an6Z}3AT%9$*n5(k}7;|;j0AsGs8eptDSkH|00_%{$0AYPH))%Z>#=3*`%vg`G&Kc_z z)<0wY!n$b8U0D;0IW22tvCd-sHr7Y1yT-bS_1IWXu}&N7EY@#h{l&U&tjk#MjrAJq zz_DgzEjreWtVPF~k+tYpGqM&PYev?hW6j7~bgUU!i;guTYtgZ0WGy<@s;q&>8kV*3 zSlhB@9&2IN*kg^%+Iy^pS!0hiGHdU#re>`^*4nJ$#~Pfq{aE``Q-HNUH3eAvZ){Vi zDZtvFngXo-sVTtPpPB-!{i!Ly+Mk*Nto^AeKpuno2;?8AYXAd;dI#hysDnTrgZc>M zH>jIH-h+Aylz*?9!_E;mc_8xf~>Oqiip^gK280tHapP}vpc^m3Mkk6q`1bH6n zN09%at^_$KYFm(lqP7J&C~8}fgQB(tIVfsdkb|PO1vw~cTabgIwgovTYFm)|qNWBp zF=}m)E29PnxixBbkaMG!2e~zBc93(kS{}{OQTv139W_D7=}{|$T%y$|X)ci(CFByR zQ9>?}8YScssZl~Mks2lB5~)!_E|D4~lzJ=V zOR2*`9+mnm(vsnJ7@ zo!UL*-l^$BuAUk|`hSfh`kAF9NK&> zLj5N8U#RQEzRc}jy(ji-r~^f={zqy6HHS}aAoi80SH*r1b*9)SqW%>7N7SWaU+M6H zI=w3Po2X;OJ{0w>*q@^A6?^V}) zjJ-~3sIk}ig;zt3y-sSVvDZlrHTF8Gp~hZkimoM~p~hY(HPqPaq=p)Mozzfc-j-3h|X2>l~b0oaFz+r|o-K#m@l0t_W^4O5> z()mKwNzGK9@m%G43@mY&Art1N$d$`W9cIYYw{($jnwLAwkPyv9G@X3hVTNo>iI?}k z*BqBJLrlLI*%DgiFhibPq$~-|;e#3SYgVMpyspM!hMdj~mu0$H|eYZ$-` zG0Q`w`GgY=Gh{})5c%}&69%k_bNoYO%jy#jYof~wA+lo135PY&<<(G$I$i6qCPv4G z%kn|B4r^k1c%-C`uW?ut$M1=fp`)uE*2IW73cS;@B#9dR;xA)B>%>qQvQ?2VUh$j&y`Vk7C5YuQHeRSN;RHfqy!(+{PmzBhiwuf-R0%` ziXG<3smszOKy^J}q&(O)MP5lRa~LVVolKHZ%gUX<-|>lhhqS41jz95AoGhPS>3q+R z?{$>Wud1By|EWck3^`ft#9gRdj#j!y31-XB1z|F3XRULd7d{p$JM?$N`R`d9B8$E~ z;au-~w};5DWhWd)3jcn(G)#Crm?ZojuuAy-V3;s2*d{z5Fi&`%V4?8*!ARkC;qSa& z9MAiJ@8SKy_w&9XF7GGKhxZxh$@>pR3V#n$^UdDp!lZHA4)Sr$F_SS}YXnj| z$nTzG=AxltGHGxJoueN!XX3&{#&wWEJCB(kqC;d%?p!; zry@jd)P1@epUX2xd_#4NQbx=(d8RlyRJpYsrJc6-4GERL@g1f6!aVcolu&uQLr3ZS ze4hE}$xumX*HI3^dEsvSpYa-;ekZ8I3!ei#ac@eTPI$Ab2KW47@I6}TpiI&Mtj+xtwB4qZ((Xv#1 zY+vz>l)=|U%VXtv=4f)HJbYiYOh1xmt{508H!g{m&-L27T^A|mZ;6&4x8@nY+ahI# zCtCd9&oj@DkCe|Z>?kMn+CREU{jO8g4|hSHd0|APyf?g~Or4Qumh_HP@1c%za+3bN zU4*pxBSs3g9W^fwkC6CJVx`;oqvoER2x+_~R{orF)O65m*|8*6I^28Iq_vHZmXF5D zt#gi=l;#m~&6HSKF#o8zuTg|tdv&bzUv$)5dL~>p_llK4%a5A38b?Uic-=31_o$hD zfj;kk%Jt0ke$-^GjFjKBer|ih zQS;>XNa;T$PHydV)GRBBlm~{!$>I2;=D`a)DCa*;QaT?slF&isTpB0Cl8&0{OFPI? ziIeoyqvmUUeiORJDa-7r`Sacm@^o07Jl^Z5@yzcamtPPki~Aon#p|Qw=|^MatrJI0 z;!jcHtNWo_&dD?7zemYKx?kDaFVAE~Ma%mcG14zM&z!hCTDr!>NJvzkDViBAcLl}B z)p2>|^L5d>-xVVVJLQ?gLjB#^#_0Y^p4q0);FTe|XBwMlIuFo2;rJN&Br?y0Oz$ZB zb+7aG_Ic)pr5$DUQ1x1CrQfN0ysan4h+h-^&VwDL-;*)2vihj$QQc7{uZ@w4yrbr$ zzf_O1H%2bst>>@xmfxL;k?gH?ZNE)%GXIYw<~*bOsDt7qbmI||wM6%6`^U?xn~s>3 z_s7W7z2l|U95LP1-{8^=-ADWEh}m>ejNBU+FH5%{F*QkgOhCLW+jYb|qUY|{BwoJ# z<%s#SRg64Q5+{f9kC=7m#mJkx<77d_5%Y3noQ)OwcC0+1b&BiO>u1ycPy4psarPYk zxIWIF!}u9-_8f{9#o2RMvqq2co6@Eeim&eLwFz61_XYz9ToUO|b9Cd(S4=cjT9Qw7${%j=ZVxE50M=Kcf3r z-acV&RFZu+cW+L#?`)@K>V4|%D`u}xvVFxJ+x2*FUoqw9B->ZS9ZIr&#WhEgY+v!m zfh5~kME;m$`-%&{OtO7cvnB9NtLwWid^pkeY30)sZC}^&&P3Y>J~K7Z_Kg!COtgLG z&}R~DU%GX5qU~eP{XWt5y_qKxZJ#_;_wLwNM-NG|efUjtl5F4p=|@Sn&)-v=WXFQO zAzkbkVfuHmV@KIw&4+l$l*YqS>=?JIm*#4`W0}OK*s<&u)zfnm1#7O%JEk`c)f|_1 zOmEpf)sE?}`lQ-1{hY??!{r^*mzJg2F}=x8DRxZ%aie;rdFK)RdeE`JS4nNO^2bzVrQeH;I(llkyGXKBJ7S$@k?O zoKJ`EBBb=8d^4i3tNf~C((Ci{&1Ip=wtYWB#_0U*_|RlKulxOtRNEdnK1~`&>)5$F z-)y-#O{Qe)`1)18`FvEG{5~{7=6#%RUe(-Y>8%m+@mig;Wv0o>`y-@iWxn}XbCt{I zN5~bg<(tfA%1M4HLK2tcn{$d%W%`N;dFzFIbK3?UqoZq3Yz3Q8AnRTk}9Og6$m+4n}oO3u`942R!0f=+B;Kwle?iP=84gYXRTq|>7w=N<;l3KP#f<(}!i-7`5%UU}Bz-1D&`!z6gA$N4Sp%MO#~t3A$d)Fe1e z8g2GCzun2&Pf@d=e5QwyB9@l_$RRk>a`pY{7gBxgW@!87^XY4xR6CKcY1{#n6t z-noSa??UX5VEOh`fx)|wdz=2fqQKx?$e$G~jq(c&-h~@q43-xA3k=?cR%?T0+V=$p z??TGgI`{oty)g7$NIeiNFK;d|co!Zh50<0rluM@X{+6qPWcBTZ2JhhNr9qO=ztG^_ z>|Pcm6|sc|eL}z9K{EDVg$8}XE6G9f)4hcTeM0Z(Ao*ctp+TSUR8Wv~e5lZ%PuS@n zBp*FeXwWAlwF#0tA1yTK6W(hZBt!M@=o1En1j(4Wg$8}m_Lv}fNBK+Wqe{*Rmf@j= z27T9{w!zX=Ialb@c83ScWqySQeO+2~u#EI6H0T3|b_kZPzJ&&TV|I|P2ig=G^qDai z21{^Ip+R4I=Wjt$(xK3xkA3q{kTh1l7W&>vTb0k1rN?WZ{N$@a^2Mcv27Pte{Xz2K zNaa3hA3kkFkW9O+(4cQmP6?7{_1e+rhg}#XFFsLdFcw@?&|U(T6dH^XuYT5E7Ov92 z>)4Ukr=2VxQDiWdeXC5UtJV}5j9Inw17-eOMFwM5r&j~z)>n%R#;l?b0;R(XMFwNm zi#r14^t>X2F>CR$K+>326KtAAGDJr9g7U+7@j@tWP4zd!Q5kVMLW5>MUlarq;IqK(zkJu!Cd8wcI{=- z@A~}c9A-vzdr7V-G??3jcWN)ID+>+gJP*XTms)LOF0`yedpWPR&|r?Vp>2EFaZ34Y zI(G_b+Fl}>78%T`E-h&%U$!hVm}?#TPCf5~iVWsp@4lnw7FT32H=Fx-J9)8tk-?m8 z*kEos?sQvu zZj|zubZ)u2S%5q?qS!cd%YXnWxk8yvI=37b7a&EK78}eh^Rolw8K)xeb z1M(fg8j$Y@)_{CRumtBV>)tH9Mh4r;+T${6~}bstT?74XT>ocIV+Co$XRhrN3M)>3FOc?$0)ig zOgQ&=S2a4ElSHY;g>#k5)`kh^Fc0dyjB}eyR4c z%Y%e-%fih;!nx&bdxL~?%cUoR?A-F5fM7efL@dsw!zTp^=d@^Zu8VWv92@7rIX2FL zb8MUg=h!$0&arV0oMYo0ILF30aE^^@Xa4rQSCo^id*|Jnlo_<==zih8i;GMT&8;&3 zkM_y_aaxmHY+mW9dxGBM(dO~>eb4QFx|Tm#w?BgR|J(QAJI7zuS>|ZHH`=$qsrk=` zOHF;>gSb2%Z606W_tbY?^?lE%H~g|2=|9iQ_gP0L`(*nJ-=2x~TL+tGhxP53h4zd6 zPG^mJ<0+>-KlV`8hq;@aHvWzO#xeN+I1X)m4xdLG--qu-8*vcN`}d9fyB@!Z$LsfO z;`iwHZ{qjszc(?i{{KxpAN|~Bo~M4_W}d&s+3dP5{Cy+hdXL|Pw)cCSw)gv;wl}WR z_MVT^_MYcv*ZDi`Nv)eMM?CM}alKC4dmo&(_x|wvao?Oat`G6N=Y#v`v~fQW4}Zsf z;`v`ac*&-e<>}7fz3nUv+2^plC4K6!R8b7IFp#=n;6W?mWCmvMfL$jOue3LFPHkk|?Mw%=F-I(Y z@`z66zIL(vMF;+5I<(xud5Znf-Mm;NR#%IKea+Xu?&kCv`v;o&9b)MMOHQ2N#0gHE z;KT_|oZ!R>PMqMx2~M2g#0gHE;KT_|oZ!R>PMqMx2~M2g#0gHE;KT_|+|lQLFdyf5 zi{mS>%X+$z$P}qSJ&j3^9?yF;_?I{t<-?+B9 zJ4JEE>*H#hqK_A4-0{`g=9f>OX8gd{bxiK|g&1!tUEjREB`@RgSwA&}n&e?Tw|)at zy!K;^-+is2(am!+zBk7gCPUU3u72)IQ~!@#oPK?7Ba^LQEd9za-cSI@(`{>S_T3+A&xr$F&DqR_IbC4Mi4&YS!HE-`IKhdV z@DEO$;KT_|oZ!R>PMqMx2~M2g#0gHE;KT_|oZ!R>PMqMx2~M2g#I0CT(doWd0oiZgp_>ghdCK2;<^$!@=E*~)mYQM+0 z+-DI};>ULxr`Z=VgSWoJxI{l~T09@?pDV{cZ@SKSmD2}ZDr4SRT$OR=W-pra*Q+q@ z)2W*ERE3#oC{#$7b=~~}1PV-V0GxXxujJKS4!1Qkw!=>+f&~*PUhL5k$ zZj#o<@XK9un5<1={kd`OM~w32981h;s`mSi%X#d2F4MU{tgcCC^P1D2#@cqF{F5gA z6S4N^h!iu$x3}f|-5MFQCerbCEIDz46DK%vf)gh=ahdeQ!VeecFs({+yF?K#ht5}^B+is4#AXX}*(VtCHN`8xA^G2AitV!b^Y!=LJ9 zx^E;_PS3L|be@ed-09=hx=^23U1N`}(|aC>wWs^Wtr~X5+W-E^UHYD*-MQZ1-#Dp1 z_@)ozyF1^|Z>|0Lb}Tt@f)gh=ae@;kIB|j#Cpd9}6DK%vf)gh=ae@;kIB|j#Cpd9} z6DK%vf)gh=ae@;kIB}o5d)3|bMlvS?yNe%wp?1_5#OXs8v{eg!iS?Pcvb9$?HpKc& zx-Om7kY{^xo~F%usH4yKV4U&upVfEuWBfl>Y`EGvsT-%CyEIOvejs-Lgu>NZVau10-r+}^ul+_qa=+|{ZP>l^lFVK;q8EG|nM6>#N$ zkHu^H6M0>7{9dIoCwtLH-Ttw$_;yO0-R-Lo!!OLf$32!IhG*W`Y+HUC!`tKL*e6HF z@Z^uC*dH#(@Tsnewsg-}nV$_xukoB%b+tn`$MBbpI@-9!v35RC zzn#6_syDZ%3$(S*j*j*D6`!@V2kwboWA!<&+F@gcavr>2thjdqmYg`ji4&YS!HE-` zIKhb%oH)UW6P!4~i4&YS!HE-`IKhb%oH)UW6P!4~i4&YS!HE-`I2>c07-Iu=?{+`n zUSA#Kx$EMs?%~a`czyEQT35DN>^U+w<0_XXUud-pFRk0H;>^Fle5Ck z`Z0WR%Kgy5#PVnO=^hwdC01t6Ut;gl10GBZ1^dU|Q4i-&2Va$rebb%&=5EN6Db^?3Ex!kv z)Qa`Jt1bg<%N`q}@O>V{yM4ft6DK%vf)gh=ae@;kIB|j#Cpd9}6DK%vf)gh=ae@;k zIKlh-7AH<{;shs7aN-0fPH^G`Cl0^+KzsuR?DnsJ9|p{+$+5^kwmQ5qDfTUyra@Im zU;9-~A2zWv6dG5R@%CsXh&xh+@zs?TpsW9e&3vL9-1sJzJ}~Yj7?c#l4Zke|R|{0* z{9jayhYiEuWE{<>q5Je$UDHb{*z|bpJNl`%5tx)G_I+Klas(EikG1Ve?FhWM{C)oI zw)qjL+pAWroUarl)~U_7O(6r%fASIIr*4#n(?w$6_`_Z(1FOIIlGF2dEC+9^Sf9lC z0T6Qq0ZUGt;KT_|oZ!R>PMqMx2~M2g#0gHE;KT_|oZ!R>PMqMx2~M2g#6|zXi4&YS z!HE-`IKhd-c_a{XN&&mdZQH=y_X;qF{gbzZ?T_SVd_CbinDg~xj5qiG8g{&$n{keo zU%{;8F?>&_FQ7~67~VFaA$gKhf-fx8&zh!E}%DF`tXZ@%))aq4?ajjjoVN;C~jFTnQfsARMVZ3ByU06D* z6ypV#>%lM2E5^C9HH4#kV{?Z07yT06>`{i(Hx2p@F00CnalR46++)C!6DK%vf)gh= zae@;kIB|j#Cpd9}6DK%vf)gh=ae@;kIB|j#Cpd9}6DK%vf)gh=ae@t1oKBmA~CHXmN0P6z09E;diz`_1++BTp>7VXby>;*S{a z+PW-vA@IuvXJU4!R?T_$Mfmr#~bG3%*PoCoRgFm%`3e(RsuJmau_$k|E z#$8*tf-W!r!MNt)R*-Dj4aOsjwuZ*(lXHAa+SX8@O$x?SKK>Ch9ZJb~!|FDW{bEdO zco^H9wn%zTZ(6YvEXaE=PMqMx2~M2g#0gHE;KZTk1w!)**cF(b0B7HMj$?8C zL|-_TKc<}}<>?7mmp{wtk9X(}wI;;!>}%Z(9$6F9)LtL_6Ku>7)9F6m+!bzAslfTG zn6A*f)GLhBb?O3TUVWSKm%nv}4NaObzN>C$SU9{j<07AT2FTcs@v)@N`2G;n6URK= z1-e%38vE`1E-=18On)r*1=f|&lhfxs_Y*ubyEo&t8@oZzgno>FUDOM*9*Jq11<&?@ z^N$SU^wygPK)cT47^5}{LK_WOa^eIhPH^G`Cr)tU1Sd{#;shs7aN-0fPH^G`Cr)tU z1Sjsxe{kXiCr)tU1Sd{#;shs7aN>$zz<#oBwWaR@fnD+PgCPBgZk*n5Y=8Kv>DP=C z4)=mLm(*f>?46$Q^uX5`x2xX+er;Zsan~W;VcGVgj4S-!4GyM%m~lz$OZC>JVm$Sc zZg5|--=b9S`E1=_NrH|L?wO|>^ob@hPFJHF44r+B@v@!WpzxWjit@Djt~)$)t`Os@ zg?qq<3C}U!bGZkMP_Hn4VRuic)BSD6ZF=^Ggt~PZubt8#hK=}|aeVp&INbL~#+|<( z3Js18XY6^n9ZOD};KT_|oZ!R>PMqMx2~M2g#0gHE;KT_|oZ!R>PMqMx2~M2g#0gHE z;KT_|oZ!R>PMp7Y9PuwOY3P8y0!~K_9ne?67&UZ2Ujbv(&;fk~j8Q`e^c65h4IR)| zz!)`jKwkl4)X)Ka1&mQc2lN#%MhzX%SHKuGbU&{x11 zHFQ8<0b|tA0euCGQ9}px6);8(9ne?67&UZ2Ujbv(&;fk~j8Q`e^c67nW9;o%azeg> zzzO*Z0w?4v2%M0wAaFvyg1`y+3IZqOD+rvBuOM(jzJkCB`3eFj&{x11HFQ8<0b|tA0euCGQ9}px6);8(9ne?67&UZ2 zUjbv(&;fk~j8Q`e^c67n?`*eY$qD%i0w?4v2%M0wAaFvyg1`y+3IZqOD+rvBuOM(j zzJkCB`3eFj2YUqHz0>-GJ1NsUWqlOOXD`1QoI-swBF>2_5z5>Rmp#%B~7^8*`=qq518akk_ zfH7+5fW898sG$S;3K*k?4(Kajj2b$iuYfUX=zzWg#;BnK`U)8PZ@}BJ=V zPRLgfI3Zs_;DmeyffMo-1Ww3T5I7-ULEwaZ1vEdvoCr)BI-swB(@{eQ^c65h4IR)| zz!)`jKwkl4)X)Ka1&mQc2lN#%MhzX%SHKuGbU&{x11 zHFQ8<0b|tA0euCGQ9}px6);8(9ne?67&UZ2Ujbv(&;fk~j8Q`e^c65h4IR)|z!)`j zKwkl4)X)Ka1&sZi((PDsLcW5)3Hb^FC*&&#oRF^|a6-O&{x11HFQ8<0b@T$eLI$%kgp(cLcW5)3Hb^F zC*&&#oRF^|a6-O-GJJMzzO*Z0w?4v2%M0wAaFvyg1`y+3IZqOD+rvBuOM(jzJkCB z`3eFj2@*eFcnBL$~NF zV2m2NMPETIy;@3#z5>Rmp*!>yFh&jCp|5~3YUmDq1&mQccjzl%j2gN_Ujbv(&>i{; z7^8;n&{x11HFSr*0>-GJJMY~uOM(jzJkCB`3eFj z z0>-GJYxET`Mh#t~uYfUX=o)=VPRLgfI3Zs_;DmeyffMo-1Ww3T5I7-ULEwaZ1%VUt z6$DPmR}eTMUqRr6d=VPRLgfI3Zs_;Dmey2@Rmp==VPRLgfI3Zs_;Dmey zffMo-1Ww3T5I7-ULEwaZ1%VUt6_6K{IT4sNbc4PEPDc&hps#>2YUl=i1&mQcH|Q&1 zj2gN@Ujbv(&<*+u7^8-6&{x11HFSf%0>-GJ8}t=0Mh)GduYfUX=mvcSj8Q{3=qq51 z8oEJW0b|tA4f+aV>8sNi^c65h4c(xxfH7+527LvLQA0QAD`1Qox$uoRAmYk5UAaFvyg1`y+3IZqOD+rvBuOM(jzJkCB`3eFj2@reFcnBLpSIvV2m2NL0Rmp&RrS zFh&jCps#>2YUl=i1&mQcH|Q&1j2gN@Ujbv(&<*+u82fbxw`0i(`3eFj2@reFcnBLpSIvV2m2NL0R69nzzO*Z0w?4v2%M0wAaFvyg1`y+3IZqOD+rvBuOM(jzJkCB z`3eFj-GJ8}t=0Mh)Gd zuYfUX=mvcSj8Q{3=qq518oEJW0b|tA4f+ZgqlRwKSHKuGbc4PE#;Bni^c8SSQA0QA zD`1Qox=VPRLgfI3Zs_ z;DmeyffMo-1Ww3T5I7-ULEwaZ1%VUt6$DPmR}eTMUqRr6d=VPRLgfI3Zs_;DmeyffMo-&{|sNTwv1B4f+Z=9W``=z5>Rmp&RrSFh&jC zps#>2YUl=i1&mQcH|Q&1j2gN@Ujbv(&<*+u7^8-6&{x11HFSf%0>-GJ8}t=0Mh)Gd zuYfUX==iLR>4~VJ8}t>#emlR5L0Rmp&RrSFh&jC zps#>2YUl=i1&sZg>)Wy9gnR{o6Y>=VPRLgfI3Zs_;DmeyffMo-1Ww3T5I7-ULEwaZ z1%VUt6$DPmR}eTMUqRr6d=VPRLgfI3Zs_;Dmey z27LuVLl2lVbc4PEPDc&hps#>2YUl=i1&mQcH|Q&1j2gN@Ujbv(&<*+u7^8-6&{x11 zHFSf%0>-GJ8}t>hX8<*HgT8_&X_2U*8}t=0Mh)GduYfUX=mvcSmhzy6ZqQf27&UZ* zz5>Rmp&RrSFh&jCps#>2YUl=i1&mQcH|Q&1j2gN@Ujbv(&<*+u7<*1`$C4BB6$DPm zR}eTMUqRr6d=VPRLgfI3Zs_;DmeyffMo-1Ww3T z5I7-ULEwaZ1%VUt6$DPmR}eTMUqRr6dUOL}el7CrfA?Iwd)pwhz2D&e}iw#M;AWea$f$RiCNm6-?77b zZBCc(IU>In`L+1Ql-O0T_`La`1J4_{E}333saLS35Z3u}`SN{RAIjy+?>>=Vi~RcE&A;{jwT<5X=x{FQi;~^-_}0HL7IO|^ zjUlCLkzb4aTFm`Q?5^D~(XYSe`C-D5fW_Pw%^}m;G%jD{*CM|b8id3S+u%Z*v289~ ziuan&}Xo3K4r4Nxa8^i1b+{Ii>}e;>FVhi5vMFY?ov{4e*1!9GmyBwUVv_h9Vb zXKu&gorKF5`Dsix!rLD(-Lv#g#pU>SC&vDL>~>7|Y{*adGQFE|UH%)E#|?pL>3k9+jsQdK7Zz37URqvy}!+$8CT^vFZR8;pOalnAf406aO8}SZefs z&Vkd#+Oa!sos^%4VIKVa3}ZiM6?pqs>!uBz{H6vcPWgfgv!PsjzjJ-a~Sga+v)QP7Bi0n$asGL)-7^o~1Hjnp_>8>|fwAz_ z-*Fyt@1tNIyuTtg_Y(7FNX)(q;Vr-8eANHWeb{v*w?gmVT7hw}#s zhjR%Dhw};v)47H8--N^YhJ^8)L`}aZ?9YE>OlJjBeLkJf3HAB8KEmO=MZ)16M#5MR z*GCxJ!}SrSb0euf!r`1p!v6fn$3;5d7d}7VJH8yozI?{MUdFyXjIkcBkID?^R}%K; zKY~x^b3zGw9ys0e6Uryv7!!X~ALaKvGxq#5_HnuWzW%rVE77;Lxc9YKL!reQ3N6-9 zXt9Pui!~HltfA0i4TTnKC}_XRu!iD)+`1C+>>$r=SVIvwByP2Mrf9J)NsDz!TC7Xb zVqKCJ>yorsm!!qIBrVn@X|XOzi*-p_tV_~jU6K~-lC)Ttq{X@jomE!O&JvDQzEwSHQx_0wXlpB8KVv{>t>#acft z*7|9&)=!JIept?}wSHQx_0wXlpB8KVv{>t>#acft*7|9&)=!JIe!+W5_ceK^Z>=L1 z?|Z>l$$7*(uomlQwOBu^#rjz-*3W9OepZY1vs$d5)nfgu7VBrVSU;=9`dKa3&uX!L zR*UtsTCAVdV*RWZ>u0rCKdZ(1SuNJj1|KZ*Aikl<*B#dB1dl7{5#Lr?tV!2mO}Z9q z(zRHVuEm;kE!L!Ku_j%MHR)QcN!Macx)y8FwOEs`#hP?2)}(8(CS8j)=~}Ew*J4e& z7HiVASd$(+$;^ZJHYbmISaTHo#+*ldvum->gBJTdXtB?O7W+JCvCo4R`#fl|&x02G zJZQ1cgBJTdXtB?O7W+JCvCjkU<8o`C2QBt_&|;qlE%tfPVxI>s_Ic1^pNHTNXCB0y z5BcrG`l;ak<~(99NQ=EwwAedEi@j5{*gHjwy;HQ1Q zZJL;)rgacuU0YZa!CZ;CYc2Np(qfM@?(qfM< zE%x}*VvjE^_W06bk1s9u_|jsJFD>@?(qfMhGDG`b0xGkE%u_+VlPT9_M+5cFG?-;qSRt9N-g%H)M776E%u_+ zVlPT9_M+5cFG?-;qSRt9N-g%H)M776E%u_+VlPT9_M+5cFUqi8wWXX#c$u`=+h2>l{k7QJUyHr{wbl{k7QJUyHr{wbl{k7QJUuXWu-u_|zFZ1Bn z`SN^%@PmbQzOg*z|2{*6zMXMSCY-+$_|cT^c~gXi_mbvh?$~pAgm*XGcg&T)9~u9B z)>Tg9=VWfJZTI6jr+XhA6UVa$VAa~HmsIo*FpGyeNL?*GqT7GWNS`4Q_GwOHdx zb24}A8TVq1aG2j?uKc_oW1N%Gc)kN;Jj+1i`3{WnECY?_J21wx3^bnaz!=Xm(0INB zV?4`1z5`=C%K+#1V;Ije(0INBr{h@$8qarNjAt2WJl}yao@Jo%dJynsl0zF?ePQ=fOD{gJ-5N#yJ^-XQnX5 zIT?dzro{5xOk?oO6vj9wWAMxr#yBTq@XQp(I45K9%oN5rCu8u;6vj9wWAMxr#yBTq z@XQp(I45K9%oN5rCu8u;6vj9wWAMxr#yBTq@XQp(I45K9%oN5rCu8u;6vj9wWAMxr z#yBTq@XQp(I45K9%oN66k6tJco!ep1EW293sYe=8nO0h#2FU zI|k1oVvJ|*7(9oFF`l_&@Ejt>c;=45bBGw@nL7s0A!3YY?if6Wh%uhIWAGdz#(3tA z!E=Zh;j=^(?7~`2c2G1d4jA!l`Jco!ep1EW2 z93sYe=8nO0h#2FUI|k1oVvJ|*7(9oFvDdj6i@h>}&c*3o|6+`DG6v7~VvOfl89dvI zF`i>(@N6%}c#f69v%MJOIaUVG_KM|iT-)H;UX1Y^D}!fyF~)PO44&=97|*dXc(xZ~ zJjcr5*RgJ*j&#&fI;p6$gL&#^LiwijcspE4GEumt^-)4i_B80TaR zo|nfM=VT0?m&X|AWDK5{#~9~i44#+A80TaRo|nfM=VT0?m&e~qI45K9ygbG@Cu8uu zJjOUDWAMB@#yBTq@Vq?6I45K9ygbG@Cu8uuJjOUDWAMB@#yBTq@Vq?6I45K9ygbG@ zCu8uuJjOUDWAMB@#yBTq@Vq?6I45K9ygbG@Cu8uuJjOUDWAMB@#$K0a?Dcxa-Y>^k z?tvqGO*AKC@C-`MgL5(l&!A+Cb20|cpk$15G6v6}WQ=n%2G5{mjB_#u&!A+Cb20|c zpk$15G6v6}WQ=n%2G5{mjB_#u&!A+Cb20|cpk$15G6v6}WQ=n%2G5{mjB_#u&!A+C zb20|cpk$15G6v6}WQ=n%2G5{mjB_#u&!A+Cb20|cpk$15G6v6}WGsA5TKH$!mqb1u z`c4#n8}>1I9}f9(fQWFlHvcT9N~8g`T5#?IgEvGD%8vAzCDb6JNX{*?PpB&5Rd-4 z$k)W!^T62i!{vD1LcPo*{nqo$>E74G*vEzEdG3UGg=_5h>}u=}nGEquIPgF?@IyH8 zM%eqrG~vKA;lMxP5EsI}e;UFejy|1zcRoM$PtFti1Eu@^$#sSPL+PPk5%&F)^Mrm# z>3Ch-KMDJEEAl(Sz8uEBe8#?B#=bp_eg6ddZMeS(f1Wwz2&&Jgv+s_u=Yi8bKcRfS z-zbmglhZxVj6MI1eO$QxAzuHl-gn4}6W7cAf_SHN!H*NXIo}UCkKow}{+;iK6btA5 zpNvHuDL>W6=_2k_KGnzNi+)1wag>kB^!<>r=x_M9+x6 zpZq5r@>6;!hj1vLaHyBCk0XuAbiJDL5%zJUaX!S6@!vk)YfkXS*z?KQ^UT=u&p6y) z^jqSvSlKh`zBg{bZ}+cJ#mav1Pq=g2G)dU6@=zYaOS`s>ymozudLUVvq_btysU;_u zs5XhIllm1bufA$JU47gpb<*o8Td5t36IJp)sgoX>JV>>U>!bFsOr6x}wHc~RgLY~~ z&NN9_mko8vHpsd{9;&z0#PRmZ$DO&}qGvnX9~%$hdf|`icI&Z8T<@4%Iqm0z=W)Hy zwp$uq`qX-^_iD12qIX^0E94S z(lru(WaH&1T_fSHIZ9b^jh5Q)uTj?fPdJt*6jQECwt=2mp)PDQ=kYu%s6v(h3malm#>%m6=A`-5}Yf+xe}Z!!MO^Y%f1xKzr78T2h2l#AheAz zw^{bXzp&5Kwe$5>i0>9D-sdFanZxf@-TED5yry|ob*1qZ#w*`yufA!sh;i`-!_|~r z6B*yV)hSrnhp}%zCuo*^@RLXPbi1#3FXtjpx?XQd4$(ZWFav9@w{X#ra9)GjA%OQRkd)`95#3y6=JLRKt=y${;VXBA9 zB~1537$^U#@kfqnf8p4BYdrt2^iSE(|El{@-sAtp@#oe!M&s6hc8o2p`|>@QvG5;o znzj3++ST9?*Y9i`tW@R2U_*z=6>Uyc9G82_#@A7lKT!rwE- z@)VZK7_WUe))&%kNT+&2eyS&wL-mC6>EBQ<{XMjYeizzF<%RZBJ#-KH>!Nh!uZ!|C z_T^}QT~t0}UoT_d9>%_%jHw>ti+(#YVF6uNNT=%!`H2U{o*%|k5Ao>hB|aHrdx&So z^t;ebDlfEO#_MeJ_8hwgt&=6a|Jo;vt7S`>^v2^aG2VJ5RgxTICHD9A-{Wm;oaeFb zf7*EaXX1Nr=hpi8!0XY&d6OqiKl+WX-OgIVAC9T2m)Od-S%FkZ6TW&&n|cp8O3(T7 zv--n1i#fe^y~4WLj$Ra? zY`+Wb$9B5VPP|?ht{1P%h3i62T;K$GaDfM(9w8ncKK3SkV?R#U>&sD|H_ER(Z&a`L zyixg_?%T=fzCGIWM%TsZzWtnzyb%wa?yr~Ak+f4ILVn^oq!XW^e2Pmbhxq4o zA4g92@#1tJcTV^5<#gXq_v5PQ`Z8WA4 z4r3kRFa{E)v5kIDn8r35;|Tj_L`df`*5{{Z1gD2FnbNU*dPZ=%e?~A4V>{)+-|?7F z80+C@0pakB5b0LrXY9*ylv8mMMs@jg z?zcWaV_%M=JidI!zFx+@J&b)j8Dl-ve#Z2DMD_XWqU#O$i3i4>AI6?H#&msDAN`iD zo9ZJ>d{BLau{??k<8Xgby1%~^VSk@8{(GEk%^dzu7$^U}zheFQ|Cakp#w*~1@#k@T zi;a_n{r#v2`}>r!zkfBQ`}>-)zuy`Aaey(6Tl9O%AI3?-VVv~oJWdk!<4-7u$4N@} z;}xfSo*9R6lJd|vMD-D-@rmjqjMv5Eq)4|SKjSb?QhJCZVPCH!9L7n)zMY&N#z{)2 z_b#fBu)ki$o`+BlJx3UO-WYp68GD`?hjEh14C5r>zvJ~x;EkS}jQ=Oct5%t+I@R1C zxt-|>j?^1Idx862&AeC0o5Sh*e#@>udA$$g!D~wDlqI?{#ysRpVvOauP!8sCArJo6 zh2LWNE|l*v-wUOaesxXLw2n~!@iZH zR%=m1jQ3hCX?gKpt0gTj-p|K!y|N9mu8@c7^*R*S>$O_0*K4(0uh(k1Ua!@1ys82j#>lPMHqF%C|x6A)D36SH4;YMFhbWz7ET+=g)NBJQDWmf92J>i?HMf9rZlYx4SCJZVrg4^FWlje`0R zVbtrC*YD!-U*+{X?qh+szv{k__np^AxD8&PW$g7?#$KOg?Dbj3UY})5*Ad!DSj6`) zxu?8#polB4&yv=I9NyArLpseB#|y3D*8NE7UZ4Fd?lrnzZjaEZQxt3JGhF6hb#I3LPuK4I6_@Y(8)K@I>ZUxte=_#{ma%V}r96a1eE-w;ue{#( zM(tLoe|nnB&-m;y_0{%`9LJLVPpcdwGD^&G_jwrm-*P*Jb`UQ#!FZt+#tRKG9yQIN zEyfGYF!kca1Eq3EtL5Jc&6MgTt(M!2elZ zW7>aZybbe9I9F-H{1V|XzeG69FA?_h#x!qf!aO|TFb_`{=V5|IX~H}_r4tWSA7L^7 zN%?sm-j_pKZ784T;VC`L!xP58lUB=lXr7zuqjZ}8rut&#+|p`8I?YSdby0rCz8pvC zVIH1vn1_#*b4xo8?d1Hv{fw~>2Ms!0FQ9XyUp{HIobLH#?0IJF`R8_ud3EIZ zmbPw$mKRT2E%N&~YPIpC)e=Un7RQiVewcs4e~-7ZaqoZfc>8DKEA+K^p~1xqtu00YZP?T^1hz2+G2wOURW8YQKZR?F#Ls}1Fl zR?F!^1EqRNtL1dB)pCBJjneg!R!f>AU02Xj7><${Pc`qjAJSLd3^cwjNo+om&R^N4`VywFy<5X&j@Za)#Ejz ze;QZA_0m}F$6kJ>_%WHWzg|sw{Pi;a`9Qf${*fU2#0qVpH7;4$j|RQlAFZ4=JcR1P@XW4O*rTggo92&n0`mUC+zhO##9gT zI6|azfAIMk`*Jkp@#Qo2^)mMDVeH$<*y|mP!?;1^_&9PKe0&-ExI4<@`vc?uTgFMe zuHbd~f9C$edHc{mX@36J{Y5z3UxdT`ML67Fgv0$s*xxTSw}0#YA{_27kxqI?$j{i9 z<0w7cUxdT`ML67Fgv0$sINV=^!~Nyc`Tp|x`Timt?k~dO{vsUiFT&yeA{_27!r}fR zO!pT(Lq$4Yd$_+SJ=|Y}!~I1#++T#l{Y5z3UxdT`MObJtgKN5HRUbArI+IjD#7 zt)q7OG8qePi#Q2d*x%0!)RAdi4gFb+=bRq;Go^?AOgQvs!vCGm3;BExm|`ulzpuIf z`1_sl-{TVN-M8XMyoERt{y#J>ff$!Sj7y{`-_pAU{!?R`yvGG5ZJKmv9uou(`Zc9f z8~&vxep@-W#*jZV=EyNhU|DY%_qYvW+ygQ01x(`}$Z`ax@tL%H9-qZ;|7pzhZRYzz z;7}(2R+K}$g>jqW6~^tr6_pdN<#rs#Tdqs|HjK}l?qhK~mi5YVsILFeGa$;OawzUx zzW6P*A@~i#^O5u5wUfUh@DQ-9m*RD+4L(0TgD6J-(w`v8B%VW=6feT`TZ&QmZNU7@ z^>sPQBXB5(e=Ev?K5Yj^M-RBD&W;=n#}d-btog_d^~d$mFnYlEk$dJO)7PqvfhG;o zsG2u#s^%ldz=574qc2WOp$QL(G_A%xP{jk?|Zp@B_+rxv_VqazIDeh$U2X0~yBX)UlWhK63mCUvv&Mcr>=(u_jXP>n^=iy`V$VP9 zQ{O+%IP0|(uIPonQL3v*xm51{51PdhUOF_n`#Q(Q2;t)Dk}dPZ3ySch?R#yzYaJQ4 zoV&HsMthtKui)~xjb;}Pk?smDLtx@eNW69h5Kb}#EMPIi!JB@+yYpeF1 zbFwi|x#N0uU$>5`+kw$=j7xp*`rtw>Y_r&-lz#%ORid#J{5F6H>jSSJ=g zI&JurE1Z5}=77lIv9Ug|`^D_4)6XY3{gL{$)SSsX8NYJ2Pjpqe<7)iP-vFPXzchL7 zlqLM&m=Tf8qmMC8UGy>aZR$OYKP~u~8Z>+r<58{pt2*gtFwVJonre6YXU0!YU8&yq z=nKa8*V?U~ot&5P*f)-;0;$GEsr&))r&O2y4QCKua`l+{yvm>m;WtL^QKiS_RD@S_ zTdfwIsLyz*nyKn$>c{x%I|=Ig(5Z}@3~Hp>&RxNHN0BF0;pi^L9p9M}>397oe_{O8yhV0Z%^w*L zp0?ES^ytj=1-X|v|A{a)J3cy|1tXuCgR zF_L{i-lzYk`sC!J^HkjoQ|vEm$3WeR!_{{$ud%QFF$OB;`9U4|>WCeke=O|#y`Z{S z^{OrY##rdOXKbW(w-oNK)?=ahlw2kCo2lIUW5>eY__5JlJyW>Jo5sS0(FJYG_paJ@ zDaS#sZO!bOc1LW+qT}Gv0>ka>x;QS>90!$F&9fy7O|cKP9|wiH?zFpBbhldt?m7$dfSbMv@>?t#+iGn7DvWIx8-x~=`vGQ`}-$A-QS1V)32^o72+qr z`TXD8yw4w1Q|nKFZ1bP6t9D#f&-I&dYm8kye*&y5zogX8*HUSFdICJqeRd>m{uKIn zj)_q4fjHGN{}t7*;zU^4y{)>x3f=bEIguVUC&2)$XGFI3r51FY1l6ad(6xId zMjKC?1R3jIRll_tiJ2f!e+mJGNk=xmD)cr(OxJ$8J10%pwgdRXtOn# z43j_Vtae=6V+;N~8CvZqtA3ey(H2=U8P+|uEt0xLa(Cb5$?*L7gt+IQOXZUCOo98m zcaHWdoYG~fG6gno%V}FTxn}hbQ(*1-Mz+<7WA>}DQ=n&~q4u@r>+FziQ=oL8xwdrk zsrFjxsj&UCoi^!OcRRG$RH&Hyyj4Z2*=Dt-!jXl^T)(?6M1Sl)6?$e(<$jozJUTRK zDy-?5(rtOLc4W?xsqjsm8+PYInN{zs)1dP4llJZ7_0*ylr@^B7o9yI52}*rE4c6t4 z+Jm{0)TJTQ;HAcW?ZBk1D%Xl>@LsK&w)rP#)UvD7Aluj3?WI?)tE{=E--_LbWv4@Q z$dXdqk<+)om=2x#%#Iw+mqK?OI31Q|i&H5vcF!!I4mW$WRUfoCpx(MV9g;?2tX^5B zHszlIi;FK)k1ZLk4!$}A^d|>Y-szaHB1Lx1fPq*~ ziUsRR)lNSX;xTrK{S%{EpP30m>s(dE+ZVL$>db_-iw~=ny;|6ry=KBQU$0V!2PN8` zb7#W($rIE;jNP;oGoer2&Z_J6J$704C}i4JRy{iDqFr4+3bUTr7RisXoA6x}vh7ZY zD~GXrcSIC&_30dKjVrl&0Q{CcSE{=+)^Yz+(9 z`p&g)|1i}KXlJ2w!<}~GAKmSAFc4$6Y-;l8 zbI&@MgRyJ(SnbIB^&RBI*y%?ytK$6}%s+P0b~{;5)mh}=K8)SirxMiG3l9Fs7qv5T zC#l}K04jXf*H)UfRn2-C;Hmd(+M5`=kDCH4|1!I+QsuguHWY5f?)n0NVn>&h+KQZB zJ_C?0lzA_tHu1bijgt5E&_#AlY z=g!dv7`tj!=RlR+Iqj;(*KFhFbKt_}Mz$fwZo;@ZQ2U#q_H46tcE|QPuoz=EsM%B- zmv$~Z^!ZM^@oIOwqxf7X`q+7!u23}_{ctW6#MrG$b|E^a$6OeJu{%9Bd35KjxiA@H zSEE4f$n~RhVN2~BHt(aE)!J{)0t^Y7i&6>CXs$%TkDmo|9VD|zTg7s`Fx31KXyBER( z7`ui;6Qi${S_s!_UsdNj6}0o}E`(i+4y$MTwXhd@FNBmByN`w>+ST(G!Y7j^sC?%a z+H)rt!iCzMRX2=XnjDMZ$4zC`CXC(P6&JyKxwl2$#@HQiya;y9O^B<4vFo3>2tFIw zIr=`v?(~{PuxU?D+XG{l_2wdYcWWb?31e5e@M1{z?NHkUWB2{Li=kq_x%NJc-KO@7 zp&iDqD8}ylsf(cn#%^eVYPS0R#qd1FZqN1e(f2Yhf!{E85C57x+Vr_4FbZS$c#+zX zgin^h2#j6VT$$D9{g*%rj9ucHdTQ9>C6EPUch}Pi>VZp3U~S&0-Hx$an|mpo_@=Kl zv$v|Nm6t;PcWc_o7`qY8mcodJ+3hln-PvJFZ^f>}qNPx`^3qb9k<$|A5D%Rl`4wYV zC+9Nw{oy!uFUBrYyELT_}emQg0ahmv75bN8T7>1ZJ*Ls z=@iSM62@*)tvK~=(dF@^z4k~uo7dJ zvP(hx!J*|a0Ap98e+%35ffX?Rt5s?Z#_qE+DKMB&)mDPto6~-Vv76Fj zB^27$$ZkJ&%pM=V65hesmB83NxN{}+#@NkiI@NxiZWYYM*lqs3yM3_aD)XHH_WlZ&yQaj9u0|Nvh#5t6?O@t^vlb|Ekr{vqnw30b}>V_0^Cb zW49M$_tRr*ZpCixOKYI&`?1)q{b~(-H*9uf7{)I7kTvklBXQ~yepioQxdysp?DqU{ zK&`p92F_sY8er^RDXay>^>|! zCo*c!T8>@wht`$ae$P5ci?J&@JTdxH+&Y+#v5UvpUH@nubj8@!!Pph)yAFn8?Dk>o z(l1yCzfYW?I$`XdI=v3Q#n|n{*uC)ZdT55ROOLU8snU9Q6=PQqW0&vy^^ncSZvDvh zP~OL`z`FG?31im~V^=NN26zNxw;N;E;pq)f6=P>GcGGHZfQ}fu6&Slr9XG&qjNK88 z-Lz>NUz8-N5^9`;v|D2ga@-#;)q+jW82qcOLJ%yYp;<4H&!17`u{HHo*;yox|Ae z{$Ufe#@MaK*cBYU=~nDMU%Uyryb_CD!}FWq9e>{qesnV&#QQE2-glK=*$kC1c6Z@@ z_t_7dVG_n}D8}yC=*>_EV;6__-PMhop*hCxI>zpslv_Y!?C!=fvv092@HWP7H{N$; zYi;4!T`jh*)OTICKt_yR|6z&Ig3&E-2xIp}=Yn>?;Vm#9V>cAX%#~TU!eNYEM~vOC zWw%0Ayzk;McFR8B3cE0NgD`fx25yCVIA(6gF?0X&t@s`o8#Cu$-3o=~#m3Ap@^6D; zIA(r;_ub-Gw?QI~nLlIfPPW_zkKmY@8^_GN6Su)meBSlO*uA=I8|1~=iQ0#cEB_EylafH8#R0fG{EQG0es%A zTfGC`!sp$m7`tXScEEXj-u1)SEy=U!8W9+gGPK+*&?1p0at}+APRZ4xl z8%pB4O3J=1Z2f+_;d^}Et;2VfG7EP@GJIDVhVLpLo!JfJ@m=L%j9t@5_CN`IS80K< zYw_|PcsTF2NNK$9-fy}G2CR*}tK2hc50vTOIr;_0uJ-ypFm+c>dl+NaDfwQgfbS{; zFm`i`?1g(UcE#~M^VEBLp;6zt_A3iWkzGpsx@0rUF?uBd^ zyN^>|h_1`B4+dlGhE7f%J^lPXNW$0^dAxQc<7fLI3%+Omi0_&E2kZljv73tTnOTL4`5*k!?Qgw@3lLVk>0^|(2a zA3i+D-w2cJx>6H=ItUtLcLu)^YTJYSjZh4~5!N3$2-`7sqwyOd^@E4t75qk6ir)yk zUpxdiFm|)?8zIG)hhQ^)Bh=`b9_@4Nf(`>xaO z!_W-B?{4BZ!lCp>AUVdaHGbc9Ds=?kh0fdEPgk?`J~{#?@cZsb{Jv}0=Lqz|*u8+? zcb(@QfwdUB&++?i%*i9r0%Mne-*?S(9EH00eRuI#JvFi7Q8Z zhvWC%o)Jf3B!1t$gWq@Q*B*r$AJ(*GF?LgK9);(>$!?e8_g%8Q$8N>$l?un;*cVGm z?ZDWT`Q{kB&~tX=D#otSuw!sf);RShe&0R1<{0G0@4I~%yXS8ngA@2|ei^^-W*0gR z>G1n56@Htqs(u{$@ZKq34#Pl4a&4eOtPvG{F1wR;OYwEqcs2fxjm;kS9yMJFJB>I607 z%tAZ(>}FIx31y3Ji=1kn-1TdA5WFwS7?%Kml| zj&$xEO~lv@*l-etZOLi3W9;UpI0ZkiZDg~YJZ66{dJ5WoHPq&6vCiiG;1s;ld#)|h zVybQ3`4ptXZ}Vg~y4!p+Pr)7RSHD;{QiY}8nL?SY$&o6c%ui%v*K^Z#(J zZ%O;!feei2b(@4C-glJOUpgve%Y1YUWfBA zcF-d(Ppit&6MN4?(fyCOs!cLPuBN&GrykDX(v`au`RU0E@Iu@J?!nKhsYz8Xz}uDY zae0sTQ02e90QV11<`OQ>Pz48GfC*I&+KcP9su$*5fMQQCw4=*kRvq?VfMo-Q+SWRq z-j(hmOgr?29TAsVzxMP+I501V-CZ`jUiijEShl1?H2X7;=nPFS!k(sm;^t<`sVfY= z2(!y=h`7(pf6;&1kdiAsP<=1sWX+l1Qin2 zt9}`etG;hvg4H|Ds^Tk_t6!U4f?2<();H3OQX__4f=^oBr*}1Nsje)(1Pk*#sC)J( zq*|T21U)7`taEN19eF6rWq2Na=$UbrWGL#sxTjBrhy=iejpRdy8 zAC2?*gcDyJ9yzx2cgD+#KcTv8>wd>frNdkoAha9aKNaXLHo2yv4idK=jka@V?YSSu!NI$q zwR+=0yY<&`@N(5ww!;@2?A*2EU{ryjcFha3@SA)b6y9X*rMx3-(_G_WU&31Z`L?z; zq5OFGW#)dn=|VYM=d1BxKRIKY4Z9KjaNu|-Rqe7JGqPIr!G+^tW1}l}exAv3KO7$q z`rvuHeb~H6C7g5qqt#JcwP-HX_PwP4glcq{XRD);geDih8>*L~-GwX4)F^~AM_ zu=?BX>d`Nksm^&P!I*c(sbsHDR;yp01fM^(NX>eoujZA?AKzIfLZ zNW16q?{Jw9#wrhipwo28hu*?p&k9|Aa zZfiUhj{Y3A@tqTGp&?V@v)*fLr$+7VQ;VlU(%F5s={J?^u`^TQ!12?zV6v3<)I-x? z&cm1O+&&*flgdnkx7%N_Gr#N|SL~B%@c9cDY{jQtWKWN2aQ=y7wno4F>N__LGB(&| z&5qAhhlA4~?TCf;<;#6l?+nvnu^np_znf&R4H% zkVU0?|D^i4>I}$#vW6;>dAFMI{S2sg{3n&B<8t-*h#7Dq^;orR;1tzq`3&fjZlSt3 zx1W0Y+zgm{daGLT%jfFp95dm<1D6D($P$c!) zvo?~-!gCXHMJDaPZ2J|maBAOO(Y_B|vAbWjFelCS=(|6kvzeM&ID6(9`@h(`&#)+x zsB!dwIcG6vG3Nk%XaksYR?G=8q9Td`Gh)J=P*K4IiU^Wq`b;4?=bUpM;tXj-(OX@s z```QRzMuZjdmldRvu9_A=|dm7rn~A_RbA&5Vct6=;XTgcr9Fw59*Jbi!k5^>&Kob) zBiXT8f?vvQF|)svw7nUH>)YNy?|D*ka6~RvDVF1rBT}+`eB6zNy)4HIPe<*re*McyeFA4 z)mrFwp%#8_@FZ4xk3BNJC}GqEPjYSLEpDu49W=i8B-;Zz!{W+v7#!tEHlNjl@g-R> z{ktcz*m@g=z6u92v05AM%=2GK{qkqc@mQ1bm42+zI|^^qm; zxz{-G_xnb+x>Uo6hk@L&@^7U5J|$eu@zGk@!;6?7tcOnD7732pUgVHN6=X{qg!TGf z#BxwR*z}r@EAMy_ULzKwRLpUZ#ES%-mBORFZ*fJo7cnTafsWRm__U=ru^xLFB1_`% z`*?4HrL*9qQ30mwd6Pqd<=m3}!mXQ=aNjZ?QWR^2MhQMR!o-KX>f?cnmVLknFMNpi z*+>j~braY6(?0NxIXK90HP)8_OODAi+ z-RnyPIj!}42d=|iUo!AeDem7g2(Czc$#E_n)duW^=ee|>yf_GNRX>E7c7BB0=7fDV zegVJ9ek3{a0lxPNhUkrcWcGc1ypl)PRWS1-hHv^~T23j9`|L*|?QMmC3AOMf(T|*o zXd$t;S3+T__U1njkjJ0u_PPFN!m9aVF5?JM8N9T z{={X?N9Z*2EBpxdCj&iv;fCZn7+2D`YchOaY65e61(1)X#gO7S5f9B(K&A!UgYDW9UcRjC%=x7kuVF0lnE(ecw)k0ow0GXCcpPwG;Vq*J1GGbI5 zfW8?zPY)#K?gX0sdX0_S0!atGH_&4r!MWyvBsbIyhLyzPjn9E(lkprl?vjr?lLE=@ zF|}M)D><%H4I*adGdcCU^(Y$^MC`SbB~RBWan{Np@^y5$uzO!MPCFGudWTKGDBEHz ze;q_xpE-ejmM3FPSP-e$^c**<`e9g25c!nkj?L{q;=;bc#PU!C=1jbWCAz`n@%3y} z=B-21L&0Rt#tQt|yd&OzLgW2)IMMa0@Y*YwTz61n5m%wPtuUBG&8fvx(eF6h4k2V| z>oR;Q?Fa2NL&&1O88}MV4MTQ@5TlkMm~8j}3~z=I_fKC?wVe}~IfszaHIFdKCI}8C zhmg^=dof!j9bT!15;xt!7(BNWT*rixn}Zw$|MVIdzb=%FQ`3=D*(l*P?LS}XeTGw& z)B*oCl(aW$1If)RVQP3N*>i6d^tzn`x^F&_JB*YRE1{E?JV4E5l*^{iiZOMmvFXwI4Lgm1c&=J z_#q>llzG1ezwuI3G>afb2Ig?KAO?GnjUdYU`Or|AhlT4RNZUItzHU>7AA9wN2kucM@p}e7 zUbzG8v!Y1m;83(KxCgD;M3Vva&e#G!gU-ZgaxC#NZoLo)Z8t;{-E{}?XP-3CxEM`* zvxi}ycQOF`Xfp4yyU_7!4FtqRlktnrO6(ufKJ*{aq+9esu24}2nS*1B& zEsi0(dn||V8*?G}cnq<4e;rPQN73ir7*h4v798y*bX+xt+}i97r{BGVZ)Gv0VMHQ) zEIbQad&H8_y^3IGoF=TDMf=##E8u))IyZ8EEScR^39`o>xLx;S$@ubmIQOHU@X;fd zRJB(?z_olqB|DZh-&_bb7ql_EO&n1SPk?>HE@I@AI8r>&3my%z#?@Qm$S;leFr-?* z*O%kS2bF7(mKlwo?BmGA(~F_Q=sY|WA4k&aRH3F*6(0T-M`SyZFl z(_MIdEs>m^?TWn(9H7xLk?60t#Mzqz;A27}F>yYO*^^S?%P-o8e|99s{VoCTkx3-J zwWsiwuKBxpbrP|Owvr@XrekDhlF0V#E!@D-^>EoHiS|dS0k*4x#UV*#h~;89HZ%{G zRVR_L9k0Q_#AxWyKbeF~eh(jt1?V|1nRFQK1-pA%gTcXMqB}kT9`?KlvWLlJ@XkWG zzf&7hJd?@W&I)L@D4&zizIwxodeAx7kL%bug$(LKkKetcuzq?9X>Y24)%`Psd)rdT zn65=|O|FT1uBQiijZDaUj9w=K(eY>+X{Y9bagLwS#4?Rc z9utaI$@kFtTN)Xrnu#B$?7&XNX(Z`=876%1g(JGA6Un1mH0$$HIHjFVl=QlGn!L}$ zYF9eR7+Qxn4&32R-AE^0g32){ybHW>Nhd8nXW{MR8^I$zog7;kj-C;>L91m33B2Zp zI-Nd&$G8ka;-2EQss6BdZ3b~`a}4jzO942SK{9%b#rh2;FyAhNv@`V=u0&KrRdfb< za7BLCGG#0FXJ4x*29Q_nZ!K&Cuet~3KAD&689bp;A}}A#2RIi^T+9UT6zpv zTV;~y@VBsKm=ps2GRcrSPk3l<1D#}<#B@?TeDJsgr@Cg5C$@Sd1DgB`wAq+V-pTBs*9i}7c`=*7xSJ3Y9EmY@+2qHuRZ#vg2T#Ui zliF2nU}c+1yz(QP#Oj>knqeK94$C2t^}3QfHcITdB!_(2?kLoz)ZooyIn?9~#;dbR zvBeAeo-X@v_4hRF8<<19c09rrmO;3*GKaW+{es269dT;UT$0`?1WR^2z$G(siR+LI z-27rUS{me%y&cLh@kKv$yq8N(%&)~o_umO!F_-w$@9Q}$WgZ)Ia>=N@b$CQ^l~Zq> zN8Hv{pvth0FlJI7d2uNlXQ{4-nVa+Icxwa>op}qQuH=#GaCf}q{t=EiAnJDKPe7wt~Z0$_Y27F;(X9Qp$mC*Ea3hqISf><<`VJ?NS0MS7_SCy zSBF9}dbtu_KF^l8O(`TJmsW$GZlvJ4xsVi|D28zn6Y+?7AsNt?_9yK(!Q)PaMC-FJ z{PKT}^O6h6_=O+Ack)*xzY56@FAFdcBG5pihy=*i(tH1GY+O-9IySb4vllC{WHH8`)8gYZeKgtUIAM3W5@CEa(FkO12{JX~|0`+Bv6IA&JhvD0nA-Km5m ztj<5#6rKEd{3hu}m zImqXhl8!_ zH#9z1PV`pZ1|7R_Yx?W!y^i!3Jwww*zxrW`GmcG z9$&xEXRd`6#K_oMxO}!2$&m^YGoTMHF)71t&nk%N{GE79nt@~dD#(nr_fbDK1kK7S z$gtjy*yXu1x^}B1J!1kc=Wlp#2g%JA1?Q=qgh4-4wqVCPKQhiUhMwt=jI_iX3Dx9z!zXxc=ZfQgR+EL9cYuEohL48U zknYi&VN>rcY_qI}lq~BG>ATBu(8(Gy{l-J?X>~2?+0+o#7q`A%ruRw9f@+BNPfLLh zuEh-%HRQmVo;b68Ia;aLlKE-WEm&rvi%u6 zxR&e*4ijqWHJFOgUWPa^x0dW5FT>bVBT%<}9XUR)2B%e_kV5GSTFsmbPiYifWU^57Hs3Uz!bFs(6B@mTZN9--4vGt{Ea7(40?7vI90W9Cc zt&#QQq2nvmz32s*%j=1)&IL?7o&X0<))UX2fQ^p|Ve{*H(sD|!P&YvVnql>1UDi&a zW3PJ1D5)nqJ`acaJAQyTM$<6DmTTRng|-;GT-EXjjA_l{TRLt+z{oZ%&VM)&507oh z;*Z@f}OBy{)oN?%bX@Y1ImoV4<61}CoagqiWK$?4 z4J{{MMudVB4OggfO)V$q>2a=@ zCTZ%otRUWBspDEojqBtJIwsfvsXND@IURr89#aHEj4q(Z-3oH-VkFqzd5;f0E683S zC#cB}z^}y>(W>Vv7 zQ%Q!*vk+n@P~%F+AKQK%fJ-m@#AG`DsPAlyM`~r*X;c+is&9k!H)3(dhAOh?x({mH za>M7BtH`k38Q8nSedL|0$noCQ_+jlT?44OfZ2VNDpV!w2gF48`_a4oqeK)BIGeJ(W z9yXI!nC{}X?U9p~2YzACnl3Q$p`1*i?PW~hUfAU;CzdA?aZ5idNUEZ3!ZZQfb)&|$ zpMrF{@dQ;}Qh+R^V~*FhV(iW;*mF`rQmlGo)xt(_exdlczDlnGGUvU&W;H#h-lYYk zZmk!$o7S#Uy^vf`YC`l_C0NZbBoEEZA@W*2c%CRE!(Px@>4nn1fIN86LR2)v_mebmGt1c$C$`@MIw01rNOGx1|3*j@Zo%)gzvIYmB z_4%JTgO2;}ayLeU8W|q{P(nHz*r4_GSbURMLV|Ai;O(1k_*+#*w&`aew7ZY5$IHmZ zKGk?}Jv={|k>QyTIeF zrDSS#ITnTPg&>_$GXHoYjvrtJ{LxafXR3gYx_iQREBc;mPjIno3JeY|C3%;(V&E=n z%j-(XSbnVr&_d}lS?!V zQn?$ncBhWz68nS~TEA%RG^}%p^Lh*68m-+~>TO-zDFPJ zG_sF4fqqE<<{PAu(4!V$RY&_YAEuE!#az&EsKuYYX+&*nDi=g+mmyChQ=MOEwWe<5 z=74mPzMWb-TDu(T+|>OB;7nS(R;SX*bx&hlq>$lEyL4i=-v)EdWARWzI*GdFgUjgi zaIi`SNi)bm!&dk4Abl<#*{>RVEnI~Qw`7ogw01N28exS+1{p_d*K)X;U?|BTX0&#r zop*7!@-oP9TDvi-U158dOrj|-$L?`^;r{GQ^4=&BqX%0-izC#tO%m{(x+nNP&m>pO zs4aI-fzrTC^6|`8{G?w6k7_eX(w*K|LTi`PC+pwZb(rd}k(TDx1aA?;SPmiAUcH_SBcQ zptaj&JO+Djizg-FMX=`51zd7Fp7@=K1kcCsQ9~L}?9mCTWC6ISFrN4yrt@*?vvDi+ zrA8IhxPGq1UAhUxV@)d8lA0e~qXg3b)(fp}w04y*6UgNK76M0WH$NnS*ai*2YiEDr zA?iy5eT;E}T!!y763NwrHgw<8Sd3YlNOs@x!58LkIPPL18M!Y5jauBt7>7jCr++oN z&RK<@(-MgztzF~f8o{k?5}8eFXVg_qh}BFYyJ_tr{C08jT}kBJ-e2h5qALX4OCn>c z%5i(rUa0d*B6E)>qA=774pz`Ut_cF_^!9`ieUiz8OHXiuM+&T*pG;Pp(Aw>(g73$Z z$%31`@%fTQnEyQa-`W{@hLLvVftm&MoUSbiBR;3SxSO_qm(dVZa8tV zFo(`&`LN13oJ@L4ue;Tu5M>iiT2BZC?+AOy3JWKD4D!L1n8POOx}AC`VbBRJFdZ2| z4%6D%ZSdwsZHOTE=y4nz;x)ILMUXV=wGNzqFLZK>AhY*2K*q^2c%HiM0NPJ}lFk=( zZcqD}Pe;OS%lBvjk)%rE1gFXZ&~Z;B@jGMzeZFU-FLm9mWOJdM)-H(lIiFjc%FU&< zv#W|E^Y^~c8bE8ewto~kb<9HOLTmSly6y?#12Ee3C&p0M{VTv2)vILK#x{!R8`@wS zvsj!SA4Tf!`e3P<8$S3QMUL;!K$B+oar)S3(r!RCuAH?ByKasqHMDl#qiTfSH>1gF zTDzRzs)D9RG?_zdcO-Eaw>~$T#2fsgW13xIbmtf{u(BK-()PmUSurH%a3a1PZUxbX zG35I=0WaQ%M)=e__TSn?@pL}L z$so;KdQK(#0?5_NUfc#+yJ9+KWZY2;yhbYFkzW9Ld)pk!FXh8mMF7cpXAjp`g~HT9 zfy88DD0B+9hdE0E$&J1F;7y+lz36<3(>;}tc~lFs?E=XgTD!>Q-rSwUK=P0tr|+P6 zO&_%&;z(<^?DBizIGs;nX3zlR&yK-7I-lZGXc3&aaRGbY3L-@(BVpOI_gEzak$E0Y zP+cB?-3o$8>;Vf{-jGfE41CR9xk=8D{V^_F)HUG}4k{&1YMVzJv9nZZ&Yxm;jdm)9+V~V9t zQtRRvT$t`n-i8#>vGEIdrkxLc7KjA-^Y^%p^C9l;POzae08i=DvEBU^aQH_y-lFrE zd~)W(W2aiY@9jfIajBd@YiCsHLw*l_p*4lpZa_a@QfX!(1ku_Zr}LOFegK|2^AoM; zJf_+RV{BO=!?<_8q~xd#Zn_wYzhixg{DBYRMK|2?%a;@%%s`Ld_fTbwA4wQkjVhX} zFrALuo~E_qdesPd*Zs%|TDzC&s)EW_Khl!cF6;X)ZcvUNc|@IL=Wbo0rlUU@R9=pm zd3#~_On)-tP$DiKWd+X<`IFeu0@n8Tg!NDTNrCAT>?ciu3;zDZX8%@vx~~dGRr{0D zv%S$~StFdFW3_+hs^8X@kh=%}F|L>PN=W&AFYYHbuFiD+V15rR*h-D-HeU(pNR4Yb zHLe%s5|U1hYjZmP^w$7^{GjtsyHVrXVX;8&P~*Cc8rSP|{$Mt(-CAl~KiUf9H?3X2 zS>D`+1c4b>GmSXSo2p2*(c1N)#&ss0KRB7zF4Jrbex~yW-KlYXM2&0KO(c7$aW$mI z6(vX(Q{(!K8rSqZB%7#lJx-0Qyt9<_&zuV@sd25HB_-FWaV?{@OFS$kM$P^)u9vN( z#FiRYTUxsmI)CsoHLlszxT@4j$vJ9V`%>eoIgF6g)VPkK##MhcA#ZB0jPHSgCjqAeJp5zLxT^cp6d!~6Z<4W4>=FE3^lIFB_ z4L!TU#yg$_sByKR#`UJBC+R?qYXvo~ze+vHUTR$RsBuO0Z)7?(uJcF=MR1PV^0{r@$Tn)r z-Ki}fpyfuoxH^FowdFdy-AEa=&|ZFz5M%b~)Jp+SYG}kU)Zlcxarvqs_vzfMT&NboIu+L=U`$iZvO&zbV_)PrNE8x!5y=Z0nnN;mb zh7$d!*q(aDKub^P;V3~a`ZGxx@d}o4@mQq%Os01~4#8^jVmcq)cL_4yw-YNaD- z{rfGq+*3_zWa>yxB$Kaw);E_fe@ExeD?bW>uhgUqA{>co+6a_1`+?R-+!P!(!V;ZcJCXLj6W!hwHB`# zC}6pXGua&59W8%1LZ4^O|DV=TxfHU_1E`Y}UF-GVces-S>X>VF>(LdmrRB`E&JZ@j z$`@J8wFZ^lhI|MI(Y1CP{R#9AyMgFhpDgi*{$HPh=vsT}rNF=-BM@EdxIHB>B619f zuJvbpHQXxn<3!gw;;0h7P4UnYU2Dk3df3}{g&?}t?-!~-vb|9dUF*2iJn-4PfVtK) z!7*_0kvVg%N$sQ%Rs5E@)=v9vK(pgF=32EaFTtXD@yxZZv7HIC-2ZW{mi*Ot=q?3YtqFatU3RPxz=w5 zj`%eC3v;c9bsu0`jS%Kq&+6?)jj0*TwQgD45BK*jW3F}I&$oi}(pu(PPxs34So&GX zTX>WoV%QPF7gaFVI(7bf7;TizT2oPQC?dXqm{-ZmHuJ!y7 zKWIJaIf$+`ZC^6j_B{cjYi)(a!0(v=qH8rWu7>R!!Z^{j9@A68;fi=I(Y4m!s0X`o zvjx$$UTCO-8;!Ms=vv#p%!kuSbC_#A86FF$G-Iyy;5-7eF1}%|)ji=gs3#NVS{F|@ zgRk@Am}_k|K^M-|=QG#(+DySEPnI*+N=9Oyd5XH)@RYB_^{0Y z=31|Wrely?pSf1Kbuf-;r;D88bscl9w!UqlQ+x$;tt4tS*y`pm*J=@V z6CAfig6LX@9{&K@bzebrt!Z^Wu!{a4xd5iq&q3JMAv%$E4{9DCJCZzU27x<=cg5d=vt3#DS&Y+XEWDo5)lU;n=Uig zYIoKXin_mMuJzHZxA4MR%3SNfxGOMdPAqe+g4;aMnV!#FYtN$ZTt}>8t~IvDLayj& zJ#($|#s^4@_b8cbePIwJJg}=~u2ph=91iMH!d&ZPJ!4cBB{SD*x9=H_^Y%m0wOY4w zrw-R1Mb}E@ENV}>jiPH!RLRC|ee|%Ay4LQ$%kkjW&M3OpuQTg#;aLkobgdidIHAVL zH=3erJ#Iqp5n9`DqH8^IpbYi*_F=AdwtWU(zqymSRy`7eNyqLp*E;W_Ga5~CWUe)R z$zyaZ3S_R88+ZWg4AYovUGQiq&d!uE*ZQEyMR@zZhPl?)4F;0rr%L8p2aGr3MrGD9 z*LtmIEBLUflDSsdx)tEvIhVQCO`11g@u4UXU29r*JIK+LfaqF1g1w<&z)KKaYxTuM z*dQ?l(Y1ElNax>KOb5}m&UmkY*eR);=vrqCP{KRy)|}{CcVyK=!}=kD=vq(Z%VG1R zB0+Sm8+#RkB7kSE^+;GeoX3mIwO(=l24S|=%(Z^7eFu^H$Xu(l;Z?XhBZj%w?V5|= zo>3litp#sY;L(gK=31fo1}w1jaD_xwXP`~g}c9%FxM(m zJ&M;7QkZL9UuKE2B7YQJ>qsA0EY13aqH8U)3&Sm5cTjY#nxnJuj>TpaT`PB_9J{sX zj-qQF^Su_eYaR%qYduKE3AGHIr;D!jq%U1d=KfPobgf@h%5k_~Pv%;kuV&(lf!mmC zZI&2{ElTb(*SaIr1s`NPFxN`LpWtQx0Onc~&l;lY)l}wMGbfI~IodMjS|4mi;r7xR z=2|yv+?Oo5p=7Rg!pvQqYftJSsA~=1*9;zKR5I5Zle`3s({h<>jk380Dkq~sbghER zd$2bVKy2S9YKkF^xg*E)w2U8~0rI+tOH zIw!hTo90SzJKRkWU2Dl21-J%f38HKDi!OvzEsnX?ErAIzVd8n_TI=(?Kr!tVbFF1< zZNY=iO%+}1_ZHWo{j_N2T64ZGg`*#HnQIMR-5d^jRx;Q6rg{&j+NPel*0I4iBh^{rbZ5^8R zzR!uSbp+#(@QABquGKZ~ICndWx)$nMFX-w?M!Zlm*J{(jS(qTLVXjrraR`oTS;}0ihS#Q8=UA`wTDz-4Mfw|Te zsuB1*;udqQoAunW%Vc}zS{(zQ;YJfb=32*%J&xxcl9_AG-ZdU?$%>h4y*(>Lm~*$9 zxmK-v;S$sBO6FQ~cg*F2&ek*6`nije+ml?yTx;Kixp0^E^NOxD_Rtl0X%-8jYyDa9 z1`d`>L3FK8CwRinBdH6@d3d9S~jXn6+}KJY2y3j>#0G1poe z`T^o?zcSZqF~I^B_l;z(b&SIrP;|^;t~KscJLu|C@sDejUE&TssAI16RLlO7d3H+X zTIW3dD7@=b%Uo-D$AM_~u9Ue}ox(l%{bo9It*l3ZiR$M32dL=_?Uk>xO&OMUT47 ziLUkP=L*aYZO2?|yVlfGg{)z&by?R)Oyw<@YaRLGE1pdJz+9`#EGs;;#Fx2N|8pnt zCno*lT9uP9i7#fZb)r+W&}mFHbFHB(WRgkql+3k`KR%6HXJ5};>%Gra+}xFN=2~r+ z>p+D@0duWKqAtU6^EeP)>p|1kuxhv`h^{rDUJ7ke-+<^^C*F#M3EQuL=vo^N<->B1 zxgfgMgXvW;G_IZ#U8~-CYMyiFaH4Ddw2h9(-inZju2t<;HCUVv5oXYFy0rXa(7808 zxz;=Hl3~Nb(re4`1DW+imr9e14nE=)EPzBI+P2--dT@Obgl0l)3C?b{V2LtlXj)(c6SJhuC>j# z8ax;IMG#%2DWCdwNFwGzFxVKxmL-bC|v#V z26L@J86Mbp(vG>-c3)rMkN!T)wN48=gBt@AnQINcISrp!6fxJ@s(-RD+)u$=Yh>Hz z!ZO+?DZ18aH#E2z@pSGGb*&}yOSohHa^_n3fEf^%SHN6r{De!e;7UC0&&nb_JK8|X zrf(p+)>oc%-y5BGAiCBQ*J5B#gE@$n-g8D?y`Eg8@-wn zUF+EsN;#}NC+rd{5UF*QRC2*%?G;^)04^tpYag@2%+DHEIa>G;RS`S_L z1ls-Gm}`Bs;tuqx3uCUe?%^g-7-TWm+Su3?x;`yuu62IuJ+5B|dM#1c+H+`Mk7D}W zDZ18XpPmcGbeu?Zt@a`67?N1VTje!s}VW^$iNX~b$-*sI1 zR0VUbRayY>vXHsf?)@%6=Zgs-x>mJUui(dRFA!bpm`eiG*}ezSwFX{@hBXhbf#_O$ z<>mq>T>_$OP0gtU>qX5#bgh@E;qvg>$%(F2a$N~;2S1RAuGL~u4Sal#g6LYKr^#U7 ziV@7UE;yeGbDtS9*P4g{a4?1Tzf;$`GQk0K6I_^UtxmfO3$sF*Yki@%4a#q4GS|A` zT~B!0g06i)U2FZSr(CIjEpx43gI`ZSLGOu0*J?85p%7J9%Uo;Y(C)bRKsj@*?>=nC zPD8VpYdsr&hu#Z?q3Bv?m43oCUtLjjt+sN1{F-HnqHA53k%Es3j-cpT%lt|(DQFam zu60)18kD(v38HH)rT6|aQ(KAXTD#1sM~BNBIMKBla8=mHPldTwm4kWMcHJW8TGOY- zAa8n=xz^2_5YM^1W3Kh>b8B>#eq*lnivxW|iHm2hwakvkO9Kj-Yqe1n3Yx`o=2|7m zgN0Ao)J9U*>QA-C$o@*^S{;t1a_+Ac%(W(eoDKul6fxI2Dc%%xXCkdL|nqHDdZo(qOrD?oIu?YCFLzWSCRx>oh4X-C&RgA=(F+YweX82(R@X|KnOmIs#|m z%v@{gp8Mby5W-xmo#9S+>YTw`tL4HzaP~+UbFCU7)?BO8bdCXaty}NB(!4~Ubw$^D zRcaxe;_H}e-E+1x?rbP$uJwVY9)^9-Vy^Y*%-i_VH5^6Py7{3!ru}q7(Y30C`eFYq z&ro!&IhDz{lQ%}uwFdVo!BsoPq3Bve?W^(mh#*09tzbYM?qq+7=vtQ@sYiIUkP}_& zZ}%#EHoSooU2DXId^{gJkGWQJh((fpg}GM#u@o;ZdCOdDV(Zsfe3hDH>RNv;y^JLZ zam=;Oo;(}fcNH+#+HO;YFy(}txz_G}6NMs=dgfZQKUHgu=atO09%&KB1-GRZnYz|C zy{3R^i(=+lyIwy9dk!Zt*XrtS1w~~(AiCCTsvdBE-v-)Wtp!w}4h_2OqQ4VZz zSq-9VeUMxMkKVQg(Y5}5TL(((3!La$FVeo8Q%>U~qHCS4tO0B1PlD)L51lH7zTF2g z*E(iNIvhy=U0 zs{Cw$&H)i9y4L$zA90S(R}@`qsI@QVBs@pawd(#(!hv^9P;{-`4j1E+x``;d*4GQF z(Ze!Q5M65x?W>zzl_L>dYwpW>>}AJsqH8S~FGp=(1t+@J5pvoOv{aY5)~Pe%@W&i8 z=2~5x=&^jBGuN7!=7jVg5Z8Gy^UfY6?wu;emmdTQmy3F{*sD?p)1AAp*f;YQx_xWG z;`uY(@QPI#TmNC;j|B9&^Uqokk>9Iu&X$+#^^_&5Qil(FSv+WVOKJD7y;yu|X=|y? zfxB$2iN)JnNe8!4*AkE0ac?u})c4Mu7;g=seF)aWK#Y5}E5JE34zjpwU^s65@`%N? zZ+b~j7z_t-J(Ei_J4-{~Tmo@DlR58NNDX^_1aUnR^)7O3;TaC%dM3A>V{rnVODnEt zVjt&(-Hn@Ri|d*2Kd1sx-Yc>etdM0y*_0e9qvIC0inY?=5O`B8OjpBMH;XT@F zuOI###q~^%hW&un`d%omXVUR^Cgd#4MsYop6Gfg-E&GY$dM0k?pF-))wo-9Dlf$RB zLrGOPskolW$@gtw^~OF@aXphR1~<6cDgCA5dM5vM$PdH%OFuo;VEY&7aDAjzS?y5t z$w8@Ir79l|u-G!QmDDKyHH-hdHcnF=|L@lEzt?_?;s8!{Qa^T$&p9;*S{n3Z@%Sfq z;a6dM77r*A;7-4w@5EdF7rDm^qUg~jyWNdH?~{8{?{k-m?`^yiTNJd5e)3G{PWO!pKRN{{#V zb?)!$;&J}IUp&s=&k>LF_w&Vn|2?kw|NrJA{@mX@#n1bjzjz#aykUQSFY$Hu-SOxB z?C0`~H2ucpg~%=lrnv z&v|1pJ+62@|K=l}XBLY;C!WVY`HOX7`TzfE4XFRN1OL6Rkd1$U+|&>dfA`igJ8}8b z3>F8w^~PJ*%2+(l+DeFeTg&4AwnhJ2?nC~kZD!MT`pXYKHx_lw^n>^*`w`#&xBVAm`g7v<2+QqHU0DAA-Akp(_B7d^Cfn0wdzx%dlkI7;Jx#W!$@Vna zo+jJVWP6%yPm}FwvOP_XUNyuN7!af?Yqz@$Ys ziw}-5gqLq4S^VMBQ_yeg!Quf)?r^p88H*>lMZh|Pqb%;WGYe+A3}>;!IvI>^?jVSt z|9nOT+{!!bA;!TCGB~p0B`3z~Y_nnZ=K&zb;di4TuxvkzLqGz1x>&NfVUra!+PJa! z^h;wf_X%fl`ovK%UdUwejZLncWn&489dar(e`;2+c)9$s5V@d~#UYQ?u`n}-#bev; z!0NfNEFLrdJ{lDf7T0Wc#N}Jwuy~wrAVzLAWAQ8Z6fC%@!{SBGh4@>&g5}?RQ#l4| z3}>j#Lr)U<# z2!B}P;>_ZtFImv-^lcVbzN~@3A&XhuW2CBfg=?WWzksiv&|JGrH$)=F?^ZO^9(&hJ zoKL|&?Ar)&0ewJ>efyQc?}I&rpt${jnKIT(1>GghV zg(th^{IC})QXA9nLW}EiesQlltc=q|+s|_T?36+beQ_E0#>x5gcComu&1;;jl=CWE z5Ow5IY}Z%87f-jwnTO-B%}fQq-SQ%KU0;M{yA=G#^E0u9ybfKjEBK(ZRl>_`73o4p z1@GOcBX|WhlUl_p_!>12t;f@wOVw%>eEw2TZthey>HA*Q{NM9)JFT40_85jwum6CO z78Sg^)iKnbQ3~@XRq#`*Uf`%f2@t%wfh;kCAs?|)BCI?vBR7<8_Z zZ%Nm_9iKG<{p~9GMWi~Wo@hC|iZ?#;4Cj4J z!j{Xc_Gc$2E9HDwMLFDw+KadQDEMc3jbJ#nHx|uP@G66wX>awoBg{Oi;PqED z*RCBuT5G^l1z)yMP5a$fffKwH{Isg?Fmcp)FfCQ^NzNsZeCZSn>+yeT@oQBHuRmBF z7ky}iaVJW6MS>ox8p}cBSqUG!!U8+A%Yjl-!Y?>$huKx(bk1-IKX`{XJ`Qq+ttv9! zLMIV9eJfBMBIEtTiZLP06m;gv_%Qu?>^y`A*e~Nh#;8a)m@2s6w`BYjhi1}KS!=jA zPBPwZVRPx2kRuYKXc_*R7@eld5ohLv#9ip_JDNa>t`ICv%%pK6SShM$?=|`Ihp{(oC_D=CrS%l%F`5 z$6A`xt~O=-_0tN$gXW|$u8faOTO)8Zr_dE;yj{`}t@kviXGhEUX_ss{Yns!H2W9+( zq3Y0r=5*Fwe2*TyqB)tQl<^N&TEJbJ6Ev3bjc4s(Da|Q!U^(x-!yC#1-O*uoIp0$^ z5zf$@R_!Y1r-v8Aq*PP9XI{<^+EWiJ2l06GV>$01qoOT2sSuV&l=HJ3Xq%I~Mo?6i z^Y0cm*B(}QM9aH#1^@Vqns#e5TW-(f3O>)S5xNgkhj;5Lc*A3IxSULLI$go9YMTQ} zn$xbA6}&2~mEJi!XyHw-kwACoywe-vvn%*MyRBd|&FM6~Ubd&0!eN?|WOyZibRZ9l zX-+PSD*56Q3NDuBWMWv!UyWbG&7(Q>zE{cH)Etq#p*ag^7TdbN*R^6(5x={+ zI$Ak2Le04%UKjOH^Ryf)UKjDTx)#{jH3wV*ig^E{cDS%19M%^X@om<7TQ`JbHzPYdf4zinh;hedG^b@BOZYZNt?)a|Ngi6lN7S04C(UVMMF~%4 z@OX{pG^(qNf9s|YzSEp4rpfq{)oX>*G^Yo8GXB{wL#;HL)6UZ}{>407E|TWd!b-+h zv`~i~G^e@WWV}?W2YILDI3t&S&KwK4PjgahS<3G;vV-97;b=Rulz*_^8(e5kCl;0R z)3`+NIAVpp50>&3{>9LX=A?J0ly}%(4?lPwSGkn(EuvMlySplco{6RW`A^NX{a36N zP+7{S(7N?(cUbF2?=n8nneJ7zz?K`QUB=I$wQ_5z4hOfD@xm!NoFsa%=W-dpnbztD z&1sY^yguGPsQ2AL9;5G^dv(WxW0oD=?xt>9i~7ch#7}pnzhyFut4zo`)Ek z)9Kaa{1s;f*M;UZ!=#+IUb>buqdDa~E$1JqAC@H3oScR7fB$~O?}fjAOM7B+`49co zF`2eYw`+3wU9ox?LEEKkz4G`W%V`_XJ_nZYd3?kfJM5tdhsteveBw55tPXaEZx{0T z1G5t`Xpa@_dY#87hZf_kEK_*xpU3y1ZGiJ|9;}M<_@lH9NV%-wwztpc`_eYxVZ|D* z*@S%Fk=BjBeMAzwBA<_>Z9vjVTfxLApLe5efaL&nbbpl3KR1@+{5U;ylH~I-?Q-xI z&B-`DpAVLY<5*KWRR5jNTLru0sO{cZIIw` z&B^b20bhGjAzYw2U2`bl{bg%}!8E5aQ3d?g7e}-lXig241-#d3TP}d+^r}lCe{G;T z+@m>VOfBTc#OuLcnp2WqAz!zgwo5c8tFwi?g{d8!p*hX6F67T{_l7w%rw-nQ{Eyj* z@LS&sU2+QfLfzyrDEP8-IT8DTnxS67xUHhJH(pi z)Gef#AA3&0S<#%5%8L2nd26_FG^aD2O8D1!MDmg5v}j_qr0vp*!8yFAjs~P$VaFFcH;k&K##szWiaP4{y zU#OXgSB$J+jC~HD?pKVRznjATh#Wq1TRm#(@UUB+!~4-TAWf>^M)aV6tF#R;-MN+v z*UaT}Xx(1<8%nJ7a`|f71}vFrE6h5R%a_nLV4a#eo_k6E&S|@}SfYm~eRBCb-Ey!U zZ7a14a`_tCF3D+5S*`N;R&nmQg68BjGLP3bvckT!U0S_3k3XU`#a6Ukx^I}r-{>VlZZQw z%BPfQ6)g>^OggwMpLQSvKCRZ4x*W=}_X8qpNY3w0K!8BqPynsC<6imOizNgpNLrlT+?BaVGQEAN9 zf+@%LJ!wuNHVI5=vG2**Q-M}>CNfuRaG3S@S^ih#Txw*!?7qW72UKW`Q zBz_%CeVb;J<@qvcI+zNFWYfgzrBYKcnJvhsvbDQp&R|-#E1MebMJ<7;_F6WHF6yio zm?pYp)8!Z)rU@p^lx&(a-;CV@Q_YWTYH{Qxb1949PrB#O(6tKoGSrnDPRgOANlEM` znA&Z~p|xR!tTxA(FFBJ#KAS4pl>x-(zRIDc$N=ZFWm4;i9Qqd-u=Lwf$@y~*IYPHn zhPz~^TIJGPcNH2pFKO%S)n5LY|pfAX!ePC++ zDubr(HRr3r$o8<@&IWzdiRh@S`3r`DNt-lt4@2_}cJnN+k@TUrjLWh*kN z(#k-V52n6{GVvE^t>jI>6mmb4j8)XxNH8__%A_-HI_zICspMvo<`gs52224BvuMn& zm+TstwhqXmSK12Z0Vdh3EIO~5#2SGqeOne?@h@bPT8c2@8FfRtmI$h*`xujTC1wF;kw!M1-aDL zU55=gnN5YrrNdzQ^dg(qLn}iiQ*bt&!XAjrO`2oRNg_I z|3oe=EKj7S;W~UD{=VNV^(69~W5$R5o6A~iC6VIbOMa^&f;s3W(V#U79un@#P8?67 zjuVskudU{+uSF7l2`S_Y-W#(`{z+uBv67D;Mr=(%68(r#@zlRjChye(fAtr-<+aq7 z2MkLl0o^{g-sN#~K{9p6ellvSl_cApOsU9#qK@kP;LT*3w7(R8?_7uPc2B0FmbrZ3 zTr)l{J(;FeMDX5+Uh{M*=o)=fN9?36xxw*%!eW?%{Habw4ub) zz;xzZ3hljCCN)Pc&3=hmt1}lc zJsy)vIT1RnIhgLPNToY-QE^~eW1LE74!vX*$V!#Rsg$@z!Pc(m1tJE%i!`r~N-W^5>{^jhc9R;;h46kxOlRCQ$Yy zGyWdAlsq+oej2>wmun)J@sx!O--HZ&rE zS|bB?Pbb#DB!NyM1D*wx$v?JBr0LL&8EMO}j!&cy&@KI#fydeviPQ@jpfk=&QahYT z*O39Az%=<`BAFutTD$0QrbwhfWI%i5(yw=kq+f$;Z{*VR#z|zG;L3f$w0A%fbu}{Q z-eBr5JBe=B81q6fY41#;nrX!QgK5FFBy#jGlg@*wtxFQE*rP4Y0+U-(60I>ckQIXI zY-JM78E+-;3Z_9C$+YQLM`i-1t&~isTy)qeFl|_$OtU7NF-tJ@Ka)(W4PUa!U<$KB z%`a83lVExfoJ?=WC$W#nr3oLBsSz?@AefH+lR|_HI1i@%BU9)qGQiibOk&z8G#9!V z?b4RA4x~^4bj!MAAhW%jLh8sR(zKE#1_YW!dF zKq-5DCz}45ZN_D-a+x8IrU?gL@|dp?tW9P#C9YEN5s|Je=Vvs1rX+r6yE!}4BZg{% z3wiVhW9I)~41L>B$;(C(^V$+azR0EC56a{xFUC+bbUWBhTi(w$hWw#ht9V0?ipUt6 zp}fvrZzbLP5<}aqe{%J9>O8q^EVVgM%IAmZ@YwOO^bLQ<{UDfbuZpFUUnBS z9NpH?mXg3Ue|{VpzcrNkf~l)v9Ie=BB_}W`uEtS|_Udc~m};HkXnd#+%RnxDPl}^= zv(1<@n7pdv=+}XlY&4iQbc-jG)e3eLOd}`8)5!@*ENq)OPgn=fh7__^U}|?do)&Mc zWF1BjZ}~EwvT*-B^G=x*8x~I)(9OAnwzR)Eo_wI&`%**Mw0{$5G;(Q{o|U|CL<04O zR<&Rnurz^QVGrpMro(z2OrYJ^Ll(|4WBCsf=pFWub@-d%7rgNJ2v?Q>CY`JV(%WXv z!ogHin?NH9jF}UdwE84c|KY@rgK6B%L|S>POkND8@7oh8wvD#@Etno%PNc=EyF9$X zw9_u}Z~Z9uwfb5z)rmw6cjQT^bz|d5TI{65Rg6p7z9*416}dE{LoSp1N78QOlFH8r zmYE+(U62855?z^1<0u-249G_=EgBd_yO9Blei^eXbE7Ciw~{B#Aa;IN6zxC;Tn;Xi z&%YT(1ln_jSTWj4(yNN1Fl4}PFg@!MO~uH7=U{p` zDVj!f$mQF>w0=`GM${0*RP2*`J_7Dd!H5wXEsn|nm!1QY&>OZhdegsVZM)A~izqb58FzMfkC({E4 z9z|f%bdUdAKgxZrzLsjELTJ~&I2U|_>$$QJO83V-)4@{KykjVBooU9YbuNpNhf=`4 zm%L$R1lzkNl+0Et_@yXUHsx3-MQJ7RK0D1>{^L+;ja-ry8?(NCp)?)2bZacJ?(akC zyfOox;y$xk7`a2Y=R>vSXNQJS7<3D|W9YGLei#`b10r>-r0<4d^c@+nrjno^OU3hi!}Zesm;6CZ7>$c^% zx>p40QWDbz)41#iIvZTbOg|d)eQJ^PXhS6n98KJyepB!B4ExgWA} zXCwtdH#ZkUndRk3T8Uh`vBpY1+dh(VGlV4CP_DnsKnH3|_urh3|4#(^Bqh_3IDGLA3ivM_z(j&#Vrj zH;y{IA95+VdoX>SXvPmBm(2eQrh&)+E#%Uq&B2tuM8PePORdfZQ^mL>K4zaeb9xy} zlaT=`wZ^P8ESO#)1MbWuR`fZT)*%CWg_goYFx_W!Su^JgmxeUnjn|_--ghzpAlRRCjCaCbR8M+ z0Ziljhf?o-=3E82lr}Sz(vVAYz|?6+C>hKoZV#rmS3@Z>q)gfXrX;6O;>OyNCYX*S zhLZDY1DTR(&bLtdHPTA138rH8F!KM=k-Y=cP^~bkcGO|*z|?PD7-=8_)`O|&R2a=h z2J{5e70WQHT%us7z_d0fj9MZC+JH&5FpQQV16;r~xkWg+BLk*`Nj@T+^pF9E!SriM zILV+}8!$cFAFh0Vw3e(jknOn>PUDbEOGa7AJ9vasCbaqlrlslO)Erv%Mpn+R4X0($ zYABf6^ogK$&}tQ!+@?p+UTD=Axn#N}f@+aV8ekfDK7y`b4_OB${WlTR6?KxXKU!n-k`JzmVDagGv`9z6)1qD3vl>6*EQvohFlRHm z`_u5CLT+4Q%uJ{F)5G=C8xv?hmFT*h3o3#J%PHU|N7ZWE+^~h+xXa9-_5U!8&IK(`oD> z=fULlE0|h-HfBj+s_7L%hsF`>j9mIQJ%mm_#~ueJzAc0{jMSDpf@$rg5XwAf=n)R4 zVYVTE>qoh-)z{M86$(m52IQdDCm&HzQ(T+0My<;qE2tYXKo_(BBO zO5gF*sP(;#e5pAypgnS_!vJ4ej0{kq*0tyOk~1B4WI!7*_1ox2 z1Carf!4!7Jk1itviotZ>(vNx|1JuAo!G4tbCzp(i{Ae#Szz$6N{`IGKe{xAa+MjCw z_>-vG)(F5Lx_VtN2ok4s`hz@(=iK+})`)>vp;alE%$fwzKiESifGKov5WRv{FTmu#Ac&S= z577nFxxGP@g*`;cH1u{5#V$AS_>5Zm;TrU}ew6!KeJzDYdeXfn>bw`u<>N{`X^EE( zKZkx{M0-ISrkU}s=oem-32L$TCB73lf{k4*Xy6J3Z-;(igQJ2x+o_HFM8W1mwSWBBgKopS4Hr3U|RFTi-KZY z`5rJ0>FQ0^hUUBqOwkj(DWuGpUjfs<8@%ZZBi`#4|SPt#$JIb z=a3IM@5Q+{n9i8{kmm{oI|Qbs!iQumi7f$BWu_1LqmSAcOygAHP2`fRocM@-3X&;v z$)-#ypQWH%&`te6ZRzd~1;sai~G1BFqO%@$QsuspTP7{*Ne6wmqvog;UqkQ z4EP8p?H67&6xSwmz|<$ui!^aGN41y87pOX{fai4MHvnF!hh} zp=H=ZHiN0C)Q7&|dPxqZtL+uka;<@f@)~aKIK|)kQSNK?wKQtJE8W1%$t~p4nBA^q zi207;IF}!G%axj8zM~YmRO;?ZNtij2qhEMC&6PS~zGF1{g`0o4QaJjkv(YbX+Rcsb zqK~=~Gbb}AyU`Bh(h|&^Own_r64X+fYni;!c{kb*-E@~}%U@f&)y%g?(`A! z9c#dJ$=sc)FyGM_xir$tonB$SBN$A(a@^@QW=^hxX=_6dT8f#I8ZZqT=s|NZb8-Ys zv2#4=A5}wH8tU6(hX;Mc%t<7erd{@+_L%Qj1*X#u9+ZullXT?L(F6~2!F!S@@p?7YJv=i za4M6Qg-B!q-Ns|)QKdH3|BE|@t< z29w7$PnwRIlXhS_y492VVCLiun0lId(h-f{Gbbf)Jpa~@a$l>jrGJ(?(;@V}mZR32 z9CoGy=zYyat*btACVQMQZ$>T!DzL^G^AGfRw!L$vq3C@P&Mf2&U8nzb}TxmNp;1kZh2TpLMOE_cR1*T8yU1=~f-~gDeopz-? zIAg9xF0FszO1U^={(xL+5adb&aK?pBM*G}o-Jf%B^*e5~0%y!8!L&?rqYcV4W-u+xbfXbCV|D>kJ5_g@ zfHUTmVDjkWPQl0kD=?j#=1yM7fNsd8!CTzvEpq7%n6_PTr|vjo9yFc!Mq76}gAAa6 zGHF1pJI#P@A$zr@@N#!$UqEZ(aRb?d_8!z5xg;BBC7(FngYH7BAe=89UFkuupj9%? zmku2Bpmb>U1-ZnYdeC|7Aq~Kk?T?>BtJ`3*%k!XB$ffIGTHIKok=R4L!E|kqMD93W zY5=AS^CjAV^Ce?2E!ZPb$3N#wWj7`2wEy?{lAnw8w|IegI0N9Y7yg1OQBUTm>N|$ zQ!i-c38pZ07c#;gaurO5%!T%24@m>lgw^mh_K;g(%022rYM43M4yGO!F4Pn=C$qq$ z5#T~AFmsX*rpy8t+Nh%~-wmdd&0Ps!FzAs9ro}^C|JILkU#qXBoryMdAG&3OZ)cSa z89=wE;M?5QmRdr$OW+$k*_H}WOFzLEwb7Qepj%he(xcP1qypX6qn4&v+R_KqQYLE2 zB*d29qLzB1mJWZiB|qr)5w$d-wH}kD;GiDde7CF*#=ynFP z3nPpi2{Q{?u9#i;b<+{|*J@fbF}v{0)sf`Lr3si_$VqXe-pHk4U`nfTq|wMFH84Hy z>7<;aV3?y||4ntGYG}0`Ol|d?Xbtv|*nU1|+Dvod>N6d6! zwnNLQ#ECpG)3F##%iB5AkNXB5nC;N&H`e)Y{V4af!#f)@-P&4y-0BU@oWF|cbuZ<8 z6W-8?f}1SrSUTUKYD04?U75-l1wS;@hI;43vC^_9{LFG2I(fN>-I~0gPdsfyreQx= zi#~n$4+k4k{j8=nzxuuulW9ZJqJ~;e{5#21n%Yw5Ug&XOSIDzR+mgk#Dz+hQ9BaGY zmIlS-vx#$0GsR`pUU~$pxc!o;a9gU%v}4Wef|$oUTXJ}5#x5r0u@-bEx1NptT)l9jrU3{2tI`W}z-TKB;E}q5Kt=ly5 z<2emnem|ynCXX?^Ubnv9zl`^?UsktPOvD`EL$$i~!rTU)Z~aHemCyNSEh*Q39>bOE zKmTpry7u>T)~)}%R^9p!!|%uZW~*EOVXj;M&+j5)o@cVL*4LCj7f+3R+3aU7b?f#f zPgtC0eBJu)jXg~Nee%CKk$Y(57n(5Zv5cG zj`XctcdWszNW~rHdm={8Z0Ol;{ZW~69crQKxvxv2@_iFy*f&0P;D1cHc1+LZXKOCh ztxxy{@swb@y7d8W$>-=s)vc$Sn((;rg1Yt9${~F9;yO)*(+5Ac`Cn)LEcT7qJm)z( zI4_1T{qaW3>2r(~?k(ij18l_G??c$vMb&)FG8=I@$3}kYs+woBQ#RtbbI);F%Nu&G zv#}Am6Ktfc8)}|TNj9RwdI&$Uwwj-9U@Lm29py1+3wf(iwxY-2=iFyAet%tCF*nMO zj~nXDJD;-^Loa9YtcYuzobZ?%WxP6IDL2Tr6)(1{cn%J(l@kB46M4lAJU_JTFWr*a ziTPO#JQGw$%R6ke6RAwavs;=PE4pka!pd>pd22aa>1ijLxM%P~ZErA>LOXFa+?Riu z>cY;ovlpAcKjmMR#Io5F>_z#2BfQ^~56oqoy-@cb$fGi<*`&MnqP}K={r_+Mi93ov zSyA^MPFuBtQ#0AfUvGrfStr(Ni$5#F`}R+D6g&Iv1(Pqb5qDhQ zvpsGnnX0jk$aq%8ZX6iLTD-Io!&TI@#{Lr|e;Q{a3T8IcDqe6v*15(;G@sZ&>%ZJ{ z(xtw(Vx{Fz)^nUXKflmc_^W?rSH|jdb7NakvN?r)(7VU~d1)(x?s~Bfb{KgjZQ#R(|{kAGF9$G_8FuU*M(YxyRT}>`xJHouT7` z7kF>0UQ0ob)jVfL+6mS40o((h3wlyzC-lM&@c#XaxJzGq(LnbJKesrZ$1JoL^PhP0 zCXe0umP7VJcUmg%JK!$2e`+uO@%zj_?$P7JBJD-H_P_X~8SQcYWiKWyZ{XRt;G{I5 zuY*X%=dlRAAampwNu@?yv=iFeJG}GJ^Ac0Rwd8NIyQ9p0+(w}Q`5S3+=jO2TgU<@G}MZJWehcgyQln2pZN2cKACd;=d*sw&-95u zp8-^Uc2E5IY+&8`&u0ef)_*=rShxQ38N<5upU)oFt?S=UE#ERhixXXt6g4`Vr4mAD4=m5%^x;LmupEP^oY|mBO0PJ!bW#RAl!0%!-@qv!9*I zM2{Cg+42eMtb9h9Xi5#V)O63w6Zez}3D*VZ2JG?}@t{l$ZHj9Z&j9Iyf0@V#tzwfb z#&VS}Wg`47uBFc!^SqA#$NXUOCo#WUfabTQ4YgM9{3JHa^O4^ksHS!C-Y2oTLX+Jd zR>j5#e-bt)OY1c2UMoz9|+Pam`SDMj;=WRxFO=b%GT>yI=h*_MV7hFRxhgn_i!VzOOy2$P46dg`dTp17@s2c@7Wl@I^eW zoyP9H{>me#eG$(NrpenKQ}whn`XY9Bc_jNVv7zT0i!Y-0bTcV#L<3K!@GqjdTX#Os zq=u(_|047pjrgvwMZDFZ5;0HDf>&OM;}ceth}q|TdH+i;{K2Ub(RWiO*Jyd2lYNQU zr%}#dX)op)StY{4U&YgQd4<%oWvTeyp`mA&Rcg{iRw}Y@Ht_sxyivY(bE#;&{TJ_8 z(T0t@St`a<6!X|1eYVlBRNUQ<&qH-JXUQd{qH>(XTeS0Hx4M>zRu}GYRi{)YWZ%QX{jfm&L%KZ+fFXvvL(K8Xn~_UuIoK8s%ZNzBzZW5;T8 zxKsCHQIk21EqD0J-RBpJX`|BQpO340-bF2KS9>U{-r7j#+VXA0EP+CdWE(8G%v_bU-YkKEz&u(Mk( zE)hYSb-D4j61MO}iO4vl!6z*E$;>TF{%WVpjd~rceDcLq%K*)CyuXT%`Qn?lk9-sS z_(lD_FsagHF+;1E`Hc7C=4n$FbuN#2?SC)&K7{{t!Wcb&FFFhgV_^yKXViOPwIPp1 z2AHzIAMeGMwpA?htc<-MTp(`4kJ?8S^4lv5#7VpkD@)Q0HO0^2M|W*Y$=I<#%-deg zT5lP`i?XqfDPT?aoA9o!3Pn4UD7NOBC9kAH5$t2nw!9DIUA7hqr+sE@L`4oCe!EZ{ z`Z0|eT7TvEyomU0m?mEUKej6`6joIaW##arZ;ub+{d_aY7JgKp`#~(_-T9N_HGIP1 z4`QRM5#Lf##P_}WAX;y+;7`uS@n=aNMDPV)e)*ycuT?D)YxOcYYjK@F9bP0>b}r{9 z7A@w-b&JGX`0?ZX3d!_Rk!TJbO=hV{&!r-vfFB=U-YECWD-v6_{o=c;+OXSgKZ>#C z#k?R)p9N3(C}!+S;={X}Gur)8Y#uA|TkXBrcXK@E+#Np0IhFMa`6%9<(&a%LOIX;q zkK*WE4Ss+2Pu8*Pr@z`Mv$S4E+mLr+PJD=F8s6WR74O9Hdp`0c_%XR>o@k>XW5NBa z*qMcS!t{nIYYRVG9?uhfUR$%$`C+V&O`d2yHjIS_TeH#0d1B}GJQn9_%Iq5E3*$~z zto;@liyo6N2EdOiWD5DQjrrmsUdNHgX*yiV7h3RR$vsPH6VDeGdev<7xgk8hFkhqx z7clFaCcIIn_hP}mC>Hw2l4nnUFMc`MGoR8xuD0jBNZxG5^nT`W^~di;P}(&11Agoh z`Cga~PLp>rQT6;}d=Q&I7W1z~`pjX@2T`^y ziSHkZS$EV@hk+7*-qVZay!arj4&C9ayi!^7*bid$MqNH_dkJ%{{UE07*WjV>qe{P` zzuGCYv|h*Mld{FEv4NT;cz^rt$QG5lKJwx4qxRiwkx-+_8o-Y#LD}M}sVTEMo5y;8 z%@!GtteMe@FlNy^N1PuV#@fYOGl%&(B5GqEOYk#ggN<{<=yp}?#3>n@Yn>xP;m7Sp z3VC%(jxfdRsBBKs9Ns8bY=s{m>sm@VBXh;oZPjeU_91-Xx?C|Px_~t}Y{E}o$rX0T zqL{`FOTI?rik{x~EUO@pn-t`VkiBMX-Pas`v;A8!wQ?Gp@#ZVPJN2#Tza>q60e(ER z_pPu_d?@<`KlXp}RyZy^;D;aU!@*AJ8^q+CSTj^I&WA1fbkln>C$6QNswap#>ok~d#AU_&U6ei>>YFEi?M>npJrYxXNsw70fq z{o%)RL$X9B{FoAC&F(DE5^Z+mF%K8`_Dq)e3_rf!Bx7Tov&3}xapo9>JU2H>JjUxt z+u}6a|C=p(!H?>XEu~<2wipdRx?dQ=HMeGqaqweYlMYjcIs9baB~)P>Kv zm@6XT$GJbQ@y~9#q8xr4IBYQw&(9U=K`NeG8&pVfsHMly(ZWep`ZDFM@PZ#l_T40J zW$;$ChaXROYs=m}cq@2OF?T7}XYEl-|H6;$t@wYTi7PCgkvA>K04P z2&Reft+-w_9Kv0)(nRa10@nAK34h-*U1%MRVud#?xvy5b*edLq-iJV*w&2;guY#Qrt^Oe{5r3*FPG=zRVCWw^{JFrg3~{VupymnIe5lCO2quo$nZy zDF${e=bdIP=CjshimmYD1gel0nq`V%(6MnpHGJ|YQ=En$2Rm+*UwW4*`oWJwRNJz3 zZL)-BX)$jfug|Ve&Jvb;l6XunbJl1V>U@;MU#NRAzXw_3%;`Hk*)^4Y49XI(kLdC@ zdL``E*DR5IMT38UA9Fir|J6>JrS&@Q3QiK27KCah|T$HzUAMSfQq zYXd*dU63s1-ZEv);75aF$-)tSw3rvhima1`-ncL(gCDCClf`lP@u#yX+utBXXlYcj z78_;k&gc}e5`N4cp^#78kRmMbI@P1&G!I@*5v}0IdrvK;AySHXzp0w-HXFhp6r>3M zpaN!b*Mvu+mJ0Spu?tTu`O9gkVv(agn@}Fe!*->LtW9R@5&W3-FjeR$O=IcsCW%NkHsg_M7LBU-V1*0hg!;n zA8#Fv<4aIW{qFj5P59BSS-RM`E0b@nzQ&h~PZt|{m-C@R7V{CC(}gDdIJ~x88hoX5DgDf@ajUSz z5Z2tDl@tZ?+3yoXfT0=7sLbKI?GnYF&(m0Q+pm1%e~H3` zmp?Rh;loZOiGf=)`JP7Cd8|#6=-jQGJ5OEAZPSy49sKxnbcN*7JXuVJj(ggwNpYIV zViWur>Az84x-nTC)BnX4joPxnYsq3rNikoStk1srB#UXglepB!obC9WEG$Mye2Rt_ z8_+pL+&FoMk8n?Ai)N&VB?sWg%_Z#nz7#R@q6U93_a~e2Amy)i$}FwdF?L3bShVi9 zA7l5%h=WgkWNX)~|}$MaGD0@MF%gJQh-4p+!u<;2$c@p$Jr&GdibL=*UN)N@Pe ziY!j}!;cd#4dFkx#EHxBquxCeJ`%NL0YAQlADg3=zB|~ni}2&HFLB}k{Fn(p{?|2L z98H9dPG9+qx$$C2k2JYH{Mi3Uyue>Aku8Rf@mBF-)?+hi1^hTTE?zk1cISrh<6@Nr z(Jjr0XBQRm^Qfgo2P`m@oTj%_k92OmEUnjZk5{;8Q5>Y151(j%2p7JGedHJ6$I~4mgsi!YogY-iMofzkPG+X8_31pe z*eF7bdXD{ZNf?W^h!9OjgfT^=HOmf<5SzE;F=t`QR(+2U_8qEN&;2rHJTOui!jCUk zDCC1yM2c&89UGejP2JOxA{{zzKWr(rvX2y#^{ZLt!6E#3W~2zjnf*bW-8=phB^Dfx zVwdk)ax)esN<8e@p-+L_ZgZ6I-)Y7=f6w85H=;z7qG_xcehl`F636DG$)~}OFH54t z4E=|)?$A-YTeLW|*Gy^yKfak2Ek;Ci=P|}LJoZ4e_!Vfx)k}(aGplH!XJEmbosQ$< z6QaeptG@i>X%~K@Hd^f4mdOt^xX#B9jS(%nm-9uF7W1~NV?+h~s2EfsX55eZv<@#W3ivcaumMUOAV+$LS0t)3Jsat)LC^M2+m#voRF zA13jv&R*=&{aEqD1lOw`smwJnR#fiML`@Mum&D@MAOVkImPI*ZDEMPn_n2OW~q9bbS5HQYv*1 z7m@H|1Nd?M`*869ejE!w-aswc!H+TUqrub&(FFVBarp77VT3phKPJMDFU%vvb@;I{ z{P;R7LKwo2Tj0kFsHM4o{5ZaUq?r51kCzrl3JyOSz>m%*kzy$Pm<~UFw2Kt0;K#A> zV<*(oE%;FZKkjQ9C4Aw>WcabuxG3=&e#{uOn19_ACFaAA3*g5Z)RK*Ie|(`TX(*z^ zbNI3Em`!r|$0%_Tew^N`Eo-R}Ez;n}`K9`7B5ElIeq0PcI-!yXM(1$TClK#j`L4hO8bTf zi_=@G+3=%7_`5a1;!Riq+ke4?cf1rV3JylG`S&e(i4-iRyW6w!;y~UmKUl=!D=?6TmmPR4QbrJ>^ZbzeU7lnbvs9xB|nXW|~^IyZk4 zDk|Z}7Fvt>!L(2z$2owaXN7dUS(wm+jv>XWlKJ>B(FcBfRJc*@xgku9gdb!6ZOg7+ z4HFuli+OgoK2vyyiL(Yt{L}z*Hm*2KtQjhCqpn`8v{SfnKX!+wNvW*!^l;&1pvzzB zm#_e%a53(r2Cs%6Ti*}=tDQ1S>vg<0-CtPr`F;O*XOF*##Qmci_Q#+{{=ysgkF(%M zqX_)`rYTzrKi>M`FXqCJmGEQRK>?yY{CF3B?4=zbroxXKT};`dlL4Xw{1}hxRd0s? zu?T+D8Ksc#%nlGwpkva^IL#+50!0VtXlP+6E!9LV!H?w^hj72mfg%fjoQUhy3e-{q z+&^xCAEW&O#di3yKm1r$94IQ_$E)yT<1RtsG_F^ZaJ|}MP7uypeqXPCL@j0c{=Qzl zXBi|6aJ{+?I(~@>5=ppTy$(NitPK)taJ||F*Q@hUODgc=VfgU~YH1Gq*c#WXN#}ya zS@>}ju2+w^1Pc@R(E|J9ig&?c3jCP!vs_w>T6zr~yS`MFj3(yrPV+YhyEc}>`{V}#zsQ3gw68u;_KU54@qsyJ( z#}`LK#S8c`41O$q8v0i|WtP_KI9zxOzp7x(Y`nkS3cZE(MIZS9_;G%FAF-jWj5UNG zzyIeW_FOe(*(dT?m%Tn>pOrNmyC{s^f8ry;MuoAXVb<(bn2)%>HIIGqFlBwKe8hO1 zljrZ0v1tPoA|8G;o1u`GFH?xSc%86^@tXZlDa0A*`0%2olxnLGaX2TJofyJrWhlh+ z&;mB*vI#%Z!WVswC|3Hwk}s3{3RhQqw&F`5Kcwd?RJNHh!yh^P(sf_qn>&r&w*Shn zD}2Qud74~;ANPFm6}7z{%ErKt-MjjUFQ?6{?$&IrS&@g3=m@UhY-zFyuXztLiBs!BaeU|2X^xkzi_^44nHQ$^%AP^V;KDS z?TD9ni1Sr5oagL&&|mz$Ky0r&Adf_=-A|urR3`7EvDi;XA#bG`sRC!Svb$}zHP#nqn0kfk3Klh z8HHMEg7X}6oabm8_=wjy&*=d_Zhhb*{>6FDIrz~a)JI(FnCnYo+UP5Wz>iTX6_NtA^a475u~C&Wy?uof{J47XCi%|~z9I#F z?1%fuSam<44L`2H{bK{vk_r5H0QZjvQA-PP|F|B09P<=E$Ngh6?jP4g`iY&mf7FK` z8`t=WZ@7QF13xb9<^NYZWtP_Kcv;IsT;1`zZ*@}NLlj^4k=H;+$D1A^uY-)~qHnd< z&qMr+zEv^K$xoDehz#_t8ZHcDzq(7}$7r0dqHoo5jwG(2Z#5r%tMdmXkpn+!qi^-v zN)om3W7kOv`HDoTu5Wd^f4t^JRW8;-$Ij?mO&rF>X!tSf^bl^lnhRI-t!|-jm3@(m z&FEVhpl`)JxR`^!)qV7>GTw2q3Vo}6=v$Sx_7vT+rm;mhC;vLhQ=CKJ>J$8!WaugO zH2B@OI%V!DtkAczf{v*{p5hexRyl`jxXM>gaSVN{F6din_7&nV`c{L`x6)f8#5DA+ z7NBqCdrXMhoteBP`c`_@LOey^Y99JlQ&NR+g&((|Z#Ao_mpB6*)6uuuJkG1GZzY;- zlAEsg5)I+U>W*#M$}3)ip>Jh|zSTu9FVPZxtIz0L{rc!7^wGD{LEnn2dyDbtTTMsb zDsQT{$VA_2Kl)ae_j-$R^sN}q$JrS&>)oaQE^Cn1{Y@Z-weZsOu?A9(?E zyztOXgsRI}1L!zD+)dO%$Mw)rr`k<;y|QLA(0@!C;4XsEf9xG%&GMJH3oZDupBo-` z!dT4Eh~s^*lr@ z{1}OThX-nDJo+64=y%-k^$_v!V?O#FuAe+`c5TKk|IFcG8j@&(en$`ZF?yCHya%Sq z2f&Z^s3rAmbJY5jl=y}^rIu0G3q9rjmvpeqz9aDeeF-bO|C%I{dg2{f-A`xiG`|ssqkfCpvQxhV#`AIA87ZmW!6~qgTTUsdpPs@en$Oxu{B$ zCVC15{CKwaCi%K;o}xR>SG91yI_9pY@P{9-;(S#PwbUBtt2Q`aO|9@0Kj24qoUh*M zDa34?ug--Zz2^xr4Ckx0IA7grEJXMo4ZaY5bhQwFwNqwky^hKmp{o(U`&RGYJBqgG zTctq9j_sU8Rwo&YL9Y5uaS{gTTlIvFdAps&zsOZJ=(zE*lct_CUv((DC2?&Y~}L^g-WBXgk;G*vU6e^UDe6Ivp=S$7eRq$jNG^0v+3=JBtG7 zcnmsDYwjY}LPuBV*j?r#+Bn-Yd+0c2lZ*HS9alidW!GH9H|SUfKd$m|5e4X5X+THz z*+sl9{N1-I=73Dx%Q0S_2*R_PL7d=vysB-|FFWSCNdqRS)#7LStRU zPV}u>A9vyXe!7YZ^pWqPZxuSoO=v^M79$sPD;+oS0e&<^-^%u!o45fTf1qy_>f$Ei zprgC`Ci#bKH(?4L4bivqYUwU^p>GwAzSS3U7q!rFBl=dGcDRdv=v&=H->S!5cj1A) z)qM1=X8F5|Gw54sLC3OEcd-+FD}VTLqB?T&&*#>aSz5nV&V5DB3en7jANd!1(czkp zya}#zK6Y^sLy)T{;K#dj97Nn-gLscz9gkdnH{4OEK}S=}16hYQZ7aYY3_;J%sOX-lSqiBU(eT{j5 zf_IMM0CM%S$^gHsQwk{Nv--#5d074P;Q3ko^W&dd^{io4NY)Jay|o&tJFx^SW9}&ObbL>pz@zYvuDPU+?$tbz1p*)&E@i z`_?~R`99RG|GYnS>p$;X-CFtkDPK?dJj&l&`FhH=^8HZ0o^q{xpX&MlcV?`5fR(&y zvqp8#<8)T$9u(WOZhdKrixfDpS=~DC=16Whv~k_~b-Pns`&(_@a~|6Cn)_`ju3NvK z5y{{DOsHEY4^sZ^efPR`9_DGk8Q!j2cRt?AGuCQd-Fn`4b~2JVL{Muh;pT%e_bbe$1~{y_mz|CUuYbx?mT(?ps~=oRj9`?*#YG zty@n#$XUOkes$}c;oUs{AA5HhR9Du$i$3md#NFM)8jOTM+>LaIy9bCHG2(%^kp$ui zBtUT4YwY0e?(S|I**ik#%r!gxR{uYoFZaE-&aG4Zp{r)?qRB(%Tmkl4zwuZ<8_usO zEupu(DzhzrJuszbZpU=bjch1|tbKd@&IdA{YFa39Z>3=i7^xwJM z|IX$9Z{~9U+c)uV-^72@H}P+e(!V`Q|4on5zx{y!_5=Pm{eb`W#uon{?T!6s-?8Ua zV$a$60J|3>b!EZ~Hit@DxAQlE*ACzLI^S^+d|cd8LwbGa!k5C#F&+3i@>RK;TR>;N zZac(Xy#DR4b?Y|MXm|EsAG6`XRoY_1?~7s9BX$p{6Tkn3wvN&CenBDs{J-xR@wLvF z*79aMUPA7{8eA0DRW7sG26j(tFnB?4`MZoZ(D1beZC>`14>4LMlx5f8q}+b;m1jDL z-<#E9Mc+R1RtxIIyQ6ARTfMuyr`{@ZSW%1Xm$j1*D}6uazq z(0EPe1s{bB#Y+e4-C; z>+!&)P8u18mq-;@kN!h?YCL=}mW(Ru@qv9`jsD42V()HB)Ed%XqpMIn-D!prt?u>J z@Bl|)&qgJV&Q{a7Ie8*b zmUs4moY~%deLgA`Zn0zc0YzO!2yUw2*BQNvh!K1i=S&up#nJ>(W&Z?|MUy!UPS`khNP zyvhmWYeO4b7~R@|I!9RHrxk%v?e&{0_DR9V(;8)?E8)t%R^VL3?)?R3L$jwV!K;f6 zdbN#&l%QL%A8jzy&kgoIvIN{^gQ{odaDSRNyf&8RrJRN9$qBI1iOq$ZGYxJ$FN9@m z23OwAL}7cV0(!Olf?{?P!G}4HnG?RChvNvbPqY$lto?!?Q;Nmw@@i0=|AP5#XOTvH zJ|tUy!KEvW=;q-#@Q(h1pGLo-C~Xgz^!*EtPavuv_5lnBvRQCu(PWTv4a^qW;yYO` zCDbl}T}N$^4ph;(w|@#d%x!VTDkWK4tP*dAkDJ-#v?H$&#AA}b?%tkpCV z9$VIt-zR(2?a~tlg_cq07<=5kVJl?J$e@uw?J@G?eHd^ggiMAxp!J3?&`8ITB9}U# z!MFhM(0)qy*qk?6atb&tI7A=K9avXU36$jxBUyk0HXN#j;kIt#!YT(`d`|^K&R>@m zs5xR}6D6pb?-h2>azv$VC2Wv41I@jT*z{2j^ys||=09*mBef_PG36#SkRxtyCc=`* z7Eqbvi1F=SL40#BnAh5g^?sg*7CG^dKFJCFW7VN~egVX6bi&fw459rt1$@5dgc^aJ zgCT~eSh3O> zL+BL^KIsW5r=79*xkxijKEl}7&Zze|ij0rlfN_D&=w6*eh9{OlNtH9^l~&T2Mopoj zw+njpRg(9UZG!t87hHcsMY1E0Ws?uMu=$O(w0MGC%zEI0H6u%Cqv;4bC3nG&hf)aB z^yp^33%2~=PfL|g>2U{F3?v)Mt8k+Ml+D*|7mFaYqlmf#qhX-gb+{*pDAOX)jrag>wu|`l{A;j`^?-^SB96Fy z2@V&=!9jZw$8JaXb8G>uOA#?k{5@sF?)YVl(TH3(mEt4=C)ym){*@A`@t0t3k9$F)Omi1|;NWaucrfcZMIH9Qi%pWD_}ftupL?L%$YS`?a~%2kdf;Zq8W`~? zKs;LRf$jFG;Ci;VY-M*(ymn9t9X%Eawi=#z$fgRiWZ#89c6p-dz&v=xno# z1|l1=XCGyr7v6msDI2OK*_hMzsnsDk!KBVb- z;h}(XVabJR2)gWr$DU6RrpuL}W$lH&4Rx|Sfq7Rp%iZdEtVm62*z9yKT(@-!xhe}` z-wDD;&v==gb~2}Q{if-$R!WKK~z22UDSrWa7kcz<4+Vx5WWCG}yR}*iF<-Oj>nT5+6K(}gU26i=#5Sz1}k@hQ?eS4KDYx>w9 zcf3$SR1^qniFJz%s|L5VH9~HVKTgYGvymQYLqfX%95E^uVAmCJm>z)FT)slnKi@(F z>lSIR`wqJA`wDZf1z=9d6&P9^1Gl~eu$jYi;J9NRY-imHcgEBSnJuefZDZC0a&4BN zc25ZuI9Xb>XdN5Z<&=QK3-bwxu8lBj?o7>8KB)Mf+e}+NzA6$@@~<8Ns-yPdbfa zQ)32i55^-cf+jYHEwH1R~&+|bj@Q*d=p5Al7ew`-CoLSlt!-_hoH0e zAPSmWN={=!(0HJ&=$BSY+JtL@aKqzX~Tf*rBZsf2a6dxOVL(&9u>Zu=!X8jYP#Ow@3 zvECm$W=oH1Po+q&P%JJ|K>m?<(X=EKPfTV%o9$?jIduuc7yhi{EPssfr+OF;G^>WX z%2MIT_AuP|CLi+KXu?L5Fzh@k4i5Mm!EBc>EGl&en+I>;Q+gPddA$eU@p4c!4adSg z*Wg@!H1rx9jwS1X+LQ7#i!ZB@d9PvJQA63LwORG^3m z$Ij#@t_!JwAl7NMbm~~zxVjjQ4UE9LVMobfCi5?gBXD`vGx|E(5A=^k;Qfcrl-|@D z8oh`>)AeC=-|G%s@{Yhh&Y84p-Fj$T8iA3aliNlB2)6y|_h1s(rG1Wmu z+D#9;_1ztblOEQQxc;R$`!;+1O&NXe*^3^!L}J3Xbb7LK8(C#WV#c5ldYyltTDFeD z{z?aGPG3lCViX=tctV>m22h)IQK-H4ApPu}O2aQjp-iwaFz$yyoJ#i5`T(2en z*eD#o=$y>zk%~6_h{CQ>2ZaJfJ!K4v#y|X;!$9Lo@?0E^JG(E3Z|id?=y)`me7p%K z!Xn9#buU&uu>e~u8SM&)#@noK@XUvo!|R<%=r|BXDMQC18#+gJc^E^0tl z>sV9_i-&zfFG0kVSS%Xg36BTAhSi&5@z3EOVQ`HIZ!gE7PyN~N7lmT6LHww zY$WM?FNSZg;xIW}pZbnYf!4us*lwpOnXK}Mj*2+cUE)L$8*G4j#$(W&P>Nc14|>jy z$3Zw}~cgNnriUp;Wx#9=*MhfahjAQLjBV)L@%{yZ$hx z*&F@ob9@4xbkL`)NhxIiX98Y6H7hze&V)J(>Wut)j)ji8$DFF&rI|OUr5!acqYhFd!j{+V@Ms;K?81QxUVZ z^OCUrXiwPL<2CI$n1tHnB-p6Pyws^r3?4BB;%Mag>a*K2JF6>jD72|dUXm;{@5H&->ro2 ztiSu&s)IssZ9SxXOu=267i41|sbF&$>+_9s5eHtWg_@caT>on*iEOUp#eS*if8-$P zbWMea3sP}H?i2Dn5dgNVv%75*M~b!m0w+yVaq<}UvvAUVaPUaQp^Y=>^OS9@<1-Z# zKbBGax1KPf3+teNTt`=WzZ6buq_G*@DzclrZ-&{9G)x~-Pqz--6;Izv!_I-_6d2Z- z-Z`dW^Dmin=lFVZOH0F}E5pb={0^zNNXGy+8%C?6HMxyT$FH%^=*Cp``%s^j7{wmh-UA;`OVZA3K24vv1 zu%CkEttv`bkby4U7r?pVT#7l8fftUm*$-*a^x7-~qr%?9rlE2Q@Xf%%_3rTK+8gRv zl7WVk;^32;5u0zDiBB!^p`vUSZNW^ec~uPy97@FndoocKpoFYFV?^<8CLWu_ekR}Y zr+PD&Ogx^ifDrq5VNiM|hWi(S-L|Pv(jp5l^+<$Nw=+;QF$Ea43+q<3hLx==;p&epjL|wPG^Khl9GZ<0 zN^RNQH!A3{BpdCw+KP3_wP1WS8@Fs9MAtP-p*ic9kLbLQR)0%{J^|V2x$QBnFb#yI zmD%XzYEMPKY+-7T98BvNOvT$C!jhRe=)`70Z#3Ttrh8bYeETv=Fz*Yt_jB;X{5o3n z;DgYGa?p=`zn-(QWXAgJ92~W`o(vS%MYUGB=&VygjfQrhF_Uu9+$f7Q8~?$aQ7#(q z45uNpZd2sdT&!XJu|_VR$-pKTk1c;e8f|^4EG8FAHlLtwezMrbC=j{U*@O*xf^c}+Ei2X~Yd@iGqw9;g%YnpV@!fIOV|U=DP% z$)j~ud1#V!1zu#u(8S*P*lO21@ZS8Dj%(**jOSNqqIgU4efelLDHe?XxI(QS=|B&{v|r#=bHr$D+;kgLpwNksRBBjEyO|3uL}1J>!I)aLNxSgDcfVEg6QBv{8?-v zb{|&lT(aMe)Rx;r?c*Yh zstzQlf=5s&FT(G$(`aquy)YoZ2z8H?k~ni9OzT*T7i(*2UP~LnTD=%seNfTKbraRQ zZ7W89i+a+py&$??FGkyp3OahG4Y}AAWBlrDx?;SV{E~|?^jHK9wlSt%O-oSK(Ty^6 zKhdx;C3q#kjP_)D(}Ptd*xdFs9o?BoE6f!?J!>V_PwHom8Qg{7E0J_aV&T%~6n%dp*uJl2^xkM;>=c;24Py*T?_ z+_AF^2k9xnLUWPW`gR#E*sB8dbRYG-j%7H)t_DWM1PJp}%JAsmV(2kr9Mm-}$LHUZ zU|^49@M~N-u1fTUzDu4%(I4fQ_|6KnE1coj`Et}&)r<@+3#EnEAYs%*W%@Kb@0`o0;Bu)rX?rK zpzHGrG@QSkZp+hQjBf?b)OkR=VuImHSp^R5WlNo3IDk{vO6(CGK-K%7z%{108f{9Y z%R3H$<<3g{5?w+E(uRQiP9?^@s-he6*z7w z!F8Vxq_#(a9Y#fi>7DB|>aGIScI3jm^NXm$O@ZQ+D$px$L>1Wz)>+9qpvLQpc5P}f z;+zVKhksP>GpPoTbf|^B+dPF7-5S&jEryG)M#0(3HCR-b48uGP;Fe7dru^v#rV*xa zE4~I_e7AVMDJ>XuYf!idfKb6hcG0gx+tvZB| zdz4%n0{srwVcP&3YL@2+haa-{{J*f7wIxqss949Y!4!(})PspRb+~_g3B{Zq0ov{A zS(jWbO{*dynZ1W!$=)|RaPpD*waxWd+gnNM-L{KAuGHhZ!b;|Cn^K5PJ@zimq3(~C zP-H?qTA4&qE2A59yO9$2-(znBusJ!mM=J4=?JLs0O1O?3qRpQ#r?P7GucW^DuCKSNpveJ=rn6)#0;z1AWNW`F5V(mL#3Bm|W0=j&jQ z!S2qceEofc88p0MbMx58oOyW+u6c*?b=t&HFkZ~y>suR~1k;9MzP8D(nDKK)1z-R3 z>kWRQMg+#1^=-|j%Amumr52TuCBfcK~ z(vH3~ddt_VKRl#I{&K#~Sh|x!c181b%N~8mbbdBpd(M0*UjOme9{uwS{Puv7cf%{p z3BHf)K+-zWsH41t`&PalzKYG*IsAmL$1EzRkz3sOdiBw8npF_T*GZGi^LzD{3q znZ~AYyN3%KPoi^!TS)#6OB%a~Q-`+Z>+kW4-O8f5>BEZnkHWgP&H3xUy(IrUf1BlJ zF_n1Cq&J-(+5j(=mFT*9EA3KNf?mHW>=1U3CQZ$NLhUNN5^Y1-Cxf72PZgF-4WMaz z?O^q-D%`s$jZEDhg7BpZ@1Lk3GyC1}GNuX()PB-D?LlyaeSdtjw~0Jsmb37>Up2GABsWMiZEWT9ZxhVy#_xLjH zjjhJCwlTD<^;?>(s%GE!iL|Qa)V7ZTi>AM(S^BZmdX@sWnqHzVe-u*L4h4R`FpHX3 z*OSvt1$*DPN_?5sNWRckfnE(-qGw=Jxmkt}R?iyz z`|sz^RmHe#kQy!e)Bxj76r&y7s0NQ+AqB6w5Tqrxcr}8d3wx zv@gFDCk{fYW0`ieF2kE=6rvl;G<;kc#-y$h1(qpfMHyNq8mNC{nVugm!)Znq!fTdk z=EE|aFhmWSvrOk)q>s^sS1i-Xlh*1s^cz(C!rQw2U@9rCTNSO~i(S75GX19Tgz1|QZ|px)7HxSYf?ovFZ8ZL&ed zGVOR-fsNT->7KWQ=3W)}EWiaiZTEt>tP1SC(+oDUOlO)@;?`tC&}W%s!z%Ic0EERX zljEXFEIOeOVpyh=dX;!RZjCUHW$Jam65rGs$lkF`MfR2dIX}CjbMR9?HA-UV=T2=7 z?ugN)aCUxf^vuP<%h_JF%Z4SGi{WQ2skFzsSIL(Z!q#?q*oW=aqlz^`(+PQK%k~QI7|3Fz z-!a)5ikp(UyP z%0sgt7aFzIiwXwhjU+(6xiW%^#3kDg~N1b>$4Rp$b{F+dIOvrOqz3vf)FF6?EQ5_Jo( zemOfoER)%}0yHtSgtIJ@=Ia7Hx77>guuSc}*zcRO6X4e_Gjhx>z~!Mua3kH2s+$$! zv0X|?AHr@0jV#1FY_B?9RETy<3vmS7tJ;D!;%b9Jv|@X8(b_eKy$0({SM# zOIlMC1}iht@X}^4+7#jf1Ae8UmSzHN-)jcG1Jf}txQKjn457)~blkO5Nd}`3e(p`j z>1?k|jTM5INjf%Rdo}9MHNr02baY{RwR44mY)WK0*0a6pc-TTrtV+lEpBpHkw;J{6 zmVpP4SJS&l)`PB|fobisDV=4C+n9mPYQpF<%XIoe1~v(Cp#+v`{_70GivrMI4 z8JL}INQ2m!9-Wtg7e^vJV3~%t%EXU172-UWsc1|l&icMaY{fE}EYC#676WxBmT7}Q zCN?{2A(XL9zwT$^*FI`6h-I4PoQZd$bYTX|G$Sb!7cVn`XDrjtADP(pEbEC@gwgB% zSvYo!7gz?nkiKRXCTJ$WBbKS__AJ~IQUt%U3~BY%EcD!|gu5eHEge(t}Db& zVOiLL?bVw4HKJ2R7CNxKx~y-Yez{{d=CJeg{g{O?Vp2B#War1RuNv&p$;KvZuTDqn z!q(H-xRzb(t}N3~_Wso_cCG8NOo1NRxGdNOj98|pnb|mYj~NVNXBrykV81LwFlU+0 z4$Z-r!x73^reh0p(EF-F*ugTXA7bxiDb@(xS*FyxIoSDvfy|C&va-wh&-s}g6^}LD z)u@4;pA|Ln*eX<)j-RN8g=z^XUu;6-I%Gq8jRf>MWl4`~!@z!X0*>0`MM0r1aOpw< z_L!AGf9_+m{of>DWl#|2l8jkly3mGYdbTbZpDr;03zlh5+^!vl3te z%XBO&84m;(!Oc8Fa%`G{t=L|z9)n~vA_aS~y}EE$As$|mf_1D{uvrTov73Gh%Gh2_ znrNV&dp8B!u-?o;hb)8}_9=Le?NxG5H3*1J!FYCl!oqdIOUd5%X4iVtr6zE-Pb$7= z*LnfVG;&rdy0L40%w{i8Zb`);cCFX5OlFr-@nfzbJLg4^@;()}jYgQxGQ|a^qVa8o zFoI=zR+@_4o9GBXSSIX{hOwFkGFO(V?S!=doS)|_B5_C;HM(cj0Cqg^&MC*CCl_=Lo^!Ih0#lvNjM*k@$9|X z(HmLcIlJdI@qihr&t&tPJfpF)$dCkfrb~08vFSvlA?*C*w}`>1&lF-5%k+743_j_l zBPOs+%a+BUVUE7KH_OylKL*$Bun>@C^12s;ZM&(#e3t2#V+>9Y)`c{7e!eBdVD2Il zaAKLy+Rm{|6KBPu(aZ!0*>6U1TVwG=P!YQq!M>+niN#er zl+b+wQhUo-%wXNi3!btr*pOIEV|(S)T}M1o9*drAuL`R5)#rAI!^!OYEZk)w6itZ3 z!ECR7u}mY@#Nj7)tq%y%g+Zs{@G!g9S1dMx{1n-bTi^` z*M2hyWto2dio*$ohTzCDX$*ao2F*R>G8>4)GqwpW`vs*(D`5KL$1 z$K6ktCcB2;iVInaDZjwr|i|oSDk)5CEoz>uGOgNrq*Sb-FE*P~M#rel^gS``MdsXn+;*NajjUEtkMANF2o0=?2RgZce^ zaeP1#8CDs>H7#E>-^Mz`)e$c4_Qlm~uQEOY1PT7R>O=#VEKg?E!kt@se z!_W_JM7q!`mMO&C4`=I{(Jz)s-@^~BD-CH6%k(AN4=2xHy|^rsMRR}bZmAHrvP=g@ z`QyVGI^su`spC?ATz*hrJ%VM*V9(X8USlELWSK7C^+&6AYOs}M@^roN$M$OJM}_z(H~_8LUVWdUBTg?1z;L!#PtNG8w`d=T7uosgzt%#q z8Xt(W*k0XkuLeb{0#S?YRTE!b$T<;+XW6yhbOHOG`aBSqvuk}n%e44wAZD{`U1Pl$ z^iF5b?XYY8Cd=ghXCSt(FoXn_>F1yzJUtDeH#c+1)a-A1-jdp>i=f0v$NT4PLW?=d9D{k;FBI6oEDDe7<4XmSkjRry{ ztI!$1_UgTzLio_i9gW#u#Vphj7LIYp1h!Wm!}VoqOWo0#?bVmX7NT6w9UI#;(7{%$ z%ly7OZa7^{eLZxk#@QWnI%ksy%Op#3$8V}I+R8F*`r(cNQ7&|ZWg64h1FiJUNX0Tm z&h)?_g(2N#nL2Fuz^i~Xl%1cJ*E~@9MInx5nZiDKu=mDw#Ct5$;ZP6kJyl;lo@LT3 z^T16@Ed(2uDYv~RYPME`9Cm&NPx8b94_z3?GWA*OiGAjoz$ca|>$E329c4d1vrJdb zJW;;R3r@34YrcA-IwZhqmPwiJiN5|t(1K-}*4PV|u=C?0AWazNh3eAzu~CRM3%&3$ z+bcC~9ntil7sj%^I;o|vzW25lzGvsB&2kH&t*saOu=CTUjT$Us&*n8^du8XT3v=qc z(12a*XIQ3|y}a=-yVhGCV_oJN-Z(nS1)8xlZMexBzq4!oG|SZgf;Y~qHe~$>MX>oT zdw!2y>&IB8b^hM?#!4Z~W10FCdn3)#5nixNo^5?FX1TsBhGn`t*5^OxN9qlK*i4Nc zv-30MunX#wE{$hh;o}~=VCy+1RL#y$wVMkju#R_ub%j4kalxK{u-{9Q`YgmzTOZP%yz|t?EI{rg`l;|6{}b;cZ!QbXnxZbPq4k(yjDl}Y~_k+ zY_H;L^<<|*T``{R)%Lj-V&8ICJjKq>n&xV>v6CA%W4+wN<+`LZ)eXOP$)+tVQ!iaN z{PB%l>qjifojs#l8tp=xSf<-%Zm2RaqZaJ^Omug{Pj!YA$TAsZvFCMXBHd$|_BE5? z8fS(0lVut=Qih9H>xgGrrs%~oY}Z&{J%wd@b5Mq*^H|3_%QW|n47;^ZgAFXx6?++G z%5@=?ou6}YGIX9}0ykJDEtL!pAF+h5EK`1O5nun|1s_-@XAKc&3kmRvWzyX&qLOvI zD{Bqu=_L`J*z;UTh;;vhh%MP(g*ht3wLv0YWP3Gzg^u{GM8ssaS9994@2PDG{n`0B zzQ95_G>&i<+pBn%$!aB`13N#aUv=Tbal+MXuUgMFfql;iFR*Lp3h_ zS}Nf>cC8z-Ocxsn=hYg*2zGuv2FkGyA|$d*vbl1c=b#X}vP|dp$#KY19pNg=G|)tj zXM5?(l31oHYx#f9kJO!=&3fIxvrLaGZ86nNm%Q2exyzp0Ph`FBw#@jfnPG>%tk=Ew zk1$ZKx5E)@+4*7p)5Z>k5VF25! z{j6(#4||4xC)=y1+jN9BqwO)9?bXO2Jz2_Pd#q-A0>)bRBx&Vfh<$r1VcVN3DSZv=XV*4?l`PY{Q;xXgFuT@Srui=%@zq){ zaAujh%N=o>dIF>$HX||35jENQd80HW)h|aJ$@a=#6RCQL6Q)YN?lOhwy1)q!vAycQ zQAgZxzzH+hUS+21sgE*o!d!NK&Sc>{@@!GG(80#wJQbIKVOuc;k$%G}(`HEK@H( zXI$r|5b{~3^g?Icp{pYtW|@rIxF8j=W+;|v)fkumaewgt)_(ba-Yfav-6u5)Uh4*q z?3p)ag>L@3E1c?I&#jPi_b!knFXvWhrnnwfnrCt=6j*i#@*s>PE7WzgHR$R)lVpXS zF7bnYuFpuaLOpepVL;#!lC03U-Ni5>Vhl-E=x1CF+%E7HB`Y-IunIh;xXC0d6ue#u zd;6>qBrEjoVioIIZV)6ZG%h6lHC)xuPow{{=5LW!3GsrJHSZiPJZZRuH*J-0&o+7GGC@L+C*>%?;ZxJO z722fJm-hE6<5pbVu_tk(g;7FBR7Gb@kf=yQT3E7X#T0C!Iy z$qF4gRs&ntg^H3DI;yJz{fao5WQCNslwdh-wjf!di{Go@Rzsa2S)n#B^WaS49Bze9 zg~b4=u5c@KaNbwYy!4J+A(!~KpqBKNTcO3%uYl{kSZ;-yPSA$)$~M9cOSaVs>*`Xp&86S)=A$$3FJ zPkcbKLbXd=sol8GAXy=oh;XufV*-*D>JyhmE+2J3vO)_?DyY(_9Y|K_-lcl#*X*hw zSs~xgD*C>qolLSq?!)US;ew?oS)u1qrSzzEe{O}YhNMwo^)7COs$U1usP7NC6&fphmp#yaT=>7RpZiP-BwHBNGsO46u6OEB2vS+X) zE2Po!lAw57&#jP!PaEhMSHZ2&*T~gip`FdGkV&X9*lvj+$qEfQ{t2?`T}iS+srBBl z?6Vn3R_N5pMCf+tG)Y!yb=xBF`!<;*D>SJ?4O|O|5hW`$Y$ogeuv5q+D|Eq?UDsNZ z1j!2N9H|C}XBC2Eg$y?3!?=~RxfMDY9t&<8E^{kndCnaQyS?RB=&|N|Fn=xQR%k%% zRTwxYhFc-gc^+s@&*N68N8vZ2166S=6w`g7P(n*nX{SE+zM@-u?X%T$>mlk|9vBPJd@3PXI2QB ztrLQ0DY+HedCF3zZK&c_NLA}84sTh@t<3eQ8^9s?ZK^(!}Sa@AFzd6p{5BT)V%l}w?f-O9O+?} z4YxvH!=BP*KYwn863*#SzOA6KX^rw z6jc z6yOw?DM(hxH>v1w&fuz@J!)WXrJCw>d-y_BrEjdv?Dc4{Q{B|(zzc(ZI;|;_a1_A&dLm${A~+J zR!B@Oqi8ENkgQM@>!Jxe_(G7Z&=2GeRAtk9xIzUeNvLI=AzQ-HBGw?fU9JR{jFKW>FCCmg247s=cT^$Z5XiU(44B50@yp73zBImk__Hid&&;x(h*km&>hCUCZkb zd?A`7E9A56159)xlB`g>-5yZa_zg)`=+o^uXgAo1y_Xt>%}VlNrsYhMtdI~?4O3ec zi;@+(AFqV+Hp4~93e6s_f`XgP1j!10^i)8>#w0&M7>D@azTjh%|3 zqCICwR%qXfdb;rTmMB>vjlmTZal9k9Lgv$0_mt*3ZiSjR4yRw?x49MCsOv(VCtGnV zWE=3D)}Qp{R%qPV<8;9$iCdwp9pmYCNfEa~cQk{=IrnO~6;i(+CNtcs;#MeU+gu^= zoRV9iFP&Aw?xZSih5E4WxqEx^xD|>ybQNB*9ze+o{mg#{2g~IoS)peW++n-HTav6$ z#hq9Xy)Tnwg>YOxcumwI$qJ3psfJ4ZDp9gRf!0b$sGBNER%p$CFSRhO)g?T8u} zP!T0aR;bmCBGBtGnOh-+VbSro_NLDER zb1BWJ>JO3?+S;X#danO0NLJ{vrHZg~A9cwJt-H^x*{I8+WQDGOsi3Tow%iJ}ZN;8Z z4_?Eq(6TNOl!7MQ3XL>(rBex?xD|5LG^0aHe7F_zJAaCPQsQ4$NHvMr9b0aNCfY@b z9mmvgD-^P#L^f%jid&)a$EOKvt(4pf-TzW0%w1W{t&qiXEvOit&#jO_#M?12Ve3_rtkCyEd9d7VE=gACU|JOniB*b{71F)H z99hmBQL;kTTiCUAJ6v6|LQQVhfXRhmL9#-rc}1XQG@e_byC0HZ-NNJC3SBzn3zK4> zb1U>}xE1u;$)3MrR>;rmHuPx|&aF_$pmp#Dv$z$CT-y-}hF5Saq`BjkV7{uJTcPjd z>y~26+zYcpjR(II_iU@#b^~!tE!aqPYb zvqHu5i-n_p)!Yi9|4fL@&F5AqZh{dkxEe>273$I94J2>yAjt~7awjO%`aqHuI&mW! zc7MM{k`>bWoC`6qkR&VgeH*j{L@Ew*D^&N`4_>Z&#;wqyi`Jmg&zW1H$1Cna&-zeqh3X$| z0L7k6ZiN~ex&&f+=?7k+zK_dejy(FQpc^3Rj?WbCzNq3 zG`h!D`n52FTcPf{_o?*_)-A}akoxQ|!5x}}o(9Ni;IR;Zs?N!3T1aVzBWE{BfB zE#+2d_Sh&o-1R26LX-N5^r?phw?a;%UQx#iPi}?uyIml&hym zdG!i@-0>vI3XL%mq2A&nNmeM}Vic@-bb}--)H5ds1o;w@tWZjJCA?nLlq4&3xu+7` zJhzLI6_VXl!TUiE)g>!rvZxk5zhFP6GAk4{tpxV17{RU3f(t1y_qiUoLJ8y#2a}(2 zE3`7+2DIZHxfQBOy$1_3S$`F?Lgr1jK>3{vZiNG*KsS-2-k6bfNL9#+?)063Oz5z&9sLZ#R5(7tpWQ8=_)KZCyryyCOQbQG$7+R=HR;cq# zCD~kFCrVamk5EOueH(Er)aYO?wOPA}TcNb6(S(NAxfR;Df#|&B2X2Mlzj#d!au05W z>}@VlP;4BxLS>dnM*R!86?&s65N8xsb1NiE8YEh0F>k`Gke}E}7}-z7tOl)mQk`)?xA`+@c-6F{f zT~^BhJ@pkNS)q1YD`B6q1xZ#&Evp{h+8q`pE41?&+v}=*>XH@mdRGfh!<_`l3Y8?4 zK!M{BZiUwENrhmI1KbMr%wRtY>puC*3XQY{!Nh@Ep_JVZz}Y{TTOmum?eNSYom(N( zg}vdNK^eC~!-HQ7Ezi_(E42CUs~JZ2DsF|Y%T2`7SkJA{?sJ`J`}cBgg&xk(rO(U*LLOa+na8crHHe|F zSy#Cg!Y6XNwB$XvLJ6(jQqgthyqFdGx%4s>$H#IjG<))Fa@mp3tx($y72*{3oQY(G zy7^8N3*D653T0W>sEd4Y54S?je+I(5_($9dEjw)o zBQ))~71Any2)jN9aVyk3eix{s)3_B%D(MHF@ul1feb%%T3`W&)D^#|>je2Y52PG@C zY0g#g$c1`tg;X)^$mx0ow?Zv^b!cpO7PmsGFDB&R9}bcgdZ7N9=4iQsWQ9Ur`%rfL z3y`dk_OC=5aPK5YR;a6f5iO~o2$B_gyP$^LOd|xz3e_%E(d?>hb;%0lykx)kSPG(K zg^I^llZKB%l&sK*>O9I_s?Dv?)S0pLW6l+Bg&ghJpXL36TcLzhJCgou-%^F$Y&Aa} zVza}f_2q{F;^o3#eC=7OMQIM5`PwJrHaUAV=j-{ioZ0=@GCoslz>j$HzWdjFt%z?` zG-uOG{(AC~#&Vlad-;0c>=yEFu08qs^wL)HHwW(V`CW^*wv-QQttONH+zxx2%BOyG z;PbvV2dhZ^^-z*t@7Xq==FB|E*Ifd_XtVuezOH-MQ+{I4Fp_4(8O`b>4|!)q(u}w{ zADYYcdVD5nMx0vbYHIEtM$(M9I}R~4fz2n8X2e;=+EKS-P36*zIQ)5&rrqiwmuAEr zJu{0AhxL$4GvbbKjudl$^^r?6;x5)3$-4CDFPCP-6*=7zY=-ueOEcoWPU;Uo`u5^8 z;zW&O5c9n=pAom;?k$)Xx8yV8^o9q3{Bk`>GvW>pFM!5XNhHmPd-|)9hEKICNi*V3 znzqw$4!cj%jJQ2|-8J^LT|v@}IA4uE8h>o97Nr?+RN7DDNduuFQ*&d`Baj#x<)exHO1ZhTGSoby>e++v8(u}ynp+BJ2E>DnV#C7fDn2$nS11zWzrC8UF6};;&nn z&HcNxOnP1F_WJwd|L!=GKF{CXXVT~YyAw_NbN}v2!{6OrJlpSXFTR#OpY(bE%JZKt zHtFm7yYox>y8iA0`}^~N^zpwxKVSd;b2WZ{T~Z#tmb%fTzZdEC-}(7knyvS{v+VD$ z_wSE~zd!!>-w%KN_um^||Ni^rf9~(UXTFyHzu%o@fA5Rb3x@xkulT#`ihum?4lKUb z`l}m@uYY%D@&EV#&z|UivG*0wSzXJ&P$*E`-Cc^)A|V6C-7O*Rganr&EiDvJhzBVy z#VHO&HU)}nu@*`4Sqv{wq($ERcE0&I?OJ{7-uE8sUG6`3E!O>YXU^=|Gka$Cp0m&X zh7X+3;=$+X`!L3lKd)?2VB<7=5Y?*DI&Gp>t1Ogq**Ys0d7{nPgIwk>i56xX<3d_;@aDS0(6pZWuThxbOW zb0j}v4P(!bdd(y88SN6cfhC>;OPmLm_z!H)kGd~=e$-g<2xug~*y(lNvGdXS2w3tI zu;edbdw$gNvz$8LpqXYk3$*TDAtsN3!G zYs}+XiT*%iAFsxCJ!mZJ2hiB{rrYiM6nXS-m4e2uf8B1ki7HBT{k_I@{_T3v z`!-%EK$&NL zGSB>Ep83f<^OJezC-clt=9!<&Ge4PUelpMeWS;rSJoA%z<|p&aPv)7Q%rifkXMQrz z{A8Z_$vpFudFChc%+LFN=I7tNCwBjvs1~0OIHm85&HNp`%-_-5dp+}a^fG@(FY|Zw zGJi)e^LO+ze@8F#cl0uUM=$et^fG@(FY|ZwGJi)e^LO+ze@8F#cl0uUM=$et^fG@( zFY|ZwGJi+!{rep~G4d{e7!^17#oAf9yBc zmxix(uDPNx{o#_T@;%w;eDio=D&IL(Rqwym`NF3~C|?O~AGyRLXh4dZ;Iu%(fOy-)~g~+A_P1^8XQi{WPnomS zS?CuGTjVT!uJ4I=7XH6gNtMSl0taL2gNF5?Bg=mC60 zKj1HVL%*U=$Rm1&oT7ioFLuGWT8ES-m0(pP`>b#cW=n_ZfgU$iRM zm+PH_H9Czht08?0*Hz>UtYN|m9!kyiE5jg8L3J`e)C}(l0+)G@o~7KWTz*!L5<2p;Ea%!X<>{BE7A^mRhUF<|J&U&2%Vy>2huRj^ zIQ%*7Gy%UQOz^@v)w_H{EMd z+X>vx{NOr}|JpdA5seCXpxdKrHX*gMZ?8BB6S?P|pSEV{FX=lMZ+P|b7^H%6F zpM?+Rx$wvQmww?FA`kpU6{7}#H5+63CLirx*`Tx;p z4XMqe2ih+t&uB=EFF(-!(&utR`eo|_?O&f(YeY@M9%%oPalyYTo^M2(TW8Q`tJs+G zmCfLDJ)|*hdvRa$@3y@$t-Ntx_uJ}zW4e6kzLqDcd=o0V;l7r0XPYLJf6;v{|C&Kf z$T{-9wpT8%CiF1uzV?XlZ|9@wg^%IczwpH0nZFauBm5aZF+6MJIY!H7r+2dR{M)l*bPXYc#yA$^ z7#;HCSqINU`OCH(UO3xo$aMbuQjDjqdVTuWeIaWKYy8WU{`=jk=hXO6{>A%CmVBU} z-MZ}Le*UL*%WeDlZyGc00e(hf=5c^|wXpL(z`S)o+$Y-iNjv&Lzo17Sz~F;EfWaUC zK#w;34H&d|1~lNo@@ov<=mRwPAKLN%kOlO>kkP=$3H-qaV>0yXWRRz&LC%)w1N3&C ztp*LFucc*AzU z7#C~`EcUhIzr_S&JaNPswpXUVi{0TP&_CuDu-F|~><$c@U~U16-GQM?*hbo6ccDig zz~F;EfWaUCfW_{>Vs~Khu=jyD+`?!tV3`9(40^OfM#KEc^k3GA*b({>I|7RxfyIu} z{x1CYldKCUsBm}sbL9oqHE2Gqd)|YlpE|GZFN~+_TYJ&^?B`Xz#c`CcULUIGdQMFl z7fVI_`%;MuXVq5?W9US;e)M_ZS#|JQ6uBq%Be&{jmH&uH3M=i~?7xkr~d(Ns(P3BVlQGIB)(>ax1cMjG6pf`0fol|rA z&!+SJdQz|D=hcjDvuNG8?o@5u1@(Q0S#)}ASDHHbqN-7H7JcU3nKpF(S#_^5i*|JC zNK2bvQkzH5B9l{l>Ra`)>i1<7?Tju(=^IkioC49*XkrQaby2E%a3h)~g%_iSZ8$!k3WpV>&vxEc3)(FtziI`k zu7%rAE~1eY3eq*(ZFRrnV)C0etz!2qp-qhoQI8?F73Et-1v(U_1^3fc=T^(< z;`$;qrDwV-(tZV{^eaYFBGXj!5-X{LQwjQWcd9!7{Yq-uvlNv$m7=ESUPV8AU4~|H zeg0h4Rdnx2ISM#qQ+Hmiq_7Vv(u-48^?UqEa%oVRzPV^ob3cx!0foBJqhc3T*CWfR zWBp1rsjXFgIXH&84l7N&I;E(-=VEBzsgiU$d#XAb5=&opEJ4$^rK(<^#L=Wj#VALY zG}XIOJoUO#l(L>qQx$5@r~JPcpOH%cyFZ66AU;Rn_)bPC*Mw()H4*>e$ugOsDnq=)o+3%lI!@rKEYO%d3+p=>i?}R9-maPwYhMrSb0wbwe z-99vr=l}Ws5mdEMA1W7kPJP&Q9_{56DgXx~FQN?NBfeCH|43eRh52yj1h6 z6z#J^XXK*-=49=&UpFj31u7?NpEZ{#L}8t5+Gj7-DMD*qt=eb%c@(3Po)+!1vzC>h zr*3BLv(=MI(d@w{?WYg#wWq0T&+56l#fx>7^{k$&-M4n4B}32Xx%&80XIhzlTF=$u zKX#$GDW~;ZJv5>##WXmr=jx%PuJqvbDLq#&f7Ff2-#w-0s=C*eHa|b5=W4&OuH;bT!%Naday;^jjzSGa@xjJx1 zJ8InIoSv(_%C)7F>F4xZZT8J)bbw;0 zI{x(kt}waATXp;?RkaWmYirZ-r}%{e6o1pEYhDC$DazRd8u2?6dixYTJn-lZMGN3pC4=GqpxzO==k$`Up@*um8|1WvFQ9XcnH7i z)Bs*QVpop=Sl@&H$T^KOc-OOhYzVb^Li#<5-7CO#AzqM8g2y^-Tv1)=NPA(#hy83)W@D^oKZJJ{WF`PMw(4(r2F5} z8=w74?R5X!XP;<#uGg$at<~_Xrm@%M80#9WuFKhJ7#p8Oo!=pk)M-JlWoABqd)86c z1s|uk&l<=0muDS3?R6wQcGNzg52+V{57#_&y$G1=QM%p>jM^A#RiNkEm9F;!b6rK( zdqKl>l>-@duxzN09l+l+_+-@ifzggWgdTkWgAe+EuD~Dv(2h3z4H&fO0~kEO3mEeA zxHLwehIU==wbMHp_~?2sXfdXYezO_sep((~?*)z2i@=9@w}iccrCtOYw4+{xcF?n| z8grkz?gttklfCYz#|3$`{y~dpM9z#p^tg1LAJ57hcsrN=GH0}|?DI`*z27)DAS>n` zc!58#*d18x4h%g*R$%A`Is%4GAS*C*iSYu%Ca^m&^VW6;hE33iw4)E9M<2l8gFb-4 zAOC>ShQ9%W7JUGN2l@aOy93+DCGFboc6!|hFl0CI*L|R!+jJkmu!%uVT}wr~-6m@? z_+-?3rQM(hZFk{g(3|c9?Px+5uSpufg#4)$>xxztPJ zVpH2Yh4>BDd_0agIr&`bukoW(pE#{A(kp}hL}RCi{kmw3_S7ToGzPt8Rx1ae*%w-5 z&@=x<`#;qf{ay%ZtTE&DTqN{FtX`$G94Xt=06v?Y3@r@aa+Y zpo4#w`Ny54-vo7D%LDq+ZdbLOz&%^uaL7NsS%PC+3C$B7<3&6406TzQ^aDPkH}DsI zqF?A4{2>qYk7pq#>;eq=jrIbD4KYR|20hxvj=*9^V6h{x*b!Ll2rPC47CQoq9W}k( zj?xZ03O(!y3_j4OrnlP>SnLQab_5nX0*f7i#g4#YM_{odu-Fk;>CAJ~h4Fj=*9^V6h{x*b!Ll2rPC47CQoq9f8G;z+y*Wu_Lh95m@X9EOylN zb~{Qt>?riGBe2*})7$L`EOrDII|7RxfgyjDepT%`bg|R(#u*sn9eJgSZigPmHp{@! z&r!e1&WOp-+X>G~nnuUTh85Ai3VMEEDX-gMuh1{cX$*UDpBeOQuR_a8JKE>9DCMBf zcejM*4?cSi7SEt(d+py_%+YVI z2p{N2_(N~fFYE<*@GSH!a>8CBKkOyrg5Sw_(Jp!b{Yci2@DaU%KlF)q^ecLXJkUS% z2|2|sf43KG2RmYnMhtqiiyeW*j=*9^V6h{x*b!Ll2rPC47CUNsyB(z+`Vo5Q4Or}` z>Fss|M!(QMu-Fk;>hRytlETbCGAi>h|d12F}m#|EzJ{{`H;DwmqeB?J@P7|7>#8N7`3FgLbhU=%EMUBeny7u^svq+d&@DGvpN8L4L6v z&ykkci$VUuWtX*-_GX1wYI^k5?SQIcuw-% ztmVhE39B~CxGJMv<|^n#58xyA0)Md=`W1ab9_Sf7A*bjc^21(e$GF7Ts$^a0Xz!3G z-a+4>U5vwClMhE~{*ZZF{5(g$8?J;o48>{v#SMa*}@g*NJfwd0xK^cM>`G zUYz43@;5v*oAbRsd%6t1*_?B}V{D zj*xb-m*fbvOO61R904pj0$6ecu;d6}$q~SkBY-7G085SlmK*^rIRaR61hC`?V961{ zk|Tg6M@YNaOL7F-B}V{DjsTV%0W3KJSaJlg4^k|Tg6M*vHX0G1p9EI9&Las;sC2w=$(z>*_?B}V{DjsTV% z0W3KJSaJlg*_?B}X9c3r4%-2($}E zd*(jz{n{sH*3&ZVg}Nx_FZS0`$NNvLr)9o($gmgQPl>(ceFy9%??F&Mk@q90!{GfF z=rih{y)>5hN7DW--aAOXL!6X+2Q2vxSn?gPU+}N&@1%YLACdYAd_?LeXqWm4u+&dL zBlQ!sOZ^1xQa?ev)K7q=egc}z8hgh35viX*CsIFwuB3hfEcFv$qrC)U{u{B_5$$3} zV6h{x*b!Ll2rPC47CQoq9f8G;(k^}{?@G{~SqICgTZ$c_6R{&O_TaFmV79-0_lG^Z zvPH@j8WR9zAa-!yNnT7#t1B91pZgv_x0}f%3+*1gJT|6|}-Dmm_sroY~244H1< z(R{ADkEYRs?rQ!%UyY*4`|s+0n;#xYFACn%^3`tc z*4RL@!yA&@OP~rPSWpy6JaFsY?~NHBIn_* zVI=ZDb_#Qh3+*yq(2E|xNAv^!qBry_`h+~9XUHk~hx}p}jBCfL3DkK`x+=6el8Vir zK=&fj)ver7v~1)A+Oj-dCHO?qs3sFA_kna3xIKzO%%4*obGj<{EQ$(E`ka2te_I`? z7fn;Le@@Ta-d1M^MpKWk$J44WZ>xJFqUnp@$5EYwx0T<7XvetFUgGLls!De>eTU9t zY18C8nosfLV`$)>JDUHro@2=4?j7B4t@P1Uwe(#rPv!X0)V|eSE$7ogqiKcfT`m8V z#-qt+=v{3ubM?`bW8_`6=uQMl`-Sib68iI>M3C@lm%_HQ^Z$0mJd%FXhs-09C#m&3 z5;;|kc@FtIR+#4)7usdKpcg%WkLU;dMQ`X=^a*)H&yZ8}5BbF|u$Owl^E1J$=Vv|3 z2zrug*7Nq$#XLWATJ(JWz19dC*utXcdGfsB^!*fzp8p3f45N>)TC`tueiTZdHnVDf zY5yvOPOhs+ND^V?WAIsoGw*Z~D=K zPN~|zq#g5C=rNy#59Yb>$NZOm;TIwg{6*x1ABp_%FBuowWxSvlJ%Eqs2mD2E=vVX! zc|^~UQ}hr261y1f1uU`Ah%@74MjXzJlbLby|7Dz%yar#Ja(M`~-(k`@!hC!PrSCQA z+!4HD2yHlJ(m93vhER@Vlg>3w3k{(fxy?EUC2RtE*ddyES_NRSL9d`a%=@Y26x&=41ZdkNTP{nt#tJe&kxr zs{4IX(vK?gooUFq_mBC~XF*mi=iyntv}Br9%iqP5<2qwl24+oNJ?~&L3Vhc%4l>T^2=$Z+lUz?`$k+0?4A zC~AAziw^%_)BMeM-6+0{Me`qj!;LOgv1tBhPqhZ> z{@LQ($kN85`CDeX(cw-O&HtM(+{m{(|6U2-)pq%$A5D0Yfs2jyqO!A0%6(rLjhX4k zcehzpwk=`g{*51%D8hH>tq7xQjLn6us!d!N-I(P^#hB*k>@aE@=|{)%SyjlCFgm-) zj|zNbRZGT&QIU0iR3V#Htsfpn-|q3Fx-Tu7|E`8!G-!=U^Iulai}rnI()>%-_o8Wx z!M|){FWS4>r1?*8;YEQfOqzfG_FlAYu}Smq--mS-Z_@k|yuIi`gh{>Z9ZoOa_|Pf- z?HFLE4IVVKpIJ5N6;2C2_o05TtZH$ma2}%%ZFy={1>5r4b%75xdSF#QwhE^v8+@p0 zs#Tq%aJqEBhkj19s#dMT$>V|#O}}PUIopNv+S7+3&s$aYF5wjYn-8@(Vb%O^RQ8~! zk!H<*cS8^AJ%|05`HyMiL06`lHUDw_Jm|zkv*uqk(1S*gGHd?JCwNfJV6)~QI@g05 z@%>uhfB9Pvy5(wC-RFeUvr0ZxxT;O#=4ah$=N_{vpBzrBtNKtx zrf(k`P8*8*P{mp{%|GS5J5Akf*8H;{b*D@F88iQq``qc`A+zQ`W~V##KVsJWyKi@= zZb!|U|K1($w4U3+f9+m(8vCPJ^S}F}I~_S-R{QSEbNCUk%=x$y5e~o0l{doS7fZ56 zIQ(VT^LY+GTK(HRhktFn%j;gd-@Qnm=kUjMjKxpEUwj$-#V^2L{002QkHBC23;f0J zz+e0k{KZe71w>H)OSM$mPW7j52QQ)kyl z(4C83bZ(zbxvYqwDo4HO*^f5WmDh4v_IlByV|?FZ7}I?3MG>cL$~q;2>Tl#{nZNJo z2>N5a7d1U=)BG1McB3y^@fw@?mznEEy*hIIXa033xzX?*7R}#3)QuMQvuOTpeB3D3 z#iIGwb#Cg}Oiw?nG=@5?x{(@$fdcOPu_+Ki5p`@v}g$7)M+Me~G=|FL4a~CBA{b#69qr zcnJOyC&6FhC-_TT?VgCfGV&C#a z4apYk$ZK_<#W?cay4x|1JP7`hE5Tp#4){wx0)NR<;4k?L{3Wk}zvMgcmpoX$Z7kJl zpS*q=Gn{7pB`?ps2%NM>HFUP)P9de^Y7#C zO|BJ8n*Zqm-qfM8N%PO!-J4ccH);N3T68Y_=eu}ypc)sUs=(crtt6Ffq!&< zZ;EbX()=I(=|yQ>GUP8aK9C{~n{{9Am3*mD|0F%eYzO@ z=Syytk~IHAQ+;Vott8FA+z4O#qhXTfpU=aW^0(l7Wm#{{y8BYxXGxlWOY)`8osu;F zRSkXVcK0OBKe>i4b?C#tTg3BWkarNBA7s{eQ64`Uc{fpEPVQY9MA1%W1^b>~6GRPK zm=)~apK$V`X3}`f6@RK!F;O9g#BK|w$30C7 z{n21U%P|`)A(V$e&hCYuEBIb)G~nf{+6KmH?JK)$6q99{@<1e zpi&>C;*!jmK>dpkEIpD8&4k z9}cCU+9rkgIi%1~Dp`#&$JPF&hf?WEJcl{nzNj#iV#}Kp;&8>vLuqL_lR|vnRdFb_ z=61yG<7I}@*or2Fcs{krP^wwgr1_uvK7ewo1kHcr{s7vymof97|5E@R+?k;HJDm=o zrrQ%Vf1k4f^x3uq&HovHWgcRw0yYX_DSYWN8pW_f{wA{Y66g z5SqU!N$)#WuLW>qADdhLoE+I5AI!Ph#e-s!(y~2_d)&n1p3Zecp zlN8nopG^#*z0;Bu)( ze;F_MiypvV^n-P^%r{_}8(7=R{KPt0<`34-GOw_%midPDw#-AU!)1PAeJ=AB>voyX z;4gC?{AK=tzsxJ}m-z<%G7rID<|p{eyaj)m&)8>4d;k_-#=cDA3HD9m@7V819Kb$H z;sf?y5;w3flX!ytl*AeA<0Srozr-l;7k>wTi38v-@d5lLZh*hU6Y!Tf1O5_!8uSWx z#B*SYz1TZT{Kr02;xqQY61TB0mUxc+vc!4pqb2@h|0{U``);4e7^{3Skvzr=0u zmv|2T66e8R;y?IHUI2f|7pP-M{sop?iMog6Yt$tqpQ2tNc@}jH$-k&?NM1%=Lh?20 zA(F>YCz1RP{;~!Df61rdFL@UHCI5oItZk-!6GpPW zI`MfJ$@-_{Fn$MNUl;xA$9k}@m%QA=NY+tL28NNWuTJy}BUyJn?;A$49s_?_vw^>? zf52bXMc^;%CGeMZ6!^>f3jAf=1^%)g1AkfH0?S$yW0dtU=w-bMKC+Gle_7w6Us?A; z9$61VPFW{Iepx?*zpSyrU)HPOFY8$Fm-Q|9%eoi*Wjzf3vQ7qnSwA;FA5Qgt@TK2F zGwM-Nn?m~tUr(B!)%=$_73Qk!Ws3QQ(^q4?DCbO*0;V&5u?|#?OxOqef+{YQt@gO9L6#u&USh!l{cB*Zmr2-~;9TXin=4nk66jQTgr}&z?;6 zrSdKrJo8`hrMiAr-IwUZIL05xhEvyxUS#>kq;|~=r~Qn#GM>1QuaJu=_p8`WI$~d3VUT%dqeU#Ot+huMW zeF`+u2|hG!bdmz@-8hg;NnBfFUl6}GwpZa8*tK>brCZJFS`W5GIbJWNn^me?IIYPW zNFV=ZR?mXM>B92>%JT>Btwx1Y4@&@*$!<}zHonZTi`a3n_dM#; zEtpzjdNaq)Dj=x)95@IGvz?!}%TegilSn7Ak8bWBbsu z5%lTBU~0{K>fMY-?h2;nJ$O!*j-cNc1ydnclZq=ELF2#XeU`sTdGWgCyCK0;euPPF z=Jiaqe!+BLf=L~JGLL3{7EA@Fnp9SPC(@-+FqydK|I^iZ^lSBCdK1pSS^pECAE*#a zouW)?-S&AjtZXo?jpjZ6@_D4n@w1F;Ma(1rD#0|H{ch}+^QdKA-s{aZseHqE&E^zL zf3nXS^=r;{c&`VVY^?(*=fecGwlKfHuEzLff-3S+1dZXj zR6J**I{NahZcE(fHJ;6%it?WBtAu&<_^LmRtHAioJgRrrpRQC%RIBzf%?W?XTRl-t zTJsh!jebkB^sBee<{I&qr_qjxQTIK9$m(L&?=NIsf%f_z`O)-yiMn0Z7{;{?;%cih z{`C8(L>(($jTl0Gk}}>?$odL2(vH|$e((?~lWx+n*SF0Os{O>IWAD5gjI)?^>>ZwG z2p!Cufz9{1ZcxgsX^vhBqGHv}`q}$?7&kKOc;0wf5LI(FYZ>~^=J$ym%sT$R7#Bp9 zdzuyU!uFsbn%R9^hnjd``m8fIv*#n$MmL%%fn}4Mr)m)#bWAa$8>E+wS`*e=gyF>jb^2bCS!>9K5 zBi}QLI<|k=%8y!JP1G^}Gp=1+M^$N}%mYjZ6`hKF$ zDNnNb(X9uG3c1EFyB}>}Y_#LZ;21~jMa@lOFWMzOqg~cQz!J|vBk=)PVx6&eXKbIv zwGoMpS3Ad$#LS~kF(k2cXML_c+GFhVYB7%3d%1iJNlYGBI>r&JUzdz=#Bj7rYzMu> zeDIN60RECA(68hU$Rjxga!Rg&{F0mgGG4CjNSwUUF@_|5)@vR^5?2#Hjv~Z*D*%*@eJfu_%N!$jOcn%tg^LSR`KX^)BKwpwCAcN$Qku00!7sxDj9C+`P^0Rgy&$5NzDcF5~^M+`Wm;fxX0yGjs@T|lZ@RXQi)QNG7cPhs? z{N?w8F(iJ}@J+PCze?VZcKBWSL_ULO_s4A)qDlO;@zH1!|NV1sG>Kn#-xlrgcaKfc zBypfO%P;Yv(Z*PCC{Q=axvPahJbpY zr_PqI+&n`+n&6X17$g_2>L^<+r z%8@8XUf#gx9wlEVuZnWy@mKNudu{go-X$!`k@tXjSB%;(=5l6At9N&LRdzJ6#u zIm)rFFzUxRUW}zpvOg^;nW!+9FMsi;W91VS#%k*5m%v znR712a_E#l-KmVcI+FmSCVJv~Kd99c)QDH1; zMFQx@Y>5hE`Jqk#mF9Xc#?rKX0PVcTH9#KAcFzF1Wlm5S%jdjawO&n7Mw>RYM9|e1 zLn*2-uVJ{(CN(#-mq-qvCf{Y$;-vm&tou#e9qFI}7CxX6KF0QY-$zmwt^-GL9oXf& zNa~PtC@tqY^GAy!Dd4wY8q%20SImv1JW0W{)QQ()6C>#-Ue{&ib=~nGe)dE#d3G?V z^!`k9B$(nmnbeUsZ?UcZTbkr@Z=dav?=8=juOl3N^?4NGkU^#Kdt|$8Mx7YP2>IJ^ zow*6upCSLuZ2{EwV1kx^-M74tIFX>`?>?LB(ial6{5d8C&??qB+!n7d|d$3@}ej>FzXggIUj+rLBDELh+2VH*&TIG}2y$=h(r)KID|!rhvQhd6IE_ zo&+?(u|8yd$Y(-kMDe*E#x|>35D`T$PWaH3>sFQaZInaK*bPzCoZ{DL9B&_I597V-;EqwSD`r0#*- zDs>OEOKk-0QZq5WcSih|y*aSd96%#=7-Ku~pwuXkAEkDIyeTyeNZ$2NIeH@390iK z?T9^~_!{=h;)7@xKSjIvFY54eP6PWjnV-NC6O8AhjP2O#i4S5AD1L;!q4*c}jN*gX zOA5vwQ)saFlxMLg6`t6uiVWDpN*uu6R^kK3C2<3LVTmWe5@(D$F^&;??a+lD^niU3 zd+>&9`CJ+MAok|Dwt0{@zaz$;{rlY>bc1~md-*r)k8K%akN{JyUZ7dm7ET0v(Ag1uzKd%PPy2Y#s7YpB zidgRajo>l($Y@*cD;+N@B!Xqw%FHt>6VqaBfV20ZYl-7Rc?Ia7r81q(jJMN-Y*+^GSd z2cA_jk~X|?rya}9DqF2c>YbbC$+u=TyhS8kD(FEu7n=3i-4BX*P~HV*)zaf_`?}$8 z=_`NrmXA}!TmG{b^BF38zdP4PI^+r68tIVJXvcS5!~c7&RrcNQd%e_H`+XPhbYK^G zm-O4_Opo9g5Q@ttZ@(iF3$fL&mFmR#yZv{IL9k%6`Wg^b167)Eaz2l&RNc};2f`< zZ^5}}IroC|(sCXK=cwhJ%-`Sj7~gTodh&gIUt@gt^e)bg8_%o5UL#BRQ}3TG3U++O z@BW@zEc#rud~5bD&gB2SE+qAn_p!EPtWCX(?=p;>eT;&<_F zz~H@?YsEC)%aa4_R$gpvA>qsh<*3F{B{_119=~Tvo!La0`(BdW$(+` zPSkVc9nHJ=e%$!oI_gxi#z6f_)*i<1_i?9?eAkaVh2(pG+;1TF0N_p`xgP*`3dy|z zxKl{(6F56C+HubS?hcas2XLp5+)IFVxvv29a*qM{$o&T3FZUjxU%3zAfAW0`#+V5# z-}xebR`7D8*{&9a__;0EjV|=JD8x_scH0W6w}rnCNOPyk8_f#--i+Uk zHs$ve@OSx6*692H6d#OhDqwjQ>nq`j^_BEx{N@)})>{9x9y5MhZTt@UUs)S~Ms$Vs zgXj?J2hpvu)&VTv2Z1K4d=O>hZ<_Gz>mosPuzbchW%6B*u?F%_brR!#99X_*flgfF z18C@}1ckAWpAbO(`CKS;DBqy~%lC%=w3j#TAA#lj3+zEg+I;EBt3-vp$;$)2w6H+N zH>dL5gmGW_zuSAtHwd7Y?*+hf$6+se>}S&Z9a`i?3;5ec$ROVc1Iym$pY}(_x-PJc z9dlB2g1INUGJX>TEcM=hstFrwkHBI(_>|Zbz9Y7V56T<>mhaL2scva}j{q#XMNAf* zBUXzojNix@-!J^rI|$?ZBVf`0zmf|;BesAHVk7h=wnM&HaC|Jy?UkfDFN&g$-;Sl* zzDcSvzt>(_dMu4vlB5Rm_p>uQjiI1FlT>u2IOX)kVbkoO|(q^YBbBj27^U|9h)k;&(xsGw@ zS1($#DNS{G6-~*nJ*ja1bd|aoZ zvuI<>P%2;9s&0GCrW;v?Q}RHI8uN5EeY0i+9pm?sU+tSiwQ!nTYb>3QPg0fgMNpn)W68-UNx#Pw+rf_Q>W-s_voqQS zms%V}6S9t@8EnT5W|582j-Jo5`RCt!>aDHP31l}w0Cx)k*fLU+QPBuLaOffa2Fq%JS%$d;0Kf z5_w!2&nA(x+^ty-`46aBj&Y$~#tVAU1Nex3z+d!+enp>|(TCroA%e z!+*NHGVg&*QSZw=kk$R8Xl3Iul-e&zEt?ocKJ~^>tAR->ZzSJER&xyfJfD zmB-LnH@*{Na5UXa98DJ|CaDg2W2nHC(R_DYlB&NehJ3S+rf+T~sahxbeuF2YXsMO& z3b@H2{LZeJ_R%TpmRo9wn*av$<~HbQHNaUELqD|t$qOgurOK6 ze6C;sby=IN$MQ!(K0941MUOFBSnv0Ir&o9ofNH;?<)J!v8O3oSLZ(RB}>*+ zt;0|F{xM75RIS^KHGJrCK&saH@zLHiZcnPVMc!Y$DEw8bw$Yczz3BJsY1(!jc6-sM zdDFB_1HSX3o<-8Mt$(P)HO4M!dJfz_<4M`Zrs=tnZsDO!)y}2Ua@L6iND_&KAR*CbnQ8tBtDdGGn*uC{PNjsM?3+RI0G7q zKX_K+5_n3yLSGWcAcMp=$R=?QGD|$fSR_tjj1oUFc8ROdiNsszO5!kdDDfG(mADO^ zOFV}yB+kP|68~X4$qTTlRz^6DGZnTb$-W*Or;}K5j%Mck&;~-%#^DZtpjP>3J2a-pAc6?@Ay1WYzn)#eWQ< zT^($CA9tkUAgauFgkm3eWBx#LOXj;7c^{X>Zy<%ewCR1^u^9vD&0W4fkjH!S>rnb+ z+YP-(c-23Y&ir&k?;Rdp4xz`dZ|FV6w{M10y8BJN*BHv*o}5X%srMjNCJ&)4U)<7r zlSoq_sZaP$8{XqIDiuJ!SrhdhC#kU?4ZD%3_c(+2`-l$vl63pUE_`R{B9o^7(%*w> zjn3FBRb1*u=lMHv?4iOw7)*&z`MYo4TeVx}LWkq5TArd)2GJ`1&H{U}gBu3Y!m&0j z|Mr>#>G1a%<4SuufCe75={=6LWA7mJ*i#4}>@|cx*38l`_9h|^_ADYN_A(+r_Bb*w zw99xwFM0qU(GU2G-q5e;6Y_|jA*bjcdmOQg(O$;6iv9TWX9LNL?|#I7yur>v)Hs0e z>g4@+``s>d@)6e!ct2k8nJe#&t$IKHJKx{9e!oTU$0zcc-Y>IQ^nSe2WzN5!@*Qiu zAOCT^H%;c+6!zmzGkxjtyd=FJpXuRG^$sNJ{rK+6f%H4ysfGQx*NGsy%5wnw@jqGz z)6=k9dOu!$`cQiH=S{sI&oVcJEHiHE{rI4+p_JI*rrwXI{uoMKU*6Dbfb2U$Y4G-& zdTnrQb13cDc~h?$s;mp8W_xbxwM2!Lp_Kl^P3^xQUks(*Yi{awf?)W&@IibKdc+6e zgZLo)5l_e?l-m8ud^paGdd=tSvfWaMKgXwq(DUZE6yjBdz9F=)=PiYJwb?g>`gFRb z5U-L)hfv|qZYjh!|J_6B=eS!6anJ38q0~R+mO?yy#&?tj@Lg4ipP~1M(0*^eH;m)w zjGVzVbwGkb{Pe6CO#WRH6yog>{zkhre=~(R+^|#-#WqeI+c{5~%lAuQEbfsWyoR&rF`ixGPAjYyt&>Xo-6%_E ztJc;05pL8!nD6~yoz$Q0Mgu(g`z+Q~u9a@oyq{I;w$a+b6u>bMIF5ZXw$b`eTxtCfjvH({b9+}B;$zdcF1yi%manxb%z<8AU12hwb+ zwNC^M$>TzK9`GIYgCZy>iwiyDI60Bu6Xks|h(3E}QzctR(9Yin(T^NgjeZ9#bpZ6W z?SLm;o|LBhTE4-P(x#>9zA7#9q|S5GbYD5c_%5udG~L&SUwhItt}URi4HG=++`=^7 zSMPEBUgO)0I)nIc%%CWT3=R2xrO39Vb(BNqp`S)M#!|jslw*t)YDPK6exPcULnpu@ zv$3XuzC;G}C9&>!QGUpSaR=UUP!RoMkYb$ZylnR?jh*Lh|yQXP$er4W_AF??qqh zUhtm1Fvr8!{H=YOEB(yhjY75)7hLHe|1JY$ezDb+zG=kkQXb2kFjurXO`hf3MSmH{BoNTISnP{4P z$dz(_%)e3cX*3nP$ud{4sRR9@>5m7lG=OCWUcfS2SswITr6tSIhTmgyzj2}bTOJ>$ z>3)kX^`cxQ(saM$xMtGjgEZamqGw+8`hKeJcU*aITAGlm`z^)yjmMl%)%|WC%;P=s z&*RO?<8r?3Nn-=k6!5YkE|mV0P3;JZ;d8QHbe!wn#`%W!&K+E-1;;nzoHVZMBG<=I zJlAUe9L@S!5<^4FxKhAao0=cV_b-)orAMs8$=~puLX});%_y51J%Q&f$H^reCv%O6 zp^uunQeNJ(82d8HgTAEZiN2aF^P-u>Sts0AuEqSj53DQnm1l_;eaRSoHCX9I4U47e zzCPjjUyI{E`dYh(&!6P^>)4;M9&QidTz}4{%KaQgZtYws<|^m zqG&)B7aC;a@1PGv(e&aRw{P?O+!jRz^SMxu`!>C2mvu7M%u>rW>KuK|`h|1-@HE}m zi=RBH;^&;}xvwvFc+ziE(sW;sS9y|cMw;%c@_bKP9+sy2+8oaN(8#oZ^abM_yU+7& zC(pNQJl`s@zg%E^nz3!bYJ0bP9Qfh|Sl zTNz6wy86=hj2nF&OE22;eIuzUYNB^6xqRYFLHASCdOq(IRl%34KTlB;YQ|E{Y`%0O zd#c8Br@B!OAO3wGrg_YDzeWA6`q}+E-RM?VtLEu;)Q$SIx9Ywoo_3=uZLC^`+oxE5 z#*l66VK*w&!K!6`z0Hk^^WC8s%ctMEQHOz6^{PfJ{r0sR#c*F8s`EEKQ}|3E*TEvH z#?l(r!xYxTFMLn_SN!`XWB6SjaJiR0lr>kXem3F*u8n+{s-F$Y;!DL?S9rD!>n%^t zRJHnd_O%pOI#t@H@tOc{8gMXG-A>`WQ+O~v&S6u3-r~E+J{wF|ezU4#zp}rN8cYvv z@^4@-)8B`t_DR+Ke#3WTe&L*|`<=VhhtAbX)&0)=)rans_~-E!&KgU3x_DE? z)2RwL^pq>b*08B1-QwtQ8sCjjF!e9<4eeEf+^F2JjCm+?(zu`96wT*qeBI~+KKrC* z#?eAo{_UzUOh1XA<=>ZCJkF}B509hseckAj@m96VCyv(gZ{<8-{bU^&M`7;#yECKs z_oNJc8RbD=@~#JcO}F{byuzuvuckMBXissLnfp4zXPIi2O4WT0z2ZZM8KbZEzxdFk zlBv3{T8TasQ0%W`ZUyf~>tYda^0uVvzLsY7rf+Vi>b|TGz39zvJVx$oti_8)KTrKfUog(G={(`+l)&xHqJ@VlwzM+#q$$1-5Jkij5r{^Z;T1>Q}MOxOml?&E*JYGDp{m^c5G+KVx#xA;1qmJIczQpNb)1Y@VW z{`B3RWaaK1Pu2eLr_gQ5YDDXJnvo@dqPHZg))nHZ*&BbV`F*ll@H&p#@cpi}b|kCz zNpW}Z}p&*-WE;MG_NNeZN%o}&9e>u31~yC4{YJm?Bk#&7y5EX*{i$5Olz$xWu7h#3X`3%y z*qx$)3p8}6wneR~YcWJX*^?N zUq*S*m%QUfUp08nALKcYzOMb|PgQsEc@^#}I)&dE@jORg>52Zd=wPz$tJO_^qC?5L zufvS9Gd7NW+VMF0u8KRgDQ#7y&c)ICBJLDa$*QXU%xjpe?&Mm_s)k>RBc}&$w4K1LfVlQRnEZ?P^~-e;`Ho)ghM8ejiQI zeNCO}OQ~m4bYH&?_oY@>QgmO<+; zV|KEQsrmHjS+aaN8SQH+hg44MiY zL#nc0|1b9514_#x>HAhuQP;HQfO&PziivPzDIkk^K|xVq7}5+3j0{6CtqDwoAv1`I z2_xo+GJ1((4v0B084z^MqL}^a*Z2LuY<+jm%bs_~{hsIOIUN6|r|+w(ySl5YyQ{0I z)6elbj^qAeUsN#+Sd7l3n{Lo1Qt-G&zzg^~I z_3s1inS+-mQ=Trj$B!E5??x<5?z*|$W*#)q<{r5;*=VfqKW{tGK0eN4s7lIhkMBI^ z%xO!Lj;EK~VQ&twbBmTH#~khY`St;})p<*kw_2B5kMjrE$&;5R?GGxqaVHM22XD^e zPhReAdwOgbb&?-@+cTbk;{ue@$JoXjHk)pO|mMJ*U=}1Iul~ zJ^A+BXn#ktOSwJxmanf%>yn!G<#w$526y)I+*~cn?WhBM&2pT_%QR{b8J}N#+GU2* z?Q27axqLg#u#fz0&`#(2+hl%bL9VuLo(ui9BWKuOm-MmyJuY$ip);)LT^~RG?$xTj zX4pBNm%h1=^O#o5540591FhYr474A8KL=W4FC1uu1M% zdyI$EYI^!W+tPhYXl>oab9y)T@gKGQhAN*UC+6D=p5yDh<>hv6yL?;gLC-_}X}P`Y zZ=_DBs7tC=mfJVG=G%6jA8hWba=UNSeEZvrp2N-Yr$6?xIj`4+xI~=?aW12nrMSE?R|Vw=MBd@IYtj??#DWTd8)Z~ z0Cjxceeb%WmE*%*Z@l9;p3Btf?DKkv&ui*j>-c!basO~WrC2Y{trP$Zp;0SiNBx4+`MTU&)Mtwh|m>HkL_;C% zn6(8rx_@}Ozs-S-Sogqw*7-}1D|37Fb(enjQoY{^a+@;oe9u?Es3zE&MYs2}uPSQ7 zIJ|CgKbz`2GY+lCAlu2~AE0|gcYn|B(IvsAtY1)Mt>^k0%5BYoXBAm9-ygsRwe|P% z-k`~F;HiLZaLamD)%vWxN>ZZCT2a&P-l-gfXm zy-yzYK4Ff3@VdXDc76S?#vA3wo$PCzpQ=N-#$aT)KK1cA z#K$Lf%;(qfj?uB2`(Wt=d>G9&^zErW@AmY0haSG!@j8yFqq$6-c|NbN_IXX6^Q7aHhgTnW-|vH}z}s+tzvIw1sshg|-8Y^;zbdq)L)(G2 z&)rpFJ<|7;LMwM#tl2MksnF`WR)_WYmCyTIKc{+bcK81ue5TOO>XyYPbv(n?{@&jt zb)MI7o_F;)E`HnWgfp!8o4WAZ7RR1pk9=Df)})^wUT8N=uMT)Z;&ZKKb`PQHfrYmC zs_L+}aMNCe_TV+uVb5Wuzdf|GWA;NnJh;$fL94?aMW>?*?YSw{VejIJ?uB;z<^CRr z?`hm|cA@?Aoa(UGaq6r>`=+Qmtb>;M8?SFV&#Z$+|LqLx?L4!0apOJ3R_Jl0?8CI5 zQ*3S9X7@TK-(GBY9GTq%x$J>ro6{z{H}dgQ#n$D}?4C(pWwE`xcXlu3nD2`1tR1p@ zEGu_7!!F(^yVm|!?PXou>xE)lc2IV`{Nyo(cG@I=H{`MDw!^nWY@JqhzZ!3pUvSny zJG(qP4mBoOPbpr7HSDbFfws_NiCNpOd}*McTU3R0=*ja2+InYKh4ty2TRisoqN=cN zT{eB7zxPm;u%2CUiGP1mRp3FiVt$~dSZ-*w?p0!^|EVs}ntVcu9l5#Zef9PA=dDX@ z+V*vUR>wU{?Bm_)06E!W5??| zW*?y4afNp0M7Imil-rf<3vIip)nVVDYs*6W%M~79>iY@n_&6Eo;{^Xl@jqb2sK{@l=Njw%4nFUi z_`G8uV4UNnt~aQoxlEl~eO{mG^O`yzJMQK3S`MbS-?(po^rPkHoAmF^CY{gI;-re7x^RtGTbB9{Dp|#=MVf#ym+Bui` zdsTkk(V?r~eV$bt&K)}JG1N}EuQr@J*mot?^qJal?$GwN68qro+OW6$x4TPh!tyM> zZGV6Jpo71u>SrQ1b}q6W9(&AL$@OO!**X56EN3XU+*D*QY*H0y-SS3}J^fu};Ng6K ztM`+om4UY(4jW`IEvyVYf97^-`NNf=Eql)xWY5j64Ey05JFSjRi*uh3_VIVS{#F&v zgPz)}$PVgQ751fP{nhV(`TMi%QMbO;?{R>u`p3+QvmT;^eAuwl!(hK)b1DRXFpiUOv#~^z(Ns z{5y6!AZ$NiZL5Y3sb)Z`^qQqk&>jK@D<4Ww#RSmb7bD8y?EU~?7YQuR=QColKqD@se zOG@%f{e2LB_u0pu#v5lJyVMS{zmCq1LygHePLFeqxgC8S)TJ_tqeSf7IeiAv~-6BT3wzi zwft2zf!6zvl-e6V)&yGn+*WFTU#B+E`nJ5(hHX?EXtlVw)ZW^%Hqd%=XsK=Dz9s#j zwsVHHmcJ8M*TQwU`xVPiDzcXjsS4*%^Sc(=r3d?%@$;!7f5T-bFXxQxs}qZC(qUBz z=UKOOD6&UdSB1NNihE=)PIq(SK8MzIFO~Rx4Szq;X-Tm8M%X6{!TVjG&bF161O%i?K|46^>yDnp&K7Y?!w$5n>kZvLUKozJff z-+b^-gKf@`%0O%KL4)m>yvo4CgFOe^PsdgU-nJe;*p58R??gDyGamK5g`F!yTh{wz zunpV5??ZX)L|dmd)@c!UwBy50%kM`JkMynIm6+(5xQN#u9Aul7XYtU({9dr%`Q^9O ztx9bxUqkWRik78zg=2nO?)QSX_d3Mh9QwDxc461bfM0*6)HeL4Cd5#!v%_HfsIW4` zR!#qAkhMIkG8=RC?jZZ=lFAT^b@~&7?88ZwAx7){y9e1LS5$`Bt+#F(WUXdZhM2B_ zvj^GVukkw_9_w}It%GdkResmQV>U)P&xbkB;GLZ31qKI}zG+)(XZo8y#D{W!Z74 zF-bg$?#mFvbHUYq_xaJqA>L+#sl|5d{KX*-r{$%^*7upkAwK8sk;Qh(%Zo$Y&cXeQ zZO=CsC&csIcv7(quUZ^<5UrRWXzA`Aw3_WO+`i4L3AAq6e7GIbw42I* z>-bf}tbRyMptWe(Fnhq?{e)KA*N54f7yi2K#5G+~I@s>^yE(*Gt@5|pcWhG`;-G%G zY_M(BvNFU+?NT<_o`AK|0>=atUHNupF?ZcFH0@s z?}0*V+RvqSdv#5qHFLdTzL!)JXeApBv#vguq4mVZ!>rD8i9l=mpN84-{;p_4b0HpM z#0$0d@iy1T8*xNk9pCOa9+T9W<>Pa2AD`5D*zt~ziE+~02TLc!bB%bX?^>1G20qt_ zgWA&d#*eNy;<-$n9zL(n^Lb63vm6g~9QV)a-0_e5wxL-1*rpS|I_vmi`)lpu1l;=N zVRrwhnuNI7U1trmL$C0$;c>GiLx$Onu1krVwGP8<^y8jqz~g2o?=;MM_+A`wvnRWZ zo^u%yH+$T&QXA~~2Z)>9{`bUXVn3J;(Q+NeDYgiek=a@ ztuV2>>QAuxlNfCAKy0>nBc5D56U(i(5aX>j68o*T6BDjJAy!;{MGU$65G;P6D>*_} za)hqr2wlk$x{@PwB}eE=j?k4H8)`4{%v*ml%+?rQlYq}DcHQ;r;)GaemB-_aa@C2) zB=O9;d&nJ!_xwKN_xCOi_Yp?65 z*w48Zhx-oWFDSNN&u4iMt(YHZ>0UFm&OBteUFJDDxcjhE^WnDcDK&xCg1v@YC(qHr zy^JS!9Byq~$3pAYO^4gKel>yCUTX}uj|Tm^?c6&M58Ou(Z`@N5&)i>7Te#PtHgexV zZ72RveF7HGai2p=JU~mlK}$SCOKpLc+6XPRy`i}fk1_7cXkKuSMmQdm)Y15)j^-D7 zK;^Mci02yjW%Nz%(Fn(LnL7F=b@a`+e^w{gO5C^9*PT{kM|IaVw&~Ta%Tj*{EPtuv z31z9@^0?=Yli%{_dH&XI&TpA@rQbEq`7L)pQkMEH&EG3a{g%_eFEjZqdCmNt=$zj& z#P3(iM*_=tqKjPoXVJayJ5U$2knyvq6NpE{qi<6zlw=xQAS zU9BUat91l)wT^(U))COvIs&>{M?hEWh=$rb$G6D)sk)dBv7a?US}#~bDHQR6Wg z-?`rY)A6YfHu`(d=a%!$wpg#sf_Dcvn=)fVp=gjaefJC$p?d$ zd^2dtXM>h}IcUkpgO+^1xa|)-Jt6gh%buNJ@{M?^0C`2 zpOE_A@f~)seCD{%p(P&}TJnvdC7&5u@};3A9~)Zoy&IYf@fds5$D4e@v5w^{#$%E? z@(HOUUooEhu}+BR+8eGPuc?({qi+BX~Y=D2jz9??4XkI=^h5yezfVhbZ>A~GyiRF&+wAH#+mjKzdqFSF6QM{?mfn|Vt(R0 zKhV-1AhfhM2rcayLQ8vz(9#|ww6ymax4m$RkN?~rY~4if|J>f}UX#YBd$z5njyLV) z{_~3Qraj)TuN$B4{l>XF;=Ds~pF>M~u+Y-pEVQ&|3oY&CLQ8wR(9+&-LvtY>V|(~` z)1KsyK3}v~8IMWoXit(l+N+G`eykJXxpr~M_;gRTyJPLO#&elE+Eb;D_FCiqS)II0 zao;wS7bUjoL$@AlIzI*Ly!gZxW7Bin*4@UY=eC2+9&0+c-R#P-rgPhZN5-1YZEt*Q ztm)i#>(9rU&TX5mH_mi!`wpsP3v=qiq)q4s|D-q`e< z9jx>2iEDXYo!q&6Jl-hRIdwcH;~YCrJU%8pgI@aV7}MGG%2&svXVycj#-wN2&wnt+ zbjF?MIgxbs9n*^WiSw;NOJ~r~(%Ce$bY=}Lon=EyXWY=z*>~LbJw4ZuVgRPRIMx&! zaM`nCO)&!*&kdzmg2%mFF$O<-eZ?NcIg7xG8HoEFT8aUHmSO{-rI-O|DV6|QiZOte zVhf=pk;ve~Z(OG#sCaI${aq8%-Jf8cpPKf8)=|1mtrhkNEo%P3anL0Yt zr;g70;G;XyHz@TOQwcvg%hZBgvyB~DARohuwG=JUA1v1u&mJ&qMu238yzzf~+Kzg5g9 zzf~;g*^9@d@w8yY)7F1G#`l!6F{q2T9BYbAeR%(|rkK_0_G8mn))%{Y&huQ1>sGzT znqpsv4RBkKi-~=p$ZbR}R`x~bL2-0o#nC}malFt~94~Yg#|vG>@j_Q|ywFt~FLV{h z3th$WHq_oe&x}dqJi&^$%$)1FymE1&@pz+LF{1I9jB|@U+TQh2E(UU&qg|%C*vM5U zjxohduGMW!8cX?9AJ3DSi?Mv*4DW|r>}5wDMdm>&olKm||R)IacgzoU1L)!x{HE zv=oC1EybonOEIg^QYnenWIp0pv6}Iiq>f@TsiRoUcL{j^I*K)o`)76Xl*WDAP#(P4rZfI^Uk0rEGR!;OTVdYm z-U{iJj`*$aA~E;V zyEBe;p9>wXJ5cC$-Hk%$>&_ImKzFII5xQfA?aMt=VQX|(i?OGB9AMq;g0Ak7 zL09+4psRai(A7OM=;|IBbajsmy1GXOUEL#VsJ-YV-7^B~ZV_`__mblAM!D`N#bc83 zth+YMYu&+NzUyuddO&w}&=0!HgWk{`AM}at{=~FmexRkhJkZh|9BAooPS9_;J3G+Q zT^?xZjt{hS_a|;UdR2Fz(6_o9g&x+ODfF}MQlYnX#|nL}yI1IW#czXkXDaS%KPY zKHZyU-KTrgtow9tnsuMv~)Kd9&~3M-gK87o^{8Zw&?CT>k-{;XWgwk@2tml7oK&2?#P3650~HSEdy2@h!UF9)=uJRZ_S9uJet2_n`wU>3V?zw|?x1BYn z?#0LBjdIu;&+6`ZOe^LGTDnUP zE!_c!mhOf_OLxYhrMu+N(j9YX>F#;lcGmT}gU@_ba;`Jtsd{?O9h|Ayv5JjPfr>rOiBXx&wh$0T)h zC!IRFs~*q&SSQ4DjrG3n)UywuyY}&1rjG8^Q%860c*Tk0-nY&YY+Z7AXhBzbw4kdzTF_MZE-B8flw*qXEajeJ|4liT!O9sG_c^qb0}5Ko4FxUbjDnVONkL0Frl6(VQw`09 zc#Lsgqnt>b<0w~BJSM55oJiDBuB3SG$2uXNYn(SJrxWK;%Jme_W$GxW6Lpm9Dej-u zc|RrY+lKPJ$2Oh#6XmM}D_7!?68ECKk;J_yZzORq${R`Ci}FSi_oBR! z#JwnQB(V+3Q3+P=O6n-5CBId!OTMWbn9x#gOn6YvOn6f+O?Xz0P1>T|o5W)%w|Z^sV^0-1*d0e5Z zJg(4H9#`lpk1KSQ$F-sM5*MUApJ3(oB*sR0LF4g8xpIWYW0H6h<+>!UMmaEvw^43P z;&7BRllUCv(j;z2IW~#sQSQx{R?H8yluHv@%7F#pEqgdoaJlBYKN^^=jR<6-_ zE>lN2MTwPCuF<%ER_7h7xNoVi_X0SJ*E<5SO($NoG4r3txuA)sRX+LOGf#L!x$##g ze>gF{;<=$5_{4iF2YX}Z36FDeH%7kwhTgeoY&{n1%y>@yp7yk%Ik-A@c6D?`Y-<|Z zo;J4L=3OMcT@t^Q6YG}7STDqDlh}9tJ=d)b`MRsKo?RWEJYLf^_PVvP*GIg2rMGF? zZ1T(7OtBB&82fVZ9$>sj^n30PH?*g;I{U_}v-cJ6oi_IVaAWU7HuM%)yjRv3=U?$z zTYMJtd!EBKbaulT>;LV1c6H8};xo#|K8J1W^S*}Oo{P_<8Y9jmj%lIK{~Pg64aG>T zaDM)8aZrqH#TRit_^)C)msIIfENgk)OKs>5AZvf+8)@u&vh0`YE^1@k$86~B;P}p9 zW8?vda}LCJ(tpo<6b;>BU!6P^t8>>r&ehP^`6%L?4~>!cfH!3IJ~ex8!tvew#>lr5 z=bMUizmOYBcge{ar90-l-KM+eyy>Pp>Adx(yXxem(jE5I$@|n$u9(%y2empmZQ>kI z^y!Ay;B_Lnrn>wv2p(7IG5?~na8-H+^4IP-*|O$wDPW#)^y|( z)?H5W3G0q0?>g!3=l@F{V{+K)9%5tU%Wddg>^P@uW8`U%-zkW5hX0=L1vHdne0AOt zSe;zxyeFc&c#ZvDKx5~nZ|EKNICpwuyoVCM2SlIiPRH;0E>A;md92QRJ&bML%J5XV|iD^6d=Ijn9~ww_zXK-18NaNBY1?y)0Qfn@?M@ z$K=^oO!EKByJP5N#mS??6}!$Gd5URo?Dy{)dNXTv-o?XK>drz#Z+pdW;WhUAcjSRr z{Cs1)v-Y<`{C&DvJ?;7>{(j$-a_c!M&;EL5eaNq?SjxtD-xD8C@xb_miqZW&-PS0=nd%AdFOp~-l~q@c5m$W+{x>!c*w?hH+-(=u`a4{{=O)ZP zu<{fBr*h>HBd1(^>}kij9~(0VBYW)1_t;P_K4MM(ojjK8`Twh&dz?WiZzpFHzgNCc z;@Olpk~0_O+~&;XKar=Ac(zS07-qNL_RxnVs_5ac1|ga*lDQdq z?;-}^U*%Tf?&QCdmyDQ%f0aXt7zw@AMeM}ymH&-+Hst{$CPZ&Y{ipJ75zqF@%rk7~ zx9SpN40??pVmA-;_v1Y7Meis6r*gayBd2!{iQ$QJ7Byz>AYzJ?r-+!Mf0aXq90mVQ z{v~3Z{#C9RVy={1hFGlME6)}2Y|3{;jG5kQ{7>ZKmO3^cZ14KJ z_KlIt0{)dNgFcLNvovOo6lAA-EDhz#_;>TnG?WvAF{vCH%!S`8pHE}wQDJP1@^=rv zTW49qnCVtFz^)y;G--@G`|+K3baI@7qA_zpU<;IYqM@7s|872whVK5yxdO1QzgOOp z#?BXkttr~EpY3<)`w2GayG{Gs{oB5uG{)WJ_--#gUVPWSG4H(NTk3v&LwBG5-Mj$} z-EofZMB}UfUilds`(8Z0>odc8+sL`g6MWi5f9+#m7A#L1;|^wghmkd7e5bfE@Ak4* z)ji^d?s)#Y_oExS%NgJOWbOZZ-9vBe`@gJ(KY6j2H5suYVU7IAKKZuqu`9wmIQKr< z%U(ZsMR+gfx;edU#po5`9hqIO?B(yjuL$qUG#%f|W=viY-kn+JqFy$-d_{PVX3p8Y z?B$s&5@O*xkL+c~U$r73M((d?_Og$!ToK-KnpoA#b}3#F-aoo|qkOye)D_`fq|-9_ zc0l_T;k~4B{qwEUfh)p0N-f9b+nGD92=6P6yglDG{PT+N?$UWr=i7jFR)qJM?s_NR zUjJcvc&BO7(tI1WYI%6e>Ae;CHsh=133ogf=P-L^!o1ZY%$}PtcS!YH;@pI}bE-PL z9V5)1p6alds5TPMrZ)1RM`|PQ9I1`GbEG!%&XL;4J4b3GcWl*0_C+Nx_A}Mb zyp^N==M5dng|~GiFW%gd9C?dJ@+B@#a%XSt=hJ%Gs#|=V_@0|E`@p&{&pxp3mGAKC zf%gQJ z4}tdtl@FowtSMCQfJak|UTUcGb(d-&2VoGU3W4d+VA-}3x=)6%>yyv?e7FQw~DOY^|Y|9NVfABI>s z<&7amPWfawBa`jsj7+(ec$-+cm3W(2xs|#)R&FKUCRT1G-Vs)ACEgcSZYAR4lv{~2 zJLOj5Em7r5A)ZZnRCs$-xr}%tSUHY36I3oE;@p(uh%-dxb>S^k<$K{wQ@#*qo$|qm zXOjQp(-XY%YRo)@aOqF+tcsAu1;>}a#z~Ky6 zxodb6Ryl2WD^|H~ctch>aClo*xp8=NRylJx`;$+?nV@_X&Z(9EjdN<{N!#}2>1qD7 zzq~p<&8xgz$XiY~vo7Qy1vnjtH@odWPM?9PI`*o<9 zp62&!`lP=#ys*E0|J1UCSPSL%BL+kH{fK8%9zSA2lxvRn+?6Aam=NWTBPK*S<#?-I zx#sHbDo=CJ5f`W2bi@*9jYEuq);`3&D9n>M zO*wmsaZ;YrR*sdwl$a~+)ewuNJtE@Sv_~}M>GCv>?p-&Rr+IWY8e5*`(akR@PxI(@ zJiR>4qkGKJ9=CJ*0Nd)kr3o=z%A-p>oATunW2Sv7V$76_bxNlhX^z(WJ=RFMTW>pZ zMw-)g`Jpq?T(7J4nvv#!B{oTWCd4dhF9o{V-=n_re)ApW1Lyn76AoSF4~HM+6^Bpd z8;5`G6Viv;tE3N=lb=3RPJa4OIr-_swv&tO{n<+r`f&C=MOHO^NkShgCqI3toc#2m za`GcP?U5o=<=IBo+EZn0Ck#fMtig9F`XBnfAqcvdP(nYps(~E2YO8JbfDk#eg}F_ z?|PsQb?$&p*4YO-`9^;mw9x7kbaMMS#n!fMeS%Kb+c)TBy?ujD*4sDeWW9ZZPS)Eu z=w!WpgDudR3pPUUSztSKMuV-fZeYuFW`vE? zSrWEYXIR))onc{H^)3vyRqw)JTlFpswpH)KU|aPr47OG8!eCqVE)0Hx&f~D}I!D9q z>unMI0lhhbpP;u$@E`O>34Vp%F2Uc>n7kr1MAo8NFkLpQHD!@PG8~ z6@HQ4!@^(EJ6ZTqdOs_EgB~AGXQ}vjUr#8pHNUP+@bUD<96p}jn8U|wn_pr}H>gYS z@$|+VKHj2&68pMoU4oBSGNQx=ty!1gP-{x+b-llaudesk@YVJH z8os*TU&B||`)jN_biU7eLFe+UBlLzB>kGZ@#kxapez6|WTVSkH^hOx#7rh;Z@2WFm zd|I6yH^y7x@mt%h85Nt+*l*CYR#i+$LvN9@7S`LT@!R68h4pqSYh=Bt+R&Th@f+o= z{olTJnEhN{ld$$zj16mly>rUiU+3aMmd+wrQJM`Z7l5MY^Y(I7_wilmzFPT#}#lCobuzmT{d&#bw zPqV9j9%LW%T%5H2tFNtUitNSe#mR&%-B0PlL?Q`u$qJW*%|LuC!f6QKGG3=>~HgGLiwU&^KHi~YeW6>`{&tS!|K9!cD|;E zEp*$&_s6f*-KxK?4|I>Z_B4CKeHHlG;(~5Ad#j~^&&TGRYBNVH4gBA?=c)F@-AfbN zwc>|U?9>HIlgU4LUd>$jnsduc^~YQ?KK;(nq5hs=?)y88_BTXwbYFPF-vY?-bK1dU zOnmN8dAW)IN0ZCbc2TbOQeXYRcho<8U;PGM^(XwOpW##e5C4)&_udn1`^)p}E{})b zXvhRBo|$K#cCSlDobNGOx8&KgUF(v)Ci+{z_vTse&UMM$>-_E4hw|*b6YG*&@0(yh z&&{*;jxTs>f_?Tto?ZXT))g{lYoM6kR_;2&- zk~`O&Xh&a|XZsg=9R7wA?b)I{d#R)@nZCtD`}(9jD?PU^**g=hP)TF7tPm7xuJK57i~Z7nj-E3wqjX z6^<8`**5cf+M>tnlF?6<+3*K?TGuD*lFc42vlH&?X~!>cy0?4I&-;7YZC-xiwVuoI z;hr{PeqGXGTA6(`zo$Lb`bxG5s%B*-?o*mSuE?N6nk6XJc&ni!^OMd8FW|=v8HmFNo z(rRIumGt%fYPW-1_A9dsN90@6%W9MPBg*W!bMmeJ;@afF%gU_6@jZ^unOSBpkIc8y zOKX#wMpJ`&!@U+zWs22ZF2laW!8FCFT3FJ+T`?4%Ix~eUe^D`+T^T{%WTOL zz3lY2Ym>V^@V>pJmuFGJTA8ej)-EOK) zn%p(suH8T1=G|PIobNfkw>co+MmugdeY`b0INu(=u{K#SX1ra}I^PPfuT2JD;P1C~ z$hUj1u1#inoLE=q{|V>+wjtxKs&~G<;_Z5^XuNGX%-id6Q0w*ew@t6iw<|{0CZBg7 zZ}&fuZ(sJSO~!Zi{GT7>+kq$7Cf}UwZ?=A)Z!3TYt?go>JAvMh~k=TKgDS_*f7_e;+&h(wgMuK|XG0^|7{-YLebA>nRuau})XjB%hq?x@e%|TWXTF7nIpG zC-kwU_h<2+oAuVdg_TPHn?oiU#zH43+`uy=xef^GNO_0S=)B9SFU21}iet5L6 z&D^9W$ZqJ;zP9qm>LAlA|J2WhepDS~{aUkr_Sn+uFa}QFx1YUORUO90^{x8Z;ABV&(>d99md|Ko%-49FIR^#`Q7pT>=3WR{5oL$ zes;;n)nVQpv3-C0suL_cfuW_6gG zZM|J@dApdiCwhCo@%A#8H}}21p&wRM2a^R)5;8}xit z(4`~qE3kJStqMAJ!D9vX!rZE$d)IrWz_xjyD(K`@FBI64d#i%3?(KL&pYc?IJ?8b%`L|aT*u00Uf-QLd?gHB&sYg3#;e!t>YyR6Rmp?jcwXfX3T;mFs$`bi+=X8k+Kc;CCF{A(-Dk}Kw%1?1 zpSPZ9eb*acpX^qZyw`l9{j~W2du&JdyN;h|lXo0oO}48_RuxRNZT1{s^S7)@`VO0D z!}cCv_ia&?EV*E!*#F3q856Cz*#P^-e|y^X6YaP^53nzH zs!CqE&FeH7U_0zlm2|ylqD}j<&<@|PDw+GhMBA#q&^B>@uX+7M+j?1n9ddJ3a?V4O zQvC7VldPS~{ScS?X*W-@%kC|(_K#I1>t8v^ZoR6&{`72B(sSG-J7J8ElUJ&eXU>^q z>z-R+v)^<)z<)cmz}9@PD*2$R*BM-3ttzXMC)@pkmmcs-on<@x^4k+P`sJH9{4_D8 zbv2^cUlhZNQAaY=*A#2FtiR3LraC!nyD4`5 z+x_k79jlX3>rb&;UhZ%E`n>pZ)nr@aIgk0--F5H#lkJ{o`r9!+NA`JRvOWHMfBWZO zs+0GhoNU{^+TX6#%8Rt*7799%gfsd<_mFG^j`+5~vWnEQrbgD^Do^$k6lm6VK(^QjQy{hX}lfM11+tgGKSD!Z3q@M?Sx%Bpp zU8b7!`7I|-HR<`g|28$%|3hDxVzOoBem*N3_fO|d_TsBer<&|Y^Pi`f?8`Qvc;1zq z-PzI4ZDo({ePxQtP940!<({)&-##)XW8d46|FGs>(@cKFyZcQu`5QMJI?d#V%xg2v|84(PQ%!zd^}bV0{@$^>`EPT6;A73En*76o+fFt4jbQnc)RCXbZ{>gTP5GtJ zlD`TM@?+sm{w-~hKTI3tC)0NM&-97>YWhn4Hhm~RoW7NRPM^zfM;7wuk&*m-WGDY0 znQC2tthHWX3}_v}*wFfdF{5<{V@c}~#+cSAj6JPi7?WDpFu$}$W8P`)#u(N*h_S8p z5o2EKCgy_HQ_K;qvzR+te=(=DE@Q4~y~Z5WI*z%i^&N9o>pteP)`QG(trMC1T0f!_ zw5~*lXdQ}f(fSmfqjf8~Nb6a2l-9ZEF0FsjX<8Sf>$F}*2WlOSZfu!bU!ya%?nakt zJ&ummIvw4s^*cIQ>w0vx*8Avi?E|3OwLgH)*S-O^K>G>UHSLpN@3iNzo7;|`oww>) zbqTo4*Z$j1u1lzMhvnHN7yJ7C(#dwwX^zjTORktW*)pYhHnO-bS#j0m^qbS>c%09b zd3Lt%z3fvl*&e$!&$jZtmwkNC@S^+j?BPyz$$GV3$M;(<^!=6tzWfDmxbBp+&W77e zNq;+gPmdAGeG_|K_fZck-@ZPW6eS-f`e_0QE;^_JWzvANadRX5R>J$8p<45+eYdX~@_#yWe z^{`jE)+hKUJLUJVF{jrj_$@O|>0vMB)hGBfZMyWZ_j=VQ_&Gzn_OQP@#{b#x^d5Fl z&-w(vs9m2PHtn?f1b?Z2aSxl>r9Q!r+V9*RHsr+m1pjLLaXqY4$NB`nYv$EG?7SoD zgWq_?%%0Y5VO{Vih0Xo6g}&#rneX|m`fQ>d`a(~;>fyR%mmenDelfw$Bpmv1x4=KS2#?!T@sX|mTO>%4*Qk6l%l3~4>dUfVR!n$D~XdxL9jo@X0g zQJ1vI`=$KWA-~k$^}=7ilbQI-_s3lAZOPGn;Fd`#KgAv+CqD6w)h>KywHIGn{eX|H z{=xTFzu}XsKk?Po&-n1_e|&q%1)pE?Vl5y!vPO`6SvyGXtSK}eSZipUum;iiVQr#u z#hOLqjkS!%A!{6s&o0e|XV&olz9@XX0{ru-?b>AV%7FP>mu4$NogtfzzR~Mc`2YWs zt6%X;{rI=>H&<5h4gT}*g!=kU^xI#3le+%>4774}9LK+nznRjae&G54{O$0-L$*9_ zOWej^{Z@UFd3@t$ZQuu<7v8;Xz(2k4&b+}lZ5Hs`7j&)Yu}9N@AK&=uify*}H2n6S zYoDv|e;NA9%PRbDq1@{}>c0utzwxMlt2N*EZ$C<1u+yY`p30#Cram;ld zx&8^5HbIwi+6q5l`T#z`^bNd%=`(l*)0glHrjO|du;dPw+*J+@)rSU{??400_xT5= zjK6`Y3k@*efCd=;p#i2}qVgd3T>T(-FuX_K4|1p6%Yxj&^g+aDph3B0lKoCr?kbP^ zA<)owqJ9fuoep=o-O%pYgEL@g3M1CrO za$(A=T2-g@W6bZVPaSZ}y@oO_ZeT2pzqKUb6DCi}4BdN3z^#if$&8*iINeQ(QW zU5-u5mp^$_TEG7CBLe0-V_s?PxXEn3e`UpCp&Yue3_dtu_^JEhz<}ZNnez__82-2W zY5#y}m&%)uza_1I)IIm5-#PIwkEP#VW5zQ%x}$HXN)~3|hrSxtyUlk39HZz{qQ()7}Y~e%|2GHv>jq>wfuKz*%`M%GP&z zop8v@j+@M;{OCb1r1d*2d^TXdGjr(E+4}zd8wwW$4Ba;Kp9mO!I$SE`Nso> z|N6_bIE=|$Iqg+_`a$2JfAoF&O>~i$_@ST0C-TbjKl+BOycT8Wk;{wrGL0x#KTu!& z!*|qgd|&+uUG+2ksQ=+pa`~;ikR5WQjWMP^<&qEi_07RqOnZmEv0EsoA4asyV)|!6 zzg4^bORffAk&t4b1n|pU_o5!;ktO zJ|&mm$_v>cN7@);>QgQ`f+a_=jN$rdq`S-)+Pss`t;Aow>M9}Go|Rj z@O|35U)KXtx_b}bKjo*_!u<}1PwKoiV86gW-?`~;`=#xooc2;qefoj=d`JDm_tkIE zr9Y_yKk8@rr2qL2{7Wv!Zn#z|uWhC_Nz2#Wc%4*UlZURGe&?U}HBIH!`MLE{x?OHt zKjmkqzi*Jr>(&Q0NagkJTN{LS!5ih07xg7Cz9V_@eaQ>Dk{A3)UhpY-!N251yCkoF zT(U-5zTK8TwNd@GPyD`(zSHT&Z`$blmt6OC8__+#dSx5&^TCua+elt-Kl?=+_@_Td zjQ%3bd)h_0S4L=2!P-*S1l4%gt^G_2J>f zcW(^e0k75Lmh}5CUwT_g_l=`(Px&dDc1OzRxxMa8`LCLNXWA~x)n4kWANY>?hwrQ3 zpsW6bANm=7;8Xn%|B@H&lDu|Xb7orpw?CDq^$$F1YWkgjJTWQ#{=MZBQo3{A7$5jS zE?bNl7x)A>Nyeu9Uw`)4v|W@-UeuSK;XBBS-|~IQ3%ZgQ{77E#Dg6fjlFMzIFUm+> z+aFt*QF+-eD>9Prvctd3@E!W+p`(Ay==-04yH=nJ4?mx`ZYr<6w_HD!*9o_8kn;cM zL;jSui*m_}`jQvlk-Ydm^5Xl@MPBd#Kav-GA}{K|zvM-`B(IiL3)1qZ*LgV9=R3t8 z+>w6g>gpT9_xVoA!B=KPx9dJrGw?(CPd}7pqz4{eG&Ups(ERZ+?9T??D3`pbFM07D z$&2qJFTM#~^(XvDUht{@hkwaMdotKF**LIlpD^DB%ie)y@4&KmVA(sc>>XJ44lH{I zmc0YZ-hpNBR8Ie>KK%xky#veMfo1Q&vUgzFJFx5>SoRJqdk2=i1IyllW$(bUcVO8& zu>XJ4PUVu9>>cH@cVO8&u>XJ44lH{I zmc0YZ-hpNBR4#eR-cc@l2bR49%ie)y@4&KmVA(sc>>XJ44lH{Imc0YZ-hpNBz_NE> z**mc89a#2G<&u}|9p$ojVA(sc>>XJ44lH{Imc0YZ-hpNBz_NE>**mc89a#1bEPDr* zy#veMfo1PhE_un`Q7(H2mc0YZ-hpNBz_NE>**mc89a#1bEPDr*y#veMfo1Q&vUgzF zJFx5>SoTikl9%iq<+68R**mc89a#1bEPDr*y#veMfo1Q&vUgzFJFx5>SoRJqdk2=i z1IyllW$#ojdCA^UE_(--y#veMfo1Q&vUgzFJFx5>_F9;83fVi#h2#1$W*VjLJY{0DFZ+h&QfLULE`N7cvv%X$+LKd^WF8QQmC_lmX zNjfadV*CJ=vp!XQ)~)&u>sfuDb*|{Lz7{{Mi^V7FYw^$e`j0(||5P#rh{eE!LsSt3)ytaWz)g3>C}-;2g{~YM>bvM*mTNe z(d^u*>tdMI(1~z!LsRK*>tdMI=_`o2g{~YM>ZWSn+}#u2g|1OTiJAQ zjNW7#}f~94VI^!IC3bas*3`V960IIf5leu;i%nKYX))-#63Rhq0u!4_Ip- z#*)@PV6AGy`i;HU7t2eS@gHN!k#flqEIEQD zN3i4wmK?#7BUo|-OO7hnyptR$|6>hnVNa={HLUiC7(d!00&9I#_$@%n|LSQ?9*qu=dia zqrG&n_R^`Ny>!a8m#%W;rTRL9&|W&_+Div(FP-0NFCDDCbn0j?opSA^gSD3q)?PYT zd+A{9rSl!_rGvGX4%S{eSbORGR(t8-#y&fatlpUj`+JNR`Vg#mkNEscSTV_pZD!vLtbISQ_Wi)x_Y3uN`+i{U z`+>FZ2iCqH_=McPAJ~1UuR(mOzO$5s(f@KrI|9?LVyWOrzE-M&qW6x;vICzudGi>7g z9}@7PNwK{)I*Z%>IM`l0C5smwFxaYFXK`isLH5jnSv>KwB73W47H{>)KzsG1EH3?e zfPH;l79Zcib4ERq#V^h&w03L#7-$vmQ)rV<&EgYVpJWGY+cfaAa8_sQRglFiTXyz* zC0YF3#+_}$P1Xx_ChpwX&hDSZj~92gHy+92rYk$!jP=(Kb@J~%$$FfW#d}_PvVAc* zi%-6@iw%1wi)Yn#wPQZX;+OY6)!MJOLHO-A7j?6ln`iN&#i!ZIO|tll{kmJpkJ#dSmdkLHZBId^1n_ZFk=s*AGtk^4v66~|@qjm<8$tvAf#c0(?a*DtcmDzbQ9Ns&!@J&UiXF0!NRvv~R62if7vv$(|*gVORXeaxu-KIMbc@0|MO z;Pm@Xw=YiVHo2rY_uIXa z#nAoJEm;gdgD=fu`0RT|7Q_GTy|S2gJ#=~&(_WR+52{c9=sWbAzE6LOF8wTi=zsBv zT*Uvl6Hl>+cFvCB;oVNL4Gz!ZWg||pQQfk5)lH{Z$I>i5WcevJWlR>|(Bf3PYgQI7 zoOY`HcxM(b{r*&2b6yrdIk21MJ(0zmE$(LTEXd;C$Dfv#A2IK=wEii(oSuGX)cL2U z-~Vjk=_%d)HtnABbHtI|Q$FwR**)cdW?}cVU6l7(J4=`P|6Gxs*L-L9SF)Jzzc)9F zq5JskEQX&UQ?nR82VIuM@W080Sxmd8otMS5SLO7B>eD~^4*jO@)1RVCKZ_swUwk4L z@xMif3#{go+}u3z0z2qW**QC8@C7y}H-9g@`T{FCGFzThU0@ZbX7N^AUubU)%HlgZ zTxh%hBa2&{eWC4rc^2<+&xLmB#4KL8;zCZk0FCHh(mWH}5vcc6&C9Kk8hZmKU}elGeX^y`kxMCf!<^e*c=-b|M+%U4Ba2* zuNCYI{Oo&H7Q^Qy?XnpD=j@WjwCl>PvY7U&oPJP!`bXcP-}HU@Q*`NP@k9TMPvips z7hf|ok!=Obwt{6_!LqGj*;cS@D_FKQl;>Pr&j|!17PP@=w6> zPr&j|!17PP@=w6>Pr&j|!17PP@=w6>Pr&j|!17PP@=w6>Pr&j|!17PP@=w6>Pr&j| z!17PP@=w6>Pr&j|!17PP@=w6>Pr&j|!17PP@=sKbeOG<#K3M(SOo8@=w6>Pr&j| z!17PP@=w6>Pr&j|!17PP@=w6>Pr&j|!17PP@=w6>Pr&j|!17PP@=w6>Pr&j|!17PP z@=w6>Pr&j|!17PP@=w6>Pr&j|!17PP@=w6>Pr&j|!17PP@=w6>PgE}ZF8_pb`6poc zCt&#}VEHFt`6pocCt&#}VEHFt`6pocCt&#}VEHFt`6pocCt&#}?32iTfn~qIvR`1? zFR<(vSoRAn`vsQ$0?U4ZWxv3(UtrlUu36`D&OHYEOC&AK_ zVChM)^dwk%Qsw^})^W5&@?sn|ge6DnNRD915iB`^B}cI22$medk|S7h1WS%!$q_6$ zf+a_==m+7LAIilWSmPY5^B1tr zU%)zl0qgt)tn(MJ&R;_Le<-#g=0C>bnRbb1uy_WGXRvq%i)XNS4(0!WGovvl9GF@A z{H5fkt(bXA^UTa?%L8t*fAh@B2R{tB{hJ457CrTGz@K&7FEjnd&jLPr(O#K8t-lQT z)E>KM{&dDy0nguK=gjweuL`(T{&ty9^S}8m&O~%G5#3BgHxtp#M07I|-AqI`6Vatj z70?LnnzlT&4eV{IfCkvxQ~?dJx2XaeU~f|eG{D}b3TS}6O%>1pdz&g~+i!48m%bET z`cic1OVOn-MVG!5UHVdV=}Xbgv|j)5iXBGX6X>4x$^43q*1jv?Gdn+7(dE$F1Ge24 zR2+QZtpWeJ&w`5gH@zv~hu2w9aqY_M1D>+^lNBSrxhCMVrp>SD-16#x3(J#=k6xbn zTO8BPM07I|-AqI`6Vc5?bTbj%Ohh;1G%K8TpzFL;_}>C{9xMDe0Xy#%{;hz$O%+Zf zU~g-M(+=4Cpu%|y*!!l!c@5b6tit>5w>YMoiRfk`x|xV>CZd~(=w>3inTT%2#|UF3 z(Dkvy7z)_O6k{u3A8U-cfPD-y76bON$rugT$1GzvV4p7)nx{U-D>Q#29Mff9h%WO* zbeTt@%lr~u=AGy=A4QjWD!Q4G*UXrA&&tmOKbNd=^}K7AtPJ?lF*nRRb7HoQy?&T8 zuWik@p?sqa9-No=*!KZX>N0=csoVS*@X4hw&AV_(7H{yyJM)US{wb8dnYV0StNXI$ z5sv9*BD$G~ZYH9eiRfk`x|xV>CZd~hTCGLb%Ug>duisjH`gdB3fB$}Kwae+YR(qYF z*6Ii6v$gui`>nP5Ey6Kf_z_+B6kYfiUD_qOv{!WL2hpW}L^p%Z(D+AZXkMT*G+)pe znn&mi%`bF@<{dgi^AVk)d5X@^{Ecu-mw6$&%oovR9*HjVOLUocqRV^~UFNCi2Aa}W z@WS8F$?(W;!0^tuz_bY(VA=|8Fns_|VEP7L!StE*ZG>aGftMWJz+;YX;5|n-v?)h7 zv^7UJ^g)hp=$jnfU^8W3&>6Bj=nUB-bcXB{Iz#pgogur1&XB!BXJBh-7dk`sF~Tuj z?2hPSk3<(cCA!!z(Z#NbF7{4zgHMs8n_=uT?%{zs!59TIR~Wls<`82V%-mwEgPC*8 z0WfosxdCR5GH1ZdUFPs_a7;H7(al73GZEcPL^l)B%|vuF5#3CV?!1VffOGW&&V47~ z-1h^{(G57qPrx}o1J3o^Z*fdl{7^@H1{~2)iv5|Z~!ZBTqAL?ja1su`UI1J?xU5(pN9?=cD5T5|L zx%nP&P7ef}(+>gX^hUrreG+g^&jg&)KLMi)@oD&egk!pz@6?eV2solEy%EYIy3#YD zJfaItbQ9&lr}MuBoYS8H=k#j8Iei;&P7ep1)6W6t^mf2GJMvo`)0KXvj`ViG5nbu| zP#)2hT?pk7UB(EyiSpnJyDS4n7y8%=7+vVH4;WqOV=-WKp^ue-(S<&C14bv|qw`I4 zp^x?7;+SsGg*m!G7v|^&U6`XAbYYHe(1kg=K^Nxe1|6KE8+4)1?LaqYuLI86@qlyo zJ>Z<(4>;!!1f25|0?zpl0q6Xg-{P3A`~>RAe+W3DD}N)DM|9<%gz|_kIvD?r@(M4< zuM61u#NP|pzk?qbu(u2UFkq*P-x#p>1O8;d-aq)60q6YB-{P3A{5tB$-wQaREB`Q* zM|9;+hVqDR(1jW&Ie(Zs6*)gS;GF*)aL%s|IOlH%ob$s2&iUs7=hh3q#W7v^;nZPV z;hzT_(Um_R$|Jh+|3i617as>-hjP}G=){0s58xXG?DG_#DPY$d_)-D;yvD~0*!2v) zSHSKQv5pHET`0X2;h3)0P1M(VD&UB&)?cAKqO0{z%#OyAH)VERmUB*HOW{6o=2Z;LMeq3ELLMHl~2bg>Jfi@gxtpbKR; z(MiY>e$YvbEigI>*@MwZj72ayiLnA^>@bGF=p@E8m@zK9AK{p;_9dtvba0Mt(7`#n zK?mpP1|6KE8+34vZqUIwy7*}o%x!pJt~2+*=m2y97~Q~J1*0?29bj|`a~q6~LDzuM zJ?J1XItktM8ywTcKNMa3BGJV^6kYr%(ZxR$UHmT5#UB%0{50scj`#^US3ls~cLL6R zKj0kQfOGr=oZ~a#T)+Jm$8^OHb;M`D5nZ(_lt*;c51~AwoB96IYb$>K$A}E=im=9i zC}-Z|mq2&lP3KkIGilpU9^qhnbL){9S44GUoH_cY2P<~}YU}WwZ~uC4#bvK#@ydtp zsCaMZ?DwxIxwT^3+U-M~T}p4P_{VoU1zh{qbroNpoZZtqf9|Y`51-v9ly}|hstVit z;B1}4XI7LRoeB7ewXUdGzMZbD z*z>c3fV*6Kb;VjYo)K`=Kfmg$s4bbOEt#k-nW!z9s4bbOEt#k-nW!z9+F#m|iQ1Bh z+LDRdl8M@qiQ1Bh+LC$a(q}8i9@B;KP!VCxqfj1=N!6bh)d#EoZ?V4lf7Gv8cR@vm z13HHCL+g@?Tbmvd@D7JnRNPm%eZV{J`f$a2JN)nnwDx}N!HUBdJQ8sIwhvVFx~y-& zYj(K5;{7%=AEr(Yw*=?vw2FQkaPFG{=V-O2PL79wbG!u{^@-X-c_!jN6Y-yk_|HWA zXCnSH5&xNpe_{An9r)C51CIC?t-w#jzjzDfKBvPNrHv5|Ynp#$$9+zR`APi<|H^N{ zp2&BK>inv{&*=*01K;sEUBP?+`<$*|K7f5rS1=#IKBp^~4`83u70d^)&*=*01K8(u z1@i&ybGm~00QNau!F&MwoUUL#fPGF^Fdx7^rz@BbV4u?!%m=W~=?dlpIO?AmXQH-b zqPAqBwq&BVWTLiYqPAqBwq&BVWTLiYqPAqBwq&BVWTLkCTLfuaGErNkpF_KHx)&^+ z9Li&VAg9wpd4#3^!*6r?|F?Cd14EshZV7dAIw#+ew1J3E#fOEPx;G9klIH#)vj`~NoiE`=5fTOlZuZHrdEz-lGJZg*d zb|{b9B0V3`N$*+Jb)0xIUl9c#bgonYCglkFe^aD^x$|ja;4I z;#mIJ^PqcOA7)&i2kiPVc*M}L`=Rt?( zaM10!I*-6-?zaKwz8P?i);#LucnCPhTfkADh=0ms{?X^+9~~?H(dXhHoh<&*)#4u= zF8+n#Uv=P9zYRFzU$g>05&z;Xl>6Mwpr>eKgqf#7r&Atb^gsq3O?iaT13{<5PlV$- zG0rUO_F(3-_qPt;`EkNMDSqhf+tcqqcIqvec5gQebv8d}c4n{ZcS-r&Ys@JOvHaC;y)AdpNaU-@XZ|mnTY>P#D6B@KNImEaE|{_C&z#IZI1u& z%^d&qB{BJXx*Iu0n6UtVp?-vawU39-E?Xbf!N%#g^dEeL?>JxZ7qIgS-vN6& zXivZ{pA@^?(mF2B^tUeO^qby)qE+GJg8mKP@$o{x2TXfi9s&DULry7n`K5LKRsTf% zGcLqKCgML6@z3}Y|BO5F&v^X*=z8n;s*dOXA9pRKxF)z14aqLbLps)i1Gg_1pE~)i3Pom)dN5N*hO8r(KrXZ2N3G4)?^Yy#jkLTYLNY zqqRr2=k(ejOKrA2t3AK1&8EHx+uCe?I)sEZRY?I)#W5F z+kV_@WBYXPv9^Erp40aA-oIu0eXj<49pKdlKKUR2*uBNIk=pDYE4A4@r_^TmZ%J)- zHAroCwMlJuHCy)Tw>Dn=_E@iedrq%@`?tLMtp=}t>szmW?|RhMKkoXn>|KvC?yg4} zch|U#1AEuI*tqNc|JpFx+kCS%&i-9D_deO%8fVAdTorb6SlG>NVK?W6-L)X>t`T8( z?FhSTO4wa%!tNRrcGspb_~d{51Nyyd$J%?>lrZS`u0a_G{dRAWdTNga{oXY$_MqQe z6J#9pduxb{gMM3^MU(X>uy+r&_U!Jba;&=_$vCigzZM&Jzy7~AjP~vxCpPZhCv5i} ztK0rvyYJX|c-hX=vb#44yL*rb=Rxk)?=@JVOPJ{*!;8hpkLx_<88-5zjyDJanSGG>t!7DdwUxhH)~3C zTR#9xuVmwD$KC5+u{ZfFakAsU-s@|zvG=WQjQ@|#|Jb|NZertJ(+RuRdcy8Cps;&w zDC}M{3cJ^m!tOPuuzT$(>|T=!yVt71?lr8idu=Q1Uh@jO*TTZ!pa1a{%*A_sYVEz( zt->%D?{%(>!(6=A#WD_a@m@#EILyU+-7VuV7w>htjKf^K*Yz^)?wgjq`=*S$`>c!u zYj>aW+S`5HYwvxY%DbokUmNefCid>$AvW%wBJA!p!tNd`n|n@jDvoismEJS=XC>Q{AE}<+H|O&@V>fTs7G)g;fW2R>222#VX$Yg zXRv3m=j$t8(8?Q)<=ENF({RbDPQ7}OCmVlQ79is}{POU^233T?p242Mp2424=BdXA zcc+$PQ;%%I%a1=(*3TbWwc?L6E(zyY+m?54J17kH4E7B64EDU_T|W+QT1t++b#MS@ zPw_Osp1*OLLA>|)Lg9z&263w*7v%mV*fZEO*fZF3+CqIeb+_(h&pA6=2rq3mUDzi) zm~+luDxAAvXI?mBt1#Fz*fZEO*mJwr{+#V$Hn!*Qx3Ds=O`TV`$FF60-cI>UO*ffX zj04ih=V%)28SEMC8SMGZ<_om+uU2x-@I!ylihOcSs;~9iPAM*QlJQ)#zN0O<<@!{E zJ%c@iJ%c@m51Q#IlW&lmr*}_IYQ6ar`+M2g1bA)0p26O-*WRAfYj6LS@@g|0lvlIS zro3}8nw58sU~e^h?d@E=_SPp}d+RIh^{w%t_WIoTR(oS%e6GDQ0(Kznn>tD&}F*Rl<}#lYU{XOwS*^pXs9z~ayYt0Yd!5m4H=Ky5Txt8t|+`HDp2Q1 zTT*!b!RC6wy1c?$FE!F9k7N;s`D$R)#xMS>%`Bo%+8DGkXk*aEpp8KrgEj_j4BGha zlveuAS^K$UviiG0C7pSZvP{4VY-qxdL3++hnY-fZwe+4=;vWK5TXl0?Em)i17l>XB z_OxPWC4J>*rOmtZbwH)+y2xoQTw;mRM_$zw?%KDWt}?8a@S+rfI&Yw_@SCAQy7Pvz z!oz;5rQ39_rOoeM=s;hk+h4b_OI9_0sis$v{me93T}xS4ryAwhJn(I-XC8NK>Yu5v z4|Q_JbKMHm&ze?~^V~}ls7uWClVeZKY^~$W{S6G1T={MQS=x!-m=ya;)!wAl)cK z72)Bt%yR?RDv8aa3nn+t`{`*}v+Lkot@Zt4{=yl12kL?Qs|$D8+)PhisUM;C`HN43_EC)N=ASC<2IT=#0iJ*EZe zAF5XtzG!l9#QciFACg+@az$*eMyW?_TI+GYON~-%Z?@7ey8Fxcf(C(lP9{I$GY10o zn4Q&3?ggooIUk%rlw|D&`cjnY^}5T)X>M~)zmLPw$v+o z2betZ(>bp-)5qhqoPp|xhFLemi-7i-czOuTBUN@wsF8sw{HGOAG zonf75Q2iIQ&>3edyDpSp_LlmOst&_A!8pOO1m`5sL!gI14}l(nc`?k3!6ytpVekoq z4;g%mKIiqd1NEBRezq>DLt6v&pvTpO|D6%2KMS@#DWiZ1>0@+rFjXuKR8N>9$MRkRtC)B{$A2MiT(8i#RK^ucM z25k)57_>2HW6;Kp?hVyDVt+F_lhwN2lXRh@R-LZRxZzWCEgAV;7{OhBs zI`gq;;o5g1_5Mb)g|9WApi8aWt!$6cZtQR!|Hj5HS)IN-M#pX6E1YTUBt7f-F0q+< zJ3{w7wo}G^Qcu-|MzDnWomSk0ROSE2EYOV18wb8nD-gRQr zv{AHv^lq_mts_x-K<2N7XJv@e?{d!(dnz2EYsO3y{_J{`zB+NU@FH`bZH3lZ4)BkN z*4;DM@5m$vl-wGv_wHOH3^pFH@qmp7=FTv8g1HmSonh_-b7zgI?XNWsP+!^A|5O;>Sa|`41`x&;FylSA^wv5sxH*J%A_$GRSel%sbvc1YT zyQ1`hep{67VUjmZ((Cr`lJPzMQ}v*N( z^$Ggaj@{-wiE6{vD7_}ZYFnmy_MW5%ru$XK10GG$RpVGVd`-0et?oME7OSH5hVbu& zS2ZR$^a ziVfHk*bp2`U{9cvKpTN(0{;+bCeTcvnZUOM{v_}xfj8ry znmqB-*SbdOt%J5n4hMY`t-oEkUfCXI%cf|(X6aht<|fv|O{{GXlUyuHKN`ASxJA7v zed)4YYl*7I+-Mz}Ho=@HK`q%Bt$)g4*G_^8H5$HNvs$=$RHROKeuuI>%&`X1I`77f zR)gyPAW9#qv)Qf-H8)qZF6XyN7{&?4363Q=CxIRUJp_6P^bpL8VO|VAVekoqPZ)g2 z;9K;$aB|)?wl1mV#{d0RuN3~n_;zFLD(iCvOg3JwJ%K%qs1mKGH2BHJLID%pchYgM zhU+VT`OE#-UEvdT?WvXJS))gR(c1qrA9=oL%H!!e>+S)<6-&nHodGL^o41SC`vyD} zo^?D%_jr|uZ2wceP_%wOvApmgpYi%{RbO~!rck}0eLG>eZ>E9q9vXu-25k)57_>2H zW6;K+jX@iOHU@3nxMYO(`RHeKCaXVMMd%fM4;Y^$6R-jsTD4}nE|jCE^@FNq{IKnV z_(8!qRcaEiLxO+zq%i-04K14*p=Ylf=%U#w^({VpE5U!UeR%hN8 zEBv~3ls-S}OR_f8OH9{mek(4#G-zC@x!6K@p|Z#_hP@l zUc4UV^HS`?7sl%D2Xl)37eB=46fN@!x9Buof4;ex9D8kAl&-b6qHyIQ@w)w-zvVoo z>c{If*cx=Ysjkqh^EL*&8Tj--O*m%Ik12!I*JHy-w=1wqohPe~Wonc-KItk`Z z;2#G65cq+?4-9@F@B_x3A?^%uXNWsP+!^A|)HhxyzB=l$JxfwWV9IA=pQd!Y-u~}fkL_U^c8}NdCq5FsbT3YSc$Jdu z_}j|yy7;<%k~5KiOxG<{AEPr-o#+;?m%l!2v@KJ|m&E9cTPDkR@oBO8V%@pIKQ@fl zA7Wkz2hWSsCBIB>^dzb?OJjAF*qp+Vn_~2z+42d;SBuvJcD*)#D@rXh{^?Qaf$*ZB zczy7=)GJl^U7SvNDTT?^DAgk&PG7v6*5qf9dd0E2UiTcr1tR10f7Y(Iep6}3$LM$E z#+#fBQUO=v^w1(Zgpcfx)8lSz5gV{4upu~>z@9)SfgcDo6KE#TOrV)SGl6dj{7K+X z0)GW5_**d}GK%hCFA;LtG2| z-Fs8J4x}L4!_=-GuVa_K_Shb##khDK+3TvwB|lwA#p~5Q4oE(??P_wq&0~-4Vf=jJ z^}NIX3Rf_(-d|{k$M!HCi^l64HFgW1tr)Ktq}eAq*)t?w-*YFjrHFo8XRJ$*Fs>a*dzjfDax_-sz!^6#Pd&)#jJAzZI}l!C4O#f4$IX5Y-hm9O>J6ME+mPD;~5r_1`8aF2fib@9jv4FUK3swJxnhy_F8Nrlf!jf-c&Nj2F=3tPv5?m@f$x6 z(FM|EW81^LEH+sG^V)usH2llgZPgZTV2kVQu9e<|p8LsI>dKpjOI80~VYx5^LU{sl5di$JA!aawF>QyV` zZv}vj2W&iGnYo-@|l|s?Vjz2#yNZom!=5+r#|v%`jd4 z>(?^w=@_n)a(ocpIBket=9`Ue4|AkQnEvK|X5mInL-p0)vdB5}B@NPDDrFbW|I5e)#g0jQchW*DZ&>7oOfGOfTD>+5Fu^^^K`Zk6vXJ-t~H*em~Rd zNmO~G`|HxvatNzTVY*+MEaq=Tso^uibV!)gC^hJHm_GSWCK-QQAyjX?;Mfe!HB=AS zo7LoAkfJt&bgn+xg-@Rd*V$X8vVK#!gNNzA^((us)tzhMdT)j_V$;F!=uxS~2J8uJ z2#zJNC(udY2Lhc0`Ux}>XeQ81;9CNJ68MwAp9KCS@F#&k31Y_(Ylc`e;ajUf*ia*rX;8S)U<0uQYks{cHbg>4U0D{Gj}pE3*E9wt-5Fn#r>j3!U~ zbk<+P^_#5eB!{p55~lB!&&;-m*}E@P{}Px**v2u|#M<^SACHCWLA}!o=l;Xw#vZ%Y z64mvKVY=mqOy)cZYUI68J+VX<;fTzky3jj^GhPqZ|Ex*Pwujkqe3(AlPBbW=4&i$3 z%k*|#s5vFVb@R9k!Z1!SPH-&2ISKR-=poQUphxo4ofpHr7<|Iu69%6!_>jT3=yU$) z7pmu<%wp@3+TLKO-uzuw;k?U->c~!6tHCrtrg3rS-*k@;xR!bYf{u`-5aWdQd6-+eYV^v4QoA=^nj8WV}$- zy!zGAUc$qNWY?vrr|^^IsdRzWU4)Nqd#F-HInSQK^H=tHv;Wt#SPa_CUhqj9gEj_j z4B8m9F=%7Z#-NQs8y}sTQFr{jyV0Di*7}yxYmd~oOu!0ksAJ{4nv!Mis?_AtI?c;K zJ6{4;rz)4wKko=;dmjeusfJ%E{jfm;SyKU*O6kQXnh1{yEv*Z5XeAs`v9xYjyuI+S z-?Hl5nR^Ovev(ViDbh>0go#nvuppcNdSL(3`tpUAqCd^iQo3%BCc>RMm)3RmwH2Eg zpO?~i4t19Cu8&LUt@Ap__`$h_^wFiggiG!!pd(M)c_pi``$hD*S2otks>0tzb-hI) zV)M3ZeqG_FWB)!ej}H0G;Vc6`*H4vm?6Rua^hbZ256SB1PQE(LImfrFP88L7zmanW zEG}AHuRSL=0Vj4A(N8kTu>oM?0UHn4cwp`f^Cj>D!Q2_iDZekO+iVIErl=yiY#}Gd z&NnKcOI&ieZ{hs9i;27Kd7^6;)t)mU(yKK1x|m*G+2P!Iis%6IGT!eD$=JR@*W)qHAe=^2fF^zWsSA-DzS6;ldCW1gm0}aq^~Zr z8WL6a;raE`8xDVeB#-{#cZZin71b@+=4X^zeX^Jyn%Uv~)r#r9{iR;1^u3DcYNc(i zMyV#L3hOr0o%Orpcz%8Mn#09Yo9~po?=1bv=$B@F#&k3H(XmPXd1u_>&-Z46$a2 zHA9Xu#GN4z8FG&y_ZV`IA>SDCkRkUN@|+bwZ?X`KfqOo%Nc-u_o5{zU?Y~%Y@w}^s*z}gxk+8 zp^F!>Yb{Yt-CRs}EpFFKg38pTs7`Uj;ZoI$==as_8c9%JPA{o%*Xk-g%;K6px@!v2 zpf1(*)o)*Px9dWcJL{u24d@{Z;{@Xb#}b^AKo5Z)0zCwJ2AAp_`EuUHU@1B+8DGkXk*aE zpp8KrgEj_j+%XajJe~l-R7e6QM#= zPM7g61*WTCevX#$E=fTuGH-<8C+5=X>f7nUCog=d24{E9KX-INwfsty99wzOFg13cbI!3rJ=9Zk9&^rsi#7YI z<^c|`iR_~KHFg+mJYeGi8xPE#VeSNTCzw0K+zIB+FfRt31al|w4}*UQ{J`J`20sw^ z0prdPcZRq##GN7T3~}e*_l2v7%`wu$tRFr`J**oe`Ji&mP}LViN`0;xH(a$^6(c=N ztDCWE=h7${FL`2`I(8&lIN?;F8j~|tc-O%0s&xy8pRVkz?lp*&b7sBUMBUu&od5eD z8mN4+F=Agashb*Z;%M)~oZ8+?1vGSc#FdUJx|YM0myA&ZYB_n5tLqGvA}rFJGf~aX zH$nw`Yqc#?8~x+d$gwuJ6V-(3)78KqZO$jEN{f1^o#ydJz6GiJ z^%|>_8>Eh@t}7$dvd^bWe=_9TI90Tz&EX(bxZxzVZj;UJAT{vc$?Etd#|G>PYzU4e zuqV(-;0FSo1o{ay6KE#TOyFAre-ikUz@G&EB=9GJKM7*T5Nn3KVu(9K+!^waA@>+^ zk0JLM@{J)68FG&y&l&O%*8)GQ+*w7K_}cq0x!wk=#wH)^eV8Sc2da{VoO}+vFj}o_ z<>c^##=X?cMzPYvylL7^-7@={y(e?n#CoBLwY?9sDaSaqra+AFflFgl^BPXR#g*@^ zzA=Bx_9~H8gVi;YtCn;3=%gl@e6u_(bh2tZYr6C>VVei3E7?SYx|wH~@;NB$LM^{F zR8_j;FpLw76C6u$P69mydI1+GBiT@57`U z&`z~1=kTI39n`?;Qd<--fjxme<-0dn%}FV-P{3q*hELy{8`gchXWWx;yB>97yW5`I zzl|4u(d7#ol3muUj#yEKE{t&cmRjlS(bHh3SK*#RsKtASXFran()k^mqKjryUtik; z1nJ!y7E;2t5yF0JmQb*Ne_{9@p9aS7^f72-(8i#RK^ucM25k)57_>2HW6;Lie@<=Q zyF10`OjfBD&ZV0Loqhnu3C1bs^Jv{{<$u_L>X<#+KGO^K)ci&o z+IVk@sl(=(-fcN(rM9)*d{#TJ2<>d*^etV6SEKV|rpx%I-)B*}C60a2vN-D4-05d- zuPjZ)J5H1SVQ#&`WS;vG{o|%&r_|YOPnE1*-TjhQ=5TrpRksm^e`jNttgd$ppsi<} z@d0_NLu^Q`MVEerqPt!PA{~y zWE@SL>hvw+$IYS@nVdfA)OX#eozu6dro}_4#7#M8K>XAJRLIBaTW*dWPJ>oE<6z?f z8xPocVD1d_CGZ2m+!^LhFn5M|G3X?iJAr=~{6pXe20t+Pfxr(KcZRq##GN7T3~^_O zJBPRKO4{tv_OqnfJK9mD3Qm1~*|`iQ44NiAMzLXCsJiJ1?Pp0z`i%*yFMPDlF zao6GX-;XE%7Y>(t6>9RqsqIy3j-cPacKVjdC#KT;22LLKjEJPlXPom#P8~*f_QyyM zlm7W2%AdvQTXOClNrlHd<5{M+qx9vSzISww(sa4C?Y$G#tUo(bKhyKr9%lQhFX?VZ zd;UaqG;08zIN|W4%R?#7)OI_r){diutPWF-NV@jYIZx`L(`dsJr|0Q6G>i(F-rM#t z6;BPM+IgH_rOJXKbnA`Hs~}Z<=LmW>)3G@`W-R@uj5D5UMg&oQr$5=2sxd8JC%vCK z)W0HqcHdd!?_yh0$7haxT>Iu!^1NdM_5?Nr#}e2R=p^t1fo1~D1eysn6KE#zErCA? z{7K+X0)G@Pe za|?QTEk=5n8UOa8M$UDC%2O_wE|_{~@58*B(}R9>8O905363Q=CxIRUJp_6P^bpL8 zVO|VAVekoqPZ)g2;9K-L>sce{-5j~LQgybEAwTVKjQ?or+D&SU0w%C0u&3jjL#R{} zr-uP1^V!X(cMJHwx=+o`y=B{P)GCsKUw5~kF9hjmpDg^SQxD;UiJx)!Zn+1m_xH}n zOD^=1@pSWixWUhkjrmJ_Ahx57*B@P)OT;_xE=awiB-ff)N5=a$_T_9Bs|drp4)8q* z_}&8sZ4BBNv@vL7(8i#RK^ucM25k)5`0asGT$nsL z#mL;%q@6i=TBP`jfK|rxg*kOlFS!o`_B1tPI* zWZ!DeXE&LKe$FSg^I1>9+4*^zxessWIKV#-*W2lgH@jSd^Um)kz0kablKkf_`#GTb zj(NN<$A0IW=lM+^uFzHPdFofbrFi1f&SJmeR4E>wt)nn?F3lBxwRx4S{_I+sH~2fB zZT0sn%9YPq|0JtCH+;BMu+5+3fG>{}=XyOvbAa0D%l(GS-wFU557>CX#shO_m@k1J z2HSogwZFac77-L)ptgGO`XqxB1h*j@4|3+{=X%7m&rr> z*-+mszWhz)9>TAW_;O4`CnvX^EXmu)b&-5KTcZ@;?bTUq#F61?JeuyD7Ag?Z^1C&zM_XQSFLcRm{`J+la>$ZxeRQ=fJGobUKq{fX*Gu{=EK zXNT{f@!|Iad&qeDQziJt8oOT1^T35l@y}a2JAAAZ|K!_I_*gMtUX#z}XOv2_#D`C< zml~!1%<02aqNj{sx$4W;O4)n(QR?`*5}fOmUE@J&#QT!`O;-8rTm7{!KX$fjxmv0zVMwB+yTwnLsmvW&+<5_>;h& z1pXxOCxJid#DD!s5IcrgGvpOR+!^A|kcSMp$B=srxyO)i40*_qdklHbkcYSyc+o{) zPOi{hdYE&Cefi&lJ*0KZ(mp32mEp84LF2d8qlW&VO3 zZJxET&%<0;Q;Zjtw)yX;@^vc8N6lwXwugChwJ0~5<1ma9j1wG7a83d}1bPVc5a=P8 z7sI?5e8S)p2A?qakioa;bKZZ>mw&D-pK+_M@g?~0vcYmsCPk|foNcCjey4y5>gA&ok#Z&)IsiwBjW*o#$^mj_%4iihO3*wH{*jy*=1pHq8O|y0XAqlAlfwDSn2+|EH(h;7DCd~^P`F0E{(L>~lyIKoJ$PLC zy~6N5C=HD7hGNjhpp8KrgEj_j4B8m9F=%7Z#-NRVsx_DkG#o=m_B zZ0I{P_sLN*ca?fr2){ipz9L|?@xV|n?w?h97_g@~8{6@mtIl(|lbd$ti8-9-bxS69 z=bz1U#kN1GJgYC~{lc+%w|Xcy4!$SP_fpqk>{HD?1L>z*-VEWPzvZ-RL7(c}olBeZ z*ghfeu}=I;7KbNP?ZXj$9h>8y4dUAoHjc@v!1I25WvlZn?*7x^ysfbF?B$V>;an~* zz1Zw77tVXe$n$2p_SJ9>X_8vTj~xoVVZJYeGi8xPE# zVZH=@AecMD+zIB+Fh>TR1b!g!4}%{F{J`J`20sw^0prdPcZRq##GN7T3~}df--L4J zN%HKRUfXUce?QMY@9L)?7wg3{cIA{F<6~$jA77P4dYFR4`f$b0&iJv4{W)eu4zW3W zE}S=APa_;&E1ZYd&meqmRyg|>NH6CMxe(4zj;0b`|64eBOh_p*pVoWI(bPWZ28Lpk^2tdb`I$st_x51Y@4YDr)ym)>o)EmH%`d*>bvbjCYe z?8h^boM&{O`-b!T_zYs7<5W23ua;K$!I5yj`EN?$GK0c7`>!A58Q?}u!ugz!&DAJ% zn1}Je*o?xX(uVV`3sSFC(AVKS{&hMTuV>D4XI@&9dqJwGIsg6cse~uiAH@9zXSaS+ z)qd&CTPMo8Rt*mh=EaNU{dH<)v%y^VS~jr(djcDRV+rgDbQ0(!&`IDQ0?h=P2{aS< zmcX9`{v_}xfji{hTLPwJ%)T^$U}zQW5{!cJjAuY ze=P{-RUgwy5A&c=I2SCPL3)_3IfikU#7rh<{B(n{L%G@*dA?MCxG{{|l$B>k^&h5= zHQ$q7dYD`$);mqCZ4a~l{t&KzA*=9T{zLhnwa&BU%l{h2pZCmY)b zSb}pB=poQUpoc&Y!Mqse#o!YLpD_4@!G{dKMW6Fu^G$t7lV19kG5-nYg-6l~Ur7w- z=e4a*$|zt0djfm z{mE*3<4OFmZ!I(5WCB)TLv_sDOO}zjt90e3@uFR&tbYht4Zax1S5Bld-!F?^4fgb4 z$0YXOQB(Sm22&%r%Z2K~o;1;%;m`8I4{uKARqYE4zfU`jALpqi-wj+oHip-|8z(%g z=QQs4pOQ}ha5RcPTT#JkR3qvE;!sncTfbU+;EI=WW)*DbMpGu=Yr zoGW8^XZ#egA5?uBH(B8?e7$5m*R1fb@JVx?clSL;nR6eo?=am}{OJ1#55y$b3Hwu>>5zk`_pAwr(o#S{_*)_uJ zhQxFH{=en>)Dulj82j@@;iawPxk136!l_IyW&4;$ax9bi%rowJNux7SHA)-L2mMo! z?P2~1oX(zqipluR&={_NHotJ(=y=XJ{*2L(sQ#1J}A7}nnL#bD)N~d^E`Sl?gKT#^4$E@08@-0XenI6Zd z3ML3oNsQ&Ab8{GN1yz+&)4AU-#qGLQ?`p^KpuCxd%jJsWmoKx34cHUd5FATjPoR^) z4+NSCG!tkh&`hA2z_$ecB=9GJKMDLv;7z|bGR(BW}&%T%LnLP2+n|_buHPzEd z{)d=6S^m!j`9AfALFU+7$As^jSeML~nQRZ!?z=el%tC+lNH= z7|l;#bQAVJFojR}MhgEL8OggmUkRVfAI$~Jek;7Gd^G<&@h9QQ=cjV_ktEzEZY)3Q zXWy$9q$@8T#Q7KfM|jlbVD5MSPhohkxCX{|j5BCs(8i#RK^ucM25k)57_>2HW6;LG zd^wySe|Es=Ojf-;<9W!CP|F0Yz=k5uP30|PWbW!+qewnCc!r%L0jmsKqWQz!RpvcE z(LP{LMY2xd>wChKT~mKFoXmsYOccH}K7yy$j1evp62*VU&J#{~cr@=<`-F$3p2TZ9 z+INEa=}7}4`TH-wQnvT_w_OBZkDf023p|~~@!wAnUX(G4(-oQ{HkVpP^U@wmWc<~( zDDLXBP{zN`6vai7w+p}M5y_)ECW_61zoNKC$}Pf$vq$sEj`A)ho$^Ek&&rl0_GgAq z<&w`yxcSIQeB{+Gu`gP849BJ3C;aiJXioDV=UsWfne*gqyUC6R)bAP1KFfa;zWr+y zKk6=jD*$XfVB-NB56qomz65?Cm^;JV3Fgi)F9w|ib0_c*gMSG8z~Bc4KM?o<VG?+D*4@3JdXH<~ja*(h9fRutD9wpIAqhG<^7ZKdQ!iQeWsnZGjUNmO%< zwvcXC+cI@7brd&wY2VqHs7jl^``OzC!XI))^ZP2BgkR;1;^$ko3x7Nx!RMdt6rMVL zD*Ig^;g~m3yy>CMPxHN`($Rcnfz&AVwskbmX|Peo`>l!McF(p5U#=X*ZA)%9xfi6$ zq>1G7lXeP^Y#+_@_Ajx1Q?2ht^3ImCW&CM;G`B3aT)57JXdd!$nb?3mfepd21oi|v z3A7PtCh!k|W&+IwnhAVM;7Yk_C|5XDn(ZIO4}t$!QE?{03AcidHsiRN~j6HK1?=_;lc zUGkOpt?39A&1XMswC_^W11_3+yJEBOeG}`mMVHHa?Fz4r=4Xe$7fxyNxk;Q|Yl*5^ z<7kfhdZSqj3F^*+DDzCuX5nq$M44B$ZxvoKHJT51|4!a5k9x4)YEWA?Mw`!h z?fV$bcdOS#bER7H?ob>j7$-QE;G6_{2=ox>A<#oGFNS$B_=LeH3_fA-A%kzx=lpVA z6enGhcWYP$hqu`prM3)?;>m^Ny@JRD_5}8Hb#XKoZ7%N~RKR53?Qe1@wYELR zm645j__fT!xeqquJ{i9dE;ykz?^;$|czm@WZdbmHaJO%RIH6P};k12Pa^`0N!r%Yh zz&vYFOZbZ;ic_X_ICGi`T-W2+bl6#xLq78p8~E)N4UE6T!k~>o8-q3mZ4BBNv@vL7 z(8i#RK^y1&(1O1^RKVy=RzHlc#)T8KFpLw7Q}4fb@YlzC1>7u0r5mD|&b*Uc#^Ts%CGj~*`}Ja3u#t>w7#!nZO9aKzS{ z!tJNk;X~&A=l0k^#e;b3nbO+!Fe8Hkd0j{e(Y#|(E3RLpsBo)ELHw>{Ik9;h5yX|- z+IOlatFjw|xc$2dGCn+gGp=#Zc_(~W^Co;U#`!&hzpA$2PDhm3k4Vvyzo;Yc#MW7! zHR8W7)|6vYcWS`RS~$O1aO8a*er4VpZ_n=^8NiX|o$Z!4UvABbr)&-+tEH)0n)}6a z&VX4(TXE+4HcyfR+NNp2PwzV8VB-NB57>BM?hNxK@B_iz8RkwfcZPW}=p>jsfqxkM zL*NGnKQQ=#zz-OAhPX4togwZFac77-zfBj&DQ3z$y>;Cm1G#nT>XHv#DwyA!%vDCq z^DRXJd1V(rZF`v1(Lo&5r<{zRHE}-`P*Hf=v8MbkMNQ$dCt7f>5an`nPEN1ooSjZL z=7Q^--1~cHBVKgRu}_%Tf@?2VTHX({p(PjC9w2;wcysPjM+>*!9LQ^4Rg*kvSU8AJ z>?>`~nW&yr3glN+tv2&a@Ax2Ik)xc9|Mp`L&$&@ScukI$ys3))J&r`xq(C!%f7R+q zR5vp;<|qGHJ&9^%Xahdd)cI|Kg4BYqjIj9`rFM2~$%o!b{ZVDFwB+E302zP-mZ2{Dze-&90s5ckpUi58|b|s&JYX zK^(fFir9cXfepd21oi|v3H(5ylR!U#W&+IwnhAVM;78*A?S-yCCzJ3}5a#i2uEL>^(y`+|hTk+PZ{w8PqbcJQ6PF9fj-s=rtx8!=i$vf?JeBTzF_>BN zhd>X39s)fC^J176gHITIVm=@L0$QHd_v=U4VUq*Gaga8OrwNrygf-J!zK$4IC7qT zDeJHrewNO3n=I$7bLtpn@OL<1-ced>*1qkLioZEWv2`X(uafo3McQ-CyqDj6&wA$E ze`tAsXS`~i+cfpic*%|Hub$GIV`1i;i7I8MoAkNIYFnnt?0#bI3k;X>M~5HLx4(=O zJ{fX>F66U+H&OLje2R9P{Ir}{HJKtmbGXMBhp6YkNirTa`#iO&Y;!V7T?xBH|2brH zGD@|}c98;8+q?==iDl2y>Yk3xu@0x{&~Rt`>fsTj1i zrk2dQOP2;peN(CQJ(}})tk{4(fepd21oi|v3H(5ynLsmvW&+IwnhAVM;7!CRZ{*-)cEWqbDjkCclGo1A;7MS1m%15ANttG;d-g> zQQ^Gfq=zZ9>?)PdDH>G13^(YP`V;NCP`9#Qr^U-0hH-*%f@2BJNuY;74}l&6Jp}V& zm=}Xj7<|Iu69ykL_!fQ6C+nZ3-p2p7hq-s;G&MHs%kt)JXXyJ-sT;@y_5}7cw%j$^ zadV>dFu-Jb2Ic)dT=ToP%KJOH=J#-w_xE$n@8kw}e^(dm?eFAz?d|X9dhHqP?eFJ) zI)8zzb5+eWPTw+fDRF`(h z+|^<8J2QiBjJIEY%pnT>1>H{Vx^+^RgO zY)@;R-Q9jb{ZLNUpe{NzS!K^__kv_q|IME&D8T7$s#m?E7S(t5vRYyH)QCe)Z}Sb` zP`&=OIgqSkD_&Pw<~!#(ap%6u{{0yFyD2(6Qneb75-$Jq6E(|cxY!R3d#;}C8!TMv z{yDX=uJdCYczcidE<0nH8sy8idZ7-uAPrjql zf8p#Gcl+H`Q?@z1_x`8%)XM=*Prf$px+*%tId*5s2Wr!hF>>sp>Nix`$`hq8>d#kI zg$z!Q)G*5}Ripm|8LxifwDK`^()RFIL-wewx$XHA)%$5@Rbp4GZJE+D4yXpjZJsBp zDu4Z{ZdG=Ao_krYtL5K0<1O>tQFq!pdsC+4_f^O3W5m8y{YR#zjS`;r%XL+zr_IkO z6*%^q`tX<3D0RXAsyb2L>6duPO?6_4T`y7Uz>?eQ`^BjohCIZz zz?bLTRKKj4AU#rt9oJQIuZhwlwcmY7`R;Ohr2Te{$mC0et+qRun;|<$f<(R9gK^~_^+MDKvN-gUvK~1`NQ+X!Z zHJG3}OggS^x1TIMQv1}GRN0G8kF>e+dDTnFx=`)9Ur^2SI}GCl;{?YNoRdHgfgS=q z1bPVO#V{`hpD_4@!6ytpWbiHeoGI?6dcI1o-PFovx7DrR#!HXn^W!ZwF0a%j1x#R1 zU{CG(UQ{1nO7E(G$@DWGZ~qe-{j_dib0^RCFn zfU6Dcz80jRr$V;9mRB2tHU@1B+8DGkXk*aEpp8KrgEj_j{BOe70UJ(58lB1N$ey*H z`=_T`CSV0NwEM?=0rQ=?t9uoDd3LWBUlFi+xo|>Ko)huX!+<@tPG_FGEE-|fg1KLR zV!o$WxhUZh1;=|H&7LMa@MU$+?wYZ}kLyGSgkOsm9#gt`K;5rmgx_ok_Ut=8UG|9X z-!An0`qI%~wfJPus$d(7WHl>QBhL>MBQ}5Uc$JiN*v2bajc!}QQ($+jj3;zk<3C_t zyl~2lXZ#DA-ypFzr{etlC#A5lPF5#=eOBXP!5Lzc=HWa47rWwww}%%ANPE{g&+!V4 z0t$O##C~7v$bddyI2t^`K1nMxIp?V~=xL2F3ke4_Xn)eLT~&t%y=~yX`?dVt0I>0Z zjR$NzFn5Nz6U?1p?hJD$m^;I~7<3ZMoxnc~{vq%KgC7|DK;Q?AJ44(V;?59vhPX4t zopb+CBk97&c)8D$KJ)CP>7IDWhczKxJ>T7%EQzjX!M;YI`6bOZ{F{*^G=P!g=Yviezej*%{NvFTriO$7Yzo}dwnt6`QwD}yQW>?#vRH2PyUo7Bw(%Ew2TeK&z zAvl)6okYfySXUIc_ z++)Z+hTLPwH-1C7oR1@crBKlAdpK z@~|lltFfh`T`vi$ZKM4DpJjLWKKJ$Cd(ECdK{ZJKS5iIyc^IZo9YqO|7iLMe@Dl3n^0w2W)%KCwttm&&BD`JRdmI(=);m*WPox5r>64<$cd{ z+wT$XvFl&Xnn`{uR@b}qhI_uVzi}L-$If}hG4ZQ}mtT9%(^J^rSq{=$oW{oLrwCc@RP{L1UoR}(Je$GmMo0pY^MllW|*clLVxia54gd}FNL4)xXY<4Ru*2o@D?xb=x~}T*EzmbB^fWDgLuo_e8T_6 ztl*E6MhmxJv5Zr#2@~!Uw1i7P?l1f#;ae{9O%LHFI~Q^4qaB2=Oj*R|Pqh@Tlj>Ve zaj${!h{ z2|I-CzwLk9INJYj?JV2l?D3ZE`RsWu+rMM~o@M*@tq#jpm(^$4>b1Hp+j-deShn-C z^R#SZWn*U9#?Z#nvh|1ci)HI4>o3dJf7XwdtzWHwEn9zEzgxC(xNPEK*~Z7l$+C@` zjh|&3Pa9XuHqJKQmTmlP9$2<{Ve`YX%@>r)7E3}-?DYutHIW9uQprny>qeqfOn2|fAG%T?i*g8 z*!{%oE4$BleQ5U|uW#+X&uYXm1Xf+|b_K zFgas>+uF$)lS|s0OD4y(H^)rwX>abCoYdZ&H0w)y*Oys$+Pm)lDj8;eKiA3OiRb$1 z4B4FAjz1Ty_Y8J&{_W6q`tsM#S}6Zdvrqip;JTk|ejHrm)3Ke4eEI2|CI2k->2H-; zSxo1uvRYzV|8zmUtJ6ARt1a=gQ?DN1%%k7Wc50O68=alpFm*$F>xQW(+FMUdozdPp zW9pCg)*n-sw6`vqdZoSf%G5FKtz)LXX>WZqbx(Wio~ei0TMx~@wYN^1|1b5?=A=1J z>Z4_IKBOllo}c#7F9*WfM24kCu%; zwDF7h&G_jP8~=T>F@Dv?zhYzjt&QJ>?Kw?6giXw~iIcF2xi;|=HZj*GuEHkf+Qj=4 zn>_erWAa1T9&7SO*q+nmld#DAc+0+SbYocXSKcpsFHuXW#KF(Xy#SQWGtk`Xn{cvZ-5A z6D^y1CNCREuox8B> z6Jgg^!mba6UEd13J{NXlA?(IT+qt;06Lw=N?8aKy%>iLIH-z1s5q5J)*v&CvH}{0y zoD_D~l(4(jgxwq#c5_?Ut_xcet!BF}Y)$mCt%;W1wIl4VDPec53A<}h*j<~#?wS>L z*Rrs?#)aLrFYML|VYh||yR}8wtvSMOEfRKXl(1X7gx#7Z?AAJAw+0HkwNcounZj-@ zb!?m(E9}-@VYem=yR}-_t>MCMZ5MWHzOcJz3A=llu)9ZmV(Tv(3wKWucJ~@#cMlSF z_a8zpC+zlq!lpm8J)xIvujsY0J*2SPTMD~9r?A_L z3cEe3u-m%|yS=Wk+XD-`y|J*{GYh-Dw6NP_3%k9yu-lUhyS=)w+rtaHy}hv8^9#Gz z0>bV!g0Oq-AnaaK2)oxB!tOPQuzPJH>|V17oAqL^zl7cEGGX@`N7%jg5q7VMgxzZ; zVfPwJ*uAzAcCWdF-D@#n_Zm&uy>=6Jujz!{YdvB28c^81HWYTR8HL?zOkwxhQ`o&G z6?U&xh23jdVfWfr*uCZzcCUqn-D_mW#<_MDwmqY*k2dFRFKO$eW!q!g`e@nqp0)?I zY-i5HehBomKcJFlvyZ1mG8|U7LuzSx$*u9q`?A~J$cJI9iyZ2;- z-Fr2{_Ikx$w^;r5I>y#Y%l7)l)=JCvy2sW^%l3N6)=JCvI?2{b%l7)o)=JCvy2{o{ z%jWxZdSQbq!Y}p}(d&0t7fxzjR{N(25Wd)|hAz{krts8MwRK#tTEY`PG}M_gIUL=h zwVrmOhK$E;2-0<4R}@|p6{z#1Eh#+zU~|1-U0&g>mm2AlN3sZ;?-*+DcMQ!t3iR%6 z2c<9i(5jXGIOCFV>XA+K^5f5h=UnQhvleu0W}fJ;GmigV#uw)pr7Ne|FWh^X@aDdL9;;C@ltKs^}U;bjVD}17^J+-p* zsE-1pwf|>6(u+=cJY8qqJwUi($vC|;V1;n=cJX@OfTzNqU8ukw(Mm-+n-{eEJ3 z;Xyv*_1~(#@XSo1dO`bk!sgvsI(4`1!sgwZdf|wz!am`_I_KP_!n3o5=%vl33*YkZ zq4&?;E&O4AUp;2&G2!Co_qE5=zb%~cgn8CJ|9{V~$#JR;@YjD68_i;;1t<#cAYrl%0KW z{G7B}$EwF;)mhIr+_iDcHPhoY(_BkEUQ3;IY5uk~bKLLW%{|EDJ;>af zJl>m}Z_h){x91_}+w+j~?Rm)g_B`Z#dmeJWJr6nGo`;-o&qL0)=kB-g=$B4>Grvm+ z*UTBO7x(Hs(NX1d6-#@6ER5X8o$t#+&i7>@=limd^L<&!`MxaVd|wuFzAp_(A5_Tnq9?L<-Sns@vZvkYkNVqsx7>bsr+*%p**_n0deK8pFZy5F zCvWl_Vt!5DL(Dts4|vZs$AgDCe!OQw#@s*NGa;iUfcH$us1@Kn6EbQDc+Z54+5+A) zA*1Gi_e@8|vkh(9L$<$F+4@x3#)^lH#h|jqrn1GXGHMZc=Y&0K5q6HzLoEXDoY0&3 zH`KCKMlAyGoY12dfp<>Gs72tN6EbQMc;|$SS_IxXA)^+7cTUKtMc|ziGHMZc=Y(vZ znN_yW(kk0$Y?bY^x61aJTxI*LuCjfGSJ^(>t8Cv>RJQLgDm!&st+Uy>t=8Xc-B#;z zwr;ESI$O8ZI-afDYJJbvZME)a>$X}Cv~^pp6WY41)(>snR_ltkZmac1TesCZq^;X( zebUx#wVsK0PVi>m(NwnYZYtY%I+g9ap33$eP-XjWsIq-$RN1~us%+meRYqL`e&Y`Jn=hjp<*GtxIalK^SR~Fjcm5n=0EmPnGRlsLFPZRAoDNs$aX#w^iBJZFP>y)@^m}3fD)B#m@PwY-<53 z+Zut&PTf}L%y50gZ*8qXWm|(#+14ghwlxctow_ahSy;FAZ0$pBY)wREr*4aW7S?Ui z&%(MbuJf$h;`-0Jt!HaV>Id_wxIO~2Q@8b;x~=EbZ9S)M>p68>^=a$2o>RB=oVu;& z)NMVdZmY7b+p3MN+v;y^-Bx|tx-EKGShqzF3+uM%VPV}CJuIx-qKAcbTlBE7ZtFR9 zTRcm!Zi{CO)@||Z!MZJ;Nm#eVvkL3Bc!pu!7SA@U+v1srbz9G=+u|9Cbz3|;v2KfJ zD%Nd1r*7*xbz92u$d|2+s_fKl@eIkjEuJA+x5aZH>$Z44WZf3ekgVHM*5^s5Zp+{5 zGpF^bvQxLkGbC!q`ut|GsqEBkIY!0o)NRR$>YchRIaIwb5*4Rd3HJmF>BvvQxL^v8{TiZp(8)_4XVIY;aA) zxSYBz&o$K}7Osh~aq6}_XI1aiZF!EX-l^O2TA_M-4N=*t+wz*DdZ%uSo;&oGsNPb6>!Ks=1sUXxX}*J_pRHC$zg_#CWz;2*KlpU&w!C))HsBF9PTiLGAk{l{Ti&x&@6>I1k5j!DEaOQ>w0F;uqC9xB^s5|!<< zipusGMrHeKqq2SGQQ1BVscfH-RJPAfD%)o&mF+VjW%T%|Y@fkYw$ElN+h;bFow}{Q zPve>h-t4oV%6Ol)wOT$a(uQ?g{1!cd^od?UmF=^r%JvymW&7-^vVGQ7***iSY@dx) zw$IEe+h=K&?K8H@_Ssuy`%JE~eO6c5KEtbQpY2t)&-^OecL9~{JA%sg-9cshPNA}W z*HGEMgQ#rZO;mR3ws;0(-4@S>`m6xXow_aGee}0Z-Ini4s(0$Pe791)Q@7>2nChLn zE#KW#@6>JiuBUpZZp(K=)jM@tTsQRk2>edn7SD?M>;=7jSJmIzcUYC3x-Fg+_1O;g z_FY(Q>^ri`_T5=!`%bO0Q@6#lBI~yB$GR=9!>rqC?=!BCh~?C6ftPh#&IzcEQ@2H~ zShqzE^?4e8oVqRN9Q3zN-Ij9{s(0$PoYPRfQ@7L8v| z2l1Rb$ltbikGq$UQwQ;!I*8}gLH@S&`Q7~joH~f-)ImI_4)V9H!RxLG?9@R#rw-yd zb&$Vpojp@iNVIGC{M+~7P8|em^{@`|w|yt>e8c{4YwtL9kbhf8$f<+;rEBuIYXmuc zEXXx$A~*(E6Y-q>7E=%p`dd7wzr}OwJg2|KbNX96r@zH>`dhG0HTzpU zr@sZ~4*OehPO-nmbNX96r@zH>`dd7wzr}OwJg2|KbNX96r@sYzg0R2E zbNX9wEn2L9z{ua;aZ}FV|7SHK#@tpn^&*^W${%h=S z@tpn^T-({-f@?neTRf+~#dG>wJg2|KbNX96r@zH>`dd7wzr}Owu-7g7 zTRf+~#q28{^tX6Ue~ahzw|I{N$?+(1tkJbw%e%V*`Q%2Se zeZ5lqPt4vy)kC)py{?PoMd;%EQ{;9^bV4b1LutHXQ#`rDs(>TA^C}C4;7@eCEL)+gCgDsLIhL*0sO% ztNTC)V}8dhRB*zxttiUhS!ooEBSL$4hv$gX)KO zspXa4-$G?`OnU8$*H_u;X~FTyo))cJ@W#|2l-{PtMzxzJuyo2a>MVO;O zEax5M-+D(Kd-Rs-oDPn2$6mkJ#GDTF&ioI2a{fpEWh~gj4sjiO^^JKV_`$!{Ui(a___E$i}Tz6_Fd9{cRt*ikEPEL#^TJ!D#sWz^p5@i z*Zi#+i`J6yTf+&)tYfjqp2~(3J?3EJ*n<<=>%aKh*!){<+Ta35>c^f_D%-gfmF+pD zvSY7(3V8Q}Psg6;tm^GMU?Q;DcSH4K-x*c5?~*Dz_TWeT!oOp$c!2}@|L%LJ^^bQ( zM~$Qmc}jqQ+4V3c$VVHnpQ*BhO!jr%wKBAvdgm+e`2_%ynZaxf3CuS znggz{DNp8PLZ3*z8J9}9y2bFIL){`;y2^+oN;*^FYL(! z{E#2`CvS*LK7ofk11I?he&!`SWl^Zj@K{N`H`j;ky-`*6PR;gjY2RwenQNnE(9k^S zJ;%nQ&Fd%YF8RZ+E;la7@{#uz#iM27u1MZ@#+cu3isb$L;ArW;B42r4u_aorotUru zKX-eKeAG5y^HQ=>th|{Y$@`LHu`=V?Jk4Xu-Z&XtIZyNZ{P&fm)2dv}d->f}s#5fuNZxyWUri3&n4@{0l3ZQZ9*g8Xc1{g>>&0x1`+E19GAop=cqZoCe?!eP@6?h_i&dXUJ@}+Oc%~olPyfgZ<04QI#W%mbv5VOrHz)ne5E-TZpc=9>I={J$aUjFIp5uU6`r$^bN@m)XWe|^TFrCN zy>7ebse66?PkLP29Y4Xf{r{zRuMh5h;s2(0uQTpF z-@k9{2>JDmKYYj|Cy$UJrT$boDRG2McsL?|T;VRMm=cknd+9ETi!Sn++Bd#i=5>h3 zD>LtwO}9nlLvN3ijSofSxbdSTeM&?=*ykR3_4$arrrzj(>3=H#ZmY-`VLx%pc^xDCq~9Hp;XkoVL`K|A zU;M5%z;pZ45&59OIsB%G4E*u&R&U1jS+j_Y@lp>SXb*nqXQbhc{=p~Xf@k6Z|HO&B z5dZC8-W`nVx@~vMn<JgV*>nR)5iqkg1-OVk#WI(So4SsKl{!{as>ZZe;1Jvx8%}@3_PQs zjmW?`?B0kB{40h;WQ^;Rfe{(wr5-%c9{kV`c%y&t$++N|c)&k#A}_$dLS75bFUUN< zAoKi!%<~H}&o8yN=NDw2UyylzLFV}dndcW|o?oiB=NDw2UyylzLFV}dndcW|o?mKj z&o9V4zo^IYNqZc(ka>PV=J}=e_WXj(^9wT1FUUN1)1j;WS(D;d456W`30Hh z7i6Aaka>PV=J^Gg=NDw2UyylzQP1O(=NI%mzaaDcg3R*^GS4r_Jij3G{DRE$3o_3y z$UMIw^ZbI$^9wT1FUUNX=-lQ{2q zorKKmBxGJEA@e#3nb%3kyiP*qbrLeKlaP6xgv{$CWL_sB^EwHc*Gb5{PD18&5;Cuo zka?Yi%Ji>-~gv>lbW*#9kkC2&1$jl>T<`FXU2$^|= z%sfJ79w9T2keNrw%p+vx5i;`#nR%rCf5ZK*N7mEfPYx9efA`SY&{fA*2Qu|DUM`V9 zJ>;z)4GKq{>ZkU!!EdRD4fT{0f19cHw1GWrpm%*jMl9OXhS+FNJ?tkuura{n{+4>z zCuNS8HuMj@>l1S8{>Rln;d5`VSNVexuZ3sjCaQdK;}-+{ zMPEH0*r#R>5BwaQ)GP2`vq$?N?pufJ1$egajSFzT@IX|6|HdE71>=H#!=%<47xwE8 zM5_!xvx*l{8UDi^c80(M;(nC2Ol9Etu+sA?182D-LsSO-q64m08RKd+yq(GzFZJMo z_TYzpz#IL8PsRn$!~_0`6L}$iH(!*IU*--na|fBZgUsAPX6_&}caWJo$jlvN<_E=iTct z^Imwpy)dq~%pLN@`!8kQPkC%W&*K5Idmk@i{xkb*gfqYXE%e9ceev5rh*o*;6E}uN zzf(?Svqwm1P@PLu{&4ZeP^C&IL$Jrc_!~0*KkOjmclbSI_=8`_h%>g_lv<8H(Xsa+ zTR$pW|0>(KDqB2Bu(vo>w)j;>921ZFM1zC&p24TG@#C3zDjWZviO0Ae{`-xg02>@3bC6HjIMGw~F^8JFe`Hde3WMI7>gIOGR$$eWED!f!2}Fl59b|A+$~ zp?C8I+3Z6S?%nX2^}CM!9v|DQrOLIVCWNl9&`@Qw*G}m3m6cUqQszi#{Uaq+#=rO* zzs3KD9c26tzlRKe@CzAn5YN#kI`$r9>qlklUu7FNDdI=*sBCenZ1JmX$3=aj!9jb^ z;8WS)^-MgKjepO?QyKr_Z;K}hb{1!niKjCBnRtrdj4R2+dmA=Zuj54=@_;zx$NCS! z-o_0>ws=%V9P*Di;1M=%z96R_Y#zqBm|E+n_){&L8h(q_TsG{1P`k!;RZcy)I#i=v zjLKJhk{4Rk?NXKTFaCx-{y*#><9GNye8M06LXS9z=jan5TYC?(^`o-&@8P#LZc@aL z;!)Y+jOZiyRkq`zKGERNbHmtsCZ5U$uV><^Z2WsBp33+ae_K3Bu(RVz!tWu&pBYzT z1W$AQouk+BA`b9Dk2n#2rqs0lRd3^lBYqT57;!Dmh~C6uUfg_fjAlQzM4P)L$cTy9 zs*mJOWpW5TxrI#5Au|_{ZSG7zoAGaR=jcseSzvGa#{xepTmLHCxZ#MO$gu?3;*99+ zu?IcJsP=a3)*iW|ALLGDatIr83z?ilW-cJx+$nxDE^~}bspaT(yw=`x{HSdGt8C*Y z!G^~YWShH)K7wCmH(!u(&hOdyK8~Tav*E7V!Z*e_CyojI3eZkSkL$>xI$R>{7Um#oms<&~&(3?1VpMq?0 zs@~#P8M%AEYqnyzVdBF0XVNlM{yaJ+v~=|@mEZ3=G*m14OO@Z=J}Xr2rIjk1e?#VP zmCgST89SBD??UGHDjRW$i=ITR$pW|0>(KDqB1%TbwFe{3_dV z1@f?059@K>>*}}S(@GssS+-OSrB6vydDyEXL&JJ+Ryka6eyIDIH7c8bL+0;@P4CSi zW2dtDUC8`iW#cbo{OY-8;+Sh;(K5t|4el`T${Eq;{| z2l3z&@evO)a3P+?GI$XWGRA>;kTE{QQyVjG;sGCs2R(Q~Jhd_W;acwKb-dQzbNr}m z{i|%_Mr0_{DJp z8OJq_8^}1`aoj*g9E{P?>v3!CJ?O0;m92l3ZCsTt9+fRlm2n>M{6ZY$4$q&=DP-mv zvOOl%hQ|i$h?k0=JgFSuX~VrJ%r5bBxGJc z9lgHiT6=x}wSH8#{#CYdRknCkwm4O`_*J&!qF#?%#O3iE!K3G$+VJ>?p63N*o-dGj z9znL}o#N+t=jio4-P(s7KPp@QD%-d!+w)Fki&JHL-l>dn6~3Dn4PPkl=I(h{c%5A1 z;TrW%zE0x&ip(b#t7+%`^u5o{2da$uHq0mDJrVP5m`{Xk=M`19^NlKV-V!#LZ-ZaR zoVRrJc>kzr?LElWkIL4+$~Lab7LR#%Dpu3t)OTQuU-foeD%*KKwXySos<-oms<-op zjH~mO7LU$b;<&c+kZQwuOXxXo346|4LbmoH$B#ZwbKVkq&Ra(O=sao|dd^!yw)j== z=F7&``Aj=@&UqHjIh%Wyoh$ZmKVt46Gk1`gJ4gSQ%{dp&eHAIfc?=xOoZoE?_vZ^L78Ax>&& zIX}sHp~$@Gg+Kp~xidVI7tYbG)c2Qv`Wzkeh3h|L9EY68gUtCodwgDS^Z$>GdPb(d z(_D7my4&A*)4K_j2Omoh&zaprqQBbYH%r+Tj_TJ_9=Lat-(*{Icu{&!Db;L~Kef`T z@Yv?Pq{`)+d^6_|&hOPrhMnICIf=5dNurJUZ4!TLd?wMSiIv1y217D2;9CY){y6h; z*}UcezSR|1rcKKxuLWa?oAjKNs@7BU*{8~@{^1#=ql(~N0*-OcLlIN7vwzs8+3wX(zv+^=}%+)+h}|B|6N zpDkKdCaum;{ErT=DyyE!@G-7Oo~bIw9?tN?v9I~mPb|C8r~TX?7y9%w-q0|xA5^Vz;HS@qCV~Ik>NX4F zzJ6Wv08iWMEdrcxzuh9hpTDC;FfQnsFW56*@WXt;Kl6pS%op%5U%<(H0sp`9wKRFv z^%Z2!OWA(Q7vD|3^41D+&8%#H{OWg-i{4j39(*?2?~(g<@}9XBKRKh4TsJpM?T2Sok`-gK)K7flXzAT6OZ~6BKUz9A$ZNLp^D|NYpd$s?=9$ctH-{(b$IB~#zH z$?{~{5Bz<3GX1Ri%`HOq``2TA57z+0U;G#sxjc3w!ba zKja7g$s6L5Pv9ZXz)AjrpLuD&XNo8uoIKE`j;FiPrH%JED7G}^D%DN1fG zo#UUIIokhyc$D<}BirB9Vzj?-UX;u^l~8&*MXo}TT$cKtnm(%K5L?yhWqb@zLM;}H6HZmTFw;v)7_KddM-e#%lmL(ZFZ zw{~Z#|L?D^BsD+D(zsteUP-QhElcs-`9UR_`%ISNY`?3L%y=kE@i#nNN&I`Ve2iat`_ zx}W*kO22>q>auHDx3)$KtNd@@tuCdfr2B2JTjeL_R2R8B-QP26 zmEWjd4QbZh{C4sxzvx3XWLKSZf5Gfk{(*05NXw$>{`C2){99vd%Dw4ns^2lTrY!#? zP3=Gayrx_}Cr$mlP`Z|^8k?s6f4{z#yxuoW!iYtBUS7)sV?CY#r;nUBo$5;6DKj5YnKI0~~ zUf~nZ>dGs8;{2ub3ZM9kU%nz37xWx2?8yWCkRSLbZ-`4ifrmT;C;10{<^|(=Zc0V@ zpk%g=_vi~1W$2~Z%0v1a6=n7xS<26cUsaT8C$f~ce&;I6)_qyZ=QYhM$@%0g<@u9` zE6Iu1vy}hoUsjUYlgxF`&|8~uY%#s$yB1OABAg zNYBJQihs+BCNk;6J({nkA2pFCtM+KVs0Ri_sospRb5b>zgDRDWqqndHe&)R88)r24lFDx3U}S4V~C{8_o=3TNxe%+(S7v~Kle^RyJT zANy)OX?RzP`nmRCJ=uOuiu(VwQGNNWc8bP*@9z3?>hcuD)8m!;()`>$#aT7EzBJ6= zr})e6sxP;u?ej6N2UF`yseSwW<=>V_roMUEi<4=;?}1{;^i%iGi<0SoTyl|Q#yvak z&m`g*e(HP@apn|1pG5pGt^GZT!g*|zIAMykLKn_+xca%u&$*-JWK?vn@-{!NysRjet9(wqrM#pc%2A$w zTU1`QZOT#pcOEG(SEWzNiNevy4|cNUuvG`ltm} zI{_VFHgUb3IJp@n)`v2|Ny==kW=99=Gtr;~D;WoFguef8gPH0h~Nv zOuiC$9${S0`4#954}rbmC-7r<3;Y{CgSdw0F!31v!^COw5+;6=uQ102J;w`s@&G^N z2mZ+$;*w9`A=Pu>uhd;$-722S#id@(N=m-D=l!223_;QbE#@IDCM zcz*<+yl;YM-cP|l@3Y7Y@4v_w@5|8hehqux$Ki+fclhUhA949S06ct708TzXAYXj0 zz_^^}jX)0`Xb*nq2fWcg_+(u0Og!M9IFT3PN4_{N=s8~4lLz=AKk!f95SM%c4|xVo z@{fEmFJ}I~+VqAkB(Lgj|IF(-?N7F7A@k#Q`*Ru(iO=fRLcS@t+fS*!B!2Da7P6t} zZvW3ucgEkisD)f~{0Be%#4qvPQd&s!?|<;W?@}t1Sf!=Z{OAY2XOHO6tb1C@H?w~5 zhcB%bdN8@A)E)hU@l!K&_{vr?v`a*P+lW@Ouv*0a>UFK;{BOI|Po;}n%Nr@X)c>^W zTFdOjT^jeXXIsk`i+3rWDxbENVlV7coCT?^<@|(Qia+mEYiT@gm!I_DOEtRw+*&e6 ztA0K8W?YH1H{(jAA2Y5*`ZwcBWLz^Yk9f?uJmNIt@`&Gz%X7x%alEi65AZ{N;Geu9 zF8Kr=@(i5h-{fUI^MZW6exj_jJfG{MPv+G!SIYe-%(J5TPHNVDSIXO8eMJoKCGDIQd(})hAMq@3&}=@4Dy* z-+R%&8CMeH;`=b-L7xn9;(IdU$9HYcxRN+t*pmnNAwTd>-Vm330uOlxPV$fM%$OI{ zj}G43UIu6F^rvU62^oKY1!uw9Qmu>It^sjhnQ+Vs_c)9kro&K^pd%`)R zLelj74nKBFc6jo`VR`bI9e&mPBjFcTCP>P!-}#4LIUSx^tb^P?^gF-j+H>Jr_jQ!B z$=m$_6@LmhInqgPirTLFcEdW$y3yOze%p>~B!1IY^|P~X7unTxtNKqF+*KOAvqj@h z7}-r8YrIAA%(}X}+_iPH;+&GxT{55EtoR?f<~k`mV6)c69=h{7>3iK~zo5hPF!inW zO$gII@2bIJ`dJy(IZXdwzuhRzxXI&U!o<_?l2T#f9JZr)nE26?&2d4`@xq=wzz_L> zfAWU7F$2A+ZwB_J z?iu(o_0Yh-sgnkAP5m^$W9q5_PE&6U@S8epFfQnsFW56*@WXt;Kl6pS%op%5U%<(H z0YCGFaWP+}ZXW1O-8`^2b@RZFshbD>P2D_*YwG3!9#c0DaGJV#fZx>3gKoMwJrIR9ztDZ+VC=s8~sd(NZ659e3mpYyJW%lTN~;XEyHa{kuTgM{ zfAWU7vKBFJYYv<8ta>fgU{29{kV`c%y&t$++N| zc)&k#A}_>`d~saRbG)!85AZ{N;Geu9F8Kr=@(i5hANgWlFfOP5C9Jc62i9M}59>1E zjrAJv$vO^rW_<_zv+jd@u^xnc@wpdz){kH>|Ehlp>rL>_IuzovJ_S6iTLCBQSvbE~ z=fb$0`d6R_53~nA^aI}LAAB+{cqSh3Pn^gL@grXx7xWx2?8yWCkRSLbZ-`4ifrmT; zC;3Odm>1LMkih;8(&4kidQe(}$42J_OUBkih-~)3=bo zz6I0IkidQh)8~-D{tf8a{{VaTMZgdHCE%ZZ6o||I3gBVi1#q$-1NhmefpM{a!}O&D zdefH@*qgqTz>n!m3H+PBlpwC@O9}9pzLWr`=}QUlo4%A_T+nm8uqO}jLw?|&ydf_6 z1RnAXoa7()nHSUNAne~TeFDNh0n>n_F1;V}p({CW`H!yt&!afAkpCIf{FntTc zz6I0IAna!_eGb8W8G80_z@B{(@WXxy_-7vl;;%0z9TKCBSL=PXhd=FC`ck^c*kj$pie5ANVJ4h)X_! zhdcu(`3HXH1^t<|-|HjSmfos;n^k=?xAV?k?bTd9vac*&w?%t3o1N<`?I&*0Ud>|H z^^@yv*rM;G6GrrtnO#**qKsZm+MrjHzeTSmeWF*>iJQ#0=+$)PZaYMh_}w^liS`uBE*9%|7khY}L8B9C|lJ`!=6H)>P_tOx3>4rP5T6yqKzeo0QSF zNgMQS^0(;Qq)+qw=|8r#oYcPgp!PjZFtx%vyB*Yi$a@=o@A=wqSuMYUymeo`_F>izSCY`aJnhd+TplgSt@5;Q^Q#)M zQgwQ+>bJiZCr{<(sQs|Zsz|YprdP`Jf8KR_Re9~*Z1q2GelccwtW- z;D`LcKl6pS-!81XZ5weRum2V!JgYOeM}&YKz|Z|um`KFLw5 zV&v5gx!ON@x#<^5doNe}D$hs9$`!M6wcm2=kXSiCE?4_7uU#1{Z}iU9{>=J+#L7ht za((n|zTQ7h!o?%{@=N37;r%&k|I^QLvUk0y(VPCyZP!+oi3@Vnf5&N+W%MIC8n?x_ zm1Uu+>7$Qy*H4ut!|dya{?etfRb;QJ@1yVZ<>po7k|sIYxA}WJv!7;z9PQhr9{rHC zN1r79pnsD7(O1d1=(i*u^kEVw`ZI|ieVZH?^c*kj$pie5ANVJ4h)X_!hdcu(`A6R- z^Md}y5#eZg^Ugf&d)(YPTCTst^sbw}O>aQ7Ot~db`y^*R7A=o;%hUeJW~SfOZ;_{c zl{Jq<%gKs)+HX0pX^dq3oU47C_e_eBDSL9YZ?n(#7|C0mt9_e14$-&SetfJ991*dv zyeU=^JLRgMGf`%b%c{BR|IS-DM5&f{|>&osT5&N#Gb)`*uhWe>ox1OY|&rtufMw?zH z(^FyIgZ#d9|UWGJ4RDfJ{gDnoJp^m{#NGcZH@$_|&SFC+S9XkS^+nEFzwSBCbL zQE%QaeA=7$4xfI^`$*v5yr=k#Yu;ac;xX?vK5?4&9iRBoSH^Kc&+)>ZJirh6fq(Lb zxa1Rf$TM(~fAp0xFUVKy!dOYWF;~a?_>x$8v45`eFm8RUBzMbIey+)gl~3E{DsOqE z%znN#a+S}$-Q%R*rMb%Ubu;56=5UVYt6F-TB!82m`6}L|vQ#m(D&&j%SyUgRb)Y#9Q7aLRgtNtX9@W#^^>{2?ao#_tLj#jUq6fVmp;{_ zs+|2G(s%m6(5h0)JgZ<_d+x3(d)~^{d{GY`Xb*nq2fWcg_+(u0Og!M9IFT3PN4_{N z=s8~4lLz=AKk!f95SM%c4|xVo@{fEmFBsP)e>RaJ@1<(KMwMtPS1wJ}eBBz?R5~q6 zReqXvY$_r1{0ZK6jB6^7j!#uSzg*c=Rt`#4o?90*l|`l}5a-tw9hym}*i_Be$yv?h z%^y=VU&Hgw-1m+Y)u*&?E)`d#sD1LZ=JLq1DeC8?ea$6yc#8TjQKf}kaczpm{dqtO zNobIwcwTv-g*<+h`K{@T9`k++d8BxX;ve!=3t9H-KF!w`TUyA#pZ00Ks0R)oJQy-=B@-*BNQ*zsI$v7uWQ(n?8!L39XaDNPGPpyU;#{-4vE1A= zP4T~dw6Q!_J5Bq_E;-X!+Sf?azB1}fe?l_tP2WN?{g{4+z`yBpNM>Bq|BysHrY|Ci zI8DDq67i$2jN^iy()~u$>%KKl^W`tEB<+?)^ez6VB=4M$4{2dFtob!f1IoK2QA* z$%&S`WAij_|0*%^a*;g6Q_wp`QjSFWOTW24Ms}HJS{!fdo{y1YJI(u@8CUGA7+Je5 zSMx0fO)r<&}q9O-NQb8R)*S1Qu)y7++UjWm0Rn?9oC zIW?+F_lzv%`Qp2)OUO6hQknBB?c?gQ-+Y5(`jL`9D^Wu_jL*`1wY;^4Oz0QUFZ-Z| zeB3Z%KmDSb5_L($&mFyM%DTKv^}qWi^DT+_1_9^Sx8K#2)b}zqUw0R&C9(4|^|%Vx zswGj+WNN;e#MhE*AI;Q!&F)l7ej1;t`Jx^?&>sBI4|t=0@X5H~nRviIaUw6ok9=`l z&~v=7ClByLe&CZ#p4A1 zU_5@%C&uFn{bM}d&{xLe5PBY;u;+0LKRlk{pT{}k^7scHo)^H$^96lnJdZFg=llxv zhKIo3@DunkyaoOZpFv#1bC`Gx|6$@Zc?lCg`pP&i=s8~4lLz=AKk!f95SM%c4|xVo z@{hhU<^|(&&aVXK5j-%z;D>n!Z#*8rCyx{G%;N|A^SDA@c)THBJPx7f@dfAWU7hxbA7#``1qhJdcwdH|_iNbmJ`O*;zr#Q8`-tm2ZzS+J0XX^mfPC?}0^@R?Hv&C)pgs7Z zAMi&1;FEE|Gx30b;zVAEANk_ApyzmDPafch{J=kXLtOF+JmeWT$v^VNyr2)T>NRbo z?5Mrk_c*0T8~I|yUhRi`aA+GTFlz#!Z?oGoZRA+bz1lx{cx@YL+;*?_Ri>S8BZK4i zYQJUgwr!=)`90dVS?lSxQjoew`!+A#(^jtkWRLc3KGvX}yf`bOFL=D2Y#bG_-?O8g z)bFxK{j99qUbfcUqyDQ5YcI*g_h{TJ7q^!aha-KYtG{b6O@D~=mp*%@z106I(sw%k zvUnMgxZ9uKd0LIMvhh;#Q`N7h9{rHCN1r79pnsD7(O1d1=(i*u^kEVw`ZkFleVfj> zJdPLk-(!<{QSy4b1KJN+^Mxqc zam4}cldRaFf^_{lU;8H;7po{OhUaTv<+jq5Wb&~*?YG>0O|+yB&C@>2)YoFkE*IQg*_`aj!*`Cf^>&B?!25pP$v+E*M|O~TEx)lb}p>au%&min*tV-0C)zJ)}; z=vNojk|*Y7DxTETS~9AodB!mPrQ0Xgmh7YZ75|s%wWa)q{o1#=;e2iBzgqQ))T1Ag z_UMzOAM{VsKl&;e7yXvRgFZ~+MBgUyqi@q0R}#kyd-4E3WSvTWWGoSw4Q7;;DISFL|lL zHpN--w_Z~6yRC}i4%RB#E-sBXIx1fFYL(!{E#2`CvS*LK7ofk11I?he&z+^ zV!qJ#NIm)?X^%ch`a%CB{iCmvanWx{Jm|wDPV{FIKl(N~F6cR4*pmnNAwTd>-Vm33 z0uOlxPVx`@%nSN9S^q-cBkL^ahh+T)eUhxppnsC}8uV4Nj)Q(n)_2f{$+{2vGg%Kp z-zMj=p=bRF_N*(x59>|v&pH(1vOWbotXlym>si3hIv2*p`WN~hsWm#|1sd3w!baKja7g$s6L5Pv9ZXz)AjrpLs!lBlCs6 zN9xfJNqh83(hvG4=^uTSjEjCt;z1uKaiTwy_|dn?aY4`V!k#?95BY(A<_mGjC-9JG z;AFmlpLxN!m@o7_QjdN}+M`dBe$YQj|LCh^T=ZKK5Be~P6aAUQkG@Tg3wn+h_T&M6 z$PfIJH^e2Mz(byall%ie^J3LeKe9*mE8gemK7h|D1P4T+YV=59eutlk>OeE91N_#^ucS26{7( z8rYlp)xeLLcMbfT`Pd+?nWqi#nEBfPr!g*|zIAMykLoVYt^&0TWIu3YdeFyxr?t{Fr9)x_cP6R#cN3dsI z34T~_f`8Vb5Z9@H3F}tC$$A#@#X1+p<%tjmBm)@#5g>p0+< z^&Rlfx)1WgdJyu(=U(VpKY~5$O7O#a6a2Fdg}AIw0T1g|z{z?R^2ItA#^uz%0zG)3 zJ@}y?@J9dOlX1Z_@qmBgL|%v=`Qo^s=XhaH9^i-kz(09IT=EG#f0F$M=&NKO0{Si4pMXA0_AQ`4ll=_n+jROI64?I$d-g@Z z5BnwHpM4aF%l-=BVc!LCvL6HZ*{6YVv3~=7kJO_dlJ@A6q#yK8(m(nt85jMQ#DhLe z;zWNY@uP2(!g*|zIAMykLvNhF@T?a8W{AwIt!G0!JHzbiq%AHO#-&oe&1Lov@e zKEF>v-ypwRG0#Olzh^PeOFqAIDO@))vaTlj56K()56LI`56Lt756M6J51AJ?Uy%81 zkKFMY61n5EC344SPUMcyqR1VeQIR`7yCQddrbX`ftc%?7n1r6s#<1rzGyL#b8vgl= zjktXF1|B|>11F!=fuGOt7#E-IF?Q;~3GKlZ{eVOI2e*v-PwO3Z^M&h4VSl@>e|SOk zx4Zc&yvId)9WRu7oSQE^cNKmIl!<=h3*tKdU3r?GcNfZc<;)jyS2(wvp}D(I=9ZZ+ zuJ3_)V6OXt`C+aHf_Y=E6N33UdNkKZLY(!?$Q^s^O)q!QdtdlXMC4lxY|$Q^s^|Hf}3f_xRO8y{JJ9^V072ovWC)yvKE1xFUW=awPomeccJXp#(W`ng=@BCYVIzSHCvc3#qFM_O)cbkh{XQt#UPYTssT7ch2=Qkg@(D*TpjHN(JlDnf0%Nb?VGIRKfanW__w)T|2XGRWjG(GV56t zt_Nt=KQ!xK{ZFh1Sh!ER*>4@^opZnYNAHvF-0y<5QgIIQT8i_I>j&bzQM;Q6y{=(pg`woLQ?newhxlb{8=KjUtpZgjkFWm1K z`Qkpv&~txe*mK`x_~Cxa@Xvjg5ts8Gz{7o+fs^|+BVW$`&dJXH&Vk;nzZck>b@>86 zIPd7+JgWq8&9h1p@!+~goMt`1B;v=qsT>#d953w21N@L5_$P0OOFn^zJOd~B$GWM^ z3(ha*3o_SubY<|sbp^o>*BbRa(zPZ%ykRFKi4xvUbxO7^2PNJkw>nJ2tC(J zggw_$gdeW22>)Dn5plU5Bk*vYM&RW7jll1$_n7Rg_ZaBG5ADGl{eVyU2hWTP{)q>9 zAx`9r_>o7B3wn+h_T&M6$PfIJH^e2Mz(byall&u(%!}zI_Ssi#*6Z+{eHeZ218COw z@VP&rS@*-|zJX>v5TE-Ansq{a?lWlC5AnJGpjlVMXJ0hd+h@Nt^z5UCJ^QQShke)Z z&wgygWuG?iIQuaA&OVI3vk#;1?86x7%{m@|y;tU>Hyd%;vkg4X zx=g{k`oQn3%j7%jG6j0@!*!g%8~uP!`UlU93;u}*c_B{Zi};a8jthE@7xv@28+?ym~oxbG_X7C5;tE$}=0*!s>swt*hU zGwpGl(+`e+`p0>}xHw;k2j>xS;`}0hoOc`-^c*kj$pie5ANVJ4h)X_!hdcu(`Nw(3 zyx{y|z92i_uLUxA;QDFchwG|=H?Fq^KDiDXc;@Aoi zRM>OBRQTb3sqoMJQW2N?r2-H4O9f8umkRvOeyKk9OU1rp)MGy~+GC$G`oaEX^pAbb z7#I7U5fAo3BTnp(M*P?}jpKrz_=lW*4~PT3+CgYkYxQuKfkhxh5EL!L`DWJFX#y+;JTz=(*+??70>h{BVsj_~+VX zh|4w2fQM_H0Vmf$1AeZJhH-JtG>n~ka6)@{=qHdf^*_QE{GF3BL2T}&pS6? zW{rzvt|x>28M%Kk_HE?8#@Nr1`yHFLJCeB%vRP*@nfoJSUr6qoY}VyV=6=d%y}o4b zvyA;Exvw?2A1*k6+4f}Z1rJ$Zm1@&o_m4ROgQ@Q`QVB>%wA zytw&-%(W#kcCKLvPPn!qxZ;|J;E-z}f?KYU2+p~7B67hs6_F#ZwOF_}Xk_nHnF2LhNJ9_3_L)*ulDa*!Py}>6vf4f_3)HcX`43d)Pmh z>lR{PU9MY*{dT!-A@oY1b(hhh;eb{=qHdf^*_QE{GF3BL2U259NR5%j~Nz z)8A<>J8#|XyWjmm&pp%KZv$Pu`&-EFKI|W7UM`#09KinUz9Wkx`>wqsyL$JxKJmaO zG4H(T-DJxDRqxtU#{TkiX7`ZjuQp*{`{1|#Y2SH#GnL<~mkc|<5qsPxjcwjbs$9Ow z$Nu$;(tAp&W}AHMUmw-4r#x`)Cg1gs-%c3OPiA)AqQ5P6T|c?*hAsNrX6O1!`-xlh zx64QNmBs6}=x=Mk*GH}`9oZj*aa|1f_J=-Q|0Zsj<1%={#A9%ViPPW@6F>aWKYq)& z_$~3^x5SCx62FVV{jH0^aGOBRAu~trH?99w@7hxyS`Sm3^cI08%arg&+?5DG3 z@}%+d@vtn6g4Yis}@hWG1tO5J=qb+37(`S6F z4Lk5~OR1V&;A73$;diu_r`i>${@%1Uk~{OX+868IPVPK*O8s2&Mtk|A|0(rfW>37_ zyz!*Q{UAFe%le*FJl`aSWzNYHigW$I1i5_K3B~_@Qi6mgozQWu$ViY!$DHu7W-Rqs zGnV#PGnRg^W-R?<%~;08nz6)V_O0-VbKSbdKJlAZJirh6fq(Lbxa1Rf z$TM(~f8b|ca8F^raIc{r_aNHi-b6pRXVE|IWsHk^9P!}ZN1V7P5pWyi;6uyp{Yux&Z5NCcjs?wItkJ;NzWQ(SX)+Z@9q6J4Knrtz}5%0w3=b z`A1tzvENSnc&FHu&_;&sIql<}LguuQ*FTKtKRVDxQeHT%_6ypzmG&b}tDiB?w3Up` zr`3Pv=C-oE)@hCVeTjDR=VhlA&jW4SNyoFN6ld34+ev)hDaGIJzIHM)^^|!oU7Eb` zk#-Wd_mq!ka_aG{PJ2AV(+{5Q=^xMhjEna;;=%hJapJv?`0+l-aY4`V!k#?95BY(A z@`kwN6L`ooaFT!EXI}6wUt&^ADPHc3kGYFcQ(DR=rO)`7)427OmXcrmjE}jFrpYZO z>uiCKIglO4TS~Re0v~fDU(|0U{k|&jF=x_xY%96?odO?oDJ7Fy$$`lQIzM)@RBP#S zTY-%wAykL&H`HLOo ziIvB7Kk>P9J4o~8$913aXWr`|Ll+;{{l^DxH+#CxJg)na|N2J3--l9_S?Jzdxq>VjDY2yH&^3 z{$TXg^78Y?)KBt=t0gqznEG$F@@i?^^_a%3ap-Cp+~}C%`LdGPKdyrLt(liz5bi85 zmpG>QpYPvUHvWE8_d`E6ptDT;<*4q5PCe#(X^(ke`oa7#{bSykaWS7vJeX%DPRu_O zKjx)5F6cR4*pmnNAwTd>-Vm330uOlxPV$d=Y32p_^3u%pt!ROcw@PknIr+zF<)O?k zt)=R@)5=d?TpNkbKdrny-K&iZ{O+{!IeuyznfCE%<@w0=HZp0R`K`&#p`PX!I$?S$$f2xoOZT#b5r-_VTQGR>8O)Ue;dP^*N>aq8>cZ z9{kV`c%y&t$++N|c)&k#A}_>`d~saRbG)!85AZ{N;Geu9F8Kr=@(i5hANgWlFs^r{ zyL^7rVIA+~UAoHy*B@3Me!I21Ea`q&`PuPAcUjc_u<|zU!|t-b=3(V?*s<`OiCrs!e6K;;!58l#4Qd=BS zKP@Zul*h^*QvdG`?kQtWAJn)nztU3{?>VS=+HdYDSsM;2&Qd3OO6rFP75^W_ddcNW z4{E;dDA`MrmK@Z4Q4bzy4}RzeywN}SWL)q}Jm8-=kr(1ezBn%EIbPV42lydB@K4?l zmwW;bc?M4Mk9;vN=m$G?=QZ-iQ%7|_@jhd&k^YY#)qTc0PPs-VKX_F4ACFpkjZ7MT zRQDxcyZ0JN?tN7ED_>UrTC?}kQQZ$cX27+QdDT(f5B=0T*UIFABf1~@4?kTix!aED ze(2qMc9AN}B6|OgE^^D{BWnLvK^Iv+_=x&>q(fI36gr~*k3QX1ddD5nxEUL|%HtOu zQ9O^I?kb-hJ*+tUM|G3+X@?bm=Z4+n@Xo`!ANtZ3-Q>0Hhjl-6>d|LKd-Pw?5Bjp` zAN^X4i#{&mL4OxBns=JIoyv&!412b)X#U(YC?NgpZSQT{LP+(Q0XbVl=acy0?BGU1HoYw+O~^6K>w{r3qiWq0F<{Ui^H`tz`4J1seDC;8yb6$^ykRXGSXtFDOu)Bi6K%HqR9({#!P-k~_^a zEym@2*Gei)EYN&W4<2X_e&`3h(LeZPT<}ah;GZ~=7ve|0I4=Pu>uh zd;$-722S#id@(N=*TWyj%WZp4>UdMUcq#kCN#$Yl&Uop#`K0o*_*}fiC!SQ^I@Aft zqi>&7K3m)ol9f|WYQElH8j?k$PHMg$JsXma-A-!0ZtD`3H*22MeC>KQEa~S@sJ`3D zuvFZ4LhT!MN|5m%olrkTXCz4M>=Ww$pp0vo9T~D;Bg2&k5Ab1xP>1c&+yOV9C3O40}sy&;NZJirh6fq(Lbxa1Rf$TM(~ zf8>jK!J0OoP3bH5S2*CCeeK)VnATTnl|SH{{qEzhdb6+GaM=MrrTUWiLtpik-oNDg zX3dcJsixL2GdJH)Kk-Zaqs{xthK>3D_gzYbPCVRCRxi)@d-jM9ef4EOx#78dfB4dB zp=DA1W$hjL#!t;q-Vm330uOlx zPV#T^vYvSvTdr93on4yB=V#9PW?%dG?RPbmi}KC0V$_7tmz$bOi}h#yR#$!!`gCM7 zdGEfnzFAu-wC(EVGPmqmfBhpR!()24ko=d=_@A$=9DeBOmLg^@>-q`}!xPe4$=(MG z{McSC!)3a+kpVkT8$WHre6NJQMyS11e)5#sf4VGQ7N?(7KS_Uvq+REe>i?_O2{L=# z35`3vlSod-6N+bIOb6MTd0cVco7h3FdHJ~F9~Re99vXezFY(m8nztu(l#d6iK9PDe zE|2zRTps;k%_#ae<4R&&Gp;1!G2==iPJ=&*_|3SIoN*;_ys#$^@I!v!pS&S1`2-&F z44mZOtMO)mMkCp*WbM9Hktf! zrjPyWhhBZVB|mZ5=92fK)FYL(!{E#2`CvS*LK7ofk11I?he&z+W zNahP`AySXE5NU7xgz3ll57WPi8)jUCCrmsBXP7t*{xI>IafO|6g*jf>lLz=AKk!f9 z5SM%c4|xVo@(=vX3&zEKnd30fo8vIBH^*V%2kThUKi08iT&#siJXi~nII$KY@naoJ zjthE@7xv@<=~;4WOb>Z$&>{br zH%qdo^pNlSAM(eaoF!|Q_K>YtAM#68nJqW%>mj8YAM&s1GF!S`)l;P0AwPG-Y_tDq zPicDQpnvS~*)sdxp7Q;UgZ|qu&X$LM?kO!-9`s+CGh2@I>?QX;8_^GWvzIKtJ!0Sa zOfR`Cd{F&FckC@IqYtY8Y0vbQ*MB{raUcJ@w`|Wmpm?ej^p-N44=BzvQGMjH!~=>y zuVEi)|KR~2L>f3&G#{`rd#{TtSR|^kGb=O`ay%|3+;E-pD*+i`fZ-jfAL-O zgmLd&Gf#+T(5v%=INzQ&Pl*46XXgduf}Z1rJ$Zm1@&o_m4ROgQ@Q`QVB>%wAyx=&z z@wNf7wOWopr_OBIGI4;EyDG=@9?X`0-wlv!Ph|Uv8|KK30|v_U53~Iy556StUUjQ{ zJ1E<)P-d>o`R!Jjd@jrPr_YtBO9o5kV_E+7hv!O}rskgYOQv6<#yojy)DRgvI@7Px zdY0$)q^x-((|WkuV)2|EDc?qAT06%rmK|}C@>P#aYyYc@<<*)aCA?XtHEHEy z88vjI9IljUMXp(F&kOOOs-vXMp$yG$7d}c>y_2Ch)wYfj*J&AwKf7R*JRg#w<4$^U zwDkAPP(BZbjh3~~W+>0hS4PXKIvL9U!rP-IzG{Yrd3n4yTB0jwSTpJ^62=#&FBInA z*|AWFGiJ_0A%2_Cg~D-Hxh@p)S=?ZukmuQ&3vK?%RTtXxLY(tOK6L;N^#MM0!?@HF ze5f;cQh)GgU0$fUL`vpPki#R=t)DwBk)0zxq{{~r@>JXe zdAC!#m7calzAl;|ms+P=^{OnD-7P0dmB-Sp{Vyz)XQoY*+vRE2F~6m9>)1s3;Cz}D z+k2@bKQc-F*qvsL4_PXGMokirC64$vhbGCiNJsv*8k6OGhcv~RJ8-hZHb_(a;twaw zm^-ODZdT%CS(lNjd=^xnB8fkyD$jwfrpWoPQV+SOxGHH>J=j9(33HfK9Tx8D+an2X{)B!lu z2l&(t<5ExXq0Zn*{lTAg`TFM-GJkEf^mk9OMpk`OvNl9ZRhJYi#P3bHxG!2fo26K3 z)83Trm!qZK6Dij8O>au~YSSh9ezLXW`!~g>({%YHH`(fb{Z09N>2z81eXO%#e>3CRv!5_sAI% z{Cbl0=-L&+`18Y7*!l0ZTp`4%^yhLR{!bT|3&(A>f4Pv)^B*o3@|^hQa&u0-ga6DW z%k6m~&iNvrIsk|I0H3;HT3VFH(J-MfN!Mv@H^)l-q$FLxH8JnSbu;h9VSTvPXxQFpi1p#bDKjK>PLi$< zgRL3TAuLJPhu_wlDYIN0@%H0q%D$S8{6^+oyGQd96{oD)EID{GQSrwF&64d~6CLZ) zWwRt{d7|?9?Z_;7az>)^Jd-|49vhRW{Nu`JN#Ni_eSST6XO>iiCF=T+ajd(TkM$UF zbe;BJ_*lPjT&(NJ2kSlZ#5$1tu|DLy5a)c6PaS|meSlBhFfR23ALqA~|SReBHg*dNIB{lfZ+ajd(TkM$UFuudaB)^8ja>pJqmdXGG@4kUl9 z4>>QyIbY;c2jEa2;8Qn@OFhAdI)f+m2Y=RO`Rb4C=aS|Z?x~L zfulCs_uJVkHrn^$Cw6bN@6XSk+-TpolP_$v@8>@!ZnW?7i1YrBd_EU|!{-I?`5eKx ze7=AWpF7~m=MnhxIfZ%g`IQy^-|_P2{yRUaXoHP&A%266|Ka)#_PBq}++g!5AGX2f z>DzaM&A)4}4febc=kp8se0~9k&oAKf`Gs-$`~n|7zrd5vFYxE{>z&|D_WICg=_Y#} z(jtD7y*@cmw#i<%^n7l!y`Fi!$7Xw-^X!Dp_WGyAg3b22DD&;j_Il~^+RgSl3URIv zkZVrzF#Bnh09)7M?A6r zAi4RlBmd~OK@xO5TX9yG50aAavK7CwcZ6ha%hqvk$41DbZ)Pi>bz37ObY`~locKe8 z1dYvB{zI-t$h;xh7UmV78zF56Wm~vD8OL?Yd|c1O!F5i2T>l&w-wX1=_k}$1JtBX6 zzc??%IbY;c2jEa2;8Qn@OFhAdI)f+m2Y=QD>t5Ci>v_hpo@YMR^Tfe=p7>bLb6l+F z$p`Cs^2B3XajcV>kM%Qg zu&yRP*4rEx>u~bH`kXwmZYO`N=Q%ILIbY;c2jEa2;8Qn@OFhAdI)f+m2Y=QD>t60h zVLi`%53G~9AAu2I%T}^zfw>d7>;pBt$IeB8; zPX1WWb6$vZzR0Hzz@a|Cr*0URdV&vi22bh_{;Z36|4<$p5G6~)uHgMWnKC3weEMI( zdwnu|dX!A)c?IwLiQBp;8SQfg?*YoCQ&F`#UyzRX z52g0n@iO6bI^I8&acf`|IO^}Y^j{Fmu=I58+y%|z)^ zH(l{-#7-2?vNRp{&o3s*xWqK&^HIh``RqiR@{In^B>7}-n(`mnV3M5Qo`&}i<hosH}CZc^UeEyLLBoRpb+1@A1EBxyf-N1W8Nne@-*)m3i+G&5AAs&&iNvr zIsk|I0H3;HTaB0yvOY1eyV}vaGJyYvd zwrqr)yqKx+aaTsj-On>MzgN3R8L=!=ah{tOX?nXd6@Se)ky6nuQ^#HWcci?~+U#+e z>!(@UkuvrP^MB2Cb*JA*8Br}$`QMBhDR2Lkq4nxJZKMSLk)ics96B%``Va@Y5g&ST zTsZu#l=eyu{ z^SArExvE1!Zxy=+EVlY_J}ivO{w(le-xheXp9}oi=Y@H(|I74+*>Te^X6KteG8@PA zm)ZEH@5~<8^rP8)OrM&~)AX;|{Bf=>=Y=@ui+t(;9O?sn>V|QtC-_ij@TC6W&${4D zWY){{@!4_H-)HBWzCRns^aI-Xrcclw*YpqCd`w@V&C~Q7+Wbu)qCGFfSufH3zP2Z@UZ~8`U9GpK+e4Js;adCz<`QQv|^28a| zlY_J}ivO{w(le-xheX zp9}S3pBLuk)c&eYL{ATGMYU?6)<2xWYbM)1NEs z&yDh%F6`Si{k+0{Ueo7mKbH|_|1a{{7YrQs3j?2h#2AA$x5o4#y&UWjwP$fpj#p+3N; zZWxz(f)8~DPwEf;tP8w2mV7%+8pm9=;8oHlFGxHd%2lrteuh_x+r@D*Z+eP)l^l8} zN)j8Ts8>lqc)(h1&5O@y!*Fg)p$9*OFzf)GrUTe1FsVPUwD-e6J8}8 z3tlDU0Iw3~&jX)pCT${rRj(4~&u`zEAa|-Kt5-?HrC8ba@g?;tDIGIImXEk(!K-B6 zj2W_S&?O6ACEF^^kkU6VsaMILwPR)0@0Zl8B=?i)a(qLA`gp83*HVTZy`}yhOG{hI zN4syS@5j8*m*nhgrZ?aClSG%lBwf94sZYp~Gp(duQib}5G)rnNuaBruUy-(tw3UFqLpCef~*;=83pab_;_ zl1mSjDE|ET_R{*bVjZ{fPu?=Wda?3x-{K=t+l!QE^Ul7KF}z6mKfTRY>be){yq@~r zS3+JWQhyT0;rqdS_<;}yJ|V=1e+b8guL$|TZ-hMILqh)WC*iyh=X{Y*9e_i9fKS~p zF7*T->I|OLAO0k)3w%6SFZg>f4&M*v!w-Zw@ChNl`JH8t3ttiPf!_#u!iR+X;ZMSO zA}C`T(E0VO;77KGYdJsXzF$E|?eV1%D65;rqdS_<;}yJ|V=1e+b8guL$|T zZ-hMILqh)WC*iyh=X{Y*9e_i9fX{kiTngW9I{ZEMZE%$x z{tn-dE&E(0$-PYdKwiG=Di@lTsZYpL)!gK<+GXk=QnQnrbgnQxjK-g2{!%ybNGMgm zk^Tv8lDw}}{Ylz4a~JQGrRq=e`5bqNjdH}BoO72i0v-8Pns`X<#txj+DIT)_PKo08 zIp85%(n@sPjwK$FaH2%{WIpRD^>>%3Kgq$)o>FH+iTaalkMNX$cS_Ws0 z{Ye;y?+5eY2SOb9gb*M8AsiRJBIE-_M<~eB17~>)-KNznh<4=+_$wl5gRi?flKP+&OqsPkB4`kyu7dg1QOnpN9 z6J6x?x-#_-ae2&Dn$0a!Uy)D4UFFH4=KmUhlG$5b<(N;I`jZU()m0kRFH?UKUWf1} z>9*NT-ucn^FPZ$8%G{)UYpLSg_ji|dZ_T^0GP+d99c#JE;U1;Rr&_7I{O)G{ zukleyt>+=-&zCCyGc7&j`39xxPtwlS)VF@A`japY-w)=)4}>`I2_ZiGLpZKkZ&>7G z)*&`evp%u;!=HrnLY(tOK6L;N^#MM0!?@HFe5f;cQh)f9urB6zfwgI-p9~mXi2X^c z@_aw37FmdWORHjypLm58Vn5S5eaKH-x)oxd(;9!>Po}#RV*k?`($w?WQ{>H+fJmp9cv;VzbA6QvririG3 zR((b4njU=MZ(J)<`L4saVfA?tw`_->gG;535_{I+^HBB0jxr_A;s5ZfuklVfa6|nQ z26yTxefQo_{{+U(?+AFGwj!VkMkzaaB}O}*Mw@sL|B&3(_*>(MX| z8CbPc>$PN;hpf&h(fFTtJ><;SC7PcR;wi1xl_<`^jh=EYrbO|ZXM4(t{v|qY!)Lvu z%)3PS9P8^Pu1(GVHP_YKv0l=;UWxL5eYuwmF>4jfD`&NrJW{Ph>%};9U_SIA4s;_v z^yIkEnS7u>d7>`lk9u)lh;zQkrw+iOKES7L7?*m24|N7l>W_M{E|}Nj&AZ9^M;!hh zv)gu)9yJ}l9}~KCliByLt3LkYyGcyxb=B?a``zR~>UGuge1h?^u&%4lof~$S%O77? z{ToDem)Wmg*Sh?Dq`RaCiavsqxA1D*5tyTk})h#>vg`Or@S*b zPwT}vbYMR8Ar5pSKJ?_c(3yOoKY5}qDTCn`WQ4l5h!b_-cWyo z`hNw=$r}agd$269lYDiiK>ZMguj(Y>I}6k&p;KljIkKog{Syv*be4+Yj(F?kou!SB zBfoB1XIb^Q11GO}7jZQnGNxZRe$bRI()3ckj@x@@7wLZ_U-{fj=^|@C%~$_~6MuJ+ zRcrFqKVe@zeACZsk8ApTdloD_1>V`k<|d@n|xA+3_D;Z7VJ> z8xJ~jURX@4c9JllT5qbhd#uCZp4S492Yv15A-Kb)P?*}FU|{b&KLRA0XWnL_|y&KQcv)q z&frP?Q7_g7^~yFLaqg>3@2&Co=)SeR$H>R7BgKepOiVwx1I{`u+NQvY6&*5&86J~At{Nb422&`0)t<%l0jGTvFM ziZuVjmc9}+u}E>EXZcEL_aeo=cFb3@S`_KHmw)p$zaxs2&#V?5B=mQOPf@R+4ic2_ z@Gt5xs)NkCTB!BfJfVZMO)J!TF%BJ=4}FLO-G~o8IWBZ2ALvh>s0;a{UYr-=oG*FX61djX#OzQ8|$-y_V+>HB5JjShCc z(Z|Lyy4m}C`T(E0VO;77KGYdJsXzP^ zSQpI8>H8JHIzk857y7X7(2dsv^yGB{oq7F0e_mIp3$HiSi`OCIygrf7>lQe?o`KKn z9OLr(2OoYfz?0t>)QjIE%**NfWyhfd^PvxMpd0a_C&z`(kT^&9heV&hy&e- z4?Q_9bS59@PoAg?`J-N(7vh{R@~H!Gs1NX|8^)!c;6t6kllr4xtPA`}T2JmH-OuJ& z@F!Uv+sAlN=cw<;g5`ar<%t~i0}0#HN1E=OS@&9w`icx0 z5iCn0bJU;2_48n98IYs?B=zqG%ZdiTdBJZ*XkR&1k*)E2+xyD>v)P)T{d-@D+?lO7 zUv~|WDoe8!zxA6Tayu$p$9?8>h&1byt$eKCLS$Tf(=%&)RNigWPa>OVEB{5V#yh2P zw)&Igd-s!04K;q0ark~PAATUjflmnW;UB_r;VVKu@Eajd_>+)7{7IbVb)54>K6L;N z^#MM0!?@HFe5f;cQh)f9urAT{7B!J}t!4eL3ibEs5Yk!_HyAHC<4@wUzqM44u24Ua z7ed>}Yb`3&C&af^Tl4N^x%!8sdbN|I#;X(lB-bXpNIkQc1%Hz3Ctc<9R%Pl>GSAgr z+Ab?qe-i$#gg?pZre0F+RigPXzSCZ2yj!d|FXem7BX^1v-|ZP+88@v+$GzCHgB<>? zQ2FFn_LEQ6n>B{vnf9rlH0WEX{4Z4TmtIW^)t}_-i~h3wag85i9KIjShaU)W;1fc8 z_=j*@_==DZ{6@$V{v_lNe-fv8#c{sKrw+iOKES7L7?*m24|N7l>JNVs)&)KuOTQc- zCst;uzsI8U1LU6R(S|?CD{ceDwSSiSflRqLP(xz%b)W_K6L;N^#MM0!?@HFe5f;cQh)GgT`(`!3;rIA!}o*v@B<+Zd_ss1 z{}7G~UlH{v_d^y`;18*FyZ~<-O$9Cms2F(|XC( z@?6DP(xSI4IG?Nde@y8uvHNm$+?zXl%a--I+JE|1YH!JTJy&@~-t8?{qjRLT^o^1a`bo(XeWv7({!`8ian2X{ z)B!lu2l&(t<5ExXq0Zn*{n3BQx}Z-p>v}JlSd^>&9$ia%$- znk{=vH=`l?KzB#UpzamWADOl)ulOU^(D#)=p+#8@~#cvA#L#Pr^9*I+>4t zPvW2tl=$cm<+$h@B_H&Yk|+91$shfvoEPGpFY>7aaHtRPsT;}YQ~f=BMu*AupEA|=!#W%$4Yy^gAIQnTa2aWQE#Oa5@9%K=s9vV}huqH| zB;lWDsISPvk_h?A!{IkF|4H-A+Iv-fNJ>J7N|&Zr)t{vE`@`h>cdlss{VT(z$NhBm zC#l&WQoLf*6{kwzNJ%M9Q~aetqr~fFbB>G|H`aZ$l+`hQ3&t@FtdY~R z$4Km}smj04*)g(xP^x~vzAG3bH+!e5KMCXT{a`-)K!^jM5aPo>gyX_jgnZyPLZ0v; zA%FOja9)UWzR0Hzz@a|Cr*0URdMcm)(iuFdKm18p7x;MOn)N_WvmSsyNzbo`$e&SH z)%U~Kc%8KxepUTI>QoGo7lW^=Pso=|hsrqbtLh)}>4>4SzVTJ{6?uHyP+4~Oiu#S* zC>tuR(oOG=@ge!8^Duey@D=qZ;k*z(QaDU1O?Kpe6kvKxx?fS8m^X(@RpWaG|C8MF z!{yhiS9IK@TE;u&X1em3?LR`sUrtw^K_f@Vs8i|6-~Z(ivgTO2`jdR}>Ims_BwhVU z7>Dl%^Wg_V9QcF~AO0a67rr9o1HTdSgbxY%!=HrnLY(tOK6L;N^#MM0!?@HFe5f;c zQh)f9urBEP8!~#VyjkDj?_o_GEB=o;d_VTSK31mGaQJ~N+B#OEeos-KkQXnHmCvrF zsDH>)kB*b%(<$mJvLbAp{J0}U{YfIXjFTx#Qq-TM%k6P;c4UhBlYHGXN^1By;%zrY zNoV7sfqurvN=*+}S+e5f`;C|G=aLnF@EhaBdvCIi+b7=iaIH&Lf0E+j@v_T!XrQ0* z+s7uz)@jM=PjaBe1W6d1to|fVx=fHIqmtF1gmLr-4;DgEXPJfz*qeEdTjAQGG%V6it>chZ5C4WP8ggGIK+s`jb30ZHkPWXa2A0 zPb@w*MIJJ~6X;vK_{db5=$WYgB;7|%m2Gt#@#BZ4N@l@j&HuQ@H0gNivf|7dI8AcQ zSybp}EckGmTwZut$4yI|CRHa~RzCBpM@zT<=Kq?0#*kLg(y{Yp$3WjFpfS!=A(a*IOr=RKKczgF8UD32mOiUiM~bhM?WLyg*fMneChxk>H~c0 zhHnqQvr^&0wFYCIincFn^V*h1bkKHjE?l2m{ zziz{lX;SdkWnI6mGVcmDH17&xeR$t!_^{Cs>%+tW(ej1MWnBjz-5xD?toL^@lGh+X`L|4sk@|HL^!c?iD@IP&O3?Ko<5+hwAL}vV=sNAc@Ued5 zxLDVb57v9+iFF|PV|~bZA}C`T(E0VO;77KGYdJsXx|-tP9pr{C>gTgLTBZ zi}l5NjCIHQkkpfmq@FCeM>hlum~L_V)u;P83|KCg3(%j+L} z_`Lv6eqX?!-y_V6-!H7M7{|Jc`B;w;2kSKAWBtZ)v92Q@toO(h>p=3y`jGQNobyFK zbpQ_a0X}uZxYQGTs55v{fAD8r;4{GI7yJ`=pM-w`@1O8b;C&VT3B2FJKY{mQ_$ToG z4F3e)x8a|_`#Jm*c%Mg{_kZN`xd0qKFM!YI2*%~}1$_A20Z%@Uz@N`4%!|)2_zy4+ zUjpXCuYfr4F(5wt4LB}*56B082;>Q$1oDS}0_TM|=Zk#m037NAeCmdAsVDeQXYi!{ z;Lp0i$Ajxb_Oe-f^v z5a;>|`CNAahwCxmbDf59xqbs5uIs>)>pk%2IuP^X`VjsejKlYX`S1fF4tzq05C0I3 z3ttiPf!_#u!iR+X;ZMSOA}C`T(E0VO;77KGYdJsXzF$F1QY--R~#WzqzLV z9+#?z%GYt%)c51N#-UPh;F|h@d=MBa*;}ruPl!)UsJyW1n)-*d{vuQc#9mWhkxdn$ z(rv&s^(UFpvA-0!UQ>UPL2LR;uSc$_Kgrp={<8Rbmc~1E7$DX+S(@K$t{DN^Zw2QBNru3P5gdL|C8bK>Lr=eYP@kPp5u(h!6h|jtgHA^1=F?JmEt^{_rQ^ zyb$Mnkxw0fLw$fx-7qfo1Rv@Qp41=wSr^QU^}>3XajcV>kM%Qgu&yRP*4rEx>u~bH z`kXwmZYO`N=Q%ILIbY;c2jEa2;8Qn@OFhAdI)f+m2Y=QD>v`@+!QX@X9#|)HKLmat z+$Vug2=`C0-sZjvd_}n5g7rN2VX&U({tWy{xNn0v_j8cXeIDR&{|ETo7s9yQF9IL# zBY`LPm%yLqp%)k9P4D}WBp7VtgDHS^)|=FI-Gp4J||DC+sPm6dCm)Q&KLRA z0XWnL_|y&KQcv)q&frP?!Jl<8?;pyn4x?pAEr-8HN~h8C$U_d_k28Zti~qe;yzeKQ z=Z%*3C8>B1P&)1zEwfWn@qVDV6^xdh@u_%kP`0%lBOh)~#ruacckUSRpP!2N4`qbe zBidy4h|tfN&}6Knn7@4>-ecBSdHfMae(N91-$C+I6sL0iaq`snDT+UH@HlzsvlJb7 z{Q7a?`&Nqbsd0Lo%$=2j_YWog#yFWdE=Bzlez`wRwhm2E{{+_>Q4$uBqW%etoA>(c zeDl7a5XZa+D8x7K2MWhMX8I7x$GlG{h{y05#rS@ zL-jn~ey~J6o}oIon?G0v-M*^zs`}Gl`Rn3UtxG|pAu{xft6Hz&(L?0DWsdlz?}o_5 zQI7mWPYf0JfUAnLa`aHs&vjMt@9h{Wr~h*J*p%lCmEW@*{x)ms4-=oC9lkeFKEuTQ zxWf-;P~TxPdjA!z*Ril+Qvb^!_8GzV zgZ)SF17Tkhd_vf-1pg5BF~L`a{Y~&2Vc!#cNZ1bre-id_AkO|N2|IPA9qKKrmR zF8i~IXP+15#r`k&doT{)59Y%UggEdCA-?H5v&V(62>HNoggoIxLjLe4 z;k*#%e34HbfJ1$NPu(ys^#mX444%{<{8<25>e-Fmt`@wwp zfe;5iA;gD&2*-u52>HNoggoIxLjI?XKMCiBIOmIe>Hr+-1AOX+aj7TxP-pO@{@~BL z;C|@T?;w1y9`_l(Z;$l`-^0gxgYV~Ky}|ePvEJbO{J0 zKDfV;C+>UXkNY9#g*fMneChxk>H~c0hH!*Z1$?LeFJXTc_^@va^cu`U%*(0&%Z@__=0hLiKsVw;PmT+n$p`wAC+b4}s2AsjIOmIe>Hr+-1AOX+aj7Tx zP-pO@{-_u0f_XXhe+m1Hpac7lpbz_!P%ri?K~MHEL1*?iL4Wo=p)Tx)LcRFj7vk)n zLO%PdfWv+(;Ij`4seAu@Ip6usBz1Zi4c{%le*>UK=eCR_Q=tg|#$#J1G`9Od2 zL|w=q_2Rq`=X{Y*9e_i9fKS~pF7*T->I|OLAN68g;N!vmW%zrrPZqu(?4N}n2>WW` z6T*I5_=m6$7rr9w&ozC!0qom_KMDJJ;ZNe!=NrKOU*xkd7&z<~20r_UF)sUy!H0dv z;K_bu@MoVg=EeSH_`I2_ZiGLpUycMaTz!BjgDm67q*X3Fn14=Zk#m z037NAeCmdAsVDeQXYi!{;Lp0i$AkUL@b_S!EPOxMKMOw)_SM2Cg#EVg4`ClJd_~xw z3%?Qe?V5gGVLvbYN%&kwoc+tlXa6#A*e?ux_7P)T_7{T>`;Nhr{m9_YK4r{{{mbz8 zU>v?5%!eNcao`g|eE5fOT=`lrEvgT88JJ!8>t&8%}Q`mmYxk41kr_-W9$&8(L! z`nj2Pl;z~}X3_r*`SgVY4*lYQPaipqOMf}=p?@8C(!UP;o&4)8`q#m~f^qm-Fdu#w z#DNb6@y)u_9v8kDr&{<^(yq|Iu>=|`WAKMx)*ii^@%vw$;jvW88}>5 z1E1?{jLUU6_;7s=o?N$sKiBh^7uWgFfpO@=eCS3T=t+F&%yFSV`JgW3iF%R$|D=yf zyFb@T(ao3T!i~%7pR;iOY&p2o{7rw#YN@kwwtQpW4S;`+Ps7>rbmC?8&w0D~%kpWb zMD@>k#hgEqZ{7oezfePSrb*A^N&1;yL%{#P;m?En-UGj>a`;{REBvOM>*f3`cK-a} zx$N*Q`6oY@u|9m@%cp)s{|a9|=XyE+W^w-f;P;Ee-|3(H`vt$FANZG+S@@m)Z}2a5 zu9x%Pj`L^ilW;%b!9I_}U+AB<&x3kB@OduM@7=$}=b80F?YIZ-{2AXn?z`f9$Nks` z`{53Mwtvcg_ya%ueEr`2Tm0}@FMQYdw?gO7_}=mFQ~2KT?^gKU@$Xsq`vU*Yg}*!S z?_cWsf@P=DvY8=8Hs2j_;A zmcUo}UvX}TbG`7{Y2VfUjQ10`?~3;pxbKSh8MyC?_Z+zIiuWJ5?~3;#xbKShCAja3 z_b9mU`r!QvhrhSkPquZ#^+P?)ezL8z*-y6hH~YzUUGSa{|K5T3f4HxX_ky_Jj`xMQ z50CeVxId5gi@0x(_l~%qkN1(d&yV+%xc~p)d?h!j`s{5B?=Mj|yuU;}@%|EZ#`{au zAMY=*F3$DBXMXRTKRtXYxH&tTXxkD%P2NuN85=?}~iB2MZj& z9}9fGH;ZxkJ}vn0JzMbP`?uiF_i{0>{}+ z{yeT{zE_XyobTJ?`saK2_+Ie+e0*Q{-afuZe4iiRFTUrG?;YR&N1S~D$Y;L*aM(ux zeD)V$T=pG+5Bm|olYI){&;A9>>;Kihh6m>wr|I|Z-*T=o>xFBQJzvhBaow`d2-h?F zk8qu{FA3K_`<3v$U>_5{FYIr^_lSK@_7942*)Cm#C2&#nlQkmMZoeX_m}lh@;N)DOz7R=C7$%2A)F z8WG`Ae_oFIN)_%3ms!RW4}It(?}f`=S4TXt{~)>fup|HIwm}kfJzH^Bmk*MX@3IxY zvUh}JZp+qjZ^uT+qi<#_pLJU!By?uB@|^fXganPvR{le-M##J&+3G75pBo`<2W6|T z6yxacWgp<@ay3B4t_GMFMMWLclgindVnttuM_yy@cMy| z4X-Qs+wgjW?+vd*_~G#SM4Z-xu)Y_Xzy?{ldKXy@THc z?KKwC=1K$kd!%u_b!e@hg;J-nh@Z}(X_;qkzh;zQkrw+iOKES7L7?*m24|N7l z>JR>`i*vo4y;ht*LkIdrKp*-@KsWkJKu`KkKxg_UK)vW|fjZLf0&)6a zAfNsiz@cvj@ad<4ap|)GKJ?!JPx^9zKm9r|FZy^u2gd*HzANzmdF7`OGV@@j1z(`_ z3&vY=f2IY$pkJuUn9;7 zan2X{)B!lu2l&(t<5ExXq0Zn*{lTAgajq9W)04{i^8hd(NG{wMoWmCT(WhexEV zzfvZ*x+TC)ZRCz32eWjk6 zHc@Vur>Wo6tz#4AgY#+XLzVo7`^n)*}q88t~fmN??y9GWE4A|3hLYD|{%9nutM z?m*Mu)gVpri$9z!WA3EtxLJvlWnD(9@>x)QiX{G+syqj_nj+`FPF4Qh1E)pJ!cg|7X4MncjWQpYgn)UmTtz^pV5!h5mAQ?$CD*&m;QL;WAQpXc8-v>o{;~PK}j1MM;W3 z??9|n`Xx!nomLVnt_PBoPo3vxNX*70<(boYhD=_Wr2H>O%#e>3CaI6Q_sAI%{Cbl5 zs51`#N#?_sk~r|IBtCpBIWGJy$p^ldV|QtC-_ij z@TC6m$z)xe>*efm>iqeE->Ji|_@C@|3P0hoZDQs3hmzHg_Xm$y*;OrBeR_}fij~yA zlGMLq4{eGL6-oS3AHxNF+Yt46|z4#8In3DNqvKZ ztr^lGEJ^)@zpXb@X1O@x?Z?lQeKj5VjZDAcqj`ynQ&w%396Xt*_+x@*$@Z;@I&S!~ zS(3CoQThCKWR^TRBT;#tNuMQ;jY(Agapkil(D+VcUeDc`B^6L<)Ne0rG=|6bz2 z*O&P4`{lUs0VW^#1Cu9wgUKI$!kic4oGlEpU*YS zi_bgw95N37L*~O5kvRA}0`al`%yHqbNIvjgBv1G;l0SSJIWNRHU*uB<;7}jnQ#XuD zJ;8@MgD3R|f7ZphUieH;Z|Bd@fj-jEhyK#gjlR>+lYZ3DnLgFf|EXyY{PR&q`g@~} z^!G*`sSoN%-B3sBi8@ke)RFq5j;sszpZR+M`_KFx0iRg@zJPx$e|O;T2>d+)zghlH zfe$TzzrdfCziZ%I%ilZrI|6?PA1N zf8U{w^fO1CKIh1%|2c5ziw=DHrDI(BsDlsv)xnd#>)=m6cFc=D?a+a7=)-*IMjYr# zeCW(^p+EVcF64=Nk^leXIU_j7hx?g0$A|l72aYYW_tOFlXYR8lG+u1)zu}x6?#t~Q zx7gmV+yClfdmj(y^>BYLa?N6U-w$!_2O^*QguvncA@I4ch;g~!2tM401W)cyfvc2^{Wc z0-w5JT<&Lr4|N7l?q`BO>*8E5=QEg`KR-B+$+4gLPd<+czYD@f43@J^%-OQd%^81l z2TQ&B*?Nvx==s6Yt>l`XFBUdVc0e6$-3+0-M@y)!e6uWoU$is z43|uE*5`m5>!hyB2w8Y1Q_nSfV^X9zwg2;Pmm|qr|WrVjN=?J=Hq-Z;^5pd;^RCrj*D~3$Oq?_ktfbIBY&KC#_t{C zoG`P4f4Z*wnR7aZ$m|{0bw6|Xnh;4@cwP51FXe^E&i$$WR;V2OBu{y!eHkiWzLTf>nP*RhN`^T< z6!UU98!GQC%G3Q!#<5SxeC!_*2m6Y|$37Ux#XcnYV1JT4v2RKK*w5s=5a)c6PaS|m zeSlBhFfR23ALD!NUk?7|S-RSfG;CxTVIi#o;&r|rH zKHqa?RFITK7U+Ip+0-D}GOR%N39l^*l1u#ybpP=|aBlXU_Vgk9h3K*Zs_!eS&4$Qb#=U(_q;((vjcg zRw@PR>xIue``Gz2_A`0j?t^oX9p^7Y z|9{ds$T*L?(GP>9Fv*;QV9x1&vS5(3`Z3$W`Q4B7j*wv+vn`zKeg8&;Bn-^9aNhS5 z-whV))-?;~fFCkvxz?F)&Ve%LgU44LCKJlDESwvDa_DfW9Fb+=obf^CeVB#jeHffG zKC1Ib$*q;C@yW+WNslq+eG-#j>7_C9;Of)0O9u4ijYRymaNiXX6C9d)brv^z2f-2Gxd#QeNEltSa)+h#PNDC*GU|&6Em+k zUO(o#isN--xu)Y_Xzy? z{ldKXy))OL9XIzAJKubNZ5;Exw(-sV#2(k&Pi#Ks{$TSo_Y<4Hxu4kcLY(tOK6L;N z^#MM0!?@HFe5f;cQh)GgU7YKM&raVv`!jS{bbf%`GrzT=&ns>N#kGHy1>L4x94I>; z&a$BA!rfu=?ygK+pK(nOhfB6wrUm_56%7*q9T^tt;?iZXB-YNbP{&i|9PMy(jyCFe z?xkV!^|x0vp1ftaJl*h$=1+YzQZ~*?SDcvfBgN}Vn&R{N$G8o5IldR**-(*|GK@}%ixRU2B*D$gOlEJyk)t@oBH|6 zGYiTz|H#e`^6`~Y#fiJ`Cq7+D75|i1fUNntM8_T5NhCY4MET5Z)KSi67Awzb$2v;a z4~muln8txJYf7-ge3?PbQh#ftM%zPCJbr%3VL zp7E7&(~5N5i!D3I;ol0CPkv=T`DA^e@=W{GPa5OzUVK@AJ_OX z#-R`Mp&N0aC-I>($A$jngSwC>>PY^mqtm?NIA7#b2jEa2;8Qn@OFhAdI)f+mM;%$0 zO6K2*Mg1i9$?Mjw&Dp+9-|8nXK7QSLw{2vH`k$J!w`yLuQlH=2q2QF+1G$rD-9K`% z!-`+~$?BXu>q^O;4)feX<(nV#tV`W%`<1*LD*JckS$%>U`kneNR0b}~v&Qad;kgDP3v!ibbB}@Y*7RKE|5UGmay%;6dauh{P3QI-C{xF1{3zpQUdNbk z=5>rXW?sjLZ{~H3p16&eChxk>H~c0hH*vAJG9X9mSpROYtY`q77yMR)_LWl==J$xH z@4fAP<^I`h&CmY5uSD+5R-CW9hDepA*^1x#O>+iZRJM-$%;^wm)+bx}SignHxb|i* z-CS?)HtHvl&9k+Ri(Jh$);L@1nD5W@0IF8M1T3Md-aRX%yc+;jRr91t?KtMq@Z z(AreYta5u@UUubQ7zFt7t_HMGU;-)qH{dxhHfA1zazudH{ov0Vkt50`%cBdn5ebQYb z7T(nSEfwA6=rbB9Rqy(f|Jp-;`*U81bH2!@4#1&4z^85)mwJK^bp}uB5B{u+bG`66 zA~;ZHdOPOJ&!}VEz(8s4>CoqkNr4jH>W1p}#@m6?uh9+Fv+0RISyT0f>RkV?KskA% zK=of1*h#)RQ=oMjzN(Xi?<~+dcFOD|M-~-m9S?hSmWttyc`J;}U7vh{R@~H!Gs1NX|8^)!c z;6t6kllr5MtP5)Q^1%)=BDqxOn|i#1JbJlQbvSdeg9M%_Ree7GwS#mxR;s#nZ0;xX zww0=$?xX!=&x%s5*R~ygvT0JO)@$BvKMCwvs`VPt-CsU^p;YUYu)$xh+%3^~&r*MR zDy2m8+jI($*^dSy(BR=%xxX_t=pg(z{F657TabAdXzR0Hz zz@a|Cr*0URdV&vi22bjbda*9f^}^@ukJ^j-s$!ilKjVAXeQSHkT~Vz1cpq&q^%oSY zZndtqmpapnRnI-Oy(MHwvFiMBFK=1Uu~_wgY_+$N ztz+OqAKCYnBYr5!M+#RJY5s>TeI;mOk>W(p@|Du=MT&pzn6G5DDAI8+|K=-?)h<## zvs!eJ(BB>R`CdUCBq-l;|L-uWgUq{HsPo!9p@XzdE7UqN4t#^RSzo zd+D~;E3Ao|+hn@pH~FLPZPo3knQr3y=PlJUZl9Y>%DkmIyZq)RL%+GD`d91X zF84Ow(t6!k=Pr?RZfU)S-*A@=103;70Unar){%dBwTF1sbl|MK;vuQmD-{3!^PY0% zhYB6He7L9lwWmV)y!*DN_`hGFJfjYHO8aHzw~XN*@uR1Vd$mIAb^N@iG?-hV^N#5rH&QwQKsAK+6rj7vSihdP5N^+&x}7w3B6 z^OT!yq%6B!=gZH~;X-*E*_v6d`g~iXtz1ehSKZdPZYyWMFIPR=4{Iy6_m!*8FMZHf zWPQ2T@uRD4#pUI4tz%59c9JllTrtljYI(#}id@RHj*LSe=0i8)Ku_XBXO0W~$p>{IPt=S2QAf@Tan2X{)B!lu2l&(t z<5ExXq0Zn*{ZU8O#ndj|>3J8=`>I)I#`At_)|v6V51VynJnzqDof*&jwpnM!^L}pD znen{On{{S9@Be0<8PDee;(T5ppU)BC@c9CKK6fxKpGV-s=M;GI`DL!Rcs|!KFQ@07 z9XC4I`9>cb$LMC`8$IoDjm~l8WAu+BPg9pT@;CL0M;PY97arq1aA3mGFlg}*Fj?Xg8%jp?s$Ds-Hp%rnUA@QLt$A#wPgIbU$ zYDE619p{BO=Zk#m037NAeCmdAsVDeQXYi!{s2%I#TrYffdfvtJz6wovzlB!34?{!V zpP?=9+t8f%bJT+OdDMvaf7Fi81;qKhKt7)%z~S=+_0EhYjpSodO>Ipv789b>! zYR9@b*9)JWo^kQKmqHWXW1$uAz0i>NWN6EKH8kfv9JS!R9W~-TAGPDN0C7Gekk4la zaQI9CKA$xhm(L*Z;j;-m`OHG?_$H~c0hH*8E5e0JJPiRW*2Xu{v}(2BqDp&@_!LtE|%Ky&UDpcdRiK#jP!fZB1-0dej{AfI~_ zz~SBn@VTdfak^L-GKC~hZG$cN><+#wCd{7JWM2*NF zwd1@H=X{Y*9e_i9fKS~pF7*T->I|OLAGKp$oa<$L7cHK1VSE>@hr9QZ83S%u#&^;B zYiKXo+Utg8d>5??ulJHozBer6yJ$_{*Gn>9xM3OJMQcn^FR4@WhGl#gtwgupQt4)a zWqcQ{&tK~;TYo69jK89_`a*B1y0ySEzKd4XW94~zJ+$&_!(NvH$I0pjyYGtBEC6q!s58*{3eTh%sDa^d7AUME%G<#bldYnobyFK zbpQ_a0X}uZxYQGTs55v{fAD8roa=?pJeLG>cRGv2;#nBbif3e?c04-+wd0u@sGZYU zB$m@zB$m@zBv#BLJ>+qZ>sr(6BYQ}2?dw|WGY5Lemj!uRyHD=-kkHe4TDyAPdP;TkVaWGGk?)UQ65e_mqP#=V|TcCiavsqw=(NlM8!F#;`oC-T8{1^3LEqtsUdg zg!#~lIM9&z(3ayubMiqg$P+apf7FiiLY(tOK6L;N^#MM0!?@HFe5f;cQh(Hrb#bm2 zK0BR%XFZ$aC8hVuRg=1RyyUrG%T=q~#_gqHUb$+xIJmtGIbW{Y&R)@8-a1&Wn%_Lv zUgn$M=J?)y^R%}-H=|r@v~{Z4D>HwS#rKYXU&i-w)ssH*+kYJSF%x_wJflo;dK~hR zKaZCw{;@yJUYYrAj@t2jI$TS^<9%h=lrrV{{9C>fKCDb@_xPv2vb2Ah*6!txyfT+m+IV|&b+hcXSvC(-KAQ)epTJ2ctfdbSnlaA?Ut0Pwz<>IewW#Q z#`iA#u)FjND%IMxsp28GT9#_<9u4!5fmKVjcKn+%YWL?|4>@DrXF#npLOi9_x)Q}X zxY1M2#gr(1^K8f2bEsXzXT7A%yF~dM>+2=1P0jx`_x87Ay`*)$66OE;axWS3P>I$q zXSJ6+QmsU5$2c@$KC~hZG$cN><+#wCd{7JWM2*NFwd1@H=X{Y*9e_i9fKS~pF7*T- z>I|OLAGKp$oa=?pJWmbx%ysKJircPY)nv);jxy@wV%2KMxsEb)b+Oj&&wCwZMVXyMT+mbr?a%}QKaMYd^&vZzH87$Ha}_puc_Vp{$1pQ>P1?+ z<^8+JkAD|x?TQ9>k-2vYwRVg{6XruJ;y^>v&vhv(_WwIY@8I@U<5&x^QaJJwDvl{!l7S;v~H>Wdv^O56>t-LJmp zx;k(}Yd5%4N9nuwhSrX8Xu^DGMI2~Id}zyYp*i`W7UYQw=NWWNR!M8%bXu=oqWktLQhp#&wM)B@{0D9&f6=jS}~KYT5+CoePM<5 z(SXTTX>Bj*KBB_f-)pipcC?qg;p2#>9`=&BdXD_~huX_CCFP2_Ph}1e34Hb zfJ1$NPu(ys^#mX444%{<{8<<0dg1eoF)otwLz&K(pP@t2Bo}$pyz7NJ{;k%PO-w2uCXE^>Qand&Q6tVLo&t4)i2Gbmq9w zpL|dk@?-Nuluo=L_Skty|R5vd|siKRQb!SGbe3{|0$roj7ciDz6;+HFYmUO&E{`Lh<|mx zy`;WbuKDl#c#Ch8`J0i!nYzSVu68L`{LC}na_+@)9rsdoAGvS-W&}PnynQ6_cA4_* zG1NyoiJQ7N^F8veSBzd1%bDDa!Z{{xED@(PGpU-iZ*eFN5$vJoVBG8dvrHO~s zZtTEGo#G+;@02Khp93DUC9Op3*s;WM{y6HG`K+hZ-(8}0JlNS&>TD>{I&P2flz?|i zw2lvr^pvudC0a+up%3$+8*!i~@u4%vh5qD&x{xR8MgFKG=Y=@ui+t(;9O?sn>V|Qt zC-_ij@TC5zBkN+$O|y9ZojGUC;yG*P{56Z`ubFe%ES}3|&TF%HUYj{z%;Gt2=6o@W z=ig1W8e2U7u99D4i|5~+sMFYfE+9TFy}jhDF1L_hrI(M4D=M>qQ{xj~xo3W(0l#ii z2N`7Ur5JbbH9y(euhasc)5pxZ$eb4mo=464=i!|t7WjV|7a)G~QLh%(=T`${-qaGy zoCjye&AEPdzB$*=#xdvm+4$yMKYLtruAj}voa<-vH0S!+{LQ(3_Ph}1e34HbfJ1$N zPu(ys^#mX444%{<{8<<0df~Iv`FHkb=)iL)p%2fUgl;@{5_)5=ruVf4_(mFo9%~$HW7ik@z`rcPUUMSK!G7f#158a3ZJ&6yUIWF`kAJm0B zQ7`gG9XT(=IbY;c2jEa2;8Qn@OFhAdI)f+mM;%$0Mc;fWZ{L|9cd92_`22jmsnRSo z)%Yi@m558RvhCwb`nl-l%W~ny<^LrI`32rDNyM(-HSUZv@VREvCh}LrE$7e9`A%_X z9Lp)kI&n8dBKu$e-*DRG1&PN)xz@$-&*GgwJLfYF4vY^kx)SGhah%MXo?_wi_ctcW zj$>*6M;!E_H27??RNP9nRy6n`ZtIH4vZqp-)$W)0xC@?><)h|lmTT%SaXoiUlFH-K z{ufN=v4FE=)p$9*%lL&FoVqdNWx?TO#R+IUUZSrgE6$;Jq9n0V3i@CCnUBxp;EaRM zjGM9iITypnpL`5YfATcr`jh|v57QnCIMfF?x$U15H{_0afAy0~*5<3@Vx0fi+HvgoUGI&Sdn-V!tFobq|;ks!%<_MGxeHv9Y+ zi+@r6RpNu>hx5PSdWhSS5G1?5|HV3x_gNg{11Ic{V}4%O<8j2<+wN2x@rP&q9LI5= zdiGKr`Sd%I6i1$2m#4;&f310G_Ph}1e34HbfJ1$NPu(ys^#mX444%{<{8^W*p%dd? z%k3gn`(L#1x$5&hrP9>%I$yujon%SZOV-=b-`P3%?3~l1V{dtV?m5lhozYF^H%n68 zdj8r?BA-rDJ!krKmw|T^Rp+Lkb(bDz6IK6v9eT*26^UAxg%v$yt9PQ-tI-c;FFob5 z*0JA#UJ@C7S?gQri{8@ZeuCEh&Amag?X3ij*FVrlsy0Z_{8M{^rC^8S`uX$yzH&qy z*VVgILS$R!MIHCa7yHS(t1c>^im&@grJ#$-^ONSGa;xD*<$rc!sNDGLg3fEwf>8On z{DRh=u8~wPkhvcVgF2EY>P!BpJLiQs=Zk#m037NAeCmdA|3CKLJFKdt z*%wyKI%Cc{iaB7`8Q8Tk=d3f1aU8RlvyK@PCPYz0R1i^uibzISwF?0yCjkKiW-+0d z0Kt5#d)D&obH4lC=RWt$ckeyV_x|xd{-*5JRb9XCTC4ll+gHn{h)2t_h*QhI;9cWI z%;&Nz2lqO&EKBk}_~6i9tu|*$u8na@%E(^Lk7dX_RDU_Tmz&q$^TgQxul1gK>A%W) zH?GeD|7*>rOYZ)wtXYjOQLD8z_#f-GwoV1V#`XEXXBYKc>&LjZ|Bvj(^+9`gi1zi6Q!ni#zsA1p< z*k<7fbw9nJy}yM*|3y3DnafMz3pHQHF&O*O+6ceq{=Qf;&sO^F`qmb=uRSUK(x(Y{ zGcQ2;J#X3sm%3h-etYdqP!c*`lYT#z8l+VE_`ujNs^k40gRw7xL)*5Hz67qB<*5^6 z6u4EbnigV=0v`>YtB5fQ{8Lu3BE~4NT_bZe8Y3Fz(Ae+4!=jCv2iczUtZ<%D%`9#+a-LDmGjg6$%`V3c#va&A1A zwEq8N490ojHewEFu?Z|=HlBz7;G7p@m*XAU^MJ0qW4^>;?mxl-r^gbfZ5{(9Yi~%L zGI1BI-VrNt_eJgyWa=+*6}~i1DUK4W@k{(qtr6p~voF+qaSW)%z_Fng8^?@V%sdv< z#=>J%v@sgTDX>GUgphsE&PM) zPR=XgOT;2#5?I72dm4Uflx=(pD(V-taFw{nkaw_gM3Th(C-8r( z{kQ_RGl+ipIpF6d=Kgftuf!r2_NUnu%`W_C?S&t$AK^#qU;L^06@RbABc9XZ6#Z%O z3qMBV5_XvrwLOS9)qW&a`{9;XLb@HF8KO%nZ8|ELZz2EEke`bCf&+~t3JsPj^ z|7897UdKe;`d_WFee_4<8k}aALnZGV^c91~puqRd?DSK1rAX}GaGSo5zOF&ozqX&N z@87(y#Qdk8|65}Idp)<4n4bfFUSjSKxL=6{*X&QTqh=R=wD!V}){pR`^)LR^{EENV z;t|hjaf<%5_=O*_2Gwy1JE-Fl?Il+G(W~PU{Y$L+l~|2OVl_^Qg&&bG@vJ&7%`V2P zwHJAiSj~^b!jH(K>R04bVva}TSz_^=7N_V>i{F^9x0`qAh41#WAJDYl7Dyfo?4Ho? zEeA=v$=EzHuCc~gUDyArw}01pS?m69tGE9%{QhXWP5;8>i_-M`L%R5UwSLx4M1g0X zAES@QkvJsy8TqZ4sJFDLV-WTxBYNp)M#f3|EUQlXjkgC#yVo64ebn}<2GKrnMIqd~ zKTq0&%nG6Gy)M$e_sRya{li+?XD&PnneT>3yO@JpwrrR7<2|qHiYNZAwMVTz+ZD~u z{iD`D_k&tL9FIYZhy9}Fm*Y2R@pGI8ElwV-k%z{4 z;|(HiFO6M2w!b-dCp-UXaD zX;<^3wHJBT>>{69|AH5-ACZ4)S9z3nl`m;md6#yTUujq8i5#ywALO{yxg_(W&L3&l zYL2_}4ecEP0&6u&V6AouENYvmX##7tPGGGD3M^`ycwS&p+eD2MSa2fzsdiao)%M~Y zA?;dC7IyAmyd$JteMd;F)ppT_pOZCTVD=;51p+UF~0D)vv^A zJQAz#2#M8qgv9E&G`kqD)?Va6Vl_V!t9g@H&8Ng_o+TFf5dPHo#XCY`W4<&j-ZjQp zeW(2EU9Zlczw;x%J>>gWe)n@Y`r)kp9}sjUe!EbfNg?kXZaF|C{aN??pS&Mm#5;7g+Qs`W2XKQA^=ZwWDU| z_NcYzehgYa+`mEVpZ_#ye);bWT0H!mL5q|7GidRPe{W5En+ad4UCvvzy~Jui2GK_C zUt-m-#A-Yet8q%qenk8d3%-OubzEY+T6>WPiPii_tmaK(IX)hzcvg&C_!C&y607T1FYM~NmRMcy603DUVo|rm^P;_0Ck58(q-vLSQed_IX#L1KDeP*!l6E!E z5^Hr*v=Mbk_!C&vC*eMs_r6FR@l9gqCY(*E#V1O0+=juN}3{j4w3!%kvugIXKz$DsAYZ46o)e%7Ep%l#X) z{#7j3LZ9$6h7IMn>BRg|u_CbAr(R&ym&9tH605$nHX>$;)p2QUM9dPaW06=LuNH%z zV~~D127zTfq9zDEgY_&+?aa^^^Es-eSYM)zz^ZN~v^+~ys})+FrK;5mEzeTbYK4|( zscN-C%d=FqTA}3$U-Ar4_%e>c*q7Eu_*Hc%=~vZirC(L6m3~#NR{B-7TIpBSYK{F0 zJ?`JdVC+j^)*7TQfmt_H#25u;-7rjyQDD{$bz+PHvu>ypV-%QmLogbnIG@qRXzcgj zVWT|D_NrzCYMzBw3u>N)RtsvLg;on{o`qHmYMzBwtHmJCla2B${i=DEzBp#>%vt1F z=t0u2s?|!rs#Yugs#>k|t7^5cBxFV(M{R{|U5TgB zTF!-5tL0p1wbHNgT+;ggk1?oiw0OikG{!P!<9YZG&UrC*IbNYPsrsFz(4fRQxR?VX z7LHqD*6Tpk?=1OGQ1v@G$FzR_sdZsIUR58FF{t{i#Hv0kv8vBXtm?B8tNN_OVjNnW z0vqxBkE|(GI{=Y4Ri71F73c7~KC9WqS+S*&)}Yli`RqTq*5q6gzKnEgOC$Z-(n!~~ zG}5~*jdXBJBYjG6E#{1j^PgIq#%o`lSF(R~zDcakLy6V-DX}_lC01iYF0l^4k=&w=lC(BR^_MfS@;(STO$7hw6+WC^e+WC^e+WC^e>bbEv ztF+Y4;RV*t;RWV%7)_(J)Xw3BUHB3H1U5SV6z%0XyxNb@YPJ65IlQoI=kNma-wUl) zwh`yt!k@5<^Kaqr?|%M1hc~i|b7?Uy(OzP;AA_)K=kNk+=kNk+=kNlnamw~;{1U6< z((LjaUTrVW;njXLEnCZ*=2z$%603QZSk1qT)975CFE9nw_PQHfL$1 z@mU&ad6ueHD>Ob!Bkj*p)oP_()oO+IC)c&AIa;b(t+X3yl)^5wT4`6cTCE?U)k?dO z1}gjttybDqtyZ=-(niI2g;pyxM=>rrDe4MKZI2yH@pM@X#IE@3y)7Qfdz zVK>quwReO#x7Xeg5^J?owF|9Q+O^uN_9O4}2&~m=fwdYguvXgz)@r`M>N`Tl%;S>Z zX~J$?SBBH&uZT=0;}WF+RJYqVOQt5v}^N0^{d@s z`2I~L?Ap8%SetJG3t!?~TVPEu5LnX@1lIHgfi>MhVD+HGM(tU+BWp zuAOfSyQWhJES?k33#{rL5(~YlvoSk*fuR^yRajZ2v>RzdA|9bPNxP9Y zB;pbJl(ZXZPa+0Qd(yCsO>HCRgZivN#A&2$X}+Z0NDKSd`-11QsNw3ol31J1!miC{ zfwlQ8ur{9s{@?k&P~U^{-JxN@wJ}!LwVXfddYAZLbxG>o-+2^y(|8nEVw#*Nmy(55x5+_)c2zZTDm82-DO_RmYyHS) zjrtLJ6XVqjUq*FX%aybn_hW=bp0#JSoQU>9yDz1SMc>c2DQE9!sxvz`1*c7!KhD>XRS}o zmv~liq}^@MuzcsLz6_#`5!U*V&l<Oe7)|6 z$Wr=|0k*VmQF)m9?Hi<)+ef*Fyp)0dCVGKS>e_^z8eLZ6?!T|sotjrh;xzX=(8Jpv zMVnJAqhRRiV2Nv6pM(taYZ5yhS`JoQUr4;LpfOyC;r|b2ZvSw^F5S{TWefrz7#|)s zrAJwbU+&LU#+jFvxM;&r92Z$A+s~e0hs|Q|N!$zru#IW7#M{!+aNeoY5)ZoY9LqYa zmDvB#C+xVsrNnhVn;5zl9#Mp^E`!S&YE9p0A#j3QX~U{USvrBc!+Y%CwjT%_kn;d{ ze%>STmZ(^~5$7xM8uY|rQ&S}#Xk(2TNlzs{P;7=%#(tF8IB(OozX8v#<8Vx#E%~N@ z2D8B?_&C*;dUq|YpI6>oSrcSS@jFWCm4wE+7f!ZR_e2T&l3u7Y+h|K020RC+OGBaU zbXyv^=NeQ$um|q-x22Mgp^$Ci4P)BaQh2f_n1vu@)wLzVw}Y^De1hcHm}}4O&qLgU zN~HZ|*m2!cpTFn8y@3s2@3EKC{?q&!5E*z!;!$rMmDIs6;M<>jNxVbX^?ro{*FW!} ztLdF5ak;L|VNJRF5-&7c3@6-EB|f|LD9o-LDshwRA+YoHF^M||r@-%Xmq}b}#y#j2 z*h*rb-}9h-Ssz98f4t`_*!O5jsKD_b^I+-d6FPx^_qq>#E;IpwlMh^l*q8GqPJl3& zQ^QH(kCUC@i(9b7>rSi$o2X=oZ+B@2os_#0@0lE=bNcdJVxI@E%s-pIlGu2>36Ayf z$=wIi-l58LEEtd>v00~sxcn(eTsXxSNBwbH;*OVNF?H&8iCsf(;^V!2B_0~^1i#gL zCF8F>IUi$Nx01Nu)_j~jzpfl_RI8_0KL3ftomSn#g>8GG7^6!}92TT+mALf@KfF-t zl*GS!972Z}gT!}7%)-Rk=@M6{+X$ToJ&-t}=Lu!!r@uKeo&(0~^#9bH419hW=2Q*B zf-d`L&M+>m_gB)kGLavAKBga(QP|mVwm(`A8igY z{aHW0tii8}9X;sjquf1YVler|jtafaaLb<`F?*&RncmunX*-|cGqYx1H@}SG z`H!uY$4>ic6QuT^Y>F?!CS<`K@WTI?jGP z>RmIh^ZX!92r<#ma`05*YagO&b3Vek9cF0J{}8Q-e+qvcw8jN14pD{Gsqo0f69>8- zqQoFSsQfkt=OrDYz`3??`}2L=SaOKA-W~v_{flsG8wbkhcuQB#y0l@&cn9iR;B3*i zcUeQ#?G9AS-d1twRK_sJ*MY9zYJ%I=eMZ~c4wQavC2oD0hgYf`rb8>;@VCtw_(pe_ z`Zz{mpUuHIV$Na8S$qe>KilJ*gNJEYvjT)JV=*Q2Fg=SYWpJugsARt8XX}4g>4^K_)x`PmrQ!5M6?IZ{R& z1s|J+!{Bd@G-&M+bP2x+%gv6^pEIW7<^^w{;p8J!Z&d?)Kk5ruSs(e%U6A_`QclL3 z=WtHFuO6YjjuE=2txfc|J{_TidKOTIx!cv=iM}1Qf$7${aCVXtg`f3?L8B6(^)4rh z>z)YBgFp=TUNDKPJ%`=E3ui zQcvd2^Qfm{<#?3bW`Bh4yUZ~A%27&>dkQHI)>x_FDE+c36`r2(#7Cyb=vts3JZA37 zk2pq-b8Nxx%YAIL?ikg$H2|6h6k*e|$LLbqTe>#PU8(EGsNOwii^0sDPnqLn>S(KM zX70*#K2F2$G(l75uKm>GR4;oa=Dog$lN{eI2IT6b*3Lml#}Hu|MHVk<8uB=CgGE@y^tQ zxzqnt6L!3JrYm{*cp%>jLRz^{b>_~eqcgM{=R%)aD;U}=93ES{(9pk*;P6W~p_-2i zb(}U8zcF{pEf-2!-T+6B{sQGno%qh(sFo+F+w*wyo1D`jV@^=3;}N=K=5FoA6ZEx# z1vs}ZfmY{FP-zDnNZgzYgKwQ6mvi1=J2DYsD!9_t9*Hn8&KokjxzbhUu5E}7jG69A zvCQ4p*%q+;fGb%tcPTw0bxkk1k}LbM*qmYhYo05$X6`DS@KnmxJxTqUyD@vraP@$b zG=#akqr&SeaS3x* z>c>+wYqcA`-I#$L^`|I~xjV5j828LQMGcqU!K{z=*wNt>b!}dN6+4W@%9l@(8FQCf zs!*x%_7r(Acdva)E1jC0raCMAodntFaUULMmGj|s{xYMGkQ_*VS8<;S~o!&2PfJc}+k1g)s zxqI&6PHrs{%x`c`pQO1{%83ZwMdq&F7k9eU$O48icUR0jD22KEjk$X~*@K3AdqeSv zM3}YPgKGbr2u`uyup-EV`Y+6dnZY*j>b?inX;1>!W?DeC>Yg-)xtrKEQWxIKlTNaq z?7?yUYiLx0>{i8YuzSGzM*YKM+B`i& zJDIz#%w1Bgvt-TOxwRjQXZxL{zRcbIF9nL<^0Rb~xodo;w36(4md-MFExXLpy-YYu z9?YGcX-$YMK1(Ldo#z`Xc-#6M)n@K0b#{iizn`P@Rtn}Ycg?n*qnE3Xpk>5O7=Ga# zwfSQz1~PX=Ip@e@Ndrt|?)sJX{?46ED{q=JGQs>h=XA$d#%>Y1Gt6DcCU5%C*aCiJ z?q>LS)0D$DP>Q+Rp5sl?%$+@RSGv-9TF2a(GI!N`oTo#~T~3egQW$tcG zyg^hT@~ssdIO9k6t+H_}b5|zYj}9|;bz6i(L}`EW zV(u0(ch5We)1fI-F_XD-_`{znGj|V|yL(&xzjN2z%b&(f`Tewa$ey{ozbO|?{|KNr%-tg9&UH@!IWu>~G2Y-C96&zIogZ`8?qLA^ z!Q4$|?uOL}q?yd!%ubQIlHP%myUh(V%*_@BQU&I&tGlOi&nb|uFn2wfyHT-$WXIgi zX708YaeLMZf?EiAGIv$F&C<0=3L!`4 zu7ua!r;-rLXYRi8y6e#PB7I`+%$Pg3@fRtKxhvpx_s6!2l*!zUWbStQUZk(goq@UQ za_1s#WA3gpcNRWD~Hi+=FWoG-SD5oXft#7g}IBJ8Af{Mt_s)8rw7Am5_5Nt*PUZznB?wb zw+!?6mtjR1JT~Fq& z;Z=q1GIuAKyUw2#vf`SV!!@&q8S;1F-!-%LWTXz4|E`&lJCV9^&798bu3jLLC)dnl z%w4bhNI!ASY{oTnO*I4E;rHEP=I(S)1GQrA%(-TMn`fYz%-uY$neL7Tn!((4FdK_o zq77uu+;#d^pzJCzke66@-lY|HQzBpH?s11%x+}wpqM5r3{JwKqM+96mqxgNtrIcoI z&2;AXUC--8zwrBREpzw5B%BuU`!1K?cg;J8(?ovXEoAPJr-oAjzwexwy9V3CzjHV3 zOgQas^7s30%C&GB%W z-QjPQ8_eC)kV{m9xeMd>-K^b$27jv@ZW&3X_*>-^f2)L! zjwE0HR%y)KC2x$R9{jCh&D^D(kEF(}Zt42)y7RvkNypRw{#KbN2@9cW!~Dl|H8~Q#fI!I z4%t9W-Xpxf6HP7nJM%4bx2j4ERcG#!_&am^FEO-;zcVvJY~b6h7}~(x)#g2dsY494 zVeTeaMCwwbV&onn05i->zltF}bN7b#2*C|vf1`EnOq#Zp4&0`s1my z#Q=Waeb^O85r=G*-OSyXpg8)H(*(z@`;2QI#8G(WO6<@3JKyT@l*jwK>b$?p=@m~K zd4Knf_Xy?-;;A%qw~hCAIY;98Tc`l>!4AZzB%nfG^B*C)^%-rp7FSwU&<1bWBZt>*pR>Kh4Er>%nSyua&OHj%t| ze>a);cays$(v+D~aR75yc3L9!UEKf^cz-u$N8)$xPM%Gqyk+s`x0ySK%tY#UC_?v< zxw}#-iGHYS0podpx2$s#HRJu=L+0+#pGowR_vXdCzpK74i7N8`t}O4(n}#OQQQn(d z^4|P-ZW2A^y?H0zn;U8+Qz_=|D(}tb_e++0^Y~`h%ug&yrazdwIfp!zF~^gs1MkgE zcyAsNpG-cyHxIVA#<#`EG@1A28+mV@+$x272K#}>n;3jOCWVGu*}^8?o0r*~LZ9yp zfbq;-#S1AkpzAH&tIeei&vH^|fr*QSC3APUVk$kewN*TsyBFP4>C}xTn8V!FoS90; z(pO^b{5%|bFqL+$a6?n;3|teDN}~=(VSnpjyq1?r6?t!7>Z?7jsdtsmm=<7{?ql({ zL09P_bJwwYp)z^(RkC637ABWg{yKe?@|e5!m1pUkQm#^|IbX4My_&G_(^cy6G9TTa zT7gUZG%B|+8$YynhU$~j=+AZv&S)AA$ve`h!}=pQf=^@K`=?RtoT<2B{u?-XFO6=m zZGb(QyO(9tzjN28T{@ZUswvKn^n-s*r-EBvx-4H4eS;0@RIx>C$QkhoMtG&u(Qm6@ zgKHiP%1EaM8(g8?r)%)*mvkDO91f;y!{C0a3<}wH11eY^WnMGrPP12#U)c&qto0^>9WF~e&a9H5?93C`Bk39q&8%ez^O}y|imp+@;D(0N zcPrzl#+l@E;wM9kts|A5eKV=+qn`|8)>YLFpPfms8aFaj9Qk(MMcq2bp!bksxY;j@5|6v# zHho2Xr+HZv@?;r$Sk%;e?9Zay%Z>2ffCl=yA>1Z@x6P;RsFyv+0^TfKRjwsMnCg#HVt*Y z22Rypz>~0Sx_bL9bWcu#;+$-{^r4*oYx%QKRO&h{*iv18cf%GK+U7dNw5YE?bg%-1OEhTzQ@P^1bm|y5|?mI$bC41C8~UAW#X#>(u^1J^k)(U2xj{>ooeO z>iX8dY{UHWH)!O#a{7W3=g^|#4chAb9*$Os#dX8@-wE-!2mC+$bM6f?F{{wVo6qwF z_8jQ0%e(VI;>7OF;n~STiK`VYg{30*}hvkl0Y;5Jt zMG*GDM&jMi%j*4H2TD9)>ks<%L4`WutKqmB`he!0Bo3QhOaJP1ZAI97U#zL05c*Q$ zS|h9J_x2lv!XDhSlKx}j9*Jk1DWwmy_m%i`$XjrI7$@-tA75x+DF9}6w57A79%CgTFC_8u@=@Pwp0-R z9)8}pMyb_wABDAl4cq5c#BxLSQQf!)Q1-|etg&JrMOL{Ax8nC8I`5;T=uoh7ID>Xq z_EE`E7qI`C&uyRYqjh`M!_J%8c&ery9qa!y>^k-oT`lb>clUMOjHGusf36)V4@`8I z+m+z{{dROIu#M6vy%=u<+mYw3=gLmQTkL&^uD@*W7i$IIiVFyV6xBzobUDi4Cne(Tu&v8swGw8=>&U?4q z#I-*!htaWo{=6v~hpj#e179DYv$M}*@Grq|r;a^2b=i->Rgz&`PkWj$dNPLobq~_! z+Ec@jn)thWK0L9vr=bJw6~~(Ip$^)U>)wv$VSy#^>ApP`_IB1CK2rpBDjuYXHS0sO zq?a(0&!6W^o(6Z#@4~t%2kGh>duX~m5pM4|NarVCfKuZE!PMs98oUVJe>zA#*W|&=+*VMj^&$GQs1REFhU$)uK19O~lt7D3J1xxrIz(4ZilLs1 zl@fB|5Ec8rhRKGqcp&x=m2r3obsLUEr#E~ST`vvVbl;658#>U8vI-3E=7oLwIZ)OQ zu8>tO5|7MtpbFPELHUPS*y*4H#ay$1a*v;23xfl_D7>rtaXM=Qxela{tD)Odu>>uD zJWOX3>MQ4pi*bAR!<4f8p)$O~JIt7Jm@=#ZpY4BwzBY$x(o}1-Ta<-veupU$U9tI^ z2sFEKn4TX~u&1pjZv1+f79UQ-y(@R&rq+%W{`MhmSUntJj3ec~c#USI%3$yHjuhFr z7^57gD^=YcY0|C|3|oHKVtaxkE$vr`!#W#uUEVrULEAi>;?xG>8y=x*i*BLi?Zt3& zz!9q85rZR&kHF)_M<@<`F!xm;96fx5+Jqm##zl$n(r|oX8~HNx6_%1c4S#^zh5Ni?&>64AY!wdAx&8_qGTEb~;hUqS{b#T0Z3YIZ>PZ zDbS_nJt%d{iL74ihw^)pV0D?J^s<}}B)SAaPWz+eSTP2QqMTsM*rOEu`X(fwUJ6^* zAEm;y=TLe}J2>ERly=o9gh|aJbe&R<(&|kmu*S^8BERS;eX}TrqdpUrNsW)u?#^%E z)DNYx(ZFN0W6C3Vb$lo`UV4lsnx=!P^G>{f^caQpMVOfCfo~&^(dSJk;moy5*!$@* zYO`+(EPI-XhHA&D!wgIK+TjVF)g7mdKcDEzy?u*&XC0^Bex|yBN5%Ne_Bg$ISV=k3 zumrmV9;e9iIm#c$-r>w!$LZ~xU$ExDr`V&cGbPvAh+F4mW5-U;)P2YaEO#anGsZj9 z^eJKJpYMg8HaSz}y;pI3ElK?hwf{wPEfe$a=fxEL#kV&bAIA+63cyD)t zdiFS})Uqyuk)bEZd7@+J9sd$ofA<9K8naK=!TddpD(6bmVyeTi*ZHublPgWxI1xHM zzX!V}x{~cwJ80pW3_omhrGCENu<21SIG%H*<`1sG!CuFpS(+$y?fMgttSa!0q`ZZ!9$8&o|Rj?d?~(a8?m zAock*9Jb$$@I`O{SAzGt zoFeaI*Az4H7b;@;Ad`{8R3};-P6@_cFPLXTFP#ik) zEI#~niXu0rVv_4#^k~6n;FBJp>Ed5;(8$x&>Cr2kKDjcE<1_HIv+wcE>dnfpZl}r5 zy#!y3=w?wEdzzHD%=I82-Jh>cQ`1E+aQ+{rkX6r}R_Sh|NfRr0(bt_uKa0bC1rE?` zp*!jR^uvae{Grw%ce;^!2t6a>!BlalJ_l#xjz_m)?n8H4eEKKMdGG=@{op~V-d;*f z=OTFevj?qDDHrDLT>|D)J!txk9l9m!-b4O&531YvM|iT~6@2pHv+;_*Lk8W4AFuP- zc#177^-lr!Ql1p}+c~J#_9BdE>q$*RFTVZ<76{L7QhZFmMZeY?Q% zQ=YVGbOFpRld2n^ zxbylMYLL_!uX;VhUZu}c#r3PP;iwxp(CjR|ntU9ml)i$E$DO6~*F&(Z_c=Ve{wz5y zO2G$R_92`;OOCtmW67i6F*)fh{Wj?pelA-T?-nth{~o&p?Nr`1IY+yFO7N-fmAT)* zb9A+T5w1=1&=oH_MuzFi2`!QRx- zq;J?8w-R{A=jUT0*Xv4$y$3s!^Yp{=N^qm>Yp^jpPjl?YLVddj;PCr-Is$v)QA8?O zSf8if@6W*61)*Sa<~$wV8wEEyyTH7Z^W@y*I^;R8gJ$o~lONxIS<$Ztn40>~^Jnki z@$xL)v!On;x*LC+&HQ3fc7+cek12*ukIj_PM}5fD`7IQ^exY2B^r0zkkKu9U-grLG zhibITgat8M@nG!>^z21A_#AY@50)3`Wu!Y?>14ouvo6rnxi+xzaXK!ry+9?!gW%)q zM`#{$fhzC+tc$XHgWdUDz46MCy0O!W@nHpD>ahjGf)DdW{G(6u{}(j=TA+F1F#%kfI|oTX+^dp zPPLAODHr{z-|q|YbHg0?>z+SdzTXlXdgOs^r2rb}7@}0&SqOEz2T-S>8^gREO5ptD z0IHR?Q1|5Bd+5A1fW}9c1Jk{)p}Kbf&8jmBK1_ND^)my=)^j(kPQD7sU-*39(F=UN z`QPAZ6-fK0M8Z0c6HskLAbo6;4dH9YkfPJOMXrJ$9KNMDJQwh(w2~456X7@8X!a zKk#NepU*=+ri`nDuiu5xkb6aF>h7p?Yx4N|_bI6?gtOe|-W%$t}$}EPESkWH&=;+WkLt zP1_ek#Tl;LnX=l+eu+&OTGX$|H<^ zY##x$>Yjv)iDA^QQx-VX-2(c8FlsjA2^^fEhxR`y16d4S-`d%nc15B2e{ zopXDjTAe9VrFSx636uv_lD7x}*f^PP|0B-;UJzOf81Bn=g?~@@L(dJ#V1R znM)K>XE1Dh{s>y6U!u*cY~aT2ba?ae5~U@(!yhdTP_IP;-<#5mey%76u2r&>fA5ppw{PxIfoSSNT;0t?bI*xUd%)ao)tOh1gHo#ODssLK>| z(I20E^F^E0m+5x31bjaI5W2Xqz4;xS;xY@L##|<=A75g&OJn@@`ZBE^RK#bT9?Gl+ zSNQ)!kKY?(@s*e04T zy+~6078c0!|J2^s!&Z(jfrM<<4$Ab_9keTkCSRh-bU~3Wx6E4zZWTja4)%xIK75a8 zbPUX1ucrD_M=MR#PR!K~$xZLd`{_tlUeTuM!HA)JG z+Qd;z-Z+T9avw+f#ZlESKfuN>ur_ay5 zlsX-YaOIeIY9I9zhTVRFch<#IS>M@M^Y(2lbdRT~oI}{-Vm#_n;%WGNKdd*(pYL77 zQ`*}&40_^#7L5|#@40?YqL_MJbo|SHh})1vwadNIEnWW>`gtVLxk`PY$HK?ZF*S*%z&4or zfbRj9B+=RuH@JE@9G00TQ@dRT@Sfrh%AjPr*(n3M73_fLtR4K&CKv8}90jb(3Et(_kys4DVbH3$2ktZTt$LT}G_pq)VX{&7VVE^Nu)Z zRtg>acmqu9uEa5RDKz%_6=*#C7+PFRq3fr;q2H@ujJ};h6UW#=-!sWLvTQ1~pEeQn zZ|-4c$5fi@RUJwd=Hs&osWi04KHVbSd#tiGm4@^^7JAXY1n-_nrR6J6D%&;|;g45S zDZNQU9KPly&Mrx%4TEOjKEoZ{*!(K>9Cr|BXCz?e@T=6afiKoL9)M+6UZuL}vG{hr zBW4|A9pR50+%|IomR!C{7t-@^!R;3KL;h9DbS=b@8-o;wx@mNo_t(pgEevbYD~*C4 zzQ;yom+8*UPNT20Ut{-_@?dY5M(0f*;?nA);dp2ob=rCrqw4K}p%2n1WlR|U@xhDF zE7R$*{sdMJh=g68)2Z;o2J~N?4IL+@Q%uG$SZVlEXtOPyp2po$p1Hh(lJn`5GP{!E z+o%NEWv0`Xj?HxQ9~Q&%kLk4k#1q}n{I`(SJcD{zTf&XjPatqa1{ELM0uAnE!pSum z)Oznp*qCq$8lB9bjw29uUiN@_F&R{~T{<|~?S%FD8B}lPBN(`8DDc$dy-r6&4k^MDVUbPUcrbj4dVXQkOJqK&oc9`_w8a;b@ z6Iw+q#amS}>DJe1a7uN;TRk%A_{Z~b>P!%BnvzLF?(PT6LrM5}TPD>`n*x&?+{4K} zne=>QZMZ!vAD3rm(l2`)bVmz{@Z7gdD($lG;x_(HI?+0d^q-v+%lINZJ2HzFtgnl` ze#pm{YqDri4&PgFx{GB_Wf3GEz?&};aYs^=a@~e`P^*58V5eX&!)nL#b{A`hHk{8 zY&!k)HBM|=1{(cvof^J)h;gXu4PK5v_b6}Rq!JJYVy`~!Rp;N%IncU>n3Usvq6 zB?3D6UMH`<)|kC23o!dSh0g%|a`*}Ol)6FXyFXOkcYX)E+uxwy@6AxE*5^IX&>J-U zLMs?F{Syd{=3^T#UByb}^a2O&vRsuEjl z_{nf^-dyqfk?$JWKGSPtIW{X;Xk@<*y+&o4d+D|Zn&@k-__sEBCzEO9PtoS@Sp)S+ zN~RejB6N;zP4qdeKTat$2ginn}^IvrO1nX zk81?qab^9n+`^A=YlazSvHmzM{V6nGZjBXRr_zcosc>dL-*Ihxm8_!tpfEQED-5|x zN7mRvnS%S+koCt?-v+?Zb4A$1<0_s0>z1z8rqYIQ8CPjpqZ1a-dzCd@_;!_=542S> zI+rn+n59wWi%oEZ^=E9$`s3_?mAJGh52x==qY<;+uy_yOalM#ELw84E>wSF3mFq*x zS$D9(j|b7NYC5fIP=II0jm7yr)5+~hDZ_>Fh05|p>GYvaSwo}ACdz?h>2%MbjN#RW znL6L-bSl5#E7mQn0bAdtQ+KYH>9JN2*ervbR%hcMjh&&*7_JFFD_Er#-*MfLLDlvg z!P0>@;m5PAIqsT@88hC%#q12a>D&O{4EX{kpEJJmJG5ym_4kZ6FW{Wk7#>US$3^I7 zF?W4f_qQ%FhqMkQ@RD_ZhwV0yx+@oc%!;L!F5d8DVj}D_iK9C05+O0u8(ccZk=Kk| zNQt(Ax~%)p<$YhuP75&K8%K`J-MEdBy2oL0w3Yq9yKM7@kJ--Lg^u%7l3Dj3vEU6Di@eLE7tvg!zOrg^JlbU-G64t zN}OAmhcOirsrp-xMVn-Lv~4QJ&U^!n#wXK8rv`Xz zDBmsLko=vyGp-Rdq(_YT8_wyP#0V;$%4g)vohRS7$^2{%Wth9Mts?1wjSYD1%!L)> zBI))CZ&*1Y5#DZ%q}}Zkq1H8TD0Lx{QfKBu=4Bh$!1rys)hdB4+bqDPQWPaHcMDcV z>V{cFkq!GPH7DELdUh1eWA0q1dMaJ{zRiL8A7RD*|+*=1*lMPA$m8_Pef7x|JIa*_DA4 zLatCh+bDd$I~arSU*UV~cks_j2XVrW(WGxwfOAHS#qO5T)H1r1Vd%g@MZYkb8Z&nt z%}tbvN2BR9b64y-Q@8d?G$qXYib0=i!0@-xWce;1AEjEsM$;Jjx*{73n>xeWQ89F{ zn}Rj#hJ)|=7@B8u1a}ADgzH{0^kDN;44U-@wq(W7U0`B6WVDNW0n3#f&WTTs|t% zF?ToTdMZcwo?Fs9u9-{Buv{+#RZo2iEjL-C`CScf2T!c&Y@m7M2eY5Y;LouJ zN?c|O&hPKzP`>B(=-mKl?Nfv!n-iH#y`_s|?mCSn>Ji{#QIYSB7=({{TP(GZ_%y+|wHW^4g!s+V1C>+WA;Re&gDQE5-TwLKG z(!OwN+qeMh4;hQc4B<47x$9|JsJP{YQ%B~md@Bn{^_Pe5b^kKj)nGP6#B&Wf8ha=58t9FHJ6I0h8L7 zK%^YRtzR{<}PP?q^^#6FzsVMmwRQI51AFr?;R6;mt~&HC%#`=j=7t;(hL{y{nF>j zPvN(%*68vwn69i(g>Xkt{HtLId7~e^$&10`14Af!3I86a_&)mb{nF*H_>Sv^A`Cng zLZQFi(v{~sKMrXj^wT~Ui(1TGpD!WQZN9CdWA2Xd{Zg;ECb(fvGdzJ zEVQ{uI~Tg~|8HpqHVeK;v-U@!i%l?YzITz@&bx!l%N@jKKZH`lp9(Oj|5*GAq2$Zl zed$)Hlv@x=eVDuDHBFS}PN6i5xl6e+Q`hfuC~dO(ijn1NLY+6EWcDT>r(L&#!A-+x zz_M&qS~!DYB;OtFtYF^;;jngH7#-Sr1UrY`gj1ej^y?btZq6GRmKjEa_cp-e!@t0h z4`JWAyWH4^s^rI-Kjxfz4Dq3;brHI~%v~nm>$a$D0lV9A?Q{2`KwBHAzC9OCXZTQ8 zcV2hD@}2Th7pP+AM2JlB=Jk1j=FH87AhH2(zSr$nrvyw_TR_q-zVFT4otY4+TYvEa z*|Q%XpG@-$4=+#--`85O&QqDr_qzL7eS|xInc-DSUy9*#^1t}^qNNw{IrF+yuygXn z+sAzAO_(37eHnw_qJ8PgB3o$q;Xc;ld)*cC20%V@SHGDbZ5nndj{_8?oaOz zMB$6=!T9J;e_A#F4z4M45O>=8Q{w_!Nk zDG8vH)?72gZbErJTP|Kc6@BKu0l(h@DbS_?ju`O;KCcb@&Yh_X|DNKnIP-^`(@OE4 zv~yd8ZUS?s`T z!`@!B$0`>h(FUsV?|i z2k}K^Zz^W)s_4gJyw00+eAh10v{1P^&zoj5ck%h9m6wj*)PlJ?@oc8|ro>65hlfDPQ+k_(H{PtqzcZ|E^55%RvCq{Oa?urbjaKD2YAWAk$1b(jsT;@>g- z!uKQ}FR}o~oo;lExw9Pdsx{+GiJRgE*3Rjkw>TQ_W6DKOQsc@PYLE9Zd8T|MQ%o+?v_tNAEs#kn z9lWW;&Rrpu29XV46KF~tuI(N)BKkjH)0f}e6^~2i6YHRA`evYqVwCV)5V3Z#D?Jpy z2Rms@!P*%ZdMLhLHxiSub_o&>1${Dro<0AImg9X))fp#ftBNu@RMk`Q>8KmsbS0Or zp6scpw0unIl`#5ntEZy$@Jkx;+nlbx=c&jaSVdK4tfAv@-S!;TPU!VroLcIsIEA%y ze$h-^)5A;A3Ts#VW0!DjwwJ;RJ;^TJyO9O@UW!3qzR*{1_mk7kUJ9)v1$5~sM^cvN zrN|vE((3+^L{jUecyDM!`^le??4jNYw}V@$-GOi9+*)tN=L@~5+lmH~h-mzL9vWmTI<7&3?G>HSas7ghYxZh;#S3&?Rq_7Q zm6z-lKk@$4?&!E~^Rri&qT{*(9oJ_C_KMe7I~{af>svY~eq-(W&599xr#f)Q_4@F< z8AUrB6x*S1!MaR`1 z9oKR592J|;aXpES>s-8lu>Y(1WHmaj3tb%*x6yGe$Jz}?*Wy@9ajm~ zZuD>`#Wi$XU!&u?2Jaudh>mMtbX@OTcT$`~$8{7suF_y9#e8&JSEA$E^`(>I_mP*h zBRa0qw$2K7bX=FC<7%nltdL^u_Mziyzu#GL18Y}=j%&D;Gk07SZFdU=(as80tX+N2 zZp814vx1=GYJ`q!Q9l<&M|4~(&~aV0%tf&u9amj+T-%>HoOp(-&GQx}jTMh_%~?_wBywr9raME${Ab zsnA2Wd=S=dTDGO46T0Qi(N7L-uvGj;Ke-s)^4O9072D7)|AcP27T&je4BhfY`!vY5 zoA(uep`RR$Zh42W``j(>^*DFNtk?JX{ik=)Ew94+cK!C$6BTsJcM&U``}#;OqFZit z&`Pll-Et|q4{z0oZ< zT4AktQ~Hlvu7OU}HgwDHVeL%uzTHf8%eP?dq*GIR!lb)@@0NwJmvi)S16W-5@Zuu^B%fnJ_6~oXizmIOY zL5;0KhHm)^bj$6B*ePzHTds+2`8;%=j-Xo}hqW_1ZTJ7$XJh`R4di`NB}toPtOx}Q zQaBuE ztxOc-Rhnx~?T{!aCz&WdE>hL}vhuXX;mszBb~9UO&MmnuzPxUt*y!Cr22E3^&jL*p zaq1Psbn1Ru{@g_IZEqp@w8xHaZDp!Rw2dS^0%i2x1ia^cgbP_AJfSmmO%>DCPLkxJ zGP?V^sUlMO7pc1Rlb#DQRkZo-DXffaE{}a~syJ1s2=B9ARqootOtGTQPfT=aF1H(N zrf60)g34O_q+d6fDfXnEro)Gq(Uv#N6fL&8(%WnD=%65cziSk2?GiyFo|-AP&VNS# z8evO+tC%Y~#8%MH$M(=mW6c%a)&8cl7OGKGU2}!jdc5E5<5ltOb#ukDIjVBIH=c-ZL-wot&orU7R`zri@?W1xv zWnBb8Pm+19cYd1+X9m=8uQjX(j=l0P+-ubmH3qPW+pX?v9{S@48=t=f{AWR~^z~4 zd#$ze3&dqFmE3DB^O;I3B0h4j)&Ivix~s)g%DmPM8=YvEgO4fmS_hg&(8XCklzFXB zUuM#%j`t|@TAO*5P+z>4hk32J-M`YXHf<^MTE(aunx=kEWL~S6YaNZZUZlaiR_(m+ z^z8RQfqAV1r+lVPeuKH!dgEgeU9j!|_gbG`Nuu8`S#hs5>U|)!%YMYYR{gn_wB7I& z?zLXf-A#v2eaXGnEjs<^!QSQEYd!GGQw&~S&Arxhy-FgMKg4ST^jeSKzAbdvRl~j3 zu6mtF`jQInwN72Qo{T>BntQEVw;GeFD>Df5T1~S3@cu_BVP5N{A#tS5BnQk&OGVLv zLL%vViZHLWH7zBucLHHv>#-A6Wc!9RfqAXRb?bp*S zZKxKR*V@kc9Xa=O9`{<$q~{V^cb$8!hZiWwtScVeYnA4^6ZJv`_ga@uzfQsz+9bN- zKq>cHC;6YIvudAG=C$g)aiDLkV=41mzc0ge!f}3-d9BjS3>xTWM48vx_sMH2_12-x zYh7eiLBED}pv-GEyHZ2@tKJZq*Ba-C$Mv=j8q8~r99~TeF8K(|Yqih*Oz*cHz`fQR zsV`_!0ZIZdy8WXvX2CaR;z1Bn31F7f5 z&)jQ0ecWGE{rR1HtzGCC*;B7N?zL)mz9J~yYq-}ciET$ZKdB(hYgJ^eC6c)%+-o&T zyGH`IWfJDK4n65hUe|;Z=Cu~pJSHpr90~JU&zycr)Q+4b%xhiSzLdoOm`s@0I;m3? zxtW+NFt2r(7T%K{q|{(u>!ol!uIEe=nb)dwtda!VRfx=MHQ0jdgsW$Bul00B9*Nj= zjeD&=7b3|=HFxf{TFvq#POft9wGPa?K?cps#0MyPPo4h_gZH^cuDWv+sVCFT}29gdfbA0tqZOM z(_>Qtx!3w)nKcdkn8>|WVc;QJqgTYe)Fif!+-tS`7$SOlf9GDSd;LCHpyw-^1 z81jCAGhtq9)s+IWL1svp*V=s}-hXE_oiMLe%Uelur#u&!*Qzz3j(BOd5t!GyqqvsT zuOA{Zul4M^O0s#|;D-UhBxmq4aaHKV@EPxlbD15^YME z*E(Z#F*P;XOqtgz7<{4KTdGm!wT}5wO*Ow;ip*<0jO&CN`+}!4uk}o9HJxZ-Cor$| zk;)f3EUqW_T7z%BqD}+1aj&&SK`L$e$&7ogJ5ocag!ZiEUTgY+7R37HSMIgu z6fPqtir#RqHOuWbQ8|-MnAa+Xc#{XGMZ&z+-geO>#lnR!uXV$ne6mgDGGSip3eOMZ zSsy}}*J`by#I@WKfqAVFKk;6MA?gD2THRFZNSJzKtfzX)fGrEpI0w5hFzIwf<;%hjf^h&Arx=@a5#F-y80=Ca+Z` zha*uR7vE}aX+-tqMY&h+TJE)WKk-}0-|~%ntv7WS6Vc->_gbr4-y$iOatQNUV^?^Q ziJ_D*ueHP8C{o?bjWDm(*Z2wPFyty>UaM-^d!pr|MVQwrBv+EDZ9WOiYc2)YxRy+k`J2;Mdr0WxcQMZ_)g(rWi@&CvV?oB16A4(E8#2mT0`HS6il*exYv4luC8o^ zQyuqO-8u$~6Xf5y*Qy&hgpO+UnR~5)ix1LHK1JMXefQalT24r!%xi5J7fc7=4y4R$ z{dp>dYCW-_%xi6S;w7E2dlzM1tL^-9YPPa3WnOEu-PJVfjl0Oa)^@;vE%xkSM z$s^+9YlL~NFz!8xnK*|quXT)0CHboVO<-PYl7B5JsGce?uXWyh^tqOOmNBn2a6}au zSdlFXDrz~I4yD57q z^IG%$KGPZBa1Sr^TDNz@x$2F6BJ*0U@H3%nUm5dSH<+UrJ?fgkyw+O}E9mRg_S|c2 z-v)iE6m9OcuIQFYpMw$iT1PsC(=!FW+-nV)mVP5Ou7vIRx zyjp>It-6=cd44lbU|y^LwmPC>oFVfm*Edc@7+@FwZ_L7lfLaTxYwFGcmr{R*W7E(TGyF;7+%4>)>*sm z3QlWkxYt@w<0761)^V@3*$@wL-;QeTwQkVsOYh7o=U!{)E4!#W&Ob7*b!v$PwL6kR znb$hcGLWhc4W`U%9V#Tz-o;jwd9B`oMYPA*gOqu#r`vy~VP-=p^IF?ReWw>QABoIs zwZbg%S-xJzyjI%`yx(EhDS>&dBd2}E2g3JF>y@9lf;wLY0}l`OjPgfOqQXD2uEY*Q3rUaLza zB_HQ_5$3g?x}8Jz*54$|Yn|iwmgJJfgn6y?JMg}G51;<8oH5gc3-&Hy70NV(63_+_gZ@n?Hf^wV<+=kTlhPO zCvcsJd94pp)M-jVIrmye_uNi@FMh?n)*ia%wC(Lw%Dh&M*$-)`UI=AgtF&h#4c%cw znb&Hc^qi*NJ3^V)dhuWx{Wf+uWnSywd%x4%xiXP?t*uSbuTQ@tV_xg%*0r?n@qGgG zTKkJ%Y2`6h?zP5xyrIXREazV9?6KMOX!kqZYn{|zq`o~Rgn6x@qg-g`ifHb&>Z@I% zj+yz~YmMw9(9D7l+-v=Cr&zqRLCL+=o8P*L=`HKH*SgG2UASIf%e__{>x3^;mE3Fn zra=gC{=mIfwSJdLmn->%d9BS|T*yz8Xu`bKF;_)WBk?B8YfZeIO|{@=|UTf_dJK=MDHTPP>lijDE!gFHgwVs}GU(Bkh=3Z;VP&M|9KJK-8`EI72hZb|M z^+LKSo(rW>=C#iH>`%4BLn-rGC6)0syx5j9uXWwaXVmJw0cBomdE6)ZG-(uNUhAxO z-)WgNT4Y}9XFT^WGnB}f*VE58P{YQ+^O^p7Wz#m1GGPKuXWNBLy~m1fH1Fh>KJG8Fe-*H zul4j?8JXDDhcK^ocLhmfJ%Yu&J~h@@y9;$Ca7SBb=3*ZLo?bz~qB zjDoq>`h2ei2}?-fUaODZPGT4Ql6$STi~EoZ2Ibsq9iHMUv_4nOz1FR!E;Fv;wJ!5o zZ^@0svrxmm*1Z?H(4F;PxYueqLzkxgDCS=4(U~UHIW(OzuXXeN2ejx{7-e3oN@^VK zzr~(1ueIcBA>9clDDzsA`+TBnc8sIUYfXJnMIA;YiOg#y`|w`&$?-DgwXQIzrNnBn zz`WMq(r?s$SiQi!){F`7=%w5R+-to_(BpW0gL|!DEvHwOd2+9{pbgG3+=?X3YyGwS z8vT@?$Gz6slV?-uuJ_z)ZNI5PoN}s?d#!456UC1awcKlc?O&xa9_qN)YS1!INN!if zz1Ft9rVzuHrQB=ncIPbFtN)aHt)Ws!^0E9eVP5O)W)Z~VfG=TQtM~p)G9&69VP5Oa zB_(7_$Xdd@R?ET)V&&P6Ft7EuXAP-yy(}=V^$O1AoDCW$V_xg*y6?m_*k5E`>yfjc zNnf==+-n`P>;*acd>{8(!~RYp3-a%CuXV-QATnasBkr}%`C>`-_$70%wPpSuQkV0B zd##0K{YiBGXYRH7&GHcpMpbjKwftZ^jkf5zGp}{ayc^=NOEuhUt;_8|LvK}ZueDX2 z4jr3;`<0>BTKCY11}9`t=CxXA_|bWD!YT7wQ(a?eNxlPRUhCZ7Pw7Cj)0BCw-Stc9 zvYLsMd9Ch?s%V65rpUb3?>JXC`&)^Od981pYiTbZL113%r}33kGgc`uuXRM_JNkC{ zT<*0_)yktk=UwMsYe*1&)?)|mwH6cwQT&IneIA_RUyowXPG#+DmWkrEkG*+2`s*C} zBDgDW$G$SAVNor4d*RG5dc(1t@Bc9HXFh#w`p;evnLobKd0U+M>(7=olLz?j=j}nW zTglbJd-3+!LuE9RH)BYCnsouc?Yi~`#IRw|g2y6Fh|DMj% zI?UVM64U9{M^?OD?a@nqYTq!z_A|LUvx_{{<0@hMnauNQDc9@iN7#NQ>Rl^o%gA)X z_A@aF&ZQIZURt)F$%DKgs&=A`h_0T-f zeig0}7bxO1`)aP=UMaBsOz7wSnx`MC3T!_UQ}h0s`Pv&qwx7wozxv?5ryVKV&&0){ zyQa{5H)Z>or1xm2xqg@fW&4>NP5VjO?1`pqKa)XK_u9$XekS^7x06rby35&qCTG0clC>NA$k~1-UH9D;s;Bgqv;9o|>mlDy>o51W z8_u6!Fh}Sk|5n_dGCw)#c{jO=?;+l{ebrii?1?*X|95YkraJ!Lt>b@>{g$N(LbFNz z_%S~3>^#zHUr*j1Z(~OO{?LK92YeKXY4LAdkL$xn&|I}+HKQiqZZ{xoy{B-y#@qP0?E7rwVc#=vv!7$%;~#!j7ta6xr#+zln*;wnuP7UDNrkB? zg#GPpa(2>{b}xB5IjlD|zFp4S3tSz=EYE7*{%;ojZ#fV7pJry$ar)13@xSFb{cpV* z+w9y1+dP+8yD_g=yD`UDyD{HbyD|4z`%f!F%SRwJ$xLIvo^~=_VcXWn5(S)=kIEKo#*hM_p@R$< z+tcLsG`T%ZZcmfj)8zIvxjjv8Pm|lz+}*)E5hp6$}~Y?r2IyEHx9rRmu&P0w~|dbUf`vt62=?b7sYm!@aCG(Fp; z>Dew#&vt2gwoB8qUHxmgwT_qKbAUjAM}w+Cgs-Ez_pa=PVf z-ab4=k2rf~^0x0)JF=%;1aA*`DkZnR+Vl2=une+p-%;M~zO$Ij3>n7T0qe@hXw?9b z{eB0n3S#_LKZ3QB>&uA2DrbSU*GXQJ*$)R0)=oFeB8lY(c{_#3$lk8Dyj{P^kun?eQKhEKd5P*O4D*Nh6@URh}^W-j{7+bP!S^uwzX z-X7b22d$c)%iCkdThL=46}J|9c+~`$$`T`M}%bPd=xIN6w_|Z*)pXqE$Ipd3(5X5PhiP z&f9CfEb09OId8vOzMH1*$>HtRJ^NDIg(bWlt>rA<`uR_d{yfu%-6H@78_tohXFu`w zu^bQ5**}}N$%uHO9TLpjPahSN?&nN+`>XSJk~m~3Z}%A4OtT{N1G~QfswSvvmd{O* zv9{N$7Mf$tuCx0o;C|l*l9$kjuy$;}a`Jnk0dMOKeL}`BaN+I7J)A#H%7zn0edxu% z8pxOR*$}>VJKa!nX@KkcWG&uBx-t zIO>)IIsPr=clzmwA7gXiFDDhbo8b>}{l^?w+N*|s&6`VWJLJNJDIaL6(={raoC`17 z=h78z-RboWxuCLz(m9oKy5)Q>lumc0GxhW6Cg)t(ZhM7xTmO+lY%cg+nn_z$*3cHE zxsY_>o9O&nMQ-0Q4`LeTh|x(c?JL z0;-naK#baFLC)E7Iy7F7jF_GUc3XeZw?+fWjh$JbeBWHYInYt~+b9c0u2YrI>U2Az zOIQ~4H*YRq5EmdGeUSyNaPQmk#Up5s*4eP+Tp4{~a*7_CoDIi@KcPeCxX?FSvY}58 zkxriyNk87eIvUv11%6NI`iI%jFYOR@o&JS3FU*F#9sTI;7r*GX7CBHk*;*W=+CrW* zE(gB(e3|iKt*ShFT@K9G3KhocHJ58$%7I$dG34F(diu>b2i9FYOWK8gqRXD-z+7`z z@^o|__5V8uF0F|o0TmI{c6cuQa4aNUd)d*Ut8$^6@(VG|+D~7d%LRMg2BJ5$H`VaQ zdJS%&xi!L6G|kF|J*!kTtH+PlFsRLi^2N}_U#9mIBGmeTbc(?gFlhN zt7plnlmAaGRt2ZPp26yLiEjhB^dtq8`MR{(iAr*&E(MZT8PSgIONeH_R9JMuhra%n zPKsxy!r&b-)H+E@0=K7v(VPM*>~SP(ucktLS}DyhG9(sWsgSm(mUbBe#3(rx{Bl&} z8w{1gs`6Br63{|^wpd%J>XZgPi&f=gQVe9V6VkxU+d!8NQK#M~ z(;(}3CCw<%rLJ~qklC(;j$ds=cPrAs=36@TK&IBkX)q^AN{=E_{_iw+zT1&zBh&f8 z>CmFckTxKbI6oaG4hC9{OrZzT;m$dw7=cV@jME{vNLv(;sc%p^_&hbx@J6OjS?MtC zszh)_CezAvm@rhGv_z&1wG4cZE^$GoB#jKXzuJhHA(PRT3~0FELzW}c_{$j(vm=I- zCrW99YXn4VrrCOtQ#CGRp|(B4|IdJxc}HklBgqoOH0qZD1oX2Prh z%$!1Paqg;2@LH^@`PT;njjl&C!5WX7HrFLWxJ4$s^=Tk#f2ot|uuRZ9UP-PM>XNU8 znXsl^38_P-&|jI*3~Qx((TA)bh{s5xlyun{Lx#=Hf7uTl~pGC>gc6|(;mn$V_ z4kSaQ20ml!s3YlfFBy#EOX;;5L$dK9c!nv(AILPzIu$;x)e+Aj)7ywtu>V_6qX?No3RA&pfkeneruFryP|;GI z>_8@~{%IhW>yo!;E2-(6H1M2fL@ba=dv6--Jmy1^f27me+i76AK8A!KQ=)GgOcM%7 zgn=VHl$r(=@wmqxGWmWjZG6U}X zNGCzaG+<-~9L$lDr^r;XI0N<=IFe(?WN|11c6~P_gAz(fwn+vM0Fr}Dslgd=BUmYP zMJChy3~*hpBV0$O$#r<_sO!rLk*Qhl%zyh28y6b;QuxF;@a?Zo3o(~oX~)5?TwR)h zxm0*24u-5WqTM=_5GTht$T;sqdnnV%?5H>>*cL;plBJ|`aU2|)T|kreI+9S8cqmLQ zrL&3+iE?N>^uY`W9tNa*Q9K;Q40v`;DLgtH4}CEM?pJ6FI;Qauh;;)K1KH4^c*w*I zczQ-6CS}J%7-oR&0Cn2xdptOtsH6+?bg4?O1juP$LXD9rUNZrbE7R#%LmzrzTLL&H zOX;ZXF?9On1lYaTk%l5uksG#O8Pe{UOMT)KAn7ll3z12!Gy$rwD8)zf z!N_DdJ`uJ$8E6C`)6!Lm5PeP}Bp}n*qls{PpgJ)}rtwyZFy@Ia*^f*kWr&yR#hfHqnN~_}zci$C_awoIJ+979}@Y4^w!7<*AEI3m-?ss*^{xb3p2oQr;gCiHWo^-ZZ7e9vhs*nsKN|bHd7*+J&T1;m;vjWtJBP1vEYlj zv{a@`lLp0sY4;M^9<$PTejI$qT&hH-iTmTAb)J;2LMD|vaiDq3k@m%0^7M-XgE~Xn z8guDQdK?(f2KqNL6@80?^HeEjAd{O~JcMr35%(d}{2B4!m!+ri8kxH5#zW97iBOJA z5$EDTwS_v#LZ%w0c&L==lIzIyH6|W(=Ngf1$Q1T29%dZ%Aqr&DZJhwd>taY!u9S`# znE3%*2){1if$yr zbsR%3Ak$?ZJQi>aNkOJn$%){HW5`X$^eGW0)Ebg)$TX>A63mzdWEL`wnUn+(5lZ0= zGJVxag1|4b4@zSonzLZ;nzN&ogAHm)`HrGAeTklkCI9`b7-v+!}9vP@m- zcCwNPwF)@8+=veBSV9{5M8e{8K2*CZow#d7!j-KtbW5s~7;KA#IkO7r&i#%=?MfuP zODUysZw!gHXC&;|T}ur{0a=k03DYqHZ0})ievX9Zm;s~y))vA#Mu8OTwtJOE!-s@V=uI7a)^h6b&=$ zwZ%5b^x|POD7P7Cgd&rFW;CcC$G(J2tG`8qqOUp`j7(J2PTn=?Wua zhfFIr$3Xk@J|s+;PQP7@fw9|Sh);@?M!Up7!K?yuADMQ?#K5-HQu6z?A@zJ41JS!{ ziRlQSPOTqovhhs=MGM)VS81~>8qK8bq2E@XO6e+oiOdn^)!q|O| zWH4r>(T-T?|Jsl^Ayex0Sa2Q=*Q+`s*Yjcbj4sgp=S`*%;e1#_v*3knCNxc@pnZ@QU^9KvQB(OqgKByp%5BK3Xf zH_W9&3*|6JCx#AtA|=9pIgH0#x_aD^yu2fa`It*He;Sg00dhEk8DKmQNRMnexL^i^ z#VCd6RdQI18L;rMj&P}`0zP2fY@PLFD`qI5V@PxP7C|Cb>MCI2!v^{hnI>FN!1(i( zv=*80F;F0=mCzbw`Vyyrn4jsi4w)=JDBvsR(n)06**X&D9e1Rgk*VdVNC>Ytqz92{ z-ttKJITz?1WYRhs33sBEq7O1Pvxk|cc zW)zT?$TT)33QXfl$#`TsTpk6U+iJ-nWZKgu8XjQ=Y>85eqozi~Cd>fSeL7;s`e=BE zb=&YrPs8a7!rz1mc}vg49AdYWHNpf0}~^af{09O zp2WbUJvzcxWU8)-fe2Ag_6C{a)gS-cf7rOz*q5$P2#2a3>a+oK$!%>ov`N#YCvks2 z`_thdUus0hbt)m-9Ks>yj1RT?o=%!YhQp{WF*G?%O0r*uL(iE7^zQ?X6+;BHwSR6pkN?fKsg6yN)_S50eN`VBIRZ7|7l|jDP_+ zo=iF*5$|M0z%$H%vYzTRNf`mNPF2$H$n?0U49Yr|(2>iG@QH9TnEySU4ms;XM{SjX zUYe9%My9%pGO#(|NOvNWldB94zc<7hmeQhFeE(RW&ygwrgA9(FE5&x0OZM$V_}*4W z{EAFk<3unYWS~Kjsl!SUMjes}YRL4+K!g%?brOb5UoAy=ovusTA=9UD5p0%Wk3*)1 z&qcU#)`xt@tX$I|LjIN*(hZpg4WJM(vw%!MrubPD4yBZmJMRo>i`^93U`6(~)V|2nF0TRth7K>C;jL^k}Xl{6r=bJq6^=GLVHM(-u?3zx{`e zYmI&BxJDS9YUoKlv9BN890snTx>Sm}wEJ=x6wflEA263jdWJ!Ro)0zol}^$V!oXHL zhCahwa{Lem4$}+h$`g)cRvRg##+K6N4Tj|67%6nY3^=*~$eC4AxQZFz5w8?9Pe@?_ z){UId5nfwM;S<)a=%Su1C|nAIF#~j`NyN2-Ofhlfw3^f5BU-3o_(Cmd-MGVSvX2kT#kv=o`V)577`e4xXT z$>nP}1ji|{&#K6GcaMM#$8^NS$kcjz1Z=sfr%{SbPuEAl(&-YRA2OXk8v(oj?ny2q zljs-$*TQtkHDn5jj)29pjfgigop~DpoArIjY-H-&3j4fv47rL-Wy59gW_khnjJagG zSOzUI14bfK`e7LWX22a}N;H#!8D_xaSfzL`R0hkiZYKORU}!gWYWARksN@F0o+Mqm;B+OauMUC^ON^*S=Moat`w?iJ z_MzF;>0}o?g8WS}bV7!dOxpSgDxiSc9C9T2mma~dq*9vo$&jddJc62?wNyC~NTL;&d9XqO(?9{RZDtI0J^nR7`(#k??pCBameT} zc!6~b?V%$kE)RoftlNi5eGO~9Fqn+Fw0Mt15X{102-fO1GMxIiR;=}Wm3)-*GaMIn=-WB9-QhmC8EeW@VgA@<>( zv;g~h+Vh97CIqj)4J%2)-w$CP=F-9*CFI_aKsbuIq|%U%^YVev7c*c>zLYfV4TN!+ z0q-%F+;8K1FauWqZAgkA1VZ}OT3WCW$g|8qIE)!!lB5)zm4N_Qw-M)bgtg26Gilms^z((#{zp?qsC z8IMdOJBPq2%z%l=R6aQbW@FtBoYoO7)`bAFXm&lOr?KO72#ms93P+|Eb|LTxYt^rz zCz&e`fn?03#i6=Hvp58PV=hUNNu@<71Yj;bMJBIdq0oT2bPAbHE)0cpSSv$hQa=z1 zyKoG7giPy=Lg5*XA-|AmRS@?71f_5unbh(^q0K3*6*9@HL*eFWJy{tt-R>FoZ~tNA zT4P^YJ>CxtI;qos{`l!RPv%@`D45j3{&|Ap`CGApWEeRjo}YadJN} z+89HPGo{4xg&$;U7SN$b9Le;*{h$lxlExQ9a%%7cSb(`?H5G`#f(LL1Gr-SXDNH%| z03xt%o?~@{r$!GT73-F0qc4*LJODk+fDB!UxHR(t{J;#@(pjC}t$YA4F_$9ab?LPp z{_wMN3C%&KMS?#>)ZqEjDIfZIvp-DBl+stoL@)S5%wb2`1G93Qi$82DH>Asu$@#HA zJe&gb7&6(s_lHzhrD%gpo7)D!tC2clBr^RT697@(`Wnf|l({?r9&M5cyOHU*egG`# zqE7OWDcB+aToZJOKQcX#1^`)XL?|*DJPUv;r+mmEWa{=S048pVA+Iu|^i98quoVi( zR%E(0^C8?yDkV2R8`6ZG55ak7ElHRR_!#bo;EfsZ*;y%G_j?F&ShqgIbj0E54Z^EifhAd}6xKp0Sy zPF^7saSDXnIEGw9rnZrRP>*AXH!?kZ6$k-kh9m}=%9{njt4TmokmGn-O z7;@5)s$edS_VI(~m`h8M>0qiK=q&;ogiO0C{2(J)Degq35#1gDHPjJjAXD1Z2N1eh zPlGWzu6qD~Pm~BVkZIo5btkjeZI9t)TO3y|rasXy$&3^<2OD?|K2 z1MAimnW~=nv+qZ9?KVA)*lIjpFqhU&k_h|M1K=grsvMcTNC33MS`ERhblDaF>#$a1 zk!jbp0O*dj+JsE4yaV7k)~XfeQb9rh{Kj1BjZEi027oD!A={Bj*6tzn!&*fnQ}FnQ zFf3Uq>_ev0YainIn2tbL|338)lsj-P5ShxXAO72a*tpi%m%<-2PqrDeoW8GS9)t9v% z>jjpW0XNr3ME@0DaMizornFb5Wk5?(v2mK1y*rGAZtO zgXIhz(Hohz`+LL6!}=PT$TT6{8`f$|ggeNT_r)6?bWkVTk*RA}35x~$%+o9&Z;m+950MgZNh~EVDh%nc5(#|U zQA^fM2Rg8&59nbAEcaH5Z%5*>jCHG@q9fj3<^vg6H|uly8taevz-7#(0qZ0}y@?OZ z#9A45R3}2P56r<@HILIJQ}TV_JdPnP78#M+Iv-exW5_{da_s91B{+s?Zj2#^z!$FL z7;*=hI&JfXjuludWLk067tT%t(g$;CkvG1_6UR7YYM<-H?0|sJW zubSu1jyrlC`+D3ScW8$hpoY1$@0L5P!3>DOzV7Ac4xyLxW+GvEs{m8p8dK+J&V$Ye6y6Q2FarSv79a2zur5SbG6JmKx1 zT)JoB3BUj3()ch>Sg`4zTxxjY3GtXq8pz~c;|cDV0j0=P+}jJDU@oz&e5U0EEinU* zAd~Y>FPMfIFbSFF-tdBVm`k?E)YaPy>ZcWuF~}5_=mqmJ1FDdz>XR4vVFs8WQ+Y>k zmfM$9H8_|BaURYx51nrOeP%T_9yh)v4~7F8SrqaMC_2^49#%8;&2;vy6l@XY{GTaeo?w~zM2cX=~_agkg2VP z3;d`{r`wU~;U*VI%$Cw)$aKNb1s>=-(mG@s{;N<(UjOxt2y;06Ku7v_@gI~S;Z zs1(N{Q~x%uaB_i;XogHNqg|oTRDF$nWHMjo3R{*-gaBlks^T_N;1&U+)%lX_Q>Z-^mhk;$vC8)%RMvKE;ZX}LihuA{a> zrdvDQU>W9;Q~-MA2EK>oQh-vN@9PFuSU2^#I$~+68{}c#PS4TTi1_RVo|sGRR!W4; z9o-=obE#W9b>cA59aOMZLD9OzO2-`xa11$zOuA>?;V6zFtxx!nUk>gtI$KIqF)P#L z?of|o$XR4Ec;bte z^<}xpRBVLD`=9eAHm)_c8>Tq`!MU6O?Calk9bi4qFD2l$LB$0J2*(Uy*9IYO4v>Qx z5RBIb>*E~YFkUmY!M;BHodf7&1{mQOoYK+}JTRB+@Yb{pam`jZvg;K2 zltiVFc+`fZOe4QI!KXjhabLPPL+`UXq82h)OmPPNga2H|?bLAwkI52Y0y3$dc7|Jc z9hZnqbM2ks0iK(bBNIeA!#>QViO8f-16-4oqFS&EXky)NpVJX#c`ocaS2J?Ap2nT; zE-)E$=`)@$jp^wMPq0>Fk?D}&3cs;dI>@wpt1B$QT$+hYBd@wb8_cDB$dvBs3Wu>) z9g)c~-W7gft@%Mjdyz?VjT_Y9`I3N4#V6dL z<2F4RJBJIha{IUcuyL)iFI@|;21|5KtT2~uWLbkg`W@qOUjAa0HMB*)qY`szuDT5r zpmQSNdf^Ab27002F&WnjrJHOZ4cAeZ;CkW43pQYj>!=&iIk9uKfy0Ga$dKBM2U1({yf+d>`s9j!2zuJ*G7-)cje zgiO)1?7$kG6EkEIciVwBIw!x7>C$aGSc=Zcd1M;$zz#YzL%#$2cV(&_d`9Oa1DUML z?LZCvj!npv*V!J5(K#u?T*{bY4`Jwc+(ssg4fb#p{SE~(O*?N7uIP7oAyZ37dzg)W zhc7buD(s;a*HLS~8`6)(_7IBesDS3-7~eT>DyveSPh(`w)b4 z%zH7HdJeLJAe>|ViEBJ`t`&^MwJ*Rqi+j7Rpa-sfdE;E_xSLim3fI0oa4z+TuN7$H z9CK%!OWm7p1=d)%Dx6Cl{mlwiVBN;)>j;_Mtl7M-{I0p4%z276^u!FfHA5oKS!WGL zFat{e?ny77wT45O0p&RFea^`mjB$?H0GYI6tYI`}z-eSEd1DR7aE`eib1Arm4V2&< z^C!$DonbaG0_T`$E<-&#z*j2zFI>ZKc-~MOb zJ3h|_w*Q&;K2U7~8*q;KDl$oW*}_hoW4?<_ZeR-&aE>_)nfC0k1udLo-iSNq zW`G2l3O#Kh5;LGb=8|E8Exf^8@<%3GY6}B!j(OAqprIY?;09&@#4E+K6YXFj)-CzC zj@VDzj;#x5&b)+KdBP5cU@mD)lL%(kc3_LOO2ql43>h9TSgWTvzm)XC4vMf=Uon@A zRP5mnjv+0OX~Ix@D8gD8augV^Jo%&~fshgU^zx{`eYmI&B;}|n2LFc3%`}+HpW>AFA$z#l= z;^SuU6rGbmTrc#rF@retJNjT>S|pmm2=qH9<9ea`b2F&JzH|iF3+YcYD8srH)fti> z1I(cm>!yP1g;jISArb3#5S^2Vede$m>t?ea(!S!5a?Y6%ADcdSOHssc+`hJJ@XGTHvH z1Q+x>!jNfSpZl-_{f?LDoV0`cFbi|Z4V{z4+wa3j%z#JeoXov`ABwPUAu^@d%I7{D z!M-#AofH3*`@sB;;+J|F=gaQHTg;_%=$s7bUWda_vSgRytTCZ&dgRxd} zWa@Lq3Qph{Vunmn_EvBT$B^g9WJ>Y4#xcYSnI^rkg68O)973j}zpbDRIwy;f>CjMX z*nrN-dt@5F$QpL(>Ig@XDfgf?&{93wOJwr6XZ>&gVdGk3Uy7V+0`^$9V&qe7FabTR zn>+G_8=62z<_aO-c~=woh<&L6`3A(AfF{K4D*aiG3-1 zgeknizBCB?Qpz$@h{d{n#=c}~Ut?7W5xt+7 zLIc(<8~gX$T2n~Jx;@1H{jx9iXXXlF|8}2c1~YL@-WHh_>@tIWxF%nXS=r;d8H8b9 zio^ab^D+aQABHpnnQD{F;Qbt+k;wGzvl(2EREpuqB<*YttM}@NTaanvWOL9D)zf&( zn6$A!OvYSl zj!a)KTQZM=phrROdssp}*6I*4?T)jAEjWfOL8eykEul4zA==2apv`?SK&Rt4GR+)& zAA-^8K(|A)#p?SYL#Ja6GWi_84?peoWaxHip1yzo-~PkKwR1;Wk*&Xf)6AB}uxQ05 zvS&agJvqe~u6(>tGA|ZU`3_@PRx2ecQ(|a}kueN;ol7c}t~6h23|CFch}G;<)bx!p z+)VvR+7BH{mv=FNW);mfSJc~!gSAXRT&=3<8rMr>^?noRGZ@#nEn>!j-!6L?dUPQF|FkTt!rU%d<@Z37cY+j*w&$j6A>d-9r4eN!mz zy_kGzQ%&YLnS#0b2chezW}0G(DJ(91t1)Dls^*+(Q@B)GD2p3~_iS`F`}gl<+56|% zk+Z+oRTv?2UxoAA*q*ZPyx@MI1#dSVU+i^>+em8nrk=3&?=|P>?(?5`yNjheRs0|J z-ZQF-tb6w*m~+O|iaB6TP?KfO0aM%N42n5tQB=ePNRpf-Ba#tn?nTZyqksezMNkwa zis{U~Tl>8C>wWJX|1-|$4?X(n>Y}Q4J@dC})ta^DdYB{AJ=@1(g<{Cx`wTC|>|>@f zZ94ih4)gy@rlaT3cYyW^GQH-7qU2@VWI=k&Us{yvU;Cg`|N2{*{`vPYW%}2-Wct@N z{JqcL*Cx}yu34u4j~`x78JPP{Zyru%)PZ$%m`rT2tSSxVm|?$%M0 z>J(>r$(ca~()-4zLlZ6>y8xs*u;c~a`gT{Quf-(dvm`&6K8NnOVn?P-FV@$^+_Wm0 zHf~nIZR=#7@}TNi*w-x>>!%pWuU*U$af@I4JLw+?_d8YctHWL5NM*PKWU$M+gL836rh&TAC;I*BtSh&}SD;Miv z_N}+L%fyHe9q)=!`?68wMto&vEY6$|jECPC@d-wySe9;rMm_KIp=O`4HU3YGoO7SM z9g>rbPx>j2K60N|)+$P>yN(uLTixdxWr~t~`Dw!bnESj4XdI$g0n}^n^VIrJhz~Y` z_dsLbKI}PO=w$}kOO3g4S`2<%7y{2u8S{N#T=3)i9I&xB=JjJP;i&o5&^E=GE5(h) z%;&9O(qznk$4vhbCjaQ!1I_rawnBCf7j4}HuaiDO+Ehax%uM0^!cw@t!;pL23WDzY z<6z-!L*At|6K*xR!99ONZW;OpPCmH~>x&Kf^M@^9c5WtYZ)e0O$tkGM=#nUWo@&Ia zmbOu^U42gN@HQjfX^x`$f)}^NQavNS#r-=d&s4%9KO-Ke^a1YA(8l-0M!as{GpN?G zrd;-Yo@f;Tef`4m-ekHbV;n(4$Vb)9_xY?oXCS$x1~v8W^N7zQq5kSuyy$gRDoCs+7<2iOF&Iwsf+Cd!wRcWYu-?f}RO4qWM|YFU{179+~hJCGrwwg>>O)feBwes0CX$szEn-Q(oWj z8sj?YL7$1H{7}bC3>xkM$(v01qa%ShXMa4jxn|0vnvC&Y|1v1|Hsvb}H{k94pTViX zlyA%JgH}Jk!{HXwe|(hk@~hobmvQuWyC>7XeW&g0S6de9Z@uQ_+pxqJNATs)cnHAhdTf6d*Ktr_%dPM?}||6g0fgUW%}3LLz(`4KMj@XgWz=qA=Fl=uV0?W z6^DBWdekTAeJbxCU*?U=;R?5VN!t_krR#HeeX)m7;HRKI;BpS{Fk&>6tojP8JaV}8 z&ogk@u?Cjp=I{ZR9bw$pJXrrdhc8W!0ObqeP%$c(hu(Mw?U^++ug>MA!#+T5Cv8}L zDVGm*`wkmtE5RaO){j26yh+ z0!{bSAh%N{-%EXl)|=77H6fE;c!SIv1*x_R)KXok=Jny^XtHD`ZJH{UxDig5%vMg?S&HxnaD{$c1Ebj7i5mX0{eE4DmF?X_}L_sB+cX~1eSLuGkv0Jja zR^Vwo-dKaX?_~2;TF%&fHy7_e$>z)N#NcSd5PU~#H;>dT#Q|MS(WqMvKQo{ny*8}F zgR^tEbDW&y@x})6K=xV%^Ji_hWh4*kG>4L#xd=Nvx0 zp%!xzwIOI&F1I>M^PvXY!I-tVym_XGoqI>X>&v;k`&~8t>9i4K|Kx zffJL{_%Ks_c&S?nW;@gPdru#VuT{5+Bp&CTPvp8Ss*pXQ1>U z$h=(%T?-QVNP8c6vpE$E6_R-0ajB4+?*sM|leov8O2~-Uhko0V`2Jokka0^5RPQBm z3*vEuPPFhkJc(bY^T6jq)q$^RJMkE{!Cg%6k<3>eYK0#ARS@Qq&aQ$EXLa%Dv1Hy` zHxss-xZ^VWWS$h|5BuLF;NhfX9(2Y4CO1@|ZbLG^@O2R!^JzrA5h?t`v0`C0@u;;v zg?qHvtJM>aJ#|y~8w~^TG4ZJFlfwVRA?S4V8yY=J;d?_*ab5s}!NLDSkFe_`Vq; zKIjtx%fHe-w=Ho+a1opulg?k=*nx?A>tN8vbgpAH0Bx3k2kp!0|9B^DOMm zk(aDmO!v3t&v<^-I!Y)c9>-pb=RF6gLDJ|J$oGrq`eypji+F4*jprl0ec+QuDxB$@ zz7a@mOc=E`|(9uf*2yP%A&%H?E5&5Ta;rkl&qgbjr?TkIH=3>d5WUgZogFml?pz5JyE`O{P zZ+tVs63b-1b67o=PhN-N3Ca9D@i?wygBV4zWKKRVh?EyghNbWv;_-NYP2uaR6t1iF z1MLR(f~-p^eBZlTY^>1+d5Wda2Mh7+1p3yUVyW*~5nYudU}~FG?s35qw?-7f)+woc z+uj|x=ujQB*_F!YpB;cH#N*nVssDHfDku_<>qbR$V|{(_xK#v%+~F=xHHqQI2U}s! zAr*9rjN#L>szC7~y$jXGaK9^=Fu=?m9}kM<%8~w1R+WI+OJaHQDFfKmSb>$NWBJ17 zMX=;iBffnY%SZ1o7VZ*{DLJv+r@&tA2l06BM=THAXdvDu9@EFgafiquSbyake%=(v zcZ#QRM|};Bza7VOw4HI;?Ofax8pjtH#9-5%5Dck^;}-i$ac4(U+|)Ims}HKjeXG{t zbQaG?#>+{TFK!Uk56APtIO0q!cO)O3gXG0| zF0nj8-IGYicp1RvY$FEOjFu{U_Q%5yeuQF(Ud6ivSC~ zIKJn+B|>BoMES?@>$`T~d*bmxSsb5pY5>kz^BqDJ|XL%xbb@G9RzfxhNJn{|`Qb8lf z2lh=sE~ixqsnPmSu?2a%J}uDosv5}OrR~FM4)vjE!9NW79XijG+yd3gSI7n8v1q@$ zXxUxD(+*I7^_U8_og?8rGOJ+Z68OET-?GPNWJA#+&FU6znO_3W$@UesI zvH!AlXd{W>2Z+bntU+|HiQp5-$9AI>#0aHGu17qM58Nx1E{No#h({IqUJ!61lB<5I z#Xfo3@X{%gyPqt?>|u7WF*A}co+_f7QUvsFjpR4=Eb(b*5wOuw-22iFe56$euQx>T zr}qb7HSsw0Qq(`*N!!xjK1PoYn1&p2XwFt6}{0U^VDTJla1F z<0~KNLr3B<;&~VkBp#htrGk2=aIQ5o71W5wl{3TnRpRk`us$U24d?0uTA=e@HK;NT z=Ua%!^2yPHMRYiKrt`E;%T-N&AI`fIkJc{kqE3I2ztL=k69y{yZi&d_605-3N*Dj2 zSgJae33r{`vBg#7YXkjZc6|a4%o2H-rU5t*kCVTNT)S`)ln{?IRFJP2RxE5G9{X%X zJ|WglZ4LPteGB+o8j|1d+)B>lHGkmap}oNBBIiIn#(dO<6fe#-4-}%^Bs-W*u{3M6h!=)Oz!!xGe&n1b zRuYfHCr9wjJ9gmV!*!6pBZAi-AAnZG;{d&gf4q~nrN4dDbO_>p+Y(i)>Hf}53E~zf zqJ(JT@pxkpPj9ORTgJD*ppn7c=dM1?y;%vf{|x5GTzufD|gZ@xglYq91LwWo$19;wC zfqth#`ND_#bI5- z_`pBvF?iuR`~hLyk9hn(twC&iD2&e|A5ZpD5QkfZaZTbeBW|y-AU2F&(f)zaZF@oA zx-hO%SBtxzYQxf@;e64FLKH{XfkcC1d$Nf02SiYgEu5QOx5UX|Md0Ed&exwK9{1J3 ziu`cC^xgopUHKg>zl8teowP0e?c;Ed0KRtD-#iY_4dCZpq68P>as7_~e)bPFXd2Z5 zKPLoo6XLPrN+l?759D>k;}PP~@opfuBOaR*e84Xxkoyvk{>0Zt`6qsh{sam(d=?C*C`+$gBsDwCz!7vS}bT2kLM|tsA`GY zI`VO3yAZz2(LmfpJYJp}!UJCn!DGbZ!(Ac#kK)rfb6iaK*IU^$;+fgjtB_7i+ zhv43~A^ZvP`1Xqlw(A?poruSdHh)9(tAVFxQt)b*1Oy`czPsd(1mbPKD?UA9{{H=KJ zFZAa>5>BI1T@7w&8^E=WI%7w@T)Z_sfHxV(;5)q#e6=%xpE+2H=M+uxmO%jTJft4i z&RvI^7{D8d$LMhl;-TsQzMg!1@l#&B-7k`KqaJ-$AC8}TSd z&quuyA0AIUnh=lj9Ut+F#G^7jAA8Jr#LbAu65`Qt&m+E)cnl;SADcYlJBi1R^nBbF z^+?8J$%tIl`|lp{PUNHaLw9k$k}uC79u@*^IziO0x?zPvp> zAFmRR6&b!0dmS20Z3SJRT(; z+mt`%6NtwW;*n7-Z6zLO5RV5bmL3p~(ZpkdwjYln9-k7A2Os!xZ{qR!xOKQB&W~#l zkE@AC4T>dS>GRP|UOYI|pSu!|Bd2Q$_g47xd&J}7VZC7I1%F;lJZgN>24jk)3gU4c z@u*0#^niHmHzER}xhbj8J>3T$_;~QU+LaJZGpoBl^WYczwLsYkHJH-glRqRLGgn6oy`J2UeAKw%E+!axa=rbnFiA%RXK+vcD76aC-qpqZ?>u?c`ApETai`~p7hfFa z5B0SPsI|z8=N>YE)vXnH;iMOjd%Xyf{2K9!vllm>Uo2cB9(QDUajS*)YU7BsN)2Yk2|`IuZQFTS_%;UkDghqrr$ zE-^lQ3h|iTtrt{$@ZkeK)M9zLHuN0wh~GL|h&RUAf&QvTeES3uPY;fO1s5Liuq&2W zEEd6Gw?{na=nnMKu7f^#kNC{%1F)5N+|%;tAMd1X>2Dva-CVizh`-+--(Z*}7aTY1;m+3*kDI4P3lVeNxfA(VxHMO_?vOk0OFkZRb{E|&DVB)G`gioCziLW6YVY*q+o`|WllrTU6iaf%<3-{z zP2$N{5RW~mzdEMMliwm9r&514t+yA~B_5sW`RKL4i_a$>E56r@{uE2z)!l5 z@yLkBm5;sonC&|-hHL$ql%=3sxgC)_z!cb>!MdwMi&r?1B!kOPBAMNkCi{rbx z@LU=vSG%TyHtH_iHKhus8|h-&As5PPWWpy~cl5A!;h~}au<2t0ro_2$xq}99>}v&< z*17PQ7mL8czY$*!eaOcN#ezsY#;$(Ie-5)(n@&6)zx(NtM~CO~;<~M<4r65Xjpx|Wc#d1T6ZfX^oT0>{_{E8Lqw$>E#AD=GXKpgGSXfBU zM@NdKYngwK=d8Tx%$L|0h)2jr7k_8IrhEuy5|7EH&b)!fbB+;@auiFN^#1sXc$`SF zlw=u$4#eZ#{VseU@mN4SPBeGnQ;Ek86V_p;SQoBBJZ8!@h&?~Ka5wVtqp!R;X~;t! zL_BUAuPLlv{*XT-9!Jspc%CYZ>;V>ogi)rM%TnZySD} z@>Uv@w<;>M;T6Q=2FhEtwzcIyiO0cnqXn-Swz9mH-sn8llHIm^C;2##@>a%%wtO1# zSf-~!H3V&WDCMmlP~K`vjV<3td8?z8x9Zg2j<2A+l?~;sCN8w&TPbgKhVoVmPT283 z$`-*|8Yf@kWXEq)-s(N^I6BjgpH%!iZaZ~rcfB=z}payt^Im|cdY{l%3B#w-l}AuTYg688Gv%#1pLgW5C~vix@>Vll9eF9`tEY%AyRk9X3x^tX@FZ-k7~|IS;@T4Kg~QQqnq`MCd-887Rv2HDiE_I5Gj zM=5WmOg_%cHsjr>T~#0-gTI^cpX6gXwX3mX&G}C9v6|Y|*&EIIN%CR>EcO9^Pd;uUA3Z)k;7#P?XX5eE5DQ*Kd8+~Bqk)D6fBE+Byp`G|3%--` zR`|@1q$;U7yO#$Xwaeeaf z80D?H9kt@eDQ}fVd8@hh#0B}dm-1F2saAXx<*m#qZ*{!MiicC)N`vxNHp8v?P0CxT zlaCA6S@R>5w~8Ykjn7d#`D-4Qv@QLurQdyJEK61`B_2DkG2wkpqJ;L;&r!c@!d0kU zy+%B~^`?DH^r1KPb2=57@K9=3M^n3cr=2N(OYQ17YFDkMn(}+puKr2wYVTd9{0+6M zv#4F2ao?0HkdONGJ-|zDDr;BWl=4*jR-5uo#G|IUyO`X^jCZGY)tkNtP+Mrm&r!R2 z-c%P4Q7pBmcJ&pttBak@cq;kWiF`beX2yf|)3_Y9t2!-a{QC1n@Q{4GKE|BqPAnGM zl8<{Rmgd*nsm&)IyXl$p-X;d3Ir+HH&zwIk9)dT>M}z0)JSXooUMC;pD3;8~$3Mx( zI^hAIM?TIYA6M;rz)Q%-2=cMc^Z||E)+3OQ8PN~;Tk_G0e9WgKa1HWt%R9;=Q!FKtk3r<40mV`-Gw;ZHCj^rq(=6=)3f*? zl5V55QM&!=`d*Svjb1YS^{Bk$$jl;{mi}A%-_m`g|6jVFR7?L(`u9>TJ)ZQqQZ22M zFFoI{?ZWTvv_JgbpN<2+k3+|Y-^ZtatN%VP{eSh}*F%4&{`)%Vcf?XT;R>0j3=({vu`^~?0H-}QUD^!NVWUwR*8 z`q%xD>0kFvrlr46dOqp7q`zBwKB<=859#@SUBA>9+4cYDH)E}1JcJG%+scj;bW1HP zF{gt}8_o|A6UKIw=}Pk{cx*yDnfC5|12;7NlpXVerZ>j!ua)UHOEU1$_k5XtI!;=9 zKTM`8>3iCyV-_+!@M?ESj>j&UUiC#uayP7-Osie~Lt=VhzwFxnPxz+pMelk{-kgfk z`zCpkgI`uu$#jjEFMjL$Q>HIR-o&Z?9VF6yK3mSjot52WI@UN+%>33Tb`M1v7zjfaJn>ug*)-V0He(8Tx zzx3a_-2c|){%`7X|GVDAzw1r>H|tIOyN=So>nN%I7wahfyFTE*>jVBb>jVC~ZtVZ; zy0QPc-f`4Tgq&fqK)D#{TA83qb*QAeOTuw*3T&0>*FnR;eMNh9>GqM!9E8~_-DEn; zu{JC$v8POT9uXnl`trB#*l8y2d-3-^TTO4`PG4DGj8&LZ4ycDL|Hb@*a?o{YmF)Px zaz-+}L8YUl&0YtXk(S4n=l7O`d+dgvjd?6(=|IWDvQDsia6a>O_(L+{x`r@&emJQ19JNayZT3<>3qw7$?Kc8*U=pq^Q&J=A5@>y?JIf-3k z80vh@XZ~wmV`FX+nhz~t(m_l!U%)D3 z2T^^g0g`^9v`_LKalouUB)f_WSjA-vwV0kmB(~oRSk%&d;l%4flGtH|Y<$H$Fth6? zdAzic)eX4^@(a6379T5Qb4ml?)c{4w-Uo$jxm_Mub$^F%!V6i}^G`56Jq?>n3R&cr zw(39Hd10g6Q+DWD5B0Lk*Kqlmrz~Mae|0m{37D(#l$iz$Rv%L2BOX5el+7P8M7_6A zJ*$n?Q|4nlSUnPggfM){#=lTfzcXzL?5cRm*8I^!ee|pwP}}Yq)414Hz23na)FwV- z*X^3Xx_u&CT=9&}a4QGtKRfq7W752;PjCxLwfkaMp{DeUOs7sC4sV?rWV(CfaVVHu zEz{Z$?BSK-Gntn3jD(l-Vr2SCb_v|2Z{(!MDVx^_;V<-M`c5^~1a(|2)0?h$QNI-2 zAWHWcxS^+d;P6Q@9j?_|{lmvTf^_@bCzN*%doRo_EG5_ z+*mps^*jw&WPAfigaA4%x^UeV16H5h1TziK3B89JvheXALGM5ZXuHgi z^-FpIZ7kP9&r?(zs&f_;C*K9MGh}J;VW4g92}W^-ti{?MOlHQw$7*T4luK}{s1RIw zQC+x&GvT&P6*w}gk#gs$uqW*^9NbU!xLzm-u{4k4{(U1B88k*5ltcA8LyVYvakY3$ z@(C7}8nM@%=b(DQYZ%x5K3lc+I^H>v551<|XI|r-F?&HIT;Fn^O)8|Rr=#2;U6*RX z+2!EzVtsh$d7nKDe}#n&OCdDpKEp$GsN?cO2>yDXsjh3rM;_~hgCmVu!RZ!^8xa(q zxx$#Kzplp;msrt`>K}f+UX5#~s^9{9V|MRa5nh;i64xXev-&IXxZ-$&RgX#>WIR14AkCG;Dp0akTp z?7C7mjG2B1G^n28o;D(^oaO=Z7MQbwE{;&pHX1AsnA5tSSD@X?0+?iK&Jyy}pzZ57 zFhXL^-Zhj7U3Y(m)=G1xp43yg+o1(m*9XiirN8Li+zfitAFzy*FU6G;K11%d2P{_? z@a_FK;77Gdx9reGqay|2?EiqJq9YDJ7X>QM9tthHd3?>?f6oFdG17F1;bB12-i!op!$ssxMH$I zobt(n)sL;gZB}D2d7vfhexw-L^P^a_$da{pOTbmlmiYRpB}+nIto#s!)(@yoX@oHj zZcN4Z5=*uyatAg#mf@z?mh9fPemJscEgtJ`#S|i}#K);L7f+4qhjDF@7wx9s(mn) zjHmj#9TK21#tN^kvt}V5iy-~salCfPnl)rsgZ#B|XzXUqZue|}EyJS3NtxE{?3ETc zr{We~+i1;xsx^bP?`C1kV5&7bxei>q$itw;HtgoMSMb4hISf8-!!|4DfU?~!sIazS z;qwtTXSz{4V#B^&aRSf0NSIq?!^Rk1gA-NxAn9()ChTGGW5OHo5^P!S&No8aPgJ*G z)0WNkR~7JWzp?Q#O*epVQ;Z5`&2gzdo8AUIBo1$dS4y9 zzON7_PO@XumpNct&uGZqXvcPM3&((3514etj&-`1Me~*JLJxO4c6iK7toytgqBHH- zu7e-3mtQ+bZLwpHl}+fRe_RM0X3thywcr)wqv5d3o_(-uz@w62G4Z%P+n8R1?Y@q{ z)i(BQ*M<`8u6qdg#@Vy0Nr@PG&H`_~w`VO~{ZP?85I6L8U~`w6VpK^A%~o+>*5mfz z%UG(9rs=>Gb{N43$8_v+!;vlU^MNa`LeRq7kqv(l2c~mu za9Fk@(^a7PI$us2t-?mrRxj&Nc-g6d(6d7>D%%87M3&;qw!#Du$?abo(1 zo1uH;a^a_~6FcHt2NmJ1f@ho)vr?`E=l)B;rPhhD(YcT%M>PVJoLQ2N1RiL+g7aKw zw*S2|baRS;>V3}4X~GT2tj>cK_njHOn+xYpzJ`h6&g@8Ht+4XyC+PpunVq(oEXOZVJaPHes!v8|yc?E4;b<0l)gX zu|6ICf?QsKU7xzKg&78LJRk#I<=k1&pWe`Y>=Rry)}0Lvi-o)4wiv&fbgyUdWz{*f zIPcE9FTaH%zbRc z_E)_yV}S>o`LYt`n=gRTM?Bb=ad`k*dZ1wG!Sq8pDE@E(jYtpHb@M~$dw_#Qr3ZVN zss|&hbD^k@p(x5>xB;0<2v(bG_D z#Sq}37qhrifi188g7h>m_UD!l_^nMhC~G8runDIG-x5C4+CX=F zTd+#_5az$wn`JF*#0%MOV)GGiwyMK>w3ZCUZI<3_`Jhr9Cu-v9Xm571T?#%sYK9Tj z-YoP{0Lpjv$Gjds?A@Oa@TqeWMyUF*@r~M8A@>|V?Dk?g)Q zZ$RA;A2v~8et4a83w|!~VQZr=3G(4hXr%CnbvfA)p0)Xi`YMmuK9hCO-{=LJ|MiGj z!aaBum5FM)kJ#KMPq=U>3>7>du?P2J;Mrt*Jdp8-*$sILHFg(qSkoisPjgF8EtrAI z%D$}n?Pqv>vOs*h+?So5Mt!rr-^1IS@@2LOw8q(M6=99FFH^Sr1dSix39-?>Y@73I zc-?6(JgV_!J;&w4p@i#T+UGHQ`z``}O`YKjd(7TPyF%O~2`tcj%&PY5gU;(5IArjc zwKOk*){n11HS{s-bpM+WV^jyz%W0jU(;C7$stNqEy&s!#4a0+vw!p$keyk_Pi@IGg6bc>A%{71qed$3s-EA2Ttd{*mG%So_6~S#3#2 zlV~HzR`zFuLdsEV(-v62!k=ZO)neY`o}hikpN$^fgsW8U3nmW!tR%1n7bunuFL&nFy1M+GrMT5s^8n*(-V6~tP{6oU5~9ejKyh>h=G1$**T(cLkKIbZz@SIeG@ z7n5nNI;w3|W6@O%staP1YMbH8*TF(-zhG9^Z zSV@ySG<2_{wV*;+&7SSTOOO}FhFh(GQzKrXhl}v(S&yo-4|2da@I4c7L(F@VtvmD*7k8Z z8lBmK9ascAwKg3iGK}!*cHCX0*coB0S< z+IIprZ>mPCc9E>}<#_RCMm^4-63NVNis8qPwP3%^wC?sN4Z)YzJ-Ki-lIf>^6Fl$M z;TT$vJGAdo(5ZffBXT0y)ie6=?0F8>wMMe+bXV9uQi4h&qS)}J2r$=o#@)-K*yXAD z;1zZqQ%*)POOMy^;r$%+w~J!+j-Oy@;5*SeA&RvmHbcdJ6|vKYD0X@(^~rbsQ2VP- zG&}S9Go%I-2&Y&y%SfmK|J^e{eSb8&*6%5lgk1!|B%0Y=ivd+;51+!LnOhC5{eCtK zHkC&+n0OCzk~3jAtu_Dk)H);_SY+LuKY$c#yECQGXqD= zF+}CcI94xRKQ`1GqdUj5)2nS!y>lGSo)*t)cAUjN8=qm{ZSgGHcQW4deT#$j<5}dp zG|~TXJyJb7mO1xn`00%;m{J(eDi!Anrbf*;d2nx|9&WBnU`B5%LF?=S zoG~zwnU16NXO-&3(TfsUxm`1yUJqjMkwi9rbqhGyR;aZ#Ph?|P)x+imnF6h<$=;lO z3llS@Ky+my8`9|+bUkxoP4gVz8?Ryu{x%L5e6(zA@Ha7+1%S~`pA(>r{Z6Chhrv-+OOJ?7yJ;c5f z8{zcYWHvtL4-9|)4oWX3vo?NO*z5UoXmCwtF(qa=<4H0I8OdzrL4Q_s%G&x}z*Cw}(WNMr^_f2%jlWl+i((p!*_tPgZdZ@{C#JC= z`Nr@vpm(mn(pZAh6d_A&#-z(>tWVny!f{&rV}V;5^X@ngW*mNv6EoA;Hn;&hUgTkq zmNa&u#Tl|5MBoYKbT;m`1bnu+qPQfT6-~;8Y4ta;`dB*aGNuwrTNk5fozAWV)WOb6 ztzvL&IvaMh89e4L7q`AkXG^uI?pkTAT3F8vHpagm#^ojoRze0lHM|=7sZN9?ni)yh zF_Z20=mByKweWURCR^UqP>qLFen4Y}tI9uqOdjL%}nXojmO%-q2};u34EZXUITY zdG0-EwPdo(OZK3lq!e_9XR+BEOi?R01@c#Bv5^D(u%~Sxv^kx{`sF0zr-K$yV3Wn< zwwK_Iy@#MBHj6#Zslh|fM?ja_ESB%sfEqf%f_cAe7EABfCu|O@4Vjb8f?qb_pf)E& zZ>?&uE7xM%nC<@=HA4V-4DdWwS}wvoJ>KE-rtO%`(=8Jd#&z( zJpyS>&&fHgf!0|Fpn3-rH|MZ~+*#OhWfhLOk;AHzip96~pRwgp4$IK$DEbX*!EyOH z?ApX(!oio#c(OHz-FJ8+EU*29*~4?$3|$7#M!&(JRk^I$<{Atr&qt?oxoq@3C(ucW z#6eEEY~m_}Td{69 zjGnYvlslBiGId&@dbGRR5tBT2vReaa?~W2w!t>bCv}(|G90zGH^4Qy|A{Z5Q9Ev;V z)B2?GV3lbF#WV7mZR;a&@eGD5+w$46vircy(%|)teAXv>8*Cj=PHQ0Lvuce#@LaQ& z>JjI&S$E9^>-t9U{+Z9@?G2yY2&Oh=bOBTUW+k%ZM)1-oV23XC!#Q1Q;r+P+wxon= z>{yk7qDujTRAVf9mkP&H3s~nwUu;tu1Tmjz%>Qu$I@Vainf`^uU@>M#9fj-j3)#U* zHJE#04454*q_yN4aAq9}<17lrXj$Io z0I~2Xi`WDB{lOdbm3zk8O@ApiP5z8`#y?|!mG2R|^>4;W%bzg|eS6Wzwox{Jq{gm8 z_>Mn*;Hn)4%*XbU&?Q<8sjqkfBD)9vfuchbA0~4s+ayh zHCO0AeRrE)9qLN&3DP-4@560{Dylsw)#Zx^z&)GyGX2NFJrEsKD$}b!S%{fS-{H@l z_hh-Ai*rAKRQG@6CiL>Dk?FQmhr_wH6*7HTlV-NvN?V1 zLxH=nsdHP|_FwZQWykqFXSsT6Hal%F5U-5<4z(Mz*^~9VP^ zw>spqT~^ny*TyPjvAN9q>KttQsR@C$Z_8$D+T_7o(CCCGV%^u?B@O zHH%qoB!6zmW0k8SghewHB#q}u|C-;uCNPC*4O7D9Ufk~e}eNZDJ*%7 z0e0>D0@MemvZXqnSW%Y_<#STmu-(yUkrWDkyHc6K{6ZA8>|p)%R2HB177I!)gQ*+! zC$*Zf$8ZJ)$*IgcM^3Wo@@HYq`&2gFS5b1I{7<32TN?AEb(vIBj)%uiPGepH3X;9L z9^(FWX>5$wcU&=C3Ej`6v8+?H_F&;=bh1uknVnwXq_qa9$6$JLOJ|BDm+?DYlej3IO&P|pk*+EDKsvi~@v|64*L2=6o#mGN zDGGE=gZ$H(=hNeA?sQGnS?O%%bq~RbuIc`#bT)Z}611gj%IK3p`_Q`IbWKTW8O(ew z)j^_bGT5HMzUz3xD!Qggx*05bcQm|D48`wG8LZ!eLbycN^e`ra%}Rd@Q;RR-i^>e9 zyssJ7Dl;tUkjdh6D3AQV*n97wsFwHJ+njSk#q2TX%rrgQ9F94lV$NB_obae%7PA;J z2N1yoB1~hz2qT%s{%{s;KJ@WYrf4y*Z$Ui=YuRENmxN?9CU>bxZ}pgNln=oT;bzObJkXB%IJ56znYR{xh^$DL|@?xZ+5e^l$u6=xWadQ zb`9MnHCggqHTTc4+GqK`l6E3a?w^O<&ho+6oyBFjf8wT{<>fkhiUPUf*%t4!{PIj+ zQ8+1@H92{f$Mz2wpCW@<-bZKo=q9luVwg7zN_UROU3?`PKXPM9<(slJ7C4SGTA6*dnf;<42`e8%o)U zET7Nu&65&Es~gTDUD5OWTF!W}Olmskc%DZlMvLlhzG7tm^V~Z!SX3DhE*j1`&xZ{2 z7C}@JiCF&o8>!cE?2U{nD#B{;m!aKSb~_xqp1!d@OePBe{$8YHArf z)}wwTuP43Ad&`-1a*pI3<+(nvlP4=QE0WhpjAjW^Q^>YR{zjhbSEQzery{wxJl9(^ zjb&BiBYD7mH?~x28l5SMf0F0=cByGdo{ z{iLSNE2GT)Q{wP(ezlmL8146iHI|P<35{_UJ0>SGOUiLRzP+a?ojacWD1L&snc*wC zeTrr~tta^0e&M3;#bD;z{{(N^I93cA;mr!oJ;9$vy%J}i$mgH!KEa0$NfEA9IO`B` zf;W_2ZCILQ$^YgA&mg_3^0S-eXm0uWlJsgwC)dzbbw7|xepb!LsErp1lIdD{-2Y@^iFp-(u^ zIa59-Iw@Lw{3o1O?;p;5qk_e$ZQ(q&aV%RaH4O<5=lw6fV!s}{iQP}b`Kci(Y(*t5 zw#d({x=F8s7ADySRy)n}NUypjce7>cc$y!PUU`gjb+|F^G=C!Z&(}#lmT9X_^Y3#1 z1eUO4$AV7t4AQIV*PPkm+oySVd9ELmnkLK7uZGHV-9>6DTIvk%5EabarKXq08D4$3 zH!CamwCBJxyyRmywnb{XIPVPKT9LDNQqwu#GyL>?`Fwb(Y4IibSyoavOJS+0`uj6H z|7_RLLsHYXJZH`QGq2V${;9B?_#yYtj;_aewoA@p@{~ljY3eZ^*49(h$P>@{Z$8Gu zr}+x6&(SQs{JgqK-*6FmDVSY-aEuo*V#Uvq^0)ne9pfJ&Ux|({+*nY#5FRi%MKr9z z*@0Fe{F{8H_lPw~mWiW7_$zr$f0o_o~5Sj?|R; zPbgnM(pwCYnzn2YJ?l3%uQq*B6v3GRo7}< z{8%V>G3nLp6-lr$P^4g6R+I5&G4@wb9 zwK>ak;V?ff_fNUa@|ybkFux+bnpV=uGBwu`epY&w_r|!;mNky>R?@5C1AT0-J09Vq z_x})f1?@!TiAQ+;sfnUPq_Zfu{s>Rb6ECJoO)qRmxcirAu~lkXdjAN&B|n?3+9zD} zl7I86J=$A1SYySHQi1%#D>q@0dzv>3U{5#iFUshLY3Y-+Xn&NSl3u+?9OtmkX+0sJ@6>sC(rfL7oFwjGe`M&d9HVA>&Y5^J<6ZTbA7-xUv{TNFfSJ!%x+3e ze%4?1(=v}>Ua=-;v!$j5KEb?~SCZwO)YSH3Fu#`H$?`;M zdiOS%cS-LWdQxgSp8J@&e>&In)kZnCe)loHL(hWT;NUg2U{OfXw>-;c*Q#)|S|y;;MbemtMtKMwEQ*p#ySc}ux} zyy|o2+HyZ%EWPsEnPjOqYCjK=UhS^#WVtQ>CVo+Rbz%LuP@jPP+(mkI+1ba|HfBHn zS9;Yqubo(uxSv0e`{%?tXW>!UpMT36FRn>Vtu6jMBw4=xOz{{wX@7p89v2g&ruEPL`Ni!?w)Ij|pX>qrVPz-V390E< zwE%u{?>L7@sVSy?06*N@$1+4}nm8_i|DDf{-IAJ)tPbGY&pR`JscC<3fPB!cClgYW z>zx2TcZx3?Ej1PR9>8n&4rdQ92a6{q4)A_Fmi3dG78(cm!iZOF!5cSme$WBFbx;aB zUzf|Dc0a)PO0V8*O|s4NJHXFMuZmZ2vQ>;ez%NLzjvXE6ko@)l?rtBvU z@~`q--zzm8czBQpB)G9~sp)O{L;PVK`CMG7=|u(ky0In65+pV4|N9W{Ue?JHB{g*% zdx#%AJ1+FR)Kqf$A#?v6JFttt%wZ>X%l&ia>MrgU?kuj${S)?i7msV{DeC8sXLF10 z=6xsmimIv6>@UaNyt8w-xO*j-ed@DYeij-lwz+t-4gc)sH803}jgM|DcE@hMWuSb9 zxC3Wb&h6%1rB@I4C0V>)?dChASJfPyEDkyM@T=0REd9oXX05)5uaRCY=;CAZ@34ov z`~MJ8IqgKk_&t2*v_#SEw6l2XwTCC?ix<3=r`Q*|hsUQxi(^t#`+Ix%qAS5-o780g zeGhNq;w^qjO{Yrk<^CVs#BizUXOq3WZX+%(NKGk2_wvHNNwxt})A7Z7`I<&fw!Ko* z0RO$b2%c}ID!kCK|a?f3C`d9FM53TLDF zK0Z&L>x-qPJpK3a-0!7VQd0-_eSCTY&Wg+Z(|WI*vpdN$Q)_oedTY2y4iK4_wXVIe2HvS}kyf`T}Wp~)d|4oe+1Ei({y|?iTSA)d_scDwm zHokwHw@8(m%52@nBa__33aP1o_%=SDaq*YjKhDp#@stBew(3$-$!y!@XX8$`l~Pl9 z)$P1^{c#Srq^4Evw)4L2eJlY|Q+=21ym59r_C)TViL18r7bl%r4XJ7D(e2#6r6=1b zHPw#W&Vwe(`)8@?=GW~!tYfrZyet5b|aR-!1n~j*dQ-KDl@DGjjhF z$YIAe%kSo;lU^M<<;=XCc5+vFuFsH~oTu;P|i?i8Y0j2NmA3kzjpB*`;#m!rKYiMc5z`iSvE^e`Nr(x z*E^02y)HF9^4w+aA3QgFO(r|xCHK$#E9>|;;Vf#(XNCXsX&ukr+*2gV{nN~DJ&%>o zc(=%Bg}<<@=S6$S=g!M#nFse?&o4Q|ioa!+qt~qUe1m+(d#_|SwsHGJcd~rVzJcGDUfufa5*k%?1HUD`8q~ta=F)xxpCA}|x zJk`}(WRd&Fy~IYo?~9v=keW_4mfzR4aNALnpaYD&Dgk-ur_W4SCft$VwX7s_HM{}%K^+{n9$KMHeZ_vHS$TyGOU+T4>Z zlA2cc+{DLE@MXuPrUo-N@$Egr*&eAWv-c+6#1hN)Nlp8XZ{jKP8Sg2d-NegBn|P4? zK35#)B0l40o>h7k9hhX>TWK?&BfVXp|F_gC{z^XAJzZ1I zJ~dm#FG#OO$!E=n$nWqEkzTDI=w#`$L_W`5dQ~~nCA8Z9RXkC8b;9tm#axo((yL_| z>_qMltN2#Af98Zbi!23K^EvXl?&X_#ic1Yw^QT{@Q}&e10yN@yR81F4|@U^_L+&?=~+(erJYk6hq)#1im zG@G}U-;>XE4-8GRW$|6h$4akC^>MQKN3G=#ajrjbahRE~mOqvIXGT*WOQ~F5{Gjye znbg#`mKX0Py^4^UdUW&RWu;ePQd9A1UVM@~*H=nSCpUTVDe_#uD>bbUUVNQA*S(~s zI`_SJh7>n8T51~q%Zq1|8P7IS)9CW+c+Zd|%X6uzX6to)u(Ok8ywr4k)H*I+xr9ED znszN+_y73&;Qy`9m;du`CI9K~r0!AOLs(#{$_g$1wZby3RIduWylKMeh?#0=3dH>6-vJ+UhJ#Ug&`|+z2FCN zG+TCttdQ+wvbbb7!-A~Pp6#jP+`87G$O?74@mWm&e9(rhQ0aPa#1_A@Dl0Vqr_IFD)v@o zg+_kgZ9CHbi^>YkC>kHq{y?hA3Qb(J$dYStvdRkOcge$||9-EsLiJnqU{xnPR#~Bb z{g$!%9WM)Hg_d9Slg~d27RUAlXu_mV zY(URTHe`h+I;XO6?{9`8E0nS%h56QKVnJ4D&exA@$&W7ozTP*#yr!ZuNYQKFFnx}oL$_nj|jj{dR;*-h>Z7ozsbQt+cWrgbaPZf<*ZmX=2 z)055O$+|NPS)tGEj)`0~{1~!A!7-P`!5y9qSt0wIk45laCx)z0YtQ%MLr^Y;tkBB2 z$)aSY`4(h_&ibW_ul;j{A}e&F;ujG++t-Gy(59|?|MNy=g{DsQw`KbF zS!IRtiE5#@<#(`<6>`iw*OIg|S!IQM&g5WuZ@yPqq2pJ&GM{GgDl6o9X(>C{KSm%c zRDSY4_Bi>NKvw8p@@dw=&s!iXG;Qi_R%q;Wfviy1oUhoqf9nclh3e$_#1>q*ZbMe6 zf>l2I<4{s4vO=?u$@98t9SgETP7@N@k&W*y$O^gkmD!QbO;lEB>g5|Oq_>C43i-}D z!Cn^Hsj@;|jd!yx+rv~=sPv8btW5Lk3|S%D(Uz=f!)GchROIEqmOSF4$_iaC+{W^9 ze2U5nwXAtQbkZ>SjAxk@+A=)Cw#N69$_jzpTv)R%E8E95(Jlc*7X zmLV&&J!`Odzi2;0R!AI=7LIk6Gh~Hg(>)gbi#s!9g$n(8C&u*4$B-2|W+aO?vpg-x z3iXm%pNi9Vg&-?5dFmI@JKGK$vO-fvzZFAA6jxcHCi@?V#Y+dNtdR5ZC~nJF)P5@_RWlE7ZHu64rL?6@jeKy+Xb$ zzEP+^RwyJgoINkKRUj+$X>Kg*8R{mG6)Mx4&>fN;=D`YK|%Jw*B zvmq-q@KFl;+M}EWS)u9AQ(dwOFA#VqAIgOu9t4I*vhbnUQo6s&3T2GFC^ElZsj@-?F9wP= zj{{Uz=y>#c;c@P~$_mBKauMkl-c?zlhqWt-=8g#}E3~GMuq|)@S!IR#R9qd}Zb_=j z3e_?OTY`$DsH{-*$c${=gAXbzbS%c4SIr zN5>VkAS?8`TM`S3cw|9V=Lh;Aiv+;gUR8}amYbG}4#0QlX+VyFeC4Kf3l@+QUxg_+T<*6zw z^u|5ZmU+l$l@)StS5XugnxL{m&3wm-7pLy3tk6i8^&(I13k+GI&C>(LkNO7~vO-R) zE{YuORxxCSnsi*lGAuD9N_f}lnZ^w`o`Y4}86Fp|L1zDkQ^8RRHw}Oq36^hJ} zEanwkZ9`V*@3rs5+Y$v;R_OYGN21V?-YP4U@b;1j>$^f_g~k*(DlRPbS6QJ0$Rl>VxV`y~$_f>|R8<`DdabfTZDUT`&VKl$vO zWrYe(`enJ*_oK=REpTqbY`dPStk9RN3t80cYXVuJGadG@+Cf4fE0k;4N%kfE4uP!D zzGXLAu5#`IS)oh`&zaTNDv%YjL?*KO*`?0Tq$_mv#8Ow^joT;)xsRd87L1(t8tWdA9zHHE|5S11B;Jt)x zt#U9R2|%LkPe3VJ%(viwT2$_mYC<{VmSORCBW?Z|z^Rx9kY z$_hCjEGMdDd84vI2iuGid3^7wtkAPJUSdtH2!^cCj~Yir*+mB#vO?dcL<#H7)eKpo z^phTlMneWOWQ8`gcq>+Rv}ec)r62M|TzRt7f~-)EL#g8GwNs6d6&l$oStE|w$3!6l*sb^JIs7Ce4 zVs=2B$_hOmTvIGdc%`yJ%Ns}8ny>t%vO*54qC?#Vq^hjYlYuQP5wqmyr!p&aAb+Z5 zSlmaI6|$Glo?AKmnaT=XA3L9ImCpf0R_OclU2M#|FoCSl##$%XAlIGp`6xmB{qh^k zcG^QAE5vI&XW_M*3S@<>-A%&`ak?@uBxxhOE$(HTT7m zs9_9Qp<8}$M5B+T7_veG3dmB)>)y{ zI`UU3Ua725?L${>d8>U=S)q%a5<=^=OjTK-nv)w?y6;a>S)o-2K3ZCIPE=VTpN>u0 z`-;z1R><{=2b;X$hCo(mjN4B6Z1xiZS)ubOVJ!RIT>@F5+RLu9S_9?_WQD$tea1S5 zv=GP&jk*7kmA{cLPS$iIIoOSkN@1F}LHmVIKLv!g7?3f+75iZykw zsj@;V_QbKCZ6>R%(A=?SS)Ci3R90wP#r>?<5c&NpnH4%0zKq%DxU8~57t8i!JNRRj z6}r+rFMCn(y~+wT9=yb|rAxBP3Vju4L+&0-Rav3*<#ySI5B#FCLOosV#p1?qRaPkP z+`(e!mrg3GWrZ3nsc5m@Oi@{(*R5V#CZ0=FSs{Mj%5FS;uChWm zYq_)5^KS}dg^J|a!S3`vDUcP~c0#b1P4@_7g{CaJ#)f@eAdnSm>i3jgXKe(sLSF~U zEPwr9He`jGbx2_=uXeQ|D>Q40e7?<%Lk`Fa?R@)*IpscMK~|{r%GYeg>#8a%lz#0U zb|q=N$_jn)I>)y5+^DibW9RrY$C5`?R>-T<3RX1vlFAAtukFo}hCfnSp&vgAumT(3 zsjN_|yQ?fEawn^-P?7TXA+G{cRaPjY|7P2y17B2DXn&NQ%;LONS)r;$28ds69;&QR zVdqsM`y%;lL75eDXmUUVxdbv~g@TJ*5J3aiGh~G}Mcfq^myTt~3jH%GL42%Uks&Me zbJ%Bby;-OQS)r^eQbkJiVh3b}s%A|Q_7jKOkQFLv`ydi0WKvn7GrOLMi8tG;tWcBc zSH<{(i&a*rPDz{CSHwqUg@USV6M5gCQdyyKg=P!ym|H3!WQDFaNMIv7RZ>}@*0b-j7MomDRw!1S zXJhWHS6QLXw*pwRTY)Mo^y%J8*5=Vgl@;2Op+9@K{GrMUwcb;NZOr^mWrb3@Y_z;N z_eEuef+Ke}oD!6(vO-hqt+icA{-Ux%Kgt&pBSybdS)o1q`iQ*cAE~U+tmqZ;Ug#1- zR;ckCf6?t&5JOhTC-Iy(_Gkk`R;c@fJHqR^D??W3?b+Ajc0?71tWe_|pG89ODGRbf zZ`@Kvf}4*6vO@W-DI&n5rwv)5;g*l0_}O$SE0k``Q<0pSj-yppsOZBBY^U=&ofWElkXbyB zsI1W4VXN8E^HC}*(E;4NGK>Pbw>vy=Xn=mid*+3Kdv9oedjzTV;iUg1ym;gQeyp-WsRum8k@J@svO=pJ{6zDn#~89g7q_1g@wYZJ zWQCgjx-CktoXU_DDmdFu+H?HIjM{eD;50a?S!X15DPojfBlhSlGD zME%}Zzo=BCKA@uE4Oi{{obiVIwb7X1!;DgLsnXxNnD6$E}G&fUltc5#=xz;DDg z-;+7arHG%vZ^YT0WE{WlJYLX$Fv;Wy&=_r;>Yl00Gf zjkt+33^6{sNEm)2ZgRgXwx_@B!|)q%bCTUd3lu38hTn*L6|~$E@K?z&{6^gII;GgR z62;VS#MvAtvFl&+tKWzlb!aEs@;a;fjX0Nz7g(4_vcPY|jj#BErT-Ww@EdXKf2DIg zlXy(vH{zyl$mMu6dX>O$#0_^T>^L%KCxPFHJL_og*keGV4Zjg5-jsBldLWYxzY(`$ zRY}KN-FjN^8*$D5DlVUinw#M_;gyA>hq6_D6>``Ge!*9fmzx0h|8+wZ2 zH{$aAddTA2JZAWfxG67Buulo!8Ga+~=_>H)6(+9BE9}7C-H{z!4&Ca^^ zD(;Bih|52GiRDYZl8*R|xIdol#eYBBOXW>|Kif-XJ^pw`82{thVI0re!ZWv!ANl=k zFU5a6gN*-vwwD@rEs*iA-_I<=IG*iA^YLsisw431F4UCu>6vIaEStpq{{74> z^?(0Q&J(%zoWVX!e=V@a3D_WM=iVIgx z@Ay9Gh4TGVtxS$@n?;49&Yn*4d(A87skN`Q|G{pYFU~N2ro>zJtG27+wBOH6`~A%S zFTbDp|L0swyT<+Ry~h1{UzGXPc}w~_CDi>-^Xbi5mf=Md*Id7n{d|#2ajBO!w&Kw* zb)SRlBcADrdl-5h2Gi>^m|nNR^m-1a*Lg5K`w~po1u$OMQ5THs6^{3N9M?z1blt%? zJ^K<&*C{Yvzreq*k4isX?=UXwsb^n;aUI6-{uo#HY`^ELdo#MuV$SdSYW(+c!*m_} ztWxlAoof8|^-=Nfbx6x00!>iq7T8vor-(xaYLiaEdgug1|Q91r6-*8eTP zbNlD-_x^dGpHOp+u+)!IYtMFVkm$Jaf#S%c#l*5jZxy%P?rpoW`-|c~_y2#F_XYpe z^YqW}0;PTDC+#~wY2W!t`_50=cYe~o^ON?SpS17%q^Mo}-uc9KE#X=%qbJFYP&cY0uG1dyZb( zbM(@lqnGv^y|m}(r9DRv+1MIs&(ZsD^&GuFvjG3q@66->raeP#DgW>I47Ie(&OVj< z`0tY0`O_~j&OPKbDWe3Y>=KwVO<>A8fhhw8rfd|LGE-p6Qh|SGlvED)e`SXE&oxqZ z33@2g1pb{VQ~6fPKw+G+QDDkUfhkJ`{+%fc1OKngTqj*WVyrWY7^|?PrFQZ|XVO(B9P9-O1k6 z-@d=Sxh{-vU$57Q`6CBtMxD*oG^2jR_sdE%j@$R9X6RWHq!~I#duxXN?aMS{UAq@) z#(HTSeW3a157j~6s6P5h$3>q>5Bg6!;S1>}zcTL*G`;(OGx>;d@)1lvg2_iP`3NQ- z!Q>;Dd<2t^VDb@6K7z?dF!=~3AHn1!n0y42k6`kV#?c3wkN$wkM=<#aCLh7%Bba;y zlaFBX5llXU$wx5x2qquF!yJ|-LB7bSdarb|ltJVTN@pm;tr|pbp=zkZa8S6?qs2S^}arA-a zqd!y!eWUv5Cmk1kCOzms>4Yz&pZtQ4|B1;*%po7a;Dd<2t^VDb@6K7z?dF!=~3A88zYp!w(zn0y42k6`i#Q@@&(5j+4}ELd#qT=F~+~^H6LbUjM_1p(~lWr{7k=7&G8Bt zV_d7PdGwDlhP9XGe0|0mS!QZJaAvGgYmH|6Ixfc79h!gcaxuQ_)%>K;ICH$yym99I zw+Z9SI&0dvn)OF*ay5_p{jRI2r+v=xrp~98$D8`^)*WxI3*$v9=(S+}qj%fYT2Lpy z(2V+qr)C`Y`e4n_lf9W{=zLs7GxQg>*Nk-)FQOUirE&Cu=A%DU2YsXZ=qDW)eI`BV zKk0-oq@VnPkN=6uN6aA~!Q>;Dd<2t^VDb@6K7z?dF!=~3AHn1!n0y42k6`i7> zaVNJJX6iXVd6=oQ&zfPT{;pewnd`#1Uw^$W%%50EGwSU5v`noL^{<`NjN=a5q8WO& zxM_yY$wM?l|2`+pSl5A0nz3FQM;~ZD`a^ZlH>!_*(s9ve(u4k!PWVFl$uIc$pO}2a z9P$xNK7z?dF!=~3AHn1!n0y42k6`i;Dd<2t^;6HsV_@cXf-!w(-y&NCA z8;uK1RlGBI4c5z|kGU?4Pp_@li1|6rOjg=ZXIyX1s2}-#k{ZWx6a6(qPyf-Hp))tr4E<9} zXvVtc7SN3K(m47+^U)uwgT7IH^plQ@K9e5wpLD_((ocTD$N$9SBj%8gVDb@6K7z?d zF!=~3AHn1!n0y42k6`i;Dd<6gLW792Jji%|=sr}~Qlhvqa(HwI&t1)W4 z=F*?D8V-9j2R6uNL)Nh(=J%azldpJQ@Pv(DjbInDZu%H=YTTYP9PQ_mQ$T&B+Sfw@fmsbRUybz!_y zgqPBW`9)W0MxC~OHKYEt8k%w3T$wdPPqSxh)&GUg;?bI+zvBtbSXZ}D%~&suqYpG6 z{h>PO8`VcY>A2`K=|TTVCww9O;D zd<2t^VDb@6K7z?d@Si@0m&s@B%DzwStB|Vs46kOIJGRMZT$-VI+w^?KrURPmhs87c^sCM^9_UdTAVep!w(z)j{8=KKe<=MW0Cz z`cFFH3+X4n;NyQ{@)2{$M=<#aCLh7%Bba;ylaFBX5llXU$wx5x2qquF;Dd<2t^VDb@6K7z?dF!=~3AHn1!n0y42k6`ivZbd+X%?)unW zGd_q>5Bg6!;S1>}zu@D4V)7Al$VV{w2qquF;Dd<2t^VDb@6K7z?d8b=>!KKcVDAHn1!n0y42k6`i8BcFA~oALpK2H> znv>Q}HTIW2s{ZfB#Hq%lCYl@cnr3)AYu+6(%@{F4^FqsXWAIqbqy49wg3c zzJC|ZIBw%AnxSWEHqFr4;o}ii2l_qYHDg_i?rX++X&il^`REVTLEor8`boz{pGgn; zPdecX=_kM7<9}lE5p&2#F!=~3AHn1!n0y42k6`i;Dd<2t^VDb@6K7#-B zv3{ra)*+)3)LyzbwY@dxF3nrtwzqzb)BG%;gLOf!H+s&Ij#hg|&8t6kvUVM!x%tR0 z*2H<5y)$*Qe)ZN|=(v+LaKGj*?meu&hcvHjfe+7q~oH`qzC;co$!V9lV9-hKQZ}; zIpiald<5gT@DWTtg2_iP`3NQ-!Q>;Dd<2t^VDb@6K7z?dF!=~3AJv@SK7z?d8b=>! zKKcVDAJv@SK7z?dF!=~3AHn1!n0y42k6`i)3O8&kt*FxIU|^ICje4M%Uui6z}6LjSKI}D}H;Y zu@T@^QgM-~7UPIfRPkR;>l&{L7E;_`LRDj1z5I&5G%06{4a%$d#k*q0hHaXc9?NeW z|B_FQZ;Z=sTs&A%amAGxj1Iweif@-qwdQ>zcS5@Ps8a}lC z`?ZeZmS^u;-Izy5XCx^+S`#qk5~Th|_GtGK~|{Dx(}zP{h+P{7FJ9-_t*919rP zmLF5xI!ghg%jRIkn6qx+HN_j-XEy4^-&TBVMONc=gyv?avKv=sX>NEqr%@||=5_mW z8>joks`($9+nbgYzvr>rYF z#HsOiH+`*3R^3tT{&JP|_3nF$R|ZYBy8iP}&+(ei7tVdFIPZbM{K&9(ihC_+$_u%@ zS6pOAMIImeLGiJhRd<&E^d7NkyCNt!!pLfN7)s(_NXBLmXKAk`|Qfb$Bg|5 zM`@l`y?}9UOldXVxqLxm`%29@Y85g@?9+UTYBp*rXr)ki<+ zxac$KLH|i7d?EemQU(~0-s@{q)A9q2?k@UVJLoge`213H>wg9r>HB0+`)ARP!N$)s zn%8F?YMd#d&(kHo@^99|G@qO_!f^1`Z0SGBD0p0RLFX|>`3TK#ySSL+Be<(Me@nIr zW}Q|0CYtrP<(+IE_fg#`rk?59re$EyOI5>=1+s&jnphr>hrY=f z&pfW(;d!Q>GLiF4opG`AO#PSd%`?}9aa(`AF3i7JNi*s+{;cnpP~Y#oW*m3oR?X0J zW0q#q>5Bg6!;S1^SvUQ44)9HlLK2I?^r)d7xV5;$=!bvrM)WWGo$&Q-WJ)LSCAE(*B?KI>3Ld{D;ry2jO z(|o7ObYtRX&6T~Uo8wus&oJkg7(c_T^Y`T$X8mI&XPU?T+<&I2C(Fv2rp~DWGfn*i zkIgjKh4Dr9T0iD*e0E&vN1fb9G^74h56w7klir%4XQxFobZ#uG8Tua=(2RAx$*mdd zrE&Cu=A%DU2YsXZ=qDW)eI`BVKk0-oq~C7KNTcF<{n>bWpOHpPjOGbvM;a$GYYp>0 zjWpW))*N1cl<{zc9q>5Bg6!;S1@%zqyaO4=?QLWA4v}XZo1?woOtWb3ZSv*Vo+VpXT*7_kWrA zzUFz+uuVVnd?|FSpLre)snp**zk)XQH^*0J8DP%$bs1pRxp8rTS-+|MK=ZhB`VKVp ztX?+I)R}(&KvVylpn>MPFi!gu^J(9r4((^ur+tp&(*B1YIxnD;&KKyX^9bvr^9$>x zarA-aqd!y!eWUv5Cmk1kCOzms>4Yz&Kd^9D^L2hp>8|GMe=ciR^SV&VrK@?p=zFlM zc^!%R+10$hB=_lNUUzbx?Pgw&5^6h{*D1>`C-eHXq+oY*e1v;d^H9_31i-!ZYT3T&F0a`ynlQCsFQhL_pMcD^M3En(az@mVU>zq%=^RX8@ia| zJu-JS=evyUYS!5l)zz$@wRku4xGm(`>3+3`XE#&lg?-&j{f7g)nd`zh-Ctoo-FKl5 z-H)L@-KXKWbpHlDbYBOZbiW7vbRURy(fuLTOXKJR%}0Nz4*Ev*(N8)q`b>Jzf6@tG zNI%Z6pLROG1|NMoYlgq;7HNj>Wx_OLKOB3l8T;g2ew}N>{#jO6GxpWGwwkfuI`q#4J#K2o>vP#J zn(?|_HMjm860he^>^0+c{&pG7c>SkwTo-6Qt`}4X*Ac3Z>kAzh*B#P>>k;Y1b&B-k z`bF!)_?w-2jhO#^v}V+q&`2}t-^->M$KCT-e?|&DS;93#=MP`a(BEQ{W~{4|mu9S& z#?c3wkN!{{^o{DHpLAUGne?Flq!Yf7e%v2=Z`3`+eMs|bnsI+pH=F((822qF95v&9 zrrT)ExX)R-Mlfn74)yMlI zIxgNfksiFCBAs}jMf&mni`Ip4+Mk$D`xbR*KchbFa~zlUKlIRf0iATdKtG*FSQnjN zSTBvE4>TYBp*rXr)ki<+xac$KLH|i7d?Ee#e1l%+hgF|rzW(F=HC-3*zMHNWct1|p z5xh^Q>kHn$({%^$>*;!g_xp66!sh^V{le!1G>*?VXg)qqpgQ=Rf$HP)2Rbf3mmod( zyn=M%a}2tE;qwhz7sl!JAM@$DfI4)&Kz+K7;J9>sfgZZsB4MPlDxdy)N_6p2 zhJ6doIr@$=0w-#o7BI?qwOR9??4ylEVVcEw`9AT6=8X?W8*QFwe%VRp7GG*^bb5?A zUbvQgANqTKwe@4oIz2y)HS3>m?qVJ{;{q2`Pht7GM>-c=cQN(5-bemXuLa{>M{36W zA$2sPPTY?lYVD}s?22X_H>a;==o!0EGjt9ary2VF2WZB+j`h}z_0l-{K=aWbs)N2! zee{!#i$0Sc^q+LX7t&v-K?4KRy7~7Bg=;?0O zSt#7i`X`>ao5$^&(Zkd;)ZW9?S+c5!slPxi4|81@_q?t@pU3=yA(~OA<5tb6pK+mP z9QWk}&Cs)PkY?yy+g&sCH|nSv>pIa+GuBJv=mX71f2a=nM)lE8IxhN5deDE;313LR zXGeLTTqc|P`@&>rnYFQMem+(?~BgpBd$B^gpe+z&&Rp?yTlP?PZ?m_jqH`%bee%Y;UuU$L!u_{f{xd&EwX{ z*T>Y;xJe&V=b?UmO#Pci^fA|k@xht&aWVhREB!Ye)TwYqGwR7vgG>$&deDsIvpl?(k{iNff&!h+aC!O$x^z*>xM&-gy)N4Y$ zMBiiMW#?=4mS{rj+7;mw=vC@h8x9e+09d_AJZ6}@T=bdrp#P*3zL5URml_$7*ZL|w-)}ZD0-E9H}%vy%T1jZ9&=Owi3D!0 z3**lR=rv;gw8TD2C+gf?q8at;SJ#Z=_P^I#&4Hdvn>0h`%u$-5|7knTSl8R8nz3FQ zM;~ZD`a^ZlH>!_*(s9ve(u4k!PWVFlhvl(1eua)y+WHoi-*vA#O7W)#_D1JTnwt-| zH{PWit;S=0?TxklH6KW|H%1@Q+^t6mNw zb}*>Y5zkHofpta z=L_`Hd4zS*`Gxh;IQl^I(I2XVzEOSjla7l%lOFV+bixsO<{ zo?Geqb!Yx_D_y^SW_@9$>sNr^3oBi}Qir~@()FuO{a04He&x>p+Dg~28=qfW>H4)f zF2Nk18vMqbe`x+&v(C51@67ss@$byz#teOL>KT9jy{U6+x(}v)&q5!}bzz)d|1qDg z3#dca3)H9U2#!nF7wDnu4s_D>2>R(dg>}*O3+ttE^nvE1KU4>Oqx$G49T$BjJ?KB_ zgfFBY=htHA^6K1&k7F)shQD_l{!-)ced-R)*bgOsYQ{cE>R3U|!TwpWN;CFVY`A9Z zH&G|H={^!85Y7UNDa!oq@f##z>R0n;d z`sgPe7kwr@=s)R%FQgyWuPzhplm@&`)_7b&LZ<8?S} zgl4=xcl6VY*X`|hG~@NWVTxwF&eup^T>W3X{?j^pAa0 zNX^H(ro?N;dTAVep!w(z)j{8=KKe<=MW0Cz`cFFH3+c!GA?-ulhtU4S{R!<`+_%tv z#{CTKbKK|9{>S|fofo(-qVom!OLQLLK8nsS++Wc+?z?C{?#HMO?$f9~?%(LRxUVBU zxZfk4xDO=#xId(IVVw3S=F`4K9oo;RPx~ClrTq^*bY4IwoiET&=MmOL=NHyXDrJg61lzXZZR8U)29y7Jr^MsHfRlJc=9bG}l-X&69g+_A7Xmzv-{J!nPacc#+(< z&G`{6@0xY0)Oujn-w^o7Jnp>X@ur@F)~BY<^_8EQ`kzgEX08k4=^lSlIx#=LpJvoq zI7Kt+e`uu{$F-Hx3_ZnvCaM1mo%vsAhW=i+HDg^vuWQD7X&il^`REVTLEor8`boz{ zpGgn;PdecX=?|P=$FR=S-)-KqqK>h8z2;m2b&TwRnoHfUW5it2+_z+1qu5i;7hUQa z4N^2GU#x4)&#J%UnyYR-V@W~H3ES%#&x>nj`Rf}4N@`x>QQsUN@v*)+|DT=>%sTsz zHZbekWo~F5w|lFGrk)W~8=5+AuWe}RKfSe~xh{;q?x%HP{={aQQ753XX4D^)Uo(!| z>PG?fnGf_Nzts$#Nsl!{|N1+cu`c`Dnz3FQM;~ZD`a^ZlH>!_*(s9ve(u4k!PWVFl zow`;vX4TT)Pd55iHLkY%{k`QGRgE?yG>7|DHFCRa{+UqKaNekStYbA}a)9QI8><;- zk83{otC|rRsd<@8b>pwAn(sfXZfv`*xmxEM=6Lp#HO%>?E7UaWwD+iK*0)`+X&yJF zU@cQm_7=5Foihg2GW8D`Q_EZz#w!=p$Hn|3Df)ZYsPpE5X4KztK{JlKAW$>(G}xsX zI_s?04E?uOXvVsFFVl?m(m47+^U)uwgT7IH^plQ@K9in9vj3zLzL5Up(&de?XZri_ zkE@h7@}}3{Z|~B&ys@Z+=E2j-8|@ov-Vs{f*w8_9p6q`aL4!22;eQz!CTi|{`7a~u zY|S+tD;Pr-Xr3KV!FaGp^W~Bi&2fLvist;&NfpgH?>kj8>-X7F$vp0+_)4Z8|NNCr zo%XdVoBA_bDx2%V_=rfoM$G>h@caA!vQE{tno<9en`RvM+z8FkGo`0y=p5fpGxQf~ zp&9Gi)KoLpOXKJR%}0Nz4*Ev*(N8)q`b>Jzf6@tGNdJgdgUs)x#El(fO9BSsi?xc)vvlL@1Y z7E?6i@36BLYySRdtT~=;={R$~t=M?8PKJ3C%=(YTMDw_JLjDJPcOHKAwEzF#R8kpA z^I#5{Qkk_^3CYwX(I`VSDkRF#M2>?a2_+oUks(PrhA4ApM`npcPLz=0ILDCh`~G@% zUuR#R-_`#=UFW~swXRoduh)9)-ot+H{aEMZ^`x_h=XIX8Y_^$K(Cd zTtDld3yL)}&s*DsnZMb<=ZkS3x6SL%6=prpb_}!5Yrc#3C$s*G9}9C|hu;|H{8tzW(t~rKy$L73*B|!_TGnUO2k&vNgY# z>NV?J_~U^ar!F+S=T0un z&%K)-c}n5gf7vmQf7_{PzJBjV_sa7Oy0K-R|IUT`=f~Z$bZ~M#wVx>^*V*9M*2(p6 z_h#$-dN1RT>~v7^xLiN-lzj>_&jG*eRhapItG8QW9{2gB@p~fc={_QUM`N8`S8rQf z!}>d%zD;57>&T^z3v<7YvkzX+{x}c&=KSoZkIO#09`@gLl8ft~vZ`VFd1}Mrd+WHL z8m0~phrh4YC@okR-sJE`>57%%wi6nqcQ*xArr-YejK>INBZ__-?<8ItI%z7TG9%h{nY!GJs$NeWh z|HXZM@UJlU>p1)1_3V%Huy4-Ke)_oVv+H61T_?G?{(~N`l@9E?Ns~GaF;u4r{=GQFW#_D8nZY&xqqE>=@;R%->s9DeiMG? zh`Oogci|e3)y?DI>|8HjU+FLP@;oh8*30wXdT{;xxF20uKdMc|I*5O(mT2{R0Hazy0mg#~ozAXOj%wJlj#V>@PJ7u5r)&t?&->CRm_qOorL-tKO z-xNM%&c1nk+wJ$u*YEqM{qj5~f4*Oy{~!DApC5Pg^Y+i{*=G9wd7W23w|`#$$k+GJ z_r-XPhAWG8a{UHf!pw8!rD5jZ;h`{(+kJ7E_5Ac}n00PYJ3hn9`XAjf%zfRzYnc0W zoPF?m_Q!eHH|J+ReO&h0^|1f0lU!VXw|ec;s{KAK?xoER?NYlnOAF6x-7cN*Lim}X z?b0jPhJT;cF74YdJY>To(wbJ`seO(}eH(>mJ%2C6kIw77V3(uw`cG?qbiOaf zuNxZo$n}@p6=t3-7loPsZ&f}k*2&{8-aE{CF6bO)otF#H)5m3>T@U;3I?2WLx4ocyI_ruLigoUOY4`L}m+(!ucTbBNhG)LnJ$3xz z{o5Op5Ol#W}Q{$hgttquZFp=zb_1PzmBsHUeEqG z5Bui)?5B^*KD!?F-*u9U>wop7j;YzwkBT+_{jHAavb)1OukM(poE1J``%Y=|6h8Nq zPU*ZY!=KIWl-ev`T>RTDx9Xg3TM%w?UgtD*W_Xj&JEu?n8a}RDm$dT6@a->j$>U@9 zJuY8=!%fHKd7k~xae4mcM|I7Qd*&5g^LoZS-Zigt_4{4(`WJoLHQyKG@74dfSSQyn z=oDt2&XVb(M6moV#Gu=SE+9@c;H4q@)=oL$1)ujA~4*Rwy)!@fB` z`|0Dd&#s64cb(+o`puEB(d0yxB|7f1qKl+2_`MwzMF*)v$>j(7?GtZKy zVdg*bmv}DmxHaDjv!3Cz!>n`A+UFbVpL0cwb6@i(gt=eG*$1y@f1HPXbAI;I$7P>g z5Bu*r$;I{mvc-<+sU6~L_~-R1evj@MK7PL)Q@2UsGfv+zEqy+G=ky)Z`9Fkf{(HwX zvr&BAPRH+*jxB|ce`2T9?f7uZ-I}B=P79Bl)+BAb_Ur$f)pyS0vqtTluV1iq=RD7M zX_q{I->Y}Yk9+eQyX5seu)(f*o!f0w@jAxZ^>4Q8uKB(gueTz;pK^WEIbr6xWptSN zt8@lLx~~E~%eteGy*$Q2lgk!{x;_d;P0^+V80FP3;<_ zA!mnQx}!m=c5Qe`)rP6oec^fMH%zat?a-*cqG5V^evJ3(*(i@6^irdIeW$$}=Xox? zs&Srw#YYu?M_c>2yKK8nUQfmEB6*$n4&ElOfAWZJ@_jM>ZtJ)gu3ugy%sjo``MkI< z=3j7En8&^P;xOy^ws)9yE-x7ry1DrfJye;cBazrUO&> zfTMOxH#QD;cyPCLO{MT2+wNZRyX2~3&I=~)o|df+zp~*TdHkNCd*th%e0PsL&&rm2 z=J~r{vS)tW8=l`Yujig0_sr|8zx7^u{TnylE8iF6Zw!lj*R6kwg|JHhr5JX=lp?T)_>l}F!we1;xPB?IQ!uB?2q%XZ_dwt`nc?~>tX+0C%L%( zPfo9R57?FQe0zCVtF%ei@IilRm1;K*A2YvI`tz6Z{JH%1iofg44gb`!l;%we?|6SH zZF6?`pjs)_?h&qd>w4;aboh+#Q|jL?{K#po^Z0cYuN`^)eFwJ5^SpO`n>_#F%iH9~ z9k=Ttc|DU)JS4BP(uhOy`o9@{NWL$|k9$7uh3nh?8fKo?n#KQj=0CMhn8&?wZ6^=w zIdFQ6v(C0phFSm5uZ6j$k&=9x!{` zu)S^A-nQbJ|Ml+`{|D`DV^8dD!}hjed)u(RZP?y6Y;PO3w+-9dR$Noo+h*4#Daz> zY+pLIFCE*Lj_pgw_N8O{(jB)q{*T^!?->)^m*+}g&y~QQD}g;%0(-6m_FM_PWBrwn^e8TOnq>^WuFbIP#ilwr>)bKLXV z{^;k;dA1|><#~?S^Bl3~IbzRq#GdDfJ{2Wo#)ujb8P21w(}g@d5-No$9A534V~xM&U0+%Ikxj0+j)-d zJjZsPV>{2Wo#)ujb8P21w(}g@d5-No$9A3<*R1V4$9A4$JI}G5=h)73Z09+)^BmiG zj_o|hcAn#_)^?s_JI}G5=h)73Z09+)^BmiGj_o|hcAjH9&#|57*v@lo=Q+0X9NT$b zTr(~@&#|57*v@lo=Q+0X9NT%0?L5bJo?|=Dv7P7G&U0+%Ikxj0+j(AiZRa_*^Bh-R z+j)-dJTI{2Wo#)ujb8P21w(}g@d5-No$9A4$JI}G5=h)73Z09+) z^BmiGj_o|h_MBsT&apk`*q(E2&pEc|9NTk_?K#KxoMU^=u|4P5o^x!^Ikx8<+jEZX zImh;#V|&iAJ?Dv=h&WeY|lBi=N#K}j_ov=h&WeY|lBi=N#K} zj_ov=h&WeY|lBi=N#K}j_o)4z)CImh;#V|&iAJ?EHp())_-Imh;#V|&iAJ?Ge- zb8OE!w&xt%bB^sf$K>Mr?Kx-Mo^x!^Ikx8<+jEZXImh;#V|&iAJ?Ge-b4*Vi{pZ-8 zb8OE!w&xt%bB^sf$M&3Kd(N>v=Z@23?Dg~;V|&iAJ?Ge-b8OE!w&xtPe)^WNJ?Ge- zb8OE!w&xt%bB^sf$M&3Kd(N>v=h&WeY|lBSN0FX$Y|lBi=N#K}j_ov=h&WeY|pvl^n`mo{o&Z2bIknojbnSxu|4P5 zo^x!^Ip)6TImh;#V|&iAJ?Ge-b8OE!w&xtP|E|-XbH?pC$M&3Kd(N>v=h&WeY|lBi z=N#K}j_o==0H$Zv|6lf;Gd_Jt^qgaR&apk`*q(E2&pEc|9NTm5xc|TGIcMCS zb8OE!w&xtP9{S0#J?EJ9`~QpkqUW4(d(N>v=h&WeY|lBi=N#K}j_oyux>A>^@b1nw9=N#K}j_oqT(Ldpn03v=h&WeY|lBi=N#K}j_ov=h&WeY|lBi=N#K}j_ov=h&WeY|lBi=N#K}j_ov=h&WeY|lBi=N#K}j_ov=Z@18?)CJCV|&iAJ?Ge-b8OE!w&xt%bB^sf$M&3Kd(N>v=h&WeY|lBi z=N#K}j_ov=h&WeOz$E+%-EiDY|lBKSkd1|&pEc|9NTk_?K#KvLwdbE z=ZxEPj_o#_c)B_MBsT&apk` zxc=Inb8OE!w&xt%bB^sf$M&3Kd(N>v=h&WeY|lBSKbhWjY|lBi=N#K}?zsQI>^Wzg zdFU0#_MBsT&apk`*q(E2&pEc|9NTk_?K#KxoMZNlo^x!^Ikx8<+jEZXImh;#V|&iA zJ?Ge-b8OE!w&xt%bB^sf$M&3Kd(N>v=h&WeY|lBi=N#K}j_ov=h&WeY|lBi=N#K}j_ov=h&WeY|lBi=N#K}j_ogzYe>k@19NTk_?K#KxoMYBWZ#lN-9CKgvoMY~no^x!^ zIkx8<+jEZXImh;#V|&gqxww9N&KbAo9NTk_?K#K%JVW0&w&xt%bB_7Bh~9E+&pEc| z9NTk_`MJyM?Kx-Mo^x!^Ikx8<+jEZXImh;#JMRB4d(IiR=N#K}j_oxnu|4P5o^x!^Ikx8< z+jEZXImh;#V|&iAJ?Ge-b8OE!w&xt%bB^sf$M&3Kd(N>v=h&WeY|lBi=N#K}j_ov=h&WeY|lBi=N$K3+jEZXImh;#V|&iAJ?Dv=h&WeY|lBi=N#K}j_ov=h&WeY|pvl z^n`mo{o&Z2bIknojbnSxu|4P5o^x!^Ip)6TImh;#V|&iAJ?Ge-b8OE!w&xt%bB^sf z$M&3Kd(N>v=h&WeY|lBi=N#K}j_ov=h&We zY|lBi=N#K}j_ov=h&WeY|lBi=N#K}j_oh^j_o;joSty6r#~FqbB^sf$M&3Kd(N>v=h&WeY|lBi=N#K}j_ov=h&WeY|lBi=N#K}j_ov=h&WeY|lBi=N#K}j_ov=h&WeY|lBi=iG66!o8mUaBR;xw&xt%bBv=h&WeY|lBi=N#K}j_ov=h&WeY|lBi=N#K}j_ov=h&WeY|lBi=N#K}j_ov=h&WeY|lBi=N#K} zj_ov=h&WeY|lBi=N#K}j_oM)ou?Dozu5;>VW@_Ke2b1>tFrPm&NtWbI5`)^WS$vn8zJH zG|YP5?GR?2uk9DM=bU}8=N#K}j_oH z)5m3>T@U;3I?2WL+jGvn*mI8UImh;#V|&iAJ?Ge-b8OE!w&xt%bB^sf$M&3Kd(N>v z=h&WeY|lBi=N#K}j_o;joSt*9zviR4g_-A>d&12B&8RSsdr6lt>zUg;%sMC453~Lk zs)o6*S1N_MU&q-8uV;UphkbK?_S45@pIs08?>foF_1kmKz1VY(?K#KxoMU^=u|4P5 zo^x!^Ikx8<+jEZXImh;#V|&iAJ?Ge-b8OE!w&xt%bB^sfcbuMcuOB%z%slt?3p4-w z`-OSjAzOr5&mF7oD*i3&yx^TM>z}nC%zZudbeQ{foPF?m_Q!eHH|J+ReO&h0^|1f0 zlU!WCJ?GquJ?Ge-b8OE!w&xt%bB^sf$M&3Kd(N>v=h&WeY|lBi=N#K}j_oF1t4VKUS}n8oU~2{T=3oxv%3M z4RgPavkzX+{x}c&=KSoZkIO#09`@gLl8fuN=bU@7=N#K}j_oWbwT2sr#by3Xf~pBQ2N`?moCj`sRr6SNHcwN3IxA zTvPhEN18D%{Pr(BQtMjbmn-#5J#Rm^xQ6lb_YQM?)n|qmJa>M7WiihD3!e+~xczPlv!0tS2(!-Nr-oVo-Ce`n*Zm#C+^^&8gV(b^&cnVr zKl|z9vd^xE{db+@;`;45=U(hN$M&3Kd(N>v=h&WeY|lBi=N#K}j_orc(FtfT=^%!o9=4E*hHFY#2VK+OV|u>$ev3e75Vb z^q=d)i&_jzRr>sQyiSua*DqQ1*W!BSsWCUq{OO7?kNf5+Vb-%*+c4|=q-mJ-*KQc* zz8cgCbH9$W4_?pyIFCK&?1Me$*q(E2&pEc|9NTk_?K#KxoMU^=u|4P5o^x!^Ikx8< z+jEZXImh;#V|&iAJ?Ge-b8OE!w&xt%bB^sf$M&2%{`I`EMMhlz$b>NSeAy+;{B?E; z^SJl^GN!nm^(foF z_1kmKeerYS_$tw3!_Sj*TZj2M^H1l5`T4Ww?O}c{UGQ?4pI0ZY4D)mBqZ>yr4L{$G zuNmg&-qCf#{5-(P+W}X{&4>LbK=Ui{kIc7bR=EOMb95^k^`u}=mnESfpvM~4SIQ!uB?2q%XZ}g}$ zKl|z9vd^xE{db+@!usjkx4#$L-;3?<#rF4N`+Kqdz1aRwC* zu{mOM#O8?2(ed@6hnXDh<;M1MV|%%=z1-MdZfq|%wwD{*%ZiMezRenZeH;7wHum*x?Caau*SE2+Z)0EI#=gFdeSI7I`Zo6UZS3pY z*w?qQuWw^t-^RYajeUI^`}(%yo`d;EKgZL&$g$jJ$GF*Hv%_YG%?_I#Hal!~*zB;` zVY9<#hs_R~9X2~`cG&E&**U(x{B6R#cux9vK-vP0I2gLpz5c_vP?B4;ge+R_=9T59>KwC*u{mOM zbbNhy-wV%4-&clxUm5m&W!U$XVc%DVeP0>&eP!79m0{mkhJ9Zd_I+j8_myGaSB80i z*UUzr6~ABmzB0yrUm5m&W!U$XVc%EgIPWX-dfr!teP0>&ePx)(UASvpRypNh3{hR{!a|+nc zDPTXRfc=~T_Hzo@&naL(r-1#O0`_wX*v~0oKc|5CTmYX_zbFW^{ z=U%a&d&SKEw<__wq@R0b+|RvYKlh6L+$;8Tuh`GMVn6qa{oE_|bFbLXy<$K2iv8Rx zCKuOlUOXquZFY>C9X2~`cG&E&*&s`B z&5KO!2f+3NVEX~E{Q%g00Bk=1wjTi74}k3l!1e=R`vI{10N8#2Y(D_D9{}4Afb9ps z_5)!10UW0v!0YJ;!1e=R`vI{10N8#2Y(D_D9{}4Afb9ps_5)!10kHi5*nR+PKLEBL z0NW3M&5P$`xy_Dov%_YG%?_I#Hal!~*zB;`VY9<#hs_R~9X2~`cG&E&*2*7?NPz@s9<|kustf+9u;hl3bscD z+oOW*QE{9e6|bj91>2*7?NPz@s9<|kustf+9u;hl3bscD+oOW*QNi}8V0%=sJu289 z6>N_RHZPu&>#{j=jX7d-#O8?25t}16M{JJR9I-iKbHwI|%@La;Hb-oZ*c`DrI=(*i z;gF+!Q`o*KY~K{NZwlKth3%Wd_Dx~?rm%fe*uE)j-xRiQ3fnh@?VG~(O=0_{uzge5 zzA0?ql;iYGc|Cno*uE)j-xRiQ3fnh@?VG~(O=0_{uzge5zA0?q6t-^)+c$;no5J=@ zVf&`AdGS14m(7uD%n_R-Hb-oZ*c`DrVspgih|Lk3BQ{5Dj@TTrIbw6f=7`PF@%5oM zj2!Ld!}juFd-<@veAr$-Y%d?Smk-;^hwbIV_VQtS`LMlw*j_$tFCVs-58KO!?d8Mv z@?m@V9H*Dh>*?jg_VQtS`LMlw*j_$tFCVs-58KO!?d8Mv@?m@Vu)TcPUOsFuAGVhd z+slW|i|66GY>r%Gj@TTrIbw6f=7`M^nwC*u{mOM#O8?25t}16M{JIcuMho- zw!akHUyAK7#rBtC`%AI?rP%&bY=0@XzZBbFitR7OkJTSm@z}2x|1az>W!(N! zY=0@XzZBbFitR6Toc>a;r@s{2UyAK7#rBtC*7Iz~=Zfp?FJ;{RQfz-Iw!akHUyAK7 z#rBtC`%AI?rP%&bY=0>>FP?|%vN>{%Ibw6f=7`M^nwC*u{mOM#O8?25t}16 zM{JJR9I-h%zCQHOlA}G(*q&!>&oj2?8Q=Qoj_HPD>lZ(#+4Ib}J^MEoUQf?6w&xk!^Nj6z#`Zj8d!Dg9&)A-4 zY|k^c=Na4cjO}^G>?i%w*q&!>&oj2?8Jic+!*$slxyBr^Ibw6f=7`M^nwC* zu{mOM#O8?25t}16M{JJR935XD`nt){K74E+KDG}Z+lP+ zwhtfMhmY;U$M)f4`|z=S_}D&tY#%+whtfMhmY;U$M)f4`|z=S z_}D&tY#%_S_Kcxgm~oZiv@&ZV2|=5bU`j*mFa$=Z0X< z4Z)rpf;~3`du|B!+z{-!A=q<6u;+$g&kezz8-hJI1e+Jn!*$slxyBr^Ibw6f=7`M^ znwC*u{mOM#O8?25t}16M{JJR935XD&VM1tGaq=o)%1El6u-ZCz7pe}uY^5c z346X0_IxGm`AXRHm9Xb4Vb52>p09*GUkQ7@683y0?DIOi*Q zJ?AT7&sV~puY^5c346X0_IxGm`AXRHm9Xb4Vb52>p09*GUkQ7@683y0?D)&5t}16M{JJR9I-iKbHwI|%@La;Hb-oZ*c`DrVspgih|SUQ_2HZ>a`YTJ z>^XGUbLg<=&|%M^!=6KjJ%|yG zan2+596Ibdbl7v~9OoQ5ujiac%sia)h&_i6dk!7;96HQ8IadyQ4juL!I_x=gn0@ei z&!J=7bLg<=&|%M^!=6KjJ%%^Ydi9N3qdtN8@yiV+So!Ij_vFCMS zUVrAiPV9M|*z-EE=XGMw>%^Ydi9N3qdtN8@yiV+SosM(frPp&_C-%Hf?0KEo^E$ET zbz;x!#GcoQxi8M^#GcoQJ+BjcUMKdvPV9M|*z-EE=XGMw>%`{8^Ke}@N3JnPY>wC* zu{mOM#O8?25t}16M{JJR9I-iKbHwI|%@La;Hb=)jx0LJusOPSdqvsl9&o#!LYm7bD z7<;ZU_FQA^xyIOYjj`t%W6w3lo@)&5t}16M{JJR9I-iKbHwI|%@La;Hb-oZ*c`DrVspgih|SS)zu%c7I&wt0B|BgNX-Eq!;_xktt348uKx@?YIV~*Gy zu{mOM#O8?25t}16M{JJR9I-iKbHwI|%@La;Hb-oZj+3L;lOr}qY>wC*u{mOM#O8?2 z5t}16M{JJR9I-iKbHwI|%X8#w=8Fq^70*fjKh8L`cVYgY)}I~b|L?=~`xN8+zwUKj znE&rBUkvkgV8Lc571!|fq0T{JzHZ!qLYS{7cb**P>x|=k{qcIfE;$chubiK+V?Hil z-&_x0_gp7mCtW{ZC%rGmKR+q%k?YS}-LqIH^DMeN%>4W85$19GeAuJ7hV{HMHOx9k z4G6RT&yEgrUtb*(=6)S#AH1IZaUS-~`Pok&mwk3U?7!3%1f3$z`9OL(bPj?$onBNOJO%3yV!Kw`g7UTS0aBZJ3 zzZVRAAk6OtzkVC$_kv@$A5>h=?*+?JnBNONY#-+L0>}Bi!0Y+FzwC*u{mOM#O8?25t}16M{JJR9I-iKbHwI|&Czl8!Ry%{Y>wC*u{mOM#O8?25t}16 zM{JJR9I-iKbHwI|%@LR9$ZKMLU*L5xzhCe=nBPZuoz3qrybk8~9bO0X`w_2$`F)Dl z!TkQk>tKFg<8?5<-|;$_$^}G(|JiHF({Jak4)~}U*U9T(uAkSzyf4Q6 ze!=yAA7LK9zc9bwcX(XCAF&?4Pq9wFf3beQuW?^~zvF%#XCJ(t{c#@l&H33+AD4Z0 zJ?y{hBp26jUgWqgnwC*u{mOM#O8?25u2mq ze!nwE#?29%BQ{5Dj@TTrIbw6f=7`M^nwC*u{q-M99zvkH0@fuP4Tt8m_x&P?H(i3yTm)vw%y0%)|Vtlus4@*ss4Zm>m;c3K0 z;eFmXJZ(NLT(51rw8`JXzszZu#|P|iM83ZApO47%%vgRzo`2i{?epW-9@Rdt=k$Bq z=XL(}Li@b_?-#bu_rwC*u{mOM#O8?25t}16N5}pB&KwyxM{JJR9I-iKbHwI|%@La;Hb-oZ z*c`DrVspgih|6=lqC>az@OD*-_iqe8v0JKI3V(iXw>0j=@K1m1mX0_(ywCD(Y0~B4 z+xI^q&Ad7M`s5SRZ}*3n{c=LuaBldS0Vk$DPls!Mcw&10+3?B7RGeqAcD(i6?)my| z+xN)xjJvo;p8wm|d*sL6bE}?tJ+0gH%@ro5bUC{mL&kE$)|j zn*1Zo{EHq5^SDpm5oSF@uMM-#L6?PD|CVFI+}Grb!rZUp?1R^{KhDFxIY0a9&=BCkUSex+tk4C4*PYBnkJ0`t5C_LlvF{#Og;r&OBNxS_iyz{Iv zX~Nav*S{E(HkcG1vHjRQ-tWY*`TB3K7@OyrFn4U8f8M8K^W*l~cwAo3X${BabvE8@ zTwZ_8X5;dGF@D9HagSWT^&?^C>2PzH`8S>r=5d#w6=pqCP7brqYmX1J{{1_IxvzOg zhq+(J*$1y@f1HPXbAI;I$7P>g5Bu*r$;I`X7dfuW=EybXh|Lk3BQ{5Dj@TTrIbw6f z=7`M^nwC*u{mOM#OCNY`{4EL4>m_^j@TTrIbw6f=7`M^nwC*u{mOM z#O8?0bL{(U|BCZy))YTS9rarOblV5vxhwjoiCg_%jKA7oKx%kcxN5HfY4+LS^JWZ4 zU)&hJbF+czvd6=7hYd^<-wIFpcwlP(X?S_ZL8-Jny#LdK@_6lLgY)&fUq3j{bHew7 z^Zd^rIwU{t#+MGs>#6N`MwzM(m(Et>rZVSW}f$d`>nV~=5PCt zFppbpdYJVLo)Bi8r=A&R{r8;|=Dr^85$1j!XCJ(t{c#@l&H33+AD4Z0J?y{hBp26j zUgWqgnwC*u{mOM#O8?25u2mq?1R^{KiC|x zIbw6f=7`M^nwC*u{mOM#O8?25t}0}&+&pCMyEA(|4}^m`t30~-PI}l?vbO@ zb(e*gj~t!0dpz9a@zLqwFT*cY8k1Jlc%%5YefJrYu51xrdB&J@-BIC1w~VRy9CCQ< zdt*}DKH;WYjm_irju@M-zhl(cJkNpmjLq{8TR1j9?v~$;&FiUGbzENO8x@8AuK)SQ zzMl$K7(9FzXri+iS%=vd;dWhgtsv?}oXrxeLSG zujA~4*Rwy)!@fB``|0Dd&#s64cb(+o`pt_R*JX3$8gswC*u{mOMbew(gdiDpKBQ{5Dj@TTrIbw6f=7`M^nwC*u{mOM z#N|15zWLmA?V`7e=heZ}&rJt!{dVE|o;x?~c2s!Y59g-8Uljgj-x2BP8Q}pFMx=3X zhp+o=MB4tx@O?*}mv-CyonoHLA3ZO9+A#b<)AQ4N+l6HBiH{rFw8t>?H^|T537WE z+&e#cvsgdtsr*!!b^bOz%=!`Lp8vu|L-ON3)_X`^&ns6A$?I%&-;liiCKW$V zdS8tHa8leC*H>y9W}Z=Nzg95+XA9!%29JCHEn(KP#l>OPS?TmJ>p%8{F!yz0moWG1 zIQ!uB?2q%XZ_dwt`nc?~>tX+0C%L$O^CHJ}*&MmX9I-iKbHwI|%@La;Hb-oZ*c`Dr zVspgih|Lk3BQ{5Dj@TR>XCJ(t{lVsl%@La;Hb-oZ*c`DrVspgih|Lk3BQ{5Dj@TS= zd5(*3?3uqWEV#30{(iCFGd=V7k@ny9%->%owCt6??|eVLSN?vq-O^t9`_z8zd*|<8 zwI1%BzptITOP~DxZqAfGdHkBnC*|v>4>>8%^VZ8J<@pb3*f&4!=w5yEdak*$Z(iqy z_x8=}Upc35zAwi8e!=yAA7LK9zc9bwcX(XCAF-awYro&IPQQP#e!s7AUw*&iejR5Y zyq^7W9`?=o*-syreRe(Uzw0Cy*Kc0rxGtL`*O((VM{JJR9I-iKbHwI|%@La;Hb-oZ z*c`DrVspgih|Lk3qvL+RGe^eF5t}16M{JJR9I-iKbHwI|%@La;Hb-oZ*c`Dr;_@74 z*Y1*k54vgFF8TMP>ZLCE_oi)zbjiO@^_tlw|DN^InlAbGuYdJCF8^Lu{n_L4?`tde z?wWs(JMi|d`S-iaw?00PpE36MeEmgV9G~a8=kRWM{<_y!{JmrC@0G{D*DbH-j7?9- z>wIsg6Y~0>t~f8--&+~?_amp1)1_3V%Huy4-Ke)_oVv+H61T_?G?e)A&7b=e%b#vHLZVspgih|Lk3BQ{5Dj@TTr zIbw6f=7`M^nwC*9ryP;b7b5cu{mOM#O8?25t}16M{JJR9I-iKbHwI|%@La; zF3<7ysU6bEH@sN4<722X1yP7x^w6Bw~xZ--_SXacdOJTUq57UmpsqZm%8Nn zH*IiSe%!+wC*u{mOMbew(gdiDpKBQ{5D zj@TTrIbw6f=7`M^nwC*u{mOM#N|2iHS@VT&lLZ^`2RSlW0?P^Jtlwd<9z+`dcH0>4_~jG zpRZ#+E??hV4`26OCtoLBKVK)kFUA{v{B*HSuHSQdn0anLC(QiS4-fOW?=%Xtp8bA( zD*kQ7I`>=_X8q^B6Xw3gybm(P~Z(iiME}J9Q zm?JhvY>wC*u{mOM#O8?25t}16M{JJR9I-iKbHwI|%@LcUs?4nqls1<>q1T*Kzj2>)9XYVc(pe{q%9!XV=62yH0X({pLlE>#{j=jX7d- z#O8?25t}16M{JJR9I-iKbHwI|%@La;Hb-oZ*c`DrI?g_LJ^O>r5t}16M{JJR9I-iK zbHwI|%@La;Hb-oZ*c`Dr;_@7MO>F1uA1|JVyx#Kq>tSApnO7;EOT0eQe(iIQ*KIyN zBgT0>r}o4!uk$=KE6nRZ^Ii<|y3o1rg?YVb;Nmc^BRS6NOJ2|GPR_&YQO?inR6Z`R zU%4J$2Xmdg4(9rK9nAY;e01-)FRs6O=P>hZ^8MW6-kJZ*=fXVh{x^kL&(sUTtaIY2 zVb=d%*D&|>S;sK<>p1)1_3V%Huy4-Ke)_oVv+H61T_?G?e)A&7b=e%b#vHLZVspgi zh|Lk3BQ{5Dj@TTrIbw6f=7`M^nwC*9cLfBp8dh*h|Lk3BQ{5Dj@TTrIbw6f z=7`M^nwC*ae0pX4an~c{C&ai7yRA9?<4#@!tXEqox<-s{Qbi3NBmvG?^FD} z!|z}G9mMZz{C&jlcl_PNasHm-_57X1dHDN_^YeEZAD6$^xE}uQ<2w1fkL%~}KHeAO ze!t*)zmG7F-(Q&D?>juM-;Y?2-=|oo-@jPD-`BV=zu$4cj@c z8#q7jL-28Ve}e1beGaaZ_c{3c9q)7Sz8LrSBd+)NCg$;z8`yKb|IQ!uB?2q%XZ_dwt`nc?~>tX+0C%L$O^CHJ}*&MmX9I-iKbHwI| z%@La;Hb-oZ*c`DrVspgih|Lk3BQ{5Dj@TR>_xC$wC* zu{mOM#O8?25t}0}&#_&{vH5ksgS(E+uLpjA%Gmrm;jb0XJzqbZHf?NvUGdFl$L7}? z`&T@NeLeI0Cgbw!lb`k)mtVL1^L69$>zU18|L^#AmB#1m?>k_8o~P{@aeQ9q`|pm=>woRT@%g?O_w_)o_jN+%@%2OI_jN@c*Vh|akFP_rPG6s7 z{l0F=effGO_v<+O;Pvc}^RREu&wl#2?6d1(|6M1!xPJ2@$935pxyBr^Ibw6f=7`M^ znwC*u{mOM#O8?25t}16M{JJR93A)dOmk%19I-iKbHwI|%@La;Hb-oZ*c`Dr zVspgih|Lk3BQDQzgP%^y@7q6Q$G++KA@O;EnRoR~KP(R)anZ?X!=9Ck&naAX>nUl? zGvVtuJuN-cC_evk`SgBiQor#0bIwQyObZ{_XF%HeiSX7Z4oW+|5dNz3kUV}ytD*V& zo2s0Z=b3o-*?In3wj7=xcS(zL^LozTY(!q?vMWdA_3!-Hh7B;u_Yo$N6E_d1>1)>%VvVF!yz1oiO+7IQ!uB?2q%XZ_dwt z`nc?~>tX+0C%L$O^CHJ}*&MmX9I-iKbHwI|%@La;Hb-oZ*c`DrVspgih|Lk3BQ{5D zj@TR>XCJ(t{lVsl%@La;Hb-oZ*c`DrVspgih|Lk3BQ{5Dj@TTrIpW?|d{a8+r3S@w zOf!Do9yQZ*gSIWk%U${ORi%zIqHnoLqc2Nyo7XC?8GY^Nr6#Y2PyPJU(jn(X7y3p` zmX;3PD>~9Y@AFA%^RL2FrhHQBbYI=#-(K{_($bvMfuZ?AlnrYs0P$yEg3FuxrDv4ZAk%+OTWG&N6XG*yV=vw{ zeY^)-d5qpo=d&J%&_8zhKh`q$klBlvWS+i|0o7OAl#P>w>R~@jAEe+-m8g-xU6Me$7_9*I8Zo#bK3OZF~85g-_dJ zqgEX@{h{!ok5p>)^QAu)uGYCmtCN5JSK;)homy4x@$bS{y_s6onD(E-Pn>;HtFs=8 zHUBbyT&p&>{8EhXv-*ZsD?9&M`20s^wmR+Q@CQQ{v^r{&--_`W13qr`^KUWUam|md z?sz1;$sv_Xsb#p|JzJG79UgO*?@77c2lmQ+!0rQfAF%s?-3RPGVD|yL57>Rc?gMro zu={}B2kbsz_W`>P*nPn611{eO@0aJp)pJIahF@qfy3u6LYk9^df&Qp=_96?^{E z%qL5KIrja+N54J2bos^_^=rF-tycb@XK zG5*%EHPdx{7Zz*K<@4Z&|FUWN@`d+``)&K=X6YXnhWC4|T57gY_`16{Pfz!Jx47n; zwp*sje_8u}(W|#g%Wi$U7_WY5jkIEFyl1<0!L1oii2yWDpx&R%yUHLnyK@R zf6x2LJUo`y;PPvnlkue|EiPUA;8Ddqj`LWKbIp_ej!8q8wJ7F%_uL~>mj=5RzPr`o zX~C);3xD-N>oj9>QNx7qLG(tmz#Uik257nQ!+_MpN)@3g3N^I2^RdynP!i@jg${bKJId%xKG z#ojOWezEt9yQ_ixHA0o%=+okjf>9}&hOf$ei~mhJnZ#) zX>{H2RlVxv@om4Zo39@?p>CdM@ve3A{FUFYlOOk->+9t8>~MOWyv{4y*U9U@F4f8R z#rR*Zk9*|${wIZ*=f>T`%>Tl##b*ZR^SHg<4zr#~bHc21;IuI7|Lc`u?(2@r!rZUp z?1R^{KhDFxIY0a9eg0sdSJ>wpE`J`5+<%kw$-l<(^=kgOJvT`Un~f{Ha?4Fpl{3QAmTa8fyD?nl zmW|WBFNK>QyK$=hUHFP`HcB7Y9AEs~uPgdCH{Crvw*E%x%>%=fp4@BL*=aWAZA>7p>}eC(Mp>t8h|%zb?~GtB)u&OUfO`{O+9 zoAa}uJ}&$0df0#0NiMG6yvVWK-Y?_s19pF~`-a_5>^@`nADas{FKmw3e6hJ>pAXpQ z3HJGeeO_UoZ`kJ{F26_j!Ry%{?7m_56T8pY{m15l%?q0&HeYP+*yjWGd4hfZV4qjm z=Nm469xiGzELG`qYw;ZWY}aAwKi7wksWvR_{d)MNz;iGw`>H z9*ni~Po6O-KkkNu2Ick4I%rT{XZ^;5^7?n&dQiSE#_KeRd*S*etNvQt3-i>N8)p7= zMVQBZ^OP{_*{p4tb$-$`%=&9L40B%%>V&yp$Jqz3XMdcBeRF>H)5m3>T@U;3I?2WL zn-@8j+xunQeZcMycHgl3iQQ-H{$q2&=7r4>n=dwZ?DGNpJi$JHu+J;(^9}nv#O3$s zK6pL*gWWgmeq#3-yZ_i+uz6u~#O9059s7L1K2NaEAMEoA`+URY&%-V^^-I%kxT<&_ z_MFr&UHL}%`QiQ2vzz{<7$1IE#ot5@4lmuPU+On7Ty^$o>5WO@)4HCPrp^h!@YSj5 znODL+EKkmr4`{woR zdS~Cf&Pfyc=Jijzuy4LE#_#D9_r>*R?-FL7JHNlOxJTw+_*|IB?RQg{_1ttpm~{?6 zHO%_&?i%L4?(Z1pejR5Yyq^7W9`?=o*-syreRe(Uzw0Cy*Kc0rSZ?o^arXhcKiGZ4 z?k9GivHOqB1)CQ(M{K^>+_BFG?DGWs{J}o2u+KN_^AMNcqx<0X><@O|u=|PKXYBrC zbHV0?%@La~Hh1jv0sB0`K7X*!E9~0*uGF*Q_oj1;=ib}D^hm91jVN6DxJQ~X zF8tN~J<^dY!rce=NZ%ZBUUAL1hCR}PDdENQx~J}o!fm>BPxn+kzqsbj~*Fg!A-#qg$T;lF{Aryq^KN;aRlhwxuYc=* z9-r@v@$>hNd*u46&kQft#yn^C2s8hSzn)W!^SG<;3$va+1H-Iy^Mk^ye?+4&_cf+w znEQ2{eeinr$9dQ{=Vw2CT=v=Zu>Y=;TwK3-kz={NU&h@B?EYZ)4ZEM%ea7xTHWzGO z*c`F>VspnnAF$68?DGfvyuv=;u+KwWevj^h*Rwy^eZ%f2cAv5PkIe;}7dA(1zS!Kc z&j;-D1pEBKKCiIPH(dTa{P*M4(;*vNS3KV~oLxP&JTN?Ha`iM|Sh&Gy)zblYhA-Qp zdaCwTc-F#dX~Zw#s>7?LHjSYty{`LvGqM-xuQ@Uzl91jqB@8 z3^UJBy~50Y-kxC|w|b>8>uI~}+T!1`&IYfBS$~IlVead=N5kB&$mzBxbp z>Ep7`u7~}1o#f*B&5In%?fo+DK4A9;yKmV2#O^b8|FOAX^TOtc%@>k>zRbJ;KyKR-%|I~I{<@;iM)*I7{b#nd4sbS{1uV0w?-`_9H;||#( z%zExvbyx9kS?2}sgjxTr1!3;%p{K*#ujA~4*Rwy)!@fB``|0Dd&#s64cb(+o`pt_R z%kBL#?ml4m2fJ_B{lxAwcK@-tVDrM}h|L$9JNEg2eV$;SKiKCL_W6c=9^&$QbRWE) z{lV@Vc0aNEjNN~1F4(-VIb!q0=8k``=@j0O4_1pU< zgn3=}(|KWDr=7Jr%<*nPw9Cw8B)`;W~9n-}JO$q}0`Hh1jv0sB0`K7X*! zE9~%kR;B@Ot(KyKmV2#O^b8|FOAX^TOtc%@>z*j zJaj~U+{-r{k=Jv;!gKRFZ<}*&UjM!KoSW~9@$oBX7whEuV;%}K&&6ZH%zt0!Fpt~1 zX_)nls1jzK$A0@@F%Rn>w=~RsUA8#P{W{J*cs={$JnWnEv!6aL`|Ntyf7eMauHU@K zvE1G-eg0sdSJ>wpE`J^lozu5;>VV??f%9Ly zqHn3%?cvIG`j&ovKm6qJCzUR(zOs0}z1XQwso}xl8e8@*bvZTM_r{*3)#Jle)^soZ zJS}{6yAw;Z?+tez+pRSHfpD!Sy5{j|n;e&~KeT`6JkK@Xcg*vD_+W?pxXWf7o7Z#m z|6}h=!?v9ExLru8Y#KF-M5Uxbk)EXt32CIclqpTbZcv5>WZWB-A+xaCkzr>nGRvH> zP01WlhQ!7;hSG6*0G*-{nz?k_kG>>{an|%zU-Fke0O5ETz}gh z-SWI>e`N2N3;kdE?-#{f7^m~HV8*}Ws$h;g{*++qd9!;kb-vs#nEI2XtX$^lU%IdyvT8LcD}T`4zTM3yKY6FP3sA}&amqbn+t4S zusOo!3!6La`2c&Kz@9&_=N0VvR`l6)9>SZ?(RHvt>jS%P#oumPPuO*aU4PhIVDo~_ z5jJ1g++oiL*z*MT{DD2MV9&Rr&!+Pb_MR5lds<-clYzZY2KGJ~*!yH)@4bP&w+HsV zAlUnYVDBk{y*CN=UM$#qv0(4Tg1r|D_FgR5d$C~e#e%&T3-(?t*n6>H@5O?>7Yp`Y zEZBRoVDH6(y%!7iUM$#q&tUJngS|fx_WnKC`}gd_{gbfwF~Z)*2zwtR?0t-|_c6lW z#|V2LBkX;Qu=g>--p>hpUnuN-p|JOb!rot6^x1R|Gwi*)u=no5-n$EX?=I}UyRi4} z!rr?Jd+#pny}PjY?!w-?3w!S_?7h3N_wK^py9;~oF6_O#u=no5-n$EX-!kmI+_3kz z!`|Nxdw+Y;XVd-du=lsa-ro*;e>?2`?XdT^!`|Nxdw)CZ{q3;#x5M7w4tsw)?EUSq z_qP|k>Hc=u``clkYk+;`qUgWrc@WrVE?}RzfPLly_L&RVXD(o$xqyA<0`{2;*k?ds zpH+c-Hma6xymaTs;EFA)mwE_;pE|TgI`;nH{ZFWw_Ie<=^3>A%;%*QA@{-bf>ShP8 zn^`+mI5l`|->*vUZ@5!2=K8z7DrtUW@bmY7UGie>T1ERW$F47V`;y=@7i=hb1LoB%>ZJcodjvDi z?E7jI?TmkAw_uL@`iAO7JN0aJdoXnl9v@8o)B6N7uT#4QGhf?T2m7-=j>Eb+KI`dm zS!e5E{jHN+tlwwTI0t+l4fc67*yqt;pGSjz9u4++G}!0SV4p{WeI5<=c{JGP(O{oP zgMA(i_IWhe=h0xFM}vJH4fc67+j$<%{ydKc`#c)#^JuWoqrpCp2Kzi3?DJ@_&!fRU zj|TfZ8tn6Eu+O8xK92_bJR0otXt2+t!9K$a``j+~p)Y&+WoK zw+s8+F6?u=u+QznKDP_|+%D{MyRgsg!albP``j+Sib?R z-vHKc0P8n^^&7zY4PgBSuzmwrzX7b@0M>5+>oBkupSs#4-Bja2G#=u>w$swz`%N7U_CIf9vD~;46FwR)}00G%YyY~!TPdb zeOa)+ELdL_tS<}Jmj&y~g7sy=`m$hsS+Kq=SYH;bFALU}1?$U#^<~+PFU$V;vS58# zu)Zu&t@mWx@KgV0~GzzARW@7OXD|)|UnA%YyY~!8!(Ey@Ie_L0GRK ztXB}$D+ucqg!Kx-dIe#6@>K)!g>W^y@Ie_LEC+O>4&6U zuOO^f5Y{UQQxBdiSg#tcoVufqCQ z;Rc&Ly0HFLSpO=le-+lh3hQ5m^{>MES7H6Du>Mt8|0=A171qBB>tBWSufk7k^61*` z^-GT~?fO??{j0G4RapNjtbY~OzY6PLh4rt(`d4B7tFZo6SpO=_I^$V_^{>MES7Dvi zu%2pIPc^Kk8rD+{>#2tIRKt3zVLjEbo@!W6HLRx^)>94ZsfP7b!+NS=J=L(DYFJOT z?S4MgH%_~rYFJM-tfv~*Qw{5>hV@j#da7YP)v%swSWh*qryAB%4eP0f^;E-ps$pJV z>|X$rBm36Db6onf-vP`x?1KO^KKmoU9G86) zVCrE%1(-V7X91>u_FsUR7yB~6%-43-!Tzj|*xB#er+6! z_eu6^gL(gCzc!fnRrYIxdB0`9HkkKe_G^QAe`dcnnD=e=YlC?|XTLU>_j&efgL(hA zo$G@Axn4L9*Ad6(`r>i9?pP1kBkSb)W&Q4Z!m(&)-xHYr>t*^h>H>Sv!Cn0c{(4a|IPXC3U%`Zx~j=J>3q$7P+ZhxNBka}7 z$KrDc`+UKCK4G6Pn9nWj^9A#HhJC(ZKIgE{7tH4$_W6SOT*N+KFrSy$=L_a@6#IO^ ze7>@s&t3NC^O)oCInD9;{N{1_TxUIeKD16gA6mcrLvbwH*&hm~Kl?+$jKjWKFyph| z7R+(khYO}2_UD4BlYP5j>SsSMn0c|!7tDNZXC3U%`Zx~j=J>3q$7P+ZhxNBka#~RY^`AL7zTgLHxW_-_cj_dhPJ-#le)7K02 z`#NG?zP^~R?W}|SSs%w?-5j6w^ti0E^|1cdNiNpU?;F0)pU^z^jb)B}zxKMo_inEj zd>{8Z!uNEqFMNOZy2JN+uSa~}_d3Pz0A9cNeZY2pH?TjyCpZqjGdMoKKX_bzm#`jw z->^=8-|+h7exuBVcHjT$?{$H3yk0QA*Ab5E^@V!8?og-KBkK1$#k{Eb+KI`dmS!e5E{jHN+tlvGFnV0)A!|uxryDu}$KEmv;4ZANh?7qyf`!d7s%M80O zGwi<1u=_H@?#m3jFEi}E%&_}1!|uxryDu~BzRb3>FSGsGml<|nX4rk1VfST*-Ip15 zUuM{SnPK;3hTWGLc3)=LeVJkRWrkT#_Sc5pml<|nX4rk1VfV6!-M=1o|9aT{>tXk= zhuyy(cK>?V{p(@(uZP{g9(MnF*!}Ba_pgWDzaDn~df5HzVfU|x-M=1o|9acmzux}r zUk|%~J?#GVu>04;?q3hPe?9E}^|1Tb!|q=XyMI0G{`Ii?*Te2#54(Ro?Edwz``5!4 zcQ5^%+^|AX|M>o;&jghOe>$OWn$bV_$J_d*Lr)8CyQXiNbz$(l_Wjab*9R}3(=YvY zXYlG@`lYfz_MfP@Wg<$8HnHrT@Cm%NO%yoW`#NGycj4gE{VFw**tq zDYJvAbM*Pa)W5^DVCFUFtYGGAJL_P7*2i&JH^*l^Jud5PJ*>ZVl8g0sTy#)sQlnGx zdTjH^L8;RD!7sdXP@4Ro;5ro#PBn*gF8bVg#KGy2CBf%jcW|0r>A<4B+0O^3#zzJ} zJN%F|@vPvsD-KE9UmINOz%FT<+k$_&w@Ypxx$B|1|F#z$n#WnV=FmL;jD5T2_E?Ok)7zdhSE*ZF{zY+8KY&DZw0fX@g+u+4H@U zq7QYhTo_FK2VEM>ytg@OM@BOUt%9rs#9o zl>Ji84#68g-!I+SFZiQ@9n!7CgP(q>LvC-q|NgoEEA#fx<4h>iF^}J^SI2zZ_h)s? z^|XAdW3F@AhaGeMOV@VH^P>IJV`7fwLq&Tf$VxBRR@9_NjNcFyD9F=yv|-1O$oxt>e6 zZJ6uaeYb|W{(5^g%=4nX?x8V9`rq~Th@v*esd8#C$uP%LlEAjO;=FQ(qe0|kEePfBQuM^t*UgGPkXW26O^|JJoGWm6M^G9X!>+9S; zWpn$6C(7pje{Z@~etoqq^{Y63rMI`rudf?wZ=GLX-yF7eetn%cV(a|+I`h=6^XrRt z&rkY$-ZGBoGvj-nb6n4V>hX0!oxWbE-`5fI^7X}hZD$?q&-yqH>*n~Zr^jWTt%vou zPI9sSdT*>Q@%mNqi`6AwzuNEiX^Gdbch3E^#Ov3_@}HG>{aU!-vl6dgKOMiO#Oqh9 zwx5@H{o20D7bRZ5UjP1!60cv^yuCKJPrQF!?tk~WU*>UsIpC{2{(_Ib%Ew)P{MWgj zanF36>%6|qH@W_ctACT{MZ53+^!K{JI9@Lp-|Gm+_4-0RUU#U|>k;*Ponl^IznHJ> ztb_eoAID+c9G~^{xU94Fu>RIbF4oWM>w^A`iq}3lj(#DSeBar3x1ycgC*Bmy`A~0T zFz3mJ?v0B+oImGX7R-6|=HtPfZ)4vN<~%&^^I*9?Uq`>=?}W-!Iyw=)-aA9~(?P7c~r~&JODv7JaDy zme+!r*TUz5nXm1vgZ)__$6?(ZpY`;(th4p7{?L+{4MYQwsT#u zKi3P#;X2~@Twgpc*B$HOdSsnkr>vjrm-C{1?C&*;~F!hgFSH0-Zye51U%zSNU9qiBgI1cOP_^hYLWu2{u^|wxPv3@=u zdLHsQ#PgHSC!V)_Zt;BP^Ni;?pL0C_`TXPSg3m?1UiiG^>xj=$zP|W;Wjmj{?9b;h z$Ki9DF;^VIG)dp?|IH~J^!i4*9CR@dZB(_ zN6gFD7xT59b+A9{<2bCFO9{u9TD8(!k0S! zFd%qAwG|!L4GnI5!|S=d=Js#p{?8t=GLO@=<$HPjs}_Bbk9*D|ALV+gm3)%xyt2va zT>t7xtMj~QFZ1DdMV<7ovLKjoW=;rZ{BODhbKJ!Zf~lv@#tp^aQfHOVf~kMNTfxlh z_}7A&ukEaZ{aGK!Vci^`_4K%`v-Pn4)=4hbzv$dnsbosE;`{z}e{Yp8zcRS;!d7X! zMZpbLwMxrh3?5v+b*lYI@C##Gr+t15{^5nz>D=;hk89=DZPJC+g4f>ICVg5bxI>k; z>6rS#7tUy#+efT#oBN;DZ=XEQ?f31I$KR=3yL{ZEyR^&ojF{Li*ZJ1$cDep1u5Xv; zMf(>+qE7msc3?2$ENl|Y_`|CNbKEY!RV~(pdVcsam^wFn7)b@1sd~IhP z?9ci*4(sOltf$9iovnxUw@z}g{-b&~OJ}x>`;*h)W@*I{o9I>2l#Tn_dmY*+onJ5b*h!62w|2odJ=7>& zb!6~gw%aY;J3P3jcq4}Q7+?z#Pri+9ic zpV+W_9_Q;Gd*ty4-LywO?%a>|$o1S&rAe-{Zp$XQ{&M>@$@8Lp#B(u6`mbNO>Hh!H zahlBzX8aG%2*F}Ao8z;d9+!2t z9@gJF$;J9dbQxak8^v$GZ;u(CcKqw}#e4O}_lKvdU0*2pxVgusZ+3XG;K5fOmu5d5 z++q3gX~wXZiuQBbpO`kjAKdZT5vf(jxSyfZsUy?D6N33a?3ot?|N6n0++OCQlXL&Y zwa4XgwmRq3JpPAEPRqxA=fS_`deUj*bDhVp9-r%fqvC`-FWMJ9{A^Jt{qOl~S;36+ zdV^rbZ#n9jqMhS*TK;sw)bmu2VCuYl!&5~&^`E^sn0X!Yk6`9&JL_P7*2i&JH^*l^ zJud5PJ*>ZVl8f~}_3t0@_sZq(|5!4&T$iGrmEZqd^47CQ6uf%l?itmZkGhkwTN2AW8zTLU#L;c-PY)~-sI_#tR z1v6jUSqJ;GK90k>IX>&@aam{UVg0R>T&(}Zn_JZ@`rq?ry|kfb@TxZTQ|CQ`H(XOcb!ij4qC$f-uS0OdDGgG+ zlHgO;{onQ@2ke~tANTmqd7R7YH_YSzHnw3t?*4Z-%=H}kLBm|<(q9|q`sZ)EOP&|) z^UsR<>EH6$V8$8QHJI@mvG~5&GA`JkIOn+59@E8(QV%?rzUiPk$R7e8tDrQ@Qhl=U1(fUbrcE zb)Ook#zVoqZ>^D9y%c%)lBDo9(>xHHPc7m1V4G`PHE7F;3|uE%I)9m zUMu%6_xD|H(TA zGtPqF>KAio{2`wObKC=83#Oj$o(QJSukR10{#kbgGp||;gPE`Gtb_eoAID+c9G~^{ zxU94Fu>RIbF4jNl{?=*K$7_q%@==eqF7RIbF4o_-R+scuyN`<+I_=seb=mk)!S@`{CG~qY_{mecq!(ug|9(%Gw9g5_W6K_z zHg*i2JM_>rtX}Xv&m5ZiZ4>O^SxWUrrXyCx2SnoZm)FiVY&Y<>kiA~ z9NG2oJpRL1AD)l<(>sUfdMZ{tBG-Aw9!KQ*k8gEEo)_&`oDy@S|GEDNW}F>X1~dL` z6+S8IG|Hl*UcM{R@M!^>$L%?$LDVseb!YQm=-S%9&r4?G~@E% z^PU)(J{cE$ZIeN1W&hyGR}M5yQK zJM6q*>iPY)VCt;!XfX9Z{!%dWy8qQ+=4(6aV1L%faacFUXFWYG>uf!&zjcy}^}qCd zkJR#`_llbDf4xUK|DVCTf7>HneQNN&yYx)kr{D?4_Dqv@2>xVI&(vwns^V{V*s)i- zd0BAdNxjnCyMnj*v{(A@#^64Ed#82R1kZc6cW$4)PoLcXs_XjXai02bpFDo6!;i|x zJ^A9Jay`=?J}TGw?b}D?`d5B@RGt^@Z`FRksFVK7dImF2uXBSLf6by`j@#hfVCq@= zOE7gVtM)-L4)veCYcTWr>mI?(*LK#y{;ZGVux^gedU{;e*?L%i>m(QJKlSnEsqD+K z{sUiVo)(mg+Fo4KJYC%}_`RK4q(kMd-7T*wj!GacP{j%Wuw%sdTx+eIAv3sSf ze-B>p?p~?qUt%slb!(Xp*)-p-kG9P1yEorE_wP7+?>x>)>-Wy%zuBo(K5n%ct#Un$ z7q!ZDUinI^T>sQ}TIG4sK5$OVk^ZBH1T)SDO@kT#uwUX_;F$$9IkQ@K0-%evcj$ zd~~};sqd`d5hpfEA3YO%>-q&@QZ!!F$;ANTqdd*piVF4H8}*|0(B z?--lv->ylMJTKa7t&Qs`{hQt!%s4kp4QBiby@EOJt4)Hbr*(y3>TJ5{`b+(%eiYYY z=5^+(VCHK(>tKJ@$8lIU$7ek~F6(SPtiN@Vi}jy3q;@*{^v{ad_$ec5r^f#Z{@~o& zsru)^-`-a{-Bfo?(Pyt8YNvLG2Vd8vP8xe!@bkCSNtI>?e^9Y*s(wfC($njvmlg+C zURyUk@o4biLG^Nbhv)0%{yq1upT{}#Z}s!|Yu_vVKia0_?y+-&Tu8qw`zZAUh;my)D^@F?rt693dTyXQ9_bmM``BgFI8JF#u zR(~7(V%g@oeZeWsbN|QQY@Wwi*QP}tf55pd@^PMb&`wqe|Tc)Jz$r_`S!xNj%k~tf;;@ZW2#X2F8&zhl2nd7QVd?3BkpWKE}h+!;+e=X&P!@0{x_H?ecB|C_0u^So&9^GwWz{s;aV z%s4N%jMqEkA2&3Z<6cv`moC4lQqO+#gQ@et$AYQ<=a++-*Eg>PGhf?T2m7-=j>Eb+ zKI`dmS!e5E{jHN+tp87MTYP`lgGWaHKYQE$^jj_}UPpffza{6=pB~^PMP7dd4={QC z=}Vtq4JrIXj6`%26y^7$m@@={|+Z@(y4(m3Db(_Pw&0*c< zux@i$w>hla9M)|P>o$jVo5Q-zVcq7iZgW_-Ijq|p)@=^!Hivba!@A93-R7`vb6B@I ztlQi^xXoeR=CE#aShqQ>+Z@(y4(m3Db(_Pw&0*chla9M)|P>oza?Y;v2! zy3JwT=CE#aShqQ>+Z@(y4(m3Db(_Pw&0*chla9M)|P>o$jVo5Q-zVcq7i zZgW_-Ijq|p)@=^!Hivba7ky?lPP1l~e+<@b4(m3Db(_Pw&0*chla9M)|P z>o$jVo5Q-zVcq5hZ*rT%y3JwT=CE$_qW>nhIjq|p)@=^!Hivba!@AAkcYph&+Z@(y4(m3Db(_Pw&0*cj({5U`$eSkF1E=N#5^4(mCG z^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjra0c0A$s#~%*sIfwO} z!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0 zu%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}+m7el{&>z|J?F5V zb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&pE8; z9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5VbKCJ)+8@t3tmhoo za}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&pC{5YIKh$i@E4I zr(MrEtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2_<@xp6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?AjFSihcg+Vz~n zdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~ZO6lG ze>~@~o^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0 z7?0x8axpJG=d|lNhxMGpdd^`z=dhl0nCEdut%@=AoYSu79M*FV>p6$uIC)qa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4&zxp>xxH< zb<=ZB`~0!Tq(@GUc0K2`>p6$@oWpv~VLj)to^#uMed#%;UC%kJ=N#5^4pR@Fb6C$g zO#L5LjdnffwCg#C^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpp42hNOZ8GhhT7YFM( zr;na<_=i%@aIaQR74y<_PP?9SSkF1E=N#5^4(mCG@gXnTF~-z$PP?A-;%`g6%GRmp zoOV6uFzvqo>p6EEyyCE)bC~14Q7_u{oYSu79M*FV>p6$@oWpv~Vb-VJua6hU(sNF` zo^zOWwjS2s>#Ux0`sg`_^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2w zIjrX#)^iT)IfwO}!+Oqb_w%8ibK3Qs!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z z=dhl0SkF1E=N#5^4(mCG^_;`xi+>d+cf72yo^x2wIn4Qk-xbz#4(mCG^_;_c&S5?0 zu%2_6^Bhkstmhooa}Mh{hxMGpdd_Xfvuc0*tFWGPSkF1kaq+mqdd^`z=dhl0SkF1E z=N#5^4zoUZVqrb!u%2_6b;c75v;Nkp=bUyu=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0 zu%2_6_kTRhu%2_6>jfTWSkF1E=N#5^4(mCG^_;_c&TYqIY=8X5u%2^R&pE8;9Ht)p z$*`VtnELT8!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0n9nEp!(lz=u%2^R z&pE8;9M*FV>p6${9EIl`)^iT)IfwO}!+OqPKEL5PhxMGpdd^`z=dhl0+wp|kAAdNk z=Nx8yeB-d5b6C$gtmhooa}F~vJm;{Ub6C$gtmhooa}Mh{hxMGptiN^YIj3FEIjrX# z)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^Zo989 zJ?FIRIfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4xi9G zJm;{Ub6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2_< zy?*IAr(MrEtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S7$~em&>3 z>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMG> zj_2I|c+O!x=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~ zVLj)to^x2wIjrX#)^iT)IfvU%o|c+jP_Fn5T+cb}dd^`z=dhl0SkF1E=N#5^4(mCG z^_;_c&S5?0w&OXsKb~_~&pE8;9M*FV>p6$@oWpv~VLj)to^zOWn0<5{OV2s&dd^`z z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2w zIjrX#)^iT)IfwO}+m0vP{`kXTJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E z=N#5^4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT) zIfwO}!+OqPJ?F5VbKCK(+8_Tatmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG z^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqP zJ?F5Vb6C$gtmhoob8b5xWBcPbhV`7odd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0 zu%2^R&pE8;9M*FV>p6$WXr^_;_c&S5?0u%2^R&pE8;9LAf9=N!hrgy$UAa}MKQ z#fuK>IfwO}!+OqPJ?F5Vb6C$gtmoWzJmL1o9}ep|hxMGpdd^`z=P-5REr<1-!^{iM zIm~?VoWpv~VLj)to^x2wIjrX#)^iS%i}mX{r(MrEtmhooa}Mh{hih;0oWpv~VLj)t zo^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmoWzUtfC8Y1eZO>p6$@oWpv~VLj)t zo^x2wIjrX#)^iT)Ifq#{Jm;{Ub6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^ z4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~ZTI@6=bUyu=dhl0SkF1E=N#5^ z4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX#<~+fZ4C^_E z^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^#vr7~8*nsplNla}Mh{hxMGp zdd^`z=dhl0SkF1E=N#5^4(mCGSvNe)u%2^R&pE8;9M*FV>p6#cpTrXm>p6$@oWpv~ zVLj)to^x2wIn4VxK69A&c|7N^o^zP%0-keN&pE8;9M*FV>p6$@oWpv~VLj)z;|aGv z{%}~&IjrX#)^iT)IftneZ#k^z9A;j4&SB<@=N#5^4(mCG^_;_c&S5?0u%2_6T&!Qu zIqiDRVLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z z=eGO$(sNF`o^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2w zx$Stu?Tp6$@oWpv~VLj)to^x2wIjrX#)^iT) zIkz28xc%{m!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG z^_;_c&S5;;T}wUZu%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO} z!+OqPJ?FOL3AaD~a9Gbdtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c z&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!-Fkk?9M*FV>p6$@oWpv~VLj(C^TKlu>p6$@oWpv~ zVLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxy!#=N#5^4(mCG z^_;_c&S5?0u%2^R&pE8;9M*GgJDza+;}3`RoWpv~VLj)to^x2wIjrX#W?p#CVLj)t zo^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E z=N#5^4(mCG^_;_c&S5?0u%2^R&$;b*!tIYg9M*FV>p6$@oWpv~VLj)to^x2wIjrX# z)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4p&(m zo^x2wIjrX#)^iT)IfwO}!+Or)V>WrtVLj)z;|aGv{%}~&IjrX#)^iT)IfwO}!_<$@ z9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{ zhxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&TYpNZh!pYu%2^R&pE8;9M*FV>p6$1 zAD=m_=N#5^4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX# z)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMG>jwjsy_`_j6=dhl0SkF1E=N#5^ z4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO} z!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0+wp|kAAdNk=N#5^4(mCG^_;_c z&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5V zb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^ZabcE`{NIX^_;_c&S5?0u%2^R z&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhoo za}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&TYpNZh!pYu%2^R&pE8;9M*FV z>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGp zdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&$;b*!tIYg9M*FV>p6$@oWpv~ zVLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0 zSkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p8a_Pq_W@hr@c#VLj)to^x2w zIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^ z4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)z;|aGv{%}~&IjrX#)^iT) zIfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c z&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjra0c0A$s#~%*sIfwO}!+OqP zJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=Nvxe-eD!jja*yQ|J=pHN-E6@ z-nQnjlAqrWe(dODO3tes-!bul*WEuDA9(NMf`?r*sN~yof-7tsQ1bJ&!IyUFU$W@- z;9k@Fmdw99xcVbU<@Rg0>67~(bW*Q8&gI|r$m75JukQJ{s}~-b>$(2RZn@5PCw9yA z>u+a{v_G7fk)tn*=kjhK+)m zukEaZ{aGK!(W6dn`qg39*?L%i>m(QJKlb@4Y5Z>Y7WI#QY)U$DNbtXJo|3Mg6MW98 zQ_|??g7JZuZai7^uk*p=bo4jMgj~P=cGiLRbJi^? z>ZE_S`+^zg>}kP_e@Cxij(b4UVCtDzA(%RkTwnTmq;yQ`pYc&J^E!W3F!QyYb+A9{ z<2bCF#o8010Nb0j6d+h>B0B|7hV>OKXCpP!G9ZEE4T0b^-j6}jF~&-aaJ|i zDUZMH+cooX|9WN3T+gm2*35NY+_h$||B6&I&x`hFt4ICxzx=%=#hNqDlM8|w|C=en z9QWMb!PK*)RWNnVsvS)I&sGd(UN4plX1=zw4)$k#9EWvteEsU=#X4IL>u;UpV*Qgk z)kyQU`)5)A^maAUoCAZ`)~bD`>+Y$VF6$NiP^y~Sk62M9_rL3;DtVj=m8#_NTP@i!ANPjS zcg*#4@492I^TB32=KA%wvktW1vtoWxC;cbS4Q8A>P6%fFx7!7C+_8TNrk-2A`bY7% z)Op4m!PI}xvS8+Q-xI;i*LK#y{;ZGVux^g8U!6KxXX|18t&?1=|EGs5r_N=rDC#M@ zsB&tvU-0NTmD9*^!F7(Woc6sn7$110*MskQwNje+OK`>Ul~SjAR~F-(T)9#@scmqX z8!DzY2L;z_UNN=o8ob|Hv+BxpGcLY<<&{4tExqXLV>YrFIn0ZaB8q9oc zXC3U%`Zx~j=J@*6sgrfK9@gJF$;JA6Uw1;f_Nu={owH6zm#heWX8Z~1sq%j>+Q%P! zLYlRIFh1}TMg><~bbMMdEBN@Mj!$#%4Sx2^>|y`+}h{FZ!Rh zM=;~u`rReP92x)Br-M1}3D*Tv&vj=6Q|I{Of~o(XM+GylJ9`8(U)xy+`?Efd!@4=X zes$_(ovnxUx6VPOxmf?o*5guzp*IyZf6`=J`tOy&-71YsdoK_Eb>%5(W7(UFKKQ_2 z-8*#YIsJT7@Wy##(|>LYuG?yCZol)%F}eSa zgT~}>M*TKAk3VPO=zQF=qetg@?&&Z(*IB#%=v=@4cGiLRnvG*F^#9 zT&#a``)$&PKTI#`pV4BQ^lHl)1+Uv-n^a*$@U>u+ZrX#aX?%#r>N&J1RpFM0Js+(Mrq0Dr22=l6_Xabs4R-}IU)xy+`?Efd!@4=Xes$_(ovnxUw@z}gem>7% z{>t*AHa<6=Qz1Mye4bo#Kro*(FZgRPpFao93+8j_vKNB+yn5NXU_Qq_v~_rC_>VO!>xzU=hn&RcI)T!yz`>{#w%lv^grpC zV8*#-&tS&KbI!VPTs-G6_24;&sT0pRO#OJyVLj)t{&QF_I?VbwjvjT|^{d0Iv-Pn4 z)=4hZk5gTLFRZ^8*53>3?}hdE!uoq*{k^dMURZxGtiKo5-wW&Sh4uHs`g>vhy|DgX zSbs09zZcfuYdij4`{VD0_4mU1dtv>(u>M|He=n@R7uMek>+gm2_rm&nVg0?Z{$5yr zFRZ^8*53=87x`|^W=Ff(!Da`W9c*^6*}-N9n;mR+u-U<82b&#icCgvOW(S)cY<95O z*}kQ?m(7bDb#%izx?vsNu#Rq6M>nja8`jYc>*$6zcXWF!*3)Cb9t-wZu*ZTu7VNQL zj|F=yj_dE+u)lA^{=NYT zVRMAd5jIEI9AR^W%@H<7+qZ=OQ*ciDe?Zv(1H%3v5cdCou>S{y{XZb={{dnD4+#5z zK-m8S!u}r+_Wyve{|AKqKOpS?0b&0S2>X9P*#85<{vXhG_Y3}`?{{oooQMC5&5=Il z2%95pj<7kx<_Mc3Y>u!w!sZB@BW#YaIl|@$n%r0``6h*!v}5@0WnRUjp`i z3ESOQ{g1vcym@gRZq8;$yV=2J2b&#icCgvOW(S)cY<95O!Da`W9c*^6*}-N9n;mR+ zu-VzZrQGXcUYwKOR|b1u8SH&!u=kb0-d6^DUm5IuWw7^^!QNK}dtVvsePyusmBHRu z276x_?0sdh_m#okR|b1u8SH&!wsT*Z{kg9U_P#RM`^sSND}%kS4EDY<*!#+0?<<47 zuMGCSGT8gdVDBq~y{`=RzB1VR%3$v+gUyR`a&tC2+RY9&JJ{@CvxChJHapntV6%hG z4mLa3>|nEl%?>s@*z91lgU!zNE#;m-^CCy@zlFX37WV#I*!yo`@4tn;{}%TCTiE+= zVeh|%z5f>W{#)4lZ(;Ahg}wh4_WoPg`)^_IzlFX37WV#I+qwVN{@i~Hd;cx${kO39 z-@@L13w!@9?ESZ}_us-hT^w|1IqOx3Kr$!sf*}xjCC1?Pdp? z9c*^6*}-N9n;mR+u-U<82b&#icCgvOW(S)cY<95O!DeUsmU8d3d6A>fDZoCb0Q;N* z>~jjR&ndt@rvUq$0_<}Nu+J&LKBoZtoC54~3b4;9z&@t{`YTVRMAd5jIEL zw}j_S$kFGyV4vrLeVz;Uc`n%JxnQ5?f_u!w z!sZB@BW#YaIl|@$o1^Vp!gG1#=yR`dr(L_GE*s;!kI%i*?sKoO&%MGv_X_*mE9`Tx zu+P21KKBay+$-#JudvU(!any3KYaD!X`d6KHlKT?-RE9mpL>OU?$vgld$m8$y}~~C z3N!v~6+S82eeRWZpL>OU?iKdASJ>xXVV`@2eeMT&&-` zI1m39nYTVRMAd(e^Fj`DHTI z4*=^2fb|2w`T=150I+@lSU&))9{|=50P6>U^#j2A0buj!}K z1K5rq!2b9FVEq8FegIfM0IVMX)(-&d2Y~eh!1@7T{Q$6j09Zc&tRDc@4*=^2fb|2w z=EZsVzt|ku{X37!XX z)T09HQGxZSzzji0O~Lx6V0}}tzA0GW6s&Iw);9&~n}YRC!TP3P zeN(W$DOlf>?f9nbk8cXrHwEjPg7r*a&>^1*ufV7+{>UOreaAFP)T*2@R$<%9L|!Fu^% zy?n4Mk5e<`fL6xLq~>o0}%m%{o>Vg04B{!&Mlp@t4{ke<`fL6lVOEqn^pf?X>*qf~n`J z9>Mxc>94;O)?W(iFNO7&!um^L{iU$}QdoZ}tiKf2UkaNS=j7&WcC?!vY<95O!Da`W z9c*^6*}-N9n;mR+u-U<82b&#icCgvOW(S*{?OTd_*1X73&oiv&8P@X*>v@K6dZd4x~=QKUfwCj0>^*qCRo?$)Du%2gF&oiv&8P@X*>v@LtJi~gPVLi{Vo@d+fJlh}7 zGpy$s*7FSOd4}~o!+M@!J}WST*z91lgUt>$JJ{@CvxChJHapntV6%hG4mLa3>|nEl%?>s@+qV=)w|SAHK73do zKCBNP)`t)4!-w_Z!}{=HefY3Gd{`eotPda7hY#z+hxOsZ`tV_W_^>{FSRX#D58rlt z`1Z$#59`B+_2I+%@L_%Uus(cPA3m%PAJ&Ht>%)ij;lujyVSV_pK73doKCBNPHZRV} z&Drc|H#^wuV6%hG4mLa3>|nEl%?>s@*z91lgUt>$JJ{@CvxChJHapw5l)VhhiyYlI z1a{vL*nLA__YHyFHw1Ry5ZHY~VD}Ay-8Tew-w@b+Ltys}f!#L*cHa=#eM4aP4T0S^ z1a{vL*nLB6XWtO}vu_COz9F#thQRI{0=sVr?7kte`-Z^o8v?s;2<*Ngu=|FE5Yus1iQZy?EXry z`zyijuLQfl672p;u=^{)?ym&9zY^^JO0fGY!S1hQJNqlypZ%3!_g8}5UkP@9CD{Fy zVE0#o-CqfIe-RxkqgUt>$ zJJ{@CvxChJHapntV6%hG4mLa3>|nEl%?>s@*z9cIQuf9&FLHDrI@o>aVE3Ve-G>f# zA3E55=wSDugWZP?b{{&}edu8Kp@ZFr4t5_p*nQ|=_o0K|pVcu^^k1vkx8YK6EhST(e`eyAK`h?n4K=4;}12bg=u-!R|u`yAK`gK6J4A(82CQ2fGg) z>^^j``_RGeLkF7|=j7&WcC?#aaSrdgZ?RUe*}-N9n;mR+u-U<82b&#icCgvOW(S)c zY<95O!Da`Wo$Xu79)jjYj_%h9yI&{lex0!Ub;9n~3A?0%iF`*p(Z*9r4mH2ZbJ z?$-&sUnlH-ov{0L!tU1zyI&{lex0!Ub;9n~X*>H}+MoS8VfX8V-LDgNzfRcwI$`(g zgx#+bW?t;q3A?0%iF`*p(Z*9p5{C+vQmu={nw?$-&M7w6>WY<9Gp9c*^6*}-N9 zn;mR+u-U<82b&#icCgvOW(S)cY<95O!Da`Wo$c;bO8-CdUaRIsj_zv=yRR|qzQ(Zo z8pG~u47;x}?7qgZ`x?XUYYe-uG3>s^u=^Ur?rRLYuQBYt#<2Su!|rPgyRR{P=BZn! z3;H)IUJJB)y`w+-8as~HJNGrF-F=N=_ceyy*BEwRW7vI-VfQtL-Pag)Ut`#PjbZmS zhTYc~c3)%IeT`xB;+))^&5m}ngUt>$JJ{@CvxChJHapntV6%hG4mLa3>|nEl%?>s@ z*z91lv)${R+0p(-+>_e8$kF}ZVfTNB-TxhS|99B^-(mNEhu!}jcK>(S{oi5te}~=w z9d`eB*!|yO_kV}o{~dP!ci8>kVfTNB-T&Qo_J6nkTWy2g|DAUCe}~=w9d`eB*!|yO z_kV}o{~dP!ci8>kVfTNB-TxhS|99B^-(mNEhu!}jHZRV-&Drc|H#^wuV6%hG4mLa3 z>|nEl%?>s@*z91lgUt>$JJ{@CvxChJHapwN&i-Tvn;mR+u-U<82b&#icCgvOW(S)c zY<95O!Da`W9c*^6*}>*Tj=Tn+dv$PePV%0)@Sq_D^PX9IQ84eB57Zu7wDX=hcv3L$ znQfj6<~?)ScE=Qbc+afaA(;2fJNpImo_Xu=VBRxr=RMQ@yk|NN@0pIzd#1>*;Y>XX|18t&?1=-@M3ib2dBL%?>s@*z91lgUt>$ zJJ{@CvxChJHapntV6%hG4mLa3>|nEl&CYh_ZhzJUHapntV6%hG4mLa3>|nEl%?>s@ z*z91lgUt>$JJ{@CvxCix*BzfZe}Cwt;vC~U!pF@<7R+~qo^ylwj__5PQAIo75oQk! z<~zcuyMy_T@ay_uz9SsD%jlv%-w{@)V7?=~+clW)2)6Sb!Tx+la2&oPI6mJIJTBi6 ztcTD1*2#AS>*qUy^P;`(p)p7L-}Uy0qBh2@#H@$k#H^Fw#H^p+#GDuH zUN7kHb%b%ezA(Pm9ggeuhi4?Fyu98qU)xy+`?Efd!@4;>>*;Y>XX|18 zt&?1=-@M3ib2dBL%?>s@*z91lgUt>$JJ{@CvxChJHapntV6%hG4mLa3>|nEl&CYhO zcV5(PD=U#VknqBF@qP^MA2dBnI20uIe zkTmhE;I=CcN!wo=Tn?bDh6E+cnq!-K$;mylD6P9sT`&$2c8cPDTBUKj)NSj=Qu$F!k*DUP;l1I#(_X zrv8I24Q5{5&I@L~wzCfQXMG%pb#r{y)8n$v*2DT+C%IU^d6DDhY<9Gp9c*^6*}-N9 zn;mR+u-U<82b&#icCgvOW(S)cY<95O!Da`Wo$Y?VGdtSN4mLa3>|nEl%?>s@*z91l zgUt>$JJ{@CvxChJHapntVDsX2cX9W=>4An7iu*Ul_b=U(q9pj!34POy{=q-q);Aq` zT5#JnebcN9gXgvHm+rbgc=?=u>9;$BSO3y4m0c42AoEc{i%;T?LJ}@7*#g2n=JqL6el*R+!2HFyl6jmn>a50 z*L_~Tm@nfrekGXkS3VfbaUZ)Sn0ii`9Za30&kv^l9i{~{uQ_K0Ghf?T2m7-=j>Eb+ zKI`dmS!e5E{jHN+tlzxIadS31+RY9&JJ{@CvxChJHapntV6%hG4mLa3>|nEl%?>s@ z*z91lgU!x%=5Bx11U5U^>|nEl%?>s@*z91lgUt>$JJ{@CvxChJHapntV6%hGi`QNC zL#Cz=zTT!d4>xw7np#&XSMVugrl#9>51w}2)HJSB@T2cdO%L}AuDR2+^ycW`g@;T_ zjn52jKY3bec0us&_e@JOFAZM)`LtAKR`A4Krswt(`cKdO*Izt6k27=0^gRC3kEiG3 z4&Hi3uIKo=Gjg5vo6X4eS8X{X&x`hpUyC`?zuJSrjMM%4V8-8iW-!NHb80a4Ts=IP zI%gjpO#SV<2Q#mwM+7rp+gS(uvp$Z)x;Z}U>2XtX$^lU%IdyvT8LHaptQ4mLa3 z>|nEl%?>s@*z91lgUt>$JJ{@CvxChJHapntV6%hG&UWT*f7S#xJJ{@CvxChJHapnt zV6%hG4mLa3>|nEl%?>s@*z91lgUyTA-LR)lD&3D}WAQoa@Rv_YH@_3SWbH}mvK@af z+FzcEY0+uHlNOFlpI;Mv>vp5k`40y#88<3j_ImKu?~h7dKMr2gqjX=J zHNowl7@gZ|v>cQB?|J2zJWjvw#^mvzIcRJ??$+mx&Gpo{e{8Pvyw}F&`cGNKK07fN z+IycAO#kCr1vAduzx`Isk?{|FC79z@njcI(V`c_Z=W!u1T(J(1_m=<+gS(u zvp$Z)x;Z}U>2XtX$^lU%IdyvT8LHaptQ4mLa3>|nEl%?>s@*z91lgUt>$JJ{@C zvxChJHapntV6%hG&UWT*f7S#xJJ{@CvxChJHapntV6%hG4mLa3>|nEl%?>s@*z91l zgUyTA-5I-1O&fQ5r8xIaXg)Rlqi67&hfPgaoFBYq^3>Gu;o!y(PfZVe5&V3)Y3Zvf zD~i7z)^=LDq;>GR5!2EYhX=2`VOlzJK=AaprlkXi1~=VtdTy_E==9wGmMPQoIQuP_ zp2r{e>hyfv9X3qQ_0+03BiFg2RN`;_&(xoh=S6$p50)2o(tpH1gBfSl_+ZBG(j}PV z?$98ZddB_sa{O&+ohN-7O#OGi8O*$vyc*1WZD$?q&-yqH>*n~Zr^jWTt%vouPI9q+ z^CHL1+3aXHJJ{@CvxChJHapntV6%hG4mLa3>|nEl%?>s@*z91lgUt>$JKLGN{aF*( z>|nEl%?>s@m^#S|nEl%?>s@*z92Q;&s>S`Uz?F%GZnYYXA8Y z(*D){UGN=GPe{!U4_^BHgmnK|!N2S?F&(imc;w89X~w^UulQtQ+T}mNcN{(`HQWA; zVw?*fnv_1S8~jew)6-iGgPUA?dT!r#yUDqKy>XNCIETGFIgkH9{VDml-w&OV>)H0w zDY?#x3#a7zhdnSQ&x`hTH^&_5|Ldq=#yPcpFyp^lA(-Rd`r&Iu{nWGVu;UpV*Tbtj+?XD(QbCI*}-N9n;mR+ zu-U<82b&#icCgvOW(S)cY<95O!Da`W9c*^CGk5#5Ca~GTW(S)cY<95O!Da`W9c*^6 z*}-N9n;mR+u-U<82b&#iUcByhy6&WO?bY#GDEp6-(m}5VpIZ9)vvq|xi*xUs?@mff z_YZ!&?a0(;RPbKsjZ7EK3Lg0J$kg=S;BkkIO08cE?(yKLwDz4~o>~6j{ot?Xj?V2b zl^>J)e|++oJkDQU8k5IAv)pptI?J6HO#Mgp3ua#Zdj~UL+gS(uvp$Z)x;Z}U z>2XtX$^lU%IdyvT8LHaptQ4mLa3>|nEl%?>s@*z91lgUt>$JJ{@CvxChJHapnt zV6%hG&UWT*f7S#xJJ{@CvxChJHapntV6%hG4mLa3>|nEl%?>s@*z91lgUyTA-KuK_ z`MP%8 z9z*l>?%u11=Jw0CJtp^`KlYeB&g(B6lgIB|cUV5|)WO4YJ(piHEZ14~_F=jHb@vX- z^P=7B1^vB_Fpk$3#`n6zalIZZVl8g157ddXuW=Ff(!Da`W9c*^6*}-N9n;mR+u-U<82b&#icCgvOW(S)cY<95O z+3xku>}WST*z91lgUt>$JJ{@CvxChJHapntV6%hG4mLa3>|nEl&5PIFq8h#P_n_-` z?w!9MRW9kBzc)1)+dF@s8hlsp{5|XWjlJ{tuO9~W$=}N=Kh-CHUt7EPQTcn^e)EpX z-|sH0c64qZG5zS=|E$lC&f_dNq;DR7rz=bU-?8a?<|nEl%?>s@*z91lgUyTA-MqQo z)9|aFD?U$Nd`tJV-HPB}AMc)i+V=UP{V(5kPv>+9KB9GxRC{Fb;u$?s&&z{9{h&ws z`d`7nbm^IXd_MS{`+BB(-VScMd#`lcd%>q))hoC6E!R8uA3LUZ9%t_Jz4Q3x>-5RT zJ-GB7ww}Hh_sMlG`)8kA|2>QP|nEl%?>s@*z91lgUt>$JJ{@CvxChJHapntV6%hG4mLa6nY;a26WHuvvxChJHapnt zV6%hG4mLa3>|nEl%?>s@*z91lgUt>$FRyn`*L<>geev2H-6NRS?7*49yp}&*9L#I{ z%+G^)?JwH#sp4;WPw3SunD>f-hXwN%IR(Q78Rd%nxRqd4CON{K|&}bKE!T1yfJEUmuUZEv>V~ z>R{@h@J2B6nzkaC`P$Ap*q`-r9M;Y8Sx=A4I$ICxZ=K{~{k&%~FLK$ zJJ{@CvxChJHapntV6%hG4mLa3>|nEl%?>s@*z91lvz@uypEZHa4mLa3>|nElsgo>V zvxChJHapntV6%hG4mLa3>|nEl%?>s%zu)b3)Y9U-;vs?4Gw>rP2lLtZnVG?SW zdt5%-TMwW4t&{Hv*3WkY=SBPZb)$azU%mQ~qJGBN{$Ih2KXFDd$L%yQn0jvBFPJ*7 z-X)m&Kdc(eyw+_W%zSNU9qiBgI1cOP_^hYLWu2{u^|wxPv3|ZIFfVf4oXw7QvxChJ zHapntV6%hG4mLa3>|nEl%?>s@*z91lgUt>$JJ{@Cv$LJK+n+Uo%?>s@*z91lgUt>$ zJJ{@CvxChJHapntV6%hG4mLa3>|pcab;oZkyI=WmaUSy9%kt&H{3f%sT%1e%R?~IU zxyNrf?~jOfe%q;WSunr(+;>kfzXdIQE|}klCcG8QZ%3n61@oJd?flkce}02<9DbW} ze15a?xcru7J^UtSo%|+d{ro28yl9^~B<4l`OLq@uoNc~aQp}z4PkuU>ypn0n@( z5lo$z9T!afZygoPygum>%zSNU9qiBgI1cOP_^hYLWu2{u^|wxPv3~O+$IaR7Xg539 z>|nEl%?>s@*z91lgUt>$JJ{@CvxChJHapntV6%hG4mLa6nY;a26WHuvvxChJHapnt zV6%hG4mLa3>|nEl%?>s@*z91lgUt>$FJ5>2Pr>T~|7-Ai!T%tXACGR=A1Eg z^=M{u=egghci+2rSH1J9&Z#=(Zx4EQj~@RHvwKWb?k|+HkoykhGUR?lIS#o`QSL+T zUz8J(`x@m+r# zsJz@qs2;h$Q2lb>p?2kdME=Nqiu{!O7x^#uHR_k#@2J1hPH~XsDL%3uikqyT;wjsu zI7@#h{?bpwqztoF#RI}8M>{2^osU5M@j#z3(EVUz++7V0bh^2PK zQafU)9kJAoSZYTswIi0=5liierFO(pJ875aJE8-3p719hd-DD; zAi$yUUNQBIL*aenY(9qNeP(uZ$HM!`my;X|?=9VY9SiR>J6-z^d!yn`h2;;LIThB^ z%hsu|{?(pNh3(dibt?3y(M6|1KkwglD)j&ABd5ZCkzL*gQh9k#NcG73L#kiiD^k1i zzLETq_mJeLyq_fh<-H~KOWtQvf2Ez`Aj?yHWIYr&SwF>7wo7rA{!sj-pQMZQU+P6V zs#$7BcBvh))Q(tcM=Z4?mf8_Z?TDpz#8NwAsU5M@j#z3(EVUz++7V0bh^2PKQafU) zowUpQOsO5&rFO(pJ7TFFvDA)OYDX-!BbM3`OYMlIcEnOUVyPXm)Q(tcM=Z4?mf8_Z zy=dMQ$(vgE-G0xe))r$H6#TwGOoX*XPI>|NUq8*Fs8tE^dkQWg(=C3VF5sOdXIPxB zSMd8UuKQg(Ml2|_+v*k-mJckoq_7^Z z14|3*53abpu-#{!R}}iQy7bCIKhw6ZEcCyHeq~|5$Ub{^<9>ym=H_th^2PKQafU)9kJAoSZYTswIi0=5liierFO(p zJ7TFFvDA)OYDX-!BbIv6yqoO)$$ZGAI%15iYFowP?7W7eU(!zHrJc%`n3ZWhEV|(D zTW((OojL1NO+0Jw^V+=ml>)YT{nEVWs)D}@-KhBs^WN_Ig}Rl~%^RO6V6&VIbN`_QeyV+w{*a&2A7beb zvGj*n`a>-JA(s9SOMi%^Kg7}>V(Aa@Kl4W&D=O2!TUCo^H_MCuO8#HjGmh4=`2MS` z&?5dR|GO!kl@{FJvAKo!=7QfrbJ)N4izlMl+6%avq*6ZwmDsJ{Z3!a zE2O>_eB0@T`HOF9g5ABYn9nIzV7JdYZay(fVT&;Hm->QdeM)(ozZ_mr=jA&N<^w`A z#a)(~Wq&DdvcJT#zr?b?#InD{vcJT#zr?b?#InD{vcJT#zr?b?#InD{vcJT#zr?b? zf|dRf%l;BuXVx~qv+?^s^p|v(c4BoL2JhIU+r06EC|~i=bY0xcf>=#(?y0M`?xV2R z2x*~vk@!jQ)00(nCN;7IUtC;5*UvG zOEX=WiTQ#(QZ00q1HK8yrBiiFjuiO(?<@bAbwq?-(XyL;U#7GVyl z!hXxLiiNNBP0@EX%XY~h*)Fkcmsqw-EZZf%th7rk+a><5+NGF~4;37a7y3i|zp`g& zt5}rsI3~*UFHyx}#O|YlyB(@*p@}*o>QS>SPyYN@<*D5lQy-iA#0?Vls5xoo5Q{}= zorV4Gih&j*>zD{WpzCXKKC`Ld4-dLqMDM6CxW-D2MVv(~!OePhws>2$n&56r+E@g4 zsVq3RM-z+r2^9su$*gVR7hJ$@$0}Q3ZY5#&zhBxSC8nz27M?~HmPcy}zSlV4yzKjW zf~VBaG=I^mz=t54H1n+PZG^qSUr)`yeeWc=@0o|@9~y$-@68^X2QBF(SoV?nF8fF< z`$#PNNG$tEEc-|-`$#PNNG$tEEc-|-`$#PNNG$tEEc-|-`$#PNNG$tEEc-|-`$+uH z`bgtJ-QU-fHd&a@FZg%X)I9jpCW{q$1>ZG|e7(uSZc)MaNRy6mdq%;(*CxwTTe3W{ zEKe-U6aTaFMM!~u7*?mWg(a{BLRKdvtoC-Lso0G-b zu?2j2sFOwemIW;9As=Kt#Ihb@Sr4(ShgjA_EbAekV`kQ|n9--9cz;vZDeY8V+Iv~Q zZrr)gXGrhBkpF%E(7Dgzf8fm57x8CgR#PfNe96OEGwRo4DEjCEX7wor7c(!y^X3=O z&tw2BU3U!jzdDbjjUC|eg>ZOS>;l$_4+2LsUkF@z0o_I&hu-ry!=hRjsVyekQv0B8 zOO~N_O=DwN{%m*AZl^4F=Cpc`XcvEsV-GUoM7swYHDHT^Pm6XfHeb?TYIjSt`@Kj% zed+Hn)a^2*zlA=i+af;Rs;Ov;xXPVy4fT<@dDSXr)JJ0fBeV3>N8wEPPgv z!@qINQ{P2@2bz0oy7*=aP7Ey%o_?ky%e097Ftk`s3aF_X^kkBYraM=e2 zz^lH375@eQU2{a;citA0ZE+u%^nv@vq;K43CVl38VX`m0k9yfhwV%W)t^bz!b>;jE zR%2o_Mq~I?&Tv4QNJ?A1S?}turekED`Qo#GKK{! zeuDH_rSE@xF01>_V+K5SqJADr;4u|C(!Qk9m+V4!rM&QMe$xh8S;hwIYJbE$5@o*a zs;2cFKVFoH&Mu{$-!xco*8yL^ZpdZ9{7>Njt<)0?yqtmh$e#oLykK6RhSw{&m-Wmh zygg~xOFOkA%TqhD9%@I{Pk+jG>F3fPdQSRD^-2G!9aX=`E@GmT2l7*?N3c@AV5MEb zia%PVU*xA?YKP)QcF)r*_E8*(mHx`|6bHe)9*U1(C2q1^il<=uIhCV&=sAibF|{N8 zr#T_l$-is;QLkx#(+mFjqRb`sV&0)_omcw z%>Uw}EtN2w5kEKa&|0}%6&zc~QQJdX!$9`mZDwhEH|Z&u|EcBwEtvmY%gYJo&jEj4 zFs~1Iy@ETHir&ZDlXfQU)Q&7q?Z|ql9a%s9Dchx=OMmD&=_l1E{ik+l4l4a3J1G64 z@`9Cmv`W9Ie!)t+f)#%RD}D;5b|_x-Z1AW3p%h1ArN6Q~#X+zVAHmcP#ZhUO;whN> zLva>N&q+V29qGSXudEF&V*QMLhB$T9T;i~`rBCCSX8nYwTdtf#^%|>YWnTY#y)9Vh z#aj2Tw%-2l=v&_1QTsmdmp;73Nj&y$h1O;>W5m-B4%c2}mh5_mvv_#vc&*O1x`FHs zhFEB)pSmFIHn#1xc8~iAd&HAQ+GM8+1}Y!FGzXqNpDpYOCOJ^-Sw~@aJF^blC)o@8 z^m+bp`^x}f=i@G9<3=Z8-)(+flQ({hEYDg_sbyr#baWSG2wAA$T%o=4aK2e##jTbd(>a09#G;&sboTZ)ODeEU)WIYsr zVOMk%c115?S9BM4MPFf8#);^!G9E;~l(8h@ql_P6mupVznn&aw0mO2RB9?0xF|BR1 zrV-1vj##dN#I&~2^Tcw^Bp$ChLVJX?i#1j$PkV&0%Qczoynfmvgk9Mq1k1IZ%JApJ znoq3k5yF4oj@TnqcBU#XSgFTAcBOv7O1pv;e*`OggkWWl5UlJG(k}Kys#A%Buq*Kq zti(;Q5>LTOoCPcK7k(;xgkZH^l4-9|vn)?`Sr4(SU$r+Gh^0To(obUPKe3{tDF5%h z-cju1O56l1Ito_eELe%ZcqdWs^<66;6Z<%gle(4(+FKv&fOu4mgWBfRzX?u`4$^k5 z{Fj#O`ql2*(28>f)1UO;WT&4~IbwQ_o+qaIs9xeKPCc4Zdy1V&J1@^1k5a#2rCq^_KY|rM1@m^u zf5ADwZttV^RQ;9ZDGq{__y|_wCYbt1?a{N;Z)%U2;z8{ZQ=F(hVmZHvrH;f>Ut*~{ zu^bP?a-0w=^Gi$o?{(5g#9Xd3s`v=IT$jlHf4WZodwvy+=l@scms&4kI^UhBb(pVj z|G~<91hOmhRIoCCwPaW3wP0nw3s%+v!L)AC^Hg50lf?FObz+@V>|&iHR@NU`k60(k zuB=zWuEbfeTqmgvtwYovv9cZt=KT`uq{_}z-Cq68||Bd|CRNc)_b_N zShADwvy@4M_V$8aV(d+Bo)1YC0)_o$WNq!-(Y}I%Z*4TR0All_V5DS0!9jweD>g1gv&utYlzem+Y1oRPQh?Tq*EZAYAKgT^@}?|YD?{dx-D6T+EwyUqFp6dE810ZwW3`mS1a08 za8EQoGBk9+EsG3qFp6dE810ZwW3`mS1a08a<%GqDF;gZE%ZS$#YABy zSrv22@5q=_u2#mJau%bZej2SBk>^0Sny;xYWp=zdIPr@LaED%YS>kN>}Mu8FZk zZK?9qI#vE!r^;*VRQYb5Di5wx<)`Ev5qHFWFze=5={wW8Z!KZB<7}a0VA_JB_x+8S#=Kl%mhE-Iv&|N7bSb0{|L%9Pv z9#lC&ohnzTQ{@nKJf|shi#k=#QK!m9>Xck9`Fa?Rk>j5m&_4M ze+*P!@l&vps}+pPeJEEe?J_ql;~?xxd;}|TlkHMGr9Uz!F5@rks+`V0tZ#qUTBKgz z{)cOC;TryTjZgKM|DVi9^}PNY*Pp^Q?SHb~%KIgL*Q%5EOT_YiiCEq*5zG4}VtKzr zEbo_y<^2+|yoV>I{hiuV>@wF$<;6Wb*?B#bs}*H<{o)>;?7Ur>OC^6OS1ZbJKV|Nf z{FgadUQc1JR@y1=O#Pzrf|Ys>h?Fv@>5v=$rSl+|avmZv7QLa|n#XUUPl{ma(_A{S1asFu9k9t zy4l+^n!Dn&u&Z*Q)Gp;}g|&F;IC`4qEyz>`EL& zc~x#&cW3pSP$kDL<0H#cu2z&+;wkHwIdq*8e_>a26y+7Ygk8~H`YChqa-4|%D&s-) zOBqWdKFatJcDd&8`*68OP;Nr*5rXB~MRvKS5v%Uf*LJeYHJ@17BZSY?4y~DFmwlvlSk21X3uIT;WWh>* zwPaWND_H5TVA`Xo9FS^@6UBF2h2w$ZBgcsjf)&y@t5rcA3{8rgr39P~{(W^1fYFkAYa; z&lAgg`+|BzURaco_xxm+_y5E$H6~ELLzI#E0ICVJ46|Ik4<)&k07R>EBRCM zlky#6UMu+y!PJhbUou}T%Zst0)T33^FIZ_;u#)c(toSKd@n5i9H>e&(N8y7Uw`7;& znOGSQ24Xq>iIwpq?D8Fw?Eebuq_TdBxbc3;Z(yij;+FUKd{&lk=wVmZHv<@_R+^NU!{FJd{rh~@kurun7h7Nwo?9kRS&r5*#><@_R+ z^Q)kqg84-(=NGY@U&L~LDR%MQf>NHoyAbs&<5{qrUsOiUFJd{rh~@kumh+2P&M%dn z@*1+dU^&0YuGBB$Eaz82Jq6!^5X<>REaw-oDmSE4<%V>s+>lO{SJJ8SN;)OCLU|U+ zlxLA;grBP1jjU7nsmk3*AB0_%8zO%w-z4m++z|Og`6*#n<(|j~nR}8fd{fGZ@t{0w zAU{>PE!mc^t8!ug-Y@Uw1Unw}*e{%KD9Kh-1i>2kdi?W&&r zhc!pNMyXicuDTvnt$V0i_axK0C(DqIYNqv>a`$3=Rz3RaQRk5r`JgcgQ;zs?| zQd_EZTgFP*)%B>D;w+z)F`@FL7sXkyqRW3~b-U_%C~h=1M7zqE5v+^{!Kyl`9@1UZ zuXfX70Y_WvuYoFodfkzyK}+I*b*}WN+nLN{~N;NEHP^LT1~lAMYItUhT@v}C1CQO zKM-X!4AZ%wqr4cE*}E(m2JSl|xSIVQ zNHx7B*w1?j*gCuyJTJQ*96I+?@XH}CnngW~4fL$%*b|9XU5g3+uq{nL+O(+P+;s!l z=uu-SX}3GR339V_OuT5zoQ57usNGr=`}8W}p} z?9@|R9s3tERJFD>IKAck6y6NKV1cHOg_)uk?bFQ*Ik%rjwDBfbk($8D<9X9({!nnhn8iZM5Tf=PcPc5lZ}?B1!Uc6JF< z{kO?O@#3Z;TK%PZnwKqxVvV4D`0HklX8I>fT-WCv_?;XGlaE`XrRy!IkpwMfA4>|Pf}_V|K$~LGda8f7 z`A69LYTi{CR~(Xb#5@tBC`(Bn`8Aim;x9nOE4Blr>|!pzEkg1=7;fL|d;1g{BN z2F}S>1V8TB8rtih3U-~Cpz-_lPH^;#kETCOKMGd&_mXc-_U7peVQ*X3nq~J%6>QRe zJ6n>Df^)25*w9J)1h+eVo?V;lBslo!1NPdjr{IBcZ`hxjABF$bCT6npEt(7N<&eo{ z%&8&zo7_B|mB@S}xc%~nY+fr1MtuxCcY$T!bP(Jk=rB7}WUt_nVcyK=oI&u@AvP>! z#!bN`Yt&_a{ay%8G7r*k{!yTjdJL%N>Hn=U8UOAy%&d^Wvd0g@nS(-M)sP!(O!P1u z)O0<(UHX<87axuFlf9<6coG%}ph562A&jk;;a7BkGRFalqgN9&(@ z8yTwDjKG{I6Si^6cgAo8HhO5sZft(buGAcf4cmmWq?tF^hQ%Xs@U_#dTiXQo>dZ)N z>+ys=z2e1M))|Ejy}z*UXGbyD<)bicZV^M93xD(zu8+dBOk=~l@-6iDT8u`^r^bfc zMLTOAtQn0DpopRVLnCmyIT};4vl!bk7OdNj!IH-xv(;6+;n3zW=y^Gred>J#PCOoi zGr#R+pGMw<9v#PGcFVP_dCzxH({(J?JkyF@d;A^RrHw6IW6jOS;ne{bO`nV^rfuds z4y$`5X-c*<(r(HehbGm{U}MXCcrs`_UiET@svFawQRH|$x<3k93`>Ff#U|j}&MDCP zQWR(>PC&OgX)x-zGju*W0pHZ*>&YB5SYCA^8Z|Z2I$NC5+*~{nck_0_YThz6y)+TW z9W~P0_=M|&8(Cq+ncpFDlL@n1Z-px_ro*c3_Uy$YD=fL<8oUY&XFE+NVM@YbD3f)L zJ@%M{@w43F@z3Y1_}fY7@VF1`i_K*f`%T8wb`Leh?TZ?&hfc z4R2$^{aQAf4ldJh#f;zVNu4Ti@8vYKe4oiCytf7DIUUc>xy$0)20+u`>6qG5&t5k= z0Rg$wvES;QEbznw_-JW^Q>IO38|Hq7UI%Tk=JML?>(F2DDA%S?yQLO0P`~G*=_4M~ zX**}2n{SdPy@ioB`Qr?{RMQNMxpsAi%)~$2ox$2Z4W>lR#1jXipx@9Gm{@!kUg(kn zO)f^kYO7hOotp;Dk2%BQW3$k@Rz5_`GK2VPw%C|!2bxow3QKJpq-L;BCfldT?VT5|2mh0n#B&jQT)bM0pRo{Noq-Sr!| zc2&pB!@*A)utr?FX>s$g=G|p1<9!CZS#dskFArf}>r+{q`SY>n&SW-W{So%+^n7$* z_=Ls&@M0$Q7GMh3?p?bPEN#sKEPuX;;Y6_b^&0$XA%Brp=ZY%pMZN`7vaEFJK5lq z55Q#DVr(~cGW)}|vyWbkmzUIL!-oBWT6v2LwL8##33h&W(ewe2X|UfCY`!~5bA@a7 z`_mHqUE2%-TI9nx%cWS<#~D&Kq(Q*Jr5G3)1@4w9;8$W9I&@8ez89k4=%i(MoompQ?RrWxc-e9c=IxkmNHvYSyc}C_?MeoP>uWV#fxWqQ z!(B~Sp8X0Oz_mN+YtO8nu0Ypi*B~i4oK=FASdwcO@Z}sE>$MUiXShSd-_MzS#!9Sk zzYn-@?OX?}La$~IHNClZ10z=9#%lp)gSmG5{;a}&yWI8jxpu?HuEt@{8nA1tf3o2C z)tGZ{8C%G;D_?mH+N=m+S$3(+cEK9Fz_kmqJHi^CU4wNNJz;mgdokPkYq3+4Y*wo6 z2-bMrS~TI>T`Q8K@9paMHki2>9P*vxpr1+rtKZ`QnF6&Ue)9ggPO zjr(K^M|#_#{p`DJW%~dK46(yuTs!L~C!ktBx3ApE?s4sA4_}Y-Cr@U!^FD*&(0cs3 zs5aZlwHuwkzEHboJvLxS(@UoJc}ySrZ@{ZTNt$C^JILCAC+nKQ0IuDRq4s!{Yd4B( zcQ4u=2S-Ig-jEb{XS@-sb>kYIkAiRQH)8L3X)yhWGc2F95v$kEhg;LlV5j>=9L}{H z-|3X5H`|DNcsqCdr<$&M!^?2(7KViD+f;GDpElni+s%aS>fwM-&!>ZhpFO*>$N`PH zcC+?`vxp!EoEvu-T4bMNmo7SBj*UBba_yexI-t|tK5&<7_p+HIPHFs5Gl6S&W|Sj7 zO%5;{#A^BqnQPa)v=bIt8N$|Z?M9e7 z;UK?cR*7pDGu;U{bL~2D?M8Y!p*`0wq|FG{;iMDxyjM!rOV&G}W}4tqYdn+C}aQ*I)E@!K++5 z(gKhmgL%P;M&;^+=5PAyE|MvyOmpT`<*^e zB0iUG4Bvta8$Q&`;@Vl?-hzW!fY}JHUHPJ}I5^l{KaOiRqpd5l7Y*0~uATctS8V%m z8GDqG!Opn4;zX`pSFYWsk;gVg&SIO z?S}r$*56v-hS6NRGGRsapLe@qC~4QlMpNm$8@h4r`ZlftY1wZ0@LeXe%(8_VP2KUi z?Ois4Yv(q?9d~f;YBW6oeb>8V1lMjp*KSdyJ9=A9X1BR^weP!Q8Lr(6uHCF(?uFVN zXuK7NPc6{yfaO+PwKqw#muvT6%~o7d-weL;bG7qH<4?1bE^kV=h{tge@bI-@DSQ-r2 z_l#?2UB(NCbM16oyRBwk=*qRb!nJ#63qW-S^I^ro(3Mz=~Wu|GnXQqa8c&4cBh5 zy9rx*dIz52+J*2nGc0QdrgQCFxpo^G`r>dt@65S&dk6XAQ?6YQ*Y4OVU$o_G<|Dpl zvIt-P9$2tu?!M!TZBG}hnf;A+VrRZ)TJw1q+-@g^^EGo9*Y2FvPOQ(@%*K4p{OPt6 zpYZ)|2iLB(ekV5P+L`h-(>ZM?PUqUq=4)o_%6>SFYuDCf1S`?Q4^6pt?f+!!%P;c7 z2%2|MMfGh0{V;}W_qwf(X3zycJj=B^#P_=fxqb+I%}nO|-LPiK2ZNSpG zcGDgQ;z0hcvYTtSt85UK_G?qp80{lXMUQn2Q8M? zW)@sKt^J-t?VLmR;GkOOo zU^gKIoAUR}EUw-6%^_HcYj>HyXO@W%!TJ0>Gxex5I6n))bzHk@{EQG$VK27i+Kn?i zr5SC$SDX>zSgNVZoV}>!+I{9{1g-C0aYpFO&j?Xx_TnS1T@*hfJpQs5hw?MRC4NRY z-e@2G=GrCkGs1(x`|ut=Bh27ugpaHD;dy>W_`%P2+57jQbDM{nx?H^Z>Iy ze800d4#gyIcl{Qw-QD(~`0G&vHhRrZ_G?lop18e?_2%chZd*e!gP-pz@$=m@7K(QK zeD{Z+5l+4i#iCq0M}EGWRwazT3uUus9Y!#Vo?-ZbpYK}p^IhM?Vd%rP>&4G^(}TkB zCf9BeKi@fC3`2XaT>wAdjr|&iGx_;0H^UZOnup^TuH6cLzWXsM9ILm|vrvA%J8mD2 z5&V2Nk)Q8g91KUR>62L>uATeCaO}CFHoL^nclZ8;7i!nMSp;S*zG(WGYgcD@1orYy z(tPLI4YG^Cay86gEI;4nMMYp^e!hFjwX5|o0zdGxc^*IC?JT(;OY!qvF@81=@4O%V z`Pp2@&*qJ-_hULgo44m@^Io3&u?W}hIzO9#KCxe%%`Y~-W!f}jKThJ>&GZh}->rTC z+w!xy5kH&v?Q;O5`Pux4mpxm(>;O*WXLCD#HXph70Gb~;3}K(ou@zSi;9y&KSkKSq zZr={z&nJCgEZ1&Zt4QqA>7nN1hN6ar<05gcQJ|TQYgczuB))Zb*N1cMmL878z4sfi zM_fDqCy}`8<}y|-GlShI7loUbhOkEVsq7a-;m{q)thfCUHeps2mf~mgBEP-ZFYhSa z-zb}P>@tEqOpd~1T)TFaa`Z1gN1-#%(-?;H%1p~cRnl{ja;hG-I4a%)o9Fq7@@fnW2D{lH5yAbZ2^yl z{D51H5262`<*+U|1Fl*g!rJSCq4kejaDVk7?0@A1G+Lbqv-TdsqmK8Xq|P7KryRm3 zjXy$W8C$rWdk7nb{erRPHQ{pO7%ZhT)*4OTqKO_7gZcr*v@R_dC6-tbgKbOkb=7cI zZyg+ik1ypz_mHma-lZ74{PHb?Y+lC1}A=H(2BgUR2Fy7ssavHXOUjz70wj zoN*wU{jB~+@Vb+mSf|6K=>8wS?Ci#-q*V}n+ViCT+Rw^@alLWkrIZ4mdL}?~vSUG+ z-xV7}?1+-0OzzM{us!*^sI$9e08DT4La@au2F=@^7ChRdw4vDaAjbL~#(}r18WJO{ z+2$pO@lyXfhJ8=Vu-krzF*>Nep{awVp8u^z*y&Y$!|*i~G&i3e#*g*t8cOy5s+n0V z7JHdhH`H1%0$kg~;sncbhUV|LL!%L~ST(eWAt3iS7_ExM!^2*)+|&n9Cmai6|G5`I7~ZTmp$uKTN~Ih4pS~}(bxW~zV`K) zIDEd&*DSem18w6qahTNqwr26`y4nFjaoFa05AY7Cq3wDm4nH?=gQC4FXs^7BLyIS| z@T#`4_HD&@92js5{3^bO1zqFu`r|C|&6>uFCyyx#n;1Z?x7 zrglr`j_i$90uHNRN!#KtN4Cr{0WH@Q*JcMrvXciA&>`R}_?JA-ikwftu3^uB|DU~n zk$|o}OSO#R_xZ%(eM2=FPreCG>Cyz=?#U5cF?SK%>Hbcz?T$crWqe<-q4G(1*&|u- z`WuhHH8@=G(;m5y_`+H6mUqRphlBeH9_LU_yEY+5Lv7U=U0EB~q`lz88CA6(KULF{ zz5B5$+HuD}2(D^bQR~*LA0zt_^U~VyDXxO2?JuHD^okL@?`ReTzq}xLU33hzDIEtl zM_A&4VHY6l)DH04V~LwiJ%YHmv*B%)C4Q>;9vu5Ofhzrm;>oi)V9>;Bs_YtyUOZPa zE@p&TnYTkR`{GyVwsobxOSfT|*ya;B%`U}ixD3M@7hXWIox@p&N5k+`+3WD|qAPP~ zKO8TgJr1@$`&r8k!!h4K5WKo2vkxi5agFO**!ya4#@ST3MA&dFMjl|bwEtvMsYi3=1 z6b>2gz_u*D%{opPg$LS%up7NjvPw~-u>D=ezBUhI;a^AL%Yd6~(L-mJ)^9ZKOMJ!d z=JaQ)c8^AW7-e>Qf9sch9F3+U^4P(M5&CD{$Kai1`Rq*7c(cf@V^I4#n?2flTGNN$ zIsb5Y$A)(@f$bf}qT9v?Y<0IKaL|e0Kd(Q_2CeXiop;9Kff)zck-v_>g(l4xePCNuf zM#saDVH0styYq0e*G{+^I1v*cJcNY)^Wpo)iD~T#7xM`w8j7*Dn`3cgqZlzkb6;EtrDu zbDnC-TYq6ilc%8eLS>C>seHDn@>D!JHhIXRi-20sNuGQY33s==C7&V-EWGtuaTpZ-uvE-aZn6JP#XbIhHuGfu~5 z;*yI#8ckL%EG#w)Q|DKMQd2YG`Pf<5GSdn=R(S^H56(i{_uHU^>t)FMH48r!kA{@M z1UNIq7JW;dgWP04D7V`dk9>LnSN1J}@*iw5=f*oIy0JBw^q7qopV_!# zeLk!-2{TK7IUE0&<$-_nc>Spkb8t(C&#<>#QP$gG4sNn~1s``0WPR_}spInAnrS_-kS8)9ShSbNwFJf9oW3J2w|wZruor({Hm)HRfU4X*&4b_6?gncOIrr zd7~+wmBkvLoQK^HH`2tt%41I|%*T%}OY3*m$!80!=HsankMxsvePK5b&d03Jf3Yfk z)7kPr^YKb`JLWL+F0&oA0J{tbV#W8LVsT*$(Ap}I#b!pZxmgRajN5fKwu~!l-*X|( zYx$CW{xXz#>{y6X=X_#SVoI>RZx>>4+E=#6d69l0EW*Kl`E0%C0y9UKMffowhb=H9 zXm;OSgk!H{uo6F-LS*a3ICbNgf+e)$+?93BV9>Mz0W z{kOBEN0*@1{3Yn$dK!Cq`U#|*T!KbL>agMKKESssOVPaR9(`5&T-ZNzDF%%9J^my% zABrAXiY~*qYTBB9g~+1IaO$~AFz8bzWQ|&eR(9i|{kvyS=fE;_pX|YNCRd=vk7d{^ zCJNTSIs$(UT8>R#oPq5YyI`2#aNZJw3e&_q26{YwvEcy;WBud*2;aEqTps zZCB&`^O>5#8?u;%VKpw>)j{)@A&+$`w+7Gr%1unuL&ZERwRCO}4tn?1!(#^wa>hLwy$4 zx?i;B(k(k|IR8DHGpP|AYq1`eYaTPB2Db2O?Rp&c_5$0Q?E}NFu1C$3!>rDPSm;`J z1Kz*p&BBu|!q7Pzu*dcpY}2d9@W8ME7woIg9=&)Er7GFuwWtXFxemGTaJoINy;?jm zDk>k=#o43v{Y{#MYraDIZ+om!uROe2_YoXh@w@R-V;~iugU?8QH-6O}7R6qL)^-~) zepDn>Y;_E7g>J-#$4`T6;%*p}!nw+Q_%>uE)XUz8k?Y>VgP4xcxV{6fAC?U>jIU`P z_jADV!}#57@H4ZA3mtI!?mW101N7~D9dJ+cEI2+UTW>hwfZblEK~JAv>`=M`wrqV1 zV1^UhQrQumk0KcV-pg)l9I^cPeNcTivbxre_%g)_n!QV9)>|BL;y5^(lU&)*BdhcAe`bL;$ z{o74Aq|^uIZ>R?^D?8)Bx=;9Blns2-I^&WOm)QLU-q2^JGafw{%Zipg3=_9HZj8pY_(KF)y>9XDe;qn?SML-JuY zzds*-YOSVd;#a7)VKbInQX1|T`vm3oZ^oHkBcPVY3#ff_GwuX8c$IVwPJZ8v-M{XK z)pL)-mL@K^!z~%^cL;<}16(km!9Be2>057%vS^c;ap8vS%ibJ}#WmY5K zu|YpvF}L|r7H9r|jcx9RL!bLIY;%_N9qNW&-bdII1)<@$47Dbte5d()9mi<*vUJW=_dqf zYT9yp$Ojf#t2WH>a>u*ho-p6x*5JV0@oD1}w&%4MJbUGi4f5hxadrr5mEDR<@A|UI z_UGY6r>)p)%slq9&Lj9eaVwsF-i*}=%Ye$xTd}Y2QGJEYIS>@H726NAON{c#hfa65 zV$~b-G;h9qg`+>W;@Gprp^@7s*xB3zZK@B2Zxdd^o?#y79=-)uT)7S-*LdJ(-w23_ zN(9|r58P^X3f6=Lf$s$m{NC~|M82_uuAe=yO|5j8cFPn@>hL@E4PRix)5n@Wy|-bH zD*2G%TVA7?zYW`G=E3?O_4FIPx8dh6+08bx zhzg$gwqX+NXtIa3Huc2cEyAHmww|q-?1=}8xWJ>QH<+WdCvIFb2+Fs4#d;t1#7AF? zLQcictltAq%$PPw^U@@bl{fOjqE`YF%^dUDhE`tqrvC~3&Q>|B>u@hD9?*)7{{D{L zSmT8ct}bNt+B{^>L%pz^jURI#agM#Y;)UY}C$MW1quKUsFTB|MGP_~v$v)NDjsqV* zWy3E_VpIF@`+3M@S4UT8D;I9Z0nc(-qflS{5x?!o&tYuU@iko&PHxBNk8_#TOJ7aG z>+N{4TPBNJRvoe`cw@~wPnlKPBq*ivMt8W(-c9s`)ziJvu15l^Ju4dSxO(G^v3{(F z)j8N0>y0bp7P9A^9)imQeur<@irxCdzXLP&!P})y=tKG6`P-$P4~Ef{070&rmvvcH6LtS!37%Ly#cTDeDG4|a5(T* z519>jVEHylU{hlcnD^U(z1rUapBft>dEpLhJnao^pQeRa{~Z`w=?fSSOw)MsyZQwm z^PuPYdYU&GJFrpZe5hQlg1%j4Uo5xo3yiG)L~pC{MUyJ&;F4v^bT+f8*{zsE%yOw8b~Z_20r$PwmR)|>tmsn~ z*~OZ@Iqiq{!auM(-)gbnAN(+JM=o=!6Qmzj!yohcyguA{_VK0W{`jQnSLQl*n`Zb7 zf2@2VlU=w{8PqmOpdp zdKMaY*o8+*FJ)eRA3){tyYNZ%wk&VlJE-rt3(KxMtKW1r8!jB&h2ER=iHjEIL(naL z|DR>4iJqJXzrXE5=PN%o`&~c7p(eZWX!ZVJ_wE%$4cUzwmOI1!$2Vc+%H4S5N+?Wf zW`LmJ-Pq*o3Gi_af%LPxab2g|aNxKD4A0z+J0o7h#}5|Jt!4mb2WLV5xc8a{Jp(ZR zd>%ZXWuoz#6M)M)@ptkmzY`yO2H^77Umzv+jz0f*0A4+p4u`F~vg8*5xUt4PcyxRX zJ5@FicWq1tQ(Yii)in^qGWJ8Q7021riGc|1+~DTLYb=uA^Z!^n0y2GGu%Xd`m^-30 z3@`nOS=|l9)ShcK#_TH_^(PRo<@HM37Lw00n+IX+)EIs4gB&)^GKhbZ)0l1U{+>Nq z8HCp=&t@aPJz`%%f-uQ?2OH*hfi+DD!h~b7?CqZzRyHdLA6LA@-dTIIrnQ1Gp~(|w z6==g2_6$bb@*mjUz z_hM=ig3*_~;N5#KMs>OcZeyL`*}T2z@iq-+tmp-d=K{93&Vq(Dvo+C4d+}L79xNLP z8qM3i*k&jnYrCH(ZmqBnTMfyE@x89;-TvB#Z&tj8c2_&H{?_}jL7Dqde$GlZ#BCp% z9Xbua&+caR682&H0g-UJ^D*Z0U?2WSa)*`rtIVQkD4xq04QJ0hXSdsgVufGjz;5G5 z_Ih+EHr};KrR(UoE4SN4upl`&vy~}>g{sbx67f}Cb>RKeEgo-I0f}ygOj$iVg>CGFlav3~dkdwpumWbMAso*|d}RxBHfXj@3&)tJ zAKB71WnimYINllgf;qX3gn%RAczM}1)+E{ubWg)Ezak&k;}5{E;t}X{K7h@7mJGAo zMqu%n)oiKFJ!m;50;~1x!aRSaLo53TOrCg4-=ah|WFCmX_@cRqPaz+Q+>F3;H9Knf zZ}x*_9xq?~qh`_CEV$TkKSq}B0bS?4h9d*_qZK&9}r>tjE|l(pYA8jAzictIXSbRVdB zG3x;Kx6KE$C#MrFJPu&X!`aX}^}N2p(F3@&$vdcF+Kyd$dH{EQzYmRSEMxadMdFBi zXQ1BTT`Z|nB;MN>1-(8VVS~m;;`ren&~yJ4cH2G@+e{q~+Rx9}#K=gT6;TO_2sOA z#X&rDGlR{2+?4suK8Ux2bC{)Fg1(OTK|IaR*Nb<}OAOZ^#Dte$S>0lbH65NG#NRVM zu`X9jK+V$8c(Bn+wy4rDXxt?l+dEum$u(W!#-wPxIy{k0`W69ko1*cxHi%Vdv@etGA9OWPJhL};}{6%ym{WC%V$`SSp?2w3^K@r7VXDt zHouO+Yj*kYu0?p_m$HX(NrfD+wNBE|EAiT`U$2+|{TD;`khV$ZjMpV5LsP z;hgpvEOm8DRy#com-o$K-99sYY^8Yo#P7}KuJlQqWEPJ(b@G^5wP~8vDe<^3{SzDC z&=~f)#ABWJFIjb;!4MG_k5TS7SSbe=uz3`Zb3FMqfL}P+7$=}lOfc)UF$s>gPQZws z_U!KRJJ54v0-l%#?AMMr(Ah2lOLTdu|JvaTRES8xG0&#yE7Zz^qh}M)`cQM|XZ-^x zNAta9gr-#K;#%VP&1T2X-z+6~YtJM4bFE4XPV?!=7Pc)RII^lE8~ycPFl-LOHSrXJgQ~Nrc8J-blMUGp4Z2lDY@bvi@1quRI6ZrT+n(HY7>o z+sa5gjprY&a!kRuT|SiG$Mcd7&XBQ%?@c%PnzK6!22V_ZnBNC5wq*(|xf=y1T1Vm* z>ohoe-Wkkz{xO8VLwaL`cs~&2qt}kkE9(oWL*9|gzXHm@1W!*t+($`&|+QHc1 z%JYw9jx}II?0>SuJpVW&ZW&vYo59kJqjAWL5SHhf%Bppa#(`UsS&OYl*pkW7*v#e$ zt6hFOtL7Gs%WG$|1EWW<&xz3(a;Avk(AXS(UV1cstIl(+6OHuMs~^H=KE{TR>!xeE z^*Dqj=Kf|iaw>UUoUT-w*^hmA@o~umrbe{05O;On$S(p%2quA^YRX1Mc19I zX#4~4Y07hsE|Xd6w9lX$8G{c3YO~J+eu3+%|IqIG?!DMM{H$plE#K> zcb@0{?ek6HM%#Q?+IS!OI61>Lmo(Thd>=LojDk1gQ=saGeOSG93Z&eQf+mssFk)I7 zTs`XyK|Jq2i=X?hZZ?Ax#Y54TYd6~NlxBX{P;}t!z?ZwGA=cc^wL3mKTtABE{fEr` z4wYt^uwjC&UC<>O1OM%tD0&q(kuHmgHaB0QgrKhLC?bFU+#J{)cTs0py zI+{Tf=Rmx~wVS()|6V{sAUgAQip;!gTKst+&gR+$PY%}~=il3S&iM}0=9;h;5QJT> z^KX9E*t79-f-q+NHK^?!&bs;qVWX3W;c5CgHtuu~UR>%9Q*)oQx%_*Z-g$kX-@#nA zs6jBcnDtQO%C#G28H`bP0?mGN?S8EZ#<;QWdKa$UsPJG6I@y4~5B_9p`1dwb^vl@f z>b%pl4N$&VSCux%jUB&vza#=9x82)BVzG_itBKzkAoMtsykiKA)bB z2$rTeU7#w5Go-aTm_7CrvwryDMNOB1)I3)Q@)!<{|1xpg#Q_~07Ao=2qsds{HJ<#hoIj!NOdaqwwrE<8DK zRBALN7v|lHgZI%#CAH13AUDGnwzB8;M?22iLz>{g=gVrn>uL?(ks*v5eN1xT*EySi zS7XPzW0JtVd!QRBc5^x=UERi+sXv&U*mG-jy$Jq1c$m%?ACt5WT!&(>Nb>98BW;sT z!sfS^Nt)~<h9R>`oK7cTd@Kb2w*Avs5M2!OB;P-X20PZ1ZXA-@eif=Lv&3bJ45)srTG*y+*8`*dVvCM&rpL^p3;DAPspf&2gTTXN}an^ z(CMj*$mXo4l*qlS9ra0ce(fnu;@%mxsVl~|@sc)i@2+KT6mrIUNe8!nr;G+|AaJLb zG`Osk*4^6**ZjStX@&(P_6dL~Ied+4xJZ*borCY6yd+P{V>CSF0rc4I6h;K;pO$zHc+6aL%`tbv9- z9HdiDw$RF&*KEvpkVb~{=WcN>M4LNEjfUq!#RZMAGNpMK8|~)J7eV-1&7967Fb>S$jl!#J<)Jvq-Usz3xd{zrd4ygK25%5$Q5t zC*Q~GMIDNcNb}9EgNsijZEEi*m8G5p)AyIjZjz&vxyuPUe|}E>>~%LRnFgiYyW@P# z`QYq_!ZhyPp{tJ4Ut0q;yL0b`)Hq6}yPd?=+&e4wx`*d=r<>;AD2Bc6@0X29y{v?u zTR2IZ^+Kqzbv`ve=_FOTU7&Z?XK2SmCuz_2CuCC3gPJ#VmYR02poJ3`(c7`k(kJd+ z#=uWv`DSNnG54gs@3WCi%$>w{?AjIadWxeryHgMDUGrNul6tN&HT+mY)75OH(FP$DW0_C8 zhuKPpJTA}-t21@45640njYlPFg)g zB;&5Pq03H7;mp;{)Ak((_%vv>us{7j@hQM?XdVJ;MYGLdpe z=E8y8IQTJppX9gg6?{y!g{sJX(m3`cU+>Zc&HAR&ZSI}ZUm1e;22;t0Une*4w#HY{ zRI=gT1v*BG8+aX4K6{dy7K3S`zL^xBQv{=3*e%a9<8y)QQ0^Z|D+cVBl9Nxu@{gDK z7;(R(w%rNzzdom|`}?H}h11~Z$x6C8&RiNOJQPIkorkx%^rKgx=4kF+NvXN?(b`GO z;@5mU3r2XT7^wuzhR$Am!;;MsEx#tBUi!-$K)Iq6u z=Mzf#;ZBK74@q}>RFIm+BHGH|+nRCjgpQxYy;+B(z1+K?$92S$y$(x%aPOXd-Y9(B zcUbafPqJ0pHgN3rVX0?nDLs9;6>2+LNaJ@E(CmQ$U^K%*${!?BWw&!M)Yw9LZGMcp zragdV!4^`;_BG_YtqjzzTS)H?bfS=XwJ?{ztNpcBJ$uMD$!+I9j%$+5HmTGjUHHb1 zYinLV_^Q1otYOD>Cv2Bmu;W_Fj%%XtcIh!YuJw8SX%f1IdaV*XQiGCi42hgY39= zVaK)GcLT|c9oK>Exb9nNC{1I>bv`?;Ba#fIAG@AVb9P+!H8GMx*>RoAj_b&6Mp82O zPM00miC2sy8}8jBc3e$+?p7REsqrQu)nvC+pL_SELmOD1zgq%!T%Fi)%^YDYHD|~5 z13RwqF2>SUc3gGXaqaWkSQ^KU>vZV>n2g^eJz>XnFFUR|{(Gbfc3goS*Nw0D{M$Q+ z!K);>*e$Qie)4YB zYUv02$_)-}PNDwLX0kPO@7* z;=p?8J-g-0*)3ne>vpRiP6HM9ZsV8@QW3l5o!Bk!n)OosnyjQ)9i{+wsMhFG^4&& z>3kE-mnRlUO(xXSno?*lW_@2It%$6Jo@3Q1U3;;Vsr~_6$84on35%t&E%)K=W?#yx zw?w+)a}L@krc%#kOQZ+=kHb9S4jqVIB8_Xe2eKcP(CykK(mBQ+?Y%FZ?Yyjh+MMsacD^Q7ymGv5+W3V_r8Uz z^&d;6dTWBoe$j23zjT>2FZet)Jf1=aqLxW(rahoP`}ZJ9on!}p?ZasUgbuP9iPJ0*(;^l z&e~+JtAaUUE2UNW?a1dxExagNDgAd}h5xU8R4j9rrT}}Ave)YH!&TVVy-M*~&$Mp? z&(lg3uXVh*0u}~7Q@qx!_b%`X@<8@l+YX8c9ev)*g1y#bb1p%*v%VmEtsQk9K#wdV zkiFKSTi!zd>w`h|TEE??0OvQEg6y^SH>`p4qf<0xuQg{yHEiv&K$N}K&xgw(bzQ9} zd#ytszJv>_W+-0k{_I;|;ccsUt@oOy!Hwc@#cOT3Jp?pboL9V7EgwsmHT{m_wJwR8 z027n{@mhVly%Wl#%N4J6-uOYn(A;XpYn`H_Cbk@2qj;^=(+b2nPgIK6S`s~mKBN>W zUTgekGul}19?4$o@)d#9YWoF}z1AMCDKzs&G|67;y(ib{d~-*Vz1BJrg%rbUd1S9O zzwJjl)2K1YUaNS%ims}giL%!k5nMx;j?U1Oz1AhSKauIDL_zjidyIZZfw8?5uhpjL z5lvsZP4QaqS!B_tL*9zldj54H`QH3n@mlq#cv6#oIf~bMKxY&68}mf*T32g#rR|;G zD_-liZ{cFn+)Bl3HS1WIGWSG{;f# z2y23?6|Z%~`xmJ#=GG`)Yh1x~an>|mAI@HDP`i;dZ(FhAwT_H8p^4S^6t7kLg+IMG zdXZ$W_0ycQ)NE)h$zE&n^=p(E;zY97+U3r3N{-Yf*=wEQ^npH}Zbq`#>Sj?z-Rj$j zve%j!%b)AD%`|1N^<2M7DmWA^$X=`8&3EM0xVz%D+T=c_tn$r@*IFK&O#{DpDqd@! zF@Mt<>ywJtx+B|*#x%-Syw;3!x^!~!W5sLTQQ3pS557~pR+HWFV*Rh56tA@v4Nkom zQKNXRS}iRERcMvswMJcR0xj=+P`p;@#$t$?QmA;XPFEcvaqV@Gz1BW^V&HkzS&+Tf zM^zVKUTgr!Uh6)Sd(du|Dac;y;-GLR%z1EQ}D!}$iz94(8eaG{f^ph%0*=s#? zmOs~%M~br7s%=ybNxmOM*=sde{ThZYoTPZICf9C5%1SH6YmGi|4vN}^DqgGi#Bc}< zPE)+r9=C0v=hS?~YZcE-hson!DPC)bqR&DLDpS1H{Pr`2BExFMYn?vqa;otb{!WFx z)Uza zjdUT|Yb{WFPHQ{sknFX#`%y|e*R&$pYdt%mie?^g5@oM-1%FT2Z(o>(?6vMOsic*S zLIl}s-MiyGZQj~h@meRvJs}6j4T{&QBjwP&-5!e9I^80Pj7BFaUhCsIM=7!BisH2j zJ$6u)-Xq0po#EYwCOs`tyjIVmQ(|}|d*|%6hJMjaz3V@L9uGBaJvv=J9*=v2&E*c6oQbG1wQ?fJQb@w2Uz19kg0$84E z4zkzUb_K7$a~cP-*E&8@1^J^N3bNNazIzQsXf+aKuXX*iYWT9OwsCcagSMR_fvQWHMo22t_H7Z!~T4SOj;QD4#yw)T=J8&C+OYvIQY0Lt5 zqnC=;`Z`<exM0yw;~9`qNac62)uv zTt%YG+)s+vx~iW?>YO9|8DpM3*P6Gj9vpr0QSn-D-Jb)-k6tKV>x~e5 zP}_GCWUo~`6$x=BB41;*lsfsQLypIBkiFLB4tHU#+F_8r)_LJ?;6Y~q*=s$jse&%S zg@Ww0rhMhK487F_*=r4{Ujt|K+lsQ+`gVy5PG>z6Wv?~!<{NmZDJWj+>MM6)_=rP_ z*INBD9aLkFD_-mSCQ*>WYg1*f^>YIUXg2ny;pRO-vB9QKiq~p6rysT1T%vfbQ=)g#oAif@*Sbyb7`14A zg=DYQ-}DsKjyXZH*Q)KFOHJmulkBxlUHFtneO^nl*D5}GPq*UKN%mUH_}n^gr@ttB ztzS>oklm8DDYDm^-K2`FJ9!AQ*E-9ql-_r3t9Y&X>z+}&q?L--TJruXrLE>Q2JE%& zY;%ULIL0epYyCOClzRM<;ToYH zb*M>=;}QdZH<2jcUPAwUaPInOc29fDqd@4Lp#VhbPHs!_2Rq;7;&0F z_F9{5IS-X}LO}LfW1R0mv)+81#9nLtlGiXkdOXNptB_p|V;a2`WUtlzZZ)qN>?g=x z>m)uWd*e`Fl)cu-bQQc=bzhXd);QZDsErw`c&%g37eJ??{Um#>HEl1zhKqrU*Sca? zG;AnNQM}fV0Y@Nc;0?uV9Wr_$yn0foc&$Cu8iBX)QSn+&zuY6Z+^AB#*27bDQu_zi zC|+ww^CWS2+9$YX=v4$mUlYporcM7``2N%mU5 z?#-d`cRWb;TI(1;A&pHNN%mTOroAV(`CUl%TI+18q#G|nMcHd@aw8)%UTfgk=k&+K<%-wZpw2b=am`urT36{LQ|nQ2ir1QW#gA5) zWGY_k&>?&1P{Mu1Ykj_P7&(^|D_*P1#2j&|TZQ7aYP#p8ny=&US=eiRv3{D6b)Z`D zT2HjD5w_efQ@qwLcc+0HU+0y**8E*I5M-SXve)|Ubr|d{O#|6$^&Nf=HW-A0?6rPy zxeek4E0Dcb9QqnEMob3TYaOgz4j=W)1leoNim!%($}xiMwN9N@137cvrOIAwV*d*0 z@!_T@d##N$ib1c#D8*}4ow^5C{q`wd>!HaPp~u_+#cO?+8v}Qu&MIE3({Lx4-Q~LC zwGK{L0;(2;ir0EOzA3ah_2D0{wZu}`##jzg{5)Tir4CXqD+{!uw3z4qvlVB5B**%UaP?k zE7)Uu8)UC_r+FwW>U$1kuk~_u8Z>?w2C~;W!Z{y?ud@N!YyGn870geW2C~<>^KlvU zxm_*DUaQU_cAj5M6=bh9el7c4&eu|9ueGjo1vnkb5oNFS(W_#ZY&lHvT3sXV!}6JX z6tC4{S0;?S?WcIH$NR-Wr%lO<*Lo?#8M-vNrg*Kny_Q1=K3BZf8%tZln|>b@uXWp~6_-z#2gON)&Z%GV!duXRkJ2l?*G zA=zu4>X}IO`y`Rwk-~ z*Xqq#5w;K2Bn( z*jvNjt)EPlz1Gn86`1@c>)Sz!*ILKx0o+g-Dqd@)_az8g?yGpMyAH>L zR<|>X*Xq5%6*^X3RlL?Jua%(EeWrM=wY6=ajc=*qwf^k7nv+h@X}wbu}Ka#!H?^`}m{*+Wv_F5ad)=+hxL#phx4r*9U zU3TjVve(*8{7B_S^%bx6V%Q7XeP^!XwN4sxlMLHBC|>KxZX(5Wh*G@P(*uuF%Ma;_ z*Q(#{5CvSnt9Y&FItz5Y;Em$7zHxXaIxJTyUaM_c8!@jzjpDV=2~iiUzf>z;E6;U8 z=@^ybwU%iDK+qe-Yi-x{FtoC`3$oW*_xN%6>XHt!*E-lzgsP}WkiFI`hi}3XFME)^ z){ZY;fRHu^WUuvM;YSFbRS#sZ)ruXil=KaP?6syk)IfMI&s5oKb(-}FV*N>!z1Ev! zOJLiA{)*Q+{a$W1*`gd#w}S#nY0rd@RmhYgG9qI{VCrWUqDUlLzGe+JI!Q^?l}B zx|cPOWUqB%lTTEVoG!{<>pMR7FENiwmA%&1w_Y&iuS1VrYC9#n(pd0U%z+P*@?uSBhs7mo#@5hdV?n{akuXW@dbI39+ z0NHCDGdKuNoX-H+Yc-jY3L_dvgY2~q*n0!Y2Oa_0Yqe5;0eYGXK=xXjt@{Yus{a7l zYgK<<1)(Pm1=(xe#OHkBW!q9^uQem=6P)gMT9m!klKUm_=2RcWYhAAU2y(P`C|+yF zr&l0U=jcCP>wrWMoRSo;_2Cu|ICD8i@mizxHh^!^6UA%wnb{c*7`#`!)_ys`LPIlN zH^N@)8rS0*mVB-&d#!e9PNFGRDPHTA1FdMomr})R_0-UztDm1KUaR2*7YaI^N3z$t z$}5f@eLF+4*Q%DAN!?cak?ge=e!Nc`kiQRRuQj{#TUxY!D9K)HZd?WV_syPj%s0ltS$X=@jU&}E)IW$%F zS|`)<($!SJE3;p6N;GKk;wHYn@!` z37ccH6|c3y-OW&Q>#^ds-Y@9}>382LUTf^cXu)7$rQ)@|-`+&CF}v=v*SdPDjc9bJ zO7U82@|)3VyAO)j`bVZV4Y|hqm9f`abHa&|E?*YXB>o5FeI9ycJRd0E zJ5{c&JgZd*MIhcxc<3} zrmhZBe*R!iowS6QtxDZ<(jRH<&URF4)47e(LUy<*driz<*D$SDV|7jWbz5w$mo_Fc zNs#L`IeZNv_)n1Qj!j?F)bTr&y3Lh5TJyKJQdfp`Oxvs57v%j+EGM)|%MG&xc|Vh> z5e?GxI>ds!pNV?wa%ylc59Iw!T$1u>IIpFZ_cMvReUjQ4*VB^sGr?~TH1r*?uw<0^c@N_A}AzcLma{szBb)#E{+aI%W4k-p}ON4>hfeIb<;9AQD2bvGjVnArgeA8 za#7yTWa^)twPr4CPV#;x$Nk%C33WG-yq`&4`zBh;`udZ+pNZksuh3|7I?4N)wD|E9 z3TN`3LcE{J-lB6*QSy!C{Y=gr@`ZPfP15B3O!Q6H!P~O7Y4Uz1`yv~|;uW3KmCs*M|Vq;_cQsghwOE=TUxwtKT&p)Ckvg^%APePxz2jnCQU77hf@1IZJ1_sCse8b zyEo47KK|eB<9|Q<4T>)dbw+koKI2nOr@|k)9h7?5F*o@BrkPTAFA~A^*$?Hj{NFuo ze(x{ze|LYO<&^`J`@6}R37h++y**o^Wa<4&-P2n1+p1*dp~Y>|mRH6o^;f+*X}iWg zP-^}+@qcT{zsvuh_;E_jzeoK0O3lwF^7AS+-&3FuzuvE(3%`CYzs|46%dhk6dF0pm z_5AX`f4#2!|9|nwzxRt%e!gG)^6T*Z!XkeDUGmSBx#Q>Km2vpER zcgZ|T{gYFv<=2tlFZnV1&IikX*RP+;fA6oy%kP6y|9pRx`se$m)cm^g`}vDUexH?E z{yq79{K+r(MdAPd(;iU&&4K?OSCkC%BwNw;YH3Pc!rP=k%Y?#s8Mi>3{nr*FW!F$T_Lx(x38i&ab?Z>t8u0*T3>j zu7Bm8T>s1^WsTUcoRok5D?jD>XD%s^`IWanf3D>4&&MnIEZ0ACNqPLwTvF5ciqs${|axLed z{QGh(=b!w%a;+nr=`FvfKYy;|@XyD~^N8~EpYM-S|9sz+`q%i8AO9==<(hv_o<|h6 zpM6pI|Lgqxc6)xiJ-^+a-)_%ux97Lp^V{wD?e_e3dw#n;zulhSZqIMG=eOJQ+wJ-7 z_WX8xe!D%t-JaiW&u_Qqx7+i--R=3G-aG!k_n`lMZ%jRoKZ7Gn@Etu`ZQ@Fly1~faVA9~ZQtuqB2SMT2 zl{&`K7dAIZQR?pZlELnypHdG$a}Ad28Y*?$4bNc0slG~`u(SjQ)lU%R=l37~0i0jz zr^t2oml7~o5G2U;(x~S!=|p#s>pZs`aOM4WrOts=*wWfZslTiYfZ7n=i;^E>7Gw;z z7xI+)@rZ#iOnj=;M^>H|d}`k+bwc3>jc*zslzM*oQSthWcS@aeRGr>DEmZ0uP1jS! zw0xx=Jj{cPiX^4}v?`J2uMSh{p%<^v^)=Q?eLR`hMLAAZ>RCx|=!g0Tg}>d(Qo7Qw zuToF3l<$MnLHTErS9;G@>h=TbXni>SMqXcl6~pUmy`PekD%TMU>S+ye zvzFIWpjVe#xP7@Z$o0jpy!Ye?1EtpMa|eb^Kd#ij_HZ^h5s$`Bo$278wXi2Y9?vdb zN1LlZ!nB%rY?0?iBgZ_2^lk}geJg841=~H^a%-abVvbAp7(+Ot;lbQs)&3mpcsPWXS?s5We#n(%7 z=&CL1PdI^p2CAinn12?ZY&?OpJ66%h+f(R}!wEbv`VHj)@Bi%+ zsJ5DDa(NoPs62ti&&J~O zlt0PW;VWc3kHzGG-J~`C9dv6JhhxeDX<*O05Hc3aH&>e`swV zhqp}MQ=dzEkeC#QzH7eGOQ#;t^hq45Ue`@ql^7t{G>pdqOY5giY+;|`Gdv!+!wCOSLH-0Dq%SRm*d)BX)HZL{-%c4s)-Yl-4 zHvLutP8)w(7@}7u7VcY`!q<=grxyi7 zB5`vsb($4Z3-uR9qUx>=)iExI@5Ygsy}*f@H!XyVK9M-%Kr}rs%Y!WxiM`fm(9x`9 z81pC+ohBEMusHx8e2c_OSBvTHBXj83GYYS6<~?Y8Bea@KHk1v=EP zT{K>AQb@xVI#G#6G#)FnO2)ebd#Ct1Vv-LN9I(^Op`LA zaYQeqN@fyXMWch6N=#vw?#o+Kh z>d=6hwB6;$=)iGins+7!y%suw8#A@JAA_|AqG2vGC4Y&*jP)7t{z@|0bcw|dQwm@| zGYuFYi{tW&VdO(|+O|Fxdv2+Qg*}lr*u>(cTWVUV`&44Tm{^>cz?pM@iI|fcixD&H zYyJ7gK-2eKEFR_0O(W|l0h`C+%jjBY_oq6TkBCFP-Q{3)UkCPT$Kj$Tg;2vxf@vJq z;a=$+jD{!v{295D46Qa~Ktfs^cHR^KtC(pae_qx-Fb92Ra#M>(!yX8;nd!)%@mRc9 zCFC>HyqWQ6cV~$(otesa#AC=OgVZo)N_UF?_p>Z#-LKDe?$~hLR9~F}5^5n&Cmg4c z4r!Q`!{r0vSUJUsYTFcoV@Nn&GK{8~U-DpBW;ixpmcjQqNru{&;doAy@3CbV0HF;c z(D@RtYpF7aX9FT|6W>Sr-~@yRb0hG>4Yjn62nW;``B!-_+iJzJ2 za;qqOyI5N^W2Wt+qtNfWp5`NF611Z*aC($*otYl*jlvHN)L}g{b@7YBv@{)fXM&J^LD94v_DMQ`YhrK}_v$M%)v=60htGL%l9?jIV{rSeWVpvn zdoIP`W&^(00W)=c6N4K+nM2RZ#jw0_ECM3jVy1;dW6>r_CA4Oy_KRXMc&@f!%}kN8l3}|&&CEE25 z$NroFpWZAH2h9%0IPTlwcmvJPJHj!Ib1B+9N(gceM?LP9Nl$fnd@>wIbFW(7)q#TB z;W(e?ko60kz`r^ihnD9-2{TRT9D(n64!OZh&9ovgfaj2DlM5hebp$3nHU~#$Dmxs3 z6+DLoGgC=;1P(c<5(1bhF)IT5zFZ;0ZIYa4`*GmEL!XLFbw6NFFKR+GkL1jq}*OwNEuX)58z#~|Fu8DPFaTL^D+ z91FQ`$1mxn?jC&{D>wt@Oo$RYEIp2IIRlo~RVQsz9_O4(vr~0we&BI*ZCgl9IV;;{ z9LG6HVei3H`KH`i7Ijah)~?g8Ss9Uwy0VhiqE)jryuHRUNjEH*PKgj zCr1fej)r0~=h7)=ibxH`wcINoQ3rw^hvG2qRU|WQR0~6Eo&Z zH4I~U4zXn>vn^pbyxJVrGE=HU7-~#Jn8-{?31OI$q7q&(lgZ66{Bwo2V8BeBE5h*H zYrWK`%=ETx_`l;vp4WbjrSQSNc(ao_?TD>~%kzCP^|}s)>?w!z-M(lz*NJ*GF9hpj zzBtn?nwC`LL4VN~E!Oa{Np3P!J@CcJ6FCF627v!pUwoBQOqnmt;X!vl+`Orp3Ljy5=Q#H8uN9to8h)XyFPTQ%(qNqS@ z!5OfmYKiES6NpLNH!FPu%@rkq_=0oki*c0jy=f4B<6Jt`RUO6;55l_KE7M!dv?K_Z z@*HxOnZB9?;bxvg^qA?mUl7jANd`-1(xV_8q8k9cI4j#c4#IBF%^{GP7X1jqpneFY z%rvLZalBxo5;ihZ%NfUUt7?hRo|#Tt=`!rb6vcuqf>$~c$GFC4?k+I(zsCmAwc9K&Ip zOP0F>U{ie`oW{8{;j1}>_4mPDoB_^L5d!D<;Bn4?GZ`vjy@3xd<_!32r?ybv(+A&h z-+Y4fQtzDd!RDvxrmYsD#C>;s@UIiKRK!eYt9@|T{&K2jrjuQKQD|34Rm`+!qAzBA z&7&G->bTJtKXNYZVWwg$U!1x-fL1Y+Q-m*`{bEkrnJG8R7r#zHa$u&+cfRP5t`eh} z$)TkmmTc1&mod|jQGQq*rKkCtnZ7Re;~i+Dgoex%yvGmC)zo1GGd=O~Lz}ZY(1Mxn zrTL-8WG86NOo7k*aI`@*xHHqFy8alWodK!L)UuC1I%pI?17CDu2NFa_lrxHYFy0;(@M{d>@)-aR#?m$ct^-^Cj z(;TnBf5(qJul*WJjpIGAqP;rRaxV3|?tzW2>d+qE->;|21JhS^bVpBih6ADQV=j5oUXG|(hw^2+hX zfjgpvcFd&l&KnEW)!_^?nY1{H&+~Mk2{RdtI*P~U@Q7okG0TpkjcGJ|;;g)9dKB-j z&VV+|6yuo6dQ2{EFO$xUH2Gv;tV+CsuE}RJBF3q zxB7o*i|=M0!&L6u$Pvu6{TMdkIj+~PC}Ew`F?8czJ?N+o#}kj?UCyPvYdYYQe+)PB z98zzt6RfT}hT%MiykVvv9epr`=a9i`GT^%4gV{WXR56qBDj$q|Y0mjs45tqH;QB!b za5o#+kcQet;^tkvW5?{9gqc(ObCEXkk;oJ+kox}*QN z0-A3e0GF-ZG52CI)vYy$`qA##iZj4)Iznx(J6duEgk4ez7eBb;bnY7%YYV!qJ@75} z?a@KK)N!Lcuoq{5&e$mN!4ePj;0$=rOda=mU;t-8t1~*(I=}-ja|X2ITq-#4fm^@v zu{Y<^{z4BtaVMEBFw?BMp4inmfX*{hX&+BK`puk*nQ8D0Py99wsUI`--RX%*nJUqN znclj3;&LNxaV9glCVAp&TRqKUW?GZ)iL=K=30;|~&L>aY^t}TdW~PbiUTAej2dtP$ z(DK5Wlbj%unQGU1;VS)Tn8Zw>mOSQ{WPl|z8HIV_i*W_;j&rHqB`<8i88CpEmK1p* zat1gs)7+-s=*Agv;i8J~E9s4MxNpV=+G6q|Z!F@zJ$2U8wB7BE>YPic5hV=p_C|f~ z)k9|5n&OSyxK|a-wEmGd+HkK9GE?6l-q@LY<;YAqy^i8C?p0gPCEqDWQRF$~56&gr zd=%4o4(Y>8`|XcnyJ-lEnQ2e_QM`3QB^+ZW;l@#P)6*8_Gt-muqqxpnFI8qrXmjk} z@gvV`zs8c`ASdk8MxET^YQcV<6K>AZq3I^&U}5Bh&1N}~X3IjDe$)xan?%#i$~<_R z;)HisX3+3!$&h;A2|r)~9orEAtG_tmx2$5i@zxvyx;bOjhH6rcK=7XIj2AeUdi$${ z6ysWY}V;cGeB zIuz5|1*>=;_kGNyH`WC$EAuFbnOf<%;N84r8nh~do|(Gfh#di>IiAl4{9W*4u{jBx zm6_*Uu-*thHsM^73SDrFuS&ehOqLB?@n|P)v4ENW9N>!PFZ4ApFjK`$S6sf4ujMe4 z?+#aN+D;w*Vx|HYR~(n41CKeEZYH_n%UMovnwh-sy5e_}Xc)yznl-L?cvS`*V5Wwh z+|Y7-0pxBEpm^ZVY<4lUWTuieZn$V;HMAd&^vco=pYr+ljAJS>CejTbbKg$4*B0ky zyJ0%_?M=D9W|y~aIEr&==H@6Ny@@;a=3f0^rtd@DF^1=m9=SSDv&bC{c@9}H+X+OLn zyj4OeGu@o-fwx*~3on>y&o&QSRL3CoJTpx_;_>hJk>|BvV`_=+>YlbIf`=W%{F znFMBvw{*e_oJ%v9X+gLXs(m*nTV`^(;)GUzAw6a$`w}O7c10x`GSi$E&X~1NTb#g5 zWh0z1Xs4d$J7!8>7UL6-)&bic$nQr%T!3~^CLCj<_)dd4C7DH04IVJ15;QKYzFpQZJ9bIrQ zXTS(%GEQ{CN!+(>CfcIeN!t4xex?ox7w%jXmt}Ys*5q#Z1@E z*kMW)A202VCZl_HIQDunJ!PgzHFlV>Gl1H2R=(kF#2-!(C?5XzqZ) zmvtbXnMRIuK$z(S#7vdi4rsAA8g?*~-#!N%u`&amUQ4EJz7Dts3t$a1H6sVK%PI!j zcg*y}0fRPF!{t#()9W0;NX~$FK`OCv-y@jGee2v;TRbu22wvg7ojs$kd0^WST*0~I zxjIVd>39TBaW0K(tq$u>96?i_LoBc8z=~T(a6iu>Va(L6@(6aX%7drObV1z_?RgHd zVkUP@NBqKbNF+0jS?P!gCFYR9OvVQt@##o}9A?rBb;M?YD&aIUjlArLOM7VxIm~po z$Pp7W^;0i1Q$!>FEdM-SlIOKwb;c}6Lx7*^iY?ZiynG#)Wk<7J44Q5*Ww=JGtrKc$~^}1z?-$z6V z8q9QAWs8|#JHSh3s@K5|za;5ETV|>i?64DOzCB`V=YV~)Re~-veY@ts z$79+8FjHum1FF{RrSe>&W!U=2zvD-q*M5y9v&9FnsEIm-b1r%K9zgR99m?livUz?0 z?@xE4F|7-s`GAAC+Blj9)#Slay@R+=Cxaf|NQR2UgGf+7$Mph0OLY*3T`4B>GIJ0$ z4`JZ?YHF#8kYI5L7jp(YjZq0>vkzei_ieD2ws5fdVZ6zG`(urMYL^9v(UUX4c2ShL z$@4H;#@A9#Q+0ZN|1gH`E2kwFbZAE_3#@8YNcfi%4I5*Dh1GdCkfvY#*%>*D=$S`j+Uap)E!-)0=*l zIDeQ3s5e$@6bZ4F1arQkiMl9ZPJv zCmMX1=}VO*mg;1{7-q^*x5BAf1@K~50O<)D^_Cm+lyVYL;Ot*?fqV||wAe%#0zkicU-|G|FwbC>3Bt}S%# zVXoxTk5zi9;(BwGGvFKNl3Ij0zTym!nCW1NIdWq1r+0!5L7OnfgyVh!1||QiS6{+|3z~$V@)@2l3_4T7sZq{BFt zGhie$x&JtfuQ-={n8~-N1%4S@0E3xHYl;O<;|!=^CbKOT7|R*p!c4|TEacqQ>XM@p zHBMN_xviytKwEr#!$Qd=CmlV__%aJQx3!#^X+axHe9yhIVpz zuRc$3f;k5*QQ%$;Vy2J5mKe&tddN)a8J0MXdsWU%8(&yrGoC}nGgD{-D~#b@MKF{9 zKr39#bI2NIS~t%MpYj|cGu1P+!duJqQa|um%6GT=cl^ln+OM%ReUSnBHdLoxd|iHt zj{z<|r$hGqec@lv3~<9VC+f=I7vAV+h)s7#(|G>AP<@vn4p^Q+ZTb7cJlvk{liAsgEJufq)Mp1VuX%7mhxw63lp2|#sbcO z^ZoQwpUm5hXE*~+%#ITKdhEtJ{C&mFM(PxHZ#S;w?@_y+*P)|5jPXV5LORb(-M1R! z=bAiP$4t5j#(3o>pMNt`gAc|SryoEy%rtl89?VvmlPfdj?%RVlfb=Kl(z*0KSbahz z4q>Lh8t%nC)3rr6W^$do7dwy9*SyP2LtXdc>bX%u0yFKowHGHgR)-gyODc5}d~;q0 zhBDLZbtc$lx)a1OlYX=bp5D#Zy_xCkdlO7so&l!Jq&;jOYC-`lW~M-+eVEDLqyE86 zol^JV9L}X=0jar~DQe2Ol)%SuGfdH&`=&lcTYTzlinqCMCX@Mi>AER~b1pTRA0=FB zZH5;)m)bN@hsio-sK&iInXUt4Ld?*B=MXbyI#*(P_L-*sLo5@h0vob<| zKYrmk#FUxdCGE%Q<>pY$OxtVrV-e3G#>}*Ok~xONsf6jw^xEDWX@a)k&rCzFnPdKZ z{nUJBy4vEvzvD-q*M5zqhMRWsMW7Cpz+=5KW+yJ=>r0pU+@QE@C!XaDkk1WvYwp5Z zoB>IEZa@cj;Z8nhYQ$rGMfxt(=L~S-IXI-Q9)@u)`SQ6zw^@4lfis{NpU1WG(38(o z(neoV34ZtW)0shVBOiP&Q!xTd-;d3S@ zX4-kg5Y70U=_xa1sr^eM zwBz%*E6n6Ma5u*BvB`U8vNhU`x|~ZRn5l)h8yz_V-Z9g%@4ImbADhf(rpk%NsKLi3 z19R)5}$jX0NdnJIFD z3GU=xHD{)27AE+Od)1Yh95YSO?dS1Q!zTN1Am@_AOkWo5!=?WZd;b*`)%LV;qXOof zbIyu6K^N1U0}6^DAW8-iP(%p}A!pC~T{OwnNvXy!yf{lY3E z9X6ciI~GvC&?;Sr-Jm||M(P(9e$-)M)JIjNnUkeUblHB&OWSGYWS*TaYob_se4gs^ zCA!Rlbko?WB#`K(C!RUE-(r#%w?&WLryQU~GbeR^dh7`0r5!YLqWeIPb*4V*)cjqj zGFG2)n(x>{KE2S>XWwYPV-n4r%s8#j-qC!=Zt|)0y*}%p`HrrXm-@{!V5zOvSV}(m zSQ@YpnmO?!pX@IhupKmW@|}F@-qnz8qM4IpZ3lQnUmW;jaWCz0XMTh3wN#C&+JLJB{Xvq z=e=J%bF#XRsqC^_`&kL)rNcCH;@01oEhDY&lTT7A#w?5SQW(vgw8a>+?W9$YHQr$V z#+cdBHH4E-rP3x$gRUVj$tQgi6Q)Af5Nq=3%vlq*w#6EzQC^a6H({e_=HwyyGqlr;j&G*|8D7XHJgyIq)xjMAx;yu~e$HhgnhYOPON5AY~7; zq~6zNiuJP}_pnT=G3!xY63FajnN(x`Mm-)Uo4srn^}ZO@EXH5l%Z5cQH@zvRQJ9^EKuFshkVKyrpt~U zR1$6?pW1ipG9CBdb?=ZEUAFg6-TTQ4U8X`cW=HZ#b-EtYq8hU&`LyMr9-B)w<{a|r zey$!{N;PIx@@ec3JyuFNAensP%k)_R<$y7im!zEZ*-Oexr^zRWYx-;~)tG0jrTeA+ z2F!(W0J}o*tzy8|k#5%xDGAp`8;JS>a?9*YWNV)qu!)qHWEUq3W==F@VWibnsxPG& z8nRT<>LJyaBF-AJYSQW><)uj-hRlPmAyVX%@zQ;)nzRZbpL*HvV``L_0>~%DOZ(V7 zx`tdNpUS%%v0SPzNs&**3Pwze>Pyz-)247EHuO(@DX7MX4Y&ARUs^D3|G)SVUDy7` zQuWrI>;=u7e5F`_7`&5J)67XR<)s@>cCv>wbCN;*LZ!*d>@v-FjHFnK+NaE>(R{}O z>KDqLR%RU(OUBeMbo!vo8c4V54r}-rXv$0WG;=a?j4HFI`Ho36 zbCRH|%3jfYM>ooq?@p<*W}5HNCZD|Csj?|Fb25u^WyKsdwv1*@22)k2REphUC+rP3lbQ?(dnCY;ScoYDKc3fqeQ>uFhm>zN3_U zvK+FTO``b@EAnZd#%^|i<~tO~r_YJI*=CyWI88puHSA_FG~ba!K2=F;Fio28sG*sY z2?sRTa>`3_G;tuxipRJMXh_3iM$*Uos6nbm_iyzT-?Qbl(X)3Z4q}wy{&n;PznUHSr-R@9) z-+QCPZjx?iD85VQ>|~cow;YOZ1LVU&%z7j(~+SnOhHdcxSM<`R99i9=S*Z@kxzS~ zRoDya$#Xsj{u}ueb72?TKs|YT^6AaD zUFpvqjS_qC1Y1U8havM|a4X*4Gw*H4Y5k!~YtcHxS$ z8dE0STxfQoPm~&?nFYD?G`n!RMvZ=7OUkXM*@e&J)tP|u(o&jTIAEa8CQ@FSO+IO7 zsMCpxF+&fngdfk7ha)$tU$E8tmH%lRTR3koz)b&%gK)UDu8pcLj}K zzc5X58(S~02D)QEVVlM_=1>;|<+j!6lDCa*Za)v578YS_Uj;Vtc_n=M9E%sU6_}%M z0|c+Iz?ocuxt4u{UXvza;xI)f@j+5f{_6>$f|(){Ds+~My*yktqePL7oIpM9fFgm( zsO>DyzXP-$FNV7o+u4jeuVL9{XP8^DoxQBS2`wQhkTGKi>!`_q9vN3*tnChVHpLsf z?mY*mdpp>(5gVYsdn@?ORbu}BZv+EoNXXfHDX|T2U&&6K(pm2K3ngav_EFyD8J*=` z58e6i`-*b!A9nIZ-#1n;EiZmsXR*C-=P^ONA^jep*Z=Y*vXkScWBALjAhLfc9z~sF z^d$4^hRLa~H+hKubVBq*pZ0~O#4QEQei|vy4;X)FOVru8J>CxcW?NPrxjkHvWp(cDi#14dYLW?R97Bv2&1> z*ghNh4QC&lEVhS!r&*DfP|-Qz^VWCHAEap`E3&W0N#q|MbzgMe_(EvI)zepj$j+*M zfo|VD#kNE7ReV&MA+{|s2{&n!i|w_p_E>p?_9>?K`?X7>x}sQ9o?U+l^!lE|=3U#k z-lhaNvgHo$Oy9;gO|pfzhu)%87X|+Ei!`(a#GQUWu!0pbBUo5BG zIp4UiB7d+|D;)}Le<+lcx|Ipetn;* z!iQ6pxcpP8{Cg4$1XV|scolTYAM;oeoGX-gS@S2vU}eypwUc+teS%g41L2I@PVRT3 z7(cGgfr2MHx!#v}{J6aWR?Ji8&C`zIl$G@`%u|^UyF4AspL~VcwaWZ&%q(51^3V2= zR_A|mh4>tCZ5uzw0^t4X8t9k3jVHThLqGk?5Jcy#_t$c8YfFTQ$_hO6 z{2MU4;0Rf#75I~r9S~@_7)qoR`J7IYa*KLj6*Q?S^1Ah%#eg;aYVA-uD+dl5?+mw%wMXolS@=j!#sK}=za1|u3Kh_Q>QlIuwOg5ltwJNE8fMeJC(V7>_zMr zlZ!UV%3Nbj6;7TOhP}Ti^WK*};5##2?4h8-2Mzv-%hwIY8L29KsWSEa>l}qYeyH#& zdOj=sWuR=~)?Iv4wM71S$(w>V@w@oOQ62bISr%q|*~Ob%UgPDS&ahZfl^gXa$Lxv8 z5Rp0nxrJd!JzbUY}N51AYj_fR#G)wVc zt`^-3{dwk2^z0u0^DLg&{_~8U*#7hEo_NooKhN~Zir)X{SwGP;ef-ZefTCyj_@8G3 z#rB_P2F3QDX9>mjpJxok_Mc}D#rEIxIVdWFGsXKklq=+_u4HhjiOB+Ix+jQe%=o9v z)x>lz={``DPvpvPrSs;;$%6YCl5(+a>Ad@-sZhP;8{D06hKK(;4AwCXa7+FSA7LE> zGrrx0M^GrVTP2WaeR0QXwY@NtPhKzZpfxG^Dv zcV|*^k{TX@^eq`&NcRQq(+=cywaDPJy3@T%{uQBSOa^~)o%VK)TZ9j0a8+ z8uLH>zdoCdO6BrnuE@0Q=q$HzeJa=5QYZ+SE-9yFp32o*WFTaA2lP3a%F`WPp~0h; zuJ5VbHX;o+tCc~<&s2VPS{ax^=W%JC#L3Qyw(#hK7jTY|oq(|D+*H%K)<$GE069{+0%gr91~q;aSD$s>;igKQ=8 zUALa*2S-KA)-UUvztH+LpSadrSUFcJ-!u6%?|ES?Zn6K4nfFd}-7IrF(At1?Qt5n) zZXC9IR^s3V>3pL{F;4Z#K{JhXK3S&*NAwB6!CvY7@Q7wiRZ_&JymTISxl{fbl)8wBZMM9{GQ@ z6UF4;_?$91nKvA~Ci8^O??{DYzACU#@O7%B+$Ni3-g~GlC{OEv_OxU^A;1-0+SkJH z$I1MCN*c6pEu;I-6yAMd8Fap$21yH2c=*0rV7aa^K{JKd4eNk8`($C2UkdLuNmB0i zvLZoKK?;wc<6N6?S7uT}3g3NRQcf>0N%&w$DxanI6(n7xaqSw4nQL{B<8O~v6iaFr zpH#XoMiY2#0aX8+- z5`RD%-x^$utL<}8RX>e)H>tr+KmGAXU>Z*u-;DDXD&phfG=8C^Q~vD!Ey5QRORhsZ z=kLEMA^b7sG;au$%AeU&M=)k1?f0$s69*3)2%juZ^F{9)F`>=?CQ&SP+5Z5)%#4IE zilsd>gs3&H0Csdr=d+H5;ugBH+ssPmSM@Z|dS4SvRZr(ntVZC{tv}$9L;64MM0w+{ zj<+M?`Rb%AGR<^;!>-2jHl;#=4)J*Pb3C{2kbyh1I^fWRlRU`T70TUfAz0xgpB$A2 zZ+4ZzAiI-%$c!>5yO#zNPo3n+TD5TNiYr7vILY+~cEBw+St#g|z(a^fC7U9F@uCFo zNXLQC4`kvr>2=~US1C!j!zY1nG5QMq^`)^G$-Ywu-7V~~xjumpvM-0-{z-UySRyYi z%mn>6CHQ$&BF{eT4Rc$bW0!-8-0IsJFimU4p0SDigXv?zR^qYYRw7UCh>~q49>c#T z@;CC{!ZXCVVXQ|b9?eSPrJlv;>y?8K zo+R--x-|&B0`O>$WUe~0866Z9ai?rDe@Q&PlW!63Hb~|@Nk{t)lEP!b$-IbojPcbL zL=+}-{e3_2V8;M3X-wvenj5jM%m89Wr|@-$AK;v^kuYd;3fEgC#NfdNaK|!*FLDpX zP3Nkh<75hd<)ndEwVNQmB8A(8jldHdf53;flz-ZZa_L_kT@zyYrn}c<9@F`?yB*8z z!V3ith{ud?v3$S?Sty;_0qQg3xND#*3?v?HRO9%hQ)%!?z6`#)#qs`&%HT$68uZML z){I|te06N;s+hs)u5bQ0!{KgoY)XF}np60F*Ml0Ve*2HhXe z@q^V#e)aJh_(nW7r<~-jGam~^*-PZ#rC8cs7b&}jc(j*F;Dv$SLJ#8c!JGvCqk1eV z5syE1C-8!M=D7NO11_dmYA}z({&tn9MX_WPQjEWBbMWHp1TJA(gHGT5QEOl#-!q{Z zpUqXoWh)c;d*X3Mj~3xtilrdZan(f$p>}j4uOJ=|4A&7jT}$Nlx<4^;` zN{bPAop^lsE9swhqFnk{$2lV-`G!R$GEH=Tzpstt?HYxGImDy%p-6u3y9`JXj}PM_ zxu2^mB)iqZm)nv2Npu>RtCWG&k4Ww@leoN_2JX|Nc)4~h+`HrolFCth!JrOsaFT_I zu2K9t@n~dTB&awS#a-z*o%9~aba@`d4T;AXjU-`iuW0VK?<;5-N#j(A<_mAvfz(lZ z+_f*7XV{j*h`=OV6c)|LU(AH3btR~BDVkq9XbjI%_7=Jmk2{iLc=W}w*lhb9kKT>pdxYkw(cFMplCiwP zAPzUUSK`xov3!+xF}8W+pxo|Q9->!+dwK-mQ;%3KH>w%+wkRUz#`4KmI^}O%+afG} z6U#@Fjh5+KF=M zUmaghJi$H2UYB`9=lA8-6MTJip+HDH4zxbObw|;C3h`KY>I4rDas@NHT6q5G1RtE1 z22+X0JzXPs4e|KsY8sf%kKhCL*Fs*7E7b3a;2(&`Q#!KH^LPYbOFXV$SR}~f5j=*D zBivUh^X_c~pFlhgi%Am34vypth{s${Y3#c?k}oD6r9$m-1;x@a^Kz(+Ny1SSOPz?v z_|GM{^hPAl(DjDVKcD0Fj!3@f(HgMNYDJZ4QGE22$AT5aqYTATL`9_RX5#UcQxsnv z?kzk>JVHhk&v`l)>#V+`){`i{@u4|JylcP{6idA=;&7pDC6)-Hxp`|zCd7;h1u*JY4A(jmig2+C)=I~6 z$GsZ(o_PGI8q1d*8iC8U{Qx=p*nirIa_L_keNF`PpwbeV_jG=>N`m=vgF-?3G)X!C zPr-bPge=UJ?f^DEgh#r&g1Kug?AaE=6Jpb#WoH@G*o5%zv&uleA`RZBgz!$fwNO^% z3I_K>c-O&npKB)z9-TvZr-}3owNa5^$-+?XLC3jJd0)n8ZzvZKk5&3f!ZF^V{DvXj zubN7uw=k6VFRz2iw)S}OZ77$sDTlW~NqAyt7&qjZpj%&pd}SCfJLnCOZO`$xX&8U? zc@0cWZ^e7jVO&z7$!*_y$EB zCv$=u5|2w+i*Ty`2|k;2>^enKxF+ZXcP1WZW@!s_FP`92h(~FOfgtn#1ef{Lh=cDM zfZ?bJo@Dj_?@WkiVx3M!KL^Je(IP8p4M%G{dXex!{Z~c zo_Ne_jrgaXD3|`#aox#4?z8o}%tJcAYs&+iX z^dKJB>!fh_S@aW;tC5syF4xq|%DATBqe1A1x8f@z;%u1Y*U zn_DCp&4PIx9p~$UN||kj!Mq>w7#^P_lnf5$Z*;!GL2qe1bSao$zFG%yVfL6vu~c`c z96V!_&~97^SIEkQrOhQ6zbS-2)$xXC;_j}4O?WI&B_1OvmS$aw zl-));u9pnu3!+Fz;xT4+C{KDm7Ech5CF-GkOqDrKARfPah4LEWG1#UOXHYCn2`fe! z;?cD>lxrWTLBp^9IAcH<*P7Ujv!oTV>xwWgLp;v;)hz6DAdDxIjy=;PgfpYUcn0zK zdX|o0Q)w8#qVp5aj2j4JTf;aIkHsGiU>n7fj^P80oD&I`DVCN@6{6L|05}9=k+)1V27hUPBQf8myeZ0K}Zt*4Dsh_m z-EF?p+7)jg1p z9Mg>FRx6^*g+QJ`JpNeFBJ_D3$XAe#W&j79K2?L@isua2n`e7M5i-#n(u`|u<2g@SnEvFfM~w-_S}ZBshH zHPwgv6OYerYa!*K4{stKjfux8U3_^Y@z`FH28-tT@^s=clXyI<;mdauk7`=7P~qdt zwTVaVIYk2dd|xq-b|Wigvg>?#H{x-ALXuE#&~bj5cwFiujrUg`=f1?FZn!;mGds@X zh{u=2xW@tm;_)ZN60KSy zt4KPgIr{MpG2TKI;!)y^AJ2L*7EOuA>D7LG%wuzW*3f{O6iW)0ama{AABrVU;_;?+ z4%X}V^9#h|+b{m;>+jEFiN_u@715~BpKl@_^S?I>%_x>mla8H}B!s@B0(cVf*lU4~ z;LN%J9zr~Jj2{S&hXZ(HeIx#CGJtal0sNc61C*Xi&#h1_|z%B6pG+z{^0do^B_c}<*1UvcNfM+*gB z#G_i1JD2TA*S8rR&~2Ot&-QkO{?4^9eX9qbpFr2g?PZW+?ZLaxErX(4X>cLggX`(n z!a42=^Y3}^%pn~x-a;0(OL=lr;xR>~NYH74C--n`AP7~eVPpwVM*et2IET1o|ApKd<9*VtxM zSgwfmi+y+t@mMsYMfgeAhi@kxU;L5~_6_vmtBJ=053~hy3VirI{hz4Zb0A2(^Woz@ zHe!0U0W28l%U_s2z=SE0kg~y-f0-@Bry~nM=ddr2wWs^lyejaC^X2Vk8knx%1WRuF z@@&@;xMj-^aBA`Wr=2L5{?)N}yerp}|IK5sTV(&aKFWP@PC&b>guT zT_1a>xbZ8*qd)QJ?&8Le5|88Q`WTk!#si7RYT|KVjT_%gJZ2G(3wyisJ;Y-Vx<0-D zcQKFElPYBf8@ThHq~ocRNy2M^?)(<JyKe6ib``@YqMflW+dRqwXwEj>Mx0 z@#wAQ$!8Id)x_gviX}DTaS`$OG1rp^6OTp2~4V zT%LH`N<7}BSV|XN9}^{nO%Yx^fq0y}P)E@Jsu%Yn9@kD72(`^#{4wz;|H%M`QY<|u z9u{{0I`c{+Z`k_vIsSU@%rC!Q1Em?QC^g!J`>lK|a3CIEZF1pZtD|IR5Rd*x zT)3sRx9}b1)w+`|Jmk(;97jC%sc_-L%FMCb#|B*6$(1iW5QnLbm3U~5E4K?M#`R7) zcw5z#UofgcFNpv=ynPw8YP701Kju|;xYQI zwjhYP@p;7KoxTG>-^h)R_|S;Yo*6*+2{-O$@&KKtMMCduZhZGFA)1dafNRZeJl8f9 z9}BDC(>QmYZK8px22BvT)txVP9D!en$2xQOf7*$1>0ce6t+3;9lYakxd>n4aZ_)3^ z3v_*iPj>tw{eIj)JO*#I=eL4fVF&T}Fx{SSCLY^~$9gFTKA3n6BObrZap0?oN9`O} zIK10|4(?B43-RbjJU(r84)$M-H+@5%hqwC|`i_Ux{@%a2lvv5hHGe1Q-j!uyf zZXfBwQ$;+^(-9n6>%tR>M_;-=t}}Pxl61eCMAt_vilxDHzuJR%e1FGUKxtX6UJaedp+7p)ia5CN3D3rmA7E4|>zYJ{3(%{#o zBm9J6Equ&#g|?(4dw7%tbvfsR=l&sn$HkC76^&QfM9F>YeJOlLgKNZ(VBmB_7;|sj$vzTINlqJ zR>x>P!#Eq>ddnQUerQ0YUpBn{U>vGBRAPp@E&mi)jOdVq2HCd!?fx3f{pF7tz3lk? zan0CCMiCA6+3};qqhNT8(4y3iTab>?Pb7qy6YP0c;_=xRZNbMQ_B@#CZ{&V&k5^l&K;?qvzF?s=Xaa)+f-kje%=+*bItkH;T_

VyDZ=#3p`|T9n;m;$P5ozcUizgW_ZZD z%K{#@JY_b3=dg% zS-?YPc*wfT0vn;m;$P5ozoQKTtkad>@JYV@9Aw$ZU66z(e-nA&c{nJ$T5v%K{#<2M<}ChwQ;a z7R!*~A$#zU*)n8!$OI2rEJKEeOz@D!GGutj9z0~W3>h9W!9y13A$#zU+3vD{hfMI0 z#WG}g$OI2rEJKEe?7>53%aGwA6Fg+G3>h9W!9y0ykl`T{JY=>E86GmhLl(=B;UN<| zWVQ?$9x}m07R!*~Arm}gu?!g=GQmS;%aGwA6Fg+G3>h9W!9y0ykl`T{JY=>E86Gmh zLl(=B;UN<|WVQ?$9x}m07R!*~Arm}gu?!g=vVn&zmLbDKCV0qV88SR%frqTSh~XhK zJY?NP3=f&%A&c{n86L9kvVe!o@Q`(v1w3Sihpf9S;2|?SWZh)}51HX1>n;m;$R0do zaUQY<4_TatOz@D!dB_A0S)7MV@Q}qaWO&E~4_PcjhKEe>ki{}&c*q0~S==sSu`I=& zIseOA)79L#saKVH>PVEHGNHuwPjZ!TXHNUxxA-&X|33Fd>+ze5CVR(t-3|(U47jn~ zo21VV9`e86J8ox%vf}@qUEPigeZ1R=q0jR*c4hqS7xW`@tKJ_dYdfzQm&XBPO(%A(;j3w&l}(eRlWKC`lD z_{Q7(i-ylE@R^lG!)Ipr%${Y@@RQI4<SAHHgJsfd^>F1u}C<^>RM#2TRX6?P%eF+UAn~6 z14Cjn==;Ow(zX?x}!d z>{Y>QPnHkEF*b0FedidPZx0UfonuTTswMQDV@$GcR>(QV=54JQ-#Nyn){21d9Ag?h zHFMB8#-`A)lp*IBQ^lscg3d8E_kQ$)&M~IM+cJ30F*a$Rg?Y{~HVFs!@|dn(`S7idIRb9|$FDr)?Y%D^$!Jr!R*tx0f<$vMUZ$5{7Nz%e#!qpIni3OL3D$5{7N z6uwrP;27(k3OL3zv|M)GQ}OTX`~=5X_f#Aheu>~18|xTXx{#TkzgkJwF}^i%A;B@$ zJr(E6pCmZOx~Bq;F~Kp`Jr$8Vo_R6edfih|=ImI4W2}2BK6`V?YcXk~?x{F7ehI-b z);$$-Pag0ZEZnSnDk6F{CpgBsry@)8X#~eu_f%vWF_hpK>z<0LDW-XFjCD^%qt=B8 zjr{YA4OCB6!V;$q%^C}S>W8G76xIspOW2}2BE~o0?<;xsyEFXqr zY4^*BhNX;29B}rE{0=l;27)fVmQVIjH=Q;(;(ZVMoblK8 z_s)MGb3RY|9DQ%S`&=+;{d3vJ!0#3Ky?Qow``?rg!}S%ozT{kAf$M85ABO8IaD9#C z!*G2CuCK9t7_KkF^);3c!}VpjzQ*!lxV}DIUt{@j$5~7N=d?^Yd1V_sXZ0&0_J39h zd*00Na3SC`hu||SABN8y2cKEb)$p0);4>>9hR+-apIOh|@R{S_GY74A0iQVzKC`+R z@R?)bGY75DeDKEAP(;iwJsWT9-q!Et_X7XLPUG{d7>=>>VK~MD$CxZ1?)PnVzhv8R zWBD)~V;_#OagMPM$5_v_aEyI8#$@?09Ak!KY@B24!!b6N55qBLIL5~EVK~M<9AiDx z!ZBtz#>P3u49D15J`Bg$hht2Z55qBLIL5~EVK~M<9AiDx!ZBtz#>VntIK~Xen4DwG zaEy)R!*Gllj+T+F;>3=F=jZ%>Q}%qW;n*i@?ki}49D15J`Bg0 z;TWr50mqo(7#qun;TSUD?gz%e$K55qBLIL7K%z%dp$#>$7`7&9DW<->4{1&*=uVK~MD$Jkgt49A$^ z7%Lx!V=Qotjpf5|j0KLdv3wYgF~c!dJ`BfL;20|(hGWcdjFk_=F%~$+%7@_?3mjwR z!*GlRj4{8IG~Bd>D=~!!b6N55qBLIL69{ z;TQ`XW97qej0KLd@?ki}0>@bSFj{qSXw~W7V6^Ju(5h3uidJ15T6M}-(W;9>t4?IAJi<<)4_30if^tI?_xwCdQk>IAJicC9)=tIoH3GtjCNwCX(9suQ&8 z$hGPOtvYghGb|5LXAG@6L932jtB%pCQ^y#sIzg+BT&s@Js`Fi|PSC1j*Q#T*>XZ+o zRVQfGvE{>P)d^a4>{@kXZ+oRmW)6DIZ3wPSC0&*Qyh= z>U2-VZ&B;OtrM$bj8+|^Rp;3~6=>B7T6JXkaQ%$!@H*{WvU@7fs$;b3JlCodwCZ$E z1zL5CR-NZsb%ItMxmKN^RY!JD1zL5CR-NZsb%ItMxmKN^RY$H>$7t1gc25Obb%Iu% z=UR1)R$b8UsX(hv(5mxXt4`3W^IWTr(W(o&R-K?#=ebs$pj8)itvW`lE@byqpj9Vm z)y2719d?Fa4Y^jGpjGF)R-K?#=et%NqgCfyK8#kKpjGF)R-K?#=i5CMXw@-Vb-vwG z(L8fmL95PptvW`l&UdXkL932kt4`3WW7nz^wCdQk>IAJicC9)=t4?xdGI!3FG(W+BE zj8>g=+jCiW9ivqzXw@knMyrm|s#89UR-K?#r+gT#Izg*W`7l~_j8>iUVYKQPtvcOx zj8+|^Ri}IytvW`lPWdoeb%Iu%@?o^<7_BXZ+oRmW)6DIZ3w zj?t=9K8#i!qgAJT7_B-+t4{eaT6Ka}o$_I{>KLs$<-=&z30if^htaBIwCa=(qgBUf z)hQoFtB%pCQ$CDV9ivsJd>E}dMypQwFj{qtR-N);wCWhGI_1M?)iGLi%7@Xa6SV4d zPX$_af>xdGsX(hv(5mxXt4`3W^IWS=(5ef%R-K?#7qWXQ(5e%(>U_JW0hXRj0d-(W(=)>e%vOwCWhGI^A`QRvn{Nr+gT#I!3Eb`7l~_j8>iU zVYKQPt-Am6VV!BNg+bOa{&Vv9Vuvc`)ZJ@^Q#P;oQ_*MJ?D^I;HORH<{x=WDpe5Hl z?>Ig8y2jkQCdj+?sB&P}X42X2nsoZ{NiQRGooRa*L~bI>GX3O-zo6F9nP*{ryqB%5VDRjT6Ka} zojS&7)d^a4>KLO{Cur5FV~kcEqgAJlF3{9$GVn> zaw@dyBGIbTvo2b79$IyJ)gjSuNx6!JLL#s~Dy=c|NwJLE*&%J2X#i3QF=U%kx z;?Szovo2b7acI@)HClDCXw~Vt7p=OgXw~Vt7p*!$tBzc&&O@tC&%o%@`RLP;>(ep% zbmaPUj6NN?J{_Y^XI!6-(Wf)6Psixf8P}&{^y$=3MxRd5r&B)}9l9Vobb3xkpDu_# zow0uMuTv*_ZJRYU9fqZ|eY!~W>68hhPZvU;&bU6Ehd!NgeYzm}bjJ1RLg>@!`5ApW zAALIG`gA_}bjJ1ReDvv*38PQvqfe)PGWv8r`gD4JMxV|{pHBT`^yz%`>C{g~pUyA4 zx~y@1I!2$)xIUeaKAoPQ(Whhd>C{g~pUy|0PS4Ni(=qyV>K>y{$LQ0ktBgJ!qfe)< zGWv9kKAo{l7=1cMpH4kw^ywIVI^+6u@X@lUON>4pqfe)2VD#x2eL8iC(Whhd>C`1g zpH9%HQye?xXl@b2&kuPF-U3 z=>&Z`b&1iZ6ZGlGy2R+y`RLOb*QaCj>C`1gpN`R|Q)d``I!2#PoniFp7=1e3JApo( zpiifJC){gHI>*qbGw9Rl*$jQUVD41!&X(xY8T9GM_2~@ybmaPU27NluGGX-T4El7w z>(d$Z>Dcw@4El8J`g8_;I(3H8r!(l&sWXf|ok5>YoniFp4El8H45Lp+=+mh)?0TI# z1JS1opiiggaP;X2eL6ksqE8n@pH9!le&T#V^yzeWG5T~t^ywmhz*!o7x*+;=v6cy= zPZva=PS4)x(*@C|(=$2xbV2m#^yBE$1<eLD4!(Wf)$)9Ee?^yv)xbm}3aPiN4lQx6$^IzpdLJ!JIh4El8J`gDXo zoqEXsZm4O{r_)^)=+hbW>2zlW`g8_;I^AV~KAp+^{UUaKI)gqPyFQ&kpN?Ihj?ky` zU7wE7r}JH(&Y(}nc8>)5bOwDoc6~ZRpU$^?B+#cb=+pVGPeYcM+pchdua-mGPoaXV9n9UBu|q8T9GM z_2~@ybmaPU27NkmeL6y)P90$M=?Hx~b%4>QBlPLi0Y;yW(5F)e7=1cIpHBBk_>$P5 zPp5k%(5Ex#)9D@w^yv)xbh<|ZeL90a9oxMS=+hbW>3r9xGw9QWT%XRMPZzYz7JWK{ zKAq?KbY^kkm!9j>8T9FNw=nv227Nl+E$muy#-1l#W6oG++aXbnP3Y6aWv`nlz(@I#P!DbYuC2Z&y7FJ+2?dkI(>fEs?%%Nq|?W{R-In|_ji-)Ba`dX z+3vHRrT@DN?%C~v+uIfh>3Q4rqxDRVK3x!fIz20*PiN4l({tT_pC5g?SoG=ioQXc& z9`xz-J!|OGMWRoq=R@@A0_fA}d)CmW3!qP@XGrwv0_f8zQ$?RHfIgj`KhdWPpiieh zL;TOya%1%AeDvw`9E(0(2z@$riP5Jc^y!op&)>9^(5F*Yj6NNqPp7OHeL90aow8!| z=?waG%8JpaGjE<|S5}NZ9idN0u1|;8KoT0)r}NRLQ)Y`kosT}9I=$%A8T9GM_2~@y zbh=v@eL6y)PS2v~(-Hb~%52f6Gw9RlZejH44El7+Y|*DP=+h~)MW2q)r_(bh`gDXo zo$eM!pU$99r_2_8IzpdLnJxNs27NkZw&zdxC-mv`%!xjoL7z^UE&6nXKAkdK^yvtF zI%T%#(-Hb~%52f6BlPL?%!xjoL7z^UE&6nXKAoO9(Wf)$(pU$99r_2_8IzpdL znJxNsgg%`zTlDD&eL7{f=+hDUbjoberz7;~l-Z(BN9fZjvqhhd(5F*oi#{EpPp8Zl zeL4?)I%T%#(-Hb~%52f6^U$Z$^D6pugg%`zTlDD&eL7{f=+k-V(pN`O{Q)Y`k z9idOB%ocq*4}Cg4$D&V1=+hb3r}NOKQ)Y`korgZ1aeX>MpH7)A`g9)pbb5|OpN=A{ z_fTg0F#8b?eL7{f=+gzzr&DH&KAnd?opF7-IP~e1*`iMuLZ8l9rx$&?Ao_I1_31+B z(;3&N^U*6Br`j?kx5W{W-@p--pG7JWKGpH7)A`gDXooibbW=?Hx~nf6i{P%QwHc9?;pCa?={ha<8U7Xa9q_&7&kc*nX{Z+uGW%q2ELNwSDeT z|K*!A%>F+=SK>bx&x!B--E-n=as1bs7+N0I_vX9j=~FTJn)!7W>)sxGt^f0LC*XVd zX;xsfWfboFC;KyT-#`85`#1Jy=)Qmbncc&meeR9_^KE8rQoqi9|Np^gS;;(_5-$D&w7~*N1z`=hC8Z3GeEId4AcfqojAr0^Zvt`Mf^Mz|E88@anbA zOZg5A*ZZ2O{>jLpFA9g|zZxZ1vS0J=C95p^V#8(DqV%Eh|E`R)ALrf)L$jNnjhln( z@dq!(ot^eFZYHj;uG<=SFKyb;3|!xPF($4Z=hW+YALfqxp;RHgp56NW*!Qy+3(dx3 zvj23t>WxyxLSN(h;Ea4yz1nV$!`CVkTU$Q+C%NS9y@@XzTFl!mNv) zJ{vguwN~6|#S-or87(t+-{Z3P8%u1v4Ls-9gS>5QZi!2e{}#6z@O`u#`c;jV2U88# zdc2ZErxi^42oA=>{%wW-XUUP*}F53KyCZ%N4Su~p>2|Kp^n&fhU;e!zu-)G|Kr(- z8@Sk}u3UU?Ihg|w?navq{9(mjGCpPl@2qpi|0rS)55)K8&5Pt#UX)Zmx`FeD>w+u$ZN4w}BEz(!k72n9mb6@jQ!-GFs8vh;t znC^Fdubexa1Y z-&Bv5mEZpr+PY0RckO8Dnks*=@tl4#_rXR^)cAU^Wy>m3cX+sjUz!#w^{?=qy3z7y zcvkP9cKu{>u}!?<&8R?$G<&(hhtaa)kG{b?=Y@axC|XWTndYVZB0^#pgv+LDDdhN< zPq=i8a2ZznEgzino>Ywtmn>Ota<+cyq*dW?$=m1*N1@v|3q8x6iFfnRPWfeM8tm4r zvY21t_4{i0nHR`7h6mOuBX?7WOaGMhIN_~uxsoYd8dgomHJVhCR@meCSD!WhmT?i% zr)s$1-z?jIv-V8;`HQRm;k%XK{)WqgA|*GyIHDbAX**z4vD_Dr**Pr5H*_xBv%1bG zX}qEH#xd?1pX<9y)nA&d!kdpNaii{jy*4 zAGq1ocXZ<5trMdp$=2N7y^f{nLV@A(6f<-4%NQDUufMFs%sdzKklK~(C`Bi^%$-<>i-No2cQD zg0d8U2l7@dLxYyC<-vG-k&Ew}a}i18DQ4ZQYRl-Cr%iO$ZO_@#-}q02oWQJm+0zf? znN~$gW7ZA)?r9*~!hRBqSvP5Pq<6kUKgokxx2#{SK$=W@xhZDd)QfY1$LvA8C$RH#yl@uh-)U`4O{jdX0kgRkLVmgjq*VYJ1B!v(CEHP2Q)#SG{E!X5Eiz zUwD5OtSlWd>ozVN-Zfm{*rlWHMjGl1#?D`guk>TAge$55l}EJ~gK~ySj>am{->%kVQ zGD_B*;gbGsFUr;y`df0E9tTP3GZ zINS(3uj-)xu)kmyS%P_$?PVsDvDrm_AM+|DJgA9DM)6(DtDhfNGj(Fp$xO_vpLTvj z`*ZZsd38JC0*bERRp-^!w>iu)Im&VP8BWNV&KuUFij>5>@*>#lQ9c6uSi@z;-W*i) zd;E^WyqY$;Dg9a`TxMckWmplSgLpsAJdGl?a3K>e)bE!&Xlnb!lDKAdS!)Tp&H%$N7~2l ztzInDCv$;VI|sIYP$+a}XDU6PY;KS%bUbBr+_(7nohs=<{+@n`y) z&hkZ-xcSWTCP^IrT$he=om0Kc?CK@FRLPRdfq*~5F$wYLmTeV9s5i1J$J`dki<9z=oXJ-n4)kCbZ1cX{8o zYVS3xI7)Vh2KlG+eB{NZA1VXxH{;3$jQ8D(K60zwPOjg*M0^8C=j0Ncg<{NZPKxjC z=dTuWXj^Bq`Q%1E)a<#x@z@T^(I8s#v~DHqKRwB{Pi*ARCT!ryUkY;pe0;(3KAdJv zSyQ)LxU60{i<`%mFo!dS%SSJm13B87yK^`2(Uhk->&LB3s`oZ<@rCR8pPvhv?FX=L z7(MZlv72dl1ZKr=_xV2VA6GqC$8%~Q;-T>Tb`A@Za%db(JH3HAm5G+?4H8Jd+6~Os z{_8mK2wqUzx@PY4wLI|aiyYZLi}@uOCSUwqja$}SMGbS}-{V&exz+L&G&KW$FMpj? zR!GqNm1`|$ocNF*TuN=ClZQ#)zgqFs@0Zfx6w$JCW*%vnI>PMRy$0>C!ZIprxM|sT z4PX8$vDBKB*yOv6*ImEt&v!b`rLixgq}Zw9-1WjN;wMou4YTR{&V@}|Ud?-Qr;(ip zAJTc8SKhlgme=Q;Mknt_NvLLoj9Zz?P=9%hkAXD-sI_2ndS z>mAd6`xC(SAr3TXzaJ;WWn*d-02e7 z!Cz5QFRY<#N}Is^AglO6(k3$G)jg^cvx*-Fi%6oU>*&a$abiBvcKsB zYKreC#qo-=>OpxbyS$uiT(g7A9!^eQ<1v+w_L3ECdr)BSDlT?5O7bVIMds=%9=9?= zCf^w*6(sp!#02eXDsb+=gdAh6UGMDJPwW@8yqv zukG!@&+{$qkgw=}t2k6(Yf zj=OB{Df1>rbEAjrxawTY&4VBDi-Tb@XBcyl9OM07DWm1WJ)CoQee3tg7%fw3cadMp zFW^2&HgH&MX}rI7EPI%%|Ky0{n&sI~mMdCjBZWY2kGvyZa`U2lOS2%a@p>jaMx74# zGK0I8@G#FQex6TDP$*Ex{oaXNREa)zv%PD*T)|1f=s5d3=xUup!S(G^$JyUO18Nit zPTW=`*8UDkSglwv^~m1(JLPoALct}M^Xc!JLg#V@x72<2JE-xFw84emyWdSylDrKx z?D6h*R;~=c1&S_s9k9QH>fGHDDECpCpuI;P_|MotrrFtp_IJ>Q7OhO?VJCSmX84s%J!kitmI`N!^6t%Up`2;ikP3Pxc-J?6GAU?i$S5fm>hb3Gc|4qN%QQGW(IF>`0 z;iv!YV0K?!#|JROzX^6R9lI~!^Z5HyU`DukRH+HaV1`Hjw2ex2Pr*a*ccbmAe{X>}HTQbE_;Zy9_!wf%gGeqTwF83#4hIg&q&-AV>{tC?SPUEVY9s48vPcXyF z4rUscXoCMKW_Z{1{Y{Dsef-gw;VH-UH$N}&LpdKWoyQCh zK8P}1&sL{0nBhCFS2SHe2&Z9~;W?)5rQh1t@RDNY?5fg@)?$X&pU}fJYA~M4 zVrHJZ5oWU1>`4bPV~3VyDmiVTR}M4n=;RP3+_&3%h8doHMklj=)*2dznY?0aDYJ3# z44vU&3uEc=-JiWQczmyy?M%YOaXQ04Pus@qtaXB#U= z(=0r`(LY-$&sSM>h99fn#F(`As5ic!A0zXc^&<{aWz6thhc;22orQIV-x%7^)GYIs zT4RPU>-xSq+c}x(f*HQ0d{*-?&qX54@Jjnv)5`OPs^a-a{QVtmJJEn@;Cksm&wLV* z6&< zW?~b<3?H6;9?dP*pM3m0Z?~IGouh}-X3X&DHHA&4!(nDBX85;gY7JSL+C*T6j~+UW z@~;?6A7h5!ypqTC`o6Ncff-)nkF2H-_S2oi4A1=XBF(Ox#e9kxzB2bX8gy}>h6YhUTzbURrF z7{x^OtuX0v(LLpo)?$cGQeD2 zTFUDI$&~@N%2`(uuFJ0su-Bu6q43ZdJxiDFoK8OJbwlsvC#=jJDwZHBVDH(#Ygagw zaaxjqy=PyurC4aysiRdb_xo~8(NOU{t7GkTwe$HyH?b<%UYB{EHFUH4Ouc7MIW|pb z@Q|%~&px?dD>*Xt1Qo%3bn{Ug`0w`$lf93QTwPOIpMXP%``>xl7xAvl?e+fmN^DUX zvS=}U?{Mk0tF#=*`2|_l=a=dz?U$}0%lcjn>LQmL&LzwGI_%xXt$QUS%ld}(LPuly z1JAO))mM8;?R;IxvcAXTaR134kY#kq*6%JEXSrWY)4lxRydFWz`o0^o zm*-^uGS;%bsY(0E=w-`&%lcNtRgu^!34F`?a^aq$QQ?QaWqmdKN67Bq_xP6Sy*eg5 z_EAFLa=$_2ao-r3pDp)m_XOv$QPq9R`ud;nd0MK`zGZz;gL}$aj$+ID%&m$d-(+XY z`bu5yCO@T_#Fq69K>L!rG-1p1c1(}uS>e8Kx!1QB)#1B&daB=i%lb0q z-pO-&J@+l^OY!$7QlgcxWqpO(m6n5L$FpU9O@3=Bmw!Lami5&}L*Tm_%h)o#i9a-x z50hPD%l%r7DImiSZe`2;I)1j9`(4bg_s)qbY~Uw971ev^$JrZ6!JCiSvcB=Db4$#r zgKSwJ?_SFZ#)c{Dqah#2(#CM1aPM5NNen+8TT}0yw{%_3kIpvGd*=>`v&z$Uzp!O} z1#6X)4uyM=Wqmt`RFLec%8_M#X+~C-KQ`Xzj7Btn^vfhb`;tKE8zP{dpE!*0+93 z9|?r**7w~{I$27J&K{@dx|>x;Z?1LikbRv(o^z?yGv=mL)>msux6S$HWYP0p((?m1 z=eYDjAJe)~I_XjWhJJ4Rzju399C@v?#7zHNpZ|VLbLm$lm2$-@$qUP8T~_Ji4~@zx zQN51n_0zs@D~xr5AKJTf zjlN!xBXPn|Y^7iH^@2LXFUBoR^;+k{q=uX0R{!|!wS!YpqvB>3&!w!d?5*r^cM2EM z*9*pWSQvYwWKn&+ApU1!zgErbrDS2uIGs_0$9y6qHzripm+NFLY2LYzvc6;3dl7c7 znzFtRnkSXFD_be+ySimRcla_&SzqT*dvbW%Aj$u?41-{db_%HWn~*s{Ko zhu8D4S#ttQh_(u7)zYtTVsmlBpXjqiayp$fXJymC^0Xn@vtMIm?#O zRjXcA3Lej)jIL0rw30F1ZMG~f@1c1-drD8`b)P;cFQp0>P+m9Z^=v-AbC5E+xlgC@ zw$Ny0bgiO`$jj8_l+iV;okTv#mrxm9WFW6(Ur#u)Uq~y*}IW^Z2Xyd1Edetrx?;mhPl{@6e7Z zoc%#b<$FzrX5>vzwkY2_kRI;#?(NF=Do-BGY2S8NzV~EvM;`D5K0RjCi0|6)KD2u+ z-}@j@b)NWrZ{>RrzAVlIPgM}h_Y&WH<9~aml32cXqRk2ac+)*PqYn4nDz`Lm%aPlRjSOzY0c(<$I~}F7Tt@4=La4-0`wMX%phBH98WPALYXS7YK zd@pg|8=N*Gy}lkXJ^v}*P%ekQ9&x1b4xU({fO5Zq?H6#pH^r3uJ&zl~-_0wd+;3z3 z+APV+EBA}89ASFQF0X8@*@MJp$$|vR)@EJ49jNvD^?>DX)0Ss9{Y*pUY~7RJqgxp} zDQDYyay6A`)?Yar5@mF<)G+02QS(xJ@An<0oNaQ3SN^!ABaG#2DNju0gwqBY%h@I! z{e@3F?QSe*t8gQ=%xKokSk9KEbty^rqh~BUa4cdFgUq-!%Z1bXU&~nJj z=XO`Eeyv#0a?3UwV`3j{E2`Hix<|&%=u$whH)og{SEprmeSGYe-Em7!rwZD8#;{|T z<9hx5OwV=GpC<_YwdYL0-ZS=Ul-Jy?P)WJp%45Un*&6Ig#=T+3rX~D3pY=DD{M8)S z<*r}gQeQK2<7)n=$i&e0qkHN5ywTG6RShl`7iALRF+VgRzws!cV)^j;&TfU$xTh%hb}C%gnuj8nk-9PcJU!4dz(^O;wS4b(uJ0p zl_h>3m(Dbz>dF#lR!D9ROC4p2Pd+WbdV66@AX35U9}u`IFu z-MqzjL|Nj^8%ey4~^w`eJ>s7F7;D6n`AlO&e#e3WsR@Ma=f&EL`t^X*^K3Q zi8s#Rn296Fa=cOPzUKSCeoB_(WxShBip)PlC2Ur02Z#lo|xBc5rMM8Eak33WW z@5LQ1mg5zBxQN0!4G_!mo}Ru+o33^d%kg&a$!PXA{zxpx^L_|3CBLpBmg99;{DG-G zIHy>S_x$6IrW8G3%kk!A>~DG|Sj(2<&B;3q?q)T%9B=)Xqs;RexqZv=dSn`DD*gG7 zXF1+K)d!n@_kE=^`F6Q{!Kpne=u95fGTa=xP*-QNct1wISEz8va=h8E8U!vr%p0;C zuX~fP14EN#4cVDog7*ea4NDQSGx>FwzXP>m9>&?3T=(bqg2mGu)9ZveGY9ugTcX#0 zG|d}4|3UjW`}i(%3I|)SeW|Y{-MLgWSfR)9J@#HZah@W<>5b<{+L>H7=K}A8U;B#X zcm*Fk2__#Q%JE)ji89-7S0&5w&JGJv=(9PV<#@|JkMabp*>b$v`)+#QPpd4J<2?#y zr_rat(!lXJg-63{M2Y2ii87a=zf)Hf%kd^R8Q^^eR&F_7W@QU`ncyxJcqverYqiuypB`VjG@81I*H|YJ@IV4v9Pi@N7~0yss927dv~LnBv~>qtj#s$SIcgke zDVF1XUF`-H%J;EYjyJprQJYIo_DSZEEv4omh@{ zVM!BeerGvbjyK>yJKFKr61E&q`sO#qpH~#i@e==%!2C2isaTHpdU-F(v}gfaj#u@= zV&>qwvSK-2_m^ex{*K~eIo{&ODNTm#&)IUk*9S+_lj<|sa=f>-Cs4xhDcF@1CB1h< znyaUCh~;?oyJt2{i(g^;TFmPuld1fr32ZsuAFdEujTK# z&9*B?*mArZr@yBD=LfUpctv6s(1K;X*uEB%cuiw7WXEH+9B+MjwA0UQV$1QmR9Z^m z+1jyvEhb;EnW^3Q8e5K+Yd|X#zT+ph9PgW+CC!{{->~I)_Xn(^dF^Yl<#^8vuA^#^ z5o|f$w`V$-a(B0|<#@BdEN2!h{ERKfJ2Y`4UH!WRTaMQgzZ-u#vWzXq8*rkVxifS+ zTaK4vP6abLWev6*ZxUJrO-`m|%kf&i-bvL{CS=R;_DA(L^Ut?r%klb5t8C7Gor*2T zo9gYM0`;!@mgB`lMw^@MDzW8wFShhCMVDq^%kg%6R>iD~S?ybn_xxIjsz2M{TaNcZ z1E#K@&GaqD%fGOn*|>d{Z#iDUhTzPhKSP$|Au>VB$M*Cs$7_Xv$s<#@ePR5dXP{>1*KFu8bgFRe`ZPsnn-bs6{3`b1G7%kfGF`kA7KW_y<7m5PZl z#}};iEXV7ddLJe2Q)Rd1c%jI?W=pN#JWESyz1NZ*|jJT)itx;YZpjyEKqgTdwN}I z@}t1w3)l7DeB7rggDa1Ol-;dJkvZ7%_l3&tmVP{~QbFANTW9a(*2Uf@Tl=cBSA5>f zVB;F1&fbFStxdwLhuLzx95EXy>ZiPVkG$rO{@ypoBE&j-8%o{x+UBe*mgBvhjQ#LE z@Uz4{^6d*X=+uVZ>g;`gbBK3;ysyq)Y&cv<%7NHMn1g8hg?^Abc)8cYNgKJ#2quK$e$(D*{lEH5A1UMSe?DQKNg{~>+t@3Fs^6G9@3!N z@0`5^>(h)Blk3e$h4cI z&ffi3#Y~U6rPbNH`RXZsz95A2Vq9Kz_Iejj zYEHFyqkQk|+R4607E@ggtRF;Biu zrp{j41@%qys|nTFt6L(kNzj^=-G$H1Zsue-t$c4%)B^e?qO0B`&;4Zy^_|^P?~x16 z|HzCqx0U0)X9}5=SJo-V`{(Gl*h|z%Io>B1KQ{Ao|G}2y)oHSd+J6(&d*q$h)=-^G z<@Fx<#aX!9G4qt;9UGB_Mx3Z9mg8M%(}=!m6t2!*((7aCQA}yE9B+L?G~CY?RcG(V zANEk?%lY&kISKZ4(SdAwkDUCQf9UFjwCe0_d6>YQ9+pI%y~zBj%<<-rl;cfqk=ZP- za8WrPn47VT-Ja{f;!He?n|G^OSoqS?%Ij{W%DSfb%+Ji7zaGx1C>1)RP3*A!0Sb>7^#|F!>?-Rr-49>Z$^ z!7%q)K*{A9g4@%@D93wMBTsP5wjRpyKHpL}82UAV&WhOwiUmvTU%baM|D_Fz2FFz0 z8fmW&bju&CezCf~PI_W-j$pEh;{w*%i~pI}IaaB2I#b8J*6{iCcIH=l#n#!Id%dqo zK4J@7XK#6uVJ6tI7F%a8V$CS?bMN~h>+H1~H^OB6H5plFZ|v^_%}38?lXdp`UhidM zVvdq^_D0;QWBw?YOr5=6yOvOAZlN5n)V=2B^Nr`|9%j^&A?t{;l%^uBqUG#_?B=V+ zr3rr>mADRrZxM>Y^`-iIo^l_%}wjDi)>xHA9JmunY}#ac$a@)OHpUaDaR{d z+L?5j_ONyBwvH-hlKy|}y$7^aMYi=%&KV>}$@!AQJ-ZeeiK2*P1SRJvISGQ21SDt4 zIitcoyB4TOFc6d|f(S?uXrdV5n`_5yf+bWJxA8-G-ZD#A&8MR&&O45n)d_KzxcQ>ZvPSa{g zV)gNs|NOo=@$oHRSi5hY?@q%Ww6nt6^?q1}>O81xg|(~nT2K1;^{5^K5W+Qf7h4a8j5<>q|emdm){z;)a^^HhP|b~ zHB{eQi9Rl~N`Gtc4)mq)knh97306!G?&jXBPS<+q0Kzv)W}dzTLh zr?4!}&CxczUVJ_M+733K?PcwuP;U>Dkbe-x~H!@J)>!<2~W@ z9;NC=1zYwr!s#uYSDt3Ro)c^2@q2og&XmKOY{bW#2whWueKRB8UE?Ml$&{OCgxRav zu_QfPW26xuFG2A=Cc}}vo^Zu&u-0Tluk)U8dfleJLW92DW`xsQ+o>r1P++DJA8+c5 z@0%4_?|Z`O#lP5wrcAd+IK5(nwwsBMQybxm^VSD%l|8EwuK3~M0#v`vD)ZrjGW>3d z0<`(YTJ`bPPbx;U6HZefFVCl?DRrlg>f@C@TaNPPD{h6;o4dCn4L@WjR%rx|geBgx|YWI!}0- z(_fcz77X|PV18B6TpKPG3Rft2V7F+l`fCb=`}O`s*@;4fbB8-#Z>t)rZM{t4-@jk1 z+G<+DB;gw~4{Lk*oog{~IbJ&u(_O!tM~8#}f# zCtR`G7k)2Mx_!1t?uk`|-`k&cpMCISr?BvQ-|X$pOADm4!tXU*R*^HkoWhFd7XS2K zyQ}Bbu<(27pYO#@{c=|LJ#S(U-ug^)EBs#bE#-LCf@)Uyy@WXLmc_dG!tagjU~R?{ z(|zIht~}_>Q%6s;!tYJq1kNn&>sCCsZy$&4o#`8~cB?11E83BN+`rTczjq{Y2cCI# zs}+8);@o09pz&-go?FolyX~|+mwn;)wiNup{t$|1h2OipttGgV<5u{+w>uZ$chYaM z;<+_>56@`-BefNN@8GCr{L9Oitnhp0b`w5*@V*s(Z$_qE+_~~WEBxMtn9X)kj-poh zy(KL-*uDcQTH*H|Y_7vC;-z5a_ZDR0L(9HX%~)jP8arlrO)LD~n}1Z}9_P}lX55h= znjiGf#=`G)tc2g+#y+yb@0IGc)FvL>)(XG3?Cb*DB4ey(9M`H84_{Z9h2P6oAU@wK zpM=HV`zFmCyQs$Nsu}a{EX-fjE5+jVeRVc3e>AT=i`Uos@=aTOQ(6|Uk8e!2{iaT^ z!tb4%Gr^-tzTffjCGF8fOw|+mYQ?e7}?vvReMU7mM%r<>KHV*T;M3~n}EyC{|p#<*tj+e*Qq5h5Yk@$Y)Clx1N?UDF? zIcuk;=~4~O;+Yr<@a{Z%*r_$G*W&KzZr4xn-P8|iV1!vYH~Lr zuW-K~ZHga1^y!*o(Q*$OnfANrOS>LL%ROjx+1=4KHm20yVovXy8ojk#>~AYIE=EVc zT|f3Wm&<9^R_(Pu_P3Yg=v?o_m_(Xsv+SSOdzs1b{Vqr|* zof(zio7MQ!nE2fiE5A1@Qytp3AQ{a=4Zl%viP@jCl@WgL_XfF{DpgQ^Z~guew#CNj z%I{^olZBGLd(6~84evQJEqzw(x)I;+-5;yc%5Srf_9y|}HCvWeb$5dH>EEm+|1FiOWV~T?c$GITNk0X)hEwVu6K`Mpt>jz*um*pI~bd-*pTZdJG{iSIY(jYM8d=Y7iW{aonh@F%t(iSKv1 z$6J0+(@*)m65xnG&R&JY_j~o(!qH1}ex&@~kmu`$e@*z2@_R`KrnUo0^-+HByZ4gW z^^Yo&_m1BdwX(e<@d^^+TeGq;48m3WZM#3Fn34g_ugBv z#a8~Yz4Cj_9=vOxYfw!2y}J1>`L&zvR(`M9lE?ng-``h$@BArv1Cv@RzxPT~tSwAb zK>59y=Th0a?RF}^ckr2uc1-JL%I{6gaM%8DDwf}ihcyd1@Jtr*{mQj1Y}>rJS^2&0 z4a?ilE<>B4hQFUP8BaJ;NBO-JShH}meJ17iy5cweGG$}=y;QhQ4y{*R`Mn$;w6yUa zFHwFkA=W?68L>e5z35Z-?CAI@1Ab5HwyxC$r$^xQtmE|Pjq>%aFrLNt8QVqL4- z;{&kG+27E$y5RQ+{GJux@7F;c>3pNPR`|URdv}-?-IJ>C2Y$~KUVhhi{2tZJ)6qJ9 zkNVmM*718Zv$?Ut?}6DfgDb!9J7$lHQ&ua?9=JZLl0JhK-w*trc{$xY-|>59WxWBu zI@6otr%RR^M5l@NdIew2`C~(gcehZp6N5Xy65;k^G?b!p5ymugY9XA-!nJL)808*jpO&|>(p->;rGDonRmmFa_&wFs;P=dfuN$hS2ERw(_l)EBs9k}sx>gtb z9%W8h+B$xZ&TYQ#JARK^KI-f{evfk3N*L|(p5yoEqYo<>;rFKA zE=7G7_BM{+qkSi48prR6SFg_rcix?mbr~O5855QA@_u;^Ie(Yoqr&MIEz)^iPI!HZ zW<3)nuk-1FQAf}HqJ5lasP7HxfaCYX>(lK!4^W?JshOL{2qbdGmhUQ@O#Gbdjx)u z#P5%@hL{9g6yRVd%**+_gp@OuP)&p3Y1 zfZsDxufXpS_&pNeZ}uPW8t{8Y*4TpIGvN1(_c$2?+1R5TIY#R;`@Q$Bk+49 zzF*xN_Y62a65kIjp8?Bf#P_!p-zeiG| z!0#FGdn7dq{2rb$(~!jX%jbP$I<(A1;`{Yl)ZC8+X4fs70 z-|zlgMGTld65p?3g6ak=ABpdm^!j5D{2qz#cck?f9{4@2QHQ&2@xbqCjhdb;r2)T3 z;`>c|X@duTkHq&&lY4;&e$R;S*SW(55Bwg9?-z5gtp|QjYt*XhWj*kFTBCm2TEa_} zrZS1|2Y!#h?-|GM!R!9cIDU`zw|s=Tf%1C>{2qz#2Y%0_u9S|XMorIq#DL!;sZrqf z4EQ|~-*3<>3k>)@65sFFn2`qj9*OU_wSH{_evicWn+5$<=ll=4P8R%I4EQ%?Ex^CU zfPYig0{mMH_%~%O&W!$L5BN7_EpDFra5wn3u&@@*H?OJ+{!QCSyHt&y(J`O4x1^sM z4gO90@80%dH2635{Yrm!A-c!4M=`=$O#3-r=<4ocx^DM;m9(K-uf(o3b2?GEVz7k_ zwoo}1@PrJWkj3`{PiVmtviN@B2`zX+7T*s%p#@LK;`@Oo^uZId_-aqbevgIUJMg0M!0%bd?|I<&Sopnr zTNirZ_pI=H=`++J@O$bdF37*coPD;HdWqooEciVZFA@Bn1;5AQC4%2$@Ovy?BKSQ9 zzsKSwg5R^?_gK8dZU;MA@OxIgMDTkS{2tbbBCoy8CJTO##Y+UgXTk4T@e;xBS@3%- zULyEC8^1?O7B3O}o&~?h;w6ILv*7ovc!}Wm?1y+p$u#It@Ou{g9*dV)big1y|DZHG ze$Rs6v*IOwFl?y>zXw(xYk@mXv*7nw*8eosBal_Q#k!SAVO*rIR(5BwerzxUILXAJl~7JhH<(#8h-p89(wOH44}_teu{ zdvC6(zo3(PdYihwVZiUHr+22qDG&Uf`gq{?4ER0u@xbpH@O$dx4ZD5c1HY#}9{4>2 zeouY8_Wi#x;P=$Wn_FR*0l%j{Ue{I681Q@QF|Jp#X{KHj%4Tr%MI)W=KTrJe!5r#@bS8O;p%J@xUx z?-BSt_3^;(nN};4tB;qzTL%MvPkp?DtMU=}J@xUx?-BSt_3;u_OhWStKhbr#TXGFC z;P=$W1HWg$@2QUmevh{0&!avb_&ox@r|WRR?-}rW>f?dmBk+6bAPh zu4P8=ly)NY*@!;k_teJ& zzh}YksgDPKkHPP$j|YB_!SAV$2Y!#i@2QUmeviTL8OQH2_&wwJJqEvL9KXll_dLh% zG59^-@q6;SjMhN#dtvZMzTD%E*J5g}x)<&Ey>Q{wpJ^NXUU=`cCE5nR7e3wK6@7LD_`Pt;^}kgW zrW*WSxK!8At2llyJiW>MJ&xb=!SAV$SLE))aFUU%J|6fz2ES(=zi0iyvwY$ARt)Ls z+g~b?_;~g9UH8H7k@$EILs>2OJ@xT8xo5%esgIW^Q%MVckHp8D@!|j<{GR%F;P))} zJ@xS(&3Vm&-%}s2W3jnD_&xRU9weM)!SAV$2Y%0j-%}s2d$B1N{GR%F6R#ch!SAV$ zcQw~7AN-#Bc;NRe_&xRUzFoS?ZtGG=eY|9S5?Szj>f?dmv*7pC$D32_ss+ENKHkWJ z)`H(tAFuDQJQn<(`gl`Tl(6N8Zc-l){2n*@t-ktr_qLy~;P=$W8#1+u1;3|09{4>5 zzo$MP_&o-{r#{{r(KjvlJ@xUvS@NQ7c5Au%cmqFfXLnv%qCOt@JqEw0J|6fz2EV61 z-s9!nE%-h4@xbpf_&xRU!0$2mJ@xUHJV?Rmvi_{=a36m%#y+S%Lw!8(dlvkj`glEe zRb}vd>f?dmWAJ;r4j25ME%WUJ_3^;(G59_8@kV#6!{GPS$7^{$CvU%a&^Uh2_C52u z`gny_EwJGC)W=J-t_cs>^+4C*g5P8Cd%6x6{GN@<(oTIm@Oun?PuJms-{YuVUm3^m zG59@QhYNns&c*X<9KUD5@2QUmeviTL8OQJO{Dp&c9qy+SH(T&~>f?dmWAJ;%@p}w@ z&j`PlVpchxl%j@l{GNT`%QWiaf#0*>_teJ&zsK{=v@nj}+f1dF%b)Iew49 z?-|GMG59^>_&r{~YOUw^JzMS3CQtaih7GOlICzHV_&wgVbEfC`J>DMvKIHg4yKG!H z&+&UauV+Tj@q7GPr&LuOzsGCieIIuGo?VgR$B^Uq?Aio9Lyq5L@O!@F_Za-1@Ay4C zwp-=Oj^AVOd%olMY{9-a!;asx;P-sT?=kp2EBxLwZ4x}Kz1g0hwhL?ANY>%jOQ&n! zR6B1PRLFwsBk}jZ^;vLzB>o<_J`1jo#NPwg$Kd)%{5^1e46cvF-vigj;QC1XJ#c*t zuFp8GPuBXWE(X^Z2G^$=99$oR>r;(f{p6WFVEIC#$H(7o76XE zJqEvL9KUD5@2QXX-go`{cR#CyXLy$3b;a-a;P*)Qy+0=BwBYwhe7qme*0A9BNPN7# z*N6Jx_jDa@rI`zT@OwslJn(xK{2qyq_sZO|7W^KGk5_u(d<%Y$#K-&glO7hF9*JMq z;P@&3h3OxvMjmo@g9Xb+;_2P){Llx#XT-<*49~^@zh}h91HWg%?~(X;6L!t8g}yIJ z;^Wo3`<-mfo<*IF`@8Ub_j2rw4w|?kKZfHFEP#)ooPI z)vA%f?=kp2)yUxYEciXu$l&)F{2qyq2Tsp|(}R{$ z1kcS^jog(6S@3&Cd_3@b41SNq#{<7-!S9jycx4WjV(@z;K3-BY!QQ&@wh{2qhf zBk}RT?;#`UvHEylt)Fbc@2N)KaB{i@zh}h91HZ@M_egv^@Oun?PklV_dklV$#K%j$ zpgx1&Bk}RT?{WNAR((A1dklV0eZ04NF0kPDR3n4mv*7nsBZJ>#@O$dxf!|~Bd+OtX z-@`MfpI09b{2qhfGmhW0;P+G`gWt2@_f#W;-(&E5>f;?6`HTg>N5b!2X#KnezenQZ zCH`TY1;0n)<85e!%;K*Lk@$GW4(+z!_f#W;-?QNNR3n4mv*7nge7vpq;xYI=5+4uz z9)I!jef9Cc?=kp2_3_}j$r^d}*4$cJ_0#+t&9*+jw1oO~Y2UX+XBN%4PUdoM?X7xu zFJMh>Vdv?&HN5&>w~jUN?quz)Zr`oR)z{tHTkY@GP8_)njCS1%5A_eByXzfP*n{{2qhf(;5YSkHPO5$L}%tJ>&R2tVyh89KXk3 z^|%vq{2rchn$$XekHPO*$L}%tJ?r>A2ERw*~Amg z;LWG3Jag}FL-8D+XG$om3=WXN0jeJe4v@hCsvigrkih|}9|#VR!2ufa1Hl2>>D@i` z1Hl1WaDeIuf&*l5fW~ov3=UBJKyZKz4$z1n2=>o{{nPpe_K(5-8SwzY2Qv6T^$EcN zT5y2s2Z95%Uw?eda~vRp12m2U=TCg`^uX`gAJ3=p9lytE(-pGf%ip!0$1Yn`gzx1J}n5);H54D|rSqZ19rw5jgQ+4X7o*q~}&XcdW z5l;`y9{YV$gdMZTdn>%{J7$mHy!zM|?=JJHvfQ&=74YPEW>oC@DgC~Ki=zupbIDq& zDNc)lks~m2zGLJFjGX5fIRYbR93w|yYbcO}Yk6HSCk2KgrrOT`vsgFx2aV z`Fk957^+(EKo!Rvh6eQhrK+s+0&^JZbiJ+WJ}`%&KfYhAdT?sOB%vQ?9@h4IcdkW` z%Mq&|7d6`#4dzgF<^E%{qrn{N?-5<+HHrpvsB^ib?;WqYCQkw7Jx*lmNnrM@WA+S~ zJzu=LR@D}GVD@yK?3X2f3QZZox=t3%9)a1jj@hFNDL43z*&{G}zGL z$LyJTxhC#*%%1uA$4()~>=BqfJ^|N2?c9 zGvc!)z{z$FsWWnsw zuP^Sub=8Sr_6W?LuFnOtM_~4JeQvAEH%*C6X?1-rm_5^f>ICDMJp*P>*XmxI zmw}SkuBK~sKW=-{fZ5Zvx?uJUm_1#q3uceN?CDxvFna`MPuJ>(4`40wwmiC4w{6oN z=KYrz=vv+A0k4?kE0*Y5-CZfK88CagRyTRnYV%pOLL|&yn+8oyiml6atuB~717?pL zvuD8UkuZCAmQ68W_H?c8x5cZPZxgRK!t9NyRMLRi)3v(mKU-zM?CDzF9CbSyFnc7- zUeW}44VXP$s|#k&fY~Eq_R5}q!+_Z%VfK!WFKNK+kuZBh&LlEm_H?c8(c`x~FndOr zz4fnq2F#wW)m;{K!vnKN!t8xD;+O|!PuJ?En2^yPdn{fbm^}k#kHzZ)vuD8Uu|9Ke_H6@ZkHzZ)vqxa|SiC;`79-Dj z(BER*vmNx{cDctGxtWN{VwMFU61scdt=J(j;X#eW$f=q`=-W# z+0);HYF&(u0kfyS6J1NQb`O|6ZD*OYu?mbD~w12D8ZKA>K>F-CgzE~Iy zW-lyWADF#pFnh|4gV|#+d%9NlX2B)))10kzt!~-hYT5Uf_2dHhZRM4tcl|ziPUT4a z{*tubVt)nr%>DR1<<{Ub{(ye{I0O1zOI_XXFfjJ_m*EX|`~5$P{r%Q=i!2vQjKwbX} z4v@hCvT%S~VlLU&)@RW5zthi5uoH_;vcdt@Uq04)4c^i9zu*8F93VRm(1HWh^}jEV z9Ae)nGfUV1el;jDg9Fs{zhe&kX2AjK`rkemc3E(MEF56Dn;mSD28(t5Z*;+zEjU0c z9N_D1&slJQ>^MLR4v>Wd9G|kj1qZ0>f58D-aDcl0w`so^3l5Nl1ME_HoCOD{>wjxp zin8DUb^UL?llkrI*S6^TUvPjH9H6fMJy4^G1qZ0>e=7{lY`?s^UDyAD1GL}(b^Y)C zRS$jee!9-Lc$PDM^$vS=*X#MZAuxEl_7)7D0fWcl-CcMunE`{x!r)!b z@J$E|p02$GgJ;0tv3Pf2@bJ9V9xUD+9;IQx;IVjj-SWQXJ-{>SW$o?eq0>Atc)Io$ z44wgl$Ku_A!82g+SiHNksWy0E@T_=uVDJnWJQnW`44wgl$Ku_A!82g+SiHMB`7U{2 z@T_=uFD-fOfx)xl-GRX~VDMPHJ1}?#3?7Sj2L{i8!L#Dsfx$Ci@L0S%Fn9(G9*cMP zq}F}|29L$NE8DiP0fT47y90w~z~EWO;1L)+7Vi!Wo&kf$;@x$@Z}DL8tax`|@CXbZ zi+2YG&w# z2ss++-62PVkfWjA9da}XIU4HSAxFa?M?<|kw-%bcjdMmLJ44%ZT0K`4*%>-_edep9yOEutEKP|$wF!9{>fN2#zu0UT)k<|S z@-lqnWhjG(ybK?C8S34gT9k!0|9VWHp@+N-dX(*kK0^j~yPEc?(mh zcZci@Q#Qe5)wamaAY^B#ch|Y&C{wZSboK5gujp@(m!aMr@-k?_q&n)|z1s0xlOuU1 z_3n_DLCDKc?{4<#PYiM~)Vs@exurpNhI)6%&M?T%Q19;D8x0NeGSs`fHqLtX|6gU8>! z;~_6Yy}Qt{HXd>@NLai1kIH(;&QKq3a-x?*$j%_)@eaNmd6)TMzXaddSN#$jeag4tW^{c^T^6<$3;?L0*P>cgV{y$jeag z4tW^{c^T^6Auq!qFGIb%{weAipbLTkju-Ej2rdVhQwxG zkT7_A3l=MV{GjH_@t5mwuGw-vB)M`N9~l`hRM%X&AUi|-J-k=4HuSy0_g&_GE+a#? z@3J$r?J_d7zst_hHfm9Lg{wuMW4>49?`vzK%#6L}dP@-nnW^&XQjjJynG@Q{~bk(Z$i9`Z6Q@-mdcLtchOUWPJw$jji?GwUmZ zhrA3%UWPJw$je~lWhjG(ybKR{8S34o`2D*O@-nnWAuq!sFN4IpySXHtMP7z+c^MXY z8RYUZEb=n2zNIXm=)T1wFGG1VF=gOaAke5Ni@=Y95)kj{2vV1f8)`~%1hI)6C&&>)WFGIb% z73UxM$jeZcZ&K26KJqfi&ZP2GLb_UW8KdAzTux3kF3P#&-F)a-m> zZDr;0(mv^Kk(Z(M%KrYkMP7#Tc*x7({cDRWkB7Vr`{k)*%HwSvg*6*{3Mh|Pe@znp z|2ROE02e~3`Smt@_5M0upejZt@R3d8Mb%*PFk;ic#@5e@L^qtJ3f0_ zA9)!hJYJ}h^^uoBE-%9(F9Y)dc*tX#TI6LYkC$!*G(_?|%H6d%bi&R&m07vFf##Oo z8IxMMJLF}6gHNd3oqLA4>M3MW7-UkYhI%LVdFEkZJdjUekWZnU8}ca#`4q~zA)kVf zPobO}@+k=U6w0|FpMsE2p`07?DG2!#R=m4bIffAODXhzxGxTktT$^j~HP*koOUK^z|FsM&3s#x^+HnBkvoA%8egS-r7LtX|UFGCqQ3Un_Wf&adMP7#K@NGY31o%OK=s=z3e^WtbWBtLb{%aYx$`@-nQ;%b$*jxEpyh45Vhz+&*a{Pl;v%gZpAW}Wg~UWSPtvd4FM8T84!$ajEFL|z7^zV@as>uu|TA?p78 zVqezVA}@p5UfATjybPK$sJ`#=GU(gmQDK*tVH%yU?Yq1TvvF)n-{oacwcJ}mE-!=T zuPp1iybQDWwdG-#mq8mUBD)4U5qTNZu6`KLZ_~UCYG3}K=khYl%R5qq#JfXYhWWYe zo{-DSpf%|W8JCwqKa|X2TwaEmnIenl@-nFDg?dK3JLF~1{K>tH%gdmQpS+;Y*+X82 zDU$6?&*f#9*3i{1FN02%U0_^Z2L0{SIDO6@@-j^AveuLJw#dt%7xry1E-%A;wg&kl z(22;)FjMhNAMx&L?k+@kS}xJ&>^aX(b)vMfZYx-C%fWiv7H3MYo|^izf-)yeFt}~` zeY>Bow?%%})AhDb=WGixm)nYZD4gE8Drv*y>Ll_q7Nml1=!486Y~FT)})L+?At%Lq>h_0sjWm+RyYuX`nxuD3;A zMtJy+g8KUl@-o7iNA=K}e56?Z@Ujbev{oZ8BfPzCYz;?VMtG4ITiYimdJ@yPYi!L& zUPcV^GW2(3YS7!bybMlvHHUF|8TNz6KY1=MgX@1;-?+RC{w1ogad{a$xawig zN31748}c%2)Uf5A%gf+ywb^rd8NB7AN}kKhuwxTU@LXO7CqCQTb9ov3#S%Z{@-q0H zZ?cA6UWRSiKbzz`FT>{ha$(rzW!Q|Flld+$gFAm+-MYLC?%be^b$J=~Lfaa?%gf*o zD|faoFN2YnVP(DT$*WPEwPrVc&fc(6)|QyI(3kbLhw%LTg!?}9U0wzwFT=XL4Bqnk zbgkjY%dkJ)KH+&*qKuz#KSZ|BG3_B=YGJVb-@-i&) zGPH&xFN2Ynq0iYvUIrsCL!YyUybN3S{Q_FUk(a@>N>)3Mk(Z(V9`Z66c^Ueg zJ>+FrR|KICOE@-o!xLtchOUWR&o$jh+#R*X}x4|y4k zybSgFke9)I#)Z`DLtchOUWR&o$jh+E%TTWmc^MXY8S3>RFN2Ynph&QngOQh^ULW!@Eb=nc>qB0K&37QbdVR>tu*l0$uMc?{7I_)!^&v0AA}>R| zKICOslT z9n5~IQl;`wyQhk-1R6SPv(%f8=)BC!A`}|7{TOg$MF+jgvNMt*)FkXHhSlIyGNw z*o-TeBX7jw;ymaLkCz>9;+-#ChkqN9kBcm8>z&BahOga@&qLdF@^Yp|rbRxsS?+f6 zmTeir@r(7e)n4f2eXws7ckRE{|887cZ&td|yu1ArZ{V6HUV*7Y`J?8qn40nM9HAF_ zbE(6-O~?C1f*io7bCSTvo-w&M@1OUf$?X;Mk{=(+SDLpnmAY5=KEnLr*R;dDoqsg- zz8gP^o1YK+N#5?@4ZS{?)6E%Tm+b5I5A%mN54Pm>A1CHzN4t3+pRK{&`V{2!YdU!C zs}<%qTUY1tMPBlv=O^VPU$o$)3#xl#%^|z8a1TD&p_t@tS>$c;VT@Iu6>WI`xcIbu zeOm9OS+&?~%TGhT&E?%2Uxe@UtVRtc7xogQP0C%$x1=R?OL|L2Slj=VUUaZ~DeuL! zt?Y+C45b7Eih1?E>F%#-KbmZfXT7LbT6xX!ERhA7vwLqoU()O-ID&FaOzUN=n8ln; zHj;iBo7Q`->G7DgUyi2hyK{O~D&@ER$Bm#pwF-Hrz;gR|c7J*?SqZPmfd_W&oc6RS zNl9-MvJ6r@dX9ceP}I9UCmQ*zc=l_?d|tH@jkw?!S!rDJY~F8c+Hl$t@#&}KX=VJM z>fDRndef@hEkTjZO!);$ZL{yG-clVme>766EDw)qo~J|4StX1ZN0s7 zhS2+md)Ym&bn=@2(39?e$2K#rhgMfwQ=SG1_>bp1c_%K^rVc0a@uIP9z31u{r`bn6 zUca)5x9j~>GTVGa*QW`t&%i5?@!xplpy^FLxKMO4uk>?C z>By57T((PfufvapDCa7Cj=whbHchKRDGn9nUK2WaDJQq2^@Wpg(Y@Uyvr;{QlJErf ze?Az`K_6z*9`ELTK6Dgqov_zmv#x{p8a#nessY}v;xBm~KC62dTbQ(qt9upR>rG{f zd}xloR_q_f3ZIt^KCf3NoQ}Bz|M0C(a(Pz=W;2~GkDxn?3VZ86UTg+88bE0~m-O=8 z|C=fBeFwVLqLf$sSPnXRvOYa%R?NG(tqS$MRhshEf7VNpq#>D?vQw`r+2wkp;CjR7 zMZxFwRf;;)>1IC4bUdf`@cUx4`z1rID;DyWUPw+CdpDOZ?lSSz{RkjyN>O<;{-`Pp)JCW3fCa31vyvYZW)CY4iyG?m= z1WA2p-Tgx8U`^1-V(BDrMSpLK-zJx>9v(qbAG*|8Xun)JfTTWrmE*Fl^<_tr`Y?WH zMqaeI2}yl8_-Pq_u(T3MeTZBKR3O}*-|m0kNPRf4y)UOvx6w#_NSbLln|0NU)Q9U+ zM|0mX={%_qDSsNtRYuq{lg{>&q^K8)GF(kv_7 zU+crFLU&E_86C7f#Jiu1dKRyz_2C#E5OlZk4Nqu>cgy>ubBnihH8Cy^WH7*+B2iHJ`A3CH9F17(e&`|^+8!X+qW)N zEtHp~K8*Rg1Z^G~VyO>TTBf0>S6*VN4=IM9F=v~1VW|&Qm(DP`5)5Lg4?FO?@EiF? zvebtLw zyfD1%q?Psl6|9q$@y|Xn8()66q1K1?Gw;~yYddIt_yp@46LsjP_2Gk3RcyOghiiTK zIQOmawxOfB80y0mw>DPl!=%?Hn+aD2Axop1_v7KOO|$M@S?a@2`%=NnZ^lv|ez{tl zGCc3G)Q1&m>e5F`@^VCdh#jjPwP?q@{94Z+ZfQgD+QrxU(63BydaK_aBlY3^g2Sj^ z%VtLE!?uN^>5WzCJgE;8W{!lHmBdPYm{@)gt=l=nN_{A{z6YIzw<+~u(C~KDZRPJ) z?nkKyx1+~9ez#K3y=r}Ea@Ji|>cdNQhSA{0O|8_2@5YX%0gtNsQXlrt8Hx40iH+2U z5d#L&b2H}{sSo)MbfPc6`p!sw_^MkA+SNUo)`ykR&rz4^dGvnd#-F4=JAPU=IFWs5AgA3#zcmSxLtbG8~mQXjrAlslYb&S;YQuqsVjlOy9utq+rW z&NMSF4b=M3uijbHvTzrz57YLfp#iyH()utWUrCB87t;E$WMN%;a3_z}hsgU^WP5t~ zx^w~0NtgO?qErbwk;c>da5_(Fs#UU?)`t(5oiJVStR$%quhyPohU_1t^#SbA)8~EN z9B@8-d&Fpx`jEbTCEI`SaFY7ac+DF7^_%@j>Of3vAibRek@hhNUdzkkq>q&~Ro zljQnzpO=x(t9a_Zl;*RoM&=LOuMVTVH|iLfKfJVjH03#**pvA~<1!;D`_Xh(<`1hj z4WMzu7FwA!Ny*1EcL;CUM%&YPwRG+{-@uq%pdkY z(}xb8++}6{@My^}TF|VamHETcZKLV=jfcWAe~2nFk{*}KV5B~L)ny>%h(FiJ{9(q8 z?lf`6VI%Vgx!#`a_}$3$ma47RXZ2VnUCv>rel|kuL#HM4?au21v_6~~anY6=+)3-h zf?w0~ty3>(eaL?R&(MFTiq?l>Z`b2wWpZhKNPDOqfA#LKR_eo%%zZf9m7P}R52=$3 zVM@;75;{?PhtUtU{wgO&M1f(Pw6?aF&r>O=6%OsNm?a+Kw$#+9@_ zG|!ZYN4JCrj{0!s@@0EzVMnbG6MtW5-%(*PbKA4qM`(RWJa=L#+`n|JT#aR^ zv1?BhFzbhmVEN95KV4#)7a73vogG{2N7EwrYb@W{nj3P^th@DDzO$e9jHYkWlw$eL zKJ;FqR}Q6N`ObdZ;#JDf^R|_Hy1PeMxdz<5!^*XhphG*laN&0=bCpV8*QNJ1b>|PfDMkYQa*AK6v9})3*(t?}%E|JwFJykJHQCh%Z9`uW^o4c$f}k&~(-#DN;X8dn z&=;Q62j~lezA#Q-Jk9fkz98retq;%_1bw0P0s4ZVFSI^DUl8<#)(7Yd1AU?O!Od^A zKDhZFJAFaW7wq%}L0_=b7X*F5PG1=43wHX#Kwq%a7asHlJAL6pUub=B^Hr@6Zoa4W zp?=fj(a;wx^`UB|{091hoxU*87wq(ffxcj;F9`aAoxULG3wHW~pfA|z3z@I7(--0u z>zG4dF!Y6W`huY^tkV|^ec?NO!O$0;(-#bVVVu5T=nLcY1w&tu(-#bVK~7&V^aVM6 z!O$1v^o51KAg3=x|LXPW^qr1B^o51KAg3=F`huLkVCV~S`huY^$mt7)z96SB7{56h zr!Vju)G*`p1w&tWQXil%82Z9@`huY^tkV|^ePP}F;ptd8J*b}-^hGrE1v`CVp)d41 z3w>dsFZ4SLePN+5^g9cE!O$1_orS(&=nMVMLSHcSg??w9p4IEk=|TOxpf4EuLTeH9 z1w&tGErPya=nJhy&=(f^LTeH9g@wM*TGYDU6d(FRYZ3H?2Yta#Ux=R7>kajppf9vO zLthZ|h3E7IL0|YzUl8<#b^3y!FRarS1btzhz98recKU*#FWBh|g1%sI{*69m^zOYVT5cGw0`huV@e5Wr6`oeSig5>$na{t<#;ARZ;g??Vp7Z&jU(Kg}%`G0DWPhFSI^DUoiBA)(7YdhQ84H0DZyG7g`^nFBtm5I(@;=7kZDty@R1I z^xgq|!O$04AD}N7`aAI9IiL?n z1M~&Btr1!upf3#ch1Lh?3j=+j^#S^Vpf9vOV17%`7g`@2`>pi>`huV@v_3#z80ZVF z56~9|`ayrePN+5v_3#zF!Y7i2j~lizR>yreZkNdS|2cHcv_Pq+t3#b zeWCRM`huY^v_3#z;P;efS|6Y`och8s6PpPLC_cKPX=ofoW79H%Q}6*&==O}3x>Y1PG2zeh41tQLthxDFBtm5 zIDNs;7slxehQ3gL68b`}H*)$yJ}+|mf}t;r(-#bVVVu5T=nLcY1vlJyDCG17Ltj{@ zFR(^+u66o?p)ah{7jnI+o}JfH>$7@3&=&^!LhA$cg@L}%`T%`lpf9vOKwl8_h1Lh? z3xdAT`T%`F&=*=Cpf3pe!Z>|F&=}Q>kXa0Am|IN56~9`eWCRM`och8Xnlab zFwhrTAD}M`^o7<3ulU5xxPR$bVa_l0T>T=<`5AM5>Q6$; zSZEpbC!u8+T1NdzXc;`iy_EWs&@v1yLr%*uw2X0DM(#)IcLn-F?icYpr!lu$jnwn4 zSad*<;N0=L4PJM@cW9qrzAf(!=6=#%yK$Yr;-^vC2W>BCM{YCnyZ=|(gWfG~yL>&I zW&4hs)wW}0gSJ;=OspPsY^uJF_nP3nw=VbdmUW8lgSH>ETkUWBbguGeZ5-!+t9}0L z^VE0c{7l-tu~o>n&}!W?#ql^!S?WCn%`x z$4i>={KKiV-N^6AX)0dP?YQIlm+c^TQnvqB+JSE-{V|3djA7)tW6U`i^T5ZD{(+Aq z?ZDHJHpY{K@x(ZDFwT+N{42*6*$3l8!T4a@G`~sq6=W?*JIGp+c96#;ZG0{id@dMI z3dR%TOu;zg*#7D@X=IzO|G#XzvC_}Wjp09ic5ck|vv!|_w%vGYe>cwhx*JbzyK(-f zZT>ILMc?bj$3%>qw%vGYJ9wV0^l{@)(srMVw%vGY+l{ln_pglAe|=V4P&5DR^%qNJ+O7_0A6Fm#X`6p`Jb(7O`(EpqxbM5RT^-PN z@Qe{ThTu6Q(suPk$I#UQZM*uQ@5TB4k9EoQ(ewH%ZFg^CIRV_UtBwOAmYX$ZXDvSfw*fR?iz@@ z2I8)PxN9Kp8i>0F;;w0F;;wju7S8~;NN)-$ohbiIa03@wjt%i;hb$(8D$bmb??g$ z<8S#VKH=K$H97sj0?IkyU&eoHTh_z~dm-Dw`z+qCZEVkCyW0MEZPQf&pCkJTUYGp@ z{e_hawj=uqwlDt%`;BBg(wpE$)ZErekMT&ZvXau-R9?5TTrfFk;t}@v2}g4?cPiB zy4$9<-M+N#jzQZGV~w)>{; z9W||Qa?M;gKjX!yPFth2jen!?-`d9CqtH*=cwcF}U)$JTX>3>9a=l=G!RuRs*JVFJ zf7ws49obK?efc-oulzkY9(iAIoU*;(_+$4YdqiGX?CY8r=K5>fZ6`|lxb17(?N{6G zc(m<~Q`@p1Y**V)deoa2JC0-6oo~=z#zEU|e6;PxP21S7jHkA7JTlJOmiNgxy5pD6 zMca{|*Y(r~jhtbH)jg1pQCYu_^6cfjPkL)R{)i83@ZFSWDMz;5cT;oF+;>yk?z^dN z_ubUzExYfgw%vDA+wQxm?V!fWzT~)Mf6{g}D(J8GpxEPyy*EkQeK)m_`)+F6eK&*S z)EX=O-FH)8ml`1Zi+J5iJNPb3JNS-EJNWKPJE#fL4r+z8gBl`jcl<2vg*h8(jdicf zy;5HfYLvVl)Gleeann9-Jhkn{IXF(OvC`jtF8cak`Fy`gxZfOkFv*i^U_h%1bm`a= zPp*L_ZF^Ab_=SvI1I_-3F&$1PGty^4%93>d_HfO)Yc{(*?H;~D`%I~}$y`tUoc0M1 z%R|Up(LM!!ZA^Ke+}1wNR-11&%pIeB+NDoTz5JWn=SikY^wH96B>R%TOF!9{{9XFV z@yOq$pY)Oa$o^ul+YgQGFZQ~m@@z{vtu@T3kecX9zA9r5b2jeH_rG4D^XdgE|+Q*F#%f8$=Yad*PGR`df!gZ+Q z7<*p&d1)WX7n1$Op4V;pymUM6bJsq&4&`&#KDZ9$bJsq&4(0mMKDZ9$`q4hP4(0mM zK4V{9wpzwf&VAbQjB8{ZWnY&T&>9&>IUaXC2iuYBIoOU|&%yD?_aZnR`CbIaBi{?{ zvs~|T-AfYPj^-i*v_wYpvwVXL;{Ip~a!8tK~Q^=WV`oN7tXrNjnC8@cdgV zIrWk6ja(Pgc}9-4$f;-9POBSbpJv(5sPjUuqwALQM$Y$x))3({`cGQU85 zohQg=9@GTvOLdBzSI~Cj^R&-C+Pr0c`Fi?Z*GK1~I4=&)Yu=}y7CJDYQz1D9TG70G zc9JJICO4)jO`g%&GKsH&)tqW2kL6w%QIpUw4i&r_y7Sxr~gdypHdc zo}+v>-u=5q_=k21%zv-M&P!vMovp!ku>GyU_VMr5V88hL*5G*XzOBJ= zVtZSISf-;AG~o;|Tm+jXiYqu&-^*0%gB{~cQ&w;AatZF!%(U)r)g*{-x@^kjeT zbw79={cX@6`?0}xuzeeBAOCW&U;G{SqS)iX`#3mGY>$KEm%1_?7Y+XrT(StI+C{_cE({xS~QmgANENgp?E+LrT^{kh}O z{YhKKL-r?a87JAFw0jJhSh{n$H>2>Ga?f!U?Cl|CF&1SwScfIwO}D<7rG^LVu;g{O zzF5EGc&`cGi*0TRwpps-`=x3=ihZUl+M9#+gz5wRSI1YG8C@ zkdPj}6;JyFYwl#f|J|B9c|BNjC++gp%Fq?AtM~of^~Y~LnrU`vImaJPcGx;_M^4>- zr)5L7o_PI+zFxFp7V7fwnD(zey%4p{xHx!kRPbJGlY?yr>nmkn|K0jZc|BNPDQ%n! z2j}wA=~_|0yK{VF*^sC^?ijM4>JT;G9UG2;gJZz4ad2!WPSuJUdyeEg$ZnhXjLWb) z29kZbV^hDy9fOhAgSE8McITq=8H|sdqkMmP+sO`5O?Kqe?LUWO+w=Mjecc^{_IJmo z?eX=-Z_V%C>&9GPcb}2&*L`;C1-Z{ikJGJ})IRRB)^kaVYhbrK#|2A=Y|ZSBVG=&O z^6uE&XQcabpPjbdwWr7Lu1VddyM}eY?%LMlao4cE?yhZZyYGU&*L_EHo9-G8+H!4c z+g-!j-(B00F;;wju7S8~AnqE7y9VN}fw*fR?iz@@2I8)PxNG45<{CIwxg$-ww9(#KzQ9JdyYwGO z^>@5#n}1T@_V!28q}LAns}t|?dm}UIkN#&u8Ag2+D!F+Wl|7W*ob8vw^c!{F+Wu{Bf3S1%ivz-2T zHq&uch;QyG!ox1l2wy#5*k4hMKmXLT{l-S~=er8?rbpZCq3dP2ZIZnFpWIjEIsR|k zxm)eDU(PDat@q^NkM`HKX$nSjvDXT7|3pdr(Yp-SdAAs^U7OhKE$Q*4@d>s;lTr;d0V%KY^LFK z?1xNdY^lWNt+{=uWUmRP$dJDByVcX*l_Jmg|Mhc;Jg>jfuCq2J&AE|>=OjzZk?oC} zO45Q-srdTGzuM}b)~7pnuh~kij@r+1ze)>`Tl{;{W%g+50d#0(ADg7b%l6f*BdJZJ zD}I)&U-%0jj;7hUI2zt=yEf8=rgyZ77m z!BtZ)M=`!wFe^v4)1~{_O#iVE*J=0+zk4eoz4vB*E>$DLKa5G_`21OaoXdav`(Wh0 zYGj;eqRLg|J3l?kp-+;UZh1X^P^2hNJ)hoRzt!-AX~p=!`seM!(^dIU?!sJZNpIb;8m`}(u<{VT60yj+`2wtM#3 zNvG|l!$o+}ptSsIlXyI^bW(l`^|IpabSyc#E$T(_jg7f@^MtN;!B1#{W?wse#LnB_f#}K(TleZRo3ML-s`m0AyQEKRyLQ$H z8oBmoKWo?XK6nDkIPArhbE}6|MxNvU>*pfpHU8R)Rm&F4luYCQv7MM(d3WD7{6f!S z9NE4yvV)nQw`vvZiaaFVzw(f{?oq6wF()^dYrkUH?6CA zcfq=U_kMAXe#H4cZAae6(GCUo^vE%ZZ2wt*;Z*XSYPQzaq_xtn_R@xRUwHG^MeY~p zXd}kfMvN^-j4eluEk}$k2Xi5eEk}$k2V?u6+?Sl=_-pwKE?bZRS?7PPjnBQHWM||1 z$iep!-%}30r}+MI@cqU2nuG5(zV94--%$rRr~{}EHmDD%8#bsLs3(3jf#=Xf#+<%|8aZj`n z_e2|UPxK=0i6-KnXd>>3Pw&^bCsM>ck%D{TpB>x3d%u`7aK!xTX*=>hj=6*l<{p1G zK7ZC9=OyzE^Iuu4$o*nY#SwEkj+o1F#9WRe=5ib{m*a@J97oLMIGD@*C-?Pd=lfS) z$NZmz`9E|42f6@yfdjn&9l?Q)fWAPMO{~6v?%+UoK#y>sN1#(U&?(R_9OxJ58XM>u z=p7sA9q1q%=pg7LFVIKOO(xJy&>$wzQ_v=&uT_Uep5y=P=Ms5df29pA%n^G3X&V}x zBQ!WiXmA^$!EJ;Fw-Flr>HQiS+(c+_6KL>1JGOuKe&JDYgrD=Y4Nv3geH`8e!=F*F zvx_@`X4?1J6BsjJ(s`I9=3cmS4f%P z-~4rYKeFBEgQ46!LlJwsX=dBxgP#2T|6%XF!=x;lwQ)d^ARsyCoCV3S(8Y-+uDa{)jt|>4CvUg=v-ISR;sZ%dcF&%zmH0A$Q4Ffp7Y#md#fxh3k=<^SrTf4juIPazFo>-LHOQ1m7D8 zWyD@$`?bnxh{L3Xa}vt&+Gojfyt>0L3ue3gidtR{`_gYTm|LTBYcRJ)=hk3ujn1vX z+!~!*!rYS1Eg{}QI=6(mC7oNs+|s%13p!TSe`6xDJBRr8x&{erkaTSl)~1Vx|J&AJ z?g~AtZ)td0^?#QQIoIQ#H1w|OBlh0%ZyUeP?cd__@&2!SjX{3IgtG2&2Kf<#{D|A* zBFK+KkRNe-TpIEtX~>VbJEL$zfmWBN6f=2Kf=^n-TIOg#3u} z%?SAsLVm>gW`z6*AwS}LGeUlZG?qfhkC6Iig!~90KjM5dLVkqKWnb~WHYC$Hv`{8>>KQ!f$t%9Z+)Le z&!0qIgPe%b7;FSN5jo@dcxL#GILnYfE8z@6{tT6nJ^3PXPVI>wf1vSu~EDQj8tp0dU@A1Z5K^Q2-E zG=D0#Li4I(Lp0wiwng)>VskV{=f>iR&tI| z{FR(96qhCE4#jK9c|>tsa!yfvmz-Y|_a)~V#e>OtM{#0u4pRJ>oR1WXCFdsi46#^B z_>G9865_5BN5xry5ORlb zNkqmu*I^y~Sw1E!{?MPV9sbatuO0r-pRXPM(4Vgz{?MPV9sbatuO0r-pRXPMP|nx! z#+KRrBL3j8tUgu~li?S|_HM)_V%XGp^AoQRZ&jrL}#ODdQ4Y8P{wwSctLoWdo2Sub^XEnMbo9J#=J?q2A~hRNqN8{8G3#IbBjwbW6Y1FLf#!y~ zM^i4jdm_C%>L%0bihU_Ns!ybom)vKDZM{3C+7sjHyV_5gE^GR>xMaZ?$}?xRIZ(7& z+DliCq`&T8XS(JbkoNwD5wvgWOXkfF?n;|pbp$|fA`ylcNdJB zB}3`S2lkj1snYYECwQCng)0*|C z*R%g>UY@lwdeyk==(~5b(Hm`dNAK#v4)-R?SaEj@?$+WmdY*$&OGrZOiA z&;z3?+1;HwQo9ocY1;$U?DoMOsM4`QRAW^wTVY~*8uDuiI{wv_cKDzxY45Od^meK1 z?YP31(zs5Q>4l27*;2Eb(fI6DXx*qg?A!M=rHwCDp%!o4WqVI;LNurM*D#^}g&;+v53)so9n~^vLUr?7ucvr!VfTN7vu?q8+fZ0!`jukN$Pu%l5U0%Tw`4 zeJY;%s(oNwIa)irK7Dd3&2H;ambP8jfbP8LUE8pFG3tF+Ln?g59y{)bi>P~+Ms(B6 zBeu&kIcX$nD~c35Zr_@kL*#AGoUqM%Um$J9)%?Y-YMNc19sEi*F1hcNaqq0VGdDjq z;D~X3o%dxy9-U>cabvi?bYVXH<`>3|tx~TdeCLCo8#iY2ucCZ;_fL)cmc^6G^2g1$ z8~2T`HLuFE`lcE8?Ok@%;r{QuVBDN^{-Z8;+_1v9xhhhr9*{O&d*zg=n@o?m{Nalh#U zceUkRlO`GWTlfCvYJPFW^~UMIh7(=+_pBX_(~aMj_2#_~HZx9V9>2Q}mzvtxI9)o~ zuP+ZD)4(_#%iFjg9~f27INkgC`s=yr!7|3_WP`dla)GURjMLRl58cAY>-`aNIy|7! zF#dS5OHepMiRGzZ)<_z-Y z*XAyo_rvv(iBF``gtk9NKK-p##O|F+S8N+;@|E~7h0-R_1DCHh6Tfemwz}&`s#WA` zV`of^t~)S@I<3t?zh7`FTI`)}8P>>0JE~D?y$5X3S`F#P-SueK#~bXHMdfM8u7=d8 z(zkZQ^?4}gGY#n3LAki}Pshwlt?E$rXgRL&$5vD5LvN{TsRGn#d>dZY za+(?Y{3&zOik^IU<)!9iwRg-XC2!nRGjf~3 zH~wyqPU^*Z-;S8-WeaeHu5Ecr<;mvp?iHAJH{#1~dd58cLv3#HRCz9P)0<}FQ&-;i&2URYRWj+;{fMmoKF1dFped@+)?E{_-@bRCT`LikbG(RSl?rr;_~8oHjQ5 zc~{c*{5kpjd(T9t-_?!kZvEQ6{>_x=_E!c`@6T4-8`q_zz1?gi{rSu&`>$(uq|8_~ zfqtv`OSB=kiroFhR0@C7y2oBfdHMcSF0g%21ag{}(I)DDcj!aZ>jU&8>h%Qr6ZQH7 zy|P}fpl{ae8}!h6J%oN*ub-84;Y`s21&#l*U=)d*)k9A@Fy1;s|e!XBFS-+03 zzN}wgSa;U1JFG|R*CW=c_3ISt*ZTE~b#48+#(KAYy~7T$w*#;b?Ck^W279{!d%_Q> zJ%OEJZ)aeC*xMi2CH8g+_KLl|f*oUT$6(*s+c(%f_I3~Uki9*Gon&t(VL#d1PuNxV zb`|!Py}gAUW^adKpV`}I*lqT98+!qJdyc(;y`9Hiz~25l+3yRkjo&Zavwk0O@AUhN z>&x#uZVY}ua%1!RlpC|(zudR@ea(HN-|yVF`+d;OiQgaHT={*|&7t2<-Q47@5hoUVGm#p$s3XPj<(Kga33_kY}4@P3h7Bi>(fYsdRhZcTar%B?l;ceyp_{V}&T zy`SdRtoPsCTK0aOTjSo}b8FxGfzBp)|Ipcr8HWc(20V~T&W3ndZ3|()i0VE<*hiwe zzYzA9sO~$2eJ85+hhTr4?Cg)oYJcQCYG{t*00tMu4p#dU!Fhz${zPz2VYM?6oNHL^PXy;0R=X6zxrWvLL~ssbwLcM@k67(b3eHWe zb|wYqELQuIf^!zDT}r_@i`D*Y#JP;s{-oi&#%h1kaE@cOGf|xTSnW?5&V8(QDGld7 zR{ImhIg!==L~(v(wLejuD_QMK6z5P@`xC`El+`XpaSmm*KT+5pCp-Hiva>(1QSxjk zJ74Z-(Z12Io2Ih!%blNdLxhI( zW9Q2?EmhupebLqId^yfG+zeP4Vdu-;IQ3aGVPQ>nzTC#v@0r>2in8Ob0vnwa%AYFmnLyn^M_2 zU#`MU!zudv;i&WF?)vgpdiAPhQRmC;Uow?G*qR!>VCB}z&IgAt9(8{B6r9Cd%}I?q zKYYXCTdCxCOQX&Y?>v1tJzDZ`)cN5J-WWh8TFE*;JpZZA^g@F^&OW$vlh_C6hp)Q4 z7Jc4(oppZrT_cOoKT&=_~uP^TVeWC>%L5cPKkQeDBw1HWpbhmYpBo zu3f39nK9Yvz<>EWy1fJYl<0}uQ?O5oKDfOG`;_Pj^vcC0M6aN4E-oSZ2K{t#3DHmJ zt&2a1-a*5l!ezC4y{6W?=)~}08$oj>)cJT^X*RTUFE+KXR z_QAy^#6G~DxVVJa6WAFSe-JwZd*b2}VozXaT)aZ;jQg$O7l~bhy>f90u~)EfE-oSV z4R+7PAH?p#zPY%B*f-cc7q1Yz2RrHF5@IJ|KV4ix>?iE4i%W>Tg&lVB2eHGjw=OOr z_7-;7#Vf=P!*08{gxGD^a~GEodk*{W;u2#2oeaNJ_5~NC@b=%y@JnT1aL>Yzm3_p$ z6aKC2FK!I*du2azV}qY8`;;34{AAgW+}PkJ%Rc441%9>cYwjE2Z_9q?<^+DY?2m4) z;J3@Z>E;A}yX=o{uHd)JzUk%`e!lFp;repF5zYm&U%TH9=Lp%ybmZxc!$>FPf5<%K%2Oy> z6C4+}gX1EUpIz{9i&~h26!7NX_+X*5_BJE4CcnpgjI+i1;7 zTWNVS%F^#VuKm|RyZ6Do)bMm!?$;n6XPvd)44iohZ&+83t8d6<_7{rqrZP47kIt_| zTjnr4>|{ncllqGIzAy&s$AGa}KQ@e+{h0AB?7s!y$o?Dg?d-oD<77W4p^Wc3XMOFy zVFItdr>TAT!YX!q%FVptfk*A0CHL4ze(BD6kGy05)oz0wT#$JCA7|_%HNUperWJT! zlfs`Hq^0D#uzA=PYULf zg88IiJ}H<_6U?Ux=F_J8E#x z#e1W7E{|}(MK!qkwiD4yZjJEl@fp{9BJIal9><*y_qNm5x3Zy}rSuS9n6kufpEK7^ zE76(D*ZRV4IK0_Dx3n?uTAiIuwPQ9iu^89oEl$qO{Z{A;(cMt7i8m(*2UC&hId80d-eLI@- z-eT1<$ca4r$WK!#>#Lh0mkwAF3FXnapYEE{JJVKeh^AF3KAE@o@Wk=YI5bqo_UHVwuf)VQaeW%rSf2l8^1?$7<4tt@81V)IV+gmvhm9Ps=m! zxrpDoce|NJ7jtiO7ep{g=6f#@OuhdfHAc zd(rICTW#GzYwe%!H>RVHWamvk9<`fG=ceD6mgl`|FXDzDuP|-rHQ@6Xmv`$u;@5j9 zXGUM~)nY?F_d-0`8^d#n!s_(&)pHT=dGJ^ z-;XNuz`5^5Z~r*LAH7|JKmA~QWdC?@9`>%uT}livA60J7r>0irSFd4{_e?!r+@Wj+ zIcyU?8@@B_D;z^Ows6ehw~XoXp?U9Q9nSScDK7ux4pX2(UC#Y}DZci>_sy|kb$RW1 zrMW<@_sr0xbvaAZjB+B+KJmgR`gp};^L@zyCY0|fIfYs-J>UG?;Yg(VAF1?eiApKU z_Z3J zg|n;jb7up0UN<6AbBf`=uB*vMsHWXsErsW{tIqAec*C0Z_4xKx zWq5nH!ffs=#g`SokZ(>Qp0NImU3qAK20ahQkQsf2b5e2SG~ud2xV zsu$qj3oJ67<~QVZGb?0}Go!C~Ya!IP3hO>M)$gs%9TDHnK6a;h@5wsMtxILl!+34t z*@1AaHP7*mS()`>{`lU~{NS1`X5@Lup$;#@iL?pls@d(&m;v=0agY2J`QyV+njYMU zyUeP{;l6pc?dzRr$%BjiZm)X#OB>1`&8^HgRxQZmUj}CAr)=Eymr7i0aY63#(MFs9 z4%|V#xh%Y%p7yrU&3W7#Rrx#HBieX|;jzPN^1)eqB0sN=aOC+KeAkHSX2^jiynk9{ z{^Hm!^Lwv4{CeI}{Mqq*^yO7$dGXx58RW1{_-y#ju&;0o;n>14hu_k7P%)bGWeLvu zOfG(6Yf;M5uq5AjI2YeuvnUn1uO#0FY)65aMd;lSdO|H?GFrSW6YXDd&S zZtip|6)$szeX~P7yLR$TRO7aJcG4d+Y?Vj5Qmp|W+RnAo?9j?7v}|xzJ~iQc`vPha zdzhlUdB6o6%9-77_>GCkp^haYr#)7k`aF6OuN;xj2)^^zC!#-~bi)fL6K&4v=ZdrB^j z*KcO@70$^QS;x@0{3Fe^FLyIv?Vd(|o}3lQy5+V=*7v4To5@?FCvRRG{o&gYRJqaJ z_V>2K?VeA%(v$CeU`H$+0hrZ{i>I49@%y$LU=KJ`-lzY zuub@E_|CAea17zt!ZC;6QX?zTqs9KTU0Z!^m!ukMbL>ysGW$37{!{@6ufmBRr+CZq*2?sky=YrseHDw(KTK2Mtd}xL=%Tsu=iY_-|o6> zINdpShRw5fqAggy4=wxXbzAka7wn=dT2bF@zt~4B@6I4+cE8~_CL)JAmWZ6^WP2*R z=o>rl_IK<{ld8~+M+@+_CfT@K^FyZYaQD-YdpZ z<3WSWtk&(#md2^{!9^n?Z++M`k|kv-Rey7Dw0+gLqJxJIr=7>{x6AIEVE4@ILVteq zu`SbRlim4i9jbHsLSB2*9~tD#=quh@2=%Sjg_lv)!@t>i3%|7Mw-VjB{j}{;a(@Or zjMpYy`=K1JwVi8HDF07c`1JDc?53X0sn5=A{BzEOHjy^rT)j}QHobXCUcP4TX}e%Z zO{zO2A2;3jrw#Ybvu*#)u+MF`*|oVr?~)wK%NowK4R30~&GJ;{qL=*`ojy6jV<*+% z_EqXfPCRRP`|UNkY2Hrey`9Z@Anu$0vf&0Zpw1=yY2R`@aYq(v{B31kG^G&#wX!13 zzqSx!pXc#MoiC-gzdB|6x7}y={n~?O&fIRB*LpF79JUFc4c{5|6^J;Ws8ChdP#sT)zK})UDhzc5{1Sa;;paQ;n%FR zFK_8Z^)7zX9=mLfO{7gYSM7IPO%Lw=(vH7&tIal~BYpGwK6}lPZ8qFD&$j)SuMM@! zUTww~l&i|2ysO@#TR(SXgb+BJEW*k%() z()0W7u& zU#~HA+0k3<2M4>@9c9K)_rfFW&X2ohkP~^f&Tm`H(BCemdk2-FQ2uCs4(htA0^QB| zX>+tXT|Dg~%G)Cgy*Tj-`uMXGW^m)r%wvW7()~AXGS?ShVQ&3#IDK_;x~X;kI5YF{ zN%YI{QfAPk3r%-UrP6bAMDD-uM9Nc_PNRn}S{to<`TS^yYUAmPg`Mr!ceJpfoZ0<` z-R2Lj+h-?Ik%l#Fk?zIpzn&gKS(h)e57wDuBS%|P=N?DxlDfNW{<7uhhlxeF z;M(lmVcHkwheoyexf~_AZtd&L$Y#h7K2(*L)v_CRzGwL8vYHw6JRC!2^cBvDZB>M3 zoL`ELFV0Qf|0JqC{IuD*b)U)hSAY6E_e*B?htHXVsE2I0x4mg-nwX=nq*8}Uc_YtF zJe{)R+sSmYXiod_sGp+sJKaoIwtdvzfAc*ylry8RcxxflvB?*YqpYdD?Hkv$vK?xV zrPCb;+ZiP~WYEKSZQ|L1aIM|Lqp8}!(YD9iJ?wAKj-olmr`Rhd53q@}3FqhCUPGzE zoX73ZzW3Qu{coZ>cF(hQ+dp8#ee-PFSE#iv?IiF>O`fUAp?q)8e5UU&DLgh?4L-T{ zU#6RB%s*tQ#8cXQgF3XDeAgSrIq!rbRPaDa?)zYF&U&yR&B>C3KS}-3Ua;(H`mFX| zTl=Z4_VV)v)8h|3Z=26}%-W%2X&LH0PG-N#UN~_ot^8$Iw7_*74dt*+_-y#ju&;0o z;n>14hu^aOrD>FX$79j+UYH)uzhD|2yZWhUr}Ym+H$OOyroI1cwEe3OMZcXmjaGMD z9Q~E&WRMei_W2);`C)tux^6`^3gscWR+$N%8c?Hw<*9VOKTO)~Rq5#?g{e@xa5J$#}bhz|DH;FuBe^%Ly?kc zb5Ij_LFGnv$oUoRj&}#qE47x}nI#^#N4j1?qe}i{>x}%&?%rF9cJ(R7=MBukb#m`A zkvr&IdA99!&Kc{SLs{1yW4*JkcgA{WUGI$b&br)q;lw^;91*Sp1fx4Paf*1Og9 z9>se1a~r{W_iJC|uub@E_|CAea17zt!ZC;6qWTblZH%bRjKF3_)RsnIOC$QbL||hx z$ca3w>yfY@Q7EeoC+tV0wwUq=RylM5k8O3=sP0yPVoHrxt{~Me)O(=(L!e_&GhJA%&2*(zVIs6tqj~JZI zjh@*J&g@3d@&;#lqvryHGkyj+k!SThNQj3}C~FLX5Dy`ZEfC@%q%j9VJcKkBL5PQt z#wZB!5YpHMAs%8hreP2dF&gVIh=&+G2N}deGRT?TZ}^Rg$f1rUBI|j|;H+x&3~O+P zjp*4ninDE+o_Q_KyjIV`7H46rXJm^rvemOQsSj~6fuH$Z2^Bqy-JEEHJXn}l33(a>#knf0SzQZ8jVKn}1knhMK zhi$@V!*_;#g<}ZE7LGam7LA7+CeD+!-MsN19V3SdF402T_kv8F6Y0T3g=4mt* zY7h%G;l6pc?G^LDz}whRR@{pP-o`54#sY6+6>npKx3P-1i2`pERlH3Ec$ zM)5WVcpIa58w0$JQT&4e-X?<_wh5mN-x>B5jv*XdIOgzM6pul`CK<&n8DN%-VwnuE zOh$1L1{kLdaw5+v9)^Giqfk~16#)-Mimf8x!ALPz1Uwii7K?xfBgJSD@L;6aEdm~l z6w^h(gOOsr2zW43><0l4Wz;2P|iw!VcCX_RyuXt-A)G@^r5imtYu|@=}Q3gGX*Cw7F2-lioq6{!m zMsZLESSgc8n{a+K=WdX5H=2t#$igqNK|O*AWySCl>Jdn>{e*f1Qp`U+ zy}2xDEdZe&fwV?|P>(=bJ3y#MAgw7N)FY7A8W8FcNO8!7dV~yeX7?L@VV~NO$ zXC`39NipOE47pKkxdFD^DCXP%b8Zxi9sw3Tq8RlkFzQjou3KQ&Gw69ZhRo?!2FZe0uX8eNNWTLH3Foy1BBWEQoJIerXYiy8GXfD3!%O#rk#Lk zC&juGu))bRZz~qzS@CjIbN~BFVSBm*0U_OmvK?zt;6YiU5+g@wF zEb0wyC~MuHMZIBE>kZRTZlP(y08wv|AqaE6d_i4eF%NO=he93vUzM4nYX3IjeC6UxeAV!+2@l-mScjhl^f zo)Gw0jB=q6_*h6eQV4u3q}(Y4J{D3=6#^d%VxYpuLf~T|#}DCI%cPM!8K0+$KgjPY9eRq+BQjE)-IZ6aq&IDR&BiJB74fo4~1(LC%!E()o7& zwiZHtQ%(;8rw1w52Z8G&gC53f6VDEWYfU*x2%IFOJR}6J5=x{^I9FQpPN;b&t%WDl z!c(|!o^5;OjEaE&EfUJgTV=pMX29j;__7T6#|${W9AB0J|Cj;ym*dMa;2$&K1ao{@ z1pYAsSD53=BJht9IK&)Z7J+|^z%AzZvIzWRq#RiU-n{CofHv&y68=hJa&iHtEgJ~uy~j?c}{r{i<; z^Xd59{Cqk-H$R__&&|)L<8$-#>G<6Id`7_s=;t#gXLi5wzW2ZRKlwQc^(~&P{9^>aJ_aK3L5L}|dNl4%%B;_h3a1|QmFf`yWG|Fvgz-?&GabGbVP>w+vgK`hb z*p!n{#;jb0@-50?DBq~uhVt#o7bJ5M%Hf>3qD(H4DjV*V}p+u8*}(A@GUL)>tsKL&uPJ5Cq5^9 zQ49V$@kOz(S@741j~dE}JPV(S!C&Wno0tqAn89D?{dop|o%iP%{B_=+XYki~f1bf# z=lyvGf1UT|8T@tLpSR$z^ZvXAf1UT|V{&Hq8}EDL{Xd?*#rr?}0So>*@wMQCMZsSu zJ{Wv61O7Vk&ET^c@YjjY249ZAUnjmCd^`ewo%ne0{RsSZ;`^P;zQTEc56s}N6CW79 zF@wKOd}H{`4E{Rtnc+(_`0K=%hL6qQuM-~|zPAN`o%r5Z?~boheDYAvjJ`ts4`uj` zF&%?XXu)46J|TQX3;sIs6%%O#KQ^}ZLpfY)@M$gh>%^ypA8Wy1C%$eXZNm9c&QGzK z%Izt(6gJcG{ig5H!Q3X&9x)RFf1Qul#bm_I2>f+EUPs`s^YJm(M6xQYdToy15(Igw`(TVwFo`FL_n zMhuq0U+3e=4E{PFPiFAf`FJvezs|>#8T@rVp3LB{^YLT`f1QsfGx+O#JlTT3&c~Bu za%T4%?|b9@Kc2qD`#<7Q7W{P*>q89Cg1=5;fQSu7!Cxn_LBtFV`0FHQh*+Wlf1Sh< z5o09q*GY^Ku}1=box~o`WnbYuAO_3euag)oVzUhXI*H99X3OBOlb9`HxeWd~iRB{3 z%iyn*7%yVK4E{Qa{o=f7!Cxma;ZV+uzC!&EWyCFGI)<2}1%I8yBoV8$;IETdWg=}5 zM~$uhP!87`VyYJWbrMrW9MyuqPGYTzv$k`G2 z>wLaACL?c4;IH%fVgi4i&lel;*ZF+00e_v(7e~Nf=kvu;@Ynf#u?2sf&lg+p*ZF)g zgTKz_i(@i!%CR=cHOHPs4m$Qum;|1oI8WR zPIB(Z#WVQpBo~jo9)rJ5a`d5`$g{}jGWhE}o*^a!1Hj;~^LPdZf1SrOF!<{{o`Jz% z=kW{-{yL9mVDQ&@JOhKj&f^&v{B<7Bz~Ha*c!rpq+5N`*-gy6yr*HB8k9;VDzfN+^ z$U$51*GUc}8VXB`E9o#d>M%QoPzlUz1(+y?x0lH*41o4{Wux$kq?S2z#A z05JIL1OotU0E53yumQjfF!<{PGXN|BgTGF&1i%jaY! z%9+tusQ;miTzO2#kP~O{*GWzsxpD@7o#e_BX@fj|Z0(0~xYm%g@Ye|z6u2@5f1O}NLphOW zfhT0}*Lgf`Oa=y(!C&X`v<&__kEdnu*LgfGgTKz>X&L-=9#6~Quk(0X27jH$(=zz$ zJf4=pU+3|(F*&pQjrYCr{vS`@;{6|ZJO+QAU>$*hWboGs1`^mv3;sI6MglWw!Cxns zNnk0{z+Wd=N?x{yM>?0<+5CuM^BF zu&fOJI>E96jbj|EE9vjPOwbj z9(}g$QL|vcU+3#(VlwJh4EXDOy-WoBb-rFE3jR7@FJr-9=j&xG`0ISV41>SU*UK>Y z>wLWogTKz#%P{!se7#IeMomqu4Qg#-&!Pq=_D0j)E1%Uh{0bcHAkpLV(`~VEfVS)82oioqZG=CJd4^E27jHe=ZeXwfnxC2`Fbt} zf1R)AV({1bdM*Zkov-I&@YnfzE(U*{ujgX$*ZF!b27jHe=VI{J`FgIHoZ0=x``&o} zkEd_({*QVP27jH@+Mou9!CxmeIH=8G@YhLg4r+ER`0J!*2emvF{B=^xgBqVS@YhL= z4{Co5`0J$h=Uny`&I4+o82oio1BKcs27jH@Mxkbk!CxmeQ>dk4@YhK#6>6*){B=@e zh1x3yf1T7`0q@P=ualarP|l3LLj4bA)D6XS3^hRv{yM1%Lah*kzfNj}5@~}vrr6pK z<#4T`risB{CpAr|V`A{vNv%^NZNm8hW}d-cCzyF)=^6ZWf~61l=(BB)npp$>I$y6H zlTkMv0e_vZ*N%d}&ev;O@YnfzZ43T7U$4#Juk-cV4E{P_ug&1E^Yz*c{yJZ;&ET)| z_1ZBRHQli`sP&FLiyH9QJ5d`R>kBpGu`!^QJT^Aen8(H(ehcb(8T@rp+m4!d27jH@ zyrUML!Cxn}@TjY0@YhL=d?+XKEb6H(`0G5MKuksrK7+r`^9eBc>pY(TgTK!62{8EU zJf8rAzs~asF!<{{p8$iu&hrT{`0G5M0E55I^9jV{%&VrZqxQT7`0J$h{9N`G z&I4-j8T@rpgOA#L27jH@=A&kx!Cxme`>5q-@YhK#KWh9L{B=^}kJ^6*f1T9+qu!9g zUniUZp`00gh58@Ls8x^Y7;4fP{B=^3j#_mFf1T8-C(;IW^s%)c%Hdi=O+ACZPHO5= zN6+A|lUn;k+Jy6inoS0Ooz!fimXpC>C$*g69(}g$!P$}m{yNVW6qCW*W5HkN`GPF? z>pWkO1%I9A3u5rsdA=Y9f1T$GV(`~_z90sFo#zW;@Yi|1AO?S(=L?F-;1r6r0oPFM zS#S`=-U)7^SYO~Qij4tWMzOJh<0v-f@LRwq!{DzIZY6LoG5G6*a|v8b4E{RdVgj!V zgTGEVnnF2|XTj%V!C&Y3tYR`ape*?7JfD>Xf1T&EV(`~_J}U-)o#(S+@Yi`hD+Yg^ z=d)t)*LglG27jIBvtsbqc^;dXoZ0=x``&o}kEd_({trGJ27jG!4S|D*!CxmFMBpZ3 z@Ye}95jcw&{B^=v1TG^6f1Pj{f#b-6zfL%gz4)*!CxmFP~e7Q z@Ye}96gZ<8{B^<^1uiKDf1Pkifn$onUnd+>;ICuw*9rF&_%0ayb;3y%%9+tusQ;l1 z-lUk0ffI?rUniVM;7Vff*9lirB5lCq6kGeD9IiERIx+a`gwqK;P7MA!;d)A>O*lW` z3}Nus31T;a!X*;!(P!IU=iKvEy7exyt~<|H>DIgFt90w#^HsX_PRdv5*1PAc zbnD&oRl4==`6}Id_k5LZ{-erQ8I!?Z7i$Cly4bVeuZz7C{B^Ouz+V>|1NiG=V*`I( zY|P=es169Xr`k;6{8U>iT%h{92uElrC-SVWP0y$5_9KzihI>9$XWKoWs?@oHwc)}+sIw?!4*w(%pH}^QAlg-}9x%WboI;+JL_<_AL18V($chU92zg*Tu#F z{<_%Mz+V>|bNDTK1`%#~J+lkvyq@KSi(bzK!ciZ}i9D-kLsmY27Y`9xV+gE#{w}uQ z`TSkX!SngMScK>EcQFdj=kH<{p3mRKG(4Zbi*?@oHjUfmJzQz{VapP;u zK{)d@79m{v8lw=7eT`iR_rCf|!pR@XnbB9M|DmjBZP7P9Qwt}&p0$N5K9M$h#{Zig z2-lj%1ccLGV+F!>pGccv8!Ge_xNwcli5yT>RPJ*AtV$Ul(fw{<_$+;IE6l z6a00tzQA7>8w2?3Vq*h;U2M$Zw`dI9y1R`uXC!wXX)a0bLejXj+>sQ@i9D;h34foI z%g2eVIV^vll*?`T`=ngX%ikyEa$){HDVHPj_er_jnZHlU<<$IrQZCo#?~`(Icz>T% zOwR0n<9%mXUzTEYrITX1ANOLQ4H<0FBw6$lXKd zvafI+G>0X3FllZ}?q<@Qm)zN;xiGoQNpoa!$CKvHabq^K2wJS@%Nd={DQ_kYEc$X%0);gLHi726|sQ!3_1 z?yOWSklbad7$M{CxK!+r+W;n{$>ZlwWgRTxzkgzQgYX4 zB5lI?(VV;78K=2;xl1nGqtCXzVs8C?@kDCE`yxe{f6I|h#XJf z;{9Lo%yQScV#wtVbj6m--RO!rmpjuHi!OJmD@I-JSXb=2+`WD-`wHhoG5m4|y<+?2 zZhFQ1%boRF3m|vdYmI>1aj&%l4E{P+yds0YE`yvIeTDiT%Avj~rd{r2SFAg`yV?_J zqZs?Y*@1AaDJEa;lvk|2+%=y_n{cia^C@>0D;8AlG7k6Xvu&?6Uk3bjCX}`A&w#%! z0xmdLZf7W{Psae$82oh^o}1%;aq9W5re;uwHArNU&rAdeYWkDb07l#I>+nf_%1|N-ib8u*QJ3A z&hcGX@Yh*z#5ukT3;sF_?l{MHVZmQ#!71nXE-d)#EV$+z-vxue&Vqx^@m(loa0 zj_-oOU&qQVz~HaTAct+jXTx`feT8EP#}sYx&82ojtyaWvX zx(sq6&nh>C1%I6lW#urj;IFgFZDPS+XO;7W!Cz;U3x&a7$I6ky;ICulPGRuZv2v;~ z`0Ee@6|NNqe;q6L0)xLUgPhs@hToWo9O_sivhqJL`0H3XG#LDKtlSz5{yJ994F-Rm zRW1$-{yM819Txm`R=GQ(;IDH$jWInB<;>_SoD=0RvEZ+>%5B2nud~W|!r-rCF!<|OxlsYxy82oh^^e|qVcy=IM zYsyK&;ICulDq--~aUyNPxzd_<27euEEj)w2j>CQPY};qS-*U&_hPYc&PR>J82a-CF z)PbZ9By}LE14$i7>OfKlk~)yofus&3bs(t&NgYV)KvD;iI*`OfKlk~)yofus&3bs(t& zNgYV)KvD;iI*`wYuP`k?bUqFGp6JIpr_JpL z_nH1_J!#DPw@ksi)|stchEdl-v&_lksphjXlW6biie~?v1@O~Xf#`eWzjEkjiY)$^|4FlUtu4)U@*OM$MbgZ9go>BMt7t)m+rH_?%HMt{9K=A z*2=~6`u}1Z_Q_9|&nd&hf6T)RTJADiC)DAatC!+xFWhOS3~I{1AFj-Qbbck$GKb+| zCu;}~ga5{zJL;Pm2U^e%1*=o5GONti4h`s?>&g@6iaJsiYW{8^+BmZ^O{`Ur{!Gh8 zQ%kj?Ydid67TmDge6p@Dcpa=+{`~W1?W~dX#@%PExt?skM2T4}tSxj#$EJ#Z55$y&|~Z<^2ajt=9EGiI7G4X2vOfKlk~)yofus&3bs(t&NgYV)KvD;iI*`OfKl zk~)yofus&3bs(t&NgYV)K!Q5(RW;Aa@V}Ka?H4Tezhjmx|M8n9 zIa2=b=SWF%h9vn?k~)yofus&3bs(t&NgYV)KvD;iI*`~R|65tdAe`!n$oh@`oiPsl zc>j0rO#i!0@`*|LpE3_;`<*d8VK2FR29mOyf&bO>K+aC-@0^ItLHh*cvz@yv?w#IN zB_dPM{{LS-P@SsvyEOfK19{DT7f{}JddmNMHH(@YUkwv^_=dMlp*=%IZZRT1Rq5MB z9dbOxy_w+j`UQE4!nts?*{=a_i8|I6-w}|}S z%28(a<_RL#yKZ~rGM*-KqaBl@x$a68`M38h zjaUAe{%p5}X_3JP(*NHzkpIbZvg?5x>74=}%kLPcijP3ZHFE)n^b zIVqI8LLHG`J=l{@cfUa7yS^MoKVKS^_cXnG61}tW8j=4xoJt)o-;(Cub90s{)auHH zq7N5c(35Jtm4n>>b8fqq&hMH}|dt=NOS6DUr+k zvSzBtwWoZMcG(Zv*BwUO{RNa zPBBj2TW%OF{dtqf$MZBLK2~3TuhaKmLVd&B3`M%W|!((S`%FT8F?Z%N;S#$Az>*ZkT?p51b&BDcKt3X#Xw zFUvn&(N^UBrOxLet$U07&4Q2Y?%`Qz3L?Y{A&|0e%W=j6fvhv($GKT@g4==QSS zLwUznlWEC$P2_j)TVy1CzG00mw5V;BwQEMxnS;;STtn+ut^e{=y1#!;Tm8+WRleDt zN(c8;j`ZsMc@=6miDnk)ZVs=`UiI0Ix6qlxo6X#9m8xF3zY8s0ei3!PxOUY!IWMAV zovx*|Yj#z+CN(GJncagXwK!d=$C+16w$8&TwOE77FYYRCj#rpUo4zSixj~apqLt=O zqc*1N!g`x#*`L;pqe1i;j&>pOJ1ix=elA78#blkF?!-!hUl70BKY8&r-~%+KHUj zycth>v7X4~e!H3vw=N>`pH&C*oR;6ncwQeckpIeeOyn+Kb>=aT7L+#MPA2YhpoYlf zm)2n}mJ*Y#%Kzj!DOB}lnmBm7%v&fodual_{P<}3f6WQ0^w{=0MIY*ZI*lgvdtKyR zi^tK{5)Vn67p4rR#y{*Ax#e3ODSD`=%yYe+7t^x*%|)(SAqO=Yo_HOg2QDiRee>gVeK_>% zJ<Gv?}s@ zwY{wp^*Y^3^-L{|nvlUgIn(q7E{tZ#pG3opG z{(+^b?hEO@!O0(wn7398l;8K68c&(B3)6jxA@`nVD(*|yja{G2j-KB&-EOQ~|COzn zV~Dih{q#|LZEE_n=PfM9_myuW|G%kB8$PzAoX8g*xrtYveqVGT>njtu)Gg_I;-+S) zJgm-q`F*=xp2`omeKP9wVOH@;{LAF#6IN$d9Mv&jBv-t^z@^sU8d z%fb%w+s#_K$K>Cf{#%!ydcP?&F5M=~dj5mRvL)$f*zqS9MlYl-+F z5MS_@8OkTQdmZ1&lzv+x)`^}e= z(qmKA-`HtpeRiY#j%!~UWpZhpyyc-gBj4Yet`E&7e;z&W{&YRbGWrplqhtDe=1=(1 zE{>+_-W3g6@pYpr%X?lc+m^4qzO2Z{Q?BP*w;eK~8=G$BQwMJo`OIIb-0-`Cue$%g z^yOs!tbY2L{q0Lf@%NW6m*00@`vE+q%ugae8R^J>EiERx@j|Z#+--Sdkso-j3E$WE z5|N{=+H>EIB}E>*xevE~GONglH*yerjLH8u&PlU#G$)8lM}ru3Ozt)K@yG#1P=`DGR@IOJ8Zf{Q0UpyVGSN zcP`V8kCrJT^2l=I`QpzW5Pg_gZ2}*9XtKyDGg5i#kg=j0M<1BNpG>bNx>4)>oA|3c zc8GlItzCFkoAjK*&WDZ1`Nm%hc? zcb^+3^29YK?VLRQMJ{l%Fc-L_lgL>PROhPyksD>7C;cbS$+*#f*iLP(BR999Jm%RI zc2c(VbIKDvYuf@n(_p^!sSiJOz7i;mx zy%Fj*zg4-dw_L>whL)lYOL~@X*>?!Pe9d07^YTy2A03#=6<(Yf`K8j$T%2PI% zjXc%1efd=tr}Dnnirdr|-+1QZYld^SpI^0E8XSM7$^}>RyN?#-Yc`F2=D?@*_(<_) zyy}*F=2!SMKX)q9g-ajq`qapUdu-k&=`*7zwgT*me9zMhpDr`kp8jquk1A7j;g_GjV@p1ro(I=?5SyD-apD0tT)?WZ()IxB`)ZD`4OXL=m zoq;Qm{{vURz!iuLTmb`DATn?T3|xW8z!flX1tJ4iz`zxVJ^)w1z!iuLTmb`DAbSdM z1q@t)=mT&C3|xW8z!flX1?>QKxE(w7`Os?4{!wxT!F~I6)lU8 zHw|Uv&>6S_`9E+43|s-Z-xRn42ChJ4;0hSH0%-$W0RvYcGH?Y9T!F+wfh%C(3aon; zxB>>QKxE(w7`OtNf8YujxB`)ZD`4OXLGyu2YN3oAIs;c=ruTlTDsTl1T!G0y{GO`76)s{vQQz!lhiM@v)#u7H6nu+0k=t_EBI16RPShGnk? zTmb`Dz@JoHUlq6l2Ce|Px`kDNE3m*7@bAaER0XcU0$0G-*MF`Ga0L%Q0hd_OU@>q71Y7|>)OzS*;0g%10$%dy?8U$p5O4*2sK|?pfh!>3 z3OMc4M-~BBK)@C7hh=gu0Iq<5D-fO081>)efAXBTTn6$Nvc^LhIdlfDKyn|z6)|vVBiYG#{jN?fh&kQTLD}F16LsL0j_|7D-apD0tT)?<{Y>J2ChJ4;0i2o1tJ4i zV1X+T8Mp!qT!F~I6-0n55E-}v16+Z~z!eza3Pc93fPgCy8Mp!hu0Ukq3JACYk%229 z;0k0sz!ea11tJ4iK)@A98{i5ExB`(~o(s5wn2h|F$p7Ry(cGxa+yBSjTYy)UeCgf? zCpe9}J2WnV>{WQaytJbfowygIs?ix9C3%&wX4qt%+`d<7PK1xmwLV8K_QG<*dNUxCu_6&UapC=FkM0bhaA@D&hz1xmwLK=2hP4PSwP zuRv+|3Iu!wO2bzm;44sLfUiKnSD-X}1p>YTrQs_O@D-@F4PSwPuRv+|3Iu!wst$Yw z0=@#JwGZbn`hRjvq<718uDWaF&@K216btwYEcgmk+~6y);44rXz5)xr0#ygT0t>zZ zrQs`J_zIMUuYlnzP#V4hhOa{b-GZ+`mBUwH!B?O(d<7PK1xmwL zV8K^l*ZJ^<;VV!Yz5<4?Kxz027`_6f;VUrUD^MD~0)nqVY4{2Vz5=D;D-iG%C=FkM zfUiJl_zDDk1&SAZ1p>YTrQs_O@D(V&@D&L73Jkd(;42XD6_8pRxq1rt3Y3PgK)_d^ zG<*dDz5=D;D-iG%sJ3{X7w{FR^&_=>&X@iCPmYQ9mMa$S8aZ@^uRxWYTrQs_O@D(TxUx9$HK;2W|D-iG% zD0c7_2>1$=hOa=tS0H3R@D&L73Y3PgK)_d^G<*dDz5=D;D-iG%C=FkMfUm&TQC z;44rXz5)SXfzt352>1$=hOa=tSD-X}1p>YTwI1Lr5bzZ!4PSwPuRyI0_zDDk1!_IO zS0LakP#V4h0bhZTV}`Flz*nF&d<6o&0;Sg#geqPztmlCY&JqX%JxFBD{^IoxD|Cw>B413iZ~bS z_X~IZv-%T$>n%bu*}g<~-TY`Dv3TNYwPsf4>nHL(wZF-D4(~7Om$2V+-SyAvKPcT? zOu8M%lIzD^f11%!ByTh+V74j!WdGwi+WuIHvXPsLB$ew*{{uTuSY_A}@6<#%aI ztj?-`cm1>auL_o>Lx=2pio5oVS&KaH+viEzQ%)NBda&v#l!RKiSt? z{^xa`*Ij>Xkleq=cl*8u?d8&_C^7Yi_AH(o#V&+20hSZ?d#hsK(*Tx$kv!*Z=9tTD@Nz5UQX ztB*Boxvl3P8f)Hit$D0%%e5D{-jTXR$Xe*IvdRx7_yo z5B;ny?wAQ%|1a9Ur>Js$?@(IbgZ`rRJ?Jm>^*v6NyK8+iT0c9fKJ_!$U-ZxF>t{~YkGs~-mag+nK7T5$pEF(On|v1iH|ywU zNY%f)*3X=(Tt8bXt)Ef1JP?BdJROcf#@|5y#}J!K=c}jUIWo1JP?BdJROcf#@|5y#}J! zK=c}jUIWoPKG3)xZ4HbzS}Us!!R@HBQ-|Yy9#$#fm1*h5qorKj$d5UG`(X>fg4~^Ho~U zSJl(=Ra(#2)n3k5X+2-1^?a2^Tywgvr|0XcFXyW?#vHF?>vu*2SY~9!A ze+I7s^UKL~sN$^Gq0;|ZyyTqh|3#lCG7fs*SyKPkIZy2KtznK#^4_4%x_?Nk^KeI> zgub}$Kd48E(`{d1uI1$!@DFPHoJ4GK-G5X|rUG%sz1KeT{~0aMR~h5-i1k0GYt@RC z8_zkCt@ZEGDVuNE5E8qjCI7Ehlbh!2Z^e|RiCwru&jL!fOt+0A_GMN&O|$zv|4tI6 zqlU(^l3oAGvTcEguq% z=fgSP>61$7J>m=3-xXWwOA``XWez@a^(kC^t{j$F9KB+fuRHgaJd?&(^#%Tac`e}d zO4qJ5iJI-rqjc$bdFgG6B1#w8yv!KVV;e#QZgNNa|TTa*6pDW+|=vRJwfn{36e~fl9xrTuc-k6rtLpjYwX}Z@p}*%T1|u zeU|#m?2mb6J*mOk0Bfben!s9VuqLop8mtMdl?H18*6O-oEx=l7_p!;b$ZN~~*lzDk2HgRj!y%iyat z_?qCWbo(qD*P%b9^;%MW>NTdy_1aS!eC3){TCY{5^%_=MkCWv%!Pj!*Yq{~Y-1u5< zd@VP=mK$G7#z^*wn910w{t-(HF;yJp-$fihuhy$BSKM`d)%M?W4n(*8_n)QFF^rC3 zmsjnCe^udoFy$v)tf4Z(K|K2qo+0Hdi z*`I6t@;Vvcd|RjICCf?AOV(Ff_oKA#U+8(s>ng3sqqMw^jEm|Magyt!5u zxty=7zKny?IzCG4xG62KBmY~r#du_#UE`GTS6cSx8o#{G&0#fi$@={_))G07X3Vwi zbUJIm*CHb9(6yXL!^>E^d{c=WwFl+wve(CpS{3b6_8h;Z0TWS0~p`OxcM`*7!`ZLh4(r=o5 z&xLEd%1u|fypF5BypF3Mc^y~(@=w=w<=?x;Bip&gDf@GcUtZ_%x8K(4dC77^&r8-P zJulgh(z<`8^>vlj<560VQ)zh}886vSP_3iuWK5;j^L5piaZp-bN5)as(Q#86*Ol>9 zTK>IjJhGi@obo!Z@k_qW$jQDgzJ0du@OAO69TDIw`8NNxis(1lGP8`zX89lR6x;4k zW2w_F%p~@-&cLTat61L$<`DTdKT_rK4qcjl||qWfcsbX!wevi``3k2Ji}4OKp7 z*#Yu>SXh-m?R?P8h59>Dj(?Ci5eYCqsrrqoR>S@s;a8|=Gdjiw5-`& z_1RS)<)*6~{j;lo^uw-xFdoY_9$c4Q*TwiP*Z46`c8wGBwOsSXye!we5EIK46U4!C z#X*-Fa=xRzvs=^l`>&Jp(*2N*o2*YdZt}XST=%ca^*Du&n;efS*Yi^4di+AiO~yf$ z>-nnkbGeQ6h?^?c@p09cadwr3*SEx9=Tu+o`o`G5fBChpZ;$&% z6veyWpYPYMZ(kc@#9r(ACf4>~fbWG1AMxEmeYf&;ee)c9D4DP8TWGm`1y;GgFT1{- zp4dDkr|X;Q^v>sU>Tf<`UUNDn* z%k}LD^UCG=c7%E5($}>xFZA>0_ZdA-3-ijQ$8TX?IhT1=P~W2Ew_8153-ijU<6vQ4 z*>rp?`Rzr=&BDBVbv!N1%U8$Q!n|DZXUxmRg)uM0d6YPLd=KJie@n67^=<7c*Bn)S z%~AE^-oN{G-N)lTPWSP<&#OV5v*?&a z$K?O@8j$BC?l;)?>fBH{FMa;YoU+`H^8A;%8o5v9`7d+Ia{tQnU*?qMzLw{|{7x?S zdoH(gK%W1u^C4&1ay4D|HF^Ha^HAvXU*%Z!`S1EBEYE+LQa)II%YH0#Df!Yp(N9-q&2`p}eoj`?ZXZysydgR>n=<*W~?L##7$cD&=xvg^g`hG3B$omxHJW6~E&x-k}Z`c2#qdBVQuKyAo?K}WztLHrV4JKMg$K=26 z8oKK1=9at;|UYovT$^=W3PKxmu-lu2$xWgwE9}?Ur|w zxkOXv?_`dVb^Z?R_p;94$$TB_{GGs`DxW9&wEte^u!PRfs{VC;R*gaDXO-6ZS*3M; zR%xA|Rl1;gDz|ICIzOxW)cILeN9Sji*7;ebb$(W9ou5_OeVjT!tNPUWS*3M;)=OSn z=VxUOPU!qBORe*>O6xwAmNC=$J0WAK^LOgnerczym2Gvo%-;!JUtM=*-7}J}CChbw zR%xA|Ra)m~mDc%LrFDK*jX~#U|1vhWJhgDkUkkUqws6aL3%5MDaLbQN*0`q1?@QJ) zSF5h2bG2$bI#;W-&ebZdbG1tAT&>a%TV~Jcn!8?Cs!zS%R2{tzmDcN1X}xZh)?*_X zL!F;h8hmAbR%!5+`B@iVnV)s>mHAn9UGSCpS*6|QJ7;uWYgFZNs-M(Di&zb^WK+8J z*b-Lk-c1!#tyQ18j_OCZRa%}4{}E?GbU!YyZFD^4^MCYu`1|WY=KhY9?UMt!Kb2$D zIYE_U)VV^LgLUN)$t|}?ZaGJC%SDoGr*o7f`_s8gnmcboZk^MV<*r<(tnbQ!%6?SN zQjSOFW_8X~URUO7WlmF$N9Jl}9#dY&m3x)faph#uPdlsSjjy@&yj(e4SABNtM`_)^ zCCl}7mDb}?T8~p{J$|Jt4VWc!wXSkC4%v^6gDThYQCi1MX&q0cb)40BWc=jy^!R12 zR%sc(JNdh>mE|&*w>|%FYmv(nGFN-~VWzdnr;%;gE0SIm@jnas~B{r*P7 zoKm~x1ch6!P`Kp~gxaAzt&yQTBkU2)3qZDqrOA-3Lfy~v)yre95sa+;ggj%tyP*We(a^pQYCQD6RWfT3=Ub zJszd?IF;7pS9*1h=Q3C8DtG0kU2#z5IzCG4xGAmUskDx>(mMW1Yc6X1l5f_%S97@d z&S{WJ=HeCK4>wE6T)c40uL-vtoN&vv3Adb`(79TfgA;B!KH-+j6K**{;gODZ_YE`+;)v9vTcjYLBTP{-eFLSl7eq^pz)pyH*%InHptt!{KTA5pv z<8R(+ZAV5xhwbW;^OMZl`D5~ zROOnNx~}G~=B4?naq4xV%Jq6s<$5it_~`Yc%H=)vpUUx_n(!UD(|<0(MXTJL`}Y&KZ}`!}h=W72qFM%r;Ys0yL(>VJzuZKqw@Ir8A;{$wa-E2{rBwtrYAM#&?*hTw9Ln^pfJPX|Hsuxe3Hp z(L`xK|IDKB&1!$qf2VDZ#N*b=bt(J*I~v!rT-U-FEY}z?Hg=5-*Jan3-SyvT>)J0sx#bbT{NZo?Z4;lk=Fc@RSnrzYg1}nhkv5~&9<)nDBJ!Wt>-IbeH{~}b*z-u zarle=J8g3$jxEnC)%Ndby*6B9kZVS1y_S^5b>$lSi~c)p5fj-?wf#F9EChHd7GNa6 zOEJ<~vD0-Fm;ZzQH{0qlSTg>9N8h~l#5{UT{iad`n;raLMU)USx0R^WX5)jUe&;Cs z9+akgsS2y|zf-^Z{50bEqZ29*6;vm-Xp$;a=?MjH(~SPfR35E-nY9#_Je$%vcQmHl zkJRsW#g1S6jL(zQ?`OrP5i!iA*Gs56OY3Fiyoc3qY(@2e$$YMZ`t7Yq-}nf>OPEg8 z`6ELJC(996X}?QJtQh_8tLp|_&SK?>xk>3FNefy#BiblEut0Gu&#((BkJkEq32VcW zEh=Z%rEXEH;o;;Y<4~@1Uh9vuc0TU*p!8OC%U_kxe;3c%lH#4x0XrYFl_Rl`^;;g@ z#uFx~-?xhHWxI3t;_7#=!aZ(pmgf?iGS60HXjika*s-C6(k<(j5LTa&YCKm*ln@Jw zwN&}OekTfxMyU&_YqiatTlCm9Q|U5C(ufSLPAHx4L2MCx|FhB;I=rV<&Eu)@w4QX8 zrcV7uY4h6LfZ{(q|JE6J2-3RC;2pl49BDy@zCdV{$R^E#W&A6UUDHVrG`!B+D!A$s|(y z?^HS}ETLFFGf3$XDPGe`!$ZhA!D;Uic;dVZDobnkRgrHhOz=~XGp zUjP3RtEQcJ*fN`A#OV{pm*e3ORc`<$W7G9V(izVA0*wmem=TpD07wJE|H3KHw zjNIonut5-g^X6ooZ(T4B{rQm1EY=uBg$wQA%B;z~#9tJ7(n z>ou3=#tEdvEuGed-oxm5frpeHb>cO;Km}?n;$@wj*4~P{DYV7`UenHL^-nT~;)Vrs zZM4nCEvW5;7rYT|A7w~D!?uL-C5%B>^^M)@qc~kxr*-G|r~Y$VI;`s`uW39q?|cvE zO{m{xVnv>n>@C+oKbPZ8;vD&I^HTJmKkX*=*>{-N;ky1iPIB$CYq%cbQ2Z(4S!)!x zK-;|KKk$TP#h6+-tqT6%_-fQ4b8`o$b#S!98uF;He_QDBt0Q^#o|#5E)G7AsXMXZq z25O78o<2``#7i`y?)B$@G3HGqcldd(hiXubG#cr%osT_jQXN}6K6fD z{p2ORM?V#_`q0PwSE)J1b~JD&9bW54?V(e)xfgD;d} zObW`1KBsy|(UWyOj25`ogH8^S?8#aG)EGnhm=P5J!vk|O>K_~WhRh~axD)zGFzhB( z*gS>vw8uEln{>FvR^HOlY55LbPQ%8Yw)Y*My z1J}5GgyVO1TB&E875gAkMA zg*R}ekw>X0VwG&yIQFW2m-?fA_r^6i&L6L-Ao`j5FfI=RyJToU61&&&8}TGA1VxXEx>Ebm7Vm+*JgJY>^}Ci*$vqpM2i~Q>?VQT z)R8v3onY5)X%C|%#(4wmiiXu zX2fU1pygC?oXzg#{XR5qkIgP!+^kfnjm_>vZXe?q*u4e2gjKx#cWZVrE}t|PXm*`T zdvZn1Zf553{2SOM0K3^&H}I58HoIG3*SfvUuIlUuJm1r1_ZsYC_AbcNz^=&n@7(V5 zpX^#E$WYb*yA@zpYpu<$HrSmGx7o!9yL}&Rb_Uoz)a;u4x`AVk((HDQQ2f9 zcJ07%T_X$6Q~Pc{*wqTR+1(iOh6=Q_ z*;zwwQl+gnyT<2CYUi}s-5j`_f;77%_xe!my*9hlv9r=>&2D9OALE5)x3+_~{|?RW z`_+?XN6oIjrzbyoY45vUS;n*V$!7Q4wGI5{qRnp5%#*yLoz3nz*xfBXf}3D3RIL1w zv;JYTYX){hKK#k<=+lgf-2kvly3uAAR`eq;`DU}5R^tJ8_++!&w(|r}H+*TJJogH1 z;3b+}r5)qAejR(?O{iakZ)VR9PB!vZSr1ejIx?t+|*&lR?TjH z`+D@^k-hJd=kOs9%`VZkoiuxm%`RS>3)JR!d*8L*6GRE?+3eCc{6c<1ZFa$6cW#=^ z?mXDVNM*C@40bcW+w8`H-9e|#t|r)pYIcEVO`OLzyE0(ce!RW!R^RDE9W}dYF|*PU z&2CT@A0zfCd*AsE^Y-7S*~Pqh(iEEAiL#!&RI^K$bv!rK>@I=b0L|_#*d^2Kvd?+I zvr5_QMuVN-?>4(ZU^nmWMstonGy7M{tk^XLyK9?mcK%@Z@w?5g7}%}&Y_qEhc8SPl zmj~<;jJEgP_U+?%vu0PdUJcIN%RV#n-igblG`nRN%bL?PyQKZo7$r5k;c3H+37Q>u zs7GrxyLn)@{jR<527p~5&8{ujz35@HTLX5H-Zs0+V7Fw5%`Ob=ew$>oI|FvpGM)2J zg>$<)*lmrn+0_9%zg9N87+}|J+Z4`=^JgU3dAG9JT^q2Rc4~GGsW9~i)MH7)=4uT*hOLQEGg&7eKfnlV3$d=%XobQm(c8r_?+a!ZS8&6 z2<+~cwAuNB-PayAyGdY|Kh>|Pe! zz@*uA2fM49-QK!2*wF0e+>XmNG`qhe!7hPjHv;UAYIgg?XLeJLAS~FWBYR?52TTf6cBZ*yYsh zl7k&-b~(ZBqGnee?BeNtw;1dS>3ugA?54P}Te#0==M8onw%F{pfL(3PE)&>2*ZZz0 z*yYmfe!;%WsM#$AyM3Bn9_+hZnq4yNJ5SASsN22^@Av1vYl3|@S+iS#eYZuk8x3}* zX4eMnDr$B$z%HIXGiQKZy}I_kD+zY7^qKh)>*_{Que(CHpvl-Y;inRA#Pq53P z*%imW%cR-)gIyxcE*H+sKAPP`oS8i|yD>O3k7;&Oac0KS`|k0OKhMlHH%^+B^_e*i zXXXaY?j!DZe`t0aab_;m>`vj#EU(YZ@3`OnqVIPd!LC_Pd*5{dJCFB&?z@E}GO07O zJJ@B~WV3q)cJcL@*&poo>igYduv@3^ck{t+qrTsj#r>{{W;fRDem4&HyLg&iqHAT% zVXiatk2FR(z3&>N3N!pPyL`CcIrOv2H9V^n)AzeTJgc11>@MJ0Wvgaa2;k){`hHgr&njK?{q8Qo#d{&9P5vx9zCxrFD;{rWlc_`R}bTd!0rksr5TTb-W|Q(eDV|@QzScza!+vJHl|hBgpr=CwNClsoBkb z(1)66cAxN$kU+D$p4Z3N33l@R?tL+D|2_JC*9~6y1Dai|Ql30fv%7=$yS<<7_q&gH zze}m#?<(LOA+3JDJBIhWcIE7MglTw3$g1D(BJqBg#_jzsYMuRlcLVIQ>i4@-V3$R| z-<<@z%J(|%S7d=!`KYIX&K z%bG&7yV)#_(Gcw9yZMR)VMcq+E_SPWlv}@>kHEY6S^aMQ6z}FM*V^xQIq-h>Qoox& z!Mk~gemBnsc0#|KPXN2T8|-)UhhSIffz7TU-p&2r+57Gd*o8E<-_7d}yGenY?01CX z0VXxl@8$)DET>=eyZMyIeQ26~H!qPOD~-|b<_in^82vT7tC4m5{WQDdr%sv)8`$sW zCyRM<-q-d!f-~cIUiQUi=NGtva|9k?54@WfoPLr!b+n&Vf_xruPqNv4s`!zI4Y1$M z_kdlt7@K~)n-{B^O1+!s81kJ9FS5_fcEvyPflv0c%Jy0hIOMg>uFRejJfy76?oN>n zd}X-J?w38|IId>*x_J#ws@Zi9ipy6r+TT^4&8ugQ-Hc}ld^_rQ=Au_r2Zu<2XTMa& zHDl@g2s)4Fv2@+a(%$XwC??*QFFVFk(Q^057j-hc_NA=ZPEdL5S&`=m)jqJ1hJ(B3 zf?L!+&171Iwo@LyrZS=$3A8;L8b(un-W%od{(CjIL-byo-spk&j49v{<7;Fy!|?4Q z|EDmzli+RPK^PFrL zz857J$liq?@wNU=YkP1p9&zbC@9d3lBhKq)@k$Y#y_eHU6CB5UQP5#^L-~Qo>_)=a z4r>PLuPXn}==CU!jh;@c-RjCTc*q;RhOwO;If06#xWjw#4*PrU^)w{kF&=}x-~8S& z8sBCe_w44h;-m=V;eK;?>_Dd#YsoWCld&Do8sN05HT}dhJu-96K~8H#vhVzB=dET% zjI(}f`B4ePp?BW-ytnZs+JiA{Jl&J;wtqrn(bj)K0WP29 zBb`8bf?j9LJtrfm5$cZ*e(C=h3=H%$**mK-4Y`}i=s)|+dxmi;oZh1Cx@9G3VvqN9 z5V~dafs{1yBl?JO?&!6cf>Q@jBaHw0=RFiN=RV4Uc|9v~o_d)}s1)j?jrovr(NLO> zwz=oNqqH$SsWHaTvPL+~X&Gb;8RE2BT#2F~rSlstMmnvJI5P${yW(FP<l|pf7iZi6jFBv*TY=8bvjNFwb$}c^mA`kYqQSs zDDuKuYOwUI*OYz^QKp&GYF+G#apPzNC28uk21b>l6s_J1RYxQ3wiEKNk${EJ{3t5?@l#(WA7AS<`84zY(KQGiPH*?`cCFa zUo%O4r`2)uCn`873%{)Ew4N3ZqR%I~avyxVUg~j)E|plo`LPG@_TNvPBrI_P_QKeR= zIOW>ad;)dy+_=ZHyN%)VXj{F_JHCFxi^pL+Q5hoGJL3a$JI3kb?Xafrjb{pse|>3( zRqwYv#z@R7SCeqA-Q=zD8f~v7f6FgxSE9IR`{v>u&bewltwnscE;-J9j<2N&h?}Fu zCa!$$Fx5mnw^y6WTie{EY>4xP8g+SFomaFBI(fd>9J%5vZ2_0uuNs;W$D-&Cc!}Oy zy@ri*h`cB-V4g4zPx?mPQNQ5Q!nEP>2dW00?86{xm*){3NB`$yFQ=jp&r(IS9T4G1 zZ4T|Ev>4BY1%Wi{{v0}k`txo*qtl(+Q#|OQ`#w|D^tALA^C~|&l1`kMV}xM7rI$Oz znq9XJrb8T>*N&veDVCY#FvoeneWu*oGVoo@eMrVS2y4Q`2R%`!K0 zioO;P#TcgKJjqqF`LYMb_WJ5w_RoZGlxTZz^;_;VvOL#E+k{)f`R@B?W;M*QF*&Tr zZmCT_%)M|8hn44B8sjY5J~|W5>o-0#BGEP~@GZ|+DCjQYR`&K?J`_Bbsvx!_Po3Ze zEqp01VqWajW}ZFXqNQLl?(H=0Q|AViL;a;68gQ-=FKGyL;RNxyXojy;A4~&}wKu=a zjG}ZnXSOGw>19lJh|wsYm4J=2&%V(#)NgXT0F9pckqSY#=+U1VWqC}!(f{?{OX*O$ z^K=wz?9HYFlp)P-8i?`C8gQAs2F#<6sK5G45KRy3M4vGJ?3q4OllB>DHRd&-bR>P< zy2KcS`S!)WZuu})xely z|MwR1-uOlu#B)cP2;Lli-$;SDHT8MNs~?u5Jk z#?W(cN$~z8_xP}yCW3XHB3s$tVETZzhi1*-TAtUb3FaTk3qZL-gJUH&`mK>c2+^U~llA(RUG*puGmpW+E+ zMccx67gOE30aOWN9^7<4ZTVvl-NIa!)W1a86E2|4m}9kML6l}zaROD@|DU; zO%anV!Qbi4+%-lNVimmDAyy|jSne5OIPz{JE!#fbT!FS_`hB4isZy$#?|S^4s(o+8 zYrx{y30J6f{n>m5jHWd{M1Hh`V?nPdwSq#kp5>CL;}c^z4Nv<}ox`GR37Qx413OTD zs6>DP)c$RE+xBhwph@ZvWP zMcl;UFrMr4#Tg+3S?m^sqyE?3L&p&!~K|JTIiQvgKZW#Gd|918FOu5UD z5A;;zD+l!(MN`40cB<1HF@6;#z}~Doe;Wsc_)|5M*DB`2m9t%=0jR&XcncmB_<{)9 z>ts^C6(^L|q5mQWMw=_rM^Q?!Uh_VuSG7eBQ5NGF;=9erx8OV7Kz*OOIcdhd5OP4b zZqk!x#(qkHnAiPEi|E$e%@KPaB|EW~48-A6fs14;TS&DLpP9LzQp03D=?3N= zd_RQR#LY>`(e^R=?muL+F$r;AJ|F*X)0ebfbrJvSnWJcW0@37Wl40)fGHS=e3SlKbQa|OPd?Kq5YqwTl^ z)!0h;hAW_L_@#-={cm$l%<-1bdfu1%7(c_@yLLUwx5jSZAhfj(-QrexCvzOcYHP#S zJbpn<4uI}aIgDGkh%~b!wnyNX+)}fmSpqR%Fu-A*|NW}hA+VU7;2ZZ|bkV4S`s1SB z^N_A3s3-K8rw_Qx@58AWnC7o>hI7VQNx^7aB5XTfTz`mGqx{!Pv$$Q{tF#F9uU}}z zZ9|_^PUvqdQ*fjHU#J24AGvz6`T15P&BYo^7N;VDhTyk2csKm+$&q*|Eo=dF9FN}Bz&260#)^8!sMxR^$u?Fi2& zRCr!*3P9Um%7)P6D|sjYEYeo|POVz)Hc}wYvwiUHbF874KjQDzGKwB89cCs)onL2# zl5;>JwKoeb4yNyins9EE_c?QoD#xD5FHpbqU6Wpp-pWCewdZQexbGD2MxE{NMpOAL z_xUWY`{qD7dOi0Y&&GK8`Ca35*$6(5asKKP%gEHwVP(Sj56vrJrZ0wfBFrn>sP|@` zQsMjpZRa$t%;#>u;S^}wKH~&#H|`D}MtsbC>)5aAac+;ejmv$6zlLn&5{Rew)|)); z@)XX1IPahIiqll`=Jn9)kALOL$z$;eaQS#Sif>)3YwiQDo$wFTjN0p!4CV8G|HiYP zpEBB^e*K*vxaX!KR2Mq@;X^+6W-#4F|Gg)k*p!-z!KVx zwwbCwrunJ*(@C`LIqM@WUS5Evf<>Jd-)KsHk>nt7`@tUZ|5 z)4&&ICgL)(xw+?A1&*i`J`;T$CJGc~F5ycA|wl+O+4u78Fuv#o#;ME1? ze&@e&`jUr@F{od$^+zriT#!mYzrOW|i**}7lhFT#Bjq_&8| zjj0O^pD~ft3h_zsDJ^x``QtC&qwRz#-)L6WV@6@{tu_*QwD7fFOQAQO zkD@70oaSWI`D6K4Y8x1vq&vQ{XXxx^moD|mzZg`kZ@g}~6F{~}J zmey1_!Csix`-bD`k92oguFu)|E79PzZ@CEC4x9Pf$ki;I9hl?LFIkPZMI6>Ih+D@P ziOr^s9aap)vvSTy=8JR@oCt9r znPZ;Y!ne?N&cy4SAma@7M*Vcpf;s-o#@rsdv0o@J4NSl(z;sRLDBhau5Az_}cAD+5 zDopL;bqwX7@_c8{F$auws9)bBgzx3bNAi4VaPcv3$9K2V=)X+Zd0td!2}wVON76m~ zZ2x|EYcQ`x^Ev+7OOzaQTsW~S_pTR2@?3J{$ig$We4-wR$&D7P%uu}3W&`WN)fOJQ zu*4zGAP$#r%`|G9iKJO*TRKlFx?kf9$@6ehj5f4w&2!od7AsEArj5m~P%s#sTe*X_ zgde1*h(8THOQp{&r<|xWwbes1;}0YGu6nJ+2dZ75I3-8>s6fT z*eMPIuUmCZep+-J7e;yWUe~y}Ig@`!{ozT2*{g7Kt_ppzP$>VpBMF=6KW)J%z7R3O zEQ7Xj7douIp(VYtU_3QOe&;L~cNphUf7JF6p4=uE#f8py(@=a3NnE039c~h6CbO&?)9Fm=vB>F_T(DrPFjb`ob z-%0xM8f1*`?^x&%#Ss7Tc_$h96GhQUw0+VvId!}Hh2(Qi@AfUpd&~>!4;I66%%U?* zuF^oT-c)Hj#V_wq4WJKIIzth)R#IEk>DB??frgGG`L6n6)O*VCrWD;opON@(W<_#_%q+Lxh(UW>SnTY)Kf!Z5VFK=eovsUsKVP)wvGZM&!Ls-D^(b z@|feC!$-;Y^Ljppx$n=gf$kqW%9qggw;hwHPQ2S3g|@?H)S&LuU-K=*?T`H5j7^>K zO%k!KS&WRl@f=n%#Qa&*UH|NT9o8DKSa|HR`Q=Rn8>s(wKuJD({yh(Z-qvLVUtjuw zYl3OQ{wulF`_r5R=Wx$B{=9MCcAkXt%8jpbWQ$om6ZPAce8I!dIk^CI`{iGF=G0%f z8~UH|I+8ngnP?us8oRl~VWs;1vD`?E=V0J>4$rXB_>B6e>wV(di}3IBVEmo8KjrGD zyVFw4D@E&zd^zJn`UCUrd0-#+NV1nEAPxik7xA3N7pNEFlWSowo;>UcT|!&0qq+G; zmk@dg7KL)}G}ko$PQ?-D(jk@n`_6WV<%oZlL8FYKHKQmJZSzh}Odj1r)j6EvXj39* zFqKBzprJF#Z_qW02fojrZl!!~qE5Qb_i1Ur(InqhE1h{qM>m(H zRp_%qvj_^=b=wHWI43rBh}c&ny&^D%&IR#(@@ZkSG3IqEWjI~m@X?g-Ykk)sPt?8& zXF=Q9W$w^`1rzu#;xqQcF?us&9n0_DyQXcVMWc^!X2dgh^C`49>?Wr~+)|gTLxYaK z;$6`7!eUU2;II4uT-I8(j13Q>cotZfpTYh|MmVgmX!|<(Su-PYM$J%v?17@ZZR7`T z3SH{u5U#QKA%8+0=dCra!#z@Xvf2LU$W4^b{Va1==uiPWdrF!;A4(+na$c8xjqjT*^f9 zJw5*7AoeNQh3X?Fy{BK|sFCyO3u4tI{s9izx0~J~hI^_n;f@6Y$QNxdrt8P4r$1IP zx2EUk%11uZa+)X8+fgZx8m*5flZ zqW&db(l_+^`0{k>HUBy-!rGWNZVM$k!sLlDw7Yhaw$)riPtbN%r+bt$-&nQAUM7A= zzjh|-iMEqpg;S2nkBu=Hr&l$HD3vRT(GP3&n{bG?^Rt>OFt2ly!zu2!m!|vXCh-aS|(4sm>;luoeA6v=Sf%Tm^htL|H5)J1&OPWjBk zzhN_&vW;RC}j*^q{=a z=u#AI_}wW^#tiizUezJib#aO_+isf$a!1gh&Q1}M+>>`5eMc|5I>qvYqqrE~r?!7M z#lCJUdB%*>ly0C?WEgme4=vbEHTyZm$mxMRC*K@u-^VH5wh!Vlc)s`S>lB^Gg>bCW zIb@zf_%8d#xwh^%kXI6CR$uV%-O(Wuw{?nB2kRMekt551Yc07Fm&#`OO36{aanuF> z5xP!~6Wxs3jiab5#u=C>1^IONLV4RbMg5nZsPKg#=}#8b%P*p(qc6}~r&AOj;YStm zeA%RfQ?&NKiu25eIzi_+`;v|a)T7U+b8=7^UH%ki^hVp#B^{zrp>#$j^f@XliURU` znoV%6@`b)qyY6v09mex`{R?_hxCL)P{ZS&2Hm9D;9nsJBHv1^F*j~CKxW=Jqd;Y`@&bsp;$3-1yx&ZcgvzQZuSEVmuC=}3S6cc3uHl=MWLJd(sasl`UD?+As7DE#-K)*>Xu~&~ z-Pr9;x)|SPw|uY%CA?y@^DSM|Ncq@iSE!taIT`F;g57U@Ld?nMY<8aB-rTB%&2GWv z8SH!CW>@#r4&J`~Ajbo{UFie3+N;H!2<$ww1o7_PUAZ~f-2uCE?`(F-ibnCM{=>~F zU^fBmyjR%l3W44JM>e~e!Ed-wC7WH*Hn(_4Pn+GLm&|+0*zB?-S;I>?$_!=Aq4PcI~dr;9mD^c2`dCV6n|+7bjx?PY%}X zvIg<#-)(loV}0ROuWWYp!EQ$fo81twJ8A9onu&dPKtyoGm$!`a*ms9syx~&6+3XUw zzQxsh+3cDGGaF^MPz=PsSE7~dmHrG3#d;p$(Vt@^drZX<|MvB=^F$Au-Jll!W~D%T z-%U<;!GE1*7ZTphm;rX3(e`?}6tudX&923lPL%JQ&2DCuMYMgm&2HKlKiU>*v-|b% zRq9&XX7~L3OX_~aX4hdz7=5~Jv+E0X3&PT>efRn+{8}wN&1SgP$O2!f_aK{H+_f(# ziI>f8Z@EB9m~pQBO@}Dnav$|8y_a(#4#tLg4KW9w4dblXQ-hm$^NeP%JPKoB_HR9-(T#cX4q?^k6fie zHGQZ9^u2(Wl*P2!eFD3X%V7q7k0U05-KytljVxG82f(iQ?>4)~`M*-+u(+HCYcHW9(2#eE@n-`5A3Sp zd^_>Ghgny%i#&l`C?)2@JA+X-UpS|HT-Zs0XEpKu5 zev{?zaYWl^%%csP-L3d5Ib)_XGz9CpS&aT%<`pPD;VqWI0h|k^SP6|k5vrE*)gN9tQ_g%^lHH`O~ z-Nz9grU7=ZvG3B)4>8+lcJbSI^OhzyyA-!(@akJOyJZ18c*jPYUAe3Q9Q9-|C&0ez znj?tox9!T!upY+5`ND1P+w5``i{fO3hnx5vlq0O#M zi(8y(fX(jFQ|5eP3&lkIEAMZP*6iZ# z4Di38*_AKa-8k3KW|ufm3fkJnW;Z`(XG(M0X7{GXBHB6lg8Utvh@9X@aYJ^>-@%Eb z$FGv#Z#Fx>i!bTQ9-Cc)Ven-gw%P3fyL-oNc8$R9j~O<*-TA)KSm|yE6}J7`dO= z`)=+`4>P}J7rZ>gym>l|vtUmZ?BLDE8r$q%-JZdnZrbb$UfjVYHyo6|gA+BY7fy8BX4e($rew0&{RVa|s_*ieg>`k(h~NoHY<8YOZ@5*{N`&9R zi2}`U@%Mo?yRJ`|PnWmZQJj?=mE{Z##(K^h){pz9wAtMk*||5qQ>kZ_(*EX4&F=H8 z0RP*XUH1yzjags^kE@8xpMuh8b`-ZW6+C6Ln^bENjT~gNYcR==R(`PAd7ijRv8wvW z-!O_fmtK;`PMh6iu$zCtW_JwiKJT&Fb!yq{ zR+S2*ayj(;XLd;bQ5N6g_hVakpkR zyK`U{a?NJ93GCh`ve}gbyGdPbcJ;w7ZkpQ$e#0m_J$=I+TiWd6G`qzCgKc)P9y2$n zXtSFdYbCeHX0xmLxgU>8WwSd_E<0yWY_sz&>~DHs{U(3IC~6D{@P7(+_zk1D?%myR zYIb9PO+m9-+xu>`M`vn&(qS4y$?2c~>F(03@ z_uZQA-ke3Vt8jk?7r1V-`*wK;Ph4xWOPMo(-`=;`HOd{tL5;e~-=7L+yf0iV&}R1x z>~?)0rq0YFV3%UzE-(E4R6O&F;A@#}c59xz;dE_mcA-sf@t~nLyMqsztx8+u?@vW| zjFr4J`x*KBQ*rP^KOU6&vHbn1cw9O=pU~`v*ZjYqJ~Y<0K=Q&F+3v51Oahz1m&F*sj^#_46D~}?IN0I0!@}(8&Al4h z`_A{l3^uOW?DAdN!CifAcA0Vo@T_}_!9W;eJ* zc5a-+-gl$3`kRrO-P4+7C}FDi>N`og52LB@`+L+L_nP)g*U$=bV# z2H?yo{O%^53!O|cu>P$zuc=Yf>NE@cH~;N08gVwn7>2g3^5Qp%S92I|&^8#lc|=;X z4dxye8Ag=my;&7;EA;p^4JciW%cE_bskf+V{>i)=Z6C%vLf7tWWc=P=Zv{TRy9>mJX=`s_K-lkVMr$Kj}d_91cw`y%)%bdnp#y|Tc+k_&ZyOVZRFJwJ*+ zqV46K@wwLhP=1X*8$NEr&w2#&5!4SX;lmBzUFGB$L%Ap0dF8}Id>L)e4?D{TYA@$+ z7;~{*kI-%a*FoD2S3Yu7*L*w&ZFki8&fT8vG+Ur;`biG!%*r_a6ELqyb0YcD^XZ2C z4)dh{XTDG@9UVd(a_$e}cvaQ!l7vT=OWYyJ0@{JLc^>cOhCBCC6~uGrs0Dm={YA=+ zI8V>tnS0|m6~)oEP3d&pVDx8l;<{tQcbSXmJN}Ifd@ES7%m30CZ4zE*Lq`BvHzWlCSGh;wZQl?lGa@U@DG4VzH*UBS}VD&Be|qRA_j zuT`XcF~oS-E=u}Z#n}!m{Ljq<57Zw*d&~x9zDr-LI3@D(lsqBQ*D79o?ag7CpGaS; z*wS<{k9ZUyeXU}-*M7b?aSy}SDpFm)$T^2DVE9_avxGr>u5CAluT^yP`NUN-Wo7tU zMVF7?c}D7WCVZ{p)>4PnZo#ob@U@Cbfsx#H>=XmOR*|S9o@tY$l)hGR>;7|2QnI!5 zwTg?+uJGsYv!t(8TpM$UyJSU96kOilT)`85KSS`fiXsVy^B%`Tg0EF%k1Ec+Q+$xV zR&j|hm9zE= ziXBZR)5B%Aq_0)n-LiqURXHkstzvnZW0a)pdV;T2gv_~3D^^Y<_*%uQ{BLO8s^18{ zR`K9m7`><$`oGw_^Kh!7_hI-VMVg2bNwT+4Au>DbHqRAhC{2ox44E^YiY6L0msISX z=6R5uwVI?z8fel?6DbNshG*@b@AtZX@B9DzT<;&xU%BL*J*;!qUc=|UZxMB^uv1eC zDvT{f`t-H?7fHdi`fsJwwL;h4zi99GS_yTn;9=Q<_$3yCYlS8K-Xf#$m4a)9B^7s( zZ^I$MwSr~IY4iw}3a%BlrEf(!_i8Y8t)Tlm03Ch)1yk1wMlXk8cXuoEu+%73XT`SxOI4Rk@xkqrVkQ>Y3s{6kL*9tlDQ8;XHgWy`>!o59MMWI@7 zt#GUH5=L(>Vd`4p75@M)8o3u!*9uCS4S4#`NL)c*%l-I;tv_mG>RKV=P!B$N@05hP zR*>wKB9|=3mQvRWg(Lc~&fe7`>RO?%y#v2D87{b1m|5}#2kx6IxK`*VU5gh6ZWUZB z45==~uOz1h*9u$bAI3$dbp4!uPe(bd#N+5aqOKKmOUH9k0ssB48;t6w0qSsM^_t*~m*H#FYc15wusd0w4Jrn^@}T`T;N zlY;EEt|IDMVM??VeDbU=718@VtzS19ru;xcT`Qda-hveQse)^TyWMZm!Ju@(*ucBq zd#HHPLBX{`->9?bYRWaiwZaMQTy*@%6HHwz;BwF#~jDw@Las*VQ1wZa$k-FTq! zL&3Ge)twjdJ>x5wx>nd1TZMa1@59u!0&h@{HN-KPx>o3Q|AoCzOc3_z{`Kt-(=JJ< zYlSB}q=?$BfKuvO;ks8J-a0QqL|rQk&HRmZ{Ra!K6{hEY#h3s33$7LBsy)SO*Eb8U z6==7OO=h1GTq`j53h<5L<$`MknZ8wcMDJ@vT`N3Hw8rE3AA)NIyK!$M#PP4-TH&P3 zK*RQ2TM-#f$GaXUa3d!lguO!e{*JDh zzxEeV*9t1BQs7>Au9Uh~C=BjKispAD)U|@op;olyy^-Krp}p-L(*K?;*g1G-REZ2; z9S~eAXvCjGp(Z7QYXy(;?I?fcV@zEu>@!}B^3*RMq{;wZGHrCo5XaC7Yr(VhHW z!L>s0wz1dj=$yKpDndw(Rj zR#+{%faBK`W9nKVz~(+~bRO?@r5oQjlt`#+ zh0!#AV%CM6QtDda&4xbQvSx{hx>hh9{0DokkP}=hl!r88c8-tWTH%S|Gi;!-NpP*; zx`^QDA14IY3h^c!-u|UbaINsTI1_LG{R&an3NnU(r+)b^xK;?P{wN82+9kMFsBs%9 z8Rsbl)U|@oU{%pf8!4c!6%4CCixwX25?m_``f7{vHhmXdE7VWRLW;$&1lI~49vsT; zcSmropty@5hg~NSb*-S``wXo-w-Hg-3UhBYqS&IDh`LtrnEnT8vIB*^LKu6p5B)I@ z6;am;j%(=t`{(VY)U`tQt!`B1k0sQ#g4Oh&=!)88!L`E2ukX>w_(Z|A!rZ|7NHQx= zaILWJ!FlxROR?ZuAtY=kit>MiscQvMEAiY^KBACW`(Q9A5gOyZS z(mg7AUGlT#MWxfEfVx)r-St* z;96nf9E?u09 zTHz{1={`^E^z4Zjw3ft;Fpt$x}!L@?xrYaP1cc0)| z!DPZkq`v=(;98-5z-}~t;zLYbD=Z9Lit4A)H3fQII|pl`=F&F7wZgBaLeWjRUct2j zckr-vDE(ej*9way8zt$aS8%P6qpgCsT6YMp723=LanhmBf@_86F}XN@*Av0D!oJM2 zxQDqWxK`*_eh*&@JBX=kg&vo8IB{qirmhvR6Sb_Z#+bTRcr&FNZ{KlWLR~B9r%I7s zsdr1MYX$2ceK@C|tBAT*xT(~Mw_KDGTq}%_{e}kTH!mp4*S1*iKuIZ6T6-9*Tv0(YlSqucFBw8PQkUp;`*tQ{j3yF z*9yZ-+HF$iO96GQP^bM|WR&(-aIG*u&JyjEZ4q26ocg#DjVyU1xK`Nhbr?;EyDPX> zh#W0Jnf|8{b*=D7tri6g*ovrY1*?%?QGV+jL|rR5+WbZb%ZCa+2ZosUp-EknxK{XauO9iuMhmVL@~%8UwpM!u*9s#u zE};qTmj%}f-wXDjvcC^7b*=EVH3E%T+<>WTg(0=$k&{N7;96n8!4sk%S9%233XP^i zZ0^(NHFd2p|4EkQYQH|gwZd69MZCYNLvXDSmOl?SrhO4yD;?)=#rx0K2(A@cw9eo= zF{OfQh0b+%@#>C4*pl|cOWfY#{W)SxT`TO_)`Hc}m|^N#A?E&H+~-syp{^BLqohc6 z%coN6S|NNWeTFQz6j9d-T3b8u)q|ZP>RRE&18Tkk+yvJO`xm^#mCSmnFHcxIDL$7u`beO7RPC_3EmS8%Ox@`5SqU)mzLR%o7^ffihT`>(yK9vnooj@}bo zE1;*>5WaKL6{f$fMz+Ux3$7I= zJh_adJ1z>Y6I-pN*t*|q42);S@x8Pc#PHGOW_x&okR#;`a1>dZ!6F;;H_<^IttuS@1pc?cSukWan2>rv`Kq=x@ zEG?m~6?SV&k&GIB5p}JwMZOC^dfY0at`($rHsg$APJ(NNsbO_^bJAMDwZemCxABR| zM+DajM%Bl#=7bx9YlSh{*|^}^b3|P$ENY*IqaHK~t`(LcX}rJvkKkHi?#5XXwI6+g zYlTleS8cx1`4@Gqa5eI-Xp~#G;9B8T%M?@`)hf7Fxc4~)#hrQguOC)%&qo95Dg@UG zHCsxMj}pz7NB{oRlgDU<_jW{GE7%2mM&Ati_l;t_KHwF6Pt3MBCp%Dx+nsB4A$ne9k%irT+%T~T;1Iy!Wph`Lr7N8=|> z&Rb$hT`SxP?nM*d?UGQ}3S}wnC}5bH;98+&;|^ zh4CkQk=O6d66#u^OtAy4wHPV5R;XU|8LhKgB)C?X>ih()`IsxXR_MM{f;N3RE4Wse z{wE*V(%3`lS|MC174>a?hpB6YP4!cdB&k(!t>7A7A-XuNTX3zgvx(R^XGjt1TA@G()xli*rG%_SSZmVNPWzHF9u43FM=LvXF|x&9Vb zICun8*9wV~>hSOrYcX}Luy0>8PTu5%scVJIVO_Xc>X$^Ar>D?3Q`a3v66#uM?f@ww zTGeAiT`T=;{KcPVzZ6l|3OgSCz%?ta1lJ1dVrj0_z<-t)iq-Gp1Eq%r*9s@vPT{+8 z62Y~?&&^wK?Xp@#T`SZy&Bm){eHC0Q{JJ;KN3o?SY~arrO7wL*FHa%8;jpPh#7$M>S|K@SAi3U0?PqY8~nh`Lr- z?p=+X4EG@FTA`9_Kvu2G5OuAv%e@U%3$2SGn3Xjj<#1~|b zV(MDq>X?_fX~B9-T`PD$p|OX^4O7<&iMu+n{K+nfu>RJpB1PIif@Cm#?Tt_=Qs4g8 zhPqbZ%jy1<__2t(Rv5OS1Bgio!$E99Vn0iO*e*|+*|s+d0a5A{i+O8($cE9f}t^$fi6OC#2bqkcnq6W)35 zDfWn=W1-N~_{Q#1EJuI8Evgc$Rpnu+1bPnR8gTRG2<#U@$Ilbn@YZeP@EW?FZ*JLx zwJ)BP(A*TDN@FK`OoB^Uy1y{Ns1MJY7%N)7jP^Mze&d`31@x4z!{?p&ik-jvp`r8| zrG`DlFN-!KX?o5Jo=Whvt*8Dy3tk^>!FxSSP-fD6IJoL9mK~6eXg(9Tv!fEfSf7Vz zJ`*_TcoCOAzKrbCXq)Em#h))$A)3zwaT{@4TuRXH+g@o(v z67rdVc9^O}c90a%d?w&-)@8GhuG@xW(DO{G5`E15E95f)x$Md4(4|%(p9$RFvm8Z! z{UGEs0qM?ND4A3X`Ap!*!1KsU_NtK21b#2Lhm=JJ5zS`;>*U^`w!W2!<}(2e)9=W! z2ZVekaCT`YG8ot{Dxp97rS+j@W-~-Ip9v_rOF{9wEv3Hn{Cn%WkxIfji6*@+en1;4 zml}s@J`;GT^9i;73c`XD-dp|zbvSLqe)Jp;oRpv=%BL{RX97$yhb}kV#&c;~U(sBL zCe3+?X+9I^(4B_H#x!A?&jgYT<6E{)%z*K+Ac z2GJFlh>naJ!&b!5S_aS8N~Zjo%^p3LO!T4`(U5tt9#0i_Lc_wIrHGn{inS8YfWhV=>pfY9`lNhR&e!zA!Mpn@bdk<@DhKS&^ z5@Y4D{FeA+kQp9=Z~nN;#k57i;R{!=c&#?qcYPsDy7>poD(7jJ>3BlFL^X0t?jV!0 zekzPwWlCz=<=LV0M}uycC)se;j^zV7P+xc;soS5x?jC;$U5<$+ljh{I*DnU5f}6=C zN~Va-9Qi>M9i2h8N?l@SeK$1_YHHY*UuWkUjYI59L< z{YD3q0fsAC)#Q;NQJ+DK6SJfjHOcZS=-!X zvT0B-HeR!yy*)}y;_XjL9*~9XnLT1M>+=#(!ccuSSt*so|8hZT@*kKl`(ubQ977ui z`ZGs@g9u~Pgv#3=6}VpXA`!OA5WaE^*Yw4bOzky<$##FafCNo))yWn73 z8aNr{d#8bq)dN1%F%SK@8wbdNxBJAtKlkw37zBOx-xcWD#j<0(V_)g$`9KmXtR@P9u8|Ns092=#D2 zHr%7%Q``U65&QqFUYPNeW}!bILha1|6ZOK*4jcb}q+Zwoo9*;C|L5wvDdbF~b&URZ zZQTF1op4_Xk~{K0>Z9Qtf4BeENBdV#jn?!LYWw`FvzGop>aYFJdS1f+3xDUMt-=4# zI&S~7z5ZYAh~|w+`&SQ+{=HDo?q8ia`aU4M53RGt(Dw)7cx5ND8Tu~>$J-QI$^5s* z(9SMtp(ZQ{#}n$)(f0%4c(lITzvst)ulGN{NA$Y>`}gSgR?q*|vlD9mvj2I1q2}-Z zqmJHx&IjmqvHv;Ge|7ihafI{#SC4PgkPH9nLkYDf|8u>Nd2KlJpZfs+sf{b#pMUk^ z{&U~{)s_3t{rp#NPPlI2c=Wpdd;kB{rxWgza6F-IU6h6vE~!p~#(`tGnC!pTlzPQ< z&oi5QxNHP+_f3b9{cdq*7wj~6H>A!@aCh8 z!1|FT1kEt#<;S?gc1;bK`PH7ES-cPe-~U0@>hAn-SPl)fXA#=w$wzjjfLV_`xOG%Wj_$84neceo_96f_9c9E{TrAPV&qZ@jSe*myXxBy<*1vy^2?5MiI}f zf$aHnQsliS%~i8egAIN%jtraZLU!dCvO9m;5c`rz1Zp6tagW#m>U2U_shj6!C9K1DoT2OOA7iX+YgUfxRIIpd;I>?}#4Q1QOxwAMg|ASNbSNB%QQ}Xg4hPO>7Q89c;b)#PfUDZp zP@QkaU;E$+i_VON-4XWuq+1K1!@V0lu5;s~wnjs(_#)c7#gm`CD+PMvz0rzA?)(-y z&X?<&CyHF>z{^x*z=8HVk_u}Je({hMuxU~{zO_@A|2%6MbZxnZCtg(Mt$Sy~>6(E= zeR~)8tjZ1!+D{X$txN@dfkV=`xPAiY9kw z4q%r`_2Qe(3rJti7goulNY)Mq=?wC=5@1(;^kqaZjCdGBST5@ zyO-Gdx(8diDS;^6-ikfPd9q`R(}`rU9M(JM!d`0^ld}W2*~~6Rth{d;`Fdp%H8xY& z2a;G)R#1Qr9oA$U9D~UH<4s7J&R=YErV~RL1=1lOn0{WS*+e!rCWO!H(N0C?mI1~cId}u@x%TJmy83u;i!08rK ze#=o8_-#23%A4)@$h&k7T-=As_qg$^Uq``x{bKYs+mn|!N&(;BvytOocityc4E@%p ziAuU1_*I=5pf~o4WNMQIFIu|-_7^2!jRZY@-KYpCYAeGgcU1V8fdMdIZvfdlxQB}z zOD^iav&up+7AOr|esa`c)>lZS}<|`hI^i@yEsMBIH-}Df(ar89YU7bRF(KDts=RB7A9!++Pm1S$U zcHv4`NNU%rv%U2iM6%kAyy~9J{_wRTx3dk2oSqH)t#l^IpRGu?jCW?!wug{Vx^B36 zp9g!lH=cZ7xdV4vc(T(H(n(XxFubI{D@(e?q|;N|CejVqkw??Wp*9BH8f(nf2E-B9 z=6vM6ZycMf7ffy#eL*611=jT93^MPC3N-is$jm-(MzUv_fC6)d(cCqfEUos0NzcNW zieas|=*1$Ss7CwO;-h%Z%@|rwY*9h%R15s=aVk_ERNyuhd@C(#5JSeG)!fLte?%wL zGC;nvg!}w68?6jZg!gJKTx@hL(mEdoQ%#5S1D%J!taM)(T*L6KEfe9zF%e9)H|2|C zoWZ9=3%DpdzWwezSiQX;xX*Os(^xtOe|Zh{uJ+`m?fxk!(9A-k$Sl<1mP8Vqc4(j2 z_FCjC&Y-y*oEVLF1`>2zOd#O^vu3>$9yukItUOS|Ja~8-?>(@bJpLlXI;j4}b!LHt zq^q%dL1W18Q|{!t!DRN{P)m|kZ$xmeHGA)XH_2{SBFYjc_WZ>qWQgnsygkN)#o_Tp z?6?P4P4{Fg4AV(v@F-k4%ayI_6O&^GTGpXYfc^A4jr3@0pvMiytZsW8*=x8Tjmgzw zRR%2~YcDmR9cVDSyw;0cP*jGtou3)?(H2CvehSQ&KhKyk>ST3+2h6Kl&iqbo!&jOE z!QHx9n^QfBf2hSkbyMfz&K|%O38~PuNR}(LRFP!Vh#}WJgY&QdDzciD0e+grT-wBS z=wo9dEZ@@19eDT%rDZLJq7lRRiw6}TA=eK|>a}@=&H7;T714d0seBSRfv2H1RQ<5! zKhf2Kkx{ z%xb6M62E6+;(B-=b7(NaA)8W3TffK53Dpxg(KUwDpO}WRNnHuSQ zA`3iXFPri#*++Oq~3jSk=eD#Bt|G9O~r3K6?~L`UdCW6N_jc z{wa-2`#ct_9Cl@`Xj?CoJ$P-Lzb%{OK%e6?RgiI!30t!Ey*dsZ01gO?YXnU}|qbCK@g^E{D>`}`Xh^(=(BTROGZ z+&P15mM@153FU|C&bi=Hl~fqLxVP|j+f<3nb-E@pc?Eaj%1e>Sh79-?e2F`_EE7$S zNP@-zP23aX2grS9IM}of;f>nm;Rx>!*M5xW>&NNAfXTM7?wJX1GSm^a9$=s@+Lk|Y zGXN}p_lH-duDs{b2ne^ig-$H>fU?WcsNKkeU#}*HGu9_WKdqej5m91j+r3_5 z_}Yqp@-7*S_b$Ml!zS^JR}|dpcMWU(Qsry<)Ai8F{fLN>=C?m~1``J@^4k3oSL#0r z5HSzOtrl!BdNEN6QDtX3j3yyN zrjf-N6WQ1VGqQ4<3HdV5ij4}ML7pp*Bx&Cr*+<`k$o8>cvC~Ko_U6<$Qd)ZuN5*)v zKD*P1?=@BsLe{sLdf>R zuaVxGp{$h5Eb`#zaA?f^#$3N?MgER7gvYs87+dGDWUr|k1injSruzNG)8rOHY_~LX zH0A=Ha4Q4U+%g}WT2UYrd^U0OUUngEXz?EsB3;m1C=hw+1TVDUHL&*3>R zf5IBGNhJ#A|O9!;iQ)Npqq# zf5Tv~wlo~IQS^y1gy?Ept8GcKz3*T-5BAxK=Cd|{Z zhf8Pu5|blWb}&J;2KcHdjijHx&lFxP#J9G@l0p|LcJi@rxJ){TWX&1H;uE9DF6-$; z?vOqkuWCw`w@xMI#g=TO%XCt>e-sgCIkKN*gUG}K-*9w;JL|C{mXz-;#Qicn*$js? zBI{*<70un)QhLn!$@!(reC*hxmFZ-H>Hws!X37pYpFkE=Z9zL@7}oz#DCv-YiM|#M zW8Fskkl=t}uvg^=!wj?`%S$E$XIa8*ruQJ1-V39!Rm{ioUR*R}0VG<>GZVC~;GE&n zFyN)(c>NoGc+2z@C>imoFz-j4_QMc?t&fA#R+ieFQS4{xPV&K(EW`nDp9PndZ zd5^Kn;LwH&^vS`KztWrpf7HZ?U+=;D+{gg6;(H<`S!e$E5ixA8^p%_*V#5d0&!Cg@ z4D4SznQtnMhF`fCu(Ec4Xa^v(9UZW)sLr91I{=(VIx1;6>3FPKbC+&;phM>(G(#hE+lbQDxPNlZ= zJNBh&8?#z|0-l;n$4M>sn1MY9@ic=tBBjyGtTUz-`g0J`^&H9GRT)XH2hAWhH}u%H zQzj&8ju|Wi41@UJU%d2Gj4$Yl_t={+LPN>lcaD3PeiY(z5ySvDgnj6_5|MF;Kivk+FzUk6hA}xcCAi<5DDXd) zJ${G#0&M&-8T4MiC>$=mL1Gvwh7$`zxVY34qF1BEu=K@A&VyZ!d|s^py&3h~qrh9} z-k}JXxn>Z5vb#UbCA5zoK8_!Dm;na`x@NI{3ZLp~3&;EE!Inpee}2v%#(t28&`K9x z#V;IoYCS-^CwcNHDhXugXQEAKJowyA8K55XLev-L%&XFj-qVhlOB^^GegJ*8=w5fh z^Ro?jCUQBPet8COR2swY`?V0REBwI|Z^`o4XS>7PM`OsDfiJlHWFxp2XGvtD3b@?W zN-*`iH{m*Fa1HYB(TtxOXQSgpwB9Zd8XUpvA-j4TokzA@7`{H&Y@w8o!Y}|F&X!oUL+T+Ja^huH3>f%S% zD-8xK{WfNAHX`J=KJ3XNOc@?e=HxknqSiX5p<0?K51j{lE~qdX>oGPu5D9xWNye{e zT!ODACPQ9wRpIETyCobQ8%;P7$jOb#6ZzVS!F|Ya?s#Mvwcg3_>G(U&w3s02z({x! zAkW+T%D^r>7ZgTo@|F{{fpvBQquWOO5?VfGhFBj&BE&x~@PnMS3NRwxg)hlo3Xd*6 zLXJwFy#KdE_%d!C8u-M6-|w3Ni$z~W(G|}8y2oO0+pH?NYa`-gVpBog(H5`uG2}y3 zW8j(2NqkyGgWvc$5RT{4v1S|1rjhLdlN{8^y3=*s=|@wbN6&)v)8)AX%F3|ti5I!v z;LDlrYe1idFCpFu7YiGu_tQK`aYQ{qN&C^2G3dwNG*X|X#mpQ&$@&g$>rR7>j6%XF zY)Hq->!WWom*V!|#X<2TbzCQN&F}-Ba(oH#ouJIRcPWwhecq%&PM0lzWkjr0EXn0F z=BzGpCvQE+kj;7ytjIo)G=J~Fts-}JVZm~eb(!XdrfY8U!We&p6V{M%XS2%0q zlC)}j_E1U&x!w3i^mLLrEANs-6f(2W8^Z~#ST&s7vZzKc`;^$&x&Gu!*dVAl-@#0H z0;FQC9yHqAWSk5b61~h3(pxq#1?l}s@Zhz+c81@i%b{Y)Lwb zGwEKc_tQn-F{TwukC)>$B%ZMP^k^bG=M86KXaYU8W~Ayz5%(fr1@f=XAfl4FT&Wh# z(J?ug$VuNQEU3(<{bC%+*7`ZVC4xcur_#vL5Oro-q?XNNI@f(0vVnPBGYoqsrjs)z zH<+>`JFr4$Jej$-gE^G{20vOKLcE5KU~h#fl6&W7k~_K+SdEp2!%BXrqw@56~^K_v=TQD$E)olSOKmxJZTolM&}JEAp6 z7q-fjF_DK^QfKS{2k&iU)-nUgvOxjh(Wu2#(Aw{*>Je~qt)h1N%mkc~vjPhIE*1`K zyCiwmodNyieYsQH(?qUxjl*sq$2}c12mLijf&PJY+-2`#)bD8&to=KHkNMn(zL!uB zK1PE#w;cx?3tiy7$dJzrw1LbylVQq85#JT(123Npg~27xyve6f(0%tD{h;6FHE$B& z^Zw1~(r{0H#_M!2>ybf;Vi$f7UCTL@cdqn61meAP(je)(5msz8;`c9#1*w#dAhS#Ee56z? zly@IN{8~@mw>1^QcA27Q$!`4YFJjm?@|8{16FXkDe+K+Y>6L^@O!*SSL>M2s5x;O@ z`OP6=@aW1@TybtV&$GTTxnc-;lhw+NF%ZGv$dGaM4kYF96xM5|ElKIn zCC_USn|9rwOs$kB!yme^N5jI&psFhT+Q5^&nVLjof3L=ePI#~`TQZ1d>vPHLCC;od z7LzHf%|#uY4I8MCO3GHbqPqzOtoyv>gqWR0W}WJ+)BA;_Y1$v;aZ;AmnMwQq7h^!B z^EtE9&xjc8w1jUu1zOG@e-3(|wJu$SquO9c}AZY2X!B&W(=EL)?uxP`dM%oBZn|$|?zl_0v^& zt*gr5yTA*cOX=~-OO3&Iw>cb&w&0_>J>bhJH5kD=@G~72!6*2IO48hU-MKL^sltifZnj3HWLJa(u!J+~$d*0421A2^Yux%J7TAu z_9O4&70AOR7dB+yQqmIj2nQ*9vdx`|Bu=sxud4Q74+dnAm^Ys#syCh4g2!T_yI56} zFA}kPB2tMjwndj+4A~6>V`x3>lQb{q81~A;K(hT)8a$!j57(BQy4GL~+ zabXEHC5`lZUA1i^XCI=9v~|*<@Ahr(*y%mUARrzNx^!|KK_Aep1503`xiUX@+z7y8 zZx}IFmv0?01>)aX!1@Yv-s!PB44*m%22XL|KgAjvvcR)o>>mVBTl2^TRr(B zHmPth&k<$(b>my^&^@dMeUW9kJ+GOP0Y$^!N(?8O)4<6jSotIipBgiPXZnW&x1$<2 z)hqGa9Q;9k^B^Kl>EK?~0+eLxkz@8ZxjJU<&%lVt{d8@l^12{(lM^pTxPk~7Rl^|bZ&E{i17Mrb?4`LEx-DWepTEuEp zq>|D$3*<4%i1j%eL)*Jo}!JW}yYxIV>J=KJ)e`p4J ze~XxN87k!V!x^T zepd{^a*`Ezk2B|oo^XS-vl@_7YR}6DECdUaE;L%koez~-PW|6`Bt`ctyI!V1mz^gv zv~=gA&xrw6xr%OBI`HbJGobf;wWRcgIj@70U`)?Syj510zg!&-{n{(>%I*=ottYif zKjet}bsUrPWe)x^K80kStYe~g7vt=^ zQKVgQAZt8``s-6PFSwot8@_NHNy~O23#S{hhC6MD>A1%s2&oIqyG-;Cc4^<;;9N+-+@X&e&g!g~J@lR?jmZO+d{>@e*#a?D~1 z%A|e8M88;)Ajc!OzOn54V~dGwPcy1FkY~FqrjZ~=RoHmx9rHAID!H3z3LSTjGb=}r zB2SJ?hv{<`F|p1~`2B()$T7dKJ;$g3w?2%8<4Ly*oZn2uGZ&>y7DylPCC>C5N?G9jb}u8^Xq3B<{smkU||vk&y3g*V;!#A(s+==~)$d9x?)6;JoDx@V#7@$USr zJz{8>79t8g?!ddg&VZ7$*Ckt5S@23WD`2W;3eIVwZM|n1#7w)3L0N_W=raeNyA32K z7yadydfCIP<2odDV>#ERK7r;su_MhFws2>U4Ft{6bI7mE3EUH%duU1cG9oh8Et~~u zC~eFNlG=Mzd(M(F(Yps3q*`GHlfG!7WJSK1h* z*C5NDJJpS+6fGdR6UMOPACIMOk&b&(4cHi0Yw~NI0mwoEOQ z3`Vc;)bk!};OqplcTz6?sprW?bLljf{U97y;lg_U5fj5HsW!|<#C}XnBVBv+P;1c? zHsMb!X}3R&#`S8l20MbtucSs)7chv$jnm2U(vdJ>`mNtrotzNkWOBa~n8-vo|OZqSlPp>R}*d&I9`I(&d z^nNJpS32l#D&@W;Z$d$GiQrS!%8kU&P?cU7s5KAgl@Q&peC`9g16e-e`6TFhY6HhF zner`OF7WlpI8d*!<0mhp@gC_kuY}l*Ke;;!R&BqEtk=`FmQR6UlDTNYDR*8eRSZ)D zSBoB~Ir8ChwDQ@DbCOq#C2xIc1;`$c#oASRyw`#V;1A!%1NBGpS@Q#6Hwk&y|UBUIs(S@~VZHZlWE;rs^9%2T~CT}iJ=1x`IM<$2EiSjDD!Z{ySA(KN% z#G1>~u2@kcnwy_Nqzv5{Ni9f57K_O?*@KLEo;wa`Ng;-do-(H#&*3Bb%gOeO{aMz% z6HnN`kYusy?0N?cGF-}?j3}DShBjN0q)tPk*J;f@UObaDy;LMk($4I3yAaY)_7<1q zc(A5-;)!e9PE71PS*Zo-Br{bB-_dkszxIepca^k_P86_5%c!FnJs$ao8na=$;>gyF z188gKI5saem{fiHgjTOnVD*Q1k=^<#aOlBD#%zi?`ToclYV^)BN=S_;czZ&4KqPa_ z{U@HcW)alR{;1ubKZfP9V*n>W!Pl2o_|%0|NLeY*T_4n6((+miA(E9`(z~CctSK2_ zT6&e+d~O5UwJi~@+5g}|jB3!pzhQ9v(J=n|;lZ%wt1n&SW_Y*x6JeSm0*60S`N1Qc z!O~zn>~*o@|16&eox0MHW$DHjyp05ZYYDOud-7lQB?E~KLd!n5^P)L)eO)?Nv?#}s zpKC<>^G^kmTX!sZXT4-FP+x|(9@FP*H6!79+jZPvGm0+_o(oKq3^}MT#jBJ$!k#K^ zvh?PC?nH|oEJ^@cS86BM(KiT`y8Ouf*Ct$b)I-EQSxR0u1Qc#LwFbQ$OXsERR&CC= zUep_&LDmL2FdAdEB(7CrqF|KAEU&f4)iYDc&y!CWkFBThj%UkB{z@4Z*SF(cIe}!E zmKwYFnmT!6;6V=5OkyK)EXbyaDMZ@On%(K>O%mcqkjV#}SeGSBNQHAfUbxtUjhPZp zR-NBVa~XKDDI?N}+$=Th8tcmT(Y2YE=U!O`{Q)*{csfxmP(zm5ChStfcoISOqOC1j zZ1;jC#3-;H%{(=jRhi;V#%vt{A49${IL(4QOq~Lco}Fh>Z>SS*eGeddag5#Fc06W# zASirk)s6~2g_GYd2R8GC4q9yo&96>YeA z-IgaYb0MQv2Ao=4`BEklN?%<^W^tbU0R3cGJ#-n8SN7nWjm1!1e^^x6<;b7+6@%Z# z?Go#7D}KwKWN6wSglDgs$ZvlY376a@xXMG7&kv((Gv?Cd&XRt-)E_6XnK7PBjIQQ> z&zuN*EfBe?w1*SZ&*Ag0zU1t8OK$M+8Wb$Ol&o`!FLV@dK>PM2lGb&Z+RNO2ipoqf z$dnurvrW>pL+ca>(3#s0*3DT_$6>S*?% zl^R(!%acg@)3!D=C%2y%6UB>GY=)*6>943l#+f*=KeB?!hw@Lj+SG%6xi^l8mL9<8 zLa9Te-`^JH@%Z<3SJt9eOw9P!Yb}|!Y~$>7(lKxZy7tzDjk^_3Tn6ky{p-iGd7=<9 zy7n!a|7ZyNW!6j*(V_@Tq?(vGo zfM;2c>5huFpR&7J^e=Wi)kFrh%71cC{LQ#H+O-zcg7KKoyXkn;z^+1 zW<$ok*~bmC9tt5ZeaN*>H08kYXK0o|81XA#TR3p$CNy>^bzP;A+RN`qp)0@BNzoQ_ z=8RTl>5C?60#58=JQtbZ!-LYu9p?wk6vZRBMK_l84CzNL(03dewwN4KP-Q!cRmuAJ zX=I4WL{_%Wl+;hAdsxa=?17HyMEm4O^1RHE-Fh&HV2?&zC+oq^>5V1PnuoD+BHh=Z z&*j`>dU$|>8=FL**YD$2l!gtqWBm`NlNB}!NHc#bTQDnuM0w_-laIAon^B?UBdsfK z*E*Dqj-5q@c@2jr+nbpZ#+snh2C#WyF|+&XSaR&8D_qXcV5$ncao@28@Mg9wv--tF zyha=iAAf()Dz5j&o42MwdTVpx?6~<7okL<67`L3eXjLW(uBP!LS?9Pr;c4jV=oRoG z{WF(6;~qMPo)w4E_{I1ztakVc;8S2EM56=1ddv1CYLA2V`!6ISyHA{)9!vSkLNh~w_* zWanIcRx@WRNyspz>*sX8vT7O`X{SmK`Z=--FD)ikkD77jV|TW8ek_ToLZ6)GA|A)1#oMX%`P{&n z@MUPCZUkHuDex0U3;;Ei0MI%=j<-0?Lf-@j_&&mzFCJzG%^JF3s0)0y&up0fK@Q&c zy6|o)EZ=&-rj{sMRuD1=ZSDOM; zFM8s^G6uX;KjO)lKx=KgrNfbIOgi~(JCV5oZ0U(^ zF?lg`8#8q_gA-1tk*hs-ne`j<@&52Q(xBJFT)?TW{6bzgA7n^jx35#Qd-LSJUR=4V)hg3Dpj&1!BTMXXh|&kY->1mPo2v#QFOg^hSgia@}|dz3eVdIs@umW z$O4~kZu|Leu{oq~m^?nI|Mn_gk)|TfVKPsNecSi6873@pPmnpfJlj4u`;>5hJ5;VJ zmUl;Rpp_i$&{H0dF1O>KMo#i(-)3?~$J#r(rAS$GW>vX&li1PByQ{oCKd=0@3w7-L z!E)yCYa*Z`)+@cn$qt)l2^H6R$1l`RK3;od8neKA$LtGX@=nfb=BckdckF63NqVL? zQx8&V?udvSDHGQmP#c5G>{#v{AZtASqHb5S-ZA%fE9qIIjOJhd9`*y*mKReSX+76$ z+y2?AnEV#rK^yt3!}in7o{5}02560H?%Otf(`vD(*BEVhNQH_oJW7eU%9!gGb#@Aj zafrKyande_B~IF{GU~$j$=Zu9=bbJmtyKlB#%SXYe|Ku<|3cZ8AE0$jF7Ev4S269x zv-aBYHC3FiKdr3|v}>ewtl7x<|fm!&3sZl}Vq}sJ^Y7&lVh|o$Iwv zIWBGETsmZu)~t176>z(y^F-9m9JZG-_Xun1?Avpymh-?Xll8?0&Id9>wFYT(ME~`b zoTvRWSSz+JNgQon)Opd)E?VL=tO@4%>{QJ`YIpsr$&?c(offvQsC}&1TvinGocwy` z)IOi+DOW_5bgJ+~Qy;qylP?QjuTbySAT_l01o{2=#cg>-O;-5Y+X?TxDZK9{-#VPGi1*+W-h-3!^|!5fKThHOIB9>j>~{VAnx(~F z82jb_H~xR?IgF6_ud#}wCEgjZSmT2Kj!q6V;wh6Hw9z+P8u9w$CT;O!7bC9QtD9CQ zCASgBuNkU+opDC!*A}`vK?`;2W5gNJ*i*l!sYySc+iI%ze(Eo?9y?thqxC+rLh14A zKK-@!Jzg2{QP;LwV2RS2ejM*62)vtM#10czi060481aZAcf?TJK}KAwXg=8@y^9gI z$X!`FS~NA{)U#5)U0KzLo0aM;TRtja#GkeXN%uOBjPI&*YqYe=T4%&1noO3b=GHXg zop;c`q+!nhKKl<(mENrrjr{jt9WR?!871`N9rI$M+&|ukFYM?o_a6RX#BHjymJVm_ zrGC!SM)hR*>-CK|pM{;g7S_gyEt9jv>i9lJT&>YDk$!Ku5pN6`B&uU?fPQU6^LW#g zw^NO{Ywp_S)2G9Xc(m3)y?#E)i2r;(z1waQe+9r+$XX?YnI} z_4Z4JPnOm4S2phV_mvQt*>{LY{$Bpxh;8e(mG=slmiqaj`Rd9aSq+Rha&U2( zwX(et_p*B~d`6<4k57@Rt3>q5F-E-ONMX@u_!J|KYT7UU@He{mm~}OjSL?~f@t~j` zsz#=U~-qtaL6OZp0_%50+lXlZ?1|WOwOu&RXi{ym9lEF~1y*c+&+}Ij@Yn5%+Iz zD_gqx8nM`&DehGwPe^+kE#g{_FphWc8Y~j)5pORaPB5)KO1$+*PL0ogN!azpdq#11 z&q)8S_?qFWP`9xZUrthqvj-b-$VqFh_MYxWyyB^&cBF&15!bSF*X%C48u9*?zS<=> zTO%%8HBfuJ8UN*tk7zkUv&xD#;M35I^xz6jF}-hXFc+B$Kv zHol3Y(yu+ybF5akiytVk>jz)a%oU2x^th*6U z_qEm1-F%HWWLKstQaR9w@4SgtA6kzv;BQPiKfRyk>9)ir-wN*dj~3#R71paCwY+;-E8Hdy2PbtF`1%j zMdFfeju_F&hq#pMK(L5LPWrXS)+L&DMG==)w@HmJol0Dq$?vS`=d>;qj^7I*E_L6A z--%p8Tnav5t@Vf|F1^7zmrFb1(#Q(#TJKZDrM%Kt8;f;)y&bQzf!gjdrL5#mxDxYVONacL-UTifc5!KDH>CTr=J${WwKW1q3wr=QD=xXI$d+JfE0 zrEuuJp&~BXwei+Qz9uf^dE%;t<{~Z??PjaR)+H{Li^)V^OkA2~5u>*F5SQF{1*`nv zx1RIt<%#CgQN$&eda0geQ~zf!*;NY{8vD|XGfAT7T;h^{ytO>GkGRwUzLdtkbO0VO z?gDY?Tnk^B*Mqo}yK#-UGLfm|yF07<_5@TsjJ0vK&Ib)D#}z zRh4{c1#s(Gn0%=*_OqqO5SMntm*$-%E?w~OmcxD!mug>el~qdCsu@(lvK)ZT(N;QV{x( zd+`Ub~B#C^Oljz?Yx6fMkk0CBiedQ>hfb0742afLYJNwc%4_|qx4RPsanLz22 zNL;$y6#I=!lP|S_2V}D^&44fE7(!fH4_~q#^V;yGt?(roN4~TUzLe(&`BD^oX-y=TNP^w;cDJxYYi+tMt!7T(W>Kon>F@b}Unztw6riELV&;?oGbb^LVhx z%f3{9SE4D5eQEfD)cAbNr8(fzaqi>Z=MBeik&-W!*_5Q#EF~^A+Hb9uj3F+4PIc7U z!z=aN%EOlqvoBege6{ASiA&8L0<|4iiA$fGj?fB}CSUS}FP%C{Tv`cVI@q7Mv%BALL8_z?WQh5tmv)_l3Z3J%?M^3s4GPsmFfLT(veiiA$y7 zONZH)B4abvrwYWSn4B>x7yHtUBf(1dO8wfKTNBO8*q0UzO7$%E7cR}K6fS(aQy+I$ zC5fr?h)dDOt)>3~;?g1b(nj{B(6a6_0)4RlUGIH-WnE9=(m&3D(((XtsStc=3i8v> zk?^Iv+sT(~;Y+VPiA$H^ORMscFTDY7_e+s4l>=_a@{=!JfG@4YK3lyV$6ej!g)_vZ z7bb6c`x|lTY@(~YSc15;$j?^(Za}`YZeOPOh@A9mul*Y>5?T?Lk_HEhV|A&IQ{NIy zM~_e+*S~XWd`afg;6Hq+N0o4uqdRfQ?^KdXn@e2E6=$t2-cMW_4PUy>zO>B2U7K^B ze5p?hU%VedTxtss@ZL*YngZNBEs0CL;Y;VX5|>KAmpYk7_6O%CN4dLFI8t>O7!&BT(XHv*;ie)2_=b3NgZvqxedvePVCK8HQARY zr$?)T>`Qn02dkXyOLbl+nBO0vKCb@ARL>%R;nH@iaN*aRxU_anlDNgbQ~C!d=ZBG-IvfO>OqV0%FBg+J8$F32VcEXqT z*%6oE+Zue^(92Nx()LlrrG4AzpsK-Y)$f|0sHW# zHT%-MgMaVic2@`&_t}?LV$KwaK3LDeHP%|bJ4n7Ho;k{@>`ULup^rO5TuSivm8VR^ zrBY6Ta`+MAk_ot7vmq|!f-gm3Jg2u=9KN){L|l3fU%Iz3&EV3K>yzb<+~iAJ;7jfD zkT11fI9RqgOkCOpUwU_%xKzKfx3v69Txyx@D#sQjE`F* zQ zE~UVi&ZMLneVpg@$y#(_@})qGN3zlH>euF3I9MBYgt*jiS9i_-3~|XudTXPzh)eUY zyJ}^M6PG+X*=o}pkS|T%pQ(;IQy=H@FOI%9Nn`oZGzSK~pdY1W% zFI}++7cbeDB3Gi1TgKz1z1A{kEOF`j8%LSlihQYMd3U*kxs(s%TzmMYeqXcf17*1z z#HD`lrNU*1OFiIAMc9{|;Y(3-iA(q30blx&FIBoZS^6FzUpfX~YRtZr2Xm$(>`QqL zbeEndh)d3$y=Cu*#HFgKu5#~hHv`|VU2Nqn_N9aqnZk~JscpU(vAp>R$O=Du>jBrfd%Zn4LROA~?H^?byoWN@j( zKJuk}@TH!OiA%rWOHC`2FV#$%EVHtROQnEYb!+ma%kZV5hsc*qyRpW5inw&Jski)= zNnDD$<%-`dBwza8*;abi_cgGq1P}NDuhj1)>~pj@){?l?A}m;ptwUTgdnB43qb94L zlfO`Ed}a2f(SP{T&hp`^N)O_aMQoDt#28LL|7Wzdw&xJ}(m&4}wO5!A=*L%sOC6a@ z6}^46y@I$DP%%&|g*t_P&OP9EHxF?s4O|+zhkU6peCfC#E`5M6`SvGYdJJDWZb82E z2)=aGhJ0xee5q;_ap@y`DfBdPX?PQFZRTguQ|e6#dCE_@;iXGkhuRCUL0;d`Yk`jRcpL9VRYiVE(;o6>;ec zJYe{%RHKh;313RxLtNSoUy5X3Dg|Fk+(BGA1YfF&`GEdiox6I=gZGF_ci~I9*q8Fb zmufMWw75)h$C0>Hv|x&af|?fG@$fjpHNVI%?xv5tlBbkE_mooD;^mJun~8uWb)sdUAuf)C;~;zYKAy zKe*I~>r46JOVgJUmtMmIRy&a|xx<&b?IT~pcv1^wUn;g_u=Z>RajDON?poAw;*xh4 zZ!P;iaVa9zRrCJsrs+8>?qaJYvoCdy%T%8osgFCEKSs4-U#g!Rtd`dxE?Hx|G@5;> z?&w#ZxBucxes_pmv(|n-wzO%exQ#l)SS3f2DsTrzBRaX4!%_WEpcfke5rR% z@};JW2FsuOiAxXQOW7xhOFqrLWx@yI()&BEvSxnrrAOe>D(>T6M`el`>`U`dV|Hd= zI=moQT&hjJRJwbjX&U>|>71$YRoR!u{ozX!%Y>^7>`RZ}0sY{W`t#9_SZf6i6PLW6 zJ8GTTm;M}kZ*JzRooY;6`Uc#Zf#3SI<$&9P0>q^_aB0PU@+B+y(&(ndr2@dM%ImjA zA2%s!vNrr9amg3skrP(rOE!xJYdH=Qmlo~ru1z^bT*~tD)`BvKOI>ceY6lCDFO310 zUND#PMrA66F`S-H&acsG1ZwemoHZ+0m1AE@X_aU`aCoY5+`%T*6VJzp|LoWPjC+1x zChoB>Jq=G1UD=l;=5bN%OWod~R@s7lsWfT=U%4g_1>8;`KRpLa_)^YW#HF$DrGq?= zTLCUP93n0$_|mdS;!+{tHg_EPk{^8O_HN?Rba=o~t}hkPYs@@eYKC#HJVsn{>+UW6 z?+};1z?a_qa+7)vNf>(<=dpKCe5TmTzBH$Bj93AF>*u_E5G*pP6PFsUPBa~1Upi9v zb^KoTr9w-7-ry5-90ADJyhq$x`SlM!Y zsU&>qCi~Ja_|hTF2lVgi)XiH9y-QsB1z&phi+pJ^`nXlx$5o5ZRB`M}1EKpX&4^3y z?}AJJ@ue+^=9TPAlha>$#{I>Yew7FpihXJDo+MES<2gN_ghSTy$r19U@h==@H(%mX zcdVg=vM=Rm>MQ-55tnk650q0+6PKz2w-ZIlmu7-X-J*y~ui#6&TN9T&fLnBV@}&;R zlV#8Y;?fiN(tFGY^c)VtmrCp-Uz&xruXk7@)Q@NQc*}Y3iAx{vyUNaa$d~4#CQycb zX~U6Bk)M5OTXwWqf;B?@TECUS!j65(Wptv+g?(vup49j%>`N2>@TFR%!c}lj>f;{l zOHwnDlitpWC~K|l5%Q%1FC4W)zQm>Ks8#OdTIIW@zM8!kacO7yK&{$I;?g+aR`(>f<7V z63w01m#SI)-Io?-EfeJesE<1cU+T-g)C}u!h1i!;fZJgo;!++5cUkfRjh7~&#ykME zR6U29@TERHUOEF`DrHApN&=V4^4NPRd?{ZHaS7u%S;n4xsWE&>+e=((01r6uYnj2N zJE$+cV_!M|Us{ejh5lU!dw9#`Da56I@TIXlUaE_+N#lmT#yQjAOWWC(Ohscv6ZWM# zPlH7i`%>wdiKZ;}r97xHqt;CA|KUqRzb#Y0*q4rnC#eATC9Df*SQjwPFa6$8Ytw?b z6oFdh%=6?+1%caI@LSKhFnsAU`_d}-(hsgLMS)9Au|}w$vlG7b`2car4!(5Rn|!Gq zd}$#2QXqV339rX}gYLWVJZ=W+HxFWoOSyY^Yk{|kOPAqG#dy4Ai?QuGt_iGzFKu97 zT3IAU1+p)#eH^SVRVOZ;T9Rl^W?$Ml_O&P0Dl|RMKl`;m<84L4MSs*%^>Y-)xnM(wApKfTv~#-GzeUB zMqOUN_9}d-SSR9A58yU*C9UmVgD+WMCoa_lZqJxYMZl#1c%^=A9jtxbP{gGj80Wgb zB`zI!gg+p(CSUpp+^+E&N|WeJv6k0%FaC-apHYj~+xfO7SOlZyrNGD%73Q_wB3Q3jiJbInzZ?XYjuMyN!I!@C+HNR(sT=!Ju_nG+WOL%u z&~ky=k+bAW&%8!xwThE3jRBY1940Q^gD-9JB`&oBZdvzfZ8sdglqZFJDG#`G5Ay*% zhiCAmx_il&?!%V?G~!Yl%#)s?-__6Q@esPtO}=yvzVt8GDnpNEswB)U^>f^RMytl` zOLf-=t5c|X>Bk>VO*H3XU;3wLs%NFYjF)bFT_!x(m-a1B64lt3E+4R#WqF^##D5)S zFZib3ej%*wmcK~8w7rh6T-=?wvRGT@%f3{2aH6RV_i>BloA}}EOOb#0Qst~=s%8N7apf^y zYRSHo1N#Kl@;-rm>5iHe`d$6`EG^@%t;RkWJthy7I`oou2@I3ApeCcT^;?g&8 zY5H#B(nR>uf_UOm4dC|U(@SH#G&oy0R~cp5EGv zTg0V1s4r!)FEvLk@I9}g^now!XJ5L3@rX0~(&T5sY9sqn!EuS^a?GV)*{?mP{Kc32 zu;(NU(W+&1PVUov40rOG+t66zDOIqx|M0+(Jfm!89yj`E(9PFP3% zfSh!^?4G*H(f`e!lSI^VT-lf2VeP9I`_d@Pnas#ZzxKo0MAIJjrIM{umva3gUlQQbTHbTA5PMF%c+bgi ztamNvJtrR@yK0Mh&q-m7M~<;C6~dmAzU)hZ*mDx;L*u0@k-@4M`_kR;MDtnhN|g(ybEYOPzq*ux;c^o#0CYFA|sBft&v^@})FzspwJS z(rk>qJLM!_@&uQ*F_*I8OQqPCzQUI**_Z0PaMkAWdR(dYSVQ5xa0^ghN@ZWFUMxlx zXJ0x3Us}h$bg4(8c_RDLlBsVz1ODPm<+1j)i+yPf_MBv~FI_`Tpc{|9gRtl16Yn{B zgZk2Y_9bUeUpbohoTP$FR*A%=B#gbU{jujHlYMD6eCgl8#HF>sZC4oWIavoTW$>Pp z)$pYq+9$EcntEt_dszmzwaN6BG8FROCG;yD+wG&wEa4Vb94h-g9CPUy5R1T7o?% z-+2vX2KIDdZ-?Ozr7^a}7}tm`vFBtt`%*&xRL|mn@ulV8mWeFnr)%og>Lg*wzGQdA zT8`#g<o(S6OnWCver&Av1keO$S##3eI4;3(HBf54ZTucq;mGkob` z3USFBxP6>WzSIL;@;yzyv>dn{=T&9T(X5PwPata@hDh4W?%YTCDBxd*LKUey^XKWzNCRmv0Ps|i}6xP z_N9ial2mW@r8lSv)Z&_e1L}hHnvpM^!@jf0muS3X4`0IbG4go^Un-hNzSJHb@PTUr z`Z(8PJ^4~y_|lwY;*u9|E4Pe%X&Jbb7EfGCgYE-(4P_U`-t|$Z(C_yL#wwzjp^T6y>yIM&5_oY#N$FJZh?jeTjvlVD|LUpnTVXnw}NJZ*z)pKaw?uP1HljbHLeiqbrckN^xuV!6K>-*Hrh#jrlXl1t88F81} zeYFL?v`_xyg3;PQ{N|M2&KjR7T90SNjW{pfDQuCn!WcJt$4}C#JGvY9yLRYEZR^8> zMm)4hZ>>bJUq)(cDluNx z+%wsTlN`dNujL+NuRF)azHUB8=(+K=M$BzW{WyP@5pxbk%()pc=WN7(-b-LW7j4nI ze8%zpWjyd(4mFMV7v42UYEADNq({C{+b{Jqjvq=~r3y`4|b}xpqo_4pXWOm;JBA8S$er zJ><*KT$+BofM_h|6{u>&rP`F2IoA3Z@fzo^qGsIyBfi&Zr|9HBnBF+#sg=l4L+aP& zyXTW?$xt@XlWhlX1Wo@AB8-ci?m27jyyjhE>~rx?#+ZjNC54!|`d{yM3%EZ(Ak zrhl(o>>(`$@iXUo{1(&<;;s1lQK)sq=ePB?37;MGO#bA|pD}xd(dMnt>*{_I)p-(v z^J`}cbTN+G?5nP={OxJP9erA8-A0!);(q1&XmzZzjoj4akyA` zj?~X_`&vq??cLUhhnIM#8dfDf4+-6*f|}8LVFB4?Rp*z4S5SI2j|=#%E&bZjF-~IB z9y?*-|{S4XFdE))71al?{!vd3`J%g1qzWa6~i#_=N6I?A2ZiyCpGw?VRR zo`*)Bb54!Le_1Rw;;h2h11z%*9Bt!+ylW4fpLd^WE0QafgF%)z{hdo|g^Y-5XJn-v7G3 ztDds_G08aR{cn5onCsNe%giyRqYM5|Z|8UJr2bv}E}rqs`5iqY=6Cmu=g;r-8PA{J z^)sF`zXNE*{BEF;1HUt9#QZLy5%W8SM$GRX8u6dcbL5-rZu;+)=($xNQeIt8q384G zIk}cpZKVJ2lzvY8NJr&<$s(%p!yXDO9q<1iyWQN>S94x4Di@kQ;-o07;AW}dbdR_Cej%bLDM6mz3KG1rAO z5pE)Hxsk_Su8nDJT>GVwhg`Cn`qsUbyGS1|^7fPEhsXv~FB`cnEHOcz95mF3yWn>S zD$Sm3aI(uR?0GByz~E$?lA$th(Zx#7xohPhxwY04BQ8GFS2oXUtLewhc6DX$w+)PV z(dHsjEbM5+cUq>1_xL{o{hUctBShuj^v>y@*!>w#TP)*eGmdrUxT#@h2**Wv4l569 z!tq^AOYKok!m&zDXYKeg!qM}9m$s@9;n?bRFRgHI!tvhc5!$&x!tsWhq! z?YM$%NyORyHE+6ybP&(;CsQ9^u&VPMRp=MmUx)Z!b6P zARJS=c*wBvgk!DhU1WeK;aITJ5E(ImaBOKmLH=t)I9{HG{~FCV$-r?JaJ0@tI94he zDnHgI9AB0RlGA$tjE5UEj4e}W4BjMT9xaBT-(yX<0O9{ugsY(^uL^w97=%>!J9{U!vGjC))S|?kJY3B&X*>l$5 z=hO+uMwilr1?zEMK6}|Vns9V7dB~y>tj8){=*1SH{>TA+u7HZ6W5e z!RdtK{jm`u)Z%}}@%+)o@#7fB=1bjF4%XwzyoXf|*5eOXOHHyKS6Vx3H=_y1E70Tn zf`sEL=y9<>;kfY22rXZ4!qH!wr1?A|JzC*=suyZy;P@PRT;)JG)~^$ymA+3n)~gzz zU1~`%QlrFv;|Ro3I_?l$7b zNy2gJmNlX*>+$#9G_kW0>9KJ|dnvXNjQ=>4yJSPYnj_6gE1Ez! zrf>GrdX*y_gJ1U2vicH^y+4l7UQQq!&CuhZrliL&&|^|{(qnz-aXjlWxKW69J%(_s zfH}~4%!PEkN&`oG_SK`%HS zp~pRbq{q9^<28%_>K~7A|L6rhHZ4s!-gOF+kK75z+k<@N$%3TEf@SJT^_ukfVSN#4 zUQ9Sf%M{@?gK(@dDnhte{?9mmdfp^{FyokKrJFi@ntatg-(i)Oi*S5Z%TkNUK{#&6 zYAsk&W&N<8DoW38cY8vaYl*RBF5x)%ewt{(daP2(URrM<9DjEAkPc%B$Db};j_79yA<()^_bo{LbU#i9xMHJkB?&SbH1W}c^w_IA%5Xkn0u@j_s>;kwTIlgDMP>OF{|9X(cDf zYd)mMV(`^5=gC+7fn#i0^3~lXLgg3-!f{^3AnDzhaO^YCS6(PgdW?e}i?be&tt}#( zFC`p1xu=L}Gf9tghDL}df6?QY;$HDR8AsQ(ZfZK~@j3d(Y}VuE+Ll@?)?=0Y&RT^i z!m%UtIEBZnx1q;!tjDd;W9@E)W3`i$w9Kod$8W&V`xD`K9(o*5p7i*sR)`k-jBq?& zIY6u8OE~t9_tCr^X`Hj=Lsf0?Sn|~lN!FU$L^$Gas8s$)!ZD+WpE}4m4mnoJJe>9T zJj6ygvmOWhp~qei(nKEC1l_EWkPwj>OV&L&A^cWDrIHKkpUXk>e1K-o%i*VG(tLd!A?F~Y-nx_cIpRNH~ z&Dw-xIq0#YGvQe9Q&p`G>#@{xYwbh?;rMyDQtn#`$Dbwq)C9(H^}nUfM_G?qRyN|= z8R{RaE?*=1G$3D{bS+H;vL1bl+2j9b3CD)5JY@bkgyR?Jv9TZ=3soE!k>77U5_)C_*gF@jv&Eu1%W7w_zNItaDQ#tjFz`KQ`d;YRNj5nicD@BKpJ7 zgM_2celP8KVZt#UdThgb{02St=t4LSfF3_wAU%G79y2!6IOjCBYAzRh*>MBmxD|RF%6hBG46KP?_4Ca11RSB-aim97pu?m5po($2riWKkG5atRgaNBjI@8 zHbv}ZJ(lPaA)5b1kE>^T#_whv(*xX;6YFtPj>Bq}4fT%$Tr9QpT%^Z7U!Anb(}d&7 z-Cmkq3BvI^^w>6l^f)hbgw|v@;rJMO6vau8x$r&fvZxMF8G5|K^_q+%kCjFejyXzCkX>t% z9!CR5Q-8uS1bUoWiuCAP9RFKeiEvCPA0#KWCLFK#_mv%r6OPZI$IMjHW7LWwQVS;> zSGcB#@3Tpd@%#^(%8?lY` z=!1IBc-G?>=rJevkIB{TWyU(fF{`_WtjOclvGCPgJkE)L9`AG~9Ir!<9uG;6i-BXg zR)k{*=uzAuJuZSCi?$#ft3i*~f(gfUz;P|(_!4@wU_B0-QA8HrOgP^ALyzY$f3*6G z9#0N4#cyI9XAgH%v(8fg*drI}0IbLG>Xw>dJr2uu(mXZ7aW!x}&Nz;J)k~YyhxFL~ z(+I6#FyXk=JV_gvi}YxN@5y(S^k@e?Rw+f}oXhn>w47H7$FJ1`w91~O$5iNXE$i_J z^mvH%*y5qJ)@e24H~{0-?WD(ih5ghe#_{yg(&pQ&$8l9`#OBlFtAT6R2oviu`$n2* zzKN@u{_?Jch$a?%8j&V)|;W)Zlil{P|^mwaJgt+n- zJ)Z6E9bboWoEYJz&axi&TOC#v7{`XtV+QNd7yaQD^ox29N8qbj#YvC(pvOsEU#$y0 zI~#(Us?q5_(+1dW?b|y?MMEatievJJRF$^r~9tanwJ) zOSIP9S&u7G&+%nF_AckAzH?o!&bN~0C#=URvu(tD)}vUzMr5!amt+2DVm(%`X)n{( z5{?JEdB~Yu&sl{!KsT-f?1Ua?u^vA|kEidE9(x1F=Mxx5=&|x;(qkX!v29Dj(HVM7 zWj$8JIA=1CbJ{xAmFu39ueO|CMBZgR+GD&L$o=D*9uZ>YU+SycFcH6;aeOw>O=WOh zZZCW_f_+ute}k7=k+1swcG5EA2*(P*^CgdSUP6!YjAIGZ$zKm3J=RB^yw6wi)!g`= zh8pQH5A>K&n)LX*ZiwcSM0#B5f_X<1(qn0iSG%(w+dz-`M-z?{?_s@TE$Q)7fKqw5 zPTr}YpL)W2ys@~nIi2;m*3Cu~WIcA;fc}wjtdxSf9M{S3m$8=)y9meLojhcvNur*uWre|{$N6>>PeeqcL8kB_0p zOs=oCfF8TC9_yfZ-KTkYX> ztJ%=wf9g4BQ750pdc28st7u-g@&=CQ7{^tAtXtI%EN#xizIv~vjhMyjR?!&e1pP;k zShsRyJz8Vk>Ikn}odu4||5&#QWIg6ao%|rLTY1?}kgal)9`$vrR{06XNa(QvuUol5 zkBPi)^&ab10laQC0(xA_bpRLC<)XMQw+QQ2fxK?j0_#@IdEII;)~&R^;5abGC%yvX zSa_zJ3TGUb{)$q~xDId?^_*I)$Jx;17}nzh)a8!aksgafkL7vZQ2=`U$a<^;JvQWe zjs`u7vA%{L(}1J74Ebs>^tkjT`Ra4%F})S(vEw-(&CZtesJ*MIJzzafg&v>q{IOx6 zQrSGtX;sZn4P-q=E-h&;$9mj2%|;wzJ!V9#5hb|}kO3Uuu^tnl$9-$aS5L!N<0g`? z>g&iYcpW(mdUWUc;}`Ug$61eWW`@a59|*_C(4+l9(xVUb_<{9!0D3$+h+wZkgqZx7aZc%tjpHXUj=Pq)sXUD1LDc1Pu^!)G z-KrJqu?N0y45C(b5`&;ryBalVAf+C^f-dotv*1H zkN;S=I>L2w4SH;qgZjs5ShpI->sB|gZuPnk;aClN{LXru1wHm;J-)-bRc&6knhqQ* zGLHQ)?@W1n$u%Kq#mV=USxJ4!ufJ&uAN2e2OB!$&`{9v!!OX&)R& zkBdrh5G8cAlBm$)a7_z$0q2p73$)@5PNuj6zf*kQK8-ZrO&NLLR&LUee2{e zzqL3of>O7sOI`fsmattyd7V~S{{Gl=9U&reC949x{AJ>($>NpE6J>{U=2lG*r*5wm zHUs_Tz_o`&?|Uc2k3fHUx8o8~uWpL?7w6Bq*ICqk@kU%jTtpQXz2d&$zta6>r9sO~ z;bVS@2SNU_t!IqVqYpjzGfB!bY6 zS95>WxWa1@(c531-nK|RuX|f8@8>Ts&x=%7-=7vEkWb)lrQ)XT6M8$QE;rQ9dErJo zM=!rnZ(au*?VRb8p%&h7G1~Fnn5|q=lTCU%Ln>Kl`M%ki^mbkiu+Rn!Pl(ssSyG_nYcUuibPI^0e(od`D$VqRU=}AnICSn)8+CD(dBKh(azL98KTH77o#2LjoG5pn`E=zPQOYP^6M`H7r! z-p9ae)BJGp4|3AmDUcQ{DkCSootw8@L@(r|xAXdKvZ*j~((`$5X>STZPI^8+dM3oD zGk@|ok2RlU{%jfLpw2UY1~m0oADBO*wk}d9k(1s|)Z9oFhn)0w`tDNdCUVm6E1>fY z^#VER`B(z0EyzjFrwOnco4FA;yT zQ(W+ST*RLy?~~0RH)N}DwA0wy-rR%vQ`IlQGlTh))HK#~kNGoiq=U$0{&a8RFKQtt z{W*W$vPcxIf7@uMC9o>~FYzZQureVhJ)Z)=swZ;N^HG;xh+W7@zpp~TYVK{~&$A8L zqJMg_S3&O>VPQ)LV_rYR4a?jhys$-pq+qLC8tR zYk#Ct>yVTFe9m;bq0S*E{rSuUR*R97-p$^litpFVATUT>FrDhR+o^Io=-fm`Ug4b`Md>I zdytc!&*S&OYB=-f+8q~l3pwfS4{PC2rrkn-Ie=ZGo z5FW@$&*zBr7b}=Q^?=nf=Fjdqkzxb$Cj?kMVE+6AtO_k8{&WXcwbF?{=YdtFyTqRu zU=@p;^!sWLtQHm|{$v3w`=-R7doe zAt(L$`~+5=nLqUwhKo?<&y4h7(Tw>s<*ti}W&RA!NH*FsF1$`U#0 z?VJZzFOZYo&P`x7i1|}y=04Sk`O_I#^lroGI2+lKJytn1kre{CO?>#X08Boz06x0`sRguzJY+aRpYDkdw~muD~jg z`BNQOJ!byw1Xd52Kihy+rA*=va*>sa5Py)1eB?>|u>)33kdyv=`U0z4$Vq=bSAbO_ za?+pAEnsyOIqA>mC9vwm{HX=3DlvbC0xMtUPZqGM#QgaJthO+J{4GxF51x-IkDT=T(y_8ePI@~!R&7kgpHjeTF!M*pDjhlL&qv294LRx0 z=Q6N*!2G!btok#5$^xqf{|$dm1FL$>pBP}ZkNJ}T{zNi=g8$&pKO(_X=d}KO;(%3g z=8rA3-i`TF6k3mC{-gsdjrjw8i7U*XX27Zt^JfUKYR3FA0ju@QpCiC(3G+wS`b6Z! z`jUx-h(Eg4Z%X1%5nz>{{ig%4lI%Z+fmI{+pCiD^g8fGUtLe-i3t-ie`BN8Ijbr|V z0xKWpPY|$*WBycv)(cD?|nLnkP{Fna(iCA+1=Ff0wy%qCkFtomt`BMsg#Wv>8 zDqyvb`7;n$z2W|A0r*pr`O^(pHDLZ+09FpnpJTvk-bdn32khO{#-`?mBReF z{~_6Yiun_h|G)aL9^U`ef1N=8^^?axwis);GJo=5tTB!G(-&BcX8zm)R^ymIn}F3` z?!V%I)pZ{KOaoSHkdv+p^zR}RIT^YDRyB~5&Yw=eYE(Yrk3QDOZbAI{g0V*b#^gVa zz-lm$fAp~i#vF$K^Z-_KnLqx(>J#&45wMD9{_MwC<0kW`HO3kd%%2JvYkXqHcg1tm=;> z{}I5d9FL#N0;}iDA3I>xl*iAWz{-lp&mDkO@y;~rc66QLqc>J6?9sa}fuYWPu>4u#2=e!eh9Sfd+^~PMM z8PC72rzM-Lc>d*))85qkKmOArA^ui1O)^RGjg6YA{*feiJs*p0i||ev&EIQd{@#xH^B7pQLQeYgxe2UHJbxbmtn7LIz64ms zpr)X=QwLb}dQJQZ0#?USQ_%B4EkW)YNc>q3tXxr3(4Wr?VATvY1>MIM0;~MZh(B(? zN+Kuy`IHA%LC8sOr-Y8xZkm5t0IOfjpA~O{#XROurJF8d7xSmit7KCX=Fh_KcBaA1 zpBh6G;$Jg=x}nyxg!yv^wU!~wpY^D<3}XJw+_p#+VE$}Et>pvPf10D#a&H>(rv_>* zX0HDn09L=a{&N;s&E)!zAFz7xlK3+eSmnr~`cEpbnm&s769%lJS`mMIfz=Gur1a<0 z1Xu~wr1a!$5fVO;+ii~3I=uKxtQ4pz6BKlhSd)HCMK zlo!e70nDF~pMe$g=VoYv=L_af-ZrtO5zHT#u@0gh^XEx(e__x3DYbo(*n^z(d>rOS zirL6%IPf|Kta>3Qoj=RE+z>U8laBjuV0G#h^+L)PR+T3wcosrC0l=znTjEb?V08;Q>Cfkr<7+X)8*@UmGXb@_e#lAB#}`=jL{54; z4#4Uoa?;y*IX7IKK~8!;6<-C5DpzR!J}=2dltoT@JKED^(|qPn+Yff8P~@byGjV!C z{1fD)x1-v{n%g6%COV%(9n{a8G=Hz^Fsp7@WT?dJE=D^WfR)=5;?G22HSE2eNpI&7u$neEAzsf% z0;^{2W6gRyk8XZaO~(;`HaosnPmq(IPeEX1y@U93@7-zj5;^JZgoo`@BaoBcj`!Sf zRlDmArMGkDWw4roob=~h5dX0rh@A9x_B~2AA7=i{erso*f}Her<}6O|ypNppb}n~_ zHPt{)dOMcm9fXFQ^mbOY@E2o{lip6x9g9Rt9paD60?gl$litpuJxa7jPI^0oyWS9= z=Y$*W90FE_k(1ue3}EGZ&BbWv0_wIu#*s&iW$LQXn=0^gk$A;?M3CnvD_h@A9%w$BL{TalCAj{l2b@re1e zG|@$DXa0oWPd43W{zSj9GtFlHgs(}6zs>wfAChby5}z$@A&0QchH7us4@OOUaF6L~ zK)pwzE57SMu(#1&lo-Zf24D&AgvM?CyW zmdX=nDaPa4`wxDr<&&G5w&2>>o)%iKVX5&+xOT(9Y<2YD9rG!iUwHYy>c$UuWrKSu z9Pm(`KRrXO(VzLYbLw`x?J5M;t1j^Ns@mlvp}Gw!HZT)VzhTUGRSnkt5C zb2|PsU#;^^oxru5RyQz5;HTBSaIHm)-=6;MEwmN5_F~2(Q~ko(>Hw~tZ6(CpZ|TYr z*B-ArON^cWK;6f+WykIi83)d)61etS(^Defn%!y~uD#d$u2?m4zS@CnQzpF=es--? zOCq`9BnP7iI|ke(SwDBW~e0RziYNVF`*9tBRcw3$R}BWB(ix^W~n1>krLVZ!X^Z zzZW;qe#H$ROoy+26Sao>%j$=nO_TAHCF{rf%g|{#&HY_14 zhiAJkRh2B$S1b$lmo2(|QcLrc6|Kkn%c+Hbs+t4$o0{UM>3fD)3ZgAkRZ1 z*NQi`392*lPx*XQtGTSc^9dIwfL1#sF+Z|#O+IhIFkGb8(-^vqfVSei`doCDb zp*8C6FZDE3%&@9Qt8ecmjd`d(CaLvfEy z<3(2X0re653I6AXn1BtR{tKBm30MEgC#U>HA?UFj%+h5wWiWAd%9a3>!uud0qLsV{td2a`QX@C5c zc#zabIUxSp`ipRjDXvVNf%S!7V(x>5=26g2-3=CUMy`V%Fb?}8&kYtKSo>R_=eoFFZc=Pw6 zzePEmGrnIwmGjtFaSGQ)Mt4z3DQ`px91mHvM7=4UA}- zwu*B&r}FKGDm-|GxQc6A2K=j1&UuPi$mh3xw(>3W*mMwi{^M(*EsnM^N#q~d&_e6r zQ`sDb`*QC3UA66+ZhnVrZxu;bZ`+6P=JrFAlApZTrs11~vh zzvtvx7Frb?cQKzcot*bW4Z-=<*Sm^c&pxUahzoxlFZxz~s?MVQD^?pt?I)L2Q(POG zeOv^@MX6HACvjD>SoUbSx`gvr+)Wi12li7oh$qE-7QYvlQt7y_#?ya^bLWQV`91Hy3A2{%CklA|YZ_x|qoLFXqU-HTlXK-zIyce9l_pNwbt9(+hO zwZJ`g5f<97U|Z91+`DTl3$5~xlIF{}_UWbXDsp$K`4_JJot&NGg^e$O#sU-F0=hkTZWCJE2b6)FSgZ~gL8EdCaxJ|X`K4xdHW zer42F+*fGBUm|P&I`eqk?`Y_{*OQ!aQ}G<`ulyxO2d*#;#q+uU__GLoR#GJ4+M$-O z#Mjk*#Y)#-}Rk*XYYIPob|PI7k5|PJv%cyzaEI@vG%LFz>6E%V8>%U#y^l2 zEGdCnT;HDKFWV1Ur;?+%{nmG);_yKSN4U>RtcW%56~JR2TQ+Mr4qg8Xv>embW+yHj z_748C&ZjQt@yo?K@Rv2L`gtGM9@fGLo>u^`!R61kKnjn2_~kbScJB`sJho-8BAgJN zDShMotmvpBT?4h$o%8n2MMa)BO_YY5&#S$P@j}rjr5@*P!oELv^0OU=a=XcwBy8Ws z8&kP1)v_Mq!t9gi!?hmPHP-BbN?g$9cz&G^{N=G#oBhVoKLA8q&;6&0al6x7r33eWKRAnj`00iFxV`h+ zCtTyc0e5m;hBkPN#am8bHC~$|0xsjzoG5hU&xcs=!~U&a<0|fd(`FK`dCAx6+_ryM z3ll5n<7tlHC48fDtg#O3vrkTCS=u`uQjsm|@eH{vwGS-Cx7>f<2us+Ll!Gd6PaVG) z_E!3aFL_>{`W=EFo1Wn#p07ovFsS|DCQ6)#e;wmNI(iU?a(?!<`37TZFUGe#_q0zr zFwNK!>+smGfu*q0^MbOC^Bf$Yk~`;_M~&e84{ol5-DO*(H$3)SrF`%hSX+NAb-MEt z`c0VxGr1P?&LzOki~C?a*H?8U3R-=+3@f<3FXA{vXFP`G+-G6$4Y0CVGTi6?`(JTS z2pXCNk2&VGM|Y_C>=%MQgW1GxWYT^4%I z>xPTD?foqo=Pp{0)?CvLPEXLX@^MV#vE2%_kZ(j3Qo^Y zMN4j%9IuCCSLWepj;}enUCB)>Lx1*Ib=`BjgF$>=&Uz+hpO(DSO3{et7{9G0pcntX z#dGiXXgcBF5 z%46%==D^oiZSg7B!n|)OOqp^+smFQt+ozJZ+#3@W#re0Ntb;E>>!e!Tr?YQ9xUMqQ zug(7sr$K4tcxc0)FMskH`d8WuKe>O;j|!x3yaeAxt$Uy3SIIqs8{Fs0pN-I`#V3g2 z|NA@K4l?-s+mH2N>PP9ZZ85~L&d&QPO3lWoTT z*!>gwW9<9iP>;vXY`PU^Z2kauI6q4J(-<-EKFs92ZEkZH3v$juH_qqqOYd;=iyhE} z^L%UDFKpOvIGo}3nfnFUzfMJXz;*fiLWha3M@V5@uWK7s_}4e`(CT&%=njduAe&IiiSj5T{+=wjD2SVg5gmw9kZD(qQ?oq3J} zs3}xwnv2Oi_iZ+FVD^Xa2%M9t)dL{^%X3WNdKHho0gki7(UkL#Z{i?7{0QFQvCRg5 zg@6Vt@ga|0?E4oE2Y1AsT#I2pOJGf(NaZ-!D2AWGYus~NR7Y-43edq%SR^@fp9hT! zAV0)J|D8KwX*%pN8v_{}v(Jw=;6HIUc=G@1(wLxmtBc^m8V-h?f|~0eLLQIZergl^ zXqE)8`2Q|kA;b1}nJ|sVHdnq$e`AYa7T0={V_nIGudxHU)>8&IRoV?u$)P;2Z!do; zW#@{ZkjLhn>VqanGvO!aEpXOmJhk^DOy&IayBmV5S3H0(oVUea2u-G6fGwQQpGV%J z*_vHo!~Lxy(lIxE6l~^pZl40o`fCgexGtTJ>G0r~sZwt~4(IMr(WIcjsJZ-kL|h3r z?tVw{=Kg*89;bC$C+x=UjKnW!J%1H$mQ0QMdya`@(%*9(guTAcUloLbB@CeU0ZQ6$0?~bZyI_Kf-&Om9O zcNtFM{8amA4s&njqR3m{pqViB?hh>BeD+=757SIvqATZFF1ZF~e0{x|^WXPuENt(4 z6w`UE``9nA%6AQlbEJyjvtj9MD;&yWx9%tb-va^dkdQ{?u1(WztYCsfk${Ap0fsR7vAgD;Q`q5 zyt2k@fhCPTg7BwbhkoE;o(Wxe?7F=fl6qnhsCbTR^IA%oT~u;i&f6@b8p?!mD%pth z+28Vu^0QGfm~!5f40~KL=?@UMk6-l0b%9A>#JOEH{uE{gJ%ky&zN`=PzJ;+DA(6-K z_j!ZWn(l$&+`rL}G&I>e4rX$DTtq$wy{rcHxTdG(=0U^>w#w7~0VW>+t7y+m(PvS&VXr``32oXOJ%3i>k%-YOm8l zvz^1FSnkuQMIl@-Q-L`CFRhaSzR^Qq1M4w0ON8d7+u;oBoVM#OWV@ULN7jGs%xU;u z@jh(kc_mf!fp2v_fcV}S{AnQE8}l0~^4K#|{z=on7Q#`^&#OaL(#NJMc^~J^d0lbT zdA?UUlJmLLJyH3-r5G$Y&sA-DV>PoZILvLI><#$s$S2TpU8ZH6z-IRz@w=A!yL*I! z-@0A~EB@SN>1%XR_QE3WzrI!)+FQB6KyJtXmyeyV)&zy)n|IRTvtlo)7mqbQsG=45 z-J@Et9w$vHwurx~#Bu)(S8{OsG&LG?yZzl1bQ!+{fAYM}{`U;4+&YBmJm1l?Zlal6 z7`Eg*Oz(6MTWjJ`<~i1=y9m$E{e~ZS?zuUw@rda^RP)#vhjYr%E2Su&XCB?uBud5q z+nV#grQJ5EgQ*T5^4OFKbzuI-JQU|S%Vti7;od)SCD&q|g)clApMa~m*5~_O0h2ya zIGWp${hmPakmER=`^oL^i zwMj6hT>m!A; z$KLVUYEb$&Qp0*~zbwU~Cg+q~?*Dk?KOB0f73Q%1Iaj{n;KvIvi04&rYCOJZdJvcJ zd>4oFyXI@&#I2l%RZ)j<|F~zkl=GuLxD>aqOTp(n);_uozMY$cpSc$QwYjF8aw$a{ z&U4S4eo-se`lKbxJQ2BxeRVyhWT?(D6M#o9kc$S!}De+uG38pf5&~@=i(^N$+F$g zQKt#OJkHg4lW@!lyMdXU!_dJ;a8}2s7{X)Y8@Z#|?yvfs)9wz~|L$K5=2|>6iBJlS zO7RZY=-wGkRNI{@GUfIW-(`~9Rvq@{KFz|bLR5~S)?1p5g_YgXv4mrOeX$#s2E4&T z?2TQUFM{b^#NMo7#_NZ0+4&Tv@YoZxlfbh5CcVefYy5%Ea{w3f*zLcHz+(GX#hZ27 zJF4U!>Y9o>d$mMX$(aEyrDHs=*zHANT#_z{`!M%rXM*Jw2gu>PJ?{Sz9KUP^PtH%L z77rkyjTVsecC6?;w3P0^V$SDsqg`N;_7*yEf7Q21TyScsnLuHsZy8t$GT~0Vm zk{(~uL497Ey0*uow(~jSaQ^)8)M#bmb^eaw{$KO|!<(J|f<3n*=B!3L|1WTi<7baK zirRUxP>pN7XKn;O8+{!dSkI+KFR`t!KYZZ+4_E!b*ZFSxV@v9aT%2y#7~*(dYo~Kf zZ388R=i7+Sg?kN~5k7$PkiV!52ZkL|MsR+#J92S-<;E!PznN_OfrE~@p(&4z2!DZx zKl`JG^K3dc0z+M|;{?vXSwaw=D2>JUJT^aIHBLPIMSm=vGp;kHHTa8DxE33arYhY} z7NN}l>s?}s5`E8_aw>JFG{r6IS8+Fe+qB08DVuEc?TF-_kkr6R-~Rv8zr2quVpcpi z8}9~m)VCjOK98y^E%fcTMoGAFS}lD$@PCweE|v804Q)lV%ln{cmygxA%VX-><^N0HF4sV!f4Me&yIixr{XgeB zIG~}N`sD$L{&_ByW&4-^^zEFQ$)NSGsh`USw@cviv$?)~uIXY3$myVOL)AP9W?Jjp zIji^ERjkxq-~Jt}md`gg%yEXZm3;MVH+{^>Bf817T%(_3f>$>=(0a0dj_wcm{iGe-<(?(u+eXqXV>uy82$&?5BcKhT?d|xA1-+tzn1t(mpkkCAJ8{ebYSy$iwpYw`~ zYJWSE|1SDC*nN?zzA*TqX^W|l+r5+i^E!1xV4Q2K|IgSjpOYu#HfAl#~UF{(6ZLti+=Y2z)$!1a4^le>XbvbzN zcYWKdUIrYOs_ONpnMc58zb5*2;;s!atap2TJ79nbBt7n`Z+F?y-M*jBuonJbxtcH= z*B$Ms@6*)wJf=mr(6{>@{fIq$YU$f8JuA`C@I3whEvVR#mLGehZ`Yo$ro}b(>)TTX zSyAqfZu<7waouP{o~M2;i`=`>n0;>gx_>-oMbYk7Am;VHNKIyI_vzbaPa0C{0D})Z zF0M?jXAM4l{`wOZo;Ub#_l=8q(A==r!p|?j`|S;DuyJ;#@|1HYV*by0g&ZwG^`%=1 z|CUO#Hs)ZVqlNh0kY-Q+j;_)iv|r&$uY6x(UyJ=XceyLo*cOTY{C8@0HiZcfG$N&ph zSBmxDf|>U|z&h@eIN>DHyhrfgR9EUWB@*B3u0Sfs>D2cH+BzSAz*(+zpgZ3;Dq0AK zxsUtdzgXvL2RO`QhnSUMzrC?iCbzx#ci}63M$*n{u4LOoMRUH@P)u2KgX6{c;oeKd zf2J#qh|9*=HLb)w5Ng>i1+#QZaUzc$IQuycz8HX~SzBED+jxS18*Vqlm6FDsK+igl z@dM8{|H&q-c<&=V;kk^hGzhD-{*7z6|I5D>Ff_CPr*oXaRaPl6Lv4;5!WI!K|c`w)-&2}Wg z9F946RxrBmkAVP=nf5je*Mx^c0MDgi?Kr$SCWGntVTj&#EIuoQhA&aCloEMZ__0RDku3s-V#G`+EkSS39E6 z^I>}uwms&JLXX-07`)4xM4a~Fq1f|X7>YO(1_j|1)+FK#pRK{StVzU~qH(~rtVzVl z_fz3V)+FMr`|hFqWlbVZ=*m8JHCU5~)1tkP^e?VVA1B|a3KW?a=;L^|aRg#bBF@fZ z-f)~Xi8xJW2g7r}7=4`0@512ytx&xlZS6QH85pFGQ@2AhY?`If$2l`F6E=G}=;IVt zECe&wB;u%K9prxTP=p@VB7eTv$4=<^9#;l`I`~LpULV-YA1YJBM3dS zwkN?K)+FNW@QVR=)+FNWycG&BSd)lzY+w-lW=$f_EjJAeWlbW^h4l`Qz?wvy?!GE8 zt5m3uv-p#TRD(5%IHuqFM4GZD5r;bYC~sJkh~rsejJL}DGq{x_CbEC{SsiM9)EiBA z8vK(pGZ;7e8~k(TO&C%{C>-E8nKk3E$6$kh&b3R%h4T&m2^^4#w8=pqXAswFU7*1~ z7r9o)^9}x~&9$oO!nZy-jsyGWSqp=I0@*)vOO5q;KKCO7JGOQd&oWW`jwIa4nnZqj z`N!Z$H-mo`MTBAjYZ7tZI0j*_S_c0F&ePxz)+F-t(c1wZuqF}5H$a86%Kej_cs7eGypbEcUi9!)j)XXO!Zth&qKANLu-c=>?AKa*aEVeLqRf1+x{;XS7y zSjcfMwN1u1i!}N;iTyKihL6ENu@wqYI%4q8a<0{NV^96@r!LoO>SECQXCv3Dj=7H_ z;xuktfJY0BQRrEint}V88~hWqGYLPlCNZxW2VyXRHHmpe-44YotV#H1no|&(u%|_w z;)NQ_U`-;9$5scdTJE1AhgF!)nnawm3ZBY_a{rt-2X=K>lZaEXv5&NjHHkRBMaEFb z{?W&2;RtrDN%&_-kT;)?8T`|2W-v5lO+rtFH(@Y`HHkQ5Yx41DaF9Mu$9Bokk~N7q zz1cr|w;23Wm1{NWkikEDxmGQ72LG@Y`P(cSZim8H)+FK_;-YZ7th z9aKU4a{r7g_KUA?A3~omn{L{Kd z9PDIGLXTD3WZ1jJ;2+Qanb32)!9Tkz6hiBx2LFuVS~=JB)PH}m7I|B~r1#HBu2uW` z2LDXvT7~8t{PT?cgG~+o8O&?F>Jfu~3VE&9n_=+JEMDs-uMPfb>l_42Sd-9meX#}> zvnDaGq1znbJZlp9u?kYbMb;$dwZ59CG_%}4wQV4h*Sy|8&CPrizjFUn&o;)sO$^7M zIcAP%nP%`$(}UhvaZi$XW|dY>4aO=5V}PHbrTZ_#@P-n~{&uDD)#LEf&>&dEdTy$d z@v^(YKd${U@zNfHe_k0C;=_|FeVkHBhq;!Xl89r*wff?3A1UHgcvglRO?(s)rxib+ zQp%ddymHt-LmL|WbANXdZe>kEj}pkoAJ!z|OjAP9>{S?wIO~Q6;VIT6;=Ep=!GEkt z#Cf>e0e7(`k)O9GRG7`0M1H!p@>Hs`e?*+1cze4BtVzUKQq4#D%l;8@{_t->MyyH1 z>1OT-_gIsNlYP(|wz4J>$7WhEEN4w3&b(J)V9J{Gey$z|jaZY2W8EehN|qb^6V)#h zKJ7C2r#9E>=W&C78gs2yH1kwM9M&R_t7h;|3fIcj)Zm}b?4K{Zf4$J-$7{WDBZGei z@mimB$l#y0fid96nnav%Uh9#pN$3gVwQgr>@K5XI8d%1fM4UWc>%Ul&m{$R>b*pm! zTyNwlwPQ^pPMrZ#B(HhBf1GRjC@;(XGxfJI-ev#rv&xiO*Ac&z`^PK58}rNkQ(;Ol zb~t44&!!h)ScnGySXGO|slyHaiMC9}veg=W9BtoB?Cxjqj|JB^VB|CK1QtWf+WSO+rs} zwKzD&nnWBsbuvs?W$=#?*J{N+gMR{y3gJkIN+0L5q=V6&4E|v)@}gGub|OyeXJv4+ zl8+?f%-~wJ%rf|AG}mft1A~A1aIHdFlh8AQ*LuUL2LDv%TCHGBB91&P2u#`2BF>hT z8d$@c^gi6{09NJxxp7Jbp{z;7x!lfE%4AJqUQ1oZ_|vp$0b;trKXcPF zaCU8je@^dB!m$So{wX>XgN3X~%qxXL@hEE&^I9O7Pa{qJyPvuCte`-{-vlE&`oGry$rN!m`3I1garRDyytHb9%tV#GM{D3zsWKAN^ zBVB{xCTkLU(w_6VDr*vPPE?J9hO9~G8ETmf2Rt--9}exyzmxAb_@^b;s`FWcf6j8P zuGt#=!&>BJeeCr9naZ^qUbeMy($C_)^B*5UGrM%Y9u_mF% zkwT%z3xj{6c&(?hCZQ*8jRt&JlZaDizXPmcO=4ant@+&?{gdP-sC{z+J67s+d0 z?;msBR%JxFe*%9P6gJj8~1zT?R^ISjGYvW{f-#?V;vucWABCv=7Or3 z#9^CJ2LF_`PR15q2LFs;|Ik5$e>~YgT`n2?wPpLwYU|J3`HfxT)N{Ihvq5+<=GQLhR|V(<)W68SN`8;TyRNyK?EG6;vTCJ|@m zdJT4GPmBEI2Rfh!YZCdHeo=)7Sd)n3>+Gq_Dff?AFIzjINyG{Iw^cgBnnWDipT@A9 zHHkQ?nvRfG?w{WN-Y|?ci8w`*g5mCAgMaSChr#_j2LJ3aiG#JQNyJ%Tkql?n8T@n7 zfw>0OB=lTW6@uRdgMZw)RwEn@{%Op$DwuDp_s=1&m17=zn&XV)TA8L9{6p-Y$E-=j zX~?w-U`;~LMqcYfCL8>-me;xods_Ip&B!2l&YDD=bYANxSd*C7tN;gyWlbVZ^m!G; zvL+Fy_5e?5L%DxG9JP%Unnav``CFA;tVzTUxR! z;zHIW>Rx|z5RPU|VqTp#XmAc|68XtG?0}zGlZdnOiVCgD{gX4^Q|VdmpW>Ch?V6VR zr&s1y>0`Nn8h$s1A2tE9}TZ{6ZW*wbBNb^CTkLLR`XhqV@)DI3B1;0S(Avf z@sIUFR>?SUlSUt>E7z(| zu!BAh>I(4db%TE@aIJ8brzGMu=URmw?WOlm!}v06oVryour$6|0UrEfELcc_j10WU znuHz`za$*Onnb;x2gRTZYZ7tl-3vue)+FZDV@wdbvnG+BOWqp1!kR>!qemTZG;0!Z zY_F>@fi;OZjb?f(rmRWCsq?6pozNuWto*rEGG$F7PCtJ4Ss&IU;tVr!gr=-X#0m8E zh7aZbIXW>If>@J?6Z$j^-m#}eoO8x;kj0)BaXz$4hWe~Y)XTk3CKLrZ=;Ng83c&Z8 z!9QkPtCiCX{^9i{FUsnr_m5G08N5g{_@@Kc>Njf=aSGW#*{n(Exx#DxD{B(-n!{`T zGiwt53Fft)$(n?o3%u5oS(DJScB2NWl>28~kOLfGO~Qw1yw-KBNuOs|PpM_Oe;zmL z9Vs-4IRE|Hs^pgY=bLjcsNNt8GkNSVr%n8wn1uYiF}3`wg`D~K@iE_T&#Qh9md-kZ z9{hiU27iRj`#0ks)_>~cA83Bb7Ax`C^zXcXm}9*1naAE($voP&;Hd4~=d^_m_H9@r z8T0*fo1uBo?0h|F#`nG3IRAj?TsK(D{oCfo!}mdf5XNzOpA3bEzr!Gib*{VV4?{1# zfaQGu-@EY?X!R!*PH;{_f=!|3jC>fwW3MSQq~88I_{E=_c7GloT?k+$i1*iqrGV1;PF-1`t?bQ+lzqMj!|K+LZ# z$gB|U$odU){`5m;g{WJ>&g zBrz*QT{rxJ>K68b6{0s4K7mzBZ@~(Y=l(}vi_hVKF`nzR)}KUCPl^WRmsc>ktc*IqkEMKR)`+S z?Qloi9Kj0F&w^!G*gQqBLUeJ$Vf6a)RIox6Y<~-rd_sX)A!_g@9xc}f0<%KA&(?R0 zojxC!6{1=D{^7u8ErD4fn)|mD_n4iQm=&T#enxmk;5|ELg=pK$GMv6?hr+B7na;|? zX*KH$R)`WmrDDzQQw1wT@jqT+ZmF+eh3K_+B+hMlRj@*o_3jvMUGxN*6{0TH)?=vZ zGcqegt#vlItX{TYh3GjxQ*JjX5v&k-n!boiU#%i$g=kJ%Kgq2`Cs-l!@1>KL^e7ap z5b1Qz&=WEQD@0evZ->uE69p?oA1|JT%LAeXD@4J)?m^9YXOLMT%Gv)Ojve~OZntEiu!mJP-XrYp0ta~fW3el12DtTy1hCQ=FRCK5q4rRWUm=z-D z-dUiX)l0BKG|MO%y3F4oSRtAf^BBf{J1$ru>V5k%yuc{I3X$*neX#RM0x&B??ebmV z?7N?W6{0ThYk_RN*yFowiS~LR2F@3O_2B1uI1RTuVuLQLL{N3s#6CH~)$1v_M773Q_;D-K8D%RTRx0>%2H$x^cZwutH=r z(h&-ce+yQK`d{>c)92m`R*0(DG7r1;o?wOOdgW+He|8p`6{6AJiO^&8c4StFHcrog z)+3#fSs@Aowlb98v%b8hF zN83%XLiD&K8IH|dFP>Yb&t*>_eEKoL3X!hiRfzD66s!EO=|oG8{gR@SRv}!2+?N3CBX`j<&%?mxAr6bxm-ovMyywsgv<)j^Hp}( zQu{}+Lgdi$lS2KA1uH}sD^^kbC##5AA!;AiM(Wd^S!~uk^7tRAV#gxE3eo%E{?IJ$ zw_t^6blDb|dHsW6g{b3wE!aP}FIXYk6n_WC*qldZg=p%ccd)tQPGnYyM)?1Nd!@sW zSs_~Rq5#ZCRTR%(QRZhI+)5g+Fe^k2)~aNuQ`hX76{1saB~Yj5Ly1`-8go1wW_{@* zSRu;&_Zd25dI%nYK6i?a9~!5T?<()vKq?o7c7 zQOeNGP$&GOV1>xpIRyNS9tu{7>I4w<3%G#H3Q@DMZ(+l=UC68uO}dv3%g>BLW`)Rk zSOK(9R}s%&QS*yBDCjvyVOEIxZ{cSeQ}^35D?}ytO5o{ul$aGF+hKpG1xg=oRknYj1P z55Wr2zv}+@di6`e3Q?=C*U;uo1TZT^mK9^s=G{@~#yPLw?+Xsvy#|;SB9pvq+|<oq`pjUT5y$flcQHD@5)=T5O@*7pxF@EZu@d0_SiiVtPo9|$a{Z@P-5mXU%LBBMu7FmmoO2;+K{4*HC%YOVujg$M^QACzqk%nH$` zt|hqNKTcv+h&rt0=P%Yiwr5s|?EdI*r;(!~o|B2LTZnr@Re}|wdX+Qqgvn6B3Q_6E zMAXD@7pxE!rQgM~_0I`bh?-P7gKm57308^Lu1gh%N*U#IzZ|1uI1B+UF{X zzYCFB44RSBO*x`g5wk*6%O=;}(^W;x3eg9PcT$&i#ex+g*A>0tK;=^;M++`!7q(3elC|9JsbwEm$G?^CShvEngy7 zAqu+n4Eop}608uJdEJDzPGN!-qRf*A;X&~;U{;9IvKR92Xy1TYA*%7ZH4JF>Pq0E{ zeC&es=T@m;g($sy4f{C$zGha4TwiTgB8-?}Fa(9R*28@ z_u-N234#@(tX5a>;j$>f3Q>{IWAx5D4$KPCtij26WTyt06{3T_S=jhW4`5b^mctPo`{R#AM`4|`^XXnsuwa{#l$kIa;tn)Gl!wo{djLW`!tgkQ44boFP~tYLrl-Tw75n zSRrcKqrbAXmWr4aq7EnD+V9}=v?-kD>Q2w46W@vjD?}G>bcae&S%MX!-;=yxN?5YK zUQeGLgVAT72v&&TO(fvWE6A)6y)JkK>Px=JtPq*m{)FGYuE?wqxn9bHp8<9CK6#MG zEdTi(3bR7A zO9d-Lw{H!$cjNPLW`$_P3lAkv)(KXK4lJsH(UbClSt0tMnusZ5(*!F-8@unt=-AhS z6{5DvCEOCF2v&$T&U}RVGx!>i$BrEI2}gKuglPUeF!2vAnQsfHxxe{L-a|6)gCvd* z$?T-Uyg(#`2JDk;g1!je4^0W>x;N@Sz3XyH)Na4Fua(ffB}^{;OPD@1+A zUPPJ0xEfDAJq64P(G!Ox47c9|%nH$+W`A&;1pu=`l#pA5rP>t9nA_RB|4`G? zIuf%&)Pnc!IQw5yg;^mo(G+1og>;2kA=*AZ6Se;w1S>?e_#?h}v>BNdqS&(!Fyv;4 zV1;O>^#webNrDxkJH2+{u#mUNtPrIh8;RS>(giC-ck38qz={IF3eltQGZfcIonVFN z)xaS8{d~WLSs|*w_l~spT!~auV96!^j5Ug{4%qt+iuMd_B{3^R zMuS!4xUPo6tPtOKD#D&tUlnGBXtvoOoNW(+6(XDENqDq@p5vh9DGxE&_LN|SXomkq ze14s;!8p&=zVF6s+utCwLNtHSSp3={U9duwmr@l&e(U)Ws@iwC@?w)tutJnuw9bAD z^Crv+(Xh+mQdQ$p!3vT6j1K%f_FusYQAqX*_#UX|R_JffBk-x$Q^5++_`+K->){P# zR*3#;o`bJn05U5?0eip0g(-89Ss_xV@!n;{&Ggr6Pn(y)l)EPsW`*cEpC9E<&_psT zM6EBD!HE1l60<_|piUla?PVrdA&Q@#3O=^e1uI0|2EKwV-~9wDL?sVz!|oqf1uI0u z3WA{z@8`g*5Y4Z<7Ib?)1G7T3JEbcqtFr|wM2_=gq|l)yf)%0zzsP^71bVwr(=H!R)`u8+JQ-x6ZO~2J=UGWM*HpxR)|tl?qT&~ zr-4}^TGiwMIX_Q6P0wdhc$3F?H0p$4h3LY+OZa$&B3L2% zyJs)HUho>36{3V+6L90`G{Fi{PG}8$Fw;>?&xJuuvzy4Q5G@@U4+E?Y zBC|pi8}bcovlk$A?4Qm=&V3 z=fz5&MTLSDq8@HexHKR`utL=A=r$Z(PtPHedG)h6;AOO6h3Mt=XuMJREHEoX5l!FY zuPNJrSs@zviuZGX!N9B#tqLf_suznSasTai0~O_dmnCL}=p|B+AdjNNg;3ekn)o9OlQreKArcIk1vqW+?R?3chI#{dW@BQOCW%2C-Xt;*YqmqW>uAk}9YK1FJtiKx%Tzdn~%lKSq&SktC z7zHN$x$ojwZ2U9`R4Z9S%WwF5&q5ftkk6kx{=rQB~^=zCW`EE3oD% zZxkH5?~?wzAn9xt9&)z9O{@7i>W#_#uDbQed&JR0|5!}i7KFS<93AT)ic$Q081E5B zNx_FOHS{U+9&zNiVr-|=@_lTpsc0-~0vR}Y^ z#L;Ri6L@0L^5^_7Df8l5^z@f$Z*?NN6vx#tYRwXvJjKaVV<`tms}9er4R+HEFT zcKL;)UtLl=hK`_xed^PQR7L&kXK(6OW<@0sqjp)@f+7Yu@-x3L)lWVd(aoUA6qE2q zy~O<*eU3rg*zwRqcJ9Moy2lvI{VA&<4&}FApiH15=DvYUe*$DYyJ@FLbK!r}cK3C!6nl z3Dq8-)_RVaAkY13B3J1auJ!spi1(drA(yz_(=v}Im^^v4b)42IXA=D?sUQ#PXA}}0 zxroO9QQ${|8kT3zc~JW$GvHHEtYyqH4F$a0DtTGAQQ!RIMeQ`VmGt2=)NLBArdw~f z;QX3<)&GUgqnP67ICAu9we^z;)UUk>O-s0?-g>wn{cWSB&|44Gul+hu?l&OUTk+}+ zU24+#FJq{}iP!2s6+Yqk%d_djxVP$UgO1?D>=iWRd4hU;Ne4`yvyN&uex}~x_Bm=^ zs)l}zy{G>9`G?ediWfDz9jdN3W&<=#SWVsbom5|$cOSCnEu^zHyVZ?GR*?HnoJ?jd z=c}6}wUD#_4x;x`cXgfqwsOQ#D|&mN(6Xx0NZBHx9yNQk$x?G-rfl0k9aou#wLbG` znY^+;Kk2&OC8Teswes2Y0XQK%B}8>xBmWF`Rd#&npj~6Ckr%pMl{R`!)9!WmkSo@n z4QoGa(=PkBSUz#%7HoMKtkvC_DtC%50F~c0?SnQ$WTRD$x#N~?9r1Ks>-@-M5m+Q8N~A#B+a*>d0;?VZqRa5CCM9;JSv-DLJv zTC&7TzGxkz72j)OP4|6tM?0xYOHe1SldTs%)q3^}hGlD3$Wn#Z+GWdrf>9$kdEdmh zT5}IGS!ps{UNAF3Keqh)@qd0-{%_lG&hWo^_}@JIU*Unp&068@_;qCR{*mRf9mSD# z%QSSS^*+nz3+jQ>*!AT8xt-xw+TQnn&jqgH6g-?~IeJQ{`9+kDV<)!ks*H>}k(IVvZNf}Zm&%b^pblQ$b$P6fB-Eha^!D^>w%c;TG)7WXt5cT*;GiYerKiCeP)Nfsf(wevC zG^bO4^~YQrT3xpX75>*-?X|;<%xev&1x6jzyBnpW$HkfC?q{a%k$fCWOjb~>>t&V+ zH`<}shIMp%YmDWH74xH<3N>VX(a-YR%IYxX=z5yd&dRciuOG}Bypl$LaLZ+~ zFozlqJb3Ej+S+o+n9;O%oMXtSE1l&C3p<+dJUArstD`*qN^`0Z|2m}8y(w~@Qwe4{ zR?;rsw?uxe3B?*u8fzy6c*z*{B_GXwDB0!=(9Wo_ zM&8|NJ&f>j)~1eLAQ$a@0#^qQ(b|Z$U$meBmwP|g0x{y7TKELUp-p2RGZr+t1JB5Ux&79>lDnO+UoZkf-c3MYa_D?N8uf7@;o28*eiw{_ue5eQuKCP!=mfbCN zclLlq;!3*J%gv&xNFqjpil zesbhpwLGy(AMKW(ZRO73Ap7^S(MCj?$bS}2kOS;mYv1jSg)`sh%XgdB&~`n%0gPf- z%XOQlh1lmkmG0c|lAD{~2&oV;L}_?gBTv+>2-($WD3-)~%2zJtp32^N9V=!oksD2S zYV~?w5yr|><<5admSri;Nbw#ld%LZ*{4>^;?(g7-FRp}HW<-sm;0bkPZT2tAb^B-2 zoaLY3Qs0{D$7Sx6xxpW723V+vu3S&QvTDJej@{H$!sqfsETXPm>!UV1yN-_kv&5-M zj_TJgE6DM8Fu&h!h}xsQ8{O@~?+0q_tnMBWBsWr18c~m*N>&5(e@$P zSsmrXa}q5Wb|@r#*+6;B?N;=8_4AP2$CG96{YIqzV5D8A=JU_@k!XL@TwCFxha9$M z8a{pBQR_BSBfr(`R=%9G)fQQ5bMsfo1>YoTtj0@r`FS&>+2_s*+}Fq}#(9Kn*){;px~`Rb zWvW7+J->{HjxLq=^c-@cpLsrh=rK(WIF)D7er8k3zvLw61g^AvQnNR0PU#|lHV(CX za&#o^$gL||PffGD9y*I^RQ?KUn$=L_e0S3HKghpDwpPbjt*2PGhVX5LjryrhL+3iT ziX7UhkNQXcIx20^42}0Xs@vtRphH$i@VM&`b%ScNXzR^yxO0TFdg<#CbfZpv>b!D* zx=Ev6)Gnnf6}7Ze_poe2-Y1=@$h(s|f9*fK^?MrayV*z`Vtx_-G+sudjVr1P`94|9 z%C)rg%1g_r-VGG51Puk59kCprk|x=X_M(mneJs~?^nvf`tLSa7ofb!*zkqd{=TX)! zw^O0Vs>>_=#?eTt9wF8Dbdc@SfPQTc2w5!;kcU`VP|T;NAuAqElFc0}Qu1+?_U+t7 z^5R{D6SNJrHO70$2W!m5$3`8sr}}8*b8bP(3{zX}2WO3(hJjMyjsDs_OFiV}V`syG zTqo^c|3z|-YX}cKhiF|)Cd)pF75Lgwgq4%+a~9ppa8Kn{!OrZp|D zE~kwfCqHj!skMrF35$o%<40&~X~%Wn29qDIk}vhm3@MrLTbeV_OCF8kA>IROE92g3 zWKBCw$Z=D^*}K=u1zE-+7tAlG;Zine|T!VBAm$!|n@T0Trbb5(p z@q?aZ+}m0n>3Yqw=7tgUW_x}4*sC9w<}cl-|AFtIYnl2P|*G@eutSMbv_|{S1QlhsOGU{FD&{O^F<<~CtqB9h zW6p^k1LmCAE_2RVk2&X@75%Hn8J<1gz32P9|9?H-z4vFI=RDLIdwaU7tKNF6XSz2I zAGbZP+xOPXoPC!OuUIY6ZQOdr;5jxCi|q2#E$lUdHH?hGC(~y-o~?R<1vT!8mgN~Y3?r8_I_nNdehYhDSWLkuu}P&IkO!u)Wn zPE&Z8Q{PH<+yxq4%VnCRXiMn$H6xSWh2r z3QwxelkdmD{*U=g*}5*{@H`5p_{A@AaCphxN_7JJ8P^;e`j^mB+V!!}{|L?x?A|hNh z?logB$w6|<+hC1^z>UkSUTQa(JfpB2ymk_c+%gDU0^XR$SIf!P9!Y@s2HbR^?BcX0 zZ;Y^KUXm%|yc^$ch=+S+Y)mPeQuy9U{h>&XbxSI*c*^%@i-4D|rycpq5;()BAv75k zp&MAT8uokT12_32fy)U`P*TEgJmQqhpl{E zp}sh1c23E4cQZbzVJx1QenmI$#Q^i_aYh_^GDTO}bEiRmmWaP)X`)+wEQYys9*olh z);Tu$et-?S(F=FhE|pSrNly5Z))G5zb2J^*Re%zE>tg7!2_~1Bb>QAGC(NGZfT{G3 z77$P;H)enJ$rN0+7c3fkgeUhXDsO!j10PEp`Lou}a`^5^%|j`V{FczArD z`iE^d%M~b`?RbMOI|P6Eh*ms?^P%TCG|ISv+O$IutG0c=lI-GwpUS@ zyV){k->IzR`6Ld*%T{MqI#rQ|Jv8FV=D+LX@-XR0?nJE8Fx`Boj=%KL5RIj?kLQcO z21|)C-7&Jy1-|HUu(Y{KQyjNFKk`q0(nWs*o@!GGvm_d%nZXXY|EM26JmN0hu+2)( z>gf5~5j$zzxg9)f%RX54NG@qwP&;1r-Vm(ieoa>>+gP)EZ_3w`m+A(@tu$OMWkh}P zmO5etEd1(V+4CH7_?=}o_lBY~a1ly>~<~F@* z$R+95QyMI-VYv0NuAH-2960atXBCSPhWG9VYp$$i6@Lqn=e%hTyYhZy2G<~YSBoHM zeYy+;X7!a945ze$wTA z(HK&D47a`(EcFfQfep@_;XSNFq{;rxa7>YWsBh*k%}!>BA6#)xekSeb<+0_w`nYgH z73uEDY*@5F8+>`BtYkNa^D6Uu6TrnoYq*yjFjOE_a!E zhNg9lI59_iU25;{EV|JUoY(2FW3_F_vUTW<(;pvSQnzV#n890Pr@19eHJuzm@~e+Q z&qkZNyk`(-kEkJ_kh!zPV+N{B69Pm(eSX`XdXYQf;_ir zB6Ko5GJoD&T^@bL2!Rtz8nPSf%2EB}z_wm(=6Eqs?piVmE>>8@o=gmp$3N%*sZ-vv zxm|wvv?#Pc8wP2zvs`V?U3R}v7x;F!sQftF zTvqq%0LXs!v+4BKGVH~dcnA$SU}{vTlFtE}Ygf;Sro4knaCi3vFs_wMn+MF|ogxN8 zo0*O&JKb+{kJK)(>CQ^WpwC6<47)~9c}FAN!K+oURNpUHXOO6mlnk);=ae% z&85frN!I=`n0LfTzII2jWGvYe_j;e?cXc6B|JKd%VfQ?EV6DI8bQbW)C>Qiwz@++a zI_%r49=bH}kd`D^Vds3U(fxqE6zaW)AG{WcZz|-Gvd`t`Q=&QZ5@9n4GVH#Cj7 z`RhuZ(RPBNZf7F~9P6yBvAF}AyJraAe|g@qZLT!7yi6b5Xg_z!v1M5yuel9|#uhf^ z-{b)2qx~?kWRj`+as%M&ia2$t+0<=9Q`lBHKOT*KZA#zK9S#MY=i40%%VWAlL$7Pe zJbjrYN0v^6z)K&^x4&1D7vC|$w4AT>1HaXg6OYG1k(J)8>GVK(508RLG0W*}xDdI~ zg^mzh<`s)s7$n=7LtyxtQsDB!SN3%Gg!J>(;ob>v`SOBduwZ*AY%#jXY4qEO!Ie8h zzE8#EB}W&q#vKO0xF+eQmytTQV0Ap?&T-f@nGUr$^VJC1K2A1WJ6Dj0L??jFmWrnR zOQ-R?p9VtnPx_Qa3$F9iW4c1^`U@TRb}x*F*Efd2r-OBNL*4OX`&uw`&>|fh8;I+F zw}VlJi@F0L#E&|CX7O*VB%gPEv22$O?0Gv|Y1XM&ip2&j`cq}eeT@-uZiwNEk6!w? zHW3rcoiy)v@{^A5kHOk|hVsDa!P5F$J<)#2QC`jvB3XjZ<<2NN>y4L5Dof zxYQk_-isyty{a#U=dUV_(&fZnd0Juhv~tpsTl;yOZ6rPm%PS=`9>f#J4aQM6_jI}5 zZZ=>1nuu1r*63DGjW-00Fk-ocp1KQpTCy*0u{fdqZO1K*wy~@i`ry2NVN0SOd}q&h z&^!Bnc}+EHmxJ*s{&=h2aMOqmdKl5NGCIH8Vfs8E9Il)#fEOOTFnQkZ2F^Dx@wPb% z$w}7-!GpOIc@eWt4!xED)zh={VIkGzSuc&Sdfs|{KztoJtU^4*Jg>sKg$BxVJNAcK z`%TP$Scsf+S0|XY{29A{E=Uf2(g0FRmV`SU>&YS0y`b5^YVdkUO?icL2{6xX2>KST z^5ywY7z9K>@7yKi%M+Hc(B1uE*zxbC+uoH}bgOt+y7#C_+BaU`E{@1JT4Ynhw( z-If6B=X#jFU75^#CJ%xxb(*F4=lY#b?%WM}&za)b;6y>(cccmEj@8$lmE3S+iVr01 zoUc3DGyq*Y+QYcn=X6Pp+oAWxbau*|UCQm-7gv?s!WK6xEv<@-#fjs?Sxwi<(%q>> zJYTVwA#kye6n-laU$#K=xZU-oadie`$h#qYb!4#AI<*(J`h1YjZX6=L>)R5WmCc1G zngvMST>@}#1ABC=RaX+{go^(@uBj=F&D(FsC#vPDj+>yX?Q745-Hu1!q4v7a{qxzo z77vXur})*ht+|<8(kc<& z#C|iR1^CN5+@qm9E`#Ul`&(P8Zg=Hpaep1{SQh6S6 z))hUs+ekyR&E%=`24cmEA9cki7v&3r67YEUy}Bah(dQ05*Km82tn2(c&GprIOwMJm zE7gAPTzS>h*ta9xhc~=#_gu1b>nO;-HkJPtXD7SPj)Nmb4E*s5ce&bSBghZ)ncW5% z{v2}b-fuZudUt#7P*{drko*iaqni}<(dzi8u`nklNfYO zcZD{2nS6R`d03D2!6~MS{K%9I<~p?jzP_wnz@Ibk)ZXy>-Q4ogNnO~hxFO)M_J(Pa z(+tCcP$R9wE;qf3T40{)V}$gw?M$ZYkResLE?09iy zYba5mq%Nt0BW@~QAG)?3qYEesc&e={WM95Z*I-REyg4v0_}jkIb)7@&NqtV!{?8)P zvro}Dz&wgYEUO?bY?X*n*B=-z?5{2@Ib%fUP9@FZiFKt}k#X3R*XEUf50u8{ioz;M ztGNH95NYeF4mkDxTRMv}NUAzA7(WKvVnVd9Iv*y*&FNy(jxT5+>!(BTuZ}n>Dhg zwYG-0P3)Cy80k#8|KdthzpzQ>7VRk)zlkt4>(-G^-8KZKpFEdRrA`{x7w!XnYAq=L z8)ikDwQa!qbYb1%dk)yOp&vL8Nz!>;G~iWU5!PCB-SW9jQ7V}qY-YXIl|9rQ`xiXV zVyhLF@(zf`S>uw~!<~{ey?i3B-1XiNQ?j~r{k9Ri`n*khXH{3SI}(R!Z@u}gnSoOH zx+n}hvYb~>rso>wj<`MM72iEONV=99f+r4?!b%T)rF~wWIObG!{Oz>2v_7#I?mHEV zpL@GVRtF#O7WFz~r)$Ne;qeQ2jot$=%sySW+*8M2uZ_nGFAwRyB$Z5aNjKvDJ(G1` zZxv!&BNOPI4_Do~SJT+aX9F=MhmYgibJyAWxUN_w$D)*rLkok;;>MV#Qiv(*R(Ggb zsTQ`syU0{vWgx__vqPIP7fsf!+Jm>}XZ|*O4!K*Fe(>IT1E15^R{ne?7CzSr;eiF+ zzUBdLT?V3dRw&A29vZ9|{fyY3Z^r39U%wT!T$)1q)-BDK9Cq%9tLhs4E z$PIp9{pHUk>OlXZ&ak&4$kP`|FvZgs?&Yg0m->^N zLw#V>gXZO{()*ilSJUqd%*?Cn*}fdcC;P*&VZ(Lq)Ad-bTxHlFu~T<{Y&h21SOB(^ zeyN-Bx*JL>FR>5B3Q02_48qX16WP#XIw}AC1k}CA#@2MHCN+9t#5|X_rTLAkBNcRv z#}(cl+@^7$RIyoq9F$w;ABTlVw^nq*9O=*ai<3dp*CP!uqFzbd*tDK>VTu?TP*W^6`f7kh4ugDv>i^tJw+B$*zi#qV}WL0_Hidy?O8gBaABA&orS?V}2|- z7V^}7mQv&8Ca#a`3x!TUa9F?kEB9E|4vzKAp(}r;EY>|30BPxox~Kpjd^6e&Aa$EA zVQ>?y;$H}kEqkW^D~?iMQv$AEmWO$+@{&S68qwV& zF0Em~I?}!9c>Fxeg?GynC=L49AK%qo%qK;MNN&?2@J-BP-Ya{s#2+`rerd(A@9uh1 z@V#m{($NbGmZ~LXUsn>{;~HQkw~A8iq368Kz)tujy@d4qfy}d2>5nm4vPwPLdGg(P z;&E^N6FT1TXxgbK^d7?M89K*?Sy}ft30O|5p?f%F0*lBUje9mmIu_>_*>RWdxGnGK zlp>6tS6&Lo0c^&8;CS zPYd`ut-QSY$T8-*n4V!7^UE!74`ZH-Vqp5$N2Vi#&ly@TNQ7hcHkr)l!CZWs5x$m= zHr1FH#9O_Lh2rZzrL3;Eo-cLn2j-n|<)olb+-Yum;FG^Oj`6j_LRo^~?#IEpZqI6B z%qMqx$6~YYOsB^9n72^~4$E0dS`qY`w@K=Vck`8!tmG9ucXAZY zshLfBbfp$wy)h0W@1D}_%421IdCiDDjk9$zH(wh@dL&|@FoSO5`mt=rZ_zmK)^NwJ zRnD!6h9i}S&xM@=#0Wld9H+ltV@ong4sEK@!kKd9+e9$&9GY5Lf&4SaIW zhA;bOm6zP;4b6Sbyn0wk`Qe-)^g9$0{8ds#+0fDmC9+MS-wm%t@3s-1-(O-lkhQ+- z=Q0G`YsQ5Jrm*Pt1TwG zvJU2e<3>38HqO-Vd|iIBaUAR{mE9Cf@Ayx<*bnYiOy6N>A;h=#w&}HgFoqv}uc*O4xOWvGMit-qU!#2!j*WWlu zu{H^qyGdy}x7}0vPWg94-;?gKFrXY&coLZq+lx?q(K zcer!MV5yi#Bii?6gOz90mw3E4o{ICpYN0+-+-_TJa8haAjTj~Q_{%+sABJEZqa#DNjMx|AD9%%)@v z78*LqamB1tEbK@Rw6kuLvMEDnF}ggp+p`n`fV{DQ{?Mgl6NX z8p3AOlPAp@0#D{fFyoyddFs{PusO)g3K>J>1>M^~*&5lvsYalj^u{a^EWu^l1#;XTJw zwMyf#CL!>wL2q58dkx%owknjbuuhj~ABI+ii-GsYd%71RJLBzx_u0(f@=8}`4?shY z`Kkh2aYcH4soe3JINr7jwt7r+ZLq@wRzY|nrLt68|B2^Z*dE(E z*h<`CJul(W4{NWmlE#z|;_>fe@kR9uy3gIf+gR+Z|AwxfJiscJ-pOji=By2p>rU$f1?BCm#F!AdQ@6HYGcpU*O$?M>Yxu*B1La@_ z()-WbDuL}=J)DuN$$5MVK-VkbaI>8xFHF72nz(g`d=CoAxf)MkWeY^Zv<D(W3IZj@(^WAgayL%@n z)#b9|`)wt0%)kaPacnnTj^F9`V=8;WlJ2W@^WQf_$5q9_xy2pbl?$fiX^E#VJDGNua)P3->fp4slT2|z zb>YDJ3V6_X(DbxpOL*v&3-=EFVtTc>7kqO##9bVU$){m3Y$+7W2fcQdgRdq+Wvkuh z*9qQo^_fP99ox;2ZLP0dvQI1=iVA1h1_#Oc0_c6NZ<|?OTI&w$&<<`aO=nAY2g(Hp z1;F{5_K;M&E^#n7*uTUFhP19OpFCL*_~9nt>svv#_W7NKw&(`#*^0>P?SEr_LkGbu z_SQ6aVs2*Ik^tu%(RBZ}NogK5?=aPe@J+>XG!sX zPk8C@2rwKw=D6Rj1lF6`5CT#=>g>mP;h@B7;Jh_e*ZX(_EMBK1Sns^4YrnY@);j%+ zjWbwF=iBzj$lp!Okk?)+q>INB4j$~{-71nT@$kCYcIZF0U{e3v33#$ycHVigzm($^ zapB~N+^bNCl=`$A#_zktKb{Mgtdqkr$HoGfyxUKDIaH6et5?RuI)gObP!5;N{+OV5 zm%7sLCePbQ=Sw--NfX9w<2{e|!HW5FNw-p3@|6{0@yxW}bqD<7&C_Vjv)WXX?nS#T z2Kh@O&b|?@i##)sb(%UDb~tZqH`p=-YJ;kWRnw07i)!GQXNd*Yb5yYI#4BNn7)AP#d;q76)-)FWy zYmgkaDiCh1v7hvhYazrISnF3xy)7t#x*_JTd5Kbtsy1xo+Ol5FC806z~eyb=41c z#4F*i*sTJ&rC!^j@af#;jOQsUEju2Ezb*4-_3f)jeWk)$#=8%Y8i+(US zxAT{-_KL=}JefCoP0uy3JK9z|Py48YrO&gQ;=0oL@opJ^>GOF5*4R}MdzlT=tV0f1 zqN^V+%vVL)u{tYG+TI4|mMbfzx~1`ZMf;#b&D_$Ru#WuV_93{Y=5<~A(+TGOo#KIK&zAJ;Xaxi8TH~xJThnB3 z9h~b_4_8|yn_64|a2w%*>wNc^>iIQ?i(~WP)uHcAv-0(X5q(bb5ig3!%r^!aEgZ?q zxj4z+X#M2X$?Ilow;FQNK_gts?rJ!)x30Y0I}Y^E>#=g*0_ADT`oW3WYuGND>#2Sn zpz@9PjNbT_M_&vAedRJx#?zPH2ljwN_r0OAD;xMUr4gJf;4JT{cbjFGyTH-P zMde`&XR+~Z2Eru6C(~V@l5D3_0;F%=XX?1cZs$pQhLu!rya~^j;Rip*gKKXG(~;A2 zcmb<{P>0*3G;Dj97cbWZZ0B!ueEZD?ciawxGgF%CPTlgrZl%59cz~?iH9Q!vHn4@R z^M2R$xzGV;oPNu^Zse5q6^O$9ZC0@yx$LA;{o}A+aBX&=iMtd_>t=SQl7@DAgB032 z5wov(V1BjBPg?UP8mm7U#T`xuOG793K%2Rzc|MyEY5dY=cw%T?3>xGwx!M6wI?}89W5Lp17&YGvJ|l zXp2PjxVBaIcIh@3+V_F9e?v!mI*|5s;MET<67BWiwATY$6fQ2s)>y!44+!pj^;JiE zLpbdX!N#Kw>cpNAv0p@dKU4m9v%^qCmV2p~w>D+s@!Tm7KCXG7ykSy5tY^2Df1p^q zNckZP)vX1_OxZi|sM|Je? zAnrH)b2f>-2jYIy{K`nwABg*XKT}2A2M&%pF7(o_Gtx_I&qyyx?FUFNN$npqkzQoyp%@Y}g8nM|v@+&S-2dL)!!+IueHA-c+Q-svmiAQj zRqU+ltJvRiUM%P9zszIC{HppY^RDWv_=Bpi;wP%UivOtkDt;yAUwmKqo24IG>Z@K? z?4Y(+>|<#+OM6<{+0y=&^I|z)HfM`2vzSNWpUV8Ic2MSBwU6Qts@)VnQSGVtk7{Sd zuT=Xh{-*k;;)m2vmX)clxb!3wzMLs%+9A^i{`o!t6kh^Ug>5tCOgm)yz(3IkL~My1 zCb+@4M?Uzlh_lGy>|g^=JVwtR=~mDXB&>DZM&UR^Di*uHd#xJ-{^rwK)%J=V)P5BE zsQoK;Q}3(TQyq_DXLX#4{nha+^FrKI*5-@aXVK)$x%=T8|7LUdm-#2fosQy8_pAMr z;%@0*>5~+9%P8)a{c1d+xRW$IQR6Oi?tWnM|8*|--`%^*`;C zDgS?D6V3lfw^CZUMgh4I}#Jt(R!!&3>DY8ki>Oy48^hf-cMf4-?A!O0N zdJpBkmN=$e{ zZ6V}4X94F^S&pIgAb8GOHtgUP)^@f8l}8kYmF3 z_8BtSEdx&oAAsqks~sE{y#}C%e9@Kk;R(9 zkI#=amH$b$T&wv9XcVOr@ z)5Pbmd(I`^h&eu1feIJTmf7x?M@gAR+lPzU2ip+WZzk9y?zcG)Q^Of=Z z`X7ED;D2MjEMv`5&YZ`8uX)UzuYa%kvWzuLIddNWUFK2Dl=uwI;G3E94~t~lA=3_- zK9K1HnLd!=1DWf~iYYSJ$A5T4rX4cvkm&=NKA`!4_E%UWQ_l2@OdrVfflMFx86ObO z?={R6``ol=V`6Wbwr7m`$#}Pra_~f6Lgjr}m?)390=nvU*=drfxIdNm9qDTvx}h$YP(KRzHdRYtO*MxWxFx z*ysb=drm?RaX)cU?4c9)6Egif&>uw>_7L|I*M*(L{e&#+r|sEOuPeH%?G;(=NA#uj zugL0s6`B4?j7O2xaVoMpentN8p5JHAfz@|GWG4g3n;B6yF+$1>&2XP%ipkm&=NKJbtDz)%eM)F|V;oBv6scVZ+B zZ!P7&q82_l>K@hJ88z}>UJL&x=_u@Iajr|IoOy0@rVsoRePHkHvQFALoB}s2&h^bW z2be-I<9uMTUSV;ruQ;z*JJ(m7SFD}uE6yv{&h-`N6>I1E!o=U_%i?`Su}-L+V=VZ# zcD}J#|I^Mr7VD7OdC2O0wR3$l&QBKWgxa~v>iCs&eHY(6E6yv{&S4hk6>H}(i}Q-L zbC|_>#o9T{;=E$*>`ifAv2vcUsE@Sqi26tyr&v$b#xL?rnYUS&9glgaoQl?<$vWomiNfBG}-He@>?6favnuq`z!UbI44~At#(d$#`)W-pZ`Dmr+Qwo zc9!oi#}kWl!hfkB3J$5wSLWRPI4l1DH5dGE%-z*jGkL)p)uHR>@?a@H_KU%j$@Tfe zwN?1Gwnhxt+RW^eueMn(mx$g$+YE8%O$PtD1F*-Op6urNM(mq=2mHpiv8baa)^S=r zd@<-P`?B;3n{mVe<8Ro&=ekyK!TmM&vvY>cZHvRN?tfOyK>9uNPVCgoAZ95)A2E_w z3-yLqmvvCdda`+aGX`8T0U})3R0Hu1lK=%&w*`+DfAgNn89lWIEoQ&E|2J0EVA#`~_@ebIZYdYe zrH7UYS)onJ1NPn2681km#QJa9$PR_}h1_FC(+@%RXD9XX@Vq_!R=f8jLyb2^`VGyf zwEO1fX@Oy}Fzu5)|5mIZ-#&(ZZ+ygbZnHCq@2C(CHq+1Z)ZEB_b^l2_D#IQr9~9s8 znOVxDBa*&A`ZA+mK|EKkEI9Se5A$ao;-eJs0kiMuHUo@o_RJmCJdY@RFW`BTz zw8RyLKXzj~v+5z)*%{`Y-^`k{uL?=Y_Hh1CPWbL!9#TsdhF{%3`8jBDWGPduF)i*W zE|?Y<6fdB~3&jy=aYXS2T6|I5ffjcZkD$dP#VKfU`m6gdx2Gf9VOI;5#8d!FS&eH( zxWR5Zb;Zz<%UJNh>1@NI5X7*1%-;4mE4HX24w#l7^3+RbOIlf>Dclj-7B2#laUGvz z=LxI4%7Nc%M?SB$9-a?&hFq_|>f3B%aACTuh8w@Ke=%Q5|LS}xGU>=QeQ7*t+IVQ3 zOdBVSpK0SKy+G58^aV{{vIA&#Ap3x3pI_a-iWN#6S;`b^sKp({1!{3Y@xrxup*Z4N z98rAfwfLgAV_Mu%JTfgFDNaF)(_h^`;Sy@NXDO?3t>7f#7-~31_=Xz35$>UedxVFm z;UVE9YB)*wi5h+quA+vkzq)_QBTUOvmNMls)bbkT9n|s;Ay~D(GwU_1IJ1=1yor>TG0N>G4;Wt&pY$z-&CiuW zNGgdAy>esjHwMgm={t`)f0vJQXpOZS?B|yUujAQ5`{C#bBY4&DUcB?>c-;Bzjk&G< zih0*fBOV`DE_PaSL0X1!win0Vh9qC;%dBe;!#}10Zu%MtN6f)N10XJ&=Zf+ zt9ZhQM==#=81X2k;twMp#eQ}FD&8XTC~hgMn6KcWiqA+q3RT=j;!&vLITDXT73Yz7 z6sq`-#G_En3rIW))qH`(qwrVvZ^{ix2Dq6_ILc%!1P%IlQzsC-Wur^*AB z@vHn$(M#oxioPnJRP3PgOvOIGx_^~dEBYB@`PKas-io?d!E;Ml#VZB>)jC(fXSM!Sa9gd56+Bn#Wd-NeI$FVhwZ2yJ zf?9Vg`QlgiZ^>sYWy;ZF-9yRO>biuIPu2AbCC{qs7)t(C*Ef{Btgd?~`C45MQS!LD zPNL-ZU)?|P86bYB@Fh!GSeQQN*u+ z_@TnDh<5?;Lxpz{9|Pit3LpE6`d9dpdM`y*byWDUIv$0us^e66tU7*$->P~kyjRti z3qGvcLE*`&eH8xutNT~|T;UZzBdflu%;P^QZ%N!>-d~JC4=Y#tE$s~kO}3o7$c~p- zwilJaV|8hGc)kcMYfuIn9M3D(dBnQe55Bjt5p2J6h21>3mmSI89Zvf%X0K~cW|kPc zAg2+|=1DRHeCuscWi!cUwT+U?)bDcoE`Rf*PfmUQVO`Er$Li)o=Dv3g5O~Q2Y+ffB z3Uy;(-@p~tjOxzjoUIAXs#SnuFZQw)fmPt~DmxhHo(slUmxt=l3&EWuw1zdPAan}L z0@?4@2UhAeE1!Jn55H$RW@cZg+4}|*@+wy0weth8UE-?D=a(?i`48E;+7&HyM&exni@LzQiHR<2@ zuxkH5yROak->qjY=gv}Y*6=Kwbi6XaKwG#{vj8+(Ru-Zkt?!cR@-xG&((f7^~2TvIrY!g`y$e!It@W8aZO>fZM!W`HJ|lP${fyR}7bxvc*%|^N4yU!zPyc{4LrZ;CY-EIuOvOw_ zn8{QuWrU?n#aIJjtU<-zG{W9A6_Yt(GFP#h6ILs~f2X}up<+8HZ09QGBVj(Oxd15_ zpqe9)as;Zm11Wc)np2Q+3aYsVDc6X&&hQ6S)-YLI{~1~FrN7h9e|w#PlK$(Ltmr!OH-X{e zx`OR$dj<2=ew19G_OIj!^}b5(P{*U>6m^_RuK7FmQFQ#7I3f;!#48jIK->U{S18^{jS1E)IJriqQGX;Mv=hV`FenzJ63O=mm_kT#HJP2AIr2NRV{789|X?c_KDbw;PIep3Fs&!g$P|Ks(asdxTaIrpE1x0ZVSJC0xV)gN{1Pw=as^nr|g zWZC|&%uOm^{eQ0I|J}#0<{%L7BmIo5V!npk88ygHUH=#3CqLr@mU^kVPg$2xbE2|d zq2@|u9Yf8b%KCc^H|QQB^LdRtm>}CzL@KumVbsH{*3(zhySwmG)sNeS{ta=2DJtU zs=-06&4FrjP-}LenjO?y9;lWFwZ;dk@jcKX`844UN<4W%*EAL&?b*5dX z_DpL}{V=T`>L0ZJ>As-dm&OAb<8kW&+BhxeRJ{Le@f*IG@{iwd&9p=YEM} zvtN0GM=uE~S&d^$Of{fm9i2FbA!Bd2rTk~@)jbq{vv+>uf~wGJU2gCm`Ifmx)PR-c zbHEGd=VA|9##sTD@_*C*@9wdsK2htFzKhzu)O}~#crx}E|5`2{)h0;x=c?{V z_7`U<2zzRKQZnQ}Yj3&l(o!zmDH^x>g!22XYVyP724nftKDeF7bU%PGCqXgw1@j;!C>swQG)8>bD}8z0Vf5Ij}0a$Jk>D zhq~-^OCM}K#RLsB@dn99Y&{d&rMl6-w$Kckwso_D7!RXn?o29MftY+6gXvDhAiLFXh#G zctOLq4zMV%3y<>9LyacR(5+idac-OP9Me*^oYTMJoH{xOOr~?dOuzbkGdeHpFFmJ@ z&Rkk%b2j%f_58YDb`F@Bugr5hnb?<+X@`H}d6k*=bfxn#83xY1W%x8c&`{4I5eEGJ z+VHAreZ!l(3E*#?jU}C|ZSXK9z~_Z|*zHd~hOF%qfM0IHLZfmRrZS?+zgJrw}z{Ya&VTvDYR{u7otM* z@X0Tlz|LLy;AYE$-0Eaw2)a-L*4)(dr;7q$SbYaLIjc7>oMr&sTW9EyFq!XRRpID% z7Z^NtD!+593X~n<3Wa9R-~&gvL(!@gA@8c$e7K_<42!4&yS8lN)AE*w2C1H)>v@V- zUtSDar+Y!gAy4@=TWheT_ej6(c)>p|&85gUzrN;qtL9YNY-I1bWVTYid#!>s&hGe< zi9RP~DS_AKTx8;2kCJqltrs#ehHeEbV40O^OpMKQrW3N~+nE?M*ty^^udPhzvh!Uv zyj^n<6FTm7tc#WVB{QLWOi}~<;uOh*O>7P|#6xm7CTul0R~Qy`k6^-vbA20Ou6^y8 zux(_A*7$vTEhcQfrDtc9SZOBaB0Mk>Z&&(i5Obs}+Z%0by*G%toBzBw_UQW3Am((- zjy{-e!()S(>v?wuV#)$;5I$f2SjYGc;gSjst9A2iK-7-1MP#|YKSd^TK( z@io*uk^uQyMYHBa5F)z`hCusGY|hK>X-RYY!lq>p*p?Tg&F-lYaJNhz*m*GrZ}=h{ zLZA$s^K8t$ulmA-wJy-4!&DyhwhGkFSryI=*~PycDg%(c8bsxN!DHX$g5*h6q0hwv znBD6>%fek@QKEz;*O=MiBX(eQycT|$Jd=$ol@C^zZHVWy_hcJ7KV=`Tx5Jsm+}QZI z?JUcLNL&%{*%11DC>xE@sBg61P@%pxE9sno4WdUF#%}Y|cb;yMqBO2(e46Q+c;U5pD@@q_kp;wfVK=|4ymhNWux6P%dN{4) zJBsPRA!h~5cP5F0RSgkSsKwOjxE%PP)l+lsek~y2#dTiiX%}-+wytpH&??@8f zaYylpT0Bymq86tVzo^A8#WiYiP4SLeyb}(fh698xsNn-)3u?GQ*n%3K2wB4!(MH1` z@m&p&)Hrk|ux@4@y)LuH`EiE%KYA9oILBP`PfPhf zsUD{|6&wJF1DI8A0K^T8P66UJW;J&JaUrvsQ-HXTS-z)tmyvskoX` zfVdV{a|aMN<7!R;;$~dUH9*{qt2qUT%W*ZQ0C7C7<`f|A$JN{c#1*-kQ-HW4S91*z zSLA9=0pgZi%_%^fldCy}5f?=@cQE3vsOA(#+*Oe&*D&I)sOA(#To=`x!iWQ-no}5Y zV^nhoBQA|V8aV|qu^%S*R5u2+$9v;OyZYWz4*c? zxLKNab_h%V%mp`V7ElVNj5^B&H+$6I4Mwk6{RjUM+-%CJCh$0=DHq(VVtOZd*V3K~ zZuXA#g)QIjn*}$!2!kPf>Qb}dW|Ma%z|yXX=6$=TOM+7qw>Ar2-Fs>RG>jf<7QFiQ zgcw*iex+IP>dM=C!;2@c%z{^cY})}scRF*ytFzn>h0{wTxZu^FPv~L#r>R`<>H{mC zAnNdTE_ihg`@&G5+-)v+b?;Sg*w{NcQ1I$(*85pjERBL!FW51Yz0c~7f>)>dv|>qx z>Z0J)x!&bt`CBwW!K-&am};2cq!S8W{p8wg{j*7ZQ1I&P16HN|z9t3*ub#9=Z?4%h z0R^vaI5WchjJUPs{94K?PcRctK$RybGPM!4u;LE_i->zDej+f6xQF5o0=tNND1JhI zC2C>CugKp-Ev)z(`KPFb75^l^6*aHox8$Fq7FPU|{8rS+irCqQS&Ns zP4O#gVI_Vku0@Tk#5Li7sD%|AAbb$Du!0YSC!!Ws@I=VOT@{=Wb+LvgLMHC2;Eeb# zaa{$MM4!Zg6}%E-Aa1PSn;08$X$AMh7>G+N_$J0iTw1|Bp$l6gDBQ zuHdb(6>)n7hlNdu+bei0Y(?B&!C_%rss$9>7B;6ELBVq|M^rl~_%G&;Y7HeXh&iHK zL&1MBcT{UAc|puI)h0?F5k5dQi;`cattpbW{y4+O%U#h@j^1C;XAG^iOip!0ujqq2 zW|6#ra-FJIHP64Wi4A9uF<%BMMeWqw5};M1{1(dFF~ zR{v0S^pAJMn`g!v9(Q24(EpFm7c8GO{Gxj??O6tm!K{se#>Ta=(U`e5X3_;UT}VgN zbR^wT)1AhNnoTTa(&aC^SM$IDXdK&{uN)N4U#Cal=}D`3PQzUO-7ORwJKyA`5)bk4 zw$*TWYEHay?tJYuq>MG54F}g7F(l;7HHKyt8dJT=Ufdqfa?;y^kJ0 zwRZl4ul~VrE!tRq*RoH`ds&Xba%`4kw$#Pa=fAFpS}7D4%PAJVtcM+%Z0YC!Mb3z+ zKl`qwk6Fqz2C%RvSlAOR>>d z$}QzSZ38h@e!_R{JHv1GazodZdGYY2PrPs4f_S5RS^Uy3KNhcdnU6eJ32%%ojm~=} z^8Ty_e!1s}I4di^?q|SO!7kWu#S?wsoeXEpa>X6Td|3IZKDc1N6COI2%7)+a#20tU z{Xw>DWBFanJ}vKMIR?wIS&rFKmo^pGF)J5Oe8S3Mv1`8eR_F_pV`IT6*Hv zp5^dufix@z`X)qNGXcWJvXwpTdHFFOZI<|fAxJWb^ICG(#L*A&hz{OoBp~2 zPH0>VZ#0|8tb=M`i|VAi_-!`@qf zS9Lsp<2c3LJp^~R+#OttySs%z2oNNYTwDqiEmE8$xKlj$48@AO7HF~J?#_R9&Yt^U zzP$JQyLn4^+uw8hJhY!4=A50KomrdD?yY3(id)DixTyo|sJPyEGk(7DY(+(=bM}>y ze${0o{9am!8#f)6{PR2Pn)aCJGOQq`PnA)|yRhP2$5Bz1t60$eZOfwdV#$l5_$Fyq z3_rhC)Gl5OW7Np{nIF26an%p#v9`bc8j-VWF%0gX6=%#`CBnmsp?!5$bVo+F5A~VC z>NBZtq&cL5<4*^@AVsAVm~uV$o=`LUk79DA5V0hc`o-*ixPcTbE>XA7l36j-!XWIVR2? z2r&wmG}1ozGA3vCgDicg8HuiqFn)Q^9Gcqp8{^V#G-eN|2&W6ZHuAr}Yz(cP6aGk= z49o0{jyjI&a`ig8gLNNs2mg?^0wntJt-H0QBjtwSkQee)$|-NVstX> znwgeWPvpRk^-`ifZbnvq%f?McmQF?S*pFFI$NtkB7z=h#9~dha z?pV^m5o40T-+Sl9vWd^w=IpcK&yGA;cqgA4}vA>(;E?I;u%xc z_`}g;qm9j{{f&ob+d#SVI}E>=%Ra+VU9Mh7cd+hb?%+L-dO_gFvBr}mfySqw8o`SB zr;W<_4a0YFA*gpUKCK;I8{6+k2e0nlxFS&sygzV`@H$cgm(B6QwQW}0>Sh&qHc?*O z^;aUJ<7*$x9Xrowey-~f6=mr*nS81S1ns#ihQ2!?zB9T)>YR(k&bU*Aclsb0dfiLp zU7t*hB2H|wsi${*%4+QRm~jxCK3B+SUoDf-@_1*+n|+z_w!;kLZK7%r`}HGZ;Nr8N z;ixFfRV?WKwx&%R_%nsWaAaC;g#FbT&ebuDz)~wd^FvoMuKEEz*6s{z4bAJJu`km~ zqfgw{kmiS-MwgPS40mL7Tb)i@1%k&uGv=PWU^K{B39cr2Wh{7m$+4jG;LycHZcXS+Ze#dhA5UBg}J4d7VR~T>lux`TBe za|c&^VTb$~T1WKQT_vK}gn_XBL`mb9k=YF}I>DpnD~)RvXB%b5R)N|0)VQDdf-!ku zMkp3L4K7L%7yl@EPHgomfPF5e$B^NTMZEcCi36YWGe6gLh>Egwn~Xge7kd4g4YsXL z3f(3bhg_B7!sC}uMESsXJq*YSry^fj@KLSBy?SNPrRnr8dN2O5t+_3c385vV>NXgmTn766S$pvDNG@kpq# zL(q66)R-b@JQ8ZG5i}kN<$Hq0Bb$z+x?H`E?qJ==+`-D91@#p|^&vLuLu{&VaZuml zP<@U;eU72}B7^!OL-kQeeUzd4E~LKeGe6gLh>Egwo2WhgRoEO!3iiRFvf^7IYs|eVU*?&8GS~L4Dn4e&|X@k9{5M zv8MWDL4C4K^}~YtYMVPUx_yp*q~BcbKCN8&3nR)Yyo2x#ecX(!yqfbPtv6A}YTakh zdeczrO@r2(hFWhLwB9t-deflwrlHoG4q9(I)OyoK>rISgIV=(_1T>vd7<5kYHnq1Nnz*6c#9=euz+e9fI~l zgjxp)+7I~*M|HV+9o@mYkGX@@dW!C7JuB22R?r$&sI{%2wXL=0Ek|qKa%wGX&|26~ zYh;7g$c9=w8?<&dT$LLYW$89idk8>#2%z>Bfc6$Z?KuGLIe^-W0NRTHwMPN8M}ILHQ1$@*RTm9YW0XOIW?es9H?9yP(BXSK0Hu9?lTLPIz&ZTx=mCL z3n+&LDz^oc+X9vI0?K)T%7p>t!a(K7fO2G@a%VufGf?|=f^up?$5Bz1t60$eP33fe zayp=LJwUmh&-~Dpj2`x#bu|6v(UIY-w z=`-xkyNVAZhz}-otTsS&#o+0C9Ujaef4GeuUxz z3E~0?#Ss$35fX|!he{}J6%e-y6z2+va|Mcv1;oVy#nA%d zXo2Ex0dcoL<%@whU7z8oD9cqW=>DcSML?V)P+TJ*uF+?H=t{;_KcL5&;zR*)qCoMW zfVfiNj*MoWSg`Zx8mbRBfvbe;9OC_XdLxd2d{XCVGFC_Xb|#gS&2|G<*}|6ku#JYLJ5lGDqW zbdY><%bt=?ZrM}v$t`rK0I;*o1To-kQg6pWxR&d=FUy*I1W8LOotE~UZpw8L=owbp1?exR{A|rYGmft$D9;fO|4S!Rewc)bdk0$)_lo{X-?&op}CgxU7CYAze#g5XIV67bLv2IIj3$k$8+ke z*M-JYgZT42x1>3zLHv21bJASYApShhMQL0!h(FJBR2{qXF3oL_`196$-ic`rjKrU} z=JQDWd22q8#Gkk3^GN)8Yd(*}pSR}oNc?$gK99tox90N(@#n4iyg~eVYd-J9QC+U9 z`nr1V%HLc)r}=h(HzVm{yfjYXl~{p{yfjkXwD{xKhJYEn#&2|&+}Z4=6FE- zd7k6Z+z*I9&vU z>sXI9n$sG@pXWI(&0`JX&+}Z@9U0v|>dX=Mnd)p2_odWl%KHp?Jc_J5?U?}a=dJxZ zC#HQfApX3yUnht^Z|&C!;?GI`zlEMdEO({u{-b5ei{;g-r7%gV%md6;?GTpYd;x@KX2_P zBk||0{bVHmytSW<#GkkJlacuI)_yV)f8N?pM&i#~`^iom)#bXXudC;-{LR&K+K)ow z&+}d%?Exb3=Xnp1_67~&&-30O?HL-xpXWV8+Do(%f1dXeX^&A5f1dXkY41@Gf1dXq zzhzmv9cT|0i9gSKu(UUe#GmKAS=zHj;?MJ*E$!tZ@#lFjm-cv(`18ESOMAaa{CVE{ zrS&Eff1dY*bsQCC>He={+N*T>80|?S@#lF@lJ+W*`18D1>5dHTqdH?>$9k;Mo+=W5 zp7&H~9~Fr|&wH)z$msT=H9Hc2p4aTOmN$q$&ue*ojE<~4>}#GkkF#Rl=`t$eXT{CO*1jKrU}^2JE}c`ILx#GkkF#Yp^lD_`uylv8%f zP_EheF6E$|-=y5Mvnp_- z;wi6(#GmIJy^h^^mvXyE{CSJd;KalMK;q9^dud`XF%f5TYLs2{=CI!K;q9^dT+Gx*VS`Z{^sgAtQx$kdTmTm{)03h+_nFB!F z03`lAa|4JofW)6?&H(Y}k@)k>B_NIg5`UgK2E;u;;?Fbpfbtzk{CVai=r}6M(*0k@ zls9+!80Ex~`170-r(8J_f1Y#Y?#NIc-x>Ql)?IU~v?5f}3n=aTd>I`gE*U|YdaUh-FByOa$EaFT$ zbs#RKQ#ayRI(63TLVPwP{ycL#iSvoXpJ&b|aY2#z^UMV$UKtX9o;jjAcIRE<6B@*y zxA?S9OdM2$`12N@7KuM^@oACx^A?{Li9c^BJ}nY|-s00D@#if*EfRm;;?pAW=Pf=h z5`W&}(>iffm+Pv&uAaN{H&@SzkB7vcXRaf0Ad&d<%z-3sBocp~xsk+~MB>jgXOg&- zNc?%`QWD3~ApSgaEQxz*5PzPzm*281-44V-MdHsh2bH*~Nc?%`rV?iri9gSrRpPQD z@#mS#N*q@t{ycMBiTjGgpJ(nX@okX!^UR6Waa5G0`@fEftLgMH;$$N6=b4j9TumhY zJaaYOks%(bGxl|?#~N`;k@)k>DJ32$5`Uh#rtZk-_94y^5`UgKOT=YD;?FaeNgtyl zE3a&BotKgE&RE4AsPi&1-mUX8GTyE8GBVzUIxi#R-8wHLl*3$0Nq754X;9$-dn>&n5eO>pYhn3#{{8a*VLfbIGy8I?pA? z6ze>f9BZueT+$D%^IT3G)#bXXudC;-{LR&K<#CmZjT4_2GO5O7-o0HcIvRD9=o(v4GD~sWF1jSgEmt&t9o9h0kQ^ zI4a80{a?qbuVa5xeVQT91gXA`&kDICqx#q{`T;%GRG)0fGfk?m=Ce-j$msSV&ODth zpT?Ydg_%pQWUTWDa=d2Sx+AaV{MLDGx!z=~)_vA_ZMojG&TGr{rgdIht~ago+H$>V zo!6G@P3ye2TyI+EwdH!#I?FsOidbL-;XYJjQ(e0z=oP1_e%|-bvr#?nUR$lEnTlWRYd#GiMTMf`cE4#b~#>PGx|r_Op^)E+qBt)y~BeCLwNCGlNMYG0b~XwtDe z@2cDcs{5>DK8~@3Gl@mvGxvuK#>bWa_bM;*9=kr}dDu=>%5UJb>-%X@)E{43bNabSqE+dtr z;X960?uPF^`j%zsc2GGiz5`0-w)k!+mGj~|qf{=8?~+nEGQML<<<9u-DYak6cT(v% zD$3IRU&kuf!~UjnI(#RR%JuMFN$$v~9Mc#5fF5fqC&hOZXdPh$#;gR zy->bOL?5FgE3Y^Y)_s+dZ^KyeUab2nCEv!nuTt`Dtote@-^RMHQu1xA`zj^h#=5Uk z@@=g9Dka~>y0235A5h&_>BPjJcghfd-uW)^=bhgq{=Bm+;?FyEApX2lH{#Dbb=K>m zI2e4lr{XN}ou7)!L}NYQD=0ZmDDMbW90|tmysNk|)_tmy55`z=sI2=`CAZ4DPgQcR ztou|Y7t6X&RdTef`&1=&%eqfha=NVhR3+ETx=&T|K&<;zoj9t?byZ(i&t3VOtLKVO z!gt#$4iDdfskl9SH>TqJ@ST~83&eM6Dvl7}v8lL2eD~(JEK9e8;!yD&q>5XG@@`Va zxk7nosp4YsU8aho#dn-4?iSyDs`ABrC#sI4qAcD2b*#8X>~D%w#CLKkt`XnW>5h!z zIDOF%=&`0aQGBPU;!5#dqwdJ)_E9-^zOzo{;`uH+eTEDEzzC}OEl=l2Lw4>D3 zYR9jP*$(oXQSJXli%bl&bpKZVpL5BHoLXE&Nq;rZr*`ggUL9&0-GwBx_49X;*!?`khS)^zM?$A3#Z z%9fJ<40X;oJ=nB}#||DlcznR)10EmvU+Dw9?lfy=?!$So#||DJ@c4ko2RuITzsm6^S z^k*!&Bi7nomM_bb-;{b;JQDg}$=l%PvK}fYDa&>84^+KbM%u&DQ`$+EC%-A}XYokX zbIxBXdB*BHAf?s!8LM&`(_cAxBuYB7_<+X;JU;Nb z4-CcXZ|XbGcl}S8xSszj&x{;A&@hK(7ajj^t*>WZV79i$4jwyre8A%a9v|@dfX4^^ zQ9i)=5L2VSpX>H~$74f}4|sgQ;{zTa@c4ko2mZbf$S({9%5Cz#QB-rkOzxc7Zi?&1 z^CQK9v*t=)jjKl-x}36xk~?Q{-4r+Ft8(>B?wq+NtGI3`%Z)0o9&zZbeLm2!ryc(u z=ki;(qo=+8UG1gEnvOl~`0r{*Pka5l+Dnf$9edjG-_?$u_WF0VmmX_6_O#=_ryUOu znkD=@^yBr2J2-v6=C~qFTwaT<8{QMsCPY5})7w7?eVa96{PCalWUx#lY+6? z$Ar9|>bSBmj(tCu@qxe&m~!_+#wU7Ml<06_Fw5k4VfUmeDq zL@7wWrzqn**&D#LlF1o+)$0nQT3=)z&RMiScsH5A_{a7kFz3Zz4*8wt;da>5x+%xP zmgj?DbJ5m9KCd~TCqz^>V<+**77)8lY>>}C%&!0!2IgYyO8XJ-GWdMR&h?&gFdOvmRF(1B zLQloy3GEqQdNNbY8qn_x9M$DgorEkywhz_GChI0K)yX02CNb5?kad%o>SV~eNlbM@ zSvQHPPAKapG1UoW-6WoA^C_%3p4lIV@&3C0IQPsZ*5{bd z5FCEDAmdWc?AY_@q6n#Hje0@&VPO+P;%#Gl;JjJ;8E?UOg1pc7L3U@NH$_jHbbhz7g&}V zmF1F;7?%H&?-*8GkWZl%FXU@z#S!@+TJc4`iB{Z^&!QENH+};uQ1-Q@Ox-_Ivv|N)xv!6-7_2G#VumN_-rj1=diC6G3uJ*Th-OsMW;<> z+r@qQK4Rw;vrV(^YH#%2IEdwSton_pELT|Nl0H6`KBT8%=}Gz@%!5l6{61U$W1z;!gG%Ry@i+ z!-`YcXIOEh<8M%|j9--fmDI)R$E1!{|0Z>}`aM}Et3Q-=wfaeE1FQd(wz2wEX)~+8 z)v>H=RF*6I3~PLmeTFse$Uegwk7S==jZ?DEu*NUhXISH!>@%$KPWBnrI4JuJ8B5Y` zI{pUb%5j<7OU8tZ4XJ~S6&W)U%NUZeB(aPw8DkR5n3J(5v5Z9-lM>4qm9Z+Zj9nQ^ z|A}Q^^$p6^_2DsB>B;&i{TZuzfz(sgm$9+~V`U%4O8+mgs&7=5EByqep2~k1E5Bl_ z{Ee~lL&nNK87seKto)gER{r({RzAt{QBkgnW&Xa3cgCt8V0~2oz*zMg>|?4w5z;2A zpJA-}ACS*g|L_I=2Ib0rnCqhYXU3}EW~};i#;TuZtonb(YFuEf#tX)(KmP*DGNZCw z*%y+paJg!I!C0+37_0RNW3^75D>ZLt-PC-Z zv6|nX-+oyAzKzZk1^8Dq6xW31M3 zj8%X51^x!*%6 zcp=x_To-9GSqJ%j9jpE@%F2~}q4X75uG*JitoAEdAGMFcSnY2xR{I`|)qV(L8fWD` z31jKw(&yy&b^Hy=mGcdd<;qx>F)uOAi%|9j64QJMWgj6i&7)BE9TL<03T2-nG0nSB z#=OL`?~#3h#IjG4eZ+ra*%y9;a&>*!$CRF|kJ6v9suxNmi^O!fP;OwqmjP?7D#?JJ|%q@OlyBR45M$3C&* zaG&4!STHVI7Mt5E!P|aVWZ`ti{bqN@6@9NU-kQ1|R?L(NWqn=Q=igWtSN`@tJZC#A zng1*7*Z#b5FlIM?_x73O_-tc+#(IBC&yfC(pOY-oJKT2q7& zOrwl#e%!e^%Gj2eVj5*^OH471GPWhAf1GzSQcN2%w&g>LX+y@g#1zvG8QT(5ObZ#? z5>reI8QT(5ObZ#?5>rfrjBSZs+2`L_7xLTx(6<;<9}d)? zvp*=zeTb3~+PjS9xM7VEsw|K)N(aVDH^#1P@^8^!ucJFy+Ew=B(k6cg%QlhYtNe}} zZ!N6s$vjA)_*;&fs{iLYDt}*x-q`bKK~71Hg|Hz2Xyy|ZmGs+qZuUd4|1^uFiB5f&yHhb0qPdD6|WbR(S&OJ}N!Vbz6nHmo{ER-SB& zmTk%AXxW_F0X* z6$|9^XvIimV>gP!0 z`=hO8dpl;Uw%L1e<08g^Y(sF@+w$T4W7o$kM^X@{R)pIQ+Hv5O9FE`&s}}FhKM)s+ z!5sU&tNWwvy~%;!>)j0C!#4Z!yw zo_Xt7m$~-Xj?Evhji`~c%i@Afezi5c7=kIcKl9eH*ZBL!?D!qAMui#Sy1cKCT}-|= z01MQJmgCM3eMHtR1F>3_iaCDxluc~dHw4?&ESIBOiL{Q0lXkpZzI@o4kNxoHVbfW+ z{-=YnQ^MGcCr?^pyOq<9-hZC*UU4{|NZxh`*6C6)$LPa>;>C!8nBtsIj`%4v`#gJZ z#}*rEW$)CZi&4{m5bh7?8eXR4W=Hz>A=stKrLYM<2clok$;OzN!@@cg?~HpB+%WuC z#0(#NwFM5^6ASZ=@eZ$WW-xY*UfLLa_CsjaHX(TJ)=kHWg2O^LeX`@~Xq9(BP}0Q@ z>W1Kw{dakuIdpCy=4v;Y^_+1zG5Ysxgr#y#34gM)1txteg2LezE->MiWd)mEY}QEcufnh z)a7?$_77dL=z*WY+Z>o>Yg@yP?^5jc?o=W+o|)SMhZmY2p0enjvVT!Kjd+>L>z(g@ zNAJBMcst$Wu+6jjV{phgWA(INVTU`l#<63g;i+Vq!m}mpj%EKkWgMS*FD${uA=oim zR%7tUBcXpS55XVbA9w6;*&%e*qxO^^d~9skmNEIW;}}L(AGezrVHP+4du| zmmIU!@q1!BW_fWsEXKX&IJ#*ZJn?<5@cX3#@o?;E#+hv+!wy3Tw#xX(aVBs~=*o|F ze0uKqj^=GMFYbM)4el!N-srw3ZTOh}jq&?>i7@65#lk-&tA&NGX279~z7KDh&lhK2 zKWePVbUo~Tm%iv7I^Sq<@Tah&D}piNemrAKV0dVOw7rcim#HuF?-@R#$q}FK_v|=o zLM-nt$-|5X_C9!|%=qvRYo;5AU-iS=9Y=-h^16)vt}d_ZsoO!hZbRL+y3N}i?2heb9XHy2`YUW!wmulkXNl3I;i9nB0si=# z*Cr#umaU&*SMtB7$%$EyR>bUiMuqEmMukm2FCLjWtkC3(9G{AtxNhcjM$s(h+R!hk zj&a=)gmN8Gvh-Tx;19hSH%XKPYu0YWxLvZr=pV1TA!R~t^u(K94j!kj<*R`|H^|KM z|JOg2z(IYBGwxL|H#Uo2f$_xOlVOUE4Zgtt1l`sz$YadwZ~m5Lm%^nn{-GkQr>p0O z68hn}T>H50xAKG<*_QS}X%iif?o=H^>tx~Qy8O+8d5xL9&9asxFJ)xAVy?$qE*fFv z>1^gJCk(l2lsRkiG!D+KfSm@LXLF0UY=M^-nrC*ek6do7niRm_zqq%Uku#3@&3oa& z#^TuKx<2OiL&k_pzARHLWqMrL+dQALJ>DB5?drDt{GB5hw{48ebs4yKAZAz)z}S0_ z9ev^!;`MLvi(s6dFuEb@=*ZNM#>SsnW@-Un^uKVF@q~`8a6QBTDHAJJC7g0T2jd^_ zHp8^fO@7Oy2Xrn!b`1Vbk`?{&K=g5pThLh1X#NpiU%Mmowd$_dOV?AcyDR%d)(&5* z-S1{^jQbBK;}qq+ z7?rCB;}TO}8KqLSV_a!#Fm`V99e?xV-C*p}I0lz{%C8@0E;Wns!O^}rvC@Rtx8TTQ&zU`>EA*y>9XJ0 zAF_D&!ZBBOun%;8TnWGX)tlQ+AIq|iwBzxugIT`WlmeKdfZ5hfzW2di{w6nmUO;&~ zb<*VKt-3u36DMrL-`t(Yjt%>V^SjYs*|FZ%G3@`_?Rl`%1>mv@HuS}V1&^})ypR_7 zxQn@mX)n_rt95$zU!Uvm>fem4KCbHJj!kqM>bBKw{*LT_=S_v}(*DJx6YsIdFC1T! zrrU9CfbSRBmHeq!T`>6gCANug|86rG+MC7!p#ICJJ?pK?DQ=3Uto ztDKyheUx`99GR>h&RO%xtIwZBaDB$o#BVO?l|Ei`tg|~V?yu1@+d1OT7vIrd454y6t&r_y=}?)x&p$)qS_sD7C2oSAO6u>vZJ~%a?nODqa zg>b{DvhZrij4=IquFJHSlW3?BP(Q_IGF8VX!rpZodjq9<#1bhXd;N&o(o93;eTa97uC8Vc7NcH8EwIjBvg|)v%!Sy|8=o2+=pugwPaO z195EFG*RAGCUpK%ip#BepwX({VRJ6$!?rtYurXk6*tV7_@yfz_aPPYvVg6k%8xK!) zfjH;ah8+kDM!25DIMVlBwyZ@1v2XrqVnOxNq3eqUW0m)*#llA87uW0Nhob`ah^f>jO$esdyRQi80*9= zgQGLpyeiHbj0tkuj9wEGd4)f=;kL#3@I>Y7*;=KogR?HC!Pe>gvSm-(41cN+56YcN z5!QE=FQ%P&Sj^}d8ru0@Rh;IX4YnL^6c%%NU#ym3o;aDXc4*QQHe9kdA3Rw*AS}k> z-Z*0G8nNhlU}(CkLAbe1Q*kHOjl~HwcE$CjFNqSdB0^*S)eooV{mJOGAdy#%GKFx; z;<7lhc@3}2uYxdF+?vMVQc1lkr}DuZD+^$5zZcowl=&X#wMviEMh9hEvm_9Yr=KiZ zWhfdNxVZ(^P7oW86^kDh(4;*6_9Qn_n)P^Vd@%2mxb??}&>pQS zVVB-HVE=#)VIR}C$3$nI83osm&sO0^8T5)-82hA;<8?2653D)+ps{1>iEP6TcEx^8 zE*Ob^-jYq1*Jbo~b$MM+-41_8XWh16%bt4MxoT_O$MkmB{V=k=r~8}khq|BZeyGQS z&!O%(X8LgvJYad~^jm#!{IW&jg=iWYbGIEUuPkg^`(o%KjL{#nEt+WL?v&I^AIs98 z^2hoaH&RY+XlQ7<9$0?CL8JB96WO*;>Vubl2{i(J;&>$<)DQdLo@tEfnb6B|H3&aN z)DkcJPA+~wA^`jRwp=WD+dZ^;#%@^t^*OOU#ir1)SGwVXu+v7KTbQjijql|aOfGjL z#?A$BIT$m3ifJqgf0V6ic{)$@!(7L_mrJs_dal2#e>1ZBxT=>sHqmXU+g7*vsVChr z->qY!e6MAp=?=8TnBlKQk2Q}%D~#@lpH|-$Lo%HC47-v~dfSe%yIzjSIw)>79gpu; z7NZX+#B;*KS!>~6M=~((u(dJHzn_rtnk%g^QIF`1Yqsx+=hq|8g)RgKW2H}t8Q08H z8{cM12XY=V;^=xKU$Wke8!sH=$llw`pI#kb!!~c7iPPtOWqYUYjJh48huD;N5XmBj?ig)-s&u#s&WK8pZwPI%%Mxcbo?PdAu*a3Z4K4AQzRdYP=WA1z8*w6Uh#GX{FvR`3%Z%%w6Wond5$d8ss+ZZ za(!8*$HtmQ!AIsDQ+E#BirD>^Y0uRK`s1j;2}0T-U$TlgDQ979ALm-`yRn zFmAqP@&w$G(d(|)SGR*Zb=T{q>#5h>m3<;>hp*M{Sw0QGO$kESp6QXvPFiE`RW69AgR9=9=I6(o=EPAmD>A;A zI0Tpe_Kw$I{onV%>4E#W+}6hjVS=4)S+`AreQ!q*4>k91r@cR8Y?)&Eo_GC4M*5e1xU3hueX#h0{EWM`s*V?$Wnml^ts&Z8CS}~y z$cwKXg7MWQsj<)7I*iw~`oq{Z%RDRHtehPWjhoMFY9Hb}v~0VA^%3vvc(hX$USE%* zbMAxxT)=yVy1Xu+S>dGg_&)@J*bj%&kJp{75q&fOVLl)b_JHgtS2z8{o`u|Ag7T~QLZw=Bl~ zP@USk=uefot&3j^!ODq|efUk;5d5j*W5zQF)x+CUQ?mSw3}tb_{z8n)XUUCI6PtO5 zbRX<^zFd0tlj~i(qfz%Hm%Fq{Am%AOm9f8f0Jgrq^1nXU-_^evS$$m9%N?8OHq>pa z+dNPP04!w?12D$Z;gc z%W7yHbP&j(m(1@;c9EmDX zo5qe8R^jRfBg-HDkYH)@#cdn>Zq%666$18hr2|pt$xs@S^6at8db*78s2P&J-dH5#`L2-rG?&$_P0%h zRs9;nuA4{Z&Fr|s2<{dDyFZm&?2e3HcfG#49o(tAUN2owz3#5;6InZat#+@ntvVjN zZsu)&yGVOzM@)`ck83o}W_-#1ur|0B+8bqHn^Ql^4zUY*hh1Njz1-nX zcBt~YU)YI4JB^dodcsJ*1B*V~`e+2iY6B&GE-bjUaEjsGGY|szhAzHQvn8fVZR+;h z6FZJvxq@}O*S|LI+?1Ae+i@oZOO1(O-Qu+wj3pjaVBKacy=;8HrwepVm|~G}%Vu~_ z8Vt1lPLDG&OV*b1^;gPvU+>L#~cVx)os(Tt6saplX!{bFl-&}kh@#|GPTu)FT z>_M3ToZ@SaDW!>5nfLi()@{M8ZaDsrGpyVF-+SQkl)o|7<#ieTU0q(+Q@6w4(OI|c z*RrSHcCOl5_c6WQbw6~+_jG^L{ZRKk-OqJD)MKICpYx1eqx(XNvI7_Ad34zDne7Xe z?~Gow_MsR4-meP#TW(u(eC{8Yu|AgVJGa9~n6noQUw32C+u7YP{Jh!Ljl9}o#GAL= z)`4+b;dd9!TzSjbG4TDURpa+kDfs z`9|;VePK+_ev6H6osGgFv|q6>U1-A8!wuir1E6=Q>x*^lO1?|G!nkj|xt`VW&spvG z>+@x{I8Bp>H~3{RMn6(kEZTA)?Ane2I6Uz%Q8Rv#(5J8a;@&iK*ybsdb-@?ouP~lb zs50&iG{>Mt4|h01?uD?;8=iR}zW=2I<9&mRLY`5j7>^353e&b{W1MD8eYlY-1>-kC z?VwB6m;6l~{}Xf@n7lFs%`)qFEWAH<$U08MUt52nj&+&nJzk1oUCg`3cOUA8qduMH zdg=J`ka!sIv?Dppj7dn3;=WOoCe670c_0sj!>+Z@vk+s9uYWJ%{9vFiTnQ>>_ONP0c zntK$L7k9x_CH~;H9^d5U+a59w3ySK@v7MgY!5Cd`9voitCySdiA%>8 z-<=9(ndozqW1ma)8UGgE6@Pzvfpw@};GJhIGz$kA(*i5HxU zZ5%ja>XYE(McdJlrk*w9H4=;ZntO(;p8P7{z8}B4VR#vQ+THZqR_EGb-lNZ1=OQ0- zoX z)BR2NL*4guKiB|JFv@?UlfgaEH%uw9(*J%R_Sc^Y2Egxz((;*e=fh~wqsdSv#h37cl)$|V7~kD zz$@E?%;xh|DGT7<1?GO{?WA*!QYXy)>LM#H8c%FpS%>m(b{W|>o4)7jx&E&H&B*HG zs$TBcM7N=CTixabrku9LpKsPZdXvf`eR(rqa6D%Y5r2u<&+FKgyrcd~qlqxbARW`3 z0j>GNA5R-#wfM={hA)#<$LgE2Fy2eQnUhWZW{xr38-MYx%+EWmxMD1gXYRGe?;9q5 z^f&i!#rf*6BqB4*4BXHYj%PAB-UE^ifSE~0Gk)bW7|PD5%$VjXu#4tVvY*lMKS8%c z{#Ee!b1$w-`(*v0Ub%^^v#aMtPuGGw*V40m)}~$vfM%DMvOdjk(L8XP*{=>ekrQo& zD)M()r7nej4~jBgc%Txddt}bXe(#?a=Y*Rv7!rHG@o}ly|9ka~iCb5-G~X?s5f1OK z$#~a>!qCiS&VlEhxG&1SHpj|xDffxnNzGUrd(sDLUe3?*wU*U^kThu+SNzxp&I~f= zOM|=upv^;bJqz}fj(exg82@SEUg4F;{7#jaL&dm1%rUg|!RNyNygBB&Bcs<{udi+g zcj~U!OV?Acdn*_AiL4#IR=bbAILwiCh-pus7+~xjX7&~NhvmQ$bt-XN%sdnBIF#Fz zX?-p=W;ti(O;!z#j*ri_VwnYLvOvkn)fsopa!h2*Y|cxkjd@RJz}xWiafwPm>-VNl zW?Chn&B?s{{CKh};(S4~PYCs0AR1LQ`{xQPVnbl#7A*6sc15Fgb5plhwQ}LUz2+YK zi8tuz{ioU2ElivajpC+%7Rnb33kcIE=dau)GVU||q<(=6Fm;YOZ(o_k2d*qAz~9f6 zqYjikX!>5kN~gunmu8M>XTvFC+Q2|lrt(Iy{E$E6!(q{&U8B~FtJg{mAARaF&hWf6 z_B1QKh%9s_jBD3^;pQ8I~pvWYqqa3@s#+K#hhHbc@8Z$;%za<%H2u+v}F!5eSX(>2O=un zH)AtXl3P9xRLl!EBQa3&bKuvYuZQ0l)FKh$C2}gGh1S#cWtwud9&c2v7uT=ex5{}GLjTE z+kIcGiAK?M=G^t<&7_XEXU%Vx+ExInd}q!rgA)vd(lvv5Y@Kq9eh)4nlS6+0#p@xk zFjgi*;tRtD!K>Vz8B@*(tbCS^{|UO~85s;GYnhy%nfY%RrShBptYcj!u=pT=*1lZ# z-^=$Eu|fHj9<;R{j;bYy53pD^S~6Rry6a+?5pp;j4;YR=*jKab>g2!?7HSR;m0{XS^m5Tg5G~MWnAZC2yAWoE9wC$e_BgC)rf$cFgo*;Q&AxqL@AgKLt)`4^{Cmf# z1g36d%anm#o6UJe-)Ze2)^9IZhlN3XU{jGW#*QRG@Tgi##`iY?oL`!Ub@Lot_E*^!eqM86&qI_cV%s zH1{Xt&wgmzR>9P5cl9;4%E?t6Y4W;^{;n>s>#5s8*HhQu9i4UCel2_IZKt=j?pLnb zUH3zGd{6f`-4Au&)BRlcLp>HgmaGduHcZWJda^Ho-&4~ch6TifRd1T|^E#XRi=aTW zP4%&?@W3h%cGq0PR@+;nUbNm|`f8DhdBA=I_?xAwRs>^n zPR7fo)`#w~&He41H+I=(oHf6b|7|o_>1B@ZRW|JrWm}l@hZbRL+y3I>}ssr^Gn)c5$sU=Jfi^(=w-o7dLw2l7-b|qi>{xh*PrOChq+JW8nld9`k%Uv16&)e=8i3Sd<)U$^=YBv8by#2Bj&~ z1E!Qa$nl=8Nw0E)x+v7)mz6@jI}q#+QC+@S6o)wHUSVY-{cv# ziijcB-ZI;0M~hsxst3$>r$meE=zPh<)yvirt#6w#xVigzaWT5NR!uZxhG@6ioOczW z`9{2Hb9wHO>ec{=Kin>)KJzyQK))@^7+aN#O*HgEHZlAwnhp*M{#iJF2Pccie&t!d`9y0u9u1#kD6i@74 zZTiDwECdI$mt~oenH!2YLrot@`0Qu#+edTHq{dJ?w4Z6`b{}4?F9dX4!1f>gZV-&# z(u(l}`i<@~S(|cOuO1Tu-gz!E?i;5+v>RjYRfc8pg}}7OSl)O2V3?Pn9OD<&)5EFi z-?I*>%0&}d-kZ9uZe9Rdw=>s4(;8J5ixZh^+kkh|MWOqqPc}*&0KJNu^NIuBb_i*+ zl=ZBCI|MpLcd!nAjvxpeQOA(}=HuNDn#VEE`|pU~6&ek@#5$ZW&IT z2LwT_B8|9x3&rUN?f01eaHDHu=-ed{w_X0OnV{B<8jSU^tm*Rp@H);oes|%L7%(%Z z+17`$q=bM&^;o`H_Hn#^b1*r&rzn3?xSE-F7vb;v&cg4>)C%1I~MuF*pjWi8^RH>d5kYyh#2Sf?3cKZDtUA8?>RBcgQTTl!M!5< z&AD&wuscTs9?QgcjiKqwL@4`^jTf^+lXaCDPfnK*URP|wc;2tCMXq1lGNv=sLZ0uI z@;d$}=ytPc5_nmx5$jg>@eWZUTQA6U^gwnU>oTWmHh|$DlCk_Hx)Y^u$5ycXM5(Mg zUggyp?l&;`@Vfl@ViDrc6uqF|?*zjsu3o!2A$TGjsbrGvaXQ-QOLpIyiog!EM zo)E81n(R9Vq=ZKk>cP0n@iHzcRRQ8X&IQu`V`}GyayQE}KI9z$O|Gsq z?WxJQLO^dQxMwZpAFUQ|>M@Fx^USHh~?$lkc zm#(K?cUSg_tR22qyWe}+6VmL9V0+%_-40S$F*#<9evSise{Bwf%B;or-S^%0hZM^;u+1AE4}x9EYcmc>(FszHxy`sH@myBt zJHhRBvVChI_ETfZ(Yj}=r!#Y%a^-jhd=L~WB%~vU+wU+K~a7lvwRS2 zKh~7ry)&*a>_0S*ajM|<5ZL`G<5g!X!s$fjnmQKUbsT!U0gRYGHq(b&^Y0}gh08$H@Mv&4j2N>hUO8{58K>n50_3qW~`58X(-pU@QHcOBGb)! zkngS8)|o^rcpegi+uG5jExZ>dcdHU{uW}lx*vIl;4~81mV{*Aog9kys0cPG|_nO); z)Ysh4>>L^d(}U`9xoi6cKaX+1@^Ms8h zp2=Jn-U=4WPjsbKib{ zsw%LkeRkI2QAlYRH^`iGCJ1Z=DZI=W+abUpRDyRuJY?eMkQz36^Bgn!J<_WU!m9VX9N&OVlQTthfhFeym;FDH&+_Wi%| zTBF~f*6^T{nK#Lpw>#u&e~Q~3&y<8dg^F<-O^VS5CO!PfZSlBjJ-BuuB|rZqSvFYn zwkqR^&r`wv!F3rYE7=?x3^w;I%g*f%2fLi$cZcMyMLDSqEEAE?4pVBaW8L-^Z2(?b zlY`VP=X=^CTwa8ATamIA9N%O5XTOVGA#LIdtXuEe?V)>mb02R`m9mg_ZXy0=qZsMn zuFdqlq}`*#`Kzt?dBRz(VB^i`j4x*F43&Lvus%1(_(8D?yBSYiSqEaINW(HecM_1q zD<9)m>oY>q0CT?W7#j#JZkl7tGQSqkXk=`VI(LdY7$%>n&bsZYKL{pw>&94@*Jbo~ zb$MM+T{m54-9GNDsQHK4)`8VR zV1LpFET7?i2-MoPgR$+HFBE!ph`%{+Mhln)vH9J~Grors*U~ZGcViF~Z_tMQBul;^ zcvZhS%MUDIhhuTV9MZ4OIfCKimbm}*x&E&H&B*HGs$TBcM7N=CTixbmOV@?p>znpZ zlduA$^~%k5c$2FtEKTY41$HIBZRcP(yR!`2M8|ZuKUnwt7faO@{2QBlt>c>ag3~9q zvz^<$=mVn~FJgQlGtFIR6=6KK1N~mfwTW!=i|2Afv7Y5wpO1x8iga~?8MjQI+!)s0 z#E)MNH}(!5z|WIqT4LPF*@rRxrhp-T??ASlj{ga|Z8_%;b7F4f`raEcz}V2u9DiLs z?{qDiIQ`PBZ|O%tuzW*Jepkmy^YntC{W}a; z^Bl#`$NJi#i0ucCm#ojq8%cc!v)z6gc_Lym-GwT@`E1%?*gnk0^5^XR!LRTSjMMDs z4e1N6VSK4!2vpi~hrjbQbqGA!{)XG}<15-fPcW3%5w>@`#P&_*yvQ%dWRWF2kiXx! zWjxpy*PNrayO$nzAF0L9Pv&ne61*_yR3-9WvXvNV&QXI_=Zu(3=gg&Urw5fbb{;cz z9$vHqg#Y@;kk2b;$^eI#n&0tTRuaNnn`5XL9UF%9Fz1Bs$mn&~>#N(rox1Dw()HBq z?#e!qwZqqH_m*ut!}>PY*`6QQ20*F9%NWs*6p3q^v0S1{1F@Oz zts5k+ zdxoD!7a>q;#v|6P#&bJVy!tcyWWNp>VfY$zUeRLkUU9Fm>7NUWw-^39Oy5hF=(;Vs zpXqy7*QSJro$7J9KEHdxmQht0&njOS-YqY~`1eg8#p&d27#Cf7TqOIgJL4?n`ii!z z%y_S}FBpz)i^IAdq2FxUIwltDoD2s+w&(5m`OMCPp?bXvjCFZk=Ko{wI>4&Rwe?XE z+t_%; zi|;z#%f0dYX7~v!$y)1QscWCJ<+`%Gtf%Y;Sx;I2l;|w`_DA_s=I&cu%P}VNF2`X? zVo#1YIS%F6ljB^DLwPI&Y)eAvPiyC?7(-s1P)du3XM-Bxf^~~=t``Ll!>!hC<=n|@ znPrcx_~d{#T;@1%J@%Q#b>$AD@awQ;T)yAn5jfmS`!1uQ8Oq`pn_RejQ_q|@YJE$N z2dw#m-kj3%4$Yp7#|zyX^SV`rH^t#SwEgp=W8H8_X6+njnWiH?Rmqaq{Z_eLS8nrr z_4$@vDe;NyL)o{o&l5@-@S>HP|NFhaj_z6Y<93a%^b~an?e!=8E%`A8Tj4yHa&UPW zyT6}^oqf}wVso3NxeIr#Ssz|;S=ua}|C|W;E|3#W<_n<(Z0EptEp)UvX>RrAH@mCd z$70LqF~sxOQseaeJ#Ytyccgz@tP#g7MY+a|qS-v!7{9vBA|uDSQ%nCf#k&m7NIS35 z*1M(?tZDX9^|=mpx|E}}hSuOXe?l#KA&bMG@V|p@&8K+b!M+~mMuVT)zV)-Bdk#0` zdVZ_?(cXn5t<`8c{7TE>&*3{!T=RA%PrRlXWxTX|B|JN@Dt+<(j!~A+ImruGIPYm* zm?p+{U41W1rz|(8t1-~7$4d{KrF&6Q##r8XrSmX|?d>GT!z;$ct#Z-N*|afo!7h@V zu-5j0=?ad+4a*H8j@#xLJGb+~>n<-a-#OjRZd0R)IACrbGUJrB@on`{ICAoGlDVqc z_-RllJnBw5N_!+2M~xYXgQHH69zCBMH@|us5%a{0?p^3@H=#jBk_6xLzHIGB+t;J= zp?%fiyL4@{7z3vbK$ec=Ru zXU^8RNpo`05e-^#9P_{mxAAF6y{;cN?i)W41=xMT{PVqj_))y~b+yI5_VuXy*i*)b?#}o~-}1Di?Nj5D z9b@sXCnL!HmWzz%sXZQwYSZf5&l$U}8j1ZotR~MF9yAV}Hvn4}IZKXZdTI17Rug4M(Mp zjHOSvR5k8fyFcPQd>7JEZy&n|zXrrV^91U0&&#${k(C6)_d&eulB4*z22D`#t?>{` zcE;>Ua8K_#oHkk9&zN{;2FkF_ovs=Et8s?I1=HHio^)xQS9a5f^>B`Z?@pb$V~Jgv zZdHlX^9l50snxbCi+99j6VlT>6BCRR;JuJ`pXQShILvsezAMfXQ-Jn#{bKBwrX|kY zHy5o|H{K}A%QA9ZSzgvt_QOA;v+Ua+ zvGCUais{m7Pa2Nj*rh-3igp|uPv6uw8Z81|p>7sE>6Gh>jb++Y$5DY5X}#Yb{b4N& z9as{b8S6nUV{;q#HFU+}qYKc}O}`l5l&XpA*p{RxJH0aQOXq@%ld`ni-Dk!E8`mQm zF@j#J+|8K#vkMxtVgfB$#mbn*HOw>c8J>`IAGWFN}Dm3@A7(RI_) zg`PBS?pwPBc)CkYc<;g<>j1lv4QrcR_IS}e+avyfza{_ieR}L&vLnsn8e)_&ybqV? z@56=nG6ygS`-Sf_)lWLuLH$pj-E@@SW04=5d|xn~LEZ!y9nhWh~2F zTG*G`;al8ZFZjH2r$p`iC}Zy`6U_ebo)2cPEI-1g7#=u7Yro*!BKX{F?L14*XThaL zw&n8O!wG7-a4^U3)4}(t`XqAQ(he9+)9snh`yIbL20dG=ovDK#X2qTJYUh;A)!@0f zOj?`E4_raUTiU*5LW?@+bQA6FCC&LDRKK!z|28wJHobPo$omTK(2Al_+8#SPtt~Cq zON));A9K=&&9!}6()!M{&=u_-*m`b%x-m%0Q<&leY>mBn`I9mBG_ObP6wAoA%l68CNQv#TU9z6C?cegx_xj;S z@xJs^9&+nf?T*nYaA(8-c)ux&vGRV=X!D5f96v6Qj)XndWFqohM9a5ocN%%e`ybi*P~+#*>d>_=StGBg_z@g;caPyo>@5V7@L;^PO!4y5*=gw`4oJG=hHAbbA)|2~}>X#p-e6EAzcZ+WpM10@qMeUoAc} z^bSD--VEpcZW)?`Uhk~!v0D|bO)EUH=jC2SI@5K(rR6wXrT+A`(`6oSV{iew?wppx zx-&f!9s05zmuc(tk(^J``t`h7niixcUVgm*qK@ubuBz&u4%BjscGk9-OOddhx~^_2BbiO#Zbf0RFE?!Lvf z9Ao_?-sL#_-q@4lO^!o3&gD3i$HK}XrRnx!i1X|EHb1?ZNn6W2bL}GUt_}VdPHMTWBcqCr zG}nvkg zCQBIy+WbK+dejhZljP@$0~QpZj$fnJ$#`$+UC8;uP}=(ZA%9su>TM6~@m_0xMc?kY zb$B!>z9{dSN6~F@&MaBzq%IxS`O<1Q6g$#k`KJ3fu!qoX_e03@@#ip2)`%or|nq1x?y`f|3gOFcSQAd3m;)zc~nWdVN@Ic zl9zJf1$$c1opUdn5eM_o-tC*y>?3d4G}>2+Za#=;#^1Ktw2i~GKYSO@ z%qy*JJ|%RZhpSuC3#J^_g>sKW2bztgnecr7U#cO}+jjz8Zr{@;SE-8TO^4t;WC0zl zufLy9igh1Nzq$q6q(tUN*)H29>nYp*E&qJ4AAS_?*Aix;SJT|-BJ&#mk4Z;S$-IN8 z#hdf~KAw&6qIE^+(8-zodxR`N*?t{O7i0|a-#Q!N!7-(1i922Vm(DMP_vJTHU%ya) zo2!q==UTn#rRcjhJtwv#UNgqiggN7Ej`v$Zw&!8*Qrc=0G$sr6-rSas>G05|PeMNG zw!bNj-hSPt#S3?WM~tP_iu>7=DsbEUY`P~sJvqHirCp(9aL3^^#4f_-jPG%D;^08K z^6>@#9j_bXHU|sQ_d^W+-Ci$4-I|Z0-7atT_v=;@*L+%nzO-oRpZ`ud9P`DQ7P=PT zAM&yqsd;Sz&7ZHcP0i=G$g_cc>8?h%Z8E;dO?}@tr%rut+uX`iikjMB`f1D#o5GXa zNVj+6=n?Z|n?23fnV(hlqRVR?u|7~QKlxB$BDLRJ)yB_%Eoo&MNz0wxY18J$c~Ue6 z-XCMWY7<%{2OYP#6>U@So=w%`Iq*yCRy6a}yZ&p(*T&1o+0&~P>iBOAh(nW|yVAso zkNtbOTEOS~I?=J`AN$MlvW#3;mY4OE{qWD|Ec^CH`BUcZTU^UACi5=GVM=08jyE|D z<=B(sT#iF|EbN-MhU6bGlBT`0!{&B;ClZ-{Jni*rlFjsAJWS`Nc+n;cSF8(ZZ~&dE zJ(#wwdgc#nS+TEPr0TsfwA%4SHZ3;Bp;y(r(siDX{V(}kMb2CL(W`rJ_}49e3Pn^L zNV|Jp@~=Abu=)NKPr7~c8|%5h4I+1QjH6dB&9ZT*6HK~TkDyP+@3py-CoPWj=uCTm zg*eH3*0f}gC!LAn);$|A7&%&wqwg#D`k(Wwj&`1ddG$hP|8JGcb>%j{SD$a$l@g!G zK9qec``qdFYSMrDNczmQ!)CqL36gp4K2F7*H{wVnD@!iUAb^Dh5;xs2ET&pklzAKUXLGpfGoY@`;KE6$2^;R1ByXP%)rl zK*fNH0Tlx(22>2F7*H{wVnD@!iUAb^Dh5;xs2ET&pkhG9fQkVX11bjo`(nWQPAnU3P~GR?AF6Y~`qw%7UU^Yh_c?2mW6_uHbEd<^3)jW1U1LZ<-`nK+E;sNKA)7)&$@?GY49oW#zAx1q7q6JvIIHq!J5i3H+$7`?$Rp7Xf_9K-A3^&_^oyZiHZL)K zFzADYo*4ARLVpbUQ(86lNg4nqG$N2X#CEDlX z>o0Kf*bzGG^4}=`?>ozZU&KFUyXFYxhkqkK@cq5eM`7*=_4y4I4?ijfm?ypIsgsvs z{WTcazL4$X7-suIw!dST?F-=t`_I7kg={~_F#E}VXBhrbAqVee+{X6TyqvYi+GPTs z6So^#e+;v|pk5C0NSB8{VZ9w_AM5SIPptO~f5#xl+ktv)f6euT_V_-Uwa@kwVY?!O z84~6Eu0hCiEZSjhF}qm%9E*NAhCeZVI2L+xEcEBN=V3<&)*ov}*sII)a|SDif6PC; zoY}$pV};B0ji203UpynU03qPC3h*D{O zVKKva{3|T458r{g-9r8^vCu*H6VvA}u~;AUHrdaVV9fdvb^j7Gf0)kBF3sfs?lm*x z>DilDf2^;cv1VSL!TL*HO9{hbjpbPOtyq(}Z@)K|*Ysij`+0NHfFl}TiaTvAq)zTw zG_rqxJ^q!@pQDv9%S`$Gw7kq6X=g)u!}%{97FpA`s0}WWWNi2plmnCtRD2o zF>4R{ zbu4Vx>niTRR~om9I}tZ(+-c)ljXP~_rz|f1OXo~xJDb1RddIP}j==B9>kC^4*m}oh z;3r$}2&*ftQLY*IHZyED(zMuHJ z?PYsR%{Tv9@p8w zPcrV<`Hs!YY)#Sk;o~$=6_}v*F)IF z{V42${FQ<4?l}X?XHOZ|3CZg zNV8MfsQmD+hykrnk#FbsVe)e^z)AA+GVHk)={c9==W9f6l-HG?$B}c6Yz#YAoMXp0 z7Ug=*F8O&M(GF!YtRI%EV_5XdG5pH(;aKR&vHZM%eegwiULiSWm;AgE$R|I?1nnf} zvE`hgoNtnIh;nXGJio*BXZ@^pafRm=l5>%WVflF<(GF(iqJ54^T&|RrNaM;IZ*jui@X0MKd5yrHLh#&8Yi!P@|p-y zn!HxZYpA@o%4@E?7K^o;uhDGnK0fWqPkFXcd%iGvPx7}vEB(LrTKb-Z?X@@-dkwzF z0KX;g<-niGdpz(n+iU526822Dz9(V&bF9r9@|?}*5UQ0cto)#2;77%P_Bny%b&Z{C z^s)IjeJ){6Ak$qw@5tvMF~{<;F7LhNbqA^^pR?rimzdlCa-NW7hj~)AQJ*K1KdT|y;eM9a7kS+g`uvFtdHsSjDSUP%nY-lqlg-EaybA3k&$seC zEYHtkKIVO~dis3MVgdTo*EI}hQuqwZ-+$Hy|G_i#+PWrVrVH~m(?QtCG5pGGoF4-rtuVf#}zJ=<^K9{)=`eW8U`=`F2M141l ziUAb^Dh5;xs2ET&pkhG9fQkVX11bho45%1TF`!~V#ej+d6$2^;R1ByXP%)rlK*fNH z0Tlx(22>2F7*H{wVnD@!iUAb^Dh5;xs2ET&pkm;s#lV03yR;ydl#SXmy2=mA4=M&! z45%1TF`!~V#ej+d6$2^;R1ByXP%)rlK*fNH0Tlx(22>2F7*H{wVnD@!iUAb^Dh5;x zs2ET&pkhG9fQkVX11bho45%1TF`#1LUl;?y=MiSlHL~we^^K~5pXVyUzSol+cddla zbhT#R%SoGJBX&NUo4+SyT(9O))jhUANbbuSLqs{ZSIBceh<3PtMEl%t zqF?S$p%3@7(3AUL=+Aj!-}|cb1@Z9MHc(4(NSvM?C3fMtuG3Mb6n`v?pgokA=#jsh&AVYK+s7v&^&?eQ}gubZMZ!-S7`&D~0 zwKo%YcPiJc%|9yFtoCN=IRW*Ihk8CoJ)fhVt-^uZi;WkT5pc=Y#Zn754cc zea>W`58`J``Exz;=MLn&IeX@I?rp0e$BJ2l*=a1xPFoZt(=bn;3 z$0YRUpKrR=VXM9LxhM8{F8y;)$)A&gc9K6oC4WXh-Xn>a7RQ_e*O^r&-B#qGm}4$CeM>HRy-!p zpUIz(`*-G1@s+yxlE<2i6_2TlN5xm_;!7TDGFCjME*=$Msf#aptjSpMn7VjWe5EeF z#w(j1`Zmmq+zoKU#^-XGQ;mJ}a85JF(Nhb225E z<-U^+z6fa$dod(sn181w|K3iqw*CX`&Aty*{QJi^B|6J8d#+`m2lm_GzzsQYN-*U3 zlfR!cLwGiFC)x#9GnB-AThAfqdsoBdGuh#!nHPw2-Ez3+-NJup^Pj299H8@(5)8Ir z-7e4v>H2`4NY@keN4oy9Za=E7+|IYK%tcBtvz>jHEqew+VdV!E11bho45%1TF`!~V z#ej+d6$2^;R1ByXP%)rlK*fNH0Tlx(22>2F7*H{wVnD@!iUAb^Dh5;xs2ET&pkhG9 zfQkVX11bho45%1TF`!~V#ej+d6$2^;R1ByXP%)rlK*fNH0Tlx(22>2F7*H{wVnD@! ziUAb^Dh5;xs2ET&pkhG9fQkVX11bjoj~JlryIMrK!r%z_&KBhd2F7*H{w zVnD@!iUAb^Dh5;xs2ET&pkhG9fQkVX11bho45%1TF`!~V#ej+d6$2^;R1ByXP%)rl zK*fNH0Tlx(22>2F7*H{wVnD@!ih=+77&vwEauEA&68Jt2eC0w#;u}>1KhISH*R|S4 zj=NUEXS!Om?=7KCu@O6;&5ifZv7_Tk=fa5*Y4OCub!ltY7!=U=HoCsc4SY$^rqEEd zbKWp|c?uJBEd~aOasuUMAx}V_h;|6HLqz)o z+9#r43jI={4+VXw(366mROnAZe;T$cG8pWl?0ZI_9D!ZD9OMz$#pR(L40iE$pnVK> z@%Eu#40iE;K_3iuaeY8f40drnL4OQ(as9zAY=P2;-0JWqSd?>ng*^9zXovepw9ow} z`sMx<`fxuBJ-Ppd{+t)bidmESlCk13b@8~Z-e?qF%L(7!X~gzcW>a*c2`9ZRiTh^n zZ=T|f@WY;^@W+!a$c)3z_-z&ke6Yn%(&~;Qt{z_uk3IUCe2BBhnL6ghNjD4A^4;>| zw7oO@0spA>Ra~X6xRU1t87m%B7mtds)Ww%P)?}=BOkF%GzET%o@>r9x;xTpcsQ5}< ze92=?#)`+(#iQaYb@3&SH5n@&Qx}hluhhktJl15acuZY9D!x(|U-DR!vEngx@u>Jp zU3|%7O~#7H)WxIXD|PWDk2M)99#a>Oim%kgmps;FtawaaJSx6Y7hm#Nldr9x;xTpc zsQ5}JpU3|%7O~#7H)WxIXD|PWDk2M)99#a>Oim%kgmps;FtawaaJSx6Y7hm#Nld_iD|(ZDoXbG0N}TlHbE6zn@EfZVq zH+g)?<4$p>xKra!doQ6HciP;g=1lF~muk*b>z&%GsJ)8XXKL^HRr^fsETGN^$?t<^ z?@i|KDOTq@b-q()bL}1I>TIs<8`Zsvc8*YYV*mbkV)9u}zBiNa)8ze+JjUgFIr+X$ zzE6Ldh+{8p+CR3 z4BHhMEZt`!={^%l_nB-R*Y7j2bf1Z(`%Em|XJY9-6HE7**aD>wxz*uKuviPwuzasg zV*iXfdh|!)o)&Ei4Mpf%ctYcf_mrY;^8 zU#W{Pd92A;@tC@J+*WTi3a{maZ|^kXlwg+oPCED^q(SV(kd$GALErDeJ}L#+n=(1= z-#^B=x)VESA8!gRg;Rp}T+2WY?6<*z8*<>3V8@Dcg7o$?gl8jnqFrz`LrL7X^&E1( zcQsr-lO0Z)d4V|BEr)yFE&RjQcsT~E*->H7b%%>(v& zU*Fq~ET0mb5{_hV@Gqs<8g@3=J z11Z)%&jbDiW;*LKDZu}DFUsywf7jDM*_~-?TPq`!{Y;EmzuQM-31qhaJnW56bbk)E z)(m2N{XEQV#NcP>_orgUDF#2=34VVPW--QmToZi#^Kg?U>Fn7#pY{3A;53cTZTMhO zg|h#ew7X$`_0^GMG`%0`HKa7hoeORy@q3DLoWH|evgCF)j*}*&qdBg9A*^oc_?)zJ zo@*QrKT-t#zMJE`*RGp8CuwcI8`Oq4#FgQ7OXpop4(7Mzc;WlgWQSi~j>GUL(sHK- z#}}q$rPcR6(A&g%o9jHX;zO6U^5D~NkW==ITpr)rkCu``9J|(;fjaDV;J8|b66j6t z3LID1wAwW8eI<@_w0Ps7+YWtUy)V!K={kUJNY@Q?M!L>m3({=?8%?^6U^~|JoHe}! z&S&q#^$(a{5pVIx%JJFQ%GkP~X9Vlpv1uh-;M_42!)GU!#Y+O3B8KO0H{vDd=5s9C z~|&uf9G-x1HTmb<>kOH0e-nW@JoPSj)7kS{BjKZ65y9(;MWZNa$IwNF!Kk;B9?fY zBF1>Rh&_%)OmZw@m17aZ91A@O(-Zim62Da9mrDFniC-%5OC^3O^AT$ke8zmo+Xr7# z@G0k!{cT{Yj3wAlQOT?Y3A!wK5XH)hC zLw|ZX>rag?~5}e&d++!+vLVK_BL4 zT~FqJj#+!U{;VIzCKb3{qc=9euf`gKx1K0S-M>`8pKIm|J``7-?hMR}?-#QS?zg)c zy%qTeeR=lDm@uRV$E%w@3uO3CjhAS4RFIir>(Td7{a&_&;n9)j(5=WJ9Gm0zpzxW? zIfkDIe&-nejzErMsE43F$IzY$+U59lhXf<^t(Tkia@LP7&-&5ZVg2asv!8mu?C-ih zte&nXYfsmo^>g5B{UBi%D>n(dm^>18v358X?Q<;pSwGB=Oh)*PW9XOplVkRGT_09Y*OT?5>(BUgOPm>~^E+bO_CTFq*Z8x6 zjNgvs>fuo{skxZ94UO3Agty+EO&Bh)%nFBfEliGou16Eb*y56#9`N#vd$Z#wx0mqp ziod191-Im(Ox`O#8cnQootIBuy%z=EFVD*#_uY%CFG^2YJJGfX`P{C_%f~qNL2VA_ z=jG|W7TXu}|CN{Dn6k<=+uBB#C%Qb8oAq*NpXlvFJ49~>^r5;w&@a*Z1^ub6Kj=wx zJ;7e8+Y5G4-7fG6)qMhfpt>JKxry03sabJ4`?rW-W|wFO3BNIUB>cwu<>jJ%UM}>+ z!f#9;UM}q7o54_dWtyF?PBr3%S9}4|A_eEjG}!Cb{R##6zqa_e!rg) zdQz~-{=SAj=^>eGkv0#Zu1a|2>a^6KdJRU^*JWfQvJbr{e{2oT= z$>UA%$m7s`NqwHT7V()Jx55uRo`rw-os#eykALA$J}!ix`FIijM{FDkUJ%4#5Zsrr z*n)p7ZWLC2P%-c$V*uL1u-?G^E1&<_e8|Qfn>X}zjm`i1y2j>zeO+VozrL=qG0Ns` zHr|cWJiz9EeSWZWuF+Uu*Vz28uWM}n*Vi>R|Lb?cZ2s5RH8%h2>l&N?^>vNS+xoi3 z<_&#aWAi^l$0HnZ0aXW9v0r-`Tpx)@yxTvlD(}>l$0H^>vM{*UZmsUDN%~)+3{s z57{~ee)h&+%#gL`B|2O!y-RR7#8_ijzyasGoOk49cI21 z`8(eCi|w22SY1)h@^@Is^M2_9E-T+Sm=hB4@G{KW8jzNXE_FbS$K!-N@Z#>yglbsVBV&X;q8dJ9J6`h|2q$;y8rxKs(h$? z$Z~%lEFZAkAI~w0oFLCJid-Sf!Rk3gB;^*7lygKdm?v<7A>A;FLIi! zT+ekfc|8Zp+Tl4%rVq=_ikvCym*r|%PLt`wa$uNnxmvxP>%rO)e&FT8KO76caV-4FvG6n3 zhxw27C-i5zT8^3jdXzAPuyU5mJ3aRa%hh6*tMv;z!g95k+UHpG z%dyahW1%OKKGsnXJ91C8!{*2#sZBHii zd((AuGQTfh&*S_``86!%;INcy!&1%;i(DiTg*y4=-nDHa+(z-JP<#Uv{VcLvwt`rzJq{G&!fK-wEq?+B^p; z?nC(5S-M;PLoQXii)MGf>`t5AQM0>WcBjpAvaBEN4qdzZ)os+zsIWg`cis9OzHTqi zsfoK~m7CUb4gd1oG~3GxzVw`h&ifC|)&8$%30Q7|KVu+r6F)Rp%j{t}VG)lCYj;P= z56TZeDh7<={(;?7Dy-etDnF!BKP+C@7uG=joSXhU7+ah4=fT+81bHOh&1Ccjp z&k_CM`2?}YV|yMwZ_b}*VEyQMb7@b=)?9s0sJFxO?{Z#V&euyh7hO-D-P|L`1wv?pYHIekya_IUc95ZdvkJr5&z{vi1| z2lm{TF3P(1Ry*dLx7 zVb6~+UfJ^`|86|)EpA5B9}i~Fz8D&!7sxW8C&zggWyV`@JC4I6isJG&8vF^Tq^@mN zA0C&i{ghzni|T!W4pi3xbR)WM&@a(-mT^kz>i%c?qy*<}I+1p*m#{Ps;QWt!}>hZcM!N3IuzBm`a7Y4pKM*?&1gbe59|GZi1Om+rrwzw;+uI`h2mEupczdpJQ_Kwh`B@z5nZ~^8T4gS? zsznh};sF1QEpB*rCOO@UfA$s^YI~5p%~Fud3@!YDw5PFGF|4cjI_W=}OeW;~dYUb$wTvZdkdQ=j{45uSi=T$cdOAYV<8Zhn~{%aks`6 zq77*TFJJOD1KphaEyrhfJS5aMD`xVY4{asWX7JCq;(^Ws$-qkdbFWzT+v_z(99nb% z*P%z_@_74(${crYUK!I7UR<9mo|W-Z$Id+8H|l74+$LXH-dA^fdpv08JdUd$%#RCq zIm&U#dloqAZVbogdc8yb9W!u!y3V+Qe0_6qEbDM4qU63epfA(8R*eUyOc%8nC{nB| zim6hDm*>nGh}yc@{HdLh9L{|8^S??XIRYdjWl4kb~CigEect0PI(>Df89 z9&bTc@BPI4{gN&}9kKQ}$2kTV>5!}oIqp)wJdJr;nd1#@E7Rtm#&cT+kE%>t`}N|y zN3JbT4~;5Mn9jH2j5OZ_KaTUA%uk=y)5cWkA?c~xhL61b!qvMZHk5x}9?#jenJg<% zjIz3WLkE&0CHd#;aiRBb%x7n69LaW#Y4rqs4eUpnbakWc`^KPaUkZ}4o!qEJKq9)m z*w4HXaN-ODUNqj?<#9JRI{VmHl&4dK$p>%^m-lGpGDqaz-i_A3dKb~<-YB-U8;xyn z4E1>$fKIk`qyAnS5UFzreQ|T6r-v;BXgOKk z$Bpi;y$gMAw3h_*aHFHMEku^FmxwFWwIQ8Q_i4|`MyUIsaAxGO`7^lyI$+w;v@0Zu z6zuOtZx4PPv9Pm&UW4++ru*jG32`J8l4X>uz99}AmdmrhCHfY7ioBxrM5o3n(hUV%PCUngyL zlJz~qQ76#BV()yi^yy_(0d%{vzdc##9EJ8nUFS!Zq?pwgl)bwfz4Y4IT=8QP>fO(c zhP26V>QK#q?ZL*#jIk!K>9J@e$hUKAfm|QGK<}WP+SYz3`tB9f5p+9rX$LwG6pnfV z&eP=_N*uZzeFT{YJD;HVwtdkEsO!+`6DmA8H?oE{eVZkrN5O+kouIFKeGE9qqf-(2 zK!-wU<59-<_sp9>{_up?$lR_T=>zR#_PBv+ZJI?KdV-#3%;-R;Eo5_VHySu@4f2?B ziYy18lzuP*z1a1Tw1v998LiRrt{+K5@X7hoex{{fiR3l-WI@qp5ql;ZXi@Nq-I-(N zD=ohg1GJyLiWAxM@-6uSbthU)C2wMGlT0A9>+%ND=;A?=v9BA=H}@E6+$(^zhc-9O zzeo1e@FeX)eoCEa(q?2C;tM(?_#}|ZaU0DGK(`9M2D+6Na7Ik$aS3Gox-F(*&{vpa zH1YXT1_eW1|Hk*ox_6!^9oYVE=TVZ;B@m4TpHwQpfz=N9ixp>UHRB+d~niHulxSLmWDya|LWd`mR zT-iWoUC_9@3EXwnsUvSs1+y;`?TX46-hg=if)oR^{Oc31FyK6~K3GSS4 zJDd9p?lSbxZ>lZ0o0coq^kkYg?%s57fqoU-wJPq1X5G=a8-8U6G6Hu!fJdLM=TJ_; zT|98NvZcn|E#R)tM2))(z}?z~8h00gyU!U;^KrKXxN8!pad&P0m(Ri)O%mL#EAD4{F1QQo)huGW;4b0HF>`Oh zT}vk?^5}&&?uHecO6W(8yZTo*kk{um?#9kLM%MPwxH|&eMOO19?O-g_t{Y9Phicq) z0Pe=W|DC%-kBe~b+=0978#V4?D@K!*Up4M#H@Zi9ebl(yy5lIBV+urL*t}PE16e7! ztFzsQv}~%4yJ;;Okz0bh(UF!UQ&DZ)jlSY+o(SCag1R|}l*e1Woe;tSE%(T6h1-YE(*9iJzL}M z3~-kwuf|H;$RH;O?li6Ims=D`-8Hv=`i60PfrccW;2Z9D=*z z3-6KnRWBN8oO4jK2#$7CMSAT}a z-AUkXw$803qH%ZCeGS?nxI1)f z1o9W$txjW&o(t|4TKSps3hr*tY8J6saChwHF>^`aE(ylY${J2&gy3!*aAzgBD{^fE zsVumw;CGB1=&p^sHo)E8DjIizz}=TY8h0~*yKJw2=gu)!AQ z0(VZIH16^McMS!1FUo8nNN_h0xVs{_+ughoF$wM#-m)Z(1a~vfI-3^=?uw4dZ*mme zxfhHzjS<|H>)is)7Tg^L?&b;ZRseUI1$Umn-66rI984FT@#1a~=sJ0!TX1MbcX?ivDj8N|3-0o;`p<8BIYH%sDf z*&dC%X29Ks%^G)`fjd{hofUBROpLpVz@1TWmkY*S5y9Om;BJrL&H=`qQE-<7#+{Sk zZh|!K;zs>G?%Kh)n<=)fV*^J z&Wr}`%FfcbI|ba0DyYqw9e}$TiQ2du0^Ai7+*N{cXC=6c0PcPf+!yd|}Q^C&t~w@xRZR0oRY2>xwzk2jGY0~9R-qbqPl3CPV$K{5-0c?Y-3s6? zSgdzTfV+)iy>o{3uASg+inQMOztdfd2=@%s@XKsdlW-qZd|wDV;bYyzJHjc?<3? zz!~AO;4Ti%2ulOCy-IH2ZiCoou7Z7LE^$U!2HaVRGs14*uG&hCJ9b8B_T~38LOyXu zXb5M7^x}*#0L}=`;*4MqXM~AxMquZ=M{q{SBe+{|Zv<*5xcdlagv^4wYbE?lJAgZO zzI*4`EFw&-cLU&A_`QO=bXA?mbiv(iIN$A#(av|#aK6hU&Udxoj8H(F?+(NHu15{+ zj4&I{2-f0!mk8&({L=X@DOfw-T?g*0#rf_ya92#6?~Va?Mc--box`r9;rr_L)BI8j+Jjw7tru2bQF{;I2%Rvl$ESZgj|RY7N}6v-#T0v8JAa zJBuzYki9sYd&1fLlsKC|hO_y)Ankl-3+KBR;%xp1&gLJ)+1v)W!{Tf{4Y(_@K|7n@ z2kz?J)3_@GXY+`++PHfS+gbVJD96x5x(n>pd z5Zg-!NhUa(mzi^n^y#hbRi60WBSVnJ-N)L|#KT=Xn}-2+HfchW&*qN5=H+K|+wlpc z{Bmv1>`^J2?ER?iRkk&`M?SpLxT_v^l#F-QxVv3p1Gzj=<1Sa253v;7z3SMAWEb2G zd}2v17t!ujo-S@-p0Ww{5O8-i>g0Ksq+SM`8TNj8O;=5;mc*koupcWpz!~k{_7;5ZL9XCK2 z>K^(Wi+ugwnQFrM_lms%4-YD28U+5CT-t!AHnK6t!reuwkFn^2RkYa~>bkUlgR+;X zMNClF%k2&-bbK;d4*lM+*h8x1+fAY-xY1&9E6CcgGbD!x+!tjYLz`C^8Pj7nua}yC8i;6 zw8#3oXx#YMMKc0jF$AO;vPmrig>rfw0 zH(IpS4idXF990HC3@@>S>~4Djg@FzmPYfZEJs+VdP&Z;}X;L#=G&&09nTMS;haHPY zZ9sl%)QgCRz<~+cnc2+RG#hd^Gok(B^X`~T$K%i&s2jYxGMYZ<9oh%DbH_0#d)5ai z8uZ*gYz2zScNVn){jbG@p|o~;P%*IUX@xUrn0Y0t3Ni)K-bY3>0nLHB_KV)40%@I4 zThO6%qd2s%^Apqf@ou!!w|S}9W}FE<(ubH>;Xmm^%Ee0IgJ=zY#Z=2{>>_*yi& zUe$ptgm&f*c#NKf4wF-Jj&MIjgCpGigI^(hdOm~qhHr~p~t!Jp$-s}-ZAUYgJvgC zp+R6{?FjTGek*zpF)+aIGV)HGkIKUwZrkT6vbfz7?SS(8?LQ)tzZl8{^1&q&P*sPm zroAKF=%>yGe3W{+M2&*`+ZjnH_s5pzmn;qs#G;uy-3k9iez07;7VQr>iH^YiPliVOk$30qXn$L{XWnxeIn-T%0$RWr z41b0qFLp&%fIm0>gq-%|L8dmq_3=bBJ<``S9L7$i)doB{{kHvk+PTrVqy%I>7HH1a z(v9}s^bwUATa3JD?nWP1dV*q(_9r9Y?s`?G3+O`SrKA*$!N}3Sp$@KLicJ0!MYa z94C2#){~%9d#i-piffac+#xMJ@You)32F<&e@&8j6wg9 zY6jY(zJtjN>@v2CBd+bAxW243u6wl>EfPC~bV zFFbsUi-(T^mw@up=A)(qGrppMAYW!xd9>l-d(;4Mj`w3x4~GZn2(*9NVhyTz{}ieX zb=~8`QMdg&Pyx{A+|o;E{@sP>B*-tm`4pY#+Y@B~JYi1^N}5vuy#c#wPD(^ak1jNQ z0DG&gG2nomH}@3;KXi0WL=SVXHrD_f7uSzL_FD^+NU(i;k*BD7#Xh7I)WuaVBHty8 z$xiU|m&1F}y^lLdDe%9c#47Y?(iw6H>KbyoqlXp`$x*25ysZps(mk4t11`RdF`HVR z`%1il>u1aSTpCR?(8hoVyy|DR3{E1QL1y3l48#k6A%~%EhwQD$n@ulBB($0D!EAE2 z%5~Bi`kHUvL~@U$WCG|g%kCKY)h3W+0^MF+i6jwLa7PJs@2r1A`gqkOEun6f&2c31 z-BWV|u(2&N(8K}x%;8{r`9=on@HM~b6x4liGLD37d}>OBx=EMbkh#k+iUhwo--;yr zqo$yG;9IZbN6FGofyfek?s$9?SumBNRltSMo7rSU)9a`P$gg_eiWog#pz(mqXU<3} z7XE@-0;iV__cVW+mxKz!JhLt5JQvd(1D*us^D`6Esi$AjY>;nvt2CN4FB+8v+-cBg z)TY=&G#uK$HhdM@U+@e%1TpqHbT2BLe-|19`pkE~h+NzkqiB#{|LF;u6Wa%U1pSL! z#h`XQi=g#jmwUBD^kvIR(^#-~B#i6M_tVwz1V7wfl88ojUu+%({<(cG2Dv}XPcA~; zL1~_$&&zs{C&0ytu9whnF$;+c`1x+OeJFUv4zd{he|Y<9w7unN5(jmc`i?_Qb37o2 zpstI11$1%Odr|}Hj%#<+G;ruwk{$T1)^4jy6AuH80DOIZ2Xn34Nn|C+Tq5a6w!>e@ z38u%cn{JhS$)Kh;NHpkqwqq!Hu=xOq1|8g=A0ZP~1d--o*Af_mBhF1F zkD%_c2d~M}Ds_o1)U~c2N7^5HV}1<&8ClvulkytPRlsjIIzsMgcSciw@aOjG@nlon zT~luGTYJB^Wc~dbC=77n2X{!x3X{<@;3f0BV`R|#^=LY9-L%3M5@90fJ=EPle=cd_ zbPcrw`IU>>k({AXs3YKdQCY~i1)oto$V^)?(%h(B5?Ty(lRUb+lwM@OkyPXu>GCaM^v(^HEIt&*&LOCUM~tTC4sM^Rv7U5Z2M|F1s{4v zCZg5b=9t$)-Rh%0p~`vlaG&pd_zX2j=t2U3i*nO0qpmF%kdwgC?6&(+INDCq0bW~m zE&6PIic|p^zcdrk!~*yEJdB+yqs3|869bg*uYA@t?U%2_A7bNG+A}W8hZ$%E(4nbw zBXfI81HB6}JFh00x7Cg%=RxP~;f=|QMz6>S(5Ly7nS}PdNoIkbvp;PhgC89v10hy( zhaM(dbA*uPU|0F$w@9eRbP^49Gg-YRt)AB>pTTeVKrC70_sKjN{PQv&yjx*UC36_~ zEwI0V)_4}}(hvN(Fd&}HY;@gJ3gmA!d`FOdb>s)w7xI;3M|mS(;KeoX2@*fmA7zHI z*?h@Xa`r<6Y5?U;9Q{aLo2$qj*me~en^7=o^Y?NN6>pl+6SC@0i?2yKrZzsWQM z{Jdrfd>`Sb0xr$L{|$>Kp*e|D&DWsrMvKpA+^;$KT-xZsb5y5GC(;wR=)V!3ZP@Hb z+5x|Yl@ZA1!B#R7uwVE(bm-LyG6G}R&fffhdPM7{-?m=S7EvW00xdEYhUXxl-H}1l8LPp;r zc3|U8zYww~-(m6;Z13Oy5V<*J19<{<>HeFfONp5zJ@{%%>sMsz(#GU0;6Zg`N!Lz^ z=HlSngYaz5=Ek+nmBHsr-3|22;43csfs2`$zmnn0&ztIjyid|QGQNLhGz9SE$M;CT z!4r`qa9XO-Nn)3N9g2dwm1DP&^CA1udMGbogSg`i-)7LP&b$J z2lVi=13C*_6sVnmx^&rP$_;*A;0I@)!>wH+!2d3tlhA`z9_H*IQ*Qoecx06uKVt2_Y==b&B z8tB!cw`2k6L!L#NPB_PtGoWWVzjP+6)&^lLO!%bID*5{_7Fa6a405e~^6nu#r>-e>U54gZNyWMGAwT zf1B}=;&rnvtgU012Z|}z-3#glB_Iz{W#fc~%=sbQ?g&IX*pOgT$^haw=v9P9= z0~_nnA}B+V7<3P8pHZnV>T~-ELg16GS(c#B4=$i9z*l^mU8q5yz33P4Ke=`Wecrng z?Si^i4IiQJ~LWHbtL~BfWv^DGhR&I@U4JrNDKUhDFRJ z>KSMl*!B3*b93UxI1&qWKLpey8CSm{&%tj?d;5@pd6A?m_@~anKr&|JQSt!%Hsk>% z8M|*HQ^B9lS6(Oi#?B^{K)!tV3lj69CGi0qQ}YXX7i~!f0xxCOCXr>WyPBO~9*&u1 zpq*ANb?FD?;b*>*LRAi!CWCzKuF=FXstl?O_|?q^#BqQ-ngQ*fJ9wISJz9mHLcfc4 z?<5y9g`>`(&)IZ~NsSX1(NmDW{iQd#R`n@j`j2i_m~3tkgMI_Mri@x{_HUAiR)W1z z-MshRfPGST@WXZAr6#}0iKq+sC-cVwsNe1w#Qau!RZrCQ;8XMk{8@Y8BGm1dOUMoU zjKA(c`QUs#2K--p!)Y|L_GW*sj0J+Z}i`X71-IModSfBF973xl#^%c#xK5Qxv z{5J4{JX&0k%PPPd&m^H)kKD{NL1yThFR1$^3&P^$XziCM>yYLo4B9-MbRGF@_9fY& zuc+1s&~Xw{nzohGZfeOm)f1OBXQ_rUzTU_AK+{APaTLPmCaODN!VnGrFTdg z@U45h0P<$lG13FZm*WaT(w^Q-ZbIFK)31@tMdp%bAYbrl6v;TRE$IokZTM%h>QZKs z8#oQz(|~pW#ev16+@5ux$Uil?Hqg{BZH+JX52SiD*95t>%yy-EH&)o zz%#TPxLA8)0oqvUGKvC@POsaJHplHlkHPIvIAcwlai2?Z&UMWkSS9v7VS(l5H|l0%lQh; zKh%VHgFe6HyNQY>%p@V8XSdl0(ff`YNdwS-M@TSwlI{rc0lV&`n~ommyiM4;)9~)E z=y2=TBpuWZ>GILk{b4Lw4gR^jyu2y0h=KZn-x_Ou#>1duu27~;> z>`}y}d`I#t;PYialXBa$5i_)3piB}u7w>7V4s|V;8R*E*Ra}aJK8?H*NU`(VO=m#f zd)o&xvzrlF0xo&*5$V`&D0&WdZ76$=WcY14dI9#f>b;xf>$L}2gCDw=Sw@O`!OJVb z#;myplhA&T(QU9j=0kC^@|Tau2z5`@+Guv&mVnsvc&&W&~;lcz>OfD89)$ z)E#67^n!b!30{buRiAsmLxo>gMK_?$M7TFH+`43H4Sm`6g>l{Rfr}65@HU?T$5p}R z?4Voh%2;ICI?l}Yb!{VGp^AALlBQ5MzQipwu<;C16Kq^~;1CLo2_c8U_TLI`Kz9!x zA{U@;{p~YQ(+syr64dpW+XxMu^NQRAzYQ(*)fCzn?j*stjUADxLPfQ^H#=QzTb>GJLb$p-WAkn|B` zAzPZQ%Xn*djMAEn4bn{+_u^TH5 zG;cz54KL7V-=zc+S9qf-2INn)_()ur!}s%m{(ZMSCJj#vM61BA++EL;i$#{9pa8cHNhdH2Q0;&Xl zuJ)l$#K;8(yaxPVY^=AbV&f!~2z5)$%!)D%_{`_w+=tpDF7cp4-!gDN`MA8fE!cH4PaL|oA==E&Ya;_7Pt>y>DF$^HRKJbfmrf&* z;GZe)52M#}gUSD}_vYbPME~PA6%p;UOSmVcMN!Ez=dImVQlykp6e-D`^=@BOw6Bu5 zNBdqv=A1SaqKHa+q(nmY{ddOnxt`DO`TzM|&mZ6a=DM#rvz*sCbI+XfdY`v2?tN?D zMRan@Lp+?;=SZhWbhqgpR-^Scz;qtk^r#%)qT6;&@<{$yBmP3UaKwha@TCJEq^!-O zaN5HNInqeW{_dN}52JHNOX&XFk|*M8(rUbzZcix-!B(ff;##_o^N&~@Fg~->_iMeE zis#nfz~AXHosD1Ps)j@OHr@Y)<4=6gbtM+Qm(^A3@ddX5cnB@q?P5C~wIG@|q1XKB zj2uzg%?dOE8HPHhU#fu zIVvUNnxxz453R#HmZ$ORG1*8)%f1}!j|c28>a26JUk}fG_!q@e7CA~Oe3N_|dO#UH zJ}*tv-75#Gbo=x{AJ%PW2QsGnXe2A6v>K814h;tsFsTf+(qk6o?nfJsy+J2w+t|1L z3Q~QDkukl7RRvGcHR}XaOv|2I^9e~tZ|iJhWj!m=cz1+0(6W2Vn~~0*B6cgiPBRNR zn8Ng8{b^fm1v&V0Yy^Ln-dEP1W~A6!#tY*xkJtP`lIzoO4XwB5Ge07WZ`*MQt)H=) z=_r3BhcT_Uv(1;#2=)QqKHQ9ll_N&;R!yBn>!HD`9nVfW$xNWm z*_7m5eCq2FB&GGN>X3r(INw5xY5fn#kHP2Kve0{4w&7S1UUKSN=d;v((Rlnz{V!Th zS!_A;lb;;ljDVhN*;@xx{{0tvxy%`yw|AqyXCvxxb%t+W%vpz59q59WGd%6mkQP2$ z4iY__A>-P6e$2=gw8`BWYWf=ETaPMH*;;3aRoRRU@MpBr+ZmEP<8V~eb2K=}8HNVk z$M=t4N7nw%Al;vb505^KTz#G4k826uO5g8|{hYyldkyYtq$A8zfb2{wX0G02>AVtT z#OI{>td@hGE1lt4svWCH=g5ZAbDe&zh)gsaQD6G|#mzZs5&!mCpYF-dUDScr((BAq z?T-$))uT}^&aj|t4bsmk5&UGZG(U-Aw&b8c&d#78k%Fev_e)1NXIPPzPoHN8&>Fg} zlUatIWZR)Sy3f;1O(?gviS?mnjV8;%xN(D74SLMYO&us(&zN_l=Q1DHh*qsr#DnSe z6rC?c#rjL}6}tas$U~P09KoyUajv^0p$3DySVHUe=GCKUWy>pkeYG=$+;&DEyO-kA z%bnq6xH1aNYY_Zo*la<~@oyb?&I)I!*Hh+Co63=2Yne&)+4{O(HuZlGmfq~E|JZl+>Ix{veVY^+>y3iqVErVKB^7XsGerSzCny3}L& zT6MushU^I)IC^I|zlUDKArCn+H{zyQ6umaiyajhDEM%wAYj!WIz`bAwqH`JGys{9- zt=~gEU1u2e8)Ge_D@cys`-k3fc=Nyv6h`X=^$ox!J&VvJT35H0Xk&>|EefRjuUVhQ zhvc@RG4wdOD{|5z|FMgB^x}MmOlN_UssXc*gtEKQMSmgdD=}=19?8Z@c z_r8hjqJLH3aWh1A6I}{%$Oe(!{W6U2OcmK__KL&BgG6@odIsQzULw0q4%)bovZHP} zJabLszy4!4p3O-+LD}`9_2ysd$-Z(B**U8BM{_AVU0TnR{;oljUWn{?Ixg2kDza1A zLi=5l$nG=FM~iF^pw*OP4P|#VU1V24*?le+*{z`LmZ^yBG%34*)*`#Xl-*xHkzE(c z?z54|t}B~|42Fp8uyYdnHCbe*ap@?kYZKW;Ty{oJl}qs{T5qcYl+n5Wup4R3TK;1f zX06Nz{$uw&q=xVIkKOczwm8&DWVh;d6yEqrWcT{{4Gh;rb_&C?@t$A**o`Q`&%H!; z;a%(TxpI-+0?O`&o5(JNvU^Hynnlxomkcdc(h59fj>t}BMIpA_D6(_> zg)wV#14dg&4y&4P}-g&lmoDQpCV*P>)+K*8}CvU*=<^y#?QzT``w<_(|6_p=(*f?8H!!&(vh&c$#z{X< zVHMi%W^0w;>uW`Jy4~vW?4KgLu~Bp(48wg#bLbugFe)t~N$JM0R%lyL~;^ zvDW|CEgRk+HLMibMK-TN!!kv7tLL0V3&KQpeYdC3_=}rp3GHiJ9_FJ>)(4Oq-Tsta zhBSGRT`gr-liS47cpTVG*`512h}EQRDVee}^b*+>={2JEFhx9&wmn5zDY7;f*{w3k zL**JGy9B2s)Xi9Aw{KyC+L+am-?o-PpHLxb(fquIq~%c*^BetVH?d4bR5!OGI{ywM(#cwaBi3 zvdb$H*?p$$dQB7AxlnfT-ENs3pzVsF7QCjlkOkV_ntxQ_3|o<1%(6nP?Y~Ee$AOhU zFy6w7>SdNWg0)=wb<{D=4Gcnr0i%c6=Z9! zV|!3`YiQYQ?fz&UWk-E2IN!bosbz@l3@lHg<`9wHfgLGmXRXNY<)eHQWht_Il~aa_ zlkJ39D%cv@g!*NO?9Nbjr3E6pos^wUgfZ_#&t*Z`g>Mnr^++g1VKYT`{f+Zbx~9l( z;F2VC(Bv*2N$bH+b`&Xh$;DS`{d|mdM%k(&J5>*56jC7eJGE*nw(1|dzY)qjOWFOV z{cgyy8s6m}J0%xee8o{@*S|0d#}|t1&Sc-fH!h0oOh;tnj^b0e2km!jbxQDpm22@5 z+8(wl)MJ;=B0I*Q1NYGn=V>ezETrr<=!)#7QFezF-gmMaNZD!Gi|kyM7Gm{4k=?iN z7>|Z4s0*$C?%m_?!QmpiDQ*6EN&g~bK5ZMikFGV{omSP$Q2d|9sP_&lF z?xbT9>TM>nI~RWxE$%9^%Q{7$nLSH|I5>FVs*L)-5!q#Yv0_ISi~a6Mv@);vkKM1> z8vfn$Cag*O)L1uL{CJVbuKaxzUh__5H}>TXJo!SZ5C;b*wX(56k;u+ZQi7*Di|ocI z)??N8BD=MeU8IJ{ZVqL))bf_uLE5gKvMqRLFOi*bNd;cMcm|?za4^QH5Vr-1?A8`z z{M=k*hZN#)hh_!}rtNuDlRx%T6WM(RZR|tGsXE_PjMDhBf9&cGW~aUX$8O!Ub?iaP zjykT;uGb$8{KpO{x}&krM0UGvP9o_hk=?@GDJZU5WM`b7kGjr2AjB}j;a6oy`KHKj z4`p{OS!DN^va7ozveTvPE}SvuX$&LiQg)yAC}JAJ2!`iM(L5WG-MJ}w$W-Uw|J|Y_ z6v&F~e#ad}hr8tpjw>`Db4E9NiR_YAD5Lm)>~_AiVwe15XLeSZA4J(v#}%fWui+j4 zu~YM~#XlWHc9%XzVbixFJMPsDoRcWBE78uz;a^V)o+NBwO0ee=kzE#LS5qLeyF}Uj zQ5D&lQg*x7itH9pc8UYvvowYg)_kwPtCxxF6qXd?>|l{y*CLD;P8Zqj?HY%dYKiQu z>-_O%b&*}NsW#T`DYCQGPvdR#TZI@#unNph`%c->7)E$wyN-4K$8OvB{^;NevEOY` zc1KQ6MRpByPa>}%k=>3xDafTtWH;++J_?;FvRjl}hT^Y^>{=>2U>nvWOr#)BigoKWVbr56y38G*&UdihloUES81PwQqf%@{uEr!9z{14M0VQ_ zJEI-FMRqF7l#%4E*zd>#D|Q!UN8?W+^r|wi^pD+>Yc+h)GqK+#th2?M|JY6Y9EHcc z5!too-oU#!k)4_(8~^z%vU3<&f=e9M3h}4l+`S$fyKb4$ z_*3{{)`AO$i|i7LEAU_!kzIphA>I@!vP=DnF`02ih(Cp9`8XV-ogu`ZLTa@?-ZY>{ zh(CoQBW;}ik6nl^eOLL%u6B8LTE#zh-IlFm4gRqUpGf_E%8tgL!faJ{bRk`2r*C@_ z?Fbav?T$=Awv{)9_){4DEFX=VaX^S+gjUKf?UKmOIlKwkUl!RFQFg0OiR|7}b|dZ? z^ECbx5M{?55ZT>1TZ$4Fi0ovO@{sCCk=@&cNhl9Qc0FQ`qVtL(yX^;@5!**(_j$20 zI{J@Y`E4uq`agCbQ@W=1Ey1rAi0nR7c0Y1Nc0&z2@Z2hq-AKw#{hY{dH)VH^5!p2sRnXW~ zk)0A{R~;s@JN5-*`B@^n<8pC0MMq>8{l_0W3>4V~PtwMVdWrpR%ZN0-{U5vU)>Dy+ zdR6B*$>8cONWbb6a;5(@t}zMd-ioJa6>Ve1V;&%K_Yw-E&m8^AcPOi250aS z@sIVt@I$(P-lPNAzA_*8rPp9ud>zN_x{q^d*%x7%IC*X?Zl%|3aO)c_7l`N4vKLx$(OqnR^Ddf2>+|O3<2e8POEi+!^L{;d>_cNJ3~5;x zqrrILmOA82&%3Sp7Jm}8(KRyYSi#v_X|J}@dG1AYY~-vVd$x}ptfSXI-1Z0CJEj@= z(6S4B7qFY?oGA5L;gYl~GEHg}yjGg))fRp5DHps}*e|yi4UMMpPIQ|ab_qpxc_?_T zFw5f!%9Ky+91Ajv|9~>fcOdGuLS$71a<80$sMiXUW;CPTiIpt%TETXb9K0wR%~G!w z92Uqyi-7`9y;it7z6FIp{lrtR6((-3L@GLFg4YUfx_n0ZBen`&D})?=hUDGi1+Ntf zoUWoP9lYSRf8$-4!>|}o8Yy=GZ=*fJB~ptxy;vM^+tw ze4l!)usg3EuiO^NQm++MSJQXeUTT8Z3WcA4;$D+i2wp3^{P7yswH*|^Rw&qdAA5|T zbE1?>)w{EJr&k7|UMo!K5svT3eMQu31?>()?9;zm@LJ&&&f!zlTLrHbLR53p%7Wy8 zdadC8YXpi7O@LHjx!x|Z(--6c)Hyrn%uV)GcuN6LCxqzb3SfqFyW19Da|^#_dAXYlU*X3Y2(m4x(Nwe93A;rFIQ0^;+SmrW|A%7_)k` z?CF(qFt_-38uePC`D6<^`KN%VUMpA|S0QfoRKaV7)$(7^1kcTa*9xmMpCgCwae~(h z#;Mm(E>07?RyY`b0PW4l$JA?uQ4LP$!n;yTy;hj;zBlq$YY<#4P?qdqotO?xy;fjP zYo;k3lOxn?g@;a8_^7Bh!E1#>z7m}MqDJsqVXyxN?4kNy@LJ(^#tE#h@>1|x;c?kr zj6UDR)N6&0Tn=72;3TGAEA-R+j_3XL!kM(Jtg;51mgr#WwL(N(8@`fpm8V`S@F(TS zUE|?t)N6%={vCMa$*nB)TA`z^9)C0JBY3T_Ahi^`oLVY)tsvi}0IzU4Ab73N^JNYec>3w^|NQy;ivPrwaAuCJA0EJa7Gi&bo#RjtzWm&p^p5 z&k9~EbPT+KQbO(vUMpPIIfO1HzQ)vRg}uj?qmY)Lg4YUa7yBdM?e&6V333Jd*tX(! z!D|IImuL5PoRTBdYlYPTGCuQbo8Yy=h4>NJd_%3^wL)gOC*D&3UGQ3=)aW?wZtzO* zS|R1=9h_ls4^yudPWfiz_G_mw^;&@&UyL=RKA3u~&~8mzbx$YZB8>b1gy`5pMcvH+HPt{eFR)3oyc&$)Z`xWW^2^QQr_&OmA zjsJK?@LEB`|0Z%bOclIVuzq$J#cs~S)N6%P2CGoake`@(t*|97aTwSwEh;rFM}IZ^7h!m+3rUQxeY@LFN`t6}(yN}b@fLdtS?Z2GB0@LItx;V7MZ z&lS8@*vj6<{yUN}^;*Hn>;nkE4NZ1%E>sK3tkEc&(6^ybT|2_=u?23SIR9Pb&Q*c&*^_vV?be(=2$c zkZ(DFA7LX0)N2KM)j{k6GdZAME9k%c$*wrtEO@QZl`dFGQc&)I;<0#tTn2V{`3T)PD)NjfUOubfEF?}eyy0}j8T0zG+ zhQ003E_ki5XtK;?DxDLhUMp-*Ji<>8ZWp{(P;D866S+FUYlU^$t~mO^55a4NT9qTX zASh4pT0yJmCN_MNf~nUElCD|U@ZA|qy;e}0@eR+}zX?;X6_o0$@wSQjn0l?S>ToOe zEqcOJuNC&~kRyBhUP_~0E4bqhJY&})mU^w=d$19^AMYl3t#H?<96!1>U+`LC)%15b zA!x7QwZhc%5Ae}#mjtgB{9`z*$v+XiRtVm>1D~(>fT-6Bm%dNOfx3SLuNB6JSMdGa zXq*?l_pL`5KHHeiQPKNSUaZWf&6NY{wL(Ml7xqc-7Qt(ULVXtbSXT;OD|DRNie#yu z1g{mmUdE#+(`SO$3M-aibh+UQqFyT;Gk$|cI7cDswZerzztEt0ixBl%0X=I#9rZl~ zp9-XY9jN|DAWOYgNTKl)GbXN2qh2dGYPO-Ez$CtevUY0xi-y~c7Q9wC_@M~-)%glu zD_HE$M(dxS61-M0)V+g-p1vn|tx%_U9BGevg{jvHD_qv1;<a_x%MP1fv15CYE_&l){ zA3pMer(P@Qh02j*q0iH(*9xYU9eA(21xvkFc+{^6N8gbXyjJM1@Ee~~nk#s%&}LVN zr7!mgUMn=0J;WE(E(%^N4DEIvyG1<~yjJ+b?81&;-y`a^!sX+$@vl`Cg4YURqwDy> ziYCEpg;m9q_|uFWP_Gqw8`hbHILiU`TH%AvJ9a`?i{Q0_v!5|Ks!%0(t#GwuGa8Wk zS@2rn`22H7*YCODwSw1R9&K~HhN#yHxkCz&li~qHy;d+8@C(IOFG196g_&jz=iYo*9w2)PoVUc98A4d_*K0g^iH!S<&)7kZc*9so7%Wzp(so=HJ z_xuC+^sRisYlSMU>-ecpn&7oU)2`=uYkeFxrqAKkmS6Dcy;4lQRyc963JFU^;)5NgB*ET^&^dXt>D><{)cQdW~tW-S_hhN%GoBCdaY2HL!B=tOTlY} z)63uEEXi)cYlR(SY1~BodBJN1XU_}Rb=f1qYlTsTyYYpWg@}5sP&LO2N1ysFc&#uv zzm>n~*CcqYFl@?9erInvpk6EJ#lJO+r0;3VX+5i0y<*ROZxOs!xN>_k>Xud|c&$*e zGy*M8`qIfOJLfD~cp*dZS^>SekMP~=hCSib zvTU8;wZgnFFOm7hiKiX2ve$nqQ>a{|O*K>BDWvk$|!pEwKD0xG*;I%@= z&k*Ey{cGoQSlucXDSpTlyjIAMPDS?p=z4i{|EsU_&?dXXhb1fp8b1+kxavOjTETO0JNo%7mZx4T{Q6Rhl8ZG2uN4ww zXk7nt55a2%`);|&NBx-KwSv>gWOP0Dw&1lwYu;&8d-w%DK! zXja}|!D|H*h5PK;9&Lix3JQAL%*Gy|aVwO|&*rtfVMvGIwSrx=GVc1LLGW5({&V8^LRZ=?+)0z5)@vRsgf7I3YU$Q?C^=rhUT6X4^3JTH%34C0?Y1 zF!fp?zpfd#am76KTA_Nr92wTum#1DUXwo>-3*&~d)N2JLX)`|7rHrLsE9`OngSpyi zg4YUU!$+L^Y`fsKLe_b1hpvvzoQdzs+1 z!o$9b_?Ta#;I+cDl2yF({SLuvh1auV%nsA>7V5QvTJ!@p`eLi#wSvN!@#w0?U%_hy zIqx7ekLz@?AmC99nyT_b@LFNw>=b0;bqi6i6_#JlMOHOO5cOJt1pYvg&)pF9TH(dE zI@EXKkk0qI^PcVKLa$RS^;%&Bji0!(Y_&1 z{(U_>bkiA+ zsz?46yjEzt_lO;StyS<^A$$8dGaWj%MZH$AKJCO0xIyPr>2tXCngVuO-za#k&^y%* z&uJ?YyjIx$XD{}udns?ubqfn#EA%MYk8kdIgQ(XEo^u>3!?b&Zz?guN7Xd z{E2p%tQ5Rfm^Aw}+EH>y@LHkuX)4F;+R7h^f~Kfnz`5K9_f5>b1hDQx!OP z|13W@*%Urd}(Y$hyJqSl%Xht#IPlNHlX}jo`Jy zGw+SaU{|L*4TmqCM1Nd!1g{k=FD9W(jk}0?t+3JVC7Pvw0#UCOvSiUSy)N6$#8b1-|(P&D&R*0x~7&;;GjPKV|i3!HRx@*9vA( ziZtV$1+NuaR^=mq%Y%Z~3XW=ND1FCu!E1$&JL8aY(R0CTg}VnLkn6!On0l@7>D**= za{{uB+Kh5$r0+cLi?*0-rTE6@LFMtn-$)8 z?6=^xg2tKMcwzreXC4NrT)?yP9tmD6#vUR| zOubeJJl2GjuQc<*_*;d#9H}b-UX_-8=q^W!>%N##uNAmwbbd;j$5O8qdhe;iN{^-p zUMt-3rfWPd?2HkBBX$}1ylEVwUMpN~xr-yR?+RWk^l6L3SGPVF)}R2zpZa{{;|?4u zrT_bJ9sGvWMm%s6eUJKNi}#h5VJ$!EZ>a6ZM{mBt);{!I$o(3Acsva&(ccel$ihRi zW3XHRy@nCraYfX6yl6dre;!kd4;&nUchK>CBjYx#bLR$6*QS6$GzTlx>jpUMIsJ~HWfPAV^0M}3VLcPj@fgG_^pFF(o(Wh@X*OFy z$8Fa{(CZAzW=jsW2`?zhl< zg%n{u6KGhTfz;Tuh^}V>yOcho+K$bLu4e)olmDQZZ6K^?0yow+q4C}8*i^c`D69jm zn_|n-^-Q3jl^i60jZSl**WX^;iqr#c@|yI%IK^7@Ol}0G>zTl-kv~v%jVl&B;gio^ zqxx9~@gjN+XRh!lQSBzRNgS%#9nKfy~W>wB8J(AXvKFPO8*!+pvzUC#u9 z^p()t_y%D;6OgHGW2fC|7uGWYi$U6Ec1vme4!xJVl@Vl=G?h&pIE=~kp}7p+?c^sm zE@m!V3?`$!SK*!JyO~G#y@+EakJT>4F;+E8NqK7*@^$!KX32w@B>1@wY0yY#Mh*@l z_ulS6S$!``#@$&JC za6><7LiOJ{@L+o$*LS7~q@2-*ZG$p7WqCW$$?p$Qw|Gu^&J|2%mLa=?SGn`gd>~-v z1=L;f6gPcrC|oF;g@*cV$X`>er_Dxb@I zYB#{S+xM_^r;e=S!3r4rs1Ylu#ptAuv;q0RA>^^rSxLz5NicBBWRhQ}%=B^|45OND z$etV17|y94b$Ggv52pi|b}=$q#lTiu#+GLBRunA8Jbs z`p)@J{&}+XlM)l7vYd2%*^Wm}zRgtWc$0_sldxQ9EMtBsnC$Q2h7ES?W}Xa`694H} z_#Co=xqd=Q7XDn#2K3Tng8PLM|C%`{Ou0x>dfJDm!9}#MyQ3u0&6P+dl%r>Lx$zcv z=9Bg2YT&tfhpfERm`rNdhjG(dWKIE^BxRNbEK-`nWqg(=cVm`;`v*_X+y606i&+oF zyY_Rci4oYOE(n|oC(lJy^dF!PAp3In}Be;QLSlj(gL& ztG$;%R&saHICYORDO(GRm0zK`s)<~_ULb7Rvk%QPImkUb91f56(lPMCe%zA|DU@aD z-|yXkxZ|tB!KSq@-rlb}=a~@zBgRGJ{VFGATbp znFGHoG>KpFU5SlN*F=MfJ!xK}&G5h5|633L+Xnvs*#?CES@J!D_EYo!qqp||NWQQ$W{2r{{^#<$sq7s?^B9S_asR_ks8@oN68|ed znvhHPKl#xx%@g;3<>w0jue@FVotI6>`6J|Nve(hz{yUG`fAji(aYV~#o;I2{O~|K) zg#2wZpV~PguaR&ZnrBV&-+ATec|kZI&C4eFPrf0VukHV8Z}fOVZr{#!DAenJ?)TsC zoq6v5<+JO|fA{Y=Le5_y*RXK>&U|_Q&I?Hq6KT8qfAZ`7S58=lo=3R;&U}3Pd*1HM z4<+QD{CB^d`QZN5Lua12fA!OuKTfz0;e6?rBW3^UvoqhEaNolDggkWr^4WFfrxWT) zIG>QWZi9vvPJI~$W!;C%d?H)!_iLBZInPMht9AX6l|wiTkbf+@vFaF_eb*npJ!p`1 z(ff*ON38*7cYiKJwI3LnFMyEkx}4F#31FIQ46e3DoboU$IIO7w3w}-K79_6#mv4>8 zbf^{A2R6d@f*S}OwBfv(Ltsk2CHl!&apO~^;H$v0T+bO?+3^U7aeKonMj3I22ZQLm z)>gdvjxOi9*Av{wXX8Gx{W)o+BZO~JCel8Qvg5nWAvSpwd4?a$9C|XKb7KZsmAF@S z!CL{Wf}O}3J55;*JV6P*>xq$xVuEkJ4>EnUiTJCg>a2Tmoi*qsCGr~_B`P}GdA}g~ z9(IM3+>Y}Un%Orfkjz)!kCVIEF#Vds$+gpR zG$vsVbFNHEUhC(Yg=!-vsUwthT{Hvkw z@Wt>=eE#iGIAU`cBy|jw&G++6vuct;=Cxh2@AUg}`I&GyJNALB`@utKwPgU4)s>8 zDDQ(Mx8Z;{6iDx&lhHQZ;$tDu?r(=St+e8z>3hCX^D@?J*9@*}W(1t6d&*~;PUTkh z+ywi_hU3RaM{z$Fu7l?23_RwJ8fV(R7_Q}aCqoZ6%id;BgR|3h$#4IsviF-t!t~JT zM8P*oW;VDxjPP4RY`q!Tg7Rl*@6~mrLZ+FZvMm^;T5KX)L$2!Fyp7oz#Sx@jW+yqc z$dkWtL`sJKiI*5ZvB$}4L&%?!LdmyTN!ZK8n>=5j$gGuX$B$+&Cmnl-F{_tpl4DCO z$kg=l%=b7`QaEZnIZwlgZPRNl<5XMWWhg5V>4E7oK%nE!j=S!R|g@1)7ohI#x0n zHgxxe>8=U!$2}+Dfn&oUvaql0YtW6ftSTu?DBdnp`p^}v`y38lfjs?&ib6Vt0dVZX zUzxFLA^QHo9m?(dazjgcfs2PdjYwj+v9{x&yQdjktD4M3Uzh_8#v|Za#Wc?AIsFDs z?m*8@SaMrGZGabg$>>X@4W~RI1RNR`qnRhIIQwlH zcIPHIeLetd1dQf(4O|cBYtymeQ+3X#yAwE%RwO4?+hkq?XTbf33^{6)A=^=^3**r= zvfARHEakouRIXo4I)cW?-bH7j^Ch07*WalL6HjeM@>xMd>qDH5S$#J9;C2Lwx@Rrv zl48RTye1{ilj9`&2G7N2xNt2C^nU^In11^M-xLOH%JludOaPlJ-6|uSOip%k%0 zRhY?lY{{}jb*Si8B3XQE3W;232r82663t_S$=a7TF!rsdB(rxlK3}*Js8pjsUD&xEdh8 zCLNJ!IrV^QH%HPgyrEJ&E(wH?)429bbSM|3V9{KPs)Bj{QVvm_c{ z$Mfiklt924$&TH#@PLV-Wb>JPNzSWl_~e<5B(Jn9Ghqpf1SoTkD&4(8?L8gFr4V=fwJYSxdd}5Ty%?J59QC~K3GfP7e3CvWKFoJjltmS zum+nOj^X|u@q#HgG3LGxdw6yh#HVVL1J`q8$zS!r{465;_~SCw z78UrlXc6hY%}A!7mWMXjt|h*$o(YR4??%g>29g_@yL4I?SFrB0Bgn5{kZhgRhhOwo zN-WNulEkSZyk>tWsg=)@Tpn~82U_@$;#*yq!7(-1LvJN<@*T`Ly&XcDK3bE2C1aVE zbR(i@Y(VBWn=rjL&nIv8sF7KVW-){E+{nzMCD?tIHS;#tk94TU;L9uNGyF#wnfr4% zRzGLKm{8U$6wcls;b_hT&7l9|3)GRpc|#_DpFgScIF3f{(PmOgSChUIzoC08domdn zc4X|felUALndFhbF*&hm0_42EBUz9%jNJ6H0{eG?62G4f_XadobAWm_ByUtV!J6AWL<-kUFSCD5W^w&DNTK%lZeIVB3HSPI zFc_R%j+=Uq&d?&Cta4>(j$ zos!);+Y`P`b0E?2tSrXn4YHDYkQ>cg5?<6$AIdzCxaS1w%Qf_Q%7B z!~T)D`L_jQ+#)3(KF&(J^2VGQ9vMz{o$HCJT_-WFS^?zs>BDqwK^=xqUqcR``-DdC z=*7r&T}X2N_JOiPzaUwk_$e! zvF>AUNFQ@d3ufBlklP_Z#{Er*tFY%?&r4yTny>7&N*1fZM}YmoTe1^QQgrrL5Lkwn z%3htwM2bV#!J8aaZmN|Mgx*;U6PmR+bY2(o0;d5QXvhtJHyyN9N5ZP#z}>`4!1k;n zyxw5JZTr3s9DhDV){AYpnVy^Ayk`(vw%nSVUljp8tWw#LakDs`eNw3O^W!T5O}RLm z5HKoPgrAj;<(4RUL$&oi401y_UT!&juWiQzmUQK!+vmWc98Kc%{VZ%uHwHK0vI|=x4v@c1RBgc%p_#3BpaV6WA3}o=-f#jI!Jfak* z$M_GLOg2_eB1Xx^jMtobB;oWxBHccd`Jv!S#+><$y}w&A)<=BFvy%x}KEj5Hm=Q)4 z=8wmHjVzfodQRuy*tB)_)0hic;Y4?kA{shmGNX7afGp3BMn`=ljANWTsaJlFex2{l zSPr%)Zce@7qmSiLhd^{bL>I&IfLz|Fq^xSD21pj2mV@5GtPy!!CA9y zv18get~|{fY7X7TYAQpy(3a(JeOn9WqPlT!M_a-~hvCF?-5c37Eq%~PF(E2RXJzg` z`#^q=g=B2GrA#m26I%Uh4XM{Vov?W0VN{_TKpyp)rE}+IPZYH$oZMJFPV#N)tTc1l z$4avgO13KN;z@_-ds0<~q@uJ(^iNkZ%4PubTzvp};A%_E9*$;e zuNsmKOQw)BD#lE__FPgjaxnR+K9f12v5IWzQ-$SjSTS9yeTdQ`>e%hFVGPSdiT&^? z_)LT)v!zr@E<1imo0B(<$yACU6XvzCHd&LIMmCTP>ADXsaABB;AP=&B!y9zwc^~HP z1P8J=r6-(=t(LraFZ43|aj+ED7G9BAGaHfp$4xNWwpf`-yTMXIpV56raJ|n-V1^1EQ`kL`3$-wZOY);3Iu~*8ZaTv7B4u#T zn!~9t@`R&WIq3LU8xCy<0tM%7X#aIa} z^zh5W#5&*A=|&JiQ4P)34Nv>M{Y;_NpQg!o&6)#(ZE^ZWcOBG$))7u z_igBZXJbQ@q-BaGZYv5SX5*hpoXleI^h`gpExtvPoJ7|u$#5g8X6nq^ooYn7bv}9a zeH8QE+<-V?BZ8JqWv=9 zpe`<6@Y+e4o9@sRj^U-CGFX!{*3|)K_AHq2WCFLErcbez>H*6lE-!u&?A@sX{r%@~ zsgY|T_f9UF+0TY^{2d6TBX*(gudTV$4iT`5{l$7`&gORINx?E|5dYka<$QcYVdzYA zywhHvTQkT9-j2M2uc>Qr`+mB>r9<>xvzD%=5orx$XAC8~u6>YQ%bf^qqo)%2QJn0I zni{NlJ)b=I?jW0d>O1<;XEm`4xRX%U@)jjtP!I;Cy1zQ+m1f#>oU?op5*b=m*{;*KgM^d zBPsRh0hzbzCAzPHWbPadWoC~gv&Kt^_qv%7UbROOAKs0)sV;?ng+nE_Qy<}HpVouo z+A8g?F2pwo|nL8seinRE9v zbYa*A*gaN>dvRVKRQP2uTw^%b^Nto21kQ#6`3c;V3oMYoV?gO5%en7&faGyK;qIV0 zTwAIKJhv!7k8A1sn0p|s`xJ@h)mU@u>9?KbyGHhb?i}tMov%BhSe@4PhUFr%L!sa0 zskn6b1nv>`f#{$McpIHdwR^J?tcO+OF4{_*25$pfuMH*&OFqjC^$nq|U<%2uJTEJZ zRfpIVTf(L;m8EIXH9E$*5v48<6XLUC>2uMKL~8xju39fau~);$g*8JZ2feh+^60nj zmoNyvC zgB7Dszv;Ex2KCWF% zjy+Il{Nq7|ejP8T%wVC5mKS4=1oL(~@M;-0z`7*Ta>a zeRaYY1mK9hn;?GCorLbSclo!i5g@PZAiH`vjJ2R+9Mew8WN&&bK`rA$pqtAFS(05c zl7F)ScD5*TK0iCqpH%9D57Xd`%tye!ggNky)#tXkn8CIs<6zFpk^f{O_u`W5 z;;4bZpPom$9bPFbJX4Oq!j)X}&Q2)YACGJw`jY#5iFVP{u_(|fj5JMDmoQKEnJuiB zl1qnnO6D(7!rpXjE58qsw7)-qJtG6ir9QQiIo&_t18(kQ)Zf0$+??LzN#;W0IejGa zni)@SCzz6ErzuR9g9XuBsY%KVr!zYiEGJXnw&6zJl2MxBO|A?|!sYZCer0_KiP~q6 zGw8GZ`(Y_57_*L#N}Ivhe~TbhiwWy@U@EhB+9qOC7fjdX9K|fXw2nA6KSNbx)tNf) zC1la??l6P?r%YXKK_1W51lRld5}H%IGp~5rjmwffDjQRq=p6ItxBFz~Gc?hbqA)mU z@Jwc#eg@S=`hi_yt1LvZ6d6x)1HMX~+hs8T+K?@b`ZSt*f7TG}+^4|jZpK{l#JO;- z-(ZjpoyoD2R)NO-N;KuJ73U@A3(r~;5x3KZbEpmlk7JY3+h9v>aj6te4ftr5{dyWV zs9OZogtYS>{A4awKM=It_u;}h3>US=19I=Z!I?Mva2(?R<1%}a&)chI!^X3q8a$Rb zacQ!#{k0&XX*L=9Wt(hXGhHi5o91Pb?=AC=q3de9ZXmtR?}{H+;Ee8-2b1%s-|Hyc z*~t#{m6FBN-6f~yUgfLQq-4nWtCHLu8}XJmn+UV9SmGG_823N2o)n+x!RU=tAVU+K zh|8!E%*$62GNO0}2{|{BnZLlCgw&5B?+OqT_P~)$%2FnMUd>@HczBW?+1dEhcpK(X zXb@3o*oxyWTQhT_BZy}8JO0z^*^B{}l8IZ5*m{{6!(dji|M>Zvsbjt?E_`~F%0H= zJd+LfjX|=9e$ek}i)>s?3EH0O2D|5}b6P2C;IMo?yptQvsjW2thvP;N=RK9%&}t2( zSBF41sqtCSt5J1mFwyCmqZ6%r zjE%LGlJ@y4CDlH${9#imF%G#TIr-ZI_p%Bm>)w2o%&sK=hrRa4VV?goU<5EZxjROvu3Y; z>TlKmJ&zwxovN2ltETqMZ05SIU-w?!dq#L1I*E;+s4v}+q{VLT8O}yISW4$b+pvSi zKCJbVuF`(3DZ3nL&*B4!wEzAv_9&?-yFA@b8oMEm)lIGzMz;=@ksSyh43 zt;4d|v}ZVef_S zuK7qB-_ntGpBu;;0?p~ht#>89=ejYo?!9TPu|l%znGp;BG?0#W8X{Tl|4h)3j-`!; zme@Q!xk2#KNusglt@C5YwG*2C&Y;^XtmWgAuN{32xxTb&sl0Ej39;#zNq<*V$an2u zPaKCO(XD=8<)24CAt9T`(vdE$6~nEJsE|E~8nw4oyf^AblOFY^3(vbKe69r0Rz2F$ zX5G9LPlBUqnCdeL^9)ctESySPP25j*!#d^;k94|qlQ+rw?ysmj4Qp7>>}9TJ`YJ5b zvS>lehbkur7r1e9I-PlSuCT9NCxt{ip2~BpgxaTuid9}iss8dNEIaM9{N8m+kIu1U zyZWAx-!+%eD{0;==HeoG!2oS~#&$TX>TE90dwHCgy_?7;wR^LDd9O)ikbWw&SbN-t zyjRHP+QJ;yZMbCWz!j?Sk#KEus6Y}nE=E{=IF-eEK9F?vR0ZXCj-Ce2x*g`c$j+3_r)<#nOtbD*?o zVhUToWU;WTE>OCrLl)a}?6YdTxu5jGlWZ32{?Q}6N+z{9pU#vYdy~MnU8SK1rZNBX zJBj}<3+Xde3_CLYJ!zw*C%wNrh*h38rG2_SkW}<=W(zO(qITa4Bt=` zqJ8Ft5biyOYB6RrJ7bIBGAWUs>-Ty4PG^bmp)i9w<(kXC&ofcl{miDBn-9x3!mj5uRS0|>9N$n(nxW0rUA9vHki_0ofH~}oTzJOH#*45 zMbTo9Kg~E`L6<1|D)fhqq`jTL5mT)I#kfXOVgFw-X$0$)-|nQ*Z=ONK$u&SRr6`-y zS^Z?kUA+|M`?Kh;;wqK$wu_>pFrBvhIa65K*j7ap%` z8sy*FdeVf}wrpHog?!CFQkvuJ#Xg-`DmVS!m_D%?#@-FGmT#DUimY;+$iiE;%*%G_k!D5NaIIZv5dujY~%nZsnZ${*3+sBd)7rJtyvVx+)7%otmD4Y zwI9YY>7HA{>+6BiwJ(xcaO85~QHvmH^O{U1`BzhjP4trv`Zt?3xpmm1csP-^w8>z* zdUqppfE5m52`pJpLHvKWmp+eX@v)pOL9hW^vT?h;6#edJ(W3{BsaDSFtuXYML3;$H2}^20>-7`pwEkxW z+PaP6d1wT^<*&>3#(bB@4eU$r?e56Zm!6S-H17o8b>hk1maLE;*riJ?O(R(SoKEtq z9nX=m@e`P=yKR05%^(@=X0Y^MJ8dGyo{~MP%wkndgC&_UBULlDWV0o2wn>%^8Z2B~ zoW?pgzb$d8J1BUhPhkt5HI^3b`yq5Ih+;XN+DSWHX%G7rVcwJOD4o{Noz*XJWQ*5% zNHb@Iu&#cs*!9uA(o<&RSTk}@=usRfjSf#{d7X2F4|YM)De_GCF8d}z;(0%5P(wCz z>Xz;yc}}FyQ!?1M^>*ZaK{sh~LjwEMcN?+#Whr&c9nI>ezb1EwHIWLh2e7G1V;U)Y zDhYhvlg+j1K`S!%Nwf}_FsJnXbi}xElC-n$gb_)jsMg6_Ht$|21kJ7qbmhRD?Qv1g z!to{<^krsCxiH{@@^Wo99l2$W+-86V8DF1C?UyO#FH@J1(RwK~^wN8|v2c@IvKvp$ z-nLR05?HUi6-w7dOBEAub*4XWc+lOYJr#8W{phP5R@D5wr=rUQxZfiazE>jKU$J-H zWIAj05#qiOwAN3fEmgxwr+onm!}M(0BYL*1(#%^CuLr+;cDqP*PvWX@FP%Xf?@kbG zF4-vtMopxOZ54v9y|H3$f_ov)*o)@+1BW0B~=j9qpZ0Y<1eVFIs9C?SK z`gB^8aQ2|Ai+tbti^O?bJZnA6Ge6?VEaLpnbmlJKWOIJTHQDejS*($hzeIJNs*De3 zvsI0^N?bMt2*c{qm{ZIR$v*EQVTb)xw)&v9R2uMA=(KSpn=3V!F7&cstr`U|qk=Bd zac^DO^si3L?yI}>%BaDt_KpFo)%2AP@Qh{8PCXQkE(w(OJe|b)eOx0j&md`|s7y8| z-B37f*-!fFXEytBNzMb|6E?b(fA`o5)sXZ6+(fT1hvhk71YI)R5Wp zno8}P4`l1?+t7b1pG$gmb7AkQyVGlS2PB5Xj5Qq;MB|4|lI#ljAdHw7L$8NFx6xMY z67&{Nqe3#>{_2jKu&*SYrp?rsA8Vqms=J>}V^uTd(;t11&Fz*&dn%8}mlrJ}YgeVv z^1lDdW4m4>y5Gms-PJ7>@3u9gD_#wO9=Al{AL&5*I}z&D&_mJ8$d|f0cA$BFo{EO4 zBj{IKO*+@rU$On+Bs$bxMLe>D6fZZVQkF29On4HYkVQa$T{A}(v&365yesg$X1nU- zX;+1>T`F}npCGKr-cuaWa(N>`xGn`6lwb)ksMv68{Z@T`H4U0Q*QNE|n zj>aTY_+6z)`xT$X z=8yK0ShTlR^}CeKns(hJnR>miP&GK6eb{?d61Z}okb83~+cHy2Dm?uptX&e#CRm$E z^UBTHRmVWK`C4b`#3jAivWeZ8W|+HljrSmyoMgnhZ1$1*jUCI*`#u#$jtZ1c>z2f3 z73aZs83akwj53*Ch?&qYp`Y|O^k(i9-E$q?K&2_IGMT}4GvaFFERAzYViQ>&Sy^W- z{Sh^mb&Y;X2JdSoZPRTKYq!#fK97AV5i)wS%jw-{_03{Q`f+nM$UcxVyF`iS*-t{d z)zP%+%l9^u$LteQA5NvxIVIb=PwOk}8k$bMMVYGIsjpEU3J32Rw(u=YlipolF zYIewmo;cP=!KMwTS=Y6wPhCHSQZk7u?;Rt(5`z>v_NjDsiwQ)(b)e#H_iS4AbertL zH*ZDpkZc;ZbhXMo-c7M$eJZWpI9dpw<)B!7ZxSsHPzjd;O%z+kLvO}Klbs%`p=i|L zLp_2!Fo!8s@-KrOXkKr^ju@_&XM+!Ky&A#}ymOT|Yjur`(TrmY{F3s$vlo#K>r>eK z1#@gB_o860$zW?2qo+6HZym9vlZ-??MhlQT6! zRnI`_oxDUQi`y&|jSG_Ag#6aE?jU?Q)=%2|S2pXVcwb⩔qe?cqaR-YedQ)I!hBz zCNV#qwM6@A2k9nREHl0SkVIBDm%a=c%qG?u(6NnbC03VQ*;4babZ<_nBwc2~PHP9y z#gAu5`gnX5bheJ9v!j052-ZbH+ip|o7`HxF3p)e|8K2XrB2OV!wl#|e_B<#bu0NZ!**KkQwS6t``sE@?Ul&h5E^Dr^8m~|De-EW>O9#d8nYPsT zNFN$7-&rwXu@}{LlT!QMeH7snhtZpJ8&ik;eu{@C7Muy>9svX#3cQ9F%hw;3TA4(+Vyn>(4dR2&h4!b}yT;65Cq zxs6!$CQXICiywV>+KLV8ctyVMaA#`%(Sun%*dTA>-h#&731#Iq@Rb9*Z;}wl@ht4j z{CwTP%Sihcu&+xw$!6;5M&!_!OjfYMMN(*eL3z6t_5|!%D+!8m7Pd9XV5fa6CEW~m z2z9mz>}PWg*bDSdm^6MA+tt)W`uVU4TbR_JHFtK9Hon`FJ?#Q(SgqZpn?Da=HhYcP ztyA98m0L$MA@H?uw{f5};#UHjV!2IdodW9`FfQlpvJ-Tg`b($7c>OqWhH`u}PwCLD znQVqfQ)0QLhje>LGMgNfL-t;=k$SWp$DYIQN_)O*80XJo%4 zT|V-#WZjYWY}cKBv}{Y3xESDCMJTu?4e6%4eqCSzik5jWqp<$ z9~7jhrZZ?+t2E*>DNqr3FN=23J}%3?=%eVh4(5i7#;K}G+!ZF1)9Bf0p+bi)T@=mw zO`-jNl?u91W{QE)QS{-CpTd<&Ek(=Ze)PJlC9`>O4d!5u^wf5DwotWMURBkS3g<%D zg=!zUzWZGg96pYf4_uvJWVwp?&P-;BGeT`PF4rUSvP{ONb(7SrTA}>+Q#MPlSuJtA z>>#{}%3!y)T#yXtzg;l9n82Fn|CSg}trg5dN3%uWjHRa>+cNKU1K673_EO6wJy>#9 zPw1b+dgZ15%-GX}Z4L95jw~I;+^XLSbFKtPuSX`ZiFf6~>{&t5R+0=>Y28im9ON%G zhk1Bk&7;Z#%RHqCPcm6mlos(D-c#E6aWczayqts{mq>TN8OJgzZV|l}t)%*kLs{dJ z7F5r?PEt41gZ1gvg%a0t$r_mz+o|xQr|4`+EbO`6R08*jCN-5TTXuOyLCt6{Iti)V6Y#VO)o zJCPogHC1#n(xGN;hEeNcD@E`9Qu@1-7ky{cU2(XjCw*&SOPy?~VsU6V9q>etKK|vW z@V^~TpPjux96W*)h85FkPSs3ubxokce_s|IUtcBD?c%Fg2G?JK!}_Ug2YD#$uBXu+ z2ZMxWT8@fFUt!PTz+z$97<0v%(2=yr_nXk=r?z6?UVr*{zXiLs_@;as+@BQY?Z(Ov z{3F*LZ$JZz2eY!uK>2{<56HBcvFs$+jz#cB8{hIvM+rcB*&># zx#veVyWL`yq(`_!NZy~pj{H0;S-5nIurWT7J+u2M$*FlE4DlGlG+(rluHDdv9Z&|d z$V@w_g_|=AxX_DrxYk>`X-5#7anY15sqvEbIupb0guWN*HU>y19G=GBY}_e4SrjBK zxRlOT74#N*t?`#mhU@E?mYo2l@TKAIPn~=f^g~cSbP%6!4!jMwK>95Y#wD}nv{UW}$+zn==5ow|w$&9R>(5%Vwz0l+ai4jTqx&@2iX$Uv{R#ug zZbzl?y!B*y&3$u+rvqbzn@3V<^N-i^f4*6!N*I+*kED;0+jP#&oG1^tuvRS#rIi+vUI&ScYD zTK1}}7aoe8z0;}3J8$9M4M#<8!BkqAw_n&2-%hdGH=1^N_*uAVucKISGk|(@X~!b1 z?!bQFZuD$TZ#FzHU;atkh4zIubuLOY4gDE=lH5cy0nwi?TZ zUTH1;_{)eLeKL?8$+MMSe%y_XGwaO;JNA|yn;ppR^*3j4lf9&qZ$z`T)gOgvqXMKA zEvB(kBlZf`D}tn^3F*u`u#XUZ(_fkfeKQNWiE3DOUup30ET*;pg-qvcFX{gJ6xOSD zJ{hyAqjcuVIA*l5njG{olrG&7#wusRnxOtCiM<77w?pjdjibjTO9tAo_clJ%hAfnX z4A)|xjt-}5irPv#JYvH8p_AzIR+l^UxISK(7??`G9XXrdB=MzcW;pB#7~?7LyI__B zzmGr;_q8#&uZ?#25+#BA-2}MbjlQ-xVFUNU32+}Ar7yp3hx_9MxId1XSG1R_@2^>5 z^h|w!g?PW!|JMKi`5dND_^mOUL<;u|G|F>;-;TZ#Bi5Pe7A*0azgTZNB4f)QI*7IN zh;Y{ZhMrg}^Cq${vriKBb6eg{Whs)8V*Q~M_SEn0D^owNr=7*#X8lsBYsuv#7FDuF zP}eUWvl=gcU zCf5D*I#KIJeZ{(_g3{M(?Zn#KWC-c!yv&XjOKQSZiEqAnTPQ#oE62Ve;H#&-Id=)tmP$R=$sZc;{SfpB#E9KutBU9E}7IM$5^b7|IDWHUAi9X z*Eh+@p!Ur=iU05K3kkHo|8}vSaB39&z51cUqZJ_3|G-)E%z8|t#`R)Rx`rP*FWw0L0oCS5g?btMSdE!p74r(%rNh4sd5&ZqB z#egn3#0Pq6>c^MB@0|wCj}z;*Oo!_2i4f~CkFDvwLB3-B)69)}o^ulGiT=UV#?4r) zr`g8P$ozWo^($c>JNR3vSfA>eO6xbqi?vQ!7QNU zpM&;@WGZc)Bi2V3#Zj*#)ne^a5J4SI=}`4CuUvg;*)MCc-g?G~E^Ox})?)@5Q-9ZB zu_n9f$(@eKgxc4oq&#qn_;|$7cv9H|eS5z6l5E34^sW1q8s+!rsNE>I&!`;kGg7~o z(lJM98J>*w`D&qZUYuAb9MfUlc1MWyn#b0xWRR~|cQtckX6K#6dY^wVJLhUF*6rem6YJW`%d(h?)jgX0REa)`I%E zM~5e~w#GSPJ!4TEn{c#RtW66d*tAnROnr=zt1najwifFe0ZKM)_?lv&$>nP z9AX%WUXpC9CXyBCrIY(~=Q401+dUCfu0k)R_V=YH;hfaRxITvYwl;dHUAQql;EY~+QdUpwY|u-_nq?%^ z553fQe>^FLb5cL|@Wx8n&LZ^E`k)%6X$^X54!>tjeN14>9QeKv^io7Vd{5+Z^iuqO z9X6~Kz4Qv!xf}+dm!@`bV^PP^OHF7nONMoQ_3L=Gk73`=qL-pzA3}|BnfO0OI;FDv zCFrGc@Y1jd^wLDoZ9~8-(M!#*X0UhXti;cA@W^EL@#iYB_FNXn7VknY`soMo7YG;aGYBt!I8uvyoJ>FeU;y9ONZ%au4 z=aOY~JPF`jT5#i%tRv@A)v_986Yiz4e{#toN0`OA)cbU`P(2^LbV#Mc9)rKt|6?F< zsg850+T4xBoJB9S2QIB}LoW%yfDa1vQe?j=O#TD8v<-9%*@9kbUY5l!QS{Po;L^if z>@a#M3Aps20=-n_=F2wyL@&j{7;*<#sXkASLB?!f zZ}d`=-St9#NA!~3n^IvO=hB+t@xt;R=%pqSA z6s}3s?_0iChmI*jFJ-;3rjNku>c{U{yU}l)OJCiC>46~h(zSLm)UOh~biOa_H#S8s z1px!Tb1uyWE@@6cFKq%Y=_I`rxwIX)M9Yy&8-YvuKafjBz@@wb^paw41kC_{tIxrH zpf8>N6umU?sS}OVL@zZ0E>&h%DyRFqi-U{?m?|nL~Z5ev$Q;jtn2&`0}n-y@Wm~*L- zESUKOqL+LuVwmD0dg)W&DXh6Eaw!pZXXIT)HhsE*S%tUU;CF z&I6a$HAODH0^RPKAeSsbx5LelOJ{&fYhj#M$j`S(M!){zVzl-^ioBo6Fu7o zy|gsMnEvjCT-vy|p1g;1Qa`uq-%@fZ0KHTl7f%j5;}|D=y(BwWf@9p6AvMaj+)HtP zaA}xrj-VNVUJ5y0Ez~YRFEuXLVaxWRmlA|G2DlU|LoW%yB?lRDX$@S5wX#Mo-32bqZGl{xvp9~OEJZIp z0WNjsT&nc&We(rbOW!X#vDCKcrRu@PY=H}M>FAz%!I5(*<6WuHf^+HCn0P^pbE*5w zORBdeIL7syTH|5x7ca@Rb4W-OdTB#mHM!2Y)Eu~UnR98|OKVymh+OIdTsn9Hz4Qg< zxydk}Q|r|RxTIf=URnrT3N%MA4FCo_;9MF4TskxZy`%&#eR=sp9@BrmaLTMefyMTR4{t zU~V!#2)VS}+Ku%;fnI8G3ucA`&`VR>#jwLw=%pRNrM+h8CEzv#Zi{)D2waj+Loe+G zF8%0&T)F^U@;iiF+6`Qie@8A=0+);n&`XW>MX;CPZ?zVwko)`KZ*|@CnG>6G-Y6f9CDX)X)Rnc z6~Gv*J_n~mI`mB;a)~^#rgof5UoBybJBePptV(bn-^6IL3Kg&S0gjkV`Qz zANdaBuKKz9OXAq167*1CdJ=R&LDZBzmb4Tz{X3K85=8Icpxnq*u^O ziNK|DbM#UOaA`j05&`$fSus?dKUv@l6?v7qkxmU^_LQhtGOtY3X%1)e1iGOfuhgFVXI}E+l=uoxb z0dqL@@jpv-*zN+xqCG zTJX};-N>a@z@;Muy;KKW3Lb-8dI(%P(g?Zq0JwBe7rC?)xMWv^UV0B)N;!dEn(XPz z=6pggXjE)mY9soTa=MzoJ(D9#FL?% zOFjjave}$VLg5SLInJdOe{iYU?^S{=oRj)}Q`S@qCpnjn0+)c>;^R|aTeBGf=%w>8 z#&zanoCM~%!{B;A{oH}TrAJrMOCx|wJ=>v|#(#!s;&QB^{VAC2}q~C%*8w`4=vQnB@>t=%uRPE2OZRd;+hl z>yly}T2hQ$lEd}44(HMf;8Gp$30&|BrY}6vOF^L9NfmnOtoIZ;y(MyK2YBh*e)Q50 z7~@*{pqJW#ZsrBAMK7HKE?K=sFUK000Tw?E7hM5E74)ii_uG7Pp#Py&ZR%+-v4+9v*UfxOJ6}ZZ}7MJxt5^Y z{^sbVa`4iceaIzk;8J2=^ip%s&GzMMag0l^&R~<@qnCnVK5|qWxum-^j%gO6mzM5| zV426!OATJWEcOF>DeR^bD{PKjN&+uE<6de~R4)iHhf|-A)|XOY3iRUDb;I0v!IE?7 zMnI)%e{q)hxP@+w2Yfza{pYy$XFdGeDsqQ&>2Xdq8Opgt;X1B}b1D1{^eX!ymrS82 z@P+pTia@ucaDM7@&;TxJT}Lk^1D6WF5TRP zUYZ3AILP};&DA|-K40>Nc`iMSUUH4_rIEMLOP_&DuYS2w^*L0-+`BcOd&es4$sW$7 z`K`*x8t}LJnAi8>$%oG9C71P;vJ%dv66cr7J)BDiz)Oeu+`AGOkk7faVs*99HHVLJ zz@-y|h+Y~5Tr${=UdjWljCp^lEpX`?=h83W(gC<0P`_7bxGzh&jb8c% zTzc{gxs(B8+&VtS*(>XXa?Yi3koybX=%u%}!At+)(zZ&~TF#}6cP~83|H7qTZE}df zxfHj%nzV%Zoceq&9nhhVN{~x4o>|lIVDwT1tf8cEE@}1+rjg$0rN&k^=0-BjD0oxE@fSLm_af&0gfvTv+>h z18aop$3OV_(uHr)OYiSG(INWCr3KIvXvev_{W?dBbXflq=%o)Z#+mm+FFAm2d1H`E&97vz zc2Chu2Z2kba6Ov1hPmu`S=#eV1|eG50*_6*LK(xJyZ7J8}bb8rMMjpXyClfWetGxSn5c&R;~d#?a4 zH7!Fg!90$(Ge<7<0WPsU=%rr3fc?K#iC($|{iQdYOZ$OKtD#S!ey_q|zI62s^wMbH zQZk<}Im6tfk4vz4%uL{toO4NLSVlZKm%2ZWCqjDhc1;pb`-&(Vve(0rK=vB@+ja+I0x@`b|tIxR=aOphf(mLSM z58huY0x$K2HA3|x^DHzPwU(g>z{~ z@=Fg`t6=K${BvCUv(7ijA!DGIsy;@5d2T!4rn>H2s6(F|L@q@?x27ARFRy+)9k?`@ zbIH68gr3SH3#y)+)YB!#}b`neZ@OGcsSrD34k#I?A#TLoOw zxr|$Z3j4?Qn+J!ny->?!xs1FIUP4d+tUA6&X+lq0m_Yr6)pUa=O= zN&VctuuOAVY$KF|w%%hymw0+;r2 zE?tHBh?H|F<4L@*g>$LJ^h%W__tLNLFFi8i8qRx_dw@&Me9uW5=(eQ^ za!CejD7L52OVFR7K77wfEO_Y!_tI0~(m}rGBox+B>)@Q!dYL_TqKW^*o|8)G{lTT#u;-+db7?v3ImzRDPSU_j z!Q4v^U>&sw=TZW2X$0p|2iS8mgzq^S2zyR0@jWMFfJ^83o|7o>QYG&RD1l2g;pnA! z&@F!;a!C)?P{y7|F9m~_8vjBr5%AImzUO2K>^bq`drp4Cde>^c=j8oEC$^05IcWv+ zk;9xzEn&~eD9)uA*mF|ghx4Ti1@VFr=hE$*N>v3PdLuPwg&br z^S-wV=H9RP+`IdGYx>a}xnyhZMvY(}gIbF&z@_fPkV~>h>%yaMaG42;|$%u2Q!wBdJTthFJ z!#;r(e4oH0So<37hV!Mz(D!c5``+JRzGT6tmAu5qPqvP*PKflupT$4 z8ppUC@Y3}*$fZ!wZBjmRDHOOg?ksxA4RnhO}$pgHU&%N{= zxMae)^aZ%2!MW7^nG;*U*W*kE!Ws(S3%3~hOEsKJosG(b)|^Wvz@?3xOXr4Fs?s=@ zmS?^4i2e(gtYGbHC+AWU>^W)RT&jYeKscX!$HJbIk9^O`E9fu1N%I@0hj)bLoaOr-F9Zr4M}1$$H>YJKhu63tT$D_nfSS zJtw(*&&fx)W;*f|y<`twn#H};81|eT=kp~G*mH7$d#N$3eVyWKyR#3+leU~o)BfmH z+RUp_Hsf5H2VVNmo)g+MM;OZYoQ#J(CkyzVlOWi0(uB{wpTM4zXujvf7Pz#Vb4dz& zP7L{;lQ7tGGLG*#`2k~GEg$0s0+&kp8cH5;>E>wk(qhotuHDJ%lYR;ugV`@BF|AkAdzpf$;aDM7cU0+{KG&q;cN_1!kzGMzug3m`hpC`a2!%F1RKwv-}?+K{qx$c{gOU}Th z`B%_OUZ9)hD&*2C@KUW3y;KXikLGJAJ7MnK6Z#bD|Mwek$&7QU+X!EF^cv2Wo;-G9 zhq#xv_cvw%?!lst&afWm^`HGqFkiCgT$=JIUQlr^9d@f!J>gt({r<|s>wn;qQhT;= z0PbT|pF`k)tHLNpyf&%(*@EpF8Y(_+uhW%{dh9CJ);d9~-8M6^4!b#uEe^(g^6wWX zvT^X8Q|i~r^UGwzp0pP0CU8$-zv?yOywO*g&N^GWiU040iBsA3`-NgX(KCv*G5RIe z+RnbLqizSLex27gc5JwPAF*yQ(q&^)@LDn@`?#=HYm)f*5v`HJ(>s`*Y2Tw%)$sii z>gO)LGFaAO*Z=EvD^(v;ENt^|tH*g!GwTnks2(`R{dsNs$uyr-?Me_|b7;r+B>yU2 z@2vK1M>Q(~#K-;jxYHdLj$(c8=@5EocQdhW=@L(;?ynU8uc9_HsN?Pov97krrokG! z#l7yl7WZ}YV~G0P_;baYza~{b&fiO{`8kL+KR2=F=PcHL{x31nVQlG}rsCuK+PTAb zIXH^-FSysBIuP$QcvtXBke?eZK7OEbozOB9?`1fDUsKprlPNylzJrTwx`3Zsf(E3x zz<8@zkAdIGI;CMK)-_ME={d8HqJNg3NTVAp2MFrVA=7p;9dn^vtREx|qt81X)qd4Sr&sC;dVkoukG2PUsF2YJr+wJ>bFGXm+9M=Qh1#!4@v|7we)s zABFm>(PFI;x79h^Ww>v|A^XN5_5ES$=N^C5kvv_EkDvaeAo*SJ_>$Eh zi8p*VrTUn!mo4b_Rrvb-vpuL@Z+zcF-eL5)aWnCl8=K>)$(@Vh|Gsw83>wmNx>#@T zkxd7=Y!iLb&=&TNI_(wxqup`_eP@^{ehv#XJ$B`ViW>Uvs8@U%JelY7q3N z)+YEasM+XS^5s1dHlm+j_sA!H3j9p|^vs_%XNCBh*HbPFcdN0_b1A+VJJ~!;d|Y>L zXSVjYhgc8x>&L1=;G73+Sm?kshCCu&{x zIFl_()*|Xd9AU5bE4UX$T@Uh&W!^;(#rj~-Aog}V-V0Nb=)w*!>rU0jxPCEV-F*9t z_2f2h1Q$E>^MsVGLaaC57Z&}!y)fiC>J|IW-u(=G*OvOZiDeS9bvHi#e(-i;2loZ3 zA75Ykj)bL-5^I;XW^~wO%**@fy=mplZsOwx_Jiq;&W2*$`*kcGrGH;M&-urb;kPVS zh;>6N*aJ+zi#p!CnN3%WY$@uvyk|Pi>f$4)->doeDfGNgu~@es8%1^3{uFE5Q20H# z?N&^EjNcXqy6dA%tUr*ZG^iRs|1Zlfk*t(>@$s1ZE6DyroE!Y9Bj=uY4CkI$|9K2& zh4}c{bsj9nqKjBRIby*M=KG8FV3$uq=~2wogQ%TC%ahZ@#{<815j_0xez!r(E|>3x z?`}|^bJKWtc7HVbaPwU=rn(&{K5kL?TKF;#@AJ}yd-tZ;;Qe2hclHo8ex!@Xy!~yi zO1g}%^SnMuc5w0k&31mz9aX;Z{AH>hCL2pIhe%R>I{Q`1$;KOylKty@4m< zF#`*%1-J8fOz6IU;Cs*TGkN^ujqvZAQQ|QVdYiIdZTgFKQGpASg?AV0vV=kGMRy~y z?h_o#QkFgx|Ci#>WESLu*F?q-GFilPE%9+Hm=_eSo(f?zQq_c@5anA7kTQ+N*6(sV({!Rv4XN+^s zFRlsf*gl1Lp7!vY7!_t;#QH?JAJgk#Mb-aH!3R6G1#a_I*EinkFoWe0Vy!b*5Hz<; z66>S3AwouWnpi6h%~V^fkqL87=n(DGIQBKn$|FXuI3_keQ%iDW$d;@6=5#|@p!nR+ zz1`{Z^*FZf=@dr&ypZk3tR~Q2S?9%bThb<#9veSVti#}Y2s+No5Iq?-7xuha-4i_- z)Ha1SFgciGi>+&kItIKP!CFP3j(0vyVW(nH$E!j*d;iK+JbztyACv3;qK=<$XRtDJ)UlCs z0!zAqItJQDv+F*nFX>ew+-5H2cE$FBqo*v1v8V|kV! z7;HryJ#9jS(>#x(jLcM9cpi1G=#ZJGP{(=m^Wf{$QODlrYDpuW$AwMJY5!8xQ6h7v zhPgbCwqf*`C+g^DJ%LuFqmG@7Q)yNd>bMc|c#&cr2ZN4}tWn1c#woBSg*uvcjHRlc zsN?APV7j>(>NvpMnWnu$9iMG6preCEo| z=208or*q2yQOBo{$8{E{W6$mh%=9km*uyTGo%2T>-9g7XuA?dBv0W0SYR-6G*I@%T zqmCVh2}0}+)Uh7&_?+j_wzH|qj_2`2gf97U40X)fmPgw2JpR62OLp|eJod3Mrz9VB zJQVIu(^F7KJILcip2t&=$3CM_$8V6wK0hXiT)hT)9It_SJPtbE*FYVo8>G-fZm460 zc`TJgqmH(a#~(b83n7nTJdfuV8&LlZsAGu54dS>MbqpMuON<-;cO5I^-IOP|j=DWu zg`PZ*6%9qgP<`a8tE~n*r;A+Gtd%gsOQ_?!f4tZTOVly``3Tl93U!QnKZQL{MIBX; z$MJnJkDnor)txbqJt2=Xcpl?>C$P(9sAC7X209JbLTbHCK}U1W)q{}7{Rya}@KT4l zu0kC%QU$^CAJj3SeTbmTbu4OOrrO5y*!zhN`CNfI-dvnV_Pbyn$%R^y=7BoyZEjBY zmY|NQp6+zg3e<6dT^OC(2lH43c^r_6I$nf4?he5`-iAC@HTpl}V+kK0y&#W$O;N|& zl34n{4RyRZKA0YBfq87v&Y21?F^_ed45(@u>R3u|5U<&&W0z^U#6jb~>-h1hr!tP~ zsK3@#C_aH)b!%EI)HX&PUv$-AWtyntW_>C1D?uHvLLQ&-Jf4L-y7D|qzf573!%)X+ z$m6VQn8)9s%$19LWcT3FU+-?cX<{|1BW*g1wf>1{XnCDdRdCsW!c8u{nw!Nyu z6kAY7jc`G@%JUf4GDN86Iy!wcQ3dckMvv1a3wa*LZOlq zb^ICOPA!sA$Da;iw2s@i4bF)rlE;p}-IV2A#}Qtx z!pzgCBl%Gz6zidmj&>T%mFLm;UkS@UhdO%5y;y=d=J5mMu_e!={)Z_nCi5tnO2y`a>!$Ap2x!*45-fv)G^fU2AMer^EiKEE_w8qJbrHNr5w(6blTu5 z%;I@`3ghEX|MpEN84sn)}aV>91MBPC0GuvR)F-qyje64Ywv#rjK#U&$G2UY7ZVJqqg zKSL!nD?lAT7=#FgT*nEAO;nS49-k)Y5-HE)*gx_(;$AJ$=XpGBYfkmHqK^5)-06fQ z)Nv=|v8xPq`~Z2pFamXKZ;?vtUSb~4f{tICqmI8p$1ne49)lo{xBH@wT9C)kaj2sL z@;H#^v8$CcEq;bv{Wi~lZrY4G>X_Uhu}e_LY{=t?zvS^}vAeQ_>o|3=t59_c^SJzX zkj*vP92?A|CcMuW zFVs;zUwy~(DDRcP9FL=pKb@kPV>i^%67o1$iaNIVXvaqKJeoY!VMlXO$4`?5!EHP0 z__Ixjkjiyj|F5a)AkSliwl1kUiQ}W)>O3;C7jiYds+Pp?JO&$?!|%_cjxGW2wAp;r z@iXMH4?!JU+DxDsiKrtnNu}QIm`7jG@!cxaF&1?EZjO1>fIRATKpi`Gh^2RYP)F_9 zV7kK)^ElMPnWn!$9sSoE(2pxo$Jae>5H=Te)EJ*jR%rhB@zKfCTN%W4oUqYVNZ@&t z!}Vh?K3{FyU4v=!Jleo`m{N#3`t9>#M_QqdO2}gn&*N9fDRYNE>Jd8|#>CAS#rI11*gHhjLSf;`r_AXghZnA5?VQOE6&$B8_Twvfk9 zJdfeF6KLHq)Nvu?@#|yEV-e{1R*E`G=Vj5_XPC!(EmLTX59*j=8cR3Cp^j5V2h-lh zsN;OdVs8lE?LPJe0e*j_;yf1qsjNR?T8zt}c#` zV;wZuyT+KukzXXN-~{Tpc9$13YlAv|gFN<+#yl>ppTayRqmBtI;{BXMJrmf5)2L&DBV2d%LLFZnhTo~?dHf9HV=~WUmq$8m(ORx!oFK^ZF^~C% zA;J!>W9D^J)k&VmOUAmyh3E0p+B|Z)C+4xdx|UpULmej>n^VnwsAJ0k?)1$p%;OBu zF_r6h2J+Z(D(a|dno5T{VjdGgN7)$EF#+7n)C^Y}H|M@hMk)AL+~MLdrabc=<5 zcpm#e9^Yu7j@d9C4uWw}eO*wz$BS(+L>&_$kLP(FJ2p&VaYInYY{=uWQ<%pZ$YXU9 z_T|n%9)oxu2SXmsYf#7WkjDW$kIR@J>u-U1bc8&X@I3ae(qT=vp^h#vUp>d?s~yck zgg#tHS636&QJ%;4vvo;6&!Zpob7t^7CP5yx`1p9GvpM~+5p`^caHlqWzM2eNZOrF6 zxsbnV^uurxDj;Rz;%2Md2Gb< zIBB*4ZS@c8c;}Bio`UN~?Z4#l*d&>9E7x(}WLIHs1&)uy8bcp|=P{?V1|vL=lfFxs z2SXj#gN{eIj>#`Zu=J6b$AKTGuom&C;|f(e8`l`~s0;7Y^djcb4Dx7eg7cj7JrbDK zMbz<2=V;c+1M^q|dECJBSOR%G!1LJez77jr&vhIN^Hn+Kv1zLi;T+fT#6eTlO`gZ; zwz}k>6Ufz=4S7Vy^Z5O0E$PMcxZTv8uG)<{CJl0@ep#5un~=ws{JLX-WCGni5p_HR zc^qPmdCUVH-3aP93-ajE8uPdw27*TpsAHmKEY%%^I-Uov9);g%RA(WwJ&cb$kH2$Z zo|B6@CfeU1whJ(i*GJ}(3xCODMTD=iJJ&HS*Hx(CdEBR6EOg*HxWok5QH(!Z+TR>;AQ^>JiVQ?L1ww zi06@P$|E0m9#_Nlqm1XVv!gk!-GDk4hP%@_yq~iU`T*g)53mFBIG5+~6Xfy49n51C z==e01>j-)5bRP3K67tyJA9a*M9&30WZD5|0!RI;st)1z{r^r?RSqAhr&!aiaS7Z42 zm^Un!to=)Wl}#eb)m+CXX|BQt-j~}0T+QWN72tP+S7;+wLw-wGeL3pb0rY&%=Q+10DBSp^mE| zkM=Dwj}M_wUegtI?ASh*jts**{($R_n|z*g9`e|V=h17W0iC%P^O!HaLA)1Y9>5h^Zsf-$YVIqV|VE1B=$!g$DZ_KvrRCMyWfJ2 zGf+nz7$5C<9`j+nqlD{tT@oT3;CbA9tgTA(YPQ&qoi|sPtl)W6uFoUcoU2iHYRNL5 z$4*Y>)Pd)*7S=oB_)6lU*Kw6p2sVY$M<~Q>JsEJ^)>3K z9v`P)#XNoi9rO9Rl|JOrldoG1g>|dleBEju1oI40SAkJoe)2Rt}KIO1^IO7S^qz`MT8<$m0gy2XKJCToLcf zEroTf7`|@R57w=G_`20HShr$-(Q#avpRxnjvDF+`A&2X@;#ZO2&HDfsp`X*0=W!n7 zF^T8#9`xl7nqeMWLmsX8bw_i^<9nXR?vO_p-p^r>N0J;Y=CKxZRJB8{#zP)gJV&lR zg*?6sz&s8<<;Tp7F^}wx9lOW#m<4%!#IGM+Vg%tkpXUVFhX~_%9t&2qRax>pZkee| z4)8pF$ju{dc^}{d==g@`u@dsQHxIdb0=Qb9hFn#zBlqL$$k~ubH-7#28OFyWJddyD zWYf?()bSzY(Yz4z=m&YM<9XZmuv%ilIO8GtalKe z$7eCQB;zmh9Mdg*l&M_Doy%PXeXe66^yM1!JidZ;s{o$IVX$tcTZZG~Dahj|-Y3t2 zJm&K2j+wA-6~Nc6LZMHt`w;V}4e#?)ANx7aK*t%Jt9@bJs`3u%=mYCkOZmE07g+Dm z;Qdtz_&moR#>aS`$8yNy6uxd%2YGz>$GTMs?~^mgV}K@(k27K2 zYC2!Hx(e%7FGr$|_K?SKJdblBkHdK$-@v+6H@R1GMY_n*fm`62N*K)2ZAdkIyKj$Rqc+wB^=y=ADoi)Nd9;vls6{$Er4upPA zB+ny->yFMmk2{@0g!Vj-dt=+GTzDQ&r0SAdp2zx?dE_w9W5mr`62`e|-PN2<;(4Tl zVcjYd^SHlb7(MUZOdMwiKpxu<$9c|m$m8vMIA1M*JRWeybt~QZSu`jg^EedpIFskG zEA&@4#_~K)fW92x*Rd7y7{K$Wf;`spJWjK^K~gwZe~-;2_y32!T=#Cx;d|@Ve>2(t z*8lrC{I3W8zxBZMkmuxwd^`yn8A-#(eIhp+Oi7pFkyJbX7rDD;rEC|}zZN#4xoK9) zXVH;#>FFP&^>C$XF4XQG@5#pX-G!9!Na}a}0bzMFg|DHJ^lQJv;J@3Vk}fB)L(M^hEwr z;i>aYvU+qRJ-@I(xcK%2nF8k%vr7=lXYM8H*O7%?6?QDl5nt!v`Denbm+|83oE-T< zSaQ`te4XGe-vx)7D>C)#Oz7B%HT`NPQ@_rOv5nZ+$(NMs*ICm1r?A`qkV<_%ao0Zz zPyQdq-a4$R=8qmd7IrHpcI&IYw!;1#F;QQ;QLwvPF;EO_1p@=H#lS{TVSh%!L@=-w z#Xv#<3F$a@&Dr}tzwdqS{p0>O&tYbrHJ`O+pP7C3IxMkb$!A`JINsXJfhC{X9p3R= zaFRGBlY)5zI7ytM8+^GgI7yuBt?pa|oFvZi_}RP}oFvYm*Dd)3I7u848=-asCy7%i zuckT!oFq<m;k;3RP@Pwk`;;3RRnZuOzQ z;3RQApJN&bP7>$I$XE2=Hg_}5sL*H{^=q~nXWfKUs`#d*8K<##E{%wfP$kZkCI(|> zK}}WSBtWaWlf!K!&Shw|w@-i~`J97R;}%$N#4m{MGQ z%z7Q%;7j=TK4!g+ZF8r+;3RR%{+>-u!Aau0e$$f1gOkLG`xT*704K>Ou~02#A~;Dt zdE>%^l63!+=^dcn)%|l~krhAG{WGnH11IbLS#)wI-vuX$bIsL<1Hnn+Og_i_8l2?3 zCXRf?(cmQc6oOVKz)AA4g;w+5YW^`mt2zmqe;lAy-J-S3{z-;b?xQvTghQ*Oo|=Cm zp;Z-dk~kF_#&MLb=AU?I)gGKApEzi>7MvuX5-z^n9-Jhfy4&5k6F5mejS^;a)Dz7= zxo=zI_qa6w*d|7(DPFnk4xH{5wN!iEKh1}S+obCLdD$aC`KbG6>q09^)BQ8n)`8lB zldN<4iJerb<2y4>KWJ6ukLI5u&`JR($)_x|8V6324?l^fbKoTBRUTTozSI2k-7A-- zCPk={&lqSmsYETaf6}1U-9egvVxZLxTg^YE-u|WB1)6_`G>oHH-8KJMcYH?y;AEcH zpJ1x0`)84hFTM8B{Nu6RouWr*{%M&wn>@iu@~Qm3C1p5j{&D>ip}YboiQ`hLmNHWJ z<4LFu}Gj&%=E({%r=Twuj@!Aatb?e4(yz)99;!-<{j2u>0wev1!J2Pdi5B_HOa z;3Vr4GU63K04G_WjnHZrI7ytJj;Xu?oFvX;Xf-G~LXkMbp;b(2%|98?>QG>HFKBfEoFt#9#MwMw z_s{e9E%^;NNt_}n5vtJr)1_=Jb(rp-kG;ZeGIjsh7z30d<+SV1llfL;4Nj8J4Wk1c z(EZZ^TDj@|Ilsk+ymbF8hE|cffA&JF@;fyDjD=QhlQjQ4gjP*HX#VksRsrB7=QRXc z?I@@DCktBD>Y@3kbh&)mPMUxEL94~!B>9|&RujNU&g%lSDy#eF7PQ(5PO?7v&}yXa zpAI|RX}Rtnm!#R$OZU&(4=pJ`_s`ta2*p?T&zJJGltH?G9E{;X*}8vzC;@6EaFTUy zJl~2(>i(%|bl}^%fBqcb$*lWlF|-QP{bLKQDs9yKGXq-n2PcWs6eCpoVx(8>p# zjN%gOa;w9;3Bq?=AWw2>Jm6f9D8V03Y;X4fL4XTN#Z<&R?*-jab82K znYw>!Z}jCZx_?GOs|mV)9zm;ix_|CLs|&h+{-j2zXLbLG3boXMx_@pc;WjzCe^w{~ zN;Ta-$@8qpQTI$Kktw4q;TCoj?n6}?w>Z$stGtrKaYl1lXU;If>u$wf6hXy zNZmiDpjDGJ%|GB`Y*JD454ae=*l7N#39W3wN!DjFw0Z+hvOZ6t)iZFC^?3uW!oW$^ z=O?rpq5G#Tv}&UJXD+lFtotVmS~b!AlL4(x=>Bm?i%^d1{@GQrmhzwOpOQA=L6Vc4 zS2bu=Tldeyc~(44_s;`z;AgsjLZQ`L-9ICtmEl)s?-06e}bV^2i-sZ(8^c$PdNPJqx)y}|M+Jwh1*C^%lZUDt17yGEV0(d=>DmM zwH~PZCka{!-9K1g^i=mxFKAU>_s<+?)l2t}0d$?`3Ki$al5DH zpJLFeg8uns1FeGf>(4%Dbz8sw?0{B^{`ut&t^9TWgyOSeqwb%-`20GhUw>lp`88Mf zPbfaW-s=AOlpLYn)BWRL=Kp+t+4uQBpI>+I`IWEle=M=rXrue5B=#EXb^lC;R!emM zyn$9LbpITKRu}cpuRv(^Lf`+ahgOHdNv;cgzSDAWGOr70^$$2n|BQfEi%M($k$a6? zJIy~C*lSGfu3dlXL#tW({zvXLu;(yef9#=^tL`5MX!Te3&rWC+r2FR*_8PBs{|vxh zW54d72H0!-)%~;nfA&BB{LlW!Ye0C=U;X-1#Wp}q()T~X*lSeQ{c{a_jWN1^u0boK z?w{(|tCH@Y&(Lay?w?d><)ZI@E@!9kl)PJnU7|_48Lt?4K*@{=r_J>goQ8hE|pI{c{`apI>56Fa47V|A++b{52l_ z$tkM&2j>gps!^JMo{PhQCoiX4f>wFex9fN-Ua>QAumwx_w@jF5(s-M5Ci_}sa|L^OMeR$9x-9N#- z0@M)QKl^dkd90tm7UKMs*g)GquRpny{lQ7{c?7M_>*ud^(8?d2uI1BO{oC)Q;D&zch6=y<;GYS5&#F(~xxRi>BbpRUl#2u`v-^`O;saFRGxrB>&)^Opfy73lss z5I>u?>i%i+x+R^{{nIWsLb28Tvm>XbGE4W*KXb!_;&lIv!M&Ei2(!L#xQ2 znt$d(tHN2@{ht_UwPBIwA7^NFt-t1NMRy3)7*M?w{Ao!)>B< z|CIVKKv|&sr{yv$>Y)4QYi|dtrTeG)>78@|oFpHsZ9cRaoaRHXThMAeI7$Dwje14@ zfRohS1g-AHYM)<*iK+B2ILUdffL3*WX#QCOt)fzEsuJfrv}(F0+@?HmCPJ&p12zBD zfL3q7N!I6Y{Wx;zgEJv;R^eXV6mXJ!21BcH;3RRZpj8SuNt~aq?i2z}l260f+0^W* zc7EUbvL)34Cy67zMJU^J{|rp7sVoO4iQ}{(Jm@PpNgN&&pbh~iTj}TJR-FG@JHI#Y z>%d{)Byp~t-pPIR`-k4!eAp74Bu?uK@Q<^vnNK#fIs{Gs`ZxBp)NR>NO-ll{jBs|K%PlH2)m0AID$8N%AQN ztt`%H{`r^?%s;_N; z-9MXu)l}Dllf>DwE8ON2I7yt)p#jQ2;3RPht+XNmP7=q%&ViPKlf)T!W+%OEr}?Ml zcAVeAN#b0+z%&4yB+jhSuPA+syBX&yw5kA362}Ev4SwFzjPnRu)%~pbX9KkIiq-t{ z0b1?cr}?KAv>GxzK#_coL#un>Bysvdt3mxV{~T-gj;?}}^v|S(U|I}Ll1~w6l>$zZ z&*?4hbP}8-jzjcp`l9=1&$E_vTKA9prwHYf?w^~{HI>b}f7}m;2ffq%lQbtnofDKx zZ@|GhtutS2o@~CSJrfgONEJ_`C+gNAC@&g^?=_EI?anQc3{W_p4#m$-@w?Dq1(BK%X<#M zSkLMMxzfAeTp44F)X!JL+GX<{j6HU!le!;2t=)>(FjQZL`Q^5%Hr9$!!q56JSvCKc6?uucWDdxXMCiphY8!)b?jl@sR=-h)56-2U z3xR*W9UqEJCLg>$Ds?%hcl<`r(SJzx5w^ViaY^Zcv2z9)#F548ZQ87LFfN*G z;&P2fs~^#)YRhcCo13NHz}Po06M1rsEoY;h?(&%{M{nTMtMFY+;A4(2d7P)OL;Z(e zDiGm5H1>w@}A9I~Y?t8;mQ*zOosJ*LVJ#M=2G96eTeIdTX(RF=M>J_&}@+ieKtr zT(;FjmH!S?e#1+ace82R^<-rd+6~wJp?4u&sp%4YZ<6?xuEnmP9L#aVjaO7`kQ+s! z4i*QFQQ)a3eBaT*SiFBAtsj4t14rR|I{#PHv=`33LmiB@ZpTvO%L#0ScIJQ#>gr#G zm66c;Q31I|?obzD?X>qY7+s28vGyO0dpM?iQXigH$_;ZcPP_P*TCJ>0zlJy%quc+a z^arzOF~0lrEct?7bnu`SSc8$v0%+_&Ke~&$Id~o+*URCw3uC{yEvB{^-{~pF4*A)P z45icP&T!P~;7!E_wMezceBGwm?A~oKenS1P_FJju%r#M6^jSHjG#9y*N%t_;=jJGW z`8J-a;`PNlcXND=xAX-4!|Pn)qMh)F9W?6c_=u~VIY|%Dr|G-T>^|Ft!Z5bq#6SG@ zfemc}A5*Pd9$Y(0xdNVh2OGq$o5d9)`1^D=h@pL(s?L~K`|8=ct9XHcI@NAL6E`)7Cy>Sh>sfqOl@%L7o)D|S2h(!}>%A9a4#e+XY5 z^qalVuGqXN7aYrCU+B{0_XssN#KfPVmvPZ0n>CvZq8VOqsXkEdZq4I4=-UM2y*+fkDs9bfe$hCc*Ybi zj`nK*bTaL#&PkY8_YDQ~;K4pM4fE~nZ7`m?{-Ik9)WLpW0e!FRrC4K*2l}Q{lgqUz z5_5N|9YbCIolY$<*4XJK?KpUVuA|ObA-5>%?{#W{`Wu>g(vJ;c6pXQkip%MH(eLyC zW4m2xMgL7orB%=(YlW%|dzMG*p>^z`y*B-~81Q?4@Ib;$)#9v)#-q<2x8nFEuPh3| z*s;h3CtdtSk-)V4wv%x$m&W70+|-L)d5NIa;IO^XL+(@mG?fImgx8TAWVMOjV(jOW zNj%-TI}O9w(!MzynH;0oVUDB7APQz%Dz`EBHvJ8vXwf1&z<;~QlLBjmaWFiVc;Ob+s&<1{fREeqmt?d20H>n=$&8=0D|`FS(lEgD>2_CSl8pf771L3I(#}fZ)%KH#j-pQl7vXXtS@alV z3#JX`fop%$8DKiJ-@$VSy{A<047b0)-+b>b$f4b5KcEssMS!%pCkM1AM z6)(iIJ=(qFOY%tbJVHZ;gmX`DUNt6wd>8of2h8Q@uou*zv%gezOh$+4LNo zuihTOzxpT8V(=NVaT|*%A80#x?#wvH^M2f;Iq+)b3n6^Df)5?WyxKha$QRbQQYyxl zv`XaRaeXNhbu-@0=KXs!6c^Ozx1~W0@^7#Bp>C&V;l5vNYS2v7bKj|4-q!z}+5-JQ z_DjYWKV5h)+B>4Z@XDp@c?WbESoJaIZa%@Kur`Mryv*TgL2QTD|7*9Gd)0r#%hCU4 z`*FN70%vu!Z622A55+S1Eb!aj+Mph*Y2qsI$*JTtu&Zr(V1oiJ%$3(jdHY;y2_I%My zTGgk5`C8ilZXES=97j{2#jNwMX@~D#8V!97M}w&Tx68By?Y*~;Q*gp#T8ut(yRN5Y zR#9{x@B2?~XYw4FOpk%NtNa_~^qE}hg!fu=G~TA&6oc^$I5dmtrnay$7#o1w)0SE4 zWX`6K7`v&I9g8Z7WQ(ymFI<_IeWXU1;|F}9>~9%DF_`HT19~VOP;-yv1`#&zbx*bdoO__0{9f_;8XY+ZE1Cc*J13s zu0N>FfkhmSv6Z@|(f3zPIUHJ4?~zZAjyKfGsI&WCgK=}nh@c?U-)6jtzIm=u%A-$f zw@h+aUdFsO|2Yy*`GKRU30`0PzjLHYzcyT=pHl0tC-JZ39?=c-x$Cl-gT(@}^I87xht_pXJ+q?$Z?1ZBvtboRxN-I-s6|FTLkY zFSk=I)Hz`5Z?4vJF!`YEb3coFRV+depiAmY6MuL!MDd4S*ESf$0MpH&3V8kCygYV` zeWXrC|6$isc>aa9JOu5WuV49T;wp{={vy{)PH1k&n5|qGL*S=K^kx zIrbK{sd(*lj>6oxwx2=MKmBAvO(v8+NSWVW@N4LmJMsqEO~1uuP=9_KMwz#c@(ql& z>i3-vR$ayqF?PONDjo4|$vdFMptw9***#D_4vj+b3|`I7TZ3AnJ?@~1;%J^S0DT_R z$fC^CCCs0>V;26R-IgOL0hrxm-qQZDyT}Re)wZUfI`w_Y9vlw&pQ3VWA5sR!ZacM+ zVyr&XE4=UAB}UrzK8Yq`Y#lXPNqw3_)1dW6yGn{Z&e$H%+Oc14wOMb2(GT;Aj)+qW z&gW1z#-^R>&LzB(C=PY=n6`;e?TMrbs87#(r+LMa2lNefoBvI4iAfh}GwK<4^c`ES z+)3@xzs>Dmoc?PVZ9+S}dlo0BTF@Nm((0Ir4~>|hbj5WzeY-)7^YjRsiPvw3<#El9 zcU2ek?}2-q?c!T;2ecDDeB*Yrm-ANOKfCvooqu?84BmJD&FlQKk-X0`>24?kR2S;l;l& zcIn7(wA^ha%RN$&pDDC(dK(^yv0Jw1kz2hGwGH&ObH=@_oHIe5XrB)=(e@t>$~N>_ z;GIR2B8rmq$%7uhsqFkAPFkO6aCol#FoYHKi7LfxhnDyxneWiS>(J$p6! zrpDFCr820Snqb3A#{D6I_HkbqUgPnZ3Zb^kN1x&(&xbS_>#N-n{BGe>U;2Qt`&{30 zsoJ|~F#6YsiRTh~M$r_sN8Qe3&xle~8JeD&Vd6`T7btfycDlPk*zQ;y6oS|PHqGa* zF1OUP=s&Dv8h>uwoaOal`19|4<@;jp4E!$HVSISdQJw+LCCmG9Oh5pu;IroNK`wFT z1y{rz54q0bMMHnGye=6U*5%#4e|auy@^0J-HPe*O^`Z4DyF-D`jvB-h)ZyiaJxc#4 z1?+~gotsvrFa0xEUJthxnn;&V#qv#PaqO`>op1k&
h<5$Ty=MG1s{LIzRE| zM(DG{@hhn%*04OQzUh!c16#J|ig^8AvpiZ=5USoq{|Za-4ARArpz_eGxyeLUI|eCF z(Wh12Y`R`xAbI^?STTXzg8!rS;8Vu(1J%jjMn2#|l=|dqS5~&Er`Z)eoCVkH)FVyGN;WkQSZG&+y>Na3aZqNnXs~n1Y zE?oLS{kb`p8lui6+jr$smdSJkZP%3b9DVc)oq;YB6Hc&I$Rqr(WqfuIQ91hG%hU$1 z+b?{>_Uay*hyH8J$Fofvd+LMs^M5kA_0@8u0>64I6FTiUsc1NkJmd`T}uU#U@fcI{P`fqNw zRcTSi#1Ap{$C!#VJ2HdiK4;OC@if>aj+a4;H4WY9$>`U-0$N|_d4)=J58~ly2ljkI zx&IyKN$4|sY7~uK?acD58n-@~Y9)5!_rNR&&LzXg2z3PBtKkf+>we#YHi5$*OMLg* z5&xnW+_H~mlf{S}MegfHMJCX{Rr=8&jLmKKk>(88O5HKXeRqTDbh;0PVD166&e4~U zV0wYEeXnk%LB&6k31ipn?oV@eCC~@dZ9$7X<-&|?Qc&9g?MP`>9M1xw<}s$opax5D z&W9F@ppCu#ec75l0 zI=tZ?)j>U**l(ws+3%?e>Sk#@h*k#wrt4@A%`QZR;kP&$j7_K*s@5KsM`O`{gbEB!?uhZt{O);g4SU~FE%9Uho* zm7;;^(DfB3XS&l3^bZ>y%K=j+kvuO~EuF#Vrdm=>j4gV;fSV25qjUr3&-lzN;kq>N z8|KolK>=sZJfYUd99t&;W!o24EYImBj{M}k9cS_|)MU}F7i@Aq$Qh{B=n}U$&Hn}` zp@x3_j`FmY;d~lnpVwH*mb<>2Yc6)R;9mDq*&A9sD{))RE|kxAp;3sBb5PSA22lp> zqi&0osas6k6@9F3m876FP3z58BWYQOUz`Wb?=N@J!h>)5FubvIlP{II$J`YhCck+| zmj|5U9~gUL`e$m?e52W8zsmlh)-#CbW9+uyIn;35chvI+QAHLZ-m2A+yJ!1u1@Bc=}fS)qLi_gq@N~NIn?wPmw+3@RR z3qF@>L~v8L{qza_A1;sKHMt0zIzZXSw?`PRT*xXYl)w|b)v znez&`kN;tH2Vjk*2*r@!9EC^3tipU(FVwludNY`VaPD|OB7 zcZELlhKc3P?Z6vF#d(_ylKtCKHSsR#p}D=xtFai_*xlT2Ft?59c)p#vU1VAZF>mfd z#f-1DRoT}2ux#sN&21gi+}7XA+}1e=*g&++xT4n~i5xvX8CxH>KoD z%@4KfPN4LTt<0}itazG6In@7ujs5mDsv*W1D<#eR zPBrTud8~~HUfPD_ygueM7M82`n%kC7s)^X%nh#sfFD4w$X+C`M z<_l+E(0sV-hA$tguC29O7v}K&=Gq#pnUbW2qjnPWf9G}DD~}sr3Q+M~s+hJRjkE0< z%I^)u^hrP2L7BleOB}>2w+Qaha39ZH>>$c+4dng!{|x&7rooH)xt%w7FSEsgJomd|hy*1_39?Ry)<@tF?d!v~|X;gyL` z%ySS^#uud%v$D9zR0lEs-AMW!9nZ+A2`*BcgQ{my*+~wfnBxHU=#)SW9UR2d{hK){ ztql!qRXmfz`5%2T>caiq3)mJAclmc z@bq$RcHZA0_7~5z13-0H8kk5i!So1r40^bcco9rMyk2t|j6(92_%s2DN zMlKQ($xkqskwyD*@dk;!68$4m3$veJ7Ec0Bzv9c)(19jC4g5KsW37F*7=!_H2}nGs zH0*)%)N}`7s#1xXZ_D6r;MvwtoIB(Gg{;rZMs{2)CV{#GGsN44Ew_KB8Ni%5&6^$e zh0;M_#=rCDmACxpAm&o7LKxrd>q&DkN3Z5lTx*828E0^xB<`}_){G;HWb?ay1~bl2 zGI8PfRf@zZhx-ZGRR>C(BH;x*xT&iuajMtI;wpuTv*eTbGl4HOwqwcX)3(pt^q31v zK9>7J`5rh)oaVRuxbu5|mN;Yjda@%pNu0sco%tO&NgPLKTV4%L5+~E$z>(l2an}4? zrKWKf?;>PYYK?&g&Dr{HbtplJj!^nLy*3+L7clZQE!115OfWyL%`t z1t*EKBfyVdf|JBK*2j|)!Aar-Om(J#;3RP_uC=At;3RQ6x*5o_Xto(={+CrsS#Xj# zWum(WmH{V;BU-ttZ^238IOSPzfbO4u_3iir{DWt8L<27uF0(`PPudi3-mqWukI!3w z7PtNA0C1AZg>k2Tnt#qWi{iPnHUD_@PGYgq){N5^TCMTW{NoF)j%RBAsQ|6Y+2htH zaBSh9XLU9Ic)&k1^DWGEJ|C07EgRU$XPLzF?VouEILZ2S*&oV7r)vJ0ciWG%z)9k~ zwe#dINT zQFL#n=AX3QNtC_8){L_W{yBR<^Uo79QIBNJKj2~<7H%~Ar$KlD9crlgXEe0xX|gcu z-XB^egOk*K1lIaEZ_Phvu+~dY)BN)UYyAi~Nj_EVJSiNUB%cJV^-16)=T&usEj7^n z6SUtzC&5Y1YhS`D_RreJu4*N4k~rtHEZDkc7L@~zkCh#J#cKXp zcGQJS?$rFVbh0;JKA`z$+#7$c5UBYlsB9RA^!KE>z`4{kir>z2HsgHgmBf=>HUB&< zoXyHn%|DBw)pZLe^Yy0^w3;xV%>LN`ttwV`RV7Z%npy0XZNZYy+}H%(TSxOx=#J0) z6`bU}CLajp*We`Q6?DgsuYi;E&&2+oTmqh!IJtA3IRTs`&Z;f8TvGSXe@6`b3!EfQ zd|@Ybz3!hA=gGPvI7yr$HC>fO;3RR}ax5qt{xRd!wIgeAlK%P6(*^r6%|9KccvCfS zl6(rk^`{x&BymQT!}X`1rx~YZvnZ+uP7O^mjJgE7n+-rZH8l?GWYnd<}{-5Tbt4*S~ z?;_1VHQ}GKJ2d|cf>yt{aHS0z|4n33j(r(Q^uL@=J!;=OxPQGH|^hQpK#Ib}{-}c)C zN}R&a3V1^aS5@NF$MY%q;3Vgj2LBAKrupaouFt#$oFpIB1J@sLk~kApKel}3&k|?N zKu$M5@-GkP7>$gE?eFSPO?7lP8c`^oMe4E)OS)#!#@(o^SO<6RdA9x3re{v zsql})`GfC*3W1Zv=}_H{LcmGlq#SagE#M?^+E4VR#o#1yX1(&KGT>zPbLlXu0ZtO9 zU6UxvTdesfsAm#=*{S)b09{hu6l|^hNJN~BoXWc;; z&eZ)=*wLF?9M=4^@ufd!v*w>RrNVf^V9h_ljiR_{>(qYN&4s8p-`Rx zPI6x7*pFXb>U6p^qN#b<;V?i6hN#giau_G67k~jlBTxcygNt{4OZ#oQ45~pE=KaB<_ z$tSo}7##yAiDTV3ipDJ0{8I>8E!nI2=U}01I(ph*#`&t4Xm~5lKj31VSKr23;xu?x zKsSrJDiUWhw5pe^`DZw^+EP{XPj_hL2TqdD5UllT6Ey!6gH}txN#Ym>c~Tj8TH`_h#b}%|An5`18MaHUCs88OG0sc*Sp%OT4)uRy~TX}sa-pZ`IqLOnZFWv zdIiltXZL*Okq0#YP7-Hx?iOXf?jP^p7L>31$GRf+Kj0+&bL)T$%>^e}=b;YX zbQ7E;pZFKptAdlnIZ-l9=AU}ds`WX|Kj)y;wQib! zz{R+zyS3Rr6QI@L{4HkxM8QAK2^J*%Tn<`Qtfcv;9ki--Q1j11to8HYB>C70KkD>S z^G^`gdMr3eK4B}J$rYR=PQ`t;v=W@;yoUN1$VT^1=gv-wzwV#c%dG>k=FR@8ZrY*_ z(f#8QW5E}7|12tF$I5TbKO6SB@SVMye@2e;=AK72|FnDV&m-^o$;^c)RU(X=4AcBm z&>)KIuG9Q81pX0+H2*lkKW#5*{;`KvF9&J@!nw5(62 zhb^xHCt06Kz6L%3P7=p$fRj2y_m5?lZq|~M#PR&QMezYAiPJ64f)<05#4(h!qj=pv zUH7}tAaIg6Ipe(P-Vx0|cc1&y{kxifc9#gF)!-y?<}{2VpEa6)PTC^Z08Wz6RYNwp zU)21w6j}|j)BIBtT4l}dX7#?`A5J%kHJaeRD)Ir!AbJjfVKYL zc+EenvDQn#)6&mPhI-NqaFRH`u+~q2lbqMIgSPY(oFq>01p_?=Cy7&`x0AA7_s=J< zZh?}M#QB@KMcoNb66eql3$A3PU4IUgwBvWWe_Fe{u#21KpT_py{I93xpO(-3d1A2U zpK8U!c=B+~Kb_#8_vg?`qoeiDFZgEwo>!Ce8sheuH-eL#R|fpE2%MyU>ID1oTyT=QR~hcf!@)_;tJQjE zo&ip>KFLRH`3pEnoMl%G+(!3L+Gr=Wv+keVWnHan>;CDIv_*;3{Zs9y1x4xpDO}o) zwu6(zdFSpzb-_vU39|R5JK!YwTzckDpWtc9XK(Q^dN@q;&*279wBA|sPZ4O<1)L;~ z9kdF#tof%Ww8|c#`3GE#E~mR%OPm+b>h2%SKM&xaci<%FH5FRj1}BM=2>-O)r}@Vj zYrOG;{8lw9r>8l0LhkuYg6s3yW@x+7#ne`Ke++4VWyXK#2W4*bU7tVy>(>>gu z2Zd<LnsL~a#ow=M{wWNtc$$+Uaq2)Tf3GfP z|5STkz%^sH$PBC)ZI#7`zFEjDq@aWZ_5~-&r-b`w{tuj_UN1aD*&duEPUR3kb^<3k zuTCR8c_}!_`do5x<}2VNalE{2c{n&poNm_*{2H7jPK_x}Y8h~nI29jtv6h@9&a${I zN*QpHI6d*d&$@$?#2Hk=j%tIG#PM)*p-;MhyvBNyCpbwQzi@wg4^K;+^A=&03{Oj( zPxYgy3OGra_3z*$=QRUs{VO<0|9E4qCxMgXa}jGj3Y;XL)f=3txbB}(p0;!V zoTLxqvDQuCWUjM=lTuIj&*K_h10^Sk^Uv=sYP#;9=mA}*bk$@|!q`FmH{vt#Gvj$< zQ7`ojrOm$2k8!^}qjU%@oaV!;@V=h?B5BjUP5cM^Po4ZjbuM+|q8R(@Cw@Q7?z#FE zV{a@&9&M|4&^Gir+t5UN*RND8aR0phzznjwP?@Z7-@D0x7z$3GN~_VoY5H^e+1G>o zfz$P*A3aR;Cr|KPb8|lpy!4V5T&MCX&ADD?McMpj5{Pfny6e|j>qLZU;@94deIkBY327~H{N4Ex?( zMOH|R9ERVlXje=@R!CfGol9#UepZkb692CML!}$q$gGffTlfpLsplfILc(d^BPulY zq|6G5H};pv*QCm zArU%tT+q`!1|zaU!ioIU;a&1&R!BTDHskG0(_~gi#APkw>^eVWR!I1cIl}9{h0Cmv z@U{uy&#r!itdOYs_Bl6N?Lo*2;di!v^3zGP30WaAZSP<1V^xok6%sR3^Le-BSp``k z@d3{WPxc70Mpj5{jVRzr8@H>-3W+k)GI(OSDl#i1K75JgavdkgtdMvf^NQ2+-DFls zym1NSnf0#9tdK~4e~h=xd&0;HiMFNIvY+8ABP%2tnA-EA$|*7{Bwp|{^-k41nH3UF zWnKpTT44~#3W*uCYcoy`@5Kw1)Z{GR!Epk1E@14$gGgKI(i#@_4**QLL$=l z99`}mEVDwwyGsa_o8`mE3W>CRAL-a}S4LJy{BDs*XHWEHWQ9c3Q=F-XW~#^vi34>F z#?W?MRb++4(Mbm5z#j=V$O?&^!?|=g>5YP{kQmT4na)h>BC|qbTA?UvJA1v%3W;f< zk7;D|ahVkoUGH3`mmDOsLc(qBUfS{GH6be`nq}J4x%Y80DUHtdI!#b(87KO+r>kM4oxZlPnJtvO=O#-Dn<^I**VQ5~u&9vGvb}gshNQcRZhc zpIlOq6%s0*{lD3@jt#Ox;#6f5H#zL0A}b_J=^6a3eFd2n62tDq@x&wJWL8KND*T2g zOx!E8LZa;RAdXZo%dC*t>u`d7IzEnb)~cC zKgz6-DBcZu*exM4DNI>CBP%2}OiG{zLkBRjLc()MHWkS$ zP>~f9StSg{?OW_rWQD}P3k=4X|DM|@sPn)=$o*7#rXVXME+-{Z#WNjbR!BU~i=tyw z*2?FW#n*x-bZgQvnH3VIYFFvDQ=rTWiHi;0>B8ApgshO*anO;Ra${vyNK`prnHF!# zkhv9Mc(YT<|4|^bLZZsVM}eD>bwO50Oj~wZ4gH!gvqIwB$$H#<{$H6D5~06m^M;IQ znH3UoojtgCyB9JmByJz@<0tI`2w5TIYs0zV@)1H-NStZ?gRPtw5wb#}pnn<$BvL$A@QosJ8q5tJBh52u$v@!!JmsVD}bah`6iC`nH3VR`&p{>{xb+cI}bsHC#&tHi;z9!1*JVQlRNc7r_XBuPo*&r(<@N zl{&=`vO;1)k6LtTOuEbpiH2Q0l^Y`qWL8Lw>Ug?a7i3eB6%w1z?pJ%PDv((rQ6{%K zpFNWlu-&hUrYQSCwpJii8DnSGB+j*F8W=@oH zzkIID3W*PG6k0UkkIV`Q6TVM5edn{x3W<5oPttDdM=~oUCXB^zi)H#UvO?lu*SA#9 z0S|U`g+#iA2Q_H< zf{+yw6DH209|M09vO?lOnYxr1^jBtuMB49DN^pq+nH3VJkDaidfpv|nkeH|LC9|ZEO(83W@UV(`}p_3<6mp z@u}f^rR|zrnH3TaOS;m5V#zWqBrg42PnLJS$gGg?7;*x?0q|I6g~YrXDs3EnnUNI| zFKfObdyBn{tdQtt8Bg9RV;NZ?(F^|@?bxGo@|kB*wzG*^<+!NG3W=rr4aO;p+S(v1 zB(5*dC)#&eK~_jy@lK;_n;OfkkofcD2aQ_1KxT!6XTUS+-tDl=3JJ?~H>qiVf0-2$ zNhc4{gWP9?tdNLLnTzkyq6t|cQT9y(>TUH`W`%^sv5U%|fP9%162Cf@wF$%LHL^m& z;ngPfb|GZgP`9i7D)Q0r44D-YGrh<2uQhQpD};UiUOsyLwaf~MBqdS}lSs`)AEtzXx=|sp1iA7<#Z0h}5K~_kl%r}VV$uTy_3W?d} z3}XAjt}3!ZqW<1&zI`lPMOH|Bc$UB)?EA^AkT~l2k)Jl&Dzidjb1P&~Px{ELkZ_oN zj;D+dmRTXu?88<*_xuARD5)PL#DDGe-vrismAj^MYyNaxkSa8^2tWr1L z8d)JxE;OHpUp}iKDd_j2+td3lDMGK*4z3n0h?-~+{caUjkQEXh z4Gm)5>lP}qLSj$J9DW&*q9Q9K3Li-1b?1A_tdQt1^Aqo0u|;Nu#Irf~`QkrkWmZVE zeSV(nHoYgaLZbHe?R+xuJtHe5CZ!ML`OkjKtdN*Ph52ZDmdpx?aXW{rHE|t5R!GF; z-?oXz`3qSgaeLllrCPr{nH3U|$^X)=`6)6hB%Z`N(UL1)&DY_o{k_TJQ>e@eiPwAX z(1=Rc7+E24=~V>s8T%MnAz^DDOG&LKF|tBpd(8~GH`UU7{Xc!ZfEJ8*SCJJG7d#Ed zb?qlxBP%3k*C?RaN8SpuLLxruFWvfKC9^`}tmjWkbDSx&LSjVGm$azrL75d2_Dycl z74I7|D{*qZCF?`=HF8%$j%nFGfBYn9| zF(I=;0^w>t6@H446%tQuKl3e{jfAX_xNG%?M>QluR!F=~&*A(tKNJhJQ}Fvkweu?~ z$O?(N`0b8!|I}8I6%r+!bNFE4Un;UfV%z8>KJ(XBW`%^9AIUEtZDM4F#M5&R`1H-w zGAkr@w7bZMl7!3(iMw5P@}Sf27+E0^du%9gE%+s~LgHRU3qH6cOJ;?{qo0#ihd`6e z3W-;JJZ<*jehacfqRO7T%AWIiGAksCwQNn7tWsrGNEjBZph0KM&$o+Z!JgCw-wGlo4U=r&d3T0$BQqif7*UVR!E5DF|_^hR7O@vgl$ZxivQL$@9TVK7tpzKM^t2m zL_O?}e8x|^jjWJ(IJJOUem$rlDu2WY`Niob5%g)@e)@pA zonCR9+V#3FvqGZK3@>sY_mq$o61DfPpz7Pc5wb#}Xv5Z&(j--8g+zWpuu|tTvZ-i? zZ#rSq5V-?ng~WiP_NwJolgtWu zb%AdWxGS?l!oT7JF4Fl7AuA+ab&2G>znchIAyL&aiTyv=60$<#s{5tdMA8 zG>F}O>MO_!i9-Dh!fs7j63W@2Ke|WkL$*hoQzxXqIRW;{0#Nro|j<&ZU0t;%nR9GO|KqcHfcwy~Qt?6%rXgO7iJMbACjW?6FvV zxzQxELLxn9jm>7{O^_85gD&4vN?PR0tdOvo+yc*Ir^>95IGwVDetMX5DH!*u9f+`7G9@-9Pgb_ zkrfgzus_QDzt}qus4ALm&tnF276XdXt$<2YMB&s%a#B$+XTgLR$oU-9&xASW1l^c( zR!(hm0CUbc=bXioY*Y~g!>jC(XoSu2D;kM1Q?A8%IH3Ss-N z%ZLZt&w;HK!pN$r&VzzAzYBZSu?H=Tbs(BVZpq{#Cy~SWvvh%8##(NO;FdP;q0{w$?Ndb z%32`|ShJJlS?r)}tq_jtc!v1cFQ9C#5avq{Nt<`WC|fIp^8!DTJ%<~r<1kgv{379T zYxHcb5bj)T0xO1m-N)7nq4rGy8DC+7hOHICCldSqN#Clbc~|xJ}AhA-p+$1u?sSTv;oGJ7#D}_{=+mtrfysD_fHFhu<_)i@NddmA#{ldq@(7&RMrZi z#nOp1w3@mO5zWi3ratEnDr<%C{MLhXTdCEAtrfyO^{&$weI^pNRtP&@VEZ|c0K(P^ zVZyv`)NK8CjWYiBs)h-EdITD_RtOIaHo*s)Bc%tTgE@H9hE} ztQErTBk$0gq3XIzoYV0HUFEhySu2F=e(a#yQ#+KkLRk6N3c6v;ab;gGEd9h@pLysv zN!77>f5mV8h`nD)tt8fty48VBdHS3*jO~rxt52nKw_GMc(X1^rcq2V9KbM%Y<1kY?5R-WJ43-b+t7%cBOB8EAH~mOw%(Nuq*gJw&t$$Ig?VB}hzb`ar`%(OIj&K** z_w z#s;-6xV8E%T^Qs{$0o9Q)T8gPZ`Gw!wnrQuos&Ol zLi%L;Da!VU!&#Z})N{%`%JzuE*PEPZ{&CiiVAtl%zowT8zAJmgq16y`eW|i0$o7cC zK$q|CeH)nIAT4{&lvA2VvwkRh#Gz?sbFyN`J7teJJiK5O8UF0PvPT>i|2B^#;~8a- zILs-tm4uYqqwEofU;3ON)iuj0+anGqnBFEIe`ip(M;uzTd`-N6fwD&&ZXU|!Ka}~T z-^+BDwBKZyO9wsMBMz$un!xV6)7?9>=P!8hlhlacqG5Z)p*dB3sw((=~ z?n5|H)_N>Fc7c5MnMv3lakzB7p5#>DK-eB}DD0NV&WDFdPnOra8cZO~x?d-3k2w5n z-Hz0cenHqCahPatO0HymQTB*Ksrpz=+wBF)9&zYz-pIXUPqrqSrNzX=Lw0hUDzR^t zv2Utz&F#P$`2Wd3_x;|OeB27oxg3?2lV}$MUk@T8+d5`*xD7-;D*2S;;uH zYy|ndGEX>MONViu>or#&)E74`&|&D4f%;ipI*Z9wQ!(y?A5G04D?VKujn!cd{S~@M z%!vp`!QllBy|6*_-yVWd9@R1AiC%p1v^BOUu*aVyPwWxj0QdO#vpK)##S^!S;f^J} zFz@1Jab(;fn!6+lr(U=$me0}BHlGqPeZhHg-+}x3io><|)HP3R@cpg3^gxH-ZtKMz zWtx*^9n03QHqVDbH?y1EWBX1vfS(bEWVRkpS(68ePABES4?Xe4&*I?cRZKd# zZ#Z^+qbHARR1j9LNk*HI1IX>~`9fZ_4(DARuhBX+7I(bSqP1?X{&|N1V&mG0xa-O| z8d-6=*nIm?%=>Ycb_~rColbN^FB?*~9V%q&(EC!#wD0cm6OP>!;!-{oIi2b+WqVgb;dSjv- z{c!}W+_sC1JGxB%y}vIsJNT8D%-SL!X&em266%1@o&9pk#1>F%bW8B*e^Rd4yEa&V z4~9y&FUWF_&*XPxKX_q(MV{Yi2iX}t5(MAN^8W4pNY=q*=p>$#$JV^B897o5>z(ps zrCw8f+Vj|cxu=6A5wE3zQ`9LrrPVSLofHe2;+N#;=%=Ju?Fg9B{fca!Tod$lJHW8; zi|Vz8`q8+qwrpPz>p}QnuateFd{t=W(FxDDX)m>^R5_m)oyedTMLAX+pMWJBMtYC&l5soBXa}4>CkEYEa72%Inrlo zIu5qB7s||>MFs}MW9aQbtESmE$*SUmv9|Am?DeUYK?)1S>0SJ#PMhptkChvCJG)HU zci$iSZ>o>Q&s>t49qI$01Ao%D{w3uRGe*KC-F8~xL>;-?yc8&i>qyIIG?%BdI?nWa zFMZ@QH@QTf7M6ZGs%i7VM;=fi38pqnCn4G(`AO(7_&)sv*&GloyA^bUjTg&6zO%o4 z4+OmymydG%bYUj<;tS*uI)pK;P|Hp8t_2DqOduR$&3VN1(&u1qc-ex4U8)DvQ zs7V1m=-UU#xiZ4QUJYtB$DA7}fh?*2`0Rx2Toxitb#+U}+i2Wrb^4k^(2OE;Rgv6&pk zz9(L6Vw&E|-%TFlcWEk4_K`K?lVI_xctXO0? z1}T=G2vzGpliWX_((K=+h5F{(q~d#m^|dzYpt~F^O{v|E{ydWco7R8Iem8k5E%ACJ z)b1bH@Y0O$G#~nc-TY!g!2=7_j|qS=5vjtP&Ta5;CYyY*X{Ycqw-YYwRt4mDFNCz& zgK%)nZL-0$qIkR@4qs=?Amtt7Yu_cEMt@O#~irVBZI76ePCX-T`~%)WB=ye8g^BT`)7$8MVo6#0K+f z*{E+n2DS4MS?xQ5N1sbcOjgR&q1jGh|QQNO(so z$_~T-BA){iq4ACv(z=6i+xuT7-WXE)M? zOGm-9R>3R1%)ihZF8yF$_Gc@b@Ot=VLm+&ZA1|D!*c$(O-~e|^Zx>E1?TDG5s)AGB zXTsL)1F=G>`y|Ptf=DCdQ0KjXy^Cxl=GmuXenc(uFxFW-^;?H)>>BQC*UUqF{3Q*4 zHL#$ir~8Z6pJH*L{bIVJcd%Ha>_8m9;~||K5+shg6oT8TR7bmbAF*z2SG0cMh~F*U zL>Hkhj>!tb?_-*YUs6BPU9bA#j2*Q_$$UM1QzsfjOP3J8v2n7z_*5LV>AaBJx`tkR zQHM)vE*82zc&2F+s>P-kJ%qHT6Ud|I33$bIvenYF=SbRLL-FmDi0tjl%R&6CF4)oD zMJhMV7Tli^d@*UBln6c$Y;T2mw@*p2M|*;~e+j&^!bH9@WH^kNg0!1lORms085UF+ zLXQ_~DrbA>U`@ml{ebdq`#HnGWeX)oQiA0k zroCXowc@OA5Fj5|?gLqS8^N_&ZROo}ZNXzXft`C=$mM^OgJ)g3z}Z@YY@d6cjOZ|w zO`)wMcWF71^g5aV8$4f2KfArs4EEJRDBUfM@u{ruazzI^Yn`;BJfVZ8roz{^rKNS| z>u7?1G@Laz&#JxT107=9A5PYIZq?&T9sG7P2m*6P3O|mt!qTmspkwbXLdA>_ygaEo zEWhwrFh3uG-g6%j{ikx`m2BNdvN;mhwMcZae&K133#!>chl=eZ zHO2+Y7fZ6eN}Cr0lkfm}_IY1$_G$&#i}I4- z%Op@Y1RA7NmQQ||OazYvwvYZ>seP4S8oikohELxok(T#z-Ja;cZ0;B-Y@7?te4GkL zzLuAY4_Zaxbu`TKP0MQ7@GZ5gJpdZayJgkMt2Pd*&<-LN4HaVIT`*&&GmOjGD2#~c zfLE*6gwT+O!nv2>IJ^Ec^6_L@@nDNs%)P|s1@*QR!{(=9=c$cJ$mNG2anr}$ zrV)tsGt+Ux$_i{fo1YloFdi=~o=v+r2aEb6gK+lBTQoL1NHi%Cil^UK#&T}H;{Jne z@JCI1+||Qf^zf~Z3tI-DzoVVlqRS83&a^L1K2TR&9leb@--HEE#_Sd78dl-k>$@4vCpGytFvrPXz9AcaG<+Wwrij% zq;Btq(=XacWK|P5pU@WJ*bJ%uRZnPCzA?_*bX?j(yF-WNr7^0{PigGKVbJx-QJSKy zA$vzA!K%naTDGl?9P(BRWdrx>Lyx=4R#SBFCN@^%cf(6w!5Unx9(5r$nSpY5(~GB@;t4h}9ECxu_KqkA-I z@TgujDSLZ1Jv2QAs+QWE)qKrMdZc(bytO@NMc38Bd2a0?bbPoFXWkM=y=wuludWk@ z`?bgH#kIiy)IH&Gsc>w%^d*Uu%*3EMF?eiYHW}5gfvELL!%`u3q?w(gnEOG8y_1)@ zJ1ivP>il$UVqTi|o9`!<-Wrd6PEDtAwOKoS#bEqwcAYLd9wY|T4#S8Zm9WubUr{LI zj-&QA$A_=n#c8J-;H&~a)EBcC9~~>8t19%tipT1SO&ac^lPizJ_=TlK+XG$b^!6!u zdhT^$$(vaHhRHh2IFl_jciyLwUukisNvN>lWFoPNNWwY(o2^2BA0_d3hT%Ss+S%2! zO2d!b?%02~m6R_uhFXU_vBSx!lFj_K@Mv@sEMam~s*GHqvfJu$=m%4{RFygUopzAYZWw0LRYtq2eS@xotyxu-MZEZeDhg2S2F{7t4l1 z$lb=WZTu}V@a!NMy|t>`ZPaY?s!2Tb%KId3-%^20o0JX>zV4Uqx%%XK{LlfJK2aKD z)`YFkN`rz@>bnq!0S@Bm zr#f8M^@e+DSt90{YSE$nFa3kIe&Sb60@f)pg|7S=Bx)0fVAP1qbj9-^afd@^oV=$3 z(r>=v6+aE0?bQrTv>I`KP(wVD?~70K?8Q5Ei?Mfg?EPDwg*f@*URtdC2&|u1Mw}Da zhdMn<#y0l1gv!My>FtNJ`g%r=5SzMAbF;P%-D`FiSc`y!-AuwmCv&aN^*cmPtcb!* zEljf4|11eTu?IF;XCYNuDS%fwZ`^qFSoQQ2)Le?$v&gYIKQ& zxeZU#NnzDwG9nR5^=5M$;+x2`rfQ*X^fi62VXb6y_Vtu@IjuDJzIw`~Yovnpem~N* z1}npdkAjWYH<6|@gXKjZ`ojKlUx~&xP~P7y5PF`g2LZ*r>jF((d=w*M+kZCr!Y@<|7~Wrw7-yXWrM-tw8Rcy3CY;@^c|u0<@tIkNQbw4)(EEcmS{S+)#0>KeTB8dhmeGh$+%>|39FX7kreMY z9OphimF3yF1k9s7alqnQQtKvGAo}`X;HwGJz|RCa=xlMvkp0s6tS&Hld^zlB@=4m8 zITX%qKS$4Ns>)qoCcsn62{dhbV|j6BEey~+(|_OLB2PH4gMew~ni4usIXWg4>Uw(+ zt1AKWAoFOr(s(_2F)di0@}wWEo%N9{9uz1)%?yHOUUk7d*-PGd&JljuxU&8DUFD_K zt3%%lA&@Iu%Pki@B#$c(go20F<>$p06VIQqP~yUO>D;b*R7p%+fkO+ zw$9U}a`CmOy?r|9Hi^=X*adVzcpUVaZO>eX~a4UpqIF0|V-bW{##iN`2#3mO2^Tykt?=m9#*a~3O_V1 zE0$O?ocfeVM(gPNLO*>D`-Y|tcl=x@=;}_@ct+^Z|73*FYDYh^_+TCHSJ&e4OO6S_AmLDbCK(OM|C&hTY98V1B}T z>DS&NaNPeA-D6cno;WxGhTY1fzgCHIR2?k@T>YxQ|GTBU@_`QKlz!(PSI}10o=SzP z>s(3axdHM)8V%DESF^q0g5{2v`$JH@cO-FnplqQJhA|s!gUuT++1cJ1eqC~bN2guo zYs+fDvOOJOr_M&sW#2{&Y90aQztxbl@|TfL{bFHq=r8GQlt7kkNCVSSC!`r{Q;YLI zbx{244C&UzN;Ehj9jfhYDjmt0L(6@OgRbA)vsWy;P0vjn1Rg%itqu*Tf+x0gf~0dn zf<=Zse(l=^GU8VVWKsZbxnTk0HCKeA!K{5W;5$kCP*QaJG!p9%+)7^esVgoxo5Fmt z9ZC4sT(sY)LtGrJx$fpJe%+)+t>qd0ktV+4sUwN#aWI1h%ncH^+>68pS^3mb6D-~w z+70LJH^o_{{Kb!!ZLwilYs|3+arjCRZ#a2jSOq6>yigj4mF zDJQ0Pil^GiNjSdRBcaU49r`OjwODfhMq$J3G>!jQ9a^SG3YW`vCqL{`aBAQCRy#ZH zCdDp~z$K$XvZ9~-Ca?FhIs3llq*fl5FeTd$?|F}r#`bfEvE7@a^{2hk_t-GFexV{> ze)2|gemoeg?_Q<7OI4P~-HwMRi>J}5dO_}RD;->Zm7t@8TgnUG>R`i?E$;qlZRL>0 zX^{BZfeh{tATRD818t5-#BX%4TzdZiSg`sPd3-TY?(m`=tTi`>2mQU};JGcJOI%BM zpWIqrV_ggMi`#>HH(UAI(ia5$!(q5-E&1BiEYjgX42(YYTe|Psj3o3(gPcS8l6ZKE zd+28!R5&tQ3h8c2NA6CCEsGtcg6lJAWM(`JY}+NQ_{Lc1b$huKYN0IP54DR;1tqFy1v{QIu3Th^Osgj zyB*uX#;UdPZtpviro{lT*!PC5>ob*yo5aAepE>kba(%h;yHpr5uO+n}w~ve+4#=T!i+&%Sa! zI}MaiZU*Tw8o61uhM@iC3oSO-%k96jZ*eqYdqVHBkVh`rOA5kAK;7MCWsv2iC>{$Hzyn+iO|j4lpnH@7tgj%Xz==uj2e#B4mg zrinP@#9dmg_#kxNQ%%e$KA)~#5{FHjeidrYs7{v!rsJt0hlHw)(Cq{PW|nCn)Q(v~qyw>Re^yhg<{uuBzxGC8KG~Dqa8GsU+$RJhLc2-ThdM#$`K|C* z&m3vQ&mefZp$=NDyD4?@>JN|M1N9tIMz-!54HY)6r8844WZQ+QkXKbhpRci(TVB(F z{ItB@E?y(IZL5V}yI*UjzVMYbyAoh;)}S!E#O4F3`fZJT&R( zCr=nhV9+mH=v9u$=Vmv8E$9PH5*_4cQgK+^q!-XF_2r6wl(?=P4mTc}%K6g=l6R@e z&~VcoX?l}+nq?hyY#esA^e%dtezuzqe%0?IEqpnIRt!vrJF|~x`@TVXFKjr>x_7qG zqPP-xWnE9GRnc4+*Ut*K*Ytrwy(bF()dA1;wuKU__Y3VdcEP)G<-o7*Ct=VcHl8%% z99#ccRebd=0b}*!N%*S9;_@C^jK2LubNPsim~~!<)&tD-VOmddK~ySsrXIBUjR0{{ znP_wvx1Rb<4;FWw?T51;e`I@628vF91>x7Ax|p8eCHkIl#5zu{7~9BIT=TFRcKZ~9 zR+Fv8X#o#uF>xRUo~$lDIJAg*m5xKtHQ$9ngX_`qztixx{ZU~^{KdV`nO~=$oho<^ zGACAz({agLL0GeK0kP{5hZQO`vicl;pM)+Qi1|y_XZN(M22|G(F9mdx-c@sixVx@+ zC?{L;IUfj>Thzmy)vrtUJM@Dt`p-1orL=r!(S|ER>7{Y0eoE+$dO{>D3j?rj>;{ ztNrAgmjL#TwSoBMM7~j1fb%Kdu)xbvUe&%N9JB5T$JREG7d~b4WM496o*8aXk-pQK3tXbWEWt}uCWV*gvUse}?2$#AH?oVg$PKLQ>E@nHl&86;DM!<+R z%NotZVpwfcFEBe-MOgW$Ar5Nq3)acwgcescc#}4TO=eVBy|^=q<`tmYg7-rG<3li} z(j}78vWi$PHUSq*&LmIwiQ?QwT3omPvnJ8pMZA4qhlAWc=6)*aDO%*EV(v#*dT)M! z7`8bY1M*f=mrV9vL*F0wB)+2u76yv9)&}G0qqVWwQ!nvw3ul~o)&*yta}~E}YvAFt z9q{{b8?ofEC$yV)1P-`WLmZQ~jJ6sciy;ku39Fq2`hHUyUVeLA_%Y5r*XEZFj~tvK z{JdA0?21Zfb3SZ^&F|)rb+6(uyOf*N$BVbgmefJ$P-;c?m5eH2v$7MGZ5AvQ+hq@} zo3+8d4_8PP*9Ab@W(%w~@rq>Dqc6BRf2SWyl#&OVjDpYBTj`>ab>;8ZQ{a2sU>Z=# zP9C{M2Qb=SKQP2yuDekS1zXQ(qMG{3jcFp(`;|e~%ny=xo{5BFpYll+w_w>Ln9Y-U zV+y`M{p9bp+CofqYdF*tqZS>DST0;=MHku+*E;4EHw2ZJoWv%d=YG@dWlBE2*`Z zQM(pi$Z3x+JJ^abzAxy#KH+Tqq^8*2A&b5{8-vAW{1$v~H>I8Wq~WRTd?9V(l-!=5 zb?AF=w(#28jEvfnj$U6Kge2FQWJy{)W?u-kTH}9%RPQ_(_hih@o_)I#?8H#CHuIGp zwzGp&ts9Evmr3Qu_(O_K1I+qkd}~%D|ZR{_@ZePq?|ZG4$IC^2fSO!2V5J_NQW(t(`c$MAi z?RM&(Iua_Md(v>rhM&}NRUbGRSxRVhzCL;$^M~ADS|Qrs4L?k<16aFTNKXny2fxa2 za^)-GNS(o0p4=oKKUEa_b&JP^&1R8h*R8~nQaWx~RhBrfZy^SM)uFv(YHs^VZN*0k zY50AC4INxIK#czygP%NC(&-7oqTQTu{E+yZ4l5BP(&z1QRBlZidB9r?dejpCvTA{q zYPS(fY&J*x)OOg+uBn)E{59slOdQ(BnI0&chKGDk3$%TH z?%5Y?9>Rusf>rxsWXOkfv=mzjPm`yTaMJ`lxGl=6CcQ#V*$lzm8xQuAT#Td?USn6R?Ayng-&7(IIr_3K$%4l!fz ze)T=+*?!IBs;N3?(Ql0Yl!codY0ADbdu@y6&|n|gZATK6S{p-lcm~NKeWE~Kd6>ug;8(3N@tZxHW3fXxKcEx7 zxLyTTG{p+9*sl)k8{b)CyhjtKIu3%wJK@z%2|BI%F&;vis$a0 z<{_>=l7?ezH=@D;e{smXSe&6lloqOE(kO1iq)e#`VXCyTi*{@fY zhw0BcWANM7Qb6yf(9WJnZhGnx zVlF>jl+3!4QgS?s&vZP?s4R-Ql3(i|=3Bm3GUgI(QWqK zg}L4xF+Q#u44nN`@EbS~^L!tW%pK*$Xva7ly>%hE{h^_lQY{@#L+h}8+nvSVtbKHS z%gsHD%6NzgmD90GRvnrY?=KFukHaWjNT+rQ7Jv2`hz|W8Q0x9dVhzWRY~5EiY(CFN zq-m~rHq{YZc5o9@57fnuwn2E}N;9$T@lUkg?0)D_yN);_VgpUSGYY%Mln|YwJ?WaR zsaPiSg3$PQL;cN@Iy?YNgtN>Jzaq657w#ow-x)`$nI~f9jOkWu7Mvv^c|*~{tXKB- zGUcGkr!JWJ-C4T(+y?$i0W9k?S2}|v(`!bi_fN*LV}w3kX?_ckVSt}q;OZ|2SgBuluC=_ivktmUnXL(#=PgfPkPI&thZEg{Kza7f z;jkl6Pb%wzkP9K z1i5_WizK4>P?&M7lI*RUL>4VbfCrXuq+tQ?HAkGaV7YRSlwngsA8}g;htFrQcUx|> z@s?D06lNx+UsywLkB$bC*(PgE%zL^dr9WgoePngEO&uH^8Vs-64Hu&9TjAjgPSB|F zW}4IT?g#(oaME~0*{sq#LL;uMGyCHwDj`6*tcO_kv7~yYdMZWk2NL5iH!nj+UFE} z<8oQ}J{a^vcC$IwKb8sS8(q|-EZ1UkNPy7OYz(QfI1yi3EwOU=!uB(qABkmld1hM< zF@x;iUGdoqE^TaGQ6!scZ4B8xT!%ARvZ zKqYw(sWmZJ9x%8!RQt;WJhcI`Z7V;xbJP;%A)EiayBXB|=nm)QmU3CQiZJMU7~Jh6 z%FEYYA)$6dp!}1{a+yw3N&SimFlXyKY1B~@vg=DaTW^^wZEBdGd+mh|GFFV0g8Mtu zm1WalVQMAGu}ThoYaIh+tY&2G`}CR)A2I-H54>jedAB)EjB5weCJh!!-C*C3Y2E^| zhHMa)er}Ie>uZ8_w+F(E<>5$!o|CkpWyS6VF*vfpN)lbhQgmkZ@~kyB#5c!LOl0-- zz1Sr8z^6p)x;!0|+{@7iXZ^&i(0CjXJc}N)4Hn&N4aP^oH|fGHY}`906f1>PMty%@ zaj)QpWTPF1OmG+H@2QV#uKVMT5q9FK?4R`anm(8<)Dy>C+fK*nMxxWLQsV9h9qF_g zDQNTLs?aUAx4!WT9SXQo*xu%dCgO}1`_}6q9F0sPduk`4>#o&SnH^4$E&Ye#n_!#l zPy5Tjtg_wl+_fgsf!a-=`n$F`XVY{kHP91|ZfT6ibjPHZ{ky}{7G>~I#t-S;%3)B@ z@Hn+;SVKMsNwBkW3XOknEeGAyLi3Ub^zYMMWtaInNSQQPQ+$(`Y(63djz@=);z@yW zd4D#at6&Ey$Huxt`t^Z3IloBGfdIKuygyuO-2ldUc(OK_9URGWgXEqr@|iQ0fSw2i zFR#Y3ncEH0q1#}vFJ4vN(qJa>&4`Bu;z z+_U&z_pjZE7;`@z&-5ulBa-~YQukO}ICC0pQ8`##`*JX*9llDxUJMe=GQ+Ucwu+c} zz*l^m;f@|I&GCew5$9?wakcD+>F)O8AoktlCEM8kQdSn?)QP)kWc~xXG_AHK07t?4=pad6DCBRk0S$SC!t`y!^&AcLYi7fq3wf8 z*-fgIhB`HR;J~#FCD)B2{BGifC+|;@c2{Z(uPm(DoRh;+CR<0){=O;R{QXr5xE2Wy zkLS}vX4U1YhZAAe88((%*;)?RpoJkH&gdUsZY57;{jZ=N{+ed3y=0q9DbQkjFxlcB zD4Tp^a}GnclK1R=<=n8ou*LT~*-|V}4p|=n_cmIvF?aSJWT`!LVRQ6PR%<1f8BzrT zw|0Ww)=lL02X2$-j6qPmb~U-d!#QN%n>cVj_*rT@v@$6boeoiN4oC+;%w5OEx^H%v zB(>-!(D;pMV3k-`nmA<{T^tz;qoY4%&3gQVc6N_|KKA>q<}Ip$n{zur)wMkZi#E;} znC}ABORpA|a0u3Id5Nu~4idjF?2Mc1 zRKSPz{KW5KFwbv?56?T^$yLt#~gNG9n(_}0cbHHlCj{~I5 z^C;Zk@Ksi1|B?`E(GwR$*Og|t3UG0NH*P4IDRsLHU^mtVH+vnFynVaEl}TmsX2xe} zLHS4+JK_u-`=+W)yb__~^1rC1O%u6*ji0*lO|)dCIF@Q^EbU zH?b@Tkmsx#1*aEoB>P!j&-U#H&F_3BY{suV;YuL5H?IfvoW0n5U`IIq*cCb*YbAdw zSq;9;>IfGrTFVE$?~@YpK*(=iT^_xB0h!V(4yJ3qNe|u3$-XA(@N36mssB!keP`G^ zta08`B)n9Q9{ZjKw!<4rdFK|$t)xe_7Z+CJ1k~s|$mc+z>`w?uYZveIzaJlok(HjK(9q){|0YEX3L|spuW# zL5_yniz#f}%tA8P^l{gS9eQf9#KtH3cl&+CjUN)w<;8f~@LZ6XF=HrJTYQd|uNEv$ z$?1ZpGsaGWa~Eswx$Ewnhw1A#YSXnJt$l2 zf!(Uq6jNF)qihWb?tAxBU~5AtTN{F%#vc=uH6zM;5#@TW|Et*{1Cf~KDEZc_UK(CJ z>qsYe4Uo4^ABEl)o9GwjYgbtPV8ZGNyV(J9dR=eaH&wv+cn?|mRsO$I>&Wun1eI`M zRu-~yopSw}VkKoIJ|*7%drwJDj;}-mV-h<~l;dOfRhC$IqJ($b*>oj~2b6d=$CMLT z{Gh~tWL>7fenGk4)WP`zI}ghJ=6)|Ovg<&(-yGk1B8v}{`~5!epxg(JjX$NNtME8s z=_(9QSh_?*JiyW=8sZ0*F41sbVCiD39p(pZKB*y@f|~Y zfu&0@*a29&8XD{aEM1bpZotwdDd|)0$I>M!=~nK?(p6}G!qQckFNCFw**OD)gU7O8 zb)8mG-YNHg^za0G-lFuXb}+V&vE7XAX-KbXXG3~b`y1zraenO$; zHHt2bOVNe*P;}wF70vz>pHY0mr0`i4UC5}SwdtD`cGNJ1X;zLG+CtInPw`{s_4QzP;_D5C|b$0?b~iPR+Qm5RkR_zstxfdaTUg|YQue1%}%LhiW0`~ zoa%AI^Q$`ikdu;Ug~!!0#SmUCQxwhq)G|d82D_=@4fa&EA>FDr*k654L%yh5v7eJ; z1vS6^R`Y!Pua%EHzy53G7x%k=jq;QG9rrt>-c{;i_Q%^T%m{{dn%ed-wBJ;1u#c+$ zZ`&>0@3`M_zcVrUXZIJl-*La=e#iZekE;}oYw>ZFf8p^lUf=Qhj@Ng*zT@>BukVy` z4P}t$U-^9yukUz$$Ll*@-|_m6*LVNg_1&L27KQcspWi=qJJ;L}oB_@NXMi)n8Q=_X z1~>zp0nPwtfHS}u;0$mEI0Kvk&H!hCGr$?(3~&ZG1DpZQ0B3+Rz!~5Sa0WO7oB_@N zXMi)n8Q=_X1~>zp0nPwtfHS}u;0$mEI0Kvk&H!hCGr$?(3~&ZG1DpZQ0B3+Rz!~5S za0WO7oB_@NXMi)n8Q=_X1~>zp0nPwtfHS}u;0$mEI0Kvk&H!hCGr$?(3~&ZG1DpZQ zz~5n@@Y}TPbOzU|k+>cHu)^)Y?Z6q}3~&ZG1DpZQ0B3+Rz!~5Sa0WO7oB_@NXMi)n z8Q=_X1~>zp0nPwtfHS}u;0$mEI0Kvk&H!hCGr$?(3~&ZG1DpZQ0B3+Rz!~5Sa0WO7 zoB_@NXMi)n8Q=_X1~>zp0nPwtfHS}u;0$mEI0Kvk&H!hCGr$?(3~&ZG1DpZQ0B3+R zz!~5Sa0WO7oB_@NXMi)n8Q=_X1~>zp0nPwtfHUy-7*H&e0eL4bh>Ge}FAXl9btH=3 zI(-y)TWnJGm2JJ1J1%0VSQC0<2q(>Ke7 z`>C_zwD33!PYc7dU|1LriysT)XTMl@Uv?f@I5kdo9Tq+(iw_H*pWO$yZ@bx8xv$|k zRkR_zstxfdahVw6SGD23s%EE@=TWucIaO_VepQDba$2R_Pl?Bn-oo&T9aPOuDfUsd z!EUNn(x=={xt5&=_M>XW9?Jcc`zcznpOa$+HNXB=^L+fTlaHtBRYT2~j%r@- z3%*X5%^0j|^N$l~k249XE;;h3J||zR>T$;xX!-}}RDE`TGP&xVr0N0p&yWZ2hpKvP zctz-pVX9s)JHUm2*8fibN8i_&Nn>t}c{b+Un15rxV4xTIi{jsfeq`)lc_%`d9~AkW zQl6;kHTF{$Pm%u``?ayZ8~jqeR=JOn-znuuq2FQSoGQ%Ei^>zCXhV2a8{z@wxFLR3 z8}6%Wc1n33RU4jD)yjPodnwm$uGB>-PYRD0m7fMXsK;3_#XhPw*iF?2d#c)SUeyNs ztIui37ga0wDJ(a5-WAnxMRg6&yFc|8_q#vs8SZyQZ53p;Q2rH`fmG2-8T{X^%q%QF zjmuTz^47Q7`H z{x3h9x`70{hjmv!gKB%ZIt=I<@ zLm8J{iv5(fwQ}50_o>==oW!^vXI%Fg*NMh;rEwip}$aQXJ!7Rs+s+<&|eJwboIEQpRVeE_WK}S-|_lRDNh-j z${#O3nGyaOgL(%Inq#;EH?`TPg|-kh&D|9>;Th_^F& zJCnCFc{`K0GkH5x8HZAvnY^9J+nImfU*I1e`20-84u<)t>bo2M-sk^p9y@Pm@^&U~ zXYzI?Z)fs$CU0jJ&FAFpOy15^+mn1elaFWe`49g#|AEgF)&8^hq2lwz_&hP*KKbXjPq^Q4zvF(#{f^JiRL2MS zdh>tr_ddM7pNcG{dX7#pNcG{h!x&r|MNh&6tj;bcy~E zT|K!GuD#@=zDIc8v@K5f)kM`(6MJArOet00$Qh2;x>9xhSAs(d>fUry_58g$)F--Y zlzYv#&|- z*^HmzAJI#uIl;x4R%*J8wehtpXSBtbNq_8YU8^Tv7*Cis4ylUr!Rq6PteOc9>HEiRM+*_#X=BvW7vE6f32Q3K3v3F{#&)~4i9!0k{ zs(!P&0-{@IRZq7+LnqdWRP{^y6nb5gr0Q);m+Dt)bgDkRUatvztX1{CyMK|yHi@b( z_19%GHfD&bOBYmzz#pAd{of&t#(DaWXy3YJ@Md&(P<)|jrVTbd3#vZY!Vj;XuvGO} zpS~EA_Fc{ER+XaBqsMwxU#gOZCD2LL^$T=3qt912C7w&W((vmjD>bjDbcsPyT2}Q} zp+7op{-Ekx%L1_KehW2UCJ%3h3tcs;ZWvw`ZTfaqwcoSjbYkK#RrfzRf>wR^hk?BM znfkoQKMZuyoYK_T`GXcAr}rPx zc^53#DBn<2^4I5f1^RnJx~fexrqJfi5>(xy=NWpZa-^#NUY!4@@hJBzyzf7zGw@G1 z^|~VMVw8w3D2HeR^r;#L5Hpu z^VGWXG^FFT9W~VO|410)IR6nH8<7CsA2Nw@-*PVp!Qo=JR2{k@1Y82Et1R{I&;l;* zX{qX#tE$4Xiyc+%6Ml_k92>0a_*xT4)~i1plCVP>xTIB&cOSJ_|J75c>ci(#=v?O{ zRpt`I!o;F9- zSVfCh%KuR7zU5nWX!p}swcFoI`@d>>jnnmy=#ejVu+8Rpu9EMLzB=%&w@9_2bqX*Vibu+jAP_56OI_p(xGPVcwh?-gqBcCBDMvXX%2*Ip-QH5gLxG zHaCP{^VlO5BrS9#T6xz{{-oo&-Fgy#U*hf8X zu$!t4_EfduysDM!6gw*MEB8_2RkU$gT6j;xaVQ*LGPZ*uy+jFPY&TqO)98r#9xKE`%4wx_Y3SrUruZ{Sn4vvGbM8~-S$(58m;s$q=t z-C!T}xG^Wj{21)4hB4T`Fdr2@i}F#itMX?^mzqb0bQR{85(g+@4Czv}Azi9wr<8Q5 z+K?_)8`7ofzsWD|cmHNjRBUU^k10JFcc?@D3&gpaE*`!GI>>|ksk#;0Pxe`il) zJ1gf6;gs*y7PUhdpGE!gzv-v*aTR7X1E0ubA)l%?*qpR}gG;YrrI8@m%aQN>yG3LjZD`Vb_IW#Uandak}%*fpDxZiQVE9x(x(hg&8 zQRo+{=JlOo5&r&8sfQFh82US^X8%?CJE}JHcT~;WnSbWO8O9|*v74csQ8oK7Z)Y+i zDD7^=E{c6vyT$O{{EzLFV@f;a&o9^94x9nb0B3+Rz!~5Sa0WO7oB_@NXMi)n8Q=_X z1~>zp0nPwtfHS}u;0$mEI0Kvk&H!hCGr$?(3~&ZG1DpZQ0B3+Rz!~5Sa0WO7oB_@N zXMi)n8Q=_X1~>zp0nPwtfHS}u;0$mEI0Kvk&H!hCGr$?(3~&ZG1DpZQ0B3+Rz!~5S za0WO7oB_@NXMi)n8Q=_X1~>zp0nPwtfHS}u;0$mEI0Kvk&cOec0d=qZKQ_wXS~Uc> z1LuJ=z!~5Sa0WO7oB_@NXMi)n8Q=_X1~>zp0nPwtfHS}u;0$mEI0Kvk&H!hCGr$?( z3~&ZG1DpZQ0B3+Rz!~5Sa0WO7oB_@NXMi)n8Q=_X1~>zp0nPwtfHS}u;0$mEI0Kvk z&H!hCGr$?(3~&ZG1DpZQ0B3+Rz!~5Sa0WO7oB_@NXMi)n8Q=_X1~>zp0nPwtfHS}u z;0$mEI0Kvk&H!hCGw{D>KslQMf5MoU^s1Kz7tcBp<^Nl!j{~VRIU6f|2JF@hHxgzb;|Y1aV0(_UPU`OP8AC8$Bxs&<19Qa49|jLVLU8;ER3K1 zV&Q$+d1T?#IN5br_?#?0EPQ@;A8ed+uCa1o!*Qx;LwHpi;!)x&azEu-b{^P|sug=E_fw85 zc2e%AXvKcaj&h;?^IH^#DE~KHt7=1>O1w%MdEPNQ{Ab9!Q}wE$W=uylulEICr^{vx zR<-%Z3AD$V1XY(Dc~qa1uT}N9;|nzX19YlByFZy+^-fatfct02gZD#KJvO`|bjC1M zua_O*LO^R(|12U$AT{@)yOw3;oF0zw%CmGCwHtJEc5P(`)Rf zES@6&HTG*`e>eE0daZIFBfnG1lS044>)kizu=onglR{rBDt`>|fD*txZm-9D=#y7naRsc zK3-&CK&d+m`{t@P9ur`vls=t$+|V~ywV`jW>i?f(eY}5Hly{)yBOg~OVwI1NF&>Qj zP5*tM?^EXYEc5%9`T5ZN zzGi-p<8NY?d1sk-mUk6{;qQKzw#+-rytB+Z%e*t4$<5E|d|dFq^K+p2*^X6k1l3p-2PsrfmLrpE8{oB6rU{Jdv=4m3X>$~k2^KmUFQGmjIq%sb1xvz#-3 z$DRIuhquf-J!aB!&b0VmS1osQ%iY{^&a|wVmUE`%oGI_2;w)h~XIjpgmUE{5yG7*M2>e{le@2JpcXn8Q zZmqma@So?#-|j4Hrsa3#h%sPUGc9W-?HBxaA&LD$zR3t#-nqrS+wz`iSu^DsTZ{*} zj|iC#85SQ98Nu?NY5Co7mNoPD&$Y9hGign*teNdB=SUdXeP zkS%v}H*ub{teKWIlfO~Xe6XyUmbpnrZol zON;>?XUBcOd~EzzubIK+ifYP|UZSmkM=mz6vUW7QJ>$B?)oHD*$fzOYwQ~k(ZZmQT z`GwCEEy4+fU>ii{|=mfRMLca@Ev14hk>3$!3w3BX6?G<>b+`wVzKnh`G?>!5FR7 zjwm62zUQb-URGS_c0ReWcDPV8A)D*@f3rU3y8W-p2RvJAGdy(L)+{+#dps$pu|AZ zSIu*1a!X!M_=N>p^0X>~`vujfBgmbYPQ_urAt-_p(HzaxIbwo!pZSwzj6Jy_`!@o*5 z>BjS$SKtru_b2}mDP`hjG zoJt8!W#p|CRjb zXIFNv)}27ky-^2O)}h=^VZ)jw7O(+EeNQnj`=7~gUiM$f$Gsb}$DQpouFtt?UD@I> zWrbX~@?nLnMiNj!o)kMI5Ytc%)0$mVtaSJY!(=f9Bow+>q0DmHxm`8#D1 z?{IoXJ}+wbZ zwPY0`Z~Ac$&v+IW@_F_Pd!NlI`({Yr@x}4TaqB*dArxkH$hS-0N!%Q{SmAW@?Lc0Fw@+8<=z> zox!9t^#x3Qp*||6K2qPANzYX)YO)g5-G%;#Ry1NK78DS2a7q(avGk%q-nMOz#;jDx zErrX$3+u71hk5{)H=M4`Aa)nR(EciC`)D7%!3CH^RhBs z<+99=T;B66x+c%ZWn!%mYatVBAl5=A)+Ak&ny7S0lb6o%ka075RxT5?>(`UnIUl zCca2~g-m=^;w$7ZI~yOWPsnmCi8|#N6X|m730aOwA>-E9Qv`BEp`d{kb65e{?l6_?+mNQrbQOf zcpmzb(cgtk{|=N-$W#ufypX9rpn8Qow%i{+)SfAww`a=F+Y>Tx$5an*$5cQ6)6_2i zcauK6oJmh!pGkk-&iFa2P5t8OAp6Dh3t849WLZCx{o?HkS?VKX-VV15&%@i{_Tutj zuQi9c9c4Q2uPHybgOH_tge>hQWZn+{J1&r;@8_sJkNgU6&bU>{m^xC(PVbiaaQS7+ zPp~G|Tjg@a*>9lZ=qkwN*^wdeJaVd#)l`27@Yo?_`V;8yLZ*KQ$|qzh2UK3jRG&ii z3i->xjB3=jDP1+C^L9-6c{`?hcsr*0`JbkC`M;a=;pI$v^7>5r^LDPJcl4J1;^~U) z7tar}U%Vb6%ld^Z+ZD3ZN61o7A@g>)y?8y*-LCm?n{rw9*OZ^zLCCxvZbzO++D*vR zF1M$U`M;a=;pI$v@^(!6bH0N+hyUg~B}d?IzT?~v3ciEtw`a3FG_`_TB`xrx9Xt7I z4RX2Eb{lqnSXsQC)LzS&Q-#$!7A4a2Tr9+*Uu+fWjV|P1rB4*ocz)Nkcv#r>sYqY4 z=OTE$X&}2vJHLci-JMSAa*H@r(9=pfRcE#0lGsaVOB zA5HlwT{Wds{b;J6>OoUIq>pCOhuTF`yQIHn(x3E1lb+OH&D3A&muBi0*+ethgzTW1 z>>$$>-rvQJm9>7Y`grqx$$CKAjpqkxH{PyDm-UNusV9?m?YEseN6eeolWW7o+4dxG1bHEFVZDPkuG_Obje-lFZl{R}7gqU3$5&7v&c}3%sR&odf3g zWf>F1ZXR1z)f5x4cHF(HGKPq4NzGo(^u5C74&|zGpD1rHE3~1w|5o=2sLuN)(~aS71s_t=UeVE^U`TMo(uSWf< zD(#?AzbbM2@%H%Ji?o|Y{qmCb)Tm!x(#{(7%Vd9~ewnx+^^4!J*{vJr$&UJ4iiw?h zy5uPGOOB!*^ZL!(HP^>nPjmgv`_-q%-a}^n6~B9j+rivE=5{l;r@5WY?Qe>A;9Sgk z@phgMyyauYQSdeAF6$BFLDtXsIFap&@gwyS?=VtN#>boF$oM#P-rA9KG>uOY@6X4r zv;*VgS=xv3HzjE|G5)1J#k`Pq7V|~gU(6%P1^E0jz2ob4{AWLeCEa2Z%NY3I9|L?I z(|$wmuVVcdKbuOf|E7J7um7ffjj#XWXYI@NpMTfF=QUsd`MS;Ldo{ClfUp0i^`WYL z%dVz=_&X+7lY3}63EZ^C^2*LeMM{TK1ka{Z_GTLWLm`1&utU6$*=XI`!%nJ?`wR&7BRMRzvk^~a=+&Ka36%X*}Bd5Ytwq}Ro$n( zX6 z&TcF{wIcOTyj}l;Y~lFdhokNXAlhOd++*8lm8^wkPk`f7zNeYMw?n_jq|Bm|@QTp$wydO&c9rxFv z^xrZ1Q~2|Eo%+8E9~P7TSy8|A&k7x+e^$uSKPzPEpB1w7&kEVRztTS|>XiOjkw^Mx zg)IHELYDqnAxr38P%&*PN{N2pV56;Z|-QBCcfN1 zE7~Q#+&?R1^ZssHTvKyv=Pv3gF~6bKr$Qwm4_n$q%Q=03U@B!%r_3Yjk!6L<*MGd+*iwenp_|5tL1)7 z-j2!l%G)vdWT~E!+K{Ko)n&g-K3r3NG^yQ4SxY8m&{ zK6+#0O}<*jeYIo#zIu_bmT|wLO`$zrua^7Zn3<1{nfdaVnNN_J`Tm&n)pDO8lfGK+6J$fDJ6D%JM<#u>BAxP^ ze3U$$`)WnHnNO3~!+o_P-OLBd+vUDmkuH6;+_%W}H2Fq(f4Q$#q?`FtxlOpQmirvJ z9ZbGgQ#$u+Gw!S1{NArR*I(9yX8Dn)oB4>j-Auk^3@98qS@Q*Kise7o3`*#n!WK>y}dkxe5b#C znx;2l)0?*Nftufu<(oEtTmA=MD!*IveB8$>-?aG~^*{Oe^fz?WlonZkueI3Wzo{LzY#K+t1QADMiU;F+ z6F)ogpFPauh`6u8v^Vj1v)}OsW@ngxh)*y(^O*eR{46BeG5O8S&V>KqXE!?&n&KRU zUtYG$bK9uq^I!jo1F>0&Y$~fIur7E0MnU}#{-Dp(<0-eO#T!eAN4!lz&sAY z>`chdt~|~`#4V8iJkEi~>CxWprj5D|6o2qL&VipLO!8c2rSPUJnJOV&E|HHDT`DmsO`;TPVUy(=J zM99)sLY8*;C;8tgTctowzFvv4|BfujgGmQIW`r!ql8~ugKF0n@{&&jqb%^XC%Kket z*`EeYUgtTin_XD=(OR|e zhLj?egk1G>f2bZMzT0J|{|HbLSBmdv+0jMW)ZI^-h&;P{mBX4>#5cCAbFc^A8!f)Q zWo7zb#c%mai#&gpO~Arctb`o!u%MQ0_AAkD@S_S^jqFE-+^|qx?M&KmAxJCnYDrdh=uIKldYzNSzDg8w$ms8I zU{G$M&#;wYuzK|$LN?doeqgOjUrArCbL*B-iuEIX43w)d3=*5x73oEactL+-rGF}G zv)7UPnKfQ^sC}vu*HwIf&7L?r!>y*ZMS7FQ=OM&kBV>E+BV7C=pOD+s%FAp&#Ud~J zu1h(#=&-+#-(0N4;O=}O-_2*sCY;SKFb_f6QuaJn{IUtv1% z^fu>hSc$+hLe5Ib$M&v|7V@H^pJBgZ&3K;JQUTz;v8<3I*0@0ryIMlt+CC4wywga? z4c(eLw9V4T|3BDjz*t&>5NcYfhhNNcS3#-G&*p0pk+kNpfkdH`u7R6?c+bI{biL+ik&lfKlrh{tC1mZjjQ~sHJqe1!F%Pf}s9J?SQKy^@!$F_bV zzUx>PMo?Kh&-b`)&m>q(buRB0jJRhfBvD&ImCoY9Q2{WRbjW#e18)297#fmpVV4Ks zCi_^pOl9rgSz!g6WGFPksD*y9R~!Azf-&Qb+TngBm4VF-tUC2EGEa))x*`Q;Qhq06 zFX;X*4!%=8Z7O;~{Hrh+M7muIJp)&~17H-%#fFAJ=AS#@C*_Gc8x3jw$H5FLTcgh} zD7&O6RHQmrJ7&QdCv{ z8MHpO3TuoaJ@2bF|}vI}jN;n&0$Xia&} zJ@&;ekFH{#aYn7gx?9+F^dTHTbspRB8vR=?!U2?jY1?@0H?uCTCLJ=|Gq6eO5p^T! z)^N2!JE@hj2d?wH3_Q61gfflVI&T|~?#Xq*hsqx4`Wp9tUj#X*@88ef#5@jOFqdr7 zxPdRWb-f0S$X12Vx}!t)NSICeC-v`wx&HhNb*Y}!Z>(?uu`5hvwRiTaqhwcecuA!@ zv8zU9%M?se>PmLu!+HU})!B`#+G@^f|Gja%(>cAtq|_UUzT4Y6yuECWX- z{>5%s-m>-zvD-)Nx_RsDx)ZxQsXDtn#LhonXQvRmH%LuZ zzGT<_l@;EV?Cf9Is}m%<+!IPFZ6v$pf21hU%k_Epbwn@dAldb)>g=Y6oq=k^ zZX|JZ9~J^dB)c?Xx2w0#?m4j=yHIEMkl5|pq_cZO?2>Zd6Z38>vFnzqvwQ0D1?mjZ z*=a7%pzR5rUH^M3j5O-(p3T_{(UM)kmop%zpU$pC&Wf;DvfE$TQ;Cu6yhl3*o|fz~ z!fvT!B)i^rcK9w%pLf$LEJN+5&aPv)FMfHTvzxpA7VaCVv%5j;BAYKlCz=aw+QnnV zKXrBkiJi-jzt~-SUrw-dCU%96=}E$=p>=tE-pvlPR~Hhy(Nwm`w33RwWM@?(ML8kaZ5`DM zVxshUSEPz3SW9;K!_UCRLpr_#oq=iR{CHTbkpaZ*8<1DlagKbXSY-)+1<3a!`+fy>59v6fMoZO*f~pfUx{5|$*%II*SMjX z&TcWW3z(v_n@jArd_AIWl56Jdw&ex80mLr+n9eSc*u`h)>}-kMzC@i}2V$2Wbapj} zUEam|ygPNu9gj(N9eQ=a^3(J+v*rscY$n<5d0?-uk?ac1E~zw?>=u?vQI<<~IJy^j zOLkj`-Kj`@-Z>MydXn7;Viz-6XLpF$WjgBY+7Y{5E;_puV%Kq{&Mt`9t+BZmSe(}F z&cyCSmd>sRu?rZgv&%;8CZ1e{HEI2EC3cQOb#~#-d*O^^ckTHMI3U^W$yO0!B)d&E zo=S1a?!_v{z~hqLt%zG{En=5Nb7xmeJDefe%_DX;l3lqczSu;vYv_3kuZ+;=T|Z*? zs;SP-i`XSk*4eEjb_Kuu#m+WGXV;0?u@gGGJ;ZKrrq0fa*xCKk*%c#poh7@ty1odK z-6UccCfWJ*?1GA9x9PbRc9HBng6-9fl3n>ZB^6uA&bf4oGDotjKc*L~k?d{~yY-UY zPGXl=vRg##u1R(mh~06?t|zhUD%oWayD}?uc6W%~<_bEyw#2TI;f*+}v?F$Ll3n7w zXRuJRn@Q}3NOnQQ?viA8lGyo3cI$~}E@LQ;A(w$*u^o z1Iex`v3nrdbtZPX<-FTT?CQyRx0KkeGGn*hUuWk??0k>w?2Z$=?vkAivHK|JT_a*w zO|tug=3P0-Za1;>m+WfLysIYJ6{dM-C)v$6n|GC3Y1g zyT&x{Y$UrtVwYdCt43?)49RW&bzlRf32B^p59X1$u-lR z)=Xc?E}r(gKP9^(v}SIX>~7PV*-EaN8MNR1A@{p6#BShJecp{HcGlnjns?h5*@!iB z60x&6s!M!zv!%T zWP!eBJ|}khH|Xph5IgJqI=fZGu1uQF?hdh=DbFfriQNFX-}R!i%6PfoMH0KW@~mP@ zXO&cW&KyW*6=%tAY!y!>N}g2`hWvF_x%>E*I!m%U*uoBT$#do(#4cH~`$6Z-7V?}~ znb_r)=gfJ;F1m%jW?B=wVbgSWEs0%^pMRZIGN|GFcTkavX6bVtY~?+6p=j$kkE2-WG1u#oNu{C@Y2?g+&syN$1BfRkkR zlkNz4CA%jzJ(V-Wj^FRT+d2lGm;2pBiiN)@+2v?vhbttz7j(b#OVsao@pQi{ChvEx z>5foJ-tVr{{cdDS{f@AP?g$m-{VtR4cO}j4cUeCA{q8BTt0?bxw~1W^dB3|w?8<-F z_q!VBZsLuW`u%PN-S1Kt>1UOtbie!6O+RP4J9WXJsrp$ZG|CElN_KT)?Nuh(JsVh3 z=}YYR-F#o(6lIiTmvd+@s4nm3i|B5CSKiIv)7^Z(w|>8?Lif8kc{hJYck={!H?KtO zn7o@WCw4V`^}G2SV%PSy&aN)q%>%#b^X?0=OX#oP&3i9+2BAmwJ3`}N75d4$c^#L% z@Q1vcuX;NJ*2uegle`sSiM*R{Z{VrSmh8eZdjtkZb~kR{QuFoE@8-8`?Xc!&{f=NP zw+#3E(%A)s`eK#Pt7uJk^SWzq;n*?yStZ)@HBJSc-Oo1hxWHMzo1Z6km9icEeK)u5 zP+Z*2tGHxfgB|*sIkIs)Ui_(_RZew#jR~K1b}i1|L>GIV-HV34_;{ht?vL~CXeHTw z9@GU3Np_Q>t?+R<{axk5mR{=8V|0d~x1(7>4;->a8(3aC`xRHhmEBv@;69zlN>8*0 zzf<2JJKdKb8J0q$mM_7J@|6AT1r;mZgjO_XS&ggE{o)Z=NZjqVMZl<%9&mulu6pws zTCh&QsO+_*6j<%~U1>%4->~WiHr>07GMVhNq>h0t>rzQgp|^|LKU3hLO}y$xWgP~5 zg+eu3qe5j}jW40h?IpN_+I^POADfo&!`S&otwQQf+;{#y7G6N_MS16-V}mFRpKa7m z#oFSchu`tcbb1>xK2aODO~cC5j9SUqTxv{RgEo=UFJ@L&^5ryW>nQ($R^OCqQ7NcQ zHEJUdwu5;tUof0>yX(3f8Ww$lesqVO()}>F)VhvKXzmYsc^#Gw_ra+Xjasgvp|~($ z6E2-&)N<_lfF;X~#0}0yt+t8C$?Ns3MqE zPKYfL4E;#|CyD1FdsTm^K>hmA@IFjacR@4CQ!4u#s0Q<4EtRdl`5TnVZU_BIhap{3 zVbhRk#l^*_4St*jF3oEzgI$eUJgpgX2R;t$PU&kJrNfUR*VNXOf69}1c-pK6ZlZeD zO?(d@114fWs{gEiI3)C3hrOsT6UW|wwC>(GpXzzJVVK%uZx%SvSn9L;uEVNX2G(Mr zQ5$CaSb2Ia4GIo0YICxhLD8Y#Venw1mcHK=-WPoh18GdUCGLkP$2(AFGWD@dAS9=q zgda2pCVD;wx6BRDfY$ITV?RL77o*?|rN0^Q6R>0ju%`SzwKAYtjg!j78Ak2b5CglZ zEpmvRMenyOv!LkD-s&el4zHwu$Jy`d2$HKT`UX$0+hL8FM(y*LH*n_T989G?_C5C) za`o7Nkz@y}E&Jf|p&+(pg`C!>~{l>zE4FSTHAqc-N)PpCV$0>#c`}N01Phzn+rO#Ni4r5C{!63>XT>b>+Y=&q>jM@&pjm5kV;!Vm^IB^Ny zr?Q=gf5Rs?9nhWh$ts(Mj^$pfr$|pvM}xN3FSp7_|HI7yKdl&8{V*->}D8z6x-dq0$s_Tr#h|16T_cD zC9-o!m!5dC$0yiBa*_xs949W-KlN49u4lmu;>D()a9H4OU^OYdj(StMvN9be zQU1ES8-VZIAJB>9!awH1$Qn^_gX+JRb1yV{a~IlBS?9C>7=HN-lp=jXwuQomSDPS+ z@^6Xw0C&cXg4`s}_fLeZwWZ)I^{dt5Ot^V-lafIFZNAsQ4xNp-RGRECsCy>7ExJc- zNqyYXF%hbtEQ^uUcb9S>phcsxSeweSW{+U?)-8CJ?3{f4BE0^27HgCJ4K;VeyT$kM z8kIE^afY`!-{MUwYk#UPbQ=+m^N23?j*H_Rk~na_mxQPquZveG|70_5v%ix$W&^xN(^VyNQMS z*EKk!$5UuY`FH>5gVh$rfeXnE^5(%tWs{*dF%7*wO8vDy3rf>EbE?RC2W72+EvEDh zc~QChAsyCGey8VkVDb8Rs7LbP$+Mwfg|{%B>VGnQH(V}#AFk0D`*QRmlr4D<=8!%c zoF9RM^A?Dw{0DzU!`hUw@RRhfY?BC1qsqZS>X&o#Oh`VlOPNdkok{b0$eSE37m*!a zY|Vt3BetlM$v!V$CxY|alK683L2&vYzAe49I+bm+Fgpaqir zbi+Wk^@}XrMR`Io2Nt}ZjCZJP<`_rpzVH)zQ=P`ft8sFVXBba<1`j%lQOB=fJn7&Z za|7q^^v0gludOr(XM`-ncU1OP)EC^=v>jHVvK3pT;(%*k)%RqdnRN_WR`F_TQ?lE$ zLF9Y#%cGPed!BBQhR0H0DMiU{13bUs!8a}8JjrFFUSh3=OW-4M$@~2lPX2KaRuJnR z4NqX8g7AaNUf!?{yV*SfC(6HTvlA9M8ViF+ZXcTu=WR@aG|IDl=S;PWQxm%9?!h|!w< zmmvU7V-Aw{HQNVC74KqG%Hx@BAuKHQMy$ikz6or}{sRq^ez{4ovOIq}9-y)DIs1Kw z9n%b2L(-v#eHV3rl|g$&dCrDssi)ec-~-b6bU;^(>+%_AkUl+^dZ0Ec0#}iqYkv9S zly_Hg5{=cON3Y|_!iRAO^{c_{=Xi9%3XG?+);3?TPfSNlBD=9GDY)75m%4=P^QnYE z>*3#6Jx_M?nqbgcevEe*Pxjn&C=ETjJXLB_{^y;)BUEnzo+Pg(f92d+Zm^oTbT57f z)0Q28yfim^Zas;?34zdw(!1GuV!KM=;7s}b8V|;~p)mj?JKQRS5xJ7Uhw5*5ak09u zOcoR))`z}Vb?CIi!0bsM7q62_t!)|bl=6G_tP1O1CV+wDVNO$Fea`m~O8t7(b_aY| z8UnYezg2SjL*bi#ppYGY)_DNRp6$?`?6bc5d+1wuDm~ip?a;wEidalILa`0U zJ<*By8g>OjrKpoQlVs0;{c!E`9h^aVCfm8eY@643gW9c^)*N5jjHa^M

;F(*tvntxoj)jLWul#bA;rw@blcgEQ62 zWZSD0n{&Kt8?_19e4DdDyFVq&;WDxC$eWJScRWzqQ-1fX@8~k22}~t<$@|whe#%0y zC8o8z1Yy-&`yrOfHc2^!4-Q|3gOpzX;RYOO6$U#f|C5lRI3npIR3$lme^Kl=`xo?~ z`dtrtsEHAou$jhKzO08Wx9>KvoutpeA3n+wntR!(j}KN>1YGnJzEa=Y-ku0|f4qkk z)UQvz+hET52hffBn|R_pv@dx94v`%WXAgnpb$7xdD!a(;9W>Z79fGOsANC3G_Hhje zCKjdIWWdm&=aiyk=Z&6p_qpEJA&~6vFeD42b}vv1QJ(r6lECPkU(C&VJ7Xc^vJ+OP z^cg|n&@ShCjG_F^BUOl7d;+66YrBI`&i^)^qdcd+ErwPVUg2G8_shkW@Okq$+(`Q1 z$4KRleHz{;J?nesP;B}dG#k?Y@|HSk8C$v&QNJp=eOGHVOT`!}yJy!ZSI7NxSI z$}Pu{?l15P*+;GAg8?0G;3%@2d-bcBoNxr2kUbqwJVWQB7RQ2apGEI)_Bl)iOJI&S!QTNz3Dd!PA%Q;#-;o+PKf zd4u=9%!5d(fBK5MczX6;7)NE32Asj*ftMhY$_|;d3D3ra0#g3iF(Wao)JG^l^5l6X z@!Ok3$Vp|ht=XV<-I56n65%!VeP!cu zF!n_>0NG?%zO9fH^$@~{S6aVw&}r;N$WQjiC-))g;x0HxWowWi%*X={OD|9k%-)f`SWg;V&xdacC)guz87(solvl8F)PV zio>aFdG);#e=ils5bLF#{!j+BHE7$2_0Z1c)SB%L+Ii~N`_LFQ^GGVDP}zh-tuW7? zuNXsi+cw4>53P^HVPv1SSG{n~%$pcRcAFZdVV)7ka2eS%X4g|JF?S6%ru+>8;xI9; zH@cIY*eV&n$6Mhf;!<~C7H;o5OtqtRIB}Ih8@zj)!+1&$xSx(?nqHw_y-0r2Vex1i zTNj#;{5c{DZ6`XzN~%BP>OFLQw;MiCyPN&a;v?$-7()64=h%WR?>vGJl>bHY7<|&~ z191IkJC?=cof6>!^=s*@9qNH@nXrrc8#~{R5_rZ2;Y=?DAFVu%Y60r2+Bng)>f`)h6_u|I4cZ@Mw=vlYr~~>Nv}|P0c2%R)n9^yO zpX{c7cEFi~zoAC*{^Ltq6)8!-WeJTSNWYu@&=pKZGLG z$L%X7;PhV6z}F>1l?u4-_)nNjHhDVufSN>i+DgQFUZ?GsLv|Th5ZU2T#CoMmP$q1k zvdwE0hgV&G0bdVSW*ZJC4}AnbVzKYeMmW;=F~kz1d;3qr@zhK3p6m~E?n3jRy-=0% ztRDIX)I1A--&Mn#{DAIt8bc9EzgjaL=4IYhu2BBM^v1CI*mZ|O#H&_T7TB!rq28lB zbt|O6*-QiS^?zEC&#>WIH*_O?@|TE!@);g@nDiXJ<|_OcbObw*{$~#RKy;29=uZ85 znPUaKFY*HUzSH?t2e{t%3+AA*hll=DM!ZeIJ!GH9I~pjFw7{cd=&nol zoHi>$jb4_9RmjfPjqNaRiSM|RG?u>qwI znih_O)b%)p@-HkDiw+G2VF!{Q)JwwprwgJ=^_Qxfg&}E+)D~3MYP&(3nbg#w0_oGm zH3KU=IIY~L{BEZb&|`Qtup+tE)pt0^=}(BEe)-l5!Q2;iKpgeA&lo=}G1?z0k{w3W z-Hw%A9{{617WiWd9v%N4UQpi?6Ds4b{6C=@mA%{gh}!*B2Jm>iKIQTR8nzplE!lrr z&6P^+{8?~|%Dx*=1SUrQ0)Eb!K57U!E{TEJ#9~2}4G`oM26Kq@(YB``Ppd%aL-OUe zL6FvMKa8L}6GziK(0o_mchwlT?@;zjGk8XIX41Qn;d!Xim)fc_j^=geC(5P5v>_KJIYCeZaT~}f&>f@#>*T5_BFkYv=UnuJf zudZLihg7!X>6OqU_jAmmvJ2LAfk|sWV+7gl&)VtA(Q))9Nw)233rfx02CXpJ{6kh` zVC9(x?GUlpe*Ka9>q{Ccl>e)9Q@nfsJI*Ef~fAC=nY+gy(3tGp zJfUsi%#8-Nm+W6*uA9=RYZhcu*_s{&zUkciSNhv zC!p366>gGzqre?_5PSgkQ=Zb}Ucv5Ji-F%&+Xj7uYsc*20M*%gU>YQxeXhiko+}0z zSkACahcwb*TwQvfeBVIrPyLE0mI_aN<5hlNn|X-*M5Eec1uDC-#S3uWwj3kLK1+XG zhcD}VkiUDMU2_C>EWV26$)42*tpdN4XIPBvR-$DOn0xILo+Y_gN;b$An~blCi?`NI z@qL|z8;EtQbr^VckwHtQvY(6GRm+jjXdvZZda)6nbp3$?NNyJAf?amL!Jm}J_+c;3 zu76j=`=wvFgx!Cg#`jdG(e5#RPuhs*DF1z@k9c9!2;}$W;`x4|@8}X(hRWtVl8H5Y zuUG9!=a+j7TAmfNT1HV{I#|P>3McWqi56c(3@;BeeFZc za@`8Q$W~5yE@FcJIrvI8Jl}a2j;Rw2UR3r$=~-A}?OS1UZEbCAcQqdN5{r;L0cuLN z47fs!t{-*{tg+g_@{_!4!*pfz@+`2UJT@1tAuvH_z09T`%x)3~=~U<2M{8l))+exo z#>N`=`(9>~^PJBy@^$M;EeB z-3m7$thzTM*==9yQK+a~!Kq}=8QIoAmDs0Pm+~9l_k!;Uak!Rbj~BUM!q{YVCoTtC z4_5A+$iiYYH?wN&5A;}R&>Sg!=df$)z_aN%kMh4ws)v5{n~dNA>^c zy9d1|+{3&yPS%YNz>q#?u{G&)qI4+M*svL2Q2txaA22*=v{+j{&P>D+Ez972>eu`c z#MFM9s#1ST?=@)6dyH(+p6rk`B@;XN?@)S@eY{sC;=){IfWN=xS^NPz?i&sHscgW- zN4WFNW^g4t=kFJQ=Z$A!0NKAp*ls+KaSxtT*`%#=aNy1;v6hbOUms(O$HP!!v3So% zwduiBpkJ&=KRc%%e0m=X4~7_-(LE={dnQBHC?kt{-Ad{AFbjOA7}>4tNr4MH7?{s^ zBMUnDT&+_*4d#wBvVagxr~>$ zor12jjLdayC~m5?2}aE@vah3}aS5I8?PeO;IQIn1(Yy-xQ!uYR=~(T=1%>=dEa+fJ z;Pf#DR$zpY-M-XIu_7N?S!!$7V=J()kPJmA{fJvg;3Ao4^391#_x@Qhf%FW`Ulcq? z|ALysjjVUvSZELu&Eu0<=T%vYBaJ2ivpkxoiCk68`-eHFj~(%VJyj2?#985 z;9ihOd2Y>3fk!`6l<8Eqc~b+cSFf~ULv^~PWI=FkJJpHWYE>^8MozNA(xlJZ!!hu# z!C*X2`Q2D394oOI$51_|hWkU3tshn;+nzbG1xBPj#8YF8%;lUBB6G*!uAxTuV4*cQ zhbHm(Waie1BFCe$u;VZz`&HXo-PO{d#f~+yvl9~3g7;If(nup~*wqnR5BY@IsQ$YT z*5R|);h02a@83L)70+BkE6QUm9gNmrc47hI)vSCp`p%w!gQ?DD*?(cSpT&86G7D~) zh3l6uR6R(CjpGek_eEzM){$=BtJ8RwocVehTVT!VJXr- z(I*DN=}n5WYY(9?v6RlvewaT@ZlbgMbZiUwrt9pMo-)FNJUY9*^Q^R7y< zw>rCeEv;1#Vi!m3I?hN?J?`o3>>M3&=wO}QwnyvG>y^%~=k3#Y>eMC7P3+E=3C2#J zc4B^FXICK_&rP3zgNWS=Vt4PG&aQByEOeW_P+djrmJ>V2eLA~(#O^|r&Tf6|7p&J- zXV++W1iDPs*}rsmo5YWWCiiuAD!t3)b=BGBTTJsVMQ8U4!=S&T zCyXJE3B>NiO`Tmhv3vDSXE%)44aujot3d2ZcGcOHCU)^Nb#~c_-K*w0yBta=*p|`R zq0t{=o9gUrj&6a(44vJgV@9}T9fLc`ZX;(~!vPb!>Rpx2lHG!?)~d5)_ueHz%_-Tn z>Enp=2kGoaK3<2@Uh3=~-#Lx!q|Po^xnT5&mFy};g-acSp$UW^X^Bnu8NyvH-Ct=I*QnRqIvgvX@WZMZVFbU zIW^D85!Vg;#J}laZNk@KgUE3HO$Qry_cUt9b#~)zg3y z?C?=%w~g5S(MM-Dh1i8e>Fg9@*CIh@_v+&poY7Th_skf94QA-B>ttl``=_=U`DPI(lM(FHTrH+Mi zcXf7SI_`kp3v_lx+ym(Qi!(5g=Gx+`VKBF=CyXZfWpEr+P<3`ciCw~@6otOWVJnH< zfsdt>3N)5361&DzbaroRCqw1}D=bN4&&n$Xy0+5UjkFJiPc}NcLxcPwr=8BOzt0vp zVR$6i6***td--&BizZvcOB1{7U6lZ0*NN7*n^UaSo|0Y8wF&CyAf4Tf!H&3lfX=S& z({&j0TxXZ#{%LG>>=Nc7zM~;@{z{;~c`1d$$#0SL1iq0+~&weat69g_ao(E=| zjV=Dr*&XRr8B-;@bDaa#5|8zHwd;tg-J?YVmFq`23IZ$J%}B}Yq7(b zW1(1(&d#>;4oG#;*?BGtfaO1Rb`P$F!Me^myN4lh@a|$S{w)<-GCu|W2-4Z@A$Bq0 zI=kh>uF4`ibr7}HiP$Y%th38|C|J=Fv$*xtSNy@#xI=ccjio%KEI=ije$3e+E zI=e4jcEFi=A^bZymbp9ttP;-f@8DRW8(|R8QD+zMAPyd%*V*M=Kyg`DbatnS-OC#~ zyMDy(&viPxbG4G;(K4M~$%8SlywhN$@8HyUpvZ)!LF>?A`?R*_{-uKy#|@Xh*!>UuXB} z`8pi?OlMd3!D(#jdx?Js$97Z-M%%YKyO~v^v5iq@SI6oX=6|lUn?USV+34=%~j z&pK?Nadk^c!{r5ac6QNUaOi-xK;OZ!I)frGV~);l!aKw}t#o#fYd>aH2!eSuo@=Je z!kNW%cCT1voKEjl;;hm

|bx9)CT-g_I#3bCN!#1#9#H!!QAXOcf z$a9o2>w6-exZgU6+!ZQW_yu!qiYZxh*Btczlrbl> zRmiow(?Mi6o9SQk0S7vTfeazqD>93*MNA^xbn7ZPXv*O4$1}lbiyHT5rD~O4j~KFw z)^dMe4@c*tvtY)UE8L0pE$DD-64=&uaUBgW(8-K&P}CT~KU$^;di!SpnCtNU&KrT% zBx~>)Z@~{e><*bH)FHphftL@O50<9gXtaz6A0f4b`oB|1itbl-KTU^jdoN^U<-y0D z6ay@G6J54)#W7g{*K`7yr@n3CPyZJ z`NegQvWEm^T@ulDjoZ49g+fzD(pj^P8~sNX-e?DruRfaGu2t1&lVLOo95$>}=SmU^ z-LjNib~vjo-*8qmxhI>1tN1azzgV(%nV9r%;+Xu8v+y^qbdqzViHX}@f%9&}l1{~e z?BqezUmvA;!S&SHsQKebW}YjVKh20W+G+?-a20gB@JvAG#!?ZKWAxjgKL;H$} z{s|;mjz{i&;=(=9cEE_$FJUB27 zrp;QwB)GKT*YiRl-{Q9REaMW~em4QiQ?He{yqJh*%*zDhbQLah&AO`DU1Dk%S8-o; z5N8KoE_5CQ?&(4EuekFmQ{&*?>$AvUgBS0eME9`%&P1D&JouSA#Lzr7 zToh66$h$qyhRPF{Bpa7o@=CT#VTxBe&TpY@y<;)NPrZRbS%rV+I}0AW4qId&<@ z=sl=CYhktM)tziouP~j-S}<%^U}$rAx{{Kwlml^BaWkpanvo+aZiRJ8}DXAeylbmdE0H-tfe!FvFmWs80x}SkBK0I(K9^d zlqVY;m`rv~D#YLQyx2G{i{`Q)gcEPMvR=Q$#KB+M1PWjx=RkzDO5a4qX7BXdHP7-dX_IS~;| z`i-x6PErWSTz#zl^#hNkjT2y_cVWq*d8YXCpiKCfHH^d4YOC(Hh+%$l4yQe>ABy~u z1^Vl&xQ}V;QK(!B_|~;^Bk?0trxyuhT8HyWi0)TD_J!@iEFb-N67)Q@h4Qmze4Do` zd^#{5)Na}H28(IDM;6U1A$I4FY>$QIn=c@nHMFhe(_xroHqtrj!7F8mVM_1{(Va0) ze3TrmeD>s|G1(-$m$4}Fz(H;4#Av}o=BU$2d_aE**?guy%X<9AI=knS zTvm-;qHWd>|Ss})K8ZAA2b+pzaTW{{Sriljx_g`H*}PMWJ<;>vta*6ex` zaqHNMiMy*C*e^iD8JXbe&C@q(zJ80L`2cRXk1 z0%#0;r`?}Fgyr($0VhMrr>EBV=;;hdUnb988q{CX_FN3%l4V@#tM8&*lWZ`ny1;EX zxfX5PlmZtWzH#Bk4QSw>NGQKIjQ_fSFcf_9qifs@?>=`TOf^E__-hJ3c!UdB8EU~! zS9|`~k~#2OR~mAy-1(B1F%V!QLAGKq{^PDRAPJ#p@f#0bG>fjUOBae3tTd7^oIR?8WxUqe7ZRY98XI7!VfK3^mMHEZMAS-QCc9BsMi6%SI#x_m%@4SV? zIQT7^ada@NV&X%_ZX5yc!ap)N(~{iHFoAoIPB9sm)rgP2ClI|v#{Nbp9=kah6h5|V z$A%rnX)l)mn{#^q(rHQ0(-FmUY_vtIv9nn+|YWG=;x&#|g%q*M=*X?06DC z8?qZ^z`4zhuVP}L>e(e^p6JC7&`*OELl+}?Wlz3!vKZ>$?ibZ|JMpLd#NfYfv&1IK znlIRq1}(coap3Za{N`sdaMnYD>pWHY;z+tSV0vf4GN)JeP+?b?w-+E?djFLwVfsy59gCix;} znVyU!?1h-Di`vOdQ?$VoPG*pppLdz82Z!*B@qy7n@F-Un zCYHMKFBe9GYt}WS8s^30b4$UR)-=_0@Z{@hzrFeFNzt8fXMWLAF-$y?BbhtghEMFD z4q}x#SSer<@318nhVd7$m;Y!!gvQ~F$dw}Zilljc3s-n~eLV4*aG%>=F$vT691Z2r2}WIN8^T4*Hsmxz2v$SI{!0^loePo$2DuK zp0rRCaCjTzwZIhbACyV1yWC++6c6Aw-2~Dzq#w0FUvW%i2sxyn%63(#k~K+F$q>_t ztZb7Rd22xTu#~OYJzdj?_K}g~akUe>ac?NWo}Y1(tS39GH-W@y?8nL}bYFu$mkST+ z;Qs5%3+}CDpM@5i#w63&$`%pG6 zVI~>oJscivZe=PN8-k7*!iM=3%=Qc8$f2ihaIQF;sVn`9`wq>67lE?OiYI6AN^u;# z`}sz*;;j$furVF7+FMHl6X!}M>=VPl#3kGr>uOP0J&hm9J;_~<%0w4NFNHT*AGo~f zH_^!ji{VN5V7~LxKqwqE3;vdC@|Q>JfO5M%Ji0TP&+u@7>nA5b<8k1>ESLo!rwoMU zGu-(0{fnVj^9H)?D z>g$IAzB!ZB-gD;UZJN;ZzzA~DdvobYjZMg9Su#mn>Z`qbgB;?{Wf2l@!o1&9Q1z`- zOfueYW(@C6#9!uRlE=lh%(ST`c+BktGNiPR8M&kdkMRv9Yr99X)rO;p)Ang(>uh~i zBYz4>&Nid#=XAfaZYmjRuS)j%JF)Z6h7jv}tvKht2irI|fkZcPc*Sxrb~uws?r54| zdmndJjgG?|q${gVthZ+q-ei&bc{0d#wizq?I+>K_Z9u-48MgdO1j)Si7|9JC&dTTc z64}#3K~AlWXEaG+Pb(c)Z7P{v7GCzv@Ht(E>|C0?74~}us_mfb_W@>#tG;^kWHJYd! z4QE6Oyv~RLFh(T^G*6A^EswF#r{f4;M@;4`hS@`_x-J;$0-xs_2-Duk!RuaE-u+1w zG~cL26K%bCrE95BSicNC*y_ogE=Fs~TULU5$Z}puICtbR+K~I0)`-nTdKBi6{=RM-$X?&8ulQp?`Vjnj!QV~2( z%^>IQcyiM&zd-TJ!pT*#w^XBf3%d9%iHr@l(Y9YS9LdIKk)L)GnajXd9sVmOPlj${ zrUWuL`B)~o&~t-Xv#uELj!GoWdOb|x`w!U9HjGGrP+_<2QXwa*rjxl@daSy&DeTz5=fHYv()pkAPtiVQbN1Qd6mlHrp|s;HD<+Xd&8!jK(^F)-chcw5m?5CE zzJnAvedlZ*;?fjqmFOy$vjq~O9F_)(z9lp9vzcgnHQV6#W-t@i@_ z=t3F{>1ZhJ`LbS;5F&;P8DX5RW0^>i6@$FW5w6@T21&`Kfwcb{ZuOtb$og|MY#%X* zk6O?l64htJg|iy`MoR`7LY!d53==-^A%J0y9vt3_cqf+tc(is9{60w6u?I&%PHa62 z)~5TFj;Y|YHy7cHo_sG|KWVRjAxg?~;aAp(;jxUqB>RIcf6y`mY`;3;XAceeEoDpK z&dy`FIBG1v*(DeZUUuO}`UCjYk37KEU@VzC{wejqCUE1uC7HdmlKho+I2PA* zXOd?B>&&ftyYSHdNo47%Zf4rtW;}BILK1LaneFHuK`P&PlM6d_*}JbzNW>URGQ-f4 zy|luUJe#UUT9X~w*oVPn+r17PAL7AY8yZil=N!SB1zzmvgbd>3X@`R!xwGkX-AtWR zl>~_$*y*#giOjJNq5(I|*<(LahORxYwXru_8u7;CCT+=MM}oGaDFj_>f{U zb9H+o?q&O2c#T3mAAg0btr1bH#~Ja?BZWkt5mSvgqG|uQ$nW&-(Hm+ikJdrPb$|bz zs*2|rBfi?}qw18qpAm0uW~-HKL;buP=NGJ!>KNC5FYKUoDpb^nznAmZF1C7NHk{KHUjMyrAn!MR0-r(vsoco@6;+=uf#)Kd_ z!^J`9IppXyUREj=V#FsF43Qqk6OFiecz5Y|&PwX{ym9fA(Z3yxc*_MRIlr{45f5l@ zBU`$78?o4vA?{TsPe^?mC1P8TG_H5=8Xywt5pOR?#+%k3CEmIvrNm{uB<%X(b4IcF zoRR*&;%bGcg5Abbd^u4i%o$?DV@_IWb@p~Q;#E%_v?Conjkvb0t7d!I$%qfM^wuu9 z*cfq{YJS?|t@tf({E3z$wH%pIM*Oz+ByGmJ03-e#HBB4XEZ)%X`WM04q5JO)Oj{=e zX%m|`DE-+JJ;!S$Y(k89;({UC&=ZM9Tq?Y~Hu{{Err%T4#Z!y><6y-1&N*rI%D5Ww z3~w7P&Bfb@$L!8fg{$}(@trqO>SODXM%>mXK;^AJ$%vD;#+z>*MXe8iPcl>7(_aP~ z@!$OUJ1&qvL=^EQE>+x?C@L-^E}c1GB~L{WmjY58C6gQV#4_KW<4} zQuf%dyi8oG>@iXnz&^X4Lno(6GTG!lQ7=rH$Aue?f z!}mlkB`yUVw9U89(jEMdDI#oI^;l zi8kKR*J+aW@Cb1!7F_Dlowzg%xUFyX#^6%^8$nvyrE*4pcI-1=`}}K#5jR;fL|eFr zxD*22H&nzW+cuussMo}$+)tdez?{UTBHe7X7-!;A+2{<6#l)rQ7SU>(7jemTcYw+V ze(O2US(#uy9YI`jte4_mCgp$Ul5O=6p|LOBIFl%P&Lb}Q##zZ@`-w{(;7h6OO9$Zr z6D|;!&b9ECdEAIgxvKcdP;gz(;XQEsg!Q!^2g8@vZY3@ifiJZd#HFL~CCj1YOHJVc z9@WT~Rspx3g~*p0<2+khG;wJUd};n!;?e~-PdWT2ajDJ~Ct0l&aVcL%8)?&sxb$>y zh8V)WWO^SZTCp#c?HeFku`kU_jyF|iU%Iv=B`yzhY2e?!O3h(kTGcZ^Ev-jf+I%+N+?Rdn<-rv9?Em1> z$y^~KntiG4rbLk!YZCqc#_qS01EPsb(_T5qC*Zn%{egq4{K3BT-OXDbZbMwUS=vu} zB@mY`H^q75Qshf*-~n0eOEck1*@hCAHo}*z#=SOtX*+yL#*!~>fG_3#Nxl>TUs@MV zT-v$6y9@%q^&G0V_mmT!6PMaQcapx@h)WjmrL*iy-Hv65v*pQ`n&pfZ$34lHdL9oD zdDxfg?@llUvoDQUm=c$lxilACI?iL<`#d4|E>iNP(pwVMx@E+rMhC3464At^FDVXM zdw8XuTRHerB>R$u$y;mQnz+>5-cQ?kmALe!=}0YqDe@(6_|mDP#HH2nr9%UVON-%4 z6=Po;zBC@b6seIf&4Vv3`ANRC9KPhZo4C{px-STR>p9%QS%8x8N@=A^aBPFyMl zUy5X33XjQ9pUV@MqO(VjL)|9bD`EuGzoOUoi zN5Yrx?jT>XfiJysCoWxvFRjT-zVrsT-7iVLR2H}$%SXO+0lu^v=WO+M9Cmk?7tRou zUYI=P?eD~;vk6Y}VsYZqVjmm%rvdrWhW#1h6LQj@z4jqW#J3_YB@PJ?$DC=5Q{UrF zM~~1LH=uJ$TnXmVkiUGXN7WFOtvhka=TxFfokv{C8Ed62IY3+*3tzg`QkB1gPxnOLbqzo8KRyF|Pio6!*ga;L?s9A;PCOacTX!L~)CKDL;JaI{VVL z*A6nHHThCa_|nnS#HDYT=Z?pGPRFY_d?|M#acMq$skI$(sU1Av5&KeS_)^S7;!+%Z z>D%j9hA*YTmo6P4UpfL`>X${nlmcJczl*rk9k_LiB`%peddl`sh)dsJILRv(#HB4= zZDihh#HHQGF~+ek^~e=1DzGnEo(&K~Y7v+A9!xL=urKYpmlF4#=iUqc@}(H75S61h zajDCOL^XOjamjbTmA09EsW9dygWHfVEp>3!+MXsZWx9H6McNUUMwRx{j$I=z?Se1u zw9{-p_gIsr5&S*OZ(wVKWmaNU4buo#gH%Ug)i;MB40{?FWH0>mn;r+*It9) zIu?_l`-kAS9@l^2q|LS@F5T~HqdjI{%6B|Ntz=)iZ-w70_Z(^5e_sWtm|EmZ1NY;T z*6d635B+M3y!>`NoTCH?y%^qjX>3{lJ3mz?4fRS~Q$_3OirS!q=c zkuQA)ZvN~`&C0rJC(aU=26=gF@7;+@H!J#SCk_*rb^^CU78Xv)BrYwu z?xdA2MqG01WTVY!K)w`oAVVFkL}Q%erzo|k6>;hFhyXRznYfgeC&4_GeW{^HaWDN3 zU%FxuB3`mDg|EgKw}R(O`>bU47~<0PHx4qZ75P%ja;|bGb15(8xpweP{k>+}`N^_3 zh)ez9ONB}kmwLdL3bQX&f-gnPBQD*82Yl^MzEt^Ukn}!CzH|(})R=uKH`Yvr*_U!3 z>@M9;5SJ=-_LRLJ5|^r_ILUo~Tnv1_b+M7N*_Yx^WC&aKrM7va#meR*jeDZv1H|o` zXt{^Tw+-Ie|XJ2xA+j2`Q|SG3(auk+ltf$_3tx)0BQE*Cm*%oB3HXxLbmGz#_)_@JR|c2z z-we{O9wuKp4quY&OF!UC9d{9zj=+~LoFFb``gm#ykBCcQFP*gN7R05l@FiJ~xYXiA zh7#;c&vHkrJI#qpMK1*?d-kOrhZ4+#*q6d`y>kD6ob-43yAJSo98xAkOz1&l+z`x7 z5-|qr_a`5@mij<1ubM6fx z5SJouIpI4C$(Md~wvq1jy$$Rt!vlW8EA@8?{t_jQwInXJ2o4bA>k^mDZV9HxsLAU0 z|egLt6Yex+Jm@c5tFFgF^ALd{}pAW?LADswEUTa_6q9({rXyPsUvf# zf~U8(PY{>-R`AnGqE4aTa}T)P%}rcN1(!zcC0{B8Upg*`OCRA&-UG;&9>bT8TaYh3 zf-fDlCSO_%U#b>CT>1oG3Or3*8qvg4oArgbll{*GNj6GiqA;?jBeQWnpb z@}$C-S`wGsFvguZ>tx*D6ywPX_@@4BCHPYCP2y4y_>y2>8U-$`h$JqhWBt8m4RPr! zJYdAD6l08Q313RtOI+FmUkYbmDhXdo*hySE3}32+^??4rI(PMyhwc%V?!uRHvM=R@ zFV$u)X|WmNjstP2NP%dPkA10Ta)9W{zSKNC!8DV7Nga9>cZq#z*Wwn0=@*_Hm;9)>!3|+MO?a!F|G!WaTPJo?Sb`x{%m{r(vus+rC#u*`lX3W z1Hh#|TwlruUz)Luxbzwxu(l%kk}G_v+kWyT%qKNJ_NAgrhiK1s5|{cM?5;%|CoXw* z@zk>J6PH3$oHWlrE}EXhk}ft{68lo;*bMc>fyTI#`Jz=D_NDqs0cvGU;*u5SOJmuW zoX5U$zx@wi^05sOrBF-N|Ci69MDYb&*W)9RR`N(B`O*%ozpdDpUcr|>a!ufhhqrvy zgt*iOxScT*mo7FNDJK*pU)lvO{WwTm`iU{FU~}S9Y2aoT{?_2qIrvh!x5TAc@TK0_ z$(Ncg9wL7oATB+CFJ+x1E_pTgl<^;lOYiSE$y)iymmYyjYj})%9g!hsvMiwe~vC{HK5|=!l zJ7}HRm;Ro6Z*AtSooY;6`VQQhf#3SGWr5ql{KTbLaB0;6@}(T`rLj$kOZkCY)z@#0 zF>Xp?kT&8IamgF=krO${m#h~L(Xt&PE-l{EU7LD}xRmMPsrjc9m%7|`(hlV(Um6E4 zyICFM@D$Bl<+$zC*Fmjr4-QGII9sOg(e~)W_$31_n z5ck-Zo`xifuIx(^>$nK^rEc#~t878OR0=hLZ(I|I0B$FcpPqvyd@1`a;?j8d(ji{Q ztpbT@c$p^l4dk=AG20Y*>*O&6^HD;bKHN!kt9wRQfboZ3L zcZf@0;Y)9RyGT8UM9jU5@!Z=#E<@~NUz%GeTC4)U^?Tkv2oUKth)WIECYX+}FCB4y z9k-8t=`gr-jOX47@PIJ(rDZDhf_A9!cqxsT!j3@gs z?&|-y0DS4zP2$o3_>wjI(oAq^SOjtD4(fu7w-A@~y5NliDF&B1z?TZ|B`&Q4RyJH; zDgj@*$-eX(zH}Jt0sVh<>gK5h-X$*mhA%z)O}-R_F>Vcyan<88R4n__An5)|Gvd_N8o1y`^t6;!@6XesbDr;!-u>cA^OR(kyVPTLf|G6?|z=YvPg{aEmHOzSJQp zNcuk@E=EkE`m7ERw(LueV-rk{>`QZUr^HodUz+@vFV!v?q5^u-824a* zqMC)A^ma}}SZQsKkT2zb;h-J%CN9-Lt#TLFD&IBr*6cipOS{VXY1K~>mnHzW3Wdp+ zLcyhmhlxw+7~||(5SJW*+qwbdOZk(6w9?OsOGn{LrLZ2*bC?WY%6@=+srKIP+BobH z>en}TdTKR35SJ$0bJ9-aAzyOC+}nqJ=|W_N@?>8s@gqvzMJ--`cJA^3HM$OsapC?6 z=1%NO)pPvYmlkEN5M}$)7giCm!_b`JP@^1 zJ%?KGr9M1gIs;!SX-iy61eeP2+neM_g(E4>@MWRI$_NBT{ z14IP-QmI)9rcCyw+^8|5)=cgHb-;3rUh{+ z6t&7(=gF4}0Jrtvx1Mt$_|j$er8V%SpIl#x0GFC#k5Ip77kuffrra`o`k{B9GMF2k3K@_fk#bK4DE6W9P>+Qh!J zx^T4eV_#bTI6z&hL0meuG{Kz2zO-xnYj^BbXnLN1k86L&VTD7)0Mt_TdlcrmrQw@; zT;q_He0G$4sqae%xdC-~{rVL6Qb+bByT;z~mnU)QZW%wBbe?=^tH(&WtT=ILFt}6+ zb$R{StMH|worp_4fZMRuw6}W=zGQWsxKsc0A*B?$xFy~}nT3#f@z4AZiOEg-FG4_e7Gd`@8U2M5^; zzNxog5PQ4jE|M?psOv44bSEzDhA(YQA}%!nmx4?zY~)ei z+x>=l?j`o6Tt%aW9s81c79iHMFBKY+U~0o-++z7AZUp;M_+P$MC3A(U)tAP&a+oi* zWM9gLa{}x6oWTAx2Q3H2UA=#nm3GzE;v9?~=K^jyx)YZMz?W9>I_@`o>1j#g(syua z#vbC*Wcbp;IO0-G;P&(LOJly|2wzG%KwQcWE@ii%G43FIX(!jcZ^DYn@*q6q@mwK@;mB*Qr&V1&iJrW9&->apt5S`;s5doP>MPeCbMffGWzqbT=fye3r+!*t#k1 zW&hzzWiel>&At@93TKwN?rp~0`wh>%>wa>OpPP{{Rkd@KMRATn$D$^DscsMQC4cP4 z-M>b@^cGyQE=ImIAHHP8XHGoeOBdtGmn3kzyp4S6G`Qq=jJV_mUuvF{eCZ43xes}a z`wd?z%Dz;-7it1GiA#1kC$Nmq2|U5xSASQUFFi%wyBOEKe_+03&%SgV^QArPOAlHl zn6TzG_~WR(iR-|=wB;{f`uJ^yYRJB{Gc-}9bA3s}7&n*4xSk&!v>m8Z=zX#oXHM4e znUlVCy|uUOOP1J=>ySueTnM;yt2p^mC*U?bjC`pRd}+`{;*u+H^F2nslnO2tIZ9lb zgSmI7?Bq-C;8GZKDGR<-l6~nLe94l1sqPCWZ65E(m28ha6g~^L5cQ=L_N5v{qg65X zr6cgA4eU#odL)=9vo9^3_Qt*MKYXbi_P%zrFO9>QlT7xdYp4ly$?F}H2cXHIJ4%*k**b7BWyieO(_iZdra zcn@VJ&UD~xhv5&UFt^1V*N81~=42)NQv84v_hSF>rIp`Th)m?CYwFh8L}AIkWP8L) zj^$eAuXG1F74g_jWtLmrii4@)dlk5&Kd}_|jeWrSVUkWTBii_x5UI zBb$TYdY;X2PGB~3$p*gEl6|S>qX6-ked$Zp1XF3=+b!+#Hm*MVk_IltaDC}4=1V2m zmm01~RK3}k-k>H>n`;90s0-F>M!s|o=gxvI(R|4czJ&fU@_7bdDw06H)E*x2k!u3_ zJlAa_`I0kyX>Jm6$pg5RT|vII0$fUsBQB*v_kDQ}WjE&D^--tL-}eW6$(DVoPA^aG z#7&wnJ$ve;#W0t)x3$q)xp^BnI%7Z1<3Hz@Fkh<9zBKYlfHJc$9dk`EKVx5V$$I1N z@jv)dT#lLQFh0ks=g_*{4b`s}txZ1uDxmG@+R3e7bbNymEZIKxo(yEJ&|ggyK4r`i}E?7n|s%zG4AiR?Uzzv;@X}u zMw?wLe-dFgXuY%2v$V{1wv}Rd6bOmf`ZlY-(f5RO5P?@(oQB z6!qJf!oFhZSDJHfetKG1#tt*?*&LNiUK!QRh)cb4l;C3Fq0?B|&Sr}d55VtaowF=r#3|2$Ed6*`}P#w%*H#*H!u^YB~2c;(MKTiB9%}>5aqgTJdZ(rT%Q* zd-mG=g)NOZ;@)SKaigyhTXx!|CfScM;@VTHsNf}ZZp1M-IY$3{nf~mlCzZwXm3005 zmz^T4Cf$Ez8`G?dd}))m2fGm0Ms`2it zhfkC~^(Pqd_IkmxL&I$bPclp3?5NXzgFiV6PLydyrW*Y)FIxb<2jH3!f1A=-7Hg4T z)Bmqr;wCKx@iY5Id>7PA;;s1hNvI9P=ePC3gx5~$lfOChcg$X4w0SG=y1Ji8b)NWu zeA=1(U5xA2`)g>c|F|1*N3RxIx3Oi7xPRF`THPF3Ms6x-l-3Nt(W&QV5i~_RI7J$9 z3+y{ra!oU^j($2-TQEMm&~K@Qv)*s;Srk3);OVb5i+F6rN85DJ-VdhF!WAy zuGH^w`BqY^FQJr5BUjAv--7es}w)AJmMpqPD z_R{rF9k+{W_*{^FeQi{l=rXCF5jQMhD|?I}y?mO`NG43LV_Yv>y`$V!qlghVdh0Ly z<$h@7Irr3f{FcQsBhD;@Gr%&-!14C&V7aVMK?BF7^{2>bHJdB_f91~_DK9sVG~zM? zdrRxpzl^wQC;T4V_HvqjkJn~Lx#zRVh|@)0*(Q#e`n zRPJ8%dAANruE*}jcQ@!c=M8Yv9`+|5Zn|%)neVnXuG=4atG>;l&v{wnvwI^e(C5Fd z@2;mTe@-#(dH=`GJnlNR^D<+c>FC1$+uQjwcT)df{8>Ds&-pWYM$DhxGy0!D(`WQQ zf7Z|FXZ{SJ5%XsQjU4zhgGS7sB{X9GjG+&OTrbl-oepfp_nuLoJpK7jeR$W;xaU!$Qd)!JZH+i0yrE|5 zR@aE5$8^wM)h%kojlKP~z{QV^cZuvYUTf2w)v!@MA3HSaqwnxd6- z5<<^mQ`jhN_o0JE?A+8(E6|MQKY!K^eI9`B7B_nSCqL+4efTa<;d>pCeo=*H9czlXBtPjl@Uj7Ky zicM={_(S!3LE0J{nsa`08Ka#%u+zx1I(`%5tnD`=J{{|&hBVsUQOGKkNN6x z@_Q?-@Y3!^Y&Bb{Y@3H0@rkNFDkyle5yus=HE&5IPndPuO5`|CV_)Wsb)u*Xjfpug zq>2y|dCQI5c5;1mYvb9kjojqYwKTTwtI|b!d62iCEH_j(n0DF7ZBg+_^5o!QM%)G8 zLr{56kip3=vvKCF+yjG?ZAt{nJVll$J?E}f{N?uAPmH+OFmKsBkBz2ZH`_YPTyGl~ z@#3w8rC8L_i0`ya7Vq(U1o}NwriF?sf9Nx(e`EJ|Jbj6bo5MKPo$I28pCKF<=Z;iv zR)pibT9(?Q?1W?0?3J|R#|TIFgC5$Nf`ntM*S)kty$Q#AUq))@{0PSzYKr#hjf;`L zHU3Y@TP+P7zupbfqU{Jr3+FM~xMaeyb@jg5t>%Q|qT^oLm5PL;1{@bKj z$I8A+UEN7IuFmhH-cBbRXY?s$&XYtq4sB&Ef=>~S=eMjA{p%5q4ez9i(k_H!xpH=L z%TB^Exr>_&o=7;>uF*yIbtfDPR30ir2NI4g?Iy_&)`a8b+4!x|yi*JucLPVO+=OH0 zB7yQ#eZui&X@5DRC*e4(pSRpxf^e)=)>$5UNjOekQdkaOOE}hYNEWRZ5RTKjhl*1< z{%=438^`b8T;eV;j)@gr)awg`qvMwdm5ue-uZpGS$$ISes-jl)I^j5NlZQ5<0^#@s zdVJBJa6Ah=mYYgA7C13QbL~KSOoJYuTxf0JSQ~mwFHSf%f*#985{`T8_0<}cBOGs@ z@Y3p3ARJ8@)wGg~V~r zb@)1U!m-h%RAIq-oS)ZDwv8ejE1KM7kxPig>bB5Gf7VCO*n3V z913%%*5hicO4`jR!to09 z_`U$)xCVM$;!8L#`Z`j}+naFo)uw1(k4TR>@PBF)Y-Qm19C}=1PdL`EJ4P#YpKz>K zt*>^eCE@4>96vISrJ%>skEgp^ zi=QV6$7$Qvi88FmKX+5bu12KC#uesTH*% z@q}aARu8RLS;8^kWiKtWAK}>h(@5>*B*M`QJq~V4di)AKCe|Q5)`uP^vK|8(jnS@0 z6OQGv20D+mkd9X=;AqFbdK7v*IEHXkudOtf6@+8ZB&Eu3B^<|;@ln={V?+U4^ETFF zqi0s)>si9__QG}IU_;WQxRNR+yAzK4^V`Y&M+nDBP2A-0WrX9rYF*^0#-zt<&||wv zgyU7{ajy^Q@hNRLU-qgz?hA!kRXFWcI9+!Q;Z_IOU7YdX`B;k0))?YddARJww$Cs?fhtOko)}zOK zd;{=C!qL?>S-fC9rgaV#t^c9N%70wrVj0I?9xiJ7dBRcrj8Kue2*+C0EHxL_qs@nk zTG%DR(S3)9HpY(hm<~M_WIg6iAE~toBpk=aPSFZElOBHp$GE+OqprsZtj8q{$7qjZ z3CHDi`f3v$3CFpZ=OnQnzeA6sS&x}7t+ezI!m;)^rD|;>J$^6cqdXYLxNNrO-KUmbUzeAO2?#*`sn-BUbJj+#t7 z!m{}?!m*QUvY0-L^f-4|sCe=ZJ$^0b5!aJ(bXxDCX0RTgV|>hFJ#MXIskLG~R?SyQ zD<45Pc7z_M@_h9+^jMblxE*?|(~WSfesYSIah3G=9XNV^CLGU0j|0n*9zWL}qXj%8 z9FJG&t5x+T9DB!kX`T)=&)N2|nl@xS`D%wmD@|=79Pu+$DqlF^m|oaN9bz1Z9xG`c z!Fqf?##&TjJr4X!kG&qGirlQn^HuF+t}TRPSPwTjbR6Nh8+xp5A{^79$1A-E$1?Vl zf$BV%6dw#<44{-eUf%Mo0dc50|aLf)pb{a%D?t~uOvmR@gbC!`W$X9>NDJ(Z` zA{?zsCJX;Xgkv!D*y|s9{1xdIcZ6{q)zL*=J4bq4`X@paXFWEqZmF%aB42gSsHjyu zPdGY+duTaIk{&0f^ulj3@O%||>^p{WM9n#*0_iau{?7mp!cm{Erm-G(G#I1RIz>4C za_XzqszW%Ig&sRrA{+~RuBP>2J(hfKrJV>R9KVcE%5^*8_^Y^&n#4G+{ZPt$l=YaI z!&+QBL*rw$mFq;G2IQ+#uB8e;)}wb(JN*7E;n=X1o6I+taQq5AHWq|q!3slV&{)Dz zl$<1+xse_{fn(YV!qFc%X4#P*EuqI;~22ZF>NUg~T!tpWmD2kCDbK?JO$fPB#2WVQo@W5ITA^4$#5<3!*%iE+FDJysq?IA$v~ zNp`J8dK?QJO#=wWG0@|*lB7rPV))(K%7kNlIe$5&HQ{)DfVb>WjBtDgJ!Yhk9wSy2 zmRbnmxXLM6{Fp;}jO!mN>Sh1m_4vJS^Ek;kPFUxn7O)Ls49R<`v~jTuK5my+fatj97l ztwk8?(F^sQiLA$Q&|`KUACqd>$@C3`V`g_ZS%K%PKa~I9`Vy-5!!2 zmjK7Itq8{s(4)9RdRz=W7HL5^R)-$11rUxKfa7|`@g?+V!Fn7%v#>0*m2kZGmmbey z{g~q)dOSJY6t{(OoHN2j%|1)xV~?Du1F#-LYFKK5^*B7MqUNp;rOjaU#*He=`jU* zT+ezu0zDpPJ+^pgrFB}%I1a>obqDD&Zy_IbiE%uAw3PWa>v2L=Yq9k-`KsUgb;87Y z%({^(8n7O>m$H*9_7aZcI=D%%X{5*7(Bo@fcg(9eRPG%{I9`ArJ3Ejb*8xXYK{(EU z9^H$P9@kRS%wnX+ywKwm zuCF>nkCj-DLC|9s>+v4+xNu-wqn>jEdUWFTql6xpvK}L#M^B!wjyZ*TjxFhNVp=t= z^8^|n-z8XSuB^w^sONaI9($MdQ9rmYSND4f^Apx%)j8H;0qaq0Tqn|5k1Mf$G_f9Q z)UuPQ>j}q0-Q46XuIH>l9iSW60d_%;vssT{pvTkqNRPdN4o^w_o~ z;aCZJOkq7%z&t02=Q(X1oaKh+q>+!~tQsy+)<9ZisQGoT>X%ogr#<6lT>T+BszhBx;+V3VDdv|h^ zm8Xy%i=!^Li1mnX0+!{6kRBJr?%lOMa zT}Y2VvF^Cd^PJ1jVDg3x1bp0Dl#Zrxaq{#bWJlpsBZ0>|d;tJR>#Zmh?C&||HOgkwDPcz#ej zLywQ4#|*BowtybHu^#K9o-?*B;W+S&mo~E`>2dFS;5dM-kZ)5#L%Y&U|9dhDFp)?yj!F>dWT5zM~Y`(CP8!g{RYWG5Y2kEz)27{dD{nP8in#JmIS)SdU52<0sy?iiaL2y(Jv=@o~Zp(&IPa7{>cnxuM4SN z`&N5--)au@_@8>tS=7mAvmS3^-ztjttvrF_ImU6#U;9>d{7RW~v#;K3X)R{+zEu?F zIsX6ABlfKvSdUiNw>rZ6R%e0Z%D?ul{8*28VNnF=Q@BR>T(fWms^Z|D?i@1YJq*L=DcsU1p8LnKX4or z?G;y^aV#{;MTIbq%YH|wW?Tojih53M*5e%LaUARM0qSx`ZAp*CpvQ8&?#K^4eque= zg&rGnJx7Bc#dvQ+kEy`XT$+3}0D4^Zl6>_!^qAI)^w{y7mu722deq)k(;l!Mr$LWT zc>UPWPpK@P=d`NsqXw}a!GSM`157QBxf3_ZH?`td8q$K$NWH?x9er;mi=W9ZTD5b4nidi=+xG~VR?r2m>>Hcg7x^qFH{8mW1drLbK|&4jN|U5E-E+UcnEd5 zoUF$;*tcrMdhCIHE9+<)AJ0LLU${;l0zHQEx??)_ty=NERVUQRtsj#fbKw8{%1!m0 z7r=2M`)X6{TP55h9Ghd`YBBFy)x>^>CD&IgLXSnbPCf|xRtdA_wa+0CfNd)?*6xt@bmHMX+z>$NN@WFwa@V^PK7!9|KsAvC!j4 z-naS)JwEGxG1}`Q;fN2o2&@+nDsasdK}1ld=DS}%zAX# z?xB6OCp|7f9UvFie)k=lHT7CDt7^SdY7%d{i0M<9`1V=7y}t)03=4D(f+0 z`8sio_1OJ(s_4SL>QLKG4re{ej@Y-FN_sq4xr@BqET1vXwu2ta^rU&tE$H#?1Ddaf zLyw1@Y2V6v?ljpZjP%$QdYsOBtd08W27lJ$P}Jr4T*nsZu@&pl3_Yf@9!Hl;7J=-m ze+Gt%hyO!eu5O+D_}+T`Z@TvX;{VqV|BnOz|8ii0&r9)h$6(Q>kFV@D=!;0sEG268 z^p!cnevA97mYen<{ypD9hE6UQ_oA<_TzvkgDAqI1JR7l_`zNtsZCw@E%~yKedL*=U z)7AG*zVdsE^TIzROkL{YE4Kyj7Ruwa%JlWcnd?vynlnk|@8v5KMhA&kj!%>=?wMCD zUYxqUURV$Em4ntF7QOGC5I_BV<=u`;MLp+a@d5YGzSmhezj!0AAug;6iC(c^@muM> zvhv^+rjT*J#RGp|+14i3{o?=&d3d0&oIfr;?&UxWSqSYkY#n2sl>e7#iX3*1vsbNd zeHQ*`$D_HgYFz%c2<`1FPlqj5&z*0JmHmC?<@w?2>ig4TB=Ygwqg3ql{X%cY)a8cS zH9y2?=ji1Z>dor_qn$H-($%6Hjz&A)o3oT-N|H%$XJ};$E$??*litp&ffm}p5%F<) zJB#xFQhQs*nDu;y-1@AZjkQ;LKEunuR`Z+rDm|al^=_+S$VqP}ciL$+13BsKFu<;>8Q3LC%ql*Rg&2iIqB_K{*q7^d`xyx6{9}h5Yv0)~vVl z4p^1#7w@jOa}Zc9_lz;=`RoQ(J;&G!J)iTyswi^O^I1~ww$QdOHt?F0c3OOz7jEFS zdd7Z%pZ78F+Oi--EJsdyJNZ)sL>1(uw{!EBqv(a4^mbmqO)?ciPI^A?E$vKwk&~X! z&z|vdY0RH|&11|bnLpb`+pF`;pMgz%)ko&f=z0J}%-@1D;5No*Qpy2t#PKgwQYFn_u? z@fEd^litr?wk;M#>fbinX$h=~eIWj12UaHJr00_#SoK6sdOqsX3$YtH>F-q#Sk1dl z{CT!1OAJU$GVA$t16F>y>70IQSjh(9U7>PQpfPoCt@B5Ne^r+tOj;zncQk6ZoQ zA_h4b@AcudD9-#DJ#)Xf8BY9JvoJ)w=tTT+d>$Q6Fn=bFv{z-3lip7E#=dGea?<-}#1qOU(%ZQRtlE7{GU@I30IQU| z#GkLgYONRXCkt4;m&Bi%$)A-2a?;zG0j#W$litomVATUT>Fvw_R+o^Io=+UGT8^Cb zeBJ`9y~s(==kfahHG=tb?T(|mg`D(uvVTf4Ys{ZU`R&XdnLqcM#k+rF{3peDX=W|5*idD>?dcbN0^JmZ8aIuN`GX_{aVE!xzRs|Okf4T#!+G)g}^T4X| zUE)tPu!=!W`g^qpR*MP{e=>oUT~p#u-U7eGLP7j#39QB-Cq17%z^V^&(%)+@u*%Q; zIR>oeBPYFoegUh_%%6ITLPQ|*XJ%S}XvX}Rde>3JFn@-nCz_{#XW z@64a)rWkV(R>HULTv~GonKgdO!FNiM{w->#cKd*(aILG|CvvskEXa4jCRu7p!PQa=%a?<(S z6Ck$9s&LI9E7g@P5@dvrcNAAQQTVT}$IqCh=4_MtoPI~`b z0agjfN$;Oq!0IY;();Hnu-`f8 ztco#zY@qdS%%39AdMxuN4OnT+ALvV5Vg57&Rt1?qLxEK@=8p+jZDjr&0ai!sSK?jX8zQL|9CThN;dhg|M-g-bAIN}2xz?(^JfUOzKi)&5@SUe z^JfjP+RywM1gzfh__YxHDZ%{d2CNz|e=Yzkd*;tEU^V{}@uvg$la-(N1Ao?zdk}we z0;@tiez^my)9gPhfz@&LpGCmR#N$^8u!?5>T*g>2i}~{z<5w8_&nt{y!9`OkDjfe-;C)IOfj*%r$N@e_CU%5z722kGaNY=FjxM z=07$6n*VHS9Uu3Z{ij%y7;_rWe@S><+AQ@cg+0uqxJ>=08(0SG~miX@typLQZ-+_v_sjEs>MHzDUGcXARGvQ)a+_c>VPOYn^V$N$=-fSnF8u`l~nA zI?Z_fbv-r7l!Mn_ZrSZjz5nAsJ>ug&Fn>-ri!q;J{)A$!bCK6yqp<#ZU!LaA)3+~H z(a1^9=K`?W!|ShUz$zL!={_F}tYUcmRSxT~s=WTfT2S4>noxhQqF8?&#+p!X#}E9m z!J1GXzutpCn|c#}qJdQk)`a?dMF6XcV~9Uj%fD9Nk(1sI)~D(ua?;zG0<3;Af2Pma zuMRPPCS$FJf8V87i;D6yncU$wekSuq~}wHSjyGk;dS2@vy{Kb3Dfirvhgy04NxZy;!jP~ zTFhMkIS8zNbN%Nmu$sm7A0J@#;3e^A7_iEgN%fx;U^Qbj@h2EqMYJORcmu1Ms7dMl z(*#%v)TH!&e&Bpt#Um%Ze@?tVtsZgxXT$XUDwyj(<5B+r?C@I5^u(GF?MyFua?G3NHjsfo_#KzsG;CavGAdHJfV$VqP}V#i|T$@Rm{3&NERa?;zWwHN#e z-f!gd9aybJPI^0?uDnnaQfT~=ebZIKbw{I}O~A_K3Grt#up0i})}*)d2v|*@7aynR zBY{=3_AzF?okur6tELl(KU*DMt0%}w&!+&evf4@fx%ck0dWoF$c0z*ptC7e_Z^v_9 zh^o`|hSJ+P^D;oqL{54?7r<|<`ynU2o&ArJ%#qBWId5&vQ<0P2&fF#O?)Qx-Y3SS=d%@9 zokC7}J1v1#yOzYCEp=~;!^lbJkKen~VhnQ9^T`gZJ|QPPpB-~U#CGJQx8wUFKs;jp zEK6_{JD5Kq_mfQbnLkl4Y)x~RKOyVl<8Cv5(uO9PhsI@zTgV|eqoLYY?W0lC9@1lm z8d&d<=!*Y!uu7OZy6U{RJ{Yy@+M1e|x=(yWeLFJjw#qEOSX{xg@10WBlw$4055yy` zWUAb;mSQ5Fz5n2kS{c;Tv<=V3^t8}=4Nr+n#Iu_QWvQcw?wC*E{z5B1s2e|Bl{Ma_ zP~V5@{OOr$o!;kR=hW?XJJc9F+xE;}HNf?xI)Z1nUtXx1&b*^y@a)EtZB>!msj4WR z&F=8ae6{X(bpp?BS=+!Iimz7pz_S)D{l zc=mX;*<$>H2kJhaEi-ag@a(^*6@Ud;B zYT?;sYrc!Mm%f^R;n`h+vl8qLLf z-}mAM+OM$bqbc(0cTszUudESS$rOaIEZI2TR|ZbcZXV!dA%~5I=S;a}_VLaVwxiJg zp1Nx7gO4H{*Sn+#sxS4Qifg#P{rB~%Nz_$QFvwTl$q}vU+eC>sQ+#F4qDgA%@s(oM z1oZ8O6jh>hKd~avSGMT(SuM+5Mzo&jE2kCurD_d2U}}nIhqklO){mL)?ljd`j_&tI z6{y(Nd=K{&cl@qSW@Va>;MrS=?^VB)Ch9xlFEbyiqAzBs9h0yZ6MIp;$-PziPecFv zM5ynP$5lP#FuLk$71iasI*J_jTpXbu^nb2q;n}z~j;e8ibaf8b^NhM=K6*Y&b;kX3 z-n@-_1|Kk?odw?IOpC#R1!%wgvWF(qg&!&n&+gh(Ps|(kQJp~CtH%UUF#l7Pjyw;K zS})$%#H-H8Kl#g1k*#91DvS3@seM(9GH*}~a8Jo>Pedg#MJ>Uzl|w&>lG$8T7v#{Z z)eo_<*Gu!{$?%gKf5ha5)y+MFePwz>3pug-4fnRVzPQd$@u~1>Qxn`jJULz5Zcs(6 zL_13ZUWixteZkIXKQj83$Y{S*bilg=_@5P7ZFh<(Xy@UIKIV3t|0s9th52l}?7ncE zh1RIMuk2IzhUxa{ELETz#;-pOMA6qUdAQy`Qg~{$;Cp>U~k!4#PV( zjT4z!2h}I=Ct&#vF&*C<>4g2M3jQe~$Nl~)0@t5(`z%z6vMM+3-&O6GXi(*#`Pdj= z`L&mYJf}^Ido#{gj-UTW6#d-MlnO4{oct~pM1C~+A+9j(gSdUhMN}D!eUtZ3M8vBJ z;s@Tb(~%n@XS)^R0s6se)fN#Oc1fM>?JKQY#fs^@4y)KM*r$uWA*wXPy0?R`v^)Mv zJV@-L>=A!!{Z+U`7gMIr!1}^(G4H`5^Jr+td6R{lne&iabXU}H{`?Z=^E*rhI{M0i z`#y^r6U&OX?S177=a=HkxglZ<_Wm~JzAmoUTO+DNgAc~Xi0*BVij(L!-;L|Vyo2## z37&nlVvMN$^_jSWXWPH5DlGD5h!Z~OtJP5^cl1Si54`V+f$mF}TFCq8|HCaOntu%Y zBg*2QiT(4c?8m-|Q+PH!s*6fYej|$G`k2K_)tgeu;u7wUFLOZUXn-Sjz{sQb1yyY4 zc5x2(RJr|7g#^qLSMhAiz8_TbId?G|`TViVQr@K>n+_q*<=z(Bk|=AFME>CoEwm0^ zRm{P7uS#8isJ30x%N za1WYop;g6oNAo$;$@xFkP~2Z*qm$VE?2~GNxX`DGqFMYv7l4G-|^W?H>if03} zj*Gsr5vnBeNm!F4Ryd0LH(6A;wjNz#GfT4RT|!_@r>W%+_{zJ47_i{ z%@#5&@~&$s^h1xfzs0knn@nza$5mcmMCF5a;sM@$a_JP&sE)s=j%Q_qM6qb~DiMi( z&OCEWJpLRhs-yocs%{j|XIvGh@vKGRK=CZcGjR^jx*n<_+W4i5Nx&j=g4xtD;is4m ztY58N?%ryy1-|bO9C$a_Y_;o;=!JVutgyy6d1Z<-c(yw}7o4{5t$2VoZJsVxsO5@Y z_+Kl``&7}fnwWwd7FIm3JRNq3+{o?S%?B#Zezr))vk$kYDgWTcq9dNoyZ?uJ@G-^I z0`J&GSZKckY)r@T?oO>Nv?@PKm@nhmr2k_XwHWtzz2_)qEK6545%(N6UUV+| zOpQkS$)h)l*iu*3X>jcQ-ebb9#1SD(tuhTm|J;B4MFc)8ArkTIFw0ls z+uDBOC9t^ICrQM7St;Dn&yNb65WCh#h*jwSGlw^c!yT`PA9!}nqDi7%p{L?Bo^=nb zEfSA>5^i{QQrB~)p(B5ag21<7*MshDf-Gbl;@c~_o15JKBR1fkB$ZtiIFl(Z;@RH= zy;a+(sbVME^mSgOhPAsR(vfF;kG<;Y{*xjdIRw5wtEQ~qDca+`Rzrhh66T2Kc=r6$ z_i9c3W}*U~E!XIW>UKKK^aA}e*3m-yQ@oO?KKkuW4-0K_R4#J~^ylG5S!&;pN9LmF zw{FWnsO?YO)KSECPampkwP&hVz$MSe^J>_q?P?ydZddz&iZdzo3D3r^SgP8%B&)8t ze?w?jRe0|k)dO+!H+j{hkZ&pr_sm^C*4(P=A7k$NC&dDo~i zc*honUWyX)0@Mq<`^VtVqFRG;svG)b|C?XpeQ22Z5BloOdJDO|z=_xt^kMLW-(u6D zC8jNSw$Zq+qF(W0MxRGMdnH=@>Mg>6MXk9vM4yf!;u0`g+$B~V7l%c5#9JC{5#P#P z7WHw@a?7b=YRM;t4@=j2VpX&2Vq=KCqOfgA6#U3FhK3O@~t9NM|IGIz7W z9trM=y!FR?sOfic4LKh^-deqF^-hdIKJ8~MP+I@HVj=Qe{B^e){``~}3a%F2dqy2B z6fV}`y__!GQ+tEviF7=h+y1@sdF>^>q2J`m?<#cpSJO=NPpXZD)-KxFbQJxzV+iVg zuhQcNqd!-MWvKWJOX7gTq1ep9>9e(hs3%v)^#sAAwr*vE?Q zE!J6RuE=Ndj)SIZYksNQxPN*3iel-*4E2B5d#|vlnxJiWFd!;sMa%)l{EC8!uxf!3 z!JI|GggFOPP#ML589@aDVq(l$L=aY$Vg?ig227X{R0NS6W>?Q}@a=1#?6dzr_|Ezo zx{If)o?f$NP2W8#ZciG!00Js~#b-RP4}JE-_w|qQKF`;pQY6&AdkrPd!@rJ6ARXF= zgE>C|ZN9>&+6(X%&prJ^4oo(-#5z3ob4V$8`J7cYbDqP3RdVM%^VngW|AEbQu%m3F z^peM(u9Oen{cG#5r7kyrKp&3@FpX<5`*bpFJGTqQa(z_?W1-cj3$T>iyP}Uk+^+|) zg!|01T?<~#QsEB&-~WnxLg?Tuc)&4t)OsO>Ym1==|F6{t(;cj*sbno{X!qSt>Cj9i zw`Oe#9SfAHSO{-;?1pO2NcDe%6OS!=;*aR{1}u4wDg1?Uq}grw&U2qVI}TIUpMq~Z zmSR%Squmy$%(*&0>KASd;a@xF_PoA@IB7ze)S7d9i|;+px%QU2an3`Qt0-}Pa%>FO zVoS9WT)aO?>Bs#y=(5mfb~jwWZNIOnIBWhIwC0+2aCwN9m5*RLkL^}?5tB~F;4yx^ z^OHcFYMhMwx&O<@9yldG4K2A{a-<%P_R7PN9A9&6i;|mChI`m!)pbwo_l5F(IqMmp zeM0g}FGVAsW76i9fWG|w7SFxU{W%by{T2OrUO!KTz>0_@9K`d@Js$!68eYfaoQIPY z9>bN+v$vzt z*jgpe;d!-Mo29hvQ3OAD?Cx=WG2zW`sK;ZcHQj_$H@t75Q!=y;A*X4C8 za@Adnt)tXnW6eHiyVy4k zQ&B0;Wi}j^3VW7eXP#p}Y6?}F=3*+(eY4F>nDO=-0_S8>^V^aPW+Ud5xYg7b_h zH0Au`%S6bJI*3z$P5C5+&jR~5!ItOm7 zVPE8NsJZ4I~s+n^4Of?j%acy6Mk^sLZ)xP;{oqr66dGSt#Dki^e%kj zye;@dXfow2Y~+0YIQR<9R&ECy?r#;Hfw>tYU<0>v9Sbn)uQAN!x^z0M!+oPBNw$0) z&fTh_385jev-tJs#1d@W{ifo_{d@B>PV4ke*p1u2Qa+*eoaMNg<3GNYfSNC%_?`dn zo@-a|Y1L?)$a)@C+>7=Pp5k}z|F&Q{zU=WGg?_K0P4Jv^E?(z(tzWiZIXb8e5AuA| zC$GKn`jCpIa2{T53z2sDm7xdcr`kVrm~|}|Mc#UcPJ>CezGDIBv-jLRFxm7Ox^tf8 zlFMMmpRZSN{(GNFfGxcbVFr&~Hu@7R4_t}j9;xEDY*;kI3J3GpOP zE-JY$=WV)C4Q1RIm2AZM>}&Z+`O&BtOgV4LF9%#Y;SUhEkDT+v)gkY}h;zGq>~YKt zy$4fyeOVvia|;vBK?;xE?f(+1HQfnAxqqYY>1Yx#2BvX)OmsemKC1@xxTeQv>hQdJ zp>%`C&InSG)3znCxB2ydZA;PCFG@MV{YO;I!T0L+D6S79lRo3c&r7f;$M02`i2H{e z#F?zQYOM(Te*HQstY`K9U^LM_!8$z0eg3m?@$hdbu1hM57P#}=Kb*%oc{SmvlCLYp zR$Oau=Y27c531-P=izBefaLP93)~dj$#CI#8eZdC9DWc4r){2N zI@c)S$R#*ebOXO~{$WKt^n4hGmfUBX$45|1R-^c=`l4Gl4DM)yb@=sL?MlGAEMB?E z{cA7dJxFJ7$JXL{wb$vO*|s540{7|Eq7bf>sX$!+7uER%fpLRiE$cBgOM&L4Ti_(? zoV@)OWV@XPXV!oD{+HN#y=(FXrHu$!av_cKcgj&~5BO{K4}& z_1|Nxa(zE$@O(#3zlLU>k=T;+Fs0KzY^_N`ndexe?tDBm>npzHx##Az#)GE+P|aiG zolYx*FP5U%&pfiJNvw+hw>9T~W4p~#2U8v1i4%QW8FGx(^rfd>2IVZ_U@dhMPDK%VYQB?lF&X5$8v}ZxL=;{RN-!SckYa z_-a-Te&kyG*XFWv+^rOCIL|$E`ou2fYf2dBzs1V6Qdd_UmhsqjTWUbnIr;kQaJ{&3 z0PgA7lgEBr6#&sIUtkrkZ`#-M(B4nMyWGB0;{hZ+I*LcQPotS1AavO}6rWZ5Jp2Q3 zXYKGP$8;KB3^`ZcDCw-zf1FCLlw1~D%o=8P;^&iJt)wwLuax>l@bc7ONqk;gdi*z3 zp4Jaq@YtYUZ((`JCV0pBS)Y9ye(yX1GUx5e_S3L`-7RR&`E2916|NP&hWea0Gy5U1 zGVUi_;r8%CBQQ!YfK;xFmUmg5O4UIi*V=I>#@_N($pt+2SDkpJ>4*{-&;8d&b;S#s zY#7Jw9vMF9a^NHU<38@+!_cd9JZ$5!CD(7@;Ji!lm1DZwKF6&5Ah^o?6UV0E^=VT; zd|qx)Jr7TLnn7b8Tj_Kewi^*3*|FyL{GMszzbxhx&t+iiGR&WKRB6R??3ncrot`v9 z@j2b(z&G60eHM=3oGjk)1a+EV%;Q{*HHpHU$g7yiIgA*15T|#1gyB3ksnIet+wobS zbK21X``-GCVO)#HCeccvQ7PW!8r?priEX=0MW)<77`RyS+@wQW?$a!)D#Yd(YQ3@9 zXz=Qmfh8RC^V1!$DEKArXK!rZa1KmwA==wR99LldBm=vdszryb^-2Zd_e|W9) zUvS`d^vo4#zvmMi=J?s84xx5-0#xH#@0=Blk4IhsC)RVm(KBotxCh>H|9i{7@JW9y zojIm6rZ@PD9$brchtibp$BIzq|MfcMixPL+nsO?2r*y?L_GfW7ecQChSt*-r^zG=> zp76ebmA?J|r+;}LS;VY(dIsJK?x=6y-Eam~7hCAtuZ-T~y2-Wl?U<{T=(Ix~i2hxm zA-&4Hr*C^5QqyR4kiOk|o)vXJZLM!toZgM*&s!wv;~UzFXqWdv(JmjWZ1@`Z#~b0+mGh@ z_UWbzAULOkz719LB$#HcZ|AJoZC|lccYXVJm|8y5+%U(fu2%A;Q{D72Cl2c-(-Mt- zj>*2=f7y8EAexUTz&hoXBHfF zt3pEaq|N+{Vq0B(`+v?WF}D4UO#Zv*<7EFys`}L6ho&tiL2ma>`q%5!35PN6t^Pk_ zKYdKK;Bm4T>tR3@L1JM-^Y&9AgXS4eYEZz&Cx{x85%}B30GvPdAT-4M9!x?Ue0nVTf&eeLJ|H3A}&M zRp0Kiw!1?gonbBfzj8Hh2ChETQQxPj-5E@eYoTxVKJ*TI_}9|6Tl!R@Ls5D9|65S8 zAuTz4U*E1hM@u%D*oxwoS%H|> zn<6!tt=gq;n>}nuY5fd7?6{yZxt}ul@X3o0Sa`})PJ6rabEBepaDe+PJMb6lTV9BC4f1aA*PP+Paq5YOTv}2uJR8_DiKfe(9 zd1~p5O}_sEM~->>6$A~x;AC=+Iw*HEU zW8SC$>l;-;q38FvUwB6Cj6%=bE$^}IVLudl%y!4)E!HIBw2z9wp06WO#2Ggr6g^mz zh%!CNsj|Nl?5#&W6{K@aB4iUXQkRB9!zG)yJvZ zAr;n7*XZM%?4Jo6e4X@h3M&?Z8EX=8RI(0oKY1%c4{MP>o^!MpdcGx=!JiKPl9<<9 z_VU{bRY1%u=-V%t(AF7*p6OfO!yncp;%p6yhh?lu#MyQ|0-mxa5$ACKQ25Q7M4aoM z8W_x)M4Yp0oFJJsi8$Q@RbW=BP#-HG@bMj>*Qgj6D`J zC%ns=M4Z526;3brPj-&Ca--Zomv+ncwaWc-wUxhQ&6-4hMwc1G3f3gz)Ua>{AJ!z| z+Zs}%3@8T?xT3EPY5&k zN6Txy`gDVT9`ag0z?y`f`p%*7h&2g4zj&=rVNGIQ4c0k9>vI3Z?oq)p)+FY&`pj5G=qP<4*Fr$?FRoWn;M1} z_8R;%;YB3YjxqQrwnie}b_s=f9Or!7RD3yKqmPr)HxsA&8~l?{p%A5m2LCMKT3s>r z(O-Y+a;+vU0KI?Kajoi@`zs<&68@R&5{f45X%VM*o(6xhCK1PblM_}g_s^gMD$HO_B2Ib*A7yR1e~z98 z`#P*i#HrZWUs}wXM4Z4PV<=?*=;O3-27A^d{4*%jkMG9}{^>R?3>vZ~p{K&jNSMi* zM4Ztz`T8?3R3E2fyHse&nnWC1_D{e@gMX@WttRX@_$PpC)k0_R4{MRXeg%6GXA0LU zuZh1T^t@*OY$`Se5vLm0YD!CI5PDpBtzTzNVqS^7*7vX`p{L%B2pG+pM4bJ+){n6! z5vT854a{LpB93;06U<^wBF^l6DrjHspE1SWQdqfv+P0Kqc+JZq&W~pP%5c^s;ynLn zj8yI)qsGoS^@qVf_xAgt$qs{m{!R|Vcfkh#)J%><&sc+hHk&5m$Uz4GTxyew0~QrpNU+nhYzc@~LR zl?e8?JB_WLh#v-r!hF_qO`VDtmKprx-X{~!?=<-5xltkBJEqddDV21XYw072IA&a{ zPkS6 zi8u?Z`AdJ`=Sd)lTr=JwVYhLdk*P8yyvvU7T`fZH2*gw2i znbPVy+Cnd%5Xy`Y*g+&)}aM zJKy6s)+GG%X$ zabi5eU_WaTaV(xi!dTWM^u$$5gu|>!#IaYW!noxI{}^$tmhLk6C)lVE4u-4raXv~q z7}?3-AJ!tzZ{=Vw;o?*P!8%{F# zr!v=SDQgmODkjqiY)g}@^bqaUh{hYnCmtv!^-^=^4%EEmiuS1sWVDH4gOiT+YfK-GWcio zgfQ%L(BL2Iq(~fnD?%_ARLvw2+l(;yr>u1>#ixF|IajmlcZW0U;1+af+ry2ZH@8>V@hI8TR%;vm)};!Ink!S3v7k)Qk!C-i1bB0p2ksc8~IHCVGNhev8h-3G|7?!Xm5l2hOj0Pr)WYL+&W{Mg|%r_5$9k2CS^No5^?r@F~+*h z4A-B%Rh{uwxqmtb`JrE+!9QxZFzgy?@K49bkvKWd;Gc$75^?HCgMWIke_pRO_$S&i z6HgvA_@^P)%KDPQKb^Q%zuXM|X~wl$I>1)%pLDL(6mqS`el36hV*j}Eel;<# zVS(>)J!=y4%47d5W=+CB&Eq0)9%~YHuRk&rN3td{uTE<W zlZdl|*Losr68TBywVuG5M4WZ|ouGZWe~NgmPcHY5YJ`t8q})H%p4-LK>`lt; za{pw0G{yz&A7&4!S`}xU{Ogxs{m3ZL54!~!{L^rJ7*;;Sp9xuyrLryr7HHkQOS5%nHnnavN(|i}e6_v~eP2v8P3xx2;m4 zK5G*7TIQGuMWIgmI2pPE2)u0Yj~Um>YqG&VyuRf5S-tfBF-j_fr|Aa&bl_V3W=$ea zA^RtrH3>Zzd98nDO=4a%d98nBO~OB6yw)>WlhAXP*Lo^z5_(px(?FGS|BMNBg1xLs z_%NN;wJi6~gGRP7LX(K|-_K1-Zn=NHy7q$V4YDwk#}08>&+m!vk@p)@ z%fDL4nR5pp@bmV(>bGIh^poh#|2K5tJJ_&$1O8$C$B+Gi=I8CO5|7RJ#^;AQCn+C! z>{T!3(Kd(0Zs9&BEOfAI?Mlg*pP$OnJp?%l@qJH+LB!Yc0HHa7{r4G4iq zj$?Z)0`C2egizMG`q~~CeEumc;phK;jXj{%pENkiISCIlg_=|IVHA(OtW1?`_vqj! zzi!(7N$gN&hl;qr$CSfLi|kTp&d=Lz4_}FW;-?}$XOH$Bwvi6kR?%G6)_mx9sa9wa zF6KFoSTaIdnWz)25S`If1pCMW!3t6PvqRzS;-7*Qq8+Mj&?MlsV1-EA^bBmRa7(a4 z)Nj@uh&MWc%nDJ@V{ak;=SE~!h_+_^hM9l*AhSZ$txpluI`KzgR)~gnQ^|>++bhfp z(dZF;W`%WSiCG~!-?a?R*35V@R2@F)d^OJ;yowC zCIqNtW`)QHB9xK6N(C!K_vLoDwQY`Ih3H4YVk~U_MX*A2ZrlO%{q#t%LKNn39pC#$ z0JB2W;AIk8t_lHWh4`GUZ@qfvqCiMZz=9HJ0USEL@B&ScxuRP zduD}b^RqIXvVN<=tPq(_&%?kC$hQa+?%&F+%~D?~}(pJQ%mpkRgQg0F^F{1U7XT^hRuJ|0RDtPs6BcM2}_ixaF6h4s1( zHD{khW`!tc_Zv8T#2=XzqMsdp!-=B2dAjy z!C!tkFe^kw`-@?J<_n2gA#%0N0`2r(f)%3aMyb$c&RW3=(e(HSF#78e!3vS>jSKJ; zV+AWjfopcbwui~UtPr)!cY{-}e+X8Hy1c0c%j)Ng{q0oMa--y?)(KXKq=PMDO?Xc{ zvqE&s?VPf6XQ^O?C}@c#K1$3HtPpKmwg6|Deif_`U46I@8&ppctPtJKxQ6iI8ZawF z@3fC`irIc(R*34h_=-dR&Ie|NDEvqq01S>=h`>e&5MybfG5Vec#iQPT21S>>Fi(V?$7mEceL@^uw#CDpiB4&lC@96H* z*7_=nV~=%SkS|@mQYcs>9LUg5a9ArE` zh0F@kNWT>5F>(tsD@5z2{DRiQU6ENK3LRDm6-&w#W`(H0L?v(COYp46`~87Sx`sYO|U}rpd=LzPg^7QEz`%chY&U8uwaEq*YFZV`@{%V zh|XFB!I=}!fmtEi7VH5&#c6^SqWY)n!IBMmf?FZgi|tbBmomW$QT@sHV>UAD!mJQY z_X=0yKb8tsh)x}AiH-~Y308>Wf6l>md0z!9L_d0lU=`~pf)%3Zy%G4(`Z_Qx#C+`| zEW2<3m=z*z=P%eyvly5aqB55p9DcT~*!x76TuSlD>T43SLiC)Op2oM`9GDfNo5OUt zYoeFJtPs^)pO5XvnhI8kh6JT!Wbs(R3ekkdFR}5>oq`pjo{bP~#+?_e5LrGvhPP_p z*Wb%k)UCsMW$%$$A$qdh9$RYv2v&%kT7FQdZ?Ry7=v>7r%AScTVpfRSN4Ak1+cS&J znuj0xBUS8JBv>JO6V?}+CH@wy5REL`2-B{-6|4|-yrTt&yLSXDMC+4o!YG?F$gB`e zn*SO$RNRKl3em7VKjC)i5M)+}<~}U|^AQ!r{wvD-sDtb8$12PUQG-<~+2#0U2WExn zxMvB}>3L6LR)|I&$%g5lx(HT?a{qmV4w>G9N1%^g5}@ix(8g)NtPrhR-Vioso!1J&b4308=nTfM^0{JWFP3X$^^!i9g%3RZ}g*@WZnA9n>S zM9-qu--$gB`mw34ygk4(V|(d49W%H)?tf)%3Vfo4j}K`LTah(?*3OCuaqbf4#I zm6Rq;I$R`JA*z<{2%$SN1uH~f25*2mQSSsRM6Ryk5M*>uutHQPn4nMaS!7m-nvH%1 zYcFp{W`$_N?F?9Qas)CfM6N>$poO}M*ndUM&*`9`=S+oJA?mx4_cW&Mc3@VBN^Y0H zqp>J4D@1lf{=)Uf{|Q!zzNLQxvt`Q#D?}3}CxXKFZOjUh|Klt0?njhhg=ogCy|7^H zQ(#tzq=e~Ex5sy2R){9`ZUX1W7Y>p?ixq=mAt_#OLCutJpc^SBgeQYKg-3O{_*ekQMLW`$^qvRzq2Wr7u= zZ59o1mp$`}oX>wfC*z7EX@V7^*NcNNEcm%#h3LTgOIT_dBUm9ay8jSkW*vq|u2<=R zkGQ<%YG77~upje5+19|U5Pj%cg1h%5O3VsThgH1)V$}l&W`)T9j}EsPIV)nHOkCYU z42Vz(R*33V{)IY72WSX9-q_&VO4AW;Z?vR)|7|9py6s9tc*5<~LGc{n!i0tPnkI`~uvJcOkPv zWM`HRVcFx6St07nzm0bIeoe9GnQHXZL8l@=g;^n5wnrsTTinHgSs}WzycA&f1&LW9 zx)_!Nmp7;dD@1=Det|Jd77A8~La#ptN4x!k6(Td=YtYsuQm{gld2AotEq)Bl3Q>CY zJpLZ-D=;fWHD0uae$D;~R)~xbpOyYxFBPm1WpuCMkjU@X%nFhF^9@S05i@L@w@U-- z;K4_Ef)%1!VG}W9^$)=c@qPX-Ja{EputJp8>LT7-94lBMD)N7TetAcLSs|J}FclAO z(*UzVv@b9V8(-`J%nH%s#A4L-OO}`wqU;4KO3M1~z^o9>si~r^i)@CQa0nMq!eUU zh_VK_V8DT2f)%1h$tB9=rGJwAt_@n2!9SqO#;W$A%Yd6w)|aIg}eyC3X!wJ0dRl#2$&V3yP8FCYRMO1 zR*23WYy;Q5a|A0y|BbjR*-a}ItPtI}KG4CF@57lDqG31JpkhpUIKITv5&wxC3_<#>M%x@jU@#`Te ze{kU(J2=7p&8P7hl6h|>aeYXgtfGNY6(nYbD8xcVzR4XFW`!uAY7sttmaQ-=L>2b_ zM&Hx@1S>?{X1&FoD>eyMh#t?qgJ=IcAy^^ml5`qdw7n%*A!@pHD;|q^jm!$sl-$9% z;PFqv3ejAsfCqC61S>=nwvSXA^L2z-A^Kh#?U2r&znB%G==l$%h676kD@597CcSIS`F#2|%PAvzPPl6`Ha+A}Lea~hRF+WjzzSs_YK{RdHBnh92j zPK17g9FJLo6{1mD95G3=^fg{b7&LHM^j5ttRC_f?m{Da~hKR){7} z?g0Is{S~Yb*;S5_4p%D`tPoZ1u->5)v#HDqQCiV##l}Y`SRoo7P!%hF&lju^O_?+r z$9K#StPqXdy#uR%ekoWX>OJ}#T2&^&3K7HAc>K|EU{;78I=#mzhxNd$5Z!F{2gg_d zFe^mKxkXs2{URB2JDblRYFb)HVpfP+@Yx-w{%fi*D?}!mA`GsOp)e~%TgGOh_Mekr zg@_is!>9K*AhSZ0aOy6GUkewk5N)$Qi~BN3utIdR*LEBd{tB5DqO`-qadTOQV1?*b z9b*h$S|C^?9J9dWi&Hf5jh*S$# zz!0r|e>-`_g+ed>-kez>>e@dV?B-uVW`)S(>{D>b*@Mgq5iS1?TOW8LvqF@(J{RhA zZLGhqJ2|HePSrf1Fe^kY`TpqS#Ocw@3ei2!GU)g*SYlR)?)v0{Tdl@|6{4)Q-y!+2 zem_5jw|NF{efK~L=Pi6iG+6h&B3L0Znt2FdNSXv0wl3+4`(6(ZMzZi?9@onVEird~W`$^m*&m$Y0D=`Fn3K}){e!!Wz!f)%2vd(PpLEBqOZ^IYxQ4!peOB{C~Sa|VpY&mA%ZD@1u;s$%$W zJwHNKdoNL*uGa}xh;oZoJ8Wd$gjpdPav@5pYFsKkasK34|A@^?zi3envQ7OW6C&xw~J z2A2p{i1z*@hyKhHF)Ks~=7W@{pLBv1q6>*ecsH{^utHQ+dkCIL_$gQ+YCK>ozOS63 z|GeB|^=WLh>y}`JDDBH_tbX_eFe^mMJH5r)XEy<}LUiE3Z}i^L5119={f9;PTa_b; z&*?rLxxRb4NX!cHc}yyj)|JLGE5zO?#BoXt{a&ySRu-ZsDXE<8EWnMWUaEq zStnQ_dfnH_A(lBZW`$^9!X;^=2eYZHVP9|?=({LKutIcy;Ucj1*Yjw!`^E8s!?J;af)%2% z^<&}g#*2a#qIa8)K-JF=1S>?>cKO1zz*JyXh~6LV4(IM<308=HHF+jYNiPZh>Z zvpB&D(X%UYc(w8=U{;8to4&!H9-Dz#AsYUi&vSr*z^o804=%*2=ZYlp{OxxG73F@D zC1!=_)=U+B$xV%AR*1Csi}8i#nZm3P)!LGUCUHFkD?||sQ}NwMJ$FfahCjrU_D2LO zL}!byq3@$>f)%3LrAP3*-ve>37a6BnDO+#rV3mg7_mAk51vd(y;Yz-bdOsAm|Hyz= zOWkRF{T;aX@=I`C%=bbwFW{|^STNz&0~aJ<<42*O@?s4wzvAzm^I*(8zJKoc4|fH& zgpK?iK~LLKw1~JQ@p)fl&gW5-+ITvs`T2j_E;=09afz~ME?;w2=HoW6>iCkM!-t+t z$NrgPuqMw@RqG|bIk^)nux5{!3J%_NUjJV3{!|w3ceTOwD|jFEx>WwHx;4mW#L>My z37E1u6#0xeI@~t`V|jlVpAkpz!}eoZ#3ST0;wWgV7xv!%3HgjT%DiZe2@m*l1dlxt zlA?r{6^S$A$YPecQn{Ln_>4Gm=~3h`sfCJW__9u)N7A>TVsSkzen?1g`b< z7XHv_{2Smi;wZ1(U}(PhC-50@w8F{+ULDI9XT(u>{q>SlM431vj-1U~I}D$|Of=6$ zrE=6-cij=rzgfn=srJ9^|INeydf@-02gcv*OWqGGuj%uEecQoGePD2eX>wQjo{iV73;yw+HOq;F*jTx=>uDgns= z#j9HsWjTa@(NN(BMSZQxe-Ji&HGO_?UOkhaLl-<)N+$;#P*?u@0nRL&K^kSfdPP`G z`9;Vmdfjuh`g(2$c^>~1MPXcXwP{u#dC4tH>ggVDdA`obqhD==}4=Skx9!6f; zIS;+$mj4Anr}{x!KeySk`L<_J?ZFAH&!}+{qSliRW!C^LT>E zlUGO&F6v9T>WD`E5$3LJecM61 z(o`eQ^SmUj^PQ{>SmrHPtUUu(z1^%`{BMDL^y+okcrQ$=yE#ej6juPMpv&63Z3f9k z%Nxu6Qg3Q~Hg}U7uIn!Mo06!l>E1|gS2Rej_2Icz>y`()Ig{m|Rhy_%f(xZW9pV^=w|C(mQUu^1DDZjXxYbhmY1dmL;q{b=<$rM78N@1 zxghOk(3czG#~+&3m3umlpl5bN!h1ICBHKT;rH?0$hF5LsBJXa|jJ(&q4j&OUNuK|n_ac17FL#Byxrv1BU@@8%Xi@Tl6i8^#A@0l$&0~0Zl%2B^Ox|scP>iSH8t|7 zBj>}bTWnC4uF%LwU{?5b%|tv<<}I(g`|fzt;%HpAet~RL!MF95%go3O;`96pYgl?d zZ%MWO8z7fWU2nPfuLJeI(MdLM7i;-AcNCS?sVQq3WLxI;o<$dizk-kJYOA-KFQ;Ku zcR=HoYIWVhHFSX)KwW5e_0bFse;@obc7@`kj?}H9ietLr)&&FAF3pxugV86j)5byS zu@k1!;I@CT9lEGrxeun5ugqy?r@rcUxi++-ZVxK_&sOcb)r`z*4W+q89n?D-WuW)D zX|ycJOx+{(2$q;ErCL|YER(OcL*KQl>Bgpb%VA6B#JUt}$ogE69BpAwuKiCN!0&M;MH7`d z>Gs-+@xJn*+%pB#^9*umncz(F;olzJy+efbDntuFKzet>Kw@@BD z%e?h$RT;+h_mJUf70c-pTTt+LXZhyVwU%Fx*i%Zo&hn&b(Uv{mj-)z~wdCI$Gc9>j zKY4$A15-U~sS|d1QQbScV0t%8b@Qk-q)at|ieI{^V{$cgsY+n1V=pIl)zPad{dy-f zYd28+SXn}Mj~&DMs|KmR_MJwFXMSSuzb=1>Xw;E}ycJYx% z=a0kq3!Sv1`1iz(Hm_FtINNL275d8Un_rh|ZtJI&Hm#Hop7a73<*M~>I8Q$L?=G0T z57I8K;wHPdH-ji;1;ok>p?W*n`F_b2rXh12| z`>DrW=|NjZ+K{ieow`MEBbuEwh^C$GsE)6d&A-Vwg=$|gSLaMUh2!HE(}X8R>LuNJ z;jd?_$UZ;Ga>ub>u_wQ3D8_c5rP+f5>1<R##?G zo$qUoSLt6v9=T>T6^(QV&(7*7r<|5(?vVZAQH%S_qi(dKk1L*p=RTMy`|UO&^;;wD zYBk?~zKKDHYv$St_q^rEm6P$&n~qw~X&U*JW{2|Ww4JudQX`kSo|LM$?5B+^St-A% zx&SV;an-JVHBZ)!;om@+KS*m^ZGzluT_w5rsk7E`a$i|%Zz)d?a@6Xkw3oFxvb?3h zM%&7*nw;%9Rt{-zq3zTm38I_Kk+Y$uw#)ntkT-CJ+~(TP@UwyMrO_H++3m-*@Ma%7 zD{x06FCF6@zHxIuH0!!b?v<$ufBfVE?mx6h-q~}|(LUz+__oJnIrw;C87^uB5KA;Xn1# zw0t~SI*HE4G*)lCcM+2pE#iH(mDF!955U+4t0=?$h2@=p-IR(qHT0%ZnB~>$ZzP*7 zzEt;Sf6K#j*Tax`E9mFm5R2#5kHKZc9BMhl^>~-us`3f#Sn8?j68@!Sd)fFuM>=qI zceqW>zVfa^mh{;rA^dEdo7^kE61hAs3mrZE__(tMor3 zSv75-cK5UXvQ3{>@`7L|ZS2@i^728Fyxpt2_R8TJ@+YU!@(*LRHgwQSaM8??Tlm!0 zCgyAdOULDWj(%47kUFK3Qq@d;P*kZR~+tzps+-7MO-tm~j&2 z%*Aq0|JBD@waUWIji$;ig5O(==+lU1)EF##9++*p#H$Cb4YZLrp15GSz;h_Qu5Tuf z9QM`n>91+DyLmeNORT1j>$a3)U+}&l_m=8WA**Thjy6y!udCX&SVM2$^>b+7T2?pT zx`zCZ)?l7(fO=XhFM57(H;%Cxq*m_EpxsB`}hzAj^Gj8aSN3f;_$*w|K%#sBx3IG~L1acrOd%{ z&RHp+oU;O}Ikndg%kq`0x!h1jKIo;j*shWPEL|!Mc-u#Ngm1Wdej5Yrx4LM@n=F*G zU9Us`?SuXw_TB@!iep*SCg&`22JImu5IJa15rvQhh@5lIIVx;{4YtWS8w~8hWQ=XH zG)>0jWP&j^*`15Ub*ipQa;jEhxW*2P+m7Z$Gfy+PXb=LHR>2ot1 zAseUZ{k9B;;z5tylPjjsHy)0Jhz6$nT>fP-O&_~p&*Jg!u4nzs?am0enb*g?;`&}BpzH!& zTXiH-6wR5!>@=^Qmg3vtqQkLi=CEA24*#mBc$WI2x$uV&t$wa%qFbAcqVS?X&5<%d z4BAmz+_)Q{O+8*f%zRT%#3nAI-8}fl{5pLHk>Oxot!SaG=A=vm#qb3wv=X~pn9~}L z5y$6TbS%ClXlUQM_;wx~#&=zu%-j#dy<|E{c0PXz8eE| z0~_hv!-9=FF$3Z8%KiLDuew)Q;HE5Q8x9D(aclfFM`%UTfsb54wf#74O_N;il&_bX4g7{e*BsZDe^w69NZ;xTw~y`f{UKX+ zv8!t%*c;j2@nn5@F`#uNSpI00V|n2Q;%1RtkTc-2V}8CaVr-@ddbfyFT9Su@MXDBG z>jk>x*UH}s7tQil(#v)!tBt+w5^G!j91xyH*AAzO5@j2{j=f&9p7z{1LgY?5*(J^ul}*sGYCp6eru25{aUm+PsiLV*imqard_8@oV`%tV=cQaO z5slimuJ)&bZ70wbRxSTTV@M zhX>VwHHnLh=9TukFKlWF`LCrGJEHz_XKT?1<`g<^e$mXw&OZK|gY@4?;6#dKY-jm#aS1Mq>z7_#*zbN2t6R_B< zb$BRTfix?&ZMkWFcc>fO>$%Oh_k^s%H7*QV&T8qnQKOt_V^)T;X;wPcJq{5=x95iC z^Da3WmFq07MLpI}Hc6>f3>hp+q+Y9+?wU{QHZ5HAy5`jD&Mu=B`^hD$B}(s%9p=>b z*NPI;8{dm9_R&>%fx*2+gVU$Y-l;>i>GfKO&$FZx0WIoj3nuD9 z{8d6MOs{ME&BCJf;<{q#l(O256G=qY4DG~&!}+y*pPOdcFZ+wtFH&iv{^)LQA2C|g zJbu}c>)gCpcZf^;Qg^i@Ro=zU<~3bnYVwYbHT`?(BN~qui@O~1t+-9-NjmixbN)EC zyjJt1FxPA=x-81!u3FR=w7|L|`0i)!?$2~+e%gvRH&rZ9b{?we#q^?@V;346Vr%nys z_k4Y$N6x`;zQ{WL&eTw2@~uv=X66%pQIBBb_QVh+L~9t|91p53O(R%oT*gx z1Ng2>l%MKOJ3NP3rc5NbHfrw8L+6`ax(c`Ued~zg4g9s`k;z22bZteM z0|m53RrZ(%f9WS47fGWfUEJTSn{>1&Hu##OQ|wCo8=5Y$`PEv7E6)^Xt!^$6bhMkJ z^5#zZqCKOd{ zq|;EC)bzFcK|hDSWPJprN`A;a9Y1Pu`jrckJfH6V<;RR>=!i)0*;3NIf8}g5?Tca1 z@Q4uX{N2CR?{&zd%|AH?$6^D0#Ea5enGG%>7KJ)5Ru9mgZ;TRA z1y988FB+&F+dop&*b{BmpA({Oy4pt+SboGT=nT~^^=>8R?n)(QCJ)k{6s#! zmI1B*GEMwkuC{2FzMM9}kwWxM(?(Q^DX1O3y59`X(@)$DORGgT8E!^R8YL$9+;pUT zvN`trt0<9d*9OP>SrN{lPh6s4WFN=5G_Cc&{llbed2#Tm_gcXT^k@w2#JsZ_G z7Ihv1)%LsfdSgS46uY{>{8e}L-+l}>8r^9CYjWm<>z(Tup>rxgi(wVv(deqi>S8${ zc2PqJXjQ`a>B~Dh1a*b}sd5-UO+^s~P97pRq z&S-w(yA{=8{LU{ON16wT5}gacqy;}Z#y9C8s+@nVpNvharK&wptjoDYU)CbGwyxh8 zF?Dh?y=sZl+KpK*akgY%XZ>Z>wPshN#Di8McGB*;+N7GJMCjAe=K6jiTH7^!MVprg z%>_+DwWkAHix&A)isLPUv?|?$#NGx4gm1N48hs~}{(HWms`f?NK|5aHUas7vDUKSo z3+Q97MTpwb1ssj`f2lv6I8+!n-xeN|;y5-@y@UJW((=%_ zXC-m^>?-#*{|2xjOD=Jx{bjeaLKn!l^FH3|OJ(#=Gz1R5T4}x>o!@BwFdTZ#t!Ne- zRMu#9+XV}=Uy9k9N;h&Qi-N~v-Z*1|>KQxAjDW&DC+p_h5MyeOUT|vbIX&&|5W~=# zL+QimA@#FBBd?zm(v29g(it#?MlkrcnUlYc+KnPUj<=Pjz2E>JZBO_}k^HZ5deW&ywR+Q{M1hAFoaqNw*2B7BEx6qvAu4@iR+$m1)xFwL+-dOKT&x9aMVg@f|0%E7_@$>)yj)3cgO zf+NMTUV9x`3XAI3F|OhFc%q}*&-kt{MTm(h3pjEOS**Kv55@1Zrt&TQ_@@5pj&97ahiXuE@M>u$pyykbg_QJokq=?QSf@(J?E4=frfMI2-vaw zbG^rv5MyJd-tblNGrBuPsFA%&3#d>c9TaU`&-iS-4n1C%fOcthtmzLw-$-Q~nbuu@7(N;bZM^KBR&=g&Nh25fVOO~y4qg&F ztGWwb=kMTN@MkYGL-1(0JnM%Qf%k=ZwON0ddG%!Bg~O7H^K08ejtn^+<2(6^@3Ys1 z9_>GO1Z4$rvV93ix@woB!G;#%%CNLhFV9m)kA>(@8gL5le`e9{z8E2f#!k??eqBUc z+9pa2{`Hpg-2O`1^3yI+tV_<=W>K}Y`TfF0bF+q7`se!E7bypevg6m8^`?btTTgZp zvwnMm-=YlG%6%Flo`>WSkt1qrfrtD>?s8Sc(85);)i-=ZtEXYYcTzEJYW*8#Vy(Lf zKAKg#zIUNnJH;?jYxPSg9Vz3G?T#gWD9R|MFSUH5b_ zWU7!?Y{`1jeXUU^Xc7C&jI5NxxV&)?Wa_s8zYm<(SQ!uwOBdHM!!P?84-Q}q>qd!K zzv}@;fiY3=b;irix03?#Lgh$^KJ%%*F*d|-Brte4mdrg4$QCZZ+zV_85}Iu77nf{U@W+e=Vb5ogK6p07*i|t*Bhrs zUt7a#ZvCO*{InR({pZ)Z2Zc?GZPgLy;>TUxEqZn~XKfn|b58uYqHN6=Ga&N-7*K6V z;Ta;a@Y&c7QlHA~Sa!3J=+Q6`ij5xcsBqpXE}11^V`|f}YEg5c&Au5d>K|TZR+@-$jo8j&`^bmp?ghcxFKa@@@dLR;soS-+eHF@!&renoGfq{} zHbrF<`%X3zFZ&nQk{!HdwyM)jbonKlHZEd`S-JmE5mw-}V^w*F`DkN=IQQTO$KT^~ z#uR_;68rZ|cf7iqN#EKp63={;aD4M{w!Zf6FtH+eb>AmH{;F>Z?;*-2|7ykg=*&=j zSrd__RH!@g)-q7FR5j7@##inPYwJVAH~ECm=jYw2+jN8~^m%?|#lU&n%!xk?fC;x+7A}Y9H=nG>zcVl|t)oxJf+AvKJs3N7oTJQ~ z08z1EY1rR&r{lLTnu%)PWq>WYA2{Yd>M69f7xcffWzy!}8ZH{OpQ=Y6b!h2-ixiIg zN%RffD{77JyF{7`+hPJI)zmWjMu^o_{7s)G^|g{MhKS**4DuBd@RuDgoz&O^Zs#3W(`91MKl$~QU|(kH1LD)sOmyXx5S-xTo8;YUO+5= z`J+2k*ACF?%hzV9(@BjH4F7nk&?7e6j_O9x zFHx}Ln_bR!hwBcg&H@TwT27zQ^L50K}PSeT5xGi z5$NdldrIRb=Fy2`AWeox_JDVAHbSzj>u6>McI0p;OMfuj{UiNigfxV z{mIh|TBlaS#ez~Z^(7a5wSn$PvFYnHdiiw~w9w}+QN}+!reVgK+RYIW;^q9}X3sSB zwc*c)h^MudnbSsuYJRi3ipL}WF#9GA(ab*@ia{~i#lYQlw2+$>#iza%M8;gzw4~qU z6lKC2h*EwfwJ|^3GusX8BL04zL%Vm&Fq4!WB1R@kto80t-rSugLhP-3++j965_9qn zoz;$6Md?$UknZ^1?;5+jx+G1ko+0ApuuH|w>{WrU^1 z*l%oG^JJ$|MwW0FROmD=_E^5^MxRvpS7v|O4Un48lSdr1KGb!4lzrDjGE(XL%|vvysTKmNIa<+O!%e-be>e+DBLnN3{KMuUd=9S ztUr8IFTV_9Sg!O&>uY26@?VXFIj??qA0G9iv+a^7I9lg>ckEe+&A!bAuX2xYS6&=! zws|lHvVZep#ris%%#|euLF~@(f?Dtkv*@CZU`~JI`+4nrB2%JZxbb|HqvzeKV&sc5 zc*bJ0<8+rM;?Bj)@KxbEj)paRh#UJa>($St*D4+uCW4;K(P!K$tR?CYDLx6$qF1|H zUi%&G=&NH%Vzy1Kp{?2nZjrWes2H1~l(stfk=bs1XK^E4E-jg{+DtWZ zuvl0%iT3-&YUcXy!bQIuCmp-eB#V9Ui%axzEpUvy^2qtAf0W1+=5$Qm^o2fm#t5NwvXWq;ID{@qLXmKeU`-m-Ks?f2#)^g&g3{q`lHK^a{%D>~nu&L zZ~8>Rm4{p0`SKTv4Lat6BTvHJgU;46Pc#XKow<^_L-36M?DK=*X1O)X%flJdfmH=!-3cJiJQ}D zgZ+nzvEMGxe|=m?8{-oxQZ>zu-)%3iy~Xv>#Z8yCFHBiO8<8neWL}=z95p;h>s@A; z=qDDKQ(A;-uR3%WWjkFri**jsviUd0dtW}H^xV3d8Bs-?4EGlm8&%iBcjpm}ON59+ z=Syide|T!XzXm<-{|NB0m(0y>!$icEe)F zNtDCuK2c&=*V>L1m&fZqIY)|2(bIfa&p)Y$9qujirEa(4`;=)R^V1e$;>+^xD}NM+ zPse~rQ+JO0`0+ZBd#kUw`NvVW7~B@3&L$PDt0gjG9Q`5Y(k}C6?Hopm5~E>UhQ8+8 zH6@I@&$`m)#sr>Yv?Hg`db$+MhcbL$w>=8uLui@NHr>%qpXOZ{PUaIBum6>2Q$ z)eiDkP69bSnp7tS96*9+cv_pSfPxxaiA6kN959bG(WY`0%suR}Xn)E*{evCf>g3d$L+?F}7(a+-=a`(XUKpvF}VdC|u+lM^u3@ zkt}mIsPg=#GNi!)h;d=DxAH))U&@WsGZ00`ygv!{YcMpS{2;)R5Bh` z?>ZW^KUzhKXDNM5w-%%g-8)RwOEK3hUJJ*yvxmra_Oh8_QiyiDX%o@!L1wY~bzQCC zv8rNnp0c9NANa1F`NV-_!Q$MC(prsx7iNm39Yx1Nc{H=oCNqcsAW>s=GVSxi!Dhs> zG2(uubB>oiA-2~xJY)U$636MnKRU-OjS{27>O0z|9;atpG*bNOyV$qvU-&)4d3{96 zt+iGZ?3Ef;ylpA=JT2{h8(jBzr*fU{o26!Pm_yHZ(h4E zckc)FBKMhFD`Yp!Eu)~?j3MUVCyE;<&~DG#yeYPKk*Y@TQ7$OC4)1R`>KH?ljlnZn z?ev8kgN<6V2S7$+yPo6oP@_xF_TckrBB&Kr-zZVJ9$Y?95atRz|Gcdfema>-O6O7Y%)d9pJ4>d{`R4J(1Aqy*1sb0zGaMiW1%B4 zKizRb^jDv_Lpzr@m!*k-1>qUp{+U;r4~h+el)lrK?|gdC?BA;k`<)Lb;tCjU4Al zj=b8qpT0N8y9SDKza-bTU2kkoojyhszjeXUYH0h|B44?LLo9QAUv0m$+leUAF>fQs zfj$xX_FSVxm949MCpJ2yZ|dAv+z&0j;_0rGFf&bSaq6d{?%lbHLe_^h#q5pK+~L8s z;J~IL;-KrG`_Im;;dX_TVsG@{?uX0z!ka=rn8gcaGfu%M*pg|CIs8#EBji#Pluoug z_EBUNqtZMVjQOIcGs(uVo5gCb<1hmNftD5CQ$hXLC1fu-wdjbO=N~ z+_OCUpgU&nW?jK~^r-KCzZ{~@yoM08rn95KqzYnqR7EJZb&aF{u?8Z0&76>W=M_iC z&0R#bQ+M@A&eYo3_CrL!pWV7MZ2>KlBSIW6+o7hb_6_crE5d3MT!$0 zlA7H{)zgw+#kKInsb+;tq1u{1dy0sC7tH5BhG?lLHWSIe%OEE14%8k*2Z$P#N{d4d zr#8n~P^>cQiO7I5S`YlY$&0_k?@RgS)24jB&FphzfGC+hrFL~iYjbUpG2-;>pB)DR zBVuQx&$Hqzx8r_?El%U_D6!yjGe^JE!}Kn*MhQo;&A#Q0{d&n_{X~iD8CMkbNddXD zwGrLd6mnPDpuyXswZ+kElik}g)`YwHis6})eeQ{PkD%eTRN~Ux=kEGH^?@5d95MH% z&T3@YHxg!^KwoaAVn+S-QPAu0iP+!HRW_#J{wt(Skh4_P+D7rSW1zzKq57tPU?b5B zJaZWKt^Nq(m2;YPgiV1j^-YO`jj(m~;p&Eb=yS(7$d_fH1)kAA>QmWB*();yf7=Aw z7b|Ks-2JOQIJyTU$>n1dxG`Jbd4Cv`-}B5}vv(#v`QS+CcYn8gH)t_y(bs*c(HHIt ztsLg?4H4iwGLQT7$xF;deTKr=!B3aZ{Oy+6JfItND6`9V?!s*1o0vwBWldX0zG~$~ z@R3T8HN`5&;+3Id)X`jE7Wvgt>0oDZvDriYYKBx=-))1%pNm%MW}5uk*T=%ejIXQc zbqkc$2H^g>bH--@uMRu4utHIyN7lb$Tjr~$UFthRY&0jDjUQoLL-Z1PDxSrA)FIl- z1u(I(qnGd{}*%*GzP|Vm<=bE0>=nh9pXEnwyov%-BHw>mZU$}2n z&#CV$8VRpA?{jzFl5gh;jA4zhGubW9<~0w#jDQmT3%L)UT4-iSHVkT-J}VlwzhP!C z*d6kG`JL~RH$Gy=wJ3lWzZpDuDwOf%vIu3DK;fu1yN_6%T#u z3h`4}t!dk&;^_{2FL?`Sg|7(nVaxtvR?pO0g|ofPej%epkKr?3X6X2ke(7>jmr=mc#7< z?3X6n3D_@9wjZ!xj=QBw7Nz=V?8yEC_RAsV0NAfWQa*tFa!a`Z_RCHEqx!I4Zt6GH zhyAkTuVcTg_o8FJP|ndJH1rev&G)q8-W}C{^Tr`;Z(M&_4yt@qxvBD${bf1J{<8el z_oBY9e|nE`?^pJh-@EKD>x1ks>xt|y>yPX&>lM9!dY<%6)kC$vGM(ih^Rs+ZxvBD0 z<*dqIeJ|?!@;Q_BYvnzXe)9X3a^Uwa<-__Q<;Hp<<;nUZ<;;2|<s*^{IoLX2>wv8Twhq`jVC%sD zARRaxWoXC72Z3-D5Z_jstew4H9QH?pDAA$4RyA)5n2@oJNV_nP_UQ8%J$2FnqP)Jw z(KE22K7H31G3IRz-$fUG4+y#G5?6){cR%|!tJ$J{q=>wm%=kIuGV@-dp(12tkdg7` zBlC3I&iHp{#u*jxI~c!S3levBd}(Oti@%J%_|{v$GtTX5EzT`UA@0@OXRJNaUo2c2 zYqr05-0)vMMy#6=W`_HnF)mzjiJY@v#eARll<@%1<&5u~MbEzZ2jgCup`yU!rTWP# zJB*{tJB$059_rO|t~Ay_eKE9Zei(dzvaw-r2~lUe4keOyGy?Oa6qg3KhX2id_pC{y z#o*(r;CdG27PzYlukZh_7!6OI3F>VL%u!oWmEZaK4q*o&ex3XiSt2Y zJL7!Q*#0=5wZ}&o4c~uvsfdzpD)~*N9HEpilzP$E7}p-5v{NYU7sJ1pmA>oVa^%aV zbgRFV-;x8BW66igx8z3kTJjW%oP{EPQ+Y3@^}fpar`If|cV{uBtNGP()biDO)%K|E zRNJriE8UR|lMWxE{&0V-_xKO;QRSw}Ql1sODbKzrV^G-ZOwWEw8H4XV->G}s_vLIYCTqW>E&+)@0u3Mh54waD>lUhOk?tp3g6{^HDub&g718|#7d#)$S++WPvQNamb`cT{$->hHe% zGNbuuSfnT=k{BKPE-@1i8Y*%Y4K&8*cwp|#)8!vnZCgUrd-URDZS9&8u=0d1yy0hK zzSJ-;&@s_vNsaliW8d6gP8*N5IKK>D-?kULD&tzYBI|_&p7s zjiUXs%4+%XJ&Sv2`9ptm!TO1xRe#9J!X=FgZBLk&GxdScKW@2GMNc+Mml^?mO7(Hq z{WZP$_OnR9v6&Y4fViiM{s&*mf9F}X4e_x&vqT-@^KPVWq!RCY^JmpLp5x&vc&D`mylh1HFsVvG*?Wa13(SN&A zN$2yIF>VaxgESccwff8&4hFen8(Xo?oS(XiB&GOZk~8KmH^A zNByGmnMs!PAEi?o{Tngw1hH3N1~folKKJW`*(;PKjca~)DpM=$_xOJ{@BH6* zkM{eDo7diZo$!C-eW_zjW&1sTT<_6-Umw@|QpcLg_Iv!e-lP4#KCbtrjy09-_xN$W zNBez!T<=RAYbx9C@nd<9^rq-1I?lghvqvJf9Bet*I$-O7tpm0W*g9bAzz5I)u%wK2 z+04SQ<>1i?TMo7yY#p$5z}5j<2W%Zk7#*X%JP|Iz09&b%(9)#vi;0-pMmNlc~JelS<5 z+2hV0clNlG>l{IA9;pw^wBMrtr*!4bZ1SRFeEak>5<;iT1 zyAMC^=-pWU2b=9P;II$-O7tpm0W*g9bAfUN_z4%j+i>wv8Twhq`j@IOxn5+&;O;HtE6b#e=CgUZ-uu-cp{({sJ|qmG(qs^%qc&nNfdr)MIAUUmf+B8TD63J!VGzjX^zTM*THW zkC{<_P1IxN_}Z4x^`b2V9OtZKDx*CBvvGEq6c{P+mzB+#??6US;@ zXmTf?w2DVaNb(hsuT-^+bZ6gC<*Oz6eDai|M? z9*t*N_1_l-m12L0C0YFuI1=uC@~KJO(XThOXn2O%|L10Kv1$gv=@+WO?YDl+htKDM z3b{g<|7i12pTEB|^VV5zJ!zjI%vp{X(O1p(*bR(r)87H)bSx{b?;m?#9^CplE`IL~ zk6G@5b)*VTH&oWY#l`%FpwPzR6v<=;Bw^h%{#uD0GqLf0$%$oi(TI$ukUAstg?qH=us z7X;R!z5qR|vRaqyqfU9GY?-BO`B^DjW+_`{DO+YKTV^R+<_}rdgIjIm?iG8(_}=64 z%lVz#Ea!b@6ieKAl+Z|8UaDJzSUoc~knlaIaqQnrF*f$iR_l^$CvJmWvoXsx8?#)qG0Qa@vs|+=%QYLbT(dEM$hzX|uQ%y(ZO?6% zYkuZO6`Imsz)Gh(|I7(xLqdHwl)(0SWkb|{eT?mwx+$o?-mu)mviwz+duL9UduL|3 zcjmDp_s-06@64>uzjE(vQhVgynK{0;C3L;gx4?Z-S)G@q&*2@JsPc&~KlV#tSNU0$ z)w-nbh4Vu+j<%Ids~HSC#Vg{a3tearqQaracCwQ#_gW7{nj4F03xDkMGNJPr+@L>jY+R$6(LxrsaD~P#dE9 zB-K8CjP3WvhpgtowYH#jGxnQ&^>K{rUqNeqO2_rDpgjgLu73sXF^F;fD`<~FjO$-P zdkkWA{>AmLNqY=R$MvsCdkkXS&$)4)VD7oS9=>M}Cv?5Ck30rdR_A5OeD*+sO%g;*LGE3PqOW86@*)mJnGJnXryor&idDOTe#uH5| zo``Wq(~2`<{L!@Hj~JH}R$Q{><$m{eP)1YQMZ;IR~-csx0R| zPM33^hdpy2+Zj3c=_Err_c5#UvYh)^&T{T!j<0PAU9Vgl@c2?$ov-DZf%~h8|0deS+3cb<(iFIuGyI7nvGem*_h>;jrl{?6<>e7NzdQrd;Rly z1G&w6_Se(Rtl`W$?Uy$!_qHrsmF1qA)8(F;S?;M>&T>!9EcevR>U=Ht)GTwkr)G|?Z3$hk^f_=} zR95G4>5F(rCaQem%a8p6)F*ycWwkEpli@tl7sM=mLCn$@#4LS5%(PD;n?*`1eL>99 z7sUJ_>r(spzKna2|KszM)sIX;pRs3M=gs-a|L)$w@?old{21F$GJ7BYv-FL#Ua2g7 z@|;d*sc79yI!R}#Xx&UqXQ^o2OiX8~Xx&V#&dbs#&vt{(Qqj7Z@=!Z*J%?v&Jbbs* z)}llST`%puXuVE#sjSY|QMPgCMP)3>k}buOm_KA))JN2}xVV)!O#P;x|I`^Ld5(hRBhP3tF9-~b z+Z+C;YzXz&)B2CI{b=7vHY}h2ifMf|u2y;B-|tW?andK{#M@FAnQJaBCrbYI2Q$o!aKQS{BOv>N7V{x(aGZ*uw?{QDJVF`1meT77o(aV{;A1^3`zLNRS=>lTd zo7K#-19FJ%j}I_UZJAz7DtnE2N!27`(Wt+fu@_>G>kTvgrvImU>E9_IF+E4m6H|Fq zE-}?Z^$}D3)DB{57qyR=+Dq*wrhZU=h^c?nPh#pf^`DsJL2@A`Igz}GNq!_p;&E$J z#Qu1?g2hgYF^|*AgU>pxXR%DDRVLQuwCch(=vEuBZMxMqY_o2)8T+DJeZfBJRv)qN zy481-iEhaRWu;rPLK*6o3{keaC0qOrmdx?r!Fm_?99ZuN%LD7(VLf2IQ>-7Xca7}= zO9!yMVCe?-11z1v{(+@S*l)0O4CMiq?xCE((n*vbSh}h*$$j7MIU4zTi+m;vXwE6lCyKQWx>#{K~ za=p|$Z}RAEo{E`aQmG5vhU0|`!IWoi=9qb@9n(pY69w`6Av>Wu*JMuGcJK0~KkU`|pkmD%@@KXb|Q(Pmh1apn}Gx0!$K&cmFv)*W-uywuF! zj!!F!toe=Wy-+)!I2809bMs~;L=neu=Cw`BiH+x8IxVInCz96hwK=$v~SGP?lDVy z$Smz7v$UVg(ylT~d&?~CFtfDJ%+hW%OMA{N?L4!z|IB2oNY!SpU^m@bVZkVKA~|->54A#d_v=#(iNTL z`Go8OrPI72b(`lCvLlqP=r-FPITnbmF+$JM+|Buwu}06*+|B9ASfe)3+|B9An5DkZ z+|B9A*r&eG+|B9A*e99L+|B8V4I$am+|B9qTk1c_mSj!3%D?IVi51&L?~co*bj8+@ z4siP@U9pX%1Kd7JS8OTi68DqRNyc(qkZ!ZQD4k?1#|7ym%Zt)y1yq146DF|UlDy>@ z;kKq&UytVTf8e`VeyLGB?x05Q5>RyINbcj{eR(n8X69;Z)4;(kx0&fT{lBN2&AKOF zMShN+r*tZh$|c^nJDXwEiRrOcI@V)a`LQ0;DhJCqt@81=un=P-${|1>PO0?%M7gV`7md_-py!@>T zZvNJ0CrM)y^0a9|)rm8|cEQU;c{u-j^9M`NQR`RhVINC``DYi+Ql4ke(1Xy+5NGv8w0) zf?2oYdsfvkm1P?Ql`q@IEZfX1`@$^y$SnKL?_J7-S;~r89cwBlbiHaH--ChVAoKrQ zR>$vipGZg@n49${_u>esm#YYK_dF4>56Td6^uA&~@R=L!^EYNbSP|0m7ClAOV%#X$=`FX`$_I0u%U}b&ubKkfIshh^t=Yz=ih%B&-V88 z@JN7b8Tox3-!u%IqvyWEY994jwM?}xwGC?9)HbVq8Cqc|e06>)*L$(^P|)`*VSYSy zD6CrdC3Eb~p>SpH;&<4aXA5>KXa1bc^DP3EAFP`ZvqHwIQuNE9r~JfY^JnjyqmMi0 zIfGI5t1G%AT@Tjzy?6vW6ynVXZJEgVEi59 z9Zu+a)joQ|s*ZWX$I$MU>ve_uwW`5rxW1tmb1k%2V|^C0En0eEG&C;NQKvDryI4;M zOL~cU)8!zj`dxmY^ugl_Lf8P$In4O#O^CWwnKaHH>@4w(Cq`Ld_(Z+@h!OlAUw`*R zkNC9{^M&Tcq5T_R{_=DqC=lT}Z}aeKUzm(>5$cN^@9%Iz)D_=YQ1vatmLZVn)N*c5 zscJ*v!1tc<>LIuogO^S19Pe||?53$}%y+9hKS z%rO-9eeU_b+|{3>plZ?Gymz>KE)q`dNv4yXX_;*hyxi*frrfJ~E#OAxbU^9x)teA? zsWSQP&3N;?&q!{6w}M*i_QRg{e#uo`PqNN))^W?gBl?$r_TfC`hUb7)T^llIUr-a) zxr#Caj>oROJm1+ERb-*#tjAI>e%yWNntOJgDW*qB)@_mQZ zJnFM*nQC2X8`QR`ZC3k&b`ekyxL&lEfOeA^?I@rWXhHsQQNX4A8D|d(h4S+B;@%^2BEc)Uk&47|DZ`&8m*@i*ZAGpqCF`{u{JCg8fC^-5*jYXa{5*iPbJ6L8PTI*EHtz&$53?ll4T zoXoh_1l)6SdvLD_xaVZXy(aiA_1F#EYwEb?bSmtht)jlvuc@YU1}TDwyAAa z`-1y&9rq+$FYecM+_y91K3>QDJTva^b=(`g!`?iLz7T=?Lzaok=nE0(N8mEi7b4KV zz>K~Sfqn;O^o5w{k6=b$h>3m*X7q)a=)Yh_Uq}r4HJH&CqNBfq8GRu-?uFjrgsxZZ zqc^PTm^Vy*Dcn*3ciIqhEl_L_dL!{sLxi@~E=H z^`?&NPJR~Gp*pTdnbmpoee+}N1<()6I;JxD{?T{L>E!!IpEWc2{?TX6^^)%&eb&t6 z`$wNOGx`3}XU$B$fAm>1lkXpW*31;MLO=C8tmaXlRm)WCQrn=mO>MK<7mA6YPoL{W zfBz2j<6B(KV$4(B%JWbBUp`B*EJdDijBOB#JcS}pp~zDx@)U|ZO+}ujB2QD1XN)4x zI8Nw#)$u_N?{GOP3E`{u_v3zYRz98>H_SucUIUIJykq$}$sU0E;b%6ch4SudH&ddXDQ zOL0u`B`Xibovddm9%YqDaVo1WieFi6ptzRRHi~yyZC3k2u_J43NwFhq%}KE%Yb}cN znrW?3RrcmtT-yj`Js-yuJ5tv3LRrrXWj!yH^}JBl^FmqA3uQfTD(iVuS_w_JgR)qW}24GL|bZFwiIn<+#LPB`O#+rioY(7 zDR!jz>vY9mrz`$CUGdiiDE>NA@zxX_*pcN+q}Y+=W2D%T<$L^)b*XZo*pcOfrPz_>o2A&1<+G*Ok>$&!*pcPq zrPz_>`=!{C>}v_)l2r$ zin)^=wPNvPU+LXY9+ka$mgXWFpY*KCG#8N_r*yLG%6SH%oM#Zqc?O}JXAsJH2BDm1 z5XyN5LAprglRjFU(DkZ)^oCU(^M=VzkWN#-$bMKcXtFC-Y?|zi6|*KgWW}<{K3Oqt zvRhW{JHC1oqApb?WWTL50A$y#vjJr9tuq5O4_IdjXnwHH7|^_7ojsuWgyt2JiOLC4 zm#Y6Nt2##Z%!-MVowH))-sDlozRK!YBYSMc^vOQ zwerwD)q0lpuU46~ueIu;{jSvp+6P;0Q`@Zeh4$sN521Q#ziyrRq zA?i|PLjD8m3@Z5*th1@)Z?Mj+k{`l4%S!$U>x?V;Ev&Pz%z&@~C59Wp%8PKfpRu%63|Q0#%yDb|7U7-oufV4Q}TVjUR2VWwCI#&wt})`9UJe!mp!z&H>y#X2xP z#7wac@-I{QDyw6t|%>H~cJ~ zwV^XN#1!YDGdIj=C+W-$F~x=G%nh-eo8DnH55Ik0QFI2xd!HRxi)5&Yi4G-mS&b~Y-YLk_ONG7&MepJ+)g=n zzrzV#ui8g%Sk*CaSgr@SUvdq`Tnoo3o$nzz%Qc%xEZ1_(a*Zb_U9SC@QZGQ z*TDSlrBc+@fkYvP0Vo{ zJo8OV@fFIEd5d3FX;nhmcBvOCFwKdwVCuKnxtdW$H**wkAl+Ut2ZI)Qe`52 zu-ty>n`M?hTW0CYWtKi(X6gH7mitZayUGbsSA1hZ)i>#r{yFgW5K=&1zp{43X=VF?VJe zi)WT`y?5A~XJu@cpH*3&0pN6bHh@{48DN%Y37F*>17>;lfLWeNV3ubUm}MOE9Zu+a z)joQ|s*ZWXG9JqPk}+sz8JlL7F>BU08OvstF>XFHFJs>(+0XduO^CWwnaDE$+-7+; zfLWdyV3ubInB^G*W_k92S;jlw;e@CwzOkU{n~aHbdt|Jf*_%A^*#UK|$(TNuDP#T2 z-sDkbC1XbXtc)cwtMlgj=9g#2Sg%x;=LXqMQtSx#oUD@+pTRvRGsSIi&&f>j9Ncqq zdnnF>droGG|6m-5nc_mY=VX>=!`@*vkNT`yrdpTU2DNQ!o7KL^Gi+S1JoCvc&w?_` zb7k+aH_ytmg)9@59XWbc!8e%!8R?M;Pn9bwFa znPNv6^I)df5ym{2DRzW04`z8c;T=}z4>EwsmiKY~ zZM_LpSDX%D8|V%cw?W>Gvf4~{rkLejDrR}dido*hVwUH<-(gke|Eap-8w;ww$vZ*Z z9(h-Y*~>h1kIBj($LcthcbYhlyz9j5O&(QN^2|IxE6>t1tMlgj=EpgU?rZZqRT{vGz_SzO!D_XJGZC#sBVVEUeb zwVtQ%39!s@%}n1DV8*pHeNTWH*Vyzu0d51Xz3F=b%(y0}?+GyDTAjWpz>M=aeNW&W zPUw2oK6=Bdj(Nkl9-zD4+%I_toS9-r7(-%~cgC6JU2EO6cFH^c%<}F(GmdxqCcrzK5Ou{j7F2zcchb2%xK^aQ>dfBc ziO&wGV@=+v=Q8D8duDI)sIroGHu+h3my=nYH{Ulu`b_A1L0pc?=r^P91#vq1>*#wy z%oIDqI1RJ>UJx_IjxesnOtB-3_b^lJ2;)G^6g$HB5HtEl=zBr$u$o7GRxMMlOKpSN zHnq)aU(laJ-&W#!a`q|P?8cR5{3RK=FH*--cq} zto&vazhC(+DQ5YNDQ>g;_7pSjH|d*H?{GrY72jA;^-X>giQ6N;mBj2#p7`v5I@aVj zow!W-ttV!0@~Eon$xX{?ic|C!Z1>a%K@YF%m@)V8T@R{KJBk#vIU z#h5#N^OG54@$@ZFX0osJZYYn+-aJcl5sgoJR%M!t$c|Gw%|&G2iD@oU&NI;WR5_jI zBIP^-eNUCg6wO7-c?SBPDyP$2M7l_2s+`dEs(ti^RUPw&$xe_?Q@=0Cr}CNsve>06r27~`gIY%*i)o4&ot9ACW&QI{$cJOe=AAQjXXJR3mYCgpdH zX9nn-rObGifWBqQYg9aAK;Jm!zT?>g`t~WepXL*?^;C|^2~n4-|0=6GhB0yaCMUNC zW99U%PG)cN#AgT8v4$~y`lcwCiLrkA)+n<#c~tqxZ`Sd%7)zpW*)gm0=KJQSy(X>u z>0PKydrjK=Q9A84>3eX*wAZ9PCo%0cY0pVadrjJN64PFj_MFVP*Q7lsG3_;J&q+*s zOQZGwu_OA19kl_^rqZ|ZneogjeKVimHJ)XqZ|O6W zf5JNBif3Qx+xy&i@@LSRiONwqA?i}~Uu9Lt@JuFs6Q0|HXEo_t@yy=jiO&wGV~zX) zmETL)|%uyw%J0b2)b9k6x4)&W}wY#p$5z}5j< z2W%a%b->mETL)|%uyw%J0b2)b9k6x4)&W}wY#p$5;Qw_Up#DWeIsYjdQM=~?^%nJ*DNN6%9tl}F_gA3oI7 zuyhL3O)DMqn^u0zCaiL>d|{Q3zlBvV{=2|@TqZsztaf5~!fHR(BQCbyP=xB0=_awv z&n(NKvJ%PinPt7q_)pXxX4y_=*?#5`bE|(%^-(#pzgB*d12g^;$%k3WjhXsK_0hBV z?|{FUNgh-mrIVbfK4MFL7TfRcV|;fWU6JpQ-?z=SOl%#nb->mETL)|%uyw%J0b2)b z9k6x4)&W}wY#p$5z}5j<2W%a%b->mETL)|%uyw%J0b2)b9k6x4)&W}wY#p$5z}5j< z2W%a%b->mETL)|%uyw%J0b2(?ULBy8M~j0Kx)&ufhD3C9C%>gl z16cQSPEH?kwJRhK`JLP5%r*={yDwz^dt4;Y-}$3{z5Uq*i+88wzt<2we+=vlX{=NF z>?{3YcBNS6oY~qy37-@|=|_$NyqZ#+`NtClVCw67%u9Tq={d%9V$Rvz(DT&y{Oy&; zl?v#uuX)bicRlb~%v<@lS3(VYmowlLTQVa0{@vg`=#5a={@{z!~b&c z@;q%`mi<;{-`$;^ncdL0xqHTyH7hkITq-c1>^rj@;a+tr$^#yG2*>Z-QeK_#mfCjV zRu5UD@dmr;DDQ3 znsv!#{n8EbohFfSWK!w=wl2QkB<|%%AX~Pqg0^AVx%G45x#lx`?@6{wc3DhnoCn{5 zl1X#!6kSp#AzOT!b(2Jc(&zErC|T)LS;4PP!}p}*rsLs`3R%(#v@L&EA?u3bCAzLq z>2^q`_n06*gZvEb`%n&pa+oTgLHYC^6V%I~Ui39!dl{5sFAn{}bY`VPznGOD%HdWy=<~74M_&;1i|R$+hSeVQ9a-%}pAz(o+K;}URQd1Z z^ZBJvew9xBRryH{svMG!Dxc)0>Lq!q_K=)aJ4ybk{WLE4wv;tqkl&0QaKMb6nRjO1 znKjd_nP$I(Ez#&IpgaAi=_j-_Wt>F26mOV5m&BdVR2 zo*AY8Lz|;?OC3Ysqw?tAsy>qLs@J9ZNV+b_JgRMaoAth!GeXqZ;Th!LJ|mcU=R7Bx zd1uZDYA^UGXLB>}%)B%E-N(0ynR#dCotbwZf8LohLe#u7egxwKLf_Cw(le8XSpJ}o zWLH@Mc9jsNOOst9HtZ_-R;JGXG3_cXe|VJdY<1sQx2qgJd^T#l@D83CJM!QCTQ;%( z-(#nbqgR_GtVFwH@=A^RG9b@bHhx-S*>qA(DRUfV`zptkT{Bep1CA-b&XbQ}bIaDK zyyp_P>1Z#FvN!5>NTpN#+kW|Na3@on*Rk%G_q-C3ug2YUAHgsG`&`!fV8-#E(ThIT zIGXYLw8l%HYdSXL_-T!!8Lv-ky!5%IV>6DQ?l_wBoF>N?1~=KqMy6DY|p zr!|gdygse*(&w6v%{YF#<7jMR#wKR$Dj&zL0%zO5e3u}mbcnkaTHJLMKG~~SK`Zti zVz7l4vn{NcZGC-?DNju0$CM8D6Qg4OKeS9&zIB^g4CAZmJvW!IOTQCF{~aGf|xCeo4#$VytW0vSq6h9FyE$rfZTESbYt2x}~2qfEW;u3%^b z+O7?MKv>pT>vGe_$Q7)A>*n_LN8^vOY13Ob%GT}jTaJHh^Iyy1k9mg5rW=I?t@O!s&6`#!2|v?jZfU;ow>jOF9|oyZS^jT{UI3$i)asR32bKwWrPfZVwO=l@)y$81@C`_Q=Y35x8S`TsGG5eiU-_ZDG^cI*PN(Uhw1NY5;LT@qi&dfWd zYg@cB`<>bE%=r#DV9s|@=lB1Db2{#H_{VuhH`vI*aKLcDaKLcDaKLcDaKLcj|HuKd z+o^92CP6rTeMTlm4u%7U1BL^J1BL^J1BL_tiUa@Z-%)}lkKvKwfZ>4QfZ>4QfZ>4Q zz(2)-BZtpo3^&>E(D!e}sbd_P6{ik$VO%)n!T2jHP90;Kt++iEH%@slW(&TzV(X*g z)X@(;WbkIF&lzuQ#i^_O6sNArk(fu7PgvDU82%|LPF=N=(pCEjZ{K!prRDdAbY{gj zW4lyL8CJnneH7D=^4`J0#!m9m*eSMNgjhBwiI6ChwD0xa0=6~`yn(_Ly#!H`TIyU3@X^o>9 zuTN{d^tq;EGmf9uIGXYLw8l%HYdSXL_-T!!8Lv-ky!5%IV>6DQ);OB+`n1MNpKCfc z)u1cyn?UHKKl(}_vuCD*Mqsh z{7qXGlq<&s6W+2tw~V)O5#iS1x#VX9mJ#l7BBzvWCE>$oa>y^=tsy+amQn6`8cBF^ zk>N7ohe~qyM-Z- z-O2;s+O2P)OuJPk)MdBof;KR#4bV1bwGGqRK_<+S3CN0B zvH}@0ONJm@X2}+Qa!cm$@7x*-_>Nm+1m$sS?4TZQjVaX6t+9r7af<`cUT$#%`oS&E zK>xVKCFnP|I0o|I7WY6-+~Oq2k6T>TG0HuB|4dK(`O`38`J~fN#8v6;C10iPPWmDH76nJ?MBqY-pE>aK%iM#lRu?2v^=*Q1tq>7~y9R zsya%{aE|YV@)PZ;y_`7RF&lff-^rP;vd(5Tg7Z@T)=Q5vxAo}>&kz2Uwb|n2ZI+U$ z`Gmrks0}A_=i-xItRNgVyD;}_8c100&R=lFR z6yFFd9uijkB&>K#Sn-*#;yGc(f5K{B5LWYru$o6C2Q|M4t9eIQ%}2s&o)T8`m#~`G zgw=c}tkwa-YJDKA)(ygHJt3^t8NzD)Aq+Ccb;-iGURil?9V4vPH^OS&Bdpd#!fKr) ztkzG$YF#C))?31A9VV>SXToaTCal(T!fKr-tk!?RxK^R8kteu@p{x<(+J>@5jB6gs z8ZoYgC~L&HMxv|{~r#5z68#~%ha9&{^jRUlw;5@{1jZ3tj;Jn3jjZ3tj;5^54 zjgz#W;JSe6xNj(K(|&^M2&QY?rnN`S1;o}I!EbTzru^Dm!*6l#rgUwtVHgiZITzJqm0$OKu(gpFnzkM1pjRGXyPr( zTg?$_Yr+kcaUcH!ehlRo?oacMm+>gX^RMhjee4;Y74q#MTzZ{5Ke+RI!uS*a?kr~q zbLJ~a-{JR|j^$ywh{N}%53%ZmbcdA=^$06J)FZ5NpnPGK4?m?1L62&;AyR_!MoHzfWltPk_6{#yAN z)~Cur`4CoeBaHpS`Y?~P-#ZASJg`1YM>%1A&T>jpyz8H_8ehtz#+|U@31P(_!ipz^ z6@LgTzEQo3hlCYx2`fGmR=g#w_)J*wpRk%2gw;GEtmYTV0p}C0S=cW%zbKEIkCd+F zDPc9Q39I=|Sj}s~YQ7Uz>jPo6ZV*=M3}LnY5LW99VYU7cR_m38aZe|#);+>drgfIF z);&sxGOe?WwSH2%+S3WEb(pZ)y9ujxn6TRG39I#-u-elJgKVv{o3&q%JW3y%!jY>01C#nNlSHaq73h{8zUul>Y_T5v^y&xUOVqJP0?AQj?Hfn=vGskq*7s9HKgjL@O zt9C}isxKdH+>!9>>uGq+jdcl+zwg7pP4^jLKCuQL{UkHt zWqI0i$LlB5_oAM?c$WMt32*Wm#4q&rCaiN+$9f+9TfI!ZF1-zU+w?Z;ebG7p0_H`7 zC)4)gxFD|oWLjy&I?w+C6SrgfR_BOa3Icl#ZF+O|%_722C->&7*DoaO2<^>p&RP%+yYg+$_P*k3dgt#l((zC0r-dzl z9!z{r*ewN1G{U*&&j_E%h9Ccu(!H15WOY4-iosFFdmxJ|c zSlR`&7A?LsfY&YDis78vU!W7O6Ym<~E#Fq*rM6|~nBH@EPF^RdGU1r&jg7i=nbgf* z&0c7;lLI;WjAzCB_N8%ryX_epbfY!lOAQP17VkLWg=cE>9D~vm{`po{J`wzd*cUb5 zqv6=7E2g=i^DV{BUfk{UGHOrZ(!F`)cIW(ZB~MK2fIio9?(EHv?QzaWUh+#`f8JcG z%auI3tkjxG->S8gu&!5pX#P@refZ)s&b3j;O*_`$7jik*$@B@^^7oyc>*UT(bkxw@q)e-j~REwfL_EGg7^$f2zejwr3zbr&4Y1&YU>wg4+D> zK__o@?8>+Emi#2Dy=+5e>iGEOmEy~Uy(m5P_dcRg7UvpU(J?8^=Y?}lMSh=xtr+55 zS5LalV%5T(>+0c4H(A|x9q8MMsnha2U+tY&G_Z!@d;PT*qeusT|!*Cb#(|Ym482-9lpIVn4kV8KErjU zarz$o*Iio(|5mvX|1Nbhj_EPg8yj`$GP(C|l(?9-AGN=IPEW_4BhGQZ797ChuK$YC zcYbk{Eqv64uy3D?e0958gfq-7%hw0zC(L0!w(I;8^ob&Pcs5(4+SURf9l{~t9(sXIZ3uO6$m24DrNdn3Fy{%wT<0+7X`O_*&SB0|8(^+;nDc~T zu5+04gki38nDf+MnCl$oJYksY9ON4f>v{BV^)mIk^fu^i)7z}~1=d9lJfM1Ez2vZN z5{7k@!+J^>)>jT=6AioaE$l@S<|lotW7vx%tmBjpdy#>q?-FJiE-5Qe>o!G1#+_971ai-u#nUcHa5V4Y*GU|1&@aGLrB>j#H* zgfOft9M%`Yu-{y`Y_6Ao*AG#nds#WWXmzQKCNVO^v4 zz&giay(8>Oo|x7FeXhZJ%wb)oGGU$OuwD~(C66wvGS7?i)M@?bTlmT0?}YVz^F#B) zS(Ag_PrTAGoHaR|{b-$pvnGc#Cvg(anjFrYgyF2o;mk=G&YB#~oYWpTYjQYq5{9!T zFS^*dZopZS!I_iN;jGC(zmJCXJo>kKnR;D%8}zp6ZPxn&=W+&T5~>%@>kQ8Agy9^| z;5<(l&i4$?2GOu9--0bf!ugP7qGPayNU$SNnP3Z%U|%2%wh#$+2f|XOuii&ju+A}8FxsWyOhx^I^DBdM zEMYj;ayZ`-hVw3mb1z{y2Xi<1F;2-Hrn zD@d>}5C(gL0J{TWutNy2M-T@4L;%<+2!q{%f&GFo*fSXDOwn*`)D_cQ(D?@EX$I$N zY7d;V8JxEXyOJlSbwHnMU=Ltm7oal1PQbukK-iT$x~xFoWT1D_x1fhI&_@aD`{sw{ z2j2?^J1lWb$7uTp+cBl1?H_E`gwgg7HfyREZU11iCXBX!uvrsE+dtT>38U>FY}SO) z_765|!sxRCJ9RXy=h45_%hc=A+n~2iZ?oPP^ofB@pXvpB|6Z`;Te!4^Ay0sn=TG=w zev7^=O`cI0+8{M~N==?plc&_=DK&WtO`bxNr_kgXrpYr3$9BCj_4jYm|B`Py_jC+? zJOTD88YA%U*}>0882o+=d~AflAIQPSMi~5r9DHnq!GFlX$3__ZiX41w(Rlt5>Wbn3 z`ZldLpl{P^8~Qe_HluIT>I?cdtv;e})9O3=HZ7UxSeN-fRo9>RA2lyv{zh>O{K;Y9 zS0*`wpE(qKz=U1Q^Ox&@K2OniZIy|>YpX6-^62tG-x1h7scq;x0(&T7ec$}h{IF+n zO<#(_=sVK%C9dg9T+^4BrY|u~Ut*fRWYhE|q3KIP)0d(!`j@Oc=y$TdMSql4Ci0uWwlxF3;K>M-4cCAmd=U3BTE;BeN9+8s*YXx7IYh_>GM$-eMg!; zFExE$YWlp?^m(c2^HS62rKZmdO`jK3$!xE?o}jJF;|O^c`8cG5U@yof&;cmM)FHBTL6d z-;t$z!+aN(POjtFs7vR+j?q_X@eO@PmQIMiBTH9wB@gzHP*vuXA^q1o$% zX0H>Py-sTOx+skPB`Xj5ovd%sA7zz^ek!Xj^j}$RK);sNHuQH{ZPxpOz9Y-FiM}Jt z=83)|%N7cD6=~T>b?nNwU|W-#Jvj=a??|&JOU<4vHG8tu?8#EICrizqEH!(w)a=Pp zvnNO4*seFG{>GFZ6W?M=N8gcU>qFm>WdlUtk!2f1-;rfAMBkBROGMw1Wn)C&k!5@Q zn04uLK;MyNgGJwwWt&Cck!7<*-;rg@McxWe)t}9kuxZYT8z;(!Ko8D%~VT-UXD2C2m}NG+a0YVizGi)WBpJcHEY86?Vy|H}OxDHvqY+Ro#A2+UBmhU^JdSjz5T_(7GTQLB*u3NDI zxZYba1Go=Zu>`n3STP2;Z&UaC7y+_d^`_XIJWE6`{)YRIpzw+b1I&xuwQt7wPGOg zTx-Qf;(6DKnZ$Fj6-$ZdV=KlI&&^isWlZ(PMqRp0(0*XWprT#DicLj(gB7!ib_gq$ z73~vNj4RqLtk_qyXQ0l6GSP8t)TQ%Z$2!OGJZ;5f;yK%j)pR9~KKFI3&o#6MSTUt! zCs47buH@0>gZicwvxIu670aaWn;)7VeI00b#<9>b`a00}fa&P#0DlZ&^mTxrhA{d% zz<)y+eI4M}A&kBb@b}R8qOSw|K!nlP0sbMv=<7iHGM2AnJ&*paUZ!4`-UhvGdYkpW zpkD}W;#e>Gi>x~%h^@OMDi6hG{{{ZrZLX#*cZOvu znGja8BCKRc@e(?Y?Rxb-egKx5eEt@rp9F3Cm>>No)*UhQt5|o((BER+DMLSub=M62 zGu9n6^xIf>(^Na7)fC)zro&r?+<)vM~F{I2BD<%9N4w0ol5&<=|BP{jJa`JwsM zo+Ysy9V@+s(v`kM82vLCbA$QOZ-X&6^ex2NV9X6-^z&fM4PjU(G3Ev_`h_s&2C>?k zqG3G``i`t`^)k_SWYwj&L2sMhX1yya+rGpVJ2lEu; zdr;0wXA_8(E=O4DcoNfkEfHKo&1IZD?h>`ES8R%*?pZ`E2#Sgo0a zKQzCxnMmZAj+Nbv(v`hVU>@|(V9YmS^4mbnH)8bXV9YmS^z&fMH)8bvV9YmS^b29k zH)3TQA#Uhc&!c~?+Z)E8i;H8hxu{WrL-3 zWt%0eY_^1zEtjye@e)?HU&6{JOjy~92`k%CG#uOY>V0$t>l||hD|;06OW6PkE88G( zN!biZH&eDmfgDpdM#9SWC^0>zdSjz5T_(x~OYK*-S;ER@OIX=*2`d{fVP*Rztj?R% zcOAz@T`|oCoo~t}No`ZMO2V$>(dWL7^|_{Os#K=3wGwtEk1ii|W+%C+vpiva-~7=0 z%4bI$)3Nf~QabvMV9pap{|wA|S|`zO19P6*fc_kq^MujQ19P4*`hQ@~Q-9Gf1aqFS z^36rVdLI2-y-d9>y$yQX^fv2#Q9eYfSNYrtD_=Ze<=2abUHMk|cIjIks~7-ESFr(v zRm=ck6-z)^#TXD)u?K`zOafsQt3X)!F{9zwu2=7)D_G~4D_HqMsb9(mO<4J+2`is9 z@lE-%2`e8r#mp<;x4`u?rg~$eE?p)n27ubEVgm@Pm;u5nmVmH|F(9mB4+txNM>HH8 zb;UFnbiOH{IJHOl$_cxYC#H2kpKHpePh~1!KVet$=(18iBl=ePk_hYj=7;82F=NCl z9jmxOS|`zW1ZPg-B>HFI%t;viHgM)7jQ$)rb5eWI&jV*p!s!12KM-N`3&EL_u!;?f zhV?x9w|bd+U3wezw&`uw`=Vmls9qKGNm#{#5>|0#(XcDus@Ou3iH=naDwU~XQwgh> zRl+Kkm9UC&C9Gm!39Fb`!YWplu!^ILhGV;4y^pS7onx+G6^}>#QZbN(Rcs_-6*Ea# z#Zr>|Rg5KJ6?;iKYE1RUMqRp0(02rO1Zt;>O(m>iRtc+ER>CUAm9UC^C9L9YqT$%6 zE2g=i^G(HMQhQXaCSh0d#Iz3Rb4|sRQkg2&l&~v#bXlpGCHhvyG7;AI%@575?ko_; zbgb^JP&)dKz~@02eMjK)pnB1F1U?VK=sNy$yQX^fv2#QTHjRUi2M--^jvv7m2XC*YH;u?_XH?|MFXqA>OaCPxu{Hamx{2uV?|iqy&|mcWD!<(wFrYe@g7Gs9NYEA)Zf2J$NM;z zeEua?_d%#%>JAQJbvK8wy0b%A-Q^*y?)VT^_i_HV-dL(DiUZIFyaPpTPsk&mC3p(G_ogiwDx+_H3#XNYA$;uyv^?9o9G*KRP z*NLzzd30H+n0fkE#nKbj_stK@4|^8g*QPPmG3YILUz^HT_q7S5?+E-fgwb~d{u{#R z&jG&MlHC*w^rmd^GIJx1ihLdjbN_i8=-y7~d1H^m%+wfMgCjGrlK47<6fTPk=D! z*!Z3RwE=W*d{2Nd=;ZjG0AbM8@jU^;u#e+=0?}}6*Q@u@6|8g26%6_S-u0$_sXO3= z(RTzsB*N;>IAL{{oUpoM?o4;yJtrJfy|Gc3E)#VJpLAe#H=o8@-PtFs?($PR)g6Dr z>h3>bnD6)|Kr|d1b;UFnbiS!O>C_(374fb*VOR3Rv<~QVP2H)dGSyvs!mi}eWu@+H z(zog^Ct-cx{LuVhGr{+Qs2m-G-3;FgqI9s=;d?=Z(RT!X8p7(mAj0T70>2Jn^c{h} zhcNn%zz;+ieMjIQA`G?>d@m>(*7NA!>SgM6>21*4rngz|3)pk;Z6&H#y}3kKy~RWr z>?-(1Q#9<#w_sc2V8<8A&K8Bi28-`mQM!5?iZIx0@jWZco{aBV(L4ehFTQ6*7;L}z zo)uxR3FCWK)Hbjc<9k+w!H$IQSw+LKU2jbNjVWE{m@63UQTWyn^-H}$L|DB|L|DC9 zL|DCLL|DCXL|DCjL^!5;W1}uz4(bgk8h7Mbe4>WwLCvwC}qFq}8> zO{!=(HtLFLF6ewyZz559)LTh}UC9&EI-t)r^`;Y*sor`b>`ES8R_e_V`c}OqLRjB7 zKQuqib(A~KcOBzg$GL~;=sUtWj~M4V&UwT**TH{780R|9c}&N-j&mL{&UKvgh;gpt zoJWjv9p(FHtmo0c)yvfD(%Yc7O>eW_7hD&S6Id_!-0{s%!r+U?w?GNw`if(Nd35Z` zx40MK{KRi{jC&ET|;*De0&XV}Ng*Qr{u= z0N*~P_TzqnYdw~uLlz+o|x7FeXfB|AKw(EGQro6 zZ;cXmC66v2^=2J?3%(?L%Z{+VZ+>WgJZqxfk7J=@JZs|F57Y6iiSNN7#m~!2-*=a9b!}QJ%7Sz z3(?|f@jZV*-#Xv(CycfbEuI$N^Cx{3Z6R7bExzYZZAQC@g=4#3y^pS7onx+GJg4HB z3S|N@koX2WVTg^yx7mqT5HpEywiAX}N`~iQ%nvb^_{KY7h`qGq`5Dt=sy8<3(q)3a zBYeXS+W@ht_%=Rah*`xq^J%OhmKER9Cye$9E5;RKU-9jI>O0yqP-nt&bQ~LX>HOER z&M}C|#5duoJrJvjZ^aXKB~MK2fIipI9)NZM>@UQT;#>EGUCE=%2V$1+&1Cu(VwvzQ zWy1Qt`C<8o5}&YL=J#GXrC{V>z<{E2_ZZ{ZJD z`P}e3{2mjrJS-RSk;C;vEKWhXu+kyFu<}DTX_W)zORIeNDXn_p-zDUuGT}REwG+yd zR{NnId8O$_t6!Kdunj6dVO0*6<)+Fftm-8U|Ag%!tlCLfwV!a`S=CozeOM0GkL^IL z`jZ6#& z3&scu}4gEaSk| zgfle^VOgp=fA`8$zZ~rCZD;I#yT~zN@73>KslKX=*xKFsdoJqK+#!~J{sn!TyJuWk zvr==yr2_NGzB9`a?p3FvJm8UsaQx0K<<$vqscjc-^^i3hZy@aFGf38cUW_n~ov%-F z8oNJZYfM$FzQBIPMoj*Y!J9p?ZY=*}#N=<^c5NlrrDF9-4l0J9u!`*`8LF6n!s;#n zVfg%C-l1rBz&Ahii}I^G2!z$$1go5X;0}dZKXE)Q4jF9t@DFpqnybh$gGsnX4vJ%j z5C1kFuz=rnNTYA$B~Jb4>Ko4SGI}HF!~gi*+mEL=(l~O^^FjZPeSH}8d^l%(41L(i zPtfx}%AH~uuaA1C80H;~7s^t{W*q;$`^6t~9M`QaBv+nfw9XrB%F@Tv(pxYCywb>b zVR7k=mE#sGCYRgJ3o}C9awM0 z?6S5MXs?BI2I+RR*Ft^<`I#z*K{*WVwNO5T@)@3=pk5C3;y#P*;m{t^*P)#p+KF$q zVEZ|=pXXaSEg$a5xL%;W)=Ecvt(70jkybhQ7K~LszDZ-%3+<86FKQ3k%dK|exz=hw zo_G7c&Xhmx*~Ix(I`voOCpoBcNIt53lAEfR z3;utNUAOmX_|;j?-%I}Q;B9+L@btAyl3to2dtIJ*U0TAs>UHAF>RlxttB&z(AGc$W#IoIpkr^DO+Wgshs}+23rB(#ZBJoH9&#`I5MLzZ2z|S!xG#PKNX)_{^uyx;9*? z!)v>zqjX)KI@a^(-|A)Rb?I%;+orc!?~C3?z3;kAbXn;#)Mcy7TptU4jP$Y7$5bC{ zodY^Ibk5+oL7O;^UABvtMa}h2{w!c)M5XVYywdrmV^_Y_^SFrra^4LbT%3E3^P}<2 zm!UR4JTwF0u*4ns4|~5O9=;C!k|*__MY!}ggLzPiM1;S(7R>vcPe^=D@!LQiv8^h@ z{=P5w1;3POC*dOTTJWsiaYzmc!Yc3$$DJ`1sWRs09iNt^^tyNA^8+UW34fMDFz>D1 z3AdOU$PQ&5NH}0~b^8w+g9&f&f8Il1}h!wLB9>=fj>B=gs~p0eEezEtNxwx;CEI#u{qB{FgH3o$6{p>GOSjZA%_gVq zv~43Fxo62|l&8w-8j>H$Oqg$ID}8@@Oq{HGwwJ7(dl}*Sn+D0Ns65mr zF~sNLA6GE-g*)@>`1f&9eP@_Q$%L?y6=5YqDo4qdu#!1pH5P=`7!g)uM_7$1VKvr- z6$c3GYsG(F+jJTJJ+{_O5UUIG#JNv7$H_IDf!YV~6D(iJ&Lxa%x|Kgh{5)W^6_+Vp z!CHT@OzG^)@B0V*{SWERe>ZyY|EL@+{z3O$l+}O!IJ)K4VulTN#!(wN7&&|@99V&|$ryVF%Z_9cXX?3 z=SLb8`!mz7w>mQI?MA@6k#HrRna(bQ#BH&(svHUa*S z829}(QK^)tJSkJlt;DZD{NZsTf2R<<10|P#A-~$6bFyI3RJ}}?| z13qxz0|P!V-~$IfaNq+6K5*az2R`t>kwaA9@5#!dl4pQy)-JznI%;cJ@^B`rFDWGR z9LvI9&9cda8wPABFTN+5dt6wD)2jta|_ zC@3s(g2DU%|K5IO?@9aE&wKIyfqhu}-pyFA9<6!xsk@kWu@!83NM%0i+aKA?Rp(jw z;R3u#-;~_Ft{YEwJU)+?D-ZYn9{T@ptOZGcqx9FdQ%(FdQ%(FdQ%(FdQ%(FdQ%(_!k^-`lg)sh6bcLg)!U|TU~j4WC+GO zW6bit*E>U0th0P^d1(m7I%AA;sgq+u@F)J=w@UpG5H{Tf88$jq2!2Q3@BexQ#yVrU z$&PNEaO5!N8!9X8|2i+mBV#(`_ry45%n#+@*$!iwv3yUA!^QHUUQdjt#`>T=o+{Q^ zLOVS%)*0)A_IpBk6kF{)4-JL)GE=Y8(wUZ@Y2|ROe6H2Ywf1nWom^`_ud!}(^35q5 z(eF`$bgRFZ-;x8CW61~0x8#QPTJq$YoVg}{ri}};#tZLPS{UzOYI%hAtrixsIp|$f5>r9_<)012GqqY9x z`eV&gEXSIse^}qNd5Y_gC1+fJEcxU56SaO?%U3ykrDtJhsb6A0GJW=#S+y#J^ZRL&TQP5HaX9QSUKXK0{20KT+?;Sw2Hdw0wq$ z;dfN6uo3=zX0@);tqe1?com%{oGTRua?md_Beogd#80r8G4XzL!)H5BVT@Z%zuu}*J}ZJY2*OV(y} zA>IPoEV|xjyheLo_xeg(kwWP>-&BWR9K6?d=CC)PpR^QDy6lK8aDG*OW^p#YxY|YA z?jbFCvCF@);)lMqZA$b7cYL#xjd^g}_G^}b{ObHBY^(Uz_OwYb?|Ea4{b&D+wzi(o z&#H?ZwlPO+zKaL&gU{NCO0D+V#>@`l<*V)yei18eGf%BzH^$`@O@{^XeGMD(#+iFI*6Qh>+@#eYn^T0#H#GFt+ezMjE)@)ir5pPTof4OQC^LYJ>qszD; zp6PQhe#ot^*nP&2Z)@J1PtUqe%o`WZdQIQPzHT8L-%JYP6SfxRLD{p5HTV5^u@!l%m}XQl-4ID>YwQ~k#|Zchv1#S{AQ0JjT{?Qi^e+1BlOrL4Wg zdCv%Tu|r3mYfK$cw_yZZ-)T3yw5xz4&#WNc=W}1a{Xk2{qLlu8l1FFW@On{^bwmVv z^?o-?`uJX08+e1EYTzDrU_k${9rJ>?`?tQ_d+zAa<$3&h@0nfrj8zvLL$5@zj4itI zYLC8lG>9L`JR0s{=V}(W&0ZYDH+A&o(~jBgU;6v=&GIz7zZZcPv`vY;qGP$DDi80gP^H+JC@=k2#=*a!LFY-hD$}DaAgKYSoLcGW9YHalbe_rryPTto(hdl+{qJ9?MY4m1RrSc8^zV=etPuJpR|LL;d#b9`wEMnMo|e*&sG}Nf2K@ zH9l{g|0gympFdxffb%L}y7L_2k?hUQQharT)cnx0NOtq?NY<+JFy@#a#Iu!p$%eI! z!*`|e=W=)n{`zf3UNtz9*$NM30r^L>o^ylv+zEZzp}pf-ahNLuUf*F?+}*i+=f{(0 zEy!!F&&%T!k7V|Ad3d)ih4_5;NOttQHmpL+>FoN~LHup&ldNcxG`!(MKOS%{E1w_i z%`e`JV1wKnvnSnVvprLR&*!T%QFA_W~4&^YboT7eB3RfHISp>_^ zb9}GY`0Z(^t|~QGX7GrUcRi+8Y?I&XTJI5s5f@o@%YLZ154EA~*Ov<(2`Ww)(j8X% zFH2kS*N@(d2dj_TBF}j6W06}$Pn$pACF9v%=9&{)>!P-_b(6 z{0t_aC%S06{M?=IyxT|)NO{qg#Nz}@Ql^V+c>Ij5Ox0m5ba6j9Y}jF2NWDY$p4*4W zabcl0k5RoG-wp|uzh+!(YqcbYn0scBOxtjw?e?Rg;+Gx$B=$X5narWpOQ#LPdUISZ zA)1F3k;#Yo@e_w12DJEPUuaQCKRWkNz=9v|gn9#>QGRK_#i4FtK7c>F{CU9M$4LpF zx|uYf*xa;)mp<|;eX>KwFwDOrZHv7rYh(;72G~6$*fF-{F7fcIAl@u~S+Q?YC)xkn z0XDDp9QKUY7Z+iEwWwK+r%s|J^FOK=~*SBAU1yPaSrEi8mOEz8RBNj^3OMJf!mQ22BJxEce|{iaMRxIFNBQP_1WVrF zbN2Ir_VVa&5$yX5ahdDt&nK=D1ps%yHIdaWpI3fY*`F_)yp|nH*Id@97|C8I3u9mOYa(qeBU#Eh zrC6DvOT;2r_hwI9#oph^ChJ!4=Uc8EXXn~9kZ+qtvaeECVhvU-5Y=E`$g{W}%QkwB zNVq(Rr;oFbz1@~UR;lmL7bbqf`h8Vh#_t=+`aF8aewbZJ-W?Lja(7AuXa2JCW!Fen zW?C2KJ7!ts`18vn`ml>v#*1-KX3{JfxJPC`xu8cRds22NYkz)} zh!1_qTI(@OGB1Iw2zB{*WaD0$z2)vNBH5!@BTKFK`} z9~t;k465kQmo}Ng?xpG~epnjBlh=3W*J|7r1#9|quS?$iLhY<_K;=mG_!_Lm_Vh9# zi)8!Wrs2(792G|@`SX<>BEx2;1J0cH;~|aX*c;sQm9w7s@h%m%+B?nhkt~rv@82dh z8(p}VOp(=}zqwL{En4m+FBkFWIqL*7?|1oRBUlGgcAm!y7tbXlpv+q@wz0dNJY>ll zuxF(?#Q2gqer+K9?S_Syoyf~D8D3mk($-z!!xSUz@}V1EPpUV?-J zWn{5H_BrT#Wq$~gB^vJ{eQ#d%mh!~Jw`?%zdu>`&mB0O%jn4voZ`U+$S-5N|er)s+ zTgim!k@{C_viq=XmtzRj5m@TJM$If&z zW7x9gPCYhvNcOOH`JDP~vlqF-j^?OLdhd#Bxx(s{^(K8dqF(l}+=bjpPYx`ZF|17L z&ZIwAjYt;uc#2c64sG;4bVvC^q;FR%ax*lz_z$FqSN04GZMw;+pFb=%J@ilor{11m zU=}%6>G`Kdr4X&ouVaCrL%u7#L(J$E$X|iJ`s}lnqGx0_hWhHh{p&=%<4%3Gp7fOC z+6*Cm)$Kw9c{jlkb{O>4opm;g&?aZ>sIPAOxtUyg(5bIxIM7D6T05Hc27UFrQ>#S& zQ8~pBs4KitL-{DpG2spR>dG(1iL*OB`54ew-BTbIzPh1u z2{CH?GKTu<(poU)Z8P(ops!w9dtQvZQIF38eYN4H>Y{P0`D{PvtA~6}iYnRC@KvC% z7O~$IV>j309YJ4RezlP(J7P9NeKpg@He$wr>FgHht9e83h`9ya`8Lp3bB~N8pUtVr zPl3LgaA{&$bz2!;1N2qD%6&!8o8uYkt4W@`5cctL_(ITEi;hYu_e~Gr89`sImuRSP zt2dgVzIs}W6iMd{W2moY?i^nZ8ut@h2KuU7NLE>Uoi`r{`f7(;xn=mBLcBKUtMS%M z65-{)V6#A9eX=o`thf0Z>kay9_j?6o?z?&UL(o?nT%9Je9c|B0UtMr>rbzUrDVqoD zQpT$3 zWXBxRS6i&Ypq3`gB53d7@?}(pOtO+%9f>yU>pMs#o=$V%4w1?WnI7|Jhr% zJ95Z=0rb^uUv!ki(^h4#KwoWDeYd#Z*~5P*;k_7*BZAGCo_CR~ z)T7;EN{hob)K}{O2l~db*-&5Yea%;{nqD(>FzBnn%e%@2PjShFhP+xuCX}5Tg zGryw*=&PfW_{iC-&pGyizPjO3SDCU*W=BHMS8KHCDsOC_>R1Z;YPKOeMfV$H9jLEv z+*wqPS)NTa0)4g9{4Vm%%5#oups#ut+9BffTJAu7HTA4*V)}E31NGI7-MnO`9d*Pv zps&`=-C0ItEh_SWzPhe^N9l9Fws;Eq>iadDM0NR#1NGH@dGpIbJBNvjpsz0J)LvFv z&{I4CeYHxR4WjChgaY-|&)c?=l>+C9te~$BY~5TQO|VW31bsEfg-(Q0HtSll?&pec%QsHtoMmk~KwGjm~edj2IdSJHt5A~Ju)h6+4mNdz-QPXfsgF(F;IMGT#=RYb5BpMGfbABx*7jDgw!fI$LT11HUL0=r z(gu36wDjaUlfGO5v3O{|AnpzhM~T9 zB}3u8BffCzZ^zdp4Nbbtsn^Zu+aW8-b4@0Mg z?F&VH@2!XzmP_fhx(t(EF2PzVJu~|c`|Y`p4UvgH53%j3GuYwQD_BCzVR8R*+*K;J%c#zTIi^zHVo=ZF`H>WgxqOBDUQl6(m= z90q#SnH^Fx7? z#Sh)Pi~caL&(F0>F*}*`ED_1JwjU=N?&&XvL;fM7{bb=4>E$la-&UOWmA(l*rdUO)0 zwoe7V!ulNay~w>Ikv!VSpT7>sAwMfvRJMmTvv8$M@?517a{pJ6>|&YPV&3?t$V~d z*ej=cFh_~?pyxmJ<82!DauoiitGr(-f^8|eBg~_CH@PWW1UnNx&z61`?7QPZhhLY| zcFUu<{OYbBuXZYt{iXLFQD9^c51uyCK5Uq;43U03N4J{x)N#AXrJKT;*DssxnOb(0 zdHaO3CaGT9^X>GOZI=1*_QT@I2e*F~nVb0YZMS|A8xqEo0&E>?%3K$VDkhU_n)~w| zB_c)lkaY48*i~+P9ZwX!T1@WD;?K{8&2nsZ^OfJn_vhtpv%*>=E-vRhf-*;DvJd{* zSDpgh;G13p`HCj>8J-8Ht|`X9v87{ZC)~0qhs}LU!T_{q=9w1Et0iw`N1NfVCx-Cf zBBcXuhL1z~^MUnx3A7ouuHBulnI;9=41Wl1&N~f=BhhA&{3kzaNWV#tX;P+CE5&a<+3uzFM}l745cki5jeBc zI$3Y-z2eDo=Ly5Mxu?&!quZF`65D)WPHx+T+sR9#{d3;KT(-rs_g=J%u0E5^cK&4M zP_mcy%wS7=w^u0IQMX1Wwe5SoJQVG&PkOxx=;VDY6z#634_*!^m*gi(e=%WuK<+aM z!!Uo`bQ1%%%}Nu7<)nI4CSXa!EMZuFwkwgP{eQ|ChV}YYx@YUyZ;wD-u}8zN?Y~BL zmA`_n*ka@;7U4ZupsrZ+$jEV%Q7XDXxn_;V>k1gSk{iVO);Pg-<{!w9c`O+-?p&l zg8hCh?qAQY*b935NVIL{OWV$#Gjtc(Hod=_Xde&zG3tsNPv>IxuZv2wZLVyZioIU= zxkTG$%WB`)^VHcU(6$-crvY1=!b_rUGplEDwl-yFiMGwa`q%7tT5l1kE9QRq+}`xF zO#*G3skRJfdpG8jXxogRt{+RCw7o>zW(ALlZ0(#j5^bB!Z>DAA*jjeo#q z+BT0&I?4vdYbepSIX_8x)_dDRfws*_zeKW`)6z+_ZT8xIg=H;PSE6mRc7WbqkG-XF~&k|_cJooAWV9}FK63(789r| zrs$lLN6cI((6)K3M|B==)sF&gn{j;Cu<)E21?q|+M?Cr4v!evsHpe(>^S9l<6=>Vs zaC03?xX)dnt{6~%BlGF|n}ckd6$^2Zs+mCB=D;qE`HfEd1ll&&9Sh`77i|`3+k855 zD;qNTumg3)l2?oHXF&x8+BQ4hZo%8FSt8K3S-Qe@)_dzF2kMIR4(?z#rp% zZ@zBwV+Yzc`xI)&_XZ3VXxsE{(Sg?-*Giym(52#H`0^*V(GIk2R;bX4 zH>tz~+BV(q?Pg)0B_&;P$CrCp!^3OBP*+T!zc}x6u2UG=HUo=v;bQD_2ii6_73s=r zrP$&?+h(q_dswN}hXYVoJQBY+4=k9~PPWY(UHO#n8avRoIbz8k*6rF-8|sQ*)au5& z)*os^+ooHRZoJdCHSK8Ie0jr%i!FQYXxki{uaR#buO41@l z_MAFMx~sgCzDSKF9SGN(nxEfqI+VWM3ij9|LE8u?Z=RH|Nq(Df#OgF*)53C*4f9y4 zBGPt+3A82F-rrZ=N->svWKZ+=+cq&*CbBnvbux0V*ZuUQb9VPG7aDviCD{!9ex4K> zmM$UL66L*Jp}D+&4n=$8>J8UIuNFE*c>7mxLhHs|OE$@=Pm+Wk**k=E&RzB`1uXez zsnos1_EE*jo>};EZZUrg{63*Xi)@MNE*7T)ddoOP*4TDbdLVk8ZYPI)z1cQ9Fr!@3 zu9kFLyUjKtkDpw9qPQ%uYm4n@>N;|4()4mn^>w!1m)py({I2*d?owOE?}KEk?Yl&e z!*gun;6_m)fg9O2gEzL8Bi~LJO~nDWFxQJPuVH&g_j?_Gjw9cJt}@?^18mihf^zAu zt|IjeSd#-h<;Im0M6wV+Ua9a};omcZ*c%+gf1R64ZWuOS^xy2qgDS2T{vp{#5?JT& z*KH=ZKi@36CkSU{ZmkfDa}*XCM!?(KyBo-Dv=g+yd8Z)#Fz)!Ixm!*tgUdJwpd(Z32bZ!ys{PKgMn|C9b z>2WyQdnlgpxv)W$f%T+xwF%-vR!^A`_S_%&BZqsf&Eoi|AbxXvh)CYLg**a#>(m1$ z9pk5N6%|2mbn|a3j%F+*Uqtxvhk0g*ihWwkcB{hKviHM8?Mm%r&I#dc$l95Xo~3t+ z6u^@Uw+e}Kd5X$ZyWzZiqNij2>|LT2@XD|MeaDe_KJvk8;9EAEsJ63{yjnAyT^yBB zyzBhAJnR+D+CTc-vFd`ad_N23Z`JIwaj(^)Jn|nFws~3h;mL;0xwPVw0RzwFkhTH)|;cvvssm#B1{b8sIN8%-4MF;UNA?SXSJ58*wnzm zWb@2ab1LgLz7N?vPtQHi#LUiQ^UQrODR0uC5!pQTwYuximjm7({e{|g>GBiiJ2wIO z;@@9<8~RhCV*#i)4qkdKwDY?k15lq_HF8&IANPbd)H8D&njBhcQ)(OPpV{A42>qpv zhYj`B*|(1D?eRQ^4fWNbIhybGPM(|6)1};1deYLIls|0=|A0c@W}$M%iZKCKPNtp{K_OD8EW-5m+IALy%VYh7V&TBab|X1ccr*w#E5$hPVIS#`F4(|odRZf(ce zsD_Klw%ITK26pkstYq69RXh%#{H!9`Hd)2|ti$aPvTZ&eIFogb%uTkz$~|5^wb)+h+e(JJ|Ykfn?i!WE7&spBx z?a8+JDtBG`tP#7&w)y>>EcU0>c9U&$cG3#=O*MQu+BUOa&&P69=uEcF^4SxxY;!&* z+h(V>Hd~9Fd&su=W@^vSRI7YB>Z_ZxMcQ*O?n1WBxFz1~4Jo{bY?~L}J+aN--<6|n zGvk`Yp$V^a1^?VZwmE4B$NHf@9QDV34S@?qfeAS|+BOqB zSu94~Z^6;Fc{WEL@lB7F zQOHbJvA8X=u#3Acu8YHW>ZbDk^6fv=4xOG!*zG=?dTu|v2Y#2X;kAYCHV3y$rRx7# zUFdEz==s|8N3(2<@qF;{N!Zb zi_h^mxvFe`Al+>aIg(f9uNfqCxB0V5VYO|6pU~ZAzwUG7_=Q7xFFuQ%LCxKKmvpyT zWpWACb!ADRyUj-rf0v)%gz{c|_vwME>Fs<%cbiS9vf7>}htS<-u@Bjm_mk74^Xlz- z71g9YLHu{>A&Y;>uFtV2ArGCwlm@xsH@&)606cVxmv&T(pDha56FGU2Fa z;i~GE&dz+ugpVqWRV9M`X#g_eygEbFt#n)HAu?h4!hO`nmY1jtGGWrs`9X0P>d^b_ z(?;c2N2f-S&c@N9pIw==?B#v-j?>b*2cDb4nf6lStnThj{5k999+=DhZ@U%oIs;E$ zlH2`x#=a_g{r+4Ica3zfgY`c9WB<(V1BF{Tbnp7H_I5cgXCc!2>_z%FQx}V0r8dZ- z?tkaWb~6TW7A-C+sNA1(tCGl~@_k{|dEZ*nS+vjrZ`HBsOww8OeVPcF|72RyS=74d zqdd|LA)Q5ktl1;SG)YD}iw^nHMr|qWrvAvH<owDw$7rjpZ8I+hV!d}^Ej?9THx?oKwm2u`;nHO2KmFG@byh1L{qUFbw zPqUlu_Y{gz?1TsWs5XVD4C^Qk_Y;-t=^p`Vw@%h9bki>B_HO+9aX z9z0A%Q9WHPHQv`l-9#3B@K;qe?oL{D8d`d7R`F`rlZcCgsi*j(GN%5k29Qs%k*DC?|U@k zESfb#4RJm`mC)U3rHQ+&YA+)>i{`2nYK81b$fCt_-?a)iO30#KtJ+gozMevNr`KM+ zaZc(S$60jio*cAreL@z^YOS;;ob4-gcRHX=H(7t_F?|Q0UdmPM#9{reId?J$M+(S@ijUIW%p;P|l*eKO`5qHh&=9oz|^YS?u%7A#`_o zJ=tWE2PTv5PAmJqr_9q+2;H4NT@)xXU(6?Tce>qsEEVoCgR|({NSoyOqrH1|jN3EiE3f7OBJmPC$3clvPJX{tUayU^WfwSV)9 z#wCJ;?oJo~YD&|8E$1v6@@Fj)n^tocZL~j{R)M|K-D&9bjG~oo3EiCrE=?ugY^g4E zce-MIS-RJ76Y1{suj^~5(}2Q4cc&>oey5)eY75<+mfTv5y0zHKSyYDRrZe6PCxzfrsRHpoJFgY>SHAz z6CiYVn*Q(Aj=fs~Ig5_}T-34D_aJA{*av~`QOLl$I~_Sn*dH4Q3f-NSt$yB-@mfEj zyVLU3^V*dgAK)xHVc`ioG+ltu-Ra$bAHbW|Pw4J6{#GM9W@a2`(Htoz*}133au)q{ zDVMx)#b4;|bWw>TcBSoonG2PBQph5k`!E+;e{8J%^Gp zU@mlI${1OpL_6j}t6e=R=eS!j7h1KBkmK8}<19Mj#Syu(WUd4*H2kt`o3c4`p~Xtn zmpP+WaTZ-r^}X!7xgK+&KBYX=%C9w<3tdz1x@^%ob5bspuTe=mM$cm%{A$1W$(gfp z+;yLTxnq5F7EO9g((7B>PfPv(Iz2u@AA`-{bB$|EnVo^LqHk`u^F9J?Hh9eEIynK7ZjgI#QL`ktWTn z=u}l=r#gE7RYzhjO&9ZvR+_wu94iv@IWnXZ`{|q^uTW;^ySSDPypr z=5{U_8_D@_PoG@QMiDDHH>Pcz)tSaKAx~}|o7UOzR6@?&>HO?C7`&Ie)1*Jc8Kd$G zm&vF<0tSkmezByx(_^E56A!00Bi)_OSQ9RSJ2bL%cUrIScyTDx9b0#&qfd^;(cbflX8u9PuXWX4;&*drJbhygh>9ydc^m1Bz?oM+S z%OSFqIL+PZAD5TYz9KESJN2y_EZRk8Rk}NMe_l<0OsUP?sb8ULqRk-mnaHaVEi!_gx;sris=El; z6)tsmDjLSoriOz#uX?U7D^BLiBz0aLcDtu2|64n$yVG6m!SgSw$ayte$%B;N`OdBL zYULXN;&8VeoL8MA`-n*ovPhj*|B3G_w(a=G)_Jw!p9kr;g?+2&yy}%ANTfb~)~)mE zx6S>;zy&jG-JK5DeUMf>8sOA<^>;c*UH83q>b$!1d!YF9*%znIt8q2^i(G~8J9J+C zD@}hPcLrFxJ9YH#CqDUav2=G@VSF4l{d<6=yVJoJ0>p;b`z@VUD^-f67s(e}x;rhI zuaB@(6(HT6?pz&B4TAPtx;uTkxU48!I}7Q&`nX?j(Y-}g(%orD^PXa5x1OZC(-Two z(fljVEZv=sFI`4#t5=6~URC+`PzNgo>F%`H(URi+*>R-v>N)=|Vo9~7q`T8rIXa37 zXSb2=PMeo2D!xu$K{~Jc<;)|_ytcVJy-}c$IFNn|cc;!G-r`!x+1#BTDc~z^AL_#0 z>C3d}hgOx6IE zx+8r*EKK=aky3M^H4cnYKZ*~QnhW*1G+wRhEp5$(4*5M?4Y=9a(p+fLYchBPcRIrx zEZ9+29WWfi^~#T<;Qi#i{u6ml#NT_7u+RQ`(`v3i>m=;IX9=C-8ZtIvU*7j^w5#~8 zg#G$)C9bDwaijA@53KM=aIsJnP*X66b4+cl~%1iXQs|LQdOfPB8Tnx*&p*NyJ0uKN9FX)ZL= zfMs%f%BH;6U;q6)>Ax&tum8cjbn4>RguVWWkE*HD7g8zRoxYEpDj%O6%X|F|Ggng8 z>m=;;cMB-3`durcba&dn&tv!G5!g$@d)4f}(4GjcKy#r!cLLOcBk`8zLg%LnQgN;V zmgYjUZ#*au4cq9{Tl#^_3$6RxLHV%U zcDLq2JGVmjUuUYVxzLA=`m2j8Cpk42x*goTpOv2Hm~s|7AXDBGw&p?~E-t73z#fL? zLSNwT&W>v>ZOw)52<)d$pWbV0F0{~<7@6n7VxD8l``l0Yuk(?b3w>6;uj-KIgRQyH z3$3DMhFg1Vz1JVTGE!dIcGA{+{rB7Zs*FY3N!^`>H|wpM*0-eQLc0v?sm2WJBsCY> zVBjA4V)!>(bD_DPc&i!Br%K(O-mKbPrEd@}H5VHFYnSwNrsuu>gUxry+beTP&4pf^ zSy;toUn6yQy2hiE%9>)m)LdxLn|A8V`@K?gp)*1@$+WNhrQYj*OZn8uy3ta1rh6>_)K~daypp;*?fZK+Ri?pd-s^Yw@=#AA zK1ki2rVW21V+*BJx;ybd;Q*hZ_0anGb-JkwmjseI)?cx z-JNbY*j9dhzl8Vt!+V^N<3e*N-JN;_7e9PTwv}p%&bzp>%iZ+qjIpU30V4d;MO!R>~@!iYVQk zwmbJ(ewtcG>FzXl*TT}f={BkN`v0h$L$>waDRp;x`sXBBcy$S-yVE_@Zb)~!rb>6G zahcA_-Va(R-JN<4`_H~xVz1O(=+LJvTtotr;ctUVmu5qVhhNTHT#Wd$nwEwv*D`X}jKY3EnwVK4sC#yH2h?g@MJozl#6M5RsGyB}1by5rdSggyQ0*N+8{ zc$|~xfFeqb42mtBzyKuu8J@|4ztl>AnP zxzOzKUcyt=VJ`I8KVPV1yUxso#;ASt-FFakq2Bvz(WeY!mxJ?3*CYYkfOXlbD@*u z9x4-(jQiN{0iDF6R~w|}LWd7=SdUu=D$Rwuev7wSl?qVIg${0Og*S_1F7#9h_{uMr zRhkQ3<2lZ{u_>0h&{JElShvUbWiHe+l;%R~G-yeI4|*~en(ydaYn9(#=0Z>Yo0?`U*v(w%&s|}Z zVS*2Hp%44bBk`>ZbD^PM*3qZrotO(<)1)XZoxGK~&}M5F(DMStm)!j+V)Hi zF{SDWskzX_D?-G_pUIgEt#GieNSXXUskzYH^S6-4-#*NRcIsF_#QlK|{Si9G+uNzn zsr<}^*1ua+{PpJ&skzYq&NUO(vA?C}LSrAc5`SbqCN&ot`kRmVIB0~_TLf^NTLa*O=GZ$L0!&=H!qA+uzJ+Gw^^)5e^nhU++$|Cx1`b%mq zG*eU_k;~U5H5b~{T}YfCuu*C*wA|*WQD7{2p1ppa5<2q;op}z<8MzS|l9?i%*}#bM zTs+uI_uTuL;thN0UZaKv>%DBSm+s5w^YX0C+`+lrX&w#X862>eZuMo8L+@q38S>55 ztK3^_;8!L1RqkNHuS)Q%+`-nW_1N8iOo+R5D}xKIf$ zl)FuEp%PpucbgrO6_(&ax!Y{?q_hMV%H8IPjQb_HQ0_Ltg-URt+--sjm7`O%%&{%H8Iykhb!4(WTsNf(w=4Lb=-n7b?Mp za<>UCRDlcSZWCOntQ$F(yG?MR5?m;Eo4p&PSKvaq+Z=U$lmr*b-6ptD1um4kP4C~l z6u40CHo=7|aG^Xy1TIv83+0*j=)C#Vr=!t4Lj*2Vf(zwt6I`f_8eEpUO>m(KTqw`H zg9}y3x4q(-cW|NdNa5VvZGsC`-!Dz&nRjrZ3S1}|E>waGP1t8|zDJfD@!c|9sIs%P z=b3kKp$c3m87@?T3njya%5n2fS%wQ$;6ll8p$c3m87@=~iQH=$E>zxHu*5Q4sMT^z%d>o3>T`})FLumsB~4%VCk#~E>t!@ zwZmz+P&M#!Z>Qlxl|AF5Ww=oMocCLX3zf9}l*@3T3S6jdxKK6kVQb59p)%~|2Djlt zRsZG_+=dHP;6iP~g(`5Nw&6lGm&n)5sclO8ysHr?bk<6m$IcWBT@ycfaJ0^2$ZS5y zY(i%?GVN#;vUpUL~|Nw0yX!{qCs={9+7I!`{{bfmohUhBVu z{>xvk_S2u?PWpBJGk#3q_v({7!oSb$+PuD&CDwn_@C>{*9VUOR={9+7I!|7A9b7?Y zEum-LKNanyvzE|V>ut%AL100hdQW`d-$g0)_OU|GysvDqj>ZKI6?*19vg*GSce=aK zGw&^1=N4N#H4=K}eP&_sc4vZwo_U|;*+jU~#V>6!NtPX>r{QE{Ya z-c8QrZrS8p?oq+13UI2t7Y`ma7(A*|cdFn~9pF)&dT$*(sslW#Q}4NhM|FTlbr>Gi z0Unjt;87jmQ62ht@Tkty@#A?f9$YAa3+27|CEL4*MPC+?o_Wua=c6+w?f~hT_a*i+ z>tbU(j{`IBFGrRVw5K2GnfJ8*-eUf$*`#OQM|ka|A3buBo_TLHp@?`Ix{CD7yO-~F z8Zg_7^vt`nZhNu$)jrZQ@8gbdrmZQ;ke+$3v9p!f>~Wm*%=^{SEyT0d7f8>%*Q~OJ z&Lpozdgi_0`g|hUmuS*6@2w6s7F%20BR%uJyub>Y>e-C+%zKuDiz!8wPNZkv|9qKE zoSt%)^vwHzWowC5OOpvb^X~bfs`!i23O)1wzRGN>HgY)WnfJSx8I7Itfb`6JzS<7a z?U|?0Gw)f;Pop>KCy<_bZ+3qIwdpdI^vrwi$YkPKm(QeU-W{#WirAuFLeIRnfA1q& zKQ1ox%zN#U{isF%`J`vwpEi2|hCa2>Gw+-86&2;yl@@yDJxj07wEe{*(lhVA&zjNl z!OKa{yw}V24-GErDfG8zG<3~+(lhV-_t_LQ zF}Kh&@83qG6kaWA2tD(jwRRb*lWQ~SnfJQ4y(oUfHqtZi|E1bOPsVu(J@fv@i>LH2 zH57X0J@@3Rv|vwDp=aJ#bvZ%%pR^Qu=KXP43M$trg7nOLr5Cd(Lqu_*XWmnee{N;7 z_mZA@_inI-+Ggk|^vrvu8yI|?~eSnFppVU=$ZFB-!s$D0%e7sc{lqPe0>8K zD!_$u_A~q4oKeAr3UHy^d4dZS;6l0c1Q#m6g>vT!E|kE9a_0#yl)!~@=Ls&9z=iT0 z6Sz9x9V0w=(q4P2-M z7s_)?;6feXLissP;6fdJe!k-8JAn&zfD3gSF4O@ol;@Jbg*w26x(yc^3@+4dxX{Yr zLiu%Yq4D5C`FL=lE^wiI9&n*9aG^ZM1TNGCE|lk(z=cY1p*+U~E>wXFRl3^*!%1K` zrOuXMI0YC^Wf)EghEwSt5)7vV!>M!+35HXG;pCYkFq{$$C(j&#;gn!FmF^+Ia4ImI zO81apI3*ZPse4E;oDvMD(mf;?P6>un=^hdcrv$^vGe=-JB^XYrdq^;x5)7x(JtP=T z35HYY9uf?v1jDIx4+)0T2E!@!zBw3935HYY9uf?v1jDIx4+)0T2E)lSM_@Q@Fq}Md z1cp?rr2-fzazl%Vb^Tj>)7juf0s7w$sAkrFsk z?n1$l5;#)sLcx&|I8yFH!I2U;Qtm>*krFsk?n1$l5;#)sLcx&|I8yFH!I2U;Qtm>* zkrFsk?n1$l5;#)sLcx&|I8yFH!I2U;Qtm>*krFsk?n1$l5;#)sLcx&|I8yFH!I27Z zq}+vqBPDR8+=YT8C2*wNg@Pj$;7GX(1xHHYNVy9IM@ryGxeEnHD!`HQj666}0gjZr zP;jII94U99;7AD^DR-gZNCh}jX*f~=j+DDlaHIr|l)F%Hqyii%ccI`&1vpafLcx&= zaHP_3qoae)@FZAB#pZQ)W zuT782Uz;?unf{Z{Z+cPAa;E>}<4rHh>%uoX``scB?pF;bAob@-dXGrDPI}DRqFwzu zeoOdT)5r4rf+Hnxq?{Gaem!SMaHIkpsW2QVxXFiPI8p(Qlnh5Iz>$*SNCh}jx8XN9r~lsQ^c68;(?fBbA0DC2*u}!;um=QitJ41vpZ-;YbBIQrmE( z0vxH^aHIr|)G{2Y07q&Wj#PjnbsCP8z>!*pBPDR8mf=VRI8w`SqyikNWjIm+j+6{X zO5jK>!;uPbq+~c!0gjXmM@ryGEyIx#I8w`Sqyii%8IDwdBPGL;3UH)kI8p(Qlnh5o z;7CdD%Y!2o;7G}Eqy&zX^u9beQUQ*X3`a`fNJ;O@gCiB-NO@l#9H{_DN`@m9;7G}E zqy&zX^u9beQUQ*X_vOKn5;#)cmj_2Gz>)I4JUCJTj#L}z>)I4JUCJTj?^|BsQ^c68;(?fBXt^%RDdJ33`Z)!ky?f$72rt8aHIkpDH)Db zfFmWtkqU66WH?d*j+FQ1kqPx&C;xpM94Ub#A9H|Q&DbL`8BgLFWLUsj5D#4NR3_dtg367L!@WGK{_O3b4 z;DaMo;7FC>NEJ9zp21JrA((k9{%qh#6*yAP+u%qY;7B<`f+KZ+Bjs!fj?@8;lrtwd z(qM3;oJGNr9sozm85JC9JUCL$uHZ;r;7Iv(aHKA9qnfcaFq7X|aFzd@3-X{47u~pAyU` zXIC(v63i!OS1_Ln%qKq!6wIdr^U3q_U_K?7Po9?t^C`i6^1M8lPX*?a=jFkCN-&?C zUBP@xFrPdx59U*X`Q&+dFrNy{C(p}+`BY#&d0rmOrv&rK*%i#E1oO%B@?bs{m`|RU z2lFYxd~$XL^C`i6a&`stDZza5ygZms1?H3I<-vR^FrPdx59U*X`ILtFlwdx2ULMS+ z1oO%B@?btCm`~2GU_K?7Po9?t^C`i6^1M8lPYLFe=jFkCN-&>1FAwI^2J^|;70jmu z^U2v2%%=qN$@B7HK5a0cJTHHI%L)5cok-5Eb;p;GC-z}x0ND~Os00hjbM#DN9b_Hu{fi+c{H9d5tgzdkopUQ&l3hvYe?o=7>)B<?v%4DxKjdmstk8(fjd>Yn+11D;7*n9X2G3W;7&Qa zf;%N}r%HFT;7$qLsnXpnxKj(Qlrv&a)>24O>DS&uHa4y+^N#tEVxqwcdB$Z3+|M_opN>scS_(+IlF>8C2*%oceCJ53EZjD z-7L6M0(Yu(Hw*5R#)&4ynlaHmRlv*1n%+$m>QaHjmdyLyAP~w$d`E zYG&;@bE1#c&sX7IBI$MB%;xhoKWP>RE_pJ3TV&vO|-nG!O1rcS^-{JR~ zz2taAu|_@lb9T@7JmO@8>r6}VH*wBSw^xKnAkQw8o+8tznqJGBjWs=%FEhC5Z@PRVem3fw6f?o@$06^1)i z;7*0%P9?Zg?qrbiM_5s=%G{ zoD{fI1@4se%s#kN3GS41z6EzG!JU%Mx8P0{xKq+|Qs7P%xKlFRsRDOOhC7wuPA$Wo z;(HlGdS)NosRDOOhC7wuPA$WoN^qx^;Z7B}Q_}es+^GV0N`^aC;7-YKrxM&L=UZ^6 z3fw6f?o@$0#a=serxM&L=UZ^665OfNaHk5~Dd$^orwZID8SYepJGBgVD#4u|G~B5I zcj`3UsRDOu8SYeqJ9QiGRDwHo8}3wrJ9QiGRDnBn8SYepJGBjWs=%GvhC7wuPHn@T zDsZQ^;Z7yEQ`>N-3f!qQ+^Gb2Y8&oUfji|nDR8F>+^IC&sRDN@4RP@WUPU{IMinA^0P<6NBt4#6{Yjspy;Q+Kna z-bOpTcO`HOV@q6jfI(%Rp>gClNA>$>m~#Mw>KryJfq$qvH<$D5&%w+^fI)ReFTzVmSIFirlRfm*`Z)WMYH-A8Aeoq5hcTj z(yQU$EW?NjFrxhIP%xqbj3^mKl(IO}^S(bAQM$7-7thy&5fxxW`PrdhLI~0tl7#Od}Frp;y1oM3TI_GLSwxbs5Zua%BY$EUD z)1>n)*iiv?lngs6z>e}WMGIG4Ow!$vbT|73`zP+d?vn0iN2aPRc6k0E-OX;eIG?)w z3MJjmmbGS6rH4aFce8<~JVdV0kEFZVU6-9=U)4-PceA-I?Bxu|A#^u8dNZEG>N|yW zH=8E>4S`1$nn%smD?t3{m|y5__Cu}F1U8jPu)0-P$(_^&_MmcG4T!tBBL9w!K#D$n>Q3&4xpQ~$O0;kGzRfj6)AaJTY8r>Ri3Nrm9Hp)Qx%$1we8gePL*f; z+xDJA;8ca?RGZ|RYk^ZG%^p;8+_1o@3f;}FUNDltsq&0}p7z}>aH^!)gIxWC2%M_W zoa)XQSqPje&-gDW)X5riBar8+(4*?-FL7UL=JZK-p`8cSjR-H^i8ExjLtA(3@35J> zS)a65BNmQd${DiS$gL6GsubWgdR_f|0RGyf`OwVu^ZCuZKj%g>*U!hBd4FC%Tj-N} zPuH^C_u~0iK8erCPs%wYT_-(eP?b`-Uu7=GUz_y%0z0a}j&e6^o=EOa-!;^;p4HE@v7 z-E2^7E!imN7@@n_s{Kyd-wuu!x|=O|G;>7aeJ!9gKii6VhQet)E8y8vLU*%ZXx(6F zxtj$;>jFc|85j($3k)r1V=%NXFtohxoMxU23@!5pU}#;(&nIvQU})pP&^pVarwz#Y z!5usCAZORi53AT+Li!8c&4N>v;8aOJzZ9IR1gA>+`K7hndZ3}9==R7jz2etpmVYRm1@<(2Q_NN3cxF>_?&OG8L!)YdEf)Y^uHh3;C{e+W_~ zeDVt2wRXz3R9+p@p1ancJ2I*q8E2yVmS|g<8BJz0h52XsfldOqLql zwO)9eLlql#g1gq2ks<1{X9}Ua)(V&Es!v7!7QB$zJc_u66f^ z?K0Wz{M@y+_*hg`z6V|wGfuC>loAN6d)2<}=xgcp!u zU;TydTGK`~msLb*p=b6Fxu(dPLrMtUwLU$&R*qg?Sm-S3l{u}t>i;iyr|X|(QQM#V z#og(&>v`0Yb}sHtYuzZMI?db2-6`BmZn&8o`dOfGGby;4NOP*@@0EOAGS8gn86vou zT>c^}_mgllx!`8veiCjb7u-zzj8M3lTyQh-Oc2~mZn&9TdT$+WCO6znJVOLGlN)X( zejRQmH{49|`Wa1dGr8er3f4IgZYDR}O#DnIxS8B=Gx40ec^*Fh-5+iy2{#k>y>K&0 z(Vz!+yl^uqxS6=)g_}vi&BPrq+)N5?ChmCQW>Ro7N#kZxa5Ld~Wb9^Aa5G8$tN^%~ z)Zp9GZR2KAa5GuP&7|OFBI9OKa5Ir{GfB9am{WzDNx{uTnp1^GNy4MV-6=du5*{V) zPT^5f@FbughxrjqvX`t5*{T5kCMZ9loUKlmhmVlc$6&T zQIhZ|xpj96kCK8%$u=G(1&@+tJW3KCCAaY?NqCfO<55!ZDA~rNq*mm9=r$fD1&@+# zJW3KCC0oxQ!K0+$QR4X{c$5@8O1AMRNqCfOJum;VU6h=-E6�vah4GS`tuS>TC(W zl7e4J8o!c)UrFjY`X`O{%8V0V+B#d>7fPs!xx=N-mbFLqP!&G*k-9q_a&NbM=bw`I z{clv-DL;43%H8SqkwsMF{mZ4!mSZr75nF$m)ZJ;pkPhlopY2j-%f}&`Wy<5e+?~SN zq~L7g=bART-A45ZJ}7l}3V)M?zlpn3_?smBP28Qr-=yGg;%A&zuGUmdn0-y^?i4O3 z1(y>)?-VX436~Rhr*JtbxSaTTr*JtbxSXW!PT_Kra5-^z3YU|F%Za;FxSSMRPW-%6 zxSSMRPTZZs<)q+p;_ehKCkdAmcc%rbe3EcEad!%rlY+~MyHmKFBwSA1oxp75-un1PT_J=a5-^z3YU|D%Za;FxSS+hPTZZsp75-un1PT_Kra5-^z3YU|F%PDDh%GX%9oD^J6q`6i+f4+F)^XI)Q zG%Y`J;oB(PotkIVlW{ry?>T;tI_!^Fa%4K^I^$sC&J)*3?XctPWYTMF(E++|>6LYO_IoWVIG1m&0lLeQPFfJ#8%SjlQ6Ii&B!nm9q zc%DD!Pq>^2E+@{Pa5=f)a^n06my-)FC(fU6Il16+;+zSWlM5~tB?P zhs(*S*#Nklg5h%F{0Wzn1(y@&Pq>^2E+?V6*30D{+UcYBa{gS?KeNm=WGClO`fI5y zGpn<>ed;*1_w$v#zHZ|D>DOwe?A^XN=TEN}c+UEXHlkOu6ZE?1P5H-SaJ}9qv>!^s z55=r3{7_(&QZp+HKNP_aC5#`+f*(p4Ka>SO6tlAMLs{@c3FC)y!Vkr)Ec{ReKa?B;Z;i<607M zEs^dp;aU=KEm_93B;Z=IjcZB3wIuaSJzPryt|iWIa4iYAmZYAkhigf|wZwcWTuTD3 zCFV=vS`u(AF<%PT62Y~^d}-2arg4&T?uBcK;9BCG3D=Snt|iXQa4k9ETH;&^*OC*i zCC;mGEji&@;v5Utk`t~a&bP;!c{$-);@k_@k`t~a&ckpmIpJF3*Wp@nz_rBr8LlPA z_@L*UtKnL5wB4JKx8YiHoCrzC;czYCS-lCl9j+yUYl-*n;aVcNmY6$*7m46SBI898 z@FJ1%A`!eu%$>rEL}9NBF?R|t62Xhad-w1n5xhvecMmTT!HdM)DZEGoFA{U7@FEes zNX(tWi$w4uF?R|t62Xha+$p?B1TPZr-NTDS@FFpH3NI4Di^SY1yhs9GB<4=xMH28L zF?R|t62Xhad-w1n5xhvuox+PG;6-BY6ka5P7m4@o;YA{Nk$CSOUL*l863@TGizMJh zV(t`PBmplHbEohk5xhvuox+PG;6>v3cX*KmyhzNQ!iz)&&-CEEdw7uuUL@vD;YAYg zBJun?yhs9GB<4=xMH28LF?R|t62Xhad-w1n33!n>f5M9-;6-BY6ka5P7m2yk&c!!V zgW9Ee?|xqUBBD#F6`VieOA_!U@mxH7Ndmqko{N8u8HZ+9vhv>jV|NL0@Nq)^yqBw~ zaFo3+b+`H8>~3nhG9iD41n;HRLtfds+pOXPuSD4foIgWl8*%RZL8-gV=cPJ`WA763 z=ZD%+bmi~?TX&mqFbO!AIDfXN+F49_v`p%56Fw$_kI6PZCW4R2Ha;c+ACs-;?(=r- zA=0+%Cv~?8HGx%^b5!_5}<7OhbncTYDgqumg z&E(KC_;51`xS4F@W)g5S*~ZO8a5Fh|w+T0sfSbwEGx%^b3AmZu#?3@5vu}u+Py1$Bd?9uiNDskiV`waf{!V2tvyY=Ha;dk-gugL z4L1|t3yhmdz|BO)&7>WsoO_o9wD;+j??*|Uhu7ZmiC*~YFlS@9nFQQSoS%)Cld~M$ zO!06t@mvzzOu=w7aUO%4$pJSL=QOyP9B?!78g3>B+)TWNo5=w;6X!h(-f6g*c+VYf zrvE)lD(TMHsNL>xS2Rx!p%f*GYR8nBDk4^aWmO)GjX>GH*H6oe$r$d3U;_`(6ssA-{{vZ)ja4)Z~M0M21DE<1l{2{_M7bzA0 z;8%fv=QaLS;5c66>j+=ZYn+d8-o#^Y*o4H_W#a4leG-qy0V?r4`h615uYXN^U-SEX z9{qKRpHrVN@$)CX56+j&yiR&;j_0*GkI=81^YhxgFR$@i`t$JGd`@2L_rZC2Jz}YY zpTDBdW4_95yoeLj8O#LtrOe*Ahw;_Em*BJp^fXHVjJaQ;1s=f|&m65kiU zzbEnY;Oq7zeomZkPvYmt`|L^l9?k0!`ZJj0d2P;v<0c4meqNjR<+b@dyf&Yc*LWZO z`FUOD@~ou^@Atp&H}QD=bKtf4`S9BO+<2|OKmC6CGwAPIzn}S>`sdG|Q~#Xw`{~z{ z{yDx32^3{UeY5myRq2=aE_*tD$?>Xn>ZGGh0((q9R9CH>==CT*u8m~gy9dKsOT+OPvBV09F zw%vKRnJ4`c^+P`yj9MX`)Ltg*Za66ewn)j zulLctDg%Ej>0XHAr{+Bnyx^g?Tc2}g{ScLJL^?GqPqZB4zeYC9*+$-27^dcYzytdB zwNxI}V&tKALGr`gt3OCR5o>Ux^;>hzI3a;0a4d~!cb zRhaw5p1L$rMq*tmc`rGr44yv&M(p(5KpL95pSlVEVxg0BtU;UNWkGkCN)w+;-6(lc z_MRK4Ds9T7-qrh84ww?CvbL|RzWe4?L+(V$NIaK&Rd8XI(H$k_p+$01<-s!bqA(Tp zeV*J2AI#<7!&H}>#Z=eN{%TG{lw4IYr5eBWr@TERP+bZrpvqmVpyaM7nP$dYImkb~ z+Bh~)-MTzQPEI>hrkNY2o@CCcCLeLAR7;}d*aL457XIpgHv`Sav@oc~Fu zA+mgzMY7)fFmaxtX@%hp9@q4j~%e* z_ZpxA4@JwBPg>dGyWR5s$}lzA)ya;?Jy3;TkH+k5QM*xhTb5ZLrlwZC;Py?1=QnN$ zQ;+NTI(LK)R0AkR#x7pqK9#4EDsnSWwVIOLYJ0h&YU&ZB-tI1I#S|H+CJuwMx8GFj z?~?;m#yK&v^w(+DQ2&bRx6DB*XS*hj2OXpwza>m%2)S)V>JXSWTc-A@eq%D_6gsEOz{jIbQ+%n^S{29G$ zYF%@<<<6Ke)#ObYDz-F8^%X&CY3g)px$g&AV@#l$R^f*nb}yw09vP@ItU4zT?aQr3 z{}!lA-|IVle^eSKeZlep@=c~Mnc&U}kV&yS> z=A>WS?cXfUcyq1ut>h&#?~j%GnuBBhH%o}?k}L7Ll>Ah)_%3Nm@^zzBWP{){l}ozy zwP?c8ypD6Nit%;kLjQ4&R(TZTIc8L_pQZU#w!)P(;50?9&I@?Tvd9s z&v_~Pb-FdDx0+ce(ph+EM$z_8OLe>BUgv_#K4MbGs;Xzw6h zG!akw=1|AHmpi`&Ws>XG_E#a5W99PZVYcT+m#iBfrp{NYD>k(8Q0IHZO1S}Z!516y z^{Qru+jgOycE1;rsrVdh}^~0TwQ%D)KH%v9{nVKRqgsH6cV&sdIUo6$JygK_0*Q>l9 zR?X?Q9EtxInrwDh4^FvdvE5;6T<_M@xp5!0s%VV-ZFo36IMGYZ%@HGa6%VEs83R=Q z4}mK82RvhBNW3hzGfdrGzJRtA?xFlL;P}WvH0VhgHRw&C@_QF&b=r17cHI%Cu1&gZ z?RLk?N87_xzCWYsj_RoX@`#b41s74FZ6(#f*MaKK>c?r@_qHk;ueTnMnp$Rzl)Z3# zht@5jjf(Vk*_@%!>Ju6vhr&89Z{C(7CQbI&wW2(O-=>P7ZgxgF1x`_}EU+*&C} zr5H1xT1*@*<8a+;f4REoc0IkifVqe*-51h@xkF_0s4(^R%Q8Atx`#X-8>TKVUP;y7 zc97E!gsBue@`@@~j!CK&q-ySnbw4>@Q5EqDQcu5UxAM9ws)?C`RLa5msrTJLHSANM zN|xgbMdVDarlky0@t;$>zg=JDO7|mN?Wo|Titmk;`&#|~>&&Dnfv!=_b2{}gISx;A zHT|B^nF{OYr}w&=?)GqcVBN*g-gP|PamNp=e|M&FPuaDO*U>k! zx(f~ruM!R5tz>){(FBxO{%C=e&3tR7s~V2aPH{ZS8poUrY$St@R?`3Zpzg!dxnu|g?+|FSh zern+or+EJ2tW#{NrB<~mBA!&d?yS(MgYwIrTom_v;H-t~MPy%_?oWQ~tkiq73aZ$X zx;Y;>@0SQy>pQKn%D1`hELlHXWhpw}UgPzr^YY`-s`$$e@GZm5kh&ilBTqfKXU)U$$3C=H zTXUb2J@HbSe}hn}@~9vX{L?$s2*nUAQ=&6tWBRxnU~&`42g$Xnm1td95n`ZB1ZNP(Y2RKd@3XK)%ZWE{@Fs;k`jXa!xJ z7pBT&E2>iNDkmbQMag0Ve3ZT2SDfq+C3|j8rLMcak+WZ*svkE}wra6}{+Ny|>NQd3 zJ2Z!WP6<;N#*|n6UKbP-b4AJM8JShfSx@MAXUzTuPLpZAPN(CO!qlWP!75qh+#=W4 zNV#RBP^)TW5$W$o%2%UWen)vGrnE?8hLgj`hoHbye1l z9-=1*tdu3a)aTfEvfAQVWqaYJeAtsx05#7;w^tLDQ&67ZFq;i2CCVUiUUmyR7=nGQC%OkqBqfz zvewpq>eu=pDtkCm?wMUdE%3Ny_2`Ja?TD9=KD(^TIOn%U1Jv4_*R2vyBjtlEmDIrd zT`gyiKs7SfB|m4MZ;iq+gNhDRdnYflDtJW6sv8EXX5aE!!@Z*9f%%ox_^E{*8wTNe zaov{h;{2=uIKK82DZP?CcRt3t`=)`)-RhS+wr7<5p1zX$AsX71keM6(D`mmz!<|Pb zhN@^n1T|CcTE?Ja8GnHi?y-}F)QuQrmUyF|$o~ylg=mEL2{2@C8d3#OU&MH;Y-Lh_<7@4M6w5y8o8SNY zetGOyTIq@VPTQ2;>eA>nGQ|J?=dL0}ys%dgD|OC{bGG)oJcE5_@Us=&QL&6myDe1G zW0GdJ_L+jq3|yC=b7}sPP3g;9f4F#q^mUICuX{>BJyhkP*-9^L`y1!mm|Gi`?%(anxwlOB)uqeqO2x-)?{djn zwyQjU2G7_(OXB+eopQDZtgE9PY)0a#R0ho*XPDJ zMvJd@N4XN$=ZZDL#kVaB?cOiXIu`|oi>?cnTMa8+cdnT^S~R@bjk@6aeB)M_*ca#K z>+_`D9fZ$94^a}=XG&QcJbqzuuJv{2h!%drs_PVmaee;xn5UTOYA#0O`kdzIO`416 zb{56;IqA=E;*>x~;(cvU^`^AO+(!zZ%Id8CHQ`>f>2)4w16RU5D0X@Q=ZRZE@%kRO zYE1zr)bM=I3MrP?*|2g3zL(8>o7FjZQE$G-^(|6N} za-D^K-8*|a`i%QaGrZm+wYR7^bd7w3YknHHuh^s}%Rh0=@7SiZ7~OWa?1yW99r!1s zTC9@oaLu3Fv8=e;r@8dTHGj^+{S=!voz&NS=kea6X`Uf68Ls)6-vx?-m%XGPuK9(F zN0Z3)$=28Wl2727T+>)~!!*NK_7zUI#?GEkiDIn&;T zYkukt14XBFY3w7o=9gbmNt`Y^DmWO|{D+rq>g3^V>udh!Ns>N(y6)E3{QTPoitXLA zT4Qm|Us|w|*p$4zbqv@1b}uEBt<~Cn4A=Y^|AFFCiuqPnT=Q>s86d8W_}fZ_YyP8k z6~vEW*R1Ne-bVi?DeJ1<&R4irdo7XF{?-GhzUE8pIqYc_K;3Z7uaPrI9J^GMoVe!8 zS2p>2`dX=QOw-qWM78}bs41@bmHy~0W@Q>hyLUv&HN(n^Wv|-MI-LLU1s9#JG1t=f zg2S!j>13ZBmcAEUZ_rJQZncimZ-|uhqR@Q}m`?8YfokefJV$W;G3zCc>6yHIEwC=#qPcif z@B#YDNO`rRm#F>UL3)nQv-RK}>bxW$mBukk?l!{t-_d*AYi^aQC*BwH5P`VYRQNBK z$nSNLdg5O5Z{zLs=|OpFgzJ3xiOu9cp&IG?PKj?q{By=rl*WDM+v&{W59elQw$<~-#K;2N9<_fE8Mv6l%M;V&i+abH)f!Eo8@;Z?lFdr;qzSXR8-XLR!+p@ zzVq^Me&G(PC?4RxQ|iS7^4;$#a^b#nHEbHK+Bco_edkh(iPS254(a<&<=dG=DR^Q+ zaNk+@@1N9qLvC>f_njGeN738@3rOF0jxI?pURSIo%Hh7#)aNJpX09*x;=bcGE0(IC z^b);r-zjmwD;-rUNZ)t*J6loqqj*Lu?mKJ#yiFtDHy7h@-?@Kz4PDFUEym-%bIwtZ zMlISvHF4i*KI$B0{Lxx8#C@lRe*lHf+fMqvQ@VI@@`%H=0Qa3Qe@_O>?yYZEar36U^JLAsQ^*Noi_f{LwJ z2-vM)qJn{7ccX|XAR>FO8SB{H?NPyFcjtZIm&NaTKll9OoP8D>+(&1vdFJ`fcclCh zp2=)r4Swq76uHsh&vwEZ{NkH9St4||&K=g^?|w~{hhNkZ3tKG(IL zal=+O1CCq#V{NS3VlIvQ%rS#CMK_=z#G(d8Z%;2!lS*NdtPYZomPq9QTrbyV|k~zybW5 zN6Ax;J}etJ!07pYvSz9o10h51hCY#@(FYae0NIyD$QoNKvFgA9LXQW?6TQ+EZ> zl_8ue*CGy(@b4~>)!KzPK#MmWWV<&XgfDP_D(=t;a`PB*0FOO&--z{R(kH*9SVqb6>{;;xq0UY2=t*Wx* z$A5_fbQri%xCgc;4iFZvmtmnbhyy%)xK5lo8bTbPUCK)FX2}5J0P@x{k+yCaae$q( zD#$*=UlRwIyxl`K&yQrt0d8LQkxyDQU^9UO^hpeqV?uf;$N^S-aFCYEH;XyI0k#Yo zCojh(3*5`NSj9^^F7HIouANrZ_2{yJ)AQj{(=@mB12+&OwSC&oW3zoFdPa@N(|J6w z$);;&PbwqxyZoT9{d-P0TV{y75p|c|zwgJca?nJ-b>*)HKQ!S0ZSm>qMn+*5r)S&T(34;uEkJ-^U_I?Qii+7~`noqN4=7(fD6L905hHbp z*edP~8cmF}&I&GmMo%F|y29azns9D9G18sMeWc~&Oo5E_UC2IR)!396X<|a4di!-u z5hE>3HM(T0G&fESbCW(RW(%AfJ^MS#=4_+DxpByjF!?p)n>#-H0^6*Gvq*Lp7 z$<=Kgh>`wz8iG9o~ppODYf} zee+_TDCshr7-`|&S>j2*`NT+_Zd8}w>MO)ZBd^>P(Frw(ktPLIl;>_VB}Ur1!6>k< zQizc@izqFpHfl|b^i87&u@zjUqgwJs%N+ejND3$^tJA^h^g3v80m`xOGK)ZD>2ehcK%|^t{uck z&%bvTzU9-2k)GZNy-2hA5+fbxJX##eYe0;2gV|bP(ro}S(k+!LiOui!(%e{W!2)r_ zF_IW58~#Ua$+Br~wBPX<&e+>ebK|5pp~Ae!Fk+-1k5mvG_Gpli8bb7<$^~y?q>J^J^nA*Sl4ab%AdoRBLCcAILr99 z-q*2;tmzcWkv&G9Y#_bP>p8N=WVco_`A{8>?D7AZ55JihQ*W)IpDhKrZg^%c!}a*y zi+gp=ZqtYl@^&;Hb~7ix zY+oC?W_hcI2KU;Q^t#oK1VfGWW;7l-Gt;oJaw$EoZ97iBVkofqPlx<=x%&sh&t}JT z$Zs7TEqO}kU}B`NR>rWJm^v*jvC#Lb^X1Oc;+F?OKeMOIPuImR)^WDkO<^s@ywvZ)@;_6J;XD+zFN%8_6;JQ z`Kilv_K(jH;+cxUl^sj><;XMJ=lxO6zRD(^c`mF_+2fN-Jo8z-U^bvd6!FZscmFB* zT?07s%!6A`EC2ZC5zlNr&58xyfSyHI+nRrPs$8>zTqCS)gF8=D7XE@hZCLAhhNdbn zCK!lk29F%2Gy|@JYg_%u0OiYuSmK%aCXaOqTZ1_AOp{HGlz}-a@l5Z*=K4R6V>$B7 z>dv=duOSwCy0XN8mCe*zaK;3#ZM&o{(Vr`T^H|_LllG3#)wYzxIZK>5rDiUR;T2)6 z>NNL?Iw3!R z`|7CI|ELVtwl}KuQrlKlX>Ge=!*~&LYY1-$YukO(!o`6lUL4tJ&CZFc%N+x)ZEGG* z63x3ua^$Gq_t%NQc>_3d)Yj0=7gXMzBS&?OIi?ou$fLFGKe~U_r@M1$Z9Cgaiua{@ zab&8$*RB^$S2=NHs@}7IsEk*U6Z)<#@&+)QiR+Z(!x_;%}QZM)gdM&8&S z$dRc&nDj;L^M}7bu(oxt*k62VxSH0suMgFgmcpAOQ{Ck2DlaW^I#U#EV9|lW1+bX_CKe*2|6~Q?(ybS>Cx*$dIXixjskS%}rp)R6Di} zmZf@Fa%8GA<}Ma9T1}?4?SopWVyIaxt!*@;<;_|?`!`4TA!b#JmT+sb;oP=Z1>?!kGRtFyVJU@8^ zJx~5U&p*A`nqS{2R_4ou_HO{(ya*he&8K6l&yGLNQ* zJp+O>10~Mkrb!pFTi>=Z;(h1MSbLUpcdA6D`r`U3w#s^}M5bDA)&q7Rc(6pK+Rv^k zzdbQTB2&$JgbNh98OzD8ZseT#i!z;T&|pLIcx zj~MWpeM?OB=S|np>(PnT_5REI(>SlDwLV^7-hlU=vH`aG_{6|`eE$*0;XYQmX)u1@ zn99qQgv1z$?9_DdYd!AiBU2SoBlxI=H5k6W?52S&j~}ieQ?1!EQt@pSD3Pf;Cp}W! z&-zPbsx=#!vxPH9NMx!OpMzNWU&AFbRj;is%m>bON2XeFMU)a-!AMMX$m413_m9C6 znQBycFXnZ{QzBEH*nX)pryyS-Q+-up35%aSNFr19Ke3TLmi;9%)$%(N;4FSOiA;4@ zh11IC%LfE9)zM80m95W!PXJT>FySyO5gH+psrGNVkSQ;P-X?h(jT4dYv$ss%ipWxrY{@V+ytr7eG2GEgE@y|?@u+h;V9$W#X$8o-v_StXFEwkYGk zPnPtS$W&`CtIwZj)tAUrpX@W?0lU5lyzjL7Igy?Jy+q)BC->G2Hrg*qAX9DV6v%U& zY$Y<)LBFf;1Xm`P-+Z+h3{E~e)M zGSvjLWagPYQQ&>2!}(>*&pBEkQ*BnNJ#RPZCpel}qSF4_JhIDvflPH(`_(KgyuU!E zI(SoO-s{dwflPJpi%{t9y(f^VnwdIthv#brGS$KgwwQ_?XN!0-37Z=f&sj z3KhsyEiyA%Qg=&%O!Z4>7Ms(wyg;T}@9_}6{P`GxO!Z48KOQxsjzFfmDKCe4SN^IZ zQ?37Y828NXB9N)p*&W40+`R-c)mKpgyxocGDl*mm2lLp?c1KiXsuh4~r8F005?ea{5)6^py6$W*`WGqA;RiL{ru@B{R%E=^RCseT+7%j1Wcs>oD7I>Ix> zsjOgRsx>#LZ243d+RO9z7A(i{z7d(~G*i^x?OZPA$ zQ*D+W!{hQ&6=bT z(VW1wLxUvxr8gHQW*75>#z8*J!fYz}rK#I8*k{8?@=Nnle=+m+eaJ73HL1fL540k` z^hjzj=MB8bFYRR7h1bleL4Ik2Q3JWh(dPpF(rS^>+`q3B68utN1-zKa0He^~&=^Ia zs~4}Maf7GsmxA|9FLFUA|I^}d+@m_z9;P%t8~9Rpf7)x} z7;8<+>FxYa&^UClxxPo6HN;fMHn7o;sWz1uNJY;bifeuh`K7zoz0p5#6y%pKu3nnA zj%ZDOY5uvEZ2Q}d}$qK@=N31jAs|SE+)V9 zNrR6p^^qz0rGxME=kxZj6X=&V(q*%th#xBYrBj=ZQAS@5l<1evT=hJAUpgXwg);kFKKZ2`d=uHiL6PK_mfz~lw$=BQ z=$Gz1zMggS89;vN2FGaDGQ)%XQlsf5C3N8d@=GVW?qy+L`;cFH+cKGbS?fxE>9F>1 zmAcjUlV6%!!-V;5$s)hB&82J1FFB0-(qVQ_*=gB@{L*Q08O(lfUGhs8h1O+jKJF&J z^x1NU;25?O!nsW0`f~IPV(co;oK|qOF!SN#P{raF3>N%)-!?q_L)n5sTiNcI$w(? zzjSd)#`O=YkzYDDLfqrShuzEZqJ58Wp8n-NzbGy3& z{n86{!+GT=mjwEyc>&J6$)}Y9{n8e@x3PMOI`T^o86)`EWL2PF>N*q7d~%&H&@c7Q zOJi3LKRebJV||d$%s}PBY00lIWN28u4?9OQ+Il_zdi@~L6}>=*`$3LRtLjri ziuS7h{ya-1mEk$s{*m8+ZoEsFnUv*r=r=|W=a2iJ6PwhIqv-kHPBE_tU;+7K<ZHo~x9Em#RY(wJzj8(&InzYiTt-2-`A$R@Q$60im6nVT4PP;Gu3o-1sP zkj);i4ub2wI>qw6i+ZXt83I>mQ&w%Bq|uu=K9^IhS3^;`_kIKM+_ z2-oj#9LNjzrYq0knfZL4V4nx-^ylE2`AK)djx@Nc{{rK7Cr5Dh-h#bYlPy~H^XI{J zP1&wdzOqyIC|-MgAj^jLw>28sRKLDTJ=pWDHFy~Rv!N%e25#GoJOi`InXmkl6fIZk z^4W=~?TQb)XN5|U+}Lv=dkxR%d&hY22IpegS(tMU!g-KMH8{(Q^Oc834dBds9g9B; z&-T;$@%pcKFuMYn*Sfp$7j5RTiu2+B`>r1ix5eN;l<&zqygklj=^SBqBa59elwm6&*Km7KCab;Ef>m1v&cNCX z7I)WbY};1PlkL=k`4TvheST?8GS9`z<=G?F8ciEEB7q*_Gbo}1^us^jPX`kY_!T6MteS^Jy78W#Oh_xHQeQ=W6 z%ebxa`T~Di$8GkpHbw-Q(i(7XPIaSw<9@X6dve&+cyaJ*8h4!W*)Vl((K_+Q`)h_X z&kO1Gi1GUj9g~XIm0M=cHykuEGvYeY^SItnse92n)IRZW{=r^F>r+_I%3>yvrTWMZ z+8R~?$A3xn4GQ|DGn>aro9QVk`la12Pm-pNeFQSz@s(m_cuuZBzcl`4A8Ebnhd{ry z(WBPVVXnP=jEpzLQ_c_5No2gM)>f5I>V`;Uyw5xQD|(h6ERpfv*RK{6%a4`Fc#{(B z#rr!`B{JUGBSy%DlWH*ZOU-W^MEwE774%E%xwew}p=BldrBgigvTYokD+hn}((bGi zbEbp{^h+B%dCNh|>PhrVqaBxt`val``lXHfRgvY}JQC=a4qBHeO5cwc=$CeQvP^vq z>t*yydpf-~`oVe`{nEZ^{<2-~hYI?o$3_QA+vI@?`lT(?W2Cr~s-Rz**d$g4UZ|;{ zUux+ZBm;Nc2u8p3z+qLW@}(YKqfUck<;%JzD*C14;Q6kEZ-|OKwrLw7204$>VL&c_6!OU z$YT$lGKiaz3&=IfACoUS9^a+j zfI9;H((12jON*sB0(oqef=qF8mW4pS)cILwdFR0kfjqX^^_{|+dC~f}+_3G!|B;T? zzp3?W%E5Qe2=q%0sU~u3>{o$)scq1AVLsACA|tI3;~-zG_map(JrCH*&l>_Ha#4#& zI3H|S6^UH5PJ@}k@FYYNmh4bt*jLXICud&}HdCx5vd|m5CW(TKCA21OI=`Hp z{%;G3EVQX}3Arz~twa`jXj`5*x&zK*g*EB3@dL&9#j9vddhTPmD7Sqbtw}pwdMFOf z36aP`UtiuRs=slR$U<}A{Eunzn*_2@X@6NPnjS8Zg|4W51pb~yNMxb2&F2Y=PHqxe z=;%j&;$nQ7z%}XhUM`~b_H==3(#m|3_?FgRA`2~3&`b0?>M4Zm;L>9Vz>m#-7X@7|<^xx5^)pExU2xOr;#azspF+w5>wHdusy>u^M;F@&#o+x#N ziIM!$!M2fVJz!A9ercJ{e^~tYMf#nqd-IoYX2PrzAN7zA;*bww`26;BSkSi9r><

!wR-_{8*06bND@TmgG^i*OvbEjlrZajy%#T&1*x~8kRLSqOQge}7hIOIRfN!n9u)qS4Mc52Z+n*IJpx~e8c`)l62bAu;_745sN zZkLj0R<3A2E_%$-d`sJ+eY$huI>T7ig7)3KN6$0d|53EB7kYB9q3MmH{l2x}<%YsO zAl`rL1+?IeXP4tcU~d0!-&!`MdpL7|xxI?3rHtwjOnzzE^)aHbY%1-+?cZz3{cJ9< zM=Jn&@j06Qa4MEEcD1sf4;Y?9Y+>AV{BPI`tf&$EOb}xR93%IEbYM! z=-|qqk8|V5LI>x4VXpS&II_@E$&1+wWisu-?R`?0>(+U5WTB%v+3+FL139wLsIbSZ z>4z#DS?G(mbJ(#R3A6|21)ahfE0SmrZf%Mg*N<$%k%jiSaE`^ix8le`gTf}TkWR_8 z2RCY@2~VBTk|PUk&VREi9ounap@-`qV5e`wjx5x}alY|Mp`bmuHBBr;;>!`_mnN2ND5k)f9>_u;2f7F^ z)t4g+wS5_&<``7kgBy1X2J%aH z)>|y9UKm7vY2@V%BKdcJ@=LQ`%oQ~tcY`c+jMphOxmjM(9-L``dZ=+O?ZLg+ct}`` zh#?5$ByLFI%f*Z+8-~N!mH)@3(VS^Jd5Lv9d;WqYro;^RKD(6Erwb9Ex*Td@jHcK z);?tDQ2wspb%t5{cKyP6W~&MuS!nkqZFoaz$0e{(jS0|xoW>={YX!fQgI`L%EBK}Q z*x@6IQGj2npIFI^7zOyH`l*)I#3jHl)vr#OO)LWZQvIf_ZaU2`)mLjVm&V|i>cKB1 zMge}Q9{f^b6m5NaaNBvO1!nELx$b78{2hsfUaJ(#dxUpWFl(=vtL*AdKRsscD+fpO z{~}8;%-UNY@#jas?Nl&p|GTP@RWWl=Fl%pi=ODXMd7*+?`(Mlbc(jWJ!>s+spa7of zZp)E{g0l+$-zG3*p5-DQiFEx;qcah^MSQyV8%haM~^~YhU8&KwdW`RbbZs zcSshi-LV|8(DQe57^Hbr%-Sc68^-tS?IAF0zpk%0U(ur-W$j&-Me*hRd?3r1E!@rg zdAA>C0<-p&tPZl4HS$%=+B-Nz^LAG%3C!B3w+n=hk8~BY_Cs#vv#I4*tC+R#)X2!b zSxr_kYd@rAEMMprrDE2;MMf--*`H{{tbP1o=mmeDYs9Smc{{${fZp zYj2oWf!mFF4Ov`2Ia=}LzB2|>*1lJNU*7ye1A$q4JkRLAhdorx+OM*6v@l4vwe(sv@SySHiz-Q4Wm!sW+miH%*^sGyo=RdWEc;f3jva&tKppz%+-UgM%P*7oiN`UBcCFlFr%zTVi8)qfIY?S1?E=Ui+3zpOnz zOBZMD|CgiJ_Frhu`K7ngzYJJHa{@S``sw{u9eV8Gi0bOTETlQ4+?8`Wa76Vuw_KjR zNq4tS4H|ErFh~cED2+$oFQEfRRF5q5=d78*;E3vxg*MG!m|Zi(MUUS8-=8P=q8xlt zn(LlgMe+(w3K+7`9H)-__HHYVEcCFo51%O;a%7<{f2#56UR^n|P}i%4EOO@{jx01S zY%4q0Ycxj|+Gi6=^R<;t>)gi|HYAoE-F0^_rEx@P@gq@_?#J; z3|T06q|CChDLM8l9t0|Fd&0gQu+Y0Rmg!GSfc-gG2h|wh#=SPqX2?PpOmO5SLpL&H zq3-*`_^{Pi7_!h~luM;LDJOx_)TI51uZ~k%gAL zXveQb9c0KtJsg_yiLEPfWT7sR7QD2{Rfa5d%Z`n#`MY)uS!gxL{x05EgCh%Fda4qS zNO;bWg_cs*vbhI(Fl3>1-mGALyCNB~&`<{V{J{nro zv-n>&99d||H;_?ou#zDQ9loXqvxGB#k%fN!{)|1Ht$?tjx3bj9nF3=^5DoqpEqC2x^0Dw8N7d`VU?Kg;C&2PXk)_yW-~65BMU9C zD#3Q0%x1_!_2C7Iw8&-1LN7M$#(rcCpY*W1~%sgWZ%ve2f@E-A4q130qK4QtXB&$|a1ve1JE9xG{IqB*kAg;f_SE7rrA zk#NnatYl?XD+5CoYEtTevT1P)M;2OQah%c??#;+T@6`)Z7I#vKg&tm6LvgsI5(}O6 z-b@+TD2O8qoz%20?^Y&*Aq(vyt$EJV;|y77`<>t4YpGm!Ze= z!PO*Z#wYzq9=Mt`j=Y%@46Y_!liI4G4qQ!o-Ev2Q4qQzd$Ii^ufvZU@w8P{pxaSG?<$dng6}H8ca@m62j5kI z?<$dng70bs-&Gco{?@Hbg_^$Bhb}X?_@Ld`BuEavYcje%_5(@?2m4oj}EEIfK z4!$d~Q1D14c%%|pD0rj-JW_!y^k+~DZWCXQxMg(qT2|OOoVX=;qyjuriQE!AQUM;R zL~aQlsRWNyBDVyORDee+kz0aCD!?O^$St!5gbVOU$>#x&RDee+ky~#4v_WLNa+I1! zD!?Npp9efr0UoJDZV4W#0FP86xAg9tAiyJ)$SuJm72uJQ&jTK*0FRV>o~<)B3h+oJ za!c??1$d+qxn;w{)&e|I@_E1`72uIdjew&NF{R1_;>%Q;E_t?mib#xtKg9e5N6Nq>mFSV~ofgi(BPB*^**Q@GkCc2K@JJbWq{K_T?yqCu zkrFR$l{JTfM@qcZCFYm{9x3@eM|J-y;E@tLon<8%c%;Nm!6RkhkrF%goc%)qkCfPH zFW(CcJW^t(;E^)$NQs?-N6Nq>C3gB-smZ`2C3bqah7$vil-MbFqzpV#VyEDdGVn-= zoj%>{!@wgYb_yOTk1(_(b_yOT2alB4>C$(P7C3XrPDF=^~*lGOS#cXD)$;3|Y z*Ggr>&0>k2F3qy!qs%W*HXru2UCVrqZYH3myw>)WbJJkKm%NzcGHdggjg{#ljAWgldCJ~`H!#;vPw^0ZquoyHm? zrJq4#r!>}>Dvhm6-_OL~JF-*oMFsex#7@B%72t~!I|W}I&7-{r za7Xp%i++o`W&n3ohvTvhKN|ucAE7*c))G@AxTEwsxT8kD<^5?4?x-#!t;E{4WT(|u zM5*AB5<4CCc$xr@l-TKr@LmEuQevl5+AmdS7vvK=1&>sKM@sB8;KW7&9x1WY3Of@- z>)~$1PBSW;RzF=nK55&}F@VyE5% zE{P6%!ik-NM=HQ0C3d=_M4kYTl-Oxsn_2=qQevm-d1nD0DX~-VNCkML#7@B@72uH) zJB?}SCu--W5jzEsRNDBpBz6iOsRWOd*y)O#0s$T=vD4Ra?F4wF#7+x&xB!oo*eQ6V z5494_#3;WcVyEDdO7KXDoksqyBL8{+n6mlckqYogiJgK+D#0VA`~rBS5=q*M@rdz@JL07nK!Xh z@JJfBDbqYs zSVw(TG>=qzWOrejM=HCzdoj%;m2FO3S2T}Q+-P@1(L7SItLzR%^GGFlq>AQ|%H@l@ zDVj$rz#~;~&kj6N2_C7Ud89IKn5m+9r1IRUtbENQ70af&D7a?_9;wK3ysy_hQaSgB zm8yB9a&C`-s^*c3%+fvdnnx<*^HNpKBNaa{j52B-sW>s~rBU-pC3vJNdZb^KvTnua zvDE%ndq3n)IcD>hFQi;5t?_5-e8f=8sT{NUU3O)Nn@30TosiAHz517M?%IcAHh*#X zI&zAk6~}D;>=nV%&dZBqHh(~cE;4UV4UXCT{-X!VWyhW~%;xWmgmWeON`~2dUk1wzaSZTCC3vL76CS!>$_I~>_``&MIvBts)g#lm_i?!aJW}Enb8?Rwz$2wG zc%+60(_Rzn0FTsY?|*{E;E@`^BPDhU9;tC`wW-8O;va8UjUh1{v-!zeUmKVAQ;8dR zUGFd7>|4k1j6QHa1vsAya?X0aMysb>0y*YSj~sui4({vEF@HK@U0o4%FN$L}-^Qh- zIOI5-V>bVQ7^Bu*W1wt)_Sfa=^se~~v-#hDFA#sKMsm#Ncdy_r1~2yEn9X0kc)d9E zxIf2i{_^o7L_1G7JI2IMZt8GR?f)#7VK#sAi%jufdLNG2{BgUNi2Ze4Ip$AqE`OsY z&(C3)&5zzwR!p|dVwlaJy5yQLbPnT~&98X(KjA;83&(8!A*&3rzf)cK{|g?@?K;A9 z^lpaPe9u2$M2kD^IcD>HGXD|6x)#T5e*97|ar0Ul!)$)7WW8wHaT~*I{_2et<$|Q9 z9JBfDn%xt_A5`O*&39F5$St?^9JBfLPjnMc#;s$R&HucqmV9%;ukSNf2ZI%wd?#KiworoZTAFFq_}+ zKSj1aSB+yff7BpzxuMy0hS_|t%T1-7Lq(3+{4rvgaJ@5};Te5{OSYB~3rcg$=3mNQ zB^HMEV|Yg2lLzZWWJoB(Gx}^+c9s|No-@qm+jOlb53EjOm_OZC56+A|B^YM&FV78? zUX|}M%;tZr9xk(PTw<8b?`P*MpWk1}Fn_u*ew*0eL&q?Gx*;nvKgMy7q(@Wc$wnD@Ql9GgZ7A^pOy^I=$m4(SEQ?z z8J^KMb$SDsi$*cbpZ?RsT>P^3cAu(*O7TQasOuo)5LNL}N>;oOBdVLmJ#!E z7-sVyjP5C~J~+zo{L;yx&hpo?l?=1_a}v|UO&@QX8{1g+k%w<(F+9KY{ZV&0_`j(P z=f*kyyT#>{x->U>Hp&zS>zmWu81a3OTu?rV;rXR~&J2--AtM={U%Gmwx6~IjhI46r z<=XK%!o36d{qT2u=jUPaMD_Lz=f2Yp66dNl~dW9JA{L)8o&g-SOPmMS?o^Xqm zs)bI)x$$flA>93M2jkorGB-v}Tfala^Gg%Y2FOLt(^WjbbS(I3)n5b~ac(?wM-?MC zUoqm`7%>UXLOyIE@chzEw_q)5EGKYoJXbbKw(J`y@chy$jg6wmramgpjlt%_|zi@+s;>UZuHrGP<(l@O~twKX!aoa!f~O%^Go#)8pzxdv2<=p^iFR%e-0CP ze(6HX0dn)ZwF1vCeO9j@oUgG%;Q6KVj@Or4t|id9B^&PU7e8a}t2j3<`VawZ#whUo zQkUM&(l=oRom(>TM7G#8_lt^iBj43SmRNmU;M}NhlqD{Jcc!$8bvFQXG`8w+mom+DHK|T3q|8|Di{F&jNvVucjhI8Z7fpE?& zcMy1fDXhCOze#fixSAYXOQU-phicGcrlV!?FSo2~wzm3yty$7s$acv7OC~w>Q zp{lu{+$MRTs=1(Cy_2eHE+`MUP*c@hP;R>8M!x2PGNXKH)Lc;hs;-Hmxu9^)bBLn3 zpsc_17^CKba&SQv%?0HvhF?@P7nFen6v8wYlz|JXAX5bwlyy43P0?IX4lXFu zTu=@!D4jJ5E-3r){E(u#pgfwTGtC9%W!4YKvk94%Qbtu)8*K{zWY<}bVRe9&RMQhvrxtm#~-mPhEYagcP5gW9% z?TA3$^Rf+P^VhsL;je7JF=VQZ;#afi)BR{|Tkw4u>$QIbt!?Ljs?T3^sZZH_@J^Wp zI9TYNI=4(_^*txj+7=vC{&Kw+W%I#7<=~)FHs3t5keLjt!qGu3=#{`4-kD2lTkuht z@lhhJZNW$7;G=T%QBTaiz`#ePZ2t9KlNk7@w6+Bwm4lB;*?jO(Iryj?eN?$EkAaU$ z+5D&D2eJu^SJB$`?8k5hJ}Rwk!AE7_qjJqhW#FSyHb2{|J)0g6XWN30D(o*a@KGt7 zzr6Mlm_H&Yn?K8Z9<%J^M%nyPkNg<;sN@A*>*d1QfVZRhs0@5mjy`Isf?lluQ8@E6 zAI{EQRg2wP1U|uh@=+Q1sFclb5IdcLk4o8mlV>grd{mA;>iOO!;Oy>f@`B1-EL6Zp zB`;`p{e}#DRLbUW-ug%ZAC;qzdT;b;1$^e@-W^Gxh>dgd(M;;!q6?$e9UJH>OH1U|d|{k2PT zzhyW#EJM$PTBe>@C~#B`J}R-(zvp=^gHLn*-~0PoW}mLtGXC_v#BTqLluhoG!QbET zX~xrp1N5`GXZ@40ywxBYSN30)v8~A~x<wo9CYMK52@8@3*=c{zk&O3!Y zKI1ZNj}JUm37#rt^TAV<;HgqJA3RkFo+@SY!BZ9BsZur{JXHanDrNJ*Qx)K;(jFOj zsygsgC9+oVR2g`x5?L#Fsti0;$S$ALgQv>CQJO{FoosXA~|X`d0?R2{gfM&zsDrs}{=rTxvi0WBn- zU5>K(kM^w5a6RyHh=h{{sMed+RO6~3KQU? z(q7)@=MMz0|k6kiA;5# z-6#coREa+7s`y|d_^7m(_qD8_4t!MF%WDx*pn#7mk*U6&QJ{d2D$z%Eah$IQAC>m< zRyVO=;G;@ps^FtC@KL4aqcZSOCHkn=F9Q_tQE4x4%*|*8d{o-Y10R)vk1CO=j<$|q z;G;@ps)yDuRlr9T$W*~cW#FSqWUAn!GVoC)GF9+V8ThCYnd)e-QwsQ~MSFRs1q%46 zw3i1yDgz%?B2xt)m4S~cH6K+0AC>m1V~N2R?y@KG7~s1lj#BeM$(d{l`{^`Pp@z(<9%IDv7+mgC@~N@S|wqcZSO zX)h0aR0cjO?d5@w%D_jJ$W*mCpBRNpkUg)pujsr}>_ahV8PY$l&H0Goj>J?q!9K>@ z)Mms~2i7aer+@23O!er~gDh%%3^COg>BHDauSvvIZA%*zkAJ5VQ~hq%L`~ln$C0Vl z3aKI{#ZKeMRJE=XVkTP03b9=1eiG3AM2z<#FQs=ld6{^{%JL6&&GNqzuefKOr-SY% z;;6ji0v&We(Rl4WZyj_$(YXDmWx>$>MB{Y!@E~+Qkta6WIxio(pNP{=|I&J;ww`d-5gU@%&`Qw>7VyeFX-e$JB)rqN2I5(BKJ1!z_ z;GZ^%{d~KWxIx{(GMsO2MNGB(*UxOOYX@Sg18*NSLt>E9|n5 zm}=OG8SGWuU}CB%X8tT-tPe+S(4^`>HhCjtkAWL}-Ev2X4$dW}nsAx11zU#`Q*G_` zO}RP1pCePP^x&{!S}Bj1>JR&E%E40yiK%W*_^zDp6-`X_`p#74ZjC^W+~7cFo^r2E z3^CO=%fpn&NFy=TUYq+UkH5zdQ?1^vp3=idC8lap;iA6cd6k&zxBxe!StvO9zzt4~ zETyhE7|4;SmK>F=FL)Nnk*Pl1;HB!T#d2h-A^qp5{qkZsGF7i9bJbJuGayslRJ*ew z-Axcvo!;oas&0$s$W-UtIIZ?6AHb2R4m>c+`1XTJOf|7rSux<*2#(yKoz+?6-E@_h z>gPmHHRZUGnCgRjUDTZ(Mq;WRUz8Jz7yEJK2IZHS@>^jah#Sm}`pNtzlp&^SQT;r7 z*UpNV>R8W4%Fj)3J_v9Ft-p!>{%XBWbdJ+Er!0@m%!BkSdfINr&H<@&$y0rse{Q!| z!WMe{#oGG~mc6HbVeEv$J}LUzzvl$42a4Vw#@G)-f!{KYoQ>UcVdgy2_Ds!r9F!VjqT;Y_}J|Fs?XisPQF>3?# zJ<;59e#A6G_%It9SFEwe@F%_sjR!d1G(g`IjbG>dG|cUAm-cj^@5!ipcZBA&sHatp z>$?_Z_W%Aoq5FwJ_Y=*5O(Ui#*T=_k^i+HBN9vj0)5%kvP_Rf0k>kiytzY@JNKF{R z(Nn#aTuH{?>PDVw?s-?45Z;(P)pp04$leWH$Wwh3*ICL)bMjQJpa-z#tD?+)`Rn%5 zWLQyV-#yrj8Pi5^^i)@cL@Uq+bqGR)RcL?)Q+@k*o_b5Zrh4RLhJv5%23q zlc(y``kQ)qkv~UIb-Geg?PyfVQ(bmbr{?`OlBYU75%Q7~hLNYbZd;rv@o_MDs_r9$ z#rRMk@>HkWuT+0;&nHhcA}3iiZa;`TRX_7l@a*hCo@xNkQy+fJBTx0govZ4A@(0LM ztpl#@f%m=1Q>`AABA)(nAy0M5nB(FM%$ew^?%8f4%)_(DQ|-R}hIm~gj6Bs|8#2VW z^>xWpeY4tJY}lSjo@(ZddZKF5Zt_&qqCSaC$x|(T$5MWU zb0*PKjqUnIWcXAhPxW?yojmu`pFGtDRieewxMk$2PBwLvHs?IaQ?=_cL2QXgCQtR0 z(+qKLauRu}VFoX`uB-!js=v2ZkS>$oQf7bPr;;*mQAzSthqnok4KLV|r~3UKA`e?AQ&PqlmfHR8lSy~$JEqtuelD~?lU|KpKd{h_CU z96i;TTIOo^e*-yss&lv52q!x~j-G1JdARdUHX%<{>&TF}Ukv?94EmL5od`Wp*q1@) z&Oz4_gRUj=KcQ=hL)Q}dpU}0$p=*i!Pv~0W(6vPVCv+`w=vpHG6S|f-bS(+3Yl%bG zlF+)AICL$kTGtYXt|dk5TH?^P#I&v@4qZ!3JMZ*=b0hYQ{JLF~wcHABt-W^MDfCt8 zps$M7n9x_HgT5+SdqQ884*II-Jb|z0Kj@&Z%7DHQ^i@IjX9JC)uS#zdJCv@0zAC-> zj!N`8^i}D(ZIgVw9{Q^E=Vy8a<9PzmSEV1~UygE}&{w5@^}HXQcM6?Q3_78t)(OR+ z6N)_5V;{r$HmmatnW}MFI-7RbftV`vH!*$WuL9n?ud-01we-nAC(BH(Mzll6m=x<`s-$ZL$=x^fC-$b4& z^fz(nZz4|>`kNT^H<70b{Y?z|n`mtd{Y?z|n`mtd{Y@PDo5)jz{w4Sk5RQ+=Il$xA=DMEQE?Z(`8jM4l@2 zH!`- z+wu?l@OR7h2|RbMi|YX1*=eIdPxW-T7dPqEQy^0vy?hUA9AHCh+Xqwku|`p5w6=|1 zH-xXZn=H^%{r=sTFPP~lkf}DPmBZRq{iEW!bI=>b`xS->%=JTW6#u=^PiVbSd{N1J zDl*lWiFs_F?+F#por4Z3w%0XX)jFj3T8rDN)*;1*J?gJ&9a8Lbjm0XSI|m(7JY!ah zs&z>5jz6qbWUA01#jWSmF=!o9?9~AeRqK#q7A0O7wGJtMEbNb7>yYB58+TB&4k=cl z={Td-A;s5Q&sDSzDPDq|RWRcZ9a6mZjZ2EwA;o&ewbP?71RYXr$?j`_WMeVIqT z5Ohefn_IUk=nFxI6z`;4!?X@5?v*!-&O6-$-8UKjhZL?%H+MeCNL*R?JxdY^6Q zwr8ZzNu>9$x;Dh4&;1-45B=u8>d9d0C6{ks1ZFt&SWB;KT~YM44SQYNS$vKwypG*c z^m_5{9X(a(ijvS3#k8&{30+Z4>xz=l6{TohQ4+eMRLuB8SCoXVD4}&lN$85A`wMhM zN$83qb_!il61t*@okCZXgsv!Jr_dE8p(~2mDRe~%=!znC`uArAT~UVOdmnT~3FwNV zd*b^qCPqu`z5~5cM*h8M&WGM8V;e)!y#RWnjOsnVU_8GRdZUb=8|&!a0liViP7N#4 zJ!RgzYQ`}sL+D;pYj`V3(Q-uyG0Uc7rRG~u(I*#`dQw=w9fP0>1}q_h161(_;zNXfu1T@|fEO5~lGPkVXLAtg^o&R4V!DcQ4pIYsM` zl6@Q}=4%~NqI*dv+ROVoQ-~K|ZtHO`4?3je?t#@*twT!gEES<@9a6%!Ww>7JkdoI* zFIF+*f45(ZygmM!s&z=o660>EnDK`WDdD(gh*9g15`*qNHfkMGGBeCaXdP1W_?3DB zGyc#aB|NLRsal7WY`QNLax2s!B@@ji3avv*u6*5{?mN&SCC)Zms3KE^4k>YZ*iKdJ zkdn|LB{1W^FdKT|V~XxOvzO9a41PfetAN9Z~`_{w2ORO0Pki=)6M(2^~^G>yVPrAw}n%LWh*-x2zU1Rp^kC_OIX5d8g1J z1sw$?iK+U3wv@K^m*~7x=#Ua$ANvzig$^kJ9a6+pp+ibShZHeY=#Y}oAw}n%LWh(9 zx=c(JI;13YND)(o4k-y8Qp8lDLrOx26rFbp9a7@1eIzke=#UbB_()=^Cl9$w=#V0& z3LR1cI;4oHLWh)q4k==)&>&wRiI;4oHLWh)CyElQDDs)H* z=#V0&3LR1sI;4oHLWh*-zR8N1YJ&Ad0Uc7rRG~vkLWdMFRp^is&>=-k6*{B@bVw0X zg$^kJ9a6+pp+ibQhZHeY=#Uc7AyvdwudWl&Aw^6TI-~@2ND)(o4k-a0Qp8lDLrOr0 z6fspdM@Io2Qp8lDLrOr06fxDoZW%C7<3I88#k^gfj*CZT;P`#sX3s_c6?LgJ{<6$- zu$#voe7*9H*`8I__n|TT>Iwf&WBBi$a2<`|>pbA=X$QI#=NK=w-*55t_&Ly6`+R7O-v>X(zdlbI!_R}C zGmY`<@N>j#@cR`1{D1%d`cNi-+wZ=KYU*t7yVQ8z2S9H{5o7Oim!)j zWbymJ`@`~~=>6eWS^RzBze~7|-V?q~7XO^^ezN%I$In9hh9$Ju#s6XNOWhG-7p0^@hV$-HN`@pwBq=mV8Z;>4 zzn=B(_q5fYu5a;^_WgWLp7z=AUTd%Q?6vpW?|$Ed|2Opon|7q0Xcb9#p>NQRv73~me~<^=_pqo(-hAl`!T1;dk2?6?uUA9kI$V!(w1;+q19_%A z9+Y!^FR0J$ctJbdKF52%eg0Pma`}6ahj#cnkq6A}i9BF@jJ%*cZq@gIO*?{3`+|*J zX~XCv*yt&k`vv_4Z!DfSJ&K>~ci?@Jk=Z}<-k5#8-nue9+@WPY{a%w+dPaxk;lk%t)zenh*0aLv!r2El)6*vu z(Un_m3E%rpSM4o6=skMlj&Rm219bNt{La8HJ`G>`<0##%dnfPK-aEogFN^BB8y<*H zsk$Ycw^CGZoj5%*@{)D@Yl5Tn>Tx%!tOu5bpD5d3?~g81KcuFIAA7y49#!O!+MIe{ zIQ7l0y2%BHRMmU$3vcPzUst_-sZwck!zp7%>90FqugZKF4`;tBs=td)j6~j8AHKUl zRDYU37BARkTlnH`qx4g+^zv@mwKM$5W_~vN{pDV5esAGrKX%sh3S`zVe7-aM_?E`n z+f-aH7`H7veNILF(xG~K)VJ%yxen*iS6tp!k8kOPyFB=zx4&9%U1-}}{O&4#vs-s! zTiv{%vmWtGW*WF|Quy&_8|ls0mZZ+DXM~rhSI|?x4b#Me^TJd6<<>h}w&Qb43&TUz zdN0#CH`9RG&xZ@_9N~T3dL(su=DF}kKR*{=_RCoMEa|E6;eul$g@#4x+pJH9SF|dk zTKtegN%^ORx7Qx6b|;UdQVS-9H(b_RO}l0kJ&-;roHNrck<>v^if4U1y!P$2e5P_N zeP3jLxOnC9UYUWzsq&`_!%uAb(5rq)Z@T`nMd6lv^60g#+tO$Co(-?$-wS?xfua|( z%?mfb_Hte5-Xz*r_=)iS63y3*IXW+;O$o3UcO#eS&$xP-l~ANK@JGNOfC4KYSXH>4lSA+9+aMkCZx30qYHcC z_ghq?Ma{!{#;fbY;~s8IWseeKqr;YSzsqq6)?<}A#UIZZ}U zj)uLxbH3jhem_@~CiY2>4<5BGT&iu9%D+86(&~rx;U6CuMV$FUi9(sbbdEWf%ofEx%1|S zcdE0f;?hnuDR(fhQEL4YAWUxpwzn4!Vk4RZ+Wx*QL4ma_J-LPd3kcB62@$~X%Bm2 z9vMm)v%3fF@DB1jZZKx|HP5S4(pwY8?DBqpt-y%l3|jM?CsR&Zm*;L$pE zO&brf?!$3Wes5!+IAY!TpO4i;$1IK@*4;gEq)uBkL?PCxwS9H{{3{e=Njn=4N4MX-L_E`^o6-1gjn~{?dR#`JK7Lp-KA+Cc|W~$1D{n}7v3}RA#diM zp@dlX*~EfgmlCOjSXX;n?&TfXRvS6ioKY45eK)CM(2~eocDOgSYKeh$k0&SJQyB0uoQk??|Q} za@Uf0qH5%&;VW88Jo#zU4wY|TFNr6g-}$)Onmk0}Nx6Dqb=SjVB%Wl=`DUb*H&)`w z)|?0GW&0sY-*Y@EGodpT*_~M<&VPAn6VlP*8u8@d%1ZR*Pjxlo$+An&r>h6I(TFFX zezBe3=XQfeJQ>#Q5!Lz75RG`!`(Sak>eUpDc=Ar#IpG?7#tiY~%XvAxLK9LYo@9Sy zl2<%7OyWt`*_*wQMQ)UMQazSS&)nQj;>mRf%jwtK2MV@?Wgi6(jCq+Y()yOqN zHR8$0bz9Z19eQiTlUEn!p<;vEYQ&RPpH!rzHT5*&$!~8orni49t`Scvj_2QN+LKvh z9=!9(uB4|P@(`1sZ8MNI7hUK*#xZ2_fH8DyYw|j947r=%S9Z@AgO@+YG31WTDYRjA zF|~G4j})WaM@o@(ElmS*};HRc%7X-|6!XU<6rIfj(_t|`@QP?WCZ7;M3R1=ON_390w$F6!@E#Me3 zzH}-zTzjGF!7(JqM^WlsYSr>vIEJiTJciO6*YVbI3>lwmFgpbkvv+yz8wq3fqr(%uB}<19#_an8 z&-Io~NhOTg>{nbIPTLigF}v`JlFEC5f47c#GUKO5)Q!7_$e8_L_{VA|KQoRod#K;} zRJdUq8MB}KREa9TRo5T04VuvP*A)NFVSxs(~oZzmst0CrAkD%)st9v zVZQU|x5{lL*43Q!p(<3qx5T>mr;}CJXNF3wYx-Dz^?Bt~iFHryNMH5_zt0n~uK$sX zyjh1+2(fPS{wZF??n4Q&Zt|QR-tM1z5n^4xc6oJ;XIc|to#8Ekx5a06rP#xV)Q~rL z-tq0JV9)CL`FBR%dP!yBwaP_5jG~QoJFE7*R_Q+^O3&3ujim5erO}wNbY9u5@jkp( z8JA-?H9UB)*N4|C9lq^N#Rh%g{laUN-ObujoiVxfVU8_>?r2PvT9?q3Ikp&{Xv7x7 zAC1`3w`@Cl;o008vE_#jH_=nA-u19nS@QD;T6b5fhqcPY5>fi@x0!LQRaUo)QjM+m zMzB_SIXas5!ttcv?ne5^StTW&JUOYe zzWepe5>LwS>8o?!`l^TZ$%-dO>boZn_OL$rb?;dHQQsHiSf7mMXQtNY>>t7U#LP8H z<{I-ZZun*TMNwU@<(vrCC%0b{)q8r5k7IrE#?n!GqweNmeUg^eU$4A#iHG$`#o=A` zqx%neh$p$eX`*)yD<<(|%1f2_cZcgrJh^C2UVYcittFnk-slr==Ndl8$nm6U&naGH z%utCZXFq+hmn}=G#FP8{Ia*_merDF8dOz&v_YE*NM$bJ^@9ZC<8l36LH_=$1G&=W3we-d7G}b2v#y+J=mKmh6K3VbU6>5F$F&gWWH+Y|Q zWNfU)`oydoC7y7;qd4D@c*6M(alRw*g!3KZd`IF5=R3stj>HqrcZl;HW%3>3d`Fpl zhdAF+Cf^~>cOoX=AcRZ8t5a&Cd$#;nJ9na)D#QBbA@*U!Q$20j3alYf3 ze1|ySiJN?f$3iS(@*U!QN11$wINwnw-yzO-B%W}-L!9qOJmGwYINyHqQu9kSh`3`ZuqfNd;obPCp?-1uZ+T=UL`HnXEj^cbrn|w!czN1aP6XASE zn|vqE`HnXEj>q|qHu(DxGle0%NX)bXAq{Upbb zIp2w!d`EM>6EXRY=6pw) zd`EM>qfEY|Ip0wx-_e}!kjZy6=R0Kb9nJX;nS96Ne1}ZFgFIb$Yw}R>3+Fo?=R0Kb z9nJX;nS4iczC$M8(VXv)$#*p8J7n@5&H0Wp`Htp%N11#_bG{QX`Htp%CvNf`&H0XJ z@*U0jj%V^6&H0Y-mh&CW`HsYsw-JeLZM zOVx-cCNCDAn0#6I!}(5x^BrySojB(^5>Gha@i^a+c*6OP$N7%L6V7)u=Q|QlIN#Bn z??^o1d`EM>Bk_du9nJZU#1oG5#5si@=f_2fbBc(`DTs55xXCGqa|+Mo6vR1&XL1VS zoI;zNf;gwpCZ{0IDYVHch;s^Uatg&cg*G{b;+#U8oI-Ij5rt5CKn^l#k9%Ah;uQ|7{6_Nv@spi1+m2 zAsTCvMmctQt4j6KSd(<+b5PH{(n4cR63JUz7kR&`#+u}u=UVB|tNfeRye6qxp_hJb z|4t8UlGTs&*Nq!2@vtW0`9*WSBl8Q-JDT$ynRhxh>7_rsZKsELvL}AEUX)fq;>qfd z`S)M*)RK6TUOlhgzM{3nle^yE!R!295>LW+JnogKHbmmdm9@g&;)lmbJh>^$oAJKh zScxb1hq zcZl;Hi6@-zD9(2zo^ZaSINyuO$4YR)@kEOXwWIq%RW@6eogcqZ@AoOkd$ z2qf>&oOgI8@6eoggiYR|Iqy&=@6eogD3f<+&O4OJJ2dAVvQFkaOLLy3Fc)-aGf=-& ze4)Z#O`ic{^cU?&VXx+nFQa@t4QCf^~>cVs`7^Bu+cj_k*B zzN0wbk^NZCcNFJ4vLDO&&T`IoB%W}-<8i(t@r3gokMkXgC!FtiobO0H;e1DPz9aF3 z^Bv9kjvr4NG|`;zNIWsTm3YGW4*VkVg!3KE`HsXB&UZBDI}%Sg-_e}!NIcD$MH;#qdCWkn;eIKCtz#DyyVyM0K45Gb31^EN>UplXl!2$NFS^bhPeRsI`an$!j+b((w!Ddsv@DbMx=g&)w)@ zePTE%x&QrsoR@gQ`HtdzN8$3d`IF5=R3stj>HqrcZl;Hi6@-zD9(2zo^ZaS zINy35mC%-=3UN`8HlMqirQWm@8la&S5$0x_e65`2v ze~y!T1ZFOfz4XyjD|;`LO_9CdnUm*wljaYSz2C;|e(@f>qnqsg_E}qk-`Ubw_I{g2 z!}`OL6=m=D^Jr^*!_>U8_xtXqo;p49r9wRUyga{S_tsYw;)$8#WKS>1cW@5&vwbDh zs5esxcz313iFZ12xfhh1`$1ACSpTDbu;v6d=c%O5UHATo-@p=V&R+>G*<~}%UkS#U zsNh{F8Nr|KP4m8gafF5}^E`rJ^9(|OBm6uInKS^^b*FPn^sB)APBY|_-aifnpCeOp-wRW0-NW8rG79M zqdX(O-)-~>WWmlE##g^OTz``1E)TNIyL1Gb_vZ*U@6{1onRm+w-rlUHzV(@Ef`2`` zwa#|+1%eMR?yavIzD2Ihh_83#Zh&`6$h8^4!G0igW_#+uo<^2JIon?c_7C=9P#)}$ z0h{{*Qa>ZV4P>{U5k2iXY%2947OTx{$nZ5n$9?I*^vvA^hV{31BG=VIAh$}{pFQDf&o*75rCr#i+~ z3UZAN1t05u`^Fc9`o>3sjco-Rn@c+xv0LBWEfepL$_NhDd(gqe2eFmyQxi|5zb4KI z4%R=o*2EAg&&az4?DjLFr(MU4eX)=IzNurqgUiGgv7w1Mf=#RtY+{JCX*eL|e}O&p z-PAcQHuIX;*35T;-)eohTo8ZE{3zvS-V|)+z5pwn0f5|$oHzdF$j-z$WMlK7U*Ps} zv6;&Vvg~Kmj`dug{p_BZL*-gC_XQYpqTu^hbWE%Pj)nii{(=6834(E6>-*{}`FX>{ zxgZ5>&I<`P=ZJ8YD3du~B-org63k!WJd$9XpThO1Z_Y0XE?!~f{NQ|;IqwwIKPl(6 zt}699%aeZL9G3@-^Hae&D06;Fqx|oj*BbT6Yx2A%+A;l=HjNzw^H=}Kc`ev)PF~+% zHnz`n*=N1%Ghp`FF#F7yt(&d0-Iq}pL#BTQ&iF3qBYYS1Q5&0P!WlH!6gIJKYunuR zg?*+Da;_@%hV8q6lZmr=rX8}{7i{DT=I@}7VE7z%L4BjY;Nnk1PT~w<;%uR@L(oow z+cxKoJ*AG3BiPtqbT)nw3^~DAgC73h@8=2w`?_*x6UPC^0mlKy0mlKy0mlKy0mlKy z0mlKy0mlKy0mp&Uf&;!kWrosnP4Hx1XzT|GIu_HZ*V=93d|z_a+@)b3bKX&OGv^=$ z|5N80ldDb$1>@43;}o4w*11OX$^ZL3?%QV{?K6?~SxNg0rG2)N+e)0dv~{-o@`pa2 z^!Gm|&Dp^3zfSnh12(=BY<#CtZl8Iz&%*Loi8He1Osdqk&(xmE_dkLoY{%Kq*~Z3q zK_3(Ejx@dt`j~jvr171Ub3^c*VB@=>k2qf|_{}?Z%e%xO)$Y4(6aFe;E8B*)ZEc&| zzA)p9^*=4{6$N(TE;)VRb7u$N3MXy{d9N$@L}tjO~jz%VP8J}dwiSt_0rI$*nn%GjVLgs=thcbH1IBub{}GHBgEbw>vEIUZ92o1Zv8fA#b!6gsJCs94P@n%rTQYA! z1~A$;GDNN&#~=fB&<5H9hWm(5M5h1l$B)0?zVR;EvP*=K_v{F9G*WE-ZB*CnyJ} zgZkV~VqE|^LHqbOkZa^fJGd?w6KF5cA7hVm;W^ORln3Jg^#z-D2z5;Rf{k3k{1x;O zZ1fat^cQS$;h-G-4eG-Vg1Mc<*fMsLa+V8w3N~^C>c z4gVd!OVhqD#h(s~F`P|&PB=R_J2(zF4%i%kHPSTJ)j;+-$6o)~>mqx-Wah+Ro=L2) z%z8%3?e!SvNW8xA3tAJ#L1&3Z<#SlwjjJtON$vz`%*^$hYO zG-$7L?DdbmF0$84MlRu6{!6T{jGj_%^cT!IQW?lYWz%25#twq{E7(V{y_PWclycK= z!N&fwHZy(+)@itpCjN51%Otk?_xbMk+$i7;xZ|*I1!sqUn;nF^I?&pVS9Tn;n?O0*Qe|uiA=L^WO?tP!seGJa`F^`BH zO@9R&I|TNHeFPi32{!f=Y`zz4>>tdJN9|)+_r9gB??3DVB+h9h_6KbH*mkq+Y1`Sh zzwH;>Uw`l;_H76{*na2#P4L0yiOnC=U%A%io6SSmHR!J?7n|7jvF&Et)3&qGN9<+$ z#r7B9-{*Bl!jC6)ony}Ah(6{Vj$m^RN3c1EBiOEQm)rI2cDT+7oy)T8oAXP7Zi#bT z=Dd@X+h?fkvsDHMXPIzzOV&SjeS@Xku5Y(vbRh7G`vn~Y8yy52odw(V?Q*-m-Hthn z73h#Sf5kc^&SjZ8!Z*9VU2fMmSo+R7;7nbhbK-23@ll|2;#`(p-}qYU*!7LCx!kQo zzzb&w-wMtS|Fj)4c1FdXzkCfcJ}&LK_yn+q98>?e*ytm5GJ;KCf;RE*aWOc@`ww#8 z!CrTrjP-_pkJh)XnXd_bI$7%t-hbe8ekXrl#lJ^;YStU@SFk?(BX)jF-0u_4pXj>r zRQu8S>)+)sH||c(nR7Sp{+WGgH{T`Bw@5x{ugCt*K8ahmB=)-!=YotqgS92rae~dd zQF3jwo)qlXnZAAg&c4>Ej+1V_bMqa>IdUleOYG+#Yd_h=$$utJx^d^mof~(VGP(Kg zL!s@zaevH}2fHbK}nJy9K|)C;21u0?&B~Huoq6AMd=-nYuo4 z`JKz}T%0`hang;ufBU#g)BaW@{_C)B3ugys2gd=&0mlKy0mlKy0mlKy0mlKy0mlKy z0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy z0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy z0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mlKy0mp&A z;DG!#hNOd}kueqMI!`JCRPi{{K`m-GU!t>jbAj_0{z^1-n z(+=9oWZD;O%wNGif{on-qkoWxYx#TP ze+0uGkcV>E3G#qpzvQa9#b1BK&X4~dKdvj1Pe*QTCB9yE)mCrDeZ2)2`r%IR+V#T) zXC3fHe9oG&g2%0z8tL9ND)^mOMyU@Pj1=7C)AefS_csZ?t!Ex;r`rmCdUh4s*tE`{ z@X3~IbJFIm&1akEHvjE$!9-7t7mV*<9NFV*^;>Ot93;kFVm#X8l-o&+Uwd5J?7FNO|Y@2VDr6TV}H@p_(d?}1aZUp&Yx49?-KK!8+Sa=+_-C?5tm%d z^w-9JjG00FwBxEBZ|yj2$7efk+wt7yo0;z`GTA8LNborxJ%@-$QNYn zxOL0P+xIi$&f{1W?9&Q1>rCOKS!V|P#6GQHz6ARQg3UTpu<@5*x3A*%RSZXj4`z=` zIL6#_dtz?fCGN|xDcpW08^Og)7c*VV^zS3P`w0G?jGZ&uxulDk{(W;7GhNJdG4uDB z>Gm_-ekSsEo*(d+xWDi22l?}by~&d*6d&3v3zWu*W=4<;I;GcW&He z%5$2{dGFvpSK?f*oiiGq1nWTTOAE%j&(y>D zJrDOVV9o!_^AB#mbMu{>@7#Rn=DVZME!gK7+WOtxN+ykof~&<+#&zO-k{kh6pVGB%hQja zr@Q@3x1Z_a=c$jMZrr(X=f<5IcW!-h{Pl^;?_7T8;^e81lWyF(ap%UJ8+UGBMe>vr ze!r{B?_7T8;^(Q4pKjc_ap%UJ8+UGB#qF!$eOS0B$mdbd*xwOw^PQXT+np*h`u*N6zjOJW%kNx%=khz3-?{wG<#$-GU=4G+uUp)?Xt&OE z>y}fyZdq3(pN`zxO5#ICaQ;!3==twAB*c?Fm)6&J{#Hitgb~;3w83W!{%}q|y`_UE z`)R|gjMmX_t`R(CX;jBYgd@22!J=dJSvd~Gfe&0iO#iU?eh;|z`d+%wv`+-@U30bW zJFbA}_QHW`I{mzwf{&%=>7bjfLq_nU6O-w^!L_7cHny*Q^1k|d@ZG+h%NFdUH}=UY zc7CO0e?8~$QnBsF&yLoI@4i~_;4M*Ic}y;`^YHXk{bP$9V$TBQhidi7G{F_qd+MZ0 zdjwxO^(uYa#}|nXRnjZ#()H>J{$_4&t?RWDJgM?}@2-n)7QDCeXm4v|q~PZtdo2EB zBr5prr{j^fpN$o~Y{%_tMBNdB&%S+=x^3`{g3md8J~cboTJV3NkG4-Uf*Tdirne31 zNEi#3jxVP#eTM|EsNPs_eXE4v+ZuM$gHwJLU)MTskiP8Nrv<;CH$|VNlLZ$$9M$)A zJx~wryuUa_9~f9le0^{G!CIX&TkwHUcb&X&zu=E%G}RZpQdInMPrnL!TJ4D7l09?i za@{%zZv5pc@2(Mj1b1KC-@D*Dp98CljgPOs+2=s}$ht^@mwXQ7e(_F~?StV`|6tP( z)Me-T95}C6Uh43I&w*pv&bNqoLqH6ENI8kNYM(~j9hf{<7;}zuQ+8&kwwkZs}E6 zaD{r^DPLEA&iZ=HAiDg=c^>M_T|0)F#cK;bR{MXaP5auv#)!);XW#hT+z^k^zr;g6 z?@$VTK;6HIXPI_1xAQ+^)?>V{x9F4+{Fi;S?SMY+yXk3(|9=zz&waG*b1M34{PMT` z%XR~&#J~S5{x|ja|Blb^%>KA?&C)(^kB`CO6Y=kf+TZ4CMliRZgFg~4PZH+wetes- z+(aE`pX1xg*~i)E595@_PFfCstYaKG?8lSS)(#n2BW0w{{~Wh7GB5n0&WX-hC&a@O zk7=^jWEsI9cpv=z8ULX#f4L6yTMFhx{NF!|_cR(o`)<44d$9Xmp^RYELw&BRGl*lR zK5_lO#Aw&(6UzubXF=o8{;V}LJ{iGZWvxN{(WUB6S-OTXfAkB5$}hY4gNk*(V~o%4 z^wp6~Icw;{HLB?$_gt#J<+8aSRo3-#-ltwVr-rVVH%V{Eyh@E`Jo%Fg^(Xm%P?^rI zp(j0ewhkT4MSZi?(4Xbm>2<4Gn7-#a;r2_tvNcOnGUKe@KImN@sYvb5t)Wv^wDK?ATfMC;7oS6YlIcyZUuwes_=dd|sYUi0y5(I> zyzrYL+QM?Xd^FixKePay&E-97uk}{^l$nyaoU$D9)?Tz#)nmD{N1w0zcVDF535xvhRn(i6A0P>QepWmrWW&viIbjb;5>HCZp~+$GY1ai&q#MGxr0dMyj= z#5P+B+rftTKtJfo`ig$gll9eSEq=l~$luSXeu=*K{mtH4T>fOMygF7Ov;Kt3E57ra z_eG1mx&`a`*r%Jlb!Cg`ms!u%g%)}Z`jyeyxc;sO@Am5Iih2Xmgs z{?(u3_e87fB8)FBdrcgE{fgVf2mXT}*`IOv4}N5SdbbQJtH0qkZ%w=1>t4ICPGY&g z)?ey9oqn$F!*U_{_X!9uxQsUNesgdj?%)Id)MK7R3{Qx8tPD?xd91)^@S1t7z-RE9d91)^ z@S1r{;4^s5JSOlNyk;H~_zYe%j|qGRubIaLK7-fHV*;PSYw#HQKrisva9ZL4YzSL| z$7b9`z+*G+6nG3iGp`kR3_dfj6?hCjGp`9e2A`SN1RjIW%xeOV!Dr?*fydx8^P0e8 z@R@l{;4%2jyp~u6|H9AUv589r9-FvC;4%2jye9A%d}dw~cnm%>uL(Q`pPAPRJO-bc z*9trapPAPRJO-bc*9trapPAPRJO-bc*Ab4f0T(HQ81XqHyq7wLC$#?ti8I3EA+J?h zI_b@F;I{au`jVd__ncdU-nuqfuWf&&dOCXzYVdMJU9!s*HTCQov~)m7j~cN~osaTt z1@!1o52=D&{>I&zb2aXeb6bs?DdB+?!-SiYF4AIIcw0c*y{Kce|*vS zdoT5dvp>G(cHUzD^k;vBSnekF&lT*Cn_2GNg}?G5Yrat5a(T`ta_FDgA7xmF1?(Tq z{^-c%!`MIR&va7{#Lz3^M_bp4gH`e>#Lz3^kjWC^n;$PuZDimllAqWAM|8>J?IBLSzizOK~L7# zgMQGH_4S}1^kjYG@T>8$hX3G4_GcXagCE(S9{dMCvOhie4}N5Sdhj3o$o}-;KlqXT zso_8Pk^QORKlqXTso_8Pk^QORKlqXTso_8Pk^PBS3*Ldt0Z;!5%QYF~evJEzd0gTj z`vPkW;WYaQTqf|E?Lfv35w-&vJ1DjT89OMp0~tFgwgVYED7J$#b^wo+u>*Llj2*yZ zW$XYRM~of7(9xKBW@K_n1fX8HbqL?RSc%qmm zWO$;OCuDenI75afig`kYClT;C&=ndm*b+Q8<1PXoLr>@n9z##)3m!vH=nEd3 zai_pzGwy`PX50yn&A1aDn{g*RHselsY{s3;Y49)n3?7@fBs?~8NqB7HlJMBXCE>A& zOTuFlmlSwx;*tW7Ooj>Ps&L++# z8R39`4<9wtC^*xM^XG+xGW7lIFBZx5|}OUs>(IZgMU9WXUDSK%20E zr6>Fn=uiGLl&FD>%8zXo|`H|GQ_&hnQTCPMCSkC(ba~;V?P=~J-jBB|~ zjdsu`%MuJ(tb<_az`6;BZmhFl=*)c)jJ_aeLpw=x@}>uCWc1g{8IfBN>LC9^z68vF zN9Cl*uTW_6RKX^jbta9YSL4D-HK|4p~q?TNKFLhAY((|aC*MCn2w3b|0`VN`U38h9R0izwuZjdYG zkjdW(=4!}=1w*Fg7ccOa|E>(5t0v#qXdiYx8GWoX>JdBNKgoSWPtv46Ko0v>aCUHZ z_-8oa<~YntR*ZFX91krw$DO)4&d$Lzf_dD_dSGRff(rsXh4B|1{Wa=`4J)W;t{f(H zmfiAz8Z_xf!9&m4q$<4EM)2TQ&Z7%A)e?MD*<_mhh5t<2MXj1si%bV)P9IaE8>PqJ z5Pa3weW-PKvf!&f9ZDr;`_EGyydZ^&*P144*K3+YY2$sb&h;a68jZaK`r$8)9&S)U zuKkI1tj0Q_bOr0!oOJ>o%{t!4Isq4C9jCEQz+b#yi)yk?!2MarDC-2QSVv-=fInj$ z>#jb>5_O!^8jSE%;hCb~q%=Yq73j49W1jBx8FTt=M+e@Pk z?8o*J4EwRY1jBx8FTt=M+einb73`n`g*xL!5EFTYijRNI1rH;!pR<$n5E`ZD>KZj|q% z*92d5XI~nf=J$6y_cxxUl9a#KD1{14n=CoV*DYZ`Umu^F8OOf8{ra#s+gJ2~z1hBk zVQ;ptVAz}OD;V}>`wE7=*}j5dZ?>=K3461B1;gHKU%{|9+gC8`&GwbPz}{@%vhXAN z#P$vNpxM4sANFSZ3WmMezJg(Iwy)>_d$WB7!`^IP!LT>mS1|0&_7x0!vwa1_-fUmN zus7RRFzn6t<>#V&-7zZ~#{-S=56tmEWBdbiJkS{bz#I=W#y>E}1C8+y%<({D`~!15&=~)~91ryBx7x@v z$>4yMdmfe3aaE1_CPx#Dywl1(Pw0N-){gt;Sh*+G8`387LdbwD{zFbJ74=ki7063!0J4yPLj z_#Mj=^Xdntw3hLjK}=j<=HdE#s?olp{ypsuZ?~iu3+I<|b!~6jp8TQgmp{CHI9)aF zPQg!oI+i+r=E;5aq_R=!R$z|YU;X^)5p?w}x5#~}QcvATUr%^nF!W-bL^qa0kOvO2 z9D+PxmZKmKnB^$Q17pRuJ`4A z%Q@PN(NDi~xd;1q{A7UsVf`Y(_wVYW_qIPGxW(3ny5EpXH0lhzxvW0C_A?K`)h;AJ;=_jbJjH)Mf2+yk)q+98rOvJm zThyHkdJF!K_dVg?@_-SCAP*RE2=agthae9aaR~B& z5r-fT*tW?T)~{pv@mS>v|JpWToT$(7fjB;h-8eoF#|Ob2ABf|F_>SWPaeNTW@qsu# z216KaeNTW@qsu#2)j493MQ64}#D1KH@$%?8tvO2lAKLuZsU>Y+b`` ziXBb+CxVZ9w#91asPZ4{-NEmz#$TGw2)6o&c7pyM69;Yk|N3$q{?FJU;461HV|=%` z;jR^9{M+p2>&wqJ&bH1ao|JQL)_Y@)I$va+OGJE<7=>76olE?m&zJJEjVJwlsr76l z&Rfcy4O?30{V+CUd?2n{=L7%ebBX*sBcIjveP?6m#|FY5*x2F^Y%k@ozr{EB%fqmR zzfQ3qMIXq)aPnsn1?XWLar&7IndM>Y}!Fv@-76(12%F6^Z!C0!A4KPMt{K^qsu@Z zt~LD)>L=DL{1xmY<;HG;jXeeP_Zsrh4(tJWz_1hK0mFX&-1=wi{P^$jqwVVxz~G0R zi|2oii%~BaYZ<|Yn?al4U`8=4Are`Gy*0&5SEYwF9KoDmF8V{H5X z{xx>%kiWK(Z_A9^)YW&kI>R{-#6<3A-sHbu?yDy_ z_w%`Q^X=^fzc>DE?@M*F;K%lk@!};%3SNF+dc0xCKaUjcydbhFzmLC(k5!BI`)8AC zf4p8z*?*JNzrICoT0O#VbIFQIG(E2`t3kIbsZ~m0sgtW?5Bjz8H=X<6kY!5>#DMH{H0;6dYlQy<*aRdCZn3sm{9{dcJRa9x}+yod~zdc!6aPxOM z>)-CkEO_O{0s56f&x@Y5o*JV+xv!q!WA*(^?XTUh3}Ve=MB)b5PhhrNBA#%3AdU}W zPmT}7@j)=h2jci3nBxO+d=Ou7d?1bwf;m1A#|Ob29~8$2!5kkH#|Ob2A0iwd1ao|d zb9@lY@xkNxAeiHW$MHch#|O>vK`_S$&GA7n#|O>vK`_S$&GA8WY*K&N&93MOrA2i1Y!5kkn#|LfVgXZ`knB#-y_#l|$gU9hfFvkav zf;pbodK7hQDLY~Vmf zP!1Wus1F&yXa_QY(Y`OEhLqtul%uYHO%2HOAOq#l-~Yabe(2ZcbFA`+RbN@{D64&C z$t6o4vh<`t25h#mc;0j)59L9BQ9rN)+7Zk$$+8=eh_1$_jgF6${6Z9shCRh_CCQwnl?@J-uQ;k~tHI@;ETcxxQf3=QgFC@#X4=_&dR<%ijq`U6vsj zeX3FV4#C$K@9yzOFqd&V34N4RuB`gXYDZb^M=ZG!%WmqE&yR?nJ+sVG>pq$;xcQR# z>W=OkmZL9w9)AWn9AK^!0Y)9ZRxqv&>;{fm_Ka9|j#&0rmS2?RFJ<}hs5b5P{|fuQ zlQX1rJbdL7vpw{s%)p(IDOJV`zOiTrWtZPSk)(XmvhL-wU!QcoujU``eMuS>}xHXc$UtdeXV8NV_s|d z_n6mO+=$z9?Q3mWc73~!U5+tx>h3%KojsGpx(e&7V2zbg9IUrc{{*q0SN=LAJDe?M*GMkfg#hZi}AmI`8#x|#4_Ys$V41P8Dv`R z;QW2ie&Sr3DU)*4we-aKd(jzfKNfDz=i>2~hVr1ls4v*a)Tn`WEW0Jn{iCn^oz&rK zfBCzCXzP`?2Iw9w{5{k;)$8k&{bl5O8`o>7q&#!AbG)}F)DWDn-0fb))@20Gss5^$ zCv$$mJ-Q$8@IgB$!*{@_i)(<<2HFBf+t33TGPzs@Dd>T^4S(GIsS813_iP#-e+ zJHe32*9eA8mLV82S%zT9w91uLUs>%at9@n3B}*T&^dw7v`h3^LWlX_e8_2z@jCfCZ2_Zg*bW#nxm*S1TwgHib32034!2LJgZB9&7&7@g z!H~(<2!>3SAs8}QhF_m$TII^BudH^I)jnBr$(}zwlS!U*P4-Yx;5co6*X~H;gDG<%`>Yt!(`6 zH5(1EZ(kL%@mpK75X!rk&O zW6Kwwjj=Ao{Di+?y@>UcSr=l>_K&Sa`F+GOU(%^tizdz4fcGH~8X9{XW+Gs%hl^i~l<8Y~na@ zrg9*-=Z^ka_vKH@d5LotG!B{j?1?iCxVLYeL*RSx|Ll2*JJmyHRyocd1od$yA!tWg z?JG-e#M0-ea}?Hj4`uaBmCbxf&|j3xc?q1wu+EblbUhJ(3fdJSihsawAj!1o7WlM`sFT;olR*8tXgO z8P}a4{@u2A&S>Y7c8+Q1o>ndonStD+a#$;um+zq`@=-e%=J`pX)W{@Y$h7twkIJ=8 zKT++pI6DDF{6BYg0{4b+KiN8y;Lc94P2Aau#F>hda&`ja&z+t4XU-=5m(NbP^Ai8Q z^Agtm_hX)gua2ow?J>_GSUMc@jDgjcqxS7j_S(#y zCGgkJ)|wXgk7Uh?b*Qxl{>yW%_W1!DV~%oubY}^`gQM@s{houla^E^9W{2PH=f>B+ zVSM@ivSTB#_1G*p8((wqvP{{}4;< z7@LTt=9xVWzPY&S#vRs!ZoP_iy~{_;d?fh~@QLOlb}Y5A9ZPL&$5I>HvDC(PEVZ#6 zOKoh&QXAW`)W&u!wXut<^1Qd?yKWyq)@g1Zz^zwL*}Q4TQXAW`)W&u!wXq#bZEVL< z8{4te#&#^Vu^mfoY{ya?ySVD&>gl}ymXSSGyN*3J-9FFhzt3a)%f@yrwXq#bZEVL< z8{4te#&#^Vu^mfoY{ya?+p*NfF0Q(`>f)-~U&Z}B%tOfKPvt(39ZPL&$5I>HvDC(P zEVZ#6OKoh&QXAW`)W&u!wXq#bZS3Oe$&ITuQ-kNQh$Bv(NjJ4yZUB`}}b{#vG z+I6_xzE_pFhsAXg_xx`KS9?tV80yzg>rQPTcpm>u?_v_x{x1J7gyarfP3Cbe(TFUZ)NWL7(Ph+ zG|v|Zc5zjH%Pn{wkT9p%vDC&cuDZDD;;M_Q?m1=uc^P-#%6~@H-M2cq=K)h#`#sZzv}i^&ALVQ@bR3ZJBRc4;%Y|DR@rq;-LpzKh^x6GD_)xPf5)m-zn$^Y_H|6wKEVU+=-b+#Yeeg7Mq(V^bHhyhOPIHuVLY zcF36P3Q%A!2G9!cF+&VLm~PHdBFU= z=6?jk9*~D}*a`B0VZWZQC6@s*rx z`lVQgV8~<{f+3S-2!>494)q}uwgZMt*bW#nVLM>RgzbPK6Sf0}OxO+>GGRMl$b{{H zA=CEPv9Mj=ZpUulmTT){>uKw6_sj0DZ3o*vw%u%d+IF_>Z~Mjem+eQ}zqa3PKG;05 z`D63S=9|q!o1fqiYz|w3Tfnd-I0p<{f{VbgB{&KUTY|g5uq8MR3|oThz_6w99l@5y zUj$nke-UhH{6(;(@t1JZ_)9oz{3TpA{t}KGe+l=Ezhq1pf5})e{*p0d{3T<{_={jm z<1d0OjlT%CH2xyk()f#DOXDx}OJs0=(Jzq!3|kt1p%0muyE17s@W zFUVBJUyvCw{({WFUyvF23o-+LL1y4D$PE02eg*zQzXE@uUq|`N_MMH5f2F?hyR>8Y zAnhBTh+M-T(Z}#g^fY`E{q26){k81?AHar?3Eu!irfpC7GO)94e>0B6FJ^p+zidC+ z{+WdsAp(kY8e71QGpP>$9+T+3=FZMXH$Cs^h>ta(pw6kMu zi0ZFtB6!SK6{-5NIN~kcGOQYH{-SjlxZ!WrY0mcVFuzc?(aCiCq3&YO(!XAM6rX2i z^4olFT!?P&S3}x-MpdReYV?#gOAW71-z~aX+L_R|I_1w(M%wW%sX~kArV4I-Z#k;- zZ12eE9_NDGTH*Hk*Y1_+ z*=rAl+NIRhyDw@^zufj|Xj<|`ddS1qQ`Y^x0!` zW01)*)Z;zZ#UPVqsO4XM6@yHc5xFjwc{XISj5zmeHe|94kNY(nGFgVl{hAG#EJJg@ zWs+{fa>*%h24f7-X^x&Hai&Cd<&=uNY*)cHFNRWWsjbuUU`@+i|~2 zK_+a+{R%-QY{&fyK_+a+{R%-QY{&fyK_+a+{R%-QY{&g74VkvTY;4!DueIB>W!XB| zy4gD0eX;v!_uaOMZ7bV`wry>j+rF@UWc$wcsqJf<12#8o&e&YCIc9Uu<|KF%a20$C zI1HWz+y?&w&V!f1SO8yxF#;Y3V+Z^W#+2`4RmRU!o4? zO*5aOU%@^o3}QfZJyiwhYZMqEzO)OT>cE!v7(Cd! zyDIo`uF~UQ9;Gkn_NvNsd#=*SIr{0Zx}QS}+hi~O$gYn1i<`<)?>?DI4_kMc-nOM7 zEy=nkbYRFOy4J2Pl={xvQ0Z%qco%;%fU=)6Kh$W$BJYdVW9X`>w}u97yxd#-Wt74- zDu;H?cz^krajCR=*W6N-lk%v~YYwGqpPoB&?WAeyfV!Rz?OHvn^0v=aa_$y1@K%a> zdkWH|a5CLpVSH@jiduB#q`Y+S-G#ABr?jR^H*Qh$=e!%MyP!8MczC?(vTR>0WzcY% z-*kHj8V6 zV6PwSb%nj&u-75BkJgng8Nwdo1Ff^ocKBamhZy#j*%RZC6wQkSl4Dwt;4rKDRzrAnF`+m|s@B3-q_Y=(fewz3FWUr6+{WS0U$sQo@ z`)S_yL+(So@27d+PcZNM1-YB-`Sbpyw8Q(8n)fFK^Zumf{Yhz)_a`;)PcBD0yg#XV ze^T1#{YlOHlhP*dPaf6g{9zlUeD3Ug`ko6jYg}9E?ccnDl?w>=@~rc6KU_+1kF3+Z z)IM_0i+-7Uwby=pvXoEVybt&C1S2;zIi~D?V7~xuS~;fVfA(Ik$uVVr#cqfFE7!7r zBkW(n>|e$H70mus>|ep`U&a0v%>GsEU+EY7H^?{PU+iT|9qa*^yjAu9?0spIx5^%X z$y*6|EB0>C7wiwP-2}7Ui0wwkZi?+DnC+(6Zi3lvitQ$t?WWjng4u4^^AU_Z-t0NR zZX(av?WjF`v*&>Qr=#wD{8Q^adk^hYVmseImDtXeP9?T;y;F(pT=i69dyn^2;ytUU zMSg4)C7f?*c%YH`uGkpCWw%UMCASU{+^E$DYC^Uf1+V!g2i=jigW&k58;n+u-P_hY?5um z)o-<#4L#78adp>)`+w!zHe31Tk@x~1+jZ=6yZ*}Ri{`GZo;(q4b=uV3>$K^USuGZg zq5*|J@&**{68miT4ODke30-&36R}4xZcIZC)zU)_Esm|pluU0AXrfJ>SfuF#C9xyE*<}|m(e!*%jm{f^YHn4Q#Rs{j=kQeyl$RSmOpc2J>r+?+p?U+pW9+Te$z=; zU;m<4eSMACk(LAWs-{LC=lnq>-$Hfw9f?;z5~b=# zj)XdndUDx;#$)L~xE{<2@&-0;Zvzqk$mlyG8TIk99uA)*M ze^RA74iDYb=Q>JCeMu#y)(q{cJb>2Cx>>E8wWrk8RYuX&5_=+3OWa)Qn$}~PPYdT} z%2Y-8U~_}{p_yv4!6}?!>s;he4CmW$hHcTLZ(}(3hO=p#pZ|z+-Ar-@FtzaOF`Sdb znX6?JVli`mj@wC#aa}nB*q~_T7|z?_4BLC}JU7cfhxfYAj&-dXO(&Wh)^ugb(HO~;{16$R3xbh-T0~Ej~7}vxjcQf;u`*Z5UO7- zJ9WLSFMsxi3VidL+VRjR+VRjYp*y$rRG&?a(q~hTgi6fs71`T!EbZ-iI5e~Q?)ZYk z!)U?bA45Ij6TIECZ=l_?KMQ3^+U`wT)sm*IdMC85l)v8DpY_EMuMaf;KdmeEP>8?R zTu)_5>KfwfG+(cJ#B+zZJVRMePI7UPxvL^zh>Lb=ChmkK&FlPTJz`p7{n9H&djOP%a4J#z|ZKB zrYd^mtx|MgG~L$zb#+_&2BE$E`qI+0Jp7p$TKQC4S~smGe_jgR)wde;N@~NOjiEaF zeCl)A_59ftO4;Y8s5b|Z8dxhy|Z+b{oxKjW6_SfpyxBG>D zda;MDboC5X>FQ#khldW)*S?caUHi_1rJiV&syF2QeEEjFy=Q*CJE{x5(b_Bc#=El? z+&)@&DzMV)RG?w3R-?YU>?23KvX4Y#H8*t8ZHpD*&!e$SJDcg-udK$O=VP^(*3`r9 zYr>yZu~r3(>vKDG;?IY%h6m5m$-myrpFOdCRn~Z~&l;{@pY>DhyvlcbNw1~qq}P6n zy;3Nf_wM1Se)sT^*tEM|UsmXrvAWPLhht^V|0weFl2Q8SCBMYdTXa|Ve=tbj|G{^$ z;ycq-m5RM}m5QIop8NJgwKdnZdTXw&vHMG$Lp#?r(>vF!j$IorLRr_=(OK6niM?E; z3bjlrqg$q=$9|h$pBlw->qfB&vCXO-UDSQMcTxAQv3XN&pw|x0^j&)m5|RTy<5cd%-a)h8#7wG7p28gBTmc zBE;SxMxD^unUMR+q>~*3UwFRr96qBjF)-zxvMS}Cxuq)JnxeDN9F>KVLitM$*4I6| zUtRa?kWkgq-F41LQOX&4EL8ODX1ez^Vd{O&@=%)|7420vmX3R zNjlaDP@emB(x1)opC^Gd=Q~&d@e}bB82{q`f%y+y5^OjY_z2t+?0o0OoryQX2gD(8 z1>`||LYxA|Saahp@tmF5%8k3@KilZ$yMN|cR5$Ma{o{`J_O-RQpTO~3hU-r*880z* z-ZwYsS>JCHeC5cNdg(*?CC+qxvzqR9Sxv#!Ue2p`jBYKs$&5|j(7rbcp5F5|uWP>% zf;)V_FupHGG{BJna~&1b;cHcJEw@QQn=Fe0S*!yEI#Ywb2| zS+)+gZnn7a%*^7~5!SO2vk-Fuaf z`!sAsPkdWa$`^EMM4jLF@y|^gQJ$}Stj}&l!<1h?eOyDjdaIA8ywZRwukzc!@0ly8 z`gy+GDg!R3{dXiun+wmYPd^v+^?YTuqNIi8r94}gFkRJ!pC9GFZtv8g;)SXR-c+F$ z-MlGT@bf9vY2Cg2oFo6;{&rQ$S+Ta@yvdcR!@RnJE5BTUM*k2NTx(Z(D)y)n{Nw%Q zsL5L-IM39wRAlyLf@f?mLvJ>!FSzKaGPGibj|W~`h8i#NaqSUh=!PeJ+-FT08q&eX zSGF!o7kuislQmm8dh-e&zqGR)?MU-w)%m16t()QN(EY%rbn&c+$a?awid3|QuV%m*Ftp;Y~dzVv#Z19O{Qp*xTB zZGQ0cCVJW2V!o`y&2{SGf`ZFUZ>5|3a)IC_ueZ_FH=if?rR&@2s(o?`zPng^UAt8- z!FQ}~udi>KQ}FIfI%w~e9D=Jh?4WPE$KZM$bk6BMu6=d~{qjB^-xzDJFTUNs_KhO# z^_Ok@HmeM6r{8Pi%SyVbt^Q$W9%(a{tBrnr*ZG169c-y{Zp$aQR?ilC?J!^e>{FWQ zkJ5@rdC9LD>aV-{+$;0{*!vDJD~hG<8Pbwja$eFVa?X3E$*^R}L2{IwQKCda1O-U~ z3K9hcR1^gFbSpVXMocJTLPZckf&%)#RWoxeuX3;ciueEi@9gtT%{zU1x~i+ItE*;q zW-t!rTex<$b!K&Qv}P%;)9E`rLy*(e+n!Qo%ojVVa`}xe#Z0Fx?ij^CA8X>9*W&W( z*^8JIt?M#w7*o*1Y_HEa%kcar#RrLu6SL+uy*D><%k$cYNT>j3g9A@2ZxBN^Xr>XLoi!)WrWmcSU+u1uWxB2FHW3K;9Ag_se z+~t*`WPY#GWx%Twwx9`IGP>3gI$;|KS|o0j8Un~a=U!b~pU z+TP$cWzEJFu8qBzzk-Rp;La(Et7&f0U-A9p)rv`}9Kw@|jaK#BPGj7;&Hz<8YR_-5 ztRv5rZLX>jWs+A*WF8XNXrT42^#i&5^3t#MSC95!yuVLcQ~ZASe)k`&gl!;f17RBo+ra;B z8<79EEb&@ZI&f!~`%EHm(8s8w#s55q@ZIWPAJ@nXYn_*`y-R#9WjoWXa~du`^Fw#j z@sRsWDDK}GasMua|4sehz2Ap6mER`LRX#7spoBaje7E{{lLz+`jepM(_Y;kOFOqT$ z@jpoBVu{iCe_y^|8LA`Cl{%4l--ObpTDNMfpXW|wH2X)iVq9zUDV_JDzKkEpFkPR` zJeqO#?ni?~Hq*0!mR0o1_`tO)+ftmIB7*T(}G=W3TqJ@<9{-(Xos zo-5mwyrc|LHYv00%iZh;|7Whn|IBOgKl4WX&%6=;GjGKI%p37P^G5v7yb=F1Z^Zx1 zhcNzUK2!()Gaot^|1%$I6aOl%tBiomJr94tjd0&3~$Ej4?h3*_#I-{7%b;)7b`lU`(&rXbDynlE% zmFcl7{Qm}PGYnVBcdcM-nv7S=t7T&>pV5%*%W_#?wjMPc6*1zN{%VmApj%;7@CH}rV&`C&6DL;*&-!If5og3`wFO0)_2;0Ct zvH`rCCFsB3W^n5|x=@X=>>oCqU9Jn3cVm@KSw7M$HuUE5Qt8*>kP&NAlULm(1$ElG=Ls?6<*mOLxA$ ztNH|WW94#~9RQtJC^}gC4CKbxkO;y~S)s#GtA(-w$ zb2VpvG4tfclEL=#9o2raVoqr6UUkL&nE?EUC!+Mi~d9J7y6(6|M?F;GhXE?x-(e)(|v(SH7BTM zU+xKZ?m8_{e)$9yHS$1k(y){Pj779R7Hf-L3l#Zj@9UG|CaA7M1~|)_)k&%q`H)Jz zb&HeRTAFlx{b1Gi^D9o^)|sSLHM*(kFXvI`>*ox<^+qGre{X_%_Uneh#=}df)HT|w zF;gZ4Bi5%;3-%6F%kn=RJhp7R^GK!#RnLPj2G8am=v+89bM-5aj9f)F(CVeht1E7M zoAH5{2CuHzFgxB$^RVh%vgPXT4_0T~d`+3vyPDn4xO?_AtH1ns6yu15*H=YWoW^+I z<-n?mrDie4dY%^Xl3!lLFGu|%etonP?YD#Wqy6^5H`?b5d7^!JAZN5MC*+UzDW)+fd;3zGil+!=1Z*giv(-QMgzz+@XeRg*ox zwCvm9vY~G$(b(CKb}{K^jL~HC&E9TiKDgLd(^!0Zrm`6o*_3(Z3uHIlYQ-_HBVT>3 zcdSaTNw(&VH|l0pcQUW}x{Nt8`3bInV`L^%YjHoWKkfKAy<}w-uD^BRTAia}YE810 znBUXXc|ojUs}g4J zTdSGZCr8tnle?xduku;X=)rSZFt4;7R_cDO@-naESqq!gpC91*iF1;h8)sK>{p#6{ z>JvXa%=NeITC6KKa=8AKwoT3ONW8BRdi$pHvEYGylUTM!U)48pV>24k;mLFXqmxn@ z(%Z~krOn(&e`MM2jL&O|t@)67z1#n`zIuKO^J=+auRgwLHuDP3nWs;D*_?UxK9tck zdE^e)|Mtjvo%+CGu3u*8R-NMdvt0k;!s+_@wLx5e=KO8JbvIYCJWqUA*5vJ3f#v+N zR|)gY?ouq96H&y}tsBF#U7DBEtavWBp)p;OGnFylMi{c6-kaXjXI?nNyiT`xUT4{~ zk$ENV9jD_8KFquhe|kyJznP8eJLlij``-SJ>nB^bSodnJx&EP|-E_?d9^?Ak9)Bv> zZkl1)dRLD$@3d;pvTaF9XUyqDmTh!&3Nz{>hh@8e+cn)|WLcK2f7kc);XC=5*XaXAbiFxS{AJwnS-_N{0{G_p-c=Ji-RiMXq-RIj_uK&S93-#uS5r*bM&ocvbp2WAg ze!-+t`c&Jex&Ep)gMzO-eVSz(Jn)pxnxQw#w*JUrz2#hImMwnyPQ7w>3zlu+l~?qd zYqeRn+gVrW!yQX9uhW+%>Hb^OGq1$yjdivOA2P4{=W=M>YZdd_SaH0LiK)Q#_fK!4 z7gx!`_0PUpNFOQs1=o*Qe<@h&(0Z<4W_RIW$EVJ-Y&FwQ*89I0!Lkj$Gge=$GmvHL z(rA$0)TJxSR)2OU{ln7cEZfnaYwJ~yRbgINa}?0K4rOOvUHbnR>~Qb`^LjPuwcw5K zHZre>!Iqv_HG%7&oNz2SY+o*}pE1|!;IMI*x&D&8!-Bi|zQpzOM6F30cl$e*?Q)UL z!C^zjv21HLtq+cvH-cr`Gjc`nsrr3bwzZ`f1UE*sW!X;tI3>8dn!~)N)@T#V)He_F z`f_=Euv+@7%WFz7@aHLfh!Q>oF9Zzv5G8zwBYcP>e261_ zh$DQ6j>ZL2;b}Yz8C9) z66=B^)&)nb3yxS90{*&y^-KBd7uGB#)+{B~EG5<~CDtrQtXYm&vmAfT!g{L2daA^F z>WKB!@z+zVp#gsl#k#NjbsuZJ5^KE@YrPU{y%KA^5^Fu)s~KAB9e=Gy9HK-VqC_0x zh&aUY;}FCi0YCOYyre|Dr2KdZF_IE7k`ghJ5;2kzF_I%8TvGa^Sb zB1bbKM>8TvGa^SbB1h9AN7Eul(=tcP`c1u}`al7GpHA29P1o#;sS-_c{*Fj@D<~VnoK( zW>0g*XPcbJ;9V0mD3A8bQ9s(Rk9MN{cF=x|-#+-p_VE4^()*{|nXRi&I>%4!NXnf00dsWue5c}}F-cjkj4&Cqmv)|Smno@#m2sxfw=V`_ zZq0eUEuMjw&!>yrFeq}ypnUFIJ`XOR6PM4A%je4F^XBq7boqR`d~RJn&n};HN1OlG z&)|1o6Jc)MDiI|8)b1Z^+Er`CdK3AY>DITE$u{H>x^7_RMHSb52jvQqt{RVfRkzsi zY!KHX%Oxcy+a67}kFKix*&#X!RB9Ai@ZZ|Va>sHm&&Y{KK&7$`bDc{j=JTuq~ z9p0MqAbq{%XcK?m{gf-|DQ^}uhl^FO#QwWwAxG09%u z%ra+B=wZ?w+RidJoz>6Sdko8*en}29Eyokwj>z3i*(x>6`{%cDJ0jQ9A_vqWPt;eA zWYf=e+Rie+aN=p*VsRaoxo@)b`hjzgv&?N?&0wZYdy#pGyw9}ysDf$LaJHKOx1&LayufYGwG(4H0#^m;C4g~s6}q5 zMgFMQ=Si-2@A;BtemmVP{q)&UEc4{)hxEXWudvKZUj9KZ*zh6q68WH6(7u4lI4Xl7 z+t|0Xq5653dQy}r_F`R@`DjM1uhvS#?T8%ERGoiCcPv|) z+YvdV7P+JrIi}uLaYOL6I=NZqw$m!;r)RHZnUCh5sz1GSk!5}*$4b5O`^?NsI$u*`jvU)Ntx@5C~nx;9I9MP5yP7rCK{TlKPz z9$Ayy5xJxmIi?o5r#?BRZ*WPk7?!#46W4)1bYz(q>{+SXE$zcH-?X38^D+)*nQwF|u1j<*#O;Wj(G=X? zK^M5vgxe80rWU!U7CEV&b^1cmien{M=1T>}1lKm$#xl>#xGgxUNGg{3!h(;32j@mJ zFOhGWTP-r_$n-6kSJv2kdfq!dS>~w)V)Wxb4P}|@3@)Zy?t6%3ZgZe_a88R@Zb#&j zCZfTU!FL+qx-I5~$UU{lNwvsTb*1c^)^2H5nq~fCMU{1fFKuU;`xba)-IT1US?167 zu36XRipwivX>gsFhnfWoPp&(etu^!NG3|?WZ^!gynX~V?x^C3?ku39r%Wkbp-ebHk zb3n-K=a?jOK*;Rpq$IPStCGxq4oiAY5PA*>JqLuI147S!eoA_Fgq|ItXGiGS@%0Sb zaD;96xhL6%BW%OZRmnE|9F}au&uz(`1HzsI!k!&r&yKKXKW`;_c7#1U!k!&r&yH`; zn1ha(gMLm*bI=iU(9dCM4*Iz*%|SosCBG36e!~%d!x4VN5q`tZXUT6k!f!ajZ#cql zIKJP2uXBX2^K(`5b&l|Ler`*?&d+(t*ZH|H`R9P}&yMiVj_}Wp@XvmpOa562|Ez?6 zR>D6k-#=qbam1S9=diS03OY5K# z>!1?rpc3n#^4CGE-Ab(8er`)^w-Rf&p9|C4?dQm}cKf+A#T$-@HyjafI3nIqBHr-x zVv0AEh&PmoHl_i+ zDG}HC`7*_IO2lnXXhaUKd%O{$jyBKX#{9qJ z>AKfrv1)Cqo` zb3@$kEA2n4gZ(~mzu(li!nK4R`^s>g`A70Pja$VrZj=8}XYHX}jI$Kl=}dSgCFA|h z_YU#k?;kywNf8gi;HiiQVenMMgD`k1;z1ZZ74aYpo{D%722Vvi2!p309)!VDp} z2Vv4B@gPjPBp!rGm&AiG>5_O5CS4K_!lX;$L6~$Y$Lnrb)|c(b_9b5_kCao&FZ(6? zEA=4tBlRZrDfKM%FULiWmmEhqzH;29JxDu|_Je+f>`L03v_om1q-)YS@uV>zOgw39 z2op~lGs47^#*#4cq%kH;JZbC+6Hl@U!o<@XJ3~CZ@iN5I8!tmVz40={(;F{CJiYNU z#M2uuLp;6lGQ`sxFGD=N@nYNY#*1yr8!zVRjTiIu#*2A+HPj9@aU#vSSC!XGTQNLJsR8Bm-@uGgw+@^U!{o=VnSd16- z%O5Z5mp@+AFMqtKU;cPezx?r{e);1?{rc5-$+45z8(*&PjXSsF*#o!l*$MOY?1$y? z?26^|?2YC3?2!8<`z!U}*)!`$>dmu%)~D37H(yx)-aO)Qk>e%DQI4-1cWDpOPNe-v zyOQ=M?NHjMv|DM<=ok4B{Z-T$=n_}6zFDxaI$R%Pr{j7KMBQAc)cWc=~5DE0E^4b9P^ zjaHw^lh0)Qrn?y(xpB3!F6tH;Mwky`zFpmR(Gu!EBwi5fTtoJZ@yP|4R|WzG5>h^HQ=d;$4f2ptpQI(JkDgb)_|uX9&^u`)!?a! z$L`s~SA(Y_9v^&aR)MD?9;cgkC<30;FNJ(Wq|HcMk~Su7Pue8u*SA&DyKloZ z9=>hUIQceD8drag(0KcEhwQ+gQ*yk#`A+M}|F^NCw>I(m>8(w?u6k<|ueaXX z#OtuPHu3uGtxddcdutP~=ib`HF_O17Q4H*_(f>$nFUL+|&u>#);Kv>mOZ%}0#n^uA z!8wJuR#Hsv#~u```>_Yb@W1Mp?61^=)Q{Ag)Th+5)V~}TIbP@&$Bo3(Tgy1!@zyx% z7sU+}3sJu)o?uKoy|t41Me#={2l3Wc>KDZ;v<7j`LUVvH@$}Yc8sA^#KBPOULp;5; zo^+{6cT`S1y>*s!86e$JIq~$?S<(q~F6>&SCuo06B5LCPj&mVJ?Zlzo>vk-CyPl)9BVmt!HvNRHkA zuj`#0JGmyxwNkF3a&47su3U@d8ZFmuxu(mtUd8}2Hjpucj3s1@A!83YM#B^1*U^{@e1Rx9>O;8&)7iNPlnfsunpWJ8}M={zJ9y&$z+t{n9ji; zovh1pFdqKyen;(%Vf;z|xz6UQr5P{TQPIhkjjy+xTO*$gEV}99)CZN8((J1rhfXKD}M!T46OyuWJm z^&%y?{Mp^5O`7G^=-!7}x4MEk*>*W!N1b<}yjhmHrbFdbMwc=-V&^liR6NFXsg%Tc z@ya~Ex_2P2waRO-^4hGtW-G7ddU+*{wZT{`Z>%-OnlZ*&W2_lttTo1(F~(YBtQljh zgBWYZ7;73A#>C&tRp~mppR3aKbN~Jw>&DAfIY0JtRnCv)wOr_p`wqP+=#6y+y(#F8 zbqKvF=uLZiQ_ve@=uJUyjG?z*-J5{kxJ}~kU1#{i_c;Epcu(ei|0I@q;y;OHuJli0 znd|+NSmvt#B$n4D{z>e;<0XNfPxs#Oq6vHNcwy|l%E?yGud6ZaiT zkLxItbh?2e-9A`EnSG6mF@E%o_U682sTjY$Z=mV0CCKj<_~Gd>X8R}28Gm|qqDfoH z;`a>f>N(zgXfpG7Nqi4^Ng0A9zb6~Z;K|I`>kI4F>my^Y?~FY;e}lcg{H?t1#XExJ zJBTE{7rf;An&f+yn&f+&RPaBHF*gesb6LUv@La|mSMWcK;eQnT56^wfQw9IS^Hkz{$V5( z82*R)&e)UlH`wdT-^$AyUqkYEHo(}k4aT0$F!pSTv1en9J=uD&vOB;(y?d9Y=biHwVXoXSbP zXFTIt?>_H55bO5kUbN}0^@{9Y;z{RXOuyT;xV+t04NdkO`52#1*2ffDdB&mobH01f z)Y?6WaqSBe&4ElucpL{lJJ!tXp1|Yfz2EgW`0r}plbLlTv3#$rCy$gfNyyK#dHrJS z^_Sc9k=e z!`?Lf4`bMghW}xFFWSVM4aGkaW8NwFA4BsL^HIV7FvdJp@ITs{zY6|`G5n8$|KV}O zd{^*4JYJZyzx)2`zpH&uX4a3y9$%KtlSj(QeiHtZedCK@+w0SrEc<)qadAxV0vkcM(B>oTe*{;0$jPLe7b~(o-zFYmf`M0~h zuO9V7@3fcrZuKF;f$)jk!kl2%%%RSi`LqDPSV@v#R z>W8jBc)Io5{N3-2dt>Cw6S_9yjS-i7W5HPFyb`0o3i@H4c$jtN)!{iV@!jg*O&%Ew z{ax3E?nRq-i+|);{9V_D?nRq&j3kz^kaumwkPZKp>q7UiO}14T|9E|2|LI+uV*C6n z*M;syo8FkRZY7qn(BE}k=w7rbV;+gUdCmR$yRHk}qc(qcy+B_=*Mhuj<7`WR<-XXx zXcJ@lyVrkUOQE&$@47E`FWSVM`rY*ubNO$-FLn>xWIOlTXYBQh*Fo>z9Iuss<-XXx zXww^0MZR5P&#t)KyEn@CuY5b>UbN}WDgXKj%~{6q6*R9|=D+K{*u7}e^O-C&zE!0B z?-}7+MYv|NknIQGDpLOUkMOM`<$o6m-zrl6_mc3fBISQa3EwJm{O>E_TSbol-6b#n zXPx}F_{yA4epg6-Z%BTJNPeG4ez!<|&q#jfNPhpwTkp8P691Djcrl5g`L%3uKDB9T zL&h6NS63BVmtvf=ZEK|`W?&qc{(yRG|8ZVx+K(Nr3j8>kar8SA)Ph%cvJdIiXQJx6 zX%@#bHRB&rqf7K>JCXVIe~YiYCg91&@_RC~{9a#Jey@)#zt?xho=z0$&C?ZQPlt@X zKK=&(lQMXAWk^oX_85CM$=I`1#-0r`_H3K6XY-7`xxm<)BaA(}W&GdbE3YAVzJ=xS zd=6vJ7cusH6l2eKG4^~K+lJ@s7<)dDvFD@y?X|UkK!#8p=zUAhmzlmL$JqOp9AocW za(>_GTXKxOZ^<$Cz9q-l`<5JIdA-G3*SPQhBwu-b3ARVyC}i2Z@BK0Mz5~eE`#vCJ z@4JDFz3&M!_P#U7*!%tt82D$#@HqzlnK68kfq!NUA7$X5 z9jXuCW#FF~!>1YeXZC6Ebq4;KeI0zDfq!P(fL{t--}`Uz^<-d~J=qw0GPC?%Us!&x zk1W5}cgCJh4C%qs6=P3_jJ-bo2LF>Xcs8a;PS5rjdp60~vsK2P4Kwy^o3Ur}jJ>(Q z*qbAaJ-cQ6-{R}}5SGF7EsW*&E9G}B<@YY-cQEDmG39qNJzvB&Z?$J%sfTwt=t> zgl!;f17RBo+d$X`!Zr}Lfv^pPZ6Is|VH*hBK-dPtHt@gN2IMnk|K=J0&^rPCY<)b_ z7kWRy-JbDBo1ymr{Mq{QndrMc1`P8x*w z$`Otz)+89*=wew%mdpB&K2Rr~&ZF-Gbv)h8A=LEcht%M_A2R;p^WLi3*98@oFUwP3 z4ZmHP@gb|6Ix_e^#%U{ORXaBKVEl3Vubu5b4`F=r#TT5GuRp|iPNi;6i3cYzp8fRM zK#}Y2JG8bIn3M2&Y8QW;^ipu>-Z5O~{K+Qz`}V^aSG}@YXK&n#ajzFX)n83)$+$^E zq&Xd-81L?1%rqGn&$xTAhMAHqIpb^Jb~F`^zRG?1x%ptTKe0CBVok=H)!Wzcb4#_a zOf)ag&Znu5bMK5Zn>MUvJTK!g)A-zN#*Z%UY#MiqGgPPjmYOER^tz1Sey^~JXy1|X zlAn^BGjsbh-Z*f-e(BNCj4w}{tn2*bzQd;4rJsWpes;&F{X@^bezX1ruJhEzZvwYI zamW1J*1^sWD+dp-ztV4RZKi@c0C;w)~FF(%m;(W_`XG=&eKYstEzvE`bvrbA*9;cEi z*9Ni`8m78#zRKlgW4ftyf&7O0m_KDh)u&wopIpcTF@Q$`wOfO2pkl3v^ZCbHjUtAgbYT=W`xW}^o3<1nZ2>&zIbED*c&^p z=Zzg>Z|oR*W9PR;W5?JVJI3DFF^11wO+1Jz>08vNvEy?5L}SO8#*KJTeQ!J&dt>Lz zNn_{BuVU98UrY7LUgVg{vBr;zYEV1UHl)qaZ&U|=O4^vTJ>MpuPG}M*%C)GkMLWN; zdBK68GkcyfZFkJMjoR*&$m*CpQ^-o#(?swS8PkhRZXPoU!y1Eai`Ba zowK^{xJ_RB1*hYYQC!~g)+5fm-0ob<7+KEQfM-03>;9QL0}H=%ea@3_J)e+zrHfP6 z=@_hk(Or)UWlW|se=~;bXZ^0B&i97f=A!O1bjCR@uUvE1>u;Mrz;(Lm6Z*{Kof)6` z`L-TivngY}DyKQRt19EJF=fmRotLpwqLKOW$VKk&^;f%_Qq7)Wyl}*D)8SZF#w+d{ zZ;od^&uj6;&nKFkds{dp|Hi3fOvmhd7+0=0z{D^4nQ^7#olL8!e2VH=pEfj88e@mAt9ei@m5vFujMPFnvaWPd}nD*Rd2QXobEeLYn8j(N8GRVi+ZbFw^lMfw`rKF zet#*(H)@Sjuaw)!@oClU6V?0e2ZiiPV)%Tn@2y{qz4eQ+w|=n<-ulJZTfZ24>lb5h z{bKB`UyQx=%g3~S`E_XhVvKWX{bGzZY5ighUbKEOh77cR`Lfaa<;zU#7i07V{_t0^ zho)h_*X!5C5;xY~>-9_e2l>3D#PYd&`8>XSPTzYr){tK0bN%vpfA85?)}4G#Up~Jt zv8*G{m2FC1QU)oTlv(x#eK!XWoaC62^z5%^6esxW8P-$k6ZebOFh4$^Jsnej@kcQw zV>-`|GpId({3eWl5o_qfT!+?KzntO(zdqVgemk^Y`|V>Nic7rpo!g;x-!*PjM&UWn8XY943NO-S(#vWhBo;-{_IT?HMGw!jgTpaPEcD(-j^+Rz9ehS6h zp5C|)^^f?`xn92+lRk(am6M)`A7Rp;oQL7D3y+;YUuYiq^T@M9LlzUBcWz!0o_DSf z5BtpUdKX^r!m-Lf8LQyhz7p5=LpV5TlsZ@VQI2iaf7@HFy5fGTrO|`U)sFeuI2P)> zue|C~qY~rtuVq#rk7>cU!850w5d-=%UfN@d(|O=%#%-^>7`T+y%^`tJ5{@nwU|#+UhS_bg-`d9G|z@{%%0*`&;}FS3ua?@}jHS5k*k zw^HYFECzj0$*d{r=JToRS2GKilxE$IpB*q2B19O4Ai)WckExCq+b2v#+*`w|-jGeEhJ> ztLnL8=I}GF4Bc)PH+fbCnAfv2N}Bu?T{+A2Ds7rQijVb9H{}d;|6Rb5Sm@pPH!gKjmaxbm@Jn z!4Fv&Z{OWgRd^>8n}5-+Ndh`rRVbL2ivHgiRl=BUbwB&Z=_{hwr*QB zWtNAlw^iwuy0}Wpw(7M@F7CU!jmk6CJ$G-uHtMUEZkuIBv{t8Dy1Zf^Xr;dYG$XgU zI(7Tex<$ zb!K&Sw5I$1w@%+xR4sG5dfQW~jQV1Sd+q5)mtv|@7I%!|pO01X&1*5Q>e-8^6s_wr zZWvQg#cZ$7ILq+-D#Zthj1#lwRlPSia?A7PRwIiyVSH?PPSvqaQ^uRO=1`X}x%k46 z9BNacW?cTxsvK(FZMXbPAg8MGn2R%2%cWMFaNF5CFSq*Ucw?^rOdzj{dEDidqGW!x zAag@5pV6{_TG_P$hoyJ(cBTHggN1iL&l=u22{v-GO z|6rZay?)dW;XiWU|BuumUC91~v8$1=9>RL~pJ@X;pV?QsBlvI_vm(NJ2-`#02EsNF zwt=t>gl!;f17RBo+rY1Ez_|J#>i!Rbr=M^+DnWdHOCYm*aot>AR@EkwMBPWtM%BHYV|Z>-%@|8+r2E zdGecj@>_fI8+`KHeDa%pvM=&J_22bvXzzPxtbf_QEcd=6%yqo)2s7T)=Xyf>Puypy z>fOnro3tO#<-uYr^uE~PjHR6NzP$HsU#_!sMlqA?lEb)P>O}MG#3;u5hj%lX9=pPJ zBER1)zw0fZ(U9%Sa#>%tBiomJr94tj`F{w1*SFCjr^2_7`B^X7zAT6QYI(J6z8+Na zT`L$ve&y>2@+)6&kYD-wlyYKx>75e(xHzvp)r~R6%kjqxtA?%n^xOlTPkr>BmtjnO#oEo!?n=J0T-KNE z$o3^)DUXy>$}gY4AesKC9k_MF^}~7y+ra;g4dC4@0ss9rgIm{e3e_0P{$az}&<@x7x_~RLQYw+rhew7j2)Y#vBjuyFBjpfA9aV$qC;WdNvd9rAZL)u?gJe zJvO0oS${|J+0jd8buUc*?%}iF2GT9vS$$Xa3F^k$5zhWWjS@b1;z5;W{dVW^g)0(% zm^MhYpL^BWSNp?+LRq@0ikq{lk_R#b(p_k-=FBgqp4?b6(0;z7+D~@W zGp4jsBQ`u381ZQab?t#ZYWkcf1I3TN!xJ%P?$rv=I{pJ1X!9tcbtmNI~`SnZF+ z+G5v&MSj{_eNx;6)pf`Ky{uWCgj$ggsnlDy=-k%QgyZW6tG=IK(SciM5?0mdrl!A~ z$DFU9Gw{|Mja2`=3Fg_a8wMH=FQHP`XluqynGlFrpGGa%JJ2l4|8(HkvhB_znI1Gf z555>Un|q*h;n>XRR~{KzglwSIOOvB3ZhM>YftLnHS8SL)n#wzuY#H7C!Rm~guPGC~ ztJ(dGyJt@m{pH7_7)K<$UL>;OG{yrj2Z~HAHH$I%1;j0W`6|C0^;h}z(avhW9kjpN zZy$VD`+OnKYF{46x!RW#@~`&gUmn+1jW08k`y0{LQE$FJjP3B}33=4{lyzA@t;<|> z7Dna`kPVmYv&E@+;4{`|uxmASD`l)hcDt=U{_lEcDu?trpx`CvY}6^PU;O#a&WW+h z0;K;rcZRDkw$E_LZf|xUpt6mg>X1FZwCvl!vY~G$(Ae3Jc2VhPjB&{3o4wskeQ>d_ zLu2vjnaXNZWK-sqFOXezs};w*j(qjCvtw0qhh%Hsc%##->Q3f0UzbrwCO^UTZ;Z^O zYAx=^^`{*_=PX%Sh3ju!xYo&0F||Xom6+dC)p+TBmaTBLPXogbR1J_kkB;c1CVYI7 znF}hu5O%N#r3OaJL;VH;bE@7W!GY-awCW9Pifm!4Uf#KNN?YC zJ{CBzZxYMa=&SlFZfr(HIy{*!pmb6yMS7dLtF)T?=#MPho$+~9u{9quuXp?3cCMb^ z!n|5;*y|i$G@E$^=gf0XeA%3N^*)qQHF@L?*Z=m&c_;OO!(6}2(5+62>(6riiwmba z*RKuY`ZMQm3#_}jlI3~gyRs^8&k8K(m%U1;Z+4er*_?I49#J%I3xPlKeufv~Sa^~O6#`T@^Z#w(l z{*LP>TejHg)mn4?Lq)qeH6M74>u-DfsX)7FhGpwrJyN~XsyWNHB`KXUrxRJW(a|Z? zsE-_$?fz}ooE{^~vTXgkzULgilaG1b9`d5|_4_|DFa6=8&MWixGp`RnY3xkA`6Tly z&||yP=i6AW|G`5Goy`*?6wQU6X9hTV65ryI3Eww&wCvc)go>8#w{f@NEH(XeDv#Cp0maYEmPR~h_)=-$seZ#c2{$l*VGzq0-5^eVP0P@j}KH!f0cQiJ$N(W(Z*Yt7y04G zzjNyo9(dcWPk7HYw?5&MH-D+$aqKl;wxEzLC}ax?*@8m0ppY#nWD5$}l6={qH!buQ z6nYB^y#`e=M)56}gu(zPFx1eut zm&wZ(8^_E&Q7n{!I)27WDlae6JC{*9hNhgzq)N_Zs1QweY=K z_+IV%UaSj7tP5JK3tFrTTC58}e_g=(W&HIEYnBmfmJw@~5o?waYnB#kmKJN4_SY<| zr$(%&My#h=tf$&vPqBsu{WTQpzVX+6to25$^+v4qMy&Nlto25$^?0vlXsy@&T8}uy zh&aTEI7Ev$MEh|FVvnF7dmvsiB3?3nyo4CZh#1L;7|Dnj$%q(9ix^4!F%sf8BjPtB z;x{egH|@u7h|_|8oc3YdwquyN1vE{6ac}#;JM{{hsE$NC*QM@+Cil1cOqHF({iQ~8B0~~WGz8lw{{zM*A zbY~^5f3eY3J^gehu0Lb!7X48HA!0g*=gQ>G;9nC&`D(vBapm-wlXF!pwf|N0o|tE*m1SHp?N2c={i7Ja z_+HM~&4*JlK7Dd$Y|@Lv7&jhyDz?bhl8pDK`8YQJynQjO=U?)*VBKWH&8S*y11IM# z)t{~GVmeow8TjnTb^X-~b@6O(hd`m6h0T?xV@=eYMBb}Mwsrm?j*c_x}Dj& z`lLR7Vn;&e)DM`W%jfHghsGpiy)wdN%wAeQ-!4-^|0?55p>JOd#@w1yy=~fwMn0b| za>Jm=8H4hGHXC`8>OP&RstLE}x5+&&$i_=w<%i zeNBYAb*n^x^i#WktZG-S73)ppYo=S@Rw~<&N9ekNnHN>u={qP_fOOS(+^bHD4bKK} zEyBz`kwTSS`3<)-?EAv%vG~jm>0jh=X2R`eYH8i74z+V=ad)-oy+q1)^c&9%Rzruk zraVYrZ#i1U-*-RdN_xth1=ZnV6}TOdqnV#eHc?Z*@5SwioKB0pPm6p|H>+3J$-QYR z%X~J^3(l+C(mNz`)~|0lhi^7(vNV_28S_j>zdux@jfV`nET?9gzcSksE4} zKkD^)k~_Qie91Duoo<%%^x07?^W^D=oPir(VVRe_{DZS#!-vdEY=DS6l3dr3oEM(KNe=0zZf4-1*^of%s0n;?JRiZBDW)QJu_)lcGdmmoZODc z4YkM_wa6uP=GGqsdhJc^kUfukrmr(O(_EH$x3j@1(drb-oZ+Km&K{Lakv)q%(L^>% zsd6~6%&U8q%&K@)MV2}B+}!H+bj311Jt;~Rd$BIdd^DqWuGUJ!?T8%ERGojt=~%Wj zwmJs`Kfki!AdiIaWF=zt7CPME+59CX`Yv)q6SwMR zCwgQ}Zb#&jTI85o#^!V8z0;Fro?0NrdHkoLEOVW~#hjM=9%7l>9OxaG(;}AJ z5xJy^Xz*m{~k}YigFc z&4%yScDds6+W2+4bzUB7h8M}V?qs&s%qv^IV(Z?H>B}--`lS52QR7Fl%r#!9x-NN- z@xIJKA+w)jlFUINv!9ca%zmy)GW$6!={ZU0IVkiT6nYK{J^T47=~)XsYoTW?^sIe7 z!#1?A4L|oJ+t9)`{9Ki6!_Q&KHvHU{>^UgxIVkK|3wzeWp8dR)>{$zY*212(uxIVt zGv=TcbI{L8X%1>J2mKtD=AfV3(j4@2Uh*43;WxDK8(R1cE&PU`&ywHJ!f$BdH?;5@ z+V>mqbz1m3KUXDRr-iTcb6fIte$Gq2&d-I(KL>?>*1|t);h(ke&widu{@DosY=nO{ z!ap0|KVwbNVomXLSXxtzSX2C*m(~GTUxt~SiAjPnAUDTN2ayg&z&jW&?4T@BHqv<-Y_EG@bhAd zH;jlkjEFakh&PNMZy-i8B1ZCaUW$>7h>`ppnPMbAccxfQ`>~wJuQlR2E#f*Y;yNSZ zIzL~gxXy^U&WO0qh`7%9aUEh&BVtiM7p7R$h*;Fmoi*ZQ?Z?T8Oa1(s;!;2F)`*|A zh@Xv!pN)v0{XClDXCvZgBjRTx;%DQ>&+q>Hnl?Hc$LF8-j4;PvYtQj{OuksNWzIB? z^Ot>AN@sYkCg(mPk2bxMw=$VVZ{V2!%((43vBzP$=V(L@u6w)@VU9M>;l}*G_1Dq=OT60xrjR2Z}Y_Vs`Yf!4>qE>Ji)umBq>onic!XD9dV9!alQA z5nCi^CG0C$nXHVUk=R#2S)^4S`;1mOY#BhyV_z01J!m=X%K)VVEsK3=E3K6VG#&P( zQI^gsg?$>UB(~I`rLZpn6aiWi`{F>UKucg>4Et1|sjQS%QEVwdi(wxRlpM4u_HjVT zK;yBG1+qcou#W+mIAaG_V=MQ6=-wp@58UnK}%rY z0`xx6ROo37^t}Y=eK=}~^q<|6KH$vJK)#$pcS$2h5eig3E=ncm{S4J1eEo_ zJ{PEieNUj=pt&*sdZH{BsKPHjvGuTe0rv#0fqgH`+!~-gQL{I;yr6k8qkE%_N@`-? z2lKrqXm6DF0qSk_1=RHo4zw~_O2AeXqg@5H9n`Fj(IelkP&*p5 zGHNLNRv9z_Wi?Qv3TPFaQxo+aj7QtFYE%cUj&tgueoc%( z4V*zMK>^T0*w@8zEznvxs)rg5sDpFr!v|TQ7S3$ID?$TaDH`C+D3sL2z5!aR3tAid zM4Vd>v<~(Sac+H#4XqlDU_*I9>!DU7Yz;sgpsX=!)B&x7bI1oagb!T<}{>P`3rPX7ExrYPZ6i z%mzxUQY+NT0on{_w8C~DXbT**M!hDWO>op2=QW3CvaxTA<5r-wTD8TT&jL!TSX-24 zgEt~S*d8_8z{j)$?f}n1-icPR4yctGv<3DZ@LLP`oi;e5Ber(%IyTPi#2&2^&dCT& z9;`D;+kmz~y)IY-Y)~7uyTSve2c@;IE6(Z!+6hNpQLi0*Mthvo4fWc?XV9wG9ktVe zcE!Fse(MO@4g2muUEw)s{px|O3uqUd*8^KO_zqehd*b{wpxscrC$_YpJ#f?ub1gY2 zt(Cn{F9I|uDBjnK2GUaFi8W7WR*MLCNFg#+DzWO&&Wt z`;hFYnHAPS-Yge;E%K`QVGHE1a$qYAS{Su+qJ%tjF4%caYz4uIR&*O%Wk^743XMu- z$VaOT>9G=|q&0}NQxW~4HH-XG1@tN{_7XU5@?^hj^*2hBFSH}nyVoGanVW4X4`>L|{ zBuZ;HS&t3v+t{aMlnOK@G;U)gY>Z|yXxzqe!GcsL1(zfTrSl3Fq~8hAFH}4EUCO8q z{Yv#+Zh!pTzZT1rj@*d;_hNZJiYJ|uuJd5;M)dz0%TpBZM)ZFzmX}dH*%rm}Suhi1 zEH9&YvQ&!YGhr_Lkyu_v@#L9krA~`6r1?Utd}_>xyT$S}1Ko%|1@;ut7sF_|QM?<` z|B+bU&uM55P-a7UkDLAE#F3ld__7BVa=pvH-DY&nOqRR6#}gb-{R&`lwZ-Ds|!k5rJF~kgZ?R}qKu1Tk9we# zf2PG)q{DoukC|wptiCrsG-7EnTcX*ITG-QwQQk%Q80BCzdX#-p2Ib~cF_>ADQzgen zSynO}QHDlq4~?gri_zH92-ApChDP}sjc^g>RRpaiLO$|p6iFtcC*;-0+c!Wz$*Yn7 zuMdroKP!M^if;;HPmygMUN4A}Z=*GZDEYR0K;+xVqfw+yv?fN5qI9CMSda;1tGLz-{tv6TbOfPFe%dD7vyEO2`4(|RipjjF#EQSMCZcqwR|Rv}uu zOF`eX{?KY(656H}i89R+7=x5NF0>Yr?<7iV5qVRhv=-4iPLx(58;BlkrQEqF_p&JW zyC`d-DC?#uYpW=0E}k_S&pM80t;h2S(5TbO9*@z80?m)HCrw1NZlYOR(P+OYYa^Pq z5e?2X!f`y>WMNUTgE)*l=_eZY5r^X#)=dn`C_0ZrDMd0d&`4TP3ndhPkd=~_C`O?C zp0pIh_DX9ASu^P>29#_&1vXljQemHxk7;e9_=(mkcg=Cv9~*5Y!nKGv+qWQ?gte)%84F&OXc&=dLD7>sI8P>LyHFy0i~ z@fyaX{qh$hPBfoErNytcRi)xp*8? z?~Ae)h*G^&*dj3AbS;T|mhZpf*y7{Z;^Wxjs5_jtDbc=Uw4Q!KXppcMC#o#sWKV}T2T7JxM58QghM6z9dGhq3sL=0H)l{i5hG zdCO>&7eYU2X3!icie9D#C0|ZnHVv>p2gvvPb08YMPmVfdNtD~VGa&`AI|pK*ff(q* z_t)g9eXmW|I>|TFwM^-?DPMJcwDj7)_SfW{fAQL`rzYygrN8ypxXUz3miwbv#eO}?rk`=$!eJNa%Jl?oUI>93`yrmTTR zp)B`n~}$qSqklzd`dp!}$n8=B1uMDv`o zw(OwfBl5$JXpSexmI79m56A{3??bcRLaqFu`B0jN?K%%@HxKJO59>ZJWKE0nNuznO zr3X!q+L^IMLPnZ#xp>Cq;?is^cRtp1KAcPPrUnPH?R=0o6)5>EvJ8?t2Poy0xq(Qk z+@QH}oC5Xov;Ily6u>k~@uCJ&1LZF3kOj@Jyqj4kovp`bvZGTOEU-I0LlzKv* zjO2GEr(Td(b0yCQNvS8k{I2BGi%i@TlDPmRrJj)F1wpANuH*#^`no5n{ShFoQ$J_~ zNb58XGy^fgwnK5KZ$Yl@MExn-p$x#yDM;HiKWNQyuR&SRI>qY$JL-@{ z{#paHCjMQ0|08SKIBUE$0oTvz-XdK^r~8DRaFu5n-Ub@!xjJ4caftZ!9T2;hGcfaUb7hRPiO8*By zcetusYf$f5&}XfcpewCapsTFah^^@^*fO-V0`zI@mjSIo#9INst;NwATrr_Ln{;1u zBxo}nJ;rw~AH!YCQNW`hQw{t!g0HrWw3hOn%cZFE7+;GSVJ+dil}k{*)Orf{A|C*K z0Hx1c&spn1*IOH`#kd>U540bCqicz!LFww&BEC<#2){1IwGFx&MpvxLSQ~NP3)VvX zx(HW0N}!ysKNJI{t5WeeE(c0i+Tw9cztXk8cpL|;m(Z`ZptG@m31}VYI>_=8w&y`N zTAM&OS(`yOTQ7n>kFt|C-5EV;)1A?i_F&xoJZTTH27?Z@hJX&UhJp^ahJn_EHcr|j ztl^-P>zuSH6FO1P>Hsw_(ZOW@o+LU#jvV{WP^+hMX_) z`q`P>j}_# z)?Cmht$CpHttUYjSo1*_S_?oQ$N4AhH!Qpu4Qypu4R-@cNW7(;cI1);|2Y*V=)auVba4D4njM zWwQ?8m;Kgul<$B)jzl@-VVT%BM}pF|x!?kh|ENuC)=`_*siQVsV>oKl^@XE0Wz|P*%9xMZ zbY0^p`g+oS8|R*ar}ty+l<;k59oY;8eV(7pJ&b)Ol)i6evNK|z0d+Fk%kbMF&_nh?`zh2} z0;;k98TH~J(E-o{&{tZNq_dX;9R+;` z`y19Z>$;T&nCvj3iNxN z@x1+lz0rOi+a~)K+W660kF%b$*V~)z7eQad(FXj!33L<6Heg$C-$u<_)@|z!TDgr@ zegORm`v`DPZKnc_u#ea)AnOtPS?rJ4E3rRfufqO_y&C%?`0c2@2Kb1*7W*UiXlxJK zWpQ>&yBzjJQ`#x)hfsRN9>q1v*vHUz8Pq8YdK~-msFeaVg`M0UgStoTk!X+TI_yXC znWb@78M^{%B?nDzC$ksW3++Yr2-F#AkHvXM>{6&x+OCM-Y|skW&qu9Ac2+ym&J3E_ z&SDS8@nX=$IBz(%5%xHoeZ($_b4%H=IL`*f1Ov5jUN&r5?GpI4q&?4m5-n!u(&8v7 zVb4X`d^-n9vfEGKXue$x<;CsCaWvnagFVst;F%kBa)9QrbAslybJ;~vvzXo5ZiW49 z)LLZcL7m)oOGtAJbUY+$iR}pJG1O{;jd$2vk z9%>K5eyCl|u4GpRt!!5TtzuWT``ZKTfuI9XBLQXAK`UW@KiX*mIu!dxXr&TpW9<8( z?jX=X_$7eS1iP>O0FL`&8)_?*IiQuW?~JoM*@<>ToY@Dz54CHcT!A*izBi8V2knD> zO_bEIyWxy3pk3^)c0Iek-2k)!&aa29k=-4&JA-ycjb1qKe!CV*YuY_g)&sN`N_t}J zZr8T!*mXhc;>_CE8i6)KZHhMAAS$8%@1kh44PujiIHs7h4QLz01A|a95OGRBAUE2i z$g>GYm`xCg(7o%XIHLb>q$q;^!>k|ZU_>>2u?+OGKndQT8a*9Rd0v_BFw?F=#E+s)?;3Xd@ie zU<_E+LRW2q8cq2?-(m)BYdd^UU$}dv~=ft-8$T-~Q&z+`03< z`%XD$PMb4#litfNs%HK!O78>SO@0@p_p`&h&)!GPUGR)&!qJcC7tRNsKz<#+V-xT) z^6L_3K7lsl;lr+jOTRP83lrgr&xFf76W;R<>P`eILA;w>sD#o7?yPs>!XHQ+`2&f& z-vU%}>BoDu=)K6_N!`gnWf^6It#Bpk+y{~d!0%~It%ExWi_BokS{CZykF`?t<9!{a zA@JRIA-l+Z-v@kv{6To%hk)|@50X9zRGN5@^kLwKY4sqj?<(!gPNz>hGi8FEnX<*s zOqpY6rrfbJQ|{QADR=D5luCAHTIP3VXD|vov)lR2J2U+=cV^02J2U04otZvOJ2Pdl zotd)M&P*votEc*sdE_7C|6dOm^RWb#yxLPQhox8a(@6?@n)f%r`OT%a103^QIK?@X zsuQ>W690WCdz2E>OPP}0OWDoHUN2=zXD?;9B89z_DUrRDDV4pHJ&knrQuZ0X{V90s zm$DkZN8VHKYUO~JvW`ir>PSsZk_}$UI`Kbd!nw|bS5;R3(m6#a3^h_hj;l7T+TPizsCRlF7O*XeGN`Y z{!-5BYm~kL{3h+5<99s^Kl?1QNR-X?Teq@MJ%r{`*Oqdxn~)v%f;7`vg4l_sO57 z=9%n!N#6V(b)SH%+yxgYC;mA6_~VTG=cxH?_8O&^fPYE;d1^ifZ@LTK^NT>a)m@Zc z$doc($XTWBlzwg z(f$$Id>r0hZv11EAA$4#2g<)kzIXv{M!BQJZ~lGBo&789z+XW=xDzPf@Mq-i%3lS3 z6`oNJ^M&l+lFagNe9L#?tY6^schORQMP5|i@ddb?FY|nN;=|=9Ux54B#TdOOarN(^ z{_adp^98u!2jP)_4R`)?IQm}${~I3k1^CE^;E3h=e_nckU;Z(8?T;nS{9XK#2S|@* zzd%;`Yb2Y$=65LH{H*k0KKCKG(T~#NBeZ@9_(6EokMR5;@FAXlNn2%zUnO}%$>Nu! zp96o+8+qjy;JyC~h%5}Zh%5|W`7*!%JwSOnq-MB0q-MB3q~^rUAuGc{z6{6oBA--KLeh^TuN8Vlz;bnM;m*FM`(DFs#K=}Rvr2i}prp+KY4_ll8yf1MMFT?o^ z;CqMgRt`uG|0cMu8{r1-Lkf^jxDWp3Wj-mF^dh|4Z%cA)zd^bgip2BV(#^EL2`;`Z zl0_R*1{ZNZ9GM)&{lItf{ye_n+{9_U2tWE8KG~gizbUom6B#^RU%vTP+T|QwCGtR) zxV;zQ2Yd7O`ozm!pZK}!6E}A~?QezeZV4~ng47Dw3J$*oDT62N#itgN7QvIsg|_2O zmN=UifpTjLdHXW(WuBI#)^a}Q!!y0e^RaL}=L6;YmQk}5KKKT{Yd&=s0ObmoQ@;$( zYd+<9iA!9;e|`~e=|$dMLi=lhr;%6lzqivd{p1yo;~V4@ zd%&L`N2-G_zl7EuX;*{naW&7KC@U{?gU7#;x@(X&s;Rw#c9#J!L;ksfbUE-E>aL*G zHOLknXw`+!bO2WKnJ#=sE&S%iaDZ~17sGY-;Jplr7WGr&fXwop?7@oGlk8Xv# zJekrl)C~iUB45epPXx{(pTsxJ1`Z?NPRmn(^06anI}Gk}3(q5X8iqV@B2Sx1JK(cN zP_qFkVAZO5l3(>3n)BQ2u;6 z@1`V<{)8m=O@cR{o;dVLS_!z0iv1@9zM#KgC{X>C%p8FSM%aajre7 zfB)!1%u%sV2V;H?N6(7$(^Ow#esU|ev#4d#6{gip%c?6(Tcws&SD3a|EvxoGTWh}7 zw6$tkb%n)>(6GR><`v-8>5 zoo2h|>`wQJ?TdYHUcHtJeO27c^nwUlBb5p77X2b}Z)9_Ul@I2Dii&7?7~MU z&J?wS)`aJd9z0SXts~)g6TT|$KH;Gg^Aw&t_E0~b_>cP8?CpOQ|4aA{=|AKs9caIz zM}EKFKzbh8S9fqdY|8)ZVD~Hjqkc%?36=jx$FO<*l6twyohe5$e5CYa(r3yMt>2@@ z$8dl96|3U#{I90gVQ~!ib-rQ+9^5gE)!r0-?d$(??Hw-sI`aSP(5(5!`*mpkSL68g z*8e(i8kLV>>?yH}x$D>8zxEZs8lSKIrHA`Nqw;?3d0#&I`xRK0d)ce;hB3dqFk8cZ9R-VDz6+rnG z&t$g6inJg>xsTR7wZV>aY}&==1LyHniM_!6Ph4K0_^l@+H~; z^r(_wnF%yrfb%qz+%q6?9>g;Uo(b{vl)gxMG>#-`rP3qw7}7{AQ+i~MA{~QVrcFz) zOs!WvDC^az4XY^r7Gzr*;r$N-~*`noU5NSFxc3<8Oq-Id5Kc&gQe&hqlCj+(j3`l-v186gl@6syb z841s|#mR{{N2(phC@>Kp#t093^~8ybIOAqqmPVdxo-pjDZv9{^C4|XG=U67$*chZIYiHoW<kA*2<|NAYarLRxr^ za|KWjEze5!WA+A99z^ntI-Z~-j-6IG>d(iIah8Q zp5y#RpER4EHF3Rr_M|S&sOL^9si{c#Q9-Fkn$4bR9=oUCFBF@UeS~6}nl7Q(ryOPf z)D^j^hNPa_JA3Nt9MYh7_SfDGqCfW3-VLNb_S8NOXl5Uay|cgh`IKVs>`|-KYkOLk zde7J=sKOvAv_5^3*dRnEob(05fL4)hYI8=Ipl;tJZ1fR?qvs%${?rZc>}JxLH2M)0^J3;o13Y4Yc=a zIz5TxoT>+v>e+9#q|w(3%HnIc)T3^x*Ig+)o8@^_A7(U&m`_i0*wco6v|kN-x<7rC z^3?BXTb}DukL;tq=l0w_M(;v1+IS!9_b#->wajO+kItuS);u&D(f8(--(2T6#Z|Ykt z{r427J3#&O_VrKNF9N6CW%NL4c-}rgY2Wbtrh8ra)V=$j`=B=Y#?No=>v{X&2;$Ve z97Fw+o1V0fQ}^{x+VAW6P2;^d3!dEcjD4HLbBNnx)A)~uN_ob<{;7L84e?nhw^5O} z4tb37d3#rM`P99fhUf0%{HCXjJuxip^OUjvz3vEl@AL$^Q+UeQ*fGIj26rj__j~o3 z_AIhzhCOlZF5@XvL}i?W$&)% ziQ}QH8&4g(I@RFGUwFdabH^j76;F*K;mQ?H2QyYfcot6wrxiPd5gS6S+;p5WmgDy1 zv1g@gf%=yWC+YLtccNA*KO&7)Z=h#6ho$wakC)z1a=`t8 z{rI2mXhTRfKqK>%V-4gn28L2MkbVy%A4Fb`H6XX(3UPmRTwEJs=TM%-P_c6;&+c~i zUA|JBHP(R7?sJ2IgL!rw-L3W<7em~vkFCZ8(Kk#OTw;!`<+vC{Je?2kSw3xDj*HRo zoVBAbFDq_#rxZMH&h^%hi{T0Da&(M6owIH#E=DmThG(nmpSD(hXe=&9M8qiKsZv3X zp$8rpV^4UR@5S<0%_+w|9XwgF{YotPE3j&>z!yP(+OTl1!0x>quLZqxmt!&4w!Vbt zrNE_F!4}d9n0F0+R9((%~(nO%v@vzfRNj?Bmk{`g7r`Pm;md z>9xn7K-!4CUJv5o_>Bxs_WYsAhQApf1Fifg@pcn_D97-P19(3eI0)YreRT%`M^HBa zkAV@ufwbDfZ(Ix1a=#_n{kQN9Ct>kl!t=$+v*I$~#jks%biga69X=23@U`fWd{p#1 z>43k+Wwg1FbP@3FJXPa&(g80E{ZDF0)p&ngh^NQ-yuA>3dGf2!BScS=8ayuaHt59f znu3SJH2(XQw7MdBqtxJE(TTU6NsI9?nMRBA@H?1>*F|S)x{wy(6*Ggnb4lmni_wLe zuB3%{JN+--O5G?ez{{g6`TxP&>3>SsCJ&HnlNZSE@re4L(sk5aixF!N=v7rH)yDe7w)+f8T=F$yVT2o_>W_ zRe$`Ww(mT9mvIDrC|M6@5$zH{W z>r|fKLvK&z+{mw~xtsrb8t^n~{|#TXSCenq&p9XZZXcp@eBO;^z{32^6&=N>106!=km@E#{U0(>NS9qNVnI7!b#eHkC;mwzbxI^XhNcyYc$ z{z?45-p5&!_wnwNc!u4Y{W)*`3-8YV!sG3W)O-@p$=k@kLEV3rzQ8ZN4Ufv(sQo71 zbHBqQ^*_nKiJ$0ymOjthFJ#~1>38_9{ti#L&r$RF?Atv32fmvxEm>P71rsV|ZL8D6VjOL^-tWrBQ<}h;hEMSBa=eE>fh;1Qt8aV-P*3@5 zIf1+@8%Jq8Cm0^5-P`dgejNB9xzQ^lmSs!M5L`>kv9$Em>wWm>zn}B~rwtyY^)TAD zz!UyD+Ki#iSokz0g&U~bm3jKXGZ62m{f*S^$~@)pKF&J4kD8mP+m-zhPYt>Mw5Q)4MX`MdK68ryqcylqcW7vr(h<2{&H!E+A*9 zID@h)GZyP6c(ctUBUkUrj^_-7x?1B!kA_F@#J8-Y-YBdmQhyTZ7*0a(%8Y`2Gr7^B zkKsIoTHISX#qj{p(;T-_dJy;^<06OM3D_ygJ4#vapv|pG?&-~0ms|LzHKetipV-3p zoSbAdBUdTk4gt!A_r>%7Ha>X=XC3YY-b#K4&$n{k!t>hiA{XAl>5X@#b^{U*u7<3C zNoipaP>x=isV^sKZsEVK=CsN!oEbS8DI+3>U&QH|OW?<+VR@JXoCj2PK0lqbIX|7W zIiJ%um!v4mm!$JJ#vLC{+pW}I3cQr>H3qS9h2_;}CSKiG&gXFg=sa3^66g{*boJKC z%riN=v6a&(p6R&+UGqxnjwMY;N4z4P_PK=jp82^1jq^(0oysSS9%~%gZM@lvq+x9I zg`@?^E~BN!^E{{U?hN1=v^M7UR^Sd!cNo`p2QtcXKDUT=%YnuwUc~c4XpRzaduFQy z=kNOOK#DlDEumU1dCnuQL>yWr#_$B`1cp~K-$s7v44$_Jw&uAD*xm-%hG%i!$Qx~W z4u2SFd@ISTz`pq5rOlzS3(O;-Xg}KtF~Yx8-y6?kNK?A-|2&lu zo_~7yg@0)`evJ}zcr59kq@SN&nZ{8G&&(e5N^6AU(vx4JHNsIc5|by9^ifiutN)*V znCf}M%T!r2{4?E8`lVkVzg*}H+DB*4UfFAVY)_4q;}|#=dBh$)Y8*Ys%&~J+9ZSd5 z(RPd-YiGf+cMklW<$3gfm1i?%FwW8(+Ie)o%ClL29*rYoydSL#dNf76A#KpkoxfP$ zP3O+h(Rb6ib9D6GbnfhjzMIaSqoePpbLZ&jyXo9HI-Y-V?i?LYNjZ0pk5Ogv88oU) zQ!^;Nih0z#QH{U4et&s+O&;7ijoEA*H!JzSYD@f&Id0}y*>Fw+E5*>xB(YKq?L-nQ z#n6rjO&t^+IId~@oI=6HHI>1}i7RLhO_ z8>y~Xe<goJVId$4%$d-Sf?Xq5bTipL+jl|-8tQpPs(0 zokEVSA-&Yc(<4E5Ll)g#rx4l%cUO1O-t@@b)m^j?bkg0`U9@k#{qu0*W^?Fmt{Xbs z^5>D5$AhC;sL$i>ZT~zFU0>*ka*baXaBp{gLPMG5!0__G^a;7_d8BoH`-7Kj(FLE5 z9^FVlYtinWhDLcU<#ps|0oRhRPg>;lNz=SO>7m!7i$0h7b-X!`{9LR9-XQ4xl}4mG zp7MsI{oatY-y6_=Urdd9a__Rd0IS0W${R_SqVL}b)Dm$S(0EWMkS+%rRq6!Nl~^54 zNYGfXn@Cqc1*L~Eeh zw)v#CKxIXJj4H7k=m~r*sXb6{;bVDIg~dRhs|BPQpuSrACv||ETtImtd1s)q-@+vI zEll#BzD=F57bx%P;pBPtMU)pONpEqI@fIiPZgG<9^pxt3Z=-VEk|fa?SG5;b3ilju zPV}}!r8w^!ihC^jV7bvJQa^aT;kDxoCJ*m<{pht0Ehh~H>Jhe_G(36R3nSj_3hX<^ zMjZ(>D%o+QQ9#dh97h_1)#SJYJ<+j}G!E$5jg{%VhB4PBU?K91#;SBiV>0<9>^z>i zSWTJ=^rVJ&&Q1nuyIDh;0W{KVzApV`2@b6Uc@2W%- zE@O3_N_hu3cm+`F>JCa`;0~ZMzpep_i`&7n>wwxXxAS}hD|tILr;u(0ii_J47H$LM zZlSD2&In@G-<&XT8}(Zg78+mdHn2%t6yuDVroGPCY2u*K)9xe}N5w+ptlbF?ZlQb< znD-u_adA(g?vH`*0r!m5b~jir7M_@}@I|$ve&CC^sLgR;vQc^mt+=@YEcC>SXLdaI z64)q?ijB)($H?Viq&CNqK&{HllI3|B&!Z_H11@U26pE2c6GkotBPT*RmL}*OFH0y* z0D1%MWb#SSlO>cEC%jw?7EYzCg>^AFIvx76n3_eT89?!JVZz9T$wIp@QP_oG=v?X- zrMI)8n+r(ufu2nB)Y?37cSNFABNDY5k*Jk^s@`_wsEi6TR9+uXeONbgj2X@k>D4(4-1SWDiCB=wC^)~Yg$T6J;y z`wrt-9i1Mr!+4f{djdmmSMOxfHsh^O-rH1_)|DQ{-qqBeT5oyMTe$;COQE+!Ri|fv zk-sr4dus9AeZrEVg)gkPaN*G}gQlirSqeV!|kMC-{ZYF@tuDEfq$oVYX6VFAwSV=bbsMg7LcOF9WfD$!CNSuU&qkVbB-KCM^7!SW9aBPVveDs zr*P?=;apFVuM^k)p6Kx5Tqn}voDLs~Io)>}Ra|>Por){aefeOmljhKqeBbdd z^~1GJ+_&Xx8ryfQJzPFm2XEgg&S`NronLva{ii4T*=3~0XjHyV#I~HO>}lU=YHt!( z8|PAjD{#IJ20aP>B)Gc+>CkIAP z8eb>P*;AU+Cf|2rwZ!fd+-!NB* z(&5{8LJ}-;$onG?Hns+Wo=9JuX(a?X!JOLcKOcK2*NHwh{@Pql%-2bA-^tgBQjhDT zC?_7ybrQeSU*kw0e4g`Ad}m|pBwr!9z9L^Id)k{C+joMJ#9C86-QRsD;&zAEip(#2z{7IZmij!tV zf3W;il6$SEl#2V#!J{XQ>pGgZPWDZPD)J{y$-MbG*)xB#cfEa)KRFWm*h8^SVuiR` z_IwucaITXhz3=RKok&d^+kMJ%adDj-YCT)dpA_jy?5(bru!|i^{-n9|_6 zRy2n{+4DLn(i7K=_N@B%tLOX9;n2tC>!irX=Je!fl8X<;oF0nr%-6}D)!hjgY_3mBbJjqyO;a?dF?w>e z>tl=SqqSQ`Z}QZQ`7?E@6@Z6r-F>sU}$vcp=A6e3W zcx$tkzFgU81DmVxH`l(du+d>*U{e? zpJGpAteh*?jUyI4?MJ!q>pksH*)yH?B}OKGbBs*<<`|jy%`r0h`pUV7%dm9-~ zIpiY~BjD^gTlR1F-WB^5JraLLHZo$-$KtrfoCa=1Ph+g2r!h*=(-@`bX^c|zB}OTJ zbBvN_s7AkzBgVsVw#6D_^5yHw2z{;&SBtC0(Q*|9R>s{iF}8!K3u@pAr1Cg4HqVYk ztmGJn=x_8fdKdkQ)f8(fs7=xK3$qQ5ad(cc)K=x>Zq^taqoBM?d-qQCajHRT$! z*G=~~Mm72yqw4txu~4k^#KgXgLypsqL{sAs{f$0G@1kE#&!ByYe#M9d-Hv|6xW#P7 z2s@+Fh@ciy-Jn`A<}s?#-x$^CZ;Wd6H^$B0i;Iql8PzAx0vw z#F5#T^&mzUF*m55_du0bdW?a1u=_YfPxIc{FZ&mJywE-0IQ4tp3-^CL#Hx=T$0}%i zO!kHsjze+w8ykmM(J=<)G0E4qtGcOi7@S68U&kT1l%T!EIf{LxDf(G|odhL_-Zyuw z+}|7zDPlejK?RGeBKjKhA7jvPd}5s!*TaF2LvfCd#5fd3AbJ+P-1}%qcjbDe2M0b5 zM{Ye7M<9B$uj3HCj}_(K^5(>ggEbCK^*(l8M=AD^vQ(At7e(&9$e-7z-Ul*AP5rjw zFY3tuE;OP#} zN^tcl6DmVAf8U86N1Td%N2%2~yxx1Xuj7zQaLOX}@#1ifLvu!;VXs~1wMkwz7O~v! zfs8}Wg*AshH+M%0nJ(8MxC^ zW#mgJc?aE6^2LpQGWwwCYz9~*ZpA;`a=uKxv zP!M|enK$_gjYct-QXSD3ype7;sRz*eS!X2)+gK?*h{GU_GIC0HVm27zVg}FN{5q4| z7%N?g@ZjmIX_UGEz5B{&ES-t^px68qO5Shlt+hsM=}4pqPn;Vyq9ZXR)Lwh@ZVk~S z)Lt9srJAS`>aD%6w*#6_{W^^ZqlQzDPGiJ`{!^`~dQmZ2+N6GT6eaJul~#M>t#{CQ z3+_lt-gfI9b>2kR5~x0J1a-!FP!neC2k*S~?%SbBKV~$B7Vv}_8Z#r^WPDewRo|#L zRFmlE)F-N6^gp;t2PfWIy>df6YEvt=j+TQMUFV`(nj@uN@i$+waqFkMuJV?gPTYAq zno%Fkvn$gx`#u{d-m!OHJT>UP?XKM>>Hef<#s_!QT%R2oMRjYg-kLPZQa+y@{m`Ix zNF(6LY9~;JZh8civ5#SeIa;A}*nJ%0*Q!y@f1Cb7>e{s;2RWr1a5sN++$1Qpqt0;OJ zV--D(QHq|%C`C_Wl%g*&O7WXxl%z`PlLI$mwvCwIJ*|ZpJ>$LP`eet((aLes5p?`w zY_$MsPjV&X;}AWLxs7>_QE_}?CC4~Kf1{7lyXaS}CMk-x2}dhdRP?ksKGEM8pXhIl zPxLp&XV3kOaciu ziha-5aKkx`-sSV?+7I1X>|rq)v8%;+#+ZbbEygfLCf78U^~o`Y2R;t+pi=9=3`b&L z*FzC=gX+ajAeSFHburi#vimqRN1yCYpYQs`v5N6IbmQPIakj<-7gf=|&M>c3&sO@o~R$*9yuJlwJ-g=Dq%U*qiRuk#PrTN}qfn zwhuG7CP6S>wM@|on2`VB674^w)&T%M?z`kp!TpJ-BI2y4|4rCmT99|r( zacEpJ%IUD9)D)d8%0Wf`ygs%b$Q%W2j{m=>-`O-K?wOC<^S)iCLavltb_*G;xNja! z<8Uzht3;{~q*@TAK2NSF7ll-KbdSTn@~Sb{vD>)s$nP4 zMg4VNo47eohRX3D$T-y3AMV-i*<6iH$aGTi#`Q4Lo+2#@JxlOl^?8h9-*bJkx)il4 zp-+*kJsjiE+`fl&9P)2*9GcP?G&T;wUp4G|=nF!#l?#p@PpjO9&>LHgp)2%;R((!{ z-qqTfq+YoTc_&I!f$E+0G@1&Wigvk%G#RMgxth`>U=4W(N)v(A=gLhn4#GH)c;B@2OaB@kYI$%G=m7FT0E8<%~PP)pLI!Q^WmvZUAppdWf=j zvwt9K$*tg(wDQvV_9KgdnpYRbK} zyH)AKJXHWIc=sS}Tb91cr@qFm=-%%A5z>dbIsQTFze4?2xm{k(x_8XC}GOfK6{G;4P|3_Ji(${(W95<@}88y!WKbGCYn---%r~d2NdwFWXec-KmejiUQ zxJ|n?&-YTwO5Psdf}6ElQ~L~`_Fnd9fPa_$IBQe7GRsO=WPeNP$JyoC6+Hcfa%zs=rG+pP5W*-yB&`|nBL&aUQ$`g?)*((Z?u*!V+Q{wTYQ zcBRr~d?G9Tl(yf_eoFcd@H^b$eGQ+w8h9W1)BLJOvWxjdsq{B|!w<8+rq%P=wcJR5 zAMiffJw>ZWfS)1%Ic@$XyM#}axP`v)d*(0YeW~;_TK=3n(VwE#r??gUN#K**YW^wG zQ$X*je zcXkKxj_l6tm(=`Yc5ZeKZ+}Jkm)Utd4Jy5p_jhLRB;Ccm*WOV6PrUtAc0TV1m2T(F zUD*%l@$*1$O23X?Ukkj8{GVz0PuT^u9aOrWn(MOf)9NpPf59#2-zU8Q^xpHoB7ZS^ zCELZ#<+o<<$ZiAPmffD+!l$kW-cEiCb+>0X@q7dDhU`Xet>4KfUgLA#VE>od_kiEy zySUk&y4NVZ2z-%NH}mQ1f!Fg%wNL+?ot~YMotfz)KD2adb{fw+NM{01CD)H!`C$n8 zcIwW|JZmtbbbNMEc44*wcs%eda%tVa0RJWXHSpKjzh>*{@u1Rr(m>#aJgukoh1pEn zNDbTZ-)EBkCELh1Y{(`-FaH(zui4bxpd!EPgi7`;a z(UivV+0msF_&po56Zqd}Wm@nCmrl%1%C=+^==(_Msr%3bO2+`T-c6u14mgoFo3j&X zxtafcCh&x86L3p*GVo;THdA{-c3ifC|2~iZKDo4#rvdCB?Rh>nTS<8i<+-H=*|C)8 zQ=S7oZ%?TM$@?>m7vF)j5NJgC4kUNE1+?#9T9_@!u%~7Vfs3<6z$MvY;L>bKb{u=< z3Zm_MJNK#-Wq(#SJDZcuBFzQP&E{n@vYC`-kmhA;Q{?`&DWd;$>gHwBvgyF}>3)Ez zJk86Fr_EY!8d%Fs0+X{T+0<-fx{Kfhptr;?=lv$i-gdBxd_p!co0Lr;O$JWo8zxYi znvJJ4A2@-0GoRYToeIm-%?d{JAIH1p**Mb-+p>+%@tmStl|OSA2a(_-$KP_ww5(vH$-YB>i(;!F&!mS(5$c6(`5HahFatrFFx zQ%c8VqbP5sysb1cJBISfl(&{fWFskWp?q>_cs7FaCESg1ak|Uql2TpPJ?oLxk$Pse zl`zrEBc>&$Z}QeAdcx*_MPbVE)}){)v8QeAd6 zEidO@4)5=%rmil#Hr>_HE^D84$l8&rvno;@upRjg>HeG>()~F%@Y$=mwd3k^cgKZ1 zb>w%S1@z{Tj_LN1j_Kx+j_DR4^^<49S@q$!!fj=JGEO07~il^jzS1w63JppsX?*$nU76G%))| zzVBa4|5*BE=~uvC@$?Ixe*^qS@}HG{PU%~vZ8rr!fnO^<2Yjydb>P>j>%=W7Hv_#zrBk{^ zr4x6hyo2)X)xd-YmxOXwa8imTV@r&imVl|72|R*y?eCuTYkmAm%ht? z`is(^k-q?Zp8U`FZ_fk2LjD-{p*&jpds_as^i;Yz<*9Uk(NokvR{9CG|3C2W$v@58 zr%Hdv^Zx>WLjGjBZ{k$2{nm%D(S zc;Bn^yV8FEe_#4Pz*6>m;D3>r1t>5uc=GAuc=GAsj05?|M8#eO8-e-SNbpVy3&7>*YUgm8~8hZ zhh7Tz06$rJ9QXuz*V3oRyO#chyes|w6W~4MJxhOG`WxWilzs^OVd+P}AC>+V__vHj zPrg$N_m9cD@m-$)K3)0@@EP)MJU;{cOzBx*SKjw1?JT_n{C?@LfIlGb!SfG*f5rdl zLF$QY(v9}Dq|X9BTlyUEbEVG%KVSL+@C%GY_tGxDse9>V^6sTq$h((bCGXBSy$bvy zd3RdqpIXaP|NeT==v9;Z*Yqg4-*;!9RvMa4no-gRNADbca`dq22JFT={dDx*(Qjue z^-4p^O3GMuKxMHh)F=}vF)4@j0xGZR3Dk!@Rq1ImX$m{$JZkjI=>+UV?XlGL0V?zgFMe(dDRRuf1Q-B**;sC=lDrQeQ{)qo^DhR>4zJo@r%%hyID{6hc{dWMPmmryLxFnuD8-FLwi(8=cfJe*DxtLkD#nv znsgkqkkHz_l z*@>HaoHggpS#zeuA#p1AX>;zxEOAK8%l+P@7~*Rct+#3b=g z?%5l)_4Ny{Ke4EqnSz%E%HcXg`pD@!CqKU^%~xQS{&M1;-g51jFELLK!zBrS)F(M} z%7B4i-dhyU)s%cUqdNm_!l~B`!iq8l$hn-)cAbqk=QxWLp>t(jC9tV8RsbcCc|qo{1ofY zl=J6&b!0xADLojyy-(^G{)-FKOqFL%DP&LcrA*a+w^?hS@XDEzMoQ`Qb#w-$f#Qwx z@ru2byE~SUgms(LZC(c?6%3@Y=rlf? z;aBUM`DiqRe1*M&zgH(K1a?@%$mED^CLb6 zX1RYkYwl`dR>S#kd)tvU);CdV@oWS*R-IN}4eP5P@0_oh%#`c11F1T#*A8jcW&+)(+f&zp z^)-O9RB<*l<+yqCnp%T_)HqXfz#j3UiX?tX-^H&vV3zaMmgKD&(u<5VKheOs;FI&% zhU85vQgd<2TR@jk+d8d{meejtvvw@=wV2vUsPp19YYTvCDOynzRME2Z+!^Y@DwIof z)}$9XchI!rg)sDMo1%D_vs3)YHlw6|R zqW)Z-wscn1t~-a$SD!Rr?$YugYU2B(S?kMu$samv$1oq$nJKmP{nC8Y0Bd+RJk4Bx z-e_A;voDu8Jk62(hMcdQ;c%cln6u)1&ElOi<(xQ^L&%4wS#j28)52LB3~WbUVs_>L z<#wGxxkNcexkNdQ`LEBNykcAGoiBCja=Y>#OVX?@W~Q9QmduOuHOzu^v_i=gEXC35x+KSSgv;yX) z^)Z+79Dc8BXdY=Uzfpa&H_M^}qwHE!N4tQ&dyi}t&kGr)cEEN#tMh6PY|ryzMqAB} z7_^wuBKlfGX(_W-1FYeBS;EI<2~U?%zm$>gOzkjMMrWY+6%J<=bpc8fhEvkxxf`XC ziMEVnmDW=3M(r__^~99IjAC7SMyETqo@*Y(ij$IzA*oN4Zj2?VUvw`XM;gnzmR5{s zJ@oN<)BC(~23CzIQ&* zadhX-&rbw@C115DeeZ(wjX5_J)IRvDpz!X&`5BJEl$NFMU&d$+p*)mSVw@1OfkVl2 z>(4N1a;uQChn#B*#!R^*w<5{u=GLWSSR=WI@hDcu7*>ULDD6>WDQTb5PBo5_b}Mlr ztXRrjTDro{rM+t+t3vyicCbm5w2NsUn@mZ2nRYX+Y1+}0F0`*{W%K;Tv^OY&bRg_; z+U0UK;+B{Ooti2e$?Ddg!9g1I$ zq$^PTawJ`c;+GaTSD^UiNV*QCt&XHCP+MJ`OLx4q>1oN+-lwh4F?IB`0Xn9Rm$pI2 z)bWaubRCLcj^u@;eQp_t`JNo{%gKc7Cx$5@luw|A zjHj$8PO8(AzBT6@nrkX#Z0Ug%Rjyd6Oj;4LnY1J1G3kmjb5NS5&Y?-0f;*RPN%`ev z<>f;rQ;L?xg|sI98_KhM>fZO1*iGD7q>7;vX$k%FKg!4L4Zrd|#oZ*|S(HB;!>{J- zDeflu&f>`Dd&_;Z#P0GgR^GqzolB}HXDBBSyI6Vua{io~ zpo#~!e@O@Rjq(g`asL_zjv0whZRU7NEz+Knv2!RJxSOH{1` zK7x`G{cv(QUZqI)uaOC}q*0zQJ0?N#OLee%h88D;m@#MlawAw%}R1dL%(mLQeo;EVmEr2a( zdjd(D{l-*2o)()(#{k9EO}yEFZC=X0nY0mm{N@BV^5!I3j0SEZKZ)l}z!S;0ux2WN z6|_B>bRuvI`Bw51fhW>#E1w(#Jc)c8tEv@n3-7m4+JZfP8|Cff!joyYoz`Q4Tgi9O zej897#12+oYy1GV(N=GOZP?LIq1|abodVp>r%oe{!@}N%_otIiO}6+`u~nbSyE94S zfNGx41JqvsD zIkY;DTzEEZ&ZBfTPz}iWU_uqJidGjS%lQR7or5)8d-a8+iNFhZx{%T&{0-Xi{vvRv z9Z-(_BAze63*jQ*CA63fynxo1kR|~y=IK&eUWDhtr3vb@a2ZLz0i{ZP6D9*MBflK1 z>j3OP+bfc{!WBGSTDp>UQ-PP!?n=@W;1xVw1!h(QrK@-q&{qF~D}Z_-T%CLnuHlo@ zO4sm-slcnruciG}_!V56;8oOJN4lnTJ?*9guOYvlx@+(Wki)qF-0lSI$R}A>sAZ>IeX*uQV!z1Hv>k~REBpqltwNwa`A()w1?46NhYo8JM|=$vfj zHv@0xlehDJ7Vs8wt>?GkH_(N4?}Vmw0lFi+i~JqH+i3AFO1EL5zMW6Kn=~7!9^~D; zxg8s}d&eE5cVfwYCv|s{-kq%5@5JK#Zd%^O)4Q=d*V67iq&tCklm8KK<^b;`|0C+| z1gg{fV<=ZG(B0>cDcy}tS*!IuJl%~|UEB40Nppes@bq3v^RUkM;QhU%dw};)doOi= zjK%-GynR1uKJZ?i?t>oo0LsnYN9lc~`;%?|exBZk=Yt&a1EdAO_w)1spL##=e)0$T z)P2DFc=`bO{rE*ZK+A_HJplXw`NL^Xd>9(qi*g;UK1lii@L}=~(Rv~9A@UC;---|M z<^%XqxL1Cd^e|9Ai;s|h5TA;VB&fXiQ9iK{sQ<;sc>57xAM!`YKZ3u7UKk%IEdoB0 zYLpBgrHy_Wa{G@_dIYGK#wU`G#wTdInDS#heS*>wEbe`I|2TBMFHpJilRQ6`?Ea5p z?|+PTPmq=*AArYz%9)>{<>SD|X{SHHC-DRLB=4RiEls`w)+mL3nwFme4j_Mu(w_i7 zP5v43KLP#;?LI?V2GnQjXcjb@qc#*8sXo0Ous!{AWCoMeyAGsOMZFe{A>?gIVK-C4M}@f1-TlI#%&2@RyYjy>rJbgX&<Zu1%-=7{E z5fXS;-1@ZTDxrRssi*52U6at3`fq5OtNn0px=dE)3?a`nQb#>8h;e zmx|p(Nj3a#`EPMS8X$JadkcH>8yp3rV~Z`vkcI<$@}%}&ZGBIk9l_!7n{r>H`9$~( zjD$PXPe2}VH1ngDe>`anyqdZKEmqp6TuotBR6f!&CD%8ZR#m_$S}Wx&@Ty zv&+?{eR2V5l10>O7wXGyp>(v2w3wZsTiQMPkuRrZKPdRX z1eefq1vN{6eVLyX)Gh@|Nsa>!0!mYlLoyi*l)CC=JP5dwd=;fuNG7X*YiO|&*oAy; zqI+v8E1f9UtfNIml44o`*Yla<$t!?LDjR9P7O2OuUd9zj7@c|E4BP~imTsoB0f|C- ztn5*dqzh#bWsNPQmdFg9lJv0|X+tTaC6Ym>BvVLnx093@lr?tnt_5%#xpIQi#13js zgZtkB*WZzLXONT~PNQC5SfvALwjQzi#fGFHW+@}I0G>mBE_nu2^Cg#mHXM8ntgx^;ma0zJwa02U731S>@3i+kL$-v31%u89nQ-IT0yO)xt!~4%+ z9bQJwRNxGrE~7L9sBgsES&IvR3s|3TC(QxQrta;OW+NHQWldhr%3BCrNd4ucxxizo zyMk4^6sU}T1?$q9rL4;&xn`>AhCj*sSuVGD`1U!ZO8fs5L-cWMAmUVC{a0~gh zl(qwvO0Q#0oDNj(ypDBnD)21w>!>{oiA107>zVs=fXbQIQ+gXvneqna@dBWd-wmvW z^ML1&-@x-ZtYRs!`Wp9FZ=O?+(+XwW)i8mOSspRz{{R8|C)Uv;)igr2pQBQVBXD`Kmv8P0)FW*Gxlo;?RK`7`8|}1kT5ipg zTv%&hYo6se`T_gVc1WT>L->5ea4#%pmKLL1`|$@jSrj-bsjut%O# zZL<672fs{!LW(6 z5%b3Jwya^Z+=^OvkXoSo!eo+uT>Fd{=>ckQ%wzgWP@Gi9C%Gdr%8<_aM)t zv`Bl9D|8`AiERPcoZIU?y^`-i?b)B*gY*P*KU&6WEbl>C+JpK~=N{CDU1kaG^WCR6 zYiC7TNh^4_l)c4SJdQLHIFj)`j*%Y<^eoUy#&;}Goyx%VuGNW-t>$?FdzJKRO`>3H61`f(^IU4AW@{6rTAOIsT6(yY z8Y$S?M7w&k5^CsE4Rh3oaj6Cx?WQktSIY{P18ssZCn*N>YQUs|5}qcje2K zx1ojJRqiC6$mP-H;N{iidqQ65NVy~b)pZ`6l2&Hrsga~Q;D}UqACYU4U+O?U3g}uM zNgG#la7T5lU8Ra~2?NGal1CEfUF~&g#K*FhwJo{M9d$Y1$-L3qY6`jBQBOu%xnvq? z63{h0o!TBiSFv;BD)n@it5bcur@?0PCSp5IPiwLVqput@kN4V$)hy4aMR%YpbUvvE z^H#+>*QMHZ{Yw_{raN#kxq9HfX=SPhuA;?KlKv!0MQVWEdD@aMV?Npfmy-t<`c#xs{VE(ZRCr(u!BkQP9}w( zR;{d3`BwJ1Ex;{2okAOTLN&A7DWAe#x0N<>M_bv|c2GVY>eLD-UvxSpc_gXv8NBZd zlvg^7Htve2^Yk{#XR+6vK^wWFGvH{X-Eur~H)r#7e%e{ir)8N((%=08lDg0HX{nA> zIF$TCut2WqJibFtDSLw>l2+uLlKj6s(lPKt!6V59$rs5ZN!c&vSzbul?GlpQk+zZG zj^vak!VAq{ZRVVk{Ez(7RNyq)=RA@p9ORMYnzVk%Bh7>tk_!rsNbYDZuwWRh?5V@W1qz=%VjMl~)%z#~?W_7@-L?ydIYkO1EE7eMWtDv=AXxoR> z1E`eR7i{SQ>`B|cl+^ktRrjNHTVQ|c`z0FQk8i4CSKwqIus3hyc-%YWs-!_}p)Lb> z8brOiuYuIaBdMcNZqiDqp3KoO(n4FHypsE?JB3`5oKPFE$1}llKSO{aS&yJz?kM;o zWojiUW0T1(DTCxzUA^nwm5%``cPNdt28wYL_|#~ic&DuG-Z7rHayjFG9mzw>qRm~2 zTVDt5j#?xql53xsn6R!AsI)SJeReWXd~^q?1nX*e*0NXwtl?Q5kk~0dtUi4va3)V; zU@M@zzaH_kfnw+a>RPckRP!u{Qw^-T<&8UqB>glzbG!^JRyqYu)>fr9XhMFlrciuIO4Ck$>oyEQ)7rB;^ znG1A3UQ1~<(A{_)V>BPAopv4LG8edzd>yq5p)2zlv-OO{5}>@8!T{ zrJfQ_6Kp;hLQUW#=!Sfd98=CO$x|s2gg3f6rDI3?#z9%&)8KyJuYzleA8OUIJu{Cwz?%Dj_2QkkF6 z`J}eYW$2WY=W>2&cb!sm_@%ODDfp%OJd%_@w~`0HBtNx|)D;*yCACSxJ8cBdi#ny? zl+-E73xzhR%rBh)pCnJEW~nRtUanK>!ak=qX)B-FoVcanl(bX3djzMnJ@HLD_`Lkm zHuADgsWZD`=#(mGUDhdePMnfDB_-?NlyaStJe4}7&WURZol>Vac&E@QsZEl1dfOYE zQgBV7Qwkm_*Cu6fN}**6olH8e}1JIZxRpXg(UmD1`Ay^_&)X)QX73B5xOKO%v z%arSs8tReMFNNNz61>TdC?6#U72MRDhmR8Df}48t@KJJ5!A%`JKFae&IX87U`6y{% z&PT~p{bBJ@$})Y~OIjc&h@0Mf+Y+9#51dzjlJbOd#Xw*$pc2L)N_9YMwW0Td_f+Z_ z%%{{%$rovlR)QEt3oXi8y@vv|!E2*ej?gNv93h{h-c?PMQu!#_#QhU$pX8V1qC8(S zmRxB;U6b@^Jnxkw+LKS9wnvf{dIE!w(#LrcN$r#Tk}`r;4o{pZpQ~$H66>lTHri#C4}Iq z=EFhBDQTIj1uh|1p09=fRR_3?_nu&COD^wJ3seufoKiPrfi}ETB3J?E--eRWebgqc zCSOC|4ZcQ7?(Vf3*oM5!1*u0`Lz{@-b38589ku3pBX7C_PaxN7(iM(Io@z5m-#;}- zITxg_--#r7A-N^J`c8r?s-&dWD7^dRh14WzBMGfhC1o{DIWKf-(j%Qho6{1vq@P~s zj!uIYI+J#1kmQBbB*_J}0;*$jpVJ2~c%gHW9_cKe&ZW)Ufbu`*Q9d_miL|n*O}da= z*ok$2AxUpIcgc&>9(XbB&x2RdpY9TB^pfjGeku7yKx6(~3a0b}Uc{#_C1vPy)ahMD z8U|E4yNom#sHe%>sTm4XuljaM!-48z-_G+0^f^+M%URiDf%=MG&Wb+6QH9QHZWOo&C3Q&3NDoWFUTJEkQO@(7oO1PSp zIvc2^`D&hL0F{ZaVZ|;0s!_d$bvqX*_jL`WIcRmXC|{c-gKH@*qO1gbEp3iPpQ8kK z9qV-ka2Ze6QCbF6qk28%<-p~v%hZTK#Th z1s)GnPjw@u^*}9sH40@YdFN;(anzqj%94$>LGvsiWSpmY{c z4(+z2nY@ivbuQ(zdAg1Ivw?bs-p*>g5a=qropb?E&h2(;F9QF?KKZfGYe{1&C^t{9 zrA8~XTTStMU7?)qz+f$O-S}^6x4dJ#mi-_Db|CMb_J!_gUr?jf9*U?&s|Tg7iFON> zj2h~-)LMl`t1Wr1*OI>FdadBc+VZX+pYIHGm&vtTy{N0N*J{Hj2eQY6UP}$u0G{+$ z3cZ%PEa{%!T57ij@iy0GNhLy~rH)I_tD)3{cFQy8?nI&8%Jo`mu;QL@Ppg;DD$0-P zdoza5cLaL!yP;l7t6%7~jHuaAuchuP^jekV;a9Iez23WOxAJoeYP8gDc}me!ce!3m zU;MIOOFdRAo;`c(x!YDe=Xx#evudS+AuYtAgi6i4rcNT-Ix8 z6I8F|dE3xydG2;8N$pnfWA0hY`RpQax;uGjv{q0u_MA669Y<2fwYy$R{Z&)itoU*+1Z&})T`ORAV_v_iYJyIw1_So0ap`r56~YlTKDv|H-3 zirTHW^jb~pwZaZ4x8`g$)N85H3hmbHM1z{vYssgDwYt7uYXS3>>$SoTxUYIGHR{Vr zS^@XfS1P=u!egp2Unwns@^87Xlor6XX&0!k*9tpe=(W^wg_l&W*9tqJ+AVE?4fR@D z0CQg{&uZix-R^oVHCmzF(h7KF^jZzAfw{+29NrA8~XTaD?p8H@f}M*}|=Cq8ZyKg3DE+?zf0TE&xqZ@x2thu&XHZ?4A907~a;lig6upjI7E_Guri zdc!{G`96I+!amq}H~U~`_K2_#dZsV84=Rz>w-2`FUB4s;<(9#)68565zJ0K=o_(;> z8}`9U+NpC_m#lARSO$ks(mN%5-L>VF?SondhfHZK zmi6p|)#zzjCi|c#Ny9QYo05Jk+V!*#Y9-9=gB{+m54NahAN1xaqYE!$zFPo2@0a_% z>jS8LP%B~B2el&W)6%|yeK6xQ+6S{Y?1P^7(>~Y**rgfv!SH(zA9%GkxqUD!gAKjk z8}rxF<2}6Jb1(PZt%Pz@xvzWC`#mg%N6J3f9KF^blE2oW)@vOsf2}?1wGOAh*8b_W z-tyOav-@j>7Aw5AirTH+^;+Sn6<%A1+FxsTy_TL@;k9+-{Iz!X)GF$=LZkJTzgC<> ze9K?U_zjcb70Y%;dC126we-}=&mnrMCA_v~zzrUa{#tr!<>wIf(JFdv9Snc1B0m=A z5S!yazdI*ZJck%QS_jULNhfo!t+&o08n@xloI^Ztf2}`^bBKq>U+ZW%hu9o{t#b5+ z=J{)dkJiCGhq!0G*6t?|_tjtPKw?`p<*!wYYPGNaS`p9c@Sj60#YgO|T84mB+T~ zM2kGOl~EwP9daUYA{wtewpB#6iU?PpBh%MipWldQRhKxZxYbL~_&vq8s>DAlk8M?n z4yzp1N`LpB=x>bkke`M3mbKZ;s2=h&$n&%Cd2FjzuX_v6=TmVO-kY(isr9x)edEJ( zxSD(s-% zW5#W0c*d~#I;&W{5v!s3XABRIFV@kovpSr&84$C)MpHvud^!J5Ra73YR_j3 z-}1#e`s1!2m3HS)p1ipRdUGlqML#~wFK8I}DHD;~SiMk6Zw+4wE&Jsx|UE;K6p z1<1*HB=(5So=3{^PJ%-pkG*)t@aT-kUW}I&rwb!OdvjuE?e2vYu|^Nv7b~K#?;e#s z;<4{JcGjMBRuLC8;%4c&UXlEt4tG3uJ&TM5VW33xiRDG2(6O2Ax1=MRxjg>dc^r21M)?rj?PfHoMeIV^461(w#^w%;9 zP(*0g&q^(q5f(ZDjpgngIo`Ju-d4tJ@Fp5#EexiOemvfGr?zT1ZHzTKjC$|&tV}v9 zJ+CTxXPgCZW%uSBWq0>#{jJnh8B zb#$xf(LA8KDYaE|fktLf zi?s--pTlZOMrc<~RA;pWs4i{|y;%x0rqbb!y>O^wup4_cBC#LJ80D`EiYoQNA&fG#J+nB z_Qs>HUj%&^#VJLp_{C7Y6PvHlpcKuMtV9((1OYq-D1XkYhysj~U zi}xdVA7(sjGjEaF8adeZm9NW3kz1EX6^^#~_q0x*+xz!~o;kidq7(1_J(c{P`2R*S zR^HFsWc+ud7;BkV8ZvHO30_|*saukgwEb(-RvPL~Y76uZEafRrt9VnV=UlqL;~URd zj{y07qvG}AxdkvJuR5N3)6zQ}+LP-i;B5}QXyaX0y^xOjQXY`FbS%KRsi$Z zsughON|bqQ)oS+T3A9i)8b_YTR`mo+9$VG(Dn?apmE@TT@bptCPerF-nyb6Tq|;K zsZ-D4O~-0FylG_=WlxvY0&AJgarD+3=i*K}@24A2A1i^C)Ec8wj=MW0Z#lAD%Lu3; z@wU32yz$P{jzB4#_ps>Iqs>UIh&qtgj9Pw6U296}JSGA4{c&YI)i_DLy5_jr2^jNrQSmSrA29VdGqNU zuv+Y1OuhCZ?;3n&|pPE4Nz|$W)U?N*M9R#T!om3XL~DB#pK@ zde3hTA~(Kkey($P!eVcG9KhIRiZqOI zZ9&Pg9tLKK1^J22kvyq;G%~qd$2eN(Dc6G5&c`tD%1E(dmv_EQOjtIa8nMhhv?c8( z@tLteF?BLEanf@v^CYIYw{`+blk@WhQnqP)#ygKZ@9EtzW0|)pv={HxE~-gWtLR;N z-ex@u+TuNr)A-aZ(o|-$f|9d4m3bAv+<7|#^Sh9Ya4ub%M+?`2F=N%oO=Y&{&|cj1 zjwEMa+!RCA&Mo9q?$P3~u?uIiGNktU&PC+&E(s64@l~EGKQ}79a(A8!)VpperP!&v zf_t$$FQdIUYXr{Ne=BJx1}*@4(~$TmtR!DWYonvPdmAaeD{wVW-W^j3TuI9{l)Rf* zou=`oR{@Q~S-x>^E#(jdl z>eL$O89n0^tVW*SNK2zsdmmp!k)ZsN(f)h7VkkZ+|$ci@TS zdiNS}eH-~Hv=B-aPa(yfeJ2ouYAfxHbG?(N=);(h_2G?sfWptQ+I?-#Jvr1##T&=-m)mGe%|exw?pcYXG!Mcm9L#gZZpBrnFDYYD~j zyK^chZ?6|{P&r{IK9`?W5Beq_kyAFc0XbzGN`25bIeU48`t+>=Dkgs$l+C-_a#|Pk zZ8UE~E@<@zl?(b7l&y0;%GT-)$|i4LrfkUxF51Z+~ZcJ zZ&I_IzICCUlueJ{plnJ6(ln)spl{N;S>SdTV3*yfT-O4X3(6)Z;>maETh~O>g1+UH zO^KsO*^~-{vPtDyL&J=|o71W0)4AX^vyd^yp5tgFle1rE~jjI z#Rp}(kkWat(=@4E2g;r?xEPvpAu#Bhv@WM_y%K$ss|qTY-%=qx3YsRB>quFOSH6!) zDM>okjqmqfOIL+*Z1G;pE{t8=YZ>wXJ>#Gbq$SWOAO3F7L@0OlrmcF9i0>gcsPB7k zpptLjMC+usEh&d4MD3}Pl(LbUkbzLqKG4Aa)F>T!)3JI9rC;fxvXhjqRpR<85^Wp= zB~waLVv_FF&@Q5OsQWM`M-9*3P+0?13o@FLv`*S37nf5!t;QiC)xVok&u`=O$9pyq;1~2QnTi=xqYI4n*lmS!o8)y=VjPrUB)9H&80-K&C@2wOQvn zkkEd}7jL9i&RG4SS`Rgr-u|IJBs3w$JltIqB99k(591f4w+(;|Mdp(TU zqfR5g*F&9#c-^6Z*W#|ai~4x2To4%DhmyL@;D36NH^gf(IPkjF>v&zwysFB>sn^l@qw<%7G-=Wo<$fQQ@TwtIy9WQZd1>kT*Fz^ZH87eG@PN^lyZlLGuLOT z$;`Eyq32X{6*|mZw;6iQvW9bGnzM!)&SSxAalC1HAv~}8GSB^)t#0&Qx~=}O4LDIt z?Z89>2UAvOC~qcx3@d=Up|XZr4D}w$8s1*h2dI=WjMSU43mc-R6&=Uk;L8Zg;*Pq+ zz@0ukDGT&rER{s`-BD{O=kJ-ome5W2DZQ%xFMH=5phc0i@$Pw9(k?mY1(uval7S#W zGME8DLBW8a2ofZSqL_0+#R!U+G3T81h~{+anX_j+Jw3nQ)5Y8l>@MsA3wYoD(NBlz zci!om?&|95s-C8x)(>q+N!QVe`kFB{rrHxr<6+uG*-6PZs{_B4u0p3^nLpr8lt_Q5 z8C+IXvaOO1vSS!$o$0R?8FiX{rAurLY84?ZM_L$z8h6@9kZwc#Snp^TekCbhV^!;c z_Kdkor1YLTF_JXPo8O;os>~CxEAL0EhVInRTh;nOwpN`Oi}Dwg&P#Syy9dr~dl1rN z_o8+;urjr!@7S3)-HVdmlt?EjNx*yqHNO@QW3nfsN^1t`B)frHLF_@wzW%0>D|_I6 z1brzhwhFdg35{s!O0+r4EsYhN&v{6MbN1;u>_5*mV%p$5@w8iMu1YM~)l z1`#y#4h~qKUN@9+rtihco>LkStrV*9yFIBp7|bHxi&Cu@hEYSShEm|(oRdMy#*xmIkE*iB}E#QleFZbRb%14Chz-fcoZ_>>GsDi6!x;uUjvS4 z9VE|>BG|X*q#GGYeOW@pnves@Y3-oz(v6|+{-EhbYLFWn)&*mcN5=$-KLgY{!oJKa zt;m6_45SGe7iPk7)US( zeRQU`<(cCFoF7$2#r9~htvw|2x&r&B6S$j ze66sSXiTgXg)DKTJJC9#5hxxpnV^zJG@D=mjv!U5VTHN+lwlup9*8`6Np`VDbK)9B{Za_IX7M+eP@zRPJ^ zj-$DgX*r5)JX#?iY8@o&4zu)-oR)3lA?uEK9VAIi>!55K57}w&gj6Z1Y)7{7kVe)l zJ$6(Z53}nq8xOPhFdGlE?l4OaNoeu@@8;Qf}My$7#4#YH;l2Y`&QCm?-*CG3j7{* zC#2ah?PWJ=YwuY09oc%zib1QPRgSbA8msy)wsaTLa%Af_?2Fjahe&T(5tJq*)^A8_ z5o;`CEr;nXrP(lDhwY)1re5BfjXhYG#QKe-PNNztF?~~8J1San$(AF(ddrRLHxYMaznl4_OthhcS5E8kkxcy+IyI#hn?fSCH5ZKmL6vNVQU1l`pBQXhwY8Z z>O-S+)Ak<8l|n)7J+vQcRv$Z(y@y$PnAL~vgv!z*dnZ&j9!aZ@joW+3(qsKy(Re>p z_8w;GVOAfu6DmuO^>;#x>^)@ZvEhDbZ2R$7vG2qVvZT{^&wnQIdnviTQ z?ie^rY{Qnfy~mEJ50NIsv?8+i*iauL>yFs!BerCdjYm#>NYb9o^dZua6zN0q=ksFw z!t#9CGJQz?eO_b-Z=NqY{d+^77kRtH`@-h)B5xP1m~3BoOMPB;e0|8a@p*~YO)dYs zZYt7;$cJTn*?Z)z56RYq$cA6uF51nG^&#f*Dy_(t=|iLmF|A1c^dY&OjV67FMz?82 zWaqJIeMoFeUxAgBtn9Pxxc zzl`lYA~cJ#mX!UYc0{F_lKrHtK034Via@jXi1>|JeaPO!Y_6p1$hP#*`;hOLS$d?X z9ou`z(nH@nlg*X1k$Q`=u9RPkPJWiXhwSLg#v``+(AUsp@1e1owD*vuM^8dUbdhH7 zQH)>4_8!GZnbn7^E-PWNA$zXa>O-?|Z0R9OIkWW88PW12laHEgJY-o}i5_8AAN}bQ zx!ZfBt+V$?3);&K?LExW!>m5c-b2m&fcRcx{;*4hb%qzBUHtvqa?qHtv<}&L%uC$^u@{Vd zTV(YiFBs{WW2=u5+*=+oBi31Z$m&C0F!FpcOAlFnRKupD6!l_z5AC;(rDV)Hs}Hm8 zkRMC+|Jr-VJ7yfSqr6_s>SHXiJYvQMdyne>wf7j$uVSkYv-gO-V8*cvD%+3P-b21E z6R2GSv|ZHLBS!WfvfPY!QDx~NUzj6U6HK7~Bto{mhgo{0QzN$bXw0vZmL5lw*SEDB z!4)P49ueDnm<5RJJ$6+6hCEr!Yp*ce$?dT}i#%Dxr_$g| zNq?3idym5NXZfq^H{{Qi&dw4XqvikV{=+B~kV%r^#{aNC@DxCn3mp_Z_ zRJ9t~(5ppO@aEg19btL3Wc#z&X&#cRv@a|hX4$>VBQJTThpgmdf0p=65BadjzrQD; zRFJHcw%y=fT$3k@&hW4^JtVi8KZ|@M>`V{yYRR_uFi)2C&-BRMlSO7mm+B!9?)>#uUA zhfedblRffxriZ-X>|~Gi&-Adx7=UkbkhuL^&j%Z4Veco-=kbS0y&b-Ra=RNjwkI(dwE+qDL z*Pd_oSy*_cj2YQ;Y9@;!;q^e`I_dBMxZV?)n( zX*;CLkk7lF=20cg)VX=Pm-w&MmZXB%b}P9?ke5^TnI74m@BOL2zR$b9AD`Qq9oZjy8e38$4DKL4a zhkRa!6SB|rke7;1_ArkXJI!N5&v*H`$a^KfKJW5&$=^l9mD56dnYvK?q_~{-V5&Yvb}ut#Qiqqskgq5Ua|k`X_MZ0 z($kucp1kaIUPn$JJ#o}nXDc7S*i%nFdZxckdgn=Vn+A{BxObkoT<$)4I{QoBeX;&F zr>CAy_E=wMYkqm=qnFb=Ph74iT**!dl$E0S=!v7onp^q!#hP3B=*5~_S({38D}O!H z*(QDT%sWrMc(Kkl+ec3xwergoFE#HxolGQudGpRQPra?{qbDx3q2@MsPrcYjPyTvI zAHBT1^JKFTTYAJg+tTnS<8S7vC$5;Ar=Fc$v>$g^-$&21werz3zdZBNlb2n_e|5Hb z`{)_R+t5?*Kz^H>k6vEhdGcXNYHQ6?FZR*1Gd)ayE8ZAuZp~BgP<|V0Zp}x}&MZoL z=b2xg`RK*oc{S0+nitHL`sfv%(Xlno=tyca#499s<$gwo=`^&%o7)*3+Ut#N-8C<4 z+cP@sbPhYI!))C*emaNQx@#3Qh%u9WF2|PGy8ji==*YRZo7~SW*clyvwR1{0rqjqx zkD;AP?Z;^US?^k>?dZH=c`;;>lHZEX^L@pDRLxv~D)q}s3SM9|)|PQvUQcA~Y* zT%NSfEY<$9thRJ!sdkaoFG>>2QcIf1lH|J~{cF_A??wB>Ix#@I%+hJtxd9cBBy?J- zw3?DPv?DC-q*m4O2_D%x4LhM!d&fG(qarA&BtEB9dy#fRsiX@#xpeoiN?KpDp>s+% zbwa6DQaY7XC!4N+LTMeY=$ulWj;NEB;uA{iv2NEnr8<*G=WWL4lt&MD2-Y;0|vhNOKv z&2PukX~g@U(roNFIt^(v;&V##_H)nP@zh>te2$-17TJF8+2{D>U#FpS{Ni&;^P|&< z&neA5$4|cPg`?B36a4Hnzs)9_8D2>nYC=C8qWY>|@ z*-DO)E+bo8tKHkpJ*PD0Z#u1X%l%eNbGx<9DJ`hqN|MW&$IAc4IUY&Bm6*TDd&T%$ zLH$-XJk2Ag=62)fcqI9o&O_AqXXKaXNa^b|`pQi5`!f2zi@rjW{7#L&1CxCp)v)WT zr~Bw`x=((-FO$4a@_RSy-$!4X(dp6lKlU9OeVIo8W#6aKxu_Yeie$~JvrRKti%8}# zPrfu*j<`Ztap6Dsv@c&&Cay}mb?T%3 zQ@bxIGy#%(wNv7QcF$pJSe+8boy$|Ee^!n1{6f#A-p#lyZ+d?H zcLvX-C)bmuhbPlFJk%mRw^q*5CECBq_g??6=ZK%ro=#7xvnKWIvg6S=J=7+(EpD^5 zxH#n{*U>|CDHWby|5hRVtLSJ{6g4x#^NZf1v?yNszt5x|!+QyJG1_u4XkB_1Gd zEv_Zor6T@Z#Gi}i-=g`qNWQXpYe$o>N+Dx;__U<`QiK#JtBF!bZVuGyKpb7G)smEz z;u=17nW~=(zfFbm;-KoPmHM6CRkjkkll@wLv-+LBO_u`oKbkLO*{Xkx*46L8T)}oiaN9!M(`&@DF z(!I9Ub0yol`OjrNOnqT%J(u-XJzacn>uZLhgb)2Du9s{_GM(%X`>?7k%YIE6c5(It z_r-g!45>pXEeGyHJe(5gp=I4Mf}r!FGe{jwjq<@hq#WLR8I)?rKAjz*^ss9r%M+al zuJ6Uj7gb-0DbG%wYRG>f1FyQVl(%DCr-SKS>q_YX;LgNdNsVF;O4@Cmk~a#i$kEi- z9^zg*8a(uU}sVh+bmi5v?sK~ z7G(l;Is^{Xf%5jQ2X)7QWBA(lmt3#tz96pXzCyQs1b76w&&gK;zaajavsMoW59eAx zelr*BLHrrlE4goiUCcMs`PzL-nRX%Py5qzC<6QSG8uLTJL#g)(*DJa2DEStY1z{FX z)d8L0@opZt2eJ5Pmiw5xmGD3uN4-XrWnon{&z%7FCH{zOmBEjR8*^2j{Ut~>1@&cz z5~MQxOn#r?Cv%4~q%(XOKf}#*Kk&QCt}N*?zO0|_W}qARA?O53@JoI5p*bka-*SGM zn+{H=c7J~yUsdn#PjDxKC%XCIe0LIfk~+?}zpAI&HR(Kh{kHXYpP3K7KZO_&)sGEN~jX>Ep}$3Sb3a5v=Gd z`BKD{{P#R_6<3;cDSrw3-fi5)gtp)%#0$}Cw+362yNI&3U|Xy=E)DwbOS!txT}Jv+ zum$mDw73QOlJB|a<)klj{k+bF@8{*y(vRow@B8^-?6dasvUcs~Wee8N?~OipQJ7&C z@vF<-6{HurYxuW8ZW*yq=c(O5EYz9sS5oH+x0KuvP`cZzD7n&IPi`nUjQd_sYMA>c z&r{W1&DE>ibzJG^&nJDgTSBg%UrgN3U+Wfwy`e*C(EA9Cd^U zxqrLg(G~sf{s8}Q{{jEw{sjNz|EdwBHA-{myPMs$-1!1>=es@p&7}A6H@cfh-^8`M z+>NB}B;Lb!^TmA$zZAgBi@y=l3+;~SPx3NgT0CGaCh?Co}_#DUQDk&VCo)m$;^{ z#S_#ZuI}1VvWssIw(}jp_Wot}3eWtiTOM!^|B8Fn-A-<;dzq4*sMEo}=5C|xHNvZI z4OjN?uT%1xd)?hi+>tsv`8P5Wh{WJ^b5*zJ4_&Z@9N8>+5Uq6!Lzq;;WLb z>Z^g(e07lEBU*WKkajL~m3;QQ`_fPH;O{~rI}34EXU z@2->Y48BMFuIuc(fPW``$93^-!FP$DcIWX#PZL(VXGlK{o=eO(ZurNVuA#5&H4~l8 zJaw{L04{K+fTy@q!BgF7;A!r3_pCdI-#trs#y#iGCifiSS@*m3QF6k@zKMUtJ?ex_d{h6hd&CKw`eyzi_poc``If4005;J7@gIK!|K?VJE8I$O zrCSBAa!-Jc>vdckU*Ff^SNc9z3*VA-OWz7?f<{y5yTv(%iT3^6PjKn~^8oQ`nC@z_ohrZg&rOkGmJV*WCx+=k5pZ=Xxer zWp7fS`k92gne%l5zyjiG;jL6-{?{o4IuT%B`1i?_i;q`B3eZq^ zvai=Uki!Z4!!K*VEj2^bfRn0Uwj#(TsX1|LO5}H?KB1FmYQT>*yR{)y2dh(~ZI~b1 zQr-qxLvz^(!f@tl&8_VSZIL)CQF;J4k{Nq8SK1TWAt_X%v;!sWLCqSYDH+AQr#_)m zIrO#OSzJ4ia>)^z#}5JzWWKLRN;X%um@{?qhy46&yNbRd*D8S(!%Q>ARq#6Fpt6^A zQJL~eVID%(@sf0^P+r-WqYOETa0p|v0;OdsL%Jf2V|-Siv?EU}t&B+Iedt_$<=3~&ZDu&MRqk>Rqq z+Lak}Iyjwcds9}2IcjfEb5$K=l=9q1vsWFY0NL4>IZnqdIP*usK1EMGJ#A|nj(SGj@EV}Kv%HOmk5n&k)jKVggmnK3;mX<=ZH z7OtWG)o_e6xTn?(Ux8mC&6Xj21Ac?NS|-S>|0Mn{aNA5b*bnj7fY%@?3=WdWE?&~b zuHY`r(3-V1m;Me)-dIAd#cnssB@<}=-HjRdH`kRJ_Yd$7p05jY^FV(cHJ5~WXdrV` zXG*T84n*$w!TsoVr$ll{26yO1$?nYL1N|UyC*t0e_d?#vaJ{`|wfe3- zR|X*$vdMRm1e5**WWUi1rs2Sx3=F-7_RhYw;fy728y>2qI73C zrff|Ihk0%=^~Fua=LZwIgM-Koaq^cMLg)YnZVAVPTXG%#NvXb>HH4C()YNRF)!a}* zJ5cM&p@d${KSKj*#W##pZ?FwzvWB&<*U7_I9CA;t^aizJmKX3a=E6Nm?-eAMy`0v4 zdl588iudjnxbfax)!Zq`W$z%-u+C$q&`NIr$l8zjb#K!9AU`w#C2{OS-o9h*NH^vB zzM(hl8{Xx<)YM7Wn#1=Ea)(a6c1T;&>+BcamQHqxNXuS)KSCCmMcMwmn>0}GYJa#} zeNa-Nd?Sm24Ty&m7YFtJ^;LA81*N%aI3W|v1J)qc zc~a8%NP-w0q?^(7v8tp;Q8t=XHLyaE+A49S5!7=~a}YEh1~qi%|6pQyUP+o!-_hID zdH(v+yiV5A7mJz^%Tuc%DC>LqTuCa@``1_1hC$c8NbO4>Xb$R)%NJF&lwY-dm3e<^ z=v(tGsG+aS%VVo0Ii0&DdhSQf5rjDa zEqQY3i);EKvt(3x7amBk)3-(k9dCI;`8~{JXUnt zZ99o;Cx9oAJDK!JtOVy1FQDdpP~UA|K>lRrWZ6TVLXC<@11A%oN;n1iW&yd=sJQ?< znbOnX|GOY*$y(raYE(dKJS9kkrxKsZ^;5xJiO+=Z?+TtujkBm-4m_RsZ1SgrXA+-H z>MSJV-N>Cokd!QskaMYB7CejiJW9_3&mlgK)VWCH-N>C!kaVu^%U=MO$pB?*Z~-;S zBH5oud?Dcir2q5DT|~|E!Sg7+h}ow*>j2plT}+J(@IvBCz>AU1FCtz@or}N=DP71M z)B`#FV(MQ;{$lWA@|QC!^#m7Eb~&kq;3ZsJM7`4BrNmc|zZATb{FTgEyMwz^?@GdD z;ALF9irS^XMZ{N=Uj!~9e+_e3FYrprt|43v_9AyJ{JaFH9l2|%R|-Ag)x?Vl*CJ_O zO=<~qUvIECzga@K8olAQ{OWqHT?;NDzMj-|$fi0MWGP_@xP;Ohm`&2a>!^PNp*XVX z_2iZjZa^x%KFF#|iEre$OF?_>bHshg4MWQlew zHPVpjZX$IXr8gnf^`pk^gqy*egWT7jvfG(q`ypw;*)*sUDS@i<-~VWx*S|i{vNL10S+X-ht%CjrLvy8m(U2ji`;!-roJ!C^7m2J zh?2Xxav#6A8@!9M`-z)?O_-zZ=Wh3a_fU2}`GGv6Btp&KI!Q}Xo#Zl=KlEqK*(FG8w%VT{IZAzgc$i;enW_WVMo?M|+=*)=!px$RHq)57)f-2K8DwOb zK{T%yqogD80hCBO()&ArdJ#C1cogN@`#OMf?SOR##pg$pcVVXYpmxMY2Y!AaC<(zK z`5YKHw&r`s?7jRzV*{tvcMt0$ z0dyliILI>x2abA3kU$Oza*O;xGLZwi6ORj=Q&K`*(%p&22iZfXVbmopJ~=*c#qp%Z zAqSX@Az9;4%Eu!qNQ#gjcx`ZZ;==-0l$0QU@m}N)4}9-%Qj#|$6&yi{bX4MLk}7Hj z=|LxgN)nhrxwKZ|V@HO$UN+X%N%ti_GH@qJ71fX-G^bCbMA|0tt4U$**7pUflI}-5 z30~6=6wf(|xC*HG_oy&yqmiQQDDsU!=@E}244_wPTxZ)i*cay={aF3PYBTm6^aUp5!wBPIX)RQ5ccU*+d{O7nYrsvYfl zwicbmU!y=B*|h83X{@G5#pQ~v#I9MbxHSGv3F^x}U6j{4P47i1*~FIwQ^eW@7Z(>* zrK!-r$s)$ykgRVUx)teFT7lBFNITJr&>S6JU-V4_(CPFAwGTG{olZZrLfTnq3rc6y zl(-%{Ty@YuH4S0#5 z^c-1WZS)}Rz(yfm2Te$ALK8ondkhAp1sqNo3J&$dz+rw*a8JJ%xR>7>+}rO1?&J3b z_x1aM`}zIRn)M>pp8K^6`rHyhi(A4^^hfzgXrHCmElrRnx)`~s{%EdD^^=LG`eTTv z`YFUyDV-Sfn8my9E8t~fucNxO&{s=UC9l#D; zD@(p7Scdp;w1PW3JpAJsve)9-(z&U;{IM*K!PN3FGG^riI&crLxvvvl%60b!2+7;Y| zcqLlfUBKOlS5o_MaI7B#9!$K_A40s+k0V~`#}lvghZ3*!hY_!&_F-Tpe*G!Wn*nB^ zojZYlp9hX4KF=ROd>-Kh{~0={T3{{qSI?#VJa828=j>I~^ym1|Ga3%5AXuntZZ_s|P@E-?l+s8qZChgnDZlS--U+Ne7%ZV5I^NGJj zL%t$t2R}et_yKh;=E^1hJ9OqNf;RCzw2SXiE-mB7?gD?YzsO&}Zx@0K$z4GH!l0G> z*e#;`0<@}cQ}Y^srN7EwL%7;6CcYN!>?`PeUqgfYid)Omp6S>6ll@8H0^+s)6yml1 zRN}S%G~%`XbmF!C4C1xaKEq${m-y?@=F`-v-|9SNWIF zwXZ@?{}L#z{VH_yE5PUY)hhoTZ*UbF_vc8zfS!Ame-Z8bWBv*MxR@!~Q}481aMtet!2L;W6-0|B%-j;!#!-S~J`mbj1%)=RvRi z-N)RMq#y9*-A(>RU(Vg^Zvt;3e+m_2Uv%Mc)!@e6s++~~_vUlRH) z{${@j?ei+ulhQ&jBBk{v_wZ%7Dw+LOe~Z`Zah1<-xA|MaTe+qc<0_v{FS`xAjnZo= zTjihiPy1)Q){szy+;iY_{&{~B_g};sPHQ)<{O$&&`M-%E9k_G%drzC50-xd@p8S(u ztFqhOi`?f0e;2>KiIvr@#DAm4v;J??dfMMf$z80~wAR!5PHR1_`Cj7sv;HN*i(aeQ zRsK3wudDnTuNCVWuQl=-uhqdCul4mB+EE%@OPofmxq6LHbF2B?Dt{d7*z3c3V2z(i zTH2Z$h-Z;J%$p7h4ojn zAiGNo-iUfAR%KT7Wic0eR`O7O--XPQE^M^+gD?v5-DrCwP}qbPh_luojU% z^eD+cusdtc!zdraYEY|6tq!GE zJ_NKg5l0grM9_*WeD;y)R>TuU>P(E zTI-Y}l!dcNvM$fKE)J$qDlg6wUT`3(L; zUY+vxOy|F}7EFWDI@CCorf*rDf{-npf)4;!JwJv_qL2v_%wFtMw+;j@a*0trnH^CPfWVPw!Avir=ZI zw{_pC*5nTQY2BqaE4u1!s<-IP>TT*D^=9=p^(1<;dYgJey;;3YJ-Obj-lke)Z+886 zs##7g)>~HkfBBu-+uZm#wGpcRSRqg{_PrK`^+x1@Ey}A0N(-VlBI?NpT>VF*RX*l6 zPR;9E<8*7kQ+u0wYa5Q%|E+Ple*erlPPgYf-Cn#`qqHJDN?cd;5eF96RnMywdZB#i zcU<1PsduWeBd%4Lyw^r+&T+c^-l?o7Z9X+VykpO*nopDOadYLO&EdB@vRtIK?2hst zO)ip*lr0_AMhY;wNHUV-qPpw7N1MyGjV!c1=FOxm6wjU}5oK&ZhrgmMB*`{2b9;@; z9qoPo_17!*KG$zYP8n!h%$M={GhTV7SX*c%y8Y(Mjmtoiek6}e64J_3G}4(uT6t)M#NcUQKO6sqPyswp~r2blA#aSn;0csV=qwN8B3bDF!?>J>#`$=3)ACD~ZOuIJ1a=1| z66S;QE1XD>H|Rug67eaZ{7qzSBa6~Wq)!J=!xnTBsiTO`1m*W6%NtpU9!2_S;&VXl z6dWCP9F7kA5wiI`n_Y{e*_)Ugb}uG}J&ws?zhiRP^O(%u#X_zg&Gk!(7ovC9KFTqK z%RzZo9YeSRoXnLgiLXH8eI+|$QwUdsvb&r@xE4HyD~pM*MH4@T)KtO}P=49h6U&}* zDk+`DxD=G<&#{DMpgeqzCEUb*&9MQsQ#Oro3n=fGX@uKAdAuwqzCG**EeGYzGM#WI zDDRr-1nsX)2erF&52$^^8DT$hM%YuF!M@@Hl*qsIA>s$aUe!aO?Oo1f2lG*KkFY~G zla%(n9s{*gcpTvgP(CwH5kDDr!kz-rk$JNjbS340!tckb-q z>ol9|FR-sVn;q6U!H0HE@S&ZYr?*QWBp!B{65K4m5 z4Ie-#4UXh`I&o=sjN}C|iXeZ6q_>0oBg#`I9|mz~`7l%jrB9OOetGz>d{nD|mDvvw zCq6LnVC{`mf!pev+1e?o4vGgK6u9p}f$ts^IBp%vYKQ%lI-n$^F@ejD2~yFRAPni4l**G670+QVrI%6s=P@0S_kEmRP6FA3|yzaeGi+J>v*Ff%10MUQj#sC&!Ts) z0-SAG;PXr1__F+-7xcv5r2 z?*3f(*j=P$k3AO-Ctfxelu!7*psXb3z{&0hA0(bbUR-SsCGrn{2ozVF9jr2D!^0jW z{W$S#_?vjyY)a%Y{sd@TZ5CWj{OhT}%bpElky}Z;0v@ZA0cHeSnHj-mW(N7Sl*o2Qz9TE))iX#>54>%9;BC``Ma}eJ zlQSLuCXO~84ky3vH$m~XX#`1m(?Abu%2Nly)O-P9n_O{J_9 zC9*`+sVlM(ol1I2;A&ICx@rm>tSluu+jR;Yt~@xE>lKL0GwX?~9Rmle1j>8m81hxX zDO{;atn+FlSxyczx^z0#DQaczxu7qu^+h0#};^Cu>An-^-W;hid}rOP0-un<8CIA~i8^wTZ!s zU}CT|m9qa8_!EQogk#oIa&cZ7pYAk_uz z3dhjyx~z}8fbxhuf*_7|1bBGZ%|9Ft){V4w^$&-`^#G3`*ORyh{K~kRd_Ba$#MSgQ zHSN6X8_nW$hX#IjXy9qu!|zXtd>jsivke5r^9B+3hi4v2YJA{o;{#{gliU#a*m$_u zP;eN$cRZP+V>V@o;8=Lr5J=7zxUf{opXq z9ZX)HX!2o`@0onl>}vzEM9<7@7G|twVa93}W~^qs(+0dF&05U}jyI_JuMwdpsC9>( z(4f-~>X0^T4bI5m9cy-PN{B$s?oGq&t{xy;d97=*2#pvCO&J^NnOXFE`D+#@*baIY zBccg;t(0^Ylg?4n3Mz}y(uBO`@GLNkURIhC*#J}|olaV(AnpQ{JBC8`gMW^hQvt!WIj5|*8TEDyBbBRd0G9z>+<#JzOxqg9=#W>&~{zF+n|lXuhoP4l1~B-KRIg-?TEJ4se>c3<$QGzFy9!G5vW#o@i zj38>r4oRz7*+NvHR9sKi5!#s(P3#17J9FG9XlIg(dg>LTw(Jn}TzT7>m`#FNn{25~ zf<2cwwdi8cs4~;}*^ai}qn_N(R=0PXMxCuqH=~%SC+&benRYov!L&dVJwZ0zL^1V0 z>!qqMdgr}=u{CusNxE5DPovo^+2^-T|19`DZ3L-5>#5Z9HylUO59ylvPdvus(QPN? z=XZ>o_DTIkceJzm^+vM$Nok%y))E?(r3gA}StCnhO`}Xy(pb|d)5y|T(Cn>ysA`UE`Y`sN&IRE^_o?oNF`0%FqiSc3MDuu;|<9=d2 zq_Fvk&B)2#lHYkbKk`6aC)rOn>`QS!Q4dkuw{+eyeqytBlAk2|iOtv2N9S+8Ru3u2 zypx}PViuv&ZR@)pdE1*M=ba=!iO0V26XO7SkD9eN#!vDuYuVkBJ#cg6x4$w!$xlC# zT%`F^dut{yW%HA5IqxL$Vw@x?rARV~rCG_9+gm;<=)AKf za;)UQY%A7yU6PypZ?Z%|`N_uK>E`y6jq#|h)lYJpck=2dCc%pPZP_|8KXUAj!cUTN zY?7Z8#yc&Hd*;?pHk46g`D9D^Np9<6&7N^@(U{uQdZ(cB$&S)b@|t%FQ>@KS}l_lLWP1u$ISb=lt-KWIwUhalzNc`Rymgndg#vC&}G;%{!Vg3*z6jIqTxQ z`blBD(=EHFX-+f;Nvf0PP@1n~AIM98lB^T=lbkxzoRW#?FZo1T6v-#aev+Gh()fvK zDf7~wfXep1-`?3*|5Y)mJ%W&I>~**Ld;vf-LHKl~)_C&pE_ ze19itkFmY_$=2L2&PzTijCWcX_smZpNY=@FUA*aeCn=xgwl3b*>z%^fFOE-!QJbZ~ zPxcd0O7oD)3gev?hHRW0KiN<>lI$m2vM!G0lm8{Xy~!uCm)ZC^LP_}~*-tk2o$d(p z&c^ylUi>7UcM7`RF};2M?UV{CpA=M%H3?SIY~JTh6^1_6_5sZb#Vi4G+7+1fX42{` zcUht!eJ{WF+}ix4FyxcG>_s=WE{^r~(#!4$b_IFylY-AX#z~UB#a1ZUw!Q`FC;7Eg z%56^BP&bmSlNUe9ZC#w#ezDein``%&Uw#tzlUN_CHf?C9w5j#Z)|6xO>L-QqP7C9n z$v%*m?2)XKS3im8o&55XSkG42^G@7PHl?@U+WUZot!FDd`6PG!NwN>*)lYJpn>JiK zudiXtzdp9G`^m=Slfqo@SU-tZJvwPbBS>0EO9^+h_0GonUb3I$#Vc~_CmYJTF+VXm zRy2usiq&VdUo2aH&4ycMZ=ct^6R$is=9iJz{*In@Yx9#0&tu$FKS|25Cc$b1ZJysy zVaz+Z^??m}MQ(LA>?iBf5L6WgEci1Uu=+-$$N;Om{7E1l%(ST;ok=_kqc&cZp! z_0ERt;#iK|7X2hI`DAm){>Eg^!nkM5D>i0Vke@o6E5~k6`;)kzY->9u^~-Is-q}2v zXUo^c8{;Q&KQXS7`+jlDaOzM?&ONBb=^2fPTXK#;BT(mUwB-DRCZJAXXc@l9q3?7w z=X8daoYPPjtive}ElFj9`eH^)QVqcRobu3;RCTZ+=R4@MhiattbzXhxB*p0*S~(OW zu1a||)}*Z{l|5uD&S+>!X%$i}d4H|ArZLls{Tf}XOl;qKs0?3MsRQ+$wGzao2|B%@ zByoDk>-2_Jtm~B5xecvYwJ5K18(M+N=br+#satCk6tK2vr$Nu9=eL&Hb6Oj%MMf)o za-*0%d0uogS|#aYty`ZmqKVf3mDjb`XkzU(n&@1sm?k>us#SQeEoocs?_E8jap)a7 zr$f}rNe7MXxV_ePYp=E4T5Y|>+HS43o@1@H{$njN%Gmod%GmQ8WwQH{`jt)*$w`^K zXku+QnpoS7COX?An-1B1UL&As7!6Ir$XK5a8eQtSYP+@C+H3SlzH1vb)@mC&)@q}P zwc4m*tu|^{tBo4=zYxcdEg4o){WUD zmF)dmpRx9euf#paT5a^PRvTrk)kYa>wNb`eZIrQA8)d9@Mj3m4ql`{;(+JS{E*b;& z1rTu#YrVLNxQn=sdX3Rg97=quX5dijUr9P>46jd#WUo&4XKS6lUZh?l-f5JvmWrpY z-;1o(Hm0oAMj30hQN~(rl(AMDWvtaknYh))5wqK#v(-jDYrEPkj%?#eW69{*a2-{| z!#7TcR_l0Mc2BoAZgj9#TN|x)MiZk?vd>t1lYGWnZIrQA8)dB3Mwz@?ZM4eS_V|s* z?Tz2K(bHOO^we2Jn#VMw>GYya^@p5vXccCpyy#%0=A$A$HWR_o?uql9{g zjf;)bAun#0lMdN$HtyTj>bO6vCmS_vrZ+kmm8_*k4Wp8^*Jxt2(wV=K`-~ov12>lr z)^6hs+0@uvI!Ibf@^F(iV;(O$<)nkP*V<_9GHRFvY;>@e8m){DI-x8t$vB=jbIuoe z@drs^lE19oxzoh>Lvmc?-5*4Un5$>Y+%X-D2BJo?Kjfr?wc1*$lc4i2A8$T?uvTuG z8e4-7HolDp*)%CUIwap$LHdSqL2Ge-=@Uyjwt~`1An*QQec#%hJ57?~earhpk`BqI z+V(Vw`Gav#n?tOv8>7kA8W%}AB)Qg(K?iH)rm6A2)gP=6Sex=o0m&eeL^SJe37<^% zhwVKsj1JbCf>I-?N6MzmrZr0Oy!pRKhh*zbIum7b*Q~{K(3&jPY$Wwv@jSleZzuUw zIiE$(x$Sw8$@EEiGS(bwUB3P3kiE8zW%#W#FI#)11J#*((jS@T&~%1LI_wzzVQaQp zx>}uD*$S<#biUd-{a>X+yk?bbE_uw}yEN4Dll<$_!P=7lUXi4OW=`ql^?l{SphHr_ zw{5s(eyCv-Xo>dG_8znwq358^HD+iLpB9$ zzhUEau-PFV9mXleEAl^IA#_ zA5FV%(t`DwSi@|ZMNum$Mc6*h`gAB51!B$TruTXC?iB^2gSFJ8E^Db#z}jULu%2U* zl2O2Rbxo5Pk16A?t-=`7ewKpS-|D;1`Wk@tbt)r$>1#dO#jAoGqHhRjFRv;+O>NR% zPqnbmr7s_f6Y6<{TC3@Kgz+~I_2om&INIG8iYLp~M5uM8?9YT+U+XJ}nP3L7zH(R} zEJLhs9X0^V5|_V;yU!l-96LuxnlrK~0J3zaUYsU8~^fjPv_)mdXQ=bb|>yh zsx{byc=zxnjorz$=6e2zsLb=>9(7$ z+IBGV8o|~Uo!+G9((_wO?K!QD)*_n$?8)O@Rz11VO{=q*VxnI4b+k&-N26gw%7`XL zAB_*uKs3?#h-spc5z|B?qgCkVvQx;N0($e!p^@Id>F;yWL3Sr`d#&x(UTeFx+PJ>8 z-CAukfW0r92dqU#8GC-Cj6Hw;DU(-kv9=pctnJoM#1(R*gY7tL1T+gHV0}8s*THOV z)T8yrt-VH{=4q zjwcQ!d*ZxWCl1j#aEK=B#%z*G_I|C;SbLK_$69Ulu~r*ptkp&tYqe3vT5XiERvTrk zbw(L`exr=IxJHD=fH;Ntg+@a)VxhQ-xQn=sc#qLgqsusyMxD4+k`D2^wLWhCE#h6t z_iHV+*4Zc$2W=8KXw!9EC}%ISR@<1eRvTrk)kYa>wNb`eZIrQA8)f2F+qlned(KuH z^{nkNUpB5RUSsr>ZJ9W?B-8cjVDHx2Z9Uz3eKuv1bg=hpZM4=IO^iOtK4a}o@)>Kj zQN~(rl(AMDW%6pZ(JE)#<2P>Y&3@xXPiwW&Gv3F`wo@o59i)HINtxp3Iq6{SwKiJo zj2brYT0b!=S$mU|F`8K0)xXux?Y(PW%&XP*u8oG)!)94F z^XMRHykx%UVC{|HY<5phj$+e+n~adxJ2e`b1Y^{*HX4PEBN>H_p4MukkG0w;W34vI z*dCTqW=rUh>=8CDa`uO5N}QOVkCG%;Ew_brV+TZ;~@ zf`qcUbP!*UxmmW%6!UoXmz;F4_F5aQT}BO)bd3(SV`a25I+!lVC}vbL%4}UaNJ=#s zO*#xoCi&|RqC;{n)BGlGXQRYuAZjH0LrywatF5J`Y&GHJym7ki4_pL5&uB3qd!<)~N#rZKT&&|%}N+iaOFKl8G+S9%0}S3x=k z(;S-4FiD3Uqd%CGl>ZfNQexduCXo+Q$)MGhAE7iUTZ0a!*V#6s!`Ae&9MYbn^sM<= z$z@Ar(hJCc`mat0TbCD<0-~EV*ZT76{}LTG&H?Q0tL@Uo>-10coh_$BypNNA=_SAW z9i|6N@*mTk*{+T0mXn;>c4f4;pk0NWE7xoaXmwj=JJKP)6fiC5=F%a_1GC$%^?bQN zA?-tLdphK|?WQY^b;8mHZ!R57pO;Mm+i%!79kk~s4XSYoG74DFF-gfNAbwMJorXCc zQ^sG#X^jp|g6^eh*td~&u4i{fyBPAyidd&;FGK!VDRiXT(U7fZG2Wqee55zk6WE@# zcE?(i6Y5lpHiS}OYvQ)Vr9jzgwIig1ZHe2H$^hFDcOX>;Y)`xssj^@P;*O-sfjbd* zB2^yjNZgrJ1+Wuw7g80$&cw1!s04N)-kDV8V4+Y6YXn(g$U>nq)(Be5$U>nC)(Dc3 zWT8+MYXn(g$U>nS)(En{kcC2ZtPx~?Aq#~XSR=^(q9?hUSR+WXl7&JotPwQV$U>nu zwh3A<%R-?JHVM)m^dVO_SSZv3rCpJQf>639Sttmlagv3CQ2Iz&CG?^;>Cn( z{WH{m&|k?fs<F$>YoIk~8Q6P<8`hsej&U-{pC(KIbpt zdS!P%S8wpk{Qcl;f2m*SKk_g57yTT68M!%x+5Th7Ui7oLb_u9`%~_N#Bz+0F54r0L z{zLBkJoo~2=laX}^<2Un{|Uc-5q#0VQiM_#5~)zrs)BcNN|H)cnAoz}0#FJ+7<( zSNN6wUVk4gyNUMQ=mlJLW@1VwV!mWOdU*%W(&#C!^pGe(`ZW6IjyGdVB{<;6k z*QOV*rRExcl%M1)xUVVs%Af7e@#li)`t$tJT&du`q5NzAGBwxwv$%4eKa==8|0-p# z_`lQ2mEcOQpGezJ0MGO1gXfc*Px?gvF4tH2*9b3zFZ0XSC|l)E_h)dg*Ga$TPow61 z@N`N}Bb*1$_b2&NiG?Tmll=nXll@!#;tlW(|0ejhe+PVrd%Q(>-Je381>VNZ;r<9e z!8Zxx=rDgc=|lZtpnT_>!r8PpEo+7*ZX8!8_;G$bv2^^+-67;A_}$$1{s+ImpX#T0 z@rfV6AN-GgI3@do#}W_sM-uN!O>vcf`tSXIT$|!M!b^SxfAm>y1a*e{UAQVP^qv2w z-Cxl#5?|>%a5+P&OHy%sc1`hxrDqL)?|CvcUSrf9v<=S_QW^p**+` zIh``m(v9^8`$K#e>UVW}QL8*WIg2Z;39Z~1u1)Y`{8-}7)Dai0OS~ub%7J?kx1oM( zcM!EE_)c8y?1uO~eK|LhR*di?DLvB5x+=?!_6Pcd{Aj`iFWajucL1r8UN%`-u03~Z z3(9`0J^40n6m=)~QG^40Pww2w4fR8~a}Uxz-7r6tbRRzq>`qA!*Vp$Uy*ugdaM8M? z>JfT@z2LBA-5$QLFYEgGJ;1)y9P9?VL9VCY-S_fCNDp>Bd{5HdeGhP$8{&q#ZsdCT zJ-Ir>?MWEscJtjR+12j`?nBvLZXd$l;6QRa`(3!UGohE?kFtH;{@{MDv+v@&`p$%% z!JWC<(RU&>lIz3WNWutr05$gq_a}b!VxCVhxInE7W9*V+&8{e5dn2Y_ve$5MW<8_SH<*R`UozaPUKRnLtf^alHIZ49YC zt|c@s1NI|sNxgo)rEf)i5cS8n7Uasf14$p`n)?={r?{!^ST~(8&CMWpEU0`nU)|U6 z)d)4gn!c8=;;WLH#r2tP7U4KIoAfMKi7VB7C106%4kfc)MRL{rT+(w~1z(YLd0zo6 zN2mpsCqBU)@8-D^-CW`m2`9KRzAV?u5Nd(7d~L9{ujA))pSf;6&o%>`OYQpZFn1_; zIB|V9nz%msBfw1BR-Z5$d8Ik6!?M!X^%<_IZvr;+O~Jap8Q8=(_b0hyxa&!T`7VQh ztK)xg|8(EGE8LatDwpmvC`tE?eIu|A@mX#%zc`C{0AYM%B8t@u-tt&;{EPsYOidtt7&U8P!uiZD`H||^TTlXFK9rym3fA|Uf zC-D;QvlzVGEdm#jE6H6N`jWmB@#$_7_dA_%hP#eBOI!)AH1s714g6_tBG*qNobJAK zU-55W5`K2Yx!%ARC)D?+x+AG|D&aJ@lsjApUgxfNpSv%peFG&+-DjkJ20tfWM#&BC zIrqGK!F@{E&+bNd8D%#Tmbn#_z6iePUIJfoe{)Z|r`*%-QtI63R&jL&xWcUjpK;HE z&r!CD)N}3$>OKuV&6UR~TMa%#{5WOLAblO-CV&%o-UftI!TOY?^OmL6%JlVox~uOq z{U{}q+SIdByI>j zP6bbK3&2x}OY@%V`_itMPXp6<-=(3CbUDAee}Towvr_fm^JQKif&U^d<-9NE9rswk zN@RgM89c|G4W3Kv$e#8 z-v!_1e~J@i75ECZ(xA>O-~+^IXx0 ziStTlh1E`0Sm$Jg6;2i_f~w4|TGeC`sw2~ACDV*h6V&RZ8KE|q#g#h5vR!UQs!>>9 zH3}=MMqy1QyYH;90&5i3WQ~xMw4P~7$OM~_t52L6R&R~y6-~)EW`tyb8QifUB@M!w zuQ9D@O5O!&OKZW#w5thutrQ#6&L-rwc5FLbbKK&>I01*$d+RMmR8 zA~bCVb*q6@c_yug8;2*-Gd2m7uEsMKqf~2X$(*8m7WJhG$Re%x*cj?(kyj58P2?3- zo03|AHjQ`>I`vHJzeZ43*5!3cWkFZj9@Yz`S~ao`4EZD-tiM>_vU2M~$?~{Q*>&wU z)CkXOPp7q5if2(fw9-lOENZD%2gP_6y#Yy{X*`wQk7UK-JeA&?B(f4bmENahhLSv` zs9m32sdc?Te6%!eQx6drNvCC6`Dc++f6>an(YhX&MNZTy2X(db*XbzbcoSOrOIuMM z%4+4Ww^PA24{uG{ii$|KTKP*`QOUIoZ!q2|Y(Y*si>ka6jgji)s`4gs(m@o6sUZr8 z8pT4(iwA0?g_f5H)F>WWUNTUlL}+=bK#h{2<)s5PN`;m)Ymh4)TAl&chXQJOnLv#U z=pYJ+8f6l6C>vT{{=d`^1w@VVq2(0=H7bObtKX`xs^yhI^x-gwR?&J>T8N@` zw`pUF=ukulY2;$JLTzK|3YVP#2AhB07{qdtcNaWV=~JhwS~VqH$5wABy(% zw%`7ycE)8_p#AycVb51zud}bN%DSKgX_f2yn5wC-+38!GaUFeOZF|T~4?Ri+Ont$fABZUJVa& zWf9?WEb`?~@ETX{z+2=2u3SM_gf;w+JlhY1=Yt*pouIrFuB6TtpnN%A30@1YaOEz% zCgcxtJYg=D|F7W5@G{{ZtmJ>-4r_x)#9GSk!4F|A-VyVtFHZ}3ot%I-%5~s%1{2{b{CO9)#y312xKE5rB!Nt^g-~WV9!asvYh^+CS$9LcwuAfAhkN?2c zgq^*-Ok|D!0`~Os4w3Esi&*}j%iYHXUx;zRAL5(f9U`mym;BfM8@xWg4xS%nqM!J` zGSSccXPM|1|1*9SU*q-hRq*`yl6WQF9`cQt;m7(h{tI%eu$G@edOY`+$ANq*4h7|V zAkT`7s7&-e_&&ZThfyM*1^G!F4$6x`UK8n2M)U#R4X2YoB6v+q0Ojo@j8AzD!Q&F+#Gpy2&B|ivX ziDP}^s9aPwY8;g(ZcOS|Y}u!BZ7@C%Q}G3uLTU)!5L564IEK_vd?1d&zW+e%&4-a5 z3LZ_oCpZi|intMX`3-DL+?Ser;KeYBD|-?4^jT4(=r`Yx@NY1SxIy%9|2x=_xPJ7z z{{w75oEiP${{z-1t{45s{|ROi*Ny5$e}aD^BDCWl+G1%h&xdw|zP?U`nQK%hs!Lp( z*hfvG3Q@(VJw6Vju+^8(LwiCytolb%)`8F-FMyGxb_)I!9q|nrfk(gy@|}WTNheC= zAs|nZ&V)|BJ9n)Zb&r}7caNG8cL_cuU8o};1bK{fC3NxKs8=cKMy-lbYy2nL_}$1= zidvCw?RO0o_v#VI@e#USbSS*#6lIK!dO5RIpsWptvovB?l z+L>QeiMo=i2JTGUg;aI0D{*mZrlpFfM@q$PpMtDKJIPEXlu=NYPDGM|z){M33>L zCV~^`K{fFm*&W=Sd)2~&q$k*ueC^;*Qk#-mSntc9qz<7r{s8hMsY|GXy}0~I>JjSt z%-}(iNl86lDpiYKQYuxOeo~6(DVcI9dFi;6e0VUCCO16l!P5?pdJ+$hb|>DSxCPiE zY8mZE+%npiSlBXZ741W44em=^1wV|cesA(^qP;0=9qmQj25b|xjrJrKwvF0F!wBuc zJ&8;6RHag-Qyrmy=~T_AR`h2izm`8EdB6OLP`nSg4?V0h_pjoI^1JrYP(p`j2yut# zPkcfuW9eSm{|CEwd4o8-K>lQ^ZH7ODBed}8+`n`xJvD^->8TFUPT)?w_5Vb>K%@Ue znOKznhkxD$tMO+1#^Y7d4BPRhq$2z*n)(zNfsKiafhn*N@rbBb)H_NeEqnAV;^LsJ z(i;+&0L?3*q0ivo(^DC#LDAqSBQ=<(|08NZjX$FLcr5(Ev()#;L?gJ{G0{lkW1<6y zClmJudq;huqlx=OM-dDAM17-4#KOMO9??W%;T}=H=tx3;a3b*p;{IU&Xh3uXv2Z{% zFgl!AI4~L%9Y#DT`W?TQKd^VNN6)lna@G_T*x!#i{K&i1!?(U$Y144 zO1{9SL!K&MQ6kTdbW&djzm#u4`IgA%JeBygPA5SQk`UfQ+ z;s+vsj@7|0W;N+mcumMlW({FA9wq<4*JK6$2fu;8kz0$0&X3@a)L6+c{{{Yw>+(GL z1^ktIFXQj?1NZ~=UJ2emuTb(b-U9N%dDZ60cM>C`2qN@nAz^jR`B%TG%ie^XGL^HU44dLqO3d&}Kv!glDB4Xj3Xl`^Z zb*_mnCpQr1!L*hQdyTR+>9ef_%4xSHh5#LMc-@*HcAH?6}E$}UByufc?41OnX zf^SlK5B1&y<->6gzxX@eD6a?qlsAHB%CAu5Zmzr!zR$1kCcJ?>cMw-dJ;>DuqKCNSdEj}`gVDpJ9|Er8PUiT9TLm#(Gc8t`#q`F1@8%ByKHCD(%T=aJXg)1bVUmeA5i zLHYD7AuPr_=y`mGdC|FIq-S%i%30>FV-*A zkpI_mw=%jlx-D7}tqgcubbGXll9k{s#H+zo;LXH;qt@-?Ik=pb zzC`#YT1)vF@J8Ynx$;f)GU>I^3#7gUUnG7cx*=K?y+ZlR;4=@8}Le!H`Xa!xe<@GpQB%*GicvZ(o3mv1}(iF zpQD@b_E|u!oA5Te8SkHy$=xh}IclE;o{10M$&{Z&xD~t=&!PFm!rSn;x|DF4`#5?o zdOrGy@B;WT@h8!YU&qC_D#0 zD)|$h4gM7U934YyGU=bAvx0}o{d-PtUorCY9N~GnB^KSI_s4^&@hIgWOBl$>t2Ywg*Gpa&~ z{2Shm-ihS3cQJl?@|>&c-iqFis#0DBe_MH-4i6rv!%52{_s8g`XgJS572n-y_@VAc z=`_4~_anV8VFv!XKT=~J_c{SjU3sI*+jj=OyFW%Fz#pO?qrHQFs(gcI;!W}v|93q9 ze+hUAzm!MPKci;BzoQxHruY#bhbODNiI2mcq$yXM5WbI^2alNM)NIBcViWg$RGquY zKjqEnt*AxtS873>=J=odw(D4%$SyVf5=Z~cS?GKjfi*S7o)&Yc(wLo_o@-th-*5-L*M0)kI$}L9}SMi z_q8{57 z`Ik09=Tif3b7_Iv5!&LFlZhvE7w$9`9E-1W7s4TUP1mFRP=0?Hp4Ih&H}zcdr%S|{zG-~l~$WG@_ej0PnIgH*%`TgUB2f;_kO+)&cii~wGHLm6t z*C5MIMJ}66I0l?X?ncV5M#8uee1&oS2KWZN_a;iN0(XfwbW)H@OxZYDUB{9DY0YrvO@-{K!$ zW^HgB*Crs{9mm>WHt`XJ39R}?@n8EB4ge2eMR+(@j{xTo9|j%{&L#dj(k{lKqz{Wc zW94i3;u_}YxA})PaLu<#ze8BX8gdl(+7CH=6kPTlO5P=`g!`^!hW|Ucm8>d9Q{z4I ze*^zc{649d!1sthAoU{nKJh-t>!ZQZ{AO?D_yfTM$roefdd7_BNs1A^Vih`u>w6LQ zX8k#q+@6HJSjF{VwL1)%ek?ea(xJ%o2ZINbAA(GO2zUs2`PqI2e#tzTM(Rt}bK|(C zuRDDKe!=Y7jr;Wkd$NY^M(7^t`%0gKpEJYi`%1#kn14&TPnn%{j?$-5Z8%GH`0OXl zmc>qh(R)cftR33R~R)GWRyc~IGR))9ggq!;0D#3Ym9*levE5f^Vjz~jt6wT8O`d9z&VdB$1>tGc=1Jk~53sWQZMs96_mM_e1M1GXow1=dE6 ze}VDIY6dy2eCh*wa(V7k4jsjKdQ*DpP}Yv=skyAMr8Aftb)r>m;paN*q!XbXoLy&L zb*8ip*on9t+P|{Mz8UUA@E?qg3aJl~-70YZ^5|I7Q{&KrjHADnW<@^`9L(yz3wLS7 ztkapeYw*<6nO3cs1?8)!GhbRVcgj~uXT-E%_LZ-vPLt91w&Vk<(`WS6EqTi7teU2- zRB9l-q!c=q4ney!5LsI%SA2uCRR+v(JSBSA@@SLGqjk>U$;+WHu1K6t$Ut9Q@&DL+ z?`SKkZQZx3#v*5s46+tciAqpZa?VIbg5;cYmY{-&1O*HzNHXV~m0-?d&WIVsh&jFA zujZxgz0cXF-FNoc_r3cE%~szSz0c`l&RL_X#^_(~-=LR|SYdInICfrQg(bie*ea}a zit^yeOLVv-ZEm80CBc%|xrhdq0!v|M(a!~zq5YbF-MPQHgkLiost%elkvHTcCX|<> zK3JbK)RpIGrzr4$Wf8F}OPhcp>CQ8?6HjFIvbytR?aH&cJN?snqPGXt)cPiA#_#Y= zIyd@;f8}f9ig}50j>XAYr4S5I2ey~TRbifVcFrWMur`Z4~Q zXn!B9*31rDGhgb<(Gu)K+mE&-*pivqw@JSgRTBG_Px1}X(U>T4ZX%E|n1}Xz{@Ral zAwR}Hfj_~nd`HCnXYgn2Z|Q#rC-E!oHyq!>K>UXFHODvb5Wi!6#ql+)!yj0OIKF~) z_!H|(jzjPbe_?&W@gi#H(|KPhrO1ha;QD zE8nv&nFhXvC!+=R9*o+1FmG?-c?;Z6`#PM;epsyow6Af?Lp?sDjvw;7ec@pXvqh#drzx$c54K^k0Ah zGXA}ob;UwflJi(QoI@+lWqolj$87K%+NHc>L8@D$hRtHE<-9fvJePJEz6IcX{>CzT z^TB!ir4_tmCb*pTJbE+06|^hqO$S}Mti(5i{&cMKX%Dl~bxpL2mGR-^Q8>uGu!B#* zmpuroCigV$12A4sgHL0tBljfuB<$b)@L$h>&+yuP^zR3sqg7Mx2^fRtu5&>Dqnsqa) z({Fwb4ABdN@rrwG5L$V$A^EOz? z+u%=kz(3vw%XkOAZ5-QSk8gq<-pOmXfIDcn!hYTX-oZPrg!Q}=yc7E>UcUvr1(tXV z-})}_E?(OL7m>it#IPq<^ZLzjx>u)oGk^Qq|D_jq6YaIUauckwI&xR=ez;iTBi9gp zyN>oA4i!nRAr^8Uy=#cFUC%3bbKFA&?mqnYb6iD~?FL@Ci{ox$Z##(@Jiseg(Z34o zb|M!y6L-6Tcic&Yqw?XRO< zAMYdXrh3k9+Lt)?5xd=o=VgwEi3;z=`yvs%-9&JWv%SLi`w4uRS6|_Hh*mkE(5f=G7#?*o-1-FG zKM{U)8vW@Ui{M?Sr?`kb0Tq^>jmGny32?}=F>2f`gw36q;zBYOzDyN^zDN~>zMwBJ zpl;A1j-Qi59KV2H;yais4jts3U%)lIjrBRlK{$xF>3v4r_-%NEL(wnEJpS(7_){Xq z@4#HV!)ssj$}fp3i3?zo7m)2RpLQNh^=x{*`E=vrPly!13+wSd?I-j;je6nl4WIUB zG9EUxH}C1gF&37zPl{vV(0lS~FId&S^!ss)hHdSa;^=r3jPajIPf#xC3|<)pFFOjR z{$u`?PvBVg(+=lOZ;9yVj=$j(=f<*c3_o}LHJ?8#{*D-b7VpUgTlGB* zK){m)|MiuLfA1Joxi+{FcP=4=@ZduO@KD1NgT-@f-YHCGc20YM z7#_44|5tO4E^%f4wUfadTJ_HIgZcSCtKdBetW4X2_jUnQu&cm(DuM-RtMZOUU=`Z( zcq)K}Xsh9E2v(*23$Eoy*v6k}|DqSgE%{5GLG|s*@&58)VcP2aKMlZYw1fHH!{HCB zcHL*^Nf2a2+T3vt8mgb#h$SJ6a zzYTw>WBePh{23KbmF?Q&>qtgJM=}j+@tzaNgJ^@@7VH4iTLKk4_47pa@YKpH4bOi9 zOn6=Xj}zekYtgF>)TQUE29V$8#b{#4@6LuXcx<<*S*DPI)Hf80R zgQs%3j;TW1gw>|&8&{p8>mFB~qU#~o526adHPV%=YYA&tUCFu%vXa+ztE;1;tdm@~ zx@s!I`pFfLt0}Y$SrHWgT^YI7Qb)Nqp1K_Q(^Xjk)^^4Q>S1Rzj`OGMy}Yddj3T%u z%**Q6=z?qDJgg6mL#S??n^mH*3L}2GSQVR(X524}wIb7Nuo3OaX>{}CG_L6?GGTRo zGEoz?ORIotOR1%$-c}9TRP3%rzc$CQ={FKRC$2L^ z&y{Oe(R1huR`lHZjYQ9R{q+3%y~?KFs0`@nXqb){zgKC#gX75WRf(wbL2X=P&#@FGI~5m z&C@gJNGh0)u>6cU&s0mS{ES7nPdc)5r6XSSOtnkT zo!3L)%1Ag%9n!Pr)e_R{CuS7JoT+M9+b0xEWfaV~am0}u%*|{6 z{r5X&jHLz8apm9fZ#wo=R?7qWef?MdmB0Vr`}}^lBi}Rgo&8pRCVz#@_so3f%=h<~ zVBwkm8t(a$i@u-UU(3(!U-LI}r%bjlRQZ+7@h*{*-dm0Z zkL9%nc&nuMjmrP)zEg+0O~v$nSOu)Y@AWrzeie+}cd}9XD|$bPxR;er?`TFry{q_J zp9HFH=v_~p!^}O?`)I;FQ5C-9IF3*6Hfjr&!IoRA!Cl6Y=$%K!zS4NS^JH<~@_C{{ zTy@UCsd&5#<>DSz3V%tCs+=G1L%BI}aX%}G=NJwmVCg+653lCt-sV%aL>iltz3jxO z@ky7LBM)~y?;J9m9XR{mvGQ@`<<93lMlQ5HBf+PnceQ-n1%3V&<&}1f3h!qHIP!BZ zEQ%kkWbR)D@jLds!xaM6mh%oLquK^+ja`^tYsO^P^mp}F>&`cl$2*SrSq&m!-O?yp zSAN$X=`Y-aUoy}?9jhm=o(|UJ|LRFkUe9MtPwZ|)#{5Nl;SI#ZdeG~gK6}(q?m@p6 zZ6Dr|3-qe$!#lEwlGWxl^^|*oK5_dpV(Ngsct=0pmj~=a+dsAYGnVSougg37bMzq+ z-j#>AkWs4vyhr8bes~9@&$9vPNFB)g@)1o^n{XhnR)FZ%V0uG&^-R!b;n4IcI23y@Q83TN zu=MvI#`_8q8EeElhSMJgI+}-L4qjKvd2<)?E7L1Q?B*n_hWydCzR(Z*zEc9>=l77nhUsVW)t00>v~~&S6G-v^%nAf%_nlWfL9l#_u8}Qt7Ywd<*f9+au&UX^oK`(Znjm57il6%2A!z;S&7IuO%FFIl~Gs&Xq zNY2bKi=|^eGxIE-ULz&aYbrA@Jtn=%GV|4v>9v`e$CgU3=*;}qS+DcmQnb#4>w~3f zoh3UzE<<}{_G}))ky&*)?nXyu+vT}S9hrq!NS~74{hXQCVN7IZ?d~~~naO9TciJ2* z=lR~bT_=go{xd5AHFuA!6sppz&cE!hQa}AY>eD}w&*<;bfI~fge?L|E3-MW8{ixIL zJ}mxD4LKU{o&B8}aWv#JW>!M=Xivi5h)-IVGn3hw*I&;JhZ3M!DtSROPMq(XN8vA8 zD?Qt_cqK1)1=j+n&^G4#I3jBDdLGV=zwxOYr|{hzHOKRcPuo&>)gI23{_>|Ws*a=I z1nac)_iw_OGq)yiWHAoP@S5kMDPz@=vB07K}vKN6q=Q+w;0l&4{yA0l)bx?ZNhVUFo`0f%_9=*1l%5c(&ToW_B!a zE!LWI*%q(ow+*PaehvPj+Q`*u|JB`jd}2C!GJEtK*_X#>Y97w7Pe7lb?#|U!Eg-^mqsMKK1`@cOLiV zaddP9y>h&&d}=r3%JKIpgx!E&tsv;Np5PqoWUhl;^lS1S z_n-B5u9^O}&fA;`*8-ildCk_sE=!xy4X@3)aqj0#`6PZ(XV}iUPvK0(pnBpNHS5zD zt)9Iqw4#w2)vhamYK~V-M|4H3zv)|hr#hCSB3FQOYF7=aTssq0XZ%>sMh;dsM-{|D-XYj>!Qrc@xS|i*U9<#8?He8%WAv(ulO%oJLnqLm3CJ8 z_cLqQ|C68RKgS9Fs|Z2nw+MVr$PGT9pVLq6ne+GX^&{))e{H?@kALHTviAIUuciMd zpXL9a-^F!vHrKi1-Meu%cLCSabvf#Bk2nE;W<8x*TN|~@#PI5JU#ZV^lUZBWPVaTK zd9_Y@mp-zpu7%%g+w1YaUQcIM)2^!jUF+$8TuHmOc0KLgBeS0Ns?V&d|Jh2~nOh!? z+}vkfJ^L)klimwEGOGW64efl``(;PQx%0py>uJ~8|MhzMpRJ_ZaX)q?T_k-P99>WU z$Mv+M^T?{&arw{I(|^B`&aAEftM#;N=p*ZC*Vg}RJ^lA9>CD>t|J-`|Z!77{+WH^Y z)6QBltLlGTPn#+HkE`ncyq?aiq%&*i%zE0eNc0GDzRqaYTv#S2TZ9V<}HxK6=`fqGphJh2kkN)p?ILGc%%k1oRff)WOn&Y|f6u_V);zL~`FHVf&LcC?**4pYiZY- zuBR)cbMrcQYI79h`Cb99`}&>CQ@u8xS{y~06S#|?oMutZ%(3)cPZ#0*9*Zs8Ss0Z4 zJQd$5%rh#{%jP(ZHH+)&LL7xT``LJMIGXT#yPkHR9Cu`K#~epR6VQ5)0{Gm!#eILO zU^fHhZS&)E2Pjub`8e`32emTA{ho|+yL!&c;f&q2b)2rPV_t90Gu~Bl9**{4d*0`n zXvsXFEq0*S3UqDlY_=t{iahw;a-1d4m2;``>6y&181Cfbs;(-BdnXm=|8hsA zs{Hy5IWs<8{H4^va`QVDcE=+24G2=%91^8ek@_gM}1>uA@! zo^MBn>&VQSGNJuv@6Wu`>&^G6w)3Cg|M!2{f6Kq`D%-zr-@okj?PqXp?Wb}r|F?Jk z>wo{h{yhKtzwb)l)xRr$nQ6bD9JPur6*3e88pM;sXhoi=oP3C#%=&6n; z2Xx%zfL_%nG3p&bUg_?vT8aL#=?KbHg=KhA?<@@%`Hmy60MQZT6(BkX_X-dlL0$o( zV=AH*9ZfN<=x9nfyw+n{clUPGB!4%K0v;o-Mpm zqV$WUSHDldmRyfs{XQi{uYRAiqF299TQPI>XZHH`>hH?EKy>!)bG&PGAoi2yrOg+a z?d`Yv5H#D{Z;SR#79k;Rbn=Lz~lHeH$K5*?ByW2^)Vht`9XS7 z^aVNh1;B`3;Y)Jw50Q)S-QW=T6_)pkuTuP)?ES*g*Rgk!Z^-JWCKkI$^ex%`MM3X8 z-%$ln4D`PAJ=FolLGM(DsTU{#dLR3NI)Y90rmGuQ>vE0wj`hs$J$}$SAFDQ?v9HZ0vf(m$y_gP<15sy0z@&hEt z;;G0ePpEgOgvaP!pynbQPbIF0EUGzj@MK4oqg+&ZRK}CT6_tx#l_)ngBYCJE@hOuh z#k|+N@VR5vpj5ObM%XLpl($S;P*vCx`;4enimkB+ zM6DC^585QHlYyXB+HI3I$so{dgLYH`4hF5dZcioPnV@+F9jF8x0$NeskxIa!pt%K| zs08dxz28uB0XnDH1$%hZB{7GfE45=IKx>-2Spx~0G0>e_$Wh=(;uNP-FF6`CGoS}` zlw+cvR923mZ#FMqCP858xU8q;d?-e4cNkvcg#BQY{DfVx;JcCe}9p<;C^D6c<=y47i*S_FfsIh`JznG6O8e?9@+HC)bK9BBV#^=n%|{(mcW!xp|>oWO0DtPpqdfWs9Zh=R8e9&71lGTzgBNz z1~?N-9g3ML&Y}XFDxO63irG{=pBK%cp7=caE2!0(OWp8FJm*oXGmpCA^YN^tQe{3h z!mIG8T(N*E;S2DrqQ+$*6~U|VTo5gy9$00Fv#5()gSDD!nZ;B`uEn#4Dw-u!Vy?rp zmb#fG^p;W=tq#O8YNap2x{xZFv#qbja}o70=TK+80nd7BV$P)&dn29=)aNXxcKc#H zR?1izehHq7shK&CI`K>KT!LnXb?KMkximVT8g=(|UPYbzCalY-vsp#&@< z)S}r8s%)}`n)ofCN+{O0Q}u&=Wn=~VR!~J1tIM~6TdCx+qTGt{ZB*>6PtiK@9nprw z{jRMF-wE!ZqQ!dft3daqwj%XvP}LCYQm+A37O~!(y{V};zn1dD+r4b9alUW0PLozXRkYB(wZ+y$zYV;w)$ zJ=j+6tHN`Aiq_@d8{Lq&OR;tN_kmUhS&M%^=#J0U-#-Al6SQ^q4}$IxZDsC5p!-H! zb!&aQ`$^vpTJf$X%^fLP9ltBOGf}<9I{Mw&?rSZdomnBqfdBRm;Bl&EB*O3YJ{Ix$btf08N30X_rO8T%mFpL`x2paS}H`kztv zbAaAK>Y@)&N&jKu9`GN5*44X%ycPFfVyQM}J^mp)Us45Rh5lD~4pCua<^I=r)E2YG z{~J7CQ(>bHz_)n5p~6NrfbZ~pn`#ZH!gUDyD|8W5?fRN3=)+jwQzi2ab;v*9IZXA) zx2V(ni022YNxnm8<|jNqQt$CSHL*YA`H5PM!)U7fg6C&yIS$kNl?uSa)B^sH{EGhC zkKj*O)^Gfj;?GpW{XsocTIoTJ7*!?6Uv10U^#1mLfKFOEN>N2C>JV%6|6K0<-@UHMQV~Nh6XQ7E2Wr?ofBt=>^LXR3E81Cm_z+i<&YDqfR(9JsuC)Ps$dmrld6U)p&D3~ zilb_wYN!rYqvEJ~s1|B~)u}A15vqsd;^RUMum;}a;PSiuKQiD)G)Yn55RKw69G|&?_3iPRzY6PAXu+$RnT+&Z)hE%0E+Z9?nN5)U^0mSEd}4{SvxRl9%%wzgs_vRC;v_T|?)%d*}vs z!`mf3J#-IU@N}l~tw%ULbj8z!3c8-5N9cy9E7f(qLeJ10Pd6&@dWT-&bUfYTKA|_g z9&z8$C-lHNo%+Onp>ODkrw5gc{X;*rLHl9%j?W1FLvK92sAe1x&Io<*^rnt+U>Fek z;^{*jukqg5DRdCpY;}KzaI1?O9)!WE0A`Ah~q)u*B7#UD9#vU4v4x_@DFdBPUJSN4l z*u&$oVOTso9v8-j5#aE6L_9u>3nRf1@yK{W7#~J~BjZu=#4sU@21muC<4Iv+7z2)` zK67%I6vl$8A5RIB!_+VZdt5vfoQ9?D@w61DhiPF#JR?j8r-$)W#m)>f!bCh1sE(Z# zW`;?4CQ>~+JIo4`@l2v(c21Zbrr?=OmF(OwCrrgNh5FdJ^rpr0!rU+&oJN)G{4g)f z0M#m95ax%O;0!Bc!-B9VEX1A_F9OfPQvdj@6c>lH!kl<*#7spHD^TW!p6kI~J@TzcrSOzYohWLW8Dx4j!4i|tI;5{c^6IN3v zy&C)6cx_li{q!2_bzv>Ns8 zHifl#)=-gsMYuey!?Tv^?akqea3P*`RBLYuo2lvEjJ-a-GHeO!@mS-%HC!1s;8{g6gze!HJQq`CzBB9ym*TmE>hr6@&TttXmC~;cSA|V@ zE~EbZns9Zv9M2}I&94pDPuno^v6asFdw>`c&+!S_z+tCQPCEOft4Yy#U=bqwi*f+=4g0&pUEwO(>@KVF8>bgGob47>iItlJ_D-i{~Y)%_&)9P z;B%lVB`=^%vLD=!{UZGrIFFtu&)fB!-(~b};JBW%zl`3EsV2Zp;EgCioI`svcoSFg zIrMI!y_xIxT*njbEnL6L>D@+qE7$J|dbiVh2323UgTphZ`of(Yp273!-IeMt+zsBv zc~oWL9#D;NRTl0ARSH*A;XcrP0Mt~tA9VKsH5DEJ-C^KD+6O_;qx&g51bQCbRpDXK z^SFWbkyNGO5&92v#?*G$#qkJdOcjXT9J@GUDn;z!*v%PJL1Hh*9?sik^wgN}3~mBd zn(z!>4yq{O8N34A40;APgHLehbjBUeumg5=D*mkVv zIG*KP?ZA4T<2laQ4tg)7njbHMs-dg!@e-&ex>wge&^-?Z)4mMu1Fb241$-GCLi;NC z3OJPZHSkq%813tzdov8DeFId-W(4h<;2S(uN6>qV_D!CuBk8?O`xc{b6uozNx{hM> zjiG&);~hrd7<%vVbREO!8%O&-$9s&w@mTvg-e(j}!1{n=KYYmqdK19|@Ff$$Nuaw2 zOaedV={gCVg#8Im*U8{y>`!^RP64N2f5vllDmWGUbNXt%Pp3Tys`#!V#TVc~o~<+J zeM$QT&(@jr4$*!IPcn<%S3F~9!IR9U_jRfa@eSxM4s&V01>N0Y9_@FayFtvS{T_7x zi3PNW!S8vtE}-`V?O~p+3+eqx`vVNgB6>gZj9mmzau&UxQw@z@z@Onu)YTXHJa9~{5KmYjz5C&wQsF*U*Zi{sBYN}6ItNfYdtev~w0 zMjXSIGy|J6BTisTnuA$j09!CK&IM+{leA=JoEyvqU($-1aUL)?Y)Nb8#Cbt?bZEnz zIA5Z2KtB3;VN2RE8_tg>A8biGdhMADySGGpumf{p_oCjoABy8C23w+zL0s$Z zEsN6hOTm<=!BGZJX_%5;%!$k5DFa*5n>legJY``^RQM>5ryOjF3Lh2ll!qnMq$F$C8esLLMpBBk>v3QW*pkw$U5^J<(JRB+wI+Cc!YY+sE!vt1 ztJGLU|8ig*P%VE}t8rbh4txo#)wmv57runmYJ38yia)E>_(bpoI1^T@aeYuNe^#q; z1F(L=T9sZy+6GBw)~u@RR|Zc?Sgpn<(QgD(!fG`>8P7>DC9GEC#&}MKEvZKDl!P^F zd@6VfYzb@D_%zVHA6Tu%O~BI<)~fWH(l$w0tHw>?Nos=4LHD0v%^I_lLEIdkq;^~@ zZV9%4FR2sPj$45(VN2@9b>h}wtE6>OFRmN6Nlu9Cf%WjVO-_tYh}+_615a`yz51+Q z+a>L3+a(R+`f+=Bk_KSMq+#43?nu7_Oi81-VT?W^cIV`zxKWHwB6gSLWY(@-@N|YJ z`6@a&?uw@iJc&v(-SBjUCsDp zOE376!=Q>Sy$s)ou3brH*%teH0bTWo^G(1UeVoYP{ zkAW%4LyT!0p0O|`d5JNN$1@JLBp)%R33$fCmgGktW+I*muq6eEF-^iV5w@fNy@JG< z+(DrrSco{&6nK(C;52Y5NGvIy4o-tFDMGwy2B>mvQQ}QA!5Oe6#fUV`0%yXO6eq?s z8=M7a@>Enjo&(N?GkF?)__;)Tp9Y_XKbc3I_Zj$-XRzlJ=Y1Bwo6s+!*J|q^r9?wPaBp(qA-hgL4JjusIfj8pW08gS8(#3c-!jpVL?^7bd z?hWuM_!*I4_YC+9+(gXxGx(CvU`{S4+WR@I$>-Qt5a&GzYjO~KGjZN8;7h*1-jZrZ zZNalSxe`|95PZoY_>--$GCSc*c4BXXmAMMOCt#tjx{uCAVPT2rF|7e95iYw?((oyP5VTI2p9g;7QOxlOcgQxfN~(FX$csYNFi^ zx_^KgYIlIQ!By*(2b?Ff;VwNp^#KU~K5o?t&-50{6n) z>=j{49)-DiRD>^4!R#>+&O{xv$3-|3b%mgDp`v@df(N!s)P74o_(+->L9*?=VjOubr4_0^9pRqDtZ@0tKdvtr+p39 z^a41OH)vIXUJYmRChX~I_>wg+CvU-?u7NLEi~Tkn>RR}cb=dE~p00y0xe)tZ*wYK) zOD@8G5BBsT_>%S5st~G(zX4Qpa6fFxM(_am0jTofhu{JDl1rkC;Y%*T{s<2B5}1-p zu|I}Ay%eToQ*;^V&IF&ro^FCK*@XQW{ZC;~FNZVvoc1#q)GOdj4$^)OPqHQ23{$ch z=HyE_)Gcr)Td)topJvK>Pq6CevXsy&q|RAk*Q@R6B48_%oJ@dMYFQ z0;(rBj7*4ML6y~plL_$~s7Bfdav**ORUjKl4#XdznrEZPf%p^rBe7CL9lO!s7&0LK zN}@0ZjDvayG5rXpL7y(ZLPcnfVh%7t-w!}({TzIlzOD3UdkQ+}f*pf-~ zR4Gtlb}~4H3<%Y1r-1o`Y6bb}=YuDiMh-*)Jo#Zt)Fvp1rvPk;DxHP!6oe<4L9cMI zexeAdzVR&bA&P?TzM}d-F|cTuLmosic#=6_iC|Sk3HtCSVIG+f$KZiK3G>N>D2Yej zWC58FrSQO?1hoT7<0%DCvWQHGGI&bElc*X{7Ec*?l1Ah}l*3aNo`f7F(A>oe!HmWV z^vlDOG&WZWPX+iAa+Ja;<}1OLkfRh%HD4)Y)54yF)5ulIp`RTphbH7IRmKB*5}J~$ zR0R+0NoYo{QdK;#C!x7nN_b#TLW_tjB|NYv^s9%KW-7s!kf{_}nW+R@LZ%Wt37JY@ zYciHW`OGK4mXM!gDvStu2Ks;&0$OWldIGcPm9oseoOESGL~9{twQTil#Hb|U~AYCvn<Lh!npIeOMXbcZb|4_fzdI&4V=uxGH^p(p(w@FZ3^^up5< zro^g--gtV!mRQNq2TyOWiljY)R!PC+df%FKkJbsB+XFPe0g_D)g#GRiZOs zOR9ncL$#=CG?4xPc#`T-wP+BYfiNXzOb^C02)3jKy)%PZ)kDBDVN1-C9SRPCEinsw z7&sKR#H`xw!Ccqj^oNDoQ7wA;qaDPV^Yco9Xav6Dp-xnrUcP82G3R`|nm-zeZ$!u& z8F|i&KVLKo&qx@Rx@01b4rca_ravm=iHu0+;hlM-F~RKLF}ylDgr^GdX6!doLo={UG=N-m~a00*!tzCer;d_%QYoBHfRGk6D%g?B!OO8PfE~F4yaIbQ?8s(tGxi$TkuBgB?6vgQz>r)?ZyoJg7?Q2@E~H%t zx3i6&wFg<`JX`bO=ndpN*8v@!R*rbS9is{3&U5Uzj2UHCnYa^6#K>|#mOQk%8BJ;> z=B3TUXlg(&AFUb(4e8~l&Bqg_5k2)r^7Di_iC#h40z6$#rdNozAWxUZ^a|4!;@NTv zJ!_l_^K3blp2{yrlwgYSj48^qr3v@9;6N7|!}FvKJry!Dx|!zdtDEW5#XSD@pidX` z`#XR>U(EaO2>N`n9-tHGbHxgQ&R{JtoBNr{j@EVMa6eNC#)_`W+{;vgvGT_pY4u>N z+cG=4256m;l{ua{bsl`>Jqv6l%CV}ysq*?UVNu; zH0GPM$A2nkC@+{7Z`<^YTfG(YZ|1{mE^q`!d>*U7tOc_w%zWW0p!Z~J$MS>LjJ3k& zJ-Zc17I*r&y^FTQlf(D1&dI8Qozf+6!_p#EgIsHnU`Aij@ zil4{gtHe2OPOmnvSSeS8UPZ=0Gq4%{I{2)qv;N5^qAGP}PFLWl$QZF&&!=Nu&Y{`W z$pEoG zri!YyIU}{``MX<%sKTlWtmN2(UX_m4V(B?9#(7n(Rdv?lc#82Gso-i&e|3JHj`Wyk z(3S*`0UeK}K(9(iVrkH;($QBY9d}-ZrTHx#YniK3O_aDS@Aj{N~S-IdiQa7eN zXV_6wk;BS`%t&dDT`3(QjvXr(nqp_CqrzH9uS!QkWzehA{CjJGyeicJ! zUJReYqPze;A6^Kbz^*(GJ{O)3AH%vl2R<8~3m?J8JPSS(o(&(u(mVq`9i9mXU~irV zp9)Wh58!j20-p>|1-Zv3!6)EQ_e7}TBM4rYxHz^v{7w=<`7 zFNW>lHs+n~!mth8%5&Tu7Pf*{@_cuPg)6}=JooR0(cJ=WW5Jnl;HJZ4UEyyt-{m{DB` z@4EtA&P+>Acsb~dOt$!3@Eqo6vdHIv&fPADT|OIJ#!ODuc^SBrxt)ykQg8`#KAGwz z;9_QkGT4j3vzRH$Y@Y=>qjX<_Mc_i_mvZ0>!3E4X<;E9)^O=vzna>C3F;A6Cp9jum z{wl{l7o5YqR_=WcIGg#docwHX7V}`a`dQ#i=ErjQGr<|mo841k2I%}+=6^cq?Awfh zX`r)ma|Nb?Q<$xrLofxL%q-sAg2~_{=KJOxOafgEn29hEoWQ!_Y%&!lfaA&WS_V5h z9vnyR*V1?i?NYMD#s%5bvEUeT#oVc23^oYmwp`h!wIdH~9K-Y6}$Y+AC^W>NZgM(NF$~_MP2eLYp zksb&RVAUv7JpgnaDUW>y*q`;K{C0n^AL~we?|xuk)}!*_eZfAgQ)SBgfW2A2%AofK zd$F#SUGD|I#@Qo2k6RJe*SdO6|?Mpcd#2PY5DwaU{_Yy^8H=GF08yq z#v^D)#+_M_kBEoUj)*(4QXd`Hy2yl03r}#w1{2TY$}tRlv?R2b%?A z7%;cZz@~xN28?b~FpYM=^fn>CF^z)20G~$QV;UWS89tSK$TVsKV|)sEl8pn=6u4v} zE3xqvIc6d*v2hpqXCg7N@fdk&A~dma8u@A>H?i>>d2Av&v2h*wZ6ZCf@g8|^B0#Zm zAQ^EYLvg)u0@u>#YULq+lf5IMxI*7t!P`vMxVvEeDca9b{ncFfT+1NoYw=_tWc97#O1(qZRDfe3vJcih$obWMV z31XIV#U;Sv#4_cQi-Sft<(P|sMMJS5^IQ}(4k{yE1T;P>Q(YJ|ZYqym2z2+is_@$d zLHBN}5?7|J61)Fe@r*ZBA^wR{lIMXdJf^ym}rmcgPdu+jE1tLhc|B zp9^&VDf#&l6xvc3=p!@O2 zrv3;TYnN^P0d(glS=hs%QF$5K??I#WGPmD>-xAB0(ft;5=UtiJZ$Nh-mH}o@wb-59 zWQM;255X1486N`OA2p8P}b06dBO`2kS=L|**^a6i0?eEWV-zC|AX zebBv!<>%i6WoG2>-vwoCF-v(uP%msK0l=(47;7w3Q$lQT9K$#+Q3SI|g zklf+sHSkrKCHKX76?9)~InP%>cfFPieHq*bLnTML4|Lybxzm?Gci5IyeGzmQZrRos zKzHYsiG3cF6O*BR4wNgCxqTLNS8f^IXF&JhJ^<7EH0bWzAHV=V1-g&5-0+j2?3|qO z6QHb}O!DKPY@Q7BW1uXb%=4q5?4OMEUT_brpiK21P_|GWdp9VHD8Ic6lwFkhegt%n zTN&|(L3v2o@`pf}%9KTa5QM=@+4ToNn9Y=RzaND6OxgJRK>1Hu`g=inQTh9OK>1R6 z{kuVTftT~Y3zS(k7vN4%#?>5wJ3yIOvj%PlWoVy*rMwN4xs|=V6_nAH)w~6i>6Pug z8I%E*1-%KpF}W#aM{fk>ie*i20OgSPz^Yyk$}R7PZM_bZbC!d>7L<#Yp}hu_qn5e7 z8kD=1(Y*?k)0XMo3GPUCrrhriaC@>N<%YL|+u+9KjJJVXlWi%JycN7M*_txUSAtuT zD^uoq3%EJik}}ep!7Gx@DN}s~czJR~%3xm(Zb~js8SYKsWyz+L`MwO4?UxU~6f_G! zp8OK<;^dN)Kff5Knlg$;Om#-vF*pHl#fKdhnuTeah2c1YVe2l=Al%g6onC zQ&xW+X#Rqn|60(z26F+{fUA==X^y~Z&PzwrDHu zwlu>+&htEY&J_u}Bg2KR0GB5#QjT;vXr_kj>A9d89I~qCfM+M?q>Ss?;IicGl!;vi zE+rF0ZgwfSgbWcm+a=)QWJ${9E(XscqePDPEN~H-CUU@wKyy#zh8Kbh$VrhgUI5M~ zS4AdyJ~)pY78&Mw;9PQBWS-}ObEpuOk)8vZ1tU{E8#FscCVLiW){G4IOweo^+3y*k zSvIob(?PRuRz~O1uB4uMTFRnN1*ed$BfCBYG>b>peKI(S>>kfK=Y5}Bu9hhCCOEe0!Nas zB!@W?96=tF+~x>yIQdO-p2NXm$?!xjbQm}^8J5VA4h7ASl06*)nmHw>dM0Q_m0as! z&`c{i*g@bxD%E9Z2ZH8g$=nVA&DE08Jp(j{OQyF!Xl|Dra6hmwIbU+aeZfBDg2@~A z0nHJUPwox&B6m!lxfj@zoHF_6o?s7h&E%zffTxp#CSQFz*gdV`A5A-kJT+_kN70TZ zf6bbIb{q%0q*?$YXh)(Nphm!O+7YM;s2wnjb~yS1oswaZIs?Pd9q5?Ix2ro~R-Jsj zdIV>!eL0=da#DEAsdTq_# z=31uAFlY{D${2&@W~NLsXwGKJFoWiDwjt)ICWbklat3N;nETm^m}5=w_@rjil9=Q1 zpjo1_+{b}tkIG5Z0L?0utEdi|Z7PRR4Kxc?7QHHHcB-656|izrC6NoM4CW-26FHI` zFgwXfR&xMZm&IkwoUUFjy!loXF@F0?k~m8dagK8kx~t zC8|tYCCZ-^NGcPr%@5{F@+UdOar1$BlYEJMa$Yb`k~fiO&I9Hqhg$wQH<&BQoybe) z0?oOWvCaZRl9kA02QW!OVuU{dV{*5R>c?P|#ECKd2>dIK5~KNl#igS^$@Vtl|0nnd zS>Un)e}KP}9WH0^JNO$}fo7M>L;MPwbuL%&3urdFtj5ovS?cnxKY?bi%aQyD zn$<3k@&jnLyBy15@O!e}Wn;bv&5M_@`3^K+UY_S$&^&rspl?9)>*a{P2F<&dP5KHn zA77T~5NMvhywjJU`TGGz;tTK~dHhWAX%iR>^^wZ*tCZoFmpQA%Q67{ntHfahUWP1( zHXAgupTkipWg7}}PD^7~N%?>(DHBiyPi4k{Y=Jt%RrptA5h4!RDcKAEWljOVTrp5a zFySZxmf#gRkbHddqS(24xBD`wGM<~G0N<`CuVtmIMpnvaxEobrJh^G*RkEV&Z2uLn z{`{c-rdNMv_p!_#7w$*qztfVdKM&}?;MJcS^ly0e=K`}pul_91f7Po$fGi;CokrUv z{U%=hF}B~!t3RX19?_G1;BEkV^;b?Yhc=^0c2fGQX7tD!(Laf+UrjPq2~{NYw^yA| zHG9uSeU1j{+3_BrDw*diy$8_C>=}1NkE|><_W;gqU5KRhz>dpFCH! zIJgtgPwxbvXT&>!=ZE_NeR(3;qGH%J(%+u@0k)coMZ6#2t(J06YAw2FULowN=~&6m zmdhH()2<#Um*vy0E-2&Y)2R>g{r(HErX4a=&RZzy(r(G4$^W)R5GU(ayX_o^!=6%{_gI)nX?J9wu z9iMi`f}SIvb`?R-kx#n{px2O3yYirC$){a8(Cf^nom`~MwNJY;pl8abU1`uW<?kz9VFp^^gQEVey?yx)(F8O$H zG?7{NjBiPAEYVwcv1?7wovqyQss`{HX&_FUrK>bduX$)8V5 zTn+c$^cE5~cW3mz^o+GHA}$~J?8bH7-66r2C#gvsKgKq$TZ{O9gzb58UkCR`sY`r2 z;(L{%=Z;;a_;&8vbt2!#`!f)6#gnbwbvO7>{oXHUW*tHv_FdG9KR?wCcoo{Ba;Wa2k(4o^#NG|3-5jT5=9r z@!wd^Lu;}HjJK=M--av#)`4;RiD^4Ijpt7yE1?5NM~*3AN3ave zRIn50sWbmg=PY&M+;ru?nVgw!oR#kUH=A>EI%lE>|IOuW^yEzR;=lQvjozGzKK!?k zv(c9`(T~iJ!Hmsw7_(<{3pU;1V$x>OxwQ>Rf6(y5pHJrj4{wqedi(JFnC_B3#uN2|^vY~}IWaMN?3v(3W zN|8M+z)_g1Lsm6EhdY(Yw&vr=&($Fd>+a<42P`|Ahr?ZgWo>hFxHqtDZY~a4K3U!@ zj$Dkfl>Nn%#TYA(Ei)|3Spk$Wju~MUL0N0ZUJXz-+cD`rO|smMRrha_^KuM3n&ra0 zGHZdd|w`{z31b3T~p_4;#zi;^r?v{l4AFT3$qs#{IsHcgx+l`;|P3oR0fp$*=hPyIYpLiyV;qXUWIN4Y{wDJdO7Y z_ga&`@#=CnE_od}CU@zQ?~!|Q-!6F|uK}+F`5~_j_xX}H@|tn~FZm>|CF{84nOt+Z zYna!AT$sCwc|CX^ai?$jD(^Dx!S40o-KRY$zvW%211Rt1-O63e|O403J{4 z>%!?hfnb_ErFm>vX_(LK^ujPvj=T?nv7qje?d3jRhI|=}7D#0jpw{O``}@2;k{N zG$DYe;VlDJr8QP)oat21tohEwN3uW_WQ>wzrSXze=$l{PlxU0l*_$KYlxT{(-J64N z1Tih!UB1o|nVDmDLL>&QXGhQA;8#=Bl>_ z%~LPNdZ!`Skaw8R-Uc+Iy(oU8ZmJ2H^WGLT>%9mbV{$4B6~vp_1NzAB&+Y`>p4iff zyu<1Q`|YuMCjQmDwE3up>Y4cYdV#&Eit;=32K!Jg<+tqv_N9u-U!)(ERascZ;`-4G z)M52Y63}1#4C=9B(6cgtI;{xw%nhV|YY_EZ?#ny~9E@dT>`ZFE3Sy~iG=!S4LU@cQ z4y9JCFrGqu>S4*yqzInEe9Pge@ynrRbOB+>W8Xtu&rejDoS$y_LaZ#ltx2;mYDE!$=xWom@FQY8g$S zey%(owTvdvt4Ouogrp*URg5N4b$2WtYbYjDjaLbeDn?VN(#yu<{>xLT-pj$0&Dftx zuQIiMQ>l`fMs-Y8&^Xw1D*vj1#=&M#5m+5Gr+p@sf;B+7&RJ9t9!HJgEN~Xy)vFN`=!> z?33xAM9tRQ*(Ye(Cbt72{9wX%*n*AAcxSnhM$5%kV;5p}VhK<_r|sh90cW$k)!J>D+# zJ5zPLA?ZRaeUVqKamVCM)b;kn z(}PI=CVIW82HuqPrr(Qr{}ogN_rcSfsQ+fFg!|&@L-cA@C+D%t@H*`p}aL21P+8N*iNPLU{Kaz2Nld`f`j3=c2e0q1UwUd>nbXq zhl1{pd^MHO!$6s?tLY7=Zu;tE1UMXK>ssokM}i~Zw63GBdK4(fbv^agqrp*dD>qPw zJq8>N!*V0_*<(TZt{dr%qni81WIQO>;=ZU8K)IG%sP>)+%C_7}75F4juH`nW!zY7s zEw@uOJ_Vc%!*U1JS~HaH6w=3aVpsDQsWnG4Q=k-47=_<7)5c$o*NjGqtAgPnPhiuncLd^nni zsH9&AE`X_dm)@r&Skv=m;Xiuy&Wr#GOn@DkP4FJW&)dto0{ z*ZZ(9Mw8)Xs+dWk`=ux~& zh5EbLJJ6|kkIMD;uy>+g@jeyp?_*zuuEl;T-S=Z(P5&x1?++v&P!sa{}b#R(cJii>ikc!Zw7AyKTAHP zj{h_2_isTl{4?tNKgYfm#qiIm`#*?%8;aov(F6Db`*sw=zd$G8OYA#P4F3}SfJ4}K zf$mD|F06N>82%Ob6*>d=pcwu&Is{*1--}}SH|P_5gMA;m;oqWL@GbWJ=!SoXp22t6 z5756K4TQtV_b4BHkK(~YsD~d$5#ccQ!>EVhL9*rKSkET6(;=d

mPv(W_MOyb7&J|t+bE7x24}2-whr)R7@G`hBdKrcBJmD4a z<>(a@#`A_(!B?VJQ5eq`UISl6Upzm(*J<5fxIlOvEQkuun^7Tjao(iw{=$XP%Xtfr z`wJIAN9S!k?k`*veVupkxW8~wdhXczZuB0lI}5vK>-+TGS-3d8{gFGjegN)|K8W18 z^#J%mbRa5;#?Ob~f#}1i6xu%@fgeVtQ3U!Z`k3}3^h`>JkHIo127L;C5`7xEi|c3L zr_pCoITVII2S1BGkIJJwbP)U;)szY-5`6(4jJ^cF0Nu;=5cp+uC^{A$qp!e2=&`t` z>(}5{(brKnx<}uDUq|0WIUzfI3w{%Q8&wWD;XCl#=zH)xunHZmdO1pXNP6xBeb>F4M;ben#r@2HmUiO-w5RHZm_EhD zXj0V+2_A%o(5gBi1Uv~kJoVA6%EA-S=V^eJRW3YP==L;3<0?0vT(tcD>k z{X8iDoP;t~K0NLVd@_nz`SIjKDX1|@S_SarM?vTm6t)WDDS)!jsVHw1!c!2%p;PG< zL8t4~P=tPAw27L8(?U@^MbIp28k&S+c#5KB)GRa&#qktFz0#-$7txKp%zX}Re-9pz;4Np~+sk)=YRvk|@6st~0p{)j< z>L^+DK)LNWJnr_}gI-Tm-Hu23swY?r{kNVdVD&`#sy4cCy->#LgMxlr{8oO0ICX7ZYZEP3=j=|dog}|}ssEx&LOP@V`(GMJl;@UWr*4m>hI36Xo z@z@>E8=Qbb+XU>6=nzgsxoskLC-ey?q3AXVyED3llTmt`jNOI4JN8aN1+FXFhEq_9 zn~FMIH#85Yq8>L5yE|Hl(@>S0j(s{BiPKS=n}OW}?Zg?V(9Oi|iKgOA)ahnn_Xc}` zv%@TO>}I21*9RrW+34HN!S0Jf;~aGF=3@6lxp6Lfc=NFPqv$vfoxJ(jXQ1>rAN{-q z*aN`<;KHx~rM-nH>4)!QiF3$<0!BO#O)GyBsW5Cg9 zVlJmQmUc`$4jc=fheqaja9lhdEzR>#FOHrD<6otvN&^x^h1r3%0LF-bj^<{XLqJg=E-Z|jept|elg6E)_spk4}(A{;np~<=eT#m-(cC=d016QEE zxdRQ?m7x3T?nK-5d~hYYomZjxx{Ch!=y_g^7VHIh+)?)$G-6ldxd8poYtfEfgU7ve zuR~LIEgtvMRr7xx9{19{p58_2PPG@&cNbk%{nz7h7hN^{H{fv>U3L36;&B&U)%!2T z<1V`D^Iw9;U371ycNu!Qx1xA@D@v!E(*0^T;c@?575gv8f;-TFRlVOGY z=lNNbeV@g?pZ$btLPZBLvDB#o#WTA*&#Q) zhW_#E*zAxSUPl-C4QzJE4R4^A{3iBO;FF-5*H42_#q5w9-a>KtZESYP4R52w{0=rd zeo+{Yv~%_z)%O53ygR{|fkV_z2DEkI|Zb9efS^Bz%lI^(UxOzY%{LK0&qm zQ|ve6&%&puS$~H8R{VMR43+E8vEPmlhR;#IK8XEJ{6#p3D)txH?}6`vUxqKx&;AnK z?DykC;Y)P24`J_*zY2%Y+x`msgZS(46*}BsV;_jW316en{SEeq@wed{bi2RB{y6?F ze2bpNZiJYo+ zOLa=0P$H*ly;9xMrfFXcVLlrS_$!pwW>!mO7N0fksX0RO(o&D0L#=JgO zmYNfNsY|JIsU;;Xh|1Kp)TPvll9ohk>dIZ~ysFf-)CM$`Q@2u8sV!)Xr|zY0rFNjP zpL&$Km)hq&OFh6Ily=B_m3o#sP|}|0QN2sON*yWbKvb#T+*Ra#O1(=J+;_?=^S-4% zrAkUF^3L2FovL4{Z>bB|nW$C$OZ`e+L8Dm>DD^K@fkwF+SQ=331{(cpt6(zQUNgH0k`8#HRzWYR(4+C&zc%-vuj zr%fi}*c9%D5K(Okk;tZz4&{<@bvn6WTr#fCAUB+A7!l3ZB{za=IFZg~k{ii2f(U5q zkz0prB$3h9<8Bm@-_|2y+AQuy6A^9}k%1v*Em923z9FtsAsTVwxS-x zdf$qA66=*K>Mf_YuBaECUc90n$$IySdMfMnE9$}AlvLESSubu;kLTuGeZXd<+Pd_P zHiD2|+w&heTRC*O_otlE>N-q$tR+F(~>4mH{Yf`k8X)&9~nZNciaRRmgBXEi1 zu@M-VOB{#oK%1C27Mp?=GI0!+JuPbDXsi$Gk&60KYk^yj{%ps{l_R+gBegvmOkQM1 zZ3i?MQOmd-r9?49ixJU`QA%_(v>1`j7^_4*W0ck*t>ki))+N`OtCI0a#5AxTX;;uu zTA#EEbd)wA?FKqZ82ZjK>zF{kZxv9$S*@&()9d*oxeM{OQmNY)R=r?j5CaN~{GsO68hZ8+4S) zK`|(om0}S0Yv*!RI9BDa7)(x%WO*%yP$EaNd>2D0am31lF^m#Nto#_mDRIQgn=yit z;rWZq??xzmG2%+aK%nUyYblkqe3_lul-2Ohi62^dz+dnYdj|Gj7_$ssg zYs~Uv(L%39{3H4C`5(hLbkU!f=O=*U(M5k|o}UO#Ko`BvJUS&7v}kC;8e8HUzz8pgVWGPe`B7X0ZvC7y~8}eE;s{i z^mpd@e=xtVi#Ga4#COTBm%kf~K=~ds{4CJOlV# zBj)z?^N*R;*Qb0AHr|i9o11^a+`d8nDYNo9|`p2If(+ z1vcNy*$r%&U%@_LOUmbA`Mr{Tz*dxOiRJeySS;pKvK5x!tJw`KpkzKa-)qiynWAnX<-N3e#$hdqn zdxGsKk#SkRj_oPgF298xfss>hiFhk}f*tc)gK<^m{n!aK-l}{cJA=kyy@Nf$E}-#Q z?_^J~D`?zSc}4DGFJL^^yCU9A{@eN8!Dz4dup8J7Gz#p!;hwNNXmr^7*c0pl8a4KQ z_5^!^Mw5MjJ%LOpMwyizWv~1}?)T1RP1&20y|DSprt%$1WMY2M{ZwizVf>4Pf28D4vz&`naRV-%x(ZyX7aEyhbIE8%;aHZ zW={YsGkMu$4#w*HRKz{m6C9fF84khnyBFsNhk?fN-JA1+!$ITweuqQB&ebCs+ zM{$1e{rr2J9Gn6gS@~#A4o(G)xO_}FI-CX?iTT)YOgKG1E*uLUOX(T8JRxULaymBO z5zeFJT&%rvr<_m8d02bpRJnkX^Rf2IwQ?aP7vwUq z82wsSmW#+;h_zR?mWwHo*I5>qODMS*YwvmC+;Ax+mtgHZKb#jXqvTSoy%&V@!{wA* zmR}ey;O>fiQn)Z&LGE&_z4AF+Ny!yhd*yk!ijpg__R9ZoH6>SJ?Ufhe8cO7NmM`L3 zO0LOekuXyDjEM3}T%WHSj3X}Z#0{YF#pR>85j5_&JQX*A#v_-%;%3k|<#RY|T%R*W ze7obu0cjLtINzmx~yL00B z6lhfbJvecEDsRDAD*sJh5jut6 zQ1a{ix7^EAP#G%1??4$0I%A#qUET$|#EanX@)z^2p-XrPd=blU71oKDLHQ86g{trh zC{IH7&@KEPls}AIRP7`2gXnBk_>CF+zvS<0c)?E4+SMTmdZbKSHep9Iu_v9xvznh@(paiZ;-EvmGVt&zi*PS zg_ZIxY`<@juZ@-RZEU}9ldprV@-Nta|3Y4_iaJ<*<*%qqPUh*qW4)|LiOkdgzkfW@E4sw%-r2WHtdCWBHYTqbb+~ zoA1ZiFq?r*vH5<24YN5Yugj;|Cs=(yCEucu-=jqlLIxX5h-@%<2(ZNDktL=GIqWe- zWREF@0#=z)WR~%f2ket|V6dq} zzGG1@)P>omF8NMH{ZJ3an|kCciU!y)D=6tyG{k~gfz7v3Xc#KVRbcIH92$krlvEa7 ziYB3P=t7C?)J?eSS~Lw!LKP?jPqWZ8bOWo3ZbkFZEZmeeC*Qre30rXY;%59EdVuoz zEXi)h-n)c+&*B!m9(sX2vH9ML*F$fx7dGG9@OtP2$`^DyUJvp+^uh9bM?{$)`W1I# z1@2eK2+<#ueMqK=0idizGDr*rWh=S|uZOijS&Z(*>)}4U9b`AUFXH{=2Nm~cavwc_ z*TY~?PNWC%dKdx@#`60U{2hjZawz>2e}`egOFresnv1z(2evniBJ#@Z`~$y7>YwwBvu8YMDY%Xu=Ll4*D~{D!+3 zcr^Srn?X)~>lg8KSeKF+*nD5Y(_tnh@>{=*r^9-b$Z!1$o({7pSr41<;n^$M?BWP~ zqh?b+3#;#u_(sj4WHvV6qp~Bj^(mQy&G#to<`&<}j>O zjX;^ij?IqY{y03OHU{MxJ3c!u+XURW*rYfiJ3iYKl$Y$p?1XGHaMNP5;-u`vY;#Z^ zvy-!vvMs>Pi!F-p;~}+0aS9$%^S~{NdBv&ODcP3AY1ygZsg!P2oSvPQZAHnJ#r)!o z?DT9tC0i8>iXUWWWD6*nUz~|&)PiDR@x$!QY$3S?#iHUz*$=Ztlq|&BdltS?TT`;A zSX`W)os})7Wb0y^;+*X4Y#T}zWAi;XJ15(gl5L9f@Q>OS%kTO4Mr}uKTWr1;;2X6) zCEH>1y@0zNiVN|O+7a9V%kM>aNbLmfh~@X9nr zEZYT}@8x(%eGA+bo9`9)MtvLn7B=52@r~LI{5Ce_j-Jz_6GOD=6geSefAx2Z*0CdW;bNt1;2yMcf;&P zyeBs#zfZAIM59ITTWp-|gU#2-7W;wwV)He+^#0&}*nEvTeE_&WHeaJr9|#_R&DSW^ zMy-}(&`8z?74x`1nEQi3<6IvC9*oV`_}7PmhhXzvfFI>y;Gx)j7iJ5x!@EY4)4-WCtaqbQM)T84`6Q6eL?%oRsdA|tho7RMBFTpUBW zywq}E97~D3)N*1RM~S@Da%CJ(iM-TuXq-UF@z{Lj);N)p6R`Qpxp7h<3&%;6%TX;m z$H|nOgw0phj_*@)GB#h?JWiqH``CPC`8bu5Q?U8U{&5;5r(*M!73B0no{-ZiKMk9& z{2^yhaym9&c}0Fe$r;#u_vP-)Le`NVf-+&sM)D(2hD=#X&H`o5l)dDvLOzqTL3uR~ z&JN1XDGtdF1`nq6+~UyeknCJa&cWJySaxW39wp~u?XAiV%g(3dyu$O>^RfAQ0($|u z^Rf9FHR3`_E+{T4j2dwfB^P4z^^EgkN-o0Y>-py;lw6F>*K^TJDY>NZyi}G^Pfsr+ zcPZ?no~m9>$z|AlJ#D>$lFPCAdJ20bC0Ahc^>p?sO0LA_>#6P4lw4JKmU}gpU(a{1 zA$K)4U(bE7rQ{m8QipJNUE!(l_26|_emyt70lXf|ujk1(f;V9K^`zO8=Nqy7j*Pet z`J0P%vYW8^db+s;ycwIXr=GWf^1FH(dMhaJtEZ&5f%3t6dg^JaJh9^=P9T3rF(H#h zb|R;)cY?CZdOG`KP}W&bZSMkQqxCfRZcvt5PkBA{y&J2qC&Bj=)40F4@PznYO76kt z>zVO=l-!HW*R$mNDY*}uuW{HPpyYmRzQ$*Nkdg-qqqaYY)pvG8OXYp>_#Pf+qW)?QD~e?bX(j0GWkvhWQ3Ny>jwreCPQ-yD|JYAGB?Or9GDY9n@-+p<9PoBmu?7K0)q~w{R zMy5Ti22YlTnHI8IJX14!o==~{ zg6x|-wJEO!YBPI*lIO7|`{qv_N{ol1{p?qiyntodcZ7ajRAv=mMfR(rE}z!nOkTU% zZ;H-YW%e6B{dLhL>&#ufOdDH0KCPSmw$NVkTR!;T^1oqy)?WK}O5VZxT#LJR3$3>Aa{mu3&RT8XqvTyI z&RT8Xr{p~>&RT6hpyYil&RT6hq~rsv&01|gqU1xY%vxCUtDBXl>K_B*THDRjXY~P#s$X zebkbCi5#Phd*34)7HwIrxG%_+qCHHFX5?BmaDlx`Eu3=|j99rK+C<$K(7+?n3$l&0 zMHfy1+mL3_@|5vuVDzd%+ws|Cuq|nqXrt=FGZ|x8UF#U1#F!e*XPu)ps{^IR>@jvv zB_)nMb-5#Y0;uM$prjHUN9u?k4~`?>iMw(93g3h-m*8#1`(x_f-X_XP&|K_&-AIUNAXP@!D+2YsV4Nq0l!x?hy*zMu>z%5opjHzk$d-k|SDDy_Xh--}c> zdxE|TsXX=oeG5_<><)G#tpRo?t>Uf(b|Y2p3b2YaCoSmhuG|IEoF4ANT}JBrk*WT+ zh^;V<7O|yL>&QFOJoc*ZH>S3;P30hI22Ld{x3BW395kcdQ|l{(N`=@R?U zanqOnQ3mUB8NqBMxjI~RX;u3?qsB1B2C?fWwVrpG>=5z+OF{WB0$ zvTCx1v6o%Ts1?=%l|K7bR4PkRPHXUtQXr2?4X&A)d`?hY@okCc=}*CLNc>NK4t_)8 zg?c^szY<^68^P~LJW_84|8nA&dMhY*Z)12cHJKdDpPmBh!hG4QoBpoOs%>)+5J>zYS|W z5}bJ5u+t;8EwISroxvNN^1sOghlL*L)Yqs#=zOZL(E!jLN8*!fle^>4YXNqt+#QF$ z46sh+&Xw))T^IyLzY=^G24@|3n^XQedF(po(GMk;->wsHbINxo?_EXi45-J^aM1a# zb1qL_=iE6@UxtyO^PIj6>wxY%^koz4KB>u&bxjT`>%eYQ1bCv!J8-ku*=)bTL=-EZ$cN~*@b}=@W_i=3Q*~PeAKFD#o zXBXphc_PQ>o?Ymlo)7w3t8RUX!D^2Ez3KkK%< z4=P`)ysg{i2XnrmSHi)dryM)rk8lX+DTn?Dhk~AR=#Ow1csQpV`Xd|;dM>Iz!V#e7 zqWU8o33@J?cxS)GTcPsM%18U{+!N8=@I*Ko^h9)bJQ0ooJrUIt;aJdfQ9Tik13eer z3r~dOLC;0^#uMQL&~wr6;E8Y|=(*^3@kBTY^jvfwJP}R?Jr~sn;rpPcqx<25a0=+@ z=>EKSek$l0=>hm4oCbPEn)rPW%snGL2p@zqK+j0^KKKFXDd{2j9h?bzQmWs<4?#~# z6R+@Lydf&juzbUZ=bn@%9^xZ%Pf8O%@sYVFrFtBk3!cYWsU8RCfu5J@ad1B9d8r-; z7l0RXQmV(ng`g*;dK_E?dQz&d!Ns5_rTQ9N0(xSqufe6D=cW1@Tn2hxs;|N2py#D} z8C(H+UaFVDm7wRPdKp{=dR}^3E)Vo+x#y;*<7;pY=&7k*2G@d~n(AM09q6g4{sq^A zo|@`ka0BS6ss05wf;Vw$dRFACJ}cMGl6b7o&b6~7e(Q61b96~|F8&3#fZAEk!@uBG zP&>={_!ry;YG=6s|AN~=?Jas1+yQEBNqpNE@&2g%+wyQ<%=@GAa?8(sNv^de@pfOD z--ER!@p)gCYi&t9-TaxE|V5j+ZNc}e`}OL8qQ zi8uY0TnkL%Q@=IW3X^!&Z_Bm9B>wf=bFDCmm;H`hD@@{RzcbeglX%>JoNI+i{O)(< z+F|a-gWy?ETg*Lp5IhHJi@6uyf#*SOG56s+@B*0lcJjiMs6AJYfDFHYfK^wIfB*u~BOnJ0th#yx6krLf?(292 zl)xHTb>F}vpaxhItL~e41k?m;VcUHRkAPZWZEU-5;}K9Btb>JDUw}HG7T&+&3s4uV zhlTfV_yW`eweY@!FF<`z3$I=P4Zw!jc=ZBk2x{lm3!o9$7(1`_|Hhzp-uHR)y9ua; z_XE5Dnu1z*Kg0{58Q2^P??-q6GzVMouB!I`7GO(!LO#L%-xAa(Jf@W}$yb zt)ez*t)c?|klIBZ(%MC3s0iBpE5XiqhSV+Uk=8A`gwCNJHvcYQ*U%-@FB*{6FRJhl z(b``HcEdkJYkxPeJN_Zs`MZNX@DI_>-vjK4pNMw;o?tJ$M6~nw0(;{nqMg4t*at5W z?fiYfzIchWC|Z)X;QiFT(Zb&k?2ng7tD-e&t6~7&BCU%yq^*mAc#O0u+LE>@*1}_? zZPAXjZLu~UBkhXzr0t49c#O0!I*_(62IDc(q3B53p%{Y4NXMcRX~$wHJ|mrq3erx+ zF#JX;uEObjA+$g2ONdRh*tek;AlKY zwC9fo$KW@jJ%0>17QYeg`D4Lxc#mk$9|w-ddqjKwcyI#VBii#PfD`c^(VjmMoWxtL zTJk4>`kQIVpA716rX_z0sK1$({HdV+W?J&6f%=X4>#)gZi5d$A&)#)bDHrHvIKLz0S1W&js~8(|W%FsPCE9 z`wc;T&$Qle1nPS>2J8LCpuT5gi*cl53%$?AVZGlJ)B|li*89ysJHEA1nP1;ErL3Fc&NRj^IvV$DoydCvfMmQ_xDkGpIM3_W4~vz0tJK z?+WUTrhWcfpx$WO=f4f=ji!BmH&Aah?en{XdZTTDWquEE&#*_BS8Pc-uh4&WOYHM| zf%>m*g?)Z+Q2*8W*yq0k>c6@G%lvmi{Z|)ancoN0k9852`F%mXShvP9zaOX<>tZbP z`-6J1Zi8k108lShZSn_#da-VYP5vP8V7yqh#vcqGf;X$y_(Q-$@nzK-e<*kuzN}i~ z4+9U!msM;0;h?^(+To7?^<~u#eb>^z#k9l(W(Xh1W>!DcPe+cU1 zs@45RpkA(8-OmE`bUlK1tj`AZbUhNQ`#GSVu18^YKNma?PuK5Zbw3Y0A5Yh#vAUlR zUVx|TG1%KL058PX^;qof7lIez?|K~e_KQG$|X&WLH*>luHOLOh@ZUH^&7#P@RQfBeiL{ze)4DYF7?ge z68z-P!MeT#yaiABbFr@90^W+B{CQZ{Zv}6|PyT%D>bHUV$zOn7{dQ14`3teD-vR0; ze-U=|JHa30Cx0<^^&f+G;V*v)cJ;f!yYZISqJB4cPq;f=hDH4z@ZNAwxEzc6z2JS} z-f%^6CFvE#{dmh?iADW>P;dFGu&6%(>NT$|{XtOA`D?JH{{+-?UMu=fK|SZSqW=uk zb6zX@&p|!swW2=+>N&3!{b5kwdF|(qfcnpCKYtX|e_s3fW8mZX&uc$_9Mpea`}q@~ z{`1<;e*x-0ujTwnP!D=7=TCu8ho^#;^QS@Iwb63^4CuQyTF!q7`mW90Sk9jXedFdH zEa%UGzH@Ugmh&w<@{Hm@7+9r<^0#6@7-uK{|)GSH(JYo3;N!T z*7DzhFNWXow)D?Qe^$K2dpBCkUjknaFY&hY!=w)tukhZD*78@t--lOtXZlgnM+)D& zc@%5;A3)!`c?@g$tDx`SJdU;eHPE+jp1@lENAOwj7sZpLzbKvqpDdmteG*&rbKE^m z`V{u(=ec`^RJ->J+;!m8w=E~RzUkJ1t39W;z8P1+$#5I64Y>*~&)45 zOHj6q&RmsQS5BdugU$J*D`nbOT95`#t($^P`8-gTfz3#@f6H%Dm(%guT=hATm%}6H zVqwY|cw?|J`4aa9XYn;Tcdx-!8*D^r4gOC9umNZ1HMkmqwJEEp7#{!naQ=#s^ZYHG zrgFMElHb`G>`ZZzqq*14;hTbEKEHoNo$_1IL24mV6)M zK-+HuI3Bb`C&u=h$o&M)QCpLr6x(ldY_rMS8%57nl#fbFp)IFj3Ht0#Y(G9iu^p0)Qn|q@h+FE_MjBaSF_l>Qt z-OU(>b;&1Ymj2uu-OwHyz-4qpTYVsxF%IpAwYZFNXfLeIRTHd9sWup69AfYWwZ{yh z2MbU>`=PP-htj_}_c^6ilnkW@l%o-#b|aIHUbI(Q(;N0)ivDV^$ST!_&$K+J{%RI`CH2?n*i-h2{b_%s z{u&c|%096_%VSWB)HwRZ_jt9IX{l~PuXLo;o@xkcQPV!yIQEJbd@c4`4;#`Ooygl? z_Kc&nLF`ZaYc2Yuf)aabAZRakj=g7pO^*FB0Mrk|p0a1`L&uW+rRCGUs~3As-Dj`b zEB2S8(4MkS>`!~8PV6Il%AT~3v^Hv+t;N-cKCwRwE-l=>D7B~TAA8c?NtRE0N*lSo z)+>I$e??ok|KC0j@q7HgMSRk4w%=uYO8-k+XwUe4erx&-%1HVp{@^+S@-vb-k!qMk|8sV#J!D2qy@nnhir)=);x>rzH#*1f9eu7g#BmVs9)3} z_Kn)b`N6(X_p4*<8#RkM#=cRf*njE?wY&Xi->5t6Kl?^4uFgpQJC1+XH1?eRqz0JC zougf^pGn-=PkIJT=B_h+q&A+yo&7W=_LOTJEui*{BP#p9G>`YomiwvC_~g>(tKU~q zPratpt5wvk6{u8JQ6Fp9mOIx2`hzI-dS*2PwfZY7Eok*_eA)jdzj-7t2$}4u~XLy%IlMpp{_f3J*jgg=o(M`))N`&&S!N%{X4o)qFky4 zdVtokCsL+wj&)Us=%Hhsl~$it&mqy6^)2}pR|4I+T7%B=-MO5@yMwNC^i*>; z@4?j^bk)>@3!eZ!Ew75Y@ju$r3a-|=adiZ{Q`U*pwQV=<^n-Dgqy(o`QzhjUQPO)- zKWpBVT6YG!k=onN#ro7aVvN{ei&T;88OM`4RxR%g>zwOMT!5~CoR=MoRn)zTykk@k zCG&oBRs1HI-jpb%Y#M)4N%I#><##E8O63%OyHeUI%BM0rnK~)O)>BlTt+}Y=x984v zs$;^{YGSP$8(UU%)Y#Udqsi769cA{1=;*VDL`S9VE;?H63DHq(--wRxCULymXT#_n zHGq9IH0lX?`_vB&qxNVR^@cq$_%rPy6QEj0J)`b1j=S1OMi;e|+R45c82h3>Ev^Pr ztM#Xq)ok`cKU!J6XUq4cwbg{Sd>>jp@fWHmU9F00QTs|%N?oUlO1Ju0bd*fzS2v)4 zoX7O)Yk-G?BWMQKboy!<E(CQ{<;qCe6E(7DGEG#+$La?TzX(fvt5&pOha#d6RQ=54x~NY zUnPlEa+O;pR>@Uv(~PbBCW%ebyR6(Qu}ON9#3t!YES}CZ>PLAmU6ngl9kq_$@O0%`;`L(&UvKhqoPi*`s_(j?Ba>Xx(*E_=?ZcN{GvK9j7DQC}t9WDK8~ z^k*PVOqfZJIkU~ASM?A|te8pTsTtR$KlLI?44GxEsGd}F&H(i{Qgf;+yTp6FkqYFg zJTKcT&FLF`ncXcrPc|iW#;l4xiicU0DtjHzvnWH#1RiNoZj=l>)uO~G2Y9gY_bOuF z%8_7AyHG2~fHmz*t*ntXt)!;b z$eLP5YowH0M@ONOZ5*3`EhtdTWsPfe|hHMNe`MR{&Z-K>lCm8I6YSl`yMrmaA0 zWKBgijWre3K-R4}SL#!rDr;pwb4BDT$o{R0W3Y;nZlBe@Yixm3`!2BsQtdm(7D%

La*>gB!la^+zUd+O%O!5;3y^lWHEqegHR2r{(E2uy{oI^;>$!AooW^UpWX0>`vW%zywe*?)to3tR zIj2>0T0bk>t|WWVx@qN{R?*h5ymC%!>Hn>tm8~zoes*WKbmc4`vn%Qqt)I&)=XB2N zZqm8W9myB3pPgNouA*0O{p<>&yoz@ByzKfptx8;-EW2`cjgnR{%dVVVOFOoG_ow>G z*|l_9k))N!va4uU&g$^Kw6!Z|N4PxSo-UNvA+A75#@X%#5*xGQf<{Z>bS>lsfdU8%cDcP;PVcJ=P>a$V|b*cFuPCV#anE7w!5rabAe zhMs)523vZ*?V3F8EnLyLUUO~ly3SK>Pd;1|x(0NeFBiF|+^+3i9eT>`dfpYGr`(== zxDIsx<9^2#n0@K$Q08%WO3rBRnY2oH{^2^zwVAsr*J19s)S>RZv`TpX;abccn!7Xi zaIVi>ow*isedheDZ2GRLd%g4)Q`!Z}Jns6;U7_;sj>0*8GUy(|xqb@h4y2M){&9CK zt_|Fkx~p-`;A}GubS?3}{`y~k{cn7IedFr@JlV7CAg%+m{j&o|503f$$Ypr2o8LFv zk94b;--le5&5!v7@h)U?Fa@sfg7Pi}t}K(KDP((+hHMYgknK(yvfW4n5e#+%zeO6d zT}cCPKrG}fh0S<7VKKOQykA6a3(7YK7m#ksCyRL}VgdPi{EY>?Td|n;7B=CN#k?N@ zlO1nfY(p%Djk&f1Hz7BY@-2BgV`EA-GLYll2JUtO=aSCh zZf9_P(%IbY0?r|w#jg(FE~K+4+l9AFW>GQ(%{UHyJeIqm=*_X{W6wjh77j&oYXuyR zo*fO2rgRYb@!()mHS{QO6rXt#F&^~v#d8YLQ<;HLt9q_6k@;mHdUZh5t^K1`^&EtE zX_$Yefa=zMQL8#HO=G6&8`1M5=P}W@L_K#AXRrfy*O&Hyys3rem(ek!1$_gy9q0+4 zZ_2g;wRGfMBbb45%A11n{^i^?Cf@;cz2k17eO!$jifK?g(5*wB)J{x|{I5VAt-R z0kq`u6j;ktORk<^o%jvL#+^w|y3<{kJEQ2X3u@u2s5pRMDJ$54r2BInz}Ps5bibHC zgj~VsFuxTer(hJA_g$R=Nu3YojFP=U-$}{&{JWsf?M1pbVl( zoV#y<-$vSU?i?Kp<5<`lTtwb+vxrgQC~_=p#z=7FI93X9VH_*I@3RRb!x6KX=X}2i z-bhL|p*OeW-f^)l=m>ILq!F`G92eWi5wl?&7dylevq2meJA%ITv2CTjt?!djts}mm^eBdF+&*}j));~lsFz7MUEA1Kdz1)B}$%S z$x-5})OEC@#M3g*r`KX+IASJo=eS5?#Z$4#&biwR+#IRRx!VNX6d8r-6lu+)wC3E6K@N9BR(9fURFuk5NZ`)g??mZXKHDKm z+K$MOZ?lafw*$Sh3r~!X@;;uwUql((o<384M^dw0!CiPx87t_=b;%Ep^&Zas2;_5S zlv3X~9Exo7t|8YjBv?5gg3QlCc4u=pn6WS$d7Tqw**6Z?X5=WpzHzt~sQmiIp)2mG zpmHkv?i6HeYLqY~v`v&vWo&YkA5j@Mu0b25MA=uO^a+|CB~|%tMGqP!p$B&@=qc@5 zYC%umdxD{@jHqp&`m8{u zaeW_>lzIrd%thH;$gf1tFMBDx<_ertd$lVA5* z88WY=yUWV>rUszzdHc5aTKvmt;|;(KDR;jrx3Qx<37mNch2_w+7a$t?%qD_q4eiUyDC=w>_{#e$?J}3` zHTx^=L+!P4f7wTAx0<4Ftf;?|FJAJ(^Mqza{grykKC{0@uU3Dho=UrT`^a7!9{Vfx zR63nmaet+rvUlt+PY&$ArMede5PG@S8!KmZ^xeKir-Nux(jd|rg?l; z)SjYyJ$0q%PEhSBx)GwrHr26x_eR(A$>-d2lhiPh5HoO@?*XKd$o=kC6s zbGv)9zMvZ0y_u-q&S|9ypgXjjs{(XCmUDFm-Gk*^dY-tm((hBxKXqvy^{F0!-OxkM z4({>#qtW&MbFEwhbe|?0i(WhK(+aLSpu4$(s~+f%ui$C`>ZM(9*AN_tgg7S!t_?u< z@LFu#5f?l$fSj|vr@saDbe*kzvN^T&H*23vmP@s(wk<7_T|n)3S|&S#+V9+bx`x(% zr)5 e1c&COd)J@3c&I1hwC3nd|^+ztb|=9@KuPWwITp{Z7l3mO5oY%ca^?+m`zY z=Rx~f>zwtqhqY5$e|uOvrS-~4lb4+5?rEOZhrm8`{b(E5ZUeXmBA0s4CC@wk?)3iE zxbuVDft!+0HxtAWQ^xe6W(CBM zePkV_j@RTVo5s3p@s;_=x{^<0x)I~}%lXJU2A6uuuAYyqlD5=S_KSUFlRPI+Sy$n! z>m!>+lRmO)an~MAkdzFKrjBaNrEXXAG>Uqu5#?%lHBUn>HN5)9w|vy_&QA5Y)bP$7 z&O&PVoVyUexk>zH|4QJS)OG%?>VM^b-*2n``?OE$S$nyD>}mV7M1R`T_N=Q7d;06{ z-<8X!QdE{qWwl|HS7ov$lBlFAlV9}v|I@#JO|*X+xhwA9ue*KL#P9z+{qs%z{xou{ z>(BoT`COg$Pnv)A#@Fh6|G(q>@=eK)lJiaJ|1|Ti8TtHA?_YPko|Nk8RK&GVIq&|i z{FZday%t*Sw7xT4#J!vQOKnl^*W7nDXSQ*t=6T`w8tw zt?6@j7+R6qFrT{H)t1zjdDUI8C-Uu>#oVcQF5jMc%^i%V^BtJqk|kI#QEgoMkZReg zs90H@tYx`Q|0%W6epj(vojhkrrxd3DeRXmrUhbzTl#5bb^34Y zCr8uLxDXll>Nvf^jSr!Y(@$Ja6m^_7bv?z^ar%|(N3M?ZWKPd=b)25{p5CeB^itQ? zULB|Rx*qE4IKA5STvx~G?XE|=I!-TmJ>AuDddKSlA9Wn4-;26IZ+h+eY6@+pOXaV+ zKDS&;t0PN~8|zip=S`@Cb^LeI=hkv{>f%i0sjYov&61~tz0-`Iu-ELJ=JbTUX79A1 zC+szQM}HrC&E9E6PuOerPHTF?UbA=F&=dBWz0;PSu-ELJcJze3X79A8C+szQrvv?A zuh}~tS6Y|4*GbRniCC)iOY(iS=~$@rzFCiJ8mH2p29M*J z30SA}LebZ18fS9j;u-KHQoT>6f%=oo;chAxwK?36j%UuJ<0Z*wUxT2td9aR7t8&%xG{l=b)Y->Ib9$L|e|=D?vR;+VX$9fR%i*SM>AQ3)|k# z-0QKk7d~>kg2tBK3*WhKgT|BAyKZ;T7}9(3%k@%PpT9DIw12d3YC&2+Ui+pNrupDp zo?V2dNU;q1@>h*DJr~rvS1+F1%3RQo2+n&`azwO8)yFb13OyoQ!Qqr`2x{AGK)IF~ zt&xXOwh{52jq7|AF`SPkcJndZ)sAzKQHV<1tKrmUHHiv+ET0o+A;7+L1gFS zC^5qGk<1OXDSawvcYP{oiG3<)p?xyUr#?>-y~=y-lTQXMmQMz4m{0TkQ$(}UD*JTM zLi=>kTKja+a{G&*&GQ#QACg}L?V`URBGzCcN1wo7ydmg0c0G7QFq-s{*)x34)5OEl zqWetHy8BGf()&cvzWPMa;`&6;2Kxk2wuXTtX_0G)es(R9vku04@|WQdVrKs`97-Gg zlJ9wj^22DW$AcEY$AcEd$Ai|c$BEh1AiJ9XdrdfvIMpW;huV16#-=_cyNYt+u8})A zyMkzJMryl`)Tq>_6OH4zapf-Nen~i=h}uiS1;o-`5-uc)_L6WB z@v|T1sq=`xb{?_!9_G3Le1x)7gV6!6AsY6TM7}mE_9>K{8jO8?O?FZ+zTin*Cx;uz zUrDs<>qw1&eO-1-I43(7JU2TJJddc}xA51O5b^B-BKbYUbrE7s{#%G8_YmJ;tn4M(F+@!~mgtJd z5moVaB4#fkI<}FszemZ@L}olLd=E4(=8s?cS!gv zvBYl&ZzpEqUx_h(Kk=jgn%zN!)(!b|1Fl1f%K8&>f8*1?5=Hu6(zki)4kEg4z^8M$ z4g(J(lIX@fxlwqBXZ}Wv>3c|b;_vPpjOP6~5v%VY8sc00?>oXPeELqd3D0j#bk_$- z*XKL-3~%z(oy2&3kkU7ZcYP;uQTHGosxiPH&o-lc)9^YmvF{|_>x0C9-JJM`4~9RJ z|1tPF=@yi19{xl;?H?2S^#SsKB+mAaiO0G8$$VDA|04le~}k$ZPTBK&~x`VcnP~TZLEo1+93pC6SKr<+%ZTwiP&#v>{L3Lj>wqd7^dr z198oV^UN^fFAw0E{#^5kk$n$k4S4n*;%on&IOuhFvNiFM8&E!iYdEo+=Mx*aAOB-M zv6Aca$w;md#NDpX-8!Tri6h*PXZjMCyB=7NQe%?;o%rMLf-{LZY&>FP56>VqX7Oy& z>EMiDH1hX}HvVBmW0o6-{6p|P{_j+tnNA#J;~!7qerhl>`QNiq{KeVC2md>9+-vj8 z>kvbEHcw0@Zu4wnlz+lApK{eEws>t~icg|^axi*%?J$;j&ZEFFq+_|8MC|6VV2LMd zf;EXvK7ss1;+O~i&v-tc1Wux~pezG3o-Mda#PzOAo%@jXB`$U!;$im$dxh>`Pq1g` z5h{uJ-3Dw&T1k}ec3=n6N+NrA06URZh6>WI{IBj{w@?LkC+$K>SFjCfXRr%cNva=_ zJHxUcQ4Q8a`W3m~)W^Lh`4v6mr%Rt)`i#CfDOz35ifh^Lsl|61+b;PZ`+xjP#=|O6 zn*Lw9Tl#zSdHOQHr~EzswUzyz)u~tY_E}loKku1ke^2=vYVq63t(4O?wv2h7)?3?} zr zjI}%HMPUrd6!}D7vT}qJJzY~2mE>iTBCY6&QlC|DdZSqn+7zWlFN%h&d0kASkqx5lW2uJQC+YRL}Aby|vwQufW!f4KbK zw_ZExO>p;bM*j4qB6<1vPGH&lr~F>I{y=&OC7&VRywxLJ|MYTfC;e*6(M|McFUNw? z7s;q5`cX{hG9K0RhH6yFZLgzShFPYIc##%G_T04G`C*|p_0b{eZr4{ux z(bG_`FZ~abS6GU-rmZICG*p&Lh z7+JC8G`2{ZZo+ja z=q_`UxEq(b>tJ@O?$~ASI-FhDrrd8vdK7pRJN3=Djs}lruP&q4k?fX_VNdQ`c*n43 zK9=417F@@J$FoD;g6l+Zb3TE0p8H{>Cxcs%4v*44Jj(X)D9OY5EQ>OCGIAc6_Ai50P4)HjJO(NhS|97aVwH!8}D8mJ!fGz!@nP1*z; zMLH%*h^b2Pm?-0pLf=LkgS?L=Z579BOUAJyYaExl%2BygW3^&5`;JT5LovmP zQyU~N#-;kCGU|^GXpITzlZjD#=o_YnQ5#L-ssi;gp2XE1oX96VNV`Wp*8}v;1NDrk zAM_Ni-k`qEQ@HeUPVf2oeynf%^^YfDqNhO9xCVlr{J=EFm>NX7cGQc5Ku=1Bl8T;) zR8$0d%7{T~f#jjykgN`dciPUPM?;{zPzg)Pu7qUoYxG-<&^*8OE{X8>PO3?Z}yl z9xTB1NK2%?Vd|RD_cTh(YWmnDCf6BpoXj9!hmv*qq%LVK`r7vhd|#q2GN2#rG)9GS z6}99TL$MJ!olmAx+89(1`ff%8WXajN%)0CQbyLV2JAEpj$gpcnb-8z2k+wuO9p#f4 z!EHd#tbG?#=4T_Z8>L;g=Sif#8<^fPQx8@$R@H`TK-Y2O$;wmReiGFlM<kWa^s66k31S0_*S)c45~KFLJ#gio@PJmKrp2FkWA<9pTC!gkbmdg&Nn+4!yg z%*yn@s>n%QTHm*<9Pf@Y-?DOKIo2Fy*2uAD9bMtr6OJ-RmU8VVb7VQz9A%Cy$66X? zUp&5+my<6$zLK1zQTG3foH+WwNYDQ#$VrCOsFRbltXL0!o}47D^7ZMHmFwX(KlZ;4 zeNvVa$B1W!t_qf4Gpw4Ns8jugKAmP9HM#SS-?{v}leEg3(`$}74rl9N^I)3h3QzIJWpisJLubhcO>yuTJ zlhs?tmi0+mnS3+r|K;bM|JHTv*ReKU6&WZ$Q+;kK?_|q5XIXtxea3MPa^7*({O`4n zU6Gumoz7R^Cw`tjv31tuekbkjm+npeo#bTsHH>njJSDB-uCu&KNu${HNm)+PPDd@e z?0G`k@1#?O)!px`Y<-eeCQ8KDbDog)JLy#6-)&#KCg+_M>5AoLU`5X?uTNG-PF7`K zoOZ-Yi~G;7=iKRErBAA_W6NuaHF?%i{?4yMPF7_dTYcVHUY5#oQeBf&pM93!?|j|s z*z!4>vfy6D-&;PPOeei-{(Lg&lXObC{5f0oeepLXCu>sn*4#R_`hKUngnTpWljY}~ zvYaFdS@FEHB7IW*JT{%gx;tL|bL{2UCo7YauVXDy)+hfeIjOEsmY;W4XC1q;^~u+5 z@Ay~lcmA8?WMyaaD_Wl{KkuxLoUF?FWM%8vbYj2icCqrj^JUK2R>dy%RoAg!$Jj4_ z=Qq7RsXjNYOqP~ipZx3R9p{^52V81DU70@d*RE;%>F3Qm{=M?P`0MD?@^`Mud8e!^ zs;^^{u24gywZ*E)$+G&y|EGO%*>n5yzWA%?la<*4zs&mNi_Yy=MW3w9&c3R0^53*R zSv5IPDpn*dOV3ZL`xTVWW7m|uczHQl6@9WIIZ5l-KTrw{&h?eL=W?Swwj3$IV~!s~;VU3W@+x1bL`bv^O$>%)^BKpElt zaMuYm!et-sD!~do`TB6z1?-HkU?1-EA(XFEKkCGJ+%kIYwd7M78~WmDsE+7M5A`K& z3bw!&s<*Z_-R59la-O&JW!CgL$4_50rFqw^#`QI-uO3Q$vBsI#@3AkZ%jSK{pf9T( z^S)Wo7c}p?IC}Fsf+RWBVEt%SIW$l*go7%^Bg39fq_k6j1s<%T=zPVTI^PaK) zdms}^L>1UAu3C(7U~8y@>@n+`YN{N`*uIoaFtt^xZ<3r;-y}b&zDbHweN!u?-<;Yf z{pQp@={KkL(f744ZJ~^PmG;q}wk$u@+d zWydk7^e970Q)=NZu@zGb>z8XJi>2e@pWC6_+e`a7^>1p2)TgPAsdlMesYa<~l1@o2 zliDpwSE_0Cv6kwa+GpANTGLePmDe|on5DH&ZJX+w+BVfUwXJV|sl(J}zHPAj?a=o# zZDdP)emkU^rrIrAucYm&_oF?Sdb8Y*%h#*igZ7;s)Q(O^YtrDUJyY#c%O}}OEuU(d zTG)E4*OzK|-^Tdz?U4FE$wF!mTc)}^tWG;9&(&o(X~VK~E9uqSq1>DHW2#rGi|?A0 zXS>u6zKLRu)#`eom)mgp`R~iOLz4Ye?-jSns<%U$N2|{VNjl2ykm{Y}I<<%GmU{W0 z+acB6_i|Qk9gs9blAJVerWrcT*42AwRrE%AyrdD3Mnh_eFK#hc3C?-yfU+c5(`8#D z^?9myYJ=t5C&|O=wnJ)x>U#3usU6f7WqC+7OSSys*60&wja8S2&u@q7vii-+L-iI& zwOQSENUP#BPbybmygpu5KU9~8W!qutisGMV(ls|C)>I3uO1+o1QuPs$dc6Ajzxt|v z*>U<+`e;>up>NnPU74me%U9Jr>Ko(B+LLMjl6C=UZ&JNA{+-%k&D6Tgrj>ZlY~BB~ zc1YT8)mvlfjFUKq+->?kjH9;9|F){_;A+EJch&XMs_xTQzVCKUs6GbM?3ws*+yl82 zsy_c#Us*d|)2=z~pWRXWPLNznUuQe4YOT{=ChcO<4)OE%hF{bU%hx@fB$Uq(JU#e2 z+hJ8}opv#4|B`kttJ4l?wWL%y!?ld-DbHS#Tr53-Nv8*CpIp5i)TW-3D*H(`k_Je+ zHR;3DO69$wGLv=!E7OzZb*OK|yApRt?c1O3tKF6QR<<+k%Fkg|)(&m?f3ApqpVjqI zThRUR((@>pVQdFa3q9Fz_um|Bg`E3dRTFZFHPkoct${7zyBz9!Tfw-78L6Ygi1CgL zTc9zc%XYPu8ZpLfQDsRU4BORKZNM7Cy<2Ki_irn20rzyhzu-J7{Wg8n%fBtvEB*4+ zO6ixU-<%{T{pK`|(r+%GxA>b^-iGSZ@@a!@xUzOj^-b;5Al5szk2Z{Q`&4fS+rXWy zvXD+#l!Bg73VPArwt8v}{gCZ3>zitt_IIhisitX{m+G5#eW|`_9HsiE(UkfqwNm=c zseRIKPVJL^b7~*$(`%xA^c5(}PxW>v*DTdCz44=zRjlC*Ye&!opwd!~JOYWXC4spVJYJnE~ogXfJN-eXpc1SIdS|iPy)yHFX4b%6tS^D$zM)mRX&vH_| zeVoPB4b?|X8X4+(XSoQr* z8a+x&_4BB&(hmPRd8pn3tGn+@?T~f^NeA1iU!@&ZM;?~WAYW}ntf>}AlKy%7f;5iO z7+h9Ex@sz~|CNR6tNLX}>sRTcRsDs_j>I+7&S{2rUFiD=t{KxVAni@6w?>OP}#7$#q)9lq>&)E7&;Gg}ulR&}l87 zPlpzu@z{*sHvu$m+A};UE?!*cygM?g%6Q84-0NXcV@EJhLFOSTxU` z4a0cu*Z60I8 zJiZNavbK0>}J_$cXi zly3{K!Xu$6QRz10JG&BZ?fI|?xlN<}y(=*Qrx7bqPlm3QuM4w)N_?z$5(4UIs1 zBme6LctecNcqo?;}fgv-&Oo|+D$tj?$Bj4v!*&-33Idgv%y! zn4B1yMo#2^o*yoxT-FmK`knxv$b~S7$Ut%tCGwyc@Avq~Mshr#z)C{NMcHw%e_Raz zhrAq@#K^#xP=0ZCEM=F#HF629cPXuREO;DjE0@ODna5Dt5H^xyNiXA5Ia=gOIvQS* zhA_EwBL6)YNgBfW(uw?0aFR5HN2C+^Z^N3g3%nZNBE26*jtAhqco2S!`(PJ&Fxws8 z4cRw#kN9n#H0I=$oHJYrH%kTA)!@}|uvBne%Y1PZ-`pTO491cMu$vqK9s%1)gX~CH zQ1;@Rb^&FUkiFzSI85%zWHq^$^e*!E!eO!(&)i8aF{IoDOUd4pd>3|-y~7>+uRF7S z$n66A$UdN~D|f)Tl9*TISJ|IWc7cOrKhm8^cL{Q}+zLm>&fM?BbpUt(93(%X{1#YA zZYJH4vIAkhkeTGCl*nLmBkV6f<+?fBflm&C72_cINq$DTTqie>Zco|4@S@y6emmGM z4u*Tqi;N-<&T&f zc_ikNpBa7!L&u9Sa>&%NA>1Z&;rDojoD3bm%Qk`oWp4NlCGvf|M!GTi8Ss~EMEYxf z>1(inyvApnP&Om{3RaO9BCE)+vuWgIo|q1M$uyWvX25Mx7p9C_q+%TyAR54fQ4hw5 z1`+E~T7#=5EF1mdsQ5H%1iMBRxqe{x$m`I9v?}sKRKXL`ll$JJRq#9X2K$m$@pNDK zC2GJgu@-C|17HbR3zSD>02~<8_&tAy1Lb+xQl96x%4^XOPKv}=kvJ-9M3#z%{H~0v z1{@Lt_};F3#{hUTHid&_3g09v%X56oX6DgYqlgu-e zy~XurHUXB6dGKn?gR$go_-&qnW#$<^8_X}Qg6rc`>ehw(!7!eD!hL7%hJam2n@}Qi z%Ez#MR7ReZNqlPohTa)|H=nhbMSq*Njg$CB6OkVPp~_A0{)&ZTu*{e!r3Du+vDu0WK*e|&4)9l zZnhvS1Q)^izU669Zk~+qdy2j3Xt+sgXJf)x za4hU2wX<>XkJRRSj0PstPl%j8A@cPE{@-7)u8xFvrB=2Mj3%|}oqxaYszn`_>{ykC{LSdz;!KZr1 zw1LT_M%ET4lNwn&m`rM9?O`&}$Gaui5^fq|f5SUNv~RddN<3d9GiJEo>+db6M*j58 zi*kO|?yKSox{9@P%dCpkaVyYWV->5&HmqRUa+l(HcZ>GeZmgM`QR3QJ&&?LBPP(zi zX#^Vo+f|QzeC%Hu$tPW- zT=YaPy7QU6+7l`0PF`P8`!J)VHaTOt$pli1d-?2g?hCFS^hpm&ZP6aIw|V`_{r{ej zb?0gY>Mhirs|~34SUb|TJY@vu9$d{pJ|EXSfQ8sJGyXR$^K(9XdHBZ z$5eh@B_;ZEiZXL}t}Yr+J+X%vjauH2j-=MV%rRor{&FOLWBQjlN!oB%<|;|tC9TOP zCX+I^NlW&5WzLhtfzpEf$k_U2j+ACGPIR*vFWMd|bE-69ZzU&&v83%IIam?{i%cvH z+5O1O(ulMHcQUp#B(2Y#OfC&b>v1${i%#*q~4d`TpUyi$(;9OHnibKJ!@2kmqB_#@&8fHI+UjEWj;RMcQf&^ky{Yf5FmQMQya*>9A* zHsocLP$Jb=O6XW5Rh|i@*tqI4#zTfudi=>xu?$9b!VjRqcis7=4H~!*pr)=QzGNk!n|A) z87CFycZ+v{bC2(#L*?fQ@pK~aRK}UhQRL;X2$9huaE^00_n!5HctR97Q96YCgGdAC zNOBVG6uCEKINFm_Dfx(YrhKP(P9@v0%tbPH$nlYp+ny)(jwe*I5NDKn2DLXRf6=;> z?8;f5+#TCS#txa4zQcLnww&=S=GqtBhIDK0_5&A_F5+%~aBI?q+#LYQ<{>l5{*kxj zK+ZZ3;y2Ha+#a$!9mu)pd`hN9t_`)?Y;>Ef95Ozyk3O44nVN5XP6cJ(n9emV>c#az z`95Y)E^mhH8|u!vpv)jWD47Au#nFRnCi-HW58hZp|gHlPd@#JQ^Lt^@Y(D-Iurq$+_gIaGjFV zwyp-c^FLexxW@1uNm&T$#g*=G=3}D;$R{K_lq(>)92$W+xq`dKpsObtBvOQXP7?rX+%Qjv7KlaW8POqYT+h^uY z-|QwKA-%UvCkd$pQc0nc5Lzf95PI*uOB0nYARVL^0qKYWQdJNe0yYFuq$(g*@Vl-V z-f!Q{W^yl2lj)1K#^=b7QyeUeMGMvrCAO0-6g_u;5StMgcXu|&(* z7mT#ZlRO-543g2z$IBPm;@txy)zR_V?= z?&!TIsr_l22XSnx+z+(9+D=QU9Uhcg=x(&ay~wduy1%)5>a0&*DYeQ&Qfst@9>O_W zqkEsr!rDT2O6~CQ)I!|>T~68-x;VAUBf+Cn3$?}C4!5TrMxNUiYCAoe+=b+9m)hh; zsa58E*lnTih~~aU8__oBacrx!71~~HmCEmO?RnRCTj&Ocq)GDpxwpv@|YN<8aLT$aa z$=<0|D#0n++bWgsl=*Fywovr~+i8!~4&5zYt-;o43mr?YZPJ;u@uX~(wo~`2ab=mj zTV+$y%F^zt-W*hZF7F$o%&dg2^xlMLRbMU3>vBLLwZ_i0KX=M-|F%w``f@>gtO2W2 zzEX5St85D@GrNk&Dxh+5L96TlIx|-A`;K6wJ#GswB)u(Px=1b4_Bn~PyX{!}OVr|n zzyk>G4|Oo{{^{7+1lyp;&MA~=jkY}7#&Y)Nj=_% zD@M^;HU~!%4P|TBpIJk2 zZdoR(I<>KCQrhfy;kb&n*9GjtaVuJ5SFkI`d7oZa8*v>-+nu`sIR~xATF|DufogU| zYV!sCK~K_Za0TaN5F@?Z+Tcw7N6K?&a2N9J`wBuIun)iJ-CJ3~eo39KFQu=>r>-ZD z(vNFqlge75JEq$AWX(~XQ3l0+Xl+vJmi9nOKY1@NHBj|XWgzuZd!VeTD*dRt`u<8k z>a_Mi$~x+{&X%kF%9_~bm44KX{mx219l)$VPoiA1M(voaj&0c~WvFXU{Gbfg%GJ%4 zO4<@+_|)FjXm$pTa*nMfW$Hb6#2o<#OmiAe?_+s&v4DO+WJ zq3qM8TqX;VJt*9FM=4C^L~l3!59Bg3o0l2BA(T|^Qva{6O<<%WwEg4Ht-m9|IEH6u{uGChnymCoprb#<$OKm8nHu(RS zTK)3MC1sgeUbRbcww65d{*wle_E{r@f7`o-&;BpHiNzf&9dL zq`55dZIYxsle1zz3t?t?> z%7bWUrEI6uv)J$Kl%zb_arp+vDp96EiEkTP;es@>$w?^D zWr=S!dO>ADrKT;wEjVY-sFbJ1JeZ(Vr{t%6rL4DuPGW0M?)Xdh?`-VAgUh-nmvX^e#bD4n(=R>F&< zWCpTqFoAR)o7`Wr183Va&e#XaAxuQ>h~&yGtidSY4#(A`l<$=GT9fJw%6B;T(g{gH zX|EMQ`A%t1W}_=8KccLt#3&2WkEtn>REcM`V04I&U-X>N~2pR@;mY_?$@06 zXzoH<%S&fj+@0Aynwj{-E_ijj?|!wE>h-JL-wMHY@oJpuT&5$63+8 zyAC;--D^p0_o>z;M|RJrwFR`G9l0y++8j4a-?BNiw2Isr=}rBT&8WRq(o1|Lj zh~r%5wDhg4lTE0l)(PvXTJcoU*5r_Cbx5^6q?#X6iwM-1Nu1TfrV6a$j<=_8ay#kU zu%xj?-I`jORy9Mg&}q#Tx1?5j3oUg7>03Fvll(idm~qU!ImtU(&y2v5t2O7eSQ-h+ z?tLS*l0C@ZJ=rsj29=v`N-bv3R0?}?HnX~|=?SY-e`tx=|Fx!vtV#W(C9(_0XQv*q zHF!35W$UNXS)US;+uenn4N^&MK>qrv&pC&l%~IQtumN^z_DNqQoRh4q#(+u?H>Os* zQ7YAqxPHUbr+t;4vpv0}`q;*xz3sW2`6_5Hcy8+d&P{!umRsYn-%>WYA<32M40EaD za=sl?|Exwa4;#8g{PMiizn+(R*6aDj1gysF2|Ce_&j&japU*Ytf%b6c6ST^e=T*a- zPdn&Lx(i`5T0@tF_BUNqAK5kaon7fa7m#CL+covFU*m4)V`tZu-u7#$$Gw2GHh*2Q z`nw3c5Uaqhq%Hw3hH2F9?R4-o7{_Z83#o;iGX&SdJ6`?448gTi-Ic`q5}YTvl2pO9*MZIx6ltEIfQfWAA_)g8yqu@# zMmUK6<{0kPn^F51`l@bR-#v}Vz0wHZi~Qd7TaMxC+(*!FIjXDc9tj>r-!+HQ?@Vvg ziPUWBNhf-jIpnwtwiXC7%knVphP^7sGpUEG(z~on&f28qE3-AmdgRO?t)8w8fQ*{f z->Yyuo%XT{eZXLHrqP<(f$hkhN?U6Sw&mDyNuHzzoD5E(9`Cb$-TO${k|iAkw9 z=?r$JpSd0E0^UY!Z!;wIDfT==xZ)1ZbfGtq0kTgS4i4koot){CdYcicf3fGWKRTN; zT~cpzbLwsEd1PVarMskl#y&@m(w^rV^e%glzbBz9{Yw|FlBezpIzsMBPG+dP(W5vX z+Rt(cn;Uu+uW3T z8+#rZ(v7&HH@G3OJtG8>W8hgg)=JD2>$skgD`kYBSG+9CBeH>Tdko=4`WFV`!p z$P4zP2bl-Xx7L={NfVh^P<^oVV<63%} zi@-~WYg5l+Ph;QXoQHS~{mED8Ve-s}R=n48Y(H`>eT@B(J&%2ieUH73J&iq(^B-3- zo?OS()oK2tI?aDn)7zX%&X1D15<#V%aRn75rskgCrvEMqGGpEp}V2w*pV{c@i zWA9=Q)S5FVg4pEJ%I$}$I6eVvO{^?-0(b&FO-sV@U@PJlq>cky5;rGxEZBlr+3Z;G zSb7Qd3-u0JWpxTQ4w+q zgyW;Yro@r{ik1aiFY%=oIt=BV9?(NxV(o@G@~ zro|C9TYhK-(uA};k6e&8A%RpoPzIo1&!9buY=+O!mbr0_Y8iwZs}Y3 zmHa+_D`x=xGD1xdf%#kceSFSN>5HtIo>L|&f2(H1ei!FG^SAO{e9rbf zjqlu83?_62R4WEBS@89tGSMK*;(dS>$`uRyb|BAJ*`t_&s`{$Zd*-I=>{aOC+ zzjE&XpL_nwFH_k+tgP?f*!@3R|6|FPd(q~kKdk@HZ{hBx<^Fl;?RUldw-x(7jo*Le z)SvqIZ>;@RmT%?v_g$7fKGwf~W&2v5@?BZ?|LEi6@;(12egBXC{YyzsDa&fc%DYOJ z$}h@L&b*o5fe}(0WF^onbLAb4lwPwnnX__AtxCAAK&5P}G}jz-KC25UXXTXjl>VF- zwACmnJ1eJbsAOFQDpU7N@>S0y3-u)5S-Bc=dox+HZPBIofyhy_Bz=M|IZBH}xHTFC}qj9(^O<)OYlal;3?*->WmhH&tGB_SCoW zy~=N@e5$HEj7MAOt){fS?rl7TOX?3q$>sn9_*1~e#E7!VKlz_ExX?3q$ z>#8Y->W@(OtZnL!>X2$_>TKp&-+U)?%Pq@VXnpgYtcB&4Wi7P6*`9LU%dMwG6` zUDlkefxcsIS(aDUw90i)&8uANtbygaXI)(Wy0;?llG{=FjXwIj*rHaX9a-z@-l%>% z`ml1zeL}f(KD=DYC1PF6eS&?&^7RS1HQ6)tpa-xV>?7)W1KUu37yAf%hF;X8{08=5 zxu3I+*@yja*0FN!%2q0Mb*!>n$|YiZvDYs5)p*j~ylWm)A?E|I16)gM;J%C*b> zY(?AtijF&#b*x;wZ2RR_Zyj6KyHwV(|HQac9&tWN*Y!=1bc`Nzs9|q>wIaNa!>E}pS#b>dgc{krrMaQ0(RvdeH*G4Ek994jwvFhP*(dPq-I-nQ#T@%2j(UN;i6@bon5@*gfO_NTf3qg2P02KH z3RWjtsA#t`9h^n1oy*J*?ChLJ9Yu}gwc1YE%q7O zv}mo-Hd$-5!|FoInT-gYz)qCIM%*oX@vchRab#|4Uvp_wO-VQ5`)X;S<%AYO+E4UN zmK54v^xfy#_TM~?HX~@arDetD$!cQrWHqrBrJ}8tHWu1XYz~g*Xlt(1 zZbJLmZ3)A{`5bRcY82?~^R|Soz^ysIka8Oej!o&I#M@D_J;9#I`a|p3?Fe15B^gR7 zZ_kkyZG(ulFIfZ*C0RTr1gRY<*AdvTj3l))s6}sg%6w<)z(`OVo1HlxgGJ14 z$y#O+u|8|s;%MKzJE1$+o$Gezs$IcF#M(jk1htmg3!4o+M0;V)qWy;cqgq?+M+-Or zT!S! zAiB!MQR%v)LG7)NBIg)t-rC6yLtLAhrj^Dl>@~V^@8b!FB^wTNW>Eu=C#(yu%lR+x z+o_;73}2w`&cOa-da?@97ye{w@N`fgxRa@8v%%?HaWdf~EKSy=o}NNjAJiuM6vBq! zNu1G(cSF$Y^x<_Sz%P>XrDPMM6`kJvr;>99sf|H>&d*4;MQ4yYne>;EEsa)QXA;_j z+DM+s?>5AS#&PGYq^F!kU2H+R88!WE(r1BZrL?w%XA=g3S~;FWP1Y*&?3C7aTdSve z;1{j3w9BZd!j#l31k-IrKpY!L_j)s7)yrM19d~jH@ zQ<~2i?TZ$I3#sj8`^MF{>H=!*Sa2w{`2xZsa4bg`l7B(6K3as;(PC2CAT7f7Nbkgp zshvB4yAxkb?(X1XuFyisYxHcqgu1#nxQO@?>hW&iZX8`g?mpl?4L%su;_*7d@u0p1 z*O9A5=kc7^%IX*_qNY&yuBSFn0kwC!p5v3iFOa7-8LMs*ri0VTyMb^$c5bIqr*5QX zYWa2(*WXAu6oKHr>JQ9N*5lOTo*@(_T^Q#NL$89fYqZi^MCzL+NMkq7b3-NC5b31q`wcu{TWuVrfcawW*aSzvg9lVnG9!mW{Q0uaLNL@*0Pw+S58niPz%Zuf-*yA{$}HHLTARP6_pe89IfTPN(g<3l?;>OCpfm~EvL=&^2-TbsdJyCoY0j%x9fksoG_AJGs^}e ziObSLeK}zyJ!X~@ln|5_Ml${nqI{JNlm$9do3hNXJvrMU5o9@GC`a|>gw^=zz|}e0nba6iX<_-~1SNzlEo7;np|r3fa>Bv1Q?0ZQ0V^ehLz3j6 z9HDH`6+D#qNK#4*Sx)d=rL=G~*Q`uAK?xyC3rYZ5k4`6EmYi@R<9}mv!ik(I%L!h0 zDtG+oa)MI9naBtArG@`iIbr1gmlH--$O&0O$kIYXIY9{_OAA>BSRQGizHCq_GbkZs zX<URrG=%*35PPCD=qAwq=iF2kOY<{CmfpOglnkX*CHhx10G6T zmIRct>q`sD2G^ylv*b{g5VEwOtgD=$v{054PC_;~=|kj%6B+MMtdJA3gpj2LSF9<^ z2`5&_2}%fATBt7}WSOC%oRDRMN@+m}AxjI(CnqQs)Rz;K9F`_09P)vjaL7_6ge*B^ zIYD`#F=^q$L=P*KPjKzeGOMtnazZ7aFpBXavkLX) z1U+Ojt5D_>GLw*5h0pl}y)e|EWD*9Vg_Ze)Ei3qhZ5Zn_t5B8=vYfCqKA|x=p)1mW zb2(*cp*uZfSwhIt!ivfXO0s1+p^{HnL~kiyAfKSrka>gMNmX(SJ;>K5r%q1jPP#ia zJ+lh+<%FK~_=KLw*$w%G!|B!P%L$ob$b3RiWEoineY7&GkmUrqhWc{C%Hk6;laN`3 zhI~S14;r!xE0<4@H)xDi$n3#Kl@nwP&L-6H30qX~2@9yvWjxX+23dvrOhV=smdz(*389izXpB!-xpKm8l#P7CZjAhud_s>8_=Fxv z2t5*?kfnvpC&(=Z1(!%F*!t&WCG$toxCZSGR zsLv<-FW4t!YlMbY3XRz(Xqk|$6qaV6@X5&u4eb*?nw(Iccc|kNvb2!pgi1c4K8H|g zpHSu*8qPTUZ`db%7WjnEf}D`85h^8wEIDYIP+v|^Drjh{pk=~;N=}efs4pj!S%nqh z6DsW!ZFCToY2rRq0VlhzMPQl6B=U@D(w?0WrIBXP-&k~ zX_>Hc`Gl1#Cp5+iOKDr5`BY}vRqedf~mgh4P0P0@(If~@31U6p-vts&p|9X`|wfi7%Q2CY@bk;7PMg0wlUi-mhBj| zRalZwsIyO48lSLq`-GJ%CoJ2Ju}&%|+ceh649h1cXB?L1?@*sr zXec3+{T(Xj9V+F7N`Hrj5<;Gp(CeY>*N`QIY^#tZggPsQ#`%Og2_gGF)c1GDd_tYH z@KO1M#{3;V&b&kB6IQMrV|{;zPeV>vHlL8Cf=aK4<@a~U_6Z+NPN?J)GLw*5h2`NB zK5KrF4dsO8;S>HB<{cW&ID9gGk;}^`)LABEZlQ7egk}3hE{}ae9g~o)6qe85p`m@k z|AJrS=X^p#zsTj06S7BS<-9|kcVwMkaMPX&FpOF0` zvlnDT@5t;InLQ$xy?%l|k}KOUvU1*G*>;S2I^;!!NRO<%B%% z@ae3duyiKjS#Jt1*4L;$& zOHNo>>oJz)1lM4!^m?fDclhMwgv#|8mw(=<2%(bb!~{#UHq{7Kj`<~110>nD`08OwHzjjh|< zn0-Q7PN-XtvC@vQ(%+#mPlw9&7%MFpKk0Rwvjt4rWW>;*^t2ckVb({0b33Xl% zuEgkijCtMWhMo?Ua)R>#Cr>X?MQhI84+A$v#WwG^C*Skm92 zZr$ePpLh5){T(Xhgt`@$mXA+Zx`a?(w>jGnBuNFfO^v zL*wfwRIb>Z*ID{Fc8qy{2Ule*ubGhT6Ee3@=jrhA>=PRD3Cp%)tXnxD@Aa^>8HY-l zp^{Hn(e)U!obc(}C#+mKVMXU1R@OR8%iiB%S@sFbv%l4U+g?$h+c11OHVk=H=gKu3 zm&b;oa*c(?Y#7QCMfRio@V%lwjB}`4i|Ic*H*sj%{o%iTuc-enS>m%}!%(>vQ{@^9 zb?Y?N_lfu{>=o4*=kW1u7?$NVS+;dtp1q>-tVHG7&i^-LiRGD_$ZSL9dJEb!EZ-Un zORla^wsp+1L__AGl5_ZIwvM0uwV3kyOLeO?x~JslYde2(drE4<@X_{)DoY4?CkXe7 za#f9wx)xJ;ZlX?3Xl%{KPm^<49y#GZyB1R==a6S2md-phHY>5>drB^QZsOzEI<71m zhLyLcm1C9}>Sib! zuIl_@drB_<+{DNCiC9rv$4cMHI+@|a_fwwDo>v>PL+sk@ zL_0g}t~>{HU*&n^Zw#(aJde~|81MB-O=CWE2I$_n(+KN;?t42w?Y=xe?OHpZE8X#U z8hP#m z_Pkt7dPnv(P}|*suozng_q(hnOa;4hbQr5F?*#6|T@GV^rp?&3x|*{!gelA;Z%*zh zX+Nhnc0btrcm5^Lk2*fR$1 zTE$L5U*x{M$mZ${2D+$1&VvcpODMI!=tMvTN?d*pZ!bCvt}gadq-X#T&y- z;Tz#b!p&hMd86VDpJE_d=efirtqE=WjG6zey~jdwLh~7-rH7etk?aHBO3a#;Jt0 z;zhw7-Y*Il65p8i2ECErUR+!px?z2Eakz;12J&wNk0ib%s7YNCE+(GNeWu3ggeh?b z>FMAa#Mc-9rgC1Nb_2V)?1C-Xb=>FrVixI{aaO!EToPu*OG208vT!M>YdNcj;rrp=;qq`9IhPY=$7{&B zwzz`4+3^a(ocQ%{MVJ%+9{v{o8U9ZASNI3i3|cspE;=j7X@t}fmp?<&yQ@VCO1SjxS{@s;eTcoX|I z-b%O`bpPg!;s$a3cux3gI5(U_I1fB8oDZHKz7{s->_%~8o@fJb9pXQSx55?0p9z=a zb$BcOhqrOhTZ_4z-8jzW&E|k}IGRU#E_h}5de|gh6|MxY4p)I!hI#SKa8@`woJlwb zJcqw^2lsKuM)!N3AFl~lhxzf^a1D4hzd3`ez83D}nmdYD!z6|&3a~FUo5kJ6vzEeEF zU%wZ;gr|D|zsbA7?-cigH*xeJti&bYB^)2ZFRu@W@aqf0kH~+p_&v|{X81kfPvKC` zT?ZaQ{1j(@R6NBBpO+Sgk$Y`8j5F7P*Yb^iNSRz-{4lKm`a`aHs@NuO6&J+AIX@qq zA2*Fpa?KBmC;1D13Qra<@i(3<{uKTkw&lBR9k=EBZNROGj|hi{P2&?>^JH;kID+(% zgw5hYuG|*fjQ9t|@4`#r2VC<+u^s0(i`%6ujtWPH?c(=2`-5UpJc{(u;i#}Eevh2* z7rzR>48IA#B0L|CA$R+DOgNhOan63Pc)WNq{4N~JneF4Rx$61w7&(s@j}U$uY zi-*F4oOy`w-EdqyKAsTw3VVlr!d`>}!?VRtxawKLGsR|nl^x>SywfAa+q~7o#irzJ z7B&qh5O2=8#c}hnIPL{*#?f2F)8XggEv|pNc!#SW0^cS+JnqL69Zonbemi`Jzdt{m z$UWv0HVs>Fr@i79guUaRxx-t@wTuh&vjsUuJ|#}^&H{Z;@Ef`&%6nD zm>)I?2N7=>_Ky3+ExFU)@lV|0&&BVH@A8Y^bEk*Ehd4TdXE;1A;M#rSn_Tm!;?3e` z;puQkI3a!^-of9xo%FHX`M&UNp71`t(8J(^#Cz}*2Zmp8$LETz!UFE_2ETo?c%%4f z_*uAa zFJ3Dir-ZiUc)z%9I3gYiZo|>GVZV4pe3i4W6|WYLg~!A8yzeI9Zrp2o!hzs{hBK)Fwp5xzuFA*=~?;IIl;cl-Mi~02qVMlN=xEt|~VW+S& zxO3PA+$HP^?#h`L`1Nm#7m62)-+{m5PA?FiFUEwU;@B`Qj3pjNI6AfukA@DRJzwDw z@LR;~Nj(}?C0BejJQh~x366@ZbN!ewo?jmwSK-R`VU=(%aYwFtEQ}7@g@xdeTsNB3 zk#Pdo9RrRhp1?P}E41VKRYE7Oex>L{_#@bnqfz{JbePDOz8joC+&0|9wQULQLT7&Q z$D%XgQEI%5LXdehmFF@8vApR%$e=q(?_(!pBSdZNI$oXgS9^qfbI$>RM)*;Ld@00&tF^8kM;oqd+FD8?k z7bX){3oUuNKNKwq?-sMe9L~%pOb!KS-bDy}xA=E4i@eDpkW++dVM>@9nuX?}MVJ|8 zk>8Xv5o}4^l-!nJGvc*5HwBy)rh`+6*X9?K!wll-p$We!flY~r^X^rlD{)mA8io;f z=crrgN!$bMN<1hG4nsmO(mlgKj)s7>!~=+jfJ6D!08&FkU#{r|_6ohh-l0$E&za$& zANhU3{wY12BemP9=(p2}*GAi&jy9t%GXV``4Ny&FCTFIi!KlBCLxNuuT$3ZMgr|bD zh{q!3uLY{RjU_b>?RpBSIb1OXoK39#Uk@bE9_WQ?S=*tt_9nLv!9AKiw>3JIT9LZd z)?Bd=y|xee{Rmw_SKC{_ueSr$ZWfT*8dN)53@$*fSLRfc-VxlHxC8QKC$JOe+LP{p z2Cl7(t3jz-@4}Vtvb!r9{#Z2Nb$H&f=qvsBi*3;~)Lqm#+9C~i29=82l4_5ZuK&)S zgazOp9Br92=qst1RJ|U2LnKFS(48TV;CKV@Na7MX5o!Jia&ATcx;dy<99w)7jpin_ zmz#;dnY6N_&?wXr)GUrdmpc}X@OV;cbjKIhqvPCwOmq|R_59+dpvHJqaa5G)I4aIZ z_dhCbiWYx#lV@kD_m$3yX4OoCia4PZ$QnaZixtxF?K& z6S$5$Umw&$k1FmCL*Pm74)P>-bLBnsS#l}I&`Sppr z&kWVDQ)hDaj8L|pzl^hIp-WeT)tvh=a;K8$4~c)0BvED3?}bbFJB#8aaA^CXne4~W zC1@J^7D~H6M&4-&TlLceETrJBRq}fNdXo!bM!QD1Mb3HP4?DUkE#}T|Aexn&>mc=Yi*jt{1{e?hFaw9C5+93}bX@obI_ZsttiyU}YR8j%G~t+_w!d!D>SZP7^6PKH7<>bb z{}$qJqVwNU9D!!1eyE0bIKMp_JeuRfd6E-A^{~T9eF5qAE2MTuYyL{Oox9wKmj6xS z+j+9HK-rw^BXB#Z%hB?0C;tw@*~K34ETvc?C-*Z zXcwEr2a9>!{XzcDY;Y6)&Kn=_1@aDW5MD#SdWqjWfW|&M?u#z{68hUqJ%4um6UY0ad8^y+N4#&45ts#|@+Xe>M-SgGd>fWvR-6L+G#Q*ud;t0C zk#7;-$GMqNZemtEkema8T-TH+XE76;343)A`3J%hy&L3={z@#bv35KdM(8bAhPTi! zWZKq>hmdn{kRy|QlY5&4^EEyG6ISZ)VU2h%zmf}^1g=f|FLGs}WUS=SmsUvBa{XBceLXPH+Qi;@^V_codWoSWNzop%uT8iIi__l~~IGv2W~`7}??A zIPN5`EblCDEO*;Jsw3@yhO{g36UFzr;}gXXh@T+!2vYjnFfM<9Kbjc-ka#4e^h1!# z4}o!6kF(10?+~w-n7H3_-GumiG>3`t<;3>9%&-1X$dbyL%9F}`_le5(ha$Tl3M;cd zEaCg$``ktSZbJMczkRvr6g$8xFXGv@hkbd1=aFe%B`WhDhJ3#pXJ(Vy4eg?c{|5if zUDV6i}Rq216U0gJ}Q?j7mbx(;g1*FWns8nBsMgjaw&waOw5j>< zGiq4#(c-#somyS@SRLdUs=1~$I@hLXifUe)qH%U-&Sy2Q9D(N7os@cD_xOHdC*Fsh zs78-m4Q-m@A}&ac0t4|(?lB7;b`*NtzfllIp-aw8+T=`9awM<9x4aHcMZ=tio;s6Q z4(3&uoL7riiYeqwh5LDv^q&j)owd+RC!=-GBz}v$SBf=BuLV2x7U|La#hGZb+t-JjZC*iZR6F6Av+-*n35WF=suk5Mo^>fL#hkd6$Yd|S9VM+j9f|wSd2cLlN+f4`y>XW zhS-_InC2IqM~vuS%G?nto=KrJzZf`PIoCLQ*d*P%Id^Z)eQET>1*xV=m`!YuNQGo_={Rn1JD6#Ky`-!gu$>BwVYEo7=RSt8XQPoU$B0!A)yMi%0|s)ej@O_1F_7aDse!2;_NTs>t2Wr5 zyF0U4%UgE@Yf+n63*W^rAg3{iw_XKw7S%7-0jwo%OWclk@GEEw&<&Ka8JO6c zfgJnBJvo-U8OXajpYPYI0S6KH;mknZc`*4^U~8UB-ljjn_v=fl75P=XUq8}*fx+Nl za$BS?5;)VJw;jN-?alX#3AIvaMrh9amWZ3CWBm{Ya9xqmZ|xVWO}`z;b(WZSsO36Y z3x7L^-^w%i+rg=I4FTmMY;~fHLSr68v9=NK29M)RYg30i5GFg);(J8QV){H5X^Hi8XOMNP( zJ`FywN3w*m224veU`8r^QQH{nfT(4SYZ(Ex*v%R7$zD{APYRzf&&Da@ks{enr2f{HLYf zCVfLKjCzqfI@Jj4N1OCLXMld&x|&myzU|te-?{Y%bUZJnNyYY!>ME z&$Tqy(Oi3T-7PrRpYPj`IM?u8zin@}CfiZqye-kTkXwS^-!^3nvoEUspta<-W6QFY z+2WegnjE!kadmBN5G7-uY}w>ev!pCJYjnp{c3nVA)iRQcwr95NTp`1HY)Q#R+i%M| z=Q5I=wpX{^w5OCTTg%asvNg%+wxg6RRm;(mvX8f<#!^0(s^w@I*(xoyo}i^_&%Qb( zRRhi-*V=D+%9;0~9BMvjaxPXHt_>9a<~ZA<_EM zG1U(1(4hR*X`@=`L&O;Oh>1397)+&%9h$lN@4^h*@EK{snk}ZbSzoRXgJ^9w$+r< z^84$pW?2kNjf$<=vwY6y3mYgN!NaiSJNjc8he_KY%DfY^i+Qih7$AgxiWuvTOk87z} zcH_vcN#&QvTuaTe8$+&TqfFu$ZK+vyqsg^|swgRYPD@QW#8KW-TMe`nEurD5)LNvn zX`Wh#C1u}esWnR_mE{TBS6R*&oXW{D%aXI42Bne;p#5i&%F`o9JImIT$ID9R>+^N_ zcjeJ_ozz1(0_1VGJQ~|>%cHb?PI>gUU$Ttt(=2<(CDHQEW0qrASu)6DUzQm1_?RV$ zELr67G?%)guw$|1o+T1{etY^Xr&#Xx`Pk!;w<@J;Ntb1uiR9-}FH1v~cv(ua+{+`Z z{d!rdvfbKCm*uUp6lS^S(J{+st5L?5cb45O{Sh4J^3G$VBVv~RY`0~p&=#9VH6_Jn zlySMdbH8c3wA}4g?Q@ko?ROnBl}F1`sv~Rv^d0)AZ_+<~tNy9Y^rt0t;jHayAn&Oh zt~@v}eV>7;Z46A`Z6H^z${P>l8m)J`ftK2U)NTiG+&`7*07_Ubr8a$;T7FSOdLVHh z&J3Uh)bf4QTI@0Ukg6i5HN8b&(yd6_I%?B5%e_rM@>}qBEmJ)m%vTx2vF~Xg6%*Q1 zH6vtM-OfT|r0ftcR(MsHfO-tFx%5C=aN!_$KNrY9(qY zjw)&^YA5PC>L==G14*fksG&HLtE~*;J=J0C!w2)7vVNwHVjrGIy{x0Do2aj-p{S$T zw>t7xjK-gW@T_UBn!$*e(HzFJW|#r`JOKYN|5r#Mnn>M8bH zSzBpbPqF{Y?V;R4vb337j?zrIMK#n@>|t{|EVs;+tEV_(WJ%rLWcl?JnV<+fihniXnZAc?@uDShil7HOf5NSZYcexzy^HmvTuiHD#8pS1QFcR$db+ufUixfp`s4 z5u8XoDYZ-`Lgn5`v`VGMCe$_MT{Vj)Ji9GbouVlvG?}!rrc&AzP^q*9wanH(jiVMk zwS9w9Y)e|ybkgbtRlJM6h>~s<&u$;11l$@K%U($NxSBVxFH&xCU6cJyfWf%e<0&;!<{{;-x*nYprG973g!!VC8KhA`7TPGS=y|xUu4Zf9Yg(MO`f_=zp$LLe$gS7 zQ#{i0H{P}gWq$eM-v zpyNZOW}&pHnK$$6LmZfgx?XpZRN0^y0zlK^_*4AXn z$`ZJedFIM;kDkA^Uq>#|uU4NWQ$Alle#{Xmvt;#|G1<_}ie?QYj|PqNV_DKyk5h+{ zA9JK=oF6MQw5{n)Y&T?CpyiqQ5c{Xc7nOiH@k<4b7HJ0V)v6VK|gsiRd zh@$nkF?mBSOnpmjdwF>5ti@OAc;)()^*{B%rSaId5}I^O>n%vX!afF4?lwdF`8)Y+3E;kNk4>i@s}jFf-4YgSjR7 z?W?Y3sc$RGI&Rp$^1M%7%gTC{dUobB)wz|7>sV+tEVXFsbBlT{tE>fC|10_DJlB); z^Rm`tpSeyN%jR&mnBN37<2 zV`W6Yv{It-p^}DDqw=98){?Sz>{ilfMJ-l7#2b><<@i-azq=OcNrW0uslaion%;R5 z>4}84;2Ok^PL5SdhW5{nQc8wpwnQB{&sJDNI?y`Rm&Xt~f@3+d-FBp;l@BfVj7T;AoC)`CTY8WyIA8-BRzMtf)*loX{OqGPD%CrM|KUC7^sbl+X(t#*wAc3zQG` z>-SD$mZ+pCLn4;vM*C92%7^x$qV>cXt;(4lIi);)El>N(y@h>)-{-^H*Yb^DYQJL$ z4QF;_qHJZ2jbDwmuRcq(EawpId2{=+UvABJshd-?tz~}3`5jB3{wz;<$8#*&&ypD-3w z<5KUMh!xjQ_~t(%uE7$khNGXQ)KlcuVDI%5_%z{XcsTx$_~+^P&m7fYKlEqtP2w7C zjNSxqN>)tY0JVPA0_sLmzr?cj7g(jLcsZJVEYn!Rv^BKK@H#X z_4Gww#R6*_;dSciTI7$#Ug}lwRdWA|h3%c7HiUXK-GyD#9mId(=q^xi*1wbUH}H1i zcgVXN)ZbQ5K~am)e{fcxC;fTf;`m$O+r+D4z4a|nt5w^Ha@osREsi0)0=~j?bimT- zK2TfN_Sig$+QzPeHI%63Y&-0y#QTc}K<#i>=exWNzRX=#=L`LzXp4o_gGC#xtVC^l zt9hP(fd9bmtD5jH@L$+>RTJI^-^YupnoxvlLI4BSZPk?FZRFPwmpF=8&Q+6Y3N{I& z`CHcOM~It|(-f<|YEt+~kUI)X4F(egL$s4>?6_9LYOD>|CddO+ zlNy0FUUe7_+U8ne=QkW1zSdzFXWm zS^92lNA8K>LgKBGAIDbsa%`QvxlRO6Hp36;s~pWIY>Ic$x!Rr+ z=HqWv&AZJboD1S7fX`4hsblG3XC!Z^8F)AyNBVfe^x_!uj|FAsjt2FMl9|&FYC0&Z zr&p9Xjb8UC&gwZOW4AqdQ$ZQQBkA#HgR?nz1nDF3ACkR0oNxplMeA~O7~yb6Gxrc_ zjqk@k;C{rd@kQAWJb<`0ek=!o2NAc%%?)o6gy3SaePbQ;HcuPr4c8>*1(h-P+{L2s>a= zJO`W;whxQIb-?Y37h}CT8=TF#?Z{mhTtvJhR;07QS)5x)?t0*M#5-}%wL$&!cH%G0 zBt4Vsw&jZT!G**-2Yv5$<{GWu^`+Z|oSnn5T(JSTE%7m=HUy6)KAO}A8K-HD_p5cUK0a2Or8#L9YfT!5AJDAJ?x3D^RA>%Lsy z2TNN09L96){$X`2|F;6S!V-IA+zfl|k#Tb@wMTOOs5p+R4#4hK&-#A+wr|kWU~6z| zti)I2`jPk+Y>Hj?*yK+=mTM2hN_Q;25Be2s1Fk`>7)xr6Fd}MqJtAryJ%V4YhOND9 z`YL!1Oeu!PBlyC@xn>0Z2=lPf9v%ISUe2hmZ7AzYS%|#2!76Ez(dF# z636g&hs1;Mwipr*#)n{V9355%SLb+89Eo-Gpg0O^;z8tND^AX!cv!3rgIG6U0G8c{ z#(~&_A4-lZ0t_H^NbHXt_u*VM2poh>`r%lj55e2~aBRzuAPfbEVl{qnME(Z*hePnv z>xX6ck?{!Z!;d5k4+nAfU_7fvgw?_Vydj5!!?6xOko<$kuyv`UhN0{v~)CT^ZWPi?B}b z0(K$yLedxE;k5wU@&ovb2gVD?xe!k#?byEtUJ&*t{{U?5^-8Gbx{=t$*K%CVSE|Kh zU^R|g;~%zKvdABZjeHxfY)cq`=fhT1*v5@q`_;#I-PvrS{dp&}G#dv(p2g}Z z_a~2o`?=-;*5ruzTx^&8Q?}#TN>T67Gx56Y8Sf8O_=4^otMDe>2iy-|(yC&Ad`9I0 z_K$j0o{3-OnRp?7o9n-myerQDPsc+G-%4UvEjcZD=!*J$E#mJLaS?wru!_+QN^5 z$6vB}u?HTRvKxEEmy-|a%Ur3KTTfQ0aK)H=!>*j)4G%c|aa}RyUVOBA;i>Tlu6dc& zWbS5df!8^AH~1Ry?>Va%mtHZf?7-QVNdF#h$-7t~LZ8XI@EGe8d&l453)Bbf9a#~D zb9W?P%{%eRdpr5&=_~XExwnHqAbyh6ZQv8ct|)RFcpE;Tt|cPs1O21qAN?azw~&5{ z_{YRIhfVRs`X{Kz)n?IkgEqrw>mT5z#G6M~71|uH$G?Mr!vk!7^1+&qr_lSP-{Y5C z;3fH2d?)n|+k{g2H@Jv+6H@c>r+kO!-jb`{1@-6JlGImvUCp;fECVwtIQsd+EVM6>3UXl|?{U&UL5A0$* z6?Y=uh}6b-lTC=f#-{|dls)ZJucTHe|+yywco~sF&p?B|R-S zDa|9^n6qo{QE^S)+ zLKsarK5S6BiTb<&XE!XZPkIATZ};`U^-JrO^m$(^>hZc3Px?$)mz?!V>y~~@S+4`G zTUw{2pKh~aoj4~pEA+{1R;(A-1)CGg@y!9};H%iAn2o=oY~buz!b@-_2um1aF&$sR zSj@n`FBWUZ8Q@I3`s5R5#!&o(zZ8lorODvb(iCu7X(~9qG!2|lnhvgAngPx%tqsm9 z%>-wcW`T1`v%z&rb3pxrL!lpVDD(ghtRC|;I2nIK?vGa^_s3(A`^TwZBo4(|@#o>9 zIIc9dbWt2%8dthFjxCJ=FCxA$PAH8B$8+wIIHt6E>5_Oc@uhKfzVfBytzNo-Yc7lz z#EGQ|rOV=_aWr@wW6foZL#u$JOUH-H;_-|?UyEy$CYHX&l^4XLI5(L!04^gwpZu?Z zlS*rp&I8Yn=fyQklSr>sTC;R6cwRg=PA;ug`YO*m8JtY+Ii$ZD&j!zlXMtzOGr_as z8Q_`mbnuLLVCf6^^dD3@uylMppycW_2at1M>0pkJiwBnuBHq7rBA)&GbM}DJA*JKu zvGEYj9~bv4ofJ<5PvqR8rDNkU@lehm8}}uDztU!{#3#?*dmPmIu5GyffYb z-WBhRvVnJix5wMSJL2uJO>udA7(AL<)uwoua%ods5ibY79QNL1i(k;Ln`5VnkH^m!c^HME&tvTNh>{serYDRu@@Eh@_SWRBvQZ=DZ z=@pK|KBeBJrkrh7dNsZhdxO17J;C0kUZp1FHwABw--so!N$IutYU~O2EcGb89$$-M zk5c#28}aohb}w}+y&2z#Vz*M)(x2j+QS4gkQu=fJQxv3(~)g zPjK`u_-_15e3DrFOMHiwF@H#^ZShq6A^4;C6!_!#Bk(8j$KX%nPrxVBl|PF=CH-{# z8Q8A)1^Dy$H26&XIrwaR27E3)3;rTL2fh>E2H&Q(JHs>=_N5Iyat&cJJa07|uRgrh zFuc_qKb2DYSzd0lt~IU76iq!0CP?vA^=U zzl7EOb>e=1NuH}4JeT<1XF$D(UFqPt#Pep>_r}EP-T;1EyF1_TML__YcI6k$ODwn2*8m zR>SK$@8)_(6Nx7f-hkD0HqJStHxl3bI(%+5xw5;mx#Qt@Wqn_RX>|@yj#q|t9Pzt} z=atpHll0xh`mx@b_}<&WJ7IU_cHd3xt{$`ZaP$rw?maNOe}mW6J63e%2D#mL64R?k z?za-tE9Wbd`z^S(YMwxjS9aFby`1BFC2_o~CWiOE#PN1W46l6e{fY0rpOhT$D&PaK zzH+>>t*+DM{NT%Qybr*U|tI{EpwhU5JgIqws)%@V%{ho7>2dxo=HMzBiKF1mEY@FuP4a=OP~kU6G&}9B^wm%4VRmW{)JM zSAN$O_T+fwbmf3$eZLFeD+es!E6dvk?$?>hYOor1*BLUg3U*iSw<tWS=}Cq z^}Qx>quoLI-^;kFAIz@vo0ldgSf*E&R}NUdSAJIx*cDv{g3ijhmP;+nuDq{&uS~D( zuYB)dm|odmS>GXv^=*+j-q!G;vcGb_&4YaIDX_V6z4E+Y1iuKcE1!FEVtrkA%axV4 z=1k^$7Z%&`)bhQqy}T7?zEsHcZU!1tb*m|i(uS>eg#FM`>1b!J&#Szh^I`Cj>5 zIbfMySzg&+`Cge_IbbEAWqoCWU3026oUXI< z$AQNtruVqS=gxrNl?j&hoe7UC?1#tC!TkDVtT)jxZP>6xmp1n#Z~gXQ^}PH zoeIAz2Q1$!zbpIex?7p=%}lQxtsF4AH%u>DKTI!LKTI!LKTI!LKTK~G;Xu%pi>e3* zgRUG^MK~06HL5DYx}YnART0()UG=Mqup#J5R#k+JLD$HV&&^D){I2Y;Oz+O19I#C9 zk&yl?`^{s+n-Sd%)}N z%+Vf&eC~R%x*HJ7122SEb-nam5)&-LyKQ21Hvr{-<$I4we6LLJ#$ltx@XGhf0?Y6o z1@AbISl0JQSlvD0bh{;XSMGOrm|fXlx!>IqtJ@VeR}NU#cUPF)J;{~NmG9k)GIvb^ znciJ_GFjif3Yp%{iQAR+-6wIpa>FvcRfXJdr_dY5x2l+!xL_IHec*ZbORR5i@?~!` z-^+RmFuk(8uB|Z&Mt4il^)~v#5LXrQy%S(+<$z^(Wo@^B>6P^z9p!Vkg5B-QmE*W_ zeByiePfYFsiRoQE%H(bhUn@f_>$_>2Q0@cn|p9#dJjoVuS~G4 z@0i5&%IwMt%k;|cj!vwvOmJ=DfaQ2)c5C5#<$e!M+-@zb?EpC2L!wNuOz&Y)rdQT? z2&}J+F0C=~!E(I)68C#J4DZmy1`mS=mgzkral6Cddk>CPg?#IX#PlASxZmOMy$6vm z(<`T&Io?h%x0ePvV7c9npggdA?-hyLmG6}amhb&~;&$bGJHzg}9#iL}fnS-{V9I>2 z%&zROTu7}WOW!hU|HX-63<%$ zn=AV(-`ghfyaQo+`+vaqwuRr71D5sO8fI7CSJrnM_}>0p*Mg&MV0v90NY?j_Ak!g?;}BWR~}bBSXTF3xLvv62RYL{%KCm4hF3;dKKC3@{#T|~HdhW< zj#sAlY|hE#o(114A1vS7GqJ7_L?HoXqvdd~hVPXXmUrC;+y|z&6|C=m;C_@uE7;zu zLZ)8QI7Z8#P^;7(|bCp>*07$PfYLipsQ`m@SYYH!72v0!oXjZ?{#f@ zSL2r5-5YjS&R2Hq#?XQsEoAnD0hY_%6WlYlDCBLw1$*mSyssoiw;3Gn?y(uH?;hYD zTqoZvgX>zquK0Z)+^#Fc%J9Atc7+{oR=DDKW_o+U0N=y8*Wh{YNv!W{iQBz9@xAi9 zvcht^ufzAs{(c`u_pZeHelPL8a=N{ve6M`4eD0mFx-!D9Ui~)citKW`cYt!iPr~TR z_ufXH-0u_cyzV<7+xukVc3n~09SLN8<$iA^R|fD$@U^ZFFYEgr9ItC|$@=~ilm(XK zmFblQmeu`R;&^3xU4?!=obY>z>D@f>xqpS}btU{wqI|I2@1n%vW{!6Y(yk~k>-#Qz z@1n%?ZlBm(8Dja|7ZTqq>nler(<`$pD=gFNP6^M$2Fv&E2%9S(EYmwavAVxW-0$?UVmD!d3mGOKAdSqzx8DLr8r{T0^cV&HD&rSw-DmWD`T5fk7obEW- zUHROxiS@lG%Jj(<`$pH!P>HN|g1zEb+avyz;^4CEi!ocTLi3!tu)Y%J0hlel_vF^1ZUWvcG31 z-uJA;`<|J2-!l^LdwSx1<$1pV-+Me9uS~C;t{kv@?(v{puuQL9#Uu&DCC`*KxgdS!WKg5`VVcjbWhO1!UpZ)SRBdF6ojNbIkCuUx6@ zuMF=3nB4{Nx-z{FByM+0I9)klS>LToGQAHbR(FfU@qRb)xpKeq!7{+xB)(T>S0-4d z_aS&tS?T){2Q2Hmu+*;j5=?Kq;>$3-?TW9&)46P`pFLAsb61RH~>3iUTWq9uf<$vXPwK%>5rdQVYuEg-u^N1@9I)K)^>IjIf8~2`h@&{m72v4S;KcsI z_ZBrUy|TZuzBj_K$uGBsTf8;4xSef82UjU|0Nca!*1-IB1XqRo ztbzHJ?;QxMJAjnjZsvOj!0*Zd%jdQN`w}-NZy+eIEcYwFJCGx}-Kxa*%I3-k%k;K} z@9je@(_0Pp=BR1ngXMT%fzRz#>J7&$2Q1%vGpuf}(yL%k7~oQ3e_v0WuMBVIdwZ5- zdS6f6Zf1JB!}rSn%JjYow=3r>!<+fuuJFB`VSe8R-vT?q0L%17INl;Ly@BK3!S}|J z9Bu&?oRj0d86<+~l?j&ny(O``e*oX-+CPFXCnh&Dz3)ev-nMYMvcfXGe}vq3j^1ScD@4iE-4SejA;FB=DZD4($0-u8EZ3FB3 zWAMi?y=`E9e+vE-j<-$mGuYiW@V!3=WqaGe_dY}V893fH@V(E0&+%8=!12BV%A~h} z#?qv zSzZxF+i(4rT=77QaXm1~YnSK+rMHG2QhID?VX3c&76#fa>qpdzC(^U1ydI9Wo37B% znkRN;2E9@A@>-pgt9fWcpV#Kmdf64RWWBXp*3;bHN$cgjii_)E*)Qqus|Qhg`X8-# z^||T54AUfz%Im|p%7oqn9qDtl+byprqd$Ru%bj6Trx5FP-sS(Xch-Sc6>Hd^TJ(W) z=8R7yf=1XNI@Ov<2@qZ_xF2dx$oJ;K``#U-}m{)JQHi} zea>F9X4cHC-}??LTcZ19hnQLgRA%K)-cDqzET2FxQywl%0%L z5XBbCLPqO_VhdAmKl04co3yw=*_q2DnmlC57FKpCo7b0WD!nl@JvI0{b$rent zCTqcMsV`X#sHRkFvMCTRlGd6yTGdx^>POZHs;^cX)tC6<)Ke0@-FDWOEWh;ZNNX*v zFV&RlF0Hk+res^Cnv%UoT5D-d$qGz0CF_o~*7EC1wo|I9)Cw%WzS5dft)<>gWaA_| z71dpKeaSb@&au8~Zd6~gT&f-GOMbJqUSG1i+*13>uCKJFRA<}Xz6z?Z?DkbqeQj_1 zQp-yH&dH)9t*Nxu()!BO)bD9uYFYWMY|Hhvt?ldo_WII$k4%4<`j}FGn6pj&Vd}j~ z{b3&MY0LGM=?~NPmFX4p+gGM#ZEJs6Q2WZRue2x3Z(lWHPpJM-`+em1hqZp~3Hwl* z-M-{^L;j59hht0q;eWb)r9QsW{;;6>DyTn{Ex9bl867;N37`Kxx>a|oBX!CJ#)Qu?vR=B{rzP5d?_rFkI*>k;3pOxD?H{X_LZB_wTJ=&Z`+aLEf5zI^AMFpb*DAB?>#tZ# z$zH3>ZeN+XUiMl_c71Kj+E==kBF~GNwMzLy+IX!pdn}rcLi6Y5=_+NqijuZ9tyLC0 z*ZV8x<^|0ive%Zg+gCyTVL@wO+cI~^9&Z#>Ut5|xWYW+*P9NlPNZJk z^F1z#{#O5!dR!C-lKNT{N3AzvO&B3)tv>Z?oqF|_$Hhj>w)9p;UiU33LVM%-D#$mc zYDfKTA5`-K)mOgnebLJq5B%z-GrsrJn#%W$nen}^TFds0xuyC_Yby1lCr@LU`jU^a zY~Pq$^1YwdmnzEp1u(^_8|S z)mmCd8DFLawJ+ITWOhkVYudQh^u};YdnM?Nu-2J5Mv}L7xC8$khc1+N` z`0w`h|4RGHZdu#cAErA}>B%KuN_vWE1eL!RNp^quN7|R3Wn1bGv)fnZDVBMD{SjZm zo3^a{Czq_3wDPvKy-3v7GP{sudl+2tS3&C=1+5=$%lgK~?7{D=FU|7)m*0&VdP-6HKF-MW zu1)XWa4zs`UdNSB%cc3}E2Vjy&M@@Fg^0yFDp!b7`9RXK!kj1GQQuO89@~@7{+{&H znO%bQ4f&rfw1v;=|HX6!RVx4gk>6E$Wlg=Xmc$-kyKa|^epesI3SKE$@t4Hjy(D?r z@5>jf^72^v3D)WI%K9Pt5%&19yT1gLt-Y-EFUCs$1ypwU^40nrs{Obxk9Pl;lX@mv z^vfRqMb5i0+Vx*Z`l4vj|1`GGvhlxwa3Oa4@*E(${-;rSkbM~I{g=^~Ipd*d%m0vh zjrbwTAIARvb#f09WSjqbw8wv))cw(x|32*Y-@wva_WSpdx*wbGw@7L1B|oh4$EvZH zJg=7I7s^ko{M*Vpza8NN#%?7k)hzS_G_{MDg}(d?cV<2+i}^OuYW_>C@vp_g{@Un? zRhH>rN4tCNRDCVh_wvO0MYP%fJX-XBPWlV%`M>5&+4W21pWri&evZoC|FdY(|0((z zcJ?>nEuoB+b$=!Pdc`;&eixN5g4WUEzO>};Hv8I1Os^drG+O0rU8cCzD7F|XOZ+C$Hedc% z3tNqlidc<}*a<#*1<)wAklnx>pgLCf)v&!kmpMQ+v>N&Kl-58u5TD2VpekCGW9ulZ zfr`zQ-Mv(7?)j|CRza(9o^0@IVGl0P=SL9EkCyng&{~X!*AVJNtNhy7;fvXoRel}p z@MXU*+x)uGD!(39_p;)bRen7z)islqC4PPE)Y%8ko=(0Y>6OGQ$R~CMxk9LX-;Vy( z;$BwyqoU2e?CzIhlYb;f_9BeNqF(mm%LJZXA={eNR;LizTc)?u72dG1=hvLbdWaH?Dlj9)D-EPh6kehclN% zd;H$fqF$=Comp{hN0#<|SeuglcnN~Mv&v>)o>%*#vfP)yR{3a^<-Yv2%15g#_vNou zK3ZkDFMqA_(W<#p34*+{%4T1lTIHQpHv1)_&AvRf4l=35eOJ7yj>js0JU&`eEBnrN zEEe~v6~8R?Ctz1SmSdglK4vTy{S)!sy189{M~-&FTD&X2xdYk}>-~J|{%ni>vDn-1 zjQ#yS#N$ZyLdO!1!9HJ>_`Nx@HqmBRQXwg5KbN0e|UtR)a>3^VEK>28F_*3itiNy1xE&qJVWr;6~{=>1> zAAt6cR`~--&80;4;)96ipt2E{6@R5@eJ{)V1F@c$ZGHtpMO&F82cYr?P&wM*m*;2& zJgCZ+zx=;4jE z2g=K0JwKJW23GzhOncI@rk8bp`)I$P+TFK|w)wKAABi=+?D1>zi4vwA=d{OiU$*?R z-*4$stNG^9;$GJDBd~ElI9lAx4?x@K0iYJ2E`c?@?ChHnhW+XXKt2IlVF!OG=e5Cu zD_&vIHvhKz?|{{R8`qWlLl*bLP8ac3~#QooGoG2VsT&2osF)w zXGPn5S=^U%>+pG37A?!M^`zIKvV~m3S>>_5mvz5v@MX)NhaKbwj;_b&L>{Tt*!fq) z68}tMS>ji8?f8prqaAJuBdhg_ZdJ7ImokCsZ9#D42g`;iq+t}mZf<^s1 z#BY+2k;j@EFW*@rm#AQtMcb2q$3_#CVKYbbp< zTIfF#t@0ls{V+EAvd4ck+T%Y;xvcoFh?e`Z>3*DW1$sra-@lC1%xIfGGur0QidOlv zD4FSIIa%e;MrXO%(XxKF`x?KjGooGpjA+*{zZ^f{+vBU~_d_=L)3MwC8U2~Mk#~-t z@c8j%^#1W0|MOh;IX(vFI{6tm44e2ac+HqjygN4dbJ17qt9JKji7$T|UGU}51rMBu z5_ZJK{}qnyf%W|>_7KW;#0SXBb`SJLyshr(Ucx)8d_e4oHwam6A57@xMsajcRCf2H zqE)`UMRdb&L^szRpBm3oI@-xLe=23&@t^UWm8T8ax$hM%@u%SNp*!9kWSKsN&=YSN z&v0ySCp&TZedy^wu zq~zp8*7v8NCnu*Qi?RMbHaRX?hRULU8YQPB(~?DYu{|a^HsS6ja8D=lNwGXRhIm_^;&6Lze7ECzs)k;pk);@zUf8d@?LejwasJ6UAg#2%i-_(VpDN34SWX z$sU0JiD34}|3DxuoBjRpRp2SnyIT2Aa7Nw|oRRkfXZFQ|f#V#_@{df8N~}35S&EKv z`#5X%!4HEqW8FA(oEwjh=WJ`9#Cw1>@*A+RCH~UnNlKpL_gFJ8Ih^k~JeiNqPZppH zl7;BPWD&Y3S&S}DmY_?LBhVv~Ba;`xp~+$BVafF5#c)V+D0(RQmq@>e9-JJKJRe>N z)6wb4jO1lXUJ5UVY01IKbK&_g1D%n~OkN4OcwBjf@|VLaVG;H5N?2$Y*;hiITWFsR z&xM)EvxHg6Eujm~_**#tmGDe>Hq1(%AHHGHcBre ze_yzaBliYl?hE&$_lF122f~BsgW)0cq3|&JaCiiLBs_{f8XiL*3y-7cCFdu`oS$5P zUXWafUYJ~jUX)ynUYuNlUXomjUdrDy=Cb5IKJ_@i@t1IVvNHK4tV~uVCRvf3j-F25 zCa00J1e5$6RwZYkzYzZvehz1#XC$i=$2mM;lT(R*46Bnf(VvJtB@VrnU-(1#F`S8> znXEzABxfbxhabXO$*y5tvOeh_&Q8{$>&Q0@88$Fvdb_wf~ z4aqKHSK>yT*)TMsY(r8%oSU47HXyDa&f~WYmLFjkHMJQ>4_93prxyBR?y~!0N6bZ$`&g6;_iiTdK zi-qFE#Xiylp;+{T z(JHLvoU`0o_f7aVyz8olYG^gi@YvcLBcB+p!s&$8VIJqKWhmt-e~&ZY#XH97u60;J zXcG?S=sb70`#OBX(hHrLdEZqDRm1z7`5s<4zUB=1(`XY;BeV@4a8&mGl|z-VzpSA6CpS20uyA92oyc;z^S zqbCz~Kz9fo!pE*csEAhN40-M75Z-Wkp)^`LlnHN=egjMX9jUE1U6;@m?Ml6sGPi_V z(O1K3=xgD1^!4xt`bKyYeKWj;z7^g^eex=LD;N27S0ixA;!^5$F^; zlkOb4gr;6L{!P7X|C{Bet>s310&8{O}`QBfjTs z`P?`XZyk#{_fEncPW~T$#*f5z_z7svInD6GAx|T>5|*O3k-H18B8$<*eCBO_f5-4P z|Ib^bJBCi-HCHZ_N6Uu_=GNPmnE zh*t@p;t%<2zPF^8$Agky9uIEho0g-?-7&5nf5({h?(^_PSkK>D=Sp#ANiUxu$GEz_ z9!EEDbUnU3J`10Rb4YK%7mECu+(S44J%Rt=75>s^=x2BimdA!q@dEN`_$-{ur_R9_ z$fu<4twl5{D& zHRIU8Nm7dlYKe+gRn23dp``MWI!^JvJb)_(gTyh=%7S? zBFgz8qz5NM(ILq&bZD|0IxHEE?v_+Ab*YOAM!r5Om}>Zfu3+Q|q=Kp8YoaxMEwq-e zjn?*c&^q`k8H}&zL1-o75abah1bHS2;WFpLK#o<$TT^AcLl5Dc!Ki$LIF4TKa63Yr z@Tm|6;7huKk!PnWcyy{lZYXCCK`Rj3;KJq360Shy38WC8N%&cMje-oPx>YM zP}YyoH|foh@#y$uLb5Zl^n>tW*qOWL19SrME}Y*l*%jRd9YfrUvpx*H2p@%pll)PpgOz4arLT(11n(klX6OXvp{g?hL|2pAo^lLsdjq|#o2NTcq@&+@L^Jn-s zIP-P?BA*y zzKd|De~wQ-<^pFnNJ7$yxJL4hf7jPYY7!@ugd|Bi5?ANQyS_T%JwK9f8-WL|$$Z=0 zeA`|AZvQFqvwYX%?peO|F;^(rA?c75B6LJM@-5Z)j`w^u!uxo@n#5=C;Zt|}d;BNF zg*m@aaxdw7{Js8T;vz|V%8C#QCq{t4K;wfmQ|Cc-6-{f!hPqKHj&?3+Uyf|lo58pYN|EKc8^8zdqa$Dks+yswCHi>w~mPQZ>1ek{iN}p;A&gxhYgkDxsAqy*5-! z-uKsr>q6D!+VH;rfOJ*v#RYule7}M3UynXUd<7*7{LP_4QZc!iZ@4L3!>2#+*APC$ zPusEnIP^GwJbJu80X>1=mdCX%4Xu45zcJ73#m*pkX7A`PPTt#A@@+SVm7#o6A-S6G z`_Nxa_{g8*ALVbJL)hRK@|PF*WBjpv@^aD({i;wlDVMAY<&yGf`DA6dDqI~t@>dZ) z_RBdp&s^p&=gi9pi~M5ZMSdAa^30{A7yC2#hE?H8KKHS|GTiI$LqDcnUE(k0=p}?D z{%AgtXD%kU#2?`=Mwe2SXIAssGs5anIw_N^4rP+E$(f{AhciQ7QaV|Ko*CAJ+$1kK z3tbb|qGzF{lHBC%kdu@|OD3hzQpwt|j*_#(DdE&`8G2c`9KAeT5l$n0Dtbw{6up$( z$sD;Ntf1tya1yyI&@01z{v=XYh7-x%=T9Wu?@#BP72))7QMeernA~BcPe(5#J|W!i zAMhveiTnL@N)8LhQ}%#Ap75ZbLCN$mBb*;DKrbM79LFE@#}OX#Gbx`DW`^^KXQ4CE zbBSl8v%(y7HhK>6Tyze)K5RfYkef$(ZaAD@ydGUoerh--92=&EWnnqGoZK|R)G&o` zY&e+mX<;&d{~UeKv%128RQ~x&AzVAZMNH4+!V^^U(u|hlV3K zK9n#d3=2!h4I>N<`-cO<`F?-G1%9`%C@c=U5tg7!IAgzXfxpo2$5|Kn;T+v9>>Doh z7x{fTa-knV$?z~DEF_-Dk&FDuuz=i1!icat>5=Gs;#{+P*aO`o?1}CfMxmp^XmoVg z3*9U1jqV-Bpku;5=ssaAIyQ_$$A$6e_%H#Tz+cKW6Zu=Y<|6LsTr;1)k!ud;@8p`L z+}pX_??+I+jvC4}NBAR2AL)-mkK*pnH95(;pq)K)cw65ETZ=BtnoAMqBJp~6OhDeOiD{w#}hC~O65qkAkI!I)YxSrD(_@7dd6%rRDM(AE*kwUGZfkY396uJYwBeFSSg-XKte2aby7gUnJElTJ+ z=%A8>AJ8A5gGv&9LVtn|DoOYS{lyqtlC!Teme^Q_T6mz6##zxp@*#H*aiBzdI+r9R zE=V5c?t&5$DRhq!7bO34;+4b;-31AhW92iZc-*<81Uq^(CEd)34H6@yeLKVhrF(W1 zgAOVjckU1~BsxgsY$2#2aW;)210*I$tdQs+aX=!5#0YJOJdhY6(L-W{s+e^UK`A4& z-kfb}{mKZfg98#tBu1z*j8H9(i4GD|BYH@5koIVXVlhJ6omqQ2iw8P6@RCi3ds$P)Z8TruUr!C6ogl zGzIO;u^cmvT#nIh&Nm1naY=%9Y+uEaT} zKXDFpP=9nFu?VSwFhb*DfkX#&i6qc?xS)xULZXAZ+Rm^;>E0aTg7*FQ{?45^G8P(W zEWfa00A0W$*Hwy|c5}pgxfb>W%ic`@jhGvOA+9hsKca6N#W+ zkq8??XpnhB8Do$|7gz+?b1`-NNUpOF9LHol2i5n9ABRXhbN<|Hc5fVcr zQfLZ$e&le6h!m;{2PAGtjF6b1sW3s+Ia&?wCkKA0J!R9-X;3}+`!DYi_u5Dqp_Z;D zXV!rI5lJLENOX@#BGExDBK?!@sw_rGB#}s=L(oGYe`@jBns7mT!u+&mACNsEg@&;o zhj^jpFhU}UL<))45i8WjWp;(`Kw1Qu=%1mH5fUk+9Xmt^>HVP?q9#rRmPjG(%RCs4 zNIcLSxS*Ml4w@Btq1lv*{z(}j?a17Uzb8^ibkJdu4w@d>p&3v_B7ssysA1%RL7P zc%WjiKXsf4AaO&YgNmZJ=AcNOvSYFET{uah~X)s!&8F)I-AuX_wd%a6!AE{b7WlI$?ygAM}YZ zLE5QV{LQT}K_Z642pxxNr)KT%oH9bk!U2gG5*H*6MRbyOc0Lx>ez+HtI>r`D4$>abB8A?71Jb_C4{`k3NC&-+YG-fJL03gmNMw*0qDP3Y zf(Fv=%#V`0D$+rhqgO^INZgPZq07+6h_$oxWzay{uUV|m_s~Gvsd*OU&v)pz5J9se zDsgAR*yP#3r$(L-W{UWN`5Gb9qID|C>EA<;qNfV3~O zxS*5~I>e3Q_=^xg+J9N3&Y=k;e`aGrs{nM}zP_Jrw4ECwj0gG2_27!nDTazWySL=TA?I>L$$IzBQ$ zN5ce(ArdLH1P(~7kVv7$kq$a8@<7XAQp6336j~JNpkpHywA_jZN=cz(A_H`(6)Chl z(cbP)M^fl1D@JHpq=Li{#Im{(C3GNkkVv8Z(L%)H zh4w=eVs9qE`FJzYO+fc`6H)Dm&5IynXO4o>ab_u`kTcrL-I=j&A9S1>i;j2W(0{-z zImn~&q_vl{W1o(HqS~q1!456uvtpebbkID~^C5*CbkKZsA*7Hqiy(!ZSqv%U%o0c; z2OYEoJrYt#bdZ>!>5xLAgG2_28+s{-7!oOTa3VVBg&-bidh&7*HzZPMTBL)XkMz%s zMEuWlk@yiWl*hANypR|nF{-absz~h6LMu8*>kF?CKLZ`~Y-EFGC8C3#feM-vd7-(G zLZXA7j%?6e=pY9JB}V8e*dVR}Y!KH2Hi#<(8^o1>yK&G$Vt~X1i4_v}a~FD7Swi8+6cp&_p7I zE{9sWKimho^FX*Cb&=wE5MIcdhv0=QjL<{qBk)2NM(7drF?b;{O^>1HL(5om0lbhk z7s3l!a}m6dg%P?4y#!v!noHq@ER4{lsK_J{K`SC7Br<4KQPc30;mymkVv6^5I~}o1_hBsbvarO4oLKnNTI$kHDZWF3VjC$ByLEgP#<_4YwAWi zNKBBpA<;o1gTxILC*B#|87`rH$0eu^}pflL>re&mtupRW;!MP>`P)%5%m6U7u^H#7!+G+jUNCbTY zHDpcVwX<`|3sr{#Y7JR*I`mHKNCd5P^CCC&t`k-CuB#3^Qey$*Gb1X%|EUiA)hsq`je2YN!${PP$zIxaZDz6Cny81kjOsG_=*)bktoTuKLt_YpC44}Vj1kaoHkBXqnI zBlIfz8L?QO&tQZ^6^RiNZ6RVvbdU(3<02^}&Pa67=aKsnDI~f`jL;3Jcp}k3B7kln z78fKsNGy@)An`(ZkV4u+{JKa7iP_Pf^W8b;{dATH=_?#@YYK`A5j zb`TGAP%=50#7e#xp#viiBt~d5B~z0rsCb~15jr604>y!+#QN-?hyoH3R4x)hqLH*~ z`8AOj61}2b?+5USTq7RneHfwl!+w$T*f$xN44`}vaV|{IAXGHW3vLL+P%dQ95Of%< zP%dQ9FmyPqP;RtR7A2&e-wkw7HB`IC8|a`KXf0n8t?g@}bs&WdOi>*eAngc0II=+E zg(`WvJjfrBLSlckf4#V$LGV5zi9`xj^kRg3w#JiI7MEqO{<0FPhbdY$Tiz6K* zdPsDTc%SmbyYdbFBkS`(q=QTlDRdPCka!}ILKm>#oH4ulR($Sx*dK92;(mT%_d4y& z-kKxNyMCOri+`JA=fnGmArkTPAo?I@x8dC9Twl)V=fwqy4iZTuUP$!B`LJ$cfPP~4 zHtqS|mQOqfFJw&L$O!!ysUR^zqKCu-{Q#jNVn~e8Gfq6p_g-w!SV*985JBRB#0yOz z79%9~M+}kJpgwRv6G(~v5gjyIL;v0XnD`+8a`+0;RoSg!YcqkEkLsLOml7Bu1zLR8e=dhZlF!Bho=4gG3cI zAs!tWp*_*ja6wIpQ$|Q+kcc6XLZXA3p)DdMBt}SN(C(2D5-ZdSHb^=GN=T$oE-X`5 z7?|?VL0!?EAce}CZtUnMUa1>efmrm9sGmboaY15)#QBKn>40{MjF1Q-(LwFe_L1}v zTO=;%+erL~4tkhc5jFIRe~oVu^&{Fy#7{~J9RedHwn&uE%U)cN7$NaQqJs{G3wj0u zXJ#ac#07of-{1_fKO%`l|2zUC^a!8dEiy#ndpg7JbmsGSaMl-*(RtB}4eFYR3fd7B z3ncnyC$xLyg~Shu6cYPWmslj#R45_#R`T^J>jLG|owLRId<-e{ap(>sR1Tg5q!r}ZZh9CC2~B^M^Z?P zkC-DdLLFg(8W4*Vsu`&ukwSrT(LpsLgfCMMF;VzNpL`-io^(g0v*&LazNsV?xpM#ScXqvA;bu^g9+Lpl0jmK zijor-Bw|R6kjS8R#Kno*z+9CxqJ;K?11bw0v>$o^q)=INAf!-PjvWXQQx=9ubdYEu zu|?v7L1W}3#Qmg<(7zysL=&xw zY>~*GCt!r0;FGsSo=Dt}7@<9gMGCEe5fV=%Ug#fA#LtazK;ntS3q2i)pVJ_PL=uS( z`WGzE(~;;ARU|g(Nl2k5`J@;j(LJJy#0Z@l8KFJkgUUuqXl&eVa2%vi8R(#K=!Cc< z;Y2?H0_aS>c{ZQEJ~BerLH~#`5(Bg+Iy#a#1n~|8I6h}x;hd=^U$l|fJ73B8WI=uMC5>;jHHklBGExtM;>S%{Eir+D`A7g z2pvvJRFG&OQ9`1Fu8;Ij6=)!_Lt=y~Mqa2=A|j|7T9xy}`iK;&22FGmB#{W9if}s% z_|_}obi^Ww7kVu6I#)sp-2~kuI_TO+_Iv;bbQ}~z_T^?DWt0G%-FKN+sX9UqkXAsIJ zOZdd4kU*u)vd9Kq8rh&r;3k%kT1xrResvIGBvPmhG>|AEF+w7P%0xy;tdK|{kwI%B zACwCbv^Jat6C^H3jF5<-b&x`0E<_BS8p$AWLYG1YT^@-b(Ly4DE{6#^^;c5p5=fvc zC>0NMWn_dz4T&TYJ0v1##jjk@MUeqYsiBkLfJ6+56uK}nLMKKlNQ{uUA(28CL=q?^ zg-(D2nofzhpySbpV24Bpi3z%ZcxI%BW<^$Lc4URb2%Q5TbRO{>V(~%eL^^2BuZ)nG zAQ3}{M^;FT&^kyUu|Xn*mPab+m`MLjh58XOBu40HbUCpYp(*Hb#G-#h4L#(Kg9bV{ zGC@cG$_R-AI)wBj&Y2t;pod|E#1M%N5*KtXca<2SNt8SaK_oiph%kgRL;#5-5*2i= z7cX=W9MBMsiWfRC@<8YLVU(qe(2_|1q>Ru35I~}bL@w8p^=do5+k$#a!16FNTK;54?1XfbWcd3JTnSXD9?`4_v1F<7jG`5(^IzP$GRF<-=O;kY*T=%^Z(Z!~B*XsS)?ed8McZC}LA z;FAgy@xef?R!Qv1U5)F#xS2kislQ;SfW9(C*e zs(RFHU*FmFRfV3k>c4x`w0)_LGObMgs&*yYDfXz9sHx5C>(A|1Gc_fiGSj=JEi1oY zRh!z><97*aMs>8Yhuh|q$wPZ~trewx734cweW`Z2Efm{Vf~u`;+`bx8W~0B?MuIMd=_SEN_Cd;@-2Vg+A-&U@j1Bd{h@k7`L4{b zuRq?t>ccr^YOOx0jh|m?Q@`blShZ8|-UmGxzhr9dKj}MKV-@Xy(24P!_Rmed=x6VM zknVl3q~v$rcW`=3wrZBOWRlV*wVBE)W*-R zOn<1hwk^-E%y{F^?GH7&*mQP~x5>y*&$7(k2ifz2KhnOk$A?WAA#OTK)RXJKJKosd z=hvp=jZA$NG(OB8Z^$2e_Fgc*-Ckr zuC?{~a%N>CfBu!-9~Ly8&mJFUM)LXfwRwM-nR(@p617*w_O5FcJl@EjFaNpq^+%px zs=Gh79;G>QI;z(iRDR3SnpD~!ZaP!WUx6&BePxg5v&S3R&#x`l*B_fNZ%coux=Tli znekyk}Q@z?oR>0j54|LXBZ_WH)=&#%qLhnZT-tZ!u6 zm-;}>!W#cN|4MhDD|qiYjpQ>s2KL=-J!$ZRrmSYG0ezSGp3l?c)uN6$>68X3xK}`@^lTM{PR)%6@)rslGPt z5C2|2{Jrak1@(tpZ(p0%S7yGvE#pJ=ftgiA?TNFc_1;a}*MIN%wJqyW1wFsi)-rpU zsaMRrN%#=(|9*aD zX3Cq7H#Qv~{`KSeZSN1a<@u$t$M&or{_*+Ow!E(_XuiBH^RLXxM)s;y;rNa+|M|7~ z_;AzleCB=1?;9U(y+6zz&#SFv#v5CEe*M;7(wnXymS+UtC9d@TQGTPK^~3+o@%+}; z4+|P^Y`wm=)*t@89#tr=B&PeNiUi1SWq+?n=^bl4KA!)x z)_Z^7^D8szNS|U`eqZ_fo?ivcm$$yY@ppY?kLNcZZ~W)$YwORi?X9m(*Q5Tk@y36*zW!f&eibx6+%ANEHh=DXxuE*mdVjdJ z`r6WX{_plBYD)b4f0OT3t^H^1T(Wt9t&b10$@%Q(*Y>{u+I)Pt_4VF@)(_M5jjgTs z7PP*BXNPF1QlD6B!u3&czhX@r#5bOzO+{5{rOR_i$ggWc2;3vOLkckm#P=&Io0;en z7A*|#DqpchBS|hRo@SB$YR;;ui1Xr+1S=lB(3U{uXRQ@+P9%|X;MZHlxAXYRjogwv z0n00{d;#Z1TM|)fZ6ORrritTi7iq)x%)i7P>Rs~=sNOG^<*joERNQab=z&;oJj?R_ zx-)TkLOI^!bRk!PP(G63T~KjZdUwz@zVXr99$8DtqN);HWjA73TFJ^vRsiZrs&L2l zAg)HJ3VGC%Ty;V<-e`zKs=+uAx;LrXaG$+-W88;S z9eC?LrY>3smCw@Os;^8Z>HRCi}NG#M@F|rKvU9*X=-@ z)>K++nVM3qsir!j9k-#rR8#r2me$mc)QoB_Q(u{y>PG#j=C)K{s-sM;iLBk;`qF#< zzOlaQ{N?o}{$DLimH^rHrFRo8s5Ozy1+}m2`Vt${CbqAVzq@^@rqa3-ajI68X=Ph( zU)lAwQ>-P~V{F{Mvg=DNE5FwA+t=3WOSV5d$M#jT!1lF0_0=f0s!S{UW9>^c?BD(2 z|8{@)cl(lMT*3X}|3drH+q$N4yis_g@kVxk_*aZKHhzBnzVSxaILgS3I(~b+k=-9| z`}0d9jkKoHXPL$u1^0*9ah}``LNd9YcT_^Pg;K0wPI19d{I($(PG5-tfW*P*X#0IwSu7)h`Ri0 zt!Q{s_2c?PU9O!-3Z#`EtpjP6s+ppp_r3D`;k#t|Vw?sx=|4{AlEr zjvq8z)hbZN7f$MRLu)=-KS;S>`3y+C2x!eG<6lQ}QaumT_t#o!P~E31KN>k}jX|~F z6VTvpWW{B^|$bk%=h72Iew?^luVzdyMuk; z`OEq%zvuh6@Bi0t%luCD4EjAb{x)5O^mnGeIsN_Vl~vCX_@s`w_}}Z3`oHyUx@KB+ z(Jw7V(5j|>Z*hWFUG%F<5Q=jj>$l6FPzipwyb1kz-=qIszHl`6(f?VLkp5SJ|3c3f z`6$Z#SGqs6)@o7R86`~3nj8Nw`ZbwfreCAqr|;0O(eKkQ)34F*D;|H%=HKyWU6Q*%NKdKRs>YVEQ%y;U_zo6(A^ z(aY4~N@;bh4*gnHN}JN3SEZ+`LaJT7idu;_^odm{Z5*GKT94MXZjUyK&(KDcH;!wa zs*N2umj8rpMBlUnrF#0LPu~XgPrCQC2C8S6o=I9?3-nhN$d@OmKkr0|*4h&KwDOdc zBdF)sYIY$)LQhwYlCp$ds4dMm3lj>_mz1TXOkAtfv%DX7jaKA}5DL?KYUNo^`o7e@ zR_BTmiqOMqbz0+qKHLdf120A>N-wN+HjM##b60euv^f1?H+t$^%1aS?amQ!{uLPku zy?H50N)md~8hTKwm1Cu~W?r-AfOuW?u3-?rNKd?mra#wUaNL_~uo=L09TKnb5U!*r zJ(%23jt)i}^C|6THUw3T42^qv4U1QF7^R-Q(T1=G+HTZf6LcuK-AD~(zcjU>;epy*YCTx5IvC4& zCD`+<9mmFz9*gR39!GwR86RtIJf$Vs1#KMh1dfhF$8u~!yuT;JyLlq{QtXJPJ78kG zGxp{9c=kUVPkvv{nSkp4-Y?!y`%#)__DAaIVCdlrAK1U$M@T87=ix^Qd~;Q&-EU=pc=*e6VFW-=*!+EP9VokVU* zYzI@~8B=3>n@XFj$UbwE$xY+v6m&BAX|ZKYi|t? zsM^G#lvYADvObLTp=fuG9TwZiVX*}qM*d(kJ@zHjV}CQ9^D3JeoOLLAD92`S=3%JX z(9GCZ&7`y{JKRktKZ_&NQMJ5Tgcg?U8{y_Wl%|`nW&m%RLz5dk89!{zzy8`OH$9#H~erR9Lm`|9C>bwPn zTBv&81%x{68>pT47RF->IqPuJyAUtpSUq$B@gh?7&0>x$K(*)KVuDH<&>t)&)d20! zH!UVCqz}l9XZz7F=>O4^TH_}D|9YPErG={x)3dD)?OfME&$iyQ;DmG`LN8isp{TmH z8mmavGik&kRZphztWGwuxaoEp_O zrRHmpu1RQ2?beK{o?GKtsb)AD&q_64(s)*?x6Q5MRnhxGjq^*A*ZWzZjk(3a~_np8UPXcp^AbAohk(4PNVHK}<@ z(Rg(;^8|J@rM5MTDZ+Kn%o)n^n>4%8d+tKijjpj~5gqw$x@)w0pr@^76q+$5@yd7R zu4+hHSH3f6>QN%Z}W;y8ksJbKFmQm#KN2jWx9s z_j+B@RXLKr&(thLGm|>p&FSnx*Sap}>5X*8-%nOwP}6!2>J4Vf2^5X@YjN%iJ=b&}7pML;a?t&)yFz0K-S;`vyha#m z4<)H{J%iLvv;(omC?W*X_s+T0z8C?uGx-PWK-`H`$_bRA&h#A7Go~zc6+Nw!D@WaF z9Hy3xk9tz_r>dEw`~b>6RBtlncU9i!#0zvMmC^#0xxN}dst2jUmDU(jJxf*k8;wTQ z<5Y`%knHz0ZdDH@)u>iImsGv3dNiqeRP}UH^{e%WrK)+&rPZoZc0$)mS4pi**HBll zZM>ds;#F=EM~$?ISF0u3jGV4kGqhc-!FI6*+wr;9 zT+PCis*d$0zZvK4K&}JzuXp~s8+M5IM|XjCY+z%I&$n8fWW{>_`n+R4Z1Ml0U>sHm`^{t0$WL<;M5N*gAs)M?yN(0}lRVB@wGc!xgY&E;o{7f_LbXJwl9Jlv; z&6DNlPitJ7lZy?v#QKX`(a{`MGi}XQHP_$X@890@H(w_xXoW!krLKtnQ}q$q^J&c! zbv!el{(bYkjlbiM%sq8S{+V;>Kk~o)?_3wnn`_d}b-%0aYi`|=v_=FqP|d8fXVscL zYpkG|b@r^fDdieLq_b+xr_;H06H3&!)gHG#pVn+zUWqi5PG{BXM}F^oI-!ry(@A5k zbUvNVt<(8*I(ts%)9KuL&^J&eb(^>W3^XcuIPp32KbXL9f`Lt%z>8yH7^J$GXGBfFPZvEHIr}Jmh z>D)RqpU$62r*rF#=hNv-I-OM)G@njq(&-#JolooTPUqQMnon;!lTK&YTbfU6mYtbT zYi|A5%%?TZN@vxXnRGg<));Hs=F|Bz>2z+rrTKLJOgf!gZ#U8$J`K&sfNvE^wblzOhtU7xpozAT@^XdGVbUL^GBlBs^EH!rPK(AJw&=)O7Tp^A= zHNWi3XiUA7W;uNrf$0ipe%YHksYJRmp%;C7<)|9nYK|gR?T7`*%u6)0?9O%S&X`$q z5vfMcnqNvas;)&WRX?ivrBr>b=9g04x0>@vbth}gCRHD=6;r9k`V9zqalEJZd74dX z9-}vyntf^>lgl$kvr;{2O7V2kOtcC49JDd9o>(P#o@utPr&Fu)_uPt9;rRS4!ZTB|N%cg9=|wb;)I6pTPerXqsAoxd9%@X~j=V?P5^Emg7&mL2 zmp=W<#4(gs11z6co#^dZc|M=c`74lX8S71N*t8;``bpOXT2Py1`OjJsw~IB_F4k2$ z&S}dp(wwrn)6GtSw8oJQ!)$ZNGg^XY16lXz`4pU$I3t5K?J zscYMWR7c7>#JcVnue7ebu5BmEI#LIEPpaDQgz8;g4rL|dJo~YjZrRz(oU8VK@uLJc_ z0o6=LZzs#6<;iQlnOS2QPdcI%vxodb;S^ltML{sE_K3YW~=Od#NqwwIS3%H6GMk zS&ax=qncMXh(r%wW9Hf>ZbwMv?ZmQ%d1|Cp@tH@#aEqcrr(Gws{2AK z0FAlZ^nOZrrsfSTNV|9sYL!6yd1z(F6C77NvV3M znJtU^&CH_Z)jTu1me*x@AQGjY&b{?^R=+$mLzi7jX6ByuVCjrr)?b;KzG$}03V^&h zWL5@bU71-ikoTy}N`k!UWmXt6{Iq(r^gc*eB;;K*vr>_+3(Ajqx|$(BL|WO%C8QpR zwBDh0k918$ewMWwqE!*qY3i|8>n2)1kq214k55-sw7Qb6x}<%W_H|J2rPY{}h*ceF z#YR1!YD6nJ>Jc^9PuF=eD?jNq428qIBg*qxp0lNvlZdx>Cv?1ir};3Zb4@ z^GnTnRo}WZG~ZRM{xO}6{+{#GZ`NPYH*0>azoPFgw9)tH&s_DN{Py{p=j#92*6-im z^EK1g>|Zl~y_rt0j{csmSIwGw9;(ght)ZTP9no~%Lu*`mDyGjv-97awsfFsksfDUl zx94uxlSVDQeZ2SEp}K=Kx0CAmq@G2p=ayQ4RCkd2BB|~v^;A;bLF&7tT1PU(Qmy`3 zVyW&X7w;qWtWEhf>0RSu%hr=vy{Y&U-8K64>H2F!ezo2Ys$QgeAE4)~RPPw{{FQ2M zRxFNU^mOjW{jN1MJ+=GN4m66<)4UHYLhW8p{NA(_^#pqE>piC0y+#GSXjvM$XtdCi zc9%;!FSdS-E4tIWs`cyXDOKy&GgPY9uV=0_ZT;zLqFVm|`hKa}y`JL(%gQ+s zldVFD?6ZEcKijI5XuZ$4Uu-o>WJSUSaMdZ1m6mhX)u2SHd)_%$lad;=hv2-cMTw~C z#06KI5;18BsXC^ROI%@B$muClIBF5{kXSB`FkBJGn8OuCi&EOa6nDj314`<1*OqX_ z9nVSfuwSl(gZ(1UD9Giw#*{ST-Y?}!I>w&lb6qJ?jHX zcAeZXbSSJr7uVVChKgF~>bkh$=x)#jJG!oJ1UeknU?;bu8;Op9Ea>KTa=W7<61ux? zu7~SRehU$+k`wqO_6&+Y1VAwSma8nr+9ai+f$LomSgcjM7cT$r({2~n;S;z0OI}4aJQS&yZ_-) zN4VkcATz=p$XdflH^NOq4>G&Ek)$RQOZRZQyD6wvCiZlDxT)wARwhQdJ>4`^@AXH! zQSM-L8gJqEa--cLW^cC_x)-H~nlWx~cPJ%#XTOgd;|`2g>-2_x zyc_3ckkcFa32wZbNy!Y}u}^dp+$>7;{(WCJ(aokrZ{PQG`?@)l=-vAMZa+7d61{6b z!0qqmQ8L#Y=nf!tIPpAlkUP*F&KvVd?jSdxoZhlec9Yx!O6Hq|W{R8a7E+@3=2P7i zw}_I3yeXebYO$H-rn)8QVza~??54RR&?V*wbBH_G9qJAtf227SJ&fFu<|tz6ba$9r ziXLT_ni+1oJKD^2Gte27E;F;-Ot*}Zqs?+N+s$&zDOqNYF>~B(cMK)V&9P>#o8yk9 zyhFZ(sZ#;6m{Z+)v%#F^PIc#?8_YRog*(lii=Jc7HK)53?mYBdbDml0PIu>{ z=b7`(D!0;IV9s!>&{dRPNcsYFwL8O|=~lZ7%|+%+bPc(S%*Ey`x5iye?jm!ES?kVn zmr!!CxzwEP*1Ah6xx`#%*15CYWt3cME;sAlI(IoGmzgWf2Djc_LCNLjN^_3e;I5?P z3UjVIhtyTXSDN$Ox$Y`+HL+AXr(c6!ZLTred;MDU8gs4DzU|kc*Bb5qex13VSgKv% zZ$Pg%HyG_8exzT9P`kT-j%}qu-*WZlZWNtQ>yUW}y=*{L9qdn+vMQ<^;8tp`{ zJ?3vUx0$QZtI6GFZYP#rxzk+du61{zcbdD*_3k=%H+q-3 z+uY!;clV%on|sWS?gn=+dXKr++~jU_H@ln2-)C+{Zy|S|xt~~itGmTLfZlH&Ft@o| z-GkPm)wi)E%Z(EmU-E|O7P$}1hvsefmiv(02j(O5j(gjEM9GKd zWAmb|DrEAx%{+N;}6CZq0TgWG9;)~c~ zwy-bci&0Y47Pm!wVPBk*Vzz`W>WlailoYo)wwN#Kb0{fcOWNYTm@i35jxA+N_~O14 zB_(Z+FF`8Tmh?G3ms}~EM>-cR%c5m$SzFrY`EqDk zTh5m8rG0s{oGow5`ZB%(THaQ$A)uZ`BSwQX%*%hy3`+d8(6ukGuib!=T**Vpm&(7Lvst>^3d`e;2{ z-`4l_d;_$;ZD1St`o5uU=o_F7C~agL`G&p`B@Jz3+t@eqjVWnlo7g74v2Q|2W82g> zA=Ol|ZRVT$rnZ@F?wk2$%Gu_&g>UYgtHidjEqx2$LM67PZRK0~mMXEWY-``jw^E61 zZQJ<*q3xwf{w?cm8#LaFWO$x%Y7?c~W( zLaFWS$x%Y7?c&K%LaFWQ$x+hD?&!NJMcmo$EyzS+C`tFpFC*2+0*;9u0usv;WPY&&Ad)Yp|x9{uwkl)$%joOcV zZ`;rBYXb&+cLe`T>4dJID`2 z2U6PK4)%k5e@b?>1MCn#*bktjza40Y`XPQGB?IgrJIoLDgD4qj2ix8JFh7`*L3X&` zjnoi3!VmXD$PKnb?MOeu52a*?9cFj;BmFQ+hT7fi9)5Sf8zsZ+aJ#49!w;uqH#@?P z@_YIblnl2c?Px#BkECRT-QDixNBi9=8ENAn~ll(z`Uv#3~ z*G~46{C?=Zc0W7CPxkwx``P{NR6oT}^Ha$mV5gx6lRLm3NGv_XAM6jZhx$X%L;Qhu zl0D2H>L*chkezI&`@{TXN+#JUc7~tsr%*E4PPH@r3_q2UDR!Ej0kpNr11bL|m+iJyngwezfYMc1C_ z^X%dFC{#P6A8zLpOON(T{Q`8pU0|2_qy0j3fn8{q`(=I+y3j7N$N1%bF}lbuw#WKo z{1SVdKNdZf(j)Bg{y2XGB}?p)_5^>tKa!Fo?1}yaQb*a7{E7Z3a!1;w_GEvOUrNbQ z_Go*GKiMBm$x^$F^wH?4{uI9)U1pct)BLIa7<9Qk#;)+E`D5+reg(RM(&Ow(f4V=8 zl4I>EzmnAP_6)zuA5ZQ$dxBl<&+sQua=bm!p6OTn6Dc{to@CefGyO@FoM=zBXZbb$ zWJ*r5r`WarEPo0mC)-o)*?z4*m6B8JX?C4I+n+|ssdj~3@7MVil$>Tyw;TL=e>x>A z>`Hr%-{4nLa=Kk*&-Lf{Rg|o>XV~-nx&91FR@v3|e1D!_P01PdOnZSp-=9gzYP-f> z=r8bVC^^%fWiRp<`m-omW7k^kdcT&Ev+UXS5_Y;jo07G5oxRjw;@44fwp~wp9eSC+ z)Ner7+YR<|f7$AxLly?wa5b2=49>5}ZKL zAR$0PaMwV9px^60XFcn)*82~y3(vLyWCE<99?0So84}gTZS$-%gm2%w_A!XGaJ#R=pOf@+hl%nd(b^@ zquFeJc0akzL^hc%X0Q9%Z6UJRY&HAbUbmIV7PHOlcl+EnB3sRNbHMF)+lg#5JIq0M z!0jNi-Rv}n+(EaK$PTm19CnA?E+RY4Zga#PcDsq}GCwlkZT6r)qQAH!?k9AQ`Ng$89yocQ~^(d{%SxhcjDiMlh~J*P#oTlnY*j%T%%kB;DYX4|-e$8!WHFxze> zGVVaPqmvkSqC3#ZjJwdC=oH4?=q_|B>$oR1#k3Z9S7XZ*HL(KcGLbKEV~d5M9XnB-idDbP?-QT)T_W z#jH;=KZP!3JcFJ_moff^o;-q%0dSIm z%m$$^;Ut65!RWtmlELU}^cDII;~VrfI)w2*^bIXPp7H93*lB_&ig0*4p*-|_a8)!)>v@}n|7Ftpo^-+hG z;mJ4z_2DFCc`}ZMhQLe8@njqwjRq|#&oglhG&;1T0?))TZAG4jV=|8cEvdxQa4aG* zp(T}=RpwbZHngNNT7_rfIM9+RXgph$r{Q?a<3dWR@iZKtNIYmsb)JS35Qz^hsbQ*{ zghUcROTOTlI1!PA(2|-w6DKB;2wGB;SuLK6lR!&qp|yD~P6{oljV8Bscrs4TJQ<{< zF3-d%h$M%U)Z>{rC6N@+lKMOory`OPTGD`L;?zV^K}#C)Oq_;DYG_GAW{r3*P75t* zgnr3$aXL83muM)O9&OC?aTpqE!)z0tjKk3|8*ZEOOq>A?w;60Ro{1yS3^u|h=9xGn z8eucqB)q$3LNnS-HYx9}nbAx(vrWdkYZf#!v?Mw2u36D6(2^9qyJkbPTHaEbWoOK0 zc}q3fp(Ux%oM;Y|w^fr1%?U5zZPnyPbHPh^TQzym+%OZ~R!v?s56pzORg(|R3p3$u z)#OL>S>9Ed6=2M7!+B>d04)he3t8S)O(Et5Atk)6n!-d1K}vXAHARRNhL&VxR@Cy& zYKoynp(VVtn&N0NXbEqtrUY8t@~+CPBx4E7yQ(P(C&`AEMoXc*vzjt!X*fv^liid> z%fL%=njEGaS{7Q8%j7iW(Q>xD&24g-3O0|)jpim=(dIRIOhqCU;3RpO<>URelC8{G z$>ultOl3GpezdABVDg))%&S033Yr3@8WC}mLZ+apPNW)~q%iNUHHcJ)lRWVXn=gpe zfRj8W$5fNZ7jTki zUh)$Cmkd*VXvx25L$m?lM?y%uabHVJ3qZ z2a@GI1w|RmI0#yDhFtJB%m+hDej^t=gvd9LlC$K3hY}eAEjdRnco>nP(311yf`=0s z1}(WjE_eiy;n0!`%zh^yJQ7;+J9?3P@F-}>MRW{#-iwfui;$DCEVZ9P_d0 zWirC!(Qz=7D`bQxpyQz>f07ZNh)#f({6$815;_rDa+QqmWONd_-mA=}Fis}d`#0od zD&rIg$#pWq-!h*HDY-#L_&XxvCO63iPb2ajoa7d{;ORuB!AWkD1)f1TyO zX241AFuO}8cov-GE_#nl@N8(wJ#;QP-+SdZsL2D?^U3o* zgqJ*Iy?{LLBY4Rp);~aH9>Yr>vt9_5Sqd*%%6bu0W*NL>8SBOHnC0-2<*b)5UyQEw zR=`eHLQYnBE14~0Tndd@1wUENxC~CR8h)|@Dzh41vIc-PI>Ub2?;DyYm_c*#1} ztD!RM;3ex>uYt;}hnH+%y%s970ba6^^(Jp4v-OPYU^1H^CmR^oi;zH0Ho|6zq8s5Q zTRm3jCV0sHeC?C@BjTcIU8Jyz&8$jnY=I~cb^W_CeNb~3U?cZ!pE zyWu5!JVxf?CO^S!ek4K^D#MBhQK$?nB1D-pgU#%Pm+XU_?1$JeW84dwVFf2SfF95a zJqWouD20|Bg4`UE!b=WAZVpRfCPyGQN2D;5Um!QXNMR;NVKzslFq0uLn`3a(At-Zb z$uMsyykscr8Iss;K zk@0t^=|q^xAB-0vB$Hq!m!PMU;3bnGCzqk8li?*(SYLsmPJx$9W&J1gbSk{$Th@O; zPrrqie8>7K^z=J;$u!o}y=ly@G5!rZoenv<&Ug(%G6QCE1BN;SUNRGMaubF+6J9cl z^(`3cEJ(?0*0-UjvmqsOy*cO{qIaREbKxa(S>I!R7lJwuW^$kL9t8D!n8^di`*4y4 z-h4>Oe8|Zo80rGp$pY4oVW>YqO@3hg1bVswlKuela1Mx5Vl1hi>%w946OQk~#_{nR=S8$S+ z@RK*xI<$nBw1S`fN3BCEcu6Gdx70dBLQSGrzoXV6%6pH#gO;?R2I2$y9$M0t8ihQ@O8DTu{9CY;a zV;<_lT?uNH!ihjnTuEw`G7y2DxKh+AMG%3WxYDXpA_6^eWjv~sh(J%6XL4m#sRS*d zQpuH5r4qD+N+mc6l}c!NDweXNa1&R7ilrQAc6f3)F`=Xs#k)RP@@DVpXnK@OQ=zDbycqfEum5gPC}&;T91mQl4uEd zNqs7oO1TEqDwSeh5?a!bTBXuNNT;J0WA+LQI%yyv;wq5RhE^|icU3_m0V@UN=`MFm7yg`(5g;VmQ|Tofs<(0N;M)? z;Uuc8tWKmFoJ2b$Y7nUoC(*8mFNoBDmT2!vO(I`FOHwh@{*_wLlGLd7uhfQ?q(SRC z?RKckybhd1I~?i}sS7F54wm{v>Oo7ihoJ$H`p}XvFVt&Dqye-f+zay>5ori5$>4>1 zUlM5qEy=(v!pq<_hL%L2O{RO-#XQpG@Uk= z$vMa5r?I>?#9F%;o-)rdh{yEW5@`cb$weh%JEzLtcFfzl=$*Q2# z+=-udbk0-m+VNB0>+DpM+?k(tg2`y7`&UFdJL@T@ZTXYV>q7i1D2?iQ4RKyHJY~7N zI#u;{CEmq(L=4ri%5{65vfSMm<9prsGh#X(v#-(a=my3f=+}@O<-&WA_1*}{*~F|T zx$jMo9Ob}!@#zW4Q4YK}pI(q0WxxCI=?%$I_PZ~iJ}?|*zx(m&3&Tq*d&`RIJslc6IE&;_igFrN$| z`GMI~#wiezh0MNXoC@1n#7uh+d}^Mx=R;?&qvlzAL3DO%7m1Fy&QZ&Gr(>-1(r}h( zmq|26k25PTv*?V`IGeObD+Xh9&Zhj#Vlu|y-co>BEXJ7JVG1&f%@~V2Od)1*7-MsH zDaW{DXS zac?QbOf}^Ht0_;){Ur(al`?$4C1Xs={iH0jlYp9e-t1cNf+7S3z}uQQd!4RQDI{g{g+>zM>rh)zR!|DBovtg3&IX zFuu>^2cz9R;e40L2}V1AR3j}X8136qb+nvdw9iPc6*_YAh0rcHpS9c~tBGRJFh! z>ha%`k>e*JFp-^to3ru|~tIaZFCzO&1rRB;FXyY($vmPij%c5r?vA-QhN`Yk%_j}VsW`L5{7ilw+MA{OW^Rso zHR3vssW^|cZ&3G8IRsTFl9K0x>YP(ah$rQv9fdWBa-U?>JvBe7N^$KfEXY~*1wYgM zRr7+ZNbGg#t%g?uz=~`h2u!OaHbIKJwAf4oK~g)b*$9Q9CE| zaV)iCQadX1aZ%OX+y~BwaOPp0*~K`AGjLUCe^60o5nMAxy({i_chOxy zuei&MSKN8@vb)51*_}f#xjz^$xwGgW?!GyT{>Dl>OMXMou(}5=IfI^dXWU&V%4zhJ zJMHd3S5BcP-6?k)>T(i2;ZC|+(3lhGad*Pqgwh;Ge|5**4d~6U=rQ-JyAIDeh8}gt zoY>=0^cNVanB*_$5!k9&mGf-O5wJ2?*X+bPG=l z$02)L(9JwW{0i~gjBeuT;us`w6S|RSj-wF5jpzoRMSg)CZa~-bbaDiuxE@`{GtFU0 z<2rOLPdSGmkZaL3JP93yNv=Ux^UQPrR=FBo#WU7^80IQ;CC_2|V4Ew^6+El$g?X+( zm-F=YGemSbx{N2hpCF~n(4{;D?t!2#MVIi@_#3A&hP%H0sx#poiQJ9j~17oiKe zkMD%gE<}Ie{=Nfp`vbaw`~G%_?gDf^&jZ^az4OuUc~000`~4oB$MeG$nD9JwF3%O4 zVa0RNIXrJ{f+5dAXY(Ag5w<)VoyGHsY87UoGkI=V4~w3O&fsZg9gKPgI-O@7)hbL! zr|}e|T7_xocRVAhR^dDJTb@3|yuU^DJR$}@71eW!Y89rSlX+edO`VKR;yFf?brL#} zCmYe%iRc8Lc$UCrC!phb5?Tze9gmLV326}=cN{vFCnqu9vFI3{sKkE9prd)x5)&Sc z>WNIWcoaI4=QB~{k*J>C=0TT7pu>5R6LlVr4&&KQM0yxHlxIGX>Y?Zmo(M&-hoIl^ zq$sle4XP(f5%0n1Af7M9zz3lNdEyisABYa%c~s1N0NS7DRI&8_Xg{7`#n}6yeR-}G zd+&?(;dxg~z7N`)=U}n=-e@nLkHzqNp*?wS7TfQM>iJsazXz(PZ&d_*jq0gfwF2GI zZal54hM*hTm8W>s7Ia0s@Vu{@gD$Av22_dg7228ih7nXKbVfT-<24*Q+6nDQ?bk3f zlyMkUVjZ1mY6rAEwPK>I?a_ABkcqywL)%haCOX>|)w_|XZ5y;TRcKc2m(Jy(w6yN?5ZNz)0xOXG8A@8H&;SJFSyr+tkH$dz2{wjiAAFaoGt>}6^ zv@Y+vqV9FkI=lyq#@9jhW-LBm8`T@L=zT4;CU4T>`8Clmc*7R&{{pSSn|B-2nz4lYqjOK}#!F0i7+4mU84UAh)H^ zl8)R4M7Jaw$aX+_OHkh!$bvwCi&OU)$c{jUi%}05$eKWmi&7_9#F0&bC6ie(%CCqq zlW{T1yNExNi80E@h)a{9G0M}3SChFh%HN1%lhHBC>xgfY=`qUph>Hp&=@qLWE7$|Q-dlVLK-Fp0O5c{0j8l{e)W%Nu2+%E9N!R8ifVjhfXm zjAe~7SmOCvP-V8n`!l1NTxO>_fJ|scm&vI{AR`*#GCI``M4%a5gi}pH1~lAdaH=&3 zN5fpWQw>5G8tTGa5mT74h*3^XEHpi;T%8zcI+W^XCw7_^r7GHqsir}xmUg18sZnJC zMPXB+R98C@+LS0&*G}X%1xhux6U$AGQl;(0c$1+?$w7+!CPkBwn-mjHf+i+sDOQ{q zO++qJEIARX?4}rVLNtL(=tQ0qpvr@aNXJK&9~G&NhbnI>jvW_`sk+xcYVU8eB!Z{TeFXA`bsIdX@bu z;`3Kgks0y(zfchyas5A0ksLAqE2s#MY5^{zB0s7TxP*!bsdnHGRHR5X1s72fq$e=U z-_Z+@C9%y5=y`~fnCE%)93)CC^c;E?LM29e7X1x!C3gB7dIq8;s(J=J4e1hXJ&m4% zfQiJOLdC>HXiuVIWg@pH(Bm*P5#8hHuduZnkltU>V=%Yt5a46zQFbng4If2C=fsSE zK}GFEl8>OGc_Pe*QBgjT=R>IIpNRB9^Z-;)r1}6VS}2aa9~DIu-`XKkaP=AJbUP!!+oz+`?DPPKpN4*Crv*6ucj&kFy8yrc7M*Ip4N(25sOlHQ z{HLI*Yfvq~WOS099H%ql$_c0{CKkgm$D^vGSmZ5aTokCV5c3=h z=Nx0l23Y7AbhI54V5Fl_RceTyjzU$zA*wnO9brcXi0cS+xE&E7vBS|}RDy`j4nv1h zAtGiw6dhuR23YP8^cyNl#CX3!2UBSx20R#5?TOg%AXGIeBE|#J0o1C9Bo9FQQ^O*{ z+#l^nZHvfrKeR79ghizLqN;)ssqTZSIz}YBH>#=`5$;~7s%b>Od!nkc5f$%&s`^H> z{A;v3RXL*Q-O+AT>xiy*Lsi8i>fROYLUoU5d>8a9s(!@jzd}1x4J3Zw8SO-s&~Vs( zC$uBgL&ISH9nlU{6{!}W1KOTyqam=z_NeNQ#3b9Hs!I~9Y>T#`UP%nI4ceMICb7-d zXcYBLVxCcGq>Zv-p^<1S8)?NzTcN6u5)}wYz zoVgxamzpy1=elSeYR$x@>!7u%K@+d8jn)e6;cv&-o;o${?QhH2j`}t2`ESG67Iy%7 z0kmdpgKL010-_jO<0c^QfJnwD`~|AnNKZZkk@yZ&wc_pa9Z*%Bc)a`wRBb0tFQ0;n zRN;x<%fFxk)p?@&@---LD_Ajq`5ly_j;~3;51|SE2<5D(V_CEeb$?=#Wl+@vidB|I zRVOHhSqfGCpx9{IQB@`e=qaj-MKM)*J`}d{f2heQ zSBSz^3|8(C1*v~jhE=W+s)$q;R&ElilvJ)(E))6in@}!Z?h~r1RE}P*6solhkYQ9c zm;qvpsx~t~l2O%c1_(2%TFwgO9Oa3j8c#6;d1a{fvm9B-Y-m=S&6XwSm=#r(s3><9 zRMn$m5}8p|m5NnlLRD=lhLI6f6{^@q1gh#(F^>#rxXob2Lc-B78*ar&!q89~X2niI zQB}W+sia3$6)V<~4pp_R7))9;jZJICX40UkZ5k_PlNwEBQ(Li|RA@?@%8K!%L{r$5 zR@5g2n%t(aqCv^gWHz}KB}#^>&R6s(DXRKk@zEq`Vw=Q@ohC*T*~C^%H4&Q7CbD9! z3DE>Lp%sHofX258tO#vNdxMjkgN8pFo4;>j`4=r)EGXO50WqlQ}iIT{*bqgiq35L7kSBGx|YtZzlK z9crz!%J5s%P`j5#TiQk{_A!18`k=}=;{yp zv3tyl@EhRU0M*qW9?&qxpeI?O!0$8YM^=z|A+G-Pd>hD>P>zJ6lX54No4t-nK0f&a z$4K7+awXGI3w#GKQ`d{U`VQcj<>r$|-vO+0@yV_409HBqN|i{c0PO) zFb{kapgLaqCeShA`+#|{8=|<8dLiog@O?m3o{I7HeZczv`X6TENXKOz5jZbGL&dTp zx!dJN#j28-370c4yE(a=>rMq2rR4hw(yKJb)tL}DLQL!xD?XsXETDse1 zMnztAx66cPM0K~zh>FbWZWn>-%+%d31FGYryInY{qoccB7^<^fce_wj=f3WC=}{dW z-R;t$I!3zNrA2j&bhk@`>PphxE;Xv7q`O@zR9Bnsc4Cn_Qo7rvKy{>aw@Z%dNa=1T zA6gwL-R(r*bfk2*OM>cH>28-8)v?m~o(R?P()pec)m5eQT|RC)US&DIwH&t7hTUf-(#b?o^-y)LUldqe2xv*MDoQFgT7Xf`uZ~%M#sY!sNq0NLTGx}#bk#3>K7T%+Kl(n_)6(bj=kxc^ z=kK4-_pi_Qug}jvpPzp|KRLeNVsyLYb;YXbV2W(cwf}5>Xd=)x|Z*tbXpz^htv3r$~W`oJ94+`Yn2a}_B{0)@jRi_7aPgagM8##T$ zTEr(ixqgqea=hyCpk67t$aQ=C?UFH553gkW9o5GxFMm_@bx>#R{QOPxktdE|R*=7` zIyZzfE6m?V-5NrfvG18#G5)*NH8(9Y?G_5|8`6#n@-E3e*xP8!w0cihL^Z`3kK>?SZoQ zUj@dlfvkQPY7?sPsmiAtS{1Fvr#o7W<5Zo0dT^9#aBRNdpI#i9njDo{{L_bHQkx@D zhkyEU9O`lm>haG2jzfKpK?D97#BpfI(P+e(+MIK9B$dd_p*{0`!-N&v})awaBn2XBt$**l<>*MMbT3zGX&5vvnS-Pm?IO z&QEo567$k|t20h~=gukQl&$rGW| z_eEY*JVW0n>h~?qq3@Ys$7*%>R#z+a`Tk!|EA{#QU&kx;`7Xq7H`otLd_}+iBB;2F z7?8SXiN}Zyso%FajlL<=Z%h0}SCqPOiR*|lsY{o5kJyvCcZmb(?AJ9QKBTKc-M++) z#IV!_Ogu?!OZ&LQne>gIu3@?o^i82|V!9Ia4Wdrp;#K;7QKxTR3HsitjEZmR`$(O> z#l6Jf)ahG1Oy6JCP;oLbyXxrYWB2*keZKBKUw5CsGe3W4e!ky*epdPXtn&Fe^Ye42 z`rdwiNBI1X@cI4j^Sk-~fA8iwc!v)qKcWhL)$N9o6A5F?#yTCEoiP{h_F-rkKg&uq zEh=xI+{Bgb(++_wMAM*I8P!Ey-O|-zUA4VwP~~;15X%$Dd8Q_Fjk!oZU99o=c3N(UIJ~GNP6+=}uU!DAjkIF|zSrR{xFDc4g z_4Osmwy2-IYQ#&DO;NXd)!-|47!8$&lQLWK1xmsvDVZVFlt<^IzRB_kO3Wt-St8Y) z$Ka#h%JK_J#3wNsqq1aHRI6SdRh@c5azq8t0{jWpvsXY>(Vl>~vTkw{Qq6lsR8{Zs zi6|#0XQ4PmgFT@C*Zo>}*F0K(X$3Cn^)}s22H)cPUL3LD`uuscFb>y0|f2$e$ zxzv}r8QPqcGGi^+`xS?k>it`?CoC=zWfWVnS1cZpxcpZ~+Ez9`k$C(qqim#2KqNlD zi6~}?*ohWp6ET;gQ5$xoB_@)H-*;PfswE+km}AnGSu*yuwYABZC*|0-XMbCABFQ)l zI{g=D5doPSgDCd56X5sAh>&`Bjuh|_#2A^33I|09DKTQv- zdt6U;1ZF~2)831nf|*g(y7y)WVHWln_C|XX&C1@xKJ41*!#W#t<>33V6EQn;<>33X zLoo*t<=_Xfb1^3o<=_XhqcIl|^;sUoPRHCt)Mt4xJ0SBAQ6_#cvwZBA9Lx@+!R$QB z&wk2p*qQVV>jLbr9Kw#JA*>6s?{X+RnTE11#J~I>!x-j!X?AaX7?x!M*%GQr$ z*Je@X%Gr-%H)k;-%G{4;muGPz%HNM+_h$(r#kuCjFe}Mk(J}1G8q031aqJk?)i(|; zgX%gPZ^zlPsIILE>@+Qh>Z+Q^4%G6fuB}PzOs#o zYh^0?T&tjRz*3*ns;ItszGGi(HB{d=)7URtot?GQ&}l?#Ft5(8+v&CjS^ODjP4?r? zur-;hZ}Kem{F|Osz zqS!aR+_pxeU|K8LKivjx4b57`zUsE9=+AO zI<%JJAX&x8*rGN!G~Fo!B5}_JBE+29*fVwFYF}#h4nc62adAC_$ce~%*WwP zaE#r@6ByOk__+O*J<7kbH+d3n2FKaEe4O=UTnZdvtodRb)ZBMZ) z`ZQ~GR8>dgGw3wD6wa`V`V70Lr{l5k8@sE2V?6`!g|qCsKFfM0o($*MjeU;wEW8@d zvrGFt>)Fg_;p1?D9o%ymXXCN0&Z={ntADXNtIi`bmmT8jtol8XdAMtW z-l_|T%x9LY9bmrSJBX9`fA%2r z1GqQ5!&T)Fk%Qi0oW$SR!$b~wN0{SjkDvH^`wNPvJ$~XJ>{0X=+{8aJJI1KK!=LOi z)N`Ngar9SQCXDmk3G}#k0#|Y4PNFBglemgocM3h}ox)Yzxzp$=F9biC)7}|I^%@Rw zXV7T)&74Jl^UmTh9?hLY&wA%@7?1AGqvyQyIE=?|7tr(G1suj>y5G?Y_>0G4c9Bv2 zg=4#mXdGN{E_reB#ks^>{e|P1`ZsfR7EZ+Mny1dK*U@XSyqjJ!ynk+?H@)OI0^Ra% zGv30_B)Pkdrob`iE_%ni>#2+DJ@l@3&r5~F(0%ltci&5m^UwqIKCUTga3p$&KJXr) z4^j1UeT+Wx9((EVF?xbN#*alkU7w;)yr*6$zDLi{r`|I!%!Rt==rixR7w*E`Kj?Gs z1^N$~0T-p0=nL05p^a}mgd*x-qjp;S|%6si)#--_vmj&OZH_X*F zI1974URGS4-ZK9W*P3j&J-s9H)_c$V9hx04s1K+*1?Rvc>Z6wv*Qk%oKX{+KT)0Vn zBJvS-*QE-qQ{hoo0XL?KtSh;S%+fHX#>c4=eobj{Hmii6Q)PUd(&2bk8K0*rtkdI! zR>g(ljaC({N;C}5v}!JlNGSeM)tS|B)m=EgQZ>*BoYrc%2<91ZpsMMyPGU8ZO8;7>cL^9!IRR`y`EJW1pw+^$qxVmM<`Km6O9sjqwIAGPq`6>s#aP@G; zs>eDfesT42%&N~i7d~YmA#$6V?UrvTK6NS5wvn@wjV>`&Tp8h48*>hAUWe)Et@UNN*NZey)*&MS@Ib!A&LYu2^!Li`$6xgM-*)@T(6BoK( ztn1>b*b8^M-mL4R_0T@9H$HZK@ULrt6JsCz?fSBAh(lvveDC_PZiI7VKm73ev;GoC z$Nu=_4Pf0Er^f;K=M7}t6m5bIaszSN8-&ANGyEY3;lMYTb#r_p2jk554eJ*8Nq&Q4 z-w@U<@tGXrTA?j*pB&08lChPELL<@PxKXx7qfBdDD~G!_Xlv63H_H)t2aaUj7MIJB zt{vLew8Q;!lxvT+!xM8fvkr{yO-Hl?Iu?)2PH0Ed2`|mDxEPLO-5HO~akv|fXZ;o4 zo8xgkoWQyZo}3eKL!8KZ63(1mO*cmM-c|qE?#$JDcM4vfUlZwWdf@pv1-Hd1tb5`G zIu#ejsjPe95&A9ejNh{E&Ab=>q2J-$*oU#V>5H@IH2fW>;p^BB$In^ zjzLG`vAGzp*0Jaqyf>HN;W`dgU)`m6yN*Z4;oG?k&({ge$K&U@952|3MAT7t1s<`J zh)l%)b0yxflZmL8?kYTGrw~yuU3vabC8A!stC@Wl=v4b1b9K>`tN%12>Y^(T|LH{3 zMOVK4Gl-~*uH5@)5>Xdj`SZ^rqAt1{na#m3cO#Cc8*w_F8|YU%mx%i3%CUbQ5%tfN zWB>O=)IV2_{qu>af36(+7Z6eZ-0jR3qCcQ=?_Y#2#Jg4Q{fp5>c)H5He+jx6uUEPE zFGZK&0W0@@b+BC;=vliAx7aEOw=$~B>M?f|=iQ???rz7Q`52D8$5`*cxA|9`dVgiT z6F=wUIQSlCy$he`6FB>xV7;69Eyq6g3m?mT|R7w|ErL$14k z&++f9>5%Jw$N%^uYdYk*i})h{!I}=a?hpKuFR?y`9!2GO{VRIR&>`1d#&P)yYdYk* zD>yO#$(jzi?oS+=|6)ytT=y5w%~x5|A=h2S(fM!IXVBB=HTO5(&)3~G^cv33XUz?F z9cSq4tk0R7?goz0H&~xHx7D{=?jL zcW|w~%leYJ=kDTWeUJ5JbKl*=<@!GBE9QZ_kNfol)_t+7XYMKf+|O9wG|$~Le7m2szHR<- z&++qq&iamd;r_wr`ybYK%}e(J|L+&9@0owyOMJm!vc7L#xqtBs|CjXx^V+>~4~X2y zb>%g)N9K)t?H)0Ih(F7J?u~m)MBP;1y8ql0B9HNNdFS4`r$nCM^YY%kbI*u8#sB3! zvk&gQlP}B%^aU!vn2+v*`{X`4`N(`iJ^z!Fzl`Uxpd@}`KL(NL_y;BRllU=- zsIzKPX0dECKdB!ZmFrM)Kbao~l^anCKe-8Kdqk_m1|OZKb;@yr)QnSh6Xf@by6GdhoND965N+E z_~CvsB1v&&itsb|$%!Pxtto<83Y*c7@Kd7la?0dq^i!eoc*^W&@>8Soe#+u!_S4v` zeik$f(X=+3pVd!GBn|FS+5K#OIwEOtmCDX6)aLNB`=QL!+c2Bc&*6s=3AN$O!Kyf)VmP4HWL1Jsah%a=GAoJmTTL9( zYB4K?BU~+<)M_&;jZ<809MwaZWk%JXLv_FM5fUv3R`E+!8LTQ>sVat5eJfQZv8r;Va#&Hdu2fZY zs^XQZB01y1%#8^pH!JLRus>)_naZ6S4oPbY}_^5}57f^ZRSXNSbvFKD~$d#&%MXf5qu~Z!*npH8t%0$d6kn&RhyP?FkH*{=qkm< zjBha<&A3W&H{)9jr!%fqT+g^lV={*E(N!9YRXCq8u1_4((AbO-sIJmDj2Tf~rEwWE zp}I=rF=j?}mBwexg6b+wz?hY9ummVRZd{)@yYVfSkXd%dYr%%>oGa2JobV~jwU0Tm$|M|^_0km>MB*QiTtRpQuUxHVAYkP z0Q3A-y()CAs((d6R_c+gz7~aus7JE;T@)swD^`6liV)EitNs{8iRg+|-;82JirVYk z-{nwvJ)k$Z!bkwf9ljK*>-M&}WlE#EZtrlnFN4Y-@h*4!d)(#A z@GW#Np!Zpqv-eF|zKb4kpD&M=`Ko9YzK#CjK3@&3%D2%A?(@~rYJ3~Lc#uuWjFQZ?Da~7T-zlxVP6KQX9Ja zo_l*;`+>W9UE+0MydRj=vmd#)*SDXztJh~<560`UYQU#HoY$~w$ftn_FRMm;8bWv- zt1r2OJJb?wY?m1y^;tKu%jpr(gh*p}?+V@qni3KHUCG-(Ga^l4zN>f}XilUV%y%_! z11;geA}t`l>*!+9ibzYy?|R+_B8jwu`EKByAc{yN%y%R21g(ig z*-g9=w1)g{=53%2EA?95!rMSwB5h#4TX`F3N2D#xcN=d5?TM)4@^;<{IuKFEW%cXm zNTh?^$s2*3Q+Eb*7w-g}?Jgr~{{8@kEouC^k-&XY% zQJ)d{x$X_2l$U8wVRIagycqizM%1!n#?*!_E zB9~cpN9kjaFz;*CHKi|+J}_T(Q|U)UotV{Sr9TmMVpjK+0Yub^SzTEM5}`jc?*aoM zzv|yIh}A%tull+SCKBk%Y)%`xGP9;DGj9WQWoAuRX7ih&D>G}lGV@MAS7z4gCNm7` zdp@AOc_$cQdz;~q-#+9IMxyfZ?Mwb(6e@pT^@|vd%J;WFS%fjD{D23LMNq#9`2-IP zs5()MvxCf7n6Elij7Q}ztj-k^P`M7Pqs2s2Zp7+zF$tAR@h~%#e8Di*lkM<;j$l2- zjxh2z9!dUSDk{(8QD&t17L^zBXfw)uhsq;)j2UgFq4G{1Oa5S*9Y^M1Ix1)7@njBW zpmJQEV8)x7sGOK5nh9o>on$7W6N%2Y>Ju`X$Sj!eWM*^h6tW0&>{Rjxb5Z#{tKY~x zR6fw^L-IW;e`xh5nUBghdb*ir7FcyMS-@OfoYmpv2dkbZKM+?hXZ1o^NJPDy=a|`M z5s`(^UiD5{Ok@$XS3Omh5LpcERj-w$M3z`}V3GT^y0R=|wG`T`ZY|4+sIRlSxU3+u z9NN3cEHo>Ltbq0|HjB(EA}gW2OUz=kn#d}<)GT4P##S^-%^Fs#p}p$ou$IUgXs`M_ ztRu1(+N=H#>xry`_Np($1|sV5tbP$2iEOayA|a>n>H$@MiOsf#k&n3gPHaKtFRp$R zTT%Irt53x?RDR^@U$GsPPk9}3jdjT}%D=pBKt$s>{bd zB75zAtL`8BiR`lnth$06AhO@8SI7Z-&_`~@&nr}z0u{}9PIncKcXb0B6+73qk^c~4H9!KR{--%q~ z2~>Xeoyj$xMCEh;6}iS!sQmA{kZU|;yOL!*jmjOro9SxKpmNRcPOkAcRBrlTlW{zY z%4NR?8OL*|-1mEuaXgR8mA@Am$MZHRxyB2qJo}TuC4NWc<)7RnGZ#^L{HHL<%^#?| z|5KV2<`Sx&0I5t$bJ?bbNL;pQ=ofLB$R&HlriDmcA#&ONY15gs=1(G5>|Zv$NoW2d z@~6FOLrr>fmB?TAZ|3S$5N1NnHB=o8!l4t_YzDZ*b@ZCOZX-+va|68&`OOHOxQVJC zLMD^Z+(OkSA+yP3Zlmg-kj02YWMO^BW({aI)^}|-qpl0t;S%>ybz{h3vYY#;x-{g3 zPCP)>y&;#$X&$2L>X6%rL*!=t$mV7C$mU`G*s5E|V3z%4%>RS=mV-#V zBk~s7TOK0up2$0BZv|7{d?50k4ht2SeGK$o_{i#m{S@fQ@QKJrUa-`w!Gl|>&$N0t z7$P3DSG^r95d-a2&j&}uLMk6J^P!ZFAi$59hd?PG!+syLjs~TC0{eZ!Iy#i{DeU(t z>ljeVXRzOAtYg9|pTmBivsSN)m{4E!uZYD;ou~hWUdAS(&eN};mvM-w^Ym-zWn3ca zJpGzkJXqyxc<&qdZ+uwg8|H6emz8_(j zNl^85`Q&|s`hH@a)TzHmQfG`uHy9J>24jt(ON}ia3WzYgG*=B4=DVA!ha9N-1^r0XgZewQ=O$s)u~2x)>dx>fs>O4(e`nFrbH67jTC>^*%aG)k8s4J&}%3^-u^c2>Jbm zdWXWOdMF*G-k}Iu81j3}Q)jYAQb?+Gd$iV-Oa^F2wWLvbSNV||iY z3F;b7dL_{kkl)kPJCs68LVnNCwc|Ic9ZErc&oV1bjYBDz?>Q+@7PlqFII z+N%yB<%pDp_Wn+#LwO?QpuHEp-@OV%%2Us9ky%A*8UFApvZ?^>RZo&iL@K(<)G}Q5 zDif&$?NtwxDn!)TTD?uG5>aPs^*pIYq$*VnSD96(qTz3^IxF?JzD}h>4IM8p(YXax4uQCLoFgTVZNihTV8E9n%bz^#A`u)$50zphe&Oh?^th)SC>c~ znD1C-_1rjbtXCgZXRz_!IIjU(AM!iF8}Btl)k$okH-Y&iDx?~r>N7Uko8*0oHgaFO zDc)qSF{-{~Q@tr(6ST2w;=c8!dQDOFG5gN@)@z0~bkGte1CTe?}^Os^%87Os_>?alI95ozfn-5hVW7fGa*n@eR>q>FO%yt!T!t4P<{ zeecclS`&$a_Rgm^stu9WuB}_(&G*_8Y2(_tAG`%#J0fjiz6-q{y!J%exkc1RwTJvJ zrZ%brtM)M8CDcZBB+>!qyM$RMx0DL0&S)pd?=mW+zCt@gewTa8ye{Zhklz)aDxy}f z?&?+sbQSAvZk5*+=DV5-sqSbunC}{DqrOJF!+h6L8`T5-8s@vsTkG{id%%3xd+WRn z-g?%(+=hT|WZm0s^m@U3H&Gka2ki~>-Arv%U$hU*cZ;{#>xcG*`EK>Lc>U3SFy98= zR;ni(upZzV22^g*16?C;0L)h|(u2@}FkiV#4@L*UeC0a*4LTU+D>v#P=r=H5xm3%w zT0I8kWIfb1XFiPiP*gtG!_i?dU-@5;K!?M8BdMbtiH?BzMtPCmD0C#uw{^fFq&4f& zu1!GIUt)|?$B8knt*4IE?Wv#~OGF*1)uCb>5p|?i=Zf(})R9^pEhaeixR^j(eW}&^ zVj>asrB+XjNkr6_TD>wR6H#Ak_0X6?WHQWGy)~v1nF8}w&y8=Lx^R3;Ts^AQo#Q(q z-@<&=wPPBQ?_j>_<}sbfG?=fte9Ry+9pYSIgw>BU*$hn5LpiMRbF%@krht)Qgsrbe<%PKqjGpeq$%G&Nl z)s0r!+oHE1*i0p^?DrbC<$N`wIa><8?9EADGhy5^- zLoi?YvmYUH*vYm12-LTBK;`Ft)Yb9SaaTU?$53_RmH+#%s52(ota#2_9W6*Id+kT=+Y@7p%}--_e>?G#zxl~k7snHC zi{pv7#o^Dy_O20&KqL4Q*O^~)H(V$`yTSZA^f}BA^=~@SxSPapxLYoRAMW2Ga?{;* z5zx5XL~gk|P8{wIk=yRB6NkG?GyKrZ5xcfxz!JS3p9uTZeZl-67_<+Ed+Ee$UlM--eHO3%m&i-#b982}ov7_==C2^mqPA~{yoNZ7+Wtr6 z4a8a0_AQbBAkLz;?})sGHjCQ6C-M%;ENc6K$a`qBsO?80V$Y(spNM?KI41!!ky{Vi zoDdbcB@xVMV9kk`g@)$jdWpw(pROc*AI9UmF+O8%)^P%?NxjTHq11Xxyb=8lyg;9>eklXI=UfgQX{-@=xU z%3(xw?diK*S9Ez)-`u*2rTR_}<)>k2`oO#_t1A5eRp#GYiCI;~D*U@DGONZ|mH&MO zX4M(1@xL$6ER3-_|Lbyre@|JoOyJ*@o-vgF=Q4r+ztX67^XR`ro!{lprT^BFXbDt* zpa1joO2uy`HNUmuf!|9pRJ-={8!U=yr=Gqai=f(Xq~lQ-)!sZExk9M+ai=pTKdSw8I=Awn+EW)i`x0_a<_(;uc~Etz(0QF3)sDvC*&UDbI#=Ml&WWnS ziO%I5sCG)~{LPMPkEG7lY^e4{>fFqVYA>YD$1JFJLFydLjAmjCK{GREWagup7@OP)*sd|tk zMyoLX@As?oQRhKoe(%BGzRtmlf#03Z4fXud5vmaQ4eAU@#D8Dvz<;HVW%d12P59pZNSP(h=49nT6kUS^k{PrFi_l(i72Hnw8(T zC~h`ZSp#QRT+TTCro)J2;|P@IPv}gG!;uIht}8&tL}y%VK5;l&;Y2b7j-jrboE#sW zgR%I;<~OP1?D6wl9IN8|BqpC&obSb%nZOxg0_TW+>v9FFMqE!XF*q7Jk91`6ay+XC zjR`>o3@U>z&b=7wpUR-stQM_Urm!bRGx$czrZFn?F%(ksQ_8>_I0}pgMOATrwr9 z^VPyB*(YpuraBlUu5s+zR6jBG74xmmzYvjnRNq6w$Q(v?=R(FhGzqGhkcbH%wwRr5^R9`jqSBuZyP4!z- z-!+Im=X9_i8?>IYIoPKSTF-eL?B52h=L`<^b%WD$)+U9>Q=P#MPW69NA2PVK`$-4In}>T zeeBZNKpl!zf4lVT=2X8s^}P$Vx&x}>s3@xYUAR@Byl|^~o@yD2qq@(jmZ1cy_YT!E zltlI3p<0GgsNOq*{rNIm-K&Cq`?A=wTfWh}qe`gmpsF~kjOt#iT81j9-a=H%P!-jETeS?;P+iNx{)PFiu3ptL)IfE` z2KyZrw0aW>_CYLU^(GSRk6761T_o5yv53{1NU)z`QL8tRV4uZeR&OG~{)@$}-b8|Z z8B17ou2TI%160`y)h{$emAeS`cPwp{yC`GT_pyvs?xL(!KghCHxr=gEeImZjVH!G4?SyII=?`*7A}tYd@yIn}4L zt_}9>RR7L;HrUUz0b_j|?DMI9pABrV|EKzZHnhRMpz06W$Oij`s&D9*HrPj0{X`qv zV1H5d8Es;NeMi-Qw5bjDBUNA0W;WQTRQ*bu+hG4v^)YQ>gMCfa-?XI-_B&PI(^fXv z2UY!0BWIc~R9P zj6szb4fdVw&aP1Pp;bTHudOnoJ*Y$&k18YDlS+gMs4}9eM3{&wFRDs}NvQIoeW*m3 zj4ChMmr8^wsPdxys6?2GDlgifN`!Aw74L70syN2=K!%iz-v9x`TPBGNr-3!Xw!s zsy@T&H$2KJQyT0;JlZN#8thLz#wt^)ii3sdB66jwI9P-#U#g0O#i;V7syJAJE+tc{ zii4%7GNr0GScWQ7s#=5Ps4}IhHCTZvW2#z%m8kNisx?@JDqpHvgVm_=rK&PmgDPLD zDucDC@};UWScfWKI@78T^h~R~=`3muHlWIys>)y^s;sH%3pSz3nyS8FGpekq>I=4@ z%9^UaU@N+ftm*tfzv}r`oF&-DdVv*Z3HG=Cft{l}yoJ;k>_o*`7ExcY3l(QsOnt#_ zRGeiA^#wno;w`Ey*n^6;1p93-WB;i7Z>taYa`um^FSq)0udt#m!M@!q?S5!Wu%GuT zE7}t5^S#=Nx&-@wud!k-!M@;Yt(Z%&U-&vJ<`V29zTS$t1pA9`uwpL3zT+FMm`ku9 z`6es&66{mH*^0je`;n1j>~TtS2V<|*FE*IS3mn>Rzybi0yj_*8PyBiL~nUFJ=F``LT`JwJk<-_M(=pHJyi!e?FC?}WG^#bvLd;csS)@G70bOsjlc_3Jois(1YV-zxqne3@GmN!tLlJP zsCcfb174#dxvC3zgNo#;F5o{@JXduAZ&C4F)djpm#dB2`@E#SV)5U2W(Xf8TqG^hHI=q?6hbQel}NDLQ~F@_5>p+?L<3=O9; zB$kWK7|Ufa;U+fBKLZ+JGMG3nE@K>*k@^tP{)}iQ>O(~PGohKO4-x0jjAo%eM4Ueh znw2^casI4mHmXF#`Lm(fsS*+A&yMDxN<^GL2bz;Ak)$peV^a2~<_r-2Txf2pM3TD{ zjLBUdszp+`l#D4{UMfaXx>SrQT|O#CQn}QOsa$?4MpC;pjHz7#Dn`<{w2Wz7K`KVl zx^#?bT_Gw)(z*1E>0DuIM$)@b#`LZTbt9p${UT^l>PEs`IAfSAM%_rb%fJ}!ic>ct zs$U!}LB)uuehIWB6(gehCDBq;j)>=%LQ7LOBA#CwEkoUiczzkQEY&08`DM{^RF8<~ zmqW`_JtCf89<4z2hdnOPzd%)QCWc=VRlS)Qel1k>W@7lYQPrCjh2hshRd-el zhF=#|)tTshJyf-4qWASt)t-soH$YW;CVJlxRqa`6=zSwpwP$5qS;jI>)n{d)_l;3i zpp}E(H$hc_R^C-$EYE({rbgVp8LA4jig5eps4CDZ!R=e1sz9p@w{MB62CWL*z7-m2 zTA8YF`$#m(M4D<4`zW-vi89q8_N~!2rnRX7v2TO6HEqln5c{@hJJZ(GgxI%3+naW# z7R0_i+Ts7P_a4Aj72Ue_T(f)jgiX$IlQSZqs6+`8RiY@OsN|p^qJl`yNpj9P=bS+@ zq9Q6FDvGEGC}PB%{^#xeeRb~n>sI}zZk=0o?_ay9en-#IJ?ENXt<759;~Aakl4!3#s4B9>MOhU8t-O(P2?g`D(_dpemruq42 zQAML^e!eHFXf(~wKZhzBP4n};P(`C@e*Sq>(P)~Ve*slAS{r8OUqpK+UQ9e;p2R+3 z6u*gerg#2`7+Sj9ske|U!`vz1I@-vxf z--s$gein1=n@~l_&t{H&GpZPQ&8}}jw-P6>+4Zfc;^Z~Ez75?@oV;e&x1&3Vlh?fZ z4s<7R@(W?9ccQz9lV8N_`Yv=gk@Aa~UEhuFAx?e?v+H}%y~N2cWnO(RsyO*&%&YH1 z6(_%(dG-CM;^bE_uYLeMNSypi=G70PuM#i6ih1={(L+SbYexMLdN^??v4$D-!|0L3 z;lx^I)Q_M?6Gsy3%zErPbBt*D^~|UrLlrH*ff@DVsG{aImwp0OptH&8{+YZm=YRI&4#KR=BseqQtEZ=s5x*Zlbz^ljqj zHGlp#s`z=$pTC1DeqQtE@1lyI*Ub4@R1x%=IX{PD>dne+Ei5jTgKIsX6^b9025^AAyRH%FN{zle&vImXQSN2s`)K_-KS9OaXtw+^`f1`awDjxPQ|2?c8_kw~hJK#-3|jh4>>K6^+>K_-ub^KfuE0#c zg*|P=-MqzY`BhZh%^7CPuc6{^-e$J^Ix70+9cIhFMBhi>HD|H!nh(&k<{b7cbI~7A zJC8lb{PTy@-ot9%`y#b$j2P!&1UUyI#Mvmh&|HiP7ht3}nUQF%tDy{nSsBR{J(q!z zYOQIKm43=Nm^CO$OJTHdPy|(uzoHbzeHjDSY9{Fz^G-|2faYe5IV~kGDz;8@kGatd z*aZ6(LyIw1uUT`gc*0CMqw@(y>n&;+krz9toTgg$M5JCsDT-Wrfnq^9|`f{ddUpjMOnP=ImNWNNki zU8#-MVl-8+uk}7^qq>^=&^oBDudct=y43Gu95pxF_56LU@9%Ma>dK<0yRP-@HB+eP zp!p@mcIc@zqBIOj_p0k zvK#6N+(uD$Lp_;t{>fJ&%eM~Pok|pCI@Ic$cl)PzH&4(|*Q)mS;JG^}&QngH3AT%3H4D%Pt1SLn??kJe zXhjsQgQ8VXv{Fg~v;o^%K}GAP)MvW@blKKTk%_ zP3yPR=Gkcd7Om@2izlRYU9{dyO`eU`dr^kddwDim2PP-)60HrRIWDamlaptobz?N! zr?q4>&#HB1vh$p@&WzTdslv0-e5%%^(P}hWizYK3eV#O*svOmKqguNrBlk;d+f-s( z>)vGKsc0Td>)~h>9Ib()b#l`4Y&5s3*?oPsG`Fg!q?Lj+=a$Al!DJuMe7BXp{5n6Gz+E~))3X~m}XVA3Q%dDP)TYD-g6~+W+kYlKCjg0 zmHPQg{d}eVJxu+3nEL-$>i3P*?;EM#4^zJ%rhcDK{r&ZS>hCZ8I{weUn(MOtKYLyp zzsTo*Gyi*BBjxw9ek1?;S948j|Es^3Q+_GyH?w{(SN(teUj83{DeITBelOqiU;MrN zpMNQ99a;T;{;&OB{?EUZ%kj%tzn}lVelP3S@xOmHm!g*NznS%WxfH*YOR}x+hb4oR z&?zez&0T?AMOn!x?{e&F&#tWY-Zj)$GZMUvttFHk=u+$`{A(Cx&qYn6#yOzaas{Iq zS6)nAd3>hia@{BNrNj&f%G_9I$M;VcU*dje#Gx8vQ0(w{&7G~Xnl)QxHD9*MYNl+J)g0L>tJ$$toXJXi$ZCZDkk#1! zA*)gSLssMYhpa~O4_S@jAF}&7`XPImzNe4lp)RWJ05#3OuC*D0>-5hMd||G_%w09t&}$q; zGqr2&74rq#pPMV_XXbPCQ}Y?R&bFj=oz=YXI;$Dsbyjo1>#Syh*ICW~uCto?-ER-r zcTvp?fc9Shz3)1x>&UI@Mj;R9~%*6m&_;V zCq^XMW%H?7&#SMq>#gRp*IUhEueX}NUT-yXy${kYeX!4pf!k+AyzR65+1g+=559rD z)iV6zs8k?aa6i^Y1fa&AiWuXJTi?nw_78e`Y*Ao)OnI(<$}L zv{PJedH$h?_@&W@+X)8hJODy4x@48caLNS!@au{(S0j}%4g z?6!NXq762p8|@}r4XtXX#G1{Y!Z8|{J{)aMe2bnxhKfuCQ}-jcj@^PaYlQ%X2lrov3c362GJ!O>_)4oh)s49 zdo(hWC>yL|l9Gaa)bg6M?E7x0D2h#1aTS~FIXq{{Z}K&L@|%hAq&Po46_YY4-e8l> zgm_|{j6c6QPfx{v?XtVAGNM3$vHxbPSdC5gJ^bfG#c*u4ij+zU3YhWngt!1lP=1P6 z;_-1oJOzmUs7N10RwWT7wu?O#ag{`r*e-h^RCLH@TgZ%yUx^E`S3#mk%HvUlRua); zyX^a6VKX)!7Z;{aA>vJLr&Y0BNyL-wvLA#+%$Rs=T!cP_iGmp&kBN)oDPk1+l|-D` zF8g7qIF-$|m>Ct1j*HQ!s8N(yQn1A;nq`Z*!Lwb!BqdO6|{Z zi`{A!5w!!|!8QEFIc`C>*gr!>P3^QvluN{RDYoZtTK@_aS#=3jl-)o0{|=*gU_2;x zXoL>HTDAwH5jMu-(EeD1cL-{+Y4F5oKWthw4f--Rq{mRyU=!G(=+JmreAT^7kE^aP zy{@5GnGzZn503-dhsFQ6;qeGG!1K2o5syUw!T#k&#-q@`v46V1+$eNZT-^NO{&Z5s zHIH%bd=?hEQy&@Zu;KIIqm18kExOPn=s95?ZrHO>|{#nS}MjD3)nY-qMPd)y39Q#2Fy z0esof>~W4bIXLQ$x#ZxOJB}WAC(sk_Bzn@lhQ8)bp{LyI=(5RigU*m;$Pgat^%#);|BP0qq*ZeaeYc&v;nqae1SVsF@B#rQ<44^ z;(D~@L+fMjptWLLm+ky$J!}>$jwq`YL6nucIN&U{0{pr-qHOrH!mYzoqN0g1(Ox0A zkNuP5`#47aI3px+1;};yOBi-hMmenbq72Z+6@nkgYmmeK;PV>PVUOfEJw$Sa;72@S zp+y|sLVq;3$Zk+MNC&%IA^3^R247aDJmzB9?8j(r?Yg@jcpi5Sa{F=o zkGVE3g6nRB=W$mf_|^PIR)*@>1MZ+J5bSpc&{ru3-9EP;d&qC^Wvf7N*l#cNwLNIT zV2|62T|`;vb~{A{>~?#wyIdiDE$_ltC|K-!>~y<$7w&L7y}s?u*yxXycx6b%TGHVy_!K;hv-(z>U`po^(%9Pe6~?4MI5bx&h!jYT@4N1`+qAF2Cph zG4+C{Tw7N!XzSXc?Oc1bz3YH>a2?T(t`pkHbw)e8E@&6m747P}p>^5&QAQBDq21im z=+o{Q^ckMVqd|9`NGoQU%c0`vTESG6hqn@I_Xu0%f?o06@jdbL@m<*GDZSzs;!142 zKzTlXj<(8ZFKkb2Wwdf!C4Mo!lU^@UUWlJ%yDHif+nZ0=o#=b+g6mD~Md}ya9dQdh zz0vdTJ=cTY)#4uPQ8j)DPYd*%JMX&VtsZx$rCQt)&qMJuY}Y`$W1q&>Kx@SJ#@#42 z(WkLpu{F_}ajm!uR$42r9e2jojvwYa%fgyHg54W0aZBBvcyBCS>XxC)+;X=&-V-l( z`)J)8?}~R*-$hyBcCsa1;a0jG@y=Mf(yema;~lYdm0Rt$#oJ@)YPSYmI>p6Y^`-$DC^uJJPYH^_}012l=W^g zo<;EzbTL|n_==_Il6YCHcz|Wpm&VJfFN;^8%VUjttcY83#bqJyLe*+Zj&2@rz^3tqtN!m-nNRL#y^1w=aKm8Q@Ro1Jc6wT6s_Jff?C7G zaO^O&A#u*b(EHIw=uqqf=>6yr?1Sh7=wNJP^g(nGwh7u89f+Od9*ZB3=c04mT-Q2& zES~2cja#Fw@y>RS$8F--ZVq-9TW!!b@e}cU*N!uu@7iQS?#v8Ne}{5H&pj zo#|$|C*qluC*uY5pYLY4neNGW2IZ-Ex_c^ai_XAKb8X{x=ydEEh zwvRi+8;KX*Ky2jG#1L3PATu1-4l%8l$B9)2OjMuv@?7NxzCf?=u5)0qY-An23>T!g+iAip< z>lja>bc!d^XA6|DnLd+<<6R$bh*uG>+Kc$rUc^tYqP&nO zM*pHj_z!f0Ts8I^=%&zfGV!jfXe~~BdTX>b{i@PykgG}=>{ihJLShBwMf61?txFKq z{wVq=y{jY!yCJR$dkl8VY3~hXFvJaYm1!B`N)i|UNTMXA721k@mL-g=_p6DUOy1u0~g)FQSsc6-ue#bGAwa*J-^LU5^~cy}@2zMPEj2xG$0G(cx%i zyed9IzZK|;cqO_rJ{+Ckzx~Lapy!v-*X(s8I!d1-=;zo&?6)dDL|Glb8m*4kpog%> zXgwMoi$24ijEuAHB*!@s-Q);gM+c)XK z-?i~;QRs|&jpLk*zTpTrqy5qPcuHb_v@TvB@2Bs&co};wjh029U{6H}7rImI^;+~T z{lAHp<6nke!tP`5DT&vkz$M)4^gI=*82bkP*U^8lEAgy|Rz@FT-;Dmo_a^0y zXceB7=tb=5=r3AMQ{IeL<5`7%h)h*+PA&Ll$pT_V|MpflJm07(NyLrEqc z_#Il$()une(%rB$`SC*6K;GPi!rTx8JdO5ql(WPV&mzYC3}p`bHe31F;~w-LJ{9>W zLtP;Vo=S;Al!A%noX;}5-1dP|SZ-f}PgrChf+|^LTk^?RWEZpb7Dt*xbn!G^<2;f0 z)1amDah$xAVXiQ2(4C3GltM&_Po>A!#6F(vR^s=k67xKV*!t6ydFWeg4!(ASZ zG0goPRAleJgFD!NTVgNoiEZq=m8j`?MBcy29`hi!@+5}4+>{aSpP&L%(m(9=cd)`P zA*z0bUCJkU1?RuquCUAaL@%@t^Qm5F7hxCLQczM0ZE5(ZX7KdiM$IVSq2EQ{qu)nA zpg%-EqCZBr&|A?@(e}iiXfL{#vw4H_Sb)BX4Irf|pcOcST!|5Gq|3$Gjc_~Yzn$p! z-O--tb^0!Vyt|#gtPe@=oQaWcl*+Y+3&W*d`daA9IrNbBY@VHuoo5q}f%9ybFo}`&1d;9|?MY(XN3!n-JJ%Zc zz`52!2F|tf*cxSz5hXv$9w$D26#YlqIrNGWb0`jVu!2p=VenJ*dyqcy8&qRD2*96- z&_9G8O8k`g1JCaej!960zd}H!N7F+F-lFv|`V;mSBK;4d2iflz%Fl^k;3hMm8Q=zg zq}O5eFfskV(({+ZpB(Lv;Lji}6ynd&mJo)NOo`v12M(YI==T?`e?m~E5w*ykN6{a# z9|m)5jHaQ-hd~VA_+c=ctNNbn8;u@?5cr-liuw<1y$7kV58cPH-=qAN_zBiC6PgKj z@gn3Y~hlU_b69%HaZvOM026pG)Gs+RYgUwCbIrLm~KFS{DWUuV_bD(cyv-3)CM|o&JkDli*Zbgoe(PfKr@fz9a zpFPS;%X`t?Zez45y2st^q?@A6QPwE8%jL4tGh0-Fy(+r9=yNx^A=(&KcAKLu=snm< z?mhmRS8{ndP9<9Ja+TcrXhT%RZHcy`m9ck4d0cLH7st#RmFH*`+@18Vgy!Q6s=6v} zYg8@T5$%ksM%%GfDb=DoXuZ?j;qpiMqDma$E;O&pT*ke~>1Z8*P zjwrv&=kDOO?u>>+_tI+!WoR^#Ub_>mIojP(>!^mS?jGVeEzyEefoL#2hoCjF6*Q6;aMtdPro{TQQq6~^^vBx0F;ONolURT3C%8^?~Pw+~6 z5>K$#lTq8~spx}5Tgr!t7QEI&u7xWU6^z=^@?oMKY?U!(LCIBe4~t0xsEA z;2bJOOQPDm&JxO?s1>jBC|c9q>mH9rv)|*CHc@+ycQMhP@=>C>D;yPyn)50xT=}S= zD}WZ@SdT?x*yAzE<536p_$bkV@^NA@$6pdHj_P0^iE6o;?h%gPDr)A6M1|499IGRH ze4OY=xs(_fjpaxKDUU_BbNupXAy?2X;s}eQMbUlOhdIt8Xl+-^HFZU!B2iP0*36Zo z=j~CssIV*KIz=6$ONmaDPZ9&7aU693Wni?BBP>GeVsDFzxWeu>`j?AZa$XJib9G!}S3D{fHRc?exGquW z=yIY9<VyLzr$ z^cjRwH;(sNqHi>jBlV@c9L;5~d1ymyQ+hT-8@T$e3EDJj5;b%U+)L3U_IQcXH<}YQ zqVF8a+-P=mKU=dYbD}=cWP0_XycErf9-w6wWpJ=uNU1q@{d|j&~E-cY>SfW=0Qk)R~l7QSWF9uhyH=CweiO%GQgN z-q8!uG`3!#ycj)C{RMP7Hc$9f;zlAbnkUQ~UQc{U{maBxiSy)d_?(;)pOItYz2H-9 z?(hbG`E!#u>P8}WIM$A{`RK2FQP*I!E(Dk9b%F98I@4Z8XV{tc97nlA&WiKc{PfI6 zKC0Z|IC~b~6>?L|uorxes&O_a-dAigee#oQ>M9J_yY%>iJQ!!OAJFrCbh@2kbCBQa z75h8HSaSF~4B6GhPW&H`J>v`R9Y&I<4Y6#ljt5j6a9n#Z(y(P)Pk@_)ICa| z0lCVaje0~OnjlwM&*<4G4o;C_B&NK9zCl)zm~t9D&Cv{fLNb{>7xj!RYRF{PD|#-9 zP*zQ3-ftGS5 zUHfpVZ5Or=r`V~sMmWJvwD+Pl!VY-aht?5lRo!`ZNql# z-IlV4TvS=;@f5y2{+Ev7WIM%nt+D`a8hE?%RvbD*HmW5na zS;AVZ4)s*Hmt0GG$rtk^nPc{o$7(XY3xt{IRe-`eg6uQdR>5C~dR4ZbV88uALGrI< zBv)BR`WB=VU|q2)suWpZ`46@(`fa&VhofvpE9 z_lGUMnq1v!LnG9rY$SyS= z&lKvDQDr3?hp#o+sK$A19n=q=#XkjAp0Y8t)DL=6e->4?veEeJ2hUOOiMGRz!dE}& zMg2K4m9?YxJhoRbl9u}9D{Ig82)616FR=AIS<7AsUPL=!M}?*M-(^&IziZ@1hK*c9 zbQE?(*d%HkjR+g^Kg5V|BzAOIIw}>7rvE7NPBrH5^l)-cHIByMA03Vf%S5H4-W>Hs zGE&WqW<V`&`|j^)mkiH3$V_-j3sJXSNJA>nlXb`J@MVuys!N4=uK z;SfIegLy`!$cEL6zXF4>rO;Ag>97yS?@hL>LDUCQ%8*rSpw}|w%InWo+3+R$^a-|- zyKZc_mC`xf5_Ar`pj}uGZ3``(!_7fga*k~dx{+;cbFhW2ZS>ztE~%%%)59#k!~sf=aBH+90?G&)ux3T8a9dl!ifNJok|2 z`A$m~LM#~x$phUmC{Jc+X(Mt|m8aH-`W9BZniVJq)GVLSbt~&% zm9yJe`Klb*rniNyIdWy&n$=gU*vIT}-s_Lq5xm5b1=J@j4L3Rjv@dnzVWW*cD*3e)8XIIq@ zumd^A0hA}~VEPQQb2zKn!5p7=YmU#j)r?~#+h&vkwmAE)ol&igzZ9TQ*2*+HP9ONUfUR7A+(S!Y+u56FM6-7 zX&+>}2-+Asm$RBf&bqy%3i|kz+t!?YrYxH;uy^j5w zJ~!-Dw%elDus891jrI=)1TU~h9s2_1KKlhd+M!pm^MaB*mwBB3T(a%$3HOH2)9XI_ zJf*I^LcjLt7ua6->Y{aRJ^MM{4(Ju^bNK3^^=y6n8NLo^2iwv1#8)4!ZyVV8K?&Xg z^Led#!L#@p*k>sX?WgqXgnowYfv=&>5M_+|1sN#)gY?l&`?^gZWr$SoAKbK=@MnxN zMK1^ag3IjL*;Wk1H-4ZVboqqpoCG!6D6yicPaV_g(S zXV5eDZF>>#Gw4UyPQgn-U)Bfdi0u@7W531ot^E%D&VG;favY=U_Z|sNc*&V%z z{ekxHZ4|w2-$5Pr16sOU8@*%SMI&tI;0OC7+6ikS8@-FZYtPy>;mTkYdG}V5hcArI z+H*FH40bhZ|E(ei-%6j8Zw2`cSCPMO6}pO?hU>!>v?Zc*_B?})A$BF1{#KKlZ-vj* zx18LFU4kF&E!&06pg-Di;c~TwtS%U=;BV;5)K`-aaRq-(`-VYu-o9spD1lYJ#c|;) z;W9EUE~nSa;c`m9FeMk`GHU(FLAV^-HMnJevdT7k%T5TFlBID1dyNm5(%v8K&;N`Q z@lObqh4d%ejqEf6 zG1(!Nsq{D7o$|X?rc$rGBYOnz*$e0e`#$1}5za(shO^KGWY`RRj>>@ABI=7c5=Y?E z8UzjbD;5Ne_&b(1nCOxyo#LdR6A=nYL1$tVl7iZC9kdRyL98he7eMn9i=_++N8C}D zKe$GG*fk==j!=JzsJ@rtzG#79u_G?PEkTzMzfhRfJ+k^WKi!h>mVb#Ascids>g-KTcMy4%ClQKSoxqj?|A(KT1}uPSg)mKSEZm&eRW4KTHOltkh1~yd3?M zeGMzRLA1fko^hh^=^<3$3N6eJnzs8-a&N3PIR{?9rk$AVXr40_Ic7_zb75UR2;HdU@2DHRW>;g z;{ZQ`=a5}vSK~Q|N0bB91$={8hHp$J>NnAEJiVaR&eqWLDKe~yamWPw@U15y#5J_> z48t1RmR`xh4O+iu#gv0^0N>H;plt^UksOF&c%0Q!L_d5*pBpd^?eMq8{}`l$xQ8$C zf8|Mr)}|)yL|b|W;yV5>JB`4i`M>@V+Mi>&$m=4`gn>#+6 zzG56|ap&jYOAbUgO!JgNeFz6p3}PF8fNK!xAjV<0=NhVbZb7_)I0(@T--luxrg}a> zjKds`cFXe+)r}YkF$|TBc!uxDT`Kya2Kg2@T5${ChGG@&F)zh^*h_T76wfU*gmDlL zaWhO8>_PX?J1?0TH+s@x1B}Ba=m^mbli?Lagq$UJ?QW~xS}G&EmSnu@q8JIbP&5B2I2zkyX-am*U5}4;z3-4*acA$VjC)WhM~N< zN}p?F%oPbCxeCx0^3$y-E&UF%Y5~#59P65Zy2u758w3K3{|v>9xx<4CRdI zhEY%pA|XDf^-3tZK{Uf=tVo87p-6{aRwP4NQ=C0U#UFd};S$++cUtiSW#AdaHHc~u z%^==EY(oxDHDo8_skjGG4cW+eD&j#@Lss*1DB?jRLl*N3`D(Y>U&&M}-3F&1x*@Zt z8n#0-h2J7t=$Ugu!C)p3>nNHCGG!wye3h+`1_Ad(@4 zaY*Os2GI;+AQY*e!Z;)mgD?6)B*Q>B2C)tz9R_%YVUQ;sqBzDk0386!AZ}r>Cmk$I zgSZEg4*g&k#5#y{c-d18Lr}30SDm;A(G7h)$&kW3gnSPY>mZ(C7&?qL@eIRJF%RMy zMxbIIL^X_raS-z$sv(7O_>1`T;^t4Z1kXtfLkis>vO&Z{*;vGbNC)HThSHvDaL^5D z{zW>Jf^IMn4Yzp`LX3kr1`!Wp7}B6(Aw)NbV-Woy#-T(kk|C`r2C?u7T!Wa0bo5H$ z9sYrFC}qSkh=CC4P|Ap8xD4YU3L*pCLrK_$lBNWV!)M{Ao^dD|7p7hWO-F8KF%F-F z89fOh(%}zR2!CPNhIBz8zGbF^b`ZmG6PiJ+gGh%Ix0ybi@6gXUGZTAnrko z!>>+sLnF^Ke_!ic=IZ4R=E>WWb-%(+!oO8FJWr{I8h%;`I14*dNUgo@}TLO@0g3L0ScZ zAswyh?N1O7A{(m0CHxHQPz^TV7xS~J&Q>+Zh6)fFeV`jE1}{?Y?Ot+ysQ1NI3|_$V zBJ@H9YA?e*R3xVVSNMn;9HDyf2)>FadDv_(`aBQapta&!dG6skJiVYBk{}u$_1r^G zJkL4N4dNKYJv@u2Cp<%i;8`cSK{SIHi0*iLIMEGa8bm*cZcr@0xCikCznXhFlNvA$ z2VfKSQx3RS;T;M>H@u4O^WMF_cGw-lE_8>{J>PznPkx$-RMMwNn^}9Zp1p=!V~E6W8#EsqHxj zaSfsyL_3IU5Z&+>+ael7H~h_ZJ-CK8um*t@t?(qgL%kqj11oajN$R0ZP&bec^`ILJ z8bLbLgN%sKe>h5gde%eR!bH@EacGOSckR#)u07h(bwE40j%a7s3GL!Kqg`DWv>Uub zYq*AP=rb@5t>GG;K`UTe(^?;@;dZzNu?-c_3e2sDZ4mEpJKLfcQs@RT4I&;yH&jB! zJ&1AW<=F-?4psieI6UX+1`!M|&{M2J6|@RH#5LUExdt%}A|XUQT!3SE4~n4$TVfol zv4=>9XFcO^4w^yqgBXV%o@Wr_AnrkoLwC9Fs&vdkcaahWDfar$3Pz}pG@30)wK~%$@cpvP;5+}N0w`Uucd%9tl zXB$>{x?!hh8&-O{VTWfMR(ZN%JH)~o&pWJzbSM(cgJmcZ%!hO+0^P6=Jpk!YB$x~7 zAf90xq{Do+7h;P9q8qk)s$ngR!$Lfw8@3Pwz8>mfal8o65=vQgF?K1eL)ls@&Y77aoIV5bGe)A%$)buP_(NL5#y3&o+p05bYptp^fJnQWyuZ3y;Ea%y(iV z#5N2h%D4&9#iAQ#d8*+F7za@i;u%sHhnesUPsKAl)sVtCO!sVq7zfb~VjJ2)H+1l% zLwmf+1Kr)z4I&kkExnE>6ht?OOK6J~-7v+I107<~4ay^}Tfv4(2M7nJtmGTxNt6w-xP>)|qV#+zR7;3%ScxjX zycmWT6QUc$D~O5^<51P}3}PI5(?g6y6?7=IOw71i(sY(r_!IFx4ldK5!6T#rOT++e>Jf#?RY3*sKcDy)o;KsS^QL^rIU zF7Dw3lMNO+K|I9Q(GB)G8Xe)NM=76so?(?|91g=RtfnSvLyop1ts z6HcNcd~VjY%JE_-faZ7kB^U?jRhyuwNBH*gXy0#OR08$>~f zcM#(sHbSJsCom2n{K6^r3*EO+5iNq{o_-MNaEW+!(Gj8>L^FtoSmEghkq#e2Fo=E- z>F^I6gSZEg4j(}YJ3;bi?9r$8^ke)fe_;$fiL8e#vz}l8^kDxoDkO_MnNQmc!w#TZkXd) z1(6POIF=X(tuHeiKH~2{goGG}iZBlQAPcs6LPCtgY0njiaS#z9mS8xHLq$&*h>chQ z-5^R}nI|1YX^3=KmJrt3K5EUWPVK=-LL>kp&U$vScP&4aSh@a7J0@&EX4> zh{+fU10lNMB>aLHhm#4>4F-)o>0szL${zRe{wF-?Fw&k#h;En*6X4(=L<=}rlApMb zTEQuOLZm}FPdA8E5WnyTE$Ps7@Cc$CwCYm^I0$hIhfr}4ztC57!$D6lyei&-KEHZ; zAp>NBSP1b6hhZ1QL;UHP36TzI6QUcm!c-<`h~GQ|A;w`p1cMj|kq&7*t8fH8!coLE z%&{K^q8~&$h)3nC}PIEZ7|j}_hUb0D4}6O4lh39T@& zHzB&=Cm4n-un!^`vUqyo`-JEQ5e(uXL^s^>^g>ooFO0S#9llFwZLwKa#6k+=kS*~8 zgu{=4NQQ3{mjW>mVjN~dH;jdh5b5wuLOeqXZ};buZq!_UwS zzy6DK$O_l+Q`8KO;b-WcEKmYaJT0cHo-XLf=b95iHE4*DzevI5D*(7 z7&gK$h+Eik#-XyO7sNP-nGoZU$Cc-J&4N4GFE0c`Uibyk z2vwX|14 zLZm}M&p3!w5EW68W8{Y|$PZ;8KH+^x1+fm|8bmtmg`A<{vFLH;7jdA<;hi2v$OjLpx75h)WPlQ9cqaA;zJg6Wt&#L2QJGg%rl2 zJzRn)ip7*VFb?7;#5mM)q8r2|h?x-G&;iv-A)*_^B8Zu|omVIbwNTI%f^k^P5kxxN z2i+iALZm}&7>6Q}SOhT>UzdO?1Fd*F$pP*Ll;jsh)WPNA-X|Ps3IZec}_y4 zLj&jraS|dO>cK0Bbr9)L-!l$fiB&RNc?gjX4TxYB>mbsh zA&kRB&n}3K5ZxfAK~#k325}7H9z-{YIS>yaxFePqJA4B1=oVB=yhyT@Fg}W z_zIg8+`uLUUt`G`hE0NQxQTv?O$sJJu_@ML0*u20M9_V3egQ>8pJ)k zfK6c>rg_FeakAnbL@ay-sUX%tbc3jcuOJ=7BzzW#aS*j2;z5i<9?vI;bQo)IB=UJG zLZrhr&p6D4SNJp#-5@IB0{>^s@QlOxKsE<#q^0NE zFb?Bww(u|7yFoB?gJlripeTOv5O2}z42;9m5DkBO2I4fHw_qHefoS+AA^Jg#gUAMP z4~bB$gGh&GBQXwQ7eqXy30{XjNCVyQI{GFy4RphsXj-iCB!ozZ=U^JdI*4>obhB88 zm|mhBjs{22W7s%2j*Wv8*f=* zl|9vPUsxDldRT?JY>Q{83(p`fLR7=Spgx|vVHjS8c@W9)DvU#V&nt+H5Xo>ie8M64 z2hj~89gaXch;F#cGYs`Z(G4OS#72m55WyhsL3BeUv>{e>!=q@-Q!Y+>TG)lO5DblI zy%TOBhJO&raAzpG!J%n9=^zq9Y{MPU42`HgOwUI=-5_>B+(Sz|4~He$CqhL?l)^@y zZYYn6hj@rSEs2ARSz}yuLwU3@R&;~NhQ?UM+odoL<-*29>WiQ$#=A<4LmNm2aSapT z93BrQQ4`b927X~Yo(aKZw!}0%0kiN5p79V2lc|ewcnY@RF}!2ZacBeVv$Tk5cnW@D z44$z;PqxG~w1r?8jb{urLr>2%w1Z$6g=cio%M%VAuwoi|K`@NOKZ-cf=c$jNJ~DWL zdPgEVU!>NF(h9OnQShd%TX-O$+c3}Zvl4I&-7h9Vt0 zhg+c+y1_e$VG!vc@?jf&8^bU>1N9)1L8OEDhwZd9MjLy^p*!A<&4u^@veF^qK@wg%# z`q1xg*aR^S4XIT^@3QxJ-a$M=C8&l*o^iMb*5MB7cfvL_qE-Q|2)ED(+Cf~y{m>2f zd&XfaJjN_fRETj9H*gr`}#W>vVSp_i;l{vCVhRQGwBj6MsV_T#{Ypm#o z)}CRg0^=YCLUcnpPb_TrjKiazXAt8c211O(ut0P}D^D`yvQN-5ED*Pl!Z_Rpv5=cK zaSOR&97JP?aS&DTD!hZ}hO(Y#*y$OEhpl)9F%G+E6VI><#v$Lo7>AaS47(v8#53%M zamY`LNQZ~4BI!$6kqP-xkq@F8hCnwA`xogj$WsbWpkf}xI}C$V5D76S5PKoIK|H~M zaDOPep}7^Ykn9~x}m=(8LB}Gh<*^mkis}Lv!WaNp*65#9Gaqq zJmXLUuXu(UR&+xXv@lk5LtnHeR@_2iv@mURIlFzKNQb>J4mIf^hM}ev&rk#v3n7xB zC@SVbbVDCcDb%ux48GrrZV=gh&Q44t4R0XQ=B*hW4oV2hk0^JkLj6>f*j6*t4FNkpvX(7g;xMvtTqhcgPGQ88xSE1{?ekqjw}!wMJ&aSx&w`oS>tgK`kFaLab%Rl0h*K{SI%2oVA) zjKeY*2hk6r7=E%()4v-W!%}F4NuGWX%kZ;(hSsOy7{onv$MX#OE7XHnhF@VEL_dgh zSRC}g(;fXC_91|4V3C2K2X{JvZeR<#;R5;rq(cyN=NSa_gkgYj_?`Nn@D2ft!=LEi z@D2ft!{2BS{R875ih`B?IClr#uoRsSkKo`M=A#S41?Zx1A-WjG!39fT930oW1dTn- z(2VbE4!WTk+5*zSK|P3)aGr0N2hpGto(JDxJ>@Vr6xlE*oQ)c6f@=v__nqTA96F=5iBw2OY)~CEnYf~KBF?G7G4A{{Q-Vly!+;DMj>!Go0<1(CZfOf?#;wIH6zj4dJkvh zeU_egQ^Vda$-dblwYj>983bazE)?U>pLwRgERPXf)*z~C4$SYzq zpo%ZQ1Dg?5T>G8aOsHb+D=CLCk#?21Zmlz#1r=?ejKNt^aSr!jvylt<9`qizwUTLN zv@+W{h@Y#1R$*H!TUGTdpK8_9s(5qxl~A=hYIRs2t&W<9thP1Kn%F$lazn9bHPw7U zEo?qYUig*TY-uIdl+|8i(P zwLY~Xd~dGLC$s^zqI^qk;6JSm`P6FN*wp8xl^Ori7B7-(M-ezf!*+ zrhY$6{eJkrZ@eq@^OgGfO8tDLe!ldry9Oh&8tKc9=0HU{XG622;-Isl*--J(Ss3Z9 zj8@u)hCWT&o&UY3~)a;Y(w zVg2leL9L$+`LC^qp8Ee+>i=J<|9_?a|CRdxSHL`SNoFil;|-J_CiVM<=Eqa#Q~tZ- zLsCCqsoytJzi*^|-$?zwk@|fjb$lb4Zy0rnyt|KxyVUO+#7h%<>3kgKe^>lQ>i3P* z?;EL~uhj1wsoytJzi*^|-$?zwq1dqho%~Dc_l?x=8>!znQonDce&0y_zLENUBlY`6 z>h}#%tJOWVni?OKI=`G6&z3sgoBI1J_3vSVEDovhHmUKwsq!Vu4w**k?#l z{*v@$F-cFJkhGMXKD$XSGM(fkUR`-xa*_c>k?YEXl7pEzMXoDLN_Jw5vl62o`S^9^ zP{~G=afHYC$aUp!$-?U>$BQzzWajmh<3;&fGV$ul@uG9ch#K!T)Jl3^Nsg|+1zMT6 z1f?Vqcv>^JIHd$xM3f<=7^OI|dCHtplv0dbBU+uc2&E`FNR(-%Fr^5&NtBJHkk7+X z2!CO+m!xOAfY07iz~6xacnUJ(nuIsMzX$oLC&SL`9^|9sC$>BdwY>gL7EWTVOIbJXZMOLINS zU8CzP#q}tsjjppK*P|>qy3P_@iQ*D(w(Z!u1s9 zs`bPRb3KK)US+Z=#8nmKs&$3U7<8DS8e?r(G}+5 z3UwFstn=_Zb93!_*15S}y|47FbFrPErasEgqa!IFPg*=_c}@A#(vpTV(7tKt8}rKA zSDt^rZ$s{peAzhvfP19t$V$n^J<@e#p@^Z-b!4Vw;U4Kdn~9=to4T5e6wwnphYS=k z6gs2ylnmS>ol81OdR{^Gly_`_R;%6ub!48=>4GM=>72T z_ki9(DS4mn!G@lc387{5E)gkXC^{#xGnS&KBSt2oR6;BHGq{6Vj9+(0D6w6>Up?bQdv6)dl z^-}&bu5UZ~RF^{aInTn0g`Jt<`v!7V&&jQB--K#5WZ~i=yJ2QlD4q z^Gf}ErGCCr{~o6PJxu-oEA{(E>i3P*?}w@14|DJhKK1*2>hG`r|Ns8dsAhWqn_0h? z%l$9>UjEO&luPm}S-+qEZ}`2eOdy5*Z)W{ouKr*8y}ZKY3Rap`W+iqxWrbOd<_=cl z%M~p1-Zl7g2TT3-D6@w85~HzzC3u#a(Pk8$#dwyOMd)HP24C)AEH-zr5YHkrj#{2z zoEeK!cmes~)pCdDUZfo|%izH}g=9aUA3L z$L%mP)Z`0ZH>XUtV7M7ZeF$Z!d5!H;<_$D^@P>IEJJ`34FvGDY*?!HuNqhF-HJgVK zkJs!;>`{(<%pSEGeH~=-GWs!y-h<6ZG=DJCjKH2?-;?GvduI>Y(~>_JNY6p$xY6j$ zaavE9wX|msI+*sf9>ag!97T_rj-~^iPT2gx5j;mtXVZ!LVd_Ur7q;>Tho~PmucC*{ zDVvw0pR%uEPuafaCF(DmzGy%5GTPttLkF1t=s+{T9O2B5+9P%yXK=)>H|x+1W<9#m zY(O`ejp$~x30=z>9^_SCHOWC2UN<@D${8dF-Aq^XY10jT#yo9S+UHF#^ab-g`l5LO z?QLE}`-8_T#Fx}B-O%JrEc@}-n^hA4^=gc9y%j`sVn_cK0vm4!O_MrRB zUUa|Nhh_=(qdR%k)pnIl4qmkyXMGj_A-e`&a&QpOt5#!g2kkc|6M7T<#ynxx*eA_X zXmaqBc@o=(@`U-;d}9vUujzBsJnp@Zo3$LPEq#-N?`S(VX@&n$Q;U}5 z;B9jT|2yVw^b!26%)90t>JL+Y#Ar&?Yf<9pGM;|l~ zppDIgXcN=e?BkgG?LPaV`GERG^C6lcxM()m`%NQsJyxUQ`)qp3UaL`Y>0Z0X&W!If zbGj+|ZxQ?lf&cx1+YjKBX$Ft(v)N6Ccr_pD6JT0zo>X|w5 zY*we3N_|>9HEv+)oA1Lt_J^>lsbV(TAHyHm`jN8ReusV^R>oV!R5qLJMqABPWort1 zO^v6-4NU{nC!WL6ZiPRFyY091|1PXljU;k)$z zn*KM#d?qjVt`dFjGIyet%nkfshv&kx^vTbD6XX0QAARyuCdKDz*=^5LcG<7!c_U0V z`OU;QnKB{1!)&&j>>V8EPV*(LUxn|5=fhpLBK|u}0W%>U9~Usm*z2@@8D5}$m#si+ zMN^RW@o_=QEAcg2uZQo`zRMOeuf*fxLbSgUm#1e1bCuR>;Rm$uvbW39DYQt3@v3%aZ}8UiZ6v9<0*}&jLB(o znC&(vWt+{8<}kVNZL_(t+iW&G*-ch7o5^Ex{goze`b@(?6BMIZ{e@uR-2J}CX)fpXnqfW!;_wR2J=VwJM}-qKfG?WTWmV~=}kJW zV24dImpIQP>gmj1;TF#LukcT7TJuSGDNIXilKDFZ;{I_Oth9gJFE;Uz|A)P|fVSdT*R`u^c2~n%xH~M|-QC^Y-Q6Js zf&@(hB!nm-0wF?#V1Wp6cXuHn?w%0iK5xy<*xC2&^Z$3>bIurdkFmxY^?p@fRrhMG z?&?`j6{S*yD9MR$8M-VvBXP-UavUL**klbUOK{0YJ}0>!`7@HG%<}RP^SqekZ1N4k zCa3&bQm6dcr2q8mlC|hs(tr5%$-3kZJb(J%eI?Gt?|A<3zY+f(t;`v!miSbhs-DED z2(5;#kyKA2G)kpXRmrWER85kUPgO~Bq!Kj2TQjMVq*65rE>$aWDT~&`R!(xJa-caV zmyy_%No6Fpu$7W`If9kQt(;U$j=OhVMLd;~%*1dUGbw9Qxss}>DrjbM%H<+dO;w;| z#iT;=o;&W!C-1xW(Dz)0BzKZ4sglY~sGQ2eUp~o7PPq477PI7>aCwr-so#7aN>xsk z!;_ViMav~+(6Y&U{wx2bf8W0s^h^JRKSB5$eII+A-1pG0vG4kCu*J4eiT+=|}8W;(76P=YRD;i(qRfzxtEDHu=B$Zg{#U-IAi%I>|}@i?2ieN#7Mu zx1?)Q3|p6+UwmD{&%O(uu1S}qIJRE$nt#>TOMd29)T7kTzH?H7oX&(UNqzEP^_`NE z_&O0fCmoYgq&gBhCHW)$I$0pfA4&B)WU^sDUX+XlM$Nl7`U&$;}saV4kH? zNe4p5BoCgvQQ@di)W{SjG)6VLU~c?*qVH0LqbBCNltv(I&r%(dT=;WG->1GyH8tN8 znwcL`->0PdT`!Z|T+xrIA5zWDkAxQHr__%rwQPP){gi4+s)bqP^(*RPzsT1!3yClC zOZ;Nu3y3fDOG(u;^NBC;XOOB#3+b2C|dp`{s2Ix`wfPCYY^GV}cqpBZIDL;PUu zTs-sqP@fUyjE0hv5zWCf*AK&&Ga5$75zWRk$In7%`{6!EltjbH&k>FAN#xPt*qP+c z@*};E;%KBFfo*M0rhZAaW=mR`d;Bq9*4#}v=I{0QVDH10HFpK?ogsF=zYlw*zaPEB z>o@v4h~4S0@>gPy`Ye7MJ&OMhX0W;n&k;OF{SmIdEOR@0#2@z0`{&T-NF65J?%SAO zQzuhx*pk-fkbi;vLxjV=t@$nWYpN}|ZTQXh_tbBxc6i$IJMJH;-&5`JwBz^PKU06C zI^b!~@4lx}f2KO(>A>&7qu9?*#zd!5oy=%IinxtT)X9wTqlvr75>G`AjiMA9M-h68 z?K8`w5Qok^d^<#WzGtQ4i$NO>U1V0{~=qI3){6uuJpM*~FlhLVu3OdbC^~20` zKMkGXr=v6d474tG7`dIz(D2*((C};fQ2fKp5IjRseK(kwG)WpK^9ha6dDsQS8lv;D zbCagz&n3)D<`AEYHp4EYL<4jIc6QPn-)zF1WD(x_=&Sw}zlhkY=t6w`lUMx9zCSsy z_*qE{mY7ADoeW4`_AmJX_BZ+4@b6Eq#>f0@SZR6sJnTxYNottggzD%n?6t}6q`KLYT#Hu2RyTv#>%nHA zsem0w7-R;RilhdZO4tF!2AXs10l(jGLeH_A>_LCPPqHuh7tui+{YiEp$A2>ZO?I+< zk$YvborIliU*MjZY!CT^ej_=X?78+FyWgKnxXn*w*-3Vy9h?kGrjWbQo=5&|{yf4y zKfw-31}789ooJ`pDdbKiY_OXtwa;%R-0Iik+hC`m>+N{TPq5R;ztwjpz0P(fXT9x$ zU5Bo-Yi(DobgezxcEd`~wrgy6taOcCZC7De+aBmD+Y>8YWmno>Sm{c8mR*58%l1ZB z*vtHgWO#D9zsyUAC&Q8*epoUTy&QWfxtIA%{m5iQatV5=zr>G9MkZJI@phcO!VgKt zqeGJ+cy?fyv(^>154zl5Ovy|9#eQ@$D%t6;@Z;=7#4q+2`7z1pWIKA1-|ojIW0DKe z?fybPE*YC_Lof8({P<*Casj%{U*IPsyO)wTp>wc%?Og1Bdox$_etTQ8PfDsa zOSQ4B?U{a=@5GWLZ6}r~)0eZ6!(#Lx?*&~HzT*Xy%zr-bP={G{$}WEzsgsk>=0YU4z`2PA=uq^ zF{O4BuC-P14YC=&68CUUG{a~53_rl+@ansm15Zw$i*$dJi<|)_!JotD#@F9`7*{bL z#UIA%{rFj&8_&maWlDS;e?-p5gv#avazBheh&7|%CvoDv|0Mnxdjih~@#pbpaewn^ z?0xJ%jX%LY5bsHBmYSJDfSDN>u(-p4JYCU;|H+! z#Wy6^C-+hE{`jHzMEpMbAokw)#^i?NUUKh?AB`W0BmXEN<-d%-U=0sb>izg(!h7*O z@!sUdWLi9!KOT@O>XYHk|=~=>awj@iHLRb5ywj4_|u-CGsOVK6V6W0=3Vy}t@+5zYw zI}okP-EkFLdv)}Ty^J+ILwMG{%(}PP5_XMW?Mtw>k~WKV)kn)=4{&GS6(69~Hsaez zJ#8;%>8A^10ay9-^+y?rHHepPg3RE<0Q%BZ@nX8W0M;;-X= z=G*ui^tDs8l7P0I7I$wmPirO{N)%Gg%8hbUm2fLGP zyE57t)v(ox*R(ZkVagXlH~96w5L(z4vK##dU(jyy8_|t;&yKF-znvXjWv@inV6TWQ z|M3deursD{ic5U>yeGGlVK5lnV{)%Wv|-f!=-znYUK7n;jv+Mn#b_8#;;>`(Sb>~H2*lZj^7oM@)au)k39r1{0xdGiC2V@3F`1&-i~aKbt%@xBZ^nAJ7M|zmRt~`ZM--^P9e#id@A&32rrM^cW#J*t?w)+i}!zRT4z<$gAJ%m0;iEr(OXnpi8`~0ANg|*y; zp2Yshntw7sntV2|ebc;QE{$F#?@s$F`FGhLOn#dWEnxGb`6&Gj>-pBcW!|LZTZBuZ z@5%kad~G*I8=|kt{l>m+-ZGa&-F>-rev|*s6to417qH)(uPFJoeTNbkNAH-o zv0vIv(MEJ*^p*XV^52;Zb#)AQrh#whOT-NbCFAClZ01|Ux5tO$=5dRlhvP$Wec!;BL`%k{ z;)ZdfxVUdfDB+utcQ9^7*+X$lmTG|>!PaKoeNEH&0BdYYi34#{N*#<_k=rsJxV zXsNh#+#oLDOZo<^wS;d%spe>N-@>n<9y%JYiEpP?T0^aLBtAPnVsE!+<5?3oj$8Pa zzH!_HJJ1jErQ?BwGVyB4wL;fm*TzTf5xbV9&W`KHC4DJhpZ`|UucAcjcon5u#p@`u zHXg?MTKZvxR(=5MD-#bOl#N$Xt_`{hTaR^=^7RO%{h0W5`DlA z4`NMi{UAa+-^Z7aE5vtU`8gY4F0j-JM$$#w>@8th?jH|~Ld_`Y9u7Mp8 z4~*NR?R^K|%U6sm#l6^yit!Zw`(*Szd)zMLf1ejGuu~Xys?R$1A>zNXt!CE$>%dp*jmAER}1G|HDbVfVJUE+SM zsiW^l=;Zs7l6LZ){j~Umecw)FZByf=tYr&&2KI86>5A^a_KEw(oqZod7vGzdw2SZR zmr#0Zyo4pT#FtUJ8+tkRQfxQ0TiiWfOo{W+CD=!+ed+Fq{2(KErJBo6+<9*XCl@*fYMEwf2Y?@t-b07h@L^ z+lDT}F2HU>x5XF6^RdzkJjdxHQ;0H!T_JZ~bZ+z;r9QAn%dR{(~?*F2GU+ z-5usAWu77bS@Wm;!%mO?B+Q7P#`BChW&gA@;!}i~v2mxYbY?s&w$3=|tax_p-0XM` zYOy)Y6XtQqo+q(6%v0DL=4q^0pQlaAIX5Rx5$48`OF8M>cwQX4$jytz20acT^q_eF zeF&SFhp~xy1e=&gv59#Mn^5jC)0=y|4_eVz^1V$ZUm30JtDseURX^U1bK9cvgbSip zZcDT|YVBIN&Cvum-dzy2#M8>P;RqB!H%I41ZCq>YSjvxcW8H<(HsW`1WZJp{F28F_ zsRC{cp0Vhi<_gWhHC zH0>#|HEK`U^P@84=W}HUd0jJ>YL2$Yj&gUKyUZxck9K9r&x_`Dd0bO+o1q=BBPlZq zJ!bAUBi%jbm>GeNbmb_U2hHtrp?R=PTt}8@LTKu;@a1xi@iaj@VTZHS2=rcaj~V9f zGxwtRn&GZIWpkmKE(6VlZAAITXlLwDN)AKsH}{!_cpABet_!vTWi!wWm(x|m=5!74 zH$=N)hq#3EJA|c%5`VzlZz{PQE^(D8mjkVc?MBH4ZZIW>xca0TxXR=tt{(CFt~*-K z4I+22t4pe$>w(sF1Mv)URh)M*nqaH2T;i%?W7m@sbLI?9YT z=i)ifoP(ZgF2FY$9c{*#O?b{hyI^PI8-tE9W6ef9o6HXy6R~4xR+V&w#OI6tI1vCR=N4q*sHkP=cC*4t|Yz+jj<~^ zSFt+_U5Qr1E;fr;{|e$~xfQNDb~(BNt${rgUGA2c#gy4^rnt#&znSW$xC3Ug+l21N z9x$6Yf47-wZmPS@On1}Jsgyft4sb^InHg@n+h=CF8R&HK4w2If?PYqJTg@yt)7@%j zyIJT=O58&HR&q_+VwQgxSP#9Hy54n=Am;b_Y}ELyJyMm zVV-r*V4uYElzY-`Gl$J{Xx93Dc3ma%9Yg!Z5%a38%0f` z#!(m3fOx~GLDY?Y*G=(tG4+Wzi0YyBqq=Cls18~e-OskwiMm5y)`Z6bi<;ita(_}3_CnpYtA;qNv}nRVTa-$77dMx zU`LRDwyDWdwW6BQVRy(4iHedlgfKK3N!}VWl2T`z!BH`C1`~!vqsUofYEZsrR3p0G z9d?7F;^Yq^42~`}mzaCqrRE-Y487OgW;Vp z_y~z!hom>o~lv5s5HKQg#OW4(Q32GtYB+aqpQtX(ekJ{ z+qWFg3Um~9C8buG%gm+bn7ho}?e0R4xw~Co*3&QQ88lC#__h&r&u0>Z-R!)P3(J|uh;?J#$^D(L0rPPc<_hnpXD zr0jgcg6M;2JY_#1d>GA(I*~JvFh4qh{{wUab}s&TXlLyE(L{Xj6HY{P@XSTKV6QM$ zqRQwF>}))9(5~3`qDd_A9^w6H7M|Hr?)Xfz%;b)jnLKf>_{-=_lM7F7;!m(YdGViN z^2T|v$D_$CeVp)Klo>x6J%K(E<%;vgXPBiXUz``45kD0@8D)^08SgY#n99*kLZ#^4 zXbMZeOE@0ojGvC4LZ71CJJD2f-XXjj<-nga&JjNoJsrIrO(W-R!aGrdCr6yb&qmKg zZ$;C|d5iFNI}(evo@c&C`}C^N-; zPw5o?C{D#MMlVD+y6eq#X0N-^U1wbUQuJcv@TcM%@Zace!n?=Z1g7;c;i@O;+)%*~BA5G;yPBG_@bFJCq&TvcJ9>R^pZ!|Zc zH<;_3iC>9c2Hby{b)D~ZJ0bKP#Un= zU#6PPaH;}iO)cPiGGe|nv>Bl(FN{&{1*_eHnYsH(aC5Q{+Y&@SsY_yUX5NsUyEKvUyoix zf2D*mGo#mu{}%m<{vQ2?{t^9-{u%v&o{IiNO?(Pv`FNYVz+KHa0X5ieW+h+`yt%^d zKzF(;&@0_e^eT5HdbPU>O-z6E8h16i%Uy%^fF=mI02$!QV zR^uUDj$ZCAbIx4mE=5yVYr1lGS>w#5#4AzjSaYGO{xf7Ls5GB-w?dJ@D(vP;<+KU9=$OouAwj-!!GRA zqzao2_}9ZVTupo<@eQdfNfm}}C`wvfLs7VfqNI0{Q`nq~=bY3PqzW5R2jUdA1WsXV z;1tdeoWccxQ`i=$hYJJsusu)@7X|9!;*_X|O9J(9Db#}q2+;}R8$>aPWhlmf665d) zq`|q64q_QZ8(bcUh8=8yxQ0S_L{6-MDOe4+PymWyRcbY`uP%R_Ip*ZZqO6()4M_Kl1 zmVGLVc@B5z(+W zC8FV`Ks4MOh=yAN(Qs=Z8umdSJixvdgebU||DthEL^e!;Xeec-LNt_uZkUcvhc6Jh z@Oa=2#5K$hT*HFEH7pEV!=k`7EQYxdvml~je;^tT1ftRlxmSI+48D{htYvp_$u{9>PyOu#XknRLBxX?hrJLD$5^B2hObkfQ!0-cPX69# z93{sFlHr@wXXNBDA{M@dUMOY8rG^Fi;Zt(*n4zThMs4u74)nq^sZUa$;vW)-hqn0J z1fJp9)ZoB6h-Y{%HHg&SKoL9-Bk*DBBUEfdZu3#Np*dWGs0T3)`=X7kVG~@#`S1;59J;2yc48nz zFMRKs1O`I%LJPPCu?`{@esH1`TBaJOL_BO`>8`L5U7@8o95!a`?+aEL@sg0@ol0;v@Gl zxwTWG97Hd?=CT5Dl0}(vsSn*p~;udP6;vPgah-Nr~6~pkBt3=6)sp^4z5H0XF9DrB{ z5e3Rw0 zy(;WORfvZ7(JI*Dgi;-bo z4-CR>K*ge@8F+R|ARgCOKdGHv{AF3Z7T#)hiz1tw2VIPWXym zy`mCcCcHvV-XDp*1ds3|1cQi)w<-H2tb@1-5f5L$K!}WZm(=Ib67Lc}PWTj-LL9_< zq&|hO_=NY}_ep(1zkTrw9nnsxIEBu{3Zh~hI^gMuiY91}c0h|_yO3W1EdcRQI#3Ly z1I17}Pz45b6bP&!Zyr31wPH3-E3BM8M%+B{GH@zUl6`iYk|FVYXT9qVt; z8+#6pcRNBcv>3jw{I~pQez=OZvY4H4;5|E22Wd5jE-1`yl7sS2=Ne7ktnTs zxBtkurc4|9I-lSuv`XIRXtcuLI4Rs+J z#4?C$s0X!>KdKASAkINtLw$$_5f0)S8bC1QBexIB*9x>qMv^DWi>ENTg(7hc4FlKE z2zDV4{_j$aNsDV}Y($jQf@{c)|9d>&!80_4fcOFZ9+IIM>_cXhi`*ZH{{YX>9O~gG zRAj?Xun8?7AAU-SDX0TCAbMa1VWyuAXHW;)U^Y5Ec<1^##HSIT?!`p>l4=Pf@pEdP zpNoGg{%Q1x&*Xni@flHOG==z7Ki|(Ice2k3=`b1p6u$sp9kUQyhrabW;2kEBJK0Yp zJ_$`A9Txe8hWPQo;_#2yNy!9nzpza6fij5$C! z2$dir;b@=}_6P4BsECH6*xLyE=^w3_*oSgZ4q_c{#k0@f<;%ep-$hP2b2q8d<`_)Q z!w?jAhj?j79kCU^rdq>!oJ`$A-a{}I$FSlZeuHUfjTPhYJK6>-#^DdNEmn-fpJ+R* z7>846d#o4-6Lo}Zu&9M!=okovjt~tg;^X{S-!X6s9ibZ{JbYF`JFr|w7>DsN4MSi` zI+>wxB%RDK2$D`_IHX7?Gr|u?N5X}irYA-RZemOzCd8(6g0UFmhr+njfmB%H7ZYFV zm!O@@8R!{)sTakde*JZ@Lnu{;KJT?c&v%gxQv;_kE$|D|paPmg1Bg?YLYNxpfhK4Z zc!wE*eV9S2G41gdl$uPKLJPemsY%HP5M7gqO(uTAi%1Y3Augd2{ggk1?wUxMNl*(7 zAsuFs(~zFm4?uKHAa^2^Ljy>N+2k~!*Y*Q==a8z8)`v_IQ6Uw#G%pZN^GMYVEJhtv z6qHyDsYod?7yT0T@UKC?e(??a6A=UZ12wP@y^Vg>x6niTKq9u_K;R1w{*62kp>Qbh z3Wox-a5!)bhXc!Sd*B;x4~)Z+z&)fnh$Df3$TBz4t2WErOdr}Ta|^wuv&^mZwazm8 z=%;-YX5w0ZBdNVm7S}>m+!5%C8}Qr+U$GnJ;?BTdT#x4l`Uq#4>*+O|Wv)Z3n=B)G zVNW0#u0=JX<1Tb}at*pG(Ws8sBm>#w8uWc07_`x$nY$Bpz3iQGT>}Gqlzshf>%z1V_ zo~c&!!c;rnPOxK=>Ev#PWLS^4vt5Vn0>!W{a1EUU$<6x&)%3Yv38q4n#w@z%#6Y zVOUK}JVSRYqM--65-XyiCwdlk1=+jfBVt!2;1Nq zh6lD_1hj#uhYMj2h9_I-{XgDrfo>Q>d^F2!3ADm;*4dkW#Nrz^Q)Ua~!Z0X_?NAHD z0>>~E9SR3=F-*i@^djsf&<}%A5h9mDPDlsAn_LD_Asq9Ah}$T+4>DmF-_hETvl-n?9~ChPqahPUv;5w`K!|RbLwpV_!hS1mXg^Ec zM*J?W^49h|dN8(zia5`UPZ$NIATDADeA&h05kbg1Cl$ zct0lo5!^y0Q`v}KsAN8Xd#HkHl$%fRd>rV71g=5E!{;pZSuC#M6BOegz|dEgeRng=QWKzv_(75vtHFc4QI55*_Q6R{w!;Yvua zd&$2t5si@M8Xkd3=x4rwUJ(BvhT(mfb78s5e$hT-kNEu^`IC*c;}!Yg{=t-vk(iT+6m zaShi8hCy7z?+^{58=ekC!wrF3cq1?jzoTLv)PwdnRGfo|h8qLP@Ot1H_6D9oT!RP) z^?ZF5u3;H0gSZCK4a=>FhCWtALtiU)LEM8_2GI>mAsR$CEQ1UX_aM5VKiVI5Ks>|6 zfmL`uFbN_W8bKC1`!QA0#zU?LPWzFNCNQ?q6_N57>I}v8?XzOVHbDx9=HZE4k9$J zjKpM!Zm5P<|xV*t?}X-4$+VJC>(@{1~CL8A;cKeLB&E8v8$o0ioipx_975OG+YgZ zv4$<*1JNMrLUcn7v<5svVY|w&gk~s$EfjdJLikqF&%F?gSHZxAiBb^Ja3z$4=!P}0 z45A{$GKg2G3DF?Bp|%ypAfiDOgt&#ri9gO(?qCTK4Hlw7bVJIDWmp@yg-3}$3IQRm zAwv0i5EcEfK6(h2VSV&4?1Q+5br20A9z-{Il+Pyc0pc6_7?BO)7Vftq8crI~3%LT( z@MEA9#5LR-xQ0whh(pM*q8l>pFM)#)-H;nL6`<{4eKKj3wH;);iUaBFcYF1@>#J8Zy5E}zKfpPA|HM*A|6CEh-=6XoA3?m z*bs?mcr(xomqyI9eqqHxh+aq&4PqBWIf!Kt(eP7X9Qtt9 z#5IUx5dDzP_c8e)8ctG277na~xQ2I)`l^a+_{J>rpIb2#MFRJbm-6|%c!rl?7+!>2 z5XtajoCkkiFQTDHpch_%R}lRmy5Z%(C;W~Ja7-98(x8H=wtH05{PmT z*H9>M3*s7Xg=G-eAYMU~gSdu*fkP12(8tsZ^g^0zXbjPC8_Yt}z(9y-xEYo~w1l_@ zF%GxDKZs}$uORwCOhPd)x}iW^hqcv(SP%svZlMH3ffxw!47bB79401W;cy@t8Uz}l zBm{!E2yqC-;TjH-FS?<5;2K0Nh>EDqn(II`h?5ZAa1a&$&?;~bA{y!k8lhAm4NAZ@ zlz@~F(a0kVg1ClP;T=RYtPH$Co4^~SxrSkZOt=HCK`ey01`!M*Bt$d}2)sdA zhz79^q8r|XYgo_riEcPbTttM3hI)ZUC=J)p4x-^2!dXxUtzjp`9<+vQ*uZk48%DgOm_m&@K=K72q1g zOH7W%Mu=-TZbcNF6X=HJac`K0+Vn!LM&IV%raE*(Z-|EKXieyb-VhBn(b~`r;ugxI z#tT=>op%Fw@h*hW* z=!RZiG(x99H|&H)=l~rdCZR)M6)M9uh<^~#AQnM{ggAur0^P6-qM>SBCD08$yoiP? z0-4YmlA$AXgm{LIfoSL#ScOh-4ey6u?cyZFCu|OM!x@2V*byiNaSfeWMm$63Ks5BB z2WwXt2eArUAQr?zh-B!BiiHrjkmedL3yi^5RQ!Y3gYIZ|O5`*jnUCqS{x$V#PGX-B z|HOQXeri5LKQo`BpPMhxFU*(dm*y+ zPxuH*q6lTvT*JAMSOyUdA99>tV7U*Bh=$kD?a@W>3SuBcG?a#J_y8+n;dMv_kr1LA za>6x;eh}So9$do*kPRXlZV$x5cDRP;DN`_T4`La93*5p9^aLpp3rC;@o`r14LC6W$ zAo4-h;2E|= z;ucyt(Fo&ROMF`*u?iv@&Vzao-O$>JYq$`i;X;nfSSK<ma(}P9u6D z%{5GLA{xXoh?WqmFwr%~w>1*6kmefNLNthn5Z!PWT*Fpq2+<9b0~l$QcH`AkINt!$@d`^YEO59R|H1+Cf~yDAy zL7aoQhA|Kf8}ZByoP)TAu@DR!@XQOG!+3O_S%21=#uY^Mu0ceDC49jN0l%=1Qqu#aa1chJN8lP}2BKjW6vM5Qo#}3Yb(oFLhG-Do zFc+?&2c@5eR_K8qf>RL7AfjQO6I&qq;VDWThG^&k_3$jc`FlVxh;Vhs@rq%19_?ntHHdiFNBmazm=oo28}WTk#KL2!SO>8TA{rLJDcr%up5g<_~1v>V(-9b)1d_Cqd+ zWw9!!kn4KnSdgL^Oz95D#$%Icct;RV1Q81cSJT zrR1c!hSpIpeC5z`QC75soYrV-n1!DBve2xkJY0iV3sC`g!8M3`5Z%x=644-zLG*)& z1`!Nm9Tt(_7Htca&<$V3z$%Dl5Z@rKK`g`Sz$=J#5aS@OVL9xB=!VbW5=2FaZfFm? zAnrkQ!(mYL?Rl-p&wyI8rF@q9ozw( zA)-O-f=GxDD3#_K#=|ajgj|?MPDiMP@qt|s_b?Yfty`ic5G8E22T{g6Icv4SAsimO?;eKs1O~5ci z5W67mAxA9YL3G12foKrBAnqXvtb^!=XQ38EJcw(U9*JuZc_8B9O?+vtVMa8`EP-s8 z1heop@vmVSCQ+-4Z1@IhVG>+J{&*54@}c?Tub>uY1a?7e#CPO>8;NKT!60Vhb@FHO zBm47^3%Ib8S(C_y?_dqYHHcjh_aL6(dboz`pcq_W9mF-f6x{&na6LrB9;gS=4SPj2 z;JKb~16+e>2N4Zo5yV4W7l?;IFTgeIp~Mt83^5JgLm!A$z)S5ZMnMdOxCSu}H<%mg z-~Y1cfLNS_=!G=bz%rB;!5|(&+yZ%|(peep%rG43d$8Z%e(^DFbl@vHS{%({wx@Wndq+&4YQyden)?YXqW}v@F)6b zbP9!Ph+!b0I@J6B0vLoEfkfB=%Mimg>_m6MGQ@BVSD{xyF~sI-D2CWv!yd-G!FgDP zKClciTth#!AGB(0#CF8+5q$#D5W_884keKago6uIgNTO9;Snx{Zm`51n1y%-1C_9i z#4IC5p<+}C-3HfSU>vri+u<4vjKjs~#Sje!e&I@%x&%JL5W9-_RjfnYM^~2ZO8sRZ z8Y-fdxVv(iD|`lFQIcU6(L*7_EToS@hUv%XuNm|Xs)g2K)ZYyHlfOu>l~P6{4VE%L z(^pI**uF%31EaQXNY-4HpMl>;9|6m+fCjCMb^Oj(8Ldn@#qW7l&?=-O zdI(fStCEiCJx~p;M%ojP(HhtU6+NQ96FJZXRgaOJXbx2UNi-8>PE@^0GSLiFy^?aF znW%bIQ$8o&5f!*RbDg?s{T~@(7dSnP35DHR3rNSYX<59Xns`vrV7$8stMYJ zbRl{~HAS0}E=+HzW@t0gMd;ns9BodzD7}nYpe;xjqqk2>v?b}{^zdngwjy1E9zLzn z)}%`s_4g@B(0r8bNNH9|&4<#SRB3|dqf~#NG6c;>*@0MD`rdRfV(Zg%b}gI z<5z`f?*=BVdHTS4yAl0#R_%tV}Bd+;iHAk%Gfz>>* znmbnW!)pFm%_*y6r~4pJXgzDL*?b(g9HcZ0aV7qf{$r)EC0$Xyag`7MJu7ULw!AZ2 ztv9-I1kFvXy(oj0MLS|kqh-(z*ixvj%=XxlsK|$Q*b=B{kG9z2sA!Ki*kY*Ykk;6u zsF;{m*dnNCo0izZsMwko*g~k-l;+riXd$#2wg4&;r71Q)S3*;?DQR6ZP0%K!^M)%Y zFV|3Gjz>dm9)jlBZAdIPS6f4lVts5bg67z*M=Fz`8K~=$${=KNKI)Lt?5i0Z$=alH z5ORh)q83^UUqZ;ik=NZpZ4=Hx4Q#|cqcc<;n?iNw)GH@NsLmPHeP>afWBtyq8K-p} z=y&<-^Y!m_zOw7vf4BNJ`}z3q^?b}eU;j?$EBpEN@Adr3K401AEBk#u`+YvU{grNi zWxvm7zt3lX@A{wo-j)46|L^oZpIskj*N55lVRn6({d>*n-)pj;U)j&E?B7HG=Y9{( zzQ3~Xuk8CP`~J%AACm4Ll3gEW*N55lVRn6(T_0xGhyRZK8?&EZ+0U=+=U4XgEBpDC z{rt*)er59%|I<80_WMTm`$qQrM)vzg_WMTm`$qQrM)vzg_WMRQZ~Ir?Hv9cB`~5Kc z{V@CeF#G*5`~5Kc{V@CeF#G*5`~C2*?}sLg%fX~`VN8x(s77CLgghZ9H#r)2MPsw% zVQdeLzM>I6@-pU!#$D0K9~zHEBiCqDmi&wkQh;$w5<(%=lhW8Mg&0kw5aXQWBvpt} zMhY|jNd~FHj6PC?aZxnuW)c2}M)T4CvZNGG`-%o%(eR&(lB-c}B9UpoBf(!?~%4YN@)?u-6^Swa~`g3)ZCP&j{nS8`5aTM|~zDa&!mD&INjC4{UjCZ2( zTr}2;M)E26w{cLkuR8uF921RTsz=kG^Bd#=%Z()+JH)P8FJa}z87m;KkC|9zkHvftY0 z^qy;<^M$=l@45C_d#*8Fw9itF{h~dWYJ8Z#o@?!O%yH0oOpcI*efR94Mq<)lC+x3A zV$xpcpyc1L+g!wT)oOjZT6OJe93fq;x^{Ji<{_3lT(f!DP933qguHB}j#GYu#$VEL zDnQ83R_X{9BoqioCMU|c!{JPwzCwNYzuI2IGU;v9w(I|Cq$zE?&T9I4mNj7wx-T4| zFsi#iXSq;Vz6eX|yleR)tU>2J4(DC#EE?8boVDugYrBiHeLC;j?h&WPg>s;$-sHD!dj%g0o zrO~1yLMECbrK6Dlq>g-`=q@&y=U4R?Vr|>zJ|2UTw!mtf0=v}4p)(UlkMxd*}s9+U1UN!M(lsnZMHPD)j9j2qGk?9O$ca_9jJ=8E7rB27X zFKJ_Yl625o~of1tHKy&y7n}ZU5ckdQSvmBoz8G` zv`dPYWTfwmxCn7oRiuB^n^z=eq?jG@*NZAl5$q}{njG}2uTg5Esz zhEou4H?$BoCu6a-Mq5*&Kp2%y?m zXVyk*Q(`D#5F>c2#u-Ll!kFMgvBN1d6di(hIM-wyR9ET<%H>2=e~%z92jhcl1o4rC z5vZ=(k%Zxl4?co2qrx#CO?(t1gKK>8(cuanP05jr46ZwU40)N12|kM0SaL_Bx~9j5 zt9C5uQH&6-b1^O)|8bPd#R%bzC^4S+I8;~jc+z7SAzWu`0^U4~zpAmtCz3lJ9fx;f zxV|Tbt9cUXyo{=Iknu>TV5j4mifU}r>EY_19ZB#1##$QEOT&G(lroDM7k4qfGsrKEs?J+R z?ow3u=(2DhFC)E#_!3H-NhpKr4d~2Jn=TJ^!19o{obt;U6L}e_737ygRo9+Hdnsbno!xSA!jAJ zI>c3C4Rt|JRPW1ci1k2wP|8woR6;AU6)tRvp8MUn<2ACTo+n+or&Vw1+17>oTt`69 zw$9waF>z1m$erqg>ImyyMXI_=Z!A)sBfTw3bx!r3C{^vK)__zssNNQ(s%!POC{<0Y zcSfn|Y`rZ?RgdePQL4ILZ;MjhBd5nV)##Rm!d<48K@+ZA-J5D5HRjsXb4a6PHsX5K zJ+9F+8*(k`sisji8*s&`4$)|v^|_i<=V%npdR$?ug)};6U9KV3U>dcv&flJc8qHHr zNj>{C%4aRE3Duk${j(BRORh^@ z$r_P2#W~REr#dgK!j-J?c{NV2#-42*&QW?K+O}NlYDcE8c#TJ^ul5?LR-?)4C|4v; zY`R9I)u^=^aaQBZYK&Q($Mk5m9XL-K;Z>v3mJjE&181=l>2h529Z`+&s&YMot~$WT_SgaavRpYU0j8;9fbTwyk6`US7SmU_r%e}^R)hMqT z)wMCP^ti!!IjedS=`AcDXHxGjdh<%(XBtIT&ko&h1vqnhPttvu9&a{1da%Yp(wM=m z2pXkUqtdn}rqOFPT5TI*8r4?sdbTiI@o&?k2bTynh(^{@yHhnwDUPyg zX4N>QLmi~?byWjvlwFO!t8<{5ORD--HJViKv#N8YdWY3_dtDdZP~Ankt8_FpvaODf z#$0X?j-f`mZ5WPcgK&K7bKG^TYKNm#n{s)>IndpwW2N(wKb#RgjqBp6h3c5qLK}ti z*eIOAMl4sK3 z38lgjti*BGbzO!~n&YdtX&vQCoC&>&mL=%BR~D&qgtBa(TFz?UYMg9~RVz1U|JAZp z3rp=YwTtvTQcLY$E3bC4Mi*8KRBP6V!ul`zkDj%qzZs~#t@Z18{cG$0SIhs$?*#u@ z3qE};QfyCpyYy{CTdn#+$3yw2+tdGd?Y)0o$A6{msVnlovn~B!*_Quzj*D8*S={@o zh3XLWY_5w(ZvB%X_5D^jaf z*dRvq1$x>;|kdBc+-yFIP;bh;&-ZdL0V{b%jzzqX{)ZR`K6J*_tM>GrhR*8kX^ z{%adL-KthgI^E9xXYJ{~wxrW->;J4h{lB-Q(=F`3wxrW->(lM&zqh2*ZR>w*Pp4bb z=~ngscY9i`=YMQZtA+i~+S6)1|6_YvE$n~Ro=&% zrBrpaT0TOEdHyi{#!{l2JQ8TFf6Rbu(V`(A#YEoyP99g~muPqj+bj>*f@ zN$pg1l6t$Df~qqe5%rW`yo)xJ~< zCgC}$uMcXcd!CK@9-;ar=6R?#quMcg1J?VI+WYD6$2Po0JDw(%cPO=3Ez9eiXwHfv zET3-k7bR7fvsMVz+0*k|-vxA*(q9MakXMkWcwKCxaNZhmj!F2 zCCSryOt+^Cu;)6SP4G1i=Tz;int0TzR!gfic{;yM!?Dz{twF3AzNVbrGQ@P0^PoEF z&G9u0=e;?qHgs;zNHw$?Wz>S!Z>{CAkv@&@)xi%`HmBP7Fi`h`34XRm53`^+icNa?N__pONbs?Q_J$FXcl6H98p%$y} zM*1C2t!P*hMCi!*>=e#(6yj=CH|0zeMb*;LH-;i;5z?nypZc!Qg0s?` zW3P5-6Ur4w)4wG&C8f8C794f8FE!7J&RS#QdY3B6+0%I{jV;Cg=}n>{p#WNdrSuzg zMUH+$O6Z+J$0jeT)?#H;$58FZDqKqqDc68d7S)@e=19?dVSQBX$|~WiQ!7cotdtK| zSyhg5F3y(DPX#>XIntToOlF`t!`W6FzZ%E4E+uk=>q1`us&mb$#h`0at(_cPFD_h( z4xic@y0Y{oL360++DsAjOP#*&L=-^)Z%EXj?^*N95*`tdc)Qiq4f74eHTi9DRP|k(_fG@+s)}OOPcMbGUX%I zu3xzI`?q=q=$xy~s~!WoGSrStw<#U=pOsIS)KV&^z7hYie0t6LFIuzO*Z;h{wjupX zaQav0|G)C5x99(K{r_rtwe;2cSIb}h2GU1ITdCt!uAH8Sy65z(p`L)v(DZi?T|s&( zrk{tpdMe||LUr9_p}MOZa|h^2qdTB+xa%9CdJd^=C)M*wHH%c&lN;}a+EJZalfBW^q}o*95p@OWX{hT<*N*l+{VldCd#&FG zbsnYqJwP?JRKGFk`771$n;8WCj+qmi8Qx;_1nIC`$^LJ}+KR`cZCU0G}AEF;IN4Sp5$ILb! zk)4M*V%=0N|_enC2y`4at# zl-n(qArbI-dT>1NDHUdHi$N1C@eV!X*Q&v*+|?{itMoGZ_K;d*;3k5(Y1 zUqdPct;n32p{j3Tzceg|J23D2%yW69B_o~LM&>c{{ zbya6Z=o-uft#_{)XiZXj>#7;F7PCoqHnm(Q=J>8ftP8fYsly!Knw_`~T9;YBH5*<% zW(Ds?sw*`}ea$G2ryDg(1Lhm=fu}n)PDAD)?}?`ecWoo)Gw+3`C%q0DGxK?GJiX|H z(1h91`{3zqnlih3A9^S>MVm4Ay80?KXXf^Pq|}3O3zpd~ZL4@A{# zp%pX94?+jhyP!2Q)elAo(bu4jYwd=hgXvk&mRaeCqUw>*&b4Je_;#d+F}J+51L@(Y z`X6+39oz_XINvxrG2i=0RJ{#4GmHBubR^$3x-fJ5XjJ_Sx-w7u7<4pWM7l9!`&d+c z3%WDwdJkq>A4^|=9zlDO9&dU&^&#lR{OJ?W@%;YZn_1K+qUtfwhZ)o-p%eMVzb`X# zPDa%~pdYh#PGJVmerP|uQ_TS8?wpEeiW$hv>{Iy$F%TWZTbKRS@NVK#uVziCIeaw+cZ=}|tANa}e9I+YJ1BQ?Dv-N^@&kz(G79_2&G z3`QyM#B3;i$2+-UP(7}@(5ZYl97ad@u5>5w=DHG(pjY^CI)8U_>L1@d$R4h{8)bSp z^_cJJdbrVa{q6~Sk{v_O+Fou9nbCBw??XS^v1G>3+rBS7YR8coOSk)e^r#(AW}KN| z`qPDW0-5pjaPQA-q8Uj4_K8Fj%p^02zV4IAOf-|tVEVmJCNs%QVLsUmaf96yx}y)J zWBgR2DfC4jMko1cWTu+wW;lK3r<0jxW|$Flq@O`%I{nH=(#L)#nHh8vA4O;TS!8C? zt$VZ^MStv3#B=BiKbn5jqlw4Tqh6h<$GNfeb{@-o9&>eh9`DAv`EZ_@PY>PkZULN6 zx7Ueof?EjH_jM8-b{9eQeVyzkxy4Z3U#B?r)15-Rgzm9Z=pQ?kcqu((#p%S$pnCSs zpsVb1sII>==`FhgE;lRaCp(j_!?S|@hiB7gb`{-e)v0(6eP&nF!FCRuLv{^w^$?y% zH{1F2xLrd(_xW%Ekvh9Cq>Ju4qP6scUqmn6^<>u3lYTKBbvKY%Pe1!5ZZX~M7ZY!y zbM6wiiOfc`*({^S?q)KZ%oekpe!^SGY^HPZa%Ni@x0sdmCf;hcF^a3`Y`h(AGusWl zlId-~ns^7Dl~=o+a0gwK*D%|~D6VsB-EO$c?51DxI=2VzHhbulyx#4Fd(2+C-EVOF z;9j$jZucAAez?!p%Y_aoeIex!^1X1d33A^yp1h1-aJG6xvN?eva62oIQpW(U3F z55a@xkl9Hu_`~p!Ic#>(;r$3aY>t@S^l(24kC>x$`rhr1!K3CFy}$R+y?ih6ak`lw zqr>_>cify{6n}L4-AQ=DoTMZCkM0yb;(vlakv+})6g)_$_%radIYX!WgYGOmW6qkx zbh^0-x=DB<3UYj@Og?sMa5WO~U%}e*fy(RO;yfd%dOZSeBIjeFb|%D z^frL>`_+Ym0UOR*Z+v(d&W5-AruW_vM_>}(28bfqh>T)5AMlZEcpnai^AT-i8^MS7 zk;z1|QEWsX!ABtz*+#XId_*6WOcWcG%`_bbQ{G-_R+~ivoUN`AH~NY6WvDh zQJKZG(S0-@lPHFb#XKgA;iLQ5FqVyNWBM3A4vcN%*jPTMj|=12xHh(r<>SG)HlB^+ zWBd3po{ewg`ZzuTjBgXzc%IS6BTi`J2bq94kxk$e+C(;?Pv8^7L^iQa~}VqPwJDy?`(4WoloYI`|pTDZ1NyOh(m3N z53!*()Q9*KFw~~7DSW6;2~*gVHlI;AR6Y$%ZPVB^KDAE^ z)7Z2&txx0A*>pZFOiMPsP4CnB^kmZ63^s#L?=z4|Z!_AAK7-FlCWFo7GcwDh(Ps9U zd?uUOX7QPQW<@rO&FZuGEXvrdHk;4tvnpe=+3$TepG_J2z0K~w_ungHv)dd#yU(tS z&0%x;96pCKHkW5^b28?zxjm81W%GDuL^*A4o7WSOA#3w_A~IxceosV(tS#V)$dI)K zJrNnQwvZSw?*;gb}!Tw;Y z`YQehG8JtlTg_MXmB{>HE8FV6ny*ZzlC5HE`0Bn2naZ}NufeRUt>tU_szg<6HCx-) z^3}*xwbgAMU)xtFQ_a?}b$uOQgG_Z>)7JBKeN8eoY%N>g*YmZ=)U>s217F|QCR5AS zu?>9#Ux!R>+sHR$R@XN6jeK3AI<_A3y0D3F?CZmNw!RJXO?(4b-!`yKeVA_u8`y@n znQ!VF!G^YxZSI@-#;}oXY+Lx|z6oq>o7k4Vg>U6s5{KDVLAEAtYFqm-+tjx4t$j1t z)HbtieH-5#HnYubJKxr~fX!_S+upbHEny4W(suCeeJj|~wz3_42j3dDvaM|=-_dvW zorv4m&aewn8{3vq?CQJtcD9@E3cLEYw!Q7{yZQEH+Sv}ahwtt?kZEr_+Md3L??|SD z?PPoTp1u>Aj<&Py?R)voWIEX{%sazAzPIlRyV$O_ukYi#!LGKO?dSXY?y#HfZu|Rw zet_>!+`|rl1BrUro{ZukKhXDrJ#8;L*bnl(VK3X;4)KG1AK2UWu|xe3-xv0=eeEzm z)c1pZZ9hBQ5A*$DKil7q@WcH`KZ1CG9SKJf4X^_l#nFD09|Q;5L3WHE?FYj_cCa1m z$M_*|upMH@`LTW|9Abys@qU~iW+(XZa6H-JcA}r)hm#p*N7zYzq8~wKxSi}LF&k;8 z_{n}G(Fi-rPW4m#C^94MXgkeM^`ps*vSXN!hSU8tKNgO$W9nD+!XeZnGex9F9W|Ey^7x?*p z3Yp1vs$J+8_^D*3*lBi=U+AZinQEuo#eR{WPG*{&VVC&Deg>K8cBWnGm-v}vX4qMF znP2K>k(p^{+vR?lpG{_#onu${<$eyC*>lcw(Xcyb{ew|-TW|3WDH~95_37N%qDf1<8 zqu=0{!KHSY-Q+j=&3+T{Cc8PvEyNq`7Qe}Ev|Ifazrk+vTj5r+>+N>G&95i3!LDPz z9`5kl{aU!ruC+V;4!;JjwQKAyztgXVYwT*f+wbzL;A*?d?(w_*O1R3dw0r#?zXGnb zE9^eM*Dr@F>}I$e?)Urr7W<>$5BK}ccB}o#|LC`p*<)X#AM`uOY_~h@VSmW)B(uZrvPb-3zl+RHyW1Z1NBnLwyX+o&%pdi8$n3Uz?Qwt1 z?06`?MZ*a{{(-uKiO0MB=bv*2jEZkfW6Fk5FUV67!SdN z@G9eBcnDr&JOU5H>x@U?5qk_Cg*O}Dbz}t-H;92-P<9T=v-eJ68?=oKCbKYKLeu3ktAH zt+&G%H^B99IO9gRfvb2pvrUW}xqe6Jd}7?h^*fT;7RJq7zoVFKWz-QI!?=x)j^J3L z?R<0u$1>Z&6+D(BIF8v)JDzbD+zBTz?uNVIM8-XEH=M+{7w&llU;#?kqTq_z2hTY&e_vDDxv+ zzjJ~|a4wujq$4;F&WAdJ^Wg%hBe(#b;tE~>7Z9K33SI~o5})A;UIZ5rpXCZ(3>Ooh zmo$J>fyY@mS>CNmFch}zNBz>6u&E2&RI!Rw< zuerPSMJMUUtUr8%PSPI^fN#-B2Eh059URE`0ltTW82^DE;9$m&@E2WD=v6)Z&>qDVZdwCAFB< z=D9c-YDsNahv(w&&`IjR5SSd+<@q=ihPY5yk0;|4Fw~`R^?4>v2~)U~t^v=)sbET% z%EjTCI5kY=QoFdkyQYDuT^bjUch|HqjZ5p|^X{4srbR7Dz`JXDm=3ihA@8mkV0y<} zDzl7?860n^HX~|DVwf3bg1oKTEHE>A32&=5E6jpk!rQ9N2D74>@V08dhuP3fcw4pE z;rD1Jysg?CFuUVjm03>494-a#tT|CjQo!7fw^f^)c`lR^-d1fMGPzMocw4o3$>c#T zNzE*uz0TzLUA@8iVC@g|b zlF4SY#b8nNlFT-fEe?yJmSnM+Z3$T1m2g>Y7F*I~vsqzQvZdVjHk&O)rX)Ja_sp{M z{#x3VVJz)(*zC3pI!O*#&gHZ@Y&qs-QA%>zoVGj}=_a{tE?a?2d32IIyt`H;Qvsdi zxyfUHAX5>YnPV$m9rpjb0p_9B~jj0Nm%BUrOv&K}FOcm6U*Q_yBBU2T< zM_A6A;` z!Mdm=A6aRt59^_pd}58M0j$p&(kEsO85^*M^e>u8BgTg4B%jet8nc%4*))NTT@%)l zzL+rB#DzIyznZ4bVm8o}c^GO5fo%qwqLz48mztAl=2|ds?gFeZwLmQiz;LWEwREi* zTcVSMXN{>f^HwM&5m;ktL#8!KNkrC|+LCF5S`vxXrFLZ6qLxIqk!*W1?NCdiu*TGZ zOncOlD9oa=&eRc|Br1%?I#VZfl4!6C>p^pY5?H+6$u(Mw{o-qam-LoJEL zN>dNm9knDjYfL?14>XfgCbsPbd!m_~Hm6WZ&aevHn|UwPlC!J=_aW08wd5SDz%2EmN^YQ> zjAotpXOxnkiN`P>4R5j{JQj{YGr7fz@HjXYwd7Y;gvY~is3pI#B0K?(M=iO{itt1@ zfwkV-%qB5TWUcpil#|JflTb+RvLZZ%`DB!md#nggB_rMB57vUGk(r84@+WJ-)5%Oj zC%Mlm@C-83(MkSd6?i6@8R#T`F?+yD@GNwa2k;>)!Lw0I9>Te-`94H1d5Cf{kJa8s zs3wny=d;fH7}ex4@dDO)pP-jKAzsKj?^E=Wr^Jg;WuBpzJR@F=DzhBDWI6E?RGAg% zB`b)RqQ|U6FIh>vjQLWy+N?r5S&eeC#;j(xf^j)&%o_BQm5eLUN!FsDtU{Gpi(ax0 z{bV(&%sTXv^~7sXW!9sYY#?5XDzgE-WFzr9RGE$FC7X!XqsnYTFWF4I#cXD_k#Pf> z%odcBO^h3*kf5AwMw=lEH=~zqH$-p?ddUt$1h=A=>@-Ah8*0feLj<>@mh3h}a0klF zZf3g}ccRSfK{?sYNDOyNCoy}`OZFQ^=F&}mM6=mPhAgTK5gD?mGDKv^GG~T1a{#^M zAj-)h6dPuY2T*2+&`A!%!;0V$l$#?WYROTQo1-Fn$uX3hV|mBAUqwl$#SG zn#oBto0B4%$sjbFQ|P9HAam4`A!aao$zb9$sHa2FONJ1iWqt+)btsz2ImWYSr^8TD z&NH4vEg4~kqn8XvKe>o{Is(091o0(w(~;;UBZ)7gn~p*+8AW^r-E=g1$!OxM=%!=P zOU4jiLpL3ZUNV;WI`eC2r{mB}ZZKX)H64#;@-yQN6p{&OCcmJbPCzf2h;nih^>iY7 z$t2=iXsDCWOC}Tlih4R3y<`gUZ>XnJ&`YKg-$p&1ie55}c)FR!><;7aXs6RrPVO?^ zK_QueW^xY=bq0FLOq7#9&`@Whm&_vm6Ag71O37^E`>3b0QA*~TIdBfy2dJlW(M#qM zKV<#@1$7>p$s@*xD5&$%Odc~nLMK^h7NC?YKskAehPn{#WFhf0G}J|?CX0xlqn<8C zFIi0d0`+tWddU*vm#C*p(My&RzoN=v8G6Yw;=ieKsE1xskN7q7zhMJvAl|^&s3i@l zfp`nwQ0dT+**nI!R5~<5KY7pi4xOYi`pE}s9U7yTG(kW4hgydw=p|vqAE|W+Lp5ni z{E1qJrsiMx3ALm-H4vZSzo;cGsDbzbKRfNz_~O1Yexb&prTOZNZw0N_J`Bs;pp>+s z62g&@ZlZk{o{U2$X-5r2fQ&~ik#j*fG6B?*4(!wjPbM5{Ne5Y1?qzCm7 zF<}hU6780V1!MYN)Ir2TC+P*_c z-T?{7#78F?KqW*%G6~R0EN+Qp<^6^%)mCqXC4t6C*8 zNzqHFQS$jzuY_7cjgrr=dLI$W}+I!tS}3jNm(kEvcarg6^+?YOQ=!u7)yKASe8L8i3`hlRaur}UKX81`yR@ZDThv?%E}64%A=ELheSm(70^kvAL0ix z6;VsHccl`UA5cpYGt+K}%BUqtp!PjfK`luNt9k8Usm8o2I*E2TR3}pnr9`_LYLKap zTB02+HObUKEeSOtrWTo+s3j>(sHsh+7HUaKlfu*?QyaA;C9_l}rKyWrk_y)MsZAPXqHqFU3^AU|!o+FZvWLl7E zj-rxoysCd&@w+X3c%#+n@ceEB)7q;-xHZ4q%7-&r zsSanfMjej-CcJ6mRZHB4|E9GM7_CXT(x{%-lIKOkXqCI8S5UVEGz0h#9`rU_5Z!{dOe)r|m2MtH7-~IUXMa$9ZcYi)o zcC_w2fR*n3a39%$%m+ZNeh*@$`zQDl@nBZE55NP&Ls;oP2oDkuMFp7#r;!`VX9%i} zl#yY4hN9}sU^X0GWCrTaOlBkD2q>*&6w1gfIE#2R>d0(3n|KWB$Q(F_cr5D3TsW6_ z9O}qCIFEQd>d1UJpLhc5$O5>4cp~b^Lb#B467z{DB#W3$W}JjVvY6Qv#>r?qOPFcD zM}V4V?K{xf>#2FxUJ#v~+Bu@*t#j0I-su?YytJHU+GP@+(Qsyc&nyCCc+Mv6(Td0z zfwL(Gvq+2)xwqtGCchDRi{xS!g)uUBnB2^wGDhL#>NK4#kE z6rFoZer9rh`JWR^EbcKexwjPL`zJv9eZrMUJJ=He{-f#1{pRr6d#a$+(t52N-j%J)wD z6t$;O`x)hir@fBa=cs*++5@TmkJ|63>rZ=#^ymI}J!K)Ncm8!SrjXQdsRa$?jTP3`2*qgPW{}q7g5JVJ3pzhhq@|tw#ti;rASZ&ZqsJ;HWDs^tggK?qG$M{fJrOw0zP*hs??c~0_v(%{k`@A>8i}jb&-;fb_wNWcFSM)H~ckt%imdk3*%AfXk(Q{70lm3*K_IMJWKtq)#c>*3sTa{LM z93De+m433l}3699^|ek?eri#z&%l#>H+u@ z_ev?QKfxclhf0b45$@;CDus4G+{b-a%I!Y5m;0|2-Mw%Rcjrs!X?x&q?%Eg8*>=NS z+|4hbzwLrMxyzqNk=qG(aQ8olQnv$c=c(W<3f^|Oji-e(D0|!BR-PhGqxfxwTX?!S zg%Y?0ZswWeBnshXxQS0j}pM=O_x~dbo}!p(ALL z>)=|RnGT~>u7zuO#yW(CxdyK0IqV?X=4!Z#XSD-po~z(Wp5A^!5nTya@PzjxO6dx? zoTtG3D5%TfGM*aup{y>0OL?Z;i{iQzF5$Uz4@&G3xS0F+ZWP+Za1rE zJ5h8O!Ua4J>_F*V0O#|ZupRApKAgw%!!|VGd2lYz6}w`@dJP9pD zuN@1=@PxDk9d`^I&6ATf-qCOrPgK%=N5PRiX-N|v3H3xKwRi*^&hwd6eLlkW+8@Ek0yz6b2i z^RYDi?ywur&C>R}K|Nnf`R@w#^sS13E>KV9suk!AJMpxx8iG!+BTwLcj znbg;oum#m+QfFI0y&FljZ4R4Jg(fYx8Ei^*nl#>~FpR1-X}@7m?`P74n?Sv{Nh@v) z^*$#Jxe?TRo;2o$umNv@(w-Z@`n(-Vk**Kx@zyA%x*pVfq;%}MunzB+(zolt+Prs4 z_pS|V@jfa&ycVpS_*2lK!dJ9tD7+eKG z0WLt@V{ml@WjH_ekik_G6ytoCddhSgprMmu7{= zYMn-UH7hq(>o?M|S<$gt*O9)>N{`igk92QVfUMSmq=>UJWV8BgREL&kEMv7|Bo&>N zB&(Gqsq3sTS*3U>G|oPR<@+~ zr-f;JTCX~QG%&SK<5eS&8m988y=n(i!IVCgS4}}mn8K&@sx?RfLwyRb8iY_7;zNC2 zn};#4)ta2N(Bx2Sb<#+`gH%6zX{X5`RncCWYEnqGw3phN1ZovfDr{m%b+wm5n+Q^M z?WNo%gj8dDX}Jj?RoY$}Z+sY!HArc{@nBrmCZ!3-g>hK3lvW%E#%3*3T5@ct)lF&4 zv0zLe%S(BV3AGL?MLGu5`lyuZ=uqpX(y^n#s6Lucg}xmXM)6U7N}GZ)rH$;P_!Ksj zF@=rfBl}Pr!We3`UMu}PBGfu=a&+|wFuaf8rMHKN;e2>69X=ck_;6nOd;oeMptd|Q zV-oAU_tNzpq)3BW^n{Fwcr>@vs3%}dXumq+RUPn^>Hw`wt7_m2{7hxPstGIrYbYH=jtno|feFSsAZ7SDe1=va&G;F7 ziiQwCOMVKUpe;yeegYq(IXLv^$51MSMVEdArA|nxeh43+T1dfu0RKYGkh1+3yw9Ex zDc|>@bPp-we?sXY(#ijT_s~hCpWlPhPo%5gg?G?Zq_^LJ(p#j%{|;}nUq$--Z75|% z`u%TEij8#rU!jy7Y5upM6du(A+=NnoR3q>Ulp>_sfuEt2BGnY!fKrg2qhVf$*HD(E zZC-;{QJkcCUWHdsqNIghftOLJq>)~Rmr$;xonC?$QM9D0UW6A=x}>&Vfag)bq{N z`8brCCx!VKl*%XN`6!h7Cq?=QJd7$RrTQ?GS|}a+5R{52efuDkx+vxQ07QQbD&jvu z>5x*(e}pKNK^1*JM8OQI>-!+eW>9tC3(-A;YWyB3{ZlIaZYW(;`u#2_y;QpXPPl{p zX43q3Kq;%L1=tRyxT;2A8QZp%}r2Buhh6BRo6mk%ZE@~*Fb5`(qLCZY0*+>S3zmiQf^m5Y1dM8 zS3qgnQhJxeWo~&;`&|Z?x@AFacqv?hHZIM030&-!1eN5)aFJUaRG1gRg>F$$d0q$? zxP?JQdI6m876g^*`EZ__A5^gC!MSc;P~n~n=eW5+<$Dg4+AlqPHdGaWbn;nnrkfSi z&u79JZe~zdp8==489}{$I-KUF2X**qaH^XY)aj?fDQ;>|zn=mpyD33ce==14f;9h0 zP<0Ke1(*mYxQW3UfeBC*5X;dd$3s;{NUIzNRWY#?4Rb71CB+i6m~lz4!a|zoXmrj| zZgfx!9R)|aQ9+G#Bvhq_)YB1A6&zAkhr?lRcu;X228X&~K_zx596}|CwAmqWFcl)w zYzMQ)TBr;?g#r)t0E=2FYH4NixlQQ zus5|WQl5LmUhEK-BHatB3PwtGPpIk`DcL=ss%E5ccZaH`k^0>Ys>(*Hcvq!`8 zU}vgwq@s6*s@9RZ-U+ITN2+^A*n#REsqr0Pd#Zk<)3=B1s0NaL-ww8=N@ytBep}dv z>Y*WM{%v4us)|$#&>FU)+Gr5kV=LH_`XgzQEurd?q*bZFB+!6q)uNh56nRUswyv@ulWlr+^wP!(0uS{p)DT1kU#0PC|;T?%b| zsG2M(xAmZEwWR3Qg{t9_(pv|rwo4jtZCHz%FKNTIU`=Ylq#M_Ssu7c(Tmx38c1${R zby$s>GU?CNU{z|(q)S(YRj5IeUR?!N4({P^$=HfIHSO(h!Pt`eHSPIt&e#HX0C@p4 zV{DFVfII@4GB(3aK;8jij7{+uDDT3IdLu7Nzb_nq*O^dO&HFMWE^g zrC}C^svnfLSqQ4GP-Dk)TDVo*JWs#uh!D$j>JPW}&-8089) z$4P^gJ47z(AGN|N*9cWaY86&)5~`Hcn!8*kvg0?QwRpKtsHReD^m3(8tz}RdhN{5~ zD#lQ?nL#BPs%A5&FhkXHmSoLQo*1g}lx85W4Ap)XXU#DKOz$$dVyro)hpG~l%AF3X zdQ_T3TBxd0X%%Ups!gR~q=u?Om5QDUsybDgM@pE&rF7ClQovA`!bu|ug&{7~NjnLF zs(zKGk{qfkR$9w1V3NV4E}4@ylN2U#Nu4yCBrvf{;-uvyhKXEaCygf&Oz09h zsXhr|0+-N94N3sxy97=uQGBR6U#Um&pz436kH&>@TwEvZG!BgI;y7ulv0*G1+evGU z1!KBcP8w`X7{kSMQfOnq=q`qnavL2+bJ3j?-Dpsi%c)FC##BZX%_&U^#*`+qi{etS zUK<%ka*$s6%L>I|PPmTy9xQI?Va|9Tk8fxj!;bAxz-bt4Z2UT+|#X11J3pgp+ z9y;fpR`?yX&N;2>TWFkhTEjQ+t2Ium`Cn}U^Mz_}t@wX|pQ!?uD)1TpOLe$3gMZ;C zs>Y=&e1fVjmk#j}s_I-?#XnHh=u$O4Kvk(rcYP04y)KR99aL3&G}h_gLRGsJ<3cF}(jwyUZ;?VEr6L}GN(#;cX;GyO1Z@|NO}0P4+)OvP5M04&c~k;geP00YsVkWYKp3Q6@f_^&LQzkq_Sl z%!A(qP{&%|1UmA3A263rB(*3OaoXTn!uJ8OJQZW;`+#g}j(>E09}x3Rz${hp90>`L zmKA22@HYwLZ;+K)W5y=@4YDw6#Mqd>L1tzR85{98$i%DxV?+MzjLhmYHsH_Bz^oo) zeg5q9%<3}MG1A>GIn>e7-R?W6W2C!XGN@yuyIoSKqoliC5~!o3yIo?a>r8h$ zX^~Q{b+=0hb)3oj{bv5gJS9cd(+dAK)KwVEd-y=g^PdeWtL0wNe z-=#(CdeZqWrCQgM&iDViB1qMi{{6qM2vS9*l1dxR$(Sp6J?U=eh;^0gZfBvcC!Oi4 zU-)+Zd^>;ieXOUYZ|Bdq@1JkqKdHELeY<~syMKLq{`vO&^X>Wh+w=3c=jU(lU*F!p zzP-PHdw>77{_}19=iB<>xAnvScl~e@YowEdE2Wcy>!K5aE286rYoX&`No)|f{SYb|srYtO@p8=|VKgPztz8}S(mhmvhfMqTK&KH7wjI^$`5G>lIZ z)L*TSHsuqBDy;RG9EtK_KlRfzKkSGaq#>fMVKUp-;(6?GdZpK5rq%ZWtkiq{9a`yCzX$bDmU5DTm3>RBmEMf3_#0v!DRp{K$CNCrcpLtW z@tI`}u79h8mwG&;<=>p0f3NyFq-K_re`gNI1%7qqC{^Ux{J^j79GOZSmCF3;$uX(Ik*LbA-W-Q&{Pe5yt1m~O20#6p{OZpU zsKrmeHfL%>&duSRufsTx>oXh4**t=Cy)LuSobjXJAVzhk9}NdG4&`hg!>?#u3uCz= z#_=l#bt~h!ZYJ<67PT!C;Uqq>VMs_+e&;`xFed-2nEdaf^Ex>actwlxWrNezY@;Z>jP6E>O2ADRlb2P`_{K8Tvj^cPi-|`kwi(WA%Ui zzSYf2x`;Fy^|#V`x3nAe`<9L(O-Fs`q_61buWnh=U9<+G9)Qwgqz$RBmUJ3@Q>fpT z^c!hO>cb^nM;ep5bV={gyR*7?Ne9x|uWLa1kgf{#`I2rV4NG0Xq$lah*FG-kO!`Jp z*DzfP(!$hDOjm-wLDcD6dX>IkN<&=<`rau6rElr`NS(f=dr5;+7c=Q$`u-{prISgs zs{p?pyKl$t+jaNty8HH>`RzON+x_m_v&y$;m2c0P-<~tSy(4^kNBH)B_wC*M|L?nb zCf?ygSRYXZzt-JDSQ80l%s~7d%*dF9cl%Hn%I~Eon+(buC@Xob^J#}bIpz7r-unLl&c|oEItfb@*u95_ZRavj~l6++3FQb){aAZ_{Uzjx& z^}JUFd12ON@)D~;zX+7GO`044CN@9g7VK1uOC}D-p#`(}>}zY`;xmuOQEkQkwghD2bNpMg?=2x2?MP_Dez-(r z5^^TBWuIJPGV(HN$Nsq_WVCOh9kXQYwrl5-F_()`2X@_kM@BA29odbSoQ(D~bYhoY z2pRQX?#%AJP%_#T(V1Ba_WE^ZmrNIS$FPFWEEPKeyRe_8tJ6AIH+BT3fvRcm&Q8I! zP+DgXb`Yjxk6{nkgKT>C9`LPmX-`?J$AD;f1!9>5OBY-F?sKY&?w_Dc?62hsp`9_3&^nk@ zSQm zLtSCx*@0RD>N=ai&eW1n*VaUKtd@c$+1EOeS!u>nTosd?u9eB`b1e(yfTcdC<)FTK zrm`=#Jk+<%H1^9@U}x<#IE`#Y<`vj=JKa@e6@Lb-#D3fvt`c+gO`gSm+{$Dsv7$el zeY#c1RAya&4*Pejl2OOxx$Nt$My4uj{BxPrU^nnwSA%(VR{H0&8@MK!8m#v(V3%+$ zGBsKEU&!v^+GJ{>!z^T0hdsv&U0tXy$&1-@To2Yo5m?NuK0A~by9Tg6O2JZgDmR1; z&<>WdgSioGh_bbuoz0D5Bb2Qb?09Yh)gO5!JE6m%G_IA*nzCI<&satE=Z`~5MKvh}CKI~SoCECh*_Gh<-Qo7bNYr}5t^{y?H%A&rg?Vwba zP3-n=52dqgW*2w|D3xUkyTdy|sVrOBHQot!L|fU$Zt~8|JE5>_XP0>wGM&*`cCh=r zD;ae_-odOJd)0Ti?ywum%P#h;_kikvyqmr3Jz)>@m)*>Iu>*d$>kWIM#q4DVd>_~w zMP?s6Yaf}O-Ch{xbRaFQLyCyB>0AA>i+DRv)^V^m+`Gww8dluxra zc>-<*XV|-ZhIk?_2WQ#Se3p0;^NCRXR42np=&Tpqd3Hr#AXZ0Jbu_*Rr{Se=kzLdm z**!fSkA+L@uD(P(1Mh{)?7F^8JQGibE9}O;LOctvhO6w-zDhis`7C@KuCarA4&!V* zw$)j6E_3xSR%g|DWahF%T%A?tlbMIRwtA{AATu9#ZS_`NNM->$&2KSVjK9P!cAVd0 zr}+|mCw^ro`me-G@uT>S9qPXkFTycx&vN9_B5OuPlh@W=Q8JR#nSWB3z% z0-h3Y!!i6R{sGU3cR+O|Ru|TtIEFum&+!@9g=6>&d^!W;J*=Y!Wc9{h-V_!}G%-VpzUd-z+N65bLYz(f2U4hrvx z58@&I-W?=!z#PIu{DV70=Ab#u{E#_HIQ zSIku$#v}S`@T$3n!+0cr9bUsqGd!JT!@M z7YlX=?#2s-k4OlE4_tpaEwWf>(V>;*1R)m zaASH8-$7003c%wpivmEXr;9vyF@g1&%{NhSuK zMTLApAB#*(yo?I_LOwQ`Sa=*2!S^c;nb>$A6=7BsPq4UnA{B-4aSto%<1>$kdr~oG z3GfyxhKo{hJd_gRIaVBZr4q!6@FFXL>rzSL#CVjI#Eq#GacN(QSyIL%_&AluuPGVM zW~K3SDua*HcQ~Gv!RM(gadMo{%K8wz(aOPcWJB>xEAKnWsuO3%FRliTSv82W;3HQPC#{;qS@D;vg~L`Y;%v;b z;>uMAx4G|`XTzB(4FduGXO>oXD0Q2KQ7UrAaLl#C{&^Gm9_>(my zE@YeeruddMBQ639!{)vj4rk4AHY zk~jpm#z(C+aVh5X^u<504UTJVa9S&auV7o8*xC}8#c!}34sGp-%i%-V9_P09#O3iP z?0}D)xEh{{-EpVuL0kh?hdq4{eC&GSUsn?+#-8}w^&+l?Lt`&| z?|Kv0#<{UKet3O|>)`0v2cNvY#C36c?2CV1KjQkZ9_;V?;k4HuhrI^)L-xmkZvb&a zd?N?o%r}s@5q^>baqJsJ+!&w9LB0uWjQiwZW?_s?Y*QEphvG)r3^ujRaIGBbo5Nid#>H?9 zaXUOV$KY-_mbg9Mn`3c397o&%PtI|;A&w`WfHP-D+lf)Vch!HkGjsLcorITX7c!k~ zS3Ex_;kG!5xEo%elW}33Oxzuh&?&exP9g5WygUA(Q*mzW$=Jj8!dY}0{*Ke|b?lAf z=yZG^rxW+ViF5{jkTZz;;!rvhpU9cS{ctXwg@5EM;{MG0*#Y>P&c*o^`T^j;DNc2*>E@v%6EMP9FAwE zJl97;b=O^jC+jFU5|7QLc(sm(qwwBbhKK7IsJ^<(@pc^x$Kcz!0?*fR%*W#Axe_nf z@nqCdcNHG76UdCm|8q6ou@lLtm+l%oWhaqQFI{>5PbQ;Yx@(zD4R)%X%3NJ^1Lcx=LY-L&LyM% zxpM5EM@Ic~<=8);jQZ!wv3~&>_0N@K|3WhApSzRUVz>y(y?+T@jCZTt`BiddMHdr}hx>VSk9(2FCR`+#d0V@wGjSpY0}`kdNSZdxUs14#`LH!97a6 z1?S{r_~RZU-io90aeQ-+6K`X_6}RORc@4~nF zG)}#ziFf1Yd(eT?dpdmcC7{dh#5$1V5*F2O(I z9en{8;fus{$n_U-7rsPHhg^RN*Wt^=bjbCWaU;G$eAQoJMu%K@1RjRh{8jvnui;}% zhg^RRpX2MqbjbDB@jt#nOov>517GByiRqB*f5tEQ7vfX!B$Vg%X?V)gA=lr;arqW8 z9di9GoS1(lrbDj(6^G{Ei0P2)f5W-?HZdJ?{cRkbe>vIfj?wpsui8KTA2><>L41w*Re0b3iRbivyryr!>+mmsA9w1%aHam) zKJb6xTK$0d7yHmZz|Hz0@lE^4Kg8ww5%Dei*gwMk`Z4jZ_KAOtEA|uO+weE|)IY&L z`zgNJzuRa2DZbjzi0|0v{uzGT&x!Ba7ydau+%Jgl*_ZwW{@gE#|FEz8OMJUu5#P6e z`&amRzasw2zV?6P^ZhsR1N+9m#{c^@@k9I8zrh#$4e=xU&cDSk{4Mcg``*9vkI6j3 zb>%&?r}l$?@1HV%f%@|^~4B7 z4|p=_tQs>ABM>0t@%M=ph#3e+CV=lx>_DtQcrxMe1Bw%f9f&|CJU&5j191Wo$wa_E zC|)3LAQBmMR*lCjvWp*x7l;DoI+P#~KM)nljVNItK_D8GOHrag!a#H=_oBpsM1dGk zu0}}$i32gA+>Vk4k_2KwxgaGABn`xda!2|ukSq`f$~7r@;JZLbAUSbd7ZPMBaXgnI z5DG&BadBTt8AuU`PbMC&OsN7X0}05)$E_(9vxF{nAXOj{l$TSQK=H+@mrEG6cROlMGj>jLbq@ra;C(2=nAF)MXB2 z3WSmgaVeO~ohnNpb08&5fooOPK$bu%C^xHYfvkblP%c;B2eJjyK)GLK4}2d;3+0NH zBal6i4$3VnXCOx)J(P=9u0YN}1}Jx}+<{zyj4%TZT)CNLa(M!|1DT=xx$*|`1hPQ+ zcI6A?WnPRiE0n8OamH*=ZeJxBzlU-GE6JE0${nl}V-6_Su+oefv5nV{5YUhA}YwI z0M2NYm=(hLtrCuDm6;XB5w0>$YE_sO!6~i^4r^7JaS5VxgoCOy4hN;2IP{V5FeD@u z>X!P2q+_i+HJ|)26=ND^`Cw{B)xE0TDJ@ig4%Pk2M@VYHe^vaVDuY#JE2?5x)wiN5 ziB**=%3(#-x}vJ+RK+W*BKbcbA^8XW&r3-DLF&1YC`eT{tBPAx#dBOfnP417RdGv! zm4lF~xK%YBAF7Hw16qnIs#V3EfuBV}=7x`YXqX`7k>iL&dE`igD-RuGfZ2cjQ_Aym zQ z#bPtd#F&w9u{g{!GiKs?jK`RTPiC&i_(WOxWZ`;DK$Oj0vk72)vfne;RjQs6*`cmd z^_s{5b(N|IMNX%#6gipaaOzc|YgPR#auKOVvie%&CZit7>UWWcjILPq!N^NSSFHMD z1eb>05O z-M%Q4KjH)K_7Azs7v)>%VUUlAi@Qg*7~e&YxzCq?#rZCJ!hOCZEWvltQ||MnU`f7< zo^iJ?4NLJY^qjl>3-0oz`4)N+ac{3mrV8rrzueoaxzF6ytC6pY#`~FBb@zpPdky!MyLt`g)zNqjQB6KI(0MIU zEj~4+@DkPLQwxRH6V>4k?x7=F*R8Mt7$C0aR?;J)9+|r6y{mW|s82@f?`qx#8jz`v z=DUWsfrexnp!u%lZJ?1`$9q5{@(odb*Yh6Gm`o#--wkxJXhNnj%I`+r2ExcRLG#_j zJ3&)2VQ9Xac_(N_rm5S)8$mOa->tk2G$&H8?+Q&38L*11-t4K=a+f+dwNa z>bSg zLiw})$U8wNDBo7~6;YoN`MDkl@*r^+chJi1^$>3ZU7=iH58Few8QF0f1-Y9zUu2TfK0F}v%O&H%1lgGX5I$q%1lgGW_!ufm6@2X z%)ArOm6=%GWQL&nUJbGb?*zkK4?7g)w(IEp?rV)u!=AW z$`80Ns|e~hA)nxWL8=qQ7}wv9M)OsNim_1c!s=Wx4$5^{9WBN~xe=?=#RMpq;vsf0 z>jguIC%U0Q4kMoAhFN(V4`=;gGL+}>2s_+Pf$~BgX-C+pP#(#n>_|He$~$>9>j%@^ z7*-CZLpdvtW#wQ7l;iR^JJ!yGa$+8D$JtqKf*lXXlb!9Tt5isprWe^6KTR zUMP#nsF(8`JKHWHvlz8ky;GKwS%TWDo+``8EJf{Aua)IwmN|7`k^8l}vaBFlj@qkk zEi1{Wud}+itRk}#wReeKY*&+6h1$E+F0pIKtVZo!W|!KvWY)Olb{VsEu9RJF*AcBn z?NvXA^<>te_Nvdr1~ThWd)5D8Bbg1Tz3L0GiHv$Yt6#)sGMk*bNXRL?LXhe&vDH$7@g>>)!JXr~?;d&#KlvwCanBcra*>bbF>%sy9_HAcCrt2@V!MC$#lt{p#-p(C_Y zH;)5k=mqW6<>Mfk1MZMh_m4wl4!XlmT|o|$IpowUYB33c$CZ$ zcg!_omGKyvqwctC&MM<^GRNEr*Me2X6J(CNlg#Bb-;%Y)R;)3~fxcCct%*;&)>i)X zZCGnO1La%ambJ#SP=5C9SZh27<#XSjwZ`*M{`VbNYdr5dvdVY?${oLx?PxDTx#o9f zt??3+n|>Eo94|w;?003w@d}jtem7PeuR^)QQC=$2G+;qRX?`$&r zE16sFH<#RgXMZE}tGn$&Y;t>>%x~^@=IT@sYD4TDs161xP$%xVl;{$7;T?C^rLrmQ zJ$M)8H#O?SA5i@e(%97YPpCc#X>A&NAF6*sIx8I_9r0f-eUKT5AGi!wT^BN=G-O7dcnsCOA&bpypFnkW$ZDlSWF>y;zGwE-Wn=!#sawc1GU_Cq14ZIF z8FiA*i6ZfWj5rU&?D4?BCpM3|0YsD>3k>>ugUz4=9}N< zvv0_}M)NIT^V_#%-k|vwVD`=xv<2*Ys16u~&?O4nLc||j;UJ3;|Ko~S_01@XF7eS7 zLy`E%{2w&m;wTcI$b3ZYErBBOFPTrMy(Mi4``Sos!WW{??rX3o!&fq2 zc)?Py27_*?KGW*qV96NNUiEfxWGrg0dOmnE4yE!5vj8gPQxxE*%)_BlK12I`MjRfM z@;Tb?bK(f7lrPYJUl2z`rF@C@`;s^kTIDOW-&e%yRS^l*SN$s@6RGp`Thz-aWYl^3 z9qMINGU`129`!OB8Fik1&n!Ax<$Ltr59q%!&?-ML|A>Ye6UIRM{e+Sk3&uqGRsW6H zFczBcXEe+>FgBX+7c|VcP<>s#nlGrnUy0*+_4kP9tu=ImvB7RI&RV*}xL}tUZynuZ ze6V{=z^>@gG^1DAsb$-a=e?$e& z;?)r%D^&L(b&ALa)s;vcB)*60R&jqtc-O8TGL~$E+ZA4d+ZDSP?i*)U{M72X;w4k5+K6hrO3PNhQ$GR0AQZ$}VkVpVP<_m%nkl9MtnVB6X;erx@YAV~ zY6u(nhJJ>bZW{TSW(J%=wy~dOW}3!i8u=!EwwYy`kZJ70{2Vjegpq0D=TaFJ=9~I? zX0B;U6y}@x`DUJJMy4rh?*eM0nv-efTlj@$foVaexo_zgnT4h$nHFfii_Id_icCwt zg!-sfD8EaojcQHQ3e9&JwNY)zv_|t?#;mPhPK8uE*cRn?1r<{5VLO!Hm1c$M0NbPd zt}?2KT1DK^uMTnzaVNjVbVT!AONCTt*a^*d9ko$iU}rSn_0&dngIHkE`ED~?O>fu>&3C)mX8OS1 zXudVgcB&_968H7Bf|OfyKVRGQMe~)9MSs{2%~$Ty17LqNU%5^XgagogGs(#|`SxQr*Q@KuJg82X>P9jjszau_lq`VioT=_53%vT7EQIQ-Im8S$ zi~LYC1P&p)*bg&9&0;c(P?!xA)F8Lm6?#AZpIqdgRa}PFO z&u9M$HTM>t+Wr%)zMDq$Jold!n`K7a^_=(nKqK*b{`=2CBlLPM{QaPjd#mxkexOi0 z`~ce#<XWF;&tbIku9xv3VKhE99iXzk2Rd6@Yo+#9=qzdt-h{%`b||OnX=*PgZ147VfKglDoewIBx~p80W2U z@2SGwI8Sl+$)YOLPF9s^A*6eF_V*J9(N?Uj=G2dxn~)u_n9orx`V#hob%L zS!$lavg{tA=ZZdA4Oo*sTQuixGj#IW)qYj<&H7}&;_h=rzpO8%7MV7-7Tj%~Jzr=q zd7eAJDq3dR+gfH?+*;zi0Y6fYGu+)4&O!~KSu zUt@RH8uwdjeuKqXYuxXs`7IXbwJ5z&Xp?&rd;`0)*0{I8H?ccwjeD!m0{46HEv(O4 z;Qj#q9_zCfxVOPSV13pC_ebz;tj}8D-YF`v)V@RckJz9qu*3bS&|do|>fgcotiATn z)cgtSa}}j`3$3>AQvM4TXRWq>rRH5M&RT8%M$KQbIBT{2J2ij9;;hy7AJqIEYqM6{ z_o(>?R%WfX|D@(Utj$_&|3!_qXRWsHQ}Ztl&S^tQ%Wa0Wxh<&W7DX_5z}DQ3QccZp z#!D-BpCd_r*b3g*ntW}pTY@9VQhNAeUTPwMGOn!)&*Ol{w2*>V)mV8qI;`%vRJl&?FAr-SnJ8fyB0y<>SA zS9AI9Ief!xO7qC)^0~7pZ9qPc&zebTKKTax{R~Qd$mjFden$0J`}NwOI~r5( zZbiSgKer^WrY{eVeR&w@PD%UkP|!V+_SUsP_eI(_hk)*dv_B38-34hM90U#|uLK8? z+XpMaf#m%u72p8!oVsI85UJ|U#?*GU zsWC{}gLBDC?Q6T+58D5`_3e-L3S*Plg8d_fX2uq@hqUAOb&tPNTDqgLP3$dgd50eH zO{BMd#_4q(i(b^)Uk20C(|FFl)Qa}%O^v;D2<@#EcP*}l#NJg+ zkF%xwP_q^kn8FkGw3bk!5B2tXX=0CSL6T;Dsp%JK=vWyJee8qHNiAqe>6~$Y1hksK zoo1xw^!EvrLhKPC_7Pj%Q^7W%-qlM}s9`^nGV4Ik`H{-5WeVy>f%dp2tY@US>l*1g z8njnd#C}>yy}iIVDwU*-GUGWB;)>5qah`q~{InGR>36|TNO7Uw2>w-y7xiZFGg2I> zw}Ri6;!FKL*zf*;J+diif7I`&8E8M%@2ELw|JCoP1t^c!@2Dkce^2qQ{u~?!DGt_O zf_y*4$9gwN+Y~qJufZOW;%WUYIL=a>t-l9*Pl~_wk6_PBak<_L_RbWq>z~1XoZ@)> zE7+Ug$JwGYXm8H2PIdw9y8*joSJ3{NW2a=FaBfd6uu*bq9J@A+CuUr+iroHJsihv2 z4>i$J58B_Vu+H}e?PE=`&J(AKy_?1{GoBe1dwP)`M}0y2Op1Tjf*qX3Lo+T~%X|R6 zKgCO{&YfXW9JN;L-88P6@zq+hchh)l#$Cf=PoGZl*s#{qn^T-Nto8Kc6u%8?Jv}(Z zb;C|iukDCM9`6ixa2o&3IB;0#>8bh}tqnS#>T5I-RN_eSZu0G;#nXqX8)JL-2d3v?dU<7hVMY^ul69ME}JUxvA$Qi#3`^FSpLeHk_Y z9m^?x;pp7at1rWbpd&WLI~*Y!!DL&%ZTv;T=OjeP1uB*)Opx)Ht-pqy2KOM)WIqA{+;*5#1Y4gl~dsMD;{C9#k)?C&CG! zdeQyxL^u&tFSa9qA$XAe;)SBTeyr56#t)9)=IX>7Y7Ny${X+)sh~8-@*4lHKqC;oC&Ha zO>u>fVuz@4hK)CTbgrf}#UVZ>S5une6CazaDb?fPJn(#UrFtBk52`QK2P<^Rh23LdXOHa*>1AS_)-t;tl4Xy>%n(Ae69jMk+|AOy>YEAVoxE@q% zs(--^pjuP?3vL8<h?tu|6l)&XVF=pUckCTe9=;FSr%d&T>Bf1wR0_ zvs{3G!EK;+mJ9JO_#vphMbCoUL9Hz*-uA`pA2t5AakwvG|EO`fjn92)uC*n_?Y=C( z6KhL~=Y4suwI#**z9QG^lHz|~nQL=Nalx<3wYj8t;aBI{Tv8nIYjSNaDZco%xi*&+ zcl^3sn@fsE{{39rONvu|eXji_#V@}h*Z!g(!2_W7mlW^(rd-R5egqGJT3%9o^jmT* zFDY*Nt+^JM6i@vJxmK7IXZ^NZD@=;N{=-}=Op42Xd#)8G#cTgjt`#Q5asP3y6(+@Z zza!TUvkVV{CqZp7cj7_t6sRrcE_?@`2DQc9jqkuSV2USiT={!)Z80g{{Jpuhm=uTp zC%M)by#}5KwaBEn^*_sB%#34iJp21{Ei(EGyaZ~I(O=+Y@RjW4On-q_z*nqPcv;ej6{s~`zmY^11y#T7gR@iv;0%!%c#?Gr3Kx?oKc3$oOZ9wh3e`Du& zTTlz{-|+%y2WsK{2VMZ}!46n>-@^-_1K5$hs@nfMf}QXQ`4{&8PM|&^@8?<38SH{j zNLGZR3)mH(kbwQaE7%R6ki00!^Fq%ME&ts?{X;5>O7e4_=jlc9|R7@KSVqKU~mY2BHH0b08?_R8n$4HN&CwY%z3?3sri(ceCi}mmr=~eV5?^TS&XQX#g zL*BbsAHR_rZ2RkjPXnjpJ)%8-IyeLG5$*Xiz?pcDXwRPs z&SF=qmi$?u{$^V8XM_5iX~~}h>Tjkce=exMnU?%{p#ElB@;3nWIMaqdAJpGW8~%o% z{$|?nHv;uH(}uq>sK1#u{7pdp&9vcf3hHk*4jcYvpnhlLvEeTO^*Ymfzd5Mynb!L) zKz+}&-fs!&d#3e%D^TCFDOm5f2K7CgT1+FKTIhW?4eR|jpdM(`vEFYB>VY<+m`Of^ z{jA#s?e^P)dZ5k1ZodfB18p{T`yD_%(B@#bUkvJlHW$17j^L88W0;5CehIi!SQ0kC zV!so(H0%`SW3gWf?i`ke4YAno4DJ$k4jW;y-v!(?>=HJ{V!tc6Ti7*hg2jF}aQCoV z*c4m+?x22Xn_;W}9H<}K0<83VfP02L!sb}%_XIy5_6%C-KM#H(d_HKU{{pBtn)dm< zK)unl&wmlr8%_KCmq5MIw9kJT)EiCv{8vD|(X`L+4eE`yJ(l@>zpz7*JnU?eNEf`m$<=|2n8gt9JNrfO@oQhd&O~qg6Zn zH$gpGwZI<_>es3T{sd6JRxR)+f_k)Sf&Uh$U#k}QZ-e@^YJvX_s9&qL_me>VTD85O z4C>da?fn!`?^bQ^-v#w<)%JcWsE@0*_tQXqTo1$Qemba+t5)|jKz&?~!0P@zP#@PL zvAUlL>f@@_{VY%~SFP@6gL=9i!yfB%Ks{ZL#p-@8sHf}KvAUlJo{y*NH?X>&4_<($ z>v34!F90vZ)AgI!+b;w!!q@e9?ClqU7vt}G0`~TcL4D&-#NK`hsBiqYu(w|d>Kp%U z?CqC<`o@0;OZ(-ZzVRnvX}<#0L;hqe?N@?&$e)6x{VGro`R`(BzZ%p-{!}dO*MNG+ zpN5V7T2K%9)3LE%2kIlQb^ZI`_4vtaUB4dGPhRW#4d9LV$!lG|5xfaMdF|>qfj8qP ze-3-8Zw7C{PySr2>$iZn;wgU~*7aM#AK)i{KGyXgfVbf%e*t#&+d%!~FT}3?Lr_2Y zi?FNT4(ca=F?RJIfj`Di{u1o!KL+o>U;a|;>UV(4@Rrx2z6`uGEDM)oQNI(sE8H2b zz@mN^cz3ufTv=R2er0hF-tt#rQNIV&TmEV+>i2?r&1*~l38?4%wb;^s3hFtp75!(R zp7UDK?*sLm*NXmgP|ta-==Xzq&TB<~0MvJ0`}u>Q{`1<;9|HBC*M9ymxE%j^?dQuu z{pYoxKLYAMul@W{Q2%)?=Z}GU&}%t=9DE`?9<-c40lL>l%lR)r_u6PV|0U>Nn`Kze zp9I};b0?Pbr$G1I+=b=*Y0!N)cVjt!26W%eJy_141>JXZFP8J?K=<8fGyfInz8kIO z&x7u}(OUij_+og0-O@iNzpr?SeK%UmUjknaFR@$t0rLBcSJ-!>wfq(E)$j^?rXM1I zuyEhaLs-jS1KoG?FxK+dLHFM*$6Eet(A_tWU@iX*_$2sf@fi7|#Z%y8#pC3UVT*o> z(i7y5V}E{{(l5xhdp|>|JsRVVXm8yCXFQFzU|Y1yMk;9!dM2PTH`<}OuBOx+ZFWnr zBO2xAq|RVxw8+i5*AetY!v0y`tREWpzLWx(p(WRr-IV9Lf?d%rV;e`WjBT86Zp!zg zGbW)kCiMaP@OMr5n=YW|1~x(K-W2V8j<&v%djSkwRg#QF(uBK}q`p~A%{acjKibs( zXjjpua)maP>k08wCs5shg#X2&+0P1#fQY(?WyX(^Nr+L!e0 zkSg;?bF+bw4g;x~mko-P8AQ!M^xo16?KibUBISlqFFQse1{(r*~a z(+#De7B^2fl%gX@+L@)&+9Xdmlx8DIo^ELCYmaFP8pCB2HJ)*3yK9f}j6;mvptM+* z1hf-`TX}xR!y&`~t>qFxAs>5rJ?#|zHSp0=*@>*mEb5~uTzvuAy z7Kd}cW%e~{)Cc;jj)-r41ox}6gW|6}i2ARg*|Qzg_O;3mjKB6k?jD4e&%UnauXT1n z{LKe&_dqm$wyIjdHh5n7MqeczfcDQZp+>N6wtsx1{ki*9G=axZzh8W>{ixqR+n4fw zP)jXgdr~{zQ?00PyKlBP`99fKz`dca+QSZL3cmrWG3>x~do+aKr1WK;`3f4s<0-2t z>_AUdGuQ_$;I~1wfql^Yodl`@?89H20%qhL>EV4qtt=h+n-jqk`Gk(tev97LkCL|d ze)K{u^qrwYfBNWv*h96ubfs4f1P4;9?ZTb3HT14ApmC(eQr32%zd#MO+Aan|^BS(T zT@0p2)NrlsVlX|WhU<~wI*hG})T~W;Bx7q5Wo;LO>2WpG4hKgtdIrTYq@~CBQ-eXR z8r>LaQ_&V`b+`aji>TG%eDDHLtHVXyn*&}*ejYXFgIXZeEY1P7WT;sbwQ!uvT{V_N z$a^w+r-8=vQR6rZ)FN^Y<7Wssgy+tttmab-lbXnxpca%KB%}UJ=kL#ATnz<>@|+sV z8E8<4aeXH5Hw^R~;O~KF!ZR-CZg;emmxF38<^9&E{5Uh`$Sd zmwQ?>z7MMX+!Af^so<&H)3R|LsD^Y4G{>ibr*Uryb=QK|@(Xt&?~X<0bnb1AM)`EC z8#__MX`Nha>*$V`=FTAJzh++mwLSFCv^w<0BJ?G&hSurL^9w+=(!H?`Z3Jp1>WxKc z6Hv=gZ=To;-mImh7e1c5f?7v<;n%r4s70g~9-VuDT0uB{mR!#M1#lOBLru-LlzP%) zS}?aG*_K*4x1rRN7VAyz_WYvWv{enIMU0^u+HM=3SxD+mTlJxKhdAc8=DHg#xR87? zH9LTg!mX(73T{olBQ>57>iFA|+AiQ$FI%a)`L@Si<+Hsh)qbS^Tc*dE}X z)CKZZpj{rdSa`Z#UF(8l;tanoyh!eKCH#3fIGpP% zD9f|7o?jh#o*Zi!yi6PV<)ka%T5?Kx*iiU`d{j;*@6@(_8R>GksJ8V>NteM}InsuaU(E;Q_ZRaEM}wnz?jp(;M_#u9=*%ELbe?F!y$iq#nGc#! zYR;W`;9OdxdE|V}BcE#?xmxqcx0>_BT<*$cn@7IeJaXCQk+U|Be6$&#c0TKpGkBs| zffU*w{HgjKMQoeXvW-e4(MFdEY3&1`rHj6cU9+FPR|ZKn%XmpUGEJb zwE+i`_h+oQy4FKPU#2#2kp9&4B~^p{$onwLT7cE$uA!^pR=%UF-4<}M8p^%muaytt zU&^m(3hI^WO1uixbJewN6{zP+H&P|oo!sbxdgVDzT<02huq!p4<9O~&DW}|p+;v5O z`#9!ZZx~3`qf{$7Ri;Xzt{8gUB9L?^!?St`L)A9fAt7Z zPcnb?+Mu3C{`Qfeo@f4Q&+*VB&EGpJ{@ziPUB7nWdUX7~>&D-^E@fA){@yVp*RQUd z)+4!obzSa>^{#>B5bKjXsoT||Q3jPavkPHl{5wJ;ktYpNiTBO!Jdde4KCuCpFx@qXK*b(lT-y(Q9Fwor4Co* zv!O=?Si$ui%E}wA#pjX=u%NaSFQBw8SKj!)L@#NyGS&W@^eU&6G?HFTK&e=wl+=-4 z6`=H!UWro1aFBij7+pz@l3PiyxukhK<@lOI(i_$BHJhYYs^e=GX*S>E_?k(YMStl{ zNncmJT9e1C316F_?iNyHFtE==BEp}2IUy~SLlj+@Zf{CO_^!m<} zCd5&eqHm6mqij4i6BsK-=5#c50QI3vQ9Q@SQRcW?pD|~I&oOa)jiK!9QYk47YQv4I~XJqnG^s|I+ySzt0a{ zv1U+IYBr?@8k4szr6#c-Hi8YA{=Kuk?L>XDa9auJbpj`SMN`xo2oqfmK|4wpJ6cN&J-boArNHe^!9a$g4j1 z%ckT$=hJ?NpQ2XHzc2p{<>k_ENo`U3ZNAIu%L5qi?hjCc831Qc_n-_k03KrWkZzRJ zdFk`)TFBi8u7#9hlz=+Y%C3c4gKgk+N?`rrO+7#*Ien@Jz{7e`QfhO(;pzy_QS#_V z3h%3-z9m;iVID-uwTCN?KGZ9(4S@!OxR-IIzxg1pm5}sa_MEP!Ts4dBHH7xk3*9$2 zLb4vIO-Rzjv0oXlT`l?dt}6zSI)n1YK_qo8u1va>O6&+K*(IHy zTu-hdAJ#Km?{9gv97VZ$Amth``FiX7EpJpyIG8sa$UWB_Lt>vB!W%m~xF+ip`4RrP z-0`iOgIR2m0bKdk&1l;|O~(5*rK~T#RPRrz;JSb8KLdE%0bJXQ^uqUAPB#D?z}(cA zREliehtiz*3+D2>lwNAMo(&og+4*S}ZgQ1~wlOtYqloatQ@jCB%?YJLA@`;RR zj1C^+U%Q4+Bfw8}el(uF-{P;R0R4VrguA;#X~O8>{%#|O`!-dezu&poH+23rI(V%P zS}Ddz;cB0iaZ=Q#)MmyAR|oA#cU4eoV^<5t0(4d2`aznwT5xrd*6?j3^<2ZtZAxo+ zd5-IoL~~d29l16-xIM#OVRUeNj2z6q<4WFjj?uxp#J=VlUY=&8aM$qiHrG+5zNxm* zHN3pbzU&%a4rcFm^=`~?V}u(k-2U&FFjlyu#1T`&$Z?D~lKR9^5V<}MQ%H|Gy;REST@J{M}OijRt{>R|$)AG=9|?n!G!LN~XZVPu7la2s0t`6kh@!;{;T@K`_Z(_wb0lSOw z-%h~haRBB0N$h&zihVGYz76hAzAvTkfW}DMm%49bU)h)P-lUVkld*#AP2EY@QTC?1 z9k#Hg*zB}xZOfHqEnwSIza7>(EnV95c8RvTU9s5h6s>t$)^@oud)aaeWX&|ikl@XP4 zdqp{O^V^ zDgo;`p%z0uMJJN-ycU~Iq#{DgP-DLn3{INbS>^A(Zv$pz(%`dSolHo2et?Hc&PCDh2@u8o{ep9<}Ia=vpSx6^8- zPr{jz@5$}ha~1iX-0p_R>u!u(PVWFcBII>vL_ViiLe8(3^W6-u%PD;qWd9rd?U=~z z+82E8BL?%R>)?FVO*`^n$F6S-aDeEJS) z{ryVhfpW8*;cjw0Ii8$O4+}j&c8WZ2TezLx5erHBfyfQzd`sYEiz4dNA^+Pka=Tq4 zf0Og=%HK@j&SH3;JW!tJj#@n{wuG~NF7mf6BezSOZ;Qy;_5|gDayvPnJ|6PF1(D0? zg`mHOoNv?E|GyYH-zJfp$>-F~$nE5O@Q)wazDA<%*g9zMJ}fuAnt93<7o$Ae{aJmsIfFc*^RT+EHH- z^$+?!$o<;F-+I8;+Ed>Kp4KyRytZ(=4%DcHP@k-Bpfwz>cjS9*BF|FWT*I}TPi;sa za&5!fg|!CD>k|Ldi&G7O98XPW(gLfM(O2%x*4c8L7mS4Q2mfz9cqEp9;qX2 z4(5!sjC2Zk3Vcrg1%2JzMVv*BC*Rwcvira@lCcleOV!lKX9`wRSAv(5u3*J<6}j9@ z4*^Sh5fqV!6p@GMqa~-i7`!C%lLDTTbA2JG#XqNXJ}8&UDV+UmC=18 zC|@}m)W=VY|Iv}J=*4#foI(yH#}MUAM{)OP#{122{L5+N8{Y@zWXF+;$R!FmgY9ty z+(<9PQ^*ge<_Nfo{#J*P4u}7oO6gEI6?=8zWv79saeXj6?Q~EscQBZ+>=tHs?ik-|lNPeb=)$!mrdAl8`UkneCwu?wRz+3ce*`Blr{u6hIQ?otXiCyBL zelpvDdRWQX7Q*lL1?7GVDQyFn*`Lx@aLN6_{kfJKd>+($YZB;~m#<8Ud}S)NdqiHb zCpxl07*l)k#PrCkUi}>8x6{VJfmO~sHRt6IQ4&XLHSL0 zN^{^2b0d$C)5sZSGtSk3JN9S8LG)nh5;;ve11X)8)GP8ZdBQ9>!C>xtqEcsgf@4uj zK_|F`qpCyXP8}$9gp+Uz2ApMR zL0g5$Z$jiZ0e(_LjeI3Uj-pkdA7%MOh_GBl09`sMqQla)cSt+ElQiHnj^+2`a>dc)tlp55cx1yz$ z6k3v;HiE^@tJ~K~sy$u1xi$gq09q-u zl4`HeW}Ykt+DDT$!Bw^PgdxybONBE}0F&jsA@nMzl(g#|>E{S??v!>VdPyVo?ov%3 z-p0@?QA(OgugP`ND^W_CNv{b|N-qfMHU8i9Dp5*%l9ba@A!X{KS}nb#(aKa?GxSQf znnX4IAGG60DJiIZCs{b9m9&#mj`w60l6H-!*JtDFv+?y|e)!q=`fPmtUz@+Kggah= zgp(ohs4dQrZ8EMe<4WDN8tiLg?X|IV2^f%a)N)@;9*{9IWTA_=Qa61Os6IL%8K@ETYVhA@{KZ(l8#c2(vLb9^)YIsm2{MBlzxNl4k|TT$v+8fBXkqtvr=)bE}Y zB^`Cb>ZaBED(R?MR_ggulyQ`Fj^~Npc&~3pO-Pb-ly8)NlysDDl!3ORq?Dr!r1p95 zDD~`vOrzYR)T5-M9$TqLDMuN|eIiNHab>FXqogCZbGL;n2~pj#QqNvdw%HThlP8pF z_5hWCTo>-eszt4|QqMHj7iyN3dX#LGhg`w$4(`qqu0NDkXfoii|FN*5AU5kinzm;*+`nm>F>Y2;hRtZR{XCA98r66UP zB=z)Q^`uT&smIe`J@Hi^o%tWE(_FLlWMws&9_bBxYi!zRqjw@3Ab%wFBQuKVyOM#(Ven|p)mk#kZXP~CAlFEmFg z(CbNEa8A;@Gvn{_xQ5K56yTb5AnRzQC|9+ESRbibPM%Tv-BnRmvz)y03f9fdDXWn# zNG(CN)_M)L0+YX=@>79a6G#Vw%Km|LHt3$j13+aRcNMvZ(H%veo4Ez(>Z0K9*Wp=Z zrsUbvj<(YKWdOOm4BT@tfa|osKrcJx1vTcaNv=F?2lpK$J(C*tK3sG9H0{Lc(_C{x zHCOI9P*PB9@4f@&1-1FjNJ{?lo`~+BvqN zy}*43wrnR#dF%`BIPksPb1;lkV1{x+iKmy$Bh3Qml8>N%7&wG{1f}7eO5%wn>u|L; zxHhN0ti#nG{sy3@qs*W*51h&AB{L|^;v|?MJUxn2X$FIXx#|;YI0I*M z{(1ptkZjJGBm+Xf&=>4aK9Kvp!2#3^B=zAOok9F%Pp*1{y*W##CutC8lWf9gEF^6X z&fpstk~Ri6=FUQDw*wHCIr*r96N#E~a#2fCbFew56}6HIZAtSa#Fz)dvmo1 zC#H=!%%>Tg*)YNv44QCso@sNWylpEE<+Q#S>i!nrpGQhxyF9!=&v z9M3|U%()=@QhPAzAn+j040$)p`OWY0iJm^?iBj)!denQMr%1hG6;~`G)84Gsc+aKZtpY_4<PN4oo&{Jz34xS12Fn79B_ME7P zITNZQ=-E&Ya}HEz(DR@k=Ip1gpl3im%ySQMX2~Kx<#^7xSrj}?>|stc*@5eCa?;HX z!864k=Dd@|Tp!1~Ee@V6_Hgh_v4_KJoM`rHb}HwLoW>a>o;UI$XP>>yS!geF=S9+M z*>|ZwHF)mW!{G($UdvAA?2=Q0r;k0%sV8S}^&L(^IRpGIr=5I;vw<}IT7Xv@F?;JIR)k@(9>WZ^qkkeki4tnZ~r^x-1)8l^0r(Mix zDQ9tV$@!dcaxv*b@Ip>CxtQN`CU_Qi9^pApv-8BcM<_i5KEug!kC0vipW^-_lwQv+ z;jb>{?32U8Vc=n0-9_zRu;o2MeiOg)a84OHoO^du`)90xcah)7?>d5$NRHs1r~CaG zOQ9#T-9Y_~!888;gk8~d+peePhTutm?_g#0RJZR_bA9lzCoL&ft_ZsBZ{ z+d$7q@r;!_z&p5dg}N+TM$Ik3b?vh3PRh$d>+Et)jA@-+7TPdhdeY$8SVfn!GCrH~ zIi%%G9iA|gG0$BFUdrFK;;-~6y@C^F&f@vASx=wClhv8$%v4j~igot6)U>2V4dqpw zIdeXB%R>vwYA&zlH|MUnn|*oEesFE}Q|j;K zoRxbycjZdH@hqf-YkB@kk~Wg7Sgl`4S_blNalX4b;Mc<6h3sZddeKU8ZT54n?g}?h zx-!}@t_81Ty?-B{{WH#Mxr_Wh&T6?UXwh9BwAn(-peFYIpcUx;pcUx;pcUwT-k>@7 zAbBOZbMgJ5GJAl(TOJNXHc2}+?+*tczg)^n2fy)OCw+|?%FE_qLUcp$7z?MPOlYM}J6u3%Mt1yAgU zTyO=F!@)eGT%k=^X`&0O2sNv1$w%jm%rT)Iph%TXpMOwD6yP| z1algnpj2}j(#v7gD<^2vIh?Y#x-P7h(h5rLUOQGJ9YHm=?YP$&ndB5cLCNG4}9ceArXuj`E@J!zPXs*8(*RbxpXv=RZ z?JjT)dkoJX&5F&v28;Nt!Ql4fn?&o^CVcXyNR(R6P9U8aSC9jdoxJWB*M9xtYOo)l z(32YX8XSjgc`T?^?Kqy*rhY7caUAJ*R+FwIU1h3!@5j|feCJ?fl70BjjY*pzW9>sp zJMmN`B`wF3z{yck`XUnA-rU`gzZn}PoWW71`U0q*&7Pz$gJ0lEpBe4Qdik%9tTX}C zlB~^V67rQ&-X2lD)4S)(NLNZopX2j)h%(sT$dy{gcHw%rD8tN0#@djlrjw>cscZ+N zRIP1FLGzGKcj0<5cXmKp*pTOp0v>sCjTVv8-XWz0cNV$Fs8t*vN)FYm)YaU&E6Ke{T8Z0G_N*Vry1SU%%j6!Wc9h#9 z4><1IGv194(v(`qetVwqyWA_Jy~gjVBKfI~MP-{Rp7I(0HskMI>(O=$y?^BZWJv#E6lr5@AT|j++Y@IIrZsii&#q*AoPHdg7 z{1W9D+ov19Nbe>&es_MUvX1jX58gl-NV}EiEGZi~qx4$g_cw-)B??x?HnioWtJF*s ztl}-DXo-#`3O3`HNzuCKXsgsxb5(SdYAaIH?~;O5pueGhI!e2hsktH@69uK56qI(- zu^oR`qM&{e(yl~DX{X1Qk|7bEA|1;q*g4Xy_Ux%dP32E%);-d(TclZ!NXPDxW<4Vv zdqkS`igfH5X{M)HHMG+MLthIymDKFbd$*?S?=SVqHBD1{Ux~75Y&x3O^w?Z+RMyhe z@whT&8#Xp=lQy)BBebrunMS4bm8PD(vFfpzMx`UvvDx|GW7APt8llZ7m&T@}vNS>+ zm5xv;+mdp9V^b;?k(&0{Rr6T;T`i|g+|{vJ8kO?c5_esBZ2sqXY<+b6zsF97w#8+MIl(=h&uXbH&#%#{)Sz7ay_^K

JymQ4*SyO!VEjDoZAg>KL?*l62`#qLN(ccq~bmdfYn>YiG%lW}sHCOcG^%vt**F^J9tA z61$i7F0FRzmMfD)sdTAaS+m0W=cCfp8NNi>G;b!2L1WjkwoU!I0_nK2=I4J;=Tkmf z(+HKmj?-G5PieHO`AHJxC!_NzpEt|bKmR%1U48Rrxz4Awf-TqJHGUmi;=1+Cn+?$q zlt$<$rMp{#hI&Ud&Ksel-8gz6EhXOxJ+(VhHz5(hFM1QXk6Y6tr)$ShMl)AmB`vUrY_f;*3K0XVgK6^pbXD^7lYWE#{1uKCbN&ArR zjpxVal(r!43+jcm1!;fKeYg6G902M~qHnyuNP1aqMfw`357t(sL%=P$b13;C*e3Mi z(vEQ`c95+pFC;$#)c0#4=_pXYG3^+KW3ABJOgqNW==ryyye;|HL4C}&B^?L4n^?=n zu~;tLJG>p~1khc>+eLpatsLLP`k)14`)D=M%JD61E8Am1SrmP^7DfBaqG+>O6#dS$ zSDb_{U3<+;KNofz7~Cpar13QXPL!WtfKsX<{OGQi;nsl<@Z0t0i zH`pK4hiDFIAgH&#yIn-R!sn8PV7HhXQNOKuq@kc*T4{%|J70$538t^s2BfvIcIcTk zKl(1Y_s$xm(ltoxjL5oD0;Z#%$=Oa(&rs*i=wq{QM9@(;`(@McHqtl z z{cPJ%Is@F6tM8GY0Uyx%xR6nG7O4GwA=l@C+i+)VYR?7rU)4+UEcndUl(&j&psnJH zZ7arFPR)7b73A*hapdXuRskPVp4)=aRt37c*@Ek4;FjEJPF@99bmZx)=*Zig@&ZO% zHK;a!0d=jxYDSp8jVO5DwJ*f3}Q%apc&)x1!-U)v0T(k)z zt1IX(uuZt`4sObwjj8Pcx@yqlvMV!)V{RkHnO4s}=x!ISV zzai!MapcWsv<;x_4$b+DLdV;DYV@fb3_9}GB6s|`f7Q|E$kVRuD0IK;P{x~9O3{%w zH;%lyjJ(l|;<*vsH#LXSC~%!P>gIsjEysY4yxGxyIy+icXLCIcjxn2YI4h3FS&YUB z@ELtmXGT6aGjhP0Tu-59R=hh2?lyzuDOsL#pxtvSV|Pg8M@BTS;Z5X6wI>Moquh_a z;HiS1B`9|@s=D#hZQ}v4bqDYXLn1F6K%1!9PiLUHcg0ithD2`eeiqN~tDq(2q5UHz zQ=|mX_)AiIYGpb6AbOZ`VSjp?(dd;eJX2s0*K+9optf(%7Ss;v>4u&^*gW>Df%GuX z9BfIgrxkk6VKqq!&C?EB#cO|&zcE={UCleoBr8P~@8P+FNf+WXdW_cnjB}CFo;^LS z;FS5awYqjw7Sz_N^;H>BTdUUBoKo}n{hnFrO4ylDJ8z&|`b_Obu1}MtC|R461|?ZY zlJzfX6p}4h`=6ier@70|Pxdp-t#1~8L(}-Hno{<={Iyl2bpEDq(TZzrF6rBC8Bct3 z2eo!-JvBU2-uBVkRZUE4xAuIKHpY@ow36?(EwydCE84&C{grptv>j+w`jL|DDcKSO zzsldC^)B$qp{-|& z*@m{BEoK|q7Fld9E$Znv*0p`)o`eLjsKspBWx^V0~b?eh&8zvX;D zNnCo_AEZc$4iA0iq~y`kIQ?U}55&s-#PO8QtWBlT z_-a@`DeocW)U2D2t@xScz0Q8g`ua(^-DOq!`o{AU>FBrCt|*e!w)#1u@%?1=>)3|OI}Pbe zpH_b2+~V586?dthB#FE3eo|V&7ICdtyN+$h`sAbVlM+qqnOd7Awj!rDs;9(^#>e)GhD)x7R17exg=kP4Sa*pYQU1vS!yO#cD zy*{arN2M99oKvOVvMRZ_A-tj?&#cH#K0WeIL+726p3T{)v=^wc{Uq^|(kdnGG+3Ry zQyTlL)&tu&)c>tXJzL{Gvmt$;A50`@t8FXkPa4Wk8b{NH^}X_5w|XA+|MR@_QS~SF$;GSE$Cl4K_LYX}+3K4k(#o@3 z<56p?YS>)XxV~53PwLaPHiV!2FX-7CvW_iZpUCM;dr-^e;)eLKt!jNz-cK4v)5eYc z(r4DUJ}FDks4KS}G85?5JqeNxU( zN;F-Q{iMWC8g4IMecvnffpYzcI;o^#a2{1dS?f1a-`v!Yeo|V;CXWKg$ba4+qkJ8k z^gs3%-_9PP?}7Fm&xUr5S-VqZWj$Mc^G<#1*wPAib@EQbXxg~7#EN|{aT0k;+ND(T z%qizltJkxY_ksH6o$_ZsPCxl?>)BTJ+o@~bX{_G9K0Vv2VqHjaBw)+eJOh))d)&mz<$vuxGSi?ac63b*D!*TJ;0M% zJ^QsIHR*Jrk@!%K;5v`@jGo{=IlY7RVeG(~rU`cf$rX(ydx^21jl|KM=k**mLUIer z$#ZyZc;^VNTT(j$DZ34MH7R)xug$8#>zW$h-4>|3h00r{M{JdzpzSd%w#P6^Ic?y| zs~`^~{R%5$y9}e9vRJFsR*LT2hrg|fZ!nzp8b-_c+lSL?!?@O)emLzl>_e?MEVkk> zTCo#P42$nHoK_pobvv-*3T@Vmns&TpYx3qKyRX*H19Bsa_@15Q{y>Dut@;6OwC9Ui?wpe=8-jsWN@TN7CJ@=^%&!m<~zd5x` z`pv0j(r->J(~Y*Uf7vGPBHm znS1sQdyBos)^bGJUbdR;m)f=;SBV=Kp`^AQ>Y}qP;fOTqx|B`to8B?KU3#z7o8&k~ zKex3~k4kS^-ahGlQ~RX%P3@E3H?_~I-#4{eUGJOvNbOsvR!#4lTGd@6jzUMJd$$_X z4y7?|OVrm6>3!2XrngJ)RsS1FuSCbxVu^42cJgT3F;O$MaH3;5WfRv*ZJt^+y>DvO z^uDQ8)BC2@^X(mrj!k!weAIRr{=vw$J<9vT$7zT3?)CR!dvA%3QZT(s;_Rt4%K3Y0 zlk|?M4O7eb-f}59y!(yHXUT?*i}L<3`~!}gMnh_eG)iol#`FhAbUA$!*Bi!&wnwB^ zNfdUxf4Cjeo0i_r_wxPH94|WO8#!pzbKytt52@FuH%`5v?lxK7xUe14ilUtRuhpwpZ8J4*g?GG`1aFpOn@r<-aY>BlYpm75hoz1nKP?+E&hQwuijG)E}h& zimj2}HPJt{!OHEE`gwVO_}_1b@^O*gEWPFGTSLC?U>)avQFN&;)H9nyN{lNk{WX@T_Ca*{OLra4x5)m>Arc0W!#lvZI4 z;m-}7k&;ZeY8^s(-z&Y>hg+lk-Q`$GYoH!M&xPS=6h5hTXz05qIWB1rK3+Sl{O%>q zi8_;pv_s-AjU5*&_J@YPby}MzIW9?XNw%%8HA-BlTz``Kweo~Ly;i4`dPl7`E@_iK z+!~1oCe1)OCrs^-`b^@ANm4HLpEQOXO=;Fh`iHr!zxu^97d$(~_}ree(2w&H`XZ-# zszTp*-b#u;+lNySJR8DO5^Ca^2)#k$nR-HkXl!85OAw7e>j?^?@n?-QD|!xvk;X(% zrkF%Zk!QPd27_~`QN_B%6B;^$@`MT0cH-oQQVi3M@jR6dob=%C@b#JL+s89jI&j8= zd&g7!Sx;bT%b5`FEcaxHwwx5>)$>e@ z3N$xHG946kVuPYq%+oUpG!TQJ)_|xf@3+C;QR9(xPLei&C!|zfzA?bDU;f4Ro$Asw{>h~IiJ_Ie$t>;(+=us{3P3URV|>5J(PZC zYbBk-hub0jS~be0-wn}fBS}DD0YNhn1sg=^Z zq*hA5Ikl3UNPTh|8;RQOd6&+yFQnGEKQ^mggJ(i<6T zCvi99??}f)!PHiXBbPX*)J*M`sF_+g(XpJeX|$#`Ppz8XH??Yd-_)wB)+c|ocF=Yu zKei>x`@^c+p{}0ne34p1$|lZNcOSO*mgs2TPr9=-ho#m?vs!A;)Fw&GmfA42Oi9yN zt4~gC`0?ApHK^P=jSO3&zWz{GJILKjJ=s2N8;GeFq_#;EwugMU9U7ufcBU`Q`sHnv z+UGyl4$eZ(MUIT}aZz78l=t(x+F?a~sr|w>X}CVQvF%X$o$}uD-&UIKSI;-f$IFNN zNqPG?UpZ?f&XGojJR`m1iv3}Ax>H-mUR0kx`Qx-hd0+ix+u_6Gq9Jm68Zosas9c}? zzu6AuoT2fW8T&?(4jenFpM0El`0tI2HPsGvOGYLBV=L9iCrfL1+n{`XzT#;8I5bMU zIeq`CerNq7anRPmFF3Uu74Zb4y)@ApG-T{uE*-1XIFmfq{VPG=h=j| z;>T%+74?U!wtF^IW0Pb$xp>`r7kXPd(syq%~DCHw5oPUT&A((V#WTD-a7Ho)${p==#%U36{%m_H=NIE zbxJF1;gZhe!>y5cV3L;0Ibmvt)MpY`O!8r=|D-YGXiBq2(#z@LqL=GH&iL&|ng{kL z?@MWJlyT;vSN2S9SNwBX;m<+K>^grAGQMYfEA`Bd-Xoslx7# z#N{=jXN`N-t~d=Hv;HBXXO?Rf7Cqx!+okoS+yUF#%OI9 zPZL%3geRt>?C{jn;Dn6n1yc2--YpD5bud9Z_AM zx*k!Ru-YF{Yq|O$QERobji|qybRU$})a0>L+9z+VWoO7z*}tkSdnQL+&)gK$ZJ!a; zZQo1`@Jb@1S8#3o^@8Z&O^6(BwCqZvq*rjyXxf$8S(ML=QQC{_4xYI&#@VjS&ZhpX z7;U>UJBQ~gzzS;5p{_DBu6vRFnCI^xy1LQ0&n2Bh6z?X~ol~qmzsNGWcZx8=Eh&Yo=-SGJRg3={ry77_6^Tb`c>E`?90^)+-V9n zn75*Y*FY)Y8!b_x|h68y1tKn&$d?tL6r?TuR?))@772|Lp$lU|Nf#G=a z>xj61Ju%;FBgcPd5Eulxe;T}5>9Yrt!``{nQ@ z{^}L}>Q$naU(fx^dFnFo0`e<}Pkt466?d*6T^@GjFS6`qo_~e7_TM0`{cc?M%XZ^V zmc2&(%i*=4UTSyl^vhnS{8~7cXO9cNru=&NT-crZ2Z^fvK==(czYcp)*Dw1m<==!o zx$2i49gg8|4&qlI2p&iNByI3B&}ifj^S2Lz4~B=r@A#|VhR^eN{bEFNzhz=Qb9!+82Q@Q`pQcsN(`(*fC%uv1tX22mcE?HHC&9!yyscK>W} zwnJDPb__d^mWBmkukeK+XL|#DBfJ?lr)B}T3;6_iOmq0#8$o{8Jo_CrzYA}K&3NJq zpf8|f7s%IzN4^QZ8Qucl3jMP!_?*qdcs^%Bwkdzn7oOMxF1bnAl=Ajr5x--7 zYQ|+7hfSy%OL_flqp&gM_270bz!ubQ$aNoZBl0oSub0gW8-_mFHeuVaUD$@SeOMcg zHv(SSpZC;K*B?~RHJUUORIj>_=XMASNlU?PxZ09mxCOX0>U$=S3p zm9o;-G*H`THE9Ouneo-pR$9$G<}5djCu_3lVOqd?8m5CY!whg%mO*qEA)vTSj?^#7hJ>{!FQ#m) z@>Y}vhauD~qP#;kC=8~&J>^B&z%YpN-o(cEO4cQG44pz3Qs>Zta+k0lclIG#hB0c| zh4$38BXtR_iMX)~Gx&Dot%=p)q z{ldV|n$P3YLYvSQY|B+Oc^9x1c}wyxp#^!D(44$WI4s8dI4s81IV?u;I4nlXIgDr> z2M~+HXgPKfYc4!g5HG5$!K z7=xruj6c#QM*C4qxf|=N?)+|S_n~{}ne_}kz+Ryz*gKGCHKBKC%I9?rhx0oR%c{8Q z8mdTr!*MY#&~elsp8X+vBYP8kGkXhsEBk%cgs1w3CZs;$8^ksF0`Wh-z+ZfWbX-=+ zoj#$GR1?0=-ER;Tqz(CRvfpOE1AoWo{f19^8+?QOycjd*yco;lycjd*JYsd6O})`_ z&Lf>m^p7(r8FS~1?AQF=+u8YCotIqzo}ayzy-w|Gq_?vRsktC~m8-Y2SIFPaE~e%} z@WSk(?5Eki*-x^Usr@7P3i&16y*RrsyF0rFyodYu@zl@2d&%#}mSuN>cV>5ickz_6 z$=AW7h>p@W#!P7&W2UqvGRiU3e4V@pZBP?>u&@eX2sxOC0xUuWSV8Obp#6Jh_wzkJ z&wfPy0C)$V|08Pd2Y<}fkGQ@syEH~0x-`Zex|CmgN%j)I{vGgT^6R*JY4&3FUiJ_0 z9r72s^Gm7? z*{{G~@kw1tYOycRE(5R6z7O6&-jVAY!0%@_f*rWuC3`q~2z)a8CHNG17p|WIf5|s= zA$3I_>B#e)NH>8uWjBL2XSaa2WVeF1(iWYw<$O}->=E+L*`ws0v&YCg(?*YhKOpbS z6Z+G1;;N=bPZFA(^}~QHXXP*u9LTj%NAx<;|D=N1)uEH_D@~$YQ3WO+ zjG?SP^>|T}GK}?^8YR7A)UN0aqqmH^1KmBS7mfP@^`6nYM$a1MAH8n0tLbf{H_j-y zkX|@?>5OL7=$)hYj-ETpS8YMhI@X(~U6j7`{22=c_5A4&<+S7%)G7_ia_trRSS4S^B!K9QvVp6J0q@Pr)n_g0? zmTHModZkGz{nHZF8b&Ym6Dii1J8<=ilU`CyN=dJNb<)d`RXfUR$Co3kc9a=MN8hl9 zk1zEB?!i@0P(HpILa&C5uNCR#$Vya8BdavZ)Qm{Ay2n>z=~dtOO7u#j%rWIylWH?5 zm5(p=MkzL&d!<)DzLcZ}KsPyIKT?1GN_zDr^<#9(3Hy-x@-5QKh);d^UUe(INi}@` zP)h3WhVqNt^W;8m{Se&8-6L|s?x5a}(yJTT9gea#rLK`5c8%k!3#j!~e%Kk5XFI++ zf%=J#rqnU=!w#VHi2SfageUnRZF#6dL>H94@>l#80qEARZF#6dP%8Ts@2k~ zM5*aeY5Gd^s{DXbv!Gf*S-qa4tejo}s^w5gei$O9q*q`({qNChO^mPl=q06AH@+NM zwWF-=@wF;?m5;Cb=v6+xK5g{s!swC{rcqWmKP(?#_0g+*e5t2bUoR(gtQig3nXAMP z%jqR2lsBePCMW#x_$udz<@8G9Yii_*azc4y8fA$S)-}G$=~W*;tZ#fZW_`G-^@i4i zp^SU|)Ely%*Dj$iy!MKQtmn0R)U`g;GhfSzT(NvTpXlX!BiUO%%KFfi{YPETm#;U{ zN~7-ee0}SU#;gw;B7eEwC`n;MDXl5_tC~@!CCX7&E`K$aUghig(#p_%8Kw2Sum8mQa8>lGPyQ;W*NXC&>yOe2QOBWtb<@?OdSWe{Mm)BsDN$qmpihRP$OKxKUS#yX&~r1Hy1P#&W8 zKpUqKU$uA2Gu0%>m(t!0*O2P_wQVL#r@sD<3ay(`Lz{rsP1lfmQ)%6lV)|EQple7i z@g;gmsamQvj$VmU(kxL*su{OhdTEVzwJ+7`qF17nG?QLa8bvQ@q(yo{q?aD(_0g-G zQc|v#URtIN1Sl1iVVz0T3rR02CFP{o(0|iQ8kMM~ zu4#4jO5@8hwel$IyV~(pPOn5MxkMUSQfy5hRFXyb%s>An9tB$nZNc(nO zZ@9}btvAw2!!?KPJn`S_jfT%(ja_eim>-sAuDaJ7f?tE(czcN)X6&b zVI6)+Myt<8)>s*B8oZ(|n@c%AOgj8zDO*{G-`M%9Vf=7K$!j)Jm)l zuHH*rQK`6o`KxwiSdzlh%23{@r>T;cGMDT5F`%BON@1&#zm&OFl)~hM%3?}kT5Qz< zt-PKut>kMZue6?bO;}ph%dZ+Ee|sud|`wTQhhhN`%qg;o-qWo3s zGf| zI4w=NZpEimfkq3e=2M!0p2nZzZ?vRFO|0MEf}~E*=o`)AXEvkUJbrTeW`Aw%cctH- zeo63jQ|E0V{y%HtUd)azTX*1i?)~f<- zQ(LbIXq(!4t9zrGn$&uJx^$ENwqI)3TH5+aQe66HMEm0VI|(DmDK7LScwm+*T0RW-+;fx%e4{@*w;aQUMnfBo9ih!I)4IB z!O@i0%}3?>T#m|riO=OI>PP2e@^$mavh{NP3)iFcC^&|E9iADLuaoP=I5O9ZaU|t+ z^0E1P`6Jod)Qrs6r?fmoKkEGaCHz$9 zQ@>%p0pN;5J`S9aj|bl- zf0HNQ!pnGSJ|%x6o0d-nr%?M2p0nffKk+t|__4kd%j0;@-|@^FS*tKTpO&`@)3~k< zGxF(qH8rj9?4CiXWtf@I$XkY4`OLfp*b=|&S(KWG+4-!zS(ua02IuB;z}b0oysGC? zssfvW^YXcQ6R-*|=?(IEc}4WBt%x43716`BB6_%1L=V@B=;2xs{dX&(k8cGYx9`z= z^~9}+p1AO?@IK{0Cxt8FbBrAYpW_PrjPW<-{p_1B;}zTlkLQ=cSIL{ucU}cw$~MU5 zV6SCAV;@m>_ppy&5j!uU-omf)}x` zs5-ll-ANZwe{pyvybQidehK-@;7ja>x`fh8?8&OmE?{q0b#^{`kuIVB(%^2aODVm; zj`e*uj(oA8S*R1p8}s`H_(-o zo@9s9m6Wd{{UWr=mW4aOJHs;YF7}+Y%Fbnnnfn{gW$)Az>;}4;=biwsBL6XW?qE07 zA%?<37HBQgn*N=$Be#H^|dGm^isH zrsbK=wyoL0cYSEh4#FG2zw&AB+4w#9`|t%-mr?Op6DXoDxedkEUZ{RD0B?O#S& zAOAMd*S}5NLELH4h8-U_vcu#IuG+B6<3_Fz$HVm9$ zF(<{{G42i6jvWGr#9cLQ*vIp2uC^y_$KId)cz#jbQLrfPC|JbZ?b%6mBDIUz-*5tW z0#}PkJ7hajvzT2-$FbjG3F&z7cxrc|W(hl+j-#}cT`b43i|Q+JFO|EG7RJ3j3*+9N zh3wMVnq600QNJZ=Z+21b#rscq)H77q6lRZBRUs|03U@m`^^h_(lFpa0BuU zi^uZE!N>C_z$fzg#oXeT`IGtF;>r9ea2{716_4hRfsgUT#*{ZI<`hrmS7&pItLdF{ z_=~6Vp~WNlqu`_Y#>MR7Sa$Br=BZ<|Va4+Nk$f0;hZeJnZ$SH5#n++#ES~y$HoSN^ zU!D)=nPJ6<;-UQEd;~Sai?xdf^M~@asTom>Ebh-A$VV0rhA42_L za58y6YG;A7iltdU?$4yWlwECW6_dEX7HLRPMR~2FFL!p%nidm^iA7V=BybY<`cS(| z)`$B$XU&T7+;2u|S~REJtY}fJUyK9Can*vHi=w(1OI}TCS+pv~6zhTOQP+x8 zU9_gARgo7((G%=h^eULHBK9hJ7ZubLVE3X2*n_J|$`xQYa+WYWlaXqQ_gRRG>XY8j z`xLu?yU;J+&ujSIO?bW%>`MNx{QZ1t_Hy2p>sRtF)V)Ia<@}%dzo`EwX5CVjbAiWEy^dh~efFgFqieMK|*Y4`- zy6fty*mYgIyZ*o5bGSQqCNs$-0Yv}#RF$fs(-@VitTG##RA*Jt-lWQ` zS18qF)#N=%y|O-84S65ZfTTyL?Moe}S7v>o6R7Et)n@%D_a`5a49NOJ>#_mRff;!+ zC>sbJoDG8BlMdx??nx(Pa&Dpr@?sR?Teb7?9k^xdQ_@5#Y+y69L>y zel8{HmFzJ;pPKW+X#!WVfBy=eFW|ec2rthHc)lhf$pG^K5_UoSnK|LvC5@`t3vw9|x`a^$~{XCnL{5<;w^cUGLp})+21^rd_Yv`}D|APKk_8aJL zvj2wm=PxEPGDa!iz6G)&DLm$lE0DXP-M(7)|hoEoF9)>=Y z-I={Bdv|sR={?XpL-{?~d$ZT^^xo_)-rkwr&eMCL@68_1?xyB0=sU^pf!+;$2l;Kh ze;oRF_P*>qYVLu)o%~kn-Ul5<3vcC@4uigr{CwV?2YqYyHt5@Ux`6We(8tIxgkF$c z1icXY7V?Xs7eOB-za)Dz`6Z-_vrDr_vNu8BMBSyNOR~$TxfJ>^`Q^0nVd%p=pPk*1 z-3WaJ`B~&QLT}7&%FfBI%dUrBPyIQhS7hgAuchu>(mC0geCj6XP1()aE2%#h`Wo^x zsJj_@b9PI%hMHGqr}K0R^ww-#ayq43v$ff)d9#+ZCOeYyTIe;|wa{yMI*Rg<*}Cj% z@^z%6vh~@kcv??dmu<+d;%NhEeYP>XlBbQN4cXDz6+9hH+L#?f%dUW4!SgY+^zv*% zx+6O!o0y)Q?SSs!c~W{(c5*g}nu%eT{wY~=dP;UGbUgXwbbEFp^u+8W=t+ETTzYDD zS~e~{jh47G|I};>pP9_Q^%Jt~StaEu?84_=;?Dfjv#Rv?Y#Vf2b^`PSK2c3g6?@*d zX2)kWl&jfczd75I^+~s6TcKO2?MqD`_Tq2O+>yU2+nm*=$7aVtkIObeH)Z|Ut$!?~ z0nq-?W3pqjHRrEVIdvKe*d++UBihKt0}J{jpm$(;o($>Ci0`$ zsqeWD!^l0iVl>p#0}i0(C}<OC`|f!y;f#wF7zPvvBVdUnN6 zBQ#R}>Vq-GkYL@cK~owDaJ3?V;^x^c-;@^Q&Q?64oqnGJ(^a}a4dCprwGbTDTL z4B~`@rF>=v`|1aB-orp@XHuS#j!llq20%R{Vr=4h5n~h2j2N4EM#I?TkaR9|ZaNP- zk25C5CWmsy#8}RoSO8tX853hUZ(ZC!d^GzQ^kdn_p&!pa0j*+ZynE!omwhy=3j5@%!hZNk$#1g*NWX*r zE?bHf;JFc=u<_rSwMO7JG`tEMupHa3oLu{`96j6TD|spp_GCF4wzZe@RE|FF^Fut9 zW05`teFJ%Uux!hN#aj;6psnV)CsHl8Ur_UNu!^6hH-b&vh;{eV^d_vkU#8k^zvS&N zKsA1v-VCnslR&i#f5mwQ*Fmr26VIjEj?aOH+yZ*=+JGZy+xpcRi%)}|84cxym4-b(o~Y$x#)ZL8lyMK!di{+PZk;2&?} zlW%489--!8(x0H>GH>Ut)>Jtye0#u4p5{}3PCrBX3-oF7PbZ>0o{aF9^izrGkLMu# z59o#1kS8PjZ~BQu%;*!~7=KMa4kVstA5T)yB~gte`xxj(mVJ~|f_{v=jQ{f;;EJLG zWu$jO#Sg?H-wqXBC=2L9SwJ1i0!mR9P>QmEZIlJfqby(^WdRo{3%E#Gz&y$Vw$U}< z9bLgZ?gzsWG3gqR6fpPfUdj*hzg>}5qCH&+y&{~%Q<+>v`O0uEPi4^SDw9{G-o5xL z>aRlQyM+8|YF-77croQ`D0}u#1*KO*uSMgjNIbQuB6$t^N(EZW_0a3k9xBipj^*sC z2cZx0x1OTI$s_1nmFQ3Rq2C@ydI0(WZ#*BT5}oOu^j@})Eif|hs^r5#_x&*SPk>~e4fgp)u;8lXgOoo6YN5rA@2Bi( zWopKv%T>wyD8C=v_z}wD$5qMW)QDQDH;Wusfk3J&znAnlSmf!H-W@dNcT;{(nt|Sx zGH)+_5^ql_)92&49a+Hja(|n98uTsphUy)xPQ;+A6LIJ2M69_w5nrxO#EYu~MqHhU z5mzT-#MOyNWOZ^H|95qwMqZt$qgN-7@(a_%)3nmWlb}+t%pOorFw&FQ3!0Em2iH6~ zozCYfD5vBH^1K5~bUOJozEj_?`$eXKW%hx_eaUgptNTu-1)sksHVmMAV6ub1(h_(> zRugp38g$PG(MN00J8OalYUvTm52L@;B#&g96Lr1Ki8|nBP_?&Yn?Ts!3RO?snyB|} zP1FIm@@@;LoSNft$tLpSdAk)XN89k!`1Z z0?4M?>t%`h>}9-pN9K7t@5(MAy&HNd`NfIa@x_UH@x|bZ@6J4h=e~fWc|A@4!MAU3;3hpFzT&0$TTp%+qqT z>rcUQ7ioKj&uGclfU+rvPfMPq{0!3B6Lpl&rzM}I=GpA~nV91Dd2>24`i$gE=$Rmo z-{Z|0U~1pX&H`%_oBVDj1}W}#7I>UzB8keqBH(uC1guUf68W#0XsKA;x!`@`RkIRt ztXYZ3mhm|Mlo^Th#cU35XM-n-e$7Zk$c*y%BACqQd3Q)6;x(6F`Z?(50#Z}Mlaaz- z&gL;9b3tC*9e5DWU&#(i#OI6+`EqtB_4B}O4@$lY&N2;DW+SDqWgDscDoDyS5Sk5% zXx|3jd@Wl@&4OfoB09J}5f}6UtW*Ja(HP4`O?xYSSCw(dst~@={oF{mAtv!DZL6y zW;FQaJW$K|E4zmnfNoYIKWI6g54I+nbGd=99lm~s=J9}ZqQ8)UN^wX>lWBMgoq7>|l>HEt z^GBrqrN2<~KcJd=4*rtqQFsnavp+~>Ex6`$lxjR0$F$Yx)V$G)JOzo+I8Ae^3k_cM^qKBb?LYD#tB zkq1Jjmafd|KqaSAJ`nt}F1Z*ypf0%t44^K#6uZAJxeU9%4lDRF=oQ$;b;*_3#&yZh z!8q%{IIH-ppMjj#B{g82&!&yRm;DU+XGzbdpTV=;h}YWZPxI86d_FvXJ{<_U^C{{Y z@n8?6_6yK|!jJkXYQ9MM3+b1jUrfIY{Suz*f%vk&3jGRx+<}Q_J`PO2hIRTQKEDQU z_K&bj*HAtJpY;#0VShl~5u`QPsB5V|io7vdjsN=l*t6f~Q>#fwV7Go3zx688_n_aS zb{*DhBX;UK=t|zM!iN1feAp{V-^F76H%f=6|C)XW`W>EDP(B>`t@PW_Z}YUA@(QS@ zV=gCs3ybxel$NEQayd*JIN`iTtX@uY#Kz@(N37dnShL!%2T?kVPkLISCtDsy`UaNl z*C{Qf)nCWj9Ekn97`g;BVkQ>tBu);T$%%op0-edzWa?&c3gHaCaSBf}KqqGLiDs%p)ci;SkQ-nAshl~P)pq~PV}40^KfkHxzM>F4*hvE412jhvdodTjckg_{Xr+{buqz+r%6Dd81 zW)Xhth5Ul4NfXF`KJ10*1m#m zsPX*GNy#g+;h=!$fUu2A&ZaEVb`IsUD4z|2b}r@f$j2pTQgaq~*?E-DpnN7s*;>j+ zk&jE(ft8I*)`OCbOE!RyjY~FyjEzf<1``_xu5mQRg&3z1ZtK*gr>ya{?BxzSa}5xsOAc-X!!1Ds=c=Czl^YNN2! zX$GF7gK4AQq=U2Pk{=~aP<=8#PKM#1`El|b`46f2QS!q?AI=XFeKdfRiQl-uyJttMgMn)sQ`t=$UzjH}%=~`K0kr+!aDuPtmi9-kWEM zuN#tmmWaE-+2@GFlj^nlJh6FF{aD89N%d?QsVCLr^#w`;GS30*Ph1?Q_(AoD880W* zL)IfT-mPb91YA$f1^u_AJ2l3O8T;0Yc(U&#-O~Rc_N^N=-8oCt7`oon{wuT>d1Y#x zT_tb6om8aXBR;Nz&l^+red4#ersHWgve@VJfUzYxor*9-B%3ac5QTk`1>3&I`QBz8P&GXlZru!9nN==sj z7jcGPC4$a)L*wke9^&b~N~D=_g~ro;70<_)8Qo@{zf8FwW8EAg-I_zBTXTqXYYvfa z%^}jQIYhcOhe)^P5b4%Tgxg>EDS6VIG%PKixsQMMqLbI)L%AP%Kc18td?*jXA*X?A{w|xA{2ncZ zlY;p-4McMawZEmtxQ9}bVo7VqXOyz=?9-@FKZ=s~5c+O3$&;K*Jb6mHw>XLbczU~c zIl6n^Q{BB?E}ns4?4A2`JbT~RZ}-=_|32=-*JgKL&jh%vmcAz~OoR(-@4F+?Q;xOz zJ#*20|L*knw1z2gZ4m%>Jh-pO{Y0Me;7JeejBp2%`y||}?w*MQvA#U%({pvEW0i>p zcvk*FN!)ee4kvfq8UgOUry1CU;sc(xKNBlalpyX5@GSmW#EZC}H178B)c!fxf9^N+ zH2*`e_LO?=B#USL&&B3*7k}JM5>L#Cr!sh3z`_U>x#TH2@#m=Vr1CVJjGp4F^K9?OgAdM_;V1Fo>HBye^^XUy-c$JSo(SH&g#Y{f z!E^WS;2F{L_Y}UpgjzjKOP~%jk&+z*nrSwejw5E7Z-%QQTAu9Q%5QBVEh=4M> zJIVDi-viZSs|WgCyvO={ZzbIlqLg0;)gycx>DJ`>;E~jCeJ==oLaWXs-InN|z7MLW zQg5_Wf8}d~zfuqMgZQ6~^fuP?_4vtO9q8-vi(eCb52Y=(@Ce{VbFtc z2I+Ks7b3>`HqHaR)7P+^bOtox=|tXL0M$dHpX2-xIea0$7dBiH*~kMi%teVP zsG8srK{s534!@Fj-l(w>{oUI(yno|x{00m8<5C70@3m`mD#CObD!{Sx{>Hlp*+2~^*O-V^E3c%Ss4NcB*8&##EW zcr?;s&=@&39v#&)N=A^p3EUe%8+ktgD&8`ZwHzg6jF{NnH;tlZ;Y{yf@U- z;!C6|sJkvoq#CHZE=r`nQ1@GuNVQOJ|I*g#1?|swmRQp%)X0buu_up&_>)H{UqPva z$M6c$CTNL~I1W04Tu;`ql=W6&2g6;pkV|mY63^PwCAg~3+TkU*s?Q(fsRZ}*`9nOF z;Bg;7SrqfX8N(J_r3gyfvfrEcCPRr;L)^Rc`tu zx!m<}=u_nHqx3}Jq3?x*%5mkc+|otq!-1bZ1$~N7e1N)A;I8k6ehe;qJ9VYNUEdXW z>&F6j^*)GCz-8sG-jMJ~a=EK_CVYxq?&>WHpC*^PdauG~0;heNT;BRv;H%!5kn!u~ zv`@oZGfHoQzB%yIJK>~v!&l{}cSG-@_7>8efxF%mcptwz*Xh8^45)kySmf-7@p*=v%*R~ zCU93dXcPQZ9x9dJ%3bB7#^tI5HwW%IEb!0?@KkxQ+*MvB$CZ;#44l>z7Cg&Xt}3UU zM6LXEXyC4LTG4d*ZGGUXo*?Oo;c{9}{FK|uTc^QQ52Pe-Juq-rPsH$yGxrd8fr<#_ z`^m+EjM%7v79%~BTJBmG(GaUoc^0J-dy=~j2;A_XfDPplA;yCAf)|SjC2-eDs3=eZ zcddqs`6O`HK2Xt~1n$}oDz=mGmnrmMo_?OQg=Sg1bvs|eJSCxaxTR$9lQweUH@%#bk z2jOuUrT0PK4`<9My%(w$$}NC!LT>Vd`(>2g34K@KK2JmCU3Wp{N%E_^;JMGBwcSJg zy@9{oNB(JeihS=*`0}&RXZhUy{E8CvKI-o$eG;DZS>8RsQwc8hW}aS0x&xl%?LD`{ z2j2{bdNlAcx#X>IO?jF3)Z7~Q=`GM(;fC_rn*-;)nbIxr$+z=-BUBD4cfJ97BUG*} z-+2fs*E$C(Hc@Qe+ypU9aCtbxS&I}yzOt|5zC|?!$*wvIyhihI9y&CRy8r<_5sJ!(wN~gmU zUrj0A1$7EMSS?guyn}QK98ykwGHD0=a%P1DD!Fz5*_|iIuaN(lY3B z=oa#2@Xjr8w5^nuLgjSFlY9G_JaHTOV)*Pf=r*1g!Ie*do)CEBi99VNEed?+XsDd3 z89E*+r)p*`90OmGr%mMj#=vDZK;?M&xcJ1luy*7)>)|)+;f`ae8OQpbNj`=&mUS<` z8%>g5$p=S~M#H&gQyLk#&Z`t!*S=r5$92Ag7eOULmo=05h_2F zJ9puKUI)F9(eFb4T?m!?b%E1Ofy(i^1TNPlaJDXir*#SZ+#3_@9-8&Kvh6~p6nci@m8PIsYg?z0SsW+TWzS)!HX%6z! z9wg7Fkk57}^?=)y2d*W$p1?yrn?qij1YVlJm$|tLp3O~NaP1*b5#|KWJ`_5LPs!`9 z=U>Kpy8-%6YSb_i(nnYRGCkg{?vAvHo9`M!pRy*+hQ^L(^0 z^f$Dea<=R9m$YE?UldQ7_KXp&pVp^L@A`bR{G>-cES_Jiw?)b7DQ9|Nv`eCgW)y3s zqw{Y&H(uJDEhmAuoV*mz19$B5@zScyN9~0=UwYrq%W`zuAGMbAz_lRt9~Dmpcg^kl zcxmarwC79jAFq8`UoZW5MNeOG)b{hk{rpg@t-bpZ_VdH&;V#~fu&3wk?_XbkoAvb+ znxZ$rCRoMZpqgL>Cp_zCNw9)__72qqo7iW)Iw@4Y&L=~ycZsH0!XJcsHcW~o{C=o+ zkEU3{k3&7pCB+hc4^-bvibne`sMfH%)byFSb4{wBM9cWuU=8d4(66F3>=`rqTioyV zEHqn|4*9Ojl)vG=1X+Pc~k_F2+qonWS zAgCUae$@BH*46UTGopVZqqY~%+QC}IJt=7iYZdpPq#dkP+?`UigSBI|jrGwC3O2Qt zwVs?>Qdg*+oLW*hs6L@u(h#T~qgv8Xs9vR7KH)c95695MnUdZKt!1WO57i#lTX-F1 zJ%Y8t9#*29NLh=umR_6>)oazzpmm+c*7f6i#2rN-YpM5JQ=X%Lr$1Jk9-fTa0hGNH zOq;Hb)wsUuh~qDk-KETO`ICtLW$>4El-CD-vmWkp6=gZ)deYUu6zJt{olb-_e2Z9~~rt7~6Gl4`oAs8rac1-OAG~ z@D1h4u|eJ(8zj)NNTEBZIfggK1zB}mkY^&+cfbLUL$+-q-3?VTZX(?aRrcLaejog0 z6Q!A?2jDD9<5{E(>Z}%-vtIevg}ek8(uXQa=ZU|wDbES(Zw~Xbg0kyx4#`_1XYR&n5MS$`R(0s-TDPW*((#s2I>CxdMK$D>W)0u zVSlLnV?L=4D$fx4bLHw6UO*ZQozIg<#$eX6F`42Tp1Ln@5bN+}G}p8@ib~~`P2}-j zZ0}`roh&AefO>Yy;=qgbH;qDG$eou2t}VVg25BNUUmE!P(!l+f1_>b&J07{C*ZeTj zM5L24Vp)&~dZDb5D=!ONc`CVQoynC&cc;QJ<;^n!Z=Mmj?~K4}XYhVn($FB^QtF-v z-5yrkc2?G@l=a=Y*4s8#*4fZ=$hT2<4)knRm+Sp3 zR=4Zy_^{57XPsRb*891vvg0Ys9WH?C_1j8vrEP`EH!g-6M`3J)zC5wT2lbAm6Xz=~|v%#SC|y=?%Y@IjP!Y~!dA=Tc z9B*zQe=RFTElc@)1MBJ-%AUY?GgLoqTx&=3d>dug;l{AqHip%!^JYs(z;YzYjjMj`C5gyacM; zIEuBVynQ{nsC5GOa^)G%(FH!Hk3sStmU~I^hn-xC+`YZbmbW%;>ue?`3P29 zFQ{Dq2=-0D{mz$ zs}3q^y^`la&{e!SoZ7)qC9%3%9TLPfw}N#x6xv9>g6Br);k+3}K9o7^x>JW6#%y0s zd0AL_%UEqADC-qi#wv8ZEu+S`n9)%6rLp9$yu-rE(*xmJYYwY$Jk*nn)bpgSyd`1f zEn(&94OjwI^J8BVX)@HEL+-Yn3Ll6&ab0;^~|&?%7ZBnVZK#Ut|5(L z_Kc=h&0`evX*AEyz){Se(L6g3M={4n^E`mkXl7wQ^8TS#Kd=5{dAk3fzgeE{@Ao%5 zv;6%DzguZBf;14SoESkG40X1SAk{!@aK6o+9ZkIw z$zJofm6OW&eYMndrKX%;-;Z(y<*u}4ZR4eNogHhBf14l9fqj+|0+P|ZC zwx>tYkM^E@-IHFnSM6(Kh>UUa{8`7@@l{es4OKt9XTx{qGiue|pXiw)WnomyDD|dX zPA)I<|8m^zix>fAcZJH`YbaIoJ8X3yQVlKc{(rwKuK&n0{2l&6>+I(^((z<> z$I%fBCEIF?%mYhWLA4ync&4X7AH_aZn~9FctH$8Yv#gnTu{Z+0DZX8jgF;|&nb^ZXS5 zoDcY%M?%Uq{?_wkZ`W78vW&fSrR{Egxw2YTnJa7W=1Js@MLt&KV0$-DUPyi$S6du? zC4wui?Hnl1laAztf7zC+$Vr^TazEF1x3IS4z&%)Vw!MNR2ewbVzd{ZiSAiT^o)@Kn zGgEGCEQK6cZfwk~+(B+Et`s?NAO1Hv^4`vqj`*-Vsf8Oy4qVPJkR#`OxX4d(PGXzo z$nn=jKAg*n5`B`d{kJWt{b`P<5!C~;m` zd7Vq@UComyuk+c`dY-hF*E`FdeU%aU+}jtq(^i&shF5fEF6DA3&K9+%oRhT7lfMN& z$@LSpJ2exfX3jI))9X4TcRHFUyVC1g?7CRWG3ICZ2$eiC)^oxd}3l@|S^ zGjkySjD4KTCi}fbLTR_Wy!c6bawnfB%E2gG)%?}}jagPEv}pdF)lZ80e`n=Rd;FyH za%cBr+VR}$Nas-#uy;DP2lF|QuQKIMoCCSVst%xZ&Syx}WAnGU9@`mv=WoGJigx15 zf1Y$kk1dXA`})bg&6D=OGoJ%RUeQ*M%|BC|OKs;#XXMV_+Qkt`*fTvgw~LGVN!xkS zp4{n3kL?VeurK_is7n;B*CGel8MkR)=X^2e$*$%=XXeSvji0>G^W=rJcZzbSwQUkL z*dkZi7tAouy@(v{t8UzxInbHU8^F#!@1#N4= zu{$$Qa*Mb<{G`ZFUJM!0-rU>MdD7P2*%P~XS2~Qmqb<(X7C-rW(_=d`Pa+RgS&lKlLTb`54oj6-wKKRM5?43Q) zV_!)9q$qdxoS*D$7q^uW`F9rO&aP$I?!U9hPjb1_k-bx#Cv88I&yzSqB4S_EQXH=$ zKZ#z{j{T?6bNa&K_8rL`k&_k_C3;Tx6+hXPe$t-Y>HL@$*Z!XJ6Qz$nlqgNx_oui2 zojI@AmA%v6T`IR<&XbqQzf;6xV;h|<;%v^17uL^S)MIxgcRJ=LQHv-_ik<7&K#c@{c%HB~*z8vB)a(kyEe$pBJB-c!g$LQ=l zDe{xnV_KXcd%yN`xwEq`VDG=P$SXRU1I5pDB%3;8@3hBH{N=gV*k1Zu$L(~+zoYzZ zFK(wePuj|zJ@@Z)G^V@fC;K)}+Sg-?b0D85ZE^edKGPXI_T?T|kn<0%b=y4z|zB~LdT z4;{~QJnhh1bh(iO%FP-f(%3lpfkXyRAg_h?XU%pY?z}|uESU+^$}c9NV@%*V3-65e zG&;>lVNVfJ|0w58N)pGlBziIl>M38{`HYdnp19tFa*Q0F$f}*db5Cj~z$vQ8dy!(~ z@I*L=&kYUD^o-|pt~i_GT#DQ#&ZyYZV*kYU#{P-zjr|kb8~bP1?T!7` zUVGyjYH4-s)!5$HtG3=%=-hM1#Gdp+zNRCZ>nh&4A7XoB8)NHYyLR28*jJHb#}SOJ zi~SZyGxl&C$KuFFt`++{_G)Zz?A6%b*sHOwa+d zdP0>vKh9_8E;o>b`E1*FHHV$O`8Ya)u`Q9a$KELN_t+<~jj<17&)9CclpNl@Fhwcp zKKB;>(9yam&WG{ObKJNZVo$``VbAR8d?=1@lnTwP=$2lIBW$1T+z+v(dFyPK?Ta#A zs?3k4YVJxF?)`j-vp%*s&Vu&)q%-Tnm7Gh&_WB{t=-3A>eUi^@XLU#YFg*0cp7ul3 zQX=my{)@b}*j#U6+) zi>=&!Z^&=ddgTZE-Ven!`_j&bVh_aD>}fy5*2fv8g!%hi7cW#lbkzDNd+nttM_R0^ zTwW9{p`w1?ntSid7xY-qeCSL+v~9cg zs=KDtcGdg$wjXjWtTX(%vl1!VbkS1I`#I_eT7D5jD9*j8MTik-Qx^4*7VX>BUHd$0 zAdcXU!|~YaFI7Kuw(Zf5i}r7^AByWP+Jw97hqi6ckrOeKh@R}aA0mI*({<5$K6JL# zQ8$lvT(sb#ZM!GE5l2`nOL^9UDaF~*f-FTeY3JUEJTM{yMNSy|A@)_|iV-o$=TBTi zuBIq8qMfw_{i}&{DVCCZ3XLbyEFt%78c(WOOzxRAo?zp-H47*W4JS=BgmWc^LOm7Q zQzoRI7JVqCA>rhS!HK6(NIkz}E~P=7Q{i2Qo-HQzq=h+@>Nv~7TM=iG`a``faVDkO zaMp!qT&rVv`b8~gVt8tU=YPdhm-~eiYWi?OhWk6G^Ul+?JvS`B$I;WZ<5|8_SxMgT z=xvV&u&zA0SESj~$tuH{IK4QTLtJ?>?|MSLJ2IZ-EAH7HJaZDc_-8zOIgXRONqn>! zF4Yw(uO1ih8_#Cz3W6niHx~X~1|3K4i6Wl#Ahzdu58hTF+UMC0B`_`VF;8R2&n13xgCcfx*J4=TL-CA6^EsomJj2*})o9I(Vq+b{jtzP+9K4V3W zqtw;jQq%DaGUr-flBly1*?HC%>L^r)kusV>xvkXpba8pPoZNkC&PSi^P5GS9_OhJM zXGbC;sJ%iD*t7bRMEyGM0kMd2!OrZsAL6eSQO7g_vd|RzZH8@9_UFO_GD~b?7i4;#lDKY7h4^B$yu29lJhn1CFg^9vi;yJ@N5$2 zg0sN8RGkaOelULA@v+^p)v>)1lPR_|&Y9TK$m?QDBgcy^jlC4x5_=~8=GZgwH^-id zzqvC#<2rO6Ij=hE8CP#Ue_{{B`QY4AGi=+sV!L9CoHgD@+qTDI8;kuGTbkpg&dJzU zv8Az>VoPH$#g@iiifxI#6n}H|_MWG_FHpRIV*I1lUv8BcSiS3R3 z6Wbg6C$=~CPi(LJK(3H;gqr8u8~bhN_PTmpLpdiJ5D>$9T5Wq{ujcq$3!dD%A7Wc~ z)f@8Yc;kWEnEa>M53#+mjj?sHT^*00t2>Tk?6Js~ZJpf6^%zGp_VCVajH@;FdF<8L z-q@?Ly|Gt!jVJG2Kd6_=kL`&Usvlz8ThC!n( z7W**vOpY|R;K{KM_q`u>o)LR8ALL=hIUJ=zlmu$|(J$nTcD?W151ql2mGrsPFZNaJ zpBJwmltRiPSH|wvh5gW0t8jhCc@g`eHC~$cN$2t8J?)2_1Iv4hzb%*cyXPCl^|JFk zDfW-@N~sk&N8}K4#C$$D`mK9ocL=JdP0BlW#*_D@ABuDJrR|5}Oz4b-9@k3bAF=o3 zC`CMZU;5#1Hy?`qu;*B%t0r0pEq(I;cR#dm85P%EM|`rVy%+WK*6Va%#whaU`2X+f zcXqrIcdf_mT7PNbLQ!jp)=;$3igI&z{qWNCfYLH*YkSLel``5E$|8BM7O63hq9EF| z?yS`=`g`byJ=Im)wp}gHGY;+1zt4V%mddVYc-vMx&uas+;K^F*x%<)&t?|QM`#n30 z*hHI7F5W&4Bkw8lqBxVI4%S-7D7HPvlf_a*RU)3EHTzQZLucC_t>b9_?rlFr{i6S-ov5A*pG*O0R)N{xs=7~x_(-bl_#ZXzv(4ksT*X-Tkg zmVzRCuDKfj5-h&O;L7Uxi?Q)NA6=_w5!$UMr+bFF=c(5R>N)Fbhf+^rSN2FfuiaC2 zrSm|S_4!FX_ube4sprJ&n~-{Lva>|$dGl&rQqQFK3|;9=ux4XUq~5kzL-IC1ap(NL zM(_6Xh6?Y96L+qpaEtc zks9^pxQ|L28fMZrqU<8>qU>VuBJkd=A>uCjE+#KBuYMfw-#CcczVxTFQY?RVz}@>o zMd%M&%yMO$dCxVXY&uCHpl5*)1vj&&wCa0FwA=% zt&bju=zo|(Pxq!DMf1G}a(+PWdo!2xR*32MW-c{QZiMR5(4Wzh9v1Bv>yQ499?#?Z zlc?1TqEEzg`Spw}VnjUITOWYDQ_Rg(Anva}z*DO|e_5=jg5-IKu7@m57DfbKLEzoD6r@%9y$3V679iahXY~rYSBDiDdNI74f)6VSy zVbtmvuYS}X#JKbeBjuPll8%%ojyu;KDM!Zfbflcw&Un|6BjtK?)P{uds0pKXU|4b9 z?(DpG)T*J5r6Z+B$nkVkriL|J4|Q!%32VbqJAg593>~27O<%lmXFLVaAaKv5lLb+h%h^={{{I4}ftfEG~r?0KZ5%sur%nRdwgCa+CB;|YR ztVNEf4yXL_rc60v8KrSy6q*C~)34@uiGjPyyysL-n4h+u^Fqh5g(Hp(Bju{!_5E=2 zhx~ri{ARe8TTWl7`)E75&(Afl=@?-h8QY(5%XM~ZG@5-~4Q{F19EOTty z-f!yoMQ^C1=GZCGlve7G@>fSqEwXr1ran=n)nur*)GDo_ey!}1XF6)0*z5Qyt>UN| z(IdBX)b!rS*_2sPf*IrE_(lJyGRvK6j$HJND!E3pMjg2sv|L}Ya$VVNzsMn-)BS0; zd{3@8<9U7hujq>)blK_92#Vr znvDEVP8hjj&I#p;O04nlF8d1TqDsNtq!7B+qEVSloQGWiyU&-{IIR2p}wJB;i$FM zI_juxt#8C=0ksZi^X~PHsA(wMT5B3HK0ys+9#Y9sb3Bz_-VRhxts~{gIG!Ep8|oPI z87c4C=oQ9L`80(wiTZ||!TnK6uGad-LPkbC#Iai(#!jt6S+F}zL!Cr@V{sUX_BD+d zi{Sc-D<;=29M7We;R;iJxtcoCH&Xt$T$Azd9dlP<)K%gNjnNDFDt7G_V;-WOqrRio z6LlnKkTXfH5cMdzMIKin7ts?XjlJi*j(w=@uhwQi>xqy??N9ENkC<9Vu0P7{avife zXf{zNHC9Aj$9dEzQ0H16St2)$8gYz7iBTwO$?8@yP9@G=<5!%)vxB}X*NBlWYQ}l= zON@qzTCX>=PM-&Kc=F-(q)yAtKu zj!+)+q>bT@O*ymHYqT`ny{T;*HPx28zU0PgfR2=Up?aWWl|kjC_Pw&twc_ctM!Bkq zdM8M}SGy(VeGsitGgsOTqLoUY{BFYjJSi9J=^wT3zCofW3+w4Eb!#PG1AVLfP}g^t zq`%Mpj=LnA7!!Y`cleD6_(irAK52#W`s+8{* zq`Wi8*%f1@ULVRvW()|u(VzKfuRALT&~o(zXKNkp z*KV>m2GV}V!af;9Z#WkA$za;AHRNg-LN7QL_K9~aD&y^$q4a_yVxKhd>l_h#rjcLW zm2!C)7yG1%HaQ|?VMOei5wxL8ppJ`uB6UQZRZ=bebNRKE;eNF$ZdOyqokw~lH?YY~ z&*3-sf@(*5<6$NDt5x%f3+RbzXf@9l(kC_08lEqrd?B~C$)UIL_dTHJkY7w+_JQ`{ z6UXzeTe!ikJ2$i)Px%twdQ+QNlDD>X<5sr5)T+07N81+aFXQP_?p-sI&U@J^lFO;N zEZoKBeVqMxF6XH$H^|je_7=ACaPwL@qg6|78BeYuZ(8$KwK7JmKlNRBQYLv@T9Sg;{bM^TjcA_GE$g zl%OSekrJg8c#wB{iGFDtcz5C)sP_-fhxd3R;UeflxU4q9lpv?3@Tn5qa3;^9I#b}7 z2SX>5PYLo*K0Tf1N$}a}%*Vleix#NJobqKTX(`k@(1wz{Tkt?WJrN##AaiyoH4UWY ztkP-JPJoY3WBxW!(->}D8&8cALw!mqwgT$?Y|YfDZyrUiL^~Ynt#0F}QOERdI<2vl zQ15>mOO2AsTj{jeS3$iyZVWZbG4G~RXI%~TuDQ|FxZm3Q=+t75fUcpoq2b){z31}X z-t6iBeIBJI=7Zn6K77mi@HgvuK9@Cc9-p~@)CfJF{6b0%&LN6jeA^gGsutmp{wlVuJp{AaEC~IUKwccr1&+4!@wve_m z?=PcfGc{Y7Czn&U2RE|@FXwp^Pn%g6<0%cMZb<0&1=&dfW5PfcbWoB=(Hd@|3@(0)8kfXZtuWVD>w@3t+KtTkzafJ zt=#fRsCUu!qDF4+?YDATZ*ufDTkm3&*LxGLoY}h@z4z7|9OdBMd1`1FMC(&#KyPv- zn(|F~7Vl23W|X_PC->#oRX{6v?n4W_p{^^> zHMG1OTF$d~^B6y@MDxZp5eoTW6{(tbW|TzGT5uWpkvLitYflcPXJHs?tcc5KU&+N9 zSRr~B)Z4tDHR{^x+;Ytrw?3a%s^O{s&4a3=s~6gKHA1zqXF~AaB*Puq#|fE2u3xlEgL};|_#xfpaY2q?tm@g5RiHM9Ehqz44T|tiHi$AZNOKoSD^QyfW<(*K@ zwm7f+y}SRN#hLG%A3*8}?HOi5cS_y?UYz-!6yd$$otyu=|DC1he`nh}JfkL?@m34L zQL#nlu_m^zrM~!?5n-l|2y@rFE8T^vUgX`C-WBdGmfj!fJ&|&=k+h}{RGm#J+mD_c z8G3RgB_r+!L0wV9S#3k0-hk=K8_p^m3LO==(K58PhWR|2XIq=2z224?@28A@l-#E>ieK-& zo=Puo`t;sUwS4acRjZHpglY|qCiQ`8F^wkmgL*rt_P}UbPz4>yUkrw-xp^09J=9xA zhmva_#@kEfsAEW#&`SQQk$Ue|@5Qt8X$&n^``3%=jq1ZGM+-_1Qbg;#9aT$8Ya#bl zWW3eRsi3Ar*)=D(l-rJAu3PI0@itMP{pJ>*M9~}Z()(w%##_9!@=@ipqY^Q0k!|gI z`@OAyHX^vuODi(a+9y%;&&pGym$tPxqUfJh-)QZb5W$d_ifOAII~ICrckPo@BO^yu!6VCgNEJPOFqP)}a}>CBO2_D`SjB2jpB6Si2&I@~?@E)j-PfvB|7VWu+WyGV4>s zQ19ea=wP05>7~vd@!)#iO{4F%9!4@3z4^DEnh})ceMwNFZtSZ*7U(V52JJtR9j4Mi?dT+5+ezwGJ^VHoUPNT)qA5RAadrM zm1n4@I^*S0Qv&}`7dU|L)5oKqt`BXEu?Egu*GV7x!};r6o=gwLhy!_vdVrAz(buM4 zAoqy=wTQ?#ul3io_NzIc)!w335WQ>OVH{%&)DdDV#Vr1R$JTZ13Ky-@f93kGWiGhl zMdNCjBXVPH-u}!T^{qN`(K>Z~BR%SvZR%%($VKba_0{Fv^`^$JjyIS&ilu6McbS+&WGX50cVRd zq$$jbVT`gf$vH5Lac$&RC_Ne(Q|F>%Ewbc%b*#mgoYRhSJ!9&OcbtbX!mbC$c`zee zPPvRUkkKp))K%ozN?l#HMe52^vy-|yQ%be8F%9J`lw9w5d({^9yrs6$RbYE*)yo`VIhga!5gtVnfw%o?PM-4S7>@|!9LIQg80R>~O<|nl7!M2M z99!NPS|3~95LzEwJ~XsGwp?s+C}ZhJM}#r9d@wab7)?id5NR;&>>5Vb@s2I83#}hO zFKEw1tjw{m4ehF>UEVz2g?H`%b%diHX`Ay1B3o@69b;Q=8~Z?Qxoz|ga$9a2tD)6A z+r}!WR-J8B3#{bXHX6Cpn`hhD3(6US%v#60o@7g%-$O|Cw8>Tv4lTEh-DqF8&{ErM zdn;&JY;RYd2T*n%JL>&uSK0Hej%|$XjeA}D(b8IMWu@j3{01#&ZRjW1~Mg?AL`NVv%1)U2cCD5!FJId$DYkCepg zN$a3WMzOVSpe%iPRyJ+`o#_X4Hg1H9byn~x<+UhX1!)8a!+JXItg<8P(bK0#eY@?r9dg zr<3>cRFT}1d_MW7> z(A&vh&)Wx+TX}jH^j*ojlQ)25od`XVcW(sU+Ya5%^DVr45A;^@n`v1E^gZM^Q}>?a zAwK!WynlJjhWp1`{Slr}@f#|MzMLdDYukhXzJz9o4K)bcHqUYR^fE`I+Q z^s(fv;FXUCZ1c_J=O=IG`TXQfK1}UJ{K|&|j{Q#PJCp0dGzU<3G3g@E%mI{6=gsxd z>ysP61aC-g3>f$gpoBNl@>6-bk(GT(Ks_%7-5g4~9C~?j1#|#!>M30b9ZKGnzfl(z zgYQb(0o?)K*fn7AUHRNql&?x&1$|X=HT3G_8t662wa{ymS3_T&yaxK3U~!g%U&wIT+rd1ep%+GZNuIa<#EKw6%n%snBUb5355T zOL$iIszXalc-BW*hxV25EFxKlHkR!iO_H+nA(0H9(Df=$@)EcjuGc5P@krAJM38)+1Ff?7`da zY0p%AyC*e0(!cWl(B!W{llv>bm-_~I+cWKzs$KpsZ@78o#(gA5*`rYI|5@}sJF#SGnzn6SJsZIN*|DJp|83-Mi4od$s z>6g|*Yx%?vDE}w4Z`v>Yw`5TIhveUqe<%M=@`vP)$#;1AL-NCb`fc(bCsk>6`eWWcm;4KL zrQ|2n{1{r9R;3wr%GIwWUx$7@`Df@qC*Od6Bl#xuo4n7G|4x1j{cZ9)=Lx0a- zq|~cf{v`P+^ry+spb6iaQu;aNpC`Y7{v!D$^q0x6pub9f4gGcUU(o+begpjt-;we+ zKS7cy$B!WOgRUkQBkl*)2496d>I3b=o0Z5aZN?g&*Yd7EbPc%}bbqKCy!PkHfL0HH zs>O?OAC62rit@TJpO;g!0-5G)Ur!ngUB}Zh>X#$m)`yk10jf8`HMucReHQ8y%b@Dn zRh0Bi9UXXtz6^aGLxay_C_MBy%1`pCr;uzfkNVboXKM`s_97@VN<(u+Q zNvC8}`hAGEA4aNGQTilxi;-%Y|6m*Q}cl!>6CKH!_SZ}M7CA&?rEMDLbXyJ zr{;ag6{X*MDL)=0+~e7~kaWs1WuQ{+-9hTzid3r#lJ33KDfMnaDkvLoqF#x20#dAk@zF+65>_DT z^#5)luRzl26+WK4g3lcvWZPSiY05pN-lIX%og3uYW5Iv-XpnkuMy8#Iq*Lm>DM-3= zf^2&$a!eVh)O!R;_x9)I-7An|%0MOE!$Iolr+NqPm2~=}-bt>H@8KZz9tx69Z`Jj@ z(YqJrT?LZrVt%WVPLI|N+2f)dtH%qmr=fgyeqXL@>lXy z9;BVR@=fTE`rRsnm#s2**(&*_Q>eL$&sHMou7X}oUWuf;8hR~xC6ex1=xfL;k#w(t zUPoTZcU=cn`d0Gy$~8~__q>1a;PVcEUO^72k$aANFL;!Gu_Q>n1Ce)n$MjJs-;{fL z&kjPqDg9$n@M>F@=fVCi}FmQnbL1I$ZQow;`Bh!?J5hXf=H{wR( zMPfWkHs#)2>JLGF^q^$K2oWDhIPlF>dt9kkj#N|fDchQYq*JCT6_s>df+QOjB%Sh2 zd8njQjwu6`aE;JLKAlp|f^5U$OhZ&lkc~<@7%lQ_evov^H|3#{PMM|*RMI6#J^e|4 z<=4(bvMCRhdd@(od$@Kf2RDGAm{oAN%y@V=LQ5x_a8yF z)gjH4hf2NLAnCpvB-udZTP@Ph(q5{Q*g*)cf}!&;9^a{we8{Y)VDt z*&l<{`wo&$NvPDTNtI`RLaHeXm2}E9CE>UDoqrBe@7u_`YUJ9FgFO5f>c542QU)sZ zDpT#Ze@VI{>AnX2XY%eyx_^d#le|0cz6t#;QmH$V?zhn2lXvISzsJ7mPJK5d-A|xD zBkx8(d6vh|dFqCw`#JQN=$6rX^xd3|*}z zkCHQ9PGom1YgWWJM#VCqFsr*Zls z$nLAqTPgkks~0j8`0~ z=)aGi`<=&YU;OtX_$|9Dj9Ms;SJ8j3gp8xsdc0l?|NYGM! z@9|7U`L!?nup{}U|I%H7?lx1$h&#;UZnHh-hguBn?K9h#c&5K!ez-5=r5`%iIy#C! z`$t}1>dx+8tVI7b_I@z57kLj#gP_LfcMn>fnz()={ejvS1F^r=>hveop~Z{G>q*jk zq(?TC4sYy@)mFulj&649V4LV@#G> zZHs=ZmaDGoU;AzDWpHPRaX#*Gi2E3{+x`1;p7ZbVT}!$6{neq~^H&r8f7@3@Qn$2C z-o)&UG8NSJrpDg0eZ5HPmi~&Kp_M(UH(IO2bNBGOx>N4K?-&vO2eIXR?~xd?I}&W8 z(E**=dsMWiihGY@Y(k7xDDFKf+EYg8xL3@`hvMF&qCKVN9CxNWN7}ciV#I|q$dgw* zVL0D=B$q4hKr+^|W$#hG>&V@w?n27<9>qAPdiH%y-eJ^MK=rl{qkbq> zSS{~{Gw*AmwZSUWDgb3+78%n}3Dr^^#d>ot4B>wh$g@Kfu855Wj`h3;kr$CJin?~xzJczr5Cr~$?&rX02BtMAvJ)uVL zC<_mSijf(M)025Hg(p2d)1lLO((iL1w2pi>pXdRd!{5#3FM2|?(DO4)4&><&K6_xW zHfNz9&*t-U`TT4&Wsxvt{2b^Up62uEIZ$oW`J@@a>NXyJ0MG6dHm*zLOpolLP@`%V z^L`F=0Qq7@dH{3|Zm1>fAFbMrw@A zGXAW<{SQScS7Z01wzpzEmH%-wp zK^HAQfm8+(eaBs+@VQg@+=csCMS&AT)C zixE(H#F?a1pd)xXlhSE$2W6cSqYJ!AxvD(t!kkq?rEs5wRU)5J5-F9Gj6F&6d}p|; z*K!$o@9=#}H1D;|$b0jNZcwF|Jf%C-XySh1@A~mK@^kfq+VCyL02$-tUk{*^K$X_+ zfN@7eJT<)+xgIRJ(ZEnvD^T;0dkvy2Uv*DrEq_x_8VCo~v+VxNKF}fLaZg|a?*>z@ zCpXSX4(#s0M$%x`!%#jiu5Ch2)j+8|RW-&wX-6tuCgvH*_JnaV-nsVO@B) zl(Yms)`ikC-t>kpCtpEs#BFb8!wQnT$XU9Q&n|~{Azwv}+)6IBikVV^ zvX=211=X{#mNW)lrj$IA5u6BBULHwl5_A%8j-vl3LyZGHim`LQk$b}2i#HX1B=WqD zF`Ew6Qdr0HG^jqF_4N6{P-7p~lV(B>=4m~pS#UjL95#?C{)u~-0A79GQQEP*bkpN}Ceg)Zjl7-|>8PmRtz zmb3!8lBZ+C2p!Aw;YmY-nudFF-NB?Kpj{w;a7Ff`$Lj-)`i}E-7|(s7L&=A+@*Jmf z#>dF|;AbM2Yq=Y`k`+EO@G18K7#}y9Z&%-Or$cZ4*SO{!Bg^uMv7|cam{4|AMh!^a zXEY;doSQ4M4qDWAqK?ypPqb({Mv+8KN8819X^e@Qju@k(D?jt>v9?-IcWQI3r?tK_ zfD!G^yIj+8jjQQ+3Ru*1w2g9o=OF5%)-w}+)18ryT2FWWKG%A>QHr`xi@qaT9`&85 z>2%{0QQwI=j{1&~z}j9#O=ljnsXsGB4mY2qz7utyqSj-ydamir;~QG*I~B~V)|!s| zSw2w9+^XQ+Qs#j%bwz!rE6>h7wVp=ax7K%}rW3WEo%J2Ho1L|uw)#%rz(Le^lngCe zPhWUO8S^jKdZMNib)S`daxHJwaiZ1}H63*v^_@Pf?5N{JeMj3=eWwqrR=$|)J5l#3 z<6GP-?T%@6pQ5It?o-2>i~5c_&M|y)1FKCPM}4OT9Yqdy_pm$9<*Zn>AFXTsW z1fFT+kapi#Xf^pHMpU_|^pjg^FS_T!lSwAQ|BMq>R=Q)iKm0G>so{Q%14-I~b@X05 z2~wG;rW4O7idxS!{!acl25T!b}rP|@alm|l96Xm5t;E@MYqYOP5I*<{WMarOR zNb*m2{)=YKCdu=9QIcoIJvOu8lg3XRigfD*)h;}gl6IkUWIpdR=mK(2D2i5~I#Exa z)r00kiEe<$)dxxoBv>WsX&hAReo(y z4AtAVn$lFLqqUke1rDgLcm(}53#!aHg6BCh*gUBE;~Gi}poj9bhSH(%!uj;d zTFUdGA}(urUIZ0uIg&Onff{ptB&EerCB%`G+ygS0c~r^xsw1?lp(^@BnWo+$je3XD zY#7h3m7(Ors8{dsJP^;AbUi4MMA*dJs>$UuM&WCdwBRgNl&kn(TX2>^^kCF7#_&s8 zbd46A#X05utOKEA$y@6k&Zdc^opBcTSw-!`y;rUE4o|>pjkAdG=Ng9^P>!>>Un`<5 z)59z)>K)UWbrEN&WA#Ms!!?#`AEGU}#?hmoaYUS@2k+wfr7e1gX8=XLL(M2hSfUQn zBg_?dCgwOxL|EL7)EZ~$&R^y@OLt1n5bX`QYKz`6fN~LMk+(;^!xO(2gt?@~+n>3h z_92$iEzF*x-Vrs9Zeea|55DkvM?cn?I$xj@d$ei{6prEH!8!MZKe}mEKYFe|m>HPOfpB z!2cW3mXna4qAd|;DJ$q5T?%?f)Hu{#a-5~8cXSDQ#}3|}MpEw>f$os&9on3^-qEF? zcX%$_86>rjsCPt-BWfS+NfKdE?{M#M%CC(0idaiTUAmB~14KN!i%3n5wnUso%*7pJ2~^#|y+-b;(p#b);*KkE9rxD9efAoJDRNaTd?W5@+c~ zFRFQovsjKei`tBP#Kl?EuySk9{o``lh_i^C)bLL3sy9QuOuiXUW*83_RlAu)YKDro zOs1voJBn}M_77ME6x&6Jt^WW?$~lBwTH7PM{}G- z%q7QJBDPXQTRMZYL~JGEED>`l;w%wWi3m$XTO#rjah8ax6wwwDmWa9J*h<7%S`e0q zzvKu@L|b;oSt7Qg+{w|Fh_k5CzF|76^u^P6qNcMm!lKr*JAFqTXEEF|*LrflQfKs?sOdzl zr|4HIdXysCQuHeoahB*;YJ#t~#aYyGTKkps5ow#|noiVl)QNH*lN!=mIHdYY3(gWX zp!T$$+^?j*6E&TPu$1%nxnD_rCwh@`O-EfxoJC)fnoF+rM6^ZSrv+_M)7e?yDQY^N zi?=0UD^cIs%D1cIs4caJv%DDkPSkXE##z*Ka*t9`(}}uI#93Y#eMdZ{#2k!hOAF4@ z8evh#=@@4bp(*N3Vl2^9l`${$JMH%$?e`z$dd=SXkD})&dXe_df7GJg~6tih51^8cp;fy}bQLTD`6PM`Bw0^_qW7y(VfjyT)-mehbMiXOa+S6-t97pXY;y5BQdAv+V z+D-Hv6>*%1;B+Y(34dyaOG;}rFg7%!7Y%H)_%jEmWi-Tnyo?A=9xub$2+yNAFAp3ikC!nH zrZYH>_F+VG=7G-qBj7kOUS?-~XYX*Fh}{&?93y37)Jz^7^U~uu5y6RQPK=uAJdP7% zWQtKU9mUJEhvV#zmwEZb%Nz_AntQK0ikC4`CihtFOT0{sl-W5x_{EEtiT>nW<2WKX zF-o{Cj`i@aE zMZc9X!Q0Rxw&1baIbJ5$cl2QyCEU4qncQz>)J%*IF8Zxvyo{(#?y+i#n&~)RCPvD{ zsF|JpRwMB7cp3d!F=}Riyv&OgFO#y8_wP&k|8HMX)Hveqq$19;FZ+_>j-vsVU#@R|@em z`}ZZa#LMiRUuploq?hZyq>kc)wNUE8jWc3^)rp3ZN?5@|K>OSY*a$VocNl39w2{0i zM8vuG*2uMCJc*7OyA~tuhmeoJQ|%e}qj+Pay%E_>=*^?4ch{h?#-k~D56ejE<1GmJ zex-5zUA}8+6z`hhbVdamsqfyT;m}^>M%|Bs_9UOcU&MPF+-oh)Hi>t}-uL7a?$sU@ z;)dO|WW3ZAK0P4By1Bp5yBv&`sUx1vNSUc5BlF$;J(bcp?1&ze+{-^P#K7f|`9^*l zZ?Es_AUt|re9JOrD<=$Hkh zxzL%R#@%wpnjZr71`f5OTBzp%cruJJ=?i(ggttZy8;Pvv*}Y4iNGkSM3pEP;FiQQP zM%gV#8|en^#@{R_&4(KCZ+yPAg8Xnk+Yf4NzsTUS5GS)3TEQn)@wsIouFiNFeNAdN z?!eA{N#4GvCS+WU`>`L&eXjlGOddQz;^D4IMzIK~RQUuiw>+%Gc7N=6o+N^%Fbex}n%Cx&QWcO)6_dpdtt4Pv5S z=}bOz8uT=t&I(b%XYsz8ay6XgEYcaAgetmnHk_pkRL|4dl+NVL)Dk6c>pKHFlqb(o zJp($F{2VyaQ0N(a$2p{w`DD+#Ln&n*w~n=GL1!W^v-1unBWv8{4;qB-qDIr6HspT$s1tRp4HfmEo}JKx)M)lz8``f2?bm~h72Z=lC~81a z8*-o2p6EepK%UMn)?;*Xt_|(igVcjOwMMEIv-7?x^(4=Bi#UiAKcqN@+6bV%$YNjym>8ev`g)} z^hDASIc?F}^h7SMjnfwWv-CvL5IJqp+Vn(DL*%qYYwC&A%bd1o{q#iA5IJqpy7ffT z5IJqp20hUv^g~)x{-4kjNkincMX849pU59M4UzN8`8(=~q!|+TBOOqxEy}FMN~7L5 zJ&}uX<8(tV(v2bjIz3S~pS6B^B5Bs7>n%i+tY54_sWMnXp2oY;9+7Fh8}YVopVTs* zRJwS@04%SIR}4VyT$zb?BOPcO??!rf#k;8rX2-jcj>$#6k^Wt~XG%-&c34m2-AE&> z-Ojak$HlwJrIg0I(XN{=>P-tcN*C{@3VL*DDy4Z>*~Pn&wpV-oN?YzU@6xaKl4m)e<>YSk6*CPu&Q)|lQu=T76@XeGO%{#69!?VQHD(Js}B#vy%r zNGTKVMyt>j4K5S)Msfe76;0#aC^ldw-c3L`;9MH-CXIAs5>5JWP#V(pi+AH9-MFYX zige?m-uzm;8yDjyJL-+>9WLrk8tKMGy;(Ef&6<&JTm&2!@5V*CaZzu6d%PRTA#3yB z(a0|&Rp!0u3)dkPGI|WHWz{mEtXkqtwDYgCXQg@^?S$+sS{*Jb)0ox;ptEE- zZlwWrO_NdWELlylgr&AEXU`JPQoy^;a452B$&w{YShhVYwPe*uELmFRshC8vWHqOK zYR{6!IMw4Qf=qmS_&T4#${C%{8@0wPv>{!Cio+TTWvuA1LcxuU#l`G{?6!jw$ z<3`bi6`NR5gsZO7=2R_b)v~KuwdQb#^7br69d`aZ^SMvPk|pg!#*$@!wr!>MEP4Gb zB4w;v3uy0bTj|=UO{tN`uvUAED@pBHvWhty)|SjUiX5z&UpA}=boMOy6Q}kpMM&A2 zw7OL*gtExCB^#EkU#V3~_N>%~RhZbb>Tq6mELpE)0h0}D8&Fh9wk=t>$~bZnaeg@t zajM73_V>{^N}~}wuOIbrQ4K{Vb`f)&Hm894G!C&M5dWIL&j$YGzlnbl=i<1S^8AZ9 z7sth{jel|e$KqmA{$&9D#&I$KOZrvx5FQc6eC>UOAHYEyrl_FU^CWjZb<=#aWz-d~h7+A}KNT$B`_Wdg8RDW*K1B{r?NDJB=b|-D^2$-n8s}}Snb2`A zvO{TK1IcNr=dtt63AxvN>N8wSd4HTjI1jhNJILZ(w5Cb^I9l5+?Lf-Er2aVC-9T}L zQ~pH}hEsnW#Q;wIaTF(bZTyR$#knk|P3n~+Pn>NyE`vuA=aJ37Ea6!GIL;Ht{LIA| z_>^paoYWJiCiS9Fg4J&@IqTW=XM$v_(VafR8{P(Vt%8n@PVhpbt zS6C5+Q$5RXjVtW*EQ&7td*cdg-%rs*Suhl1Sn>NZ(S?6&Tw%9PDidA!@3&4$5rv($ zC8KBg^WzFT4NE4v@UQ7vvNbG!pSZ$`;ps6$xV0+M3+kO|51l57R;uaGvquAF2Mtr z-<*kz9PL;!fg|l(q1mY&rAeGC1@&bV#lA-3A6g2ECsLFl&0?|vPT{yZC~vkY)RlmW zuQ)Z~GNvXx%2dv}h_lt1!NdzpOU9i1N~=-sL_VF`s$gf1rzc}l9u&pQVbiIfLCthf z^X-gelqw=yQ6j5X0Tp?3X2Q+Pq@;OIGuSL@+)hA6%tV@PHl{{0y*$-5>lHGGiR+xr zQDv|P`E0nI9?W{uZO);r__gvzo&(?03!Kdv&59L4ak6u%m%oPioq35II*+nu(zzUM zlIWN=p=KWCc^qv5&(nt)QS*U3S@Xbt)XgVt!px|7V*%%K!TID1;Dh>s{W#L>nFC6* zvyila*-_e%Mes`lK;D?!6#){@<|3H6FVt6kBwADbfMhoC4xOGajM#$_eWwMlxKMyVp>S0Wdk zlpa$YoZ``jphmsMWCTY1d(CXxPffF&q=QzBB}K;X$h)Wv%9CHarN`U>YBHk47k8oT=0HoiD@QJhtz?CmQBuTP)+*pKu#EFPNQ#@^ zjkEH0?8=xZ;+!<#T^Ruyl^Q217m@d-BspCCzNB&KEqid3u`J{yyBw zU6ut&2~{|jB-)oAEDA7)7kNZoPJXp&m79?pYqg~PE(!&!$JAzE9$po0{P`v zMUTYKrrfJ`q;y=Ztc`g|Us6OQd7^8t4eg(??pThp>g6*6 z72P@$m%4x+Eb39hd-3VHhNmbc<M}3k*<9e zr8(%E^qjsNYo`qD9;E&yJ(Bd={kWnC6wPq^4{6j_p+9QYlRt(u1fmPFbGR7TRg$qS z4S}eFV*D$bzoP=u8Vu$7s-WnE8~NI8Y!IVR^g!cZqj{qQ6&YJvfMJZiA+#FB-G+do z78?5+-_j9?0;KV5$I?cTut(8G(!a*Ei`idH-yNTffbpCkMp-msJSD|?%cCUjD--uk zV|^m^vT&4=Pvls9mv&f`g`)&iZ1zc%3|PvU$@J!0pnQiWlj?xdluf3#HsiM*J$VYL z0jOR(h13v~K5S~zQ>W4+TTpJv(Ny|aOHlLEH2%5v4wDW=`-Kev2XQow(je|GPD%T0 z6!JUb3Tl%iQOnZf_Sw+>dfH1v7A8HJ=3ecrS3h|kS?Wd4^u4sRo<^3&yCRTe@3Wyj zz1)7LT79QozBIDZ{Y(p!ktNLD&s5_u-PJVYidIQa)>tcCZLEnVWbb6!hGUIBw-aBw z&qh%))-wBhMO>r#H?yCqcCbnJ*-%f;?6XlsS))=jYy`TUOf@#UaP0Qk(0;d>@s-)n zv{Y-5#zSOt1lWCQo$C_qd?Pn_Lp>e03Ox->kZvVbsv`?cJX?E3E zbFs;)@?A9(uWe_qIQi!4^V-i;v!zB>`F%E|r5nQcjzNvkH16~ut{O_xZX0D>H;gu# zk=NX9LwkP>r*Gsi3bo&c_A}KCJ(%k@qW@@bQ}K4%?Nrf;M4v~HG$Nf`rriTHD@*1Q zmnW%8n29^B(W;2k8s&;RJt7&i+8I!m*L3765_K9kKr>jn+lI!k_Sq-_HE*ZdyEHzd zbx7MXJzjn`-a!X}$V>rZtcx%Et|;fvn)PcamY!{Y+ha#sZEN znXv|_c{ZcN(|)FsiBj#Ib~4?9W5s8be}MM)stLNd(=IY&MOv)BpJ_$3b#6b?ik#aT z8j-z|siDU0aO(CmUHf`A`9S$l8F4akLa*{ES>A+ff!cRlyJd(L$xf&hDf!gNUKoPn zS1a;`w0o(vcG_n{`yyzk4*kOj%4E2={4hibMaLwSXn$w5lP^=YA4X03@7nw@0;r(# z!;pL-ZX*Dl9m82Lvey-h@`@J;!HhSCcIuMvMR|Ww?FFv&G|g!pCDc-Uq9hh^CZc(g zk<%5$PWPs@HKK!(TeP}ZvPuMs?xlVhZe6jwphPp>x?)Kyl5E=3+Jcf@vaJ~%p;q#G z%B(1s2UJ_=WEE;Nb__`<;%L@p#}I`Toz%)WXUCBIvbrCJXr5$*o+L>gZgsI+S6r3j zbX~FY!065$(sjjdMX|GHh{B3a#$dJ`L%kwn#}NG!=bw6Gh|Z?o7;as0F~_2tl1kQG zS1j6^Sy$}#L6o#2iAMZK4w&tSA*!0%F{DLF*A>eTBei3=6~)83L+XdIHV=$ks9Lri zL%e#%j*$yRlZ_~~V^m9Mqgz*8o!au=7~{CMyd9%DEz)(xlQ`>E7f+*<2lY!=(o~=< z%SK8ArAL}UTHTHzS}EU)JTQA*aS6H|x1!ilMOiTNpl#CYq%=@#zcO}=JSds7T}X?y z2`S@^p%umR6Iz+BE1t`>jw-sf#3?;2rJXDo`JnVMn^7uQMFThGDD}gT4lSjG&L^W3 z%DE*pGuw_)0ENr;!>B=v)EmRCD_+d~%iA#upfBYu7?SIkkTQ0Rnm^kyWUt7!V>myI z)S6M5?<_jDHa(2KR|!db1c^G9lC(dNv?!@WCcTQJumF@qCRt2gXigTBbeGCvP6`uc zlwX>pFi|{7WC1AaZhi6)Y(SpMV)9~>ET(<1vt_YLv}l@eq)oY7>bIH7VxoAG#Y6+0 zEG8*TbT5LgRZe(CNo3*=wSS>3wCR5Lm1&`!g0wrKv@YdkG0`{aWVDx|b}@7knPf4W zP%g=0P72e`LK#`iCOqNlvREN4x+ZiumBI?4ZK*6K`X*US6feUorn(n#eLcC>d7EX+ zVlmV!TNabd<|MMd2_5dsRnos?B(i?|lJqdW5{g$|7SkTDP8O?@(6{okm?)dHF{vyj z+B<|Kjf|7UM9oquY!JV)x-6zx2^-O71QahLi;4b?g0@N)lUycQEEjY-87GmsozrBu zO=U4Bg;k)}ikek`V{=lNsPuSJMiwjPcx|$nG%}LK!JzbnVpvA*Yq>ycgZ8puS(wGnt$b8 zRgYXg;*vz1RFe8tsm4hq(mrW_)HUNAg{veHCzVK}s#$n_@ z{HmN(;{3w1ysDJGRfB-1ETbjB}SlE~I@{adb*M4VLOBoWCSsXXE&k!-*4j3iRtFWgBY8IN%1 zDZVbAB-P=F=aDAI2jw3weU1k@O^(y*h{tjI9BFuDWy;p-IDL-f8mGx|TAkmk&-rK3 zPp8RoTAgga)NFl@G&z!Mq{DIg97jK$pOxFG{rAz&4CTzMs99Z~^UL&e{q;HPLqF3M zHS4d*iIHlYCPxxe`E@nx(&zj>O^)QI%(@z_v2lK>(#%NmS$$oN^f{7)a*=&pw7AqS zRr(wkA+Gu_YH}o7$?B8~O4psniE|!4*;<`6TAXw^>(=LFG&$1Yr0Z%N<&+#Etxkni z^iw*S*`#0B>ZI{eq|cE~Jk{zE?)Za!w*R9X_ zC;HXMqsDpHq#iX+cP;tsukx#rK0EcU`Cs#^aUM1DzW=>`HKJjucg;V`uf}=QIPV(S znw@veAMvYE^hKX}!`Y;q4o94c^OPy?UE};}oZd#O_EYVR^fv2?;aDxv?o>;79%*Jh z^sn-tDM2Gw6_h=s%_<(e#AuB=_DUyau7ON%Ry zJI4!2A1+x^=ybVS)$cUA(&Z`&ZniGhPjtERCrtfn{6wSc{A$FdNtauYNRjfZNp-mu zf7aNvL`s!kjlNf^%Wck8ZK#*tM%u7ciyI^wU8lFvKI$1=ZpDP>X@wTI9rdYSjnn1I zGcTjdt+ZBMZkXtD^)m3L4^ zms_}oF1IMrb-oIHcRal|2AxJ% zJ1M4qH93^lrpwiOV(D^o)~d^um)WFbJp6WDu5=*T-Zg9Ut66`&&3}_$jqJ+V-Zj7G zSEG^WcH-zj?^V2MMGNalS+`j7?rm;Gwo zsyOFSBYEVH`PImmCfmEldDP6IZhB%t&e)XK`qgL^UdWs*TdGGAHz7}8=T}o+8{;%E@~$cGS0j%a=Ur1? z1GA=IjXY{nJ&d>`S(81u3em>eq?&LUlIF@t72ziIHsm2)13p9kkSXs`ng$7j=$~xI>H6T*)|^=% zET5ayqoz4`DDPJzZ^hKFCe_0P=wb9NvOQ`flLXK|`S2*JqWF`Hca11##;?XjHfhft zoOeySK3IN=sUAiiHL@~?&?3mX;n$+&Bc>VIWS>3NjtL)`9EQ|A+ zdh7_!B-^h>y(;5Z6G8K2M^61}oZUG)UcY>9WL*|-vZh~+ycIKkH5OjPMK+N=U3O)= znqQ54g;T#8S&CD?8hO~Hel^3nHr2*tuMaM!MJ8UqxRPwY8tI5Kel?25FTb4$B^q0!E- zCKnA%wqH&4wP;{+p=#NFHPRGi{AzMnX<(!&+Jv;aUyZzNG9HGC+CP^&l=rJCN&ITk z^}!X;JxfQF@hx=m`YWuWfzlVHu}(^|v@!Cz$>_23)~d%YP4w7{xxb6ipL*BiL0^`@ zF=n*cE?&QMM5#7Lem08NUt=}D8d0T8y#9*3Yf;R#`PKY)>tWzmxlCb!DzuV3Hv-=~LJb7hlT@$~EKn>OfS{%k#rG%%_EjPs_G1}62X%htm<4NUg> zCZ~sKMf=s)H)ZrN84Zl{uhaUbKT{7Q4UAjm^xvz8aT*w>jY-!xtz8eJl}%0?Bktv& zt%v#J>zkzQl=o_OY*P8JW_AdZ{lV7?N&C1&8&sl+;{a0GV zG_In2VN>a&HSJTc{?vb_3NncEpV3Oi@)C#5k~pMomj6tZpCyjepI;iqRQixdY$|

E&&VS-6P>7dHR+=tcW~0j zx+4;49kL{jOhh8BdMj`Lm0o=)DO>tj`)*+_uA=;6Q@JC1hcNlVrm}`s(n)Jt4Rmsc z{2WsIuU0H)q>t*WNgt{GSKcws{#zlDJDkL!HBRL{`K7&){kM9efyvl^C9O{(Wqb9P ztdc&Q9wxN{%hK!ODr#@A8F1Jci9_q1QdvWK8`*zLR@r~u$|kLfnoUZr!1C%ZT_t_Y zp`7~mXYUiH)lX?$MXhv7?Z0zrzknn?OeQ)}YWbCiNGgNmC(?(sE~!_4s(W#Ahitsr zaTT=&%Ecnu5-o%z4ySu@mS5>`6k|~~Uuh~*fBpilS$(&#n#ds1ZlwM*6%*;h`Oj2L zWQ}x(u!@Nv|LSoSWr@keRg|9Nm-IIBeTn(s&WmP!^ft1dq}rQ+YtvOxZatLK+r->e zE1~{B^)?Oo=jG$N{Sm#5+h*Bio^?DmeIi;~#+j=Ocw^78JlyYY4Z8oJo zT@U3nHrZY@YwB$_gOa4$n>GCpv-LJx(Js~A{55(T{ja}vJ(R5H(q@P7h*}Aiv7!Ic zdZ;FFoaw44XG8zx^-wN0g`;)lZRoPdWv_>FQkz>9#r8c|CD$&zjZy7i&T@L4C{_p<7k4S)<~c8zY?!T_Ln~|KEwJ%W)QcZ(dPuK z^f|K9rcoMPv}swE%dd(mzfXqzXq*gEMDDD~TumO4l{VGqWPA0?pFfpK z))t>(b$w2DWCqRh(&t30>2ox@rTQGVHfqgPQBI$e@#@!lsMYm3Zl4V4dV2Fqiph}1 zXRwr=9a(c$s?Tw;8rBu1A=|6p?UPZ=m1~d8@az8kve;&<$(bk(YkKwn@;({A)t_IU z{N=65sXpib$DiNna}@7pCS34;%AY@t&ydmQD1J?<&smp0zxH}hwK~q9f6XWjzt5lF z>2uax54HaO{BHO6^;r+4T`|h*7hA2Tpl?&hJ|lwfagZMZb|g=l9XiKWjZy zgH^P&DHKig(|O~pYgOr*^wX^*b@X%1m86b-I!%tFqD~*aKJ+uyhiipYx}J1(`swx= zaw|#y2>r}ZP8aKDZS*sHCFw8I&)>Q#>hDHB6&)wljc-^F<)Zbk|9U8=$yuF>{wLQ% z{c-x~JaE=$J=EIi=eqrH{(tp3F4pLOI=;>C)8}NQHW%flygui@HNMSXsn5wow#lrC zSbKb%zmGo0X>!&TYjl0$+pO=J2+Q0rThlK`xsjDzafVlqY!f0wC?fGM#kY}7^Y6D# z%FzV*8Eo*+DIfFdpSVtH5L|1zTB^K`_kU%b)SnxF`1i>p<@Y@ee)iIlf6lK*+I0FH zMZrn6I-+u^JhEog&D1|9T*E)-KdaAKQy$5z1?Y&5Mv*put2`o2PR2hc6QyBIeNHAO zgOg3%S^yW{W`jN__0Rd`_zW&GgR?JZuL#JFY_tCH8M32prk**g$J_jC^f|vApW&~U zM}BL32F15Yt;~z@MG}@lkK0Q zy-?Gr#eWC?oYc$lKfA8Vt*F}IpQCl){plZn_jOhObpISjMcuk8dFG^1Zl)o9q`rtG3!VgZR?Jw=frv2B_9ob}kn~sN0XZpCTe(8>EZg)0C zFJ9Y@Y+Y%W*^8|k<(cU6XW{ET6N`=8kxjd>W$(*Yen&R#80Ge5OLt_`{%hI$vX$S9 zO*^z{N48%0`^vvp97X}?c4zC&QMx0W)?}qSvT1j=bVs(niM^>G7DKl?+k!;Hua`t{$DZOdfMtM+2^@R-wDhQ-uqFE$S?L%KVg+pkUgvdLdLpLZ-zY{lu$$0{YC z^U54o04tFfChtVwFPHBrPkUKta_AT0SgLSr!6Ndi$&;(cMD!*-xq4DaAJmg5ZnzH? zlc(`&q_5RFQtkaz0-EIBCb^&fLlv&jFYEe3uG2GWADT+Zy()8W{R77ji9ZsTB%aCf zQu2M42eje_N^hi?JK~O{MN&NF%r7h6jnf^w-RbnK?n(8;;m`j=|0haDgnp&!s{il) zz1~93&+kU>C^va>{Z`?sck14#-mF%(yLYd*uD755U)@drw+hdo{~jdw)VnL`|cQEy$pRmvUp27=_B=(kF^ zuik)us~W$eFR9-u=I(kzo4g0T=c@dMdW3#g{X@^J-&McS6RI~=O5VBpmYz^O%z2jU z8D)|DU;ggu;U^`r) zRKB;XN2wnc@(;87y#9^;wR*l{PyBM9|6d;Of4A?xwm!ds&ac_?|0tc`@ZB9}@pqWt zHS0O+m3R>GB93O~C)CSPZLP2pMHe5V2sv7fCH^Mmdqfu<_oLmX#1n}(((IvmqmW#b z)Jv}VJMne@%j5m8{O+so5)#nQWY^FxARZ`xp$a6oyQ_4}xtvkNNf+rUpq1f@9BM77 z_TuF{+Ubm}tWk1}JRB95HQuoZIZ@T*_n$#b8Hr++{l0Nm%dN#LuQvX)} zLcg%K|MKhaP0y4*-=FntZaso~cYoyBvj5|s^=$5&x_|vgp6x&J-m?GiAA2_UMfGL> ztoP=6n*O!HuITm|Rtx||C({nk+Sf`kRGZ)}-V}dv?ZeU3t4palC=c>FiKVd)N6oQR z)FB2~8A&^#mL;h5|5|$^R5T97N)u`gt5zuswa1m#NDH;&sn%u-6&qD+!i9=GrnTt8 z4%ia4`n@A^UU7noHKsNHLhXa9b^l$Mb*dz&Sg3_0x4Upx<|pkctSF`3n8oDPsOYHO znW40!xT1mdV1}zmIX_wFuXwUOnIE;ca9-jYE)TX|j7{xgB`>Z%(3J|5b4c1VT)J;j zqrM5PQk*cY@3%<=M$s>)86OBe(mvuLX>dZt2J$6B$^mIeLRp3+R7R*>!cAh&S3ekr z=1tEy1(b!YfYQR`*%xwLk(KQQ)J_Mdp#v+Rq#ZvCk`OoC+?j#Lbexh0HPPrRtcJjvMN3Az4 zAL`1iAK!$szQ=5EHo7v!vMNlz)*Mi}vu&u;N}SG=JCWw`?e%usliFeX+J>`Rk&3{r z$+cRuDA6Ys(KB*sw-?vV;~R9MG@P_I*pGY|rG3ERPYI4yya!! zGH+k+EACq4eMw&AeT~LzOK?k$zTmhD_$B!_Xv8)LH|P8}q_4eybH?pIwy*bXqD}jj zHs5&v;!G9qyF~l;9rfROpHo-G`<|Nbyw5nQ;(bc4e*7ueFzGuDdA5#>%s3g5F{K)2 zJFci;@Fa5t`O z%2iFg#ay+eS#0+8_M@zRxY!Klzi)2#@b(0^Aot9tJX0;Ri?=JdE7v#U+NNG@v$MAg zxC^ygaqVJI{d_B#jeM%>R?-r3}5dFS&B zqrA(>g<4sD8M#oAjL)IX+1{lbjR9pdxP)9d7AwHHoIS_8n4@vvIDY#)YR>gG;Wtao zMbvEvZfBO79$ zj4?NOH+nmn)|7m(4f$|dPBg7J@ zH>XtMHRs5h>%5iTB-4z#60a$FiMNs2m|xh4G~ArT)1Byzpk^a8!ptHsrIlvW2Bsn9 zhNcnN$TS8Un1HF6nG>@9>017cmzifJdW<;H#?epNu9v^$nWtwna<$7=?dP%(Oq6w z(+#|v{7&yKubZjmwKeU)cKm7se(7oOY3~{E8Sh!}S?@XUIq!bZ<9uzehv{i*dp%7r zu$So#_BMUMKBg_$mV4Ew^#chfc|Uw%H`CpedEHG9um>&5ygR8Y^KSRUcMKH-k5Ow}7{Jw}Q8Nw}H2DzAmkAO8C-;z?-O@m{6a6$rV#b zJmVzN#AJ4_p3ME#;RVEFiZiGV=cJhI;uuPp{q_Pi3u?`oIL#@f$K}qqh=}`!Ok2{r#vm;(QAO>re{zy9iC41QCT{xz>yVE+8CS#zg0v@ z{C!P$Bh8qdNIQc&bH~oq5VzM9(XI+ul+fbYUZD}6R+XA62~D5lRW{<&ij8=%V(P1! zM%=MhB0tphx-ft52=2%oH51GQ#l=;leX*M%Jmv~G!RpjhGhLbWcksHBx_AXfd}4uS z8?S`3)lE0figOol@Gjh5i4iyXF5Hl$3dt&uc^zATy9CAqu@&#;N<4Qk!$3?q(o z2KSi>70lsi1~XX>bgvRE7ck5B0VTOir+x->RCCbuWX74!923LqEHHiHl={LoFEo;6 z7AAb%G+IuF5^Lr<1}=IdXq>p|V@by(bZsM0yw-7W*2BPIoD+>30g78YlIJf2N0N)u zjZ7$4Swh9i5*k_t|F#hRaZ$oUPUW|z!G}opIi7SJw7U{CTl45tQzxOlb+}Hu-B;q= z3A8+(IdDiaOG}0ljjqG&G??0x5;;q>yAJ%*AdXMwcLsvuR7KhAz_%?jC&Pa(GN&;2 z`25PL9GwCOw<#sf>r>3>luv`F-IUT~=J+Yhmf|-j8yXmKbd#BhD)KyaxvQdtYhEfK zeGFFQ=nSqtoq4N(ngeN57fyRKa|Uzmk6b$`;jKR9>?d%4Tfjk|$@w#&mEXbb_XI_8 zzeQ>g4gDUP`)xvfzedXFWxheO=tk`i;1AqU)b{&?%1?soPl6i}^`FR`&;>jT?tcq# z3w}fM#6;$eiEuT&%~!}Wz0KF$u@7ZYbV)+>kS-1c59FC8PkstYYROL|nEXVhIh%W) z#SHc(GeBP>IjJAm*Yq=zjn3ih*M=WZq`m`boOuYIXt;ThtIkX250%e@Q+}BGhnR!* z=jrnjP9QJg0rHZ$K94!N)JU!$Y&7?r&kS@veCQ)w^)PerIQT}*#N&)+vJ05c#05Xf zS@P(KgJ8W6fjUNO-Nsxav`)uKjr?@rq;2 z9&mt-0zMYMy3RZcXV~Pn_m+ zpk`_DmCu9E!PkhFd;xqOzDm5L_<`kc0OIZ&@D$SWtbp@rK)M*T7d3X}^}qL29jS48JbUNu0YO-2{rqFbR(lBdL~|7zwiuD48+#>LM>n16|wr zaO^k0^W8w}fU-Dgap(c*dZaaRy*A-=Ej;d>`@S z7owJw+f!}_zaslgbGQV>^OTQ__!;pVhVvar?Gvs>v5^eN;%cOsF&s-XD7}r(QD>gm z2W1=T%yB1Xa>e?0`w%IDzjSU*XkR&*u@x7uF=cTgm8hu;WGoJ3A5@IT9L4JMD<$%1L-3*$7G)&*B>MNupPE`GtH^0Te(x zIaC1Ug(B`HH{mF9lUY`FgqqZp(IVzO$oE;?y}q5+!|O}yTe#gRz!}MxvLC5GoRmB&`;xS)L|aO|8C`8b?UK=(QXhE0_LO=tirT{!YS)UM zjG_+omvO)$A6uNu5ry_?3#yJ?)fiN;)0m6}H6qO=;(qPdcrYJwVx z4f(&4p|p38MqoqUmty=iNxrgZb4ALH$?I{ZA^oNaUpo)Xr)SisRu&Dd>QRm<=Ok~X8U0Th=z!X$$s5tWnu_ACDAMYiia_0jr>_P|huDNv z0_wXrNxr+2c{L9y#)hQbrlhK%r1hqxCj4VX?vRwEh+_Kgjg#-*IQi~Q7Oq2`_7H5$ zzi-Ar)P8@GCz_EI`MNRZ#OpTW|LLDAa$J3|F}Y@``ux{C>T^krzzXDE@?K4ay)(T$kjVIeH;FBAbwC ziS{QHC8Wetbkf@>TQlf~WloiNxD76Mf6=O=R zlCRL3w=Alzub`NbqV{_8EqUt^<&dOxJX%Gm9hRCUUrDGQsr{Fl@(r~|q#LaG~s{qPjv^-b77=vZBg{+7&EH z%F@LsR=VPy>zj(obm!ZPN~;I-1dBNmwdzTqk@lm6)ElhMQ7NT9p!$^PS08$wbP+X4 z{lFR=i9+?GuS)YEI@OP!EW47ZReySR8Ra^pf%N%02}*viOVWtYXb^1@N&_J3B$N(8 zv`Q%LgzoI|OY-#AUSGAiufAj%$pq&ar-1e#xRU+Q+dPC>o{z zSeiUTkc_wL4$BA!Shn+4N-h(>Uq|YSieB zcTM_S%(rpYZP~g-0o^zfY8>gSYL5zi+Z?VC^-=HD3@;k2UY!fd>!vxSJo;O6P-7vF zKGqU!&N+=o?Q|i2rV{-p-J4YOv28LQ#d&CC<sADd{84yBSYgs9F8b#BYt1wULzwf zd8S;xx+t-}zn6>>_ms&0Nsmw;Y4GzC58@lurw^&u=(#n1^bgg`>Vfq*H-Pd$Mozor zpX+Ui<eF5RKCNsYowT-&BuPzZLD(H_(^Rdz22(_3ggNSkvBV`c~pa`X*mdd#7m} zYFzXNMUype^-aFFzPjrP8lR%uy_5dY71SsdKhzr(#V$_zl;%q}1~oP{Vl`U3CB3yL zsL@-U9;q=adY+DwVL!h&jh>;rrF2wj9@1#j3{#KXjXI4$HztJ|D{jQP5!|0+H=gxB z`X&EHW4$jWH~#h1ntL2o(DPR3sYNG5J4$&nM^Snu&#Hf-=N6?A-EnkCRH>M^Aj;(E zlzc!mw>avh_allX8Yjw^(maiylp<;d5`7e{%%+{9n<-@#H!V6Vn(L^qC~r!Y+tB;U z(`@xh(Q(mqN8Lr)Qx07HUE{%x42=}W2Wi}BTxc9<^k_tAKGBHLC{TabtkXK_*^>7S zPo>e(mZTkr+fdhv_a*dbr~a&+aH?~xz8mm7)j3w*)jTI^);#GS&67USoU@9_T9sPu zF5Cg^Kub{b3pwg&D}X9aW8F>|Kd0pH@`c2rg=Z5 ztLjY!d^tUt_=f^gOL}N?N|ivzy*B5qiH8;ME6t7ik+|W?yk+&HB2r=UMfCP1D^~?I z-)MeR)JgRSjs9w&=!WLg>Yylw#(fFYa1c0%<5I@`KyV<(HImU^gPKy_pyqM$nKhDe zuhFlW9{V8UUsO*suSS0vsWx9oBfbtvJb5olbrUY49w(Ogj`&A0m2l3!AeLexwBy&YfM&DD~6G&>DujEeWrNNvOS*9_%2 z0MSTs2I2rbQUk`9cooMbxDhR`S{#Hp32_w~-J(v8%4&2vKD-6rShQDTS2SDvlB3X0 zQWgD{^y>H>`74RX5znvhsQw{Z@%zh?1VtBzk-IrrQlVtSVbn?R47SMGNHy}e^4{FMr$qlf#bzBSC{gwMNJ*wt}!d#U3{?P z=`~s<1E%wHF}+SRv&N}7T_+**pdY0&Lw91Jll)shOOffN;$gd?q%_)y?HwYOdDT zlsqW9D%mjR+vyui5=>`i7gI-)TRJ~W9@H0YntWSPSC1ZIKvCBX-)qD7+AzL0jIRy! za05NuFn?{}H#YDa(g;f{wShm}z#nel=Qqe-|6KXYNy?I$opx(&^0JeZQ(IS`UzL}o z%SxqYX?NBwFPE2;yC4}$r!D)b(`w6pDydmkR7uLxW=md{<+Qw{?5wEr+gX>qTwYRc zjbtqOxxA$8ESQp@WlNRREZv7R%Ffc+9QoMUKBb3Tm%MylP|Z6xI43xl{Cv`R!3BYI z3Kt~DXLF{ScOf+w1ZM?jQ{IpAg~6GWioG+btLB}-QL(o__4@^<2WL<|fb#yqX&e=M z2U0#DIF+Mf@1Q{Tg@dR$FgS&}V((yT4hrrHj}DFjj|q+ij}49kj|+|mj}J}&PY6x~ zPYg~9?hX$P4g(Jh4hIhpjsTAcjs%YkjslMgjs}mW^*!Ms!J)xDw7;8j3BPntcyMq? zaA$Z5zk6qRQgAZmlX;Fi!@D@TGnB?;@1TaaS8#t&adxQI^dmxbZ zcQ@A+c@J@i2ZP;$-2-+yrsclDa%vt5?&4gbcUN#X`8?|926s|d=-oli>P~9r z1@pm8g4=^Ts98XHesCK{h2BES3xZoYD)eq4FZAvUcjNx|@r3t=_k}wII|lcKI|e&} zI|Vy~I|sXfy9B#}yYe)*hgH1g;2q?*hs%SDC|?v@3|<^u0$vha3SJsq23{6i9^4$< z!mns_E(~gs7J-X`O~Flr&A`oq&4cs!-TT7x!fk>jl$QkCg4+h$f!hU3!KK0W;P$}| z!ENE?!4=>Y!Ij{Z!3uCia20q}a5Z>!a1D4nttxvr1~-8>@dTBdH66jp9Sx6zM|KM`rg45&MXffq5k3EUCvbWCR4XO?916c z!K2ha5h8^Y&<7r+}ix*>dlD=!I$1;c|&xc1^O&$}U% zSI70Vt^msFxH7yxJTC4Z3m2LuDb0uBj=2HSJD6XSo={$Ktl{-?C>5_AnN3wzSCNALyp z|MoxT%*wDAH9dpQK^M;Mz*XDFN5n_QLxUqo!-B_Y`Gx-x?J9U5amC882JL$VHFztR zhMlEv5A#okfmIZBtcC>uQf0wh*a`qX&4Rx1? zb%TTAgX6litP{NLzr)$qK^y9yqs_B^z2Lz3ptv4w>IQH5Z*#U)(3-Q)bM`sEesDm1 zU|gRz^@2D3w>aA%*grlXZa{tg;04+|@3#zE(f$qpP0lt9_KWwA8`7pha7EZ6XbHCD z>^0#F{)_%K;kD#1k-z9S4_a`p5$ziWFH`f9-z;cOO|@V}cvV;&R12;Ot5dEPR1JzL zmr$-ARN?5Vu!#Jsu#}pT;7fl6rNW?yn#$x?ghK$C zzV<5ym4d6oZz+G{7X%e4=LZGgchr3A=LPwc^GMf(-&6CQ|Gj@jcx6~2xF&qruMp&s z|3J<6{trC$6=7~rf&Y+8dd2_IZyGcUex&{f|0l{n`cb@FynAfH2;7xCFeJ~VCI{S!+^23&aL;(J*pT)Hee$>MPPBO2?ntY5z_&3X?H%uf zqqZUc$?g*`13hYfw9Dds!Jo)~u=~dQfj^ReZ-21+f&0acg7572R@f+L95jogzy{6Z zFo?j2;}(>ggFz4mO=BCxU^DV2aUA4;P03rveh`2`&?0UXo4^lRQPVPR95;z`g2p7? zTI>Y|G@NV1ncSce=@maO{t5SjJkC~#8^*8rulfx+|B9a$gY>$6mD-QNkL@S+71F2RtK@Ie<_++D^0(}J zDim&iW@KeM0P+wHrwx}EfveUamTfiIE2KTyZjmiji}SN3Z=gu0S=2&pt~7eB*WXh(fp%Fpsn22)!j9?bdDxIJgv z#e+Dm2@WP7NU0V$h`cbAwYLZ?42wcpge!-IVOy^X<)W}kD36t@V3n|HD8H0SVP(z^ z;QHF}0PayMt{7ILrkJx;!{SgLE5)I#*9Bok>OT+UneutincDtbQ9I5L3#k7W^`8g- z3gof!Z}4BizXN%xZ*?`V5^Uj<(Wvf6(YOtN|0e-iaO*==am#+z&_gn8j)>L=N) zscYj+vAJP|a0>O4?N-#a@upHU#ZI+3VQ#pXx;EaHb}=~3#$ir4jryr}y0u{(PN!y? z-NJ6k*%{PKw=--M+OU`Rb?{9fKY_1H|zMi8p@3!Rl zw4}7sUQfP~RL46VJk4Hb<*RX>T}gfhHK*HaZC&ik*K($=cMV6iy{qjt2|j8cvsY7k z)b{qi3BC>FlkiP&6}6Ast2pzR?c;qLd>63G#;XrSuokiIT4dq#OW6CDVFX6u49*VV zx=xAZh_@j1j3-btKHi*CFK`R;&B%L!z2e^SrsTrjai4e* zxv)>%H(p3C>>Kxs7m)XhC-OgAunK z_~f{rcXE6Rctd<6cw>AMcvE~*d@A`V@s;t4c)2}|@~QC^94)t3kS?;PQ*&B;IdvD= z%Sjj8GpIQ|J`+3xY>t=3S>T!R+2C2AJY3HK&yLRp&xxh=I5$>gnHH=tZ-JkN)~dH) zy}A6B#*rE(YtQR@2bnAEmG(e$kP%*KSJ?UHNjo8)Z=SGEQl1b`j2BRz&kF6U7%2

;arzz{>FXW@5YvX;Qq<96-$>oIM!4%wBHinMv{F zcpj}L#fvz*kd@E-lOM|2L%>VzWp+Pm7O~oSKX9&@XC}v+QGX~aaQCHdFlkfbYV1pC zh*?HH6dVHXLp}@~3hqrl92^GjMZPCEoK>@Xf+N6Lm#00&&f&RFv6JH| zl&5gbuH17J>u7fckF&?ynelO?S@Ef~JjEVsXT=-G$J*n_kFguav%zD@kG8YpIp8tm zN7MhNsMv;>)C0)WA=h>`$?w`bIIl>-k=fy{mHi<9h z+?M8I(qeNN?JortE$K4e?PlO5_EI~5tNODhTCrUEa+lfQY%>R(V@|afarI(zIV~>( zFSeIht+zfEJk{=O6;ovvYp7>&{c>{=EtiwF0=FXi(iP_N_+onnS6xo|GWvIKv$NgB z_GX>;&UO&j4rHCR;;|fVkFcA>hm+>VhnY*`%fQRxE6j!5X=`w6A~Dq`F2D>>QC51H zUF@#57c0njv4`2i?fm#~b4h$Dcqvz2z!lq=2CV9z4o>Hqo@Q6Oo9)SUyV@gYdAK>k zTpV8#pHJIu%=x4xtd3O#n1-YVta#te?rwW<-EQ_sS{`A}qty~{2~nIH(Xt^pnN|6X zNK;w;zPsJScIUd??YXqr&YVlzZCM#SnHJs59(GULjaGZub2zh|Ift~A74qH8p0+D# zFWZC_@sn6ptf)9mNR7?ev|0)-HQTfDcp|kG>^MeouB~7jdU=#9*c?iYyd0ZLo^Qu8 z!t<%mvoU8Hc?Hzu+qWWFg5HYWCVxK~OYJ+6yn5e37-)++`?x;|tuq~?z3&ggaWTcQi%3*%d&TgmT<0vptb97<6JieJLE{xBj=C0_h=vDHYqUG^L@lBjx9^V`JHn8_{pL?Q@xx+`% zjhw$IzL9h>cyWBBIXilV>&_;f72OvZ>)ZRd>fY!R+J79K6TQs&b4X`LH*ocl=6>4T z7u_Fu*4T47drow2^b+|4(NEMpK)OFVFM5%>^GN4L4@N(7=0VZ}(fQP$2fjf5Q1k<5 z9wI#$T|mwG;Pd1UN8fYiVbVj~Ke- zQJo#`WOg=ZglC3h!LdXkI3pZKw1daYvF14QIQSUr)H@Qpp^VfS?9AHsM>%&q_!#*U z<``N%L3*5(^qq4`&tLu=;%#-G5+CE8o0z8VNN4U!g;G^U<85w)o znq1x0)a9x=<{X~z?C_j$d$R-O9f;6%dU!@S9vn}!hSS3djE~d9iHwtnxyy;*BjitU z=O>9MP?NjWAnk4ICGi#NanHKuN^=8W_Db431s+NM5LccAK1^O}_O|=jQm)?H{z#mn z_U1<-G}JRI%=Pq%6FYsT{ zzrlY;Uw~t2b(L8eT@PN*(>%cMpF(7iHpG7LNI!Yi%`&^Mt-p^Alqy0YNvhZGWALaXa%9FXmfQFbTCx<=}S@z}ZvT)z%t>KLbeWUFlR4TiywltT-ev9v@21^};Ynd+P9#~-5`X3d>S8mR_%>fe zUzl6XZNxXpPvV;75vS)%bF;YxyoEDglD;4wN?sBTC70+s-z8Cb6bU7t*d_VI0s1#B zZZltT)tBH+c;@Fh`vcK7V&d(5#+f_7{lfjj&nVqV`A&|WHaBpm zr%B%=u~904m57t{0(W@cd&XSP`DaK^C(%+WgOyDoSV;W3Pr1kb;fu6X9E{_`6GFvL zDKei>dqDUJ=l2g^qW(oilQaj~&%FcfL0}OP@Dy#b$b3xO1HzZReZjM~{)0aPCR)$>^!5D))U9ti~Oxa<&+Jl)RMl zPk~QCciVA?inazvPe)av>b9D#Li?&wXM1UMS=7aLw!+Jz%cG*G#8$UOw5bxc<*IhJ zlf5LmH0ngl&bF()Jh~$4YP*nkv`<6RJKBq*OTZf3xg#w**>3iV=*p-YZLf$rMWwdH zcH*8zQ5){o)^?y}N3dp8BkE4uE2AFK)zLLkcd!R|6?uEkcChVjt*B@|%ldb`;T#-8g#IJZEM_*E2R|MJpL4v#8lPniV}`o;ABi zeYtLT(jL(i?mQLjZF||7{L)G@llHTs+0k?6c{4lOn0y?+HQtW1b)!1b9L_v%=8#@6 zGot-?z8R$JC|}2wZTay=Hcf4&nEAChZc9u#KZeU?bX{5)J0Ar;tvK z#&L)7;6OXTZe*K8jiZfdIl?ZAUNf(oMbSd?ouWgz(@vzFqv5t`)C6ooyOX)kDbdN% z5c09yVH`Nf4zy#yvC)`lupMMKjb1lzm`$Ta)zx=)`CkSDZ*XDLNq<&d~{^6Qk{;BWSffX@}@|>Q4YS zBG2_cfuiOnQG;@c8uTu!92Chim-IfU_?Nk)4?)Ex%T3~v8|2^}*sR5SyPbCqM zo=&16Jx%#3uf#9)-!~=x2hjWy|G@Ad@O|@vsY&}9eog-!^DgCg&3i<&dX?**VWxN$ ze2wT=ihcQpSBo|^{px;+e^B^D5?kpB&b&eVt7F4wyxN?t<=6J#GH;vO{@dmqQ;oI< zh1Ez0hmR9M=`Escy~P`PoEVyK5-IE0Q1P;k36Bkn{c8Tf;kV{3uKd=#Nq!CW&k>>X zZQhQebG_|V^^0j!m2^n>9c{if*V0CDPmd0d2_L0Zu2;pc>K_t*&-Z`Bd`~}k6MWNr zXRf2owRq4xLe#JvQm*#{ZN4`@n9ZV1qawcwSFNPYb;K)sgcd(i|AYC_Y#wbEJw#oO z_Y>tG%}-{FX!FSPw}^gX$>)~Q7Lfrx-}sB8Eh8T^zVB}pEskPOG09@m1E6A?#YtSW zm}r?fUO*e)5B#m8t)dVN{LtSf+B%BB(6?NxHEg#N$IB*>y{va9vA!(nZt!j*h*{FT zpkkhlB(7gmJJM@p8-k5(Be02W3^uh*>|Fn-aE?FMKQcTj?ByRC9v1cnd-?OInd|rT zd-;cjef%QcKp)bf;Gwjb?a$%5*`%Yvqj@`h{X$yxCH3()=KM-;W775BCfsM9zlncD zcx2dvdmRq;B%e>sCVqFnhktn3&#%nY{YZWNSzLX+H;Z(G*PnAog#Bqb-!G$0Kd=&c zH?BK8>_+PE&*X|5yqTmMy*ivN^XvE($-C03KiJP2f#L5t~lk&0bwU z-!Jg%k}84~xv~pa3;+lC1O0lOt?PH@XdpPyALLK-r*qXb(khCGnEso+$PDCpE232sb&0Cj_j+_^EwTY0m|_or^K zMmrT!8Be(H|$ z?k5qUnVLuaOTov$Vcu}>KF%NQT}Js*|6cz-%9m5V%sKqPc#b>9mb2!B778fi%?XN==ur zJ#|C9cH~37wqZN4P1rWUVcr#f8%o2dxx&BFKc3$@j)TzNl|Pj`cMYe8UBhnSv~VAK`7~;#QeH-HpTe1L;S^G}a5`tFg)PIY{Hy(z zVJq^6=--2|FKaq2#;Y7}tgeUNX z$9pGuH~BaFCwMpexA@J&Yy4}$7UUCXS0kK2+tRRE*gU+}Z$`S#A5UG4a6GAI*pxHZ z`AtbH{c#-E3deD#X4r%?EB&z?*AB;0S1a5-+|%33+b!J7+Z)`Sd{>^Xd$?=38_&2a zX=bz!5$+l8;qB?|$yIxV zJ5$#K>=E`1_fma0nk&k{van9L6K8sYJ;Pq%D30rbqse!qt{2!V>>ZAzt}a+NtQYP; zU2m{=*e4vpaeZ(k`AIz0iA2D?-oL@$p7VXe?MZ#ZjcCyT96>&uQbTYf@}->b3-%5B zg~O<87``7We)W6gyL<1F_5k+^XNB+b%zJ_FQTIW(E0L`~pym7Fc3j;L>=*VA-{Jf$ za8|f+_#tgR2;ZhO8+?cSqi`2*SMMY0KMc2}^??6l?>*q{DyqiqJ^P${ZgSIm?;S`; zLJA2b3F(jmNhk>kq?3?@&^s!KfC@-Qdhb<01r!S^C`eO^2qJ=j9YvbhzUP_Y{O`HR zO$5dF)$hH(`;Uqn77rjyEB=h*Rv=#@UPs=vVza8FvtzPmRn3W;Rvp8y zZ(8-+;zP)0Y_+I5Dmxl^bk@A;Mb2DVe37$P6q{5%RD2lOl(=Qpk*vnuk|SGG)l@xP z{C=^fstNHW{DzD9zC^!b|Kd+Mb3f#Z#Eq-IUwi~vL;M1{tB^k>ZdCP1@lj-B;-8Sa z8uPPpC@lMa&>Y4VyUXS>M`VF#m9@!vAqWQJn@R`2-fgkk^QdtI_cMo zzeg@7Z$*3Nt*U-k{4r;)MLtLT2K)a|tg3pv_yn><{49Ic7K>F+ z6n}uMB3{Xr-ax)l{A00D^@HLMkwxMg@@rXn_eSImd0zFy;*-U^sz7{wenWm;c2j;0 ztNGr<-W&7l^6SaDj&OZ;Gx;~=q3X%vQ#c!Q;%nWX-I8C;%EGs>_vU;*RtEoLaX-SF z#m|sWF16=T$Q!aFk=L_k?=|_g#97r-#ixr|RUrOseidsLf0pAphog^1UPF8;`Rrrs zXynnfe5n9CK=ZCHs#-9z)A`I{ByNetG$=;%dU%#m|v* zdj7fm3cl;HfA)6qouXf4e!F-EIiJh@{_;D;HH3GO?-u`5Jd^x0@-y?xGuDRo+cQPJ zJX3tHxGq~uSzMPrU3>=lOz}s^AMxDRWzX{D*JbY&|BU=|@h`}~6#t6+Yw>T$zZL(E z{5yBc6*y`gcmH(pEUtfM&U}7st*Y!wemO)uwpUelQGPM<;`|ciCHbYuOY_T+m*tlu zFVC+)Ucuc~Va>S~#_W7o(!1unA$QB? zf1dQEd}$>kT#lSht(9^8KzbcI%gUhCWsS4bOErWQ)iv1)W+>ETE19EElTE1J3Aqz< zgP03i-5uGLxmd22aDVArrLNg)%ny5wd1CjIK7v_&M^qn)?4Dg-VqQS$3gi{cU+4wL za1ETn)r4yb*A=cMzAA1@H+0OdCr^&ydiaAYIiTg1nTR%L&N=>|CoiH1{=k`NLNoia&>&lY4E zq!=!aTtj<)fkZ?5NIHC{_z?U;8_0$(uneCpoIotg&=&a+@h8|m9(th-)WeDF?~;9- z@QK3r3lA6CW)G78-GW?0=j^+%6rD1OhIU9f3b}@^@Cqjq%QYxH{{hZ=u@H9SI&TtgdVo9uzYvcgjKew&={6uyQ0c40YrUEvs(Bkw2YTZNTS4qdZv zlD@yNA6s3sZ;<{byg_SH-z$E%*g2DBkS#bWat)pNe-aJS4aY>f;n+ww90%PX%g{Ev zKe8DT4KfZlN4nvbNH^RX>4w`P-Ecc}!`JvPUoUivR6{q2hW$vdhHmHv(Xbl12D;(e zNK{-~JQ$ilqCvXh&`38N7U_n=Bi(QWbc000?Z`VK-Ee258}5p9!xtmn@TEvM+|F-m z1<~-;LMw=d`;e`PB^tVA*F}CpqCu`4t-#8zdUOguFY_4fjO4 z;oe9$$WF*L$T)m8G7hbvD6WT@=$6Sfz>M(!zfruQcs)5^BS*3Ux&mII1@gDZ-$jOD zpGYh$D!g8hc=!$ZzlCv-c#wDKmi?NX-@q-%JV-CxP+ZLZZg34>WA6X&Iqz%5UvbQ@ z3rh-%$^Sz^;z5#O@4}-6`G#Mz_g9f&SODp;gkv6K&wa&lY<0^d8RkPI@SO!%1}O&_ zhP?{o3**@PMC2PJ8TN!ZxUslL;Rlg*Xr8?a!O%Q=4X&X%jKgcl7Q{a%egzgm2I6JX zKZj~)p1llD&^&voa1&I9?rc(EYSAe}HH z(hV~s-7qWC4YC(<4PS*<_%W=6M1zb&GiV8k250L_MKp!ykZkx0EJG7m3gx{}29gXr zK{QNypKds>`uu8H2kC|hk!U!#T5e$yEW>!7?dRDq*D!%+E!S{PBpD`0mf`G3CQN~G z_&l>|r5E1Fr5DD+HOM$fH{4y6QusqI(J&^m3X%%a4~JJ@z*%w)XGJn$YC&${_xYQV zhuFR#{UE)tEnI`dgOtMS`3?nH2l<52g(IpD=L!-HXGT_G8eD@6#BcK^**(a6I7doh z6kLNmgp9*2a1HVwat&ux|1g(?_zlPZHt!PY2YH5(kwzF%_%->z$)C)nA0!&27CgUe zK?dR}_S}uUo7w#m4KfPS55MB9U+2;bx4|{YNc@tVU*%6n20~V0ctN5;c0mT>7wr9I z{tWxST$EcFR*-9uT9AHtjlI9ff5iST7q@2b(1JvR)PfAetL%L(ms{An@GM7tx!8;S ziEH?D^(*XsHJ4HtQuuK$_aMIfN zTtiJH8l)K{9{!$7IY=)Y2fHBOAl-0mbv3c_Soj6Gg^xwjp$c|EzCpU-=twVo94Y@G z#ZZX!!Y5!Cn6Nv}8hAa{d{i~%H8b_i*c0ul;FT}!6;TnFL z_k(4Sc#vq2V2~Q=!`{Btec%`58sr|N8~VdFNIS?g{4AGWaIU??L$B&4nRLTTFb^^g zFXcVS=>^ZwBJ2*DuzAl)F* zAm1R@@XJUt{2nR)Akpvw@(p5%1}#<@2)TxzM3NzK4bMlCL9XE~hz99~=OV+9xP~7y zm;W7z2I+=pOY#h@pch)hGRQErhFy?#kZx!hiH4bxVQ2$qFq<6dh8B@%m=Q^Xw$*&| z3oE)iM8mg{4?s6`hiG^J`Q6fk$nQZnbcbm89`a%6hVBpz4P$S$-XPoiO$$S|~nYj_WSVMyd2BpP;(3`2XkhCe|rY#q4=iH7Ns zVdwzSAn_pG@J>mhVOr!CI!0EZ6S5QAat(3}(hrgjKPnB6+=C25=W6MODb>;lU667P zat#s;ts=)T9CD#$WE|Q+IY={X1E~aw=gt2pd`^C#~|?_(ICel>#&x+>mV9R%;8@ci3gd2cMCi6OLl-`xDOuT ztAzVXUx#t%0nzYv}NEqxPtPsz1yWf<-)T~@l3_-^`gat%Gn{W2x4 z7eqrZwl8OYkL*k2d>LY)J1Mz^$B~b-CBN{e!Z?1(j+tD;7fa6AexfAHAkpw1`(zm; z8ve|-EQ3VDU)YvqkZAZT+fob?4S!>MGAzSF_=2n`p|B5(!{jU!v!a~BKBV(vAYFiN zm<-WSKvqFFOooQ2LjIkrOyS7M$i;9FQy>}^BbSzzAeWVvBA1tzAy<@^BUhGIAonY+ zM6N3Bhg=QaFdvFxHF6C^!+hw5HOQgF^Vy51H?FNG&oGqqP{vZ^8Dt!Wur0BWh=!4H z3{nmf4I_}U4l)d*k)zoo*KlB@7vvg7L|)+#V)=wINSOyI23dw@pcoG0C>aO2B8i2u za0~Je(hW~RGe|$kH9U!wdyr^Y7a4}_;2LBdQ2O!UIC0xT*r0z!E6G?`v@C(R2NHQd@;ciHV zYuJ`&xF!+}Uy3|~bi?(LZn&P5B*XQQYq+brcXkovLhtNixQ5=a3|~Rs2iMR$yAZD7 z4vxGtG7LAAE`fRIom~p$&^wc8xFeDbH^MbsN{&Rs7nuEhGo-`i)t8ZTMfK%T_J&Zn z624)}?5gT3querb4N?x*R9}shYS;p*L26}Q)`xf=VRz_;zHH6S`Vr41H7}EA_(CKa zJ`*Gs?kLGJNHjbNxgeh~uUf7_qCwU{qTw#&otz`-a3{QiY=m^f?Ijt8PX~#H705kc zBK9Na6o>}72kC~}N>U1YR7*E3hg#T=z0wUQLo~=eNH^SCl4m#>c41XGDaZ*dWB$Fw zgG9rppcy0{rbfzPD%&T*F-(o}L|BIDk#CT0I01q|zCpU-_{cLH56!SMsTq-PkZ$-m z1cQ8obi>CY&+swGgPEix78XRVVLnpIL83uM;X-1$h6^IkAlD$_Agi!2at)FSd%!}*b6SOnJ~10ln(PqlQzc`ytT4w4LsYd9zJ3~~(;4w4K@ zs^uEaio}9kgWrj}6=orE4QrqgmcSzH6sZL1hJ7OGuy2rVI5RQ>%U~SVafXz_I=O~O zH~6JHNrziYk`A|&#&ewsky}^-sjw5*kyW@EqCo~iy5Z(XG>ngA!X+h%2I&N;2#JQ9 zBGDk-a3EwuBpRxr8z38G9BzYaI0hO*x?vo2g5N}(%-M1c%ONr36P8D!K{`PaLOvmJ z4L1h4h6PB!lGvN`7Dl>Z$H*#3H^4TOJ{P1Sq#JIjmRPs}Mxi%n$vDi9bi)pjRgi9w zgphH#xmvE_`XIM(5WGSkj+9S04z58K;>^fENGT+);W|hK83^fyy&|jdF^C2!2#JPk zk%va2LE@o5Vb91ljExL~T!YMm#KNILqG1g3c&LW~94pb_Hv#1u_6QOUS0fK69!TEq zp$2}TA2dThG`Ug9)p4a48kd?tI?TqQB@7U@QW(xhhKBvoJ_7kUP10bGT~ad z2AL{(hHFU6H$1=qgG7S#!*8m7%~{{#YA-`D+)pgGa2;I3bx;tJ3D?6i$T@sFau1RY zFI7EQ^*~kP8VaS~!bZ%=z7y$(@38M@kz2T-TDsxu5DBslR}x-~+`^63(hXm$l4y`o zc#!yaun}`I$%I5SB)Z`~cm;U~xrU#@HRR9=-{ZWz^g1NOoa}1$B(C8F=CGd`z6#M0 zO0o+w5Z6TRLAv25Pz$mSat(inU66H;OptDnfRJdAQIL(0XgC}B!$>!r4O1Y8aDJp49*8faA9N#9BND*8NH*hh0L*UpUky7|nNxGp!I3W@kCloJ-M>qk-;c{4pE%<#B4blx;K{rS; zB(9--BpDLd(2lw7r$9J3-~E)583);g%OdX}IU&pN5b}Ev3epV{ z4e}7O3`3AZI8&lQx}gBw@Ttf>e5&{$%z})=gF&L9fUJsiLxJN?Dt;%xzBfJ+01-XVMa0yZl5)Cp6-yoJ;_*0}5nnEGG2j3v$ zP!m~&w_p@xAS4>#6`&a2jg&&O$RQ+_;myc0$SX)Z{3Vl$kZ5Rxtl^u(5)JP_H?)9& zcpJW;1=PY{U>E+x8DE84xSwlDFUU1WJV-QLP?TD@ccD*q<1Odn2*%hak})wIBoWM~-X!SFV8j|{`RNXdtmrB6;dzt5cE`kT;#V|UFY6WYNwJPFIt9&$nXLnwykr50W%QV!A$Peh`j zL*y2ogkq3&kYz|*gN(y_Rqaa>4ILxN@DyA_bFR>aJ&9=O5IKZSkP5fKEJ!qrimbwI za19+G5n4z3VQ6U>XGt{3E66~|D%_5|opVM+;z6!KqTy*c1-XWsAsQqfBo^cvI>IB2 zjI_korJ-DH8_w$twa^)6K@MR|Nj~9=kP7k*(hYY(A;>*QH*|$)kd2UT=nU6zSL79> zA0!qM*RWmHkkZy%S)xHw;ZEXht7IVL4Yr3ukdTmW=myu&8RB4@$VrUmsIia=V__Dg z7vvi5j--ODm6XDl;2Pu{BpRd;WFY26LPENsd*m9V79=4g782L+$tsBkxdbVSPq2Rn zNQE8X6=ViZtdeMuKaiG~%k{d$8FYs-_&7&MC&)m^HAodmNJu062s+_jI0adT#5Kq` zNIXb1NE=8+?8UWrfH~L!;$RWnL*g3l4ss3qR>?5PHAqoNH}r%-asR)UNCCKNYBqSPS5#%T28e|S6 zBqSPS5#%8x8kQn|0taz9Ji~;@HS83*28jg835f<-1UU)0hGobX;27y`8*KOxu9rzFuJe;`+}MU}*ZTti=21c?gihKX4s@=4W~z5K_21)j!j%cA{rzZWE~_LtATgQUZnsz=Cq6vjc~ zLDFF@OoOb0q{F(ZkjpwqIvh}yN7g~oVSQDj>>=obM$iopA-_-D2)g0>$i~ElNJ2mcdiyk=R4YL1d}_*Qm5^4rAK*>{Mmvj>Q)vj>T*v+oj1QhXP}p)Xv+tgK(D zKeB&m0CGSin+BroOCzly>2M}w!|6~AJHj=bR$Laj2PuXnxx~U*MahI6AQ(>L8I8*& zA>53zH(Nkm!a5xkQ7E zLeoe$$U{gpjEW4yWGID^kyn^PEZs0a5)0qR`y$G{CUihmw4Eky+b3(unV)^s4uXct02)J=OE)S z4X$AzEW^oA4+E>D7*5Qk7iK~#NIb|mY*BR>S6%_va4sx^M8hYc7i82v9Z3kehMAcp z!?|z`G7qv0iEB7M@(c$AcG>&@bO4841{YqjO$A@d@S+|gCfyzT;v(H z$ep`+EL_9k93#ar6S*?~bS~W>&9Ew$bXb|+0kN!kT!}s#r+1fdiXpmYsn^>aZVC12ZZjh4gV#i3Ul9??k%cfk-!;!#-Jt z#5LR$iG{;*iH7@;k`OWu-()845%3Pq$CYk4oO4FOGE75GqkN4(jx3IjjDrlr2uOzM zk!u(Y-!Po?Ht-D7Nex8~gH`wfziMmJLrL!(xrRGnFwTz@g+zngz&D{ABpSAkJi{Hi zM8l9sCfu3JFUTuQrF_qaZkUQhk0Q^oZ6q4zM|xolT!Y+$T*Kfex)K;kC#u$Tb|BNd`zf zNGa@8lx{dQvI>c7coojzo?O~MGUFn`J&|iTq$tBMF%k{0M0#OKQFbVZfII1(I6`z10k#MFkFMogIt62 zyJalo8eWX_LgE@~BE2BjunM94q1I(hH9wWgg@f64&sP zNHkPO_TaI|H9Q~5g#C*v`87vC0?1peglqU6IlqT-Seg9+#$hEaL(8g_+3$+2kkSrv z3u~Yk?Ko z7#W6ZGx>xc!ZpY|To1o+Lw-{(@gUc5O(Gg1y>K1Wg2aOy!jo_fvJmnK*X0ro5)5(= zatD8eJCJSo412DIVz@rLHc|?54L86?NIKjQXZAnEOn(^(i3SM1-@dy9h6`h zE<#=c*HFqXg=;9mGF*zh9Im01T>;ln;$E*n?uwOGf@0VeIUAczVs$rUH8BG+k!H9E zmcbt*-B657!-WtHG7g_d7Kj7)l0iDi^aMg*>TKZkev(N5VG^28v-oD zdB{sSLq6hs(wDIncv6=kbMgW#!#b`r9jy(p64Q${SrdA_rz!TBjF;Zo70hes z%^He*7z=cq|KIUF%AJ@2;}>IH!G8jA!}m4(9_7FGeGU7$e($m|GwMt6OCcpvElF1s zTY6hiUYj!`yGW`zvWnO;+>8>|jM>?i-e#1yrj#s8T~k!534MLbvN`=?$}!?R8^Abk zP6(XiSg_yC^lO;|$n{I9ejnKxBvphW|2usR-Weu-Tg2~V`z4X|?bY;!R=>~c9SkA% z8}E7Nx^-)%`>QTL1L?csY|Ti0*% z`h8^AxJ}<;_glMuao6vtmcQ`s*LVFAtKUN&Pi{BLefmz6bNd zCT2a6J&==$dm(!wrx5o>_Cii2?t^rlQSIlx$UaDI=7#t6-}Sy4>f8UW?-@0`uZH(k z{{C-+J>$&S@|U$gn(u`*v|s;S?N`J5YIt7__Ix*N`UZQxq5ow+tigZs-}HUbhWFKA z&o|if|Gw}4Ht1J_el_S|8yz0sgw4faNZz0qKAG}s%>nGZLz!QQ~qXs|biFzeDe znGNcjs=`!Hh-6h2TK zS4eUF5=RZ1vQ9|jIQzLVsrIC6h+Xxh9iFkatU^*vsx7h+u`9Q&5+ghrPHHzcuDP z_vGGsaKFCm9^6%T?%KE9J>F+Gr1Rc<%SzWp@(z_Tyv-jS;cl!u3tpD?ogBXTbhvLT0{O` z|9kosN*DDi#p6q)t2y6eyqglK+Ivi;wpDyt1!Jhmc- zUvF9U&Xwui72=zch4B5g=YDe1K5?b>K;=Dp=YC7w=isv`#p8WnC9dsRb)Sj<(Wh48 z4hn>tc)m}(hTrbhYB(pA0ZWDdy>Yxw-7?^nt;akg#Q)@#UH8d+e-j`3V1HFi`ELBx z?kz@{%9BUbUMKzDbcJ*^uj2NHyUwP5kH4?{f4#E5EnPkRHt(nM_iXAqoBBOI4S#QX zF6l~^-SYb?|8H|riB9``UcNcYvA-yfzbq%uCz8&tj&ZtLdP4q+be+oUr`+@oKFBq_ zLOQzqpVBoepUZ#7H4ErtAMUt!e2d<5&UOt?tP0tL*yrWyVQOR}(rRE0aceZU8L|zr zwNCR`4_G_3W~(Kk1zKub;P>O(qIG_`z8kecS9H?v&UYlVL%PnF?N#^8HMhDUU75=@ zx4QDzo3pzh+w#|&|JDZCl)v8mx+X|I*@)x=wDC7vV|fqh>H55_*UII`H(ktn_Vlfk z>%a6)k|udpN~OK&J*M(e-se`*pYmHySF5~Ec~3gCvMkh}PG!ZbW;_{xfvrw+o{c5f zTFiD>&9XJN9kxZ*YNF@P-`|GWby$@?pYisY)y3HEhySFB89-oNMrt~XTq?I0B9kLy3M7l1d z>pi;0qixA(^3yt!ZCU%V3vGleKz51iOS;OWZIUZLc0-OM9!ZVV`u&wCCy>{T*=F{) z(mIuCWk^?p?9SXX?bo!HWm*|BtreM8x*Sd|)Z+aWFncn`#ML5QInuUo812<0wp}@L z5;bC4JJWSDdy`{Z=30`jujwkAX?@M6#C^!O1$K2w+uI@3wf2WH!c^o`_N8??ZGVSQ z7rQd3YyWJC987G>JeZPMxmIXDj zUgf$rwf<=9_sh+;v5chkN5@cFK8p26Eo-%_kbd~}M|;GQX)m;CM`>vm9#8r zR?@Px!tBQSHI(J{r=*Z1ue>*4bHzLoklFxK^h zV*T#>>q)I=oo?ONi#O~V!UG5cDG{D;-P)VCYn#%aFo3eshZ1Fpkqzt?-@LkG`LnL? z8f$%Z$`&BRnm$JkW@{?CW|>t(Z9j6_3R}r3gsHLBoWi@bM`OE^Q+IS^->_Kze7gl& zq>iz6vE{Ae{SHG8qcqwoPeR&?S*zLxY=g8_o`_UOClK#MY2Su@)lqw`QzoDtYIq}p zeT@m!1=bo9&>2^KZcP0#3OSM^TE{oonj^-&-!|98dboyT>@BpW-f2QkO>C8SL|O)# z#`4pY{3g`sEy-y?*q%~4mOag|AI2ib#1gw5DO-T;ky;kp^6ix|Tzxw6Xu`JqmT7E_ zB8=uYO=W8&VHCf93R@!xBe}yVq_*KnP2pKgCN-QVGnpqfDLykt$%gVwe5O*fTO)nq zuBtu+>AM+EJQ(Sl8%MkqaxiawTzvOCaA#W*#!)_Yh^53)mqGkyOOm$HK%^zi6*~qX ztv}ij_m5Am>^V+;x7Os=dX6{r8T&lSo@1Ym{^Q=1Tzl>M<0?JJ`i!+cHuN0pGqx7o z&~sd$&$v@8J(e%~ZPs)hVhJqwSS_FWkL|bG7ts@Eztz&-me4Ni*|R~<8uV-!n$@6Z zji~GObZkjLxM%3ThS1n^LW8bSWwUgF|HG30kCTk^Ytfu_$|E%9r?#KGf z{?mS&Ps-otTl-J@ZT8$PAJd83$JVz!X??x6z8wgD)4|raBf)Pv*zR^BX!A`b)j77l zU65Kn0s;I57`$vCbqs~NZAIDp*^-l4$BZ!I?E8?G}*&*bZf8L6F-yHLLE8#JSYjYQfLXh!K8 zjkHf#*MiqxZ-zc<*=zSVLuYrS6lYvZQhErrh#KcuMjP}->eKJ{457rTeeDQs(JjeP zSHs_$dPPlaPjC)`^ynb=45f}yD?1R{qoc#nmx1gVMt!4(b|iE_j|Y-JfUpfUP&0Bn zQG<*_j$^A6^~-pqy`m#IVrRZ;whbx2%CNA4K|KzGAw7 z^xlMtd{1-$xeM8vh_uhPo}2^u7U=*|>yQWVb+7@X`tuF8<;a!9{rRriO5`fy{@G%_ zV%ncCl`cjuCGO9+NS7j)6L;pSemAN=$8;uT&Af=b&U_Jd5prK*Ye#G8en@LgYw5m7 zYg23KK1gd>Yw6xdd(YO=*2vb)-6=`Zz|Kb9pT7Zo;cN|ZEjjyVtC6eurD<+Sd*XJK z279lT3EPp@q%9@BuU1G)hQG5V(s4-Nd`sflq;{puHYc?kspgdY-H68^@Nyk+?K=TcRc?k=rA_pC0jz`7ZjPsruI)_pL%Y2HZWqTi;bb-jQ{T z^GTdj&U_pF>-(v@7_em7#RlV->f{Mw8#7CDx@L-{|4QKI$PA3``3%{YwM zZ^DkEbUV}IV8S7k>#n5y%HSwUbXT_3wNXgxmi6Qu7`1F9WxOlfYSu_fdRMmnLgYwF zP*=A7#^gv!R9CkBCgn&eRrfQv;(;ZNssF+GiW2b&WOD@K_rS zkG0saSYr)~HQmrys||g>HrzT|2l^%FQ6A?}TATBWS8~0sQKKCt&f~lDouoM^&Ps9a zitpd~N45;wv$ht2kop7ebFPGAm#ub2Fr0OLIP*vyfVFjx(B?5SM3e_=^HZ=2_34X)NC@ ze^>gi8>ZFNX6UN_X=j3UvHxEmP&4$||F{cbXY|w&a4piNXuEedBi`8zQoEqbQ`tKu z-os4tXHYwM=US>YNbhVra%NHkc&~bk8dE1siuW)Psio@E(1WI>>T{WZ)Kc|HjgL|* zwSWfu6tr7&q<5y38j!vP?bZyP+8((*+k^PO`idM|-vVg~a%_D|r0t+%>swJPwnw&S z+mUtK(~ihav0c?qGnhKj7S;Jw+MAt8I}2_orOB34O&p4*>xWX`GxXY)(|K9Ls2jSG z?jB2UKaOz>N_$z`SznH}s585^p@!L(J$(uNsAqbR-;*#BITB6o!(L~PjVA6z-YDcK zwt5qsN!E+lHFR2#Ydx;+JL+S*?bwf2tu?-uhU0g(C5{h`;Ci+S+8(X=m98$~x)S;p zZ8`K!r|;0U=5AbX!j&eP@axBr?%6WiTlOC|rLpIpnLJE0q;$&%$P)$MpU z+9N$;3#QLp5B7GHaK|UMu6P9;y#4l{8x3@Cy>SWWZmMN*p`Ik*>q0mrsfq|E-V4g2kOOt_pSHh?N!bz zw1n23UFe+HP0uT|?E5yIQK(M%Haqjq%05kJOKd!^usoyCd4=koHD`HVq4$`_oI)&f z+Og`A7Oj0rb;dH@s`w-F`=a$@!bDrzYbWU@ez3(0bJ=MPF?gZzIdB@!dX?AlB zci`Q3B{+(BQYkk|bGrQaJCVjL2XnuEjW_SH}?fsVLcYD9JGrPT4=X-BBvpe0pckTVw-n(x& z-L-e;tXc2a`QFJ_pJsNaS>9!D--h$ME8E%f``xh3tvqH^>3*@C^owPtUwq>I_$?iI zR+cn>Y4WnD6}GcJN$1DguBj*X_?$iNY;m8T<+d+R!oG%@ZjYlM&!#&mYk|JJ2Q7gC zoY5TVY;*O*8RY}WZ-Q(}?W;C9lBc%yCRIaz6W(hd(v3;i#QIuWDI=#5Th8jW4X!5L zD3%86cI)#JK|98o7gcfFcHZ{WntTAkUZ!>U0756E{gf`mojFR47)WS?v~3zlXoqaa zesyLbcc6!jUBh0r*73^5q%Bp>E9pyaj!ZL5`f;Cqqh?rRTekXfx8_>f`XSx+%8pO< zqy8_q1&*(#u~*v;M_+9#?6pkcxA%n}hSFZIcdoQ`OFqHW>iH~f_a?-a zFtvwz6jDFlC%$8R`pVRPQxdwb&rum}S*ETxsb{wU~B*cAl-6rPLB@ zZEq>H#Hy#3Gs~(y086PQRz0ZJ3sOC`bXsC9@9L@L(K2f(wN$F7 z{<5T}{bLzbPY02*bgHA4V)e9dETc(J`^M5~xm9~ZEV+#+Z}xfn@to9F%V$5ft-Jfi za%Z$flnp2SUv|lV0){5$fZ$>@sPuddVTri)7n&}g$ zA$C?tn!D0BmJqd5+szW$ZB@7ulEXk3vt?&01~!aC)jG>$6s>n`JxK zZ$JA!lpjP-%NnYls}}zS~Ay+kVh?IrY)Yt#i3QU)J}^c3JIDt#i`xr1g3YYTISCKDEwu z+hyD0x~+54dgt)k5^t#QAEaHb^a1jD*CW=1KD@rN8H8Q1(Wa53N34cEzrHekVy%#R&Gd*hMouN(p8T0u zY-*;yvc_0!lSx+-H==!*M5;twO?jCZTV6e5`p0a8%bu|bJel!q>lqtQJvNS%p0RP1 z_8nurHh|VZ|JaU{ef<~KP}`%6ZIJrJ^o-d;>l4#6<~Wg-jpIl9#FBSxF!5HDJja@} zbp}&D^@(Zm456etvZUSP7_6Q#>%(Ex3))P2!G=fsW*8c{9l83-^pfe-?M4`Z?8;U@ z_S%PWY*`y<1iGiEOe;t)ncgsG@~V~k(2{3N>u4l3;23gy(~^y${ZIa}ZDYNtmrU>2 zw$aiow_3?3R&L+)l_hUj@{Cpb$|`+gWnYSn`bhvp%s(yR_0L zR_P5(Pgma#`{g4G4Ia%s_PZh zQ}p3EWACM|KhQh!PSZW=8S}nuN#%^aBQ57z!q}R?mNea|bEG!!547f~^$OPIjLW^Q z@~QwIz3<3(`(f4w@IBY{9eMX<50ZDCRs~2iJQHzUp5dw2D0z@JwKjnL6}^HVtv}Fv z+|VniKhRQK_5_yitA@MNQ`VXHyP-eOw_4XLnASY7L~q_7xUv1bVQ=|A$$n0jb7fE2 zdZuhkYdvd2+jjqR{bl>g*0=VU|I_T}a(}tDr<{7n$(Annm@O^;T7S9Hqh-Ln>s9L38tFphGY!1iOl3%NAMN5Psv^V1TnAf&X zl4GUVGHf5)L+zGA^juU$D@AE-qm`nxtc@o$LXIPru4s(3U7A3in-qqm`C4CKu1+2i=HGkms> z&uV+NJCh#4o*g)1BvP_v2U24xHFCnQiUe@$8wxQ4^38IByDJ zBBg38&YMb@M5)pjIxUuyX`IoP^hC~^Mwm=Fo5VTJ?VF1IYx&tFmKWtm~G? zT5dVVhB&Wj333TrD`LI3BGz)wm@1M}LjP7o?O(xlmXTh@p5&WPV`%pEU1P*~toq}f zk<^GQYmt<)H225(NvQ_6F7MehZP{Z;bA$^2hCIFNdf@s|R%Y;Do$0DY=gik#kh`!o zlV4?@(AvcwqjQC3ur-TcmLqevXAuS=t#4-YdkaWwl-Z^#Ah=nKBGBo4iO7< zFcP_E%x_9OAMI;~Y(}m#Tt`xl^*k*=*IFQ*4YYvm`N;Wf?Ts$BMC#|*o3Jf%0b6^M zyMWTWH#rMAW^YP%D^iQlxK>C#LC#U#7OB@{5n(K4TAz@!R!z4d-iOq7l`2+xm*gy3(|WCz5ym4s zkhh$At0Qt5Im-zXkR91tL7m?T*@Rs z#H*;!ox!M=%^8jRA@^fzHTkQM_JCJYlXpk1;+WNh$;^K2LCTr7ruEsaA!mQ2{(v=E zFXA<9o3D>=EjeqDYhqf@;5u^FBK0(^BV~@B!~*8Mhk7|~_ z5Xb9hpdEV9)TLSMv!>QNGK-_E0FC3tM}U+6g&1= z$UVrN&l!6lI}_VVj7MraE+93Ivfq(?ds6~CAhp7*?H3@`u!WSy?U8!N)EBj80b7eG z+3k>8bBhRS(BAB`RoOmjf;yt*x^HaL_C;UR3AIXnS%max+mo?Kt>ML_#-IaQmrDq( zk!sZvQnn(gZP7|w%F&~dOQHrXW@{N|+0JOOE{iSpGPczedmGC+XC!hd@rszcBDQZU zs7acW(>&^q+P0FTMj*8vSCZO>(yu3AKSEQaTD2cxC9)}7t2k~LawYLT2ezO>)QM42-V2_$z8{> z`y;D~ou5A#sr7sSsjZ@RtYtp4t=f7*6|#z>ozH(joZG)8auC{bAZ^AVq*nMrXibi^ zeLN^0cMz%dq-~K7B6R@rK+ZadFcXbY&(t4hHhZqUC+D?zh2)QQd?Ky#QQ&|0OH%(U z%`|W<)1I35y@>Uj*&;V(Z}O%(f6!K5Qb0?=cB&DfDbkg`0%fHS(s_DXHs!Ski(IQKn)4uD<-C6dg5pv{o;;FIJ*_OD%fu+utrohv))Y&E#V_Q|l zbDl)bM1rG8mc2C3+IG?2bLvT3_Qn%xkoKr;eQS8XmOb0!8s4~df@=*(Ah`;G6q0KQ z$RTYC2B0s*%?3jNyZRc=2|1|J!_*lx4>0YM#ef*o2CtA*s?c* z&>lIGEiI(>lzhwHa6(7qHf%{GbwUm&9!knFr(wj-(sl(1N29dxx}am0y}<-mlCW2; zMc54uwdLB9&;z*@TUwbtkd`{F&z@+y>sh##g)3M%H_W*uy^)qWd#si^XP2b1SKs)* zrOP=o&X=iwmXI@Foa>`a;!L7}{3gi|IZ0=_SYjPrcLd#e1kV0(%{k`-Ift!whLEdh z^y1f+=L9+OpXR~#=e^0MXj}B>tvYAMGHR{n3JK1RaYZ_Pnt{B!a|A5I<(Wawgy}~q zD-b(Ap5_F3yye^@)6Bjy<=}|B^WZ$rQtjL#kMKBqC!SY%OgeA#$H?;4?FG4NtXH$A zRJT7=*>~Fbyt>DJ7@t-0R;hK?iA6MH2hwGqmHL)ES0Bb_mAqBzn>JJv^!Z=+S*dSj z&y{t(Et&JsoQ+$ak>v>Dhw)h@Z1onirACk7E{AhX`QMSGhH>RVy;YIk!9bM zb*&pQ-o&ZHLMy#FnD|IA2m3SumCL<@u9?Rg^ zW3kqrO^`WE9;z9XqOzY#FPA+Qy;Xx_pTt&Y4xuG-HfPoKQ`sAuOVC?2m~(dLxK>D8 zAU#Sgk;y})Zz}nz_TakqM(hFY$yxL07wDDRE4EmB#a3!B^rR6vyOTGcBkgbK16#oH zd(tzoHQhV5rpYT+_E7D`o`oDaAE_T}Az>c9gTZX=6WiK-xYpjJ_hzfsXSD}C0=-%L z5*E@67|hn^Tf! zYkAb#6`Ye}?Q7SrAn1=;MxK3%eUV;wCAn2dtqOY)_9a%3w~~}SaDB%s30ot#W`EC~ zmG$q2wf0BpyR!CoEJ9zGwpD@u{XzX+|5N^|`aD%tl%Fa}V}1UrgjE*Y#TIuS&kFK>5*zd8P|)ovA?S9snVCFzp5oAG;d-y^bGJe2zp_s~7O6d2_EBkz>8Ua&d9bu%lOIdp)nc?` zF*$WTRmpdy?W>*w9m@Z)zg> z`mxGhD?L?ur6$Gx^+fvB$!oPAImv5P_EaUWRi&p&&z1hF?#NnymAC_SRjt2Duhh=5|E)}(s^qoO2dp=%FH(<{KCS*SCC}!J>RqDk zVg006SZjI)p%2m?ovR~ENA@S4L9X=Nj9BycB6c=WPo%BaOn%`Mq<*YfvAvwd-S!}D zPjVLfCL?DO&mwnbY+bq{ZG-h|O+t1fp3M{938}@kYixyfy^b+mP5!)i?5!*WHJF}HjyGJ8!FZUp{ zL~2>>LGGxi@6C|*=hXU<$mYa*V!>>K)E?U_woiLe59qN@`mPmaJun=p-+F#*^X7A; zemLztYlC5ExxLKth>n)wg4j0bw;oEmG4bB9E!mrvqnfn-k-a%?FmeI$-sIZ$*%~d3 zZI88t<2Y5s3$fU?K!e<_OmAAT)zXk=_)6he ziuB~9)mx>Z$C55nJX&>S?~ZE@*XP&K%C`iknS#y`R6F$Kbd5UTY8S39S@!E_xvEim zcgmE5^8wY(G_&KM^XpiLcI2wooRWQAk@l05U#D4YFI;QC6{XqMp&57G2C28F32{?O zTjK0xWg77mwB>9O8j)&-Y{n6Rx}^uQ7jd9o>V>ps3)mHXkUjXn$)jUmRx+g0e`8DG zd?a2>)|_ow7%#F>g>G&xi5rB#(|Iu-32BoZ6+*uVdLOdv`2- zX4)x)*LyjV@_3N~wOk4KK-kq{vrvsYsQTcVs9-Z#!x@Av~j?xxnQ+^%$ zcKSz>Px1dhejQ71U&`Qytk*~7*Gc2hj!0X|^|EZvAEV}^vFm?yY^5h@Q~sjL{>4A? z?<70lvFCx&MsYk$i^P%Vfb@CHA~l0n-%)7o1k-6OI*meWg*e(=Kzb*;lA1-^t|hTs z^dLBH<|wp&MlA%#(0oGWQE07w+j^xIzT;-v2HN>$dtM9Qk>_e;8jIF$u&3(Cv;NJp zJ+F=6XmewvR=uNV!;sqddy;a@*)cX-aNB1seA{&UuKH5vM=f*=&5>tE+8jw6POEF3 zsomZTY1{9JneDZn*}bDq+eVu|pS*?C6wQ%Z_zOubpq=W!TZD- zTN}O=>6YZ#@3r@;EpNYfTcowizOmL>9BXxL^)}e(TK|rljg1z&Y3=+a1V^5={+GrY zUQ50mX-BA+M*H6JFUQcd{Ff0Nd3LONIrUL{q_y{QQub$;vd=#7jz}&46$GvN)bF)D z(qiv~bewuW_Dw*hk>?d`IfkY^Z%=tuY`Io({7Nix$D~&i9CLPD%~7@eu*AEt<*GYf zkhXD-f2~3~;qg{@nIo9U5*;J&K|9Zl7M!|Zq|3Gx557O4~z}Ol(Zsv&DE@;m|gnn_v z%yF~zoOKXkXXMW8KZt#frC9_0JM}JUoc-&6P46l-P94-+q~29(T+%^DwKuJIYFyI3 zjrC3)Q`gk8x;m&eU7y}1E!$Z8lHRFnmD*R>s`_{``1bP)HuhhllIkWT++e1 zdZ%WUwXag+>{TayEbE%~Rnk5+Zt?qCR#)%rZzo-=)V`!&bv3S56IVt%u&&;zUz^gt zx_YOUZLEEp*1HWgE@|Tbp5D1)U0uCPn)tt^cS++m-`?4}&7u9PZSU+KZ@#@N>s_s` zRq9}+-l=J}bg9)Vw|Dw&KWuwv8&|1)sa-3#ah0u}npmlEAFRFGSnpCBm$a`^@6^P) zdRN)rCB1V_$p>riDqFhL_HDksOD&ykT)Dlo1>9Kg)VkEVDK~8U>gru>8&_`iYym4< zx}<~U_U?o0UHvUxY6mxN?`-XATRP`geUSFms6M9Fty24vJz2Ik>$ZB%0IqH6Qrnm8$z@z=Lp#%Uu(G8q+nLG2Od3~dXWHs* ztao*FE$LvgHaBl)rnXN_{9t;QY|f9y&irTfE@@oSvPx?+X`i;`|5d$98duxu)z{u7 z3-dom?>@MlX?tf2r&XD3%cOUy$7e6EKE12k(rI%h9sD5eU2V@U_4xjg-fg~rS7~Ra zw$Hxaru9xO+qjokpPiZ7yVT43_x10RW>vO#o9pHM-)QeD{VJPp?`pj$b^CYr`|7rL z<(97OMXBpu`RDA+4cj}lu0D@S^0Xu^t8DMe{kz&eU8Q%WKD|@FHtyM_eqVjuEzl?_V-fHP|JaLyy>!%Q<1 z8gsOBZXBWB%Q8db zc%@dQ{!A^;1<~8-92_-Hk7apIf;^3WNj;fbtP7)`b7AyzI_BtJuO&m{%!D*2!MO^~ z+R=Nd-({cZ=iDdyIn}#Sv|!Fsa882r`;+%_pJ-<~cfncxV~~!k$jY=u>akoxN*|`Q zfU|F$t78keG&Q(}R zaIXLI*vr%YTp9hGvNE0N**Pb{Hf%i7qgTbg-m2*5T*ba+cvRFc=^0lCm$=zKp0hux z6{J_izMd`Mn&_*Po9Rwk%4RKLKji-GT}zmR)Wf+pUS%Ce>dDk&DLvDZKA7hmK<;Yf zT8=y*dN>b=9?ta~W1mis<@)HcTpvA__T8ppE$Z7m@O|H={?P*odQ|$wew-fAy55y_ z(ZW1%1Fz5Kx)Y7F^Ps;S)-QLxwaq49K?VZ&0#_gRgTDiST zZQthgPW`H{rAzvl+Ph6@Uu{dL-s!#ESnq7t>b7*XE#N5xCO>3OmT36%L-qg}1 zz57S)oo!rQy{px={o}Y^(!~1ouKt!TX<}tdm)gF6)ZV3*E@_`5bg8{t|Gvj^Q+k(L zy~_5k{+7KJ82Goo!rQ zJF|Yh(^IJ?ZLZa;YhkYE=#5*tWRd=R?97i!?>5)Jb5@GnMP)C~UR$}BCktNL*Q?*! ztlPh8qKWlAP z_U{~JudlsJcBb}Z-JV^tGwt_nuGO=bx2gV}R%oSdS?=rE@7uJUxnZkUUwfx!)z`mM z@9OK{rJh~ta#Ozt;)LA=BE5Awfa@|vD8|dEAXc{PpsCjVh?UZ z3$wDl+t{z-=y}uj92qt^=InCtZeT#<))k*-=_R3 zN#n|GpFO_XR)pofUHuxDJT3L{yDv?)wraCWxdm?tZeC$ zZ?mpPWn+y?9?s;?+_-fJx@&#bSd+qjKO)@E4;_ry-zcpSmjt*%#7O{~w(tn_Esgb zZd&hb#mZv}8+uwcZEdE}gxdD5yn5Zn+PC2d!sa}g^;w(swRB1EQhR5cRrapfGFIwc zc{HK2)vMdy*}vO(G+|@C+q^$B_3x4=GxhQ|98;*z+N{5q*CjZv(Is>x?ndYuI)^TS zv5~mliLD-457OO3$IyxNUmOPs9oXuT{gw1zvi5BC$l8VW$iI>E*X-~3fO;Z(vfY;4 z?#On;Z9?179qh6f`&x%KqyyBy>ZzB5n~{hHlwAab)LRLsj?@SNL=G$Lvkc z?a6f}hV8=kT*1|Wro=I-s=&8HLkU?5)!_|}?UFqkN2#9W+#hAVIICwE%Q?NXv79ZT z+MDy83sN0eWi~VlKj!#nvp-~SaBgpo?-j;yMsG%p#zg5imh4kC3Of=Shvzu{$5|ha z>>Ym3d4APtTh8gv@%Cz8?t$55nj)J&+&aZw@>&9InQT5 z$(n`cVL&!IY>V8MtEh)HVS7T8@B({(0?RTgj1B`i#&1(@pEU{F5t;_uS7p=C4B3pM zxiD8}9qZ5!*)Q}*_74M)1H!=2IeVS|-Z}eq_8a7Hvfm*sn zl`k-6`9k*7?3e86oNYn=ps+35FUAqgpVDJ~G5c8@2YoS)iT;fCQ|@XNzjh#UQ1qaV z45Pwoa`d-K*{qCX(9WJ2gr<)OBg6jLNRDviV@vdXn=m4*A%A~b_!ZDkaQEKKLfY1DzP(kb(^MaT(ThECb5*=tzvuVueL z{(`&eMCc5|uyq(3cIMpaSoBLdYe^ix-X$9nwhp_ncW3I}C5&1xjw9DI$lrxp*70lm z@I$H39iet6(=h6M$DkL*F=##D!>QdDVT)PIE49i#%jo;8>{R4uk@{**<(e~)gTs(; z8uHZav}~&|IDCd9W@V?7J`K5L*eZOQ?b+F3HD;&+tjOk(LP?hZ*c0ukEW*}#TnaG)87IIdYjhr2JMHV@>efGWVA!ZFcls$}m znE&2B`&RaC?Pz&?E5}@?#aGSxHr2! zjH0f%oxMK{53}dq>|w%JvM&V5(J!#~_V5sUzLGse_$uz_$uHEXCklza54ju9zg=dk^h94t4vehYnIy{4XCYb(F=$N<9JLEqO?Fr9?&g|`!wCOCOe69_9VS0TeoE22;U61WVaIE!qaG* z-NEr+K)x1!5k3`;$&SrF#j(d^pWzCh4mWc~+w4yE-hq5IycSO6sAIDe3CCrh<(SWe zmU%0Fc}v2J;S7$sGy5d>{ipEBa9s8=(kBvslIQSlaQ4P$k)I8#LYwSnuG}WOiTF&; zIs^Gics1NePMd5sN39AcaFzFvpCoRPx6EHez8HRn{8@M@oW=2HW@lwT53ht9vKu*T zf6iJRj^~^|BTpc1p0~(f3TJ08ho2*V&Nt+EF6wJJRE^MA{>c4 zG8~0GDjbbGIvf*PWuMP3ppSP!b|Lb@>>}hv*~Q3W5aRCHeX4%={oX{*gC!C9Hnw^C_ zH=Kt&FPx7&KYSkf`EUX9tZ;T{o?Q?wL|zy!LS7UuMqV5)L0%FrMP3>%LtYjxM_wMT zKwiQBlT5w zk5$Ac(C6ua?7_bM+0!dKo}3fH8n$|6pCEmFSj$$g?Bk?A5!SKQi>KM0?c=cEyYn2o zvwbY-qmQNRsyqWq8?ljI?#98}Ln$P6OvpC}#YOuqp2X5f38?lv+MW?2QDa2Q^ z{~9c)spL!}98LXnHRbSZYQC$(^_+DB_0$n)=ydiUjXWCNJcm+xCGu?I>)3leb=HyS z@6PN$DqKtYI%;wi=(f>D%&|+!SutGLe9*tSoh6HgN^4^N===V8~L z$8pb~FPDX9*nc^;?&sO_IN=HE&6%8e7n*fRxC_m?6!{GCV;u81cI^ekUqt&Z4qxP` zOTwe%Jcf;XA@P^c&5Od9*ne?&ggWg)Y}|{9A0hQ9R^dhH@|QX4qVRq4AE6g<9`}}0 z0|cz_-LbnmamTwOI}_i{85d#+U&65u6TXjadMR5E5gx|&yo{~yQRiQVyp-JUlKvj@ z3gUM;^Mdd$*5`%Ddx-zP_Rcy^uj2au&+Kk?Bb$}T#*^KR3nA{dQ36De7A+1zi-zD5 z+}$;JfI_v+y1`%G3U;md!Kpky)$#> zoHKLI=VRz6(Azow6Yg+!_$TM*gpVls7^}n`93SGh4`X{c8(#D;?m9bsNcl(D63&80 zeae-y!apea5X-`y9RJ9bGqEj z|GOytJM!pV(7QSQg)4<<_;+*uF7!Rf!YCaoWyL}mwfhdU=Akw1^c;kVrXyD){j)`PBx%={F06=I(OV;JdtDSH27-1%Gd zlcy**dds*_&AsbF*G1AE8;C0ue$MZTa*u`=unIiNuO16ET$>B6=J*S)7h!d2mm7;5 z{{na1Kv@x1l6I8-hLT61FJeWwkt;>mKH72ZVM=}jeM#E_C8LnLZ{+Gj;bk<7hbVs- zi$XiDJs4g=2YHb4hr$EluV^I?Q1W27KfH?ec0VN#gyXQY)S^$<@Knd6O`EUf`R?PM z`@;$726Ldtb3B$ikINm4<)k}W^&E7o6VbxwpmF!$+A-KtdZ1z5#M3m%-Hc|?BzH@= z8G38D1$tY!75Yn_vkL3P5VWviSSqTpYz%{rz{+7XoDtz9^!VA(*=wj84!4KfsAcEeNsQf{8NrLl&kC2IxA)@iqp;!h3i`b+LSye8j)L~VwsRzQnLgnN z=#l8{{X*YxIP?fK_Wq$?I1G9?8v6ijAPb>~p{uWkCE-x$LiB_?_}Ajxo#77X?fiRj z?pNVX@^^(_L4S=j-WD6kKg)!@P#lEu#rQ4#h?}6oKN6NLgx<0vxG3>7JMOb$B;`%nE zZLtFFMEM$|2eI$W=gQWkZP2{ulQX*9gU|;UMKj4gfHh|U*R~>UjRj``xh<`@^>+^@) zaS!w!G^Y2t^8@H>SVG=s6x100 zd(`^5e{Ym}ho96z2UTp-ccF-zp=dH&bkj5fF{Fq!W7=tGlzTj7_ts71HS$@le z$lZZNG=9okqj~?4@`4b;=v*Zwt>x2*gyUyb{g(&yj*RCKU zl#y4{2eS-nT)qwkM$hYjO@LU@1;*%WOLRe^D1TT$K`{do|%$^v5v{)_9cqq)A0 zKHfaHl;>=odx0lzo_i7fx;dKZi_n+Rf19Jvz6|{t0{e(me$|`yO0mm&Fy>sn@{aC|&RW{caac>O zHME%{wub+3ozZ`)&J7^f6)M(&qq-~9RX?9zst=bVQ>s^&ZMf4U|L4@xPj0y1; zhLGCRFSXk{PTJE`wJFDWMEZEW&@L)B6qgIyZ#zz}~u~W-vDe)+bxLQgd(vo3MDy47fKWGnYK~L0v zQ^#3z`lA*mduKCxr*=5|Xj5ir?W6YK5@u*E#Ln8qalUQ>)sF7$EOk|44U*^_qHxS4 z7ocl!>`5*cN0jaM-`!p#X)RGZY_-O;moXzNVtbXZu)QWkKTX@KP9%*;1+18q;3lNEkcZ9%3Xzqlw#d3Q0y6w?`F`jQ?p*YeFib zk7(;ECK(m9CAn{k-=dtY4`f1dX^7u4nYx?OYn|ikVvn5^`*1>W5wXRdpHN(kF6-KK zi#RG0eoHAW;@sdmviL2IoiU_k<9s@^xz1}`S;yeY@LRGtpQ5-p#)p#7b~tMbUr@hs z?Nj6yxw~tk?cgSI{d)YC_VAj7+@gI&td`DDF1 zs^hdVe6=y-bk+H)95oxKa?~_h<)H;%^3`m#ig>glzG}}Df5V*)MwT1{hq6bzb8#%a z&_3=8q6o3>xv*!Brx!XV?3oi{pPUGF#MmdLjwjderH(NBq|`kr_C~3@SnQKhN2K-BYH%N`FXrGiCDbYS@lyql!d#3p{94Ac~MM~0+rDlvI`G%vb zIipU#;n-`z$TKRnqp_5c+L3&R$UPjlqGic99M4kasVY)s9PJg1d!=u=Kqd1=Tk_&+ zwa!&nw~u#NR>eR1PeybWZOfQJvtLL~ZPePD_#J(#ChbbsvSX4dZK*Z*3Q9k>eDHEtySu8-EGmPBsNLS8NE;H7<^NMnr<6k-6 zaod6~sf4y{9qHHB)I8Sa?+Urw+WcJ+)Y_Elnn111nv5I&T|dir@jlV8O!uYVWdD?|G`9X#eV*_8 ze&?^6*oWE2OCJ~Cv6}Z)udZe+uHIT9ViffW)Vw?9Xu0;}e z#;>?GX|3F>_!VbSvUYBE{ED+F5lzOgIEQ4+7A2LrBqPB4Ro5YvLCYvzH-7VVDPITv z*Mjqbv2_Nbm^6ra-Vrl|B$A!uW+-V0eANCkj3mCD z{c1RA7`)jLJc2YFek`x9uI|lQjy4nXu@85#mzN~cr2L{UsShnK=hG(Dm!2T!(@ND3 zj<3B+^x7uWC+`!{b^vdq?LMTCnM;W+KROC*;}qc%mJ-r+KubSKp`hGS2PfMy8wl(xWEv#bLy02WztMW>B zRts#e4M;|~vb}yx(o@Cu`VmQgYTIjllK$1U*LozQwc1j~UDgxZ_A;iI(YkD}xg^(+ zY_B=7z2?L=nnQ^(!EB@1v5jVv6Ai)EnHAe*R&1A9oEtmL7IDN>LMyn#k<<$6h;f9q zhB}fQd2OJMFh^uts3XsjS_O4PI)d3nOPawqvn{5Prt>Xri>ah(d|lgO3P~>kEtGNy z?acB6`G@>Mz9D{M9n@Bs2vr8Q734kDw6I)A&QwFo%bDa`we$!%*0}inJWp-NK9tMbdf^g(4Rx#?*7rgD`0RT)azX#`XWTS;j+V`Ct6Am_sv z8>>T=e}<78&Nxu!5z7)(%<63k>jj@q?Y82Z?EhQm5;AMvX$(i)A?5VR_G%!jc=$&hB%T_`Kr~> z>exP_Pm280jW)=zfD#|KJ#48-&^oBI;UrRLTEek40cxAb$0v}~gdB^?wd^qxvMQ= zf6B*)kZc7x`(V-#TF7~H5NR+i<@~xjX%Ow`yens4oz``3c155Wv>BxXC|Ql3AWwHi zpafb%X+KK(({Gx@-XoXqLrWAvizrpkDTEesp4kZG^1VpC>5=mCAKL4O_L2+!FuuN@ z@g>(_%{_9JipXc=9c|zWu5_jKEp6O#3DL^ci>u%V%9?{ngW*DQD*1jDyn)>^@B=Mm ztc`Q-+|Ul*P{Fx6xb`G1NzOEh+bNwSE~xC{T&2y;`A3BCK2T?#a`;F;sB=y^^$mbl zaO}mg_m`a2S&&^~aNG89;yS1{COPgDXjz=`#1-#J-aRX2%;{@G-PclvBrqG=gQHxs zSLBatLFM=@;r?1ww3xJHhL{f3CX%d2Et&VVB)JU5o~rLbz|>PH_nag-;JF`p6kKcja@^|L3_kfF)foFR76a% zFZbl?9_$b5N^URsa6-(iX0K2Q=X*ovvoC1}?p#2AZ|1q}$=9$WX&%&=3v%!UP(5~v zN&7O@*J1w9o2!VVOsKz>lHre_ zdS_`p)|R{pN9P+$^w%mRZ3xvztB|xYbYt#v9_o&SkSweP95bz6{B~^z>h|i|N~Bs_ zwH=f&LuonCqEJk^>tv$9*V`KWjw`>%o*{N#;FvV$F7e!+8)&^i?@&q*qtA24TZkht zP`mO;F1BATer3Ef<9jIK_}|^)OxlCzb7U8il60g@q%2VwM|~mnX`^>t*OBGC?ELFk zD5P(fL4D8Oyj_l50cCy(Z6kh*VyJH`mRVX^)QY0apxvnjRJo!cjt?#V>eM|sb|<+y z<(yv|&y)SLCZ1PAYxo~!TmKDzVUAkV3(5K4>D&8E>H$7kAE+9jxnf-S)vmF&%T-sWHG;HSU@OQ&E1_x4KvcyJyqmoN&uN}iL`E(1@`i5Q z+aB7U>(%_K3R=Z^O>ET~N~-yO6`Xg6x(;Y7_9D6WMSj);D(CZS+p6xbC?h`gMnGL*a$RTyX()VKX?`?ZcOW}|?Gx@3Zpn_}mK@y;Tm~(pUiSn`wW!=p z>c?JV@4JUwf9TyDZ>QuAxV>v!V#%w!YHhifI|e}S;dmSO+|HaZl56+zzoVh9N4bZ1 z0DGcaa>pdDs?%zJaaZwZs54DnoO|lHs%CpXXOm;;WcEkiAN%30P<75R z-IG(;|6NM?RL-WbN4%8tY2?*=-GO-{CBI}2c!=}q?6-ahe}hs=e*wJ#ZX#ci!^p3U z)g{l_G;-1X;7-P0mPZ*UrIg>az|Y`nsQv~m@NBpis)s`hJSVP$>Os+h`+g3el=~h` zIsmFq*1;rw&i3Joo|gMS_u*VlC@Q-V7UYdaOP1pr$8~G=7ptkiL|Oy-BF7hai|Nqm zoV^hDpu6XI4R#r;ySv+1Dthr!uD-zhu{Zx>>=EaJ6qCfL3)@BR?vCWO*-8Bf_dbs= z!Xwb%@XL8{apxF!Z@N=?ZK(6`67G4PS!Xk@xjS<$_H2vrxT*=48)xX%iq|(_@`*#m}^SE!ldEBKgFS?qN#hf)Kw>a)SpM!@$ zbM9=0U%~I8PjPG(Jr$baeeg7Sy%3sl*B_wGIWEjOU*(_+@f$E+@wudRpw3JB63oTV z;B9I@o2&X9yv0$Ef_0(JTKW}8*Q0gLCvArJ!rR<;0lDp=&d_=eY=*ak`{vIiorRx( z=+}A??0~1lWB3uAL3#)J4tHD>B>?>jcErEpF-lLvOW`r-W1L?crH6~7JfYXYPH@HF zalL8ue`p%LBbxI5Pf*f~V^gl_dD0ZRh+pplC)58o(DsKw4~e{OK4&HD?mhwPF7FaN zVorkU8B@ZqPk}b&cs$1w*oj_3t^jFfH|TCiC{34l>TY%Cn&aTB?zq-Bdk^UD)a6WcIMkirP4FYR1bP|ACU~n{2EBq~6Russ zOreZbMA{X)h_j-&^IR?U67qV4S6A!d{nOai-ggN3X3$;vr!*g`uR7~E1Nq-+CBWIp z8OQIa)xnh-JOiPw?X)Df8?-q`<;C6TlcmrK((cd}9Od4-!%NGddoVAQLCeTHM8UCu@zJ)Up`y|m)2AKE|UHpzvB37O7t#n&+%?%m3C0& zjk`&|hDYDYJ$egQL8~a$e|b-44)>mDIqwTM)ocWc(L-z{iOStW0Vtza;1iOsFqT9*3?4v;ogfnlxX$O-ivf=oUQch z9?Vrexc7>)*n@EAo5(w_JqXq3`$o$4igVdRQ2oF4aor2PdIQwG5bk@>?&%(hsb6xo zgk5QD7DuCzm*k(@#5rXu)EQx9oCW4nlVd}V*7>Asq59L#CtU~CcXvMN=TQB2<(WHt z$&;0ccVKRs$$yU`Y4x2+P7bEUaxNU&XbH37&d$9rLG?CwCVUyHN4j(73tW2``Xa|y zDA8Yi1V*Y*>!%AuJ$01vTcv0@5?k zXW-TgNY6r_%toeb44dtcJ2&{L_wcpUq}XOD*}XKV&lUpk1~ z=FrVK+YerQ1k`96`;m@<8hv9w(lJnDcI-zw4tgB*D6wn;RXRG5v<~vj;auAvu6#ID zzvul)mqGP=-k)>@^a`#k^Q;5Cg!2PxnQ zo45Lj@7{`}g~z8-|HC&TJ{P4hHu`;4Q%W`F)FcYTw=OTgcnkMtw_XL#lgTDg zZQ-mB*bZ6WNc}bS8GB0Bm+V1VAG2p=ea{}}3QW?IwFTHeo5#NMKlxwD!kAW7(mIQF z#tv|G*Ivd%>1GVl%~)n2Z7|v)JHX%TS6*Dl>BL;+N>2VNj8?~NttWp)rjD81wIHRl z{M8vPli8Y4{z^?+SJGnHmD$nt8f8G%$B;?Vx|4f^T)R;!bOp_|8zYLP)hc%hxMt-l zj%zut?zp0*M5V>j6&=@gTkMJ>OqfiWiPD* zX)DqXpeL=F)`46R8bC`YTTU;oDFeGQq|Mef9#?u?^HFwpl}L-O>p-psxh|yq?21ue z&eMufb+yl%Y^d$yGj`y)TuD`rYtOT2W$}sH@n70qe3q*C&+a189^=2cpG*sl|IjA( zPW!5s8~;g5m=+x+`bwTp8;|n6HlAelair(?qMhS7DWip4oz()Rm8L6s_j)REYq=R0 zpJH5mF88-Jr7!us_O<5FrW_~4=dzczAn(_Ax18(rKGDSZq{+);B6n)vaD+}G6+nHu zN%46n@fCCAi}+0)wb-*t$xY#0D|9L6Q@K77I+62fvG+}fx|5_oS7wl=(%yCSk(p3; zkJOP{3#x2rf7P>7Dbe1Ud4JB}SF@;L2GkbTH&l7j{gktLj?PefP5zGaEXa^9{+1 zJg!&iMkMVo?gH2tsy)WOxiM)ysJjL>;SP~{Y{yNgw=>k81)EUs`cVBGwcPv|2}K*u zPpD->sFs|cP={C{Mt0tuYs8SC{*9prGgpYKAQ^GO|`u3yZj#-Bpf^yiayMFQWQ+}_l+JCdrt&kIOetn_r= zhqM6saCOf1C27-|Pi^}{_d~*)PwqhI0mzT@$sNQmwLR=j?qGhoH+uO3a)5l=B79)w!~eTK0qLBfOAb9td?e#zJxjK=%o1=R*}5;YzJ)dq4hwHyaMj`LIa--gM)^3O8qb6pm*WDc+L2bU3;Er-&~u_jq@C;{N-jiC zIWOuwLpUzt?kc4E^T}Nby#zhrd~%mVFGCN|Ds~0Gxd3`TrB{-_0{v3E*HzSX5p)R0 zt2j5VlXK-_et!vc5j8I+w+QNdv6vb!g=!tTnp!T0Ue5V7yx&`}+5lwC* z-HHun7-zSWZo^u0Gqc{E&^xgA+)VB+s22O1$=wY#o}8BOd!R;!(;lwH#`tiq0pCk4 zw?c39uQvSOk$#H?Je=P@&hH<9 zYM+0coZ7K#)lbA({t0SqP2T7#Pf#Oq|ETd1s20@UQ_Ew}$2fnIy!Hg`qEAuB@1Vcq z{Ap@?9Qrut&v0KW><~|o`xEq!SS+-l{+aYAEEd|6|3dmRRuI?7pX2vW zLPt>7bEK!BPjbf+YOI86VO~PLt)SYRmr&!gQ0>^yL$$jYg=Hzf`7=~&_)>DuW8-;_ z+>1~xKqEQ6#NCxxftHYa1^P19n>Z*jgKJW&0y$n@$dV?BYfoj)(lUiPdzRLMq{N^?2Yn;DL9e;!V zjq`V?^L6O!oEw3)f|xPHJ|KR~8|2=H{+*~ZZ;<;3zkCDw2In90%QvBKa{duDyaUz7 z{t>yip>J{RBc%3GM8r{w`NTz`ip{5AButz9g4X2Z@lmWcQqju;pJbz zSuv>zzW#-rm5_?@_{Z-7TF7}b?!yxv+6=${A|e2kLR%0Wp@>{de#v!cOJXDxb1Wwr zqql^!3hHSJZOT~%sT}HFjY?{432nx)k{XFEK#jx}pvD%^mPT8k79uc^Dv82e&RJ_x zE21-3aMp&@nwS%K=0Phsukv@qp-_UZ3a;^1ab8VK3jH42an%^mRh+dC(Z_=lBSg33 ztV2+5=)f6q8z^s2MCnT6badkXDxsB}cjo_ELECWbOs*60KG-)4ZA)1fQfK0KsF!r* zmwlieIdm%s8i@OK91VzpstPTH#?c6){yiC zHHT^B)hSD(rcg?54diD%qV#~8$uHCr)Cgu$R~M+eQq>?PA=$fYW=)cMgnMV!B57|n zX3W}AFPKFw(~<0_bFPjs18TfuEz|BopGlo_q3Q)Qqed{3+1hEYS=kQ(QbS8Gs%=mK4rvW=i>5XN{> zUr>WE)`~iU_Ro49VN>c-J5W#f3G%wp@6{SM64asfA?>B;O$oW>} zHbj2knA|o{R~C#UldmakOMPkzt8r9oaJ^N%U>-H9DTrh}kGj+#)MZ>36Y{$_M!Q1Q5$1iVBN*+-7)P0= zkaPsK1vP~opjw&L6x0jU8s?LBhN>^jC%FqreR=PwDeV2FcA&nXj<6ea7p^ZLuXdoO zun%c>sG7sRl&Br3HS9;)7g>HUa{KdNY6-?iI)GnxM5f<6>I-|5OPazVl(>4C^o67s z?8EuOs5LC4-b0bojfr#^N%?@~5ob{1 zT7>JlXHuhDLedx10?s0x3_Y3Bv#CqnLA~G{(y7o>DLt3pw?~#g{YxF;JfwBCf(xOp zg{UK3$nVcUT0fKA#ZcEg)EX8+FNUf+Tmsd?uMTnv=^Utf#HCRSxHRfV>ImmiqGoX^ zsXem1+QDTcwFdQq%Sq}EY6n-4)EX9Xb|p#OL5)DI;S%T~O4S$IA-Ss?Tm!ut3H?%X zKckjQp_fMaU#;Ofet$XiGD@!}uP&gz@N?1?&?}-|Fod#SL`~!unK$_xCv=}Xw(bT5pE&fjI@3O_1^|n z7q}s60XLAllUi+la zaLrd;;a2|f9_qavsuplB^d97ObpiE)dy&`G7w#vi5vV~tK)N59T}|OZ^b56vUsL)J zzif-Neh<0dK-CEDi5h{r!=t367u<`~es9zc)C)2lA!!E>aQ--Tsu3jZAn65aG*3i5 z>j`RaOWr*^`P#wnqjvE7s3AN_y^kWJt0z1~jgLVe zP94ED-J}=1K<t^CzQXz2Q4e}2>Sgax zduwEOwT5@7{Z**?!n;vZc$a*_XCNXP|DblDF7S71c@vs6g}2CkK&@{ z=ujU*)fC<#rxx%IRGs0Is0(~T$;Zg!?{WSwYIzT;Uhpq+O8)PY`;0n2fT{s~M(%y+ z`&|1x>T91zt>JV2qZK9U4r&JGk~0F@ zXXpx_MeX2o^eT0MLZovwfnumK|K~*fDhX-_O`#=7>gov1&ZNCe^4_}7cin&1yR$A$+hHvijm;e1$3zECqLpPGLeJ3=q8tU$VJPsZWbPRF-YALS{-JwYE(C(opv_)C{P>1SEt=-6v;h*|ZOLwSxUq5oS#f0O$bDM^ejb(A78}MNO+i$L0n>SEqCo8W%oE)LRA} z%yA6$4u%d6qr+J8W1vGhj^mD&xp7gG8W;7fap-q_C>hO_@!T^OT%2JXC!iVOx5j@D zBR`DN2_(GOqHZ-2jjJd5aU3V|+i^sL9l^bmNE4tF&>icdhE*3Pa;&4?F~or#!@YH+ ziNt$VyPV9^k03vS-%KX4vc`1~e7L`kD9@A8M5m%#_Jz7OHI?)J(2-o3%6pH5;sZx~ zXEnQNQL~#yY}oGP@wB6SJT*-tP2ru@_|zfYXR8jVp84Ms$81IMcJxclBG6$KfLAyg z8^$p!qkkA3Yb<>`KaSb=6K_ZDSPk=sIA*I7$E-2&k-qP^b49e9am=P+<9ij5qY>aA~OtB%;c-3mR;uvQ3!_o9P z`>DNgG(FH>Y(E@B542y~567Zc+TZm$8AlIv7pVPkJo^3+@`IxdQ~#8S^gp9&*bk+X zcn|$kr0(H$cdXRiyzY*by06zBD0RQC{ZOj!hCNWKKZN~Is#k=&nx*dcbf>aZZeec( zXO3jtGWTM*S4QkWeVX)NDuj0DSVPWeT(uml$-!?pE26)<2c;XSB#wk8afFmGKHMkb zm?^=2=Ps7cq~=h)1C!TaN6s@p!pyrc?T^vF(A`Wep>hvLav3ALU8M35$GlYTAuo{1 zL);lC&uGIDJ3DoBjU&Bl9OLe6=}bxTL$bbZv2Oj4vY2Ky)Z8uduZEG$YUBUZ#(%Em zo|^dd`c?Ub^rX^z%71sKqI(H_3O%W6p|#xSS1{s{-#JC@@!Pqp(r;y)B6pvqC`Lv| zat~wj(<`Ls`LuePwukC>Ix;@VNXm_*;hQSC=p*X)m_jnL-WbY_T-K33WaKggctD`DVs1Ge%h@rA8{Nq)!itZEOTHBb8M^ zE4VhEyfOTS@>RQWO!3Of>2pSc)n3t!zG%EM*EHpz#xb*{9fA6y_NT-iW;|T`#0;oo z)SWr@LapHS5zMC3UmVlR#x9#0+sN2uQyCe4{i(Er7Thd$nbNWC(vL6g-ij2#%=YL@ ztGFhUqLw)_2GMq|jTFYwVaxTQ{gi`?7)L#!J-KF^>Q&e)juItiqm`BO?R~!~BuA~^ zN+~bJD{Dy$7|YCesNj1$hr0V|a(w43f|)VPY!RcF$@^OH9JX2y?rOzX_x)TInG~PW zcxApB_?49Ue669jezu3pwUiXQ%%?P7nQJVr&-iAJFyGCH4ZhP@(zy6V?1_E3Di_G2 zmW}4jUKrQ4xSHZ4)kiI}-IgD_EJauv#g}(IIYlsAUhFa>|SMkxZEw?u+Fd6=D%2H z@|Ctu>v2zYea-HG{&scd*XFY|d|IQ|HGIymzI%G>w42>8vFgwH-PY-sY}itIA!M!N z`=(v}wvE&qG2yw7LPnd(eW`}K9Myp0@Hj?scRy5!ecgv;c`p)RBMhH);H9PM$A)a3Ev zh%lxUC=z_b5~xp=VxlLDg1#Zf;8Y&<_xhXY8DgBw`pD>h6TN0qZ#H6;{}6a4{Y}6T zjHCbSo-=zwd%91&yyx@@>z~%W>h=epQ%}?MoIYXw(=Pux{r>e&+weK%e)1{5r1d)9 z{F2#MP2bah%a0qHeNVqi{S#*2b5)+xFPXf1d{^tuctpeJ%x`y}&35;H}eb4XeIaky_ z^V>aZamSG(sD3m#vpe3uz5m{-)}vpa{)Bq?`7PuIjrAw=US}_VnSN8mTNppa`s5O+ zKB-(hc@XL^ldc+*#y7T}mEDu#&{%`9TJ%b+kI#~7TeW(!=dreL@;v&_Bo3$_jWd9) zs-K|}nPXi}l)Me?^NwY?i&B8RRu4eOvQcH^%W^w;YU&sI}x)#q&ZC7m1mzTfV9Hm1(}=WI+HHKxw|@42Ej`s(*| zK6Ng$@7TNQzkq#dMbEjS{<-q!)Phyt=U4QctJ;@V^ql#9epTN+|9dv3jaEK3l^vAQ zb5Q5xq+uz&D@n*hm2b50$jRga+I*B+lSiq%UyGT%vVu`qOy20v#)2;4nBqY@Yqz34 zzlnNV(zT4b%5{DpI^rLuZUWc&#K?wb<8Hz1NU%HFPsyt0PTN_~P7a-gxTzwP&@29~vlU+b~m%5^| zYjCw>SIU11M!WX$-6+`=EcWr_b`Sa|>>l((*dw?uvIqIyK{R)jX78{I$327g`aQY2 z2T1g;wd_pEo*<^X3vWL6j>_#6^g!5&t2=|d?yAUML3{XK+%*!Ede=-2 za3y4)NEdLv1NZC*b@i|}xa$M4|1Sux9UcVw`u3FX0Ck;l9(4OKFSwG?m#ckp2Zw_~ z-`sYT%nREE*C;m%dIM|->bg`Pf(^-SAPzg%HV*m?Y!LKI-T)MKybdVY7+iKe2KrH7 z-`v(gkBhCTZMy&pxtdxi@CfX52L= zwSpj>ZFi9Qi?!nUNj&}}##$z45jN0NHr5iu7`Z~Y_YhIzSl!kWaQj(Sng3`YdlZ;uE)Slv5e#*5qpu2KBI=I4jH1~GJ$Kj{B8Q~bp zy5SiyBTNrQD4G$D<-9s~ELXbWE3tEKIvDeMOPtP8s-MA$l$;Sx4ElVW7`n64b6Rjm z|7qcLj;989m!BH+9zHdk#__n|>fmwIO(gTM6Lp>vP7PJLQ%G%dCj{4IPoSO?!|}oO z!sEkn9FM2`gm5zVw#}VPYLh!DxbOHR%D{9AMpK$fZPVC4r`LHMB~wABm-C$+PU1K@ zh=o0wt94+~%OlU?dMoza>E|(ptCK?oWtCvipGB^mqx2&1>dT;V-V4J;VN%flV-mlb z686OxWKw9EyC7T$y^#A#$%D1Xl}Vumd1a>a!v&!^RD0NY;r!4ncWyWjdLE?{f{~IY z1S8u{;8znv)7&}XTv+UjIgmmFZi+CIW81)wMlLa&ZcV)N=dUd!GdKGs(N8Www*MzIX67tXCnKFcZsCu{$3C~l$BzJANhMe9j z;2kKJFo{yd^{lZb~eC;3fVUhM{AL`G-wcMc(%Ybl3u2;|>r8j$C^=BCX9l-un zBVzS}_F|{(iCoohr4PGf^^RW+x*EGvPl&r?PoP{M_|tMd!>PF*?6^IZT#s-(SM_)~ zE;o?;Kz6w5Iny25ot?PX@dPjAuH#vj;_Y$@{(8pAl6DK#(Av-~TpwOw|NHg9efHP$ zix=3Nu7~cMoc)h8xkw%MQ9)2=VCG0*4O_Pgup>)!f5;QewE-i1%I z6aF>!`M*Z_Q|yg@75XaYPqKsluh748eirxD1pQ^I!|y47GWyHZgtOUQ+%;U3b0_je zlywbHu;=|1JP}^OgW8 zfBm%e3fAxYJ?MMv->;j2L;W^NjD%RoZhs>Zv>&Tjszb9(+>ozn+c@1*i@J>@^g=cpO``>!K^ zJzhyoL$mNRO0J8(OC{l2N{nStg0FynOeM%X&iLCwm2;F0l!MlRI`1nVNuB+bq@>2H z-BIZTnQKR+mz_vIMt+<_ExSgkW9P6F^3Tqs4Uju_MpoLEv?21Q63b7yXV;rTU!if;2Ji0uk+YN_)`>F0IzicC9ZJ>>>mhyYhLp4} z$GObKJ41Ko+WO3`yCWa1$5ApktH`JZGnvA+&zc;=ORHFV{|Qku{+X`{-LwE zItLkU3uGtdy)BT6CsD(XqP+B@C^0GHZHa`r4RYj3UL>t?PJ>4WcBq0r&qHnbt@%8zYVxw%eA@^*69IR}m#oV8kPQbTzqvc|c*;*e zo>QVe4!L;B;hv+BDcx~7mh&T_V>qfg zoq}Z98#)dd;V9&zu^dlAR__h%jSSk8A z2S?@FGm(FcoTKb>G*a-H$kEEUXCe!qfxKKz*%?vhJ{@{G^0E@sNytt5zbdbvhO~Yf z@^U-Ql&VifGEA~{hbT8Hd7pz{$w*|35u_84)|ECpM#)oo{oE+QpO5^ev@x7}Pe5i@ zMpc489~o~r^2e|!xeOzB96E&Zt#Pz2z(YoMHIuMo@3=FdAte=5D3RD=Bw2?Tln~Wz=P^e?=pn>-r+hI|qk9prqvU#IO>IX%qvSdyU~QY% zQi3#0otHDWcEDrpT4b^g$o|UI+I_A?hfwy`W^@gD#?|39w2~$qf5x5HVy7uWmVA}t zYs}ysDZLIkp<}oyN)9)XzYZNoFHG%UuOeL}Nu!E8ZX~ZPq4aWNlu2$Ne}jt51Ibs3?%61_J&RQKM`Vvy zNFaZp{8=QgR>&JqA+vn~eVXGlNXYL(-{p=R|NROyaD0yPXP`!xc`{0vPez&3h`^uV zgZc_`?91G%f2)z=myn)Af~ll_Wf~wYc0X@uzF@DLJa5%gh> zzeb`fftGNeakPuVgHckwn{p*}y+ZG%8JY#-a2JOANd?dcII1ZWKnsw8@8O=i(Fc^4 z)f56WM`^u{Gp$d%wyllRo}8?uS$tmmxfaiKwSZ%?klN2(-%hqqZIW78>#ush_oTJ+ zWKXUCukpoR0qt+*EmvYZ#)ZR+29#Ee|)Y1BCUW=(S zv*>Qh+RnhDM%H3&6+dz&U#uFb+_`s6l2K&bOTQMWE3_-6Ycp?lhIZzB7V~W~%@vmpZ=oe{7Z_W9T`2B{&Z#jf=u~S^#8%j!upGImmPU~>KZ%e2vXc^+C-+Tl~+|L%|M$#V5 zp|;K_IDRu|GtNiTuS=lL0;5TKF4*hGki-DBU%T5}^iO%baf8HBk&BNf85u}EJ%MCw zQTgRW(gY;I9Jz0fo9ZfNfBsGMR3o_>=T+QPSH)H%iJt1}>_AdNPfdua&G>dAs4fpT zHA74-<*SLHx;)&}3^BEwuO@=(H^oiO5L4a7?~eVI;if9Xi7sX&R&B8&JQ{IT=}ipP zgr4fiaO5|{O*Ot%hMsC9-|6)2Zcx!vXOMR^)Wm*YkDF>7UPpstWG3TAA2`t}SB#q~ zVroK9T@~C^+bcs)wY}!j2gONkO6eSWV{@q1)H&o5da5y3UHKC&ttC_oZHAkwTqcsL z=&9OzMH&_@Ra{{ah(${ke^_K<(Ne`F7O_~gRPl;MG8QdW9AgoVMN1XmSma~TQpG(M z5m~fU@sLGI7A;krWWTvMshv2_a8r#-C6ekC+Q?QALv=E3B@XkX*b0mRatSw86z3XR zxR!I#oone8-N}jf+?{?R@^ivX6&boGy`~rEB1Vgt+M8U$O%+vI#MHi=XSk^%re^4= z`gVw(svf0ZPC`sg=&2cQs%uagdaCPGVyOOrn<{7j0XMaGIG_=8G5RDwS-kiPgMh0F>b1usQD2IL{C*hToH!qcZ-`k7ztgu z+|`z0q@l?1>a`hSs*x>5a6SylfBCqn`G~0rLp2{UHDRb`xTzwhCiK({H`NuW6(gpK zsVZ*j7;J6J$4#BcRkhiXXge#$O%+EqLr?vFaZ`=AyD|FhhLIX&SA335+1p}d*KdcL z>Yf}iBE&{@o$p{0t9aC1kD)5Y#8+`sw_>eyOKiL9=r3{1a8vUUQ&)_YDjJ_CdJnVf zCm%7@IKW2p6){yr!R<)fM2q(SCEV0}#MFeLDr%~@dkHaBOZ!)GQxi(+SJ6}RQBw2K zQxl%*@^Di{Oik#i4RKSo&?ofNuOg<3u6H^ddqudZqV&nnf6uy-h^YxZwIOb*s3jqH z2t4xt7u?i@nCd>4mEop3?=|Hvt(eXW&TLvMMIv*y^xG*F=<%mqpf&2d!%bCM%uuyE zB0oA)D9LL*?i^>1YN+!>LQGBQsoK52JKWT-Vx{)NQdGmd?)rDHXid*>Q?)%eL{II- zom$bq4mY(PF*RYRet)>BQ{(KQy=@9JiMXlr*eAOk`#Fq0F7o!WD5;IbM@@LDMm667 zE-6aV7LiA80iWC!j=VMJ?l9RJE1GjyLQhS&sqQi|n*1DS!c9$BsYbpPIn^Byjl)fK zoospNsjf04+|-1mnxUsI<^F_~ns8GaBBqL}Dt^Z!P;qIT@$%7A|C@1B^HEasF;p|e zRIySMZmPQq-eQM=JNptos+{{#@^bdCBB?G9J@riP|2}Y26JlyYPt9;s6JlyYPyO%3 zO-+cY2|e}O;HD;yomOqrTB$3gt_CIDE_sK@*}W%QyZ!1ta{ZOzrs~C?a41EJ)OS;_ z;g-;roY%(%&>P%6SHk6zQ*$QgJ9nr4;keCli%YgIWKpM^DXAQeBI4^}Zp7s_XWvBbU{qry47=9x+wFF)fzH%j-#> z&(Kp{IaK0ZjlO2=IMGuRZmMhOt_`}zlXk15b@qPrU)K-6EpBQ)VybJdK1DnJ({))T zbkS2?uT@@e!^qJWdU=Sc@>eByQKl1Os+`zaq9XE+viP>;$lao+cIB*$HgKiZ^;j*r zuHgP(z)cnJXj#P6DN#PPr#22ZRWH1Ro0>3G=kj}ZvwRgdRm9YUp1M5T)C@6oHZo|! zJ`x>C^i-`cbE753-Y0sh7^)(sCiK)zV%x18F?9nhH`;IVaZ^Q16*qMwN;BM45mOU- z>hf??-5Z~wr*29v!%fv6Fhft>j9iAHn$T0lN6HXW6MCwBEFTRi;ihhnCb13r#kO2a zh^YxZ_1od5W{9ccAc=|eO>t92Oik#i-yd#jJ{r>ZgPVFNc8+@V)Ng{Dnh;aPP8B!x zFm_}o+|-1Xnvb3;Z(eoW)P$JouIyFEO%)lb9zFG&fAKBRU7o zX<5Y7bJ2gqQC)T1)P$HSCX%?R7eK{PZHSwCQPfZMm2M1f>SBH`ZmJ$gVyKFkbR{_v zQ^ifalJoyG+|*mx<1B9KFWH;>-QuPuG$avI>(NvH({NKoLu!bgns8Geq_pw4sZYec z%%Z1?o2o@Lp{FLq)P$b8>bR*Qrq-jUeqXq$2{BddRB=;9Mf&!*sRjo(Nn=ULRZPhOjl-U|yVbdm89sV!jrYiX_A3b$h+*GyGgr3?EH&v|EeDu^+!A;E& zQ`cg3RRq;l!A(tCgIK88O6)QF2rX~zk(NmYjO*MW+LQh>DZmO{6s<^3#;uCr_I)J#ThmjL2^)P6{O%+FVWw@ysV(O82Pl}-05H~d;riz}rEMlq{ zs>iUJo8hMFp_!qlsyieM)r6Rup{FL?RIyUUP(6e7jZ?^pn0g9Stkko~<)f!I4mb58 z>N0|Z`og!vO%*FOA3gOlY85B7A$sbHaZ|6vKe8S-^%5lg72~EF!yw_NCJfc<&>0e9 z>g9OgiJ-bX#8fqi3^!Fw)yCtdikK>H>d%n#Gu+gKm@0OvxT)78`!@zR)wl_FkVH>a zYY;>A4m|08NiHF#CiK)*!A;FaOuaqo3gV{TOReIh-Vt>NF;qoQ)n6{*rrt&F0le-+ zNEJ6VVW?)fsdsa}>bR-y{rN5FF(mken|eRzE5l7qh^YxZ)%`6`u&VhRB=<)-{yzFX z)}yD^1s(!5X=&A4FgR4gHK1tkEu~PHVQ|F@KnDa+*JL7 z>(Nt}#Z46}HKC`9m|BisxCp8p!?K8}2}!kaxTzwh)}yDc95+?0)O_^Rug6X8McqB| zxmWVf5K~1@?Sr<^8`_OyALK?<{#MFeIx+=J-BBmzv)NhKLI+7<|9(w8+o+ral&Bslh6sn0)GLqkjl{yA0zUmZG kccQF(6)|-b_a>~=3{_PO)oDThx@r8T7Ai{WSJ6}dA8ao?=>Px# literal 0 HcmV?d00001 diff --git a/advantagescopeassets/Robot_Epsilon/model_1.glb b/advantagescopeassets/Robot_Epsilon/model_1.glb new file mode 100644 index 0000000000000000000000000000000000000000..4821a73f1966a66000271a361ae98238de80dd97 GIT binary patch literal 3379232 zcmdSCNv=0ZlGsyJPE`LF--7ykME_~TFi z`1k*nuUvkTdzmpZ@*-{BQ3+{ojA=V)*%d1f4dH*XuPy^7(q+GbBML zqLls1^YJKf%KrJgp3dd^ygd@6t_xDx)A3^ttZug(l}2b2QZtUGLx5^?83iUa!v;4vIKlzwhVkb-BK7{FnRt{^Cmx9Pf_@?AOEb z4yW$y31p9i4;SwFmOLfgnLPTrTrb~mh2xPg1y{bik<8ym%V)p&szX8YV^>P0^Uiatye*N6PyYMx?Q(+U?vi^>PD<9wc z55n(ugW5g4n#vV*0v)H&d0w7J(P_h_ zBiQ7=_J=A2Phh|2l`CYHU@bV@+97;MA-zMMp4T6tFZviZ1?miZZkB$?Z!OG&)Ch_u zqRxWy=w_9CKE=(ff9U@Dh~>Hb+@tlOe8@qu7oyx}L80hwd}x3LO`?F2aG?5HAdvE& z2YhTH1N_Xi*WkE3%5xRnrNH$o;PW;w+(%9hQIfj>(Pg;o(PznU*}q~_%Nf+18%dTu z8@}Wq+2?Lqf;cie!#PYOMRz46bA0Gp+gct3AC?l#5Ik(UVMR1dK%v!f^n51Z=lL=m z%Q0+HgXk#m@gk^C!9$$aVGG@Hsx83$>=(YIFtP{5x5a;>PRK^Hi0>g+yLB`kggzhZ zj>?pL8Au8D;&!VN{eC~2)Rh0QX|6!H@?WFa z-w0$US%d2{{o0kD@BXk1 z**r9%nlhK$m(OheZYWpf+seQ_WCf0`$BD;PvA-lc5J3<%1D8fM= zYX3c{uz)89!OqFwJxCj0X?&?Vvi0fmTOK@LPs?b}<1nR!bg(QR%~`hm*T#nej^(pX zv3wI~>8s0}Wy?RefL5stA!YgOZ-(UOelyJ5Jc4t(eQ)>8DE)@)NMz39A99S;*CHd< z?|B&U^SK%R{^mW(xnCSM^+mg@620R4mSXC=@cdfLxZxR&bsD$?(Zi+|C+w85@5M?c zZ{C#~t(*f7BN6`2b&_1)t7R{4F@*n3tdNf#rt2Jt(G-03`19hd@97@Vvh6d+>r^+`kgxxKYh>zZ0)`z9j{f zJm><_yo8fD)B2Yc7;kCZVSVl#2wzsZ=K91XS;Ob;bEHz?o`jDwfNytF_Hw9F@^ri0 zNz!wu@|&yjn&W_P*M|juY5`m!C=~*?*W*j*<3ZR+SmOS?d>#*qZHOpfss>u;2Yw@z zCgol6HF-&*SJ(*gr4#VD5zgpaGLqQcsBnKt?HIwh@B90a8V^qP388M6H@3F?LW-w0 z^(tKb{5~G<&zDLgiRS(YTHGF%Wo^>pN>S0{g^hiAT<)(xpAwOp78JSNU$^z86Nqs) zLkT7#_X}lxFxr#!E%`Kw4cmy^p6|~cHj6KvfXIWmf1j%|^`o!|Wraj)zmKK z@w$AAiz*lB?a3OuX^5>rKzZKZpxn)SYXiAPZWiQ^l>&eU8;5Y=3m0g{Kyk)T)T;jE zG{6>5r(CfbFEvk;#>@I78Wf&>i*fTlt$)|O!iiC+g9zy^A!(G9_#C4 zrWsSqWret6(8>;frA!o!_lk)oVW*DLhy{|^OcVztJbQHS^T#XZD^_DPQ;?8b5_QR3 z3es%Fdticih#V;IIT!}h$8zqDqd-=62b2Gn+K)XHl=nO+;E@@+B{R23`rRo@mBZ&h z-@+M~RvpNnTsM-Sk3Uy=Q%oANwe!c1MPYGJYMayy1OYL2EgWbN*eMej55&btUVg#{ zCOL^bw}DDVhT9t-4rhuQqRUgxl(0D&R|^x8PG3Ch{WY{ECFm!R;)(Ot*Y7#}cQpLo zuJJw2P}dJ>>_CLm*y#1Nnr%$jY5KU_OkvnzCsA{|pCJNol(6I6?-Y&@16Y6V$Il%X z`RsH5AXr}5SDyLc4~Z%{bnXH6wTvbT@LA{oy;*K|YDyl`Bt3OXY5|{i(MCT=6@7`V z^vRN0L5D!<;)EtEaH4~xd9Qmew=YS;J}Mb?I)L~PxP0Fj7^{?ppw{I5@HKT*PLv82 z1*9HMlw2i5iNbc8+4MD&QYl&bp!ATqzKA-!DN4A#KKF1(7$Z-W$y9p2J ze%uVz5roR~m`2E|Ps;Sz<*{Dd+g(Y{N$Hi?I8tcku*x1}AE8FC4LL84dZh(5U*ect zGhAEMZ(Fb>xqtm7$G1Fq-b|YmAT6WrYaE+=Szji=auy9 z#XGz#J>PO3fh4Uj$;_Tjde*^2Q`44+Hd$Ga!|i%|vSVqxrlfDSS&ua6qItBBIjAWU z9So->@sE2QYBiclNoY}?xGP0+4uQlZB+3u@tdFO})cX>a^%KsBXhXYL6q_W?MIGMlK`}Dr%j9TBwX;Dwb&{Aa`=G&ZD`|BH{0|| z4mtq=OXY0{G(cN%(vC8@W`9ktA`I#flt7gxHxHtqQP{&+Tp|t>6qyyW7)Wi8l&UFG zI;#ec66M3d@|AvcdtP#LE~Dm@UKX4y&a#P5W6o!Hl_laiZ$gSDIh&O%V%>m%YSWsDWF+C?8K76 z36|@Txme|&TVSI-Z>J3ER|KK=^XeL78welF` zm(vI_Z>cX=J3>KPsGn0QN1KO zPU<4-dqTx~!%+S;sHyThSEe#2c+*;_($+~uoMVeuH&;M~EC8W{)}*42qx`nIRL{VX z890Vk&7JJ(=7>Phx3OD`Yf8CH{BLxW!=k|}H71w&TOTIuthXTl8S}TZR@w(7`zFnf zV>o^tHf9odkPKhakL!nE`Mq1kWfqo@<*I@fsy=r5UiS2vj--4@J*`tTr9B)AC3p<7*71v-^*7{^H*y*K{!DY9o^; zw;Nwz*Iz3Qpz*o6>!4X$pyc?(Vx9p{QeEB}VmY z0)74788|Toz)R22m^%({|O6Xghvgf4^;?w$&2SaM?3>g}==qWX4 z^c;IKJ};TKa@ohy3EZ_wDV(WVB9q20V+X9F3j@V)&N^sL96Mi{)9;_h)$+{t3m7O+ z$P86@NqfQfb0=1|wZVsx9CRwMA#C%h_uUcl>h<+y21t1I&BWn-`eSG&mbTjMMGED8 z?iWq57C(CMz!bb?EfNOs7>*n$%*w(FXF6ZvO>bX-r^F(f#$lLb~{NhK;kkiuq2Kb5W4O!iMWwxXOnFlRMuD zlR1-5vOCj?1LIt5W)CA9>3R)E`Js4zImeo%H(d=C?h;N9XU~L;c<^jr`-199SEmf{ zmk&EUL6#MmnFtClB!(jA>|?2d1S>GFqT;zcm=9@O9vO!)wUjY%qF|U{`dE&NHuFv1 zxD_(y0QyIK9-%mcr`f}B+)v@8REQsxD;8Qs1N6R&Cb43t@JUL~u-DC_g(hLIPIr@BO|7FN0W#85Zw3 zl6$LC-A^ew%qv|o@iKkApR4j_*Hw}%@CG8kO!PHe>O=5eWMJ|BvsVEKiZ>N-sw@`{ zcbqSG6^qOJk<*N2byZty&i$BGRa@VXKA^F?44_lD7&G?5;HyoqN>wV^(c5F=55@jT zFyQ+8a^Wv*EZKVK{AB*`dg0esjSC%_l5C)pN+XT=Y%|%WbcD7sMyfE4GTdW|Ih5e? zx-K^**5GagUZNFP8;~wM?pQqr9zL?H*INR=MT_+n7vM7W*#JBzfOdD+CQkykdUscs zy$fijDp*{To;H0HGE9Hd#WLJQ_Rovy%ztGoU~T8oAs`F&(Bwk;*+C?F8saUj|tS}VXwA-^ry#e)GyT~&vGUdMrb5X^IB6V8f zjB}&Mz0WEQXz!obQ#N5hcj=E45ZdtK>SCdndXm;|#+*$u`tSsN;iL2ETUaH8r3v z`LxZ_9cgufYFVre0YpUiLX~TSk zHa?hHhA^TlDlY8^U{h3`kXrFwjh`iH^MaMxdyVxV!=FX|8BK8^X|nw6?hF4WHio=J zs}$AHmp2Upmq-+}2%qv^dpHip0c%PlB#fTSTxa+mU@+xW;C`|32p_UEiR57}n-|v~ zbIOSpN4@b1o1Xjtb4-1X(9ik$m62=YUO3!k30xE2>z6V$L~nU^4qj?b`tT}JXHYm( z6&(B*Ta%0^CFx<9VL}KO3uECLN2`O{r)~voO@~2Fuq$(Gb2D%*!8+JBNL`S(O>_!a z71`W*#&@(IOZVzrOJsuHU__iA%MbB@AZG{k146>Z@x*^+2hDZ4s5dlSpcDHtuDS;3 z++Q>=5n7d6k6_pDhgTjnR?z!RaY6Fz7*jk=Grj>W!AX>=^r$^VV!P^$7=5TL4bM`E z5S|`{7pjh^hdzPJr>v?1vN z8wF$O2PLF(`56&niax7*o|0ByOw0Y~%7ex=x#Olh$lrbMQ9j4G;)VY*bj$IUo@9}5WXX7OML4)UI7J2Gi+#_¢pcIA> zTLD|sVT=>FY=EYha1~07=?8n{m43EJ4AM&3H}N#O$K^iW zgr@|ymd??W9W>L)VX!ru_K`Q`E{|ZQ+tvdMKDjC$6mSuuiuUi0qU*wtRos0Y+>ke3 zq&JqGu2h;a^flVxtpEg;gJcV~r-K?C)DV;n87$mT#3Jx`aKSS({2}ZjtPO^zQ8p z17Sc4fn^SJS3T6iIjA0}lpEq&0(`hZl!RmL5PS^Kn&!hpGM9uN(0;Ely(Ce9K87&E z?7FO>ZUGp7hzbYB4H84nT;75s$kC7|y<%ms5bGHu6@wgMn!ma>Lw3l(P{%533l{ID zrOQYMkXFK+OP(EqHdLw)@NbX0<;imV6nbCiv!IA=BJe<6;Xoqb@^hE86|glC1`qab ziv--N)D{685Fr3(+m_pjs?_Nb%2aLDJ+yiuOKyzB#YETN-@JVeRfYG zc{BnQ@K!iomoORBhc`j*3W=;}l(nJ#QhxBjz}cT2gjTXNeF@X`7qxhlkKSH{^noFq ztx_vc@Go`EvVWK~i`3h$MG+G9dy~%)CGJhOkhdAi2q=*32UtQ)Ci#J*2gg6+zNy)= zh#OI&5t9cNq0ou6w3JuHL`oa#Lj-bhHf2vE#t*k!$*gV0?uo1q*r%nA8)As{OU#i( z69)MwZmMj9d*ccxS(iS%Q^W_a)CzP>wFbOm6iAK~z03#_QORv^DWTw&N}nBsmWDQi zfg8|L&_iw$-N6wPOa|HmYJ=>))EI=K!WiqBtd5|>){0fB_usdMWIw=CZII8PHBUT_ zH{(1SsJeKB?7MO5I@CnU=*PH`X@gs%yN}%)%l%5I4-v=-wUsq!KwU9wo3Xn>>w|VM z_)bU-^^E2q<|2T0@u+baFh z!LHf0sX4l0>jT!d`=LQuTzvVNSPNOkCo4ipY=zpX_5}__6C!|8DWic z#mep_Y&%!FjkRILwp2#00ojkQkUkRSbV3n!A!R7-NxEU>J9Bd^j1Dxe5zB99MhmSgpAmB*SPIePf2bAQ#dH*Hnb#>#R5&9-3j7? zRuUThvu!|2$cV^>Ok`n`O0fFd&|;>-%IUMC(3&=W16usKI~g*5aHv}MZz+FQ!ng!) z7%)R!Y|QmcDh=W*uxig%(mABvbf|AM_YlJ; zFaquSO5+fHoIqQbVFT!jSKEBulUN_HgC;*79|h6$d~q8tC4o(7De1&LB$ISQkT72BrfQST{1cp@p|?7ZHhkaK)$3?mX{<7NiYmRVz;78LYk~qmB{x zZb?!hes8&~#cd?IAa1HmJljz1M1jzy+pkqx4m1_L+L z906JUYf?V*OuZyWAIByuq~*}s%*S0A3#MTF_IcrI0ZNy3%e`sft z2@Ih!qX{hoj3|$k?PKBD8O1@6#5h|$#)y?cnD7CI;^zQ(SJA!5ATrIICLNSwbij80 z@tv+|<~L54YEnwm=xw6};BX3-?zf;Dk#=%itHm+XmyWI-iqa{N>?c_0J2_|O4kELZ z0e()2Zg6^rS*lAQ@ua(yDp4>*;j!>Y8|q^ea&Ze1HKL{!cI}8_M{Iq-64M;I!ZGD( z{-E!JoO>8>cA#GbZiYYbRl>}GNSUpu)d#k{zzzjd8%o^C5}L*Akl|Xf6K*egDOj2u zJ~g=DMa+O2Fkz&za!+ant-C~5Aktj(#od<1E8qwav`V@N=E3z0h>FinfJ+7XP=KyW z-r{V5mUf*7ew57XxJNCwq2}QQncinyCaRj~Qn!M(ro&KGmlXFK&T9kM7xxEAKt`<4 zuN`#SCOIXrwP@}v?mJm?sf*6GbdV8b!FPW?jM<3kg zjJO8eL@0=$8I_0lh|4FpeILcXYer;&Rq~Xm4ansHI(= zoly=~vsF*$;4XO!7N!eEhEGfT4mCH0-gB`6Lx7CK)uHWCw*t1N!x$$}bvL9OB%V!& zHle`F>k%Wfo8Xkd)}lG695Agox?b#Cx8W(+qO5}GCG)@*DK~4unV&^X-Sa|>gQ~^? zLmxkwTe2HalQ{_GBR7e8#$MO`;L1b(Frb3sG>NoeX#~j};|Q|221hhB8KDOZC&bC(9#pY4>kRC?!+X{hM9{KaLbIN)ipzp zwiU1y6$aVhIhLFzS|tt7c*`=TINZZc#ZZam&fdOrwM}!*y*AC+phyr0FLHMv?H)2h zLu3NU=3)0@Oy(H+z#bZtM^(BEVw2c5wO3roeOZ(3Q%{D@Vc|%j*330bujr8DCRN;I z5=e%in--^L6QF{B2}3Z#Kn8H^&yF!L*pB$bUGi4Ie#iws@GglF6=ZO60{J)NWL3q` zr)>$WLWRMT9T|itYYgpri0Q5>msHRU z=em^ZT?SwD4_t@;An^+h*D)y3b}11~4+wkKv5vr(U=ww`GP;!R`kVzys8wPi(9-O% z5z7ZPx#A(HE5_}}XGfNuz*>4*Gvyh>D^~=a>UfvYHpk3JMp=AcC5y`|m`yTSQ`U7y zs%&eP!-SQzh-b@)pOYAKLAZ~KJHjP*~4SZ%Q}f6N$XIz2A1AsVhM~e!%+$f zY*ThVP8gXq*Qad-t3rjrgEfQJy0)d1rX=i&!y6^+n!L)MrZN8JGugshQW%ULozWsszkiB0m$ z!%;5BI6@*f{Yy<#WI#aM+u$Qdp(DtZXL0i*d>}Wscl(`15*a0#MVy~Fn=RuXgDzZ6x zw9saRZ)G|o4c*X~#tpo+pv*G6K^uz4=10Z?FhwGn4>0CRkboRgYX}b``RHrKK(hvB zQeBRo4rz?-*+HI=R`RYttZN6nG|T|{rat6dVh`+2=YlC@0f>~rl01eE_m~_Q1D9|O zJnDAeyVR|rWr`@?&pw`G$INw6P{8LmaxOo2iCY4zkYVs-&A7Fy9N^k(yd-3bb#bkh zz$%hCdbDP3iGBwYMaeliNEJ5itX(a+E`=dkbi}7KFM0ED; z(YA(F%pBr>k|v)>aRRJ$Md-lxC|dwa?MX?4!Gkqt%jvMv_Kx*RDwuIaTp<$d--M=w zwGzrPtw4phrEvAjjQShd-Xsw(sbW56F&lm44oz_vnV*UQ9_It?lrES;3`xpn z@`nfEWg%T3UX_LW1g^lPnEXrVdY`hfqvm1;vZTi8>d^McTLG&OV(@IuP;>)YaVf-m zl5)?YaHxc~md??mwM}#N{w0J&!4IJkiZ#SN6=i066fy-`SctoLYvvzQ50W?P^KV1m zC^3tj@l}R;kgZuxD~K98OC(O(ALGv&x~oo zETpN9aD_DZ^h^guG6!`7CYhmjb*>G1fDS~Nfq?Vb+aBt&`sTm=|OEE2TCE_TWoysM+=sJdk zWzUYWFETTt7<#m=V7;>Cl;I8gxQrbymtG(xY@DpB#QL`llr@{!|hna6^g->jxv5f}$wkWU1L{FOXHxzvwVaCyQ zUx*|A;JGnB0`*PKzk3Z6^5K|S$SMP07MFO8CD089OEgpiy9a4}z@6aGmN5`pD8J+h zs&6Dmkv=;JEwyYT4BVq`4J`2+GC=!Oj6nvby~H?LT{rY-TLP<4Ven)L9F3eT-WQHA zl~;sj%6j7x*jg}0Pu32etA0CyQfkR)2&6iBtx_=iu(*wgNRx?+efPOp1RK>MH^ilh1k&gOz)ERLleiVIH5mp^*4)ja z>oJ+OCFp)r>?cf;p%f5NC^PRn>rWOVl2>9V2#`=4Gn}vI3+Cn8Pof^+oxH ziy=@k#>J+q22!q4aK#`efuwIVkb5Vd0{14*j&TIzwG8%cK+BF6F0jXU9+51B~jgm z`4D+rKr`%iL>)_|ZNaK-w(be66Ie?b>qfAw;6>fg((|Tzl@cnxLfwLN<3|ZIC%+EnU~xAR$Tw5Cua%jy{oK^bLY* zTJ*Z!Ag)K5zOd;pl?0{m6&hqdSxI-Or zm!FwWAw~RD6HtQnXvtE^$`Wj5$F`KOB07TNq?bY$%~<}UhNP`F@Cw3+*;vNk(2*{l zreXtqc2v4Md)L1OOZ9{#CKt8CMC^BGh0C35yZ9(h_trJ*FGwX6lPL2*pV%k`B zxDGL>-GrCb0bvL6^0e^AP7xoxgQKT0xfuvSFD>Cg#+r83Mo2?*^Ci!YLTe71Zk#UT zHR(?$>WTr63>@-P(BfC7B4SZV1#gTb&aLHuA1yyiy|)!e_5&=G9jw9SPSSKM@Sim{ zq;+LL{=_LG&_cy6Cm(BF+dv&N>4S*^h$>LK|f z04)8*ELLY*9BLsadkOae0=ZZlRW}k7)p)h7Haa5f1a{2k=g_zg$&)e8K-$Q-4V%D9 z12jcA>9ac*`Jf#%`NcVr(9xTfmaJ=GGjk7Ku07J4l*e)BU{B@T{ z22pduaiT~YT2bGWaY+3UQLk8avc;NQ;7YWsf3^)lq;8cQ7g`QAC*ilQ;*fj~72fO9 z6N&?O*|jl4m@uBY0|;crBBo^^QKFccZf(n{>J0z^LGR4iecN**ppl*u$Fq( znVV8isvxkguraT(OQZ=cn+TpXQLWEjW^QpNN*IT$!;2iU$wXF;(ht`6t7z(Y6OBn8 z-Fe=1wxX~4jL^`_Br&Lv!q1l7X(9KcNK(njVgi21ith!(vyKV_iAJt&D$zx9+P%eoN4nlcWCo)RBl;}9g#rEN) z=7*%s`t%IE<_v3HZ&2|~xh&%XIXddp1p-Bw3Rb2Vj+iKkl)ajGR&UVbXy`pv0u@Nw zdV{D2{v+B$8V*{q93PjM!$EYY84Hg!%Ir7t!LcQ|4fP=c`Jg5U-@juTP*=>_)*D@^ zbwWGV`f#HcMzRfzYbG$tdG{re2pg_9%@3%Va<;JxUWvl?Pq(2tD8pbduJ|c30V`TO z?E}WqB{aG{9qZl4oGa{>FvBjSoWdDu11a8IHtKAIuTJ|2iJVZ6Y3f?Q zI?UY_1t++c@h?%Ea;yv!K2ZY{*+mzej!8@{SpbHOtxVwN(wEuSq{xZ)#XD4DdC40- zn9aDkWW)O~;|EZs0l@J`whCmtAsCVg;wBV$$0qJF_uER#YgPw;nge4(2J1dBI$~CJ z>)k4$#6&`S%MKN()Q%4i^+!;$Y}F4d@)m(Ds7o-5VJIDbAooL(i!Kx?0haUK(DN_? zwW$NS;udAAgRN*Vc&sB6{shQGz^DPt#HEBac~)U;-*!NbXTC6%0=tFtfWFt10O0EoCY=-dl;7? zwzB^+>N5Duzi+?e0yd@`*Tr(Vi0mB%8ZE zTzzNntNdRWrcL*F?;=o!Vy6u>?@?C~UZJ#| zRE}`Xpl!=yLgP{`MOC22oS^`O&L@T$5PA=Pe=}QqfU}y7Aw&%IVUPe7*!hdT<2H9l zDu83jlU8IQvgE{r6Qj&usEip=k=;z!Th*F3yHuAJK;^&&ez=|5i%oNeqAM~?00DGpfA90o60)vI9obaU|ypYr4! zR(}7;_S}r$j~#zcP<(KknTJ}xKzY`FAgEI7x739k<931>NDBECLIZ>&#!VM8O2%>5 zU=tdaZPzkLhgQ%+Np!W#o7gAe8;(kP-ey?cRb;dfivBU2Pi4SsD9a21b83{w+gT zKjsw4W>o2Xlf*J6{)EvY(Q(2g-Tsd!k6)Qz~XvEyh^m&0d9 zHH{K)QP|XJv``b&rkIOgWTac4(KQ5^eL+*|#_7?eJa+ahY?mog4I%Ntjset%y%y33 z+sR4RQjj1WdNIv=h}Q`&5u=ew8nOu|x+ELMF0g$YK%ju<_oQ^m2hzl+Dcq&hdKFiIt24^3o%VU{9N}mMus&{G``2K#N83@o_tS0 zT#)+~hDJUIR!Ooj@t3r2bcT*3qGf5btT>TXxfGDZi+_L73AS|;)yfd-kinFM!;%%Y zNGkn`X#t#K*vbG?bm)sr3mBhL^n$@<2&w`<%~2FBkm7pNidYnX^tk0qH5xq+%UTE`yu*w5vWOrO(W5D=Gjunhr{A6 zn{qB6T_u;SE@Nx_l3R=X7zL!5!r&Z*^U0yp*^hUJ%4}A@Ym$qLL41-HF6^*RoH8?} zae&*Oe_=(u%+IFhh`{m^H9DqoWU9IpUl4JUs|BBMvQSNiB66_3LN(>wWkV0QyeLe@ z$Osra)w}#o>WImy;wUkR@r*({;I}lsV%os99s2h%;AW;8AmyALcaN^5hGM|!koFXt z1G*U0#G9;wA^&Q*AQ}zCj3+JQ7v5Ux2Pr_WuwUn3jw69owh~~8x$0eW^v<1dDV9cP za>9oRyuZKbVw^C|#4EB_Bu>(Y>DJw2I)^MZ(?6v*K)lv7bdC(5_Uas}=1_H{aGAnE zdH->pgQ}vMg4_aGG}f=2VWyGsH~o^@%;_>fpL1l1Ad!09I4K&-ard!~nd49#DvG8K za6lJ>ns}3T4%O+dX(WrC!vRuuK=Om4S58w-au>oL2H#rj2bGR*Z)${_#3b<+mTt&S z9s)r@vTr@;g-ZXL2SulBQl2#1==4d>XCH|_-1h~^{k=e z+p4<2FFhQ%WSn3%*T2UtWWO)WAKh~IEM&~;2V%A;^9 zeSn({&x&zyjQ(8=D$>nbIg-Qc-&z_XghL3vEs~pyUl)8u;s+HD2C_S*KrtN!YAn)1 zTM~$Jz)b}tm1UAb;k*k)<>DJ=>KMmeJ0@h*8KEZaOWS_nLpBaQGcY;>F)3LgR4nMu zsvF7y-C=odB$=iN$506YvmIBLWaRmOM90aF$L&?~@DF$=WZB!)@3K29gv29E*k+X5 zM|_cE^zR~2lWtbuFa*~S08QVJ)gh2GAh@-}4^n{o47a`^jLPyHnYutq?|Qgh^71or zT8f_Od&5*%sycUr&ZTe2{2Iqy>l@CRc=cWC^S&ffj|;5CZy57P*$`IQJ0y)~1s1_~ zE1b93C*qb8%@L2*fdI9vv{qB-M{h)PT&0fyBfd$O{yl-E7?%h?jdNF=TEgEs>Mp=h z)ds^Wrr9wL=whG{Z`P}lF?DVm2Pwccp@PpXytUL1>Kq&#zwlCO!jJ%bLFs@jT%+#6 z(=UNh$$wg0P832WI->Ke(Uvh-#DcmX=KF*2cIQPv)w~#>;Z3ZwfVDbT_!jW?d+PRdD zbK~p+_#qDHVo(!r*3Lou8bYAhIb@7wwa6m82!AGoT?}fm-`USc0<(#=W`0I<(fufc zNzfgof7AmTJtd8O@T&~O3?(dsO6TQTP`fY=;h6iER8iQJ>u^_8Z=@Ll@%5up2)qN#;(3e;T; zPu{~gcn$Dl9MDCfCf=;lk^HGa0}P6yxfR!h+=Gk+r1B4GJg#&Uu^&`AzD2i77?WTm zl8c=#c0;^z4^^N^HwMi->oP;<9@uN}xFrzN zKW;@*wPQO}@JD!`%Rx5JhVw2c5> zPGl}H^AT`b-$glaPqEu{ITrd~n@$f44R+C*FG;BgaI z{@^ze>ygz&GsjK((Ji0au^r=XChJq8xSscnVnMY0Mwh~-PQ@aXp>3M^SZ1WD6>_7K zN#P`{e(dObGU9=oE7bDu6bU6hA-&HSS`6cg!MQ_sD8+mfN)X(mxGGA>*bVwYJsGyH z0`-RpGqM4INo-5f^q9dSL!l5XBC05)sQri33Q${P&lITNtYoAwf{+#!%^oGrLUC*y z0_PX{U;>dw51aA?zgDRa?HFfMgvErM<*=8F?X9 zJOA_u<`Yf3msK%VNKuAbHkSY5%6g2Io_x3fmoR3ZVQN07=u_g&T%8gEIBu)3-i5Fk z5t}^%Fv#XOV8$J!LCp+Wrdo34OUYqz1@?>;sURo8L!tp~RJu>T({`=WjmFBC&Q%%z ziAEt-=Q(avAiJ>fpK!Jd=5j(k;7VwRc1WwpCN|m#&p2({gTS{dLK6y;IxUqh!F&hr zpS?*Bkc?iHJSwHNSlI>PyL?VnXj?*DkjvC)uUbJSW&aa~s+4X7xc9(p4{mzAs8f01 z_(`+&L`0W~3|26!)+=Zfd>9s-6e=<||x z8Zu0l9iyb2sN#|#^gdzum}zZ{wn7henc9y*O-~mJvOuXX&q^2!$zTS6)O-ekj+}K+ zq-$L;7UsoSw<^p_Hez%*(`dPcWPCR@Kt~N6-jlnQX%U16Vx{Mxc|+HyaoQTp%w%OS z2^T(fzNMAYW*8Z;ju}i~m^vC%fndA)T0SOmE$J8zTU{Sr<;AEtOw+9_o>8f4zUy2n3TNxR|AzV&<&v$(*IbA%|V?XYMb3UtNEx zPb}A=b4?lML8VUk>&)38HokCpPV(-dQ`FX$3?JNP?YJVCRKPN{j*=cJ4HK{rayVDA zj`ha%Nb4ZcJbtIQYJR_~0IxXNf9dQyR&Dr10xdP*)ba zVxJI5*bBb~Z4}PUDV{Q(Lbjv|!=fEx*8iYdp~w49kq~2kxc7@Zlkd3A*ng>20GqlG znqV-2nei9*G#*jm@*-ofWQMdjdelfx=oPxZyzDK1zdp7D+#LXC&?|KvO2O8`>gAlo?iJb-5+C5M&AKt#2+0}o zD1s)Vzz_RA^bg1c6yhHk^z>Iw@w$vJ?>n2dj8cD&c@^?SNLw5pw=rz*xMiypC3WP; z2*Srk)?Fw0j@!%uC}2M*>SA9Rr3zSyj^Hk{O(bbV9kL`wCn{V%5X(^H)x`<5l~X&U zS!B1Bl>Cx)Csz{}R}P-{+e`vzfGcd8n=EG5h|9N4GZ)8@UG?imB$Tbt^9=ay ziii*HfpL~-HFBzyQ{m1K6OL4M({&DF!MJZTsuJ!v<_pii8HH58I6YYfx7V>NHgtVACd-i^cH-ErnA0aOiSU zz+$OTm&(j>Pa2wROItczfRk1=*rn!jsq+i7{jkr-8y(jultIasLJ7r55%L6=ldCkW zat&-kIt)HySS*HCp&Ghej?O0&Eo0JgE8?uJ!K;(tq1(d3k&&+O4|#tEIe3cZ;Hx_+ zF7jjB;G03Mf=09W8)aE!Qi!6}=XOl5;4M>+dCG~~PDCx43Zpu0l|IpYB1(0tTcgX4 za;j_=W{=eiJMFvNE|Jfcn0NpuuON0{?eC&J{6KeR@GDPEAmrC!C-Bbo2y zO=m)}xum33rZ+}LFNeiVMbg{=;&J}epknba^u7E{mow$KqE@ys zHiz^IjD`AT0?t0hX1}$3Ofuq8Xoq%4uVATQ5tGfBKW*ESsP&=3q)u0;M=;m9W1<=s zuA)_tPLwhg&4JDHySt}T`r_e(n@St+^(p2xHWno_IPIPaQOa|O#xQ&njq;gklOv{Q zb+af+g}GSx5#$&|Cq_5ym`-62ElLa@2p=le=M3r;3g6tOAw8Tl0P&ZTQ8mYu3S)@a zLrYh~HmYV&sn|=0HRe`M?U+)b_DxbjCmi?46n}+DowiDsVlL^FqK3Y7D#jMvE$t*U z+cP?CmgA6Gp}|W!*$U$fa zDU;Yv>B#hqLrewI%al`4078@^cb$BvP3M&RvYjD?W>eVYfnz;_1#HqpP8Uimy zdgDN*oPO-!dm`e4TY`DsAfgnp(>F%tKG#XOzK``9FrS%eF2M<5R&a>P>@PaO9!LjC zjW3OQv==T3X8!kqokny3DqbzCS<;F%}zKM*H8pvX&EIobcp<21Zv8W@|anf#Q4vV z6cLxP3FNdW~u^Hv9Z@>>Ch=l&KNc{pyrV|rkD|~+9%~4QaHk9?5m(f zQYPgD#Ah|m%UnjRg#)_u?@<7LVRZ|+R2fB5tx<4sj*Lj?bBx5mmVJl%!2OvvL!7+5DtYy!jm2sht6Rb#s!b- zBfT+kO4P2boM2m*l?FDx1c@U`R<~{Q$3#{pn$ncb9CnHqLxf;fWJB$t)3T(0Ra{k8 zLdw*?rSjz%0`N6!^$<2mItE{N9sx_|EBwxMl{Wo*0!sl5(E@3M4U7}(!8g=hobwr( z!jBtwfCIW1D8!r9IkHs6(4Mu$MiC6PQ28Fq}FfLlS!T30@(+9R$(-6BI6qORPJt#{s3 zhmv50@$j%@zT&jda_~%j>hrz=Kk0PVAHi$Vq!HVZ4k;aJ*2ajJ(xjzHV@~G?_?FIB z>>PvsT?$A93mg{K5en?2^Dz!4OaI_C$PY0<7lE2~b9N3iFz51Xm~iD%jxiv-wbTz% zfW){m-h$-DArWtOXU2}8~p4kCXZ-qmLftM>Q7vqr6GjzNLHf{-j_|EVa zO#GN%+K;UZHvudefQwlgI}c|?R#s~E8DD{)v022hCFQU+aU9b)bb>Q$f*=qVMQq}j zhku}F>CvHn_w;2*4;#03uGy*P8H{1kqfwC_S+lWoqzk>)@%S5-Szj|Y>5DchjT zlk$lww9!RD5%@t8hzz+IpI8E>8Eenb8l`vCgB!|WE0CLI^oRW2Eb#2&92_LSyi#Dw z%us}t04xSZc1?D{X5BQgSE(pMU!4%kVK@!>Y45Q!E}gb3;(keE$026FyIBi|44xqZ zii0Q~6;zi3u%CVF1V-O~W zN@)7%2{h4BS4jvw=>1WSH!~)h);Yui zT?{np&FUR$u?93KHBBr5Sj9K;(Ln*OC4Z0#lFD%lfNW^v?!k0moKUVkdPh$MF||BQ zmBh-wmJ@+prVeZ5jq_H-7F&ft{hRa?vxII%9I^+uOiQKejv$aMC=8MQS*fK-!msYd zPGk^1EVA{59I|z=3(0k{iFEG^nTFp^nbf9Em;OBhfWY&?9k(#fC8+*Uh9B`uj&VQ_ z1!_i1;z5*&@*GCPnr@1wKxGXFdjh?(%f7He<_FK8ek`}eAl-`aJXu>5M;yg_Oiv;y zAj&~e(uTQHM1fo?2e93i!i`D)7-sBhBV!!9TK7}yaSN67yuk2FHd;~;E-H3bVyU%u zD|*%%5R21u%^*Fm`TqNc%FuT#7XJXze@q>Q{wy=&dH5b7voSQV;sEV zlN@7!E&?^}W)%*TnT<r|GDu5El-)9i(?y{c`(1o|G@vTgYvmA*kfCfew4ggm zC#efIwLGGo@yTScSG=uuedPn3B0WFgQec30LdKi&qMUWRfTL#_@IgdHrgNQ8Qpdn7 zW}>;_$JC z-^D#Jk8%1M?1#9Zi$YDnSqF>hPKF$4N|ZKg$vNL8k4Q_FBlD~X|DfuDat8mDt_stL zQ8?7~E)foia8j&G_sUInRkTk&e-USeG9T%A2|u#)!^b@4fFKQUavb! z4=hb#y%2^@AkhAv6I`!~=eYRevR{G7IZ^CjWf9Y0;?Kd;CWOVbPj(1PFeKo-HP-lG z_xmIf_~PWYzurG_!d9dhxgVreW9H0dZCGEsi_~TT@0>>o2XNUOKJJQI6q07L;W~BZ zm0CIl?b(4|k+AN;(}h(FhYw`CLOlhU0zam8$yyHCJ`_nU)vGcUa{0NZ8bvw^*LlO2(xjpspi;#q&HDA8XIIHP)DHcq2@YWSvA>bXSq%{hDZP>p1sy@Tc@jG zIe5&j*t-Vp_IEe7jT|7em==WSh@ltVdv|c_8j8U@$?XqUu+>}wzv3ycjB|Oo!8NDj z9A;PrlmdZ77L|v63`QZS|c?|_8G5_T!PPk)y*~Qr>6YhOO$2uUFsg4Qc z*?PF8%Upx}O-L=lMi6$LK8ZX--#Tz0nV;eyIw0eg#_6-mZQ%4}-&3EZHT?z%l%mCq zr>@@Q2}&^*`*}*KNk-U!QD^N90R48zKpYY}jBP_7Schj>1u2Xh7B1E#%WS}?A0AhTP^|UxPiF+*%GkriA|(@hi7Ku zti#*>ZVB0TWRo{2SyrpC$lyi=fD+hUGtC)O(noD*^%Ph_tZT2Rv@h%4#|CQ%$tQ+h z{`^J=9|M?sJ~9SS0Nxys4S=HnPaZWXB8Q5vAlF=x9;c|Mzau}5jO$uZu&JGv9vu#1 z@8Tut(dyd;UEWXpu3FtGr=L8(v7QrN*Ugcg`4{0!0O(yID(JNvx8dx=!AuM`&pe_~ z1LDLbai^3woyeFewloBh5hQBQO&%3cdg7qDTRzY!s_FB7X3ZC%bJcr&s*0=R8>cx~ zgwBj>Yyh2}qjeOWS+9$*uW@M%AlCD~jv_YZijgB8SGjOZ&q!;_3oo8#FtHf{4b>a5 z-!njfq_%*&fcG$VN&K5IUmx(M=8eha)&1BMe;4i=O((RLemZ*0F3p;<*oLPIa3*FL zinV{t8@;`7Zyc_?=)}O%rNz;Qy5ioS?=ngq!SF$Aj-biUI|93gZ8jPo198l5WAL=0 z!;1sWoUBZFts$I);7%I(=y(J0{PK}7E4B9Fhl(;WImx!NjYX0}^b4k`tSsag3;~(x zEk80hSd3NXzQk!c)RuUImH4T~J(EGsz=j7E$@nUYg7d4VYm7owHD|{C&;1 z?Bc+@idd1anUn)K*dz5b92hQ(D^5KVW!uDrB~!p+(=h6n95P8pQWusCNFfg~6cc-<`sTt-%I&qRc=OE0Q&vD_GaPZN$G5ehpQ8Ml665EGi`JR+@;gcODp zu27uArNdNUKPI>=NZk5`K}^^XVpw7sO=yB(8x^XYy(mF5(re3bbqn|_&oIPhe~q4k zrBGl%AeedP5$Yhot*bz`ai>!zODVIVLs5dEx!9!c~wP}#JHxOG1Opb z&}`1lo>-(deKk?VQWb|nd(-1N($*|)S2vP#9FMMh)5Sx3(}M?fWtKT1?dAzRSoe{W zAis{68WQ!$!;>!PP&x*OGmDu^VrLfvygC%EKq_5iPM=X4FbsYGk;7ohDW<1929f2( z_9?sk&0U`24vKTmi^bXA^TM-J{&uChPKMGt!;=4`k!)8skBo|%(%Fu;Qgk}LvjR_v zrxi~sP}-{W&d|G);EOL~-QFemg(&?E$i7V>lHlRh}jAt_rfq7P;;UN*T|@i_}fE4@Q}Y!!Y1lQ?AP5mV0dL0oE!KBFd5 zg|;3oVJ9+Dl*yv`W3QR=mg|@aSR01guAu`0m2a&$ z;Q-YJuDNOUaP8=JZrx<`4t9CXwr%h$cA5sC1r7#p(2$e3$&8x|`&wDq8h(P~$BN0+ zMi#VWzJC5>YB<;b8oxtr0i^`lx3%xM^v;8MhJ6%wV<*6ky~;Sh@dee;2#5? z6%_)W?1ho>JUmSS#Os|odmID(adLsmutwHVJR2t_--nI)Qydv)CGCY*CpBeLhvENy zHwRY!+!gDUKS_lm(_9&>5TkKaR_8QWh)J1+%?u;Pa8{Ls6LCl2wTf`0!l_MGLwhVc+2mVkGXi%&Ijch2PK{y zZdiR8(JKETCzbqbg4PN>5-Md(i{KFy3jC;i%7v5NNCXq4a##MrEB zm4LCTQ6?`J&*m9TaSjsZP`Mq626!u8 z+JPpP)nU9&;xKa+=Z@HdL7TUS(a>n^5)@hXH820oBaMg&{^60D$s*0gl`UkJ39vE)M(){uT8LQ1hh zH*ChUG6j`DVtv%Fl$R-D%w(3VHZv_F}V%UT}i#7+`sW}%U6y$4N|2jz%`UX0l1MOnWf)yg4a95Dy^Fy_cPqCn*9v(l zs;*eJxQKFteYr7^Ns6(U&EQQcK~w_r9-@-@VZ$%UBZ@R6iq?gV>+JV}Ce`14G;@0D zXtubmi)Vv18Up`D6T?AFnhyrQTSl>b`*`Ns=tMjlY}-0BR(nkGty%uJ5i}~0lnj(T zZK3HS5*qHh#NMJ8S~C!I!RO(TJ*WM zAZo^QJEkq3>!aG>kd~m%qH2}d93$!&stx{aeQZ`%&5o3utStItTi;!Z4JaO=yeLXn z13JtSmI+gyOc{qa8a;oL#k1*bKUCKoGg)3wSlS5 za%UpS1y11@17@T^h~e>mL@itJN0Jn0g|$DBlfVOBZAZJ^rxE>{9_Q+d1uz;EJ(G7^ z-~J?;)yz9(=um_Dq{QD0G^gH_~Qu53<9*W_$8Qm zkf|%A(})uH=-UlP2zn;xw!SrwsWl5OCnS#73^h7Mbcxh4;`DSdf+gPB| z)krx0Kw1JZ@wm72aY^xNS3Kviyj#8fM@V@l$F{zeqRB1f=Go)xyu#(ic3Fz|+118I zc4+znm;B%I0%ZUMi4S{9UlE4z>8<|CVOhi&c2Gu8~=FaS#raGc6*iOV#nlKo1`j&PK zY!A1Tig0wRkERG(5g~C~q!E!&0dab1a_P$`Y%z(ZRi1Q&oDHcO%yUTs4RFrNqnKjmU( zV)0eJ<&#l!Nku_a9n~gu=V6NCq8tKen~lBHIrxoT>`a%G>XLRJDaDm?Z{=*Mou?OH^e}Q^NLhc{VTWf&28NCM~>#z!cDIu+K|%|@g)3s zrL6(Y#Tm=sc&|pni7*f?l<%1oeG$=nU!-J=i?#2QPUFc0kiI@Dr1VTYbLxZ*yN?t~VEWG_bGh>P<|fhrD` zY>CeAP|A;xPD+q?0Q;z0X~a4dLccO^LRwASQ6rko4O1Z}X9G)JKIuk32T6jV92Tx9 z|AEo*aof2hjSVz&@ob>k;I%%UkEg8G!J2qdN6`%d&Z8-1X*vjN5pBWNjV8(*{CfPbwt)NLIwGk!)}poen)x z>TJ=V-jg8ZF1rR5`ZsDPnzd)HD~+q4N)?UQ}2Vw;?vNF?EB=I;>mprND- z+KE_F#BsZ#hPdeIDR66`7wIsMaH?3gSgng@gE1PyIgO@OWpjX-LufX5w)L%9Jk32O zg>*6*iQ;!eg>(l6?R~fN0riRBl9?g%RZOp=f}X)>5;7vZMTMBmY+KSVY6FOD9^uA* ze8}X}rsb8+m)Wdd5R`F?GA07@|7ow!SrsDZ4mbDi?E_*cDBf1f>{oWZa;*n^eGDw z733sx@gYJdxoB#1nCTF1y%ump+KED9`^dzt&<&U*SNPP8`T`|QXDQ4kyOXvfZ}f(z@3OE(vB$^ zGKkFU9l+Bv{&E>@;MrogE}{+QXvpX+q8Mc!89fux2Isa8Z5mU{_$x>%Q#uJ0Q6of@ zhiJ1QqqJvWuzip!0#ap_!Ud0#W?mv)vMq{+nXZtMy1zcSTF9loDc|#6Fud-vjEF~J zgi|xcJOGlo^rLs7!w5eQQ=(y%`$;C8*%WS*f#x3r(}JcAOj|5xpsI67OHgM~wQ6h% z&3i7YI{&uLjS{>mvJ#=_E2W&Q(jNs+V#so!0Z*&KCKpkaoDGp0qG#h<^N7N8E`kzsreNhkSc8UY zMzwbZ6n9w$iWB-ElXktxrI1pTq#vF?^Xi`zT(c^u6VsKxGp=0em%(htUvqOVk+nXe z1w~av8xndVp5&N`;SsE&6_!#Ezl73Q+Q+j{xGJ6vcGIYk5|q8o6hcvJ#>^btqHdy! zp!F=KR+UYMqB7?Gbk=R1+BBx-Hr;}z1aogp0wTi7=8rXB*n&>NLX7aIp-PrC-9)ld znlc-VS{&{SvVhzeT_GhS%HRgpFUbELsQ8mA#Xj>EBvlb@2IR-nkzy|nyQ%U zQhFw$1ll+-n#l;E6Y%z%47d(Ij-(nLGBN$$P`s=b!kH$1(7#J(QKgTh6t@N)BS8ZyJ~4h+g54EVa%z*PQexNFNr!0K5UwHaZGCGVRm&JGsfy@Pp-aq`kkDso zO=&?#wvRZ%mF7nl{!t}V29Nj+BO{omiNv$(KLxCIl*~~p3A$f zuTA4h>02Myf~NR}WML?3C)dBuoNtZ0COkw0i7*mj3cO&FyM^T|SxM{`C; zw3O~rS`q1|pvNby$aQshGx*4`9SZHMqS_GDGcmjbld`S|kj8Ni2rB;c^lmDV2l+?$Qf8I8JbA8Kt zhzie2QV*f2Z6#g5#1$nq(F^i43DFr#`7qV>{C_GFz0NqTL{8GLW;zPiUp%wV;{sJUQrhGOphkuxw3Jo#|{Z;X_ zR8fzd?ZUZ3T&v;P5CD>glLVE)P@d>L*BI$dnU;$^c5gbS0a2+GBG(e`114IOj4NqZ zifg6HhdR7goox6LHZwUy(s3fD1QOliDQz}gGz)sFXzJo=VELv#A;w2>HP>n3`j<#X zQ`9T8KWDg|1bxY_OU_f=oJpO*E|#*%4wk&>W#=<5Sb*q!!mlPH9sj z8zQq?Nr1L&d66jM1~8jc)iJLV|E^<;AL=W+s3_Bqn-fa|Y1lh!) zBsoJp5tkjK#maCl1qqU~mnz&aC#EBuWKEccL*XD(eJExPWreON5wqzG`=Fqwil;7| z8Jbifmnw+t7!yNCL=dUE_k$=mptd zi{nZSuB1iZ1=r@}q_|9K9KJZIXe0m1J38qM`=B7Fil#1`29{C~M+pb$OI1RFWp;5A zqM_4;qacX;W^A;(asg}Kz;c3^3JFr#?4nr^a}G^92As)Im6#2I8lh(6QAH1YWQXcp8Y&wvg3V16dSn>D(s1BXk>;8a<} z#3ElYUJFxCW;WcYh9?ov&DxqdBDOKHB3j6$4~>m6{9kV*h%Bu$?Wv-vN~VP+;U9rn zY7J-+C?}@nvdK_kVy#lCjK*{?S0dGDS$Y%1R7jADW*^O5HmA{aW;<14j`6IHrv5Ej zLgvVcx#^KjdcR9Tq^^v3s2)<;!6ukzFk#HJu9~tVG1b(h`S;2iCS_Qge=>riGR9F zX8hE)hLjZRnuM>IKYl4)z8GCrCzjUOfsL2}v}~!V2(_*>es5TQEITi!WrpRprL1PO zv(Ze~z*11}Ood$~9N1St9b*0nG+QS&%d}t1(96k5Z#Wj{vJ>)Sh-S7&ldjLro{jvU zt{&|-Ycq;h`fd5MvPP5bXTno!B(f(jd{tGb1O%;W^fIA0#ts`}bzLLQ~w%OgQspoUc~Z zK@m5M>Pbh3K3&$XGR{qbnF zPHdWOX&LP!n$eRuV6p^qZRl$NmoN1Uy^Aq?5UkpC)hPRcx&jdDzt^>y6bpJY@|2lc z`O+UMLs^in}ml5do9Z{!yF@5 zFoC*GhJCqJ54VZlx;u#ZIPs+&Oyp-vE_#3k0)ii;gwvG`_g1}cOT0Gq&yMJ z)~6;pmI5pT&Fso#QWe40bh)EGOS6|rhxDI`9z?QF2ycS}aE!U*Iv(NkKPE2=s`<3BD zhEXZTAqkz>r>g% z&jFTwSSDUZO=_-_)sAa5Xalx7VQJZU zIWbi%2Z^~ag5B6ccTCX8$@12xx4)0lZL3D+04WENOctbW9NYNRJj+tk*=N~|nE77E zwX&`ST(%-IW+Hddq#sfiIK-8j41Vu%Kh0;!BFq8XfHJ^7mN_-kRiv`QunXJo21{C2 z3@kHRN?+)>z!X|UPv z21k19`Z(s4%=T5TI1Uk#PF$)iW&LZy5{=W!R<>T<_a$|o9@9rBSh`n}JZA>necrla{#=WDmO|+{q zem_{s3bo_mpKQD8j^z+Bb-rjwrfhWD7PY?J0Rx7T8&<&)Vh*9H^K9!=vrJ1o$3xC+ zd*ioXok#mqve|R*`45trZd&A{T{n&x)y%$2w18C@lM|EKI&t<8)&v-I1@m` za;f6jVzM5RDn~Sgl7@tBKP#=fZoB7g6~r8%;|PvAv$no8%dJexa!@i`)=0%rb52)G zNVXO~icn^&6)~v#oIke>ktsq}K}=3eMoO$pMrF)KAGY5SmX?K=o3T2UEl%sAnQnO9 z`Jy42=~mX4d+siq$*p>rBg7m+ldi{Yzw6GktxwG|E!z=1vYGB@l+;PQN?O2W%N~oE zY_=j(N_x6U2~3}4|Dk(aTi=>xTlOvY5zXkC?Pg?TL03BSU7N4G)g)h} zNU1}o`X^g{_$Hp~HG^Oh!$8Q$nJ*M&0ALTebju?XR+3?XVj%pwXcC$A5Hs7Gx}n+N zwDa&(_`+3WiECp-M~+bQL^KAyRwJM3yj6<`WQ&sLVVUk; z9iimYDvhxzc_NanPi0#=N6=&*orjjseGemPj(%{KO{x24O*Rb{a+$5cWNb=TFtbgE zRKUA$O=dCl@yyAYE)ZqhVHdV^N9TpySuUBsE}9IX?xUHDrix~Z*G|M!;S8UiB|_K7 z^8h)|#IyCSjBnW!>E_#yW$hINO&2h(UH>iMnApEB)npKD!MN!L%zmu_MOpiPLxu;r z8x(lQunuy1rmI641lSYLY&mB#^(a`hvI}?HXZoXYq(i;WvpFeM92=xO4M~M1e1gf~ z#Xgb;2zeTkjSo$;E2F^;EDKVm+ZNfm7x}dT9mAlL6`I64bFs|!UG{IyY;hwSuHD*) z(lHSE^I!k*pZ@xnU;gs9zx&sJ`sJrTQA`_<|Chh~jsLMOBnsk`Eeh?I0A*VnnSGrX zRIrII*#j-`rbmQn8nhIOEL{oOiO%wA(G+UoaS8xt7t+@iE zBxkZ>k%^6c;bchMwl$Mcc_rIAc3h?_3>lW`j_a}9%w+@Z%R#xU*YOQ{$Pq_kUo^^C z-dm}IepNIrQ?DTBwgWXmv&CyC;;Ar(Pdr)W<`T~zjc4o3rukN;OLi}nlAyBxa@nhB zOp(dAWl|DfFmAfqa$ADfl7VC$C9~Ar`D(^|8Ad{Jc{-MYru!M0Xc=zyB;@t$qG?%t z1vxb|TfBB6p4s}&g)@8tinr9~+XM7G6VcYU(tVpljBBm}DJe=yzS^i*Ll=q+vh|D< zs29-^mUYAa70CS&;IlWq1s`BbQRBAWH5&SG109Y{&fWN&2C_Y6eHHZy(- z;}#2NU-7suPpK}?$o>@FZTlzLYU?*{zgFc;A(|u(w%wSmcu)W>U9u@fySaD$YvRb7 zD4!veZaHmFcsdu$nj>67`J$@KC6o#sYe5=CvGJvBx#kGBvLMsIvXDq^hhhV`bRDB4 z0dsy;7dz@QNfLBlI{ETfxHE$QEF8fg4M`oeY!@R-+^vkhj=1@Q(6kR4#z1cHsDwNZN&QRtHq8-sH8+10q;xD3%+@cyZ-vK|t*dONCPXIl z?TcUkaBsHR8`eNUN)1U}Cez)EuQ+Wpk;z{bN6W6u37M@jr4*y1T(bp}Q%EWt;kzf< zGU`&U8XDuDfV6gL0OctOn+~AT&VhS!}MOFbqz+lO=92B0#qE);F~k_@NMpKrkT{Rmk$m5*BADE0&9)-0 zII7~9ZOfE?;anVlMHJ1&9yuA)Wu@d;dp7H7IBNXhlgGQS&{?HpgICk#t_KOJe<@p& zIl`>wN{^h9*`~mC01T ziJi&guZg0$$|I*D1lu>1HmB%^!~gxDXw|wLpkjkj2XJhBDJ;j#Sl-8~<_eFDj!YwC zj6SXIRCtm}Z!gCbO0p)Jf&jW2K1}1FuQ|6?+2JY$4pcwOxTap(?@l4U>{(`i(3d)F zzqR_Zs$4QcHgHtsk!}{2=u#K)fDWt&%$?*eijijQ1Pwc?12UVw7 zicp?~(?N{(_#=yXkXNiGzC`JHYXW4T<6TBhys>u3Dn5e`>QgyiS1q%SqArb6?#fxP z&H;byk*6a280OMAjiF`7oBB~~ z@cT55mKB##@kV~14drYWW$50Gd}Pn(kcl|7CNd0GHrmoMlG$;$y9|qEE+t)<*iEhO z${>u~uP?fbnG?al+55-cCPICgCzR8`QWZz)?T9cuALu5o##de~*vBy!$9WtrOD?D6 z{YH9*@HZp=aIG;OIvI}%By)+JMiQVM*JFc_x+o1Gseg!`y-9X87j@*MWZM^$MHtq} zt{%jsM@d#{%97!?44A;+EXvP0FSIkRAz3Xh+Gbl*5K6wm$P@}>skeWGJ`>jsNmnCS z9In>EzE+UbMUoULqr#byifEE@Ec8wv$6P39aWuDd5p za6QC;#1ZMzkrHffN1D25zK8C4zyn_Rd~XC4_}ZIUaq&w!&%?N%m$dmIyxh?4Sz4m8 z9P+3mse|^$W@U^X`-h2+g>taOQT{biG?#K@bj1395ZED}Mimn#cb|~IA0(|3mdusZ z>DUq@Hz6Aznr2pWAxBQh2i;XnTf9D5NU%05>7e1OU>RMw|K407$V7fW(&O{K@NZwb zKZsTK?nl`D%~DMkq)1sbr5=3AcSCYXJ0z0c#~MjhATfv84$5uw6vLabCmtNL3vwFA zuepvRC*elLTQIk3iq$`+Y}a_wLE>6Tj#EW$o#cs8Wz` zmsG-ho&e8XM^cwdQs+-r*AsJP`4nmPTrRsvW@1SaWfn=xtjj6M%HIzov1pKbKewT` z4KABNG84*qBoS+me$^>?9+vu-PC(N#>@r&3xFH!yh9|-j;V(X7Pb#@P7@Eh1n9H4q z-$nR?IQ)lz>{V7@d}(#>h$T;f=!a5u{4<6Pc<;(D0_C7(14&gXvEV6U$J4#M31U4; z92srE4=M$-yO>0s$>cnSmR*;VQ9pd0$Hr02Byt)>5^D2AJPXCfcV-zC>!pulK}K9i zqIBN}AxUQJbPb*d%|2IV#bTxN|HBfd-O(c7Pk@Wf%s7&u)-_#8f4qol605%u%lf)2 z1h9?`Lm)GE=uOa&)TL1-4p9>PmEs&!RCYyToPRL#8LEyIfMrn>3Fh)Ri=(-MBO_$v z_!~?%fn+X`(@44slN*FQ56Q-tX0bFEaO9+9(E_=B7PwIF!4&1@J7r`wnOGIO@Cb~1@1TdJX`OC-b8-k%RQ zq@=Y7Mdu><_@a$)fSHOyuBzN1or~lwlIHG>oQ~S*H#lqt$6O+(adg!tHwbwmmW@x% zp-C}}WzXfLBvb>cH2@GJHN<6a@;=#nFTu!1K zT!{BD!fH2PFO;fM5JZyWOLp{oEnKafn1naKQt~6%GJMA^mIQ`8m!*zmLo69R`Q&!x z$|nI^c+3})xWvJvNan*;S}xqn<#HBDbK6En$;SCN*o<`DEQ$SfPY3aOmM(K7FHLh8rg zV6q7$3!$7uk^^-JWrL9CA=&uSV-`!xxXVdN_>fpC*?x>zqZ5Q1f;cJJ3)T%1>bT@4 z?1gZiY+>gDq08gR#haUV1uaRXa^Vu7W$<#ik9;O9g+d-$s#rE;k}!_MjY-@xIXw5A zi8rH4Sl#;Nnx{zOQP=~8P|o6L*>*W48|U9(GX`%Cqj@eVKd#c{i%QB9k!*Ylr)-L0 z&Gi~NF_{lW`46!Tk|8gIsb9U!dM)yHSe_rL(9XRs!mm`7GXRoJK!jCg3s1X;nL>50 zQ;7}TiD@!q)osM0PCSCyz_THmXe!#x&=_P!ijiNGAd$R$iGU)zM7`DusP$91Y|i6p zS$H`;8$@U@8-apxM04q!MHJTnOb%BuUm65G6Vb-ErZF{FZEPfs?qtewL~XA95+AM; zov86+8G}fO-HV609m(xTwS8fzUZP1~?b1lUiPtCwI zKeTyFtumM`6x63_3)L?BHc)MRYZ_N`@kT+_)NXrmOLRTYmT44^Ej6=92KL&zNZU^t z4P0eMBSH~29nFT2HVnY{rOe7AOO$J){4Slv(pgVi#h<+69L9YHe}&}lTS zf|x=+bz-*A9H3_7Q?q!QOE(H~W^oSsvih>wh?qojrf~^MgIeoc&j<^V?+1@Vc2R^) zN3$WDT`bcGljLQ)vN;z`U{aTXWkF1x0u4@kr6Im#`C&Y;KAMGW&Z23R#}u-u6SIM4 zD*)C*v+=3P;1EFz!|p4{nPvv?)BE>kGyEPAO;agk0gBK`LC-Xm^777Pz7b758Xj6; zOEMrkp1N@M(Iob@=bq3J-6Urge;+~9GWkk!CfTf=1Pxvj9@p|>;lvCy&!wj97xk#x z6S=m5XXD6b>1nRq$my9T)EWG-dQuJGvZVEOukw!cO!MDQ?DPCm$?2JNM~ArP+^&tGRXXt9LwCSoyO9#_ex?WB_KNm8pO*rBbSzhC%K5C1WY#T5;a*QJv(}*jB+V5ZB`H+`G-#Q1@`Z6O$$gpk%T;LR2R4nS zRX3A|fOJ|mupA*~<5RO}np-$>YEpra^f*&S&@*HiOqp~N^WIj_7DV%&_3J*?IbJIN z=l!RQH+9SA$Eu#m>DfS31fzrn-XR4yKM zSMd=nbH#zOiD4U_t3+k2W}ul5hT5iIt)I$-^8_?4n{R@g*@(4k;I+iGHSo-jY?_>p z!`0GJJkMj>2A;Zj&J)yJ*-;QQ8$3y>JD}eHE}MN=8AIt5MY*eTn=hwlIv0?!mtNDB z&KJW%C`?-w%T=Uu(E3PbBR|VXbS|6II9m4J1SQj9q?91+gUBNHcd^WmYZgl>cX0#| z@+qQI{Hh|^;QVPUEmJS2Wj>^tg)=>|%m?V+id&N^@nqnzY-I=}R(U_4pG#kgTP|6S z;-O{(PZc-=&2)A&tuZ~1a~@4|gU19pY1B)`chlvbTS3`qjUI8Q*-s+P(1Y=fS< zPz@1O|I|F9<}QzdqBJ;fn+=$X*bNHhQ|IYZDJYtb>AxeaJqbl=?Q0UQ7wD%SWnA$Tn#@r%l7BPwOqX7;)VCmK7tLHg=h5_) zM`z0_X4zK7vmu|;h??6ya(d=Va+pfqyFl}0G~|79f=a741=n${4HGkqt0kvswyWj& zbXNwEi}cw;*}kIN^+pw`7#B3>(>g z-2NwpYDQd0!kz#4_y6^$Km7+Ek{W1fFjG62AA}?w-iC1Ilw?i?!`8MRN+ksK`nLyY zslU|tmUd(=ZHsqn2DD;-uvxqL!P$`1v65};IED|pA+VjQE9`9XtG1ou7RL z$Hp=W;yd^ir@5G(fj5QNLPCT81n&N`C_@a^O0uL$1`|0;aj zx!01iAN%^S@3a{o)(3W1F>(oTzu@z(x}uQPFJoNxkwD>b<|YxWSyU44aVDZnD#65K z(C_1pPVy=l#-ACWXR?Zlka_TntbPhse_hx_gBoPJ5F`G|PU!sAcaFuA8YY|^qEf63 zX5pY4502m{34{X5k?tImlRzif&N5R3;FhrnkV-1UBblSsP&6eYYz(haZHHf>nuq(r zz>2737&v*qetd^~rIQa_DhT_WvVkkYSDam7+k{i}GY?W*k!lBg`pBiPpqtdo6^@t$ zB3|*PEEEpo-d~hVFh8HkmQ>kf-Xfy|WiDW*ao7;WOf?3vF*22DZC)oIWoESi?K($J z5~$hBDljAmUuj7VQl?5=yfgkO1oa&*vmsg8w3<+$W&p~N6AZ}3P-8G^ez^(+tre@LgDtzDhj5}d0_W2 z1E^|pyPx}<9ExGwSJ1nPYn=MZmitj}YA}IvM8Ppw(*SPc-4<*a>t+w_uqkZg;#^8k zfuq;@l7hKQ_RhG~5o#Q=1H3-&gObsQ4k)vWxV$QKjVr8L>FFJ69D@mci&Jg*S-W}= z6_v*exGVEZqjLIo<(7F}l#gU4#faO52DTbdbJ)9HVh3_9B($IZ5aQBnG}&Sc(+x7_6+k1Fne7e)Q|(z7scxT1l#N4Gv;vu{2=~trMZlxrTjuN!2rf zRz{34zF_$&-4>}caK;sA*|Ks0ls@d>%Jwd5l`;>Y0upIvuTZW4B_81ij%~et`7?pT z;8zdQM4WODNAsV6H?NsV`Cg6^=lqXCu|(J!FIUH z?L!-EpIu-q)4Q}XpYLAa@`hJ>*Di4RkadBvW9Ayj`~qvtd2yB1kKbeIMISrhqNO&a zzGhi#0iHbOtX=H406$eS z^L>Dqr@Y1S}zHpB;0~`UZF~Dcw4JtaaKCCnLT>kEMjm=~e3(Ul`-(*t) zZ+#cr>p5QDk%>2^Tt4m4nEopTW^svCF1yy9fn4=#Unx%jSCL+Qzl%KI$bWUe%crgT z?cPu3o?X<&4@Y*bT`U%A3;7?`voHeL{JGdC33#?H{SY~te&~^NC#fq z1%c0G{ROL=efa z@PezWAKg^oM{rs!z*3K&?wKCnR#-+qG;_OnYW&Yufld65J&#nJrDwNkJNDACXJ`5} zYwp}<_mXB$!Lv1hNhps95{f!lV};!g2$Kpt0hw7jd~o@^3oy%Qg(b8BjG)UdZPR?G z5GTpF(q!X=uRwlM2P0&&2ATT78dsbF+<(Uw&)D60txnhtzUY(cGg@!EcyR&m@pY~j zJ%84bW0ae{?Ge}i`bUs{U{e68;)Ay@b^i04sd;g!pMZ)BE0jaQvQ_=D5cDdw?HS$CR|CAAF7XN<{1+*9~)%zU)?C&Nbo#j59+nx$v}e-*=d;d=7lY?|K&W>fyyYFWpcY@|3MPv z7(DymE?g8hd5j6O^0(ME3F6xkwpD4xN!bNO!ZsoK z_DL4Y_cE%Ti@<*smQ>&K0Jht88$d`|EBiCJc+uP*nl<1)q-O0Xi=3=Xc-yy$mlKL~ zyH=WB64REyWt!r|w3YW*elotFc(wfXa=_Qvjk3wHq~f2GHOtjl#EQ_;wdka;GGoeH zPW!Cafp>`Ika)&=b)fZ+U z9*CRMfN4}zg5@(AQHkTe;5Ay(;9j<;EtsEkDi5pc2>epSQyf z*EU^2@u#Q5EV9xxEUYg8Dv+gNfEH!ihobY4&8fkv)5{!i3+MpuW8Wl0-gkI$KSZZk zh8$BJh|bLHaJ-}mu}E>@K2x(oq|kO689k;d>sT(B(=d$4C29FH3mdAoNtoSNJu(xp z_~^LXEy2#u+CjqzL&EfU7B_Nm6OP44(?JgH#^9=JA-f|TGf_4af4ZPrPbX7ue#}Ca z7qCf|;kI8MRy}CA(G=AYiz6k7G@Ws*oMa(+H!`~CY9Be2;f}bU#LhvPmpohk^K3#) zc$NQz8NfF!yh6%d6R)&R%Re~75)%Vnu&)=o)F6y1n!poM^} zJURJ9I4p%e8Y1T3CKQVglBF-%v-sEbn8RHq9E;CRCt2*u&ff2>?-+iV2_Sk%jxY92 zI_@s34ISw<70R%rW6cPsDGdX4vo@zkS$=Y_8_R#i_2*iSca?A~Kbj7*==hRjJh7>B z#aRBq2{x)U=sCp*3i6d7cn`Jx6*WLDIy+Rf9m{2h8c9epw0%tfVAe?BQ&)%}nSJzU zr}N8yT@RWsX+ds(fI&Bk3go!X(k8_TdgLlRP)p>Bf7l-3ZNE|b@V$TQ{yU}~Az7?j z{*OwA;qU*}{Y+Z0c9@6Os8Ub-siT=j;t7x9fr*zW#x`YaQalSbo-)NGxRSPP+Hx35 zL$4$V-#3cIzn&OrduuOIu6B}zBNmWQfdyAqVe4aK^d85k?WWfqzUqhAslHihGqLOT z>-PvrT`*=eJ0;OM`03uO_wZX7Nzt)lw8FN&uHjAv^jmz$ke9tzRJZ`AZbu_VWCYW- z$(b`^6{S-^G7Ixf!c7-hVPWra;Ud0|Q~lu|9+$xK^mR2ti4e#&N-HxOvMhZRSC-%z zeYa0MG$J#rJsJPX)H8JYYMk~b zyFt^_zpf~qoRg?lImqF|=&DxsaS?^Dfp%hg*eD*)X@X+M%z$gY%*BVnPR!9dQ)JUi ze48*H$yn=dxudh_{_3Xck;t2qpx;l3;sn+pS7`gA9>6f4~Ft;Ot1&ZlgCa05dOziU|JKoU>Y`-bPIZeFW~V-`ye`m z1;FVRh-&lKm}GaO)R~Nl`_O2x5XQ*bYCdrXeHS#6Gog&Vg)e-X03(4y;wSwJjT^*s z=nC7tG}=F?sE*-{F?WyV+;rX-k6F&_sI2I!|TetG(0gXFQfQB z{vesS4X?`_0SO*T#&E?4ymII@$H_CaqVMK8yLcofdN%iv>!X*HT!c+6*^|rpIa(*l zJF*ib8yMG4w=GGiISgA%xMf1*MSlHu5Dd_mY>AWw1r$gee@zPNbvux<- zAqHA2WwZ!@mI$SpODN&9(LD#;d+Yv!okq=uz5z z&nz2K3Uof5^Cr<}OcM;ScyE~lo9ItM2$SS>3%DZ_9p{`<66@ne^#PuJXlzp(0<3D# zDp91yW{g~K$bpU=HIKq-!YdD_4_LrffEPPn$ zIN6Lj0l3*Yq+XSyXE;s=6}QDnSIqh~C0}8hUAeS7EQ^;!P0k1GdVXDJJV9U0S5Fcp ze2wJFt`lrEB+p=LN6Rm*>%w+OZgJP(^R1tCs_()kP{$wNQSgWE8s4%S8X!1PZa+(j;nja5GO0}*DS+Xmw=?5IoK)XirN%`Hog!~psxy8ODB-RGjeUH!D z-C6E&sV50u(l&!)V*?3fD9zO9y1T&wF&z)@pF)HSTcCTTirJCv8Kk#uTY!Quuy|j( zvd4zbb{-{A57@XDFY+44+GU-w1nWB3d=m58*gf(vi##b)ysN}f$*naU&p^9I(jnxx zNX9-Ghmh3p#Y|92s|iWrNuP>Vd@Rgc9$iRbib!`W%BX?3_cyA#31HDbeNX!KMYIZpDX+zYyZA{=2(qFtuDzf%FhRvVaZHh9STo>y`Ho;B_pe=mZ)^SbA&rv);mIaRs-9RuhnHFa_ z<~j$(X@^uJihqsdj$JEsJcF$nA-_dZ7ZR?NMEs$>GjA)_(w$0IEQY$Xm5#}6{qWl^ zWGmy$zVbr|UcakA5@@;iFpV;B-O00yI$;Ln%~#GO;zsC>l~2zQJcaD9LPNRZso>JW z%ep_WjDW|PaUNGy82JpIxOB3&LV26{dDkZ=Nz6L$!j^Ze#_%t7&o)0*68Pi)dFw9le2Oc9s zO@-Ph`Ls||6M|=VUnsxKDRwa|G}Q+*)QvrbxM8ey7M1Vko{?IjwJ>Kf=eFQ#pjg;< zF=yj~O$(!u=>)DsMeYm5SfZHQ#MINA3)F+9y@obi6mx@izAH2_q~(D zjrn!&TjKj5!v%_Y=z=QaqRS4WA@i68ig_qyzAKMYWj$QUsk=DJ)$KRK@oO^5ey);J zi$W4+8zVjHdXWVDR+AN@1Iou(ltWymt0)xADxWACwPh-e{|=`X^%c`2Izch7|6l;i zj#CX3D|h8_s;rkQIkke~iA;?d32RB*S2%u6M%mO>a%#~*zV?Xk)IaQ7^5s+mxzyHP z#iNSaN@Qv3?DnXJfnYIa-V=X;5mDr_fa7`!M;nBunyuQ^cu2BZ)}mToly*{@%3aei^1Z-J=j1Q;G1yK$PPp~krX-YdquwqSRELxbJmk4H-=WF{)g5 zc6FX@8!r+3(vPPV;qCI%;Jo+z`1oWq3@hOPkA$(v^L-b$h#4|3^_+yqP~RqH%KQap zWgJs~%$3liiQn60r$Lt@?E8prQGQ#0gq29&hZtr#DL*J01&%^d6mqmi!IP_RhvA{( z$fF^fBpe>iQ!vw9@hSz2u4l)r`aqU7;lz(pqt&U=G6)E|Z z@o15n`DF}groJX&$)p9`Co#VCUW*U@D-o14@Cp(ZxgJId)T7!5i8NO-Z!|1&Pp>Oo zSjya~xY}b<3bU_CSYntffEltnj}}>)sfam8Fqa){r{qrR;_7PznYRN5R~-rkk5)-| z0@_~&MP`9tqgc|g$Puvp{k^7N$)Yv-)mii}gP|TPk%!mH6c5Yk&p9-AkeU8c zghX?%e<1dCq3nwgz|{Zeu_y-EH3^F+ScR<4qlJT1`Sbb9PaO0RSG4vNYL2Fpuia zfYn*F$jPL60vURFM3C8S7gitBmG%P;Jp9rSp0_o9m4GKV|5w3quxdz)WXdwHjq2FEyo?zCcJt&I(0d(no-H zoJ%r2vOkaHs0O*La`HH9;K2y43qs}zr%aGc=M?gYPR7YE*gv`AN^L{HWZ?w-|YlD?n&&g6qU{QN__pPOVb$gj27{_y=*MG5Pv6mYiB9 zc_>jk7pi&wDR*)c8B1UJY@%7>_&h)JffFCI|11oP@WKRHollGWQx>F{5GDL&lP+G~SRT`e~=`|7mAdYh4_>NC^71*b2S|l*$p$D0PQ$|Fe(;$ZWU40!fWOj|oc}8l2EPsxLJUXk^4*TZYk_19qLTl_ewMNA{t12@7IUFNdWXRMaF)}h-{hU(^ z6DF?>N}O6IqPS=%c5+v_+4w<|&x6^jmfkRMtbmrWYLTlUvUY)Eo|>Awg{;6Eaaf@_ zN?xtvcyj-OkhvlI+eoUcT4?|j84||hp7Ls$+n5@VaysUI^V||uzpEll@IjkT1S>7g z@ji-K87Nx^vKE->Iqux%b5<>U@wp|+V^vwnwqw;io-$MMnjZX zUuzfgI91lO?KrhU#X6@dGX6;%-!5OD9#Nhl8mG19bxzHjTNoR)39m7_zJj%|-r2HO9m2um#YhlWq6q6<#3oDB)F+16lTWd_ez93|7k$%+v!!9h( zdwL(o%p_ev%h|QCy3gXn(`{7@KkrS-YPKD>R**d5)^?Qq9!ZsT+i`1=J-M1*UgkaW z{`y3o(ht61)*^THiL3u$wWcLo-$zln`bEm>e)S@2Ekz!)%Cfc{vsREiVb*4Zti%jV z998BmBIRrQHY3ELJo$mN<|!0g7dx-;0hXT_VaDi8;-g#06ibE;fL&jHu^Vw5BICnw zk2}-LUGwun;QyKj`R5JtBLFqXnHYr@UbTRPd_mN^boN_ZLtee~)9W759ogay1@wxe z1vJ|g1km|)Gq&l)h9uS!r=K%MsX#t+SVDGVk@bTn%qoyoTr^n^2I+qQbOqZC^o6B7 z(CO&D=8@vM--LVtWm5kzN(JQ&^7R>;kSjyxlS^M=*+4(CSO)q>B88#0!UiiY{Rlu! zq^#0yg}fp~zlL0H-C7|JQ=vlk8tAK}*v!SsH#68j5{J)Nf^nG}*%&4P|K`0fz`P6m zM=TS&=Y9eBRo=Y`{7Nb7sZum9fG@bF!nakfDb>*l$u_Q8arI!oD}7XQO~nFv6Zi_+ z8Sslp^?;XqM#_u-$asm1uVB5wzRFY&cJ>@Q9A5#UcJV7P8^>Q>{3=#G;APCRy!bcm z-9>b4uwR-4pThpOc1ol_z#gltDGw-2?kk8HMDUG)9?QVLW0V}=qclIV$Cm(;5EcNJ z%yD>?8N91N-Y)p~5H@%h>?~$xyE*_}we2Vom;-#2+7}nRqUQlDTj9zJzT)6jYit*M zd~@psub=kd#f5P$xCX%b+efDdN-2JlCEg|)Qp0Io>nqxH7}{FzK+^|b)F;E3Aa z-!6E$vbQdH#m?f0*N@71t?-7KeXvxs2e)3>1a2tn3cr6Pfmzfp{FzNaRK0>6+(ksK z;MTDF4qR#wub*3Sxs}Ir#tSFNEzmBgd8`n%b#F@FlfS=#TMFO!c!hOla6gm1Ean#A z7MEN3^B2%AoSRZzi`B3SJnvfNj_iVG%fEaDVnthjccGBzn*RBP)|CGSZ7I1Rf9>Pn zajPtqtzPRE=)DvLSKuzTvBd==D*~@Cm%Tx2bhkq)zxc}f6DBUdjL`!87lW%`!xp68 zl6>*bn7&RQ7@zuivKW)T+W991vdI9LVQK!1%KmJSC)aod;0=KJLKW9mu;U=Ky7e1N zN%A=QEvM^41H0jf?&ocG4n3kVJfJ$z*h7niG33>66;uUoD`+ zr)!VFd6{g2RVHQy+D&-81MT+duc4*-Ndzlk`2E#Z!V?8^gm9Uvj2Bh+ft(;eA~<%1 zESPbox&m$c=xUgM0-ID8VfyT^Z4E4WG_HNx;z%l5#QV8~w#H-o_tTIgd-lx>8C$tq zpYAiqS~oe!{73C3E3kDF(;csIwqZWtNot7HOFl};)F>as|LPa z{e)>?F)v8j-H}~igj0+#r3Z5}E>d?0Eie;A0do0)$8#HTo!~A1d75mne!udG=>UsH zH@U>|KEV7NPHfKp=@v^B3@`|OR+!?yiw|@^n&-qjQuyRe+w@>0L-CcB$an3U*nNy}^D8%XaU-8S})3HClOq(}CL-@ES-H4dSM&BuIQ! z`<{o2oRxSVheA(O*r8D7C9sdJ^6m5?Y&5KVBpu+OG~8ulEL%}?%~!){6;3Fp(U5tsibs@7(PN)!t5bmC~9&S&Sy|HjRx$aCHzlmBpsCG*pcD;&q zY%G}m;t6ya=~gD3P_4ebJ)KT&#Y08gE2~s^6O{_@WP~c^;A~Jgkqe{B(Z59$1k?Tb zBv5!`HaZU4$Zat!$A7-;^Qy^-(UeGEbPUZx#saKh>t5votDjbS`I z?#jj52$K|J?fD*&npkAQA-;Bj!jb>1SB{!is%CxV9s;M2{T!hQZ4Z9A(f%EEQl-F0 zI&*T{zI-aZ@)YwB;EA<+B-T5Y<^0qOF7*w{C%MS$xBgCeD2sQM@t-%tL-Y5OfT$f{ z@mc?nX}KbnQvSguI>cz0Df;?h#B2V38{&o5O9H%&b(c!q)?Ix2HYwufn?D^FlZujts>2fnQ z`KWz=_3DlU{D3;NkgL2)mOmgmoMNE?`t)B3i2gwsZgn5Wox7ZUaQja(cMxO!&MWxR zqD3sUas*lp@EQ==^>5H-$kx8&0Y0j7uJS!Vp{+Thf8CoBbqh?tM=u=j%yZ(})=NTPs+)GwcA9mfwIX7!-*Sx!>~*+=l*vmD7~ ziO773`iLkyuM#j+T<$&T zgDlN{rnO;MCpmB5UPW=^nUrP7M^d7E*+u4w4Sg+2-w`pNpi&nxU!X!(RI%S1a^wS4 z>T=`@OkjOs+m;Wh{>J@hR6XZ+9?>Yrr5?l1Eeh#80)6~PdB5PJhSyrNU$Vnbain zt(Q3_@h{T^#h*L1^5vu$zKub%ewp1hp=8O(KeJM;ZqmFj65rWNySopH>O8@Pg&OW| zRGnsliv+~mc-{I9sf7RU;iVfGHC_?uL!z%gQ>>5Lwiv&^{M-vM-_=p1{E?_!GL@eF z_+%f^@{=mH3@b2dDV5h!Vpe6vPf)9KWlPkk78i14k6P`W&;pVx)k&BAyduWC+&ZRo zuEVNajTXMoPmjc9$4tNV+pgNe7O>P-T>!lQ%qnm6SENVR-IWe2awPTFaT~b*&0(5G z)c@SEVV;GvRsS~PGuDixxAp2#;G5au3d8Q!S^1GODgP!q^@rIIox7|N+&`zC(yD2l zWOTftviRJQVJ9kmr?R@(Q*>?JmT2u&mVwnln*SbF4_)V+Teb(06^oI8JXA1a zPp_R04$$_dY9Ls#b1N_Nmt@B4u0m%*Q6;RBrb)QGp`7^KQL{BsQ&g5Jn>|lL9MzOW zruGPb2O0FfN_M{!k0JEJSY_&>X?=LoTAF-gJjyI_lmPhU?k%1QQ9=8cv}#6AwQMgVeSb{DH%5zFHh^DObOls9vUJ1|QXdKUG_ zca>|cpCu4cVlr)dNeQqLlWIJsh`cnzMppwq~}Y8aDc?bA6N@ai56 z4Il1^k2&(dKBia4AGt@T&|qeEdzQf|Um`5NwQUy+AN+X?p0R)M3jPd+Bc%k?zJVx# zG*^(_?^GvVi-MxaoKE38#e7{y`ioMaX_>)}h-6|C-;D%ULzY7XAiHe^n_=eB@Y-=t z+!m43*R&3YBvO@#Y;qr&GQ>(ZB1x(K#*udSyKE>gsmR3Nk=1TgYC^>y8t#sK+8#yB z<0un_mbm<`Aqx?eKrg7s8+f!NXq1B<$wK*A+jtk zB}U>rL^coNjSOf;Ug7ICH4LFCyW5@oErJ#>*eW(X#Nqy=f~MympVZxzEt3PI=w38N z#?(0$kxtn!9_DL|cNy#H5WtH#Wt?NkQtp(Bgv1LTj$~-Ag-uDtAsTy-@G-Z5*(E8R z|LZuCxLj>%O1We&49M1vs5p_Z>#2DKwr|S>X;!Yr)@B+HDG;mOh z2$BBDScO|`N(n0hw+k_k7mMnpc40jyJSKu-9TqK9kj%QG{!SWHl!q0sk+IzvWKXPQ zN~8z`TtSA}jOyV3Au!PNMHq-XigKza_(#Gq)!&?9_+UawL;`8t=Vom~99vT;jpOPoBEbZ!^*!LJWychyhA*0@Z&Xx ztlbsp*DyT0sjo3qaf&t=KDS1((?UsbvNH?8=-O`tZ$xCTBw`^-u_$9oa=-ZlNHZ&ZBUC!7x=GVmJm+9)! zgT$(6FC7`q+V3Q34Z)LF_$`KVHBL!EVlBiLIus$uVswBuF^2nXwP^aK0g4h1JoJdN zJotavSh*x;n52oh@O;49xYtSFZ|CqkzO&p^v?51*5Q#dbIl-2g!B-V|gx^7sJ>2y8 z(#|p9-S%nf-Yl(xk37c`Kf;WJKZwC#xy_TFZZIHGkq3#yf&9@bNAahSGZ?P} zPs5J5F^k7yQR321{#xX)h@8$hAET8BdSZCS2IVDMLv}pEfb2JgwRZH2FK`C!?-9zG z?up+KS(}d`O1JPq#|O}XRL|jAe1M?RgFC;eiXp|Fg!U&47d=?um-SdD8N(~1?Ui!c zJ8c%zX6M@pg2*St3r-pem*N^*Pso^QHm4Vr)a(h?Fyx-dPvKSHF(j>@E~gnr+2PnIS`HVN0h#Bg{JTj=?7Ocj`I(b^LXs^QUs07B_i7&3VD zBX1UY8SKbIoNlR(U5D2St0357jDl^d=>=C*9dBw7*>*q=L+nLJxRfxL=;1!3ehXnU(dCMXo!%cw*%-G^h z__GH{FqQO17*0_x;Ibza5$stIkfv<}Ux#BCrsY&jfTx3tyYX4Mr6go|__Hxn-hF?}Jy6A*g?>kNVx0Z(hgf)p*^~rBojVzXPjLo*InMr2 zXoo6uQqVwjKWe=q2O8VFrdRweetKwVNk9yF?u2+C#h*yN#9GzY_dwo7JTdeiUSr9g zM5obc>`i>Gn=n3!k0q97s>%wfXB{*z@=dk z!TkINddM*}c`Mx3Qk^$4IG1QC;XqtE%&rna+(8(R@-B=5E?`2i`iyyhh!-pY(C?lh zhaKMt>sNK$mIy{NkZmbAwip$d(n&PbUm$qlsiLU~4x{Nx1Tkr1{3CP;5p;zgfjG>g z7q}sAUH1VvWduee$a5iZxC+q4Lc2temmKa8LGXwd<uV#1+DgCkDB`!SI+;O&3Pp zBMqnVNC>lCtH4r2P%+4>LBI!(&awLX6GZ>fcNYase0E2`8h$7D^euj5ysz;qWhnIl zJg8Tw_ZYi9U40cnSPR(5`caK}FFkmS!a4zKy5?I12}E8a2z|3Sb`3wodjt@oo(-xk zL+6l?=NJQU#p1^s)rh{|nYOrUwL>y1N!LneDG(Pr!RDM9T$^J*BRizBtjKCL68l@O1Ns`%V zaT!!-5*)@)nEXIA{f(wB(x&)TBySgKm1{x@6J13?hq|ysOF3FKWKJ+7S4O1}>HvT0 zUM3@^8g;xabUHz}SrgV34)rLgdVH7xiQyIiB`tjY3QI9_VvD8{A9~2iMl7tA8`@pz zDb>-dD*7+6)1#r#N1K!(WE!S_P!Tr==1Py}#(!}TK6}JAC;Vt4fO>$;JQ1p#ia;6( zF>D_C2TPo_YHZ>^e52%=UWimT&;0ga|Gp;iM{PS13jT6sH8c zGn#3pPLt@asl7kQ93d(Esxe9zY!2npu2C%B9}ObBJ{~*j3d8=$OyZ>xY`M{XdA((PQnkP zU~$7EU4ej%d|274g$%t@uNB<{I8sc`yTb5W8Hxq@J`JnVoybYryDx%eatPWp}}Y%~BRTT=Vc z^I|XZ!ioNt-@uY7f!^{6CZ9}IC; zOf=#mBf|w;3KG&0Dk5LMd*sms8Sc;mEdM*RD8*(3l$JR(WlCvg(dA2*7?KLZ=h1Y z5{yd}$#RY@BnLS;$)^=e8T+J&QmzCn)Liv}O_YkSlEt8UccpR)BwDUrRBa1NNkXMZ z^${Wz^OSEY;e-&(t|Lufv2en)5IB7x3Ino;14ZTS{8P3~S1ENA_6bA!aWbJ{%X;b` zMZBR%npC9*mO?Q*Jya837*SY&qtX=;lm#vZevw@xEHF*q52Kf5X6%Nn)^rKiX3R;(+qWrN=KlnLEFNLBIkjHEC z5X5A?Mo`nQ3YmvsM0qK+t6-Q!jB8?H_6ZY9knJ3v5AdqJ-|q=0`);lYmoTh7nHprP zt9oS3>72?7u1F}4GwIL0=1d_v6J!Sy-WQ&y7=A50i3khraIOB%F*NnxbkN?XXrTbn zQsO0Ey8;tr72Crz#p0OE7W>w2A($huy0$M%a6Uj~Z#5@UeQRMxyU+ED6TUz~s|K3s z7o>BNQxX4#8}XetKuu;NYE9sH{#x}?7QDXkNW(u;^t$v20*HfMKS5@>+zG?XU;oY} zjV!1@>l3Ls;bjF#ru*4T#dOe@5fX5eeJ9sZt_ikke5wp{r9uU%zpL@GEYL-5k6n{P zAXxEdIRTh4o>}-RMbn8V@Vm{COPN#B&L_rmqD?wx`^vntEv9N^p4?LVBrN4t_%x2vab^6_Q zCs~-Nj^&2X>N3r-v)X+*RwnMVs><203|(}JP6k6;6SZloklX^#P-w@s%Ws#4;ze-nd5on-nr8n^_M|$psh)T{$&IN~mZ8d3Ha?B3 z4A?dxV4M`>ssC1ES)Q~aU;aA&Y$}`n0!`XkM3ChTGhTRyRS-QtnBI+6O{x5dr${-WT1`$-A(#Ki>|D;F2P z6=>Emnx1{_${e{$t+I++ZyZ}kboy<8Ej7bAu;kk(43~FR|^|uA%*72;ofi?tXxR51>js*Qs4ju7~yZIeCMDe{^sIal^ zLZX8r*zwxrZ|%9Vpyi4FEs>lQ%Hdw!mx;=>4WI*xb$}0~Qb?|>dH4fgqe&g{+X85z zWcdUqp;-|?Z=iWRX~z_k3jP{PYMzDo$&J}+7L79V7%WVVFKQ%axjRtqMPfQyI4Ieo zJ8q?9yyB@SYq43UikEurQ>s~tny=W!VV4au!bAz3V&y;`KPrhRR-!15YB5@)lW0ZP zP+0%NNmYhs)SX?kkV=@h5t(v>x!CuB`T zBv&u8PCpQ#D=HyKJIge%?feOz@n_5-%70RvDq7;{k692*;|wixPH%db1grygsxGSd zg{V3?XJ=N~6x7MWYYJX~mI=wQ)2>BKoP)z%VTEsL$P~n{WN5;$_I%7&m@urpW+G|d zJ;P|Rxi(UT7)_wP2cY>78Lg7DNzrzGst$No~gwsV;6zWu+ zyl6tV8i+`}3XPZ9UbJoI9#1`v1chp)trr=oL+~PW=dqqEQSi$u&=ktP=1~@1ZK~n~ zv^|Q6M=xp%NrBRTyZy{JRZahVjiDT9_W=zhg0*nak%V!~6cJx_q+N7KU{!_uuMrGB zI)XNFm&K*iL3>_k!ln#g5XwTZX&p&P#si=JCXRG9Uq8i9=qOPqjM(ai`paoXc$v= z>iR5K(2htlx(?rhUTPX`V$;Ax%SdI>bB740*9zyVL^29Uao_0?rUHe!=*jzyE!2dR z87hEvN;mi95@X9Ts*^b?F~@~bv8h?c@u_I?Qfg!^Q(5uM$hN#E8j={3%2kJZ4)hav z^zo3Qqxp*D2o^lRM=uSaZrr##aIqRm{g6`JxiZAxx&Oz z1;^jQk>v`}SH=J!TFwb@Or$#A|CZ~(^CDtFr%ReKK)hx`vd$8iEyRErm(CmDYFyi# zH?4FDD=}uv^@5ZiNFO$v(H2QhPz=6chTlxf8c#4)2Bv1{P{dg1-}A9#GV(RQt{#?+ zWDU5Cm{lx~*EO*Pl8SUTqv&D=w@*w4N(uWeig%`nm4)XSbZ2tfj zz+ui0QZrTzO#+CX7$zRVVsxo91f#@}&mw?h>lxl9+H*dL$+NWXha-;Km=p=k-LW+% z%>?9$rOUE}EU|SF+*v6Z;vbbCvy3PvhSTRJdN7QrHtoCEB`o}&5o8P%HaWH`t4rz6 zUNKBsg!UF*8m0^*0%!9H5+2ZFNe|j7Emx)+3M0d&AW`gVxwBcY0LCmfdL~zMU_pgV z1X;bnWZ3QfjTOK2RMR=D`7~>gn4gpuPb{{5vYsjxO%?^AgK|dr_mxZk6)0Bj%0iL1 zAjE3C(@d=H|KQA$H9GDoRnoC~(2**j%(;?#Y9R2}hpm!ix~D`JvuuaG;M*8m)v65~Fvp>dv%nQoBhr%d&+Kd*@QP2?I>)T%7n1i{h?bi_8A!Fj#s4lF ziL=8-)?7a-Ls~$}xK~caV*$I=!XPGL>4(Md3F?OvB z)x1#-N1=95Ok$a2ahe_xe~KyrYzLcQga(9SXG7lh){a^0xZl)z7KnvKOs&Fp;CuX@ZvHcfqxB7o2xHQhJG9~1s-Bd5V{tX ztDg&Ab*?-T@9fSu;;9SznqXw8ukk8WKpnA+U_>_0hpU{Bd*8u$b}J6Sh~8Mb?FzAA z)axf!r_vs;bk3Jeqc23ZAlN62_$i913-RpB9=+r|_uU+-s-~`1^W-rKC|QQ;Av}&O z6>UsFrMhj7Fr1W>9LuLX9HY+cvMTtk$F^0w5c_BI0QaBQl(3g18$}h53E_#OPB=d1 z+7p|Z$EDSaN{*!)9*zV}uW=+uw5hq1cUKf25(^3zJ1r_n@*+0N5+sVPu`Ff6l!@QQ zvFM9?0@=jhb8RV5@tRG%eQyF&3suUBjXnd&Q-C6JYZmq`~)WF!N@+8_c8%#EJB zidvawP?%oQx&F`}T~7>1`a3HPr^_dL6iEg0Dv>{#(_P2XvxG$f9ciOgr%(S{dyeI0 zk#S4ZEy95F!?t)eRxt@)eb-tE2EEo1jd4ogkSssS(S{s<*p(yvz zk&=^-@NxvsW`+GZpPcO}(jZ$yVjcQis=~WPh`a=J)A+G#;g}Sw^;8tP@Pm}t>p>vsnvVBeo)X`SdJ$l!MSuj) zWNuN7A2to{IGfI*!X+-BWzWniW;O*T3G+ZoW{ov1u}gvq7|>$A>vRxXG1y;&fkeKH zf{Qu1&kD4tpo*4}7)asv9q?6|_FH31lMDbjtQw~0lj~c?z8=k*c&E7=0k`a`EA}qP zc3r{YQ9Q%4p($ThoD>d;%dC`5i5N`zB2PkkF;qLNft_pE?wBT9ATgWDobKzy!KdwW z4uVrnlp13eIplV*vt(3N0j-hv1kp)VUA^Q(Q~|{pW6EcEs*E9@v%uAoE=sv#k<24D zG?EMOk&HdSm*!h(eg~2(QP#S(dP&!l+Gf-w&y?&nY*$#{R7jBLr7a)|32-y$m5W=< zk!1bi&%~%O?w2)P2oBYBSR#5-amF}z22B%9XIlvteFz=QDAMLAyx0siExyRbYP@Uq zNU}(mtC*dyh|I9?CI-t>@I~QToD;R2`w}=yKayh+uW|GF6UWA*V|Ns*h=^z+)+Y+o zig$?pMVUpUwTWNcwh8HR4tabym33fzfSt5+_CEThl2TnoP9VuPnW$onJ-h@`?XnRn zvf$Tv5&VmVWkkdJ}Vj_!>!}~pz3CE&5X(`*O<5+`jBVRA6 zJEA$U_OS{}p~;drRvfT}k+RgKmNdi$MYUw$=(zlGH<+^yNkym*FA_--FA3cjOVcMN zs}^9<3`LqE>=O!tsH-cv6=R9MLPFE5M@A=3#oXyh(m=|7o)k?@H-#jMkAgP!G@UyT zp2cix3S=o)>jkb@J?u<~G&5C}iw#yOaNTH_ths~16x%G2qP*1}Ba?c=bb*Kf0t^Tz z{wG>e-5lsEf_m3lacTP~cby=tX=LRozHw*SQ+yVr5y?eRlts9VKN=cbF3#a}+uJk|+9I zO*aLsZ|AztALIM5Wpq5)OjRV)AEn+hbjqg{-5{yrtg@mz2w5=MQiffD?K335tmh6- zLgWETJK$I<5(KEmtweOL8n`+;DT`%(61t++NJ!Q#IyW)wzVa}z%qq=sCZ~uKVJlIx zUe;+|+*XDoeCx^`Y)^&bb;bIO;js{VsaI#^A{j$fubz&X>fVWg#Ny*A4Vjgz$NKja zt97&^Zn|o)Sj`+@IFzfOqxVj=IspP)?qvDZYu>-CRtGzkkK0UDP&t%x2g=nN^L^n- z;craGtbw6vwh%F!N*VE&wdz>n%5B^Vx&I{yRxZloPvX!bj3X&nqv|1GDhQawSE~75 zt=}n5^(_I3KnqPF3HYn{eM>+3SA=c4;g>FX{|Cd~s=qb5NIQ8AK z{4b4KOHHs2T+mK*ioAzc$dE%#N_@3i&+=`b2({J9eAyzV0ot+7;tVaXOC(M?6eXoM z_gzH_HPFgW%1iUZ^~o}$RJ@;|_fC^Y?Yn_fG?sqTBQmlJPdu`;_+yLZS9+=fxP$x0 zFQ-zs(pWjZvq0nc^@Lodw!?a8Wcq|XMz!mbsEFJAhGr+2?K^w&dohq9Hz#YlH{&G! z$T4HjZ||v9CI0!k4zd2_E%oqSM*%eAiUFHwt{1;LSpDz3k-Dz(hcouK;V^;k?uolJYQf;88%utvBEtMuLP zdUasImXE{~XZ=w}*fI>?dxi&TicU4NR|DmV ziiRK9m~fm>?^QE8^gDxPKtVBL*CiLd@fXp8bQY6*pOk>2V7tMpF2W~;#P7eZT6U#I%Tx8yiL)cNuN z*+iutnk?^#6%4C}h<~le01pS9U6sX}xS1mAx=VcQ`+-t&r`kDm=rUT7oCM>pMJXM$ z?`29j)(*0eB!MOL;2TIr6?NGQ|7DUKSlG{)yGHU4Z|(#&!NYo!UEMk!*5X}Un+ItDqW}d zwDXOEXm!^hw_e`tw>lm){mq>_;u2D?wB3iIvo_2Txfw{_DRE~46UH(&I2{ky+?t5I zKP8Yk9FrLM#k@_bexb%KPB(`wGNX#L*0qv+uI0H2w3?GqTcc6-KBh%b*>kK04i4Ff zD&M#?eA1+Njp3pDk;g&Jel)A}bL|jCKGAE$S;QV0z%WI6IeCaKPWH*r%|bzaAzM?$ zJpF~?P%$}y)~cXlbm?HF#!>W4PI5JxA8EZJ>2PCXl{+z$CK0=-+sYobyXhkwJZL8v;OamPkqMit+FC6?yHBaYcv5$@B)lYkZ_+UnabGqFFBQ z*!UQ*ZOsmkS8#0tO_a#*+aBYbdXe^beUISyR0S-nMofSk4IMl_ukSIi+|R^Me>AFh zmPz&>^g4iLuliO>EKm9{D$R;!(_^4mX`PIi9@kY&{kJR|B17U8ZaIqSZR}ef6N}Y4 z70s5%IH%U?@Lj_rBxIuTwJcQ)j{#Y&P0?(3b*s2|hW~XBuQ|*=bs?!k?V%A=huoR~ChOcUWVx{40W7A!y<7^#O zJ0`#Da|{%fR)kwJF8zV~=u;hTu{ekoER&YM(Zos49nnnT7$a06h)QCxK!=uV8mXT{ z^u;G*q254V8S!Ch4BE7X`CXz|A820?`UJxfaT(ROo<2#;vn;r@AGT#)aKpmqcM^a@m7=;-| z5lj#C=x@J=O&8;q5j#^)b%csz#T8i@R!FBQ6FYf&^n=;XfXpH^g8U)9kp3d;C|Cf^ zcn4fe51Q@6{qp{u#lOp5iLSYnWrK%A;?@w#!Pw{Q=Bhaqn|h}%uQmsbULU= zOwLPBYMDughBVtN1AN6W*-`am?jwoDk1Tf>OV9eVi#=Hif9;TtB>!?Ip zHby1b!A=w=%fQH8DvahJrj8P`iy>Z&y<(EqWW5op%I0wTxnVl#WOAysPv1>ivyqMg zKa4_Wni1e`lh7x{v)74%;X(0KKWdXvHpUg4T11-Cu-*&MGF>*0(aNc~$1%|PEhHbR z^S?C0nYEGC9?aV#>i1s|5*5MyOC*arhI#f;%}Vk_jtt%G)#Cm=CIS@ii0X?i^tqe+ zmSdSe$YonfdfLS(x`|)&7imw%C3?n@Z)(T*d&e@F_$@l1A`!J@J&wuit1`Njt%Gag zfTW6UJl05YAc=-#9uI4{7?Q(m&v~rPUbDp~%c7#L9Ogs|@Lofv+xmqW&M5Soa*S8O zlK{`n96YPV8LHSP+RRxsBr0$ouvRsg@ZG+#bg;ps+$jfD!ahFlne49E z3cCFao6g{V@H6voE(7BDYIYt1AiW8G>#7OnehDwXNC}6U$bP1^Chy@ z4B2b(!SK1omydfbE)b`4roHPo z*QU~@V`e-enYRASOOhgYy8o)B#8_e@!n!*)o9KY~oc~=u1E?YTv)}IUsJ|D!lA*;a z-U->tNfug>biC%eqP=MMn2BTuI_2HYi)YGTzJ()k!7X(7|lG&8H=Y!eKPjS0Mkp)Bb-xwLyB zrSKM~qgbl3Kg!`+$~09VqIiry%mDoYwfZgn5^B6`#jPa~nKrx85UubzqU$aF5^9V| z6nde2h$onR@($}qmCtbA96{dYt7jOqQiURqVvDu0Aa((k1Ps9uFN6{Vfxv4kUSyeFJT#* zBrkg=-(Xe>@bc31g#tKtW*xFq4H=#PJq-&J;5kLkuDR4eu{0%~ zZa|mBoAi#gc06E{q)o}Z-5cg=$&%cC;)cS8O@U$SAx0tC*F-$QupsRi9=j5!CB2v; z&<016-~z{jiYE+K_yvegO~(2`ze7j4N#YIdp9@c>r%#gbl2Hu|_x7u6siOBSE3T@{ z4mv&&ac|lcoO(E?Vw7TkPux)0Jigw4;a&?))egrQj#zf9FMTVr5GNKKMb4So7j{e= zB;}69cU0pUmZc|BQ1ZyE6;k4;w84^H7GIHaf~_C{alx5iODo;SvK7OQdLv;WTI-Lg zl!&kSEfu!UE_7T!r_@8S@T!H19Ce8N`cWoI`Z%7jYbm6ew;ecsD_mJ#q-?o@jwi4+ zL-JQBiK!zEfj1~w8Yu)~5&;ThC)>7^I51CW;AqbA_FqDhgo_Y71u4s?G^d(NhvD&D z@^yJ=^xAuz4=Sw((*JQEdp0pm0ZJOBDR4o@DvD&NCSkF+@-Ad6LFOq!70rfQ9P>4C z#GXxTB<23ID>b>oR#NgiG8MG<%s@mHCQ~4>WeI6 zqq8Y?FoFsktLI?ru2$fdMy?&?_>n~KTaa;QJ|_mNfp+Fcu3Vqum>ZsRM7l7hK8VXb z2!aY`Eh$;5$rZYima#J<$o?UsWp&ZqnOZx`qGt$tp+&TaE%99Xu}il?M3dJ$J5aQ4 zySq~MMxnjH)76$CW2+{gew?MYe9puy?F2s~NeM=%ivRT=|K~sd;~#(j$3Oq)fBom* z|Mu@#wF&e8`;UMA?ccA0163JI%v|Gm#{PwnU9hZ(Yl~xP(o#qklsp0Ms4pAi`874~ zfcP~vPtYul7A7eaJbQ9w2lFT0*!Orc)#wGsl3Coq~?WJGND=6xG9=zJx``*D>Msgobh|jpRt>Z4PdA__qU-6`Wy2q#R$_p&BYg`&cO5ANEX;@dZd;>|woMbnR;12ro%M9M1 zvI3@LiItM&cNVR5Jjh{J#tf<#S(e@(~5-lNf`@5$JqeJwnhrKn8yvU}owXzoae(l3%QE6wsV zT=Hfv+W+Ti8!qg$$OTN%q=n@Gk&55a{yB#XDd)MdIj9`7m< z@_1RxufIfcREgp6=U3b6-c^vi^)xB1)MaQ(BJbh1xd1twldwr&!4aN+X2+-et?Ty0 za6(1K+J+S6#gV+ua`ExMbA)2|%bbQ0rpTBNO*s*<93KK;m0vUX z!F`UfjFLG89S_ibNXWxE^@n#Ni(D)pay@9Y-E9w&b}w`@`Kp2Gc`R9)-d;Yf7Fu?5 z5eb`sGJ>TD!WLP&4NOeJ^1}M!XPJi*Cl%kB@I3t5#S;TmP_t;Ft^;@2xc1-v?e^cJ z8EW_$>7I_^dEMXtZ5PC^A9X-z#xqudbXZdK*A0v@ay4a7vec12^@jMlzA}G&yALj7 zFpzcG&oXquhMHzhB~S9VMkigyBSeTMfVVLirSVvPnsHgvUB}1M+u}c5c49o3Fw_eH zXafAhwDj$1j973Boa=ws0MqntSWuL>Odv3DjUT!ila4*R;UC5a1;Ep%sdZf8T>rxb z7@tb81b-!yOC<irIx}cPa>p8wq@Fz2(wsDK`opTmgFNfCUc;c>HVdJ}y+;8&Y z9*`gA931#Zy|^PQrW>ogU5{*p1+JxizB#de+ee!&i9E(kGRU2HOtSwNR$4IUQF?;U zqyuW#;~^ynQ%IyHNL&;W-e(3|h3F1eF{|+_Qk?)7Y}69Z+F2%^N}p@$rMFSJ@a>fy z`Omx`4<~kjw|Hh1>1bjZuk4KECQ5B2#}TC(2VD^^5&NJGPi2sYBh^U87Hnr8#jqwXDh^h44A~79wU3l-M9Mt_1VzfAk zP|J>hhm^^OXhsg{HxYZm&DUz}jhxaa@2`46zx4cQr+;3)Gs~2@K5+T%a{6=<4rMxt!}zg948D#a6pq*IePpB_#&#cLy*yL6I3bd!|KTNkk;R(q|#D(bFV;`VYz;3J!+y^@fTQK z(Snk6hp1ZK&k)tbT+uA=W{+hPa^B^1?!qkFnKFzSOijgIo(Y4FLMlQjA5}Y zJ3>SZqO87R<5A*ThVb!2{37sNe>oYKv%0=tzRdMI%Rz}b*Wap>EF|4}kQIsrwhJV2 z^Fl5%moR>A+W^86pXH?Tw@tCsr6VON*R=H%DxXNX{&Lb7i>-Q%W&KO_-`*=nS;QRN ziM5Lv`Df8QGQWl8OAfCsi8;>7gz_PNW|Ls~-9*c^U*e$2GgY!bC-Lk0OLdTiBHMU{ z#wNhHSCff3hLhHv(-7U7CdG2(t{lUK?lUjcX?Svu zgCL`|RRp^v;VKd?-{J{m8HVdQg_Jt{HXZb(ydlP{GDam4S12@&70~`gNXAYc!KrZa zS_`#l{6(+DRj+DuQEQrz>sOX@>iV$>Au%6+!PIGsm#hm{s@a18tNA#(1)r96D8k6v>M42R_ zbb3vJkV>@6!i^coN@WxeaV_FKhL+wy<`ASx_tFlTQ3WaEO2D$l7r(>ek7)QvUZSnO|v`Os+RV0gbM5YwuXc$o!2tKi(j~zH3$tR1!RMeUuvGHn@V1CXPrx1C;TvK7z0jBgHOLe%lFycF2CHAA zwlm1)_-)K3SVQaY;&PB4aVza`Vc3CU#*$2jm+~o1y^tTy!A!pPb?$}&@gCH}wNz7E6+A6S3p<)>^o=m}LW z7Rk>nJka^97+8NBqfHG34H;RXV7#ysENKQrMp9ZE?O({mWMO@TWo%LyDS)9!m$iv( zTuo}`Yb@oe@IsC-9f&IIl>##qu}N`jX<)Z)FflG8Ii2;RyG;)vh5Gd$XG+q^Hb#B+ z@-v}G>Gz#g#>-EnHY`G-p&XZ|j^dHYKE&~GSBZ>Y;)tSCVyEz3VOBEL>)TkK)70Qa?%&abkhv0}XFoHZ;`~R`;ArPj!cwHXE@z7rJz24Wk`+_y&m{d0@*=&-2uf_? zg8lLZl07@;GKNk3dN^l#lVRa)2f1>G73W_n5U@GEq))gt4*DHt9bmp|GM4J&U@x(9{N6-8A~%%9 z3L6(9wN#H_a|A6=G__;(oEFNFqBEs7N+MQY;z3AED0;dva6CNe7OIh+H&v0KRAYi| zuh1qWEzOwD*=yLDj$bK8I#gvVZyp!KT3wYQ|A8T01ualK)cu!wk%&U}^O!BUgBdZu zM;1PAzLl#Q*~qBUNkaRBPhF&X%D;BZgy46&pPgt*XOv-pGAg!?x5aC#g!Qw?&!Qaj5F7SY?~_tC*Y85VWl1TafeEKF1T)TNrW0h_ zFwJ9JQ9e5Vg<`QTF1hJQ-p0F1x)dTds!CTEi{jt~jG|2TO++)d37wM<8C`>U?GTM! z!NTI%(XqPtgMIf>H{QZN-aP0e3L62$aZF5z%0z5U5@z<2fF)JxF`3c zBh8#aM5rjfB(+P9jSyveve8u&WbyaSP; zP{K+H1JeNU{(46f83!^HM?i>^=$t3FePc~J=gD#e_dI2EdFMT)mu;RWSBbmlsT8?+ z9%B@>95x8t%Y`q2fODYSs2iHXIB<|G9Yes31L^n_$tNntobw)v#^!l)Z>D)3W#894 z>KPjqZU`9oq*g8`3?H z@Z&XOy9df}rhT9yN_WR*aX9f#EzmX6rcKk`<;ETJ{dLp_3K&yp#X-B*wPv0cAa|{z zi!R!)yDH*0H5FM|)j8#f+U_M+Wtj(#vMSdUj3WWdYyNg2ys07u_rSXgfX zx+lKw%Aa;mq(M{A+9b>h?dx=k}4?GL%p~thhAR=_GaW-WR6&%W0H3PpCR5X^| z^qNcA?O79#XkTx8kF;P38_K=M=ud46W6!26aiV#T43&g~uU1jJ{P-GFT+6-3@hO{3 zyjS>SA%wu%4Ju+Ke>Tryez4;JlXhU<4#-o{UpdLgoGJbeqzoG zN#+Gb5w!|w_dvPs*A$G*ybvao3*o5zK<_}xbQ`<;J=1XoE1Jf4&*HzL31iT>|sSJ}ankPPbd5`9ajMWfg$Hls*I`~>^nbEoC90z3sxIi+QO1W?@OA-uLct=pgxXBlb?!--+Z=2cm%K30ld~{O7dO;5+#VM@K zhxnrLs_jE0>8K={3nN3cgg$gnWNLu2eN4)*QdRJy31bX~Z%dhx@mWIGxG=JZxGiN! zmZ?zq{q7kS;~@8!xks{qO|EG-uaX0aEL>ZC!C{7sq(eg%-`Y^#(cF!pq)@0Wqj$7O zOBv+eWiM5?eV6pnE5uzWU-J3bP`;2GjVV43Dq`wF+5O1EdiV7(Qc>A|@$b%q>=+Cv z-ne}vmEnSkSiSB+d3!2~d&&_DRGRztiM@K^{)tMm`Ltmd()H7^k7TBx(BU?@DWMS@ zT?yjU2~xCRegX>?p_A1+^g(q z;cH8795R5osgMCY(fUPS4sF!=tciTWk=g5-c@A8zes8G`bSDR>Ar4;!6~D~yvkc_rn%-x z|3qa++b1@+d2h@w1d7Y2Xqp4e?ow>-auC5(7>pmMnna=OG}W0!Dp>=RiGc1;}rM8%T!MbZE* zfb@@)lGi^{7Tvg4`IHq7{)y`0*eAA^ysSP0ic5jvnrh4|5mL?854}u^xmStg6>RRF zNJDUA^+1iDx=5Ec#PtP`_ERM3EpF03QYLa-;xIEo0O_CD+A@F1>JIxNX;o9?cFlp8 zl)N^SY=;wk?h=PdI(+3ys`)3jb`}|uAz0GCNZp~}lA9_$#X+VFqU5Nt85BiK0!WkG zoY10ygKT(-1_KAdvA8 zA$e_bhrifV^fFmavAIhe_J#44hU$TpEXrB*FS2>@62&Y^^4d_|Wg^EV4kPA-UbIha zUA#n8U$JCF2Awd={r+nH6d7A5p5ooT%7+Xm`X?#})IL$J{qav!ENM&LXM4%3t8jfN zWjN8j%BO63wNGqayu=19Y4h@~tk>N$pz&Jc*tF3-UA8dqTbCLU;BK5EiIBMvYAypY zX0Npo#6TATq)i*PB?z@>bI>4D= z-wjIyr8!`Rz#g%Q?)oXZO!;8wQQLGSCn~GgB@Xk=g;4WPR4nN}MWzF)NUu#Bs+U0Q zO7i+gK9teoUgb^hLaSqEpt7x!@bI04*0WAl;aWn6QyPDzV4xU@e)OU z&Gp03x_F5OP-O{hsQnsRHW{_}kY=QBTWux|yqYNjy#2J4Yr$`>7-1TY0 z*t~4?p=bQq9Kw%`T^rl zMs7?~4Ue|5WzLDp406d$eN1DPBox&8-N57mNc$;vvTW2ol0|KT&t2l&%+blK0+T^0GY;#G0xce0jk^ z?o~eIq(l2eIf>doQL&_JSFxNx85p+YeKt>_KUu}t_$|_|DfFUCoM-FFOV4NXf_;MU zQu4Z{8l(|7X)|Ttx_F7X%*p|E$<6M>#w-a(s*7}KL!egxX}|74riN^C!{!2UmpFq= z%G)Q7stLe9QL&_bku*Yzi?qp2DRXNMdW|Za=w9V0lk)zFtyxmHO2q&>r!?_7N($YsjrjZJ;?#wJc|Ez?+v zt1i+sQ2U$Au(=isPPdFUxa4l$*wj;?C)nJ5i@LGNKCyX*4O_Bxw4o>NCvMW_Aj;_k zpSxH2XdP|nAFZPeoY=bdt#98d)wgezV(3X@*NzjFf#EU`!O6xf`9`ahE6jTxZEz)T zFXOznh0(lKs&C#Z#fd6w=Q7Y6tx_&+2AL1DCGQ}YQ}{>9vQhUco3~2g;V3)WhEdzR z?(2TZ44eHF+qX(FZmM-`pn0oQh>OO;oQX88jiC0eQhobYsn}R05I0{ACpHdOu>rI( zOLC%e?OZWA=(Rxpky7&7M>3J7F}b_ebDoFpuIy-+B|9y7O<_KC(&lxAIe}vts532$ z;nuoUiW61!n@gPLJD`R)TBYoZl=(3GDN?B>o}zzb>#59GsEzGtylxf2a2e>{+~#E& zxQZRyw0TI$>mMn@iSAYMxCKx8CpJ!z40@}SEqUK)m2w5fQ%YW&+|661X!uZU?vnf2 zx>ah>JD}`~Y~L!ygc8N(K9n+%;}WNNs}$>!TU+M6tZlF_vVE)6(7siQ9q^5Z7;vJh zJ9ZhUd8^d$Myr%-nZKGB><_VN{JLJkRyoaErH1CMQgCEzmegCN?AQH9tCY(@WAj7~ z4@c<-^DVx9TF-gr#KuXNi1VsRabn{X$xH8mvY#S>-quf%@T7Q(_Umrm*o3pFtX}sm z>c%Gf#8I_>+TY@ zWMfB+6IE=$zew54?>*0Yzn^s;BcWviXGl@h;0oZGk~6WMkqGW@)S*?y|hzWl2`B@RchS z=3iuc$@`F!*JjE`>#5A+_luer`6BhcxHPr@LHfl5F z(0ZjjIeEqAE&~w?5;y6e*xWLYlvrbOzhv2{&6F=0PIRyGH7Ya6J#qYL?JSO3^14rP z)N`I;2PXkKGLfb&2Zd+X)-sP16`OnH=0v$t-ak>Xq$wr=vUS-gN6NBM8%oN+goWW= zWhVoa_KA(>Jl_Zj`s!Y@I^C z(FrMI=AM4wNSQ)+ukzk_Dl;%XTC=3yDrFi$04Z%=Tk<|+k*9y83@5teel%VwfBSjJ zB2ODeZS%UXn@tiT`CxO?7s-wvS{gsu1V)kvB67?CHlA{Li^(~H&E2>7#x@&Mns<-JMS3?*lzA5$NSOk4Z}K50=hzJN zkZz6*B)PzAW6cLr4hy$MFQYdFo7+d?lnCu@A33ykYr8?x+osOYcrC}R8zjALAYZcD z$mMg=s)B=jAY~Ta22u`R@`03|vd!irvsSM~hI=IO8^Te5vP@}_3Mc$#kSv@?j;uI7rQ`J5a zcc-xqzrT@hiyBiWio>3P5ZhPJ2S3m|llX{wlKz>xg}kHY(gU;~WN|7abgq*VmHx3& zXPB#!9VV2VsG#&ObHqmx3~wKL$CXkK(?9gl$x%Y)Yrj9DXz2PGMLDp+N*pOe)i#uO z=}_5FKI8<=&g0I=uD7j?ixZWB-8~_nMV?-c;j+myNE17fycU#$OqkhF>WWSKNcuU2 z=M3L^jOnd#WaAQVPLw6yE|7FvD09oxk$1*qsOEf=Hk_y&DjP;QWP3f%Kvrc5+fc^br)&GNGZ}Nx z&c1)7_A6{CWeJE6rR)!}j~wMzT>nU!Ml!V|`8`!;(A_80m8qoNhxY zn@)Tv|*5QD)?97%_kw-y?hBu1~aKl)*du9%WL>hLPaVHP$wa^tE1}Xv5fe zL>?xPtj2d?eEg_a=-wlBPJ+X27-bm8hEY~l*f6GS%T;#EhLL`GB%7d6Jf(B`&VojSy|Wk9tY(v*)U2w*S<%Yez9T1@oapLqe?-z zFjDl}_|51A>^6*@3M;v^rkp@wqa~M#p6Lsb?X>F|4^^crZpu4*OamEv2l|>_b8kE zZ5YY=U1M$E_#W@7pvs1^@$NHXg|eN*hViLhp-tUTw0U9Z>(ot zl+3lIwH`8S)0)Ipc6@S~hMV8hs}S7_fO&O&2aH=euBJ<9fO zo|I8X!iln1#J)!vopE6tnFf1J85c%fb?5RU1BisAuwm?!=CWaIyt3)RE+iGbwqd-t zwjW1XL2kp?c%uvVDBDopq zPtB&aT(x7vI5xH)V`7)k3MP!4*f@vO=@uv(#!kILlhz$A*Mh@s81Kr9vtg7YMr{}= zYr1}gHjJ#pzCO{0QFhqdFv|WC8^&I}LK{YA7&X2}Ie^fHQ7*2w@A0Kxp$+4!aSo}| zO#v>9h}_0+reo&8HTT#scFOy3Y2A8l1Y-&0Fhd(gro=S9N2UT@pJ>C#oWSc7ZCcCO z#x{(yCDw-V**J#;JE~V`!^npFYs%R7IH*@>!$`AbV;E(JlMSPc&e-=zFW)uRHjHd$ zx<1i`ksTD`L>ES8P7AGI!`P`;Xv4_dfX4SI+cs?&HuV0~kkFUl#B&zmW#{h0}e5y<9J4@l( z-s4?%IomMGXATIsAT8uh52(uIX#a*!Or>uh53^uDlN$#)o=^HjEGDeb_KI zULDTNRJl6bhLN$4*W6>@BeN8*PqbldyqSl4l=Fsd7+>lY+V{xDlE(Kaw=TFaKID8) z_a4b$14P3-7gP9^_hG}>sYslCk8J>@jc#K#{fvX3e9ETqa2Q8-{VugLL0`X z%0SvM_N`+8kG^#b;4!FIXy4<|ItG9N(E82D(SbItDJ^LHu1Dp4xG+BD3@n${&rW$C zHjJ_w$A*!ij@Oj2VU*Q4HjHwTjSZu$#<5|PlWc4lWi^fsqnu=8!zin9Y#8Mv8yiMh zjbpS&ie; zx|fq|Y#3!Vjt!%nWMji9t8r`?%4!@J#+RIA ztj4inl#^_17-cn%4Wpc7W5Xz`acmgnBpVw> zS&d`EC@0z2Fv@Bi8%8KM>)yHhEdM) zw_&7^v~A3Ol+`#kjB=8VeUGvl$A(c(vaw;5)i^eca*~Y=qpZfUVU&|>Y#3!Vjt!%n zWMji9t8r`?Z)l+`#Ut#2e# z+UglvDpVxShEYzkvF}k<udao391?m;rFt*++b))SAAX@5~d+WVYx4W#yvG1|OnsoO(VJ z0&FNd8R&D#4ga)#i+9pLjajmjgb-BhPvzdr2@W=pL+j-b_d&L!+f4cTk@~^q zASz5-zs8aMOO0RSC>t(Zyhpt{*yM9MiW=vvI8j-YE}uWT*4|ynULn@Hn;CR?+@y|h zgAN3()Ln*Jas(R-4wXQ+k3>fZfo>z-OKaMv4{;1ZbN4QpZ`>O3mlPWIU5+x*?HrVuS(i8TH3UMFGUamT@FLRK#hWp5$uR)os_K~z#iwEf<-m|er zyvS5j=}64}DHC}1nJnN?QaA!!4wyqXC=13u@+R5Hl$gU!mN~j4Cq|;gx_u;h7{x^< zaURdc0n6dhdhjSGDr3XGNXo#}3pZstD^A)O9rTIC`Xws3i4SZgHC3_ z=TGy2zkVd6KL=RC0rNF59PZjTOXaWDnXgfq27{TZf3cNQSQ}k$3iT18E>M5nz1w8X zu+kGYlsY=*aywo7t%cD@P*4dYliNpRuy{Z=;)5KlXdlVc8NrzTk+Qt!-gg#bK3PY8PVkNM0wQce)^j+cX5M7i$#|Q6qHOE3v6d^aY#8OjsxX!u zAxS7yhOyieJEgrlQ#(*ppscGjgULZWb|VTd?;l>m498I}QAq;8fs@TcGOA&!oO^#) zG&i{jH(Z%l_KA(B#$W)-sWCQ;GPr7=D62j^#{{gU6Jf(BH!j&H%AOw=YdwM2g>jH+ zDEmaB-q&i@##(mh*f7fN)%J;Ueu|B?+-79MDAQ#2i85zmV=bqh*f91H#J{S%vQLz= zXl<-zy2OT2rt$0(8~3U_F~_B;;@N1NDC0oxiE^)xOY4`c%5^F8l5<||6C2O{fYx&E zhYh3b1MyE(7QRhuS=?;HDAQN|i7Jg_V=ZT>+AvCI!9P(216-_iz{`bkl+~2}iAopR zSj!Na4Wpb->Yu3mLK|xtl(S)cw$_EC^b2jQWth*#T27bnPn5|e(*hXfW)>SpIjPe; zk$Eht9@V5ZC#rk2VeC|^n0=z0t7&5`x7^w=$~g=6iIh8D`!hDyatfvmqs*AwC(0cq zHr5m@UEiY(qnuf3pV)YY0n2D)lGBE9R5pcsBFP`Va^|Z}(EbFy=v|*HcEBq51`_~L)Q3WM7j0~b_e2;R=ge%Q%vRK2$T23AG zPi*X8KW=g-gbm}Xv42fGQ|UsR){MSr%a06fXe`ZIPxN~}^h7_G)^{dCHoiyc7rL}& zzBO25#?T5g(jVWbVW zu{5J+79d)BntBqQjkT=DwojCPp-bzBEUmO*lyl?k6Qy5hV=ap{!{%_R;z%nfh0O~v zPgG8q4dheirCcB>_7&RD2eR>y^5;X(^z(u2mE~;Tq^z{_PgLK+0&T4W!&{ z>;ozLq5UJ}ep(lA`WnT<@lRB;+(w(d2EviGfs`{yd>~~!$p%u^pZh?{)>s=z8LY8^ z96J?JGJ6`Il*p+ttbe53Mr0q^$@QxCkwg%o=#@ARtH!aUpLZ$O>?7$P6H>@*&SGql z%AMLLN=6UGY2D=WrILR3k-eTV9N|uc&db?anRkncAC;3KYIq}dxhz(m4; zv7vm(x+?!jSq5d3=fV8;#^j-5vNgpSe$`mIF{?_6b=TgYPfb;`xcZD)RZ8vJM-F$T zDeiYz!m$os40{k<dxxfJf)mDgPcoopys*CgbIOP|+6j?}WDe9DGL8_F== zuE}#V=Tf|e9~FPO{g`I!Ym|vC_cF&HSs7)6$wV#1M(%BncbPWwkCgKne9T$sryh{$ zqm5YXLRt7=5-bwZ$iB@{)|&Z8$|5Njb8<(rLCkzXeauV|H21-L_ELCw@`#N9qtrki zYvStbP>g%zAmd~UXgznb@96MW?8~I1dF-|__<4tu*IZ`&+`cTS*g%4%xAR&m$AfXK<-9^GzvF}pvDfXe1 zgH?Pewa4r7B|Al0-{rGw{(7F$JP3}k9^_MI5bdj!H6do8xxYW<5?~uh3U;nVn}4EG z6ZVNRm}g%kYDXB>E|9&PKGE4nHZBmQ??kRxuwj%|wSA%-BIpIy!CERt`$Sn3VPh?a zMc5LJd86WKd*vluq>Q}SKr$XwJVZ0%bRT4cjD4bX^E&%T8B%u{XppnzZ22?DmVckz zulUN9CG8(MHm);ZCbM+HU3$M{=-Z|a@eFw6`YK%`h|QMbHM(p$zEu3zB{)qo$^&=r z@_}nB@b;mU8Df)%qLolY9_$mTy%a2DA1R9(O%B2u2v_Tp&+Q{+ZN8})*>I>HqkW>B znBlsMjE+!s5H7VlS(|S^#ZG7R!eVfIJKl|YIW7mmmEz@?rS$!SUU+e&4Wy)w4`gdE z`SFlmvJYhA&IxEEV~Q?qu-1ey4}oHFIRoq(GmtKMv1y}s#Jgzsa=WY#SR{z)mHf+~i}Q_>xADx7&|pHF6@CS4JB|D*QS@ZTD%v7zcFCKej}B$q}qJ zka9b(52TEN*+A+>7WYVI&kGK6d2(#LRHCOsSNV1B+a9IMZ40204XD>#ZUTwjrxI+Y z0DAt&B2|;voTv&lJ5wdHR#c(w)(9~LKzVicktC9Zn6!_iY(mIM|48ZI*hfBOuE0L> zDXmHS$euH=U!#5G@K8pJedJ4e5B8DcO=W4_Bl{m|WY|Y`GMD2YDc5Y;N8V%(-9D1l zej=-39|>D34Q?6*y&eW-LrFQ05NN^o#`8mT5GOk*|FkE6K_sbW{VqHMEa^YvVWDb2IX!eE-MJ! za-LTwyOP{A5s4=irFGv9Lo<|p*YjH`$XCH zZi{pbEM*nAP%;CmZSeCo$l&LlXW;lduR;1d_El1pA*7IflQL9k3!#^^(M>;(f$%aS zZ_>|FjCpGteX!Hm~P!9!ayIm#8tG317t#zE%4UG+`iK}j|<;xghkimOZ&N{-z^-IWX! zJUrnxQ1PI`873DIW0O93L~;$xN$kj8G&3X?xgr((HQoAwxnW8ac}hG^R0YWjoVi6ig-AA9fLYuRxe z34WD__CLD-McniI9L`^~?AaAY5(!Z-cHl9LX7iD3xY7C!C&QqC3}08zxiIL`;l?#`)|1;?heY$iSmHlt zysQp+=7WWqwh@QV^_?h>7)6}22V}P_(cC0&ww7)U{nc#0SJcV5K9b2WD2$w1 zM#MGq^<|zNNhC83eYWIh8PseMztjCj1(u-SX(PikCqI;^iFDn{biczBVoW*&cvN-t zmCIQ8Mu|Zo|Xt%n~Nfc9NFjR0Nr}GSm;Ht;9+X&dBtPuiu7IOFeC6s1Zz$Wf!LK&aTU`3-vVFP!Yg#6!TU>av6Q4*-!yyX!#_*M zhO$!G>4|mu*%%Bybj!NC7KunhLbwnRvRm*AnXl*R6q=dGM9ezci<04|X$V8>>A21` zg?9?s@DpN~;Vzu4`?ZvUwZTHlhMy)>mkmBmvpp{YrC`qUkXz&l7bhpP+UG9(fXo^;2DF48Wftwh@XAY$L0l6Mu@h9fhRET7@EMvEvJu%9tM(ez{?;{>zm8DGLw zt7%BQ!3jD(W;+f~D>#3$6Tab?ynaX~&$D^M%fjo3X&XZcVj3|_%$)9ZSk*kK<(%Ve zo=HR`dXD_nJYuxO(}+_7LQ&w4Ejq)x&1llB2o zJNal&2x_^=6Uv*31O~xoo*qrazk`i3tqZ^@7A^KP=8C@vj)*)a7!<6eJmwIJL9!fL zQST!#GwTPg$A9y{&4`$uwi3w!g5{nb%QX}Rq^-nz&0uAwtwj7K>Uh#=+aN2C77?1v zd`028Z{)RQ$8ziASBqIIp@@h&o*m0EeCLtfhVgbUzLd(EiDxs>D#{KfQf3CHMfOlb z(t)_;w%%c=M6(dHf(UJwb8GwY-^In3pL%nn;`)_#Ajfm-?z&$1Yq)+0h*PP`Z*gbHoGf zV>fpQF~jf4-1iD1C*gCF>=88LMSifwrRQf2pWdad+`4Fo%UTJ2eYCenR${??{pY90 zFTVZu-Q&}<&px;XerwD_VYhH`^zUkJ^T9ox8FX#{im0Y zf5NXYAnE~sXi1(S>o24rFFnNCVa{kYg^4t$LD#$8A=%dT{z9IJvz__j?AH%}r0p@Y zUB8fy>kN55BO5z@Ar1J)AbvO$^D&4Y_F6v%@x%1?5#g~0i!wVi@UjBL{E{3l+*X|X zZD3xwH2oON@xqRN#zbZLBzJH=e(>PgVdB51b|QR}f6#yVD9DICyNqsa6h{T)4}M3U zt=#3nX@tB`j_RWzKOAk{LuRLZx=>Z}j0q1XIp>!WKAkbs6NHS*!7|G39r)Tk8nKU- zdfLVdlA`lK<`F*}!u%M-!)NBgo!r^RdWDnPhETmFnC-knRPNueJA?U?0v8LxiB`o{ zslFqp`r&qVQ27Oh<~!e=E__9vXFh+Xm4Xbx)Tj4$V1D?j^K7Vrc_Ayz88f|WmbX*k z)F(Ih4pSd|1LgaUnGeq25DgkDoM)qeY}uV;N1889E}%>)15K%d>=17j6P%LeGzP+ z(I#SmmP$d_SE#Ww!H!@H%}>*M;U@4rq=uoF0uIJ4RuOJLFFTBnC7&9+aDm+6P+gx|y;nqii z_7@)Be;nu3ks@%DMab&^K0TbRy?Bd{o>HKESeJV3-+w)8!$~E?tcCw5k<@+X67v&5RVSrPzN;pn9qm7 zhwefm(DRt4!?wVTLzl_O(15Jb!9kziK!F)A(zKlyk}iJCc=i|GESxdZ{_SunYs5!k z4v{lv*ck?f3{0dnIocJ2WH$PaHz?nrI_a}P)?v7imHIsO(1~T&{Rn+;Fs26Rh3C8< zWhs(tMYCUiAr-tu$UbtMYO6WWk}c-?nAV(YNzfsRv^t;{1pViUazHOUx%ep1XiW3W$4i6{zu!8qQ^V4JjN+sDby`ln zXq}clJhk{s*~$PkP5p7W@P2wXr1+mXJCS`jSfvJ^#v2H2k!>RyQNvQ?1U!B_nQm|u zI6~BT{6x(+xC$H*c@37nF;PgebNoat;Z>kv=^A>`$Rd(;PN#S~bx<#5-#hOp`2oOT zay(I|`9cPtkFxYqt=W$QMaA#yPMW$=!l zs7t8>KW0fGFKXzaq@TOt@kVr+waWwC_7#Q7FOh#{V1}pZ?&V;sooi%gcHPgAl?11r z0U0?b24oaC$xl#`VPD_y3`|^K2bkIL*4%|RFX`dzE|ft$vpo+P-rF0Hk&mBe5W?BV zPkJcxH0%tom-EB9MkkyB83iEnkl|z5{9rmMH0L8|*+G^N&A*aOI&irtOu~q{z^12Mj59c5{cRYXo z;z4)B^z@`7)N=Tljw`#s&h&5&VMxe;jJz%b@^}Xc0ohS< z-zmJ;$}=6Y-NTQeIm}R#o*{@Xjy}^-{psjQzf{ohW46utLMHT&!VGf_7z=5RB8T}& z4|6;jkcaz*GpZL|-#qe6pTjJB`3WjTmX5abQp)!8;!Mv_tk^Rk4|n923sn-&9XBTE zLXqo_!VERqhMgD6f}ZWn&(M6hBez^AC;U-Xh7M9XPL9ezhdXizdPGc5+j*(V)JF^_ zN(x}19QqZASn<(r!Wzm6@(jYero$&4qL1SzJKn+L`+*gW!%9BOt&lb-%g-!7!x zEvE}rm(DvyY`u#Os4#x#t&BA4;1H zJ1^8x{D|$nA4}Jc49>tQj-npvb%ckb_?v518WR*|5j7?#)FBym;ydtq-}A#6zC<-3 zqo{`g8GZWaCulfc+O!}6-r)#4xzNk zzzjA2`5D?G^_c+~d0hr%6ivtvCf?x$3^Fi7X_J9D9PY>=dqL3k^b8?+!O?C4?lBH` zGhCOymplAocqm~qWTG9V9k>GGUpa8ant) zpO?cOxjB|LrI|jXy888==NA$#2_lCxZD$E~UAHsMA>sv z3wjt6gkss(yPjU0D=ORuJ5qKy0T~4&4alP%Iaqmkq-#B)j!Q5>Sw8_EmQmM@Nk9A< z!5ZfZ&rdo+Dc48SfD9vYS*HuZ&B&WcGkraU^>Ff-r7rxz!-;b1!O51MA(SycdeVUy zIC2|$k-8jNyHMJcmQ~~RRn+x7(~;!x@JSD!5#%R5OuCwfM0VJtSNnXl_IvHZ+)_rz zqtn+|MaOHpR+Rh-_Kv)rsEmy9I?^{>QN{RZ0-;83(DU@9_s8GhAdC{77x^=&4+U7p zq=$91^1~S>f-)eZ&E0^E&NX9#!W$d|GZbLuCw&Nu=B0-dzWdR%98O0EDAwWl8ysAG zM>jb6NgqPBlz}-#8oB(WPf^zm$fIK(>k!}Iq`xamy|C+Nr7=OFrYp~Ml(q`&OwSN1 z1|5B-L&$gZ<}n_BgM%Vzk%MGRP$tFqbl#=kdZf&pY-kU zM|{w@M6O4k=}RBlnPxhKd`C}uTs<&7Ly%eq%iVyC0u;ssh1V?x=JC>|bqS?S`QZ!` zK^c&TN93U14AxP8E5>ztz#s#&7MQ$tIg(#UYbb3>&k%HxM{n=z;brsIH7uKF3}&3Q zDZLegl+ohMV}{bE{G^A8pbW^v9XY5s49vwG?m630lo^-f|;TJ*nn;J=rLp$@BVTtPe3@wolYd{|D8zQ&z;SSP< zTmQqE-kqYZr?+>=G9o+EGX$yS!Dl+GjJz4c%E*x`VcOJ1#@2;do6?F<_;Hb)`5mcS zB8M~I^|0!-0eQ3|w{=StL>^7c9x}#b!?0T)=9WsYqdqK~ zXAEYTTgsU9P}*c*BKUsv3@uTtD?dY_4#|Lw&NX8&*W>+!A=Dw|7w6EGzquCWOAqG| zCW0~`qkGUiWLP#YKk2Aa6$O0Ko;K7{!B%WcdYH8-Kb(gbq{B1VqoWDiaJ;l>L$ElS z^lU_K8$xMQesPXnWM_KPM>w1ZZysZ)Lo%$4KK=6y!n=fM($h>ILur#?XPC7qKb(gb zq}#^BUy=hdiY6F?8E0+EPkJbA%G)`Gn*a2qPlp$z+fdvfhBm6 zUy|o1Xbvwj@(T$C6At&@=TP&XpP|DG(rxqMFUbLUyd#I~Fp(pd_TJ}E+LT{ND57@s zclr`OBS^0!lx4%;92!kP1S!}&jKPdcRHwIMlwmmD&ck0OY|G&<695@0{`2c7tZ|p$ z-tkiTaHb>E-|>@v_{)TC*`luJXXx;X9#Ir4?Zza%<|}M6JP$Z zwkdn412lf_kezmb9{xC?U>@zv70k$`$u1^fqMX?E)s%LV0D8Q_3810GDZMiRbUj*z zRxpot=?do2K3%~)+*#^QH>g()(70fAek>8j;S%lZtlLLDAYi1Z4euo%_qRd)w$CY2C zLwMcc7>jzNk5d%=ept^%PhH4WFHO$>;Ox1{c&g<0A zFMep3g5A_H6qTqBH#7{2I);YzZjBM$qHj^d(CP3@lidla-GZslcRnum>vX=0oIS(P zF4F8dh93Tw6tmPvLIlUqA^K=GMl_V4IEIGFHl5vh3iG==sB;*Avrt1JXnv~ZFmIkQ zRd~^J@O4mknjy@;evlZ3LgjI|p-cEM&M`DB1C*corHhVc$Iwu>>a6@Fe0}AhqLfK+ z>RG6vT+Bg54u#-b&q5ue^>3kuv0VcdPJiS~S*T$-R|mBVpSM}4VX+towGYK}7U~#% zOjxMlLuLnc2m|L9YM7_eL5)+Rqk?5JDF8lu@tuDCaCK1QTzd}c7C-K-@56E-1tfWj z;*-UvNrOf=XT}JiWBnO}m@6Ypt+J`wpu%gqJ;(d1Tnc)oT7(SU95Fk$u z>KNWpS*C`sG91+7%O-TtsYfd{|4{^`di0n+zfz|g+yLPDS@e>zj81Y%O?`9-8olqM zZ&$}qTq#}mg2pnB$?nIA?~N6O_tn9ttHJ#_{KBe2pk)71ZW!}>?UvHvK4j*>0Q@Wo z$r%e7MU**aSf=a}KoQC4wx(b6sJK}RhM)|5asc421spJDYaPPx3;5q@_qwRgZ(uA$ z_rb@IF$5dJ7svYm$P0J_azWD`kt_d!fdqM>7o1)J0FBNT$I>D40W8qymdODP#jX}; zv|HuRR^%OwzAJ_yyICReV0a3qcR+~IBWKOAG)yX#->Z=-Fj`WMrQzGczE7W3$e9;S zzq66uzf%q2l^~R%Y3F*I=SV`|%|rUzdfUR+pg-$aQ{Dw4&7p^x zY_ZfDE>359r3_rykJEKoA$Ij^NaO^xI~+SBU(p!P zFh!|hCj?d3V?mCc(b?hH8TpEiozdCh*cthXhMl3}#jrEHLw4+p&JM@U$X9gijLr_n z&d67E?2OJ1!_M%XnqlV>#i$)SBVW<6GdepQJ0oAwu`@b53_B0czl0B&F#nQcXXGmy zhht~tD>`;YXNO^DnBc*%bBkisj-8RO=-3&Z9gdxmujtqrogL{1bEtiKiY6&< z=oE@%Ekh$O%rP|DmGd)?;!(k^sbOcBo7u55^1>WDqg~mtGxEY5JEL9Mu`}|*3_HUb zn}(f-7a_+c627)^?2NoHXFQ`_*|9V7!VEh@iM?TGSaH#@^Y}0L>F}hgSf621RcAaS zFU%OvFx`-0XMO5*?bVWFXLNQrc1B*9V`p@BICe%}m}6&jb{KXZUR4M@3Lk1Yb{_u) zk7{gz59Zhz`HIH8Ptn<7*crZ1H|z|n;5v3jzM^C2@n7)M;f1-uqwo=pF`kDf5rCax z5&_4~vM_D4#UpFbLnB;!(4ifosq9-j3=sJUB8ub?7TsoAxuSW z*cs-|F~$?mP!Au^!;5rbeTG%Kobil&MQ1#35N9~NaA1GJ#o^&Rnh(#!TkMR^j{Ll% z1a#ml=I0$XpbzKKe2RQU!_KhKy)mBM@k)U?%;n?Q8TpFNct&T3W9RX423+a~Yu>Q4 zKmHB<9;36vnD@hL1DElP&JM%QFnhhhqbWK&96KXl(Xlf+ zI~+SBU(vBMIy($I!<@~Ao%8XT59ay!I0I^49shk47O8Q@Gdeqrd0!%5(Xca2cjMR@ z`HGI6(b?hHd3>B<4r>!Rc1FIUF`nxU;tXM$C&$j{>@dc2jeJGN&gkrL?2LRx!_KhQ zwqfVtrCH!Fg{4^>J0oAw8P6NU8Meq*%-e~hjLr^YJa3R;ak)W; z#brD`&ajNf#~GF|zq~Q;VGd+t-fxg$vDB+LI-a~t$Hy6#DLOlx@r-;$W8SCe>~QRi zd_}{~8)R5qZjfOSh1HJ#KAIz6(HYO<;|vRGt6t}(Vdo7pEG{?5u(;eH!{V|;zM?ap z$Hy6#u;#g8=M6F}E;q=qxZEJa;_7zTP0i;(CJ&i;#OC&Z9M~^zDpi-H4IbSf!y-Q8j`!=3_~39q1dpq)V>;s*ogK#doFZS*u=55P7S|hOSX}2Q zMs1Ae9QlgQct&T3V`t+ycw68Vb8c!u>Jo$)+A&afhIbA7Kf z?7TsS#q|am77?yH{ye%thQ)QgL7ZWY&JJVVZ;)Yey+MXW)S?bz7Y5(A=yM8!Y<+Zg81vpozM?Vj zH^>8tbS%f8M?-XW7~^?^Jdk+a5v+N~&d66Z=KThFAh#Rjf!xOE>@dc2jC@6BJfpM2 zu`}`&9Xq45!?5!Pc_87=AJ3yH@)eEoyg?qwZHjzF$Ij^NFy{RRc_6nNDg!S-oO6y z)8iN4e*5n63IFU)q58l=ouY4e3w4XUCI=O=hQJ>w`)qPpJ7liB?%X<{OEjvJVQHAc zFuk30-SJP2ffnwf%JjzoFCHRcui9` zgqkMD&M5Za%u*=ua6rRXG|tp7QTV|a(j{7>4rcT@Vqk`8s=GdqI)=jKZl2QK<2XbV zwNS%k>edK^PPs9v;Wbz{!5vEa`x7uObQ7~*tBU<)5u8MDu(&D@M|McZe1|@i!y$~9<<>A9f58jPDE?!tfnf-rmpiCq_$`p$ThRSz zwK|y5<4_0l7W0IRj(5*`sR1Uby{F6azbSXb{xWdY{S&0QO8qsOI^S1le0C3 zZ~cq~i(F?>n888C9Z)b^7HXJX$3cbT7C1u|YWSkeL5=g-cBf@YFIc=_2!;Sx&-jhp zik-SCblm!MU>H>@qRp_Zy`-rafMCIP`TiqmY7iLg)0@kLWfNHHfW`~J=zf@t)fv+; z8-dgPTWnWTe~ayE8p7?$7}X)n#cPb}5GJE=K*JkRr~6@9D$CO7WE~NVP3}`eSfHrO z@2EpqO{hLtvd zTUh`NPe21Syl_i@2|!gE>7Je5hY#y5(C9nB>3#I!?iku|E1q9aNThr{8ff%B42D>} zk3Ik#(C~%1(fd#cW*HjEv@Os`5M%T{thMbJ8pmslT`$ZE>GVFjV6l21xhMwceEhp; z=)j_HKFiS1mB`OM4!py6y*aE9?esn@yJCSxD&_pjpSwu(ZW(%mV{{IyFB`oNU-LS> z4@)ImpwTgE^gg`$aSV-}a)bBbOIfG)k^kuQKGYRipi#Wn=zT0zGo~pl#9{S5I!2A& zhgCBiL&H>b7HD*gI=zqlN5{~xc&-H+eT^Eu4=deThTh^Bt*V}D`D*gfxOql}sOuk& zPWQuLtOXh^Q)BYOG765NVQw-DGGVD=I4HaF!u(A-rzF_b;E-YywUqGvA#3+;Z>;xdi-Y& z!ml@2r2P$!(WQ@~g~r_XH~7q1!q=G2+=utXM(@LP@Rp%BI7XM@_|Kg9MT*n=uqvbl z8Xcp?+=nF`9Ye#s=oV;nj2gWUlMPvh-r^Vy-y#~lpQH4lPVd7!2^MH{lkfCC@*f>T z@w)GL7b^T3HG029VREbYw>U<_uTi7-VU7%^_hF`N3p6@Lo!&?Oqhsh+{^;nhobYSZ z==~P?k5=!aFpL3;g&%y4=6fHPqO%N*!Y~$Sbc{N^kNii+P`na7eC6Xs^Wk5(YnZ*t z>irFlQEbn_F>1_xnCRH)eSd>vbPc~oo!&=bn0z9e8FjCM4J!T62$&I@97B&Usx+_R zO_pP5_#Vm_(J%|9V`wOYGYnlK_tC+Od>yCrVZC7k^aceY=D0wFV`vxMwCAS@)d%oL z*Str^(D3z#VQ3hAbTA_y-|2i)X?78@};4b-{D;U`!oU zq$&x%#VpiNUS*+f(UXUM!Vu+N=3tMCZXPVukX89-w77JOyb}vFibWWiT9zSB&z{f! zg5>1Ux3gpG7{2+8~m8+G2RSeN)E{W7N$zo6`Bc&O%$-MZKf z&S&e|x-HzR4O{y#eX+3!He^JP4lBdfA-qO%Y#l;{%bH(ULs(U4Thn_hDzt^Jg)ywi z{SfSfj;(9xS{lQ;hN(au&~R_b_a92xFsVv@u>v*BU+vh61f#)cP3(K)}3nPujux?>G0|#`D9*!CP z$NE10^A%|;Pf@Jhv2_en80Ci*AFq)!l#UC5|6ykEbU`104v~xPSQ@4UcPvFJ#Oqfr zj-_$Y?(9_)#x%@^=U5uP&Tz(bi|FrI8tN?!OL2!E94dyTQx~dD^0PmMd5i}1Boz}K zdPrb{bILI^+@#=gWDOmo1Jy8ej5dA;GYSVgn4w2)3}~ocF$@h=+U2G!JM*FEZ(xRw zgo7FFBo1b@kEV0ufb(<2c?UEM{usSq%4gEGfReN0g&OtrD-sN8c!)ZduHk*1LHjLq zp&ii3g({cXN#4VQ!XI6m{rrlWLzTL*L7_@VaE2O_k1Nm{fQDbCPWO)&l_2XsippG{ z{Ip~hprNOqFNTRby2ImB7_CW`7Bj-aD4Yb+z*Q$r9gEJD`yU+}Qb+ zFnX5X`Ecq5gmNZ7Rw-r^V`1%wRl1A=8ik;5(ETkUR9gCj4LVf+8arQ+XkOn=ksdpJ zLT}*>N`9R}_Z3W((fuvl_zgp$CA>bQj-g?xR>ROaTKbNmVVPFL&^7X-9L(sWEMG=% zz^zeqA(^%mm=Q(u(*#k%;XX7l%Smy~FLw+L6EzznI!0e5j-g>mBE!(IOud5{u|AuE z0Lwm%nmCwITyMyh^{(8Hgi12cSz?o2%* zhSv{KXOV`Njs}~;i+qRnp_|(|JJc4d8nfRxLmyt_=f^azK5I;Ve~P|GjDxffM2X%@cBjq)6!!$*%k7Mf`zeqQ1 zox{%)%hoW^<)A{&b^~r9&Uw5HeON#_Nv2 ztM$Kw!iKHJ5wJf!Z!>(yeiu; zp282R`cN}>V?Lh3(=Y9-j;G_lDS#QOT1q51+xzgbpwatVyyh5h@|t7p;@2E~`ZjLt zLn&i^RQvAu@Z8wP*mY2*rC( z9#dl&ozIH~aAzKQefcOIK%Zd$vn17(_vRMrVJmU)ws^ZBcSHK+V zu<~4;hj0f-i<`zd%syZ&)j51_X7oP%;LXQA$2lx5rFxmg*2Cw4AC43b(}W9fu8!?=duXx*AW{5E7r2>73mPmdc;>g%Y+w+~A91Y1>p`jI9m=)Qv) zUL@qt(=Dv5W^DdjnA6YbeYp4MRn7R8i~@f7^AwR7pD<0qx1bY#l;h+Cq)< z?iwS2FnYjM$5woxM{G?ylhYW!kIe_Y@Fg9w)j0d(d_ei2*8~A!z*czi*)Mc_NJmiK|S@V+;n4+pY@ zXz}M`iBp^m&Eb9=pm6#hx`6puBC4509~Jpn;)I;r!I6>=rA^xwS!$e9Gc+{Oj+*z> z@WLtjP<3qW!eFw68YXfve3cod2HR?tMCW`JD1M?Huv^j>bn_7Ao6QGlag`Ri)kctZ z9>XWt&Jq~IOR9Wa1;XSgN}u+BfO&Yd0yl|Kv?7110yI*O=7Y5OPK%b5F`}WPk`L0( zQ=AYt?WO`WOox~CD1jM8D)KJH96w5MKttyzKlcdK1beh&=nw@dEYN74jNXSChwutA zzoO>o#?!%!&QfPckFPg1%yGRbqxYdI&)A=FHr-(9hq?r#_u)4myu$PslSQxv2T4Ge|8RZ2}G`awA@kdgikcERbde!88YS zEhq7{iE_Fh))_KDr%>%*X*n~X7y>q0wY8j6S{5W!h0i3dXM9MjTL0h0IZ>Yz(L)@dbQmN z(v>6!Afmp(5{Ta<86$uJxPdljJ57-`2bcHRaYZ5IC{B@=5d$^uHebHI~2-uGYLXXB*-oCTSHFK%>u9r~7jhrFXhNNB8Mz z#Vh>vsP_hDm^#J5EVt#?ZYUhg=+@7{yulpZ;>vHk$*UZcQ;xnX^6n2lRiekUhNrg8 zapH*l1vRoTN8jp>ty`Eh%ox`AV?D1XK%5GnE7zIopvDRKEz~ViX*j4o;)>TtAbprpoU(6 zGp@@G5~z(QT-V)Twh#{sW-GmEV^xLkzVheG*u{x+jmbhZEcy_3Z0$qUe|}iI9(R`4 zcUK2=jV=P6{*P;PXgPB=_2Gv=I&z1stbO!tX$@LiNY3{dnX zI$?}67ShdVwv1s#_%?Dg9b2(ngY}vpR$LB7+kgWaK3aDAKi}Z_0&YdZ=L?RlYbXpf zh86i0g3YxST*@7V_<*}XyrG;fH?S3TqmMtd5c;{np;cB^u(ujp%ZPyuHUSGYOtEL7 zh7SWAR2DhOWuOHt&e|q!w*=Ntb`0?@e!>>R8>erwD z!#_U!@$tp?uiw0S^WC2x{`pUT`qQUx@E>11fA`|~H;Ae*e|~{rQ*w z`0)4t{o%_${`%oJzyI|o58bEzsjq+V-SgKk{}X>vvGJ2%zxm;Z$JbAQe)iQL|MAO* z&%f-){(rpw_2>WbtKaHXVc+HYQe`{wNrKmXPL@#XJ+^M3+t{PcwX9|Zx& zUv;Nnb;F079R2}=h4Fm#>iN^-HxK{UhayftC#OE56`}Odj8!bMgYU}!kkjD_=dmefiDfv(IXto#$`A zEAu_T8|nY@NeXV?go8OExqzD3El@a>OQWZqVZ&drFn{j%FMZy1v`2kNBU3^22{EYw*Xf-~R6L>G`WyFJJuO&HL}Ze~pMFu_%ok$ zpPpdH+rQ%f74q~c{tzi>@C;&JAx|1+OyoCj-hch-@heQlH_twMdi(yd4FAsPvK}%< zmke0QSTf;qWEwE8r%z8ElGdNF4xnovkj(~}W$?p8jV!dx7>SZ>1EL@u!psA%#}H(| z*ql0Onowb6ocax^hKrH-5ni`qRU-E^JenS+A33%|*6ePb#(6=Y;WVJQ&N{)yq3LHw zT0JJMo;H+hg8m%R-qT#PXs1t+(FEByR@57WFnj3m6Lbt}a@^3LHY8>n`$NZhN?LsC zG2t)_X(CQNG8@!Yj946&%z(EU1D5k#*@)Z}`okkfdd}L7C|rjOG^jTSM{(-LvWA;} zcBIuy(rOIqiV7QuOXDFiCcmtYh94bi@|rYxLTDOW1C}#h7L15`ojz^((UB%^Nt2;} zgV8ITNBrNio$CJ9^s^(a?y_ef$_H*s`G3$Gpp1OkDsW(9uf~povc2otZEG3*5z7bv zp_}l&8QaXE+eeo^1Lv`>4-}KfBI(Ldm$MKj33`Ck%Y8YvOJW=N7^sziehf&r{Bh%4 z9FNC$-#?Pq@zt9b|MvLw@O|;;UOfNt;oXb3kAHgjJ2;C&|L`9V#hs{o_%6{Isnk@B8wLuYU8#-+b|VczSRiUcUb3<%{xb z*cS1z_gBxSx`98uDc;>!+=&kZ;uM1`cn0hQ5Ur&FAvHS#!jn8(h%XVemIj3HdIlT> z5Ur&FkznHth|wVn(OMc1Ug{Ze5nuB)W9M7i`seMB+;)gnC_YOed5nw{~enqD&{8 z=?u=4%5CS>(+g*cH1~rx{>$!r^_SxgN7vJv*TB56dSPC%`h#{|IrfTndDl~6 zUTH6lNX+Ynd8NHHA~CNQ=9OwAX+&aPFU%{6r_zYTyk3}B^ayE0VqP!I>ka0W+`PNF z7Uq?taA_NfdA%^Nw3kLC<_*HUBAU-4mOQ`bUJt?;kNDea|gB+d-N83ZNr zh{TyeI8$PbX&Z?%gK(y#{Z1niXKDm+=iUtlXUe7QZmxwhgTa}BI5P-mN_**E6K4kD zOldETNSqmkGlRjIa<6qB$5A*lT;j|J&cFNT9=<#8pL=CbZ1@JJ4MEP(`{!QU7}92N z|J*C|yMOMrM#0MG*LmZ=f9}=QbLjxRA9sI^zlsZdk8ZYY)%W9$1G=1=BrM;wRDe3akh{TymI5QcXDMjygb1j@HZxKIea5N#%+%|f);qPSq#oB#F<4nvlyHy?|^r6Eu1OsrF%`BS%fpCy)+_mW)aRT24@!H z%qpCL$nnEA?hnwrW^s2Rdynd2#l-&aiRdfry-X=z$9vEAm|l6ieRecfaVpD!e0B?puNCj6<+=L~ zQJl)sUK){{%2k}o(q0;ooXS<4%9WhT#$J&$5Kh{^ub==ouT^` z=g+TdAY!6rSC|*m_wEdFa+tSd063|MtHh zcOQC)i+8gWx0A5l{kUu1rs=EXe%#e>R{APwbC&J`)@Pqt?-l?4@p;MZl=#-CD9b9B z3djeu`=Tsg4)MoA$sfG?)|X3#l`a(;5ovQ;Wp^s=oxge;5y=_f=7mKQrbIrv=NcExJ^9z(q0-7bGGZX1YSyt z(ljCkUN#B5Y-Nr7O%Bu8YYMy|D;FsVO0~Z{U zM{d+=i&;p`0>bP;p1lhlr=##6zIyoM`>!7#zI^rmyH6hahyUlH`vj?gP;#U>7f|0x z_7F)Q(sBBbvf+lVNG(sZn*#C2Ym4XcYJ_CciNwCPn1*E1Nd^&QeA-Vzqm@iLNg>j4 z3Xw)gCY{{JA$OT!C6i8)h;%HoZ?uw5tWL6sbeu(`5t2zKZaK1s2t+dX6!c%pOSvf~>Q7NKOUPNiL9%bAhyVyyWKC zEh0$<(s447Mo4ClWCMZKM#q^wk`4q({|rcUX5Vpf_&6U(W5=02k`SchgdmNO%$`9U zKF$cz2+8b`lpwYISoRz*DLVFJDGnd!1ZlLA*&|6oI!+4G2FXc5I>`!x%+UEo#Babl zc?8z+Bd|s*nLY9f3|3#TlHAgtQ&ol$nncFRd+x51r&Eq?lmgw)Mq41D9HM8k$f_hAK8sI(xxLP_K8pIMnu|kiXO z!!j9;7pLp&?jXP+(?ecf+w`!PcMr?__3U9!uW>B#Yy0UD_T0lV^&L^;Ske~~0vx>5 z?_rt5SaNP2loI2yJTxqG7tTb*PKuD_yi06+|9`p*XXwl5N-C2gWZ8`)U!eYF z=va1$yyc)CnSsa$_FXvhi&I{tI_E%rQ>+K#oBizEg)@KkREkt5J(k2BNKp7hxC>|W z#WO`{?!~nJTJG!qIHeT2jWtat*3+???p{o*aSY`!r9JCjOshRb10ST~fZmH~wK|{@ zapg1g#5%aP6<$UTD#BpV#AEkaicO{Vxd~>HDvi8~O76t5=VI ze%G9$0Jn_$Rn|%U4#>^-M{fyX#}5NbJ&p6i?WBN5ZSfokZ-iuZid67`)rOU{-FH&L z16CW59Ilrd9v#>4XzVzL8l;E^tTwEqSVJdOJUXu8(PkxA@#v(CN5^G68X-x9+)eW2 zj_Y_dLXxA@Ng)qdogYgsVU37w2e% zWcEmP4p^OEL|mPtlkyxLm*;4-lG!thwu|d?G(zIncI=S?9kANyII~A8baY&yV`n9u z_jdvMU$55rE~Lyy?4*=e`ny@Z=LPty4jW7J?431^C2zBGA#%?PkkStGHha$t@XNa7 zCx&h7k|R2JVNX{>_q+g^b;(hky8!*KXAehq+SVmUb~*{|baw%ILNtBP3-I$Bp#QJr z1*oa2zN)dP?%|&v-#)#3fvO~}r4+kT_-*HwNu{}tE6o*GCHC}6<+nW~>xFBJXNRW| zl0O2a)?CN6=Gq{+)?Byn6IW{=dI>$v7zBP6p&iq3Uh zbgmJS*&|iwI<7j`2FXQrI;pDDaaEm0NM_F}0Z1;Z(+J7zk-9ptI?tX`=VrHvq_9rM zg>@ROWcEm9osKK(G(s|aq_j@QrF9x1@oW2z3wt=Xaw86P0cIWux6sgXNQjob*y?Ae4poEy0jlG!84kzsY7J^aS2lSf`1Kk{m{ zlG!8akvmS0+z83+k^IQ8+UPi1-mym#BzK%3xzS2yk7P*h_@P%LB(q0SBzOGMs}Yje zgVGEf65tfcO_0FYk7X|@lDiEpCjCobFeJ05wwQ(__Vkh>xwe>wq_d}&6v@cuWptd_ z(@TnESZzQOd-@YU>VVY-Bo@Y*J-wtzhSdfnv8R`pUa;DLB=#WxJuP)uZ9p=6BtsFWF#sUD-HH=uH#;E9rv8;xQ*lGhG943lIs{&8y#o%NUmd8Z9p=6$vBnI*pKg_DHVdo^u^HLNa^gP6Jlwm%2RBkT)7VCrxa$lG!6kb$U*!(+J7z zk)%33-)S^L;@5WUkvol^pJ_BgGJ7O(V$X>a8zGrJk~y*G%!!SV%pOUq({t*?Hb}nH z=;f(K&$$yDA(=grJh3k=X5FlE!?2ri$({(S4M;wFM6KHMoknBFnLTo+(es@~BP6p& zavk@a>$njTzqTJsIeR$QaU&$NM{*taoISu)#bC9_8)vwdkXyKNK!>u#xw zWENH%km$@FQrN?i*~X4DdqgtZvt+grlG!7Y*`6h{jgZV9k<9iinQen)$!sr@*`6h{ zjgZV9k<9iinQeq*_K0K_R_7NHOJ;kK%=RpqZM2fvBa+#kC9{o?%pQ@d@h-9{B$!r@WOJ;kK%=RpqZG>d@h-9{B z$!sGevqvPeusXkpSTfs-WVUC?Y@?OT9+AxUESYVDWcG+;7FHV_N6S0*h-9{B$!w#Q z%pTDi^oG`;XRSd$OU$jP8?xtkx%uC9T(kzY#VjOi4SLZU!0Nn}<>r5Hr9`X^twCRI z{`ZjluoYGtR`Pd`XbozM>9J(?h}NJtv<7{-`QLY3BG!i1pf5N7dr0xz46Q+5ZvOX> zd|O&uOphg>J)$+JEv6xvJ)$+}4Xr`XT7zD+2ECy*00xbvXbozM*^ZZ+|K0S6)}XeS zhGh1L)}S}E27S5t-&@JgHF`s9(3hM4J*2S5&>HmR=6??<>@ldZzHK;9S$C9-My=V<; zi)lz^k7x~gLu=5NoBw^sg*}GWpf5N7dq`oAp*83^r))1;gW6(xESWu`HK;A7A&EVM zXboU>nmxeSkL4g*gWk{@0D~dfbE_>TJ3f?~|MQFwqBW>3rXlI<8ANMPTTDX|dj`=O zz-nW9h&_X74PdnaN$eR!YXGYaNb=kU(Hg*N1CrP?h}HmB8<5N%(Hg+&JS1xk2GJV8 zY6FtlBU*#O&>9S^H5f!|0ILlvnLVO4s4ZsM!|x{t(Hg*N!%Ak4XblEKYcQ0X|J_a` zb(LYYVI{Liv<9`s^jI=`L~Ae@T7#k7{O>w0T7$vR8Vsy87({DOTg-Nx3-}D8HK;A7 zA^GePtpTjg&p2xh2GJV8Y6Ftb9?=>MhSp#xH~;$?XU`2*8&)!VL~Br6OivH9N3;fm zp*0xF&HujR9CI5Ct--(rd=CWOU}y~nem^;g)&N!;Rx*1;YfxKEPY<(4>MFx(!%Ak4XblEKYcTNp$w9ORgP}D5 z1`$%U2DQcPShCh&5UoLNF%8M=5v{>sXblD~;4_HU09NN`oV5mnXbozM>5lW+BU%Gk zZCJ_d5v>8NHXxZjlAdcYv<5@D`QIHBqBR%{t-(-k{`Zh__83}&q1^oMAVq6XTg=Wl zYYhg`8q^lkkjx&@8VrWkU??~L`;PN{53J5FBGwuVqBW>3raR8;5v{>sXbpyP^S|%7 zcy5N)U??~Ldq|GC)fUqoXZDEJpthKXWcG;GU@)`>L%I3ibzHOtgP}DTSZgqd)}XeS z?RdHQ-&-j$H$!VMl$-xOq_D@(8Vsy87({DOTTFMH*&|wm+F}}#*&|v5Se@TC%FX|N zEQLLW)?nbg27_n~219EA47O6v9z$y|u-0G@twC)uJ3Xv57({DOTTDYTdnB&`tj^Ck zYYhg;YXGYaNdE2-t-)aAH5kgx|88B1)&N!;Rx*1euR(1wJw41G$!jneT7!YL27}}^ z7>v9Iz~HeI_855$hH~@2n;y{`)E2X2$y$R!v<9`sG$gY}v<8Eb*I;0+!5~@#Se;*& zoY!CwtwC)u-En4*e)y7y7dq&Y3)E3hnXZDEJU^KJ_BWn#t z(Hg+&e8)Mj!6;gT+G4ijtTh-#YXGYaE15l_HGtIyB(q1f2C&+IWcG;GU^KJ_BWn#t z(He|~)&Lm99?=@q7Sl7%>=CU&Z7~hW>=CWOXlM;a)*6hWH5iS&2Ed@P6s!=CU&Z7~bUT7yxv2CzCmE>@)`hxrbn~}qoFkzS!*zg)}XeS9ZS|4jG{HDEv6xv zJ)$*$)yDKNdqishs|`qIk7x}>Lu)Xy)?gH^!Dwg=fWeE1qXxCb^z<-$L~Br6%tEr( zU=*#vXyi2j26bGt2BV=h7+GsDN?wE7V!Gpe_K4P?wwQ)w_K4O1R_B*GYYj%pYcLvG z17Ps<$k}7$H5kjy|L!;wtwC)uJ(kQK(Hhhi(~!&_(He|~)?j3r(x zYfxLvcAT{aqvSQHEv6xvJ)$)jjl2e9x%uBMBGDSa>O6bO&Ho;fl{&S>bjO)JlGk7~ zv<4$<4Mx!#jE2?#7~F9=dkn3?$XbI@v<9`s>{znaU=*!EZ7~hW>=CU2tj;eY)*6hW zHGtIyB(q1f2BV=h7+GsDiq-&D8&)!VL~Br6OivH9N3;g8+OU$(9?=?%hSp$Yt-&aH z4Msz201P6eXbozM*|B7;!6;gT+F}}#*&|wm(a;)=CU2tTwD<_K4O1RvVDa9?=?%hSp$Yt-&Z-gVE3$0E3shoIQrtU}UYqC|ZNsVs^$^ zYcPt|pthKXWcG;G09NN`oV5m{XboVs0m)~NXbncAhQe5G{&#McXboVsVI{Liv<9`s z^z<-$L~Ae_T7!|b2BT;VMnh`=3?55ikD)afS!*zf)}XeS97|yAt(+vUL2WS&N$iMtBsD6 z=Qc@RgW6)cU_spYcPq{pthLpIBN|i(HcxfUISoo$N7Z< ztTsB%>=CU&Z86<(W{+qMCPQm5m7D+baW;w8U^27@z+gyWkD)b~SZgqe)}XeS9!qAA zXbozMX-H;|XboU>ei53W;@PWgGsaowZ$|fvq!WBlTkxqDmVYTr7l_nSe<7N*HD;5YfxKEcbv~2(HcyK z)?i|-!6aG(SZ#Ei*&{U+YK!TPGkZj90ITy>vesY{t-)ky4S+$5NVEo%p*5ITYcPq{ zpthJDOU`RBiPoUDn1*Ebh}HmB8`HyQk7x~GwE@ZOks1n1Gs4b?ahuI@q16XZX$)1~N4JJctFtOHPk{Sw=p)~*o5mK}UwZ-gM zvesY{twC)u4aw{gt-)ky4JOtaOrkY_)%h7OH~%{~OSA^H#dOE{>=CU2tTwD<_K4PC zGHNJHTti_Jt-)ky4S>O8Dc?PY)?i|-!6aIP+G2Wom_4F3s4Zq8S!*zf)&N%LXPj#& zOrkZI46Ok$XnI6z0ILlvnLVO4s4b?)lG!6#gUQeuOk6`@60N~xXbphDV<{19Lu)Xx z)?gB?L2WTTmh8Dn4Taib8j{%~S_4>}Uqq}mm_%zZ88sAuLDM5zgUQeuOsqASL~Br6 z%#J1JHJC(eP+LqxGJ8a80IQAZ;j>4y2C&+IWcG;GU^27@6Kf47(HcyK)&Lm1h~&G+ z&>BpvHJC+fP+LsSI575B&Z0G_Ev6xfJ+o*HYKv(|I(uf(8o=uGA_4|?oV5n9+JGeX z%%U}@Ev7q8?3qPtFdJF}U~tFz?19xr$H{Y>MQc!7On02vGmF+>Hnax7ppJ{y09NNa z&RT<6v<9`sY{yw^FpJh;Hnax7;EuD_09G3vXZDEJpthLqII~Bz2D70xm|1Hui`HN^ zvTF%8M=5v>8NHl~Nq9?=@WY6FtlBU*#m&>GCFHJC+f zFdJF}VDKVh&#ktYo*rh8XbozMSxD9z%%U}z4Xpt%sN8N&M$S=8qA_Km<_D~FnD_8>@lEW|Sv<9%+fMoWF)?hZY1~Y37X3-kVhSmTWyoluNF={BxTti_NtwC)uJL9Z1m_=() zTTDYTdqishtMfC?T7y}%2C&+Ir((8q^lE9cQh< zELwxwVj7a!BU*#m&>GCFHJC+f0IT!t;k*X3XbozM>5lW+BU%GkZCJ_d5v>8NHXxZj zqBWQet-;J%gITl&b5S>B$C9-MvuF)!i)lz^k7x~GwP7X4+(c^ts|`qIk7x~MBd@{C zc@1XK8q9{)02s6riPoUDn4TVHk7x~Qi)lz^kK{F&4Xwe3 zW;@PWgITl&wZ$|fvq!WBv!OMZS!*zh)&N%L*~57aX3-kd7SkPP&rP%ju-dSa*&|v5 zSZzQudnB*HY-kN;)*8&BHJFXO2EgE@F5f*yUW1wQ8qA_Ks4Zq^oV5nCXbozMX-H;| zXboU>e#TjAFpJgzRvVCf_K4PCHu4(GoY!C$tpThytYr3x)}XeSo*rh8XboVsVI`kE zqBWQet-;J%gLxD77+M2h>{&!> z0ILm1W{+qMV09jnwFZl54Pdna$?OrW!D46)7SshSp$Vt-&HS6kxSsC9_Ag2DQcXSTcJ=YXGYaE15l_HCPO-!NOXD zMYINsp)~*oEh5nx)E2X2$y$R&v<9`sG$gY}v<8b&Lt)_>3X5nBV0C`RxrV|bT7%kR zy5oHIh}HmB8&)!VL~8)64M=8>)KFN8x*^?hW{+qMmZEORLbBFi5v{>uXbpft>=CWO zVrUH()*39LHK;A7JI?G8twC)u4asMZXboVsF+F_th}K{+v<3@n4Hn63uozkcVDOCd z`<~ijdMueeqBW>3rXiUu3raR7Ok7x~GwP7W*N3;fup*2`oYp{scU@`I<0E5SpV{Wy@502%({NAnM2^l$aPGvxxkg0dip1tl9Gh!IB(g|o?!=+FMnqzZMCMLh-Lw&r=puo+69?uR z5s5DnmpgG>t`U(4BVoA{hvga(i7^tDJC!(Kc9$qIvhztVLAetLOp)So-$V9$p(!5@GK(1t1YG>iLZ-D z@M?=`NFwYa5M70O2 z4M?K;BC0)Dorh%A-Xf|!SZzQu;Y76us|`pdoT&C-wE@ZO5!K$ps=YS$uxf7+)!xFY zy+%l8kEr$*&JffH$?Or;9;`OTlG!7wy@geKjaD*yM76iDYOfKJ*(0jGrRW6D2f+?< zzia>UVTg~sr#G*U`9ADVd%^B|jfg}(x%)ct-B%+baZj$k zPJH#%h)C3vo39h!e6=C+&6iw!o%rIb5fN+n>`uwO*NN}F8WD*za_x2E(&3GW#2LBu zI+c62EDOsW)UMYO2jNSvMjMGUa_4p8JFiAW;*4B*o%qVD5s^3}uWL``jx9Zo#2LBp zI+ZK7G$L_E?z>KW-__P@zVDLjt`lE(?GX3p-?pqn|9Lm9|Jtp;S|7f8dj9hDtH*cm z@V_1(Up;*F{hRl%zIlB6@Kp(zwtvd7`h5}g`@)&_%2>vqGMs5|5%v4R>i0%S;xk5q zLUOQrKgo@dMCe7-@37i{Bt|cyeuvctBvE=1^*gLKAc@n9sNZ3=0f`|$Z)J<9-(j@@ zNvvKZ(;logAc@wCsNZ3A9+K7Xi>TjWwE;i0H|7cKg3U5fgB;Y@ptkjx%Yzb~wQZ-m6J?XBeNfrZuYjgZV9QNJ&&es6>% z_N=0QU-&Yu2@)9lj<1qwZ{h2-Mo41MD(d&z;@KN$ge3N?qJD?f>7@<~?l@nn!D<7N z*t3fIy|$R{II(9H_4~>fYmH+`>{&(q4y%ohqvbPuR#CshY6Ftkvx@p1RvVDa9=TtG z)p z`dc~l*9gh%k=WnLnf4kX`RtM4AFR%=OU|^nO7w5#=wG9i%pM8*jx&2i{l2pLz0pei z+KxSi0%SW{;@fS608bL9+UN74`edRs9+vnLVO@UpdoWBP6p& z)bFr5zld1i0%SW{+grTe+%VBP6p&WPU4W+G~Skncpfhzm+rXH9|6bMCP}0Rli0^W{=4HV0C^G zv1V@-&ECqIy+$jUJ)+rLS+my&$?Or$9;`Mx&g>D*-pZQ2Ml11aJNAfXZ)MG1BP6p& zG8@P#!|EftD!YmIn&-MT7%kR_9lfh?X99Us4b=;nLVO4 zfYte>&Q<+Z(Hg*N1CrSzT7%Wl8mydYZxyWptTwD<_K4P?wwRtCW{+qMV0GR~)*7s$ zHCPR;0WgR?qBU3zt-;Ef_Eymv)E2X2$yNPU(Hhhi(~!&_(Hg*NV|w`P5v>8NHXxZj zqBU3zt-;Dw{Z`4ew;EalVDKX1$B4DX^z;yWHqjc?7L$;`*ju@Y)?hWX2EbrQe!N>- zOj}8w+a_9r+F}}#BG%i9wFaA^H2?;8oTaObw6}@Y09G4TGJ8a8P+Lq-53@(K2C&+&lFuH|8f=EvVB<`Cn`jL- zLu&vGBBW>yYKz&iWUav_T7%kR8j{%~T7%8d8f;wEZxgKntj^CkYYjHh8q^lk9p|%0 zv<9%+u#(v$S_4>ZKr(woYp@wwgRR{B?|dTB8f=EvU@JHOdq_EZ46VV&RsA;68q^lE zGtOFrO|%BJ#WW8NHXxZjqBVfk1|*+7qBYnIt-;1xgH5yso1rxT2C+x92DQcX zj5B*gYfxKELo$0rYp@x44K}Xow~5wZGqeW4ps^IKL2WVHan>4aqBW>3rXiUXbm<)Yfw{m?@ma` zYp@x44J1W)hn(A#TSl^kqf221oI$gMBki_e;#(^>=fEW24R(^;V3J(njdl`&fJu3E zfSEpjU?-hFz$C!|Fw+zQCLKV)B*g(R(_cTpBn|GAE$=dYf9*0`1^e$XKu_kPU-Gws9;HKq5N?!Y7- z0n^}7Q2`L9@F*`lfStl4Rvt`}NW5)4iw=P76dvW%9KcTD5o-@%r@^D51Ry(wM|tr9 z>=Yic`T%wsJStiMvQv1JPjvu0g-5JEfSm@9iW*>VCkqgOY4C^z2py7!GB@)IgrO!L zB|C*j`E&=s6dth#VUlF0Z9L+92k5)-C@(^Qox&qlA;3<9N324Cox-Dh$^+ObJYpRJ z>@;{(Q~@;a!lS$p0d@+HScw2T4IZ%)p+g!`Uh{b=!cbF@?)%PK1lVbuN32DFox-Dh z;se+zJYqG%BneR4c*JT1*eN{9%MoCw@QC#Yu+!iX>k(k5@F*`xfStl4RwTeqgGXHZ z4|WQV@{$DDDLmr*2e8xN5o;2<6N?gnX`DwaN&u#uNBIm012A}BVp+ljyYoIR%MxIx zd>`d?39wWAIu<6tPUHKCO8~-7`98`k6JV$Kbu3MQoyPZ35en@0Pu3;?)8G+n6VP|z zQC^&Yz6*~y69Visc*N?2?!@v0U>ZDPc>*wnNBLX`12A}wSfDV$?mUlJpa46CM|p(; z>=YicL;-dhJYtCg>=Yj5H43m(c*G(F*lF;nNCx&iVwD0g4IXhlK=fUBl$R->@4_S2 zDZoyHN32umPApUarokf?DgaY>l+TJV0E6d)Y6=0{q zqaq#HuTNGh0Mqd6igti7#jnfD70`F#5$hFTr@=Yhxb_CdI@Q4)) z-H9a&z%+Qok_BK2kMj8u24L{KvuI(0-FY6dXaRN#kMgPo*eN_>*#hh|c*L>=*eT~x zUbg@{g-4tu0d^Ya5epY!r^LPUSrT9;*7Tn5EM0(|;BGcXU4#ULDRJ+-b^&%uypF{S zu+!iXix;{Rs~3Q2#2Hw<08EK9{2Xzv1lTEYhP;3QcFK9g3I^C| zoJXu+fSqz4k6?Ft zU&63{W>_LM&H@51Chke{CNZnwo~*B*i`a%ik_k4 zL<&=FGdoA3XXr%F(B(5J48V}S3y%yvLnnHMPV@}5&2-;|N1RLn<7x0n^bDQo8DO_D z@4_QarvN(*9*Lfz6Fmd$HtZB0iJqY|^bDQo89LE3!0x=AoKXQZlJm&WGXR6vyyzKV zw_&I7Nc0S~&Fq>NJwqpYhR)D407LpN=aHdj=tR%ZiJqahneMyrh!ZPJwaql9oJXQ( zfZfKt3y(z4&>4D$j#DdOyJWwvGxQ9=;CUB4Lv1rVo}y>yM9)y$Ok)aGjyV7=tR%Z8F~g_ z@R}DrLv1rVN1|uwM9)y$Ok>JGX5`g24KjVmpFr=XXr%F(21U*wwaxG(KB?SXQ*waF@;B>XMo-Lc^5rHCwd0hZD5LD zCwhj?&@*(RXXr%F0J{x4g-4uzVXAGW=SX-YdIs2S*eU0c=ovag&(MjUp%XnrXXqJ# z!Q2!*Lv1rVo}y>yM9)y$Ok)aGjyV7=tR%Z8F~g_$eNe)$j~!%qG#wt&rsXU&b#OtI?*%K zHq)5GBhfR!?)Rhz+i5Qo}spx9Z%6SbfRadZKg4WN1|uw3_U|9dWKH) z46r*t@1keuM9)y$O!r;RBhfR!Zo^LDk?0vt~>o|=pX*$;q>XSOwT@f_T$@^KfHW;`R|YK zo_+SuKRtW?^z`;6{r-oh_o8{E)$5f78?<1E%Hq!5NRbgBGO9adrTnGe%^>k>yTe%1Ce&~MnqbL ze1{1{T7!*<+Dju6XZYrF ztgpY*h{PGbw*;cW8GeV&x0XOOIK#J=d}j$ngEM?*$v2ijG&sXAu=&0chz4i){WafK z0@2_MzrN-umze5f_cv`eAkj8G1+*@sXq4;+D zpg#aFb@0kT%0g9A1&xw*tIe(;Dt!n6(AW%$ICL*+mvv)o1}aAtM1w0LMisJfYOOZ1 zh!m9s-EfQzwulf_=)yA8MjOfLWDzQCH25M(wS+J%L2a~=oK6;?!bXEJl2A)1!}8Nc z8_DTp@hNOHIK#=bSb7S?OPtvsckiB_fA{#%Jv_bn@!`drx33@HK0JK){@uIBr}nQq zzBlGq@T0tfFDp9!y5n18zB2|Qb*v4M?~M7z7>KkPG$P{H&Knlr7mxD(y%CX4PQEP$ zVgdPE*1|?akaK6FYzBN++=xh<0pAqEM%oM-5kbzKjj|c=yZ1&!+6?%X7&g*o(1-|f z?rfCJfbWPK5ot5v8)Dc`@>Zg`Zp?rpv1yJ5Z= z24Vq8a)xh)`Cb@^<`c{-@khG_~(arKR$o)__p=T9C~)h@#KT{l&QvY z&%G&w6`h*Er11eJx#hs5U8NC|MhH(j=o=Q8G)8Th;+XgHP7HSMS-ZpBkNY3tuzdLn z+-@Ipb>HPJ8Tz(ww`ENZy*Ti_yd^{53`{z;G3In`PqoeS+Gw;`6f9|9((`+U*@lRkcdncj(jNvAh3g=_50H;$)pjoo?JNnC5h6t1yD4@}}( z8z$ep;Q184f$90~r4bXqwx1)ueVKZGOV)@e;1S=+pzp#XzLjb0yYPtbWnibl zBfgh`opK)W%}k@6avt&B4D2*`#CJ2WQ+UL;GmUl%kNAEDb{ah5`p3@W zBPM=rf4<9GvYy|PHDZciCvVAMcYb}!Te4o>lJ%S$x6w}Fk-R1A`7K!^rtnDKlEH4H z@4_Q_OV;ySvPL_FNAi}e=eJ~yn8G8z6_|Q{OV)@fJmPx+U>fHU-wPlef}BVBn}Gos z%p<-Vn0kIo*4B4m)aBFK@|Uw=qY;BfcqsorYg0Z^?STD*&d!Bfcv@3J~E@{;e&`8AgUXz^nxAnofS#O4KQ0hw={^&bu00t4Fm)s*g*HUT3l(>uJ9;t1f zeT7C$Izo}omA)Y-*uD2Z8Zmh@=q2|^&$&k$G3gkEouZTC+#`*co_uo&$kNv&dn5}cUt9vR?4?;qW)I(60@7d)zh;sYn1D3cBiELE zYY9k$J#uTwmzJX>z-(KWa%stTmVh+aBX^d3WeG@wJ#uBqHT&uUY=qvj$w&w(sFBid1O5u5=@bqfn=-8EWB z>yAEc07%QO5s;RhtU4pkQF9TTyG)NiU?FXCjTVxF&F=L*^FixHkv^Rw|Nq1fr`qO4 z9!?2c_}Nq=B5l+BXbP|44Z27HF5wG5nQF9=_`(mSU?XkQjfm_Q2xIuUR3joWh9678 zM)Ii}5!t7vXNf>0m%0&=K1lhY6cEXy-XVVAxVtC1V=mvt9IbmIKe6HmR(CN+LWBT< zo{#*yn4`F#{G@8PgI&JCtKy2?ILc{t7jv}o`u``1?(Ug?3eh-HR)Pa@%z`6j5-7W8 z{(<_eaU97RmLS=QgJg|};0@w0{>@lp!7G$Imb zSiuiO`haXiB+jsYABYrkX+)$CNLKFykv@!XQhUh#w_>J*ZV)H#teUDSWeVMrB zppWAFqr3xcBJh^;6-vlxp|S zz5D0h{d4dBxp)8EtD>IsGnV`3UfCG`w|R8=kr^nE?~JZdkxPqSbR&-#sf%}+4laI_ z0FytA`;~4_fJyq|MofwXcl|~wlYmJAgf>i0l?qIe6LGTCMofsCcWmo9UFrn8_jwQ+ zG4X4JNn%A{7D4rgGG=_>+BcLv-E+-8Vu$$4#pR7^s`M`Yo@=&jsP|m6t={H6*X$o_ z(F0^{B?00+*K9)lbk8;W%OYY0aAU67dt#=SufKWu;_=-*M$o!z*HlSoA4~)t_ry#M z^8Nn)&doQ`(aOC&amr}5c$ey zRe6B2L+r^rJeBs&-?+P;UPGks=6jW`!o2&HaO+hjSG~VKcqyxgtKGM;@O~wX=TdT7 z-K%W1vhaQ-oIdtSX58ID%ID}k4{zJ23Z;d)f9~BMytHmu_XjWc2QNQI*8X40!@HgO zZT);2w}0){U#$xIiw z3g6=rvfO3j*lF;HUpiqtg-0CNZX8eH5x;hV zoq4}*=+QKdr|_s`kIJt3^8Sc0Sx{NqOk>JjvQwhr7{t zgGYn#h%-C^)8G+TBETF8k4l^AwInV+xPB95OJC^QaUj-tQq?4;h#Sk4E7U7eof8!J|^1nCz7E zsI-|LPdSgcBr@zYcvK1$@9pH8$iOssBsGx-E{Y6HgGZ%AG1)0RDs5)Rv(zXiOyLoi zMJ|II#@2>Xq?jZD<%E$wkMh2$ABPoqMaBXB@ z8ayhMifNAIJmTWWjdLVCn&mv=>d0-FQXP5V^2q4B!6PpE(hXepWg1GG*|j9~kq0i2 z3{2xZk^;#CS4ak?aUMy9J< zw8(i>+Dv20dBg=_rhyB>wC#1JK+Ar8a!D9q8ayf`S_o6(bzBst(N5tJmxY0y29HXa z7P3=##D!rR?GzqyX&BgP@QBN%cLNtr2d2TJQpkMYcP^bi4O}|Ct?#9jIbjNqxOjRa zrtpZ%r^8NzN2Q!O*(q@bE}-6Mr|@W%I0KhZZ^RTHt-_<#IFIB3^dJwQ2YvwEXs7T< z9zYNL0J;%Vcq9*?VRwH2ln2m*Jb)hf0d$+4`k?_dSGYmyrK$zm!8G44HXbT8a&Lcz5 zFcfXU4s#SeLv1tZhX6w`C0=Lf8SsWeFxjuGZKmyH9zoB&7l%%@%`_(SXcRpIUL2(N zC16P3`8khLT{GV}~%(H89Y`Hs({+Gct!36Dh2P}@vn3Xeq3FdBM>QS=O>=ov;s z&j1V_Pth~fHnV*fJ;Nw^hT3KtQ+OnLhSAV7j73|pUrVBAfZcg+ik@KkK^uFvL!d*VQ)D<0(86Jwt6XjVXSe=ov;s&oGLfVH7>XXy_S$A>%1LGV~0i z=ov=QGt@TI<0(86Jwt6Xiz#}BQS=P3JI{B~GmN5V7!5rGFnEqc&j7m(JB3H0XQ*wa z$5VJDdWO-^GmN5V7)8%88hQp`$asohXXqJ5(KC#r@W{|J07LAQ^T^OMjG|{4MbA*% z{NTJ(>V~K1-#tG3PxjuY$Fd|%^J=k}VFN2zf#527(=A1&?z!iG6arQD)QHm5RFx`Q ztyZ^Mqo_!yGSr?CDG$%;sVREHCtw2-n~`S42C+g&T{99J5DUa7V1*E00FXwA4Ubv4 z$34%_{f687Mr1~G&Mhgbydpgxd+nG#$LyH>?6q$9M^`U(fakNPSIy^jRG!xf>_d(3 zSiTzSVWwaJ`!I}HlW_K-Q4^jUF?Koo(5MN|jTpO}eQ4B#=fFM;g|`SlPmEn)9|mV1 z8spTjZRe_B9|mV18Z|L?fqfX9eQ4B#=SFzW*@s3=j9p+K24^4IG{HU$U>^o&9~w0= z2L$^tIQ!732_J!dP~7qU3HD(C`!G2B&=@Ct1omNY_MuS|J_7roxD$0((OVyZeHfg5 zXp9p+0{bvH`_QNfAAx-soPB82gpa^J49-5ZX@Y$iz&;GlJ~V2=M_?ZYXCE3h;UlmQ ziaXwy3Wu=mOJE-cXCE5lgpa^J49-3@YQjfg9|mV18a4H6R(H$+oqcH3gpa^J49-3@ zYQje|#v^AR8a3e~un&W?4{e%Y9|o`wgR>8fn(z_Whr!v0Mosu=!Mx7dhel2K2<*e) z>_ej_e6(P%$=QcSP521x!{F>gqo#gs>m#ragR>8fn(z_Whr!v0Most#?8D&fL!%~q z1omNY_MuG^?85-|VQ}`LQ4>A_`!G2B(5ML?fqhWi@$m?`90srtgR>8fal%Jn9|mV1 z8a3e~MNO^lRoo7D-TssQu>0w6E?>U*^@qsmJS`&05 z_`t#Q9W`l6!{+WI@*NG%2R3T@TysReqgrOL?$SV<{>`Siw;ixCPXA^b!3Wkd!*Tjt zbKLtk+vt2?W1K$M9Ki=F?nK?yr#CN%aqnv%iaVj{J{rLXD(-})9+Aaqud-2bCp6(B z@PUdut_ePH1RpqhzN5Bw2Ol_s4;-BjY}AC0zy~VsMBU*d@PUdup$Q*>4;-BjY^*zc z1U_(dKCn>}K0>~u(fPneP58(s1moxvf<{gK+SW(l14o|{G-|>}J}FR~Mdr=KrA-rj z;0Qi&bUv_A6XOy1z|r#^HEO~~-~$zRqVDh!_`uQmz{WV?Bk+Nv^MM=9?ZoZ#zxVm> zkH7il#qQ^q-~8(F?y&pQUH5pm|8zec#@4CZp~LIU-(~`njdm_W+CwupNqQ^z%S@8i z2#u272>vdUq`k`;CA|&&RVGQ5c(h5Qq`%7iO(w~r^2T|MlKv+17nvk&LeMDbFEW3R zNzjgso3oA;Q%#w2OefksJxjrm(llEoCkXNk9%zr-Y|62p@I67zSM5d4IDz&QIW zOp*!rAZ44s!6cb*4+v*}fk`sq9sthHH%qegn`n!>dmL|;WWqhbo1Jc!WWqh5n-4ab zmSn;`eiw<7+iuVANHXCbu+5G(OETdepv_J;>##|}Js_JMY?frgJph|MPn#qY?kSA% z=6&f{vm_JlDTwh_(oU;MGT|Oj%?>q7GT|OT&7Px8k_q>KX?CPpk_q<|ym<30ooJS1 z!aXFK?ZBrb6Ye3}M8+Ieup0APtxF*=a5DIGUF^`h(-g?CBb3Kd~U-wmjuG zU-ONU_6nH&z=9-gcDj+=KJ&U@swb^u7r#)!^Ye5FQ+_Yi5=vvd?+ zlBaseTbc(bzLWTpEOXmfKkf<@ziDv?@g-?r|BcVm=2o3^_>#1*|3*pu+BQntik75( z{WnV5NYOckFUg`3eU|PXhwvqta8Ci^Hx+jVUy=#;fWdbJUy=#;ApM{d_(}qja1XK% zI)E?9gnJ4MzkQZ=u2PZ-_aOJ61-6Y&o82HVzbnIS|3HJcI zcj{h}3HKo5phNePOt=RL2c5Z>WMb?APv|(IBoku~a6+dEC7Ey!vJE;+D9Oawfco9N&Wp`whtM;b0^EUqNu?l}~mZyTkLJ+;Je z^VryPaDq@#Cfwr$q1YC4&%pu0w&ro-<^bYGQHN*2(y(U<;zm&?B;7qAZfc3q<|+Kk zro}n{JbwbkJgB_WJ@5nS( z+}(pMnS&EIjgtDcje9`c9GtjmlyvuixH&j+(5B6sib)w?#9&FGYe1oPfO5dP4V29@5 zJ2Z`w?jFw|s06HunVSD(l8vZQt-Q%eP8~dfZ$1?{i%EZjgvjHAF z8K5LpVzlC(4DjH&0F`Pu;U2#S@!+WdC7E!KUxRq?On{P1xTj?0+qlOQ0ZKCAo|2Sr zD~VNucpgB_%+%MmlKAe4rva3tk3F6RP!&(O$8SJ9coINKCdMA$Pd{Kk{gBvCmxet{ zPXVYX6YlZ-^aJ+OYl%@q`t64Y?57`2?x&yLEtQ5>9BXdz{C}F>yL&wSpR%AQ+~Zdt z9z6S>Bokwg-+XxRi8?zS%U*u14W&X^sxu5fufE}I%{wMYoMqT zl0I_-Yj8-g1_x&i4qy!wbs|c44_Jd*V$|c#8VDZp^~(fnAPw_4Sc5}?H4uR0k{Eju ztihq|{BMRcum-in@U!%p8(4!{Vp!7M1J>Y>U=0q=8XUkH91^U7H0)V|HK-*<#18JChz#1s(M3lbf2G*dK7C59!1%GirzB;lUuW2ZHK-*< zEAFg857wZT7?yPRfHhFm@lNEdK@ZkIQ70tbJzx!b&+gIIJkA>QU=0*?B1-%2>A@QG z3D!Uw)-RFWLs2K9boYQYs3nFwk-G=1L7!j^`m*zX{5tEw8uSU)KpHOTq)sg{T5)F$ zdawqy#IU4~Jzx#`1Z&Xy+0P!VfufFgBG2y8gEgonhAZyw0c)VB6H&T*z#1s(grvI% ztU;e(4SLV+(StSU6Rd$WtgC}Hs3k_5$613OtU)a?Ea_tpSc5*n8uXssqX%oCsN*f} ztU(Xfpq3b}xX;|c8Yt>SlFxn*&?i`f-m`o3U=8{NYak8p>X^ADScBfP zd-PxpYKhSnch;Z>YfwuJOS*f&8Yt>`i#u!3gEdgp2}z&1fi>t8tU>RrLGM=;>UPeA zdz>}s!5Y*O!_DLF0c)VB6VKAe9=57wZT7?$*z8(0HH9d90I4SKK!iaH_bV-Hw^KEWFF&KmT7=b)~(O^iLx8uWhU zpd=ISan_&*YoMqT&(hrk)<97wB;7q=4HR`;(piHZtU;e(4WwZn2W!wL&hGcl8uVZd zYKc)pI&0ATU4y!kIpH2>4SKK!iaOCeK63+Wpr{j)KK6h$P}B)YAA7(W^a<9Wch;Z> zYtScH18G>l1Zz-BjCLYt4SKK!wZyQby9ca6pI{AoXAOF=28ue~;-1%_2WwDE3|HL8 z9J@QO8@{S%V&|fuc@G`gadlgFe9;^v)XeU=0*?B1(4;Sc6((xOvKL7&KL(0g8k9;`v1U=5_< zT^(ajf;H%!H5kAe)DnX&E{$!Jy6nox##&-n(%dun4M{^SF)V4T21*QPQ7Y{oscy549IIxOAJ@s+%teR7!s_3G`!+Ib5qobird&TfHkNkhAVFF8TRg;A;B6* z!zvEeKvBml?yP|>KR~}!iP4ICUIS%>cgX~6APuiL+>>Aplxo{0;hqF*puE^F>7-6A zG5jpuJzx!LiD5~14_JdC!5S!WnOEGif+#Csq7%7$z#7yN!xeY;fHhG5sCbml8Vty5 zpgcVZNgsQ_8Yp>5Lekv>)<97wB;7q=4Tc13ptFS5iNG4@9Cac}cMn*DT4J;lm7V`1 zurh!((2=f0l0c)VB6H&T*z#1s(grvI%tih0A z4F+co2CxQ0f;Etab#<@?wZv%iIBPI~HK-+qC4KAxYcM2OgTYyY0jzk81_M}w zT4K23K63+Wpr{j3x_iJHDC&fyy9ca+?rKR$x_iJH=oXZOq>nwwYcM2OgTYyY0j$B0 z$ZH@CGbC7pT4J;ld0vA7tU)a?Ea_tpSc4(K8Vr7i!T{DlQO8@{S%U$rK`k*{ad!_` z14W&P(%l2rKv5?o-92Cph6HOcIBPI~H5d}Cfi$eEgEgonMw`c3g8{5TEio+VV-Hw^ zA;B69&KeA04HR{}#ho=6z#7yN!xi_j2dsgjPDJVM0c)VB6O!&8um(edH5i;V7{D3~ z3D!Uw-qo>NnqUnEXAMTM2DQXsi%Vl0uX5v;+OU=5^U z6$fjesN)rP)?fr{P)m$f+*yMWtihOI4W!`}ch*2rCo1mlL0*GeVz}b&9^^F`6L}5B zvh#o3+8n_ejETGk(r`(*C&3zw&Kiu!YfwuJKTCHHSc6((Skm1C)<99mJCU;nBUpnm z!5T=zng^`Gm|zXYvh%;`L|_eSiP2~2c@0Le2DQYnq`L>K!I)qT#V%}b2du%EU=2pULtzAKFeX?7X;@bWYfwuJKTCHHSc6((SklKHum)p- zH5i>W7{MBhi8~aeVb2n*K`k*_anEZof;Ffmh9%uSU=79uYcM)%FoHEu)N%Lt9SS2@ zgIZ#^;y(6(HBi)vDBV3^4HR`k(%l2rU`((Eqq7DhSc5Tfhk`V$tAjPDB}SXa?@$=Q z8q^ZQlD=XM)?iGq2BWhEBUl4P9dB{JLtzAKP)iI~+{YfU28ucnrMm~Lfuc@Gx_iJH zj0x6Ybk<M1lFLI7_PXvX98L3mKg1qp4VUkYoMqT zQM!A;8cYe+U~<-ALS6$!oru!i1J+ zhP~Cn8q^Y_&(c|g39LaaF)Zos0c$WN@)}H@*I)u`ps3?5?ySLtyau(zaK(M>0c)VB z6H&T*z#1s(grvI%c@3rnYcM%$Fo89g5_t`zVO<@pK`k-bJf7EJ0&7r93`_dV4XnYG zU=1eEYcPQ|P}K1jch+D6YfwuJSKP-Qum*}c5v98atbw9VNV$<-2>KOO0Wi#vj!9L8cYe+KpN&Aum-inXp1{*Fo89w zC59#4Jzx!{1ZyxkYcPQ|P}K1j_d66Oum-inaK+s{U=0*?B1(4;SOZ0!kaYKeHJB2t z!Q^)+OkfSB1ZyA-@9Mr=T1yN!kGlt~K`k*V>8!y7)?iB9p&$*bI9P)z!5U1?8cbjf zYKh^B`*#mmgIZ!((%l2rKvBoLdfE9uGS(AVgDJrpNW&$u=9XX$CT9&Mum-in@UwLH zAg@6!F)Zos0c)VBqUyQ-U>^oHdxh8Yt>SlKOO0Wi# zvj!7bgDJrpNW-2bSc6((wBpVhOkfRaiD5~14_JdK!5U1?8cbjf6m{G^&KgW$4Qh$u ziu>3D)<97wqICCwHBi(ENp}xegDJrpOwJliU=5}OYak8l>R=6OiP7e9)?fl_P)iI; z`kEV9gDJrpOwJliU=0*?yv3b0n7|s;62leuu?MVyqE1BV?g49{s1uUz9Fxn*Feg}p z*;#`btbw9VMCtAUYfwuJKTCHHSOZ0!h|=8y)?iMs2D7sUGgyN;!5T=z-s)ftYKhTj z>8!yF)}WRcmUQ=kHJB5u!R)NT4AwwV$6MT4gBh$rEiqhiAA7(WDC$I%?jEoPiaH_b z?g48sCs>2oS%Vp@!JJ?Xq+wkhtU)a?+C0u0%wP>_iD5~fxq&s96Rg4PticS{KvBnA z+*yMetU)a?TyYK!JJ?XW@im%um*F2HIRmP zb!QD~iT5_oU;Ops-#&Wr^s9?UPab{#^4VWrT<^ZTc>2Ze+0(Cguby39{MGLFyZtBq zVfT-B`%n9MeDwIy*H_QKdVc-<*B7rIJ^AzBK6-k6ef9j8-&~jf``br9{n;=6;SYcE z=t;NwlAT@tqYFxH$wBkEuU>wk5VRC^O7O7v1v^`=lb|g)GzyyW{L02!+VP1s3fh#< zlPKX;2xA)b#Hbq~Z!{XfD7v~xk%_~@&+xyyFqoSDwOLKc) znrl=vw_s&%@3)&aDwFJ%4)n=*gy!zHJI*@67WA<2=D=c*$tyY%k061f$sRJi%yv>G;Oqd4f@U&#CX% z?Qr+%^66K*Uta2~x_ORq@XMpRgHx889$3L;Ab)U>vq>KzurB2dG+GrYPb8IC zkaKhIIX6oiKh&kAXd@bq!PN4O4bY~DV=!isp_Ug`G>hO6%-#>dG{$HK!5Nsn=i6*l zG<)C(%-*l|Y*aLJ-~`OxPrx)Pnl*3$X72}J8WqhL$hEom^Dm8x_Q{3gFMCh5*{EnA zTsZx*_e`6Oisl&{e%brsmo`N|{DQMDdq4ZqsHk5%zOr!iW$#B{8WqhmIQg>olP`^m z<{2D(*?W@BMn&@s&b{pY+)JaPc?QQ`_I~W8QPDhuQ!jfz_0p(loMsYiUzTQ6h>2EGyzWC(FFJ4_-UGILPDdCH6ng`In-Y$2v zMW@T?Z1n{f+LbBdLqn)E?eR;~SBY?=U8ANofHZxTsFrygMjJJ)2|CFI4o+!&|5ycDO;h;gl5qo%#Sr0Fwa+-ujUX)iEo z+Rl>dZZqOWO?!n&6RWMh_S2|oFEMGlk8rhJqo(@^ciXA%Dl^=dRJ8Ra_Yp3)Ym5^< z@?{{!S!9Af!aftOx07bVM`dAVTX)}U(wz(mA2|o!>8dz;f8v6>w&z)Pe=JV;$oHEX zHQ^)QaZ=qAJ}Nsv7AJhgpbNTkkuVN@|~x~y2D4l z_oO(BOwdQpgKKBW$0J;H*A}M(;nFm~LAzB6A2|^&P57vk8Lm5g>9&0-FWSTXbQ=!0?fuf; z#u#n1!r8XHpKWVYG|%8@+uo11H7c5CaI$UhH}*CvnrCpZZSM!$8WnANhjVRvKiAf% zXr95bw!I%~Yg9DP;8fe*Pqj5F+6)he+VxhjYCwlAvb5j{x}3RJ~AyDG(J!L+V)-Nxt-KT@$snA?psY?bw3mK(ecP}G)=N_QpJI^ zws!Zd>(Yde97)?~Zb1NDWxf1^q3d>^UA=tqPcC-9{N~k{fs9;2F!U{R>?xktLdP== z`zSAqhvq_3G_cpRS_tZ}57I_O+kf<&7E(04uu)O-;7zTqHKkZY-i$JhiuP9Yd=^qH z^X{mk?bmxY3n?02xQTJwJAVGn<>ke1cCWsE`t0JWHQ7XeC_CfFr_-rP?X1_q8TSIb zKh!Iv>2JA%U&^ARH1?Kj)bv^R0q5~*na8Kzrit0Y!81Q9PIJUYbNk%SAFwqe+va2Q zB$uL(ckdaw57^IZj+NK_{Z(sEKXjhZyhB3suB1>ucA$daKGe}AX)l5f3C(MXVM%)v zbVz7kOAJe@=WZ;HgyxDmQE`83AfdUUPDpy!Ktl7*6PhMijv@uk31DEuK=4}=CgytO*nk(u=ls1ZXNNBF86O!&8Bs5pl2}ySk5}GUO zgrvI%3C%lCXx`X7?j9sG?>wP-qolhBNuxSX8r3N2?m^b5u4Ji-y2rCdb+|me^UKrQ zqV&ttJLHY(Ja1H^r26vaeTl?TiaJqocMmd0De8ozy9cSGI!_(dSaJQ@w&K1o(s}Nv zMoD)Ml1Fu(JZdAkonf87d(PiI%K2M7ax*2{_KtO4`ojh0^eSUan_oo-NM)tvusndG?Rx@;&q5Y*89pd(HS-t|cB{sEv~L zs?w9NxkD{6ENQQ*8Fy_f>g}tlF-m(?&G=we)Coy@Rn7QfR@4bedsWRip`xf0k~YxK zxNBQcCnRm4pK(S-Q70sApr3I_MN!8k{jTj9cWo=`grvI%cWo=`grvI%cWo=`grvI% zcWuvp*LItG{I2a8cWuw*cJHXi%gxuvfquqa+q2)b-5902$5XBiiaHUcyT>!GNiyLc zziWH;glm#axW~7H7vBw*WZXT{*f!7N>DD9}caJn&(myh5iNQ{^lnZr^ooMl7YeOwD zENSjpd?#3v@v%o59;Ge3OET`B#j}PaK+A8kJNET!xQPlBH-Gi-ZMV+X)y9Zm-i*HRgMyX%h_DkbghQ+t08ztR6*qUB^Yr0X=-Gi;^#kZ#0 zBz=QM!AuHNE)ObfcuZ z2V2vMI#F?V54NTk-$< zZ%sE!x_huSz4+F2qojUq`z$f`_{BzzlI|YdY_#~zMvap09$am-_|-;jl76+(g1e0t zzuTx$(%pm0jTXP$s8Q10gWHW1b=*DWwxLan<9egTuQzIp(%pmmjTXP(s8Q10gA0xp zzu>4*(%pj_juyY+s8LeCwtbdxk6&@rDCzFO9Y>4banva3?!hHTi(hioCh4rf0@h$j zum;kwX9?C|aWcO#N_P)fgIZ#AdD*XOtih6C z4VJR=zpc2FI*K|z_LQCft)!o9sU?Oh?(P9=uq0T6#aV*|tih6C4W!`}$9_+OHCX(5 zw*{<0EiwEo-92CpYKdVE=`ZR}aW8Yt?7q`7DH zBV>xQ%vs(XvTK^aNW=OiSOY~Jmvq)(1#3`Cj7I6K!3x%3O|S;i@QVA`qo@-VclUrb zs3nFg?(P9=uqIf8)meiTtihUK4W!}E(#M`!Vz}b&9_HCX+K`3lxRQO6DGC(Ku{2DQX+#eM7n zYoMqTQM!A;8Yt?7q`L>K!J1$VR%Z=Xum)>_HIRmNb+87t#Ax$4Yp{Yfs3nFaedY$% zU`?KOO|S;5AA?`P8mtM{KpI|gKZ;mO3|HLU1JyqK?1Soi$j& z8q^ZQ75A|Rtbw9VMCtAUYoMqTlI|X`25W*fSj*1;wqIiGNw5ZM+44b}u}u$Gum)?{`QJ!_HK-*OtihUK z4c4;rzpXgj<7oiZln);gTb(sn!5Y*O!xeY;Ag@6!F)Zos0c)VBc`H&?I*Ya*|K zG`xA>o&;;KI%}{ZuR$#_{4Cu)U=3=CQAuYFRGKqKw9Tby{*k8P2FlJKJ|HJe8-Ao|DWQHckV!%2_HFkAWirv4j%NJA?{dLYe&k37wR>JA^p*#p%bK63a#aVC7^@PXolkK&mQ6eoP-_<`a~_{dWoC{Fk& z&L1dF_{aeS#hLJt0|?#T2?S{-eB=azG~uIox`SRC?jvUqM#UZXkuwO26XQ`FLQtF- zkDNkKoQd(sGae{Tj7M<{L2+U{at=XpCdQ*e1svz`iWB2e97Ir@7>}GpP@IYJ$Vr55 z?;!KQ31rV^hV?2uIKTw<)j~q%+oCzN} zl+f*+N|0v4M@}V36F!QkKn4mb}BPSCSXTnELCMZsf zNAWZWiWB3Jvk8hbF&-6CVB6;%PLO88M-C^b?(k8ZPEg(9BgYdIXTnF0CvV14k}0!^SXFegkBon?v5&q ziaS1bII5sH;iEXKpg7?phZPiOVx6I&1KU3Dw1PAfJ}T^hX~IWwTtRh*k32Vm;!OC+ zc?Go*d=v*36eoP-*%1_H!beUlbbCh@q?z!MBMZ`mkK*|edTDsOJG3w=?zoQ}T2P$u zQJh*(obZuj3yL%0qXH3Z`@C}t(oFcMPz0t4AH~51)g3YH z@R8?9P@D-LIlIv5GQe%(LTM&^iFJlJ!=O0z*tdT7%NZ1B z;`_)U2E~c*qj<&y#fk4D#~2i6!bgrVbbIF*q?!0Wa*jco@KGFO=%wLp_THXi%IOkDO&toQd(s^Cl=xj7M>pL2+U{a+*PLCdMPD85AeRqd3l>I58eM z&!9LHX&A5-G0ZsQ&Ei?H3)Mf-UeO_0~3~Ty$q{Ses zdo44p=|0lOHZp?(k89XXwB)bl@3knc=#_ zN8lN1nPE-%2t0%0PP99G1fHQw@C+Szh7LSKm*5$s;q4Bdp_Unap5Pfe@C>!guqMVM z@C>>!Jl;m&89ML`iaVhRAAx7+5|m|#T{>V@C+Sz zhFWI0?wHqsXHeXUIN>Ak42nCU2_J!H=n_0b2cDq=&(I}!25F$rV_uiw89ML`9e9RX zX0+YGGj!k?YMEh8_y|0M;*PgFc!mx>H^DR1GNaEEJVOVbp_Uoegpa^8bP1lJ z1JBTbXHeYnb_dVUdCG;cmKm-)#v||yiaQY}eB?Q0?*KaXXp|vo_=AhWro`b;}LiU#hr)~J_66sC3uDoJVOVbp-b=#(r|BrXQ*XH zpC@>R4m?9GGpq?8foJFvJVOVbp##sLxZ~{(o}mNJP|FP09pe#r2F0C-6F%}p45Q*s zXu?O}8M*||(1B;@z%z6So6oyGQ*ngqXY6Y)H1`G&NCd4pFwel`;s(Jci)Fq+zCzh(E&U|Ei+tq_t63Q84d}a zK^myL^9+jnMBV@5uOI*R(Tk^FT|9d7=;z;DUS9lW_v-7X&n~VWJ%04{)$^~OUqAo# z#j8h8{`|L(o?c&HJ^$r5*X95I_R&v&_KSb`!=F5Q(jN+gu;K6y;2vsh$7iHKA7&+` z0ZsQ?Ei(2!iR$vI ze~?a^qw(d2eOtK*7Tk+Vh2)jZ+rSC&g~Qb{N=O1ytv+}Ghe@a zvHSAk=@+|aPru&1dUkd3SG(Wu_Mh~J-9O&#KketSwN>6;8Ljf(chb+<^- z<}Hni<`(yg6zy%>sAyhsr%189I-<2Ur?^j~Xg+C-(cYlGPcKE47md;P>3x@8iYhOx zXrA#s`a!u85{l*--=UXc!ZW@@@B8yoOnAog4fyW76ce8DYy-YGFU5psJlBBl%u6xh z8Q+=reR(M+JmdTFxcQ)FHVF4e^NjDwE5?Lpd{5qYcz$0K0}+Jc(SJSpZ$z(FIM66K(-=4ZApS-58_U#c^xJnD7hI$H6e3JgzZD zn{+yAtr!!ILFzbI#zE`G7;Vz&n6+X|c*ZenhpeS|$}{KT?(-l2@sEG@(??I>U{9yo z)~bH|2nIe6clxGy_+$P&+}X@fgVQPNzGWhJ9_}7J@qDRz1tw;PIA4V6;d!`w^rY>@ zh;v1lB7WH6?!3C`)9dr+M=f7v=6G;K|^QPY=rMt_e;(-wIeHEm~6b+=_6 zY1+zYqoyzOjJ{JMOK05LPpZe~~re1I9C&=GC;=JSN z=N%h0;ZvMQG!=P96oW1fX)5xJ zC~S&TntG@iQP>n|r$;}gx$RPK8B1_Zb41?h(a&kNio&Kis5yG#>84@W{qo>Q>zER%N^2nDx;(Y1o=Sy2fVP_mLRpi@dY88c_al%xQXGCFW z95EgJh-qu2a4620j(*0pRTRT14w;UA$h1`y9>pos(NCGSio&Ewn?3q5(^gTq6z5Dw z&zs#Sii4&j4w{ahIJ;F8vtFDu9sQ(ft0)|Wqo#^H(fN@(d&F7O(a)N;MhZvau<7WB zOYMd2u%IUW7XX{#t4g+r%`Jkh0a>U6}Z)6uhNw?+y_;n?Zu$4*;C;V7It zRpgoK!%;YRI{LxW)=1$foID-<-XGGmm6Aqx(LgUqUM@=|^IyueV z`b^zX6RrqXgNUW{MGm*kkPQGcWCF3ZdZ=sLM-lc$Ztcl&@78AuM>+AW zNHdNC@;xED_TVK^63vWJNVGlq@m+~#90jsv0@*S-+0xkgfwoM3h*yzj#;C%XY@aFE7Db+L z6q0REfLj!KMigTd=$6UpmeyyASs!o}MV^Tivpzr5s||sSqx?{>@Cee(e{9La@ zomiQiSZRHx7^8r!DDuoR#jFnuiXu;l0z#Ppp-c{;G*%xJ$^;5!atftY6k`-H6h)q? zJ{$!OMUiJj;V3X8Q-&Ftz>G{_My3oiA`yS}ff=cVhUcfaOMC(|QVWfX!ckyGrVKMO zA^Y|OW<-%ES|7~F1ZJcb8m>O>6Q970DDq6Ca1`(kMV=9bqkwlP@{A}P1-xU*;2jh0 z6rX^1Oc}gGBJL>Q9ktMS>togjyrUKx7losMcT5?)V?rM833$hJ8t*v087mQgroc67 zq2cO-*O#X{Ly>2y4@ZH*n4H3BjTDXohA}yY(JG2rA2^K3IgCb8FcTA)i7CTONW}Xon29OF zOiW11J%O31g@$d4tlSfriCSn}6k`;a2}Pdhr?_W)0yCk=Goo-5n29OFOiakkJ%O1} zSX(0D_^QD7z%c_LCU6BC$;DZ@-i#2p1@V#+WR6Vh`}U?ysz;b#hFVgfT! z3yq7yQD7z%d8VN-MuC}7?SM9`(|7`dpv%*q6^bWdO= zYN6rQ2Qx8&nV2%nghaghU?voKqVOeF$Q>_=soiP_WL z>EadNkE(^nBlYj78O%g2G%o6nnsEoYB9C_|iQt*~VNXS#5p_q+U?ysz@#?#yW-t?T zhMABEs_(1kiab+&AERb46SdHI_2DQm6LW@{n9JwZ=F@xzGoi>6)kjji8O%g2G+cc! z6Em0zMV^Tijsi2G$TOmF6qpG`o)Lwkz)Z{;W@0Y*g0;TyN6i^#Vg@rYgPEv>##=W-t?ThMABEx|DxM)k5P91xJCIsD*|_!A#6x zCguz?ArY@Wn29;VOw3>=W-t@A(0KJRMuC~Ag~mnUC@>R>Jkj})<6{OhF=v64FzUm1~V~dm8O%g2G%gB9ftgU`nTEm`1!h8#XGGyBFcWho&&CX9Vg@rYXYy=F1YHVa zREC+D!A#6xCTgMK)(0~&gPEv>#zo;MFcXSA(fUY<yDKTc;Tt0)Dm@_FcB!XuOM`f6a8O+2CW}+4vex_h1 zW-t@A(6}fZ1!h8#C%P1_FQ36oDDsRb90g`#&M*@*n28z8gd)#G3P*vNsD;KG3XTFZ zp~y3lVyzF%#GGL!W?W)EgPE8!%!EYTreG#&q2Xr=W?}|2Q45WW!ckx*<_t42gPEAY zOepe1>w}q?!A#UbU%o%241~V}u&%~TzCM4oE1v60#4L?&b6Em2J zT4-Dpjsi0=XPAi@%)|_4LXjt0A9*HbFcY=Vc=a(xftgU`nMmO%FcXSABML`>nV2)o z#EcuxXD}0UhMABEIzPs!3^Orf=k2&(U^=ZZX2eIKJ1Zd)dw@NfSFh-7azbsDDp&? z0yD9InOHK+ghafdz)UO|W?}&|v4EMVg@&Ign280QsEx&MM`_fAPXTQx z?s(n7Y%E|l6n8=sz5}wcII_`LcZ`rAHWYUvPWTSM#^OmX8so%x2VP@wUZYVHJ_4?> zIIhvC2_GTD#p1L^qo#gs>m$G#izm2f(*&!rfYn$M*O5pAar&{W#ZisMII$iAQlpj` zeTO5t#R5=caZsZ%PWT9%#^Rhtqb7U=Oha+Uy@~5Z7El_CQyPtN!bgBK7Kbz%HQ^&L z8j3qncNM+$5fF{V(^|B}2|{B5p|N;Yi$+cO2!O`ofJUPxd;~s2amSx0@Qej`#^Tq2 zG{y-ZfzDW*&S=zxj{s*V?nK=&9)ZnRoXu#A6Fvf(u{fI1s0kk-o5kW}Mx&;FZR;a| z8H*>gXww9jv4G21JeNhICVT`eV{t5_Q4>A_m7%!feF=#y7C;$`Lm7>6!be~-7H2XV zHQ^&58HzhmclZcI#^OXqW1R32fQ-d~j7ClP2t3B(JVv9Yer@X`;24Wv`_ZNe8e;*C zv3LfHMost#Fvj9AMx!Qt1QtVa$NLgcj0Gsh;^`|I}05KGIqVDh! zIE=+PjK(lM^8GfLE81I=e5&E zKmFM+{^1XQ^5{vw0Pa}<_bh&i%%-oNUK5jsz4KSFJ+;i>_pCIa>EGS8%&?}vpI4AQ zwal=luV1Z5hO#=?vw5EH&-*G9&&qSBsGi|>?^=kQ%{aaS1FB_)pOwGQS7c79Wrj8V zeZB$$QrwBU`}=$a1EjbUnriy(^8^B} zAb(cBVWv@2zqa)ez@OE@pEgZ!KP$MO)w!QWP521d&+6Duqb9~LP(O-0-ai5Ttbl%2 zzg(sJA@)_*tF!X^ay-0`Rjs@YARXAK_k^)$f&Q)YPwS zeFWTR^=oA|n(uMm0y<~~9ke!k%a8RQrd*u|I}on8 z6PoZH$e`89piSMkZTi{8)2rt%e)V|wi{XcV_GgbCKl=LW`B%@cpa1&e)uShW{@X`S zudlD3|MHvb@_&DO{IFO-5Un7HRuDwxk-hxl;?Wb;`z@kyC~m5$g&t>&bso_m3X1{> zQsmo5-zo}^f(cr2Q%z&_)kfP+f)Cr(p`gY{K?SX#f>x)3T18bMixi)0js>-f!gt_& z6nUbdkacAR=(9TL(;6w92hwMC(x+7vLmp5cMV_fX90k^Ab=IdfQaB3m&g$?^t0)`= zdS`Wdr&Sb=0=~04zSAfQerE;0vpT=C72Upg-wmErq3%EcKWhT`Spod40Dfwj$Jg&> zKzYk6y}&oyHwA#7T4q=i_5<*vxVKJej1%qy@Uxx-e%@!B!mI#<)&wB5BA?3&Kxj<> zLefB+I*?w=47Vwq3P7lq8PxQHvQ4%#jl@Uzr5Pr%#?PYUA}zwm%Gni ze({^#FMjkV!yo+c@^bg{r&rgn9`8Q?^5xa_?(?soKD)Sj^@r_~DNsi%62z=d9o03N zhvz*=5VHb1($m$GotV_z#~PT5rv^a9<5FuwN@Vv1$wkPdekb4;S}uA z>g-XgC_D=IXm$9gRTL%#eY84#)F=x4Xa#<>I)2nDis2Fb(dztBt0*R@0FV@UqMw35 zT0tPKP9U{L3P%A!S{*@Z6@{a~ASv=p_2DQ$NUK9gt&ze}ppaIlkhY@RH~+iM(9Tu7^T_ST*;_thkYrYi21XpL=jD#XGsS3fUha7O==qB;obyQ1Ix`|PR@G=$FB0h_72`{f>f6tY-z~P|DKmS-XvaWTf%xT%N_69rugnUFH0VM z`nPmhax6PU8=sEYmKuFqs;RF^1DbxPS}pT9O>5NjzBgi)R?7@)`X~R0J*m<6q#EP& zHM9|1Qi^-~9lgjt zHGOGp#L}4JKJonDR(Cz3ZJbyc(*>a?G~ZvFuE=1!;+)i)I430ytJjKiQnk$B^OpuR z-TSr7u%>%|#W|^3W?0j`zv7(Kdh(pqdu&sjt6FicO7%R^uTJ+>Y2f*TA5NUBTFV)y zP5)nUuBw(9e*Rb*#JQ?kW?0kTCo9fXDee=`^L@6dzkgPo!&(#Pu%zM7ALp=C&lB}} zOFzLmtQF_5YMIgJkBfv?oWoiZ=dh%Kx_iDs#hs|TkI^g6VbwCjb%*b84r@)E!&=Lk zsIBjC4oh(->JH!G99AteTzB{m=djk3=dj+N?`lq;&9ge^5jrk6{cX)7RNrfxHa)*f zk8OH>mj>5Q&hOH8V&!}WZL_)Q-=ya=XhGkVO}Onl{Co!OxMp}hgLZv!_5A7OqbE&k zQ1v{R^(CN*=QC)r=ZVbII?Lrd-{&)E!RLu@tMeJOXxBR$Sr&TFKnPokaI zNH_fi^V{!Wjda9b_6T%;Jc;g~UeA<<%`-<(_O;C5x|TGc>EmN9Gpy-rkJ^i~F}Ic( z*7UVU?ZrXU5c|zs>;0|2jpaz_W^Oj(yy|%Jyy{!p6vt3U97C;TMxPaOD~&jXs<^{z zs?tE+-BXG?q3Qbw+B5ey^)sm7N}JZ4+M702K5UEOoX0!%EnIVIZ=WalnR6cR==1db z5#_`7{(16P-|2Tw&8cl|*cpumB&w0F~eaXjJ<->Nr`&qipnD`dI z+%!bjlKln)!4aqgw&)ZTjYoX7jk8r?aMcksPbST5^J@X^V&l(&pWxK~~Iu)WVG z__3N(dmAVCv2z~pV7s65c)wXcR6cC)pXWT@Z}KybCFkA7cO&xhjVJd+PQM?d0Zr$t zYnj3M>WDmhBl7IkGQ*l!J4K$oT4q=iYp1w^Q*ob|tG~Z>&NGL@l4W{`(Sh z(XpbNJRgvuDus%|!Zq*}-v9>wMWk?1QvkJg^>volVmkCax$NMaVBxq3@V!Z}fQ7a51s0q6*vW;p(+idLj)?6z0wA#M z0*iM{Sab%$kKY#`&0^iVwdwhw_wn5;0Mphi{`Ma9#`@Md5z2ASnYduOCK=hjdp|@X zl=Iro@!fmA$nw~q&lg$7zM;ycl3OpI*LIG5>3or8tS_C{c8>4l^F@|NADu6{o8_xth$?yk1yu94~ z{OQ&8tH-;~zkGRhz5D#@r_U~~Uj1QnYWorQ(T})~UaM{vsSaCz_4130M^CiCeKMb@ zL~I&6;y(IX=%)IOqBuZ}`{-+-aZz8mA8{YOBF|Lc355~&(T|z?=p}+@>ZqF{&qV6p zA8{XjEj0d2-TNc5>5QIDXL}$0+q#sK^CQyfDDq78{c~$XJ{?7#5XFUWBNFN;@{A}P z1$b4FXGGyBT=}NRGoo-5(8ba3aBFORBq$yi--jLj61P@SI10D8jiu0V=PxO4HY+G2 zu5nZ38BsV2_~Ph!by}+rMLd z`rT};k-|}{?=36xOr&rWZf8^E8BvT;xSnnFmFw2(!%?`OP4~QKB88)nU}y9MJFStz zQMjRP^c&h*Md7H`(?^VJ#!;&~YTA3ww{cC3Q4+DY)U@|C!Lbw?b(BOP>WhN4(732O zYQjoaEi^9bj+%gLOpa@`wZ249eIKI~dFGkAqo%#j`f8!^>bs++y?^md`@|R}5meuo z*cExE`tGP{?~ba4#;XrUb?&HXpK(;_B%5)6>fBL^JW>7fVQ8XoRPC9^&&a0lsHuaa zIv=AHc_vags&fFU78-6SklqtW@5!%=YP4wwM|E&iDKs7_9M!>5rO>!29M!>54tuv& zACBtaD8DkQRTPdoz)@YsQ3p8c07rEhM*;YraF~B8g@zjn*G5gaHfr)~qZ*%SIaX32N0ggJrQI37LHWVC%GyPL3G~Q5f z6fz}Fo++_0Qk>|XdN``2XADP*T!|BMB~GQ#xG2UbBuiA}8BsV2*%B3bMih?1sqV?I zd1-AZI12Z?OyzEw_%ns0z*S7nRkTJ5M**yuuyfWnL&4731hQiCt6o|og`oL_-0tm;hHyrOLFqv>o?Hj8Ub~ zaF-hK9ff;_rc!8J6l2tg@2FB}TojHP;ixg=sB-O(JySSp%s6Vq7=^orCckT_@qG%O za{|vfl|tjs6pk7(>nnxEMd7Fs-%(@6QRSY$Z9`3Plp~#u&lDF9O<+1Fzg)0Y6pq5} zf>S9p{7iAZ;55Ne(|R1*cMITojJN1%rw_BML`N_>P(~v%Yc#kaa11N0k#s z@#@1-xOZssdxu)P6dZ+%ho&jxsDdwStB;$9rgGa+xcXowCNL9IhMABEBE?!?DKs7_ z#waiowa~aI90g`#$}kgC!56HdFh*sVi3!ZaG{aFDWh#EUTZXlY#Ow>Z- z4FyMmnV2%n#DqJDCNL9V#+WR z6PSq!%*2#oCM4pm4`!kk8h)k)U)b6d%tS3TE(%A1nV2%n#8mJFixgv2hMAZOzF?wo zREC+D3cg^X7^5=G#8mJF6UBE_hMAZOzF?yGj><3-6PSq^%tS3T+NC67kbs+6FcWhDHR7V~s2R+J zBF~7rqh_SVQ{)*@chn4KLXl@geTV!PVOw3>= zW-t?qJQFD#1!kfa8t$iHCT1`biaZl390g`#&M*^m!56IceT-7%nMmO%FcY=V_%ns0 zz)Z{;W@0Y*!nXQgCguz?F@u?y!A#Ub!_@~fF@u??g~mlOMuC}7&nV2)oghaghU?%1aGcgx@VcVs^Ow>Z-)yEhGW}+4v7lot1Ow1W(VlMcCRUeMZ zFcUL!QOsZ_YN7G!V~hebQ45WW!ckx*6nWx>g5&rzn29;VOi08V3e3cuVJ2oU6Em2J zT4?y0f|;1XOw>Z-qHq+L2}Pc0sDdwSJ3p8SMV=9bqrgne8D?SzGckjim@~|TL{NQS znW%-v8w!pBGf@kTi(-rdGcjkFi5bkq3}#}^FcT8-X9{Mb78y%)|_4Vn*iIIm1jy1l7kFm0>1kFcUMFiCSpRqhMAZPzOe25U?ysz;b#hFVg@r&3yq7yQD7$K3^Oqoe8H-ZwZ059 zF(X0h3}&Jh8m~USqb7VuWtfS%;0soLj8Pe8VlMcCiQ+pd!%WOzCT1`bwb1Z01v4>& znW%-vMd2vqnNZ}37fQhww$BvIgd)#~!ckx*<_t42gPE9-XJXDU6B0r7F-B#Wi5bkq zj64&y(0J>^QD7!&p>a_-3e1Ee&$K>fePAZ$3^Orbs%o%241~V~(nV2)oghWt%I4Z+T%wQ&FFcY=V_%ns0z)aLaon29;VOh^QgVm~UAXJQ63F@u??g@zld;0yLlvBR5T zCT1`bGxAI*@ck-|~PGoi>cqHq-QOw1W(Vg@s@fSH&x zc_t)cU1|X{Q45VWltduvj;e*mMSYA~z)aLaR>JR=H6ftgU`8BsV2%*0Yajc}I&GqHe~STf9nMBGteCYB5{v4ELakY}P68m~Sa z1!kfa8W)A5z)UFeOhds@U?!FfGqHe~SinpynLHB`@zw`3Q40+}Q{#zo;MFcXSA z(@+?rkY{2!%}i|56u;YjA7kkao5wYx3y$6e%k<{q1jOipBYI#h^VkH9n%)6NbU?+u zZGlEjpCgUve~LSy>D_Nc_fy;_G~ZvFp6|oj+|7YQGOI86H1!kRsbwBnvEH+KUeQKP z?@^0hfim`0PSho6Xs?GbDOsyEpYMIggkGa%}u}pEF=>Ko=KBiJD z#xlj7(8N0mGbzP=Li7FkwB9$ine&|QI6M0Ee8<_NH+Qcu02>!1gIYWpRFn6mVPo_H zuCbOG^u9D)6If#{GpY%yaRJp>%M5G!9DV`RxOgI{w&w|^aRJk)xKF%KPQUl0f#>O4 zaf&;k>F>P-L}M*8{57od!br+;eH^lzL6B%|U^)Ezzo$f&pzn(z^FKPm2n zCVT{paq-kojn5N40>!vE#n`9`A0hG6;t*q_CVYgvPm42*jhgzk?feP|A_xwtsF*r=&r+qOHv#l^wJHcfDg3%JF_xy43J z_z2kI;;Eh*HQ^&ri;6q$qrwl`^MsEaT5OCHJ_572IJ4NO2_NBVti_SVMost##Ny&N zV>N2RM*tQVzZk1g6Fvg3xHzxasHtDuwmWde#c{cc3m#DQ^1bcAf3JxB?X)@FPCpNB@AYEY!n0kobZhaVT;0FZfnbf7Orp zgjeL-rf(JXK04wXUXf=+y_1gkh*#tpQSYTAzTy>mM$}*TBR=C5c}CRV_anaJ75ORA zZRdZtjRS4`+MqLHp@Z!@?U+Gyfsod3d`h*JQFD#g>`a8o)Lwkuu#7GLV0WT;V7(>uf9^g6@7oB`HEaf zE3knzfelE*2MVk@)H08+-^N)VUg=nLsAYyV(f_dKu=<)qW1Q%ISaMi>$zh|pZPV{y zG#~L9Ga|3rn8~Xq5o`Go-!Zk&V=HaD^yvw|L?G%PGPTgSsGDyDepCyMi~4Xjf`n6iw&#hD=QCHf>7V}P-1t0w zrXfDd`=@_6H){GsLwpuA6Fx$2Jn>o3w9n?oIQ47WcOAZ(&s@Cm3{u>KmPI0e){N1CqB#j=b0e6-)uSilnJWvvm(E<-@xAoXaAohdezJn&UGctM z6YpDT*gIzh$6L!ht~NEj$D{#GpSRR9!!`SI>X>&2{;| zzkPFV_Rs-oa-wPI{EiiQN&=8ckiA#P@DzWy&sTmNs9}dW2PB?@c#fR%#x#CV}I^)*k8u(gfu-&DBID2a&#hr-L-)%h- zn%6SJak`Is+yUQvKJ%vjDGk)!UT;d(Xs@?MP4`icZ05DhaNXTUJ(8LCp3J;4PWMrd zT;_^9(eCgOQkg66xMo3HHt&!gnamY;LK8khBJ;lDG;d~bZO;>TzxT*vuDBC%!beDB z-g_GJ#yH_4WHDFVi8$dSBr)$jiFsq3@DXyD_kQntqo#h%`jU@FeaV|1^=3&XZkoP- z+U*3EE@2 z%Ny$sA0cDNY-+Yi}!biw|+WYQx?bj}!Y3Jq{lz?t~`BBj15g_J)LykUgdMEeL5Qd{j0Bw(n%$gOFyz zN7#eteG@{O2_In-qW4`0X(oJxbO60?Lr62>BWy$Tz7HYIgpaTf(fdY(G!s6;MnvyB z5z3V3k8qsQUy9*4VoKiu7@ ziFqB)cGohaV{u`|w{3)@-HJQ@Ji)2=;M9BP)En!L@d%uH?+3dZHPxrB?pXKsbKQ-a z>eHra`+CZHl<-l>MQWN@uk%ygjd8+9$bZ^<{?kTH_z3w=d(VH`rU_2HNB+~^^Pe_q z!biw|+I#-fMost#`A-#h+(+OhdvKGzbCZp6!bjjHd(VH`s0kk-|Ec0m)EzzoH`#ms z)5bXUYg-?Io9vyNY}AC0kpHyz{HKkY@DcK#_MZQ=O%wS~d*nauJ^yK=CVYhar@iMt zZPbL1kpEP1$NLg^h8{dapWqp!;e81_L+|-d8|w}qfoG^?M#uNU7Hs=Gc!oZ~GxUWm zFing{37(-x{?i^jLoG90clXf%o}rc*)RczReE`p(xWoNZ8qhS*QP+~izmEp+3c!mKygW^tT!bjj4h6K+rfM*!MGbrvvobVBNhFWISN4S+;$f)s4 ziaQY}d<33BPg{akl-1l0ZrrX z$698zFX1}&0X#!3GpyhU*R=foB*JJi}1f z0_#h@&Y-vxb%&3@Gt@G}b%&3@GYkoyVZa^O19*lZ!81t1pC@>RT4uEF;28$+47JR# zCVT{*VMy={1MUqSz%wZBcwa&~^#MFXEi+tq_y|0M;!eZ~AAx63+zCzi2t31(;2DO( z7Hs_vo?%Gv36oyGNWw-o?!sbP|FN!VqOQHL2<|12t308ov;2CO};WmPgz%wZBM4a#uc!nXtGYsGv2Jj3+f@hG1dlNiEE%V;z zxjoA>2_O0g`kdH(cJ=bbKe^cb@|#y*K7aA6_ES5^!g0Xr=D}At%PalCT`Xx>%??=I zJoxHnqozNt16DU{na8KqrisY>LkmdPH!&Q|*ZY%TLxxkgQE0BJhFU&{<@S`+BN_TIX?;@&nwQ=HP+c4lefgVz^e z8#UePBMy|+GJ|!O2I6$9EAB+yeS$G!0k)PIj?))lM=ZdOz5v_!Jbi*OVgXihC+co5 zF}1sY@G9<6AQ2-7GM>3LK8m10_^Au zux)(_3$P;=U=?>FPWT85u%jO+Ym5^t0v>!PBoU9zA*V!&k2^zWU|mZ+6|IzgBPE{L5EsFxBt5S)$XvL#sMN%zCtb!$IL=c|iXUp{)GVf&`pKG%xR#r5vXi>F`go<03~_o^gQ+Wr3PwV{8! z+kYyio58E}u|!|Oef`6o09CX$sK-fbsFSiIs6F&IO8cZorXQwBVcm^NwA2 zU&Mmz^kmD^txtIRbW#4HZdGzqr39PCi%+`wzE}^_x@ytvb*!aY-Cixzl^^D1zAskU z!($CS!PfzP+pT}t&w8QVea`w;i^hJZ`_)c%?0$#&AVaH9?7L~6#Pq%SPib)dpY`|< zwfNS*>4};T-^B9TEiYeO?7n<@^~LVh^~X-<#p|T?-+nCeY)>S=nK?J?{=ls zXD_c_D6iP=SKsKJ_PTgj_gA(_D`ly=RvogOgh;r zPb}3C)hai(xnmABX{XdKLTz5ZX{vw4>JHPJ7S>weYo8p(!>rp9?M%`wVo zu?_LwXM5{uKI1#_7VFMySpmN_bLhpWFRpiZyzd;k-sum9eyV3^=KT(#$9smJwBGRQ z2ZzJ5SHqX}S@j~_!C6*rPWOniOm-9K?MGGV0&Z}DLwIlqIWfGwb#yDHP?lf4)ZPrgCEzlO-&FkgwmS~GW!>#I zxWD)L?vKCurLq}ce)FrxyTk5Jcim$Rw)^RD|7d#~j{f()F5h*tn&M5DFX7#ewQDCj z^6nT=7VK_=c|8Sq@JZb>6WD~Mir*ia;G&HiTb|Q#O!)kv=j6Snj6do&O3-}UE}CI( zyG?l*8qSx)UMVuBW4Aeu12^-b2Oq}0-G*-`J(GL>s=mwav|{a3dO6>|Xf>s4c~-GHe=6~-5S4?o)7N@45cLsn5d&0f8 zcs*XdWl&Z6552zjH-qXy`w{A>-CVL*l-Ga=omD4y4rMSM)?-KAyyPt#ItI~qYgRqE zdnUv>nDw@|TUoWeZPmDI%VgsCHciha%QEjx5cT!?I%Ryf`x9+$KYyk>U+z4on-7J1 z9~ixRZx@>fy=gaZ-s3QE;>}x@jc*@R=Hn|og)7aO8K}!z^i80?CU(SGF{5R2e$Y#Jx@QtlFzcH-tn<4B};`Kzjby_sHzOnfv7Dj&=T@)&)`%OGr^ZaV} z%S#QEY>eAi{97hj`tDd};dOJj&iZWD`tIRV%}LkSAE+m1S%r$feH?F}Wogm(xYT%e zW##=_a6Z9mT#I5m67MZ#maIl;wIp`Gu~}v@77<{T~E(A3;TE9S93XD;SV$0 zS?jCd-Wss4-091TT(h`SA3P`C4doDrM;_}2O`+C)p_<(Zxx5?{^Qm=}6C-jtnDX9Z zZhoQF_t|)A+3ZvY*^FB6vZD9S80KvxUQ_lh*d;RsW>~Pt*SX-P7W)!@OO+DW7(4wogy_>o}NY zcA#&k-zutpdERN(5|!rR^H6GAHpuHS?EO zQO?2g_l1j5{;Zq-l${i1TGqLVH(Rs&LMFY&vkF#y6VHd=#y9~$6>8esI6ThWKFYSn zEnV?lmK6&pdlT@MJJ@*TlMgaOI`w=vgHP*<%H7%Kds;azIhSvq-P;%BZkx2p9lF}_ ztqUQi{c#*nVhh>oLmWC}#C!hg?%>zl{WQf8m}e2fvN(nX{|EzIn5^y^bE7>YnoTajZG<8Y;2e+bP@o zX~P%zsYSbz+S{LJ@V$Otl&#Y?J=DFf1HPXZI=zrv(s+B!nLcp;%b|J7Svo`mzIW=o zt)vb2I)tA4y`8o`_M2Doy;J1Y@$|mM(vp+>Cg5#H-hltgvaO`p%3-aP)5;L7gwC1^ zDP8hXHi&Qj)mOK-`2O zJ@E=J8PjjVZhwW}j)becNC|9=*e(3#rimxg;+;5)UYjo&!WnR^}2{_EPd(G)t366#ZRP^XY_CN0${VlL@=6M%yg^FyqYODpXrs*n z{n3fQa)3YySp=);k505HL5U7?=#Mre3Lsk#4(j*H(ZOkT{@HWQI<9v=y1e-H)9aU4yBjy|J}cPC zO-&B>PfeCj54z4!-`ndluIoI%-e1{&ss*1#2#Sza-Sk-Uj;Mp} zyLB7|+>JU1Gz&;q1&2@jRp z(AVopCBf89$ND4TG=Kl)<>kx2y1070`=eiIBGY}w#q3W$>dG9)==WTidmHAH_tG+I zm9pt}XXB%smk+hfJ5K`ckOxO#`NV{>q=LJN@qUZ!K70AaZ+5@<(Vq-|@Wac?-Orz1 zUB7~D{_sv0`w$g5&II0LMVh_x0lHVY`yD_wK>k(fV#i6# z-~QKeNoN@9V$FW}5a$0rjrt{-;AL30G9rc^L*$1dhnZAEZP4fXvQ$9pOwNZ?9 znYBK79gEk|(s5dJ#O!|=$PJIn-9`=j-!9uSoi^EDCNugw&(mSGDRs1 z3Aa^lYL`2ay?@>O1XgCm-SswMo9w z zoCLh*w)r4E?OU4*e306FYjc4Q@rK@HY*t#jyF<54bL{hp2>>)@LH==XF8 zRr`kequ(nD@N^7NH`gd(u6|F)ygC7Foz5tAVw$>=0anLX^lhm>`aLZ^>Bye`==Vgv zcgkwpiQ?AD4gJyYP35$~O)cVk;3x6C)}8Ig&Gx(Vb*-0+YCW&hbaS+iOJ*lF!3zR# zTjMrQ731Ii<}Vxin-#q`i+}e9s};D1N8gL;1Sd2fduMBz(KwfSmtgydyb~PgKlav%u5a91pO0qT*`$j4Uc3svU$cTu zmZ|SU>ugd`eJ`pLUF7(_-R!yyQZ*4xFac7h0s#=RSIsAR8Wcl~ABb($_ z4}M=Nz-``u{W4BH4bN|D*S-MQK+6_E}{>yP%Ym2F1p0Q5)u*SdPOn>YK{CvwOP$Aj8T-BC_hjE6~A zy6aX@9Yin523GB`rZ$GCET2bgN}Fi zYhTX9>wHGT;*jj0==-8*pPTl`gUdFxG)!cu*+kO2%?SAjGAOH0C z{^j5K*Z%qc@NfRR|Kj)bpU?h{->X0WkN@ny`@0Ne3{9H7OR{6PTmom!FrA+<(di(eK z{U^7-FP-{x(UE@rx#;Up{kfE>e^!4kWvYz&b1740{GjNRGF3+X`KDgCf4^>i|H($@ z$wvRlrral+c%E$He6orE2b+5RU{l{8Y@S2W`CW;vl(~6srQG`WrOZ<2@;jx>&GUb< zX_s}|UYEcB@BQykS{(imv zd;R{C+uxT?{kiB!zy4hG^{4(^%G5vm!E2p=`a6|Te=cRJjQVpaQ)SejOPQO$UpK%1 zWTW$BqyJ=6?vqVCKiI_igH8Ok?QZH-{{FVU<@bMgQ?DOvp3e_9&#jbOf2WjL>U>kL zC!6R0WYaF|w!KOn|MUO#-~XH2I+mYH`K6BK=Td&DWBIw1U+P$XF6Ec<%Fm_zQpfUh zDZkXQ{9MW}bu2&Mwq5!8rtSXb_U}s>x4&P?C_fjSQbzf?=$Aj`=kj;upOv4>@0K#k z&;LJrZvuDMbp8J)K?V^q#t=$kikL#s+;i@8gTx$!AR>Yys9AkW5;26Lh8SBVXbn}W z6gB0Zdp!x?Rx5;5%~K3DOH0hks9lDf zT;c;Jm;AuU_zXrDA22rX0h7zLUYoDn&wb;6`^Ea?rw_`f!uy@Sn#*55`?dPzpRDM7 zPN)5g4=-NadGnR8E$*Jt!Fkduj~Dinah=H;_L;NkHtZT_v(YeHm1w)c-~2KE$UVpA z6a4}?`uKpcgAW+{{J_Zg3`Uo0U~FIu#x_1+{v`5BqMs#pvc!It_|21e@+8hYi9bJl ziIcCw4|z?-i@x%J9cS~ICwa@wZ_c&I_$=7DHnTXLv60lJ^3Q7b(q-TAI_@}acKzm2 z%Q$~$)E-4;Vt4257rUZ3=fB_2sCC}+!NPu=O;*@v&ZgV2Yn;tS!)#U1H`|^|*yaoJ zy5#tP(Z>gj9elvp=Lbf{XE3^417iapFt+gllZ!-NN%XVCPL|lu62DmzPoBh?C-HlZ zLp*(uYrN=Z$jxV-x#FF&a1rQ;~KWsr^Qx-dpj>Rp<~0?^8lNUGdgx{Mx0!m zIzl3El=jf$jp^|YqO|G#r!sY~ChFi-w)Wxx85-n`%W+7o_JU+U5y`keX0 zmDkq0cRkzX1I9jKI>TIk?FlOtKl!w65Z6A^_(#3xMpJ!Wt?}+BroX7`3>Z7AxOMVc zQ_(qoY{z2Xn=f{q;|3pY*B)PCPCn8&ws_(f!|Uk$`GGn0#TMDcb^hA@D!cYKQ_(qo z?4)A%=WcYJi9M#(*Q-sdFo$Q~-?VFI)zSI$1BVtjfA6oZv;2T#>RVpdp^i?=vUl6H z>lNrs>@m2waq$iXzHa^Cx~VT7vqFK+ilcvL*Y4*!%MbXVp6Co3`s&F+XPa~E+7n&p z)(`sE6JM3hxBiXmEV*AL)u|*gS594iy6gP0a-v;Z`l=*jPj&3tGUhDFVV3yHlCft= zEhPOXf@^sfArz&W$Xoqv@A(sglfrESWQ( z+ruY&`}Q-Joqafmebdfd>E18d6SnWwZEwsz`kTC0r*@pnxF>Qp5p!mNIZtplfjP@? z#(^0VXCIhz2|qA0K7-Na8WOEIOnJHWxvE;!s5=&zU@y+#;@-iC1(#qZ4K#s?h7C3%+UXNjFGvF|>()@1GjCI?BJ?gKeF zEiyg}c3vV*XKdgDIkwY!Sxxgb`kmurT&8(~bN{_IwEg*iIbVCl&9-mf+nIUPcg_~h zL*7`uVL#3$V~#nSZo{t0uxU0LX3N=Zd+m^$PvixR93Rrh2aFwjz}V*pM#g6_y7+*x zfh`!@_<*ThBF_?iI~$gE+z0xMDe>z*kejaifXPh~zt;{qxlG23zVd*bTz2pQlS_VJ zWcUbnI=T-S8y3IIv7OcnW_j*9Wr7}?2tp*_u8RjGIH*6 z(ooS*_IsS=M17K+kQ;IYt53q@l3pe` zJx==cJ{UXnL|AwT7~ARoB-yvL?=tX^A`@2kMPbHV!(Fz;OO9tF%h7rb8q^Uei7Ffu-a(d8N# z8`y&Nz6z}ORV3#<5b5)*62=biaKPB-IVOxx`^*`iynlimpS-UEZaMtrTJ^2+nKDEH@YQQx1x!T99) z9?Y{heqdxtJpTL*IX-#*24fo^Fwgvw@%r;O=@TnV>`C76>vDWD=3vL)d2l8-G_by1!PeKJeD;zGJ?#Ll4T{JMALpjZd4LJ>Hn)yz6hT zG@E6djML>d?t&j;KxSiiM%TvfY-2BM?9Mj!I(b1K-6ZBB8B39j5!TqzQBJtlZQ6J( z*Yome<8}Ks-nxy~*~VM9@jBah3mdPqjkmDzI@@>)8?UpC*YC@3T{xf-YBZ~I!})z8 z56=!ddkN=hi(Z0qT<7fWfZN9%!m-=r8{?d8WB`4I!&m8LZ-(Tsp`moFP zb@|Kd|JHO?b@`}EKC4gP@%}-?bK`CI)_YI6z+;$u;|$Y(u|jMwufJ|F?&xk)(J96} zSf8}r(XMmyt%Hl{I}UT58*kgXnBISlIy%cwZmoZGTYuL%^y-uB+S8|Erx>$CvEiJv zTxZ)}7uSckTwGziL$>;vU3*O(o#iLjijzLO-E}rve2e<6>pw6Roo!FO#I9YWKxf-t z%N1+3%ygYC+I~EB<>?>S(Rui_v+dfAU1y`k@2Mv`gC5*>M1jr`SB$l5w{x8>+Pc;g zUzIBdpYA%Zp0!k}Q%Pd3%${?x>l}34c6M#)tCEa8)v;^Kn6o5@sjn; zdcU%GicRufWgq%*?vl=3Z<$qpZmk~9qfgtexM}%L&YR>H7H$1scDqCR-c|5}FJycM zqsuigHn0WDHjGb``#VX}|CoeK-Q#u=Yx%Nd{M!x_Cq zUP<(`#7>sj&l0~`5>KAQnJ4j=e(;%$7ySbN_)PMXCwarK>)?|yqmNH=0pnA-!)IEr zmj`Xzs0{kR^ZR1=35_9(O?F#-&po3t@~|1sW~=doM>@-H$sf+Wz`5%!!!3uCokyQG z({g)~Gk)6o@9#XM@1|CZO`VbP88*@78W(`s7ApC{u&uJNMp zjL#%L*l#dKd@?o|pNtvCC%J&}nbalwSL!>kx#VoeR~~3g3U(;yJUdyUpCx{?#D12^!ID785?54gh zIg`SicRA<7dR72)-sNlybKd0#M#g6_=UuLW^{fEKHp>UrvjWLE4@;l3IgB07&oK7w z#~GiTw~^zMb32Sr&h0Sqb8d(6naKTFLDctW1u#An`~Iu|IkF@k&i;zipB12k?POg3 ztU&T44>_?SC-x+7{;U8wV`a=RK9l_WvjXILRsiEOeQuC4xsJ~k+MoH@GZxiR&uXY6 z%-kWTu<8gicbG$xQ%C7jM_6@)v2Q>B_A?*Vk$T1Ywy!&z+o~5iAWS$oLFKmup~bU<<}JeF4U&$@zCUE;oJNb#Q&N$$G*dyy&rYPuIEPsH=;Q zhxKxueJ0;fT)+N%1@o;_>&)V36F)7OZ=-H`xOidig03@s#n}a)p@S};p@S};F(=W* z2Rit~2Rit~2Ris9R&<_6KlYjH#5}uB%yW(} za%n#DFfOlG9>(SMavgGMxpSRZch`w^cO7zRxpSR3e_SWdAJ-w5mOIxWXO=tHfh~8g z11EMWRs-3oSPf*SlEjl)Efr5@wNyM=GOo;W=Q=h=GRvLo*toJJKbhrD`N=GIu4DPh zl00XYJLNg!GjfP-Qm-5zkzx;&UJ`AnLoMZPV*F!t@o8K3rXs zjWGQ<$^Yk`lc)8_gR(?zT>i7W#oqMzP<_HXZ>Hk_w+dVj*{;yiJ9+D z`I|rS``jWh-xrtPjb_O^9$)f(nE&}ZVq(^JxbxvX85>KmAHFXx$Mq%OpP3hPV&8IG zj`1seuV!A%)JNY_Q^zE4&R_O@n>2peXU=@obIsb2juUHbTlB8Me;Rg-^BW7VSz9s> z@|XY7uh!?Nzv_e#{~K%Ca3ihwyr>pS6%@c**TQYa##e3x92Ep)T-)r?jvKEUt)?9&#F5x(^NkuLx16`!{3JSy-$ z(>`svt54u_{{CspS#x%Eoqr5yYZ=-a_;-`qT6X+t;O%C&wY+gu;0{}U*0SX2z_;G^ zS<5Ng23~Zj4z>E`fmhh5d#$oU;HM7lUfXQtz`d^SUi<4hfd@R%z1A2S_^Pgp)K=Ip z@S+1@87>m)a3~9PK*qJl>@?eP&?fJqI7-a`fk1 z9~e6eEH%#M*kA9+!1%rFuE50eRHyN-L!5Iq2u%EAh6iR`Tkalsg{KxQ<+Vc>EcMsu zykKePAJ;BW+Mm4J0;S*K%PdgFQ+uUT8RrA{b}Hll>$FbgxR7hS=qnG{QGT$myx~{* zBp&6NIF*0mS6vv_%>xhcu`}LFS^|@Y?xO>fpB2vxOx{M{ADDdJyTXBfEqQ)#d|>k5 z{rSMu<+bgf}0GCeTzAFqFq%hBKe7lFO*oey?7_J6%^VEp#FH8An){9a(<+<&!0 zT%Y(K-7GNUnm#Nr(N0NBgzp`LII* zlm8$6B`|f_XVX1ghkE_)cY%?2Ty>1g(Vu-@V6Xd!fwA9r*F9YazvuiaF!9WMB`|T$ zUS==XpU1_x%ml9LDNlONe3Z?aE5<=68Z<01cwle#E=>ZNfZ*Lcxa9k%eDtW%i0v3_Cl$-0JpU06Sa$v=Gn zrY`gcSp86P`l0mchcI^NhcNc(hcJHWhcNNb4`Je@AHu{>KZF?<{Saonl9LDNlONe3 zZ?aE5<(E7w9`dg^sf*%QKg1VujTe380Xy_Vbg-|y;aB-29_5)hm4D(_UDA4qxksyZ zuxbaZcCcy(t9Gzz2dj3lY6q)!lDFT>mZ_`eg@Wl2G)KC z)_w-oeg>8u?8^=;JFx7)vIENwOlFyo?c!_-1@Y9xJX zCp*+s_SLt!R(%^*--gwD$t$Z^P=_u=+NPU*(f{lxN~p{)u08N$Vx1j;bB3 z+QF(FtlGh<9jw~HsvWG_!K$6)x@V!Udzos7j%o+1cCcy(t9Gzz2dj3lY6q)!uxbaZ zcCcy(t9Gzz2dj3lYA5;pzUOL>#2DG%G6xtt`zV;4u)l)I75grj9I_vS$u0Xd*mG|C zTbNp~uY;)_`#qT2u@97-{h{>PH^SJNX!}VR`|LAe{IdUqiHChDOq}djVd7^W3o|bE zw=lJnoZ3mB+Q|;JlYMF@zkc70@lZR(N$nIrwbQteYrN1ub9~2^jQ#$T+gFmJ&%I*JPOwH zC|J*X{KE1J%P%ayu>8XE3(GGozr>*DieHRJ z&pgo=^XyUjdIqa}e(|}Yp3SDuY}4nKV(g@QIk93(pNpo?LM8vAKF?{>vB1hLtlYxN zEv($a$}Ozi!pbeI+``JOm}iXe*SXfxKA^ocF=#IhYcCCJFAdW(+t1NqANy@NN4M|0 zLcP8%`>yu$X{gt?;e4w5-52kD>Ag(fmvR5n_hqoYFN5`c8LaQiV0~W(>-#cT-tnTaFBTPlukhMfMKNe&*5b=J8H9p6hHZ_17q{0 z34!tT=D~r9;j=vh6Whr<2PWnj!vZswo?8WGjK^#d_|kz3mpuK=&b3RPImcr-{-e&d zKmR@O$d$U(#&rz(tBmPV>$XJTj&_FX)F<%%%XY2(eVxGTp4+u{@SwoAF4e8J>L!8T zzM@-g_RzriTC)4u?yKW-oomm0IN5p4qH}GdR|1cj*tvG~qk)g_*SU869|JFU*Fv>v zMc|#bUZ^(Yroi|Ae!v{e$*=z2&*7fq#GAYc0?HKJcfnyxQ{kLxCS1`)bQRF9crYXR}%s zJNP^w%W2!sYN?D1d}QBQEzh13*xoB>x$A;?tU0jyI@ONjmXfCaN z>7QFP$38gdp%%@(Q+NMMi{|8c`##*Fx!U9SM_M$8_qpQH7R~Kf&gxp*@Q^U~Hg4-$ z`{1C!OCQp$w)Fvl*ZNDh+Lqr7JaWLowUtH%{=3%SONzVd(_s!>{T^JgOIQs$RsedND55tJv`UQr@=Pd!_!L&v>`AGk(@PrTxp+d#Ci<_lCJ; zJZ;0~mT`V(iMeI`+qAu1jtjZQi@x%J9pwl6${T)_PvTLYiBtI}e%0l#OFdK8>*Nof zDdmIz@@%Pp@D;O5JHH?OTxtIopFCIkUH*jU%Xn(DpD*KFY55n*_}^LQg>qcTRWI~a zFYKsZ*jK&qt9lWS>P4KY7xAlJj7#;}e1oS;`RThpRqF5Y<0nfy3qJ5fX}{k(Pn3Rd zxbE>Xp3}E^yo~eLJs&UQf8-yJmE%ILdZDj+VMq1CzUqZv)r)vkFXB|ah+p*@(Drf5 zx$A`c-90yc(z5j&=zo-*vCdGc#NDD{gK-!JWKP=B{Y_76Yhofi3>ai*=K z7|#=bdAmh%4&3+c7R5ibfr<0Ep9UuW4bBhDxZXQAF#SYw`i%7H zKe9t#l70G>{L;r15B*JX()ScU{ZQjVuJNL;JYYxp!M^f_U*(f{lxN~p{)u08;l8YT zale+F`?&PEzsnByec5L}AiwMr6c76i#mRm{@w4C1xR7hS=qnG{QGT$myx~{*Bp&6N zIF*0mS6vvF>c#z9a_-~O=l(7`-1lXl{eb+kPf$GU9~3A13dPTUL*qiO@uIIhU`P4E zzVe1&<&$`nXW~@;iC=Zm*@S0wFlQ53=NDM#8d&EYSmz*E=Ob9>CRpbwSm!KQ=Py|M zRapC2So>R8`(9Z4VOaZQSo>#K`)XMGZJ0ed`*1P)b6ER!So?Wc`+QjYe^}=NSmy;; z=LlHm3s~n4SmzN~=M-4y7g*;SSmzyB=O9?;BUtAqSm!BN=PX#~FIeX?G3P;8=R{cN zI9TU9Sm!=i=RsKKL|ErXSm#Pu=S^7WQ&{I#Sm#+-=UiClUs&g2Sm$L}=V(~xYgqdk zSo<7U`yW{QB3Sz+SoB&>ZV zto9^9S-@>{d!Mabux_`mCufe+C z!MYE^x`CeNH-VCtoLMZGlN^qc`5yLK&I>Sca$bOmpYsCDxHyl)j8}5s!>{s5Jjye1D*wc}#ImSM#5Ev@VEK>xKBWju@BL z7vq(jJV>AX$PRgveex;4>t^z$w4}=LxW$Gf1xS>bV4R zJ+FZE90S(#4Oq`TV4gGZ`~=o>5?K2~z7Ntq1lIlp*1iSSeg@V)2iE=v{w6%{(*BTm zG{$tiaQl8Z+~2>+`(f3NI%@w9>s$cqya4MQ0qcAL>)Zi<6P`2c3`jg;=A@oQAlEq# z*7*+BxewNP5Y{;n*7*_Exf0fS6P7RhN)AgOmK|93Vflp>53D$0#SiPgfM4|=SbYgr zzk=1rVD&dxeGgVYg#S~|X?0&928}Ttuje5?uZG+2gWb#(OQAeGRV4a&_ zou^=(vtXUSV4cfgo!4NU<6xcdB^}Px6T;H28|Mk5I_0sny)Jxx+P%nLNLcR38iO%ErMXv8n(AW1S*wObU*w^ZSQc zy)+N?91LHoBdq$usynRt0BfGWnm@4S6|DIN>v=4!=YFuB2f}(z2$&Ai3tPzF$DD?;T)$ z9|7xo3RvG?!1`VT)_j8*m+p7WTix%N&${0+&vn0J{_B26y>!2$Ub^40jc-RXX( z?|1O4?|oqO)qk*~zJz`CEBvaD5s&&CajNeTzxpBL()~_jWL~9A9(2DWKf2$MH{I{Z zr|x&;S@%2gulpT!(fzLdd%AGH(|jQ3nkTU453G3wYresnhp_6Ud8_(TFV&rTX+BUd z%@gXS`9r-luc(*i8}-utPT#BIOLc@*Us!dAH6LKj6Ik;H*1Uo>-(bDBkTT;nL_1*=n_c36-rvWQ|SnqqJ%ox+Li_y`$ zC@D+->w2GGG2?fBzYnALa2T%`zsf_(=;&Rbl+n?($n~BNtoMIly%z-QeIZ!y5y5)D z2$oIkOAbpPmK|93Vflp>53Ki^urEgb&&Kt|f6JivrgSZK^xhP#_o=>UUvhj&AJ%(W z=!+#!{|$xw>YXw4#nS(}{+&e{=lp(ejozhy(;;TO8v7UXp!fQai_zD$$n`!RtoQU_ zy}t+Ry*^m)`@wn-5Z3#Fu-+SliO&D12+)lX}fjU4&1%O2ji=@(l$+usfQ zZ)f|wVS3JXU18Tdo4vy9I`g|s&7b6%l7#U6hD6O7srLX zh~q-vIofH&abe#%`gM-+ILA1h@k742HjYbj#w&gD;2iVgj34qC{gO{-i-$ZrbDiSE zp5jmICARg~OgZZFdvMD-!qI*XM@BlzScFmgrt^57iv z;~ewmY<|h7bIh|d*O5o!#Gc}BUtcSDPTJR3`}&G~#^=LVwZ2%#>KkHv*Q4x{a9ocW z9M@?M$Mx$R*R^w8@6It!=NP{;>)Y%)t50Gx_8IAWpF|$}lFMVia#o*=@#N^i7N_?~ z7(dtzc0!*_>XT9KeG*n3;g}!Sk9l)epF~G} z(yxtu5>}rKc0wH!d3(LW{nYdM&8ydNUw5Hi!|Z;ySgh9&yAPi2y!yZmS?kVY$F5}e z&4qIG?Qh$MtmJH;7pCWI*A>}mL!8Z?&9`CBVSR;lfgj27BYphH4t`{xzvY+D6%W@b zPV6au@{GSYF60Fq^_`;~=V-qX$Aw?#7>{#|(>ccP9LFU&IQPYx`uUnU!rVe0=YVsZ8#(egXPo0)a%PS& zr_o`Kum<2bCnfi_hCI$;m&dv7%-UiNpu^w%H>|bh*T%I5Ypo^nBGGr&T0=b9=HKJgS_^i5YK%%@^~I}*7-WvX@5>a9^&%^uZ7OnNq$@&^X9DcH99(9!#ZEXI$y)>Yi*X# z=Woke+h&nYzP4wd|4?Jn5*?ar{`%Go?)Lq68$W)1{T%-L;O86LEOL_bwAvpVt?OOm zY=1ZGzn$%K^qlQFu6H(jh1soQhaO`7obe+$ex#2d*};$O^SAu+x#HnE#fd$|k01QS zaUn0_xX^FJabd?f+INnAont)CF;3?ge-k_G^T{KOAMyy}hdjdgA&+p(o3r`#|3=Q| ziihhIC-xM7S}*Y)PiD=Oqke`w+R5Q)-#Pkqj`29hIGtns&T(8-?5K`#%!A8geq_h% zh)&F>%T>o1kJk}a9bwfGwsCnK6M2#7H{duQoK;8Usw1pA!ZA+QkMTE=tB!CSughZ| zTwirWM|Ff%M_6@)RYzELgxl+N(zmK!y01|??IB_9Az|$y;kf6?;kXxa)*jNYjeAH~ zdq|k|#ojK;eGeJ+{k#Ti4++P;oa@K?jn*P_1fAz|$yVeKK|m`}e}dq}@F?BP95?IDAm zu!p3ts$Q__1*=}L>IJJ_u<8Yq5Ap)5Ua;yFM?WtUAJ~Bdj{Ysw1pAMtS?Xvz(}o60IH?$r3x5;uFV+N?(h=igs( zYrV@}?-s}hzqo#J`^L{Zf6)1);=+yp==@T@YYKkQLB?k=x?BTe16we*Szj@n!GGumCrj*SiQg=VCr{$c zllZ-Maa_nXUi6DNt~|+4p5zU`u7gj;9LJR<`OlKNRML7`pY;Flvwatr+4pqL_8ncu z5C3myWPAprYu`UQ+jo7okGS92z8kEt57hrl+Vl#T>%O}G_xCKfNiF8X|Kpo+x_ujW z!A~4JV{m3nHg;zlyX_h8ceb(DlN=T{-i&L<-F#Q^+YRd#xX;rwihlQfI0(Mu_y^&s zV$-QhC&?A>xVW7-Ugt0S|K`TlTNe)SHDvZHH=N%m^6>1SvzKtT=hE34XDs0S@9K}A z`Fpqd{z_fyzZv*T=TVoOP#-^YsM~*krPJ!eF5B1TFR%Yw(^=K!qb~WZK7Ggg2NBPW zx7}OsJ>>$AVeXAHO#j6SvAw+hy2ZGoyG=!>81rC#(soC?&dIk9E~f7|%yn+OZR=us z|2699EI+xm{?TpyUFXoNPqJ%IpNgGg%nrqdbIx*|ZF^l@AKr3th4BvA>SuQCHFb2B zpIj?W`s{Ys*=X@C>bI`{z*Ka$J@pd1c98;|ZF?%4l_QmIZQiMcX+&c&{C z&~e+@wWY60GWJx*t}SEEk{qVKvSjR8Qj1Cwvt3)}FiYxKNycv1mbJ)|IZ#P*XxElC z&5}7&Norx&mUE+$)Y0_Ixl~E!K$grI>qYaUr-k*n!O$akuP$S482dVn>~hw!Y`*nHeYcIxREIu=KE2ocI!C{yKJwt#!N#bzd(o8-O9KJ?+-C7rw8GOPaFT0NXcpSE3b z)AF61H_0z7+WNojc8B!6tKbJ;$oLFKmup~bU<;OQ7@sDuNN)NWjK0}%#*W!{#=iYH z9u%#-*_Kln_>i++KBd?xwH zlf2>Ab@0iU(Z?sbfbpr^;WMq*%Y(LUR0e(E`F*kbgvOA?CcCY^=bq6RdDskRv(@;) zBb{Zp0VsE-M#e=>ko0B*yAU~(Q}S%jGJ|N@%Y~3ia*U<%jM6kJ*OBjZLG`JTl4K= z(qRj`eCDPrH16GaGnaShxprfhE_WB${Ql#E8n5lQq|47aeV4|Ik8J7kIX7+7*kZw{ z1@`-0@&m6m`cK|9yz%6~kL$>Zel32N z6Tijja^ke{x}5RaxLnS-EGI4}Czc17lZQlJd7v>V*kRJlvy&zIS>iWK>}N@wc@j^a zj4My#&yzgl$#`>I$Gqi9e$ZE*kt?6rce&*aJIa5a)Dgdpn72HsdzREUPv!~Za(&BN zmdvF}GJotm+y2~uX9M4s=LVcT_gi*TUzeOoVa~gpRbkG%oMBkeA z^@3F|SoMNcFIe@GoO(&0dcmp}ta`z!7p!{0su!$!!Kzo3|39_v+PbaW$j|t$kMWA5 zR%=W+Vm;@5Ca=?YtaE?oGkbrxvH8mV{tw=N#D*?^XwSC#l*QI|K4sE`;`whbx0mZ| zGI#f4i}Af(=k-zh6dx?TitBuQ*rCOu7ccBOZQU*}dTia(b*?z->f+;JyPYdSTs9PQ`UYNU}>kMCUcEM-ppv!0Ipvz~>Np$gn4nFaL4nFaL z4nBz$9bzX|bcmf;(IIxmj1D{Jpv71^

J$HZIqR<8qxiF4tjPmLJ!N`Ei|?AJ-v2_L=L%JiAWJbB-@^X+H8WF0WS} z#^v>L9dc>8bDdas*NJs^9dc>8bDcPUTqn*S*CCgdJJ%s+mOIyhEqAU1Cw3}U1KFuq z4P>X1#FJSq6;EchR6JQSuFP`hIyOf#%bn}kxUwWandMIT$t-uSWBJLFJZF|Wj^C!35Y5wHoD9%IgA)#KYIpd35 zCi59Pn$OtLd?ubE&O_oU;yfgt0z1T$tS`ppI&oaC!?==lN`732Tqf%@XO7~FTrx-T zMJ}16_#&6g^*9fyS0jwe>*YG+GU-3m-F3(%YuNK_xlH;P^T&0_Wzxs&InssRGsz{- z9O$Jy&)``E%<~MMQNTRU;MoPt^9+7qWPApr%QY}IumxiqAF!SUNzU^Q>GSLb#tzR% zVC>tEGd}GzXMFOU1s#0y%m>CN&w}7MF3J5_P}KKlK`=fO`+4FwPvXgwICnp7n%=6gTL!4RPtj+kGw*5J|<%ga|ZzL!5I{Fl>-U!o=$(`i%M(NWVVf99seoSwK z)f-{@agzVfJtt4=g-zU&;d*7vZ1 z{rg=1jw^ikT7EbB6}}JiKYvF|%=!*@KD;NB$^I9{^(Eh*nHO_npYN3YyI|hI`Rd-Q zDQn^N(f8Em*L_hx%bW9;ecvXHU-p?Zr+qT8deuVLR_$Gz=EfTgtUh!4_09)BF`)YX z>o+;?zu-F6XFA{J{Qj&ps+Zn5)%lzQ`c!wA+i+gu zL!Ghn!jA_#WB>FAGiUrxX>9CFJP#f+(3v=&|73u(jjM9c@#{G=uI1a-mAo!Fd5}K& zksb0T`{Yx8$+O}i|B92kD1Oz8{_xLObwo#XgjGjab%a$%SapO|M_6@)RmUjzI!1l3 zBdj{Ysw1pA!m1;zI>M?WtU5|g9;8oxVAT;;9bwfGRvls05mp^x)iKJwj#1z12&;~; z>Ikcju<8h_j&M@PhQ?*hg$!x{^m%t_>$ zljv(sV#j+6`pO}!+``H^tXjaT5vm{Re4|V`o{j_b&q|?=R@pQ zK2KsF^Z66|o6oD*_k6y^e(3Ws_DP?gv48r!m0UT|JeM8i5V>*-Q#-{&?Gz`qi}B}2 zc0929LRRr!{oZ~1Ru?;YBj-*F?NuFk&IZnpJ~*nn_zy#$e`=?lt7{Jpeg3T5x36xu zP~c&!Ze1N(1m5ruL#j`XS>LaHaeA%#;fvvZF}j*nJ7nK=`QLZjxVr0>x$|}d2UdIi zE!=mme_=p%ZuiYyzVf*Bs{M}*_bJOqmHU^~wEEB3@>J!1hmPg7%6$;FJXN_r!d8bW z_f6R9Q{{dNTb`=iXJN}zmA(O6o~rZ>*!)-N8?gB)<>sf$AFzUhw;OBT#ny3=kde%T~3^Fjd=WV?fAHuZyK-UM?01K|KJ$F#iw<>W z{%`ingPd6xN4~j#bK;-w%l99DaP=os_G$K>a9=)h&BLnq-aDo_tIvJ;Q41YW9dp@k z&A~6s$Y1YxWcAWPBbuu`Gb67od1Up`*6o^`^tvzaJ?Mz)btATF_CEB!{Mus=tM=|a zq`COC`|?{}JGi<*rPe&?+57U7mOiL@_LaUC8uH8fP2y=JaW<0p8_BpD$#@${9vVr0 z8cE(7Nj@7%o*PO28%bRnNxd4Xqs^IS%E=mRCTp;ntifio2AjzmY$j{4nXJKPvId*U z8f+$Ou$ipEX0isG$r@}XYp|KD!Dg}so5>n%CTq~;aSghDoZD_E&Uv>V*Mj?vYsBM; zYsce^Ys%w~Yt6?M*PxGA@?;Hqeq<+EgPu?MP1d02UvX*;ruAZusdjMEZ@uoZ5Bq$G z{n_V9?AtznVn6qJ75lu;x7h!E9>)8E&(CA7u=_8 zJvLa6t!K5c9viI3)5mPadTg*B-#>jz)?CXmu^t<&$Kwv%iS^iEJzo2lk*voC z>+!pbjA1=CSdV@F_C3~PgZ23PA9>HgZ!_K>iKnS}Y&|v=r>)1P;`zm#8#=c4&o3XD_$7bxS)Ug@+Ds^nezDgaNv9D6cX6&ofu^IcS=PmYC z&nJELhgQcs#~<8W!uo1gtK;Kq9@f0!Ph*<5SsmvrbVPH?CA&4>dSgc8s@X?0|7-7^ zo4Y?cqrts5?g3bvC3Am{_kGqTYm9ptYm>F-%zZxI_x*4F8y!AJ59T_qhp~rU7@zoq z=>d|nwxmxFkR8^d?9&6}m$j>S=mCn8wXXP8M|>ey&p}^n89VAZ*w@A&-mn*aVsA3p*YEt;#a-WI&S{qjK+;OAJIJa=i4-| z+2X#&M+#upwq-r$s;SM@>ObRTZB~=DSxwd^dsnTIDswEZoocc+tI67|CTp{r ztj%h&Hhu3I*Jd?Yo4!|-{bX(W-ZrkyYO*$~$=c-Hp`PRNIJaFt&Uv>J*FrT}o9;KR z9giojDUUO*HIF~8K_6FKn?7F2leOvjk)331dOqXY^gJt`WNlWpHq$!VddyjmkNtQT z)??0koblxDtjC=7_@kHhVm;=p$EVNVw>kK*Y1x4bUgGD+s|Gxk&HcxeD)VRD&2MG9 zzB;AK{ONuEXW3>CO{p?}US4m3{LjCiQf2<|%;4Z@Q+%8--(^tClsTs&r{0`jVaCt7 z7N%aDcVWiQIT)tCJllYoXPlc|-+B|z5@5#9vjmvA%d->7d6po3o+ZH8;aLKVeV!%2 z_~luG>svfLOMr=!X9+Oz^DF^ojFK~dq|f}39qJ|f)KPw!KZ=LCD^BK*;%A;{T+APh z7rF9)zVd?|y*Fz$0=3j&!kQtXU9J^rON!7yXmXh z*>6v&GJhVM_DI&&Hl>=*ANu((CjG+a(*6?;YW92VXy;D5*|{w1=iK)Phd0kZ>beT^ zttdk6U}|Uby5y!`!04MDXY81LXYAX&b;j?j>pWGwYx9=#-C;MpRgAWI%lU4Hvp*}g zwt36>u2X%1#(sBC@$=m#Z3{G3ylaY|@9sUXLu0=Or}+8qy}|Dkyi<&AA$dw=T zl{f4tpV*IneIFag+hqS7$J=E89LL*a{~X8LWd9t;+hqS7$J=E89LL*a{~X8LWd9t; z+hqSNzp=jLycz539P8^G>q{M*Nqw8KzSQ02alFk~-wb)IuXC)gGk#-V@_lCPOTN#H zeaZKku`l^PGtTE`(u z0~Jrwi+tax_>*4b`%H~D=|!%u{3N}|?JJ*2FYY`r6SX4W^zc|Of(n`}Q|Gu& z-R3m=e{IcvZRz~_L#8z0?#FDCFL~WX&a?k;Y(9L(Pn{23>nC~h#q*pmJ>Z)B#-%1Z zzuEDQ{M?gHbN=MSyYt(3o8-LbnfK;>&i#NUXu zV_c0`Q^wnfwI&aZI0wj2BhC%-)`)Y4d^X}-Dtj`%(*7(a{{O^1!s2Npd1xegXe4=P zBzb5gd1xegXe4=H?I;hdDdnN`#dyEune>1COe5yJ%GhIU&N1d74>fg;V|0#VcaAx6 zj=6Gb(UYoE@uA!C-y?j!({B5x5TOW?3|2U^WWvk*tK3H5ndgq?#@+1$shq_$8h*?Y?zRvG=wAL6` zng?;Z9^tR^j1bpClh`6FZ@zY7-o91e7if)tlfOq(A4u}AzNF`z~sE+U(T6|hx3o(FLS1^zPrc`W>p+8@(^Z{`onM zJ=4!kv1dAe9p^Qxo$g=M7bZ5bzdwN7>R*j@;k$ru^g9o+&+{F@H}+ki*fX_%@cE$p zD}HJb`+xiQMDe|>FY`T7(lc{y-m@t0Xd&0!So)nJr$~n$A=Qs}~_dRda_q}km<9lQ{=FRnEKAmHpov9alTlA@y z;@AC0a*a3Ex3t6k2OaEl|B+wrKX9Bs&eV(h4|3|o{Rd`T_>1xialqsOe=zwWZkW8` z4hr$f*Ch`3??7+H<)_S_h9N}d-+mM-$0H& zeFMf0eFMfmeFMfXeFG*Q`UXs#^bMH!>E|$iI6DLiOx~me>snYgVflg;1FYC!#SAk> z^+1hL^7fuz_O2>9VNU)lJ)hd4pVpCitNJpZRd?A$m-(-G!n)A>VZCTxvFvQPKz zbDWdTaZWnNIq4kdWGScr;}?DIgD`gJ|1kFH|1f^(|1j}z{(y;-{tpvB{U7EJ=Z`>v zsiSmYT^r|v+l1u{Rt&IWgB3FzdyC(9G)BpF?^8}>r~TgT`TwW)ZfZxa(mKX@tGfHO zd>-ey%j5iaj_blXt`}#k1?$L}b*Fh4*Ig;6cGyRs{S1s9Y6oMVeHV;h_FXXXutTFi7f$C(l>5Am`WZUWj&ro{9Q``Sc${OL&M|&pU;pfPZs_+U;7e>d@$XoZcRt(S zWwm}s&dCY=j-12vJ8}-w@5nipN#E=^W5?_}W8Z4+OrNC>pilp$ z55V+g`T$J7=HFcC_j`z`X=L_t(y2<${Nvd^I?O-r2Qc%G`vlDVV_yO@|Jawn+o`oh$bI>L;L`bN3m=c2yf|6uYXJLFCF$*261 zXT?MQ6(@C3{Ork9FZ1v3W@Ddyxbk3r{M~Zo=EvXhhRu(^`wg2PeJae7a7xu6l>*ep?#yXaA;*vh`$`0d@ea0uhj9c-L55-BI6hHaX zxR7hS=qnG{QGT$myz#g4$>+*5*D3$lQ(f?*df{Jk;*vh`$`0d@ea0uhj9c-L55-CT z@E7lo?7d57ZO40}=fa(ayQUe5zP1|~jw3`~6V7?}9zF);DbV_@Q=$H2rF?+ae9 zc)##E;tw6>6Fn6sZh9@uc<3>*Lyv*6Pmh7|OOJ7Vi-#Tq6DK_eCVuV-FnO1p{79d? z$qxCHeex{7joOP<^xtK=fi|0=nN>!M07;(Do)i@1)e|O;`;URN=_c6Pkv;FyvaWKlwb0!c*wuvq%Mlz{8VFKqOVs~ zFY{AXz08m9NA&fo>Scbas+alEeT}|eRlUqlRrNAIxLWIeAdM z$dBqp-c&F0sd|xT)r0g57<$Du&=!FxAMv7$}`s~ z|Kv|~!H?>Nf60kU`ot?cj6?PrpZqdz#X~+6Cwao3&W7~Hc(3%eZNEFwf43g;`SE-0 zEN`4^+*jl#zP_g4ALzccH^8rcS0rrX<@Z~`|wRPQ2DR+H{V-oMQ~m|H|*f#4de?zvKPKIo^Mq zr6a0ubqk0 z=DRcT(`T^BAMOkM&HYyLc>i&Ey#F}I`;T+H|2W6{k8`~LILG^sbKEbKa$Aq3zO6@R z?AUsA#=fmbXZ+fFbS55KkIuwt>(QC`>Hmy{Kje|WyIhsgtZgvk$igvlFug!!BQ zhWQ*lnCrM6re4^E>mFnJ@7Fn{ykFrT9ba~;>i)C;>X z_2O^-MEQJs{)P|wG=Gy<`ZP?w>C-TEpijfphdvEcFZwi0z39_0^`cM1)Qdh1Q!nld zl5<~x(dWJZV~6_!jD7A4Fn+l&z{JCS0VYoF3o!9>Ux4|;eVo6&UQtfIrB5AXhx*7q z^^#xerFf{9;-oH$pL!+Z@_iqE(N`X@qx@iBdBd;rNj%CkaVr1Bue#`7GtJI}y4S$* z_pkbSA^u)g=lJ_to#XFub=L2y<=S|E4Dx^e`*Qs(iN5YN@mjyvxP1QoUg9eDb+3VS zuYq;1fpxEeb+3VSuYu$J(QU@DIBWlaj`kIPZQM)5Yx&*6;oAA|dwP@i{l3n~mnZ*rshRxSCH)&%*NN{L zHmPZh!P(yJ)V~qdwLw1b-w4Z>%VP}A@!wTB$C#btdyLL$Zqu<#&imDp!}^^AU(@e! z&^w=c-&HZYJjPb=Z?0o(&R@sxAGrRw-C9q1W8C0X`#sw-?ZlC-J>Cv{(wV!q9@}xe z%MZAEm)7l92z=-xJGb7xN#K|J?A&_Mp@FwJcSP%jR|NiO)e)^LJ{5S#i#xR*vg`!6 z(|6`ht=EnWjQqt51Ease!-26=?{Tc_WB-m#1LODN!vYge#|r`z=fgJyCjQM@12e7} z{~h?^38PB+qlfQa>c73q=+e#`tL;(R|G^V`lzx{ucuX13UXP9`<6L^#Jx_oqLf01mD((mlsEzdEY$CemV#@T<{F=hOH_Z(A> z3%SONzVd(_Xu5;xFqGYxnlP@3yF3FnK^9R=r@=3s${g)eBa= zVATs&y(Fhz(x+aq>IJJ_u<8Y?Ua;x~t6naT^@3F|m&ba+su!$!!KxRmdcmp}ta`z! zm*mt-`qT?ny7TIrC#?PntAE1kpRoETto{izM*1hL{t2sp!s?%}`X{XZ39Em? z>YuRsC#?P{IsH@m^iNp*6ITC()jwhNPgwmER{w+<*VCs?9DMhw54LRbk*&4k17CUK zF0HGK4ZPV(JGZ`_2Yz<;POV)R4BY?z9b0=(JJzo~_08d}n;jmwb<5$culEZ4@C!S% z-aU1K>pU@i2k$5NLO%KZ@h(Sy>_vgG)5Gqk=wN@tx5hc+cgx=dCZ0Wy3QU}9ZxfjK z=MD(WxQ^-9U838PE>UQh2)+L_RM&(i+7>+MzgeQ43W%Xp^TvUeHhkCy#j z8UG2{_sVf0*Lcxa9MgK(3#{G(tGB@FEt1n)q)%^w)mvco7FfLnR&RmTTVVATm@(2@VD%PQy#-cpfz?}J z^%hvY1y*l?)mvco7Rl)?(xMgK(3#{G(tGB@FEwFkE%(zsqbbe|LQd6x#SZfg0 z8ich5VXZ+}YY^5NgtZ1GXAMf9H3(}B!dio{)*!4k2x|?(T7$6WXP390_MS=4fi<6D z&2w1uAJ)2nwO(NLKv=yI*1D6NaY>(X!CJqt)-|m44yzBq>JPB`2CRC)8ZWFoz{(G- zyur#RtUSZ&fv|cbta?dKKaoED1XkT)%?DWX1lIh4HLqaJH#n^qJmKhY9#8qG^+vYd zdt8w3^TsZ%CtMJC$A;}&ZV!C?wIf=4yb^e`#!jt!^bP0nzkIx7>*5Cl?sn*otxMk$ zc*9;hwl23|ID^0cVYv74OaS@DzX@{mvrhtJr?yo%Ut|BBvjXFHvp)qUo;^PdOq{cN zPxNy=@t?YWV8->xpujKPH>#As-*a@S-(?fqw?sQn?lh*f-)oaSOTVXd*sF|ZhqL!8 z<6QNny~_Ca=@jmLj0?HOi@x%J9pwl6${T)_PvTLYiBtI}e$_?wV$Z31!KxRmdcmp} zta`z!7p!{0su!$!Nlv|_PrYE(3s${g)eBa=VATs&yYuRsC#?P{IsH@m^iNp*6ITC()jwhNPgwmER{w+7TIrC#?PntAE1kpRoETto{izt}YK8H~6*H|J>5C*RHMS zP7l2BT_ajAxG3z**I^|2)aw~gPnb=IlJ zy3WE+Zqs`H+Y_AE`Qc!wbk>1N4~UsDc?RDQ|cdb&|amT>-YO!Y5%v&?b|B9{U`2M#jih3a-5%kQ(h(8 zwRM-tLB3Jfom+1{An^Mi+Wn}1;Dc8f-umF9;hf%c()O(%9v=961Gj5^#O@uOuTO0m z*1FIS1Hb#LZClTHHJsBo`LAt#yyzhR!#(kAZu;9~fw42e?ycxxf8^l6_&xFQV_Z%= zOP>;$IDfunVB-I{PhiHi-O^F#uH8%dD(~!3>hIIZ?nlwioM-ng?QcC{pVIFKf84i> z=b=0IE92a6=doq{%bqs292atp7k%XcJIW9Cl{fqkeA^@3F|SoMNcFIe@0RWDfelAL-;pL)Tn7p!{0su!$!!KxRmdcmrf>%@AwPOKNK zdcmp}ta`z!7p!{0su!$!Nlv|_PrYE(3s${g)eBa=VATs&z2LN7FgYuJ3`zNga39Em?>YuRsC#?P{IsH@m^iNp*6ITC()jwhNPgwmER{wPUIIe~M z@L4%tSb2bzA6R*Vl}}iChIRjfbzg&3FUc8~^cfedy2F|eu;vM@`2%ZS!J2Qd<|M4~ z!pZ}z{J4I+@4(6@tUSZIf5E!1!K#dND@s z1<$P7R`wiNy$Dv1g4MfV^)y($4yI?)17Y3EVD(JN=`GTyx4`PXuzE7AUJa{Y0*rFOa_Spx%pIJsDQ7hSkGi z-HTy*CiiYQt(V5gb0m!&R!(5$3RVtbJPB)3$X4Bu=}0{v3mQyQKFEdkP<&-Q$i&rT65Y*W!Wrbw}ger z-b%I+RxMW9ByA`u{L+?0g=$qcg+ieX?I_xj3PqIO`JLDLeAl?|<9Oab?&G+h_kNzY z|31fgjCIb>7}pr*9M`q3>zc{-K_98Bic@dJ)L}98Sxns)Q_sbGkBj*p7xTS9T=kRo zs-I%MU&MUxi1|Je^F1Zz`%BFCxLC)o-|}cZ9$DNmcgY(OPukr+_wvspzN~IqZoxB0 zCD-iFFSX5myluqy^l6iOY*ECeZ*HACrEpX$w#-P)O&=QZ`g2or>wg{b^9Ncb_s?4U zil4hVs+nqkC>GUB<$3p+h?W25GsgLIm!(H6pVTKKmS@H75zGI{Un5q(zB>_d@3bzC ze_Xzs+h6uhy7TmJaZ4`ww>{XypWAFvPy6Hy=w;6b_Vu#=^JiwbUy9RTwPzfZhw)K< z#!a8gc*=)ymM7yce~wFdyu|mtIWpe;yr`D8d3R*|^1>0PelRlr+LwPNYwXdFN5+S* zi1_`_M#g{3iMYzwBjf!WL|o?Ek@3-A|Cww*=(~~eSF-*imwCTq?)Se$@fWIf$SqZ3 zRI-ikg*dZ8#7pY6%N;p7;{B(#&F%M2#LbJfN#0kZoE_3y=T@III{CLtzfR30QPwS3L#^uxK_K4+~vLIsl-7Mp{rd%)kKN9QZeko3W z)t+%s9^H4OekniWrq5+O<-<73lkt~7$K}6cKJv{jA4YSm$m<<* zFWwc+vBht7%w4`anq!65b<7>HFPdWmHgwE=d4Dv=s=wDU_u-$TIacx4#63}oIi`7= zd!l{rzJpQD;zc{;b~+m6tbTTf+_`^6IoFl#kb7~VQOS9mS*b(r`9()1=k2Fe64$_s zjY`hjJ6fgX-cxQ=GUs32(sJV!MvAxfX65mzKNvvQf#kaOCc^+&>fl z)7M&fYF1kA*sG(QQ|G4TetT_{v--BSx%<0BIWPRSZSI#nqMRvzwar~~Ym_tn%yzk- z4~%kdDBmu3#?UBd`5KA)^hQKEV|Cl*4jUEad_AX4?mN#%IqzQ3CU@PkDCar3ZF28> zHOe_|TbtY+uSGd;*wZHW=iDgg>qpw;p0YN|xvfCk-22u?IWL~rI(Kfd(aFA_{#fhW zaV1A5`+oUrt#eP59-Zua<87^TTbCW3?EA^Yy%Vd?8=dU?iDRvEzfIhWs5-Fdv^Ke4 zT{t>9o|$i?=4Ra<<$Q8iYVKttqntzjOwEmtiE@rSw{>pzxG3in)mrD)8Xx5x8*iQ4 z`K~BuYHI7;d3o>D+@<@Xob$3%b7S8{Id?vpn%npLDCeFPsktdX zL^=0tPFy4UG0J({7pb{L5_LoMDqbO~8=6b4u8UYTuz8P&RRez<6R~Pw%JhhJ+@Dw+ zvHITk)rgf-p2s(hNsgyHpWHYmIiB)7d&8LIc*^sKcg7^gQ=X*~teo;ZmZ)9IDbE%O zR!)uQd-caAb80*8qW<^j!ov&cvik*Y%-_D^Y>a~lQ}h>k0t7% za_YFhyfDhCLgSL2 znxFUn73I|YTzfRisrfnfaFkQ?v&Sz{PR-Ao4n#RMKiB>c<T(a+4 zN7Jq!m+ZUNQD)yrA@u4WE*85pAqnujr z&8I{;wcaO9igIebrzP%9V!iJe73I`=?>{2Ssk-z^;(LL*blY1|PSvHOuSPjlmtI~L z_DJfxxW?uvr})~$XK5}S zxuJ_aXEy6%&$jU{_FPuKi#!1HJ92Oz% z=jA_k^?1(yrmM$u->$A6&$~WK{7*1%JimS+-N(J_hGJaM4A=jV*w-90~JA0+Nu&YPd*-|6o8 z`Pk4NUPs$I_3%1sn$pAT==175ypGN+-^1(ZvD12Z9o=*M7O$hL#`N@hZ+%NoulMQ= zdwRW>xumDpdzZw$WUTk}LOs3SR~+f#^}a8qm+R82m3p}@{cy6U>(ZWmJzbYpZtv;3 z^u=pEU6;;yp{MK88!z{A{jC0QFW1l4GJCmxPUzgr^>bwNUap@bYbLIl=he@H6?(aT zmisc=M`>*qdoyCy`BINYtU5pVu839V&mR=A=KRXEh*gshHHlbrUY>j($&>FRdGdWE zPri@j$@h^w`96{--$xoxzBe_Vd~a$z`QFrc^1Z3?)W*Kz0jUGtNDh~_8z5Y12aA)24;Lo`3xhiHDX57GQ&AEI@{ zeo5Js};)g|_ys!QxYRX^D$tA4UiR{dn3toq45S@n~B zvg#-MWYtgh$*RvfPsv{VNebsLV$N&CobQM^4-#{JB<8$H%=wg<^DHsvU&M8uLVKO3 zh&hiFbABi0yid&epqTSSG3SqB^-JfNu+G!@ABw)$zA6>{KSkebC8|ZN@3l#-BG&iX zrjZfrd#%Nj5$k(x`!5medu?6IPg1xhp!{4b5OWPdtZN!N_ZM@`LCm!XG1n->T)Pl+ zO@p}3{b{dre=*la#9T8Gb1g;8H5M_~Uc_9J5o_FZtwzi>0WsGK#9TuVb8SJ)H3u=* zBE(#y5OeK9%ry<-x>iGbU8@muZA8p96EW9P#9U($bL~aUH5sw`_1`%M!ga*?vgRJ= z(PGZ8#hiDGIUg5uo-XG6J=s3*yk5-tK5<>gpuMhRh`DYc=6XW1ecp8jG1ni&T$d1Y zy+X|1QtO4irPd33ORX37mRc|DEwx_QTWYdMJpT{+pSD<^w(<cH)IXU-HPR@OllXD;CXvaIXRb9PR=EjlXFSscI4IXO31PR`Bo)SeAb?b-0uo()g!+3?h! z4NvXa@YJ4-@zkD;@zkD;@zkD;@zkD;@zkD;@zkD;@zkD8Ik_gIoLrMpPOix)C)Z?@ zlWQ`{$u$|}iD<>Z>7 za&pa3Ik{%2oLn@Ag(y`^%pw^UB{ zmdeQlRdC-}xw^vtA_Ug*X zUR^mkr%+DLDU_3Q3gzUSLOD67P)^P%l#_D`<>cH)IXU-HPR@OllXD;CXvaIXRb9PR=EjlXFSs zcI4IXO31 zPR`Bo)HPTU4vyjbq$vB z)HPVfQ`caXlWQ`{$u$|}XqNa&j$BIk{%2oLnlWT^`$u&de_^=brxS&prL$_-rrFaPb_FocfSvZci`|ImE`+y{(0|B@_jqJM@3`8dsM`{M@6h_cX}@q@&6s~z0qfBPoiV@ zpWm;-aZJYlc^{77W25&MX-qhdVveJj<4F9!`+Ye2UemLae6NZ5UK8`ZCgyuh%=em@ z?=>;sYhu3F#C)$2|L6JE|Jw7d|GcN@|E%{E>G@o}!-3~^#XQd|<~d(6&;N>fE?CU- z!s7pl?@Qr1YtGU13@_(sV$RXToTG_3M-y|7CgvPX%sHBvb2Q@rJX`%=d$yY6#q|Wu zE1tg=^IW!==e5N=$1UdhZZXe&i~py*FGbHTC7&h9d+s>-EJ@yT$KrpU>xte4v@P$s zV~xrGm(TU^4xfMCxfC6j|LN~s((_h&7LwUimVP50&U9tJV*VGwh^Cgwd1 zV&20b<~_YVEn-aEv-)BoJ-J}NnH|EJ&U{?GgLKJUeo&q`Cb$Ay(Z>+P0aV2nC~?)-)myN*Tj6UiTPe5uJ1M4 z>-|Dv-Y+EP{X$~iFC^yuLSo)8BV)g6)*7qO&^ScsTQ+W5gjy2aI#k~7n%)8&k zy!&0uyWffbcmA%#g=KzBDR{x8_>kJoVuL#VWLCUZu}Sg!FK!kSzju6MywRx{Kmw1r8W^ae|2K~>kk_zBL&j76!c&Z=7*8>t zVm!roit!ZVDaKQbr#SR1b8J%l_o20u#~s#q&MGuHUgM8i$+>Y?$;t6G_eVVX!pZSH zDG{Ghdvd&VfrwvfI5~dpuA0gA-?y6_AG0~)3;X29-@PNheW&dFJZ&G!&mUWu|GBGQ zm~6L@aZ_J#6XPbvO^lluH!*Hv+{CzvaTAAb;TnN8Zj7PY!-|Lgu;R>NwTBh|U)7Cp zF2QO)bz-*X8?5*%L$f_6(|Tlku5NCV?KwQPakl67cXhKp=j+$V_FC9fIooSw%LUn9 zJA=>5_L_RDT(;NR#`4)-gJUaZdu_g2HQVbqWIQzvc#829<0-~djHeh+F`i;P#dwPG z6o;Od-jHKYSmW8ZZI1g=u49h-_^(bm?tA9VIUbYJ?Q=XtVm!roit!ZVDaKPA zdOn^$#cLVXc%I*Hit9|#5mQ`e3T91lotZUzit9{+r>3~h3|l$Hb>^u}`SI4D=eOT| zAV1H}6Z!eyDLU1k+obeVyM>IK`huGnH!*Hv+{CzvaTDVv#!ZZyICKlw2&{2q4AmZ1 zJoJYZXAY}9tT?qoaai$iF2RcLo}LyPzU;c>_XVu@$@*!rluJ^Q_5Y#m?P5>OjCfPm zcCqZe5jXs#ZLCA(ShCH@mThCTTSVM?Wt-T+_7Tso+Q#wpIj!A(`#G(hr|7&?=bv9U z)t{TYrceYuqaR-X-?Q zUsaQ1Qg3wEShWkQC3(niU1O!wBEIj|Zn5hgjrg(myT#TYiMT-J^jO#Q>dE$#`lQEN zY>PPK!Sq;mn@f`MJ};)nKG+fQM=z(xR&~8J8K3^|^w`^bB0f1GJvJ<(Mlyau^Yqxj zFKQ$`L&j76!c&Z=7*8>tVm!roit!ZVDaKQbr#SSScxh96!Wz%z2b#pb?iBT9*E>yO zPrMiP@%+_IV!vJ+vEq%Mj>bgo|1KY~@{D*WZw$vbjXir|#P98E8f)}wH0BSbH;eVi zh`7?%&0@2vM4U0Cd2Hq1(QzzQ@OmHXka1IAa1-N3TyA3A#JGtw^4!F@iE$I-mTVum zF;0_du;R>N<$)EaCMXUo9?m6L@qfKG-fI?CJbvqVuj^0#zSHZy*pxe6 z2PU3!r|U!fj&ZIVGxv^lJ=xQ4tmBWbALI7tG#cYPEjNyK{@p!C`*Z&;G1_h+zTG^@a}3tF<(8T3d3a0uWY5n<^Cx@W=6p8U^Ep;B z%k#YUwOOA3WjbYfT@)IS<@M5QSeDn3;;b*VXWc0eH6&!*)EC^uxQTHS<0i&UjGGuY zF>b`=Mtj`WbR1$gSmSo2+z|Vpe|WI_)$QBC?yut14Yj9kC=YdG(X&H5p2bTI^*Dbr zb*RU`*O|lekISROe7w?X4)-w)88`I>H!*I+sT;T{j++=aF>Yeq#JDBf2X2g&;;_ao zTo^LylFQ<9$ex9&@}8nK5gQ_aTkm znB#p&p|9q6A9DEjIo^k4o;uh2kQznidLL5s?>XLwG(0fJ`;gXK=XjlljHmjArx;H$ zo?<-3c#829<0-~djHeh+ap*az(KLI)8qY^7Pjfw4QgWK>N$Tm-Tu&6Io~S+bM0uzu z!v{=rJ*hT7(LQenA7uUS~}Q5nz1W>$*M zUshc8Z0whb5x;)&nOO1d5&yR4nb>=0N9QjGCOs3Ic3s3bG<+uU3YdsD{Q0!G%Ic@x zroxz~{kI)sPdjJ#qEGv?=I&fD(&Q$+>iR;XZ)t9=?^h#UmI&;y8rLHrjr!94z znLT%@>_mb%Vd^59a}nVyrDy3P#kv()Q1WIWX`JjHm5@f71J##4-^7*8>tVm!ro zibKx@pDeH^tnqwpYeq#GxBwr8ul{3)c>; zc<2u+&Ky=ASaE8F;;`c3T!IxpRPimZUs&;izrX4IL#s7!dS7wtJ#TuyQMu`x-iJ*5 zE7$v$XIA8T-?D8$e*B6mxo&^p>o=U|w8d{Yf4j^#{JA|_zG1hJaZ?|06XPbvO^llu zH!*Hv+{CzvaTAAbEoQFu9D_A(m3FT6Jbb(2I?vD3dad)k-9K-g=kpUEuJb&fd19UC z|H$&|y)Js!T<`U=uFiU|BgHx2QG3oQl!x=3ka1IAa7*?v&rOV*7&kF)V%)^IiE$&& z`A+DzcF;<@!5X)1ZC1Jlo)KH=+W1}Fm9CkO*IVgYTCw>`*VwbVuXOGGaKcL0tVm!roit!ZV zDaKPAdNPKJ!y3t;?T2S)t#P)u*P$F|DB$z@#l7W z4tM!sr{{M6%DX)0e{H|ZYhmGpU0x%-pWNlO(|*-1uc?pT+2yr1ZR0Ml!Q0;6<+ZtB z$u6(iW%uv$x(*pn^$Slio?<-3c#829<0-~djHeh+F`nYk^P5w)*b~-x{<(Lv>u1Sr zn_X95d~dVst>Wxk)Si8d^005&QFDvy`IMepT;~VR+v57a{HrbgUT9x+tG_QU8?x2M zI%M3`7u>|S5oh0mo8q{MaTDVv#!ZZyICNvI6o)l#;o5-}5B*`qnZwEhD^9IY99BG> zOR(a<4jk?OGs24B-C}h7#mdpWD|M@kj(_}TbdO4@Q%A>(z8P_)Z%4(e4T!ke`=jEy zr$pQ;@!Kwk?~U$V*|j+F8!km6&Uif0eoS=l%2kh!ijVw0x?e@{4ILv^`+GJ<_pT@p z_pXGDoBD`bvcGw5V%)^IiE$I-CdN&S8*#bO9=EGbj<*}Eaa&wsg8eTnJHh=*EkD8i zRh)59d&Wn37`N+w81M1yxpln9dC0Qy9{-zWj`wl-bKrO%ubC~z`Yeq#JCZs zo`h}}*SXzpu*U7-#<$!5%$sg^zfxM??*1xHJyCn=iSkfSYFv1`$FuFJiS~JQyZg79 z9{=msXZpD8e=^g@Yr>tGKBgh#rhefj#*H}j1UJQT6XPbvO^lluH*x4zyvtCpQ&{76 z>X4zn59F&ULw*0rhffXl{U=A>9qRi}n(iO!`%hjhIn4K;TyWJe#|Pa!%Yeq#JGuZ6XPbvO&q#~^B>l@F@|anD<1m8 ziZfT$9#)*SuQ;rDIDcTpKm0hua|~9z&r2Dehv&@5@ccY9D8uvi@75Wf&sDC@@I0^i zuME%sRcB{-T{J10XrH$aDP1_j>qv3xhT2m%l!v+zGH&W4ZerZTxQTHS<0i&UjGGuY z;?#}Mt#rTsc7ru;_ubLo_p|*np}+5EE11>a_p?1UslV@M+c&nq?`QjINPpkYR{WO! zzMpM*%l^KfZOG;QeLvgxrThDSwp~a1`F^%@cJ%Z8Y(rk^=i?hPp6Vl>Vm!roit!ZV zDaKQbrx;H$o?<-3q355|`*_X58qZ4>^zq&xXH_5X8M1fu@m}J#Lw&r*7+k8a_a1N7 z>FfQ;#18qq?T-95A3xOBf4h1`U*~*fYhQm>+3)(=q3Q9y_6!+M^$Slio?<-3c#829 z<0-~djHeh+F`nYkGh8pQ#*?vCdsy+XFR*n3;wi>cjHeh+F`i;P#dwPG6yqtzQyhApGOxQmVU6d= z=exUp{`7Kp*VPKEy1U*gP90Wz_ASc8zNOfd?yl!o3{JGq+qcBpba(wfzjk+jFT7W* zyT31P`7YhZI%M3`7u>|S5oh0mo8q{MaTDVv#!ZZyICML(wu{#X&3Jwau0R! zzGB%~UA^DfennUBLoV*n)%%l~qq} zKd|C2Hca&#gB5RjL8|BBkz=hqKR^7WmFMkOt6F(JpZY{A&-3EK0DUhYZKPE?I_X4>vu`DHeT0H zHf!U$v9@m;*Nt;>+PH2^SklIIWB<1N_;tVMx9?uIt@E_4+t&GOv~KIqy|{NIK z`huGnH!*Hv+{CzvaTDVv#!ZZyICKl=Kdfq)F_3m@x{aZ_J#6XQmldV-tcxQTHS<0i&UjGH)gd#`3QuUS~* zcC2ADpKEmK)Xe7~9W$Hx+~nH(oB5n2Wmz+y@66cN%;!68j^y)`=Qeknf7fm9znz-a z+&S+a+}xk_-QCUYPtdxngs`h}+$PcfciJjHm5@f71J##4-^7*BEN8Lkmnv`_MieG$BJ`&C5{fY9hKM5H(^$|BQZerZTxQTHS z<0i&Uj2m(GC!yQ61~I$A8n@;*#_a!k`>>qE_0tv@$ss4Pl}Ie$hfIrxQTHiPCda*aoohXiE$I-CdN%1y1mw` zzSk+Naa%sJzV`{!?yv9t!(B`3dtb5egZkc|96ns%`;%MBHSqrAz3Un{etwSzZXcW2 zzIK`huGnH!*Hv+{CzvaTDVv#!ZZyICKl=KdfEfM&(A0CsOfpTq*G1L=N++{ zp68!kQq%LlU-_C|7r&mBXrFgpv!+B%uOr2&8){G8P#)?=$hfJGxQTHS<0i&UjGGuY zF>Yeqh*LL0w>3lS*bUaW)t^wud#d?U>Ugj9;(c|z2Wx+C9q-L%XVvkZ?XgjHyqA0J z);iwf^=engd%p{>t>Zo6!xz-?UUBMQS9%Y*_VX*fx4iJRD}8)J##4R7Q;eq=Pcfci zJjHm5@f71J##4-^IP`q(;o4rau*P%Y^R>OM?|i4W*Za`DwOt2h6~5f{;hXB0yKb~@ zb-C-wYs2#6#U9LWU+b02ou|@{%bowkPnY|14;Q+^ZXx5QzThUtO^lluH!*Hv+{Czv zaTDVv4&B0a0c+eCL$!w$5B*`qnZs%iD^5*N99BG>OR(aPoxCy5^Tn{@3xBvV&hy0^ zx84}%`Qne4-5BTj;uSM*jPrbP#-JPHJYRgY#f@>EFTU^M{CIaqo=OIL{Y1y*)L~^TpTQl^W;y;=k@m zjq`kQ=P9Xio-e*WD>csZ#ovrcjq`l*fPtxT?v)K0PxT8=F`i;P#dwPG6yqtzQ;eq= zPcfe2&@-z_3wy#E&$G(3h;!fX+~O_b+z)))=`G?sU#vLyt*Jftttk)pt&OYSBF^*0 z9or|`=RMcca(Ih4&leATphcYLi(h}GMV#l0tAEzQ$2w%()EC^uxDn^RHQW@(O^llu zH!*Hv+{B?9W2HE(aSPWAta#`TE6yBN9$0Z|g5t2^;aq|he|}>}uUS~}LO?|{ojGGuYF>Yeq#JGuZ6XPbvO&q#?GO?5A7_4z?@>D0!!v_-o|6+c=lK8(E z^Y)pdojso?SMKb2KK7ci+{DbD&*d)A%uP(wn-O?|;l zjGGuYF>Yeq#JGuZ6XQml`|U%w*}t^28?15r*PeFvfA*7h?$_8I?c86*83(neZYU3R zV_M-fkLRrw(>%_dQ_?*C?Pu;Q=J?&-A&D?Vdl&p6Km*1WA} zoaX_rXx%f;^MI*W^o;X7;0eZE&2TI^F7?=>-&26Z%+>H;hcrq z_wZ*uaa|8P+ zKj~M#xA!Nfp55E~lY0yG_WBJOPxT8=F`i;P#dwPG6yqtzQ;eq=Pcfe2&~wpi>Gp&* zo>x4d?mF|@f^^rJd*`RS&L~cuQG4o)@=#~yeUR=tGxEno`@H?hZAH7g&fIrNch{LO zZtCtj({fmMAM22DQ(tfs<3^l1gPY>GiE$I-CdN&Sn>ci1tQ3beZsFR26%YMk#hJs( z11nCgP#jh~oJ+9c@82@e>laph#|;C$PdI-0K<^)llpg4P#ok{Bc)u}w%K+~~sy{ox z`;*u2&W{i5mEXQ)qXEv-@uC6FKkoDa{@ko1x7jUZ+|)>GIaD{*OQ|U4t70huynBN$?SE5T~9`QG}!fI z(4N7rC$+vG?0S;(!(i8wQTqnFo}BafVAqq!HV^hX{STbysea)p##4-^7*8>tVm!ro zit!ZVDaKPAdcJ&5KYPL&&qgErxt_c?sGsY}qqp^QJyD!`qW07i<)NOu@Mu5RlkArh z?epr%nC<;sPv#}=31mO{Q`!EmC!MeB?_(V@Zt4qeV%&&RPjFKlH!*Hv+{CzvaTAAb zjFsZB#w}bgu;QUVtT=O6d0@q<35vst|A)DhH^&rT`e&mU@0*1cFEF4{jOTQ6zi1fa zIi0IIH;nO|PQN|z82?`=FeV=3Ih_lu#$)_HqV4yw82_gjxh59ldhE)VV=+CaBhQfe zT*diZF`p~ubH#kFn9mjSx#IA1|6F=~jBC8G`n&0;>tkF8URb(CjO)X_Dz!*@s*U3K zt3CZv9{O9p+w~rYmyR^|_b{9{|j!4 z<0i&UjGGuYF>cBBft!v|hr`i({9ujAPjAIy&)s%i^7)$B*Rj~s`x+#9L%Dct=dBT! z&4|b59;u&<*L*V`D>x(K*_Sqqt+_Vhp$i(usvf;I+2-Dh8pV!mi1_wr8^!v)81eKv zjboQCiTKLb8pm3$i8wczRqF5+wMZW=r9tB4zJZyMXx zxIP)H#2VM8q-R9W`?sl8|Kfl|5`^4tEowM>=cl)!3t+?9`yPmzYeq#JGuZ6XPbvO^h3HuB(J@hcmP625a129hl|4R^fhG-h=(wC(C=YXZvP( z&vwRbS>DT?HZ;q7ygNo^dGB}88j=cp=Ms%R_HudC$3iOO}ss z$at!cc#829<0-~djHeh+F`i;P#dwPG6o;OSq2jQ{Gh92c;$dH4#hJs(11nCgP#jh~ zoL8{ozaPKL>laqM$FFyJjW6AIm)HIkpWfw~5Z`#0YemYcyIeyaeEKfemK6`@bFu9F zHm8rw|J!o?@^jAZlK)vhq~<%cYnJaBGM?%$o?<-3c#829<0-~djHeh+F`i;P#i3{M zPbPXE!Wz#nznkc}+UVFs&*2S4CV6fbFEhz=eo5s?UJG4oPVyRgukIwTop&2d@|vm^ zpX9anQG)q@(EBNqyf({UJIQPI%PS^%UH=Ep^Hjg^6yqtzQ;eq=PcfciJjHm5@f71J z4n04*V7xtHjc2bC<6S@ZpEBNc_4NYdU2heq4y!%qN6N$b(UvR5yPiLNW1@Xtoqx3d zc-Q|oa>o06;mjrD{e3Zd+jt-Aka1IAa1-N3obw~x6vs`Bn;17SZerZTp&MhRIIM9C z*AA?B=npH-99AA!acYI)u;Tw=F6GTJ#lN_8r0Wc<_}+6z`nty%f8OEiA!Wb3!`DfE zd;JbyZ&@_w4qtDnH{uRoZ`s@?KR&Kze*4bF^Yh$#aD?+u+cCnQJNwNMb_*Fd^$|BQ zZerZTxQTHS<0i&UjGGuYap+d`n^B%)u*NO3$Y{^Qb(fCz{QU05(Vn+E`;Yc~UOsuW z=lS!GjQ0Gm`1EM6i-(pa+UMt7&kF)V%)^I ziE$I-Mx1?1=(fIXrrltTTdO9Su7TfQo9Wv4N!?7>%sSU(x|SYJ$#jj~-!jv+_x&!J zuE|w~X1Z4QpPK0!{>#5JUE5Et%XH0Ow=dJ*1^tWM?&BLWp6Vl>Vm!roit!ZVDaKQb zrx;H$o?<-3p(kUgIIQsu*9)w8*cVuF=CJa>ic=F5hZPU!6|DHZbsBli!iwKgsgd_B ze-&-yeM`ZE4ZUxv@IgcGTh4p2q4zBtrZ@DyrO2Rse)-1yHp^<{|Lv9%`8l^8iu<#M zeipYwlMQiuhK#5Bi>DY*F`i;P#dwPG6yqtzQ;eq=PjTq^%KpZlhp@)8@>xw>XEGDd zJ8*vVVEZPnGgF2qo`cBy-t2W>6W5upPd0I#+45o&*O{iP6YcZr%Yeq#JGuZ6XPbvjW~5Cbi2Jvirrw1+ld=fTxT9`oZ>ojPb|fC z=IeNh>&$}YDXuef+oib9jLk@Ko!K!e#dW6KtQ6Oo`AbqtVm!roit!ZVDaKQbrx;Ih=*bu=4r@HawF4_2_61g)IjlUe;?xSo zVa3CF1uH(b-_>5fu;P=`uJ-=nnQO21zT%bhulBy>f#Y?(Z)x&LUGG~yd8w}VEd!?K z$IB1MZ-1<1UFRu$SzYI^QL3WTz*)3$;)JNQstVm!ro zit!ZVDGog|W?X4cSmXK2gezSq$J}wH>*o!bSGuk$PQ6uo&V!VP^Pp~vu5{hLIycci zuby9$xF?zWi*8KZt4#fWtWq6+FBEN7$HzKk+|(D`#JCaXJP0?%aTDVv#!ZZy7&md~ z##kv1Yuv*10xKT+!-_M9l?PUwnxHtWcsQ3}#Rtr*;WY~@9?PlWJ;Ue2Yj`iQ`{o+n zxBPW&4ewiyoma#Amc_>|^}glXkMsG#moIgjnGas-zkOlkrOvsm+ok@j*3B-pL**+k zwP(n9s=s)O@f71J##4-^7*8>tVm!roit!YOo)2}X>A44MJPVDf>G|1iUQN&25xF%z zpKtxVrssL%-)nmQ*DqGf>*9s-wY**~zPOgxQTuAOyuK7?-=g;HTa<@=OUSsXFSv7u;R7etmL)){^Ckr z;~(5t$!q_>;7YCu-=|h`t$4U*CD)UWi{`yEawy-_Co!qH{iZe?@;*d`v|< zl)AN|JwwJ*{l!y^rx;H$o?<-3c#829<0-~djHfvCyeFr!=N_!_{B=oX&(Fr&Dtq4c zK3v)J`R21P@;twy#zmh0mo~h}>tbH(i@aXW>6~bvcOKNF+eKbqic?S2o_eA@)RT~L zQ(tfs<0i&UjGGuYF>Yeq#JCZso`h~q{qT!2MO6aZr2e ziSkfS8k||d<9TlN3LfX8%`15PYusAF$7O6z1s|{PmQ?UD4H-A}3pX)t#HlB^DUO>M zH!*Hv+{CzvLpR1saaiLPt`S)A&>vQuxvD&{;?xAiVa3Dw11o+*kuqMVu;T3wo$K?C zQJ9KUUSa%`A(@j&h`1uQ*F=n`A+?s`SBl5&u{>Rs=jGOw1n;17SZerZTxQTHS<0i&UjGH)g8}VjY&oNlzw&$C&o`+W!Dd+jw zzIr*&+v}T`^L+kSk8+;p=Zz@m`9CeIoY%!E(-ZCU>PDUW%Xu9sPTf#@>W1=AH$uiu zeZftPn;17SZerZTxQTHS<3^mi5xUi>RmyI##_i1uOWD8Wxux8%^GcO+e-&pO)SkMb zJk*UEO-gw@3#TXA=j}s|jVa~vFaKC6AD01dmh$oXF9{R(IGgp-dR-Co3IIMU$e_+MyUsud)6IQ&$CB?i4 zc<$_C-Wx3a{S5CJ-v9Ir?@Ji~j8J03p6`;eDM%{5) ztPA&^Ziho3oNmvM@l=2D6yqtzQ;eq=PcfciJjHm5@f71J4n6xEDek!kYdp^=Q^MCz zKDfGsub+I`p@grW^ch~l*H50gw}h{s6ne6Rub+Igtc0(heD+2OUq5+tT?t=5Il8`t zub+JTb_riUnY6Nmub-U$YzeR5knvQ%@D$@I##4-^7*8>tVm!roit!ZVDGog=XB4p~ ztnpl$R>XDY+8c_v&YXUI5!V^TsWWO%olzd@%=x2=xX%1`f1-U}o%w!g5!abBJ}lxo z)AdLZ*O_H!*I+sWZ4Kj++=aF>Yeq#JGt=H^xeFSmPG19a! ztUR#d)C$F6#lyJ-D}L#)0$#tc;#YJl;C;f)jSG1H(EH*7-d8j}rGWP*-@N&^f5)fT z$iMwNK6Ps4$7g+a(!b-=>fa~*J3jsTpY-qeEU$agzvHvE*h&A^M##9SkGP3(6XPbv zO^lluH!*Hv+{CzvL$?l>6!IK{HEwUWD&%>1_OL>ppI6N)c1{_t;+ zT-o>!|3=B)fq(e7O9syW!@p@V_R~N7TPF{dIqu&;sod$fe;Z}cqsRT58X@DUKH@3H zQ;eq=PcfciJjHm5@f71J##0=6GKPx78qaXOz>0@`ffZ*CD-WzVH9>J$@o-+jir2Ym zzt=3Rc;m|Zy{@Mp{L$6dYeq#JGuZ6XPbvO^lm3besD6LC-f>F-+#G&`p^Ddn9DZ(?B9#o^ViS*9hncS{o>!3S=sy-|L)AcJOAR}qbc0u z7ynL;;?xthr=BPe^(186)EC^6eav$c<0i&UjGGuYF>Yeqh*M8Ow^QeSV>ejiR$=Tn z_P@N}H}2O5J-=~(6{oJMJ^K*lVIOj2?Kd9JXO1S?=j}tL*V*gw-#%imkIU_^@AdJz zsqj7@(~xmfzi<=dMx1>JZi?e3#!ZZy7&kF);?Rw;QXJN}h3f)VJoJYZXRay_tT=05 zaai$i{=kY4Ip-q3p9fa_lwT_Q{Y%T=uk80P&3vx1-@o+uw90<}(%Q_*e*e;Y-7EY3 zOPyL*_WPIiG)uJ4d;ik1#+Cj4CB=EZM(ug-MtOKPCuH2zN8H4?iE$I-CdN&Sn;17S zZp3;2Qt0;5zpL8~*0@!9xw`!y%dPHyz4vx?_g8VoLG5{NNO^c}Xw}T>9?!4tNVLy; zZ`)6us(bu5T~po1W%N1KeZ0>6rJ9dv$hfIrxQTHi&T~V!DUO>MH!*Hv+{CzvL$|r_ zU+i}o!5X)Bzq;7(V7%n$#eO$ql~Psw&c>pbSMj?XOSGxtcRY3kjutoT4a4_%Sp zX2g#CzwLA=KWFcrvzX4=Wz_1y-CntoE?t)C9$0#lv|8D}GDMa-Msz;;XBb^E<(goR+xmcWU&T zU*CRL*6$Fz<-M|gx7hhFmGwKv);w0$?;_iCZ&|;i?1u?u{qC|$Mwj(F%{GrL>vx@f zIkv3df!6r$vVJ$(YY&w5`VARR^%qYuo?<-3c#829<0-~djHeh+F`nYkbHT0(_JlQ_ z=l)p1b>`l~6*5MN)*<7jzThUtjW~4%H^p%i<0i&UjGGuYap;y)u)NnVtZ|!Ero7*)*6s50 ze&1T_)bf50+wdXf{XVxfv&#E@Zna)5@AtXQ{VYGe|73pq5|z$(o&vG+oqyNO=lgTF z4Lsj&A>*dL;3mdRjGGuYF>Yeq#JGuZ6XPZh-NLm1Yup$^wTBfC{b9wKt7;D`PEAl8 zRy>?Pu;Q)9m+%~e75}Dl3D3h>iR*_vk396;5}vnr9xd+qyzqtVm!roit!YO zo@1^q=`{;$Jcr*{((C%BJ|(^0q*X8XF0yB&RK5% zSNpS^=a=DUIsc~n&hqE3dGai~g^Zi}f}0pOF>Yeq#JGuZ6XPbvO^lm3bPLx7tZ`!u z)gD$n^oJE^4y!$^I5k0WSn+T!!HUP07xH|A72iI+kn72$0fk&odfZUR^<>axgYeq#JGuZ z6XPbvjX3orbeq_;sNG_ev3F6!}IdTye9 z-ah2@qeVRab3QKO zIMr(t*0?=1{#2i99DDFopMxBE@l>Dhe6r*lj;VH&bjHeh+F`i;P#dwPG6yqtzQyhAR z>jKtzGPY_DD<1X*R-8Gk_ORmA1jS*+!+8ZO-tB{*{f-V;@w>Bs_Io_`HvHM|_n3e3 zpx^tkYRy5v52WyngMLrQIeiZL{UJ4*AM|@g8rDg)&)c8ux$L0dL!vnKMD3|3%0oQ~ z88`J2H!*Hv+{CzvaTDVv#!ZYHaq3Cv_VuCTc7ru;8_zyr|CcX5;eMT4^6JUWosWC`OO-wD<1*}nKYYCAWdGq~8ZvI`7j9zQh*M8+ zQye!jZerZTxQTHShi)%5JRIZqf?*jGGuYF>Yeq#JGuZ6XPbvO&q#~^B>l@F@|anD<1m8iZfT$9#)*SuQ;rD zIDcTpudBbya|~9z_pduW57$1s)AMtDznz}9k6gCX^Lg*FPd(2MZ~4^ozr>55dR&*TMvEeb)-0TL+z;>%0t}<88`J2H!*Hv+{CzvaTDVv#!ZYHaq33s_I9^@c7ru; zFOA+8JDMB)p8J^l_Qe)AjDF{R-t2v`rSC+%@BV$UM_NU{3*S3yU+n7-Bffp$zF4I; z(Qn5uzhPhO%=Hl$th6t-ux9jI^P_*-8@nt!;@ej2jdj=>aqBzw#yGE8d)409{TD~q zwMPH?jgN20c&d+hit!ZVDaKQbrx;H$o?<-3c#829hn};Z{laS&)_Cs!;ENc)lfLxt zFJk_k^txZh_?`5@!@i91JLw~reHr6-($72cWsKiRfApHK%&{?Fxy|*fzw+Of`28#A zEPUB+f7Zq>yX|n%#NGA`8Bg^KPx0bBPcfciJjHm5@f71J##4-^7*BEN8Lk&t&$`k*1FF8eOjV@-u~o?0&87o6sOLpJ#|KTs52qsras~(#!ZZy7&kF) zV%)^IiE$%NoeABZd}piOV2#`T-)wcA>GJzl*O@y{Zgrhme`2faOw)r~U1!>Vyw!DP z){3pJGrOm5b)D&S^H$fH8!p`HI#X-+7T1{tk8g3E>C|tVm!roit!YOp2N=B;Pne@JbT49c>hpl_y+GQ{(NDB_Zy9V+2DQ1*H>@!zGd}< zjo!E1zac+|vtIBTDLM89ubt_GUhtaw__i0k*8Uj&g4f`h zyI=6yd}+Z8UcVvZss7?A##4-^7*8>tVm!roit!ZVDaKPAdfs*UYJ0*O&s$rscAaeB zYqjg=@_wsbR~4t;sy*jH%ENikjMG-TZhy9ImFxL$53O>Yf3f{4*Z-1duJZRnz4a@7 ztV704eZftP8*$Eqa8n#NF>Yeq#JGuZ6NheX$G_w?3v1jOKmC%|_3xj(Ky(8uNHkqdpi%GO@! zV;VAU>KATe+=x>*a8n#NF>Yeq#JGuZ6Nhe>fB%@*CaiJGIdh)RHBwXN`5dHq<~*O9 z6kj^e=Pc*`JkRGcE3bIm=Q#C8cJ6$8 zhK#5Bg{K%#F`i;P#dwPG6yqtzQ;eq=PjToOt_xV>$=Iqrta#WLSaIgC+QW)d6BLIP z59bxE`072AJ@;V6zkX!0=VzmKlRa<$EIHZpxy+79p69)unB@6C?2buZ7dbai@_Ko^ zX`+4J`A#f0$?HpT>WSJ@Pn3sx5;AV;BW_~c#JGuZ6XPbvO^lluH{#Tj&@F!I47*yoXd`v^eP5r`6j2m(432utxCdN&Sn;17SZsO4GtajO6r?AGY|EO%Q<(iALy~eA2 zk?pmApxhMKgx@+%ajkgx(J8Jc=Y5sWum5YR+pO<7)qi{Mys6GPdHYm<*7b#Q?C@mu z9D9b0r}~Ab7*8>tVm!roit!ZVDaKQbrx;Ih=ozjHSmVjqsy(cD*cVuF=CInsic=F5 zhZPU!6|8vT(9Ca}(nx#!ZZy7&kF)V%)^I5vM+f zZeNYe@cM-{Zg0Jp;q#8_b$a`JaTDVv#!ZZy7&kF)V%)^ICEEvX;cs-673gQ16V z;-{uwp5#}5%!yCm7IFREIq@zxT#<~o+MZ~?EaLX-a^i~$Uzv=rU7iyk)+FNc3v%K& z_K$e)jGXuxcSOAO&iwdk1M}OD=$fBr+)erUXTMf5q_^<1fZvjK3Iv zG5%uw#rTWy7vnF+UyQ#v^j98!=M>iX>$CWMOgZp=FuC#GFgf!aiu%IuZ>ovTrr<3=5xh-t~mVMu{)>wnM7Fqjc=RkXP>8S zp6X|!v)-HPXQi)vf2yCMp0#zVpRJz$(NsTkee#Q`eir+=@2C11?N+}{^|RaepOTpK zY1NYRvux=cKkGf_q8vX1-s-CS;}SBS>KC43JjHm5@f71J##4-^7*8>tVm!s6Cu68M ztnm!j0<3u07g%xTp7OwoQxg=2iT~&MlRl_Ktl$NclJ`D|KbV@82etTlFjoOzvHYxeHY9DggCj6{g#U>^1^VHwIcYI><{!ek! z{S%Y-g^CM)F)?|+sQ8u-CMNGA6~DB8V)Fh{apN~8Cht2HH-B|v@_tnDx63Cc?^6}m zOR)aWD{lDm#N>Ug;zO$@ChvC@<0=1;aaJ5>G0tL~#W;&`7UL|&S&Xw7XEDxVoW-Ft z<1GJKg(fHO`4rz(a&q!sQ1R#sCnxU_6`xUia`N6$@kASmd9Hr2AzN?$EJDrs#+%t}_L* zrnt_`nmxsJromHFTxW)@oZ>q3)TaD+>(BGs?>>;9XXlCh{O=T<>d$3v$TMU-6~|MI zrx;H$o?<-3c#829<0-~djHfvCWIk)$`nJvS94OZ@$8+OfopL;9GH=fDTq@l@$8)S~ zYL4gL;$}IXlgI1lc&>J;mE$>lZlxU0?dfMF_L+HezD9u@uZ3`JhK#fNg0mQBG0tL~ z#W;&`7UL|&S&Xw7XEDy=(0TXtwB)-2G@chUPftE$t~McuZAulqKKZP-+TS;%OOn+- z{v&`;fynAum6W_$|3kHIg-9*E>y;&$cVi`Ky~GpKTW_u06k4 z?R737Rvw)rh%?4FO+MQ$es5pX`%=V1e(Rci zkBa!dTe~ISuOfcz{cg$ku80d%PEWp%MLelbdh$Ij;*1B=lkaa4_jxfr`Cb?CM=z%* z-}fS({_phUdtk&TC!{Ce4F7UL|&S&Xw7XEDxVoW(ecaTen&4xRt? z+IZKK+Sg{eo`f8>Nvk>B_2k>llUz?i4%@8hIK=hj?-HY3PeKmcgnXpj5Z9CQ4-a-d z>Gthl*AvC5Cu&bUQ6B2aqGyM=o)j-N)b-?(sY6{)dYw7U^<>eb!(313i^eTvJQc@N zjHeh+;?xs76~|MIrx;H$o?<+c?E}y77{zZL?{)pj-*%hcQ?sR>K-!aa0 zW9Htmt|xoijdlF-^<&)roJM1ur{%`c&cD0oXn$^ad_%@l{&*()nCB_RQ;cV_eV(Tn zPcfciJjHm5@f3%i%v-JB+%l7W+;2&roIfAtPxd^?`E0W1Ppo8?=atqA^Q}y$EYHJ2 z1F}3ndkxF-yj5K9jnU_-J>Q$*x(gXk`Qs_ZQ@kk8Q;eq=PcfciJjHm5@gy!!+T*$G z@NCzO)?4SeZiF1R+4TH$*Nq~*A939XIczhj(KOeMN)=|gZiF1R3Hi~=(>$I_N>1}Q zr=C8|%ENISK46-UZ?*Y}_KA1w=y(-BvB0c7KA2MUs9PdLKy)no8 zkV0S0@jm46?{mBl$vkzg_aQZk%=JE`=-+d^4{3N{j`tzq8Vng{^#x}!&SIR!IE!%> z<1EHmjI$VLG0tL~#i8?uQ=fG`8QN#5>q*FAoBfR!xt>%z{(|dC$YGlWpDb`aX|#N? z>q*FAn~+~yxxn>g%fA=6o(!44!1Y9N>WSJ@Pn3sx@<73bt|!;mUFdpJbJ#-Hli|x3 zx}KCizR>lAzG&P+##3=T#dwPGBu+iSQ*k`Sc#829<0-~d9D0VwXjI0tv6+=pl51hb zRnNwLnHcfwC!dKG-yZRAYo3X{cXlk<=D?(9V$-gR_=bkh#Ok(-c*CDho2#sT+HER~ zdD?&5G4`}`b}#z0KWpyJ#dZjfb;vlYFF1>F7UL|&S&Xw7XEDxVoW(ecaTen&4xO3L zswcx!mblKG9KXbM=DatSxXx7neTnPLi`AF9&h$!K>N<1Lh^4MGrKc@*otZs%sq4&5 z^Om~KT=L*j*O{J^mb%V_Ycph=)fb$_IE!%><1EHmjI$VLG0tL~#W;&`7KhGrBXDn~=A)S?RGoBev3G{$1Ub zJ{FJHTj^s|vH40LyR*8l^fCQ#!b%_O$HWs7_q^$S zNadz)dVezUuUzkEo>`IW{mixj`SB~Nt#5oTNJxjgvk?YB_`**pXgdDcHY{*vElYUiqx}Jm_w)y6iEv_e%zS`z`5^~rk zJjHm5@f71J##0=6hR0~tjE}r$_^roB-b?&- z=||pUT>bM7?>%ZQ-QhjSy#sf6uX6e&`P}#0?QYZksqOyThi}{Nob#{R?$7$H@OC?d z$2w%3)fb$_IE!%><1EHmjI$VLG0tL~#W;&`7KhHvXVsJC{df91CH`FE+5Eioqb@(} z^mkDI%DepC^lSTF{?1xBVVA$ldOx|#-*N3%?ecfuNAK+NcjB~-yZl{w+uOVR9lBu2 zE`PU%Ycph=)fb$_IE!%><1EHmjI$VLG0tL~#W;&`7KhHi4jk?OFVAc--v3_?Ic(Es z<~aX<`KpuS{r}~V!#1s69p(QoUr=SN|Gyk^*e3j}yIYJ-zH3Owx^9)x$#)QmOPxA8 z`EH`*cgnY;lJ6`MH+z3n@?Az^< zcSyYWwz0|g5s7oAj7`3$NIc`|vB~!riFa=tn|#NS_{shGe5m+1w>f&*IREXg8^$^3 z$9=~6v+CVB&JN56Ifsn1;y8XBPyi$8Ti=j5k!#uq1hw+}DJ-3ecydAP^yyx>xGsktVm!roit!{) zJqbM-PtD;|hYa=oAzw`y>ibeYd}^rgOF8oHP~Vr*bpKG_m-1rCVZJZrf~$r(KIrCQ zZa-txFz1={&@kuk_Tn&qE^|Q6A>*kyo?<-3c#829<0-~djHeh+F`i;P#i1wjR^#?? zW1<#-)dZVyXRrsQxokI&x9&}_ir;jZ?9XQ>G{0> z$xP4laNUKBr~L60<0;0IICTS0#qkv5DaKQbrx;Ih==tHt8Lk^cUh3z%5pvk3>G8g< z8>Rd8cijj%Y*X`J8Lk_DPVeKo5pvij{H#7NWq3T#nUUdfJ~Sx9{-I3qs zzuD_?d#7f`(0ljj!f2(HIs#T{ptY%ovu$o~t!)k`r z45yl%&*XE$CH><)w;!+WAMd%9AKgFRb9-oH|9H=B<>me3J+~h&>>uyBZGUF}c+YM2 zQT^jRw+mbKkN4cZuGK%@b6c{mU%cm5`~80Lo?CiurmSYhqGnjlu$o~t!)k`r467Md zGpuG<&9Iu`RP)Q*^^7`m=2xdjok=;3*{@}o`fZQM?Mbiqh@2n!NRRO1r5k&MM^{|jBfM*LW{>c+Q`a8hb(fAkVh)Tyq({t+ zeGl#tbEbW+N6e+^NA!p}rcQF0vYKgEGpuG<&9ItbHN$F#)eNf{Rx_+-Sj}*%**tT; ztoZ2ExPN%zr&Hs;;>jAP#r?*6txt>lkj5vS7WXGNjW{jtTYi~V)_%;(W$_n&S=P^4 z<$6W`ht}&A$8~O?Gi7zsu1;8;usUIN!s>+839A!UC#+6bop7qt`Apu1KXyi3cYb*4 zjJO`vpL<4Jr)c;3MZEVd^yBqzyX()0>tO3aCGn;AExF^*i0kIAEzgMS=^NXf5!c!D zd`wxL=vODKPFS6`d*7l?+SLiG6ILgzPFS6As`H8VU89~Hw_CTUCn={fjn6(I>dD%7 zyG1=oIgQ!=hGV0ie6sPls3$3>G3l`m+pTNlbKS;cBhT-Ccx>c<>D*((mx}it8-CHJ zKHhQpvEgsSAtmvp_bopSIyUA5?cTQ#?|qBf$Xm+lq+Ok`I$?Ff>V(w^s}oiytWH>+ zwtL@_>NKCs|M#mMALsAmO^%QA`u@X@kGiqo+~cEe)E<9))QzhjKR)WlcZ&L_a6&e?s)%{J0b1xXuAIr>sue)d{N;Rwt}ZSe>vsVRgdlgw+YF6HawHZ^_%a z%esZ{pMBdc=EL@@y2U)9-T6bjb%TDKZ(E-47W1&dgC+5$bz|Q#-D2KucXqd!&(F2* z7V|tk?^0GL`qc@m6IQ3~)(v&iu1;8;usUIN!s>)mo%apv6m=ta!jVxoQch!P-O)Mf z#`4NXMcqg_jrrxpj!`$>XmNPdjg-@v^jKTEb&C6t{o8hm`;aEJJH>s-eH%K)eMqm* zJH~xTh1WaAeMrM+JH~xTv&TBdeaQKL?ilwWJ528w_aS>c+%fJ$Mm^av?nBf`4pUY$ z?P`YA467MdGpuG<&9ItbHN$F#)eNf{PBoin&Wnxh505p-sXY#lwaLjt505p=L6Z-U zwM_AohsQc-(&EEo9d!JdfLpa#3eePGi1bcVN_+=lUERbtdIB zCOuZ;>)J&=-|N#Z^893nc9H)V8np{wR&3KQ{Gv~NymaM(;cwBW2Zry9KRPhx1MS|Q z5byno+Q?hV>ZDzrusUIN!s>+839A!UC#+6bowj>_lIk>{%>UWL503kU8z&ze_Yc?1 zJUH$v9(?EExIbCD_TacbIkWB|aewm0p@&5KuDuV5_}sOJL_e+XJtX?yZtfv*T;~9q zQ&uPK>V(w^s}oiytWH>+usUIN!s>+838y-px8$vJmt6S%eD_?;hwo3x#XOa^Xup-$S> z39A!UC#+6bop7r2>ZL8BZtVVCo2VNpr!i}bT1VZOe^J}08!4wTpX}Wt>c*qDw~V@x zavGB!tM+p(BA*LxZxMOE|B@Dw|Hpf@2w&dMwFtlHQy=@)YZ3mgsZkPNx~`dDtwqcS z+N~SJTQ}53-cnX4?dpWp39A!UC#+6bov=D#b;9bj-MW$LG@s1>2On!0=kJw&ZyD$H zMJrmy`97smtEdCZo3@JjaNM!2qHa7lxU7AvsVRgdlgw+YF6ILgj>U7?cw}Y>48~393Uf(wEQJS?bHtu!rzO-%J13!0O+qgIGb7I@LXWspwws9|g`)+OH9(&xcZQ|a0!KZEFo;*DV zQ&ux$Q8TP&Sk17SVKu{QhSdzK8CEl_W?0Q|s`>7%UGhVoJhZTHHDF-Z!nbjVNjZ&a z`pJ=n?*){C`fr(E!jTyb?k%c~q?{@Rig<}z)avGCzjh&Co`+ne^+aHeYPtOKCsue)d{N;R;TU0&!$e=)d{N;Rwt}ZSeV(w^s}oLjI&TYe;G<&;-(P~; zY$|!4R{GvrzHZmT_nK(`$9`Q4-*JMs>)N&OeJA+rzFiC7eS#0WxNG5iQ1GGGbS-=* z3jX!Fu7&SM!9B0F)9CP*@;n49{KRZs3(`de`3@V+N~$VTTkf6dU9i>Zc$Ip+oN05lb*%hqMlrF zMz^RZZ(Z9h>WO0^Zz-#jc6Gw)gw<)g^+cVts}oiytWH>+usY#XXX?@HIVZg>c;&Q{qn-?HcXHH|s+usUIN!s>+839A!Mbvkc3e>*+YBYeNPWZ#f)=+XXk$$lc= z(1ZV4wP(zqQ4M>>yyARuzOCxqGv?tr$Ct#Heoy1pZarh(((d(c&^c^o_caavC%J zxznR=T)cPhs2eG#F)6ox?DWXza}S&zdA{M^(kIML4f@f?Y44mK{to}PB);@M z)movBBY zu01R7{{yx-|E#?K57_#+v-18wVAs}X<^6xaqjx+j@BagCT-`hG{{tTQb{YTcvEC8$ z<%Hhxw_6AGjy{XJ_l{%TcWCd>kb0f6ni-3lVKu{QhSdzK8CEl_W?0Rznqf7=YKBwI z&Sz@Hgh74d{^Z1x_no{y>HT=$xIg)7Vc)nvX}+Rw+@Flz)Hm)=&e`_txIa04=dNjZ(_d1(KrGaKp*iaL{W8uQe3{i4o{UUz=fnUvF*lsgRX z7j@>13;IQ!x$FFXQD%=ygTIe=!ZJ} zqs}-M@|LnXX;&w#PFS6`TW8csyE+839A!Mb*3J@fAqk(PuSdQVB9}csWmX} zD^{!-5ceCmygeZ9Lz+G^Ans3|A5+#ouuob1Q5^Tk;GM87&= zb;9a|)d{N;Rwt}ZSe>vsVRgc(PUkK4tn!>xm& zo*XiBP}GxKUKteiWY|9kMLoG-*`TN=`+hwr>dE+T21Px&bmgF^C$&Ev6!j!M2UAuv zV^K4#W?0Rznqf7=YKGMes~J`^tY%ovaH@IcFC7ZsZzrDvK0d6##H5_Yw14lg+>+xC zDdhZ@nMV}9uTFf*Y0R@v<#H#j&7RM|!@th{$K>~%#>hXsl*>JOe)hMyFLSwvS7yh3 zt!_T|@p&27>6_2px$fYCo)$0WbLA&xd`q+Tx%mfWe9;5#b9-$#s1S2QqYk-suVsAk zBOP-6p2&D&+m5+rk7wNGxsJJ`=4bpuai`oN-)H>HGbP`PYnJu7WY5ELlds75z%hsA zc3GOSV<#smn+Mt*7wouT#|1ks*m1#*3wB(v*D_8+}p>-{YlDc%&TvYj{B2a4jmi!Cn={f zYln`G`;#S)jEVb`l+&1$pBXqhYIUW4qoaoZa?a?e?T?&0I%@v5=Z}tSLFJ1^$2H=T zOGn4GqtU3*aZP!3(&)I>RJ~_(T!SXf7#-K9pZ+#Fu33(Y9Hy*h+SLrJ8CEl_W?0Rz znqf7=YKGMes~J`^oN7+J`}*YTVr_C@m+NB9GPn4;Sj)V&?{%@pd3E>eV(n9ZhwEZ} zbm*^Rf^YeLOvFt7bWHs1eQ%A4J{!I?CXO|D&X~}U&ViKG%vjV6s~J`^tY%ovu$o~t z!)k`r467MdGn{I6o)_v&*RgRQJEY{h$KKyo96UDedw;#U#7#sJ=oL}BQ zH@J6f+*g0{U`c%G^Om819vk=JwEMh;c%QeV=V{97ME}B4ov=D#b;9a|)d{N;Rwt}Z zSe>@}yd~B7^X6-!&V1f_WYn3I)0h#9uZlXe{fE~^ok=;3`R8s|MV&eE@a$OVNjZ&4 zxlgsLBA?$?xGM7ee7UP4|Fr81@vejDM<3sAeO37TaF>$!Qs3|De^tzfzm2~t=E)9^ zUlsGmv7k9+b<(a*Se>vsZFe1{PTJK8s}oiytWH>+aH=!)sP~#{;#{7&@|rluTYq#- zocsCLuZfyaJolQY6}LWoP1KM%x0msDW6NT;8D93cb^Dd|dFQER$NHvgnTFKsl-0~w z)C{W`Rx_+-Sk17SVKu{QhSdzK8CEl#YIZ(TPd@+Z+PKzq*m!MRgI=pLGOkVA?>sWD zS&ugy8P~GYT8xZq+#CCkjBDRN4jCEO#3uQXajpDk3C}$(`#$8G#Uta|TJNBdam`K7 z&6L&5Skw%w8CEl_W?0Rznqf7=YKGMes~J`^oNE58+3=_{k4+sBbtdIBrhk=-qs~-a zereR1l+&13PZ%0?=9U+S#r;gmX-vw;b{ZPF{raGxk@FAt9~xe?J#c7vw6=I?c=z2= zL&MWIPaPUw?|ISCm;?RC4UM_+|pl6X#1=krVA`N{g{FNxp2M^o zc1b*kdF%MH_A6SH#rNF4te^8%4U7J7e1BLRH}ySbb)sLLusUIN!s>+839A!UC#+6b zov=FLRHyTqIy1D&h`8>&(riRrkG|?MBCb;(_a710ui2wU#C47H$m`u6508lJ;B8Nq z#FyT;ygFw@TsLX=zJ+-2Thj9}Wp$!oov=D#b;9a|)d{N;Rwt}ZSe>?e-;(OQp>2n# zC#T)tDe6heX-wT3xu_>kf7dbUNy=%=#itfWJ?ZpXKI%!zX-vvnx)et}xxHg?)RXIS z#Zgbb%oj&Jd7yJ~)RQ|;ERK3|dEerwC+}Zc9QCB`l;Wr-_dZ@6^<+lLJB>cO8@j4E z>WSkbpDC-Eb~VFlhSdzK8CEl_W?0Rznqf7=YKGMer|%CBl4 z_cQh1X&?79yFAf8?q^<`*go!Os$5XUPjxAad9r!g-@aX~tk1OcveUc9i=^RK| z&5T9Ou$o~t!)k`r467MdGpuG<&9ItbHN&Z9=Q(wzVU12vXNH#i|A_0OTf29PI&=My zlK(3yy-)5lp;Ocu&M)iC+fQ_gI&;{(lK9d(bMfCgMV+DDIzzm5COuD6Rww$^39A!U zC#+6bov=D#b;9a|)oHtRCe?X)zXPJq9Q{GNs52?2F;x$58+GQP2JNEGq@2d|ozy1k zOxs`gi#n5X8k6#mSGS3LUUo^F$n()d+eH3p*B9blAJLCK_L|-%{5{}>lK4{J_bz#- z(f1R&l)UTcJh{6;+n7I&g&d}=PTJK8s}okI?XHj1NxM2>b;9a|)d{N;PIaapjp}wl z+$a3?pabIm;ptrui2IY9H}4vsVRgdlgj1c)Tk1xaj_u-_vSZ(p|NAI? zFK&;K?cy5r&^_(q+Vt%+?c$o%>8*BgEo=OFyST>f_HDbk_I>(eySOH{`>9=AE1Rrp z7uV1QE84}iH9ZGYRx@K!GpuG<&9ItbHN$F#)eNf{Rx_+-Sj}*%dBC*hQBMxuZr`XU zDW@?TMl_9ja@$EQqMoFj#&mn7Nz{{uZJI?rNjZ&4`HMMCqMr1Bv`N&HgCA}Z^@Mio z3Gvnw`mvrI^Kp}?Cwr|ei7%}ub$4tU_2iH?O{1PnIH_sW6URc{QdTGJ>V(w^tJ8Mt zi8^UlC#+6bov=D#b;7C6)T7+^=5cTE>5%4e&+x@5&Ex*$*MpkJ{mI5%n#cXgUp6+2 z`;&itP{y}D)huFey0uyS?Tq2gqR%ILHH%{%cX+eVkb0f6ni-3lVKu{QhSdzK8CEl_ zW?0Rznqf7=YKBwI&S&aO(Pb@SKAbqMMa+|7FSLmHbKa*dVqSIpxkb!3&LijHjC%XV z{A}EK-^Js(q6C;HV1s}oiytWH>+usUIN!s>+8X}k9)sm{|D zH;8)DtbL=XCn={fUp-zw>dAHE8%8}zIgRPGX}72+HP724>PgCJOv;PC*)8(f^NZag z&wGEiTjZa1>k0AJ6Z+A|Lw2Yi{_fPYe)wLsbN!eP&CjbJ^W^gJ^<(}x7IK)fI%!uY ztWH>+wp&lsNxM2>b;9a|)d{N;PIaap?fYVbIG5l2OM^Ja-?55J)+P1C+`u*%3roeXh^+ISV(w^s}oiytWMjl zC#lY(tLz;0WS3!eqn@Ok#(cQEX4I2mFV=~Al5!f;cHf#&Pm1oY9rYyTG$!R2cdr@w zJZh(!k>_1%){Okqt}nz}Pv}PHU7fHxVRhPWJy9p^>V(w^s}oiytWG%9nR;~MPdmlB=b;mJiuKOHEy~)z-KH%5A79swe%@bLJNn=JMC~|k>Tk;GM87&=b;9a| z)d{N;Rwt}ZSe>vsVRgc(PUkIkW7+aL;d`4Zbz?qsZ(29z$q}9F#{BtH@47LsIA5G^ zH;%3w^RU9ilK9fP(ROm(n76cBH;A`xq~~4A>O{XfVRgdlgw+YF6ILgzPFS6=I&HUZ zq&g2ibi1e<+dNV&>PE_G%s=W@jk{})3#!v5T6LllyG$!Sl-Ks=B z4?4O^?8H`GbHI$?Ff>V(w^s}oLjrXE$>d%L&?cy!0@;@)89&)dd5!yL(wo@BPaD_KKa$`n+b#HgT-oS8Nj+Qm<21GhSn@&rhlr&ri-7QZ1gJ z{Pl)v@%*Id{%Z03WcicT;`zxZf2$VHPwsl9T0B45@M^Vqe)6xEtHtw^kGPtfGbyJr7u>Zues|-f zy^EsGq@2byZnY_XcVoeJTjO^(Qch!1Zd+?p{MNvLa+~5e2#(yiF@Bq%+?I{;n+4Za z-4wrNFu1{{_>F@$9XG{qAFLR-DSi`S;JusTw-PS@XjA-#!fiWmj^9>j*kg12=7QrQ zhbgO>b~VFlhSdzK8CEl_W?0Rznqf7=YKGMerE zqFV(w^s}oiytWH>+usY#Xr}LRQ^YXDpaoyQ*a8X>3_M1`^*QvdpD2nS> z`GrMsUE@6RdN*)YQCtU?Zzzc`y>F?tr6{hOw0qw|y!S2X`Ixdg(XUQeov=D#b;9a| z)d{N;Rwt}Z+r4i|b+$d`yTUn6-rjBUWBiU!%4y6ol~zVQ8Tb6E_#K~=)0m2PE{}Th zz_72Qo}`?{q+I{<0ptmW}LKD6r#@!q%4k3OzjusnXp=dT+|;!E#a zCbnG>zvJ`Xuodw;J{Lc~B7Vomv5>=*)k(WLVRgdlwB7p_b<(a*Se>vsVRgdlgj1cV zM;#k}7w7N9Ro}*W{qU@B<9zRX(YH|t=I{M&)Q#`H_$KN`t*PHc`;Zg9iTD=Pzlna1 zc<<}z|K@wYj^n2OrmRl%tFti1Qk}3mVRgdlgw+YF6ILgzPFS6As?&MP{6DMG>hQhj znAI^Kj+nSQ=E*(_SI7KW_Ur1HSDY`-w`V*581wMYJ%5b(S*iDrF>h(NZV+$XNYA^J z)ro#}!s;xHu~a9lPFS6=I$?Ff>V(y4yLBVgd138F@%^P8eryuoUrITRS$^PN@%^P) ze{LGzUrITRdE<V(w^ zs}oiytWH>+usUIN+V1z4Qk~|L`TviljpG}Pdv9nQ-)7vi=AQA*#;UFMjBhzsJATjj z#^V`-_l)mA?s0P&Uo@vIX4v~>f7|1yvOc?4+bfRsbmP53gYyCXDXW=wHN$F#)eNf{ zRx_+-Sk17SVKu{QhSdzGnw`(&bI+%m#(cQ@g{Co2-gvob%pcmFSH%1OKJ?=}oO@H# zn4e28DTy!rp4$&Sn#O!ycwp0*=Ob!2jrpIRk14AY{py6(39Hj~|KCTQw5td6C3>PJ0EIgNSl<~mVN#+R=b^(5sqCOy`? zCUxW6R_iL4Jin@Vc;SBl|MgX!_!icgZ`6rzWbHbuPJBCS{@r!rn_A0ms1x7X`sV67 z@eQuMN7RXLbGvsVRgdlgw+YB zI-SqtZKrSRM?JY=ZT+Yx&;49K>Iv=E6XLBW^kY5w>#Oyno-BH_B)+tse0pR3s3-FV z){lD9|ET&=Ptx--Wp$!oov=D#b=qz{Q77%{gw+YF6ILgzPB_(h+*Q@0p8U|WX4I3E z)0p}9*NA#Dxq7XrCn={fkG{5j)RW5&s2=qs=NKOx@x6Sa}Il+{VQI$?Ff z>V(w^s}oiytWH>+usUt`{v_3DKAHbRx>S$z_n334$9bI}RXxu4KGUm5-I(={>QOg# z|Gs+Ejqx>VMEjDqH6s4k?lq#HABWV4{ufTD5yy27pgCoA(ymTeov=D#b;9a|)d{N; zRwt}ZSe zG3l}1n^+X}WaNONs3*OTE{b|`!9GP%Pj0SR6!nBYttU-Zm5+Mz#ESA!Pp(~7KI#eW z))V5bCu$>aDXWuqb;9a|)d{N;Rwt}ZSe>vsVRhPWJxO(%PtJ?muBsSojg7Zfj5Wx* zCo0Bz=fk%v#(L+|RTX2s)1pSDSnsTAUB>xtl_KV_p_Srqn@p}0eKvZmQXFf{f=Z#m z`GEeE)l9pZVKu{QhSdzK8CEl_W?0Rznqf7=YKBwI&S&zuzFXCp4+BoG8uR3?-c@7% z(C&4Lc<)c>$9XueW!0FUGj}S9FTFo`enXX*&v$%KCFc22v#Z4XPtV7c)ro#}!s>+8 zX}k9)>ZDzrusUIN!s>+838y-Hy|X&LmvYD0P4T^yl+&0_b$-tMd{N87y5q~AHpll; zQch!PpR=kEgDRQATUW*RCFagw72lnxG-*|Q zkAgn+u|?-q@%@VSZA;=y?@yNPvnsxKLA&*YcV(w^ zs}okI?bef2r}-q$51zj^*L>5y1&>a-XKil&vFZqW!$Lmy4*oa zS`^~9Ji0D-*;^SeURTzB@geIYe(sg)qn~@`u8;mt{9%0@*ExXZl+{VQI$?Ff>V(w^ zs}oiytWH>+usUIN!l_Q@EqQx=$1UOeQ;oO8eAub^mY65BJAa6`ZqSeOZOv<&V;&aY zTCyitS~pJVxjE)-%{rT7J`a9pQ_S=9yh~Y~=vODKPFS6`TQ}56yE+839A!M zbsl=~lBgRa)+~>@k#ZW-=-Mx$ZoJ%UWz>z7)0nkye-w3N$|Ije-AFl&Nso2*nvWx& z3m*A6@_bdlk0bw6_xU({S+Vh>@QXh6vDyvsVRgdlgw+YF({}4ds?&Tj|G#_Zv)o7Jv)VrMx6g8y-j~&fzwG~c zuGeuH4;uV=Zd#3uhd=pw?vs^St=MJV=ef4;WPI0wOM`QlEsdBX<}HoCt@iWM=(Ey3 zU&OIqKlO{y;Cw)T%4()v&9ItbHN$F#)eNf{Rx_+-Sk17SVKu|4X6JL^dN*QaZo>=h z3w8Cf2`h7dY2Ts1({5RroB8*QS597;n|f@=Li^dHSLVKaH{**3uFN$!KKpI-*+;L; z?eJ>GUe$Crr=Hl-0~w zW|eA&)eNf{Rx_+-Sk17SVKu{QhSdzK8BR6tI{lTXGd)gwJL*izX-v^~3!~25|Mx{v zXHrgM-fOoY>dfHUuSK0nIgLq=b=YaIM4frC_A60m&RD!4>dd9LEr>evN}mN$XXw*9 z^ZhOhqR#wQxg@^y{^Y)L3!=`@Zk-|CI-@r7ma;l&S0}7aSe>vsVRgdlgw+YF6IQ3~ z)|phN`Q*IllY1@h6Luc*THHVUGUK(lujugOYjMBv%Ic0Uyu1;8;usUIN!s>+839A!UC#+6bop7qtc}w0V zFJBb(!PS9uWnfs_2jTsi=v)%|6oznlPPl+MLqdq+@h!_Jx*B^_2lT? z7ezhU_lviqo;+~R+fh%_b1-E!GZr<&YKGMes~J`^tY%ovu$o~t!)k`r45ym6RGS&~ zq}{8}Mm-F z)8+B-V#|(?hetz~&Is>bo--pn{cXyO@VfftGhz-*ykJJmjStSB5p!nKkQp(T=8u^X zb4;D&Fl9BJeChb`tT^9){$y6vflunp zj{5MYQ)frrn1A2ws55tbGdt?c;5Kujz2=BH5r4{abE2Q(4RfOZHO-!i<2pCcnX)=* zS0}7aSe>vsVRgdlgw+YF6ILgzPB_)+d?s(_9XBtoFWvjhi|fwpe)HmbM7!51;#~*P zkJq(HmFLCv?vurH<2tzhwz+YAe4_i@xNcV8VQySc)AKQ9b)sLLusUIN+U`0?owTbH zRwt}ZSe>vs;Z*06;dewmsnhbos3$3>F)zPxZ`70CcTSIbl5!d|W&5d7Pg;F_chr-V z)0p&F6+839A!UC#+7}y+28Hnos8c_#LLj8l-FSv{;*T z9y%@7EZfhV7HgTER!@sH&aS+`M>t z%pcmVC&XJ%=*M|@;YHJ9em-|-Nqp&Zm4B9-9`pI87aojxzIynBG5^!^F=ch4U!AZz zVRhPWJy9p^>V(w^s}oiytWG%9Id9phs3#ky-Wc^H$*dk!m! zFJ15CawB6t&~7~;-g=@o@|LnXX;&w#PFS6=I$?Ff>V(w^s}okI?bef2r}8=l=I~uaBCrzQ^@ZD{jB*`lu(nEG^^b|1>UQUOj7E{Ot|X#zmi_ z-WwOkI-+QNXmCEDKV>!3u4Y)xu$o~t!)k`r467MdGpuG<&9Iu`RI~G$eD2j~Qp|^1 z2TY22GUU)nF@I=xUJ-9Sp&#dA*Ci8Ue%|@e#F)2p&Yu|b`NF0XW1hdg?8cb?>G_zl zI?=CASe>vsZMUANlXi8&>V(w^s}oiyoa$_Id#|V`k5#%T>PgCJOu0S#M?ES2bV$^b zl+&08Ug{b3Wa;p}QBP7%W71=ds?;m;+2PXDBG1pPJvH+G{pF{IFQaOo8h+8IKE6M) zXZX9hSI_YMkmGyCe4yQWLcH}vZR9Owb<(a*Se>vsVRaVbOLfBPgw+YF6IQ3~){|7H z`DFgT^hV!UUo>rdcC0(rJ#u!eN3LplPOMX2dj6bPzg*b$+*sG_@x{5(e%1x&Mf`Vb z&WnDY?%yx^-{akWaa`vBnp0LM?dpWp39A!UXCb~+C#+6bov=D#b;9Z_#3wqPx8!a2 zorlKScIF{NW6it1%g|U0kLf%#*2trq4~@0+gIk8gn)*-A4vDq)-}(%RHTaBQ2gllc z(hY-S&EB*6;8@Fdm~c_7@zZlKWi>MvHN$F#)eNf{Rx_+-Sk17SVKu{QhSdzGnip&w zpRd(2+arM29MmjF%P))=r_j2|6sOxb6osy=9ER_;(sM}5KKk{z_}|ZC z*N=<;37uS_BoE!P-;AqMYkd3<>1B<^$N!c(F2?2Q{wvO0y`Es9gF7$xuySSf6IOk zh~xU*KlJ!LKy>M8zagVbn`sG5^gW=Y_fDd@<)97tJZFfp#^(YJk-Ms{vL6tOi&O zaH_#$alWMI`0v@A^e$I9x2byO^-)HI-=8np_ zaRW0R{!QiFZo6gtVCO2i&zI~~m_Ku8RLQ;hNXAolt(xm~W5!=isG1uxD&qsTmbLFR zaGQv4{@ymx&nd08js9P~X4^P!(fn;gPwk(!4V`1EZx{Lp?Xq2ri}s_g&BjQ4lhqm1 zPjTtorvLu4vw6;OKdjKaFc$Reba=+-Y%(lk^xr-uW5#vu-5E1p+sT9RkHqLBtdFoh!ukm7Bdm|GKEnD4>m#g>us*{22m#g>us*{22s^`zind1jBCc|j2W-( zi7uCC}=?FLmOV`ti$g(LQQqHb&z6{FpKQTzblZ1m#g>us+&O9*ieHus*{2 z2!a=D!Fcim>m#g>us*`*A^)&G!ukm7 zBdm|GKEnD4>m#g>us*{22&X=7o?Y^cvUFYZz{@578&G=R)#}@leaF(ZM!$V(2m=3@i_qf`y7Dd`Wyf~J_kUj&jHZya{$KWa{$Kc zbAaD#P@5VY3mP0F8elcRYJk-Ms{vL6oNDk`?P`G40ILC31FQyE4X_&E|4IXTe3n8?%4$nv zV4pj|KJ$Tn<^%i82lkl{>@y$OXFjmcd|;n7p(o{3n;M8w1FQyE4X_$uHNa|s|0@mZ zasK#Rj(D}DF^+}W3)4R}8RoduY8XA#a2TD`b{PHCe3)@jhhd)?!sLN#2O3gNwJ{bn zI7T$UYJk-Ms{vL6tOhvMz}!H?|DB#RCS~R!*Bbto`RN#$w~n3pY)+Wx=8E}m4mmH( zE$53l|NS|xcWPiPYJk-Ms{vL6tOi&Ouo~c01NW{xXJd@q7xA18=6;FiY%upxJZFQs zzv4L?%zYQn*fwG>o!qagpZitEMLW-DI4f*MjMv=Up(zjDDV{!HkRN zY%t@soje#%e(Z<5*+2R8xa3(q_@z$#Qa^q*}V_@aK!HO7UH|Bm%h z-^mZGkFY+%`UvYItdFoh!ukm7Bdm|GKEnD4>m#g>us*{22m#g>@b7)(xearMcAitg#PfUxrXQYb!Sv7bE|}x; z91KPe&&ObN^4ttYKhM)(#>I0snDN?99*ieH_Cwz6pL}{;@~j^GQYU_?AHN(I?L431 zxWw~(2BsgLYr*u-^Dda<@*E6C56@>{bn@H`MnBKfV8+FBHkk3+P9BUWKlVf3?4Nvk zT=J|Q@~=*OQ9tJzAfp#^(YJk-Ms{vL6tOi&O@b5J^H&PA1=QKv9AD*E(MxL#~9G7QqFnV|v2cwf` zbTImPb_e^+8TOeoOdfb9hUS#fh6cxi2FHj7SPifmU^T#MfYku2fjYPTrknCF?yy^- z{i2bDmbE|e zV_E!wtr^o#*X<@3^w9shoipaR<^Pm1diLHsV{|renKAYI<2D&Ht~&c=O#QZ<`fWV* z+kU9u_D}uxxYTd;P`}kl{Z>EMUdKhd<0ala(2x0{fAhw1%_n-yGdj&b`t>FCOa9m6 z^$XW4e1ypZ@vuI^`UvYItdFoh!ukm7Bdm|MlLzC;53G-{KEnD4>m#g>us*{22G~d@0@>b zEY|lg9^6#yd^qTg&Be}>+P`fscK%Gdc1yAIYWA`%#m=`|cKfB+dDySjFU8JJ+MTz= zJD=&tc~1Y%e~#;UfgaBnbb214-}8%cdEU+2@8@XW+GBmhzdL?i^fTg}wbB2ymTTj< z4QKomdbS?(Q|R2i=1-yj=&fsFT(mo0;>`p7m>>E#ZyeWrqQ^X=)BK}fUsAv1)JIq! zVSR-45!OdoA7Ooj^%2%bSRZZoywgY8^%2%bSRY}1g!K{DM_3I5dAm)tSF9qV(+5R)3ahxPMwwCEFb!- z&n+M0qTTTlZyxB!{LsI7m#g>us*{22Wy#zqxle+Je^*qv9>X`DSfOxz zh3CzzP`JLrP0Cd)TwmdHI#euNU*X|{D;BP=@K+Nn7Ot=GyHhI`?i+09e!_U}Ghq7R z{sX3e?n_{f%l!(B9`0jcbaFogqo4aB_~?>xaX$oazO#I^@7AJx#8>`%x#(v}zjD$4 zz`Et)xTin$kNItD;r$=mxt}ne`wWM>*?Q-fPtdFoh!ukm7Bdm|GKEnD4>m#g>w&SDm_z3GG ztdFoh!ukm7Bdm|GKEnD4>m#g>us*{22m#g>us*{2 z2oE@>Qm$QxiwizJ_qR&9hFvngqj}}rlzth{oKo_~`tgf8<^5cw;YF{OHe6wMN zzrF6-D!D7hW<2%DD!D1EGTvrUmE1+WE-A#U{isUrrMEJsy?TClp`G|29?O`1D%8HT z&`$p?2WQN2r@fppdOj%{QHVk34{b6=|LMnP%(#v?HRIhrsTl3K3o1r@lgbsNpDhnp zi2iTvQ6Y|de4PrRC-+rR=zRP2qR_wM#iAG&?T(jt^FTl5hyKkQ$2FhmG0*5U|LE73 z)Gs;p5!OdoA7Ooj^%2%bSRY}1g!K{DN89nyczlHQ5!OdoA7Ooj^%2%bSRY}1g!K{D zM_3MVVY|~Z zCO`FW$e6sH_GZT9^Yz{O75yer>lbWBmH2YyUzFejW5u#0}Ac*|JS}5bKIThWQ?Bf>oZ2@xqA*Q#H0U%ju|tqmyXGp@!C!vj3+<#L*DG4 ze0tnMo=f%MmpbuF{rKg$Xm`BCn+N(aKlE?jIIj6bk9kI?`A5ILq<+b%kFY+%`UvYI ztdFoh!ukm7Bdm|GKH5$mj3+;^KEnD4>m#g>us*{22ET2hm|LObzGCudynePhP--|*x!3Naja z(nA@e=dG_YM(5HxXBJ}c>$v?hW?Tp5GiJQDlLzC;kNuE0`zN0sw~*&jJ@}UVYKG9>I(P{qCuP>=za_S>Y9*Bqa5!OdoA7Ooj^%2%bSRY}1 zw4FQ{Pkvy1g!K{DM_3paDI9shcr6_iCIm`dc^8m~q|IBI7%c*;Lm4@P>$=SO4ee zr_J1T#rA*Un6ET2HkFY+%`UvYItdFoh!un`CJ{pgYus*{22m#g>w&SDm_z3GGtdFoh!ukm7Bdm|Gdq8;Vz7Ooa z5A41V?7k1|z7Ooa5A41V?7k1|zK`vmckcVp?!FJ~z7Ooa5A41V?7k1|z7Ooa5A41V z?7k1|z7Ooa5A41V?7k1|z7Ooa5A42=?Vfk;`_S&b5A41V?7k1|z7Ooa5A41VocblF zKEnD4>m#g>us*{22m#g>us*{22gr_krE_f!+6k-S>gr_pzP(3FEoXfZg|j-S>gr_krE_f!+6k-S>gr_krE_ zf!+6k-S>gr_krE_f!+6k-S>gr_krE_v7P$~gr_krE_f!+6k-S>gr_krEB zOF8us)<;+$VSR-45!OdoA7Ooj^%2%b+wswOe1!E8)<;+$VSR-45!OdoA7Ooj^%2%b zSRY}1g!K{DM_39`lS&^N)UgN&S*jA7Ooj^%2%bSRY}1g!K{DM_3^F#mUjpLe6^q6OKnt$}`OX`=L`UsN; z;$eM+^%2%bSRY}1g!K{DM_3J2#jCsbJ@(VSR-45!OdoA7Ooj^$~Uti23Qh z5A41V?7k1|z7Ooa5A41V?7k1|z7OoakL~RH7|*^B?7k1|z7Ooa5A41V?7k1|z7Ooa z5A42Ap}ln92X@~FcHakf-v@Tz2X@~FcHakf-^X_LeT-+{2X@~FcHakf-v@Tz2X@~F zcHgJaUb^3!a_S?jkFY+%`UvYItdFoh!ukm7Bdm|MET2Bx@*n5vq(V;gm%QmOtiQ1S!ukvAukHWI^VDl1$MQM|dmV(m4#HjsVXuR* z*Fo6pAnbJz_Bv?0_XEUxpWt~#?KItY6mguM>h{-3^|`D5Le`St&mb>AP)$1=bEzwmr4eJ<_uXU=P%Kf^wMhJF4F z`}`U9`7`YEXV~Y@u+N`u|6?EFzrT<0$9`+$!kXQEI_8r5bg=t$u={kd|1SxOVM|NZw;dUb-%mIrm`K zaj@$(*!4KowT*8ti%vcD)9>UV~k)+0J^+`2V;6?|^Z!UZa1;%l-~b9@r;>$q)NSFnMEN2_~QH zH^GHGm+aHQ_~rj4;g|ofgkS7u5kvbQ|DW~0_WxO|*T^A$v2PCJ7yIcjezDIE;}`qy zFn+Nw591g6^)P<<|C{*Y|8?RQ`~Jkx{>T5ZW`3DZ&Uf=n9WejY2Yqq9Mh;!C!LHX} z*K4rrHQ4nU?0OA$y#~8pgI%xL&i#<_+z-LNF9iF(5bXOxu?a{~Y%HbJ+LKVc$Q8eg7Qx{d3!S|J-=~?*sPz zbJ+LKVc$Q8eg7Qx{d3s&&tcbVuowc;%k>)V z{+|x)|LMT~pAPK*>A>jZyKOM~`EDER|LMTgC)=q{#`}Ld#Q1+Yu>Yq6`+qvH|EB}{ ze>$-Lr(?T*5wBnVpAIqppAPK*>A?P<4vbE|+Xkbbbu`Rx4>1?nYlB(4!F&VLcGz~; zYs9!-gI%w|uGe7KYq0Az*!3FhdJT5H2D@If{g3_A|Nj1|>os!ddJT5H2D@H^U9Z8e z*I?IcuxAMcs`_un&dy+#gQufeX@VApG~>owT*8ti%vcD)AUm+z;! zUbFp=_woMM-p6CTMh;!C!LHX}*K4rrHQ4nU?0OA$y#~8pgI%xL{>OXEnP05e$cgJU z*!3FhdJT5H2D@H^U9Z8e*I?IcuowT*8ti(__W$Jn3%g$9SgzM#*K4rrHQ4nU?0OA$y#~8pgI%w|uGehW zFV}0dyIzA`ufeX@VApG~>owT*8ti%vcD)9>UV~k)!LHX}*K4rrHQ4nU?0OA$y=J?9 zxn85)^&0GY4R*Z-yIzA`ufeX@VAo=NchohS>>AB>UV|Av%mfHKlOW09QS|fH>Noj zzqjjLN`I60f9iL5(eS_H_mMfSzYVPh^YEYi-D-|??0)0(n}5n`;EG9QeEG-Y@&i9> zUZ{=v#pCjW`(}LOTjTOCFUx)(YV;f9@^eqixXqj6^6$K#)$J*Z#^uKzpYg{jp zIIG)RKO2`n?evTv{d!#f)pc2|K6d@M{GoScJh{U7e64O7*Qqr=-(>fUFKaYD|KYEh z&YJs=&re+3s-SJb#*+A!EepKQhVl9NFJ*kuPvi3yyJj)Zd|MWO@E7Crrykw95P$4@ zCGk&Y-2IjD`RSF~WPQ#apC8;Q<9ZK_&v)scG5Oi{l8k3wS=L^8U|IaI)5`j};+V4j zC*{kIi{>>4WqG6jXMfAawV>pXmzrk;YClfBpO>UfVxjp+w4qtksZ?5^KeG55k+V4lkqM~%lP>}jfKIYC>kFc246BV zbk18gDt!NP>Zr1Lc;cv-hrd)G74vZC_eaJ&>~r79n1}S~JRE<@$e4%s999xvIuCQX zkueWxcODY&Jlrt##?Z4@qe;wrlSKjhF!(GTtRPrUOVFVxd@$;8lk=R*@i|D5wD z#<(tQIx)uk_Ocrz4==xPZ}`~z&gqf2R$t#8?c;Zt7P;+OJS}qGdFZt8V*8oX!lRv5 zPYds!ZGBJpd+@L_{`8r9B4*`=d*W{&YkP0>IlceAajbq*?+p!8wx1e0mkhrn@>!wf z9WkyxUr&wk?)K2s$iso>PmTPHI$&z#jXuriqd(jpd46HZ?UDa8-@iS4p~PsE9$@}b!JC>_|vJgqi)Q=Boml>~xFCBh-E&TfOfY-yvc~`$4 z{!V_ati4V3g%N-02@9j2({EfD{qOkl!Z_}G?G}W#U8lbiIXvvNS7Iy=)_x_%c*f!d zG4@MuTM#*UrO$%M6@8k+?{`@cx&5tjNqlKdzOUSZ@Pc;FS>iosdz|)m=$X8HQFwjo z&x>LXT)A~o%#ByKEQ&dE*s4V_m%4wjDCXFdIg4WMeKBrP%*h_7EQ+~$^zMsd4)6QL z+cCEvxaaMd^Np_kB7A(g*UHG@lt(^`_V3>LENbJ--#&|)`Ir4ak6Jot@aIuuhd=pw z)ZSgzeIE7st^=0_=Pp|sF-Oc>8h=~u=cUnSrG37LW4(Ur7olP8+aHC_Ll0gOxjlQ$ z$KmyYM?Ma(uj==4cs+HWkHhN~8$SxK=~J((J@HX^-C){B;q^ zqW$Xd_uj3m!r!^`SB1ZoCans8=~I7ObY2zywr^V!UwSSt+hzmSfx1Dm<5$W!=1mD51qN$MS0h8?@cVqyN(+< zpeXM;uJ_SJdDn3l>{FEY{^aJGMS0h8^l3hutSX;3&rhr7-&|cMa=!P7I^o4z z!|Q}cpI=@lyz4loPI&rj5cVc4$m7{KjwD-qw2?;Uw+_T;p417H;o+L`DWv2|HsnCQ5*N(&^T)5 zo;CN3T3WT$o>60~9lvMP-ZKX88TEOOo6Gp3Ib|`!-Y@&x9zT`!*}d9cajd5s?-d%} zIHO_cys&no$Y+Hg8^*Y1zu7Rxd()#0BM+C|JTE)EB);@q zezIf3@P&5IW#T=TclfbM=-KnBrqO=)3r!>bjhCB7KeXFF@%oDw>X~~})6lu}l9KpR ze}CxFG{&{?z@{anG*`u6XD2oX?-@U%ou|WsmInbE|&KbN9WG zJv)8ptmQeMqtfm(PvU(RN3V+Z8#VwZ1oOMb2li7eBuu z=d;-dhJBqI^5mg~XLoIn`7XF)!|!s%dlwhlC$9Q7_s~rlKRoN(+}ITv_r2)b+(`{{ zg_!w!f17K0WX9ip@l9@3_l#>z{U+LnobXM=x2XP2^mD{}Uq}Bp-}`kO_uVExMy}4P zv^q2w9kV*da>T^dF~)rsu8y%U`*n5XgnrD`vz>p89R9iIkCEF-y?>0H)2(K>w zZ4Mt#+Pf(B7aF(P6gu11+LUuoVL-V}IrkKf+_*94o}4L0T6 zQ)tt1Q_ekw6$3Zr+*25M@1~r43YUMhDd(QTZ9A9TAC~SZH0-fC=bplX?Y4%e%?6jt z>vij1b;hcZp2W~j8bK?hWIIrJv zAGhD@P8bLrNL_vV{!zVVu$oxSjtzrM+uO}@17Xa4ObYd(GR#e4G;SKVaI#rI$MsV~0C znw=lI@Vic3@1q~K{+uK4z5bs)^VaKM^I5;Y@qDa1eE-IC4L81g)46Xqx%H;=bFR;? z`}aLxtKWL~rt@>LW1hU}{JiXq&)sx>j<&(8Hl3fZeeZ3X&d=Sx{{Btp=W&1c(M{*) zbieu7rt|Z=AAD%j`MKUXS8X~!@B8ZaHk;>r>IZK#-f4%;=9)ivht1|$?{}-s=2_o% zv(4sNcigk?e9yYq@vOJobF+EYe{uM_^Ow*1w@=?}p7rh4{d=JA&&Pjovw7AVyzG|q zd>^>st;Y|&?pE{uJ?-CaHSgc^-gB#Y|33C5x0?6wW>3A<8sDE^chIfY`2M`>_Un)T z=*H{M|M(AYIj{5OPu+4}|95Y_<$T=Rp1S$mtM7jAHgnB8Zn*h;E)Tog=JPo|V4rpW z9=QD6|LVxi=brRB?$yO>H=lcWgXgU~fBF91>G_+_J@2^pZ|8geUVFus^BkXj;Wpzv z|7VN2&VTvOE#~}3d}oV!ox6W?i+TNy`?#I&nf5xa^L~H13K*$47o~>+udB+P7KmXBC>{_^?m`KUY2{qMNv z+xedFZ%)74Jku9FeEadiAHC~b=Xc(D*E#>VH{Eq!XV*8}bzZ;YK5plGzP*m?e9+hK zI@f=fU#vTS`E|Sb&F?m!@BMbX+uVnX9)7pEKillM?L5=tU%uUV^@ZEbz5T|Mx0`$Z zoxj;`p2Z*UyWKpa-`;k+d3LY=?Y8rLfAFvC{la%`JLg>b!fofDeaq9fo!5NZqqd!o zb>QCH&Nb}1@eXs}HhB8>bNvr}`S$a9o%(_8=ktC1H@2Vqu*a{rpZnA6xNmQ{-41g< z?{udf<~~2{t~<>A@3`mN`JV4ad+#*Q^mSYBGCt~(9p^fK_RJmU{HH&4$9bIxp0eY- ze#brE&i8zK9oPA&*X}si|JNT_cmDGE-u)Xp&gZ-TA9tMl@UpFUn)|cUAMZWS^o(Qw zdVKD|e?8wD-+14@p6{9OzWra%_tL-p-OlqpdC#xzJl~VQ`u3gYd-CzmTYvm^$FD#C zxBKlpuk#oGXXknS?KazaKJEkmb(gtU`|q*K{F!_6qjs4;bGJHYm-#dIb+6cE{>=T+ zKkhPr=I;5~UFOf+JAG@H`7?KmAMG-K=6>U6yUd@tyIi-+{F!^#pYAe$=6>Y+yUd@t zo8N5pJkxjoc#rW@4qG+X{QLb^&G|3hW7WLQvsbU0*Z=o5tLEdrdY@HuJuiLes=3ZH zj#@R>|K-zG&F8iG3s%kN`^qa;&3$;wXIIVrIpwFT=DzLui8b?lpS#oU<4143`@E0- zxY6$O{<{88cboU!mY?5k-jBC^>u&Qt{lxQjoA>gDPg?JH?Z5ttFMW z*R7e4b<)?@%r!jnReR1o+~#I`&e!TGJMB4N!!LZ;p7XVR!ISr#uldJbwCB7RdL8eP z&%JfedGGA?o^|IhzgIuy{d>-Pt>fOyo$tMT+=fq?=eyDOP8)yhpi|~LAH3%&^Q?b( z-&5vUe|6_m=2`D_pHt>p|6gc|2Soy^<^JCb)N4xw|(09`?q@9yuWVpho{c_?l#|g>bxI+^}eUh`}(yn zdFs5ccRBT`^S=JGOPF^tN^9FQ4zn-g){w-;R5}o$vXc z{>8KAnQrpcv&UcA;;gyO$8LJood4q+oHeiWzU!SeuitSWxAT3k?sZ(}=k9gZT>l&P zUw8iUd-dNPch-Eq@4xV@xetGN#aVNI9=i9l<~jcQck6xR&!08#oh$$2S@WK{*S|e$ z-oI-;`K)>WuDbeJ^ZtF|8=f`q-*>)vy*EC8{W&*&+WLQX^JCY)=1UJ-|FQn_fc4k# zt$Up__w8HPo;_cayZ`p=`C9$NhUd)J@FurDXTG+t*yf!1nt$Z>=gfQI(>tFt?~#w+ z@0@w>+;z=4^Pc+3I{SNxU-h;Qh?>Y0{{MhH#&hx$O{^yT>amw1c=6`(R+ByF( zj$J#i^M_;B&g)*3Nyn zpV;Bq^V~mnhiA`o z-|{b?J`t|*-y@!bDsZ=^X8xZ`_G;?uer@Xoi`urv+Fx{mS#_ef0I$tUG`CzCPt2&Y$;P z$GxvR-}`#EFYUGZngj2*@^^ZFxbgw>^VX~0wR-i#f3f&`!vFfG)vMq1goRiC`|8zi z_>aZ;pV)lO>aRV1;oBUwX7x*dx$Da7Z2!SEtFM2_!k2Bk+v*SBcj1#>z1!-${N}zZ z=REh0yRZJ`Cl-Fn<-4yw_N@y)Z>K$0Z+peUJHB_1)%$&T;Sa3ZbM^gxvhY9tu9=^`UhnB^=4Y~ZxXYUPS?xhTTs=R-ecFdt&(C&`|Jq*ju|D-*515||zvdSE z&d-G(yY;?vZ5{Xb(w*<`rF$0sUix;Adca)6+kd&wT-&v0?laeX_;2@~&*gT(R6 zBkq6Pynlaln-j+GdiJsNb-4S}j-9WEPe19{`8xT#CmcIpKOOgV)%m_}_d31~-|~0I z&e!Mp?^<{M^85DFzjW+;J-_^y$IjRJf8FM|`TAe`%O}ix_A`%u;`qxCeB%6>_`7>P zasI5_@D@*;Ka0Qr^W*2w;>$jF{QOybx66;8Ka1aY-umNDeC+!3_uKvWd7VSKKn znKwRuKJLptd&1nSm)-Y-`JVIG!%mp*MJJtp!hDbV%?nSM?_Kx1@`U-GcG*WynD2F` ze&vMu9{8m1o-p4VclhB6^F8yz|2$#7m!9??C(QTQTYlq&`QE$V$w$mHz4k#zjbHoT z!{?gs_2$Fp`M&qnhtKnU?kf+U=i715xAQ&UUdQu&`R5Ox=lirDtvi4De4nt<5%YX6 zy899He82giBj))&j~QQb_G9LIoM~^_JKEl z%zW?t?SCIR-;?k2x%K|Rn~$7x{{5mO=b!!42}jOrZt$=p=VSf-{g0e$c|f^Q^b~{!#O+*Z$8@^Q@1#$|_wvjB`{8qZ|Ia*p&cFMc z9zL)0*B3v0UjI?2JbXUx8TWa_+^aobcj#R6-+uDY`CQ)pqeJI&eB(xsn9u#(Z5}cA zq}Oq;e!9;i<{lpNkag!T|NMR7!H<}G-f@5acD_G<@Amb5=Q)1--47nGz4N|voj1Gn zzH|OdH`#Yy=Lt97cV55aK5plGroE2qJagB5=lTzM*t+wV@8A8NyzhLzPyE|`=RUme z-TTh{IrwiMIM4BAf7*Zin*ZE??(HZ4W&gS7|N6H5=UKe-(*5Td9rdLB=h^*c-~H#A zUUaAR$M1Lj_2+N?od?eA+~va$oY#NQ8y+|x_xL9sF!$<-|MuW{&+hm?51#kzn#~WG z_w2{-eZahDH$LEidCwkw)B*FJ-Rmg_%zO6!&pKeXW~~Jy8ZmD{L8DipP!-kn*JT;*xPMCKXd>2 z&DNd2{8|5pH{E`IM&EHi>+gI&>%YT$cbx0l^_e@(?|8iOf}Q4fKi+!LPV+k<4}0!T z^SdIKt=(yUhva3a?KHnz^4`bqG{1B5*oW>kzl(B*`|dQqqw?Y{cADQ^dCt1O8}xfS zA6fTzhJJ772A{j%JjXBIZ}r^6_da&lIsT5P?K=1Q;^*%=_y1W}?mExqHJ{&gp6@Sy zvFkkFM{j<=dA^^%|NZ9p?T@_QoWJ_)`_1dz>y`JL*WdW+`_0Gw$uI9S*LLaUyUhK( z)3bM(=li9{?lRB!ZM*L>&-Vj&T=#d0%io3g{*8B;=i6&~zNh`iedhUY@QwS-^Znw# z-DjR}$35T9_k4GF_Nuv_efD2H$KUs`)pPz&{$};OPRD)ybiRLQ?*6-;b^pusT<7&R zU3dQS`ZxXWRr7iMc-`Lt`rX2pUcPGX!!2I2&pf;D-DtnLZ=c?N?>YY4-S(c}lR50r zz32C54moA-`CXm+K7a4|U7b~L+k1Xj=aMh(J-@5-kYBF%t8TT=obwMm?=%1Ga}M5T zUh}*Y_L+}$?RopmHT>a&d(3tI{i%D-{rvsGd(PMD&g=ee(AV%?Z@K4uZU6mm_L#5v zM}2FLc`w}HlY7j2WSgt@nD@@MZ{B0xQ&0GZJ?6dkm#^Jp-h*4cVUKxlp8K{v<~_Um zpnd1s4!QMy^Q=F+)qeA=|FF$|^Q=4WS$Do?-E;A*fAsTx=ULzE-}aqnz2$rMooD^~ z|GV!z>&s8wcb@f~jy`Cf=`X%;@Z7_%|MtK+{^d;{GVh}+?)s2nzy5Fd_YaO`gb_*;Q72ZKKkJKeBZmZKHt?3Ibxpg?eB5KJl{`m ze8fE8y?*z&d5*U@_PDu+e|X+8bNueFK4!i*UU>B}^F8zYFCR1COP_GvG4nn4gv}l| z-+Mo})8pp*^Vtty?=L=e{W<^oqQ}iY`<{0`ZeH`<|MIx`Shu_ls`8s^Ze#gz%=ZW_`ZoY1Rc#Gra>-m~>e=p?g{FYxncE0`}_OX-a znciuqr_4RvVJ$XLvs-HY*uI;<8I$`eTsn0lJp6{L4{e6+= zyTQ7@NAmwN-1PSA{vK)he0RS73G;k=P0#m}-+0nI--EyOq{*R$Ono-)^Y&<)p}zr6kKtIj{Mz$DBDIYnNx7IoI&u ze>`oj^XE@IeeUOZ`<_0Z*Uoo7eLmmKZg~3Khpm5b+T5SLKXcmLw_elzyyo?%&3!)V z73A2_H`JV5k`<^w|^ZHGnImhpCn`h4X2i)$N^Ew^(`kn9j_AFe_ z{r~f(jU_v3!>r8(z_*L`XJ*%v?IOY@qqy!V&p zV}1QEzBJeHw&!0n_w60WeQkc%cg>sD{XdM$-vK`CKfgA=8+_b0*Uaw>|NLRs%2=697Z{^T|DJIqh`&^7bB&9A=Vn)#jQjlXvF zJl}mU{mA$uPr7QZ`HK&^YRZ|5;uHE^ndHq-Ha@Bm?t@gQUuIFY)Ts7DEg=bzh z*MIKiSIy_O@i(uU&-Zq>zIyJ%&g=ePX7}eqFT8s0+hg{7|2*sKw)&^>^?&`r`Ca7) zfB1v*JIs%N_6O&8o448PgY!GjXaDg7^E=XSeCG$|cci~~{QBefy7LF-{Ga^$`{#9T z^!oSD>p%3A_s_?@^!Fc~`?mGhJ~CgcAKL1p^EG^<$9{CawtxKckIvWp-+$qw^Iqt6 zyhomPyN}I#=jiP}Ht(sA?)0&FuXWttPj$uLpz5Z+F`X8|KYv%LX{^Zxp=lkS$yk_phEq?c! zxj(zV-y>Z@mzxwbS=l%GTbKW@b(+BSM#(6J) z;ty{a-}yanm~*y#`Wxn-J!JJ8<~5Jl=neC+Ui!7y&o!KM%$0NBp1kUc`I`LGSy#;0 z>TTbD#e5Cl?blb#*Y;cQcIAA{Klb1&=e=;pQ?H!&$Sp3ua^5?az4Xd?Pd(`6SI&Fw z?k~J@-h+=h=gN6+e(KH7o9DaX(f@aR&h8h_HUHf<7tgc4;-(kRvp(R)7tgcqxM$t@ zo^`L|SwH#si|1M2^_A<+Uw+@-lDp zKIFu?=3j1p;ymBm|KfyszK{CB3G;kA?)i4U=iBRezOTLf#Cg7(Y*LBqvQLtAAR__ z>pz!Qo;#o8gn_d3_ z^BgZa@v!mP+wL{j`Hr8g`+bS!|95uHKkqrObNlz~Ij`Sw&$RPB(_Y7Q9(C4UbN!$G zkG=~*<9D8S@c2)=9z6H24!r6i^GsiPmvwt1%l{wk@RuAo=YQ#z2hQtk^zsAd^9y#yXiyr@|dC$J=Gmo10?De)eeBQI?9CP@*XODW} z;q#t7=BZI-~QMO z=D$NXI`xA2@6+qAy$b|DAjCRTs>E|Gw^1>yID!jrHe$=O^o5 z=WD-T|N8&D(R1eG{^MQFpKE*0+2_xHkG%V&^XI?i4_@~>PW~JJvky6c{@edKdz?Ri zCvfe~=g;32?7H3g^LGfJ+UETEyM@nfvF`VmmTj~XZhQXxUBo|ae*XL&#V2of{`}p= z8C#t{f2VQie?Mog?QsWPIL9|XKv&#V+gY|I^>?U1!g;yYA|<=b3)~Icw+IzV+j^ zbNteut)25v?Y#bTf4X))?j=85JJ++-ch=5zKKUza=lVbYiM8{2UG$!{ z^ZDNBO>5^qyym5ASMJaMyQ!qn?fCz0cjy0iGq>~GBetviziq#%bNXj(IeE>R_3Rw` zO&z!2lD-<0h)Io^Jg^S}Gg3->w~e0$+u z{|mob|8Y0H@g*zgcRjD)eBrM1E_YhE>%Z4_3-@_ly8Xg0ebE1`KmLZ_%=z!x^4Ie^ zJ6`?ERbKzZ^M0|)$NkiEuUqAMzV@Y`uX3F`9rg27u79spKVNnB^B33I@y9=P;m-f7 zM=jjzoWAG6z5cznU$~F^tJ^Nz^|;UXTz8#c|I@`QpKsUyh2Jb}zp49XzbV^q%J!SG z{ibZcDcf(#_M5W(rfk2-@%EdX-`;Ls*%kWj!oB`Bha9nTypMay>lW^MK6~xLUFWxN z^XQdxy8Z)qUbxTezH1h?x7+L6+s*cNv%TGHZ#Uc9&GvS)z1?hY*YWnMoZsGV?sZOh z;=;ZD9yeXMkNf2h9JX>!*Yl!hEZlXjeel9v|1Iyiu>Gc9(|%L7-<0h)W&2Ipep9yJ zl?sMsQdsVsf z+a1m;&wbq$WU4J{sxzDTprrhV-u50c-wD+33KkdNg z?pu39x%=7PZeF?1>-KiD{ibZcDcf&yy!|HU|JR!r?saZ(%hTrd?{V_NecYFSXyLBs z>l>WDa!%LzUpp?`^&kF_h5Ni7aM;3qzK(YvoZtQNI^8#~-~IG)yU(tt`|mn?F0Q}l z)sAqVOUK(6&Yj=xa9(-t%lp&oyKjA5_p|G9pSw=?zw7s0>^JqA_M5W(rfk0{+i%MD zo3j0;Y`-bnZ_4(Y9IvGqd_E%f2T=Naq9Y64MTd%nD&;9$qT5+%Q z!DF^raj(C@=6772|Gpcq{{Gt*?t1=lhdZqt?>eu%aN(|hgO4oS=k>dORD-<0h)W&2Ipep9yJl^F7Xep9yJ zlD-;~>FasBq29QVBJH+h}+U%hyC z_M19xzbV^q%J!SG{ifW0f&VW1|MlN%Z8kZc`|rNa@4xl9{|4;86CLOO_rDGQ-~VRp zeCPOQJI7Wej3t#VVE?V=+Pw&2R+(t$p%Wg$(OXBVKSe)~V zdt5r_e|OtU=XGAX&874DN8IMp`MBrZ_|mzar~l6-bDi(G_L8~&HYt2wb}L*%yA|1P zMed*7=yi+Zz2_KC86qHLci+b7EQiL!m7Y@aCGC(8DTvVEd#pD5cW%Jzw}eIm!(CvyH> z|9jzHXVvol_xi`ZWAQBdxL>`&b}Q$1J-6C>;jZ(pr!L&}zxV|U_j#TDvW5G69q&Fk zzx(5Lx^G^;`|0C$pIuMiUtDL;#r50&>T~J%f2`a8%AMc-SMGIw_NjZXxYz&alNRpd z9;!c`{Q-GZ(hIq>Em{vT~E); zb@semf6uF3v#!76=bp20=Rfvm3->yw{mp$=&gu1E`_6^?xSRdOE-S~oo&)z;xa)k( zQy1>~zxcNc_j$ed$&g&3wNC_d)mTX|0XY7xXk#V&%sxJ=%%avIoJkS+gN=p+gSOSyWexp`ReuVIsfb{ zKX8wE&3`)j9`mt&`Kuk~8vgFo9p>6za_#nW&260dTlY>z41W6JiJR?c7UF=cyO*{)W$ ztCj6)WxHA{=P!4)vR$ogS1a4q%67FJ?{{3C-|x6)TT9s{RJOa6?Jnirm%B^Z?ozh9 zlL+hEEzwz4g)Y)dQK(#p29vMsG_ODo&b%C@w!Ev;-zE8Eh_wzRUXrEC)_+g-|b zm$KcZY|E;;V`+Fk0n-KA{DD%)VnHkh&vCdWNr8%!Oy z!IW(L+hEEzn6eF~Y=bG=V9GX_9QXdU!PIdZ zOxccAw#St1F=cy9*&b82$CT|cWqVB79#gi*lL+hEEzn6eF~Y=bG=V9GX_vJIwegDKl!$~Ks?y{&9lE8Eq| zcD1ryt!!5-+ttc;wX$8UY*#DW)yj6YvR$ogcPZP1$~Ks?4W?{^DcfMmHkh&vrfh>L z+hEEzn6eEf$31HsOdYqulL+hB6sGqu6gaT`q822-}dlx;9& z8%)^-Q?{{{ZE0m&TG^IXwxyMAX=Phl*_KwerIl@IWm{U=mR7c z!IW(-m*&b82$CT|cWqVB7 z9#gi*lL+hEEzn6eF~Y=bG=V9GX_vJIwegDKmz%J!JD zJ*I4r$#L&xdrTd-$CT|cWqVB79#gi*l&Rc9*gp zt89ZQ+hEEzm>l;^Z7_A*22-}dlx;9&8%)^-Q?|jBZER&*TG^IXwxyMAX=Phl*_Kwe zrIl@IWm{U=mR7ct!zun z@&2DC=lB0KWm{U=mR7clmGhT-OxYe&w#St1 zF=cy9*&b82$CT|cWqVB7_ExsBm2GTg8(WThFWcDaxQ(rBV=LR($~LyLjje2BE8Bs} zHkh&vrfh>L+hEEzn6eF~Y=bG=V9GX_vJIwegDKl!$~Ks?4W?|zD%)eq_L#CgrfiQX z+hfZ1n6f>lY>z41V{+Vk*&b8JZER&*TG^IXwx#8`XKG8UT2Ev;-zE8Eh_wzRS> zt!xJ>+hEEzn6eF~Y=bG=V9GX_vJIwegDKl!$~Ks?4W?{^DcfMmHkh&vrfkzH+hfZ1 zn6f>lY>z41W6JiJvOT73k15+@a@_N^$JB9qTiLEwwyTxxYB}!t+STf~U9D_aE8Eq| zcD1ryt!!5-+kwh9n6eF~Y=bG=V9GX_vJIwegDKl!$~Ks?4W?{^DcfMmHkh&vrfh>L z+qB9XJbkgplc zxV^1xS1a4q%67G~U9D_aE8Eq|cD1ryt!!5-+ttc;wX$8UYzHdaUCMTsvfZU@cPZOl z%66Bs-KA`IDcfDjc9*ilY>z41-pV$%vW=~5W6N>hw{2{7+{RY6v6XFXWgA=B z##XkmmF+-fyGz;bQntI4?Ji}zOZgMa-KA`IDcfDjc9*iCaeG_Yu2#0ImF;R}yIR?bQNSY+otcSIYL4vVEnM^OyTd*?v~Gla=jcbPC4Y*#DW)yhv_?rLSbTG_5vwgZ)IFl8G| z*#=X#!IW(z41W6JiJvOT73k15+@%J!JDJ*I4XE8E!0Hny^jEyq1;8(ST>v6XFXWgA=B##Xkm zm2GTgJ5bpMQ?|jBZ7^jUOxXrgw!xHbFl8G|*#=X#!IW(t!zsx z+tSLmw6ZO&YzHdaV9GX_vJIwegDKl!$~Ks?4W?{^DcfMmHkh&vrfh>L+hEEzn6e$K zY>z41W6JiJR?c7UF=cy9*&b82$CT|cWqVB79#gi*lL+hEEznDQ0N4W?{^DcfMmHkh&vrfh@B zaXlY>z41W6JiJ@*S3YOxYe&w#St1F=cyO z*{)W$tCj6)WxHD0u2#0ImF;R}yIR?bMQ2mGhT7R@oj?w#St1F*)wvvF$N++#XZ5$CT|cWqVB7 z9#gi*lx=KfTUyzcR<@;;ZE0m&TG^IXwxyMAX=Phl*_KwerIl?hWt&jh?ozh9l+V9GX_vJEE3JzpD49k;=h zZ7^jUOxXrgw!xHbFlBpN*{)W$tCj6)WxHD0u2#0ImF;R}yIR?cxDBRk$12-n%J!JDJtoIJ zUwcd)x5t$2F=cy9*&b82$CT|cWgA=BmR7cL+hEEzn6eF~Y=bG=V9GX_vJIwegDKnF%67G~U9D_aE8Eq| zcD1ryt!!5-+ttc;wX$8UY*#DW)yj64vQ4OLgDKl!$~Ks?4W?{^DcfMmHkh&vrfh>L z+hB6sv$nz1aT`q8j#akDl zt!zsx+tSLmw6ZO&yv1@$E8Eh_mn^rmvMsG_ODo%2$~K|0-KA`IDcfDjc9*i`!6?`vJIwe zgDKl!$~Ks?jje1;E8Eh_wzRS>t!zsx+tSLmw6ZO&Y)dQK(#p29vMsG_2P)fO$~Ks? z4W?{^DcfMmHkh&vrfh>L+hEEzn6eF~Y=bG=V9GX_vJIwe(<<9z%J!JDJ*I4rDcfVp z_L#CgrfiQX+hfZ1n6f>lY>z41-pV$%vW=~5W6N=WzhPsm<2JUkjje2BE8E!0Hny^j zt!xJ>+g-|bm$KcZYt!zsx+tSLmw6ZO& zY)dQK(#p29vK^>wgDKl!$~Ks?4W?{^DcfMmHkh&vrfh>L+hEEzn6eF~Y=bG=V9GX_ zvQ4XOk15+@%J!JDJ*I4rDcfVp_L#CgrfiQX+hfZ1n6f>lYGZE0m&TG^IXwxzXl{&Gtz+kwh9n6eF~Y=bG= zV9GX_vJIw{^OqY;*#=X#!IW(L+p)^_n6f>lY>#Q>{N)}~ zw#St1F=cy9*&b82$CT|cWqVB79#girmF;R}yIR?L+hEEzn6eF~ zY||>+W6JiJvOT73k15+@%J!JDJ*I4rDcfVp_L#CgrfiQX+uq7Hwz7?_Y-20i*vdAx zvW=~5V=LR($~LyLjje2BE8AVlHleZ&rfh>Le|ovWlx;AroWI;)$~Ks?4W?{^DcfMm zHkh&vrfh>L+hEEzn6gc)Y>z41W6JiJvOT73k15+@%J!JDJ*I4rDcfVp_L#CgrfhpF z+t|uBwz7?_Y-20i*vdAxvW=~5V=LR($~LyLjjjKGdr$wn>CH93vvzdWj?UWASvxvw zM`!KmtR0=TqqBB&)~wFj-Hz8Ub$)%(tQnp)!?R|1?s{saX3g-d8J;!6vrc%{3C}v= zStmT}glC=btP`Gf!n00z)(Ou#;kj$56YiW^qgf|B>x5^W@T?P_b;7ewc-9HeTB%v1 zHS5-94b`lnnl)6jhHBPO%^Ip%Lp5utW?kH@i|ZWES{JwDy0}>vH|yeNUEHjTn{{!s zE^gMv&APZ*7dPwTW?kH@i<@qTe1=&To= z^`afGx9t2n%vmow>qTe1=&To=^`f(0bk>W`deK=gI_pJez38kLo%N!#UUb%r&U);Q z*E4s1o%7u5)IZO?eqHq3$E}y1yPi7gx$CU2p1c0K>$%UX9((Tdb-erF{O*s}>ArdW z?x&C2eRe%PFW1@ga{YSjeXNexGtZr0=REg1_0My!Ul%?1aqFe$uBVQA?mFwM=dQo* zdhYY8$DaFq9q&Fkzx(5Lx^G^;`|0C$pIuMS%XRj=Tz}82y@Nhh$1i`y-B#TB?HzQy z*Ln9R7vIBs{pUP!;XdvbTP)o5d~4k=vvhvf`I*ZX?)o2f@xpyxPd<0yK3~VX56*YAG%xZP*h)BSgyJr~#C^YVFhyuE;~t@GOv$h}Vc0=d_3cOdt1+at(bPdf#< z>ukRucm3@epyUw1A>(`p@V`*Gx9q+6` zoi(Vl26fh;&KlHNgF0(aXASDCL7g?Ivj%n6pw7DDSyw#kif3K%tSg>%#j~z>))mjX z;#pTb>x$xySx@vJMJwZvDBFI(bSOFV0dXD#upC7!j! zvzB<)m(JSPS;sr;PG{ZetUH}`r&rEjcBixMbk?2Dy3<*A+VOtI=lr_USxY=?iDxbG ztRtJW??yNzbHK?-&b^gib7p#8y&30IM78=wY*PzZC)LDZ% zYfxtm>a0PXHK?=3c-9rqy5d<^JnM>QUGc0do^{2uu6WiJ&${A{`#RJW@3^jb))LQJ z;#o`F@qWJS{958!OFV0dXD#upC7!j!vzB<)n$9}dS-U%HP-hM5tU;YMsIvxj)}YQB z)LDZ%Yfxtm>a0PXk6kvXv&MMV70%#j~z>))mjX;*NX1y5b$z z70+7YSxY=?i97E3YKeDTOFV0dXD#upC7!j!vzB<)m(JSPS-U&yPG{ZetUH}`r?c*K z)}79}(^+>q>rQ9g>8v}Qb;Yxmc-9inTH;wteC7OQOFV0dXD#upC7y43##>gmJD;`0 zvzB<)63<%VSxY?YhiCoptRL>U=c^yyasBYDAD;EYvwnEi56}AHSzkKqU}x>_tUH}` zr?c*K)}79}(^+>q>rQ9g>8v}Qb*HoLbk-HmTH;wtJZp((E%B@+p0&iYmU#ZjZ9lT^ z|EphoZ`2a+xR!YCxc6-5`*#B^@y^i?&-&q6KRoM)XZ`T3AD;EYvwnEi56}AHSwB4M zhi851tb?7kyR+_e)}79}(^+>q>rQ9g>8v}Qb*HoLbk?2Dy3<*AI%|w)UGc0do^{2u zu6WiJ&${ASS3K*AXI=5EEAF^wtt;MfUGc0Xp0&iYmUz|@&sySHOFV0dXD#upC7!j! zvzB<)63<%GSqD37cV`XitU;YMsIvxj)}YQB)LDZ%Yfxtm>a0PXHK?<$c-9inTH;wt zJZp((E%B@+p0&iYmUz|@&syS+d%jxY9oG`i`r%nWJnM%$?)$TTc*pg_vwnEi56}AH zSwB4Mhi9$nT)+AcdoBKZM7z7=8q`^XI%`m84eG2xoi(Vl26fh;&KlHNgF0(aXASDC zF`jkBv#xm770%#j~!sxXCk@T?!6^~1A% zc-9Zk`r%nWJnM&N{qU?Gp7q1CzI4{U&f48scRK4%XWi+nJDqi>v+i`(oz6f0)9u#W z;(Ck!Ue=xNxbAe;ozA-ASxY=?iDxbGtR=p3{<0;WwZyZQc-9inTH;wtJZp((E%B@+ zp0&iYet6ao&-&qxd;jW(cU(U_>xXCk@T?!6^~1A%c-ETEI@npeJ8Mv94eG2xoi(Vl z26fh;&KlHNgF0(aXASDCL7g?Iv&MMV70%#j~z>))mjX;*NVS z>xy?=S3GNpXD#upCGNQAt0mrXE%B@+p0&iYmUz|@&sySHYdSyYeLr3OyXzKzpReQH zaSiIML7g?I9q;#loL_@FYfxtm>a0PXHK?-&b=IKHTH;wtJZp((E%B@+p0&iYmUz|@ z&sySHOFV0dXD#upC7!j!vwnEi56}AHSwB4MhiCoptRJ5B!?S+4%#j~z>))mjX z;#pTb>xySx@vJMJb;Yx;c-9rqTH;wtJZp((E%B@+p0&iYmUz|@&syS+d%jxY9oLl3 z+Sj>8^b^0i_!`if?zq-;)|z(Qdsb`O>zw+c#m@@0raP`RowcU3)^ygI&RXJGOFV0d zXD#upC7!j!vzB<)63<%VSxY=?iDxbGtR);y?^z?JFYLCwXd^|ch;TGy3<*A+HucRce>-c(^+>q>rQ9g>8v}Qb*HnI zc-9inTH;wtJZp((E%B@+p0&iYmUz|@&sySHOFV0dXD#upC7$)evwnEi56}AHSwB4M zhiCoptRJ5B!yWg0^}{=^FP*iovyOMxozA+`S$EoT&sTT4 zvzB<)63<%VSxY=?iDxbGtR-c(^+>q>rQ9g>Ae3R zcU;*(&$`oDOFV0dXD#upC7!j!vzB<)63<%VSxY=?iDxbGtRq z>rQ9g>8v}Qb*HoLbk-Hmy5d<^JnM>QUGc0do^{2uu6WiJ&${ASS3K*AXI=5EE1q@5 zvzB<)63<%VSxY=?iDxbGtRxySx@vJMJb;Yx;c-9rqy5d<^JnM>Q zUGc0Xp0&iYmUz|@&sySHOFV0dXD#upCGNQAt0mrXP3f$Coprpk)^ygI&RWxs`(CXz z-EpnytTmmrrnA;`)|$>*(^*SAYl&wq@vJ4DwZyZQc-9inTH;wtJZp((E%B@+p0&iY zmUz|@U-7aZp7q1Cet6zw*$>b9;aNXC>xXCk@T?!6^~1A%c-9Zk`qEkZI_r36-RZ15 zopq21`?zrxB))mjX;#pTb>xySx@%)Kp zS3K*AXI=5EE1q@5v#xm770r`i*>a0_pb*gjM zUwb@jk7w=itUaE!$FuhM%K6Loc-9`z+T&S!JZq0`!Z~Q6wZyZQc-9inTH;wtJZp((E%B@+p0&iYmUz|@&sySHOFZj`XZ`T3 zAD;EYvwnEi56}AHSwB4Mhdb`iU;Xfo>q}=H?5yLRb*HoLbk?1A+%wgk?zrxB)}79} z(^+>q>rQ9g>8vH5wZyZQc-9inTH;wtJZp((E%B@+p0&iYmUz|@&sySHOFZj`XZ`T3 zAD%zH?1yLl@T?!6^~1A%c-9Zk`r%nWJnM&Ned+w+Wd}QJcW2${tUH}`r?c*K)}79} z(^+>q>rQ9g>8v}Qb*Hngc-9inTH;wtJZp*PE0!(stR~wzccHHcU(U_>xXCk@T?!6^~1A%c-EKB+SggTJL^to-RZ15 zopqv&MMV70QUGc0Xp0&iYmbl}dwU&6twZyZQc-9inTH;wtJZp((t?8_Towd8O z26fh;&KlHNgF0(aXASDCL7g?Ivj%n6pw1f9Syw!3iDxbGtRq>xySB@vJ4DwZyZQc-9inTH;wtJZp(( zE%B@+p0&iYmUz|@&sySHKRoM)XZ>);JzxFsj_Zf#jhFrKtRJ5B!?S*P)(_A6()kw4 z4tCb=&brfCcRK4%XWi+nJDqi>v+i`(ozA+`S$8_?PG{ZetTCQ-#j~z>))mjX;#pTb z>xySx@vJMJb;Yx;xZ~cxy5b$z70+7YSxY=?iDxbGtRxySB@vJ4DwZyZQ zc-9inTH;wtJZp((E%B@+?zrcxCEjr@@vI-7^~1A%xZ~cx`r#ed56}AHSwB4MhiCop ztRJ4WrgQyj|IV!4-Ej@-tU;YMsIvxj)}YQB)LDZ%Yfxtm>a0PXHK?-&b=DZqy5d<^ zJnM>QUGc0do^{2uu6WiJ&${ASSKM*WS695_moB^FSxY=?iDxZw$30&y@s4YWXD#up zC7!j!vzB<)63?2_S^GNcc(0uQ{m-uUd$wBB9oL%99rt${TGL*~?^S9|cU)^aYfWdZ z>8v%KwZyZQc-9inTH;wtJZp((E%B@+p0&iYmUz|@&sySHOFV0dXD#upAD;EYvwnEi z56}AHSwB4MhiCoptRJ5B!?S*P)(_8G(^&^Q>v(4k>a0PXHK?-&b=IKH8q`^XI%`m8 z4eG2xoi(Vl26fgI&${ASS3K*AXI=5EE1q@5v#xm770*(^+deYfWb@@vJ4DwZyZQc-9inTH;wtJZp((E%B@+p0&iYmUz|@&sySHOFZj` zXZ`T3AD;EYvwnEi56}AHSwB4MhiCoptRJ5B!?V70*1^s?-dT4#>rQ9gX~#Wl-RX|& zPG{ZetUH}`r?c*K)}78;;#o^PYl&wq@vJ4DwZyZQc-9inTH;wtJZp((E%B@+p0&iY zet6ao&-&qc!(~4_>xXCk@T?!6^~1A%c-9Zk`r%nWJZnv79qg>*oi(Vl26fh;cHHyT zpzgQ^b=IKH8q`^XI%`m`oWE>PXD#upC7!j!vzB<)63<%VE9Wm;;#o^PYl&wq@vJ4D zwZyZQc-9in`r%nWJnM(&3zz-ytRJ5B!?S*P)(_A6;g0+MtRLQSed(-&oprpk?sV3j z&brf%d#1Y69oL=Cy3<*AI_pkn-RYI{m)+^CC7!j!vzB<)63<%VSxbE7{AEi#Yl&wq z@vJ4DwZ!vA%a-`c`OB7g))LS9;aNXC>xbuymi_RoAD;EYvwnEi56}AHSwB4MhiCop ztSOzfud{Y{)|$>*(^+deYfWdZ>8v%KwWhPybk>^ATGLr;I_rvOE%B@+p0&iYmiWr~ z%a(Z763<%VSxY=?iDxbGtRxXCk@T?!6^~1A%c-9Zk`r%nW zJnM&N{qU?QowcvCc6ZjA&RWx1YdUL9XRYb1HJ!Dlv(|Lhn$B9&`G2>jb;UcbC7!j! z^QV_B@vJ4ja{jU=)wi-)Yvm!0+eHQezJ{^b^PoNH*;%I^Hy z+VzvOR(96P&RW@7D?4jtXRYk4m7O)Zvu<|Q&Ca^nSvNcDW@p{(tec&6v$Jk?*3Hhk z*;zN+Idzq@Zg$qq&brxIH#_TQXWi_qo1L}FvqpN>NY5JSStC7bq-TxvtdX8I(z8Z- z)|<_GvsrI8>&<4p*{nC4^=7l)Y}T92db3$?HtWr1z1gfcoAqY1-fY&J&3dz0Z`Sd8 zt#4(>yUzN|x$Cdnocp}$Ip;oK$GZ>C@BVn5?wi-|e)_oG zXV=s7a-BUd*RSW?$Le@J3!VJua};CoqFlH z*Z=bg3-@uKe}{#;o`b)++sZjz=k9M=xa_s8pW-@JbJ)5q;TyPod9>+HF>emezSza4>W zMg&UXT9sJcb)aFv)*;qyUtfGd)Ha-I_q6$z3Z%Zo%Oo2_I1`9 z&pOyE=PWzeSqD4oU}qidtb?6(u(J+!);Z7G=2_c3Ynx|n^Q>*2wav4(dDb@1+U8l? zJZqb0ZS$;co^`OZMt9c4&YIX+6FX~SXHD#^iJdjEvnF=d#Lk-7Sra>JVrNb4tcjg9 z#kXpN%@d)@##TR3^{%ttb=JGide>R+I_q6$z3Z%Z?YQTw zcinLtJUc?5u;Gb#Tj9wXd`G^~(9n_I1|2&f3>m`#Rrr z*}l%&*ID~IYhP#W>#Wh8b+EIpc-F+un%G$r+i}lY6T9P@*jW=hYhq_j?5v5MHL=RE72XYK2(eVw(hv-Wk?zRud$S^GNw zWZAyX+Sgh8+HvpS&iChqE_dhXU}r7ytcjg9v9l(2*2K=5*jW=hYhq_j?5v5MHL=RE72XPxt`bDs6Cv)*;qyUu#oS?@aQ zU1z=PtaqLDuCv~?tJUc?5ug7b=R9j)XYK2(eVw(h zv-Wk?zRud$S^GL`UuW%W$31K9>yGPkXC3UUC7w00vnF=d#CF{GXHD#mYhq_j?5v5M zHLJo@br&taF}q&a=*W);Z5Q=UL}G>zrqu^Q?28beXYK2(eVw(hv-Wk?zRud$S^GL`UuTW(tb?6(#j_@M*2K=5 z*p7QIYhrg?6FX~SXHD#^iJdjEvnF=dJkL7kS?4_KoM)Z$taF}q&a=*W);Z5Q=UL}G z>zrqu^Q?EB^{%ttb=JGide>R+I_q6$z3Z%Zo%OCA_x{zp?zk3r*1pbK;#mhf>tJUc zY{xxQ9qf+lU}qidtb?6(u(J+!*1^s?=ULl4Ynx|n^Q>*2wav4(dDb@1+U8l?JZqb0 zZS$;cp0&-h_I1|2&f3>m`#Ni1XYK2(eVw(hv-Wk?zRud$S^GNca%Uav{G4S=JZoZS zP3)|Roi(wuCU(}u&YIX+6FX~SJKpb`Iltf4&pPK>+dONVXKnMWZSHu#W9IzY=2_c3 zYnx|n^Q>*2wav4(dDgqmde>R+I_q6$z3Z%Zo%OD>-gVZy&U)8b?>g&UXD#lmeVw($ zvkrFF!Ol9^SqD4oU}qidtb?6(u(J-f#Tj9wXd`Gb=JPl+Sgh8I%{8N?dz<4owcvC_I1|2&KliW z2RrMEXHD#^iJdjESI%EHv9l(2*2K=5*jW=hYhq_j?5v5MHL#Tj9wXd`Gb=JPl+Sgh8 zI%{8NUGA)dowdZXCU(}u&YIX+6FX~SXHD#^iJdjEvnICV-piWU9oIQuIe&-ERyy`s z+dONVXKi!GJyUJ-j%%A|ZS$;cp0&-hwt3bz&)U~{hYxPO=F+WKt$dwmUw2&lI%{8N z?dz<4owcvC_I1|2&f3>m`#Ni1XN~TxgPnE7vnF=d#Lk-7Sra>JVrNb4tcjg9v9l(& zf(SI+;RE#~>^oOfL3JnNi0?)mDRdmZmto%4?CoM)Z$taF}q&a?J)*1pc# z*ID~IYhP#W>#Tj9wXd`Gb=JPl+Sgh8I%{8Njqa?2opr^tCU(}u&YIX+6FX~SXHD#^ ziJdjEvnICVp06f$$2HHh&Uw~3&pPK>=iG76SLeLrI_FvEJnNiio%5`7o^{T%_I1|2 z&f3>m`#Ni1XYK2(eVw(hv-Wk?zRud$S^GNca%UavtRpf7!&&n%G$r zJ8NQRP3)|Roi(wuCU(}u&YI_0=RE72XPxt`bMCn3t8?CQo%5`7o^{T%&Uw~3&pPK> z?>g&UXT9sJcb)aFv)*;qyUu#oS?@aQU1z=PtaqLDuCp$8*1pcV;#mhf>tJUc?5u;G zb+EGzcGkhpI@nnU+i~w-9qf*4p0AvL*sA&dtaILRo%5`7o^{T%&Uw~3&pPK>=RE72 zXPxt`bDnk1v)*;qyUu#oS?@aQU1z=PtaqLDuCv~C*1OJn*IDm6YjJ1o>#QZ7b+EGz zcGkhpI@nnUJL_O)9qg=woprDs_k4A*JFauSa{fW5%=6VY@3^*k);7=D=2_c3Ynx|n z^Q>*2wav4(dDb@1+U8mNI%{8N?dz<4owcvC_I1|2&f3>m`#Ni1XYK2(eVw(hvqpE; z!OptkE60~j?5v5MHL+LDUpBF`CU(}u&YIX+6FX~SXHD#^iJdjEv;O(Y`CFVd&t3Dp z8hbj(_jcJny*XdDcA7n&(;bJnLO&z3Z%Zo%OEsCzieItaqLDuCv~C z*1OJn*IDm6>s@EP>#WP2wXd_Tc-FzrI@nnUJL_O)9qg=woprFY4tCbTcHH|~2fO2% z=UL}G>zrqu^Q?28b8I)-BJvy~Hj>#Tj9wXd`G zb=JPl+Sgh8I%{8N?dz<4owcvC_I1|f&N|pxOMK<{vWcBFv9l)j%K6JCcGkqsn%G$r zJ8NQRP3)|Roi(wuCU(|5&pPK>=RE72XPtA$eXrIz@3_u+);Z5Q=UL}G>zrqu^Q?WH zwXd`Gb=JPl+Sgh8I%{8N?dz<4owcvC_I1|2&f3>mqdV(hXI=5EiJdjEvnKY+`O7AD z*2K=5*jW=hYhq_j?5v5MHLm`#Ni1XYK2(%bj(wvzB<)#Lk-7Sra>J zVrNb4tcjg9v9l(2*2H$)pT(Nk9oIR}+U8l?JZqb0ZF9#xQ*HB(Ynx|n^Q>*2wav4( zdDb@1+Sgh8I%{8N?dz<4owcvC_I1|2&f3>m`#Ni1XYK2(%bj(wvzB<)#Lk-7SrdEZ z{ACk6Yhq_j?5v5MHLm`#Ni1XYK2(eeJlP`)gl!T$elRV6XhM%a(Z7 z#Lk-7Sra>JVrNb4tcjg9v9l(2*2K=5*jW=hYhq{3^Q?28b*2^{%ttb=JGideg&UXT9sJcb)aFv)*;qyUu#o zS(iI&UuRwMtb?6(u(J-fE zTzjsw&ilq4-}lBn_r81H2xIifFLVEQ$(&Vd&05`iZmx3<<~rwKu5%9NI_F@na}MS@ z=U}dL4(2-NV6Jlx=Gxa_u6+&W+Sg#NeGTT?*I=%F4d&X{V6J@)=Gxa_u6@mR-oIS? z8g{PB4dy!7V6G(&=9<`Gu89rin%HdT_;O8b*tsS)m}_E#xh6K4Yhr`BCN`LBVuQKP zIhbpkgSoajm}{GZxwbi&Yny|)wmFzzsqR&N-OtoP)W}IhgC5gSpN*nCqN_xz0J5>zsqR&N-OtU4yyaHJIyNgSp-{nCo4G zx!yIH>s^Dn-Zhx(U4yyaHQRa5a=mNVxfVB=YhTlQ-L=HQTn8J>b+Ex)2OG?Fu)$mh z8_adE!CVI$%yqEATn8J>b+Ex)2OG?Fu)$pO9L#mj!CdDY%yrJeT<09jbBc#wXeZk z`x?x(ui4JA=Gxb=b6svQ*TDvJEpaf{#0GOsY%tfvW;^d+u89ph*Te>wD>SA~TuQUH z2G_)fooix)xh6K4Yhr`B&N-NCn}fNwIhbpkgSoajm}{GZxwbi&Yny|)wmFzs^Dn-Zhx(U4yyaHJIyNgSp-{nCo4Gx!yI~Ii_6i8g{P5 z4W8b_ua0L$vnC1G5{I4ZV1v01Hkj*Rvz=qgb+BRQI@n;YgAL|7*kG=M4dy!7V6KA= z<~rwKu5AwH+U8)cZ4Tzz=3uUE4(8hCV6JTr=Gx|9u5AwH+U8)cZ4Tzz=3uUE4(8g| zV6J@)=Gxa_u6+&W+Sg#NeGTT?*I=%F4d&X{V6J@)=Gxa_u6+&W+Sg#N(GBK0*kGs^Dn z-Zhx(U4yyaHJIyNgSp-{nCo4Gx!yIH>s^Dn-ZhwOaf7+`HJEFOgSieinCoDJxehj% z>tKVq4mOzUV1v01Hkj*RgSiei+xeL!*TIIJ>zsqRwmFzM zO>8jN#0GOsY%te62XmcsFxNQ;bDeWA*Ewf9$CvAz!_IZi!CdDY%yrJeT<09jb8_YGa!CVuY^zNG2 zV6KS`=9<`Gu89rin%H2ji4EqO*kG=S4d$BIV6J%%<~rwKu5%9NI_F@nbIx{-FV{JT zo$H)~xz0J5>zsqR&N-OtoRi*N=N!znufbgV8qBq?!Cd>A^zPc%V6J@)=Gxa_u6+&W z+Sg#NeGTT?*I=%F4d&X{V6M>(<~rD5t}71an%H2ji4EqO*kG=S4d$BIV6KS`=9<`G zu89rin%H2ji4EqO*kG=S4d(jiV6J%%=9=eVu6YjTn&)7yc@E~9=U}dR4(6KYV6J%% z=9=eVu6YjTn&)7yeGTT?*I=%F4d&X{q<7c826OFeFxS2YbM0#|*S-dG?Q1aCz6Nvc zYcSWo26K&WFxSBbb6s&T*Te>MO>8jN#0GOsY%tfv26IhpFxSKeb4_e8*Te>MO>8jN z#0J}IVsrg-*tzC8m}{Pcx#l^TYo3F-<~f*ao`bpOIhbpngSqB8m}{Pcx#l^TYo7PN zKi8E^|4aY;r@brY%yy+t*^xiVAY|zn{l|J#o(n^P$*6)-0{lvOGsoNz+Ke|7*3$~*l)}tS82mNsS_%HX1*Lgg6ACD95@%Yh?ZCw$nV92^~COWh~4eG-19=e#P0DByT?h4e&8?YvA^I)uzS9&haZUD{vmezjTrsl|M6Zu z9{8EZ3I7wLA09u)3)fh;o$h7m2jhd?-43z4eFJuPzr^nG5ThUX1seDGiQzx^(QT)A zf!%%}yW2m+h!6Y-4gQP&2Xnl@ZvWHRI9{-Gyufa|wCRaCUa-5{cY)pg61&Gk>>ejE z#|wJ*I%GT6C+jI*(763WcDLV%-ToxzctP*>KaJBJ7h-$7m=S9`yY&Kgj-zcoklo#{ z0lRxV#2iQ1IgVhCBlz!qXVCuQIKn3!M=-|`%y9&B9Kn2FL##Ou0dpP#cHbWjFy|p) z_x+UYoQJ^fzW`wPtb3+#@& z0Q3F=^Zo+!{sQy<0`vX?|9zb_T<`<$FEH;fFz+ug?=LX#FYt$~W#Sqn_pSZ4asJxi z<1NM$mvohmJ34$E@!9L8hKRuhRcA1Y<>;|yiuavEm8e|#z(S9G+=y?!qp=UiiQ?t`V{8eB6u^Ze3rEs~k- z1Pv}7H@m3GkE@lADszN`TksGc#-QJ_=pra$JXeQQ|8 zxcWs*&b=yQ+`S4WSGtig&ehQ573ng?73gnrmMWRz@<+KjSF$)~Ba`3G{h}5|ccwP) zE&HN6bTzr}zAx%PQIn@V|Dq;8HT9n=eN_$POx_;wRkfXMa?ALy>hWlkll}Zn?wf*7z&TreQ}7iy>E2fbAA-+?d{yu*SXKS1;B#=f zmtPcO0WP%vi$aXRxt4!Xh#i|onBxoP_<}jUV2&@C;|u1s3g)#6 z=CumuwF>673g)#6{;fsoIFEW`Xf7_5I<8oAljoO96Bj+mAj%=Y2$puOrEzbZCvy-lhdC|8#m&Yaisa{dfK@CXH14YYn}0AhyLkC zlhIDfTocHS_A8Dw8T~FgU^2#YD}@(nFwUn{Ovd^m_0fc*%Df3Q!%@Ei6o z82-e*2GhRK*F!M;kLv&!al!Qg%-2J<<9f(?To1u$2iHR|+Q;<}jDB%F1Yo%CL+hD$KgZaA6 zc3k&ZkLw|ruiIe0ZiD%{4d&}Mn6KMlzHWmtFI>05eBB1~bsNmrZ7^TA!F=5Y^K~1{ z*KIIgx50efW;?FitjBd5%-3x&U$?=0-3Ie@8_d^jFkiR9_INSd;|S(Bf;o<0jw6`k z2H8|0AyhBVNe&z=#*}K(-@4WIggmFxv6e`6L+aBhLh*U*w-) zj0brs7~@2~3dZ=6$AU30){`62kW2P$G+fx>AvY65B4386Z?+GkA27U zf}Q6JJ^O+7uiHOppZ$h@*`F8>`x)b8|6}|d7kj*z?QsNi9Kjq%Fvk(haRhT5!5l|0 z#}UkN1alnO&Urrcod0tiq2V}!IgVhCBbeg|<~V{mj$n=>nBxfMID$EjV2&f0;|S(B zf;o<0jw9RuE6*ueY|m|&X|39x3-SFFc7C=4=4U%#ezpVVXFFhiwgcv8J79jc1LkKt zV1Bj(wvUGyKH)Ktul^gKFY&V`jLkjOQ+}(TD}w(goKN|lhV8>OP3w^J2ThrWdw$gspvH>sQ#uBW&Xow($$wykO_~LNDF(LOaCh z)8;qyOLp{$Ih+1zDQx~1wzxR#@v7}{UM8z=#!l_MCcpkUg5vns=OlS^gUS8tzmR+9 z{J;6bf+u9Zm$=&b{gFiCn_Y^_d^ye&_pd)fF3S{4JlQiw;s@=(hS$K*;yqxrfwsVC z8$JP}e{FZLUF!wwbvwjpN4HOm_Vo`j`qZxxqfgxjG5XYf5Tj4s2Qm7z*&Q~$u(cy> z?F(DK!ZsdZ8>g_1pJMHv7wkM==%ssJXonbm+Wdxo$&NlTXS1CV!sdTri;Ls`Pke`G zIYVneEuHS%Huf^D0iPSQoh2gUX$@pqzsMQ0?ht9}4$mSp$djbm5}i{{X>o-#cN*rG zm)q?mO>K`h((j5SjoRB;UY>cFG=F{WD}M`ELYh|BLga=9t4PyzW2DTGw23r({+uE4 z8rCGVcnxb3TD*oe2`&1727RIrXwWD6fChbHtk7WW7%MawJH`qP#*R5d10P_{(7*?n zGc@o4)&w-YsbOu=5aVL#C?xcY)weLvd zUO%L9uOHIDm)duvfzPz>NCVcsBMsQrjzhxZrz?sZ6vzTivv4t>Fww)Kp5cs-*XUe6ehbgx5< zN4nP`#v|S95c47pd}-TXm=|d}cCIFUn!qjxm9eH({*Y4(0$xpO_mMePYgFj0e5|qfht<44)x~ z0lVkLc8a505C4!IecIZGKgkZ8Z9MQl+0iF_hj!2>`Y>~RCnoI`&o zWDMBkNAW6gC%^IibU&5z^cCm)XSs~5BmLCWO&#QhiRq0+ZT-~TdJARJkFQ19s($K0 ziW73d+p}U+Za;Or^mCb}zzR|C{X`Y&o7VMpX+Lr2`b5<+DyM7o<=2kQ&WS2t$^0(Q z0^>ZgES#uD=PBg6zh}2I^Q4LDt#<*}%lVCD#oiOua7S)e$>y`=uDTOdpTQYj9*+*n zbj2pBg*iXSJ1HK?8mT9$wudjvr~#>6E&lXX&#$kOFS6!vB|Gk`rj8gTPj&p>wSBFx z+IcU%%w4shtMqJNwQf~}Q_s;A7U)ZJOej;p)nuTry4~uSg{gf+Y5^&37a$C%`X=i^(%eOmr5 z3LW`Od^%s8klQo5pm|VpmS`UR9r2J}Ek)Wx`HAEGZ#tIcD(Fga&qo#gF50m+Uh^{_ z72Yw21LHjR&WB^+`u;m#j)kj4H9bc&7OuJNeK{5~!zf>lg*-Ubmt!GcZ}jC@$j+yI zITp^a$G#kk*iz}OSU5_Tv|=IBG_qnL{QFz65EX)~SctDntXLQi)I^SjQT@(Dj)f8U zc_PQc$ehiOV_|GA_K)@Uu@0>_2i9AvUbNl>*4sEgT5kgD?cqXNZvyLWnUmI=z1?+z5pwZMal$NalBt8z=~sy zp8|M}#_eVSm?OopPdEMEO&utX-wz4E94U?+yaF&sisRO>0L+o%cw$a~6-V#Y0ahGy z><+Nvm~=S6ietY^0ahF@CIwh=ocb!jisSv{fmR$_Wec?8*r0Hr6~~7^23m2PUOUi= zW5*_eRvcHi4dgkxn)eR0;&{PRzt*Ylx*__#?l^v!6=cP+>dGK1j?=aWS#ex@Ajpbi*9$>b9A72` zS#dn@JjjY;{jWh*9Jgf-w&FOfV6YX(!{vjmI94!%tvD8I7Hq}wc-LSnj-G>qtvFU2 z9c;xh#5b7d=qeW#Y{hYFjDD{>j)T_+TX9_O47TF<^;obK$2`}9tvH_eBiM>#pSQtQ z94n^|vEsNbXNVQYB0q#!alBI{#EN6J`XN>v7q$tp;y9yMh!sZ<&k!q)cl|=FIIav2 zvEul8MhMT*h*=t9#j)^K{a$w*ukQ=7;+W%Hh!w}-cS5W zmwq2=#j$9aP%DnpJwmNGwrmn=#c@UFP%Dm^283F1Og=W$isPE#P%DnDW`$aD%(*z! zievvZp*%-dhTWl79H$-8?{&wq$(2wmj)C_=tvKF&6>7!tZSpWHj%%}rS#hjeG|Y-) zwn|}E9H-X~v*P%zWtbJmy*Jjf9Jka6x8gXd zQMeVyWF5k-IC}OAx8hiSbhs7Az`$@Tj*q8@TX9TS5^lvYbW6Au#|rzxtvJ3q9&W|4 z!NqW%qw8TpxE06YFZ6reaV(WA!ir;`tPxfmRlx`=j#tV@SaA&dDZ+|l;T92A9G`cK zu;S=BIKqnK-3bv^92bN~SaEzcH^Pcz_tgl5a)Z!IA3qyrUw`jxoj#Qa) z*A$CC<~Q2vd9Cbr-f<+RppmIsq^c0x8o85^r9vdH4P$VjNM0Mp?^z;wZ5U<0S!+YQ zd~U4`F+0&(8^ZUZwKl}bgVx$`RM}yz4UfJnt+nAynr*EOIXcu@8*=wJYi-D01Ff|o z-*vIphATxgYi+o?3u|q-c9pf(hU<9|Yi+oeJD^?i%xf)<1G5m+N6T z?{OJ$Go1IhEOFY}<1&-7_PFf6$=c)2LyN3E9{bl+YmYld`CEHjq#SAOanZPswa3Ma zw$>gOVGXQ3ZbVnJ_PFt+xV6WPM&DU`-0;t6?Qx@G3TuxW5r5HjjLwy*?$LFO&XvtC z({+r_l{t>kb&SrHyLX529v6$&Sl4Rtc&>G=cC-(-uGJnvUe>kRnesR5S}kXFx31Ol zT661KE&YG8uGKQ{kJh!?^+RFnTJ7@9YF(>cSHIEyh|ZPS-qQVu&XxP0{NsM~{av~r zAqRHNK1=r_isP*~x*s72mdm%${Rla*Y`l!_N63L?h3HVeR!iT&P`*|>?~StVxv{zW zTlZYY%#PMQR}^n--E+mj8rD5mWG`jibH&=c);-tQk>0xJ8ks**UV*cWG2jv96*$Wn z%MvKBp#9k9+CTD&^~Wi%pg5LrQeHuE9J-G33W{Tu7|JUsj#r~7ub}4xalVvS(DQ*z z!zizy=L2JUgz&Z6V`VEVcXAf5YvoRIS0yWVlJARHxszO$-O8P$M@lPqay5KS`5`?Y zSagr_LwY{&_A=#%6vxV^C_kh)CLZ`lerW8V{E*_fYX#+p6vxjqDLPCAgZZ8-8s)cgU=g0t%7I0d z&y?rmOe#)1r92;JQseSn%JXq1HGVutc|OH4Y#-(M6vutHG0m|^*Wu`=s8dS6LemqIL0~Yyhd@%v!2dt z6vuW;>AXg9OfmN#=e1wL>AXg9ygGr-YZS+VgXz3RalF@+&TACM@aA-0qd0p0MCUb% zqbg75HHu@2f^=S^ICjcH=QTWAa9sIjok_)j7uK0ntV^)Yq@w+W0M4Dnqk{pQI~i|w z(7Bu9*m@rm)C=UWU)WzPOkW=^!$Y4=rM_&pHLh}kEQ1)6vtvi|MC1}Vh?(LLUDZ8 zlAfPX9BbF6=O+}$)D`LZ3B_?;5qf??ah#r=o}W-0?+SpM3yM)8IhRvoAr!H{Mo{KMkKzgWIZD?%IC125gGBX^s_AU8IdvLk{{>5M%w-K z9L!;RCXZ*@fB&xG-{5x*_`L&uzk%3gE$po>jY~oGoQhZXRu!(Nbe%unL}p6wrCzT; zDGH1VmKF1RscK)GqIBbB@8X=r!x=1jb- z*V{{Nh|MoP-tibi}q4`zw7EOH|L35yxdC- zDf-Fjbt6gswcShIe_UVY>v~z1Ipn2A_Yah1n;($IB`Ox#lCyXYl0V)NfN>1f}G&kqw%8M^EBj>+KJcx z=^6Oir`cT9XZfhEd0UDV)l<0MweV51ug?$x#S`S$ls;;1nLT315GkGez18Tzi=yT8 zS@KMvx2o@PUzA?lRrYV-t*-BWDgNxF+t=fd+5S%4+tbw9EY3@fdi++T-uuO4$#^f- zr08>TbLtL9w|ZVGEbiWa>KQ)b&aqZEmOJ`2_Eu?|r*ws_Dk{7>d#jN@ev{Mh4Huq+ zyw%A&FJ=1e3q(UNZ&fvIyv(&_ulN|@t&V3tCNoaEA*RK6tFGPG%XVj8iZmO%)$D~4 zvUyYrqnFED)oI#XW}ckhSa?d$x4;+Y%zc>+b<10&*ejf+zGN{DJ@!_6c4lyV_fuwL z>nCqD)*=XZ81J2Sqsjpa(}862J|<2mv;pG^^EL`m$ns4-|r*75W7`$>^*__nD>2AVrF8Y%ha_D146 zp3CL86Gw=DdKDPUcal7V^6mGWM4e) zt)o=GYs7c04-r3W8Y-^lTu=O}>nbrfE{Zs8<36$GTsz_b|H~p*o^-_NYW*%A zPd_ZDZ;nz|Zq5)6za28?j3^atokAi-lx%McvoWLw+eKFJ({d z+WRz89k?|{{&was`Tk9$dVgWDoY(8RtoJoiUGdu|Pqm7bbJ9eqR-0}~|-}MAWxL~%Oi#BX+k>rd*LWmJ9Ro&maA=?BT7f9>N7I9E(ND@WT_mb`kzei zYE|fw!{vxl6ON{K1^6`*-u0tYPsbOzr+m0*);vmu9Dg9Uo?j=*cZgDHg3ijY#G|5U zk0@28>=v1A)m>43K$QAnd6X>N=Y?qLsrS*MrZTw4ClNj&O3m%`%vsCvP238IQZ3S? zb8g7+Su}`>QahtsI?la#DfZ5aQltISh;TyMX6%F&WQ3Q8;C1MqSWhhH^rrd(K1KHD3vhm zz4Z8Yh&Wa6L-OGH_ry(GjFL$m)4QNqS|Q9iu}@m!-oM{-Tnc?ga8UD@^Idgb`Cr6BM&f7V_2_C+-rnBIccf|Gl&csg1UsJw% zID@XU80*;W(}<_-XeLF$2;v$`j>+fJm-yAg?5-J8dJ(stZMgIgv9`JNYs6aX((j>p z={8)tEn?la3w_|9?h|$ih8=x?p+_HJw1YmtXdgdd*zg({TD%90Hnm9e?8en4qX*Zd~MPd`Af+#V*NM&uDp3YiMK9k z;=&K!3maYoLyPx-(FWQAqiysDMxWX)*sk@&(Cc;#*wKz|pBU}yA7b>WUn54J`aQ(x zQ};oPKJ9a~*@aCnZ0#7f_6=LVhHX5CZJdT}{N!WzykO_~LQjl7ZT>;~F6hxG<_1Qe zn6ueV0Rz4Oqfc90#Q(+fqWSWgtTQ$(?d`%D7P`RWpUw5C|9JuNyN7ukCGVTO<5EB3 zJVl~hV5}`L+QECl{9Z8L3k`m_FJ|}|j2OcIV8jq{0V9Tp7Z@?b57@L7Achw2fgNqQ z*P;t;+xx@%fd+QOnDx331B`aCCctQ4{}7{3{TeaGW3DZ8oVqQtyZa`4|7rch z&OYP#Cb{Fg>P}>A+RSFGdzW^^w$)l_l1e-GK!f$e8Zc|X(4cKF&jb6;?KfJJ@F&LO z-jDy5*TX@R9psa$AG{4P<_n%sstMVT_<9;^erZ5FXYgpFm|tz;+qK4%271%yt ze20&5GOQ|bkv5Zz1;c(M-ZD6VG|;mK%o;E>sg{o-eTxnaiD3sHNSa9Y%u&^iMTR%= zu_$5G_8CXK&8rS+pl1!3HDGAg&+{Ywyr^o#u!9ec3?_SnoF$C?#{!9CTa+~>XA2-s zHnt*Zpl1!3HDG9*mpYTa!1zAIu!G0n?oak_9vzI>nBK(con4If^?xCD{Lq6m(6a{2 z8Zb2Vw*5-_CGFZ1!wznEdnDO+{@lnoet#HoREB0o>uZCFlRI0H271Yhhm6f2Vc4~nCz3A&o@T z`x|s_4u&1v(Q7`nQ~l5aWB0q(#JQg=FlL^+5et2t)TRb{)__?9c558aL!;YtuwM67 zll#?edT^V%FVdqOXrRYcj0aVI-stz$}zcFzjHxZpn_ds@Ehj z)|+0dre3c@XrN~em^IXn*64jidh8J}>|nj`$d0|H_Y^Vqi{5L**hkPn&l)gmz|iRH z0O_&E!LWn%b%X4x<~EcTBomR z#JFDRYaKDJW6(g)8Zc|X(CF(hwU28o7#LdmI>cu)c4S9rsFo zPb9|uPTwnuaUX;Rde(qh1BOQ5$4QTSG#GZUzVDMA_j-L#C&v9+-|LBSABP5d)__?9 zhDPThq(_bch8?W)7P2E((K!h*@(rD<5F-zP271EH;`w|<$E7={a$(XK*9(xWiq0zLDQ z271ZK{9zgZ&%G3?;YJIsC)Zs#!06^$ZIqn??K2LY3b2VF=@8t7RAW(^pc zn;T}3zT*>o9&`rH7yL2TRI<;`m)tniaT>9_`&Q%)pH4hr=6Mfe)WwXg=%55SIwd2-+ zSp$YfuX7jfU$llbQ~P?&>wQ6X>;=8%iD}LE3?;@ohX#7qfLQ~EMz3?yV-1602kU)7 zcI*Yc=83VM^wQ6X>;=8% ziLsvbULeLghX#7qfLQ~EMz3?yV-1602kU)7cI*Yc=83VM^k1V=w46PmJ}f z_X082IW*9-2Fw~TG?`cDqTD;eSdAIr25Oy>x&);O_8pn)FmWj(d;)-yxT znr5|1Q~TN9FK~fj2j`mbfb5Pw3tW4@+e2J!#RAvUr6I(AS4<7`tO2tI?AACjHfVI4 z)Gt`~MRxS1+a!iw_eG3$pyBaA!)-#teK}J0B!5Qq?(PD^4xT@~4cT*69ppM*v?Fm` z%Kk2|MO}%9s$Qglo;6_BfT7vr{Tt~I+-yM%JGe%?*>Bo_Zmzs#`;lfx`cAGKJqHq> z^leKT=vf114Hz1)F?C75bkA5~*ulyCDwF*~4}aHyDK&^|mzn75A88P$oajXw=vf11 z4H%k))vZbYW2(W#u!Fx0sYmuhZ^pO|*J?~0mt&-B>gQ&}L-GtG4fL!5vjz;!-mT{K zFlEV%#IS=WwKT8E@uB%$2QGwDo7IctcGYYWNjz|UHqt=P8Zc|X(B%DQUeCwR(a-QT z!wxQ$&wM5}uy=Wv_wgWV^GJnKuAm_y#7!O*B@MOX)__?9hQ{mLc+#H@s6`ArICqnw zWRH8=+*P~D2;wwVe|D9tG={il|N5kXo;6_BfT3xA(0pDO@M{HP*uewT1Zt;F_)o5# z!+nX9Ppj$rIi){wy`UkzQFyKj}s!G3?-+zkZUqZtT7`)wQB?O43xDF~#NgJRR}SpC*$Ade(qh z1BS+{%XbP zILq#jCWajxnqeE+Tdbb#I-9hY_;)qSm45AUV(+6fNdrA=z^nm7vwQ1i(tBN;O$aCKzN_%C3B;G4n;Pg@17-~vn*CSnliny1Lkv4O#_@`-^KIKLaIM^zoix#3 zVqC}DmnE(;-_$_Q8Zc|X(Db=z=1a9(ypmwp!9Cxa*QL~%Gq}FBG;_Io<5Ri%%r*0| zGwZ*Q271A| zFl)fj)ahvEPW~Zlh+zk3ooV*_A^9meeu|mP?X0^`-kV_NS0#t;APw}a0kZ}S&4Ddu zzO*=F05R;~bd$_}-;`b@J(`+1n8%OvWvNuAK7H{iq=B9_VAg=4i63g_OTXo-MhrXg zIkTO<%_qt3 z^Ve42u6B_7Q17-~v8l8t2xIQ4q0K*Q}xeD2ltLU7B82N_IRfv&?Km$E%sC~Bv z42{l1NRJ!?3_DooEo4WoqH_{rFf=+3Aw6;oFzjHRw~!sViq1)hk#Fc+g&27VG|;mK%o;E> zIu9W|attu+V4b&+9l46mNr;he=v;*uc?dMnvj)r>Ff=+3Aw6;oFzjHRw~!sViq1)h zk#Fc+g&27VG|;mK%o;E>Iu9W|attu+V4b&+9l46mNr;he=v;*uc?dMnvj)r>Ff=+3 z5uAsBVMo59^A>6cxr)w7h>>sTT!k2U2sF^M2Fw~TG&&EV_K{xbWTEy zd_(6d#K=RSfu1#B)_|eWc?ju|V}M}?>%4{Rl((!sPKIuCImzQ{4au!D8pLhT?|(K!h*@(rD<5F-zP271q|oQy!u<(6a{28Zb2a@9{|E{(C%nFL+#X^SwVF zOXkR+e}4@9z+q2o>c7h(#@}Uuv3J1GgIN!Te$Irt^tWO7yR0;mYZ3R^np)<*Q;pbj zZIEoUr6lp33H#;O5jlw$d%lzSp}!x~HoOLg7ViP04YUPD+x&N6=u_JT+qIq;dfg5& z+R^P3qfh-~K#xB4YsBbNzlRuo>OP3kr|yH;JukKkn_k%35w`Y)tzW}79>X?H!!~~F z@AS~8ZNAV;w;#|BG5WOm&9M0s<8eWcKH&>6`n1JG*y9Dh-_S*VwKMdvV=QO~jIp47 zFvfy@!59mEz_8&pFtm6N7;T^}Fvk&$KH&$pW2~&l9KdJ?{sg0a{bPX9r+$qXeIhQf zqff*Uj6QWA#2iPro#N=$QyjtQ)7C!45q8*Y<1uXGG;HIiIGXL4aRg&5Hb0;p2|LDa z^P7RW!H&6N&SpDi9Kq<*78i;m?CyDy9`pS>UjOsswJv8HmuHSc6gxW)denmK9m29n zU3`OBbet+nR;@;?Kl34f{k1UhseP$k_(40c;WaR{cn=tDpe-=k###ZRPi+@$*Lq^; z@wpP%(T;B40Hb~VLySK4YsBbNzlRuo>OP3kr|yFoecJ58rWdw$gspwU)~{h3k6|09 zVH-c~JNLX`=lMcUj6QAtLHjQEybR0@j6N}Evz_x8Co%f8#YKNM=O3}N+5e80xlaB^ z#|yE`u*j3@3)vZQgdJ-KaR+1VU_F4bcCb#sSUdOu!-m(u(BeH{w1Kw3Xd8O~j6Sh$ z*^afvdaQFW+QC``qka8Dj6U^i#OM=in%?W)cVP6X`ye~-JGUL{nf0{qU`L;}_OUNW z1DkC;wC|`d-G*)awC~Jz+R(lO>-o~YV?D+S#@KCsqkRWE`ox^U=+owZ+IO&{Pvi=y ztB-l%J_zRf9T@jm+&96v$Krkp#yu84VA${)7+Sms%=rlzZKDq`=O=8(J(%^#2f%0t z_iQlQ*FOdred^bU(I@f~*wH6)0x;(%VE4S(PWg#jPx%QLecIZm`~-H`Y~!K)1a|a^ z`~-|XZS#U%vfbtf%1>a&*lm8J`~-H)6>|ooPxuZD-`L{vPx1PDul;-NHG90UC-E7f zD*AJ;HrCe}>+`U7Ce6R%bF5gaX1_1&{SxCfj0gY4zbXx1h!ayn9O$?Gm)qiH!*l|l zpFRHcxR_h634MNcl+SL_A!Pu4e)jgURpR^Yi|F&SfgZC(Wcxh=pPy|oG!*UYbCx+@ zw9R7x;~)Bh#^e#ArvCjM`h7nrN>qLsCDCutge79{r_K_e+r9B=_OsM}rhc`brS>!RtNkpspQ&H% zXQ}-x-F`;z$SNmCNKT~|QpQZLQ#aH`TYCk*N zewNzL4!57}{fhr+4DgkE4M5Lq_Z6{wod3$TN9|&5m-u}()d||a=!wYPtvK0FA59dz z?lJaVBVx#&GE1z$55@x<#_aanzifS?J^aJ^&v?T{?e9G^TT~sof_O)ft>R3VFygVn z`fo4&+7Q2=a9zZ%$V@zK?tRg;)-?JIU)9-9?c*dr|0~wBeeT*{)UWoR)P5w^esyAP znX^fj%w~7k^nzc9_FuT>sb3vKY4d}$`A6FPCT;$dHa|<7|KT?pE86^5?GgLjZR<+f z)|<4gLup%|(zb5@u0^07iO>H3yVN4EuciM?-0kbf*5<#gZicP>f7x}?wx|AO*EHMp z+Ky!Y?V(OdNd z44Z%cQ=g-sqtCem6JYd- zb0XVumSa86cwn@HvmY4kJaJ)?an7=n+JK_a~9`OQmyuerwh!>dS1?G5x zIbLAI%l^HYw(n&8`@1r=fAIa8|I@xJv+uJd5_RzOf5q5Ndx)DYnJoIuJ4{^TXFu_G zO}{Ah-%-;qe#|baPdF{heR1;7YQ)=j+@tdcV$`TYl1LRcg=!lP?jJ8+AJ0fJ>XZMP zsMn(<@!-%CBIso>aluc!|LMJh#!Pn%*cYXSHjWnsA7&Ltw??TiL$8XjMLLK-mPM&= zhmMInxg$i+nNjM&{T*WXyA@(bNR*m=a)B6oK?>*iDAoCkpJ<)$j7T*&N`2f?Tcm$> zLzL+jrGj(5as=E=5K7mwiyPU%(I7EVl&&46lJ#)Lmdtraq^%UCw&vXD?A7L?s9!Wn zUHh%1?D+cuF+7K^L-=HnTpqDe6iXGQ-qebgCriu}bKXX(+=n;FJKu(gwhtoJ$@&Lm z+?LWp|1Fr>cl&~Te&&&f#j9vDs;lse2>U^Ye+a=u3z5%jQVs`j{Yp=>OC? zcWI>Ztb0>-_WDVx8M@7dXJm%2zA|-Cq9 zlpd9j>F?-`RIM9#l3&tYm7khMs>?NV$YHtSWoP}}3SFzscKVf1l79O86vlYu-g9(Z zyxd(_f5*hmC`X@jS7rX}k!s}p%%Wq*e;8oqyulA6J><@Hvfh={i=mCL&OK!h54@S&5S#B2?c@v&8+S`^Cy85z3K$n3y{7g1F*{P=j8T6`7{o78%M#sMcY} z9m)44ikk%@R81q^qeH$#(M*3=NVbucoKaY2ZwF|=4v4p!ay!o7(N2i3Vl4XB7mskY-#b8xtf%Fc zGP?b|4P^U=ZuyUMw!+ zDc`RRQ)|EM6KAVdkmdAu)0}&8UL3A-#@Qn(Oojb?TX_EXDz@arFg1QdqFD8^q+_0E zm}*fYQ4CIg&rzpOm};AFQ|w9WAqKSzQ@IzN75P3)5bGL*sSH>53g2q;#hmJ4O7>kX z0=I7ypGt+PUQeS$&$LHHaK13*jOr#T{B%XE&Jd;=U(79hHry2-K830hI~F@?mrN2_ zpM|QjQxa=NT#Of;6GBzSs)5cn)2@jl7eZD0cj@G+(I>?HgQ4oi>X!0MmffP&&QLX^ zTBuCdaj}@XI#g{AS|-bm4-}i`g(|-TvGR{*jYR6mQ1v40lnl?5OqBEqRjHp|msj5O za;zH~s?v_owP4ry$ENEQsy3ucl8qC#I={9FRgcfzk+0_!mJRBMs3$@4;l7%NtlNm~cs`yKrWyN9Zq)(nub^Xe0nXBtQ*<63mLYf~(%76*yrN923g~y{S z%I?W-%WaQCRPA>cobBc$%2E1zm$FBvaIR{bDDUgKyrX6Q zb24swh&pzLg??STA1vlsQXihSduG5IS=m^3$`v5SJQ+jqudgaI%}-> z`aW3sjtUZGzMT}^9tEp$K0k}xv#txDTfwSPpA@1&(**JUbg+sUKiIJ}N0Ml_FIXj? z+C4Th<6Y5aTd>OW!$xP}te3_7<-w|3n}YIa=ffgSf6qdr$-QNP*;_=HkYM#&^i;V$ zc8)kYK3Ms$SSyD*MvKMzd%nu=h?9G^R~A>h1*V35@oqJIh|E11*@LF>3uW*rt{CD!D^Y;Ejea-Rhctqu=+IjoV@gSjBJ%ESbZ!N zC%255E6cwPQu{uxksj5z%6SihRM*o} z7w!#G#Vf6K?#h=Wmu(JGm5Tio>nxQZ-!2VOhx(3m9BFc0dPWDSZEaJD?(}RLk znU+n3r`I0&d`ysfS3g)3O14xM(%;3l;`S1;eQ2<3-8D$H@4iQjTHjP|Z5E{d(BI`+ zZC5IJ-q7E_;J7XZd>G|yQXxp)E|MUcU8(M|uyBz2_I;9Q`Rf|T^6Wt>u+d$yB29kr zEJcvI>3vy5diE4KUI(hdFAt00l~cs(`+=%X$F1W0^)({9{?3JFF>}SMjB(y(`W_`kCb5(ShnnyUOy@**LMRf1oOuG)gu+vQ~`m6sVG-=g7=*s`x{H z*WRCFw#X5G^cDdkP`#^lSmxheP^>8zsNR3RB(FT(=y+BjP;Eti@mt{l!oeS4odBy68BXVGe0QI%a zFQQ?tZSqZ{05x>iWUX%Hn#r~WX#lB1a zYWL*xqR-V4;`L#FwPDOYadFFRacH;x?t`i8g!hikqS`utHD&cQv19omaV5rIrA*#W z^qY1`e2(&0As-8iQ%COLzOEjw-{!cPCP`HH^j9y>26=QDmmp^M@mJM*^>jKvT^IS< z`z!yp-<+!#pAtfUe`W5c4Q1u{STRF?uVwa@f%5k1WnxPye^s#ZVtKensCbdjUp0HN zOU_N%N_5NUum0+OLQd(HUc7!kNrg?iCOdr%bey|2Nfkb&zr+2*8{9&gjaCvW4ocaylsWy>yBC{;GvBYW-P?&OW12(aRJ~$yrT*Sqk0O^uhk?7DC0r9# zo$xziz>Ybw-xh1lr$iBRr-S3T{vOq;3lc=l)gK+V224~3+T9SlWqnbk=|r`)#A)Hx zCO{l1H&HpJJ4N5Fi^TJ+6IH^5<>I5Rf$aaLVleggm?}D*WoJ?v|eK^xAnv-2K^C<^3U- zjNf%s6e+8}D>h3P`Dp5PQ6jUi+IlHcde)2)zrXZRmq)FVliT@-^H+S-s4RP>F4Hc$ z#rmjQY0t_cz7HL1VtmwvpqsK++A5AeC;F%kxf11*Y`0^N_4QE&4kpUh>X>tIV;>bT z@3uTQqpZAA+DFy#xga0K4wcn)z4{D$_sf^}XUg5ryj5JG4YFs2O>)sCZ}r4yhDR)2&QmzkR0ktcn0?foBI&Q(tn<*Z)bs@Z~dvA@M7$X^?J zt9rjQca&OtLk5@fR-PZ;IK+n2@>F_nbuP57NM2XUK~KEY$#(wYW78Ef;JlaW>c3F5 zX%;Sv?DA6H{yRm9PVHp6d0whyt>dD{=ghK+x0lMi@2VI$X|gk04=;6Yc)Ymk@v+7v z{hb1?@=4-N>6wnKCAGe6y!g+2KZ5=HBkX71E1iQS&P08O>=EaDno69B0{l;k(Lt#s z&P1i^T^HZ|ILe7LQH$aUV)rKx51fg*>wAIo<&O~kVj1^0!oTD>Q+x=BV_tCfLOf=~0 zO-GZ#iF76^v_F?4G$4`AL=_rjbZ$|%=uGsg$yMjQbmz@8QD9~H-GMlPGtsfkqh-IH zYX#0kr&i68wN_6RI1{A^*&=^&_7*r3B{VxMjevpzXQIq$F3WM@8yz?kElG1%ez&Wq z2hKz{^}V3U#z9V;iKe$mkfSQ5pfk~|1=r=a7C+OOXjKNC@AU|xGttL_v9e#jC3Gfg zd~m6Z-nE;~L}}WF$a}9((3z;iy5=(9{cCh4T5>gw?DsLA&O{fs_&A&BdjZZw{hQ_V zsN{8*&P1M>RyZo&zD#GLKcD0kpM8%=oQeAR{UW-h+9q)(8hK)}csy{P#F?mKp*7-s zq45%DqR5f@PsKi0mpBt$$aYTb-5&46nW%56TOvj6LQb5ChPF-=O^zjZ;7n9XGKQxYnQ|orx9&o)^_qjHEMB!hn6^>cQD`Ci*;ao!ES6Go6X9MNbpXEr;k# zl;?6^5i{=+or%=08%il zdv>EU(UY7aSvnJSt?40;+_*_+ zqJ&@XIbT#wq%)D)Tgq8xQzD&-vdw?tF`(sbIuqTvdD?OE<9Rw0ElF8Hbji41;!L#S z^>8tx@p_3f(bBuK#7}{y(M@_bGdf2{53z?rDxyaZ7+!zTyML{ZIei2V=i)0t@8_ov0;Ujyh&ew~RF-YGF za3;E!V)~xa_wUk~Xzxx}$U^s`*nFS$WcSfiuyAKO^Ov;xPhe zqKv_-rgS4xEXCB5%r?KUH?%Omro8qRhJbPAtwu z)AuLJHpPxRaV9z*eOnehSeDL2gGOGEIqwgpGm+Qk{j%JLnRF&9lx2h5UuzSciG~cC zAsdW6NN1uKDF@0ou@~t~)V6bR*}v5tIul)1(s}7wBAtn@rdb;s=}Mq8QD~_aj$F%b z(3xmLkGGDZOHb38=)!#s9=4(wf|D@@)7rghn)VtpO#U+I#G2^4MN5()cXzF2P1JS4;^fE&zpQ0V^wT$UlF372t%>&9dPeft8-ukb zT4`~T>^pUW)(E-mt-ibBQ$fZl75tHhwSQAayz}}IC)>;#N+wYBNy(dr7nrPA&PesGp*Jw@D za{S+;VUOIeHPMDuW1{_beM)PhcH5p3tvd5{t%+JKZX50Q(tNFnR@&tsRYP7~qBYUY zi)M7{_se3fi9Xw=sy5zZuGU0LmVZ+F<=r#1Ci;BO-IK$wDMhS_3Nr^K8_vEnVomh? z{PD?8n+}gy6WzS=Bgy9H9u%=ATDJ9bNvo6Bj#v|oT4`4D(T(G(SQBl#=AvZLv#tKb zn&?o=5nj9Rh+5V}>3~JaKTm9~HPIDs&r0UJw4c^QCmsEKGP~JTS`*Ej^k{PLdUt3| zv|!3j$y)0sS`%GZGbDL$*vncI?Xhl`twra^sZ)i=l`FC4Ib=N+fuqJxwz7wL0j(8wpO>|_J(a{Z?k4;z; z&H3cM=&<5x32UN0W1fs2Zq*@SO*HxN*Q0$tdA^o4(Y{yCkB)t9@l@7CXQWG_kM7!` ziZ#)z8!w5P_xYfTHPOQB=SEZ4inJzLx9uy@?XM5en&{lBC!!yg->5awd3WCxJ$~e5 zt%?4;=7{LpQO{~kbnW$rL^H>~r8UuWQ`U`+oxf0PqJjO!S1q-3uvioAGxnxG?K^Ri z)Ay}sq7WbGis+#T%tA68`Hm@dRM0#`>j)-xGV!4X-*107 zD%SobVNEpS$7iCG8?;PV6Aj$ut>~@|{#MJH=$pG2MyJ31{^P8PW^c1JI$_2oRji4k zS&O1apJ}W$(T>-@9i4aKK3WqExcG&rcJnK=CTh0XlxV%PZ_}FShZAmzZnr-H!J4S! z)t5#!gI>~_=!O10qI=$*tu@if@k-I$Qx|JZw9QjTRgG%0RBNK?tp`v2?oIn!Y_=x) zdcZ@q%kP`1HBsA>Hc#qam>#hv+I7G&$r{ThMXZUAKjqqF_6Or4)@(0nrN@Rdq)dqPDxl3UD)RGXszPk64peY-*Rj8*B6E+tchNK?eYJ1 zJt%)pQ~kM1|5@iQ<HiPs&d+?}O6^6lv&9SjU(&hToSj-&K3C^% zb9QQB>PJ`l+2YZcKj_?T&Q6W?X`G!c9-YuKJ6k+z*(N(%yz0T-va`iIUECu(TfBCq z1G2NllQWLZ&K6I$JtsR`Jh}AJ>}>Jm<5Ah!;-$rZ%gz=rUGZRcws>i~Y1!H0rLUgP z&K55nch7IPUZ$|%i?)Law zb?&y}xcNgmcUy6sJx%9sa|Uj-w$+b5Smg!9@pP*zJ>T|o&cKbX{6yz&7wk;xsMF6n zcbhYCt6p0@J6pWdts7-$i`Q=1E<0O18PzE}TRhpPS9Z2|a>v2h+2TpF6SA|#ODmt3 zoh@Fv=Q4{$`3&6BzGHQMI%gS|*11LJr*oEZ>GDCpox9y(gwEYo93L95bGH@8lkd~H z+lu4uwK{iOas2f;ox80#wtQRXZkITB`-S&(?lxx`*B=WZ*G z*G|^C+lu48PwCuk#j)S(I(J)f{Bp6*-R4Z{PEUQVbGJE@y0+`DI(NJ9<&8a(hnr_- zizlaTnw>44{A1h8{7mX(yTWCDCUvRRUOGRWGpS3@_tW|5oJn0e!|HA}Ru#vN=ji-& z#qsX_emi%&_fa}`TXB5-44u2JI1ay9=WZ*G(?{yuZN+i(n|1EC;@HV*OjitQq&R+L zwWk9|tfM$y`jXDwRvh=At8=$GTfFLx4=&~Wbj}u!y8QFfERMf68k)uNz?M2cowLQG zbQ_(YuIF)bN1dOpI3Chn=cg-<%lqp5bj9%>hwJ=wJ&(KX{@c0R^Y_xZ+lu4Sf6=+y zisMFq)w$b>;{pA3?zZCi(3LuOTXB5hI-R?%I1ad5=WZ*GYfsU++lu4Te_Y~c#Md4> zGdo*6d1GmIwsgzJMtrjGnmRw7GvZ6#HrM&-isOgd>-==Z zaa64H(-p@9tp;afRdIZ-^>62HpKA4;bzXi;as0~aJ|iDEKykeP0G+$7I4(O@=WZ*G zozK>}+lphqOLXqG;<)-~ox80#-f`=Y?7e#SgW1{QRbQt=vN#?yBRg9>+I&HFws>^j zC)wHJ(ZV0Iv&9QDo9O&>#j*c}IzL@;+@hV%Pgfk@-C5_SD~^*|4bGm&AFBs*kBZ}} zN7|X)4;-L4o>Droq{J^|so<*?V>7+k+XaisNopZ?dtfIG(V6cD8t@h8?rB z#cLbwmz^!1yn9A=ws>;nwb|L?NwZ1W+2YB97qhd)OV53foh@E!x~k4kR~#Q+N9U(2 zj^}Tx^V1c_SHBw=52@8hLEUzB|xo3E+!(`y?|-?%h;&cJlhkhxX2t-EPym1P6dE!V55 zx_6QBX9Lr#4qUtHf9j0sd<}^AzVC~x-`iHdx2=9}Tm9a)`n_%Sd)w;ww$<-#tKZvJ zzqhS^Z(IG|w*Qp9ZIyoeQ@>ZOey>{nUbXtYYV~{7E>G+Cs@3mRtKX|uzgMk(uUh?H zwfenk|9N}W^1s2^c-Iz8+@Gnd}jZ&;TsQDHU8v_y7wQD?$T&cvhIUVL_ZE2 zkUro1xn%Wg=S0_zACUGt^uA>O8DB;X?;ntkyJ=X`d&DY*BTEBp&wTHs`PEGdH@!3< z?YhY?wPU6=FQoGZq^mp;)wcO%jl%Sg2c(Zb+O%rD-J2I4`e{J=*SFrUYJXef!cf}- z`OZb%qDcp=T-bf%f$3(ST^Y^%<+Esh`+@15>HSf!QM00BqJiliC%qhf{d8^g>YfAB zzZ5@=x!#64RjvnLNsJ9JyW(BP>vlZ&4k zn0`2H&BCIWu1_Y-7?_Tq-K22gJ&z^SAJ;y2aC00ZBpuW;-GZ?zRy*C zy4Cunv-TR4K66XY==?U#O6zSmD7|=4O*CYeUy{G9IVgSL3i};s*ZIkw-wsUUAC^Y! z`8nZ%-)hqvjZ$rz`g@_pS*lG_e=pp;pK8<8ZKL+Ps5VXAHadHK)uyT2+Fpo@ylxvU zu-_zxeH2xbYA^D-ZKpME%IdbY%`eXCw#g1hWp&%+vCdiDHfh`{tJ@~Kt(MhoOMAaR z$m_PHm7cfya(Q1CMaP2Xm{$BciAMG)q{$7e> z?J-~9bk=z3LPD z0ln=NVLwc?#)z!`9*sREtG`F@+dk^Bk0M%c$E^Nd*mmu#{$5!0mBpgGucdqBw4_oA!z*j>}tX zuL%1nqJ3LxuL%1ns-`s3UJ>@gbb9Zf**=Qe6F$oJQ6%5Z&Gu0w(M#DrisYSAwvQqi z@IbbYqICH!L$Ww78mT=7?4u}kx>$P**hf)1=REB(U>`+kmFs`o^K;l$+Vi70&bm;0 zeiX+|Pu89v#c^3b?fFq0uj;KmKZ@fSyKB#n;+Sr$JwJ-$Hk)eC5Bp)J9%R39ussIs zYpQx{dA1)WI^m0KKTI@nakd{O>iha7SsXul`V!yQRQUE0?G<4^Org)6+AG37io(5P zwO53F6oq$&Yp;mnc-G&4+q?DB&Dy)AIQAT=y<2)7uNkbpTZ&`fGqiV0as2)$?cGuw z7w)IMTZ-d$UA1>haU8d^_HHST&upc=TkNB#?XjNrZn3W^nYG$b-$#*b_}!(xk0N>c zJ?;5nA4Ss7eybAp8J3Q-->QWDX{EYa?fFq0Ti&NVKZ@i2w`$Li;<)6g-}c}Y9?>2= z#qqH_vI#_$~6vx$iX%C*_xNFsA zSsWj2e_8fC_SiVvpB7!UdbU3;+WBYg-C|!;^unjwyT!hy!kY`VcS~{H{#EVWQXH?G zroCH=7pEqQFmY@cEB&n>cjhRJPfW%~@1 zP7ShshNbS`Xb&Fyno2h>(;hs<@w+#*2TyU_=_T#KQyicC;~4_6M~mR&nfkoA$&ij@#8-;rp7BL6=_P`6L-t@i$-g;$@Ysz_im8w7cD$uzX!CjsyH^czmeka)e}C_UP{IBw#C{@ zsW|Si%2mFvsW9wo?QK>ZS6!yP&5C31H?_A}aa{Wu?QK>Zr%buh_ccW~-;?e8jXu6U z+xJ`5_o{5)Z>ORCvwgp{4Nl4S{U&1%&G!8!Z}-mj{U$?p&-VQ$8*HEL`z>v?dA9Gj zG^jp+qKhg&h~Fl{d#1!f4k~z`>n2j9~;1 zuRH(pTGcb-H!U>lI6U2MYM-k7-@f~J)IX9@lSZU(%^e+84Spn9XY`14(d!RIFKly5 za@)Bh(v4coh|b^e@?_(FBhs@vycczxwO?|a{SCBNru`Ic(Qn=4u&wQHolS07c=6G@ zYCmW?BAs?@^Fs69Crth9%i-y&U#wO5QZY=g0N=a*UX>=U`-Dm&vv3+(vKrYfWBf zJJMcBe_rN)Fn97IR*+o%Jl{tY`GQ zPUKl!4`Vl7K|-B>sfX=>v`5+%09gKbT2V7FfuSQmE`S=Y3bpNX*)|= z%sJ6^#oIb-^n({~VG-2HShGB7eQ zGL_`*Y-?T1+17T3wV3m%?QCl?=T@WNbs`TVpSPRWQ%OGW54Oj#OJVuNRj0}uSC3!njTi0@?ww;|V=3Hz$Q(Me=+30tj$iv9z?dJ7VlF$2tE%dl8 z7+ZFxw(N4I_Q(@26@UIjnUR5!fsv^sZ)bVyTF&yeGrPr{$8BeMi#ewo{jL*v82P;2 zyq-$(d4I5l9=8Q!%g*waUC#2JdCEZXh~*oLk%5tck*OqaXNZ^mw==};tZ*^sfZG}3 zV$KIgzw1O^KA3#oZeC9%`Mf{aLXX>mv1Mn7%kC?7&iDm)A1^M{L}FxMWME_}$=liG zx|Xxc?Tm6U=a1Xj?Mjfsv^sZ)c|KTFy+jv(d$zdv0f@i#ZP+{jL*v82P;2yq-$(d4I5l9=8Q!%g#)f zUCvCO^8M!GjX%0jj0}tnj7%kYJF8vSa#p*Y$u8!+bvvtF%sK4ncb&+?$mi|m^;DA2 z`-3g?xGfl4c2>LWa#s7(^IC{U?{SG385kKDnM(3@M!c@&jCeZ>Ud%b~c1FCI^WV|$ zI+2Hw&)d!GsU)BG2V3ZITQIiljCk4QjQG_K{xxCl@!HtS#mK5#K^$N zz{pgRKmG1mx^~#`n$lgxrDD#tU%l>AG3VW*-*qAnBcHdM*HcM8?+>=n~& zF>3#0P3fDvr-~06d9@fB7#SFuO7d4UeOTA-efPN1D@&gczmtwFHM#eB@qlN?te_Kl zbRwU(o7Y3T`;eE<`-3fH+!lTq2< zqsxpl&@dhIUBLgE-Nq&6QS6V~uxBrCF zozvEmo|<3Am!9w2UcB>-W&N%bc^LV;-MpT>4|(~#KiEQ#+k&xm^c&aeeHHKhRq||2 zc}_Lz&2PoXz{tSJRFXg9yYf79wdPGr%lElPI+tCrYU$|fM~Y|M_sa@8kw+);dAoT% zw7U;^`Mf{aLdI>uvUTJb*`2)qjHJgd^u&Hyybw8QHf++~=p+E9gWXoyh0y=Jn9-KIG-|{$L9kw*_OX`oQaCcgW@UB>VO# z_w#9wJt#&7Mg~Tvl6;FX<@^0%<(HBRt{E$xk9MAxEW2==xb>-zte_KlbRwU(o7Y3T z`;eE<`-3fH+!l=T<)K5+uoIQ+Vgtp z?6m!jNt;#6`kQQh%?dh^MN;mJ2j=Y2mNmrVJp%=5 zGNx-;|K*$hEd8z%c^LV;-MpT>4|(~#KiEQ#+k&xmeB+yRUmvuXJoRMzPV-K9wCmBe zFfuSQFfx_oqwCB5fBNf_wfDbV=2Ne^w)Xh1%Di-=-B-|wJUWrj+s*6A`;eE<`-3g? zxGfl4t=}!%ePrgbRl`3i-`CMq*L8xCfsuicsU*)iOY{jj+RdAm`GU``@6`3@vi|Qs zY+1E5wBNO0_|!(t%Q8o`t(v-DxOQpV+Q;*Dk;g9bdEfGSD#_=4#y9l1Z?O9Y;~W0K z?hlMV9k(p|zr~l0q8$g6`{#h`OI0v3FfuSQmE<2u*!pqZ^89w(hAS5)oLkO|{{7Zv5sVCsjP#pKCHcAcm;2|y zPZmWRTvZ;=C!F&fN*L4N5+ z<=prtM{HO)YUPME9gYt_2=#8_0aAzdHK9Q*h0o_!Pv68Re|qvsAq{o9j$;2 zj0}uSC3&lD=~`-SRyz|@&$2p~m^zo$#WJ19qcha+GP`*_mE`mOU<*BN3&xh!t)w&5 zv&5l}CV3bc97T3%j#Cr8R}W$P)Cytj12O~RFdz1Zf9Lft<7p@V(M8|=Mq!rvbtEN6M1xo`dwx> zucwlH-XCnC$8EvbvbvRYhI*Db)X^jlBZE9LmE^6qrE96RS?x?rJucwlH-XCnC$8EvbvbvRYhI*Db)X^jl zBZE9LmE^6qrE96RS?x?rJQSzRpCi99+({Vubc*HcM8 z?+>=nucwlH-XCnC$8EvbvbvRYhI*Db)Y0Svj12O~RFb#amae7NX0bi@wW_t<`@EQX zmesk$)VZuKmgz(uouPi0+0E;zB%k-k>U7fMw$OS&UO zkwG4rO7d3Q(zVputac`*o@I3|F?BAhi)A{IM`x(tWp?v=D#_>l!4`Vl7K|;cPgU{W z2=y%K4|O!j!^j|yOeJ}%ZRuKSZB{!IQ_r$GmzX-2)x|QM$fGmV?=ri2J(cA1{$L9| zZVSei)u;5n3iT{;sH5pU10#bxGL_`5wxw%TYrB4=n0l7gxy01DtS*-6L>`@?ewW$J z>!~E4_s8mV(&M(!i7l&7NoS~Mi9;Pt@-Q;UBU4GucwlH-XCnC$8Evbvig*ChI*Db)X^jlBZE9LmE^6qrE96R zS?x?rJRDFj5>w~0y4Y_zO&*=0ewW$J>!~D<5AF}PV7CQh%j#3o8R}W$ zP)CzIj12O~RFb#amae7NX0bi@wW_s!Rn|#8%j#Ter_N<{u}mlO=nVC{%x+#!CHcHR zR;QC5w}nn@SxrhhL#;|2>S&UOkwG4rO7d2>(zVpu&R@B#bNlC3s%pAMnNK|J(?40w zE7OTQIz#;~vzymbNj~onw$S6YU~E}kNjgIvN*wB6l82E&9+^t=R+G}T)X1#nC8iE# z^(is+DXV8?I*~^w^0YHI2(`9MPbK-hKiEQ#+k&xWbtUNubtrMDe@Pxj26<#E$y-fI z*HR<1nwOY5l+~xi)TgYTmFYwtouTfQ+0E;zB%k*OTj+6HFt)6&B%PrSB@Xp3$-~GX zk4ztn=`jnXZl-08`oyemz)ZH?>c|Dcn^ZsB9J#GuemerM{Gt{BP zq5dU#7#ZY|sU&YTDP2pA%xYd@>QGjn5>ubDdRC?rd31)lTV^+}r;>c$A8et=ZNb>G zx{`E;I+Qrnza$SMgFG^oQh$F%5)-+&QN#D?B?}UlF$2t zE%dl87+Y3XlFm?v5{LSi!~E4_s8mM(&M(!iLDFU^pehJ2Axqj=lyc+WB%Ba#K^$N zz{pgRKk4c!>DlFn0fknBWAXgr1%-PK>n6VL!IC!$jj&b!4@)Z3&vK1sIBZaI%jC1?=LOI2QRotj0}tnj7%l@ zmwIiWYo~R(s<6kzO~p+fyrMAwhgRacmY1)f6M1wZpSPRWL%aKsm(TlyEo9sljID*& zc9Pw#9~oF!@O&Hblqu(kk%5tck*OpfY^F(1|=c zk!IC!$jj&b!4@)Z3&z$3^N*81%R3!V*miOG8Sgi;j~E#k85o&L^0hM$mYz*6 zIJ(fc>tW)mtqw0t9e!IC!$jj&b!4@)Z3&z&8-OBI4pD(+ru<^J?@?ooshl-Jbk%5t^B>$}ay#T(~Z#;W- z;k2&J#3N50QTTlNTH@%}VJqlF9-YYN?dJ8+?mpz@^ZsB98Mg&vYr^%b$?l(;UQ_7S zwOj{jan+S#WME`qWGcze*y=;&Y@eS#s_@geZ^Va>y|ysq^X1|T4jQ?FPUO*veBN$e z5AE(lUOw*+wvcgKFt#pT@Sg0p_;pm_iQ``scVBIU7#SED={K25@})1Q>)N3m#uk3L z?^SX84r2=Y_L(RCY2%s|bRv&VehS%-}+jG213 zc-yb95hDX510z#Oe$ux$>)K0yysq%shZDu!+h12$ea2(rC3}rqK_~L)L_TjfuZMQ` zAupfz2V2OvEf`y)uA3mc?`(N}VdRmQil5wflo%Np85o&L@;5$kx~^Tc-HnCE`wtb@ zjJ%<6^tIQP^)D*xcb&+?$mi|m_0ax%@_B!-g^b&R-!WS=7o04+SNFcL&}*fFc+7e= zVq{=sU}P%E&*;B}u03%2_`)|0s>HV(IKFVs!2QGr&o1kCoyfz;=k4b8(EfY!d4I5l zjN5{-b3Ky$YmFm@QDopvlk94m8Nm;+^L>@*yZ#S=p_TQ7w`-3fH z+!l;2)AP9dV|r@ga9_1KosYx#P)Xiw>00jH?nR7#v#Y-kgI)ByPUPXxpPAjfo=Wog z;Qn9>c3UvEEWXki#)CMFL&?L)AdgHXc^exEeZp9^u_tCc*f^0+#)*xqOegZ_4C6nu zo7YoGKJO2<(BrmXY}s=vAHwr14(|=g!^j|yOeJ}HmUS)f7JFBSd4BD=7V})&dmz(^ zJUYYsDzlr{Q%OGW54O=K^~b(^7ii4wR{Wg-CkyU-`aav z%zN10+nG+}(HXuknccjeO7eMsuq8dg7K|mv1RiU=?wFkvJd5Xl;oL5A%i?J zmE>)1qidOu+1yFYe8%QEV&*wEFUoWxkIpcE%k1X$RFcp8gDv#9Ef`xipOnrp{}hLL zZ`rQRdyzpNnM(3D7cKGLU~X)4UFl)|Y4cJs^HQ6~W;&5aXP9qicJq2F$>;sS7JA$k zj4hl0%b&1b5QlY&?83+(k4z5wl*fb%dC8gsnR=oyemztdBCgc|Dcn z^ZsB9J#GuemaW&MGpz5#VO=SC7#ZY|sU&Y}JzdM%)7Fw=)_1n<6SMBKbz-Iyd31*L zY-TsFr;>c$A8et=ZNb>G^|f?{^|(0X0VEG2gFG^o&X9k|?B?}UlF$2tE%dl87+aPPkZh{>N= zUPVk^#quzjPUO)U@o`7X;sS7JA$kj4jI#OJ~R@i$fk; z@-Q;UBU4Gj*#g@9-X1yk=f1bsU)BG2V3ZI zTQIh){vw^BULy{5BFV$ZAdgHXd8^&%T53sF8xm8mu{us!r`2(+?vv?69-W~+mD$bf zsU)BG2V3ZITQK#hEdAw`SHS%LHtg9=Z2y+*zs2_dOC~3_>k_+OZ2A(@E9UprX3yIrZ^w?yW5@Mi$My5C+vWee zKV0X2qR;)u4)(%*(Vm3+LS7v7l)`?1;=pQk5 z=*M7}{uG-(^s|`j+)wnm|M_@1-?7@gPvkksN3;h$;-J4kJNCIxIQSzDeu}YA|008Z z(<=`5>+OmoGNFIe9{Np;9pV@4Dvq$n5ylSJ!`M;(8hadb?MY5v>~W+$jFS=^?23aw z;^3#)-s1>+9Lsvj&t0xP%E^oC<2BU#pZA0K ze=1%_oN$QVlfNhN~Blw|`6a z-(vg!iOGrWy2P#*o4&;KiW!Gy&)Xw!$BxTm$Ms;x_4BXW<^Q`sT<3nG&;7>^_QHM9 zp1?s~9Q25T{!+Lv?23aw;^3zkJMrlHgFj;I&@aef$MlNBeR;d$g-qxNwTJ!@6Ce5! z8UE$JVUHIa`d_|bhkm5p;{}KIBquNSc+np8m*8Mm9Q+XnKgAv|ES~*ykZ-J(}OD z-RB{+`*#fv_azyhhtMASLG3;dq21>pu+Kx_(9e<&{VzX#9)gTNU$8%4us>gLh`aj4 zpD)_|`GWoVg8lh|{rQ6Z`3mjz?@8;E|L%Ko)V#kHCr_!VesI7RF+6tgXmN41d(^)3 zx$WY4JKZb(^~JXFn_Em2Ki{-%-1((4Z&KAJ?zruJYHxa2>v(DBGJoBFoA}|zWj^Z0 zt>dnjm*ro1a;x~rq^$Fz?^?z0K2WyRqjRhHx)bk~o>T7FGG6$_o#OMh-ZH-SfIGx3 zp4%cGbIWbwkFMDw#!r04PugMHk%y5-4~!o4!|2B@j9vVJ@drO){KS74|G6)i`{I6K z?w5Xm=?D4;rhn)+n0}kJQ_tP$XZ(a|hog%xRy+N_)rn_`@xR;S$BOa))i)0k40s;_`lhYWyb%~$~&qZ|2I8wS26y- z^YZRu{Krpx#!uS)zL1BJM-Pl1^uy@KE{t9Lf#r|+3F9aJ!}!mA!Q2=33v<8p157{A zKQR46zrpm|Yn$z>v9a{kJ;b!bn_ak5*1qPh9mTB=>lOFv`6ux&&-aQi7#E56TW8Ps z>ZY-H)v7(?W3TR#@r5h*$Yk#Mb1yO1E;_om7@gR1yR^f!BM&2w9vEBbhp~lSXZ&#) z{Dip{|6z3IpVR!a@L%bNyq}fEXQlT;e%$8A#{O?Fe}Zvddr$8e#!q;a>NQf@cbn8T zuD)SS@m~+_7Vmie+TvSVc8{C9w2pZ154*=-T)nRNh-Z7mdrv9zdH42=KkiZH#>4iA zn^l+P#~!1g z;|I@bARaun>?c0sC+#rp$iv8^2SyM2Vf14c#xDNA_=BG?e&Roj|J)bMeR01q_e(#( z^aK3^(?9eZOut>b>+vP}^NRhq7SkTM;OzrWs1kR5cB}Z;{Tqu<>9gH*!B05Y z5~I_`PZ58J3ychGV@&TT#+b!RG9g~#5HE3vmpH^r9O5Mo@e+r4i9@`^AztDTFL8*M zIK)d#yzmpB@zdfc|HJqfhw(2C<6j)czc`G4aTx#NF#g41{ENf*7l-jL4&z@O#=kg> zfBF2c{Yl z@zC8L5MTRdySTx$N#bEAwTr($@*(l6o3)E)uQOS^_V;b$39mdNe&(CDaf8bq6K~hD zUHn6v$HfO9-Y#A;X{xyIGwtHfnK4IEn@BhZ<_KfR#m+xzjL-&Zs%`D&V#f4t+(Jjinr1_rl z2CJ3(r_sxM#;-k5tN!V5=3ep8&gK5>^X*>oQxm4B{jUf2j{iLGQSsn0Wn0+A7VR+Y z$iv8^2SyM2Vf14c#xDNA_=BG?e&Roj|DPUwmh3XlVcOxI_g}1b?!EIigUY_y`@dK1 zg<_tU`-hw-<~fSSoGs@0n$Yk}G0)w-pPnY>d3@*KQ^h=|tL}G-nCJJ7#eWs^TrY1@ zZs&P_@1-*H9+^1L_j6QA*uc9?eLVdT*RqX+#k`mqaR7k^; zhv!txbBdq%jGy-Wio<(PjJ!SX;_%)RhxeX1y!XW6y(bRuJ#l#NiNkwO9Nv54@ZJ-L z_nw%3v)IXJ#wU!=u#E?`^Q_sp6^C&v4&zoF#;rJvTX7h-;xKN-Vcd$txD|(SD-PpU z9LB9Uj9YOSxAGZ3Z9I!k z_udcraSL<5j161+Xr9Bm7^WSz^_1FK!%sSfE%i^$J7Kin+IINe&VZAI4>t%6R zFN?!^Ssd2O;;>#8hxM{Jte3^Cm+=#y@zd7P;*ft3hx~&$H*BgTKr|A_J5@;_qy zxBQP7|1JL`#(&HIi1FX@KVtm1{Ery_E&n6Nf6M=f@!#@4V*I!Kj~M^))5iwwFzv|0 z$fE~F5Bg#BV;9CQ{=oQypD=#nKaBs}7tDQezcBYpKfv?@{R7iK^czgSSx!Jchn$Jp zLoOw2UvzYDamZk!k9JbogN9ysJ` z#35IcvE^7Y8OyzhxfcJq7M=O$H2*C8SNb9EXQlC3>HUx&xB0O#Zo5@t#`)eqwT@x@ zgnJ&{NbSFDzir%fpEB3&(INhB%`#tcV*7ahq=u5&W?Z}Y@pffiKC5j!=JM6lK5yr? z@oCSkDxUH{o4DDx4a7I~ZWGU3x6D_zXd_!Y>{nBbE$p^jW_@nl_~1tI&&J;m>kz-$ zsZspd`=hH5_^^Ha{o0M<{XVhrd20Lk%Uax^C1(V_u9v+@7E|!`_xpwc4UXR!{LqMS%0pnp89MD z^@+xz^$Gn3({J=AOn=hPF#Syb!}LFKfr$(8f{7P#goz{Zg^6#?oo^Kx5A;7wJN(V+ zi`CB9IKQ}1j1LVjnlHwOZnNi#@!|VJ=ZNv)!F6Vf@!|L;Z;SC^ryjG!_|RlV*)Bd{ zYkIHpn1qK~tg*Z1m_@~f@7j9v=hpGD%@!5=FCJa}x0Tz(rGX2JC(j>UJ+x_?_}yg- zicin6ciIMR;t9PM6vxaSUHw7(Ht~j!%rCxdd`Z_f@!6ZrFCH{^boCBLw27yVnpbSO zV03kKQJeU!X7h^Qo6d!|w26-zJGc0b+4|>GZQ?!K&Mm(D@#yMK@3x6AdtpxTwy(^e zMs4Hu`p+ru|KsTDH(R%jn^nyzzO_nC^>ba?#*H_aQ{22sP4$6)ZW~uEpIz*?W=-`C zhqjG7em%SRQcL@$9NjkF<(t{XdpE18wgWlhX{*jDe$u+8x<$XX@oJmRDfZv4rh4K& zZR18=<`f^6<=elRSM2eZn(B8>XcHfH z#r)#-ht*UU_i7WLvgv~2%f{#L)F!@U%7S8J<9O3H@gw^#EY9dxQ@!;XZQ|XRE-Y?& zP)+rc25sWyr!FdPWY6sEUs}fxPg_*n(d>R;F(O`!8RA7ueOwW1m{>CgV8#Gr17>V6 zW?;q)V+m#~F~(rV7-J7+?D^Q(q)m^^t~28YX3U&y&(s~;^w5}@aX?M=3tRNim|1X0 zP4&AiduYsDc4$rYK23XQ%sgWEKIHrE8Z!fo-(S>SW9AF%x2k`1*O=MCuHF8w?iw?F zOy}^S-8E*8HCtyM)m>v|fIZ_o7Q1WA+|||m*|@vL%s2La82eKb zHrv)zuk%JXjhRokw)eoZ-85zfZfbeRr@Cp(+_HX6^(14)%wO!?)$fIF8Z$HOoi^>w zZW=RV>|M9svThnPi|ifP?7MCnGjDw}y84*4x@*i#{d9Eow>x*&n7Q2Es~aBFU1O&A z($UrD^zW`Qv*E(g)elVQt}(OnywTN{m%3}rY+%nMHD+RKZ@*d( zjhX%?-+kR48Z+B0vUqLQLt|!Jd!LWmx`)Qh`X7w09@4rTJI#SDUjF_$;}AVQKGE;v7P~&4@yEwGe){;wfB&vw3wFCO-#*&;-u1S3{#iG4*7xoZd#2W{ z>Z0%6w>F;7d#sDTck9@9_imiMH-_ETRo}ZB zd!L;CL|1+9*0k?e&)2%@d-v%UHsZOYZwX42&=dV;#{p$Fx`raL9@4)-c>Zjpe*flT*T2R11O3^7{k@leH%=M6xY*0)Mcmi?w-*<;US8%G)?HG3 z&AwB#KeEe`;tv*g=Y4E!z{p(Cq0C&{YPT|@bGeN@WU$3}hWoYrzIdU%6W|?R{l3_r zZ?W-Nm;AGMzI~(N$!&iq9=N2;3#R>0{Mz0>v>)2_$Ku8|mxDY0{m0_SAIiM*k3SYy zS+#8I+jc({Tem3l>d{ZdI~cbnPy3ek4TX{Ku~V7RQ(GuA`a9UOgA8{2+VchD&zF76 zjGwRDyPbCYpJCqxnEQIgz6J25M}C*JcX{C3On#+?-)4H=I{lkW|G}Spo!K3H>DQS* zLppw)`I)Zzb>{y)-+Yzb7wvw($a_Da$NLBU-f!6T{=^^eXZ-a3$A6DY{(bB7J)S#n z|JQk-k3+uiJ`Q0Yht9t@fAevOjE_Uu$06+F(3x@QGK@pm$06+F5cY8h`#6Ms9Kt>h zVIPOEk3-nUA?)K2_HhXNID~y1dOPFLlaZh>wpa=G`XLG-lxnEc>q|E)odLd=*7uE|YbHA`&NSXVE^+L+r zFRT|*=6+$lkTUlR>xGoLUsx}s%>BZ8A!Y6t)(a_fzp!3NnfrzHLdx7PtQS(|eqp_k zGWQGXg_OBpSTCf^{la=7W$qW&3n_EIuwF=+`-SyF%G@uk7gFYaVZD$t_Y3QVl(}D6 zFQm-q|E)odLd=* z7uE|YaVK{6&Jhz|n>&eF589kc9M%rvuyzoKwSzdU9mHYnAP#E>F>42GF=nu3b3bud z&x*r(Rvgx|;;^0-hxM#DtY^hxJuAk48@F}2Z+e~ErQP!$HutMz?iX?$bX`e5Tt^*qzmV&wW9}Dn9d*q8Law8ZxnIb2)G_x9 zxsE#Kej(RU$J{UEI_jAFg3o{=49q7J=`KQ{$ z{8Jp}pW-n86o>hzILtrAVg4x&^G}VvupZI)3~P`&a&BP_Qb*1$tU>C?xrH@I9XYqK z2B{h|hScBA&a|>&bI&yAd4N^zWEv!N6$hn0zNF6!1um-6k=N8r= zb>!T_8l;Y#TUdkCk#h@ckUDa1VGUA8&MmA#>d3i;HAo#fx3C7OBj*;@Aa&&2!Wu;J zqE9?_Vcntju0KS{~Ch5SiM&Mo9mQgUt~f0B}O3;C0joLk7Bq~zQ} z{v;*m7V;-4Ik%8MNy)i|{E5a4@gks@HekjEV+Ll-FqUA(5@QTz zjQRJGu~%uVdOPp!{I@kfmSA-H81uEN&EZpDOWNE%^);rg3sPTu+PWb1H7V?CRb+e( z%eB6?MW?TMvFp!KrFXB*t5aXM+PpON^^wh2Q(rgPJT~?9l+ABbUuW68H}&_@7(1roL{q zbwt)~>x)d@)*YE1TaRS=ZJm?7nFC`$gXS0X^P7==XlZ zuJ+I<|tJ`Q0Yht7;cmth>j zJ`Q0Yhp>-B*vFx>`{Uz~b{~hZk3-nUA?)K2_HhXNID~y1!afdRABW!V>sB9!wEH-O zeH_9*4q+dMu#ZF7$05vpF%DrLhp>-B*vBF4;}G_72>UpMeH_9*4q+dM-tOyGABVL2 zID~y1!afdRABV7yL)gb5oS(D7p3C)i-iO`}zkhY(I^HuA*ZFh&(~gbn7|-y$w;Rv+$2 zJMndS-ZLYyY}SlT3chxF(sN zc1xOM`cG=rG_!l)!A&!N4jA0D&i&l=x~6sRf9G48X7@$A-!Jms59sm!LBIDKcD+CG z$NL#Sz5nsw|l=_?6HGAcCg0|_SnH5JJ@6A?cBS|(gFSYz#}4+`!5%xT_v4cH!-cIaXp4h=2JJ@3fd+cD3 z9qh4#J$7(DUj7XFH==&stvv=Sth@8yO_;tSFHyf9?5yvXzqkFn%)8FN%dmf!VgD|} z{#}OsyA1nx8TRio?B8W?_xGNEmudI!GVI@F*uTrLf0tqZF2nv^hW)z?`*#`k?=tM) zW!S&Vuz#0f|1QJ+U55R;4EuN4+x@-m-(}kUyA1nx8TRio?B8YBzssT_v4cH!u*c5ZiJi;W&+S!f`~RHVd+g{p=FH5`iDUJk#c3y7 zgTuSNxj4Obw=y5I){?Zd<G7+VdGlq9(|0U~ ziOl<>7pEJ3U!F(RwO*X={aKmsx@%FIzE|d5*Ity~W;qJvuRe2Ox>cB`ZU4-I^tdp8 zTej{3tsjwbpYh+<6tJ%;U|&g@2+j@b2ZxQ@*k6{@w|tR6UNLDN6k;q3}dO) z!}HSp!Wi4X*}QbMuoigg{JH7LVJ-05H*?Z`EyvEaeTL6TFZgGf4~^!ew^~k&_Pra; zNe4GC^KDM&T>S1TaF8vTQ8iKj>PlmO?G1n|ej|%+HcwxGw<-w4D zfkt+4{fe{cmw8dR#1CMUR)o zvFLHM_!d3B7WbmZ-Nr-F$Ai6Fw5KB9KfEjI_qP3K>}~V+vwaKx?fY7P5V+9=Qgj?eihi}d)mhW+dNSFTVR_XYTpZN z^G5B5fo(pieKN4kKec}b_I(=O?(=HoJ|l=_?6HGAcCg0|_SnH5JJ@3fd+fZO*ttBh zgFSYz#}4+`!5%xxmvhK>NhajMbS><$gFSYz#}4+`!5%xr!V2>T_v4cH!u*VMe*ufq<*kcEK>|l=_?6HGAcCg0|_SnH5J8vg;E>G-Wj~(o> zgFSYz#}4+`!5%v}A1}*8>i10{4_W_Pr{DRlljmmXE3c>2?~O0-jlZmUi_Xy)B_Xztv!rYg)Pr13R z`h@n`JG50_!B0QmMtulhcS;-eE!=kFHnIEj(VW(?`#F1JYsCneldiVk(^>4`!I!pH zOue00!^krRVDvCHVDvL)VC*uMVEkc>!T8D8gYiEful)G*`1(CEZv7r%zem{b5%zn8 z{T^YzN7(NX_IvbpAJ2Y|wEI26evh!7ccU)skv(@SU1z^*3(wt0f9sJwceML+hrB;` z=<(+c{r=ox*PlE5@#hXdJudj~&mH&WarAp6zJ8Ce-y`hz2>U(4evh!ksR$FA9PxA}}N*>m^R8C|mH z?()s;w?g4Pu*bsA*>kt+q|VuM_spoy*>gAViq6?{N4r0F$oq4L9)Ir8@6R1}{kg** zf9~+ppF8}|$IG8PzemQZ-y`hz2>U(4evh!~TbAc(-Kj#9g+^?@w`fw}`{LMI7EO;_z+} zhj)uOyj!w3dVINGk30R~)u7mUbV{$on`) zkB@)!`*VR^e_rs%pCkNay#4EQ7v?HzXAa}?%xzo`a~{{vT*&P*M{<9dJGr0C!QB5a z2a|s0V1B=}dp{uW{evFwH}rddV%Pf_f4u+k)8m5w{@ih2{;d5g`*RoOEsAxRw}`{M zMI7cW;xKO!hk1)Q%v;1^-Xae3maN^MyD)E2dziO~!@NZt<}KndZxM%ii#W_%#N4Al zcVRBA_Ar+ghq<&k%%#O)E-emoX>piKi#?7!Utuntwfl32JmUeGFqamGxwJUUrNv<` zEe>;OahOYM%=mpVZnfbM*Ms=rOdrCYi-7C%e&s&#+!1}^ zxg*$fN3iFPV9y+dWU~ zId^XMWbL_C^*kRAH!=7V@J;x4vjve+KJM1}j*mLZ#=h$J-vBREY z_jZrhzoR~quhssM>u&XR_VT;&U+V1H9-jLB7}fn683$SuAY~NY^{uH+FuYQ*b z+jqIn{kQM6e#h$V9xvqm`;H#g5y+sQbp(uE))6rNu#SN7lXV1)|Ewcm?u&Hd8V1K?~f4*RUzF>d8V1K?~ zf4*RUzPz1yxjgZL{rQ6Z`GWoVg8lh|{rQ6Z`GWoVg8lh|{rQ6Z`GWoVg8lh|{rQ6Z z`GWoVg8ljOcE+d6^L)Yne8K*F!Tx-~{(Qmye8K*F!TESOGsZl2u*VMe*ufq<*kcEK z>|l=_?6HGAcHZvKTK&7RJU{f<(LWwL*kcFhZyl_TRWU|9Agx zM*eU8@f!#H@!tc&{(C^UelAq*pFi4M$j1yZa%Mc#|DDGFh`-aA{T+V)9TTy$=UsnK z7`EqKe@{3(%Q^_gAJ#!IezFdN@t<`N%zd#Af^E*3wcDICleal%rpM-- znSPsdW_E4PnfYUL$jndA@1fuGdob-juSVYc0X?i+kwHJ}Rv5diTVecR-3sF;>sA>5 zS+~OZcscV7dhB429qh4#J$A6i4))l=9y{1$2Yc+i-RIRFJK8;Vu*VMe*ufq<*kcEK z>|l=_?6HGAcCg0|_SnH5JJ@3fd+cD39qh65c3-o5>}dDc!5%xT_v4ivR zqRx`5kHk4%p|(Oh^~d}O!YZyQf|rR@JR-?WVzT=tmSw``2}MB7PtFA z{)F=%u^Y|+5{EN@#NiAeaX14=9L@j|hckf0;S3;gIA2EhjxFy8eBhix?1r;u#Nn(N zaX4#69L|~%hqGqH;j9^PIBQ1Cz1TNVKJfjuv#rJ9Y-@2i+gcpXwibu8tuwZ>tuq-r z+gcpXwict)zV%{k+4pOA?u+x&?Yk!C%yc{RT^!DQ7l$+7#o^3%aX9l`9L{_fhcn;B z;mmh2XOvGmU|VrG^IaUyd>4l^-^Jm~cX2o~UH;>z%^$@0Z|A3r!};mraDKWtoS!ZZ z=ckLq`RU?te!4iEpDqsPr;Ee+>EdvHx;UJlE)M6Xi|Iq^X!JAB(ZBnQ7(e5K=hV+H zz^;wwI((r0|HQdP*y7o7A9$wz-RDDjKV!@L0U!Jf9iCr5TZiY@&)nhp^|N?*e*KId zo?kz^hv(PN^x^sSIP(1d>%QyUUTggw81jcEll@H?@^Z-V9kjfbnD66`=dUg1yV>NW zb;Nv6zqoo`G2hv}r<9rR@5epL%y+q2by=S8^&S(~l04t>zN1=*`My8ept+due)sj8 zikT1Gv!J1vdBTHdH4rm@AZLi5e51)>!sHc=OU{lXoY` zv~00eJnp>3weayDwt}miO(t>~yH@(SmK-VV=p+XS(^uxt6EOampK8ZX^Iwerc3)!d z%kEdq{aQbW=?Ci{G5urxCZ^x4KgIN?^|P3Mw*D8>{}vZ9aj|%bi5K}vd?Swjdu0Dz zJnjEC{eIl@X582R4S%=6^0!6qCES-db8B*#Gv6 zw|hSz@BI`0K7)J+f1g1d{yu{^{C$SZPs^)|!{28RlV9@o@VkDshu`&!!|(dV;dlMw z@VkC-_+7s^{H|a8KlS&BJa0xHdfp87ycz6yGuZQHu;$&8;;=RmhqZ|~ ztWD%Ue%g9O9M&V^upSYI^@upEN5o-0A`a^jaafOt!+Jy<)+6Gu9ubH2h&ZfA#Pl2a zK>Cw;6gfI)@?CJq!-zv3MjY}m;*f_ChdhipC+ws%4*D=oF}G#devSirr*e0;v4-*UJhnFkQ;0z}T)U@~a;fK1L9Yy&n1lQF?2+vJ=< z#z3iKI8j--nw_4d;fRNwY`=WpKI4tb=6nZ-P6*Z z0Y=T>Ob-~fgtI-{jwW`O7-ce`lEJvLmSg@Nh>VITq&lu1b z=WI92(Jz^OJ!3{6wMpxV1^qSaq6eeza4rg8=trE10ejCA7<=D2%h>zQS;pRX&NBAC zbC$99owJO+@0?}qedjD=obTb>55BzT349OhJx^flJx^c^ef2J8#;~K_#mpG?)w`G( z!>@W5Gh>WLy^EPK#;M-L%oyXxIVb!gE}X>yd(RUXd(RUX;~rdJi+giz6Zh=e7w+Zt z7;ulT$A)`^)E5Jb2F&7<-IV_b`~M_db=I9mgTU-i2=##qsQs$>lkBQ+m>uSW2|>^l|2~iVA*0GjP2t=sA1GCtF~)glTp(kN zf9k`^j1gC=T=f_u-m{mQGDaS%g|uUg{NPL#_K`Q7i2F&*-}K#U) zo=sfCjDK5p&+~N=m&{+o#0$C31N3!%U`OW-_H{ntSLYey(fP+XH7^*y<_q_ITAp=B zVWa=LSz%+RS(3uW{$VO){EqHl$c$%h^+INx^Kuk2;}7vIWcb?jzMzR0a?Ka?HD9o! z^9K8xFZk7bVLX~Ij8pT1@oT;imzKwODPr{f4i_IbI8G0tK6TNcp=w(L0|I)JDM-p*L=aR<_qJ|d|{lL7mOc$hkn=n z_#ZKPQ0o9A575zh07ib0H(=xq`2hWv7^gIJO<{zz( zc}d&Be5LJU9@Bm?zv=N{{?y~de5l8-=TF$j{Hf!GT;~D$IzOGm*9G{+{G;_TFKIiNue5#4W7;p~H$5KAdwQIh5B2!<{0aM*KXts2>pVbT z=LdFl-e6zn6Ml7`F&>?Nj8pT4@jKT+XWwazKGizFdS24}V&3@Qw2mMyXAL{C&fDMh z?3wHS73c9K`O|OH9<$uF|z`1|Zy@nW_SohuE>%OP&{#Dm~)TG|e z0D~{xcmJ;YaDC6H?-Q{u|HnP5ULUm%V*fwwZz0z@PCHuPx#nuW|IyCAGz(<{^Tq-@r>N--_ zGgkIU*<}nr%Ab}CEr%bi4?o%t{Am05SNp~1dOWyJj}!Lv_~FM97v$uP3;K+`cBD5h z*k|nZ%h)>}#@=x%xI>2}^5nkJjMcwV{Xb*%xm0?L)pb%`&sfY<~W3PS2UcZdJ<6-O_Cu8_QzF-G@A&9eH*bvfJP92=PXgs>l8U)9t)IGJ(5GG*2Jc#d(04!P92>1#n>{j2sNxfrX@N$D|G*O3@ojj^()>a9Lw zPk%MiapO;gbhOxJn7^6l|)6hYUD7%bxuX*L% zYrx(b)^@npy!N@*fW5uII=a{RT5qob!w-4@SofMkP7Zy>y4N80+LyrSX~YSvdyTL4 z%n2;ly#~4NHDGVNtmDmtwu8BdvF-oaNp~d|9wuPa-#3AkrRD?4Xp34f%W}0u#>yL zd(Bt(!oO^<{ZJsaEZ8-Z-DK%x@jktuJo$BiUA|o%Q8H-;c|9<*{rc5i*N?CLWQDw0 z>}LC31g5-^M%wAK+ClHWc28QJRMt(A&Gy}sn0C&5L#oH@v9lXehpCy^=DeS(h^95O zGoH2jfU9J_oQyMuCl4u~%_EO4e8OGU^5{1kRReZ}*N&+8OJeJbQ`zhhwyzj?KABZM zIGf$7LOWNnE-9=w^|INEI&TVXS2MZQKUFq6Bd9v8s6Qq{DANIIz-p*`)Th~uMSw1fC$Mu=*uis>lUC;M% zx9OhQE|5K=T>2sfTF>zF5@?)AD5MaOm{1|Omkw|8V&SY2Yx0X^QNh4dX&SduvA498h zCB_-7{oVNIu14P{W$gD$64$w#Nf`IM+{)d0pAX}=3DVJ3|CgN4#JSqj?BAmqr}UXe zLw6lwoHI<);XKP3-|Kdj>}vfOw=5J-4Tcn8{IEbm`D>SjF8KYbbP_qURhdxWMYEF1 zW2?g4z`1Ms%Ag&Bfd5$Yfu6h{&A9XV2Q>4|ddB%CUZ7eHPBLCNZU;5WaEEb+B~$2U zRT~Qq{7#sI3*5*i)Bg05{7+qW&wHFfcBub`CU0s?8wMwr>%|9}Q)MB=eg2$AB~B=R z^EplnUY?=E=X_*X;U|ko5E{SXs>@Ry?dhTwtFqzC!Fq`b2 zy-#TUJ}G4HfSmGn$Zl7QnyKW=0oi5zyc!~?Y#Q0krRuTXED`ZpI@zXkN*Q?npxBtn zPcHO-O*ee*i$gd4eWmj_r=_z zl&?ZX$4#kasmZ_5p2k^P(s8ZS7E3)XOX`jJab(4y)hs zWIX=h4q2_&yE`)OUclda)ORW4V>Oal;kl19u9)e$0Kdz-#4^8=LbA))@ljN&(mL0b z)|qA4uxs?9Xc5sPPkMQ$T?GAX4HPE}B$e~(T&75|QuG_~f)dugKy%w26MyWBp!eO+ z(&lgOh#MC|sP(8*G+q}TbnTbp^e{;(Yqn@g)0!S7-;)`vbL2xll@C!DcUCL9 zO9l6fn)~T~XbuZpRBh+aT&Q}p#!pT!z4d0@Sd>&=p@Q%i5XiHZAC>UtBYo+sD! zCZ48Crt3}Y%WCS)wZBkeU2lPh8~EsYbMG9SK-U|s$n~DQ^+r8Pz9w(I(XsDekhk7w z-u`&<)|+gR=rMWgO`gqipS<-ZGnc$W-g=W~_ueFLy~(oa%j+2BfQn@iqYFKCwq9w( zD9}@z8ka*t73pr_t1D~1>adMb8rQN(DWr?!O^Mo(GjsqL2wB1Q{6wfk*; z#Au$TH2GvSlS3O9kF!esYEiQ)0Y@WqBl*O*0y$K}%(8Xn^|E-*Yc zmh%md*8X{hNBihp!{gqoa}1BW<7XQlkGz>>czpF?rr~jN@|lK5pL{b6k2}gtH#|0S zO*1^k1x+@A2dALB@P%KKP$W6@HnILKEvb1@An!WYjoaYcr4z{Hau?n zMH(Krj3vY4nk8<-r5JkA@VINt1;bQ3G+~CvhlP$A9v1~3H9U%-BZkLQ)eajT2dp_{cx=7@ zwvJIIx^m0#xcSCS!(;ZiIK$)U$FYXTBgtY7j}-!9439apM;jiOLQ*S?Q5JofBx)$n+GNQB{W_LOkLW0_f3439_VUp74U{&30gsLnWbjMlqi zFAa~Y%f2u?W^_F_JPxVx%<#Ck)$fMKlHKABj{&`(8Xo8Ne`0u?Kk>2Qar(+fhR3Cw z9vU7mZF^vN>}=mRJVsrt@k;}ZYQwyKBso41h(GiOuzZj z@EH8|gW+*r;tz($Q_0>N9^3lAGdzYDduwZ8ypAs?R{>U2HJ0)Vo{gDWLodPl9{zycONr4z~eWXmNHW`de?-SOCAIZ_^=65rw%)H6-<8DH`_-}op$r*Kw@>%ALhR3jl84QmJa%C_) zmR;pUUdI^Vu$nQF?ps zZXYY}t5M=b2|xSPz_iwb_Ju|KYCk);TV`wSmNBl@S^e$rD&??BKl62GAM0g5%*K7 zcQ~WnI{#^LU`ZlbDIk-5q`?-xXH3>MiK&P3;YoDO%QoL6)ip1Ro=>W4o?g^VrfZ(A z>`A6;o)(o)u4|r(>@+p+{;gyRUGt%x)}+ui@A@fQN?r5f*6ftJ=EcbjsdUYYVN+7+ zniofWQtO(xx(-OKYu;M&2iF6i30(dqjjnm?C4WEbj?$uTZwedQ=M-U>zbGGXAy2K6tW*(i^ctk@LnCyI*2r~N4UZAaA`Oq77hN+vCY*NN@OYrl4ZW8T4Le2Yy@cr4 z&g>;zcU#2hy+q*cI0C$J^)68y>fxzF>IFe(0j%aqYTGhQ~kV zUN$^_KZEy6%wyQ3aKmHPq7jD2vgvp07_DhJ_|8C_Ina)cuafKZFoEzMux{9 zNE#md>@s_M*Ne@243Ezi>@_^T9l6i&_-Md>!=t;;0mEbdpAQ-yw|srb@c5z1VZ&pa zioEY-9?zCPYIw|h@u=a^qLn&EId|nM!{g(Hs|}As=dLk4W}3Lx@EG26o#C-VyY+_0 z!7a@_n)}_i8x4+I!0?rgPDfM7d2)X9>-LfZFtOCZjRwGD(hUsR&SZR2yn`(rPQLcG8!tnU+@kqntr2C@`j|HMe8y;^T8e@3uy=$!DF?g#v zGjXR}Ki=?|e9i>JWBQ@NhDV=16Ah1NdrmSux;joaJRWH<#qgM+(p1A^-wJ%5z&zeA zHQn%7;mmZy z`B(QaJmwzO%kWsT(JzKa|DZmG$4%w>86Jn{9$A>* z@c2dF;fBYpc94!yc9~Y$@R(^tRl{Ro|LTUvj;(7N9`Alu+whnuZC%4-S>O6*UM=&g zf#I>lg@%U5FP490c+5NX8^fa<+r;oVrPsHH$JJjnGd$MF+1&7$(x1=wn8&+GTNxgM zE4OAIamL>NW)8z${!6(GcQsGuG2H#SJ)hz3<=_H_yYy`e8SbinTg3EWmAao9?keRk zZn$gk{By%y$+(h+yAxMS8}1e#E^D~kHLbki?wcNghP$jC_-vNBd(o_-;cou)O3dAi z+m`~DZ>m6@szr)pRgb!WbH2GG2Hq$vfFpJt7u&9NW<2XysOXe`I^*Q)mWytcH!v>u zdaUR?X&>X5Ctr)7`k!H(IAJ?DG7H>NzDkBhle3X2VWzN4Bs zuZe)=VXhul$@UbPg%-E*CJUSTkDpqTg9`C z$CfK6oWC1-^x0k4)0ev`ZT`&Gvh@{3*4kUC!PB%>J!_bV>b#C-{OoJBh+Hf(wq8yP zr^butQ`}=0)U#E8soCer)&Q$)%-55-nFic%MBEbMpj zVqr*s>TtubCMtAC!>$b;U4> z_3JF^){3WQtwzwObR~uFo3~Ui^C-&k;;yUo@PzV*Goz_M-fvx*awL+=hmWOlF_}Y8 z?eUStOOK~9`KG(;wMigT$4sF6kxA)&wO3R(cp}}+R)Y$NhxDk-WV)Jo7`2VQPH(SH zp(PI&P^xYxXvpAcbU1n!^~=4B2IrhX`}>`ym8BL@f;}@S*Eex=;^_$TZ#J8r7JW`b z$2Xwkzt5qpJrl}SpZQVQ3G-;e=SgMi66@R@b1k6AFH*{8zi$lvb^AifF(w3D(j3jz=hevv@Ik*m|lme-phu zpU@imVFNW-HiHTTC%0A&*hG~#bf=@o(^}16Y^Ec*%F*nh8LZ#CZKeCmpStTU4zT3i zZPf2*NB6>jELQT?JE+T22YQ> zEBevYt$VqzyQXMLiH@veeB%6g8t`ZeFk#_4OGq;yAi@SKx2 z!4;Y{aVXD4r$$H8`$e7In14cdMbOuo5)p8%MdzsUt6Gew^gBpN$Btw?ZmY^ml_iW5 zM$Do~Eq62C|7B0QQYwt`jK?LYNrg*{o8P^6UUlr5aOri}dC(`KDH)-d)CvM;jjeX?1?5$kDF$sNT-{EZp@Ydkp=}reX zF2qR|CosJz?8@SG{^qU*FVpfv;O~Yu8&wNyN8!? zW36=JZQq5nd}rJocZq?g8NZ*Ak(#&K!#Mwj?`gz{HH>#mo=ED4v67McjIq)sbq!-> zgOn{7d@0-f_YJ_xC**D|hYw)r!v`?zzy~nw;|CZrdx z4F@l-=o^Qq-GTC<6U(+0nGbDY9MWvEXy14aa-4^6M~N0$hB3a}@RZm;VJYL3@jJxW9ya4-17?dM2`(}Y8P-{3o1?B* z|2^%IOBAplF-|R)x%>*oGsb73m1D)E?O%riJ8RO39eMb>K2>d?cK+4s^HZEw-{awZ z?$TxM;02y~SnzEws+hu4Cxd_JOf`mk>L*Qy*>r4$r>=HH?w~$uZ;ZO=Ax_cx4xT!^ zcrl7DT31|aqZjQ!&pQI_L(8Sl;HOUu?iVVos*Q}=fVo-z*p z>Uv;^%8CI^)7P z-)Fr^cVC6MFwRQTuT#_G%UJ$h+uO7)&mxwe4U3`*`OgMIKlRk#XvF8o1EHTS+Vgj8 zkXsLb<9tBAEHI9OSA6A$e0|Tm)N?^SH{>tEVql-;Ui&PE{f8nULI2^gXv&}DEz8$_ zdzErD&c*U_F_AQ5Z&rdGznPb4XotEiuYck^?U`PkU7?!7t+Cz5oku0CnF_h|t&SH5?*X=aA^E8&PuD6NiUR=rY9y3!646;JT@Pds#kY*%+ERKa}NB2SyOa;mJ=Y!ZS3tzg= zT!>-$t*F{=@C1GI33!4&aQp<1e8K5Uf%zk2Szc!InLvkqm&3m6NRpdu=faogT=R!q zXZ_KQPPiQ77mo3Zh~$Dfz3dw+;LnqXIMM8Yrbs93LJnu#bn|lYV(eVT<;PAEXCG`}Jg93IF}$B-{QH!$BG2Wc zj5mGr!nJe%X~yZY^mD22CJ^kyruxn%WA%MXp}w=}hFpE0k~sp#Sd`qQ^NH3w1KB<9c_Qy>l3kulk#Nb(xV|GmDGvbPp?^jODrdC!r}%zGwNg zjzwu{?Fyl|c2H0XDzi6$<>RY%q764&x*_kE{)4)9oC~#=tN$2Me^$bBcaBr;rL{vs zAs-Ypftr1M#`69tN4YoLjB-QXFZ~eec`+HmPRq5sL*wsQ1i3p$eWyII*~i{2@1HWU z(~hg>#c?cexwgF9;nyj5ImYR7*b$Dngu}0JxCm0@nsN+9_5ySt!yb7+h&NCblm((?kl?_t1T=1oAb58*)|B$=296o@d z4__Qnkl5plXlOygK7T{VZsIfqC)P8>xEZT2=K%s@}L(RlSj_ zH}cjS?CaWQjQXrwdpX9y`qv6Q*aeK*4vSgJy@1-jaxb@-Kc|`nPVnE|#g!Six|Wpg zpRB<6!->&Ut6dSs^XD8QzsngJpY8RQ)DP!c$)x&>vC>t~A{xzD*^tT>V`W=Li@m)!b3t0K&@11Kod}w|60EQj-0ET`107Hh)fT0T?z_0-yz!*P#0K=z4E*$#! zj!l&?*B z1JnvIY8mwgj2cI+0HgNN1HkAB_|S6r(E9KJ3_I`v4Ey*2h76wpLl-`PVFNyZVH-Yx zb>DgA+;?7m?mJ+N-C>{m4ss>qz5_-M9OLA^gB&?S-+AnK`cBIodEma&b{u)*zJnYx z`0&{A^c^s4ICv3t4+?9?6Hi?64=OO;6q=A;4=KU;n_)xgp`C|u-GfAD(xqkW4tPrH zN8nl|lj<|ZN>{3D7%Ll6*^o7HYaM%|Pzm{V>mSdcjWBkmQXFLLO0jzvNpRw`@JB*c2%aJ!r z`L&=A89wvaA&iqTY`_-euNO`{P97cn{@r(~&e0S9%6$j!h&uD!;>6$) za?B0rUtr7`=xboagxG*F$DrqdG52780LGkzo(INUg`Njiwt4;pRz7+D)N=UH`tSh^ zJMaMv`}hHd44(l*7e0Vt13rK;e)s^^^QTvic}eT@{0TY6?y%4EC*(@TJOU#Jj&bt* z2|03x_0D6*GkC*wdob0Sp`P0j&3#!0_pi^FGt7&-+YZjNM_M_nD9@ z8SgWJkpss#d7lY6a)!S1*zxQ$wcL>h-e+n%j=b?c6LQGl!(+#@&jf}I_yAUMiE>qD zGDcjB65tuhT`Hw~-hjSu6wEl)#S_%C{V>Mms$`H`^R;8Vb54*{Ka7=3s?QiJU8$~N zzLX8AY%x~04PVM9yw! z{=^rat#vN#PaLBYZ)^}`s?rc$3V#5vPDzHr##=VU`4F**G5b7CM@x_Caf9;Z6{GUI0+p@UpH;^pUgLylZJ@&o%8BpR-W-ww}v)-kCA11N+c<@%aq4|7z%2 zF*NZ^#@`-0A`YGP;P(k^)`5NK{B&R<+i7+@iPa+G6vo?2y%yQTG{z%`++rQrhtA?E z=51PQ;L>2mWjdy09oUCX%z$BRr+U#+)`%G+88^99$l5z>4C7R_ za$?q`_O?8V2lg4fMFXxfZ-E5xE4By z0T^*(tiTvMVgN==(80CPL5_ftSL6a1xj~MAku&JvTIhfSVDN@q10(m~02rJ=2iHOe z90Q{+z$Gxa1;@bP96GobI;bIF)E#OC7`1~M0!B?i2iHOeH42QnMlAxPHc_L%s9EUX zTIiq$fYB4Ebzsy!dH@(b0UcZm9rPG5dJeq=jNU?z0i)-jgKMFqaHz(rR~e&s(YKHT zLr2?Gz6cn;lufs`seCbpFX-S}=%`p2BNjDg#u&4Tg)w4*4(vcj<%%(KrE$w zQ8TKR7^9Y;1DnuMwaOT^s%nxkYEsoIW7H~iU>`cF7Z{@#RLwI+&8uEuj9!2a>_bQO z8e{aD>M6$PDb;I?(QD9wedwqk#^_Pivy9QR>W4A<7&@>I9p!^DdQ{nBj6POA7^9D& z1N+cXF)&7tsG zIADxEh7RmQM{&#;J*v25j6PNzGe#dn2lk<(YKSpK2|l#7<~*K*oThl0mkT2RqKq=$EpVyqmQ8j`_NH6$rwGVdWkXmSoJMq^f7c` zA36>ks(O{>=wk8MrKfqnF` zqZg#3=B1+-SO@me$Btf;j-HZ^USl2DM;|+SSvq=FI(nIPU>~*}bA@!w3DPlFunz2F z?2freI_4bdn2T5k_K_RMTqhlKnsm%{tONVVy<;wwjyY30=2F&yeQ@iTtEFR3mX5ia zbzmR0<5&x%W6qb3wSaYCAGPUNYoudMk&d;7bzmR0?^w&EW6hF|wTyLOAARFkE2U#i zl#aEMbzmR8iyqe4vF1w0TFg4I4}HuL+LvQZhcCU>vkq)xJeY%YERH<`VqrP@7&@?t zcrnKTBUg?+33A19^f7c`6FQhffx(4i&jT)4jy{GCY(fWfG%&b!?5V&t>!6RJ1Dnvn z8UT!1a_reqODsnpLkBjYgEa;iwd&XtqE=asK86l#LI-OYFnYnU=R_~C9DNKO*n|$& zNMQ7uV^51-V>$X5I;9BS?jv1qmv6q4zeT+R8F!~rexE4C9h8Uxdu~&l}eT+REF!~rexE4C9Mj4}z zu@{6KeT+RKF!~rexE4C92NR{gDTlE z`9E1R&Km1ddp6tr<)M4h7_+qam`@<%C-(--5Xv3~Pu z2S3@%&ff1keJuN0TPTHm*I+zf+aqam`DLTMs#@}~aj<&3=JSbzKC z)SsM}ob%X{QhnIhsi@NO(uw|j?XCKyWpJCpY_pBzy&3l}=E)RI`m#JEjgVsx^b`qyt2OH`IGCobKO_Ku%PBNmXY8xl(oar@e=&OO~rTm8xD@ zU)Ap?_ax3ejOr`)rTR>&KH+Os-$>OzY*Y2qpY~Cz-&n5tPpUp-ebtxPv*|OFKkcuu zX9L&Rk715LTxy<>s{aFd9_Tqws(B$0ajALYPkTbl7g~<_LhFBOuZT4XzOa|We8F|7 z;=+7^YcWpD7qE%(W6gs;_HvjnAV<8IFQAV+d}`l|^%d7*Ux)cZ^M&~W*CPLzFJKeA zV7`Dp_H~#qAP0|_FQ5;8KedO)UIEu)kB9jJzEFplFK{jD3iAbQqTa9~u0_9KzJN{i5#|f%W50*_0&?^n<_qYfA3t?( z#q)x?);kZdFYo-o*J2*P|HCHc2k5~UU#I>ba{gTD!58qS?h`RST#NA{9>j(CFg{$1 z@nYPti8v5H^pOw52|40M{Ln`}K6THFyyIH%0G{9rydm$n7Ce9t*aSb|75d;A{6P*r z!7KE^^QZ3LQBSxQ^@aHYzEF>-CtQpALY=`T>JIe^ebg`N5^~fj>J|E^-%p)Ipigiu z`Udj_e4)?KC%6`UgZ_a{^b`6J`shpa8|3Ie^da=om!CRU!F+*hv2VnD0biIu)c%35 z#e9JI0yZ&EIP?P@@<50FC(no+;}nj#gkzk-F@E95gK)$v9C`TUd6y&q!oint= z5e|NZgGb@u_mgLLj=HiOb!a*2%5v13<)~ZBQJF5{B(O;IMUo1x-S&n|R z9DQdw`tg%zs*ZWULeHZ%)V~(y3)B@b<_pvYFmzB$>N>`dV?P2p^s!HIoca9eeAqF+ zS&sS8a?Ed*W8SkI^QYyQCoRYP`N^|x$GmMh=6TC8Z(EM}+;Xf7mSg_69P7d-&+Q%S zk>yywEXR6eIo2u5vEEsZbSZ6KA`fEAXam%q@TaI=7lfO^F zd;zX;|KZqgSdRUJ<=9tPj{OPbdLIIPy+8Tn?}pSk1$^Ot#j%gVI0foT%^w)QK)tE? z!*cAq5HHKs{DC~MzM4PqyBoHN`*p{e67tV-+^;zHhsZx)tL6{z!Zy|XVLA4b;F0BO z{s6zMujUW@9*1q>?7?xqgu1d27w%Ua`(D(Qg}BuGfqJtLmzqB;$37YL$#OM+pl(@T z%^&!k4%@^zisP&a{laqGuQ>Me=oh|L%^&C^wyEY1%d!7Q-?3cHALvKcSMvw@mu=!q z$Z_t3erLIN9-F}`^WtY<{8$9+;P@~`HJ=7ALmZE7UNa(A^Spn z7$1CLycjopAr8b3edGgiLXNl*KlG6g$GH>cVb(`paR!BJ!GoIT*%x?2-f=B>03Wak ze!wgA!87=S9DIUT=!0j+85GtR)f$kC)KpEJ?Pge}(foGk>*b%luC~i>ZEvBHZBteE4rSeD== z;~#x*iIMT6n2Q{5cZ(`NG+^9$%yIENEG6SM*}_HQv6I|b*E_e5R^K=DJhP&7^&SS} zGlyJ#=gWL=ot)oKhrHVV_xGCF=Ktw??(l)L>(bSqDjoBj2Qvme9{qiJ=zG8W{Ga`< zJ$dXSu75l?!|B&)Q^lgcD=q%3&jG--USFg!Y-{X|#n^ZFV*UTh_p%-1SJ#@jj9=x8 zvHo7UBgX&icgFemXdXL;7p@&IUySwl&{Zr#`})s(huz7w<9QnYI zb{FUE`frsTf9w1A-&%YBMjF2dL4J@M{H_I9{~pBiH`4#}e`~F3gE<0^j=!15cLZ3D zzu$NKjs4%>Wl$U;H;vWza>3F6AKzurzqfMyKI`w_GpgU^{VV>S(fK?X$FoZQeuj+V z3(t4?S9^wxV}1W8pZ8_fae=w@ANwxPz6CPJbGQDxo&zTSy#M*fUgf{<`C$JTzrz>y zMZ5?2=bsz)k1;#)hW!=W_vVeUdVbnJ^*k}>n6-WE!JPL~|JA*{^M1kkOxoN(?V_Z4 zj)n9|KUOr)yMcC;s}XWBcE&&TtlDogk95ynb1Wq2M6`H3F_F9Mys9AqGh@Yn#;-HR z|I9t6^BK9H^6QNKpLve%r|z?y&)ENWdH*%uWA#^hNBRHOcXois|LyNv!FvGz3h&MN zE4=^cukaqLzry>-{tEAv`zyR3@UQTm$G^h+Is^U!?_K>Xyg&DU%lnR0X9u8t^~G=sbznAv{)>aOd@*M71>-Yj;reJ=u2-bf?u^jYnocVD|FtxhWIrpRXd z?nz8LXTBlz+y{H??1nTqQ9?W;!`|ip#BHbY;Ont3Lzl08%R1$92Dv8ne#&_N%{#7- zRt)2afn~(Ub|)FvtJqC6d%v4;z8jw3QNkvEM|t_%Q53W^o87ich&Vg24t?=iHhcK6 z6QcLX#8hQxR=ZG@2$AvgUT)vYS?&7yW5n*afr0BUWU-rPjT7z@Yh2-Nv)Hn7lvr3H zn<)DzvwgqkC2@RVOVPAXW_#JK!=gv%B=OoOvt6miRuOh@jc77Ez#cqyj`$Fp&+qA268mVtR1 zq_-o}$5HK#o!l>?)7ew&$55{lK6LY^boR^z5wxv-ExPwSt-UJ6NgDUVNIEt&t^FoP zD7DM7gg&NAYu7xul&0_6O^24Jv6Fl?nr=NmPWOtZu^X?eM_F!%)4koP?Il-|P`fwL zG@@#1`}~%H?%H|c=*6W}cKf>ifhGG#QTq<5?Cz;nxJq2VM6pj&+IJsj7Vicfp*Q_f z+UMqPbV+C7g?6c0MirHyk_*d=nV5$AIDrKmzF>S@@CnN44h~CZ|J*QE)IOHbRj@@eyWred(RuoLSK0eX?H`g{7va@P z2zT$K_M#EzL^+?HqW$|McFd3a#Fc}yL`-lJ``zGmV)LQRqC>7EcKGxu!oB5?_-UiB z9dN0wm_PTTSXs{3-g7*cxPIb>IJPgbJ-5a-*WsjbqG!Xzb~^i$Xy6ew4DQ5lQV}DfdylZwYR5TjlW9Mo+f@;oMCaU`T*#6ZPQ|3DA zJHV?F+LJ!+B5}Eam{BsJeY)duiZ7g8Omio&yN(T~ZF5Jsd}<`Hubhb{-)h%F25kN) zmlceoRSg!qW6pk%AJzL$@-E9nS#Q6W*Q;NqQZ2uyihsP55B-l)wX4B&B<(xd^x!s{ z|J71XJ5r`NJsg+MxTHIjx8d?jN#+;TrH6H5u!R8A{$QKa|T z?cOo!iR?Y;h7h@Cg^pYCSO&a{6?fJ)ah*Q?NS2rzBl4tp>-r(?p$x8fRqVf4RSbXr zK=#RcN-XX$TY1MRQ0i3Ze; zkX<@WqiVk%q^9k{<vR%ah4gQu8Z2XneC>a!}Fn>iwg~ zD4^#~`TLiRX?y!Clzrq5IV@{BYFIUzvdr5q6GTpRS1%q%DeP_X!1mg^#?+0b4AEQV zxinKfB;aac&8 zIJs6%j*At+oA?e`<;(4)a*m9XSrm*So_r)^y<3o4+>eFIk;>Gewor?6sBq@?+ zStPBCgD6YHN^v1@p$xk|pWfz}AcnPEAQxrZLAicuDmwI;FK^{PMtM8?iC*L8$*Jo7 zmG|e(aur%UR~AbbP0>g5RtVldM>a1OM^nBGcIUh`TkaVUO|Lqprk-zR$uZ$q=<3O@ zs7I<Qp(hz#r~?yJD#Ox+&6sZv%Is_*lAkcC!3qU!7T`6(z z@v`BJ{bF0*&nW#E_1%{r&Wi>Q!`$uXjg?=Hy)N3FiwXUD_ZZoIPpr7Vs)Vc6jnVRK zwpfw6;cu>A{um{r=0u9n^g`T8K1yaNtlk%Tet;;FbEN#mWsBDz=ZW5xM#x`RuM#1x zwu@id4VR751&b+DkBV&rhsh~(z7rScUlvod4VA}sXAteKM~R*_2g`xY=DXsG#EE

VO zTi5OuKgpcaW9Zq-X`zMIb(V!b#M1Z*yWDT@bd(q8+@R1cd8lOCAEj0CBDI^*o+_4Y zFS{2%MDLqUrH`H3%JX?PQ?3H*scJ}T8IgDvy?C;ZdOmF_XV>pe=kJ`OtC@a~@7fio zRaLH2@k-6*rj@7Nht|bXzCO+5g+tFmR|UpW&%@u!$ps6#BJV^}=hsc-(}g!(+t!?+ z5jh)6zlaK=>MffV*8EyNJ>5@4_Fhe;Mm3VLdFF}!2`AE#b6?7h%eRS2?(gYk!Upp6 zn68Y6<5SC*-A?iLw)EfWP-1j*MwE*8tThl(6` zE6TDHM~LZzPKw-qmOS3ShFEhuLewemlAVJRh{&H~#Oxm{$N~piyQU^r`=agTBXAt?(Aps$!p)l(%gGd?%Rp-%2H*oQQ}4A$WyXTbH4?<@SovyD!n#`+uRGDc6b%#m`ezn>kb^M!g>^>@<}w zu$8PoT8cuSpP&>c57W4L*+h-LM=3$;OEh`bT33n_2Pt2LD00{SA~1vEJXMxB>N%%} zdw7hbe4oY8qg;vUa!@F>Y7{}ka@L^-V|LQkIVULK^HFppYAf|07eY5rETJE|Y@(~_ zmr~XGA+-JFI+{3q6xHs0f*yaln*6TTp}0~J^mg`gdUhuEnS~HdERBb7~=&+T3Ni~V) zOr0eBH_f5qYsS;%V{1g!Zog8FTx00|`#mCY?y}_5Z3M;iJ1ce_yXJn`b1)tI@tR24 zG?Tkoy*}jMAy)L-l-$*5ba(19I#zTWdf8RIT_=h^eochsEhUz`X-!RYoD)5E_Y(bP zH=~&Ad&SG4vqi(Hlr-UjO?&P(5TI#UuAe@Se8aVncV!uAyd&nL6W2WPWeRcPlb)+L42rd~FCQRhve z?P?~s`lrffhkO_2F4xW15@)j7%?p*H?ib&S)>E_Ek24OWt8*TR?O$iLt5sV{xz=0~ zB{F8U%az(sQ)arwt?(@NsY};s;IsK6YJL_w>E;*IZgVeDq-7SnS59As+vg`Ri?l#>s+Xb>`luKWvq-$j}+fAgO zyj|xzy7nf(?sPM?Jilrxbvh7W$1X`CyN7S5q2mJVI?3Kpyt>DD)-b>>IVO&3Onyw0 z0|M;#pC6+QD-y{p(V6Uu{nk>7Bxz*J)tT(x;bW+*l}Q%tn#pc9ss;^QkX2^LlgY02 zC^6ZUbI3kdGTL8m8STdJo%2r4XoD;DyLI_2b4J_$)MeMa#~EbU!VLE0O^wBd!O3NU zTp8>+RThf4&#{L1+rRl77YkmVp~j{C?Xbd6M3U?)Xp-B{9y2JZ^@Oo&9n^b}N2f4N;?6I=h=IlU1lvd#VgJON_wDv;(*W!lHebN3=8vCommqhT7zLx!K8v9AaI`K5EpB4Nn zwLQ5$wj6zIjql$r?%Iv8t=mIoma)B(lJ_nyQV^nZWW_dKRzX5 zBo(7IvUf_vNGe7V`Z@(-Bo(8G7?T1ql8RBJPm=;MN)@9RH8nY6lqyEo5&z_fQK}dN zYc5KL7^RBQUA0Iu#3)sabbM1%#3)sabhAWK#3)saRD4$w#7HVe`mIV5#7HVeS^0!7 zVk8x#OxwU0F_MZ=Mx0HI7)iw_HxEyY7@5Z+6%y+h<(mVE43Fn(Br-fE4f8QPT3`AY z9-CiFXn362Hlg7$+3f^|$J(6|7#^qJ{3tb#!EZlE&EvepAEf5-RI>L{^Vrt^ozy&r z7keu;k7Fynk($T+)m}@@V@T~+QuEk;;~!G<*eu`=eqI9p4&+_2ms0b%y6g+7dCcf~ zE;WxsYCMyg$Gxq7mzu|t-QuO@F`)NTsd=2+|B2K*&Y$=gF*1+SS3W|F%;VBc4-q5t zcxl@M#K=5$w(lcG<}vE>J;ca7PPy|NVq_jadw3TyGLL)JixxGHKQ+077@5b``)}(Q zWuhy$5F_{F<{LK=BllzWxH!bf{W$t@EMnw-Jd!LHF>*gv2#7(9+>bf4MJkMkN_H$1Lwdd={7?fXc>W6us(4Ue~nL>L}tPYE|XmYH?M@OWhYWy53d z50?y&9XnsrFJQh51+VHsg_LhQ|SG4jCT1 z`yJ9TO25Jf4Ucw-1BS=X%I-Hj&ZxZ4@Obh2y@tmco%a|Xi+8gPkDGpxhQ}>q$?&*l ziQDkFdu^!U@!rM|!{gA9-G;~K=XMz$SH|u%JXX28!|-_V;daC0@J8DWkA37e9ix@y z{8q!`p@=Pp$I>@88y*+j+hll*Oti`H*uZb2;jwJM2E*g79P15_Atl!t9=Ft9Yk1uA z)f&U&(Sq^&))z2zHg4h z;cIoS?>g5xtaGh(ue)pRokc$$HoSAuk2|;SWOMWvKX7}|kI#?0t?0*lCf-u?TJ+<~;ZDiw1R*kp&>{T&UCD*AEm z=|>d(_;iapML%|FeOS?t8y`KS=*P9w4l4Tbxi=3e`tkXNwTpgy@t1vzejI!7K1Dyy zXt-C=j|VoXS@h#M7uG2HvC*L2i+&va?5;&WE_FK>{rKA()rx*Re_++3ACJFsC!1s5 zZ_tiKKdyYZa?y`|>~=*z-aUQWq8}@*-@53>Z+6(K=*Q{1ZCUi=EBlu(`tkKMH!u2e z@|~L%{rFhTjn4KtZR`Ba**<611sk00b4I-Kt+Rd3MO%FBY@aiC*Uz2pb9SloiL-sq z+-V;=+vkkAeyx7*aNtXO__h63xw;Ly>V3@{0R>N{xKg54)E1 zYCqLoyQD_`)xrN!^34w~y2|_Rl0Q13LAKi|6Wy8LRL)P&yJf4c8}EkRSRub?*{H1A zWngxBi?xo@HDP1}={H$hDHuu#v*)Esg?KW;4oNasRm)S&r zm)ov(i|plJzs*Lzbi2Fy{R-Lj{lCpxx4O=?eeuGQhev;&o!_RV8`toKDaSwdQ8s@< zQ&+A{yVB*Kt;jxpu8I3}>(@$Kb-1U5w+%NoS)JARta8TNhK)Ba%6_ZWBI9kt?=xm) zJ6G?Q@wVa9k0)g}{rFhM+lKqzeki+Tp38XKaNfo)S<_wL(c6ZfpKX+F{q<74ZMbWv z?@GEaTcfuP)7qU-a>ClRdfTws#idhf@3c~H8z$~Fz4X#%^Yyl2@eQ@zIUl~Nw+(~7 zY~{xEdrEH`HZ&aK-rjGh-ZoT!{Ykg-_v`hx;qBvJb<>_bpzyX~#XPs}of##(ZTRxN z74E6i=G5nH!@Bp@y1l+FDdla0|9Oqu=c=ztdE3yY@iKSb?F}4n8>)|d$8GalXUE%y zue*46$hrp|ZyV;#eB2#>@Fd6EhG)0#@9Ni`rMC@Do1E)5Zna2n8{V&1#kH=wT5lW9 zKkB~HF5zc6ylv=EzxqovZ(Xgo4Tnq~P;&X)ARpc~v>UNqcFs9(>TSb@zctUU7(H2U z8_wISZ#L=ik$T&(`~Ht*jqmKHw+*FxyKJwI8|!UDh5P1YU0?m7l(!APk64<``R{n+}vZTM~7+U${*u7tM@Q~t6tE3F;=uKw`0;l|hIXJ;?ICgW{Gj~=gO zpR~9)<84FDv!2d6Z=8_vw&99O!?KSbc_rg*L&=V}xFgJ0I$hEc!X z;f}lS3B7ITSmi-iDnLM$MLpd z;(0H)W#^1>ylv=p=flpoFLk_ac;$}nE~`98ZyRRqa)SHIiA(jiq2f)ylpb*38og~e zqQkkRwKlHR+lHM646Xmfkd=Dd@b1VLO8(=B1$x_X!MMZNp)&T$T0T@fp2s z721T(qbFpeYPHeZhQDr{p1phIp?cde_nY^!*N=Utl(!9iPF|6&v@HV{o!}BUH{fG<88w>i(bw; zA2lN5ZG*dFY}VuX=Q7?lT>903?2?KzGu}3o4!9sYw828XZD=yTde-U5ReIa7-=t9` zjcR|Ow+#mkTwAZ-{MCBfulxKBp-0B0@WX;4<-Zp$OccokZKuyQnhIb!b;0_pfh2w3*)R$+tnq3Dw-ZrdW z@QgdW^?1kIh9wK{b5+lu?s(g<Dl+M)!T+0 zhiqQ@MDw+J+we>K8YQz2U9Ptc2cNaNTScUIY(#XyH3^HhA!XVn&pR&)7ysn z=RA;gSb4YJHnd(pF?-|5i}bdkY1=ol4K;Sv+lEUPyq|sC?y*wdHuUSTDm%Pw^(nk< zm{IG4touiIl<>CU`;Du!b&qeE@wQ>vmy5G`cbuN_wqfLEZ)c4g^vZbKQ2P3d*+UZ_ z$#~n4A3Qp%Pvvx{^n# ze4w`t^g%{4#v5Tku5($J>UV_n+pT?J(T&wqg3u z<6QltCpz9XoIhuvTfF#n$J>T2-oC{B(CU4?Z5Y~WclS-cN^cwXt@GE?7sAhSc-v5C z?*>y!_g|y84KuE2SMtUwOZ2wkx#s1w-R^!{ZyOFg^VF=(?JwzV!;i<`mF>CNBYNBL z*ox8F^Eck5w+(-}@TIK%gj4ml;gb$;XGgtIUT+(Emn_My`CI!^-ZreLwI(}l;nDSZ z+wgmM<9FuO<4Snj(Bq_4*<)Mop7FL}*&Xj^{o7oU@wVZ*Z(q;udVFBU+lFJ$nV7w| zWL(DEhSMG#o_)9Nw2Ze6vyZ7L>D4SCz}#@Th1=wJsocwzB*)z>sxWO<88yb z1&_Gv#=huy+c5j;Uhcrp-qPEKg^N#j=dN6=w+&})Rnfio!)m>4sMV=+>09BAA8#AR z@4G|&g?Fyf+lHUUjw#vr(ffMau-NaCjqUe_-ZuQ!?4s<%s?X_d!;LT8osGQX0ljV5 zYrApTo~PZWw++`_IW;@+kYn_=;p{EvW~c4Erj)l0Kh|2FZL@XFQr*egptlXZey*9#eq*KHHhebWxsqjDexSDv-@eg!}k}yAKjR`&*9^-Zs>nz1nT|xA$M-Z9}>J zKXChg`fw?48@f$i<$i5b-SM`e@0knT*g6+D-ZpfsHPh|)#sJ6Lh6Cn5=Wc5}*73Gs z{P`o?(9)M3ZyPRadb?ZJ=Uu&R`01MZ?wAG3^tPeJ+aHwHh8y5FDpmfPIVeJiX z8(!REUH#+#vO;egzPx2l$!q23>21S}3l7P)-1QZ`ZFua>o3bY7P0-th?z4wwOYXhL z@wVZ|Z=TLdcfDF~8@AnYMmGDnz4f-Ceys&ri)&vjf;nlO3W-q$qGu}2#+;2{Hd$aBtZyQSPDb21p|KW_c4Qo1% z$$qZ?LdM&MkuCaUC%^Ni-Zo4=v{|-mt;KrV@Y$2wW^X^dT5lVEoYtpgY+^!CXM^|oP`eX6?EFU-{2hThw^be|7;UT+&FF6i&t)O%2G8{TjK zguDCfPI}wWe*2f*36ErY+pxUiyRKH}&q{dPFt6t_cWK2VN_gAQqUu`rx>9c&D(>S;pZIF6-Zq@}(D*4gOk1P3 z4aZ${dddEOU8=VYZT_~QBztm>-Zsqb-8d`PIK1%-ZyVk|yIc12sgLPx!};AtX3b9P ztG5kzbeo**ckbDG+fcjVo7u&`Zl|{m+f84TUEB5UQr`xW4Ik~XIy-XVju~$o=I**E8~gb=8E+ewoH{GpVQs&Rw++2do0R2`KOW9X<-(iQ zhqA4&@ELC#M*Zc^?7ZIZ=xsxdB@MDSk65O+4UZi1b;+$8*63|Rzdm`%%mr)pwqa?l zx2Ej2Vuju|yt&1U(nG$Pr?(B?oOOVE;o?{IwjmpLy*udRC-t^r-`|J0Syv6w+lEQ4 zo^rRIbe-NdJox6TZr+^QdfRYd!})Ig%IPJ%Z8&19mF~LUFW2X7!`M}8-HFSOE9GrN zxixECz0qhmw+%nMzb1S7$QSGLwqenSYqM)k zomRrzhVAxTnZ3VF?Toh#{jQv!JutLY#@mJpzrC96w)2pTw+;O#JeB=C=E;n=4cDGA zG+VU)s~K+_+PAzRYx34Sy=~~Z!-3iJZ>-SUhRP4TUb5Z0YxTBaXotD=ckR4ZZyUaC zyPf`yEBl%9rnB&-v+$;~@J7GsEWGI~yy+~w=`6hIEWGI~yy+~w=`6hIEWGI~yy-0b zfB#uH{kiZ7Z?4tPh~F8%a7vq<3%Jd;bxYjxWolo0@<$~%HJB?L{_eCgzazlk)yA26 z)9=o2`rY|WzdOI_cjq_#?);|To!|7k^P7Hme$(&HZ~EQ&O}{(8>38Qh{qFpx-<|(| z<#*@#``9@P+qag$_N^tbeQQbW;af}p%D>m{zpC56^7pTws98S8CN2A|FKKo`Md2zP zwk&z?!!3o|EewAj+VstZf7xsYw{)i;^t;>TYhLB<|8BMLwwsS|U0;|Xyyu(Vy}s8N z;m>Yb>RvvfqwppBf9uZdvY+sm`<3&zTt8C3SKj=HE&Z@dkDP)I58qeO&wAp`QgE#% z6?~&fnFIeg?l-q?V=v+B=6&IY{X9W5TIN#e#`x@sT_=_^TwBJ|ws_jPl zfHf{S)gk#Vr%%4W>67nr@_q13-+v6>F$Oa(-~Od9xK804;zgO{8=ZVB+`iq(H^lV~ zO}+^XrY|_h;MtdCPobJ^6;OzS|Bz-(jXNnC~s8GRb#)%Y4s0`OdEg)0b~M)7LmtoXQ+| z?Y5HX^vD2z`7f1)m*3LAj1I{+j{o!w|fcD9^p?&ynt9>(Cm~m;N zui-z+@cmFYXeVFb29ulg1JgIfv{`$Kky*O>0?F^v;}Xxm^rbD;A^E2EpMHZr`PQ}v z!-M_k3&wt_O!9s0GT*yTzQ^ss^u@O+XNpr9e1JSY!8c%hmFkduznDC=?-cvw`^Ds@ z)?4x&3=f#T;F!NfndDo>tS9!3WAapMGHV5xzH!|sa;E&LOvrc1kndp~5M~`nb>O?X z_?;X~zJu(O?<13&`VKGo4n_wseZet*i!#Z#l37o3VvKLFC*M{Urf*y~ikvAw@+K4V zU6_0i>wqxpK&nHC56uN%CEr>0$@iDZP3ejM!SI9W3#M->lYEPr^+a>w8}EDz8M_fX zVETen&J?FIA+{t>tcBPTCe~6NLXL?)=Ag!nd8+UK#{AV>Vm^u|#nxB#lwAM&x1L!~ z#EE>6(^!U?OUm;{jJ(N&d>1C)!@t6;0ilmDIt06jpBzlS6YZ1lN0XbHOR$+R{9yWm z>6^+V-;!oM(OiPh$y1HRS^=gnn7+oD;#4O1Kr-Ze@QpC*K&nIXeQKY4huSCKr}oKr ztA!btnnqtRH8Yh-zE$m$Z&>@}+t$MLr5@7PI8%(g$%Nbxre=nm5vFFQIwaq}cFA|H zUGn{FmwXpn7=HE|^aZn*NoA66VY}oT*)I8ZwlIC!r_k3pQ;fXHgf&Z;y-ZlkgxSla zI)pu?{LUUN`Hr?rzOU_)?`{jj&mNGzVEU#q$+xy$@(pem_LLfnJtLUDVEP(oic^`e zr<4qP%&?~vW{;WbkbJ*;O7flVDarS{r=;KY1~V?_4ElmOL!>fE-!k9+PR6RA^woF6 zjq^|V>z}iAVXP{_0!y^ril%oGDK7B}?)sOY*CX4$1nHC+kw4tXFxmjtQd!H9T31%E%<^ zWS*>_d9tnw!$bW~*0(Y^S;z8Zean+|uZ#{!UC5JqktcN|PwI;>I#9!t8c{|jsb6_g z*Yc#^3ByDEPwGw?oYa>*sXKX6kILwf)ayK{<9SlwbLwxb`@-lzTT;9KlT17ps6Czw zgyXrO$ODJfcmDg2Ffz%0AW!xQWpuzUaUYc@`>Q1zqWFMX< z`|~{6w+mwjaxUdeak5X&ll^m^?5oS@z&e7hSTmCINS>Ti^5l#oj1H_f$r+@KOmaTT zlXFwfddFC-oypmx3}|F6p4{nS zH@oW-MhE;t-^8{>nc!2$T&Vxa9V0f>Sojf4-{@0eI2p_MQ<>xrFi-9V%jm#fmbnna z$=zL^-02a|(vutkGZvV>VEU#qA=fk)>VL>V-EFc@XV1-8N=X}UqsQ<~G9_zpKjP*r4VEUp1eN&lGn=}{df2djF zr2cb8Wi09un7*+#6*=LdJ=U+H4ChSRssEfm!PNg$hfrt5AM3BirT){N)Nais)@AXe z*!pU%3$>ej1o|Sw{Q~v@2RV&p7=2QnKVsxfCbN%Lc z;FL4PsSNjJ$W#BhM*~y;Qys!OB7SOkSZg#c^*^jZ(uevV)-25>tTDpyfawdSZz>b+ z1k{)MAMOOiN&OG&oyMZ(gXs&VuW_b0mEj%}8R|dxn_%jHszX@c#ZL_ncLExh`X6e8 z^r8NTbzgI#CWGMt(-%zNR3_XBs4w-OpEKcW>VK&58jE@krY|_?{_}Gt zF!evxA=F**Q^P~O*SOUGP_v~E^*_{j&4ro_h6hYvFnv>*q%Zdj#>v^-#uAQwxlbr^ zra0lB!p|>}r~W6HyM>|-iLJO-F&nzXwl1-`Fr3uq#BOC|5}$JaBTnjn5(C2UP}>t< zl);J3xu22F)c?dsWpqel*d?*;l9+c%E(oIo^*M>>GBQc7aWAL2Q2&$M6o!Y|p5#aw zoa6%cW||B2KgpdkIwWfg_mCQw`k$;tK3SuL(SiD$tTSa~k~NU~QgKrMlQmNq9%_5C zc9p@&8pVC4=0g2X*0eG@Y=7Hr4YyhReZy%lAJ7OK{tjy4XPz$LakUO;^l{UUYCo&r z{*B&fdAsl#ztnDY{3~||e|JaiMr}KF7T&*7?M90`cM(42`TZKTxuBcy4sG{qv{%3G z!aYvjuTisCdk8NpDPVK}BLhZ;zF_*o35Jugz>I|sV01t?FuI{L7@e65n7RCMzO+xc z`h?=#Q;bc}6PZDuHYw^1wz+(=tVwZ>EuU{voO`XdO^P--u6mQAt!^E6QqhKc?0-_x zw!4iuQF>zkSIeFFpY$<3Z7#^z9O-Lwhtq7rSY|79FdL$q*%qD6=FH{K=6hnZQu&Ly zgUu$D&V5A~yMfUkJT)s|^nCQQ>1s#Mx>px4dfxopG_|AWiUm`J(er=>FAJmRelK}p z^labP38Uwq>4OZqAwyp4)*%mvI`Y`(;X;XlsZ?0}5f zir6-t!8RA-+~!D}+uVtBvk7r-wj$2WhQztqmN++?6X&T8rYHK?T#&Ij(%0q=r`d$D z%vR`NHbghGEjpXcEw8ba(VoK5p2E?d!qJ|>(VoKSZ)3&0 zlMZ0BPs}y7$6OPRxh5QQO*rP7aLhH~m}|l@*M!NV)JMVB(k~n84(qTmI;Z;3j&8Ig4@MpyFg);s;b&Yh#sTGGNm!=A(25r}8!zV%X+L4BOm^VY3M_Y_=kX&4$FV*_IeKn-jySJ~kKHZH~y> z+~F~sz;CuI+3t-Cyu;l`nTrgkQnt%?rCYV0x05%=KrUTe? z0GkeA(*bNcfK3N5I#~Re4(MhW889*_HW}7Zn@gyt!tjSWE6li|{tBZ{sLR6W8S1q# z`iD9$%)F>aa57)kZ7{w7qXRhA2OVrK=m0hyz@`J(bO4(UVABC?I)GChh+ET*xH6rI zH=7G_Xmcb!ZSKUa*@SpDTM_4GL*n0jVR?-XV4J(?K)dMxHXXpG1K4x`n+{;p0c<*e z(czCa$Nr3)>R=dOgcxp!Ow_pyhLd(=42QmwiE|N-a}kbn5sq^aj&l)?a}kbn5sq^a zj`kFeHk1yG8|+-vC)i&YdG>^66ZVQ=_}N2(8JE2!7=74tg3*(`C>Z_Oqk@?i^94s6 zN*}|t$JkbTjBR1^4&AVA+^Y!3*cOhlEgWN8IL5YcjBVi<+rlxng>78)VO-OhcAE?G zHb;1D?(myU7}sotK4wGoG~1%T**va+(jl%hWw7aE@qR7=6$a zjGpKZMt|l7W?nWfF=KN#j0`@qc5s@HHWy;s<``?M=16RtO^9u?6|rqLB(}}A#J1U- z*tT)e$818br8?VOkheL)V{?b!Y{Ix^EA%lNqNmvw{mtggYy3{{HC*`1;)daONE)5; z!+QR;g5D%*zlwyRtQfyWMRXPs;(@y_x!Pd%Ln;m7pzh{JU2YLS{VMsqy=XQR~xjQ%xu`#|l?>-$3sc$>O&i|uEf^KMao?>_GodES~cr^x^H z!E=h^-aLMGQJirAFUlbm^^+2n;*gEN3i)3 zY<>irAHn8Fu=x>eegvBz!RAM>`4Mb>1e+hh=0~vk5o~_6cKm4aW(V^l?dC_Y`4Mb> z1e+hh=0|Xt*Hp{9&_31t8|0^&-viH7i-*8J)#4{EVc*#7UhHAi##D7iu@r? zisOd(De4pAu&8HirAHn8Fu=x>eegvBzt=;m@{7Ad`5o~@0n;*gEN3i)3Y<>hYNBjsj zKZ4DVVDlr`{0KHbg3XU$^CQ^&2sS@jyXBqvk#_SV*!&1KKZ4DVVDlr`{0I*7QoZYO z^I64p5**~U-hu;<)?skq*ZK?&<7(Xo2Ys}jgM*%0C&9K(f^D6&cKl`XkRn_4*o652fr72LOc}tL!1=H4e?XdC&ZQN z9Xz&9f^D6&cKiiKp1cFYL*9YmC-1eegvBz!RAM>`4Mb>1e+hh=0|JCk0y^F!RAM>`4Mb>1e+hh=0~vk5o~@0n;*gE zN3i)3Y<>irAHn8Fu=x>eegvBztsOs_Jbnb5AHn8Fu=x>eegvBz!RAMBn3w8Z^sm;* z=y$ER;J~AG7##SuK7+%!TDQSLAFbzL);)_iTPJC^brMXw$AYzQ{ng3ab&^99&^1UBD+&8J}VHP~VRY_S2hm;qZXfi1?s7JFce zNo%+HS`5=}u?@DE2U{+HEl0rUiSNMZZ);%cuRW`OUijHTsC|ZslYkrQX9|UOVcNMv zv%B$dCM{y_tZ3(~$~_)9-a84$dne&|?<5@WorL4PlW@Fu61F=uI60HrSn*y(GVwk~ zINs+7$NL=Nc%LI2?{kFXeU5Ov&k>IIIl|l(*nHzXiQ3U2oWYAS;S65v8_wXu@t#CD z-jfK&dlKPzPa+)eNrah8IPVK%+i*4)j&}~i@y26@cxo18jF4V7u!8+g%6P?mEDB*8#S>4zS(5fTL|Smfb=3j4|ODW5vF#tH{I{6OJ(^9Aiv4#+Y!7F=1O*;bFe4?O^QB8Vj~H7Hn%Q z*w$FEt+8NRW5Kq@f^Cfj6F+8K#`I%>#P?Fn8L9Y3E+o+6`;n`$OHgb;I@s z%!TzKv`>XI_SO3V!^v1`kK-2XAN#^%>rXQ7RB+mEpLAKm|egPyt<0tfwdUj(*$ z7_i;LfbAZ}+BqAVJm-2aJe&=|@N=#QGcMq0K>z%9t=O{dNAX1 zt_PzJ=Xx-DayA5`KW9U*oeg8V&WurBXGyT-BiQm0Z21Vbd<0uQf-N7xcILHq^B3~w zFL=yf@SDFF*ZhS(<}cO_^B3z$;;;WJ@2jcHe^TGe)Lg5@mXFk8%SW)~BiQm0Z21Vb zd<0uQf-N7xmXBb|M{7^+Y82!$2-v-CKK4H6uq22Cbz;+JY*xOY6Yj0NZ zuf1i(zxKuz|JvJE{A+Jw@vps=#lJQe{7WvUH8OGr2}PdK!-QQ9Cx|EjlvT zmbd6&Y|dMBFuvd|Iv5}E79EW5!W@P1X_&h(z9z4c!7r>ihKYZ0j0fQu55h4XgkwAi z$9NEq@gN-IL72Ia*YGn(!!Z}sjt$9iWUwuFtzc{(Vow-fgqRe@MM_!x#^0kMSTJ<3TvagK&%oVdg@vF_z^T*m4bQxdyge16!_v zE!V)7YhcSYaI~$)!nVXb?Ur|7%R7@NhQTqegkxL@$G8%XaU~q%N;t-qF!Lhs;IzC0 zTi$^!@4%LKV9PtOxH}&%a>W7z2zf zeZX+Q1;)nM5o~^p?ecq+S3H2xJ>e%lZCs6k3^qvg)EKnm7xUx!JKyFfKXPz}PcJ<8 zW`A^r@xu4jY30KjAUyTgbNs6d_RNuKbxK1Y{uK^wKKz+*kaeMtaNux(OE_@5ForN= zChb`wpCvq5!k;JO=7~OeqGz7ypU#VR#Vuo^6Z$hIx`G*#ImCHsZeYe_&S1vG7GTE2 zMqtLocHlTKYsU^I?-Cw|?T}~8WL)fQ`e1+46Tb*ErumB)AwJ=WaVQ+)P?%UF&XI|6 zn1f>+3dcAUj&Ud)<4~9}i52=XCOHfa^2DKVj6-3@OvY7=A|K<>^b{BEX&i=mDL$>;Ol${c%w$}j=;IST zJ+?!hF&X2c!DI5XcNp#~E^nTJ-+6tQUpC=g;a%1b^k?s|b547`1wH&>M;$NRrrotZ z{3{&VeE2irAnQXP;lSYnmvG>AVGLo$Oxm+VK1+D=gg;Nl4Z0Tf$rC;EM1R>X&Wm;z z=Y_m5W1?%E7yQDE$=qmXOy*qR**V7+V8+BoV8+CD;5aX9cZs}9c(9vf7&93cJF6Yp zL{I!;`j_z+u|sd>Ghx(mPli_Zt_)LZzCwxxN;h5d!U?)ySM_4dKS?fXv5 zhc+H6yz2>1=P!ReOt|qo&Imo@wUr0clqa5HqMB*yGr}|8=9S*5pVwVfxge+Gcw|B z%@+6iDs!Jx-=-&Y@DDCID-|(NN4JA&T<-UtJX`!5J|Ex*?6hT$ zo;9;pe&6%n5&vu34D@%O^RD>2l@9bB7jBcI|Crm_`l+{9&e4Bn_l|yOFWdHKVRde+J>bq{f>&1tNf6Db|`ptK#o}>T4zjpUO&8wcH|1l5u@C`a0 zA^ztkxA05a*B5^_??V6PnGMC??ZL}^;1z!u$Je{zSn(@6H|L^Os z_T@i1PW=C|*hT!oPCocm{K3yI*hT!oPCocm{K3yI*hT!oPCnR0{J~B> z_*MMD&o1~?{K3yI_*MMD&o0EA_(Kf3;8*bnKf4fr;t%oYf?vfS{Op2X#UK3aLR=Q? zzp}9laVh=~r!K^$_(Pn!u!f4CH8sSg_(Pn!u%3#a_7Ioi4{_>3T#7%$sSE3@_>l?g ztoXrUofSVg(LW1ouJ~zB^v}ZjD}LI;`YV2LqJNg?pC$TdiT$%g|17b8mgt`)`e%v# zv&8;cV*f0OpFFXDmc&n<*gs3`pC$1_URnH*R~A2c6943t#ZR8ZKY3;GLta_@0sp-vaq zpHQcZ>rbfD#q}po*3VG0i|bFGte>HN7uTOqzl-Zno~)mFvVP{t`k5zdd!DSHd9u#u z$@-Zm>t~*<|9P_h=gIn?6UT9{k|*oG+T*?@PuBlDS^p&y_cOwAKO-FXGwAPPZBl#O z+n~RTbxQ4VpCcUiIq2_V{X%~i>lgaFSii8p_{lTYg;>9^zxc^B)`eKV(BH-Sh5f}( zp0TdMPoA-^!B3vCF30+X{l!n7u`b8@h5f}(p0TdMPoA+Z$NEM5_*lP)A0O)%@h^Vz zjCDEIFXCVP3RkpFE?kz)zl07tx5oeC(o#h=ue(e7vU$*sEhEEXVmpV{FH-N{Nx#Ry%0ZJ!Yh9AjJgOvc}86?#LqUW z>+q9j)OGmDGxjC$lV{ZRLi|+C*_Xgio>A8e@l#!O9e(nReF^;J8T%6W$ussP@RMik zncyeS*q6Xhp0R&|pFCq<0zY}iz65^qjC~dS&p0Q*j|}Go_`#eL;0GuAJI)O7)1K(>I6uHoJLd=Z!HNFVU(=uZ zYx=vy{w~qqCH8lT{?uR7-zD~E|6ulK|6ulaN&NW4{w|3hpV*)MgW2CD@x%T{{Bi#y ze)24df1kt;`#0I2JWJw-{g3#`vn2l6zllHY-^5RzCHc$#P4*|xlKf@=Ci}O zWdAJvu~V}Cu>ZI9ll{M~pX~o_{q)KD&;H-mPtGZ}{dA?u5h1&-`+cXi0)w?Ip!>P<(&hB zM^&Bez8~04c%ODv{hqC_6h3=lBhSCgkv9Gej4XY?aKHtI+hT(;LwjcJL0%a7z>^zK z;1`BJ{430uVGLo$41I(dGmIh3m|+azI4^6@68S9QVGfdE%w*g=(I-#z%oF|dHdT7= zgU*bZ%olmH13W&?3w~k7WNx%GW@2aAj&{aO{E~$?Mye+l)$Zd*u6r;We)Vhhk6iSy zY}>8o48HWqzNhoGBFbu&(Qm{-)_{hfcLH{F6h-t-A`(YSDf;hfy%gJT`K^UagFs85_@I&O~6(I#q7dE$H}6XzwK zXcO_%9_-Ax`mOkb47XmoD0mD3BOOq z^@%<{(G$Oz{+=-kJcYaWrk!5Pd%ak=d;e(mEBQ-Z`behoqHvCAI8gZWsipZ@=M~of zWBb0CA9Un>YOhi4xxC4k2MYL+r}Jes9uz*J!i0Q6ori>9Y&JIEW^n-%S0TPa{QP|l zS=@D@*4P`L7~+3>yQT2E&yFC*w9cS!pJopVbRr8Vype(krH+~p76Exh4|ihlVw zg&J35{^9mv$3AL&-1LppArwC9O@p77)ef1Zq+CHjOs`g@*+xn#^S z%q0(V5e{?7nM0gA?Ka0enLBpLE$;%qaF}lv#uX0p&4NC{VZP`o9OjGu!ePG5OE}Co za29pL4%Uu+Odh)lW4DCgC*!(AALYCGF`1)J<}SbgtKzEs5l3Z=Rkd?he{$9!BZjB9 z>E+iPbz(*g&)9i@zvJ}NGh%rEJ@4@co!B%ZhCljxh(F?%=hSz}tegFHTerxF=dsQ1 z_w_F+70;w6y7;$BUKLN@DR=o!_n(&$+q*7&z|TACO>u7Q+0R$rbB;J)Jo0Ye>&0?8 z`dsnkW&YLo-V^7$tq1#;x>U^3t@g9m`zj5$%hBzFM?3iP&E6O1%kSUo&pNM4j-D+$ z-szW5-%C7m7o6q~IYCpE=T66n^Oprz`J)bLB+m0X)bYbBW#YW(jO+Z_W1EQc^XB#a{1%PG`P+n> zeEBL(#ku?5js2p#juU623GMyP1J4!b);pc-w>tk^an9MNimx*50&$M|;WS_VKQ0w# zyK%etZ)RR9&YokM`d}By2Rr%cS6wImawI^CvCsDV{YyZ*;-d;t96*AwD!#h!;2R z#@^!T)v=rpu_FEuJ1+P@Ji#Y^@?HJZ_lld#`w%zc3~}U6n?Imn+b6g5A%?^gV# zmOdfIU5Fv|4Kd|Hd~4hg?=Hl*#tQN7LJWx~#FPuMF8&bvF2s6ajwd#CVXYS@Yf^}H zafaA;Vci!e?P1*)Cpg5qI795aPy@tC`h^kL%v;-?q0BtG*bHnJoa$ZhFHt|zgPCwW1hOHcAXiH$tT z3v#~TyRZhF=bOkronEb-Coz*JIl@|?xv)0uHN2_pc6pt{@+3#{C0DkTZexZV%^IP3 zv1TMWlJ9Z!Wzy~Ay&B|6F639-f0guk_1$B0^uS-}b^OxnH0~GmPs|yQwT|%_gSCz^ zm&|CbvFh|VIfs|Ej&a~(eSu1=b6xYl=S?9xk zrMPD1$vU4W>wMU|6xYu@S?BX)ozIiHlPBwZp46Z`sX=+N&gV%z%9DDeeFF9*N0WM_ z_P93_j(f8_sYhy$`!wOWPeV@!Cu<4$7WZuE>0+%!PZw*YWa9n}JzcDu=;>nJ#Gc}0 zy=3i(brXAvlXa1`4^GxX){a;=v8Om$|5)STWX+=7fb9)5Bt)J^e(x=9Rp_{o(}H^mw1CVuyDk`tkBiZj&BJk(8b zhPs)Dx+%_3H}g<8#Tn{m9_pqzL*2|n-4ti2n|Y|4;tX{&4|P+Vp>F13tq^CZn|Y|4 z;tX|@^+BAWZswtGiZj$r?I#McQI7RN{Go2

B#l)J^Rz3UN}AH9=#Ax|xSHP-BI< znX%_6#LsrD2^u%l%{;7!8aLFAgEQ3|oQOU}LuJ;}eYHi{?IO=3m-9#L})dq&Pk zaFRpp5#c09IWNIUJLe@h!R!&?Bu6zYL){c-sGBa-O>u_0=|bHUXQ-Pl)J<`Qy6HmQ6lbWLF4RqNhPvrO-7Ii! zQ{qD16lbWLE{Pcz>ZUkD-E>KuxKKC68S18EzZ>I|{gwFHUxm6U{!lj^d*2wJ?5Q*s zd#WTCd=j5Ni4FFX>dSsIiBI-a(t$lyk{3RSPao=&bPM&$Co#j`QaZ4=Oybjrx}~u~ z9b<2)xwE$nHB9pgHO(jS$=*^ru(u5LOq`*<`6L&7sBPj2wa%jlwnDE^+tfGII?s66 zhw&MMSYpgj+hoH~>pZ-~663%{{J@>8pB^sa2kvD3_6oU{>OR6xoEz2FPGd6 zhW6q;0C$zeyF~0#=sTIai2ugjMe#o8k9VP-y8`Ztle>;G_dMwE|8<{`=lhf@ zCO>!3xU}<6BBQmAHoI2@+r1)~ct~{6y&~;)uLury$dh?#T}|Ra^R+e5=90rwaJecib=GU*u`y&%nsi2Mh;XV7M6r%s)wcNg|&mJXyk@CF5p^K3Sq?mguk8 zW}Gl)9@mMcTAYy zLF4ztXpg@;mV@K(jtR%#9TSefJ0=`|cTAW#WDNT9`(BIz=J&uD0~~*MOgR4Tn2pQt zj+s9E?wByYuf`bkwci~p@aT8_oV7Cs7eC`dK{fv?cmrf78=rJ7gHs<`wH#3GLJt)=x0Cg>@B7ZDG9?F4QmK z(5Cg7_8{w6x50sf`jvyJEv)lk#!T9&UnZZi&PN{A5inyW}x`YYD2 zQsfyEoxqHVuExV0gbVdcm@%0%?brZYfEg1Tfn)s=j`Om1>X*s8gopZN{Mb`C)~^B% zVcqpHT>=S_7fgm@}awA%00q$Yu)88IC_}yvV(h-*6lG=xc(32 zv+o}pBz)Xuk7tXg_7blB-e!5HTJ43;nR9Sn`c-pb{>%TP4}Xpvn11vJ!v`;zaTpKG z_~-#fFZ2VWFM5NS2lD|lKjsN$-pn72J+KQHJ7F&{_QQ@~e8)fdl(h?7TFd7{Pc58H zC%svkcUpdz+HafkQvUtNeT7fH?S;Jax&gum&YGBa-uoWm8Fik_H{WU~xt766t|e;= zxvBO|Yv8}n8u&lycjAY*BEEQg3FciV?^D6N>*TFwL8kB~7RP!Ek8Rrn-XHR#`m3l)vb@nh}CsJ_wdbcu9p$3Z-u+|#=Y{4SUqP$KRZE??({ zY2sPAZC`&;{h!2h)8Nbef<~{2XV$F#{+(T;8uQS+wwX3R2kF8|8`l$9DR2C zzJuS`cH10%7M;=A&-|%o&Rq5%af-jB(e^p|-0*BSKl;i2#M5P3Q-9wJ2Z?999nSUp zcRfrz%jaI;$NMA2GyAg3eXVB4if7u72l=yG))UXEpI+_XuGK_5tG2J}Z{Pn6@pNr> zjNk0pX5xAA&dl%q-MQkqsCr}H^VsvnGobrce*Fm-is!!XPVf_dy-YmUT(X_-{{FS% z+2_d}ef_`PD4x!rRQ1nP>mZ&BFWJ>M-?p`QUbysiciqO0;<@7HJ$!{bZxK(gOJ=){ z>pP35{GfU6zEir3r`}PE+^Yxn63?rTu5jn>dxv%QW7XZPFP#l7wp&$QFJxzDO~6VE<}T~m5`%faG#ZB-BVw5=q;tSUK${twpBZow*7Rlc*dO7y|nfZUBuI7-p3`g=L`|gn*Zoo z`bdQWPor{Qm)yT~f#=3X8%i2%U*I|W*`G`9$O=4zb}N^iyL+MUE6;C{wQJE;I<(w# zXmm7$S9BN8 z$l5<=7uRSlp6@^2Du1YPbMdV2ST*0}vi9oRdEK`89Uboy=fFdM&sI)uDV}w&?V4{l z_IB}f-g}4q=rb-A&%tf?%#XSIMDaBLa^Jkwgf8m4`BppSw>G{?oZGJ7D<66H>EdZV z=b-${U2hOio%d?zJ*GAn&r!b}o^RIrXz}ph8CRXFzHfdU&OHm-i1Uhr4$8ZJn2U%1 zzP8{Z@yt5CB){dso z>v~6sv&qw)b7C4!V*I#!>Wk-%Md9}@LoU&m+&cTvM&j%}uXj%VAWuHsdiC+*Y&5rD zz9>6I@}GY@FsCLm->|33zi)ho$bc!>94U-86sTRg;gu&;QC0BYS%MMeGEBi-&k*e~-UtXMc~s z!0hkwmvGqM<1cWck7KWozi3bNafv=I(Z?nFxWqm#(Z?nBaUuT9J}$A3OYGwkfBD2d zF7cO7{N)pW`NUs7i60;0&-~?+`0+{n_#}RO5Mrdw%&O-+hu_KFN2VtCmllzlR_dmfV|E~8x<}ZB5Khbxae)jag@v|q+=k`t``5nnk zzq=aV%<#LV|8Bp#n))lfyZdL~v5;rnw=m|Wd)NQjd)Lz{ZT>R$T|H#J?_OoImk%62 zIRkHf-Fn~m^SU{B-LY%^X_a~iPj58KPdj{^aQLqe|1TW=96908kN(1e&jsEF@Gwpo zPndD6opDT_ag2v?jGzD7xcs^4LqF3KKGUCZl6leY;=GXeabEBUM}FZru5i>xIO-`J z^?w^s}c| z$dM2K_2K`8!=Jk#Cmi~@&|f(4xxgz-eueR@J+pSkF?q%@9>y_#{%hm%=cW(+Oi%bs zf5u_FI4|0jUr}B-@(4$MALqrm!ciaLsHZUFU@zq3ysVx1nml$8j`k6bb`xeC{vV#8 z4|X;^vA-~UroZ`%bv3rDt}zb!(H?n(BY#eN99KB%Bg{D11sTQ(yuxu_)-Hb`6YZe( zXdhwxgB_9Kzx+Sg{H4CpUtq?;j$rdw((V#@Ve=R5k>7*kxWZ8%;i#vu`3rgT7dXz> zh5Sk}zBWIC&5vO7V-gP;IF6fxqdvmsNA=y5 zcgmv}&%)-%#BORgKhkb~lno1c^q=z1>KcBueF)h0Az<5wfMeav!L|+AAip-CBjQu-Q^E^rO@8u-0r^hw)ND0 z$~Jd;zx`3d6%Om@mwa`&aHX@u?~^S%Ncf(|+xdPw>?i#2Np1asi}ozyQMc?;lxdV# z5vK3`?J5bw`SryWg&C_-!!3l-;rzy%38UK)J8#UGJ36<%=2v0nGXB=zgqh<5!^=sY zxxaRB1z~LR^PH`PvDLy8Dhp%7&(EqRyverzeB16hE_}!2($R|H&G!m_zxU`-!h64R zLH@;^BZaHpd2Zh6%n`!KxBflI9JX%`zW>9Aeb-wK5w1~nq;FYrlyLRYBYee1x$x-W z_xlZJ94CBowV{6VdQF5cJaVw#u<%sj?RFU8AKUH>;eoSz`*-FP@OFKA6x+MZ>Rgl` zyTvU8TYY`UkIa5-vd7oM$gB-SSF1ACwE>X%)Hibe812h=4}dk00eP`f{HfJoNB~{jJ{}oD&264jkz}Ijqn= z;f9gE{a+84Oud^P@^9XLq-4H7>>+=~od@N_Nw*3k`~^Ght@gp4AM}4&b*SXW%oyQ6 z=v-gzGw&PWk84?1^3xB0z|TMH0O4W7hx_O26vl12;{*PoPmfmL{`K$oyZv;mWTwo& z-_P6sFySlu+~?a=IzlpCUl`(#`Qk+JU%GghA26kX+82F0$bZxN6t%zn_`Uv|>^SwE zKXZt$xT2n9+8;d7|8~!*!f$=u-=8z=G|3-dZ;*fH#uFufSEYM={mHr7yN$Tpzi`V* zlAm3zuYWT?UG0_c>F<|c-bC^hY7O+K+|)?8+Vlbb{O}G7dmjH&AK&8VCh9xsn;!m$ zr%sd1shjurZ|&MxxbmDne(6JvCDZq`JB#|SKc%NXrDLJ*F*9x{&iA?LU5a{c^G^6( z?n4TFr!8sk@7nnU@#GtB^0)2ZSUODo=(eIAs^8X4dZJs!hPU|J?m1TSHGaF^KXpR` z$>05aJO9*&4W!$l)jG)z`1-PW9sT#GWRj^@{U(3moh9n~=&M)xe)W!${JwK;@$)vT zFZ|R??fp%=9WD9pty=kQDinOT{oKnGZ^YjCzh0s^gn#Vn*8V7enB<$jca>rcnT5w( z;=hj^5`w#V|ax-)`lv8(UK{@GMwg==)9U%lsWTRVt3VW{;|x-^SR{hTrG$vv<44c@P;zT-D<<$Hf$ zK{EJp^eJCw%F zBtL&xPyg$cUrUBO9dgTZVeu;_8q1wso zI@3OuJb4E{eaX}1Kdh6?2^;S5myh~feec}ke%Txu^7=RTt>hQoI@rJX;ReZ^S80TN zhyL$R9VR<7ch*UKO?$iRhZp^|)pJ8+Ph?nE&v~q(e8<|`{QPYt&pL_U8Mpl3h86wA zy4s<2!Pg6S80AmDc1Ovx4&U)^CCRf+5)brcU9Gx%AyzB@`jB7Tyo%acd)NQEz3_{x z9`GwB?vx*RQRN0!JHS@!!B*?RR_no5>%ms*!B*?RR_no5>%sVoTCet4>%ms*!B*?R zR_no5>%ms*)gEg-*lIo4YJIUi)Jl`5hJvlut3B3wu+@67)q1eida%`cF!Q3;t3B3w zu+@67)q1eida%`cu+@67)q1eida(H`-OK$En;$pr+5SEEY^fiM{tbI<@TR=`LV5J> zns*(VRBd2q)h9pMsezr9K3!O)ft{fyHr%m+ovo0!y8^J?6@cxo0Bm;!V7n^-+g$;qc z3cz+(0JggVu-z4a?XCc9cLiX(D**pj?2nJ^oC3Bp2>!D34()ax0o%C)89VRbQ#&`& zZs#53?QBB3op+G8vlZCRQ^?qPhrV_;LB`HmU^_!0W9Je2+Ifd|J9p4-=N;_ShrV_;v9UOF(QaoD+U-0=Upwz0W9JUq z?Yx7$ouQDi^N2X(xdVAS?;vkyE86Y6gS?$bXt(nY@^;Pw+j$BZJMYlf&L+s%Ig55X zgV1j0Df-%Z2N^qe(2hLk9pvo{g^Zm?z;^CH-p)J7)0eXq?RMTl-p(ep+j$3hJ7jw{r*WcHW_{ouQDi^9b0^AjsQ!2YEYB(QfA* zG|l-3TbDcs?MH`V3eGVJibTbKE{z>KRV=x2lA z9+f8enycTg4_;kyy#KUTlM?VYSB~>%%o-#-vF;PT(!5E+RR)dm=e2)Nc;@iY{`M9h z3Ln>gq`&6AFN6;}VT5ln|5M=!b?*1g4_PjJ$E8F4v?eoz&;Rxw|JP&32w$|tU_bxF zn}tU`HPD|kp}O#X8^hmUzvCIwE#fKY7G+Aov9ECC6pmvFM;(NtZo*M#;W!uJI7i_) zcj0Ig;b<%2XhZ3?$+n-$CjU&^a$as(GFk5mxvP2e_DPCo?sJZ7`JCFhW0|-AGipbE z#?ndt_rY70fWMsjykFC~xA4thPxNCSdR_R&+n@0@U;R~hL%S#a$s?=l=K`bFjq{yP zJV^Mt?H>0hzfxcL%Fjpp-$xxM{NWQ11)dWN?UxTPwpVL3v?zbzMT3hx^OlC6HAMak z=Jzd*+v4KhMSYeHysN0^7VUc$^$*|UDb6dlmol#?FC2MH#QIjOIXmD6#tL>+|%@>{^iil|LOZY;O{;4 zV6}hi2N&mics8u4=Vjv_@VoC(MKUim8RUD;tRcL<#ofN?mQ|#~X?dQkt&`t3idDQo;9eV|RZdTto?iA#I z*r#8SC-$8Jf0OD#|A`luGH$j-A9ANO8B3hIUfs|CxcvsT|GayD-+8x&;-9d*FZrUr z(T@(!-?tp#+wHqr@};8&kQb7Pes_!&<3#e&kB)I$cO2*^pEphX(eIM4{{9euVzs)G zk8vXT=tqqe{jR>{Mh*4lkKIds$MqOa?npkyiP~BB_8r|w?MH@RYPx2?*5bcn?Qrr% zGBNMej{Mg{4wd`?Z5|*mBop&gIOetFW8O)gzO5@)ReQ`+$?r9Htbg?S1JoY#TJkaP zgkzpc=E1p7_}Lfis=f<;m_Y7GCg!#9A+vIw_l9uwZ=AUvXWP{J~#5@4I}qkL2SzEcv)j3deO- zGFLB}=-+BwP3>{*6|PkJwEyan-==UMYqbMxwH|D>9&EK9Y_%S2wH|D>9&EK9Y_%R7 zYohKyW33dnT91s?da%`cu+@67)q1eida%`cu+{pcy)=;*wpvfS)q1eida%`cu+@67 z)p~H8ms5MJ^3^>7yFPu!{*0Ldp7MAwWl&aViWTt z*!&1KKdSwoxMxfKnE1B@yeaRhE04@y*u?w=Hh+Q5UuypsnC{%`TtdW+9&cUA4GUA3!rozv%{ zue$PGXD5Tc?zr?1b->tL9ToR zR^EY*@*RAtya~DT9rTr(AXmPFzH%#A`4l?JcPOje1RdpBuyQDLl#ftW`3`dB9mtjM zP*ynT1XiwrzVasYmG7XV90XQ=fsXPW$|{FKu6!p`c3h^dap)-Dp{#N)Sh-cE z9xJPSB-8FV^p$^Q%3A%(cW76+Nv5q@+m_ps#!cx$+(Km1n`qr_fQpLs{h}=qS%Z&K^V#f?W9&WtH!sqr3w-`s6$4 zD~Ccy`3S7M1AXN?=u?*53c2zf^p%?+SH6S3@+?^S6gtXxD68BA9pzcDawv3^k5E?m z4szuk$d&IKPS8fF>Z_4f+ znLVWsylP*bZhQTIbzkP0!cKesmJ84D?C%|Rdumy(`7gtb=T2*ojQZ_r&Qlj%cK-tELr$y#I)Glf8$G zGM#5P-#A&aBCTifTAL+Td_ThEKYZ6K8GG!t#;4rUJDGaXRmMmD(kFTH=qrkRLeF7E zom`tsj4Av6QA3QWbDcfTGp4QWx(_nOh7p^cVT^6#2cKq)%_nzDnZ8`L@#!X~j~`rd zrZIhA(*7J{#$>Y>&NpVPF1zg_W5%%c=u3@PjqU&b*pm10o+ERZ`!t?K!`$=mOdIAt zjdyZk^!dAo@D8XkfAP13sXY8$MR+IDn7?}n??f8&cMl!P?l9(^&G2rV z@$~R6XL!dke*R8H?ecdjvWLG@k)8aVitOjz zRrSl{mtSJ-q95K3HKv~M?pi7j^@n#!jcGT$!)lB@;oVbX>>sJea5F)PZ&4V&)<=#UB+4VF#fXB{1WZ|BR<9Nyt^IVEwDMjd)eW=0hB!*@1%!!n@pc~vBSF&#*bDl%>6tfZTI$GKjvo7y}`;(xOqwL;f1%D4)3Igcc+Zc zJmk0B$IGub9p2Fn?+{r17q(xKo3`)GCg)x3@ZNyQc^5mpqhMwG|E+Oy_l!}dQ#oU; zr1IrEjd`~vyc1^nyo(*)Q80bp#SZUAn0(n9t&+2!x!v@SZ{04r@TOFscWT1>XQt14 z+2P#?;|VXcPTm@QiL3dc$TMq7;wAte>)8W0I@J^fY)ce~dSL|@B>F{?v zvcLS%F3F3%(z5*Rj{3{r?#RyB_jXQNt(}(bd(4)}p+j%8dS2NvmxOmR%m)5;N8`ZX z?qDbD{g)Lzlh0nd#q_6bwN-LP_nS?A#+AK!_uXvcZ+936V!~Y~Zkm*LNXO*Ob(3W0 z=Wn#Khn~NEazxn;rZefZp1k{Ryw|WTlaGeoV08|j&^PI{H1!>S-@|-kUh%g(%tPuw z@X#dLV*e4Q&)@Md$Iw}SwOy0ehYvS?Y`0x){bE0VyTe?iEPuPhyh47_+dCxX;alq} zyGEa(#kRuxI;L}X^Bt`o%JO$S%wc%*Gx{du-@T$(Pt!BgvTJ>?Q}Wc|LrhM);oTt9 ze_>4DVm*}I_1&SS)8X~)lh*!1YnQ)s3hx`4K5d2fkW9|s_k{PBO#XcBR!QyG7g<^U z<|(|}WIFgUybEP={-!6qBW3#hZBuy1&UEnmdFvc!%sdJ2TA4n64DVo>K7Z2_-pw*O ze!u*&fu=uX=S`Bg_d3$#%#-jgm+9lj@V=KZes8|;6w`U=*^QF^J05Fg`TMi*E?QcD zm?z=AF_ZK6J>fkwlW*UDgJhdtCt6wlE-kzRXF9Aq%Hl8d!~1Qf&)=ejckE1ub=u&u z!;M+j;hj0tXWdZ`{-SJn$Ij%e)1BWu+Vqd#r)hG=;G<2>x(@H>nLg`|`YFpgy?<^x zw&(2KEE&*ufR*KMdKhzbSl8kGKjXdjXr7czKgo3Xn;v|J{rpW2*LtMRj)Op6l-tdm2=@TdMJMHqfJMtHC_0hvpUq7_vq}(=-U2OWq;qY#y=@TcJ z50oXY?%E=qt1k@yI(K>JOH5Ae4ex6jud`x)ZjBEwvG>)rcW}q3y&l$H4{NVCdEDz^ z?e(zsdRTisti9ei_=~;XIPUeZ_Ig-*J*>SR)?N>5uQz$z>tXHnu=e_*JnWUyXAgz7 z*PA@<^|1DOSbIIJy&l$HZyfr?UT+-tdRTisti2v)+}P`3?e(zsdXvY!9@btD%U{{E z+&{AXh+KYzp6weHgO70=j=3Gx5WUU%H3C|BhU zN4XOBGs>a3lTmJkzU~TO-4(#PD}Z%Z0PC&*)?ERty8>8u1+eZ4VBHnKx+{QnR{-m- z0M=cBn7ab$a9059t^n3u0j#?MSa$`m?h0Vt6~MYHfOS^@>#hLST>-4S0$6ti@E;j} ze55=DRt|!{l%6BNM z+youvS+H^_bd--!R{0KcHJLoGnL9ToUedSrO z@+owb?@(5G3OdTOVC7KgE8jt1xe2UX1AXO9=qukrM>zzJ;jE*L z_uFThKlFf6#y7VA*5CT!SmQPOe&=`D_@h++#s$9W(mBQ_&i%!ow|WClJr^`>P*{9h zGvhA(n-sck)gqODuzF$k`z?(>`%BBBeDJNUi~6rUTwYK;mHW0UsQ!gR+85OB-&$1{ zWX~QycPhxv%8p$MvVYA>x)jteG{rViWC-)`>NwJ`OJZ?i)Vrv8o2o@h+F&(G?Z zAjh5oO?EQI&ZBle&KUb!eQ~bw1)*Q-RbFUJe~a=k4$^0QRL_fH+*Ci~sdgD>*~9qD zPW&SK<*!RWJ>IQ-+gIkhf8@iDnd}GdeM~*_jS5r!Z=2m{yy?hqe6QBe8IOK_w%_p0 zkByu4Sm0kjX`b=WJAU!ob!g}*yZ3|@ez!MQH{N#FCWUX#ZD~w@hqheX`1yTW7Uko| zwk}Bj`SIli)pPdc?Fy=Y1K+-&cBk!EU64J;^zB@bo$s8~r6Bu%{4n(+_8{Nzribca z^!L2w;98h^!ngf$F!et%ZL%@#w(wmNo+bireAzJ8GZUI zIpZLG#z*xqZmOU0RJ)9`>|y+6Cw{^H?f2QM=sQ^cg5@t*{(|K%SpI_LFIfJ9EPuiB7yO_3EBLh-GyjnlKaneb!it};;wMZTAilwhpRnR5toUj27(Zdf zPgwC2R{Vq&KVijBSn(59{51U-KVijB$%#MGCoaK?pRnSm>Bsm9D}KU?pRnR5j30@g zu;Qo5WBh~_KVijBSn(59{Dc)hO+Us@_^NXjS`9^CN<$cd;S=2x9*0qcE+&jE=vHs>;mKN0RRo9mlWY5jlmltH`aoyV#WPh)t z+t_|bzmR|S=v?y``pt&jXG}d+ujP%Yzt7Q^njdNRxO>*Ap)B@1xl@B2jGYhe+SeHS z_quR^G5vb|>9dUKujGt_^cf%3!?>w_##8Mw&a#K`m!0@U_RC+a$M9RW=DUC7%ZL2p zZUHNzi#_rv`;id*5w*<0g#?+s+?j z+;WE|g)3it%J_qeS1W8V{5fO#J8hkD#v686vnZc?V9TQZv8S(HtY?S)TNms9WN}GB z?e_0iR**fH>`-2iozG1vFUbDgN>e{#C-P4Q%(wjl{bAofXiPl|U)s@_`nPR;XD#}) z+jrvlJ}~z5T>MoHjGg^2+aw2L|DGT3V@$tFYmYFdzmhW!(r0{B596l#8Bev#ILjW! zUv}ab>}Nlf?_l{0mcL;63zolN`3si6VEGG{zhLEPuiB7c76l@)sEPuiOnZGy#YYqM* zD}LHJImS;|@e@}3gcUzw#ZOrA6IT3$=`ZmUR{Vq&KVijBSn<>JWBh~_KVijBSn(59 z{FI#dBYol$toR8le!_~Mu;M4I_-Xnve!}#N_z5e1!it};;wP;52`hfWil4CJC#?9% zde^#xweDc8J6P)u*1ChW?qIDuSnCefx`VauV68h?>kihsgSGBptvguj4%WJZweDc8 zJIVhq#7X)hf3Y63EZ=F(vUkAp9W39$@*OPS!SWp}-@)=7EZ@QM9W39$@*OPS!SWp} z-@)=7EZ<4~e=TOxuWW9v{0_PDJ6QQ0to#mEeg`YRgO%UG%I{!&w<;e`$L+t8k28ky z7i(~3EI*}OEI-2XBP>6{@*^xi!tx`$Do^i{Fb;ntPbX*5{TRF|AD?JBn(i|h zlU4cns(f7MN#=vjld#T{Hc$SOe4MkT))%bx1?#>G)_oVO`!3U8^}OIue_oKy-B#sm zm)dimf7g7CH4@gB({rn^zMP(Ch4tn1oGYv^r{`Z`eK|cB3-_W<&&$Gnsnc_`aG#vd zJdev~p2y`g&*O^na8Fy*5Bo)4^@M#SulmD%Z(i+&d*Hn63HQl)*%_X@_sRL^;f3TH*9XI|lKnoE4p(k%hCO z)3dX1R&;u%7S4+K%rm%r=FDG|hi4^u>4#@1dDRo1t>jgIc;=E zp6TRee|V;2zN25rGtc1idbUM9Vc*a*xV)Z)(XP(q*rR7>*r{h~;jEk2v$k*s&S##% z73GYB^cf%3!?>w_##8Mw&a#K`m!0@U_J?!6`HORAmgPI-@*OPS#dE3o4wmm=`3{!v zVEGQFkN6Iz@Awp!?@S(j2g`S`d@=6PH`^E@t}c^;R~JdZ2N!#!j~$CV*TO1H?MZXJ#b$3g!|;Y>lljauxP0arTt4#*E}wY@m(M(dE6T(D zWKlodPZsM5_mjo?!~JAl?S}iwyzB}0lX=-0?kDrIKip56@8~1)%-wQc&$g&X&%CH# z&%$U|&&aSx&(5$@&(y;GYF^LU@LlE^Tu~nGX^Z;d{qNF%)JWnd{u6Ku)TY>DmO2_AN&97++1gsRr&b8e?HFH zQgf_3+0`m3H7=y}|q_Pjvri}7ETyA_|u*?kma^6!+p@%_Mq+nr|L ztbxCJ`?Q4Lu7bOMd`9wPv-OSNZ+~|3{*XywG|dKj0TaznD| zqz#QfdTmrPywy6!{m!~E+2GTTMdmjpu@fDBQxc}^O{cdorq20?HZ!KJ7Wu};*wDXk z17mF4ykc37veQub+}zOg>H8}iH8o~TetmBZW5()}?bbGC48PmG z+<4X4{_l@1-;LpW8~hzI-!kHFk>M`kdq;f33FaF_e3J=ApYPuBtsI!|-ti3`nD5^4 zZ5@+`Z{hIG9hmRl@vR@2@80o^9++?T@SQ$5{C0D~w|-#0=f}5xOdh_WB01mxlRn=C zR6TqzQ1$a2LABcS5eeKi?KoyNt8!Vf3}}p<>EULaMOtwC;j)_+H@w~H7wcp*Bz|vfCsNk7Cp9$>F`|#z9oTv zi+6`5pWoisboj2G>|b~HE0dkhP0RA_M)jBP>dDSl?+j1A+c+&-zu~B4XvKC`Px$@E zgl{NdKi_WDIPi@<>_mR^;*rTYBepjE7Hw}y9y`&QJp8_7!nYf+jc+$H4)6)xuTOs3 zDQ7w>uDU5X_<|ZMyUUihC&PR9GM(^SmI>d9K!5vWRB}q?7N$Sxs9TffO;g|TeMIIP zbBu2{G7r(;@u8cNUiIBgpYJ0w$IyB5{JWAl?{zW`zv*0zSA4sXxk_2SiO9U7Uk4w0 zN3wALRG+f^MylH4dkW};--#~9I=yfo`R!Ng-|*nulS%Kiw6eX!cP{xp3;MLhwq9H1?1=KcT3_X ztZila)+677K?gtbZ3XJ&n~r?D0e!yd$Twxs!SBP4pOu4|CwyB0ef-Eb9nj~Sj(jHq zIes5~_V=cL@SWEs>%2VK^qD7o(*b?_$TuTk{QgkWUrp!KkFQPs^4JV3%Xc67o(?+9 z6TT&Z4a7aZorFC9K=@YZWj|V3zV*oWdeC9rQ5Jj9=etYj^BqUN^@9%UbmX8fj9J%w z4+4GG9rd73S-#(doORmuvFWCN_x9%`XSbPda@IB9ofd`Il%n;qyAC-FON@vTAmi@18$$*HfeYH@h7>wwm#PaNi3A?On)nGY~=wX7tXHnu=aXbdwo$J_Dboqhr-(HVeR#>_Ig-* zJ*>SR)?N?OFZOzq$GslbUJq-phqc$k+UsHM^(K#dJ*>SRmcKYxtc>MHbmT`^el+>2 zGuyxH%$D_I(ZAu04a;A!{AKc0>n>ei@r=!w{43TS-x^Y`$~TUbEAjmz-4S z0$6tiu8u1+eZ4VBHnKe`Ngek@6H+ISBqzzJpx( z2&}vV9pyXtRCyC}==qMkdtnwY?$~%xN z-=VB>D0GyMz{)$&SH6S3@+suXchFaEf?W9y`pUCl6Lgek!OEe`wwRAl zR{0KcHJLoGnL9ToUedSrO@+owb?@(5G3OdTO zVC7KgE8jt1xe2UX1AXO9=qukrM>z<9pyWeRc?Zg@+??66gtXB zD64!2x$+L=%6BNM910!fBd~H1^p)?RuY3x*@*VV*ryy6pgTC@CSost>%6E_}w}O>7 zW%my4Dcs@1tM=vPImY3?x-auw;MaL`YWWQ?c-FufwFCZoi}ASXPiwzC>qg^&AJx~M zT07GCV}DES$H$K_p4jxz+86G+*7$Gd{x zeO%-5hfRmRFZ}vJW5(pbk@p)jR&zeR$CxoZ;={X)SB>re{@9WiKY080bdNBGc?%Jk~-+YC4e5p?zzXb~q-hRXIJF(ZL@;lnp@te)at6%=D zmfv!QAH4mwT7Kgho;vulT7D}UUUA*(wft5z+#viPzZD(jHIfJY8tI36YE)0Czee@% zct@L@+70%E{3+V=QlFgc4EE<_f9QKI)2|%AjZM3uUpam&8m1n8E866tets(&rd@t3 z8pa-eD;ma5elr*j{i@-&pW)D_uKYf9l-EkmI7pxIQ9X>C>JR;@Q@f0F(Vj5=veWz$ z?f)Y_#qa!XJimPiZ`P@29lz7b9N_oi`Q1e1GaGDDcgOwL8}}<;r;guTL}!z#u66t- zDD#BhisyG3k+-~}L)~M;N1Fb_FIChXle@;`Z|>Emj^BDj|N72r*72L8aPK2ls~bEu zZTEog&Fd~7daadx=YvJHZw(%9I{Vf%sN**#(cir=r}nNhMwm{wyI-i~Hz{eiQ(T^(+p{Dco6Yr1Xw@A@{zi)$avo{=`>Kt=PjqKm} z!Kria-)h#YyV~0N zcE7H<)`wnaI%5xbp@!cXMgNqgpVr(p=UUT0x~?p@=h><6!hFjy-{L&XF%QwdzkXRw zQZ>@_!yL;o$IvOeIG;PBG@Y4)yXB6*;a)2n)=rM!_f=c`7AgJOW3`eTztf3)w>?_qp1<}UD;w5Jj^7eS z2S4)LoY>s?mnJ!W`xE`JE^_=PF*^8t>|uX1W}fidoap06eiIb^6F&R8hTj=Qj^8)A z{c+R(y!|ybSHJa?$-{c7;Wt6i$B+ExD2(4v{N)kT=``e`n%CY>+X`!^hTmgGC#;tm zev1@)i0AzFHuA<>9$d5MXOCIguwMF1Y5bJwumNt`FzdAA`RUjm zbNjuu`46A4vSG|?8FO@4*ZgKGeErxfYiF%U`xtyzhwo@NjB_pHjLpPJe2qN#t4{t3 z<5|miqC;HW=%ELUiM{;hEBeGq{7zfJU$ycVakc7|)Yn^Wn5*mY`e@T94)a^H=o2TI z4={0c*Avq^TMyl!?z=rkr}l@~%kSEvv)!$&>IRIyyPi8n?H#c8dRTisti9gkaj%E9 z*TdTDVeR#>_Iem!v)4zt?e$UL_Ig-*J*>SR)?N>5uQz$z>tXHnu=e_*JnWUyXAgz7 z*PA@<^|1DOSbIIJy&l$H57RI9`Y5-(KI+?E4{NW7wb#Si>tXHnCXahPti2wVzc^Q{ zjO9mk#hLST>-4S0$6tiuW_I7`pS3EQ4Rttzd%R%4rP@?Ay>Ym zvg9CYi(CVp5SJ`Zp=_ALmUF?%tyB;B4rP^(s9o|M^p$_9EV&gr%6BNM+(d1Wb0Jp_ zf?W9&WtH!sqr3yT@*VV*L!qO51XkXGzVaRPm0KZKzJtE<5#-8u&{v)XE1yC~`3_~3 zo1mjS3%PO--#(m3JUlzC&5%Q0OQhfr-83Am}UKL0|b4 za^*YdD^EeLdKPS8fF>Z_4f++Ecj0hga>(V{9D$tNZegA8+nj9oi`W z=u4%(=T<%4akY)|zdTavlY@J?6Bjqizj#`yziRvzuET1L^A~k1^>?h-+jX7XD1XZ2 z5`XDWya+am_DY=U({+#v*G?j%l!2NQX58Al=*Xe_Awjg&MP&>1{fV|K!>u} zKw0X<2I{0OY@n^I4gU^flC@#u>$=$Z>{VLfPhQf+e01lsHhxf>Zswz7Uv1-GyJ{U9 zpLNe^<3IU&UGq`dW^KHGVm%w5Q<|mB_`v8eKIl-E@u4hrGCtHvTZ|8Fb^ai=VNk!e z{-~O+X2Z){w)H3MpV~0|w+dhTZfe6WPgeMMyR2t6^f{rzKRrLSVPxNwu>nR08_=OF zHc*y2v4J{i3ma%FYs0_8m}G4@c9#XQhAQ!&39nnr$lm@*T>} zNAJDe&aZt}8ylaxOWXNH11ro&We26q_`v8eKIl-E@u4hrGCtHvTZ|8F9eibKL)G0? z{*HyI4FiT(`TJX!nGHSmsPaEumfEnOQI&5pIkjQ3uk>@qq&D=qA!TfU(ZL3ED2ol0 zrA}<1PTIl-+REDS?=U7=8?HELR`T1yKf5ch?&R0(F*|v`uON;GE>?k&E2j zu9L6bXMWP=iAC=41=aqGhCd`-4qN1Qd!*Wrx%J1SkN?>{d{N3TEnR4g&Zqqsnhs^Z zUSpw^rOqAJS!i|A)}Hq*w6@Nil-lsb>z)0gCsG@h{;jibIy<%D)j^&8{U4_`T)IJL z|Hj3s4X01<j}CugZqY}BTFfo_=wd&o=%a5xn^W}B z_xsH)`Uo53BW#e5ut7e;2KfjZf+p7(9hM+<)Ww&K|BA!{8DSTZL3P3)%m0LXX_cz zE$w^bdn^5&SEqg7?dM8A;?lJ5r)^Z_YrCa=|6r@C-;G1o{;Up6zof4|GFIw)R_CQ- zQu)Mj6~7yw?AT^?V0+IISU(qPs zfrL7{d|%}^SeDlL_XFGe%`Qsoyz9aC{<(+JI;)#?@b})6*7>08V09k&(=SeS!ql0q zKih7D#pUkI!HeDf4}`N>?>5G7O|JCUoZHp-!Rc-MrQ=e5r+wSs@diPT@4gK3tbWf> z7WuePcF|sy?$!(Eh2OAm>pRYE=k7j#o}2S&TVH-zJGb?D^V}ps(6 zaeQ0<{xKb#e|m;HKD3*yGuv*zT&3%^=Nz|w%SwO2QI+nlEoQqPn^gMKdsVq1GiSP1 zliK;|JGOV*_n7Jaeos5U-u)fiv{2_`;f$TNCtFW;Y_IQE>4uG%>rPsu@^}8awne4u z5ahd#59{dX_1(3D=D2aMmHQUAtnW7NIM2QLS-GE3v%cGH#XQ$^PPtD;t>-R(YrdP< zqK)6>>UG@KpMUR~hn#C=WB%I~8@ON2nB!_g{2fbuiaonH+-*DEqf^U$$>|w+X)PnC}h>b@siiyE`uM+3%G3UK6{!gUjc; zmc7dTtOecOYbEntZnbhhu|W^_M&Qf#E%(2E+TEQ|Hs2lc_cGsnR(Cgg?fI_q-ZKCB z^6u`eAa6Ue+<#Nu!#x`0)nm&&ec5M=1=g2rzpx)U_GkO@*^Hj5a0=extcFZ2C=>gjH~ zYM$%FKt-ZI=7w z(Nh1+=*`?^$IWynttj;yH|*ige`JOmbw!!K?&pmxo{V3w+%tcOIn3c~f9n_bbniSc z+m*aq=4YMT(^ZA})BW2r-(bpS?v-O_x*2`Sz1zBn>l*5;dZpaIHK&_vywM!@@y%^~ zhmF>8r)@IFwf(T-clFQPb^|x=?isFZX&XQJmi1io4Q9H^y(@g7)w-@v|5Yp*}k4R71VxBqAzH}Zg4?#<)d_#wU5 zaZ~DMyF;#M^E-RC*u9&pE}iEZjcendf3K_iaOpfZ=%Y4%;rz}v&ztwE@W*V@#rT4g z+y2h}%dhF?#+J=FU0ci7=;X>)oA3I4)z)ABdPn!% zLG#@8)$M*~+lY6o-Ht(L;(ZnVFPC+6Zy!9*?KGppPg<+mo$$syht1ix`XA8IeSF?* zH~IU}ukSj#9P=UgBD;4G^R>TZZL7Pvqbr;{+s$3So!@bzYIjNS``gXi`F)kSjO^LqkDgVs z=eq1U;h#CLwmRP`QEF$M;>45UOKD2pL%OE_v;PI z+&81z`ztD%xoys0?uP!Yz27%!>R!5gxqGWs2fv`Au{(0ua(ClJ9sC0yHFVP_Epw~A z+QAPysG)ml{8D$_7ae@veGT3G#Y^1n?{)C6ZQ01}*KUcs;fW4@pH@xWm&+HsN#VQ= z_xNs+@hR8*ntbv8Qup$c9sOmKe@*J1S>n!nxTBwc$#2Oo$1ZkPUeM7`AG17Z_QWr4 zhre|6n>^LPeY)8%Zr$Y_{EFU9UGIY$(;C zgbsf1nJbd==_}k9-8%aE1Aa?Jy}jK1ba6*NWa6*M6$dVJ6=OR3H@0cvE?l_Ooq11{ zKlZ0J-Ti}>xj|1=`E_qx)4hAza`)_ORldPq&BIxAh5K%`_8~s3?&fXVAm49Ddw<(j zYg@lu(<;BuAuZjcZcAKYK$X95atpWaTEDu17gza#)urys(8sfKm43_vC2pISm$-fQ zsq{?`Z|%NmyTmoWsnXv*u$7JThHq8+ONW=Z>I0U$lKz$clW$90>5)uy?rE?X<#G+z@i}6>Z!zYc6+Rp4!e&+PK1< zyumVe-Er-F@17Oz<>0Svk8S6-T%*D@toYS^c5*wP&39Iov#cz4`0wQ1+1&Gw=B?S> zIh%Lyyk|PcmS5J@9O;26!9$41i z-!rng8~4--_x#o!{H43B?h0W&HhsRs@78j*p0bP5b=rEX_P)VgE!_!WonAh=z3*P# z(mmbcS9faNKev|8>etfUdc+b}zE=BxYF%gJL)M1F4-fAkg}HIdnN@!G86|GlS3*p< zy2=k49qu>d&Bm=&D$mJ;t)4>8Cm7qtQ+1F zIDDDwcVX2(67XI#g)N=Put17=!zQj$rez{xxb*1mKTZx+%c>B$&{6SsA-)7#h+*LkW=}+ht zo)cZW+k2ov`Eobs z;Y#25rzAL-$XZLj09s4`+BwOdq&zrdq!g-+S-#hqU_HX764d;PZXLb0U z4J$h{oOEI{H+!4qZtyl8{3*vYb8`nS4|Ao1zk2&-?%lvsehK%_nKQ#*Z)<42d#0?~ zXYDy`|HiIIIB%>`*U`^x-N=3T`7*c1Zyo=sGfD2?MsDa|(tc&z`e)83+5IAGTje(m z-Nav(xG_zu{X^$8a(9Hi`?8rG{bTPna(z}`;@0lj(N7-H$Zfvn68G_lu-BZ{$ZZw) zu!SA`slyt%!D}sX-`98aeFrsiR|kIb4x)XlaQ*-0fdGSJ%b&+;(!(c<1Tv(MetWa~FP< z^ltQxyL^5Zf79RBbF|fY$MC$q{Z?-4@Ocnlm?hIGCU#Wlln?7#C%f4~XzFq2OBJ>R;yX|9Nxw;L>Ss*@}?M zpW4Iy)@_>0k1O|GpV-I^yJxDqeQ+CVi+53IYpbWWa4j!wl5cx@nI9hBCwcm>;dg?% zmHD$q_Hkby*(872q*A|lMvXhHrb&Lus8atzW#W!()Fj`2|5ATqH|K7Cp>h86>QX;< zsdH5Y_Wo*RcVF52pOxKf{ZHNV{CDnBvUf6n^v)!E_p-9Pi|k#;%I+WjnLB~( z9m4xCj6sk%k24WWoO9j*=%L!y6o9zWoNeksWZ&V&Jx-4M)nz2_Lz0>p6QTLSi#t)_Et4|It@o!Da+4*X5`w~Cso5apn&(3J=7uBcd zt0(JP`t*4i(xPtRA!Ue?+dzRX*@&tBO2cW1op*)ppGbLN!(pLPDso_n)4 zEE|@ddr!W;wLfBLdhT8Gjn=+yO3u!`KUbCbkMB>;s#T+=jvczBcl_U*Sg#x85+pB%82n_cy-+xO_!{^ZvZ_gatXZtHoi{m+;7aX(x(&Fy$| ziNEp1Ug7W8rn&EW;QIp*n9n*O@@`%Zfd5C{u=2-Ps zvy&svo9y}x>g3;9{o7>qS0}r@!@H&n%cmu~CsW)tyL9&Z4E-v(a`F`S#Y3I_Bd1PE z-gs!LJ9cqr|NZx$B{N1$b9FUc{0(hCO+Fs^wfkyd7eDit3CXwzrn>_#@8TJA&Jv9I z%KZ3e&bRDZ`!nM}HU|Eg@i{yHvvYp?q3Qg;bV`Tc&42ba)&jYCc3ouUf94vwXwz+N zy*xC%wSVW!bZw3f?+={yOS(315APUES&**HBQ^{%xi(#!CGUq=y?weiFCSdur(K$^ z&7Mh#A8~5BHrHOW#DBXYU7MrAn#!)tY`e&{PLaddvoiUgxt7`2Sj*h!eEW79L+)7I z+HZPm8bc;-S>hjjD2*ZK-cjO@YT_)09J6kzpYv)OLrxqY{tjqG8bgk`G2G!yNMp#} zr78qjNs7SU32kuD^?Q*>{*$7W$X0bPj+@=wp*((d!JVRuE2edoaDa? z%x|S3Z*#~R#^1gDxre(x*3V5laiafW{gz?}$FfdkgT7PQP){C?ZRKez)?;OnFP`wJ z`}*27O=tCSpE&NY7I@2bA} zs=n#+-Q3U)AG(LTd|8kE`>+3zJN|@8##wvzxNo9sd~-wV*NC4#b(2qCXgW*Zn&4h~ zX-5463;VeVw~Tjg4_|C+yK7!4@*imz8&nqV)%rQBXXqWj7-!p(&FI7E{AavRo8Mfk zjb1jLvvcA3b&G=Wl-(QU{jR^SpK-gp;ZoOslV`2nN#R+~HV|b3}QkW=bP6V zZ+2d*{2tX$8GmzTNxt);52W?4SC&7a@@C@)t|-sH{NiQCl~=dPZ+7KC;}15h$lrFz zcE&YFR1|-A9{HOW&#uEZ^lx4FPGjnscg}{!Q$qc>T-mV}9ok)I#;6(?dxj2OKL=yy zD^pH2#{PPDoiY8IbHS~~^f!O}O~#DFo+XzVGgdQa?v-O~HEwX@9h>Cey7F%}o(~&F^vB<;LGUS(bnJ$u z9$$w&lzr^;YmKS%g8RA})7Bxg`q!d^4foBetbws@aqZW}*u2#N>sjCF%j|V_G^UU9 zzuCi>zTdLnHpYy}u2ZXw8LQr1Up8N84DkhXcr`WG4sFV*IR#A7JHbt zqsO%}IrI6f=X)A6&&My^$(XXC?wr=wPYo|NIcpF(^+*RB)E116+9l3pdFj^8l5Cw> zeer{*EXgS@jeDeVqPX<&dJU4S4t(TVpSUZIXlwFMj{3}}2}G`%Z9+d*qGJT=a>nyy_6+W{o~` z?>~P*%7=Vr^(tliaC;UpBsTjn7@_Z66vRxWi|zw05fT z*V87r509R2{Mq~u-SQs48m~9>?{3c2hWN=1@b9=m1DYByANz*ebVM`b5EtEE;Tb-C zY!+;mZIx?&=FZsbMYH+s%1_UIYc^|k(?_Oa1z{2<3 z;vW_pcY5?~cU$QSPzUO zS06*)z4{);#A{5#Sb2?A7(=fy3}fpxwqeY@#ys@ZYfQ4Xg}!+8CG^p&kD>2geGg;e zH6~%Kyv8bwq1PCOvGp3;Fy>xk9(-Z#(noC2Tt%K`%@f&~)rZ5J_nPxzEqJYkutvPr zNLV{wYbUH(&$^5A;Xm4H^qJS(4s+gX&WE+&wHCq}@meEcO?lQ-T(h1v8`qa-EyuO* z6;II5#0M*j{jz6e^+-o$(GN1kCF5*cS$#OfD{J>3ImAz|_!;7AL2)(2+k*Bi%Brmp zGreMFh^1b!G{o4#=on)un~B?25AB9Mv7kLM?3D%Wm0=GpXb%m0Ye9Q!*mDcobHiR- z&|Vz&=z{j>uy+@&$?@&Jxt4GY0kR z>_NLalVFd|D%hzr4EF16L%($9p}#r{F%CK-F;+T*Y228TVIM4L9}N3rLHlFaHw)S~ z!+u)Oej4`Kg7(?4{}#0WhJCr9eL3vc1?|^iA1`Ph5BqyT`+GPW6twS$vq3@U0a)h* zbaZ~8tj-nGsq+SH=^TO$I-g*h&Mnxi^9+5_Ifp*#{6pV$E@Dh{USg~==T93$e99cw z`Ifn@b1!o^#I<_HR%K!4tr6?Pr<1 zAX{fvUrautm_VMQ*h2o2)qz7k;>kzgkf(U%DItIH%3qY1t*lPQ1Us<}4mp%p4i$1M zuiPr+TwXa>$i+OlST@(=n=~KPt!8`QT5s=~E1lTP_<|?j%5ApZn#RvORg#=?Z7bud zn_TkB^a|rUUOXb{GQX4YoU$Q_8?ce_f{DY!@11RFyvaEulC}qIXZ%d~-8TBneu_Ld z{*a=6?FIvlsi)0LXBkufrZpED)9zcHhZVvNPD9$o|kTo1d{?iTaDa#({b?KGd&q zqg{eyLshC41G`0oplcr2Z#qS@qsu26E}z-F!6+V1JmC$-i){SBRO$N`ot^MLmX56 z#5c7|+><@TL)l53l>Nj{^)bpr{yx4w>Kn&;66CRda|PpCgp{o&t4?S}uJ$evIxk)5HwMD`QEGW|ks{f+v@ zu^yY}v3}#&u5q--INE6(?Kh77lAQiZpK&mb<6|7h&6xht9&4X|(;m!t&>qY<$$t5Z zdBWVM?SEv}f#xmiK=YY(pn1+Z(ER6LtqcCU)(hpdj;K%Ti#E0Hf;=aA(9cOf)RU;5 zP=BKO!@r5z4gWonJ)vA8J6Q*^KeS_hq>oW$DHGar7ez3+5*7(61KUm`jYy6_z#xLsI_`w=KSmOt4{9uhAtnq_G zzij+q&HaqLE~9T8>(RK`d`Bm?Yw~E1ap;%LcXUF(Y`();f5EIl&P9df{r#yRO* zoKEdY<1|eCqCGhLYjGNm@zvyv2kjweoM;bLoX*H|aMU-B^(4q+{l>9fW8x-y=nywG z{?UGuvj)RH?&%*K_HmD&;joW;{11nH+%qrWu#bD@3mo=w&pd_0KJJ-caM;H^^AryI zxM!Zi;d~P6As@1HOHm&7@uGg%$BXrZeY{wI*vE_QhJCzfPuRzcc7}btXn#0^75f$C z7IUJ$ajYl7o>;$eY}Yv2V;t=?4(AZ;H;(->j{P-`<6s=e$2g9gaU4(MIL^j#{LRkj z7i0O$_QacqTOZ+YmiEjcIGm+Da|;e0iF^+Z`NBfOqzl>vljpH~N$MG?a<7OPk(>RW^aU6fMGy26i zzcM;);l)9tZ!_CS>MemGqA>C&JwJBm@@`30p_eitbmCr#1NRX3VoEEm?M2+5llVAD46<*T`=tu(_ri& z*1_0G41_tW5F26oMa+zH?v$j@U6V0;fa+lnQ2p!yYL`7g_OJ)YPWAxVpY8$0e%T&D zyXb2is7K>N{Tesg)p%l$#+kiJ^?}+>%eftf^X%a{1u?xeoOk zntaIOyK;9vyovFE!`{n%a?fVQ4_y0G?#s)!G~WENHIiFSj83E_gooc;EGn7oIaW_vq&v8!w*OB6)P^=EmReTAkcfUSs^x#Ep~w{regx z>uiynS+SGxoeS*Qd{I7i?E{PYOWr@+n0gAW2N+ZT!}p$SOuG;5cBV1*JTT)NW9*!~ z^ZCZuzxa>~jOpX}wTDPvD|yhblYXeDPW6QP>r{Vew_fcAd+KFR=vTe$4E?H?{h?px zN5&Jm`is8CfqFDP)UR=)U5zL9Xq>TA;~)A}E5Fb$#*wz@FXIa{4vag@_%Mzzo<<=)~EHDJ;u>a<7mHe?3d)Vj3Z?k z2gWhhQ^z>Mj2q(!^DqA!=D#zJFy$x@Qy=39A&>o%yjF5z5wQ#%Vid6qCUz0aVE*NQ!~A#j zj6*rf!_-GCgNd1$ej&I1(vHR<){{d&)^8l!HIDWq=tMh>X@_w{9{W|~5KkO_XTF4Z zV$6IF@x++*6yk|7^FPEBW7b88C&tW|5KoL*cOjk_GhaeHF=pL`vr17O;z?0I#1muc z3Gu|3`a?W1rri)vjIk%g6JzWQ@x&PWLp(92k0Jg`PMncG@yD3;qrQ^5U-B0m_H>6&nJ-~a zH)g(sJ>8gj9`B^022D^~0W? za;PWl>BiI__H<*~4STvV_Jlp%7(2tBZjAk5PdBDt;S44@d%g5I0~j;URS)xD^|LP2 zF6%}1#IuK$W!=es)?KDwoMB7{eT@V4Xnd$&<3_t0Pwde+v+gwhtULK7>#s15o<1Uj z=_9%@eWVVUK2kSKA88Y&kJtj!M{I=gMT||JKGIj@^pU>8^igv9D1G{}O7@Ur|mh^HDzs$9jxo{l>9f<7f|Y%11kmqy5IQU&gV&#&H~sZ@dSVNG{6{9vuwIc9XIRHDafbB`6K7cW#v#5D4`AX9 zaRMgJ5IWJ#4jiX=8 z{>(YaGk)qX=UHJ)odyJ!< z#?gM`*e}U-E~HyU?kIoBG8 zb~x9joStiqLpz*nE#`-Ibgrde$SvlCc61K*v7TI}e&g7#acD>9Y}sjXFWPS$`z5)~ zh3GR5CdXddqpdh@YM1deX8dRm9ma!kfumo{e)$XklDE<}9O8-BybbZh<_+=?PrT-N zh$mk2Kg1KSbrIr;%^UPXJYhZ5!y%s7dWJ(h3H79LGQ^XjJj9cteuyW4jiX=8e)$WZa(6@@;jpKB&D*f2+q^*@_Vlnm(|I2DbelKG z!=BE1sDs0v&OEM%!=7&Q1`d0=%^R3LYTboBy(s7INb4@_>BV}&o?fg!?CHgJ!=7HW zC+z7(JHwt{w4b{^^()G4-bQ_!&#@lkSif;>*Erf^>m}N09PKxb{W6aIHICz89LL8v zj+@mV$J02DvvC}MdDUYq-yxUpVEGP~?_l{3mhWKs4wmm=`3{!v zVEGP~?_l{3mhWKsjyAOhVZ}^XF%wqIgcUPk#Y|W+6IRTG6*FP}pP0$NikYxtCajnV zD`pzUm1cOw_)%w0IG#oMyHPtkaK?q>+0{6nX^rDq*Va)y0~^P)u`y>K>ZKm~sC5_5*wVKg z0UgfBvIzmScg33 ziN?yuk;lBU9*+5@afmIBwvmU};^e#Vzny#+VoOmTVoOm!#1<#th1lZcyAWF}AE(X` zTS7h0n>``6IK~Khh%J_n!y&df`7X-McTqo=smD0hZyejTv5oc^M>~z9{l=j#`ehvZ zYaGYHIF65T9JiEXK8`(coXv(f{>ITSX21N!8q^)jKXSZ>vG^13XX?<2_cq31e|M~Z z_mcZz#qe|MZA(FyyzQ~adAil1SBFUrIIUepi!d$FFdzZdHd`+Kq7u)l|T z()bzncSlY|TVa2<`!QJeV;Q-{�e69_ulV^&7`_jiWsl_oAJ~(SGCDFXPx><2Vk+ zaeR#9xLN&iJdNWx8^`fCj((|OUNS#vj~KxGgjuW1Pnej&Jco%T%ukpY!~BGaVa!jM zn8N&oiDAr7IL^zWocSqz<|j-&%uks5nV&H2vfg3rVSd8c$^3+|pZN*XFXm^I+jE4d zZ_g26)~)IxhN*tmx!Ps@%O2v0>?DrJ{uoEBE#&Gi`Wgr7(fClm#*KD0p4g*tCXQ(Q zL%-}fg8C(Y(MRTFn0MA+G5av{7CHMf^Al#@W`4r#=gd!-eV+LVbB?DrJe&R@`U-nFa`q9@oP>;rk`ZaE}tMSAhjWcmX;~)BE z&lISWerY{q_FkLMte-ePIXf6L|5*>n`Ir9<^WRwyFy&YeFzb$bVcMa+jGTQ{`gL%u z$2it+9NV>Vp&jNi`n1FRhNJz)v0swwtb{)Iiza8Ds~+Y*>w$Xsm;W8@v3p#Ya+HTz zU#th1b(iUv-8*LVb1>~_d}943kL@ODJ?V3EINE7)+F=}#$9@%=H6TBVGv{BM&z!5{ z{It70nEB6ofccmI4YTf8560>F-I#Spy~t??JK!j1UuAxB*H~x#A9;Z4H+gK=n0A=Q z=(Fya-*B|wn08nXQLcOiea`PDXP&Db=0EEJeg5Tt!~A#jj6*ru$+}}bAg7&7zmQvh zX$Si<^%%$cjbppU(VhhTXs0plFkZ-Mhx-SZcDR>_`ote&#wWxRW5zAS6Jz`p;)yZ- z3h^Z6F#aK)7}HLOC&u_I%$=f~`v=;>Um>2P9O?=2#F+X+JTa!-5KoM;C&UwD#v{ZN zW9;YtLH*+XA@++nBYonJG2^3p7&q0=c&c6eC3_fu*@?eoKmN+}i}-2vqpxwG9*qz6 zYusp8L z-I$me_H<*`df3yAV{9(U!=7H$4|}>X^@Kg$nEJz>ZcMvjPdCOM?jK}l*wc-%Kb*CU z=@<78=n!)xCl*Pcn5lY*U8N{Tesg z)p%l$#u+;`{@5?SWc|gw_stq}2I-19jC@E^vQunlt%F-_CN$x!W0cZ9L6AcKj~J zSB{zJ20pmEaj?OswwOI$_Q=!(q-8GV{E^Jjc%9uVUFS#|q3b z)`igYPj}U&1#%{y*R1qpWnYWp`Pv)atom z@Ywpc+c!5}_RinzZ{(h7$6_k>x-f0;R=eoo`b#=Eq*q<&iePmK?$ zIl6wAhd(qPwQ1kbukpsA&7yq5=ik>!fBUz_)Ty2@26d``^f^!0s@+@1?AM2P=&^zC z_Q=lv$KHF!TTx_f-{hQ=NRV?5Dxwk;71&)3k|l{^0tH1t1xy$KBZ88HC_!>iR3wN5 zQP@?DC?cSsWDq205Cj3q@Yc0nipfV|L)y`lkGyDrN7l)=3hd)z%GA_Vtyz1 z5dJ}buq-)YoSr1xYyT<_4EmLy2L|$xfqrM3fo;xa1Djo24BFz_XwXL2c7wJ%pBVVW z`O3go&W8p*biOs7Zw-7-dBlQx5F_eG>{u^iN_!A%+KE0u`_VVpF0}X8K7p^`H`m_` z`kU*AM*3l*e;V{p*KZB_t?SPQ{n_<%=wbgi=>P71F}N?>{UYsUIqoBOzZl$K)Pwtu z`f)$9UfiedelfUzX{X%RiTmB)es^Pn#F1_H`jxbo{RC}iA3$HScE;<~{6*{p&zkm& z8Jxc+?)Ug7`%aqpj}HsSe>`m#E$AVfZ}K_Q{lTHaRWhZEGH!ia__kB&qx)7&6CRtI zDSB+%$HGmX%o257F;DpA@3KW#zo3PuRLGeuZ}D>Or2ORf^CtCtJ}Q4w|5FVLMyz+t z2ZbWqGj2-Zh<3hxOOc57uY0+O%fYoGj`9tcU`@Uv4*5P0z9S4htDlSsL;q)!I@vY( zia6?hIa|!WcUTdJJv(z{5nsX1M+epwhW+PrKOu~E-F+Y4S*(boy)1_xC=dTo5Bx^` z@F(kqpJ@;LPdgD8+Ru1hH}m=UsZM7lcHlD0&YDr{V;Wp^**TMbW;5XoPh2pIW<4uB zs%g5YSNh(37l-pE^|xx2KUwdoM+!u==WvyR5$)VFw_rs3&+oLcu;Vb=g7U@v z&&0uyKeJ)JF!VgVwwEyUFKU04FzRia>799yhdr+?NSzCYoj>)sswx=v_pUZn80~8R z^<-hRm*wyS<>4Rdf#0Yf{$#!IGwp%@X(!@B`~7&?HcI|j*kjumvhB8wA$?-o7}8g^ zjUi)a+ZZx-wv8cUXWJMucD9Y77rT(Lvu#Y4+cqZUZ5xw%Y#WpMZ5xyI+BPcMW80`` zr){I6{kDyYu|qlA4te?ndgv?Yrw>steG7Z&bJ)pPz<$Qa#x7*+&|a3q50r<0s0V(d ze)yC1!q2n^{->RY3+-pTaF5%uMPm1Bw&P65@yCucA;%><&V(GV>^Kv09JAw0$nn#T zGa<)MJI;h0KkYaZdgEuv@zaho$#Of+B<1Zmlhk9!nWTO@&M4Mv#~DR?>^P%nryXY$ z?YHBM#1U;oImaK!b6kQRj#tpnaSZixe1kn4_h2W-L)g!85^?1CiT1J_exN-3Lp|^t z^~0a67k;Ka@IUQDTxkD2ZHq<&FYQqo?E=poJVxfD4F!rsb6d}ui}LrrDHP?uZLEy{ zO{*1-ik7S*{LIwCQR7c*Re{U{2hvB?KA0YWZ5}%lZhTC5`MIrT%=jL{pYGab20wyt zWLLyLd|-ze-g3O~(AK+5hm@(pcW&8ZzP@LUaDxT=O}^G-?wN zyN(s{O+ELUb?uP1d_}zV>^s%~AZhb~#XK-6ISTzw$@bnW*apZ`|>DYx@-!~3^Q z#r!7MHCdy~%ew_FyB*ild*qBpzIS8reb-HT#O=AGeK!^f4mJK9@XZya(G~U*3?9*7{lBu_I@cDcx$_tVLdP+rq5T zoA>V2Wz(gYa&Kjf${jkUhc&N<+?g`w9II8&oISeLtn2k!F#lX#)8>gyf)`(? zYkoPl-Sml#31-f&W9GcG)07J*1>?upHu>l6Hs7C_5e%wY%Z#{upSio3FyVuW=JkDN&3iX}8Jw+B&h)j$u8Ta9s7rSlUk+%n^R9CzQC}WdG`nd3auCbJyk@ z&5nsD&7O)`%{8s6nj0TDZa(}VtC{ttGEFiaHGT4BHRW4ZH#bZ>WTN{rn}_??Fb^+0 zV4hr?!Mt)+EiX;STcbPU959?y}>YA2z4thSz zZe4eET~oZscJuk=8}**6>zSH2Y%?8)eybn6wVru(#a6SZ{i0+a`&;c|UqxL0({sn1 z8$OJ`c;9+6by`((>8?Eb{M2G+(!_4}1(%ETHb&yz!R z>&?qe#{;!YE&ZN8(PgRG_i-H)#AoYA4t;436{u%gUGgd)E#}3UujNS3>Z0E zklO^z+%jP1mH{)j44AoPz&59f^F?P9(}BM-Z4fg22oX1ZIvPFmnWfnIj0y96?~ef1(_@k0_7aN8mqdyS#Ww zt}55AKm2%teFA6;_X&WxPXNq)0$}bF0CS%JnEM34+$R7I+&%#?_X)5Zzq3;wzrTaI zPXNq)0$}bF0CS%J7H@VAEJF==2ZhT-x`>C z*uc!s24>ziF!Q;Andc3R@d5K27|#@#-@wcl2WB2QF!RfSnRgD1F&Xn4n0e~J%wGp) zUOO=J-FfA4PhQyR!EY|qFYM|ScJ>H6JB6M7!meGyuD!y}55mqr!p?8P&Y!~0&%)0C zVyBCXF!~|mh5agsC+tVRMV!IduY&l4v0nxK0*w7C=r3UGS3y4l<9rkpp`F;TLi;gpuwAbFzv7$FKku(B(tq6j zEBt%DzZfs9gZ>`#euNC~Q!wveFz;(H?{_fA0Wil0Fvkrr#}hEe88F8mFvle@{RyU@ z!5rVfZk&vR-8d=CandW7yqX+WJw1|#ljAVTIX;6qZi6|VgE`KFIsSt=FMv5;fH{wV zIlq88?|?ZUfjLisIe%dd`1jU^D93NqT>pY=4p^?cocdVGKh6G?u5v~TKl9Z*ZGV#& z{yufG?$mXO@cmLKHo3)|nqbbQH5;SELW=>FfY5nh%fw=N%FC(OFA*8Wee_iw!> zbHKJASb9^CV|T)~uNplP%zJgM*cp7+FSw{y3+KFVLhwV%3gPkJ&JHfQd71Fs_?N+! z8Hw8oYgOk-4i!dR6euXF(bJPM}lfbZXl5bAq4tePbGTI2$}P zYjTkH;cv~dr%nV{zdbgXFnEP|@Ug=|-$Mg}H_xszpC8^C6bqjT9?QPgd~?nEpwrHV zLEgvLnSryH29@8uD!4Uuy?NxmD6p}{9vC^7hkVwaJNE3P0fEl8+T8#8wZWA3ZGt`@ ztu@!ae^-#_nHz%o$JUwkPreY)W}K%+#=8Pud-$%OHLpF;F{9zNcTLP?D3A7%(U;iw ze8xKp|J?=UQ5V@i)6Hk-KU=+b@ac-e^7}IQ@^OWu+w9&9@Ug6gqm5PC2!B$bP;?~c ztHN6r6^J(Nc|*A0HTk27^TrBSye)6k&+g5@wY6&Ij;7c>S74JrXVk{-%>ch^e_zJ_ zE^xnrS)%V;dAgRFqF262$meR3A^IXUp=atd>7q(Hp?~zO^Jeb8M7`^Zo;5l1B%rWE0p{KeF!yYLxi^62_}!WE_&plT zJqBRt$M4r*?nwZ1uL78R7{J`y0OpZ-H zh8?Q|_Q~CARs^G$pES2-yiuRZwL0k0{FI4b(%A0JUl%-k<7qQ^O&eWv{HEZlyU&;c zpFgLkuiPHwnR?bNS=v)yde#1*bjo@2K)%=Yw%$jByWhTGDwGsC|^vazs+I?h{ zp7}}!RUt|jeK=yg{`pu|6}vlqwBnkHy1CA+Hhh;p$~XT#owBf?nq4|Wl&|F^U3|wS zYFVue(U2pP@ErA5=e7A~xBYouUSf~g|8`y;eTcntCoU_j-m91)>O5<1)jF;7sMJmA zqe|n(Rc-ZiR#ni(Wk;_zRX^C9UR^#VUG&rJg;n}bITh4ie9>$gFl=s_QHO(mr7oC< zqQUd7|9p4wdY5x%)1|rMg>T*xtlodd{QTs-@i%YU5bSv4w0UU#$oLlvR|j2to-%{l zeiOgqrj^0>yHA?OE1Zp=Y_TG!^U+CjbWSe(?w0I_=%4J9;Q!Wf^1pqK^J6;2?o~!i z*WYln?se}v;e)D;*7l5hl+Vols-E)bKH*#KeEL|m6T)A{$Le?Oa|UGYwexRtyLTFV zt(})2vwJMTqCt9h=Ic;_H{ zeNpd!)BaVq3%>PZ>hr%lzC4!`w(-19FwgM>bB_2u&uimf%%>WxI&J0@n61I@Uwgqs z>1GI@Et@`?d3>_Y|8izkWBOUs@}4Qe%_dwlUzB)Xx4HRbP`&kOb1d(8;e%VxnTaFE z=<62m2|7Q1#uPpa>VOmU_#m}d=xA&)bNX(#SG)`d9^%yEGF|4(NY`+C6Ki~egpemTDtGSjLU zGUV;Of$>Ma{rN|}_h~Uoeyf&i+y8uv`Sj8C=9Mf>)b7-Jrg6V5rt~ij)rvN?&8o(` zO`Xj3RIZ~pn>&XeG>7lLS^a!knO;qgn(le4sJ!)tyVP9UIZL#(^O>Oh@a(2!)*R84J2wS=dLGtYYvhiqUHMsX_?dNj z-oZT44Pz5$yZh~>ezcw6A2qLVnvIxH<} zoqkFDo$lj;4@_G0Q@LN_D;JLs9{MgVx_3~1-Rg_+L3YbiD_y0}wHX(zj;BS9Kd7dw zd^S4RHzX|@KK@R<|J3lHPm8o@)9UuR$W23nUy9goozi#JJ%{uUj!#OB$_?$W>x}Il zV#zmByZcYb5__iPxws;()td8=uARYUXWwp+}yq8m(&RkxaL9qOCb#n+gZzGz~+ z`$G0?xckd|RrCX$`uaALeQpCYHlNXVmDp?webLA~cVe+_^3q0=?Q~;PWY0={*Rb_w z&$(O8bDyl&t*%&W_6%)e%BmJ-Kl4ruV-()4;e8qy?+=sjrZTKI%RhZt%AfgVttr;O zg>c`S*O*fkLgCAPTxr_Bk`nmu3ICn%2KjCc@6c#JneQ!8Uj6E?OveuCWo}BDy3~v+ zcv0lvJHE`EI(kaD+M(~v)bU4zm%qHqJkfHG@PmWbn4B+e6kb|vojGyma^Ye**PEwr z|19wL5uq;bF9P$uCHQ|kPn>bI`}6ca@_rKU82xvTn8*LyzoDaVy>Akw57UR}&t&+M z@;>8RJmgkIZU_7>2}W)Qi zUHPARTwUyJe@Mm-%-De$J1}DhX6(R>9hk8LGj?Fc4$Rnr89Ojz2WITRjGb4GXM4)y znV))uoql0guduTR;}z``cJ>Rqb_u)o3OhdtJO2o~J}>&+y&&xF5n*@l2)lbq?B~6P z`weZheKVOW28H-_##2&ySrGll#E^{nGet{r9vd9QJU%A?m zHYRgo`1{6p6y5r@`PI7Xv?9^zC#S>qzxs}k-}jZeuC$)8rAYMZxJc++ETyyVBzSxrl<9(YZq2IUbT2MrrA3EQk@;K(q~IX12Y-@&9^~N zbZ@C>O8$3r!(R6WooA**>6Q%9dlq&I4!2E>>Wq6$=c?Qz*t0b?I&z?$Zu54Zpir^2 z=tSPT^ylmQ2kmO7MQ1DDtmljx7>u*){ntlct>-Tt805G=Et=f9pf1~IK=4xIwCIgN z=i~KH_YD?blNL2;yEgu)>J{`plN!BydU`xx&+b8MlN!zL*)RTK$!CLn_ohY#--^X^ z9B35`+LRJqVf4JZU25Ck%Tl8KmHSpXu&HoR=+I@+%pX!?RqtOBE4!d%w6;>e*x&Q{ z3%M$p+D+0$?RsT1x6LbM&OMSP+F$*&K073b*;zJc^vTpc`s>4ob%A^HMExso)J5yu zYM%J$2l=k>`trBhJ%pRh#cki{XLmF<`7drZ3rcO$jqhn}E)3mjHa@#wr@q?Ad~CLx zS6=%?@42U;X=T5KoNytXslU9wS^el<^WwLeO_BBW%op;kiV;0vqZ0;(b z%bb0$rdjpFQImIeZd2&x>gHsZ6Q<6Uc}&9$%Je&b${c+&w|Tx^6?44RIddSRm7j5= zxvKvKQ?^SELp$*e&MSG#nmJL%=&oIJf&*8VH}@9E5EX3qMX;?yCHpN{y6CHH%Yynt ztC-xS&Y267R|RdJ49x>WPMW)~To+_*SHs-i^q9%qa$WG{pxUNc=by~jbE|{VVLfyI zl!NByjNb(%p0LjhIrrIT*~P(8``+Puy~~^$9R=;0H!^Kgc9{GdW(Ch)-q<`^cAMF; zXi^Z)Zfs_c+G3iG9UZ)t+kOY~(q>cfo!5huDz};`JAW{jfADIu-=Yr}DRE3M%abSC z+b9;C7@XS-9GN4k`)#M7;yoqIv<6wDrS}a_%A=pZ*!`$Jd`+GxXaA`||I2fkp<8oA zogY~ooLp}AsoHPfHh;Y*_)sa=oWWZpk{-mJg9h&nL8x+!|y33Fe* zva05ZTIT-nh?(>F_3HKQ^~|1W2h4kS#MI~-4Nb{myG-j(ZdM~VG&axV+F~ldR!3ET zrHOgE+3Z|j*jr4Kt&Pp#pEjF?bL*JRH5-{X z@7Q5lFRf`-)@@)G_uXR}7p`v7X4EkEXFg^|@44P|YJa2Yy7+=w)wYc3IOq!V@i&>G z5*tgHlzIissxjH41p^A2n$u6}BeQcyoo45>>z3ZZpZf=T$)15f!u|n2UdWTc*nzoU z0?d6BVD7H~bKeD+`!T@Wrvc{v4KVk0fVtlT%zYqW?hgTT-w2rdNx+8K z>dW|ge3{=e_WJXSUzh)_>u>q)*w^z%nWy}D)^D%>4eTHNn`OU^WPB&r;U*`Ax zjO0K2`S$-&zFGF||1Hn1{xh)O#_`@a`@iLTd|!`0zWL*xuhWfbp_hjwocotNB%zo4 zBJ^@!gv@m2EULFtSm2E zULFs{JRbJFukyYbS9sn=d+qo8%FBzQyu2vN%ZsACyeP`ci=w=|D9X!=qP)B)YS~}% zq9`vfit_TJC@(Kc$h;^v=Rn9@E;gS-=;eM1z1%M$bHCU*D`c)1KNrxS`F|35NPf@x zfBup9y5|Au5AI%0-go{zi2i_k*5xM&z5FC0@{^$d+dL%y<6d_2qx3!ZJP>+$NJ1|U zN$BMv36Y1yw+;IJcCkPEHoNgBL>>}1riEUPkg+PHO?DurS_`ceHXD96PmI%ANCBiOmiLlFCBJA>(B+Ko0e@S`!J)p45 zTO#c8mI$L>`(2?h?6Kc13cI`|!Y*%#Fxq9mTVy%%LQo$0E`(iP2w~)%pnjL{Ldspf z3t^Y_jZUE_a78 zW9Q0ah@F#753vr{`0>3c|U}0o&w|p z5w`gY5(%6ljSzAf-vN5 zUIk(3!P#fjk2BH0sMqFI5QaTCLk;Dy6KAo3VZY6vAdG&9v)Ej@oWW-{mb4d6cugkf$G@2WPRNUg*bJY+%%jv)E`4&SC>2 zPXzssJP|hEg_NURxVIsLdl2_F822XbZ7}Xx+}mK>%ec3}_>2DsJ@hO2s=B4o&CbDT`Z4VJ18Hw_6b`(+SVs*^=n(7F#h8I zVFUgha?Va|>k~Vn&(hv<>C(4SWiAZ4_o3z4EvxFHB#doIV7*dNr6n2fH>(xwBuG zv4aeJ2|JuT`Xu$BPYT1As1GvsFZ!e~+Ku{94qu`^Fno#n!0eM=dCZd+c6tJoJN?40 zUSV60+#`^I|4<*;*)QzJi;Vt288EK}Qzw{pfoTJnwt-z6rN6m03bT!nVcR|VxTi;h z=|eDm3wHL1jI&diF@g+Z2ZoOkJ1~5Y*f~9a$omd?vS2^v1KEnJ5#yo}j1`K`B3r0O&yX34xPd)~A zdW4;RVOMXE(33dp5R7{0e`mkQ*ndObD(R14JR74wg7IvO{s_kU2x9~o>l%z5U_2Y! z`#>1a#u#f*j%Q=nkCAsv#z>UgJq;L3LW9q@PG4nD*e= zn0DgXnD%2G>imd2V={ig1}6`HAz8gzHmxt4llymI=5UA@B29${yvu(My-wTtCkU!h%iPL*=!A7SS=Vdqa_ z=VxI&7oa}0(ZxlW@j@K`9y5-Rae5@D9OH;`SFilmz&Iv!CgKQo_KOVTh;qge%s4uE zi6fYC1T&6c#u3aof?Zt1PR0@Cj3bzF^yK9pbb2HY9^(iZ#xbEMv8Dnuj$plx#%a}1vE_#Eig8xlLW-VjE-_&jOL zu|AY?E06V|FrKHV$Lh!WP|ETA#phW2?^qv7zp~e1eJE`8VSR{ol(i?hK192?ZbZAd zoD*<>i@FUY<$i<(X7oo=Jr~lWdEZvr*w&cpD2jgVoD9sl1$%%F8*akaLpq z_}18c$F00Plgi68sk}Us@>?)%K)vppZYgJfz;DN7_?+@S^ZR%F*6cHM`oHy)aV`5c z_6Cqy{#`tatP@dQa6?v=XKBMY__{JV)yp%M2tV<9J~ex00qiN#U+la@6@Nc;Pz63;Gx@)Wdk$@)*mle2nr|Pe46Ze?a~AZ@_x(zX!C(UKh|#t1qDa zww}Oi7s{o*PF~pQ5&t;-!meInXOFP6Q`p%r?Apb0w3qVmgRt|Du=ATR+K2k!f3zF* zf#DC-=fy?X_CtBDLb>gShV8Ze(9jRI9~%0{_CrIz*?wr~PumX-{cQW8L4D9^`=Mc6 zY(KPm68D$whsko=50mn?A13wKewfs6`(d(P+YgiW*nXI_)Aqxp{dU|)w#$`Ed!4+n z(oiTUI0zhb`g z$9BXH`?W9*yZqI{|BB}gSC{eX68=}@%64rO{m!4l|B9T|*hA&#fw8R6M%>?+*TA^% zF@Az^e_~t(-Xq;|<1bFvbOp=U|K%80Wzlw=n**9PX34ggx{#?4|%$<}kc3a-0p69R0 zpVYs4QGt;4epH}PNPCWCEgaI$(&Gw;wBP0&mUFSuMwGAl{wMj?81l83OcsV7>uX`? zpU`ENk;@UMOeIdB`*8JoMmfbjU+LbIzk)oTZL(*uz}$uoGvmqa60* zOm;BZg|phhXfMm*2g<`g)C0d!zx~!YSugxdd*FZCiMYUi`+SA`$#Q>-oEX?{vQRk7P<<~Orf01?6LiU)E_~YNoNsD#&R-s-3)|S7^Al~( z`RngaAHHXE&X=+|=hu9fK0F(}r!Ra_P|YlzA86cyRGWHKpUQxucjU z9QYUapHa0QzBgW@@`fPCo2ONcl_TS~e7QOp*YlJr(DIvj7n=kB(C(9J`ITqmrCY8D zZu{t@x?^T8jpuXPM#kI$&R8!~xTN1l!jm4z5WMIR@eZ`Oi zO~JNP^L7Zs=4$tpL7p^)w(P&6p0GXFAUwRQi7?te;;tIP@JYjM#qo|Bd7d#x#Cj(3 zy{mRM-}{I}zIO$k7ZUm2)yH!WRPFhTILZNaVMd=Y;LeCBMBqCmhTu`R(O7 z;hPSU-(H>*Mud{zUg0?b&oQtcu`Zg(Z?Ev2fE@BD$8!SP$o%#;2eksbJo6%hYf&!O zTAg6%L|tIi1slM4W`J#AJTt&%FrFFE7BHR}aPNTeEW~omxs=CTOg)&RsULGU>&2Xo zHbM{PdfJI+0NRgd1GEt`h~ux@Yjb_8=H=#yA8ZbA^QFz&vV(cHV5ySvgyO|HlIBBy=yP1DK^hM*yf*CZ`=IypTCq@-9F)>dfw)i2UnYZ zR^_)j=Lc6m8Eo5nPGzvU<-tMg)2eaa@%oOh_5>XsKch14AE-l{XTHgZQ)xVc=f5R`xc?)uhEB%)*ZQdkb8k$M5ryVgCoiSJ02&xNSc(mig_W&yZnGY+;ux+h>vY%9Uf3 zOCDgWAM#`=$NCQY;!uv?|FAC(jNc)#FAj{~3$ZT_jNdJ>FAj{~GqEoYjNdu2FAj{~ zKd~hsE_y-q%ca;Hbw=@)kO1_?ch{m)=$ zr<9`}#s&4@99YPpy|#Y}!w)z&*6Bfi7KYz!KNN;PZ9f!7ylg)dM!al46h=L^9}2sE zku10UFez{Qp)mB=ekct6wjTf6jQ;Z?i$so=RdJ|LDk!ieeq{%o3Y_;H7ZLz^=!F%CQr95>MeT?$Ya0U zV)nIPuZGz3LEL#CAmNEE zoGf~|d8t*#@TpljRFmf_m4GMB?P7Nm>su&;kQLmuUgQ?-xv!mxd z-{6^``THs1gDbA6n)guC;LvBK!tRfx#F|`pd2myw%fc6L9Tsc4{ioQ*uw;bFeXcNnnS#dUq!m5zzdi3G+;6|f2eS{jXBd0`+=l#;_I{P; z4O22>eKWK1dbKJ~6EpM9dS>h0TU4iljm-Y3b2==bY#`EQkX_J{J$ z{!rf8AIdxXLwRR^DDUhKg|k1bUCDP-K65={?fhJBH2Gjh2JSD^;SmcT)k|9}5+2m6 zwjMQnp|Gt#S-z#*-ZPz}&W`5A8127% z_h6aF(MGh3et>Un4t<=nAZrM)J%2&*>XAmUY<;vyk4<{dkJx-6X(=Y7m6?XOnkauFQ3u>&)9V8#y2*nt^4Fk=U1 z?7)m2n6U#hc3{R1%-De$J1}DhX6(R>omY-`#gs>XrXFF&4&{s;n6U#hc3{R1%-De$ zJ1}DhX6(R>9hk8LGj?Fc4$Rnr89VeP+y_`QfpMkn4z!TS#P6VA$j4DK`DclgWu z4*$;k4%hJv9q8lPI;e;D9nR`tInMB)ywww<9;-h_{q}E+_1b?AXpg-vpq*AKml zh}SNZOTTsU(x06kVW(f%)hq1mk^9BjDeUYQcI{$0+Dm!(LD>06*!hk1!k@xuH|m3* z;Sbd3#YOCAybwp9;Y+j~ov@1?n6U#hc3!#Mckm^ABG)GRfG}f+a#ydEJ9`3@Gj?Fc z4$RoOa*3Ujm)L=we?*V-8|#(WL58stcCiDyxQP9X7wfdK#XJFDqF-SCfG>q zOSvB}vW+d&)9!Y+1T#tzKbdF8l2&@PFcup0}(j2)P< z13P;HuvR=fF_8=Ct6S1THh@ICi&Gtf`et;hO2m0wZ)JuQD9{L$}(*KAZ z&)9V8#y2 z*nt^4Fk|P+C3a3;Vh3jIz>FQ3u>&)9!Y+1T#tzKbu^h3ZJYpy8Vh3jIz>FQ3u>&)9 zV8#yY$IJE?yxUTVcW=VRW0Wf=gK}ZK!-o!(;~hTUg@f@9AMeP)c!%$PQ$fxRgLmpE z$2)wyYX{>UKHkBD@eUvF=D~P}k9YQ9{Kt3sc!$q&yu+tF-r-XZ-r-X}-r=)eyu+tG zc!y6r@eZH%<2M(!%a!9d9^}w~JbueT4io4RcKQ>Xs5gL&vq#w3DeUYQcI^^&?G<)@ z5O)3%c779f{*-#1pM{RW(Qo)mf8yWiXIw}BLm%S; z|1n;+9KSVcv=#oNJp4yJRzH4g6dC&$zct1oZ~q;?H45A7@LQv>)ra32rN7yFWE}x{ zS1#>!^5O@lN7(5XcJ+!sojt366P=j?ai(%xp6O9$n)AL2JaX|L^vihi*DP|-iOAIfi=kjHP(s1I!Wq5LKZw*63k z+XUNws2CUf|5i`pw=&xgljXJ_Cgp8EOzN@yFsa}6!(_d-A13Xw{V-{#?T1PGnM(&Y zxN?b?lNUcYJ;F}Eu&Y=6>Fg19b_zTDg~iVAPUmN_!TDd< z#Rc};Z+gF1MOtLXSS7!4kQYuX7%r%OUZXtEb(e&n-SDGu)yBob7iO#zUT~m9Xl{*! zXZ> zr{EUNONNamwt}7N;@V>2`_FC={xIdZy0paA7{gVQ@`qLLVmAs8Znsx`e>N1(aB-{p zxO;8ksaI@J4Z9}xTVRgB+<|K?8?u!#l(E+uUTbw4>a=wk)@5xlw87dI(Kc&yM4N3} zBDTf0F=88S+atE!`Xr)Htgj;a%K9*(53O$_`quh9qR(wCBF4hTC}NCo9zA1cV`|8D z?~Q5KVWar`?2s#rlao zM-S#%Yx=Y*D&@Eqzo9_h#?~M|B>2L|Uzv(;WEFnId~G^Cl3BP+k8jPvZRv&AA6{uL zR5&Bo?%2M@tZZ{wxLMuxrr^A7!eg_4ZwiiDDSWo%M)TxLp9|Z%B(E~+vNp)K>R>CQ zC}Xcxyw>Ve)M@KdtjpSn$YvOZMw zq4lkzZ>|63cN5r*eQS&he!FBpx3LQuI~!BQm_mm4i|qp;`+)5mA^V2yGa>to?Mos1 zlI>$5`z%L-uXk=R@{+doRd07ibI0d5=Jz_YU;% zo`QbfYp9p^Anf722|Ibu!hYV%XczBsv^RA3KK#Hj0siDT1HW+$fj>F6!2gs1a~!kd zmEw41$1%lm%#Lpg|4><-@0K~7aIv6y_GDF6wngS}^qU3E)+2$+l9D-Wb#+1W(Y#Q# z`!-WpV0i(Psdjbsb^Ajw3{JCbx-+is_n2sX3(07>WPY5RnsR6 zo3?GPRX+{2dy4KUV&3|;j2hf(i%P9`iAgDZH~^ngsV4jU{Xwhex2TTOQ_Y+{yMt^C zx2Vn~(#+Oj+k;z!t!n0LX{K7HEkVC6Th+yFX=d0@8-uSVZBu=(D{VGDxgpr|#&)&k z>C&d_h;_m0!8=s?iKWe|E^C9i@9k7CEhufq7Fip_KHsG}e4XIv_H)9udt?=#zqYlc zDSX)?z4u_gutm$EJUcbSnSkybz!2vM+h-P>HT*x$?Q&;+h2A;Ep?6Mkh;xeF8DTbd zE3`XLFx=BEvvKDRhd6iGoktwvJmRMwNC}!NncGLxW4kd(`e8Gk*92L|;XNDG@UzeKlscwq2jv$U}Cu=0B0ef@(h)zZQOg=*`gx%vbh3#5f9 zxti&D@4ps2w;?s$eaWNxjziA{3!hI7$G7UPr>1*2D11I8eB!l%y2v~AgK{-f!ogX_ z=v(Go85C|&DqQ%;6n$yu{jpUAE(>ot7T3+z6p3A*qeNJ?>vuZpJv;v37e&J(^Y`k% z=W}<)V(6W38+zy4hB)8WosAfJXZVKR8NQ)+hOhF@@KxR!zREkpS9xdnD(?(m^~qn( z@KxR!zREkpS9xdnD(?(m<(=WHaE7lt2T;!9A>)i5cP60i+sSj2m3MBk+W41qla+UF zvhvPNR^GYE$~!k%dFLi8@7!eNotvz@bCZ>KZnDC;$?iaYbDHio3z!UJvxg7a^La-Ny~14ob*3=K<`U+Sr*1SmKfj=AcPL{r z&Z%Jvr#q(RAH1ID|0h~KuRdvgiy61OiAlY%T1{&x zzqJ~yHGcgLs(#ldrc3$tYO+0#c;ni}rf>c&>RNkF@!qhZ**<2MYHH6f{&q_}vwhY9 zHO!uC+~9aE)2;duHPxPX?9M?}I0yNIrsYhzRvE(jYqP4-3rd+e?X!gQ!b8Ef0eQ`v z6>@~lZ&)4-O?O(C7@a%Z)^J8pDQ%lx)Y5)0`Rv;PzVG{Q{O%I%;&-w*2bOL8HS_yZ zl=Hh(Fuzv?^E*~Bzi$QeyH_y3hXwOHSunq!1@pUFFu%72^E+HHzt08ZJJVk2duuSi z=LPdSUogM_1^eyg_otNS8Mypj73KVn70mBj!TjzO%7Sj4^8f9OKmR%5*Jtzj&kQ^}(wz$|XZi7Y z;MdO^z8?SFI)Co-ul+6areE)GIdhQn6wdhLxolwH26r~`?|%OEefZyW-k%>AKVD=! zWBBLj`E$B2^Lu^{VH?qw-}5bL?~4>)Y#@J<|@D_w4iA=o$@8$zi)pYx`U`azkVD zOs*}avVGpG{z?<`bh-6rntcxR?QH+^E#}il*PB=DH!r(W>zT&=wwTiPTbLDXYMWJ! zcbhty>#1BvZ#H)hKWGl$eY5)cv@*S#9yQ(bR&mdo^4$Sh?8LhU+V2?uPW$C~(*I7! zm-%O&SDmjEeD%+K`{S?C{O^GNZ#@tDZU1M!E%NR3*U|oWL%#j~y4(M5#lQCdg*CYE zpFh82%KJaQWAgh6pSAGb#{a%)W!(m5ao;_%KJ{h(nKiHfUDZGH{ggMJU<}1rgfZbC zUQ_$+{Vm^Bd1Lio)$7~iSpMDl&|r=4>N5Ct%$GUWt%+%N>3Z|j*jr4Kt&Pp#pEjF? zbL*JRH5-{X@7Q5lFRjVCY75Ex0<$BH8hWIyTvRky1~>~b*tIdp}uKde2sbO zizf7g)SEV=hPglUF*AD4^`=w%8%@{67tE@*WlYCGSD25#$rP2?Si+>#D_~ZQ$sR4R z?=EUiKdFz*&K-4{ozt8uzDPg$W4>s?tI570_PaPn_&%;hm7jF(4Y{HgR}?gNSIli* zKAbHYZohZSu)LIct7)caYVOO;I~6OK=(Y={MC0=2Ncq5YDtgR}c%tfG>34lH!aGAZ zc18FW(yz;nV-emZx_dmrx0e33r>aO9uuy?oW#*cP^;Q_8Abo)Hp4AW6=3{ z{nLGe#n+@oP1>%FKdO2Kz0agZ@1C9>&)2hi(AuO%vwQZ7e^~O_Am6>IQNg!j@f-(Q z1%o!FL{}I+uWpyxLFtr~Xn*CtRSs+_927cqSv2#9)L7N~SH#LLC>gD-)Q{h3ihl|O zMT2cAmqjluem6Gj^aH_^5-HJ@OZHTKFl)D9divDprT)$4-h0`gpvtDy=-~zx;&<*I z9z1I8pFd-CyxZE*LDOMrQS0iwsN2Yp(kMVnT)*F|m`68usmEt-|S ztL{0Ze{g(KYE*7$e_dy6_aJ}K)M)bH5&HRd4+XtyrbHD}KhV)rHwQllrJ_tdKGnlJ z2CUcqdq8{abph?P`U2W->j}Je zp*)6qoqPaxdW4;RVOOuPvq#w3DGYt6&$X*G>T~Tvdnpe;2s{4>JHH8|eW=gb13wGH zAE*!I@DuH4yec-jQWdKHmF$_`QKO7%xBY90Bg*rrh5F9fedFK`4dQyq=&Tw%@1v=@ zQ1!aP!!{4scmB{-7=Q8q37vH{O=1KMM+3uvd+7tnrNkL=e%U9LO^cJcw(=@EANgh2am>hjObAaS{9fR_qYR7RwgvW(Nnv!Ij>duj?(& zp}{3*f27-OZy?;V!)QIP-K)a*i~mpbfd(3KU|fgm!O#c2V6+i^#g)fcZsh~Y+j;`( zvHAn*w|@iHYyUl`<30kAaw*2k zc5Eq)`dquvUdqD{!mt^^;>J*xj3Pu)Ak9 z7-Jajd9b_3h26a`?8XFPjA6JQ@)*OQ7tAr!mCKk3c4HCs$e4+8H+D%m$4r!S%miah zLVaM2Rj3clG1DuT_B#0hC-P}PvGRKLG zo8!Q44iXv8aVWzV&1?-*ys7Ibv zQ0|@?q@2$xDCe^Z7|#Nz4~%C7)CcCXidP=<jK(o z^#!!w)+1{H)aA-!U?(r^^awls0c2dg!pGjjO%bcWEd|n zXCS%-1$w)884JGUUIFA7Z`p*ePG7RE01~d!i*Qn885J_HvltUa&4kt zNjc+%a>fhn+AA{757dMHEbROy%y{8i=V#g}@k06EiWg$a*!`LrM=$Piu+uNhIHH_! zOz8RZzJnhaM=;~)`RAX$@Azzq_;M`(cF&?3?4D7D-LtDO*8-5?S^(^xffF)+zV8Y= z{|Gz333Dyr`B}=j7C<@I0$|>2VBTNgKgY>Z;;Bh1B|M>8N&Wcc z9fe=mRz$CODZw3eKK;gZPfL0JOLOX4@eY-GCV57iK1rEv-TDjT+K(T4T^Kt1{Pcz}>Nx?9F9~O;TvxxJ zu~VYFQ4Rgeg~x@nRtt2tBaa9-t9pYzo4JkfE1j;@*&ca7cxU;`^}Q8ZCiuPL`nrxS z5?rESvb^5997%cmo7G?R6h9TG{)y)g##wKlvOD6mXX3$)aoSn$rFC)IfBgKKIPPDx zMauK_7l!?v7jj44Rdf#0bAg!L!ug`a5;{7*Y2F3$dcB&LY_T|*n_+dp_!gO5CZ zi|*6lWsN?t>A|`>SJv00yyTv`dce@O1oTi>*>lgLbethS!{SyzpIvh>oM^{Sz- zN%@|vwe-~cUljS=Z`IJn7j%^JyJ9tTw5yBA-||E?U8GAl;iF-w8|LaNGS6REO}D=D z8M$`zD>1#Rc6*Vj@^PTc6@F28V9Ba_P{l4Hv*h_odhzXT<=Wm+W&KQ#$E3XT&)4WY z-`R7|Y+GtHyG~Ee&`z#>d`u;Mvei=}^Wj5R>2%W`5N`2fX+8Oa`$fLd%UA0rE82?u z$};8kqCSsH`PVhd==zJ>i2MVw%k)j@6Y_h?m)4~>wHEnRw_c?``L=`bu>n`;cYkaz z*EYUbQctPbTCS~dq@d3B#{D95Z^1NuW9dX2_r70JU-5Q3k-5Ej&ZPabCKS@2e3`iR z;>wK4_P+3KuB4rtKPapVR^*2r{xN>Maw2xq_2xMG8~Wa^C%%uPA430@ zA5O-Xd5_9{JuZ#=hN?qAryVfFSn`YNuy5I-76ze4%IOxxp` zpGnB$+WZgnP1d#aa6gf`?bU6f2iKl!b2yGZENz^9DBkd!9!WigFHcSkK&dzN^Ih>*<_s2j)Kx!2KPex7%i;LT zCEk+ql*^CCAN+WLT)Q*v$GCa-O_4zy@5wb%%5Pe6JiaCxD)J>OoQ(I#^@hkG?k#(a z5=K9%{KROHM;xE(FkIw+9Cjg|&7SYaxUXL@Lga7BkVD^ec#M>zpL{iJq{t(VnNBC_ zLfi|Nd`o0Xy_HixaV$~SqYo6+U)3BZ^5`dXSG^@VciM69>G6s3*M82e&zu`B*KR9O zNcSx}Mr3f`;ab=O`GYTy5j~GpDXhC?9w{=oPm6s%Rv7p7kP2f(9`_yeAYQok#l{K$ z;6CjW=f%G|6GJJ|npzseeZMqkA^iCCk2+D@ezuZs3t~;9OR~RP|chtKwT@}rEVO(9bcaZ3RreXvA{ek|XALDS%%CCz&#!2)CT#Iq_ z#2X2nd$ZKlLpt@Ba*Vy1Qw9p(u&lby|5ZO-wnbj~JrQ#vm~%atb3K@Iy_CDT9?ZEO z%())SxgN~9Uf9M9bG@*e>%pAs!JO;Cm~%1LgE`lOIoC_Mo9n@x>%pAsljU})%pAs z{b#vfGvoN@Gu!X;naz)5GQRd18~o>eH&XoYd%f?Tty@TOtvYp2LB+MwzO@Au*HAOU z{EBNU$n#wRnC}X}d{+SGy8nW6T zy#sl!O;FDD4&=Gc0&_hD8LoG5E!QcK;W`VChU*<%%QY96Yb)x(dI#5XJ;Hji-hn*VU%VD; zE68xYgKN1qVO>~rp`2?Flyg0WYq{Qm4A&hf=XwY7Tth*I>k%;59gydG2l8B7p&W6? zdI$1ckD#3E9msQ?1?GARGFmA5&-GOqhcOcI-6lAy_ z0dw5}d9HULk882ELOItvkmuS2W?sJX-tj?fXi3qttNi%j?V*K*)89WX2232rxNKrrj^|Bt;lkGpfa z{=XG5#t=d&ibm8-43Yb~4iaLHqC&+`D(0yX5@QW9#SkJP#)J|xRbz9XZR}u-n$=uG zi<(GxNyZ-4h6edV2%b?vqGT6?(GKD(Ee&gAXJ)`Q+?Jv(5| zW9oIEY4vf*Cl9J;7__*4eq>R<) z5$qhnWsV#ZV$ekD1d4Zi5*m;4S7ub1$ofo*wi)|5S+k$Niwk_DUVB3Oi3$`uT zwy^u?F4xv?&ik_tcx3-;>S?{+6n}WeRrLc0%vm8He$eIhietYep5xPt>v7wzEdF7A zVg0kc)(|hW$)x&_5$lM5KIokKnN0_ZPup@r-Q)eW#3M(ItFIi@SA0|Fwe__A@Aaeo z;3D--?-WV>U(e}u?nA?uzi5- z18g5)`vBVq*gnAa0k#it=3D|Wt+J72K#1v_7`^94I!u=52wUvL={ z$Ewh2#WV6%w4=CvnX&r(m~oDf+b--J!Ojuv9Kp^J>>R;mjvN!oi}C#Lnn%RewiN%E zv+%!q4A93|duuq>NpY;7;#gP3vEGVf9Tvy>ERJ4tMUAVOC z@qiB=53t7r?C}75Jis0gu*U=J@c?@~z#b298QU`c&I>y3JM6y0?mO(h!|prmzQgW2 zT=v~@M(!~Qd#u9tnYfkgxFL7kV8;!1++fEIcHCgc4R+k%GH$koKeh$i7HnIvZNat$ z+ZJqFux(*C*A|_;ufVys=;U1r&b398_Z2wT7ERv0;9OfYc_)K&ZPDai4bHVilXo~c z*A`9Q?ciKnG~^+M<*9X8fVffQeP4tMUHEf$H6Fqrjfe14;{o<~fIS{yj|bS}0rq%+Jsx0>hhXIzF5~aK z#IqU$u=@_X@38w0yYI034!iI0=lZU(CwZ=Y8I!>ptFV10ZYBS_<`F*FmVApj3+I0Q zOLIgY^O~7>UxD*lns{G<^BS9YUxD-5n|NP=^O~G^UxD*lop@h?^BSIbUxD-5o_Jq@ z^O~P{UxD);k$5MAIgjMM4d$GZ_c=JPjfwX>IIqu5zi;F4ru?Rq@mgU18x@c?@~z#b2<#{=x~ z0DC;Z9uKg`16;^6af2N<*l~j$H@J+OZQ+k?!L|k47HnIvZNat$+ZJqF*v)e><+x~GCvl#;Dd$g|=XA<>73aC0@;DIZ^&s)y zh7Wn2NW9O%d96yh|Khxsq?`kBUSm@BTb$RPl=~yjYf{Sn6z8=n<^GHF8kTZg#CdH? zIbPzt=A|4*ab62kj;}bc2Z?uC#pKC@67RUgs`SB(-2TA!2ev=3{ekTdY=2<;1KS_C zj6=z`i=Va&+b(Rouaf2N< z*l~j$H`sB59XGg)n{DBbZNat$+ZJqFux-J%1=|*ETiDI-@`?8qIKOMB{Jtg5@8F5| z73BHdJn>Em=XdtRJ0+aoyY-9Pb83Fn$1@lFZnS|RaH2CsF_wQ0i2 z2gp`_k4w}W$XEI0wfepp9CH1}5&HUlA$%4`n-%(DOB_Ck!#8pGERMd2qmSa~yEtMZ zTL-Lny8b`=*vj=s;yoDN`bXo_6ED77a%Z9A-$CemtIbv%Dso|;Vfzf*XV^Z&_8GR% zuziN@GhD{1WZT70+l6fxwq4kEVcUgm7yd_f@xi%+om1GkF62`ReZ|e=6S>DH?C}YE ze8L`|u*WCt@d^Q@Y zGhD{mJ}dsk{Bqoiyl6~1Zpa-s*l~j$H`sB59XGg)n{5@oDL%GU^hLjC*%or!f^7@7 zE!eiO8*6xiV{I45nlFyMKpcC7IQ9;4>?z{dYs9e!iDS{X!gTwK(>RCcecQ zD~`2S9BZ;T)@pIA;o?}^)n=^u;@AsXc3XR>IQGy)tV$ou$n6hoe_;Cq+aK8e!1f2W zKd}9Q%Q%#5yTrtHVcUgm7q(s4c46Cv|B+pMa9&{N3-*|SJ!W8!8Q5b6_LzY^W?+vQ z*kcCvn1MZJ;4=PYj^h1C`Eq>FcYI*S2X=g5#|L(NV8;h8<70n_Tgi?Ia>oRAOkl?Z zc1&Q$1a?ed#{@28Vq5rTTd-}xwguZ3Y+JBx!L|k47Ivcs)Vzq=P#iU*IBH38)R^L^ zJ;hOzilbH)M-3~EnpYh4ra0HNjDMLU=MEjm2X=g5#|L(N zV8;h`d|<~1F5_c=h+D~y33A5-c1&Q$1a?ed#{_mvV8;Y5V`5wQW?Qgr!L|k47HnIv zZNat$+ZJ{?dtg0+a~!lD!8tx!kKi0Ptw(TKJq)SIQO03f5kZ_{4Olc zvC`f^n>mKs8{iyU?F}&JAM8Ug=OXM+#L7NI+~h;VQ$E1<0k#jYeSqx)Y#(6z0K4z7 zV*)!?u=52wU$FB9J72K#1v_7`^94I!u=52wUvL={#|pXQL)^^BoiEt=g8$XA!mi^6 z+b(RousYz}ohV}=xKd}9Q?GJ2!VEY5xAK3oDWgJSjU3|7(*mhytg>4tMUD$Tv ze`Htww0;v;9GtK4jo&3(^44$GVviYgJZ4~z8Q5b6_LzY^W?+vQ*kdMG;{lG}VP)63 zi)Zx#I&nKCt5hJ3g@E1DEl!Kg6x%f7d+1AKMDwxHIsj#Q%=VmS~?(!jH~< zP1@q!kxh8Y?3bn&SAJK#_Pb}NResqgA>U;A(W&p~oyGjg-&^hUN$9~m$MZ1l(Jst) zAUPuod1ZOludJW#)NUuYU%UPMXKlOr-}6~p%b)yQZ9j8+wf)a_^xx6IR>&(j^u^Im zjXc^Hhh1^_BMv{s*$)1T`3@xZqF?ma`ouwuzt}@3;wGkl*h5agu?G_m?7_J`@*?&* z9`d`ojZ1?+-lPeyzvW4(-&6OBKiU0A*0Y4XbJ?M3_@p(({K?;u^Y7@vJje4e?a?kw zzOWba%JQsVSwFW^yPe#A?e_DZwe9AAukBBMuC|}Kz1sd~JNnKlwnDD{hQ2u3snLn{ z#bH+*{)od*akhj1;^>#<^w;{tK^*ZBN8H5p4}17Pzp)1s5A22ia?da1F)t)% z{9+F|;~IOg=T{-G;LsOGJ2i68FF5Qacn zM?A%zU+6^q<)`Nta?dX~j|vlB1kjFTe-17^$=NHWQ#U32j!XTRFN{jqN{510>d{6_OPzs1nLb>ObK zxwGQ@Ri2y9*XQ#aV?e)8{iEOJim{>JG~Etz|9%JiS=Mmte4af{kjEOLJ=beE@>p{c z>@~dAPS-mUaqt=rdkrt*qy04ECiWVRj@NM5YdGvRoIE;rMNaiwVYv?E-*j|NijJ9a zmCw?2whQO;EuFE#`Fu-ftms<@F6E_u9+P^HN5@P%!TLQh`@{d|QR`B$?gm(gXG?jh zA3m@i+n<{Dqc7s{O&q>S-#R>7%1iw?laaoe_T%hAZN|BlIL^DIZynk%<)wbqywW$* ze$+l{Gip+^?!?ljbztI0T!J}skbd?d5hLVg+RuH_eNH(0mgqB_eM`gwee1xbywuMz zOvD8pGwo!XiT=a6y+ohkY$p*5^sNJz@=`x^QlXz{Cv1u1S#dloee3XSDKGV-kJ2~O ze#A;`M&HHJcj;S)_DgxGPYmb-I%e7@X7~pa4}5}&6TYHv9k`U2`Y~pt|2fv#1<(3S zBUoop*oyHZyD@&uj32e>_duTgqPsD1S3&Rm)@Lm$+3%3Z;~hr(MZDW+kMKJrI(~<2 zwbNCj5eL6R!hVM=;-fvn?~us-4hj1m681YJ>~~1=>wLlG{S)7fDaL@-ZR;?W{4D&B z?$z*aX&u<(0rq%+Jsx0>2iW5Q&VKODoZyIqxT~f(N$;)^AF;D>J#BWmK z_)SV2zsuA-YkjzsTOWDZPMqPZoj5}_>;Gd#zv5h1?OUIAN_m_)OQ&on`;h1}?T{b( z24^4i|IvW6&-(v~gwN84OS$!tm+kO-DSf7$9K*l6(fptw?6W+9r}$=_@8zD?l)iL z#E(8io6?6%d2X})8?oC#C&q)?{~Wh}+w$)b*ov_sTQPpbrQG_o|Ccvk?|kXv);s5` zd%WDa<3p2bC44m|NhjURXbcE?zsA_ezUI9;y#zI&~e$;EuFEu9@DYuQZhL|FjgwyMm}$+4ZN6iUbJ{wmy)!|~v$xFN`u{D`<{yqaO>%4< zxZkN_eE8jEvt=P_@bEIEBSZ&*uCA8(y>isbbDk=@6NiOCN;$BBv6GY6a@ zCWgBma+bI&wqJg1`CjoQ=MHQ#hWS?Z66dce=6l+2jay#KH?H@dtEU+KX_E#thrV`x z4X=NDzvi`bOcozDaGB<$w=ZqU&zryb{(e`A7ro&2W8Z{2Z&O*YT7PwZu^ttZ$Fin@c*C5DS5xMvu-YS z&-oeyeHL4#x%||NYR15`Z!go_WzUxUmFbpmE_><4(it>g@8;vDUMijC7wXkKtH(t( z<7C1EJ(}k~GfDC}MlaG_=;xEAf7$I{Zw~Eoh2(c_K7VtbBQBBtX^YR^-1aX&7O%eJ zOwEn=YT5nX3bQrWy6ZAMd+!4ubWZ#A)zTT}EII*7^SJmrG~jCmVMTJNG*A z@w?5~x$q*_OMmRheL6Rs^{3L`XRgyb=e+t#$@jRmqjTz*pGyC=Z}y(@_^_7#wu}97 z%5P`5R{HOpvQg)Jv$cHwVAwZ1zj^4@diI2E=AW|gX4kfSyXk{|doO*x^k4kR{Zk(Q zZA<_D{?ko)Zn2-Vbao!qVgHxA12cxLVKt{!fo} z-0=Nt#2?Q2e#g}>w|vNP=x`jepB?x~t|vbD^N!`uZ9V(`(AlcHXSqu9{g(J`$6W)j zavVB{1G#==`Aa(X`mmMLZ_fNl$N8sS(XzW`uj;0^E|ty=-@CPAn@27e@B8uN9ZT{*R`td+Yw-YUjhjKhj?Nc)r1ryVD+bg}gF7^@g#==3~ljcT`!N#eX-Y5vAo ztr)93o5xkfxI(`FDa%!Re>SoG?2hxC-L`e;oGvzJd^wOVnu(F@cQ7dv*p{Zz@x`#C>7LHbWFJf@>Q`dG;s zCs#Z@TKeR1pMzSq$osb0Phz{+;YW7NaCpmBo;w{^u5gU>^L**(oOF`fWZj$g(9x35 z(0AL80}nV+&*u5k@748>lMeHaXK54t5wtNmxjU)Oo+S;wh;=JnxgAMf_3&_2&HPcM70_3X~)Uf6l! zA){q0$Gnr6qr<$ucEE|^({4Di^S2wf`j~UqBzO3qtXNpu=je{dp%69+3Q2Dy*~7{*TdfHVej>@_j=fSz2vdi!`|y*@AYkY-Yc!o9twM} zmpt}**n2(fy&m>n4|}hN=~w=r`=z};^tIQ+-s@rS^|1GP*n7R?vDd@i>tW}se3$z? zJC9xOY+ucHwla_H{N{ITxNF{xRvf;n^Nw=^*Q$I&+qDwk$94_HH?dt?q3^Q-*k=W> z&kA6l6~I0#fPGc~`>X)=Spn>`0@!B-u+Iu$pB2D9D}a4gVCJmAI-C{2J}ZEIRsj2~ z0QOk{?6U&cX9cj&3SgfVz&22$8{F$8VViPBRuPR2f6DGLErTha@RZPyEZ}YdIx>iS+MIVbX@Q7tZNf=TxY?qq0n(X!n3Y-kn=uC z-GSWoj_gJag^ueH*mVc`u6Lv#^%Qc~JLtPMLGF47eb-sA>nU_x@9?ba6m(o?!LFgu zcfEtYYZKVDhT4z134PZ)=(q-fU0-9f#>v#z0#yWa7$)F8G+t$~i~9iGi&STz^y z+RE)v@9?ba5!kp} zoOea)9rRs8q2qc4cHI%}sNO-JXQ{1_yWTiQ^;NKpzk^bx$7PDU1!0rr_gb| zgWRlGaTy>;=DtE`&%?~Wti zWtT)FT)Ok8Of zW=+Fh$d%vFSKi@>kK5NcK_2mxJmOsG*&Gk@2ot9wkGfY}osJJYmOK z&$jxN;OLjw`3gDxlHB=?b{OZ9dpsbIen}qvvY+%z9Q|^>)UTqyl6Q^6MKw0QO5>0m z(Wx(68WVM;z^o!)}dE_#+NK#n}%2i&;;whko?e`ouwuzt}@3;wGkl z*b9G%vzT~b4>@td9$e-w~4>a!IWl_}2MWulmh3U+IKb+s*Taj5BOLv;K5-C7 ze8dqq+a;dj><@7k^PK&}4(;B#&kYUd3l4cF9QsW-+7ah|DPPFLuH@lQLXI8c2#5b- z=PTsOSLiEWaKuOY5jWdazR+>LVC)b_*!gO;)5=#NSARplLhgLQ&KDeZr4#_Yhc$kF!dAr2kg2A zCU?BQhFo<`=u@vr9`%~obqzYMYhc$kdbU-sHDT8^u-}slxyG>fHRRscVDD?N_cb{D zso|)<#O(jX3wiX*^2+jvgXFFwqJ5nwz!6XBM4auX>Sc5yFOrwJ^ISv6a}D-fgFV+^ z&o$U{4fb4vJ=b8*wUBqMlQ|}yYsAEJ4gN>#*E`&AFWIvnsGyC7P|G8gH_lvnk9IzYm&gd`t z;%KKC{iS_z*cFFA;_y=({)?kuVq%Q#=r3`wKJgJp+{6)2al~01@fSy4#E~!gA9)lL zV{HHb84u_jeE%;yK3H_-PWZ}ICU*=u_lQo$PyPl}^}(XYOFn4g(2ke;{6z9AS6QMO za_%(AZ{K`sziV#1r;{C+|cLOQ#L;CTbG^?- zPr>KKZvRW?qklL>I-{obZLZeiPW3Bv`l0i{&@Gz7e!PoxmR@6%=6avaBAu|+fzE|% zozQ&skkEs9j^|<8qg|M}h`o?kmS_FS`q@tHc5?f*+s}X2wwwRGwmyBCUi~d@lIE0SkBaXO<=^yrZ zmVRR|{3QPJGq*=x#CZ&~^X2z3^y9s&3H$vG_In-d_dS?#g&rL5UE+A}5|c0Nq2u?= z(9i4kI+C--x*fl-q7(03(uwyj`IevKy-OVLUE*w~oiD$S$yWUC14lbm(S8kwU2*s$ z_WL0^;lJd0Z0L85kn24YjySj-;v@F^Dms3Th3Pl;^la-rSsZz(W_+c4egD*{I!}N% z`sqFCivFiG;rEB%p7!{9_XJidse{D#zIa|bWAf2r{^akib_ON%V4mZ7nD%HF z&i%Rwdm*nZ&-${5Jll~yIJaNB{ro3?*R$CUdg5$H_R!Dm$zH3SsmfO&SARplMjq{m zqkVDM6^B3K@Kc=oh5usmmHTBm{k1-E5aTcQup4m`(?9HmKg3x~{ID1PlNb4)ZE1cX zk9ntju|BcRAdh*P;F!PSnAc*~C-l(aIi82T9>QJ^L$38O^tB$svHrMy*+cI25RP?B zI{oguZOVLLpc1Aj@LuvUJqM3t@SYES`XofgPx7} zh`k=73O}Zx|nNj0bUy6LE|mvF8{1o?o!% zSIA`#_WXhwU)Y0VoQplbkjK1`Jm!no^Q+ZPYkt8Yui((Hi+04GU&zC*^z2C{)K+mI+^3+JQ5S<5q2Jje{GGb=UR6r))RQn#xK&~>rZIHdv4TBcb_|R zf;+FdGWA?*J@FaOo|y(ebGVp4`FpFK^%8n8&+$A=d$bF)PGT?QvKRWb^|PJY?d0}r zx1ay4Z8!gWZGZA}wf)R?YWtt0Ez;+NB-l z9robpul0$87=N)RomSk$^bdRC4{;Xf=ZL>J@*@A8FXp4?-RIf!4!P$Y?0E-!-oc)C zu;(4@c?Wym!Jc;^*SrgTjWf7w{T%d#>nFK(9^uGu*Su@Zca8b4+PtGa$o0GCAnVx5 z1K$ycT)7LmILlS-Uv<{!IK;U} z`)u}KeFo_E$wko@ahw_I?B!o|_Ul}Stz1j~pPvbTQ7# zl9^b}bLPmWLT%*bcdB`Oxn=+syHCEl*5b%fqha`HjzKfUwU7VV@boK1+ms#t8fD z5oTU(FrU#4v_}Z%V{W~2l-uJB4>uUZ{;van2uikT&W83`Gp`+V6 z&mVb`m}hU;ug%>JU&}J%WgYJ{?fwp*4wPOeTy$%sO~dtyB4poL|cBuh~?V)TX(G5 zZfE8->)P$VKWIR0yVI|}UTuHge{93reqJ=kpxXX(X2SecUy#pzk{JDMS2XX`=Y0?EgN~Cbc;CYx*6|Z*lIgW@>u`-e(@ z|Gi$X7P@_y72XjpQ@b(@2_VcJ@cdL zcLVp3&LS&*SS>%_q2m3w`=mN`r30li?V%a!yEflh&mOVxv}*rj_Lh9}A+y(WKCq+Y z$GzLFzI^)K_3V&qW~e{haX;yN8{#Ayw?u%)|X%Qed!+bcY5AH1e4|>g7 z|7!F;l7Bku-1UZc4VC`xJr=C{eyyed{K7r!UQh2N{r5hZv%cxqdx{^uwMRYqjXm`2 z!Gjj8uULC0J$u%+z3N%UeqTC!_nWU?tyim$&re>k?)~H4r8DwR%eMWW@5*o0H~q5p z?A-^i((dn|A1%}N^A8s;UiX}P4?Wv|=f3s9y>}J=eEq6EZoZZe1Getdj>E&>SxSDA z>kp@`QXhX+>)999T(jQ%p}pnv@Do?BzdK}a`T5YdS5O?t^`yO4s%Lv|U+LVnWL;l) z+Ye=H`$GrTBf5={{!_zNsh4l;C*J(nzV+B|9U%R~9_?Shw|Xmg@9eWd&3I$%ZF%}e zHRF)>x8A<4?>*`e>HlQ!fi+_couy{lxSqA&G2*K>*;w-z|DXQBdNpH}XE)e)&6;tA z{K$LOtGn&r(&yP8JDkwAbk_`d(VRXYsN6V^6>uk#`hi5ZfCwFTF=h; zzy|f&yPYCAcIO&*Rv-`5A$N8C70`qbNgA+KYYXG>%MQDCpqKf&NI%I zK6#w+qn0i5KHnk}q;u(w%hvn8+p@LY8~IN6+LK!C=W#OS;R$N3y5=`-(W zhkWtup_{bg!#o{%{khWLeT#1O3s1D-z`TBUg>$9PyrX@dWuD%B!C7ka!0*mnzw$xL z?yR%?r6T6&Ft2Z0@htJ?o6c6B*85DgfBptCe)=6@WyzhhWRnFI& zPtBlsqQkoS=+sv3SbHD;V{2ToPLg-*zH!E9mGi~A`m0w?Rr{CreX4r$wUg97>+ssE zpCWzMNyY=uvaY^Aw$tXNpu=o15 zJnxm(XAgzF*GnFIJ?y<6_FfNruZO+Yi*vu&>&3Cx!`|y*@AWWoW3Pw3*TdfHC6B!x z_FfM=U%bP75lg@8ovn5riIwvRJCCsQD2_aezr=U8GLP;2=6u0j^R6{7oG)VHe8J9_ z_&+f3_|ArFRle`xT8VFWxQ60;9j>j=_gMk#vjW&>1+dQwV4oGhJ}ZEIRsj2~0QOk{ z?6U&cX9cj&3SgfVz&v-&I(|k6~I0#fPGc~`>X)=Spn>`0@!B-u+Iu$pB2D9 zD}a4g0Q;-}{%7J(j$Eg}u0hC`>mB5-M_|_-=(ye?r>>ijyWTAx8VViPBe3fZ^j+_u?|KTk>mBr6n;>_+ zgTCu5*!2`Tu6KCWwFx?|vtZXy=(rx?S=T$rU3VaNy~DGvq0n(X0=w=&-}MgquBVW@ z-a+5B33Asv=)2B>T~DFodWUCSr=a6H3w8~KzUv+IU7NtJHPCn6gud$?bXc-Hj}I<7mAyWTLEp6%a@RZPyBiS+MIV zbX@Q7tZNf=TxTJ74T9YD6wkWeLC19ma@RZPyM{u?^$6^`1AW&!=<_VK6>`@*=({#S z?s^A(*IBUZDRf-#@T_YSbX;e_uA$IzJ;JlDcaXd8K<;{nXI(>~<9Y;k4T8Sw9rRsK zA$PrlzUvg^u6NLPodvs|LdW$Ea@SU{>!xz=@SegMKHRl0pP@MXPxobhhsoo!anP+p z(%_CKsuMR@P(1XV!SzdP&m-o)TQKInnOeNS-SvJ4zEz{opD*RV!~8pXFwgNkOnbB| zdA7qHxkBD7^b;KIh@*WmcJkj_-16sU^utea_%DurS>DWkSReny*%n7@LjxdgIQ;_WT>ZeDuTB@7J17@+Y_4v_5%{ImMfeIkO(I)(qlj zAN_g#)=IC|JjNBgL#hUVcMfz7@PP}$eV?Jf}|+M?d*TRp_T9DYuH`W@ZGbDeT$ z{ptm8)a0E%`8&+NqX+Yxp3h8sw2K@&*n>mfEc6o`?TDj&ao81yKR2Tveu~3?arDdb zX0~U2{1fMPuqV##(;wSS{5|}+8NKlH=4?+)d)c1+&;8OIL?`6xFLoRU>^MHyaooag z&9mW81D2hLKX!;0a>hlB!@3xsbun&h#zl-n&8HZLnrAT%`FG|QV^8xk#$nC4h;f+P zY0odq8Hd(qjJX|g%r7zHk-wu8{xII`r#SoZ2B z>tgSyi#;WuRcr5)ez6C!7qR!T7ie#cJwkhC>=AYBee4mOd3*1(oIS$&tp9FD9PNw4 zZj1lA7u!$v3;QpQK3eX*1AXr)^h~F^|1Z{6)Dd)||Rni)!Y2tSwq2V{Ose8EXsw&YH=3 zqO~^GmYTU9YfEmYy=Gd@+G2gy4YwnXHB-zQ!{5;fe^^88r#So<(?{%~Q>;1YYfX=K zSTm(ltX_MdyIK5ONaY@u{Xw{O zudr1+_->kP#oaX6chg|sO@nXY`)(TS zyJ>LT@l;*lyJ^U=Lww4xd~WS-_e74j^|<8qg|Nsg1th{+G2fi zv?Gr86FOm69R7&IPjUD!CSTc}<<0De^_$s0ac-xX?TK^yDcckCCx6E-|BhbxnX)}G z?PYsn>`?2W6Y{Fi7e_ndXun1$?25x5F?Jk(><~xviC@gG{2d*Ax0pOKF7$l@xX8P{ zD;?uO--lw{qZ8wh@l(e*6c^(yx6>Ynbum7zUlr|$i*atdb>WXV{1g}SNaG^r7yZ)r z3FKRRZ#&x29a6ZMzZ&n%H{`{9$4}<7e9QhbpT)$FIHDi&CS0sDZbx$B=eUL4gnq0W z;%ukM^T@-0ahb1TU&wn=dwgn-iakPmSL_km(_)X%UKe|W_Q2R9>iqBMu@}^__la4v zV~@!H-roD_kh2$9UmWd-vmMz(C)@F!Yk$}a?58;PJ~92p9y-O|fxh`nA5<$l>u_C7Ij!XEnUeX*z0FXT<+#4q+rwyYAd9xpoJWsvXGf(rL+xj*PT+DIyZqI%8Zt3aS z*4o1Q@RfKcDf;NO)N4`28kha-+9SUDdxZ8V_F9dx)}AhoJzdOR$6kw0vF9>A*^}7g zQtats+Kas}kKgv5{%?7=>^}bTIxuJoDL>EppK^P&E6#Sj7g)}kpF&?8?Ih&UzBufP!yj?@ zDGvX|%r)#qzbgEI@e6w}{$dZNAJ~KGANFASjXjunU=Jov*n^25_6m7b=!>JB8hNxY z4!h#;M;v~NiJ$X=o!Gmz$MUW~o9w-=2icQj@1}nAyMgv_{*Hd}F5&uGeirW@d2esO zlekV-e~Wh*w>6QW}z>Rb`;xaUmSMD;g6Vk zj6K?69y>45FUie}&*;0xs&j|jxr3cMIASaPh`HFgL&v#mwe#;?L&zO=qwnH~iP*VA z$GL-@JJ`8{ojcgMgIl?4o#{Dug}&Ae=MK4Z2RnDIb~Kh0L+1{;a|f6Cg7cWUnfwl( z@233!d;Xeu+09qU|9|-pl;2#J%nE0WGe)uUS ze%M3q+`*n}u;&`=xdwZ#!Jccd=Njy}279i-jD74Ca`iX##nDcUPP8u$yW;Ri9Da(! ze{uB7^8c!JlJUX3i}5LrajSV6<5?WzTpZ(H9P>gP^Fb z+7Uc+C>>-bFF1hCy@|YKrdwwDJ{DO%e_6oWB z>-kl*lVHy;*z*ha{DM8dV9zg@afrQ=8QYe_&LiwR!p^#EGBkVlF#Fac2 za?Lg85xMgSJCCsQ2s@9k^9VbSEuH_~buxbIPsJU86n7XjZi_nu`fWe%5^$$RcN!Q2 zafdE9cde7H z_aBXu9A~Y|#OMEQos4@XzQ4yEh7@-&#Bm3s#jQIS37z7O1a~yP()SO`yENvmyEMAb z>ANnR-T4lTIPS)XzXEq@7@z+&_kQ!*)pa*7|1S2w}z$guhqrA zRu}tPUF>Uhv9Hy|zLwi*zyDj#zGnRz_Io4j_eR+7jj-PvVZS%Res65)wBP@c`~4q% z?Yq&A_G37=uYDTMcC~-Q*`K^0A1&W^Ceo7wx^X{a27kl~L*!>kp91?Qp3wFL>=L>eeVCM^VzF_C8kn^5zeQII1BX+)! zJ72K#1&5!~cfMLW?f3k4zCvI5igpry!_F7%e8J8a?0mt_7wmi$@@Ao*;Alted?9zf zVCM@a&)9>VFWB>|dIb>a&L)OJPWL=y?*2OtwZl`??X}R)MoI|>u8oR|gr0q&xoI~1A z$%}JH_sephL!$5BYv`BGPq7te@3yP+R^)M3FM0M;=d;Lt<`1{d{B>?@xz@?h7e_k@ z{oF6w7l&PO_#+NK#kpVpy~h30e&>8K@0>5#`GTD<*!hB;FWC8loiEt=D&$%ZoiF6k zP7OO>aM+dH`9dCkO746ik8x&f!Z!{iPk~?4Mcz%`47;x@j=dLxDTEEf55krju=MK4Z2RnDL za|b(jg}iI7wSJTRr{@|mEc58xkyGa`#)HNU?A*c59qin}&K>OB!OmSF@0xd!yH$pT`&IoJB(qz z#h1TlBIbL2`5P%>zM+@DyCOzEe^V~y@2u8v{!VPl-;NXKZ^xzlUDlR-(14V`*DB86 z983AzZsPn6tF%bZ^ThcZRw;k?Rh++JmGbvsTYT|CDStbz#S72dmgjHBwe|B_`PX(9 z`g7Cm=WoX~Z8v{Au4#YrH^iFuGk*)NY5(*0;+piGzDR!jC^7o^d%0rT$=}g!$#eVp z`?})%&AMj(?yeYr@^|XR_?f@;C(hscOZmILEzbSQ-}-BD?yu#jF`MWe41NmDzDSv~pW(?$S?4Ph*#i#6jUf6pi7Z|q3^^33a`{GCSW&oN;@nq&1dB+uWsN%^~u($C)l zO8Fa%;ygk2SXG)&Gca-vXG9}O7w@LYXo_cnl^HxdczkIrMuHI#-l)tMf&flL& z`8%A_&)-=}`8%1?&);84`Foy{-#g&jDSuZ}`a4wLOh-&;>F4j;r2HLD>F4h_rTm>t z@w+GYPWii6_|Cj({!J%ICx1&PFkOJe$9b)?^H;kJrE1%-@e{x0Ao4t7nIQ^i1>G9S)Zq zyZO7j($C+%Yqzs>el~wQS2|nF@%v_vn~%`5`CC2B{OxGzV=I4aSMvPLpJx63zLGDt z#2=fTFCM99^LK%o`FqjQA&>bx#**jn3pG!^Za?Yg?+!KdccG<2-t%{l#f+2uU1;f( z$NU{*>F4hkHJ6w=LUQt+zk4kG4W^$h-Lv@*BxjuD??p?WJm&8hi^+Tb?y+f5Hh)_w7cF`I?J{lt_V$t={iiw7fK~U>v-vwtDSt0oI?OwsC12?8 zu<}mQ&)siREwF{`McKAXWr2c`Qq8N#_ujU^E7{_TKYTuxlbB?*igxt z*ZI5F(r4b$KF=~w^LMJHv)M;0rrrAQrf2iFuo5vxhk2d9Yb_q}$#Q9)m-d!U{=QZs zcle*byOoGDW0iH1TqDol?@G>B{;rqei4N;({;s(6S$p%hpry|`N#3!WzZI68FV@xk zU2*B}ztTo&z*R>{pLIBYBU<{blZ*$RWnInR6_?H{Gp(17UwoA0tiAag(c)F7u9aqe zXjIKNB)xaQ-s@rS^|1GP$z!jFz1PFu>tXNpu=jd#&KG;VIQDwjdp+#E9%j#FuZO+Y z!`|y9kG&rDUJrY(Z_D#uX?^xk*n7R?vDd@i>tXNpu=je{d%ZaKi@jbPdp+#E9`;@j zd#{JR*TdfHC6B!x_FfM=U*)^p=h=DedT0A;zO$8iZ09$>W5ZqZZa2l@t2*!aR-S8B zzR~AeiSO^ZhT@xhuC37bSpn>`0@!B-u+Iu$pB2D9D}a4g0Q;-}_E`b!vjW&>1+dQw zV4oGhJ}WSDR$v{@3SgfVz&&kA6l6~I0#fPGc~`>X)| zXW~zeT&KXULCBZu9ptV@VAmb!xZWYBuA7j%-a+5B33Asv=)1OpT~DFodWUCSo1o)5 z3w8~Kj_VPgb-jb!bq8|SJ3Q+e3LV!YumBr6o4~F$(0AR0zUv)ys3WLBVAmJuxZdGe*HFk^ z@Az425Zj{GK*#kC&${MK&eSJz~4mJLtRq^0U-d=(yhDS=T1EMa_lWH3)Lo zQ#|W>2OZZP$X)NC?-~jn*CVj&4)k5`pzqoWx$7PDU5_Aly@S5%EZFrFI<9wk*0l*b zuCtK420`w6if3K#pyRp&x$7PDT|=ScdIWaefxhb<^m&%r3c2eY^j(`EcfEtY>nzyy z6gsYVc-FNEIa))Ln)r$*N7a{){H)2dD^5GM z-e=cO#A~l`LcQ|WKNa8A|Kxf||LLUvL61}G?rY2-Uf{^n>bJI^S=@8q@%4oLx{DwF z<>~dB^*rK12b@t)8nHl|mwx=4ZJiV5?k(oom7ZEgOq)-gy@pWJnJlHHLSHT=Q*5F!JM&h<^-e9xjttBFz5Q55x|`5Q^QD}e>dPv0p?tvvkaJX zea;|Y&LsF90?z-vKK(ucw|;MYv?b3qB4-@P`F+Fs{O;j)_&vn!b9Q38i{#&7><_=g z*iU|kvHzUSxL=azvkYvZ&shdcJDg>}w9i=vj9tz$VEo}M1IABkTA1HqIGcd!7iSrg z=l)tw9IQ`#+zxSb`}|H~yTsZ45P$oryoCS%Oisx=XOryBFz1fEM=}ODcVu5j{=!x} z)mvUPvzRki-U-m*tdVzC#tCPQyf+~K`f9t@2kbMe^xwH;xB8xmpEi+m=E}PW`kXcL zP7HUSwpZPAq3(M2*xC20mmT^wJ-hfV`_@A)eXEHMXRf>h!NV3ER&TvlH|cN&$vYG6 zk33?(`k*D>Z{jm&jl4S|=d6);FP^_}#$%FZrDl>(4HEL2`bZa)0^Vz<$ns z?+JD18gEG_EpvK(?C!6M^MAXn<{c6L`EAN^;5P*PM1JO<$JG~%d|Ue67dWe4_4fBA z&;Ly`{@Z5qjo+q-1Agwg!fExT-Toq-X(vsnA3yJ7J-bogbL%yG&Y&FS|E3xLZ8PZ) ztWU3p^qF4yeQKw(>s!`q<&NL47;of@-=-Lcw7>qP6YB9}XOTX?Q!&QS`RSpP>Sqq0 zU!4Ej2<`QX-=-L=Jj-uWj4S%J?e^!@kG$8?=h@e%F4nfi`yx8|zem?z>-e3DF-$u* z_Bp%${>5K!xAWdst!KZr zJnB#MvBkSG{o?m4-XoD8xaC>(Ne6yg&+?ldwJtj3k#|RY<~J+eP0{DKJ8EWh$ony0 zUq{S1;oT8^^2j?Y`ut|adoXhHe&E=(q`&RNQ|nb)_+5+h0(2NByes1m>mFxA$k(`dOnu8NYwB5k%i=r&9p)X+;t%?qE1}Qt zRGej?!#w?L?1p0IHSfFVGw)~zeV*lf3OV!i#u4jE|NMam)+gV-uH?*X-mTGR-qAkH zJRP#xTGIK+ItSMiJ{h2A`Q3wl$6gP6 zuZO+Y!`|y*@AWYG;&%(lW3Pw3*TdfHVej>@_j=fSJ?y<6_FfNruW!rqUTJ;yP}qAt z?7bfLUJrY(hrQRs-s@rd#a=IY?Deqsdf0nC?7bfLUJrY(mpt}**n2(feDPlKMeIDH z<2=I7qvT!hZ2z%$wla_H{N{IT*!hB;FUh;+U2A^DJ2o--Ps}^cQe3NYhT~d^^BLDr zoXNPhLf>Zvu+Iu$pB2D9D}a4g0Q;-}_E`b!vjW&>1+dQwV4oGhJ}ZEIRsj2~z|2{J zbvP@4eO3VbtN`{|0qnB^*k=W>&kA6l6~I0#fPGc~`>X)=Spn>`0{EYaKRI%p0=otw zU#@qMyB>jEcc9~Xhn%`@LhgD8eb*+)UGJdp+6s0(g^ueTo^@@4j_WMgH559oM|jrt z4szEW$X)O7tZOKAT#vx6JJ5H%gTCu2+OM|jrt4szEW$X)O7tZOKAT#vx6JJ5H%gTCu2K*i5fB9KzD|B4%@T_YS+oI+|?ivKS>nWafy@QVH4&<(P z(02`mj_VQFbqD&cchGljh1~TH`mRTiyWTmBrYmf8xr>mBr6n;>_+gTCu5*!2`Tu6KCWwFx?| zvtZXy=(rx?S=T$rU3VaNy~DGvq0n(X0=ou5-}MgquBVW@-a+4W3Ub#w=)2B>T~DFo zdIz~{E7)~Yxp#O^;S3+{+L!w&4*%1AdEaYN{lUlMZ@z8Lh12%qZxNro?)vG#m3|>! zZMpqYk8P)lcU$x1^z404h<`Qxq_n`dUKLL_+kX`NCWEY3r}EOf9CJ;oS#{Y5&xpZ7jy_`)_Y9#-Fv1 z-Aas~4{R|+jQ@A7yN#HBS^m3gUT9i>+>2wHZs(A0pLV+acc(w3pY6`_-PtPpv(FRz zRQ7Y?gmWwVKjZAzRqodv=X6%?FLK8LeaDA(95>o`JhAII4e=c7Ad;6t{OH392X8V)V_2)hz zUUAt;=_en(B3|Z%tJ6$(eI)KbT{Hdo=9wC_dFYD2NE7OOza{ft546@6c+(s1O|QPN zWLy61j(yttA9vJZ+PQSGfnwU9{J_Ry?5;Tbcg6T~|AkwL@$*;1hlugN?=IVj>7(Tx z$Gp(A{wXJqX}X;s&G~Vs+y8i>A(yz59 zG%NQPx#NJo<3l@+8|^!u*ma!o$MMHc=LP>yE%H^4Pv#&w^&Esf2Vu`a*mDr}9E3dw zVb4L>a}f3%w46C;edZwSIS6|W!k&Y$=OFAk2;=`Q&u!XRX8(6JCSU5=;?rmEpN_b7 zkmQHGvs2pb%?-reesfgX=(csl_g*+Q9kAUR;*q;gOyfRSO?=HSFHI}lwY>QGU9U;+ z&Cy$Y`Mfu1&BWG~m)w|6oNL~;e6y`)YwN$UK&x!Hp z(_0=F z|MqbUHEs8fJ&x|QKhO4fd3F2Q`<(qd?Ei@qQb)ESpYOlrp$_*Kx#NJo<3l@+8|^!u z*ma!o$MMHc=LP@Ee33`LXOdso^A7gBgFWwH&pX)j4)(l*J?~)8JJ|Eia>ldu8RxL) z9qf4rd)~pGcd+Lj?0E-!-oc)Cu;(4@c?Wym!Jc=p=N;^M2YcSZo_Cfr@2t zuVQ`IwNC!;S||T+s8#7B@6W80|4p?(S>yb-*5Kv%^jU<@894XwIRor-2A%VK#m|WH zfBUSl;ZeJ5Ob*#_Q}O95%GO}4{OzN*jly6O=+W<@^1>6kuNZCwzmF8-KQ7R z&RJ``U!z0&_wD(r7`v~}@SGTbUKsMY7(X|<>>)A!=l|xLn7L;8qffrwwEn=mFK@b? z9D}CYzu>^@I&Jst%eU-je^&2xM~D4<>xD%s`#*W#byUaUXKtr*e~~*5=sP~Nf}u|mLA#q z?dBbw-&H%?y?s`5>-jcUJ3so_#O7QtY^rva?D%nW?hU@9c4mM6;^rMIZKie}zj)5( zgX?dic2>OivgV{=-%&ebANpopSD2R<<6nGM!gI|GhivGb%&)>Av@uC;UL;?u3G zcJ^N2jLu_jUt8@=?(sKTJJD2W#a&_Taebvq-E8W*|^m{9+oux+{QXR4F zifU)#3OiOCy}p9lnd!Ab)jnITpmx5o%_`Mhqn1=VS1);Cwe&~JtDOb6>Q%kI)RJoF zHyz`u`sv2+hkW(f z;!U-~_}O~g+iHjLvrxZ3*2IVLbMbEP*2IVLGviB7s~yJk>UX|ZvsN>H9{%__wZnK` z=kgcS4&(Xv=f9+O7|+e>Wwpb2KKRK8)DH9OxMyBbJB;VshdiQom|vIf__*3(e*NyO zC)5t}>y8tjRy)kE_y2OI+F`!;9Qv%LpV#(0H#uKR?lCHP z{9N_WS;^z)*l`n*$Is8-I6Zm%^t)wT@_2r7z!k~k=aTQAmOP$kU;5JI@qEsqlat5u zpO3jPc|7-e?fm5Vwe!X|C6DLtZ7?Z$el2p}b;ldwlIQ!lo>P+N`*c^`m^|O7KjgaP^=HqsewjSqM;-jrs5A?@V5Q4q4?!$yqm=Klr(rb>rO^Zxu7& zfBoH?#mx83-KI4zqXZ-Q{j6dElh>zE2{PBK4e7s)} zAMY2$$NL5G@%}}=yk8I>?_cE0`xp80{zbmLe~~Zmr;H!(U*yaCDdWfcDdWfcDdWfc zDdWfcJLB2=DdWfcJLB2=JLB2=JLB2=JLB2!8_X~7?~G@^Z!o|7zQO$R`v&vN?;Ff7 zzyC1b{l3Bc^7{|--S0olcfbEI-~Il>eD^yT>yO`mnD2fcWBu{_80(MU$5?;-KF0dv zcQDqR^0x#3rqK0UPwO|Pui|e#an9Ue--&bPMsd#EDDDw8ihD$j;vP|>xJT3|?h!SL zdqj=m9#NyXMxJM*;+#`~H+#^yuagRvt$2}t1jeA7$C+-o+ zPv@n$N2Gqmy_CP>I4^1x=S7X;yr@x}7d3n@C7&HNd@lv|y%gB@QefXpfqgH<^0=!b z{kX%UcH(Z2+K)RwvKx1Sp-2MjLm5w-J$ytqfy&KGj$3wFL> z=L>eeVCM^VzF_AIcD`We%ksE?(#{w1;{HiHU&xF5C+&P8FYcen|2T7Q^{aK?MjU5i z;yBA{6nBam#hs!?ai^$J+$m}lcZwRtouWo@r>IffDQXmViX@LaMbeKuMQSJR6si5V zQzW}_r%3+9og(=eXIAn*?i8tCmKSGPjp7biqqqasDDHqYiaTJ9;tp7&xC7QG?tnFl zJ7AK>-74wFoh!8ycd^ud+|iQVxVt5P;!c{24$1$xQ=~pxUfd~a z6nBak557~>DDD(BiucS$ai^$J+$m}lcZzcS+joj2k2^)uk2^(bC+-xf{kT&kyK$#T z{=}Uk`RTmifBZhKe#Jea_PopYRoe3o_Pm2V?_ke6*z*qdyn{XOV9z_t;~r6a-XZs0 z6xerBVBbZ7eHR7xT@=`NQDEMmnRl?~9qf4rd)~pGcd+Lj?0E-!-oc)Cu;-oSagV4y z?~oVwh}!cGd2x@ZJ@1eg_lV?wnXhuqEZOt4YyH&y&vqVJubfBNd4!!u*m<=4%UD0V z>bvp(tLnRQ-gT{$U;TBmtifI1b=BSa{}8q7IO=HEaj@$+*Vmjm!>;2j|FY_C+GoEm zYr2xV>hZ6BJs$T`l*hQQ(kSi`HHv#gjp80rqqs-ZDDDw8ihD$j;vP|>xJT3|?h#2I z_j9Bl_jc4y+~-mIanDC~6M$_tOmbf#qU;);&-b? z@w-){_}!|(?^f|UT7%!w;y0`YzhTAiXpQ1`v_|neTBGP|54Q*98G*f}@CnsEC;vHgQyx5k`wFaiQ@e+Fd`0TrEbRdwo| zI_JE5*hlkyy}q=s*O&J7`qI8$ANzW~&)CO4qwnkWv9IU*jD2aJu`lg2_N9HsKK2=X z-?NW>Pv2+kW1rFYJ^RwWXJ6X)>`VKeee8SsK5QTRu)gov$G)fU!}g_p*uJz6+n4rX z``Cx|ec?X#g?%5kk9}C*7w${@!hLC9xG(Js_pvYR`_z5xQ~SPfAN#_-Pu-XHsr%AC zbzj=2?o0dTee9e2K6PK(H}6aP=6z}3yf5vW_pxv8`}mTFIgFi?>0{sA_wgl<@8e4z z-^Z6czK<_?{9J+bkDuF7{PA-{8o&G;k>Zb^ zBT~7aBNFy=M8bZKNI2x-T$7(8QhCUe&NcO=b4`8eTvH$CnnFLEvkG}Q*A)6m=dAkD zIjg>O&Z>`dR$(vBeT9BFXBGBJ=f3*Vxv#!-?yHY;U*SKTLkoLx?koH!okQzO=g|7n zIkY~`p@lzlE-w6sb70Df2Iv3ZM&c*d{E-v~P=k&s#ITsiGE1lEpOXu|Z(mB08 z&gn&e=UipRYv^bTxIlk&Q(VI;ap|JAI?=q{NY?> z#GiDovX66>5r5LT%D!~2vM-&h>`Uh=`#4t_@fmp{9&)ZS;&VFZ*_Y0F_N8;4eaI8z z1^S8jj65-3q;scz>D*~wI(OQKeq#K>UNK&vpBTT=Iat}t&k@O9evU}?it!ZxiSY}2 z#dw;|<;s8j9FhFT&k@OgVtmJ+V?4!wVth~MgyqkEj!6FO=ZNIbG2ftn#rTdt$9yB5 zTUP(_b42Q2evU}}E9O7+_n2?czheHA&QYts`#B=@cRxp@{vLBM;!n(f=3 zfBYPg;*XyrQv8WI7%?Y*?;yU9kn+3hQ+{`S%I~gE`JKMU5#NJI`Q7y?zti_Y@YUvf zBBS>`k(`@n9Qk0fW0R-X-#_Y^JU#ER#{ONiud4HVJ-M&SohI-7#v&Cj(bwxKk&(R+>`Rl&z{tdds6N>`1p3* zld|_)Kh}-*&xF?0W;+_;_hE26X z{8#dOQm8lXF+rZV-vl}1-V=K#d^_$#p^5J8t1g*o|I3%^6Ylp zlVa~&ZO1(+Gfq0I9rvWzdrI4JZ^*muKC>P7q}Y3L+i}l`y$7`&_k(=@mebpDPs-t2 z&uYg#DfXVycHEO<@8fO9{Ui4N)pp#IGV^nvZpS?-cdYY?cHEO+`RB4=+`S7dk<*G zJt@>1_oUc6(z|?kHttFJ*@yqR9rvWzJ6+pxPYQL#Jt_8X*mm5Lvios|w&R`@dw*;@ z?n%LpaZif9hqfK}ZrJ;2+i_0{c8_~f@RPVF1v|z)DfXV*cHFyx-Q%8=V}JXRcHEPK zpTs>W*fH)&!R~QS%3Du5rXBaB*gJUJaZd_~v z8uz5U_IIbXsTKhUq^o|L=(?bLSMlVa~-mhJF2dq1=EjIR=7=jeAmvlW|Xqy;HhtFXC$4lk$TX&2E3h?@1vJ$2}>;$+#zlxElAQ ztp4ZEx8t4^VsG4&^0gnI(~f&mV(j4Fff(z-G1h})tOv(f500@O9AiB=#(Hp!_23xm zRqkUwIL3N#jP>9c>%lSBgJY~$xsUbW80*0?)_2SOo|G8tDUY!p41dO4aE$ff80*0? z)`MfL2gg{iav$r#G1h})tOv(f500@O9AiB=#(Hp!_295qp35za!;X}P9l>EoaM%$X zb_9nV!C^;m*by9dRCzOJ(|s#pM|2W)1cx2Li?U;8-gF$65h6)(XI}RsfE*0&uJqfMcy7aNLs;YX$KvYX#s~ zD*(q@0XWtQz_C^UMrPIuz_C^UjjgK056UHu~FnH;K)I+SL8dC zM?M0MyaSrZcd%*XO_WEz1AXKslt;b;edJc)$fux*e1~TvH-RSdEO6vd&_q7Mvytym z9(f1lk?-(q_o{fA5n#emShd%B}i5v==$Vb4DcR(Nc4*YpG?n#M!2l~iOppSe9`pC1u zkxxMr`3}!UZURl@S>VW_pox5hXCvRCJn|08Bj4fK$f2N#d;}ah2=tNfKp*)O<&p0| zA9)Jpk?%ksc@{YGDQF_!p*(UcaO6#S?1(WX?n!CJ<@%nKXF4vkC$ju6KFwX#bHJ}F zXSFu@$?dNMKlIvDS`WQsw_U&k51rbYe(Nd1>uzv*YnAU^C47zD>$=b3-xYq|)t_x0 zwf6(UC;af-)`4gJQuv$~%x>-d{fC4%-tfzpz z*Si3Emq*y;6#l1LeqnD{U0%0W*!3Xn`Vn@$3A;X3uj^UZ^)Kvp5ndXbV)sj4c6{rk zgO=X~{G(T&&^q&*MBbhi|_kH>(SHai~fpN zf3o%XDSt0~{|^mcdZcL9JK&S8YMt-v*cUJ3=OJ5=S3qJnY)-BhyM8Dm%Gh5qkxS8mG_0Olb_TFWZ${)Y`tk!Pj=Axhb z_H$cj>{F%A8G z?`{6oZp`#&uZ922olXAB-+3MN&f4R0`p$K!F7cfI^ZBj+UF~-&|MqtCTSsruFa8_7 z|Eu&DJ?nN{0MA=@y|nd#$v+YOYV$9lUx>!-zJR*iPeku_TtL11-FZ>#>U}!m?{*jc z6(63{+I5{BMDKngdbgwMa=Yu z{L~A@|6dM0kNzSW?{_MP{?XI775#bl&!%69#`~$T_iNF6zY{&rzIXMtRqp*%^z)8B zt@Y(Yw@|tFYtehZ6ZU>8nr)B%OzV#Q*4ML7?EPu_j%d7J3!nSP(_5Q<_xYk(|6fj) z?Xb%iu9`)EQMt!S>FUW9Kh?F@!8e>rzmUB=t_pkX6}`tv>HNJ%&g$CB9c>%lSB zgJY}*$5;=Ju^t>_JvhdCu#bt;RPJLvIL3N#jP>9c>%lSBgJY}*$5;=Ju^t>_eJZ~$ z(F?~|PkD^>;27({G1h})tOv(f5B7E~P`Quw;27({G1h})tOv(f500@O9AiB=#(Hqr zi+RXUIP3^b*by9d1cx2LVMlP-5gc{|haJITN0m2owxyo4WjiMO?g9>bfx}+luopP& z1rB?G!(QO97dY&t@}}RZpFY!m$GS@7s;uEeuEhFGjgK z0LNMZIMxclu~q<%wE}Rg6@X){032%t;8-gF$65h6)(R57Hql%MjjgK07pIxjjgK0LNMZcxm*HjUrD0M-GC$BHy7r@)2<49neI+ zgH0oEqCD~)=p#3wJn|jrBew!aJ_SwWJ3Je?2{e&sfg^{4Ch`%UjeLjl$U7*He1~Tv zhk_>Z5pd)k(EGe-8uXD*Q6BjY^pTrT9{CRRk!OJ;pMoax9iENc1e(aRz>z~i6Zr_w zM!rLNU? z*~q!Tky|A`dN%TrRPVLWNB)(b75~V0s5f$xRM&NsM-D=H4BJZFadh#9UBZq<}@)2<49neR<13k}@TTveQ4)l?mQ11O&{3Fle*~q7$iF}7= zBR7F2@+@%VP|!p^!n2X@P#$>)<&p33Y~)bTL_PwJ90dBvcc71ait@;JppQI-^2m3f zk30(;`4lvf?@%7O6*%&yJa(ip<(1%OTz)`f{WBexTR)v$kk< z>S^E?9`Z!{6A$mu0zX#%tZm=36RwI|+nwz$5VpT<`@b;X!!tTzd#-KI3md-$#@Fui)1-(O$* z$F|vSa_7*}_ICdYp7Y1I6@8u0Pr9DA|Hn7_`aXW?^Ms+l@ZWyl-tq_Yr-66b=9ldk z@33_XeBAZ-wEz0re;0oAYgK#WAAd>M{YQ(xx4Y=dY1sYk2S3@~VDi<|pxN=7N89(^xNQrX1F!yd`z^oOt_97C*Zj79>_I!U zp!wuq?`yBJ(nm$}xo`Zq-TC}X(Y)~7pSC}K>BmHK={f(=-u(6Fi)MqBZ*KqgEptUP z>C#);pTByZXzcU0(TT=BZyTLx?DMwKiN@+_TYaLjdfHZ>Xsn*L)h8O0w{3EZ#^i0A z+@djg+a|YYtlbN&{i3mUFR=ED#@fBW+AkV>()xyIz}7eVXgk>YMjvfQe~Hhu#AjOY zL4Qe}R+6U`@}R%eu2yPSE82zrl73oAKdsOYpC>)HlAc?kXX;7zY9)KM!d}Rm?A}Ut zZ-w1yck-WB@}E}t5Bf{7Mg75Ji?I74d=|JL!e@c|A$%6NA0kiN{SbND?uW?Jc0Z(D zqCtQ72Q=sp|A5BzBO3IFpFxBE@H1#!&!Rzp_$xH%4}XQm?IjxYhu=ek{_uNf-0q@5 zfAk+{&>#H=8uuU3pg;N{H0Y0h2n{iW7){&F_ckL&Ljxv8J0JWx_~6gM2Y(KE=ocXm z{UYR{Ux)_%(VwZy`sjTlf8m&` zKoj<2K9h0SF3odVVCN|uwxc|3SMzD+ndl*G2M*gM{b=6kdJ}ei3Wx2W58Hvmb~T?m zFZk&5`lrR51nhH_X<(njw7|@Lm`j0u&Liw|Az_~*2{ZR$ZU?>3se~DqncI1}=8#~Y zo2i_7m?Ki|b2(w3;|a$c5*q5^d2q}j!PG;)OXUj^eH-k2gq^>z*DLJu2)mrZF^7Z? z^`J*^%pt+9hv1_*B;~F*mB$>Ca@VuUV-87q%pt*HuiOW}KI^^HA{Ti1%6m_X9O22o zyk=VD4$w#61iNpvz|l9s(Ko@-H^EI@9pAV*9GgPJ+=00Wc4tn(9A(m9U&EYNxdSvl z7Pp{bPQhFU8Xvn`(D;}x8s*DVUQZ4|5IXzR1knfjK<#FsEQ{4-In-=DyGnbI1jt0h1#@ z17_~)e9&X?L65;lxdSvlCk%O%Be*=u9iZ{KrD)I}b6jYAE~>iFA9Gpc@wuyLd`>GG zpX-Xo=fI+g+=04$&MX?AON%CQ2WZeAa#I)jOLkZ801fR<{?khSquilx*Yh-ofsgd3 zfT!4^+#&H<01f)X9<&`hV2>nEJIT|A276*xXuMsb@pg&E+a(&;k7!&!qKVuAKCWlc zxSmDhdKMqImuTExqH%kP#_cW|^hf_mb{7r$qaV^P^hZC0CUOVlF@IAo01a3%+GtQE zF&Y~8=iq}s2Os=7juak%NoI`uE+(DhkEGG&_wP4P2>X5c>EDfkx$FgY zJp>=wi*nbS%EMlihrPfir=ACgy})6wRIc_qeVcOUBOLak-0M|&*o*S87dY$%4tsg| z0`%zgvKKh)1$Mnfy|NeOVJ~pl3%n?MVaKrD!Z_?mdDsygb_9nV!C^;m*by9d1cx2L zVMi~Q9i3kG0K48=;IJb&>C^n97@e=W!C>2z!CUUf{47IPB%+O}{gp zxc{pU4yWJQS=KgsM2CkSeMS4t@BDYg$w&6PsQvjJ7#0U;Xd3I6lJo+gk4TymtUATi5|UOv^VI{gRtvIn0nBo*NZ-d zO&-0k%-eHNR zFPFW*u7}_wdr?k3*a;l=0*Af8u7Al%J?N40uou|N7bJS&uovadzYX?!g~MKyyPPTy zdr=2)*-fB|i}kJJvj# zeuo~yj^MCk(vSLA*pc$EBRK2`4m*Og9b-;{&%`_g9PCH;sd`WNNVzrfMIz|p_J(Z4uz68#Gt{R{R%AGNJA%WG;B3d(gTtn=X9|uzQ?T#l zwZO4w3iiD}mB*eb<-S*_^4K$_ocSbsnPA^@6!!JK;G;cL=ii*WGhM}=DLRS129Ev( zj{XIX{soTy1&;m&j{XIX{soTy1&;pZEPU(N9_sMRvvt`u!qD;z|bJP?tzgFHKpHIyhL7idOv-T1Q3-B-OcXsTm2+*PgpD^e{xg&E4*#K? zI>6A|AJM^wIw*&~*D;AQKBL@zDt~4YJfe=8_spPC9S|c+qAwDkGVw1{y(M+iu1&U?`muYD6TWS?cTTlmVJn+z zp9vf7RC{JF{Ef#{<0Wjor&0&yRzKxaz?7>Fr>73dW_+jv41a#XDzneP&{78&9(5fv zD|k}}< z(i`=vTxCz`d0x{0T$5ik@E*!`Db6tV$)?2bG)6G?shs$o#t6l0e1Q0!#)v^<9D0m+ zoyG|0V~l`Lj1d~=pl5tYV+8UToyG{pK4EyIF+$@HG}M{O8T*2M&{&iBGxkY_x~*M# z$|UEYG49Sy*0{jiHE2vsdMNW4n)JrlXPnSeuQ`2VO8^y zrNi&o=+BC+|MlG~2Ch8yap7Gz-p>C1NZ9>F`Uvl<^rD+WMJyTFiL7 z124+qJ!{oF=DM5~Z?EW&a-%Q6&>J6N_^kBB^Mp5=dRyo3FKP>ady}trW*mQ~aA)V! zIuFkMx$yI+?%#ROm!1%w`tZ7)Dt1^j;@U?CU~`|&@E=IBpd*gw>>iDn?zo67rBU7duBM3bNGr1C+} zCK)o#pl4HCa$TMLY|=?5$=u1$CfyGCZ1RC2pH05e$@S)Eb6uG})8uk|(fWYmbAu;> z9-f-}r8(i4%+-nA;S*`DJEn8>sq?-!FU{eXnYp^@k~wnB7rK3pIYVkMc2r*^&#>4W z{c=$5lX4S27Y(#2HyM;$Eo4U<^SU{gu-92q4xf~pP_N3Vld%FC`yuBNrq1k#(MH;v z%CTe6YaFQAOd6E?q$sqM4d?w@Te$A$ zGc@)?&LvEp$u6ot+E$YevSnG9@$YDqk0cIt+ef0q_l zXdU~e_6`f%e4n{}>FbTcG&pf127pXumb-iZxQ{lX1z~+oA2Y7tEfouCrh>~(?gDF=SK!!OTL z#%Ew?c?Jv*c!A+P|FOr<2UDk&_eZ(W7eQ})gyCcSh2d|%!qjP>2~(%lAxxcChcIg}RD+6#Th+XWwC>P&j0UX@cP zZLaz3S0w!x$u9k2FVp4Zm9Af_T6@hmmB0Airc>6xW#{V2*X&fT{qa4fTyVtetIMC* zxLj$M{ij&H)o#bHP|kns{auW&Y`@_?Du46WUu-(uQ}}gWD-eC$uJG+TGeO^022(`}cJ>AcIoO!eZIAy1j)ER+1@mdpKms<(^sj<*YXVd_l! zfq&)gQrp0)^C>+er)a1%*`)~kVz00-IP43)Yu>umW?R3ZeDJNO4;=O2s=@=W-ly}j z$*-ukT4&pG-l;ovo`3rvI?!|uy|lCE@|&yts5f5LxpCKTs{DQ1J5 zth4GYm9KWdiq*X7cXi-%d27S!hS#m3^6lQXR(1EyC#d{i-?@FY*@2tSf&cpd@#1Rg z1J?{d|LU>@eL*?&R^A`w#$V;|H$DaB@G*H*jyzVc%Bk1nS2^;VoF(+gY3(iHPkXIh zDyLnh6P2SA(}T*%2adfAq+6=OsQxqAyatMdDv1Ig2Duk=j)z`OBn-GPSq7 z^n({nb-k5IKhSqvZ_cFsHSj zk&MU9v*WA7r}Ul9gs`8Yc>-(CKEFY%k)G9=6KzXpT{zn#zwtUXzo1Um#G&Ur%QHQz zv(}w2xFGElSp6-|;vj zSNA(=+yA)3s&yW_QT;sD$tkCd&%n2T^UeBB&BAzt)8DA_JvLlx&g#qWF1-0qPMh=R zLtY_l`=N9C`!^Lnanl#f<(Ki4GCl)C%QIkjzzbaSrpB2S^;`MmC^vdx=#7sse2o7T zXy9+Z!qjP>2~(#%BTSuEhcIWRBZIzkwDM&aiDsS0UfcQO zwmXYv{gu{Z??L-AoMl^gy|YEL+XElz@EQIGEuZ0+(DE7Wsc9eSKtr8=9#7w;q7G=N z6Ir1_c0U)V?+YU1pqdBuwJim6>i(odXkL_bB+Pm%P@o=E7qG~G$&nzm~%ljW&> zv}CU$**(r%V)xQ?CqBrY{6}X%u@`45O?Tlx8tbsT`ATWuq1)X3u)JsOFHUtogirW$ zoc|0y;m^n;8g!ZZ1@gcfKQy_z{fl;WsEf0osehrL%KZ@ih=%>d)KAf~XwYTq@90@| zp-X(dZr3Am-Zktc8gxmYfd*ar`B?fib{7r0OmPhVF&_0h15zC0`(O6+)cDunS|g1f z8a<4T4?NYkmc`u7zxSm4g1moO%)#jijqN5*-d(SmV6~a@OHhMrEi`&)^zhvCfn~A( zFKuk=`n_`Y`hQQ&P0S~naw(Uf|_`tI31NGR+es1hzv7Z~ctF^m(9+>^y z*q>%UH})NU-(2|xd)u+!MxGe^-;Al8p+=8huC;Tg7j`}xd!4_q*BfIp@(8<}!Y;os zd3cQB)F1gOa#3GxOP%W$rX8_AP5Y=18un1_k1+b6KFZM(^?{i`#(M+3yr9(Sg`E$) z*yHc+*LuAww~utr92%EXGr*As7`pZqP5&qyn$K{L}11x{EbIjc}H070Ju~s(Tb=|zvSGw;S zoBd$11#Qe@bo-3Al#?f~syW_U?mDRa-_3rgxnkc|N0d(c~q49yn2O1w}e4z1x#s?Z7Xndged?242&*#bWIdijH_xyQ2m!8k7=X30N&n};P zCr64q9rHQ)e11NktIy}{^I0;NM|)E)r*J;cZ+nY+uMs|%+sOYTSL2*Ma!_J?n(sB3 z9k{_5guO0duS<6Ex`b(06KA@9EB|pD zR(P8Gt+4y8uzl3+NA9;OcfS>0R=+=mUho_K&F#&4u#dX>$$HEB%z8HeeAeSk)9;$` zeQ9Gg{h%4&yKz!6!TY)!F<#b=-L0^b0$?-tqzI zaOS6e-#P1@2MF)^o4>8@m|wrQH-naVp?k^N>-7(+3D^u$~muLFS zC-cwsW_hyA!@<;l*uFo$P--$9-!IP3p1u5stL@)+qI7a@=a_1}FR%18{p9jYAMFeN z_1~fGV11|ied>(i6SA3qcHgb!YfuFoeQl})k1XaqRhO@oiD%A*tqRu4RGwp6t~bk* z<;?OUtF=vhhKHZ(r#u(^DC^4mRLDH)>(99^j}_9t$G5Nr^-BhiZ^9nmg!w#l=y6!( zS^lNd4H~Tb(=WfU;oQ*kHRbwqL;puiTXSyM<+dAFoE!GK>X1k0gdN|$>TSd(+4q-U z`23u(`^Nvh_nh#DA8m8b`L*t6mKV+2`ja8Em2VbpF?!zlr8XL$$KRI+_^-gvj zlqS!V(4omWC3I`@t54Y4^i*qCly@k1`VREYr-G03ui)?XR@CeARLJ9UR>R_ulCGB#N!HFm7u z$=2(3tnG)zW|j?Z^w9Xg==wl2u1#vjHGc5CcW%=65!Ss0CA3i-Ed8p}e zN^Sqfb|YOwc(!bZU()aBe+_Q*(D=aU`T*k$9MS8tw+{K4W*xFV`&vxw_2gyGj@I9r ze67jR8Xp)VA87KmN$k^&Xy5SJn)743CU+aX{onDlV>3S=-T8T=&qklw2Y$Q!&K18m zedDaTzuI+2;cbrm)4;1X*h+Zwc^~e4;HHg)f4lrOooSb>EPU(N9_sMRvvt`u!qD;z z|bJP?tzgFHKpHIyhL7#c>&DyJyAA#<{9oU_V!)!A&THA(G+Wo4Sp?5Nt=baq?D=Ttr28M}r~Id9 z{-N{YRn`~2VUH)l1C)b}Mi?42?Jo}u1_k8II;i(U=+j(&A z&xM~qb^p$c7ze|fNbVHv^?Hv}r;;?%= z>zsU$>f3(9yM^EU_0JB>eATywUw6nlo!zz^5WeED{W_QIb%F3H2Y$N4FV9lOXJBY~ z1`H2)f#E&>vB%E`Q>T^pN4e1#L2rD7;bZ)T;cvgf)M=jyQ>WD-Or2JTFm+lT!pHt} z$9bu|KhYP7Pm%Z+soo;VQzSWyB!98xavzxL?V>!|3w_7i1s`GROnReUl~X5euKDa& zB>fl3F8yII)8*uqu3xKKd(AhMzxdszQ`Wy_=jzGV>{PD(@ja$oaK!7Y%b(b|Txpm6 zr&zt!ZpW`s&VTIvU5u}6zu`VAfAiO0Y&zUi_;rVzWxDMbrk+do+FbaQ16Qf|g%4$X z28LG87={PDD2KPzHwR4pR$fH8(F;S5je?KyFTwD)Ut!g`Wxp_W+B3q`X>|xwr_~{R z>`$*WTX)M%hh2KpZI_Sfyvx5#_2QQyPnqN_llP-59f935` z+rX;xDLo^nXs9#Ur3m|CudpvT>MS(Ys2b>*R7%Q?cTOlb@$CDsQh2wxqY?Sft$~P|N8&&;%e#x*9<`a z>aqoWK{@nR-XG=0U*+&OJ_Y6QF?m#uJXWvDsn_IJIr5vFCG^N??JeO?d#zn6r(LEK zm7^2WgUZoED(~OxygrqG^vHAPB|b%>FH*fl;$I{=izH8x+Epg`%cO@gwYR+VgBMJ7 zy_HEn(05#Kl!rdcWEc2^{>x;?BH61FK?m*9-G|~_ zR+RI-8?e_|g5ksWbinZE`#WIj^tlWFt@yqVfI2xZ2d?X!Da@I(RNnpW7j-5+W#Vr+ zcDG)5h!3<$&N9i*yL0UPEk83UkM=?@>@rqRz$fXAdR0!H_L;Dem97igWw~wFE~clM zqA^|0TNI{_MBmua^x?KG(M_+}5t+u?Uer1%5}b%a-$c9 z-uMW^$M{cy9{%<#Or7?bFm>89!qjQJgsHRs{&C&LR6aS;PfmO$C;n4Xy;G7rQ<9uh zlKfMyzkSP9y1I5q|G&-JCReEI&0m@E|Z62-xGd$uzcXg z-6ylZp!Ipy_*eVg4f26a*Zai4!{z>>x%;*+vmYTE*8Vs7+iOMhgB4fooOWR zBZKx+R=(^a(X8{>Yde43c4yJ7ztVcXr&8~Cth?UXqS@_%k97D9|ARK|BUF4wdurN8 zI?zyO+IO($UMm{vL{?~!J?&Fe$O<21r_IoygS4+v(Pn7S0bU3V{|D!OLK&YKpCa+; z?)w;@{@`Qsh{om7z7M)Ic?xK1T|OcjZ)?=+ZtD4Z5^CMC0}n4Z5^CM1w9(R?)cKMdNlC4Z1YliN^g$H10p5ab1eW^(Pvz zwL>)E#E1Q$;L~q52tNHu9`=typ2Bn&@)W6EgZ95tyNaYA_NT;$J+Y*pBI%j^tk83r z^lWu@?PWZk+DA+FDw5p??XM-f7s-DH?YkxavH4Qh56e3@Sz~ke!}6ZBzc|(X5I*70 zgZAl?KO>K5&}HfuW$G8SOEl;*^)Itww|}9Z%KdQAeqZXR=vg%AGVcS{efTi>EWQpO zbeZ=D@%6f0uPx{^(4fl{f3Uk~&}E8agZ2|s9JBote(E^i;6@LP4~(`CJjHLUbAjp8 z&$l@bKjW7REUP)V>2hk0i;eBHJ~JWKPiot#A1FsvmzY$q88x`kL*oO_B_DX|y7ou|~|_SUcu(r_;J^ta-sN*240;!ZNmTr2Fo&v6jJoTY0(5 zCQMsn-Pzlsa&M!sw_VuVD(t#a-tY1Y=XMRoNKwyw#zBUK-<2oXXsfkZ*xEunqK&M9 z3iH?6EX?Olr~QV|mC4WEgJ|qLoYs_RUB!aBf$|*|*1D2FVfa(zH4SQLXHdKa7_P!>07HT8oipsN2j89irS%+D-S?Adn#&1yUelEopw_U_f#sy)w zU4^CHcEWBuVYi*I+fF#g$@&hm?wqDOCve*ZA8aS=wi9;S3H#^5Zac~8wiABU7Q0mU z-?qJIet7nJ)lX*aDSUJJi_Vu0{Ac0SE5%b-w?zV}$KMRR5m09V>j# z+_x4hzVY9M5By-K*yqdd6+ZrNRxH1@{(i!zP1>^j(Cc3%{Ks{7FRy*{CBk>U|6S$H zKl_8^IeNbjls~@mV&U)qU%r>t#Gb4%ai5I^5=Ht_GUd~{bapmeP%sp z{b##md*!h#Xm+k5w8Ut291VX?(2y z?d;EAK)cM2l&f84N9cvkj_?sSJHlUWG&@qSu-OrLgw2k~DQtE`eqpmC?GiRS(q3V+ zBYF@vJE9+9vm<&Fc6|!JaIL+|Isa70)wlot;PQWVt>fye-tytHvtAunAGq_F^6`yV zkj&BVX=BD?9dnwwba$RPlKgJa{4L_ojAM>2clzrV9W1)sa)*~U{c4`@i|;s~eC3~> z5Ps;6H_6GBvcF|N%>J4EHv4n-^X&h*U*!Ih`%&&+x!;+8R##v34m(@h z?T>1U(+fKvVdt+ldcDFfkFd)r?D7kHyM(>H!mbBl*N?F4O*qFl?~f|?{wUeJKMH$) z6s8Z_{+HUgFs9x7jCJ3%`fbf%S)327YO%bV1CIF`+N7B;)Y^;p#{%1Ve-!rqDD3^Q zG~bc0Fg}{^2wOa_%y)z>o_EZ5ge{(T%y)z>o}2&FZL8zJ)3N)G=*f-AUnwJJj=b0Y z+l@!$*yO>`kbB!7Vdg{34Jl_n#GDa~Us~O2GyX#zQBECT=t z!b^OT-l$jQlu-vX_QUrhgyBIQ6xO_J+f91WZzr4YsNCXtVZI}5@w_nK5w>_G*$}QU2f8z9O05v*7UZ%pXk_Ug@Hv%d4-tziT@y zFOY|FqZfwW_z1(t_?OVYpO^ME)^**6)7%R{qD~wFX80#V-kyO9Gj~un^+{jB@R8)SX9qRYCD2c zTZBV~U{#n`DZTRh={+s-KP=8PTLUl40;RnRl7$=Ci zF|OE0qqb&W=QXw0MZNEv{`kO~T6Mhp#`FGr;Ov8I{N0z_F!0A8*Z9)^Ibq<257u#T z!}qN@u;E=bt~u56Put|>1KU@1`BzW>@<99VYW%JPzCZA$xiz2T7CbcYk$q~MpB>+} z>uxOD51KT|+Fe=uwN7B|uB`pS*6zyMFKq3uto_2)?#kLPOsoifTDvQ2zsjxMm9<~k z+Fe=ug{|F{wLhLM>+klA{e0PEv~jbx(NOq}tG>Ly&u#aC6TaMkzuWGiH-EqX-`#dM zzv_|xkNkaYyQ^RDX#ZWWt?^MO-rfJ=Gi&_d6BqUWX5-rK&s%fP{_oDO@$K8++jql5 zHO?|1*Ldk6*M+|)yO+uCWwLvj>|Q3jcV))klikZ?_cGbN47=NYr^Wm_PMOb-`5ZrV zo9oTk?XEcFb{BTL3%lKg-R{C}cVV}?u-jeO?Jk__9nZFByJw8QTl)uy1NghOUl@P4 z_6y_h)_!69-P$jVzgzo-@po&#F#c}s7slVM{nx`En@6l*UO~L0lsR_H(S7bMT`>;E z9G$;0F4`mAIl7M#qWAduG(F$@wnwLizj>S&jmLRmkMqJF=Y>7a3uoJToL9NWd0~(9 z!XD?J_Uw4-A=j0$*}Y13uae!XWcMoBy-IeklHIFh_bS=FddlutdC~LBXTQ826Ohnk zDeJ!tZuHRjK;r|?rVl)ubuTFn_G&Db&NSZEzT3#z=%Mj}=Z+85Eq(Uql*rNe-E+t9 z8e2EEZhWBef${Z$ydIU;zVe!w*`&KxmehXjv7erUWSab}xAAFpWf`(;S!Qpe)eI zy|DACpmzSk)Pt{3Za>H)>~acc8#Vo|YrAe=&V3wRCflLE62&(CuJ+aJ!`Zj9&$~}b zZ|;-Ax$opYmG=`f&NTVi%rn=OWyrE+nVWuB#~+UqvP<^)+!svG-9ADbLXTE9=$r%p zZ^k<*p&NVMCo4+bCxzW7h219=+ubLH(PcB<)n_+NeNWS2)~$Ws)%j549X42$e>UY$ zpQBDpos4hZQtOC+n|j?})JGfK_(S6Z6VV5-+C-GQk$HIiZCM%T<)>xc<_0%H%~y!m zQ6A$0^%az-{u}&N?)8??xIDrxr?AT}?ENmv>32cj9Y>O%(=Pg*Xi~pG9xLmPQmgj2r@`Bk3Bf@QUhK9^Q|lYe5n@K1C_UlvV@E$9}V zO1CMtU^_jJp4|^+BmQr5Y5X(FWz!T}upRZu2U2WNJ>fGhPX!;BQ`qGf_I~#?JRWUq zPyfoew6VzxCRSdM$AXL-J5DS+HhICs$_w&1o^fNxiDgHNlaZ%K9#PsHK=VH45a2Xd zVO}|+JSeSaYF-HcG*=n5Jjmu?nzO^7c`ox>Z&%0a6J}0S&ug^~Hln;Wt!GM)-Y)48 zT-Q_Qi9SDPj)y*}H}s4=!fE~-@~hm&IITWe4sUGilv@7}@?TUU!4iff?yfWmephFMzSDpuZe%j4j z(|Ts~yPz+iPyH_Vt336)kjMUZ*J*`4ZU~$H=J7ed88>$9j&~Enj&85Y>?nUp;{v(4 z%DvwS`*zS03v&VRc9|j*`=P&H_me8a)pz(zIC{KBJ zbKDXwE7LrRIIrj72|w>&dZrogy6eFBLyWVb=a^@rKgMO1(~rY0d5jy3f6hFjay!Pn zI{2vE7~Q6HFgQy&<8P#+jQQ6CunedPWhoR-SfUZ>xJa_1xL{Dr+< zVV6hPg=EVZjJoTjr=Z-{EiNxOhBfkTrrmN2#TltvZwGnqRS-Zyceebku zwEf{@D^Kk|=g{}a$2MK>6aB0G?gshT3(vf{|LPa5A|E?o!{7G*!#>-{$5vls<>EIt zyjDK8_l=trzc_A&eC*(2+v4Fb9U&jP{`m9zzy9R|#PbI$u2^jHx7Uj27tVN1vBta= z#Per|yswyi_+;^1_y0~RUh&Oo;`xWSe6cuWvwg+$OJBISc-;YqiszoIJk~#Jg?|*! zbsl?dvGQdXiRZn$oKk#kpWk=r3lBZ{)#AQcFBZ=gZn>p6d-68odBpR7UR=Gy?&A5x zp?@eoJ!xO@+~vaci*+}7g?R4vz({7U01p2n{Y4{YX5$ zzl*2$ck%T8E}q`s#nbz{czS;qPw(&I>2XOsJuZo-$E6Y*d0Y}tk4xg|aY;NqE{Uhd zPx18lDV`ob#na=bczXO4PmiDC>G4xMJz(9^?1$Bp&1U@MPS;@8QX~f#1WEaRa}H zC*uZw4^PGo{2rc+8~8mu88`5Icrw1>_wZzV!|&nA_=exZlkp9|hbQA3eh*K^H~b!+ zjBofoJQ;`adw4Pq@OyYNU%>C-$$SC7hbQxz56&&8!jpOKJ!^k)Dmn{zuSHDB$8*e*-85BBz<<0KE>1ZDV}b3@pQY3r`ugT-R|P)b{9{#yLh_Y#nb(>L)+ay z#nb&$Jl#LV)BRIC-9IbZ?*3WPcIGwkg{Su;@$`Nqp5Bit+RnTNzO>!@k$8GP5>M~% z;_3ZeJiWh*r}ua9^!_fM-rvR3`@490ToO-@OXBHqslrCgYw&yI^tdFR9+$+^il@g<@$~p9o*qBNllW};m*yoof5~}`5p?sNoCoFnDCbQ%pUQbw z)I*J4uJIwiUoO9QF6VbS?{j%H&g48X=a1A8c_qm6bhVTDocWKik88p{t_l0NChX&y zu#an+1NyjDq&0yutre7M4WUeH3uRh!DAQU*nbs)EqF&P=_cuP>HH|1I_YZpV_uwP! z{Dr+k^%YZ{WD zdTdSOMbzu%YOm8@=Ia#uUFXDG=yDFVV9pZnP^uRkG2osV^NRi`xPbTpS+7w z*#29Ye+!#GckfvXg4~?BP~o{b^Q$uDl4Z&z%alu&DVHo$F3H*nxw&|zoVQFlZ|S)? zbGFiRbLMQN=jP1W%9Qi6#zSr{o+&pkQ*Lf{@8;&#?rv^grrg}@-p$R;?%mwHa5ekdwJk$jMwN^eLXMPsZ-hCv%L@Cv&0Dr+B(P#nbgEo^E&X zbi0eE+g&`}?&9fo7f-jlc)H!i6MtupMcds!#nb&$Jl#LV)BRIC-9MRQgnu%}h<+rV z-jBr7`;mBhKVse@fA=|C^ds@~ek7jW-^J7WyLftk7f2XOsJ${O($4~L}_$i(qKP9KfPx18lDV`ob#gmv$ zu9D_3;z>EV3UY$URnRAxT!prS$yKlsm|O)LrMV?>p4>d-BsUK^$<0Gfa`TXr+&tt| zP6f|22QJebSZjOaey-1$1EWuJ^Ux=`dFWHQA3W1s-TJ$7bIFcly6^RPR)xp=0z zI&oe(s{3c;6lKaOi1Xy;;h*H@;+b*^{8PC!`b;?mabCHK_akz1$(eE=;=FQxY=pnV z7aOJAhkitEE*qsBjW|zkE}khzBhFW}AD$^kBhFinsx?^RJh^$qC9R<#XUZjsOIkzm zxTIVKo}QaWT+$i}ZBMx*@l$I(@bug~;%DT%#80jDz|(Vc@$}q0;wQPei(|W`~u|k-24LUp4JdTPSy~J^Rb2ya>jTRYY4>o zSVJJr#~K20KGr%ypM}TySnD9p$680|vp~+Y))D$Fkkjq1vDob{o^JPow!7VnWOwm& zyBDHS?iy}y^W-MedX#Q9i@i~cU29+$+^*H#juZ=%?01qlcx}LwC)2%+JOw6gN7^+Qj)?HMW{6 z%CrX9y)Vqy(nXWU=#1UwqRDH9&3HXoQ*5ih-Jw@CQ_P8Nz>t@_9EIi!UXmM%|QusVM)_J=35j&p}8s{&Z zeoV%)g?v)ETh8fR z-U{Kf&*#2iA9ec(`d|$LdiP0T{vWoh@xuSF?OK1<;6@LP4~)zQYW?LtnER&j?)KT- zmvbM_eLu&9h1Yo&iXjmjn{ll+V0R4im>;o`aalNzW!dJ->R6E5yDW{}we9$~$=BSE z%SI=SKa7?S-2Tlw$8~P}(PJ*Re50GMjoIAz>Z|T2UwhiPkjD!XqdSgxP9b{FHH19} z5oQj~^Dck)yYtlZPdDyp-$xkVT&A&IcMV}gdFZoYJA9@7Y3AgO9vUAQ3m>@sn{Q@p zQ|!+8zSm4H-h5e|C;a24UnyRH=i#E+@$p|3<@_1KvYheO9fa4s zY_IZ)!`2W!X^(@-&mME1#)ISk`-t*{!%q?3dee`VkKOnC0oru$?Z=is|JCGv@TqtH zdwKGm(+lt}?|ff*%PH3gdrnwVo^cP#NxMVNF1EH*(H3iC6>YS(SJ8IUNfkOVT~(ng z(_s}lG~HIAThnxAu0SDmnFw)GD$@8kP@$coN;O3rNSjD5X8 zdiHe$VRY|wtUGttE`2>hGzVSx;_mkrJr7j5&wGLo^B!TJ_XzvEN7z2E7G>)mkqsF` z&f(xiwq>X`8gKg!&L z#Hj3t<^DL5I5Uc}EwaCO>{Qzq!i)6V+^&q#-O|Jvf0jC!C-7I;YF&vC8BE}8}XP+4f9!a0w@a${M z&b=8=MoYHrR~e7iIOyw)>KDXg<11Y2b*tz{-StPO@8Bat*}X?(>&A-g|BLUN+eCXg z2QNK1y|D9nmg2_v$d+|A96X#@k!g%)W&h`QNdFlQ&B)@$tvwt!Mn|?BD>ClE@qLm0 z(1UW)@567qc=7S1Z`|X_%{zTu@2aAI^@41}i6NN=xu1=B$Z^wmtA729`W>MM|Hqcq zL9yT>oQW6r=aTOX@(!~KDcrU)8) zwuonqXBj-Lt}^N}8Oo3$>m=h|lQYMbjC-*EVjtPa^x4HdC})}E?BZVN%h|q7oO!x0 zWxpBeYN_v}DUZmht%H6f4Gf-Glkg5@qYgiacJ}nh$$_%GZ2PP}uhh zwMOK7h*~@Hy+!3azUL_Hdy&*J$@eIQeeY7(_cVoluT$7!EPJ3ejlM%suaEuP*&osS zHsRT8a%LS42h)aT-lCiiJ6C8U>#do$oT7fztkXXAet{ikHThBQBg4V;tFeqTd7m+3 z*26|)zh-gs*x3*M-1aqxw{Gvc(wNdCvJvwnkIB}>*52-S%obi>y?LiAqrFRH<5!32WQ{Qcs%;-cMfk^zSNuXWEiq7(iXkYXR{qA zN<6Xn$@jhK50jR5pZDtf=aYBq+0n{Fa}4Pb*=V2InB(wbaFytnh|&8*i5tt}JfxS; zv*j4lYjO_d|2;VFFR~Bzpq#`Qeq()LNqCX%%JDN}_>M-L@ii;z=Db#OZr}7U%XXE8pK9>+4D$a~#ZZLhbGi^P)H|H&*C|hZ+$!|}`lkv!Rmc@BX6F0^` zZZ!GMBI5~hI^xU{G4ZIGhfJFEEPl^%kv3}L$uo;5J(x!<(!MAJ@YO*zP11Glpby>`7dTpI^s6CxtlXEQM z$<_CNtB3b@MoqS!iYLBit8pshk(_gQ@Q{nKqj-+idW-v;c=m#9`AlraJ$Q~CojuLI zJt$|HT^5I^KC!-}>_OXn8Z$kDO$@_d3x85>o(sS$k#h=^llj9yY zW^C|k-W4M|E-r42mu$m{6`7`v7vmo{Y#pijKAYUtBzyvB4Gg z{#ENkw5f2md&U#7E!d*ANo|)U;oRQg;F@0@ABKaSX9aD>O&(Og<7Kq+pmAAO zx%|Yfv7>+AQ0tZ+Cxx?pGwu=D=ojIKU2OYMJ^LPm9cIn!uCer*oMzvy4u^yBo27|O z*?&fYn>aJNai#~?G3e9Lue-PhTcS=@ZMS#No6thbETp36{icqD5#c<_)jd-z=3=*X61NX9*wUl3mvWAnJvgK{o1&NO*YeV3W7 zw=eQew4vh0P~{3IOR*N5eP$%MS#KHL^_FJd^33Kfi;E}YbtWy37tMLOr;km;i8D<+ znTYY^fH;r3#P26&9~hrlw?x^NdVbQxljp`d?SqGWt%viS(UC2WSs9N{-(2EYzsMY? zM`T;-xY6wIOq{sU%tJ#?JC zH|S70=>^&HoFwD%nFGA4hx3{x%C<=V@3noCY}5SRjjK?RQJlFD_eItIBreA#*z}IPoz3&jGM(zIe;om1XKC%rJABHL)>$s8M&yz9s z8S8s_T6b(~=Y)p${jcmBJtA9WqRUrJwk|e*Ud;D~&W-jiab0vIbFFO0H_X0;_j@4U zV&B_#^G@R(Jv9>H{n0S!P)mRwmh1< z8mX^&@BMwh*Zr7d_ul*Q>C4%^6D7`ATz$s(^-SMv)ZW3k$bQ!&vX$0F`EA}Sy9~Zp z*7E4e?(Nll+wSeHPQG)xu*IV4=f9e)@B8~*qKZ*=Z*O(N;iq))2fMeo`s^|H3EREB z)fI=Wp?Gfh_Et0Ax`VLY+gt5%;dEhpM|Y>3KSS8xr6BBUs=|X~$cf##O0UT|)Ob3Q zK6~~37m#0<=ytU7O_LM7if50=hAfh2C><_T-jzSMWhjj9Mq_?59y!H#4u7%PyEpTl zVaT>fyDTo>8LxLi=NNM3yC=qbs+)Z08Q+)M#1n#ujT^)0vy0SKkHosAjwj8%#zW7^ zM>5t=-|Q+|m+j4Y$SBIT$iA@9+#}O0(m$7lc}Vl#`$?0Uyry1@8_NHi`AIWB@iR8W z!Pt)zcApVm-1jVIKR7$~JC?ZLm;G=&<|o6DZISW6*VZL+?(>G(&#m>7>F3|nyYrUO zldZJw$8S%s$2R*r^%|+IotBS{`Tow85m(1;A35KpzPL4?@ygNic#-i)@}R5l*F7)l zYrVG~J8H5`hmKkC8x$r5F&(zwvYi|d;+Hh5{QKaX47$a9ijkS)iGjGKI? z$#+JY?=M%^OyfqZaI&nyXz;TCtFun)_;eCtEA^8V&cNmoIim! z?n=mbIPX*+$r$>ZowmC;`rYz?yRr&*u9CNohcCO`1h(*?%%f(_U~Z{`}ebi{d-&TLqGQ@?BDZRnmb-A6NTSF zeRCqpob8@5ZHw`1ICvpnLf@gECE~^R(`_b5JQ*K3vyDa)PsaKkS-mD_?wg~P_nF@g z`HqW8&+x9Li6UpVZ^pxk6`97KU1EF~ie~X~qi@{fMt;Xmmbn+?%r+WX+_=^B+WYg6 z4bL7OIdgw(<{|fu+1x4nXT~{J3-dR)~G`ke` z_x1>n=iO(Eu{*Lzo?eqV+r5c1%XXaUul4BB4?I4um*t!& zXW%{l$TxafX7isR*Imc!dzabY@^>+EAM6D=hZ93GO_qO{c!@D2`&HK4c*K+M9Nx0| z{qXjqCyJbw?>ysow_bh!eDWRj@zI+9FXSg(f9N$id!avO|8L?(GY=W*cP*D@zSPTO z`cN^Xmu2qdb8bV$mR^%N&pn2N7xI(Jp3zvgnDXv;WHd{}IX+uHJ0afHKT%{J$$Vh? zW@p+uV(-se#zM|!-m)wGoS!9rN4_R&)=&IguJ-HAe>krzJX8$KF=RaQvZa}~j3jO} z`A%(j|6Z+pfb%=eI!X6Crx9B$bo6H2XyzgHT^n|0yNo+Hp27R&x^ur?&M6j}$4&^D zoB2sIKk<2mVyVwJI?Tlu{(jKXjQe@6vaHTe#`-R;tizGaqsBtc#l?+h`_7achkHTJ zCa-yB?*&>`(hHF`+I%0- zl(E(7M-+2UJyJTc?>`o|9QPh!`(9-E?)~=_w(m=p@qI~OmsWX>C(ZoixjR3ZvB4Gg z9;FS}``sJr`G=l-S^2Je zrU~D>%WCBg_w6nG);HW)yz6C$2tRt<@x{ZteOUPA1Gn|R_oj~uul1V~1}^*HvBFf*vMv zyKHT6ZurS)t*b094%@uJ>f;B!)p$H*$aY*@{?eR38GQc4^;TiI;b7>NCPo-f`dRQ_ zD%@+|{m*mb9cIm3=V6T^BEf`dH;;?P~Yp!wjP)HK=U42&0v-^hcUY?RZf)YdpVvAwU*m!GUqvG zlOIjM{HTdDV;*Ok{AgEVG(SuAp0|t`lsjv*Nj6*q<|U)mUw z=@%DIn*E@m_k%{3M|^F9#;lNY*?M|ZuN}fTaFbO4;3GVD$j9XX>k)b znt8~xb@xz?C(ZiFvb}!NYkMf!_lEk;a<9q!|Jl0=@TiidJHg!o!95AC37+Z39RdU= z!65_-79bG89d?n$U4pwqrW=>w?zXtQ+h0|EhrRpW?%Ub7Oa6t|d|%+uQ@5q+bl2%S zeQ(S;;;-ly{rgPSb68*RzC`K&N)MPh89n;yzw4)&hi3eH`sDY@|EyLq+y7_X($MaI z{C(@B(+qpUMm=kA02zF8&LDzHsB8*3W;!JT=b?y`KDY^@)D3?61EMT6b|F?rU&vTmCMc z|25W)uhCDq$0hfSSx@`oA5QdPt<5*_=UBi&NN{Q2kacm7O2^?v8?-J|^{eWKrA{Uz_v8i;dAuP5Kvdh*xy z3v1zi_CH^rRL}nR_wzrk8~VK{dfh<1ZmgI5d)(J(9rE|;kbm0VLGO3I+$TZp!*MP< zau3#QWAUk>MsXzs)LA`a(^2*ddz z4(E&LOc9(f;*T%9qO(TEIZ}rGf%8Qi&KD7e^F8)=5F}>tKM6i;ZhlIh8fB0QSbjJ~6i+^;yzKwY4dH4IjTk5augY>+k z`}p`Q{9k%UtIl^{U)O2fQl9dup_2)l?>YP@-J-Hx^yWLW=8R5_WNyn5Y~FAFe`(0* z?E|vmmwoIXV|^b$&7a@)nVIL&u||E%_W>N4k7k?b)aT|nMrR)kZgKT5{{72+li$MT ze*SOp?YHM0_{P4!M4$Z%+vf=I=d0d-Ft6KYjQxqOJ}BP&di<&k|Ni%Kb3gw#^4%}< zDLU7a=$M;&-=X&%xc@iiyS~o`j?nY&zuzZireS_Yt^WVGIr3LHKLE(^`EW z8ZCTrv&Rd3`32)R?d3X-|NTBDy5gwgMf;<_{4V+EikEq=nX!)Jw-rYnuWu_}=DB9Z zI*#8~9Cf_Dt$3N|ni=ajep_+W@%pynWu9whtmF7?#ZkxW+lrTYu9>lp)VQ#d9InUj^no# zM;)(kD_-WgX2v>>-&P!TyuPh?ndh1r>o|T}an$kpw&G=;Yi6wD_-(~e$LrgQmwB$4 zv5w=n6-OPfZ!2Erxn{;Xj^9=sb-ccgXVzdfaZYa zfaZYafaZYafabve9|yjs@4sf<=rLXY{~vF(|CR5xAG9Ad2Q&vX2Q&vX2Q&vX2Q&vX z2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX z2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX z2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&vX2Q&x% zBL}$2KN^!WzV`3S()BCOX+LN`Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx& zXbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx& zXbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx& zXbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&Xbxx&{3AFZRUGi|ej1ZAv>y~F zv>&t|GzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;X zGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;X zGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;XGzT;X zGzT;XGzT;XGzT;XGzT;XGzT;X{&zTVe|q`_z8ON~$)knXdY*Q{njgBz@)=jMppq#T zoLTFK@A2mQcE(u{n!dc;I@*=54R|yk{*~~5-X!t9`S7^}JAQxqwE1wIfa`h28+GSH zeFEy`m-3#SSGdqU|eoSJrc&{X4EfXT=sS)jLY613FC4#`YB;tu15bQ zj4S&LuNpb%UFQSeCNjp0pRqr7|6@Pxal!sC zz;?io3ou^)is4#|jwA8pA0J2LCB_S5sIm5g=D^>}0hm{qBXB+Z>gzwO$B-xbNyuvn zqGSDsycPlDvgd`bmaieNEhIkcbLb&TD}H9x~X~4kDIZM<6qNV(HTeNCB_SR zqp|jb=D^>}0jy2^`A7V&C(5yZPk;XGUi*t5aL;7?`LlIsd*wLo2ki&V0nGu;fp3ii zxKFb0b?tjJ9E1Iysv3{Fr;6BqPZhEKo+@JdJypc^d#Z@-_f!#MJ5l?6NZ%Xf0!s~h z!uETrSZ=?kir8q^o~!X5FJb#VRkShsPvz$ut#F6-2;2A6Xk)*piWvUjJ!i7Pd#HFX z6$|b6R1q7WQ#te#?`cy%q5pWVn=rQ1b7D2v>(Y4X9ynsdo*_2s;fRg;2^;MahL7kT zINBKfq;jMGb{qKg-?f{L+uwt1RIWZZY`hZoY(Pj$X%3jSeL2ae=W}1N##Gz5YaJAAT#h z;Mjk!yl|n!(YlYY$HMHB=Y#d#XeyB_y_M*;=gzw5w$d8yuWC__X+>~ za_2tgm#)ah+ z6KoUvgr!CwC1R`x$AB2eWcZHSh0mxQKH`QisGsN~v{!BZ60fEMJIYj#cTyYAV-=D3 zgLYVkpCMNF(bY9(oNin#xWC>{R!;9cKWVH=gmYZ^asG#ZVuYjipO|m8W+OZ#Tf7DM zgZ5a4pCLwDyaqAWfpsBPbz|!^udv+JUJmwz(H`m{jP*eMZfJw`!w+F>6Fwu1ZNfE# zu}x@$Ft(}I2{lGjxvRk#^r`%LyT?Wm{mO|u%CpnO;cQ49f|MY`|XGWJ1e=0hvf?s2lDoQZ%guW8*w08 znqjtkyeZk7**8a&PM4c(azykJnKNx7n^SS(h#yW=C!3}NABe8IGLX&lSnEZCm5a$H z)#GyFUA`h@lQwP|S#oItve~=gj&Mmck!&hn?#ap7Ef&P$<(I193Mt>OEC|^Dx8)IB#V~mSza9rRYj%^wKAsfR#WP|>J z&&bB`Gsm_JKa&mm651deBVJ@<#EWdum(W+TG2%`(M%>8;eF?rJ8-qV&WAKM;3}2Fs z;XkrL4C5dh#HM-}#K2yU6=Gno$7<>i1K-*E!@zg;{xH+H82FBCU|bA*M>a4nX7UdQ z-;oXYhk@_N2K>WJe&+ZY`VejLGmMwA{Sq&zW4%3IFxGNpgKe7P&cSzNgMA0zkq!3U z#2*g6v-5|8@9g|xhQ9=~%}-=bo&);>Km2UU8SdC0^reZKg@(}vF`9G{yZt#WYX5XdV^t2B3Cj?dYUR>{=(Fh1Xdb6@VPd>5bZA+2&E%STtN z1M7M_FBa7e_l*`DTp7m=+caa0qrDvSvE3fEfxR9u;r9AbOW51Rd~fd$>HvE`Q6Jd* zkGjD=E@+!~7@INy-orA==V6*tpJ=BAKqk7P%_WIGM_IA;y_WqzxVO-QtBVN>h z^l819XGY=kOh)-vizD$aA-lB6DA7LR zW)-=6qLuKw*m>n*kA{Scy2O`Lx~trutJE$LO9WH-u{bS6#m-@bGqwNOhMdHDQoHnu zSQDxAcIcaIEJeKTRKDfLY}PAlE5fBc9mLZ2~xBA6`Y;hIUx0=BZtUlw^ z_y7AZcceAY-cN`H)nmkhun`NwMl1*$u^?>3g0K+_@~06C!bU72u`MGO46zXl!bU6z z8?oSMW5j~65evdbEC?I1AZ)~fun`Nw|H3zB;u|yZjhXnyO?=}fzHt-ZxQTDv#5Zo@ z8#nQdoA|~}eB&m*aTDLTiEqrrH)i77mpIP3>VtDiqTjyPIKq7$chkD@UB(gid<(w+ zIF5Gv-s1>d{qEz4Yt8>a9FeQv`MNq9xk|Yba>w_&uKo|iF>yp zS%dhkfVhOaZ42f7hg~LJckFgJA77sdTn}y!@5{?Ltsq=@XBVC?MH#~5+V$n72gU|{ zY_a6K6wdEd_ypR;VtEiNj4v!ZhU)BkKZvL5evWX|PJbR*HwE=4cal2XeTxU-b~TFf zMB^(F-dQ&bKVPRY;r=UP^FqS|2rt-rjJd~+F!LYhxJ3Vh&PNSQ7<4{rV8WpDQ3DeOosSxrFz9^Lz!X!^`KW;j zgU&|{Y}fgyfmKXdC~9EBpz~1!69%1+8kl1rK`*nd8h zO>kHJDe|RlEXO`!xoVTXx1xG*3|NkB8s9_FcY4P6P1L6HMGXK-0|1J*k9Ou+I zOyxF{J^F|2(Lbj8g{fWm{7Zk(|Mq@L<9j-aOPuAE7GPWOBa1v~8}VCMZkkQkmhjBR z3pyPqoU(^AUl{z6aIDf!yjj8I)St2?&a%}pvk;D7aWT8`n!Y>Z9``%3S&s`*`K%PN z*|uArgj>2C^E&Xe2Vr(-j&1d;{DjkNDj{~(b|;+W?ik@-HXY%+U2UReu7rg54ZAI_ zAAUxC*ia#kOtvhFu>0p!^3K+oglnwMCg;6uMtHPqUOE5nNBoYGrzlofj!hXxxN03w zxi`e0Vfn*Bd3d{7&#Z`_1{LNnn#S-#94kf<-lp?$vQL}VgQxx2fa)y1H!mMrUB#|( zrgzq$g=)Md`*me8o@AtcHoLuwZOW5~u&c{W_9@mAx;De$xO`RV-Gui=rREiwVdV2GX^GP*teN;3i0?)j*xwt0x5ZO+k3*T z(!}5omnNfjOHDh+ir>vl_|xLWtY6VQgonCxAdQUmz>oZJ?Gn|$_gZ0jc1~le|Kr%a zvWxd@!WC*}lS93Z5WdqXr7W84E#aQcW6Huql3*SDvd0zS?~{?RYl^kv?#i5mJ2e<6 zrUVouJh4_bv9z5h;X+F~*=v&RyIX;jv5d^973q zjdx5}4?bnX;mz3pr|=VzSCY@02YT>|(o10Zu^svOoV+6mC(Dq7Z<)D*aQ$(aNOzzO z{K%o{J5c>8z{mbgFB2YoE{RM%GBx$HaI8JzQJ(^YGjA&-mbF!5zn(YHdU&@RmEY_% zmbvARO;~umWb3_`Q9ThJnfZ<;kEqZ0M-@g){Y1Q=KE+pNJG_)VA4&0*LAm@{7jYAS{qx`S(2^AvPUL=NApoOD;!I#IhRXf-?RAl5m(Qv@5J3Vt`l#3X|BmpiEfJ( z+wS9dWuX@FWuw?z2tTiuUfy~!fN+wXIpyh!$q27)RY>lNw=NRxe|+RAe>$-j`z#k# z@sK@xHDQPo^v^4+_(c#7-;+hYDRG`~x-QA&lzS9Y8FK%%$o|9y{UH4>>=m)*l7Hlq zWaC8Z3FJeWC~rYgA&h(|S1k0kO)jNylJi5Xl@8~pYxAV?Vy;bH2@hR1iA5DlML6K) zLDn|PiE!bjA6W7#r>GC16;kl*SBdkoXYOp=y55`0n+4?K_nIb`*q^wOXV~2r7Q$gE zKCy~vF9|FUZjh9x^ipRS2CmD%`&A&$$e&$uaL=Np$)?GW{M_^IF^ruYk=}!M+&6}N zb>)>OubX@r`RYkAPhNj~YHGJgj6!_v23n(J{C;`(xE)id{O+~vykE+mROb?wn@=1Z zkMP0Wh4{{+kyNM815e)Y;99D)^-K@Gy+9SZw)l;Fd{VVFWG_Z$AOX)F>wixdh%GbUPC!lCSRUF4%#0{ zecKY0P9CW-ityMg?y~=)f`rG9Dj@G28cP0*Ebb|H?#)Nz?YY`hj&n3(A(m z1}YqpQ+7DKf$#vHL3%yAsqnFc^2nLE9PQUvc`P0^PD|Li$u^Pfu{+@yu||oW*=Ze< zPn>dypqYwq1BaBh#dT4*=B07g=Is>s*4{3|sz+p}Yd6cOY|LK8y$ZDsu*u2dPsn!DEM37+Wyl5)Lw{D%b4`uuXLkH z@1ZWD>y=jeMSq&~9_k|G4C$gulY_tLBC}pH>nO9nGV3n09y9ASvwkz{I%t!|SSRW9 z2va%gSSrUpn(9FvOXWBwQ@h}gFM97+y42Kv?s?>cUE|rcCh1#~AFv+s6|_m36@7xf z#2>`iE`Ej>ZB72SpQHOyH`>HmzIVQ|Rj~ssRe2>h(|Es%zWq?_qHhA5XBgCB}PA8XjyFS>U6=lgp_itAAE_`Q=Gl9kDTUz>L2(A4UYk z`tlsl*XDzF!8FJ%%jt79xEW{3qn;&6*10^t>Xn6TN<>uRy;%mrWumHbM{M#wQT1%z zSB{(UxoQQep6ato@LS{a5}ujL%11@zBz(1ZY3_(k;E}fi`~M=S88_p+@8eTF$LBQQ ztCqzk{Mx56-(1UyaM~xn+!33xClZkTHkSt6jPtfgP2~-{)#S@dtFw7=18Vd7$&*s~ zBS3Yee<*ZWEWE8&;oi&lL%I^G!a4o83*y9kGcSrx4jkJuJ@6`0R#KR9+x?ejcYp zal+|#6ymcNc@j?D0?w#AVAH&f7ulDpn~$4ugXR^fe8G{dymXdwgd1*j<9!cu!u7}G z;*Qvqe07odbLdf9ZpPOVzoGJ2&zteX86Oiq=hu?YOm&O!h1IROBQ~W=NV1hZ z_Fd)3zF4Kc+>Fna45#uX_j~cx;T;G!$R5n2mNg)JvrHfEh|RiLG0DE+)lhE6Cy#Me zPp`gw_pv;LFEkC|t+u5m?3Xu`J7SaP_Fx;XKYO}|b2E0Y_?gP@Si*R(o2LmEn-~W7 z16L5fkUX3_V)J6UWh>Ty^>a8kW2c>csUDX>;arT*P1tR3IR61o8KZssC*j;d8!Osl zJz)O@LtCY=9NUFDy%1xa&=%QXTaMVk7|9;}V8-ApDo4M8PY9z=z*mIPSB}^~j2QOq zCdAQp>eJ@U|ufvZ%Gyai4YMot1(2_sh>v4J^4_BfAz zg@5Qz~S44V_55`9M?Tq(+K0525TK*TG|` zuG(F4?+MH0)tYRqw{Np;p=}9wK6sfqVpIK9XR`mecq238mnqcQze0OYu>4s&kWI;u zD7HFvC&FhlY-f(x(QH(^UW9)hI*>VHb31kj**8Dn!OZyVE!FO( zo`I}ef<9!^aZwX?DrH~7Z+BK=j@TUYQ|Im`eY|Bg<8g&myXj9CV1;6bQl0VlrDxTJ z!ey4kWscYkS*gxv&U;YRYQ}Z@sCIi=u2?g@S2)X<4OWkq%D!d%F;+)xfWwmX1Mu98 zVJ=WP&I{l?VdOl_1;RKN9I*iolRfg>jA1TNInE2Bu^ zP&v*E;5=dEJj?~cI2RnT0S=Qr^4yGJE>Jnn3*bCqlT~J@VX)VJ=WP z&I{l?VdOl_1;RKN9I*iolRfg>jA1TNInE2Bu^P&v*E z;5=dEJj?~cI2RnT0S=Qr^4yGJE>Jnn3*bCqKZnbof67L9 z&j-S^k3bAIgwf{D+F$$_pY;5}^WoBr{g(+UZ*)CO#>q30@I>!$=~Sc%;Z$?OrGqv$ zoWEEP*nh#$7GZ1`>LiSHLR*BfEk|sQr724O?EKh6nz3v0JXC(DJCm7?<|phDyOit| zTA1*_fyJaFHX*KM$Ua4!oYIWT98&FODDEN0)hS6f4aO9ZX?9x)Up}5kI${%cJ|o%Z zA5le`@!AQ=sXTCe9qF+(72$#lyyev6X$f2AR+o<0bg8Z016?aKmu9?bekQ6X@BPZM z*OY986K$;^&xX1a{?N0mbi`(sdmFM(TJDB0;{-4Ks60c~&*E8^=7e9Ce z^?oQEvFX%Z)l(t;S2d0;1 z{P>`X`?7L5@t0o%7oK*%`6?Ud2yjG*>5bKM4IvGSk*e09WP-jg2)}vQTrywve$xp-O{F6?_cz|9Ye(*GCC#{2 z;lot!U#GqNxyKp82THb+TjpFPyenZ_>4;72CI`uW*yi@qjBg}aMdg!Pb&+#^+)UVO za%Z{d^A5tt)^(JQ*!0Syo}C%HwTm?44@JgOJ?}z-WSWOl32*+~U5=kHpYY{?ZqgB( zW|e;+`)<2~q#5rY(~8Qyrv%IOKD`L9>CjuA4IfN6o?9>Jh)u3}&B*@Uv0!P&arb7Y z@=K(|Wto zOWoTo5@!6NR!6FH`L$ibvxL%egL`fjZR2;L@}M`Xg(EhvrzyRZ(SNuwGi_7HD;yHi z!4`H*;fz(%*&ML}jlpr9L>*$rpjD_Gbqi<`!l+3=s}M%5;)o4s46;WZV#c6Vs2p_* zXcEGxNkFR*My=wA4QLFqM;&6upjD_Gbqi<`!l+3=s}M%5;)o4s46;WZV#c6Vs2p_* zXcEGxNkFR*My=wA4QLFqM;&6upjD_Gbqi<`!l+3=s}M%5;)o4s46;WZV#c6Vs2p_* zXcEGxNkFR*My=wA4QLFqM;&6upjD_Gbqi<`!l+3=s}M%5;)o4s46;WZV#c6Vs2p_* zXcEGxNkFR*My=wA4QLFqM;&6upjD_Gbqi<`!l+3=s}M%5;)o4s3})9MW(-<|>OtKC znuKgnlYmwsj9SGJ8_*bJk2=JRL90+X>K4!>gi(`#Rw0a9#St6O7-Ww+#Ee0!P&w)r z&?JOWlYmwsj9SGJ8_*bJk2=JRL90+X>K4!>gi(`#Rw0a9#St6O7-Ww+#Ee0!P&w)r z&?JOWlYmwsj9SGJ8_*bJk2=JRL90+X>K4!>gi(`#Rw0a9#St6O7*^yD>JT#qtwQyn zZUId~7&QrK6|zUI;)o4s4B{c`5Hkj?LglDiK$8$gO#)hlFlrS?Y(Qg>J?aoM2CYKn zs9Qjj5JpV`T7@ub6-R79V~{=S5Hkj?LglDiK$8$gO#)hlFlrS?Y(Qg>J?aoM2CYKn zs9Qjj5JpV`T7@ub6-R79V~{=S5Hkj?LglDiK$8$gO#)hlFlrS?Y(Qg>J?aoM2CYKn zs9Qjj5JpV`T7@ub6-R79V~{=S5Hkj?LglDiK$8$gO#)hlFlrS?Y~TzY*&FBazThJF zRC(;uC%n#nQh1PUM=3a$MK*YL%Zz`|K0423>2rF2-+PAt^*pDJBW8)eb}lzM&s)OT zWIBh8oi?3A{wn9g*QAYUKSv#H=fmMyQatC+jkDWd<$SpDzE*o1_*{(rod4f`KHMHJ z@FkwLr`VaXj^i)SP5jw&{?Qpny-p%iznyi`9xt8m)E?pQd=BORA>T>kxi(xsF&EkM z9X-2mJpToseRp2;;m4@LDG&qGnWCO_Ms zha%sgkFZXAn~06)+NfN|j&j^L6+8R-xvz!#eHXa+M-R40Yzv>af`6hD)Be|JHyUw2 zYHMGMVf3zc9DDR&i+zmvZ**dbV+22Ao6(7(Ipu3?|G&kiXG>-E24`vS@ZdvX$%eM0 zy+iBHd8BVz_3n%J8#2k%jV@F9#0yE}=e{vg@7K$9jZwyvr+7ojyZ#`hG5qxzpZHeEyv?_TiyJ7IYK-3HIU6NcyC1w8+*@Zqt)8oQB0DIXd+*Pai_9&(fUok*x9s2uYl zyywUMY&(beQlBBd9O6r3f%tNWFJXu;hxihP_;QFZ)dTTm5MRO&Uwa;h|F35zKX8+O zxXEway#=k>lwtFFvOZctOb@stU1J*FvOZetO-M`ImDVU#F|5_iNg?U zc#l&``}5$$Ev(1T8)UCE&M(hR8~VZi{592s{{AcTOJDof*C_2n?L&hDlwUROr~N=A z(06cgI8CI1b>{_xQuir;KW80^EGCnCwJ1XCB^9*xdqRyYJbQ;c9hpV$0e!VVP zikTs+L0n<_a;Vo-V?q7&9o9*f@8?IjdG_K3J`W3TT-@)s!F&zyaOhndkeyWqo0Wm6}k~# z-+qC(7^=?S?tYe2y!jMPzFJY{_yKFjAk_4Cshe;zbtB;i-pd-CAIcWGQZ>xJ>L>#a22 zWt+qKfOI|#$Kutm51+DEooyR2x-(BPCkDsz>$!Znt-UMZlf}#PQxWPs_d$d#GGDaR%Xj)wGpt`8kb5n+&CE z$ZClTf)UoUlea2s&nAE3XKtu3WQPlsH)FxV!w)M&iU?E z+x|XOK5KjpmN8)<;r`Z*%>9%v;mu)A+#_=Z!WHUg=cmW!Bs_XaY2MH~F5%$Xjd(Su zUDVGh;T`!s?{`2_QQy+%+>?>+duwHJR`>nOuEXFymOnaO~#n0;O+2hAk#hRF{sh$|S?}+!#H3<*DmRhdM>_Irs&7!i} zB4@&}v(%PREv`^Mr!;CS+u!+-aNw{Y`6B2ejVn*QFuA6nGmUrIsc>02sro${F3J1K zH&fSX~SnsA(XY~U&gs@Kj?a6+@@k5LU*C*V5PeNX_ zftB#XYI%A6_L&KX)vU}*?tDxA^b2mr8+k1!yz*8TzMyak!WH)R<-vYM zzqL)Bfee8APU*7;QF*H$$FmaW)Y-W;ePXf2S5-_;)&3ZHtX5yL8S$yCs1;9rFIoH3 zYQemkQh5=#PomuRiiC$X%qq9_QfI~8J~Fv@X?!Z5d9r~Vn0G(*Ie$P0ne0_J!jo3@ zmRkqRq?iW48ULYG7g0=ovxUpMCDn5@)=s@;3$FtL$F=Eodl_SH0*QEi(FSs@e;&g3 z+?X8NqY~jweX__kdz%veQ1XMg*HJwK^5nuwk#uBVDlf#CsB%}uG3T-~k=-_gQhA>V z@z{*RJqS0p{lxNmwIST~!F3jQg*V|RD^hX)+(iiYzT(NZT~0-K_(*Slq|6QK=VLg} zUMk~6g=G)E^F@5Z!?! zg|l$9dAOnyPZOUJju@JU$IjY-@WP!5c)cs_3CCD|fPHGL&SZ{h)|*YssN(3GYKgUl zm%^_y&9wCu$|hxsZldC#4s>nU@_pj;dsS!J&hh17xD|=*I(5h`7k0`@IOD2{GGy*2 z>RXF6P37u-YY3-%5-8Ug?|3O#sjs{->=TXA_bNOC8?4?bG~rsP>=SRiz&ZyP3z7?3 zT_argVjJ0ET1tuKL%P?J_hWey9v`!)bl*~waFWk1GUMRZgmdq`B?i@3G0L)MvUnAy zVz>NC67lJois`Om^SpAOQn79qvp9?KMseWcg=MV356!5a6hUuUaByY96+JWao0IdZ zwvtTPx7tLUGu7E-*)=6=iPgUQlCe}>&*kItS7G8K85j7ImZ!)Z#E3)pH6io zpCnBh%$IrWA?%%?Bd=UdouxmzwjqzGnv3Ijt?^3ppo0|%R~eLz2L#ghD;Cz%!k+{M zQhCWl>)8v7nuGc3RAGlts5t)E*2TIsfy$xXPJOW5pQ7gShOR$~!@b(lwFz!s7JDk! zCfvWXv&{6cDB+2zJ*1yg8o~oU)Q|(ps`K-+ueXw$dQPK0pT65&HfffUuz&SXX=@%# zYf(FRm*k?Ig$4G1PVx}BwD1zb8M}6s9pAqqe26ud%RMqlwDBxoMK)nxgr|n(lSd}j zBOIDJu^hHtJ^vMB+fk8nRWB-!6VPAu|Jlf)FNCdn7ZuaQqla2Mw^VEL(klLJ>iCXi zKWFw%mdL*m;iY-w^2p1j31_OGlV6*YopAT7<$0_nPK0e+eff&X8>yeO-gf4LTht_+ zNA}?rbLFF$2J8;!&bgmbOyd_1Z5w3FL#P~DWnpA4N-I*pG`|v@2s z^Utr>ELY@Uf<)WN(iogoCcsm3yk5 zpg!j>5Fn4k_cYkgWA_wVm+f44vf8 zH?bvNTidO%ywElW;gKuK$Scm}2_Kp0D(A)YCEWd54C&gdGvSbuTZF6eyxYsQK4RrY z6~`@2OWRm;72ig6Zdq^n^(6bXSx2%C3;YSUd~uFNMb#nPzkG7O;YxAB8&ej7_c*5` zT&Q|=z9;n~>gR>IE%|`CvkAv`?#>ryP|rEWxe>w}PZ~n+=IRFT=8EC%&TuR@r-bme zE9ViO@?$sN_J=%#m$wMvwVD;Dwd?%*aGv>KN~*Jc8}{Hmt6e9Yxpf=- zzKHsR-@Dv7n2K=w$=>{CY?TYn7HPwCzESUdo3XnGFW*_^f;1~b`K1)6sjXRe!}-v( zjQS8YsxR*|L*)XW-d%X1mns)@xzLnKF6 z7nJOGfDLb@*7;4Rd$Ii46vvYIF0zg?&ap4*G1KP0McLGB)J-hxrE#EL^ z;~^KkQEfdA$t~Y@QMn*sc}3~pLFIy+Ih)EirBp7s`XNxhcP~d{xlpsOycOp&jnNBo z!M=qm7o@rxDogsPTu>u#ki5Q7<${R^+DO-BDi=)guO%~DR4(v|S5($Js&c`yt1i-M zqRIuu2i+1anyXy!V#s6>KV0R4(U+2lxkfH%8MMHw>p_(ZK5j40Np!xOMC!9AZ)QS8sJAN>a-B9I%&(tV80fT#zvHN88ZxDi`FO z@uNuFUgd(-8Lx<9d24gzf6PhFviDV$3;Mfy$nBp~Q~8>YHRSuaDi=(8)=D19uW~`< zm)&LR1I{#-W3@x&+zq`b7Yu-0P(G~(`Q&8c5V;{(<$|ADca;N5zozn?d78^@rBp7s zV67tWl~TE&O#giH__BI5U)(<>l3_Ds0*{F&=el?$$1+{teEHKOv?rQ-5bXH_n+`Q_wEd#hZKKV}7(0qFzz9F%CPhj|7SO;P~r|`9%DSUCGA%$U?E_oXQ2&cSA0St8&565*g+8HYyiXX;(^?&#iL7 z)SGo>k)$dYEb$7EiOvqB{$KO!B{Lk{N8@6uyA=9IWd*W1-mA=%EW0@F32cj$QgrFE@=01Gu-RwL)VU| z%^ zeeOv%KTH_HJm#qRn0w|4>%56-p0>%;&Nl2-Fxgy7?kCbt>_j+tsSu|QHYOZ?E0&xS zQkHO;UhdLsm>c2ZmCMN$FJlsJ)3k})@lz!AGu+Zy_L$m`aPlI3iHl|8wC-7DMDbwDEFN=4U`q?v0J06^OIN_}Gd-B1}uh6(+ z28Z$VO>5J5>n;iBuRb~SgidU6)R+TxAE56-p-a^h>qj;FLL^pZ3 zTrL_*?>-^2)yQ?kTPN^wmpK{950{>W$O9i|5zd>xyWBQN@jqaHOZoI;T8c{>xJQ_H zlA13)nirDJQ`J05Ju;bBaz8-ec{@%oF^ zdJ_MAM}D?bE9!rNX~F#ZynYnZNnzo9`A>T(rb+gN@kf2tdX>F>FMeb8aq`KedI5az z&BWx}iq7?ThSF-?t2(k2@BCifzv^2hBhM45*2$NJUa~5?)%xjNXA$e`6++jhe3qa2 z80+n)0r|W-WLN8Oj}>Xe^yzAS&e3p&h}ESP*}KQOFGB09^}OM=G}4Qyb^g(|VzTwT z6l7E7Ol_Gr-6iU$$E~*Vafr$nF|G&6+|yMaS)V^l9=_yG8o%|q=^^y19 zY#_|j1WNx_Do^FQ=_^Y&R{85z`UBY^BTXFtm1ewCLi9#6z)4)CJ# zPM-Pr^sbo*_jInphyI}Q`^!|#`OR}G?@#dQ%Cl7Wr2gl$gz)TjhmuZ6`Z}CvE#XW) z$=V>4Pd%ufYrYn%2k$if4wWZL(wa}-sC3AM!ZqP{R2Ajef4_7~opD~U4`m5$oyw@z%G=0|mI z$z_o--&P=Of!_s|VwBQjA&0r#H(lwp;C>C|fHO+Joxj~d4ocaX`t1Cnw;aA$>Aj3_ zkFac(H5AhbxJNi4eF*tsN2cCVj5$QOPS5tzb7ew_<7x`;5pPpFFX2*kta5Zor9WE^ z%q;J=X-4G-;=L1r7rGF>(r39?v%4?hb9GCIV^35}XV+U5S!$%xy|el!W~Bm^9-g0L zGIL+nn(V9Py~Wl%Q~G(xY8PI-qSDp3b`;?qi=`r)S21hxCIz!lKi$rS@IJ-VJFC0) z?#{b*y+h?rXGIknav`qx*vbA zat+Hf^`w|k!;jxgHkReG+!b5O`SCr~ny|?wUx^#ckH0CFn$`3FB!&Y%;WNkD)Mk`9E44)E&U2zr5kFq$ z$Z%16^iDChm>-u17K#p|7mLyy+P$$|fy&P?6AnxW%gKoJpFjyJ0HZt0UoSH4nMwO z*Hh83NEln1#g7*bzbYQDnaw@}mPhuB3O8(QNKQZABzT25U+D}hl*^ANeLh+oEBgR` zf3_bVJl$IysQ8ZUb@t=cTtC|UW?1-}lzu!cZ9dzX=@z~&lOI1gHH)>E>pRvrjUQiI z>XY?y&HF4#0zY2jLtU16aw@HrDcvkUe8 zc%!E6tpx|XW+xza{mUk1dAHtSBOt!}3;VJTuTQZ3fIDU#$M&_@!iGRhPlm5%8FJ2G zr|Ll*R~}$lBfGQQaBZDUKQlSboz(~X5i_5&N*>FsDJnzkPJCq3;%z8ZrY87&xrLXA zGtPFpE^ub~Czi2NdNBfGow~zI2K^C6e{3h_yb@)g&MLK?MdOb*MKP%JX?K5dX8K_< z9qL>(af+xNXN@RS%a6}Jxmmmj{!!R!`|(9`t`ndW#%BKMv~)85l69QGVnACB z{EmwqBi1ts{cqNBgE*4w7;EX{$5WmANi3~>hZU{r$CK~!6U*G*u;(xr8dr}m4yLy7 z+)%zds)}vbQVZ|l?Z>yqnNiB@a~LBt#>ild%ornsF*0L}493WeF)|n%Q~eth-Y=aH>8ycZuq+h4 zF=2<;0h)it%|$F$lf@!Q4nLkTd z73&>KanjS46ZCWK1r}Z{eIKti&wY9KQck?`iJ8{!SAF@^J)fD!^m(?fpM3d<{GVC# zuC2GOzURyHG;-oqbI!1agUy4}pIP~~Sy{j}Uq1W6OSUynS61zzFK>S42J;#`oo#yO z%Li{b#JX49!W!Q3Kb4!UeS1&P7 z=>LEtgGAD&yV(W6hg(F5-B%W~K(IMdVyEbsYZw~@*ZR3#6pi|qW0!9F@(Yt5i!6iV-{I2TP(2;uJy0@PW;fZp1672m(N>& zUyPgmqxkUFmtQJ&!+q(MD-hE&GE^5!#KCvxw5!mltKgnwKdnG)ep6nYku?quk z3h}^~kDuR}o$hs5^nCBj7x$mWstsNz4uNkoH{8s;BPWP=(9ij2Pq5r;n~8?de_NZo z>_q(}V)$cU?!E90dwH_6?K=22URw*FJ!zKLBJgdg%1(T!_aW;fxYlXIN0#_Qakl5W zFF&#NDck+iK=#8kUw&oAWj4Om0yYTtN0B@BusZd2uzld$eAkz-4(%?mesFEUM#EXd zB#&8N@NEpYip<6N13L_Rt4A)ktSe$U@g`4w`Jh}0ti`TDe4+lUTT9s5&3VVx!L@Zd zIEfwAAF!U_+X^S@h~r7lu(IIWblrXsS2_yT;gK(2onWO%xp+3a1U_kYKT4c>*oPGX zU#0T@SroaQhpoHo%Ui{MA=X@9VZ8(UyX2AJZ? zgRnq7mk+!WKc(*|Ji)hNd2flCp;JXsxHi1l5plKMCQ%;hY~5?Ua7}bVq=swDT>42I z*>^{{fNw{XX(@urf#!$4?M$6qOs#E^Q{F(VpY*n^s^KJ4z*rvV9pTma{YS9?#(3<) zUhDlL&qPlc`^dUQS=B~Y#6$4OtHuLhZ@5OHA zcJX<3eotkQ0m?rQc*Ojd-M3{0`zt%%vwHnf+TKGwncrCW$-DWjAyEIR#}>ZB|D$yt zTpRH29qU)T7K;!4d425x>sWRS8v*^yc;O5SPO*Z0hW;0+A=!&$Q7i+DE8~_q?8U}w zEESA*daF>@bJTNI68tc3N`AH{{1bBr|2Pj>XU*>I#7l$U`fM-eHKC}5#|D3T93N%t zSNt_Q2G@r9q!pD;-eSwa|4}~%i13$3*c-SuOYjtN(SHMzQ0JE38^xXv6IpSvufmRt zJ%?JevrvzF?mJ@e8E4iE`Zo8{Yw>hIe`{^vLt8J4j2IUX84hD9RmVxb_upaL0Asw$ zK8gEFJw#3zdx8zmMB2>#MGf%D;}lm#%{KGICGb_67W;(z@NHrs_^|xVWg`B)a{_t0 zW8Fw`?BzqT9r%2@Lr{OdbgtHpwcm@0 zaBa#rudO`jp_mQxsOt0@EONnFaT4a&sN|#B^*r0eM3{F2(=KOo_Rkef!M6>H>}PLI zhl|&6ZPB>bSevSa#7>yMbCN%2-EwTPwS{@zz04;z;6#haDDZ9Ks!qIYi=i-QeEG5( z7M^I13tIrba-H{@m5Sxha)NI?`rKxPdQ4`Ku%4V=eUz;px`BDYImgX5+huq!-e$;UEem+$MT<;WBdsk9*py1( zB$p3;W*Z6D21dLWOFmTN(gjA*z|%!R(q zJ~K~Tse4sif@_~-?=NmncqVFsZzJA%h%`>0#3C4@*eh-6$~(#WF!ua+2S*-k1@CPK zpS*d}-x`(hjpz%$y8Y0ZmCbZVM1T(;1+`{L0*{I2kOxzDoW$;x+aw~PeE(1DS$MH2 zVgT6xIP)mmd?i4%hI$s?zQufj_Z;d^mFP9AH)f=5AGEtRsfC9ZOzG7E`ZJ}W6EE6t zqxEO#=SlgA^=*)!O@jV6U-g`gsT|5u!MLvVyT&%Pp2HZ7_u!lT?9?W~s)8S4U0cDn zw>is3!?o`cjA2fvAFveQx7>4Tv0QuJF?aB%f6EWnVTUaIF5uZMJ*=@^oOmy=88sk@ zt;gHn49axM{(@(RIghw_G(rqxi3brEdqS< zqBq<#ESX%?17CIR_C`Fq*+S$1A9me#M?5M&QA`8g_O5tb#GbcKFyM1ofz4v;!6RZB z*srWJRa`80OB8^5TDIvZn$3PC*1)`ImNbLt@Z_@?0`n#A4?o&EH+GU|z_(ZPo+#Dm z<0tU}`str&jdeoq7oraIf9ujbELV}AMF`BtHBo(7jvZ0r8TfWetJ$po#g$?;_%`Pe z8%yH(gP080cAj&F1(xy=66SmBat~PJHx@Af)`7d7-m#W*t+sKnK5VdA_>nC!tw+JP zSF+QGW?(YAwio3@7) zf%;=TUcdtHUuJ9J+RS4IvK>D?Wu3sc-aaK*)jl6tVeswgSO=_gia;D;J?tH|(#vhM zh5rmbDd5)GmiEjWRv3I0F*u2k&F``$u&$P^+e}o+aDwi0hGzIlbWXd4?F8QjtXwPF zb)3e|f&JvShsA+Ao!JM#O=sQ|$)hr{T;SVvg0<}b^0}N zlD5gqZ0W%MX7SG=#^;qtYHx81`Zn+O&*DjoSz-$b$&cdWiu)oE#=iALJ+Z|3owy1<87yK77tq5De3kQJCEJ1APBJg} z@W%b8UIV6lpgefA@Xyx7D<6wgP`)T*IaX6%5GlaERoP)I{=}Uk9>i!;{>7~An+P!w z>MyW$H#@m|keCbY`gvYv3qO_;7U)k?=cg=e&QV)m=;v9FkL=mfU6F}^8yWLC@$yw# zS+nANoNeLLjwWO&V7%K)yk*a}`LcrGhg_fUvfa!i% z+hGe|=*de&~aX?p=X6H*b7yRFTU{>~K^k)_iIM0SmwfZ-4;`^b_3KQmU z>C^2qD+%^h+!oprrG3dxKs}9WyNeo=uQMO;ZPNWg;>edIbsZVLK8Th=Q_!F@$;ZWfZJa6CsqR3Tvkyr}8?bvabICyTC zI0^NavMds!?%A_%>%?Lu-erZ^cWv){;IxTQTjP*bMVGZr;Y=tCONW%Pj+6rS zI5JDjH>^yX0XEp<$PX)M*bBdN4E8uO{o9dj_`8P;_Be7;(P}JU z)_dIJ$T%OKSv})BaoFR?XCCRSJ1$u`>~Un=GC6I7v%kkZj&y7C%66*TL)_!Y#D{8# zGsVy0+Ac@$9VKqAleou`n-4D+>-x-Pu*Z=i!+z1}Z8(EHjvTP{swi5j5Q9CA+?wmT zSl7;Gg*}dZ*5{MR+@Y)&>~Z9jdQS36rXe=iiD9qBtgQaH$B`u` z-4-!pPR2cs?B4H~I9hfi?s4R$X&XfDxkqu2BV&x1ECM>-7O=;WM@#w(@2Rf^>~ZAw z^DbgvHPGTv&(u>xZ3C-1N!a7aezlr}qqN&tvOJ>&>~Z9k31?aElQjhFab&E3hpcJGH#XSg z$dXmxvuaLmHrV6HwjV6q~Z9c`xgFo-xDkBapa_4@7dn`)o_m^S2#Uli>8gl zJ&w%!?i{;+WEt*pWRL0F*nRJPxW|!8`pjctF|RV%+pE20u$m2IWSnU#@ zaE~J=U)*86UfYSo9!I`*?d0XbEFAVYlBe!(D|YKO?s4Rv>CU2eu{*fOkxeJH7Q?)c z;~qyIxiL|k7_|}iIP#Rw2621L6b5@7x$5Q-QF3npgFTL{yXTg09i5iJ9!K^o@LEi+ zINAz(968O?BCmUSM#3IP4)J!9GZL?}!5&B681zZJY?dGQIC9>^=OT51P~79l1$(Xu zzjhkG3P{=!FF z#3PG@J&trgR>0=@)*@k#BRkJ?wnprKk9!=MsK|Zm`Z14ik0a-dsmz{iK96g=?AUn( zdpBS^?s4R>BTHGLKJx|aab#fsy{tyi00Da(xwgs`)_8PL0ec*oCC@X~vDQ8t>~ZA! zmmk^cS0f`~k0Z<1aN?WN^tQqtM>g=W{2zPY0VZXUyuT=tgJj8Rm!wDz!cI4chzbZO zh{&#pfFwbX43d+A1SJSa5ZEP1kQ{fqK{5y;qJV;ABuUQkUvGWi>=pihdppdY-W@kQ z5AJJiO?OpwRdrW~L7&~D46SBt;Brl`iTTT~9!IY)@58pl4p;&acO*Ar=~ zaqP#LQ^Y*B_8w{+Td4JXZ}YTQP~+Gx^PVH4erZ2Q-!acqYc-

e zZbXe^f9@J>@(=&bP>o}sSkT`boORJqjbk^Ie$M1va2GX>&9#2JcXhQymTDY(z46qT zCCx)D)i}22oi?5k-`qfrV-IIfqc(ha3N?;x{!t?}`_zx9acuUe(JI~hD^cUv`|Xyf z$S=M$RO8q+&3CA!zqB<}pvc%zg}%CQjKFT zzL7|;-!#iZHI9Ai_C3|*W+Bu#w(_7WYIUWqsB!G$`H!kkdQU-(W551+n>yFUiyFsn z%e+91E%vjb8pm!~IZ~aSbw*K*W79>|Q_IvX)Ht?LL}K;o&JayCj{Ut$RZqioi8R$X zcJ6O?V^%f4gBr({OLoXxW%_y4ICj@dRZPY*`%&ZAJ83^QztmWV8pkHxI@=`fGDA^~ zW4j#OVCJ40ps2>NJ9i#1$$zb=sK&7~Lob@i<$m-~jbn$jxN9=)UKUO@j(w?eB71aS z6ED>`_LUwXc5#E0sB!EI>24Z(CIU5%{XX?+^HtwbsB!H4CA&>n&&8;5Y@N4Ond&pP zqsFl(CeU}AZ$4(I#<9y9w>No?UNuzX*yU65nx4DvqsFm2CQkCc(IAnf8pr-v^O=V$KKx1NqsW^JJdM#?bef3o74+YlG*si*)oIVD!|9V6s&VYl!#CCNS8IEz#<5Fnh%S`vR5;Z*wpflt zy2A&*c&Ns)F^li03ezj0#<3fVTu?iH8-yCizI$Q6I=g-rY8?A?@%8F%$_=P-?B^Y4 zDwFPjq8i6~@(ohmCtpxhbXRkY8?B0jqk#r8Xlsl#-OD3twUaE2I zu;%womSOo(w@l-HH&Nr*Bb$?(Li0l`)i{)&8+wZtNMxzTv6o)i9lrAJ9n?6s z%ul;LZ5LcXjbjhp_NYQ%A3%*`>&+dgnxx-=8pl>PGgZ&_vryyMeP!3Hr40rfs&VYO z+WXbL{FM#WIQGrV7u33(zj>*~v2A|5qyE@-IEHE*JGn$6eY9^a57js}2d$Y??s@_> zj$O6mrmDEUK588Mr8=WJl>ZDhj{Wq-pVfqs3sK|P`=w%3vs~Yy#7qvtj6EIqNv8P)$SHh6`S5ijbrcio8{?FYi6o(Y_o+oD@>bkA2p7xQEj}p(!r~! zaqPz3c}%6e$5G?hE?e4}Pu|*r8pn=M6HVL1M;??o!A zaqRRxr_5WuQYor&Y`MHQ&G(7k^H7arqiN0jTzeZsHI99~SRy;(x$nJH^_4U$F?n6Pc=%t2Q`k}ly0PImfMRO$DaOTff_k&ilG|EUar4QH9OPQP>o|Vu0Eoc zd|lX3jbrx@xT5-9o9Cq(#}+DbUlnaJYBkk3wk+9rNR81Rs&Q<^@9wKi*>j=Bv5j86 zrq)(#iyFr!+I(DH2>TK>j-B@G_v-3zD^cUvp=TGXeJ6II#<9P@H%8g=rxevV)^oFw zN^5SQ#<99oT2=Jp5KT3XE&N+M&(v~>G}Sn^=&-M2z8ZQLHI5xMaf>%}*+tYiHuo|%u0*y`x{6+^aqOD4A-3F$A*gX|xdFG#^wF=O#<8!q zIBQm&8jc#rZrHWQd^PDC)HwEsw8o;(mTk4zn}%`$)i}1#fRn51-MNn%$G-FG2+yahuc5}VY2L}M(ziK*8pm#0 z*IKntv=cRs-IsELx_EF2Y8?CJl@%(YYnEeszi}? zOwQN5Q@YWd4+QCT%nN&w;y^%B0zWi>KNx5;p z>5?JR?!NCe{SJR__EP&PB6geWm7ANG^pUpZk0;F5dil+??2-21<|`(j_p~=dXr$fx z^ldZu!%w|spN+I@n%y^b-(OYnjeL=I+Kmv~qxcNZ)6{;|+4sx`(YaOn+>ti4~TNma-=A-rMTPbCLE?>wVsxy+ia1o=Cf|XDaU#LqhaeYBTY3X+1M@ z+))=wM%uSa{p>k&|Dx(Z^m0W?s5RS;c)X{2@c5>tKYIFM)YWDMy zcF2mwD&>XA>P2d^?uxCdOR;{cF7dai{+s$JqN-Z2BW;0Gf2dt49#gsLvnz7lRO2(W z^Ngw!X=6USuYR9AclD%~BW<6hA$mgA5#AT7Mq1Ckd#YCLeSA=S{`$w~#aI(6e ztHVWBnXxq^ZRV9!kN-5$tf&`h!!B$?JGd{0c5pupcekv2KMi-ctb0EVcekv2KMi-c ztb0EVcekv2KMi-ctb0EVcekv2KMi-ctb0EVcekv2KMi-ctb0EVcekv2KMi-ctb0EV zcekv2KMi-ctb0EVcekv2KMi-ctb0EVcekv2KMi-ctb0EVcktL&?j1bni2G@{g9jaP zugSPN;(i+L;6X>+Ps1HN=!pAixPu2BaX$@r@Sr2^!{81cbj1BM+`)s6xSyt69dSPm zckrMi?x*1n9(2S#3f#eij<}zOJ9y9$_tS6(4?5z08t&jhN8C@t9X#lW^LO0AgO0eL z797XmI0oY}7>~ic8qBM~`SE{neq31W6Gd-WZ0Ny#YPp%C?$MfL(n_mN*4eCT(E4X{ ztEuXZJNwiGS~G0l`muUF)oC@G)-#)$zoE80aZRP9&-U7xMP*rfm)9p{Q+(t3d1Q$0 zOl!ijhgXL097B8Vv=(X~^I1&Cnco?Db72oAo2p><}5 z?ds^lkIa!Aw9dJGNM*jL%tpdnR-9LFPYp5Ac_ZydyKbr+X9s#m7Kya&zP_(^SK7O} zPuWOY>nFMobGD{u60L!EWDC)MJbB1-q)Mdyrv7cU?(HJ#cI8OBG5KZHW%4_!1kty} z{H~g`TwuymeYE&-uX;PFH6=*4^)Jj<&iA~(GmM@oSwAto32Kqr<&PI94tX;Q-{n3a zdEc-Aa47zr1Nv+KW+tBd5vzr&RJ$orv-Mzpj3;DqQEk>exVuk+HV-8)Mt zf3TGEVR3=0iM*MH4GK+ku($OGCq%C=2RE>T-%1f(=|&Rm4}Mr(BtPlm5qiao6Qb82 zGaB1vmmiBBu>GR)2TM607U$ZQSA9{lf9Q9cKeGPdgy>Z}^aDG1*NLdDE0-yM@WbjN z`OVyKJwv+;4ApyjS$}Xs^olyr!pe{e$d z+OV{@P1<)LU5)=v=yNj%=ZuD!gp{ z!3ojpLerjh#^Op*w^yYz{$MHR!{T=q7SZ$aB@UgrMOlAvLiGCX^X_(cvfNR7R@5>6 z;D^;k^5^MLR`<)iFaQ2grK~?VA$moa&bH^2+tVw5@Uig+OF17F@90`tf3kl@{wq-h ztv@&+dW|~M-d3--YI?^`GmSs^VRe!Gsg_sQEyp&=?@6BB`hydqSIgY*+qGvqPEY#% z2ICKway~4kx!5b_<#=&I^h*74Z5!4#UG&6W8MQz7VRe!Gw01IL9ThK5h+dy8e9=~@ z`c(9Z)_Ju*SjzdZm}*HQ>dJU=Li8$~Cfu%Hl`DGNqN3U#{II%6eyaVA*awIgCq%C& zW*4{Fc7;Yyd+|B#50-L1ET&r0h`KUfoDjWM4-2(d2Na3!nf(Rr4}Mr(BtO;uM(hK` zixZ;P&dphDr|rd}OB8rj`-7#N4~uCHZ^U{&UYroU+BHu>|CVIw=%x|%wLkb_b&>qE zhPPrpA1_XbUjBS`)43Zab&BVr$1Q23{lQX~zXDS&U`1UJFZM^rxOg(A*>AqO5*}T$ zKy&R6PKdr#3s_MX#EavS*&q7QSB%-yxKi}M*=@8xI3apbEnr1m5HI#e{WZ|38^q^ane`Ze?L5aoDjX}JWGqS zt$1-vgCxF^2V7=%(ON+CucyU}Z`$G?4tsbym zbe^Tf*;c&RANk|r381zLST8!y(&B6@UL2Rq{?G$B+X`4OI?vMLY%5;ukNk1*_;da! zd8nO$^`i4EEzY*$#c|2(4?TdrrhxUL^DHgSw&KP9$R8I^0DFT0>qX~TTAXdgi{p~n zA9?^ae!zOsd6pJuTk&FlqX~T zTAXdgi~W&5E*^jGJ4v2|=tbvQTAXdgi{p~nAG$yHKP68>^rG`DEzY*$#s0`27mq*p zbtO+i^rG`DEzY*$#c|2(58a>ppOPmbdeM277H3=WVt?e1i^re)x{@a$deM277H3=W z;<#k?hwjh4JIRv}z38k;iF2!Xu|M+1#pBPtJIRv}z33cDi8HBqaa=O{L-*(2o#aV~ zUUUwn#FI+o#aV~UUUwn#Fc>K9{CwUU07o9_S z#Fd$?Ok3fIZlN_44Pwf#mT= z{ANk|r3E-?PV7>gguPb@tlGz`60Cy?^*2|y!)sn{_`QzdV;7&!r zdiir7Uh>2xvp@6z?kokYmp|_pB#%Gx$Hf!Couz>F^5?yYUE}PXKqZ0@ll)_v4Z$E}8wI z2XKZMuwMSW_m@2W$R8I^0B48+>*de)pGcm#WcG(1z!_q|dinExHIm04`QzdV;0!Tf zz5Mz96Uh^o%>K{=I719rFMqzTM)LS0e_T8PoFN9Rmp|V-A$j7G*&liUXNUpo<Wdwaq$Fj77(yr{=D~>JaNhF4?Tdhn}GES;5*8q0^P?B;4C0uz5IFaFM0eKm$-NW zIJ*g0FMq!OMDoNXvp@6z&awm6%b)M7kv#s$9~VymcMk&A%b)K*kvwt9><>MFv+RKN z^5^?%B#%Gx$Hf!C-GhMj!uMs;cXNiEnV3Bq>m_`*+)|x2+V_2Sohqb{cHX{)=*{br z;5z~=)zv2x;=Ae$_Mr|uvv+#Q62pkE zkDfi_=^^fS*nyrOccNT=(j!FU{EylRML%x)q4??c8|s`7vOHn<96nEShM^x<{xI}Y zV8#yxNG~7VkX}B11Aez1OL~R5?OW2z*RLhLeDYYx^6~0{QVK(2^aaF%K4zcJ^ev>XRo-sqMWP=hk^WW8Uk| zxZM4^s{Q&ljQ6ecs%Kw#i*cuoPv}IQD>2@+y^vo1R9?m*S6|dU3f(f$Hf3ZZz3uqd zjJwrouaCS}l<_AuKhjc8NtgVx9ofF@SIQ&hl=4fxq`uM)(mv8|B&UWhu&2Z{FQJyB zKYgH=0)k#7KV#@i@-v1VNPcby_96Kh!)_!$W7w1AXAC=&{ET6LlAkfgh2&?9@gn&d zV;o6-#u#6cpE1T=$|>oRU$!ILm;Fk4q?}TIsh8AO+Ckb!+D-bypD^nJ`{y2+hH;0f zb?t>2Kd^203~OnBE#HUnq&;2i@8jlrFc!aL?hWkqVd62s;Gxel#%HNb3p(1A<16Ws zU$!ILm;Fk4q?}UzKk3LaxIPvaX5Ihnhf-#Vp_B8+S^vg|w{Cgemrtz3qD?LQM+^T^ z!he+TAL+MV;Xg+Bj}iW3h5uOLKUVmU75-y||H!eE@%RA0Y)7^)`<3!YIi>s}F1%7- zX$NT^X*X%lKVjdvYvFrZ_?{NNr-knU`+OcezF5F#8Izx*P4*x1bD4V|pi6$)j%;7{ zE9H@LO8H60SiK~cJ|^-%#*1T<@+ZcfG38JA1Ghu@6Mn*&@~5ToVodqd(s(hZ{Ap;s z7*qa~^BTsB>6Aa=w~Q%&DjF}wls^@X7h}qwTFNQul3%tX+ZXc={GZ!|JW@_6ztl_W zEA1fdBkd+_>ksy22h^+nU}{r?kMa-vCtl3;BJnqGzLM$yCkK@*kvdGuwmo%P?)zqq zy88BxA9<{crE94d&+N~*PSY-WNC(R~Jn`XP`pw72u%EyBT5o-2?uQEUq+Z%p|D0|s z<22=4>lI(7VA;N{P+xCt@C@TGUh(L6>%Po5Q|?^4vw4T{@WNMBgG=ohzx?Vq>XNDh>6_j+zFWZsr%YLOiQcfwq)Jy6s?I7(V?I!(G zVrhT!Th{ko)&u0XjImB2zhzAI*MH4A(B}_SpTYkv`~+Cq9Qhh_~Q+W z+vkCCm%bVomUXej#Lv2*&Jy`KxPL;!;qE`Mecb&A#_s+DV|V|7G4>yX{U5;6<|2Nz zi0k0~2|~cxPviXN?x!(!_tO~vc|T41u(ZFZ0fYM|WZHkWmjcr}fBI-2qFfXwCV$2q z5&FYtR4A+HUm15( z)o#one$vAcDoHFJTPmHreqF`~?xoSS_Poyc$JJ@|__rPUw99F9 z^YadW%JHf6Z(lp@^l6Yxk9#(P`SXr{On*N29mY9YUsW|j-eWv>=OMM}pd;sZcQ>kR z)toh6y*zVN`}B@pWeYFZHG24H$QcW!@thIDRp9@B{Eud-xoG)|G)Ve8BYs%wQH<9#{!mx1zn1allx_6;pYC^fk~P;a9J$K)-q3e+o$*geY>c1nQ9}<|>#Xtiw0=?7KUI+FT|AZbfs9Wx?$l0c+qo#?aaF^0 z{VC5fo?5b^9zV#zOJ1(1|2XH=`;EU1*D-yIFi*uRN}mpO+U)#$W!*Y;ex`S8SXJlf zo`bQT_=>KyIs@ac($~@1<|b$S#_syM!;U+w%kfEX>$91TG2UOInNHey3*$}=TI+QU z=P^!xxShUJVNBb$AsBW@gHo9AiPOV{buk#X42-a7B- z)8QDeJjZ+E+&gx>}jrH@J9qjg~HzCm1A_>2`kV};LH z;WJkFj1@j(h0j>wGgkPF6+UBy&sgCzR``q+K4XQ?Sm85P_>2`kV};LH;WJkFj1@j( zh0j>wGgkPF6+UBy&sgCzR``q+K4XQ?Sm85P_>2`kV};NBPwfBvBZog&H%Ypf@4RBZ zGh)6oV!ktCzB6LJGh)88V!pFtzO!P!vtqupV!pFtzO!P!vtqupV!ktCzB6LJGh)6o zV!ktCzB6LJ^Gch@T2IVNMM{`L?h+8i(cIyQLx?3+WcIySkZoRjlPcy};P57Z|(s0_)<|3yj@*fw5aJFm~$&#%{g9*sT{ByY&Lw+^rWF zyY)g0Y~|Jqv19j-dH?U-a}eu_2lgmPM7EDx&oXxFS;lTX%b0jk&oXxFS;kJi;^cxq z*VMjT2|BI)G;HGTbuf1KIvBfq9gN+*4#w_Y2V-}ygR#5U!PwpFVC?R7Fn0Gk7`uBN zjNQEs#_nDRV|TBEvAfs7*xl=3?Cy0icK13MyL%ms-MtRR?p_CDcdvsnY$9t(S@+3$ z5O#;%61wLg`}%j)t^e?czxV80_AC4lH3-|5{17z=WAa1PAdJZmQG+lhKST|}nEVhm z2xIa?)F6z>4^e|KCO2mUgfY#b z*gs)Rb13#t7}Fez{S${LS##{4Fs3;a`zLG%nnSUF!kFez?4K~EITZURjA;(V{t086 zL$QCtnC4LIpD?C56#FNPX%5By31gZ=v46st=1}aPFs3;a`zMTP4#oZnW12&;f5MpN zQ0$*Dra2V*CyZ$h#r_HFLUSngPZ-l2iv1JDG>2mUgfY#b*gs)Rb13#t7}Fez{S(GC zhhqQ4H-}>X#5adx|HLgLMCG8MM_uZ1r%q*t+G%*nJk{Xy00s))ldL9I5Ttbpy`w zeCrAN8N1GK^EvxH^1N?dg8c7WuOKJ(>bZc=NL)J4D=t4{w;i4v-1Zr}{W5mtVeHDu z*p;6#z2%wV%faa1HxEHB-#kR^;QWvIQ9GeO*b(}nKVbU3rXP&ybFuXp?1cWngBWkJ zt|YzfNT4; zcY5~KD+8+7k1B;RUU$BXz4%mV#!Y?-wJ#p5!Z?$C%HICKxd&PCPWBh-#d00J}swbcPz;<_|oFn^cU}? zW8COQbN$xmdpX8yt?R7YSO1uCgRgt(Z2NX{u1M6WxBj5^K+Y$Vb9U4H54Bdv0|S0& zts^UMV!ZZzeVwVVb8qIuBubAN;@sWYxg(c8vgIWW{`5Y)KdexL@!V;b)zm_b8Lyf!Pc8b%*}uzO@?|yRu^voMz4~>} zyR)1Pb@s@c4tia+7(@lE_Tn_YRfI@4#I zE^Whemtnl{RCW91M(2*yswR!>mrpu(-{1eWt({V416&zbaX*JyJ==srr&utiM@EV0ppX4cbH$wv|^lX=}?pM z<<5*xpGV5jB_3DZ5K~*?rH68*3*ug zmX2-sN%szRY>~-~quY=T4?8xzZ(gw(YdU*g1@jcO;bX#C{xTn=u+8e%XZ+bao6Om* z&b`KwSz4HGZ**gN+QF^7AB}cwRXfWmPr)~wdz=#sj#S&DIx)|Horl%LwapmkZJSvy z$?vSe$R^eo??ksgI`JDHKec0g?NIw(U;EUr$JZ~(qkQs^oXRIB$*+C#lU~}V7wM~g z`jQ>A&kkfC?XwTrP5bOd_S8OmlAX2B&SZb>vp55+rUig!iv z&Y0p|QM@yzcvlqfj49qV#XDn)cTMrmnBrYiyfdbF*A(yUOBC;#;+-+YyQX+&O!2NM z-WgN8Yl?S{af)|M@y@YN@vbS}6?~rJT~oX>rg+yB?~EzlHN`t)ig!)%uE9_7t|{Ib zQ@m@6cg7U&n&O=?#k-<-XH4;~DBc-Uyeo=##uV={6z_~F-VMb&V~Te}@y?jy-B7$U zrg*m$?~EzlEyX)ycf1%=-nKLsFs6KNX)a*-DbHJ)3m8-Ww=@^99bC-zad`}MbU(}3 zZPS7-eM4fJr;Kl&qWR1C<}aGpjBj3}`Of<0JDLZrZyu!i(fZ~`nm4U)-lX}|`sP!b zXRU9ZrTN$T=3knZt#4kY`P%yCYnsQcZyuNPChB|C`OwAPXJAbK8{7{eBLw$Df_qu+ zUKz(la4*Z58$gEIrBer51IDaH0?uj{7OvwY?}5VnNIs`n)V?X(>|M~ zeMrW%&!%Y~k}>VGY1)TmO#5t__91!wK>KW(_8}S5KAWa}NXE3!rfDCNG3~Qy+K1#d z2JN$H+K2S*vuWCgPn)V?X(>|M~eMk#_ z+Go?W56PJJ*);7#GNyetP5Y3HX`fBgJ|tt>XVbI~$=J2Y|A$@sFx|BeW7j^6UHdS0 z?Zeo$56kJ=hp}rP#;$!ByY^u_xc2ew)51P%H`hK&*oU!eAI7eI7`yh-!aj^$`!IIx z!`QVCW7j^6<38W)`poylOGfZ z{%Re6X)u3=&>iP#KAYeTCSy_`=V^>#S7BSwm=0bs7P04MXuI>+>hvAp_|qr$oDFo? z9aOhZ3ygL!PQd6B;|GjB>359jfB)HiNFNWeIb(;<|J6FmJARH2Ieq?>I{qC#8H~HX zCbtCR?q8Ezf^p}3$B4+u|FZe+Px+JcD&@A=I~U0JGAGMiEps@fU;eB+N5tlQnJ51= zj=s6?fjNcR(a7cQ9KqO~BN)4L1Y_{ZxlHDN%tL4g{|1JjW8K1Zt z?z+Xt6P)kJCa|TnCz04b?s&!8U-+T@Pnhq5aR-kM#vP1+oP?YUj9m4nJn73Pf6-bR zz2c9PFM~K}hoBDxeIV!qK_3YEK+p$*J`nVQe~l0PW1m*mK5=8G*SLTGuL+K2ZBBj^nsuc{4e@I@cyuK=7cjZ-&qvS+k9s#bdI7aGI-61eQMvC z7WS!qXDZ}3!S~c;B=`J|Z3SEUY>1ye+rpNtcJ8}H#_qdC#_qdC#_qdCzAx&&TjV>U?z=^Wm5KXq zk+J)3k+J)3k+J)3QG?%ox5(Iix5(Iix5(Iix5(Iix5(Iix5(Iix5(Iix5(Iix5(Ii zx5(Iix5(Iix5(IiPsI4|e8=RzapQj7H*SpGH*SpGH*SpGH*SpGH*SpGH*SpGH*SpG zH*SpGH*SpGH*SpGH*So{H}J-d$IE@=#@K!1#@K!1#@K!1#{S^GabrJm-?$mqH}J-d zvHQl2vHQl2vHQl&y1s!oZj9YGZj9YGZj9YGZj9YGZj9YGZj9YGZj9YGZj9YGZj9YG zZj9YGZj9YGZj4>u`2TS5{igGlO}^j!PkxIh$1%9B4z8=+b*@Iv!8(`Ly9yZVT;F{c z)SSWZnEKa!#}w>~dd&G5#6dd*eIV!qK_3YEK+p$*J`nVQpbrFnAm{@@9|-zD&;ghoBDxeIV!qK_3YEK+p$*J`nVQpbrFnAm{@@9|-zD z&QU^AzSLHlbH;UThe>dpBGkd2y^HCo? zd&bj4&<}DO(etApmp_!+LHovmwE8biRA%KYbjX z@xzGqAz#N>26501K_B>6`2cbwtcmup?sew{UtayMp4aei@{nG^dF{V^eex)dBm5F^ zhxiNPpdErf@UQg&tQXPZ-;w{R&Y=3IkEMDo#otlaP(GYNdi~||HPve~*^d2he(Kh7 ze`y^`b_{dkAUJjj-9z|yjUD_FaRJ}FP?~Y|yjeWoRdR5eYy-XHe=5fGa%rD2oje5@?;bkDL^gPa@tx+8 z>ZcrTHto_ZJUXz)-wYIOf%jH{L_q3WkD z&G<;4F`n*+9ei}+k(iG&mSlRR%ZW_i?N2kVlC`NhSveo$PJO>JiRNZv+;HkPQ@lnJ z#>3ZKGWN_#g}&~NPGQ^TTg%v!Bdfg=I+pR7<)QY#f;x{RGQD@OTLuQnnl8n5%{D zpfHnf|Xt>E*! zyt~@k!I@uTyzjf?>(o8Qmr?5^wE-&L5!(PXO3JX~ecQ@b@|`tU19RNnm^8UNCBjLKQ6C*z+}W>LjdH~v1?;e&eXfgeP&Ja1j> zrgslp&3IDjwtCl*L>hh7n-HOIZ_CHH%V$;T=Rd|b%XFvB%R5r2!C!Rd_OA~5L`}Tc zigDi@+f-=UhKw_JORU>utj74z#XS1h`^6YP`C$e9`o|d==j&TrPucbd>$_*!yZZZl z^BL#!w$s@My}@{8o$h+f)bacsv~O1Ht>svdztR7Pgt-33*!4HYuD>yM{f)8fZ;V}k zV>`J1#@O{Y9xvD5SRU8k7`y()*!4FHd0c;E?D`vH*WVbs{>Iq#H^#2NF`W0; zO2m{BF{MOIX%SOe#FQ2>rA16>5mQ>klom0iMNDZCQ(DB77BQtoOeqmlO2icTqZ3o~ zU9$xq^>LgOKJ0&B9EXKH>f?y-MSj%d5&7$XU>xDAoMUP3ctrE+F!-v*cs{E0BYo%h z|G+q=p7E%UBdv2}?eIv(Bh?O%{5Vn#_{gqv@|5bp^TqswQ_Pl^x-(w4=Dftk*7)NM{}KBr4V-F#S>MVou7RM8zSKhHSD*)ZL?d_Bg8=B1|ootp7aas5c{3DBBQ z#x-&m=^qk8btq~y##D!*Mq^BMC~7puREMHQV@!1@YBU}rszXtuF{U~cHJYyuMUBSe zLUkx=G{#hiqDEs(btq~y3mK>mMUBRo>QK~ZjHwPqjmDVjP}FFQsSZVr#+d3*)M$+V zG|xVw5&{q@>RKBdL+jYelONbkLoyLZO^g!sP47m4ERwW$3N{0J(BVGr~SQ0 zG9Lf5Py0xXaE~YblQ(9-q6RLo>zFJ&&-a3?VuGny?YzkSfPekkG10Q$ z54t_Y{5SHgQ@M8V`KI1E<)Rw?>rw7&{+v{L>47DT*L|NuzkH)F<9(M4>8#IWWnA`b zaXowopDpSNHL{x=OZaS2r%&{>cWeO%zqM$Xr)yz8lhscwDXYrt595BvCH+iEc`D{e z%5A3FQ$nZj)|m0R#Lws~-%n&bu~2^f>6wj;tLiK|yyQ8?O(r~EPG4)Qj#lft^7*DNd%KdVvcDAbzxCyGPm1pyIg`#w>Fv|z4+`mZ-z;bR?%nJ9+OIPyhC26)YE?zpbUN`?7<73&A=`q9j3{?Me z@w~d(JCj8_qw{^IGNP0i=;y6~_uo+@;f zhtGy4dp)K=wNi{|mao^r^&FRA#7&qLu)4V@3 z3F9ZPT{PF5pJzFHY)xu=58A=_<#`$HZ&~^LTIU#?+x{_XAk*KWw(DLFXI#@hYnQd# z$MzX_y`=s0@_w8V>k3Cp+mp%bvG2AXT-tWMnplB;=RygaclK+H8x${UFRvZW_?fo~ z*w<<=V%&U4PW!`%A03|K>1~Z1ml%hSO=9Q&;Q0B0FD{ymm(y#sxw`p}rdC8w#(OR; zGP|xgKC@-)NRxQ>GfXertAQEOss!UHHmx~a((#$$t3UCUeY_0Q?=IV1an}*Yf8O3U z)suO@6BkG8W>bmo@Erqv{B@`OVIPiCp*M2yXPeboq8dMzfpIqd;{*OvwwV*l zKg_%8?Ka+t@qD>HG-H2tWG+{Hp~*8O6@RwQv&T$$btf)5S4(E+jE`a6-x!e1MzkBq zxb2IDZ1W#7GM-wngx&e+kGPYdlb@rmPm3tGJH z4KM8AtNT9nBpd1YUWeIQz3@BVThOcKj8|!UW#o1$r1@TL+8Dw(al3n}-%P#>p;wg8 zpi|74#PV#rl8;`Dy~Mb~^`g3Q$TqGoaxryjpsYL1zt8fpAK*_c~q?V1-E7jBT(Ztq=)@oTFp+3FEbFwQaX zEt_Il47D2)lI>O-d!W;6jE{ZX-Od=BiT6)l+TGh`S(A+G?psTG+D=`@GhS7pqdk)S zG~QfgbXk#mL~b$z=j@nKiyDRri^DOShX zFUsC?jJMhrr#7EiVw0!!Z_fF9|3QOQi+#YjGt_oUZ=}dmT~UWrF6e5 z&YAm(QnmH5OTV#f9Xr0Kvkn@@czTk~`p4S`c`xX2=U!Ug8CaRUg@XJQ-{__nE!@C( zSlIiz%&}w|^fz9AQxDAYG~@JbmA>@RON>tx%dLx4euweyOV?DrmCjhq8#_xKYVM3t z<-0|wJ!kB&=KsGi`oLR7{KUOlykP{!dqMY2BL0`(Rs!ICAl^O#Awm@{+cJ@_p ze^=1|lJ7Kd?th}^KK#}b2(}b<&_u%D1b?SNlk#*gs-?E()@)U-S7JNlnzD%|{jA0m zIA(x{zJFJJzGx-mSMR6MiRKPreDT}tdUEIDj8`oP)%6xfc-K7smTlba2|Xk8%&vW9`@^=p&E26V2$c+-IqVTU$% zV?3jIx3CdUjAZ;yk{V$JGEQM!;m}iI<)+VOd}_zHp>^N;hHfE}SjCY?KAHC?EHcLT&?BxxmXDnW!5MOih_wWuLTTml@Xa087J975|rY{|P-CN+p zJWM|o{f_B)bvo1M*DPb+TAz{WPxp;7y*hl(^e?|@Y33bH%=9tIcAGsDx-tFMs-dQQ z_ah4J7x?V1IjpNW?R-7ie6wW<({o%;YbQRRmg#$Q&NDsk^kw>>3^{FdyBQwHd2r4$ zvoLWMrk^rl_F&$AOwZDHg?X{SSr5zKqM%JNX$I$wacNhZo6lrndjD00Ifl_rOoP>& z*TKK#Zed$(N+B=kp2DllXZOc>LGN>_5ZY(D+dk80Qv2b@zGr%!`-@GQso{p(sgvJ+ zTQJ0+omWyXFh7rI!Spx1x$T{8`Iz3p%rYI8jbi$~>{&^UicHT`X`0z`cQ(`emCImT zrEI|TtSiQu+~?Ob{mai%*w(+aWBRTEBTSP|eqs8E@{ig5qXsbj`F92wJ@x|ACzQWn zzz2EoIq*SFeD3ul;ed8ds0n(<>DcE!~1 zvw-oZKh}*|)~lok@}SLBC9i}7-(EG-+vZvq#(g(`7Fwcp;y$A zg%5mo*?Va{px^H_-6KESXmfj}FMO@PM}D@(?TJhuezLGfezsRyXWV~C);e5%R?uVQ zX9e~O9{E{Gj}d)&16?XH=&k9>T@L6Ho82MSrFM0MXK7j9Uq8RUE zLY|z(cyIQ#X0qzTIBLWJbF^eZ#+j~PG)Y!W@__%-1gMHsAW1F@tU_jrV^^*Cf zUvI`Y_Z%?UR;*y0Of96J2NPEo6N`clwB=?{d38YWgABjhwfelsb2djY4N5UOos^#wom!Fr(`#;~QZ8~SCsL;J@# zlAKIO8zettv`u>PIEI8A$XB%XZKiuuuJhzD=NLz9FR##ttCu3*V@$rM$oCkN@2QlZ zUg2?B{>6<4#)bTiKF|K9$ln-~zbW!J#^i7GGuCcu(F?bkzWe$*&$ava88@2sWQ9Zx z9D1{Q-+ISyILGvvGs^S6l&{wN;|1RLv(I$B?X8rJ_x)_a8C^{K^}J_DdtpmWg*hp> zHr%xAq@lmqv$90P?-&y=KEs&WKwH@FvedRsGOt=FF#e(sA02%FgCBhWqaE}CjP{*A z$}kPT10B51XUedg=mT_L+raC4ubm<29>K3fJ4&>#M88_dqlKK>*9UC&WA1b_9eK)t z?$a0iK0BZt#?+@4cGJ`^{f_m5JdD9haxz96=)={E_YQ%{mSOah=@OGah6w)PIFhX# z8^`+9f5bRa{^9i|#_O-%O9}4vC48^XH(tR#+kgG{Vg8+awiIr>4x#(W^gR->>yy7^ z9n!03aeOx-;{0!0hb&nfL3`}6>yy7^-PmN^q8YAUf7`l|;*RzggJXyFuUMl#^qT+Q zH+I4K4*o07&hUMumT3Ha+Vq1l;!2#sQGCUo&FQ~4PdeijobUd-=eu+L2dL98c46Nd z)~6rishP`r^QG#>c+M+Jy*CCnV|=cEV$(fIb;j!&7BTdfG0_bDjxq5X`iuu{QX7Wa zVoYtD=b!mJKj_pa=w4vZ(T9&8eE_2!^Z|_a@fR30{0LV0F9d&Z99=vAr;VepHph59iuL$lH9EMjLVF9?6B7G2|8@Ig zkJ>o;>U6~2U%jtVqsDZ)dw@TG-yM}l?GBZ1yvUZguYp=Q1o-i@&UtKj&8^|Nt~)sU zp+VuB?mD>I;UwXbXY{u{`LibqCsogU?|hfhj2as}s|P#$zb5PIkvtVP_h9}VIiFL* z`Z;%*y7w!j8a(Z^)9KeN>H(exotS?`=;x}%&Mu7mwdk)xbofh6P?G23@%NZsCHnz2czG+v6`FphmR4-bcyr6uO7e6l z)R^gYr(af?^EF|-zxY{oEoC#t_val`l4swyuQ5GI?R5I7J@pxHoS9q~ii%*IcUK}U zd0wgOytkb@B)i_Vzb5lkeda0sWc}KVYpu(uB~O_To@08OUd46R8Jh9(m4)@@NzOaa zq~3g5@_-Lx4cd``r5GRXQ&!_I=%7g+$N@U~L|edU8+`zyPssy4L5EI|6&SKZ2Vm$V zd0D zK6QwE1sJ{q9|DF?Ngnty=OjWyHZ4>YEXF{U)u zj4{@dhkS|Y@Hg@q#_$>PCC2b2$wR(sVH5Z>`6OfbB>5_1_^RZgSYSHhg?yede4b)~ zF=9dTP^>W>@klYn7%@e$#u%|Cd5Dkch*64J#)w(^%NTJic}NbXBSxt$#)xC;gE8V* z@{pcPM~srJj1kAA17pOo8!<*4OCB00rXxnl){GIyGzN?j$C8Kq zfa!=)8cW8AV;W<|h-1k^am#eXDESIw#4-60W5luKAwOn1Vw8N*;iotzA7zXl{_NXS&`GM$aPloh+Jw#&a@(zTFE1FwG}zpid=0akC+Rr$oW>x1y=Hi zxyFh)#frJcN**znSutl>F_&4%Bj!qaClxy z#IfW-9tS^SRII5m)=WnnOCHP<;75##H5+`1>4;;=gLw%2h*7a7gs(CkaV&W-&w(E? zD%PBc1*Rj8B@gCN@FPaWnijFfbi}dbAwH%fM#Y*LvCMSDvE(5+n2s35T#mjF$CN7= zBaS5x>B)4&DAo$#M;v1f0gO17JY+|vBSx_n0T1FBYZPF_vE-p~Vme|JYaQ?)j0S{q`G z2#h$EJQOEPM~q^v2_D2T)}X+MW648t$aKUg&54W=$D&sCN*-S=jJB{=#!tkqsD=66 zD)t%i&f48$`cenUnmFO40^U1?~piS6D$gfL(e`kgxPwd?-=*4~b_=SDA572R^ z$hlWkhH1jizPnr8h8P#$-7TGD-lnM7KE2gu{&3BC+dDATh?qI|9GuIjn8xlq-woER zK1uKP@tL$uig{ZUb?{^ThkAQ_;Jgp*R=|2&Z*|`7jv8{rJ2bIFFZJ!u-p?vJIP0~o z-Vc&HJTs3!W`3>V;JRsVd5aBm@DsJpc|WkuJL0IfbC|G-&O7?FQDscpo<&)PQS)9k z2MRgwlt->Z4*KAqIci8mg1?^0(a?X3?+G$&x9t$0Ou4OZ` zt79Q->rsfUjo$?QZMw%2=^D}+en-fizSDg2-OCqAo(W?$_zj&%SG?~9UUB8ob zin&rIH}jXMHrM1h?cgahW}9AL=3#n{$7h;)iJiC41;;Hnm8U$#^v~vgYxX4N?;F>f z`fN9oKTOZ`G~0KZv2`*qKG%4cxnDFR<3g9eH-k5(Wt{!SuO|JxCm9zTx6fq%EFI&I zO7Ag^V^T667k0vg4shP-7fpJ>l*|1%(W8zp&&VjLBat`4eOEFH8Q%nEcU_KQSi%vgBus$?q)rD`WCs zOMc0i{M3@aGA94E`@`0tiz&w;E zz|V64_>nKb13L1Bk01F080{lp0Ha^z3t-5Jd;tu-kS~BCC-Ma_+40|G90K@*s7r+=Vi82z9>VDu09fFUpR0fv5%4;b=7ZeZvE{efW* z=m`wHp+7L}0eb<%ey}4j>qw7~>2- z0ES<{KY-yc@F!sS7yJ(x{s?~phJV4&fZ=!WS77)r{1O;`3V#KL|H8k4;qS;7z=#9H z2{7UYaRrPxL!1C3ZV*4fh$qA$Fya#N28{Sa90DUQ5x2mIW5hEs;v4Y~?B)Z;xD$?i z0Xp&l@&YjOgy0Vs^l-snQMB(7{d$C)9-)^<$mtRCdxRa7(AOjE;1PCH!k$XlUy1Qj z!v0E(ixT6j#5gK3zDoFm5`LnDUn${-O8Au${-%WAD&e0>_^lFtu7v+95id%_mlE-! zL>ws*k4nUy67i@+{3;RGO5_35wd@1*lk)}q0qY2nAC$;5oG-vbzvp}bjCG30OPnu2 zr~Wx#0F%6&FMvru&KJNWFXszj(u4B_Fxi9i1u*H&`2v{i!TAE1?8o^6nC!~=0+_~u z^93-C8|MpP8VAl7z%)LbFMw&BIbQ(Ncyhh~rg7$c0Ze|u`2v{yh4Te4`4{I4VDd-K z7r^9SoG*aM?>JuolmBwQ046`>d;v`U%lQJB{GIa!FxK5-p5=T2I>j013t);H&KJNG zPn<7+DK0r*08{*Nz5u4U?R$Lfi**jnO;{bjT^zOR$4NJE&L0`U-Yne%L{*(_l~Lhdsr5 z597sjjF(vNVO*GwaS`iDj3d)Aj$%Cte_%TNL99#RS4@XriFGghis|qxvA%`hG97*^ z*2C~yro(T=x*Gn^bojqmpCi7Qj`$MmbHowT5l3SEkGNwx;!dpp5x-1F{E9jP>jtJ% z{=hmzV=VAf)E&qV%!B*@KJegk_(9u8g1u*1=KETiq`2ra7 zLT+H_fqVfBdq7WM=#6{<412&{z_1_k1u*Oiy8~k!kS~BSZm>Hr#sT>P7~_L+1;#id zUjSn~F|NQEXXFcD_yzm}82*BM0Sy0w{{h1vkuQMZU+^ zd?Q}~`|<%W_B6zPMMdNb(2*y|Z|INn-7-NOv_sGb{vAH>@92|98ucoFhZz0%D=_9I zU;BSCcJ8NbZu~L5+5f9?h));%{420^?S{7h3QWy9HbOst17;oEzJl1XdC(3)JN&DB zKs&L8|NgCU9qiZf;h-IYb_n{wBkBWGD_f|Bn)#`2nHhVt*V66VpTs$FNTRGwb@y_U z8Mp7+K{qU(hjG}xk95IHmzRSFdAZBNNd9cD#36dn8_r$X>W81ws}@vddflc4b*c+5 zGX6PNUOn-prx~BEtaSI5DH$(W`i9P0ZYQ^&`cO-4x({&rdZ~*(-8duTS~Ys=upOiM zZuX|vdh6A{ZZx-li?F>`M62kli%jCP5%%}3tJIb+qs`mbBJAv;8&#w3UzjU*BkX|p zeo%ww|7yH9B5YLEk5!@`n@pt(5jNGtD0S2 zJ|;xZX>dI}Pe`QBbSp$pSTojhnCKb4xvyR=dDheNW`w>w=eC-w`^F5s6QS!pok+)g zRm-#NUW6VnGDN5G{HVIU7HMz(@wu`MSE?knBklbGi`2Gt6V!&6BJGV;+tv7-ZB?df zk@nI{$JC2^bE)v^k@k;$S5)-_V?3kkM%o{S+*1o97p|`QYNTyCkG^Z`jc>e(=(9T( z-c@O~6*g_?vzyaiR!8b|HPdQD+M-tt5>Na1cJ@B(> zPyE&P4pYBWKVxnaPIbGsYG3b$X;m}QzV=d5HFflT^DBL}!P~7oV}^v-%Jf-Ve_PC^ zYPU@};{UkeA#d$Pf0&6R!|e@K&EC)Vni8bfq>!QJ)NQZv)`_%NhRri8r%g6*z8q;w ztl4T-ChcGzr_X+W=ZJawcy3dGbnG_&is@Tmgg05eNSk!iJ!3c43hzNO6rB-b%NN|_ z8G*jW-!a?9Kc^m}zD9>#FmJaVs4UrGWcvMPb>i9T-Pa@St0CW-^_w@Uvadwi_9Ld7 zJ$nzT%P&USVy%0bbDv#OMTmYb;u&*n`7PC{7TH9f^pcLs)zM2jYFEc_(owlOdPqm* z>ZnLZZnLZogehki!&RQM*+5J?; zhz;s6)e&P-N2?y)W~+|0_MTwYsXcfi*m@N0wFp}&d1CRT4Nu~aZ}yx{+ek*>-;}1oK^+Q za1&1JjY2toR(CJVH;HY%JPmfAGmVo( z+8-~xpkC;Cz>K;XVfVZ;P=z1cXii^_usv0@nijRd{BkwIrr8mr77X~pw7(Z&??(Kf zX3cGC7M_lYg9>dli8w#k%B>PYgw>fpf$ySvFDm3QrQHStJVIvG%11Tq z^3rqFmB@Xn*!2jT{pL{h$*n(B~bQ0rc5nn?5zimsoY+c!XWK zW1d;keVXb;^|Hya#k9HETX{)_eyb0evK33HVHOPC1Y*@Weh<(3dX7dZ_KDO6&GbL|xGnH&o;fvqRlY$w~Eda{H{k@>K>MRLxZ)?2Nv zw#B?j@+Vq6P1S#Pp84c_gl&*@je7F`vG*2mRc+fI@W$@$?!s<`HHY2Zh1iK07#N6M z*xia^cPp^xw6L+TJ25b@ML@nW#@gF6&;7mo-u3X#ecyLK`2EgtFqw1AF~%IV*81?#eQ77^xkpfX>$h{j<)?)V1RQu zfmj)|Eo2^VtrYrA^nce$om!b*dRBTV?xRgQFX`-;P8+g7LWa|E-pit9LkT&ZtzX`NYy1^KKfZ&6R3%LkT6 z+fHffpjM^aZ>@-HpH2EHzqpo^wUFof#h+y6QeHAMuHA6zv2I>OA^$l!wW^Yz zP&VhnJ7tb@H{~+CCv&6YY`Nh28<`GusWGUTO!?`D+<-bp-i@|yd}mR^QTIYuN?FTC zSQOrGQSR&08yn9?%2H^n6cxgZ1GC@B0%$|u+4V&DkvnoMu61*tA%09aCUfBUv`gDW zicx+tFU}u0{OCf^xtXio%*v-$aBOFN9i~0iKvY8a~v5Z=SH6sw~$Zy`DL0>i00@IJECvMm&sZRZ`7qiwKuZY1_yBvb$q<+hwQPws!;@W|MbwJ3N=b< zZHzYAo6tcGTJzj`A8oZaYm{8~rna1jHhhuwy}Sq0CHZYl&%1J7@K$*Y{n?|>aanKA zDLD-N{D$WSnSb^JxeEP1;qHm@;pPuA82Ja4uOf5qj+TpYZLX8S)_}SWYAwdmx30c{ z`+MVem12B(MGY|K?D{SjW86K?o=OA_c_lleZF`S#6)8iwoA}%o znP9|55sdkH#KR!D{naE<1L@0`@5`ijokSj-vkBizzq(S0;e%^u^of=kuN`!*g0`(! z-9bIQ-QAi8ZQEe9MeS>!T$Vx^YNd^kDy)-Shq7Ht`C6_Wzd+u{wLAA;lLfu@$tGyq z<{kWH!;QgmGwK++e5L$$=9z4Rx*zO1Smt^9MGiol99olCdR>i?qtR9uSFWaAG4PHdP~X6PQKIVlYN7$!;Z(73aq+pr3%@7coZKwZq1_xypA^x_ zgG3>;=lr3YgiL#1yh7T@H${wE9WF-ToZRDt_>n7`>)_q3w~SX+9N-$B*QG`moU_cf zz(735pS#;zqX$KZb0|aK#Ytr5O|Qjklr2H~4zk(U>*6%-Yjv3~ed`8@d*~-Sr|y-X zSFI9nFg8m(y&!LgdWcZe-8=g;`Mya3u@P<3anKiOO}*Y|O@6yFMkX0t&c86)@OB5x zw_>$*1^Vr*-Z3)sto%}-KbLa+O?8_jEy0VZ2wDn}pZk&2j?f zf!h^NiUaMZ%K4Zd-Zi@?e&(+(FQaYSWeOK3az3zn$K&1Z`3`x{z?{5hKc?t$t3}Y>evY09!Gy_S_Ru zb=`7&e*xy(Ms=52t3CW8PM~d1UCSe@<$W%0yk4?f%w4xe zjz&2@wLLF-hIz^q=o=XVo{0Thi^{yH*S$%f#e}artm#nSBE@1vi9QPgN~0YrqK#)X zT4-cK`#4>Q5gD`R5)ILAu1&s*V|Cp{Qal%jGtWhM!4)DH*RCshNql*5M65&m`@GpF zZiikKNzmtC^jaiTp6Fr|5%0hHoVYXo7n! zTAygq75!ns%Cpu22S12us7un#m1VlD55*zWadyp#a%9LUkq>pRxqX9d-*>C1hPGWa z^|)*hG+l(Dt#Y5cBR}-6BYesdZD&?&?=VTDZ zS0=x;vQUyIavj=M_8Tqpr}!+pqisvIEiQAu!yXIQR_wRWnhJBl5scq)lU@e2j*5|O zFs{2anPbch_$sfXZBup0F47GMmCk6B(g!~HTR+IGd~!y?g~ z#qt8$);G;n;XR|9tc!UjV#!M}{Y6^Y8Rx%f_gxeT9Bo~Se58j39M&vyK92b+1E7t6 zo-ndwuAY7=TC9w$Aikq*OIG|S>ZF_?E})#HF5+{QwSM9j%HMSFX)$caF|i)=WQ`u% zM4<$C#0t!xT_R?PnnT`+w`kihiR+8&&my@FUi5fp6iM#@UD3AdDyB6$U$KC~{G9i4 zY3nz<&TNYG#^@hb&mV6@VVv_gqNxm6d`ry0eVZMfC5=x~lt$ZHeRsugc3$meF`iPjyp9aK5w|9s;(=YDB_ z%3HYa9iO}v`=5QXQXOnQFH!_M#;M!Z z)54|mMDYM=5&S@S6f?vD%rg_0gp0IU?ism~xv140qQw4~qDIr?E-LF@3p8$XIPj!{ zi&~4lRjWsPt-a9B3-GyT#@5+o2OPJ0d=+&|bd-*`cF^NjVt$B^e4E)t-3-4ae4RJS zZP{E@V7DOgDT!6yPm9m6Z|@TEs$P+)Qn{#S?Ux9TK~H4A)GjJjDNpgVLbwdd=%PAA zI*Thse#qH*T-45TQN}flyDP<9)T^Q+jFXWTwJ@)Xa^IQAscjjH>W=pooErAEj>{K` z@Az?1@jAb?jxY34KF{T%if1h=XL>%DEepA*{)79=pT)1ss%2bM=g_$_)#Kwb3hAib zo8{j7J7pyD?>ojS2lQSl#}&r=5=k%1Cr!NNE~FQyeRbqYM{sfF3LM(mke1EEOz4jdzDtmj(6_~2c#qXCdqM!UWrr&%DJhXJoo97*jXK) zw`M9R&vl9vi}60v+8Gb5F2OP4Gu}rU?%dTX4_IIU-Xr>&+%MpKB@1-My{hD{YP32V zCC1crQTIolG$y-$72lEm(LbYbc6lp~;r*ouue##N%Ew{{-a8s_V}vNTa=jJr$-s<~ zF(Tm-U#Ib(JHe{D4lw!DL8IK)PH_16SSc6y-uJVyrk(}jRl@f`O#)-$DGSsr=>jFb?hnkpFk0L%<^rxa{H?F%e-?X+ zyTHuC`DO8Wp`vX$7x>zympr~SL^KmFF#73yIr4~AymfYg-qm(WOOg#@YDE{=@iIs@ z%s5?KEAIm3tKN~PkF^r(a4(cw_9du>;hx@1;{4lPRVn1UBI)spL|vXKWkju1zNP7A$#0^N%!txfp15d z!S$1z*uVvxj}?}CqJBt!!`~V<+fS#=regF_ZK=+&pKLCgypl7lYpREJp z2k6;4;RgWm1N3a2@B@JO0eZGh_yIut06kkL`~V<+fS%I4*=o^=-E2q2LSN{^bCmb1AzDedbUpZ0YLl!JzFRI03d#Vo~;vp01!Vw z&(;Y)fN8BbJv$)$03d#Vo~;vpfOI5`1mOorN5V)Det>i&jD)c1NEivi50H+8ks$m4 z=|~s}!Vi#+gpnZp0O?2=3BnJMj)ajQ`~c}l7zx4;kdB0rAp8L7NEivi50H-1h94ju z2_r%H0n(8$5`-Th9SI{r_yN+9FcO3xARP%KLHGgEG434W&M__?c0*DvHI8TaCL^%#t#T%f_`d$N9F4tq z(505*!j#+cJode%CQTP*tS9BtR(KtEVS{M0X@?w%y?vc%tGKayzPy3`K+1(7qTS{` zvNY1Gc0Cuhmlu-DF+X&h_er#IJZ{~Oy?x64Q6kHS=Yfd*hAl%aP``NsBLU9eHv;K1 zM~%05T~<9=v@qJ_5m_p`z~e`sMWJ)9q7GgI_RjlK6gn_lMB{j!DL2F{@2%ot85ii< z_?UQ+`h<9o*QaA|Zx)dJwn&-I1+15R#P`8rqG~c12yeo6m&vD}dE}~@82*NgibzyR`YorAb+W=4Y_Au^NcL2mTK*^*B0++f+6Se_ToVaQ| zRqBI4Yy2>-gl&Ksi`U2{8J-fh0X7cv zl)c7$CTs(=E>~2x`1+Hu4bZLH7VG{txL;T&_;K!3z^H^4h1do-ePD@UxO|m}ZGij- zbBVhXo=e0wzyd#aabv_q!ZyH`@he2b$@>Z00J+;85lsUZ61D;SZiR?q`&bo=R|U8?tlZGdxfM0qX^po?=poNI}o#?UEU`tR-v%xQ3mR*WZpJYy)KM{X|xH;Yip9=$`Pi z-1~H=f!GE}8;CYunbH}t4bZWrgYvIA--_4~0dV4KTKN zs9f!}Tq3psyenOjkNO-YYy13b75aG2GL-yRm~pYy-S6KEv5PGMcaraOLi4Bdo$liP#44X;o1)X#Y^sXGy+x zm>|^r(}Zn+z#e`g-t%pQZGaO4@!t8=8T3pCBDUNScTUwKYy-qhcqe*q53?e+0UjQY z6s^Z)up+hra(~CqeY`4ZAhrRnzqi2g-q8kP8=&uxA7WhPW&*Jd@a^#%;Z|d|Kx_l# zyn9oOOt+J;4N#%65}(tYBWwfY^!F8?4?QMq1FY=sC5F%ZMA!zHzpSJ<<^7Ye4Um4y zej|TV2S98Cj5=1yd0|BhAhrR@U7cwiSNWSjYy*sKnN`-k7Ag?i0O#iRmEK=25w-#H zj9ez~^*%`02JrVhBu_;xCTs)L7gyz};2wl+fI`Jy%E>p=3s;nF-TiO!!-Vk$VjG~B zGk%Zd{Jw#RZ2+eh4l1(uaVugQ;F0(#!?u-^h;4vm2S3WJxyMVyHo*IIk7Sdc>m_0v zAWPRXve5LSgl&LY&$r8@uWu8!0gmtYkypOFC2RxS>eWzg7!*m^1}IhSgH^t^D8x3v z#4EY11`K;E5!(O_RyG!a8*WL&Ho(lZv&2)!ql9gM ziCK3D-?Qro+W>7VoE6`1coVh(Dkgp`dNwFS*aq-T`$-Hb>~BSE19(*bDJFz;4Mc1M zq-@{-HM&m4nCS%D8(ScSZzh4*1}L!pn{Z0dTOhUp%8hy<$_!m95ZeGZ_FNWwrXD10 z1MF{eNMss#g|H29FWXXaV)_fhHo&d6y~WL8-w4|PX%=S^?ugYxYy&iyF~xY$+5r&T z0Lkx&z_#Ol61D*{e-5;kE&oX%wgD=~D?Y<3EKb-d#;n=Pj?Wu z0ml0(>GNnNJ=1};cwg{qf+mD*fGfS;$_iJ%8i;LxJ~<*~M2?~cVjIBco<${ZoYjih z25?H|pmt3CXhm!T4BQwgxBhG(5!(RE6TQPY@R5jZfF16)<@Ma#3EKd#k{pvW+MOY6 z1FXHdUOsH~h_DS1o`1Z2zVIVq8(?EZIhn=bCt({vo>tauwHy>;8=&N?$$=NTTNGj& z;CuLZ<6QFZgl&KqZ_|q!xn4@dHo&`KJw&R3R|wkxncbF%*EJ6lwgJvAIv~6&EhB6L z%w2t19C_H6unn-~MX2b6evjA&$e7}rXg%A6ss48({vZ)3R{K350Ec z@U;(RqfHeF+W@sQ;q#4NK?Y(Q;DC&lR~{^PMr;E#G#u2Kcq6TdZGg|77L~bbT8Y>O z7(C>=eD}PoL~H{LKKfF=tF>4nwgEirT$Kse? z5U|Zr6s_tRela(8^GQ7rWokdlCTZX zqvjjY;k$*f4e)Bf57BL%VMS~M9JE^Cl7D;yu?_Gjj|2Shdto590Y){563tX?f!GF^ zkpI019Wh-XwgE;)-Vq&(Z6$02L|c!GAuCQ1wgD2n-yjBtJs@lYdl_TrR>k!2Ysd zWxJV+48%4-xQda^WyS;`wgFr^Iwu4*3B)!)(U?~v=;H!`*ajFE z9wL7D?c;9!h$a3NfVH=>|#JuABtQf*JfS9t} z=#4lD#5O?fg?|2{hQtuI0qPgrWKEIvi$H7xv~ONWHeUKvAhrQgpB*M2G`&FB1~~4z zTJE^Ghp-KB`+I=QG+`cL8^Alm4Vk!KJHj?VaF#H+ePSZQHh|lq2zfts3j?tYunnIH z7U**?5U~w#rksN+fApS}>fp@KD0z5PHHp{;*iboK9!)+~BDMkgjlU<0mfcL)25@sb zDKFeUN!SK(vTT-e^nJoMK+TBBGW(ox!ZtvojY7JHMG>|E&O6_*9?kEd5ZeH$Cf*L* zuos_`qHT)|Y-jXe9zoa!uw+jvcCL6W5!(QXi+4anbblE@*aip)+9L+8 zSVhh1ikbiYy)&`@=SDfDnQr<@M-=<>>jhmir5C2)FDRf+_%#ou?;Y*g9BvW z>uVsk0kUk35og!s7l>_uCbPbXwzWM3VjG}f-De`b%PN7`25`<0EJTU`!ZtvMpuOT% z!|Q}?fP|aoi<{$K6Se^w|Lh=2w~ruf1DvXxR1BStzJmF)ztPFK<>UZ}ZGaW8PX#V3 z6U}w7LgSm(`bY6Q>Cm=5Hw<~c`h9`e25`7GSr)7wMA!z%SYeYKpJ)qV8=&#G6SAM< zRKhmEqGR`D#m3bM+W=8X!sYfGcMZfgz@xQMa#_=N&Q2)9tgH?yVsT?DVjJMg35$Br zBauXG17wVdkkc2nm56PCCKbcvf)(>5VjCdM!s~MPrQL*WfS$pDa+c=>!ZyI+-K*u@ z^-l@g0QGtfm#H6oCTs(||4>NQFBn7E2ADm|&w2%M5{PYp@twv69DNu=*aoNxD~*LQ zUnF81pu?v;qVVTu60r>spazNeH-ZV<0HN(yioX8)2-^UAa`}rn=N1sQ0p5+jCML~w zA#4NWdhtq}OO}GL4e;&zccFUpvLdzth7PyDM2|hrh;4wV8V(S8`-(wza4Y7>B4wNe zVjCc$_6JdH#Uz2)1{h#@AY3bL6o_qr3K>p`1L;o?wgD<9-zq{A-Xm-S)ao=%#2^2j zunpkyv8L$MDvGcTkb2-_qs3JVAhrS4IF>dlTyI&}{`vRYWAY24I~*DVwV#{sO5415 z2&~Hz&f^2KcY_jz%y)Cd_iYGGwwdqIC=aD!^T3usYxA^90|9yaFn#sWO%bqTIMdBv zOcOc1&36la_PuYU*=oL*;p^_^)+bd)@tk(m+sTy4%=c4F>=`KE4(`a~Wv<6pTf5a{ zI$_^}YVwFeO!pd7LsgGXz_dkmP)R>amUGI~0m^N=`EHaSZ%3+l`FrzwSQaetR-K(f z_;dGT){Rw{j4Awi{Km;gsLSoHGu`}9A9c2TYDK#2D%(oUZ(NG$iF2x|mggEU-BsjJ zpFPZXX7%^^DErhl-%EAA-v)VnwD}IHgawPrgfZScKS$Ah0heE!J^TTyLzBc=mWWP=Ok$}k;vtTJR6n3id`9W7vI&pRw<;Edidb%77l!HtK5 zZ|0Y**Twc@;l&zf)_0`8H`Kb;LXa-+CXRyBSB@|}+s7Rux5Wb*@0%a%rE3AEi`A$F z^A}WSI{B2s;FGii)1L|^f}`;VFuir`F|ll|`Hqi+sk)1Y6U=k`5k1DJebPMNi)YVR zyZ18R{gHR+M47B%UtYWN(pBmBwH4Dt(xy@ghd43auwzMexmix84}YnzYD9l#Ij5iN zqP!ArW_tP6!Rl_el1%TcF-CQ4SBAeEv1pXH$`F}Fk}gy8cp->q71JZ= z+Fi-;EQ;nNY}i<32&u&MBu9KVM_6;FPfSUt)_yeKYi5Mrlb6DV@p!&!vt`Ay=6k*_ z?fGbpIAfma=gWnS3+G4ioPPZqi)+aTGJUejA<^a<;;rx}`#1+!oxL{Gi#z0pz4MAN zy?tvn$ki+{)6vb^L#D(hS_^r>@M&|ZG`@Vh2nrvReY9BB={y-F}WxRo>H$zPvof0ta)Fn1TG4-NPx8oQY9 zg?YDbt9X`p43DeT<%EyzouT^|Pjp_=%8SR7d#9JXBR!ZNmuQ7_b?Cu#j*Bm4<(y5J zwp`Dw78N$%q2qDCqB_1RJ&zA9+*~#6`jF*3+`gBJd_9-xRMUp3DI=m;uYyU&D)%hu zSzrI_-s)}gdTfX4X-BI^tM@a#XvRSGshRnGYl$c0_bIf^r%2!L;kDJ`6To!OrA1Yj zMeUgO9i2qw{??!AsM)7v!+0ajIok(FOH1<{uOC=wEuO%nr@8DiI%V|aIo)=R5!d?n zV|uX+7PZE-VfyT`_O6z#c`=}kR{!cf;xrfaY10SN*!0nIrR)&x8r zS75qV;qtKA)qJl|?L!$L<5BY+Kmj)%i@W)T@tidC7l zS(bC!fd1-Y*bt^G?eSDkj<4Y}ZCKe`rEIvF&$MGcZ}o8C2uZqp=HWOMGxbl{t(qQilvOrP@02%8F+-yu`=IewpW zNJbv_TF?}V)i>WMnXO^la0Ktn=KG%dUQGsF9-HrGTD<8{ARQ|zvnXb2^j&k$+$+CrH?yL@Z?PYp%_&{}jWlg5@)*r39wzu$^UU}%PtYza% zlK;U|FLf#70;VTd7^Z3reav+ATRqjEoi6~LuGeOI z$jE$fp|1k^nTxHCz8G5MN#jvY#7G>)b+Yv}lkk=B>X%~+1? zH&?Fq=*4T>etjUfKy#)CjZUvNC$Ge`>-Vxsrq06j^AC;H+7ho=&TlWftGE4EFg-iW zL)G=oz;sl7FEy>=aLz@`zI&@1U&~6;rDN(bYI`~J{jK4H5ZM3yE052BE~-YkT#DvQ zuT@`#8qQ2-^)8`Y7q@1*V4jq!;qksqFAcmbo%f7jx_FoIGUSn2L+?yf){leCGo37^ z8il)L@=yw%6V-6ZKU zZr4cFA?q=wduJJ-Iz%Q^H140jgBn-2Fw?$gtE+tJYcaihNddJeStq7XU5}?04tHm| zqv0>74l{e6ZqHlF?1#;Bj0gtnPZ#ri3w;PRGPw@t`3b1=CGx zr-kG9Dl>f{a~a4{I~&vf4I4q#%n@kTf`lyinX%vkwo7++a7cR~8 zgkx3I>yZta9@IX&nibWR>5!S>GMk@y&GO1=y==aH43EE>SwMcWU9wsaPn$e#T0-U)w^+_jiTl9! z-qV@By<#{N`1yeK>NILBc-L#n`X=7)4aq9E6{JgvdZS>-hXAId^0-5lt?_}z5Bqe4 zpJ3Xv^W>T^u&!z6mIn$!4`0*%FH0nZsYA_k8P-CHl8?;uI_}q5yqs^IV;jTG2qty6EI%0JN&Iu$eJaXgR= z`n@&fw78uY>3ewcoD>&Fh^Snqj=Sb=F$OuA^n35s))xoOIrC-@k<&cQUSjF9GxF&x zlV^h&NmcHT=3ZGQ;kypInZ3lIBXyMFVfGTQ3wBnGtC_t-x~PGwM}D)HNZfR^3ibcV zIyQaetz0*my+oErUdpYt*-Jz?4pWylnZ3ly^F7rmU$d9^>E28|O;n!k>FZEYy}Z?g z=~ve>sqh76FX1*bREBgidx^kROQp|vvzKVPIF?Ml!Z3COW1oJssUHie#6lO2c zFSRF(=)9kOyRCya%?P{l+b^mmAI)>xOsXe}TsO}#U&ai^mE@-1 zZug0@4w+~65)HS_l?8g4y+opt59Q5r&3SEwnd#N7ZxxyLO;Jt-eaOso{3J~jM7?C0 zmwf52-c>bwiH@H-7ovi z952;H-EWXfk-p!{)K^>UIWyhQql9wY)SBsoiBhVam&{&b@wm%!)M2xi@GCN2`aBuS zb5eeg)~)X5nL0F|X85-=dx=Zoy+zw;W-pQ9<_WRBi`h&3sF)Zk1ev`=dygWJXn@&E zv`JAL`Y(21o^ZMo7{kn7Vt{2J9DLW9WlkG33Z8`);WMpq2G8-6*-NCXFc#*S9QUP8HriLuknUSis{ zRiZ?8vzHh$EvuLlWu9sL*M$RH*D-sElBr6{4|fLx*>KyXO|st|vzPdI{IiTm+Yd!|C8ijC6RnwL5e+pS6F4r)(NvzM5)tGXIi!t5oQdKOT*Gk4-S zJC4Rv>&Lk>eL1PWJUnI;)5Tp{%Hc=MbG#F6Sbugj&o{>Fg%Q}s>?QiQ@)1*(n!SXh z;~lZjzXh+o(J?Kgx?=Vc@e7oJ%Ehwrc%m+i;K+lwe0JCObc0-OW-npM;Q=+@<>K*M z&&Pm6gO%J%RL5T8R-oBSqCH^S7A2#Ic3fMS=Juc>LPPDPqrBGakKyLW}~-%rlMY(bGE0_Rie! z0xt6VJhNscJu2n!^Bs8Y(U%F-;l*Z+JKC-gUN@PwuVy{$C0>~|aX`?jp7q9x~_<(s|L*i85NOyi9otFCV|dx;+hhO3KyW-qb5R3A0hFl%>8 z@0O}kxzdVs+KtHLSF9-w%OaM^r^*&C!uxL*418pHGH*+rDCm)O^< zod2`K=J>fb`9+}BoL_4FI&r6n$tPXtdvW%l$$wGO>=515+}CAA73kR8lxJ$UmXIa8 z*-I49&<8>bnZ3jdzu^$+WcCvAy~aX|_RUz|qT9To;SsZ!s8W3tlq_M|r*uYlSa#I3 zTf?y(p=fi{o_B`Vgb!UzJ1<&N2+Hm;?f)r#LfGbIo=b{?N`!`*y~JC`&SLf=^Bm`O z>}z=Xndke}_o~%Doq6ur5>Js|PMZDzIj_rznyvUu3ujNQ8Z9^dCv%NbYFlg5uUro| zP%nZ^f2-7^tIF$Z`eAP8Au6+HQ9jeUo@3PU=|SwbmwtMyb5C-zKQ|8_qx_SZex9PZ zhk7y6^#5uXx~Wy~vhumSpV>$i-(ki}|N3RrbYC-$8jVY<_IsJ}6}Iw@Tv^MEyY|<7 zWa_qKdF`j0FRe8L%s4$Y)5$nB!;IhP<}E~#C1zX~TYN-pDQ(94#zpZUb8|Bf1T`)I zsr(8vpG709Ln|=zMp#69IJwizCvPL%VBq-ftV_D(BjK5kH~VUWTMkrWZaLrh2UX#CmNgi8c-? z#QLr|>#e?hYQ%PUd1aL99d(fDg_#Gc4!zAfbsIk`+q02bzq%Bztr9IX>)O0+MbtVl z>s@63#L8)?SqF1eJ}GlF8mTCjd!6kgllL{x@$#D));llE^X*pDYNQJ?>+I9h5n8B3f+Cpe&cM49?&_!>_ak_ZUXVF z6@ld6UauUy$lRRiv-{FRmnLRElV96)Aac5o5M0u)$pBM3&W^U%Ka%SGkXQ~o=tLn|h@HzI)?y16jf|>p>yq{X_ zmt2uvHRiNYS=tq6I)5WW#ndtT&to3B)#>i8Jl-$O4>|VEAf~g8+aVtYjb=Jt^D6RX zxOt{A7j^}<^)dV2C1X>H0t3x{*r~`;QGQzwo}a38sF?P{?4OTq%mh>Fn0@uK;}u}o zl?*)ROQUAcF~Jj-^Zx#x@cyjXpAXJ948EUCz~jL;yrA!<2=3?SJobi4E;R({vbNo5 zXme^0)4S3Qf-~{W>w@#OJHyi2=Jmq5%XPr*iU69wYjZJJbFwYdM@}XMpRVS0N7ZI$ z#guKHJpR6(hj>%LJV&4XYmJiyP5R`|jaIio=A500N60tv%(XLx=#EdVU zna|Osk)qV5x=inK$^-6e9hpA#(SQ=~k}*9mVOtpgz`Xaq>{>sVI@gnBe%IC$vKZUg zS0`ojhTUIRun+I9?hTdq3}!oYKIsWxr<`GW^vwRSu2oVX9h0PJ2WjdSV|sQGfP*K^ z8u~0>q2K;KcH)P3tXS4K`ajPObWeoNmF|(ml4c*V@%hWN&Bs`#-=*mt1GI+TIS?CK zduM@)4gI_F>+^A6)&=z-8U8X&>ouGFWm=c*cWHd@1Lr7w?}LgBP3viIdXGeG=--uJ zpO5dYU|sON6)H9~ttY<7L&k>IW&2$k-@C!O;CnYzY-n0fd((S7VnhF~{C}Qbw219@ zlqEK_J;&eL^he$MD>O+n4osPTkJjFYLgylBwe5_4i`LFU#D+F?_-ndgoU#pUG5eQk zT2FG=a>!q%W1|bbtA^IwV)if7w4V6ba>!q%iN{~{G4uzP-xjlfnU0Nr>T6@8%O5sK zhB?6Qr+v5S(psLR z>jKsVdHgp0ugLt*=4kZ-Vnb{7i>?dowd}X)eb2-M-;8M)s(+XYxN~oJw|MFp?i_E-qsJqh6at#U#4TD3)++Ar#c@S`gi+;e>Oih zx}cx4E>!1ZL;r4{@XzMQMiJgT9uu`D=AwI}7Ta>}T}bbZmMCeQj*cMT-&YY3;G|+w}id{}3Bp zwA@A48mtTT0>4Ys8j=Io(Y4QCremXvR#WJDkaeM6;CE?SLvr9cx+eY0bZm6d>ONh| zvkdfaENHr)VCVDObZm6dY)H=m?e_d_T06&B^$)SpMe}WX4rurD-=?+ridFv*8(p;g zL(c(O7s_Y9OKUkWR{cY4bg|c^vSm^h)agz+%xm^*m&=H~a|QwJQ7h*zadV%E%fes5 zD|;;-513T|=s%ic8)KU0(i$2k9>j}i;$61PEI*=YPo381=xcG}FP{2dx(vE(y3D#R zb{%=^f1xIyJKGZNLO1O-_Xq?Q$wjPNm7IG&z+fr_|&`pECP}|K?nzzEq45EKlVO|e*5oe^KW>D8|?FlMqS7j7UWHGGL3sml#^-v6WN4ml#y)3 zv~7%OnoDbl5Ah&gL=$iQEOc6*qp!tfzj*3<=`!fD=`!oO*mWd1{uNsHZJpNSq!_X5 z2*}hfC&d)gbe@`=pveiEoI;aR{4?3~Ir>_ir@ogigD#scv#twS#r!e-_kX7U)p>vB z`;T$)54J`9%{+s0GL5>DZRtM?>iVaAMfRm})Rk<@H2zAqWtw=P-IzvQg}#?QuFu!` z==^C9+RHY^G|koJq&;X3@z#A?r}2DwE!jbn;cvjT)`r=+^G1{oe1N@`mQO#Gm&-`~NBbX#P*R+Aas>YNm+?+MH?f{ffooZ!u*Z zr}S}szRpMIuf-SfW1ciumy`A&{wD8#)h?z)y07ZAZeLAis`Yjqsn#=%oc@%5G?@Ya zW|#R-c}$ZT=lmhFKCbEbCq6oV%~t)BM)e?@VE4h|6mg!+5WHckIgPD!+%HrgKyjOGxau1+wvCkK_7|Lbp)QrFPrH5 z>f_oO{Vh3Dw*|$reLsp9dyd9A)CaSy6fd@G7rKU___5nU;XJ0PhqT*^{NG;Z$p28! z0<@=Xoa56rpJ`j%5idJ`rfvH&jeq*pm)qpzahv>17utAbqv`K_58~IgG08>y5r6#o z)l-rl_Fj|pqy1=tO>d^j9<(2glb!6jkIrkAb7RDe{~G`0D|S2B_yEnZ@n_n$FVpxZ zl80%VoJ^Db?B{~^)9%y#K@(rQ-`MP6=M#61Xqo@Fog*KYE&k)qtCk{r#Km1){rq@2dB-datYZz_wnR^Sqw($tUr; z5%1;y>ZQ5g)_ZTgm(zO&J*U~^;l9EqC(}0hnZDD0XCd6rKK|>TKF+6}na7dOuWJqD z|LYzB?)&TB0m?&jc|NV9_4xaru5oCe;ftN@*9gC^iEQ)P4mLhOYi<0Qw(ZL_{)yya z+9oH{dJjqK$&Ti~OshCL&JJ-t@c$bh&|^Q2X2<_iK8&+ToK5~ieBf{QYxVcm4Lf(U z4>Ny@qvPxl=L7%8KJXusAIXY;dyb5=6+3I3ooz82=MQoI5a$E`**>7mSf~HT^(v+< z;_MJ-hyM#7_`ldQF78cVkF!IZ9scb;5Z7C=)5TqHnXwmVhyQFlaDMrPw#)dR9)e2^T=m(1|8ofbH2j{rW$CW|lC@xCgJL=jwJW0PU&q`Gp0bJ+*yl z9j~Rinw<2^{}(R6#3z$D<9=ZQXiuEaSOD9eKr@IB=|D8;M7j}8d*a`i#$V}k3QW_U zWFwkm?rFvcVU)FT!a>{T|8IV-AMwfb^XHgE+&^PFZ2JDPgKi&Oq-dp0U#4yPGHuhB zX_~8_i+*1A>#=`0N79$ql8tE(+6#aF6|d0t2xC;zn1C;wy`xBHWyX!|Ps8_yvd zXmb9^4@q9T9pmV6WHZ}O9BmpR&JMA+199NIVb6zu$}{*!_B)DcJugvCq?NY3VfW4d zv98e?Jx^-+@PDnY(H`c{e^yYAe#0h8xc)=nrAak1)eLKQX3~b*ysCceEc;2WKW($ zW12iZxuAw5{%JQRgtr^LnE&M}B_ZbSV&;FwXbO!}yl4Ki5;hgtTlq5o z*=t-NOICGjzn<9n623yF1*eGMo7yZ2MKz=yQbmSD%*$HqW@n z{C$54sIob$B;7ORt|SiK3S<63& z`R9FcTRiOWj`;^9P6cm|r&MI0n;(h*@@4+GkLa^3vm*Oc+g2WsFZ0KJ#J!`r6xru# z83XQR$*;&hxm{}j@@4+Gk3hbP?2r2hf3%Zb`oe8=8tv~c&^MJ&)Gn`Fn_d@z;k8(c+LXt!u-)r0`0>5 z(M|%-Rnht4ISV{j=8xwr@LZWcp0hxoWB%xa2A(VP$8#3wf6O2K(ZF+M{&>y;&z1S( zIScel=8t}ApkFe7^izR;$^6kz1?EuZPtk;a$^6kz1?E%cPvhv9%pd(!pkFe7^izR( zmif~h%(Kj&Xw0+BpJ+{fE9PA0Pve^WR?NT5pT;r&GJm2q`K_A#Qj=e5_P1*COU?ci zS9bX+uI%zl&Hhreztrq6HUF_{_LrLfNX`CIv%l2*M{52fHUE*C|4Yq(q~`xp^B<}C zkJS8MYW^=Z|5sZ4Qe3h9DbBR`rMP1IP@HN0ueA7;TKp<4ez6As%0E(zU#!Q!@{iQw zS84H!b^2HSky`%2I{hpEC@p_t&Hj~tl$JlSe*elpO3ObKR~)}|&RYIdTK-g8ZkJmA zR9c>wTK-g8{#082S6cp8TK-q$$F|xewfxWHw!TGb`Cn=IpXb>68K!Oh4AZuLhU7PF zwTb&#TW>@18@4*dKDl`Z1s!m&-^LQC@KDl` zZ1s!e7q_oKapQ{uF1Fmx({c8Ra$NPjN2w;*9b#@uxVWyiEKl&Zw>se~L4z zE5x7TjOq&Ur#Pd!Nc<_zsIJ)R7x88O6lYXdh(E;{)fM7TaYl8K_*0xwT_pY#XH*x7 zKgAidHPMs<<+Q=CyN@eKIHS5w{3*_;FCqRE zXH?gTKgAjKCB&cNjOse^r#Pd!PV!TnQC~v*DbA=bA^sF+)Rz!{iZkk&h(E;{^(Dlg z;*9zy;!kl#eF^cWIHSIV_*0xwUq$>W&Zw^<{uF1_R}p`TGr9&K{vI1(BlT6ppW=+J z2Z;Zz468O$Uq$>W&Zw^<{uF0)ok098DV}Yl>jdK8-7mu?x=tYe)h?CZq{(m4H3RYQ zmciJh$#2m01My#Hsk4c$ABg{){tY*2@>Bh_%TM*!Ess7sK zr~biif9fCX_NV^AZhxWq5A_c$KgF5mKSHxV^$&LY3(bG1|6%^N{)hQfoN4|qH2)Er z|5N{C_aEwim_Nmt=Ks{cF@IbC#{4PHwD=X8|5N|T_Mv?=|EK?sDHNSAL{?@`IGu*d;X#RpXH}> z*76Va&-VNS)EAO}(m8ASllp&q{sb-mQ~z(zpP=P`>i_Nellp&q{sb-m)Ab9>PkyT9 zf6#J1XnCHlQ#)%Knv@Y?#eKh`bkC*4rm?lp_O-?!& zyZku!kMklbO^4Ai5^C^uWvYzsaJNJt)6at1!1QLx70o#_ts>m=D#!Gf8aZL2r2*3o z_dOGS$$B!~q{dD$@R0d@xY_r9qP62l9`~K~#&D@WmTBUJIup&m+n%5De)KFwf4*;< z$14&P@Z$N?S7(v^*A8X6(CfwW`G#Ih$1C(ecAM0aX;~qSYOuwL>EPTYRpM2-na)wD z9{tNSJrB~xL7NX6AJF&%Uy`3`)R**P8ug`rnI=1H<76NEe5LVG8h^4g&mlW&^6**NbotZs zZcTSZfB$#+Rogd-4BE@m2xP?r6Abd<=;lY{rfJ6v^5KJJld3!IA`J536DLZmd`(jb z^5G}%>Zqj;C-K@D(<;g`nR5&B=i76-s(Xhmg7~bywp)H(A_Vc-|0%VZ zn94k7m>`}3TZ^c{C1xQ#!!VcS*VxiKFsr6 zqYpCs;H}JaOo4vtme)R$=iuzBV3m)|XZ(ZAa-!uN^KTzsQeD~9kNMopy+HaUd(Qkb zb*!U49p1q_o8P=GTRTQDPmi;0)#R%WnP<}0Db$r7sRY@ocJ2gn$g@c1>G>|F3jZ*j zd1j9GmRT>R0 z?J6q@gJnpY$U)Uf8p&%@o*gXFro0wyEYS~`Kl+7r-owT$&#q1>RM$g!na`PHDdzMs;k$Yn_jslIS=) z_=WWT%x9`=7Xxbp^QZAL$4xm)=h$dqZD5`>zGh4r=6N*!4WshvD$Mh6!k)%kS(kZU zxD#&pUfIVyf84)sSVwnbo<(LR5oz)yWI3x=FCZRw8_qnF%*-I%COII$vo1DKy^@S}Yive+tbvgccV< z^G~7qhS1_dX#OdN24`UV^f?@1Xg(vf7!jI(ispsqvfXlp4HjCA2xIVd_WvPS_X*8E zg%%^Q#yct7Fj9pIEfyf7%*Hk>ddmSw4$3Damvv|4Em6{7L)M9uy0-=evi3 zZFrz)9w5GyLueo3MR|jGYxz?UFUm#4Tg#t9%b$XHQC=e6TK>cyGI|8U$LN2dy4~R*$&el07L#wR*(kw%&~T4GYD zPv%Mal5&TwZjwEvt!|P%CGn(ONV&sSH_4uocvAjDdooYTc~lQbPKrOuam15y9@PNi zNij#co_JDhQH~>?l=CRRGf&L-ST~su)=fbn8TB z5zLcf0_!I8#JUMsHzmo2byHy7WS&?z0qZ97#JVZ4ZYq))>n32`WS&?z1=dYPa$?;C ztecAD#JWkjf_Y-yG_Y_c&exq{`vx(S#YnGe=Y%1g|L;*a_&I#Y^2%#F+k>!zR{i_Vu~k$M-? z4;B$g8D78A;l%;K%RqjQ&8{4HpE_xdO?zhVw8F>Iv0vj>I-RKic#tdX)lUV z>b+<$ic#tji9f|C^@zliVwA3ti04)R?1iXDB%TzbbiG78>)u~nh_082=jSdD3sH|q zJSj%$+KG794ozJc>n8KTx*15Zy2N>Z!E2puUdfq`237LuzqBeI2i*9DwzSb-{XN)qI9}OXfqprRJX!>lW*X zb&PsT=0m+D)-aY0YZ~=+tQX}BEk+d9Gv*tr#;A*XiuzdycgCwMSRJZXdmK5{zJUA{3(eS`492d@+Vz)Fi)~E@giR$-dg@t zTF#{FBYU2wYYltOr0XM=({_EtJSldy{7KhG_B>D5NA^6gw0b19Jg>BRMAvTidZe^G zPuFqwdPLW8%#&hNt3h;)X0J8Mt?MmuE`A>vwe#KjQ>QL5eaG*Ek)uZd({5eci6dXH zGkq&&oH69&MW&;3#u)0;ai&+EbP{FG>}A^HjEAVUdNtEoN-Pl0uck2FqWBg;yl5}t zy{Y_4rauQP(#NGXUut}$#$RgtN=+WCCa2Y|*W^UWHfXv?O-HLHgVbdkRqvufayk~g zDuNH>*g!P#YaKrW%Y3fYdGVm(VxIFb^K~&f(TsxjIXG@5n#OUyB%0LCH-g0+)kpMnZ~mw`!kI`hG+C^KKX-vj?mVU z|L{2ZkG3!Q8;_H}X>tlpenZpC(Dl`1z;TvA(Ye_6QrcdMeAu>^()Lp1^R~Sd#e!`w zMKNOAOQCK3Y`S2awX^G}$meY`D2g?GzQ)IX7R29v7PPPZEJz;vS&*Fevmp8HXF+<| z&w^yI+n@F&|0f%gJb#*R^FxJxYxhHi{)~R*UV!G4yf#1Naho6VeA1KV(7yV7o9`*~ zdGbT@VW!FMCQp`)Y121uF^#^TU*~Dd53HjtKd|n${J=J`s=f)A|p)8^Q79iOkpll+1CkUwZLkpJ*F`Hv*b0GVJK3}t^(CjR1 zd4TLs=5T0vGak`8BOqib_-d-18(a@tor)o&yN}57(u8Z+0@7OeV=pk|(*nN8D-_PWa_* zokXoBV+hBL@8bPDPXyul!52ME_YEOjHQ6*49NCp{ffT3N5pP4nQQb1~cXO8_jGy=& zGT`r^14cgN2L?az1x7h24;bY`4q(Xjo{|q3@8(5f1Hyc9JVVH&d^LQnY4Bh7t1 z70v|_pK?bE`OYKVxLndIg|d)Ys5M4~7r)WB5aFrd;UL$OAna zIiY`Z9trJY>h&bs9Xw%Iu&>ZBMv{%aeZ9B{Ytx_b7|$B<+PpS|PjCHAT*z0A@ZcSO z68|AD((pH6&>{~ocz_o$c-Kvmzyn*Y*_exx%_BXq)t#qy2>%RQJh0WeYm>;x&1XHZ z)htZ{Cbwl}Eu_(&hrf^yD!^3u`npGqoeuel-81eZrM?#seMM92xrQ6^yFKK#$IB=K33JD;rI{9WSn zoeUEjTYW=(?zWvFHa$qqp`VZYZ4j@w4JAIg0?&#!>y#uuM<>qq4j5XO_*`D|P<)wO z$))sj;Is5%M85~bCt=>k;@q_y#3!(2lxViFD)9-a@UD2bgopSn-5%nd^{_4RId)}> zxV3j1@oDzfa__9-i8$D#T}6wxT=tRqI83 z;?6b`p-d2;D>ql{?Aa|D@u`^ir=3~*1`(hB1G0FBH)%qAV((Y-9y?K)`1C)%x>Bug z`xBq*Gg^4dwe%97w5tkvChbm2e8%k@;@P+)kocS``KG5_)5gSS^4guA>IeE!-dq(= zdM0GsLV17w?YL)F&4iS9TCJ?CaO*Nu)(kP;^HqWT#AnsI@~l+qjYPk@c>-3mLp-7% zak&Cp(>sj#->ue@ZJw2z=#Ta6%DSH{N_-x4jq_Z+)Q!rWnqmU0ziK7%dB0@<%lcyt z$~!pQboN8xpQ&9IWbexcrVXaN#nbNb)IZXZ@@8!p&01&9O8nE0pTRyz7(;w+OlIu( zVGr?Xb7V8yv*;S}>9^oj*1dWj;&XEDSx@cq=_&8xb;}qZ(~@{z8uu|P-t8TS&xAIt zSHCjEr@^x0?Am8%h!4xPkPVN^M0}c$yzAMKtr6u-9d?sl*^`WT=F7N;efskZ;`8A4 z5Ek#l!o;WDksn!)2FHlcy~S(Um~zR94}Mk}8jtecn{|>6xl@gJ_D+?Of45^I@xjl{ z?eY_!54$Jj-;~@Zd6n;i#C`Ww4hveXp12zx2+TPAYeDD);z-}QI z^a4K66XZajf?V;xEl7Ou^M=w3_&`sP1AQNIK`-C~J)xbz2ki!3fDd#7IWQ(bF0>Q) zpxvMs@PVGtPT+%fgRPJ}%66a&@C4fw#0U>~4|y}*va z6LyU@15dOe>==At*RUJ#fgQo7!3Q?}<%Q;ycixB!47P&2upQVp_`}}Of4~R*3H=9o z(Vt+`;0YT?{{cPv(}#zX5YNH6ID<`tCv1F7tMSC=>zEx3eF=Hdx8@x5()^NhauSaI z1A6qQ<3C=Zxn`h$03X*l1JNfP(va3xP+#R!u`=HT68-q4eJCArD*uYsOChK7uP7a| zDgTNv%2oaq{Zf!>r|5g*uO*|cS5$q75Bh|v5Ai`i zQ2Hf4uy<7-;sbkE_Dy{BxGkY)*toJ?;saY&`XxTFS=HXe2X?CTOMGCbs=bL1>{PWk z@quls_9i~CN7dfM2lfb`9{RbEK4YM2Z{h=cgny5A|8(c&)A7QnZu-Z#l?Io=C5|;gVt@aX@{Rqo`gk?X%vL9*Lv#{((TJ|g~dlr^GOUs_6 z)xU&g&(i8&!s=hb>R;08U()LD!s=hr>hHqp@6zh;((3Qh8h?b<-=#JF2y6V2*7zfp z{h9GcT4Rn>@r{gsD_inVeQ)8X^LG`%U3B;+Var;NAI`Sp4E=%F$$o0cqx`}rE`)8dQ@#eazc-) zUL-&CxVO=nDduiQQ(sMQ+75h7+kwAnJCtkM4)U0`gPf-AAV0O8vX21MUN+WsBpO{u z%B$;0JarwZEL}&ELD!LFvt`zGBs)YM+bs@HY3?mFb+>h5>&n)lty^2?c3aqObUmbO zkkxjuThn&1Nz-;d8?bEy_F=Uh`ip5h^dr-Duu0Q)GBW3?DSOZ7!M&QkbX6}OJ?zZz zvH9EO!d{In{gF+UACbeZ*HgF2Dn)pTF%jzm>~^%<*KT*)9&9_Y?Z>t&+upi&FCS=Z zQl+E4j2%9eF{J&k^Hg6;t=?gcdS-2>){)TfXgt|9u`sK-K3R0iPNQY>9Lw4FXA(rW zSTaz?U-1juw(*Ch(P=u+w@zPw`1w+N^VQ=#T`78 zQ9slV^{jqrl^?$GLj8X&FwqbCfL^wTl=Xw2ps)9jY%2i$q3!H;RCX5c>inEB)Cbjg zy@_X!K_7(84XuzN27M5=cyMo$81zBd=*FJkN23qIc3Y=DsM^MPSNH1tccRe;Ve7ds zHjRc&q7R%7`FyDwGtq{8d2Hdyuwk7}W3;CCM>*&lijP0a(fs}KQSfB6s$NDO33*Ts^rGtJujQAj zUVdus34%`Jjk}vl*B9wD-f4QHAMi1H1OI4MF3qpdr`9v%G5Uv`rd=R^49Zb@j6r+- zD^@yj+tIO;=e`|bmuN4vp^IHTxHj-)Z9w%aim#wo^1;+R^t8r*H6E*ZB1)=xEyc4K z{}ErQdYO6Qsm<4jsYs9G?oNFc^EF~BryoRd8^bc(cKq-Cu4mbfuuHTT?8e2e9$XuE zvNnKu1{|G#E`HK_P-`}3{E|i5u8I+R=F;50pvdBw{$(;LpFK*hikceJYC$u?d&YH% zSvYPY;X};>V!C|)4&lb9cSbKxvx0DibMux~thkPF?>=4p>lRu=_;753fY)y?B|JGx z&4BWmW)glQe^kIMF^F)M3UdP<+$&AEQ{`m=nR=Zgd6o`Y8}R9}Y&MRDY?_9!&KrYt z&6BV$i?Eh~u$GOmmYJ}w3t?SH!n*E+wN40YT@ltgBzYd`7Om#ku6;MPS~rpS4}Zmd zpZFUv{+YE2V8qmj#esFqOun9ur3st03DBs2zIT4i+5{4{uSWFvUCBh)_&P|@F~6bl zy)$FhCO~7>CV3;I> zcsqIW;JXa%f4zFB3<8ebj$|gSV ztcwsYH=9Fwr)G-~y)SkqdZh#Cg6LJ9gsL0S<33>A?F#ubY_1}X_by8Gkzd#I&Mef2 z=#`$lN?$~e`+dz_vsYFg^By|9lk(2`Fqik&UAPBTttF<;&USU}N%Xj{*W7*k{nq6> zC&cU}+0YI~{?v88^Nd;&N_nAsQ(x%b$hrQ_2v4JzcT?VO+Y|9Fd#VwA_N3YPy&|QJ z9+=SsbWeAss(PI-`~kc4NoJzYv#Bue8e4$q4{W}|Dy&Rl^x(VWw(7U7S>BK(RIetz z6Y{!u?@+mexA}e`QcZ~7p}1$wjt#uU)#eoFMZUlYCV zcSH}}gBJO9KPCDjGfs=9KQ|(J-LDOQ^gF7T?x&RZ!R+PY@b`HsFWN-44bkgDq+5X5yjZ(z`4trK>)Iv6pa{m!&v2GR_PAnYjb#Y0vd) zZ2|rW^}S~?*Q@oKKwU373jq92nCq1um5+yi&Ypz9&QG@;;Y&dmFM`hoIiGgFLmAJq z-#O*^d~fnm{|Wuhsh4x-F0dM_Ip!Z=H5YKq2f!+gVH^jB-bD&m$2p;fOK6JVJ!n;EgNAiGhtm9!n%%xb=?VT zoe;P8e0=41TqAlDLxIMMN4SZ1kgoj`lGDUHkkg8xxQRzV zZ{iNfVB#IeR(6>s?RUZ6nfAvBn|KN|Cf-3_D>h*!&O%-jLuvU zkZ$4~@Hepu(oMXh`3sC$z$Tsojfr=V*NRO{zb1MULxIMMN1$hlcaU!44)8Sb4$87( zC^N27y-W-OdK2$}-ioKpxJvXUP654%cR+9AEMOB)fyTr;NH?(+u!);6XQ4ki|6Kfp z^&pLAm7ZNp%6M{mc(jHec*{)oFj;_i<)>*Qt~Q~maj-IsCqM4YyMDtf50JBZHuVPBx! zXMTYvc{b2ZWoKIu$T_^FzWXgBAqDmdO;0ykX-@23%g6 zpKxHK^!_zo2_hVn=T!9gDFK8xwF{5&KbezobnTrnjZUQ?oOkw*F<)-KOgw+|rj0Fj zcNO8%ck{&Fs?wbBEAI!!&doj}8f9sWGc8in1OV&2gf&mXx~xFZXc-7=*$8Wy3G2EL z)^#MT>rOniP6%sV5!N~+{7AQGK==C*XhFrK|EM#is1w%iunrEa{8fqnfRTp30pq7R z2L)`-IDyujr$V|p?*welHG#&QrvguNE(_`AJQe88*(ao%^HiWWXSaaOc`eYG^Hj)d zoqck@A924Qalao?-zuPwnDbQVJJuO3voA*d+x>o|DCxnReS+T1c`E2lpP!^L(*1tK z{eDF6=g=JaB7H0B?vJ?pBd}NabL!up?n^pkPF(&hzT0xj`)B&tDt_XB<@*KDyWfwz zggBJD-;eC4Gyf*uQ9gf349gNb+4nt=QLi1XdO`~8Tz z<3rm6zOy6jem??l>-pGoxi+p@u<X2XW%k+QD;E&m?^AO1a=`<31z& z{TqJ4TUqir$gh3|tKSK$zXvHg!YW^o%1>DF3sQUuqa0P9Nnd8tQI4TUIff6)G5qn< zl#9O`d63V@34TU?ryP_R#dUfRu%;)h`4HCpgLS=7E@3SXVJ#5d+w zxUR3EhaL!P{SelABaCwJJIYn^K+i@_=$|mk0bkHOYA>g5_`mb-kv%=_b#h%E#o#J7 zc_#NPq0Fa!CT-Z86_-KBDC?gTbD=(}UT%BoJJz8My>>)xt=E(Y>pK(Z8(`g!2phYA z9#5^Sr}``Y{T}a~T_>0qNdp^_>snS04oftZ@bKy-f={hGLb&6Hxq=tWOc)0m^)p!g zPFVdtNYN2i`GQn_!iryz;!7AMsN4ex*-3M~_ib z*VoWP4}`UT2y49&R^>vUgq1wdGhyU|9<6pE{HVR0y5axMzenGBKJ9rym-mmG7u0+g z1bw4^|D<``ZLcTuO^4BA3KpaKDE>up8+X{TB(B4>uCO8gUCnpm-b#0#aCDA0;!?1H zV5E;O6cIP1UsJ;BXPo+-u=;zPq9d&GEmQdkD}KuqU&1I+m1oj}OghRj^eD&hK{!n$0-S{}k$PQoZh@g;n=(4cgV z9;3Lfuc3z?2y6WiMmf-}j}e#8Em&Eu-y z(b)2|#}n0ds+?yRkK^q%v=_>>vD=OmFVkCS(2l-0oBUz*>!0prKf88(6cd>78uGf> z(SoZ7R}cTA4VXTUKILLECsz+nuX6S9B=qnf_N~YVviG^{{V#i8%-%24`&JYi+WTvI z--^;9uT!3H-^$SY_V4t*6{YKaE5dr;im=|dGIIL%4fVbir9axYqWw7Eeirt}%s!XB z|7Gus+52VoJ{t0w{WW{vEwo7CbWV9xFW)|$)Y$Z5YtqJD)>MgF|Lw}i00Mu$A6JRNHrdV06j z`TL_cQ|x=W?Rd&QPix;7t>pK8YlHf0e&!n-+7q$&O6)xpdv8UTYw~kV_q(@d?6m^@ zh6~Z_`VzM9Z&9-Nd`{aJ)%qlQtv|wA|7K5z-f4I0^QgUyE|KoGoj>XA#b`U)gNrlm zY42g#dt3INm%SHe?~&=fD#c5ElW6U!>AfmSM>*CWoNsRqdrj6JoNq5r?^RJ=y;nt8 z?^R)J{M}xm-m9W?XHN_zMoD`Q3wvT_Z_D2EviHL5Ju-XmOv@Pzp7vf_rX2q1tUWm2 z-kjD0(QEw>)_NnX^+{Ok8RI1C<=ZRN?Lz5}{+xRKhkYxevG=*`{V#i8Oz&G!xq9D< zu)V*g_pK-$B|7E#_N@%PZ~sp3TT!~+w<4_ftqALVE5dr;ie$$A7|KK4AMIQD_8FHU z-QMT2_rL6YF?+wv-bcg!81jRUz3(>st+CUc@+jT6PiODnY5h=MtvAA2pMqENY58fZC*ebs@_!Ivz!;6_FSOfE0w6-vz*6`E>W)AcK)P)?Mo0= zYWY(i?C)ti+Jg&5yP*y3JuG`~%ii;{_rmmEmC6r3kM_>=UKOS5y(+>e#oB}O?ag7Y z3FT=%zP&uXS4HXAvqE{G(R)>d^_-z9sj%W^BK3JH2bPgdrnvV zPVFN-JNs1qE>`zD#OzPa2UG18gg$_>o`nyl`kHSa+-;O#q zk&7KIxO#B)@L$*fjm3`UoN?L3t{z+)cw#nS)&i7D-MLKL)f3Z+`@Yf|<=;lh3g_l6 zt?0h5^t(MlWoy2@LfhB1_ZICvM|&^Qj>naLeRHHv7qDY{uT%3OySDd6b-BjgArE1- z7wOw$wbyL*-X+oK_{h);>_IyH=h3>Nz22zzE{R5$Ls;)!lFWA8YQ`hnzlVFWz#DgG z;Xh!c;cvkB>E0jMnL`ieT~z2v-!n$<5LxfNns@Dq-n^X(dh;GDbZg#$1vc-!g2vo8 zj`Z4dZ zLT~1cRABw?D(&A zwcbv}eVYt-*dg7#k&3+5d#|`}Q?>sl+>Kz~$)bL2?$ZFhdw(Fk>q=uA^aP!o_gL|} zdw-xm>BPLp3Y#%+zXF?gUC{^3+ySKL6tZbO*AUio5cL`RT#cTyC|zauox`!u=h$n5 z?)yql=36}X{=k2Z&-N_(9m+7iul7-?&uZV*^k3JrjU&Ootd=mJj={CA|AcnAH+y#0!Fb6+~f9KF6ld8cNJ5b7N?%KKpUa&h?kyy_0V zKG3;<&Oxu%ALu;^U=u@u27d<~_?!1+k*?xUm9HA5tN4`Onnm91NwZ13K?@rFP6XDa zxQRi)M~{YpZ`rQhm*Y8;ncJB{-f3XhQ^yei`~@Rgn5N%)to}>s_3Rj!{31M)7>9&_eahb z{(xQjBr}IS*_eYMIZ!~=0cdI#+WB&$o z;fs0}!rdQn_eXGc2R5w!{pr4>L*|?fa`#87lYji*ov2*E+9d%Eg&3#A!Z0=Ij~rn)6`zyLEQUltpoy zT4QHeV+SAWycyQXm3*6sM#ql=Jk5D9&|7EBxQ;`KUaid|J|%h`w;~Q==Ij~x=s1_w z>gS|P&lV-xO!TTuhBbQ7tMz=2HG1G~I-Ww_T=6He6$OJSuR7P}!F$r6F>#iq4@y6n zc`eJnr8U-Fu&?34d)1&Z@46!Wlf3DJ)K4l4u`kwQKx5u}1$OsG=282)`y=SJkIr;I z&$!>!dNfwGI6hMTU09V(;}gm+68|MWpnD3rrgI28*ZE@>eY%G{Q+b7_`N1^eW|s(= zqQSR2KdbC7kA_!~i%KLB?UxUbmHBirWMOrK8L+0|pwW3b@@k$OJat(dWkCiNp9MgM z=S`l!t6l7JpEsR6Z}Ql>`n&M+rjzGQp1-SI>~fzsojh;y*t+_=@bjjV=S`l!t6l7J zpEsR6Z}Ql>dLA%5V&wx0{!f6^$T|U)g#KZ8zl#n%jrF|G>=>oR#Q%Y zC%*WuLVp>4>MfCWa5bUyFAJufUr5zeT%DC*9r7M(^Vyom&3kazdddqv15(#d1wN01 zbzR7ReH;usQT(T(O&%Ag+I@IA=&L7g$3HCdy;$A3G?P6u@x&b($U0+x@MI5qmHpCr znA{)U&a-c15b3S^r^yO}f5@`f4Ud~QbZ}nEo2W*Df{#-do94r)t!ohHT-^EQ>LwaT zD%@&t0T#MwG@rXQk!S7FRcv3I0sPIB(>w>_rQp-{HRF57obxhp-aZ$}U!A&tN9s=xm4Em!k`KKYUCzdjlXu=nBV~hEvhFPQ zZ9QS*BNM~rtEE%0o+;~!p{WPT(5Pvw{LSiO(v&W;)UD&J`qm1+!+%7NxNpR9WcvbSB8io?!>N3ngIW zt;I5@9m&(oTjc$wZaub7rSDMbSyg(*bR&7s;)}dn>eXWjSBJ~ExWwY!LUl#PmBVHA z)A_~a7GYviqkhtF`64l6V^wi8y17gP? z@cN-Le)0xl*7n-sPP}5PsDW8>jMMXr}j0Ut+XhH(q1j2W&>-N^C)ja2}l^8@nA7#wKT|$=j#N&A&UIpWXbd20z_4 zH}Cdte)izarJj=kk^IZp36(;|FZCo3jN}n>Cse9?c7o?_-$*`c*UOdI$E#T1rUUq| z#in^qvsLWv{sVZ~ZBsp=h0?K$Eh0FZezj7kbvbym@pbqsdmeZu)lbV(c8K7sg1)O1 zk~{~Wn>>t%t-nt;srwPt@iDN>60a6?LVfVPqeC!GimzXbMt_lY`%WyB;o)X+v~@qZ zYwR5Fw%8!qq$iV&?<5o1l5~}Q_I)h6=c*{as5M-s9a>m?mLyDMFFI0g={(cRx~lo~ zbhq{3bACakbpb~Wwm_c}YWEqN(hEM!aeOSl}h{f;MR_qw9q+8**;kYw3%F!B8^e_1AJ z6<+i0B%*S>g`(@7LHwu8W4-&Url9tH`@3_&Z{}G+eShkM$*>=pp=J)^S@~wT>=|*- zGreP7QEX}t`SvNvdMMu^@)du%j8);)yC)IVrY{i9QV!tq( zJuKt)a9$vNB38e2U3NI;jcpjKFKp?x_4?iQY*Wkr{7Cm1o?WjM;)l0Z2t z;0gNfVc*X1uuYr7`Te&Nv7IFx8J24qTC5w&M`mxpE^n*N3Uo`(%ZD`Q>0deP88Is{ zje$Q^{i0xjh3Uzj@87sy9P*pIDOL^T=lV5Zoi^8IQ?e!G-|?4uMClWr%aMb4iVt34 zU+1aG?nU(Cowjab*=KV$G;wcU`_u+@C_!cPFWE5SczI(>Fa4I4Y^l(UdMlulYWahf z@5=P4NdK@qKVE&cSM^yrENVAXeOA2Iq;Gl9q`g?BT$fRwi1B_s_@o1?yi4=;kZMd| zYD^FxY^p4`ed)(L56n%rIwsA>@K40XtixpZl^UXDnmVF(v$}Hgh0L;e-av71>H?H2 z7j21Je)+c&8-Ty;oqj#q-Q*pbdYG)Sv!=M0xQ4TT$yc(Z+7Zgq?@0EO6#x_0S zy|yZ`OuL|^oZRONFUA-2L6qrYR}ZcYxHjP0!1Hed7_YVOM03q!U>-60Tk=H_n|!Wf zlS?W#>7inixjHsEqhga9DmM91#U|TzY?4^TCIhxFqj|Ycveyc=OzOlY+oThlOwai) z@%(RMllo0d`F!2A4d+n&+c7?)IdOf(oXe{=^ss&1M#(}ea(H%)-Opy`=q=wbvcwbr zc4l6;Onn)Z_$SYohuiT|C9aAbiOaCP<45rD(I0y+eNmU~pX*=YSLNr&h9@Z>l$Eht zZAQtF^>ca>-`US5#p^A*zP`lcS27DPlBB+j>+_Rm<=u8XP55`><-%oH{K+GDlh2QO zi+)Xhi!b)c8y+s#eV0=7ei$a+>e^o(+dEI(m{Uz;O68IBS+J}H%RV? z8SfPZf;VDLk8YcM!;S)RG{3*w_O8L|Y%2D-v%S7JsA8Xo3kJzW=f;X*I`-*4X8ivd`<(i|0en}PGhM-gfvcR@ zr>l;Ac7MB?@;+|tGtr8Dv^}#o7xn>vo}zJ;|1V>oAqgMFKGi>RVxLs$=27f(b$Iyy z6#KOL+KGKqEvmH6U&lWFD)#BCVxP(?_UWo)pOh;0c}K@S+pX9q%8Gr?pDssnO3wA+ za!A3%>by%`QUCj8pJ1*8P7`Jsln{@6E6+o^Ky@8XYbWuKgTOpLB;qy>%BC} zXU9M1yn-DE{ZSloP07&faAGEu46|1b z*z&A3*|gfdc+82-Y;X_GTJ-M4N9Nkhz8=s2E!GIrvBt(|C)TJ?;*VpENjla@{TE`5 zh(C!nGG1&)oxCa)W7Jpc2)>zlc4sOiM{^u(9aFFCvfd$7JYzLjL&H!8D}35L^qJ424vp}i!$ z4F!GtUFE8{26AG*nB;jJY-HAT5vYrq?wZn`a{mYqujw&-&OAk{-`NAJt&#N*&+Iaau3xpUL=W&;?HG5$C|{~W7%#2@r( z{_;Dub0eKC3H^NLvS%|Uq^7Y5W5U8qn}abfJ&SUo6_oY3V-ennGxP@Qag||Q)#EMZ zYcmdG9yjAN=69jTZOr?sTpG{e514Tteu7um9sYw?jn8VtdM+`7~e>4T^=gMU`&L0YJ!=Hvi1%~Lvt!m1-sGP~ z#t%75czv;-h1`~i=IREW?}-~C0pSG`e-jIK#3Q_>UVM41{jWq{eQR-<>1-~-Z_X$v zyA5#o=km)d4@_M}>0=kCmq${ZBn%ynPn|plvOOuh@aDJCnjinGILYc-{wDAGs59P; zXF?$tZ}C-Ykzhm!;Zuv=75neyCv4L%Pwe$ZhL@!DwcRU_RNam3-- zGF*t7x3W|E^%Xb7%~eSWpMIE1rcQZ*LH>Yzd1Q);>jU^R>9$AL zSoZ zjAoNp6ePTPbyAk^W9o~1_@Y6T4&8Hfm2lc8-s2gy4tKQ|r-Plg3*NCzjPIR~@^-!O zg}7ZT9pUUhC6xI-`-ODUc7GPxvDHDs)7u5ed{t%oM%#ooK;l7nW*bV+b1GEkU-Y%FFC`gl2*>0aGLl` z>XKK!`Swb}_39Ot-(>AY`1P5gGEM#K|HdD6$J_({kBg0L_$D5A{vxls_dw!4Utp&V zHxV{>?IPXW#|x~-A_;8n0R}dA2m{;gtA3Y%N4Z)zBF7n?9oY z4mW*A^(n6Ada`G`TxHwb*tW8HZfsul1#bF+>Lc9r5!I)d@+*`LmgcG-G384TR{e`9 zAA>OdW{n9?1pn1>$)>m4SB;+@%=9SVfN0cM%9L+FSdFnv z`38h-o3zJmH75$?8xW0}E4|7$Agtz4kMa!&tGSga-+-{1bD8oD2&=i6Dc^vwnxmQW z4G62bn=9Xd#s@X0bLATlR&za9z5!w7190UV{F|NYbQ;GrJ=ufiLs;`CtjpzSPc08& zEhk|uKVe-j!n(eMwH^p-{SdatF*Oeg9`Ijl*fUugEneq(?tNEHM-+*+Y=5elk1Hx*4=gK!Atmb{Ld;`MDAK=P2AiZf! zy3#ZZvgy2pHBZ92EW%m_4tgycVJ$OZT^GW-j)ZmH32U7Y*196BZI!ULVZz$B3ETdy zwogjec1u{>GhuD#|CaZ!`r$S`>i?w20X>ch@K*5%H}QyyQ@Dv!RQ$qC{G#F-ZsHm} zUPYcp6{B&)X!~~0@x?-V9)>PyUdJ2+ zY_%cXp^rHW>3W`r?MOZU6V`qKVeK!#9u=R`vevv2=fy`A5ytiKR5nAr7M19cMhM@auSjapGvCcv1i1VF!n%4cW z&OzzcI)s_W5zCr+oUpZ?L3z|TjWxL6&F}WSZ~Ft9KlusP`ikP?JELLbuo08tm_!Ri_-Nv2VrY{$gF1?|3v+L6Jfp1L0Hv`){9Us$}#tx>vUS@)bs*0s$Sqj z*jh*VU4Pf|fS-|*u&S3?r%`K|kJc@1?6#w`4*a6DquX9DR(rX9&9}GZ+jDtQ`kLEz zZri!O%6-~n{kwb>l#Bn|b(I%)T}6$f=In#pj>?v;F$MdiCN3gBU&l+_ilY!OU>_Mi zJ>rFDx)1C2yBDjy+`jf=uV=dR9oEF0^C2(NIO+Dg7rx)o{HoTZ>3pBPPG_&*>Ge2T z%hT&|gzcDCug9tR+_xS_Sg*$s*5@-#I_7snZ_bHH^aH0n-}))h=zc-vI{t!hosri6 zP%iuhln0Fe)c!fniJ5e>&Io#1Thx3ATm25}jK)7P@(@4EKQZg4ly1&vqAYv;QPDq@ z^Pu{>6_l;MX>r@mZM*;bT(8^jp3I(;+wXj5P~0)oIp5DQ=Ie2uush%R_Cc}sP4lDn z69{Yn!OXu(XMg_vgWd0J?9P3@?_@}y&#T{}&pe?0f48n<`BP*E+FpLQK4i`9zdP5j z_rXzbuKhmvcZv_4e}g}3(%}!9?*kaH!YN-X$_u2eOgKgEQrx>?I{Buz=9S{t7T0k6(Yxx7g?$AX zWFF8ykat`DI^o3Wv+?8I_Yr;`WUzJeI9T5kLcWoW?YuD;&ajy=X^19|T*ZcD&P%w_ zj^3tMU0>)Lzk;$^~pnJARY0cB|pwon|j%p;z!Uw?K&zMpJ^SfwwC`TM*A6?d2Fo43|hm0 zPE8vt-I{ix^$gu!w4R~ck=8SG`@*J7yQ^|HnLRcRd(d`*b~EcH+;4JRtd;K3_5*rj zhv4H|!$6rV)H;^ddKShH8aI#+?Qi-z+TV;NXn!*{p#625qd%LulFBjZD96yF{S6s-tgz*4P4#4cZn^FRt(LFzK*E)QjvBSo0CUnm=J(F6l`h?T={ay^1 z+KF)Mh&Um=0|`fVts-W28AUkkOf_%PO_79q+}`2odvy%qOP};$k#$E9jvKX^6)E1I z@CT!Av%S|l5ROcpmA|#N0pU&a3h_-}Gs1tQf4h#a^3ih5%A!=48aW2ambq3D{^~+I z+4M2iM z+FA0lQ!f#gf$eP{K{Nx$Eo52x3?`hp(hYX1nWLY>;kkJA1!0tK%lSCiwt-f2-eyZu z58-H+5qER2JgFlHx0|(n$Iag&3H#qKB!1~Wns9^nmkDutAmP~NH^iq6IuRCGv&d$h z9NT91OUUE#%TfBgQDL%mbS}bkFSV0ZkKJb|E8+Hja?1Iwgui}kg#2cFXTohekC8)% zUh;qjby06+srSSjT(90z^|nd8c((lGew)b>mLE#|f6H{&GbZ~O!jn%|@xH#{0o5>n@uH<#r;O?}FqnON= zN5vFW2gDZXcb4QyGrr^bzN&f$C0TLauzFS&|3PWlH%lR&{<}8pRME2X$b7A6 ziBsid1Cf~$=z2=dlX5M2*qRz8voh!>stG{9iTmQ^D^sXio zhI(1VHwk#$qMEW<@%d~~WHNp^UYPum4Q5~5O34SlUSHa>{V({}M1@#>rSo)+8q0kd z^0GpiQ}YGq8p}yrbF;}l=Qu-^j{ zFOkjabb-8@p0MTvUhy=4!n$0->Q9h|u$GgsmY*=**)x6rS=aIKp_i0SrKQjSPFU;xa3p z0c(1~nh$sx{)Bb8gw>xQ4`D4QVJ*L*QDlxyf|tS1qK?W|)Z1gex(HCTPFp_m3*p;Xz7D-f3>qa5<{6r6;3HYS4!ue2@QIRm zyAfFXaK;bt`L&u4`70;~^#Q#um$3R3ekx&<1HFJo%TKuT-caRJIqjh9Yv|#_5ms4z zK9klPrE7f>*5we^`X`yS4@Vf~;H^-|0BqXMPPgf8J~n^5Tw5N+)F|Y?_EP1@z}WQaEo)yp3Sdo7So4uc*Zc|VatW(HK_0?d zPQtbwu1nh-?P$`UnlG;78V-3^+zzO;^nnx8+v!ewPE&8dKMOw=HszERIK3?E^TjBV zt<)Q9+4mzI`>kC1H@2*7J4!z%3-JE$)F2#qnenI@g$UPvttt0^FAd?#rMvNuZ+}fT zdu7~Ue*ESF!Y>yX&DYd+V#%sWBl)M*Hqg3=UH8`(W)q40BOLzUy(xMxcGhwd1fCI> zV!BbfD4kAr8vhdE5Azn4VaqEL&J|c&CS8!1ux(#9|NR*n$-MGbvQ=K)Nx8KSxKRi;8^4j>#Ef++CIu4)lC#Q?+lb!XR_8rrU;2uuhZJBNSIC)_= zrjI^-{J+dWZr-QgKF`t?+_IeZd|G-SzOv*}Sq|u}n>$ZC`0G z6D++;dMLlQk6gBG58*vIhRcsXm_WFnCqkzEIWyt#`jPT_y1Aq)_)5kOZJcY|XqjVZ zFwq|`Fi3t~DwgoPppJ5E?2m*KB@2^{%I78-W_B$ido`;>xI(g2vVMc+gnwNBp?JGr zFT%g|9VPY^3@02>Zn^iHypC;%WXnBW^Evqa=A&4p!Vb;-*biBPfll5s2~+XejUAqa zIu_yKt(>x2Bnsmxm?MMm@5ocEcVs)8ZxAn4*^xQ#E2H`LsZL!mpBjI=w^~;n|B>Uz zTvI-N!d%W;d5ibj@*2NAWN4$7xvKNcQ=OP1{u}NWk&S=NdlraSam?miSJHaUEHP4<^H@;Lk> zvsIV%W;o@xT;EnUNfeKGo}D&8)(CRs?3i=3%=L{U|D(2Z%0rtD&~hBPRD$Ku@+A&j z%RXQ4ls7bCJpOWar@UIz{rUPSPI)DBSLah6IQ2iNbg?&wQ(lmgx%5$|ypgIdW{nng zw6NS3nvZms`qXH-yZl1J8B~9d8FGbi@oZgWvQb&6K238plxNXse;=w6Lzv*)36Lz_X+t4YW*)}!Gf+7C#EZqD<&>3F>Cfw1h1AmTg><4 z#ssbV=rqrt`9%hF&Sc7j(P8dl{Q^R!|o)x6ejbrC+I z;AAG$y!PI{EId=`W$YyP@P5r*`2yVN3FxoktWr&$$#*RM9OCQo}V zhUVreqPy`u-{$btZg!g5Gq!ht(u>nC9|zm9xzRan(C8f4=p0!6Bb@`-dF^zY-sWTT z*Ypy6G(BNWPgv6vcH+$_!ggLe-KMws*!<6*%>)}GK97Udxd^Gw%y7tQV_hz#H;rFV zRE}`^?!&dQA};kHO21L>wurdbfpE2Va?9u)bqL#eYs^k3BKk*A`g`qP7oKmNxbE2X zk43#LJt=)-*Q9c4wN`|0zwIYWU3U7qEzh&W>g<6~=X@k|Vq;r|A5yoFrOu@wnLF3% zEz|BkMD|(rbhtc|c>v)m-6Q2&VhZ_A$+nJ>EtVW1KVkBx!(`8+lLYu*{;9kCasKCo z_fKjf--t<1<-Qb9R_0XiS%c=&*;(Z5qzwt%GPM4{EFIdch(7=I$F3@@g?Hc$Ac){QzuG{`D{4h zm6z&?CC5h+F1RnF$k4>``7_Kq;LUQ-ITIB%p`Z8gbccVRMc?l%q1sH%9cm1qaZIW? zCBTdiYOV<|ae7`Otmiw4IZn@Og!OzUtvOCwa~$=HQJISJ!y7Ad*#A%EoAJdfQxjfS zp+AqRzL_CC$H`Ir*5_pjLw9OD4E{nqJFlJYKY29Ia3qN6$5$T2`%a1>+_+aqUUBUY zgfor~<2#q;qO$CH=id2XHerlo&%l_XV}X__%EyH5zdn%g13v#PS}>&#EW;XA@F1=c<#Vfd!-OOXyA)bUH>#j6z<$-g)fOJiN^(UE*v$@)a2 zbxV1>C9cBZ z9j`*|>*7DxgR&Kjf2K_tux@L@+6Fk%wQUgAHbYqb$>#@Z8>4h>dxXo6cpGPxOu8?= zflZmXNAZ!myx;Ak!8T1CqivS>z?M-SWP^>HI7XEt)!C?La?Z>-6Xp1jPrI)f{h_|V zZrlBDdvz8(a)$$XK+GmANL|FF&!uEKe`1r;N^ko9azbO zpM;g1zI6&c=aBp;NA0)Lc(2o`zM7t}<|DyV^Czs!C5&=({eL$%+WlCq*{Si->ECYK zIcrrfV%zn*T90g}g^Cee953GgrH7@r_K5ek^r1fD;%B3W=1S-Lw9YHv-XjWYeBpjG znS5d@YKvwmE67hyIeSx;2IQ1cJ)AwOvadW8IX`#ii{YIjuM6%KHjn_(2`r(r!Wpq?M!efF*$l<}g3D>(iOil=P)?LnL8X~83f1A<| zE*>DO$~A;9&gvuCqP>K>|Jq$19qp{ml)c?aJ~(@g(!YMat-Q_Sk^HZI)JmoupM#P z!t_!7_z+5#bWOR9y~FCOqQ1aM_?jf5NrrkCep{HYWUV`zU#$QU$`7 zCybWaLY;k^mMJ3S*(y0HeP+D~x$EUjgzbK@Kqip8v$i2Q1GeOqHPY86+$%?EIr2s+ z!Z!WTx8loT?>qE8R_2yT*481KQHM&)IozRNoFPoEDeT08gHFCI6MdG5XjZi8As3!M zK{8Ap-cR-|x1DgVfFbf|Jg1F5NIXKW9@v-C4;>sWTYliQd;1Wz|28<9Vl~WZPMnAt z@)1s~*0~%*71dWK8hQIDDB(6k?k|t zzLf1_p}nZt=zove&aok9T}At#3?xs(*Zh}u#QFxw^t60UQ(s#Twtj5A+4}sezUJhf ziIh+4_?k~MHkdqXwP=^{l6d#*OFZw`ZK8ONv*KD@6P{*mQu*d9{-QxpGyd*NXGKXi zO=L;bn*X+EkElFrr0;RpjZJ=RH5Z8z4V!T}p0i`rD56D@w~PS8~hc zA3gN8xm8ncVQFNG^5w-*(NN|}Syj$Fc-7OTjlZn7tE}uYaCW7B#X{wUBgN#v*7LoY z)0LMgn-`KRn-&zuTUU@1-VKy}*;p~EPFeZpYyL9n**MWBVF~%>L_gW@<_9A2_+Ysr zyPs@v;d_xZZEiWMsh{kUDw(XmERDRC!(VQjlU3$Vd`|@2_m{b2{N+&jiMYNcK=#aE zOy0`4N_d6`%G_aPW%f+3h=JLIWT`-ptktuyh#DCr`?antQ#DxU?XoaPMvSQ9~dG>%Oev^XIq?bIEaD9iiLGqi2Tz1&>p?B=cKso6|MOo*kn&O+-0J*qaY3X-& zx)?gbU*=2{BKs}cDGKHHlPj*|lb)9@in4q1%h}PHd+)kMK^#>!kGvVceC+7Ti@{$+)?+m4E|*viY@k8eznQIA`arMu6VvhvMl6@-3&!bzhR0#rQ``aaCpVJFjh>7AO2a~{3JWi($-JbxNt(W z@&xeRsr*&UzFB;ivM5jAJwQ&oI!9a?P>RnT6(rZ*=_#g8FUMO)7Lq611&a4NRN#ry z6_MF8-tt~5TY>k@U0il3H``n7OgV1qbt`YK4I#4%%h&-QcvIJ@#NS*KC>w^A5$n%Y z;`yrj$%FM?5h-$4;B!Lq%Zm4xiSl8k_z$7^v`=d}~NPd2IC!WzTu}Z^!b< zB^Q#&*QRCQ2iNA8Z9d5;YY$AsTc0Z+ziOLT7HIe_`?jRN{AF=LS?a<2?6(d9a^j{? zIWzl0HsR$!IsSNgx$N6+EOXu)mi?gu zKd~T}Eci-GF|T@rj3j5baiM69YTe=i7>9koA+lCW@}A$@@(xAV2!D zwAd0^nIE6GQ51ONyvSGkrN_c%%yq_jXZ&@ss|VKxp0*A6&QVZ2pza%y)_o(=x^F~U z_mkiZ2GQ$%ZSwtWtnM=bJ*BJrNu+f@i8S|i<5!mWE$xOI;Tv+hx0);%iBx<|!h-J{~Q z?okoeJu1SwM@3los7UJ`6>08KL0z0N1pohYY}|4jDLoHahjpRlpL*QVER zblX1Ko3qzZ?DZ9U-NjyyvDaxZ?y5Uy%(uM0v(B2H#yQQ0#yZWPu)WWv?7+8oX|FSB z`H9{+SM==G7yrd3X$@Adw-HwLf-dnN*7Q5L$ z2x~bBYxxPg^P2B$kMGQhJForcvwQzylkU8xI+!~)x^u*fZ3BP4{_!|#BrXkRV*GRU z>FU9@f#2JNj)9Fo=Q~IHDV(l&#%@)aE@6*o2p(|e<7@6e!}WcPt1o?zK-u(6&s^`{BzsUpLG6L*DRiOJ36i9 zwint7x_I8(%kFD7cH7Yx=RfD|XwQ8vcI?*GgR6%pX9MQjG5C1~Yk$P7$@snr)_x_8 z8F~-Jj32&li&fkB{3hFpLe2>pLe2>pLe2>pLe2YhReK zzGsr~JI+0mg!Mg>g!Mg>g!Mg>g!Mg>g!Mg>g!Mg>g!Mg>gzdW6Sl>BGH2U61!urlh zhmUjTB;mhGulp+Hefs#x^$SN<{NLrN+l{+AaqYpifq$|MnASCWlvLMeG9l#UJcJ7=X8QPWi%jn!W-#t%DzNM^l=lqu4b$GeP8@QdZo$O}d~-xP$m&Bs$ub?(4_XJIj3 zN!^o)x?i}=`QQQ09r&-5YsAxipNY~pMz!a^#5s51uiV{-m)`B%fj=($aGv-x=MMas zN)fzH$}F^=m`dH1*@l@r@E^&hityQN-T7Zhy=y>Ny#*lD zy9R{S8v#PSYd~1N9U#=Z287j{0#dzeKv=ysAl17Dgw-1aQoU4N2i2Pe zQoU2B)Lmm*1JyKC7oC@|<|#q1%Ob30AgpC0tYs#w>q1!9k+7~iVXYJ2 zeP)P*S{HZjdk;|ez2lt(l#TZt1`c%Ydyk*Ji_A763rD&)XT#rpJEMN5boF)mvwDCnL(Vu}x#=RoQ$zQ6Bi9EL|S@tWC#?#A8yR4q~aG7bB z+aINlbMz6#16D6z(zMQ;fb;5}`LWxt?pQJOCr`U|;oL9hm7Ot_2D0l1`tuz_MtNVE zv5tMc@c*%QCGc7n)%!yU1Z5S7{Q};55fs@$mhTNao;@SH`VJ}KAp^+x0n0It!3%rog26ZCk=PKzB)a<8e`doH}-IgE6+&FF_zu^ zvsP|(pEc?2Nzt{w=$+(^fjEcjma%Tm)AuCP?tCo04rAG^Tb`ZNTlhlS5$DYBvB!3a z-}miwPnmR9{r5-*>@`gIytB`&?lNbL!#agK^Y%Yf5AW5% z@gA+&Pq(f9_HLi;oO!gN(%vDQtE{?4-SC`w)ip8BVOCueK5JK5zm?-$4!I8GI*{wYC)a`a zoUs_=>;f0=0l{4!F5KmTJ3f+d#|Q5INW$G8xDzA^cY?(49&*}t?ua)s8|pWG>$^*5 zPj~F&_niNK$v1zU-S<&{i*u6uUeE3U8F5t8WZjXO%^&mmB4C^ekc4|ca0iDAcW~ft z4j1m`z?~f~+}VM;F!;@w-R319q{q z==VF`oxA=N#h-uhV%O^4y@Ypq2Io<{-%;|C4!VB`@|oPPpD5ZcSR;ez@>QB+=a;Np$x|65aigM0bA_ zqq{$f(cK?IdG`nXjq`e4clA9TPT7w5Z_oVpoIwpvu0$VM5%$5*$2?`}TU~>X*=zL6 zU4xH#QTIP~4L;@zr$5*=_?Yf5H+9814W2&c4o_X!HTamnJz{Rx;A75S+OBKxG0!_} zMJ0VqyNiUjZn%qtHn6w5NN5{-yNiT2v)}fNt&+jh-%0Pr-5+;daB9+{&r9hAxcj5e zOZOz_RX>(a!JNjg*A`s)WS>5PyFYq&Ztv&9$iaTWQ~lhKKFd?iY5e%wUEOc{ zy7ccawD3u%ecem-x4_kSZ>QV6y};f4+PA8EVou|RSB`T7c571o-CukoeSGJo&fn8- z-5qsXrN5Z4%uP6L=i8qga%pwsU--!H5H^3r)9)}}L)d%}-MeePhOqe{KJq(!1V?imaO2*(iaz|enEU{Yw&$P^SJ;=Rxb0euFLNJh|`U+$yRCMUJurhFz)qW9VtJ! z*MoHw*Qsc5pNJ3liQujfAMOgl9U?y5A%eR_e7IYL=|*>d6&aE z+mVeI!Zwa1jJNScnEg!N?l!)^gt83t;(P|#LUfMv%#%hn8fD6(AO^zju zTn?E|2clZk19lpYLhp*-&?G9gIyTe!5?(h}1JA8%h4qsur!&lhu@D;W@ ze1+`}Utzn$SJ>|G6}CHwKZNbxWX0RP$-;JTvasEoENu5C3){WP!gg=6u-%(1Z1*M$ z+r7!cc5kw<-J2}A*}ciab|18`-3Kjf_dyHWebB-m)pmBNSI=+NVTNc1omJ_tKV-P@ zl%>P{5yw>uw>VADpuE}rzrqtbp5UKemHl?5P-mGxdg(3N@Af0V z%-?rFe_{Gr*&Y>I4I6ML+($g*tW~0!^RpBD$ogHx^YFqVfBA!l3Ex|GtiQO+w}nT1 z?Qq|A=QM6b7ys;!M=5?lz54#u6Q>KG)abeN z{2S*8n;pY78~z3*tl6Z*@fuIO_G4={o;0>*BaDAbYe=?cqxg8;BD;&Ew4PC#zl-Pf zz^63d7taIQ+_8AtyuYx``zy~j?=MW>HD3P;Wn>*N@BFLjHL7eaEVGqtzS1#WE3YvA zWqF0IyuzPlt~@#?wzLiy%O{pwEYDcZmLDJGQ#hV)&DK*&^;qL;ip&fD;&q*Py~oP+ zA-To!#OozF$MTQs(cQ#JbT@Gl-A(MGyNO+NH?fQE zCU()?#4fs<*hO~}JKjzF$Lv1hYTid|cM!Yi4q_MGLF}SCh+T9Cv5W2?cF`TgF1mv_ ziS8gyqC1F_=nmo}x`Q~0?jTO0JBW+X9mGSUJBX{JJBZaLLcOrPeiXJle2cup*Y5c( zM)&->=x$;c-A(MGyNO+NH?fQECU()?#4fslNHbYCm z#4fsn*hO~`7o$6fljsiOB)Wq*iS8gyqC1F-(H+D|bO&(~-9em0cMvDh9mGj=2l2<^ zfmiOGrsp5%(^IOGGfzH09e>>ceqO^nlNH3iSn;ND7i@|P@Jkv3i1&5hZk zuW$SPiu9q^d%N#l+Qgq*XP|%fzF#NfCiV5bCRU_F-s6q&~xR%Ft@=XV9?XUY?W7q1dt$q1hUHp!By`y}-x%P=wA)o&VTmBvMZ+URc z1It);&H5Y3XWU+W{qNo`PX_+8xBK1wJNcHaS0n@P=;kI5+upaC^h9$1%^lpV6Fd3g z`A7~2f8z^SoewW126BN zE?79pjcL1;|5K+U)B7LZ!@d3DR=#}B`1IuG4|0{K-3?qTWmmo9W)?cFlH?vi2Y zH7$>KtGf?Mce#3a+V0L{-R-B$O}m{oGTrjoquic9JS}ZLZ%lgAZx3_n`&Xqmyf-0z zX1@bn|LgBe|8e`2^!i`!B;U zgHImfZdiX^+IZ&FblH!ObYthAo<8#Gp6T-kALAbR>w>iX{7Gqx=fCDgtl1@9^W1J} z+GC;n;cuIy2R%PNeQf(h?$s{ORS!CKT)MjcVt4F)H&(y6?U=OABa7XTJBL@dpFcXC z)nSR-=J~I$d+(Of>3P6!E+0Phl_g`+b$?pyUacrE4!wSCddM-0-7lM*UR>UL*K~{D zE^<34gKNYd^r8>iXraD-`U33{m$Rh^X~59ioKfnI*&B;v#L9|pAByA@BMKb-($hn z?#^dg`WGLZm$v!iM7PC3Tlr;AwDyJL8o8d2weZi~)xbafjWSm;zL~$j&#US9U3$9t z2R8N(*MBe_iQfqxUVj_^@>btXA9#O^`_@(sc?N}FdD%I=`Q+#1_S*^X@n(hp=?yO@ z<8E!^Uw^QNfBdyI$zQr{?~iWY*H>@ZE9rY-Z~wq4{rv5B-&~y7sh|H7=nuH|FVtPix?6iw8~@-jTl+Wu+|u85 ze?vd|XB~W^r?|#)b{-DJx(?bW1@ym{A=ogJY zB)#C^iT;x)Quckj4+|$oJ zsIl+!Py@f+31z;~Zq5ATPq+4i4r}D!f4oJ|NgwIw$71WpJo_-YO z(krJe^wWOcE}gk>czV;ri+tziPgD=Ra76mrF^he_TUJ&#SUEDi`mc-q(L;By9`vhG z>G)1d{M3e5uY2_3(P{m%CH~kZBZuC2@u>7~Z!h*2EvhK4YC1AKu4=JA@Bhv!9&^X= zbiWRZ{jFo}DgOR1!_r6QE%Lvf^iHw!tLS5QTIh$KQI?$c-te^S%Hw>`g~O7o4;-2H zn|Z9?^Ui~l$^A#C(^nqp+yDODFr+@$1EY)i76GwsvfK%dU(4<1@cq{nmTCruUw<$iMsYBh`PZvs=1&5J|6N|z2f#&3E1;pyb-rlt+19O-Agc4oRT zou2mZbEqGF`>M3fL;Iz>UOdk)A97E6!aeiT2RqO7=L~r%wK360W8%kRw$XnxS5sqi zQ*nCnTt`jKO=aoT{G5i()yOwPxoT`qBbJ}dbL#h1ai7chwiisS7~5`Jo`K?<)E!gN z^~v*u-#vI>1%8tyTr75}IJL`G+SA7;|Ic`?FDD%_-{bqlJyXLVoaGRmdm!RfYV=^STy~z3(a)>4lAtu<@@VjioDW`4P5! z3L_onUwGXE-Odibb+qyZddfkV`DJ>>pK=ps`IsK#S#G9h`K0`XDJQ1K_)LBu9xq=U z*~jm=@SSSb=`L-%`>v~xPl=DZyFJFbwZen1Yv}L&(X+yQ^8ZW+)}|RoXz8imb*yv^J5~-KYHRSZ$AYS=}vn z!|v>=-`%4BbdU6_sC=Q}-^z)nt?W>F{_=UK-{tQ6W13YCyK{~3+b0z&XI}fLFrWON zH2j`)#C(tM6O$kL5>r>Q^c24;#Dl&n(1TA^-~;|ufj^$BL%R5Wb;u9iTOINVeycGO(LjE_@7fYA5yU<5x<*oVt)8txf{by7zt`8>szb4kvYP$`x z9C6(d+n7jO#o1Vy65ALmY-6jijk!MKQ?gZLJMewRN484IcCh$htB^j}Dj2^@whC>N zV5_*uR$+cfr##RWFk6NB54H-vFWD*~p0*0hrSyo6PeL5oDj{9*h-{URPsK;Jii>QO zP+rk6UrdkuncpnE{<684o~0XXl^|#3hw?L9CDaRSl`r2O!aUDxY5dFU?u##njq9lv z_D;y&VXCz;&rrGg{7R-((>@NyvRXdpMbhHd3~ku8LdWF3~F(K z@VT9rS6rALE!=AGr4{e~v%m1{UDi~zIOHkiXXUXsR{UyB>lm*hf1?q$cdHn0JcTVS zVatQCFwlWG^*@aCe!X_(WlcDmnLAIHE8OCR*!-w+xFrH^$@;hSwnVl1S z_R`$~*o#Vf`J>p=%kz4KX-orh(z`a7D;)2Y1wm;KZM?Vkv+Pw? zatO>W4fC9(vy8sXdzC*)os#Ao&mZJ}I;K1!e$MUZAHDCp^p|~@&u9GZYo_{ruKby3 z&Rsvj?{~@zq6t1V^`!AX?nt||{-)M1o*h^2%j#Yx`f1~a`n8>#&^Pxs?~#zctmCce zuj|zl?z;Y_^rSP&#dB@Drv8Vmf2Vg(@6g6SJG`GGeZw2COx9(-~7P*1Ko5UYag=dXDHJ1Ij}5VV;5X zNHay+%3JdvVGVx4PNHA-)Ax*sZfo0CyKQKl4SQ$C-)?w8f~Kd?^kUifhP>i6#G zr+5F-s7-Rmyn{s#nN>q}qJQbuYuA0F>Zi&Z>mlU7(YWV|ORnytcPaZ&Ue0H5K7{$a z>5`?zi8JohyYp|W>*n4yLiBCww|4*Rk*)iLxfjw?_RJ^i?sGnJN$1mld>JJ*1MAzZ0W|o{g%=_=9*pI@1OX)Xh#2eNz$tICBmcJ zImxW_)JzWT+PPC!-zIvNkL5Hybksxg-|^3Dk_Gj56+O$xa+2oAP7B;c7d%uX2A%o_ z(^bwB75Og9#IiAd!aw@DTQ0al^!9FblvYX_e8h+EvL2|z#M|6|SJHn`H|ewS(Yw!f zp5@jxxK!_k`7zRiulmL4UC#UY$}@Lxuk|@FWxA|4>T8sic(Q&_PoD9I-0+iRsr#qi z4fAq**Xoh^^)o9hejst;nh zY~D}wtOxcffLuQ zx;A~_r82$CIziot-rBY3|9JMmv}^ktlsA4)I;I=uZrSB*Q${ux~cdcI) zMq6OtD|+iEl@@73eObRM`k%iu-(R% z`qbiUsMKhpx3SGP`JDB&9OpoDpO<_k$9|s}V}av%K#aJA z{XQ{$oBqGqz2fQi1L%vnbpv*(c>eL5gb(`m_7(kiD9~SXziZc^B0Z$DaQQ($D{tO$ zh;Yx9v&+wJHbMCMV+U?GX7QfFk2h+t>YVqrN6S^*cg3n^ex%~7Zh3Ll!tp(YpS-h8 z)mc@|g#Ws*f7R?+k1O44ZysB<+MOo+=9!bL9_;z!mCS=--OFG!<&3v?g^gzg<1H;= z%Y(4xP1y1*Y-JI)G74MSg-s^HCM%_DG8Fza@<%;5j`?QeIU5HP)>rU%NE7@KVjE9I z6Z{?4Y4Dr)Zt!KSi40@9^Eo zH%Wq@Mf%`FS^k4R;)1`!_~3U~KIQN5-N=V>!5<;L*{iCr;O|&IgFoehzeD=SH{m)m z*T+>Bv!8{7KgB!*e~0e|KZX3wJ{NuDL%9ph-ywbQO^Ac9!FPk-ME=3wAx-c>h)KsD zgf!-N(63RM=tD6+_&d?N)lpjXDcCPL^5MJmcWJv52j42bedL>jv}kj>;DeA)LjnE5Cz0gTF)i$cGB; zROJeO2kC>qL;B!bF+TV^@vpC`8tIz;%aA1+J&@#o`(*WUP}V*1Y$g(p98N%hOP|C>oa)BnhH zuiq^c{@(8QrfYw`K=_C&w(>VE-}^(jrqjLqo6XX6{!-7p#rU9ym-$!f}4cQ-uI zcmBn@nydNi8DH}^J$jz}jnht>@Bgv#3E^+gpX57@+*W*6{CI%hVfVhmKkNBb|IJHw z7d~XyzoswEnJau=^KYknbU9YI_R`v@Ehuf4JMSwpDdc0*f09F?@YUIA^7B=PIa0>B z^+Ee4KYewP;=gy(tm32bJGXa(}!`%Uh@3T>?L8dXN1kp5jOir*z6)bYcH*jY8QEYrW=IGf~J@_E5*>v;%f%5)nyAky`f2rd*L8=(T zx2R@6&UpA1MfUZ?@GTOK0mSev5{?bT@GTt23}W~ej$;Wid<(}hh8Vtuv;%f%5*i{(-(!qz@%bUnkTTeV|Z}^o>IO z(q{_wPG2hM1AVNZC-l97{?I22dPQF?=v(cjmG=*(4{C=W#u_7hG+vZ2=ZZpq&N-ye z&vR}m^#7c53gZIjqQZE=IjS&@aPBIMFPzf~;|}M#!gv(pnoT$FA4~^a_GB2#L^h<0 z?8y@5TxqcPIENbSK+dfO`;c?4!EWSSY_KOeM;q)+&fNz4lXJSkF6CTruvcp@t-OCQ zefY@!0lMJnSCB5os4GufpYf7h@m4z`WVE}orFFH zF?1@Sk3kGwbM!Gjh-)_8xGm(Evj1TJfUzQ>U%_u;jK18_?pJ)n6CHgFV)XrvJ_a$y z1Vqf#@OQMV-RD^N$6t`V=PMOV-VL~T6zCKd4IHjv8m*vx&4&> z2~&f8TEegyQ~C^yhb>u6UxgSpW|6)MF>KF-z6vpH(uBSWF>F;wUxgSptfQ|&4BOVx zS0RSY>*%X|5Z7$FdEY{LZ``-kgiK1h|3EMa&Y~z=(jce*dY`hbOufuUr zW1@{&8WUq&v+34Eo7$XsmTX!_eK7l0*z8YXvrC1|UKKVwR@m%YVY7RM%^nsuJ6YK5 zSmD}BYjbVao2pzT|JPF=xG#x1L2Ul1u=%aR=Fh6Vo1ZIe{;%4;`NeAc<}WAYX@0b@ z`Mi$tF|OHkH>b8-6J;sQkExEhZ;N9F>&WJ;R9`l)mDOD~-z9AGV8S*(CT#O&!Zx2K zZ1Zg5Z}VWaoYtmlN1H7l)f4N#=55!S(C3=wSz2=p?S*TRL7%xkC~WJ7!nU3m+6C7c zg>C&&*w!V5ZM{;Ma}2bxSR0&spk4Jr%sGRaOxM=jJ=2Xb=dL)eGv3zCRbE?97v>xo zZ3xoX`n$#pTbEB6Z|n8KwvMl~IQK>yf;6?4)@IwTB}dBg^UZZ=jg@O^sxMn>6Snm) zVOtkdUE6w@bimfp66V6z*Mx1|O}b?3al*DvCv0nKAHp@8ZcXIrxyX&o@rx<9H^=Tn@P$VjU=kv>E;5j`^FXOY^{V&{y0-53rijoeK^oS3csHhr z-;HTzeUU@IBt85$Sp5(3<3hh=IOrE2HRRY_d|km0j4% zE*#Uu@i9GRz%nqOF{aE|2F6n!%o8!?#Jm#6G;w@PZ#pCT4`Aws;!Pg{rk(`)n5GmT z)1%LK7$d5fpY5()=IZ`(vfAVQtFT}C^hboh`}Y&vgJ*Y;{9}4zzQ;csmsRgJUJKhe zF1pXtuOg2+Z;5G{y&;}vhlG5T&iFOEC8S$A6WHt*#hd-3e41S(%yBR}ug?d2!{}4y z!T5OM&tosu_T381FaNAgRbH#>BI8X5gkzexu49_`-IylVhjQu0r?sDJTOUH(XWa!H zxA(Xoi2H~1&cpr1x7{lJseFHqf8;mM3b%S>s=uw6{ibjHeq;R9OFF5o#q@D}Ods<> z9(?F?kggB?lHs7Aq*1ytyEn3HHPFX=SZ^V3tj~~V z)^jKe>pzq+rjO%e`j`*ib1XCS41SJfBSt!oWhO@YjErmAKIUUIj_(?cu+bzD zPvMx}(o%d(AM>#?il>!P*vcquG7*mH-4Oo+Z5Ctglqw+VDZ)sr??SIN?X{3qRU*MaAj?EqGs~-}UQ#EB>;wvvB3a zX62(!<~^6VSGwb4tG<4w?xXZ;_gh$1{%AYJuNu3qYT{!Jh08Abd)4o5`-^z~y}HTj zo^M|--2d&4t6v>9Rrut4Dpz0H=KNLUX_z*gH<}7!dsoOl%crpAU)bhMLOkzh5A-SJ$UNYW@)3@0s@V3n??q$sS3a#?te&!V_(|%N zG~t|8;&6s4>pz^=%J^`eDsebBl{DeJR_aMO_m%PCyjIeOvsD=%&TA#Tollq$hx1@b z6V7YpyV2RIJcl3WKIZpRgmY6VE8g3{^Gqqj=nU9!PXW&~4fh)GTvD{_>>hK{^9~2p z0natf@25cHqfEk?vBcqQSjs2ApW+gY5BdERw@MD-3|O|W=sZ>3LBX?G86VC~rT&ET zTB%pj8L**W<$1QD?@dV`&TA!obRKNzS4AJrStWfqua)%SoLJ)gev0h=YmW8Nd{=3G zZF3mw!<+`~$Qa9_Kw!2(!vD=?5H?%FG5+(|Y)F&#ulUr4&9=GLBkO^GHCDz#T% zS$dnNjZMA(H1{KrKEI!W_jxRL`TZ0>)13mr-@$mD-%pYGBl-Ol@aw1#!3QCRji_-O z_FlLrBEO#^yC;!0Ipm}J6KOx^_fz2RJjx-zpQ4@a3d!%MpcS@ZzO&}B(kt!Ft7)6| z-cz4h9m-T2K1iS5jjA%ccEkQdq_25d#>exq@jPuje;d#1#`C>+y)+MO^W@@-a+T(d z&F2d7`5sgVE%sq!-!}GnV?F#pebwlkzz6E9RF84}#`PZSL#!vU{=|9}^o@N!KK|}I zFRmiCIegtq73PQ-ALf^c!`u{cxNnHq?l{Ao@rH4PINXs$Jm#`R6?lpU@kOR*^qiL# z4tGB>KHM8cjC7SAG4kV>9x>;$Ic^bypVA}dXL6G(R!8wgVxv!pjgPSL7q)c8Bg}!5 zKFpsJTmD7U?-%b@GS1?wnGd5+nO^qY+B8eABsayIJVSmw(<43Q!Ssl&UX*|Q@9W)g z@2ZUF#yGFXlAe5_>oJTyXv6rc&2ctQ>odx{G*-vsK#ntM=5om8@cDFr^4rii!9J;J z`%3$6m}+b%Z)*FB{3(~{H(A^}U1Mu2wpZ3M)!OlEvfp9lbytwgW1qroa>b)M{^MSz z|4!X)XmfEL=9n#rf4O{eIec~P0onTKw_8V-IL!hU8giUV3 zCQo6Lv#`lu*y=^t>Py(_QRSkH@!9CNQ!L|0#kc7ETDpa+6rT=Xc_7`oxI#FNf3WUZ z>6sIM^C6nEX1!B=W%su}mVTeIZpCh$-v8Kl>s_~7Qg-BXqKVUr-`#We4atFfuMrUHy$IJk9xPq$?qm7oOz98^-=E{joL+=Zv3vLl~T5Gy8q@~(R|dqmWP-o zPFL|(mN+fp_+68U;w{e~de>z8vG1A=eC)fX8={HRjo*#ais@sT5RY~sou%H^0uJ^Q z)5>us^IQ(O9C97Vbs*P)FT4&ggB!-nuk@CY#@oDR)T-PrB_JKHB*Dn3$g7MM1HrHdhZYzFae-vq= zb#1K2j^TQ&Xrgs(t>1DTH~UV%r4o+TwV7^M*Jgg4t!p!%VO^W~59``|-<_6R#C7cu z&voHI&vnnhM>ty7X1NmnPnu|5JLFUG(Ym%@U)HQEXhVEh*Cu^f*CwB^t{vni`euDF4h85bJmNC$LO1x?Mh1{q3V%wsbUTy40#Qufp zUA_nS3+_``Jz{+-+sj=GdsO&4S@kXE^9tA09+jYnAx-|D_bp%EzQyXU#`YT3-ft*2 z%{UqBb&f-8U+y=Y@06dNh4a4hv$LYPJ7`JC4v**h;yJ*0Zjf_+ocpt}gL^oI(cWCp zxSAd}^Ru&>X#UOSHu<~Y{OqiG2kXqMF0H>=%`=-Qlb3G2cHK9sewy$sok#EcZi3%@ zN^XtDJy%?EbswFDm7ksU5PvhS-%GRoa*o#KqKl?i3C{&%yq$R^`Xf6na2H+hP&MDh zd2#NiW6D#~;G=$k@8)M`&7?f=$<_rZ6P)#w@cbs?{Oqj!>@1sGQk#j_G2``3G)vAq zi6&l0i`Pl*_oSkU*W)-=hjlve*<@q==6dE5`8h-rJ~XJ;KsKgdOA`Q~S5Q8=l)=r*s2=@`e#l1a8@q);>2uY_^51Hi{ZIs8{rok{%zGG{j$49 z&R;&SYTC*Uq8WDQnyT-QX(l}L+DEJ2KB*wgC;ulOeos1LzQ^~8$&Y-Avox8LQapb9 zS)#8XHa^0}U)a*E%=joj!j?~A%fB#F$<~{ed&HL`AA!CC`4dKdE0CTr_*Wo3VLti4 z<)@N#md{G0Crp0io8_l#<)Wqa8WUT*%FA?u9GFg!kMXY}y`{T4itGo2uR%fI4T zu27Hh{#l;i#C^Q1-*~@mynoZiTg{=`{$F9+|0^8kTr)n|94c|VFF4*W9Pc9z<2mUq zU5-T|Kf;zz;duYDl`F(^|8Jn@{$F9+|0@jsDaR=C=ac^vhcSnk?{TaoCO@R7ecAjU z`;FH`@nK)H_9rvm_(&$kU)a)hq>1+<+nB6)rbBs=hUGFnbdi3#NN*kW!t~HZdhR0q zcTu}=*1o8R&e|9C5PaCC`B#dk9tL{qTi_#X{Dm!D>R8B+u;o+O@-NI(vhS$x=AQCjmfKB9})NaM9ryk44TjptwEv0I5)dN%fnr;U9fAEkNUcs@9uC$@5n z9_8{(&+=b7hlaAu)=W$Dmnyr_3mYHLca6WWr7MiDm>*%wr*J%W^ZkEUcTt~1JDPna z+A+t)(r+ec|MIsBipP`xvk##?OFH4G4|GxAi0?~%W{79sLfcm9MSR$w1RqG)(iIQO zkFe!a*z&(oI^+}eIZP+~W&(7j-%O|+ERUtjK2zyNeO<7@6>oi}@{e~)ztM>L(mBYkLjo!ENq{mMY=9B-c?(x0oz=!Ygea4d?`4VU8WV&MURg5=!VWtB2^RY)(;S0O!NrPK6cVens#^o053|I7pOvpVF5?;$XEo$SR$sP;oMSV`N-`E#z zQhN;i9C=24Da%zO_Ot!2tyb)3=*NfZF|OaZ-eY};^(5AxSg&Gz`!{+h{fzZC*5_Ey zWBs@Mc-DQ~UOs9Zw|*ngb3IuYue09}27mreR2WbGepDFWJEq69@E+|b<=O13(7s%D zHd^i4UCa~v>rj8DpDr3ZTr{S*XsmJUvu%uU(b(joG0R0`nPZ=AV+8ncjOE|*5YKTT z&Z%N52%mMe^vfzN6yR~TDEx{9~_2wOgdE&sw+t`ZJ)R~z;i(`I_L zVUMxDWLnl|3R|BkZ1$=!?aE;9(cTPp;3u`8%{Q-c`#Jka&; zf_?0jDjq7+|aV?=i5X;$7?4zYZYjW6{WVfE!HPmW!b zJ2C!PU&2;j!d73x_PwyxR~Y-~n}@NFcVfi#r8JBzZ=1(B8cr1v=2z<54Y>#mFrP(AJL&mmcY;%J5CY$HU&eJH(%LRX}G>^Bb=6Pb9KQ3b|r`qswkaq5$ zVoi*`4Q2mneVl(&UygCmPtHFJ<6q9N3fs6Q4Bx7BhO2$Ac)rK?$;alyg)zqPUXHlF zg55=WVdLZZuJIR+$5VX8{3zb?DIDt?-_QOsTO`N19C97l)H;yyvvJK)zHG-)zp=^Y ze9&*i>ldNl;J6n04fX-*2R_f7Pwuak)=BevghIvRk&SE8w|JeG<67LJ?Pueou{E~0V>{gP6UN_? z-ER3;e7?R`+EbC&U8ZBDIe`!E?fLJmjZ*vbzL!$S<&a4sm&2x#Lq3O_NwQ|-aN^P* zV4ny7mir$2USE~obt(K+{3fo)RaHj}Xu-8IfBo{as-~})B7D~=bE~dAZ-=y6CV83Wh;ja`GN3)L+6%{@BV$^2Uc%Uan9>2h0ka;x?)g^3xv<@ zyu9MV^l0H$gDC2TTOem2N9lP^P@9ij6LiEaO~e1Du%!SgcYqw%|V zY=d1@8uM)aFxXX`KNZH))6U|%_$$p{#Pb^Qd`CuBng^-zea2aOrFm7AGxkekyEC>& zV>=Z*N;Xhz*T(j4W&>nx#mX!BnjC~pKEft9VWeA{k2X0g-sB(r=Z*HKvRt2}PD#Tv zQE)bj&RoTLtDfhsQU}8Ci%1jBYa+JuMnq%38&9YwI6E}OS+4qhxSd-fp3}w+^=mul z=igrVaQo`_?&zm8Z2!`zO>#$m{w>efanv`{L!L=1UE1-_Ymx=^cMUq``1=Xc*crC@ z`M3645w<&=I|SK`NGYHBx7BrX?;4>#+s;Ym?@aXjW&X~D^fRH0j1Ol| z5r=c7IA+jB$(}Vo)@O4ywKvvhb2gjbSPwbE#^ayvGb-UMF0V)0Qk2D)!DeGVa~u21 zRA0+o*gucHRJI-K5dE!VpG%CsS~d+a+NjIVzs=9T4gM7MBtQQ)KmYcaYj$Ve{(V4aSGx#*;oj|F#ePi=@wrVpqsX=Lj_a(XjN91v}}C z+2ET{Zs80X(&y*jewTh$68t8P#cT)JUye7i9Ax_#&m2n-8+_~7&;BfU!yJCTK7utJ zt#Rb*Bb$DIdDeb6zc~|@3u6Io5%oYBbc*gO&K$EYJ%#mMf_JjOdvnyOCs}U*f zJj&4Q5YaDtazgb5-47LgIOB=*HjhgC(La0LFRSl=V4dF0*GEpxk#_2mUbQI>K*6esfWQ|AbsS6!P{5cn-qiWp{2adyrVZe0`)@1?5n6%ZsZPj_)a4 zao-iIn)#8!k2h+t>YVo{3SWQh!0pB?&euos^^t?nzb0QF!QCd5L)eE#oZk;f>+Zk5)|1&p*?K_R3pDoovF)}kZ&G&* z?Ev5P$@9wJJ$Rt-1NW~lFBZE9pW0=s3Vuk#IDSV=TE0U}9^^%w@m85V(?q;}1HgFD z3zHsvgvkf|s{((dAg_&k1yXCBxRdIchmgVCg z_iFLUJ^kE|Ps~02wojk`^7jvlr=JykEsIk;Y55L`$%DLz18-ucNneDB@$^NAElo#E zKJ-P1$)COmG1D|(g#UW_76eR_J_m7@=7x3=#g~5n$}}TBJdZ8#cTu{GQ#@&-e7Y$A z`kv{cT#OIpCB3la(UXFFBDpbL#WPKOCk!%Yvd~#OL3UZ18|v$Sq3$Lgb$@lgyH1ph ze}BNwgs*%4%yqksuNGeVV1w!@$9`XU;!)$OXHWdLaEB94s^*99GLGL7la}uglLvVb zlQ-*!m}w$@Xov@WG0=mLF!_MLF!|#n%rx{vc!&k|E+L-zfu?%~A$j1T1{eUJnB z2qR4w$xZvG$cJ(Kj+nH_r!aXi4aOU9;k)m=n6ebk>rVF^eyQq?<170z{zYRtZ573H zyp6{6jckT!O!s(Q^c-)aF?}PO1as@KyZ9$tC5-8$4`Vv{@DpqmVY5|)InGC8I&Brj zlSeeBgI_kL^L(i&p8aH?XFn;7+MRuK((MD>z{`hqNJhl+-LBbvPKAP@7CXN3tn{bO_*KQn-fS!Vss7gE#SVQ3N`EE|sFUoqW*_O#8&|bUZXS2K-u?TN z_ZDyLc&v2k{T@3eyN`TAd>TB|IXUu)ZN=xDG1HP2Ki^4w&R=$7a`Bmy#peejzLorC zo2BA2s!j9c_LmP5pBd*}n_T|rL*mo$n};Tkj^0Xq9-p})ncKFr_*_x%wxq1#aPe8! z_>W2R-|R0w6^{%_{(AjX@wxj?ZzkvTUMoIr8(x+i)#}xR?c#;;4Aj#i{f+g)H28S*}lk+?~@Pt@qM;0^5gq#U*yN~kPpkp_u1CS zkL4jBmXGBjAC`~hAs?2HYu>M)!M|>zB!(J{ShD2AMr8$ z@hlhh2k(my^%45xSuW}i-WMO!XYnz8_LPt5v-nUSQ6BN3KH`1xp+2HK;$!X0XZ5A_ zB|g@^#E1F_`HBzq5#Lc_|e5}2TkF|I4vGy)L)JN!__)s4qU-6+nLjT0a`XBMJ z{zrVQ{}CVRBlJ&vs5{U<@u5CK|HOy!&_D4ZhW?2UG4xM-h@<>eL;u8w@lk%N(H=s6 zs?i=oep0lDke@V?Pj!@^G?Gt>_8H`pLjQt%Qs`fhPa4%%8p$V(>MMo*i4XdZ6#6GV zsIL_ICqAgJG}50ms;@NCpA`BR^e2V>i4XKAh5m^T^v6f~oJRWNBYjSxe?gy9zE3?Q zKfZ7J?4$OTM*8fd_LZ_c)I*k!L;u8w^$-0MAJ#v0#rnfE>VFh({b5R)tbKJ*Jj+FWWIW47 zeT@2N(OZAW{Dl6Q`3e0q^OKN|9)W>N2Vtt8^)tC5KeTfh2D;iH(U*bc3jK)*ykN8j@qw$pbP z#zp&x9BFO;j3W=*SK~6?OeNdT%{?*1jOSh%V$$2b9r3aKJmPQre3Y*3|51MMP8Hu} zn&2hOG_yIkYz`%g5BrEnANCQEPuNF9{$U>x(+&HGn4hXBpJ5*n^Ix^@fo|MK1U{vG zM2csgtXyFqk@!S%3;T$aZY1Zhk4X8XjL3&Fi|Y$<>c=V77)SFDH8LlbrI)1{t!Hht zu7_`>Q=Et6+$E_w4`=HxU&uX0;hc5KI$po4$$47JC9kh+eml|=>PyfcuFc7>iWF~qibQXFip0nE6p6p>DN?$&r%3s+Jw?i=%~>h`aT%ld zFqcJo?z!ULB=X^2EMcY@r5pBuF+X7s81q?ed!m^Cum_CgVm$YNDL#?|`4kyXK9Ss* zuHu;{z7uACBKe0sU@X@<+l%6`FQv-%t7wmm?PJm28Qb52Ju9VsMBED#_7QO}jJJI< z+)p3&5%Jum(%u*D#r6^L+$GX;?~v%31~K{Aejf3+eMCx^-(`GC`-qfJ z@?w10qeMKp$rWKA5#z%?BGQL_L@Za>M@0TflrFyu`B56=N!djCcm00x?&>T*rF}#? zPs;WYi9V8#(jYy`6!sA*E|PQDN2Gj4^};<$$WwoZy+f=19nR}fdy2mB^~gS&{TKgg zdfg}AM^rQWi1Ix}U&j4lY;hafUXCdb{^c^s<*+GqAoIa7hfr11ejLth!#n{0YHu&f zEjRz3`(rhB)Ayne#vITm^x9iJ>n3u6fnwRJSlbzNIW)4Hy$qorI&vvobKGut|v)^%-NPwULKuIFvtoa<;> zXXd^QtfQs2Zq9W*t$W+Lp4ORdol)!Fw$A9Ibw(epGp4p~Ey{(%oKU{~mby%)jhILP^!`nJ6*Db?3tdG`VeY6g%eF3&E?72_D)?u|Tz}AI5 z_bJ%Au(x${uIKt_U0C}RY@OP3--N9TYoCIxQ+w{4uytzBeG|4$?W1*S?VDg9L^*RG zhpkg{4O9IK)?ra!FQ`w!IxOm|v~G_2Dy^HNzO-)6{XfbNd1Cz(f|BvF2nke_J0V1Br7M|(`7@q+S6$j9U(J|-XW;rJYl zUzCsdP(IQ4#rhH-t1t1f`Vt@3m+d2x{zT&!_x*6cjrIXi|Ck?+&(I(7;XWYfk7K#0 zKh!_Uhx}|Gk;dm}d=LACgFd@RpT&p#B71}S%zZo3=g8g&`ZAkyeuT?^ur!@94K;8ds6H^aozvYaqSLn-s&!r8~3Sk{}|BhhP zmgE`kLnMve11S1Y?wn*+n%|QW-GS)C-HvRh`8_EIp^f(U>&u#T<&*k@drXRu5zoR+ zt)23G;Plb^zRUY{M9=+^+>c3m_I&)F?}vL8`G0;-O1Wf`-y{FaO6thwHr8Vv1-2sp z@_Xbdg)g(s#{8Qtmk^tcCv3K#W4zgf!e%Q9<15;b!e(0vo6Q+$K$iK{W}^oB+{T7v zK8=k{IcC2N)BS_8pTHu&M?SwNg|@MNU&7yHzz*Sk-yXJ$aDGopeou~L zH%q=#_eY{<8|Cl4NFVN_B%Xg;T{rix5%e`&`#Ps4-|M!$-i>?{)YA)gSI40mNAaHW zd0)#LlQut|sdxFCF!NJfxSx?cgTKSHa8GN(J8PM@{GOE7lH0T6%6(bg%T&K}XZZA~ z#n6XdRq^@yNOo6-*@2QL?z>OQ zI^Ie@&gbhRn%@X(7DejVHuv9^^k39X_nA!iM_+f#1y|_K_h&oLa_bsgO1oP3pKy+z z^t9DD4o2_Nmh+Wo?%-bQb0BRw=_&P0*INWMPu=Oxm& z;4e^aKYwSwzi9vQisu<2^cN^M>nDY~uD>Zg>5P1Rg#H8WWXab@vON`>biN(yGdgFD zeP3927fnD!ohwEP}<>;a-2^7Rq`Hr|@(KIFD7QbJJuvOs{sz(0C!lW-wL9Uk-;D3Rd(pM&122_nT?R5wTVYL#^kE+w zaoA%<{`{VFe3xrhJX4VI!SAs8@?kv->rEbORH6y~2m#%dzi{gyS`%c>HqM*=FRhW}HtptZ)AB6oaP~IO+YV=1^X%zx_BPM+4rg!k ztm<&~HooUs;QT#^&f5-WZ}YtEaK<*ZDV)8{bV5AS3G_@S@L@WEKc698ejoC~_d-6& zFXTT1Nk zHeT2ZM4B*fPa5mzMPuvQ;$vfq_;5Vo{)T8Q;Cwah0gg?gv2jN>q>V44!TLao^h6Wp z{K+S*5s(kZ9GmynS+v}bLYlB%KpNY_AU-zciYC~uq@jlJJ(i1@PySEL?~M=lcn3b* zBN6yej-rX?;k7R&$`AKcg>vb)2}~o*;aj=5KR`5QFDWg`kH2dmjqUdk4dq8V^5OT9 zoE_T9hB# zA!&ZwVnrq5#3#(3lP1`Q#;2O?+4$%;1;!^0e5_rB{FLm*Uc*uF$#?JJavYa7ZB z<;V8Sw5*+q#@eZ9_ZW*q*JvO7>xvPF7#B4N3XY-etM0|53eLKNj?d z{aDZ+_G2k^4t;2?*(&*bX?EW2=lu;}{JVgx4r_kyG_Si&S$E6*usgeIO@{67k$x4G zFEsqyD&lD?J5-*(d|nmt_s2A=9Cqg#;kQpJRL;EiQDHnQ@IUU+C7(4FpcBS>6?k75 z{K~;sm^y;=Lj0-_&vXJk(+PZ-PT@!hA2} zlj(%~Z>X=VYz#T}publCiN2bCyD;PU9clQN`+#2_AMlgZDQSW)z&fXGLK}tkZeuR} zh1AC4gfuorC#12lJ0XpY>7off0%^s5lCaUglNph5RKU$jx=VIh$i>~ z1Nne9T4?AKDJI;YmZAg0?C71mA&tsP~8y4KZj%LyYeOAKG$( zk9-8^FX@ZYHn&3N-Pw)ju z6MO{H1mA%)rq7gd&}Zex^jT>IU%>JsAHniNpE{IF?U^*zzCyX=J20)_3y>!G2;^h! zRD6OjKpJcBsxNErq6xkLX{_H6P4FF%gYf0dm{0wgFqQbXQ(YoL2)sPWCucwcie_eb>}^HQ2MXnrYRv4UBVm)&x1$ z#$GJQ5&i=Imb(~daVl?Kj}XSE{SABV)nnd|WxATnA(ul<=m4dfk86~|=Q-1(_WHxD zzT&Yg#{8ClxqVVDKl}?kt|@<6ZEa|Oaa+uBCY@Xkxg0*d4p3$r+Ev~ke$o5GtiIy0 zEXJV)Vj}Ao}+;}BOHV0 zD4pXs0`sKJV)SJhOn&Au`nD@h8+tX3d8VZ*rCwAunV3H+ZWmu9G(o@71|aO zJQ=nvv?&zvX^k+!b10sz5wZ3Y=mcT z#5F4P!gK3FPkb68?1kq}g$9MK5H`efC&V=@^uTkg!jAaVN7w_;9f0Z~+!4?2c-BMs zl|o&F_3-S5XWhc~_-u)=8=hSYTNLUb+!D{Oh}*JIiD#Wc1wI9Ym3WRX?25XYfdA_t zWZVRN3JAO6zugeK1;VcQe>ZUGif{trc1P@%2zSGCcf{|8up6FxAhs^Ty2#HSh}#lj zcYL!4KD!qtBG26s?tyP70_{4Yk%AVP8D=#2 z+!v@h!sgJ%eW8;B5e~w0KZN@t+!yitBA82g6|JR zYzKrR5O*Nr+9Mo}=Rt@$5aEIN_F#NEBJ7Ah<6y)wW(1xGqbC_rI0Vl!gd_1h1U<~i z!UFu?3E?RGzX1KuD1?U~?od2CA?$=6=}^QkKsW}^!|;C>goomJ7-9}ZI2O;t&}POK z4o7$x!oxswI9k#;gk8|r9ga^q!g9pz0DapLx?C4J+zaih2lS`_)CZp)2-(W}BBnPq zgR%X9dO=ePh#jD|GeE6o0KVG^G3*-#;IjkjpYIF=U2kYX0q+dL|9ud$oeola90b~K zz466PJ`{JF!Kz&iq1;hmRng3#eP9N#(AQiAtJ;Ij+r z2m8x35|knAjM^B5*x?9=ZNZ-o0I?f_8i zhrWYj-)zurjc^v8vk^NJ;Y|ED2P4N82)6*oIr!{@a38!m7d`k^2suj51#Lrw2jIQA z;y4ejY)kYU93|(0u0F!Kc+NvCd!c&xejd;P2+3<}jU!uwq5&{RifuqsA7Op`-$-Lq zBgAZjTysQgj87xTfMZ+}d>TV?90!}?(*%;^SlJAprl<#wr_J$crrxas>SQ~_ZHrHH z)Cqfu7Wizdp0OS3oc&Bod|E&|*r%~SZHKTO{%fUPtCf1ER-kODUbrJd_IqE&rxjA- zh|aNnAacO5gY_{GIperPX%0Y+ITBGu{ZSH*S?rhkp@d%nu7^(_l$`xfeW2b5>)}Z` z_LAHgawMhn8FHLuEi&XN%(`UA5u6&pkYhUafFUh`#_G+ePu(D=CJNbKH3ixp(rOCa zTzwIBx+^5q9R1R^_>6;WwpGZ!m#u{%dtPlg<|sW){X{W^GlMW`OauRzvyAa&N}7La@${NJe)Y3eFwON4x{ zQzw2;#BWHw%d=(1w)__OZ%ed??NN`F_|!p2`#!ei2TS{hNaHCV z>Kxk!J)2h0PHI18$Z?u-+8Lh~kZtgpIPSBJ(c@_W{celz619!s{jfDsZrh?ow8M9q z50v>sq5jx@GEXS;)H1(~-cjZoH9Uv*MV+#q8`{Xj(TQGLZ`2IOACB5RQ5&qu`lv7Z#vF_2A?}14q3=u|lOe|QcZ42vg%(gU<F%usC@&)ENl87j86FgHb;CCpF_1^(!{DfYh`&rt1*n9w_Cb5k6{HlCqk zn`2vJYog`FQ7!9p*|TmK&o~doc1AmnquMs=O=;h47|+-vvR`D&`%iOI?D?{hEF0D0 z@oeK+seeD7ZHE-PpgwznPj7JQjy|Cq5Ix@R2-z3+Lrfo(m$CiTchKX_{9^jZ>|+Pw zL%Wzg`#^lQgADo3&Y+{e+zk@UJmSI9{=v}ru83iaqkmh0kY4i;(Dg&u4{r{|TbXy< zAARItP!`qBi$Lvw>1ijRAA*oxc!DQQ)WIL3z&pd5`4M-BQ5nb(|o&|^SBuek?k z$Ko>z;|_cHaq7kB1GfZ@{pH~pk9Gy!aCo{s@XiGFbQ9Fm(Wm_?Vq#C3KKE|;&|mH$ z@0cUb9{4ntPum6|edNq*o(QV(@MY<9PsE2_a}RmP>Rhc(WX#=76ps z&$bc5*k9fkbaTOVUxYpJoCoSH5VF^#FI)%VY`ifKpE;OaW4}FL{rr5qF&p?RXn&lq z+Y(_<#LdV5JrT}ET&GU;!HMGt?HziS^+8`3VF4e;vk&-h`7gUkHrf0$?W}UNP0njm z<90*HIh{%PY=MyS;H+~U=od9>GJ2Oi5OQ96vaAJaA9aWl+7q!`N<;QUNV|eFG@Pf| z0naIt-xQR*9`K&{Zz{go6Cr1$r=pg3M9A8n3dDIDj=j_HT|MdGG=#Km_Qv)!8R!LjL9aN%Q@a`>oR0sfkJAy-vZ5|=rnxub_62H) zFw@GJK>LA)voo~5IJ?7n9ctqK_-<=x4`-QY;oJQX(tewTey$(FeL)elm6po^_@6U6 zjGYadSqN$S%?6^L9RQj+_%wk&4L~esapoYT-8dJ0;Xs6(ah|8vKTqwO+S&wqw==$@ zZc0C9){SKnDM3kd^kRbBIKO% z;rJX@I6^(^5$ZLM!2hiZM}qQjgtWkqL|^U@avu3eQ6HtA^(eg8x^OhUJrdy&g`*JC zhCdqrA5l04|F=QNp7mJZV-OyV=dqwU8X@ifV=)d4FMJK(wM9tV|7#kfjzi4X3diC5 zV-SwO^EiwMBMQeOwmm|QP78sLM|d2b3(=R4L^u-vEkbMugdDpT11~~Ie`K+Imc>8| zffwSNC7>un$Wdzv=sFfoz&DE!a?a)ipd|>$AZ{s8CxjfYPQ-XJ79m%qP6Rpu;Szjz zBG8h;GN8@~=@l)*XS>33#4JO|b*$x}T8eO2JWoRGb_nTLoupCyWIQViC*%8N2$$i% zlhGGUK*-VlWT5c~$K!i?H~-JxdBEvam5KY_nPifg^kmZ8q>vB@B&5g2uq7+d< zK@da*DWa&jh>D=}VnIYK*bqfgEUW9PxLDSXU3V4i|Q(bMHOp?eBTdq_kGrfoek9>?ZNfe#4pR8>-Qa=iU4cvl*Ys(@&%2>K_A? zYmG`XK8n_O+T-boOHyi|zevw7mTG&{-Z(tX`*2!Q5)O}o8u?91?%V;K!~c;|42Pmf zwT2|B6;kiev=WB$+tfsNh6AT@Rn}mX{6nWv!ztnWQatsXCMcaWO*+{O{R$09+NF*( zBvH4PM6-nc{j6Q7A&2g@BvBh_*6>7$+MqAKS7>X?(tAsNMnE${t5dsM!JDcF`o*Ls zqY^byOAH-Rxpj5I{m>(&4r3E_P|pmFQ#_Rlj87Qe4hB1WT7vZS?oUswR*wyhR{8p% zG%rfvYQ1W_SrZP;crD}W`FdGr4jnq|gjvH5ZCjgRO#@dCcQuF)!qC^9K`oP6pI5)1 zn^w8dHLT_@ltamZ3Sg1sAbHf06nzCsF^^%6_5eOA@g}{hk7fS!0fY}hZY8HtzEOTT znydE&%EPq$?*S)~Qy)W78j^eI=Tvq%iYp$+)r%8%QA#?R-f^seW?(Z{$wh?vL!ZEP zdjTIutq;=?`PLIzcSC?fxb}F8Tqe8(N-Ih|djZuSPM|M;Q9^hUML9^x<;j%eq5UUt z&55*>dgL%C(q95sP^LJEbv6vxlDNr}_+4+LoJ9|&+(b!5TabK0J~Eu&m2~79auPj? z!jrk?RLVX;InZgWCas|V%M*RKt)6xkICBP2o$PE{XC^9t29#T# za1K|j1fI#&=g?XOd=_Kpf=eTTBNIoEb3B{g+0gH^xkCECDpB^cq0{Px&!L^KJk2d&w)lim+Pd|&jo5nl+Le)Dv#xN zsk2bJ|3X^Qb1jkoLVsVNH2y;9>R8}du6+?jN-m9;dcP3(FI;~SWq;rc>Ae`t9|u%3 zele{Ji~Ut*cj1))rSnl_mnU1YAk$vf?Vr<-jYcucmbc@CvTHnz74^Yq;{t;#$g8z-y?l z?)w~G1o)oCIcsP)hj920c*WbD<@z9~R$!mp-v zeeoK~D}k@%iq|l9eQ^U<9}Lv4e*>fIfv=%{E&uD)#f_BL0AIuCjf}mzcpa?`z#FM= zf~rmfPUDx?Q*H#_M13w#s-o!6&q88rF z|9TUxn~OKYiDv+3aMhbBZ!B)1ej`av-o!O;p=<`ek=|SQ<&DK#x&F;SZP9O|bqnyV z)NiNt7T{aB{_Tw20@RZH4z7GFQ18aAwB81M2lYFt-v)de*S(Xn1!&~cZTxyGa5nXA zaPis2yQpt1-c2pMmFwP3*$Omj>UOw82e5;y-a~m8@OJ9=QojrMF0OkozGAeQ{swJhTFm6^@^CGGN-9Qf zDa9xa%hfj}D7V)_t=&v}njVKaQ0wrHs+TGCE#*ra1E=3%bCQk1FSHn*p(dyts1L%q zC@5QidMWfo=xxy2rgvApIwHZ8&a~oc%iWFN^eAYx&9+=+H?3@X92UY~BU(%woK`u# z5K4Sy`kUU_{}(JZagtrXN7gB$V5R-7-9K;iYp{vz;?McoCtOJyfoc?8`Eu&(-59 zj5t4~#_$$RH7``!ASwtne7Q?e84O*X8nQLn% zt1Y~tTJc;vMm)N%a+Hf}DMv_#$0{NxT`k#aJwMThMd?n9(mfWj&N`S6v3?P2WiE3$ zkCqn5X+Wu^o`xAfpF$tRES_7x#1!CE)>+B_na?ci<#M)NeKFVbnd>3+7xD!r0sRtM zM5m;ApU?MN$ap(&BCAKKY&VJ?H2nw@7;k6Q>R-^GuLobxzH4AN@Nfa`vA}U)hrWrC zlm$RN7h`CtJ&mLuO>yo=QR{Pao$DEQHLBwb0V+Wb=ehNl``25Fj*b}f*P-c3b*167 zyrQYgwPCZ;cI8#tvb0=zRn3OA{a>tqzj#jnT6a&{`8h`=>fqZNO(N|XM|&(!Fp5?i zbpcd6Y@_)0;rVZ)4lhf1WkN4(;q6)(mzuOtd;;$fK9ZSf?YLSxSQ)Mh^-8r@*N)n& z8tz=i)Muw7Nz9{lHPXU7B!hX>N*B|R8SE>2OhYEQ5_ml$*Ci=s8WQF_`bsa;kaaEt z&QDV3e5B5EX)9yOca%ow(|!){Jl33)ZxOS+8!)_W(yiw*s(iVK`h1|)g+;WU4}2c- z;v!lX0AGOgd#mZ%8QnbcA6PfE-Noso*)O z8cn5a0X~f{FqPJ+Npn-{QzujQn+ioxT2vaG3RTzEy?4^yj8K{cm49NQ_1YV?ORA5l z^NoWVNUN2m$3Z>Xfs?7na;K?4?>jb0uVbO8>uFEs3Tf|H_^Y<9z=#y=7@)dZk+?^Zbk-tis0CW;af~0w?|~iClCY)}iJ}x>q4Z-6SIK#XQU~XW z7;pV+;muynxLVGb#9M|@kA`NnP>%!?jUJ0@|Y;O%l= z`MK*qJhbv$xwu~GA-tFT+enb$-g09-o^s@{*T{jT1tB%)4cA*IPYx+V3ymCD3K0^D zaS{6amhgmn0JAKkq$B_J>6Lu+8_JEf)c75wRa$?IgwOUGz5H6c^#03#S24p{bLGR@ z(6rPTGhlSRQT6g%Eo)k8kQbE>l_4jwzO>MUrADc73hPlRP;P9DTu6cIsf{0+ zmN>7}EhIc;LE|En?UelFz)E|{b|KjrJ+cv+s2mqET}W{5T-Xeqa>s&E8ODnkr!gPA z+nT7Vo@T$bJR@knyh94yoW5_3{A?_!+T z*OaK6Vw031&7k-S1 zyhD3>b0tyVXcV+~5-@xhQtFUUUrap-iDy!hiC#i|5hL2tUP}8#v@b%^8AVIG+9af$ zQS?uyHwn3C6#WZ;FNC5Sn>`sx<`kgT*va%KA&Z}1}D4~galjGlyi z`5d6OPW_MPBhy^KFUM2#eU75{MBwpAV<&Ot6KFpX&hr%7>nP_Tt>`h68=VKg(dsH6 zdN$lfi>wWqyk>yvEa?%RO#sGH~) zJkcn=f!HNgQGObd#>BLdJfC95o~ZqaiOP%a zByjJ5bZkQUTS^*!MK#=3U}(dBTmP0ipcK!)B^4Tx{%;HQ2Y6epcFHjyplIh)^Va6K zu=o(aEyM<>gmfpR1E{6zPD)q}wHMCg>JM}6LM(u@=>IFdh1daS(Z2)uzTzW{EyU_L zi~jEPv>SYsdiUbrsCO?uM*Z)=-HVS?76G*?eVnn~p)|AjpA)fhz6*Fe^+fEJw*$3- zeuAs^0IJV?g0dLf=tQpEi{4`Fs1xb$O?xk9{*%;8DA?6X>DzXhLtVU4>116Vt6^MoC;L)YAv3d*Dg# zta~!>#NtQ%@)_V~icc3mrv5ZsjwrbDOv+c`B3~`Ok~rU2;ekgdPAI=PBXN+k`0dMy z-+Tqm^X1}8i4T1lo_TEIobr)#82uvfZ0cvgOXREal&1sbw9@}`x#A1JFBHE4o}y8m{~QieCYLO)V$>HPXNn zlT4r&`P9UN<;}lBUO0jNDL^F%ce$PnRHi8SIww=~1{buh5hD#m|7(Q@@JVPl2zbzKUzE#{Q**a3$p` zd|j{N*DH{3E&yJ@=;cT}F9aHOayhLlu!vnq>lH{y7XmM&|8iue7Xe>He)GIa=d4+1L}KQUg%?6&ge2^1^uIIlI*sI|MxQ5`pMSd;d%>D-`JYu4_kwD z_jcO)Nmt-!yBVlwZUvsTHv(_wjw@-qk8}-pSVdc_$(yP54Bdh}@n-s3Y;FPSrQ4UX z8rfoh>itrG4KsKW|BP*P&+$uH+481wrMzie*#Xv$g%VB!bCe9nLOo{y_5X}5_4AD7 z`f<>n@mwnn>HyQQF_qG$4)Aj-{ZYWtrL>I5dfKC)6H{r;fxgN8qixjofb)~&Is&RJ<&iGSV;=x61TKKfJwR&_aCbP_AF20%;{Or&XX-uZ zFM><_nbrx=v`Ij{Y9~;p0FP(P6+Z=>m`KmHJ_Q__NdNKhxrxAu^iSlMDd1>3{e$RD z0e9Q!ADejJvGBfj+U^iNh7sjTWs+kOmpmqMN#&JepfA!}DUncab2R+%m_)yZm!C@< z>C;>z9hyQdr5gs6Yu(Mrr{QFJQvQP?S5pp^hPITSPaIDP>1ep%T7LT!lyPmM(L+lm ztD_SgA6nj;xaD2^Do>T(Drp@Jl*5cjykZ3Xqu}LA+@GY}mAJx?@|}qTAIVjZK{}8> z-^MS^BmyKv zB!WG;YZLG<%-0HJk=uYuFDq#62_C$g*011R8-N@58`3zT@{W{Fs5JCTu8~%$4M;0L z22@h|1tY(N_H3f{^Q0L_L;np5sx4llm-ys~wtno07ad z?1MmM)(emTrL1>QUx1W(2NXdYrgUKmJo2!_Db*V8OVW)x+TKtOEuSyo`U~K-BlzWB z%6(Aw_c8i>WY+h=CA5(mE3_9JdIVRFKyrCyzQmww07=o@RgAN0;>)B_XeJCODPP`0PhFB7LM;hk!<^4BtP z+%oawl53=+_wW?A@D$GlewF$yiBC$Sp9^i4i%O}V1NFRzG3oVrK>6*PkVNhQ-otNi zL~{8W@N4wno_Mt}4$p?B%fqGY=R(WB!BuZSO8N%y>symu;I$Afuuhh-uTF-*}sjVA9b0*yA zyIgk}y)%Gk@GV}OWWCoW`R=v+YBb4zG1``-xwgdH+Y(oAOT4-*ap|_iliL#CY)gEz zjsJB+QNV*Q0~(7{z^AVO8f{a+(XRqt#$Qxoz80D9YWiwf*CHKWO}`nL;OZpxUJF!i z7(!`I674lexAv8Bui^iXKu-KV@CUS&D~)xKLLWjs3EXqnh5IiigTGsWTj@^$leYl3 z(69Mow1?=Mard%&nDx|5r>(`?ea!Cp+W_A)CNb}?G{(W*%kCCg2SuDsdlo#+ea!A# zb`P_Dl{vKKbn@!Cz&Y@-0~1e^SI=jS%H8DE?uAinGy-!sihE_oC%&fMs)twZrd7$^ z-10biihI4~bn=ruD2t$rQvKK!zBp-Kiy7Gy{FAQlMOh5qIs@)La(}sd%Z)SL8`|M) zxEp;55{+8$J`}TOs8hrq_T^~~+~MxNcK5Nn^Ie%lZDS>61-Pn2?@oDl$-66lH6!{g zl;0;%R`VPsy^$3Cuj=A@a@u%yb#(nYt-O!AyS^Va`LNZ6tx#P&Y==g*weWSuF*1SD z3>;6b%|Oe6TK(YKcx0`O!TB1TuR+>7aI|+2zXtJZ5WfZvzrstY{9#;~{!yip5lAKa z9h6h_uPE0IO|nY%gpQ-1{TE6#%0bFN$~?+P%0|jUdTSzX%`6&9QDu^ys(<(4l&`9P z*XQvGmE81@4ClR-+>FmLZb#3F(TFX)L3nTU<%E}5sm}~hemSK+qdmsZjySu>&|_?f z5qbqz8ds>dCL;CxUw*&lPS^MCJNUF&!t`mCGl!-*>`u3Dh+r&xk%ncc&TY zl=r2@jx^VHL^v7kG#dTDET4H_TI@&@M1wNyM1Zud)mCz2J^nOndpZ(Gfdu>=B_mJ0&D_m zEfT8rZK0TD#z-gaLEY_3i`Zy2K%Y6HqK(h0W*EwOSB;-m%Qg1P=)Q=%Hd;%KQ-46YW*C~on2}&=*0pH#QG6-m!nD5UtU|`Ek4)do2r(nYBA-xX zZH)+bF?3BKjkiKVtuk_|t10G4_#XDB|v= zED@D24T$VQdQ|&{Ut*U2@1Z=sn3b_C<5z9pXW*B5x)!}wuqfkK+e7#jm?bX|ziRtF ztN0a|rL91WGLA5Ie?}gm9phJEmROc|dF*n#jtR*Fbh)H!XMC{x# zN>@yGZN?sx=D$;i*!^SHEA3#$tj3-oSFF26jIVGF4`qHL>eG0Vppg;3D$Q`ej~YPU z0TWTI?lF<7u4b)8M60`yjW~7hj}fQJE~{CET8~^eE5X8ubk&mN+LC@t%Ux|kSEUiH z#;HUcte9(-X4kB|BKG~r31UBrk@)fbs*xmqzZ|dYTj!`<-`d#Sh}!Layl(I@>4}lU z-N)-5jawN|krHIwNYg7Oxu| zETVSBvd;0kaSqg8j3W&UOKjx-~78p*#Rhq+i1JIs3GU(y_L zEMm6I=O(R@vY4@;FZ@dhF}PTk4|~hMf^$h}a>jyPhks@Hu)Dkk_2fe(L$eozl&Gg$ zDY0|j0weX62jvOI3QN~xXPx;dr5x`2RC0{npWy|O>bvh#USp)9l3~#PpyE>ci1iQ7 zmG^zhzoZb_6+4+MW!uUNtts_pnx@{2r_%7gMF<)kHGQE*_nv{KYw3BSVM z6d5R$39DR23{(ztZ-+8k<~ZV>{tx$m1Rlgbk=Pwl#Az;&kPr3OD8)t|MtPM|q8<}b}qQ6xg#0-^s zU8VD82hsOx~hStQKZway1mGw>->j zA>n_MSE+xQi8FF^idnN*4d(1r?+RH?{YwrO89&v##4_oz`9QX^GQ>33$Gn7D;*@yS zS^pBx#IMZ7I%{FE)5h-*npg0$-soR`=g#~~+zVYyE;g2Tk3FtpojEJa^Xg31)4w8< zqFdLv)zvO6H|BACSl;5g4m%FFkV;y-5gO_D4wp+rbR#trD{L5(7&iYqq zUa==yzLt0G4)i%FMvY1dyXH=I^~Q|HF6P+L94p5)q^{)pk6rq%tHyFCOM#Ud-OrVG zU#p`jM~kD*d#nmqf|97#vVlJbMOrkNYcg_8HkM^lzH6?@{lMQwa!p2-Ni$Av;`)QZ zI&COYGiliNSti$l-R7EH3oi5}*JNatRIccpaWYP2sO6eGoM@q~ME2}B<7AxB;AstJ zoa{c=zIN2Y$CL_zF)`*?WHMxD3$;dugFW00| zu$^;Fntd{|Oh(4Z$SGMb<7DKQJO%zWmQ|?U5Sb;n&o~)bCL`ly=UkIo`6J_Gcey6D zPUb9=k#};(xh5maWMrJ&KG$UAm#k)-j9ioEm#k)-jGU77GEPR8$;ddFvrI)#WioP5Mt;d^#>vPm**VvwyZt)nnvBen zYO^`xq!FQ!ce0vgGV)GtpJg(#Pv$I>k#SPFGUu0kQEHo0vb$W9?g`MwISE-xP4|(W zYf@ic`1C@XjBNTn=bEhAY}8HaZ(MS(TtOg=9)CWWMrJo z`6bPsVw`yFG3uOa(kzpnIb~)_W5b2!ZfPXfq?snoGAZ{sol?s+nX^njm56YyDLKoe zSzF`*rx7KdvrH~a5##2aRO31WDXt9|87FhD$!8F0-8t8!Bav%Td(2rBGfw7QlU=h+ zJ`24rvQJjCOuEzgEF#FwHF+MIq4_1vNSQNEKAZ9Ga!qcZWzy`E#X|74LPr4`T`A}tT8#&jcv^+9S zc9&~X4LN6=G}BM_c_+;{c@bAemdVIInR88QgE4mg#XxfibtY(>fL$d01muu4KfH(2KHv)6U$*#F3%`EwrWb4a$C(St7 zIoG6FCL`nI_E{z)`=og#-^O03YR1WTFp{%OM#jlnu1T{<9>SiZYOYDMPr4)N9qh!( zxh4;xZT88WYf`&o&NykV$;dmIGfqaX$;dlt#!0hFz6Us$+C4aCnKZLxE!X5W+UBk5 zeXhyKFR7?Hk!69yBF8z2}%}l~eBW zTvL7ON>lD)(x>j)Hx^heO$=yZ?dyva1B|0J=F$u$=Ddr)6@SIQSo>S$4*r&ZCI7|P zF%^Hyzmor=Igon#TfXJ!^me|9*_{0QzSod$-^;&}-_CqXy?L*J`dhv6(dwP8d1`z1 z(dwP8d202}>ZetYHimE4@zLt1(mNX`IMjT!;or)h+U|X{dc|s<+VIZ0pFnSIBR*QA zWA!acF^#U%J8P_`r#2{QNjIxLS~DEhGFocS8Ow8<*K#6jYfO5JF^rh!RhfD;#j`@D z&>9I84}Gr@K=D(r^9bHy8nZGz&53W+%JaMWXV4m+q|{+RHBae&3s8@|)W0QB|Doym zhtf9w+_xA)F`Lp{T4pku3)IKlM9Ua$JmGQholI=Ll`k5m06RvQp^!! z9L^TXR=$?8Zks7vkW`F9*hJaP*Vd-9k+O;JznIp+_-Pgc7t>$QO56)*RK$8(2V)Ug zLTfGSaS2fS&RSaQ&`0*6wFamyMeFh!G}mQlL(6G-V!5Z9n{(m-c=ZbGtt)Bm2h=ia zjNpFBvSW1Ne$0c{L=0TS!{rDr9JSMKAj#)WuhOhku7EJ#F$^oHgb5hC^WWF2KRYkTsFk%@ATq-{23xx@&H zyL9DCX3;VZTik4=h&z#)TJ3olGb!$fr!7FAT52;C=-Y^=Lx9p(akCkyJRoj1CERSH zE!K#eB}J?;BBY>{e9@V-wk6!$M%z>7#mz$~+rSv*Gf%A-kLJ*m=7>ijpBbCKDPgGb zd*YFJx{)FtiKiPVVv~4!Fhy)qe_BrwkHph;6tPJ>T}u&<#M6T)Vv~5fhT<88;^~2u zHQuxBq?`zJiz4=6T?t@{GCh>EAHf#Q|ex(cWTRSfl1Mlnx36+c((7E-!CIX#vDNj4lwcr~~0J>6qqwzpjkZ&{&=*seq#sZZUYH`Er3Q~2W zAmS7wcaccdeRDJ6xibACBPgy+zf>E=mFX93rMNQvvcoB@tVF-~Fp3$@rD!b_bL2_s zhEk;G(!n7V>A6&;nIcu!rrbnvWv-)DCfZT}OV*NuA`9;Hz-L^l}t&bD$)??$)U`fv1RV_k+OK^fDtl2lM;&&oJO1( z!Rh%^Mx04QjN>%o%)JN3nMqlcSls7h#F>=DeLngKq$KY1G2+bFO=TE&{1{v2J_Nl3 zMt8fz$A~j`__zGn)%u1vTm5ONj+JAGGm<)foC5m1x|2BiQ|Bmi zzo=g=d@2#IXT*8zU1km_#v~y3*i8if1&; zqSekj%;Fo*rZs_gn9aBEpfx_x;&DLfo0NGhQ2M51I0h(Xo0srI?&HbRVvMxfQyau2 zY4r%87$&W51H%^r7t(K~EoGBR52r}kq|(DEQZ}iyv2;>4*Qe5h?S%dDwb><4bwRz~r@D1f%BX~cfi`C=Zg<@o~nyz~~ z{jG_s%qb$zQ&v%8narrti~CPpIi3~hT1puw)B0&)+&!r?7&V^D(+pip9h70Lf|-oX z1G>UpS90ljX+60IK*}q1SU^U9ByV>vTZ&RY%PJ%`Zu-G%~((x1r_ zw*Xt{n^)P)t7=hZbylJrOIs_0luFK`r(<_xsOEb2Kr{%fvJZ(Ng#GWP?f61%JW0ZfBNDM#lmD+a<+3G-jl6X2$|O8>Bb$n`d@9 zZ#bPdR;qIMmouwGB_6v6aUpGI$@%rX7&)~k)k`&;)A?L8JbnM+X?9v^JHO6OYnq)o zJf*a;q@GK0&6Kp%CY>?4{v^t5-on4B1Tdesa)nGze>+Z?naq{Wui1L1P|Sj)oKTxt z8`vUcYc2M>Q>aFac90=4?Xs)L@P^E(Z ze=tSOdjs`)T58_v;T!pN15`;3d>v(Ps9V9P*`xLbYDwSB$R=o)+W0|~r9h*$w=lk$ zXe;&e6DiB^k84kVGQDN^(Dg3sIX9-u=wMGGS%J4+UBJ^sR^r7!p0+22bP%QZ1YpTs zw*s}al$32iy-Fp2YfJjZhXOr$%ylXB?34K3TJsKPCOkPazP)zEM=?X5oEh_=ZSx3b z?g(N#V@|XaKAP3w%*sT6V)>)y2^-<1oyvgE}Rfl4^DDU*THwAqxYKqZ;kl%s*396g(IEYOoS zXA}F-L3uoIHhoX(?E8B3`Q$@BrO#*Pcc0SdGfSCI>GO$`KBdn$mA@+`C@AiAc4tdL z(FQD+(#|Z0%ACv-TBKyYRsKFl(VCv#&=a%cJ03;t_w_5AtK2vDGMVy*yVA_Lz76OKEYer5 zeeqbMv0h!fv65G&)f_8)MOx)zsk*Q0e|f?IF;>l3><~{*OxUa5ye#34SR^K^Rcq%G zpVhX-HL-4O!fkbNZDV5Qx`gNI>w7266^F%nwfVqpaeNLV>iU8CQUGbQ6k1-}d2gS5 zK+de*Ce@ZR?*Vk*UI~@h2-FW=QZ@tkWK4V&Gq(auMz`=}a^JOl<)J*c+MQ27glCld zuH!2Y1GX@>CSl7Ou4tmI7Q3FcG#ogbE6j~pBsx~|)UAw4*`!vj^!KN=Fi||IRV$;? zz=b?nD}AZrLZH%zxvMuNYPkR?-&@V-Zak@3tEHv$fy%g2SEb*Tz&SvrVrR7jIES?r z+3cOwS?R0KO0zL5&C;wiZ?n>TdY<5Nu366ic^Q9Y3(zlgaavPGcx)wBOVe7r zglk?#3`Z+b9>#@iBdVj7zVRa4fUe3HQ+6k&qm|z-O0(lBRJ#+CauKt1VVWr;R2C8C z;(U4X)E+>oz9*(GCeCFqp6LQwdjVfa{Q~M)DKf@Wy^W*vT<=+6vL|@8Q7#913TYeV zN?$ZSGtW+oKe70{PuYI=O*5A4)noO$fTX;Ld%VeQu}{8RLRIFCBSDu1;^4JPdNiPj(S3h ziJCxk?P0XX(^Hc=3@GPmPZVV)_dO5FbRO|aGgHixXQ_K$`f>a+GjWEQi6_iV6n$o* z=ra>Vm!2I5m2HPIO-!^Zc#AwmJ#He@D=4B;;}OtcY1=d?p_055QK|pYK)KdbO6ZAF zOwV5*2>(PIf5VvxFU7;-p9s%{G%N3(6pI`4PlRVe{nK46T2$3PvwuQ=#lZO|4uB4* z6^56hXaB_Dd}UA4;Cv0@SI_>x-r|>>K6^XWTIVHcpoGIK87VQ8aD4k}tR>L?EZVc7 zJjym|e%iT}mXvbz{4{Ze@{RtVCi+S_1@y6rzA{Y##nf{o4=te5`j4cb1$0{-SAJGN z$F*X})s*R#p_>ygGeRR`GmO-bM>Qwz6nVay6Gt+WY&+v}46Q$tfLaffzM7Gz^b}+% z%f1?7Gm?~2my(rdVA$W7T1|}k|COqmlAPs<9U)mYC27hWx~ut3si_I-wi2jp)Rd&3 zrX&e9C8Q3-yd7F{CU$nbAo}I#QE5l($!QRkzxm@1X>%wzUYJ-A;P~Wlx}Tks8@zzNQk9 zI@)5s>p0qDDSPw9$0n%6J%(bejQQTQ!?-5Q65z_1gQTM@ZOr$4D zCMtGw76jwQJNV6A4^4>{%uOpn>y*^Mm7onu-N^Oe4sq#)>%lWR&2$ngAwR88E=`aU zI4@d*#D2edPdc*m>sMXK3_P9Z^t6>`W~`Z>XPGrKpZ3j>-poAPKQ*=7NqH)N`7nNK zqKK{f8$98siFMS>`tf|OCg$J>pr`jVF$YHiJw2g`Ie0A4(-WGIM~?=28ie0LnSMU& z^`x|FUD2*=SF5Yp_3nCo3SYvt?n-|$U$mLuV=YTXpPW|ullba>eJSRXfSzFCOm*<3 zT-ie@u3Xo&EBc9iwUz`uJ!TlKC-4=A(Uyt|J%2_jD)d|$si^Q+o_qwYV-qbEPqk^f z8fF1qA6r;G(jK|0cK+$m8f9g@n$r@M*#bq;daj4Z9PA}`kPgiNN~@$g(i$aheLhp5 zh-$;T)0+hSR6o|*DZSB}c`zdzpg7W_Jt*zaTD4iF&-O%z#sk$S)-kSKZckRQN=s`J@YhFD|502JP?Vws@JbO&q(nimA zoYHN?q1>#EZ>_CpE5(>9?JQaiJf%v@ixj_&uW9szwg!DlCB5A#daXAy5_Ssh6T9;* zH!z}=ViDi(VA|R$^d)PbkS-gmB{kOSArzaX7>j{YZ+(1ofpUS_l)Zt{{MnSHK9t_2JoXHVdv(_HY)|92^}y4q&*W zKL@(-IN;;xk57EYI6Y~-C$Q^x8wKX}A=B2XTuH06ozdb6j|pUR4tI!m$Vvc9!pNsaZu*&3$NT!&LWjEYQ{)!d9&FCy5@;7POaeohuoe|oG`LPyU*c3<(vtW zBY;OFiWNC9wGc_yq;5*HZ4^)6Q(l#-9R}2I5@(^0VGXrGqm5V_lW6-GTH{!eY6H?% zeTO6XZ36Etm)K0bBZt+HRbM+EnC5lES;o)iva5am~1LTr=*9m0!C8jOI9)_3d6+chSnV zrN8FNUB}uozEVv`zAP;^ZrBwi{Wa&4Yb>(eNOO%h@$B2k6eT@18fAZQ-$+kmRU)gD z6hd4uI>WH(h<{DMHRP#0p%&dR% zT4hZoP4zReGGePE&N^bNBhK19f@ZUdyxEacP^^#G>WH(B*y@P0j@asmvyN=pW-F`Z z8kOHTLmPk_m^XJ!DHR&wW5z$_LnD8T!c|H%BFLO$%93gjY7WYn?h5d1C*|iufYSbm zD_X@>Mi;H1UdjL7LTfqo3hug@)-vkl{IyNA_Mu+Jci%{BDbHhs?*>{+sFx-RsHAVi zyfo2y(?`D;sFolllqRY}90ZgOx(f9EEdr{ANDrleY9|K(<>ba}NgKm|wt(96oc2rW z&U2mSGn3iO;JWWp<6j}`NDGv3f`0|)ikMF4E%UG7T#<3m zdFzRP1?P&4hR#>!U%|N|1ERdloQP_UaxuA=I-@%qs{BhyPTepfm#h4%Gv|^<%g^Lq z$|`1$t;fIQUdmHal`8*|Zw3D{zOQ@!CEp7E)y!-S1po30@*ahFI;FvQUY|Qo8H)_( z?jX(kqI%9t_%63*rrS|D1>SsYQH&qs`OB*sJ0>>5URzfrwZi{%Jg|(z0@#r=9_a_IdS`a_0mJB zqVzGSVsNd{z|7{KPZP;!iAWi>6_~eO4j5XUl3`@^4cZvlPNj!RKvKmx&%j*LYK=h^ zmFYvXbeDkCL&?y&lAgo~B2vZJGpc-;sp3XvNa{2v&7M+Xri$8H%t@P12FX-0v}En5 zWuhQjRmDHop*B_VQi{{Wdx&3BBIWr5X-lDuqjIm$K@{Vr4oXn`lEw+eFKJ)IP8lC1 zen}&ZjFPUn4%?ui(idOe1fCw@uC$Fj<# zf(z(*+Nab}3NoIxCe@T~OkkCT-%T%^@xNNYwT-(Y%l%nFdQ4%R zNyVjiQ(0$Hcd3U~t|hdkk26?nas%n+4Az=lLJ3-Vei?1)th~e+Ea`^vc*buT%_V-V z1WGsNCJHVT({`iI`1LsErodjP_ewv5&}bX|4?^v!`Y41(e(I?Z8u_UoL#WkH|AtWc z=!9eeJOK;fURXoL*C$aPhp$8%rMV0rhXvILr4#8LhpkmBr{0*yCvVIXfLcZMy$H39 zo9#ZwGROf;oi@toB=$S+Eb0s0G`R6&ZBiE*3|Q8 zKbKl)^w{~yer!IevxsQZCSw-Bvw>QUpGVn;csJ?a^C{;7wH%vCN~q2F0_yXy%No&T zCaLqV&T8lV7s~m-7t%A6-}zW-pU3?@8+$p>2)Y;X%lX)Dl`t=&JRd8vw%`}jvu)g+ zCt_cKMfoKO8jp7|J)zNh7gH|8#(Xi*{7^zqsL@-0@QNt*~%}**8U3Gms2hVUPkRH$QJ{(XkSUW1b7Me_grL0)Do_wtitkdJmS@q zmjkb&zJ}H-fLBvrOY1V=HPqM9x;&lAd>N-Q>kGJ^-sPOltiRxulvU}R<|{a-S+4Rb z%2i}_(zozxdRLLb$q2&NP_6~On%)i6*OJNUTJH2(de@TE={oLf9;oZc`Xv8&9d}&? zyq?-TP}h?ON=|hX<@f1y;~W5Gg+VHtM8=TLXM_exc6<8w*ucu&m2#0C9jhiqs;E~ zRo&tN#7m$rJ0}&#Crza$nE3zq9xltq%hKjr!lY-vL0m{J%5$ zA>hZTKMo%n15}RqIIRx@Kg?Y}LH)1ACn+BReuDZgS|0^|l>6Pq*hh*_(fSzhF6#fF z{#bE0wNMMm-TZ|Efghv(H242_@fm92$GP8UD4#4oOZ~~>bCkP)pQZj!>brn@>{t~tD)7`4yzoD{_tz+2NTY;CTMRHz;39=evI~o$vl7;Fq}T zwe?t8;TK58fO8s;0elYMp>Yp=q zFYsP^zu^8qEPhEX{2_P!6}9k3-0xSEpA`R(@>AfisDDlU)8c<9KLh@n`Zv@+1OALV z{)WG?0r+$3-y+#e0#4%I|4S|W1^50PweXkR@AuTgUvbwzP<{>kJ@x&x{s;I6>icQ^ zrg(s|0eF9EYa9F{_x~+W``4dn{V(v3)PJV+JK*oQ)1Mjp-{LQ{{s8A57K%7_yG5Okg@xL>ioIn`~9LXIgFgBuWryd2=n%homOEHmqjwvT{|It8oh)L9A z%E{bq9B@)4J(t#W;PetZ3}e%1>y@16oy&Rt z1)#dleCnCyZrp7)a3=L`<$US|)U(Tlln&qm>fLG00WPFoL~AZkALk-k+km?>wg>l| z2UK&~lRM8Z_oO$kT+H1T0OwOLW^8`B7xe<*0`9jr^}=!qwQwPKT1qWkR32I^r5py_ zo!&mBde}bPe~)q*J>eeQZ#iW#a2fRq>czmt+;s(I?{Xz&32+7VD(WTWYRXdJ((%U{{2+>iS&1MW+`Kdt4!<=kU`#+H=_P_HNtq^txUK)r_6D&T?C z2hmy$TwNYs9K_fv+WL>za<~1;wWV6)TK?9)OzQyP0o>_e#`Z5a zP#;)sq^tpMpx#95AmBmeql!(8t)Z=FdUL5Jy17*Q++1qw-pt=xTW;pBtSh&a`jxgY zzM1xBMz)sfa9iowUdLbCN;w#~fa?w^)#?u6nys|AGQO?UCbWHLyx+cthVxIDB} z&pVXf2HG2VqC>fITX|Ti&UaX;f8sDkH!-rQJc73S84fESjplb4|MyVF59RlKZo+i< z*KyGQiNMEEKc3bkpnE3Nza|0ID4$4~0(=7X@wBD_pGbWI8e9ofqdb990FS5lB=BlF zaC*|e)Vx9q>#TpNd4(1hnwK$gPeA)o^9n7@2u|bePN2@ZSmP^)L6(gcf!VcOQaA)L9E_Mk5k)&!wn; zsdi-pehd~j?w?b-Z=p7bwuuBsN6 z^)Ia=YGFfxRsBo+y@=9R{Yy(rO$%#zNdFRZF9o~i0_XHu|I&tYC8ZU334bwbWa?s9 z@mF?6|5Eb`Ev%-0wLYYO&EvkWf-cNMBkGI(rL8G+F14^$+G=4pL0{$r=T|hZ(86|3 z|I&)3{?+!7{v`zq&FdCgH|@0krA_Qs$|zvyVsGYeW&KO4_)d!YS55N@U93C(OU)~^ zuT3CJk zOM9SN*l1u?|B}vsJX!KSPHRW{mpWJ0ztqJ-^9n7jv;L*M@oxUkn1}SQJ$I;osd;2j^9n8O3*2!WdQoU$chd_k?2GW5J<*8vY(W1~^9n62>tAYKp@n^oyN^dBx`&ah zi+zEyuP0mP*RjX#MSJmf`j?v5H_?^8gg&&r{-x#>TG)4}L+2Wgc2w2E#v|)~kNfwJ z{`Fn%b{}OcQ28@!VOm~)h(&G*aBu!z=wG3Wh5i+~SbZ%_{VQ~_ta;tX{j>hHG-+P_ zrGNdLJO75V4NXYf@NX%N>R)PJp@oIcRn@}OzqUQ3e<|z!k^8HEX>|_GE3~kzd4(1h z`j?tlXkk0jzYcv!|5C~=N^RIhxs1QjS^rY=3N5TL{VQu;hZQYJzHLeJXV$`q0Y@*= zMn0_6MxM1W^{>#yy3@kczd{%5P77;60?qo@O70t)S7>3K^)GdDE z%boW@N76IaKl;~E59wd}XtMrw0Doz1sn0FzUus^Vg;h1L(8YG7e;xgh{-xh1^sLRL z9=y%mU(HKD9^=^OwgA<<^x$RvtEzLY#}0-T#&4mKh0cY3h5hP~ay`GHUtwj+`q#k~ z{c8iGXi(UTvi_wmhR&6AD?NUPVISE9%v#tnw9PScSa~eAn$W*Ig)}-k?js831dLzD9->M!w?Q*k#dhpg! z&j#ut*SgpN)QhJ*a}KZrs2z1KP%oa=+Ic{IciM;N1NDt-+1?H4?hh^MMz!fDH-ckf z;@5gDje}J-*qvhDBV~_86r;(NdG?@~dqBrNqS)GZZQ}?nN;}q0;Hzl!znJ zL$0^n+=Rw+7{##in$5Z0asBx z16O_1otLZ7jMZ(;6}6hT)ZXZu8!@R>P_MXgec5O3S)ZO88?i!0PaeqJ8g;3k-0!MI zF8uDE$lTaj=hahU!=vw9>P0v1QXkS-=Cd}>da&|YvEf%Y^73HbUVnjJv@xt0<1y6? zJD(Lhhq3A@=f=<&bD$<>l%^}NdRDBFnnrBuk&ozwh+U|j30v^ne7>V`ojD&$*Hg~T zUAHH*Wh|SKwC)~=xC`SinpsH;fks^Gb6vn(n%S;})e|w=o^>9l#KwuS#=GroJhom- zV{dZghA~0ipT!)}<@yIB!?)3UM%~0}G;+fTo33Xu?mOnqgVL zgV9nwpT*plcx>Z0q#$v6R_A!Oh{!Z*to~WdTUbjGxnb_z*tOs~GFmMnH{3-N`y14e z#hl3r%Oc)H>=D-@YFRAvL}oEC;*zENQ}_nPt4Q~aJ<$f0&pJ0!BF;CLA52TwtdwCi zg6?47Jp1Wx_1+$;cIP$z3_(oV=myS?5wx`GnCC(loKmcw;dyqMfB~ zMsq92c0TJ|`B{3m4`0N17jbD5>qT8a+P4&pG0SK~L`U?vbkOKEwI1yPdxKe?fi9NK z1HZHhh-L0TG1f!+=nB?07@10?lC{&%-G?h?8P}u*Qe2A@&m(`NQEvIfb7P!pC!Y6L z9*vQSDw>yFT+v$*dD&ZO>%n#fHjNS&Y?Gi;$9?IT{Fczm(r@7k=<37 zzt}uR-MO(F&~H*d?@452SNGpcF_W}<`lj@SbM_N8-;EUWo;V9R`-!t=j`j_#q`hgG zk=^W4&bYDWk)7Q*bJvDh;OggP?`>X&`us}|V0WBLz9#>gnD8g?Yt2LaODdGPm^%Z+ zDC72=FCzxV^F}l1SNT`)tl(dAE>F1DzieDs$SLl4tMRXhYzzJsyiEQzI?c5FOZg`v z;o`g*XT8S1B4*B5mn#1f%eJu6BG%4$n~1TiaWP}CjV6kiynNz$m5aGXB8o3!_%gSW zPZ@P&=EsQktMRqqS@JLUq>FRz*%qJVRz?cSd5j*6NJ97SmQYHi5$R>gQ!Aw?9X9a} zN-w^NnH)CL-bfh=RNB$MI3#_Y7ND|_e$!!mW3k^aJ&f6jJYZ6YwUjpCI_iUHjY#v^ z233^~tw~f$`DFw&cMV_s0Lo~f6i;eB3aWen?focY(^?wC%8{DpcwWy1Q1X$=N`aNF z+W)>zR??ctYFI_RBGGx*#>BJ|CP6pl3(F`|fXnF_Z#0E@(+A<~P62zQ{5g_sDLrR* zI!>{6<8Lh zEp^4RF|3J*#MBc}l@I;GU9oH*Mm8n<@|%z1TNqs{mm0;lmXlSnOfEGtQCsCh*Qs1= zK5NUF$x>p(!ETRhwfI}Htd;d%lLj+p#l8on#)!7fQlj!<6~AhjrIZ-B<~)~wr}V}o zD(|ZUDCesOs2eE%s~@N{s22>Sr7oeqAf~EOXhHJt3+3-dj0vUQAs0rpxqK|%S{=r3 zApKFdQKM1A*%K(I7)7lvqz0r`q>iL!q_(8)q{gHcrA{Tkc8+%kqar?3JxjX00BH26 zYfETUsVhuqw5cmnsC=PTBUJX7LfM$svHGP_jL`||n94Y=TJ_8I&r)FK5#>W8#5n{RoxvTscB*5z=9yb`LqUF!rzc)b+WTvCCQW z>Rz@g~@~LN@i;|#jd_#~kJD?!S#` zb;!Abult2uHF7Rt)^U{-VwHt7q0|vE=JKzQL}I6+`*mU^xQ8+8?9$!PFw`!j)nbO) zN9F^|5E4bs)cpdzvM}^UB-U((88*EnNphjf1H8->Hz#Q|=OC{CY@MHKD$nAxwx;Ll{DeN0&lykXvsItU z=keLvfj+TM*x0j~x2NQrHBtNAKD}qyjpH7^l^Epvd4|AHTE4%3$rJiK*~sVcJH-h{ zek1o^$nAYz?YDA!zpVCK@!Bu0{Z`zc$_#lPnX}~VnSI?uAJ$60nY$BftJTA8jkOW7tIjxTGEY8YJYMiCUQ{*N!&eD6H zQXgmgA{$isZ>9X^vET!C_grKAq(t^A$a}8yNEGzup>=2QvSy zY9Ect_EmYHvm}u9jz;G9k%`NVeA}u{mt~vnHM{P0y6U%mWYFz;b6ut9{f9fsgf;Cr zq{OcBVb8p#|DGr7={u5FtIyL}%F6O;f8c_&uEyPhqiI=CA65q65nl_ACdJcw5gbkW z64|Md99=bGEZpX>#}ct~dA_R;(x*MIAKvDnEB_@4C4Be|1j#lRp3B=wX&;>iZpbwfWtZ>2nolJJafaR{WI?Ys(KWLs)$q zm7lw}RrUu>?oVG*bsnqjU0Emk$I+9X<*S{Y-@e#&^%B-RhT$cYu66YvRq?kvzdQTP zRr^(cuF3wJ-;B96n@0Etv%jV)=~eZ$M-IQJ&SQ0ctG15*nBTtGCwF!KQD^^xen6kN z>KUxY8+5e^^p;2TY%i_OU3E^YbKM&`A!~45{R>q+F5(c><~rM9s(M^RBV=t(&qDWh zn1RIKs%Er(oJo~FKQeT*>YUb_>;AysM+$v@c;;6-fLd$S%Wu?B<`-T4`;FN5x|jDF znP1PA^sIa3uTgkZjNS>aw!T77nG~b+6^@~JI+B)|u{>`Ja44hWXzN=PqsJ#-;dokl z7+dM9%e4Yq>F;{_j(jLTj1<@`KdW$Zk^JBpF$J|>}&`F*%>Sy@}^ z)th*{T@RP5GU2Xk52@No9y#;-kN=*J6nj^7es?wcysP2tz(0?CHt%c5@_hZcrs~|) zvuizEIGd?)SG{;g^3@>!?fYC;*Fb;ZZ(nq!uCXY)8omtVdfR?aT*l>^^}J{Ggs%XN}sFao#ljj&)kSDy|=c( z?w`4D&(r_kus8hc9~nzo&o142`;4+{-VeUL&R*5*wx>C+f$ri|vt_2Lx$6O`>L9&c zd;LGx{lUNbLf^Xbug-J&$cT&X+j`rvO{1^ttv}|so_wN@rnb|+w#R=*_Ma+E?%eK6 zteqIzbw~4#>@dCKDSeZv8o}8tw^UlwPt1qTH zr=4;6pLKq#+`+l_%XXDv>dkNW@<4y!Y?UT!pYLuDbu|_`aCStp?`3PP>)u$q&ht1( zllw}O`vZTa$veB(tct%~_fQYaTyIaGGgS;K-8X#sXXn3FTvl7kyXGUdEg~hVxSX+A zJ5X2su{yuic2yVd+xHw;`MGbrc-N=Z_2#$Hy-3wLt+uQ4+kfA%p8i{p-*q2L)|gII z^}B6PPuf#FOmF#b_s{ci(dV6!uc~ueZTD?{d;2{fPWie2arTiuzm3u79OqWcEY~^j z(~j~^h)3PUl8M(j(_LTe8&zD+{Gu8Uvm@QDN?Vklcbtc+KV<28`frv0R_Sw9|J@l` zdVGqT9iQax2`T>42u*Y87&mK-rhAr+n>B({c|a?iaS$y)qdtxPR3G=rjSSUmuNGiz zsC$-`8H^k?)?LZL{PLce;*%R`I-S^4r9>l8XQcR4qg0LDFg|rA(W_%<8Q*G*?il*U z;d<8z)Wdn!2|%NCjn*}0*BD--ddC5c>NUF87++(4hj7o)Kyz3c3#=AAik7j$MhqJ} z9FfEYBTZb_zk8*(kIAXG{(b%(=XFaa;jH1$F>AZ^J#>_h3+A*DbSAZB^ixG8|xJEKw`;M+2zqa$`s`8sVU#>Ra z#5oer#{sotn%m7$pHs{-X4|LsDp!K<&^aHJtJHf%R;cdtK~;5`h$Rcm3Y>CPbpaU{ zbAL&fTxXGKp_cor(RgoXc?49zS#NBvvpv6x9pZ)a+Zj8wi--~3&vozcBIL2icUZ;c z>KgDpV*QQ+YsFtNT3pW0T#YN+5s&uSx@H6wm-G6p#xT^@r!+RCUa_}#xLlpzM*Kb* zi@WZy_76m*Ggu}8d3r!Hf1+?tCF02S9wLL zMV>29liLQLRm#eGfl`*zqI!Yym3&gYK+3Fisa_zL$~$3|Ky##i#OLpvT)HdFb-m}$ zytpb|??|q$$6qons!5E}?i#JGN!QBGRavnox!M`8N!Pv0vs#t4>iPIWE|J1Xv6V_1 zkyWa+I@@YO$_kFwm6zr3(^Xcf(&{Xwg!T~}t+Om$rPYJDyer{ymRqV4^^SDR?q#hi z|E073zdQ^2X&>}p%G{5-96pT z6kC1CoRWR}R?cb7k`NfJUcBRP4^X00p)LZ(~h%DVb{ppE5 z_cjl9)$UPGSE~95`c9v#>wjS9v^tN~cHh>a{H1mpOZPVFhaYEmO<7C4$Tq;Ltn%>D z=h&N_&*JHe4YT_E^=viS?oqSLNxQpRFS9P+6E62w)~big(rRgVWB{(^F?b~5a+T-q z%DCLqoDR}wy(nRytj=R~ejBr|*3;$d(VYIl+5V8P28veqjjs*zVsUq8@wd0O=>Db2 z@+Rqf)nciB(a4-;p4GjrK2Bz<*>da2%vJpD+dAxj`D$n9v=RGr_zJUSqkfM4s{MIj z=-WWcR5iNY`}uWFyLuTKwaH`+uI4}Lx+Z%wzm52U)iU$hKzU}>bnD@4wpRIFc5I98 zi+yik=eIHYRXv@zw>n*w=2UHN-P<&JGrx`akLt@T)qJb8ZlG+Ey`Ag+k{S9JfB&)cxskZ0hi`tX`caPKQg_lLXVlvq zYV$YF0nVX6DrIyW#Yi=m<7{lNvlC~ET#n{-Y@-s*)rkC%pT9N+zi@x~ z7o1tW3N^oQy%>pskX!OB*OyEGukz)-%&#`dn)g3uHv5n2<3%HMyPjRB5xF|^xcYwc zM&`P)=g(`kYusSH=NG%XixHLH=6KqkpMOxs&e5~o>mZHHZ+*G35xU*T{AOQg@8ddp zqT7wc^E86j*&}Q`kC8mJsGj=qJbmNQRqmE?xvO9JpI@JPxbU~04Wz3tsXi_=LaVoz zVIoF4&u^9D^**knYU`-lEvw_b_xtB(Zd7jU-J0wV{M|ME4*ie6)p;D8-@eCN_KiM^ zvpvP_^bQy5@#5;d_x_n(hr5Q2x@yC$`jy0Azh&1wEL9&w(C6w-z^<9x)S7lCuChws z{xLYatIcUoG`SI7xJr|?VALX|^(94&v~yaEuIxV6ZhKw0UX1as%YUnQJuvcv>$WFd zNm`Wm9;!Fhb{#evx6|7gk9z*5sz0I{gV)vHR39(YDLU`!iv2$IXr1~+_q%=~Qo0&L zUOxu4I*$Xxf2;Io`)BsN@Y;^-+D@EovFXk(x3ltdl|E<6Y;<5FbGoBFX!Ykb+XuAS zI=^aM1HVV9I;T~;bhTYyX0Epmt30Ip;gsSLt*3f~C@Zm#ON1t9tWW4`;JZ zq|Pht>KqXrxo5NeXJ>FW?+SN6ygP0lnX#1hXmUOLt>+_dT>tH@E&Ab`-zv^l+XGK? zdWXL~(d2=SkL}85d%ylOeXeFj&^{pD>uHaF)qdNvOj4!Koq28ze|tZ_jjYLRlMD%= z#%+71IX%hGeX&U@IoGIk_j?ShzJ`#WJp(BA7&i8;oX4(QcxUWCSu*LpFR5?%JFxTH z6aLnt$&JL_?Mz%&V{@8uwyR9FbMi@^+3sY{fx+3TOy&IUdV5tG@gwYv&ihEA&sChQ zw)?g|>&^Af%Y^-nzx8CQM)llB`uz6(`PBuw%csOblmE(|QKuHtO9-M441hrd<%s(12pf5=z$^xsD0t7;C19Hoqq^;f5T_Ab9v9Y z(&T~RU)g?Dwaiy_$yyZCj^YwyPhs`|inU7D#*;oW;ws0(lZ}xrQY@=0)JR$5Cw&Ja zX!ZJO@i4O1{VB%88gXlW2Dz}>u4k?rrK{9X%eoo)Hl^4`^cshwbZw-s`8Kse8v$&- zO=sN5VDoLN5qm1USvSqX>51{PkRHsy=^65~xtI4b-nNauChau>S1geB8kuX%up7u7_HrbS*}@>))-?!~XcY^hA;2N@7t`JoC>HF+nri{J(BGTc90nXle@R-YOBmU^SW0^d z(AB$7TL1gdURo^UtB(MVV01Yva3s+6zns>xVg>Ex#mcn)SJGZltYRgP0ghpGHD7ux za4h|OS^49D6R7v4wYu1k_P)jb;Ozw91o{Vnx9z}o`Uirs6M+-yuK|N60VmNv2t1w) zoJ@Z$csm6+h5kD5b}Dcx{q^AOG~hJ)2ZOiMfz#=40AptWXHjpUb#So}jGYCXMSm0R zjm2i*CSV8k7T{*!9O^B_TuyhXA)0y8#aY&Zi!nufh2m#IJ$FuYVLBemMWG zd@kpLcsT#=uE1xj`?&`4-9tXhoLAXKKI@k^zqjqa?Zc`kV|4wyN_N>3)gOPiDr3my zYrDW==U0~HvPKY+W#8Yo(ZAa_{-`7qQcXxQA=QK=lc}y>SgA&NMoA{5nw^zrlw@jB zO--IrlBr2GA<2wKeo?Z?@{E#9O{#hLocXj#D;?>;M;x{Hu zepAxnd(ZC%N`D`mufh4!GB$``17jZ>#IHg88pN-xsrA48c@Vz_@oNyj2JtJ~ul}#g z^Mn4=LI3HXzkA^5;UInu;@2R44dT~e{Lf&#)?mEWV0_(Rd|lSO9@+7bcNFg-cZ~Kd~NYM;Elyiz}FSuEZ$bUz4!*T@a@Grif=LUP2gLp zzs}e@fbS@7ExujcQoIHD7Jm6Q$G2ZwywDu@IO}!^@58&O@i-E=){|EJ6z{S8%QSS}ZUwIex65!sz zPf{-h8gKjw>V1Gqi)RqUyS8{bWgYMt)XyZw_aNXw^iF4NU2z5@&jcPoB=8xOHO15T zWgT!Gp25?oh3oMYo<`YFoXM4E6sOWEfTvL(Mx4(6!2S8p zfR6&MrhYW=2;eH}BY}?wuE1k@BxP0c7}`e`j|DykxSaYZqN0}rm(xF*H(Lf=M*phf zq~a;XmDEouuBLqz@I>k>ij#{|fLAhp1?A-88pf{%KB;&z@X7Qp=a*B8%P3C;K9x7Q zjImRSYq{o{;#t6JfyWmo08gOz3VuJeIE#^I6=ws_0zRR5BJhdy&Y^vFaW3#2;Bm#{ zfsd#6Y})4*=K-G$d>r+2fad{^rG75(Il!ZfV}QrdJD>J*iFY@jUP`?i zWj+z>FQK=9vKw(kFQ&JUvVhq1i|7rZEF_-mMf8SJh7g;6A-xvLP`us$LT?zQg?O$P z(i=`0Mm*OA^jayyi$CKRo>BY-Z}D{Cbozgy%qad!1o$-IG)Di(*bJcA-Ty|E_*CFj zetVGi-+=BU{Vwpq;(NrFPXF3%qnM>_ZD+X_m#}y*N$>#Ig62*l>3Ug zjL#`&l=l@sEM}BHEPe!>NpD{1-jjL!I=3uJ_ns7t%qypJ?T?C*5kToalxg&T4E%BN z6X0}uO{IHMn)tOWrTvK$2*RgMOZF2?}Jlw*No%W=SQ<#^!uasqHd*0rJmB++=L4T#ya4zDR$WVZ0XraCxaMfCx`0@V5&W-x=v}~i zY;)eAFtdvepl1&hl)1pU;6_1t1@IN%r0ti}npa#(J+HWgdLEc_2^{hcp6C74O>oC1 zdhbcCI~i+&OWp~*o$?;Iqpj;0Yl0&-(Ql^b>2cRn-d-YB1xU%oBzN;#oiR4)0A#1Y?-c;eR+|C4XNC2_^K zChjR;l}pMA<*4`YJhvq-`8D8eaLcbUa!=xw@<#dUR~Y#!Tv0A6$COLTKjoG3$D0#Z zd_&@xa#6XY98xa&QRq)RQ|X*al|hrjwvUUqskxUlJd@tJm*&umy|2YT{keYF>y(Gqg+%jDTkDQ?m_*T z#4$e&ZtNUMlxIF!9HyCH^R{+yI|EGx5?h`RxGK=mthl z<-O#U@=v+s{_sY5=HZn6;EnQ3Ip)6bMtPT{@{kocp#@d=4n%0Hh? z?>Km)JX2nIEbut$=TILDSCnVUCFPLEQlC$KbmEm4Cw!luxTL&M&MB9aH_AWdlJZ9R zr(9CrDF2j8${XdMa!Glk{8KI|Z)~BKOUfJNpK?iQll)V@7+g}WDCd+v$_eG4^2k3Y zF8Qa#)n+6vDTkDoK1e+!aZGumJo9^rXUZ!lC0;3Slz+-4<&bjD?^Aoqi7{GbibF1G z{gL+X;DjYy@^`>LP?vDYKL8(~F1g|Xcx1^nzXARh9$C`*HSmAnktMBP0skNTp`;~G zln4HRzbBWJSIRl%h(h_OTvDzmFO^HqN*wWCIH6orE_omDM~P$J#}#r(d853vpclMy zY%v|4_#>b^RsJ|V@xmV$a!+}qd{r(fZyIkc3E$|Wbm5q}Q%lrR1q&f_k;7JeUD$Rj7g$9_ReF8Tk7dkeTLi*<4PnWnp? zyBk5eySux)ySt=2Bt;Mq0Wm;nL68;+0qF*5Y51;LOU~YI_daKz|L;5J=x?t3o_n4b z)>^sjwyGk(StydpeYvVd9A!HCS50kdR87?~Lpr-2zWV3v#mqcLL!%#zVy3}#FW zTV_mLTV_noqhZDj__bp5>q`FglELKsFPYU+z?A$i`ForSPT+sZzbZe+`5A3|Xhs{y zjOJ&zF?{z8_%6Hy?&SY~`PR?5ekS#Et)FrGhi2RXp&55zXvQ5BnsNOM>)&JgnKu%- ze>d%C-iV<)$uB~4We~cP+{oQ!a)gQB@zq|b8Pjls8 z=SP1>`EK_7^IRGH!(8d_DBsPJ{vPu9AM;~)uJm_qKmE7n%8z)S;ThAn!7@UdD_j4^Tp6Ap!*iv7|Jvq{+4G;xnD6FF zKV$mYvuEfo)8ALVn>YVoXH5U@*xzG@?<@cLjOpjf@Vxow8Pm^|;d%34&zOF$49}bY z-5Jy0OTL>W{XOQp+4Dc2G5pGp0lfVGj%z~qo6ERQlcBjs^7#B6 zoS&Ker?>vDD+tXYLFj%f2+bk>lih91L;<7Uz|Gvt`OiT8r@LPVy`7&E`#67x*vIuI z_HzF2vKRHj>y+nSQ zf3J%I|F72H1z&*v-EP2L@CDl9&^xOO%-jK4b+?nd+Um}K=cw)u^G>`vkFJKR?);r& z6Ik6fasH07F>K-*JAbFy2sU<&oWBEY2phSE&fl3ffDK&(=kHkS!v?Ot+sFND3Ek0k zaK&{e*AX^#onS{-LYLGfbO%?AN^xCG*K|!?Df;bUNn&Z;-nE0Jh-Gv;*A|v0E^@71 zE4P@~%6;V8(EEtC$StAP3bt}B-9oNy3)?WZkgse5%jzniFBy0Wh2YP!li zi(Jv)s=J|Ds^EUSKHOmbsbUHb9EuPu0>uO z)_3(>O;}6U)cbg4YrvYihW4KuRM$W9xj}XE8oHW3z~>3os8rWgwSUJ|l}a^TMf=Y& zs!*w_bL#E9N6V=L{s!cvUPX`RnaLoRF3KazK|QA);BxC+Fc+1vv3)toW|{5|HMCRQWH_0AV>`)x z=o;Hb#0GY%n*x*SB)Wl3qNkEi;kqXFLpRYi;o1*feVa@t)%Cfifvsng>twnfmHM`+ zo#-aGrd&JG)wL;fa$T3vdbXCG;KsXJc08|AEv}m2>e!Szg|5Rjb!}=r$c=NUc^2_? zcJkD4up8uR+f+KGuFaKoY&I&{bv8Z34R%@eP&Wh)aoKc!8&9W#skknS9_EI+ER1H= zne}it%w?vMMQ0+<3`e-(E~Cy*%t*_mGwK5LGQf;FJ2-CnI$N_WEE61~x!3R8^{PqJINypP=Y-Ak?M$#YH(l&~YtV>fVV@uhnI*Kku zrL-++qv@!+B$ZOOgpIDF=@L{*+Tu2bj;@PSDPfC|7q<^pOluRfH971)I}8Rllp8jOMaA>@)RL<)D(&=3~49tYFLA?Dn~Orm{1d!)CGN zcule}Ql7j#y=?Y{dakl@O?LZ=M}A+uQUz@R>vTc-P8YHTZC3kIy--=XGMlwjoVL2K zEo5Wcd+Mc%&1hC@bP-z^7Ul{~ZeUSc#44z@(#331E1}X-#~=zFlPGj7q9Btx(6Q+S zG@;+B*ko^19BOaK->TQ-Z(v*UhMKN3 z+e~&EoUUi+Og5vPp{En4>f|;v%*@zKozZ5nGa1ilXX*4d9n4_U!vIxJ)nAx71CwRNq#&)DpNq8zqz~u`^bXJt>L1Au zz=_2D@JIL|aUa|dClP;u``~2aUOk++m-d5RO}^p}i& zWxg~Q^`-R9b89c25qL9Lv=NrO`Oi?3>bqr4NiwKiF3`TW))mb zoXfSV%~a~sU@YQP6Pq}RD`YT<@l|FDm8mceF)q&{qDf&E5>wFPn#t6snB-Jaz>kQ@ z%pzhkT5{9fL}0u-ZL JsDg~Ok$Q0lhBfy#NGC#3xSxFX;0+9*l3|nV<9p{Zju#e;Ch(yHp-Ychk+h z(hIz#0)lX^lLrHywz{u8>$0MKyM&zkQqQe5DH>{H~>oG59&iR5l%Gw z)P6X@>{t7Ud#V4R_Nt-gL-V7WV8+A!!~<%)83%tP9#rGZSa^Wg$&5CmOh+?@*pb%B zbYN@@JgCOPF;qL4L+YUF%-AT?nKsh2r_uo)R)_rjj0hdHi#n4#vp>ScPup7dLD zO&inN{G^VlU#Xvmy-hDufl6z*NByMEQTY}2F}=-Mcut*FeN7*82A)-CR6o<#`~uIY zUzFt4{6+OQ{mg0dU({)(cy&*~)9RGcMv)t%%}IDlolw>ob3!>|p`rS-dZC^9naT(xW3^nBV6>zu zOSL{MLo9AqsE<`~MoXA-)at|frk*KgK2a-FF-D7ct zm2jmhYCcsJOT*Y;pRAo~MR$}Z6@=dUcsccelO<}W9 zRW(&$74wDKK)w-HGgZxcxIwMwRjg({hwIhnYCCZq{9LV5JBaJlPU2^9omvY&gS&`p z;99twxEij3-xH_6)$l7~4xSl5ALB8kGAYeewNPa<)6`TrT}^{iRZ5eUJe$d4W~k{Z z3wc(P+00ZkRAw_v&4e?kW+KmQGMd?HmdZ$;$@EnPO##yf_EmjUc2m&wQ+-tdSis~r zy{Yt3{Z&7e-}I+_Uht7WIam!+AIV%Mr};?cHo4$J;vDL840GO+H7? zmP6GLHG_T*Gea&S&X75HWoA*IEoaGLYN#5a(wNj{gi39)!|XhVNmNFtnT*boGv#nK zOns=*nl$D^>XTGIDl=t2*-H&q6ID8s)=XsdLp4FAH|fj-mBFNk>8Ot9HOpYeQ<Woa4HPjS2 z8CECORFmZ-Sc6zg)l`#Y5BeXP9Sz=v>U9WYO6lf#>tMfv9J%Z3-zwBuBxLt!!EM3tf%U#25NxpFB_=-ats{9 zqi?MS$^o)9^#-aF*L0ShWPMdnwNiuRK-r4X)~XtnPO_S;r0T1dYOow6TQb^8wIFW^ zhseRQxf&{mz#+1QYDV514wFM=Gu4II6gE>$RaatD)s5H$HdT#b6WE>D2sVa2hz(&Q z*ppZkHiT`6Rb_Ei3>H(BU?m<|BPvy8Ls>!&eopl&UMssM4@B)eNe=Y$wyJ4zfLLPd}Y%EIY__RMM-As-0{rGpY>4OscJH12Ymc zt2VMV%tXwhTFX{2GqHkfDO<>j#1^tV)t0a&z4DB=l9i}7hZTwCWLA|$m7`u>R+i0V zQ`nqXnepbbtjwmesDPFA7TRF;w1RW?tr%a}jsvIz<%nozF5MzLoFG;;=YBz7eXJEXs1pfcS>`TbPk3RZ&?4 z3Zha)WML?YS}9c+7M6u%YMDwFgau^*nUY!|SddyuX_QtexuT#`D9-B0Wlf%GADlxUZGAVg77*Rz~kyS<>aeS4D zM;)I$vPwcdsZ1gxsfa3`$}BU7rrfH7f8Vssb-rXogz(P3(0R2U7WAx42wVFKcP znSdqAfu8;gO7+&U{v^+7+F3cMy5rPk;o&%--!|BQ({C~BpHD` zqC6$vlZoVMT0(e=_zN+iJSn3ya*}pRo}r%r{z5!U79XA=o+FC~&k|pXxH1lmC*#Uj z;-!cqUy#2PFT^>nc}+hyd_{aNe&uVPi}UhVc#iAdh}bfgd?Q{HpHY7<-ilZo_EA; z@e`Hfa1*0HarIqsf|1+swzwsZQU3{kDL2WJ)NYBBw4356m1FQL`K3HX?WQaR^xmYSc zlUw2EVyjptm&)(pR`H!!E|`37O_HpEH}d~Vzc-}u8`lr&Egxe zQhp-8hTn+p_D8W_bhF#UkMKwOJ?wt5PxP?eiCygmu?=oxtf$>4eh@tw-zR$6AH-hR zli1tt6?7RG*AQ3n6?@Z{z%RsDJC4!iVw~t=2inp0OR-6eW^{}l zMLrsSCB76R?bqTfxRO_JB$ZKi1o=p~O0JZ{;Rrk2ekxbVVQ{z|W>?EkZBwL|P$xke6#L+oI?Sgw`L;b1#fw6I-Z7aq+_(bBfCGpURfGej%f(#{aAZ7bN4 z>U8oMVwz}UTia=(t!)Ea+v#E|`7|*_w6ksP6!NKJzFjJoz*%A`Tp||OdF1o$Lh{98 zpc0^TaSJ z!{HLU*p3!+#T+r3>RdRAIF$M@xYRDOW2ns$L&%51Wp=3@NPo5%D8>*6QyBu6+hulz z9WQ2y6+H5JCt?AevDb1n1h1?K&!-!w$Qe_tzAPlS**70sja51v7g!w^ggv6iJy|KwyVfLwJU8W z;!4^o`-$yL?-SZeJHa-iH-YwvooMIUW}>N>7~+TYJBbf%Q_)FGvLD)xu#@O0CfiB2 z1MDa|h$(imZ4Wz$_F}4?V%x#?qMev#r`oo#ooFkj+i7-}?JxR?opyle5BrN-8?#E*8r ztwX)8s7b9W>?*p5+Twuy(bi_PjyPnSi_Wk!kNX$$L$HNtE^3K`_JFO$m9@ob+fuZE zEyOSO6!~e`O0*Ooi0$^E{eUZLiIcXqXa!q|Q}zV;N!UiT7C*xi_GezjHsUz^*&equ z>~uJt-cRJm?J@WhoJl+ikHJ~QBk(AkO*~@f5D&v6b|X9t#}o7M7(NjB#20qEEe-RD z(qfbS!j=+W+D&j1)so^X`=u>OrIaWkzP4Z45>!fx;^G_owJlDigeWF9+iz?!D#b-n z@?zq)EhB1(JGQ#025X4w@HX)l_1pHYy<@A1-)L3gUE)1kMO21WMHToP@xHxhD~sHs zqNo5X5p#=N#GG8`d7sgo;(@(ybJEWx@-SXO_eMPJhqSEL&h>wEerD!vr^9{ezyfgewbgBfn|8~(iI@fBA(dC@UhJ* zgexctzyd=xon_zHeYd||&MzM#Fd&&glFt;A<`8}S+KxqWIk(0fXIX3vs8wK2pwdlTN| zaU>PL+H*E3l^Cp|KW~4vNvI^nBD-ME+r(6ougB*VNy5tHC93l3GgE<);)W z#49Qx7s4fU+`3RvwB!O)!X0Mg#bTB@v z|I@&=aqKiNt$whRmiS!vH6Ommcm)|{MJ!*b;gB7az-Q%Eu`+z*ZD@gt*DCi0h3%N(E zSS>{DQBc@D#PTTY3K5IA!tMclfblU%-^2A7tOx1ef`R%z_QyafgY-aM#N7{uP`wKW z69?#`u812zeV`tyhv>V(Q0>i#p=5W0{<@ee>iTod06mQH+d)5F+!b^EbO~1+7Gtb8 z)muSt#%~9GsrS>R+)ccUQathxTs3D{g<6eDDc6V5zPgVt=}M62b0u9>Myo-KpHT%? zbyb|hacID3A6?l+z{sdfrHZRWUKx5jqav*2Dmw3IRB*g*FcQ@YE(*Q!umX%qECusLK~E2Q=TVp5(n?ZkNmT2=chxFt_W8_w~NZ5eUym+ZZe+mZ;^ zWh@5OSo#S==1W21gh~^Z9frCq#u_& zUJwVyg(HcvVVocq^ymHc*0*31eg(zr-C3)k37^1Xd5UFxyws7;V-?j-)RS_RH&VT) z+=;*0imw?(o}8KrYVr<51u5vMASID?%Q7)vn~I(a4sb82g0j3*QGCrLD!2UiK3Z}r z19_*ag6-k}T*m!~3QF+VpbGNx`Jf6C^VyLKy6|2W8(PF5&&+J7f*X7W!SBwzsDiP4 zavqas6e~y_q~h02L*x-qi5aA&r-F1u6|&w`$aiC9Hc?@2jKt(9%C*s95qd>wF>o43 zGFFUUbPUFk^oxh~UM@~Q8hJ5d0qO;V67-^CY>cE|l6B;fVN_yCMxx@dL}t}=DSDBE z(jm{NG`&bc8F~@%U?SoPczZNrP>#&Ovc&Qs_pUsTQIVIUSAnQPHmF~hod$fg{?Yeg+L%!LWkiYyoY z;y}h))60p$IEY?jS`%E29C)H_sOEsJiH$-&U?Z++9P&G}<7o_`){xc+!=)|Px1(jl z-WbYA16o6@muz^b?HS32%Q1|R`m_cZGg%Ys_|^UI;!PS6a%e=zo)IBKQ-lmn!Jn97bOb%Y zYU&^OtSJcY@p)4a+?V%Z0zO*|f`oi}90W!91UU$b@{@ufXv0qnf}kxw8w!HS{FEpN zrts51R-5w^K~}%>v)~|jpLQGwBT$K`1&?X36v19TB@w|Axfm|yE?NZ5x%U!5Gw!}bFoAdFA{fuR za}jLh9h?X@@J>zyXYCnyhFM<(n)$)-EG^Gd@NdhJ@oEwogM4%v`j^L(CQ51wFP&cx zH$eQcmy5u*+d%J2+9p=k`^@j?B5>|LhcjqjVcM-D`kh+@zmBhZ!_GT*Gnq-ee>WS> zX4U*$qTkC!lFf&HFBfm$ErfnA7jNH%_iqXB~Ru%fc+Zyb{w;sq*X3XBNpelE@F`Tbj3 zhRpPL`?`2D-FxTWT>tBiF8^vTm+;Ol-ctA90sUSs;oV)lpWZcOr#B9n>3&C-@Ln!{ zSC<}q&-J^x_&r{{bJqhe-S6t+?ezK~GyOl?(Ivc>i{I77+qSitk4N*qB^B|1cSo1- zUM}2o@h<6QXit}awxf&R%O$+8OL#Ar@V+kLyNH%J(wATT4Jo4*d=- zL1>4TAhbhEz^|GFW9DyrzxbV80t_DSw}re; z%oxOgyOw*<@9PrqzUSR8E*HuDE-uN1H`BeJ?tOG`tpE3Sbn$z+g!gs%XFIz1y+tY`L&*-}vy~e*Z5g2>t5{xJP-9-0zeW1npe}-qUt~?eV%C?`hjPzo$(*+^vW~ zN9P}HN9r9gul%1{TRg5vK_}`RalZ_YzYQaiq2JG^v(r4^&i-8nG+fsjUn>e89Ph%g zx%}UyR@9;dE$KxKTHtL(4VvR_MdeQ?A&?!QZeT>cl-JC+C_eV{6`$A=I#KqX>)gw*|fPkguUm#s~zR4RQP+T zx!d@KUh1GGkFA+IO+PJm-!H^dWa;2(;z_df@D%X`Sq6BL_%m6?kWH9@cMN_XH2*Fl zBkvWClmEoC@pgVDVtD_zGsFNB(a-E%unBj-?YM(oFw_pi9lR6hk5hOKb|Ln|-TM{x zC-!yzdr)7@$6qlh&+|Q`4|e2v?8ytkMc9Yf%lYpoz3?k926=R2OuyXtU7k&F@p9wk zRmbvbjPLcnZiM@nOIOE@%!LV79pkGJWBGIg+`oLfAvRz>DtR%z8jwwQb#d0F)9Pb- z)g_xotB(Ozm;OvVx4IZz)2K|PHGm&rGhu5HXE8bxCk!JFmn%O`(-g+@W8u}NIvc01 zwwvq<;5SWXya4`MEvnzq!q#BtEju-^>uUI-2_I8=n1r(x;!J@asRrz9+-jUbq|ceav}C`JzW_b zLeF0AQc#Ahmn*IP{#vDR4lf0z^kqEFQrL@^gOb|svQ-kR@k&raU&ZSzp-U2rYrlh5 zab1E~Okc+nEvC=#r(aALr#Fb_H6A-}g3GBZ>0-RQpTncefk&7_SJun04XeO8#HFqZ z?%z_3#VUFUK4Vo_RaeuCF&{mv>FRnBrleUjU>o-+^txcO%-vy zV(A*xt7DQ4#-XcVW8*hfU_3Tn+F)11ma&3Ys*D|kXII|F!Fwu?)fGp_=NSyZ&l`Ys znHr~YE{snsXX9eJmBa0dt5acV&U2}BYGO)y^WZ%E&$2ji5p`MYuXs9zPKo=Og0{dV zr{}oC zMDIt|(+OymU_xR6o>v)L(?;aJt|q=*MBUUz&}m^!ViTKIr-Mz2jcq#Yzs5L>>2xET z9xKrMk?D0qn*mR-A&z7QtjCP_gbi#%;uTfeUdHq)WlP&j>N34c>I0h}mc|3TO8ttu zs!G_B1AXz zgH22ChDuAjsWMT?h&NUcOD+?wuua4GO_hdr3*N$Y%FJjcOs_Qdwo1;cQNSjrk{K2t zrefr_N=3Va^OWD#vcIWI#22cTtqp%8rsS$SDkbeMyvu#^b5+~c!R32FOu_g?%)jTV z4(?waTNg91uB`{35r0?pY<>8Y_(avW4dCy@C#r$Xq#vtH7@Ln(W}O8-q4x-5F^hgk z%L*S6AE>POpARq`v+DaQ8;J7|Cd>?P|4Sb{Csyy~BAAse-c6_UHTi$@_+_;c|&V>Uhpuia%rIXrZb`*YB zQaeT`!SNeIHX0jjlul+x(qh@MIx)WASVqTSdL_c~8>ip1iD6=@p3c#KP$ux~KMCg?ZjEm7gf#lskj$JlE#0ki3~c|+9H zmDM&5@s*i~<@5^gYa(76?``Z;6Nj;v=9T$SzobplFU(8hISKP=ijIX{IfdsD%PyoB z8^*@Nd~RNt$@)2M1b$vt?9Bz3d|C1O7U*m+8@A^&^W2QU_M5M>dMfRu zno7^%m9du!~U96YD7{q9H31(n48=V-{ zF2xv(YNHXO*kyV-j7p4bquAwmT~BcQ*6QEQP52pcoqmktw~qQ}*kEgM06*7{F#SHK zz7EstA*SDYDxc#gJunaPz8=y)W$u~#m|pj=x_-fGy9e*lKS}igJViW7wgIne12)qc zbC;{m(0(x|7}AE$k(k1%=`PfG;1 zalMY4FZEBfuk<%O>YJE(H_a`xho0vxW9>1n`br<8c>~YlZGNx!5O?EeMu6WFkD6mx zarj|;cD76J#_rrji)eS^d`5!1h&y=Ymg^mOp^?dV61US^uD8=Z#zEX3;>UUgzTyfD z&#lx};4y9`|Bkj2zwx^eS7M58q35{@GjlWXBfK&Z95J8rC|2upm}sBs8?+zb4|*Rw zNAEf|;y!(iwjW+6UN!qM0k4{C#4F}U48berfIbMX(z}cac@W?05dPXpcmmVwAim!z zeE`$%6!}Tau*2AZKXcV#yssaz{!TM`3g2r#*55BwPU9`@!}>czwu-75kp}8U3^RGe*wnwe-%yv-+I=g3*n5W4noKFu~60 zHMC#hull@R$!oF;uWUD0tTelbtGVjDzR08AVJ^~k!ky+W?TZ~B0NBS`az3Z~@g3^ewc;!IAVL@EqpDS9ptY$-aaUh{G9o*mrTM#G!qK!xtySuW&nu zG4@gq<0^;q_ca!1EXKda0{q5ohOvk-$hN?k#OTB=a0{A|HhB z_YDr%5I6)U@H^_?;&=@t+o}fO`fY<-F}?cZ`ZdK>>t~w5rmzpO3C7ws)r5XO@@;B6 zc|U5+8Epo86B{$KT{Widz!U3DwFQn`Zyc}2W`}A-+le{Wi)u^Ex?b2_jm%EfkhV+J zAa2y z)eK(AgBXU>VPZVZ16YVj@EH$;m;`@wKR%;pQtZxsD!EAk_bZ<#Gs(>l7?CN=URpf( z1F<5{uCDot$MQ8E;#YWvt$1`_;VQN=$Ki2|zAl)FoBOn@>cBdtJbqU#e7_k~r{jCoG_}l3Dl;&>YT*0L zqB0XVsXD&jY$~(xx2j^R<;Q2M3ajFF<)dF6R_BU*^s8ZpRbi|E{#zAHui5xbc^RLL zEmnzIL0SQPuQ~Wl?=wC}72?@f!d0up7>*aVQy#|Ws_eWb74fkuGM1Z>c`7$;zRE?< zb3XplLRB8Sav@e*d7Qk3ssgNlhndqX;OAaBal;m1>3xcWxr){Xqi+?S=1N*yY_ObW z3btQcywFeZ{o3LLw!AbR*Td4plDLuUvAeRGY^J@+hV|E;UN+NF zWx@38NWBAQSbLSybW)kI{yI_bs5+}mSbv?Vbiz`~i0{{hN@rZ9jAWB!2Hd~NGCdaC zWO8qDWi(yYhuB*g%@mmq(`^c)lX15`lwH+CS~qO4w0Lk+8J&W)HBoj`cwP8S(_|W4 zxoM0}#Zya-PdA#%G;$H7HsiUryBbgHp~m5QdG^45>dhlgg_GBgI2@a?2rPoDIh>JH zW-Q)UPdvDu7;wYz@rs%;tUu_5<<*OygAS!u)C{E+gT?SdhfphS2GdHwA;dwva_eyl zOW>Cd!X7MvpST`Nb0BRa97Jybaii)_^xTNy*^jmf_9ylw`x5pe_90sh`x5)}yhh{C zwdLos({az*sztI5*4`p&ZPZ8Dh$G=hoW6w^i=Lx!{TARedXB~foR9hFIR-ay9(JVX zSZu)(Y9wA?aiZra*%#w$BsN${H3G-4m@1C_R|=PJ1RTLwY4TEV7^YttHB=6R!|=e` zVzmv%^csxC)|S>rw#Hs7gV9w+m4!p-wWc}*S8Nbhw4zrQqpK`#Q+q1yu*U`xTgq}6 zPAwTPhd(xeS_fKtR%G<2*M!yq_p3bKQwy#wubR`V04v}?Rpznwla+B7XTW0g>f>w9 zgq4ZSWJRpEX0kc4o~n;`S&ueLHf5xeYDz1L;WrD2wpvl>?XJ3v6(*}gUWZ;W>P2BKVj*hDvAdG16skCtVwht!aN>&7u;Lg` zp$gJcsuI+TV|f*nDHTo_4%GWpO5l@KC+24)mC8>`tv;aVnOdb$X|dX>V%$~5tIVmY zVO{2=Rt@(HXH4azCB)?GgtwVPb;jh(fwR|%wLJM`LTtYr7@gT@U13+*4Q8j86+f_> z%tGr9vxf5SvKd}tGu0esA!Z_L0W%XblC^}Hh#812VN2CYr6+o}Qms`wqGxN|(F7_l zzk5j@MFLfYmK)~ArBE6Vrr{wm@#zOO3Cyec28NGvb&;R%+< zip-}TVfE#~`pSd#_YmVN53W~k;$xYM_<&k^e6O7Jp3oj+eC43`JM9U^QVz1Gcz!u> zma>z@$6kvEvl8Qyd1hlIF6|knS60RnV8msCS?I-K=lefe8XeS03Q$|t2gA4@fb^Cdd1|L7&PzRmBQGJ zgu_<~XRkC?XG9f=7@hIg@HOjNB4F{Afn~5j9loDuS$t884d_`8o7C_M=2wPS@dIdy zntlPL>E&07tRU1xNmd9dq97K6g;Ze`&~iaRd@BR;d;I?QG3BDO!X_Qj^PY@~v6wEz zsF;0ea1}kHspu*-CZlI`Ou$q)kDf79OiagA7=tNkvDA+^dr@$|qTuxXNZXJ56`5=w zc>wnl4`T5}hLIUNgv%ERMxuWhKP@7RNdKO&m}~chqjsO%+g%YD`whP<0^XOwa(h7i zJ{H$uY^S@7AI1$+m~jvJaLz!(6?ZVpj>W^@} zj$uUI5>@iOk-TUG&H##p?9)At4& z@rrycuHyQ=##p>6Ux{ltfUocwugRC>}73Xo*et>)7uf#oA zfGg!5`WMJA(A!7-2Y8P7J++ncd)g|wpUOTQva`h9jI5HoX`jj;sqDupJ44*X$ft4_ zZMED=O3*P;BWc!n|fm3%HX(O$q8;wDbvm-N0M-jrX^ zZecCn!qD7E?-n-WM)D1`J6MhzLcD{~`8n-3xSqI<>=OK(c!1w~G2BKx#Y)h{a52{2 zNpVVeev8d_0$0)VJ1oDS@fkh0V*ee-dGy?d75EcAq~~^Q!DBd)J7g>SEp}f^`yK9I zOT4e|@VmC)__e0q%C@jA?dRBETj;m3oALeH!Zui6--ylFUteSTwIgqft@Jh7BJrj8 zN-P$eh>L07?)pl64HprYV8LyIn;2V2wLM1HN5rLKBO^;`cw&ZE}R&ZBj*b44fH8O|eiLf&q9$9L4?XZ;y(;*npnLc=h^{ z9TRu?I2+0Vof?7q*$P&*8+qqkNJv%}$M#5Gur!{Kl{!mh@A z9AQ7DjfAU-lk5ykzeyN<-VB>5#^Q;6NSsW45+2xe+`lPsG9K78tiP#n3Le-LOuwnv zebdA=pW}5+#_;Nk+cpVKqSqS>a2n25pHM!TUOz_r;&Sz--itOJPRDZUPrV-w*+gPb z#%I_8UPz@PzY;bIAt7dBpKNiV1cg zk7zs`k6So~72BRGaQ8-wF~ai`oW4o-!25}vDY07rj7%z;AH;I=~K8H{az*mN!Nx+;k8YV8@^jvuHA-#cgPOH!5f6Pd4QhhVBF3!VmqsF%W&;>Y`+6`2)^GCF%%o{ zN9#FM3={kC13ia{;kbqScpZPBt-&u`gQdBbxE5b=Z-{H{XLyWzLi`N3b2mNDb@-pV zY3p$ycf*}T&-HkqHFy*op z5V!G|ZGids6Z{E7us&|2=W$HJdYF+v<9?MCr7*rq3h#uK!T>x+trYfG34Ff`)X(F7 z6~pnnXp3Y0U8H^i1FR^f-zDl7@s^5`rNd_{BGS>)iZrk&OiN5dcG;%Kc`J+!R+uYN z)4yU1j3Nd7 z>ox@=*D%}iVNu@1V5|wx(fgfRO_5w&$B;@cZm@PbIbU(zKA~C*6YqE8V|ukraJ@A;O@PTf#~@Rr!Nn# zqUUprzucINo-c3!b74DrzQhpBDPG|W=EQ+~h25AFlhERNCB_6xjOk}E!90_&)-D1S zhx?TX$1j3=5BD!3c?7JlL}Zch)DmKX`IF)zlSgt7gLwFBkKjYrO2%bX-~)E_kL(_> zW->l`d|bB2)E}{)G7cWxeO6IMcK2yf+!HE~S#ueiHG}tpDA-T;SX~*#{Z8cxt21M< z((gA`T1Iuh(W1GVRDKWcvg$ILyGx7i?$Gm$jujOXt1Sk$8x6+9MoB`=GqcFT`oudy z40oHRvHFs@EFv*2D{B~UvtIr^mlfOdJw~#ML@paHXd-IaL_(Kc;j{!@M zb^A&@4U)lRF1eFzAVtMpUjLm zLxG?AS=8}5`}dzk}f$C`@7YRsJEIb0|0S7~;Jop8J&QSGSx zip`EVND)OBM1u%00#|g%U9k@29>#8klKD%;F7u>WCI=Abl4aQtI>RoZa za^qgLV-^-vFy;txRj%ZQ*K+o6Mq(yk` z(%=^sCe{^N87 zT)*YGe!X-?%*KAOpY9L)>j7{8zGX(d%0X}twq-^)7{fB78-huhk;k6Nt>stkrPtDW z!``@&YlA+zFU*LOxHc$*rMNaIi?_Ho=*!o9i4jr`mUHFZCcF{P@~(pW0+YnEf~)8@ z1{LunH)5MqbQ>^FD#1#wvRjXJ;#nET@^gF>&nmc=>w>CSn(J^+s=CjxPO7;Hcq0p0 z^VmvE;7vko9#2E_X=zWB7H=pr|vc82U@#SmJ21rJ*(P zOEBU_laC~NF2z+DL7a=@Gy)DI&JBhVz0J~u&*U&%c<0E8j_l+h`BPX%y+5DK%Aggd zB&Suf`;H7sGdszkIqyIGIh8lL#+#=y$jIkDGN|r%iwc}e2_tyXYFZ2;1I?-gjP~_px!>@RLsQ_8%VWNXti~x&}!>WR61gF`Bm7R zX`L{}`jK@F*$Z9CyI@K5q1TP(PrvO=uRD*hH|#^T2YGj#4@owM-)Amthygc;))+R% zxtK$13Y+5G&7n2NFPRe*4~o&|;0Mm3Uy`qygV$0l#5wpvrKpsI_3gY2)RZTsFcV3smVI^3bfjIFyCSuh-t!SAq;Dp9Ej zs}u84+X}bhB~_+U312ZEx#G2|3QO~y3!^j0LY@WVPtmf$Y*>Se7G5czlRPK(j0$-) z3YR7ic^-@#Mav7Tc}p21tQxG0v8QO6VO8uKM){pp$Q)B-mC5sl9>X?jDoDUu*#xYl z49L^4o|1EPRT}t`UGP;fm9MgGjtcg&Qbz@sSj)j#yZRE0$j|y!5Rcu1 z8CCJ%PwbG(SMl>f6|Ckbg(~R7&yrLyf}bbx*!YQq3L5ZJ2Nk5_b7`KJN(bM{Tri4y zD^+kpMj^k%K2$1L$LAy}*urNeD(J=?vZkF>`x&KnZ$J~Qq74Xhn1&4W$j$O;U zI8F-Y{T${3^FH=2?*J6ec~a-kPE3jo<4=h4HZLm*iGsEJf@-2rmV%mK-MpZmAn>L` zbfRFbal*i_K=;06z$)~NFeQ<<1B|36W?((LKj%9wOvjq{fGjmk!|M2ethbAUkQC*7iKEbu)#)*V9@KlX!a6?YLVreL zKyUB%civ6tPCa~fj|jTCXc!IMsB~vdcQmpt(4XBCjg|3Hc|56DRUa+1+CCa5+MFPZ z#_D<81vMRrZJ4WSiXZPs8JG)1-(*Ku#d3KNC>(0~s**zA2;W{mRc8_39x1)BA zcAd4}-u%5vyT%%DZv0cth482W!5nh7cHNF5ZLT?;j;2A{?cEAg) z`VYveyZ_s>dpclylw`g7Kc3)IlJj~>v%cN49iB({9G^0*esBB7**%Lwr}ixVj}v_S z**&eWI+nP_#J`@}6F$vnDdR2OQkp-t$Dh{|KD%cbwH9s}t@&S0?P-n~(EN|Hd&Iwa zc28|Qg767Ge?7a0vwE-({(OQ@ozMwBb+HxRo!aBi@9}5%)D4~5>ht=Pxu6%@TooF6MX(R&+ZAI+7mv(r;+ui_xw9&_x$~NJ%4|W&wuai z9{g?lzkhbm2n>ku2|gKh_|%^82|fj|UH3$Rjqs^G?-T!aQcq>Z{dql= z|8z!A-apRnsbI^q(!HXs!0K#&UeCL;d!Dm4KOZCEQ+vYa^@!l#JFlk@)It9P^Ix6UQyj;^pW0KLHTQo#wddV=J+bs#<?@ma!W_x$6jJ>q}x)E<9ck3Y31lbz0*^-Q=JGgztaPwk0g{fRgK6KD7MQ+vWE z_=HdG37_Ee|8jPZ2;QCDGoO|F;S+qqr}jAOPw??)_x$gj+7mvn$DiG^MBh?N;cXn2 ze|2ilBJI!X@u&7I!cqA1sXZe2_fG8@gU=B@yXViR_Kf4ap77Z{;q!XJXZQS1oZ910 z>j|IQ^O_av|LW8pe_qe!(Ahozo%4G9`93#T1OL)oFuPcff5Gfz1-C!7NBobT+Vh+7 z=k?q-_sk*A@$u*NJiu{ycWRG6#peJ{%im7znMf~ucF(^)wP!NkO8D%ay_g<=qRP3jLmM zyq;8ck5BD6My=28`7_j>^Z2w}z=!FJvMC}o;Czajv zI$j*2_H4p}->3Gx!SV)tGu{ZS$G<|vo;L#)V6;B9Jd$wZ1ot0XVdK{BV>d8v2cs*Is>{oa__hS8j?+vIutMD-J z**!O=_N>8Qp&+TyZ>T-%@NV$gJ^wChk7GpZ8EL6KBmaQfBVLcs?(um&KD*~yYLAP* zhR^P~mfAB1UyK{Gd!B~W^PffSam>Gy+H(sY3O>8X=k@sPo*PqpJp5Nu**zYmtEoNW z^@!RNz(U_A^<2&F`IXlb4nE|G-y>=d(SGn^NWxk_mEH44)E@DAe0I;Dq4uoC4ib+Orm`^iu{k9a+eExRWn zxcMq-Pe+c4&+hSgJ#|={fK~XG{~^>K$N0P+pWTy6?MdbJEXIz1DV`j0K~a3f?zuj- zXBl1`zp{I-Pwf$}$7lDXQhVa@;qci#e~#KCUXRc2@p(NyyXVH#o{Bf%^;EzcV>LGL z6@sGk5S9u2eM`1rh@;=x(e z%*ICikEuQ4_4w?b8&iA4>+#t=qV_oET56AYJwChVKY`ja8Y^`1dPL;$sXZfE9)*Q< zTP)?p?h(O9WS^T@FKUl?JwCf9mD+PXUe9c-;YIWLtEoNW_4w?bYpFfr_4w?bUY>Y8 zKD#Hyn}|oljj268uV)x`4A#f^N&+|MCxhjirOPyPXa26k5B6H**%?Ik$Xh# zsfX=;1N=99cF(oc9`Sm7c29A5#@t%w%DljCY?PdT?B%cAxa^!`z5kL&$?UQZAk_}@}{Qh7aM_tgBi z@p{r?x$jeZ(&G{G6TSdq4EekspWXA9{G4&kJ{t&dVF@ze?7Iw=kZE`E?4#t9dQz!9BKY{c9-rOwuTy)(?3sn-elPUzQG5D@MCnOo_bkDFU+kV# zYL9q5KD#HC+LOxbS?8>Pj7_ynJq@L>5@sXgNL`0Sp)n%dLm3aO{HCH08c z)5h|8TH|>kYENr;J!14+kKOY*44+hL&+mCXV)Xdbo=SLgBw@=gwvTu{Ut+Z`iqG|^ zJ>vDGvU@IKga0eL=l8sxi=jB|_eJfwme+%QW>^#-pVyPh?h&2Gr}p>+pWm{3{)pNm zQco(ir#1wi8&iA4>+#t=KCj1T_x#n=p7%rVLFo~@=SI|?-1uGOfzngLGJ8tmNs$$f zPd2R8#PP}Tf9#&W%kB}i=QMsVF_zsE9X^9UOEfhx*zcdkdnGFTA>J!d)JJ38kB`cq zr1t#E>+uObe@yL3kDo>ctoX(5xgNF0=k#_XQ@Y;jBA&ro~B>+#t=H>URZydIz3^Y5beBx0XGGSCoO&j>V;yaBfQqtH=- zL~Mjb?P-Md@Q6TtEbvF8qgmJ3@_NK586FUqWEeUuFf>rlh}u(+E$d^u+yr7w0%=H~ zF5UrMP_cXJ;!V&E6}zV{+t>Ri**!^?+LMIOLia!t9t}Ov6ucXfEVU=eQhSmtwI_*R ztcwk@s6B0{Ny7G5)SlMVw817=)Sgz%SE1AsO~IPH3MJQw z)Z=2aK7_KkCoXpC!_X1r*x@?|99gK3pe(+R?9^qyF3OLr?Pb3%UXd)?Wq&W4k88<0 zt`Y0UwKN~sh~VQ|c8`mvR3v4QeOycMag7K*F8foJZ>Y+3;F_6?jk`uPAJ@`+zuWphjIrJk zark#k#kzeuc^qCK)6tpaad?Q#L}!!7@lR&sm$IAEF4As1RrZiSK$?mdifZr2Ha-rY z7IAR)Qac5Gfc!q{@5k?DFZDYub7v&xONu#dG5 z<129+Dn`%4)J??eryN^sx2&K2)ZJ#bVS8U5El=%MEbuF!6fHW6I%cplBHQ8W72WJ$2WhYups< z{8K_bQBiw5BWjOlMD6j6e04n|YL92+-RT)odpzI!4}ZXt*y8_LUVu*u$ZV+r0c`Fw zVb`w6{CHAehcB9#7-8aKc%(=)5+4H5!E&Rr($CK}9v%nz(Y)jy-UE5j0hSsdcEA8E z$HQ2`_qWu5{?GwL69`+H0M3qZ0n%ap-p|ql28V;#(TgcC$Z`SFo4%GBAdbLbXad;( znLd^d(1Y?2tiv;4C*Rw01A4KPN($(S9k|a6@QD5|KEP2T_)9agbQq06pCEsd`lIF$ zOEJ&{dWN6G*8ULXrzju8_WmH{rzt;Woo<;0N(MTgBix5Q}HT z8!W|QtM8Z|;n!IbDWEWZ6R(kqqT&X;N~xG-1Qf+fLA-!hSSp5(LUFt>US_E{J_;fR zyhJK#=>XDbj_QjnN8_pRB4x1&Ai9O0gJCcn?s(C}OE0)~c95Kn$6cJR;PN%6Mj z1q>zsS9k#x0$qstU!GX{(yq_}DpFG+P%h97jzBpg=66H8*ld09!5Ystbw^KNvp#bs2v!FZ%J+TX&6L++OPtWEH7XVT!0$H;;#W;V2&jVG=UB< z0{Xxl7y^x<1B`$XFam-=W6KL@bRAN_Xv+u?F(8q2$}|X^!Uv=QUJ|EF{lEu!h1AD~ z;saAJa2jusdN2Y`o4SEBc#+h_=i-b>2%N>cBq30jyiVXl&V8N0o1FbRfdrPuv3Ik= z&0r(cf@e^Ndx{7N&0r`rv%G+1kOF*az&bo9TEGiv0X1MPo)rHGFCd*|0i-3m{tT!A z)56oy>EU!lsh(Kb{1c(3;@CBM+M;;MK3^^R5MCx0I5<}zg=xA&y1C6mJ z&k7S@CM<=V?8nS-42*^4XioA*mN?KT)R;Wl@&cj*;s!*qv;tj$|4GA8BZvbHNjU$C}?>B1uQS10E~cD;R1nV{6_LyQb0b-3dqN@=l~)Hha$VF<3HsxIBqON108vB?S5)~mwpbe>Tphu`Mz63p}EBr4} z13D1_zhvMPM1c2+vtJK7z>6=7ZNP+^wNdWA_JdL>v}99#A3 z=oi@R3rX#DmXB$)WE&u>-!tKD#YZ_@ki^M3Fwl=b#N?;JA$EXx0UbkM;SL(SM7FPhSB67W{rnICrjQp1O|vY3Y1B-`g1G<$fyvmd7l0v<7gE4<)=mq|pgbMT z4FzCEAP+=_f?27(gnd%h(D&Gm z&w&&m*1&g`EbtvR<#VyWo(%n90jYFoB}>xMPy@cjwtQaTTT2ryblznBj5pVx1*Z~*d0_>oE zJ9f<5EIr_YB?_E}5pW-N^5@a>*r(r*wfvXR1HNSW^`IyKuajOQ?*Hf5(!WaSbMyTi4r|75Dy-9il9>A-?UGM^SK_hsXCFyR<7x;uN-hyiIN$@4; z0DGVV?7;^61V`p$qTqkbx))jV07QTXu+DynfBiLa|Gy3f;Q|ChA@m{g7uaeqvH15w z9C#uS3WY5xAOsg63^m{|b>YzSSf7hW@F4cvhXNu793rJs0}fJ`F68q94g|ywI1ms+ z;PGF00UKZgY_z<9$H^bF+)<8Q@!)HLr=SD8#@bf{uLq71`~P)nUc(yw$>1?8)Q_=zfAC1~D3;>)TRj>S zG2jSGyRgnbg8lfDY$rOvlh~j?LG5lE?SBVr-hdSF1~%>6u{D>z84y|EFk9>)`v2je zhyZT|wvpaO-wwQkrM&zlHnVmQdXRi8TfGz5N;(;MFYpe$fcMygj*1>|hSCZ2M8M|-91omkNu+@1123SW2b`kxA}V^o`;?BNq6e&Ck2YHd z!n=V7;2L}$I1v0C-+=?veI7{V1&AH+H%I|rqF>^B@L2FXJ_wIN4LBcoGqbMVYqNqHq(Pq9paDXe!Xd)Q##&Ng#Uc}+}aIfzan5A)wQp_}li z$WAWZi`T~_)(0&q;6e03cmY|-rTd@*Ok`aMokSjCsR0qJdB`#X#0z-Xk^=Ta3CPUS zemo+?3&=$Bc>#~$H}Q4A=LLLiNdcG8OZbzd$Dcy_4L&F7@G$Xt0pD6uz<20(_@1P} zli{<#2=?W6NC+XK%FpG$gz$-&OL;jd7v2&7JT>4UqU(>xB7Hm_1rJ$Lz<$aPLkk!O z7hoUJ^F&=8b^{(8EUi?@oR*B!HVO5nv2kbYn?$ zfX5&WbfYu|d-I#vs;8v@bY;!oyso6ju|OY9ZHkTm-vv6r<6ali0qoRAQQHf@h*6dc zaKP&vJOE{&J;!7Ok?%*cu01{zBP|QyAS{4`um+AmMZPU~#G8l5$Pr5Of-gV|Sb!cO z@5r`?u)seAec*X$0Shf1U;*@jjzRGV4#OQd0WDxr@PwrY9QPLCdvct*MQ{NYz zjDW@XN-V*@7jBIbW`aG{rsN5Mj3>?a2o zSYE&aV(YiX`n*kW5q9XUi2c9BYYih{2{ntorPPQf&A*gcKP6P$O7f5TMjp%9ex!niM-zq zpMjOI7PgT3VsE|zzCbxF(O2L}AY#D1q<(l8h#0V$)E^!}x!~RSB8VHXiR6<4q+$nb zfD|AVHDEoY0I8?}>nt%~ouvk>v($jKmKU(b5(Cy)YQSoIF5ZC<@D8kiRhAgA%2EUF zvBZFTpa#51{Cmfgfrn6*|4@^(4PL-DOAXi#FQ74Nwt0>4nb_eqwCsR}cu(x`u15{< zc>!Vv)Q1{yzc;`W5um>(Qb2!}O2ZB)2^U}>^#iB$R=PmLo6`MnLW0ba#e3 z%9~Ca?cMIxffpcBKphwX2~Y!mXUPuNHdRtM^1IDmN)7-`GXyUzyjW8Nsz+!g_It34cRsRAt zAOQ-%6t@nR=+Y_fRIJh`W0PLjn*-J$e5jsF$^8Up9ACHb_U2kd|S~@_YH-P&7*szav zZ$)oqsTb=Tdc8=Eux=kqZ8vxZW6`nhKsSZ;jl2|6W3MMmQn3b_c}wu3XvRNYg4QPQ zNZnF&DeQnAZciu!JuGpcgC}A@2TKj;&YC2zyX6kFx72|4@B;3%jDTh6GN=J01rOr?T20;q&c>$^HfUZ}l0pbN*O%3So_3%dFdC?uO3-JPc zc0gXd2Rak0J}*pwJftqfr_Y0bL2i;b0-dl`&*yc74v-(shfR71=l}&!(FEG#V^9z+ zfK7TkO9x0M=6`MM>}z2!-i~!ODPe0*5-}i|b#;jKpKQ4R1>ph|gguZzO&vFZ`2MZY z)+|+LeIc(pDblM;eS)O}M0)XVq!)#ad@Hvu@$XxbixdzADIm&=_NuZZjrL-^!gx*$ zb_)}UzpGmg(!vn5FnJZY05L@8kMUw50Ss}6x@9drpfYP>p#ltb#S17)9%rcmah4ho z$C_bRNCBn15%{r`f)OwR6*ZuwA@0(?oN{R%{^uK+3F0yXE+a^zo7Cx$>-mM)SmzzryCnF3|VzlI3#6&gpL z6AC~Mv=n)EYQ9Eu*z(tq1+rU4KrYtigd0!-0zfWH0m#OhOOOCAVT+xc`dmc+{|1IY zR_eaNs=WlYc`OSc51tt%EFIum^joL`8L7`htp5ngSxDa#@xLPcgdh3W72yKZhZm5} z`;nT=tp6VU9^37-UIRDLk^&l7IzS?t2sqR2?0k%NcYj}kh(9jJLl(G@p2x>sk z6EPr25+k4*bbx>-Za{!k>5Uj*1@OQmTQ99^jCR7f=IMfFX$&Aa20V_@k6ZMGyGN z{TXUSUVi^F*8G==xK)&t5zR|p1ZF^{E9`*6{~$FW3eSwJ-Z8ud(i3MtE%{R<&Dy2M zv*1ZmKJ*w%PqX$Zcmg5?JVO#+Ak5OUq-S6Vgjjlx^sM_iLvBGdNZl8dWjP*V-Dg;t ziyPoU3iy)xFCYOt2XWw>a~!_FIktKZZh#9H;5^%W2?^kwB@0mHUO>(h_x}XMflpX- zg4p*4KEPSWVco~h^RNcQ1$Z8YKt31&FY~YSK?2Bc838Yoe*|^lMf79xcP%yGT}u!6 z(0LL1z=zleya*ehAf$kktS<-^;H0Gnh#>GbOVUV73W(x}y~R=#o)jVmyh+Li9YDl@ zH!L;ab^I-|Lkh?aH9({QX%5%{ul~Xd$mzX8#I#&!E(jGDom21vE;=var*P5vkUW(d zaPeQH2CRb!u-07%3*fY~9$n|IcTYhCSi_9$Y4kMIfDP2FcQ?52LkHN1Zg4kZIsYEz z_h12RqP)>Pik%`vzE zZ;~Ho&1Uy7>0b9~YMz1{@CNxI*4*nJB5iRWqvmPnAaz^ZgQTtQ0hXj&VG8VU&tQYG zgSq505CL{TS$LR~$_Nl0V4M3mX}e_vT*4avacBekSh@r$;1UFZeR!Psq=0YneRvRG zl)WS|0=|P9@BpL$mBkL&bA=ZmZoqC!4cJZHCr|-Cy}}Fl6e_?u%L~{=exIcV+(+GK z_yc^7-^xzvK8KI6o!Iiv@L#sOuRG7+%kVnsub>9>vMhj;DV7(|o0?vs-j)l{ zGn4{7peN~Br;lX>^r60Ys4wL{sE7dlu$z;f0P4BbWD;Lxy8&(O1Q0ft$97HYsU=Pv4(k%mA55HVn! zr3T!}(s4WrjyoraGrA1!z@3&sFcwdP6OaNu|q& z8^1pkV#1xyZK3-}q6VxdzaBLpl@}mtz$6F)*HQz-3-H+ib3$|B0L&pRaps|OVFoP1 zmtZ!&1xwL6Jv&dP1&W9#2-&sI;0X_x`RSw?KXf$b2Xe?Wfffz6gOa8H>IgkKGJBwfhED9|S-AesfBL0tZ7KcWX zmV|~cMp8*wM28@6emK(5~(kx2~m>Gg`0Gr}2mSz#Lau_rNkq|bb8!a_p z9NrBxNSpDS_~)qs4}=Cn0oX&Ned!>$0DD4%Ek|IWWd;m@3$Po@m?4k^6#4(b&;aNH z`zSvMN1z`xfQKmWgAO1HKy$Pis>uIMS@W6Rz+ACcp&{G2j`}?Zg0X2zMZn z^f+t)5d)qkO|+x{=|rdj#~=krCpnYxj}S57Nz!&W0o#A!1ss7CumcZ@9qykbdLP7q!yh=J)UO>BF7y%*%d}-MM zUsCGmd|{~p;sv~7Ndd2-ui`iI8M*W|SOFphNMDB+AX0$z4Ojsp1xVk7Q}HqR@lXkP z2H&6s$*W+;{|)-hA5sIp#|NRJWd~Ha0W}~H&I=KMNcj)}f|M1jo=Ex-1oE;RvRr_W z#wj2S`0n&tXK>`BS@`!Qoh;U7$gs-LslqAM}Ca0vO29&hCfYOvp!4Jp?DWC*ai2>*V z87*1BCkTidAeulNcHE){h$B!2MnD><0b&OX4h(`5kj@zdJD{xP0*EFcYJkra7#Jvv z)%QTQDjOaa2to%K76?HN5LsX-(f`X~2R;BsKsjgvL2CP3%0T}>1?<54v%Y+|H}%7b zl>e~_I{jE*5xZ3J0;+^dkk@DFTetwU1`6`*jq2r7C& z4N65((F3Ye5-C9RfcPuC0C5AVK?^8=iXKpvya1GhKK%M5JOL_)C*m7XIeagc^I`&s z0%`q0t}Y+i&(n|n|ec9f{F-WOiM-sjS(5sV0*oS8Zny; z7QkbunMq&P7_s(@5e3FrB7iYfc`mXkV-STARe=tC}QfJgyXvjcjwCY2iSdtN{<{418@SJ4agsR4s6BS6%E33zKv zp!QdGz&}F`Fjr9njHL#c|0dLc-}3@Q5fC+?JsvNAObw`x)xXaU@TmdSSo)P0ko*fT zKPRT=yk(ZzpK#P-?q!dI;ke4D4qCxEQOOe8ytx{+lDGi#2*!FSMg*kI^ zl*^LRp=HR+QA&@NB`;4Y1DXNb`|{MK=UkSjT#=Lstw3IhQf4$WehHPR%fuP2M7atn z0$)MehT|8D#uzX3SR*%qZ%rdFpGRmrv`zm-+yN)fq3t*nY|OIcC1H?^f~sM?#_Qg&4BO>HR$ zs`jR~loM5ZQ(MY~s=cW#aespV;J6WDLHGqo(WA+T-V7^3=XEah}!MbQJ2L z^*BCiSDCmX%2CpBsgLTYsa<8{Dk@7!?MrP)El=$$14l*2PDd)ywyZK}8P*x<8lnw3 za%w-iBI8)+u&kC;m}}l)eXMOorP0!Cp*BziEkY~M)vRk-SGii2T9R6xT9&SN`8oxt zReMtV3sR%j5THh_tOWZR!4b%WW@Zl}C}lu1@-KAF8-6bWjbO=;^xx7_3X+HTC4H-F zzmMm&{cmYmqkkCW_tQ|)(^0CYVQ$WPPE=0{-AQwBp0c6317<~azsMn@BmHvaY}gO1Ma9O`^6RON~%HPx_Ivm=yY9cvIu++!Re>yZ)@nf`@T4mIttu z#q^-u6D>jBougj@Ex~d(%JQt$ov<6{u@t_wr73km|p$5<<~reG!vg)c~s9~&0yY$FF#%FjAI*&Zeo6bB` zKF49U%VK?v!@P&I;`5W}6Sm^2(Y27yULo>34)fO0nsvIK^y~?f-%gGEYuk|DP9L`o zp0df5Lafh-swWd7Wk%(%9O9j4F&bulh~=>LP!911l5Bl#=yEJTVyW7tCdjA-sI>W$3LF< zdxM@V{u4$|${gHB{HLg%Bzlgr<^u*P3S5M$9)aY)fXM l~Fyb^~}~i zP)~r2B=w%vPtL&kQV&4Se?9wk)#?eL-a&fqd3v`>OH%J#y>ay^(sDiOey(0d8qSs8 z#r)of?!fBx>yE8nNr*G19*^$Geh((Vx%7KCx~9~>Db6`ouSxfPzbB;g9^%(^w$pRg z#l6zGPtR7OV(Dt|@6~DS^`U#Vo)fxa(){1K{%>}!|F3QS_iCG-ZD;BksnzLiNl(9Q zv_JJ@^(@Rr>s23B&#$bsVfAy=q9bU->X)irXQ2(N7piuhneWou2lP^MwQfZjaH&zR zO#L*6{Kmhl-@5kK!_??EGXLh+gVbF6yI23Be#^1{M87UZpkses_a=XT1JvnmrvIW| zpM&~qq+0TOjs8|5ChE?vyM8Wugu16^L$mYmbgUxmvmt`@IVtC)t~_~Gdyn?tn)Mc3 zo*MPxxB9wJ^%||MR>aLs5 z-jnm$J9a*M$IfT(d5a_qi>?;TC#o8C9_pcdUg@4)97ApdVCQqw`Qp}s&}1MqylJba*ewcK-C**X?r6r z$P3YTQ$M9Sy|+U2J=Ke8Mv6w8v(%J4nm%g`|2c_L4BC{u33)!A^i9xl^iX@yV;F~y zr*GOF?aq?OuRYKn^lT?kud&{)x&Pog(8noo_gy$C&Z({SDCNjHVkWcowu zZ;WJpJ$rSgr(Zjgnh~T1sNTqilj}V|Z7OWrQJC-0Q*jEt-!N$!n#T5c^`sB8Z6_bFB}e?`=p!&>{5M8R4gIZb-w? z;rt(CdsBJ`Y(!aa)P|IgHl+6Aw`wbhv8qA(7Ubd`zTW?A|xe9eo`;bylwL!hZ_Tq|EA64(LD)(loAEn-0qq-jYllq{#hV|as zm#axv@<38KRQFW9_4VZn)3r2+)Ze~ON_CwNw%7R(wkmJmNC%?oIS=I;NQb85Gs8%O z(V^tSDGfn~u#MhP2czm^kFd|L5qxSWEp~)ewUJS*tAwhhjIzD-QIslD9!cG3J~aZ> zGjTLmX+~5nUhhldPmkiBFZ%Q-^d|CKY^%S8Ek{$<9Z2s{H*x3E7}8iuH={SRq?k%K zalgyVdc|Xs>aI54zCn!VnNf}MSeC|9I~E;BK7n?W8P#)q0;OB+JE&B5)7#mq8aj?# zk)+0PkBeZtN#s)91NE*f)iYu;TUA4KSDZr2jX?D@oI+`$eN&g}KB<^lQq2TTBgLb7 z9!+QaDcq}cPn*G#%DT(VWVyPHt2GVPGi#O|bDPC;H#_BQY&)AY!;U9R=PiGR9Z8tU zmKsTzf$IHhj(vX3wc`$R`Rpt^7BHJJ08!uPlWN&%wt+4U7mJ?@7qXDaUPUl1OvejzRN*jUeZenif zIkkpu>!B;j6^&~p^Va#QN5YVT45v6#bj}y7-K4L;wiMnK8d#2C(%~6 z+)R8jSu|{=KT(iKW?Lz5Cv8Eu+42^iS36j{71b!|PD!R@=sQ_mLW*J6XEV zKHcu8PZCKawn#p+i?q|mY}-LBx1DUUo75QH#nNuuE7`-gyRa?Lc_O^#;Zbc|PM6a(1 zs=2#|ShpA5%eN{1+XJZjN)M5W*}Ij-bae;ToQg(*HTs)6TC97Z?nmXg3+Vo)-iAMm zquDl%I_Msu-l{)Vt=_46to|6cR3jA{2bbz@HeVcbw`ZF3=YQ)i1&qhbTF~?Z%4S#RWRAV6i%;~jrroYaX`tzqZ znlsfLR$AxvthgU3HmX1XtL@17?p*JEciY`Kg3=oC)R%-qGySIB^$uA=ozA7<#zIr=XOpL zEh`TZiBF>+5Jf95HijRdr--hV4@<*S==Tk{58^HSd{%sBA4y zLUWg0=1KG&bCT$lQRI=%+eA-`a-zwjoVSRr7VX54M>}s4VJ*gqC6965AR1RJ7Ntah zb6!`>H|$A?`sTc*Xm3tY@*>Ww<~36k>rrCAIj<<%8@8gvesf+{v^Oj)iT&ohWQh5O zMIlk&oEObYrX&`H#CvlT?X46Rg)gAbn-`3%2%kq!5Nj?D`@s{aqQA+C@HqM$@!-m0 zMfe>0tSN^L;j_f6E9X2z?7H$!1@iLF(?qkY;8Y~9;5>(H4I2#E@cs>bjJS<;u<(5heH6vy$z&iOMRCmfmtflv%x|_--YV_F6;68(fhc+%S!w{RL=uhhVMl6 zoRBs64s<(DjaFDlZ%6fvX^lnjHdN0ZSp;uIx9}vA74Q~RPb}F2-;3&bCi~ybsI2nZ zqp}3nvrsm_8&N$eJ35`nJ38xmZgz4ylXr6TH0|tkA@A(yx!c9*O5Vj;!_&8`(~Z2V zqbGMar#pE!N6+%^P7m_#&OJQYdpJGGdpLUP%c^}Ps-A%?-|t3c6V}V=P2S5F+|9(f8=<^ds-@4pCDk7@|EW(!gEw1(nuumGJ;ze~Ol^HKHHhT~N+4^{6?{uOi4IrQG- zgE0qH&u^47ntYU_`6&5v%tB|$*b}kh zpMYxgViH#T<5BgoB-17T0Ky` zsjk99t2?Ukqt(tD^3{&sZ`U|$$=5h~`(29Bj4$04B|d4I-8>!p^!gWGgKpK@;PgYs$VF- zv?Nr$Px-DjK{cKxZ??v$`atqyYlJp5@_JJb=|M+5CwampqUuXM~|g^-|uMt>=EZt@<$xas6C3MY64n^-rHmN_|-wxx0B~#ZB(;p@=L6Rsuy^` zIY@rMQSVS*jx|vA9pwXA9aW!FevR=7MD?LH#$6UwuUcc@Wl)WS zsIM1?YE(sI<(fs)T$;v`WYMEpG>tBmL^TqmQKu59Mv*icRUFkwuEwp3p&HxOcvewV zqrDp8DuQbKSL0uWQO((ETr3vV7_Y|5Vo;5lY8)*ZjUvy6Mw3U9%bG!>uh~i2=sy>t zl!H7w{py00a+2quw_SizF7ll8zw=YdO`ePXc|J;c$aB+fb-XkOKM>UzU%dS{vRaTm zgRB^2;gA)Tbwf@2Ph_Q*m2+H^U$15VO;Pgf?4kaL-fE=!AN{z}8gN94Q7&%(jcgbi zaJ=+yWO0>?`$d0h29WA=9S^W73yYHWU&^K-H`jU-YLZBGIS2ah>W$~2JtR?+Kwg*g zREm08OC)gqw3o7SkVR56YMP^UILA5?vUt#&Npot-+T$eahx}X_I)1W#D8Ln?>}kF~hO4=%Rh`?yEX8u}t5MR} zs*CEn9K^BL=&HwkVi5O-mZ(N32iq%ku)RhHQ{zz+5AWm%96=N{Vy)fl8k*fOHJ)@22vk+W{(Be*|zLp2hqk+)2!+Q3Ls zJlcc0k=)yRpef{|xL@@_Q&`q0Ts$hC* z1bH+qOV_Ddm{eD&T9wqdBq_yps#c|YS7}u3N%yokv^ZLf>rdmgZTOX1Xf2l7uw0Yt zPvgYN{9+BX2205-SLce<$aGsf($JQ65KlRty0+9-Vj>W<%@R0-8np*_jtYIeAW=pUb7FHWz-qatb{CMbY?VL5n$hR z#$;C{8#UP$=^o(U7h>6Wjbq5xS+wp)19{v zXSo*T+9Zvs)VAu|zi7lomM^lxlsr%YI}K-3 zSGw-nVa}_rHQl>I_O2a7b!F+UE!DNAt3}=hmB{6B;GmVs4Y@2Lt58x)ZNw1~iAAlm zky-E7N4F4VqLI0mSPqShB0V%RcM}If?R^Qcq#B#m?izHByB1yR-i_YP+U3MmYHaRu zm!pb`)Y!~%m!XS@$<^2_bQhru+=b{mH-X<<$8W87bw1ajI-jz0l7*8j6Z2EM$!)?X zbkCXME}*PPTuqE(b~Q1x+$ltYnn7tJpWZ|Ss&SMzP~PaSAR5MIG(XELDBVpos!6Q9 zoxF(|MLen|W-L*VnwZ7x&k|x~tt1~q^r$9gHvd^1>ZRnm=2oC9*`k2CgSrCdPGUtB z;B$AP_wcy_W|eynx&jt?0kf1(CYf9Kt|XJ2_%%r;53z2N@I%tQG#f1I`D`_tNI1Ev z%}1VO=20`>jUwJjl9@|+9+9;cuy>P*bhf~aWKEJOM4n_y644~dlq0rIlDUNV&3FpUkmZM(dcNlE@X1BrjW@=Orb)2M@}@a zV!3b!xCzb9XPOzs_-JOnb1tG6`L<>zz55MiMFT0IZHX0>p6&8eEzkQ4YD(CcLCuUu-pr&WVoftsienMuMiav*#>U8LX2Rsn%=hf$55yITWuGHi`pJo8 z+i1##-B`4UTNsTdZcn6%b-!nAX}%+p-zkk2B5%$&={Z}0=sL|!6(UeIH&uyM)!bAg zB2#rDPc=6`^0}X!1eThc%ang~E;yGtW)~=5Mt^3n>$nN5RRpc(ux@Ijjoo@^I*vkm zqW*kEY?MaCF=}oyuwNcgcQT++_}XPaGvT2Z#kQHy46KWSh?5SDG#8vG^EEM9qRb`Y zutc$Z$!TF4@jWd}lH1U2VHy%Ii5>*;wpy50ZW3{UqKr!LV!+Ek>Z=R^RlL|wG0 zj9*{0DNjVKXrqW?JWq%x7R?sr-Ik`i+XL<4_CyD`z0h7nNNdS=w=gx>s-|0)qf`&A zL0*@d8a9qxOOr^suG^0#`lIA6O#^BY-4Vo7YiXLW&q>69s!u+gx|U`bc}w%DGYoCY z{S%pF6GN#!+Klxvra4i$V)(x1Xlo*%wc;e3gH z>6}N;6BDT|TeWlFbKYk;nWNO1IB7AaEwR^PSnkA9XZKy=`n1CHGRAar6|<+6`GD9x zt<1;H2WSfM+q%0cq+YHfCABh&i`2>tbbGUx14)D2Sks54Sfki`v3#O0I?x@8#_+wd zrVF2sHNDw7)^z3jVyW%wwl+nHTGrYWBc2(y1zrsLA>Z8E#CRV%`Mjbm4`JJ(L}JTF zc`)T6?kCP*;;DV&#IpPeNAFW7(u-nkAukfmM(nrNCJ(WfTAOnmk@ty8bPml;1iIGd zl=CKgc8c_YqnVFS&^K8w%(m~KZ?V3x5nZ^jdB=Gh{fti+Hi}kNn5{o|+L+vYPa8be za(Qh`7B2#gAX-x!lZ&`;XW8nMliAC{vgc(+&royLNlR3(Hs&|qRy z^0d^4$=jG8+%W2RKe%m7Ec>31_<6Bt5td-P^K?D!6d^@ZE=ZibA|@{p@~CI4BKXu5 zMp@@2n~OvSOE%vTb1m8Y%nMU8MqUo;@csGON)-4)9HFd~^P~AGe@is9WRsJctll@o zN=r7M5=|}Hlo#2ScmpLLA zi9~l9y`M-;ZH?kFwKZR{kDn5|=_|CD`GlxU#mv_%6*HHJMpw*SAj(`ZK79fGkxv)n z7k)&Gk{9FCpSbP#CXH_?mQ*|Qkoz$DF!7+;nLR{#dW#rS?aXIvtGG{ZQ9eicGonI$ z!G7(hd=5QF`90RRGw+hOGanFZteyGT{Q!NGBXXD+M315$5pk-W*-HGOCy9UcBzsoe z9AT-rIZ7O&;^q($h>G)xL+BH1QQSPn=hTzjkBU}ZoYLRi_C~SD+M73san{~^$oIB4 zAMwrY4KdH~xGc_ZC_-6#^9*@=vxAzQ#8P{P@^;EQh@*8M`?#BY53$!?pk6W9+MANz z3A7xM3fr4E+4r~HH{A!wOPG^HODjR$NwhfMQi8M_-OKtC=0W0Xl`y-ByH&zGz-Ky` zGQ>;lV9F9lv4g2b1Vi3G_)gwYh?@8|TfO6+Lf=N;=4hQFeL$4LYHW9w`cpQ3VFy#4 zScVk+%NgL&G0nLU1*^o(1QrQ_%; z)Ri=^;*|=Mi1=(J&1pVgl5ahYzRcF@lb>-r@*NrtZAkpkj;0ZDLOYtqUOhC4sH4xZ z)p56#m&Ee3l%I1;c+V2yu7p>T6Y5QkRe zlg4!SdZ0bLo@h^EfEvELqrubOYflu(?kv}2+gdidq%k!p*CbkN4USn|Qa!X3wY^zy zObR(Z?@kK3oY8M%nh?9SA+b^$viBOtHm0@Lls#)rYUAn6r7qfltxB6jV!M`RIT3Bj z7Nt#nK3Uo{;}fOvB5sB@!Hd|jqvH-E;u?{g<1BL=JO1u4?mow9$5yR9jn6yG7c4;A zQq#_x#cYCOk}0>v2RWI&>qP48X?DP2reG#Iju`|;vkzz&_PwvykJzYvy*NJC3GK>~ z-msFwUbyfMtPxQzeDF=ucK^Dm5fk-N+e#8Eqf`68Fu3L<7Xvq^K90UANgFmjif zDUlB+v%gcAL77WlhR-cU=dxUeHPg{J>dG+lFdLo6R%MvYn1{}0mc!#aG{V-ISuD@a zUwL-s3c4BdVAI%YI`d?mSvQsPH0FWIP`Z^PHcoRwCL4JO3xV>~LQJOIgndq89y*phH+3PCiyXUE z>>onRJGWpjTRTnB3RoF5K}El=z|1quYd+l^ZOy!K1-5OC;<<$u=KHW4<{QGsb23ww zjRsb=#5uyI9$SyLY}F1c5Rc_#%59m;uRtl@N#>Zvld5Acl9si#sE@~vBn{;sOc-^r zM+uv{%<|WE>XPa?R8cPr7CZ%*oo|TcM??0nBD4K9&{|jlRAgqpKAOm!eMLT&aQ!bK!%GxwoiB!Zo}9@U?>`}Z z%6QXdw$>QbW%Mg*D`S828Ttu%WvqO@LNAe5X1hx!9TpykQCW|qBfWsWz;~vj_5>C> zmHF%`j?xF{Ir3A~oWm02DYiIE`4pBQ$0$ESo(}7q%G4fYDIL}~AF`)!lD~yz$3bdj z;gJqYipSBn+25D2WO*B{!ZvTBFJcK(1q++E(Uas=s6C0EVZBDu&Y*9zReHWda|he7 z;z&<=2$iKrdeR;&XsYl%yI7kZ3!2wBLN8PE3RW#uC_PPj21|`ytUXT6(^zWUPkB9g zdaNzhqld7JIf0(w7~D%;dTUFV9($H2*|YuRkC>|1&^(JCC$CEB5L$($s;u3Q?#F6{ zSx1(bbtJFK7Dr76zDe_Wcavwp#$pXB8;lI3yUieKGGO6SmCue~DFYTRRaxH65feGK zD$Bb`kJ}lL40aAB19KI_*m5j+1}sPRvEN& zY)3_lt;Q#IqI>yVHLPLwqPxkfvAoq}JVR->!g?|9~mhM)t< zHJZHvUCB~B)+Z}babe^6zE$W3@=Sb(W{6|~l8LkkU5>>_Cei|Cw&MA=k>tbd%+Fv{ zHrldH$%O5L=8I&Tk_j7%W#~=R+>BkuILe*aU(Hy_@_Hh5nXt>4h)yBTWPA(v6w`(M zu8yXlDa;jB=Q~ED@#NJhbwV|#Ro!S#t2)cwOlB+*W}vbv$xNDs&faRGsfx z>)h>RHoYnL!6rps-LpxuWv;C?5I zwJFGg9l|ZF$W+01^6+srP z0`{Q?u@=aJ)yxcz%?f8KdVqQVEZA49WY5--);l$^)L4ls!fs70J655xB(I4T&NOr~ zxn?&eqbvDLP1db&BCsPkfNGvUf;s-f=mEYt0(*hSvCpWZFLkgAg9U7H)(!6r+JN<*PPeU*NLK~neeRGW7NV9 z;{lGNXWI#bIyzG=}YLd1_F} z?2pga@7tH(vee2_=TFtj)Utk!?RE9}Qp-whWvT5;v4^g1U%D@+wldufQ_q_0mek9- z-ue1xV|)FT?Mr7%5hfa-SD!DnuGH9GYF&y{(dakrE7k9yv5Dogn%~eou^-VYHGWY8 zzQ>Pa;m5~P>(*~6dY1eh>XX+cmk)&ICuP|o)tqV_a;fI=Woak%@6)NViR5$PM=tVx zF*J`ai;vt~_rAY|;viie9Vykn!;fL%M?q2qi&TFQwJCXs=xpk&`Ozz6S)n<6`IPu^ zEEKg!SB0(tMJ@8P9kn#Y&Dogc$O zc6PeM$nMU!x6>THVt4s*EM#e?NJ5&&SNttM+K^%qd5lcSHpMeV>^#0~R$QJ~MQA&+ zw=-MdoU&0bAMFY{jMZUm#+Up4F$S5+C ze^hjw{iBqQEoA{C`xjZe$O1<8FS2%#1&r)pbS5*H$jEEIL&sR3Q}hshn?C3J{OZ&C zrVRGmWGxfqdeXP)n=<~7`!8yniUX*gr2MU9qb18oJ;icy=ad(go?`N}lFep)o^UzP z9IR8HS$6>459?8{euMgz^1#Z6${(vPZ8#g6jdkUz&5zb1PoRZoMYFO__xAj#`Xq{e zrI=TWXQqBs0q!}9iB+3+EmE%ct+2vv_J+V(Y~*(Qo>Lic06dF$S)9%2khu>#XmpU&R1 z^$csk^`j?YT1q9jPSq~o872^ulvkuB1>-0n{hU&Shn52qQT9$R{kLo@W zOPy~k9H6W=p_x@hFH*~3eiGFzpZZ2cxwh5E&|OyNQ0G%NZ#suMZ+{fyQRhltch&4Y zTwZg(#&}f!F*UklWzL?Cqt2wxgna3ACa;a|sI!;An*5v{okKsyqxzWYY3jWBeu27k z%f3*37WF*~a`yF9zc$9Bo=<+HN1eUjMt9UP(|Ie$`Op&%s{r!U=#DzlI&WpKJPZ9u zkG>U`&YsSXo|uY45W_i2jqVuBIf$iJ=gp5kSBf*EM7|Q>G^*3S-Wve zPMx6&SI(Dz?sV2FaE`7$Q+oR9?daNQoPYj&sm-OvD2iu!uin?TCGjd0o8T`)Tf>`oi9D#i`mwuwyU^biilQ-QjERZ zDN0&C%4!8M_87+4D?G+t)iG=tZSR&bwjHL%VpS`Rv8^s^ld4m#=-twS%nMo*)63B_xl&KN398vC^}v(Rrp#5TXWkUmJd}Fu%}~uo$s)Qr+QQCBRV1&#TwV)D zJ^z+yD`xQYM$igv%^aWJ6k4O2->SmBunn5bJXckoY{_U_W}>X6H`+Lw7x*{JqK`!V||`_O)9e`Zl-YuO(ifS05!83&*P@sgB<;6POK!SXN|gbrq2 zST=5h(IL)YYa=!U9g3Hvtg(io!7V{s<~!)zTJ%8!i=*#;%-65FkdZCxiRQiX6fZYHx|9s z8EZZ3ZbdaCu33X|=y>MGHKQ;d)tt3F^d_L1xlUmo;WqSkJS64Ohi!nF$PBqW{U)N5 zoQaM+04Jf7ok@;711F=J?B%N%sBEDe~kkw2tt2IPAp|43O5$lqi> zx&ZqDc~mYy7h-!LPs@eqBCIgvfw>4>jEAH=GZ&+>d(d3V5_BncBAU%vippX^9-eog zcj6@}&(Ay2Wq3)-BXk*h7q$=b6uk>wj+dl7NSC84ur85j=?YXM?3&BC8(qmfgJw5Y zq8eSF#OV1wsK(eQGg7|_UCl_lJX%+yYZ!@_r|TMYt+NKt*XiWb7(-ucJ!99Q>lu63 z+{StoYMJ$<-GFXn99peYnf4d4E-CU`Rkay`y2YW z^EXEx-H)RO7}uAl_W|@E^BVF1KZqV;wnU!chtR`}*gnF4vLA48vFRzx1`PoYmUdm_*Fr%}x)Xy)`8^jYQ?G^6?~ z`W*8E@{oTHJ0<$Rcz<&XKk$Dw)=D&z)ra?2i zFQG3p@1XhJmr>0l$hZF$RI>^4{C^dFjoAoA1b7X7otX$l3V0oTgEE$bVO zA`85U%9d60(Ql!$Xw?k$+oIXKG!fEu3bJ|8&ID?*b&Nzy^a2Ea0IZGsl zXUU&2A7KHj7!4nxA7f3d2o4{kpI~3C$PS;NpF(ccoIPAutaCrLks!{YvdC40h|f^j zfgm}U&FR8x#G z7}HD(p%Y5zEdkOXB=nj9p+o2`3B5z;B@lx7o@Y+(XPe*`2;u#|S`hd`=ir*~d3b@ygEin6oB}YT2UT7W&jCbYIR$p4pK0W zcza_k^1ysz@{Q=o2MdUfH^WE)*npb5W*%t(HYCE{j3f=gM#RsXsiYCum=g(RFlh`n zp@y%SO`3p4{~JTn6fEQngi$4hU=fl3W=JUljsLeQSut3`DFE}Tlz`1RD`38rW?*y9 zNSKGEIoN{J66R-V0k-6fhVd>`ZRRXS%hafsR-mUg%=6M3^z4TDU)q3eIl*CGn6_Xk zr#;LUQwo-G>cu=VWneo_$Cy#39oU}p9Y*G~2g^AdVysR%Siu>NK;%jVSV_&_l$e-G zumfj9@`!!u09J9fBcBMEDzG}ON(+dCsRnD(>a+o|GBu#*I*bnL2-bSOgQ%fe&=VYu ziNvV`J;z~&nNDD5PIH)DrZd?d)Zsnv@oHqQKCg+9BJQqdm1p-fvI8ebl1R1{k-CT2wnI`bI0!6w0D5 zRSIfnSC?uFYHe4SY6EI*uR)h;4SH%$T?$Q-ajU3HwFEsir!Lh3G*fgPz2;G)Y6f~< zPK~Mr)Yh&>RSarp&onAEsZ66PM4u``^HQT~3TkUtqiOQ%i#Z9?i*y`o0di+*pk6*a1!PI$VBT9O)77bs>ySEK3-r3+fs*r-vBQHP?BR+Xq%jib*vQLjQjU_2&K zui}Iqcpr^ab}zG1o{(^{C7fA z+a>B%JA?G1UbT~mzMx*UBWPv;^{OS{j_4QaRg1wT=pE`+i@?R`BkENP!A0mP>QxKC zh3GHpRrA3G=r!t9oJ425L)5Ewh#J-Qpy$`ssOEv5Xjh}!4m3_kjY@sW$RRZ<^(xQD zt5IzO8keL-wKeG3dNr!8K+oT+Q4w>)7(D=u>Hzu&qA93Rt&)NUp+-gI595_+QU{|? zs7tMczCU`$q3BZkL0O4Dawxrhqeis?+!t*{jcOmz43%nB%RytF)Ts6btpK1#wG7-F zZAgu3FVM64YE*lIp66GiQlIktzZ#W#m01JSsFs4pfvHjL1};TAQ={4yv^sWl1Yu~SkMS3HL7ExE_Dq3W6?*{rH+Pj3{hC>Qa^-p zH2RCW)KO4=NK}%#)DNH>g}$RMbtDvPQm9KE0maG`>QY87S(!pz>M$sWM}5lZCp9Yd zszcGX)TmZRUFr~UHM-aZ=u!tqE$U$UWCMy?)Im@VMhl=KHhO`&6gmM~zy(p4BA+7T z^P?_xJ`^)As!N>*<$UxGb*XcqoQFQ5E_Du+bJ0`OrOt+O4*H9_)LBr@Mz2wqIx}if zXF@km6@BV7v@Nx$Q_!c(YN-}= zGL%!$&eWoQ1m$G3Hnpgep!_Jgnm*&GOI;-<#4(~5ki`&WZjK{T4JX zQeEmdpt%>-r7j15lUyEksb7PaqqC?>T?U%ZQC;d%(AYZ@9${lDQYEgfHaywed1N3f- zy40=UZRjlOQn!G&qRXgD{T{pp9YRRwRG&QxTYe4f(szspzF#fZBP+f{>UbKTh zMP2GC@K5Lz>QYaFPoZl(AD%m8eBM4&@276}70xpgfKiqZajO)Sn)O z{unxr`qLv&9!2+2e|i|oBSbR4M(?4hMLh^UgvO*6r4IEVnv`0Uy3_+`SZY!CgGThK zMcoG)+u%EB4etfxt<|O8idxiP!MD&X)S})5 z|BA+;7WD@BCYp#^)a&3IXeeq?uYs?lxu`|G3ciL$qZai_)Sq6V|0=qV`qRr$UO^{P ze|ibZ%jin#PcK4w2^}iapFU^&eAJ)Rs9r$lQh$05%Jalvt3N#pQ8@z@(H?<`qRfy{)P^f z=}&4->Qf)1VYQ(5Vbq^Kh?)~sq0^iwRUQ;QP3l$oP>faS!g+e)UGMJ7{#>P0Ya#>^>5sUyLdY7fjM>Ps+g5$6(hCm6SkbEzei7U)6FrB+a^!R1_P4aFJ^ z&ZRa`TBA=D(kqQKs+4|PG%sgV8I)4=GG|mfC`PI}quN7hhaTsQDu;p=7d7$&Fw1OIW2Pl>3iOwssXECm(uOCOfyav>d^B!}mCUS$0pxzuUE4840!Vl=xMb6L( z)Q=-)=nU$|kuz}CmT{NJ8M=b{apVl$K>av!hVGFwbf<6KKsiGXDBaPC)mCQzm&o5tOFQz)Ax z)8p%r0Lxdo^P z$DMi(s0T-@Cuf%#b9OmAiR}Lrs#Uq8;Z z?AO~tnTuAU-FhDV?UL=IthGIqdC3k@*4hEe_UJg;t>;78Az2V*tp!l#qZ27>ErhZF zT}fGM5tN1KP|8}1p)5kTx;5N_UUduO9izmxBa|iRVoF>)LD>-|2Y6;Sp;OVa_o}~tK9F$|x zztn(^hjJWxnYzyjP|TdK?sFm(w6&-Kodo4X^a3@YA3-?@ec?j9Nhd@35qbnV4|>Ce zj8Bak(5X;PLGL&iZ_;T{tQdYUy&p$S_Hinq5UI6O5QIow8 zydb$SYO+58_1&n+{uI=Aqb7S1sP9Hi_F_=qjhgHwpuQV@gFgfH-RK+qIjHYuw{Q}g z$8L;&5p5B_1oho$i})3&??zk1rJ%kWZ4sA&`fjvE{2J7Eqb=g{Xoa|({;$!P^zQx! z%H_##qb=gMP|RAdE#e9&zeWGj7I7t%E0U||UzuDTEfQDLM^B3u3C^3LuU#8064yex zCb=$JB(8&UZE`(*y*Anw zgeI{w;|HQm=>aHzMEjVCP3b`>51^H38+-`LgXk<;2p@*>5W0-E!AGDxjHWY%-lNe@ z_!y|yMmyo-pk5mzFP;GP+Gro$x78uZ?!XKY@B}v=jar)N7-K@Gn>eXM!`K zJ{@g?Peb_&x`4L9XP`Wdj-YMuSt!q-J7^nx4$8CW6m#gk5G{l+MBCsCP@YEz86CDl z=hzBePt{wL}wWr#-O8&Vf;#h6HrtVCNF%Y+z5)Gpbg1Fja^Hmh2D;U7dVj^;B;b=<-A(Ri$KKfwa{s_v4XeGUgB>EW2M`$a(u!sK*%ExFiz36>{{k&KB6x5H?9gF&> zSl4@ozth*7(+zw3XQ1AkuGr!K0qV`^Ld4VOpx&I$L_)0r_2zWKp8o}?H>VCee-i2# zC-?*E@Z;1FZxy&|!CGER@g>xNHH`D<>(i;C%?G1ThqfS8h7KTS`a=bMeL59jIjB#k zJR%+rw4U~i(S2wegL-z#Xq$j)J)T!@3aa&ZYP}Ft>uE!q`E-hcUY*RRQ;Zj;HCm58 zosyteC-dp($!QrfpH3cL0(Bg98)MUw*mG=jn$&zSA9_`lQTD#u7;rz65ADmJ|MF+n z{hJ#|KIiVStaA_tcT~lvYpAjXzd=A zTS=ZnGL~E3;^`yz89z}Fds5f#Z@K;HyMDia|MUI^pZ|vL@7mRoeC7S!`1ybT{;ic} zGU?{a^Ly>Rch=i2)w&wtnN z|6M=-UGM+K&*%7OPAB+w^Y{Pt{rj%-_rLq|etUUmwu|~C*XMt}?i1S3`rr8ZjrVWk z{MopE{x9(lrIbv%muvms=3jDLC9Dm}uV0q_k}t`h8$ZAC{%xE;8`sZ9{_)lJlds~R zoukZaHiLvnANfZvOP7+aSqoAkecaP?S-Q+VVOE5E;(gZ5t>)?bT!u9xxXiA=Ne!;7 z){$B8jNRIBt}f%X%=uu3HRH8B8&E{lkCnm6a+{d9Y2Dmvp1aTG>iTkSwIRfBwItrh z3~RaEYM#3{r)Nvzeavz)oU09JhP4s&%&q3Rd-Kt>A>PMx_vSJwCEmvz8Kb$Z!soer zGhvhw?_&lNt5RhZjoK$xGO7TrYc!sox$wr(PN1y>J%c}y_TSB|_H{Ww{DppF^XZsr zC(FEJc9z!hH>}OhV$K#bV`VwBTE*X(%hY0)k8HWAFSDH`)rc^Eys!{&cB|_^0j$B%)w$6OlPh$wI}mE%hXcG`^?;B{tu!OSpyr& z`H|&lG4sd2=KSc)UrG3+`MX?8A+9p3&MB95R1a7vsL)~@q=uA6DjRb)20w!CK4puECw z?r#~+uQ%tFt1Qb`KZV!xi*qjvR zv@&O2mO;;q70vj?=Ge*d>$$Sbq~rQCkB+$_{Ox8xDh6GD=Hwd}@51=_qX^&jc$aIfQCt*wla5-4cxIyID4WJlnEDvwUWvsD$vJsd0^5pzP88dFe z3}_3sW!#h}OH4198QtWfgD$M;_?^muaYL`G`wEw+(vZ3dj*_^VcE&t0_OcL+0oYB=IuaskY*X5ydQhBOR zNe(No^%=@}eQxq%IkHdHXD+9fXUn_g;LZZ?hn!s=FRz#5dxzWu+zH$h+#B2>+$*x3 zqZt&b-^V`kuk$cB1HXD7`TBWic2QSPOIrDaTvh%mpOxFnIpiyHVfnFqS?(;SkzdQT zOBlvBr*MwYNexGr%1d16=-NXIgzOVKBeeAzq&7Z%Y=lfmcgs=Xd|C@Yf-F3SD zUc7eyt&KB6iO;-(uE9DkYrne&J8_w9&^6eZs}n2IHQ1J`Gg!)~j9Dl)h%2<3ZzKI&TfSQo3-p1>5pjS7-s~x~-(|$)|jJ)?l_0v$MTxoc~>!|E=h^;*(X(RibjZ zJP}2F0uo{~Ub8+kx%=W;sEISWhF8@hQ)JujaV>P`J=PC*Ep+6PstjC=4BrRr!?=XL zGS6UoX_S7`DE%r8r+g>neKjQaadjqjYj<>I;JhdU=OH0$QBj|46*YiNKWI%~j#tl} zQ1|n9DCL^_vm1A$KHeKO1M&beE(7Iw1LOV8a!e|9o88rnu1eQtckRMG9?1LJqbUsJ zUJi&nZ~(mqJVl?3r^Xs^)qtK6BYz^VG~|v~g4!z@a#ev&9k<&<&+0{Y{LABm0UZrvtzoB3J9YxT6#%d(Rpii|& ze5yU@_2->xPu{WqT)BM0W)QCAiS~%|&*#~KXXq2|PHzD3R~K{s4&W*UyOJL=@t_|6r~`%sroEAFjdNOEZT0{j79f9zR`9 z-@VOGS8%yz{Iu((f?w#T$!W=0uHTv8>HHu=OZ?rP=#jrA&e~4&I&k-zg6_l};=R&7 z!zsi#w_5T}_iS?8@LTHWW%I%r(ulr%p^A&A&PA1H-s5j}cD4n{GQ%_Vsky?b9n7c{ zx_8Za;0{#E^K}K(a8+{;-Gj=wT)TmHWP4H}lr(crpnFLsIFwhMIaGJb!vFl(3b7j@&(F5}!+OVuu8K5y+Zo^y02^#ZlU z6w#AUXn&D=BykobaTX-;nUVFBr;~71fX=Ces{`m7OX7V=_+DweAKnW&SKw*}%KO|m zT7d5TfvXkh%nI=?2kviM`fd4Jf$z{4?91O+m)95a*E2c7b)Zh2jZ@gpP zA@8L3sAIfi-XZU(->-%{q`gV&SCe?hyieXs@0j<=d+8nXK6x*-v}O0ryX9TfM(o}4 z{%IHX`+EPpW2K-Oi@am)Ky5(YG4GysAMcoVPb-gitO`tN{pHT2B;E(DA>KFdp%xbJ zoA*%bmG{kisO`r4<~`K<;~gsk%@@7yeA~#wHuA9l1P|LNQ*D%~zDlN2g2*JRZzfZ% z%bVQu3gOL#k%QOLQt6wqa#A5&*|EDFS*_#P{a5bqxEpQPxc?Nwp~=h^dGpupZJ9N> zg!dP-BPfrMivjN3H12IpwD0ro<+0Ow$K2-%*x!DtcG+RObAg`do6AD)h@_K2kk7=CE_-WYsLJ z5@a0`eN)y4%2lmc>jgE3-CCcgJ{kSXN?le4X~tRl5_&6nb|sv#FQ&IIxF1;<^xaJ3 zHR}pZqd$Ob4AVHD@9J2=wJ+!Pi|A1mm)EG7OFJFx&)I(0;c~8hIP+gfuOF}I``(Op z2G}oI7U#k;Ufr8a0Zkbz!|ugQn!&4m$>Ct`hMDyC}%+n05*4Yi?Xu+tGF-7sPhtagcW`;#y38hdg>+p}P*vVAnMN&+E?c+}zH*-p=rxXMF7p&*pX(P2dbSKcllco8cRt+s@}N&u~4H>&|U;gD=l; z=eC+dHp8=7oy~A-Upa4`!+M6*f~`KN$5>yY{$c&edI_DY@~?i(AU(2dv< z`QCNvYBeK%KhXQI3BA6o?M?W_)9CeK)lcIWPo>wJ88emNIwjtLDfFmhz^Di4ubv!d zyFO^D9>lq=PnBv2@mEibzgo|AXXcZ7l^)top!3uGF?C#>n3v<|)kdFhN6^Ry{lYcO zp)ueX#?|y|n3v|Ksp7Ksh zBOL}+-q84bhk(Wr`D6!!&Mu$nAkf*> zmbM-o#5__P*Irl8JaXk~BXX6wTKjXk%G`&rFUo6Gg(PSlIb z_0^1?7OQ3;wMUpu+OgJJI$cdZ*{)o!DP=rmLajmCg4E+PiP72RGp*xtc4_0yVr4qg zuVo%JW?U23a&>&Z)%2ZRu4wH(&Ms{_mGLQ8(sy3@l(pbGuYAh-Va!nMQ*O^?hGL&` zJ1%FJPq~b%9rH*FfYQZAKK$RqhrdcDboZPZcg(5Gm`O-X?x8EWrXn|0MG2}ZN>EdI zbt3Cc%w#8J#T8u2P95k?fNl&}PIj7rtfW-AoJ-lMlHPb$wR>?+b{dbY&iOWCP{ zp0>BWBHx$+&fwk3PUDc6%A@R5PS1UM5BP^t)7Z#gc89hHTtum9Oq80&&>M@a)E=p6 zDYLdcl2JQ)qj_}Un| zXeW5m){#dkLG1`l*{Ll(YRW`@rR+2!%1-hcWv4daa47DI%1*=oDLcu37I7&%wWcQz zS_oI0$2*2a32IoBpoT>WYA7hjQ+86iSO_kNd{5cw%hE*_MfhbIW3Bw0Nf()qNck_N+@_BdjzFczqaq*WL!PT4j zq!i(9-V0O$cTevL%I!zf>%mhW1-i3$r?1Xwb~TKAe-F8RMZOGhqig*A`6KncBSc9RmYB=Udvmnts# zf2OVa1oalU7pTQn#Al~Q>n@87UD<90~wboFSG2BhmQYB%Xmt8lTWQpTxD(O z8w27hYs+N}h^wrWOJAs~tc**K=mdK0;#zAD%9UMNMrMy^mSwTpt}kOL^^>WYRmN4; z0dzmf$;qRc#Y)IjL!(z6R~gmO=+(sa)e&@mb7j?nN-M6lI#7F@>&sQ9eaZFJIj*nH z^o<2}Wp&}w=j2+`v#rm`^`)m;pOeok^Go-L>#IkU-+DmTI@gr7pT#%#qMyYAt9u!j z*(a{7Tr99_tuL3cz^<=;Tt)%AzWQ?+1uRz_z-273D{CN^-bvR~Jy#x>2Xzn>D|zPD z*C3wE#^?3l^t>MA30kM;A=(GH9whJE!?b^l<3||p=KX>Ucz1($^FFhw-wxhRUcI05jqU*h?a%4`f_#FPL;nre zZDcSEP|eDI8+dDS3uvBlbGF|?R>3PG-je*Dtb$iYG(-8-j6}1NUrq03G7Mf#|5~ma z!E0#EH+~~{1Ha`udN+^@@;drQk!A5GWa__&mbzn%f5`O{@F(PDJd#|C7l9Y?+R=>3 z+Q=&xCPzR&61;@=7^vriN7Ek8FSrB@w1?9>f=rj^lL_)zUO%6#ngQx@jL!v+r9GbB zIpA@$Rv$PAJcsO(Cvu$yo$Xj^|t#~^5EX{0r8h8rr zUbLryr}0Y{CWnv{lzMn%3AOgb!N`M$&@N_tAh?Kj3B3cNGH%aMwUWgFNUy8N zLaG&T6%y|L$p2Qp*dLj9C0c+LF;*fSTk~O8M*AT(Tk}ELd0!-JYd%S`sgS*g* z>Nxra>On12RQzOA2KTLJ*V4YMZN?ZNEe@qzW$a_xsiu1UedF&glKs^+Bd{gB)ttxp@6Un1z99Sp*W-&DV6?yc`T4WU;eH|&g zSOZZ1hSk@tcdtjom=L2EJ-=XNi17~YvU;DC@|B6*&x*h<+-Ktk#7)rq60SW!D}f|j zd+~2~bjD@i-u&C0S!X=t_WTQIOFMw``4?CN3&6ubt8FacS`DsdWd#0``h)-HgK*sx zZky6tLoJ2dI<~f23b%D^&9xK`>)2XsDID%TFb~?}pszha`#3x|kKR+@lknU;dVdE0 z1kcT*M<#uG*Mm>PrSj;>b?=7H-bGJtdspPQ=4riyk$GJ2hQr>$SU!74B)0{ zANj4-_{_R02mW2;w&ry;C#xLTysmQL>-a4XMp)H_n$-Zzb zcr4Vd*g=i~k72wuyUfwx(TumDZ}x3>rfos9Z(ApGE@lQ8+7;ZDv6Yq70IaP# ziQQypaA(Go*=2SDcVbM%TSim3%%5)6)~Q_PPq&)uG_I-ef<^SYu#+u{yfx#!a$Qeq zsa42(vpC9uyhE-lf0ZlCVU3KGFUxi1Uh-zSuKI;Bg>qf>3*!-uO4Pn(?P9sE`h{n$ zhpd>E%Sw`m1{Nw82=LHxItM0JMH@9_wQVu0y~> z;JQ0-9SVBdPw({lmSn4Qt?$KK>!)7VL#@YJU*6gitlADUpS9Yfa)Xw_oS!;(E;x6N zR$t!#oEzHNzU<3Wm&`nR-^7<^ zrbx-zppb9W(V;98c}Q1>_Fz05w%9m)`Ln%M$NkC zD-m@D^{gpr{Rn!sQFf#bI=zlO%aP2dQS@qf=A*zdwAG+8 zle3`;tOk`FJ!R>s%<=R*k!tjVa$y>htHWKapQJ^W}Y zIF)fbcP#AlXq#@XlF;!9+d6q=4oKKueDvXuT^1*z@N>$2MN^6Cz zZ{;whFu6hibEgZN@<01O&Wiv0%=kafgks%3|Hm0z*6s6u+>Fb*eFgNU$NzWJ_&;t+ z-@1MNkDG8=x6l7^8kcqZ{2!-sS+`H#G=GsU&+qh1Z3*LX{C>~fHe)=N`_dd#z8y<%9J4?vcMR89W`|PlXfESelyygO z>Ff8Yc>1|5*aqs_Q^iKJxa$n(Nw)(%Nj!`h&>n2hcxap@L*u*|3SIAiWt`DU_e0`r zBTk&&;5ZitfvyARXg%o4a0b`MIXw_`-8k0=fUYN3LVwV8rVQQ>bQQXC`hu=bS5%+4 z()!SM)w%+E$2HlTzN^@^>Zvg2DMn_6T2&q;n zOsN#%_=MOy9$HEji{rs1RH{(hxALNzzGyXz#ZdH5S%q=uSnERF|H!Zi%3@aL3Dh`D zVhxWZR_{n+-Hs$y>`0RH!+E@VK{y{gJzM~$d}1M=)dpb=j0Lg!#RB>ZsRxo!2V_2! z1xNwM(Ay!_!#D%_nPGeS#tK;#V;;CYa_({Ts)H7YYN~J?9;*3{M}(@N9ij?)b*O=M zICwa}u>BL?y3w2;1`NTx#&DQC2{&BrkqP-nk9* zZK>0%zF8iuNLe1NQCS|WT3H@upox_8DXRDK31y@ijI}A02f21Rbx9Ixpp2y+iMH)= zv||!$G>)M+7A`fOb~KbR@SBUMRx%2tLM+td!bJY}ZRk&6c0w1hbFBZ@mEJ>C zR_GdTqylscuoZO$Zj9BRZ;W-HZ;Tb6Z;Z8`Z;Vx*Z;bVwwKld0H*qx&+9Ji~R3~_l zzh)i5?$l|}I@t_tM(u(JpjcC|2elluW0rs=R5iE-y}Fp%A3b=-AK}qGs0kwPzCUvF z`|14=%R+y~_eEZRZ{+^>(!UR#-d*7y?rl9d5MBRn`uAWnNa%HrR#x|e+t>%RtagIp zUZHK)z2R0+yK5bk%r(M)iAulEu^}c^|au;o@Mu!^Pn}>YywR z??&zHEzs(e>T9CaDG!5kXw>80#MbZ@<0HVsv42>vQY*-t*e2eBdLW}WKxs#!5T;nxf)SXZ7gv7Tl?A?Y+)f>5-n?MuMxfj1yp>wl)m1d2B9Ea2IW$$ zj0f_~eho!Cr1hCD2dx)%5WU|}ZR?=$TTtubAykjPB3T^{0S|#XnL9s<8b;dOCI@YC zlY`c|$w7PFux3e>*ZidVM@ zTZ2};3RGj-7Mvab&XxR)5G$Es;|_qD;h7r}mrPud{jT)`ZhHMjPcx>Z~y@&Wm;9^q)~b z4*FSqbLArb3~h+=YKRhSK*Br< zOrE(?>*-L=K$Z;1x;H>MohN?*a_sf=Z$M@aymnobX|IERJx$0_xLzhTgMCub1)pN><}#?2#Ano83Dv0MF;n zJo3Srb#Z6XcdRt^XDEMR zcD%@6_!AU8%F0(yf%=%0vXrazI(Gxh8R>^E2h}33q`Dm*QY5HyYLY3voe+9+Dbrcy zP8sNgphkNF(%y-@)+<)L8^HKVq#ymm>b@t0p3r+C{S1IIkgEcz@g%4{(1K1vj{Fhh z&0>v1rKJjF&6A-jnN}dNVi!gRJvmCCYE)|E6-cORRGUx%anq=^S0LA(%2;W-0x8*g z@Kd2^wNTTV0%a-^-Y{P6j^sUzz80$PQ9AFAq&||q_NeYr*6)t=KZd?GsQy9Cpg;ZY zNX6;|{h%lzEBp72vVULt{iq-|iE*DOvG+!g`!TZd`&2sMeT|Bphb*=n)W0X#BjIyf|ZF4AJEeYR&JS;D0OLeZ>K|TMaRPFi$ zs6<&tHLu&EY)hj6*9tYL9@% zHMELct2OVwKiX*ih#aRJtW9)oFAk1!;~`Oobcbut z&eswd@*wC3ht*NST+N=>j-9e4)I*Ux?}^;Gj0%S>p~|E0fm0hhu?oroNEU}tL2w1v zUDQQv33Vm7KXOJ(L%DGXVoE!A9&JFrl=LT(PbAvXt zB|+=i68dxD-CEBULs^0psr76Tl*M6TP*z+BWl?Av=7lv$6HuvU9#YM_vHIh?ald#M z`C&)o#CMUm-{aaFX=NVodmkxsZ)C~6k-|SfuG|~>Wgf46h@`m;T!viU07^q7&<~NQ zKjPXm6hLW!tZGflkExo6w2eeP51hwqc|rL)k1HR^Wj>>nD-Vfg0i(c`BKs_$m+<`; zg38JJAtQf`oVZ`aJ;LtDiytGI?+e|?1!ZU>8+J#^{Dkoer07qO8TW^>D$4F(ATcXv zDLL=Mt1FONS0Te6z_l9^=ciDYBWZt%e0u=${DEA%B7G`-|CnnzvhRV&_NPHHPDAPY zRIbyKQ|KG9@j30u$l9NSpELdu{gaVN-=TLRcv5l#cp?(O;mFuqh9i)%w+dT^!$AGl zbAnMRbD(dDM6gvj6!~B^GWyo^RwF|k86}7xAa!pMjzZGjCKwZ<^l(U&9u5YL580eo zt>I`a%w!k*<4n6Gx?_dv@18Ns| z2f6GWUV8-_$V^aM$PC(<*c*&|(Q5Dx_zoj28pmTtd4+c@1C0QGh2EZ^r{t9J_TbtR z+l=JeccSUnck(^dwdwP@4TW>Q( z>eE&=oWD5&X>b~pVNjF>=O;VRUy#g?a$<@kxgg4pMrd1yGezb!9%l#^F{Ml`W!B_O zkxsS54d&G$NUfVe85C`HgQCT55U&oVI_C`N^?a9|z@2!DPlBR8sJ#6an91IM z&l&s)XnqJ%6Ei2_26&nckM~5PgNUsFWPQ#+%@);Cd?Jl2h@|<6}yx@ zbKV3{DMJ}UpMyRKC5j}<653P-(pOGMqHR8j*7_vM14)zw5_b4uyxIsUU@{!HQAF)& z@?X&%ya~OD==xK5y#Xk<*3Kq(o&dVz%cIQzsyt9cZyZ=iE2ka{S00PBAg3M+H!7ju z413`ya15;+Y7}==8AE%-DDIs$L9G=d*+Z2>v}KIo-nwh#@&6ZqHSBJAi926j+za#K z?q~*$Iw;zS^cZz!@5|$zo^r0@x#rO`dfOOo_hGZ3813zTo5uat(?aHh(YlhdBYK)h zpBa`{TI{m4&XeK%GZx%=(tv;Zfkr|xYJL>$2(FRw7y4eu-UU_`*YJ3!SWR&}1TTF)0u1GR~n<=0aP?c$TqBD?%0#uXUN zl|^8SPWaA_|NnFuov*<5GUf zA_|Np&_efhr^0t{~!Nf|4kAJ7acMhoPF&I+Ri8i3lSj219*z`1O+fZjRhsnG&i z4m2YNoF_&dm_^xHPzny_{w3VUZlHO6Txs$KPxU&W0ZgRwSZ+^krIjKBZ5aaZ%&h;jB8p3?UlH@@+CeU~`@ zuYX?auC;8{xhmzbuE4C{nSS`^x^+)9!qU}i^ySyr6VTUhOo#c-Juhy)b2GvDyX0Kv zgEMBpz1Y(XMjXlM8pmBY%XeBv&nh*BaTRUSG_tG-k%E z=h=C+66WfL>IryOS1sPE0>sIU=p0KlaKo-|yrf~C8=<7GrxjE2B(K9AU z&%Zg&J@=ng67Zx-E(3;H0o;$WOy}QcJ%OQoC-Vu&x6PR0uX5)#8qD9Kj%x<=Vf<#f zeU|Th1mDl71Y;D8f%A-&Qh*r@o2#4fH6(kd7Uixx%mi6c%q&l%(9*vqor(Pt^)HD7+;s=K9?sfDdXnMdG0RgTKYcLmn$n3%DkE?hjGfG)Ji!yShn};dOx8cl_C%F3M z0`iJs%)~6)sPe3wF5?(O<9zN4I(OwC@{2aK&VRYM{$6?IVAg~@KFba0xnX&Pv%qIR z7+x;#H)Du-LtH`f4=W?Iq|IifC)^sxIW#b?U)QL!)Vbv>bH-)ohh6neBY&5RWV}Di zV&eYb9v~OVP9eKXxH7%3%DK(RDhj-ZL;@vibr!_o$Qa+X3Q}mf>ht75|YjwDT8KY`uCC^&AkIDNz zYnjb0cd)GDg&f_?zRuBXg=Mj^#>{%w(iJABHk)s@CR}ZDXIF`9!j<9raJ6NXUYz@` z09Tu9%UE95n%Q~2zFvoWmV4Qkt9H0sxtCeB!(ZbXQSWlMaz}Hw@;A9>sh?$)I^3;t zJC~Z-`t>?0c+FkRy-dAXja0qCGp6g->rh8klQ60{tJINI?Qq}neD2zv%e~CZ!)Dy6 zj`wM8)eiG!IzQIkxtvAjFeZ^W%N>EK_6dpXZs(f$WJUwdR1mY!n`9ZE9N1 zMuT{K=#8TtA9{dV*Lr|GLG5il!Cv5)Fo$+b^xMn{ThPwI%hQ|Q=CoT7AEjToFMX}A zed+fDXJP5<2lfZG1NH|8fZ7TNfCE7-i37oUP-|m7I0)2dJqR2OYOfp&>igE3IRqRE zY6l$(4g;rPHyj2I2Pb0%91e~Ejind?mVy(pkCuY^fp!i%(e8|&q>SE@P1a(TR^)oRDlb^eA)$}8k`??pq-CDwVK}c zv^(H8t%-hvj$kb#V|Qx7I#9b|9oPw+i~YJ2*csG|-Wk+$sb#zi*cH^C-WAk?sm;9` zSO9Jr4xrreW7w+r6a_mf?s2j>L5i67u&)q`_9zV{D7 zeK-2mKLYjF=xP5L)Z?P>{coWD6}|DFfO=N+&wmQ)FEQry@1UL%V@^K<^^P1Fj-Wk~ zn3{j!Z9km$2&}xH<0C$d_HcYLYhql(7oeV*L-DdD#yNni@w5dn1@*?IU>;~3N*;Y8Y#!hLw+P7GJko*49) zUKOsSy(;KQy)s-udu7lIdqwyy?G-UH@weeOw7-qfi@yn%)BYw#M_wL&O?x@uC97A~c|Ea<7dH2jM8(%{MSUlHx`IB4XbQ6Nu%dj5?Lc@i`tz<80TKqCc= zSN#)c1i>Z5ll&R}rM)fa556_r zLJKCpPw3I!5^lvG{QK}b+TY_1zBTz>xS95Mc)4#&ZVorm-W>FS-xO}7y(#D$zcJiE zdt>ml{0-rH+8cr=>aP#i(Ow_Dyw`1WQ;g@B0Ns}M2s?dJUmAGc#Ji9 zEIdm47?C2ECXa?kXdfm1iY{58Bu`&WFdrzLNOH)!7^PUpwT z8{u`@H;CUkJ$XI6M*BK(J!d4Zg;!}`BW~!-& zeKy2cobWX5Gep_^G(w6D&pi%WL(-yQXQzPkH zq|Iqtq{h=XPn*#;PmQW?mX^>qOO35BNsDPq(&hMri_;?7;#7ZoQCdh_l$vFrFl|a( znCiW6nl_m*>R0ZZcB1W^>Rs-X*3ouK^)c6_wX}7q zp61%LBW-P}zqw;tL)$UcTU?V?)7GT(@eo(1RkYRVf@FSDm3E-5N*CfG?vPf}c1ZOK zSEd!Tm8st1inN@zBGp4&p0=kgPd(4kK5a+aKJ`pTyR?k9U8--mEG?xiOFcVLnzp4a zO+7WyHf=-OHua1|o3u4;n{*N$^w#MR+SaKW-H>!J?T}QxZg4t?c5tfiY*1QHJ1EtI zR-X=}txt{nAD9lH9he&5KOpT-J0LZ_zkk|~wtu=AQU3kXzO?;PPr>y~`_T4HXA%L> zC+$t!CpB)MciM}#cWU%Nue2v^uhi2BJ<}evJyXvl^hmqY_DGFD=$>|??VcKk&@Jss z+buO3p=;WOwrgtCL6@{8@djPe0iasS08mSW+KZZ^Rt&WowermNrKLHufT;ypRYv_> z?Pv(7POi2z6jUeIKQ;{1FRaIGIH-QE4{ZdfX0BIlB&cSt?Qs;Sey(;l8XNt949cZi2y?R6qswb!&L=CwYsHL$2jjK1P=B37!X<~gDYpGES?+0q5QD?J4OGi*$ zt|O=gOdYQl)b^$BXRdzjIBJ8PK&?4yiJif&Jg>du_uq=|Dp&CP@6C6WTloE##c#eB z-%?)UH{XkIDUb1+@5y(S_xR2Ch~Ip7zNMVWZ@xR<(sMw5^QC-CSAgGqH)cbB`UAOk ziF0FDW`pa-xv@)}6+1HnTvgg@c4h{++ME?TF#}wM&Wau5d@#$OYt;F$BtG#)psRUn zX4p2&f)?~V!`YZ8--@2U-kD%dR;#LIT4{qgvz!Tq%minCCFrwp_Bku8uHq^%OROh5 zT?G}OPb-C{U2IGGow?dGi_O!a4_Mn-XDFTG^HaNb{&+gQE+ZK1;0v zW&eDZp4s*UYe$}=YbaY)o=^3x>T-VhBG47EJkI^)^cK@!#K^2L3&91<>wV%1*eA|? zBK>Li;k5;D_OTJ2`zzwCH^=07`t#wMD|l@_9Df2mcYz&1SHQk-t%;!AYhO6+JW!6i z9~4g*>IAufpWE#aIj55cYu|= zV_S9<*V6uRb?wi)Yv`|}-Jf@QQbC@#Km2VoP(HVcXSX@1tzuPNd+thA^yPf3V#L%c z-Z7j0OkT-+3jaB8-M@MhGH;!Jy3A+y?|Ku~_10C*`)+qjF-UN3;bEvu+I?;-* zlBz1Xu1`%qY+RB)RwIJ2#;UOb<$Chz5Zy7n-R=lqaUOk6)D_%3Z$(FR{MBS1V zvK6mx!_^Mll93UATe4=%|Fmsf_j7rTGg!RBc`T^g#5J`w>u?OOZ^yN5T$Q4Jp?QqW zeKMEP_K{m`&pWqcjhhQ)2d?tC-nWB0jO85*7?p$D)5Af5G3!@s1ti?2-R3hWjt!Jv-4`!mcnLni=*h`Z#R%rs-RJhd+_Q~&^c;MWEE(37I(d+ z?0*w!mqD!t_oQ9Mcu&w+%Ds7YFHr8doZd3fc+2JVs^Pek7_FdJ11_gs!FV}n=3aTK zd35Bd`$4M#J*Oo%-3J~gXO;hT1oxxepYeX6^%qt}Ub~9-tVG7%pZ6RPxuVkdN+j(m zvAgK1au>cQwuW)(R!uDL_$)zV)L z?J!J(L0jp*dNdy zMXwVvvYRkEno%e4hq3QIdNjSGh??C5+A(pjIF{bgM9>~Xdn~=q#L;fb=y*n*!Q*0I zEBf*Djz!Pf6xs=KhdGhn@n~De^Qs!yao}{?6QfLbB3xxU`j-;INpOqaU;*uqqWqv{ z)|-9<+LP(^0UI(llU#2!YbDQ98TA1h(w+*%lW(UmI*nbR5t?-)#y{pAeZkWr46c5lC-BbTRZm!*&gjf21D^%u4D{|ZY0sk94{XZl>?qTm19}GR zY-s23T7OV${W**|2gKD6eOxI=y<9A!J&#ugfQ7W@M~UYG@O-p#t@{_yD*}sn#|2yi z(9o55e!^?@;03g5?NW*v{S@h@1XS|>Dg3rMSi5hj0YuE zRh_x#R!p?|OK+Y@Pwr7d&&rBs^Yq!8m!T^tS2s&aXE4i~VkGJS-q#y+k1$h;c~jgM z%t+i7>`iMdYJdJmS9U$GRe{Q}=9B3G_Msibdj_&Y)bk$mO4NX^$ickRYK3Ms9>RMD zu~V24d1zd7L+SOW-=BB5zv!_u)>UtEE$F+=wPNNKCBG58It>0VN6-A$Mw67&AH+M% zjG+f|2%}MP=NrZQN5I2J@}ALratJ8*9UXb$=SRW6)RoLoYo1zn zxyfAS6&b@jCiB`ja2z8ujhNRq@R_N+qX;xU$^0aRpnt`9;wh|m{nX|&DF)3-vI*Bz z*0NE>(|N5KsPEfcC?%j7O{Q~g!rrV*uo>5;?Am&#XYjrPa60V_K5st4DU4?Fni*I0 zI+=&1F=!^1nS62@IE~S)C{>uTr3rm~ShKkDz?sm@;grb;o6_GDT2+-=PtMDp`KrxM zl=E0;-uj$>U+q{QzrJbpW9y^pp;o4A&1HR5qY9MkyuU^&m4e=7wW2amuk_G3dz4zt zmSWD7VNlEIx92GikMm;$SjotpSG~CdSjoH}8Fxmt=PKrg(VL^`jRBqUW55J--mCW- zW1;4vPqmJIRyR>ksnS;`C|1YSU+M~Wtr}aQ1eSS6&G##ZHEtlQF=_2BHMCrHNja(V zv=N(`C)P+fC24c~s`=+~{Av+UuC{)nmIBYX_vL>}_!e0l?e`<$`@OQLp>^Z&jAZcp z7=7_=;)Rs(vq%Ot;fy`zFD5K zsG%&!)7MG(SqwuK&0wUE^Cy$=v*%?Dk55fYi*Y+fpJbUUjUhL7K8qw*wl9F68-Jo~ z|3Ae~x~8>V7)7b?f8FPm)5vmhCq{W0C-ZIMCpV;#Wlt;9%Y0r#<1-t|dd}ib)XO&X zyjt%e3(JDr$7_nj$ zi}lbZ&@;Nl2(R(wSV+4=UoZf9Cd8~kzi;6LJGZzW7ZuE;>*yv5yT4uG(;x>)QEP;c& zHjO+o8cBYhMP6nxnMSJ^y<}9C5i0Tm=aNxcMmxz9j5~2Q8k=H#iM-7@DYwhwPO{8$ zMwZACo#R=2NfsHIRdA52TF*glDu0#h%4PE+&&#Y&@?g1i7TxmQ_@R->*(%E-leG#q z;CugTeDZ%Pe)8K|JicxG->)XapuDiaz+wtBwqHsjK}k-$$2u{RA#5jY*QImRGa_0c-Qaa zc`5N2|L@w*A}8Isa*~Gom+_OCMNuBIA$cQ&rJX)@ZNgj%?dc}S`QjwH!?=D6>!2;elm~|{xhQPM#kv15#R{k+lwf; z2INWT1rCQ+AEWG;!;IP07&YLm?QrPE)C~j&^4?BF=rv4?7Hh~k*Zxq97HgQ)(TdLg zzQo$~BEqjH@9IvRSWjZt>O!NW11)tx{eE*p)cIPDHBJ@ve?UuhkKW zRS~GuN8325g;q%{U0eFCX&WciM6y*9Iak5!?TMzVATrEdte9x7#xa`%wR?D_O^g$3 zk`&QW{g3#%HZdx!HSub$!v;i`HAxyWYMQj-v&At^tTiX~8$v0dZJIQPRvcs1iio~a z=3K)oO*x^vhJGP`p+SsZDFVdnNJ%P_A*gTPe6H$t2y{2?eo0y z43SKK;uBWtXdW|PG$)?vX+CX?)6-Lx}CTjWfJqcwduIIg%F>VcBMQiL( zYvQYJfNn1MtH~nsYbck}wk9^~Mkr>JxhlDsaU1YbTJznsiJ4rC8M=zUVP>2*Sk`_9 z{s!7*WXJgh?>!e<8!UO}g674)82lye`Hb6w=h12jY@7U?S1yj$y^F9wo&!bOWn1ia zTJp5xor`Vq$52kC71dv~0g`8k_n!uyNqao6lwxZ=9yDs`v}l1X#RjVkrX{u%Tjtr& zwWywoRromQ#^jV?L)D(DHTC#tH7>($tTv?exD0#jDbUTZa2$5*BcK~$(hl42aeP`! z@o~|*P390x|!@(M9)DvzJooXYoFKZzl`@TfmRMGk?7T~z!$I&pVnuv559~Yq3HFn zQlE7`^k6K-_d;9>sMSW#Yi0Cp=xJZd-_Q$N89gZbfc~LG?;6c} z1b8G-x`&32FZnR=` zvLo@$ONn>h1>7}MMTx2kYIV%=QH5-^goyRUTvbR(i@}9RMq(AR)&lwqgR&A4>4{QT z2dGs@M%&Yyi{!OE5|I+vwzM6RZMe1|g52KL&^nN{Wm|g0ZP2ewjPsw31XY>LCZ1eL zYIE9Iw3SFnmB>Of7*!@S;&?OqGeSjT+eeGoMAByjabavDTC5UfWc8if4RkCO_V+K3WWZzQb#oNMR@r5A1cqzh7$ zsJ*0Tl&pGyJ&~8p>1rf?JFCiJfWdkeb>dTh&E0)~J?#hbT$aMmeful(x!{ zn5qI*cS3cq^;JVVrE3_}g@r(48ik^p_WuSWo zY3l_fmgjiA1+?doik_kO7p^Cwtkfb(N`HxR)SsiA)dDHVIC87)JOw_pa%{0VYW=65Yb zema|x{#*U9b%maJ|J^jF$Z}?0kqSK(9!gWHFk(z>zm7q>W?#aB|Mi}e) zJ_+6C1YU2#=!7UAH9wB8+}Y-Ef}10=+A^|{U9`Wu1QEo_LPzG zqYu>FI!ae&;lUC>->6kRD_Y#AM9IjwRx(T>HI1ho%cTca->zAJv>GdW4F}EsqpefP zNPn`qfy@ImFd4$gj6aSC(;tG&qmQb8q6DTD+{%~(c|9;1h`iLFo|&M?GtMZ0j`g=& zH$fSx8}d?5usdzSIDmQp_0=2OrPW&7wwZ8@wYAQV)!OCA+Ov&m)yChMs}sN9ifL9w zH4e6p_tZxIJDEK!^FvSK_sB!_xVPfoSYv$(yJH!5(p_>Y*A#x6ywcyUFWl-QLm4** zhtW=eqW{7jdLoi|IatovQ?^Fl$>l~MgH(VOyk=~fG0yr8^s$cMJ{jq(oH7#rF^Il7 zb4GF(2Qk(^G78k&Q3Op}T|K>OXrn4f70idV9J3<`?*3jzB z>JRqkwOkFNaq<3kL^RAJChbn8n-W(Hb}7x-jm}sJmWCRn@wclLD_4@b^6p>i_R)TP;mix$`dvM!s$? zC9@$lh?LwJQS)2*E`22b(|bHi+AzMe5&!>x?!DjS|IXgyHwfH0M|y4=@r^zA>b)@+ zRHOK+cd)AJ+vFwDpOs}NSwAm{Gd;^rl4T?@oH`4(%U=>*;($!++X>Ev&8Hqp5YY?BCc_BQ{on<7+ zyl>eFemx2P)|`ja-=W8I{X7@yy8cF2ZstMK3ZTxsex3_|f!|oas#;+JPtYT(2edr? zj(;c5g%*}9+r__|=fdCa{qf{^=1nyY!TV|62k)J>D?O{mDy*OF!pN3fhKnq>g}a9q zwLv^zcZ19ynq?x=YF7`>Qd`e_rde(at$^}Bb@t4!s!vvbtkE@Q4KNBsk5%S@%|+nk zydc(pb}eS>(zPh}$Op62=B`11qwCTYYDPbMo=?x?bIzOf*Xz1#`Rm@>kiV4sA2Xih zS$F?pL;iO5f3M3c{GZq77VH1t)}YF&Pg!%yx>Qwd3u$|S>e6bTy+Ji?wa-4F8n`-WU$76@h_)Zt7i>t|AM6J#+i;rw-;CgpD9!G=xhFK|*gRnredmU=6zKF#1EWB7BZ7 zVK@}MGurw`KpBp`;WMfrn5f#<;;xaMKtgkl&2>%lNZptXHqjGnUy?`{ymGDnaOO*GG))9xzC}j6;d62 zE;V!D*VNH>rDiVHOttgfsM!^p=F@2CyHm4UGLLoVPs7MP&GG!iy?EzSGY`hjy?7T; zGe6lQaWCFIsFBfgFW!aJ>;d1WPQNEL3t<4&;1?xo_KT?B6PECCN{f@n(C8Oa-V2WK zF-m(U?zp=TxOcKo;*Pufg8RTPy5sH=aNlG};$FM^fpU>rN0x%JlX3vdK>13Ufc?Q` zu$%G$%fbDV<;i;3fCIqgFq-b8dmwl~a$w>Px(9&=!hpJ`?h5drWJRI{WhE$2>JGZA zKv`5dgM-0U@TxKghkysey2>9M3LXLn>mC%V!9!tQ-IZbuxEhAmohS}Vw6YvVc@3=X zjW7y_QzM6a0}R6v)Eo}a>z*A)QgZ~%uN=cs)Eo&fd>y5=iG0I4a4p=hdw(1au7e?V zhvH+vqlp-yh2~iB7@`qeMd`T2{X~ujk0VxrdljDm9#0GdcO*FxJb~B-@)IY4Cld2O ze&S^CBw``BGw{iYyPTXt`D7v`XvH}dJcS4f?s{?>cq)+<^wws7364)s+(Y<`J^+A91bFE3vOWdX8JZjD*N`yO# zoKMYp$pwk~hg?9-`9veo-~B>rE=Vp)+!^>HYAz&tf&TCpQ*#kf4NjqSNh1GoDR>Dn z53~E3c@NlmOH7rgXjpZ)VPb9JBga$UO{(La~IJRT+?w6HFpzb;UG%)CR(S~gZC!u z6W4>>2d*bJgRIQ`AW<0-`IrY1SL!`L`F^51ETi;b;@Xpkzz2!_;M%~46W6LdO!*GWZhFBV6V5SMX(`5zK%kdIkI|Q3~XWUIkwvdV!45Yv8LyHE)>n2 z>xp)?H^A4EHxgG}y$QZSbOd*%ehYk)s0psvdK-L;XbL;RF#QdDn| z-2P6@N5qYgh5DG9zY~W*7U~mfJ|;ea_PI}~`GmLyV<~->jDeN<2lyFL4MxLH{S*8L z(GEtzpL`DflZXhTD1DLWA^Jrk^YSI-FNm6;pXgWMmqb&LwfY+TiYN>6EZ=}%6Mex* zmfwQk5S2mA@;mTbqBY2Vd=Gv{6bHGHAHeU4?jV2iFYpJVKIkp_Blxf6$HZ7?nXLR) zCfkqNgfamKvVrTOoDi8nrYDb@ED;OjbxKf^MPV zh=?FtQ-+$-L`sm2DVtS;E=zqG;wS_jhWfI^SAcH;)rTv9<%zx^(^3(vKvV|Vl}cbm zA~$rPR5`2OTLr94TnDw>s$do3J*f9q1FI4TLS45ySdI7)ay2!;>e(7ub=sO)xwM*; zYY>^BC8b(fy+vz-wTN5b8ml^4d9^x}YZKu>ZMiNrb%=bR4qA_zxrXdj*)QTHZ!*N#Ib-p#(f~4!G`>fh!d&=#Im!L-3ftvQjQBb$)NKFUg zE2vd<%Bp8|qP`>17u2mfQ{RcG4C+>0sOe0!2DPfL)N~<=gF03>YPu5LLC>b{)N~{2 zgIZD#YPu5*q7{_6+b0js{X50G>uZ2pkBWl06kXm7~Fw2Z1M(4*>^* zCuUCqPvU4OlW?8lD|V%?NNE`6zHC zcvN;RxR#^Q*&{g`O&XOQlRZ3p1b75>V@RX3W3z`*HNfWY@vIk{XfGen*M4FhLoIQ}b z$)riyZ7EL%4|uowAE5PtER}-HX!Bq^a3y*+m>pBki2sCA%j_yO5@3r)L*( zG@Z0db`Q$avopx2XBU7ovNOqNWaoo3v$M!&X6J#kva`u&Wp@W>XXlX5&h7@z$<8I8 zlid}Z%NH{OVnC0=gs*8NXk-_pggL)VGRq9h%k|R0Uv6M;&8+vKVYW&*J z%TQCAuU=2bved`}=;>IFnzHng36v_Jp-o6CPLHhS?SEt{FA1snSceIW?}P z(pR+wHO(2h=b_!Tq(jdq~(hVkp# zgU%<5(D8`s!Ep!lw?#=u&{;?ykWQeplb#@*L1!)F=5+y`(~PIr6?Dck&R#drc~5_m z?x3^cQnb4sptI#Nw7Z_5v#4?WdV$Wa#`o(DI_v7O(g$=lHXdMK&{_H*w7Y(wbNC9h zyZ-2JE5H@h4nTif$*jMUz?{b&YJKM<+G*mr}e8H6-pOuQk~ zXdzoeX(*c88l;fJf(&9Lz2WF@$|m~ci~yBcjJ!7z9DyuzWRPf#%QqTbPN~OuePckS zA$@_@+{0^nkM|?Tr3*Hd5?4NUzh--_Ak0JvYd(EWJYEdn%jlRENW(EW~0Adl+32a_yESHn?sG>X~wLZ zOO25MjAgegHAV(7#@%kzXuCD`-R{)vmYIkCc11Fe8lwRiD{nqE#sM&f-U4*CtHGTSl#I|z*W+`Z^{>p5P5{>%KqPg9NPIy1Z ztI*%>M^}7+<3rHj9zchDfa62a+#W=?e30YSXl@Uob3VlJ8uYh^(M65^w}yJH{g0v7 z9Y&4o_l+`lI5n={H~QQW)Eth!YgD=;sW}2Y*l2Y}QRA9@qu8ybMh^p{+pVKUk4&T9 z9Zk(TG;E{c9Yc*?34adyx3Th$Lw{2*H-_Hvp!&M8^-ciQCOgaHH=wz4k+942HM@Zpe)FnXm{s#`L=alm{}_ z-<6>JkTC$S0_BZ9LC3oqlvOg;+%=$VlQHP71!bX(O?MqAJ7vte>(Ju<32*f|rR&k( zK8Mfxg5w*|-@bt7`jX=t(civ=|N4sKo6z6Bf)_Jx-p!P6%G`qH_6^+GHyq!J=JqX| z+P56vhUWGiT-$dX-;U-I zq-5`={;teDnQS)6-b2mZnR_#NXm|Hga}Vrb3ADTQ)Z7beSQ72-K5Ev(CYGdhf2I^V z-UFaqV`+4}2SGW=GU#{@Wy+%6Jw*9I*vfKfcMntZ5G-bS^twl=c^G!H0vg?;)I0*~ zSrLuyF=`%#6E)7>ux<69$1e|L%^tvah`6FCx zb@aNYsCg2Owg!6LpQw2X?zSd+9XmU6{51Mo&Fs_E{28vdHhSGN)aaX42fgku)acz_ zmpFCLQu7x$W8>F7N6oWv$@S6ho~PzHm}cYMy+FG`v!8hR4 zjq>*vDC2JQzqdh|_?BpQe*@*|jX3uX`dcfo6}9hDme+5CcK06oTN|()QS9EMMqj!1 z=ymT?^B(qr4rq5DQ1d=^gN|r-A5!xH_5`EkeMF7x6O5kscWOSu{?G-z?qh27&+Cd_ z_X#y0W3Mm@->1}kf*qqfdfjK#e2QhG2YTHM1Sj%{Ty_?L{CazpvCpf zeu4hhEBhs={iF{%-dCV@mA>eBUxV6P`k~`}18RrqkB;{(sC{Mt+T3?wu-l-=eV-Y~ z@%NcQ=y5-QT6+eg!Tk%=3N!=_?nhAT&`@-@Ofrd6%JuNq)=tb;qDdDR598BRs>ss(CG z+!>v#HmHqp8ah{Y-Wa zTn(ww!Z{nAs}VH~v2D&l=OWrR$N9D_CV)r0c!DFh%VR?)Z)1(I%2D25&B{) z$}O>Q?u8!NnwnNvI2WT|wxOmq7S6rVJKIv@N~^sowNLgzD{W7?9k$JV(NjB6(;nOA z67<)O)O5hMxgT0>Cu%xk+gys)+nJh9ST&bY>Y6M=1MW&$E9d@b$K9yWzPTK&xjQx5 zHxEFc?m>-K&I8e`ds3s7^FT_ylY`K{dsFU(eRBnRc^_)DZ?2%!59|xBM1$|2tU`nD zPg%?6!RYq`sOg^!Ob$WsA4tuBWDsR7n}@;;3D-5OV zYPiEF4F`uM`T2u+)*zlekh_ME55}50fRZcWhVZ}WPiYwWQ2uxQC=Dkc#{YVFayb9j zzTr82DEFq$-{=i$yY*Llfj#+~{onKi_51dJ*#qp(JMwSn4tC?+`L}fgyYf!`o4bNt zc-Ov#E}%AM-&AK%+p}-56R1tv_uCQdKr8y*JAmzJUE8BQsBPPJY6oibw*A_I+QMz! zHlQ|gTfH@??cA@S6{t~h0`!aY+iDK_rTWb^1Do<4`zIdAV6UzPI#Sr%Yl4m-jsi76M;1qi>Y(F} zV@Ea6@yOAnD(E=nC{qP={BrcE3_7kkDpdj;cv=c{ymp)|2|A8D3YP#K-yNOvK*xPY?JVeg;AozJ z&J&LE8PNH|asS86m@uz6AN(sbI?OlD6F+1|g?Y&NA>s&@`22+pNDzz zpP=)u^W{H4{SBN)KLhnTaDM$1)a$@`_Y+XB1Lxz9LA?%~q5lr*b>RH{5vbRJv-^jj zUI)(lAAoutC=I+1>UE%$@E)kYfzrdfpwfv_#XF#02TB`%1C?f!Lf!_Ia+FTq0+oK0 zTHXZTKq^w2c>`2hQoeZ|)W<-H=QU8dN_ps2P0_ty|MEDG-zk!nC z)1dwa%8`Et^*2zy{1d3ZfpX_lp#BERqfdhR8z`s#5!By6`Sl4IvssOR9M77AY-RE)LCRMye*jrr z>0f#Me(*lD0_FJo!1d@1%J=I*Jq?um?*;WVP#?Gl)YCvc;cie*12u=cKs^oADDDLH zG*HvH1Ju(%J>+&!PXqOn+dw@H)LU)^^)#R}l4rAe8mQ;o4C-&7=5rIMmZe5?BdGSJ zzH|eqR;C_xJ*c*(esvwFE~nmgEvSyCK6VYL?x&u1HKE~>70DX4dWI^-pw{s!un7lV2lsB>Nf>S>@ZdLgK%fja61;Q5&g zg6?`gcpf^lI_-I&y0p6Pxu80>I`BE5y0?1r*`PYP`twGko!0i)YCvt z~Cg1L|oY^RgP$(?CY%P*6_;nVLhugENN&2IpXKRp#Kp z?5qOil4N{Vf^tkUK`TJHCmEuHKshOyqXR*?D!HTsKshWqrsbgAmfX|+pq!VS)G|;; z?1AKd@&^J_c7Jjo`Tc=GliOMXx230n`$p^w>SG`mwhyR}fgIW1pgsn2XNy674CK`I z0`)PFYg+{BV<7vsC#ZLUtlUCSe*@XNJwQDT_%?I@~ko%hl>S-V+xI3t) zfn4Ekpgsn2h`WON7|1Qo1@$qIbDRU}T_7Vl8`Qf%rg9cI6P{G=awa$Rli^JPFjhK<;=VD03~RJOPx^mTTSy zlXvg9K`nR?mt z;h+q@tokre?*iHOp`eVvEc_5q?*e)G!Qi0G;K0`p0taRW1s;DOsCR+<{s2(#0(t-b zpxy;q1^R*7C$tvy1+`mfMd$-+&(ONi8`RFB?V%T_{X?5XPf)wap~)fShX#AeA<4ny zhXgx{R*i1hFto2|?dS?>chL&c1=Jp+U8FOpokn{}Cs6y1c9f2wb{*|29YF0p+Fja% z+JUskv;(ydX{TumYB$n;(+1R@q+O>qs9%Bho>rjV1=@jHg8CI`A8G;WSD@XfIjDDm z_M~Q@-UZs3nu2;4Xn$$~>Rq5+st_!|TBg0K0L;gVrX4FE)Vn|{7x8|vu{F+U{URDL zwl~(kC%co+!zR}-qqVF7sCR)@wECbnJgsZ>Ky7UC5^g>!UWpYMEWIM^?*dJFE(7r_`oc1=N12 z#j!G|T~kYBB~Xt7EtC~OeGIf*Rsi)b(4tu$)Vn}?XE{*s0_~t>LA?vKkCp-TF3@^f z8q~W$t7<7wzXGkTB|$B?+G1IImT1}4Mwa*)fS0e67RS?h`HeT8)ncwcTq?J_0Pq|E&!FZ~e?G^0#Q|El;@x&vbPcN(Em= z9(i+;YrOO;Z^r+y1Xzl^8Gl77P;d2SoO2C+8A?sSrkPq9SG%|_tOj398ERw9{Myu3 zqg;!;fciq(wGzM0Dq`|Fv_fUj^)Id(tIAhZhU;7}R*|oYl|o=ea@UAeZZ`~f^3KZXoZzk{eXKe6399i_marI7VuvF+xTQes8x4h$` z@8s9F_3zIpKHtRm5l56?+kbxRXT&JrJ|Htpoh!TZ;H_o2U9KXNQ|Bm-j)FKJ3 z^K0h4+*bYd&)8VD(*IJqTxq;45^M$JTxDY=bk~3?A(tk(LR~qz6v=h6O3Nilu7)-) zLJ5-6tde#fNf|D~QI?d)3>E+X=F0c3IW77{e_fqmYkxQXqQ9OO{s;b6HJES1W+F=709L()RUjyUO`L^Ec*xSO3Z1P5V>) zwqk#>t!)i8?CRvDY0c`OyTsX=)xc^T+h=WC+qgt%-xAc=b8XYOc07-I`>$)pZB62b zlKg9BAYvQG-V{fofA4qwu8MxqUGw~ZZ0>hsKaLu}mi?~Z@P>c2e{b&Z`ZxOb=Kgx| zzjw=i>$iHhwr1?Z{-v=$TT_m=@0eDOI@{L~&ns+SM_uJ){|}DF_UrU-w_p4BI(pl$ z{YxFy?brV8j`sFz+t<<9NF=tf|A+tV@8-7eZ}<25H*WY>Z}|7d_Z)eL|J-{{xvvad zR!iQwdtJC!iLw0M>mtjs`&z^uFZAV?4Rgl}V;a4ITx^7Q_dJr9b9ajxpnDR!14B*F-589%Z|qI^xqhU+ zu;=n{{Ym=r%fk&I>B}zzXIz?kU|njBNK+p)HowvL-8F)Ei*WbGR5AK~jL1I(mfw8{ zjS=qdgYH8(JR`3+0@OB8Kt2-GW>84({uPDT65Q89esL6N{FUF^>;KR8vS-=9+*>C0 ztk}zP`&ZnBDDFt~Oa059Rn*Ih`d8YsD$|qfX=(pTdzO3u*t2?u{$?*L>R+*E*~{GH zGxn^w1JKs>uh_HfWrIRbvrokxFJjLku4(95LqdNu>XCiRofPa}?gF;y{^dR}_N;V& zm`(LB_X1=6Sr`dNQg#->wZ?RI8hJ^MS3=Ux= za3mZA4h9_$2ZoVwAZ7O}b0i!!u}-pI&&oKM=~m&?bVm$K53OG^$z1bhW2U!8t2&Yuz45(9S@uTG#)yR+8VZsKCWUr-xtL)xb|*qd`klQzn~Is$-Vo!Q))tMb?40)MY=UDV#XgS#!d=VC{C zSV^!c|2pyoGy|Le^goXOSO0=&gY$3mFLPe^|LU<%k5)E+#lOL?+5d-sle4@3vxH+u zpA0QfA9P;N&~6Pu+cra+H3n_FOlUQuycJS*2l%qIw|}**UN-b)cZDy5b5aUNDLpr3uj}G#Z+tigUmy&{@FQz<22Qk)_s=$MM5s|5r-Q9!L2(LtU2t zq5o?~A>)fGTRZY(Xe%RHI`U+~h~QU5bcpc%xDO|hA;P!ej-9qeoi^1f(!qAGgsqqGF*@Do1#J!+3ZCQ5>uzeecR@7U-D1{C9`@4qrZ5ZA~ z1Ky84C5^ThdyiwdF;R`y=g4OCKBM)u;cwJeq8aEIVy{s%@w;Yg#Y0WC2@=3~?I`3q|jFSyBPBx6(Sz42b>9kuNFpqcSm=nhz%`B@IWS4y5+9ieI6zVmr`U?%vob9P2OSIMotVB2Z>fM)0>bKL+~y%Epd@Jwf%& zEG459#~8&*zggP1AJ~_6bIfoo6CIVChA%J14|R9K;h{}O(R#yZX?Lk80Hem}h@xC; zo5pCSjv_I(X+yp<+tetY#P{cWGdialsc||t-=>>tJ7r%brj6S>w@u>=namQ8$jjany|?@Wx|r9BJbit5h?PztQ)TkOqT}$qC6A)b3{N|0AKr`hkwU32oX3 zbnH!N;a;F)uQ5@bErp z1m1Y0HA1VSvK*qV>!>VmUNrVPo>k<{JNDYLQ4*^{*|FD_wKW}kZP^;2W3MgCE(Kxi zwPls09DALe640^N{i?fz8;-rh`NEx1okN{39b+wxq|R1$z8y?*#J{=nmqJ-by|{Kj!C-0gmU6EzZ=+?atJZt?fqH znI#Fcj8WK)y55;zC;=+Bcjjws1~%utIs-a0IvW!0iudTO=!_}zX2~9x$9r@Rwck0T zIyx(HI?{V?RQM9&$nSjacjfn!E2rg-5BB+N=>L98eqYsj!=1vr>%?1BI;uvh&U;h_ zRIGCbt{-G$HIDIoK}yJeW!r>rP*hr0`w*3xw```~xYZo7m8onsXUT+QPj~iD^%!R= z^q+;>=lq{QhPE=f{O??S0mXob?Ca;WWP%y^|y+f=?;nbbCw zcUCgB9b+Wt@_a$QFHep0mcBo9xbX-(+r~)dPDmzr=jkE+? za$Jpf)B8&H_4qo}X8lqfQJjfljB#ZeAe?gfUo%<=x1fb(Z|>^2j`el!?071_ax81` zj^RnCQFjb$^G>DabnZF{JeK?n&Yb|BMt)}K|7Y?Gr761t&z&YuVAbF0Tz@v{WbiEV zb10nxo=tu(zj7+*_;4Pzr-A2?pHJ=S;JM^PJmyIkaE7?UVLrPs%w!i*cLp_QQg{EoX#i5D_vT}kOeR%2eyl~TJFAsy6eE}cC&&Wl_b^)zuIJhAXeK%n{DEJq2)ds539h{lbdT33NDr~L`3dkz za?y3kPw^{{urB&Z%6}p~%6e(z2>qEekFbu~I6_Zz=26yHy9WB1Fxxy6<|TKueViKN z3b7K~{b&EeeUGt1`!AHA;zkw3|b?tVP=`7nRK!1140@BJM4i_|>@8eixo zYM%yQAb&Z`hcELBRVcf{+nslxW>vX6=eP?~uRG@f)D~1-ql(YpmFRkFy_;-ee{J2LaWxKMYdihx}$$ z%C5ryh&$dU3cyDJU9bOl(mTWma6jWukemjB19|GFJo5waW9mO8y+^D8qYr(?`FDvy z@F{2iN%|0UFF$uy{(zVT?tT0@SG`YUAma^uL2{So&pG;%{9|GQ4dNN>yg>dn&-n-V zCG}sEJ|!}cF^In5{3oFMFMrFKe`LN363}-+-u;eWt4@t^5!?s*AH)j!hAV#{eF1(? z{x3>jf_ce4k#4j`Mhxirv6?bQouX$3I-6y`z#xqwRT<%v*H6U>rV;I~SEWyvd0DoNCg3ScF2u_Vu{%yY_u!;qmX z^Sh;qzEO$#Dx@+*<#1>1s+=!Nv<~AGRpU$EvYF{X4(d9 z%I~!2NNmRQ+#S9pv1wXxZHGi&ssq2=As5wdy6|iD z!Pewmxwb74bGim>%kOk2wFkSA_u%;*K&=oxsqIMo9U~g`X}-4M?APKI)IUvLolFiOT8GWO7LO8r4&5e=s_kTsat z*Fhs7jY!7Ah>WCmFzYmjlgAxwM{#Z_D>_F~KPHhA9mB6R0*!X$TF=3(10BUR<4D86 zvE;539R?chXgp~o>q*@ocbjA!?8-L$)(BRcj;DSib)#63>Ygv|w>y%Rs*@;BPSl4d z^9zl^(d655?I>^*zpx!?9Jnp{_LRnh+mY|U^S1%V!`$r1(^l8*oiZfSbMt@<*6k17M{pccjl^ztkvC_@-)(Rtl`~`C%JxiJJ$A&XT9z8 zWE(i48Psi`%pmQU%;d>a!0F_(INk}IK|Y)37G!28YVxzGol4DA>Sl9(Csr9x;dkbc zrhzj#a^>+fRwYm4*{(>Q#%g8vf7y*+oDNQadD<=G9XmNABQuow zY%n$QFEtqLfpqkg@tvmXnq{?ZQwi-|j<6-E1#+Lh zLKTr$qc4iSHEQ=2sL?(rt5Xnk`~uFjLh|lKZF%H%Ic;_PLe95F2A6p)M=DQCs_E

lA-WO>fXF180VzqLXc=ig_!0S;{dr0W zSd+!n%G4}|N7T@BpqjjHj&tSMcP+NQZ*X zCWkSmZv#^z4|F)my_IE#j^JMRS6)djBU1`Iocu^irQuH2aEGkT;eod~7(AG(*KvGg zU}}y6kKn3f0?Q*Wb0}QNQJj~TSqC1?k-UxjL9Zp3g((eFGJ$JPARPmDV(jIUD6Iw8 za-Dlf%g@LXolH6&j>KK0Pa&NMN3xDu*_m~4Bt$9)PvD-@n6V}V{^dCEIIcc}tB(bb z&fq!ckxm9> zbI#{U@-`F6Wns<%&tb+qpENP>HF1yavtUrp;%<2xqbzHsxQHi~fjuE=4R{XcE}_O) z%jc5I&KSq)Jo3w!FDHSMxbAXl?sJIe;fM(*Syj<4c=8Jo+vOQz;R z@ItPTow*8>0lJ1Hdvh7*u4VR`3{K|gI?i4LGa^fKJX7hySe@j@MiLRc>XPcuelTU#OTfI zx#n)z5c!$=IIaNROMXAKvNv~d^Z?Jj6}*+J9}KL^LzLud?&gYz`Q_We+quGh;v+Nj zAneEkTqPs(5cn`hGA|WjM@I5Lc${=6s5bF9rH2DQ^9cA5&v=64N8w0hhW!0Mzqu`?)J;hn0GCxB8C!P_x8h5%M#nGRT>_@?c7{mE#u6YXl1Nk$Yc>)|w{tP8q zlRt3oFI@KrI1>4yXGxVoB1glIJjuD|xK6G{9_M*}^)c`%@)tlO^gT^3^YR?{4Ec*Z z{~7Q(B>Wdiqv1}T=DL@8*3;l~oDk(V)Y z^XpvoE>C_P97z5y$8W=(yulUkb7$mjWLC7se85wx1ZKwg&2Mx5Bc38l^A_i1WFkLf ziQTehO>y z5y$`JPPv-DQ<9hY5d4rUzCaco1P-F^ORoL|{DiB%Bz+EF@+qaSd17_&GxBe^N8aXB z&V5UbJjy@GzvXKA85x}Kd7doIVDj%N$)m`|e2)Y?1UBVMu9Cg^4o>AOj$~(kfJf2l z^&_b!_%%nFL}n@-?+dB0nTYlfa(H2IVEPL3zngo}S0`890<5cybBOW?@g{ zgk*0@z?J;SlS{+W$ll22l%YljB@6dbhV)~mEM*xKnU-=qGmml}ca$TQhBqm}d3hTd zmr`&z6-c!*GBqV&OiFOBBG<{=l;Vm?JgXE~mRt^}B3O>R3N@8rM9OhoHR*-?UzJ~! zx2ebzs*z-J%5q(GoRNGJ02Xky>`ha+l4j(Qv1!Zys3Cj_c51L8 z_q5|&tH8fRmZmj~NOOLr1E~#+No&q`B(;MFX~mgNqz-T-eKWE&vgooj?J2hygMT_2BpFW@KsPQM!=JzjOfG1RkXW zd2gQ736#6(!!==z|1kBp5Grsax;Q!_M? zpXmq6ix98eMa3|xqLKbEm?1(&&{LFTsHuN16ZRq%>KnovGUa4rK?fm9?1yYa+iRJ2MrWLOz}2o#8*W zPC}GllDBQ7dn=6IajT{505+sY&C^Y*Kz^4*$0u;X!uf%v`S68QhsW zcjb5%oXaj;yBldX+{Y}=?@pQxm-DqYvg3Q@vQlYHq-e$ZwBQVJY@lC7C4JL zWoCATdGY=|IF@_q&eaR4UjWatJGG1WrTolZ9PbW?vXFc)N_)bk?8ceJBzNDH4cZ%A zoa~cm)7*!vdVt+C3#nPi(Y~DB84`S z)b9r_Cf}d?7lVsAUd}a3L2a4`@T|RwF1R=64&?rQ!F@SCD3J|2i2DmND|p@#q7*LS z+)8Q=0+*4m;+|#TGL8@Cc}u~bndRV8u0A;F0RM3a&)T1ei2HNhq1=A}cmT(%6FIKc ziQb^A6Fojx^V~w>DX!qEHKap{ySS3N!xB9)4x_Z1@@kF_=l)ehXf%rA;fY=uhf_L? z@?jhuk?03<1i!z6h>jhIxOfDmHAH&UbK^*^Y5^WXeiXlP2q?p2B*>QFA>?Zly*Sn; z@;OF}Yz402+O?#kl68rE&bmbQW?iBe#5#WQ2nL+f{}SC{*?duJ)` zi@&E|y8MP$`Ac5q@0JDqMXyzVvgGf`)9BCWZ&~M^vP$~1`;7QIWhni7|F2*39^_|y zGjd1ee)_*e-`u!!z5jRLjr>lQzsA4B_xJ1W^UcTy#dj(%uQ1O%u|KbcFs7mjHb2>IEK6nBXrC4Nja7fa z3Z(Lk8x5#$LF$F>rUzj~QUyjEd0xkrUg&mu6ILSW?LCB2GtTt^o0AuL!)F-Bs2Tl@0aiF?^=#Q)W!A2`bN9btqXZq{$lz4!JMxfzGvl= z5}Z>Lssm~jP#>xtdYSCBK3-Z7v=(SbD8+F{uq3&51pPgSQIhfQ0G1-xj-XHI@bDcO zHNkiZ?Ld9+v?jQc!j&WTPIlU*U7CVTsVx`!fPRE+DVHVJj!=y+q8z=V3gu`)aJ5x= zYAVntv;pY3s|BGs*qrOM2($wAiPUN!>N8o1RGGiTmWr!S{Dxd%Z3_+~4dq?9B3r-D zhWrh-qu!sxcxy&Qh-*{y`}F&@HT`b1bl6hqsu)|-@5WUuwwnIHdI#$h>KCJDy{)Eq zXN=IQjYKPpUsyfI|@u_d89-)pu&XTT8(&JMPPyIsu;$wS7@6T4WNpEWGC$^V< zp?ZI^TXE=3H91o&v{Y-*c~pN-y~6E@`hB(q^$2xcwJl|zElX{?&|Yn64J{(oNVb<2 zk?4h-wpX{G+Dng5Z6tbpR;4}kTDH|X&;pJf`hCWh>PQPYHtGG@IkcD9g)8&{?E<^I zJq+>=p+$C}4VuF3BMXD}tSO;2r%-l}McZ*Fl6x%Lc2i02v1sq#nR}YT+uKspI6D=z z1*dV`1SWq6uGodA>;SK?{a`vtzs)I>X7H3LSOK&j=qIY*rX$TP?r8?wZ~M;Xta~pe zJaINj%fc+KnZr}`7TuYnxxr>Iml~}O(>dOiXXz(8lYBRlUY(9`^LXZL&@V&}P<=RO zlh5bQ=D`}!0&LFJ+8eYw=!3ck_iI_0%ke_)(VDO;$9smaXHoc$7V#vl4teC-9<(>? z$+xu^*Jy{BPrjJ@wJ*%)SbM_)Z~@2raP=ObmWF+~hd9+?v{=HEv@et(*Y>avO#fo; z)h5si+>2}XBkhY_U@@g-+^>CMF~`~)j8(4>>hkcd9uU6V1HyNzpXmN@|4YcV4`@@^ zkE;$OX@OYISFG(pf6k@kD|nW+hou~AbugO#{^YB|*M4yLx)0{b2f*}e(ayNqy)T?tP`5NwC3CC}*Ih?Y4IF=zlf*Sof52OAF z?r#I?iFzcchv#Z?Z4ax#L#bU$**zTXW%`G@hvVVoM~6OlG|xO7d%+Q$KZdK?fylYA z{zp=GEJ?4UamnZO~wV>nZ2^=2{uH}joxw9Q;FFuJoj{&t; zoJ?wuW#BmKP9dFyO~6_$3@3uxDD)gHvO}E0nKMZGc4}8Rllwb>CzGGW@9H^v0(YE6 zIvxK1WX_!(EDdLK&#Bl4+&SVL&YzA&;55#i#}ys0G&p9QPdW=ci!1aJJqI=C?pHZ*4nA+$qs@1`f=Mt{yfHmM;&RxnCS{*9z#LGzMfah@M<-v-e1>zFQ z7m{mrxB$F>d#>cHwuei2ntq~JfR~Y9&A3$otiX}pqFNxX;CgKj7h@67u5c}PT?JlF zejR7EJzUB04Po57fpZ;U^{=5$KT$0WS8&};JXs6E)g0Z-)!G}b;vW4#Zv?eH=nd+g zkNTkA#<@=L_gXIW{nW~{z0Ch#Wi&|CBtc>0^UR!hTe*a&Xnj=M;=V+V+qhMPHe zPZ*8w;fhXyT z+8eYkXmxl1w%<|yVUixA>$&e?()}>}_i&Hip!Z-UxSy-FI_SOm0Quu#UU-}Yuq z%z1W!B-c0eQLF*lDD(z>0B-+5uKpu;J_z&w5Vfh*L0?m?4u8ag@E9fS3HpXU&W!Uk zPt%&<$|CIzkAm7Op5eMbf{%0EGn5{O|JPEX)j_Y&r>ND&&;@jkd!8pe4L;5J=ShEo z>3@prUZA9h=$|;swKu%P{q7+2EV(v@7vTP1;7IGjOK|yGBD67d1)W=84f4>d{EC)^ z=egrm(#u!`UgQe>LH`QAOs=Ituh74e>-(v_p(?yzM5}PdY@;#5iAYv>{N~GKOnsY z)2|fqAy;<;-zC>pP#vsB{t=~W@cr*{?&Dxf(B7aY=X>OzP@}Kr`@!B&o$K`m)i?C- zT+a@YNGzWPdFC^YyTkV@$NYn&x96uEX?xJOQ@_(_f%u$f=_mRL$Enq!2G?qP_yW%V zGo+)hf&}$-ke2irtqJpAgZ!IdZ_ry*3xrk&EfC-QWPA9I`#;APP?IaaCuxEBf^$D` zbuUnh!oQHoYJxR6_b*Z{EDPUoE|X|c$Ryu#r0qd_!}r{qP_J)iEw0T{lVB52;>$~v z2lJ92cyftE?;q_0wZU3kS2FqWC)-0FR)7pgS|Cco|0f)kCTV-9&6PzK2>m>jG|Tb} zeKO?|CC_qPQwEzr9_PyQ)I3lhR4owN8?-cNbhic?nAoSkU6IFYI9-B2dsz-7U%9=?(tPaZH4HD&ZYy~{40Z-Lu zvd**m2-YEQ%>8x1IvnS7U0qO1Lp~+#2wDgVNW{t^4agKG>IH@TigpNX z7frZE`+`2GO~EGE4H}a-BQ=Hf&*!K)No#_-g`S}UGA((I-lBz^Z<%a^w$U=t6GAUi zEf7t(N^3+5YywR=YE5bdldmUg8&YfR2F*Frde9tfMy)o9fthxsL7-L){X^ZqastoQ zOSB!<0ewidPiSS(2elJP56`w7btbuIWxHfhrVD9srYm>1#TKB|qASm759-a(jiOPoy3Xb4P?GyT- z>MN=ZLa)+M)M$+uNGYw?YwR7k0J&_rFC8ds|tO+{X$ z7s;3^u3YX(GO|i@O5M@XnuD?$-61oHKbG*_u(|f8rNnbPu&;zb@Ch`ak!3lL0BHAo@NXXHp)^kp3Jx3h-=cdi1@{nt8F_%OK&G`O--c|sUx;6gUx$opjDBiNM&qIy_tfa8eqTmsbRD{1 zpMBk4?N@1BMpg`vj923~D?{3dZ`<$MNT`1G^58O|`Sb;QzzCAj8SNQHLbdm3Rntq# zxJULRBmc=v`~Qq9xn=D9lI8c}y6s-!FY^B%zkU0G|L3@RyJz^@{kx2(=Xc&Cycz$x z*oW%#9(`{yN@5XT9M`EgXKWX~F#D3+V`N<83U$9rBS1K6%Cl9Jz8Capwp7 znSIIG)!t?=bF4^Nc6*sKk8_25xe|nZsbA<{&K~wTXQ#;G8x_YsXa90#M4ZjE(nOBj z{#BK~FGjWS@3l`wUc4%QyYfP`G&sXl3BAm@$9|UDC$vR4=TxE(+3W0O+PorD9<6rv zIeVElvdFVL8`;+?(r;oMF6ZWGwJ=_Y{i_34#3)|Q?^@;Tdnwm1Cs>xGRoRiszNGzD zCf#1{^mFC+!k#YasG-kn!U++&VFXp3gc5mYo=q7@kgqM zkwptZC60?$MQBrYE;9<0wqSdv7GZ7e(SB~fFH0NM2OY`Fl8o5tnBl16PI=BCl1 zB(VaLR2y`@C{L;jI?|RW8D**pcNkHnN+v%)MrXA(m5G#fMv=6fjtb~VKPI%65t&9I zFZ=$+a=r<2@mR{^IX?&^Efw$aw)EJ z9fqqr=5Y0V&bmMCJdPG{M;lP)e~<8#J-A{vmJj7R*Iu;6mZELOl^MqA&>piW^pr(B zBd+>z1xRU*_TrxQ;6ie(Chf6=7};YVzP&P__M3euEduxC+&+|C@1fH*hTTD058RA67lgi*a&YVc; zIPf@*P73pit3`WJ4&>T#F66#5gYD*AtSHXS7xC2I z*i5Q(#l?)x)xit6%5@%nKxN}gsn>#YG4+>{F2w3`VX)?08p=LPD@$Kc4N(iuC7_m? zD=1x#eZ^V*N|H7m_f#?aQcic$27S!%@BPAn%)TVS3=^D`J9@=BB$BJ@2vcoN; zfmm16bzL{&YLVJpcPq&_Ag)2VjkE4)@9L7$8p1Ry~A1Ou# zxf8ofwENr>>^{b=e;~*y4{$sL+e@_g$e|b?#I+>#xc?zij1m&9KdwTlPwgYzJsi}A zq~*r7DDn)CkVXc3kn2+FbM>Rl!u3IIK#!3>2#%yq>&{590dviL(6{|g}`87leEz*tE?Hbc|>V=!rjn#_Xzd*Su zS2vamQ^HbbbI*`g$U;T}A01}?F~}Ruk#(9=r)vk32PkpMyV=FSeuuvl$dg5t0--4C}Fih22wgGE?eaV*-FVMm9UhpqMS7)$PP+a zZIO0zB`l=_C9HNxGs;#`&YBkFqv8@)iJv5_80E|eWV>*0u51;htyIENR#MK|SiWr+TET)9zO4%q|DdX%DWRoac?Za^@ZAA$yN?S{UWTBkZ1-U0z&Z>|jVJVwLsVbGT zDj;JOm#~%~Pq?mjKd|CYvXzn0luZsKDO*K3YeNZ3sj4gTkn)I9m8dkaDo7%$ctVt| z_NQk5O-NYXk!cR$`a^@1p;wC%mNHZ-XGIB1*<{U6GFRmwXRYQMC9EDnwi4BdqihxB ztfLsGl&aKnQ)w$oSZcyiwpvRmmA0aU6{RiZte(g>MG{sjRaMK8s+2O0BPm-M_bf_S z%2uwuRU$iqr}P4kCO?reQK>3QSW&i8eo?mSg+x?6$X3c4o0qVZn@;7PKHy2@>1teM zuhWAxae9yxPDiFt+A_AN8)X*dtUky*xpG#mAYmybZC=hglY5IxSV|M;la#QG zzLrW=N(vW{ie#%Zk%^*&by1Lml&$(AH5nmIsme9Eb;vIcGSnqO_EFC2heT9|S|zLt zK_!LDxc4GZIZN59KPdkZ<*8f=>q@Rys!~!gy4q!+a+wm=fFN6mN;gVSuF{QiR+O-m zt*&J@uLsuSPUWm9VGTseQJ%_`u%aY&BiAciDFrA^T?Z;>-NZc90Bpdqa#pT{H84m@ zgOHt~Y}Jq}qHLu!rEI0OLfOi4Lvkgk!Qd_AQMQV5mXgwtAYly-lG2@^5>}M9?hf3* z-8?Oou%gVRgf%3{MMJ?<&eBUphDV8LJ=i!%SW()Fa#obE)^qm*f$LGW8cJDaM+r-h z86_rtZS=1x;CT;`qMW6KRlu<^*(}QoJxobon<#BPNM2mdD&&eNTj_(NY*iTKDOv1P z!cw+MB`Dlr0%XS*?5(C_CD@x1JV0#~XK3bdNzti<0z8 z_tLa?x@y85EaW?!JzWK%9B;JKnxH+S1m7yY4&j?E5x&6^;cF@pzK#;y-+;3$WZYxC5lD5xYMeL1bUm;tx%;Z-K4D*r@TXmbox zt`rn`CgX%eo@wj3C3z_sCL@hRZYlCiOObJkOFqhho8p$DEF>qDNnWu)#+rRTn#eFb-=b3UXdB5{a#VvV7JX4V+@0ZvnC8kYt zPMc<%jJ`G>>06$uh+&GHla{<9o=NE}vQ66Xewk;IVT#h0*1MnMnIfMQd8WuYZEVBa z6suGoc`C|Q<$q$BiX^PaGs!Kaq!*Nlr-{USykG2NgM|TuWXq&*aLd zTSq5xo&C=8dPMMwC6>JDO&Qh*cI9HHfEb#J*8Y$ zoM)1GS{o#bT!ty-oV3qvXw{Q#ik3X3uw%J5TJN;jZ7t6f8K%fK$unuGGq!#%+Z1`G z$T^+J*-csUa(Sj`$y26Cxusl7-Y+psHIcAt2A-+NlBY$kNW#js>P5Cm-bj0%a#m!U zl&~V_w0XA4C~lkLnIgj^+Z4H_$TLN|U24ONY}1B3llD3#q>b4oe>Aaa4StzXoU{@=NaKC>JHmq~CeunWCSP8oSXSjJn}WV$2A= zj~vlU1Wv0&;I#BsuSktMMgB6+6d5Mjrj%!rVUlgC!~Y=Vnd%mM>ciyh7=4(cKhu_YG8N~Uq7)P@Y|)2Fn_Ki`+EDWOB~PZ*+7|6>`ZN7nPo@od zrcE(S8+$TEAEwP)*f#cI(!v%cpU5*sZYg>-MSmt`s!j1s(TAysZHo4^&HFG#wkdiq zZOAbF?$7kQKa;xv|L)JE-*{@z+mt6$u7p*@GwCb-OAOQ8{}KL7GEC8vskjf*=6ELU zcBu_7vQ0``%Yt6B3>|0FJd+I5^57S>9R6p?R6bj2BEyt=GU+k?Yj~#O9^<*(Qm&kp>(8V-Rorhp z*Q?1WJr}}E{nk8FafYeLSG+jGOv4ZBn`tyB4L?3tjmwUAbL@QtGv?|9ZO8+tsM)3h=6w^nQ=) z!dcU8J;X!X6gzbv3*z;avmZN&wf%yI#KyOrL8R_2&{@RUcQ{XDOvC@RJ~`xneTf zhMUt;Ti0I0Xuaq~pRPHNYtUVb{#&${YhYumZCQI6Um> z_OkzX`j>Gq;wqciv(om;?O(3UkFECG^{?Fa`aeA$8owm=vf|_6|BLOFJ09ltuiW<9 z+;|uxmBjw#igJ%*dBQw~CT{CX{bVp*>n;X;CFDOQPh|wQn zbO>WZII_nG5;1;+YqVng5+hEOV{YgeW(a487~v(xuZWQ>T$LZ=TsYG>%fv`AagA1t zUs9FX$hGT6mZ=tIs~Eq;HCkGFoY7)Dnz%YE#;GythtUX}6Jrz`qZHI)M2?X^{9cTP zW9$#dX=8gBmB9Eo#?3LFuye6-2efZFM;lwGKI4mPvtr~D;|Mflj(5h0Gri-{Q05io zfEdBYs0zm7Fv>!V$PpuNxDIOsGnTSZ(;!`>qhoVgE$xN5ab{wKnfMhLbtdi2G0x29 z*3voS#uatOzSuC%j5Bsow3%NYXGZH<8g0gwN~Mg=t)<&soEiPaQ%@(`D3yA)WG$WY zlx-GcO4&}fnUa=s!=~5LrSh7xz}Bv%GZKW~vEQzeP$k}^l2QE9(=S_j%BT=&{FV5X zD_!}O``+v^#*Z+1gprMm!eZQr7)2)i?tPQWYSkFaV-yx!)A$kXc-wm3$5=J7uNo(! zEqy~@{MbW`4bdjZg7y==^X==#v9_c2 zEDvJw{nUeOAJ;REptsq!M%HNv5duU>)BGahHaQe6mbqP4oe*OVtlZEp*@@>Y*BUe0imUwNgS;D}eZ_Cu_op7Amw|8DckE~w+arx3mbPAu%VMj>=s@})#OUgx z--vpTUyAyU`cRA(<98FI%fxsyF$TNro7$_GeiJdmd-`Rhk#GDCY;W7%mX2RQjI5(= z$v8V&xMEw!s5-G_V+1$b)E?*RG5s@)f^X}@wkv9*7)j5u&^GezJ8L;g`u1adx!4xY zU%vl>&~NNTwx;t~jCB(u+t?3B@yuEBG+sl^QlJ-*0h^=NzIiJ~kWiRc?_UE+U#`ZEkTI{h(8rmrTd)g~TbBb{V zf2;P2V~_2%`Tn&f?Pbr3v671SuiW<125>}CIF`q$>#OWq~+vUFzp`Tq6a++NCs${=cgx#OYn2W>TD zFZ|yc4`mJ=AC0pRV|~gZHen=nyP33;diyd%G8-&B7_D&L&?Q9tGwHKQ2uQ|8ba z$k9yZP&vg}N#-z)fV~(Q9TS!DjVk5{DT`Q@e(Fpoi&%x8>kKH1sE3_1qby>jFd{pT z+OOpjjT>fEwHWJD7SWhu&cU*XuJ3e4mPIVfyr7&FV}i(NwBtK=K9_-#-|)MZiHb9d z5z?Gt9*sqYoN~E1k`Z(;D}ov7MUy@7d3IiRrAUHW&M` zGi8h)=R6wa8fVs2-f_l_JKWed&c{(=in^t37H97GwZ`$r7K*a9U$^>clmL{)ooV7c z<9w4!jLHq^?41?Jnno1?gs%jugE6TR%C~KV7DA(9R%E-#VQR;CXjl0UI zsl-u1?Oxee>B+b(sZ=E!kd7`fCTpD4m2zX0x+vc&wK<}$sPj4fnLLM3cLSHcaEPMqO3SG&ee{?a?drhyTUid-(fRReAs4o15NyFZZU0RMHa&Nk~ExdhZ}j z6cj{35v(AJVnytZWyFq(j%6Ij8Aly;oadQm{-xjhy+3Tv`QDP;8v>*ABYEw0%J-ae z&)IA3wbx!XYs*F8C~INYyvfm;)u!@qva{|18)^fh$LY?ZfUC-7 zWh^9b6<*;%{uvPSchm4A1RR=J0EldWLNRc&}oG90N3 z*b2U~Iu@7Fu&Ec=0zQ(9Rh?ckvZ@7eglSKSelOaAc8*q8Os<<;N2$q^FRB9+H)2g( zsta%wDxHhF4W*Y)AJ1);bT|vNods}+4xy^XN(+4uE<34*Nl;m;1N_a8P&Xz-En5g73sV(R3!gs{jA&Z{HOM_9!bW? zc>c8gtc~PPZlmgL{S0TShjsP*87gCB%@rBn>b4h9+r!$7k;!C~tVScr7+Isu;%%*D zP<^hex3zvf?Wq3Ga7}k6qqd**sU!K@nT*;V*5-;#RDZYsk5bOaGe*`rU;6wcW2Bxx zO|D4u5OrsaY-crUNA(-+-;U}xFQgfcY7WW7_9tVcxgr}s>!ET*Hs03y^n4$W9%bKT zk8J0S?2hMufh%kFNPT-w7uBC!k;=|yI5J~oJb!A&$Ye5V;`z<=I8@%q(MI+Eym$c_ zTQ)FnW}+f8_D}i8G7OwO-N#_Z{)zNM!)6W8r$!R{eyr}|l&AF}OjT|Ix|^K&Y1>(}D>W0`DfD!dlY|Npmm{{Ibr)@I>0<54@R z-@2w}nm1CNLd_C6+IarPw>sX|-5%D-o-|m_8hJc_vPT-#-z{g2ByZ&4NdE4qwt;@u ziR4ctTjKd6bG767tDH43l7Fy=wK7P}A=#F*;%BX#mDv7)($?AWvu@{&92n348CLd9 z-bnQ?HGAaX%-l*(k+x3fZLP-Vi^wCR%Nsd3o_}y8|8RcRiRVxBni|%cH!>d9?MOCd zrR0tLCUTUOQ`>S@GASA1-<>@&c_Z6V{m=81Za?cr&Z=J3?YxoB>P_CHnlW-HKkHx}7m8c_W)hwq%d|9gFR@YEzH*2by^!Ydl+b#z>_p{jc@8j+|AqbnA0%4khz*>t}72NaOYgdsxTwTJ2vG z&#yLr5t8pbpc1gw03-a>c~<}HMO?Fl<5|GPY^&$>63*19em$&>;GYgmRKM#tHH6lb zJF}?%F+8EKPwmkh^f_vM#?i(A^(L`Coi*#!Dox^OU^NmoPlIccSk=UQnEK|_`Xp+g zMpmC>YPo9`?_;eJqy1;_*I&~!y)uytF`{M~w{c72k8`HW5%&!0FmC7BxAuhcYD-pJv!P0619MV>HvZPRG; zMn>{!>y~O(qgT5!Njq=0Gi8l7t9c_+pJe#TB;E1+?P#-hJioF{Bmaz4+w?Q;s#4H! z^+_5%)33PJO7q=SN(O41eo1WFzhdngSec|P|L8$bGe$O2P}MLQu^(CJ_t+{MJ=1S^ zX1C;%7=Go7D*33Vs&QtKc~YOG9b2Xh)txuHojp=nsOHK}JbycHq!}Y$i|2nWp8vIY zervz|@6a=8vFp||HC0M#9XP#E%o}N~lHsb9qyk)It7x0r@%-)DZ^Om&CmVO8ZK`^v zXqaj||G?UBr_wXkjFGQ?eUemwYe(`&=QLV9Q@cJ%qhYFb;G$uQw#f+pk<}+Ll0Vra zYu?CYNg8dHl20LvRS9c2ZPQ>mtDP~joj1wVbk!|I+KPmAw&M8*YnYVCYJHN#^QQvb zNcBur!_>|jsf{h!BWuP;HBYrli5h~MHz^h123IMGw#oSX)GA5Ux1l2ZW7SKol6Gu= za!A&Ae(ia&y@Be#g=C7OH|CakbqfuVcTlj_?#X3v+EXon&LUMpfK=s;_ zY4T3>nQ}gL>SD*yoipP(_C9}+=lKLR?)u&O966k4yxYI&be=cS`9134#{7%xA$$wu;*9# z6@K4DpcTFsU$N=e*S_)&@jaG%eX@9yVx0G+Kyem2oW}V{WtJ0)zZpR7AkKfzYvX~w z(@f4f%T44LXFn^td$n`=RG_w$+5C+$K>K($&+P?HXFHo??LMrDkna#*zKd@r<>zfG zu0t(iv*8ZnGjAic)^RMK@cEG*>`&j+-kd}a+9OjrBNh1W_V6Tn(=SolkqX2@q`N6d zTZ=f>n}0HGA#fpgjOXlPp#Ib zIt{v*1DwNe(#SL2Mb3S8#rL>8TYZ{$K-e177l**=~UnXY%Ho@Oobd zT*uiyz6D8;W_AX@uAkON%+Ok{5Oe)_zOUu@9Q^Co(v#+F7)M(L9Lv!*&YuG`)6iDn zHoS1h@$1{sPK*PNg|Zv~py;ZcrPkpWO!(Id16fL4~ba{N}{Rw4-=F3}$kV>MAr z@G#JdVLO4w=Dd@8A3>|}CicwkybEZY)kAEBiBPo)>t5O(JSyHse&>C(z4%tVjlIW! z`^m3;AA7grv2!2rzLIbIHqP8a*6TL_^_#whb}JgA8##X-%~kMCY|WB=FYsQjIG<{{ zHvwds3J;yiD4iTGml(Q#ThaIIt@eQ20 zn*9?%*JhV}|xb4XM2UMo6EeU3v%s+5^|__g`vuXlbCH_oW?6zB2G<{r!Y!@<2Gazew; z8}A1BdFJBGF=Ady$of_Rk*ytr+}G_Jm*J{vV)M`!ev$ z{PqI-KLBdM?BO@Z?zgzE2QAsRfZt);!|@m4GSBhc8`%oKhL!Ys&fEa68N*v%N_!4? zS=oP%-!A9;Wk97&`RZ4JU*+#y$5q$E?Jg~xZ3j}Ne4v!59+?A+nZa5LLm+1|_C z^ER$L$aNP1FJOC+y<^Np&gV6|o$ zZn3684_x~Y*BFDmuW;?hnVarnE-^xJZJEK>7YSi6bIWbqbvwV_0lb^7Gt(Vq{{A?% zmEObs@1{MDR(dtD9L6ac!?+%)U(wu^_bB<~t#kg5v|r*A z_#)?jL9X8q06)OlpKxvk_UfMi|DE%{0R94d^zV7E4*{Rz`1g2VJO%s^+h1{P7{rt@EX`8MD-e)%uj|0@>f-vF%+{eSuOzmP}u4V=&MzX1Qpc0L--KLXWk&g=Z2 z&VK^`FWY(a+_}JWIaeK2ELA$k%z&RN3%fp;3Fmcu zDQ(Px|Eg(prKMhVBHQ*l%fIDH!@q7d8|8lAqPP5Y|Ke1h?q63fv7WSl-M=`Ur~B9a zi!=Be{&oMN^R$26zpH+?`Md4!ZU5bT_1XJg|6=`WwaIN+uKf<@mUrF;)KkfKcAU&& z-1uEvY1perWF3btnINTb>EMJLde08DYLb=-n~rU(5*e4MOjZIsc-6T^h_^RD1hPy^gv1ck{jZ>!QN`i|{$T4OqVfmf)f@O!*I8Z-HW zI8v7&W|Ugh&Db}o={1$-s+IBY``v1=e7?uh-dKKbk5Q?~cTr>Fo=;VJmT&n~^&j5r z_p93*Q?Avfq{T_v7e&} zG-YjVW)o>zXdIoBXzEWKos((yha++dP5p_Za4KyIw6m7IX=M~n2g*ksc{70W66K4T zK>3X$ZWd5Js@`EXP@ZH?L(%IR^6gGg?CHQn_^RZ;tZlBh?qULR24V z?i}e(oq^P*KEd9M&exISC~{TmSh6PzwfCtD&R+}`JENqJ4&&^#G52bWIq?(ifm|?S zO>8<2`}))!jDs?ym+;AIz0h6}{kdFQTs!)rwT}KgTJ^rZJ%xjDux!piD zjPk!-K(&zloj$hxNIW~)Tfw#u{<5R+(d|GbDf#QUKr;`>ceeqT0OiMKbkcKOKD`CF z2q+b~PFe`m=R_}hv&(49-w1Ryrv>~RpzAU{b2k9z!aX+tH*h=$uDTw$o@3XNj_b9+ zSwKhnNwzbAasYD_&H&08%ji3|fdx7i9o|%Hz^37hczMS1q?%cqc!ps|H{;*^UR%Fu(VC^qrJp#_yW_E!p~# z?aaCf7k~*V%zW?WfJ<&Pb2}$%n)%_AmrJag2UGeL+h*&tB7k(DoFKhR7iN()SDW74dI6y8QBd#lpE?nv>qro)U#;aS>%Uu!eh{oT=8u2L-}C% zq0)++FkDeS7=Adm@WJrIUMQ>KhaHZ33O{tahP~vNu6d}}ay(p)d!=nxv*!Sl@5<37 zZ`{bSqf35hmbzrrQrdR4Eq65kmMe0lZgX_Gf>-KR+E#<&Xp6?p+@-Ew&6juT9QS4i zR`OS;*UoXT=26K%Iqs9++m-lGIquEA1t>$7g)4rp>zMot?x!#wR?>Jn(BzeTuBdZ6|GOZ@sxj;>dT5RVCGX|DLv6};W?FPEcC96E+Ybg@gC!?jlZS3E_;bx>ro}xkVbn~EyWys;@sjJ^ ze2Qj}b50Cpm`l#NQ+iQTyZt3fGB57AFHxAhT-iy=b51r#ycB7s#pLyOb?6Kp`jw8Y zqZ7JzogIod)1ta<*KO-*+RBwL*Ojs2IzgRLQ%%Qlr9{=k_DtoCI)9Dh?UXbkbvTw% zlb~DP$jp^ltjZhCT#-6XEpOEMD|45#*vRHDd1a)I$Q#Lis_mnZH{`jE)Nwvkql79g zrM}MrXiAEz^H*dIDb0MJN*Pt^I9$e(BP+6ov)EvHL;6n^*lu~l5tXd5#~D3U-dG6- zZ04`g^222MOV+X!FDH6uDyfVK|OiBCYwM#VXZ4%=@a8C_hZi0XdiaD-{cr7R~b*e%M{}$5C@79|}KGjt_@Y7aH!R&Rgj)98KOM{LIl3}4tt|6Z=C2d48b8e1%T<`N zg|fVyf3Q41-1=)Me(1`p;fl@r%axb5)U3kv8j>rDmDD5K#~gU7^;hMG%JX&o<;tsB zg~&f{#&Uu}Lk zoIKy=hr`M9?fFZ+h7zQ*mFM-pXr%hn*Q{#KUv=hEK6c~{HGgI1YWQJ${%YfE zxcTel$@8HX*A=6c=gpR$Iot|1%J9zRRsfKe?X&+mc|J3!x|Y$)^I3Uj_RfmbN)4lz z=auBm2CY<|74jO+tUZJES5|%9tFWQhU#Y+4>QTx&41Q8cEo(1VVOf6#M{TT~DZX5D z4P1q}{!%WwjYniB!~4tF6po4T)$Q zyDLeYs)j_ndPKCG>Z8@Zq>_aC`F0J7XiK#}G?gT@o>Vhzx~=bF7;o#kxetBxRZ(p z#;HCQ}a!{V5VZ zW#8!sqZfufrQXzgqnbf6MfKWp}Bz!hNJm@RTX($7=b zTh4X`vzq|yJ-`o-?&7qQgWw}$JrTCV{b1Ex;J z-jFM)d$u>!^Jz`BH?(SK6}LC=hhsaHW-s)y=hrK-C}U5i*$d0r^Xn(`)yvrP>-DQj z+}u)*YlPhr&W_`|7X$V3lq+dRvrl?~zPBr*F+jh?(bfa>s~l||px@_c>;86qP0SrI zI@{W4b;)YCV#OHVwlKoGbHK@8t>A&$1v6gP*YoI>TigD^ts&9zntML$Nd_&r{n&>9gq;%^hhqKj; zL^m0&q#P#_Tie$l75Jql{-8+xPip6zdOUJ>On58EWeE z5gNm>T900!-eCI+r_wTh9;<+ZoY}{j{m7h$*x$?kKKkC?PK5Tf!mp0xhAv3HDzv-NOh6-^s}eqxSYxs>-i8|;KD9p$Kc78%o{ zj(q|&u$o_;J$4k!$OPofHSBA_+FtbS6QHG)>`T)VkXlw2`DG=0^N~(A0<~<+FMLD4 zSG`|XvK8xkjOjO~55!ua{htbA<({*XzE#c<&XCRv&Jlfm)iY22I-VvkmhU=)>aQoac3r7<(tG66 zUgP!p>v^1~<>@|8EPLMGbVgHlaK@5rd!O@}T15Yj^PE~=|Elw!UI9Mec~L8vPjYTh zi|F&5N7ec&T{*LA1rw7?3PzoGwXGR+lKm9<3>_AHw-%Y`TVBPcvdA(J8KE*TT2dTkc~|No!w`u9P-iF|DR)^H%aw z#!})^`c%eJ;!^rl;mT+xGd0#N@|sQ zg0n&|{V7$+k+(s~7jdQsD79-nx5nXd`deNvr`Cg53R_ZWPJX?Go^?*KVq&s~8A&PK zsM|?R`b}^tX>nzl8&>k`s=~=P0;S9TGF$ZXYbw*r?VU69!w@DObUoLd4Sb2IV67Wp zVk%e*zIGQJ1z*9PSaaqTYeV5nOa*Hr!PnTo;OhwZm=CUkFYy$7xt17+ui$7*!A=`@ z!IW4V(}k}#cG_5L<7jEYsWYw-b7Ci$a;~koYvagSxZ4cxO5xRPUMdu4%sj-CC@2ckT%iGB5puFf_C)f2lu+X7Uh?D}jg zFn;a&yT{L6OUJqNftqPoXWQw;MZiTI?_gi;n(H!0(gNTDj(0Jp<^$(*yc_(^1J2{P zv2LW+X{`3j#B##wx#UWGKTT;^9(W#YCU7Qa&o5l%K;ef6*w=r_b@&A|?e+4*gEak@ zT!$Z`X|ISC zNZL8cSRDf#!*OGuI>~kOc^7BRc|iL_*+n@?J&<$0ew%tmDlaFtr^%^jKSclGZ0#Iv zKTM)2r8*-xuN${zoT0L>aS?K6`OTD0U!U@bQ8_*-QpuR|j4_7DI)4qJ|dbMB4S# zM^ru~Egt5a+HOZh+xF)C;mX&M)AojR=5S^mD z?!;;rTXnpc;&ml1wlUWAyNVBGJbJ{8arRoS<4?JUediBnk$6gpF>CEQi$n_&Z(y;u znSOVL(OqlT*`@7sEWWiOIlI&3-lgpj_E_-mO6APvwOzK)plHXK!JB^)iIxymq4&~loqjLSG$L34d^8GC(X&A1GTxSYNIlH+G3 zP`++L|4y^~SgMO}KbWbHu$90VL zX$4-#Z&Ns<*6w=tCX@T)dZ^+C_LSk)Ga7H;cmmLIX{M0zKvxAfvNx_|0T~M%N4|`k zpp9O(j{KY18&k4q^Z>_{Od35<<*iU)U*8n^T*_4nQ*UlYf_WTIqlf1M<(kv!;RV12 z9M7PK7XlY@Jd++?1YE>%D*RZL*)^Fn?rfT?E$7-fH1h;FzbZMo(sX9+p%tAdM`LKN z;`-@zw1gawrJwtO{T!PsOHSwvuC_pWS1T|9=$LSfO$0iNIJzbQCwBV!ul-kV+mUXGK>@vPg8q%VuB=7oEIo_``gP6R|uUiCM z%ytE5Cjg~fR|LEZdkca7*2ms5;0n$e2RxpylHQHvUjbafxs^2iJC%G_afRRRSXos@ z$ttdw3hkj)TrmgOU;0GMH|v?P?Dz7OepzNC=LP2%qpFQb@N6s(u|k-i(0IQd&W>Z> zc_r67LwT=vIY)Snae&_Mm98DVv;DV{eL@R_Iw8M8{+ao!&Su&`hRRVTF2{6S+l!6F zsrpx((L7d5lE3ViI9EAqnOm)gZ9h%TxHyb{Ts^qjaIFNb?DQKclMja zT`(^ueU|uC@8A<15y=ITJGHC%{nJWc`1EKwti!&9w|8vWZ+@Y99L50s=4I^71X}xR z8Sm2zoXOGh(oaUq+yBcrQl~QqxQwmQ^60k8dpb_$us@z(GJg6wo(qQU@qVrmzkQtR z=h$d^ziTB;p54!parHv+w2HO>s6}uUdukW$vDF2yM%^!9e<9~8-B*g20v!Qux=$o| z@_ULIYsZ_N&Fl~Mp!wS5p!SEjm4iy{Vp|R>Wk>~bQ0Ycmk%Rj6>Urd#;!69Z`YOLn zyQOu+{3iL)T>hr-nDH4Y(9!K!jioUos2S0Teb3z;o-2Q!&-=^(N|p0zvw-4nK26R) zojqkDZK}=`&KlZ!Tr=*neI4)tV`lu zI~u=Q*Gfah$teZvMXIc-6fDKbKaK6FaRy4kO|-#4zgpKb@iS@18Fc&AW`$zRTidU; zZOb!d5e*!8jbq~ui2an63OnwN3xtnNEHlf^EQoFC4w(zr8=^N~`4T-bcE z$|!PM`Mp^Z`}#I8FRX{oS2JSFEOl&{TOpe9K9T39n2xGEb%PbI2fDO){}9*MI#7g^iv2x^FCab|Xz zSQB&tJ_hRa~|7%W>D9~>WsCOX+P^{tBkn=Jgow%zjgKKe5nO+ zDo|{zTb~Y>b57F#QjM`ax2N>rp3;+gXHI6E*|U0NPGH{ijpq2x1dmk&!MS1l%_Y*)E!FM<^Y=p zoW|MBoH0|N^Re;6#y&cinsLF{9yJczIAfHLbMLt{WA`1?+iB_!9n(8#=2~zx@1&_a zbTsdxsXKHu@206$aLnwX?S}FlLCytxxXyiTNMh3Gd%tpttJFv*-Wl7Hdp%{}y$>3}s&7v3VTl;7>{bHZnJ4#66!v1oND~__#Rq9w!dPlw| zHvJ3A@saP9^J~s&C4aqOlGSW6-y^k*E%akgE#b|jE8ky9S9UxnH40eMg?w2FGhihVVV>J!CQvc4$S>F1z?C;nWqII_j2vcKhO_Ht$AGJO*YVbOuIqS5e;qUO0B3ARjw|}cUf|bBv9YpS zdBFU8$ptB8^w8`bN3y#9^ifvPe!ac`zNwsK3e7k5T_)3fQ%8qB1bPzaS)e?o=Yf2x zj&8YC)iSt_YHSz2sc%&M0emC<8^oAzG=?Sy<(KNYT;Z$pvVVJkav|}kZ06gl-HUgh z_UDD1(OzPo$U*9Q&R(*D(u6XS)qF^;_L6H=sn~bYZX#X#POdnu;-KW1T>HwAay#Ei zT~YFzi}AibsZQ^eNNjTc_$%aX{ndYdS6|=B@*OA2cbs6~ED&CIoMsjXufB+876_ks zjAj-H>Gmj1FK%s4TAk$wN-2kVcP-c2KDAyS1}YK8_N|3WJGho_Enl&{9)ufd^E#g| z(AutLJ+@tKXWHSXaaI}2{11&4J~sE7xkxK~T{r6Uq2*2sZ8+52!l7J4$DY0eyl6RB zqSQX?>QRYOyQ_W|S_Zd4Ra(NeyKaT%w0LV}HD{LcrLv@wrh0yLHJfRAachy(BC1_f zTeqG{@`~6+V-wY;seM#F)6Z6WXl&l{5amZLudW+on^kYyteh9HZzN(}W1Ao*ZCP>_chxSZ?&lY0f9D2Q?pl$I1dDyiY|46~xmt5Hn6KHH!-)&8DMWU5lZRjL^9YasccU_k_B8?>r$9G*)SLSQE!m-;}ld>|8 z9mz}{T9eiTojG0`Uw>=kOJ1!dudTgOpOx|D9Jh}a|DQ#SA*C_%0PTZ&IWuXWHL}vE z%8aaxHD#`j4#Jk#+O?DW_&4)DVaqcb2KHN zlB29zZZonn%G#r;J=PpK8yP>2I7ilIMpZM`99bJ*8f6)Ay^JnrPe)lDS&p4*t(6;& zrK$fid(JpUR~=<%n;#D5grmimUheY4S#bQ|>o9vG!PmKk2ll})mD=Qvaz*hY_v_}0 z(+Uq9j4!$0P*_vC6?b}P4d#lITR4*Yb#q0f+M)R2P@GUq$^9z6B0GmSiqp~LFH+uU zvL?EQZ}Jz(n-e4I8eVzBsKh3JkvgbkO>8oC=o7EJF`E2EHFJ?Z@#=gU&-f-^N6pmX z3Q2jRdI42$c)bdhG-?(jYFKYY556qWX^L3m}pLjhn%wMFWVO}sbFXsMI z-l+NaUc;C2)!z=j%#b!vGIVt`)coaar5EeKSsVJk z*7k7)t7h05ey(6$`)FCVvcq)FYS}c#Qa^V++O>OX0d)oIx>Z}bYi(E9u4}a`8kr#f zF&ZI$Z1dsh`njubaAhX9l%KjXQ-7a|bFT4xFD(TA1>Z~ixPQU->Mif3J=VYDd%0@P zUx>G!v-)_>s`K&*^66?{_3u_ItJ*KMlg{sQeYG38TAv9u9X>UBQdg(0Ui2=y*+l-RsFwRd+GV_vA%?^*zMo?1@@^L3iT59W9>oj(Kf9nMct#8 z5Lc{9HV0{|%BWZk?aNOc533kmQp^F`1&j*0tz%;)V{R>H)t>bM`*@e=)z0I*BUO4j zkMCVq#zQaC=2(vRmA=`>zV=dkYH#V+z3jQ}oxt(#(#N|CR<#)zZ=k>V&Vu8e1;aZz zqfgru&hFqV%+oN2y}RN4$EnD3f<0^d90w`|-pLuO`KVd5D$zwiWyCu;b0<(=u{(;F z*u7=VX6>S5)b+W9v$q#%;CAT#6810Q>}_RTbQ|Yy$Ct`A@vXGm@Ue2#-9oz+->XgR z-2~JpOF6Qq)HLd$;?Wz}zpqq2x}R+iRhaGvzL{+gRf&!QkISfH6F^E`X5gO?&rS4)5}RuUP}srue~9)$1v?_fuQR`i~zd6~I0~^`!f$o@5=z579nI?I&wDK27@& zb(yR&`6SoAnQBm0cKk5y>CO|Jd!X}v+Qq;p%D(l&tTlBB)urB7p!LY!!;#P`X4c0N zTEXnyv@1$=E1^}x9%p+ce9PL9v-vw80e*y9OS5So1%8x@S+i*$2Y#HIZnJ5h1Ww|P z+1&GCsQcdLb*av^`lV{0kMfpsbu*gHoL5cXQF$ww>s%?+;PnkzA4sDxSIQ0(GlUG?xIjMT` z#)nsLUOlO&1E<4>v}4Z)>Se7Dbz{wz>W|a3W=s1gXs)Ro0VioEiVyV?puX1nP%j1Q zYpoCUGN8WJdQvY3>T9hh^$MWA)_PL+0rj%hle!q)%|sF$@AzZxjL zOZQU0(#Ul{xtlV^^+5TZJ$wUDKIrQGMqv2khQcxBn_}%|pqw-_wX^eXc%#*`b{FWZ zy@xZdjW@Hm7rwcfk+p@r3%TkRM%tD#OF8qN2PNu>5Px}nG!C%udRQvGfMz_58sUR9 z<6*Y5cbM5{J8(P4$}flcjvnYuDvL#ZE#It^xVq5YDyX5C9?`pZB^0H1^jMDjp$UCn z^^mS!ljAwA9>`W5(!Vuzj?)?vLZ_0HA?xRl?u4H_$~HPC2c?Z;BLU#|bPJVIaW z`9S@z)g3l|rM|iPc=d{XT(gp1ngX1{u`4RQNR?>x!q(^7uhY9!y}hGS8um&(QCAn< zVN|IRrg~oKm#sCl2Rx6Vxt?%eOJ}^Q^>YyC`ei%5^*I&S>J0Uf9_spfW#fz8T;Kj% z)sCB$iI~uy)>EXG9;A>SWD_Nu9_CSxm3ov#Jyz0DcJ)~4MhVvAUXEPVD6jMuIi|PB zH_9x%WsLO}X{EP}!`?D7d&^kuEu+_r1J)nCpvV_`>Aacopj2{*rZvrKl6vwyzzDIT z@?qK`MwfH166k}BNM)7_%R5M>w9A3}*zRHP z3ZT-5qy2J5{vP(_2SOzXB}buBgYu)$8CWS&crD+%y>KVvP~@CSf9e{HN|AFeq8WXn z6uFcp^(tL1qb-Ft7x8PVgP5Uq8ML{OGYe>!055@`sS`2pKq@oLXRFqJ15nv;4$azL zN`mS;todc7uUWLsKx=;)gP|vin%NGmAE>UpQz*Ct6_tIa;g~|TisBJ+1Y*z{8xWCrTT49tr^~3X&Qm6=YSNbCy+B`tWSCe=tbhll75Yw zbHurtbA9Sqc9rVt)`(x_bjOF1y7pqds~tOM8e8D^`EGJ0N1OSXe8;Te^}=_Ix~_N4 zuWz}3)BZBwj(#5Uk0!z(u?6y0`&o{vPoca?&jdMd{1c=LE&X~T#Okl5Ki)|3Ptq^b zzo|4AUmv}|V_R1XA#UZHdWjF8t;)XY&RJzo_Vu}@lGpg%avZf3ez)8vx(e}vmqx{^I3a8_{DO0HPJ$g#(aE=XK~kp_BcIBOVD zV9yv=;J&zC&9QMLJ$zL+{~yTDC-W`RW991lqNaMb`ZaZKYTT;#t{OLIQFU(W+MG>8 zA^OVs^)<%8UR1_3#y~o#IWeS+CZm9Ubb9&g^W&&>v`IOYPU7*U6za1Rml{7{eQnjj z>2>SZcgmC03_7kHw^R64N|Y|t&Djsr%dt<_8%3{=WZoL+y%Nowo;TiOM49ms$y(z3 zs~a@_AR0pZ&bbhL_xSI_Y-CzcY_9 z5Q{asK#FihJs8+OrwL;{-&Jt>$hmJ9L4PWgz<|Z=auN7ZsD<;HxGod7Bq+~>n z_e-svq}3xf57%Ms+DTgal_09sIW%s3x2rCzg zjd^LkHiq@tn3vXTV_2Vg?0Rhs>obpCuZ>}i`jR3Ghnty9)(ow8n2 z=YJz-)TC$&Q2(#Cr31}&uh(3ujby#nUa9#ub*1Jy&h^@ZtTV=x^_nZSx@vQ!<_hg{ z;C{BQ*Icz_y|(u+tG1!mYp&E>r(FYd?dGbjyor$uS+!-o)?TBv*KV%OtSMSoZI?h_^Z&9^%c`xe*RoP`)uv2et2AfTrqrSx$kjwI zO&go5wqDvwpn3$Tot)@y1o>w3*OSQ$yJfU|aVoywz1|H^Gz zH;r~xMmLJoHCUDH^(9uOR8rdpJQr$ly{0_rdhN+_<&$t;Z4Dn_`$T!d6P$k%d&5(l zd4GBG`#JvvRtML8AL5s3*b)4@@1wmRtHXyl|K9RG@8$ga(D*;infH|Ud=KZ}%g9jX zxtlhNvEujLMY|hogYwC{Y42ggC_8B(oQ0-iI#=8Qypz!*9<&h7X5>ugtd_tzSS7}D z=etVJJOtH#gmE*SD{kZWIcWQ*bNp8H`X2#)gm-!?Z8|oHaoqDDN4J-reVkGFAp4JT z^f=m%2RVKd@XhqyV`%y9!N(X;4|4WC;Qdg*J3Eg8d)Yp~xi=P_h&IDVuq*UnF?a;{ z4z@j9_YU9~wjblSw*h{;@Ft*R<0hb1&qZ*Sn}N5oUBvji73iqG znz3~STf5tALkt-AS&x8r{b=T(4!;k!uDI^{AIHmM`YKbNR)L>K*K> z?^T1llYM5ozCfNq4TZ4&1|*hsVC8Tu@=5@45$^_S{cWI zTiNy%8K4iI>U#5F8QEIg*Km(om$htH!e1ThhuNB60E)?VY>hWo zgQWIJUAP*jRY2nbwe_xKe-*T@ogIbs6G&M=`Fjv-QPpEOK(OIb* zFiuI|_Bm|lf(hYHj^uXL|2>s>eRFH`>J_LSb1rY_OzNBO=8NUt^JqrYsTcJt_JCi< zzqwNv0MF&fFEYB*+1Z(4FFm)7U(KLuFUk*$H&EN9H-K70qYfN%#u+3t;y%7DW6t?z zKW$(6(*5AV(PpkRGp3m*&F|h1HaBzTJdXB5OU{d%Xe)t^47Hwp^w>DAFsk%CD9s#x za@fS$nlW-C^dxUp$2($tcwH&&M>_cN|d+mJlatfKmw$q9{XUkXe{ zcln{Q?Q(dzqWr{fmNzO-DqE@_)q_k9sg&v0q!)aDzuj3yjhnNFQMkUp-(?i8?{6fo zk+$Fb$=6+pjF{l+)vuy?tBX5np^Sg}8^ZorUqj2qGzbm=u<%~;sN8@p$ z@m0_3JFDH5^ZU-~$Mx9rd^FUtx{04?y~UqeNF~~eYi9#Bk)aP~12xuuzZ(8%t>xJ2 zW7TaYuZ}uSX~AbZgQ^*w^wM*+7?=|#UWsyS@AfL^U7zZmdM5hUe4?I-YH;m$X~}m> z|I4F1=Wo)Q*LshBj6TC>sYCVI{tb1jnH!ud{HlDb`rXL3_*VX2tg(Z~^q+YGC{lGrXYNuTZ)P6e=?xq%g702ca zbHwUXFdk?h=}n*)fql0Q7(ZA2HS7ze5i2y=M@o{{SCeXtkh4QtzN$*m=vWfIA z<*VJ7-lNO+IX>0CZD@Yv^dKde-$SbCriW01R57DahBUAQ%u5;4z*3-;Aq{BZ4?XAw zFcdw65~PYrg)+~|`iBjOOOKeiShW-LS>h-x0ZeB?Xq&Eo|^6}UtGqO`pWo>%V}yoF5~>=v<as!42I$?-emewQ z#1(2R4x)>2^xR9+e^NP7?ZqLq434BX6e;oz?CHaKFGp`Iqe_2d{V0?@-^i73K+oU^ zQ`>L^s5E*X?HF(w=k6~fPtWCJ>?_aS&-M4Av$&uAH}R`FK{>P@%@+atIeIhWt{>RP zxi@q6I8Yf`|7PJzwt6<70P0!xU>T_oma+OEzv>I3PVPZ|TV2MLGP?4r(XLvN%vhin zOP;M=NiH7VEjM@6gr_?;v`IN?v`i%q%Q!z{Wwka~LB`lWqxJ@^4O-${n@Oq0n7I1VU((nU*Im-0(6yHHrRxea zQE6w;uTu$KYD?s%(O6QHbf)L0(LHA9HDcPRPi+fY81(%#p3|&T+8&I4F(x{-{*0BD zGF(@p;-H$=7e&; zHb3mV^ABG2pABN-IR;W*n zpPVneQ92A)loQGi<%IIRIY22ITe;%hFY&#>{IK%C@WbIap*%4BuyR7FzRd~48@oB-^1=h?78uL9=w0F&>keIo)U%0x;Q~83cE2}YcYAq7^EiXJ> zPKCq`$0J;ARE?R7FL;e4mIujqjxmxFNt|p7YGKt$8SUN9snEp9sijJWtj)+|O(e0i zi8G7Z#=(B!>ZLZ8xkfKt=bjofr)(Hs@c2J8G2e;ycHU8PZ0A&1$NlOzl?m6ExobUV zlrf#VHqguirqri|>B_^oYa`7VVrQ^K5?f`~`AUgys2JkZ)p7>gMl%nXGguQnY}}O5 z#M;EoPUPG*R9&siS~ZfmsjFo)am`$kSu2smatZSmh;%jGIJS2yb>HYF~mp8y_p4#Iq(_M zsWYXO#$Ailnb52sjlM23>N5U<&vb^osLZ}gp)>P+NNvX5IS)HGFXit_l~R}%*E(-! z7GF~2otk|!bG+0SKN=(N9L3K63k%KZRU@6A$8j>PEQFex^{rBb(t~{4yabJ0B(*AA zC}A`bh;+6QjLJV84^>`r2G##mNyeC4Wf-|j_7C{-@ttZGC^d^(&D8@Wpj_*|Z(PeV#!FvxSIMr8^-@!tFp;-XFDU=f9;%kcb+bAYM|-L@ zs7X=xqrOwUjBy&SwEOzZL39j?lXgzhR>IGvzl&+B;ObKAB{Zccwa%CF%PLldm$H93 zzi2CS9=M`VN{y}PK%GWdT!O@NIlo>>yA;_+in@xsjirbU?n<`T@FqRLOStwL_O1Y4 z!I5jb%YnveT+21rAkSRJ{nv5#Wk@XMyuY5d7D+|wyMe2&1iHq&f#YkDU*h+DHTNjX zT#bC9oPHDctwl_m+|UUXHh6 z<$o`u{QZoZDZt0LPA`FX1K-Wj6Xl*KIQuxh1n=X@CuuwIGI$dB6u-Y0XguNvx#kJr z``PMQFcmnJqYv@hlfb9gKFxhQfN~vu3wC19H}>%({Qe{s@+Y|JnZj$H;RzpP|AU@JdL$ouJuXo`3P`2cYc!g zAuRGU*!vXiBfyVv?X%pY<^B_FKh54QpliqH3Wt1-D?Y*g46c5T_A%fmxcW1NAAg2x zcXvL^mCpg6(6uTp3WCI`x)Tp*nSaSI1@ONd%j3}7U-Q{Dzm|t zxNmRg%N*_N{2ljv9{2^eUn%_jE8P1<_P@yWU!i@W^Hr|+67cWXeyyw(zQ*1AI$!7P zmw{hp`*rrd*7sbD_-jC)^*ydSALu;#eU85k z{5Hqm=l5@RUf_=Bfv$dDpnV7UJiq*aD-HmikAKMag3gb)<9opGar9!DLto^&@3a2` z+ZTDl3!NYH`wu!l;f@P{u5A8+;~xTl%=V{cUj8ZfzR3Rfx%Q{*eZTWF&i@qnBd+=x zdq3*@oI8F9{2@>I1zX`yc-k+DJn@fZ=Kn{o{)f&#a_`T8KjY|^9RD1+kmFy{{-N_v zMK1X#?mN`^6~FzW^Up<&`DcDP-1#-gfi+|zXU$Xyme)$*ne%|@lA`ks5 z_g&ce4M#^h|Hjq-4E#0Qe`D`oJHO@XUjvnEe#?Eo0xn|vJAV5O@ZZ?}o|*9?pz_x5 zIeVn@@BH$c&L5bO7XyFG6aK*7Z-Kw&jz7|V2mC|XU&8iJ+;ul-iZm*RoY=S5{Y^ zS87*QR{~I1T=Q-!wVU-vd0wy9$nIwTQIc1JPv)QGJ9l4itD3`CA6M5jk=j$ccryG= zDMEjkDR3$!5dC4yJgR)655_e3gK~?Nan&`M*Hq7#nT&Jg9Q|WvGKQ6Zl;D%~+$ely zH}j|}t1Cabel)A9`ls`0>YA*Od!R^Et}5q4y~;nuHZDfo7+s0WOmc1rTcXiDwJ3e?W6CymhcpZ+vL?cC;e5Gp;b zVJlQ_iXO^{d(W-`H_BN;XZ}kHCNJSv<*bW2b6J_mm9x%4{!zk;v{mISv3*6s{T1vD zl(Q}a!&f5*>A|F&HN1qS+|-t^B6AItvo<0LDI;`CSVqv@2t6qeMb1*fx{-DrGLS1m zObZAI2m>bi%fgryAidMI8gYCQK;IZK)AUe2qzR=QE^dMbfDf*2E%hRXJ-LQj;=8WUEM9%2wwh_qcv&OIUAVq)kFbnuJuPg!KlX zQkk;Vb|f1m3qAd|Bk?GUDQCS2xkwr3VcI}BD-u?ut;kt#=2F_~mb2c@(;lbo1S&(li;>^RS+0rRO;gT_%vGhW$B}`Qp5DuyyMT|g zRnFQ4RI+$Kd}BIrI#(%YDLE;dDNVf(Sf#Dq$Tv@N{Re1!kb9os*D7ZzD}4|yGXtnJ z@j>?94^;jdD0A&WvT@z0%(bUTO-}=rxgvi(!xJKHJ%x9mt+cfl z`KK*sMZ!|HGFyalmQq!6MSKeGW^Ra27CB1^E7I1di+uEHp0y8o=;Lgk<4Ps0NL$KT zpW(Otz)!RNEZlMqP|54F>_yu81oF?b{H{!;oa9PdX=^_+&F9#D5l%W6IG206<*d(h z<(Fya1HZ(!Th4M_{uP>XmJ(K^ttw|JRaI&0%RC{nm2%dXk)K@gSJ`SlcSgcezWOTi zl9~dgE%z6&eV)6Ojg*qU$+HdszsB}kT&bKDnXAfK2auPPgSzD`^%38pMcRs-bpg_m zQcsn$B4H^PM5=m$JtZtBj+fA{f-t1>ljjzRvaazBd0Cn3k43gxS!63MMUCX8 zgcZq4O<7-`G_wEDsK=U-6f(=XMhD&Z}l`6Q(}eRFcZwMu=q@}_@JA2Yv1Zza96luZ2sbEGT7 z`qqAva&GdkDGB>ELgP5?(fE7<>k|Vm`Rm&rn(&j9+E0!HsV%C03HV<)X z&OfnH{n5pSy=)c`vEeAI`1QFJv-+kvMqdtogITex-+M4?%&?f2qWwz0!d?=uLu0%f zzfyensLW_|R0em!yJK!Hed5S;6wc|wzN6EMA0zMEjGgrGnT#E4Fv(S1#Z~RKquG%w zmy-(g1JpxNYMDw?&n@-opK2vQd6w}8)_juB7;m7?UOrRnmdI!9iR!~DZxYAxENjMZ z<*ELC$84%NIdbhYt4%p_9WlnVJ8~U26KQJF9X-~na^wz;-;75&miQYfuElP~hx}H| zI-bRMs-?<*gW2FTc$DMn6D!{h_Qkq24n~gOmpgXm7u@#nca1Sff2Z$9im#DTMJOTu z$3GyzAv0+>?O^<7?26?!eqU++oLMvSZXJo?otZO7inWoA zeJLTMx{>5wUD;;jn05ZNHe%*#N3Bv(_^$I)W^%`C@S7PrSk9d7d~PI!BRDg9#`UX- z-&#N1$T(|)Yg2dDUQ+n&623}F%+-z&a%PxwBzCX!9E+|3jqVeJW(KkXu~M;-cIJa~ zW;dgcaUqU+bKIFZ&Wut@b*|+dl}l-<@Mx9i2^=efngwq#5BF(R%6&QO7bV+f6{BPn zyo$?(92pfhmp#8+ZTURl5}<3@dF<7iY}QXVuZ{7I=Grr>b28&t@yX29_F%I5SXbCQ z*7lM4w9WpbY^I!6Ys%HyOs-iYStWu+>QSmX(|J5AtkKD7;RDX5^4!sl{kmEXw~tgV zos3N8YgX{DCZG2^m6}~C89U`_NZi>EGoS;b!~C8Z;MjOE*XLGfp3bq@aW1nev$(1m zpDIsqyok|8+hKIRlD%s)&noK+Up+Z|#eP(tt(N(c>9yotk5 zf?6zbt5!=XT+B-q@(DFguN;1(C#kDx4qsqq{vq+kCz~t|Q51{3;VTg5~pPI{!NJ zj#ke(l>fL^d@cRmdBwH&>p!ks+Fdj3RQ}_s78d_;y#b6s(E}iL`1JmqjZI{9HCMW; zt>`DJC+LjM$a0CB9Zc!yTx<>PEaHv-xPAsJv3lz*uBUGD0mqNLskSomT;h6wNIx6F ztiA~P>>9mPeaVg4oWM0TbGUv6gFVNkx^uAmXc;=fx7OI4fnLc2{gJgr#VfgbBI|eD z_#-bXy)Ryrl~=>>ju&g2HZ}1Tf8;fsUtO$r@k?G@zF=hj$ohB>^h(wXT#Kj@i~gL- z+3TTyW16Zza@!MGYpYRP_GI-$HUpax4%Htyp2$*YJdxv*Y<0vM(WT69#wG3C)i=3% zC2xTit3R?)%8fsA+XuP&CMU*A>$?{FfnLegAK470<_}OZ8AlJwGsd&E(srU5Z(!TQ z(TzZ78a;S=faWKdh?RH(*5S{v_c^u`i#2&7Z!f***<*C}r#b(5jwS#naIL;Rp9g*s z+wgAozKA{g(_Hr)M_(x3KhFW5Y2$y?q|N0Nx;ecK9ygl zVEf(6zJ5Y_^8G#5;eG7=J(gwt`SzDlwVx}evcHeB`)OZdWPYDM`Y~`iw$2{|Uu0`l z)cu^F!O?VVwbS_h1-w!?~Hzv^MI4*o40e{0`ga+3E}U4X!@KR(O!@ zA@*Fg-3l~1%E-^#fH$+9Tey}PVs2*NSg2cphuP}e^g7_3__bWf-ko^U+{|^iaC8SF z_d@oL(3EiRf#QweTu{7Tj0L@y{iFP5hW;aL7jkX^ekeyd^9I^I@GPT}j&Woh=25nH zv(*>*F0R&J>TaO%REzOmS%jy`o7vMRcrjir4+70eVs?Kk04(9$VtiK?an)NmXZ|z2 zTuyNGR^V~AZ({op{!m6YoupX--~>m@@Jd;V=gA}NnTcu{{wnVP>SdKm0cK5l8)qKn z+*06Dt~H<2qd@asUBcdDc)wi2{-s=L-2gLKUCNn<;c@SV%jvDshwsUIfcl~6{q;Cd zKdsanSb^us3a)w|=d3vJ1b!x$7he@)so#eW%;lW1(#YdLJ;ttJPjC6lIkyU5m6dpy zJjI@Q$5!Ea@*$uR)kcgz$^O&qJq5IO!Bu#Wd>E*gijjr-4PV8XwRnZB!4FHXn5${} z+h4`e$2q?i-;j?3pJA&n{4+qS8(7)Ex(Am)S!jN%O~tFt+*ZaQt^?{_zlF9DXq|-Zz%4*$Iz0%t0k^OB9JcCgpP(T*!z>kDw2o&5G$e%lN*qU5ve$+17nzWhqR z;9bDaaK;%?{`OqqZ(rm5=inxCudf5YRydXt`KP%;pT)1kY4!lW!f$#P%hU9L`E=o7 za;iOC@m03^vwVfK;cs6q{O$Xk|0+C2?)4?MUxgFxV>=ZdrF^H~j9lx-@TUF17x?W< za3i_dG>-Jc+0Sn;vi%7>Nscw0ZTQuT@TVVf{2lm`J}G(|&wxYy5cosR%dfr*r#S%p z7FYZL_#L)#uO9$^z;*H~y^!^e`6lPp63E}4FZ}Iwoc}i5MDBG5@O6bp-2sPsp6ldt z&%j2tceOfF{x`vQ2$G0r>$d`sa} z55a+q_LR%r4ZpdF-yYzKyMS+DyQuIqdDvZrU%eInb)4&rmQ-UVf0IY)i6@tPlq2I5 zPOv9udlT?YoR?p{6Hapy_;#+iAE@`8oa(W{!|n&l+1|mq$KX@VAG74|9!N%X&zc0^h@LZ-X1j)8t`qEBs0yy34piuR1+i_1(2-MfJA;u`stm65IhTB+%AxX}j-l$*(~^qad9sP~=T zuyQu@F0O)$Tv>eJs$@|IKMp!H~M&iax*!VaR}D{ zt;1vtkQ~p-OhyCAt8Sou0$Ju-_T+LO1%8xY4P4nvdj`%VH#1)C z8Kfm6*Ty0Xskw6Hr^af1p>gwuI3J%nx@%^k3`dXkOY}Te8nCX3>y9R_%Ut~OpsF2m zJgXDZe(K+i4rQcqT|J%G;=2B4;<^S$bm?y#-{aRa@0=>G%V@28;h7_i?y7NJ_rNO> z(Us_~>Tg`*x{Ti13`a_Imyu$69dCx?B$ms#t{Tgwk8$-k9xkG*@i*3!_#wEBE1999 zyWYmH-4R{-A?tPg5FAg7#OdO?21j%m%aypU8quXUaue6}2psIxab5ZhpDwzqiR((F zm!8J&h5NYDN_1C^>(UQ7(On-boVI!$4;Rx}D4j8}Jb*T?u(A7VMD`q1H{yW)YYC$jw1h^$k`b?H}}=&tU#E+e`U-8GW9E~B(u z4XPy?S#;MIxW2}6sqd@NU1t{8m58oHcO|Y%|KX8EcXh{geI41RiR&_M>j2W!;OH*> zhX=-ZHPK!1I#&Dq0xkZ=Ms(@JoVczU(be`h)(5@DW{l8vm|%9SbhQw>-yV_>q`9mYtdap$8}xLO3tXS(L{F{KcDEX8q1~J zRHM6UT$fSwRoWUD-KAEx#?Lp=UH2lTB%-T{qBqj(bkSXjqEGz1l1`PjUVd~}TiP(tR*RoY7YygodMqEEb+@$*VsiR)_1S&8m4qU%xC5jBebooEY;?n*>gqUZ-pTZ!m0 zx~oQXMcOh3?A^!}#&sFX)sF7!j-ofBE74u2itBm|*~y6d8rPK=uXc2o`t!tibw_vU zn^h$*i+OhP?AT^@i=&%|~pNKAHjT+-MlIX6)btQgYi)4-N>Xx&b z=q@9=65Ta8uB*n+5037tab3p38$TbJt2?f%9YvqGF6E2F&nL#q`1!LL-F2$Ct}0t4 zuFHt78b5Em{qsmnUq+5<$8{y5E74tv>rxt0+ET*$7I#!Rs~y*6bXer9s=rEfSK{Xr zOW%&7Pjr{E*$b@87Zqu1V2qbh^lb_2MP_(oyqwz;-DOO?l2a4oW%RtU@QL*LG25SV zz0qBRy?S_GOjBzUc*OsjW(_;5nYMyN-Vt*Vu|bOmbM1Rb+x4}Bj^8s#>lv? z#CRF+^+(PqXChjaSAxz^GnD6u}~fR;yUchkSe`R8!MxljCSFnn5$VpD1s2lDARM=)0ZZ?PEJJ*Si_r&E~G<#VTSuD(G|Ri%w3$G2y>DP|25>#wb4p*D?|23_1A9@+^>lO@&Rg0UrlG@d zZqwQ@6`O%GqIU7*Rhx*OKn;UcG$t1-!$fQfVnAENL{{=j30fE?FuN&XXj9PUsfAR_ z=Qy;tnn>;^xn;gIYO=6XmT zh-sx4)nuAE%bwPHVa^CKpq;}EaAq$JmXcvYYp?h*+o@S7%qnM2ikhin0%x>aC-a?i)##%Um4H5sij}dBfXL{ zE4kJhAm$XeX2VqO(KlS)p~tKqJG0nRJ8aL|_j+&60*C&6@u}ZJ^0JEm>O14R=%273 z3h-;BgN5MJx6(^tA5`KuI<^;q*JR@Gt8T*jrG;(}8ndV!=A4=4>_t5m zqzKb9PM)_8n;B2< zky%8z(sF%XGBB#! z$(z+@C--9B+P8PEY%(zVWq#+We4Q%Q^pu{mqEE6D0bX z$-JmnSm^DX!ZR9QC+!Q;p1Bu?%DR}0()yAo_hPaxhJNHIQy7QlOLaV&m$gk}ay!Rt z{GMhM%9LwZvpKmJ^>|V~I2V{ajN75pO`LV6FoMiFaQYfp4bGaSTY&z>ot)VY9XmJe zD!=XK%uc>x2fyy&d(Htm()Vz@4Y-Y?z2%<0T(_NltK075uHDeI)ou5evA@5J{r%j( zfirv9?&r5XP`#N-&*%DmU`XC_pv*@HIJ=AeU0ip7whpS_&D9rh-EQci!##%zr5xg( z)$E_g9fxQKfCo5txNz{pT(=KS+Torf+bj7j&jXm;6b+L4m}7Z%Z-lF zE`)jybKga@BS1$U@IhF6Wv{up>L-uV6eZ242ec3Vu5d zJkHS-Tx)j8OSt1on%NLHqN7O4H_* zTmZb1Yt4XkHM*;-xZ`@7_T-*oIlhwLZiLcj1NH8^k^AQYujd-=%GRX2hG*Qwz3RTM zWqULC-hjU9dVZ@F0+fMo;dnMWGA-8TLAn8WZPAzYaCAF+*8|N?c{>z8187$5*YTT~ zij+w2pqcf^5pXA0SU)fsC~xQJPM&Z(nlf`D-9v=1&B`PG|?CpAwsbP_7IemSZ`Q^V#2g(0_6#7(ZNbcLvtK3!2oGMkxBd>p{ zJXT6}*3iq;`NElBnSE6mFU}^(FzpC)c2@pNwtD9vv)(F0Mj}W?d%5glMr)n<$1tX< zY_*7QbMB8UVD8(E#NH0r$PLl@l{e{e zYW+OrxJYgC*G*tbi9iWX{;Ry+$Zop|ueEw{q#~suCAG}!I}68+Y%b?jUQp6Z^#COU zIk0kpS+SEFTbW+DK^a1s!WmLbMYeNQbByE2ZhZx71MwwZy0Ip{g1g9-!{bX#1#83O zOH2i8-S|=(4%YPgi0sx2PL!U5wc+rk9H$(nOxMO&JkqPAsPCE5_uiKX72X7vKMR8Sv&uuD~9RNth^(-0_l4OJW0xREotnbm{P}}zCo&&$DKL8&Tjrk zIashJrqtGmwUOYfJO85+!)mB)4p50zRj0B6zNzj&UCTN2u(~Sc!Hvv} zN7=uSwi&2)!0dyYm_aXO{}62}@G#qh>}>-cVtWC5=K@{rYu($%+! z9>KhoJDKCpD^R_awp5|o2lX04ZOhGQi8Ag+x$H6M|ZhBZegf>5G*udg&LKRo zRzs>Zq+&yAHKa;IlSz2=wHi{N!5Ju38j?@=bhR4P65UA~oISYhWzw$F&}0%$eTI1U z>ZKCDleQnP>)$&Dd6^7dtHG6VDmGLvlc9ZjyK@LTdTN!1!9KnE@mg)+!M}L+CX?{s zS`Ce7Z?{kHTe!E@Y8YIlq3vrjv`?>oC01!j#fC@O@6H}<#^B*=HMBiWhVtw^6K~$e zza$u}7a*TgT z%_Q8^Z7`GYo|n9NM_;Q!kKB>@^bTLKVPv%$Mpvcb%XpdSYci5r4SJV6-{skxDh>Lb z4EEz4SgS$*l2mM{IfRw>t7orSf}4E811mP@L6W)+wPJ%+8q6pB{o>g>e60rkbbo?> ziR+1xR&405(vZ3h|Hurs;4k@v|0ioT4Cm9UpNO6zjc0G_HVp0GYYySxa(%7aV8w>& zS zYDo2lSHh>)+E&JlYRO48thQ%wmA16-RR7+{T*k%MDh=`JjciqGH9S&$d98`1HA&B2 z_pRG7dY|6Z$4X_a)M{vCE~Tx36&tL5RXuwnZ7HGDXsYVj`(%lo(x=z@45`)7uFqgR z)YE_Q=8b1>+ow0)yiKi!8ck)zhQw6Wx(!B9r4Ck&ozk;6b+DRR4OYgQ&2?5`Ffytw za}BQ8@F{-(Oj&`RzE(r^=^d_OLye$PvZy}2P4$MMJbM#CrL}XYiVdmN(5{b_iVba_ z-c)I5SHo&YO(`{`R>M%9y~EXQ_y&?ze0on;u|eNmJ$nb%ZTK$dtDKd}Sn=sqi~0id z_2MCYdYd?^S|2Mlv6d8ROBt=Hj5TzvhE&5!t%lTXNM$T_wY6e{H5qE%hISlPyKY0R z*kEO>cEtv3HKcCCP!$^n*J`kaL+WGIiVdUn>5U(+8sl2GK{+e+vD(sBm9qxdYUoG5 zRHZE?v_Ej%c=P^&Gk+{P=Ndbenply%)D$I-s@BJfXRrRcwLVrnd;e5qtN-BqpV3aO z1nTSC*QZ6o7-==r>P_{`b7ek!T?Kh$&Fij4J+%?W7LEGYqER1<9?xu+>g~recIE;d zLt~4aJ+{coW1+N#oRQ+x8Z8DYDXLRagQTaQI*A_M@lww9;JKhQV2pkTX#J+kI6DTY z-rZ~>J;3#BFE9EyBk{+uzk%)L=+HJGPpF}~0v*~pz{@$hf<1LG>cX!?hqe)T1xHu1 zcLhEOYQK%R9|zpT_Nt-RIqEkt>( zOJzOs#k6nYcra4@&${DH$i=j8O6!Yyle>ycsF#d@Sc>!4OG5j@CNkYiN%{o2@>69A~UPJ|4LnN5_LG%b+1LZ6)%F zNO9;B5)Lhg(0KOO(gt_N3EAQr_{FBu&HJ0p_-#+se5YK zc1SU7HAkIlFU_)*i*Cgr`5Z? zlNNPDs)6d7`lTnTmhFQS|5n##pfh@wYK~ea7OqaIUuvUTHZy6~tfW8tC7n^r9O2Zd zS;$_r2e3CA&C$aF;$IH%ZwP5`9;l=9p(^@L*o`C{gFZ85Y8ORwg@Sj zuYRdn>YiG*80~RXJ}l{;n&lbMfAwbwQk`4JwgjoxsbA`pUd!Q}U5Zo-)f_cTE*P~; zjdP7bol&P;fl$|El~ME5oDoQM??|qxWon-Kb!5^XHOuu3wQNPw8Ffl+lhsBoQxDaj z(MYvTRvVdX)I+sM%~Jo4VOxz<1Jx|GNo%dHsd28as71|4wN5SbjFwf+Qm0(;Ro6Tt zMxkb@M@B)ZYig7FcLLj5q?HHNuRV}^aMxtsPH2|ex<1Mlk3;X3rxEEVt#T*H<66)YB-u&Xrl1`~f%Q?>WYdL%Bm-@7V zD{5Icw54pt92@uLH{S)hf;+O!DqFObTno#!KX+=y93it6(^?(C8TCv1bpY>TRnjT7 z%<=F*w!(fn2ELxHr4?Jl**EaZuR(_W+AZl<*@`(TX8W}^=~`GZ`GeH20Z1*{!Mru~ zYYJ_)TvIrX%xk zbz8?MHx20;^E&p_wXkBYj~&i=Giu9LOn>7Dw!(_(X{=`pEgO#JgcZ}@IFhZU71Q51 zit%e!(lRw}NAAnEOq;cVt4ATVXh*ZJEi+o>XhyR+$PG!$=CYSc$=V ze`U)xoip0CY`?TtwX9g#a`ohnY`L^+`zPC`mKD}Yk3QQkEtgg*Y?eNuwoS_=gQXU& z+J32fdVbokuvuZhvgOhz49lf$tF~V)EteWMKj}<(hFY<(T-vg1ztlQ4ON*uz)BkJB zerdC+tyowteaCFS)VJ1FEL*OyVp^`SV%dIav$FkC>$YUS3dneH#T_`=2DL3`z_^rn@hPA>$`+Kb19c#jdy0xEXu`5JsGnp%`G&q z(p<_#*kZFQjr>~3i0+tgX60l?aV>(GmGUxbJIt)yj*;5glUbDgkY-w%MLCsmTKlyF z+cb38dD(Qf9nfZHb4Hp@XUx?ano}t|V~z@xtx?-*W~B^{&Lz#PG|$5MrkRzq(LLv+ zW>(HY-<-FaSvePd(kn2havr+m{C6id`I(&~n^|ebgnGRwY4IZV{U!8i^&a~0z4c2M zvY9urGv}AE$r{_Av&I?8z3SMaC((=Nhf}qyCav;&f~vu zPN{dgg0tO_%W3CwW*%?a(Ngch98x{fIc#(3L4(;_$+a%XUD9tbgfn^!UFcIo_)Uhg z&Ei*B#Tk8t&isBuIio+iBfrRM&J1U7CUO{UC(bxi(U%y(*%`>;v=z>Xcj!@=r?!Tk zsO25W9n+B`XpP)4qTP5NwR#8ok@F*aQv-c<6lX@WO{2$6=B%FRG^F-@9B0%*V+P03 zho;bH$8g@L!tIdy2F>h^Lyo1bq`#Ikl#CDZznjee9;|xKt^6L5A7@Oed74J2MqZoI z(&n|vt8BKNnVx2~MTU`5E8`oocbX+?kF;NES$xygd2Pn18k1_=S~;)H=yhXK%}zB& z)yQ{qSM4#%oSkG$s&T6J45eefy+P>+Z&syo`o`rOv2QHDQTs;q%PVarX3lGij5amh zcN($iW>*?rY=)&-UuJ*38hLF-(u&9so>Np<^ zx@wq_-sV)RUq*UI+;@!g5%=vlZ)UcUpT_B{TSn_U&insntulIlPSP!7K8^kktuhPT zNN>k^b<1c_$9Xj@GRTebc05+UjLDDa?*+UwHOy%Jg}gm=%MA5J^Z|9tX#K@#k8jtE z_MOol`@mARCG<3PYZ=>8^hw<^T7MZm)*iTmZ8?3{QE(Tw74&a=Y%n4inQzv;ar>*; z*Uqa2Mtti9IKr(#>K!=V?S@pV)Q+`Dvy9LmpGMZTY0RC#Gn^BxWE+NDMZ22+Up`t{ zwRhp{aO6tbUHOiKk%PImg0ud&yU?!TcW6R3aZMk>nULRXBInH;6_bpyBlK(%XY>&C z2lN8P^Ohow7B@nC0M{IYoE0rWPT{=cw0?q~hyKaV$nAKW{gC!K$1-O^i<4BR^dz=J zI-ZZ?-RQ$O687eJDzZ=Nd%f8opT^1YTpdTR=}ljp!24c+T)?%SX`I*3m_{!P&FV>O zM&(Y(ow(2O-jUyNUe99&J>C(!l16D+85-!n_S#OIH(q)!dyVwaIY>25zhoxT-rSW< z%R8HEU6A@F=7@G-o6WEPr{~#wLBqOCSpQ2o*aRKIrMceNjBljSJTcT~SJ<3XA0K+OtoO{=5Djtn|=%3Px& z(@`I9d+zYvZL?p0E%vLHW@)n`msO7`ctwVwYwDr1u;FNu{%~d#QIDK|$tzN=WrcpJ zO|`YGEnX3ASZG<9SEOzI(yN+X(z2HNm?-;L0=Iv?C*rQ#`I;F;`Su*yN?Uy=L*0Qi)p=J6Ig?_cP zUs|lu*sp3U)-m25typAux6RvQzHv(}GaI?SW)-$9TQM~&=d~9)Rp{Cp`n~hf!hVI# zYN=o17%i(^74}PfBdl0G`_;(bQA0(m8u@+Yi84b-w8pp($2wy`^eugB<_xtrPsj`* zN1ovR@5jDAdGF-6TU)*f9rNv558jGNzPqBHghUV`H|Svg@*CK1WUXLJ zc|x*i9L5_hvW04~(H40^vSJ*O@c)-z0YJX~!x@n`q*3|kG%iPmko8Tr#Qk4CPe|7P zr~r_;|08}iIBB=c{hu?0f{nI2F|WZ!oAZRs3X+rdcw$bSx5-R9BXR$qOw6itg^qLo zYg^9XNi&H^)!v-RU+5V3zZU6iw%N!tc$%EFvl}*|W4(|Ovs!TfpUXXGH=N5AnQ1c{ z?Q9}dwP3jdfEh&ZU^83DiYuGY;NHmI90d<;aMA|r{{?A2TA%x08+jpH!9&}Z<7x)l zt;rKIH|R1pBUgiywsqucku8+-gmP|>@vB;#aM*)WjWSX4-1Lf3X!g zX?G^JG%|#YXswQ16@4h@2?h6m)B(s90L(19hfPje@vz7ZiaG$nI$OU2K=9CtoVCsn zdLS{_2J3(AnAK$s58)#%CoWaI?P0c$AdPW-n7#XmR*m@8VH_K|dOs1VB36&`x#h6K znr-wL6$NCYeT4S$gm691^%a{VSD)aHM;kth%^Zdt#$B??K7o9M_G9?^E0MC;ew=nC z(Wy^x|C4NwBh3ej+@Pnh!^7Dh&L@pueS*l-C%O7G9@?%*k+`RM#!6WK%^j-d{x?G? zqF6tPCC_~Sku#JdSIgN#;(*n0-r~{xsbvm1Q zLS_i%Y#}qWa|M96ay@4VnH!YrEm;S^JRyB1(Rn?rxyi$thjcx4BlDTQ$i94LBU{1x zAAVNk31vU4WronX$-~kU+r(I7Zjf0)`dnwV^0RVoP~-`{3ypDCveTrMyZa}u3A#^>TxRv{F*_@Ak8_y`X|07T6CZ2o;_WxGo ztz3`Xpv?VWuCAn~a3|Xxn{$Kotn`hdcBSiIdRs01ta65sxjy`alE3)2Wp)sREzt6H6E6$ zrutc{TKHL_WI0c$Iz#Bm%^5<~-d4Rlq0IgN3H&U*t;hs2?|K6J;dwpF(WjCh7TH40 z&GKibBbgw#{-&Yo;o>Q*X4IH8H~JWQ zw;2c<@Me!qD+J~0k}}Z9B;#6s!AkSjRAaI=&ZJjV3vKF^{2%kA%Nf#E2|peGC(x$A znZ%q#n`Ys!1lp8wCOw+!+~}4FQ%7q|o`>gFA7^S=T~c4?{LNlaQEBr0&2=Tql_u-+ z(ezFJPxwON1qIGjzv|IEJQsb!j4(xANwKIa7^}hyx)|Ii(5AqdYS);|8PXzB;!Hc? zf4rBrCBl?_p0;r&ainY8K%1`TYCW7uKjtR<8ZE~yY}LMymB96UtP5^6Z2g~`xxW@4 zjrET1;2!-S?M=DHWUhL22cHhisTyYzVY-X0s4f|`kIGe#$~cpJHnnl40%6ie5@-4c zqsqFt$=SF9o=`VwirZvJ8{!buGdOm?O)k2s=hN^Lfd@Fg z2N}Lq8EtxiPgK|PE_2Yt8eV3iaV781i!*IK!W8T?8E1L|KTDh`yshA%v5L2RG*+6- zt9mVQro5^bD|rPUO-7i?>v=~0=k>hcqZyHA0waq`g%y(h8K0 z3cmM&;53dIzRdyPG@?`DMg2i&#H+-S`hnCKV_;RuKFA8Koa$Cs5o6j?rAZN=h)HU0 z&e=fL6v+8JqGvhh$GFB^>B>0cRs4>|xvi!xSHluvG#1l-BNiF8JaQzR(PlZrDRO~C zX07Yx_m7MyW7*7<@>g;8V)YGwC)eMtZ09c*`BmnEMBbIrq>+tfB&yMGMhUvkXiiB) z4w}p5FB%zL#u?^(ugLw<3i&%4lW1H=&J}aUZVY2YGa7SkWP3z78qcYHjm$GM6O2uZ zJer84cD*%6Q5u65d2O!$`Id}~c8$-NjYRxk$g4tDAF>elJ%&XCwVyMw-t;iclDVz9Ul9!&usxNWa$# zQ1BT@zt{4F<|vJUHzrhRgy9m}rF@fV?D>t9Mk@M^l*S4Bjg+qRnrWhR?bmOlwC00Z zDLHRtLV90D)()We`M!*1?@#Yj1B`g@NAL5UnRU{a{^&b1a=s7!&-Y~xi|=a;`^E^1 z-uk|bd6YTb`~)%59`rx+6U0ut)Bn^VF;!W-&5{yj71I@y70Z?TX=swZwZTc-#AX}m zed?jB+C_ds6KCShZGAj$IUmyh*xEih56uW;-%|9*w(}wVrE;A=f59A&>n~fY&R=Lw zipHqhjjhLal!c2_SgAywZfH*mGlEg zsHhP&j@I$Zm59h{5Lb*rZFyc!~eh!oNL=FC{F z$!xobqKOgT{JY4`8^nkiIcQn~dzfQ^IeliFbwiqgW-oNSFbB|#GxN^ON7J4&)iZZMK^EgN{U6S|foR-_33_f6#Ht-`N!$ZGd@jYL3~0<`TNfqn$8gF56*s z%=I9%=d>rI&^NOMwa+<2&-}a5jOR;{<`CvwK6CdXdvFZ;ENg+f@5sE6cWUA^}J-m{J+-n|7yeh-*@9XX~X<}Yxv&UFn@zx({G{u(voSplwrNJ zXJNmzUe=4yemN#8wOP~I3oBM_zqDN1FD+TNU)rp~inY&v*)s-g?lbl6mm_Yq6&uHy zdiHBHy|5?0yjHBf{nBPtTd@(G3Ck5$OpDdH*?xsBv#)8tv{}_w%<<2jEB`_h`?4=t z0a5+fA03!PME3sdAHX(+m}#|529_zTdTI0J4%?2^uh+BxhV+Xb#HXxaC@X>MVpEZ3 zoxPF0X~=0D9n5vt%j8cwgw0s&gJ}3rfa-mh#z5ryptv5x0W zK)#7{hjYil$irx@Vrb2V!)e#EcPP@xY`MA)Mapt?6n$m}at5E+z%#}pkL3IYwslCY z$I)Cn9C;M&G3>b(b~Np=?5#(-N_HH3MelFb95}|%#I1KF;D4Kp3#gHyAh)~4ypBf z3wNA|Jdsbog-;xxVtP&jqcJY~G>%Rp^5-=6-^%u8R;$c2Je}&GkD4vm5>9lWS&nTcXX`_4m#_am;6fSuy;DrRkV#fcQo=0 z+Kt?O2J&oL<9p5|LdS@rx3isvJeMQmtj_{DIWNhxxOWrJJcl(aqpr{AS)-5}Y0u|) zBdEzHu3o@)ZsG}6p35`d$z~MLd3^3&9G%CS*SiuTGnY?X#K|e~$d${XD z*10a{o-5cc0Zq9g$xC>;@zj?hucUo1dzT@vqP?2?uRzYHy_!*Uep=_c45_aq7Bd2Q z8SORP=la*xwAa#JiM*0$7*%~0$cnhk^&DLV=3;E-4Qy9~fjIxVk!#{F@8d`m=DnaW zSM!XUxa;b)UUd!f8lH3un~^^^(~7oShrEtY+=dNUfLy>QZs&n`rSH_c7%<*(cYPVxbsb|2ed zq;WtWPHSKH(|!=-<%2x;0k*r5_tP3HeK+!M?tPHw+>6wLJjCalkoVC(#I^g7AEAAi zJ3fqjkk%;a4(erV(M^g;XBdjJp%Dqo=^e9M(_UiZB@x&F0=@9>0gAiqZY9nO8N;k&foX!su6H<90^{XRa^O5{pD z@gF>^H}c!G|H1WdBEQMe54ip<mfNPX8A6RPkcXMe-~A821>uSdiGa{UG53p}Zz@>`zNQ28C7Zm9e(XDXH7 zb8iKp;P(xkDwWC~8X7CR@rlNY_)h1FbN$Yh7n$vM=Gu$MPPAPrjg>zl|HyN@@|=cB zSDsKocHyWSdz~uXII2{-({`%#s2G{vgJ(8YdRFupdsaHr_T*Y;&UB~k#a)faMxN1| ztt+w@Z6DgM$gVu8FRij0pXkRkdm#59j=ev}JuCeyVkZ5$-ktrP91Y-lkIDeHUX_7t zy^+0n#z4;XstjVUFLEGl6K&thV4l_wDW~X=O2S)sQWy67(hlLSzLlXoa{zKM?J)KR zA_wy6VVoOK8O~l4av1Fh+NR1#o;Db1-2JGE_~@vL{_rTS4XKRct|sIV&W+}oLo1`X zcW`A4?NH=Uo-~$iIC2baGkYVDV`;}#UW;!$jwg>~Uv|^+JgF0M1nqe48c~_R(?%o5 z(N5t0aY*@rCvtX7Wg^>HZ*x>-*s2*vG`wx*-E?)1Ms4*|Eqm zd}cVUsJPZgOF0N1K?F-QTu(&&ZWzZSvFd}lXDDa%CbY{#Ikt{zgWsB&h_y+bOfDqxb6Jq&K9V2F>~^`3MBRf!Xaz?jcn>loIcE+QB)N~|M-rWp3#nzz zV$n47WmeNe-mh)v6ruU_H*uZ!2ed*Oz_(r}jznAsXeP8-d zjeG}D5IvsGdKeO3)_BA%mzLcWl&Ty2zIcFwH-c@Ag-e{mb4VqNcRh_=^WymYeTLGMSh#es{KO^_cxA8*Y=({^rK=Vu%88MTF$Ps7Y1LZ)pjEf zPlV9?JVzaC@y19Lb=2+g=JnY-V&saEtTFW+^(2pUGQZ^!P(~f`n5`cV{f~-KG5^Q8 zQgGxC7T+x@1?L*>9jy`UFa2`!2RmBBy`%YqYL@+SWa_WM3KzZkmCGNL4Q>d}*Q$x_ z1_~_yn>euCZ=${8zM{tRzlj^GC8E9JzM{;sz=<;ld!%Ff3iMX1>WZ%1aDm2)`-*70 z(k5Cdp1X{1Deh|qV{pUuN2A1gwdhMyuj-G~%8TkQL90c4Mc75%#nQ!gcSh$$d_{T} zp%vosBJXm}iqMbaiukbOy_kC+#u_nW@!|#OjJ>@Vn^nlwO?{39XpTLxC!0AK>Wkb| zJ?Z7@te(qGjP&Z1t13OPBwv4vBH;4EiGho`2OnHFG^!I_Dvp!9I$2 zx)>DMsuvr0Vk2@LZN{#Tx#DQpYDmwmSxyAB-t1kPmyJFshUY_n2N1XnI2*kad#W1r45#jfoy z8Noi4ql{gPS_gt%ja`dc2Z9}_bw;qorL9u86LKeT>y61)Z)8O2&i)x3iCUkLQ0vo? zBHQ(`Yfd_C;u*Nb@|N7)W(Su+=be?CzUU z>p-wGb}efCZmwLA(CQ13fnZ)d;qzb%A3)34;80 zJW-7LNu(Asqt+tZ)u?qDuNJ`;ul`4nW3g*d>u11@ttjd*1SCgeZS2AW+T zyB4($1iKo$-jk<(iB0VKb384h*3Nq}b}ech2=>3S_jzz-vFqm&jxBcmc`)O^uEnJ@ zg1slteIDFxPjF>tRASeIkzb{)hh2+V2X>uN>p-x-#dE~2tsC_1F;@B0C=ij}AT^rBSSXrGAZ09qbD|)yh*yJ|XL9oTFMXodqP66t5NGQ zpweR6V$;pY)(CdSt`kztoN7wNd6lU3cw`y1o|sVUz_i7#rz8)&8t)B6Bv4f*&c+-at9@3JN4h*87+bX@6sO*mMsPJZdYhBZvxGVp`820^tTr+4!HgnzI!u0@0{=sQB>d!>{j%r-+W0Or&Nl+juOdSp4qkm)?V4aV%DOEa&#*SD%R7oz~T{iTEn= zQ3W?uu3JBjPwd6F8;5M>x@%s$BdxW$H=mh=d=2gEIDQTCwY2;2o-4>bxOX4+_CoH( zk!x6gE9{@`XJwFU!5O;M>$?&)b`-~lBIOU=I`+?~TQAF0W&&-So57lPC(;j(VV3PY z!0PqWi4Z%9eP{5;Bh4?&?4QB=8JUA8^4ZM(*_!v$iuFdFos2w{wj&&%!AI4am7yN{ zr%Y6DLo2H5)>pGKICreY0a|8dkcld|8LU{}F;)h1{c3T5I-d?E&{`azoA}g)XmjQO z%}i9m0V=;jQL+9!=HO-sUJMd&0rT*8^5jd{<}sI#>h)r@m$C&nRl)dKaDZ0xQMKm% ztjEV7ep8?QQ&b>xfSMtg**{yeGF;Am!AG@qtPIZPbIzcsRptNsL+~_YZiZlAknuB^K!ck>wuWuIpRV3o=V?oRt#J%_HNNw+PJw66~t9p!|r!kM|g>Uup_!wFh0lU*fJBt4fq2E z2ZJjpwfNPqW26q2t5`wF{OWoWnfEg|KyTm)*|*YP$gB+J0Nlni^r~D{m04Y`&){PS z#?OM4As9b{l_6L@JI==-@4^R@kMKck#+~eE#w!^=Mb?7%GdR_Q_cL>S>KBAp6@FGr z-)cEt)!iw2zs$-|W@5uv$`BuPbK8wDXeCh zQ@yo^CGV$2JVy}?Zi-p>IXSMz?VdBOgf89zl`Slh#!sV3j3ANm^BlIK%1j_kQENt?P%F!vjpx!DVXCey za~60~_&?_DWNhgjd@fg+(F>|oWhVTeGVfi zujvJq5vDRXRT*cxfzM`Es%pm10$b8^6FX{IU#1rO=guHS`b)w1S-;ARzEXSY%hY20 zEHhDQ+p_0V;7n!zCpbW5r79y#a#QIMRU=HnN+nxW_&jJ%%wD5 zCD=c6O_@NI^glA=dD-&`Y)KC@Gf`Pt#>f>`?V4+?pO*7w^7`qv`ZC*arq{4iS8okZ zAGTbIai&vvwkT42(57Cj2g?3w zEUvyubxoP5G82_$s=ckhtokzT!I|nIOl98Bz?teHOf4(R$d)cz6gB-sn_^Y3z?|NR zZ&vvpnL1Kgrlp_NHqIo%bPY(A-j+U8+q|FEXj3qLwyrEw_N@Y8 z3T#OXDWgq+GnEl0y{*44-p_kj1N=~0$&+P0FsBjVRL1Up2(RdFFsfL$%WHVyVbx~; ztY2j&dsxdsn~WvP*wWVUeu_5L$C*Tx$~aT4$}$DQlq>iJ!epFEUe$~GGP#0ZQCTMY zSuN|!l+mW}v&5Wat7wTfW%f_k@QSs)z?RDFpW#F0Ix^vN1+j_ox;{oi$o%^#*!w=YpJ-vZ_ z(i&4I(W})IKG1a$NEm zj^mCEcn10b$8+X5q_yRY*qOr$l$=y2vYh~SBEE4Fwz?OxC-?gS_I%cw#CSe9K8c+KF+zc`UtL44W!+ato0`Lh3^}rj@_yACRu~e1L1aBDHf?Uvc&7PL4%ytlBb$_CxH+NhKP8H`mr6&1Y~WOHQh& zSNB2o?&U5chQ`v~%PP#+{{w8h zgWlZ7-bXm=8kYII53-5S=x12vSN19~o`=|WN16@t5Zj(eV@0hR{1Eb?v~RY|!)$xu zGd!H6)rB9yPK`(IMf(VQ4w@q#3oO2g|?ABBf#Y%)CNvTHe-7%fHupx zgzb|(kdIlb;*@!H>+!V810wH-S^bWlN@r+}jG0&0$Z)v>WCw6;s>Q3D`KXNz zcYG;$bsgpO@ny4i1XJ@fL#z6~5PfsxQDYaOMdF9Sn5~bzIBA+(+KvNi(Gq&O`m2V> zsGD*LIFjo#WfX93IeksdvZt<~AE`C=ziOV=%=>Lrxc#FRudZ)P9`Tkut*^eP;oA(v zA-s zzajf&_A%_SdJ?md`YGAp2u~xtj_hyD#v{0>Ox zQ*ad0hggQc(AwW{#L8ZW{zmv7dL8;3g{Kj|hyF%;Jq^8!vcFOGG|V?HaEh|0p^p*% z#+E#d!p8`&qwHzuW9VrZll;ng8m_q)KE^G033?u_eT?uuvZs-KjN9=N^f}t&X}Er* zr;#h;ZrRh&#|VGJIGI=8)6mBVf8*tO8hRLd7unw^JdN-!oDFC1B76^hj7Qk?K=vZL z#aa}@u(!rmWUH&K)iMv+Y?Ec=(C(W5BQMb~#s>3r*E9%8r>tY0N`V71@y@3XP!8KSWIb4iCnVvkiiO7ju)BBo=ln39_t)vl^GOV4UcW1_*-d)c4GvjJ1SM(5F@tVwaeM5PZrf{EL zp$u_y(}*X?E3!R*S>I6RrK$XV?XtOo)A&zii8D*EE8j}Crl|7ax9rZh_q&=AD91?; zj^#fwV^H5vUZfq&_o5S1FL!8Gpmp81{n9nwkUZL$UV^FSiM|gRw zcA_8Y8_L|WfPScNC>xyB7W5L0qFzML(>Ih6YcajeG1kcHo#|m>MP>{xp>H|v$tSav zUZrnnWc4z7k{D7jaTz~t#-LuI@zpEnFZzV5l5c2a^-6k%TsFp1kKz668SYB|8q3?3 z1rp=D8FNBvq& zuaPS!^s8F4V&r;7j{16jT0KXV zT+_(@s9&g+bmW;r4|Aq&PZYx%j&yX&wUO+bF|XBUHOA3i*@aCu#i$bHj5vCzJ#1g>%i)1R7bt#fKel& zmaUkUOZ%l2E9+O-FSV>A`js`yjCU=UdGA`W&@Xe}wPLmPOUqSQvBG}6Qu<{dE3DXZ z`g7Q?Y`KErbnEO_S-;BmtCoI+W)(O}pl2AP!p8VfJF)|3T~m{H}lw!W%w6) zTN$}xWvtkH)hD_n@*Gyx&dPtrHRG25`~UH`|Kor2H-Gat|K0!lzy8ht{r~*8fAc^6 zFaPd;{;$9N-5>t&$A9{#KmX@{`tA4s;lKX&AOHF9|Nf8v`QQJiKmMP;{r>d3-~Qvj z{N<1T?(hHppZ@rl^gsXb=YROeKmX~EfBMVc{>wl9@weaK&zHyVe*43p|M^e+_<8%? zZ~yRj|Akdf|HJ9@d|#jU-_?J+z3bQO`MdvKzWcac9_RYa_xt|8@!|jUCqA5hnm;}K z>-l^;-5#gH~p9?$plae7?xN|)E=cD?bL$K`rGT|@#S7+)SUUQUWkSGcD8%FGD1 zZfDQJR_BL4kjoy7S8Ju~Ig0CXc_x)MQ4>nYUPa4&gv2_Ms{(RAy{f21kvz{2j|(-0 z-X}$&S5g{v`mVdvBWEx8abjJCF%9$(1^ZDFsM$vWGWh1~u%Vkjf z1m#t}&gTKt>T?O}>3qK|AHpUUO}Jhwg6eX_Sxcr3dH5ip{v)#9fJCyuwd&$_f82?jKvb6-InQ zzem~y-r_>bw=k6eAAfa)anC}Dyv9l)j8J8cQMt=KLqh|c|o$v6Zi1?ct1`H%@$SL zsonvZ<-+Y z)4lV8r#v_O>Oi95ryIs12^OIl^+$tD_adM$R~2ZI#S1>|cbzPW@6=&nrL*CLMbsgV zyQ2;j#(l;|_|n=~hA2PXk1$FzHyZaDp2mcM-DjilErIaH=SO#Arv7{a~Ij>*zttaUUuZG-p|0n*p~^&~vtk{hnW5-P2(rk1-6SYffV z*ZBddyAW}5Y_HqmiaU~6mfzvKP3o37D{^#y zo(Y+?Wzg3`|J&tqk^kg%va@fj5|Ow2!;3yDc?-Z}pO-%C@#uBRFT?i$;M}4|$#+fe zv~lcBVeSJ5J&i>ov?JQ+cq>ub9f-{$e+ZmgRG{uW#Mf?*7xw!?a5Se>uBZF^&KW)5 z5?Xm+S2%KOTMOZC1Xs^5a>B3o zhy&1VEfa#r@j39iyPQS3C-K7j^F_4yMAj|Y;3>Ap{dwX4?(Zks@m;j#igJfwd*7Ty zTc54m64jr&=uD9$$* z93qRUd|s)>z)Q+CGuM&+M^Fx*!BLkz9Ej zloF;3bzdBPaYv3&m#ZT>1l-w6;rHN7hKk#QmvuxVb0355#r9`4O=lHGxxFYeL&UCE z63)~kWa{B;-tTyZ*T<9Mzr>p7*NGyu8XG2Y*n427>+^g=x1OIcG`6-Z^SItfFJ5l9 z`|Wnk(kp&!u!QOIrWRn1Npe(6IPXsM@O9e zAkp$OERP3qd0+1@>ICJCO&p6Dd!(YnyA>?T0%5J4Z?D|+U zA<7YVa4}rXZlzUjqTjQ8qS8NBd{ zvL)7^?Ed<2cHd5!^AVGc3|9s7DyGiZ%N&QrXr`k21d*G>yId>R3nan^9i-xt`1A;! z#z%bh@Z8P`Wgf+|3Jb4A8A}Cxgb2rVu8)!^bzY}M8f!OmZd(+R#bd^2BX(XK^f@Sr zwRD*Fd(wsZvjt2#j&i(`PdUoH#E)|>H`-018v`?3{jd_rxxTI#=VlLb2(GJ97L%eb zH|G;Iq1U<$H-YRDP&Rp6>LRkg^QEiuym(~`gAKfKH(6|8-k9ZQUN-R!ltRHuRcQN4 zr}K&UJc%&PIjv{3^Yhhv%$xqQgJbV;d<2My*&I;QaC^?wLDI>N2+@bu{z>R;zUNdD z-{gJ&#by8YjoXU#;fNL^XzGw+5fe`C2vkAt1B>DgR^cj?PYu7NaU<*#JZw~>fb%?-3$Cf}@yg5OGhaDDX* zC<4~mZE|EUCZujNn?AtyhbiPCcgWAb^E)Lk;0Vh?9pNn^N!OZqTlTOCKt4jFUHgdP zntcnv?Kx7`-`mU-$^HF!&;*`9{REQTcj%E43tvz7ZxioJQIOd1G&01V#1uT6FB#D< zMn{LVSj_Gms}XZ-mwE;{{E8eaWfoqvPw}If#kkh|o8hW2fXt7!1c+7o5V>&??snvA zM>-}H^A{G>d8(QXsmJljZTR~1Is{ap{IoG5fmZqlK^GZQA_4PsAC}+k%V?HLbJ66R zE4|OX6lMivEft{_g&nZfwAzHxDvL;ut`Q6StL7iU=`=Y{uNqWyG)g%hkgb3zogbX}Bf|E6Gs8%FP*HE2j}Cy~ zX}<bVymj%4ej2Q@|I8=W-}M#QTEsIpgD*qubvZ!lH;=RV30o3! z42G*0usKsV*4dpKrKsIVrA2j(KWMr)?Q{HT26Z8r+6~7l)k~-GmxJ2)>CSl(=4;;R zY8q7D+iNuQqMzy9l>l({B9_*zOpM{D8w;7g8^lOWpJPUMc}3JCGy1ZAogsjr{LC#H z9jpY?SSli7bayzh((|j=6!@RaQChxo=ozO+Pj1U7N!L{5Q1-k`A<8?qS6Urd{pHnK z0i5?UJz8@ILV_|2%Z?IK#L0p={^~Bd92ZI;jg=x8@gkkTl4jZQ&uys;;n?wa|J6WV zFLIxs`SGfOjd0QXLiK(7YEH=b1C40>Y5G{^#9_ghUb$b%5X|@AMj*(!M|^5J6t?`p zwDZ_nhN~Z8Mgr~*Gd7&ZZ0-{;g%ggF50y42U%Op}VQCJG-9^q{lIzCE;5n{Ft`J+M zL$Eg2k!v?!=EV#qk1*zqmf8T)-DJqT)SSxwlDm0CAykYDn4?m<|IDa>zRo?lCDPS( z?hJM^;tZb3O;`;XpFQ`3YSU+#HQ0ZaP)dUJdQwE*v~L=y9zliKcBDz;n_NF7VepiBa5u(w1>!=b9h9DBsJ~6!`Nw7v>R@=$~hJy(Q`$P>2sA z&W=JHMlh)sM(TM&N=(>KC2RA$Rs^c2@FPf`?syk1PBxIRG?~l%j4)9_>oA>0 zXe$gV9{bgOm_tj7z4cE7Wwp`|$_dkO+;TbGNs z2m=?iv}be}z7VxM6wfg+W2s-TO>O#&_#KP9yz1j<_$X+B6ZzQ-Nw!naiI5h#7$>gO zLE7BP<`=#bH>UZrF3s+P18GLZ+rb zjshdKES}@4L~8>}T(azienhYkZtp(7lySjz1jtCar9jE~L@=1LC(2Xpu68P9jE3 z^Fb$yB#(gPr^FSXs>!#hhV)q(p|^%~yPcR~NC@^FbN+kQp4kiK=Nd1FC_bTTNY%^corgikr0g-0zAL!O4&oc zvnNp^7JQRydsb9k>0?rNHv(KQ1`%+TVlv!ImutN1XNfVB2w*-YAxx%D-ttg#(GOj^ zA$UJ}ac^^w$UC+Mk`oI0!R-&NNBQO@>1_tm$<>c3cJT1^d{RKrJ`AK=v|N&Z6B2E{ z?5lpgqL7&I=xA=uZS8#di!u+pe&uX{v6+tD3`oYgFvjmYL~eMGNq-iRIP*7;=TWM8 zIg?PJzZ2fKcH=;@4h9v@&@LQ(1~C!rj@nm$qWUH#=F>f7{wfY{wnf}iS9_Tvvd`s9 zQDW*DRG8LOY!Hb$;I6?j35L8YH_EjGX?-ll8WAl=VYL%+Sein7Er*9hnSK?n({c&q zqn2*q>8X9k5`u)fn$u{v;ugeHDxD^pTRw~gtkix4%k|+Ut9O&f#j=k;X_+;dL!d|r z%?Y%n=|*n(5R;aotwlnR++vrVnr>?|j$Rl|Kw8Gom=R1&o^{-YO-y^YGeyOdHiNBB zsJ^tbGM@1h=G(s;2h`wF9fHXn;I-Gm+uF?>)5^n>Wh_TA#D2WaGbhxR(@NPAN|#3^ zcyQ>Nt5Xa$+(8)q^MlL8nZZwzPkczPHC8hBKrva4ikjtXN!hYl%R&*f zcrs?cEtBrD);k0d-Xn71fa)!jkLi4tsTcKYNhxh&+IuuHP+snKX|G5dYm|a>c`J)5 zDxPnU=Md5vpPAi98x^XD7#x>!9Z4}RO}w~sp_E4w1avKskQVmi37ys1gg_BMJBa;6 z82IWk5^w)WLk;k5me%CJg3rb*4x<49Mg*RWR*4l zMyMp$oH-0Hg`K-o(kS!u4^e>3<#Al} z-c)r8kl8D@JDP$G@d{R%AI*a(ObdMzPLlRFOpewS7N+x?Nayu5rt+-kk+Q=u{>-e$wKc+6#N z)P$nlEqxk6C%kgFkZtU%LuV0h5He99Ye5ZRqpWF;ZLf&gdvWlLJk27C7ip{%-z$X3 zow~hOz{bt&)ER?($ts4Fh9J4G=b~_Xr7?<^NWlv)hnfU58WT0j{5?hkp!j)jgiE@V zRt@UIT1H~KJV?a@GBOJxmt9a=%S$DMXypMkOj0zC{v?t;XF_$yUt6(+kNXxK`pkWl zrxRZ}(MI-!v@Xd&Tt|6yWUlgMnV-N%&f0N2M8R}Q-#U0~Gqj@`g~rSmP>bVAjo3>H zVMxkJeB1}f!#UE`XmfsKBGVV&tn1o=LuuKLy`w&E^q& zbh!M0g7L{`;WNl*XsHl73R>pWJI94@qtJ#QoPXT@-ySwz(z~1=AbvkozieGQ30lsN{3tV^N@0 z!-#KPG}nE4T`DI_a=^q%>xGs0e2_rIy**Ra`}f^`K*M-nvTnTnik7;U((@Ubdi`eO z{41Y&;N!}Bh}pXYA^n>~6K)g*Ql}ccs^F!1%%-B&8jC?0Yd;;oExd{g&+Cn()@XHt zlr^wHZDSYp4*GyRW9}sucJf*3pR)L*Vd+j{&1Eo|#i9|Bq1D9E(_(R(JKJq%&1Ay! z2A?!66COJP39>dfo;z7A69vv6S;PWDjm*Gc8>bK-S4Z+KnU}#ETMQLlD2;Y%lcZjv6!1wRR zQ4y<_hlI;epCMfISIxC~K%TY^x&yW;Q1V$z7$abw?i0I;Nb3M5d*Jy#sh{PYMCQq! zdHqrLHNUHls*g{Q1!pQW_JG-91j6&1r&x&QaB~hpxuS;L^SI~X1q+;<`gy&tj$nJh zCE6Kh6rmk~!tdb8CRWED$0wgy@xUPf>6e~Mn!}tXKz1ACP7|Qb1|j;9wwS{^OZ93q z%+-bBFZ1;j%S?9n!S(jVUDlPl`f))+kpgd+Bdix*!{nXyBa+_O`@5Ht+q!!^nchVG zJ=u;oS|oeyL`UwFi{nvAkJ?ZlW5p+*v_vv&1jmww&4#CZ$tBRbGsh&AFy8uX0*nVLw+~hcR*#A%M6lEdSng^0s}Ltb z0%tEqDHoQNILRT?{K2fziYi4+V>&)9VjPXJN{CWt_T=#27N(VE2j>Tr+IKWDP;}kS zL2c;?`lC<^Ja#Kj2}mXIr$V(;Hbbyv{L&oO)uI(-`9z)D+QK{_Vr2}-rE8mLGo8Mv zEH8%49Z@Wn%#!!QtnYV@jRlm-` z$R9Uzw?F|-wSn#4P#l?PlLMf6y)S!-b}EBrtSx;APIF|cevNS?*^@(Ljk|ZL$2GR( zfm>-KA)KXSL)Z{f2ivA~Ug`YANuk?HvSfofJO-9KV}G}K{t(q@pEs6?5zBqkW|LSe zS88KF9T$#QOZmi4T)n8)adU6`ZM5vtl8O$PrSgd?Xa{<0oe;qosd1P`p9r@0#XVd< za{0OuYo2SwErN}guY}6DIC-#!>(|EN#E9k3BHD61h_}DE_b~{7Oeb-voB=kv-&|Pw zYPxkgFYJR5q50 zp>pfKY2dIgA=ZA*pQvuF;|@VZByP@lg!>Fw{B7)`?)2b$Q~#j`sQ5klc&OXE@wN*A z#mn=Mb{nv@sJiSEF?Y<*SOLVSwc&>`ySdX$XLRI(kHU0lB)lG-E zjhnM~yV!z4D3+%z>sPtSueZ}_w*?BsfEtwE6MH5MAW;CBiP8_z4;CSjWuuU9&SD!3 zmcrk8(2KDLbN>eR@AprlYrcO|H*<8Bgjn0LpmgAkBFqpkiImO(Y_O8Kf1}r=+y8h& zuuefd0n6UTK+%0S2eq3jX+Opxcd(j-6tbj`7)%+1Ky~RH!dx)6Heu~sN?w#!*!pk~ zfgAVUV6ENzF~N*#O2B-raw#`<#KbJh<4>=w$JTyKFk>CKeAu$1AhRWMVObP+O^iO@>I+aJU1b*NkjKECK?%dc8YThTY*!a1J(Sp(shqMabWy;`zq8(%woR>HW~~k+p> zh#&yZXLiUT2x6%cL9n96#zDlexGmtjC5G)-0_^bEC@>pm69eUDwzdeQmD_Dk9iF8H zlyb}6W9n$AtqIOur~I55({tUnM;kk+h?$M({Y~x z$vl~_F;NvZ$FxPLm3Q|MomSqReKIjR5wmbGwRf?_a?)fakK6EXFD8;xAtwq7C9}cs z`v^2_@;0dV6xC#RjHkT#fYS^5^oldFZQNIOW|Bnf)jUZdzi8 zsbDB=8n>tsM|B$?rDlBjifU^#oFg5C9hwc|23Q|5p)~u8?MrbuPXJ&{87-OxBfo+| z6FrR#MA@P#1l%Pr*gJ^%`V|t5X*}0XEc#Q}gmR-X8)ZO7D@+vLKc35YPn7&b%xBES zXU${y5l~*JXQ#x7)`D3EuJ5U{AusuZD@hA!tT+7!bJFbPvH}AEWJr)q#Kl;^C_Ro& z)-*xvBZvVZo-zlrlgBz7z3es|`&jG{+C)b+cIPX)tV6Oz5reZV%6!RV?s!I*$JTA) z;)c=zWW`zIdOJL$@G1hPcX zM##qFW)Yb{1iiq_*!o`inGJELfTz>LVkMwHeQb@q5w#l0(S?6xk~_L3J#E&UuECCm zpiqG8+#bW?-6`Q-MmwQs&etH`<&)px`PzqEYu>2h-T3_&VPNaIb>~5?U0O=fqiLFs z99uf-5EyPQS462@Pu4n0?S9cSZTs6Q>WJ;j7|S^o<{C=&U}&3e_oIT6PZ%mK#5+7F z=J3vL{Zx*B5XrXxiFVq69s|OKdVc&vbOG;NIZDYlBvwI{TDxlN88D2% zp~E>xz8HVNyMpbj)T;x1~B@pj!E+yZxu8A>BZcmJ5_ck_T9B{{5*#K^Q^jk|v zP}wmcrWZA*4X?!TS}66?a`kLTFonZiPk6PzFk(b=Qeu6F4-p45n-(Dm2q z@+6eV5V3_VblGX&!o+6>A0Y_IrIWIZ79@Gfb@|G|G`rl^aETm;JjXr0a%+4xhKaA^j(Ka@oo$iFSE>vwNv4x-56@CkqVWN zViJbNOP@8gWekZsPVD8vg+&ZW{vHR|uQvGr+NpjI}ies)y;K~P>7?RZtg!C7uEqOK*)+lTUUV-iz4 zC7W2j&ci#r5>S>@Kf~|{5iivung1Z<>cb&aq$C}+U|!j_uo#!Fjza0iW_?r$WO?W@ zC_G*gk)?cLV>{`M^m_iqOSN{>kktEv1?3PVFE6}d-rYWdf`XH4w1wmdqA+0I3khgd zuuYV$?d+n;)`ueuc4b_?qpaxwUBVmWg4SgnT&{1_^PLH7@CFZk%PE$_FpdXWngK@O(=3{#MGVr0;4v~0v7Z&ZX{}HlO0JvNH;*jTuUf`88Moeb zYcr{l&~yDPaTUQrKjCUtdk~9fL5Cvd2F7&0to<|+EnqfI;=5NPs0Q-q)ePB;#ns<= zxCR(r6XR~aP^OUeYcM>`Ip;ER^^3k{*63con~YjDQC8si~kQeR$yq*Rc(id9Vz zV?g%_%Co+uwP090?`C0=$5j`yACiINQsQ+~NWiTxGAVA^rYAFo!W=>oc%spy)MXKz zKw~o)h&<&@X8e*>iO$01L0vDYxEqp){CYP*L}`(nI`}xqe&rGz2tn~nzi6(;-| z-P7g5K3=?Geh2SD;H@1whjycHv2jK*+P%Cwh7a69*;sMpTuA-oj|0+Sj6?MVtoJ5n zQEjnNmR4?%W*U7oaPjLSF_iDzKG{O{N98UXlqUV*Z-pqugXXH7_NYbgRkEaAj7A?Y zrOc5?JJT)5Fzamc=sBcSaEH$K^Mk<+6y)Y-j(Y!tKvOWrgro1)21X#QcheY6#Q=@t zu(&j$1%Tp3me1NOE%9v<+KgIxK?RZpo~_ph zAtY8wfvBZMC>l5-N8tGiPT(l-L85fIP{{~|%;{3{1NqZm(uIR`lz}TV{dVFq(|`JF znUN7Ra}6MFdAlhok3np`G1z8_b$My2MAyFUV;OirP$;_{G;~KtnMu!yL!yh7xM|y= zS@80DP?(iNU7gF2{Y!`0QZ>$4TBLlbk3ikMA_3JS(NW6GF^AF|axylm)!Bq}+|4bj zQ=x|*6aRjqv9A(JtWVClnBMBTJ0e3O7>!nB@E_^Xl#2TD8cSEKdyU;IPY$GYFs1SD zGC!oOF^FW0Mx66pL+sXf?8Z`9jyUBE@iEk4YTq2oeoG`^)}~}P7V98lbaCH%xbO0I zw0|I|{Fp-GG@YH=s!9l9Vi@b!^r;@)C-mX7$$#5m)EE~3-N-G&I^I1w?sso!cIz|<9mP#>*xA^Q4Iwkr#z#WD^m4mwHxGZsOB?$!A*@(QK5Xz|3=ET# z=fb@Srf^aO0wDomq$4&i7q{~<`StNV%iIU-&;MJwDH*x37Em{+#XF5@TVoV zdRy8u)2!}Y62WK9WB8Vv7{UDsHw8|1B^mPB2j(_~mcJGU88kHKsx4ZqSYx-DSP-O- z7#c0YPQ=C|`K874SaU=O!6;Q*9}Z%P#EV@l#?hMmWMVNs9K%AIYR+1g!jfY&--soP z2%+oOIMv$BRWRG+vV@6pF2-0Uh{_X~q5ooWti&lN9#g-PS&-yt5SDp5U#6H)W1e-{ zgav|K$J}wANiAzg+PAQ{T{!AZqO)D}b-9*|J^b*cmFMbEjaMwW+>EOTdt1wdc#tUhvYmXEWcoe5&tN^j z6`~5t$)Sp+@AUpZdCp9*C*xy$I0(S=%Ql3iKSkpSkvRpBP=-j=J2M_$@|Inl-NL@5d^!T{k@mEVp)^7SLeV;T zu?=Zq80Iq%9cDflk6q^!5>*?tSfQ49)Z%&fyaVX+hJF`DcgZVEXj8#NzdE%a?JGJ1 z`%a^ba~V+6jymtn*o^a(ilNGQi0OgY(ECGI)8t%YWO}&)W0KyM1!d}~v7h+^F(WFW zie4rMWvs&q!D39rC!~t(rxPj*mL@qiRMx&2Y#hUN@yKOKmHg@5`|)sT@jOJZXsL57 zE6={Hc@S6(S|Rp&L(b1{q`SoQF7#<4BK(j($J^B}yQB7tMxiIK=J0GlX@>bySv*2D zT~$|@l(JP%ec1KZFu^2tfs6e4)!Ny4%QBJd>uar;y*V3h z>Gb^@iX#)i2SD>G4foS*YeOGGGp^AQNh8YWRp>c)`Gm)~g-`GZ53YE*turul3=Lk~ zoCmiERboRQP)BrT4h|gy;prLNq35(lBJIk363Z_FTUeI`Z)H;OX8blFA^lHFq*8P6Zf z^@em^iYcbvOrE5X-a$;ZGju~B*k|z~3`lISe#sLzAzbuFe8648A6638Fc}?XjO5I! zACr}>gl-HI1Fqu|V_}kWx3&`mwY5wT)yoMGiJoY+0Mi<4*^tv%HWG`EsK&B&YeNi; zJFJ58>KU50opvWEsWhWQXHKr%(b<+cWLVVWO6laB2OVlz_@LUnrDP7=9xB{)ut}NVl_T|Ie6&7W7m!bG<(b>PDxy^wTIF6nR8$>{#&rD z2gxLvTo1>I(dFgoh}~E?ZsTMPs;rU7M~zbmA;Dle9JV<|Dfp({y7f;)Z|9hw7^bsF z9kW9-ahma{)~dC#5og`{XRVPKZna1Z5u+vMT5dO$(ryf{X`uGe=?E#h`$Ypf%)dR? z)kS5JYQ=p=pnA9=RSZ_=KGc^U*Rt>tsP!cQ8Uz)bGGJ|rg;V?y@FVu*mRRa%G-M2oQy3j;6SYd)O@SOjWR(SwTeoDEuj>aYPZ@^Xf+P%`2aX$m-fA zhdCX_kq6eM?aOnrL*CE2E=EZ46n1so)?UBWTbt}><(h@Cboa$W#)(KtpL0#xPZc4R zb+nzJOz0w?Rz!V9rwCA@_|Z+=Bum=P{5sKtQG{7R$)gQJEG8XE0T!zsoc!s*qfEtE z>$pIp%Gz|MMYJE73nY#6h=IC%bSeJ;)cUgbbD($`$e|Q^yHm@JZ&s9&Jz9~EMys8$ z(mHFB$7tm?S(#S|i&ieIoh*0=EQ&zp)Us}|3DqbOpTSyNfUR|6=s%#{8`@3_et^p4!k<9(aGmWf(ORP_R&yCHvTG)urqqVk z3Gv^<9f`M}{~S!F5*+Dt2&StiQ@eG=#&()SZSdX?M3HGT_3jah`_x@v)dn)T>FIdG zEoC>_Z9>;9r(17~-B2uZHLh-Vv`5n$+sA zH|3UvS3JV0t8<9a=Cj_46-^8jIy^FPSSpN29QHkir(4Tp26+U-5TE&=`(XD;gvj!A zFRf;XXUZ3j{;IKqFB$6P#^{G;=I8TDWji}(xSGtIs7;~e7PIcO>2T0Ez*7n7v(G1^ zc-3dm%|Vac=xogCq*y!=j+TQC%QvUZ@J(( zo&N&r$!mk61YhqQ(0P#~pl*{|$p=k<_oeT=Lm2Hsq668xf~$8ZNH++nc-ESMK9t<$ z6nF+Gp$XpWLlV;s*68>esAd7YHTtD^iFHg7A$pNjcCHVM&hIaKnH8Z>I_|5S?V0%% zAoZ!XlsH0hM!+#1??iw1>mVqkzUC%$2q#XVIDLJI0jXYl+_)p$5=9f07tuU~{}2k# zx!J8MLm*|o+rP9X&3>bAYX z5sT2+m1nQVnI|im)O1097!%1>2@F#(SW6c{tS3v3#Y_-|lA9qMER?d=i2ClM<5&sC3BRquN>~2+M0T++X_a6U!PlVbQ!6P~!yA z7{uh1pfC5j;W*8Oe*arYa?ZVzoJS~kENG!Zlc~3m(jwf8m!}P)859}T>0GO?PsM_x zXn=!<4MYGsg}5R6f;f+pZ$RitC-4oWJ5|r;)VO}7$0?2t-4Ss zHNxV12cX(mB?ijP7VmBs6|u0IB0E}*(j{jz_KT)vjQ)fWtOsH-*BOt87O?f!%=&~` zHs6jd*1Ng!$p|Ed6S%o>nKjh%Uu*BKx@GvR^(%Qdj6EP^ak*b%(<_m0S7)TCHvKT? z8xu*;KIyj1|5z;(0(hqse@?T36|;8-4~c?)UFq170X&yR!B(!iJ<&E7!a8(82Ot@C<$vg#*FJg<;(;VReEhGxoijrK5;8R7jH?EvLY*lf<^rV!qEZ?mB!%$snEedls@y*nLUk_ z0{kf$y_?&I7%x28_jq5Pgyyf<#%^R07-!V}8j?wKgNpgd(aJKWuXlP~v{(}P-BXPZ48l=XCe z4wI)dv`xc(=)I(@16QOI)i?g8w%g-R^Wj_{cuVyQ1)C0M{MD%HXW)vH1d=4g;+u?r zPqvn}H~zp!bPRwC1J~v%V-JnSv;B-l#~{L5I!bU!F{FJ`57GI=Gp-wcbD+`i(}_ru z`%`~1%5^ulqqSYL1tEEn?y-f_Y34*(imcO#k)_B6to*T%PUQaRP*TC%sjuZktgU5~ z!Sf1Jj`N+1+lP=EFGc`l`|vfH+?mA9r$1zKAFyKrYO!{VA9?L}PP_&*{lS2+H1cJV z?7OBPL_V(nb5z;_*byKiTjZ#71c+NVV}OO$pIki8^h}q*Hpa(81f#sbk+%OIhJ7xl z2Zc;?ipgm1&gUb7wfk990BMx^}_xb3akAg#THW$PeT{3t3n5N>lTpMkP?AV#|VaXHHf zZ?LC>l9g-$OP@Oc)Bf^G0W}6VHb7aws+|yfAtDf6(m0njul{CG_mgP$9Ie0Z=#G>Z zJN8)n_WREEGa4Nd-8swcWA0(>i|z~>BSBh6WjcK^#%wnDHwoAHyHUQo@ZiN9q>2)3 z-7^g9GlB*b%&z+8#i(5}ceol!{eBoQ_jJd=8u4N4zq>PphMqF&;xcIr(f z?j~CL{MXRj>DTEY`Ia&p==aVq)T&db>@7PN#@-bDdPZO&!Gn+2aY9?kVuc6=FLw%j z=MDCD@}2?jGZ7WMKq5)eSh?9Ku%>Jc>L?l zMfOHZ73&lxW#ISy#TrZ*kvbB(fYRz|A)YUO$g|tT+k%x@7dGYw^kTdXi}N zd-GQd)oA7(ra&!?&3P?(K zMP)KwFUulSp_=;fWOFFjYi?QcA(AD0T`qj?QL>Vp)Z@wMS3HgT1%@ynatJ|{DsR6! zj*BKEyejROOb?_5QQB)o-N0h>AW-rz|0Q8S`Q{X2VpXgPdX=|2b9Vr8AbpyEL}MeH z#{i^%z%lR&Aa%(&kq9BF?h{p!jaA8u-U|<*kNm)Hl?~u9!$veLN(x%(A9X6 zX=n5lCz@o7NX?ye1YU0oz`Bg~jFMK#D_!Un0yxb3Tp|wg2m7@`X5)pl&p|GoM2Vj$ zo_p}X2^9gi=bf~nAQJMzq{tFY$|&~i%_%x!L0-*nWJIiVyGlJW3*i!Hsg|c*vB&&} z@jLV*q+dm?@hD33gv0>FK#CVOEmM<2$hI;4K|w~NBU(X(@?5x#SG=AWZ}B+Af@G9a z7l4)v-W8@P3U!Q$EY1CRrw`V`Y(T~r6a5lb7z@Qfx|Kl#$Tw>6mMrx3Oc`|%8rs7z zrxz%3(1{|V@`dci<~m0QpZ$s-!Ejdu5Mz<4cB794t8sswP~8+|Z!Hu<`SzlKNPkC4 zR608G!R&z>`lnnoXl%KF??$JFIOSU#>k;xS<>`s~eB4mf*QUSl9_TEWerr?^y-piv z6@tk5J9=lEkSF-6nC^1=_;TDgFbZ3H>roau@~8`nIenn91HPg>Y?y8{7CXcsiV^=% zASK3-wpOGFewE7}KGVkGF954JioU{=qlZ#H(uwt*VFw2xbe*_?i1=xk@7Ehgnpqi% zhQhmeIecB1nSAoD!%1^J_$);c7kCw}ykx3Nq#C1f6?MynI9nk@q+>Mnr@m>WitWZ| zU{=xX7)ZQvP9HZFQ-a<=8Q#zmg?ZQ4*^Y`tE14d`*kG|Yw5ygIHr3pGLrTC>9CC{t zVjx{lbs?khl59<;zKC&T;z~OH1tLEJ{O0jzh_cLbRA*j}M75-&q6n`cywZMq1VTJA zFXf;SRt6Ji6ZbTUVq;X9Xpb+qwXp?Y$L-wAidN~^ly-}vfWBnYE6lZ9)yUCni(Plt z8|+O5vA|RQ1AbvTkWSBBF*}D?{p-nnSyGXY#Oq+H1+%i$+yH(0Y2N`CF)@GdIxveS zExnfHhyY@Ay^F?xZ#2}h35dGbX%=)WJ|7v~hU~HSe#3?6!7&Jh{dd|z*;%DvG16&g zos}l8!AOIRqhC0*BOnIwT|C^%2+3(+rAP^mmBgYDsz+1J^a|z7PG?R{EA@VZ z^fQ-Oaf9i24l$T7?>4OC8fTFsJV@?>i~uVnqkR+y8u#nT1uuP1MK!qas@pyq0B?x< zB#{Fm4kcQ5eKE9`OZMYR53fW3(peY_#qha>oC=>b8WLB2ld55t1Tqp=qO-WtGLVX) z8MrzmmP8uW*7(^F(jYv*;5hm!84+@4jEH=ObOLikE<|Wv5@0MZt(hx@P;yCkZiyPD z3`@8_&rg}Wk)Bf$JZy~EJvDxGOcO=TSEvG#TL%*at{P_J(Xa)g{?1K{6pac6w znEgsL2cK|F#~kL0Av{M$;HHLA0#n>v$p;d@$U*vi{A^g_#N;Qk*QMz=MBt>{88QOp z$t_sw`jS)^hM)lpX62q{fy^8cL+L)3r0K{IGFn&VrUB_50x0c{D=>FzW=|kp60|bd zb%c50&LuY`ZuZ=ohX;|C1z})WGp6Gx`RNnu>eSky@3u%#_uBXUyeFU z6QL%URzjhQmPslR%%w9skw1lI2$)K6oorNfb&`0Kx~B)ZTmuK*jPkOrSX)Pu(D5F+?$hPw!gXBh)JKmh%|ZL@pX}Dvk2PWNMp=meINb zJXy$IMIU26kgA=+m^LB7&0d0Jzu7)k0ZPv+H78(YALRqRM9VCmM0O?6sA-FYA81q_ z;NFi9vzW9!#-H1hMB36Wq`WcN4Gh4&W*KK%jlR>(BNlTa7ykOZ0W= zr!rOwaVcrty-tptzVg4Av7WcKa=_$Qjh!tQN9_@otW9P2#Ung~O{q_CE*-rfR&$p9 z=<0)XZZwLq%+pz`zy>g@n#HA0K(a|JKE0HF90SjNn?b=#cC5OW}xeyF@ag6a9rQiZuW zfya>09ih`mnEu|NA+j%8F)j+C!N0rAfqcsIp6|dm$junlXiA9bCa>4Tyq&g zfJ_04TaB$XbtCcDa#&=V2_hsHiMw#Yc)}0o-km9FEEK~?Od^7@kG!;u%}S8uG>n}s z5Y=U>$~8F*?!}T9zsR`DqH&CMVhH^=E*h`OzHO&#b)9t~N-?Wkqsi4t`YvBfxT6pq zxe*P(cao7ZiK)MZNLhko6g8vj;6~B+QkaTU$KFo75JU_snGIuW3l;gujXD7-q9O!K z*>FN*8xCWk5E;>`yH$?R#&mADcn}C6Mga{7Vr}MJ7KqHSr51%rmE0k5aP!S~BS`f% zM7j9PQyV>}+HQ%wQp_yh*W)hZ)15589F%0yDZoR$Q07q`-In88QX9u`s?>c3AleQN zL`e}|Qul-oUpwOB(4BB4L?l)Ww>FlSK%B&Z&^WC|>}xV&hyoagfNE_Tu9`yf|JzxY zg;ATjLFK@w#hG7)WsjkvTRg4xO)?tD53UXoZ2XXr?5_GIX?G1~bxx)*(@M%G z?;^9KyL1dr%DVRAl+#XnXAEzw0uxh^^24Tf2#!l8A#r%qUPLj)ML5O>AS)5kIy!tN z5#t1=uR+{b*-)(q84Cj1BWJUjv>GsB%z!W&ZXp9zQ|0vdJMslE;`;2;wE1#rrRvx?w9 zsJ;=uhIVU(=DI!M$`$N2-k(Ra5D^+M00_oeQLVW^G;5O3J(`JqRwHJ;noz0)Rm;iNnz2^qpI84;LXdIig zqH{e?AWNajkT2F+T6zYKLFo?RT?}N}9jRTd7}GYg?orJ_Q{|I^>UO2PP_L>}Lqq!Z z*OJLqJVHzzC8sncYl!83RpV(cN>z~E6;`bRe23tqzA2`G+8tLyYOQar-js7pt-7FV zfm%d!i1A6`d7|+u$af4(X%5*L^GJVCd7MpgXqVF~=*$b5l{qUH_!yM9QX!Pu@2uX5 zay$uQ`PQT+k+U0I?Z5Ve4{{1fTa%+x|au-S#eyrm2RgVhT!lUV|8q=qEE$na%uhK*l;?<^jB)G;Hj)ZX) zTk|pMOnIrDln87}3gl2cx$GvCRrRNe2T36MD0R3m zH{LA9s0RBEp(H`wkk%oKmOX-Yi4ZvI4#5l*AEVT1QC?MUHCe9Jm4-0p0WKRMT%+}BiO zdWOTOSeC9RpzFtw+;+KWb$uQ3ijdQsle9=}4eV_k>8OhNi3I>>>UAzma|lW}8bwOoOM4E*iNs=TVn zj1Fd4@Tr$BmKQa=6p5hOiz_jnRW%%|r9y<1u{v{ZZ74;`mc3DUEOR+B9V zUTKUD?is_(WyEgHHM0sI&EG5|x=|H9$yOx#r3o%zFI^T$l z2d?n+X4QmIwk9+pz>RB410avqW)czxMlvbWps1-t_p1b9X2ghU8e;jS$Ay>DkY0p3 zvo^m<02Vq)c{Wh9)u;g3nAbSHN!4$V8G!-Vz*oR4ha%g!JqZTvJor0w>i z!@H##A6HEdhnGG#PU+S=?w3W!#t)8c-8mEq z6vh$)N(mt9Epu3ye-0s_WHReQ9}A;fd#pHhiE2=5nj$W;i}l_Vt6IM5)?wB7NC^TN zcg9bQBhx|Wglr(wAFP{OqAnU`4ZA3mWB8`5R3lV13Y1r>Fmo6v{p#29=+;;_%aOO% z$6aW0sBE?bUNDZOGz>0la>UJR>6I%WbC7C@1Z9wwVQVNT{c^vQjLr>P53zFlLpaSn zVHP!-A-ks4cH_z7e3npom829+&M&1$xd5Ki^Q@dIU2LW%j*`vz@*CwUG*!~4)M z$|F4i4y`+rxM7+Umb6OQ83lX<*KzITo4x3aA)J0lIa4x<=MKXX(Pug<|HN=+eEl-z z>KS8Dw=}*fn#@D>!Y-3D%VeTT&-nBIg@#L z^_mu+2CzD)d|(c_u^?f8`13#f@oB#Z$zx?)lC4enFCH3C) z?`7HP>uzL*vnzo$I+X$l*AiA<0&q0e%QrQ`PbE+W^h^ON4$V8GTTdQ;CnAxc)SdCf z3GTq+wk>vW2%`2w^j{?gP8J5Wf_Wf!Lz5MO%7pK033P|w_W1CP@rb$1k-=b4ec?tj z8uWTIHywi}L*1L}okVAqQWQofM#oK`s|}in8CO|o%N%`@!qm;e^`(fR%5t)TpU9xw z+R*bT4k-N^sbrsF;F*A}@_={-nDTD5>C*Ajz2~G^^kX4(2gGQAr3^(X_PG;eg8*Za zS>jSGuTvnK#i}VY$e5$vlMz=PW?=q~FoQ%9g|al-)6z*UM1t)Y!-KAfgtr_;s`<2R zO&;-ql`_TT4TJW;0yK3^p`^ImV-Jj<%Dx)8L_(CffF#{u_cFaqnbePLA(_Danr1nC zvVg=-OSne%Mv9XdIJ}#x&y&I1%I@>Sgb{nkyB!aB0Fh2iDQAU9<8;!)frC`kX(x*^ za4zhy;S49!u+Ltoim3-oR`*s|jDSDR%U~~%BEn883ch(*h3A0>Seh;jdHevPXEC%i z7Ih=Z-s<;Pg^EW*rFd8PmP4LvpLEeT*m=xfF%C^{Q85Mgj`%(_iQ+Rw7`2!TNeYt~ zEBvLN0U`dAy%fWmEzM$**Wt+yoKFcU*OW*-E7GcH?#91rr4NFq#C07;ZTcoLO}*8T zZs1Z|WAQ{b(%U{*ZCvL?;UvSD0yYG&noi9N)gXAfW!8j^x;-(}aPhyZdrEu4Et&$q zk^gb-7mZg#n-it8X&=){>aIyDJd2*XY|7r!@9LF4@KSM39OI#3)_YXC;WgbSJ>My% zBv(A{A5%9qgY3I`YGy>;H~SXcEZm<8B{#mELYcSLzeLsIxayMEZc>Y%+DB0HGMrAz z;mM7Y(y>CY{>q6E>w}dtp#!kh39p&*PF03^O4-%8VJ|Y7%scP zsqoB)62`@L%jwIbqiJu-&BR$5eDY)>QH@HsHg}?VzGbQ2^`+RqFmd&LKb1(gVN9{B z@-;8=NLtxk?`)DCto*tNkC7DJs=Qx3^TnfUOI^b84H<1aXIBN1J6$Va z<9RG%BMBs8*9zDOaWssJne3B{=_54S_u2$3~h~LU2aS6wID4En%Y*YjnccdkGQyp8bpKnBPOzxU?>Szk~J+yQErj8->RaHwf{s% z9l81)Bam!$u5>iF?%Ud0AiJ1O+IKBGOVL?$Ytf+aL7wX+@!9IIH*QTqo$w`+6p-WV zXoxx@T7!c%@JI$9ty-=hZD*D|_5s=y{z|}Afc7|nbl<7ayxK=aX{ji>q7RGaNI)+` z#DTS=!^?0|23jMu)orUMl|r;kly8jsg>8gO9X4IzBdNhi7m7zj{Uy~>HJaP9(dxj%jo&f$%aklmKjHaIH$> zGYVqkQuNe~5-j_q(qS}i|1`KNlRZ9DHUyDHN66_n6(Oypy#1TL*|ug0V%0UNv$fVi z7Ij)GTx;P=Tjx{5=ys%PK2;^91pX74rs-2f=~B1Zik~tCRh3w&j<2327SWKyX7{C_PMY}=Cv^3640bF^tS*#pjfj7^ zlz~dPkiD??rYhJ4>nF4>rNUC$|% z(_wxx4f|@kuDh?vbNsHz&EMfsC5P!kEQtxJ1}_iqmaGKs@{Lm2(hM)?w#{L?4fE7Y zPL#-jv^)uViyTMwd+SPB4&&(!x-BEdVry?*T7m@Kkc#UJ*)pY}g*K$OJY`BU%05v- z?M7Cojo;H!Vc+yd-gd4}l^jCHk~8M4Q*J`G)?!PNnt*DtDUAVSk2e4|q(X_*p) zOPLbtlWK*1AG;yN$vUCB6hgfbR+V%%d|FZyv=JpVDlNS**eJ-1bph zqlrAHwhu1pI0Pl|Ul;n^EV^ysid89W=vz|i-fDpuu_fM)-s7Nxyv;SfB9NK8YyO}e zmNpt6N~8O>uZGx)^HP&V=G2yUk)HfAy??NZqcDm~%kQSC#?m325Y{YJYWk>ceod%9 zHHxIx=ITcCY2RW&t7T@?y0hG3VHJmuR#A6+)aKl-;e%J<%^IAru5llS5!bG3>z7yV zQ|F<)i!Dt>q9kx7msS+I+447^B)%x}po8p^%SRWB(d79F*K;M#EJ|B5|C=Huvil4k zFYdQ2L(YpFITy)jBQfP9UW|AENOwM-DBT6rSD;fe7L_n=1u8T)HiRU9Qw{KfvAGbf zwn2`nIuYrH{HTGwv{C~ZPo+|s?3j!JB?pbwmN^O1D@(Osq5ztsb}`7*-clXhq2vYo z;l5w*E6f_irKO4^FT~;mSY+xCZ{Ssh`W+?dEqDCW0V7<=?0QT>@59j`vU z$lGcQA=eNI{iM(cza@-pWq;z!A3kA@U zZb`e77c+5BrDZHZS15T)a~WTd_O2paltiR&)>tfVl9Y2BAj1;Lgns8HH9!6<^wzXUHBpr{- z$YqR~3e*Mh&l;+yu2bG=MB74_8l~z%UWRfU>Ah$pMbNF8EyS?YnIckdW{D+(KBB6J zK-_NCBPe^#4^P!>>Y(}8guJTiIMP_1B|?oYLa9xWp?czWl1Sff-BU5PG~BJ!7GotP zVN5`X?+{U2Giz@pWtpbIc;%T|)x}0O1x8oHsCQDgcQ_|bQ;4H@Zq1>St)cWX0Qnc( zllqk}8q&+reRTt2iVki`^u3=B-Gt?3tGRX&!R)+KLj2r)u=kX46SqP82}b>rd*xL8 zmF*#L_!@Mj-J`qFmb^fEg2wz zZ<%&S@Fo*MdWlJLETOY)j%~!`IVya++TLIJ;?Swvxb|KYZot_ICQUZAzNnKY9DrIB zWDsGwRaL=6aUtMbvGa))5vPAj=8V)*W@DuoIbH8&fQdJP8%L6pOD_}a>gJ?x4NpnN z;SsCb=Cuyy&dGjT0uY1gwl@qg<#NXqzf_s`cu7x+>;qlNXes$FSg~|_#52v^rbv@9 z?lLI2zI{jGGD#&E8F80pv?3SZ(lbqjnASHgK$9}WT&Jl@pz5D*>Trs6%q(bZF4I$1 zT22hdl}GXNC1!z1c!L04x!M>jh3LryQ^yC;Fe|U2C0pMU;quC}JiRb^baBDhF+cXP zWHm&QLt4HrbZ8O0-8`%qMAuo>5Vbk4Eef6f!JgMzMdSDvkewovL}R@s6X%eS-1|Zu zJgKIGK)N-@3S_eY#hhzX!sHi*pKb4Kf!Nt3X`HT1Szbs=LuMuCa1chO6T#dMAAs(s2mx9kmCcw zuTtH3m4{DhLMC$9#bKBcCzI!J_lkq!Mm~m>5}s8IC4JXgDnv^{h>rE>QRbrsCXM9e z%(x~~rI^!L)=qlL;plZ=b!;Kko0Pmz2t!POd`e#5S}F$0&5rk=2=JPF3&Mm6^7elU zlh@JcU=k*cL)v{f2eBi4_w%TnG7@Xb3CfWG@;!^EnvFpkA>(W#CHl6@G-d9upxqrLQHzt2!ryB zB5kBNYqit=O0@C0Br7sFY$Ky@DIX%W+TQAsh?DgF6Om=+&9>VbQjp9iag3WrMudXV z^b+i(IHsm0R!=TvTC9=fV6Rjq(3eUQIvWfwjp$uc7UJc#u-&(28%qN7&Du;AGBRAL zPLltknD0>wqx$+}Ae#N43w0sHgqbBH14o&2d5{ZDRLoJ18XHEHho>mYqN?W2 z)YPP0WC$&>c`EOiolnPCxq_S6q`{b4)E6y55-`i=tuDa)5qMml08VuOns7uh1B9b( zL~@-nEQ>BP848x9jSCU)C6kAiK|(^#EuMsrpNx1yrWkZ01&vu)xfIiiN@cE$Jg=i- zzlOGdUVYkbkv3`BApu=PzKRQD7syG=3kh4$vbgo{Y?oEJ*F#18ZHB?s$jg@(a}-uc zkyI5)ZU|qwHV2Z4NJ@_GVEUhmv=|&o1YT4mueef?D&<${462G{G8F?P2#_DdknVtb zC2f@<2{!WxJ9;6*Ad^s7ieLfr^R~sUaU||A(#CX}jIOXWBi#^OW@H_N&TUp#=$f9C z$E<1Zs5B~yju-^htuvmqpEOlrCjwaqVMBm+suHo#Wozn{;a-EkWOkw@Z1Uli{Ybx9 zaUC4cL~!>yBptB)jBL&_*Nvr=U5oP#qSoVT^yZti;$*v)$z6NxzEzK8{PyaQv@_X8 zuia#4`en+Rxm)An7n3JbbZhDHQo0pmcMKcy5c*zML?9^LCT3N@+K;CixRhe819_BQ zeH@iKz<}&^Lj;#Hw6y|$QHx?}t2WWDqkMR6tlt=$6y@%Vv*TCGS>mHbP*X513q|>U9B!3;hZ%ZXs5i6I4+DzWx z7D(|Nr0Q{G0=lE|VluH3cj}$S!NM9OE8N(bcwt7{!hcOOY{yO`mdK+NKz+xdGGleD zgl&zD^>Mm=9+oWB4k&c>l$pd4T>9#n3yFGO!UE@SPH`2UCORv#qwAY%ilyZW`UR}m zWbw7%kVvz-ce(`A-b)=gS`GDb0sR6QiG={c(0jXXojZ{2yncQTjX4H;wMUY%wKd{z zuZ@ult?8lpyQR#nOTOt=(<3#V$`321=zYEZ;X~uT*NQkRO%U2JauN_p|dFT8B zT4;uLQPm8dmC{R@gQAd$u1;6YDbe_0JE0b{OzYIE-E!yr0$6N#wmRsIi{@@rjqYjt zx$`uT3dIKE8Dz(=KC^KXs^E^yH(bdLh=%qs7`&m zVY7w}s ztk6K{#)gyIB`KG=;gZc3M(nJ+9NOxd`2{X_26W3wC)2{i3|AT@>KAcd`P!)T@KLsw0C!f&oc8ce}s?=6UOd!e5K z=~pX1YnFO@b7Z>agp4l zOoJ+Uv-&m6UX$^yxx<`GIE8|hfosOz_;3gTS!Bngk<9EN&?ki;2?QEYF7&U~uiURh zP1%k9vHGREJ1NjBpJm|8uFpoWP|fb;YWHJF3g%NVTOSUgVepJ|sgyBmOPz-hhH89l z17*hiLr6qL9A@ny)gOdQ$`rLZD#kofKumW2PV;r5>4Ws8Xh10#l!rXC8Z=gk!J`CV zE;?FrcI->^h_S6j&!@2kFW%RXVWQdOk!qKoyZTkK+Qup|a2Sp`I9-amXJb3ip)HeS z(q*2?2TpfJ;MVl#*O=gnIi`VNTf2z>A)&^|Hy-7n+(SBJkC7~DVdqGE>WmwUfTC@t zW4Y=+uN7yA?H!V|M2tKuO-Q6& z?`sF9l_p$;>ksh?85!zPOiC%c=-G=p_H-{^vQ+Z;Lzh22$*j#Ke(`FbKw;{{jzF+J z9J=H4#C9Z9wrodo!H9GH${Nbr&Vr>&Qpt#;h1aqGSsxB!@vN@S87^R+427rXwti(p zNp6R+4)uHF;}u~#FwAc1hux$b2R(aCs#-oAoxRCi3Gc?S8;tOYu^p2zBNq9raSkE6 zP&b9UGi%WuV$2KAn|wlIwG){0ZHq2HAu!aec>Tt^!EDH{NtY3eeAYOJ2wk4^RXKD~ zUg{z)E7^}A8A-bF*&q@xMYBbey?S^NcN6^Aq+o>8XChJnBx7Lg!eXWsf+H*m(I2l@ zQ8Ks97Rva1-+W2(vPAL>bh+0my@ z8+40dph4bk?+&k44J(&J%>?bwaRZo$+t1Zg>j961l z=i5M0- zGLMm&2$YdUH$EFg;zd>f+H7B^cvrVNb~9DM9eb`mdx$b-O21z4mXasn+xkGtf52EOf|C(a9?qmnvVC z@{K>~^*5|A{&?$z(!s5Mo5e!Fm=xr&YVwU1VBCDKGOC^s7X)JtcHST5qde+I%`x#M zrcqW-m6tSRjm=r#9eA^}CBNU;srf(Ff4@9jv z%lus}j(e9%I9IWcQ865yvabVQc?OR+#?YzK;K?|^&+W!r9yjHUt+&V@ zqjWQ!`Lmsj#_a|s+lyTD4q6ZN!stFCq~vd&6tB0*O(xLty9K?7)nfV?UCqv!=EWnA z1Ptn!d=0Zc@0%9laT*!0C^|37xJ(`KQYz_*yhXciIRZaJPZ`Od1@t?5VuhGCIrpTs zAD|hC;{L>;P?)$xRsVFQzwI@?98TV9eOmnkD#gft~?f;9uP`agJ;SzNE$#^ zD+Sam?=G*FXdyrF4%(dE^ka~7KAAedJusJ*wW=lwA9yQj95R$i~y$Ics zjau(}V`uAMOmCca#zJqqE@L{V`d6cmrCyoG;nfjngjy+94a&3dT8@&u8rr=BX|H7H z;zLXYw!$<0^7F+c=Fzdu-$*85Ln70VS(#;--v`&aCanWolJ{k@F_CtTX1z|r$b%&> zkyYZ^yw?1dvB?o`<PzWNf zkz+F!!W_A@9^a4MizZ7zd&9Ush7O(dNEtP(sCiQ4AA3F&%t z)&em$bZ2=k=$e#UYJFQd_)vt<-y?DFISNUHOxxJ%k#rpUJrMsX;l^-DL~H@Kh-B@p zX}gURIhNg+bg);L0@xCZO~EDo*+a2t8j~D%kfq|cqZRm}Sa`wIAxj?z>CX}(XRBwB3DsgU3cj`efTY12NZ~(`_5Hj&D1Qt+7;$0Pfr4Dm%bM{!HMG$KM&f zBomiX{*i~^<;@PBRY^DNnrxOKF~~su8bXrZQt5;JO9U6;QljVp+mkmb<-IWxl%}=`o>RBRq$Dj3LGmJdli}fY;_;>)55aSdi-VVu0DUYB!g2RewPZAOljP}+(0r@Kl$-@D2 zkXj}=ai+)-)Q|))USVdkk3eERNJHb6-YDIm5@x2vcns%$=9NAQZO**N6ecA_7CTX9 zebG|@iKA3b$KIIUN00Xnu_!1Z zQgvFOv}mIGsbRtmrncht)V+Vw14inKq7`f)o$Mu<(k$=5vb;thmWL`ena3Q}KzDci z+`zIX$_-l1Q3^bo7@s&aIM{ip>ZV)pB}#Wf@qp6Y+eauPw3J6&nTo~ydnx1#Ta&xn zBr*slTuN#hWx&&$-08B<@)1fZ8z3U#72e6@>NS<{$L)C~=LGQ?hI|RTKX-RR@qm&_ z4@RTX291@bg(-XMO_~O|#Dic{%uA)n`#oG9nUKy!jJin*Iw?WSgGjeHmiJoG2J(6+ zPVXg7OLxfNz_BLEEn3b{qQt1%xsf85$6o0a)_P29pKnp3{X&j`xwlVH#%L)OyaXtz z>6OVDVIAwX2#p*|mjthS(ldZa$vc=6dnr|86OO$Q@#JMx3L=SNI9{=^5G9RLuf(Iw zag<(JghnY98`Rz3ZUl8+T=phxM#zm*ptM+OlIieW;+x6Az<}aZP;Snnq0}eM7J5@$ zj>VBDusPjm$>){E4zE){i=_$D=2zY~5~cX&-C5cqQW2HX1IMO7kN=H|n3y7s_9$h*}~(St2E} zfz(p?D$`YF+=@Bn;dXg0{X&p8xxyhrqO2T<1G5?sZ8}nqF7%^L40XunR9`8fqr1E~ zB7Btks)v}gI;^iT^48OwjGtmWj*P}(#poyxw@hOMKC5ogky70gX#plg;famL1D8;& z2OcQ_+?nGl4{mWWBZP2z;)I3`q{NFu2yx9NVnKrA%{6VJ@fj_EcT3v?E-rrKX~n77 z4&u0C9$9hb&~e?o^Iiu5Otiq8KCq}4K*h8Ja$r>h~#<$G6MMo-l>8E^3kb{K5D336mG&b>t z@0+#i#zF`o*(hX}+#ub`;X9V!88N6FCQ{LJhk-K# zD!ZqTi(A&zcJO=yaqWk6EXeCK!Lc1^27LcHB?pPLP;O9wu`CiK=Wc=YVJHWgq>32z z1*y?X;!~0-3L=EkvLTOADh@`_3ZkhBiNXm76Oq(!IJO`KLtDwkY>*r(^v z_DT$ltU3W9DhZ{pX~M5`oYT#N4&$G^@02p0F-juMb4m_UX@IoPpN64}+^Kos4WzeG zCeLrYAa208t~jto!M13a63PQW#_~QmRVzx`AR*6Dlw2QIh>$d0J2f6Yx7rw`3y&1@7_1tRBxz@z)!#^rSZ>LLRHf!^H5fv|R#aw) zZ7HqJ8~G2$U{E?Ib6?QY;SmDVa=0~F1E(4gH>A;lNT`P(Eanq$n}3<4h~tDf0Mic9f13AIQBp72Ll z=SU4;Aa;dJ@IopN^I+GI$|;Kx`K1&Isb%yI(y5&Qf*~@Jhk_;kzr2yXA&^*N8KNmE z1i6oeE9)36<6s<^)xfwRkP_XVVC1Sy9+gWbX-RUglhgVdBd0j0<4$MC8dpo?h04f^}7~*Pph81TrDLg89OOlc#H`7%ubi;aGV!_p=NIWw-^a~g@p1rj3G)&>jESG(6SuMBMm5wajZKZVvx(@aEd}9wsR+X z0%y-UOiZ0D+J^~zAZ)}vNOP7# zeLHZA2go12lWXT%#)UR+DBTLIK`Kq08`N}gBD9bRdQx}9ASiueS}MPVDf5u$4XbL6t#GcGJmX^&YldV{Z z-c)YSVM4lvSeju?j2m>EV`Nq)ZVy+=`;*FvS-HUX7-PvEFs`@u5yk)=af(jQ7rb*J z(!fJnFg@=0>4Q?>IgNPlo-9mSUlc+9PRf-yu% zbo84v0TnKAM?CgQUzg(yXpuxZlD@|!kuI%r*ZK%0nGm^C(hYKF`1`c5?naiFEExB^ z8xg*Exq!4iMHEjO0{5WwRQe%F7Y?yDEtRM!)<^FzWz)0NsNg0e4rgaCtz9r-?vaD0-zq6t7t`nifn(PjTzLJ!qCdpx;7* z&R*ieT!`Z$v!ov-e5{vJcP<c&ESYY3_!Ohznw2x8yP!Q*d` z1oKR7&uTm!da!E@p(;{CR9y+vz@%KUm%b1>X2KZV%B+D^4U8M7e;7v9FTvG4j1m1m zr=!NG8di7?N$9wN(b!rij=z$Q7_~V@Esoek+~m^8F^$fUu31__$olW#)s4eaEg{hw zLb~mC2eOhb?Akbp@(e)><+Q3c0+~pnrI8P}#u9chgm0CRC`Ng{cFw69W8bR6;D(7bs-Bm;vrZU)AsLw~;n;sIjH-#_ zn(tRO8Fe=Zwbc_=z04d{B1%g)i1cBG$%rF3C!@xwO8<#mOsu0!xLCSDQbpWCM^&j$ zqDrr$rBO9X(7h7I=vHJ6tSXJkwNIsD+#uvp7`sLZLd0=0(hD>vqlT#3RAvP!e?3Hm zW9A4oqxKCPH2Ti;O_+uoyr3FE;*kzQK@o(i;D+vFEkVjMN_c6h++l!%Qa8GGq_$}{ zk5|c}uHK=fE-Z^~6_#RD6Qq6o2ZB_kE!4QgL3#zt8f0HsM0wN9RXq@;D#ZGPlJq9& zvM*|pX74ycFIY8jYgboP5pEp*K?qej3&FcELefWb+o2JnE^9>*6NyUY)Xzfvnuszh zZC}@tT&sA#zN@m~nZ21XMya@QQhl`!RV`ty%G9h7#J&yZF;<```Lfx=*i6eBM6w?U%b}@PyW^8&C zL=^baTlWbOY3++hqKu5GjZ|f<%2715*HQgggfPQg>b{|-Eu!jA9pf%q4*PE2^7?!y zh^m`(8c$UX%e)O7j^Hrn$04HTQwyVg`l>1WD~x?NFMY0ISDc_zB!VMj^I9)8Z!~U) zQ;&n#_hf%WMp6e6S)|csX)~rO=va^&451p9sn`w6BT6y?QngRL3dm;Alt6O*S~{_K z7C~PeRZkbC0JHqKZc;jhb8!rcbwFx?G(p+~I1r@jQ3^M@QmW-uBrA}8i&!dvpRntJ zAXQ7<2b82>Gr+D==eG1tO)rffFzW_K^j%ojclbud8|Wd3syp>LT=uj;_WjCOOHme! zg_J^x*7$sxzFO0FE5k?88Y_9xz=5b))q=Qr_)AOn7Z6n=ugnpO>Q(%thz}ssSg3Q# zebmxJJd?)17Bb@OIzE8%CYi{ofOlCNa+e)8X(f>lSub2 zkD_>G$Qq*R@hCg{4B^uA^TR}BU|z&7_Kg{6x7pR$-;1EXD zmoauMD8snf`XJFR)k8sl_0UzRWwCF42-hAn_00=XX+E_O+I;FDTzWgmrcRqZ$;ozo z57+3V5@~>mnEt-EW7*nA7`uL-AEqL9E+UJnA43|Ow=c&I8J89jiFV9V|GKdQ%N+J^ zczhxNQnzC;n?f5jEsd&5J{h#dFscp_#&`@CR!ie|9S`)rdi7LF9BqsnygJ3GIwu&K zpbtx9RQ(QVu0qT-@=nT}jvAx6wNEhiJup8_$G4ZkQGP0Z_|k_l&;IL%j*(Rftt_1( zWoGHdQT6Q{yq^%2My$UR;Lr&BqJ3@~n!mI#s=D~c(q)xQqiUC+LrgEE8THE^hnrhZ zr5V+NxN-PXh^keBuInkpzP};-EQE||b{rfH(cIc67=I-hc`$9RZ#1X&eHT1>JPWGQ zm(=wgtys111({Y!$kR(p{|5EDVQHk;JAzR?CP(MLW-%>}NIKbNa(&cXFvy6lEw+*9 z!ScS{qdMaox5n?@YoqbZi&AM`H8F1R>KtSDCLN7cL%d6?9Ns(Nm_B{2jb`*v9*179 z<+;4JwU03VLORMzH~Ulnyo9+dX2z@C%XV<`^y0`cY`Qwjdvx)NYU#BN zVAPMUQX@Z=$BpM(#XK^zOZq+OPbSpEte~kMhZ+9j^;YI4c!4S0dQX?Pnohl|j&sm!mP7Tl)m#ucRZ5#1USl5T`!3isc}ZH@Q4+J;IxLwSNJY z)ah)Y@7`^dM)U|q8Ac?{)iTnN!EZB-kGL&w(P71<#ALCLtUwQQd(&=^Yh^mrJ8e=} z5cUDwk}AckCPtf8kHgqM)W)3sC`6iM95+WplveQeO5U`BlPbOCy}i7%e;q2`8Gs*< zMp|*Z7vyHXDh)8pOLXV%`5BQ#lTU4CP%qIjg)K}&=88lBs`piSibI=5B|=CnslobG zD|3ytEUGtOiL;2_vdso^ygb!P|5zBKTT`X^)Wm2X|8W@mM@+fJg!K(=e2$N!K~j;p zJR&=-977h#Xj8l+V;IWTI%)icbR^mm;Z^3jEU&9hJyp_6%R8+!(@t4+=BeVQF3+@{ z;}1kL5Hl32qG^N*V~S_e)6R1#VvI4bRWgT?7Xnagx=vN5s^VqK)M^U5W+@J4&C@R; zel5cu36O^KjSLWR$f!Bhg18}#M?qv35c7hW`Nepl*Nc{_u*zYE%bZmQj68jd@?%2e zSsq)T_+C=lzuH?bj=zqMh0^ph={Dfe5gF*k3|8@w!yxw$cB&w8UPxB* z4kfz8Cgi~&nID*{hM@Bev}q`2=p4SnE=+_{*_2c!%4`U zgK16-^P^!E6JMT^Ux`vCg34BxWEJvYs+{Xf;r-I;;sI`<3Uen6eJx3E3b=JsFWl#0#VMtN7)xOki}k%MnwR0zk^v77j38;0XZbTYt6X0Vg~W%gKD*U0<4bE7e!GpM)XtAua8 zv40KXxrIi9P2@>ndGJU^MqnUqEtBBMqq+<A>~qFZOA`4p#GUNU65FK;?AdU_&?)Yf3V7=uVd@X*wNd%Nb+jf0XdM!1~3#)B7(@p4^H8J_u&3jO~oqUA_7FCj+_J9T}t295SiyJue##8BB&b?pd^T71DNED zP?MOIsg_|u49;v~&L3upiLapKeWGm=9)^(W5FG9_V^*Gdh-=eWg^|1>u_mI;U&hvY zLHu<@bPJ3IK}0UN^l@7x>Rt+;O@wEz!t#U&77bBE;SctrN4OQ>%4~`k$R&(d=J1|L zr-a#*H_k(nh-Ko1Mmq3B>1;$klOW<@iStVOjR`H}Ei^)IM9el$&zHl34QjHbi4*ogn^7BD&>8S`xVpq2C#Hh6ZPp?L?iTc6pruN0zC+xOx&2+0D7nK*Dc<(AIiG+C^zh*$lA0#nB|1G8KTgi+hiL?OWcJoXO)a0LoZwj9yUa$ih z$JcwKL@cet)tMq)37+tV2Oz@;gQJ@GYhuKCeqCJRnMphhp}Z=~mxSIBh_KN|?>m0Y zplS>n+JZ=j-?Fnj%%$VfUr0l@tVnaI%-hDzXYK}^Q##jegoNZ_!TfB2r03n7%1x(>zB&w1XHjl{w?=JGmk= z!JkkK&sdgu&*nNfq&V*{&XgJ942lnDF}Tk<5H*|9?kpuhF9s))jyz8!@i>UsD2$;@ zwv_l@9Ad1b2vcrQ(Pl8Yoex{ZMkJB=CzhQ0cN}7D`9u&U5=!Js9)scHoW?3G zB;+b2${${ryz1nR$b&|BK>Q_M>Y!XM4$q55X(=RRa!#iHc15#o7C?DW)wwM=5|JZB!92nf z8jx}GN&qeP+&Co$_@?pNWbAn1DaxPn@Kr?o#His$6A;4s&KybbGX!2<1ml93uB;vL zuzsYjr5qkb#kAs?6yqmwOmLaVaoFMJPU_%O>?y6JWGfg|Ni+!8bV9$s5`4kZA&Y)C zW5K<=C`PP}k4Pn$=FeY9LAP#5Ng(%nalkNOgoNcTg0fuCMNb-(XMxEWJ|!+jNn48k zc|5vtRA2Ha(jJgOM26?5q?Lk6g%93)+m;@A>y(=#9xJLQKPufJl)4-#dO#D&YmOVm z-*QyU)03nqPpk22GgS&2H_RD>)!}JZkG*l(ew?z?OM`De5K2LcRbqBzWgZh?DA6|c( z28jJa4yEoxZtk;G19lME!8_o#O6Aay9>ocL&~`@o5j92R24)gXtc$-zWQJSZd6W{nY|UX)<)ol&_War0WLT|YC<9e z-MgOGJq9;-3%Br$$nX3`cK=^zWkk8T&2!a%A;n5*vkYkk06Kg~;ibwVw7KyCLl3*X z@30Qa(kPX9*rRFVH7mX@odSx#2z=q>B@3U2K9{hxa2j6#`y7>+*P0e4&7Z>`J1$1Z z6BC+vAH)I+(XhKwf0oQrj8Q_}d`r1CD$uMp^dQ{0sDl*BSh^7iwMdCvA1N8^HA3Fo z97qit9;CJ?6I-Fq)B=bLb|FcoA!!7Zu2rvbnKZ;K!pA0}Oc6bcr_;`#p^{7d<^V)X zq-;Qw@2jom&-blYSo+rikrvlJ7A=S_7G3(%oLw+2=RvE7s(nQ4Z2EI(L>u>Ew5kHZ zPZp1?H9j8&qaCx9uMk}!F-7hydp(7$aUpcC>NugQk!gPqG%|*&9TllzylJv`hZnWN zo^&Q(LMx{D$_gTzd+;|1hfp6w&q*iiq21|pXW&h%Y#e$RHA|Hd??Y(lRK~J0_zz4J zg1cE!yLV6G^DhG6P&&p(p${PeMdKhLyvNG4FpXxepDln9S> z7?C&y**8)fgjb1I#1Q&7WvG;J_b`=WGWMy|LWolbg{o+0(fMw&PqmU-lZ;%V89xQ# z3oe8Q#f8+-P*K;*Jra|p8Gw7Gdh&%SJPuwIh_Xzm8bjDi=}xTgX)2q0^M4fp!#PV9 zKnH&=cvKOwF`8m2977~!D(?9QAdo>UQ8LETCwLRpk-(EjyUl+T4kJhDH6cyJ6;}M` z(Wie+$LJG<7F7jX@F-fv*`qa|EFh7gjv6GkNft&eP4qnjq7^XeJ)u2^CD~~>^tLwT zFF^&of!Sdc3XCSS6{a1r)-+@XLzzEBoSqy>2Z4VP_`=yrmj7G?x}=54p~7LD1_}XX zrdJqrF3Ok0M=^-(9nlb)X-&cj3k>hR&x6Fl(Uyud;u_ZQDPTi!nR0E!>N|vR6h1g< z1U^`nE=*a3FKq2jDJjtn{0J00;TJWv8T`ReM6ECrQj-QYK!*iY?@UydYzKz>aG9k# z#{vKii4r6t?oSUc`6kNAIv4*}fiE1VWZ=`b(guM(2dd9oHG>Lq^Un%_?KS!QcNBd@ z#|G##u^o|Z#$w^%;n;T&NTOOLly@>^7-_b24bzmhAezaB5w89?A~}B6@qQFQ`mjd; zBX+wju?Bs^g(H+)N z1d{+U{DVVSWnbw0O1raZSU|)o2P-}AW02A}vN!66!k=HkqB zWGPMu?8*dP$cz7PB~5B=gH^cz$bBMH|Ei9XDHV1jjEIh=+Mkj;MhGD+yOB{mTLQco z2!xpAT38rK0`qI?*#HwPJ$o@$a&_|3kX%@?*I~~P_cZ|0QYtOQ1cI1%Ks=TT*j|zl z8~HB-QDGSLQdB?5%8aN8K8(9M>RNfnz`#Lz8Ojj=N{fIo!iVx@I7a*+iLp=S>G~ z0j2)?n5>x6*sQo7o%=TyT~WjS$6+MbH3XxJ$PJz>J&zWV?rr%jc@&X^lKMa{W^2BG zV{c+;br88_w@!#G3}D$sofjR2@wq!tm5){iVCa0z!ot7)tvE+|kqIX#(9>hcGLn;a z5)b*1gmD8rRt#xEInOLAd|KTKbo_A;DLd+uY6YT;Mjys58f`RZx+|X?OswMrEGoOZ zFV-!!ceqGMP@&ghqOHJxCe<>+PKu(%4L!!Yg+S7rJti`BZxep3=wyNsstifD9? zrHh&(dUA$2F|3)YsI;tkqsFe6i2D3%Iv7ajQM}Zpy&Pq+4%M#bZlBIh83L{aS+fL9YVz zGz6jy3{=Gz02dESgDozn##!cUME629=_L^0&-bp|PVH%@8+gZr5_Sj7BpJt`k^? zQi~~WIRrEYBC~({Xskdq^Sh?8yFN3TIcKS*DR;JI2+Mh5nB?1yN;i67>AU79Hvqq zhwCgirYpVDoX&zw?NGR0it8|l3`7_L(M%Db+-RGF%9#>0Lp>|C$nx=G0LL_X(r4*% zZU)}CUNpvwVL?^Ji!P8ZBF$6@<_@eAmXf^rlR(nK*~jGPKo$c~JWQH7Bi)W~Gg;yz zR8lqEhq6)}1E?&gXCV5mSiPAk9PeHL=P-~D>d}XQq^J}}44a&uQaT!XBC(t%bzz}v z1!XzcNJYup>}@AXu?cRJD;ZM~Kv@y23#H4IcIZ;glYbIMXsVCN&tVKOX(n*dDE>`M zA|LutR!lj7Ni$t)ZPLurwVYB#iFqeFdz@P7(H?=3@h0ntL^bwq-@l!;NQZpIljXcW zCXaMpR1UGDqe_!@?>{us)DJ0t2G$6aX5<$&^F5|C)6t5_ z%gG)D33)XG$|54JX+$<)4HSLv73;C@1hOsPv)i zqp}>B*A3Ji#^f)N-Q(oy!)WHf(OOnv(oB@YnC&p783p$Ny=p(u5R_(0R>ym=qtfcS zhifsCj8#oN;cA9$jTg()nh*e3F{A^ak3=&pt**}bg8-rp`WXBWzyO2PqOVi)B-%H7 z$n8A84^YUUh(3f?J*w85=AvoRV8_lh^WfN;U9n*~R*rV7PU7P@gk#|=wZ<>|*BE!O zefM;<6norgDYG!zU1Gfi3f^Y1$c>f6yl6->s+qfwMN6kHj4mg#KBU-k#y|gYFtY3E zJ1|CgG;8lV4y1QiV`!wbvJawV#{FnCtK8@|u1r;}f?IdO^=4CP$IG(Jjo{}nr9Q{v zR6&Trba zhvPWOAL`aTR;20y=`*8QiCs+8&P5M@5=I75^bz?ni~%Cc4e59q9Xz&|HN=hVSq*f5 zr5N|4(X9Pupjt(%W`Fp!p5CVi)XTc}JNaZ|AdzdykXQoQ!~b`R7TPUAXbFxf#_a7Bhyqk zOtH(Ga36~`|6w3);toP}vB*q8Mw(&9 z{4(T`BGraanXQJpV0fs8J0(JO-}A$uI))rGBMTkJP~dUZ$X?4a5TA^YQWxq2+q%a> zRKb&u(o8PK%`ri)qEjGyYb9}>VcccLJN>Z~E2Bz@x{j|~)L^~<#+p)F82#I4$gRQ~ zTnH2D82a-Mgpt8FeLQ{&V}wVL$TD~aypYnOuB9VXo!c5?$5)iZso8Na9;p>$QZe&z z6r5m+P=!Z^_p(++G6{j(o4BLFN?Zdocv&+_VfOII`zHkneKb}e@&_4_r{dx#%+#?< z7?X;Er%sO5G)$vx%E&dG@kZyE=Jhicse?wggk$57>4fAE0pq=ngrWl=D_Zq{^cj+1 zozjg=mc8O!uvEFi(GMlikYKuCDsSA zChAf;tfci&R8ncGGejq$ z^E=6M)>Us-vTk457}>Hvq7P@yn|tt?;bd5u_L{MB8w(Gl)pQFLl4$2UYC7Cnz>(op zloi&*8YCdbEK~V2gK!RpuQYv}dBr#ntU|kO3_qTTjrBgFO|T^g?NY<}WZo=_kZI<~ zBMj*d-KGhxI5vdD60E~uh80&8dwO7QuqTwlDkCPfKDAc_h->!5;K!W7HUUvv%}M#j z4ui??v_92-4kn`x&%&m6V`Ef{uVloX^>+p9!pcFA8AdDRK_MR4~XZP*27T6`AbNiQHFeziR@$WBhWMj zpg5L6-d@lYE-&69w{(O!SvwRtS`}z){JFE&XgYVs8hVbosuL_3Yi!%5*l-5VM6P7A zV7AZSmqGXbC9G&9r!Q=;7%{Y^8wq38oKBMr=JGkRTF=BX#*(eg9zoP$+ib&>$MjHDw*zjn}b6Lek z<;Wh`Sd~_D?1+qnAfxR4XPT|mN=uLQUh&Ux_1dBt0u2)~AW3B|3iBA}jA++2$$hpQ z$SIw8BFlYi(^^v0SMg-0?IMhLc}Q4;G>HiUHVC&wOFf+h|1*OhqdY* zqrx#IaQecr!rD$7%UZQoe(bif8ar)-$zIqqk+v?GjEO>ouU3&Q`OG3PDghRX%p$w5 z(wIBCs*dyy_VKPpaJI23zhPADQ-1dq^Rd#jmLT_P>(-bV!Wy}Y$b1~c+74ySW|}_M zBv}ZakSbeEkx>bWaElC)iq|yTQDGYPeUzrYXE|67qujSN^)nfkKHlWySuH-wJUDrGcCvXy3Tp5e*vKmv)xqlp@mhs`j!I9TJgb1%nI^weSW^a>B(=$|qs~7H5;HOevls z2hf3Q0%SO+%Ifwo%)hvq`ui9`>0J8`>w$Uy_^iY+0{fx5W-Y@ke)5gx4TjpfWC&&k z?BnCTDaHtducdYWbmOG%zUMoXPJTQz1{QJ=Z@u2sr-@+hjNvDzMfP9A+TV!=9#3}K zT^6FZl?7B+Y7(~|B~?qNZhDkC19~yifHwB!*Y)W zUkbQzIJdf(V5%IJ82BC_VFjGQ$SRdwP^hUa?ZCwq4szLCkG&DWxy7CockD( z0qpM#7^bAN_FSK^PWzVcK^Li@61r1`_9jTJ=pREEp_RUbyHG_xX(F&gDc}#4X3LM< zO-wU+^~=9j8_q6V22nq>bS*zwd8LQfN1nx}qwX|b{{Db>0)}nw3nZ~tm>;~Z%} za#TH7!ozAo(cF3PFs_|`+de#N5Lkb@JyALka&xt3h+b#9m8;WQ?p{86xt6y^#H{4#maYiKn+u-e}pAnRu`koBjdK;FXnUKW*S z0olGMVX_A293UBj7AP}=Nw~)#Efc2ecUw2xN=b(x5{$UP(|<>i#p3(G4L8X0;TR^! z_BCHb6_bbpTgsx!)nYq9Orsl@pw%A*@yTBske(ZgdRTb2?@4HUR#NgD*-5cepdoBT z#*aQ;=|OFxkE(>EdxqjsLi;okE|$Jzr~e*O)P-oqdP$P`Mo$4VeaUJ)Qc>M;;Nbr{*JJ&gL?Tp}D>^$%>mrkLwQ;`qQW7 zo7DL@I7FXZ9$k9@CM``i;v|Ea;i`h{tzgWcSl-GpQS9|nPEo`>Xs8hTi~MV&#gowJ z9ljO}-#k0C5mB2(L&FLNlJ+JSt78Sbu`Sapj-r8@;V5Td8D|5MVZQO-!_>0k$737x zx{~)J`iazJ6s$I+Mt?8ioads3m08AYzyw%6qT6Eru;7m0)Rwj2PMOc*w^J@cFDgF8 z|5|r0)=$mYjoJ;|2bhs2)V_-%?8#4a3 zBDnaBDyZqlqOyHW0y4d)d?o{FU!TWT3=u2~O(IlcRW3lbgtn7lA->XRY~S-$R5BAP za&l010hIIvuUz@2&P$+Q>C9Pw=wL8VVsRG?NB}3}vVLa%xP1R_8VE3iOFGB`6%^=_p07W#EdOZ5bn2mrd zrh4WvpeWD@G)F0J=y@rSge918SF#CyYhIYnIF0hBj;N5XE`FwDz*OTgSg1u4Cq0n^ zP!Q2KP)x*z(^nj6j>Q_5v{3M#@(E@rWWj+?y8L4lA#g=t<{MRh8Yr|`(R_{c{)}PA7Y~PbXsb4gGTD~a_1R0S9vgQKP+biIfbEwQCN%vAtA*()< z<5^UW!4wXcN2V`!MypYD_*Q0Tg;K&a$=<~QXy25c*?N^a&0j=*SqaLdrT1uXfJjr6 zjOwE<;i%ETkAL~4R);ATh*wJdey)H2XKOXKP!8VL7%syG-cNu`pc_KTWmuEh2eWfF1LmC>D*>2U zVAU4zS#XA}m3=rj4wtyhppzLgd*NJ&mR3=ZG^RTn<4tC~^m#LY(?@8`oGsZdS7zbd zy0SqqBV)P`W`d_7wU40OzA(c88ZHE3j6unq!XwC>q1=an)h=jpIlpPO4RKDlrP&~q zQHa-=;Agpaj#rW>_Cx=U@tH#jgR=rD?R6w5z7*di6&t1&jDgc8ZA3~WnlMJ!o}ARc zh7`oAoV#*}*xMe9_Du;;wU@0ws-;MlgjyJWHM3poU&yJCvL1nfz{c5=7^hDpohFT* zUioValt92I9qJ%;yhRg^@XdHXi(#Il@3}aWR$z zQ2V0w)8(POmyjUeAWz>J7#NURF2F+_v5m??ly_Vh-D60QAQ3}a3fn$%@cB*pAniapuIs|i@T zEWY=mCyhzc{4Yj;&Qbm4MUNL`{v3^T^QXf~m<7g+9xBL~l*c$5>ccYI<)dlk851(u z!JCjvgo!cAG-?43cTwo0^cse|qb=Ep!MOVCJ%dO`NDB3^`xRJ-lBREZFB(H5xT#rRc>54rQo`M&4pH>Et3hK)WS@7>;g%Rye>omB$h6d4oEN3s6yJ` zK(l7rg57hVyg(r%P%``*5@cS=3npaqMaCKyCBhOr=?C7VKUCys5x}acg;;fRrVwkS z|CLD>X}p!5U_vVOAP8M%kCH^3T}}IF(dCkawB=u+7>a!ixn_ue!HWNhztflTC7 zoQ|9_k>y;S;T>)p%=D&9d0)`|X<&w%YAsh*^g5rzl3JcxUQuig4> zWb$U0>z)cdSq&j77<( zYcxO%Co@M2O@i>sZz^??W`myvC*{w5IJZp#u$YDYs>|8Cu3%~wOp7Z2Wdb&9UKTN{ zODJuEH}%~aN@H9gh$kqQH}RJwfd|c2?k*Y)uqaHRHG{kN1)JGU-cf&nu6RCZ{S{)5?UH#)wVW z3T)U5^J(E2mQBsW1^o9MwbL;@qhvD+k!F=C6d(s*OfX<}GQ)}(tt%L-52uj^Z31v1 z*d%F+H)Sca@tR?;3WXjSbQmw=KnZcS0)qOHVVLxmCZ9RTfEW`Igf^bicttuzLzzjR zdnC1*0Ij2z9`ax1cxoe-4)#}+)l+Tvnuca!4fpaZ8%+BFCMS|%o9y|-%Atc3k0UW9 z5~=q5N*L?+WEd~SG(l+$-J$cMF%Y@AzKF3E63pby5a=I;Z#?NQ=Qsu~9`<2LpE^$u z0i(SKePHDD1P!fOgdw3%v49luxb|9W9ybPSfC(%0jz6{7u6$_@2h|09C%Q4 zeRvG{`S3JH+aQ|-pfnxB-b;d}dC^HQMuu4cqkpyt$c&&G*XKY4YwyQeK1g%7-Seko zw%AS|e+eX2y!Kk%7bI<*P4JutWb>wT5Jz~Y4`nGn65rRi{R!IKt2qgvCD{MS1d~CcIwlNS@ zo1Gwy23bPTZSH|3M^v`5FPhg8?M*PMRhJSQtQl?RW2E3YFfze8;64K*)3C~8WO#^* z76%3{9XKFXdokKxqi4(wQm1_ukg!u<#8@DW|2)|uB>~5@D&&+roC`Y*^^z4h3q0oj zehl7Z8k(aK{GYt_KA{#2Ji%f`5V?+%s5Ff5S_B#@C6}L%VW^9J5+9Li!mJ^9!ZK%p z$wvACL|S$s29b_Yv*;cu4LnPztdLyHbUzD5!s8<_8p5O$GRp)%f96U24gJW(&?&fB z5OLN*Cy{IzuU|;ER*;=QUSF{4xAwl~(Bij%WI5zcWJ(|!GNZ4_p;yv}0l^AL!^vpZ z{GvwJo`lI)lnX5}X%!m{(3x+{iP7OPkToA?U*Fy#8RfIsGR(UeAT2!+4@_5WXpc1F z4j?O4n_g2Y5yFlqnL5;?MoUflAd2wHqrIu@igbvm-hh}9Z!QXNW{Tr@@@vFmr5hp& z5E>9I!{jm5mcTG)cObD*w+)Y;rX#iQ@?()hQbo{IEE*c+4K!r@(|Ziu)PeX? zO+CM#d4Ov~jqRz}->NfYlQx5ivroi_sut0Ne{EIGbQi?2wTD$tFp!WU4yvcbj_LL6 zqt`xf)tzL57!J=GwnnrpjmbdduYgW6stdMq*fGXpm@RnOvrH+|se1 zbpf4^sY;Dy1s4W>70EC?;@uQ>waTX0c+Brf49{3BUvwR9<6~dW?l@Zm%d80u)RN$Q z6OJtbyswp^`egwM`Os@Fbu&P(ssDRP~dU#dp1y#p1OsvDhShV{`}2y0p6-joV#C|6_0I8(bQN^m~Ny*;_W#*^45a*K=V`Q7YLk+R%=n1F1nPdSOJsgW@xqMNTW39 zPskWE%IAjfk@4ufX$+6y3}%DJoo8zqvH`Nx{mMNhaEyI3N7Ijs9enQ~sBckeg#LTh z(9Pj?Kv`DuGXpn6Y0Sa%41hbbe?aOO4Y>qK&Dk)_cJQQsTTQgJl{@1`0PCVZwsEEy zW@((H$Y#P~X`8SIb*U}nm#vNCF!t|ha+LvNeI!~^HExf3MbhDHt-9MSQZuB9AiSmu zU+Z79e)lA)Lq&36>KLiB^K3CcnotJra0181Nq*0Y;3(!dg2{bn3t_Y|DuR+3Mnfla zT=BSMeS|?Ai^wvVv1Ff`v$ZT)g*eI(fc7M37)>NWS*%v%d}8XT8LW>;1EVW`+x za*hvBT6cRvh+pRCPM!#7A%@ z9GOr85_)}=)&naO2mQ`g`*A=Y`@N9hcq151ud>83TX)~WC@VhtGHBt>k;C;FG`-10 z6pBhE(>gVGNgdXizpoK*#D+T_b6HS>gFcw)w`IgbEG^iSr9*|+5j76qVC`;3) z3H7^LvlK!Jm&P!dqB`Hwngk#M%V3qY&f$Ldn?DVh#*kt#a7L!_sTr7@K0R)(lgkLK z1B=Y+aGr6d!}UovU6>6A%yp7B2C<};jW_;5=#E0~ApvA!0_;-GIGA!9Y?fw=m!{wp zVA34=WFXs1v!u%M#woRPf72?fL6(^_%liMNHhvO6?0fhn)JUW5U@Ia+*LI7abPVHQ zE^X)L(`gb$MQAn6Ru1zNysJJvYkUSHNA^cVGMsgSKNDb?;b((hU`V)Tof0Huf~#O0~AiaW2)ij^*?jT_+UIp$y}fj>7(@8ng;)!d+UuJWnPOzuca%U zZpHYNsuf9;X%y+5K^*7MYrI&<>P)Mf^)F7 z!#`Z9Vwf#3iJv~fR#mGBoaVYRkj{&SxbijF-C^vL$>TM~0zsWpU&0f0rIHSAedi?& zWQ+xMiJS!FSZ{}Qoi+4A27vV$>Bro~nRwylAdU=B@v3 zDfLMe#?OSzB2AKT3I68+71P&^pQ3?IC*g5_Uq?Dv1ztWxdA2k>sRghMI=2v}*O+Tc zJzM$hhxsw=>WGA^z_B`HDn|1Rl|oB4;!7_or4Id&r>PJYqzwcLT1}aNECa}Cq*=nG z;i1NYZ8W8OT^X0=Ow+EFI&0%pK(hyBb~D zlIytt@eU`USu~nM$jeP=EHkxpKe=`OYW;6-Woqdu+_%%DO&DIb%xDvN_i4I=v0#@V zmXY)o7bYKJ;B-JJWo*_ zlww95OAAX1Ll#P97X@YQ2_{_j#m?r7Y#Q(+AeA5AUxlu`(^_&q<(EfM*}bi=0Lh@} zK9B~J#>=CtF;iLL?_woP9XeL>6e=>|dDmUFa_57pCDxzqE_TU(usquo>}Yd}2@2zP z6dGm+%xoB-6s%h}W#iN*LO53EVq92Mdj_$r z7u(TZXKljeqD;B=60bUpLp7#$MXJG}arUP%=r&Nw#&;JL@c z{>DpO&R0+m<}>djNP z)&ZL=fk_ZPt`|D=m{@^mX4qW%@J0aaX(!okJkIy-V3c(}l+xkh*~f=O%5`kbUz&)~ zf-{6LU4Z|dGvV65)-S0a|3Dv5qW_{ZAqyAz$&p&OE3k#6WKKfXNSlTbrOU{SFs^{eH|$Mk;72kiJR;dh6ySymzOkW z*akIW_{7uC4g@iyp7|mPLC*)B{qrWJDPeXPmIo690$9e$ZtIp;-?c+`TMrKr9y?Sb z!dt+CBreY<)5f(Wh;>zuxjN`ZMFdH^`6prP!Wf}PAt~+dAj*XpkvzX9Mf!-C{g%7v z#aHPi%V0{FZLlne;muLVVHFlFc81IVApTN8 z`leCzm*6X9nrN~6=wKVo*$SkLro62*%E?JRFT|KLa*YC>fiz!jfHc2NNNZn|FkJu9 zK}~@+i+Y8Oq}gB}htLwue!__jPbWB!av}?617t1>EHmd22VyhP@{^sd3JEjGGBTW9 zao7g$Co6;Ql`~gU^u*33U#dEQ3mZk=eawq<55m$yGLg&AZ4R8^FyEQ7&qNvKZvLz_ z&K{3$K$Hm-r=xz;kgy>h5Llq)HW^<+_&{D6sl@Oqj3uoSWL@0Ch5)$%Qv&}mNTDxR zf|O1&3c)NKc8lHPFh%tr3ryQ*^P!aAT9Z(r(Ot4`IrSuJ3@x(-%$bN4AyghA zkMS5wOZ(6!>4AHYRNw7qILgLx4eKaG zv|k6jWS2^@hlwu5<)=$_)mJOBtA3lwu2Jt9ZPj;2fh2w%#7`j0)ifqIy4#xa_`V>; zkynxMXbiI|=F|0mW08M{zjE)Mhc2e?5=wo0-AAMDn2J{e(gUrf13Zy6g0Up9pyo3NB#koqnt>oTCvK&JPY+xnG5G(evZrtm}|lL|zljrs4Vq=%+4rDM#WCWDC~Gm~aEr(>(P z1#@{<_0;^b|%97eB^KC-4x65;4PjL!^ zeKSh^PXmlL4`tMukJYc7KXzU=1S!HbK&dsRAJaJqPzcft=<;C-nh^DpbxpQ- zF6biPJpCl?F&6`A{aXjj<)Qga37hs)vLBgd=U1gGVITdd#MPRJ5p3FH{4p?(=}zV) zXi|K)e9E#Wi!&1Da^foI8$| zPqcw%5u2{#s;KaYgvEM_f`p@JoQ%H{u-NL|-%)O4*>$x2*2>m>+}NJ%U0Ha|dwh|T zUNlRbB%`Ud8^s|-CJ~)}AXwX@HR|I}0(t$7ykv{WMzsl^<-=J?#)w=V>8r^0wmv}Q zj^ZnW$mVQ+07he^kMko{+JV}jGP8(NG3;&D`02mX{0MDa#@=V`5?T1)W$GPz;FsLl zFN1q%I(pm|cO;?5e--sGY@j9MM0xlxC3@KmxKdwAp%wGgwOlsU)eOm1YV!hPN1Z+; zpe#5peijF-Jlt&VkU=-MVsn8TSH__070wIQk(0fHhd3&57?L?=;!v=djjLO6hUEwW zIPS%q2#uOD`f9#H6{Tb`F2?DWWY6&mb+Yfb%%TE?NjkriGDNkV`SBe(bsJMRp`@B=z zwEQFq)4V4kl2)qgO0BrEgXDTcl?9efK(3tE7ds<55`ijl+$!5MsFfLgW9p+}NgeGl zN6s*ow3>A7IWUd|F)q>{MZtAqy@td@i?Q~gE^huw)={HqGo>C=kgWBMY*tIC9)Qis zJ_E3&_fsIGp(t{hN_VhTk0R4Ew4?i;Or=IS%IY04awxKm)P}{O%ZQCe6B0iWHVsFg z!icCYu+&>X9jQiLe<>uALd!swnh|rXuNl*OY7IM~@sMIv|5Tv27=AIvBaIG5&42}tIWmNAggurSVGG-{&N{`(|qto)1nN+Pw9 z%o)Oi%AZw$k<($*;V4prfZXlPEhk@!|CR*FzGCy`*(h86W>AR1pDA)U!gObmd|;hb zL|B++`pff~=l|NX*MLr^EFn5@cFga9fvSsNuh>1VagzkwxyQXxa^II})^VFpTbQ`Y zFXyA158sBti8D?oH(#2T6p@Bn10^a_7*s!WlSEAk6~$z_rZ%EL`<%NnAHJU^Z~*C- zC!J%@&5IJ2?5FunBU%-u8pX>kcACQ_(OTbl`(cHv4fd|zlPU2a=6;E{^$E}hEH~oY zgr=SZ{wXUXqQ^|FM3A~a`bZeGdHs143@YUS0@5IoDKiNkh5lDfgqlikBI7{n0xbn? z++g5Q`uwF8Er4=QLIAB$98Ny0aB0HFsM$SW-o%i4xDH&8LiP>^jTz2kIL~y^pTOcK z1I_}4a=FmHvq8xghG@ADjwme#dPSsX(eiaL*t>?b zTQKt)MhxyoVAGiv5>iBW6c5!kS6y?u-CwCEw!cqkNnIu0xpH})$ncl^1#A1Tg~@Se znfc^yiD)W|ttsFX;KBq%NtphvHwTN57t0hV;2h{efmxu=LN_VqQPg>`H5YUWY@wDmnDeB; zurkJ4mWv}c=r(l6vfaJQ- z0JH=@(sL9);SEvDiB*%#WjctFO;kg@uNQ`QW`m~~m|gTM$T zF{AZ*2ejmNGO`ut0AnAEpLugWICnvh@x>fzD)jUnDq3z&mYLu?sxay#c*1n0h3EZ4 zwJjo*T~pMorS1-tBAW5GTTI(lJm+IA@1OJ{)8-gvbXiCo|OHl4Kvh<1IzCa(JP zCMu${GtujI2PoP9I7W#TkHbUUp^qTLKJWHe-Zi)2V3ROnTVufp;U@M0tuW#b(H)jN z61X@AJqV^gIQ)9W&OR=1pxH&G$B`2TKMXVyO_j){c#0b)c22u?;_?=jeFEe-EXdpe z%rN(wNrniu7p0_m-KQsS8*ordd-&}*I84+V0jE_To;qy7akOu%t&T(Uio)-!m_`y& z30f;dt3$J(GtlTUqkF%oL|&s@Re+e%>z3CVkRxN^p*;lBWphM>qzQ zMHDME2x#O0VOUc8#J-ZLiG9PQXVg485bH(9sws^TJE>S5gN=c$*&0wKGwPI5SynD* z0zJ$(%s&p)&7wUyrP^BQlDgj!Xw&*B8lRd|)xeN2XfUejw7?+@17ZU31YmZHGy&6I z@vE{llFx(a#&};&pa(0$nv) zfuR}Ict+;{6qdXw>APqeMo*(?aL(vBe;|$1!Dzc8-*=IWdH(Bm9|MhrTz(JZy0RWuTuR5EG5yyKY>)FhizF%T(11|>M~V042T zh>}RaT@_}0M*#)0P|q~0lTHMEc9`IxfPi~$rCH+<94$K>Nyj5m#w2JD9^6zUIcYPn z0frMeZ)lUb!wfV*#^=Gf$HC#E`@+CbTYD9~Uu?MLqKoiB) zjGS&olt(fRH28OEDU%9jvb2z2T?@qHz=UJS3~C(7Mu?-Km>L?7KwXJ=9GkGM-}`dFAV;Pz z9*J^Xbh+hh4Hf*V)X*pabP9fsC)WrOvO)_R9K!+4nKDKSP~%Ocr|D?Q*`>n}5!V6* zy>10#8KC}gaEPk2TZP+A2P4TsK$^fMQ9lBod0BmpBdCjc3s^Loy>LO}@ ztRjWyL~?1@4y3h#33rWR(ED@hxyT3O-qn~$8#7a^w_swZ3PaYf7&btV^Lp5BAP)sg zRSxWQjy8Q^^A92E7X?o;QZA&T>M7@oJ%^(W>IgOCsJiwW;6kh_+{fwxuM?JV#|am( z#z}=rzvo1!6)_HADg`%1yC~254Oz_ulnfH4o7^FS09sv%nsQl*zoQP&AIvuF1nf`U z2G;|mGLv3%pz>`TXC|T+0ZgU5L+#*EQ}hd+X|s_Ib^$wZiejVG1Uzymqh=;xWjBWQ zRx;)0A<5Zp22gn3;P{phQRE7y|B50NXBE_NCz!I9~>Bd07 z09=HHeo>BXYU+8C`X{}EC3(etI0qcMYWv`nB;3v1!@7#22tlwnw% zqjWM#IB2)R(j-Ij$V<~mxu9f-tEE9%zipf(KgjG4`XFe4=4-53`2_gIaa^Tx8+ddC$8L z^p)@rYq2AfVbMkdtk43qQ=A;f5UR0{Aq$Tyt(*)(3z3(4FfpK0{8lZ!2uN;qi4uko zZZ||4_5qezcGmD$kqELB=uRV_;xkcAta=+MX60qcsZckNA3TntFf-iOt~wXOpUeZo z0?^(#dixch<$q7YWb9jN15qlFBsI}azNg{HE z)PGaV!_ukgK_tGW<`4psV{#HmVKHn~&4+*{Wb-2Uflh)66ZznmQ{hLVfwE-c1wNXH zmf%LAN@-}MmN7lau4_6Xi5pYMK+y6WUW(`Su9j-zCGTYPy2-U=Dy!zCv}vOBpvQ#H zT^#16>r-RTdg0Vc+&R?aFhnTr5)Z226P%~ohFeYw9tSA&_xc((QC%yvT7W!hXQT@C zz9QG-5QPio3`F$iA)V;vpcG~vH)ok4*+nftdqv6#07VY0l?=#fgc8}}3-gc3pXO)* zRang8TYg;0fDK0(EC)ua(LtOaBmyb<_$21XNK{;aGmu1hHqx^2*;*a@OPey@1Q}y^ zAS+qbiG&bQ(Mt_E=@b(1bZSpeBGI)&^^J$2O?{^TM3}cP7_7f19k0p|B_7EW<*Q~x z2gM7lng&{a<>H7SDlU~K%05)LkRE)HjUsSp|v;O9=SY?ZnQz#BAI^ZE|)yc=9{TR}x=ZsK8&d|}!K$#|`TGwBUI*oXMzZ;;C zi;Rw^Wrn&96`x3t;q_`{0vSFUawzsXB`KkrkARQXF=ILfB@|E8JXRc17wD$5DHcx3 zh>Q|FP`+V@mBf=IJJkX-*>%82wrH;OIw{P+(E>!-zzOWlMso`8gs^)S!rZcIW+;Ev zGy^XKn^1Bk1cdtGKR8*_c9^fgL}npCldRhFXW}12IUdCYwL1Z(K zcm^c8ozRKQ(8hhhDO%Wx6fEAGYT>AWc2Y>f(*`THM0*@4JnI3mx0fdxG`TeU4Q8U% zFCe^C>T%OJAczGlXGX&D3keJ*iYYFm9)SvTW$^gWz@x{Ilw_MJ#Xte%uOM7-MV=(7 z@q^W+cZv|ljSN!C1{|iu;MI}aLQ2l&H%W5(ArYKt77A=~%VrG_@nGVVRJ}{aPp#$D z3ee#R(b1cR<#AH5fs+JmWLh{dWjGbtZnFIJ`b{XJPo1O-M^k-mt{<);;=o{%)E8M; z{7hkkI(-d)!4jje6TNT_hQfrH!H@>?P}ocJ769aaITR3T>W2yif+9!^kKl;+Kv{(S z)$NfYVAS7$VT?TKr*leyP?1ri!0H=`3n=8#fjNcpbxG@k4|oRgPhbmO?HA6F#88kP z!lYw(8E;O-C#ASlN>N~}$*rfLhyIcg1_Bg>GI#nQHg`=F0+HdtabWO6?NY84sj2OS zHkL<+GNqC>p)gI@=W|2}bFRpno&!&qHd^d%FyxR8Sq%gM)JBk%xBTB_{#l1xo%J5|Onp=ww>X~-OdMz|ja2KOVdbJo}?&_J0Ki$NT+mGKm^Xmb@}4U(qc zDbosZsSapbr|3z=<3NQTUWuW-HcJc8PMhL5JOd4pGLtc~;9dSKJ2DWu60mA1rT}gU z%(d2AdJs9T&V4Kk^iO_H&0-*&qDM00=TtZnSBm1>Hdll^q)vzS5*!4YYWKrKJuns= zVLg;CC62lW`f%j%svMVa-8ssKEKOisuYD@%p4FjFDYIe<WA58RyX^q`R zHjC^Lr}g0>xI}J?ZYt_jxeLBTFhv!*R2Y!fA@p;OyFep$VC^gtA>k)giwZ-eu2RJU z6(%hoH24v<)p#X!M!FRz8PP{y)j9atUxAvyaoBp7IM~N_$H^_MK(*M}$JGsX$e{0` z(&ONSzUg9$`b_QeKno7(1_q2kq$Fdh0F^LsgvfDl!Y0W|7?`04dEgMn59U8r-5@|^ z2fq4orYsOm04g+>2I3H;JVm;N*;T83oH{^;A~9cXE;mS;rIprRx0eExRH#oC4kQFm zfe85;$!o(wWP^wsaI-j~bFK}5($rYAi25A-p->)3EJD@nSx}6xj*W1Rh{MR_$h|zu z8V*TZqzMojIHbmbNA@(4k`Gu!UN;6OWff3Q%SMbxP*PTfFjum7`V#-Qdaj6|zL*A) zHQI5lstFr?kSrsqrbpu`6ib_`EPx1phEJ4~%TbaBAaY@7Rn^sl(TokOI_8F<)KF-u zEIfzk23iaghWNu2jL0;__{xTgB5TMnLOc|m=Pug@9#B9G0WxLHF`@nJld_VH_Higy zmL0v==Rg!Ysz!3F1_p14@m6#cP0b~Ao2ai9Plv=%9>mc=Bx4k1L=2qrOk8~lH7o>0 zB?w)~IL&>^hebE+8ps6$&+eOUA#!d)T{sl5B2B1>f|1TZk-EGh<2KR$Ke?$ z4Tg&~5M_j*hcSmX;~E1Ec?F<6T>O}HujXPGCl-@X41 z4)YDu4FXGN5!C5aZEVA#{{}M-w>ji_0x(g)x5SLc%zI>jk%T#V?L2lI7&26Sg;Qdt zCH^>;D4uCTkW2+TKa@yZCW?%%!4QtsSfKLk+}_5T)N1va9yINg=XeNsQbF=`^|A#J z<-Pbl2x^+{7%{A4QO&C<0yty(wN?u7VFS+(8Ew_W5b>TCJTZ=18FJ14ru8t#@DEd) z$^`q=W)Q@Al&|67>Sv#;vWYw}^@1TXlo#K;Txv)Nlj1qNONORUnqk<%~n7nq6;+VCj5}j0zGOf5Iz=JD9p^F9qk?uPM zAl3Bu0V<_6l|#j`w(q%SAP=#mqf@3&Y2nK`;a<&}2^h#gs~dQb%p{LRR|v+bN5kQ|!{SY5%K)v_VT@LbAQ@cd@t*X! z?gWS;abOit)p44{l%q&$40(#nRm8^uLX!4TWHgW~-{L400?#uMs!Yo{@{Kyf03ah0 z?!Sm5IuOuK{#Os0ki1BpRkO6zGbS+b{PJdrk`EF0T` z8sBp&5Yq0IK17y-+H+AjN}gP_g9XQ|4p(Y}7p+9lJa-awxn|78?O`EDZB$_MNbfF1 ziXJm~q*G(aBUX?3j>8lBbp}DTb`-@K$`Re|)~l|xKLMnOi%QdHr!uJ#gq62L*dK;P zlg|eD$I&I8=&gbAL_NBPifppM6#A+h{T#2G_OHM!HAaudN0T7X07A{T%x)^(TPQ~& z68PTasq-M_8YBsGx=5ZfPiYyL)fY`13?oWA5L76CikYC!*FKKc5(M!JK?J0kv?LWX zvz?$`X8wmuFI+e!vEa+}&k3PMS8GeymfkI-jBYYYIWL1kJ@EHy+eDdoc`v1#D=aaJ10+Jh$B zQs*^u=Gugs@NDndM6us!<)r#H%Gw)Mq$oD?KAEUNcmzXiGU!nEpp7B}3>vSWP818X zVYcCPGa^_O46{*3Gzdb*o}+bqYE?OmCi=-D1zU=5d7nh0Wzo=AKXnOGBO#kku{r{~ z1S36eVoZsq2xxEuA}05>(u|A&q3Sbi*SRz8I7neG)d)S9Mg2{frYhr|D39P29)!jR zkXLohR0N?OBG#x{rm3wJQxN|Hw1H&?51b>!8S)ayhSFw$wBBi%1NW&hWyv4#&Q)`g zcMmRRk0Xd$slEg^B)6AvT7X<3sgZ58r-2~?uje=t6deX;g8|5+98YA`0J$=5iIgq0&rB%~6q{CJ?Rr(2$wN zC_D~T*tDUr%EC;*gwmm%ON&OQun86bBk1W0CJ3Y^XHUJ-07}?|a1WmOF9U#bJPdn1 zr&ZL?k{US<*UQR92w2I)wNQp+gVdSEbQ-MXWT|33D~m^UG6|nt+*_jvD+w=%j%nPY z`684%!V6L35avSme2*gt0_by+frsjHl~bz`9}GBrIw|rCecX36w}B9NVz_kh)m9% zaYR$=AXAk{a^jV+VSr5FIhikIj7iHtz^t=%|xeZBSgWOm_W$R51Vic z#3tF#MNAp?%MwMs0Zb?Yd1M1|8Fd$jsZQQwpXy4fpbpKIcCt~&=!lkfYA!;+Q|+V% zJ$~p$N!;gL#Bq2C7Vd|K=rqm@cR)CJjuuqRovyhC#}g(FrJevyl$^Bvx1OxR&0#(f zS_MIYlkPf2zA#}i38p*M59;j9UH!))3P+R)e~TI-@j!h)e2hB>dv7yBjUnPC4)1vy z>^MlcUi(STl~#^^tO4>A@^^$BVzUp<>b55H4ONKm2}_{#iOT6SyMJivV=@rwTZoNz zbI~^z5K#vbX(9^~;wlO42Z<{ZUI`}R-3*JO=LdB{Xtb3JNv4tVOXEu^k|6Un*%>e% zkxYa)vWD>h=UCn-h`|0?_de)o&h$buKGg3pPl?12IV~TgYI@-`35*hqvnP7VT8z}| zqKpzmU?J&M&_Ql8Qywyo#vf9U1WgfKjlqx~Bos{SQZXRn#2LS|7*nc6OET65B{MnN za#%PJHVd$1DGye{)+BDK7AC9-9am$KFk*x z!4Z>#RC`3iln$;rMTb?Rj51eGIbLhiB@}697Gw$a5zEg~1x}<@hyXaYEzeVbJ*3}l$~6G(6j?1m?QB!3BTrXHfU`TamFQkGy-1pBT^wnZe9xXW(*R_b z<4hRx`0qH$g)IjSRm)>wQpGS831V@lZEPr7?1_z`rp(2B5#uASoHl_ciq(J!{98NIgQHg#{?gp?tDE!>Ki6fPfu;4xfsOi2Ni#5o4t)56en5#WF&uMks%t z|Jy(P?ce^#fBXC2{`GJF?tlKDZh!m#{^|ey+kg1)|M5Tm{r~)T|LO1l_uu{%l>CSP z@o#_sU;g8N{J;MGZ-4t&DiyfObr1tW_?RX;|rCc(?~0Px{>_wNdpr%#64W7(%>;_oe=36dxyoH=H`!>4YFI7 znc0Mfl5nV|ZBx?is#z`rbG91PZRd;T?T5#q3dfpN(N(C6btxK=z)-1d;DI7EuN-f( zcw0emS|%`on8~fI-jt4IVuP}NNGWDM5=lO#U{x`hF+?eLM_~dGY4vZG;_N8Hz@hnp z`Qfz2=Ey(M&1s-2d9PxXiiENG_)B8hA@ zvs074{G=gk4Iqkg_8vF^fT-lM&IaMVG)MZ)U zld@R+<@$+@UBGEjH!d#CQnW0S@72w?qWw62(Ds3O!0!t?E+Cke!aT!|IyKa$0wk~= z-4&*q>_sN%o)t@^u7!p}t~?7`GtL?F zpRd*6Fmj!kD5WPNhOGeR??;u~XiQw4RvKqWlh2u)`a zW=(J2FkUlMccDRvhxKPT<$%i@7zqX%Z!)ekytoF(&f?8j{l-LH2IPj^W8kUAmB1J@ z*->jwwK)!r)}OZ3G2)&=#4GW_M;_B1);#j_`^09TafG$oyk4Vcx0F8tphy~&!fmHg ztih2rP1QL*56PsdSj3U>$AJm6ss-i_?5(9+!Ix%;xLP6ouC9nSEQ>*|Yvv78A zVE_fBg-<{s4_)=?Pvau3hbJPNgcEIrB%}ZHfBG+f``3TZ@$tEd(WmbdMx&0d_&MeL zYA+i)KcnDsh*j15lnG4N>81-fy{s-Bl$J-92`=A0=kgg#6X?Y1@|VNQ#%Iddbognt zU`;#4@nLOsbj;sB;p(+$Jsi3`nrLZ*x@>AuQ%|<5{C0*%-A>uLCiiJVs0$Tx&IQQPjeThAB1KDiMT@LH&dFB0vigS z)(1`jfQpvDL0mDS^ArHkrlBpJ$R-K=AKcwsY{b?5AVUkkG)Ls_RfmE3R0WCjM z6}u*@EwDJY8Aqy{8=!}G((_-?+(c)>U{HyVSrI3ycMOSINKJ>= z*Bwv~^Mz8Qd--C$_eAEc8PPerHB!z}+nVSyetPk!u_8R1$d&GGd`UJ~ z{IlT@+8LQt8vEotg9B?nYVuysE?Oyw*keIMH+;Y3kuMOv_PXv?$LTb)-$ENw;O7X~ z#Vz`Vo5Rr5a9fMLd@KpPQiWx)9u!cB;Q<9V_{wrHTR5d)Zjz!~hMpwSo%ag61fDeK4ZDp}AsWS!g$KK{5s|KY0$@kcQeV z2Dp4GCt%#gh9aDeV%GHV;wIv8Ww;QKbgQlppW=bwA@2{giK-ek zBCgkJvjtg{p|r9=k2bn1Jz8Rm@!4mv6`gMT18|(oaz?)Gil_285W`bEXxVXk(6ZDS z5k(aN?~loGE+f8jwk#BTJZ5xPdh8oQk0DI^19SprQ7MrE(w8-_;%f>>lgdWKfWgB~ zW1z;v^w<|{0d0gCaMT+%*<-2!P0b{F>p>Dpeg}kzRaRleu~z95 zvUv%yR}FXk_QNeF#_At%Sv$N2A`xM_(J6xfNUOi+<>l*WOO_HDaJjFG-rAGyr z%puW;^jyh#$`EdX^Wk`vg4BzHJ7=k`eEM?onVoMRW>N-t1_Ix?^R3fVXP=2Hecj;b zBud{uF=eInjl(oYr%_9LifPm&ax{$#u!MFJ5aE;*+=lGl3kd&Mtc<1?h^iyv4{ZQR z?5bHc+CQDaq;dR3UZ zp<#te7`w(DWJW2B`sGMD%~QvmTR0BQ*wR(+T!bwsBIfSl1y+c(mY$>qqj0HSqV%3p zlzD5Ea}USi8H*5j$3h`ehD*JL^59hRG}M-)pQ=enl92SL&>$zon1hT?qyv?uh|@CN z|o9Lor5Jx7fVYdBPNNhvX%5b0ggHY8%TvO^;Ybq~kk3A3=Ps@y!7qr+>6 zN|pZ=IKpc0MMeY0fVHxIJK?|q^*9c~PR1GszIodkiRm8fff)#MA!<3u-+ z8SgYj&sB0t68#%AoMJ38{4KQB_XARsP%U>B$Fx-Q1EWr<84QQV*vcu|)JcX)ffz5oU{YLQy6y%+SXd6> z-FdMuNq=KT68C^$Xa$uLy-u2TAOy90K<6yHiqg0?SRH1Ujl3e;pO_X<6u1^BP-^s z`d~45j?7{74p~6WyJo)O)Iob3y0AT9OC9Z(&c19%nVljS7#kkQJqE~?Hsp@04e=u} zIh$XPQfQt;bZHZAH|rM@U3IPyCRdg-8EtO3X>IEv{lr+dz*gH959t&!0G`yQj`MV> z%?OsjhO4l%O5W-?J78L$rEhSR+H=pwQLKcq!)>fo=h*>^BeNMqauR_Nrys-0)@fou zJQ2d2;nSrvBmV-P*_O^7`RWPe1_dcEI6~tnAiv7>G%6WBAxQO$w76rj49NPl{Fd!vV2CPN(^do{V}rhn|?A7@#Ip zn>C$>u$5ZVxC0OJSXNE&YaoipO2jwru3bz9~m}1hMHB&nZv{g zSyDEz|LVY;q#s#r6xo`aLbxMSS20#_h{EZo7|3km9=rQi7jl<6*&ISnY282`J8F@H z@>$+J%WVThY%)eZ#STJpuHk&ckqWReys<*@K{vsPpRK{u&xl=>L^U`S6pH!$M9pzb2gSux2{JB90^ve)_k@**&;q$yIB zm(6++Ds~uXo092jh+9ji-g;yVghBn%hamOmRmUmtv1Tb6@DpDg1}4-p`|+`LAQzko zA(jm zeLmJ|zPdNd^VT1U!s5`29OZ_!&2jn3kww;$*AEXu5Cu!ONPgoyWOK_}v`t`Ux;c1$ zCUQj)MFJ}xxhK*U5saR={r=F6$9w1Z-?)z7UZ77sxq8ZhcI@61H+C)f&p(cL`>eM}?5-z{l26#LwjY3`Z`$+pAV`n2BsYWuO+XLg zXeG~*!ay(QX(t{IG|REDVP5Z2=9CYk7@1?cN~awDaGoB6CX5PNgcQS%7(cCkBdFqY z81(R!pTcVTeT`ai^pZswDTQbO!b;ftLFhs~cK2btZ1e69QBnc*;k&13G4L>nqk9U> z7f2m;E_tB=e?t}wp@SCKAm+ax9XgLo*o$;B;H>79M~7ojP#qhHrxGD8Go+(CV#PiA zBm=gd89RA63uW{E%VT&X?VtTC0`(qFEjC7VasQ2gAEKe==}i(GLrNItyUGM#IlKU< z;Zgt^G57?5^ZlXovyLpVu!#tj=P#l~!{=Y0T|LWV*2eV`PLNoa{_4KgDB__Y%X)q% zDl>urrq@TgVVP5zenjv9u-Z6tHxMKJ8G6k|GYz`nmb2|c7x|Ut2SkxI;^?)8@HXE= zA3g1oM6O=i7NF&&iAyl)pkj{7FZIg79z2E#gpKhQNLttzOI-g*<86o!g;3Jya9<2W zf$6{LYj6$>rrSh<7IQK5jdnTaeP399oFx@Amo-d}zJH*4tZ{^Y0F>bbyHycwLm4Bp zCRrbsm?b|@CUpLO(DyQ>q?jR1B`s>2-w~Zw%jpnXvKK9qi!ocWLrNFXlP?VaLsl?kgh3XWBa147Mx)h^A3UqSGToeV;b@TD{B7+LJ@pE(|GC~;^+P?IKxTfpTH@yw4_!O?OtrA zH<=4#fXOJ)!UcgxWr=p5!qm~Mnxk&spwfL$t4Q=Bt9YNIX%|*AhBmDE zPbs9+5eTg%`#Ws2#%oS@u%gxU7?lY`YvWx4UQ7;){~~MpJT4074{;-tha>eL>qh@< z$--N_>*tzj*jA3M`Ijle7 z7fv)=8tgyTn)}0W-lBF=i_S(#COC~;#5oRykN+Agrt?w`A_`^Xhrv>#eEGxyI*!U= z5I68><#b-5{c}{lQpFsB7--4Q(6|BPcksw6%wyJ0g3($jY=g|SI%e*qH+>1pu)uH+ zLt3V}WU*rp9D0!nNb9RneBSt2Q($vQRlX?xJI<0H0J%Z1#+6|-T!PY4$_EYzq3Q_A zJzRMrn8x5e3z-`Kd>olp1U|C;S_;c4R@!rzzeusn`3r!&^^LoHHe-Duv&Bt~E!1}> z(~Gcr7juwQ%am5JZ_2T-A--gWQ2=G&P<{&K247mcmrkQ}U&g2!kJBNr#&EfDIO{O% zLgvPszJpEjZs%hY3pU}{x)&Jh4Z8acaRd>T6wm6;A#n|(WY zvr(DpMOOKaXDS(@9a`#pB#?=jB4%SKH;C2;(@N}NCt9}@`CSH=8;5Ij=E-0l#wI)L zB8zj*N$X_6Vn{k++@bMvCaf%Z*Gx}=Y7*5x`HlfB);DJ=mm^Wlsq$cC0_nxFN| zDmYul>;p=ues#5nZG-zM^@SD-`|vpmXPJ8W0HJ5p7oG#A*xb6OPx>Zix@|HqL)=M8 zRbT^Ye#cT1O9kypJ1UM%0SuU@C?dV&P?wDXylsxJeb3B=#p_oX?dwPFp9fug&X!MhoxmKOt8>j4^wqU7MnG>d~*%>`hJ}Yrfd^ zMPP=N*0-OjR+OPSFZM&Tj_!3OF>_fo4JNhb6#hT?tw{mI!OeVNoP^M$XN z&F}kKl)r-7zN@*l<;(TEhCqGAL(tbjNXd9*2s^dRbXjV*=4~xR{`o;Oy|4Gzn~58_ z7g?4rfo@efGieBes|FPlmMtzU|K^oy#&E8Ukq^_yGF2@)v8<3jS9qD(Qghh4 zy`>BpUw=REi~?hs1Iyq?Jx$db2Jt-9^J*9{#fHJ>D9h<5iyNlmy&e>a%wjbIT7R>` zVEt=7^h-B}RuNy>v&GS-!BNfM97P{j8VH~YdsPcnIvV>fOTCd{tiD)*Sp7D?h6zQN z_l1qtcQ)!xZpp!(Go(Qj;##Nsh`Wew%(#+h^5z+_9YcK2^DC5#J3nhx~jc#Cq#FK6}sYXc%TyTDY;!2+;3T?h!S{Vmi{2fl|P3E>)ik6bQ#Eo{F(Lb2YYrsqQ49>mX#m zv{ePz!Z@iQV?Z4CCw+D5YfXZm*)6TY<7oDqmerbHCsv#9Xa=r%!wBAfp~Xm88oLwe ze_x0WU8f@@+N*zIL8*WHPyc-R7pyr}K8lcOe}i@Z{?C`6tm^7-56TT@(?vk>ms&II ze!H_FoxRSfz732KOMEdLmZrvM4$sKNe6WNa4~}kE#OMO0BuryjC4AM^T*908q9MGg z(YYVDFf{2O&4Cb$8Mi_c4rvy|s4@_`@Cfpw;H2f1eQ@3d!qPd04xcXFzl0h;=fD#R zjRif+(H6GCjY)hJQXnp8?eO@1K;=-JLV{1mI0hsb;cW99gXm1~Bp-m#adF06IJ(F!c?6Nn!$*A;uS zPn91+v=~Y0BKDm>fAuhu9#N?313KJ1T7jf}gqYvtkn|WOVg~HQTN2&7OoU87qauCt zYQ_M1Mp4u?>W?2mn2lWlj~lXqu_dn;enc4{zCIqTXvL(ulj*px_G~^YvGW_jUObWO zFQc!f+z9?958%7KDC(nt`juT$cGX|`Ys~Cs@idcWM+cga8i-K!oXy;PJX{bmbJ!&p zWv}naF_AJQ*OY(5o<2q>;kHyvh7a^+x9*z+4@2Z>5Kr&hf{S}o0|JIWRzF*LNA)tr z*Mav>>bG#X@Tr)R!P*qojWW=kbO11AxcUM8G&G0kAmEj}KFAWmXY4H{sQL)d_zQZewPnw{==BpN>GzE9;IKHKMGyxDwaAGq}nfHlpWS=vLTf< zZ>uXa{8Mm_j0f8>?u;*EQ* z41l!wdS1y^GgALTxdlntlqV!VZHSSuF_s9NAl@qS*;4wfE|UfF;;g)f9C42puT1!- zFaY=bL7r}y6fv6m__Lr<{=!}tw@Oq%?AFl86j!4U7W_JPIRqbR!598NPom zl%p{}liIX2v%Z#_Od_SKhhi6IlT!MGOeic&Vh-w@#7V?3!6oQXr;2+iHd2^^kt3ru z?KpVRY&=Vy7s+wtJ$}#ijiuocXCF5Ab~Y#g)rq-9nu~1gaCtYdMPWTloGxts$@(A; zppWXvLm-Cp@GbfndCIL&X{GIvSE_$J{84RAVIr!EnleV_R>XP5LuF_&GKSUR?-wNv z==u$_j78ikOQkRqV-toLRefv_2~=MN-p}Kg!VcoD)Jgv4_(RQk0d(#K`9#2k+y_w{ zDo=^7KE_!uY)!P}dG&zvPZq#9fWf0M-XfQ-LLf0G0$kXFM7apKIOK^Vgh`5Ylz7EQ zv!avwg_}le6YsiEdz_OeK6T<7V@B|Ovii*C{uy@VunUG1!9oVCw(Ydq1yIJ%mu?og3tOx z<|`;lOPo-){C||bXd5El7M;$EM#4ta_eV7)mhsHr`v^Aga(w)kw?O^MxK;=&dM$0b zu=z(TfjES|!!T0UJw%%&Q{ibkv}wc-ned7>OJ=%G&c1s|BuiHrjiMb^>Xf*j4q9`h z!kjjO{w{ZH(_%5|gQDSa*rJeFMVcPkHg3I89!IcOD#%YDd`DXx7r~+!ka32HS~+xy zruTiJ^nB@W$e-HA-MzG>ai2zUr!?74x=bf4t$bDw3`15rLi5eIs7IC*KHj*zjMp+R zM7asr#=-s~n4?g90CUC(VquS`$hDndb%Ls?uEr97l3eHzr7@td!@7?B%X{^Ja928K z)I+*N*@dihf0nE9kzYD@tO^-sH|0^gaWO-cE@T@A`-`A1+y!MMrB$nUPf}Xf=eou; z6Y5I~oJ7JlO+vpVDH!kIPBokpnboJh6u_ zDC@H$;64JZy`M2|Lyq?$GbHIl=3jYxvX1~fh&cjvefTUzny3vd?vSJvr73V+09KmZ zxZ>M#(mDg<3N9>Xuz-~g*e&4BCBzs)uu)^q*j1#(jWDss=2REqUr-Ucm3=p6bSc@hJLDyjB1KSy zxO1Ii4Vj5bzg}x;O?rVbHoK5HH#8t80gd?>eWV$pbV2j){45BM;*Ok4A3!5dtk;-Z z-zwbI&bcMZ$}Qg(CnjC_98N-lI->m}kd=R?+q^`lPM3wtNtDN*!7N>Rpt*F})O>vkp{eiq1bL4rfn}v--P>%j zcl{Tw3w@Ffr>K_yccE%u^t76lby;S5-oGMKqN$RMe z3kw@qRx46~StIiP?wMM@emQ!2jY;&7Bp($f6x zXP6$TEgu2Q1QF2h9Ktf1&48dfKLpG;+GM}R0gL=lOOPJMJc2w6zQc&SkA;%U=oT|K z9mJV%8~bk!;%wNCs`T^%_kv7@=P_EH@KO`#i0n7n6!t(?#iEHzOrWi(chWCMAS*LG z`G&@Xq$XQ-Q&NT|O$KbnnS14D!B-Y%3Nf-H|cAR=o#^odz;+i(>hD?GaK@NNkbfBfX*3@oN$ZWV&B-B2 zwJG8A8%)xMUf8d}Mldyy@e5^k&^9Ct|2TxZ z>mbv~j9~;G^4(kPm4-*|h$#run2fB7-wr%l%PQ^W9TJeYaJ;Z3O#fsSG-C{>o|qCe zle+0eunvO;>+h799jv)@*+)N~7@D$@Ot8o^DFLhPtP8s_zp8aXQ-{tN zQHIl#E4WPFWIC7yt4iTifSI5J`zN+#WtF4iJ!6nDb8dtteT=y@*+bkPgfB`!RhTn* z6AyDXAApxxp{`EgY@*JDA8ErKMqM~Dx(2OEoV3i=WN|9kstm{XKx0eY5LJ3u^N2D+ z-k$?7%0XG&nPh~UU8~YK7IE(5?){jo36nL3iBd-EK0ht#IQL{mQkritqhd{E=NFhP z2NMFeiSjUPVS$#lE6vGgq`9|V!jSrz3j4$$RwEF;31F0ns;JVm$Edhh?ux;l%?`ZQ z`rM2>)1adzUR(Z-NuIF0YOq_6vTnw|3=!rI*h*19ovB2eNq1~iAImy1nH?594p&*Q z`F`9>c1{rT2Wd`W`gAhhJDNC76&cUHfV}p<;up-kYbvEWeBvLe%m&85r$ea8CyE{IWfsv=EO4LIc} zjLfvz0;aE3lxf`AsaeOnBI6n>oia?BOo$(%%owyf!&8A)`muAjjtg2@O2`=4VaUR| zt%@!^$lQY&U%SQKp93&TP*qe}XS~Bjo)-2%|hzMVD2+#i7eGvB0prqF*-I zn9b;N7k&Ty_!kJ6WfU*Mqc8s7b?Vv~il*?lhP)rQ5opl`|J?5+8i7uRip`0!7eO36 z23}anRgtHMJeNFU9GYq7J_=6)@*U;1Dhl;@aK&LdR4EtGB$XFrb3z+VP{OvAohkG* zhCuc$oF_WBj#P?HqZP>dcQ9x2L$`6^nMQMTLk|^odWfs3GsAcq{tm;)_R1jy8oQ;g zrA)vzxuK3pMqX$efyUg_DDzSA!Z3eWYyb3fn~(8XLx9$;lE8 z0~gkKRn+NW&Ocgd3oE(zF#?V4`U#9Iup2^PnY{2fD;N*-nL2Aq{24EAn>03nhs>=3gq=)1Q$zA zX;mXC`tysan<@e>j3@u4dV-$>dUE2-hqoM^%yjC%N6?sO_*;2LoB4El(~$W>A6vkM zE0D6g5ZceY7GB_7IEH(+`a=Vx|DG=b3GoFg-U9h#mQ6w#IOF8W!eV6qWomy3_d6B>HsFR)J9>C*2%B z-TdZh*JGS>IHKi|5P*MHaqiwNDk0yk{!!j-KCM12PWxOx9lc7X6-A^TpLWG;V)0~y zC-TT=%xbEH;>V};<~#Gu!^6^jZuc3_jD; zUWrV^!)UKeh2}-b`*TF{g)J|U#4<>14+p}`*--mC)D8`Pg`&bFPON5LbRLkh-vY60 zfIP!~_|rxb6Ck2|l%-b3Ol^5DP_NrSwv2s(er02DXzdzAZot^cLjhiXDD%IRtF_48g`8uRudEN4!w; zuNQ&z^t1XUVBdV024LWFGU$8yCLFi=C5f-9N2ayd)u;7~(%VLh*I2a^l^q(X!a}Gy zQlP(=&+x<%XI&aA)LCQB+TUy(FAy#V%h&@m=?mKHhC7aFKvNQHm?lBfJ~o6h21;_^ zUO+X5r#YF3X~kFz55KIgC84o-PZpX-A!OJ35eWUGMIdJEG?+dKqR71|ah6Zg+-(6jjpz64Sj7G6N|&n9qAgRyzhIcN(PI4m#%P2&0HvOmC@do$+%#OTUCXW`c_UN#|9 zmQYbcCNJl5OM056kat!-VyYpmwFfjoy$)tfYGF-Q01D;jPexoKhOzlsfSes&t&=B2 z{k}m1?CG2~t~>7;lZ}`Y1MvM)SU^KL4$6g6QbBSddH>=#bUSOo_B+A+;~Z;|^eleF znt9xw40m8DVZJ2jhK<>j^5aoyUtH#B=QV@SMG+i>y$7qpwZ5A@ovaN{(7ll2unO?9 zuSnzaL~72lR_F*QUswgm-a8&k(Ur^d_P8^_<;fzsBk5njAbU!8Cy-6gaL>#bd1bk)7krZVYB5UeP1tN8~Y8opP1h#5oKum zmw3BU>aT<(nEO@rcZRL_P-`c1)Yl=Xg)FZ~l!s>W-GK?~GZAL-A>!sq_9Mwm=RIS{ zLp<$A9-|0mJY86mlUa-z0SiXip^}g5QPm3IiYnGRD|sMEx}ua398ZcwPXX}GKHvcW zS2nx9GXCJjg&A+T8l(?g!DUpiPQb0)hRa~5dx@(kkG0?5bjajKO1w>S(5@e@tC|D>hS(V#@y;TeT@^d)} zJT;GWT^$3SF-?+WDJ>YNHG~b7xR@pA$-G0WFkqh7=Sh}|s9-;6(zN)VcRJnBSrTo+ z9P54Ahscjs9q+*0&*Sl;<^iLP*a91mGkw2UmwhA2NJJd(_B5gLi25H&)S+&%RColJ z;7arAEt4i&MsWq%H;ItXV-vb^g@OW-QmEYL&-5JTqvdYlDd81!23myWiQ78nDCHGwMp z0nKjXFTKT(`HLt(BJ+hnnVZQ5vh>ZPS{<6&D_YXuD+B}n%6ziYKf3M!(0Wf*l~~$!skGT?>T@z>$YU6P}pQYIO+)%eeSak6miaUORHHXC+Q^a z!$?Ma^kSGsy3~$~q(Wg*BlTWE970$rOmkeQOarS$Ehp(L=+I#!(5=o4nql@t3!ms3 z`g;ky;)zLH79J5ARMz@A)On8v02=IBwOBo8V3?|s&DJgAbVUlN=r;Vw-0Sm;*qhQ*qLTdNS1kCca>2H+K<_L(<$ z7Xn#c(pk6*$4Oi0R@Icf7HJCWB<(QEDi2B|VDzb|^&GxaXk@?Cto;_9%eY9-95@Sb zR|J7)7pgFZ@REK{3bZ`J9vzE3(S&U<<^be0Lq6-d{((hjKV#I z{eCIlA3@+spYmJs8LXR>{rCXD!pp~rn%+}6N++3}3Vw`0XkC}-XoYadnH^ECBCByRYfShldx!{drI%bAR1pPqpQ#~Q?BV80J-ZCB(54h zWq5RkLODZdwBsb{)5l?<;u*>&B!r6vlB%_Qc>Bk1AK77IwN^Cd`j>zza8i8y>W7OlF?q zGdWE$f!fT|ggxsrodzCBy8-MKn35ZluGsoaO7(>JD{zHRm5r9lX~LyH2Y>I~!QGnI z$oFIbSDu{GJu!eb^E6?rcAZWE@JS4L0E30Rlrxh7T;=MN@d*Jm*{A6(g;-75r*pu= z&Kd!)$@u6LMd8EZJoWW_q41P{%GXpX#uqWQa{vtYNgDxErF|x2&GDZC_>6ZoA+U0v z&H*o+Tx!8vtseDkY)IwgKW0j6DCeSvDkqruzE{lXT-K+V zytdm)r8)Z(g0~X8GEq|%NJ*nhCGKJPhPD@5e`b;nwFebKXS^%wdouD0A+tJAp0FCj zUpN|b5i^{-knY?%t&I6-mH!k0XniYXq7rqMT0*I)bNKJQJJKuoj4wmMU_RNZ=5zih z1kjYvO)n|5{OUX%#vl70_gXQW+PX5cuUq*}K{!;eDT;d#S@Sg+-%07HQ!q%~=75AL zEaX%}m*YZ(shx8`5e5r;9nXp?*h~nH`*a+GDvsLc=<4c?J2TgZ6`slDn z%D3~*sr~;rh~bvpQpi|`X0D?uFoFj)&9m`Nw$#@ZNT-xeadpvSK_GIWCffC0G$co< z!rdE@;SkoLnPgqbRXH0JA+caw<)spMl>>Da6W(_Reg$43>y!)9!7BeL7BW>i-4u2y zB(yS9XQj-@E)NJ9n+?hiw^3>-j2L2XRhu|hj|r4Q#ma#?$ys_)=(b zZCrZFPJ-{XJLIc_nVisEkh6LPb5iNS3LwM2L!Zh_}{%%WHHnwhT(TtDk@LJ4jzylz$c%h&9om6T4@Gi74YYfG zzX9%m!Oa1;h{$_eC6V3C%80@bdp~hgd)rIo4>xyFH1qhnlIJ_~LI$P}b=eEL#`j6Y z{LOGa9kO3YVZlde`^o4eqpCC}-tnwng70hD9^>%!PzaN%eeXciZnM@eaORHXjzTGO zay{ywn!b2i{JxfN@Ope5E0TFCSh|>%K@LSdD*^17k^Cwv==6!6ZJCdG6^F7`F{5Cd zHW7>IXkFmSdit+J)A_C&b``@~oL!w@gG;L{^EtZ#{bQgzgXgs_Cu#0HftBbr9M#n8>lH4;dMebsu<0NUBw z<*TZ6DJ%5yXxaFgIoRgYx7?LDCd_&1*=woEIMucJYiR_zpvF_+K@C z4HSGwMIT-j)6&Z!=BwsgJB791RmM`l7^}*X$Ji@DVwx(5UX_aHqJuSry*gHSRoK*r zP=}1#g8-M~fdfG87;`aAks!RBvKr*r%)B401K4VV+)WwsZH5qa%|H4Q9%VJeWmiW3 zVDE$w(-afdHiHm9jVYM`opXo^xXz6M-K)SYhd?~-Ivi#^8041mV+K_WF3_2jg`v#WUiD12HI z(8pGVfGv_IczPAQW#5)3pATiqdmm0y@c4n9c5WMnz)JVgE3FSq){DqTx$J6?B=QZB z4B+i(`wk_tRwTkM&~FH=>}xu!Q$nYgaHw)$DTtj3Ry1QrYdxd#jt_zE5J%WeIe*}% z_&mMmz``JI>NOAOG% z)oMaJMXv^NE-$#FUH3W#s`@RRQnvckOGMEM0~vrWq^VsjeHQTJ>#z-H=dI3R>kOiz zD`DwVlKU)8#0M!BCC8J~H7=~F8>4z}j==$VyZ%A>q$*wABmY5ZDx* zKEzSwZS?5!I~w{Z%V^lUwu+-(1MqXTvSI+(2Nmq4Dynn{q)HgHKVJ)}^=*IEC1OKNg%AG{gl~Lr zhKRjsAj+vKA&jf$ve;V(EPbJ3XGKcA>NOab9ft!IyQUASM75WWrMr832(v(3`KD4@zhChPXdD@D+>YPI7le6*aH8BPc176PrONaPSr>>(IN<|lJM*lrTUi;8& z5L`8G*qy+P_xAZt(fq2q5yI~B33F=JuO}j*)goV`uklgW*2>%$AFXor5QK@`NezFU;3bnvVg$!_2W{xdI>}d)R(mlr|9)yDHYk-I(_=V z>*Py_KJ40h@w`HPkvg@#*B7HG0d%DzjR_e*7h19ZdyTM5Au8^w?n7r4x7aG;g_I!P zt%G^CwZn0#3w3B6tXj~=R-?h#Rm9Gvy?;d9Rjs}ctqy|}``6?EF1L1gfSpfCQM3*_ z^vhvWhRW+c zvU(A~-yU(*ixO_1yasVOhT;@s-N;Vn z3P*%cYk;nZ^;L^8eW=gFO0VKl)@5GK*9c)#2I|SPyYIDzy6%<$eZW=sq&gL5bu8W9 z(~9(qw%ddhc8fZG6yg+so!-ZezpsVR2V5UTqx5E|6tZ4|kTQHm&v=8pA@m_tS@_!B z{or^TBlO``4R?D_q7<@TgK+uWiB~i(zNwk%&i^WP^#EOTQ_WTLp;bCM=+OY6D`Ra?I*+~*BIn$$AY&8Kdi7X&>Hb>$HLCuAhLa^j36oxcgeW%hm;3A8&LF+P5@bpnWe` z)x3XA#$_WwS>=V#=kCxtmXYb&E&0(l2C2xYP0e-hvWqVMBSjAV&-$+!hTJj$8BSRx zh5f^^!|+(4;PAs*xZYp++Xu>8Vt;%SvSus7FZ$q3urkIbf#x}jG}T zCpcRkrG3?t19;!-YOq5|?vP<>1}pd@1~M1M{czAUgElobJ$%REr{zn6TS{>$sri*E zbuY-i-Tp9yZGY_8rKzU>AzfBgl?G>P6g+;B5W1i4-xNL9nnB4B_-YK@k{oTu_i+8i zNojOFz5RyJk=*zors31*=*?fm6=(cOL?R&FNg00Jn<#eriQI3u{pIEX24A8Xo5N4r z7abLHih5t`mZ3*@R0m$X1nk(cJ)C}Ecl)X*wds%c0HtKnk!?cAh`~ZOT~qSN5(!E& zYQG#cbesxfGTqt!RP*G6L#~%JBX95|2T#i*Z-t62j!)2;+ zw+E+gOZ>6Ic27wcMXBXP!5RQ#t`SY9o>&Me_@bA9q)&b!TAuM*_PtRlIGZ#`9%Ny> z;By&SQc`1~_0|1UOq%XcU52If_l-iO=bxzPhxQZ7vHUG*7vAgsWcNF7dm>d%eD;s> ziaq1H{0b_C|EY0o@Yxg+2GJLx4u$_7iOMJjg=`oj2MnM7e3L9UmpM30({&Aqy}7O3 z2J8|0uyO?P4v%vJ43FsZn=NcfO~BafsbeT!3jQ21 z?kiX6j2MhrlPe`A;AIjPLYZc}1|z(Hr^&JOipYhY(Blt2KLSId=AErs7HdZA5inMG z2{06Tf~q4E{R|r3vz)~$heZkQ6iO)T!FfU`!8O3Aya`BB91ZfJyGdgqXTfyOx~ZOxqP4y&7d|6%(K#eBjGw{ zv&(Ai>^vcsL6h5OkES)Hk*P&4%;TBFjCSSZGy#y&u%3J}iDTu1oslFwO~4@`5M_Uw zp??LC^%UTlpwQKDJWU|CArMN^bRV%7oBA?Vq!g2aTSyUw_oElgb&e%E&_#uO;z$Np zkwb%1J(v0uQ8}JRu6y$Y$50}84Ttp7bvgUS<#Y>Ek1Uw%h zp(Vo$%*id}kSt#qX@R744ONLfR{7#tYy7|Zr-og&tu&|xDItwzI# zZ+A99rM=0IKvpf0}0HWnpSfZhUF67<$nIM8# zm*&Yrgz|#3M%y;&;6D{wLFFInTt?Ff8QN{m*wN}jj5@O?CfyJp>)`- zgK)$CA}mY2l&&C#0|w zNF1{VKK_124mj|t?r{CWb^Ig!W9C7OW3;)`FV`NNTsJ|qb^$aw%$$8>wD_}0Agd9p zGcp|2QGA?;4B;(2%TUYbSx!k3nT6wNVj$yZPjqsQCs z*YJxPCQjx}Z};z&v*jW3_BAen{um)kOGf))={Yg#zOiVIR*U+Z1WnHG!uMt2Giss~v6rB1)6Rh~)9 zW%21L)<>lg!6-yLNTY5-!Z?ah(~?)Ear>qQ@<*4I(wN_RtTdr<$T~CTZ~UkKRa+O! zPmMnt_4N0n1lC_PrW`)hP&`1YpJh?f%i9!&olZE$BXuMSfb1U|6i|j9s$nfGSPL^n z|92uuU3C4!;=S~ zrG2DeXiU(5{Aedr1jL_S#6zBdO+U!gOqIq|FShS7R;WGe?WclR2T%f6AO(>M&`R$+ z+BNO`m+1XwA%9t`u+sL_epvkqF>yPYnD}73+h=r7CT8tNuXIn| zKbE@#&zbajKeIZl8^qm*tt>j|m)!|S@hD>uPw1EL(o26(5ann`4KXzg;=-z6259;l zvydrhpUb@v&epvVINyqmfQO_v-B0iUOP>)Z(X5mH7_Z%ZcH4cZ3{$ut&A%rFkXJoc zHn8_A-7!u8n)E%7@9b+*@K`^+P@n(bKZEnbvk#?+15>D7f-+3CE$Czm_Wm1icSVPoj=^SMu6!WkT#&d17J$`EY z4=TE@K8o%t1(AV>g-humvVx6Xgdg-EU@rKC zxT3B$U_~1%kChG#;^N9M_{}TF#fM~N87)t5FfGF= zhgtc6Md|sVKZ;Vo4|(KTkmMDuZ&EV0rAfH;=xh>7)!B(D| z`=+If!)O=kN&+D%$^V>LME06I1*^2e=r>_+)!4bL-l4a=ci$NWh1izINFZ*~Bk z7P##@ReFuVxWp17*U&2^ChMh($)fe@Ys&^cErrWQpdO;^U#H0HqPSbH^fmpmhUg6o zipd~;IwN#knZE0*oE}}yKRSrs9N+8G9-i0eZ1)HKb}L;oI0&`!GdL43;?re|^N!HW zx_4cQup|N6_xP)-p3Cnbq)0ihig<*czv`;yB%c~Y&+yfAVabbFe)E=I#HjMHuKF`} zwi7*((l`2|(S4~5@hb|4=bcv*^Ny0E1EcdMt%gC2jL)wajSuFK7s)aY(A(>}4=-u= z4Wjd6HV5KYEWa8*0WoWf@EBva>wtW!QjPM?kEt$_!~H7njVkP_4(lL#o~(|u_f_T= z!{9lN+gN|6^ z8#IkR;9aJ=O8sd9a<)YQ$>VcTZyAq1==e3fgR#&p4JPL$8)c*B~VMnoy!68wsCdH>FtC03B0X z#O&Q9C4623Z`oYn2so&Lvb*q@U|9n^WPEf{PJ1cg^BRcDrHvk<*W^UNI-2uLj;~AZ z`ITlQLc4Mdq+bJ(k*)-j4(7PLZaronmNev2`tnPCLDM@*WP4r%a5*}-(@^L3CoA&f z{gSy1>N~v4VnRE3NG}7oTo~fOd4GjWVxB*R&$D@{aQqf~E*~rC0gnDkxq9!Cki->+ zAcwmboCa0JdrrEi-%&9)x)?6XABT7gw0q7*=u5o6LRLZWoPYE(BSC%cs(R7MoWoMB zbI!=?TfD@weqRm7YC4l5JGWf8411U1v`3 zttgYClR1u6B4q{8b7G;M=h)X6h8sEC1URon44U&q-Y=9wy$;!y75n(;HHB=-<(E^w z5TtWbs6cO3U2iVP!!Jn}M#kj;6CUB7)^PWc+ZF?%8`ov~-ln%3_u5jrPjV`p#h zmCkt$#O2%ckMu|iVr%-dE?2)gFSCxhebL^Bn9?x3Q?{@Vu-&XJNND=&r&VG7QV+Xz zu}e(0kjs0!;l37n9lmFv;v-wb>FrrR^x`4zMNeLlui9Y6sQbxwALd3=6FZ$5hh&k^ zO^jq>DJrs5VPPjc6`Pu1dwV(9C!=@j2x2KZT{HL5Ozh`s0L8h; zEGz0*Q^%Ip@;#k0Wg}vJPW5?!%SK)gu=$E#M0{Ic3GHS)7^WTZJcswgmK3jT0*v-_ z3LH&W61y5}7f|!x*z(Qb)1i57|DqHT?@LeAV{8s1%P`qPY4@)OFzmH@mTs~~=3wsk zqwRD=2;oq+FtTcp$<(bD*L=A9{p;A>wSP|z;>Rj=?;!TB)(<>eWQZN6KVNKpVj0NC z2mH6B;_!jmz~R4qD;++~sXQTsHknlkJ;dRjD@0EdcDb!M)zO_c^`f^rR}LO|JG!Nh zk&)5gjJg@*#rU*5gSAN(Zvw0ldg`5?gMW)w%nK3;__zl%z}c?G$) zilm)-9b6P@7uTbm{De_cHoz2<;#AZp?Q5-cy+iV&KG7 z52DMk;WxdEir>pQ$N{4lqWbbxP8JQMcVy_D*H3>*8rgol2!%aJ6nyW=Fq345^WMt$ z*jPHqqdpR<=3h~%bo*acIOSx{kpYbT)EP$hk*~S6%SM?eQwiz3r&n1wsQ|_hpcz2#smvsBVgRUc%PbyZ@CaXrM0i+|^?qPaQb>+tirFUm`mv?ZX zj8UF7kj%!diiaMgcWCxd!3%1ce2valOr(MI;vdj{^6F$WVas~p^b()%>;wMOK1 z?kadRltBpUHSUW-$2)_$DaA85HPuKCp35;+6)0D45vx}-I8v{1Sb3~>mF6Gl=>3}d zezbF4Za<~CxZqar*KBEy<2Q-u(N|^SM_!RwwMC6E$0UqSaUj9T(K?xISx3tW=>y)E z5<|QMA{qb7v6Tsum&g(+9wcdv(95HK-wX9NJoc>dAj6Pyb&h(Kvkh)bonQ`*){*d_ zR`opx_52bVl1WLa9G`+A>o2cn^jp@R&e1&DRXIQEILNjuu9PG)3x7FptUDcYFr_qg za8LNfNJlg(`lO9ALeY1>goyV)t9er&AjGC(iUqTiHT5&}4S zE{|A3A@m7?lFk}jrB@k3dM+|5CU!$|?u-z+JdbH&|09wjFCm~7P$UTGy%yzJ?6CXd zfl?9VXH)&+NmYAV2BN+QAX{)&(_)s*B;)WJ`q3n@&@h&#nk?WERi{o&(8)f0pr&VrpYDvXt=?wYbaqWKEdr~2 z=>zz7-WpEULWu#&3Bdh(whe@JOHsy4V^QWRk?7Y|;zrlqTt=AUuna%k8rAkUlJ%?K z-@5&V@oGPqp==FdlHT;raNgit(eV+KQZ>QJ@)%8L1-F%=B+Z!%S#%ib6{69}XxS*~ ze#k|S#kNQo58oq-oqW-=7`41=p;7&UPMV_&Mr;S-QF2iI4*^-b!h*9kN?v{cT$GHK zeWoZ$cik$oa46kngVKc3{jia8iqd_?zUZ8m&!S`mW0i_J<5y$a;(r_SRa>@0)8D`O z-S!2U{bKiD&5mwb_~++4`xXIDt}k<QI%#F~TaNYwpT-i6*^=u3^l2^6eAWfAH^uo}zh;y&p*{A&DBid}pO zEh+}fjv+^bZeRIn`yapG_v_9lO3?FhyFk^i?zk@kUSa~G_Ah$XF^2ENkc@XZt;_eIBtJfX-bw3gPiJw_4&P+niT|oE z+0G=LmIXiFiQZshaP??BPhsCk{h>qt)Nu81xZ`iO9l&<*YhM%ms=g-$@s0VFmC;np zP$+pkcu4|1k5J!y_?A}yynXV(?_77tU^RTaQp=mhY$nEg`mXEi4=1yWV4mXpo!!oN zHr_IuwDYO{62@k(gzw@xaTYe$meV6d{qCKyn0Ls)hp4yQ(==pUYSqrP%c7l)R&Sg| z+)p<3(y*nU#RwfYHy+go-dL&2PzhqKFqm+REkL%C|W5SPs8Kk(in~R zj^ATH4lnCdDvrNFE78sHnS7XyG&q}!QyTSnxW_==96L;P*3)$4Rp_g-Xg96(*@zH3 z1Gv$z(kl_(e!ybQRcFham+5mVBDOb%E!i55NU|q8t4}%SN}uksXr~yDc1lBX*@zsq zVXPX%+f5qnYy97ySw(&M@DC>6HdncZLCq8qy?!fC(#8rWI9o@>fyNVsYWc1SZ{^0}qgaa{%za_zQT9ue}QAKK6wJ@1eadppOD2~zLdP+LOa;9?Z z-;BN~1ryz|DwaJ!%G0wwhBD%cBuZXWNJ?d|>FVQI2Vxpdr-d0o-#s1s+mZF{hw&E$ z@|{D;^WzJYo|f((EZu~cPu5ZLnsznd{#Q*+Cn4Te*@rGD+Ibhhr3mR% z+=$jBydB;l5LFNf5jM4QsUcE-gv%5+nto#<2@%>QDS4hYas@CEmjqoA!xnHHKH zzV|=xEVcRiqvH1$@}tv+1Y|qk*Ntaxzsbe0Oz5o@{){Xtb@F^1r3C(NUx6Hclb)L8 zB{tP(QFXk>m!~2BSb~N(npzn!rQ2`sq^x-rl^4<`+EmpV2&n<4FQB%h zm3_?{UAolJc`cS|kMiFWMx||)-=tN5h6rXNKhwpWcaq&#wW;X?GiW^IM{5Av_Sork zPR9?{dO<=76T@cjjga<5G;woZUw7gG8cph8b4W>+yutDillxNr-~o^yD}}m?qn+(W z;|t|DECMRCG!2}{BdsY=P`&Js-WnzQpz6-vFrFbCA@=73sCU7JL8!+y&XxH=(573Ik4o)5lt3&7^1!=iL{Hadr zxlVGy$;My}q|okjQQ4HEIe;g!Sop9%8_IJ?JvxlFGx&H_<(u4HHE8SJZR96LCD{*6z+>b%y0kmXk$!@oa3NM7j65Yp)zhOuIOV`q!>L??}2;ha_G z$~SeY3$^-)gTwgQMVJTMK_A2nWvB8{tKa^`W{hmJ9zSnqLRnBA%}~zE`TBFYsw0rj z130sfh0C1n9*W4$1z@<=J`r=Pb0u&(@`{zAwX1qZ5WOQeBV+G>@e*rm*0-DL9l6_? z15mE2_XzQI(x&6 z5sRs5C(x>jue!46s8{ui>b&Ir+;6;NZI-;}^BZ69t5*F-Almguhif4fo?wS@Dva*3 z|Mq|*6XjjDT?IOM2A z9660*zt4KC@T1vtPTLBNO6qoOo`CV|5TnH)^_z~AmG5&HX_8u`$Y&UF>tb5kk=^Mk zqjkh|D9?P>@K5 zBhbfBuMUs7=L^c>zl90$C`bDymOALya<)EFuI8|8-db8Okw)I7jIt zN{f;@l%Y>w4Qt%4S9fR#3MY4H&UcdcLqgWp2*UB>(s5yp%=Qx8l+YTqo*1zv0 zMQH1#muo7UE_kj1YKof7Yplw2GnAA5GIz8Z*Pnu%W|aMHmHy@=NNrNNsDU=_X;JTq zDG_;L?T*WAsJX-F7*@ObPt>fw$+LdikHy(utN5<9Xe7B~?J2wJl?i%hKkvQ) z0wIAqm`Yrk@^l-X8%gqQ+D>aX%h$m1a5DcMVC5S9`p4&zbF+AD>5E*v6fu77iBOF^DC4@+Yh*wp!eAUVeUC7>sF;M$16+kvF4-Ca3{N)KrU@o}8X*rJXGlntN12t# z{fngeX{JNGtATTd(3s&QxkcsQxi#d{ZBOSPs&!lHYrH6Z3B4S*8w!U1`JzIYp7P)+ z%hhOrXVFha{;92?;`RPsEQBWqYaDtV-8<4wVO|M2W}wmz4MmHT0OJ3!bqh<4nz>J6 zVfs;2bH-6;j*$Agr(JYMG4Y;;w+bsf@yJ1lttiB3_r^K#=J29R3gOYIqP_}D1dSC` zo%7@)MV}BpVgcr&!H5SYCn&TKCVE8YRG6q(QL5tTo_x_Q{T9AetBRxFb$puL#aW@= zrdQ}ZJYLtH zamJr4#309}{64wkM`A%VQ;I*eE{RSLj(n%oI{|n+STlVIeAMfht=BEluAJUsM4whF z)a5}?QeuQ}{G*hIX7F&pH8qc(Wj}yV$0)cxTvEj3(Cj&M->E3~Iy&}oVF0w%fdAsV z81Uv%QA*^~)Ja!vwJ;$(YEHu?C6&waK|yC4PL39;Pa^d1A9$F?Q_4o(Iv{d%dXST) zn+AunvO$ROa8XHsGzZT03(o>~9SmX6@h)F_?YIcEZ%}0N%m|Cb9?0=&lTJMWS zw=eqL>62pf#e_o-Cu`)pj*lgKoDg=V{7rBEBLG*8(xZ|1gn}5aANoqC6~f?X9m4pc zA`*TOjj1rHos>Kko-c!9qZTxL7~4~0+&NkIEf1N8zwsK(# z9TBPdF-7rC6_lxJ_;n(Ov{TsXOeHng#N-U2jjpkY2v?KEIiKWmXSxOj!y~i`UMNoF zyJ%$EGPw%%Kp+yl0D*C$p=wqEg^J_ZI$^{}P-?h{lBwJef-7o-cUAk+HW8Jb5yuqD zXuyVDT+Et`7!de%MX4IV6!) z3{LhKKm?Z(BkEL5UylG>)}t)>{#hM&yxR1SPDxKM>|?zs&J0R~}I znxMONmKvqY08I+LA$ob$p<~kMqJ9Y=VchQkoSTfu@`MPF_mrgIa`lum`aGi&P%u2% z9ALs)&`AHJrqK-7wfd*^iKx*AC##HbT(}SZb62Jt#NetT zes}@I%bDPEwCfO|HTg7_graFE7Yq=|D68s+)hDBT)=^Rd;louWh4FghQ-v5EEi(Gp zlo>?)scVc%W6j9$S%{a@!4oP*4E8FB&ok=v&L@LN_6#9p7{ao>lYH9;3m=toqUD81 z*1CC$Q7m7h$K5FT<5=@uwX7Ol6y7Ll1%8*`CU^Bf;}iN|p>0}9s!;Kp{wkKT^1r^c z2JqZ@iw>6oSsNU2gnw`|7^SC$g91TXp=xXNT%nE-3GXPyGfFz()4p(4$4a27Q&@`X%eP7so4QBQ(W z={L?fr_vn z-aHv?;tf49c8>9QS4oWTE5kTq49}LwNP&Rm7H|AkzJWhD5b7`au=*QH0ciqpRvM zHg!XGfg%n68g*fE4S7b@bD^0~L$9=8v&m?XmYx>ds5*{k>kK2k{lRU;AkoO!M!X3U zjrqMOmLnmrV>}$Khe$1&o|{iXM=VgFZb&K`ldvp6_{c?)zlCS>RKydTQ*jT9 zi!??ji}dNjgNqzNN5Te>c5d>-q{OrdC=ZYd_8g$n9;GH#O?K$ra5x;&@<&xzQxsFX zxU?C&bMvGFM~Ufb=BDa;1QDm2f*^tT#Cy|PA}Rue^z102ZpP(zOiHEyhBJ>evNdgU zbbA_Z`jqA>4YM+5tl|s>)DjI!$3~(fbt*$47wFJkkq1ZB`B@JurzAq^(i&1oT_2A z3`2*b$iKFA8Acd`lR1c_nty03qqGIBXS$TU58GB%6eeQMiy}eEf=ve^>Yrh&8|Fi}Z#a_IQzFe@dE2Z%_uBqfUIH)@yECY1SvoaO#QGLjW! za#yJVE`uiHK^o)R>S1n?BH~Qnu?&oCqIIw4tOo8yj#aOtBqumiIg#dyAs#O)iIK^q z3?;QQOAZN&M;$OHgfwqm{Wy#eQJsU+y1}OstT5<VRGg6liQOP`CVkPjF%*y*MltW=bEikaVe~ zNcpK{(agzWCCSyF)HDj49na<{c^#y!sK(*@z~8~uN&9lx^PJ9!6=F=vpT>B-Z$pU|d{vECv$KNi(`jpX(XO(L%-1k{ ziTmBH39sM7ZXYGNDK?^BClX0P7L`h^k~oJ|84no9+`5_^M2$ePX_bCI7S;^z9JN^f zKk*Xr1T~VAuG_QAN*c**=SFz8P$0qso?YRz80hhEz2@QLmvIu4vezE1PIVo#o8L!(R=(<^`h z3=A|e77|5%X96=gTMsk7uuzN9o2Xh9-3CnQz~Om2vh3p^!P~X`>$Qi=Fzs;aM&?sw zo(8|?4{q%yAXHOrqVyU+xhRikwkSY zA}(}qU+8&RQZg9vx z`zZ+7D5xC)YDZ>r(E9`Njg7=C-*mjOobn+MUa;)0eC!{jjz+4GZe%zPO3YDeQKOdp z*^6Z($nd&OKr-k^;eh~Jj%D6Y=aH_fW~72-XoEHlJT~6;Qc1*qd_qh*UNCW336fy6 zF$}Z}@9URfCOZXW!L^>AyeZM;`}WpJESd|H@rA`W*>fkuN@9V1u@CH;=A#Q^;(0cO z^LV%}x>U2W9?>HF z=hRd?TIU>G;9BY-MKe(~p6Q?y!x>-N^L(pz{W;(6S&^b{dD}yFMPoUL)=r4H}W@&GjI z5)RBLNe&5bPZNen=mR|y=(${_y_ov(Y$3lg)=E-@JO+aslpGH1s^?URHA&{d9KQ^5 zS!o~Sk_7Paa6QUh0m;k5$}!$Zn-b#!1IMaFDvMcO!V8=9x862uPNOxcP7plmL=KOZ_r3xI{M@$nGt>&>uYZ0PG4K)mjT_p25 zIJ9^`Y#!mtXxXL1^i0E+P*X1nDo4$RWa7WHiY5J&Qn4A3Wa5Xj^|WL^3M=ZglZG(o zL@Es;H^rMIdf}TuGhd3v0ZDfEMknieb#EVs(!4@}e<1o zMho&HggI|r`(fZZSWhIF@u{`;(0I&}!|_cjWhgJ=JKj@L-Oy~kaCf{PfM-Ixjm9KM zrEJgjK|*Yh{;1+sGSH|?tOh$g$Q1DE^H3TI?$mXEEw*42e%3eh>__>jRd-88;QdWqR$DM^NVuSMppfx z-&!?qJZ;&|nL>RYCYEMS$-TB^BBSCWebsaxk%ed9<`Xc(`wD5v;-POsYZ7GA0MHHn=yVTZh{#6Nv-N zi23}*#;0L2K(T;1aBO_G5G4(;G`fDUh6T$y)+!0Q7!JiDg`Q-WHk%t+k?6W|9y;FR zLdDWJd~R}v*o>V2H&&OJtk*pW8ds851t0JP;g^*q(7Txk_JOUUje<$tnbinA$r-)V@iI9 z5q^z7Q;|T!=XERwZNad-ui_ZiPN!rI2|Ak3w~)7EG-y+CYRRG+CwWVc9)|&@VifD0 z(*WxC+xA6~`gtBFk!y};Pfpih;sMmP`^rP&cF>^98zp5^M{hCFNrc5raM2P)cm0H% z(z3&a<ACsn|PpaZb1iQx9>|u~Z&O8Iua&1FZ8Nq!Mp{)H#(-I?m~Io`#n2 zJpHH?3Mn4p7N=V$;h9yv*<+-u^P64fq={fwR8YXK8%i#Lj?N8bHyTr7n-t9PzLJE5 z6;g!M90k3TXN$BBF8X-34r8diA}T7?^Q6u}vCYM?Z8}M_>LWVG zxfFFw?|GPbT??3=TPYOKih{l*hcVTwEYYA9iG(Q$0KBT*eAr!4)y6kaB7}@J?(Vtk zs<|MVx3o+H57;^qb7~c_0Kv>Y?vAS+jl#YPZUh9Z#KUtdM+;f?c(k5XgNuqd6;sWf za+x%SuzE6|l%y>20i z1a46`v{l5B$d_R)7Hl#h@@I1;B5r*FM!K8kl=K*5RS{u?zh){YgK@m8B(uupoHDC} zh_d0TS&vLjg8u%A#!=;5g+=Ckm?UfMS4KpdHYiR}qE&keN$4r3GKPqQLjw~5!2=F} zx{MMC5uEUB5f!Hx>D7UIMM)e{Iy28Tj`pasEk$Wr=AW#ID@jBmgABy@Xdyx#;w1A= zU5<`we9gf&qDh&%!2Xa4AgS`35Xm^DAmWC@quN$ZKhYNQMG%>6;WufCr2pfSw>!P{ zPar(rRFaAmSrQQGg;aAXt6B8O-_-a|5pqAlO+^Y7&jyDB!^kdt6hPiE;uOsRdRLtC z4%<3u2BRpW1#%mMg;YG8t=Yx+rb2|23}_|LKg*8v2Xc>kyEqAvm&R$iqAonqRX}ovR+5IpounB z*Ds2hUME7EulyFbJ8u(b42B}_8&fevM>xcrwQg6B{-`gvO%cZT6mcn5h1@@_wp3X( z3Y=CoSfquyK-HF-l`$#%Y4`|n6iy{6#706U@avy#pZxJ?og9W26(Y1rZk5%wo**xV z%z!V%kcK0NkPbF=P_cKL7ULtpCWMERb@;TIM|CXaQdu8*Zt!tupd9?EbS16Xc?w?N zNN*GjPu5wAhVLjm4WP2kmxT~cf!-v#kl6g=5M&#YUK=x=H@5wf3a7YnW-E*&G#SzM zN031y7=@-*rZVrFr8@+}TF*nl>$J_feh~|&m;@nhOS`qT!seVBB7lV;y7&Skh%IE; z6gx%7{63k{5mN3zVLWr!R8C|&8*W}p`~M9nQ?46raAcR|*3j8QqsCDhdyv#viII5d zi{_1^2Oi(osB(;$!F^?kxpLqfF`0KjtJ1(i5?=4EcZS2M)q1!o&iKYcm}H5`!ojXI zhH}06ER|fpxfADM^5`KOOym`_teV{$Q*sh)sP7u-(`-)bEpKM%cwxT<^K$*z4u?wN zohUuji>W+|HwrDaN&FQwET2s!iydWKssBMeT~3?*(St=Dv1Hk#2d6~X&E0Qh51eV z)_<5m7#{7!f@n#goM?usXv%dCIgtyzz-%49JyRgR4Ds^BRguN$Xb(Wt26qyq!o=FsI=A5-bI^X+M&}VLWYXr(L#vok{gcJF)EEZgc0=PFy630NQxTw3ii>; zzI=Xz$S$R8qLYOH)wDoj5VNMG%KgBOc{=D1yihC45D{+X=Y)#SVqDG#INPW=AvoJZ zC`0!*MtO99lU9QX^*OIHX4FSlmz64e)y_>LZJm*49^MvxCeL~1@Y7X!G^0*81u8;g zRV*Gxnx@8)NAqaCVtGHEkEqdIuhws}1?W^<8C1b2%rq-|#L39(ZD9&lgdusgvs_xT zX9CLMw0(@KDyeu3^4r`8AQ{H`8MP;1z3CVlafUY*vMhFJys;$9k`S7+tQSn;Wu@}; z#GWG9&4P!#rr(_5jIS)l$?`W;EX`GvlIbVQ)05b6j&rA{DMyO2=yNoBS;2}siEM0#{2&-4!+*F@hN zzuxlQ03>@C{5r^Ge7F!LF|LIwrhY7!Ur<&>rUkFWzaRkbmeUOR^=XvYzlAZ`J6C3h z>rm2ZS_wn1G0k7Br@`}44*H;Em64?iKt{Bs#ZF)zE-a^HDMepZvenWtt$aLO2a{s@ z#3!FlfyriWjGUXH17}k`~nUDiJ()3_0wqI9QH}mk%R*2r zOuMx7oGy&#E}R?E=yWm8WBk-hCte<-XO|+eSKwUbM_6pyMb&Gswi%UGh=MO0SQV~p ztI^}Y)R6XhXNV!xxr8FX-N0nLp-$^)wm*C3s-!DvYogIJ*ic6<_WCNUXP38;H(l5i z50l}IXl8QMl2WLo8dNxXelY9#DLbw1m=n_nDRIkk4Dw|?pilPlYVFe;<4#FYhmbbt zB?uwDtl{OkT026%il-S$?PQXw0G_Ful29zH(IM+iHi+?6GkNrBvRq9|qwJ4&)set= z+s;pf$w#(N)}l2z52gdQPtr=4wH8#TR@&tZ3hsFirF!Ytz-Wtj14A5CS}LE1LzZyi z&UiR9zR-kpMj0mmN%CxJ6YcI?81|OjG`L#-*b0o0N|7 znAD%4*DC2_B2P%1W(wd6mh(?PkA`yPg3lbBrp?0J-MOQAhV>J_h=FA6!saNS-Mpj) zb8P~ffUv_(#U*sQUk;_86^erSoCpsiScS={tDmaeBG(fL!KZWd&`Q*lFl_cYmWALv z9Z%V3&(S5NJ0!%zqJaK~c^JRAT|cnDw3C&;P2DSIe^tYA?67lkf^jJl z^gLU8tDoj%W}jB!t2_F}5_a-{icNiNzZsr8_+;+J^)mJYoP0P;%!_{&3OcJ6UZ?!) zCXagbgA+4XsdMvxc~#N=+BmuVeePaq*UKn24VUyvw~XoNRR9in_)B-%!{6>Ac=(&F zde(NRm7d$pq#d+eD@};y-2Pr!v8ErBA}D!Y{_pgO2s$&A-ZX?A=PxvDw6Q>C@U5Pr~{JaXL&0(d>dTy;c zpbFWj1B_LRw~*&jIvz68Ur$0Sg~%SBWEUFy+Y}8M4PSaI!MzkGF+Pk=YN|1PH7vDQ zwH0|)U405F_I5XCK8ODPQMZGJ*=3yOE~q45HtXS)90gUA-Ax4fzq3kCo10cb7oDf7 z-SRJXrnjDGyP*dTq}uY_OQ83(Gq7+g@m2H1>sY4Rm$b38{$Z`W%)#NOyMp6yji|?8 zIr(w=rd5KP1LKg*aj^4JF46K@9i5sbSyI+WG5O4ve>E+&d*@+ck|iXz$docw&2N`e z*UyVvqc6zGHa$}do!0=^zj*s*vXqG^TAcOhU?IU}NFeIHXIxtQ(w9QQbS{{U8Q4Y> zyg2Q@pbd>CGh2gExQZO<#%Ky|!yoSS5-q3~K-e7~l&xGwCYu%E{3|pt5OM84rPYJl zwO$dXBPSjEl2TYXSL8$;P&Ro`057bEfMxL=WU?^C_(kDQ(~?CK=gI`S8Z^^6yil-v z!4!Z*lQWbw`+PFW!<-Z)wN`sDGOF!ETPdj#(DlR}hk*8<9=<9ifMl#!DdO*aH?bjN zK1cea@@9S5{sEjUYou|M*;8s}%tO>3zQY%7;Gcv^Gt@#+vYWRPO7=R?y|PQwM^*JB zuT>f!4p+2j`CC?tSWf}OW_)I+o9F%)!Ne0-=^h6Y;uHDrFds&V#iz4{9tm|9)6Dj} zC|RC>(>^Po{a{q~a9OWhu$OnCcqTN|AR~r@)%SWUeOng(TdYbC>jIr;Rhr~AAi7Cp z3B3=8TXU-V_pqqc@?>1s0%@!5Y42j$^k=#~U-!5${2nE)msSL9D9bkK2T(G8fw7}& zkX~o1W53L)xHk(c;yD$iBNMq9@%qlx12C~J>_g^79BeM$!!N_6sciw%6BAcc#&Uyc z{S%MaN{#>Xh_49x$zG|Ya@DOcFoE0plb+hsrtXvp;R)jAX+J?&#)#wGPJ1Su__rE|(Z52)#5L*q}N#ooi z=}BA~$1x<$#F69{Xxh!FRyMx$ab&5B=dC1h9V2CQ7~ASejU)Z4(qW-V%78GTVrKGD zapYMIxPkd?Ci}_Z{IW{L3@;)N%FQjVVp)PkkIy;*Z@8&?s0r#@y0Ny`ADCgI?7;-( zI2F~FQmL9V>M}czIsv9mDXWrnV|Ix^@>e-kn;RD{xo%;Pk>N8JMLw)`P&JHKB9uxw zGI{X3C>f|(q3p9)m^BwgKJ4nSH%cqhc-TiHajE<2aSOu;B4&t)t8;K=`vGNIh@Bc=i$=mB{dtqzUpW8qFHN7`fTgF$y z$eP;D(P5G4#2MFHxXPCjFKHpFhc#YLAs#J^u)a2j!6ADriPB|X98HzHKcVO(S$|aG zZXGopn;wgHL)O~2z zM+fIH6JlYGmoF43CDO5Okx4W^ZzJqUW$d_Uc=%}#P2y~Fc=)Z8A1B!pcLLQkHx*ct z0>utO`W1};xAAHY?hvc13&T!D?kqe`>Gi%?1#<1{|`f{Y4}WEqTK6j$hfbZlrmN5*>fKn}UgH){8hn<|2hqJir)X)RTE8zl*1 zp?5Y$ZXGqp?|9O((bu@J-79E?fi5byPSRq4bL){4G_8hzj%+8`?8ku~xQecP{z=WR zEn3f^8=2CMH8*WB(R!||UvgmWBn~RhXW?IC8L)Wifa&|+Xm}-};c0CCgH`@yb_Pr;i!$<06`r;&+J5++ zBO)@n*>nPt{`H3{14JYqLrD5zqtbra9VMW`%Rvv@ndD~Z_mF+66t=meo+o13xyW0k(<%u zDF=F}4Q7vV*VOhy%i;{b>GydJf4N=N_%#O6|BL#b6hh{)Rw#X*4L1I6evW zeh(RMd`Zj?CRIP=H#dR_ZA)hB;FIquhBf$f4w#x9=D^&Bi0-&1KqX8xU3uoNHa(uI~8?M1dnN5@eK5EW_`;u2OADQ6=^La2{51py3 ze;U<5)p4cRd*{eml4f*9jVyS*nfqIf7scU~dqK6a3p8l#&=?)gxSq|DeP$67Wl<`t zf3%8mn{mY@=lPNSPxsQg#E6L>wu`GA$Xk4@tu~!O6;yA>QZ`iWkWygLB+)nJWRB^g z1s&5Er2?aaHKDr*@$8Fo2=z$VTv_&vs);KaXnDGc&6})kmx81Rg7P>O2wqaj~dSEaSW zjz)_)l`Xw6s*UNqxwQnyrLqN|?gQFt>xxyvX}T%jbl+6hYP(^?2ub=;=APs0=@*@g zksT_5yiiJVp85I(I5TB;{5n?0Q*6@c&)F^6uf71`GEuMU(oVq(YGzJ89Xk|3-Vg9M z^&)_1y95c3_>e%&XCr|ODriD~K|4q+OdYC9-7IE(~oI-ZUG zgsWa7e>zfvfbYDqq&Gdt`}4GoR#)p7Hq+XM}_I2k;cP`-v?Uq*4?X=~v% zhwVM`=&Djyg4dQ;r892@@uB$VX^z+Pk@3mq2>ILiq7;8%>**Gu-Hhk3Uu6h+F>19C zy;n1E5Iuo-k~~90(~3bn9&L$H&gO7YYG9)q9d}0mSzEGRKtURg=32(7(JLO-5?ypj zO!zVlO%D*{yYXtO-CXF<<~S4;v50Q*Hk+BCs*ADG&^VsUNAVUleuTnM;}U*}xuLk2 zS{=i0@?tklp1x6%4o{v%rLarCn>3SQfu4A{_IKC+MIZIqS^C>-FP&QJ z37EETLF1rr*r$VLH(!>qW=8MS7pmLT9VKaZUoCgi_-P}ax-fOG`X9>jYDA+^l4dm8 zJsJR0tN15rEqHkpf9eAOtOl9VD{)akS}s??K-aaB#|-(Ny7OMHeCD z5TevS4 zl!uzLBF=I3mF+;q*QxXwSjtx;XQuciXQz8*adzh#R3}p?BBrOVeQ@xIT$U?bd?eSX9zbLq}F7sXzd$Y^ukclI%J`i;2Kx#u%d zjob}A0vt!PjkJXXbo;F6h=s_MQW~N&f#i=*Ba#JR6|X7|5SldcNH*3TvO`{*4k#=s zQ=BH7SYnRNla2hXvY=W_K&@axwKuh3@k{{^x-B%j&vA`3V?PFWLHUXqezMm((I9C>R5UWo+w=6nGuhAJfN#Sk$xW*T zNpAWj7~tPvZHrh@Q5)T13o_++)%PE0|0%-f^drf~g);G^BcntHoo)^YNa8xCoes?W z8G>mmC^RBS1Ia);LqibqO`E<}A?z@#HldWk?ns(zwBC~%L^>0x`&ej`Bl%c!0R<`0 zNy{?vb|m0?IVrSb@e(6KWcR;W{&t`sM5Q84)dEe}VY9no5rx(nX{Q1e=3AO<+{z_3~`V-v?O&f+S#;ZyUxuQO=;MmB}SLc z8thQT=%mSp`B^1iMzW!{Q0mO>BQZ$2UH2e%m1@W(ko0VpHoP%|GBD*Q)o1phW3PaoV@HWI#Y8>J!$O17 z-~y%0SNSl$u~=;ernP z#aez-aD9{vnUH6yp(;077cV=$1ccPiT zA`ed^0|o}}V#s+$Gc+HmM)E);Z+-?3QY{tSn*0#Vl^$0Zh^CeZ_=*2_M@sXsmd}oL zG}AwgI*`}+O?C%IUZ)vUq8$)VgX$-b%TV}-ZVi;(4Z4)$B3yhM6^juPHo`nP+86Md zztgm0Xla$RakNrH6fA*V|6&1I^%z3&q6dZOmMi~exeGgXcYSC#L&={zK{sH9YeQD2 z4hdW!G%uk_-+X5`(9@#MUdA~C4wT}s6gprIxdiOoI+ChdFXV+rac!vip>N~UrFKX= z!O1xBoSTk@+6URe(uk+xJDg_uo#~2|R>?z+*?S(ISaM$xWcn?n#tQF5#KO?3vqO($ z>FnLajEKeZLE;~pHE3njqEh{=p~9Z>f9URR^luQdX61^{t!ktLwP?XduGq)*t%hbh zP$XC=cbfOud&c?&grs><21-1JNy5Mow$iLQ!eZe9jej`J+M-EsL>iVh*d~a@1!9Ky z7x_bQys71gT=c838($OC81Nsm3Qo4LXG$n=d}vAYsV5g<4><<~qde`3$}mSI6|k7o zFb6i$i#bDF5ZSgL#}aK_zqio*pbXW z&5Qz4hzA8fllL)t=SYTeSSXH>Wa_Zv&Ji&=M>>%gu`Ta`4@8uQGFRg-PP;c>@S02o z>P5K`n!66r)Fw?-M9zx5PTrqKcvrnHo@B5NLn35r@Wf9vV!3mAf6+1|N7RMN@tlki z#L%>7(HXDDkir{r-QZxY4gA9}5Ke$@B}Xw1xX>OW#mM`UenPzI2@QS2+EP!C9b(44 z5!>^LVb>pmh5w97$Kg;=T}^zKVnk=a%TggY_cYRGp<#(u*;7X{&Z%~D(nmOW8wZVQ z(P*Z(`v`Z{f+@Bbj580~+*EW$xzO$0w4!~KTneA!291w##qy{)(p+~81QQQpaW&FG zKUnAh{I)bB^8Krnsx6)rZj(TR=J+%}R;~zCN-eYsb_I zOAnyjk37}5l7;%%sa6hz`$jtP&h!oqzNL8?Ya8Y9fyD&g2jDOeSYwGwA2^dyKqaaN zo!Nrktt#A1;s*x@ze7nyiUw&xlUiMn4MFTm6xM01P=e7OvJlFYoAjTdV>q68RFcJ% zVDlR7_{>0K4N!e-?xj0>tH8ux^^Hl?qjO4#Aq)>dCES=p9jLgo71oxqNMleuLG{Pe zjICY6+mhP7Qp6ESf_{!T_j(nxkaZ~UgdIARgb(RtBWb`@QwL?Tji4gjdvhmIY}K74 zP1Ta~rLCM_-18uK@#Cw#{B6w-)2&06Ny6OjO7HyE*&6+WRT`0z2jVu8Fu8b7XA#U3vU&dysCbDXcxLJrn93;)4o@^yPw8Wghn_N!7xX8$nILr**N>+1c=< zD8u0bkTz3pbyqls5ziWd{UXAZV^R$1**86n@_Ly~XCq#}E7Zb3lh8L;s$(%n$L3Wj z$M^0-pWRiE(L!4E-6zsWb_Pj@^yJ3~y7GPuMm0sq0OQHoaL-ubK~e~|l&9v%NTCB) z89y77Fm>{91fNC7i;owzsxDf!3T1pqZE(Wkr^UiZA#@97AQY185aME12b~0KanR2$ zO67Yzx(|{T*sOH^i(qVJH@q+g5KoRq_@tz!#t)G=Xzw5r7HNtXIb=)omaGhIqje}e z1(6Pb3=x~n*i#TO5xXpcmX*-o;2=s_mB83q5hkLzN5(`J%BH8&5lXhDM6olB8^{wf zV$<=wsaHcSII?)vbd@c;S!n?p9*v-s^tQBx+|pmsD)6J zD=zqfkP=&dWlP{Gziu^}4q{6o;+)ka*~qE-nms3_E*)+KW=P`WiGn$!4zhRzcqF0$ zB(+OmL@=+88sb*Zr^LS&pF?21-m6a>OojnO;UY_nD=84esZYD9RH9Pu4Y3|?Es#0G zEvl)dkbK`6(Mp6%@dw zUp|A@)y7m9KZn;UE=qoqs?Wn)?jiINsFxsl|BO5s60ZlFPp^Iokn|Z*Fjqt^wyxz4 z1@I>K7eOYi!0a!^GY=5iovRo}KjPt9Q^eU~3#jm&5U>SMK_R)TNaM39NISo%y~c^} z1<&Lm;#JHcdK%I}LSBqJCHhwUHaprLBt{qszx3h~$tdc|w}~Frd^UU|y++oDyiXqE zvg>9iW64GAg?ve)B{fdSXe&9WjUcxqcbgt9Un6EHoggGOW(Zp+h)HywigZj|rlOsV zb`Eu4a&#{BBO5XoMa z1{xeFh;uHCq*PT@*1Wo`=lBK+{v4%Sf(~*`L@VSjPC>%WTMHIy81YE6Dmm*MA;o;; z7D=>F)yG>nKilh2;vo`eDshe;PrtWBVuHADu5-LRsx8f0*GQ?M2hJ&}SLsLysN@H4 z^UK_SmqF#CkZkCpJiu9?s0-{GAn9T?1DoVk>IQR!O{*HSlKA9GRV<<6cRPs->}Ui% zBxY1&<|DYG4?-jht2Gf^6;_lQM>-bPQ(QSJw#Hx7)kGcv28U_04O)$2;jlLqvD)&B zt^ah4Fp83Eoyb}!f~%XC$Mr76J^NM&iMNl%M#?q=gV*!m zc}m3Cu6$`54!@kbv1{#SUZ|AL2#L-va}-Jx({AB0s4thGzpnEs3E)`E(6wg+69m2`YWfr`!)hsPK*JB(KH4l~$(8*e`H_yOlDS z#wC$Pxt2B{YH8*{D=*^@C$-^!^Uz8id=Cj3S_w-{IrwzW+@rnmSZ3{mZQAg7+ybl~ z==j$QG{ql%EgXD;Ih;0FsPkfbih{IemiiMieA}PaFJg?e{ko!MS6bZucKaOvnXY;= zE3|5>pg7rc*>;@PdC5Y8BnQb_kZ0rgp~uHe>nJi`*aSC`5sf@ZF?JZtE|R5 zz47~S;oI-F`?lZ698i6$EB{QR98GO*|L7=QdQO5noZ*wv5 zM@tZGzm6OBp=)T%8FS2fbDL)8|~ijo6${+$C0>Eca> zRQ8BZsdbXoup6TC$r2c%1*Kxh2Bb+x!`n)=c2ac8nh{q`iAQKgn*yFaJuYODevy2% zG0$bM_pTHy&_;$6h&WJ6E4wHQUom`zk;Ky~IeJ9vHQY&H!^7)ppddib3m>^16y40t z+Ve)R7Aa0$JoN_V`Be`yxlyMojS^UH$^({4qN6}DIB$Uwu&Z>|^QTe~1S)hBB5vHq z{vCQcjjz#`d$BRIHa5?|@8KTjd6QP{Br>L!s4l7Xp=yMRjGi8z!27AYD>)Yv4;r*n zKjn{;J;O%M5H>)BKfA919Py77umR?Vq+8Wv_dYU>5eHwZIh4Blklg@Y2^PW7`ng=8~Kvg6_^x z@i!4h6nq|^%E43p;vB6rE)AILpN2{4?O62q9t9Egs3zCC$s8u~QYcl6@DOh3R4=-PVwn-~dCVv;~c@)3_+d=+xG8O+DxOZ1>H}M<5gTN3 zz)VJ&l)l*ogo+#54OYoVV~GigEcHcSV4tsqCRA7mE%ZGItKJToe2>OZF-10x3h(B< z7v4KqdDi>pL!IsA7|BW2$7*nADM{=%Ws!r&m+o_65dju?VHf(SmXbP7neN`swRtbW z$uv%>5*Jk)3)fm39nJxDk?kvra}a!i*1pMM*uEfT&zWRdEw}J0@6VT=4eih=V zQeFZOd%gnL=k(O2L(!jS6cBjvO{fv>&Y7LuuHb)<@Va zErhCG&N%oJo@BY?L_obaZkPh&NN#H zqDv}wgurX*3vnZby3f4)QAAl-Jeu}89iy@?c{$t;t)wgG!tQZo&Z$}|DL{6LQM}t# zib$#4cK4@5;-osYH)#ukYa*lj8rDmE=ONhy(=@ol*=kx-yNl4$T62M{ly&SRHTp>}`*ulnUNF-_VH(}JNOZ)6?{#Cql#8jA0fW9Qu1Q%h4% zbcgxffWQ2T9w<9(f z2Qj0KqN+$eu+*tYkp>k)){8w`NS_Z^W1JPeI!r8;0a__CcgO-dh}I-N8hlBS zIARI1zS;}N_me`+gQMqZ4$g5UCAoSm_J0&j>9JKsK$jr|phF1tLx8k~cJQ6ma#*j2 zS@H*fY5ULA26$k)Z(D;&j-whUN3;qIFTMg}@51A->ebxy5xBgCj2NLnM$ij1*kC?-}^CwEzo)=XOyv;u7|XZ9___52FB)z&e`j%Crc zfz#TKGpb#HcDSG;IQte;B5Epo#B8Hh6O_w<^T*ngCh8F=@=6MN%T^x)a9d$m^&=I< z^bQa$I(@(+ndtsb+KSpH**-X18EANIj2&W9AE270I;I*DKXY`pu0iw1YE(04)T|n1 z{mrR4GNh^g@*OO1Nh=ak9}5rJ$y#`*-dZ=Cf*V>OF39( zY>RW$WX!(dBC!5ya`|KgA!DpXFSg**L!s>C)_^iNSh8|NpCnEg)>WaO=;uH)s{SlH zA>7%+(9W~2StDz!CpI7|A_bP7T0-mV>!+&GX%L~S=OV8fT5H2*=Q3>c+z^ng!Fd(Z zzGMgYh)E+OkpL%tDx}lWu5)l{!kuCB7nEd6@(&4Yjx9Is=GDk0raatFfX(j5=tjb= z6cn=9R2iMML>-uN7r7NSf3BuXLe37rd5L?3DamWh!Sy)=wFM&H9EAA4Iugp*m0Tj$ z869GrO0`tGs;N)tO_8!2b4ORcg*I+%8+mX0!1gU#C#cc8@+~A38J$&NK`R&&^m&(r z!KgVr4&0nAos85!O$4;j)f{WhNK)@4+pe-_Nhcm#C3k$vR0d6(c1x;BQQ)a-N%%D~ z)Qo2{enAx{AG;CoEy&lWNYH*H2S}&!kJ5))@(8SgXO$g2gQOvdED{u^7Q8WF&1a8^KeGS}!cJ|akp&gq5dt-M>I~aDnAu1c}&>{1z zdgTM0Nw4Qz^7<%exc3=nK7j5QI1>+UVHB2vrybjfp_;N-KSXiC1c{;tN{;!=11_fsh%uYyTPqPCcb2kK%%y)x&>V0G!aT$jvE0Rq-iSeCmCYhw)(%8ooR{ zUHE0A9{iuwD^zlMO%0$j=8QoEeeZ;G!oFohRS?+Jh#A6USVWKj5h zPQl)D!5)j{NbIvvrDpc{PYfLH1r7>R12t=j8!Dd#^H0-n&z*3q)^M<_h{_@h5hbo? zGa{H3Yx#%C^UWuE*kq23LE_G7VN{%cf0VQqGTX7Xc`kF)(0qMQDNq+h zd2LH+xpFwzgZ?fZZg540v-7(2$OZ zIYjy0dzO#ZN)mHgwW;hXBS1P>t?twHZbf3ePihH{X8bB;2}ZcoS6|CQV`*Psgr7rA zi25=Yf}fe!mKdTr8fs+$8cNi-w;LG4q@ytEqGgNtgueG;38xyj{zhn`NoOk6M6qDN z-g@u+Hxn@98Z0pksVa=7`JMLYLnr3BLe8@bBBfEjL_0Vr45WDvbgO95xJolm|@FG6TxhzCM8Wh!YRzg7IvmI8AN3A$FGQ_TcupS`Y1b^(34ha zOWQ*GaK7~n46D-9k|w5@`m3a)?g5hMYXZt9S&U6Ma|O2&8IBQg`fhtJN{mtVD0o>k zt4yQoUPZrQ^yx5X#f6FJCeDa4-FsLia*^Bgsk%-_*4aTaKB`Yl1M2l=6l;K6#BB3yISboG+pui^4d z7HLJIQ%S~Di@cn&k6S6Px|2CsB(=BDEItDXpW@Krf)jzzhE_z;L8STJxb!GN9RWjk z68{!KryMU2qgY0GRR4$bS&{&;stF2S$LAHzD1{e8g6dNBD(ewB{sTB*I)yOVcKDK5?NGFW2}AqcwCo5iP51s@_VRVplpPE3PpCQdJu6t__9ipwYHf zI?{>stBms{M1CyDk%^=cIGwRmGs;5K^ajyRrlV;voqWDgYC9Qy2P6aP>^@&i52sQj zWOB-i-<^779_hiLh@(*|?f#OykrF%9hWV0rA_e8i=q)F$oc5aKSS)0)PZ}te)DA=1 z!|@er(c0$ssl#ZOSM6TX_F48{5zDXu3py&8?BHobpf;pXu~Emi;Hjw5H~_)d54D|u z@Bwsf3qX=Nmru#Sfz8$%J}jRlb7%yv&1(Jbh4P}-ac_cyr`BB#u83&sQXJrcPM5@@ zU8NsX`m>(dBszMJ=hPeWAxcImD+0cn@Y(V-b#lKpE8FClG8^z0vtEaUf>uxP)S(iM zMH_kY73zUc3_v0YjPyX{GYb4O3w(V>0gh5$iOB%C1>P#Bh)$+Ooq9Q$yc`v`_q*$T z)rMi#0us8C>!)eENFOS)vFEL5Eizh+yfD;8(>j&|A2u(4+|ZnYM}$Zpebnst2n44% zF(?ZTu4E|-QnYAe5I^uiS%eEng~eq896tDyTY_ECP7*&J&$M;>Nd~2;Ifv)OZ&t(J zR!eNLHsZr_p7QiAds%vf8uVxF5NmYV98%MMltsX2dtAskb1Qav%HgRk9Y*CpXtzic z5S6~L5B&8WFe$UB$1U}2Cnl*7aNkS71dDRbx_Z`3)>%uERS>a<2cPo?2v`TPPf?#( z2NIg(<4Ji|lfj-{a<5oP{)d-ebw@e!F>0`IUR=%`rOvZr>@n7klFhP@=yck8FbNI~ zhL$MV)u%}@MQ$=@lIDQNt8t(nuDKvSEi3%C<4vK{R(M>XJ5-6$i3N~OlIiN~Ns z-Z(IswE%ZyPOTb7%9K;6CmY$*j;2{vJz#(dXTOKbpBa0Sc42s(YW2BsuM(`s%H{5o z0?Jd5!pxj{N9Ac-YL&k9RhXtcg%71C&rzd%1dd+0nC?VTV)@8i*GsZ_9KBcu#rXY_ z&Ji16JLyPd_}WZpQn_%9IXo8`o#^yH`VbcFoMWvL)evkz&!3FE;YX_tiHg;M2XJV3 zc~csSk5k#9F3D{n^AGqgL?#Q}*~^|;zB%zqj})AHD5CAUQ>8hI3rwA1J!;d!iHdr* z35>UtQq75|J(*e!cB4D&j=j%OpOiG8gIA0&A@CYb8x=S zFkvhBh{}{571qQj!)z0`5u1}v>}jV!6$XdCa!^L?Yv8t&i#j2E?2*$fBxV=1k0;CD97vfok1n$KDV z(jE)iIm(GMPq04`Hnke21Ch0BzQr|L*Il@=nBU+T%mx3DeagB=|75s8wZa{2N20H5WlV9X)P#x zjh3Yy`T=~a+N`6VCVo+LYL41R`p&6`v7!eYb7hulx91dcSTak3R*qW4njP_;M8_!; z)FZ6s4pC%m_N^VyOedZ3=CkPF5fm>ifrRwxe13p<%QTB49#BZ>z;XD=JlkU`A%sU_ ziw(j!8B(ouAUNLCHe+R%NOYraw+X>e_+EgJa$Jgl8HCIMp1DIq7nrEwz;#R#*vfO-PiKI#PCAv5{YS|0*h z@_hAsLJ}H4ygJH^yi5H+vW1LLA|5K{K>-S$$2Rg8@+biH2o)I;95m)b9FJxILSyFM zAhX5}Y#~n0{?Q_s(J^NKo(5?4k0vSDhdU^ud`drh{s{WHPV8XXK+wLL@LUT0EXhEG zHe=ADW9W?{sK?ej@{!gf$wDiWti&&)TNR3&1|_Es{aB@@kgaA(LhhWRgLPTUgv+UP z_JnpteL^(~fDEAINkaKj3gvQfFwTRW>O{8 zC{N6vxz!AtGgpQVfiJs9viLiwPYBB}0+n73uphnZ@_qneEWSBRLL!iO-v(=vS_Rdd z#YSm|=z#Y*W795dwExjZrBNx0)EF)&cII`W1<{1K*1rlalZ7y&r<}8%{+rN^7>^z( zcAF6|s08^qHZ>iSqJ}r~J{iGH#$!=UT`6_;5aC6f6K)L-k3j30YIQzb3r&X;g(Lh{ zcI7jkn2*t^ZKpJfz-j#^Vd`fs3ytbhTuEM9eOI`Yw91xk5-nJuYmCyo+JXs+CtUeF zI4GVKxeMxK4Gt5Ib*8)HT;w3EGLx7@`Q8th0(A8p8@a1i&@(-U4I?*Bq2@&9EWXB1 zCRa}Ki>##jxV<5VtT@Lq+ zBd6Qm#)vajRnbU2Z7)l#Z*#rF$glr3yf(zKd;Sk1e zWQ^}@P*A}4jp7h1wNiknLec2HJQfouVhn zowS=mv2EdDQY7i|sgFpLM~Y90hU^&1EL-J={47mIN^C+iim0roQ=?TMAry|oG_xxZ zX47L0-FMI|BPvzQ`Vz87iV>76%ui^k`);9DoamVrWZfLThaO5UvR7{&{!wCq5< zag;W!@@S{!rRhZ?I;F`Cy+=6c;ECx}iQ>13Oe;8IArL?&%^TG8pDJI9>j?7f(EzQw z%Q7g#VXGMZ&J7F*=|tk*^*C--p98{w{rb03g2Olx!cu4d$G=1oZU`Mlrj!n$d_RPY%fh-lY%~Gt#A?65)@}S0uqB$FJUy9g^5=NR(&~H6fI++l zPB%oAkNN}|UkqzHJw`iFCfqZrgB0`_aWPYPyvzn=aKX5BTKfigl*dWyVqoyPPGyc; zz<1$$2rjhB{Q<*3VInDYDsn4zi#n_a3y4RLs#3JD7J>&696Ay->a*51Y#KthZ#hbx zQujD-R1)z7)lkj1BvmG5)4vp+83l03wLzpfGu~NA*HpW=6+w&cW#Iq~cj#nlr4J+{ zh`N_y-yRliXM<0aZ`3<<=Xw*xg5scdp}3r3*cSGcuR($dA8@{vE1hsCJWiHP9diWV zWS;UQl(Rpz3#})jAyjG)hnJ4k{q_ScwZkzLjQ&^u&fvUg;{Osx3@D#RBB)j8d#SY- z8x47BrPy}&w1LqHttpF{5RwF?-a&M(l=d!x+jqdBMD=oCY9%ycP`DTkWzAcPS0u+d z31p(+s&%k~;og#XWvM(KhBH2Y7$a%v(j zz|$m^R!))eJ~e@~gOW2w0Exm8q;xtLF-n^Vb(oS6L7Q!9g`;l4sMAh`=n-9zgE7Wx z?u#rSwx9G8ZAtX3iKLADnY$F~b#fL<dzItM_MWmQ87XB)Z4v<`)2;7l;&%lh7sV||o2lb5 zUnin9cA0%~f$epK3-drH30jzv(KbqC3Anw9%WjTalJrq7!_C(8cbs9%_dYe5uaH*>-)-1xls$b1r8JWNxGn_IxDk2Jg{tntb2&mo zaFnq|tDRzlaVcIhpQgPd;{+yCz^rbd-$gHs)VIeXa9j|Ei{W|Z0+{K^r_40La#8R~ zpbg!g1xK!pER$ZplxE#Cr#^5H=@b{S3W;A)c00ckNLk~nYDMTcm^S>#6(I>$QRkJ>pIai%tPA$E5Hf3n4oh#jqq8F-qRL?>9pswW`N1&>rAzbM`#X+2s5Bi{vl zs1@~gsm}lhHeXF4zrAYc^toJ<8YWWJGq2 z4Cq^WH(TgzQ%5)2UbsL|=|&Q@TZr8EEoY$@t@t zp`>v*)2<3?D`U^G%{aGO+Cvg*+pk=-=75fw1x-}IgDQ`YW&s~tQWXQPSFvc5*=W3h$%=HHLY2$2(_fD5korgK>d;<>7ED2 zmHz@bbP9%1dp{}vkcHh%g1{+J!>e_Sbd!OGed9EzXvZCqsH7UozP$(Jj$F?in>To9 zIe1PxT=5@vPs4}kI+Y%lg#Vxr*AE{%a3;OfpULGzzFjvRNymaF)jr9k5hvu!UbH+d zxY8TDdM?zs#+|pkNCKRxOafXwW8wsS5i}20`jj;dAKY#KnU53XfX|6H=oFd*w1Stc zIBFx5Izym$WN~N6k)b|t$Q<#kz(A)YWiP_NSYzs2Fo#-~sErzQ_&icSQH|zT;Ash; z>SR<(s4jbWH2Bf2LiUj6|IKK6#@w!moEQg$)zz+=H+bYL65yG%{+sv^k&EQ3CsQ(xJ2lQjC!SJ}G1MhQ@_%@tYA~BXBtN5>VuW48 zsSl74Cb04N7xEL5@CrW09568yLUC+x;PM=bzc+_R zq|)^TDt$|`oL(cf#Kj(2k)5jdIG|OIcNVR;L>!B2M&l=a5$EJ1y|1FW<*>n+&%GlC zS2?sEj8ZoRZ~Rmg<0*T}o~d$z)69R=x2O8r32lz>CY`O6Y0)yL2=O|Jxo{>Z((^CA z=hK@CxfT@M?VkxDiA!1|^Z+l(25JN+*_QIVWX#pKLmChBjC$J1Sml{!F?tiRZWBF9 zxQ^>WE|5a4m?zJr8m^vW^bkqi;V-hq$;R`xjV5D0$slZJQ@cO5x|?#_5o$4*T32Y@ zI;W%3HB9=EsbHr}}gGQJ=$b<=Po_1kl958AJ zFa=&FHu0Q{=rlT?)y9JZTQWGg7!Vd;gzzfG7b*&)T_<%s%|fB8X2OUQg0xbB)QAp* z->JB(R8sAfwE2Y@LM#O%9!MlvNv2fOd`b)gf=kT=6(EgY{p^-`CmbRc|b4lsZ+g_q5mxTVNz(G1A9}B`hD}6dz#B2D_xr&FZ$B|V2 z=iqVUIH2XojH0s+^)O7|&sWJ1ke%S3l;BoNI;75P8kGNnM;(hQz@a2Y97{p=eT(Bf z1x0Dn51Q0K=_-{%reddHRi)ZfKqZfK6Y~zC4C-r8X6)y~YGV3{!SeldG^Ji;&`rmy zZiL{YME9D{WB9a}ku)zvI>!eW5Ps@83aZ=r-DPT6UvTJ1KK@10L!62YEA?DQcxn-( ztcO?g!9^S_z5JLpI0R3vRO{ZMz|l_c~i4`6`sm2nQbx4Blx(+Ilh)_D(tD|BQ_|J#HQY{@l{X1icq;*7@3Ns z=83Q@qx>P6Buh{q#6w$XvZ+u$i+weSxC`)r?XSR}$!~rnW3g1BgC~PuK+LPB!-$Ir z4o{gB9<{?!iJ%UF3!BHdc?9&0(Ow8gs3SkmrrP$Fw1V_v$@cQbL5Qy&Op7o{zR|pc z$4Q0VBcxG)sVb5Y+7*E>6RMfQH`Lv6DoCnAMWU<+AZ9a9xG#h=Dp2Ff>JXvJt-PY9 zn#oa+-Ng+FOudGXan(5gF9O7wT8N@kq_}EJfD#~36Yl6~2CW@s()&O`8A44m&^^k3 zJ4cA2P~=31wzUbNb<#v6Kb^7l+D}Q=m%JAx&s`7p%BCm@vht*II2CCO!rVdCz@!%- z*1OU^Pz)j*s#gN?0GB1D*1fBLkx?g`fh9|W%N25|eoa$JcKH_Sk1VS03aULs6S5j1 z0qx&Xm%biLMDX!>^2U&{=Y^JOF<}CnQdHzNNo^^=a`*CQ7L}qD!6lU!s$r+_bVn>Z z!lo(<@IYrI>Tm&X5I|0=8GgBICw;BD1&kI#L!3gW$`YnQ{HUWq5zIFZAFHlU(UCqN zLQ)z>8;|Y}h#p~g%0wvFh4;k2*7V*{^a$aZX}|!gXC4GQyutun4sAlj8uS!y?0q!y z&x6Zl?ul=&fg?6i?~61ey%H^s7dSOGQORdU5uUAEl!F!n`V;sx8Bq-m!RRJl6Jvq zL@p^5H@X$41}lbDM5Vy7Slv^h(-rY)@-N&dn)d;Xc|Bjh9St3ZBcj#L^x{t1vj`nl zAW;|02s6U2_~2Bt;PX)N=UfV zpx7Jgk$d5p3*xbSBAa0>B=gb&)$ z%1s@RgYzYO5K&kF7mRx|Jw-Z#M4e`3FoSewhZ37~(J=kQDnar9R9%~|KVt68<8qh%14Z9jf!_a@%6Pf(V zy>qXJFS(9y3#!67#kebS#fr~2B1D6J#~P3vB6`4mhIu&qoauBP{@ zRy=hUFJzeghU(#d>rU?2?rjEbd4z z3lw)yY(!4WhbKRer@=pkgkikGYTBs6qhvrmGAx0t?i19$$kY@Sa50pX(6uWSuopGG zl^QQzGP(TaPpP&oEf>URHP7db8>H^smeA=bqyR$4zX$&g`->O69*lS$ZBLE{v8!>i zm2)BtFRr-9g1wU4zh7W+#|ObgP?n+?dfnhe-GP}5^a}8H3nqCb0``We3+P6n5MyVX zfY6-npBov$&f|X(%B_*kSi$A;5LOzLNO%@ve-!~L!<3@e z+04Kumdis{sd=D@YW#aHn0#8Xf7C%9!ES|Q)U2v=qktRhu}H^P)vrc&kmp`bRREDn zp%BrMuio4niJ!U}yqLPdg~In;)bI}wxXKutrE8gG$H^C^iI_b&u>4=x%b12D?YTu zwP-qL3tL2{7^4J+0B`hsev_^3=OMIM?(=gtD^1zfmyZ;0ee#+xO8U9lNEu1H9D+By z!y|~6iWR}yQ^g?{zkPIkT@+F6iNHNrRsS~$C>9s-B!NMVn#Sy!RGClZs|4I1;BfI# zDKJ0I_T;p1ZXgk_a9CvazEmcwG}H@=-(KMMY@DG!b%6vi2|%rC^Ze-nS6U8P9Wb>o z26K5Uy6;^4^?&-EPR0&$5m*5#(IBY!HxlomnpXpbq655vD_x(49A>dc2!kt17=v?x zyZO*1{AHE1vE8Lfkjv`~gwmE3Mnany_(lYsT(ucoAd)sE)gg1J@b-h-#0X__7J3pjoW0RMpM zB~u0nJ>U0T-hjNaZ9aZiE^(K5U*zg=H}EBvbCnvw2_}C4wu!FY4RbY)jU*bmT&|ou zymc1TpH^OizouAo6#>jD(dW~^|yX}WZMd4i$(UxH0gy8LR8+csQj5fgmE(#Kh?p(@244DuF+KJQ>nH zly^$QR&ij>tdvdQ1My*~IPqVxiGPkaM5)c&#w6SYib4OVjJrnI<{e5du>{M_)diIY zz2RnY)~yHWcZ%0zFLj|n7r}YP}Xhc zHr@%xB7O!q3QYYvSGxiOlCaE~m?=V*(9ioii zvL;bJ<_)*6&D)QVhjcQD6wn^mHinxtZH~ozV~-h5Q?0QjM*F5qs5nyNK>pYdd3&{M z%u{%2!ou}Bi@S2>sKHW$Kv?p-!;^3Gx3vOzP0Sr#J~BwTsBsQ@No!1a8Jp%Gk!4lEXit%y4-fQVdcn30_o#ZJD*@lmTHx*OE3 zB908uWkbmbL=e^WTsn1c(I)>~8#Ad^&|%O2BTjvCpsPD_5vQxgTAyb%^y6)DTN@5} ze&hz1Wp9LbE0u~5E5^a9b`?;a#jk?N$~1-0!48 zLL9Sa{xHV;L%N?tGM4CyTj!5ZHBhR;2hK>vX=L-r=+zu&T;ei<&-@kCyC&_C*`{iH z_3kKRJ_*4Z02USEEP7d~o8bWE8wpEv#4~#i_{fb{!!|xAfBmjV1pK!=Ga(dKb4Ap;#IIMnZ49dF}xPYl-Rh~QrZ9|U=~gY9rvSO=oGWfsI* z5x$2&3wLEeC~%UXxDhGtsH4+1k1+M&ja)*TH}Z@RWy$4``sd$Vom(VRZvT)(s6VW~ z#Y4IM^AN|X_!gC zci0zDd#kLY=5eJcKcXtWRl89UJR~CX@-f#pw=~iNCgJyhv58#y5NJC7gdzZu?ky`F z-Akp^M8>``2MnazR0xy`eXxAu$I193_Ij+oVXeo-(?=&#BStf9RC%QrDT`Fm^lE`O ziX1@BjlIHs6E@&p#&r%3W9g6$K)cF>Ot8o6rrqVCH)wkzXGZ$};1$Gsf5XQR7 zJzL-m?i9{EOqcn+C6G6lw%`pvW=xIKGdh6~nKy*W;Eu=%-=5m4M;?ro-v}ZNn_jbF zo)^rOf~c8b{1uvl+CBxD2NjyCYE~RR$`!m`F$(GkXBwAd{Xm&6sX5hcMM-7!VXye; z^h#6sgBKjx>&d8NRI>shJjKl`EC{^i(wg+miSzWE^dI<*zCuIDz#ND+XBk`)N-?{5pG3@mv*ljZ3(mZ1ZUF z`s!r3#*_}JdV|qthUPYs-dC6lq8AIlLOIrmwWPZuAJQN|qw^FURa*>J^ZquiTBJLfAQUJ`v|P{0y;X4V0{_<*)CLxP$=9TiW(6o&-U3Yyn^b zWXV;>;)$Gz+I+sgY8j_khKerPx<*sG{4se55Cu&lK%Z+2*R#39dq?M@cxnpEwU=!1 zbxinl_ze0_b-`3C;2i-<#)q$Y4mXuNTE09V?g`FwYk z4J90_v=n~dEj>fK7U_)ug(I@?uu0L|gDD75(7Ze=`U8a<#doW{HqjzuNOX-bjbw ztb;+V7RR_8g(0$l^!df%B_VbIs|f~fO)aG?$#^-*QJ%SjKMEPuKerK0Y~@~X z@NiEG>$JQ)?h(GoJdw?Xa_*p17fhSKEi#B26rmPqa!eG8;SqS&9D#~NvAKjV%i-Gb z4~YnFkzf(a&kbK~d4=$WTdUPvL=`KO7}hloF8?lX*{P9!!sN5PTO*h60nlBx2+y$5 zD}$uat1A~@zx>aQSy(YtHNcM?%%e`acZbBY*n7SuDlG;m6i{Al!Uh=ox*OIEe_nJ{ zNdtc7hf#MC?zVnd`SsxGa1IFsZvNqJs;@4LP!R1!b!VH#Y=#GT-T3I&=SQpu&an_j zgmKAHk+zHnS3CHl1yHqQqAm$yP%4(&koqd>4LV@;DlWLOzq`twMr+*I%0 zg9A{6v(6Ae3g39Q`MqID+DfwujZgQs7qcRG6hdnT5;p8QEw@|93jf#zcz;7EE05jG zrfl>H5eqpkW~0?i+RN>$FBw$;t0YtEFK<%m+Ojb0_2jEMg-d!Lf%C9yM_!l&F-a^&Urw_Dq)(cEYNE{VVvO;>WoizF06-&J=fmH$n;4=Q`b%{?io z(&Q(#I|6B8@7bW&!AO4KOj8RWuwR}{Weu<}xK-3Y){F?;6*`b~1aT@JmA%rL%+b65vnI6o6EYA?h%7Tr z>1!JdVb+)U6jCHI76#EOWDNOAD=1~HB@i^z;!@dC5;085$x}zAsoK){9Lu8iu-f`t1c+b#^Q>Dt25T(K&@FvuGwy@IkOQ=Efn$Y2>r=vh8jPm!-l zPZEy!?bGkw;8nX&0wae&zWkLN1pZ3KjqsHaVJ*K`O?PoQL4#4MUt*3dZClY$`v$l6 z?`09KlhwAOnr+5&eMLlTT_N=cf;%GPTf+TQ2_;S0=I>8E!B-{pQwFIDw;3Gn-e>7c zQYw_`Dgja{N?bJltg2B}FGa8Nps2|%Is>hGS3C7z9#^=~LG{oS#ET^>NH!2MHNPBJ z8iA%LdrN&*AIKAI>W!pCrMBA~9_|*tPDXBzQV1nh>Hw5x7eOkwiX=LRiVX1A#umCRVATa$whC zpTZYb1H1vlWB7j*=9ilz*GqQ0%A0())!**GAF8Q+aa+;Ek3?ZqC8r>ji%9WbDHH*Y z0>(>K4K|_^4iA5j_@q+T-d8zw0q{HoDU)ucP;$E{WC7_i7Cmlx6O!2g;c>GzV zsVlG}&;f;h?c-_RABGSci4nnQ5GyTIYCm>Lu(uRQ(RO(JEC+ev0s(p8l`X~}Y*-a^E8^h(uY>A3u%!!7x5f?sy^4<1E|w;~ z<%5F*!o4VKg(APgYTDQK%om0AYAVAIt8(=fKhc3PJa)OSdzy9;$cpH&+O*yxk!$Lb zq*kr)sfe7w=L)bD&Z?k;TSXxd2X4tRQDQ0J2YQ9CLvYv0EuoYn0=aRws)qH-!GygR zumAJ=mn!# z*ddbvm;n4O4-?}#DQ#8L!&*kbN-ao}!q-rY!fo|?tjUhR=ZHmtr!tN2N(ncBdJ9ko zU{?he@1!_czb2Yx8>r$-kRYU7Uw+DUOdFMSoasU@Gd-OvdV$HOCs z0dXZelz5OeWCs1spRtvcEaq**RWp4;Zw*hF=SH=MFSA}0k$p|~2WZB>1P^odcLni+gbB{P>( z5W9lh1PM*D9xd9!uDVM|uFYE8%{Vb-3!F1Nsbq zgrC+Pqz0A% z3!;d4y~kzPd%?Bo#~=~A{ArU%aNYGq0Jq}9@?Vx;l)nxj8CQss))i^|@pD8REYb3C z&x%8&kysmvq{?}%GJ;SfA5pV6C(!e6wx$Dreao7eWE5WkQCcZI{v)P!T|PM;4DNn4NY=W=YXg4s;)slSZ`D>+ z(17*wN$C`}y!urNE6|HU_Ai*Zd)Ah!^(F3)+M%B!Lk+ z3B)y+&6NtM5kkM30|7qfnjrpMo6u`y+T_`1DYa2Lt`eN6xAkOba1i}GC4{vWgD!vC zyg*WIG-}|s!W~Jsl?>St;JZuj6XnsB>kbTRRJ1YYyN`!F-p`}88Ql3!`%k$8hx9$P z-{7PCP*&ho;c7DY`b+M>pd$P?SBO6d#Dy;AWwIq!WznO1>Y>SD6;K%9Rw7D;pX2v!;$*rPt) zzQ0F}h(qAK1F~X6A{Rz)Wt|H=DU6kLBBUg|UbsJ!M0})@&vLrf>09*HgKi~LgZ}~| zyjS)JT&wt+8#~8z?&?x1Ts;mM15p+vL4ga<=e2x;!m-~TSSAqCH3z>E+~o|`rz__L zM-~q8TB&C)bUwd909SH@+uRCMIgu{ZLoF*>zCBGeHC_w%lgNR7`WJH4^=Yc757Dj> zUF&zMCVSF{2s@D?QC2Sonex*X(M=pgR+C-F00F6Dt}T@dE|9T?)hq#|>;+d7`~mPY zSgF`x74z~A2+C>Vq_ya_fwRNyk(q2W_Z%s_dakBzcv;3faHk>chPyqX+J81}2C1;u zIu(H945O*Jaf|xg6Y>r$z77koQ~cC?-(Jma<){>@8dUt*!lS-1 z4dFknXHi`-@AISyh(Eq%+xIEZyiP?K%Tl5dST`8pDba! zk;=!dg&je~)J|K`AL$Gtg`a51y>n%)81>M8_H*n%*A5R&ap4<*+!3X{{=nvg+fhb; zN*;CL;)c03jl%a2d%8*-@4wwuK%d_eWg~Nw`TIK}=XIslysDQKPzMHSUu~<#ZKz6x z0Q(F&6G#cjjq;Iz0|Pj!*$0Icx&dXI43giVT!1kppHhQxiwXuGXN33%JRxmWy{cKY zAy626c9#qJfvTr}9>C@`s;Q;4FnwYwFH>b+f;zw&aGvVsWjF~^vHCDXyUQr;a=NOn z*(sJ|7ab4kzy0g~__u%k$KU_)&;R@%|MvI4{ze45#6bW4kAMF4w~f^tx zW<6T929?J}C|-;0UU0go($>(sqJndJ!?%-N;RXvl58&wjrysU06JZ)?Y{MZ*5UK>M zt6P@4jB8Z`C=Mkr^e*$&XslLXKQf7BV^$iUi=iF>DSqMf3SH@sHZ!6}h^aOP$23ir_!O;4XU3vdp)u10lOrJU26ED8} z&I4*{n!WeTJSB?ntXcrGMb-NH$~!PvsEn7duvUvuhOFFWt>OJu1vc5^^=0wma# z^d9_~t$5a?uRoq9hp%g^4h(AEs2uIPwFisCjaUAeNzqGO4z2?r;yRYFnuq)aGVp1c zo0S>8$4C?Q;gs}sAoUJXN8!d|7TQ>b*4GZB9NPwgAEU)UcrB{Fj zqG4;BZKXb!zAC0mlHa70Yz2MxDk?9D;O3j#_%GGZLzb58ZcT|^+!q>k3$8$TR~uSx zTE590i4zjFH7EjyW$|9H_cbL05HWo@y|N9sfuc_~MK1I!?dPB!XsY4=>Z>yc6jV<2 z!GN44&-y}<1mlRggOBQn#&i~uWt|Lg4z%XgM0_rcOgR?E^I4hv6ev!$>;*%O;&8lR z>vliSo@966&2a$FQ9}(u#=TguQfr$f?h}Bn6|aVi@d|g>$6CX(e~NPlmKYt<)*a8r z`=&Yw&~{#ZQ{Ufzy88_}FrvuyEhDcy^(I3v$+ zd4X3}{S^-xi;l~<5UH?`h?R*SSpBPg|Cl`*kj*oGtO2Tnm3H7}0BrGHXrAVeD9oU; zF=8~55CT{`MNz5U169+j!f6GmMW$Mw!L-34V%rN*N)p8+^Wk{Z$q2HEN6_$G0K*-Y zFJHEY5;8nfr@w*VUBP^b_Fs#psis5w-O)2m&irjv9L#lhG$# z8=dLW!h2t*lQOFb2a8S$qA;NPR`6fQ@M}ypeg}JgRzCzr5n1ZQBv()`oxH5tsP(G$ zuY=L(`0e5B$yNLIDmKF%1M-fi1){2MZ|@0z{`!zJ6k{uWa@U)$h!rpL1>HhP|A&V9 zGs=awuUE~&FG2;pf>8$KvdA-0)mYtIxxJqnYFEHJ+@2ye?tbLL9{u1<1fcSXqp`lc z-8a)_?^OlWfxQAMHHGt0+bRB-K2@njI+Ll1(nH1{fv_OaI@L-sOy4Vp53EqlfhAZX zyd~+fP^mBgqz#P~bX5?>EkfRbK~5$N^7jwZPR9$Tp(aVO?FM|)QdO-vJ|Ly=qRT2? zn?BlC2)K%_I$Uo8)k>AthawkV<6CRK9k7;O92P{P&EW$rwOk=qpzv-ahR9VeW|>6@ zJVDMnS0AOe9xPNaa%fNfk5-IzZA5ixGfff_Sj1Yq)#(b!ABuOjQJ`ghzn!dX{ZHX) zUtmGoh*1&i>eE~2^Y4DA&t;U@UT$#1ApN?C6xe*QGHi1FRkYgtk%9Oj1~5xn8^m`x zY}XAoJ=lA>)LN3Y_j2<0_oAZez#Wt4+RyKyLE&y!_eB~MB3tGbJm6NuYpzs%%MR?} zUANhLXqP(K&&T)e(P(H?RQ6=^4=ESL0c>)zp9^Q*%C3#sScfab<@5Wi;JJN&cipo8 z;kQ=n73j^5eqx%}pU^BcUWsvkW^PZT??0R0HD@B?9WGB>u%G$c(+Zj5gu6Wf-%(FJ zc(b_Sp*KsFtxfb*)w=$(CY!-{6T@K;Nn?WJzd9YiU*JNDf^v1&kzpy|`l>2%MZpCy zfF8%4>c}4&gj9kHz5n3!P=NDovOm;p-JIbSNL;wBe=KJho1y^U76; zmf3Q+?Ifskk>q`9Mz|&R+BZmEX{W2<&-5eU{+pH9X3(~n_I2=b4f4GM_CZd)kfrzu z`~NeD{iPGR{Rp@G?I@c?OsR6QsDo{J{G)C4tF)s@NTQK2WAz?s*djx31pPPQkZR}E zwRh@sMMGqogh@ZYJx*5wj82r*=iKqIU-e^_@BUrI*LUA(#%jO8vIP%de9;9xR-l~P zuMH;cHbtigd)88NxAY5p%OseMG5k%i+8pi(`a*x#s&-(r`l_17kV}3fWA=66UQIdc?Rlgp2D7Nt27GJeFEVRK-tGc7EdT?mr{3BvoWNF7x zrwu|yr`p$QtU`4mlJ+1=wftd?PM~T=I;0aWg7!@_hE*+mNGSlfT1AZ`Ne3Y+eKC9} z2~ZJK%qHgevFz#vYshb_4G**&TZC~Mi)m)9fpmltnweV8TB+}Fht#>+?{I4me*ll` zY~R``UP>EY5!K7j_nO*2XN_wR74rgX;Q*at=ZUku&hHM4QOZm1Y_H`$8l1CmwbPSM zbkcv?5kg*GbgN8Ouk!iT(YL&M$kbfdhf!f2kQ)$6Rb6J`Lb1?RoMflKwAP!$N#wPy z50xp;B%!EzQ)ePH>6OW5s-(n%55(2__3;&H%mdI(Qe};27`IK7iprxG8z1hKY8n65 zYF0rH)5>_8+eoOzH>c)CAqHo*7mK9JMM}TjB9#z^j8d_tKXQ%4cXgiJA_x&m)Dxv6 zMEtO-;9Y6>{2fx+7eU>)YI|B8F{1&yAjlL7Db>DGG^<77-(_Lf$n@aQ@FL&EbZ2ly zH2q=`cA$lX@{e6$^@lqOs{?=NhPJBN$mr|Or!Ay`5$(XEM)VsgeX?HLRwo@cvs@jl zUFQSuTFxHqyqxK+1JOM}Uk>qgtr)t^ZQa_fS8_~yCUi@sSDA%@L*lh;MDiD_wK2@E zFu4Dnu*9G|@vEr`qjnZ6+TjYBzSw?sTgU8|(3JcO;Apm~Vg;Fop)(sx9BQB%AUk&N zQ8y*YxcUW%>H;-@Ms+N$Mxz6tv!x5S;lnR{lEh2~Z7*zMP<{^V-kZVtIhTlrSix_Y zLTnwAxk${C`Kom7a$rVM)1y-Bt#HDwBLdn=l(~GGXI(Fct$N1WJZ=od-qEVB@8{>2d*oZd4xV@6V%E1u4g=6VsvEUKWv^E} z55!i?{bSh9&NI3Wuf&`rvy6+->*CNsR9|n3UU>YOKwM6|s}tKdndq<2`9wU#ifqJn zSM!5nuEY$XZ4JMwto*|JuRS^SxBM@E>aTrU)PqR_{66sLob4wbb{ER}`!z!2|3APe zz1Q*_AC`lI?ZL=HG(VTR+HfHg+Me?C5%LZ3!kHYI(_aW)au9gLJK(EUyUUdx+0iTHTyzKB> zfU`C8lM+1j6_Unq-Y0Nie4VPRccl z1Hs~lf?4^jOD4Nh;Rr9tUfMQG&t^!HZA`ZykB&B2EF2yjF-#4Cr;^LSzgIXTMNOKR zZtMaQUgJ9ksZ{qmGc>9UP#NS-F;R_~5y5;|x%K)0piz><_SW$hEK)T?kg1?+j#kK; zVV~U}JzBNghrAlu3CMI3%$mg4esbH??$eW_>8iTVv#pQ>zDxiis-R-K4%P){_b0YP z^8F1UvgHh3xGffA(WX%?n59)<5c!%JtxB#6tj9}tR>c^K9yOSzRCSRl{X$)T=_sq# zfs&EW)g=g8Nx9rDLH!H&)LnHv*0Ocb4|H*(311M(*FRJT7PDl;vvlq$^4~3ZeW2%G z@5*)$elj~i*Trk^rOg>>6*NB#VgxXb4Xyh*i;TLEh+rd?W}@1RJ^gxDy>?(ncUW)1 zo=YwEh37APy=wnEF!*{yz@kMqhIdhKBz$&klQH|+(A7b&}BBw~ORNbcxmY}NHOOepfYNEK|kAFJ_ zAmD&U%3AA7Tby`89-_D!TkwKRGO35ahWZ~x;kC6E)H(B20gLe7a435%g`&sVFlEo& zy{Z9zHwD}jU!hi)GTiV`o#b_SySlc6Y(`VwcZ6zJd$*bUX-J6TKvYy1$mXo-?CGUX zs4KSh$@A6K^r!DK^@a)9F(iB9-Qn(Z%KOH`?WytoH`Ba6<|Tc9zPl!+1Am%F*%*VL z?%}>dZ*%vm^6kK0ErV&62{yvH!iP!|?3ms*Pxqhhn#s>ODM)sklWjck4T!%q{9Gsm zS1KH|3JJ(-J^6RG7T0(SnqOSf+JgcD5ac__e8AV86bT)4a#xC1sUd#!Ub4I8_K#Wd zg-47T#`4zB2{5(jP!FjEUoW!sNrHT+a5hK8|?u`3Ht%02L-lOS`Gq@|DR= zg9o!=%Hq+kN@ld+I&?iUOR3jYGQFxTtlOSi@?3cC^i>pSrWP#M*~){i!6#%gX?1%E zn~KMS8DMx1$?J8k5O`xkAiP7e4`iTw1wO3CGzNLC50E%+B1hx$2`<3_E&`Sd>auyM zy2lITLP~Za!;2>K!L#Q30Uz&lgJ63^PVb8IS25jxL!xh9m-o+gD##zvsaqy@^~4+3 z_@Xd$VDM~E$Gde8b%fmFwhL@EKD6BN1nBLgL!Q8?m!N99#skH%@VGT-ONpfR`hsaM z&$~v|t-8L=VKsq~XQ6GDO(8I~7{*vt=^{wzz$!6PBdAf4nsF&fsALhd zziI*&IhNJ*F<}BA1c{%KruSZxvFc+tk+ z+xWJaNBW3Sw?x=AK^$Db@_h?O3TTBiN-fHG;pS@nF9KaXWZ?bQORD{W_z(=JB(K{o z?=m_@d}AR1{h}F`Z32~mU3lT;kxS#OtaGeZ;q|<2*?hV=JWyO%l2UB9qbl610Sv6I z>6MLf-+L{4-(2|GyZ_2aGrNtH45LPREqp1(B`)aZ=Bf}^*?-3GlmEXe%^hvm=C5Xv zzoMBwe|a^$uN^{cu5VA7qxzWPLY&HU7eFj8O#;~y@Lk)|gF_1iHyrAdY2Vz_&-WB< z2X@FyGbtLYp+{xN8@&2P=nfsk^5$x;%w3$Q@bCh16w+HZo^hVo-uEH z3+&l-bK#Nk5P*Zq=?DFwL#z2XHCu`*X91=NYI*5p!>OE9Q!&{=GV+p@mFwuT{(UgP8&63@}#g)UNf*sG%i`BN|u!->Xm}v z`-y_w+#66pl72)hj03(6eqw$_?C;vd~yb+Vn8v#0Qy*SDv9 zcOUWR>=o=FxW0S&;}?C`Wb2RnCS-OHww5g3edT&S1&504tEtSxi1y?1UMW3 zJ@E92=rHSrWDp%$KWC*BBPzj3pzce*mYHMn5I{~6(F7M5&0c9}+;Ne@hmotJ{kS^* zY}ar4{pJ=jcX9qRzB1@u@kze3^%F>wp>eic?H6r32%=V#w|vn>jLiW&Q&=@3V{QxM z%Ulzn>IC04j=T=uzAOwEDL;~8)OcvjScqWs$y~A{0Ly*DUwzCT!&q%<+`}VTKKKUg zuq06{0Zudb6@_y)leSR#2?p4Q6m(!vb0*&y+yOv^Fsg;a9YDaJ!BJIHw|HG!4xd#e zXh3%9)XMakG|JVv_%$9V#&%%T6c}i)p{DtTe~A~}$=xFHXl(~~cdJhJvJP**y&bU9 zAHo^IpqYXVgU=VY`^npkJ^y^yM0R*=KGFUjm_~Y_&DqN)vIB<{)?ReGep3Uxa8YCM zr?K2sN*x#k2is=w5d-|94?w;AG*xW|cdTaZg!!SHKIgA;8EyVHZ|;#h*>juPOg(=4 zX8=^S&`Er*4KI6MMeLgFp&j=efDSiB+gbaj9`G>KKNEvl??=+6hL+@x7<0IF4eoQ4x;L>m#D)FF z;U9v9&4omv4rjc z%l6P7pKBOm##i;{Z*r9a!hWN(kALjIV%CN510s_GZAv_!5sOzD|06h?T5K+l?{5D% z*PdL(!pSo39boMqnI3m%`O2;Gd>&JNwOo5x*rsmTRl$D*=0*X^jKc%wR${eQ{JK2mTb#u(5sBGyPZ%be&STy9}W%p+6m%ibE)p z{fQkz)mvogTK@iCYu$*~ZIFJrf(LFkZYXQ3%fc4@9`mUMyjgWrR57!k#JIfH# zJ1hqA+i^@gFK=Ntvo*|YIHa`7rkom_&6vcs8JBn#Ko~Iv7*Vj5mccD)9P8cE%z)!oa;Rzw>a~ z;`tm(-X3xF7jgYKH`R#2V208<9oW-;^JgDsH+tKDIBgF1mFWJ)w+>9Q`Lt~bpP78s zg0(r^Seq+)`VXxbVkfStm@R+cN-Aer{wso1s&7|0G#T8{Q@hSWhuia+0na9I*(5`Q z6X~V}M7=x{pg2|kqN|6X@{09svIjg*X!$1pd z^~@gu#76gV)_vXHygyvcT4cjy5?fsL8ht3Pwd(||z*?ZB9cHmC)FwYSZ zSw%iF&DquOMCegkZ%-*SncEv(wyS`9aHsJRs`Z|r*fm=~ybHUIQ+lAYTt^qy+gr8@ ze{&Mh%9uZpAT{i((|7@3^A+Eo_e^VW<}d1JE*44yZV2 zOK1m(oTL&Dkc{ur-(JR^*;UmL0CpKQ)l0c3rr_b9)ybFj`b3^Ga?SZ3`iLjN$B)anYa$3GRy0J+#9YY4hm>3(x9yMsCQTHF?ct^ znwre?(o6^-b3EMg4S)mDwgHvevqKXeFB;#j6N+N2hHy zXs{QgkA`&0)yr>bu3H+omfv1F&Ecpa)}jP|W2Tx0o|qwaD6wo`&4V30j3;*JTIr?u zDD?X6*KiaiK0req?oc)-2GfD5x^N;%n^f!mH6fwS$|TW-!HMENd zK{&3B;SXNw{MQ#c;oR;ee2p7$fAv_0)L4y z>S$EdmLFG}E#c!;`}bmuk<*bjc-#{Ui^%RzgdRjkudTa&ToY|OwLIne<7@5db8T?e zy^xPhK!kuo0%G}GEpknjt;#*M-w2?lerOlNqcG&K_{!3WAnd|Am#Uq#Tbgl424?n+Ewq zN`R`6)!e@Evsw(~Zu^D(={#Lf{dz~ee=cn#XkQKwo}`WQ>`DJi!p3jEJ-c2?4gD|m zw8zzO3gEuCq0IH4>l!{1*|nA8=1;#8h0>?`@X2eI@)85FlkW$e&+m&o^vl|zSR~nb z#lyq5um6x0TNooN)a#bOL>Z*#!B8FP zmv5ci*h1#%w*SCAm8E=HEiC8RdkwF=r1~*sy`Rsp<5Mc2+RIVHa-fHz3boww>xYi~ zGinY!YB=0)Lbr1}bXmOii1u!WITQV!5OspcW!QZ}Xe*NK^bOZ=70RBk%)of4Owj$b z>j1X9{`zXAJ~poy6>IH&+|*Bn1vqihaukX|5k1u4D^A2W)p^Y^)ONDdlSW*~f6gXt zPA{vAQi6Bwm0sI#8uX7{U_rZsbobt4dFiDUV>_?3>qDcBEb%C67!Y_-FbZrVyLv|; z94O^ij~kxcOPkgJ1OjNeQ@PgAz`oRG!yBE|n13#Z^{)zUYgt9Ox;BNFdJYa>@h)nS z;ri!}{dD>7)q%5{ZAGsAL|&|kho4_-`Pf4dhP z`DM8fFD-^S$(QKB4Kv(ce=(T9D>Jkj#hbzIKi>ZmJ(w{ow7r@eB#G8=6yf8aR~+#> zGy7lSb7l&5@Z!xZvc6*J-eINv89H#HO<<2}ftAOX4X@?-Gwh0I2Ubp2n7Avl4JW(D z`CX4a|MpKk7CbhwmD^i+=;Ta|ZF$+~^G?&->4YR>{rX#Z3`g5qO3lv|E052xVWm_0 zp0-CTuRh<(lLxbNnznr1hw|<^Kc7Dp{BVifo}S7RBYWOdi<4)ka__etIN@K>mad&U zDQ9^1%eHvAIWNnPpKp{@cPEFRLX9x}wDN4!s{+W-TB1(pQf58i!ky z>NQp0A6rV0kck|M~kr|N0w!&lByFa$QW&e3_d)6}A&p?{l;FVDVsTun`(ufMu@#^d2RUGOU-?HuL=pqf45R-jvEVGOppUCd8RbOAkEx63`%oPV-Bg zg4v}J_fBf{GJxDM2xdbm<8#>&^g14T=R#4T1&-c1TgYV*`sI6VxV#+W+oWwkEM1jB z@7<~UTvB7HA^I@O0+c#v;TjNG3Q-iS=~ty~aD3$|zY)4(FMkMsc9B4##qVWSowCRa zt*-GA@fIzvAH~aiv4`nbP%H(hbXi65#x_526?1dt@Az*giI>_U5wW za{qbnGD*)TWq%qmn8!m`$DHdPI!DE1JRA65&Q?>t0FqZym!bN#Gph_a13}I;A0K%| z$x@ViMP6YZ0jF(;+k-0vfAI;BifZ#Co~;#5`J+VB%cFdSO~!y!iyQ+9=t!;6Xlr{A zBMPRG)oCD`t5oxvG2x5x6WTmMPO-U#a?{G_#}~>Jwzd!O8mIe4bH~=*J%ZmP7nS|X zXZx5}IvUTka@}LJRY!P#ukg96*s7`au8lA)Z)jaywDxsA*_P4^JBpV-{bmz-o6wJM6VJuU zmyg!$eJ&T~xA%Fq31FMQ8~En?TqsS{(MfRQ+ft@yFzl~}DsqVE)l*+V#CAE|Zx8fI z+*ae~jQ%3H&rf|ZR3V>Q=(LcmZh0F=VeQvjhyt=jTDFnhP228i?vPFOZ#P+;{l~fQ z6z%Db=4}?Ezsbe(ZLW$tAwYVM4+(Na2WL#lmtc*)1~&(s&M! zSoo**5yP)Y;Lw+6k_?6|#mq(b!i+5oE&-@!B$|K@SnKrUjMDBiOxuOoIGg$g$dJud*z5JLA9wVK?RkE8i!39!g5N`0R|yOdgePDY0Q-=olv@K z+JTtq)Y+-&WAX$;SK`P}DY@*>rjpb*E1iBwYCfIMh>@1>n4Ynw+qIp%P?a(8(%=O# zMJ7$k86)M$cu`AbWxh8AmFMh)0Q=;k!xPqq^se8KvT@%_p*StNvF57=HjvViy_SOY zMHDsp5K;t7YYnC$*Nn-ro2Kj)v0ZaD#XAYrPVLkX`Oa>JrQIfuDM1|$P+nyqJOi0O z`HI<_t_r1m#Q2C>KTeORZYbSL*;iytLQh4;J`kG%v3%y_rYVieO_xDSC{kY*uG1G- z1>yF0OofMS9YQf=8m%Kthtfy^Tu!(of0B#AlaMo}pAj5^PzD4izGBEUbA0+rBLwX$#z)k&U?w^!Z>tfe1o1=Lk`oiObZz<(X(sCG*fJfz zw{VkOpSSz<}L`^Sp>sc98+XjIf9L8rfXAz zU{KmO9TT*RP6-|@tc(fvz7){a?QaN(K9fY2f{2k0bE`n`P1U9kke&!RBYO}dw%Iah z>Dn@BfofzVwVBnBZOn8j{HEm(&p5C}t4%ShaWMJWm`(|j$7`Q3Q;cU?6y(W-CtUU} zHg6>*NPVNtaw<4Tw|vBuA~XBt1;!L9kM-r6LahjQddAv}+xLvXZ0u&TC%yEN${9n7 zw1~-FhxI%9BFt>1MMg5p`XMv-8^oBBW$to%H|zp7Qy6~9>7 z6j_BNk`ppbCQ6Q2-2e&GjtYt?GB>h)G3gQ2Hw&|6Y`8P&PGyI_NqH~n8RH5DUtC3BTf`ux}btqkEaO&XJlITzO%-?k$lW7K6#XRFh#uQ9;$|cf8av z=w{L}<(l-HyqNT6aG&I6((hQ4ZrWU@g|`{$k!Kx~q+MISWG0Y|fie*f2~tfL31{VJ zBH>KMF<-f4A$T)Xp^WL!R5L=|)MLsu1K34)Qm&a+C9;!pT^k|VZziUwPE=<7XC~Z> zG7D7?b8gK1FS3xx<9W8ABRwQrvP62q@5opU;k#z!pIml&NS3E`rpSD+ z-V_wuO;v1k!F{@ZYvYMGa-khW~@U2I(!|p`=r9g=u_5yTwy#W zNncQ#WO_TbET~O!NDm2QMo5;}MxXMiQ3#(Uq-Z)QKjdi8p7>KTO0lmx$CG7HUHigg zL3emv{2Wto*p;#udj6yO#q-JZvPQBXdX9MF7gcQO+o3GiS%!cE7~lMT zWOf+cEhJ;M8SB@6-?5-ybnZbaLAB0D4w>>zhDE+)ER?M2>HR4g5iBHAYs>T@eLA63 zV#&-WNS&d>mp1sO&Jcqc?Z)F%G7(?oGL&@2O_>(T52;0h{8Or{nxB%1GxEe!v1FE~ zkc=M>Z%0U`+VXH@NxCqe;qTc^K(Aq&WPO;#@PL-98*Kr{LjWF6M+-Sa`g+a^TbV*T zaUee{PdsLvMS;D)CHOWGqWF{-ZM954CHF0#5?dEZC5u(fJf;-swrtCJd`9gDjlUy1 zTia($-_6Xv-8RLT>(2Fk?4lONL`rqSlFicsnEg{lq$Adcj<$xqgk~5ljo?bU-Q$Bvn8Hlf&eIBCIQUgXB z*?cut6=a{1W@TYK70Q$La}1$*ps~>)4)Gy%fLeUt0Q2Na#&UkvOl2zPXNSh7?;Fgr z@SR=`T}JY9Vv2M)wx4&b)+V;iw@Jp=J?XHL^t$O=7QSOK_g1L%axR_c=3!>FbQ!B& z{BpVOSoN|)mABTiIq8?2wYf7@z0A%tlM^0tU>lmaK~sjaqMP6EJ0nYF>EmFFaT57c4Dt4`F( zPkFJ}DJEHqYTD{IC#k9}1ovVYPsVsEmZRdX!=6kI$uP$Dr>rtk65cjT+NW zIng@P<~zRcNg+~czIR|^ojHN2{>4ZL$@EiRCVP!BMXlMU6&?Bt%^6D33B<~pa0y?| zd^Arr=6gOF_9#{vtoag^5he+0rLpMqRDxzU2z7qmELIhg>GM9Zwp6}k$Ttw2&aWGa zb~j=F-l1kl_EkYpv>_ki;BgMw8>IMwp^q=Jlx)*NVPw^VY&?l7|xmDoyvMr#$H_($wYvPF1mtPpNpt^ukXsbeDt| zeo{c(IdlMNPO{2V{C3U`!w&gAYi(l+aVRWBx5`tR7OEKr$VkUDAWP)!fv0J})1)DN zOp;t>XTC3*lFtu$wwzr|(lH~c%9s@#l^;?SdQNh-`dCU5=c==#3Pp2N!^=4{=S_T} zoT7cmG;zgcTlqUCSAva;T|&3=%ygRG$Mp5e>9_O^Jcn%FG^=KM$IDREcsb@< zlb?t9!Y_08W6s*|l`_sW6qCyI!hvZT$*^*Jo>hioJv2{h%R>D-gUo1K$MldS`OWK3 ztpwW*3?iSO(kC78VG>)0uI%h#LD9T|_*2qj$a8B&dGV(_C^{^B;NzitAM1Ej+)R2% zFshOfOXG;~s0otzkU9h>r)b&An4;RTQ-~(TBj}vV7zbS#k+MAuhG?%SBho_tblrTS~hbEzS z1pwW=48%5iJfpTn#C#L$h<6pskmGRjQ)&r3jYY>%Hy`ATJ5oN?ZIkx6jUjq(WP~Q_ zu;pIG-}2&~OX+|_*4d|EuP0T((@8h%rB_a{W5DG6lx(Mx`w2A>V^~cE$BeU{N^-U7 zBcDhQiMN`Q)HG<$xQ+%4wK{u+H7gdzdDGdO8B!S3 z7kq!Yo?{3CV7PWY;g++JItG`6`hw~8FsjKIk4X-itv!WG{W56hc33;P0I3yMBd2J3 zC=A6J3}e~AoT4R^(`3%&qzma%(B_407@~#34Fs$-byF6qUk0&hF(xLdj(>_A2i0#< zNjR9rC*ZujRUq^=7$IioOj)1L+6SMiws};b4}+}2uQ_=tD_r_^m}hVmZQGOf#mqkB zE&Q5=fG{1L1^7_Z$tKy8EQ+QvV~VObVv0J?I;Uu!e@szTTTan#CKgC)W#R?aX9;pS z?3C1HZSg4w74p!(I)Wazlt!k{p{VH6n4<0@j4A5wvQ+<^fX%n{ZcI^UQpECe)@ISv zh|vZ=Ss20m&G6|=vy}-$BgOzIZBdKA=1lKJ-z&$z5+O=e<*eRsOi^`EPSMnPOtHJ6 zrPZ(Z&1hR*Dv+R3>?x*3?BI~v_>@N#^3;eOjv&w4FEKO_%oDZyjwvc+Gp2~GZF3!( zoWn2}*D*x}{l;7?UjF=*o^n<+PI}5&u`^2pMdDB%&)PLvE=WWY_?5W5Imxry?)a37 zb%{?o`GA=8lw{>a3B{)*DKFO(%H{E*EskN%4%b{;ze+hrVtLVMEGNl}Y%9w{s5KZ# zYmX;B<*c(2bCUWVbCO=WO>cbGC!U@X3vS*}PExf-PEv8dIZ0JSIY~B4%IgVloSAH< z+u~C)=*`}Ed`fK=$WQ5;1maU(Y%)b?Cx(MY;3-94O%PMm9`l%@;sRregTZuTiYMzm zh$-rZhnS*P24jla77|m`nZYqd-LaTb^x+;cMV+M@Q&c=tOi@>0#}u{P6jRg%UuB9C zr$xo-)aa*~6^wK>VNdR6ha^ksH2NliQCjO(1d zm?V==B^j2JWUhSY*8|pp&)-6Z<)_pYY&l6q`{pEpoAqYgL&j9pN8NZDGfwXy-h9^^ zXHQ&jX@X%v2&6d+~y>;sGgJ5U^FK=scVoXTrS%5#^Z{-|BFtBOwTy$kb;nBEh3d35U--mV~QG$#$0P!I;N=MZOpZ{iG~!B9dp(~uAyks6I0ZM zdokA)?@?q9zDpu66iPOi?oqG1m;cYCF&=MH(UaNh_{P zxdtC3VO>lS^j7pY9O)}Eo5qNdSet`)E!Q`Ed% z%(dc8Qi?1ploVRZ^`K>|n4-?ljJejtVN6lmS?+>)!-Y%d1h<_>ae9Ya*`_Q zIZ3sRIZ1szIZ4ge#3X$ddrp!BOXnLu=o`;ZshNSCq^gaaq{CrCXX8x6S?}v%3a6;x znDL`yS7OGsE|Q;8!>5=eEi-aGg$zre4B!z>1;-TCsm>`{X(Xn2F~1-cAQlJp4Q)Z6 z8q6=|T45_lS0p`DWkn!kiU&h(#}tp|qQ?|Fk8nK#=rrkx&)6Geay}`@BtD}iw_}Qo z`)j)wF-2{mNGX!<ksH>TJd5`ulTbWnUog@nWuH5DCG)E1AJV((cMXGY74I~AX? zH-O`O?hW7oW@=$W$~9}DFrPhNp^xW?&!|h3V~X0+5>sTwOXu&{8*agX(cT`wsA=B# zJF5Q}Q`DB5l;Wfy<(Oh`a0KenJb=`*XOj}Um+j1EnayC5~A96TYV3Qtl zIGO`gf1gCLW+{2DV}tkY(L6vP z9h{dRQnzKtUve^;jIWzjd}3_VL%y&EDzxA9-h;%2ZgVw{_neg|;N6q=xeN8z@U0YPnd*V_~Oy}**xNnt8i+|Hm zH^ju>@;F$algiLh)o*@CSC;984>~bAKIIDwx53IYn~{74MN!B$AONR?78RXSU`P zEyEadtq78sqUOY6t`$L&Q#2Gs%(afGjVWr{F6LSTrkJ7@)nl%8U`I?*H}J(=Yb#Pp z5vY(P8&a;R8%SIeQ`DV)G1oc*B&Mh}otSGK#g|hwPb%hG6Ev@rcK>6nuEI}TPzkH4di3(P56G#qoS zL$PCux|}}dT6;8eiWYOlTx&Kok0~kyH|AP$g-%;l*#T4hx z)fBRiR!s@NBNQ#>3b{Ug=|J_EBC~ATnj+>}JA7k`8gs>5E1)K($asOy-%)#pEq&N9{t6zoW)nDc3%gET*V1=#=Y&_BF>8HRg)BW?^w#dUA^9NyS{B zdRwl8##}MiIxH@xs5r6sJ1W97r)V)(%r$_>&hiNAyG=3W`ly5HbBdjD04JZ}m)^|r zXgR5vYenzn6g%Sp$o5$FI{uDl!*a!3>!|yjqQzV>*E(7;rg$+=D(3pq+j1Q>=1RF9 zba;MD5jUl;eq`K3Z;Bdo#asjDZ*v_}Jeenz$|DmgI$JIP@Jj%JoSnhsG3-mXnIP)>%?HMYCKn*E)+drg%0_ zD&~6ZZMjYwbH!ZibkmrkHv7ciQCH~Z6wPv_T>HG#nBu{j^HZ+Rhu)U!tT9*2wN7A- zDW1%eioc_-Q;8{R%oTI3GhJhfI+-cvTGxwF@=TiJPUqfLsnfZ8gal@|b3UAnLA@z< zuS$*GBP5oSboTZbq12mV_o~#`Jwl>B zPP)7*wF*=B2x-y?DdzfUbFE^E-K$cQ&JT)jMkAz{YZmCWb5c1)vs^LP-6JH1Xm_>> z)1|lNnz~n|Y8FxZuG5>j=thZDdM-N6DyL|)#xDL^Xxt^^`no^uK=1RGqwJH@;JQ`9u=2~aY#}qZ@in-RR zR8G-y%`w+HLocSNF;~pBE(3@u>h_SB>q~EB>Z~zW%(YgfLW-=9HBT!1j_0p~RY`M- zX1QXnwJH@;)ahw4*Qd_NREhv*xni!hDiu>4J6B21UyONf#|rVyXv`IJtyQU*;@lbE zbN-q;Tdp&Mz9hGoa(&RMR7?>lU|;Du=~%_!9qOH}!chl0r{9rw1vz8P^|7}nMd3_zc+9nK zhRG?K<%+)}JM!AvET*VC#AB{?)l5#&kf|}(7t3D96m{cw$~CimJ6kShb_>On>zW7M zS00CB=V}VonckLb(3mU!j=EGRrl=$NV|hIHwp{Fr=xk?b-tR5pm(DnV^Kj{Hxfo{K z`4!TD-Pz8ZzRZ(K3QPEF4# zn&pbWHV~V|}rk~H}-j?gEF;~pBuBeVF_MV!4Mup3piRDpau9WNXtG6dL_MV!4 z9(65u`W-&UGYePc&7|LP(wHm#j-Ze`OZe1#YWf*BytADFg)9`~@2E@XV~V|}rZW-H zasaVBYRnaLty}D4ioK_%pC_G~9)CxTxl*n{A$OK=8c90GGnYee%Y}<8XNR1mdTpMPDviLP?~Nk zB>>TQAw4CSTz>N3{`G(S+rR$f@BjGcfBuhu`}<#iJ0FgVkM-~W_~&1Li%&@o+v243 zlqUyPrX=b1HLaGC9No;OBzZjiq;);43C*4lb!U_HoaT8nuRIl_>4j!h#4J%9(+hoa z;RVr+WoDuh=+P;eDBf8Yv4+{)jP#Vmp1oiB<)F)b;!_ef$@@v=@-k>6V|+^XY)VWU zpYrTbqEId`qoNp&;nHyiE*RsCqs*Sq1-b0~e6T)ZE8=6$N6jXtUvoYx^dJ?ZnJI0; zc}()8D zNx$W&YsW(=I(@w`b0a;axBG{tjP;v3Jvp_wr^8q8CwZcc*OKV@F_BF%x#`zDxPO_G z)aLS>b0SmWJe79pFou4Mk4eJBsype|q}#zfn3VJ5LGk4=Njk#OiOpn0<`tceOnes8 zn`-vspoN5(@e?Cb+Kk7i1l)p}ZGFqbSC-g0(KKtv%;GaBdSg#$ERK`+6r?2C=pu3% z-}tOmy_Dqer7^`RWPD(JmM|V(_;64h4i6!SdrsJKi=E>$Y8E`EsCzGCt`*~w1r&To z4en!#ng@<4cJAedYwhKZ&)9i>7H9PNSz#zKkW@BW1975o@}OkPY%jWOFgI4?8~4+*{t!`l5RW1Bu9;+Vv@7@s)x`_ zoDVuGHz%nbzvV0?CY4dUAPU>A&jWT(W<1}0Jn8p%JAGAjv#`YtF zE5wOO*}mxh<(Q%-@N$Zk3up!QF-6_z9N)}jwfj(GROUhMI;J=qnmDD%?sqW|F-6@4 z7E?T$^u!d^ABZXH=B}9H*-Up#QC*gpqVCy>DPGJ)jVY>E6;dRgH!M<2@nBwbOi_^( zF-6^BHHEp^i8L5`zhxHE6f#!9k_4#_JslM_lzz&iuEod?sny{4kUIY~rl=Kzm~9_) zlOD42$8DL+52?A9_>hX5i7D!S?3`__K;$In-kKL2h1A;8FL}~=jxpOO1yRI@)WIG3 zAz6FVemL7CW_A&1`9 zVba`Od`9hq&OfBqEaOA!LdKY)wgjgX9bguJNLq>{gBTyOcMfQ}^v(fIXrInL)une1 zXu4<)D8KC4g81~ZXB}S}Q`E{@Oz~*8CjOAKZcm60dG3BSTKtR8sBS?1A$4R+cu2Yr zJ1evcn6oVT=_@v5NPIUZpBot# zqnTl1pE72gAtv&?W0I3*s&bOEp={#oVV$CgWlVDJ-h4NIX}JZ^c$N^E4+=0kgni$q z8HBWG%SwMIFq?T`3Q$`Crx!$lwj{6Rxr7+c`P3U2J`>xCT!!ir-`vb?PSL`}n4-SM zoT52^F-0v3#R7Tu)-wb)dN!k$Q{z)kDPt!6sN;|^npnbB+VZeof$T_&ce9sa5Q z0mUL*#}svpeQt4PoeGlDtWBC`adMhCzao`6O|Z98_zmCV0@#;hh7Q)5MqP{P<5P~l z|1#5UY^&6H7V#-BI)Og^ma`7OPESeY&J1pP$^&!aOo;gV!1T~h!9dNndljGZI9k#r z{+2I&Nm3j68kc%d-mc4i@(D!9<+AeCi#qL}mZXgy=;10tDa%}%K;XC|UC9=jYIviCbD zK-G61W?4ZEX$dm@nr9Y|c2*rMk5ttj3OmCV_5Fm_f|Xfz3B)#IKu(uXlJxL8@~tj(4L2dt#M79kvl&pMn)z$|!mgL9HPu0JN}{V*kE(YGWEBf0SKMKZqJG+R~yz~rdai79q& zhv9&o+hL&S?J()p_y*PzhDd(Sj98RhR(d%;0;qOqsaw?Z=Id(u!e6(Q>4 z{G*C#ge3bCMeA);uUVTGeg z97S4aK3SGJeLM5XEzi*wq|D`!IbeZZ&<2v^QG( zklNbmOA(>z^M;_M!iG>P8INMu6I0Y3lQ~6uIjK-mVi#aeOi`0{shXS)>g~s3&Q=RP ze#>i#W%8(rku;d6G1zV=RvAZDWwaSjFZ`%QvQ*5;T1gC=Q#5TJ-wl;k3GY%X#&Qr- zL9y-~W;wbH9qBdusm3-DVaSY>O4QCx|FF5`R3f1 zqUIc`c9z78(@1#Nemd!6#NU_47<(85^FlH{WcQr(#M2R*6T6g?)OuoT6P$Oi}&)@OfXpbV+4u#V%j!@5hJKy)vmkP}4Z% zd8fG+CS6!%HPsjw7J7AlI9OT(p`^C<0*F?=Wh&~A1IjEDps!$_H!L=(O|)+G48&})F$wK8F;44qV+#~#5+wQqb#%`v5q zk>TfZ-RT+6J_S4`$*}wOZKq+*<*WuG7IVT{`IPbdK5I-83+1RbCsu5uy5}+DqXJt} z86xp18Y6u=OmCF?jw!l@NEPL%5dQd(y}_B6Nx_+M#5ifPF0I~OCN|8ql~DX}CNC+c zw=-!0IQCMRz$d|2%sBIcVXUY5zOXx>H$`)$W2vNRK{Q4&5jjE^1>dBK5&^P9rX*)Z zd$cbnHW2hj%4w+!8w}62FPZw3^Pt*1emaBJl~X5U z9yBKupYnueYfEKLQpX?VBzw0{(M{d^?VL0zl)gr$@!H*l*;Iz-7U-*`gz~%b{;4qU zFnc#_YHgY3*V#h6ux>8B9Oh@)eWxOH)~Im z)1$i6sSJ??>@Aj)4s}Zp={>ut%9zwak14ugOf}^+82T~(kZNkvL0t1iQ~WW>`Do~< zkmUIFrJhhua<xgHG{?N#b6K7K%wS$WEMsm?T4W#5l$zC&f_2 zBrn~u=wR#Yr zas)rzj-g_ble$mVk{&@fSM{B=;iCB3LM$1q6^No{?K52^PZAJXTyq=%e! z9#?)y#Vy8%RChH$q+&>Nk~)to<{P`ywznaUZDdZpW!gdjA0%~(Kz>RszJ;H1U@?w- z%JjamjOMe&ht%?c>=}Fq=)oLIPtqV_BLXqN9=CW+dgUt5$iP1h{boKS^4;ogD%lZ56P|- zNwLKO^vZ0VYPL%JUf|u9a#@!&Cq(B_E2F8$KTkTFJ|=llj95$(RDsyWkR;8LI)N=j z4M9>TOU5J*>h$L%bvi*z@~DmfIY}+?ap^#b!l z>WGxgQgBGk1jZ6{Qh#X3JOc*esArJ!?fbFg%V9I3AadeEs;?0rvi8%qL-6#FXZ2oU z2|6pJE0&6GH`{r;M6s%Rz{7dS9i}*`=yIU&e7p?!NhrD=RF+QYb0pmlCW*_3~ zzI4tj0ub}OVit)`jM%YkSZs3U-Z&RDkmg*{2=73fJ~Gm>5UIa^U^I-745gCz!K5-j zq{>iyNQF=56b&hrQ?wL8{2`C-VuX+J;9WrZDSJmw2k!#P52?xNnB<^yT*9Q?bQsjf z$WPhZBRCA|5yXc)=|q#zTLa(Hd2S;fW#^W9C~EC8|B{MmO7+@FeT;N@HK1|L2py;J z#*bcf3%fX`<5A<1GVn==heo$JG$+{`p8(^EPe=vxIOtTnnDIeVv^hyFaO8|DJS--8 zQnYi-_({hB<)_q|b$m*C-Xx0?pVBA(=ci;XbYH)pCE)5@rkZF}BxL+89oQd#%dvZS zLeHC4M$>PJDaR4-8R;FT!2s0px12`nQHyVU(qv$K%8P=2<5T*~_WYDn{iN%SUlhU@ zpK{j0Qt`K(y?_wLq{rDGWJr=}hMIGVN%qExO@LGElPvh< z1<|C}147PRgY=X~ZNN=m&v4Z4*7(Mcni9-U=^e1+ZXr`4VjPKydQ8%x z{pq(nX>lvQaUUQYU(cy~SUQ|EEG?Ko5|0n($@FDR(x;Xl(&WZ)(PPFmPha{q&!J?V zygYH9!Ux1W39Gv<7^vjdPqT(o(>W6)pc)pT9mcQ*S)r-ew9614)0ZyBr#vafAg!F8 z&$=`(CON7r9Fz2@FDA)u7rF7Aq(1YQr0)hA#zQ8UBP9SynhZ0aCVA%LWwzR8`pju- zHj?4YTDIIVtF7%{hkP&C;x@%O`;ya_-cEc*c9L{HW9MCO6W~ab$@n{-wL3iYU`h#@ z%1B8PrO4f+w@o2i4w-(*qgtJq;@M_)#axf(T*had%p*uKL=)*3iFu|_S&-Mjacm_F z4xx3Jd=kJohEmR=E=$_dM3b?8x#;l8@f=FgJbI^Ic+8paDaJN*RiS8t8B^40qoIpF zPmE4!%Vm7Vvt>16ibRj?GsawNraC^OMo%$C9qkfxJ)0w)o{?pfou%jUWo9jfcFQx(DO%bu=323F@fo$PD5j`rp_uElZJUYD z2pXmHU6T-KQ;fORQHwFx8Z5*V72*+dO-R%Jj@cQ@Gt*Em3gn>38t3*IGp>uGd3!O} zy5b?GsBvM;^zY&S8((uX01rB!QOl7r*K^@1H|H#&ur{ zBI7eE5F(~{G+UV7^`L8=;xj6=BBrRjW@D~T=IzC2RIo-&akN}>%(bFy<1;FdKBlN~ zVazpyPx|_1!`wI541!+c!jx;@U69^P0e1U-NAJ6jxn|ye=QA>9p)*B|3uCUe%__cY z?GuS9YFrp|tsv_7jFV+PVu~6U#$4-koA`{{bDmNpP0`smJ2P^r?<+hXEb|d_t#M&` z*S@|qKBKll#S}FzjJZBrHKlyF0NZ`}8nv(xlO!Q7b|EIo5;+m_oTOIIVv;PMlwwy( z^5E?-F-d$CyB@xEB18;uvb;~&8vy`I!ALPld@2*7lyO!)+l{9rSq|F!dT4(V*DwB- z(_}UxCV5fF=HU`5Oi}`t*iE0$(Ho>=l1BxMokF$Fm>`RgL%D>aA!=iaI({doXsRuy zsN48*iWV!z6t%OH*PrNfh8vm=$|+j@Ii{#XA7YBy6cSTZ^%GOnE|Zj^&%%!>Dnciw zsF~Q9qISl{6t&MHrl|9;Vv34>i79H9Gp4A6He-s~Oq5bQ>qL{7qIMj_6ct$#Q`9-k zF-2XU8&lL#pfN>t&SHv++K4IYpqZGW=F)PCy*&V5x1FBRw_C&%bvso|QS($WMQs6& zDeAJ|n4-?yizzB*Jf^7FfSBTJu|i65(sgz*MV+D)Q&c>5Oi}CZF-09|5L46zQZYqV zY_}@|F~#0kXU0<-zAHYX&S^<0f?<>-UrbS#U&a)*zci+(IO3dQZx7(2)!q1vXG@jF z6h})z#uRmkSxiwkD#jGGa+*?{zpMhyQjV}hcN%)TxllAAPjk5^pD7;meNxb2OwwnK zJB>+Rbo@z9Qay~Aq>qEnNvf4dNwP-M zNq)`W7B+R7V~^gW_ENnM{6lbp3% zEhnjC%2SencMSiYlVo&r-`7LpytivG9tMMe#f&qGyR&k``?pk1d`e%k7?T`)J$)GH zjvzV+xO=MLanQ1A%=k(759cJcG!~OQ>pIb#q?R{glA|u&%SmdAIwz@fBw~`&U>TU4 zHDQNaGYJ3)x zbU!#J>HbCvnw{AIYTiLilO&9Yd&>Gec{mjwlaYhE+HJ9;0pye9x@Iv$*5|KDvqdrI z7ftQNBxhYEl`?+#(s;MhyUF#?W?k4-Kmke>3W<=mX)!E{l4 zNUc-khg82PC#k)#@r57N)rvo*7B}NVdR8?4l!G=Jm43=Wi%9t))oIO1Dh?~w z=qH6a$0X0%^&OK0-OY`*g8Z1|qz0GyUZI(oHSJcucVu~Hz4G{wI<7T6BzDJAWZ@y9 zXrXR?NUeLsht&LKen`ck#fO~Aacn)E#Z63vk}haV+@{Xz@uUOHW0Ggx#1)eqb(l^} zl2}5by_lpgM2tz!>ZPY72R4R@V5T~KVA866%kcTIR>;!J@hOiA{)tKY(#DwNNsHMr z$+H#>W0Ip5XJWaWw2~5&WRDAFjg}4$p>y+a(TFsa^oxS3bBfA#<_)ps*8ITujA|ZZ ziVDlhDO!pogPbBgTAWBJl4ldu8&lNLV=+a|QpXfk{lpYcmZ*&>s)G?z)BrE0sJY~r zqGnrSinHmSkRsSFb5~-Dij0gYsx^!$YCb5Y*m+C@<^RrOB8s8~v@zG3Uy3Pq9uooA zoySB#QBk!i*9UdZVv3!|M9ieBI(q=MOdB_(<&wr+t9Kt$)Pj0UvGbS+ZbtK`@fo!+ z6jS8c^u6n2=P?oU>8RO&lHk%QrDeU(KD9)Fenu@}k-| zC+VGJ>Fb#lWEP)tR!2W2Ni1UMx}2n=ro(S}W+z!^<#s-(d5jr9C}tuic^s^ek(1O& zEGCKX())UbNqe+XA@Y3#G2`mHEo`g)Cn3f$%9VfU+i6i z?wEkyh^)snFGoe}rKR5sW7OrCG0Bq_h+>lXFp_(T5$zQ3R2iiuYBEHYVN6+{Pd-H> zJ|@Y7&YzQJGDdUsl_Y4MG^DE9cC0lk^n)I!gWb^^$GjL&H$UcVabb-AoF7$CwrFpF?Fw9e#}8vHpRyre0_7O z-Ur4v2!Jy_=E=9w#>YG#Y`R{2%(E}ojE`C2dOHCSACs97;(g>KkCxqhgJgG2%&-zc z(dVZ;+0cQUo1YV!5}d>w3TVl+%~F**VEW8G}}mFDH5IJ2M_X zW}@%2_bGK_V8uyMbTKe$LCjB1^P*128#FbtdV?m`qJ2eg(A2eoIZYDf-S22V*}Ht> zoRf)sOtXem_P(PN0W}(;r9j>|C-WM+)11xo$j^CDKkf~h8mzuSQ+H>ls_t~S*cH7& z(q2(clJQY(L3)Fv8O)d@4y-((H%OWd&Pl54{su|YajElB8+N;YOU=vVj1Ly|zd_Oh zjGW}j%*7idEoR9{GWWmp8$W6oG=;7q=v*r}Mz z%7>%X8s4C(trjusgI1{zY38V=sB(^$Q<#6viy29@KoqW>s3(g%oPSKsI=?~E0+vH; zB~R+O#>b>bqW8z7_}SZ*pFpFu1v6)Su$);=l0J#vr_`__KP5Tm-lx>ES}y9NW%hE$ zCj+;~frSOk7Tqxz6p6nKQ15!u*sMvy!nIKI^`>GA5b-HfpzZ{4v2C_4W@K!qNN6 zN1us^whBLH=V82Li$?8v%(c;|y)0#$L)NwLI+r8GEXI#=`s(h;09_NSmY-7Bz{cNl zQnYtYQnyyULDEd`8zc>ekdxH0MQ@Poo_O?Gi}@*at!_?I$1CNpr+;JtRzlpjobmpV zg#(E5Q}&N67zio)@|Z%WPu^bk22Dll#b1+@tB6r<%fZ|T&G-RbG}|0!3Be%nwOYB% z{9~#!{02!4P-Fjk*5S@M$zyk8F%On_%ulK9v+@0aLGLX^bAOM0R*yYrT)Rl$AZZ!# z{KmBntm48fte}h3t~|9CX9nIG&G49zv?6?ZLA2c)7VHg@>R!hm^Pmeo<72Knxq2Fl zGwnsaul%5sFmlGbH^0?X5#Dj%Z>jCgv9onPC>lAZdDK~l@dYt>OT;L4;Ld<;gl6i% zvDwltJ=MeH#Jg)F`0g#5Y*vuWV_fDvS8rnH7sL_@34z`aBdx>dG)eHtIpY^JeA%TR zViPpz_^og?)Zyzq=n%J@bsw^k)AYe`vGzD=mrZ<35@seyht%addHfgCJOjY!{MOIf z`WAmpd`Bj^SCAv7*9*`88Ip^9N^2RYQhVqSzA!Lrs4#ljqB348*e(3B`?|ng| zui;EZlLT>ZX=nCjcg9a9Mfr{Q4^zkfVJZt}yI;>}K0^L2M|+UD;utl9{|3$3Km&(4 zeLx_bMRUZT)7J*QLDHT%Pd3UOooRTKXyBNC%?UzHzqc^fqZ1&B)}Z)G-~0 zA(o=<)sVCAZj1H$MHf@%A5(iR@>6zRjYd-9aCmjrlBJx zT~!gK-rku))^PP!MKss+wiI*sh7gdh-3vBz_lA(O4@Jw}^;s8&#L4@aiOy|V&q-da z;2Eo;S#z1`DG5z2Qx*>qCADM8gPi7}_mj{TT8)rrh&mj=CQ(r#UJ3K4#qq@#gY=(c$_z&G~3yRX8Y`oqk`; zq-`tsH)yJ781p_I)N1538UEOvcW>v;zvs!PC8sh!oi)Rif6vkJ2za@X_ME0ecbhp) zx?mu`BLXawrTC6!U78r*(dElg^XWM+2c2mhe@}8VYL4P_4qjr4X`VDi&cNPK=r3ml zql{@Fd>OUpCa1~c^K4|kqeoi0TlG6kiDzcRG?!DgmIj5r)taF+d-I;p{-_hZV zchp%g9S&cL$*F&5qLcAl6r!KnIJOt)wt@JLcYU`U!r#^{#UFFj>`i`3Uy&GJ&)Kd# zXMD8LY`GNqSpPJAail6^0NGgB0cOc#e}kk+W=>Lz<2gxQW&8cSLDI5IIY|vQQL34G zW08$ehde#+ipV@|0SE!P_}{ibbMk7*v+-y!cOr%5-XD5F#8 zcN|fgR?p38`aJS9g?>B^if+tlo^;K~8#HwSOHLC2s@yyHfl$xk`I;GegD3@9ltjzx zN_EKbqU~*Es3IMI1mxKLnCc^y4akl;(|y_bYtFhXo@MuA>Nu?U(uaeFY(rRuLd9$765r6_tUU`;m{&M5=-pIj91pQZ%iely zH-^jE0IvBt=l(WxnAK*+=VV2bS)%xRQYz~n2UE_pyib14qk8iB_dL#KGV^l|x_~f0 z=Sgj5eokLqI;1%j+E0tOmZvm@h3q4-leTc@=cEa!`#F7WUVcud zDfT`msQ@!_@j1^`Efe`njq%y{ryVY-F$R-s!8?3Je)svL@V7V434(zS)_U;qIq8cR zSMiN=;xve2iqCl&%@4`X$uqJCpPrLe0kd&$oO3u>*b$%8A$4z@(+8i#=X_yGN&Mbx z4|3;sG%|>{`#YkTYf0bqdjcD`3~hez(@`<=@i{>x%N4zGPS(xJCB^4F`FNUGKBrOV z9L49HC}g)y#~a^sCQI8U8lMx+<%;rif^)V)RC-S4fSAkh#yObf zG)#QXQD-LC_l|rpkkh@NJC&nygIgZhF>U`mUgqBG=^?4>>GRL&spR<9Ss-GsJ-+q% zY?dQGrrM1+z9!RE+LDwX)8|2^Uvs9Nw(~J-RzUAdC!^Tgqnm*@_dlkV+|x@(cXWS3 z^OqKM^J9XEXp4LNgqRS~`w7iN?cI+FaJKgoI=Gho%(vLUMb*8~jH`_e(P_dli%X^ksz3@|ap8E2*Elfv%fEGivvW-jw{p4rRU ze(MV^KXSKcdZFav^MkVGM-G}_ypI7&%O*86+nml6ss&A*Iua(ji=-Yi3$g~r5LjX% zE#gB{!-B9@RwPZ)p$8LrhonwU3spQMb>v7+QpcR7uX4cIE@!P31*d9m_@cBSmMA~x zpn0_XRi3)f?EwO$b9?gdIcgVF{yj-Z+Z~0D5>O=_aF_Fbanl|a#s_Md>Mo?}m@JwC zd{eDNi=w&lV|>no;>l9*0&TuJe<8NQhd~o*@q0f29W@Uml_hME(M+L<;NEm(6WfbI z6L*+&2xB_ZVE`;{zGr?+Ef&SkXzINT1jcptSI+p^6iB*Sg=0=ubj&{{(~sN!!W$&5 zj+v7r+1dM)I^Xb(QyR7+Cduvao0dEG21$c!q>e1W9|LRTr_|{PZ;N*deN1Xx=pTjC>kf{xLO;@&-x! zn6Y-7=>uu&;P_k4jO=KW%ulH!K;myXAMIP_Bo!tZKObL~e8`XKN!a|H+6qv~oirrsIyJ4JE2d#T}BCDo$^R;U9(@N~e@iw^OWKe$2sK!Z(hoZE5*2HCTzW2uHHd z;wCrKH3La{}s8ra*H0S=`%l;#W>L}fXy_-h`!8_T25 z%L==BS$gWV)zoAFPN)QHEBZ^9%5YBY8jQ^ltXmiqn+$Mr;vwZEXY=FouQ{l(OdUCz z5G^AU`!mOZrq;F~#b0yK{T*+Rv^#%;b2cKjIe+8Qb=6?3;|AcX?PKO&lWjF^lKClT z6Qh_ULptn!!bbDqc=ASyT#$UtZ|=#RN7G30_dHVw?0oBI9hv^dDa|d;NnUzqN{?r? zLHQ|xRrkK0xp(rFp}gjI#EjF>$8TD$OimK0Wp|R@V}b5#orj~Zb&Yc^@aeO$WDXjzKEmAyf-zp!gZX@1J7zpyLV>X=58jK}EiaiiMoi3Dr&2#@S;H+UlE}LiFf){_yvo2K3Nos-e4U)an!vlV1cdK?DE%eJ@&{>E0 z=3leF3x|s>Uo$@C*x!X?Mia+qxo~*~ftr9R_gHI^$QGLU*X-}fP~h)==ZeVA8Sn4O zjQu?spm0b@OEPoDFJ{j3;LoQP$H!#)V(&=JcVOkGbQdo6G$+l9$H0bRa{P3P(`1Cc z6{T}Q@=?{t6tp*7v@DIf%G}qBt|5(k3Guf~ZN5SCY;JZvvXFPJDV}0cng`1|$8hI? zlA;*PI38g3b#HYHNmIwEQi7zV40DpqnC)waz?m7iFh8XZv3!H1y`Y?=f{0TUcltV+ zvzeb#OO$b(dSZYD=V*B|X>$xZ(=G&znd->=f(zOey`_o+XbRi*n%mgQXm zwk3#$feYJMjHsqWT#6KiL(5vj-~FC!$?hl8)6cKsFzekl*2Ye==S);)L`G!9$p~&& zlXSqVY#nqdZR~nH46B*mbne@c4rf-i?Eo?Jo31N0VWzEJDI_@OvQgJsa2RqPa`-Fs zRYMKn(w3JJhm>jiQW31`-4x8^rQAl}R#&|M1SLwFdBKp_fF#G3x1OEC*E}RPH%p&y z<)H92twa?|OzAYF8e$R=Fn=!cnwH$KWRwK0@2@jbY(Fh>9UqS-!^>pXh4#a%zyX`G5pb5*7W^v6U%$> z{)}(&q)E8sEYgd)tMTjO4^MCTjx%QSQer>%bZ5<#d$lzC%7ui7hAKZ^&9t1#xQ`Ct zG$oKcZ+3?SNda6sfl?;yr<&DGK@v+S>(g}cqoX~0vnV`kAUpY42zPL+oq{ zU)e&cp{LXBWyTb7UQFair4w;w##h66F)=Dkt2_6ENUM=%z=97-ThNRLae6HmeCe7# zjr3LkK0LiW3kFAdDaThSiz+M-wJ%zkl=CgBcLQenrY8Ct)os$Msfwa3)9R9Z7dQ-#IMLrxSN zrPosPsKI{H4ya&uE3KGictga}4$a30NB+ZgzCDIa>m?5)&aWko7tA}0!W|aV%B~R| zutDj>YteKP*rEKlt6?QzrWL7*y7yR-^1ip?WB$CD%v{j075!a5_)G5E| zcmvEI#yrNX1yH$f*SG>u&b+Pb(?@G3cUDPj=P~{;KJYNkONoii^rM@q-gu+;ymCvK zv~KDF21V~_yKHY{hJX9`o-%cOPnkMlPnmR#R3{9L)2CdWHmVL}54k#FDLEY^Rqk4n zS57rl1s`l+V#^5w6A$>jv2z20yqp@N0>++KPc?G~=VoBy!?1LqRP_>LxSZnTgMMcH zTOI!(UA!JTK=L~zk|AhP{>!lwS^iMcKyMH;9nFc;L}|Iaa;j^e7k`;ya8X; zta+)*&?9Ld-hi*}3n^0CW9;bH+ToJZca^F^H}iXbU`va<4ISK^D}8<(*nc9uMF-yr z(nr#<5kD~h<(Q)}AcA1b5oDKX8`6;I(TXJQcN1ge zSu99e&8#AAx>|x`%Nn|}U395V2XfoQgV(a>yPj(j*Cl-qRH2dLg!B%nb_s6CfE;}p z+UA8WL-|dgu@{iBL3krb2MU|Aa-(-hgQx~4rnUvs6Ae;hUd$7e#@EGB$4mn%hMjXU}`FT zciHtsL!b8OPLTfcip9{pzE>o>7?{Y9%-c{!zIxsbRnDiRRcXU%E9q_DkOH5Va&7V7 zQ03h4;LLwGPMOK?IX^hf>!z|ku$peF(}(+^CTN50l3$#rPmcq0Q+Yi)kj`jeUXb=tXLhaEqmwf&=b>R9(!Ph7S?xS- z=!epFsYEozoCYSQlJcL9w97ms^K!D$_Mv8Aph;Q7)agNa==6~!`Yv6F(yOVijPO3g zfFyoKI^lIp3q2!AhsMWL=;1^D_~56p>Fed8f;A{-I{Y|hycVRleIA}jI+Q|#FE^wl zub#H_S@pKZE+c(oRW~ro%H?%)!HY&-H#P4Kf~35yFXM?h$2y*vqw}5iD6L8>-wL$c zsfQ$oGG3#NXvHCaX}etU*;F19xtw|3|JKB8CPfW!1=&fO$xvbr8%c^LKJ-DO^AohwnTOAeBUrM z&YO^^f?$?;F>&%r9ui9hc}?Q^wP}Ul&=2Lm9J6v;wiD~I;|SM0ri=*mD6gApxD4@3 zb}ED7I1Fg=m=h9N^O!Sc;q#d4LkoM9$5elp;d`W+2XMyc<>cX71}5_0^Oy>bhwqWt zQ^WU2QO)Q*nrL)Mfim|MLiOJ49rh1b?S|yLE z8_e)MQn%C5cBEtl#mM<@Kh(l(upP}@*+|PdYfRASJ<_}A;W2~8(9jEz{I@U2lFehT zSQXA=sz1l@JyNcBv>nYGl3MfM&RuTun5spLKI;~ZUV=SJUOP0M1KH8pDvU5kQ<)ni zMT&-)7}?}kQ=R)CAIOH7I0zvxCdRXQF(;gBlonH?NkH8VF|nI>UQB$1X^4q@yu6q= ztsyVwjDcrb%o*7lhM3q(BrhgjH?nCEy$;46S=m&gFfp|dS?z* zbr>vbWw&0K$V|(+_HtX$lJb}!GNTQE)S_5X`?@UqkEAdC0$+fka`L7_`~yRG|6+oYG#WEFB5JFGyCyM zRZ*HQea>lYE~S;S{z%`BDRf#-9a+En*;fAPh)&mTVd(MMNOr^V;reD}5f^Gh3# zKOb?Q{p81g`{Q4J@*h9=_fLNH-4|axzyHTCpZ}m=iGXi()c8J-Z_GUTK9JKJ<}zvmWH!-7A0V||5GLFvDI&^gRy|F~MdVmh1t@k8?!GcRYIKYqV_#Y`_} zeS^;X3Yq`(`o{a{SIifSNZHU^<hXYGF<#E*vu-v^O)CU4>gp2B&| zNg271hFh}>| zznfWqR?as{FR$xqV5;`=SkAPwR7^~PLf)xQ%Nu#0`;ULU0iRsaxA@VopoXMH^sLcK zS`JdDyc3?@8ln68^~On3-*~$43hGFT$CDxHHhsLJbth^5%v0A2aCOE(s^*QLQEAQJ z-pEnCe!KxmI%+_E{C54lq@)cpq$GnkAU|Gwdj0U08OpiNO?kA(=hBwOR6jR;+oQ#1?bi6_H{9a$lIl zJ|y+=qA5{KpSMl@4bsoF&d)mR;8ebA!gkJ%gh`jAtQ`sR<7J)KO?oND=Qe59)Ue0u zlwVKj3aDuM+tt% zeFq=MK@zWuE( zj<1`v*4IaMCj+H&P>7tq7_~kd@b%dek09xcHy}SwEqPr|1Cq4UfTR>%9&#GLJriwD zX%00P8|zvCYLw5T&Khyy?bOuD`r->&>0$(i-Xi|SnX@p;gVvdMKr0=k2B@rQ{6;M+)npt=)h}|mO05g&e!9fFXc!?ZX})l(zVvhhF_u)NGw`E^ zr0PBj`;=eOLudZuy*Du5m^Ae2M)Du85P~9;{5GjU4CNdQNf*p4rex}*js zCIgL+SNlXTQDd9x8{KSPzuu5kFUd!1{;DV1;78N<+I6qAqKnoc73T_*Za7(QzwU25 zM0njJ1Cl~A1Cm^w0f~|L-D93}DT1{%pM88Rw~I<{(+@SHc#N6;_O}{MzixV4o1~a; z3_SRLn6#XRm=rdolcDQ@)os<-((AbsPs9-PjcLoTdz4>KOp2vdNdufIM_^zg#WMTp z<%XG@w6W{iB4sktmA>{AQs4H7c4J_^F+1Z`lhWELBN~0s36cWE^urdtgru^Z@#))W z|5n~=gZ8>Z#-|_T+4CB&o>0TJQ(0SxX48qLmj{7hMYn88p}h4V@O6`n1zpDxCau4YSc z*~)wOS?Qq1#+hHw8OtBbUH^o07lhJURAt$xGDefD;ATCkAGv3#_MTkd_3kD3`}H;4Wko%lp(DKI2kJkmwZ@eB%LA+=zsPf6MOL;--8~uI1&&O9xDjITP zLjeO5Nw8~CV3E^$ey^SnLbr{A<$M6XA?Yl?p!*wBPhXWug_i7szSaHk71R)Pp#{xv zk{Tw1^K5CtoHFf&qLI4+Iwym>T|JT>2Y2b9Nn{xKbVJPTg5}(4ISo}(clgK4Y3RJN z=>VD+^gtR$Ugy>O0X9B=FdgWT3^@xaXuCn?Z1bq}?P)uDYk0x;IqHs$V*0$8JF$ce z?Nm|fu^HvX#AgHoJN=HjosYSp{2cLB=6et>U7E-3P&g&@we7Yef`gUVE@wREm`Nr(|*P|}4o~@1h zWA!xbNZAemH3UWCR>}4QtP4Izn(s!dp1X0?<&C)wue+3|tyN`JLG7ERXk>kGcUbU@#jarV9TsUqVjAB{*&Veivf&{{Dil2)h6fmoJjrh*Th z_QrCqbU5Wd{pA|)Na>9o!gq}ZCX&MPpI*q`4M>WVHLX2+*lAE89Cp)|?NM8|iBu{5 zC`XudgHP8{G?j`@`t&AkND4C`F}KzV)j5B(VJ;}ogRC0{V#dB7beYTVyP8`;W#90d zdMpXSonc8D4hlXltxj_9Wbw_pEkHO(0aY`fIZ4<{eiC> zL`O?+5|(50oAkyAoY!E{fFw#s{?kQjVB?harj&lWy)jpx47$JDLu1at7#( z40S`DX6&?SNV+K3^w=q-w`sxab~@3tE#s5_n{rohGEH|As?H^vG<$M1#j=gFgxJnl zPwe7oU>@W<^O#CCz#bWx*kZuI#I9}zCi05YTxE4|9DV5&BoTSi?^m}Ki)i^aHQS2) zD;>~-;_vkNsV5Y0BBs_2*U+|tiH7_UQm{8qI!nD3oV=1>PNaPsHiTpr!`M0NpZ@lWL7f3f_qg<9 z#!Zu|;OxwciS+E|RdVNtlGKvpQN1HCCfd3o=I~C+$^y}8oVOu0&;X}l*pRLzS z0o8doc;^qy0y%PGBmO+7ijjCOCpA=%q)d*Sm<(}1u`i?pij8Zt4q0a?J!Lc?iMwV% z4$uGXH_Xnb^J@E~y3AvH&$BCcbyx*ZLr^U08<_YaIKA&0EKY}V`pMz0K|27Nub}L+ zINFbQKEI$Mqk^F61)Z_AYWs|o=hUT(!o`vvhqN!)10XNx_=Xa?9a6ZsWXpz%K!+d6 z3Th!#Hda$lVnO5c+ur)FJqFDSsy0+$nrW36@qpGdz3n1a5@t4{*E^iHT#s%Z`BSNk zKa~oeN`{zNK`>l#!6BrEpx8aW)ogM{ayckhnOAvCG#Kky@rsaN&x*aB(%)Xkmtb|( zCaz{)Ow2PFcaFx%e|&`GE!}c$-zM_x zHSIFhu@a&MLrzQp=BYc%`w|r@o%t2!_;`Wa+oUV7`-WrM@~L!jy-Dfwg31rWNtfRw zT{a=8OP7jw-8Dh$jc=bRS7&@XzTh-&_jShu1P49hcY!By1-h&)7w#G9A)u@@rp`C##R|lB+ zo!{|bHZUopYIEk$Q@)a*Gz*cQ)2$zl z6|cv6%2Dg&21k9mLx+m+xJ~H}9h%HZS5IS`)QAd<$pOV_-uWb3Ydc5bSeA1oOp2S* z-3o+BW}iMus-{&vKJg4l3LNrjp+isFAQDS+OAifCg>To`i);`sVm{b>{%GEiv1(vq zyYF;TU9A@Byqj-J_5wDEC4&)OIwa9+6P$OMUI2k&E;xVYO*hT?1?6AcVUwzW2o>8h ztu>FT@pqvA`G-C-!yC~YoOLZYFeUwrTcY9tkj>&YOj=Y2la6Tv6SKGuCLJmcCLPia zChd`@wE@F5TJ=mb5&yaMXE2(itZ42va zeob*agQHX%zAtfn9}iS@eBXg7NXPdbJB6vny0%aSlr^tcEmDEJS^8WRCKYoWOv>*$ zm=vNom=yUMm}sUBChd`>qIlhPP&E$}ZhaOi&a^Xp-!vi3An&G>9~tjZ1xglWNlFgY zIHTr?bv5hzCaDZ4mGk*p)W^9QB}LNLY5g7QnqbJPb}lHZ0jne$c&S7GJs12<`%7*0 z5$DqZRTA;>W;vjEnKnT6=zYATn%HsyDA$S80rhm?!@zVVQRg(ihD|>*ZJ_j4#sS?( zPfPwt(L*7yen(P#a+e2{@1s1j1B#Un2NW&J0mT5_0;Pz`0mUMp1B!K12NZL@4k*qV zcR;buWr0$L$^kuyT5Nz$NQulxDB@hvA?<*^5I!G8C>H4W7*)YE#;9o*-6C`dCY;Yl z4vGVc?G`Q2@d3J;9gvH5B*i8|7AU5X4VB`y$_6Mmv2;KwkL0W=7G^9^B6wJ!RO?Jr z+H^ZtssHii%mO9H=YZm5FbDKN>Y>it+$~z|ZZFs<@dL(h)QmMWV@+oyq&T2*eZ%#1 z#=#Vhq)ZFXtJI8b)g4J!y74)n*eTNjy~3jKO@t#U^Wu%&$G$y|r1*B&0=;6R@I|sC z>2ZONS}=!VNP2=EpI516x?rQ0`2ruc;G1k`O~=14o78gU0w1+tw#WJWa>Yh*+Z97k z@x8b6`P&s6wOwIR$dxv-JKs?v${aBvD~#kY{gny$!h zwLTxya`}zY$#=n;s)g71jhe{sJ8SwvjCiP0#+qJ{>sznL^{t%iGd>?%*Et)7^ghQ- z7qqB+vTJ=I?~PWe@xw=zk>=^6#^>X#P-mm?WxbW|JeHc3w%_; zoV4-z<%UsTUQg9@aeRDQCbX#hfl@Gg?yTu_fsfKF!3)+DA8{MXUog+_tSL69cR-QV z>3lx6$h1H&@KFW3OgL-0Uci|sD_WFc`&c`1J|8EZTA&yBC>}ND=qXltoX@XU_$cH_ zJD-o^mn={!96D>N!8yZ&-ok_34Ku}ucg~vP=u>A+cZ~XsSn9YS*H`$3tg%s8<1^N@ z-Z1LRuW7}X2Zl;jY+jy!BcWb$bo4o(`0~I3t+Y`ND0U=uK(WkWfT}MHoTm;bCS@H^ z%=I~-m_l+uF*9L+?k6t1*;Ye(%87%njLPATG$aQULum&T`+_*2m7a1spgheo?@x9l z_c)SbG~s~acy!*U`ewSQ*`GG|VRhdDB?pziL`qV!Q3v#b*HL=EOS*4KifL|Rqb_(ICF=3`*HMe! zg$}Rr2$Z~@vr)`LFg9u%-w;MEE9n;Dd_FcWa6p+dV5}*=4IQl;zE4hqV$UMf{nVM7m|XW3xWy7(c^uT z8gVO99<8UCKFil5mg$0;xj;$z*KGgqX_@fViP2wfQ8OSorPrF5b>>``fx2MBN}~fg*g=VB}od~*On#Vy^n?4BkjCg0m*u()vpP%2U4M`1-poOl_4k&gknI>HY zlA*p{Fu{Rhh`QhC{*WIBt?qBwV8Rg)en zO`ETA;Ex40QinS>SXj5bNgX@I=1Q)nGac)6Q0`a_&9e5t&dBJT_9-uH#q_ZTzovz) zIOMUpvYZL5x}Je%Ej4`xtQ+Rgj11DcArEC*=k#vrB_9P=Q@N#eOYd2*DyO_icEeOY zr9!`92&Lj#kRI?WVlPg1HX^pNVJ2B!qtY$V6$g_qP{+V6yInFb-mbKLX^trAma(#R z*SO!uUM4?7cd7^Wop5C3p-Op$mA;abX_SE630vj3;D(V0)$C8&s{H3~HzbfblJbc2 z^qOvM_$O#;`efZS{EF1y0j2w8tKR2SN|KVEI-o1nQY=s+COM!up))(=ecEn?_Q}Dd z>a2rF;kAQFIUomj!K8ea_3>1PcR=wjVthSzDsnKd2pv_2 z9UqS(2f_Gy%;Yq-`zRme&U#_{c$@NH&-2k8%nL$C4a%nL%tnY)}Co(bU{h`p`!(QffvCRZ~0vkqh!2+s@V;s z+l>`fyOZH}CiQk4kI79G@@{#VD0FmIR2i+&w@}fB$79YHgpLdMxH7g02P7C4iq9$x zOm3THd_2CPc63y%*Wo&f<`tnMJ{d4{lm`muzkXGN)Y0dtdinsS_3;;^u~)o{7%QqtrNdWLeX<^7 zIxEUO;__B6LJfpu#)`f?T6#nxbTBUn9anDdVXP?LMU1as$cs3b7cd}JY((KGKHf!) zug7=D4kl$Ct&gV!gae9?`;D*1H$o03WgV@LzaWjh)(gA{jukOhv{Kg5Sy7y+yh_T<^`-TF(4oscUBZ%pcr3|Z_EwMD_CCzSzpeI;tLe#>&c54m{+jA z$`vnA)Vl=~-}!p-A_nFatS?cN#^+x&h#G3v&exL{F)*)SeHCPVIaXiBm+pA9wXvdC zu)aij0|Rwd6knhiU$0Irk5g|BCM8{+k4M&*1$u!O*~gde$`!1yvR{yYQL8dgd_$j( z@kv)T)de{nb>g8k`2=af7by7^)$r}%-mYH3`ck99@s)v!FHnpXoyI?2u2-j;>J)mLPFIiPqKF;-Nhx8W;#1?#KzI(#gsv!ZwxF;-M1vB!cs zm=}bO3P&$ce7uVoUyqGh9n1?#cNJM*j*jA8#Q1s~6X{@H5IX8n3mB8LqWA*E`1*~! zh=X}S>8>K{%UMypix^+O69L4*ydrc&)|a!Qco#9g{va>nU|tY9D*rIvGpPaT@cWHA za9)5(Sw};iHe`KSphP3g>(izV+@qtX?F!bHe8_muq`@wr_{NIPYSznHh z;$6h}`h~oRgGpIO=i`y}Wr2?OBAZ4!47d9Ag3wV3XE0D_MezlSp-+Xph=WPBE9c{p z^<{xx;6-penz5o+u)g$c9gN9YQJgekeEmjV#K6SSFwV#C6gpa<7kH7Kyoj-)2i2~e zk3T4Mv_LQLA_sYq{EA9N#~Y|BjN?6%2Eh!!-|RQ?BF2hNRJ$_NX}{tH%8qvt=j(|_ zXJEd}w|Vpc#aU6DTWNug_aZw^RWVj{xgd1h7fL`lD~c~rjIY-VxzQ2+u2Fc8F`bWJ zDRi_zFYqEbPRrP(azW@QO34MD2`3;MUth_KIG7iNj{6laPt{+pIG7iNj;aHLfjTRS zcM;?37xE$w<^`dnX1hXC!&y+4V0AC0;LP)yy!^Jii$l*vT?RP|DXuNk#t4_$V)ooJ;TAIyRd^v9`L29 zXL9dXZPe)VUxT-BgrOsA#nC>_nNl}OF*v9k3R|d^vQ`f2j!pk9)I!w{3l&-X4(hQ` zD%5a+2lkLKy!A982h&&pje{n|a%5Gi3DP3@Wt~=J&^Vwo9oWwISL_|+>{Z43rz5Kl zWQbUeW!wulnWN@ zlC{;f9v9rI){Q%22wr;sII3tBg11EU6`S zRDn{I>PU*UYGeO3WmB3s*!78AIs7uY9{5zv`Fw0p?rap+ejQ1%b3`6gGquNWR8cSm z7L{L94K|`c+WGt$Bh>UUElJ6uoX^KM^v>t2jPls_9Z4_nQkp<@#YSn6!1&Lv;{$XJ z%erEtc%Gf1{QDIfg##ZPJv}biC=nXQThxSo{|(!3w5Q?9ulg}q)SPBhmkFsE#_o&s z1RLe7DQ6M$7B%72C`VFk_Tj84zF2c4MHZC>IzEY1rj3$F&YFr!`q)gJ&&O8S7U=jZ zZ<#QCYOJZa^lEFeV7Ny)l45vnfzpN70;O!9v-=pHJCfqq6AKg{yyV@< zyiiHXS<{s^%K3b59%Xz!zWH+`trSc+Ys$4l>&5jI7k?8EKDZVIoJ|8(A zhNKHl7ceAUkT~Li;wS*;^KsahBPp`n9Z9jBfFmi+-Zj$aMNe|*&XeYN36xHhboD@( zbT@S{sUYPn>56w#3-yX;14Vf`9m9_@{f?|^#t2H~pz@$c3w0%qn}v$=dK^?a>I-&j z!?x=$+{zq#s_fWvU(Z*wET^K^ey{?@^PzI!j9+87H0zWuYWbHF>Z3p^kUj=mZw6RY z2a^sK2a|I11}65DaxgF0BYcTrsVGiIa8Re2aw!&SMNUSZidZK+sPmy(oeqkBEKss2 z1GM!eA^)E}q(yM1^Tas#W_*xrcq#FBDMjU=F33u7P}NTj_R2vm=usVGEe9oj9n`AF zh@`D)N~#_t)4}4%y3JHhuuwNj{X3|dLNPvGulp6viK?kmFZJjp_@dO)iWYzWhg56R#T)DbOnVaclOnUCxzE3x-FXj7l?0U{KehEZXqSM9L zu3eWGxD8vVIH1Hry@FD`FG#6&WK{z93WXI_84g%S*b{SN4Kvt~25Cg_`;Kk3oE6w* zw2#jhN7mzlCd2cgj+Nt0_PAZpWLUCdli_?opf1bg42;<2Sa8aOp;*UqMZ-3|tss)6 zv8)Ae+|B}2q;6WMSKQ-|iuZWqrLHW1?iv>AO8Jp=Zs6Ef3NZ{!_RHQ*S+3g<+XJ?Z-%1?_p$S2h46*1W8X-qz5yCB3Wy#Rl_57lqWFMWEQE zpn1nED7IB{K+#KCphUDgq{`XPmjOK1RAWguI-t`P3~fH<+AUBzQY=u~CkGUpzZx2) zBLxmW!%7zn(l-V1Nj25L3P>z8HO_+Klk&Xo>rM?zYHa?(b7YMr9naepaS?gDj+!FP zD9zoIr0Am4t&{}1Q%=eGd?c>6<2I@LE7C#px-WAYulp5*Zfz#NhWBgfK@hPEU_nOEFN}7L1 zv8W>rEve!2#Pk7;GB#gY3c;=gN|evMMr~@u|2W=rb|1+o4rrxvk&!gqkmuz{iqr<< zG~JMjV@SH+D7~52sQorxOBF~=VPhNh)j2+ zb{UbWUgpAKY9t~>orc|a>^SJMM4Wez62?r<4EH=AO_E0epCPH@h~cKc+$a&5-+S(jYG|omRl*syrYY+>pT}Qw z7rf>gr@lHE!qz*W3+;WL$uKR*F?A%xo;VIDc1CkRaip*XN_QOx6sMmXmX9rF986Mu z2a{?~hR0u!wQKB>W~+=h{1t22#^>v00X%)PK*^6fYl;+G3zV*p1~q6}@ga4d8Z@aR z9t0md6K9t;3d@b_Q^6S^hIcMI z(Ls%U!hr?OK3z~DR=$`5Q^PmciOOWg0bS?ue3PkSk<^hC3C4y&RV?h>ayhcD2#tMvXZsWoV&d1w#}JEL0>P7^w3NdDa#xULze;mEa*YVWA?G&q6)O2RNwnO1CKs z6;p@~>M~O%#X{9l_}I5Ps4HH5EmSO?Ij98(YFnr)4H&afcZ#kYRK2i;_{u`nW3%y^ zwM`UaIkIkevvyE*x4gi%_LZ(emaNAGQO0~MbQ5-DJ@DzifvVnbR8p`|_0oK}6{z_c zJr;0eRT>nM)fOt&f6}*tWje^R@@aJyz3Ir#3p(SIOGi)~EMN$V6i-J`3|S08kv8fG zilcxWP<+T}e0`yiJ)Z_#W~O+i>AlO0&1D=(@#Hs_6e*t0-tQEw8-ilxE6+vMm>P=z z^MbavhmU=pv7(ELzK=l-LGha62#QTa4MB1IS3U>0EZA7b5Og7R%G1#n1(9%*Fa*U8 zs*W*XQq2%lt-l`Yy|eXrlXeuJd!1%e%FBWi>KsAwwWYC5*pt=KC#1{nb4k1AqH8JG zlLK2TN^4vn>UP0Anx$@6lojfJMOmTlSXMA7RN^{OBE>;f76H7pg^JG`EL3hyou10n z`aM&k+L9H!Gw07i)f9&NRbf&Ki+ljEX(AJ7RrcY!_Z|atBiNm>8I^4_*yP~KArN#(tK zQeMMhFWCKpwYa?QD}g*-P5HH)A?QRGy~Efi<+$KVzPEcz^5om)^&i`Qi{7%JJV782 zs!`_pOOGyl`JoJ(He$R^9WzC|#v#RQbm#L69nuacK5=nA9~%}rpvY^@f4+i9%JAkT z-8CHdk*^v}S2N{xzbUj{AXM8Q}NQ%9tn#JV;G!=KK zYT!tU19==tv0~;(ij^osPZjhH4<&bvqZ%IcsyzxNCX6)|t?vR!v1sH-iv4Ph-CwYa zk0U7$Wy$+}We-75jnCJ_?cur8T`k%{Qe#b5y7uI5JJ zU@v$#w@@oFh02k4sH$<0sv4*o#|CHW3zIzQ{N+?Y)=4~_Y)o-X*f2sYwKS?C6PjCUDbswXASX366rrPQ$nkz373k+Ci<@8P!6?5~72uT0b~K z3$;?b?x5<-g58>K+m=)E&ckY3!;F7ZhNs$9Y=V3%Vn(H|~y{&i^-1 z)`9%zPjnDElHw%EIeQH1^D%C7B*nK#j-(eHSNi@7jw>~|!Q;wU)fMx~#;UH!cd|e! z4di_OiKioJLtT01X*LMZ?iUO#@+azwuhHhbPg$`S+jKOVQPQXEmS&Qz~@F#`$9HAwX7CWaL|*bQj3p1lreAg3S>W`(|076k8i#uMzSPsu_E~ zQQF4(dZNAR+Y=KgG&G~xbWjcalvj7W}GM2{IC|;s1P~y=TUym1aOVA74sGf9=KlShi>3lsFXf053qsHE2zS|KL zD|8kpxl!Zmk(yx%dW9Rs+ooFy7fzoZ%`Fe^U9YHrLb6B8w8&xGNnTgnN zprj)y65T9NQd48|cPjT=g3|eHfs&dUUw>S2%@GrSc+NybpYaYKC!!eJBziklqx13e zuIkR?CC%^sj_(Amuc!0b0ma9M#@A05oX5fmH1S)k-bov)|((Gv6uH;T7WTVT0mNm_*I$r^Ic^uYQO$dW%Y*Ut6UC2)lFC9aP$;~O8efl3_?)jt-mV2o zw^8ToDSmVWMS`gXO1Dwt>v7a?{xQI+u8*{)2CC*#Qo7JWtz`QSsvbMQ8Ev7eZPDY) zvxSO&-$7L}3X;1PD#oV{>Vk)rg^Kqm2X#fKYN6tN-$KRU&p|Dim$Fdtl9F$UrT4*@ z@^EC`uo~l_wl~s`PZxEa&elxl9XmKVm~``XFzK3RV7|P4ebj8m!K7VsFzK4&V3J?W zKZluj3@jW_rf#RH0-E+g=?P0xy7xMu*a6l8rAXZZB@;D3Ph8RSyMG|l*pU=#yA~)F z4J}ZLejQK@|1D6;pIe~ho*Yo@iDQ9MD#-%HRKHkp0QC_l5##D2Yy(f7X%Z>PT5&U(*1&9;uzomdYupKhvj@e^7-5g9%Mcrc0#r`SbW-LXwUTCN$ic zGU?9eFXMv=Njg555K)dOvd-tPrIN-M60VB|RRD#;LdAJ+7AlT;w@}$$jomu9#bzE=&FU~xcTn+Fu(7VK zbMJWDQa@aDgT@L>+_%C(<(>czDrdhORDR3qpz75G1T6;Yj6~c^! zZgWs~ytEmp3fxsOd=zCkyR~Ql<^`xL^7Nb)z_Pcs0{aC~hFT5d-Njgem0x)|sQiM) zLB)>y&TgF;v1iCykO1V!T9~ou$jbM32X(t5$|zzMk3U`Ngqb#D1=JDof|F2PD1ct* zXja9kD;DZ;MU=5kn7}r6Yg@2-<)9WUT|1~;YI0DIE2513Wn#hTC__CLFR(3T9WJn~ zo!es?yR{!zL>U_Da6wFXa35P^1&)I0Oa~R)ZaXKTvJT_@R=IIA_xuVd8n_^rQIvHU zZ(Dj)O;LuEDJ{G1oR7l{gS%VyN*68%RrBT{onxUE3|@|+BRH3WuFHA}teyjdJ22Lu zZW}s8V+}Ml=Mva*1&e(vSFqT(iY#_xzvO0#&g-BmGA7;H(uSZWWu&n!z{y$Hwqd8L zG(}vPq^*XaJJLm3h@bp=?pEZ0zNpNj@YN7>rkbH6DCPz%Pzo}g&BxB1#*$(V!x6Mn z6yPi=&f#@H@rq$ADfUrx1jS6Y1A4&_vUNMKd9dS64!m9%sQV2IS{5n>Dkbmv_6f_n z>Cu_%KB+Ur6r;3G&6jTcp$!!km zu4(L#&s7T*%OVb{n$BFXTWuEW@D-3-r5M;)0nH4$AQRRSVQ>-}Z{rV*ScBb4`xjy2 zr8;~46($ug966~R;9$}&8JI}Fb1*6V%QJfwQBsP^0>wgz>>?Me922Hg9ZB&{Wr5Pc z=YWbC^Y}EiK*>ZM&_cf70&Vy3M`eX|JD`+Ec0OO_gz+22g%9KN zG4tVkJ~jlhKq)@6Kq)|VK$&1;Y}CuB+QGIj2MrZfPeg$os1J3FY$LKWsI|8}8F8@G=$U}vs}8*3o88Ttc9*ut;d9a#2W&Kj_vnHM?D zoY}U9f8c2iS=FG6e4>LY{svfWmK#tOaV;n&Xdzy5RYf$p0+nay7#c9Y1QL%@+WA%0 zyk+|SbU?7^6o3M${@E?PS9-w&`5ftLdI{9z0}Ibv+FaM^HoT}&Rs}C$SCb>^N{pj) z2414d%fj{85p~ByAg!+J#F3^Us*(4Rc(Jst@5I( z@#_UPX5R4-HAz3*737GLa$a_<0{?E%-ph*(h$lVSGMb zEG$Vci2n+g^Ni2uCQJ?}U96oo#a;szDBY`!>yNrkXw4qpD)VOKc+n$0Jz8!~zF2j7MX3I`K+$@q41dXAh_u`@9B!f^P$WA(?86S-#j$YjF{lp`o* zkQ_|Pb>=Zuq@?3Mt@Jx~ws+*Dl&ph^XT9<5Sez^d==f7)$2QK!f{w48sQ(FuxcT)I zkzn*`$1S>E$c(wVnaZ&wsfCJzjf}llqr%5)+FsjdKOe(p<9fGq!c$YTS_Txn)d%X9Cpx6Z1!Mxxc#i2WSIn|nCcr>Ot*s-- zDdQM9u<~qt{4_oqYuz(O8>bQv;}vvxGZJOShc_c>m~?^~j_wdsTkb_v^N7=kkE+Bly$gQ@c?88jD2pO1^b;<`ivd`fGM03`DRs}Ko+=g3J~@5FgC(}s;WZ^kJQ#`hy{);LL*8=a&^ z0HH^|ki&0UoHYAoJWWF{JBF7Rg-I!VBhJ$cS1HWcJL7_PMn|7!I-DKQW&8=XV86cA z&{3RxnP;NvrO^23Q7zgbuQBcU6KcUL&PzHaY501A2(soSU9m^~i*aNn6-Dc@l{%

@CnqM*fmft3gq93kK z6+=fy&ha5$MTV9mC%I1pbEOc^!5n{Gt~e~pk(0eles%^PQZ#bynLpg7sV5|l1Bj-a&lj-XrnOJh@H727Raf)0OsQPdqBbkx`-4DcMx z3j&9o>UNHt7X%JFogW*bw3zb{xoid?VWDD{)IptZnA&Pr!CcOy&MVz>Em<+S<)Eqwygu+z z+-srYixdZS#SxJfDh{7>P(^_q?+2^MfEVmmIWQe*SOI5{oOP{SBsFB!EfX30tZz;X9biMBh50-EN;l+tiXYT zNR1WHJ8jIk6#p^XgLuHLv8tU%RkAy|QQ z__`}Y0;1|+L0SbWzH8d`oGb}jZz90J3hXazyOhG}Rv zB3CWHumYt^j0H-ucKRK^J|C0Mj-+@FTA<_#ozF+_;^{1?c;c z7huWC)!Y2tUn5R1`H|0ktzwBnq~hp+hG(E{F+`+~f_)_MGpaOJM> z&4jhCD?X3S>uX)l_^tFgP-`J)V8~j}#94V+ckF^<$hvcp!8l)Axl=y$QBpiFt3W9$ z=;-S<H)r>;KeHpLW|)n30J}I*;8+bwH8}!6jWsPdVnsNT zUT_)Q^%4!7sv{}B@N?F5rnu6PbZLo+vBB!jttA~vu??iNrYq$_97*+Pa{QWNxy_Lj z`|mhwiuE=}Qe-bVl49c0k`yard2d><+~`QU)1A`DvhUo%&d7)FdV)&PR6fVNS9GY3 ztO}>Vr6`Qc7Kitp`%&a`%=?aabw>wuQH2xGLalUI8@ttJYr}43Dg3oz!uRLt%ZJDT zAn2Zb!XQa!Jgw5@yY}h~K0jS#66W|zia_a-lJ_bqic=cgQqwbus_db1Xude?lq0Kh z6riaVDvmgFQ1wJ@ijR$)-BR}) zu&sO}hI)v}2evic@+Wpdf}pdm1>0sg>#FMoSga$fQj35(ZTf{Aqwm;|dS6?tm_*$d z3fx;lI}2JUwVscI)QtreH6IA<*ofA_#KfAho)lXwX$sS^V{Os+cqA}6nB=J(OwxJ- zbEC7w!6eV;V3IF!FfWLxcTD>`g3@iuz*N79$2mF&lLCJSlL$}_CY|&SCS4>POiIl= zm{jX^FsayYcuvgCbiVw)Lo}^(C`O3khu*_LeX7px*QhhxRnJ~^$6^aHs{OvYj*ZTZ6>G3GY z>3sZz$8*-@>FZ}w()_6>f*j;qjTL=q=K08rI&xBO)WM`HPCA0pCSi4OX@PL^$k(_A z*d{~N8Lv6{HJzvNIyz6JqmGNGL&U)xe=ci_Apc;vk!jDzI5S>C)IT`w=J}z0I`OC*7`pkF%w#emS@A9KJZH0nk`-?v#sXaMUPVm@ zF(S(wmHJ}nFFjIK2Xp*kT88KGwVs&AH@+R8|2UZA57UBAG>t20!P}x^O4ts@SW$dX zp=0cAwqi3zLr2x;6Zmt+$76cL!5p6t*9hq0hZA>nGhAJLdG_*1 zn;cu(#vjcZc{==PuGn|jz=&B!^_omAA>d8CgSUyswo9nA5;SRGElZp{YA z2Vw$GhX34NI*2?prhFAlH$_lVqX?$HEf;LmcE#@FbVMU>zwMM3)zshgrGCe0 zruj$U3Z51`q4P)denCj8XT`&VGCeCEer?cnEYN*tJ;zrS)m<43-;fg{d zArzWZJ}MO`)q^Zh+WslOs*@T&!||L}Dq#+HBf=yrO~+-zq;z{e)}5w_1U2?v+$1aRo4Xm_PGf1|>y5j}f`ejOk|LMc(fx+5clmnw zwBqZFdCE)5Z)}av$C;6iq}a|jpV-sK(*@6w6x$OS%FpkvjD6Bbo5#nAVNffUN1P=s zlq$@hQMxmOD{;07X~~YDq@>2Zaouq5=lo@SJ;;$7cRao0qm4=@-zUA}180)|dUX;4 z%)E_ix-}&Y^lv8pQ^Az3q56e~(eHWXFW5=R*e9&E<_ly~!6V8zObgZrEl>*hj3vDw z+ASFEI$DaUEkj4g(=;_Fo-R6$j$RR#>zxCfdW|BOJ)v;kQoFAwK`Xx9Hp22ck#{ye zzhcoT?@21Yw>5mTy2pWUb_As$!oj55xKV1aI18g1l2%$#M@eyhU7ly6;yh)a4d+xZ zNb72N)p#X6D1J7!9_PU1d4*H!ANTl@cjN;|o>pQU&l~ptF*IL_58i3ZJCY4A&W7QO z|2jNjxas-K86)1<1vRnBhYPxat8VLBh!ZTGH2)UQHr6XJ6;?O6BV79bTqF} zs*Da-Qq8~|uB1D*cr*eip3r0*dYb+Y4$tt+d!abr2%&Z){X1HUW9l7HEEG7PIQ-qP zd>-LoNP6Hy0z*%k0qcO`Oi?3>Im5jk${)}Nwn%qAetbg|5fms{Y8+7q z-<^ylMV5`Dq}X&J@1VrfrDH#Tnh2C)v%G_v)q@#)z6DCj()8v_(BX9gVUp?_a$IxVrkhN0J)mG|gnA`6U%043^ZvBsXGUF5}-et2;hcbJCNuw|TrvlH}3(Y?zZsu%P+I*W()^2Xnk1neozWSiPn$Km=ukdNXn&Cgaeb zu|Sr;InFckwv5d`Fjt&5QB8Azeag$ZV1dlo`vtFf#x5;5V98Oa1@BJAnj!_(!Nfp6 zuTR*n&)It{kma*b^Rkm4aTMwxbFx4wf->BwS|fqsJD_-X%4_M$6|%IJuJ~BqkW*8@ z9>*ny8`TqRh)XO`(kJKCQv?N~=BvZ=iX2c!OYw!T1FCjYkGJ0e#k-S{HPHzTmTz1g zdFqIvs65UiZ>A!eT=4ZcBE&-oQa5~z_hQS)Oc<`^DN-8BK! z*?Vj*>VV=KU&lo8=IDU#bj>kTe;;3b(6__hJ91JH+fh;+sA|L|+cExh*5g4~QR9Hp zSfyFqtrO_HHZg5^O7nHLt2{Os8+)V8%>*&Fo%0QVUowo zCmYa-)Wliu(;$l6)R&(RgJrCnJgw6_6w~))WbwhDyzNC3DskYk7HtnsG9N zgGqJw>2|ftisL?J2NgBSIQ3WDDP!WrQn2o5p&}2|L9G)d zj4f15?K`Nod4D;){+=y-M$hu&=KnoQ!-VUm!z(9O$ zq2g>p2el}vG+qY^Hi~s*t=NOqLPY|mg^G+h2X$NMl3}6ZfJz5-R~Llwnx#f}7ueQ; z1Z-yo4s58CKV79(5M$(vKPsruk!=WCDHw7D#Ve5^C|)KCOCLQd(-?x{b67{v@h?|3vTD3Bl^Z$}V?}WmyR)L$FxC(hTlD0UE9Hg_ zWAoX{qIQhn@eUC;ve$JD#-Kc)VAH9vT~C?7>*p0fTo*d|4EMZmNEdfd^;iJ5OPw3D zyS1xZI-tHZY|W)?_Vz!I&(u=VO(zJKb{CvGaM<21B@~8hX;gqfX(RXN0FPx{2q}cTCBWwCEKltR`x8FX0_~b|b z{>g8izkYuI?!!0lKl#xoKmYyn*H1tB@n=8z@n8S+=^vgy|Lxb`eD%$5{`mAyfB3^6 zKK(}j@$+}ze*W&)&z~xG`978ur(gWTPo94E_dof; z)AXsjH@^IZ-@N@`Rkwj_}_l` zv%h)z<@4vC{^I?+&%gcjhd=z`FQ0$^{`p(|^2=X;diV9OpMG)wgKxgjpTGI_cb|WF z`nz{ufA__^&p&+kzKQm;ufO=_{qO$txBlW6fA_P$6xjOdP5)OdwAUX_w;xW+$N$OY zueDfO&#%6E_u={1Pyh4zo8LWuc>hQJ&D*EzfBya3@xy8T=db7gd(!v(^7-AbpT79= ztLJZ@zWVZ8?ZYQOdH4SPm+yY_{HfOG_n-X7fBfK+Uw!w*7tini@yq8w=(GRn-~asQ zPktni^Q%98c>dexuYdF5x1aoIQpcK?aa-+&KmX#3mu>y??|k;*{g=Of*6&E~KD>MX zo3`VNu88x0{2+%H{t*XtJEoVBX!k;j^sVx3C))BKQqDhp`kz1h?pxLBOc|cF{fai~ zSqt{npML4&$9W18h*f(W?*Q2fVR_Ce}+m|9b?B0H~>Pewqs~yXv{Ign|)gO!$dPxd>+g3?j zwAy+zzN?kf%Tk~D*+{9^q|~e0{%`Gn)_uCk`r5LpR(R7At9yxV;EcS{PXIq}de4CF_s!oQRs^>cSUshI( zr@7u1y+Bik9nEcRCx((L{SQaVeI(_Uc>AmqZWEVc+Dbc|&-`el$Wzu2YVx%%{0b&? z*6B?~ley{gR^?tapJ3I@cl|^Qt>@mGDz3Bq&OTJ3r>qnFi0fE%jOoBoup!TTY_}H= zqj!a?gw??GGAs4Cjg>m<1k1}Qyej&sT4|+ww5+r8GrCc=_9;5H^^--zgKu@yGkAqa z?a9?p-AKE@GR?KUA=a3VM%;giHctI)sMuK_cv?T!7LQ2r^c7mG%M|ln@ zh*Cw1W_jy)JN2`nYn^q0b#ABevNZ>zv#&~O&9iBLmX51`(eV;kZ!OBxdt_ySZ#qK; zpC4I|_%Z$X@6qUg`>mntoOOwcl;`EP$t$XUR_2#gJ@>PrVrM;~eD}O7pDed64bed? z{ZQCHms_n0tdB!q^syg}6naj(#N#I6^o&$x#oFota^uoyy@J$HsM65VqH5h9)%>Qa zs-tgM6rv0jIqMROZiRB<5_eZicv1hFbKxHil{x1S^-oL4KmG4eF>+3>iE;P8!!Gu7 z&T0Lp2%|3xbJ`8Ptj2ILvTj8Wnbr1DGq(;I+0rJY$p$yEG1M4La$C!bl>gl!DuJLlL+AIVJeICv-&5$81$+MXx6dI3_E*pES~jy?Sl)m6 zyDvX{`LBQe@9#b+8ThO3KD0mn`zL?@^I!hmkN>u116x(-7eD{(XaDfCpZ~p*i^^4f z`Sq{A{Ji~IRp9@cX?w{${_dNWPh4B}>P{p6P|Is8|NHCHkARRFDK_#)Lv zUIl3D#cSRwK(BzM1Jn+u0rl^`0=5k1y;f+4(}3EiSHP_U)DEWswNI~rdk3f;{wU!6 zCVuwK=l}2Xho|4RT>R(ne*g6C=kK5Y@bo{lm&^S0Z%^`^=XbQRL|>&jI%%}suhKMy zJ+Y&~ET_&cTMa#p811q%%sCk5Ng0D-PMu}W!7@)G2Fsi})0~58oY~MtOVH z$GNka#ju$@*v#D7Oe>^k*KrRvGj}$#7&fy9o0&VCQT8J*W3ZXIvzg^Bo4NOT|9|N6 zsu<0FPq^Zs7@b~BK`%}M2EFLiqP?#DsDuMIQCXuqb6mQEvN3)?D#3%Ge-8)c(jAm* zI4I98lG60|GIj@L>t>ObF&vajcTle3pgbvKI4GCyplq-5J}Tq=PAc#e|3s{jZ-4vl zix1}m&ej;|^+a8|6Lk$IYWp%)bJd9N5xWz04JYbJ#9%l}XE|%IoRf(9wY#tGOs8?{ zUKji%VmMKk?nG5_F^?FGYwe7y1mij>V=%6@Gp-Vh>m*_@uC+6+_Sh%Aj={Lr&bU+p z%_9cm66+`2K^y-rDdWqt!&mKDJDX{VkThbjnYFW-_Bj2ci1!D;hv%;whwl0PlL$@k zzx?9M&!2wv&6lSS0##)1O=9hgOi8AXi}3bYuEzucu`@CyxAKU=$kxutO5Vss&%c+k zbVkV4v|kTeh**`Dv8D6w z5IdXM44Y}`ygS6sW?E;5>^in|-W_6RGn-*EEuD9V*x5|$oS&94*i7wgrlmE~h{0yI z&SqL#BaIkrX6tOGr8Uxs!DhD3W?EV!jTmfZ>ujc_HPVQ|X12~|+Ov=>VoT?}YR}f$ zOuONx5rfTaoz1ixZW=Mz%+}dVyWyr0gUxK6&9o{qwU&K+WBGa^Uk5rfU_oy~{_pGOQfvv)Srp4z6rI@rt+Y({;e4V!5R zo7Z(bg3So=Et|Q&n*O;!D$>A*Z@zv|C;bz-FtTu zGj-Nu@Kp3{Axha<&znS*dtdm|ub%(4y^?s+7 zUw!rTi+AroeEWl^&-C>9!_#NKfA_iGNB`ydRBlTX-LGb6l9B$>jES9N%M;y0b|xA5 zFXtdT{!1jlw0BzfCV3Jvnq*|a2r`)DNyuoDkpd&g;Lc7$Mw5&j7(oVqb`ny*cE3HH zNk$UPNyuoDkp-i7Bq5Z%gS=Pv@5d1+ExmO2RgpF$5rPA3e_%as`K5cv&V(ax<|Jga zwn&_jl)(X>gpAe}nKOcH%l%(&`W$3r&P;X$z_ za&4waw$WDw>pTe=tuwN11R1RJBxJPCNVgGWaF{0{qjg5=h2HrE>%4;;xt-BEBUeKr zw0||Lq|rK;&N>aU#!CzCJA;pG4M}NOXUk>XLw3IKO}fSdJ&r64y_}7v5os82Z0E23 z#MpoORSPK22Mdv|p|^|OKOKB#TP;3hTiWY>fx0l(AZ(PD_qvDd!dQc`p?AFzvh$e+ zWuvsr*PWD+v$5&5;=M_nT+3)>k+dPmU}YyEqm@P0h9KK5;J*y_BxLk~k+vbohLVMh zRu*|1f($rWF5FtD3F*q8v zWt;A$?5xKiY1By4P%ETpkOoVmw(QZpl%4e$G>w-r>GzPG^%y*j+OkLYke&4yM2*_A zNB5AO^%zVI^&bk5k*cBQNrv^bY|x#Qk*gs{!+Kga=pM4O9)qk=TQ=w(va=q8t)XUQ z5wf!$gRW5{T|?a-qxBek4YdS`Qg+s35H@NgY)pG+JqBZ=w(QRR_H@=`P&R7I?%YFm z)?;usYRm52L3X4Km6G$3TO@6$m08$vm68p}Xgx=?o|oyM+1pvm+T4G5v>ug`4Jo7b zbes#7lJk&}b1@y!dQ?g_AfxqktP7Qr4agX|9npH!y3>G+*3 z9?h%oKHRXLNW7Rk;)QxlznQ5-&7{B0|RgASXXOT2Dv3P)lp$!=v@Y4k2p&ZCFp_NT@M$_u=hZa~bOz zITGp++CduD6FCxd$B|GKH!o#u5~6V?os@?4w5-kDNz`#9RFyTP)cW5;cGeR)66f@? zWo_;uJL`!YiIb4g_jDWybzU_-JX%l3d6**S;iQz&dSb7TO&xd*DWmV{I1f|gJe-s= z`ks#SpjOj)DI@1WO(LVJN6y1JDI*+WQQ{*t5lv2NTr|KPtq4i5m zA8svca}U{BPvkJ1lrmaR$6=Tvhv6h-w4RQWpus7|hezw_I0;kaB%G8oT2IGG&}0Kc z%4j{Yg@oD(8rBmz33JCum?9_P+=oZ5!Q62TCZjh*ja&n@M2t3Wa1CnY8q7=Qdkn6D zdR_O;L$b8e9XdR*{g)$951hgnZ<-MXrGc8+B3|z9(`G=GYLTjatj^ zc;p()9oInBQv)(aZm}hVq}17$)ytN(x$`}-Cxjpk-xIk8b8HGBNW*#}*IR@xvV*FfXVIw=k7iClv@_J@!X8P*fI26M+X zQ1#UK@EEyuTmw~44agX|bzFlsS}VUjF>*Vi^=Qbd0U7T-9oInB(>!G48fa=^P$E@N z4an$wI<7$*ike=_mbJO_JssCT)l&mf>wga!tw+^U15)dM4;dpjRZk5_t^X_J(s2z` zJvAVM^(-CNV2({5nvx=YL8H>5l=0r9Azy}+!Frai$%Cq=24t`v%}I}{9-BOz`|!v$ zSURqOs;7A=BiBHq6gw#m>xooK?nnwA|QJL@sH2AT{VAUm#sW;q&b z8Lg+|8feD40U52Q;~LBc*I;WeMDDhy;~LBc*I zLUz8#;2LbPUxKDGN9!@T2AaegrR=Q7;2La^Yp`_v5;PAlub17VijHfb>Zt)4t*7G} z%m&wB>toK?nTjUxn9oJwsxCUF~8Y~^xK*K5XJ07_POUE_P1WW@m`ksz!py9g)WVD`+YcLyJ zgRNz4?o_?w8q5aQU~4Z#?jgIZfx$J{TGr+svb*;fTmwxNj*y-2F}MbMC2#N%3ak(Me2JxyEB9=Qff*VjP9 zYz@e0JzZY|4W>3AqxE!LgW2F3XgGFU%g%ZXuE8F;21~~^Q1vwb;gM^wbX)^fPYuYB zb6YyD!EA61_Q*9@I%PscS-_0)ijS%Z#ipz5gs z8Lg+|8mM||Kt}87xCW}88j#U?I9_{7(br&)T!W?K z8q7vtgFSK$mX2$n>S=y^BG+K)xCXP)*Ikr*Fe=%R3&;~Fdm*I0U08< zwd-rJ7+ixrat+pwYoO|>A!W3luCIZrrv_w*+}4h3pz5gs8Lg+|8Y~9aU~gHQ*P`Lt zaSaxOYp_SI!P;>R7K3ZBN3OxzaSaxOYp_SI!P;>R7K3ZBN3OxzaSaxOYp_SI!P@mT zQ1vvgM3HN-c3cBhPYuXuJssCT)l&m9T2IF{SPZVg9{U=s9oJwnxCVRdYp`})165Cr z57+wN8Dz&bSPZVg9=Qf<*VkY%xCVRV8mwJkgT>$)9Fc3Vu90h?>S=l{kH|GxJFbDM zrv_xa_jFtXRZk7bXgwX*K-E(NGFs2tMQ#Sy;D}s$)9Fc3Vc3gwS;2Io}Yp`})165D+N)-DVtR2^2F}Mat}#-gT!Y2n8XU2&!P;>R7K3YW#J&b=$2C|CuE7!e8mt}HK-JSX zl<0nP-k%4W|MvOaub)1D_xq=BKY#!Hho}EB-F~>tPyhCG`*h#R=?QE{Y>TjVR0S1Z z?6i|x-5QX=_)5ogQ0>-$48~VF zrh{s?24t|F(lH%WyUjyJrbFqN4yxT6kimLN$8=Eb)_@GwQ#z)DYPSYtu%6N}9oEQn zXxqvJ-~Rd+PoI5we*Ws|hfmZ0HUIM`Pyg%r-=6;JoA=L8|5IbS zpZ?;PKmEra&eIRo2<-Nk=Y3}V4z1RGLDQ|xFHDg+yl(G)w{ zgbKk1WHiN&Hladr9x~Dnm}HPR-|ZBJ~`P&(Sg8fgcOl+k)R+Qb@Z6DJ{~@9Ah0Yotw_gpAhH z(I(bNn>Y!nU%T6$jy9n}u(3VSdOF&K3c&_sw4RPOp+c|$8Lg+IO{frTKt}87XcH;~ z=OH6)qI9$g6@m@OXgwWmLWN)hGFneZn@}OxfQ;7D(I!*~HXx(*bhHT-f(^)MJsoXA zg+kw4RPOp-QfyMA3RW-oqMs4=1IJ*339!om=yIaeS_pnCZ z!%4_!Jst01jl74GkkNWN-oqMs4<{j`^>i&7*2sG}2^p=Y<2|gA_izp}@*YaZdr&Dh zuj-NaP&(ej8hH;VrHt0owP;u)@8Kk5w4RRlutwg)NyunD9q(a{yoZyJ`n5aj>39z+ z#Twfat*7HXs1$2JM(gQ#4=TkPkkNWN-h)c924u9Jj<}#wY#uTa7fMH5P$|}cjJ~HM zE~pf1Kt}87S~RE>Yd}Wp>4*y|#Tt;&dOG5QO0foHu%6lx7fK{9oHNLlwRttj+7TB@ zBrcqU4AxUS;zEhUg_DrMdTK{pD3Q2u5;9m%?T8B{5*N-vM&d&4hzqKo=65`{Xs8`= zLDf?OGFVUThzlhW7fyb7u%6lx7fK{9oP-S4Q#;~>tDW8^^UkuB5~oQl+k)R z;zEhUg_DrcdOG4liNuAIkkNWN;zEhUg_DrcdOG4liNu9-kdbRpJFbDMr}-U^T!Y$i z4N9JCAW~eko{no!@>~N!M(gRg1|`om5M;ETj%%Rmsj-$?|2ymHxCW}88j#U?I<7&< za}D(2(RwGH9kCAPscSVd9Hz^jMmd}4N9JCAjoJv9oL}bxdwua z*3)qfN}g*V$Y?zs*P!IN27-*%({T+-o@*cyakQR}Yf$oB13`v+Pwlt{CC@bwWVD`+ zYf$oB13^aX>9__Z&ovNaw4RP@Q1V;@K}PH8xCSN9H4tR9o{no!@>~N!M(gRg1|`om z5M;ETj%!fzTmwNy>*=@##o!uDk!w)977ePNrjOt$at&(7H7EwxV2a})YR5Gw2G?MU z;~;9sH7EwxV2a})YR5Gw2G?MUEgEXaH7EwxV2UjoYR5Gw2G?MUEgEXaH7EwxV2Ujo zYR5Gw2G?MU;~;9sH7EwxV2WIW+Hnn3J@P&=+cF}Ma(u|3gxIG%|k}6LG8E(s-7BYS0gKIFwaS&U_HK+#HV2a})wvKC14X(k|vNo?yck8$Y)!-UT zk!!GZTmw~4^E)2723yB9Q1#S+4A!%CT!U(G4W^d0xnIjTg0&i4gDEyi*gCF3HMj;- z90##=T!U(G4W>8_V(YjD)!-UTaU8_faSf`$HJIW!h^^xqRD)|U#c>c@$2F)1*I$nE0o*IzRdOEH_HMj;-%PscS-_0)ijkz2<#Q1#S+4ELU`;~J=XYCuNc({T+{JvAV;{&()I z;~J=XYCwjp!PapNR6R8yL)KvHxCW}8z5#jPi|V`I|Ni;?)32Vt`tbDmSMPrJ`?H;< z)QBuzkvdv}3a$75dedio;5kQH!q(9eRA@CILxN%JXbCE`8j#V@I$DAXtp;Q?w2qdb zLaPB84XvXk)JRJ>xjoU)I$DAXt%j7*&^lUz3atiYG_;PEphBww84azYC8*G9Kt}87 zXbCE`<{=|3Ve4oKDzqAq(Rw;sf(oq$WVD`+mY_nb0U52Qqa~=&YCuNo>1YWmv>K4n zdOBKy3atiYw4RQZphBww8Lg+IC8*G9Kt}87XbCE`8j#U?I$DAXt$D~uOV~PEf(oq$ zWVD`+mY_nb0U52Qqb1ZxOKAA)bR#Wc>u3oz(h^QWM(gQl2{qCZPC`cO>1YWx(h^QW z>eudqypEPoBQ4=1WVD`+mY_nbvE$KtI$DAXtp;SYo{pBFLTer}(h|0gmY_nb0U52Q zqa~=&YCuNo>1YWmv>K4n_jI%b62^p=Yqb1ZxOE?D^X$f0LOHiRTzdezbuywSA8fgh9 zrHt0o(GqH;C7gte*3;1vYNREcgpAhH(GqH;C7gte*3;1vRA@D}NB{Dj@9Ag>DzqAq z(f4$;1Ql8h$Y?zsEkT7=12S4qM@vwlH4hnS30p@?P@(k=$on)1j%zwUp5mo_-Rs^4 zQkjm$aC)~rp$JX0VT1m~%A`)kpnfM2gZjn7q!5GlokR@U7weKj49a&BF(_XwOA0aQ z-buuud$B4h#GrcT5Mxy`7A1ukH18y0h~)`s7C^5%p`Y>KIFs zLJTp_NyKn!$BLv7L&$RyF&x^lASpz{W@14y)+6Qi4V#Je$XJdPqG2u@V^zkwP?VCKe)N9a4yf z&BQunEJF(MEt|RbdK!s)+kUKnc%ZF#PD>5U~XlS*OO=K$bF(K-79!oQ*wnGUl9(ott0n|u4F)l(`@U= zeOn~=os=>hXIn?^6J5!WGQkTO`$-jVx6S27@@^~4Z*+hPcP^24L`#28wThV?{p-yVZ#K^oQ*$$fi_q6KMK zPbBy4F^m@E|Ht0j^;mKp*S3G9(0;fwK*^Q4Gk50Z8!5}SfMZD@4WA4702fWNBsJXZ zCYnvzhH?J;omr&1a*V@bMMl#{wy|Ff(DfxzLgv4 zNH*NVLP9Hd(vjT0n|J%Q+DAmVZ{=1xk`4C|?pwK+j%33<+)JzizS^`wxNjBQw-D|tO6JdYJ2%07!Ih4C zoN(VNxG%U;Ly|i;!F>zizS@Hm?pp=-g+V$#O2U1s;Jz?O4N30Y1oth3`-%^q-+%wc zc`aih+*g$3&P{ONLb$Ie$(@_vzJ+jKQIczq;J$@$Ur{oDw)-sw_br6`ijq9{2<}@5 z_Z21S9ua#BiM^8KiNxM2VlNER;ZOa=j2z_lVeA zNbD6Q=^hb#3yHm=Wd3aD9ua#v@il%+x<|xbw!sZax<|y`LSnD>;3W1|5qn{fj*pUs zgjNxI3yHnrDCr&%dkcxZq9olTVs9a_SCpiCMC>gj_KK2pkBGg6#9mR7?h&!Kkk~6q z=FfKS5wRBrsqqofJtFoN5_`o_(mf*f77}|kNfLXjh`lgK#~+-9gjNxIVUQYgj_KK2pkBGg6#9mP{f3|avh`oixUQv?n z5wW+B*egoXJtFoN5_>gC5__wNy)a0}KXnp&tBAd1PaBeSkBGfwPaBeSkBGfwPaBeS zkBGfwPaBeSkBGfwPaBeSkBGfwPaBf?{devWv6t*=Lz3e>}f+1?zxCHNcOZL z3HMyY8YFw#kc4{zF9Baj_Ou}h_guspBzxMBqDe8g8=T5Y`BN4 zK?rwAHrzwjAc(sp8}1=%5XN1S4fl{W2;?rwhI_~wgmRZ;!#!jTg1J+&!5W;%8iaF~ zWWzlyBoxqHl8v>8tU*Y3NjBWWLP9~^CE0KfS%a|dl5Dt#tU+LRNjBWWrbVIMCE0Kf zn-&Fkmt?~|Y+4lFU6Kv=uxZgntijq~4Nh!YbP;Q?Hduobn-*Qf8mtZ0;KZgy7qJFw zgEcs@I?zR|!P;OACb9+>u?ESW9$v>MvIZBi2Fac_B)M}FYp^z0gNaRxE@BPV25T^} zY0*Wj!P;OACN?d)h&5Ontii;lMHjIKYlAgNC&zuv?IPA-ZLkJuZ%0Y3Jq^|%J-;Za zwWq-vOk@o%Vhxf#J^rbaHMod1NcOZLN%x2~SR1Ut#HK|Tu?A~{HJI46=pxo&ZLkIt zn-*Qf8mtZ0U}Dpvi&%rT!5U0#T67U>ur^qOiA{?xVhz>?Ymm}(aF1AnwZR%pWDPE2 z4U#=Q{;88SxQI1K_Ou~M_lPxE8?3>^>OdE<25W;gn6{|RL)zma)?jV02DujqNwEfN zgEg48sLgJaVhz>?YcOq5o4usYJq^}i+M+glNv%B%)?nJAHhW2}Jq^}iB5QCFYmn^e z@lTzs!9}b=vZoD6x<{_8wZR%pY+7^?Yp^z0gNaRxE@BPV25T^pHMod1NcQyjr%u-3BGzDS zum%&G7G1;|tPR#+V$-6FScA2}8cb|jbP;Q?Hdup+O^YsK4U#==ydJJSVhxf#ZAfzM z5o?g_X+x50k643bPaBe4d&C+fdwN`wtieUBL9(X}N#=XR8YFw#kmTAU)*#u_h9vVn zVhxf#ZAfzGCe|R?(}pB=ZfQ)-koBbj8%%@^qRE(b@~4e)!avdE<}C@-h9(RYP43<< z4c=g4Sl=L; z3|(Iu(18ksMU$~>)d<_H|72m5|D#5jume>ID{5jHN{4s(sKFgfH07fPelW4r zK{Vx~27fTI*1>Qq06~?*YCdA+uxQFh4FX|ewS#ENM-2pFB7zW2`KVFvU?PJMP5G!% z@L(c@5KZ~0QSo3Rg%C~os8RA@B8Cu6`KVFzU?PVQP5G!%^k5>05KZ~0QT1RVi7?y> zMM!e>_@03%LNw*0M%{ynEJ8HpqekI_i7-Mm<)cRBgNZakH07g4>4S+lLNw*0M(u-% zJVG?(qek(Ai9kX$<)cRRgNZ~!H07g4`Gbi_LNw*0M*V|{Ou}$0C?RRq<31vk5KZ~0 zK_yJ25~3*|HL!$6K1jr8K->IfD>lI3DJ~~8g#-;I$^jKo{)s=VIR%J6QU^}HTZ;?d_pwkqXwWb z6HthzeAFNmW)cd~l#d#S!c0UVn(|SDQJBdnL{mO$Knn8~>)HEAl)|M!Da@o4GEVuZ zfho+y6rw2~H8_QtoWgJ`P~p-56=s48(UgxGq{2*6A)4}0167!bDnwI0YOo43S%qlI zM-5nECae%m`KUoF%%l~fDIYa(g?Wqh?0qC&;nLt0X7UOdr+m}^7G?qq(UgxG#KKHs zVYn5tkR`k}ES_N?&k)VyK01qM z7|1h3^SF=B;u!|=4ADI9qqBI1fjmR%T^{$*SvC&4!P}GYsSzqS^3~c!q&ILo^#c63;M@XNYFQN8%X< z@(j^z_((j%K%OB*UK>6V&oGc@h-Sk_;u!|=4AE@(NIb(po*|kIABkre$TLK<;Un=3 z19^sMHhd(WVIa>C&4!P}GYsSzqS^3~c!q&ILo^#c63;M@XNYFQN8%X<@(ihL-0+cj zhJidoG#fq=&oGc@h~{HH+V{==`SUMt{^oT$WdFgCr)8XT4U+k0Ec%CHB zBICD5eCqaB6!Wz{L^gSjj3R!gqGG<)og$)|QN*uQRLqyUQ$%hcikNGPiuq1=ipUH^ z5i`wBasMVief{}A-@U#0!`AZr^XFgPe7$uzzxj*2(9?MHuQ#_pJCAeu#ioqben8>D z_p#t~dc=sfpYX{yd(U@2JY#ThNn+|NO6IrNOCnQ|QDWvRO6Je@l1NlU5))rhG9ScV z5_yV9V%{rC=J(%AB25uVOnXJi{QeJ;A;I~2nC&Y{!pi}{CAodc@7fF(C1K`p;F8=_ zj!MGK!N4U6I~PX@_k;qMWWzno^aTQ!WWzm7^o0SJWWzno^92EyWWzm7^MwGHWWzno z@&y2wWWzm7@`eAVBy)VVkBB+G;NOyLxQ8je(BG15xQ7|Oz~7Q=xQ7Y8u-}q=%sp5Q z-#-8S-OX>ldHM40-@dLcd%1RxxghB^JWlphc%1FidurW_CMJVu;(4Np=c#Fm=N!m$ zMibLPQ4@=4#) zN+@b#K}}i}b3)pg;2crZ#EKeCObXG&q)^nvk{V6S3em)@P}Izy?cY0j&S*A#B%X61 z&l$~zkHm8ho@Nk!L zHhd(Wa}duNF71(V?)L%j72ilH8m(XAKf|%@$FO}gPwxlBe-12XmEQ`!D{5-}Vm+&9 z!gobYu3sZhglTjI-xW3KyOBr2Xl^p^=A518{+)go>GiGicRB25ymYlVk1f0MiI8HDbltyZ4_bJqGI0J!@^I?MiG`RD(262ir7F# z5e6(OVgpJ0MG^KZD#Cs=Uld`!q9V;l?=51li<0yntrtmHuPDhSPtllE#M-;LD9N3p zqA@9m)sTd5#9imX8^&QYM%Z;E8_r=gM$~mA8`fboM$mO68{T0wM$C028|Gm&CQB8L z`zeKW{EagjBjS2VC9H-d-J@uXfa}_)&S;Ey>x}X-_w3ig&!2zx@-FfIH*a3ty}9}9 z&GRh@P>*-$?!-t3XFbLkwm0$A!k0Z09X!&)(S(JInzZo9h-x(9;hLsAJTjyjO_;c- ziRCYdGGi!V!1rHXQ8Vx0VF8RLmcWb?HZE#n35+IVCf;i+>`Vr<;fj@P*9t1rIYQmp?M z;-)9{VgoRCRwK5`3q7e38!j_M5J$73AdY58yG0NOv!Y-o#fRArIkyPnSXLCoH;jZ^ z1aTTv@pvtI%Dk%){NMP^Ly-NC(Dfq2|Dk%)n(B%GSR6&&#hB&UNf-0j5 zs-!SPLld7|0;Txs5_~=U)umS(zPf1Q!;9wO4=~KFWzkn(`3~s_f>*$G^|)Mx`kqv7ky(Q$A8bl@x|({GJS~jVh>; z!VnEj`A7v-QW&D4DIckzN(w_XH02`|R7qiohNgU^f+{Ht(a@BSR8S>_A&zURpvtI% zDk%)n(3Foww`TP)b*MH5;=b|b)qpIkn8ptCb(hp4X zTO@41xT}gzs(~~#HF>IvPO5=4G&OmuicYG5G&D7Ns)|mkfjpwQH|B8uhnv3`=bOL# z=Chkmzk2g+1&QIW#{c!~=I`$Q_2ws^{Nf*fIu1Y0HI4IMmZ8#RJIm}}i;D5&Qtf_d z+eG(d0ANuuo>9eka;f&Xri$^5D#nvbwGBh=j3<|B z8=A7Cit*%9Z9`LbR56}hs%>b>jw;5JOSKJ6*-^!Ka;dhVDIe)F`oPQRH6Q6R`l!q3 zxm0_6oVtuY>N0vR)iyNcBV9(%rP_w3e5A|hxm4TGl#g^7J(p@5n(~n@qvuj>LsLG| zW%OLCZD`6zx{N;XGJ5U%RCA$Gm(d4aMlWj0N4kujOSO$>*O@?<(Q~QxxTY?nkGhPW zOSKJ6`AC=1bE&qWDIe)F`oPQRwRfb;=%X&9=aOt=obr(_qYu1{UL0rsY`?eBW%OK< zZH!Ys(q;7Qz8acZk9ebX%|)MvrhLRZtON%X87EF;1;Vyxp2{HhiS!LL=|DMzgUVskzXJ7hKm|^l3aheRLu{ z8O?@|bV2T<3v#)*(-c`8p*Rad?bMKM1nG!4Ik;2>xl?uG#ftB zHP;gv%4jxxByQwHh%%ZDAL*j&i4s!P+8W2gW63WwXEKr( zIuRbpI2%6Fg}0L~yp6o@Rvf2%qzi8&FTB+>b>Z!#3vaoIbKLK`@OILLw~-g#isR(I z?xYKExmeQ}C)cBsz>Qq2X=rj^chZHokr&>I&z?Wq?dwju@HX--!W1>-Be5_eS(u`xd?XfTBnwm2l#j&1 zB&UD;TT*kOlUSIMEKG5n@{w4Wkt|G6Q$7+4Gm?cVYRX4qVMekrMNO?oVqr$IFeS}& z)#aW+&4rTFKm6X)Racs1VMekr#c|3m0UCo6~Vqr$IFhx!INLa*3ETX6>9|?;XiA5AO^JjY>35ytsMHDsV zBViFEv52Ckd?YMlBoGlgJ)R9Gn~XTj18V)70+-I&yc+A@n_#+J^T4nJj2-F8P+Y<15Np; z!85E|tOuIBE0DZwsP_0`K10lfM8?ekY( zy#C$q%2?sLh4=QKrVy5q2utR~r?J9y3-3WwsSYA6MNLheLRdy3EJaOCokCbfA}l-2 zy@lT1z54pa>sP50`t?`OKfil(;HTHFU$jfI_WN03_s>5L@2;X-za+7U@SRZ)^_2Se16 z#L`iegPrhAA3=fA3L*}@ei^wJIVdW{zPNRp}vd=@;eFg8wvSsCyb}Q>1kER znUf&Dz)E|c6gBy)odo#>R%&SGv)#SilOVsqN)1izGz9qtR%&Q!ryNyGW3#`=8>H`DFU&x4*3~hN1z}vseE( z40mspr&mMafRk{*U`_kCSrwJ#!~>ql16D=lIRSwu0)bUgnU0(01k7N%s;FGYZF5Ai zdKE>rZ=Seujwozb73KOhaqApW_^v9-1#IHxIifILRg^2(#O-rL;k>FSm#|4(;E5aP zs;Jg5ZlMz|?Ko=7n(Q`%lgPjm$-wGJQ8`L%;E8NtRaA}=92m&yu~}+A z@xE6~Wm-iOPNE4zMPU&6kEf?!#c3u6YVxtrfHh6|Pc-4_c%&xJF8eW5lX231wQ)C_mkM~ZmMFxKT=`a7`+k%gwP_Uo)^A#ERj}MmRgVro9>@@gXzPES1hqmdZ zU}jCy!cI@bPK%nFqlKNGh@BQSHAOScvz~~Z7Bw|P3p+g#JFRI7JDr4`rq0XpceLea z_6w=7)6^MkXllY0c6uUqT6}g*xWZ18pKOdX|1_Rm2MA)P#c|3;C%DqQ~sU{89(9GjQQ@$gnS{$c*CrtH3Otq*f-w9Ja z5mPN{%6Gz4PsCJrn)~nMiG;%K&*o|rCG$I82Hr#pWns%%iHAjyZvxrDROiG#qNvFC zfNfb6w;$=<&ZMZww*WLNikrw$Mb3Tb92mv8=&+(@zWru2ikSCmPpyy%AmJ!t)+;LJ zx8FG#b6ym&cPJ|6&vuH4QAQCnSW%HP7$THW#QarMgk=~ciDJVu8(8}A)Qpg%`fS59 z43IE962*pR*!hpKktl9I-9gW=?;isrQEYf-14?(lBcl6JYb+mM>aykZ9!8LQ)tI9Lvf+E% zt-OyTSeGrQ2Tgo&(Zm;5)7(OU(8N3)O?-1j&HNcOF;hnqUtLi%uL+u%tD}kUZm0R9 zz0+(yxiesZAt=)JufCg*S)92F&|CPhgwI>*T7Hw$PGnyiP7#sRl2}#_Qy|l_KksY`jh` zT+6^&Ja*Mv2L)BzbnC zO=l41*@}|+{r7JifsBmuxO>h{n<0)7$>Z)hJ8OnTK9a}XbKVgD{e#Or%$XH`OS*?g zl;xHwv!W#3!;D!ZkGto*@%_68XTmI!$K7*QD3FoBNN&%1%sppC0$J51k`4DL5Xhn~ zk;GbGdp#T5zyB@e9))(x% z^<0+Q?QnDSBid^B?j;rfVmX)MgVQ~%=8{o1+@tO^Eano)ZD0r8qhc(utnn*U>vn8B&uZJaEBH3_{O1Q9sOC%faQ3V$kaEWBY zJ=+<7|KM^D>$lXtOVw{-JDQBL;U1N5VKy`;`Ptm098aGrZunIofYxJQ*aSePS{4fkxR z%>9GQJ*>-7d+;rlxtG+=jb%BClKHc}q}Co@PcKT+J-nTs-?FjxY^luMD0w-38F)Fp zI7+&Qche);aL*RC*^iP@gMnAmi=(7_cr!ht+*A(k+|+)C7t*#6KB*}(* zcpE*Pnk3n94=Df(=yYkKB=P9lN5pP3Y0@Og zhI_WC&F)iYLV5{Bb9}yJLOLy)G|KH+4^A7b#*_|Cl5Dt#Dd{w5l4Qd@Y&4VpOp!oka+=xcNH*M~>@;!dNH*LfT$;ReBpYjw zcxeLDk!-9z0;ZXvj%33}ZgLZV zo9yXv_YlBMHztj;;T{6GX~rbUhI_~wq!*JU8}1=%kXB5RY`ABO+U#GC)}97ykkY)A z)Y{Wv4bE&RlRiv*@CIve-l8_U2N!EFG+2Z47PZ++$~_I%;Jig`_L5qAc&oQIZER7S zy`R2C)Wo(5}>lmR8>o(5}>peH5eo(5}>NDw9Eo(5~MkTpo( zCAz1<8sy-~QOZ3H)*u@xO3FPA)?nF+2<|2~u?9nfHCV_Rq~{WU%LZ$(kTp=Tn?=QL zO0#xlE=?I3t5A-S(0SKJ!B2iWl53^_mDM6lO;(u+(XtNJ(eWda1U97v{;g4!#!jT z(qT!G4fl{WNP{Iw9*-IDe8gEWqiWWzmV4bnG4k`4EeHAveC zN;X)7g{(okMo6;Z9WDU|OLXr*lkTpo72uU{FL)IXDA|%;x4_SkgSc8!T*|uNd$-AWsS%VXc*Dqs( zHCV_RoOlI3k`4E4H$--mn^=R9HQ9;}p5K2bDb^s_)8pGLvIc4Uz&GAt4Hnk7Nz(^O zHrzwjAT1vx*>De8gEV}QWWzmV4btvGk`4EeHAu4uNjBCVvIc4OAj!tsL)IXT9wgat z4_Sk>d5~md?ICNBCJ&Tsum%fRgS2>%WMl0iYmf#Hl5Dt#tU=m4NV4G`vIc4HAjyV% z$QqZ)>$r_~Gz9bv&A#0Fo`;u(9hpa*R^h&bf9}<_e-||n zYcMuggO#koNvy%xsB5s2H8_biNcObx;Q9Uc4=(pK>Kd$M4NhVW#ztL(m8`)@tU}f-iYme$0BzxMB%^%iOkxd^J#9$BJ(F02WKSEC zaL**xAlcL7l4K1gu?ESWHYDMmNvuJ#rwvKCXA*0W>}f+1?wQ0IBzxMBgnK5j1}AoX z+g|^ZY2uZv!6eq;)L;!(vIdh_gJe$|4^H=pHAwcfAxZa$HAwcfAxZa$HAwdKxFlJF zNvuJ#rwvKEN321zrwvKEN321zrwvKEN321zrwvKEN321zrwvK2Jz@=#J#9#G?GbB` z>}f-i?h$K{>}f-i?h$K{>}f-i?h$K{?CEhyvIc5&zo^lDZN4OHpg#AJY`BN4!6eo| zZSISsqvqYl*e~&>O4M)HAwcfF-p2etUiO|>XV_lPx6Gu4_TS%XQefqJPHCAs#9HBc+n zq9o5fVhz+uwJ4cC+pRrf4U#=Q{;88Sn8X?+d)knsd&C-?8mz&EtidGKAlcK#DCr)t z2Fac_BFK)j6!}H(0t@g{CE~Mttw;lg>`i$e>uB?vH#6~chaAPzNuVvB1 zS~lbx*?(t&1`gXXny_OuLC!^U`>7ArzlkPRvuFaHi{@j7e6(qLG_jmT6ZB6sx7TuX zoG@)Pk%Eop;RS8Fa6yYEtQ$>OxArZOo{J{j8%?;ks0sH*69$eZ3|!RApFJ!<(UgxK zUDWm-{`vDSZ~o@>%a^bJ;(h-7sg-q79&u12aaAI*DyrAXRANN=I=2s|FjBowCKDsd_gNIx3uQVn zqI{u6QO%@GC`J@BY4JB@Mlml+Qz=u5RnfeN{T#)lVn&L&v?{8}lxf9?Vlu6YYBptJ zF{0R&R7JHdVQMj=*p^g9wJ%|EF<>a?$J!^wo6KoxtBncMi`9|JQA{vqq#Z}`HgiU* ztqD_%)sf0kOfqJqk2-2U@qYH=_cx!tesS~F%S_SbdG|srIt!jQM&zP5$2>WiUC2d8 zQ*I_0UDTABNk(UJf|-k&@-oY?MH5~wYRby2!xl|gxu_{8vk+S};pC#Gj7&N@yf2Jg z)XbmlCtTvu(ZtGF)Rc|MM@JJjE^2CBBp@A4tcyiWnV5uhG-2YJCJE_bA|f44959NS z@)7H?MRSvRx5+DN%14BxquKBg3$o?eb-*AcT^y%;L`*v4Z1{*J*@lUn^cwQB@q6ZR z_C6vg9nFT1)BrB0R|FKoem2G_9}$(#I2%4%J>1c923jW#9l#fVD z=h+)RVr90BlLz$xpp9{AJt8liaW>W?)@I8%dGOBJtuaonM>C1(HAlCGCVey$nT}?| zM=Z}a%w(pc+3*qTvqh7;%8Af)ZLVXKI-2qk1JyN62CAbeA2C*4)TEDQa?|-eH<^R$ z5o@$%obnMP*2QtsM>EOkjI-e*#XM%B)6s1Bi0E{>elT!6k)19+d;V;<9?gn)AZ(T-Wsjv%4O$H`)CdG8DyhY4+H za$h$q))6SQp(!6J)G;yCQT#o*ubUO=m>B6OYHB@Fpkrd7qo|ob+xtjyj)`%OqNaSL zFvr9&M^RHgQj}w2l%uFAA1TN&G00KVBuPEYEZepQ4n6*T5~Yr&d_U^}_ z13tPBVfD6XYG21zam8nskH}Q#*&F90GSwNU_I2AC_vo{;fLk=>BU071XD3x1P3`Np zGw$JWYCR%Xo!_(JBi3-sICVZESY3Q}tw$uQ*NIi!ikkVey^n}iN3-E0mT?dDt=G-hMN{h$5$k9kUXP+FACa+M?_sRNzo&de$U2&beUx!(Uq{M1numQ9 zP3`N5Sx58m`6!z55jpErp~K@)1evXf}Mrs&2zf)H<3C9|=&K z1*iqIIqr7>YO?^ffHMtE`AC3Tz?p`od?Y|^BA~Xtu%~j7dGGR(0JRXLjd99H0@Nk~ zYQ=HNM*`H6mpwjC0cx`Vwd7?Rn(~nVwTXaQ?b%u1ZI}h9O$5}6np%$ps7(aaike!F z1e{F-&Wf7y5xMJiB5+pJ%%AP&PXT8WfwQ8fd?es(B5+pJl#c|QO$5%0n(~o&hUqxZ zkZ`=#Bk>H$%O3X;3%w1qc!scR4NdLq#4}9Cd4@c@d?cPBdD+G|G*iN`g?GtA-{l9z30%17cEl9z30%17cEl9z30%17cE zl9z30%17cEl9z30(nn|U49UwjH0h(Wc!uO<8=CadSv*7XvJFl8=q#QgdD(_0eRLMj zki6`1P4Nt8@eIk!HZILah@TX@{xFkxxq6G z;u+3tO}EYso?#Hra2C%nH+Y6YJi}Q$L-MkR=cPeB!&y8-^0Ez0`A9rN^0Ez0`A9s& zyq$3m@(cs}(+y|w40D5L7{oK2#WTzeo?#Hra2C%nH+Y6YJi}Q$!`$E*2JsAM@eIk! z9)CyT8P4Jv<_6C&h-Wy9XGmVQF;1;V;u+=!&oGE*IE!bP8$83Hf;(sN40D5L7*ufQ zES_O*@C<`^hO>Bvxxq6GD!6kN&oDQ5hJgj-hO>Bvxxq6G;u+538RiDhFsR_pSv*7X zvd6!9@eF7240D5L7`9l?E*E(g&oDQ5hCu~%&f*#72G204fX-Pw!`$E*hAq~!e|GT< zbAx9XSV(R-i)WY{Jj1ZXdN59Ms&j*97*wC(ES_O*@C<`^hO>Bv2JsAM@eFf=XGoDM{hs8#lb1d2qb=5hcf@-WbAx9{ znHp)zM-84~P<@88c!s&bGYsMx&f*#72G5XcjC^+S49Uwj-jRGHo*{YJhNj{S;u(^c zZD?ve63>vlY(rCV2JsBZ%O2Mh&u|vcki2X|Q$7;Uki2X|Q$7;Uki2X|Q~Nsc49Uwj zG_@XyXGmVQp-CSt;u+2jo*|$wyt#;HI5&8PfRxhYJ-%~;XBbqUVG+-8Ztx6)>N70j z8O{x!VGz%-h-XM%_V|0>Vm-U{Xc5nlylg|0K3c>xoEtpDu*G^XPTq$-H+Y6YJi{WM z;oRUE5=`Sb#WS26JVOrG(q#R-bAxBdfk>M2QG;j5MoyaC*PR*NJCHUbdmB^+-I!xxq6G;u#k44Ce;VFo z+jw^E>%=o8FWb=6zD_(t^0Ez0`A9rN^0J3DNAV1cc!uO<8=5*FiDyV&wxOx@NIXOG zvJFl7NIb*2!844i&#;JRNM5!vPMwd$GbAtD(A4=zJVWxb4Ndt-JVWxb4Ndt-JVWxb z4Ndt-JVWxb$2G+>EaDlGmwiNYU$6YVnt!BWBi|{v7>TCfm2Us>RH=YS@|ALj5lOt! zq9oraHyDw`3oT0Wg>rupNxaXRr1lrwUPKbFb0@ifo%c;#Za%wv`S#}Xm(Rcas#<|Q zmo1{W-!X|~Nk;yWuj$b?F45EsDv~7``G%%uP?0Rj$Tu{#6A{UhjC?~=GpIE!nKHGNk;y-rbw1WB+I!$vWy~G7LhFH2FWstWLZ?1s4~a7L9&b@Sr(Bj=LX3#iey1jC?~=J`%~YG)R_li}LNy2qIaMk#CGs>yb#7oO_OI zieyYBAX!Fr8d*fLBqQG#C)cA@B+Jqu zSw@j8t4NlmL9&b@Syol%SQ;eDD3WCr$+9#^mQf_jDv~7``Qz_MB+Dw2B^mjKCVjMu zWJyN8p-CUDB3YIO$uf#$Syh=M8TrOIxvyJAvMddfWfaM>ieyPfzA;X&N2@AxBqQI@ zEdbEmUSsEnED3WCr$&!rx@o|b|Sw*rWBj3=Jk3_O8 z4U%OP$+C)MNk+agPWeccIg*iYXlgwY$&!qGLsLEy$&!qGLsLEy$&!qGLsLEy$&!qG zLsLEy$+9#^mQf_jDv~7``Qzgh$+C)MNk;w=&3)MY)7PK>^WEEIS*Xe!`(4azZ!_@;}B{HDQ_L=j(fQITIXI=Mv=`>UFw)&=k+QN-6=ROIdo zw^pKvZ@H+LKihphV6vi!6G~B$ClnCEQN(&sROEUf&u}#;Dq=O@T99y2!!x8Bxe`RN z;TbZGTnD1KJ?OiR6vd~8XSfPPvEdo=j9dev*zgS30ImR0Yk>^& z!)am9Hkv0U|B9O2yri84$I0YhQIp%3w6l;VCgY+eCgVIiwlHZokLh@)xwq(d8`ICe zdHeSDs~^~(j`a=deLbv)9RcIY34h~JOY6>kHLRT?9yE%0(4r#tYK$pI@%XxPUkPhB zM(ow1czoTtuYb3? z-FcKUI^Ea5dQeQctiAV=J2}2tyDxvWm&6ni$<1xY_Ez`RulACdAtKqZjl#%`B1f{} z8%2>BM2=*`I0_;&h8)R;b95V$A>>FltfOYtj37s{;T=Vg892JEq!f*Clxid9_f10!s|&zP5DUIlLFf}-n)FH>q&v_8=CTw zt|tYyZ)nO#x}Fr+{5|IAODe^2%164S64<^mPWeceR2E)RDUMS< z(j}F^_Q%JmODd}_sRXufXy$SD`#N1x32ficl#g^tC9r)%Q$ErqmB985P5DT1>g9Nx zI^9s@BgLtg<8kU}%14S*2exlKyL_ZLbzu93rhKG0bzu93rhKGJDuL~fYwD6pHga5# zcuA$^cU@9hbx9?#ePf*RkuIqOwr^<4N4lgE*!~gCA1!`zy(;|6fB5CEfA#Fcl&Rf+ zcYnUC!dGVL#j7t~e17-!vkya^U^3li!Kadw0kt@pBA_2dOr=FdPNm3$MG+HeQIQiV zKD{Vn8m%c_nWcCbVcPtTm_CcYBex;QgGDj#?O=v!VlB2Sv$Xm8$}Bzmu=YJNy}{(h zm09}a??3t<&pw>)Z*lJqPPz5HU(9m>;qc}xn%ta?q`RVt*`=~EjV5Q8QAwctI_wYg zOHq@DoKZ=j`#S80HF?O%t#AIGk0yck8`Epi6ULLaL&sCwmlS8=Cz3cUe)?ZS)8vKsbjcC7!Yl7Z%|!fn`=x8qlPBZlN%!Zc-Th`r zR3u@01qh0X#w$Q@1qi-{Zmva7%E|d~*bj3LSAZnvK>!!i{a696MNjTwk;kB$eX{wA z&Ar>hUst^?(p&S}b=AABde>F&PuY>0XL$0tu6p-t6kxF8?+DU|C|I%7*LBsqu6l@F z)V{pys&`%WuB+a4)q9FYJxzq5i9lzK`cJy*iMPA58}rP{VuUqdvJF0ns`Stl3?13l3)lX zUXhIC@lWu+zU}_OL0Cufv3SFy6{Ak~v7VhIyLhFx6E5r*9~^=0iA}sBc|5XxU*dK@ zO5BZ$DfLcTH^G70HHs*t~0E@2*raYq)1CfwlY8NwGz;;hwDm)?SkC znHm*VFYMekv2j;M`Ivk5kJ*WXPdq!yDtQbw~c8i+%ruLeu?lx@E*@t6TQ4`zUVN`Xu;dphoG+@Ad5KZomhDWQr z{dl|6`_|w4-%6E(hvSula|xe2w6qH6cXGUPa5VEBV4Mi~q+1~lt)+K*-})Pxi1|bl zb5l_>e+Es=PSM2dRMgBa8Ja4-aJ+JGnv`%&PpfdfqvKw_Z~cvN%FD+q2WOn}vML7; z$14X%Q(ji(;Nf`X;AqOrsvJBVuN)jr`AC(6hvSulqbVP$a`14xa&Vf{fYKV$DxBZa z@yfx`l#f(7c-UGVADzRu0K)$JROR5|c;(=XQ$AAV;Nf`X;Amzp!#L%mDIckF z@Nm3xa5Uv3RSq7GR}PM*e5A_3!|}?&(Ugx=Ie0i;IXIf~ktzod$14YCKOi5ea`14x za&R=|BUKI_j#mzjrhKHz!Na4KgZKNEYlo(-D&n<6)3Xn+9h&ZM&Tpa6r=p)}`ouZ+ z7S}PdYHmBqV;QDvhoWP_bWu}#ra@g>VDeBOKG48K+C$Fu9~!2+$taq8^B60Irpcsw3=Us-KGPBxZ~<~FqN`{wt1 z(97+3SwBjP%l~g!f4bg$`u6#YS1<3r{yP8L-QCNZPyg`xo0nhQy}9{xYinNxp61hb z+jTd#b>VNgkbj9Oo?Q2%$=`4#0F!?LzhP06dx@0Nu7Bx8+tt(@i3lW&2Cg-A+ z3{1uuA3VJ4qGtYV|BeX3L=*AEnkFHbVI>6<&Ah{-<0J(WP0mFNF__{wITx+uU^33U z!^7j`T(lB|i6-Wv;yC3ak}%QSWZrqas3{*2g^8^iJ|YS;tYl%L+3*orm}t^RD`A-8 zv&%=MVKUB!kG7cZ-bXypMzi6gEv5@iuIZ^vbNsz;FW}t!zGA)TECt>^_{Oq~Rl-Z7)3BMzi4~RdmXVkJxlJNsVub zKDw|0amLy3ks1(R*nv2j4Iilk@r4K6Xf}ML7Q`3!AdV*D^0jYCJ%}%CLLAM;dZZ@A z7j_|zW@9~47vc-s5Jz)++=J_p+7MsZhdA4(hL2RS5Q4mG>zXg|MYH7zUYjZ$~4C{b;i8tjG4+b4Na~`mqF_h&zQB}bK?c@>{^d_#w==b zJ-XI zfA6a3l+MkKXV2q6ld+m~Za%Kbd(FdzH=A>;YxsyPSTyA$(qOfBL>erb@)4U|6gA}| z-t@||H`XIHyU495eM{TW4z5SrJ*WM9SF?+BZfBdZdo$>D+w$y>GD|JiB~EZmBp<`AFQ- z%8utnO|3`jc)pTbDr(9{;+9r&OGQojNZis&ZmFm#ABkI9$t@K%UQ$8ZMRMeD@#4V+B^I;#|Uwpzi9AQ$AA1^BiIunt2EN?^7MmSC;aqy?1pyzo_GR^0LRrsgCCtbv#dA zwxKB>v6@FxsEzeV9jY!Y=Ml}k!-Fw_Nj$?vJj2@H87A=z7x4^hgJ+nwSkL}j63>vl zY~$JGBk>H$%QiISBk>GtgJ+mn(_^@ZXIL9N!z7;JBA#Jw@C=i9hKqQHwZSt?EbEbH z*ZHWyGfb@O5l!BYS{ppW#KIoYRJ^XiGfb@PFvl zY(rB%63>vlY(rD)k$8sWWshr$XSiG#XGmVQp{ae{h5NeXWgD7Wk1q64^0Ez0?d!xd zBrn_0)V@wUL-Mi>P3-H&Tk#CZ%QiHz9z~P+qvT~9n($FHnLkQiwxJ0hMU$-WrNJ{y zHEK5Fm` zxx6S%`KZA&Ch`m!r+n1l z8C=`uRy>2M+thwf@(dZLeAM6>T(|aCJcBCN7RRaeNIb)3JL4Yx=E*aRx8fNt4W1#T zDETdkXSg(YhSZ{zrq-hd&yZr2(v*)HJVUBcN>e^+@C+$ODNXt4QJ!Icm*>5zG@fR@ z(_A0gZ!uDl0bBL$Kc2p-%U3#(P>CdV>P1Ps(Sd+UByr#^O5%kMC%n%{VxL}<sCeODDk={?r*E2a+Ef>CvI@7qH>gWxF_y#tDq%=68!|N7={UOs>I`@1i0zMGqGeliZrPv_v;e_5TM z=V{BqJeVo_F`DT@&hS1$_SF0wQJ5*BG}DEkVO11nil|PCBn_*gFjGWzR3vIx6@{6` zTd{^0vW8Vrm?@%Mo-Tw9tD-PdM7ca&NE=o~VWx;`n@ilVDhe}26#Js2zPK;i?P4A+ zq?>!@+UTlKTEMCO0jD<7nU&HqQaOsmVO3O)QmM2Hk;AH}93|%PLguh4Dn|)AybwC9 zipo)<4lkq*tD?r2F9aiLujrBT;4bLdPi?d`D8=m29HO6+M z*zk;EyV&?fvEiBj%pJ*6l>F`MS2vHh?HKEQ$!3<=Adr%pgvUSXncZfHqeSueN1db1 z{TE)xh>tpo$3N}Fk!+YpQF;dHBiV3|V)P8rFUg-D-cih|qrm`uB#&>TW@0A; z!}F1RY|+`D0N*Rqb?ryCn_~a-^doz}cY5vO@#{~2`Q21MGTnIX;_+~fsst$moMB@# zj0#Z?3Q=cTeJc78O>S*QMX0Y`Jl>t2i|+`>f^^)#{w9UJu)is3X3vW4=e3K+yEtQh zPwa7uzo&ep!1SQNbj3&4E*`siUbo?|T|AD>AwNzRkN4cSup?p$l_Rp4LW?mH94a^{EdW4)S8S> zB$AJPB0t*eoJR(jhgI ziU?AZ@NiKx7Tj5MC25+v5u3~*f8-s}A7KYI&cg(fkZ95&DIzG%!xouG z!KNu9D9y(_@&n%|A*Epzq_hZ9Ds0^{&b$M>ccg0a-VvFreM@TMm?DCD_QTuOj8i_+ z@ozbP{EMc1q~qTrK&ke7%17dp7V$|nP5DT8(jq*mrYRqZPFh4K)imWJ9sic&$G`cc zun(2AP!k&2-$EQVIpl#f&lZP|{m2hTG1 zw`un8NX5_=7DFqJQ$A8Lw1vgcikk9~ilHqmhE~*+k5mk8VKKCtri!8EDhGYUVrWIp z{2AVne8ggCMNRog#n2WOLn~^^M=FN4uo&7-^GA!Hq$UKPYgGJXI37QVCZB6m{A4&D zKZz#ihf(p9;duNcnw%d-#ZPiO^XU8#O|G+};wQOD_lV|?_fGGN7VW|z_p3$_rCY5 z??&BM4};P02pAgq*4Xd;o_}c0(H=%O)&G3Wi{CHxe%-@7 ztap=|3;dVe!(7iAI}DV$+CSe};}o@PpCVc$z_2>V5^YQC1{_Wl?MkFXbD!HJ57tC>0qG1COE9`B=?)a?{24G@9BN;?A=}_WbO8Ay<<9Zh$;B*dQb1! zhu3?0cV9pIF!!Oh?eEd=hcR!~iH_v<6&{sj$eU%NBZ*a}_?2^&VU_4eHjHz|p4b6BII}w7H1Fu3C z$LXyI_9E-RyU;~VB@R@Lf8Zp$)BK+O&Eo|K>h%XEUV_E1c2@26(qua63M_uJ)F#3H zt*FS~OqE0$#!3tqUkgChjPdxYl#CD*fdxhJ_@bnm>pb~H@%Wl_t-iA@NSJH#J7TV> zeUGfP&O=WWap);3Vy0nmFZELzp5grmUVn(zgEY5n|;k9lUl>b+m6`TT!e-@zArz2)^VAMAD= zKai5(cbw}`O0E9K-||Yk4~Dcxp`OEW)H9mgNsdB2hvTScG%>#?>x^B|Ivhtmqsd*- zDAaQ}j(SE@`y!#9!=tF@-lyl=w>RVM7hm0c^zxf8U%dL}%bVe^#{c!~W~<}-@#{Bt zH@`{b`R;8>`2KCmtKaST zMQ9--1N87cO3Y2JuEUG?!{`-tKw6j3ZuRZ;kUyp``S@_q5~Vf={VK(tif5^HrN-o!LEwRQR;(zVISvpqw`zo)hQ5v8bOY7#_}cZc6Lxi^a+F$OU)Tz}Dk?{*7xsm{u&bhSl$v2**bKWW zDo3#!cA8;#9L09n<1O1^N3`Q879Wl%Vj>aU7La#w!s_G8QLI25(Y(mxqH+|A5J$AL zMv-pF<73ws(T<~7h&ZBfR75*#6w`1K#W^aXoi&PixQOB$717Qb#froc#W^aXoi&O@ ziAPl>PAmA1qqckhyQyzrDlVcOM{O7XAu31Rd+4a6wwwPDMS3YC?Kn!ku?JEQ5$!mN z*h5~F9L4&?#R-K4iX$pVu|jcGlxvh~6zB0fj@m**cu{f`s}xs9$~7vf?EQU{jI`q@ zW@*RdvMI_uZFQt_6l)b3$LEkv|;6!W(c?W|Eu;O6n=D5h|$kI!A-z%1@X z>}E66ieAfRE}agxBB>U6f?RRX~$7Y>E>P`r#>ciiz8(= zERQcoDI2!^!cT|fd6Ocd+V$zyc2QK0;P*e>atvXQQGyf_FYEW+4ZsbT}Fz0R75+DV)eU-%2DdITzh<$ zzl*3GrSf-0(frwdIbn~^Jbq`5VgbC2RJ%U)=q!#@yFOOH%Sb!BK9<1C?NROeR06L! zQms*}fp@u84ZNbLc6}^@7tu}T=s9W&5$)eTtKdbnMUkrATtrs?ST(E>MUkrATtrshNI3bLX!LFa#V+zIE$GW z$V_CUjac7V%)~%uBBFVbhkw&;cZ9buM|GHqGfAoZrdp#q%*2_fR7B;d4l{8kE0u~J zTBAD5#F?;EM8Qm4Zad7xnY2_ywd?CJ6Xz{Nw14|#CNk2FqqYzcMCGUsGjSF(F_4+a zNIQ<&Xnu@TYgC7sIE$GW$V_CUja}b)3lU+Ya#V+zIBy{$h{{nNX5zesi1wmnCQ^f; zvqo(pB8bXS9cJRZg@_<3M|GHq^A;k4s3H>`X5zesh#)FQb(o2>n2CYRL|#3Zy_Rx%26F=;=F~3ASy?7n2GZiBHD|RnMf72j-$2^5k%#v z4l{AyLPQXiqdLsQSADI5lYw71+8ZsDe<-eENHG||Kgw%&42 zSkvT|Fq#MiMiUEIQ4>4DXkz_}CZZNaO)Ov0#PStQ9I=X;SiPc&)hn8t%)5wHQ4@<- zG_iO^Gw<-QCf2TD;BIi$Zm>8`%m>lLW-ywV5sI3a5u%B`U^Fo&6gBf_59@X`u@#Ia zW`&}rd?b4ImOH_kCO3i^r+mbXU{O;(;yy6X-tZB(ff=WK#BE@4obr*#*>Hcyzjk4YEe@@;ubKP4Ih!34Lw314Wwp^rsfmv^l#fWv=GhUS@G|IM4{pS`@RUl2aiqN6ODlJr>W?)llL_ILAn%i}-zDWX{GA_|XIMPbs2;srz$ zCM}B6r4fZoBMO)9Mfa9^`TAe(-rRh4_wwz{=P#ds`PH}ov%1Hg&m!Rm`Z}Y4ueTrX z>31LyUiGM=iG5~KGk=EnihX7@w<-MHKC`HaeP-SO*2idKpIOwz`Z$ia%#5iXRZ$b` zV>GePOrHg;k3~)FGoy+1F`6)6QIp;qS@tiQo6OO7MC*+r;KT18*AxJsd*ld>2H$OH zVtvf-iSt^Xz2T!R+rRtfb3aq#Z1_m@dv2&nv*9C_C(EU%=r`?>2VTk#gm{B|W@eL=P87O3R18*GM;)A08<^AO2pV z@Os^R3y zn@j7Wn@crKOq3ZXU+bcaOEpc*lSzs2tuDv&!}&e&QlrUfaygzMjwWWwXyTl{F2{4k z(ZnPfO-_=_@hovPF-Jy|bL8@9p7_z~mGj6eOVPwRJCwc#sAT4m zTaIYTN7{1K#)&uk#-x4 zb{jQK`AD0MMOT$-n(~qM8jEf!RWwiBY7DEk8jH3XHO*M#VN(!I`A9pBnkF_H(Ugz0 z(Wq(4N7`pB+Go@>ZGHROg5pO81i*6{@H02{+ zP>Lou?KMsLi1(AC$vt~Xlh>1iCulv=^`x4ne8k&H8Rzl!=)}uO8K-=t%Sp9y%16AL zlyP#uUelD1cr_`S+^*L&@)7SPMHBI^(mv$GYe_+# zwXf5)q}n*;BUN%;bStT($xBHYr+lPKNi|LRNOfEn-ASrxYCYnWq`afN!`&gRrYRq( zitC~qNi|LRNJU&1T}Y~F%16A9v@W`jRMV7?RKj)9b)=f6e54Ali*6&;G_@XyJ6*_~ z*1Re1GzSfYCKht1HBE7+iOfnf@9^mN$(u+)+qADEcUl~$d?fC4A$MBTl#j%nF62&k znm=0nBu$j~T;d$UL>-D)w`q?Rc5`>8Qywashv$=M<|l$C=M&|j zcE9J3_D&O zMW)31v>(34IS>7wr;Tggd-EFSeD%e*ZGCfu**?i*^ZbdGm=Z(dKJXgnJotNVd-whK zd5v@KzRzo%^T^t9jdMQS)?cr2&Icb|frDn(n$^Gm6 z^u8bU%^&Wbe{u8q^RI5c{`}3|zuf%AaQoBKc=N9}w?CV!cb-oZ?@C>gdo-Z5PaQI!rGrW`-#fE2?3}z}gira%8{T|^NCW52b@XU7TefWBq299FG zGfV^XGGY`Pp5bE3tB6r-c!p~!j~r2Kct$4iwzC4Guk- zw;B%KP}c`{TvxqkALe&#IQY8iC9x?7Ust_nAMWO@N0Ys$i2&4f)!STnUG?zw>{q>C zyuAD4^S7_xyels7@yne4Za#kf#lPKr@{50*e)7@Fmp8w8{^sr1AKZNUhu3f3-h5k$ z?CWyW@-(x#sCtVow>-UUo2VyGf%A4= zj1?s_3+x{p;i^btH&&G735L~GB8ekRQ8ItFA0=kkjudPW7j~B4hb~zBtu%`}StM{o<>ek6wQB<%?I}e0ekc)tF?^gN+Vr(MK+>J4(N((Q4~{cL=i;J<72L^J$@!Cy(rAK5yfm< z6~%O$k>dCpQOvhhQB1fI#f%$K%(zuiOu0eS5p2Dr6WKl}Qx%n?cu_W@4M!~`$TCtn zN;hSTpOhTMtFjqs!%>TR`Hj3Q8_{j)dKc&_{-(Svo5z= z;&s_Pe#cQ;t;_v<%KNer?Kn!k{6=1wjcCVF>g6}`#_VO#joIRFDo63kY(zVbQZK)e zcV;8HjqUJvDo63sY(zVbQZK)ew`L>SaTKr3jw7$lMii%kqD|GyZzN9^(asvBUVbAl z&PKH3DE0Cid2=?R9Y?8`-^i=85$!l?JC^Oe&%3ji^qy#Zr|RW5^73p%JC53pW*Di~ zs4dKX*ippF!UG8j5mr{4P52%=o0Ms|NFimLs?N$np}#=h~Qwh$3U$~7u=>^q`# zR4ygzlj=B19UxBX0Fg@eosrT}C$)e`Df^D79Hkx*X*AIhm7~a3288UaQN&Dw>&sEZ zE34nB97V!1BkinFOj2f~aulPY1%(kB^d$5HAAaUymZX1C+0Ekv}R`bb_zwBsnDmnXuP5#5%$qid8o z6p|H1ePz73nQ zmUu?0HA>gNY9rP4uamBSCF9!|DXWQRq*|kN{i`_A{Mmj!)%CAY*T0IQJV%{${VN&Y z&f{y1()F)od^@7r_38RoGQN+A?y;I{Z_3ZNcIs(j$mM7A<5MVGx*6!9{OiZR2(C&O@F6tS@@D(262iikW!5xcsgB9m*Nlar!Nls(z-MZY~pD^D|V?{|$V{F|T z$%bzjyvstQ2X7dMp}Vw5mSn>@4BVyPu_PPTVc*u20hVOLI}F;T+p#1Y=HV^qG&`1L z!#%nO&3IkNMeN*a-{nShJxoI>0nAY{T33{$dl;+BC^wbwbI_F6;}h7#SScf=Q9M3>O$?MWOnSYTw^a`2~R~6o+@hQQ-CI1 z6-~IRsL7RRVp1WRSc`U=dtbd*plmvOFU1}0nlRUXN4p!tqr0hS@;n%PW4|^;leVgS zCui-aLT^YDt3z#^+EE4Gkmm94`OM670*_cB^6baI=ks+hjNc457{_KLx`#Px1b61((!Zr2>3$@T8q6Z>7%a<|?+ zx-O@`I%9Av@BF8o;Ng8^G`VkFdF4Nvhxd)q#A)o>E9Tj5Uea~{ijS_nVjlJ_E3f)r zd&N9tK1y@QiP!wEJ+b%R)E)nlH+jWBzbDUM*PhtN*0^i0nB82*yZvcTaX5}Khr{L` zj92@wJ+Y6@pS;$eo*|55Tzg_4^gFNg=l5hhaM6|i(ww}-lJ@5g-sn#+^oEcA)Aow_ zuF(FK^84UnDGy7A(DZgLdMYh)ny-{!_+uQ=uaw`nEmDi$50B?p%I}_N4~vMDPVKk6 zQhvYu^{-OG`bznI_YpBCy8DQJy!?0vgjef$JEgLe_z zIT7i+zs~aXEJda>qU3gRKlibb?kC>&gq#S!W|0Csn1zo&S4Q;YgPrwjrJ{x)lEcZW zaP6FaQubJy{IN>o6ttIm8q(zKQ`6++lX9ZcK~P&#b7)nQGuovo*Ww4DG?HwQ+KyO2IWgJFl7*$H{pr_12`h$$Z~9_wV$2 zbNbJJbNahYYIS#dnzs7%4_`e#rL?rfnpas!BFIl^{~bjT-%(Kz%N-`~2x9Us3S#q! znLC1*xp#v5Fa5n%q$?`+@VyOJRBVT2Tv4&Nci+Z2E2~!U9_|8G);n3RsMz#A0`k0^>Ui$g>-?VFeJ^SaQ`k|?Cw7L3CU?`z z6%{))FP*lk8T&Qvii*AZ;>G>mIGEhwQ|x?2#datT+ri}bWB{$?_bV#)>7Tm4t!xDo z3<(E{(i(R~#dhE46%~7!>$ZsA(e<4zV1gmxNFHQpJCYvT*WITB_Uq9V6?=F`YX4H2 zKd-3R!~DtCFZn(nTaSLU_{nr%KxOwmr`*au%9LZ^Vc$g)aj+o;SEza1chTfNaFXv% z>bz9=_M*x2)U@zCbyDM{nkE8bd3MCa)|2`!J!tOV>38_wV}*@|YDhBWCK!l6u@}mE ze^cmT3f$J~CxiPdTcHGY;3so`Q|PcJKbaFdp(L_}sk%5$eljOELWw4h;6+V-GACBg zh$gl?MNNJ(Cl=3$Cc>yiO(wujtep`}935(!L@5KLFaeep4*7iEEvH3I9>Gs6nwW9s z9Uj)qKfRmMPD*H{fkQ)6J|a??abl`2K06ayCndDfzM(Nr`e;%@>;Cw6`1hobCMC2^ zOhgo)oj#h#RR-kQWR8AI^wGrfiP3EMNaYhJ)=!LP!$+#0II)0YG#fq=S~;i6$r7RNR*)%u&>&InuC0 zn%mFwZb7JNvfDtaC2_+tsM|on#5o?(9%CmCy^SFF&dt^3kmIXe)L2y_)-d%iFtGU%z<$ zDwRr;@O|^*cP~D_`Rw(J|L5zQ?NVzsfHf~$Tj7W2%eDY>c|wi&2DgWOY9k&^e1p-% zHyBNPgGEhzgVDq{7)^YGMNNEz(Zn|xP0Zyb&6RU`H1Q2a6W?G_6W?Go@eM|ElXJVlFRgVlIy+=JIG_F5hYHy)ukBqQ1SmdzpjkH*aqK zHn*d0elp(P{Pk}>xLLpaGXK|?FJ9gKzn|ua`{wR1Z+`MWfBu`FriaCC`8+$XTpzL( z#`=)(I@gEoD|pgKE8&cY%A8stilTBSSBQ)h?z|6{6h{%6+KekE}+1(`~AMx8@b!KI{4BSwS`EJi^@@}&ScyDgyW)e)T%XVt7Us!RE}EZs7q&!+By{D zMafZ@?ISw6oNT2SAgW#8cD6n)s$JhIM{S4ea0=ZR1yJ~qqb1#@sY|= z1Xa?bsN<-uL-GDakyMFj$5CqZB2*=!9Y?9ri&&M2b{w^JD8}Q{QG!*9dnwW?$yLx% zqE)J*aujiuJbuSfynvmN(oy17sw0)72&`nJ9Y<{eC%h;+O2kTaq;!;!mGtQ9IEpuC zM=>iA?KoPliJ{L49j#Q2!yOWW2)+oX|8L8GN(mTaZiug`M_S>G5)~M}3eE4v-g@_=^$V8II9Z~K2 zNYJI5YR6GT=*Ec%T|_%;)D|MbPE-$L%s4YZ4j&*I9!o^HHY` zGjU;Ii!i@hqdLsQWi#G>q+%wL@oh|f+ubIJYS-6cCN5iu2%?HibeM^Yn2G5uM|GHq z%N8QSNad&wGjS0!F`eb84l{AtLPQv;9MxeaE@CE9`*jafUy|`{d{SG82qTrFI?RNw z+K*xNHPXheFMuIODrVx;VI~4ZNmP#NFcZ3MKkByq#kcLZP0*8}&QJjwsT|c|CX#NH zs2tT{CX#WHs2tT{CK7a(s2tT{CK7j(s2tT{CK7s(s2tT{CUW|cs2tT{CUQ`ssF;bA zCTL73TZm{sp@^ACZGw)d)+jL($@q3e9cJRPg^2L><){ubabanXaS}6e>M#=*F%y%RiPR|QyeK(J%tSK29Z@+-%tSK2 z9Z@-oE1nV34v#6`@+EM{WrFcTLs6SJ6!WPCfnsT?I{V(Ksx z7cmpFn2BV38zbF9MEj{v%tSK29Z{`OVkV{zGjS0!k(MGj@l73O;v!}u{S_qIanu$f z+W)3vCZ-NEaS=0-3gH}Shncvr>QFAfGkQLCn2C#+iCN4!%SSnOw24kl#zBEwS|cGBNa0- zb(o2Zn2A};L^8ge7nK)*k;+jWX5u1dViq$ob(o0@D-fkfh0ak8X5xG+W?~jIao>9D zATbkBtx;ko?%Qu27nP&LOiT@CA|sWf#7s;LW+I~6^@*8C#`o}d8c{h)%*51SCL*eH zl$eRB!AwL{juJC5HJFKr>Kvsy6Uq2?ep9VcsxvV)n2B?$hj2nsorz?88zWVniCJ|f zrUo;Sk;+l3Gm(sMXQXnJ>P)1_VMkPs5;KvEZ%0&)5;Kt!WgSsD>a1N~gPF*SlA}~- zA{pP#NaZLo6DhFX5tXA-Bl<%tH{byOEf}4SbW4!fDp)h z85Ya-0>VZcTLe~_4cZpMqaduK+)c_*vMY&o=6ORrNe zciwmJ-S?b(&c5dYRBV*gnWzJr34jWtL^DwbG!p<7MoFECI-r>Vs4z-26Lp}@1VDvR zqM4`znhAgkqomG69neewR2U_7Ch9<)34jWtq|QVg&`bbS7$tQka1%j*rlOe`Nu3E~ zd?TR3D5*1njBf-~7$tQk>VRfqJQU5ui0=oPAmbZpsW3|FOd#VM0To7xW}*&gCh+;f zDA7#R0nG$Jg;AoJz@;FO&lg6CW}*&gCeTu0lxQZ9@eQ<8G!rAyOd#VM0To7xW}*&g zCdNb2OpK(?L>-=W47$B&6qoDm*FU6{`*qr$4M0wOVr)4@O_J~sDH97!^kdIiKjtD} zz$9q{Fv&7xeRcA&6C1m`I~Q>Qz~+?`XC6E8qI>Rr;n}-SoIyKj78fP^W^Ez9neW?a z9s`qHGhkZN7UilIm^W-p*X+FKMJLW26Lzk+Q+0TH#c=HU%Q>Dx8Su`)p07^F=_!xb+=t7Milm6o|B=aJG@{23ZXtlGSh`5@lFm3d8_s zES0nTV0u6*AN!~kbh zP%4N4&WM^+IKx^}Uq4FuEjo~guMTiVbfm%=R*^c}NSt8_DcZP` z955ftRtvy5Y#lIpZK+wy1Wa08jC8B)Corj}&`z?+z@)x%V$%A8%OWXW*lP6`Upr}q z0VdgHVA2}nY$x00nsrRTw8=JKWiregH&4dA&J`sq=-YxO4iQX9k9wV7sIHl7EhmuMh7-s}yjA=KCUdRj{4xFn z#W9?i%(a%&$H261oAbhn$y{qWdkjqCniG>OdeL(77??EAotStnn?Eh*j)6(@+=t1j zW3-d!dBdq=CnnGHmNUm_C(UywCflr*6UV?L+wR0&x6dv*6dS`#)wTwsb*X7#- zJmQQm+9^EZqxHUa@@)jb6drNL*NMsY2(=pJ+XMEAPO(Rvmqj}RJmMP%&`#kI>n42d(Bn@6}Qz$1(GkND6$zFq7QADVZ5J6@x93Xk~AybCi` zRU}N|5nnUl#1tO!iFx#Ae;%cpiquZ=>-fODvz_ACNsg)I9Fr4McqBQdmUB!_OxYhv zj;ZC-@=i?Qk>r?K&M`SLg-4QOYB|T`#1wnPN97R;?r)D$F~xi?@kx1LVhnq(b*Yvj zVG57fx08>^1GB$9N<|b2Q~WwUA@BTl;SnE@M>_*NvRDtbQ|u9+kN35c zkH;4iJ|2&D_TL|+0*cg5*&p%gcxOAsuj9kF3v_;)!`X`D8rOUI8BQ!Fb4;CCPxlzFqt}J{Iq6Ctf2= z;SryT_hIs(c=V^(BR&-G#1y}d&%~oY1NMlo5kNb|9`TWQXFJ6n@rih}GhmNI&oB`^ zLmSXDq>_pGxQm_vdD;HlCLC$YEF@;B>XOI(IPE6sE=o#b;mlG4O<#S2&404Lghsk<|5>*q~2jg=M zPE6sE=ouyfJwvL2NZ&3z3g{V92}Hsadlb+!qzZ_HDfTF!XOQX-bslM!3r zP%z8qAQe4G#y*pY;8^UtTf&&ogFmAwVOHVs&9TW@|hdvAWPXPq`cuKq<@u&A|xiF5R0+DF$L?o7T3>ApPaUUYbP&tAML?XBokt`<1Pk~76b|T`n zY-GsG1|m`0iAc7RW2ZnQUON%VP;%rHh(u~9B3a3T1E)>8MPsp`J0ZzN792MPBoW#P zNvtV2Yzjz2nfnJ$NV1OwM@<14;0@ofT5!-5kOAUw(6r!~DIf#PkuzW%G6iISIwp@> zPzROV@|`pw1Kg1lU>q<7WPm(!0F2|MfDEvQaqy#X@`~i~#wy1p?z+@JeBKSxB&j2QwK(v#bTZ}vL*x8?C1cAwc zrh*0kPE0m~r3n5D7W_Lg*$$Q>_%B%S@5B@yiQvCr!M_tzcqD@Vf(8FhOyLnk;Oq0NcFlnoR{#@o`OmAGq!$uE0E7J}akoI)GzFfy;?y@xq1@?1$xQ@$g?(`t! zF^J1ZL6dc1(~H~ZFQ#?j2n(AYHr6J7GiNFBUCVr|_0h0iFgwoOmg|_W6n?_-b5KnU>eLk`;cKC;Il4IBKmWP>+2a{cqpNZ z0{dpR=VRcq;g~Gs57EvJh_thFBJysX_H{t)?`MeEm$gPfq==WVjV$$Lp%D-%ZtO(F zYuTQTc630b)y9d)(JoqRfJkeN6Om(Gw9)_(rC=vq10B2N8l>59u3~)x2M8X-i z(7v%|3(fW!Z47XR?K4|vATHxfZuJi9$TIQ6XALuN zf1Neloo!y7bBVpDa-B6?>>Srw!(MZ#F#%w{F0HeMi@6lYFf}Fwr2eFx2r_)+Rk`@y z{125iTxXcp8K%83;5x(9BcQ#`FwL?ewBD{WO#QMV9Q;{lm}Y58zW2cu6d2uz4Ac5z z;rT8RkwSBpddAFT5GaNL#6T2o9l1sZfYeCn$3PU0PssB5SRk$=*FI%QZDmLo`;B$v z`otN;M`@4cTCVGLbdTV6G0a&ez&XxX#x)6`D1xvDW$8WJlNe zTBjFwVoLsdOnXOQ(%vz{%yaN-PiF1OtUVd$8Y&lN()zXbWZY*>)}9OwM{pf0 zLo2bOZ(-sx z-MEW`3a#KS4k{XvYQ?XrWj7vjoo;}V2L@1Dzn!35s2iYEIs%}S!1ID4?z6~J0F-p= z043eJ7Zecy0;K{H0HsOk1ts+kT1xpTfKm*?3(7%=F&FCwD9d-O-K$66t}f3%pR09G zMpCWY2}%Nw<~$_Rf?;3qon~Gg=7}W@)Oo`VU z)QTU{=L@5(NNaykVN@fGvMR0pL4{F`Fv_m2>JKW6YJ^d?A?^<B+eNt<&gFv7LPHG%(3_I=@{^C*N=cOfsE5Oul&<{mGVd-2d+B zak{uMpG$oEG}=jq)7ehEMwqn50h0`j6O-0Bd^__9S(N^BiPtz_GLOc*#yQ)`JVMDm z;`^A_I436a2sPLQGr%K@0cT@`n{x%znl@jHvv%g|=2~2`7MJv1$B=rb9l*M<$hxpd zkDI2}$8p!kaZ?q^BRfcNsAHB@Z8^<_<)w%UJY-rKpv*MiK#Av4v+n{>W}6cf1CdWDt_BKFW}Fk0 zD2LA{)&Z1R=L99%0hE{rP-dPJR2WqVqxeEA=jii|Rz=NsT0t0SZR&N(c$ z0i4%D8iCwEm(5Iv95O`m0f9)nDkmbjfSl6;Vt>1yjyGg&r04|@X+Py_qn&NY5Gi~C zMA}R_5%F4vNINMY(oV{WNE<26WdV`4QBFkKMR6tzh!mA@B63iI6IsYX(GJQ9$sq~O zV*!#P5>80oK5-fgkcKkf=Q$xc95EE$SYhDaki?r}NU;dCGC&-T`r*(+p1%WRfH`)C zVKL8(p-_h-f4;u76AU?|aED`mPDtVo#4YmS0rE&tk7Ii1%K&>Mq{k6GWLpF5v6Bl~ zUvfMTkOB6{bv_);1Eh_}LF~yl^oMe7>UEv%Mb*LMQ)l~7V+w&G&(whfU-;G1m%UaWY+|s z5k}c@Rcfg)N?a3XOYs_kl52vNMi?dan@V;~pub$osC>-%; zcX&SIRAg>$vEK50wqlMV0!l{&*z5Y)&S-C>})Aph=wEAlQBoGQ@dABDGpti z4acql$`-=eQnnBcN3Q|O7QzXN*RnMN;c1@yqD6Ir3Zqzyik3zg#adMKDY@DJjWEiJ z?$GCxs}0bljLKKD=WcDjW@Go#&iv%;?OT`5y?Su_rSq>F-22>@)VG}7+8VrgV`ulu z$-#XWF750N?z_BkZgb~~+mWkMb)-d03mzw=E@fdtLsYO@7?3nVPDonv3f2k(l2$w?BrSLaD}@1R#F?*mPDs3#k2qOxK+sjUM{+O;_`dDB+1U=NtIX>(%oo((yt+>HaK!OYFG6O;A==ug@V0Fz9< z4^v_wrNlt6JLum|*6g93ykW!kAb`m{DkTDf{XqZ|T|{$9c*Fq^XMZw}N{N43#HK1$wJqn!aBS+U`K&hx$+m;oN~b)@)q;Sq1FeRIi54O2VC9`VlFi77nd ztu?Y&0Uq)BTcp`2VGqoJJ<^k5eEb%e0Uq(`TeMT`5ud(w_NUk*K75OI26!aybjc1i zFatc|a+UaYu}565GW+%eLMrRyH78HZV=FksK|^fwa+OP5t&i6r%D^uB`gl!`VoT|& zkcDX|*jry8ui5O=m+Y#qkJnsGWt`T>YxYl~+!h{ARo=3VhiZm=Wfbio8*dKODx*@j zY~z7RHXfMdD?2gCR|Y1%5$pw2=iSIpAog z`JH{+Ne(zLDIf$)Yg$iC7I^_v$jKrv-?y{;9GF5*)_6HFg`6z$!nYGSotQ#S5uaDA z@N#0}wVd#xJ+D~c<-`;ovA(OVSl{Ku6dsB4ykh0K6H|C3!t;u6=W}8Tk3@G~vF_Z7 zDLfL{dBw7G7v_Xj=MY>9kN9dnCnnaid@hOT9BPpze9ss9tCufRmc*MMsgV=N|9r!} z)THwKi`B-OvU2rCN`N7$lK@GcfD@8Bso_2XB=wOKlGd7rW%+=lrN#+KOHIR~d_a;L z;Dp2^TFj1yCHa6PFTe>&3r)j<{ASF8d?zGc%Ua2Dd_a=9c0$rJ(~QVk1Jc40b1UeC zq*bQjGjf0=W9@`w_V5uoK-v<}vz3-W%llH;!zbi?t+f1E4oQ|8tu&Ortz`C$$cqMK zfIXHy%UekSXFvwnW684|l6+`D2H0b{vka1NC~U@-GU(lx=>Hs&oLxW$*khTq98%cB zw-Y)i5wnNyCPXU(?6JIA-b(Ux0U2PArOk3kVGrL+==*TXn&ptf9=?^(3CZl?I|=dO z0rptVEN`W-hi@cwwvySy_YtC%0rptNENdm-M%aw`HbQ4B@mdZk?BTlzosi5PzKIa6 z4A>q^m*uUbjUpfe?6GWF4k_&6TL^t0&X*82jj)IBAap`9d-w)Ie7K?Xv^|z8%RgLf z58prNY$daYZy!V}1GdK!WqB*b_VC?<&Q>ye_~yX|S1ASh5`Q^sCEq&;$bjv!2wDy) zwuf&WbbdIqhwmIjD+BDY_*vdcVGrLp=xe1#x^hTi58pTFgk<)#Vte?uK_?`$rxo__ zU4u?YW)ELIhT#dY$D&+$UkZEp<}qh0nLT{*Sc7z3fA(06D{Cd+I|j%Ado0A2Lo$1C z`XJCsW)I&whE@jHV*#$bmCPQT-@A}uIRL|RZ-y$3{EPn?Lfp0IWgh_sye z5Lvs&$~_>`YT`sBTg4~S%lorq+J`OXX= zV%&OvHQ8a->%o;HGwf_5nPFDz0WrWCRqN$zArP%ueaD(O!%96M1~_B;@5St4ogNSa zoZ%ckXYhd-;0$N*Ie!nt0B5**9cS->7~l-ouH)Q25Cfdy%5|K%2jVi${U`N^uj*ba6YYc__GA4`!CIL(yApv95uq>pn}g9>nRr*aUxyD6t(A$_ zS0=7^fa@J#z?)s~0M~^NW_L05H~Z_`pVzlPAMNeWU%0dJ>do!JOUJ{(?K@YmT-e&Y za%J$sOQ?3`75AZn90C{&LSOOUlmUTD8-mi4~(P+0HqzX7nH(G0HuTv zKxxzL1?5On!?C8xm}5;|P!2XV9Bu+AEjC_I3`9OqayoR(5hpJwhnyM?I-#W$bn=37 z)T!aP6F|vQJ3%Gz)NtqtptRTUf?^=3Pbs4TP>MczL4{EqfC6ZQQ4)b_I0gmK2%{tj z)o>UJpb*+U=p32m|~y!Py;Z@J~=VPJn^XpU=o>}nBwp8u?Aog zmzdZt(RdpKbuASS3E*;KURj@%aXPdw@r_cIWHoNcK&9 zz`@y0;n7G;5}$BzVhWG=h{HsVI5;tdM`KcH12e!QKI2d}WAX6#kb|?G;^6Tq2edQ5 zBR=JTc9K{Qm;oN~F$Z7@kNBK}@7wvD12Bb0e9*y(DLmqn4*2!}kNBhm+9^EZqYln? z3Xk}#1KMdYJ?#;nbtoZW%vB^4IqcwUr|_r|9`R`hC#KjVKJI{a2J8_ZcfhyPc?Vzy zc*N%&fGIrU0}sA$=K~MG6dv)32PdZZb$sLj-yZPm_{am=NvdsN26$xQpWGhtp$A|F z{5n4LfOd*K;!_XK{uFz}#~vnf?7@jCJmPZ?zzoIt=J(BeekuDk3IlXc*JKPoS4ERKKy`h5AevMKKY#I(+|K5@W_Hbgemrjk3TrS zUF=aSJmT{YPE6quAAp$10SG6i@Q6=905iZNJ^@iS6XuZ|fpE4{c*JKQ(9Qsl_zVQv z$vl!n5WaTuAqZeHkK`1D6H|C36|ixcQGee?DquHK0ULK21u%t2ELy`D1?-W&s2#Fjhl`8?n9QSg$bKE}F$!R^U)OR?y$P-{3ScsiTB(4ITZ{sj7=vt# zTB(5Da0P7NoR z0Yk<%0?JfsS;K}d4N%F#J^9y55o{!EBMlWUNfm4)Yzfpkp@d9Q2D{;7G~RI%Ht|WC z2@OH*g845^n=2pjj0)3y@{+Z@!{Qr1$HEuW`BONmcjP&Q00AE^N-87AlFi{zmd z$wL#7JRs90^ORjYBy1ynDufcr0}{45XqvUFN8bWJIip1KfP`%XR2U_ahlV8&-j)iZ zMDl=yZKS2bD3LrgEP3#@6azthDvV;ugA-IF53NWZkgyGWz8tq{`M}Kt3EK#$m?)7v zAYmH;6-J5V0SVg(s4z+-4-HEmyaOeS63Iiuk_RuSFiIp3O+@lgisYdc$wR}E2X9M- zQ6hOj#x^og!YGkEpbA|8R3s0mn8=2YB@fQe7s&(8K?^7`%4zsS^3aOp0k!Dz&-a1~ zqeSw6YIHfM)0&Fpq2)rC6V#)NfC{5T@_>qT5l~^2NFExNJa|7}Y?MeIP?avyQel*6 z9+0~wQ2P_B?LL=rEL#yhG%R}XO{t0tIRaD|#i|D{sCa!MdqDa&|9mf~*eKCGG^~5@ zf(oNV_|UNM!3!!jN|X-`D<8a|!YGkGG+fis3o48f?L))b2QR2FO2iLH;zmYa7{!$x zCk?9~ye$HugQiX8$_1se=uqzTiUI=V-*QlA zpW15#D*GswKzKogQKErB{h>%pg;64cKr%N1DvS~pM8hfwpN*r@|mt0M!YC0&G+YnT3o48fWkkcu2rsBGN~94;@kXYUFiNx$4QnI3Efq$II08xDKubj( zfh$uuh`{OyXG<+al$#TgM>H&t@Pdks5`6^nyphirMsa<}Ny7pOZ%c(yqL64joT zMu|iMsou!v3!_9Mfn09{R2U^92_$aWPBr_Y@<*LR_1AhQ5GV~O!Pz~6D><7oTD$AiHT??+7veEJEbf{ zl($qg6K%?t^ad41iDsgWXeKHP5m8H7S>Cc{!rQ09DA7!`5zRy;nu&>MCXn$B%u~5O zd?K0&WPBr_!YI*9v=PljC7Owel!<5~nu$to5TA%(LPYbKn1Dw+ut@)ghs zqohhHYWWIi#70S(2$b^`(1?waG7+fgE1(gtPs&7~s4s(xX2Rye>WqYii1L+RG!rdr zCerHa02M}wW};=ygm+2_qeL^&vSz{yDvT1%1Tww>Mu}zuHGXBFA~s4i6Dad5pbKKVs6(XwX3Ii)N_M4+rXZ&@?p1rA_5ggMKlw&g@_1L7!}b>)D|MjK}9psMl=((g@_1L7!}b>)D|KlP(BcajBjL0 z38O?a(MB{AwUmsQh-RXVXeMgWOiV;G(MB{AwG@q*h-RW?&4h13sYNp}5zRy!(M;6# zw`uf+Q4!5V%@<>q6VXhx5zR!+S7VkF(M+@v%|vY>qWtqkGtshU!aGpHDA7!`5zRzx zr)sFB5}Al-CU8HqfU@?yjc6un(M+J+4tppO%|vY>BKmx>Q4!5VEt&}wVvv>wyuMlr zNZ_QqfCjw2+CoJ1`C_9Ynu%IUNZ<@4w=|-es4Ya4w^TF}ZA3FsTZo82#YROm6SY*4 z!1)FF{6J))mNF91Fbim4A61KHVj`LeWPAfA+CoIsr^2X+W}+6&a`ZA3FsODTzo zXeQc-W}=o_637$FKn3s znh9ilBP}IH;S>&geaQGmK#5TRWg9h#XeMe45iPh6Q1<#J5zRzxAtC~08#PHo(=!)c zTZo82+3TA`G!r#zCh+;Zk3z;bFi>1(0-)^mA>$hXB}M_1_feCGW}>zb5%nqWqmc29 zw3KWVTFPD@GQJT|VU%blknxRx3Zq0bA$PSp7Zkp%wHk_MLauA|f(oOg&V=09>ID@> ziDp7CZM9juG96d5W&)otjAG415<56R$wmQG7{!_i-}$JT>r4Pt7{!_iFQ_m|G!uG( ztFupqQKFg9J6xTh!YI*9=ryiRP`s8eD59Crn_SJaa*V#%DA7#FWvnUE`8oh@a}1VDvR5zR!+nhAgkqqxq5x20mEL^C0GyLv%|QKFfU>s`H| z!YI*9$PKSvP+^p4CMK+z@PZ1XL^CmA&4d?J7$usC32P>jZCy=M3lZgv63xUUqM4}q zYK>|rnu!T(CY&v0%>+P&QCw%j*{7_T0H`o3a&V={# zg;AoJm~fp5FQ_m|G!v7EW};@zL^YH;6O)K$qUNhL04n>ah-RYZyEOnRHi|V9KD|`U zbtV8R`zY2-_&`UjnEG!rA% zOaN3E712zLSTg}oVN^sjF=EXGK!s5e&BTZ`695$(712zLY&z%8gj}_OjBh?qos445 z1X?PQ3D!(_LB&RiW&#=CNK1uLqM1Og&IqV@eWIB_xyBsSxuCFSq8dt_31ob8P;Z|~ zWJ2mpAmf{ZI$O$`3A9ug712zLSTg}oVN^sjF=EXGK!s6}Iuj$-OaN58zDS*k5o;y@ zDvXL~CPp?%a_);}ViM6zj94>K4Mj6CiD)K9teF6)*rj94=PP+=5nCVVlJ5o;y@DvXL~CPu880H`o3qL~<3h$uHFqM1O(H{eXLW}+Ih zW}-mGm)t(5i()aNys0djFjVsUyr|;$v1-Cl$?@|}015Z8Y{F2<^YgYaPAh8p3P1&gwN1xzj*#J@)56C;Zj5h|H0Lyd4t^b-Z^Ck&Oi4Il3^l?n zQBV|Ib;3}ITTT{;grZ;xg`pC+oIM~Kih?y1h8p1(-_=nSETS;f2)9H*xFuqWg2fbuO5Ad`l`Bx72h?t{oWjXiky8{br?9q0xWzRn&{pyY z4K>0oEba2*OSs&I=n6^2UO@}i2};zAUL zO5Dn4)~jBB^05=!8;@+BICJ8TjYkI0yR@}+>Cw%dlY=|%ErzFx+fST4ae3$BBNuls zzGm~vi8HTw?8L_I?#{&rukPBvK6c_o_uTu!vv;33Q>Sa}7nUA_OCA&oR`EoHkG3kg z4NUT%fJyTZm^=-AnB+YHlV%|>X@R#D)X`2_-!TPg4x+9WZ%cfbGy{Q2o)a)>anIVB zkLi7v&b@kbcW_~I6scYv#!O(XRh?){`*vst{V z*8s@9MtwFGZJ`s9`;2-Fh}2_FL}D!4LLf3-eP2y%WjhE&qN=lvWChs<0+CIitBq^{ z+5Q2M&7ThueV?rkWcz?fZl&+5+48a710t<9PDEa9XsrPvtu;1Dvr$$zrV8#sSfqHFtHLZ6waHeFI{EGpre8#UKy^oMFKr%LRcL z;0&t;St|&{0B5AU5?N><1~?&mF@FoD z1g^X#O4z@wG<74UM8TW@ByqwCNt`H{6o4dBI3d}PFe?B_tnfiHD+;CsAc+xm_Ex`wQ4-aBmOLaYG{)`%n6F` zU(7pzl9jZU66Kwsm|6r%q&HAvy%UryC0a_nH&8N`PEazI03~y2pu~MADA~)ZV0AD+ zSsv^J#cO$=vO3s6Z6?ocoD-C+CR$24I0L0c!U;-?1VAR_~#<-tx+yp}VH)xicDV3eqX3swgkXn;|o4lY<7Y@lR#ou4m^Vs)^A_P0@EQ3n^S z4mQyKj2eqNxL|d#f!Y`MW7L={s#OK6gAKGlqsClO4WMeHSRU*es4-Vm1E?~J<-tx+ zVHB%_@%bzdc7o!yoKdU}Hqicz8jCu(V0Ey8_Gi>s)WHR-gAKGlqsF2RE?6CGpaDjS zI=EnUuz>~`CFomtAhc`@?d96g;A^yHqZd0_!c^}RJ}fy2RmCTULUK2t)&4*aYZ$>RJ}fy2m4xT z8IF8Pu{zjV8eo*Dg9}y%8>ls|C!<6iT(COWKm&{tb#TGzU<2*%^^HXxT(COWKm&{t zb#TGzV1Tkb*g5)mEgyYW2ODUBQKAkmSRHJj0UIUi;DXh`1{z?LsDleu2ODU>Mu|GO zV0Ey81{fvk;DXh`1{z?LsDleu2ODUBQKAkmSRHJj0Y-^BxL|d#fd&{Q>fnOa!2o4> zu#Zuq4lY<7Y@h)~i8{Dob+Ca37$xf9g4MwW8eo*Dg9}y%8)$%0q7E)t9c-WhMu|GO zV0Ey81{fvk;DXh`1{z?LsDleu2ODUBQKAkmSRHJj0Y-^BxKMR4VEfyB5eFA44lY<6 z?4zkgh;qZH+F%G811%M=Po=@oGX_904%AZd`XFcQ4=TdoLWRLlGX_AhvQbMVdJZvT z02Jdupb|Y7Rf})*S=CaBss$5@Wi3unj03e)A`_x(ae`tTGEmXAprtHqaf0GC0wtM- zfd*`pD1u8>1VhFc7=30`se)jr7z3cps8aR75Ha=#6*+LJa$sl}1E9>PQq{naFa|)G zQKgE3p7#sDZYs#Ga3q+`6rSp;RE0Y-@ixKs@=Qoj8MiiJ>UsoE&k zLiq+t6u_k_fRXYIv{V?S0$`+k1E9hv)_e7u%VDb|1(Xn;{H0;x(?ff#7O zMoC4rl64>k8eo)YCQ8*zAm!VCphPoKs%8Qy-vFrCDAi090nNmiWl|U@WmG^jF=nL{ zK-ESCG!tVMO9529zJO+8%(u{0rD`UMfM#OMx6lDpy}p2EVr&tjoTjRoK*~2TrNrw~ z%>+`u0Z_3~s+lMPnu)P!CQ8*zAm!V?rBYF?RLulZz5!72`cyN4ly3l3ygt=TAmtkX z6&t0R38Z`jpkkv`Gf@OI6Jx2UR;p&A2xun8qM0aFGl7(E;PZu1s+mB_HvlS(Qq2TX zzP&*k(M*)8nLx@n04g?0H4{kr20(>Ts+mB_HvlS(Qq4pW&`dO+`u0Z?I-Y9^5K4S))xR5O8;Zva#n zrJ4z(d;_4uDAi0L6yHKum0SwMKm&}DI%>FyOZqgRnP{Yp z8m>)J&;X-EGlA=96g0pnxrGk*TqtOOQBp$w^$QS{l$yG@_Y6hFd`cj1tWRlF7LRYC~ zq6}yz8qrKts+mB_xBui9%|xY|i87#>Xr#_WrJ9K{pqXf-&P1h}i87#>Xr#_WrJ4z( zd;@)oamW`G)l8HD%|s)biApsSWk560h-RWv%>+`ufzRj2M5UUEGN74gbUbv{GlHQq4pe&`h+VnW$7Vfs}8c zPlZvcnJ5FAiPlclXhkzosb&Hx-@xY!qf|3d1~e0`XeKJvOq2o51ZvPq zpK4?xpqW6ySOHZ=1vC?_)R{o-JaHxhnu%8GOjN3wCP%FsnJ5FAiB>cdm1-uC z^6kH%NS%pFH4|k(Gto+&iApsSWk560N}Y*HH4|k(Gto+&iApsSWk560N}Y*HH4|k( zGttT|bd_o*%7A8~l{yoZY9`8nW}=lk6P0Qvkn#=8Q}_z`f})xUqie{ox%>+`u z0Z_3~s+mB_HvlS;3Dry>Ts+mB_HvlS( zQq2TXz5!5SlxilB@(qA8qiWSmAmtkXWk%JinLx@n0LqN2RWpHl@338Z`jpv zd;_4uDAi0LqE^iWQoezf3Zqmrfs}6mR2Ze238Z`j zpu#BCOd#dkA5=6GwQ44i@(q9rqf|42`vI4L=63_#zPYh;ar@zugL~_8zT;7%n zquA*}OCyY8p(Qe2rMTzH?mwfUNj-Ag-znd>{aeG8X-4{pD7 z{&j|QxJxbMQHo!!BGmp9IB?p(Rm?;W$69R=@5&5k@Zg*waw zTkRb4#tfL^$MU|+i79R@@5|6ma$}vCVsm+0228TKPE2uPc~=HZgPC7QCtYQZyIj~Mlyp~g*MeM+&Wz>l&t0-&O zA z#OifdJ12ZgA~3}xVexu~nS0oWy2ZMlu-F}KkewrI-OZO>xrR?z>kdrWII`5;iHXn8 zdB;+Bj4AQXi7C8er90G1#5*UZ>>63<4oriY&pjum@Q!uvz$D&fnE5=p59WV!cW_~I zb)B+QIPj$ZPnqzSCgP4t_l0Jft;k)rlYBoZ*U?KWjN{uL|VO^h{PEVd5tHW zW^^JFXE@#k!~kbF+{M8zAX>Bf&PU=5Z@7RM;0y=4ILrma0B1P0$caTD1~|iKu{o;< z!~kcwcs-{Sff(QnpTg#RA`k>CU?9D+<{3Q@5JPe z7kxW0spB)uyyFi=CLH?XzGC~*4B5V9W51M3faI=X0|Q9vDJLZN6k8ZTQb#!<*(+lc z14uG4K1en(xMe8!^Z-dVCWE|T!dM%<3Et z-tA=XxMcqrnEmbSn5!3II?}EZ$A|md*|9ERyoLeOy6~Ve%6YdA&A;fLdtZ3=?h|L~ zmdnf_JWbnbgi~n|v4wKA{p2b$z!WEA9h%?W+_|{1h5mQ-Cs&w3f6@kf9hzSd-r1k* z2dzW%nOb5Un(x*|s3pm9A^8oWtTxvUvNTIQ3`ALB@fMbwTt)!)c3A)jbGHDLNFE=@ z@%R=1B!7k08MLssvjRYJR>)HU;4)9;FV|XEBXN7#>urV{3HB^9fTYQT+k$z6z@cCt zq&U5-hD0lA0y!aR0^z1$X(hS5PDq+UxF=X3X%aahX%gXrV-3&6H?1$Rn*K*M!c5Cd-$vumnB>|YSB@}NC?nvK-5SUC3)ZEOw zA4PzydwMOdhz!!=if^a&6_`X1-?wwYKwuI-fJyvtVlqEaa8tgW2;#(Kf}q}}U=l-| zn9Pt;gcfqaq7zdnB0>wfU(t!l-kjX8h}usE(|0am400-q&_ZrkbhcA?Bti?hT+xXs zJQAUW+^y)sl)DuXoe>_f(87s{*Qh^*M=Z2(VhWE$I3X7+Ix&SuBAk$W6`h#EBN0x> zwTezm;gJX@$(4$T9*RBU>VUp> znu0f<^L(Qs+S%V8$%Tq&r|^ht13KF&JmT7bXy-C}bi@3XQL4d}^%aVCk^O2o9qRcm zU^16cvr900+eBb8myxy+OmZ8Y?PM;uBH~SVH1)GzXeV_?At7-x8SUcEV&XH~oD}U^17H$&_zj z#^t3!3t$S5#J6l%#Os?&T!|Vt3<{4}#OuTq9*J++u!z@*DLfJpZ@QSN@0{l{)VK&y zc*G)JXFG*Q;#)Q>;&oyQkHoiZI8x}sOcl5CIWN9t)8DrorGi_8DLm@$TLM#fB)(;gR^3O@C1?FvT8;Z`t%0;gR^3O@C1?FvT8;Z`mvrPvL)7?vb=e)=@aWt9z|7#Y#0~0=7Z%pq0 zTH-uXNGt2BrTzfg$^BnToJZU^L>p;?5zmJ4Jur z6(m-((aPuB-C z=lU-kgtNtLzJsvtTc!7e#z#gW9|IuL7&sBx@1flT5V7L-ZXqJD~XPyN4J3u6R>qNwB86ri4fk@tt6OpYgtzSUIxb+d#R!lUu#RDb3b9j(hIA>;Aj$dC`e85Y^Eth@BCQXtq1J-Y$k$ z!Pt&tU1gQs7iSSQ@n6=({&EKnd46(boP8>X>DI;mq)%yy_Vy|HHCT6eSGKOQnmbM2 zK9zj|pAE)ZPCJ7f^oAKzltH6`WdYE5!d3h{<^+i3u(JFIh~%(35owdh;vXQA!|Ft& zO&&{sfJhFj6Ojg!g+D;#p~PgFZEf?BoS9H>Q3D(jqOl`J;(!b7HSAwj@1{+!knM-^ zbpwDja!x=RIf{?~kOs~P$O9)Wq;bmt^Il#Vav7KYYFHCf3oUxA<~zxtpQCYiZTKd9 zC0Wfkk^z!Tq7xEBm$#C(_kirby`Pv=D2Jr|Js|t3i{`kzzIpT8}ThT(WPm+f z>TkpsU;r|}9xnDb;_ELOxRw3qrHO;GdC8Yw05ZTH-j$8G0y`iB?BQdcBRS@Y>d}D@ zXZFZ3PZaH60-0OGLxo}>ct%ew`o36;=jZ8+7S<*2f18D?9I&-`KA%hML!&=wKKuGp z4rZbZSne?blgxn=6R%M_$(sTu*#jr0@MtZbpI@S}7SGT9H0N9*vjCAlB^=wec)nkM zuEq0*(_erD0XgmO*W&r?QlGVWzUMl>7SGSq z%I#V_zgXwj;`x5-{8~Kk&fu)eBF}UzocesymPM9uSjh@5l!&FcuE%Xcy(-Fzpp-48 zMSw|xT_+~HO(mECnn`ZP_K&ek*HVII~;~@r_e4iMYp{)nS8@SoX~ko|BKtY z*3I{Fvu==X{!n4-Y9!~2_;?XkpWYEXKyn0+nGeX`%m<{*JR&|IdlMg!LVQv@1F|>o z0m-~)+Bd_cw9hH}#8<^$*V*hOqw6}G>2hY&ETzeA$%R$<8QeL+lbuy?;1Aij3^JeW zhg!SpbY3J2qpYu`S)|;K?pm5dj;YjqSzpAMjcNayFSyu}{l;3t)<<^{MUan7jp2-&slzI zv@yRh=aJMaT-U)>!8L@~fAr+YSWcp@uXW69H;3O` zYtHe#*70!rg^8@CwXCI8|JtvJfnblF&F5NbzgGR_YjrwPNSG|AuKL%01tx}`Fj-Dr z^{@R3O!i4?Sxc*>wO?=CzJAPAR*<(9o6B`pobz97E>~JX-WGmS?=_0&Ny({rU|JZv zpDi0pO~8_`Cs*lf%-7T5*xJP$}18s36>e_g++r&;gZH6^2Ub4lgR@JF1%R6agwRL;^3XPt->wdaavmg+>$*f+N#{*O=sTL8|DmP z=S%Y&7rJspTBf&+$tueMOtKunq}h#g#bh{~m^8P6Np=I6G_{?WWHpd%qnX{x#CBrR zyap!O3}6~eFJ~G3NfrZ`G^>G01|w_d4VxzzGQcj@Y*d=geJJE0Xl>1!urw$RNS=CY z73fTB=Td>Ltjy%E%T#me5+WA7V7FWa%3-+C##e7$wBxa&i*VM`Tfu^uSpqoQOw_ zGt?wQ2naR5VCrC-U`(+3W4XrqiaaLD`NQ?b8i5=fBr)IbCR;R5XKu@T3v8CzWJN3nT?GYsDqdnkB@ zaOAL+fH{T%MJflG7o79QopxBYksZYaZ@7;QD-VSAxSR|*6O@ui?RO*);GJOx;0z4T ztl*3Z0=5XSA|Q$YCIXJQ!4@GR#B(5znv70P#wT&NDWp9U>kV|r5dDFD05&rC2VH_4 zUjbFHDP&F2Y6{dMbsOHZjXL?nD0-=)eL!h!hU~!F%XL%Lc$FEzrTHN-EIB1^T!^C)*A4rh>5>-0jA7yCL0F9HzP`(AjpwcY*FU)qtH) zE70Qwy1YQ27wGf?yR0ktN4J`2W!VrOjWPz-b2K_iYZ_B(_;>)7a**O=R>xP8{MN{2laviT*Fq z|4_Q%A3US)%F*Z`at&@NZXMiKJUfwW=hE)R?!`;S#8bo5IPQVL8X~xZQ=d1`!mh|49>Goxl`rT?3~h8CwGfosuu6)HxI%cijpu)mIX ztj_bOtZ_&3Xf)o}c=QnXfD2T?plaM&9}iDg7B|J#(f=ZZ3F{Q^K^)wzz1UX;3v=pjxng()38*t z#yU19((+Tq=^FdkA*KfYN@EjeNzdBH=y26GTIHl2k4GRI@-k_-4){JB0tlyP6Q}{! zk|9{kAGqy(hQPXCoA;MJn=q4bqwD?w!hWI8r`T*N@Q?j3{@K@^_*C!>tm&pSf-n=T zeKwsz{X|OK)Q4r=rb>yB^n6}pe>iK&xsA)aS9dng53XF;cxYGG6;Bhew6`ex3RX3^ zW3pKC=V?vAW^(rDcQ?1MUV{x(M9L4g&Q?p9D_m@d*}J!Z4HvzIo$9Q)Gh#h>b$9pD_Ta+i#`ys{ zaB$_^&gP?on~UM8svNv_0QAv8pRj5$C*w(j<#ca-f-y$JTU-%q58ysN0jrj*u5jOH zO*_P~R9y>>jzVx}EZc40doYEtA)kG(Ye7EFtAU*X>h&$hc8NAs)XFbmUt<5-)nd__ zVB`;4yJ+z+z0~ZlJ-E5CW9ixlw=SJ~bz#RkTI0(Tfcnbfccd$w=f+75B%Ni9rH(cV8Ohj+esaNq9c=GNfU zpm?n_RU#VI)K!(00{79V5(L5O?isbb|%ZWtUW zjP!NKeqo!gUcL;w^x)>!?%>?k#v_*xYDIjQjRDw^<<{G}4;!g5JlMK{pS#!OG!Z(# zI&)3;S*7LX=)loFT+`viq4xU-<)$&sv9Uwb;gYx58sceOp|tz~OHr*Hr`3Y?D_6v94`l4S z;Y$YmvC(yx3`+zYYRQ;P#RKG{g))qv5OZi+nyl8*Xv6TzwVER2#{41+_6?YSM!IrNHiB_~I0`x1_(W}&==HGb0X z-YwaB>_^45X4yHMUSD!_zS2Bcylnlo^FMvQ#n#_dQ8_rC@G22{8zT{h{7!OztSk&p zy<)+tu+O*U37#x`(tQi8ogSLCs2JZrxVan+UU2on!F`u^_MD@|-nZNFBKw1Ns>V6CE-CkZ#8S{ib&g@7$V!}V>b(R9ZQ=B z)9UoWz5%ka!1`cHjJ*Xd4L%}tX_-MNy~2{V&qcA*X}gw$`r3ViYpuC4-8pU- z5xq>VVy8D}1O3p}MIk6X`C zM__ECQ+)8);-!d~Lg)y++r)N!5P_b?<=V(Cp>7iNpKV>@r{)jy#s+`H{A$P&JO1Hs z?D^HUjkN!y#|ke&Nt4QxngsAT%0*qAi|DV_F55+Vn^q48tklcpD(fHz_%SZ&}+c2 zx48Dg(zSbAf)tKHta4<57{nH=4n1c5lKhYzP2}km$mSkjLt_Ue`wYf0{*s<1^N`cZ zoKdVq(D`)6Fwq!_d`L6Wd^%XAX2r~SKJ`#79pm0#7}gu<|5@03CR~J#vVJuIn<~4> z#N+Ht*TGM?nZg9Hz<9Q>AmTKe0L$!?9e|Bb09RPV)MA7SO~g_u(uMd(AeTkm%B*^ zXl%_Q9#PP59<1S*?IM6~XOsIFmBUR9{5B4rwa{$Yxf*PE(wxTT#uS*d|D*#COTq#W znRcyx5;=@3w+T3t)_s<1MLxc^1@3;YFR|%#2#0acvLhinH$BE@g!`QyBV>48bK{Dl z<3R6au~?is?LN>ovko~P_;ub6rW01(sY{$ig#=;0?7)he&ekB57@D+aN2B2bMSH4+ zuo^Y)wl=R^@ky+Y@j7cIar&&Y#c3Q2#c@g;Asu14gu=|?JSi%KjSx;(B-K62zgb#! zWE`Rh5@MSmLLO(rx!MB-%bqY10!>iVP9`eI!)~nmsOyJ`(7e<}^9uJK4)S+~PW1{D z+;#vLt%1)u0n*;74ZGEG*2Sl*W(0};)osY}?Wo3GcMeX&Fc0pzbMU;ajqQgKWt=s5 za0^aEpF(+|$vzp&;km#*r+xgw=UjF)#x9baeMNs0XH9myo%@CWzrA1Fh(sLDgtwzH zVo&Mx@^Wn>oPKHglWG6G#8p}ZMX{CXKF_t59+{P1{UtrE^l`RuR>`-|!g?IOWtlT> zC4`@B-?Gf}u-e5>l5bh*pTn5;`<7!H(6#Eny+-9IzQmPwvx>vV{!3DHVbwVdyN9gT zmmC8(cPZ-^F2M1%kv1x;Ip5RTo9lJG$P?_2X-%bO!dz>*tY!kr{dAM##;MQ_?I!Lo zQPJbjo!t{Ro9~C%bRX5iw9>hPin04V7X=PI7`)?7fp>4L6}zZ;WBczmj?k4_Nnfi| z)@vA!@MD%tsYQ_13a<6~7|&wF1rm~)d|!bCR19lox*ghTTlKfDLF3^rDkPl0jI;1p zAGx@F^${(R@ZxlM1Y7RCS_xlr$BR!v_*v}RZy)aw=xd~pVtsNMHmlgzjh$G-yVk8AQ4tu`UyX zS2$jST6jp_A}F}0g26FS=%f%E~xN2OA|E z8=D^+O!TdA3~{dlp&f2+u_u+|f>wRF8;}0`9c!~WsjCk=q00_b^vIbAoN|DVqiWe@ znIS8i+_Ulfq{V#N6*YbF_q*e+I9zGfzxS1Ggqt=0yEiTdafIIf>dj+TY|1^GR|S7K zxtZ3F{Ri_WIJl4Fk2Y`N^UhP7RwcU|`Z~1VI^dZ89tCgQY))d`m40DXA?iMlUwC9| z-h7rUH9J}LDEBNmz0t-yTPpY;o>ULdQz1cM~Zdd^_Yqh+pR&MVdM8 zWiYEH)qf42pwM^)DFn(tqaZgbK*Qdngtu>1KPA6yJJ|zI9v`^Qd}KHZieFFtN% z@8@IVq6S)hM7qK`IhJl^`&O4a-u7T&d0k9D!jGA|YRgAvVa|OYa};|RSLVzvhUggM z`jo?)JP2g4jfap8LTnT%u;rJkf1#`jezsgAWA|8eO^z?XM`je~vumkQ>|1LJaX-`( zfi@f!GZ89jA^#qpuF~nO!vG?RH5{k#RfA0x>X4vRx?Ph{ zR|nS^0UP(L+-wCK&ju^6Es||3vtm;#TiPBXs05G`n-^=j+Wl?5I!+pUNR%42{6 zxDTbo4icw`aq|ey$03Gp960bmus9{+uH#T~gYbRYFy|atY?x;pI7a7h9h3jbW4Kql zRJh`(n^>;t-%a(|&UD}W20iRF4C+>PM~u?06#M-Wr_uLL8Sh<^vFx0&-MG{>X@xJo zS6*sGK*Ik1{2B>dTXbOgExY2W`=cKg@rc#a7#CV~U+f!tm}l$#{CPjC0Y&$K^z=CvnHd4AuPV#orLS(QveOcyb-s>RXsR!j+~&a z(N>6mo|MXLAua^#+Fq2q-JycZS9fN)>2f%@^Tj6z?IVw%=;7AI?ai0om&*L#I=IDx zvJe&YukUXxv;Qpm+FSk^YyG^r2iAW+R&}6#CcJNvDVs6Jc8{ACqjJ&m2tUTL#`HCn z$9G$Zs>~hDUE^X)(}By7du6)b@$zM-i|rc1u9+*0Clb-RoE~F0y>F?hBm0!qE>~8E z$~}_~Y2*+Z&B|uksyg3t@BzBau4QGZ4t0X=2HEI^sheN&w(m$LzGW_qpeSfoo~k>m zRgGYfUpuH9{Lk$hTU(36Tle38`ziPYqkXB;C+tgb9M1$vvvMTnZ7eHCf*_FcJ8~ZC zI2*t~?W^N!&2jTh(T-MZmpKDBx zwTG2e<#K(@;oK7ZHfPyvtA)K1?%l{QXkF@^JUNSVtv2a>t8*Q06fhy}LQlD(sLzF- zcJp+{fkSZI?cZXS9Ju?&<`;q*-0PWcB(}^)X{TBCs`W0@+w3pN)uV*c;d&mwy}#B7 z?oh?NM$?xR7(r4%JG)1NkIa#s@9vf+{ZM4Gn?ya<9&f~EUuY4XZ#5QEKDtkE}g zGuMSH#RM-E{2jX@UOn80C%TMRgCdbwPLRI9J&HI|h}C5w$3?OK0~Iz|AulXIMST`G zJRV$W#;S(Az;5_Vmw6tiI~eCH4X5CMMSPPtv65!Mw&RODu8yu5^ z?&mtO$*gqO;Wm}WHaVA-19Q>*$Tn}QSFEfinD0}ZCwAM@IIlFu6+AdWg^hffZnd^M zu*WFDJuGq69Q-KUX=*~F1J*2wFYRrt=kh2>tWoe4F#YP}3Yagr ziYo-Vy|!yw*>TwJANY)>5@S6Neke8klJ~Ulm`l0Ld&-J=-H=1E1ujiQmFKp^4S#sD z1L+q1nOAB#@C&koexnKp_-JQ=8>wn=!w%?>-uAYqDF;jGQ|1BO{eEvG}noI%U&KZm>T14r-YgX%rve%KCUC46!={G}ps z)6KlWhwwj+!XNY<6vy>Cz1CJNou=+Z$Q0N6V8Mcv7ZZAna|RQ;W)l@)s!_TNao>*) z_|5&s8ZY6@LeWBoHk{y|&Ln)tk^#_3ji^5A$zJak(E<|u?sE=FTAux8G4P+Pssm2+ z+LCK`2jHSlJT29pW~H&N;^L^C!GoJyy9XC^I1=B^IZ*;(Vc!8{^xc7$Wq;-AOds1kM_42ziu~SffADv*ULiVz9;hZZg#M3p3mMxEH>^BSl;oN z>Z|T^pjh@Is0Tf(e#5H7)VT{6x6bcuZl5^wigIYq+N=i37w&AldUJd5((!O``_9!X z7gBxg7hc-Ev@^J^c=mob;Gi+GPsBg^e>p5`gFWirVST&V3>c`IP!tDL1&5R9XtFl< zNSL0MDWnef94}OSL9lODdth;t0>_r--{W+*55*c=T3JiBS8hOS!z~NdU|i{p1Xw7Ap7sS%Xy6L3&Q^R$8uaT@~Qe zCYa^f*HWCCI{2#&?u32o+VwwU*=^;BmAO9yd;lc>005{@6vO(gFf2{E{!RgFVnxb+>QvCQ+r)^7e82hTVh znmGTu!M)FYNqx&%$TeTQv9o(cX5qeU$C0cUE*}k2)%o|jSML4B5k0E*5R!pB(%#nS-2_+Hy?}d<^!~6)GN8aEV~CV71U|V=D|Y zvb#$mE`YRP|Bv=6Q_`(+YygHxj zH*k$T1_QX9-3uGPd;mFoU@IlgJtMk1yVoyOw3?qFT~^Tw;f5!obB`h#Wpijw^yOW< zFxbnxHructA<_gIKHi_QdWvOry^imv_{?IYuGfLSoy*cDa^*t;K8I_7{PGy6-?>@(_E z7_V1KX6gPlEA4gt{p%5~ymO8(9}tg)W-|g?jAR3Bv=yGVViT}ePjqFIy*O7UM1ZT6 zYO_*>YD6jK#91Ol05uO8x5n8-+g_unxs}n!F%W!yrc*_i9CRUKSuX7LN={?9pSB!% zm@z3NW))V}L@DbuPsFZ|%YW#!ua3UY&KJX9T!?quhOZ;Pjn{ark zJ}|s=gfn|?h?manzJnd;a4+GK-*r&!Qdcky$t%u8*EpNAe3Wd7Cyy?!N@GUkSG7gWR=Q3 z3_j+=$-?(7Zg#9!v#dJWhru-KY2lCe$SmB14}+2E?*Y^(FM@lxaGyN(q4f|ld<+*V z?xGA&HN*wq$opbDh@b6$asPV<1x8HBmsPpzs+p7rl>UJPZC;))%SUDP)GSm`ovp^h z2cG*{6c^my*c#lsxeJ-{#qEa&_u{{vL}@ncth>#$Z{{6Ez}lAyk5pE(Rl%oN+&8QC z#YR&m+^t~hSzrx+{>r({?adQskYPwqSD>AH?8Nq^^PBcGeAVk;_4>hJaCdX&DYxJC zqNjYpO;3IIQ}CaE^KHL;?W;cFDeu1ZT|ailo%c7?-x^h{-fvo?zJzt=}qbR zC!hT@*M8zzKa`&Fzt`~Z=^6jOy_cTxd-nV38F-Ha_cp_^zk|P*p6%~+KexZry>EY~ z!?C~9;oJXqf7ky1u08g9T{{i0Yrp-S?7QsekI%l#-oG~cF2hOBGyL>C`@89R)}Hh{ zYiD|%wg26QbLkU4;xnxu?b-g0^`kx8-?4tQXZt(WkM=z4xAcs^oBrK?ZvTJR9{atn zorc%7KOe8|`IWzU=H2=8?EN$L^BK<6o@e;!dG>eH^Q=ATdDhPKJZpb?o_*JChSQCs zJF3=z&f1g4(Vn|;wC8Rd?HS*d#xeW(`!4&t>3P$jzhnPyIB1XcbJtGm|MYBlUHiN7 zvUPR#^JLfT?^yfn=QEu2Jj0*b&u4!(JLvm38HoIQT! z&oTbo*z@e~PVITtp7h*}WBT1S?-Gw@^Eo|tJTDL#$6aKg6CpKg6CpKg6Cpe%W)!FMICzWzVy5PwP*|FZ+4NFMICzm40`AD5ng;nQ9-{ck`2QR(@O zZ}{@*zxdpzrRVqj^c$w%^__nuJ^wGi@uum!Uh|>H4d+>Z@#g6x5B+(1zWwyqPs>mK zV0!+U&;Q2h%Rc`p>HR)$fH>GM7!J%7p@zjgYDuX=iVe&+VKPv8D!H>Kxa{+Dl? zK70BJ>G|&6@0fny)lZo}-}-BRYyQsHfBfH0&-S~+-~62PY?#0PAD@+;?QdQC*g8F1 z8y@-SCOuo*PXAP!o~_Mq{gg?1wr|<__`RRoH=h2nQTn-k`_l$xdbU3Kg|9r7o~^I` z^V4rh&(?>({pX*Np4WZ*#P{vr`k@Qc;_@rg9DeF&Y)rrCk6x9YPyE!&rw^15rsrqA z{w34reEWs;Z12DPS$OBuo^j2dKl0%RrqBPizm}f=`_s-%v2WY^`5!+#eZ!~zm&fg$ zKmE`n)9?S_`_l6de#F)3*WLR6rRT5wnXj0B|NDM3J%7yCzG?dWulTj}{7paiHPiQh z@L%u!{Nul2{_|H<-!gyy`JedhbDVd6=iBG_pY+am%>VA+eCGGe+w=DKe($`UkNm~= z&D;Of2i`gVuJrTMpPAZk@4w;d$@FYEFP+rs+3=tK>}h(ozx#o^&!%T<&r_S{rDtpB z2Y&Ug^!zbs|M!2)-RarB>lc20@7cb$`?>W)_rCQ{hhzQL;eRChv-`W&&s}@0|GRdk zahbKh&zRb{zw3wp&h*s}JmZ=@f9(JBcc)+UvX8!IbKvIRdT{!0Kkb?6=fC@s2d7{B z{ZCKNKl4TBr+@KFACca<=NHdUzx-d_bj{|;=;n*lt@abs&p&ze&~*2ak4o?V@ee*c z{n_vR;Nyn*uBTp@e$AgeExrHG{?(UG-~Z_Vi^x^oNfd{{Q)Pk4*pc=8sD6U;gyV)0aNyY3ZHu|8aHt8UOq5CH&XC;mfA4 z{j3i>Zr}2CU-0_rk6!zo^z--p-lNm^p7?`=^VWZGb^6AC^P%+455M}2({H=_Tj}|W ze)vt(-`oC;^!`8j$*-Iaf8yVz_fLJ|W7EI+tUpUX|N9?&*?n=J^ibvzy2$~o8JGVN8dR8(BuCpJwNT&ziRqhfBHx1onQaHH&6fFKm51pcOU-2 zw@m-x=lw={=a=91)zd#exA%=V{oI?Uzx}{}Oz-^KfBNQm`#lO8<+3=FW)x(2e0{~^!`ns@?F#Vr#_J0|JUz%+jRVk?@#UgdpEr`^@EMYm!AIC z=?^{azomEn;v3#R{k8A;@9B5HVEo+Q&-&gp-)y{o`u6Wj^U(00|3hz|e*0TLGQIyNr@uSRF?;79KlXjo z-~P%^O5?usPH_1LJ~h4b^|yXcnydD^Kl!ZhO7qIT>lLs1p6Rc=fA4+!-S_?cApNfW ztyliR&FOdF_xkUduXS&H+B?!5Hk=D|BcIrG2! z?@!;HzW1>gzGIGKzkBfqKRvzkIj{Kc=^woD*7SFq?eCucU$3ju`}Vh9{)`jp=U;Nu zJEs5Q`DfD4AN}I*ntsEhpPhd9r@!MJ)3Yxv(mOVekAC*&r=Ne>mwxAT=PgZo|9|`C zw@-iRvrngYY~26eC*P5tZJvzZcV~Lv#_>nqds}+{fBLU)oBrnID*fEX{n58RC%ylQ z@BNl({l4d?pW8h7;xlK{`!F8#_kPyf*e_Wst-{^47uU;MT& zNblG@X@6{*Fm2uYkr#ep`uXSmz&B0b^O4U^zx#1-earN>HlCN>G2Yql+IZRf@BC}e zPw(IL)VEB3_HTTCddGPBp|{?Zo{iUk{KyN^`^G!NvGKCs{fT$&^^fuN$FDv&z5mWT zADw>VPdzuiZ@m7|tvl2E#yi8e-!-1T?8VPX@BHW;ubaO8&(Egcoqk|D^|`%cyney< zv(x)u_xWEj{ezd?mfrcAPrR7M&f5Qt|MbgJKigcjb<)P#etz%Ew&vsYnLmFu^{2gK z>*~%AKP%zb+WVUS{JH6UTPJPY?eCtt?aSulW$WsF|L>{v{x{t8!1S@-``hV#TZiv{ z{pY0jZJo6FV83hY>OURsVSdv1-1LwC>u08)+uHlfFS;c?|Lo<9)A#-To3Gva%8$FP zvmN%_*?N2KY`r~qwm$uQX6x;_v-S4e*?N2KY`r~qw%(p?yv)|8pU-T)J$JU=o;zD_ z&z-He=g!vKb7$-AxwG~5+}V12?ri=1=dhLC`({J!xwG~5+}V12?rgn1cedW1J6mth zovpWL`!2Kf>E|B-8im& zw&Uru<>NRXU-;Peyyo56)DOp%ce~Gf=55_x^?&{M&$zAIEB%LG{e;`PJ=8z`yuW^1 zx3{wQyI6recd-I{?qUV@+{Fs)xr-Ipa~CVH=Pp)Y&t0s*p1W9qJ$JDJd+uTd_T0q^ z?752-*mD;v=$yPU zVg>fx#R}}Xixt>&7b~#mKK*ZF)a_I3x!Z%-cy;?7`+2t?vFC2zVefSN9UIeb-()}U z_B-}|w>Pn$cl#ZCzuQ~cbGM(ece?$K{cg86v3I(CmOXcSD0`>dkJ#^a`yKmvx9_l@ zcl#at-EI$M?{xbSd+zof_I|hDvG=?El>NNh@7Vj@-o$?1?RV_`Zl7h(-G0j6>GnJJ zyWQTz-s$#P_T25EQrl+x5&PY4zhgh|_8s=~Zogx{+wGz3oo+v3&)vSm-tYE1_I|gY zvY&VR9ecmqo7m60{f@og?X&E;+fUg$-G0Y@x7(-KJKa9Zp1VDiz2EJ3?EP+UV$a=P z!`|=qP4<4b-?4YPJ%~Mb`wM%g+wa)#c6%uMdAHx`e%JOO-QTjkhP~76ckFk&J(oRq zd#et|_B-~w-F~F|ySCr4_q+X9_q(>YvUj@uj{R=8H|hSC?YZpd-5$h#-tDLCcf0+L zz0>VG?C0Hn$KLPuQ1(u@AF=0d-(l}}`yG3~+gsVsyZw&6-|a{2=iPqC-tYEV_T25K z?454EW53(&P3)a+pJhMq_8|82Za-ze+wFJkoo?S@KezX7zhm!rdnkLS+mG0Dx9_m` zyZw&6Z@+7MEBkr3-?8_*y@~z2+wa)>-9F2nyZw~C)9rWcce}lbz0>Wp?77=R**o2S z#D2Hi@7T|~eTV(L+wa)#c6%s$r`wO%bGHYv_q+X$z2EJp?C0Hn$KLPuDfaVjzhm!r z`z(9z_EYvwx8Jd!cY7;)?)FW&?dWWZ#qjNUZI|2B4^g}PXMgpnmeWdFgWEsmDe3uN z{?9-5&!7Il`yaQTKj*#0ZWJJ_a6ve<-&pzkZ zQ_g?pes}H_ulFuo>s>x;_pV*LYF9YB`V?*a(UCK9{Go%4&tP;Z17ibQFt(HL$BU@b z$y1U${j~I*9b@b``^MOJf5z15J~O6HSBEimx;g^vP^YWIm^wXq%F|DKcG8~xv{!H1 z^C#{3nfCk-ymkd%djqc@u#>|#>h$`JdQDE9v>6@h^!h*T#U!w4hNB5OE(_+`A zsH*W#^WV+>IJT1Us7o)+&Hc8d@lA(J%r!jYn;iOG&weGxAB>F8V00-1V*^_-wrL|w zolc&T-07#K@9Y?3$JsZ=zWXz#PWM?5+nJbibr@5ptHYQ&T^+{M>B&=`e%iB>_Uxy< zdefdif#+x7`ERjH+J#*0ML(CcEAaX!@cNB8&)K7gd_0vX}`e`Ff{j?EQ?BFDJS;?tG`qTkqhdN;F^9Lj2GZMPIZf^SO((0!EbITtb3}_rIh1(84%;cXB`7As6=W517 zcfU6G!`KSOr`4R9d-~;K#yt;tE9d^wlykDkeP--*BUi@Q*@&F2RAM{g|NQ6bM{a%W z>O?<>9DVA5u|pj&_W6U6@fnORWngSz3&u8e!2IXQQ=Wd>vy=Ahr@eXu&!52aGw}R( z-~aWVNwlg#B{4~af7njt(irq&Os#_deEc-C~ z$YuK(SHJA?T&inn<8#YT$qjwx`!ul*%DtX*f5uLhbDtSI-N=VUD&AB>F8V00-1V}m+iY*PnJUwHDAr=Rxhq&@p-uimuhPvH3( zc>Y@-$Nn6QTNQ2{YJf}gUtC8#CE2nDFb7}i;K;J!*)DoT+>C3pHc={q~d*tzP{DaMocdL{i% zt0#;HPhOZV8nVW?-5JBv)4u=AxXUG1rN zS2m5Gl=b>B=k;yQ>+_r!i<}puoEN*SA5+Kwzhj`%`0rATljj~fGTY~iSB+=(n3SzF z{tg>6&pk9VTe{>BlOKD{+fL_flh5o?BRBGwUmH_)b@WrV-0@3oTph9XXQ#i9=^T5_ zWw|ATk6wyS_iJ{`wRvQ$>2y2k7FV`=iZQu5>XLhV()n3*R=&0+TfWRirn9N^R9AM+ zQgpgs(=*p{-2&6;T6S5s-iganjNuPoEpla7WYJmqTKn81S8Xz#1CPBkd;08RS#-kv zpLS*I<nqPUBNQ?H%i!HPn^8 z$8?r#tDW`gN}YD*9Mh@THs$N2JfBnd9{8l`ypX!bl`Yhj^4jj}xUvPG(_SB@y}Hs~ z+tXewQl8JQY@rX+UK~?i+g;g0EYjW>NO^te$`)dp_Qp)gi-jv&7#nFXj!wTYmQvmr zNPA=EH_!0iv;D4|%jG`gVSl!q%YXLso(Xq7tGj1oo}>TF&+5dEyo^1O+(b;y0+UaW zo518ULfRT zsgv9UrcTBoOr3rkJvlj-^ex9p>{#vtQ>Rxiag;ygT*lb&{I}<)*pB5~YOm#J$kF%u z=f9ONd(R&3xhsCQskUX*PI+G9S;F}pIQ#DTq`=f`&yAAv3`1-^x#=Wj?b$Ep%J%$+ zK0bTTJcZ}OYFjFsEl)r4?ZjoV^Y>>(SFb(e#Wr^<=p#?c;{R`SJf9^u9qH4a#D~Z$ z>vRhB=Fmy}v9ayx7y8ZD@!CsWg+A=@_%)`FZl(0q#wQQ0k^AwzONt@D1 z9{(tJO`JHA31fv=u?O6PzQ{C z{$OO(0i#P97#rAvu}vLt(k{u&?Ur`U^+N~S9=kwc*XHI#< zJ-1(J%s8sGrJ3<5n-7oNpRtoM#*CeA1;&Kma(&Ku|w|aM4p3@Q-}1a1I7+@ zz}V*xM#g6_y3_$<16we*sRJfa8yWFr~$Lc_zHhJ}09mt)o)dABtp8pm*8ZI$-*eKNuNx#CCSGI$&%#|4oi`~1Pk_zXsuGB7q&2ezpLIsbWb ziybn2^z6`wvTw0N$I0k(lRI7dQGQzN&~dg4=T!8i*Iw&)bm&X3e=JVOvCkh&Us4B* zE@fc+qz)L{{yCL*ezogd(e)2!et))e#a;6&9?$<<=9eEYnDvvn=QHyWIqMAbG+ASJ z?QyP8v`*3|^bLIkYn_DYOV%>US>vS7+6QBYH4)Z232U8%wNAoXCt+;+&nMn<%dY21 z_x$!}e4cc%v}a@TDdro`nJy2Ch;hun&A&Vy#(~Q6Y-8uioD-v?TP5C7-6+s-({CoW!J857@~@f`$rZ`%(X6}kIF?oPsmL7n49 zMeZ)D@qlASM(&QP@sj?-BX@VzxaB3oB6p|NxM=a<$lY}{?vNiCxjV4No5%Ev+}&8? zx32FKxjVDQ7hc>ma(8Ks&nVR`a(8Tvi`VTOxx2T!bI*KtFgNa6S@1X#_k=($lZmB<^6gU?k-Hh zA9p9B;HSIWQt;p1g(deL|Hl#Q|D?kUG|XW!jZPSbYkb@!Bw@yFd$HpWkP zPubYrU5ea2Wnf0*Ivo#2kFy4vO~YgKK-eB>1X*v|I1H{OXB~(6I0^u-sz3p zd$s}W-VKi2ow9&2;NBUI+`GFbpMB%_$lW_LcJI?h?w*?IxOa~ucaJP!oVfRsBlpg* z$%l4*Fmm_KO#h*0#zq^uHa59?UpI31)J)&K+Z?$&WyT}NjEUU6Gt;@W!UNH`Pmi~< z0~?Qy4*cOH({b+xNA8}Q@zwoCMYohW&UD=Sw2`~FXk}Zk9T^Q;nlZV1e>-yb{!H%P z*Nxo$L@WEo^TVSO@10;ew;nw>a`yy{-TSnWyH{xX?!EEI-TO0r_nvU%?kAf3p0W2u z?w+9Ozf!q>^kUH5D=!-qxqE`K%^&(j7jAE6Wfy%;x8P@~<-McN>%?WB zc6T6IfV*(p!8jRu_1(DdEA!I8TMYCQMxTceu~Jl^zs zUVnX5s(2hb_nxhdH^!d3A7SGV`_n&cA2p2Xn!bB?*Txt+s~cSrx%bAcE_X+!uwJ>l z7&cZZ>)sQ#aYehj-F9{4-b*)q%DTJ2#?;?`#{r^Kw}$>)t(%++BFnr!IH@ z-Q?~a=4kJd+tbv0dhd2o=FM_e*1hK(x%=;?Lmb_`>@@9i?@LFsd+jiN_a1fR?zx)| zad-E))ASYN#NBf@ed6fuWt+ZxA3NIe&K_o;xVwAYrr+b+F4196ePH^G6LXTUqz6c;xQF$M)SgarfU%&boK}&udMd+t?$jbniD-*1eY= zx%=;?!@Q#`?LzE?}kNJP5j)-x_A4n&(UFCyLUDP?3h`oHb^lI+>8~z7F=~EY1=D98cK@z|>9bBU9w^JY>i(Ss(<%4!xM*#QeNE2V z>;5eTtW)>UT^YbuZOkQ z!`ka%?e(zsdRTkC$&5uP?~mUMYR{P*{7t$&5uZOkQ!`ka%+QnXP z@?@`vwb#Si>tXHnu=aXbdp)eZ9@btDD_;Jy+&{A7xa*ni&-u*e$FUG!_lynins=LR z9{pM89e00}t8(W^xf1t@ltXccNVygIIxB#6Rsid)0M=Ontg`}GX9cj%3SgZTz&a~{ zbyfiDtN_+o0j#qESZ4)d&I+W%SplrG0$67Su+9o#ofW`3D}Z%Y0PCy()>#3pvjSLW z1+dNvV4W4f|4#oCBjqWuauDLBd-#(m3JUlzC&5%Q0OQhft7cluY3o6T1iA7Z z^p$79%BRd`lJ8Jfxd}STvtZ>==qMkdtnwY?$~%xN-=VB>D0GyMz{)$&SH6S3@+suX zchFaEf?W9y`pUClLuSnU-_5Hl3Sspe222iO;i^- z7joqw$dyk~R{0J($~%xN-$7qF6gtXB%x02zps#!fedSijmG7Xhd<41j9rTrF!OEx5 zQNBZ2{Y}=qoot zu6zf5@=qTSouG|V%-sJBc+EX~ghj;DEzozMj|LVTHA>AVkH}9T5 zecCTYLp$^gf6VM*+~xS*;i7tb8sGLopRhzxapS>P+#7CLUBbB9?0(@s?MoS#f4qO# zw0&9Qpxc13{<8AMW4<2{mO8VN@f|e=hRwd(uORO^s%k;MWsMrf*g30XEo1C=?|7Io z^-e5#q%r>VtyS9?Ki`>uv@!kRix&f9dT7JF}N|EZ84# z@GXUUrC-M)?Sj=VSnYz65(SF)aDXjihHWYjKn)L!W)>xtP( z))TXztS44)vYwbf$$DabChLj$pR6YtZ+>MoAE`_86xRHOHLqdKcUbEH?5%qlZ#~Rt zJwZq7jP%tHT9=S(y@Iul!CK#7t$VQ6Ls;>0u`9$2R=i-v3s$^f#S2!vV8shoykNyk z@?@Pf{bZdi#0wp7oEPGS+?yALcp>-ZQ6XN)6)#xvf)y`V@q!gESn+}tFIe${6)(w? z`DOaa{4zW2*XSr-u;K+PUa;Z?D_*c4FR>p-c-OqM=dMB==@Z2fRvcl)5mp=}*E*wp zANlV!?{0j!UwF%2zZ4PErD4Z#&D8D2&(ymr{4rm}#>tjCw}cnAs&Bm4_)ymhrm^AtOpzp(aG*o(W#cjj~Zzlx(L&v^08 z{HrnG$uoXgZ(LVj1lth!*;1*cz~MpU@;`=0f|MV`h%r{dmmGohJ?m%ntLn&+wR;*SA&Am|X1F z3#(pO^}?zbR=u$5g;g)Cdg0f;x<8{>{7`;Wrp~ExTwXcgfy@E##c`bb&4ZaEkBj+^ zz7sNin#W_{;3pw>A7ueQeR8u;DROv|=$ zd;Kx+XCAAH1?y7B4G#sM7sYKkq5AZo^JVe;+Sy~H+I#(jeaEJ3Y;0INIvCTpvGKz5 zrUp~$onUbvt6nJz#{O8}_@#+Y24l9@Gydk2r-JCqV+#D` z!3P&~DpsjsOxg1LRWrusE%mD!Q`i0-4=~1uz1Qz&jBgbORWZir2kxwF?633Mzvxfx zU-0j>r}%3%F*@$?c-Q5rCrCAir1XA8=4j5_bp2m^w-{aOu^2Br`Iajzh~C| zg?cZ2uYAFul?RnB_&I4ziH!U|;`+S`?Lw~hqOX3yj`|1t>No0Df8vk&89&wk_^-Gq zUUl~vl2N>1#mnSLykNx(R=i-v3s$^f#S2!vB&WU7Ctk4P1uI^#;sq;Su;OL%Bwn!M z1uI^#;$`wAUa;Z?D_*eT1uI^#;sq;Sk`piK6E9ftf)y`V@q!gESn)D>5--?~mzecO zv4a&mlkb{qHpdk^`b4pV6+6lQh`B~x{Bb)4Zu=YWC^9jB4?DapEn^j=sH&^eSKlR<}CeOdoD}T=PgNzTqq*uPt$ODb9 zU(hqZ|D*dGPh59TzW09n8CT!XBVY2x%Eo)G=$3!m<(SwnKdwvu&Q#3TTzFTW{RO$$ zuNPLmuo1D5b=e`eOeAcr!JiGK2!JK7rUuEl`5%ky=vvlxtXFN-5 zJZsD_&efk9^Y|>euP-@eX|LuB{h)b7|7d>EZ<=@Xr{*L5ta(cRYyJ`!&1+((G4IFm zkBpr^t~9o3yT&%Gu?=f%!y4PL#x|_64Qp(}|2U`A_MN@fz1jNqe92$x+q}Nv>pSv4 zza8@%x8IrntYgfltnZxv;e~ka&!~NO{=)V3O#hc=UGl#?Ti5uZW4h+Yc8S-n5o^2V zk1AKk$q(HHr z{c-I;V_T8M7?Swa*I@ z+c~e!Dw5B4KQp~ZZJ{ppGd`#v&{6+TR{e%e^(S?ypYcKck8g?#J}X|dMRC-A@gMCe z{vNb5&gJwxi4XpB=D&Jw)EO`Oe}?l?o$uk#?$`9rbH)gtb4;H+XN+*qulnRUV}!HQ z`sO)fgl{_Q-aKcF@R+ym&2z>Gf7ZNTo-;;x{p5am&KTj%Z}!V`#t3)(xL=+#Mlt6n z(&79BrYz?tFg7_qfvJo06Br*jKY{U$^Ai}KIX{7E3+E>=ZRFer*7*|rXZ&7(?=tYs z&o6X7hTP8=bVi3_ks1j53KKfV14fc>w6zq=Yg=Ee_)>3jy@oMcH&uX$N4eq zc?limFR=D;cxUDg*w=FltmhV3&n>W?TVOr6z6?k zYL&U-&6w}ZU!57}-g7{{<_RRVwb&WU9=$x7VbRFZ# zMO`v0s~&AUds4T|A(tIxe8I`x?aT_B$ooBhSV8~ot%n$6=cjXO8Dsy&*J~P6?|Xe~ z7~{{0cUL#Y&wU=PW{m%5XJV#Z>?725UY&Ca@=*sjE9lp}_oRZI3kRnP_8-2cVWHmI zCmdVwr+uwsGV-&{Nk|n(XR_tKK4p!`7#ST{NV8u>yVkdq21Xk=|#ST{NV8sqr>|n(XR_tKK4p!`7 z#ST{NV8sqr>|n(XR_tKKPI6)=ePRbIcCcaxD|WDA2P<~4Vh8*2^4D-NW0gJSkJ?96 z7xij?fwk|z+K*uEQ?T|gSo<2R{SIcYWFLh6?;6C&{kDr)m;8NAOinGI(Gg<@_V;2~ za{5y&x%P47+TUUA`>>t|U_B?m^a;-ou%0VmJ#WCYh361h-+RLP-V@gMp0K|6g!R2A ztnWQxeeVhDdrw&3d&2tOQ>?b@I~|qfnFQ8%Izu<{XD`4OzVNjl^;u<{*Pc@V7p2v*(%E1!auXTi$9VC93bayM8x9jsgr zRt^X&H#GeuXM~kY!pbpWoo~Q8bAWXg0qcwc*4YKDGYwd09k9+oV4aP?Ix~TFmI5o^ zhjk7h9rd&FcjU_JVdeX<&H-SZ55PJ%fOVb#(_THp=-dOj&Lv=-SHL>QfOWnB>)Zp@ zc?hg?5?JRau+DQNC;yc``7f-q8dzsIu+Da1o%z5z3xah<1Zz)(^$Y{+83xuf46J7u zSkEx9o?&1;!@zomf%Oa{`L5^B6@_OQ`b5t#u%2OHJ;T6%iJDN*w^zFtmiIR z&ttHj(_lTn!FsNP^}Gk`IS^J|_#-(ieOPv2*@smxEPr763Cn+2dnn%>h>`oxFgts1 zRbBX?Jr~wq4F6u|x_(_^wU={OpQ%@Skk9D&&j9*f0J**|fPb&ONp<0a_AFR?8LT}H z*4_tePlV+UEI(oS5BqhAX^a2-BSv4(13sg#e)Aa}Js%35tg5@{D+n2`b@k2qkhnLYWS%$XW60bACWI>JSdM=8-MTb^;k>QUNLR-+b+fj z_C)z6M&B>Hv(GV97yjsc1Kt_mHIw)8jtb|ZdM^>ydx<7b-b;jcy;B;$`>OX6=@Y$| z2|2UbXa*htUMi7o(?NdmweZE4gdak4gdK5 z74IXFi|Jh~pPA$OZq#RTqCfgQG5N{;k)3)s#JhX=uf7Z3w%6{_#})Rq-_zu`YvE_7 zEV19Ng-_a8KlfOp^*Px6j%&{So~!XkN6yIcha4H7!RS&3F41~x4qGs``CSi~I-NWv zxzkTepWljwvE%F;W1ruVMNXaWGh^y>br@5pt0O>%I$a&c)al7no_^Z1llJVVy?X7p zYZHIco}X#YfBT&wbg0v7Z{YOq3$<3jrm|L&@1Mf@{Zkkl*n;)@r?7tiRC0b- zRQj$CWBvXqa{c}(Or8AxDU3h-wkWLMKZW)Cr!Z~g_fHeK{r+j9Z@+&EQzyT#3iI2i z{K3dPf9&^9ky9tXe+pxpI$(Zt)oZW){;Blw6~=e3->BE*)JdCTI}_7h|EImUr2Kfz zs(60-#nPYU4sWm|{mQbw#@AdkDa{{pWPApro9_3Far&Zt($|0fs_}*WhNax|lQHdZ zdO6w5?!CWp=SQAO&u^H`B0u=Om(xeS^21X2@$Rp~jm1tUB^_7RY*N;H z^V98y>}$MipYiD<2JT@@U;jJ$cP)R`Y<^#(M0QSthm9{A*CTt^@>9+J_ci)u&z{i6 z*UfeAwD(eUa({h2 z+w+`Grqg@LNx3ImoNYP_9z8SnWbGre=o~osiR_P$);68?(|WnG1D0YZ_t*1s4Y%B9 zI?bz$&7L2QP0`*{&KTp$&d8#3;NTN;y>>iiI>%RNmR(Z+wWa7ZzjvG~TPBB2^C}1A zjtZBXPP1S8FRl6H_AEMYem2CFZDcyfS9m__=`?=5%>_AhI!w97l|9FFn*CZb>(!Nd z=%fLr^XYw+e4Ui%bLzt_V@;=Bw{u+CLR~4Z?Y@pHTktvU^`T!^+G~5-i$%)w*_AEy zVcLsh%4@qTTZl#48v`k?4_(GOa7JMPr4&1O>8@!$RD^H~11)#>S* zZEX5FtW)T-X1jWglX?sK$YVR^|8I0WpCzY_1%1l#pYz$|iO-G;^_p(tv$3b2j=95c zbiDRrGcB7U8pyM*8GSBEir zo;>C0r#(Aq&wkpgH|_Zoczy<+|Al&}(`zsKIqIiQuYUrs->BDgsFOCMPo4AyOr7dG z>h$CFapUGus_{1K-;Jg3j!r2**lg8uzwdF$%`Y1}ThXnn_mbTL|M1NS^0>h$80{?Ej>LFT-u+{n_o$>+S3 zEmr>&eEfWW#L&-vptvQuz%#ZTP@b;zw^}j z(K`*cXOYi%=^pgc$kBK5l;qC7$+7S3q-DqX6QGYjuHFDS^*aAej{nY2ljEmrugPhz zYnRDsm+KRg(C9H}=-`YrI{p7!D!c;ke2nZE0{v^SPg-uQ9( z?5=YI&MN-5oEwmPw%xy}%}a7pn0%L971mh+OukEQ3zP5i2P5M%n0%KqFgCCSW1BGy z>#RU>&I+VYZVqFI{29i+`!l9a@@?eQN!||YtN^A?@^+Xy$>$TfofRbdc2)pWr)S^J z3Xmi7{2}+3pPUJ#(80FXF63%2`Z;v)5no|^_xjDw3Xs!Q+6+^t*Z+1_fSfx0c)^@4 zP`}UgHFA8x4va6@PtGDNjxfIP2h-2^38PCH7#rAv6-Ssl@kw&}NBXn@#tvlpX#d3WxH5!H zjz8=m<1-jt%D~vb7L0BB9j1OKPf70d)6#c#jIrbF8)M)71?W(x`^=a+T^+{M>FO}1 zPFII9b$arYr=Rxhq&@p-uin7(C-D3XJpb)kI%yYjwHJN$19pt5)9bf@wk7StA7kqD z`akW(CH0?)@BQPd*%;XTmk+W>d|k`Nz^b($Wv~0ZwvB-q`~NN5piLFiY4T0WT(i5X zn$G8!U7g!j`4H3DeslZWK4VLn&aZn<&Xqm0oas!tZCY;o*;P#E>cR7JbL)SXW4!JD z#PZyjuD|3MZTJJx%BQY9HqK3>|d&3>|d&j4_EWb)Z9?)PW9lQU^NJiLdD3 zJHDcW@A!%izSCxO=mXk}4t+qI(V-6*6X?*FFgnZ?7#-${vy<}dq&zz**>V1)J%7@k zKWX{n+GRRPyG$o(m+8N#brgN!(3`zI1(OI?4Dkon-u&4t?qR&UENA*LS7^yS_6W*t3&zF_4{< zi-GKz`h9s1H+ z$J{y6Xj?PsOU@ivOF7TrECS{{gEI=4^9;@|V9qo6gOTwWj4owhY+wt1NxLMsv!F!Z&Vpd-^y~*-y@BUX z;Q7g!kNHfUoCU>pMk7~y(Kp6Nd_@P}y?&!!lT#;cmOozq+gT8D>hzyIynSug^M>mm zo&l|hu*Z;2h<;M%=JT_TFjG5oe&E%YR*EzZCAJ#P1M*4)cj&%yw+6c2A(|3}y zHcFqh5!TuWvmUcH!de?))?=^#e{)Xm#|xXpjsLvwO?G{s<@$r~xLjYQ=^MWL`ZIi= z^&foiX@2T^UVPT~urb^Bx%M4b{M~EeyV11wj>muVeVBj#9Wg%ZJKUY{o=jTy|Dj#~ z&G%>i?z3l~@09Jk;NSPXnnElrKKh>8)oXPTzu)V98{dD~XUtTu(k}CU>VwR(eGZD? zWxIWtX?J@YpZV)0BaKHL^igK)$|c67n|z)*tIiv-{;01rReNtXzVVA~nY&6B zE5c5<;>E%r9xP#8>#{w=LryFc%U>@Uezv@<@!HeM7UW&WRw(E{JF{{qI|p8PKq&iL zyB`#)-Ua1rg!1RS?`nqf^T6u0Liu01SFKR(LVmZ96%yTzwG43;dTjrE%yA@IPFK_P1oby6SIsOd3=8f4&0szF79Le;mV&ggWeipd`abE;mg4k<0-{=4_EIu*Em~y&#>YC zON_s|ZLe_FuS<<-<9^d}#-)xfU641qy=+1M(y`?Vb{-l~pZIeRI&Yzwjf_S=L?G+`X%~KHO5ZWXG3G`H*VA0VoJT&PC1PC6*Ks= z@Qh+<7(b^sZ(@x9EqYvMOuL?2bh|O_m7IQ%KK&y*^qcI{pQ@LBmOu2r{3I^&U-4oN zUbf#hiyhpr`?k!8&zeN=R||j0MAO-&R&aM>7pI*%>hw}5W4=acA|D1|(>}U(})z^J#YbN@AznX50ovlxvZjAkt zD@?GplzN-IwW2X)@u$HL@26n=yzJg%(lGv?zv=>G+Ep=or7`W5oPLl#{UbZ{o9xq{ zs+WG2KlH!+Brft_@nSFbS+PT|*ujb&tk}Vd9jw^FiXE)j!HONM*ujb&tk}Vd9jw^F ziXE)j!HONM*hx;?rB9#0iXE)j!HONM*ujb&tk}Vd9jw^FiXE)j!HONM*ujb&tk}Vd z9jtiq46Hc_Yt6K0<7CZ*wPwOvGhwZnu+~giYbLBU6Q+%0~9jti= zYu>?{cd+Iita%4(-ocu8l55TRzq)2Bj+&?J9h$%FDX`)QD~_<@2rG`T;s`5_u;K_S zjlNo&z9!ru6+DYmyh#osk0PV z^9$D57p$`{SZ80Rzw7&gKm7Xw%`f_2^9$B_7rZNXD`t7w|8(xQ^_L5SRtIzlHcqP= z!0*4*A$afSgN+Yab!+fVi6f1dAJi#W-u)QkdwSd*6t8)lasK%pLER#f|Bc?XT`_Okb@&rJON+`1!e& zjd%6!&hOjmGp-Nncevcf@a_j+6}0&3ug0~WY#FpZ?rP&o-7XGJ8gacb`Yr1@ow|nx zaLMah2R-hnWBgO`Ho>K-hOzwX>w*#|2FBn2+CKR1?54)k_qZe2{e))5-CyV$e7E{c z?|P?DwepLz=cz@6=y58{<#^qc#}h z=hV&b7~}uxUDp`XuC2ek8OvRJC8r;xPyfgc{U-Y*U4N=x`dR+a|MJt~lKB7c#FV(t znt4TV`4@)-@IJ3!8Fc#Q=zuYB$h%huAJ>iL>o2}KxOHYd(|Msq+u+5!8ko*`E7}HU zcdH#RPL4n1hM;A|S|;D`_-lg;J~+nozn*?wu%T;Xlh4}y`k?8h^-ce=*V+YdoO`5k znH@I|9cpw4ZYgt|=`?!gj-b)z zQ_X&-9vy>0OEV_#e^$5P>-J}uJiqDA;G%R>D?4oR9YKlrPB5LBH{KKcI_ym27BhPV z7mYm2^dDK)J(z#fsiuES?+yfLzO@X`TIjLW>zH+Xwo z6VqAqw;=`p4?lNca7O32Y>!8W7utLB2}25gmVbFb@OhoMY*c$>&}Y9>%uct1MhABu z(ZqZxdiefAKNPPy*!(2cV}2MO+&Szd(=W6C1Hs%IGp7G$eq=CrW5#^zQ)Za;1F>#b z_x|A9Gt#EBW6`eo2|J!QLger>XbOiyjCvZxX&oQ-E?kQH6%D~?#EX4r7s5tn{IyFbQmYq>TNSQ z>)!D{uQho%ZE#TO-fygIxnTo?w^pq;9p)WnX&3tE_gZKAXYM{Q__@uOro%iPe#g7U z%(BcbztrJ|;Jt+vgQG4lm(kt< zYp;j3*TdTDO`h!au=aXbdp)eZ9@btD6EF69lP7yUti2xAUJq-phqc$k+UsHM^|1DO zSbKdz?)FOQvxmak>tXHnu=aXbdp)eZ9@btD(=PUUlP7yUti2xAUJq-phqc$k+Urf8 z?DeqrdRX!DpXL6M6~|rAY=6#YHb0Jq__}9oc-Oq!Z1d>PI`3|8Rw<)gb?>#P9QSplrG z0$67SV$KSr!&w2WvjSLW1+dNvV4W4fIxB#6Rsid)0M=Ontg`}GX9cj%3SgZT!2eGF z6C>p*uyPRMrF;ju@)1~h2Rh1kh^g`>SH448SH448K zqPoa6&{4iaS>;@?ax2*(-=VDX5!Fk+gTC@Fl_j@ANBItAm7Az8axUb`L69q-qO9^A zbd+}>SH6S3awv3^kHE@1&{w{LzH%$%%6HILK7w5N4*JToVC7TjDBq#1aualvXCYS( zf?W9&WtH!sqr3w-`s6$4D~Ccy`3S7M1AXN?=u?*53c2zf^p%?+SH6S3@+?^S6gtXx zD68BA9pzcDawv3^k5E?m4szuk$d&IKPS8fF>Z}RsJ?J1n$!@Kt7U(@u%e|2Bxdx7m+HfJ|Z8yCT!-tckuy1O4R zURq;K_PyIj8Q<_ml)WW8+;~;d1KCyA4>NwN_+PV6OdMjop!3g5$9EWPyx$eCK0f%1 z`;1fb9%%f;{;|CNjJm1n-^M)b+CHf}I}SCSS!c{ieb)1S4^#Jl zJ=*w-L7%6dD*Ir8_d0PxL8nox$;Ol|)nuwMHa~c2nlW{q_s$Gse3*IZEMt7zyTNQ@ zd``EHnYJALZmdHa_ntS?bZGn54bzS3lS_v`Y)oHmUNgm*KD=_}MB`n3yYu^&e0ln~ zQ*(@A&T0;wbfPimIbRMx#+Wmfo61!(Mt{e|rnxp(jfvpXpKP3~eBub>uBX<{9d-H8 zSU$c=Zsps9jB7mgbGGFh{f(!Odp3LFU+*|5_(?7C9zsbI9S5EcP&jo*6|I1H{OXB~(6I0^;d^X6<=rzX1K>eBxau4h-bwlVZo@#y@<&>6~5pu-xCGp{8?8)kAXi(jz0r$>`TBQUoAIx zz;M%_`Q(1Nw&}qpf1yQ{+>%#^ng0C;m(JbPVwCX-SMHVTx-PEwlDegG{rU{CvM;~> zefGt!15D?_RI%Kaw!@9j&2P?5ymgrA96ITVYe_Q(L>Gzuc*F(>VRuvA6!4A)DO?d^Ezhp8QV4N^a(=m%oG>X_-NRu|r9WviF?Idw$tKCA1aiw;Rw`0G&9 zS#rq}srH=*8{hoXn$*P2LrlL-u2TB^PI2tqcuOYP}gve%_17V4_`(j?PyYn|Dl ztQ*5=#xR_zUokyp+Sr1fn|_^OWoJFyF#SN&sU~-GBz;Z0Nv7YvT&02?${s#_g6VwH z_0aV7BObD{ZtkSl44q;6)HUh7*q`(E+Bd!G``IQx=e#oM$A?U@vTnYl_w6y=$`Z$U zAI~%S!Q1vs*M4A@>AQK6e&^$dO^3KIxnhAa<7Ds|3r(LmzHsVX({HzSL#p+l873$0 z$Bdh2`fndJICbBPkC>csa!`l)rcWGOu8Qj-?l*3mZ8|l(-;;WFd0dy9JE?=JEjE2O zUsC(bn`1Uv_g=g!mhaK1RqFh;bFHkKFO5Ik;}O$g-cgo#x$k}-ZhGk>X2;Eo#%n%| zePf<>7`Mpunb)7~y-0SJVuyH9*UBU2o1A(2>fnW@|K5m2*%KDW{lL6FbMJ++zZCnF zWu8{=68CM}aSvs~mGiBv>+>vqjt=v>a;cc_UotTJ>5jOKE_OL$hySjhv-C4#m35L> zBX{x2DPFEWv-BrAtgA=Qm}bn{d(5lxxMH0o?$qnzl~uf0SF1i9$NI$D>0G_%CYycM z;Rh;AHGS4e#sg(pSDW7$+pN&%sNCo0O*T1eZ>#N7j87R`K6l;ZNfGC<+B;zF^|1DO zSbM$6lf53+UJq-phqc$k+UsHB#a^GtZLd%CZLf#5*TdTDVeR#>_Ii^idp)eZ9@bu8 zkh{H7`s|^w_Ii^idp)eZ9@btDYp;j3*Tb}ny*`oKUZ3dOUJq-phqc$k+UsHM^(IgD zdRTista$NU@vm5M-1W@%=X_@K<5-BVd&Y)$&Aa*54}aEq#~FfhRnBmfD{(%f9Evj; z?>#P9QSplrG0$67Su+9o#ofU{VE07Ln z1+dNvV4W4fIxB#6Rsid)0M=Ontg`}GX9cj%3SgZTz&a~{byfiXJN-|Ll&8STL5P>~ z9puVKVC5a?DBmHb%A1fY-$7rw33BB-=qtB^l~19ge222iP0&%E1uKU_NBIb4mG2-| z-ho{C4rP@?p`&~RR^EZW@*VV*Pa#*ngT8VT@=qTTz ztnw6elxM-pq0m>pgT8VTShr(I?6|2{Y}=qn#Vu6zf56Lgek!OEe~Q9eRhcp(Y+7eV|;AQ22uSdx)^uQ*NuKW=uYFNosNoL?|+-|tO18agX(lNo_u1psQsZG zjPG7oC0fxn<_=N$XjuJQOIGu++8zroXFicYfcJ zFT3|QZ47f(Gxwb4#+>I&Ds{RsXDm<5YGRDOyXO(PcR=l&-`)R++&huR?p{db-ieIm zXE%-9JCVlj9!cchi8OZiOCtA9q_Mkq61jKdjNN^d$i3qj^R%jwdnYpHgDMu}?j6s9 zzS~p&Zl~%GIoWsjEpn>Y-NVSqA9p_^CqLc2jhy^*2AK9Vb zWZ&JtiBvEBEPv>K`Dt-U{Qq}iO5EL@iO9WMU}tphzD4BT8?ZAscON2h?<<(R+Q-eJ z`$pbn?Cxqr?j0l3ad#{t_l|;{v$;DEk$X47{wVf^iVheZ#6af6jTXGgVY_Q_XU*?M1Bj7ko>!gSo7o5;P>X8g(YYSCd+t~VX` zE_uQKMUyKAX+UwpKFZlWX%*s)v@;6x7exDSJ?mFyRV|Onh=ibRMAKW|X zg?@1FkDH&&_Z7|ei2BWq%f5QRH@OxoZ!&#%MdP;3TTh5%=k5XI7;lV2 zcZVRyIK=)3?`_My-1BbJcklb>7-Q(Tf2b|DcjNf`Ecfn=&0qX?cL;KfRm!?|{Bw*e zf>2sLQ>tV><5r9kWAOcb_1~7`8Sp-jZwnO8k8pb}Anlm%a7J z_i`s+7k}47z3$y0(|30l3U-ciWmmk?-|Syd_M_as+4%c7cb_BY-ZwIR>T>TPS-af5 zkeqvO$>cQ;{afy;CGmGp?hZ%Jz1w6u#L>MAWj5Vikequ*%Jkh`jhuUT%5;ePU;8|0 z%s6rHTA4m^bnjr9zPk&ObMI!EoVc%j@&VI7WA{=~qc6vsoN?mbt6$f9oIW zN9*5;`+<4w-p@0A<{kDa%RGH?a{S%y`9Ic+KKVYb_vzEq5q*vh^V+@tXMD%cb)x$Z z8)Lq?yIB#j!~a{|Z)(ubj8)c2VvXG0!HN{GcRDn%{zQj$^-cGEG0fWQ-f=X2)=A<{ zz3vWHqvuMN}@%Njo zz3%>)=`?)xq^QF41MM7Adk1H;+UsHM^|1DOlP7yUti2xAUJq-phqc!myLhqJ8z*}` zti2xAUJtY9ve(1f>tXHnCQtTySbIIJy}lrKd!_W*Lt*XpCQtTySbIIJy&l$H4{NVC zcI{%XH%|6?SbIIJy&l$H4{NW7wbz?G+3R8L^|0dQKg<0iD~`w&M_6$*`L1WS|FLH_ zKaPd?x@T-y@q!gElkb{$@%&1jvFQ`m|37-(ah9T7l`|aWN}SIqhvG~|xfS|4D}Z%Y z0PCy()>#3pvjSLW1+dNvV4W4fIxB#6Rsid)0M=Ontg`}GX9Z%;3Z%nX0j#qESZ4*W z&I(|i6~H?>#P9QSplrG0$67Su+9o#ofW|UPX7}l6Lgek!OEe~Q9eRh*Q9c4I??7Mq4*JTckSpIoU%3f#96 zp{()|)l0sEzVa`XCAUIH`3_~3o2V{wF67EVkSm{}tnwXnly@LkzJtDUD0GyMz{)$& zSH6S3ax3J@chFZpf?W9y`pUCl6LgekAy*E9T=^7bmG7XVyaT!N9rTq$ zp`&~RR^EZW@*VUkOKyc+`40NZO^_?!L0@?mtb7U`F3hyUun{Nk8(`5_h7Qslh&AgV80FdJ{#UN z-hAT5{N*K98DF<vn*?emK9oC7|}w_Edq@wAgZ%0GSA zvzhvLy^$9;xblts^us^OU-{GXnOly3BfsINP5F;6dnt4GPb>3Vp4yb}Kjf9n$4ge` zTXor#?=gINW?P$;`3|)=vxY-!s^hzhLjzi{SGXZ_J-^+e+gOl{e;3?X}9d_B9*w&mXngc+vFr z`30@l7~lWFy8MKL)*2^$TeNBSXYyqq-k9$*e`Qgf+0W#^{dq(Fi|1Aq9sSp5^Q+F> zkpJY0)kQy6elCCNu=V*1yR0e7zWH4Krd8|m4;`|$=z>wt%eSJMZ!F87^X`jzep3YA z>+H40#7=VfpUCr`Jnxk?PRdFiI{VTuu+uS4eE3HW6CaSvH{+yU7arSTg7GgWMB#Z~jWyoy!66RD_TAletcvt z<7?VJ9xkX{)A+(HedF#@xv|O4!^wMdE?aW?}W#%eb(6hdzb|-ed~u|!~0^L{N#1v7ZYAFou`V{ zhg&wSGQK^(AzWSaL*vrpHijo}|HAm?b2o)|7yrdLy=qhV_SGfK&x;QID7^8l^2Tlr z2|pZrV1YHRww7L3hRYjjPrd#>w(&8w%s++cp~u<7&T>n+oGCGk8;B9A5m@ zro#Aacl1YvarTn~YR;nL^FPx;|Bss2|LBkAJ94c9u+|4y>jtd#1lBqO zYyE+>E}6c!UQw4@Pl{-7GT)7pb-*}TAB>ZA!#G(_jFWZ7I9Y#;lXb~BS+9(fHX0{w zG)~%RoU}2rSj20laneTPq>aW&8)N;rjmAl=jgwd#C*#UE8CS;1xH3-0m2onzjFYiy zoXjcnIhiBI$=oqc=9FDA#>v`coUC2O$=YR{tX;;*+GU)qUB=1UWt^;C z#>v`coUC2O$=YR{tgFV!vxIT-jA5KSOBg557zG`TtK|8_K4oIK|kC(l2| z$#ao$^1Ni6JVzNP&sWC(6XS|GrFvnFH*c;*u*N5>aSLlan|?CRVU2%S^8)tgi$9+I zdVThF#Mtp!a{;;L0<5_JYc9Z=3$Q;Ie3nh-uWZ7yX=_gW4EF!buitA<$shcbP2Xo& za}d_tgf(Yj&1Kl1Z8VGI*kkOZN0>}{P6MN z^XDuwerEWD@YU`MV*L&i!;U5A8Xs`zq;P8SnZ^TVP6|hjnri&;kCVbz-2ZC;;bIVUk{uYe!R4kamNw!!r>F!8$Wl`yzqlDZH>R#Z(i7Q zeJkq|pGVy?J8ZFdsLA`Zo)dl(-Dmvb(R0H!bp{xBer;}eMa{m(@0~m^yno3(#$)=< z3va5_*?8&5dEtxwZZ=+d%e=67scVdr{?8CQpOdj+@?>lnCu74n85_pQ*f37UhH)}B zV*Pk*7$;*gE#>x1%{!zWeB^j$GPsXZoGFFX~v1*)*RpVr=8Yg4b zI2o(P$yhZ`#;S2LR*jRfn(^jQ#+#=ZZ=Pnnd7AO&X~vtU8E>9uym@MM?eWnpTPJCI z=MrV!Th?dEwK`7a2c($o#OVAwU}o-Z}Ea~&~vkl z?>uE;IP3Lk#y8Ad7}gm$#rT5{7lyA_m|)!c(}m%*J`Wf#erjRZe7AV*`tYWOVYTT) zi&)#`8|=%ak6dC^y0M^)mHD+MN0`}weXWOR|KkYjUpOdzj zJZYnG(stvdPmGhkGEVx?IO$vCq|c3$SQsZUGEQP=oWwLkANnlckjpn%zQOVhmT$0p zgXJ46-(dL$%QslQd2=&h&L(pt@aC!c?63KL--^*s=A+pW`}W~vu9^L04*sTIeDLMc z$LD&J=jQdycK_ZB3Vc_cqWs9yR@gipe_~O7%IKJnYEhK0`*FQ?>?UYGJ3}Nf+o5A@)ut+KJ)Q8 z`I=*5JFAAw&cFR#Z0D$sv+{=y&zjD0*UrqpbI0Sx7u_)<|LuZ!kH}1$p5On%M@&BF zr)l{E?~eC{i@HtApB~2hLiU(x`8m8s~hh#ZhOYG{DLpyXUO^o&dIlR&!Y5a!%4I9`4;i>)9LHrDP*cT7yPrt0U>HJ=OsJIY!*@S;1Px>6WVgV~guwn=M zG4*Zwtk|Ki*ujb&tk}Vd9jw^Fik;~sv4a&mSh0is*!e7fh>QGzVEF^fA6WjF z&VOPoY5d@u&l*d}HI`tFrT?fcDvJ*)3#%-gv_0d=jT3$2#Ex;|n{m>g#z{XLCv(R* z=?CMae`1|@4jL!@X`J-4ank?BNnDJR@nf8f&sZLhPvc~K8Ykn^I2oVD$@nx*)+pm- z?J`c*G~;BgGfvh(<77S>C-c-enZL%#yf#keyK%A(82hpKpYB_4T-m;dDNWns-VSaT4T9a#3+)0LmXJ3B}AbMp}uyO4`ne!BZjy~6_@9%%f{ z552?1ONSWmc3GeB^{OL`?;p@7d~^O7<8vLq)ndGH=F&c4-%XQ^7i{Yte%EZ8@mcM9 zhr?UWGX8jRuW-xm^NhQ`-81Zc_(J1i>+cEMFIZ&U{-GY>jzLR|%eCniW)?hZJf~By zaOr^F#<#!TGi#xecsdG2}c99?FA^W9xtXLtIq_p4sj zRp->HaOzam{iHX%eIdE?jkl%mmY+(VR)1UCs{RP_o7dl-UUy$x@@iMyk?wNlp5&W{ zbxjX^dK>bn-S0{t9u>b65ZgbUcXxWuo9mFzc%fU`=G=zl9S3$#ADI7r?$-_Ok#^bd zTk@_OJyS4zwl`;XXZq8B9gt4#@HF|3!2{Cw+rL2GWS0TyP7PiopK?|I^vuSy$m1XC zmsY&@4td>&`liqC_#t_%>z+$TUGzEm_ z*oJ5A^X!jUaTwb(GSAGNpNoC6HTl!n&Ymw^(3R=kC)}4dxi{yQZ+B07Jf8QB$?JDd z_ub%j<{5hIz3Ji)Zy}Ev)Gci}@@pq*IYz`OIlW{*4|zfsAr`|Mj+{IZMLI&*!XV8nru{&UAawbw>nK6YVa zryS|4iepgbd@M7Mjd8M#L9&favW;1?jb*Zpak7nlvdsx(n=8oZ^Kot=+nhtTxrps% za}?R;F0##OWSi^AHV2YzZY0~BNw&F^Y;!Ex=3cU`5oB9C$TnA#Z4M{f+)lPRpKNOZ z+13cMtsP`rQ^>Z~kZlbj+uB67HH)lR5bXF%oyDLo#lFDk|JZATZH(t~M*GI`UT~b> z$TlaCZLT2O9749ag=}*U+2$fL=CnBW$(YmP*eBbZR;0(VU*wNtpKNm@+2%~L&81|U zW63u6l5I{V+Z;}|Ie~0*1=;2hvdt}In{&uE7m;m_BHP?WwmGdxm%cU!GTr7zvdx)f zn@hA~dH7gvUUrN@wW+q)_(-SRZ@RjsPR<}J=6KlOcO_+tig0V2 zJII@UGBvCn&$Ce1ka<%=ydz5fzEMRu@yLD1Pd+&{)Lp*|dDwYV!-#Zia_BfUG@93h z{MUP@hK=uEhrHXeso~$AUX48Xnu_qk6Mx~^{o{L7hBp1)A-~nADs-xxMLzR~s<8k0 zRpj-W#Cdt*L~{F9HQ}XZV7*M?iWX5@Hpq2PG`D%{#G&lB%Xgf>S{VxD++BDC#Q zO^$ab!uGXu$nhRj=rM2!Io_QJlVA9Z9Pdtqo7**{%<=9-*l6VXQL9$9q#D-tQ&H`&1#` z`z6PFRw3R8Ci_0{Yqbmdt>gsDUSQb~Ec=3Gcd+^cSp5X7{sUIO0;|7))ephypJ4S{ zux~fXi9Y{JjVZ{WdchiNV2wer#wJ)}7Ob%h)))tC?1MEYfW2Pm!@3V_{W*c|*3Ze- z|H(EkN|DFL3)#jI*~S;y#$BF2ACF`kr)297Wa|%k{(QWXtv`^hKaj0IkgY$Etv^s^ z>knk>4`k~PWa|%P>knkJ3)$>KHoK6`E@ZO{+3Z3#yO7N;WU~v|>_WCVglyxTZ1Vuw z<_EIP8)TbL$TrWAZT=zKyhK*}qi=YYEs$e?4y<&%b&!AI~y>yZMV@m#rs}yZrD%_+rm$@`Tl1 z2Ibf9!R=r>^kMx4>8f)NR)12^A zyLkDf7xGA7u-XBv_5rKiz+2ojEL_oKvjp6B@bGZ!_3^jVB5yNpM3~omU2^AvBg3Db zY(TF2Xh^v8l+DSt?`^gN`43@0SmTu4$rtzSALh4eLEdeAzi{Gp zdHmEQ#TzzNXF#g0m*3_hb-|$rRB}{LzcE8YLMIPr&hV=_S z48D!&XWrL8ES!56`IBb{gqP3gPOe!pFeuIzV{SjnXCi2aRqaiX-g{(ucy~|@%jtYvdAMLo6?xzF%0s*7r;_76aK3XyelYwHaJ=sg z|Ct=`d&7Sw$NS#!pULsQH~eREyzdSFnH=wX!+$2n``+-M$??87{AY5!?+yQ%{7cTy zXg9?t*WYf!k61CiYu1_=6cejjHZdqx)-IbA6hk}d#@B*kYe#KAIVk3~`GCnmvAB_I zPYH_AZG8BYpxE67r%wrrRU%!nKIB&n5alRViSiYzM7@etLLS8`A*W)MkYBM%=qtS{ z;@Q2@ubMNY$lsvhkfNOBhYl{vU)g6+QSVM$3@YTgZ_L0#&OL7!Sja#7{DFmDNSD6I zuXaE=Y9ExZc0;{tPspQohMa1D$S=Ft{7{a*YV!u!<`c5bGh~~8$TlyLZLa3sewB&2 z*QYDLo1d9qCJvaKUzTVKew z?vQOgBHKDew)Kl_>l)eCJF=~VWLqD}wr-MbJtf;ZOSUzdtZ{^PuyvW~wqBEM9Vh$o zqH%=()%XJc|BYYd(f9(JkHj(lKONJ6Jhm60zP8?xf6mwf>b3cwbz!|z9NX4DrrUZ! zwsnMT>kHY|9kQ)QWLu}mwtkUqT_f9iSEMVBZR;b`ZQUf>dP=r+mTc=U+16#Ut=D8* z-^sRKkZm0y+xkMbb%$*05!u!$vaMfaTi3|8-WBPJW83=3bXzycww{u0oh94)OSW~H zZ0j}W+j$?H6wg)1@NUDfCr(IL8}SnPgAT{1JKX&u`GJvWZq~&1plWQK4e%7o%dCZZ&N&h(H8S?J$AD+Il!IR_{x7?|y_q?rJ z6zQ*z->=C3m(}(w%K32VK1KNt+}OORck$%C{wB|iJqkIWd49J-{=Y-v3-jCvE7PtVtW?l$9692jqU$8d1mZU$QkWb$RF)k=w**>oqL*P%~%>$o$>YaiPu{HEOrAq9 zPlYop4c6l=No3S6c{{w#xYfRpgd{pn=;laiE`PXOnKM}q@ZpS>& zwU38`w%eZk*13H`r@b#B-}h>tuw`|A*4E|Xr^B&J?__$({HMd7Cw3>Vx6w1z%*5Py6%-3)uQ9Wzal;bj<@`%>!V~17OVqV9f(y8^0`5^8nH{4}dlQfIA*~W;y0S z@TCVFRQA&JyU7Rkm^E(QyK=j{dhf2|Uj1`^W_S8kx3~V?m-#te{hj^VcDnI#=HGAm z9c^!2CqJ9pbwG=k8{U!I=!1`cKW<`Wf97d@@)~6yzdD$_{wtl!>W>{xK4!>(vOk^n zJbA#@OUkaD_5%6X`!*@xKfZN>Y*&03e`6xPfdYSf_ZH>PcRzyshaEO8Z?yNRxITlrjeWAs z31piq$To+NZEhjkoI|#`h-`Bd+2$^?&1qzt>&P|_lWlG!+uTUD`I&6HInr#7H)K9?bCt&px zu=)vD{RFIj0#-i(tDk_?Pr&LYVD%HQ`U%*#r}{JeG%?!qml{*3S9O6ke!&{QV2xj} z#xGdo7p(CM*7ybc@$2jI?B^@-zQ;`q=NxzdeCA}$HETkTjyWIsa!qJDKIeNn)rO7E zXvsXIzo-opo3|pj_+wodzkh4;x{K>V)3e)<*KScC9v#`1Jgswm^r=h8?_60Qrrc3l zq+h!-De`}L>VagGbNzsW$SA*d*1=@dTQ#pe8S>mT{17tay#A;|$&mktK{-ROJu7oQ z?a}HYeX}K1MgBQSRZ-5+{*^`f&3CFS>OFZ}MIldzODcloe5kY{NdBAlswnhAy7WbU zwFAmg`=ETa8|qbiLLRj<p12IG4lMg`5};BGK1wif#o}a|kjJyiaq=^d%5n1lyZ`+) z?=P$mu&q2xceIJ*2Wx)>*8T{r{SjFEBe3>IVC|2<+8=?nKLTri1lIltto;$#?~iN_ z$uQ4|VGEn1Xp5h7kLl(^%AmTCuKg@n`&qE|vtaFK!P?J)wVwt1{jBstx)}PJFF_f^ z&VR_9|ByNVA#?si=KP1u`45@%A2R1ZWX^xcod3XdTYs6~)@7Ds{sYT5|AFe!L+1R4%=r(Q^B*$jKV;5-V7mDa%y0e!%Q63f z<(vP&dd+{JJmx=8PV*lqzxfaBtFj$z`g6x&Y+Yub@vK-4`j}!kV8wR8iur&Q3j!-f z1Xk<_EM34}N7V~`&41urevLo1>k*Y@QWgMSjIR!9M1xJSazbz<)2#FBzv* ztQazTmdr?(JYdC*!HOG$6*mSeZVXo37_7K4SaDBu+=N>O#8e z0;?{t>H@1S@T%&945}AweTH>;RvZlF{F3oE$pG0T16VSE6$1n-1_)LR5Udy=STR7b zVt`=90GY>PfMCf0-QyaRBCZ0CepJEHf8)6`(xd;zb7ye$-+1l}j{Y0Zox#z6OK}bk zj{Y0Zox#z6paL==vrSUw1dEQ)m(=?t(kdIrlX&TQX z$j_g-NgB^1$hS4#B#q}00Mi<@jQZj?C{OgcpgEv|IMJg{V&=6mu&w_w*Mtt`;e`D$ksk&Yag<; z582v>Z0$p~_90vQkga{l);?rwAF{O%+1iI}HYJ;_$=1in*2l=!$H>;l$kxZm*2l=! z$H>;l$kxZm*0;&g??QhjM}G|cnH>Ez^k;JP-_W1Q(XT^)CP#k{{h1v7K=fyF^bgUW z$wPg;?~cKG zj||p(YOvl@gY}*otoPJly{882JvCVGslj?r4c2>Vu-;RH^`086_tap$rv~d?IoQ4( z!LxF`2S>WziG%fi9ISWcV7)g7>m52+@6*A0w+_~KD!}@Fh0DWrR^OdKy1qvN)^{qv z`hEpi-?aeidlz7R2Lo)jVEOvq2-5X^53s)P0oM0D!1}%iSl{;m>-!#HecuDD?|Xpt zeGjm{?*Z2LJ;3_D2Uy=f0qgrGV154ttnZ(I_5BmDzJCJN_fNq3{s~y$KLP9eCt!X5 z1Z;gc0qZ+0U>k!>xA9K4@lLk!PPXw*w((B3@lLk!PPXw*R=v3UCx#5(cE6^!f}D~K zEZM-aBUp9>%Z^~#5iC1`Wk;~=2$mhevLje_1baJr**vTNBft7TSp6TY{ts6F2dn>s z)&Ifj|6uihu=+n({U5CU5BB5Kv*bh{kep!236`8-$qAO6V95!VoM6cbmYiV836`8- zFPr8u$nSYodGNpbmJaymnCmphLLSeW50S2U60G?Xta%lz`4+5s7%Z8=(giHt;RB;y z+}Coes9^c7VEMFQ`MO~Fz+m~tVEN2o`O;wd*kJkIV6_$4x1s!b#8ky-=U-}1Vew(? z#~GK_{srmUzks!W0c-yP*8T;o{R>$87qH*Ic)heoLmtn{W9JT(&CVUjcJ4s7a|g1W zJCN<%fo$gvWIJ~t+qnbT&K-*McuK(>1eWIHD! z+c^>0&WXr&PDHkIBC?$mk?ov_Z0AH|J0~LBIZ=@w&xwls@tlZk_e{uk&xCCEOvrZ6 zglzXr$ac?!jD9OSf`9IPxAyz!Kc2NWN4oaxVD06>+T(+@_XjH`09LF3EM34}N7V~` z6^p=H@7aF~-LwBjmS@dfDATj%2gu;r%ka+@w?SJ;X0T#SV8xoiiZy{1YXU3Q1XipG ztXLCRu_mx$O<={Ez=}126>9=3)&!PKVHYp6XT{u*UokhZVs2o?+`vBOrvF9x`d_gA z7p(sUuj+qMrpj^5y`-i8hlpelfjB7gB4E(E1nEiJQ=KbGFb6su;R&J#goB`CxaDF#=N2L z_9NZ1bb(zw+uV}ie?8m$L)&?_`6_{*<5}OlMLA;B<;xT!-R4-9Z*wpCzx#{;@~AGb z>H@1Su+AgEI*$PBJOZrq2(Zp0z&eirn{UJRRK3tw>0Wo||0K@;Nu2+aIR7Vc{!ilk zpTzk;iSvIF=l>+m|6#iMKg@6b56g-7F0j_K{CMwz?ED|f6YpIx-T6P1Ki<1wy7PZ@ z&z9-V|4E$xlQ{n;{(d*_*)qTLe-h{aB+mayod3gg^M9D%{GY`6KP*4qlVSPJ|Dinb zo=hQUyeC6;{tx@7x8u(p8`QW%zw)g3A<`9B1S{SMRvZ$n_#{|yOR(aZVCe#uju_*s z`o?UN?Wcv$cjb46vu!S~4j-pEKQ^%{^u0Rg%Xh2_JtpOx_Nol0@ADkKOPuZ2tTKEt zGUqU=A`CsOFVo+-up%6=Eaw+WD#C(C`Y|2-w*Qg+$wuv#XOK_eEe-PFytJ#Ex(ye`OiElXXw@8;+)ZkSMKs`I(U=%Y_%t< zL$6jj@437xe0grp3lFUdlSk(K)$q#jO0(yff5l#vVg4gI-#wusoVG__rhj%-MR;Rc z&i5Wv5gxy>AJZpC9XsvUpIp)==6N^ghtIAEFF!hf=?@LA2xHTMyh*3gKNVDi*o*EuexyivCr{4v^zan7dD@k z^GjdUg%8i@%k<9e>cg2|{o&YMYD4%o?@QCN+OYhYoEIEY7q)7ibNT4H(5qkG4-Z+tK5V~U z&R-l=A2vQe@3&iDQXkeEoA>7_mq&fq$a&$(^*l=6F}2~%LHW2lZb(g-(K+X_-%kruTIQ@Z2zqI64%V6l)?Oa0 zH4d!3KUgsVu)T5Mc(Jz+WUZ~pqcvCgu?DG}cvq9GwHxVL)4^Kn!SVsX@(sZ989XDl zqdZ{!FIZ)QRTo$?fSvz99Thi_F32Mt!O|V9Hc>g|KNM|`Wt*C_(DjRj|7(Qr2O#x!1A@g z^1;CJ&A{^6!1Cq5vJu$klYn)$aa?N-xR~Eb%UX4*4jZ1BbBnU7P`Xvl%{Q+K9i|Rq z{;%(<3~!y5^Wt?Y!?rW|y|wJgffZrBlAJf|9Q}k|1DOBn))k@W+x^KO#5MHNJ#(IU za7AeT`+iLCc5OvyJ*6-C&dC*F+>SYSYEc;;eBe2zFMhEyY`t;LdmK|0wjTN{(?@?= z6?%8h`GLOGq3VE~|8)Aa&~VqBn{HSWhPBE0lkqj-pe{MjKesj?c+sH`H4I4kEzF0BYVj~T%9W0Q*TK%<;*jkY-U*#1m^KKg7+ zAL&Q#a#7^PeaQ!osR$#JoZs5EG92CiIi~OQOlA1pjydnxx+;ts`z+H>T38hZ$F_z1 zqk2?_Ct{m}-##pU?{t@(PyIHY%e2h7`-qxw{5d&q(V;eU8Ikj+AJ&FW&GPbZzN#*4 z_*l+U7S@GF_s-?%ws(EFY(~zVJJyGX@5tq^jJ6n2lIzv_-1^Y!)0{VIT_2w8m+L-y zMP0b{n7n;t3&<(PxcJu?`JWvlYJYso%iAU0yDrQyrwskPyx#|DM(AA2zC zc4}=n?(IQg{Ej`dUT@Td1##}$@!p=h7qch2wx{bYyc)nViBhLPtttqMcyhmzlk z{{Qap4JNnPKJJN*8Axt)($o+(>qmZc*p%>n=V!>Dx0n((JN!xV!uKYJ?-xHt?o~56 zyw>TVBE8#!`-}Wn-f%A&<#g+K7a8SO4ZNL1kaOG{zb8Zf54&DN zhF(vVUHv0QTPY7%{|i=`VATbd3}DFyhK`UK3>~2hSUM^lx+_201gy3Ks|~?wTd>+3 zEL(tOBd}}-KJbbf+78_H?poRoeDnQvv>kY#Kh@KA;4_YzPTPSiKAuk7fiJpv25kqv z{iPYS9k`};25qNw>5Keo2b2TbArH!j?ZBuPwgW>R*bWRiVLLG7hwZ?!ooDn<6JLW5~o+<^h%swOgFul-^MA+F}+y6jce9x7);z4Oxzeu+!##U7);z4Oxzeu+!##U7-YJQLFTtH$a0`BWOHMX^+I2yyD>;P zp)b;;w`mEYEd!tO{{e*mkWfYpD% z>Q`X(H}H@Kbz#L*v%^hwYX@-0duE4qvvtYm9638Y`^5U>rEkp&;q(p2Tb(#7O#Em= z@-cm9hR(-qOsig*>0USyjmSd7r96{)@WBZ!VZ#NdI`znv@6mPhVpV zGRjE~Z%9V@ZJ%GAjCy;YxEdMqG`Rfx4DACsH=p(`8S?Ko?He-m`s(*NLtmw%9h4vK zqjJ!0Dj)5sdeP332kkF8VHe3Sdu>1CmBMyEW!VwwvLje_1j~+K*%2%|f@Mdr> z%Z^~#5iC1`Wk;~=2$mhevg67RCx?SBe7KYYNnDwUYs18qpE%i=-*jO)o~@mK zRHpx5r`M0l`A1~%dO5rNT^ar(-SK_tTgDI1P_O50o2_6v+Q;*tjo&Wp-t3Rd*q89X zN(U>w#UE$ze<%L&wd{x+bDq*@LN@xeoS*I;vP+uee8ov+S;ryMng8tHjLk0HDd$Gr zUd)cat)A&G?eju*TSXmtlOvzcw*0=9eE*^m+34MJUSsVM?B`x)=>>Vfk_Rk#z>)_n zdBBnfEP23^2P}EOk_QZV4(L214A}ME(D|Dw*%hs3ghk&h3Gba=nceWs^zh+?CE=d? ztF!lBoF2}+aY?wPS55ZixzodydoBs@o?Vw+u60jOv}bS zK0RzdWO*2!)Ml5poE}cPetDR5Xnl6Vg!(Y(kmaGO>5Qypm-_JiR?EX5+Rn^+z8>ER zTKQe>c`Y0gWq5Vi?5x4zlfyR;EemIjoRd|)KRL{~Wmy=xUp~J{7vB%Rx@2N#RJtUb zv`$^Nq`{=nxZmQ?b;R^+?;(@I%5N8i4<^sd_WHNi!px%3th>}*)m$zj8z7l!L^pOdwZHjjPds8=Zvx6;li9TCtTlhQaGU9 z^3cB1jO?=h6XP9{<>BI8>a%T{PYjdCE)Vrj)MTw=neQ%J9?qRwm1Pf32;J9O5r(f* zksWZ|gwUbMig5OkQ;PQgC2aA)wbP6KdF-3@MgQ#5w!Y|}7u{7?^v?y=wMGB@&HA-P z|HPc2{)sZxCsC&QB+68uM49T7C{ukBWvWl2O!afOE^wW)F-x|2iR+*k|BF5r*CwWW zwtm9@^{g`8oR+vbEpc;N;^wr(&1pZ9$E_EMo5K?~hsXOQ#T=fvIXrQ5c;e>p#LeM} zo5K?~hbL|hPuv_%+0+hL@4#`4Bv=Q*af~EbAHi{qBv?1Waf~EbPr-4FBv@y`af~Eb zf5CB#Bv_Zhaf~EbufcJQ{HUGXI?H-(Y_eXk>IJJ_u<8Y?Ua;x~t6nhbb^b%L(Xe`r z&19?6=^C5KC8MWnY$hj0U2JS7(~h5^v6-BF(F~2v#Lef4o6i$BpC@iUPuzT-xcQuY z(#8wRw6!L2Yfa+Tn#8R&iCb$Dx7Pfq|NHUc*2KiEiHTbi6SpQNZca;@-9ABUbkcFu z1g+7@t1BmHjZSKhn5Z>6*=pECt1-29xl zc{_3QdE(~z#LfR~6ZD6l&I7O``e$5&61R>dZhcAIx|6u|C~@l)ZHILe^{bl(!ud?siyvn|3^D6tE&8zHtHm|bp z*}Td&v3a$S`InI2tu={TYZABCByO!q+**^kwTAPF#*SMf61VQKe6^2TcUZpK$E`ao zU+weewD@hk-^Jhdjenm-UkSX+>tn}_UH>)mZtJ%ydnx*CNH6Wswe0@aa&EN4kh1lU zn9TI+Uacx?^JdO7TEAO%{hd>oe(;#D%Eq;sO1|%;2IUWaoO5Z1M&%dAGj5cL^uecB z7WtR2Rz*fRO&`x0<@egMn(3(b(ylo}o{MJW3^|)On8rMi|B(0_kJ8Jfw{!VRTsbAK z{1R7hiIbccAk+R z>9QkOb_C0gVA&BYJA!3Lu+l!tZ%N4;oAaMX)-1V_DSN2SA#$`3n&Q4Z_~M)|NK z81=%AV8{bIf}>uvBRJ~SPJQO9_j;9&xjXOw&kcRB{12Pt{rUTK?=7#mEAPYmTy=B# z`EzR6pWAMHcKMd^eg*pWqw|yUE#o(J!C$@Cr2OCq>&gH2bw$~4|C)2-O^zvBZQJQg zM;p5I5|_Wkl~d}5*y}%mFV2x$4#xhuA8LY7k)>sB> zEQ2+c!5Yh!&arIyIhMh(9FAphET3Z;9P8y+21j`~mcda@j%9F^pW_#dISRHGyZ*p* z^gZM;|0InubNMY~^Mz9QislQYF)k!uD2;I;`9f)o3&|HsV_ZnSP#WVx@_CAKqR&&5 z6Me#>oaplu1&K5E>Lv#l&Hm#!V#5I%O?D^XwD zE2S|mr@c}d<8s<7r75u^&-6+^6JwqSWn)(imIQo+ynmH|>ei7>m=MD2*{X z?TOMDyQA&m-YV6eD~=Je?fX*f&28V8V$W{-z7%_T+xMl|GnhBU?i z6=z6e3{bHPjz`QPYD0^kP)9qzpze0A!8Wn;4z`t@gRl+le1vUl=O%1(J5Ql4?3{%* zvKSg|XYrzgi;8-YuDA_YaT~DWHekhVz>3>|6}JInF0!~;8qYoyH%sH$hvH^w zJo`}GERAO$ikqeJ>_c(0G@gAZZkEQg55>*Wc=n;VSsKqi6gNxb*@xn0X*~PjydC3; zX*{naYhJQAVH(dq6empM*@xnUX*~N-oG^`NA3yqEi_aAE2Fl0$hBjAS$b)vkIP$je z{Q-H@H;`_!WllDo%Rn}r%Rn}r%Rn}r%b*Wuk|D|y?}0Op2V3YI3bxQW6l|e$DA+>h zP_Tv0p%)g6LU*uF-*)Y8TyQ^Q)FAe zGR%{&2)@YrbVU5<=8P;f>oneip zY&I6i>f6qj$Sj@-UqWYm@FjG{2VX*GG;BkQXTrD1ES?G9CbM`Ze4EVTnec5gi)X^O z$t<1;-zKwoCVU&62hm<`UDNpy?d#Sxoj0*RxOGkEQ|v!(UCZ3M#&%FYbn`=IF-fey zIy=LKG^TfaTNbGOsBeB1kkHr3FJ`($z`AF<<<|F;0GFyxh{#a&bTksn*i!s7)%n`2L`oDfV0gzRY=LpGD*D-ap3qV|uUVoyvyx%6Z-neam*;^fjjc zFm`&`>SJ|apIVYL>fQXp_)a924|$TQIYZ8E8q_cy^8aPioS~OX zZ|CxtxN=Hd`6aI25+_fole5&xU+VNKb^4aNb|`i2Q|j8S#I+l!tZ%N4;oAaMX)-1V_DSN2SA#$`3n& zQ4Z_~M)|NK81=%AV8{bIf}>uvBRJ~S4sixBVhfHLYf?I5k6^`Hz>2qk6>kA6-U3#< z1*~`rSn(FH;w@mbEn=sZ&UlOEXS@ZhcnetZ7O>(iV8vU&ino9fZ$XR&jM&=0`szPd zU-h=LSQ+i;`z;v$4D9RjGlpjAj2~Km;8}q66P^Wt|5^L9Zxf7J=&Lac)|drLN3g~$ zSYsBfF$>n11#8TLHD)bcF;e7Lj1=W4Mp}$n7jV*6)uHA7`MZE=%i=q_>ik{6({rYUtD7}t{)gjRzGK$ilsx+L z+R*OloNsDYAI8+@+@j6&aOhJxZy4`|T(M@(y-%4Lrfrm$v*3_fp>|SUe%}pehx_)( z>n(q2cDVkyT%IlWn-jh|IG1zX8|Q>?H_GMz&BJqwHv(VZG$)+-e6H`%(mA2x>AW3w zs+%3&ADXw%QKhrPo{RE#0h@H46?#3DzYDl{#LUqA>-_%zTCdIshcEw{?*fj0WqSDG z#;?dbjIIwmmw!nf{#;#nYiP~~KT;c>I4;k#Nw1plMW6hCn>`c1f$~sZ=H$uMVaM(B zy1rSvI;{CbE`#0z{Oj$;KgZjR`(B=%#<7;dUTf|@Cyir`-0)9x(m2-0hdn$ejbn}6 z_=Y)Y9Bbq~_L-B$u||IHh1qEwYvk3|pPk0BM!xI7S!o<=5;na1}xT^BL-dae`Q!VPG`>S&dVIH% z#&;;>_zoqF?{~=Y9ZDMC^^oH`lr+BgA;)(pX?zF7^5Z*{G`iSJN~^5Z*{qTcuprI07SLn-8p?@$W);~Y}xh4lFTi*h1= zeE&s8Ir04$8Rf_KUu4u9-)E5_PkjGHhMe*J7a8)$_g`e_72ki6p|8@>4$6=AQ8{Qg zm5=sRy=Z62gZ7u4unXkJ8fSAO+1}ld?L7|J-szC-{SMjQ^^onoPl7V-9T3^x2a)aF z5ZT@nk?oxk+1?+K?OhVfxA#h9d&fkMdg1*SIqHS?Uu5jlFpeM((xor*qaBcra?n0t zl#g};qh7Qp81kTI}w)KK+>j-7A^@VKf4%yZt zvaM5OTffM*u90oMBilMiw)K&0>n7ROQ?jkIWLtm9wl0%xy(Zf_PPX-(Z0kPR`~kB0 z31ssh$mUm&&EFuKA40Y@j%;%&+2&Ys?4Ou>$+3T8PA13xiMg5_`zPjba_pa&+sUzi zV$LVW{)x4K9Q$XH9{XpJKlaa}oY+5$@?-xj>W%%gkSF#}tOYDH_D`$@&qO)l!yTV2SbH@uKjZ+juX-uyx@y#Sf?n$oczbM^c?FY!0%zP&u za7z#J0W055PktbmQ*}WG)df~vVATayU0~G(R$XA#1y)_YeZbqbe1$TAm!34fknOJ9 zLLqafNm-#wvRzi_xLNP=Lig|5loxHX?3=Qpt%ffxV;e#SZwu9nbkz%1ym52d?RM}i^8QD@mR|G4Z1S`NC#7pO z$nWR)yEG^hcc}2cyC3vQdQ-EUCtN%}U2(`9rZ0Xrq-!nB%lu|}mbP7gCev3xGD}Z- zrJj7stL5oI8`YAZ>rkHFzi~BrV&n4k^Vg@6p$qOFpf1ykZ2FR|9mv)`WNSCFwI|uy znQZM(HoK6`USt~=Wa~?0>tkf=dt~dAWb3PB>%(O0+hptWWE%?w>DvX#Ceq*^M^R!l4Cg`&cozbeu(okIo2EE zyiJbsggBp*qnshm^W-Rhi1R-=>J{R;kl>qLv29r|SoMNcFIe@0RWDfef>keA^@3F| zSoKK*tZMaV;`Vw$P@cUA#?0Ag)Xr#6*|T~R_Gr4UePA8PZn(z`)bjKu@AFt zQLpL(t1htW0;?{t>H@1Su<8PDC7*r}Yi8^%=7DC9?G~vh_W( z^+~ezRkHPA)~mW)KV-VH@1S?3EM)#BT(Mk^XV-Iq5D>e#vjw z|M9*#>GHL{A)k8oob>nSeNR4W%Q@*K(^pIJzse6*ez5X`mEV`||5xeo8I%sjeFNRC zMY`v^mMx^8fb{L(T0s8+e8iIZ^ee!VzMn^b1FXBg?ykju>E5-w7e|?6U!u=|x_WN$ zE`15`sQM-JF~Hwlu!Oz`_=L9>(0wTMf737J+pV{+kp34_BMSU@Yjvs zE_@-+x)+Up`_2oC(~qvreXZ-7E>73EGxvoaJa(nrq8eWyMP-cGOF z_I15K{ZHMg#(k1i-DCVU+~IWg%Fu>puV2NTMt{dfZHRBfbN_vlcL^%It9wkBI2 zAY0!cTc06YUt+td9M>nAZhe((eVA;0n{0iaY-53JV}xvDCv$TG(=pHB&Xv;R995)) z|D$xpf{@4Nq5!rzivMeK7t2(B=&1Z)DQ~^c8uV-u3C>FXVP<-J`DH>37r?c@}i7 zDgO7HN2e8KUifNtQP<0BRu?kFGh&=u1+>5Cvp=s)_mAhrNI!3AW!m!bHOcY3I6Y_H z+T^WQsoy{0OyKV?Jmp<7m`Blq2ye8$r1bU;NDa>cA^=_yT{ zlK*W%O*(4rP072gtW8hulQZHiW8---WN6-UdXfIc(KCwt_ntVjDCet#W)oJSHkBZe>1rfJ`Z`F##QinXkX=rt(70F{NTTrAOE{guP<2UPgyc39p#82 z=ZjBNat=hg7;A^_ks@8}d?(Inx)+K(n!|s(E+`MyAkQij`8``qhUI(ib$EH&{pu>F zA3Ur)eej_g@_q+o={M)bZ`(#0?wXUO?doQbpXeFVCnwD!Z`^5oI&c3u5n~SvIh8I(y0c^A?D!x0z~1-sEI--VF#((HD1&EfPu44T z_neuoI38qE91pBG9$0Zau;O@N)#Y_`cc=O0QE%eh-D$pg)SEbWclt+f9=$)0y1bki zJJ?5PjEl{epkAJ}M?g9F-#8wb=cnZ${ikLAG{5rLJi{|Jn-j=3SFjwLLs*ycLk8ss zD?eEI-F%*c|F7QVfGuo|OVK`_ZB1mlt(9b3L&>(bl5Nc;+gePvHJWT|H`&&7vaR)G z^8v`_8<5RsAe%2iHXnm*z6aTS60-R!Wb;ozH*dJED+H<$xO|uY^mR=4US3 zb{QW|IVg`CR6HF**G2i6OP6I?IBTsu&hY+kvM{79KXV!ON_jYJ{rt@3xDMr^{|5P) z%b>>P;o>>PnM=T#3*uC<9SZ*A-dT9~@Oq~A9$6mV9aKZ^d|Y|BU`iEv-}TBvyXU8} z|0qA&YMb-2a6rrHOyA>#EPn64p8Vv2F&6!3{JwW=E9C*7a@Z?j<`%CreXHxohhZnr zA@4mVgj+YBO+K?>yh3tXuA}5MI~Fl&q$^&nJSczbn}&r8nry~$T2~DZEy70Rb61WC z@6B7AeE26L!Lw@Me)NUIwLm*~N*mNYDj%3r3EP0%ql-X=Sd0>lo=dDeKEw*U&1M|QZPhGQu3|p+eawgeq!SZc9 z=H=vLlX4sL^`BCcOS@rt;91;s1k`V|zfi0fCuas4Xt#PzHA z-?)AiWybZZs4K2tg$!~1q8-uxo}*6^6t9RrNl?5Z`XoX7`skAc?f0Wk5)=oBK1oo# zBKjmj@rvk^1jQ?&PZAWbh(1YBydwG}!Nn_r;uX;+Dbk})Qsj?5Nl{MpNs98LPg2wy zeUd_+=#vz3MxUgRANTg9SM*5=eWOoOw1c;!7=6|A|D|^U=-a-}h>;%mESyikF%HRj z0373!#rzQCmYg@x_mm&3{9xq=|1^K}D>%34e^oEi#hAyi_Qm~Oz&GKY&%pPjO1FJz zktgm?3%);o4;w? z?7RSeh|UQ9N58)fU2t9rdB8)rco)7CxzY3`@TtfHE?fd%i+thRi{XQj-#>6Md^7UB zcQ1m^MsD@WJMiVm$G`tJd_4N7sO!!vna_q{nYr=&gEi zZ`Ff)s~+52_2AyB2fS5>9aWCEk^A1Pz6%lDcOioNE<|wOg$VAu5W#&HBDn8D1ovHt zfbT;5)E1BjzN?dmKDo)6{F2|=b?uyBJVFNC=lQRG;}qqqK9e^HpSM}CfZ<)(|nVYlZ#`SGI{heNN) z&pmA(pgh{kKu)EDZ9ZWh&#Tf4eb45K1bskx!1`b0@vOR#$Ft;d^Ag+8@8fLlWnEzG z_1xTB@K4iGm;M*|ZSCNm+U9w(&HpUN)&T2D3~ zfNZ`2*?b1F`4VLFG05h7kj*C{o3BDPABJqc4LQbP;Pa5p7b2UFL^j`vY(5p)d@Zv1 zU}W>n$mX+=&6gvak4HA&PjMLdhlkSB4Z$Q9$0|M3?5HRBNcmo2~8xXMGfPnP|1gtk8V7&nW>kSB4Z$Q9$0|M3?5T)Y{ zh4SNV1z2xDz zoV@1^14G;0E+o%Be_&XBNv9&c@|n|${2M)b0vYA>{_AhaD8F{~!^x<3+xZ8PAy2=d zrDVvt^wG9t$p6OZyiL#!&?Wv zVCe;xUSR13mR_={^n!h5J8$c2)|$w6K>n&_@%@suPrGbV(QYT*7=L5Q+ViOGCl~F! z`GCnq`;T0EN|0SPK72}$y)HO?N?}K&%f84jyQ3WS2b8aVf_l||AdmVL4KO|fKB%_~4yOYt+qut5Y&x`cfK1Kf6 zK4cp&WE)3h8((A_cVrunWE-b!6Pw4#(hIsvFR=6iOE0kW0!uHj^a4vSu=G+o^iqE4 z1(sf5=>?WvVCe;xUSR2^@e6w)-TF3l_qMiv!gT9DWb0RC>u+T1hh*!YWE+oU8>eLJ z=S8~gYvY3HHeSd!j>tB?$TsfCHXg|~P759597UF1&|P|gr59Lwfu$E%dV!@ESbBk_ zm(rn^@}ob4r59Lwfu$E%dV!@E*y}ZO=jT%C_37XqWY|~f;8mrg9G?fQ@mtckZyMJx zwqehY`lfN-Ca*TJUmDjt@)o!CPvg8z-f-6eXx5dpmY3+W+`h?YL$>nCRxjD)A)B0Jlb>w% zBAdQNdhEAFe)t=%Kaj0G$=1$fYk#uYg>3f9pu6=|vh;H8!*uC|bm;|_USR13mR?}# z1(se)hhEALy};HV$kGex(hDrTz|srs^|E<})3Q>4phmfcaNXP@V?(jH;? z#cML&E=HM$Z$GF=_k8p4yLitBvC40!+!bc;J*E^qvdP_Hi`i4jN8f*U=y<_g@&>K% z2~#>PCBN0ETbOgqXXHP8)-5!u{GNR8clU)zh8NiYOEE&L(f%%;bUiW@+k0#l6?>MB8Ik|9Xq07t;!wMby?J~U3{lc2zMVmA@ zYDCdiV;&w+v>|?f3U{a=gJ;Qrbjbjg3}DFsmJG~qGJqumSTcYm0~p^WmJG(cQ?v@^ zcTkazZ#lYe{ElO@OG#O?^!e^ba6V~rL9?{aLmkLF zU%F}f?5^jN*O|3Rde+RV$-58PIK67$TgV-L*dXorVOR1A%hpS`Yu}B$<4tR)r(AU( z`Ruuk(iZ36Prjhp>S@=;4^Usvk^$`?8NiYOEE&L(0W2B7k^w9kz>)!Mb!AR>u9cF( zrT<7yqu?e#i8?VdVKutHRLwq2zZOSBBl+8%%Do zeMPwPn1SR*Cru4uvwq}9hsE!!cYcQad5bAwv%{YxFMKb4gMIO1{lQ|Y{AQiS$;lQ!CtF;dZ1Hxo#o@^opJ$)3 zxINk8`DBaplP&&FwsQfpofnYp9D(KA`2yL_9mw`gDl%f=G1g7C7$#b{0UkGXk=m9gyuzfox|DWIKZ(+t~zJ_HyxX zzNwMzkS^PSWjnBJ2bS%?vK?5q1Iu<`*$yn*fn__eYzLO@z_J}!wgby{VA&2V+bJEk zQ~qb;cmKe$9ay#l%XVPd4lLV&WjnBJ2bS%?vK?5q1Iu<`*$yn*fn__eYzLO@Fz#%P z`;qU2bX#*X@a6eBMYi>eZ0lM%^4NMuwsnwf>m%9LO|q@0tXFlpHIerORF_*rnO}7= zf4;smU3DQ{b%9kE)`(*lRHUCy-!Xts>{^z7)^j;^Q95){y3Ye1xa+v|)%J_HW*v6R z*tFx93&?GHzmyJnJHHe7yE{jxWjp5g2Fs2gmCl}<-zV(3&d4;{n00wpU8q;(gH=9Q z<%3l|SmlFNCgl7Hqi?BRvepr#YkdK0-2rPo0&ATDYyARiT?1o%#5w}T`iOM|to2dp zSVxo}>j+ruELiI=SnD!a>or*GI9TgDSnEDm>kC-x4p{3ESnCv6>law-8d&QcSnD8I z>!Z@8uhvtfYn=sa{RL}X25Y?rYaIt`eFsCYa}GR!wp(+}n$V+T&PTpn6Pk|C`JPU- zVWTrzGSBEQYQx0lt;j9@82y3$Ta(v~zw_Jl>^9`JThxa~N46zT>s%i;Z(2fr=gRsp z<&M%K{o0jDk^jq64jxY}M)|d~4kn}Cs(J0nkmsi1hmaxX^+z2_hWtMa${Bj? zS()=`k5(7yn=Pp-^3O@)cXO?rq5Uh1@|*8eS=4*-xQara4wqB}$@x%eMUebA?Nw3e zg>>nQ{Avf3qxM1hYB$uY_JllYXUM7chy1cjmpkf0&60uC_ruNVLaz>k$n&184eiI~ zys&9)$Qli1`d@C3Z!FTB4_h%U?!|LP`^<1Lc8RA>bLRjQp=pXkEjX9pOflPSiX^;NRhW1MVbpKNmi+2#r|Vul}`Gnm}x)|#;9fjJ+$OKk|>4q|%zg}Si(nVc6K z68*I1IhT))W3%5t<~d~j`mp_aIe&3fec1T?0ZiZelKQaT*#6`xm)D1n*2sC`$@O7m zhki`obldvSdPHCHx7Bqa**NEgo$JERU7ut6OK;VN#p~w0%Q3a#%|XvH{kS1DVMgbi z$9^Bje#@L;ua&#xyxJ4hp;xP%_gr2TzC1VQg@;y!$s=?AD!w0jrCDD7ioGhs{6})W zdqPDxZI4`@&#tNnZ%oVi-h(Q_<2UB=PmW{1(|);LC2eA!cXNLD?27R6qj@_#G`J#+ zP4o6?7Wb+j&Ca=bx61J58F_o|w`EoMb4AW`%d5ijt#Vs*yr?>yaAMB=w~6OC7w2rg zO2AkHM}H>BUy6QCkRKKOpCJD#`b9y0SM-;H{ITdq1^IHGqc6nr&0k{q=0~x7u*wIk ze6Y#~t4zr0Ir@zO{v`5>7z-GBAtnZPzH#DwyoH*Y&alSFr%{OL# z+as_X#Ka(v^Nm?AVq!>lzA@!QOic14CI)u%Wa8$@#Lbh5n$T;kTa#I13OTjLV9#?f|hU&C?de3HcZB#HA$ z66cd7&L>HnPm(yFBym1T;(QXOn@__0=9{scxUZo+&L?5LabLr9=aW#*xUVVXkNX-j z`efYKkev^iI3F@`K4jv2$oM9X`zijf^C1)GLnh9LOq>tNbn_vZ-+ai#`H(C>?rT`S z^C2lu+}AMO`H+e8A!#q$k0fqClDPdy;`Sqn+m9q}Ka#lpNaFS*iQA7PZa+e^}Rw%1O~e-4;G&95d~-zJ+MPPVZ? zHou*0{yf?3wKdj?blYodY!>C%URz_C={Cm6HulLjCy;HfAY-gqY(#yP>DGtIwm%|U zpC{XXifm(q>|!GtQ%rZU5skqjzr`Fl)+{!nvCKR+#>qDJ$u=jDZLT1juad$>V2kyU zEe1%A{tsf0xzCX;<5BOJu8p-w9IdQb&B6LF#k4<{%x}9h}zKXv1MuWZE!amf`o%lgjrehdH+_ z!|$OdUIyqW+1&5TC+_#<6ZiY_iTi!|#QnZ};(lMA@1XHpkQ3vZXq4}{f5R2&4o_7u z{o!fL)4vX#M*i-qRHAd?tnqy%Ixl{@ zW_~-JBk$II*~>a#-emKJWjc3$`l0q^I*(qfPlqy`Q^W3_B?HnW16VSEB?DM8fF%Q1 zGJqum^Oy`^)eC)B!I{gGxjbakg>2=Mt=>FO-X>&|lWg*nO)s+POSX2P44zF+rb`B= zBhw`V^)(s5k^w9kz>)zh8NjL+x_h>BbJius{Ap*(Ma(&#n-{TYu>5eaV%K2#?O?^a z!HR){-I;O`GgrEuDHkzzm1AehEZ@$QS+AWbQyx20rkr-BT*UlQ4)n4+0L2*r(sgzK z*1id>vj(vCSzw(_fZZJco^eQi?c5>5~8NiYO zEE&L(0W2B7k^$^xn3@euH=0<@J9yV#H#Gh3&GF=Oj~$xse9tKIQ3nkz?t^)b->~96 zB9u9A@bkRe13vkIk;R>#gYOzq+yxr)=(7dU`in~M2wjWm9DY~KG(BiJq)YFFY z4ie58RTuc=(a)#b56kZnUGwb7^nl+tigyC9d$p>p&6_#TX#H;4^>m$-UMoIE8?&Jrg-e~;VrDs}pn zx^^gW?Nj2~t;DrwiEHN)*Zw8WF72F6X?MFDNwzzaWV=gAwtJpryL(BtJDFs=tI4r% zcR0y*x07p!XXqR6$gwX;2J}hE0G143$pDrNV95ZM49uV3W&KgT&|NZs?anRph?WvVCe;xUSR13mR_=#fB*8+cQMFs_DzsqZ~DM` z`-VK8eI9$~$o91Nag^V)@}M019wx^ZzTv6wRpLw>J`D1F^6Y@{@)_O9XWrL8ES!56 zIT_Y3{4n@7a*MV5g&r%eBRA>aH#}8+3Ay^tzG3`{oybQG?Hl%Z^F;EMP5Xt`KyM5!h4(TKtBGm!C|kLwj$SkG$h=4%I2A3 zFOWIiyDrQyrwskPyx#|DM(AA2zCc4}=n?(IQg{Ej`dUT@Td1zQacJKozf zd*sZTu-=jJjdp!cmKo0|L)q6kqpjwi`7qNDyK87TXS1Adx^hTpc=SWO`=mVZ6IyIJ zG@Lg#PjC73;1Eve#XRq|i*FxhJU~9{vjO4#%kCq;_Im$tcH~N~VlSfYP8{WA3Sn{mn`h}rKA41-s zQUB2BgEr*HKIk9jKCut^_yz;R4-f51em5NydTq2ldA-L5hZ{?`A`fabG#uAzbM`Cm zJ9+kZzgNN3OZUgnpY4B{?%BRM!*u)33E94XQn0=?s_*`x{q@~Hu)g~Tw(qV4u)ezp z{7WM_u?^A>gPZf4c!3buWI?A+|~JTMx0_QneLW-#OIpEZ~1* zJOAjn87WKyVEadr>{;o<29ZhDk>5?GbbR?r4qV5Ij8#~r+Ot;(f*ZA9Z#qYq{Z&tFd_*;0z@5b71Ycjp#R{3x5LZ0~hZbhE> zyKg_+Z_A>t_$@5N_b9{9`MVoxbA4YlenSuOQr2s~F+sN9o*>(AQjqPpD#-TR5M=wU z2eSQ69NB(9j%>dxN4DRaBggOi6*BnWQu)vRt`>CE?|gx+`~>WO*F(Q~hjjhs9az74 z2i9-if%SV9;Qx-_hC?}Cw*Ra=_T5Fsy-OQR3XiOqm!AH@^kn-%lftB7^V3V}W+vOl zz4@KjFG$NSoSh77Iyr23^uqM|+vgAaR-SvuAa{O)ex z{WcKgy!eUdF(**Y`fVV}Ijt}Yb3#Blzh+%Po2?CC`z_ek6tJx+U|Unb*5+7l(YK8# ze`|mAZ6nIx+8=$}i1!;?dm>r!Ins3Mv(`(t?=d02eUAxj-(!kol0>pipu_gvCFroq zmh-KBcL_SIvQ3WYJHyWMLj3_V(k-`?v%F?=!wHjTq$9pwmoM|^yztzH8R_{iughOm zK_YnemUZf}b@?Zg#bN8mXQqc;zAis&_oZRy=CjhVyRFO5ulr&+?DARZPg}3cU)p1N zh|V$TL+QC8SaAv)6x(V1q5&NM@GrWv9$&49Vo+JkYo z_JFNDU~3Q9+5@)V#%)8ol@px>hv+QWVjXc79HO(}5S;~cZqc*gO=K9I1&8P?I7DZ` z|4p`fX3h7BjH7W+{&ZTV1G26qFWs0i=KQ9MGsarbq5Dks7i+}UX~tMPdi0sabgU_r z8p=Ikaz>1`=G=EO#v1hU^w~_u+JyN5d9Y@|7giY-`I~o#a*rD6KVv`j#(B*D$oRqj z(mD&sKUKZOzi`7sa_0-K_NTqFh}@&rNxtzni^+donfS)?K1fz(ZNKZ_rR3wkeW9@5 zcNy2H)2mRX*)pbMA3jRYMfr14IW8*SMfJL0JgONY-<4+x?wT|o6OhLedFhB@<)1+VcSP#lK;_| z#yVi}Nce3Wzhp5^NdI@mQ0X|bZ92Z>-xBw(I>Y!Y=?mT+AghkCeAPXZ33QSy@`tXH zRfmggveoy9IllUSF`W_+&eyf!^v}hykp3B$D;+M6%wgNY=X+$$AGP+3sRRId&H-*zRJr zbUWA6yB~|?{MI{WQ9k-*cZJ!R6w>uPi*@Opfn>c)kgRtMlJ)LEvffEZ*1HPHc4sNd zw>wM0c4w)j+Z|$hM`E#@-+C7-%GdrTV7rqOYH2)4T!E#1b^?q)=~o@*D& z|5xsuL^*oS&T>BgUw${E_1ESf?QgJj(Oa^`8z9}{4Zs#}0JeAou*DmIE#3fZ@djXv zHvn6_fu-AgtNOq;SiAx9SiAw);tjwSZveJ<18^K~fIeEk><&ZZ`6J)Wi1usD4DH6> z^S(aR^>^+G^iev;>-UZqvKT6k-Tz=5m&S}y&f10qZTP+K42)ESL&CC4$M7E^&X{GM^JC_j$VusigS zZg=Q`?G8P#-Ju7zJM_SIhaTAO&;#2Ydd#nP=z-(-WV=TW>Hkx)%BaiY?ZN+(G5_`+ zMAQa8Q@{7S7%E%V^?TnL7~flE_l&W>Z_dxlw_x&MyJrk+_l$w^y%+mk2+z}`JO8YIT z%yE(argkTu$RV}y68WUbp5>WGBB=T;HP(8SQ^}ddBFNd~1p6qKCzF$iebM zK2{FoX5~YkRxjji?ScHQofsEuzm8X`dWdwg<|k`8WG$bp^^&zcWNjx|+fUYhk+r{M zl>=GjLsq$wRi0#(Gg;+N)^Q>0cooy_8&W#HOxJNIt3HrbPspl20rFA3BCEcURS(JN zujnUP^_HyqOjbQ-`Kte9eJ;rQypZ)dO7*NW#k-JT`#z?gU8a@FW$ALJnO^i&_T5i8 z>r8Ln^(8w4O`Cm`efLw&M)}=0{I=(L;>XH&GmY^rRItPb$R5joG2#c1F0otb_J1Bu zme{TIpik~2OYBxUZ`5DO61$b|FyT(J#BQYzHyJ{f*sXNS%7e%fyOoZ<=615gZpr&O zw~-}wEA6{W#uB?#WQpA>=8@Q~;%{%bHZ7LfXI3cIl{62L2*nacA_}$5<5}U2Z^01>WRco6!k~q zC5k#`-*ZHn+U5Y(zL2$#WbHdyWkOb2kyVCdl`Yx6LyhuvESRoiMAoq*>zI;ttjVea zWYrC_>I_+RiL5$CR^213PLfqu$*RL-)orrsJXxOwvOXhZeRjxrzC_=OZ1IzL9%Hsx zN_}RTU*Z`sreuA_$@=V*B~AllN|v|?j44^im#n%+RvjR#Zje=H$f`?Z)iJW_9$CLH zOxEuXll6PVWc^MtS#_T0lG@G$XO!B0vdw8ow>b^0a$p{t(=^V6`mb>&sl>@7i1U$H zjuf$T8fTIsb`Ehq63dYyc246=QpC>TJk;6)oix^%oZ>TL^=jM*>(aOp)}?VHtP8PE zR+q+&ur8Eu{RLZp!PZ}}^%wl_(1)na7Dt3OTO1MEY;i=8kHrz8%{=2ay~0>nd!ljS zn3{ef-SiV|`U$pjBAHv96~>YAS`zOB*;>31+Zm0c#S5{W(Kxak(^b?Jv&3Ste8fh^ zZ0`#of6Ug$NXMwd_DpFETk%=5x*%tXH)H!XF0LqNi8m|CSz8ZTFrzqMcE<%;sR_G3)r_GtNhW^HYX+QW2P zn~-j66IjdPvuPZ)Gts!d;`1)CvS=rtcWo!1ca<}rcWq|^Ia}Mn);933SvRAxX8f47 zL1Q3`^MJKMV<0&XMEa9NI`-e@H*04!Ud*F9%-GJDRfn0!IKG?i@||X-JC>|V|J3Kj zaPBCXXRchAp4E0~XxeFJI(yo>bm@JILU)N@TKoRG^pv^tLl`_Gy|vN@>4YjTgdH!N zkseX|gY=|*=2*N5l} z0k)V8u=Oh{C($@M$k6Tvfeh_#5XjK(27wIiZV<@O?goJjEhYzj=XlxKebfe~Yum_n zc8@%EcCWECEJtH$AVZ6#febB{1~Rl*8pzOMX&^(3rGX4BmIgAkSQ^MMfq!K6g00Qq ze->{5o!9#k`CJ=E`e}Ez;O<1bvjul2+MO-9JCSXO>$Ug?$RuXV6OUbVccR@bgS!*$ zZW-L2Xm`ut?!VBV!$*u zEJbXX#*C$i8N*zP@)1`Sjdjd%+bB=XZ!ujchcWF)k7Bw|FJsz~9>sK_os4NmdKA-z zeleyU=}}A<L6PJTE}sWj@(te#Uc$bm&qf zH;ZYc?nQF87)a`BG%gl1N!^ad(PAw5EJWkZds_ZC-ruEn0P-#`yQA#cEr%8FC7XqYQcMjxw;_ zQ3kd<%D~n~u-z#Kwmap(cBdTJ?vw-DopNBiQx0r*%7N`pIk4T|Zt1vF&hq2_cCg+9 zN!I%z$#$n4^4OhnV7pTeY}Q5o~<~TOTd` z_q;a`@8IK|ba}TusUdeV?|4?m-OgB$ZgptJI~3-pPTprno=y$tr$@{kOaAtTdFiU7 zGG1L(;>MTrz5ZmF+~ra&mvMs=Ur2WxI-2<}?EXSJDQ;FQlcdGVZg(ymauON0`3)sd;IWS{ZNKYkt~f{KHIt^7HxW{U>HT zXyk%){*D=6b@alte7lV6ZnY?VT<)JoUp{+gQQA}Pr3bG(WpUbTYQ`T(Ond+4S@}=O zJ)Gg8j8A@NNxE(KtUa%HS(+aCTE@%!EKU2|nzetW+%sSCPg%b%IC*LM-d7oK(QRpZ z|Cme;AFo@IzH>k(pXhFZ1Y@ChBm7(Md$hYce_of~MUV`ZI|{1H9R+Ka4oPm6y9?fs zv2J_IkYvD-i_=5oPJ>ykh9u+Vu7lok*FpJv2PaPMKv*GnAZ+*EAhvn4{`_a?kBu+p zjm`J6^4k!<`@O6>f95fVfRF3^Fu8V%h3S{=GH!a_g7lMo#`nyepN_mR?KLBbokoUztna&v=S_o8z^+A7wh$i&6WGA|w6J z-)D^c4aSXTI?8#l*BCO&Km6^CQSav`k7YXA^UR`*(atf=#xWi3KlZSU(XS)q-hS(^ zJo~&m^ncrZ)cVZ@o8R&qei)LhxNuSW!k@dNWn)JVWae8$@ zeelCfUtV9zzdhrI;})l9JpBe4(sIXW#!Q)8CMFYW;4b$a|bB-vIhB`Q8@tME(ft#rLF;9{D3|C%z|z^vEA6`p8JPu@n6) zjvd&>4s2rwwy^`-*nw^Az&3VZ8#}O#ouy;!EWh4&T^u{4+t`84mjv6`fz6i$n=c8r zu>;%Kfo<%-Hg;eeJFtx%*v1ZQV+Xde1KZeHy82ngu|vA~l3*J*>G+NV`hxtTlVsiBAgfN2 zRVT@+lVsINvg#x`9xr1V)5Q7wCQq=*8Eo! zw#h8=85^ghUv*eOo>68>TD9pb?~7K>lW@;|UTy?x9Y^85qWq_d}dLC!5- zlU`kt-F4i%&Dyl)#OijpOnUvF>&G0>cg;iA-;%XVk37|~y2#oFvbK$^ZO-y%eetm6 zEM^S+*oryD_%Tbzd9KBn;U1)zEkDwgc~_Ff1x00ss4m6;{Jl6L^aby@!OjQconN#6 zEgj|jophG3>6A~*`dgm+;J(e%Yd7FIpx&=Y)_WJpxR3G9nk~q;0u1#$TDyHMC z7Qd|`zlBW9_XmGb_aXY@;9I7Q$)E7!oz(5)Wl!eZHABfQR*cJ^-f#$c-r~pdeMa3u zUOQ%de)$8plAk@{@qCw>H<52%|9HMv-#wDtsLg}JiqYjiR79?hvnxSkhP)ur4Qt9=##bK zn7!}Me=#y^gN|K@#x6wrIn-6`2g=+YqWzo@?dODOKPN={IU(B53DJH|i1u?rw4W2A z{hSc(=dcZ`S8;n1JYTWC#cVnm_2vKBeiY8E?Y%k3*%;~nQ}57WKD4^P`n?I>_paZe zAnP|8XnVx0-*I5Ne&2zt-+dtK_aMmnoe1icem{b9tenf|E&fOEMd7?{cbK4UdXEaz zC8mYnOG3KcVFI>0Ou%-B30Q0i+T`Hh@|`KzB(S%&eB4n(wmVFauJ_L{UGJqK>wPt3 zy~l=ZcbMR}e=lwa=@wH2{%3Je$Yb#j;9nEph5XtE-uI<#BkP?l0eMsoWV@3G>2@a% z*zV*3+nqdMyORg3x>jb|(*5bzqbG%8;%)!*W!Y z$f{#x)jhK6B>C4oBdE*XO9k8aO~C)?+b%=*^!ZyaoSz^M?iR*7FW{|8p3PrWJL6h? zp2@H1ntccDz9DIT*sPbB=Z058zGTUZFxvrZ*N zcDFP5^BrEvcRgbZ{&xM9ujF^Sw<3AZyI#qkyrMFB=PO>x@7}l?c}VA1@+a+EgZ#jg zFXxx`-ilna#>@GMU22iP>G@KA^b57gw;Z}W-@9&I@>l!6n4es^9=X#_%kqbh$XK4~ z{IsPRx81O~n11|gi;DSQcxhp=oMYZwP%MA<#tVw|PP=G+u{|@snOAJ*))VFx+rQil8PW_oyJes#V__2o=I|N3|GmEOyAY)E)J|G{pVK6iZot$e@wnT}~)A!-9z^N{to zWG$1db&<6VWNjN++f3HJkX2S>l_6PWLRMLkRfc4hEm_B+$hZ?8eX;xJ!FK;V*zTVP z+x_!kyB{8`x{-oaXUM8cWYsaU>K<8jlB~K)Rvjj*Zj)8#$@(mi^%)`SvqRQrimcBX zS)W0&KAU8HX36?2ll2)V>$6YRIf1Nm1zG1G%GU1NhkWe5eX!lP4@UmZL%(8vyQ>!I zIv+A!=Si~8dt{vt$vRJxb^avlyiL~moUHROS?6c6&f8?2&&fK^lXd zQ{-gS=(OSClgZ=1AC)$~VnUXu->7u&{5W!Hr%~y6|0ucoR-@7$^&TR(Z#61ich&=B z+i!s!4tnv?v_jSEnLb>8d+gb_kx$)cR66maJIViPdq>^pPe^x2YqD*pYgSWdq2iOFgC-2&P6T9IGbgYDZiV67{FQP5W}VY2FQmM7C;vg$Bdb(n1XNNB%4k4)F+k*v=nS)WI;K9A&obuSC`+B;}q zd(R83@7%HcU-B-S%&RHhS;KF^w%*zIVvsKLaC-K#GMu+%eoikr^(W?+c{^QK>3g!Q zkLkh3l(Tt06`PPO^M5KfAz9XiRBS@BtQV=+gk)JqQn3livc9BZ6Ov`!NyR24%X*ZG zO-Pn?DixcMEbCV)HX&KowNz|EvaENh*o0(R2aD;lJ{I%Kx>+no*3)A7vd$LkmG!sS z9$A-*?UePp*nU~Zi~W-Iz1Uw__lt7C`%NZWu@j1N6Z@ekPq8bCaz=g|7kz(US{GT{K-RXAwasMh3)$Ye zLtXJZX!fog((PS2@IQKwPsf5~>Nt{B=kxfjjvZOYlzDWl$@)w&kLm_lb%w0EL{=Rm ztL~9iC&{X-WYuA^>NZ(*o~+LTS)UQIK09Q6rpWrNk@XoQ>$6GLXO^tbGFhK-vOfD{ zofF7n6XF>m>-D)rrIftxsQ8B;yO*#iMkIs!`drui-WbY}1b#7!HdrukZb{7-a zz8ed+@5X}dyRl&VZYXImkH_ijcl-eBO7er$OhXtvcdL^Y_NSJn|Y$|blbg5NVmJNz;;IySmnm{s65Fk zXR^wltm8t~@gnOulI;#XlplYC(!PUl1uqjDqbw@t|^XR^wltmDFV z>Ufb)Jz_+<>cC?H%3pQLh_ugkXOnMxZbaI6!Ik7Q&U!FC;Jxd~l@Az^?p1OK`J=ic z(k=(?L%w0+@buVuJ;~QJAD*sSy)${(8N<>?U)-KNYS05|h1ng*``&+lI(T(k@)vj9 zmwtO-t1QpO_oh9YXWtfl_RxFMN~bhuI%Hye{CDt}{IYwsFay{F!k_S~W#dAE;lPRmYjOg`xLThkx9 zH6v?Xl%cjEL0y`MtiL6Hk(Ei-y2#oFvbK$7YMaU07qa%9`E`uQDu1%dpRDpHtNh6- zf3nJ-tnw$T{Ifin{K={hWYq_<>I31eR~=8zj~J1@de>-j*@GTTAHV-$a=&>GroDC{)nv*^Nx!<@T3KtKN|1dG3~W zrO!Pui0MaPFrfRvUuXXE((51X(dWv0nZEtHfj#30D|Ksld zE;$1Q|8Qd?Kk3%J$(OdQ=eOAINOH3+D*JQ$olfqvW=-Lau9uK^nmn#Bxc{|e{cS)w z`dhO8maM-e>u<>_AF|4atnwkNe8?&vvdV|7@*%5y$SNPQ%7?7-A*+1IDj%}Shpb~t zR(&JuxRX^M$f_q~)gQ9z6`(t@_`lW z=0(TIla8&E7ab#CTcb{1bd0>DX`Q_27`fAJb@HNPs?YWFFHnk?w$I1 z(J^xUyBp?3$H?RQH_nTWk#D-UNnUh}{J`R7dC@WQcXe9gY@NLOH%;=QZ{*h|H_3~> zkt@Enbzbz1{N4?X^P+F$112=gi@uTdw+Zx3e@oWilJ&P_{ViE#MOImnRaRt`6y%WR(?JWkpt5kyTb?i%&p*Ep`HIu@hj6od8?x1lVFHz!p0J zw%7@<#ZG`Nb^>g%6JU#-09)(?xZW#c@~@Uz&Glk^y)k+DZaaBE$1(Xb=a!P!o;@c2 z*lmmBJRZN*JY>y7)-uW3-+=tuU$XX>tovCF@x5 zJiX-NmHBRed)^_IK;j;Y{OB<&^6L+q!}J>azM9|v+429Q16gAs$QmO- zwtIt7zTF!PwtIuYc5g7)?hOXpy}@9+HyCX927~S1VCL6*gTZ!JGuZBkj`9Ss{+6s| zdZcSzWNiak+eX$lleI5oi)leQ|L(XEl&NFKHmhEdRjO5JWBg#adBc|(fMAqkstj`fypCht9<19y?YqCDqWPPs5`dpLs zxhCuUK$f`Z{7$#cAxn&L{-fa<6E5eoAFo-?bcspMzuaO~mj8j(`Q5(zh%7P8`70{? zNS4^<{ECw+v7Hk0oIm^3nq-{k{_K0K3C2$IkoC7@Ez=>7#6_bnvbKRNanWcSS=*fD z&-&sJGb!wz5={W&u4k=44!e;Gdzz5uYNe?IW_qEb%E#C;IjJ!o@;}9 zKj(Sg4SwVZ&vS6Fe)~AV8ew&T|6Q>h7At~&#r$+5pYJ^21%C7N!0!tA4+qRizOGmf zwtv7KEW6bxLw^3@r%EgJ`J#aIo~w5#Ozr+Q`Rj@U3V-cBm%MhHF$Me~57O{&VC2Pb zz$gP{fl)T<0HaPxFR^sVpR@c@4jJW0`DBzYe`M4t|3*fgQU@7zN*xa6piZfSto^d| zk|=*JDkm3}pNs0vMeWH&?aW2(cTvAw)L$3L0p%3XHq;r(4fQe|b)wJ6gE}Mm=b~{b ziO1`l*3JB=+oy2sP6=C+zklMj(r@ppOTPQ4qY962s7yYm^@zew`+QzN{;PT|DBur_ zH2fPFdGQ-C%0O9Ql#M=uQKzJrSi0oTS$-*pjB=!WGRl`fGU}9nb6Ghf3Q`9dbxIv% z)G2k4QD>B166McD<>aFBb5Xsys68%fr;FOpvD1Db-TI6C1?`uM7mZ6vJYMMI;6=?#t&d>Tk3ND?Kl%tp{pceY^`ky8>PH{Js2_am`4lv5c9~f!)H!$*|4lv3<9bmK{b%3>BmX5Kr{FIfJLm7h6r>I_x zowbK!fjp26>HtG8P)AlyGmfdHM{>Z}<&X|pq7E=*i9ayX@NZz`MIB(2fjYpDWjtPc zw%CSsqy7VHwsbf5aMQu34sFZy5AIl3`p^$e$%D$BUijv|T4dP|EzF!>hJ0=7R}1o& z!|x=`%fFE&ub1DDr3^1+m1x->|BL^mexy^zQYZ2kkdFMQ1B`M|2N>n!4~#VY8yI=< z8!*a1SzwfnI>7iZN-v4>=c00QQTe&3UKh2;MeTG^``!7q2aZHNkZaUm9J18u zBDp!K*WtHF!@p(ajLk_q$tWWlmy&-pc58<><2WAj?5fhqM>ilhJNmdn$yL?J2iAPJ zFlg3SIgGX2YDq!<$dXo&etdtB5`7qy=<&f3!w>DFK5 z&mmpvbdh{qBsbK{JV=xFxU8IqbNCGyWkln`=b-Jzsni4X&A7tf%I40w;&rB1_}jI) zmEUDLansD1xqj2@u#J+(wY;<)xk1>N19#~2RLRF%d_f-j@D91hSHDF@8Ld8^L*D(v z(K-AfKhp4TVC2Pbz$gP{fl)Tv21cEdUTW!*zhL>L95Tu|>HUYv4^>={TY2m=`LP?75=9>PBw{SX=MwiOumnK`t>|tetUHZbn<0?WnsmG2bUtxvc(^l)~w!}dDc`LDZd>*9eJ)k z?b^aIZ%t&Lt7<%3+GUq#OQ6H676$q4(o*DEw)ot_ZLupi3$)5X;XP!Ezmc)5VqBfV@(D*s#nOo9dep{@oB0V`E5~#xo8|qqQ1*-i(`?Cbf6@Xq5QTurnyLGN}{ol-xhTv7mcIjFX~cB zqyxD~XEw3nBinwn&n3PO{ILHtpDVWgBAalttuD4P?CAewTODHuzYJ?4d=q2%EMWK( z@J+z*W#Hq0(I@ymVE85Y10xOp21Z`|28=RL78qrtJ}~Np|6u9xD=a_!4KT`q9|A`C zkSQ2-!Z!hsR{&OG{C z+I|_=qy2~cXme!q6z#*NAJ=19QGOqnll>Ou{FkjL_0q=6$}C&Vk97Sl+P_JjsLhtn zJeD8*(Kh(#x00t=ZvlC3rk%$8$XhpeGI_T_%?sbYekA$H zR>KSPKHZCa&9t?JZNBY7_G9aK`6El3mw$u4I?3zhH)JWpOIc(oyVy>t6X^xyM>^^N zBR}e}a!>~t<>L>GG}Hk`Ui=1(GEf#6Wup$T_RG?9QT|+1PA)2+b>O#>#yY@|LDWvx zfpo|W{xTS{jQWfG?7P&7a>ytrk{j#5Z;^(7%gR}cc9KyB>OeZmj>k*J)V1Gc5c}95 zTtn{AXD6}GFD8$Dc(T~-Cz7E@tv=q1y!(gky!??R4LU}ayk35jLzz;Bm$JxGHpdR> zQYX?2V5FlC%a1z1C5`XqfFYZx{Tw@_LzYp0k>BKia-5ZeI>3-6{=i5>9a%YLSqB(pNc)+Nvg7dr zqks4hdGNnz7upAgOi(5mvO-;8^bhrcAy>2w40)hFFyw^#z>pvQ7ym)7r~{02)B#3* z)B#30r~{1h@drj4{tb-0_zf6kSRE)Ebs!!8Md=(nq@j&bIgp{1&#^-uNrTLpE_oqG zYbVDJd8F*(J{4pc^_Ox-9>_A15621VC?9`d$P#sckr%%Kqn)S&jI!f>s%Zae^S+|U z2YY`1Y5R(spRY`x|0vH_JYHbTpLq6S#`B1D%rkgSb&lP<#)(X9o`g&w8^{Q3^CTFu z#9U_SnBy!z<~}gW!JG)Tc@k{%B-rLju+5WTlpWhAk=?S{o)r7-Khd6)v7~Jbe+thV z>`d{4JjOWVP5rMZ5A?u(3)_bK$=D}G9`lv{U3>CqPvke5{~~Mjzvt{AYQNYp|K%V3 z`}V{CzVG&X?BQcvB3Y3!zQ4yA1mYj|t3IF@uL4HQ1>z;Zh`B%<1sE|Gh_3)6<^q3U zq~YJd$cx{AQ3lEaTf7R`;#DjiaUhl-dzE06gBT7l%Evw?79+p{MxEGy1EW3I+XCDE8`$>W zz>q8U-!z^3Z$G97iI&sjN)c_2eJkR8%dXFOi053vx|M~#cX*jc;;WrcLqkN$vBKk5Uce)JKH z`cWTP$8K}HO15`u^4T1(BFeToUght{8bxsto8wg^Rs^vmo8wimAGtYR1-7X81)Jkl zB=%!-yvpWy6^R}C&G9O*=VALrw*6+GOJwq&=yPqh)w5V`_#5hjz|SJXFM)reJ_!9L z^+D)Qfz8hXtDj}Q3H>t5ANex>Hd`I_!T-XuCQM%p9QkFN{biAljw5|%__>i^|NqQi zmOVYj$6`;?_QVjU5yjK~+v0n%XDIr&IbKEg9kDLK=dfTqhXva?EEuwcu39>D7>xW_N5FOt3%0QX+c_*4dGQ;tox_4r_U3pM zzEAguc@J*$^Ofnd=sKSx=(+rn{}Z3Dc)Y-vWAW_8yg6RwKR+gOvpxC8vL~_5nxBQ| zE#uAcDw*GO_rLM|&7$wTiSPDDk5?IU|87a&YDX31`@HU}j}A(PKK~=)OWbi=9h@}T zdD|kd?Y=GIGnnVn=YJ&Qw`Wv4Du>@TtFU|WQp>@m#xJ)VTmnAigKvDfZr`|Fwjbus z==+5~C*9!Y-u#HWXVX4&+pieq=GFYfUzq#UoxEVITUq8?|LOtXIQ(|(J6na` zjpvh3ezQtwo2(>Xb9(vk<>+1vgKKITW1vmA9YN0~2VeY8K-c`P(YAD(E zLAQU$;4Vq4g!4K*;`XQJ^s-Yw^ijTVa2ji_s+eO+}Zb43FnUwu33#I+=|nhhbJ4~#XgQ1*d)}u zXb5H4b>Lr6I!-*F+54}6wMVVBdy=}Pi`|jj-R<#S=Z#tg5y=_L2jSE(=_y3wlD{| zmG9d$Y}@6v9OU*=ho<4Or{B*(ZtHSQ!(GeDP;O^G)iktysVe2xb$GK-+N>Vs)_F|x zu+PFKl-p^ywg{y&T2gK^2Dc2Ak7!4^J=dg57}WTJ9CUBx=N&`akI%_L_onaNA@tw* zyc~4z_)cBIJG)#!9o}wv7w&69_tNLOgnP<9OdY=D<}P9Cr!AOA?$c);xi{R^xTQ|0 z(tK$S{QTVN;ejuEIq+?5|FwGY@75mt&f1Ccto^75^=ZG5UeJCazt?`D9I}>A z)_Td>o}m4rT)?OY@&cbp6PowXC?S^MMh zipN*So%5cKFImT(^O)*S0s1rkg>AwzV+G7DH!o}%j!Ew;Oq03gR(am*wZEf)x#i}`ZNf8q-dMog(x+OxFzS+P3z%DU z9`NX6;n8+sz+F3fJR@f{ZX0g#6xc7Cp8VXpEuM)ZgZ+t3m;6ILAkvt^XIO6rj%Qa1(m~fdrYU??mw(@ zsGEC|a(nWC%AwLt6DYSY=T#1O-aE!aZe#jZ2|qkL(nD@LZ(lVWcj7}Hayy`5weaDU z!#(77a@!i=y!rQf$ZfY~TZN`W?)H$|=a(ZQM_Pyo~f8xwW0s2;V z+z`KH_SOOV*6*@Aeg49x0s1zo!VdoMJ6lt3M?BNj53byja+|Y9cmK(?%_z6&hd94_ zuO^gR?V-E*hwC<`+;*6>zrU_o!vKA2fBm6;X4M7(`u6Rgj`nMItskIo6=(GEmlx^< z=-c4h=lFR&>jmiBeY;)icig95fWDnQu)nYE>jmiBs4>_1iD%aj(6{gU-slgl*C0UO zHkQA|FI(LpK;J(3aVNk0KTf^VfZ98(6`hO|hS*r`nT(so0!rLpiq1-+ha$#Zez8xvI zkw0EqIId$S%5B_pr{$Kvx((%4q0b??AMS5Qxt-Fhd+xfM+E8wHY~3Jt>6@)6w~mjk zDtYCcmXzD-G1r&;^|%(4+Xv-ql$8CXIpuc6BTw!;|M}*W+Y#qXm_Fg9=9JsxJKbJd z<@^?u+r8(lDE+i|OUi9Vp?2Yp39Tr%+v;~Nyi~aj<<_LF+$YkaE#vJx3OlcC7UnXE*HIg{b1KknpgEZ*H> z2Y2_~ttq$hNAKXqv}s4VJ^xNucUjqOD7PM0-Qk{pt`X(7?2cPp?RpIRIW%VexBb#34#`UU4x%H}lwrjF`J<9FcdZ)M#Z>mSRbzXa{yQqAoZ}$x8 z?FwV+Q*M3V-Oml!qao$iq4Vx;%k_;Yx2E+I_idRbl-uhAcXnI6A?uCk+XrR3xg-A6 zoN_y*?vAd<)E1PRJX6k|sV{pCb*~-VgmSBS^y2g~7Je$s*O?hUWJ+ty`I(s(d znRWKe%Cqn6*%ztE19$Ct z>$xth_;!tZ^t_L`F5I+YmAmAWkGU?~?N+)9z1MSHIN^?$-0(v_<@|Q-_e));9Y5#% zHhTRc*ZJ@-IKS0AeSv#>_*b0Yy7ZgtreFSjHot9r-d*^?M$T_z>dkU}2bQDUF6=hb zEgHQA<<{`~8Seh=DpGFG)t>2^K3$1&lR4apzr#6P{2eF$4%Y?ocbxb;zKiIatOZVd z9M1W&MkM0n*jkW?k3*Iyc{L42I#{PBV7 zg4hg+_&DsN_&AC9IFy_CIEnZ;l$+QdiTF5_iP$8G_&8*-JreP8$YPTu;^UCTwn@at zVVUCNB;w;xZsOx4;^Rt`2O?;e0d>qP6e4Ipl9Li06oJ4#a z%1wNnM0^~|O?;e0d>qP6e4Ipl9Lh~>)I@w7+Nk2=B;w-~)W=E0$0d!5?7iP*iAo7laH*u9jS*u9C^y_B2Sy@}Yp zl$+SSiP*iAo7laH*u75e-bCzPr*>~5cCS;rHxawnsok51-RsouO~meXYWF5$_d2zE z6R~@p+P#U`y-w}kMC@Ltb}!~4_EGHKMC@M5P3+!8>|V-E=QPSh=Q^^^X=Jf`G1rlG z&SaTl_d2nADL1iuo!GsUo7lZh>|V<4nVPel*u9C`y-w`jMD1QDc5k9~uM@jBQM=cP z-J7W0>%{J*+{Es6V)s&RV)r_+dnq@ud!5+5l$+SSPV8RFP3&GLb}!{7cCQn=mvR%k z*NNRrxryED#O|fs#O`%s_fl@U_9bffx+()|Bx?6Mv3nEfo35dW+Pzp?$-0J;b!{c< z8qG4r?sa1KCTjOOv3nD>d!5+5iQ2tR>|V-E>|Q5!FXbk7uM@kMaud7PiQP-NiQVhO z?xozs?sa1KCTjOOv3nD>d!5+5iQ2tR?A}D}UMF^MqIRznyEjq0*NNSmsNL(t?oHJ0 zbz=7>YWF&^dlR*LVQaCEV)r_+dnq@ud!5+53G6qu*(ejW<;ZHYk=2$Xt4+u<#qQ0C z-AlQN-J27;mvR%kHz#&4}c(+XnuQf^}R7R2tQ+{ErJh}}!MiQQWeyO(kkySG&A zUdm1E-cqr9DL1iuOU3S`+{EskCU!67CU$QRv3n^uv3pCz?xozs?ky3!mvR%kHz#&4 z&5P++{EtnV)s&RV)uHndnq@ud%f7b zl$+SSUhH1VP3>b}!{7cCQz^mvR%k*Nfdtxv4M7K8oGz#qOot#P0QC_fp@~C#6i( zS0$@YN>*Q$tUfQx6uZ}p-AlQN-Rs5frQF2s^w2+uvpH?!^ImLS z&S_%nda-pWE3tLG*t(RJ*t%Y9UCK&qT`#sSWfh$r_-Oy1to#2yIwSC3%K1VsIXl?D z`T!rDHF%sg^vKQ{$WLTv4L+LRe3t`abF!Dc6kAjL3*S8Nj`*T_GIh~NUtRo>b7fq1Df5tz)+YZ=&kx+< z^VhrKmrU?8ep=(Yo&T}x_v&On?afuLlZ;WtGoSXK?7Gs8K5V@^?B?ly(w#54tq%Is z?f-hgk1Vsyt?u%HFyv-&XvQZ97ybA1(gK zb5klMU28qzqqWs{Ir9tm^fMbAWO(F^&)h?$pE<}dTBCimcKc|J_R-qy)gQrn?Pc%I zY#4vpjOt09TV^}RZA{NCliu&mb&y+R3;Fi1)R*=SqTEWl)=f@WFqm?iI=5D`xc^Yf zt=9otB{v>;H|4g+x7CxAn%qaZ4IW-C>C|W#<@U&}Rg?9tAEeyoJyRulyZs}STfa~_ z`Mkzh%56)rox0VVK)F>Af8>E%rZ~v$w&9hNGhd(TAh({CswBHCDs_W{#N@sX|QBb(4iwxU;mgmRO;VzZh3iPhUB z-%RXExosi-$cXygD7VP=_HQ54E@^jY{~YwKLxncUBQtNwLEmOpZI$#`a8C~UcH|B% zk{6qd%R%23jA@p%dLhk0-(FqaG}*bZFb91bCjQ8p`mg1nZ!J4EO}-lTeh&IJO8k)( zv&&F!Pd(W*IeK1I%B|+GW=XDIJ<4tFsOHH>vzkzDuio4u>0D?@xz!ugGCBC5c9fg? zBk&#k=NmdE?|*ns4sttw-ww$SUC+xw-y$Ex7`};*d=O)tzxc?<@$k{)911>~Z+mdZ z6w7NBnz?A$4NP4?lTZ;`L(%Pwh|%-X-bhurSjszq{A*XAB_>oc=iviA7;9&+1q zR@0>Elhr)rcFB%SlbvR7EI@AWHfx$pd-#(ACf23(r=i=oB$nEKZ(Sp~Yw^7v za{F#;*#o)jZV$QLeo3w5!bL+p-tm((6@^3&va+MS}s7}1}=Wy_1?Bj zfW8fRX0E%x&i9ntkKO0H&)@!V7?+nG16cDKtuJmfZT$h)qb?88HDVdy%y)2{0&w`ecUKYib9 zS7Bg{0DZfu_Vez9O4S4OE!xwwwKYJ;qCGuZTbUm18Tx3?(+?ao#HG(~9iVT2yYx;s z{(`0f`WEe-`Z}Sjd$npy%5BB2-QAAYHKW{W^m4A|zD+2%qi)&F-Cw^k<#y5N{axo4 z4FmM;&?^pg+g6w8GSRm`cR$*d+pT_pzIAxIkK14N*r9JPRXoR4-nCwUzFofarS9v! z>jmiB(O36($ID(ls*WWJw z$ol8oQEqd^AKANUTgolkL-x_$vXAzVeYCgiqdjUL?Xmkxw_TV!d!LS!+uPq?nw#38 z6Xh1|)%zbWI;8OFuy&N&&3(HU4!Wfc)!Ba8ZuKa) z(_5b6ca?p3$Zhqf$NG!QW%{;oSZ{yv==zjfrBC@CPgWYRqaIkyr3=wv(7rU2o6T8=o-AlPeXOXabz1Y3ky71E) zFLp221+ja**u7jA#P0QC_i|kjyVr}|%lS?0UN3ep=Qpu?z1Y2+-^A|qV)t@>6T8=o z-OKq+>|QT+FXuP0d%f7bl$+SSUhH1VP3>b}!{7cCQz^mvWOi9C1fn`^4_`V)t@g z5WCll-OF_$I+KOni&!Jh|IwK&>|VqgFw?(5LF`_x3(?s( z>|SZ_Aj(bb-XL}_*u6pQUdm1E-XL}_|WY$V)q8I zduhLk-5bR2rQF2s4Py6FZesTav3n^uv3rBqy_B2Sy+Q0=%1!LvAa*b17R8Fd?hRu1 z7S!$yV)qu*?nSH-ZC#B&!9F}}U5hm`#y&jkUW;FX-D~kzuzQ2py*agegV?<}wR zh~4Yd?hRu1I<|V-E>|QT+FXa~P#li0NV)rI$_j<8=6SaG>h9=OrXs^%KP^L$F zeb}c${0a8=VE5XdC+uD?c5k9~uNS*FQM=dnPGR?Yv3n^uv3tGPy_B2Sy3-3wcbeH6Rbi``4PiQVhP?xozKJ!IIuh(DpMqCI5Ty|%XuyBF~% zEK}@W+hd2_TM)aKaud6^Aa*b1)@rYsh3|&6O5_`a{+%6mC|umLO|tB=DgLOF4l3+^ zVY{Sc$pncDJh(8oSC+@Um@7PVddBzP-nKBMU&hF@*M_Fa`{5bpf9$?S$*E_|C4b(N z@s{A6@pX+Fx<&8TOe7Z3pS|QVx1w)l@{v1^b-RE4wL|*KaZ6m4jejF=+~zaa{>91U zo!+RBoPP5SB|n>+s)jg2D$Iq z^K-MuF~-tM?B&R5S?r~k^n#^JesB4u9B<`F`QFNxdcD;v?eW$gX=ku@O8bMgU-}iS zU((-T{S`R`lY_`7n0!QT-sC3o^d?V{vo|@5{JqIv#>LyXV7#Jn%thmyGkx%T*36my z^uE1q&h(+ti@BWXNpv3M-y3~!?!!Utk~aoV@EyDbFRha$ z&7LyfjXErTO-}q8J{RKG|$@N1m-HGD3_ zuW{nn@VO9Q#)&V(IYfLJC%z2l5bPIm;>$SkWjKe3FXP0Q;T$5q zj1ymmbBOpdPJ9{8A>zw8@ntxNh%e*Bm*E^DzKj!JhI5GcGERIM&LQH5>?EZ-Reo>p!#`|c0h*(XD zc?j};CEuNtn1>+mR~A{`uPoK~D}%gWS!B(RxCqNn*8GU0u>Ahl+ODxZ9R1e)5#ya= z|M8djiSPdTrP7Hzx1=vQsLFuSFZXLfuGVbg^rbI0C$DNev4`=j$^%L)PvbwoRARqP zW;6|t^jqs?ufSE_uVGlXWCMB9HMPSni^~M0_c^V4SaMz^a^J%%hKnVJ9O(m>mkW)~ zD@VR?yRu==MrFyzoUzeQIc_7%iT0>nv={B7J!*STmieFhpib!6WeK^oL4)vq?j`b^ zWsSnfHd$=>iL15_V;^6|^sBCN;j=4_BtNpSM;Nf`FXVTpbqg=QaXa~oo?XMGSC1f< zy{}{V>dfKfrMI>Zhm3rHJo)CfVcR|KC;u?Mb@Vmi7n>n;%4$_@W^1FEgH5VvvHogN&E~ypJ3t z28r>^$RqD5W8c*^>zIU(4!f9K*s@1h-?krl@F(5E&C4^c`tFXQ@sKN-uKTp)fApSU z{9a+Sm+Rv9Mx*^+r{(9+o-$wT9L_$lAGzmeE_~SJ67qNZ^$g<=KZC6DcgU~fLe}vj z>o}6@SL+_OsJsvPyc4>H#l3eW`%|_LAMKeZtDMOye{!^sYU9Q9Xy4W8_%i+F3)+YI zcRxTr?1YZthogs+_nzN59Mxt7S@l0b`}MgX>+`}q`W%rff7K}LJ0Ob<9@3#fXmip_ zOuu+Yy^#EM8Cmt59PM-3bHVgzpA+v~6yGb?=ZksHOv{DWPbkOsY;0aJymiYKyaO8xx}CUNgeVpi6M;kA>CPz-RrL%+nT@K?xtb>(31A#E6#Y> zcRi;A`GPj1{mhTD7|!Rv99gLT)1R2W{=5$ht6tfa{KAfn{Mmc;Bwu!1;%_}5PcE$7 z#a}YEJNfaByZGA&b|trZBk|9jwLSTYH93FY`JKtpzMqTs_gu8^hj*-OKhRxM_o~97 zYj@;t*Df7UIQspa$!DH=TjAhm9XWU8J%#@7??S%xxWrl8q|MISEPcsYU!;#Y>*JgT zx93`Xm6h{Vm4UfjxgIR%<$>4ax_;b^EN#eH8>0Ogv>EStF;BEVvq_Ax^xawC>$Kj* z%|9cP&lYQTar>N`$!(k3ySQuKC}BCG8_sk?bjF#^h%PzPCDAcwI=1!nhh3F>vvJ&K z%rLj(LD~2odddCHUEP*tiVir_fhg|LMe&VzM-uO0F@F>f=|uOO>E6qImbqB}OJt2B%Nm!+8b_8jE|E2k zEOTHYYaChT#((;5h{kR)zs$XftZ`&n;}Tip$g;*Ivc{2RjZ0*WBS&$zSl9mUJsVM+ zE!Mb1);O*mvc@H{#*t->OJt2B%Nmr(8b^-e@tnrsaSe^)@iuvfNPk<<^(&F}i!AF` zBI_4f)~`g?FS5$k>-q(mlXWb}I!0t!zYsKP{7g=>Xp#7@zWPKKxN1qY0tY3+&Uu0Ro5?Q~< zvVJA9evws&$*S9A)p@c$3uJvp$olM%W&KKI{bGA${Yqs0BFp-f$ofUrxrMBA4q4|S zvd&RtS-+gDUu0RooUC7DS-&KfEPLl#=Mbhxabh;-Fg=PB!+YGtcSUvXVjfw)oUC7D zS-+gDUu0RooUC7Do!iMe=aY3UAj|rNHG(Ybmy`92EbEt(^@}X)my`92taCV7_vFbs z=aY3UAnO`I*0qBy>sL4DwC3H#ld@mYI>ZpYkA?$&6pFk$r7ejnxcQGUO$bK}scP>sK>II(HC zc~&KIr+O{JjZ@2$C!g3RT-AP~lXnwbl;21BJ@Vg><@Zx0{}qy7+U)m~whd~$eL(xC zOPhasy(_t#^kwC>-N<95k55+aL5}kKD8G;L`zXI3J+6zNb;|zy?U?nA{Ud+wMXuJk zqJR3>1IX8(@J`{yHV2ZU{65O>qx?R~@4L&`JvRDk&+(Np+Ub~^GnTPFZofOp7}Jie zhLfZG98=BDvDW-P%I}{PS^cH`M*g<5$ng59<=M_kG8Q+^szhESW7MEfEkOQJevkYj zbL8>Je^Zv<%fJMKjdTiAs@>R{c)l{3Cb6JaH2nC(FZ5`Ll%8-qCey)KlI1)Lw_tk z^vCi;{)xz+Z4-GWB7c@6@=QejWRa&tj8;oj{+1u|PfX{LU*wPckbffbCtrQSJGtem zdzBkkbf%M!u5au{s;-V4*TtC*NBMn}-$(g$4#9RWe1M5y%H)r};UiG9Ti% z9BY{m$;dDBAz9{=MCKp1P3DtC<{z@mCyC5IWSM^wnSWS*lppht<;VPku|R&zKZ(pg zEMJ~?$TmUy<#~59Kak~l$5@c%dC$rGK#uZbez5$QA1puS2g~neyb3bD{B6Z-&LKZ6 zbCHZMd3ZKQQGcTR7+=g$$b<2<{1{)%X-tp&Q$M)j?S;0P@8&yI9az{u^WFS6vi9}N zd^aEYk1@Mn;!8$#xu~5nd$l(b*n7X$myG;M|EAamXJ@{xuOzm?1(|Q_s~vGqZhYq3 z#&vBX^GN_j(vHecT_AWeZzaz4}3%|G6eqU#M7ja#i%xTg5hW%Cep0HK?)#7`ek?pVgJH_{G zneDIotHk#_AlqN{k^LOA`z5w?R2S@o;&UCb|1Gw3WLNu-#W%nFRNCHtH}TCcX-u2k ze<{BCHGP}0zfoPA%xTg5<|6;g*B0M)X|{js-x1%ocea1)Q}J!PX8X53@{eM6zrWb&dnEh|@l_I~%zaYNS$glBTWN+%V%(nL@ z%HGtenQiYslf9`2GTT0`Ym+rMT7R9+hwQt|&pDZ&$ud9ZWPT>g{G5~dnH>2?n4huF zhIGu&|I}BC>cX5{v@0UUoQeHRmicRaC0#q%PMMzzGCz}LelE!TOqTh%AoDXhs%sOQ zIkKN!v_Iy{i0^+zws-A^iSNH_ws-BX7T^DXZ137f`&Ti$U$U1K)df4*?6jEuZ`sR= z_O<*P*&BHy+uQeNozOAa@fhxj`J-iTWOlZX!)X4V6eY8Irv->4`l~G+TvXf)>zh$p7+PCx<%ihZe+1Y`w)}mrk?pE%3 z`hl|dGCMmvi0j(KW{&OcXn)dU@9XUB?8f(#y{|8_vl~BG_P&0~&Tf3Pe;Bj-C3}fc zT`uxdVvgV0|J8em(Y~Uu{l(77W7*l3KSA~et2E=;mT$Iy&*ZWrdA1eT^$-2HX#dl1 zBYT_Y9?J7OzfkrzCuZk&et5RGiTy?&?N7#xv$lV_R~gmiV*fE>|6BGdqkT)itL**G z%FZ`^YuWp~Av@pnJ!S9r@a8<{SlcH>PU7+GvEoQM9L;a_<1FOUxZ!i#@F7XQMFe?gAw+GNiy+JD3Pg|l7em-Wlb`bC!Y z%gg#jmi5ca`bC!Y3un7OXRKdd&f1XfW)=4pBgUHYFUOO} z`em^tSigd-Uu>tWUqRL{vaDZ0)-Q5Y*Cu;z*nhMAI?aVi*E+*gknHb0(sl<$7+ zS-(E-Y@7HOUi=HP_!nOM3$pkZUi=GkRM#eZKJk7L<|vKf!TKI#ea}HRWPJ~^zLRBr zM|=)h=fI!yFN&p!>caY7jK_-@YcAFc=%@R&u{63~P`71$53;_KWql8_zLRBr53;_K zqq;UZ6Or}3c%Gtb-2Y+kE5Nk6wY8A}hG7Pn8OCreT3qH!W{@I<;suHpDoBf0uoicB zcXugLm@nCbyB8^5+@0bS`1iYZvQIddIj8)$=ib|vJ`WFXL-xu_-j%FmeS5D^ef#`w z+2?n{_W9ki&+mlo^SfoA-w7)p`p+2WckAE1t7Ejq;ZODNJ_g2_8v6~%=WqJ1j@oaK zZua@zvd`~??en{3pWg}F=Xc9KzY{jvdgV74^Y6 z$uYj8$8Vkb`+9DCcaQfg^!oq1)_mhTI38E7HuIfKqdxLQ{M+y5)R~v&qk+wLa$fls z&ya7{;dVK4DdW2&lr!~xpII)Aa((vK?Yi&V7;=yc;0lehgi%V+$7ARWS!(Zq|=0H;(cBm(C++VO|*JJg&UfDz_N= z!sE(yY<{0*)c;+1oZ^b#8t=fok{im9kNX|m9Lq*-CH?*tIKtfrIv+LiX6XFYI+jH| zsukP>;>&KOY$jq%|wriC0xboGj^_IpnuAKQs zo+7>elm13|ocW7vAEaZ#+DA~ojCXAGnolxKeT+J27vGPQo_0CjFC{rfIsB0>*S{6g zcq%{mU+Tw|o5=P%`hEoH=C*5;!ymo&-UKyYkXM1nl{4A=p3bN*jq*72E2_E1v5py7 z&si!rWg6J5!__)KdYbPv8s$3g9LY3e#RfLz#F;zM_?A$wMbxfQj{9O>n>Smn&rul9 zb>p|ZHkY#beVkGMcjft1z97o*3&7f^P`N47z-Aq;{1o-ee8<%&*ZJsZJe42(XKc!e zGl!?~ZJ_p*)UHv^)*vBY@d#|ni8FVl@x7jz>yjJgJg$2g z?Db0L-NO3$+PjwQb<({<%BYX^Q*_bxM|KIXeF zk28Olih)qS3=A97-+8@~6U>lr*1^0+{wtbC=66^|Ip({YQ_GBv8`zW+XKpSt=a?b? zcisDD@5gi=LYy~WdpDDjpAhFwU0)jIapo;lF*od0UWvCG@ASTs3(=5|^QL~(cq-Ne{GYdOfv{o0&_X0An}J~ztayr0YVr#e4joOgs7c?)q~ z)AfH>K0_lugL9u7t1)6YujEKH(^?z6>^Rmczf}yEB>#D%Sna_?7x` zN|(snlcTn z#|?EfkF>8-<4pT5HU22a`Q6RUrMRR0n1M|>apw54&*?f3zvi0SHOg^*e{Ft#WzUYD zaoiDLqLTe@#3u6tUI{D*oyryS!(d7OC>$UPQg$Kz+oQba|Zl64kzi`ek6mj5f)pRH(a3E&Hxgq3$ZR?7K<@?m!&W zI*VoBRVr`?;(+B@E&Hxgq3$ZR?7K<@?m#qRdViXG1kAXrp+E9Q>Ub>jMq2irr!@Zd zou`(4=P8Z9ednoV-+4;oZ{K-p*>|4O_}h1$TK1i%Qr&rK*>|4O-NeQ6`&ss#r*t=Q zJFHu<)gb=}iShsBX)4RU z^OWw`ecCnDvhO^lJ9drV`2IBat(d>V8v1jioc~$waJTnwT-~w$r@1G{-e>AN-_3iD zu>aKM*nj>h?t-`dm%dvT{`XIjYub3f%e*5J{#WPI<{$k@?!ZO9_IUPxc3yWLFfiCk znqfck#`DeF{H;k3DskXeYvWsM_KzXFrQbzadBS?a_TSR}f5P^^OS>L&*K_+hX+KZc zmM3hvgwc-Oo-Sv)9PQ}(Xh+LIJ6b;e*6rfowLW-G>j`;Uf3#!t3+2drPwhZI)i1~) ztmG3`?Gje{SgKz%F2HC9;{|Nzz0ZnqRORTeu8(mbjCL@NsH4VBw~O&4jDOeq;5n@) z3hpYoKVJf&r4jf);E3c+Q_LWjhu?~ozDO7d+A2pSl{V` zoLU+qFJ+v+UB2meJx1P3+`X&wUh4PQCE9w^@1D%xYK>f-nhTO?{Kk#%#I66|@3z#K zlT0J;sD96!%HQ<6HuJZ8W%DFQ%>}}7{WkZe-^D1KCz)z4SQvBTy>xu{`bOUk8NV~e zd5>FMztz6!cTdJU^U`={UK-zOz43Qp#_!Jh&KDXJBR^G~@8-SfciBcxEotP`(z!LL z-8cPi-FVMX-_1dCjQn8I?jzrIF(;K9?`OX8clSn4Gil^B)44B5{+s3{ux&%AbaXoVP)(EhNXtL#x*!DpzY1Ve{LTH_Z#A)*O!|3`=r)jo~39O}MpSaB+`x9ZY0nN;_0bnyUt?|C zRQ{@b$DW;MP1~k1`7d&yx6xmXbzTLUYjMp%a}6=RsYgyo{cU@kIbhBBNnA0CxV|s8 z^SSAqv2o^rHNKUWam5hg`o7!zo;t1^xyHBZbgox-TfB0{|5y1v{@vX%rhkcR4Ug;l zeIs{boH-tiTroN>B(bkB&&Y}+3+2cup>w+ao*b~|`C8cz$uZBc#&_SZ{mHfBB<)+-$RnKy87uOzG=|FWLQ|AXWa!<*)a^%|fqwgKi=Q5IG?on;~(f1C(e%ze2 zMsBn?bJ*JUsvTz{|R-!t>w#g!vh z>85QScS#UdeIcy+NZ7~;iS<+G)QvMot{Pi99%%YRP}VZ-lm!#8o`d|~F*c_r74krSR9IpMjne=zqRn$swI9n)MBHvE^F-;DpB z9Oi~!<3@Z~bB%dq=G}TF7nb2KxRJA+n>i=d*peK>H|epWa>Kv8l8emn7aX?qx*YF@ z-{FRD(zb;8&JF(p`_%pdGXHH3ZNu+C=D)fV1Z%#TpAa^$bE;EYugk%1_#No~+B;ti z|6=CP1i$|_N4nv6!0&7C#4-GfnSb(k<#;#z4s7zZcLo{$<&|8ihQHuOPIYePbT#}A zYzFrzXKJ#C3*(ORSK z>}EXs+WXD*`3^e#tMi)HjUQk_-+MlBNH(GGLpSeF{G;wkH1C>>>+W^vuXVc~zB{%; ziAB-q$6;RwXFIaS8+2?Jm1p-aB2o=2 z>YwbO@{+3`iZ6CPY6f%H7wMwox(BR?zdV3cPXyw$CL=E4@jkn>|@2Sa|bU7M*K z?Kb?>!O-WEU%pw9q8Zhpo7sbqugWEXNDYR$Y(~o%+QA!dNMcHlPiBlWGsd48ym(B$fHQ4aOWdKq8l%6!7zgwh7~_Nf0%P3JUto+U`U{M4 zMt^}Z{^&0-ctn4JHIKmH5&hNW=&!Di{sKb|`U?#C=r1tZMSp>z5BduXJ<(ra=x_GX zDEAokY21_?8c$$bK8-W5-7bwku&oa>^kjzq#G@m}ha3In#yF5YXgS8Xk^P_??Hc3E zjPYj%FP_6mV`ATbuYL5^zQIusf@5M6MRy<^R4^vCbb*e9n|vMI!5`K(yp$H5E2t=N#F4*u$?jJ0R>cw=i{ad6s;F|ij)^dkAGN5sSyndjhBRbyf+rs+-PA7qJ%-8$aE zi~VC_U#96p<-j>-I2d(4&)S#D@$9J?4u;HML;6uU+A7<{!O-ESLk@;+$y4{II?(y? z2M$JGvNUxt`k20}gTafeGl1%YmzKF5j4@0e&%qeO?~gk5F@{Z6I~ZeFYLbI7hOGZT zWS*Ka$d#FApMxQD&{GFPX8O#7sSacoF5_Uxtlh}LklE;K2SexYJ3APCX+PS*=;MrK z4o2Sxo^de7WLvf&Bp+i{vx|cO6}vTyfOF7{i5I{vor<=`pU%DgI*#L*}z$4u;I3 zjT{V_vwJugGPh55Fl6pu=3wZ2-RofV<u=dFiWU|F@|XpIv6t7rJe4|O#Xp`A+u#W2Set|$qt6hkaZ4*OwVx#LuSdF4u;MR z9yu6&shwg5$wwc1=5jFl-m<=fF(wP9I~ZeChW#4Nq-QaWBV;zpp!+%28+4NeAQEeD&r~Ib@dI>tM7sw#Zy6hYneWI2gKpa=^jR`GbV>s1Ewl zF1>@%$F@Zsj4=!doKJPY%i8l!ImYml7zbkv_Y8M1#&At*2V)FJ)o?JzaBxWnL*~>X z3rJ?h1M6PF+MgP})iQjmW%yRh@U52NTP?%4T83}64Bu)QzSTnCm2b7scja3x=&5|G zg}y7_YN7ASw_51C@~sy7u6(P7zAN8qq3_DKl1$}WNv86xBvbiTlBs+v$yC0TWGdfE zGL>&7ot1B;z9`>nfnViYE%2^&7naa14Oyyfirt+;MQ~6esseCKRRKAsTR=$<`qI@g$ zQTbNtyYj6xCd#+cSSjC1W2k&9jji&nH0H{;5*Nz15>~#I>L}kz&nn+aGL>(owv=xr z9h7e+-IQ-7ot1B;z9`>HeN?`c#!&fI8bjq2F* zzLmyS`BoZp49IZzY+^w^Ccmw~`LZw~}tkx024vw^Cn}Z>2se z-%4Ysd@GHi@~t$6%D2)OD&Il#!&fI8bjqb-2L~P`b-V>VpPXn9%GO_i) zwKq0(Gj#Zm$G*U|UegR5Wvp)|COgsVs!^ZH^|=G(`dkB>(QC4S$$oU5Kl1FObu(oC zx7K{{qWz13$!7F9&gj=)*0-8{2mY&^&B5L4_C;nNjXGqvdT$0h|4+t1jCTL9eIRt! z`&C1Kn!ma)Mjf(qz1M|4|LK^L)(!LbkJw9tN4;-1u-PvY)BOD_o>|Pk1OHWGp0LT+ zoj1)s8g*#?>N79w{6866Hrl26`$wFwp|g$y82Z!v)qOGQkZtQ20`&P$$Lh6in7@BS zi~>CBc!+_`ewmo&?_V(%WcD5Suku?GZ1Qz+JhP8R9h$#7mIyolPyS|Sv`h2%kBD1B zXB}TP^r!i&`(o4~+t#sJ=<}cc4OHuf`TIx2e!-)TGaK0Kmx-;l&3}w-JH#8^J75^$ zW#5YEan?}6mut%Ca=V8RE}z|s{-yL_!mTe_(I4a+NO8AGiA+{UyBkNhkD|aO342(O<%;=XF4T312$b9{nX8 z+q^ycOBit~yT2y3&|g)DuzHrTl1W&#MOf)TSm{Ps=}cJlg|O-);gbCZM906-C<^V? z8aE)ie71UoBeo5QE5w4y?tr4#Nvv-eh`-O5bvkA3}`kM;3APhO%Tel?)`I&OGBaC)aMs*?# zeNGJQOc;9Zc-oaP^#3}lJ7M%|duIouzq%abpzC9Nv>c3^mXGn&?P8p@J{W(kCwS5N zE50nvmt9U+)hDdv5LWUDt9A)1eF!T(2`l{xt9}ty{Uxl%fv_4M!fMzrdPbV9hVE<`-D=3#|DC*8J*n@T=>CUtrBIu;v$7^9!u`1=jom zYkq+>zrdPbV9hVE<`-D=3#|DC*8Bo%et}JXHDBN{F06S(9nB-K<`G!)2&{Po);t1h z9)UHFz?w&3%_Fep5m@sGta$|1JOXPTfi;i7nnz&Gqb~oe%u~f(l)*1y#XDhT4}_JS z5LWg>SlJa}Wp9L)9THadNm$t}VP(&Rm7Nn-_D@*N3&Lu?5C&iH*U%q)!H)xLKd8&$ zM}QT-gca|El|2wvc0yR$4`F3jgq6J!R(42O*(YITw}h2F6IOOkSlK^eH7^LO`9fID zBf^?5*kN2)&C@8<(L4fc9)UHFz?w&3%_Fep5m@sGta$|1JOXPTfi;i7nnz&GBe3QX zSn~+1c?8xx>TctoOaZdfyAI_r1W{&q4+^-7GnMP}1j12E0M35%1x}!fHV&J+=n{)+y|`B zeZczM2dvM1!1~+=tj~SG`rHR>>SJQ91NF-}pVF9U9Z;@y0MC)+iVaIZy6qqimx~5CDB>03@7|7^^)i# zWBL<5(tdGt!Fintue`e`y4AVHgvSqC6kTfU2ZVdqSQO2Mp|zb5ABuc|{>Jxf^0B&^yZtaKo(bR(>ECan5GSoM)> z8^f4u+XENCx?N!1F0gJFShowT+XdF`0_%2xb-U=J>O1N4KhP-#dp|fpxpUx?N!1F0gJFShowT+XdF`LI>@G3`~6Ka@5zlncqtq-%-B(zSZ{Q z_%8DQ+V`!7jggPj`x%t${S2_)&j9QF46xqM0PFn>u-?xA>-`L{X*0^k$lvL94V$EL z-7d;?yTH0#VBIdTZWma$3#{9P4%+7en>y%n)Ys+ayK|_I^9a5nHOk2ks&W_W-+;_> znLf*CIq+>D3KHmZB^Bu50-vPhod`Er3nBccF z)PXO+Z)d>p1^Dd@7`_0%odLra;I}hi_yYWP1`J<--_C&H3-H?+Fnj@iI|F{*UIOKM zO$Po?`=i&ad;cTrylJ1>_RwEFFM$6O^HJM8ww;WqWnLx?^Rq!LB6s9!pb%X zE1My#Y>BY4F~Z9B2rHW;tZbFAvSGsJIbFvMpo5wVR7b}RP_E+!z&dUKtm6j2I&J{0 z;|9S0Jm0Zypj^lLfOUKiSjYE(b$kz4$M=ABd=FU1_keYL4_L?dfOUKiSjYE(b$kz4 z$M=ABd=FU1_keYL4_L?dfOUKiSjYEt`ClwfYoT8%?nhX~0|~1*Az>9iB&_0!gjKwe zu!=(xR`E%~DsD+w#WM-3I45Bh|0Jy9qJ&kvl(34U5?1k5!uod*gDo@{bf) z-U&HD`Q3T`%-gkt>=9C#e|>!ri^Jx>ku!DWm-i#&hVM_aZZm7kn|<@id)=n75fy65>-kE`ifxOqfpK$2Pdx)IzRau#{O-kuIB)gm_O3O(bABq|iipuskOG&>0+eC@- z%?0rO1@FtFxmFOqe{|I_*<@{2!c~jB5Su?uCu$ZhEmwb7 zNj^?J)qCmNGV);Ns-*M#i_4PE;AQ(raiX@FKxWX1lL8FA}^A zcu@_!NbpkTy&B*}fR~GtYk?O5UViwsHh2->rDL9Y;3WpU)T!G5ym-J%f`tvi3j;4T z6MqU`7@WR2%<>2Pvg@c#dEn9*Y4qnn+Xa!z4Y;RwM zHrnCW2rWGmK9+n$`fy}PzO z8Si2bZF{oqv!2@agu5`k2^06b9szNI>O~~Puh_#j|+>Ba(R5#VzkTS zC*#JrJZ@e&*5$GA&T%e}1MZD?d0dfkqRV5!_b0hL9;-juvLTmTL;W{d0fX9xIAWU zy3pluK+i=kkB`SMc6qG4VTsFQ``b%h9v_DM;PN;n*K(J~9Tir%JeF*~(&cgU%vCOr z^&0-@@~CopNzBK#xz@NmepNHZ+*QD@H&^r z%GKAqJjOQL;PMzae51=FTf52SQC!&U^7!eKEiR8k!ne6R`jp-7^4R~Y9WIaQ-`(l* z`1tfrm&YPccDXzj$+E}gF|_(#m&c~<_PIPp4A}4T_;BG*E|2dYJ>c@VB;g^K$H0t- zT^@TB{n_R5=Y~gI9$yYV>hjoi1lU9KG}B0v>ldHm|Y6_>}ux30Q8 zmQ8fs<#FP>H(VY!)xYWT_+HOjE{|8o-gbEmS$)UlaqzjjE{`cw{Oa;JcjvDzkKMc6 zcX^B*`@rQfcKt(_$Emj-xjfzqdgAgpXFpy-EW1r*{-TQlaHTOx$e83>a{EKD}(&3;luK?yv<7S9TCZ_ z0zD_N$dUzl{`twQt;>F9yGEqv?F#r?%|v3}J9iR3YNfyRWr6g3L$=E-L0Ev5J;}TL za#4#V=o(;sGTOt(KKPZeH8KZh$AUP@zi%GQUqs{}{HW9emadq`!LwtTceCxI?K=G% z^k7-KR^}lO{jEWp60qL(er`xRf2(8AlcM4AtMYF%`dc%0&G$YGsmNDZ$*lf`iimNg z%kcfRl34+sfuitq#;@P>vsNXE5%)jI%cJ`FS@8nSi=01a;ODaVS@$Co$!CpH@Nc#x zwXW<6mE~4EVFw#0wY=@#k@cqSXPaL7TI>A^OW(4yS^4q4R_eSZWI$*OHZ;GlwS40H z^6@1~mztFXO>hvColh7r)f=QEngiLeEDrx#M#^A4RrGzv=lXW@dP%=cCuZ z@l$s`7Fhm7&qwxP++#f-*@IS(^n7H&B_Hbf$Tz2XpywkG^u4d=BQJF6o}Q2VT+CfP zA9SJ}}8SM<8d zKJ9W@udD2rYM1o7>M1|wqPwoPI(I>@tD?Y;^Lkws1*V#C^w)mgo+%6OH}=yg?A z@|@P|s%#VXi(Xe{`fDfkx+=YEPv~`3)|z=-udDLnpksPnmBT+js@GN7tjH0)uFA{F ze|C8+`Sg&>W2zGeT^^?_J>c?~y5~hgGc+!B|^Mqe#`^_Khu+`r0p>Xad2E7m40!ZC6A|wJeG2K9HVO5mTX3+nlK1sOAK4&C<~yBDP`?@k$Q#Le5Z>Iz zN1o}kh;W(Vw?)z1KM_9CW1r}K;|}2llNN|p_k1Lt&2h4e2>&5~aQ*t3M2WURggZ>_ z?wye`m~i%jejYhE1z}GcA9mq+62fW5eZ~qFc|tOm=AFW>e|duN=-Hdu`nGEbZy0`w zC96D?@P{ws@jX@EBOIM787~pCh5GVM@jyEJLmzO5IKcM@YKVWv0rPfyP(CD8AWt`_ z0s~In#*g=?K8o_m&is2bx$bc+h$VPj>Xx}LJ8uf)C zM;P*{4Loa?*?PPBP#Y+>Wk^GR*(Ru0W|Z4)qTCB?w<&F%gsyMPA#Aq^`Gg@Ke^3Wy z_%}z+C~5;3G9U{Wve5>x>X$C}KqplnAn4u>(^e67nPR4TOdG%RO zy}+0EmgNnGbfETkbS%y*9sQB8&({U{oHo}9H%pwEe>){WqQ3n%xBs88{qM}KN7#Oj z+0PTUVY?lV-5y~)kN+N&mus3_K^$aoTePzPoBH(=DoGr*7mS-@I0Fl^i|XS&?3PZ;%WIfNm{ zmd{ZK^6fu_(Wd=xgwdw`3}Lisw?PQQ$|=IMJW_@nI8NM_Z;NqL^;mq}*Qi%I#B<>N`_ zt|%WKKIa6|2#K zlgzYtuQJF&-ys{a(09n5mt`Hv?6mVdL!TiNV*pv`J7lBJkclyXEc6|+(PwA}ePdjU6) z39eu(kO|uXH;@UgU^kEnJA&OnChQ2@Kqk0?Z-7kLIcx|rVN>uEkco2G5M;up;4>f- zo)y3*5Y@Ggw;6bA3Y7*ApFE)3qu*420l!#;(@u`Wqt&6LKPDUEeW!k(P@&ZV(_Qn@qV3rl1Dq;lAjZTo~_ zpSJBwWBr7l0y1ser#jAj&j3BWkZIdKl{@o29C~^o)3$x+>4i*tj#3@il5P9a9#4{K z+dlO4LZ)r|7*7G2w(UbtFJ#)bkMR_cX|E+1PXU>>?L$v5WZH97+PsrY+x9V@0y1se zmp1Pt)3$w#r+`e`_NC1`$+T@Bypv4Z_A#CUGVQfQ+V)8@ZQBR$B-6HiY1=2sv~3@} zlT6$8rEQ-i)3$xsC&{#JA8Q=Rv~6EP7RD2@ZTlpdw(VmcN%S4EZTlpdw(VmcN%S4E zAq#znY}-CbrfvHIeRg=40@xI&*D-bV}A5M;upzzt-AE7%ZZ!lu9tWP&T$ z5M;upU_+1zn*ukG39jsQo@B!IVMCA!o3ht=l8JKI5M;upVC#^H@+=b^ePpid9@stP zqa5}G`D9<&GmuP_pWEr^xvSh+&(n2|ZZm&6?6J=hBp-EtU0sm$8Bq2MwmTp*$(&Vd zj|X-SnW$5{U^aJ zlcgn@9ru2~+8=ZD+z=={`#%mNnN>v@HsbS)By;Civsh^!PBK?!n#ATt29lmDW20C| z;&75#{_;t7Hh&PwJn>|-{kuj0=~-o4F_vXt0Lfg}b2zIyBamcXoqUkx^7xU=dB?W1 z$^pJ4^YH9}Z0>0vl4<|VQ^op_%%*48vmu>)Nan1Uec3SE9>7tv2+7iod_nWb{+k(d zjSrZ1m*$cEH~S&wBeL65-B&VW-f>%Rnwxe%cK1nVz%ESX;Q=Pm*Kzn_nz_ zfON3`W_CZRzTIzb%xh+>KiFr|v+%ukKdCLd-`LCPInInV6MIgQ2|sMCnS9RnrBvS@ z17@sC*e6q8)IOQo!rsAHm#|l-@x&g-SU<6E*Xum?$)p?h4#qlBMm)mpXKUL@gGN@ z5R`j??KV+g0NZU!TMl8nO=-&~Y`2Ma38M`E=ExZ%@C-0yKo&4$+x;S}`lZV~MtzJA zl|y$!J~P^7hCUd7ttWWV`oF>#+B+IQjaA(zHQ(HQpa4EPA}Rl|LlofzGlTeq&1=0V zKb^ygx9qJOW_>q12fv(bi+6qJa4Y`3O#JZt5@LN!gtdQB7|GAuIl1*bbtS%-mtuH! zR`DRdBG)ihXklurkZtq9#RU7dW@^iS;WPH@<1?&GywukD+NW5K8u59xB@x!BVO}pr8V?>6}7rnR`%h`#jLOL$yx(~EWZODhtZSw7iNQ&u<N5@Lq^Z<{@7Qx^5Pe68Zcu**x@b!GrzHErKb4D6Dzd!;B9J%VYV97HR4$nPQWT>B? z@PmC{dZ!P{O?c;~cUggKsR;KQwSnFH^cczMHzyhY^>7oys0t z<$5gT*;H1x?KyeN!{Y?y3{4^z zMF+@tr;ZavHarlu$0V0qA8rr>^8YOQUrHfQ?z=2*R9PSA$a#F4{UL>v1-m@Tf*(JYQUoAly9nvY3>)!w5&6z3w&N9Ua_v zxd<2^B~ukFDmNayB)%zBOpd#rK}P(LR6bi%K&I}WNOr6oAs;TyBl|5mEE*TjB9jN? zkmKbHao|P{IjnLPIX34svgU{|Z|~0v@Jea3%6ELad7_%;<)y1+lS{5=WuM>A&Wm?_N9Neki&eGX#bJxH z%cF-^usWpzd6ApOdCuyM#kG`$WXC3veC7aq-OF8AX8bfiAJA~W*ixp5l$EpbpSC;|(;5_& zk1K@ndIM6*MBfyXOGhT=8=7U3qF(lpDVOONF?n^xFvfz* z$ZB3LtDP^w(vGVjA8d}28#jABA6=;^y?di&Wlw^bRrY(*%a0V7)4n+2&6W9mdGAaK zIk?t`VocSNGU=s~@<_P}!dwUb4!^N(sgZ$yHaLsy-EayU^ubdGT&(JEEO_rk!t8zq zULnsy56U~W$j>XyPbGkdZhn_H%C?4ZvI^n+dU9Wh^4$|Iuw}cm5$?OD8@n>H0AX+L zLy=gAoxR-Ky)MS#|N36{|H4{r`WkaTTzuRxw*0HqR@3){RbmR!zTcqF~D1tbU4A*3h+=M5dDSS*y{(R=R}o<@5Ku zvzn=bt>KCN?RPbDv3Ko#(d1{rGV#$_o^xjF)x2_kOlO z>rtj~xo>KuC^Rpn6@4d2b~(~l+{%{HI^D@nhO(vN^SLRk+lgO@Y#;n2rsYXtZAf@d zOqp_9tXQ4g+Bjl^XuQHlZuTU%JPjv{y!(>N3o!xK{vVr)kGF)#vXKE+kNGLY`Y$77 zu;p)^{jILI#kL69qny9>+ZA8W;0vMh#I9u4Pgfp#&M!$R&s9ujbt_SW-7J+vF5hXt zKUs4W`{vpM(W{c5^`M)Vl^t!3vCw8kMv4l4ZObG zgR@+5{{+^Yb|I^pG!5so>~|&`2d?m*?hwpNg~qqW$pT_}sbt)DOgwAM*j~cVCmt^p z63^;iW|4^e^aA^#$V<6v)m~Av%4SyogBLR1r#HpMZ>F(!)t}2BwkDLR8n z{kD>L*6xv9SHaGIl4H2|{+ov~Ra##eFn6`6+x~(4*6*>nKJKXK-1olhkobfseCL6< zG45Acv!hoOFOx(LopetYsx(RrS(Z}fnQ&LW_ihc*>td*kns7&^+4Ru6)aL!yS-0iH zDZbvCwms~Lxg|T7ujh&093q>pzbVVf6s*CX3y0uSj+AvV8fyAFn<*QVcqG zNiM$|#B;w`=S_C;qFkLhoIm{h)S5o`FUZ63Q}eUWXL*Jsz99S03Fmna=3-<0&dV}S zgZchy-C23xb8?`MKQB;zJ`3|bE5DBypO*{U&58$|k(FXDvCq?8XP)e*Wmv*(Y|_sO zc+Gsj$beom+2iH`{QbPAU&U`ZQQpjf?Oc0+>+AZH3mqFxh3}R+%fsUT>wR5pvo7Ei!T8hB2R= z4wviBZ*bQKcCh=)c8KQ**ULKxuCND#=7?+o>ty7)_&oi*??fN}wepMQ{=8)WtfH}BtjyOk z6`xUPoVP#Hhsyu!!JEQt7QxSA>3-n19h}iR_qjtZ4J>SGK*&V)<@TOH{1& zGkb6NB6%R{lo;;2iWQl*Q2O0_BHEN1!dlE&AWQ$^D-V?_$4*Y2FV7zcl)KWM^dy`< zPx=oGlS>}VjeN9tuKeLo;Qip85|O6x`f8M=9^ShmalF6qPTVo#4tV$PZA@~4`+#ptW?#6)ANOn#+QP#a)jD0iIPu>rhAP@HJ%O>*|VsG;CvcSzHY<;P7B72%~GF_6N zSnp%@H-`Df%F&1z*788n$ks~Mi@NSKpiF1WU%U-d``NW1P#iW9xWD60(yB}}h zP0L2gxlJPY#DK(}TUAEL+dCromG2&S*4G^_&)f{PSqVI6Rb_ib0!$YI@TU4 z8`Vj|FBS2!B=v{L;+Y?^VtbCWx-AFG^*}>z z)jW^~bQvIP23Kb5i-hsXUHZ#vIj?yhpNQZM2lSH_ul^EQv2+AKKBcc5H1Hemu}?$z zh}nJQ@E0NCaK7X`!K~ggXnRZ1{A5BtWJWLfbM9$k)|i`Y*!-SyQu57W+}*vbKx_}0 zIoAadIB*dgi|_J|y%e|3^CqSw%sd=-EJdCPQ4(CzjIT}3U4hdj@c}lFHI=@vbU6HH%${w0+P$pS)0q7 zfvrW_N+B{)rY~ge+F@b{i;zKin@XQ&9lg6wN64ceHI^kp4@I^w7bf?&{!F(0`m(1^ z-9Y(H+fU@j8!NKp1$|}a77b<5!^2p|QjbMU+Xk{k{nae0+zH_wUQgDqeUw$-=oQCS z){!5@JYYXe9VN=jkK~4TlknWX)DQz!*OZ@4OUa++f9xH$`a_xJWGD~nl+3$vS2dY# zO9a2xytb#$gDUdVRuMdFq7>}9Pi2{TUkFbT(UkQ}P*FbnB{`1`nam!(C@*8S`S6<6 zH?W{&@5@O)-DY9C&$5z*%E|(Le_~UQJZH@-m6k8NE@h3H`SH3{O3BZ%^kbvX2l4kR zl#t#M9`<#baGtJ8v@F+ZgQueHd-k^Ea!JJfVv81q^N0~1IcDfgZ|Nkd_(v0p$%W~2 ziOk{teBJsGZKmqq;|WI*=GF%wd} zBm3Tokfoa*^FGU&Rmurra_a3eqJN&uvd`^6xqaqf(KLHT8ImNatkr3yeWp$?AJ%y) z${sr`el4F?u3mLYq#FLKsM0#M%s$!@W2+>VpLPhB7dDR-x1XnwFTM_yzs;y8igXE; zNxn`ceNrbBsTV}Z_J09C4QdkMNGKhgmC`Lxa^UL2~T|y!Pn;5 z=0Qw&)AKN1KY0{GOt}5RARgGhKSNBoU@AXee#J6|m~gd(&zT%?fFUNl|gIhJ%SYV#3?6j207)+-HahXS*iE!Wu^yV#4Lh zo)lB_{>Ts$E}ZU(=-6*4Lri$V0AKmdlkyBP;hN(DWzQeadJq%N_+^+p7a1Fgm~e^9 z5i%^grx!8dHrXR&*LR<$~cJa0cG2v~2VSLK*sthsV_P?d%Mc0jBhzXBbmV{pqj$w!i zfAQ=g`}p87hM4fi-N#sl_>UN3!X^D<*y-g-C?>pQ^#~U6A|=IyYj3a0RtJSqOnA(? z+nz3Vdx!~_FY+LAaZTF>?3nPQ+Fy8|4+-Ij373cr7CG7{=ZFd4&d^*;VLlu&;pF$G zhaFdoVO1{O!%8KezI`YB7fC{6caA++jMbZO8~`$!(!SBZ~735 z32#rETHLYi3^CzSVLiQpw*4U{{NcXX$P!){^>#Dqno zl)U?v=U&8we_I{OugnbfA|^b>o`1DiB@bf4OFKvKcG3O}G2vWKLimbSpEJaSt7J*R z`y89d5EIUkH4#q~xt<{=T+M!;C-t#23^C!;0}rqrzRwwA!c7(~V|7CPC??#nReyGO zQ4qz1FFfOHz>6@BnDDj4+dM1mbq6uw1TEi*Ous3dBPQ%~f3ml$ClyCb_??fli`|Ht34ga`r|4a8J3~x3!IP_^n(u6enDD&@3FN%G z9T;N5dy@yq>?t!b#Dskoq>?vt4)-7?+{1qVV9?b*F^CCodJrKG?>Xp2Ot_ghO!h7M zoTt9k9ASQfj;V&ZBihBYv;TFs7?=|ly zqL^?IpYfuEm4afzb*q0Y?$!#WnDBe&6N#RaBP3$N$5$5gcA6F;5ffgOIlsr(epdo9 z;T|Otv1YqcNW_FEu57@flO~pk2|pC$7`u2+ASUe7HkMrpJ}eLuZt?XmZ1R{D0x{u9 z&z>^x+(7~{;ZE--=RaJ%TKo{wKfaKwbCv$QcK z5`}ZbgjdII@$QTX;)n_7t8s!8Dhe*O_qu0DbF&*gfmn0x{uH zqmPJQm+aq}?3l2((~sipH@*}T-g|tgxYsX`V#1#&fX&s6W;pKMdlx{P#`9}tVKM2s$@@rnDFrt$@sjhc?Dv^JC+3VjMW!=5feVt zJ)AdhUZ@yi!dDZf<_i|B@gOF=vtl^U^j%?wm~apKdw1(xZ-$ugvU`5~`qzsYV!}J3 zUNZmKeGD<-`)$v&U1e`E#DqVI+{BV)^P!k;0 zVu%TM*|A0(@ITHF6OI~nOicMGh9M?Ad&fiZZPJkpG2y9`lE_J&sxicb3*1U67r%Sg zgP8E7q+v4Z`qN0ng!BCrA+vnf#EY2lbNd~s4|)a(#DsH92$5sI`cfb!oV0&(Ic&xh zftc{r4}IkAA2tfagnO>KB`!TXClC|99<^VLIrc&zCfqpD5)ri9k7B}Gd-V|?M*YuDazJV#2BB z1oFjELm6Vi*{AsO0@qhD#Dw!#dBPe-9AStF7wLMEWt(%KAtszVk7TiH6H`pMXTdS7 zQq`0c6MkBX%F` zDx88NCftARXJR!^#1Rv2)_8a9I>XOnCT|AbGRhb`N60FCT`BRe_lB`_s1zpE3z3 zCfvUEZ1H7DKZ*(W-`G$5tM{M(-TSL=-|=|+j>p?~Jl?+J@%9~$x9@noeaGYNJ05S} z@p$`=$J=*2{&(N;cpGDX8)JVPV}BcCe;Z?e8)JVPW4HI@Z)5ClW9)BZ>~CZ2|BEqp z^BtJ~&bRz;zi0nzf6s2_F2K9WfAqazkokAGPwnrJTmJ8GN5J3Vu7|(FogIINyI1}W zcj)}p??N*3W&IiNtNI_!@fAl-JoD}YoiF}Gnzy;=Y42s{zyCeC=usE{A^$!0fcDx# z`FOs#R*7)Uekld(SDG-ZHB`J)s4!vMmxv}!G7#RiE|J6^Jc}~?8!+nP8DPkOEMUk+ zo4{z(E@!&ju1^^CZ8?M?$Cl4g2lDMdgwdw`Z-mjN{S0BWX}3WbZQ5-RMw>=CGwL%# z4m0F)qg{J^Tz$BqCpYxxZGsYJQT;->?l0;SMw`a?K)zJ{;^-SN+C-lnIs2g}VYF%R z!c4x*x$r-E{|Lq;eQ5Kjf@RvW-CNHR4y~7!t)Fs(aJKVvJq63$A&l`i%DqN?nIbN&DXzPHmV-8cAs>H$QHC~v zQ5VkuLk464LpIs~R{hfD%&5-{In0pHjdr=A4>$DWhW>o+q%yM{ed?fG_ZRgE+igM) zVT`3QZrpB{<5`s9-yAtdp(kO;FnD1mUzoE&Pa~+0n6to`XP7_0mp2UIHZf=ESv6;Y z(I)0BFxtdiR^`H|Pirj7(WW6^8tr0j)cVjGi~5jZ=r6&YBga`|fzhTh4v@o8j`hYE zH(Fy+jy8>PhMpYd7#o8Zd(QrYuOnASNURB;jxSJb&#YmDvzM>TvL_foc>A{PY+u{X zgp)N7vh#m7BJB5)^WO^Ex%=#AZ=G($8}7N71Nia06$rl&!}you zmls9(jjJPgyK5C`of)%e7=NB|JK<)519;(dK^%3ePwC9VBqw~dRU>|LZX?1$9XOXe zIuowCKafw%IDl}5@3ygOD~AzYKKKK6&u#;9z+Ia@6Xb{Gn?@Zw&WgSJ@kAMUvPo1o z@1bIw3Qv-W+BS(w_BdN)A^*uTCSjAP@%=xI9G%p`U1m&=^h@kutIPh#vGE=JNuGF~ zi`krKbEin|@&CY)+2MW~kAG{YtuiNbdWr@+_y&`nV2^|A8U)#YA)3){uIXi*$ zX}n;QXWg=iq)+Y8-JacDCXqf{dmQp4Yvtg{tf!F z%=N;PtfwP0jb8%Rdg^%U`<$0P?16o^HpXG{?qcj&xKlpy;ydiSMh^byVF=qYbUf*^ z@4G1W&4&|6pIkXgvEM=_l0Higm1PC&I{-0O{j7?t>k$X%n^m2iU+v&Y{cAJ6XFNR{ zbH6V8;`}(0S?<#YtmTujq(hm#4Oyq9V+eoVr9Wd?o$@2^bZ0|GI{5OaHtdI{W9iuy z{)5=I^y5h8ph-iR_47E=;a1M!ENG#FR|Jh>y*fL1{L?WkWfcccIXj+JZ#0&k-Sg7~ z)~xLql9^-UL{_86XwqTnib-tM`jLcZ)>_2|e>{rt%Iu3-#IFu6d3P48-f|Q@J2GMo z+aETXWF|c2W%)OaCVlQtv)G0H4({4%9rIRp@a5_o*|I<;XCKp3QS$3u~8W zB+0D!{Z=;4GlJS3kaZhdmuMK_*aD~7!R-z{QS1oY-g`Ke*C@1)9kk~x?78hb=h)6t z!%61k)EC+8)5A%h63MTyq~jet^3XLlrmBN`O}NS4Pwe0nAKzgg1P-HT@5kO@nbQs> znb*_bWqaNkLT%mec9$LKIgs%A<~}@Si$R2k42j3Ts5F@HiW*N?*Puc4?9gY4c;L)I zB=gRoBz!=D!K6>Jv`KlwQ-cW4|Hh9m?C0QiJCpHl1svQqV*qc=2hy`6@&xd7We1SV zA0q?!f-3!~trKMeI4jTwQEIGM8S*!%%G?k#>m%a0Fhuq zf+Qt_2^9fFB&uYT93-nV2nNgvfN`7_4lm){xx&& z-2cj2-&*fF?0ReWu5)(P-j#&=zPL;BUaRrK>9#v259P)Ned_L+)M_+NoYj}tOfGzM zoOEb>$zDmnZUGNS_fD4lGFH!*R^B(+bAG^EoxWdEfAJWVefpUFl0)tqEzS|O_Dj}3 zG)i?HS9!nW&MU7JKKI!}lg}<5A>6dAZnFREk-{r(tet$&{VJ8MeC1(wzwrohwm;^G zhIG!etod&>c9HvWT(9@5q^8mhRJj30O7T1Ch6Pqa^VNs9-lOR?-G^$P2$d)&C@$yJZ{ z5$Ccx&6ADqU8uV1KHV(ocwsN$5$Ci@zHNT4aR0Iv$??1Q7H(eolw?qqvsHG~@okb} zH=ixeBdfMe&Te{+>YA{sT{5ZR*}}hk+dk=jd@td8RXZl{9o|!T_kGSxhPCUivdtHC zOr9LlRh(UR>zFLPp|k4hG_yleb=VoghfV69Oq$+4=rgZNa>ey$3O~2ttfb-hXQ=F) z3wkD9FKH{z+nS%9ocl#v)z$lebCVliJwy1h1J6rte5j4^BX!SD&Rx)2xckAqlWkvW zsj?rAIzQ?1OAB!}S#@60sorU->*{0AO9q_VSh&TozR84pn+k9C^hL>ARsh#yq zKXPU5LCMC;j!@aQTVI)6dFv74Z2$FD$=}~SLUmpB<%nd*KOHW-`B@{AgL)n&{MeHt zljHZVC!8KOD(T<<5S49OJ~HW&t1HfjnvP6<-1Z>VRb$17*KfadA4zDvddA4~iahBH{m#lAJOLaZJUl2){l1 zn&hx8w-era;nhixm$w(bWbydq#eJ%%Y@Nvyk||ZIh_l(~iAnpvZ>_rO51Eu?uG>oZ zxR)j+?M~cMxaZ!Jlbb);LinM6latSFk0|=gST!kGw{kOawmoH1(qQt&EN$`Q(uv97 ztv(TM*lgAQeP<_k+&M*@ zORCRFKDvFf>T3MUoMg)56NH-_G&i~M&GEuL+RROcd^SdS?$Ei(OBak%*_$4nlXO^l zl{lwWo|7E*@=(=v)+w`-uP!}Vc*f;(lI>19OL);9bCUCSxKOxk>Fi|S$IVo>M)$eN zrR|!Cv)@VclD|HEg6jIy5%ZIE?`DM47W0$W)*mChzW03FGkb*aAIHp3P8xWK%Kq@k zyrlY?I^vx2!`!4&yZuyGr9aF~HhXYv(4TU)?Bt<-K#0V|(o&nXLxSO;+FZ zW;yRq^4z@Sqrof6d4JX}nV*i}Q|M<|mWaPgcDjHkp@WF2Fy#Y zzO|$9lJ4`8uX>GKhCW?7%};6_ddf2N+3T1E$;0!vUxq#pRl6?fJfzV>;2Wz8AMe;? z>bs1Ut?y-xv%Yhh4)t9J)2$4QZl;4UI+$+4=w`pAjI#U|`;BFA@*C~9mr)nL-E1O^ zP0Uup*vf1uj1A4UDvNE+=HkTW)<&v}HnO(Mpbu?lZ6r(^S=&j5wzIa*pbu?r??489 zcn9p=$e<7JhP^YwyfgML3G*)5J0{FKX78TL^6uF?DNf!=dxupo@36hw!o1t|4h!=R z+q*5yyKUcs%JMDPHzH2H5&L#j7vGM3Q^I^x_N@u?t=Tsy%r|J?rpoed+BYjszFGUm zRTtm5efz?E`}U0s^NriLFU+@ZzCva373M?4i4QT~qPp-c=5vJcIp&Lm@kQpNgz-`4 zyHpn6Wj;-u_%!o@stX@zzEK$8Xg*LFA85W&7~g2VRAup{=3~W)k2T+`y70Z`lZElg z=BtJA)#k&6@!{s%RTkfFK3|;peCs1r7kz~F9m4b-)<+1_M_At>Oy6OBO~U&_Ut@hx z!uvxXWPMYjZ^!y3>$8OEv#c)@rZ2NTPMAK<`aYGV@3THpob-v-hbFwk^r6|tXSm1V4AV;FHVhOx1Y>SAnTV;*6~JT?{* zW-Mf5Bw@x#Hg-~3#!fb-5+`FS8-uAX#$Yx!6J~5?V=!UHU^X@rW^86-IhAEBXJb5Z zGRCv9pXy@lXJbNP#)LLj6lSbwV@P4fkT$kdS;m$&<`gGmP8*}DF2<-fb`@sqYGYJk z#;7)S6=v*eV_lVHtZQRnaWV$Bv9ao6Y;0p@VaCihmKJ6#ZDVX<#@IIYR$0d0HYOJ* zV{#kAt1iayHntaLY;R+DVaD(_wioViV|$AQRF+u4Vgzv#BUtR9x`-VtrVu8kuvkNw zSi@ovVPX)AO;ncH#9|h460=y0qq>N3EcOv5_OTd8m>9=mpP-M$J{BvfEU}WsP~s$p zve-&>5nEZzB}~j^v6wKin8j$q#Ap_~sVuRZ#dP8%rn4AObrAzvY#8db*wA7?VPZgw z4TXsfEtXVSVo8fJ#Yv25v8U=H_OzH(n3&XJRbgUPi(!R{VJ)^*Sz=p@dBsW0YcaCw zB1X2@S(w<_Vq{@rWQ(1JiJdLhR#{?gi^0W73~sTx>LNC`m|d8d-C}uRVtI@4g^BSk z_E%YAf6EDobBg5zEQg@F$RSv6L73cvQMGn()o5JKaEr%&g4%2d*!sIqB z7pk)4LM=xsPI9D{J5^oePA#V@OitBut-|D5Ee9)14%TwBDobwGa<<|mXKOiL)kTii za=*glel5oKa{DSvZr^hL;w0y9a{;Q0xq#Z|2Rz~E#^rAg4tTqFe_ZyJ z*@Q7ki?O|ywabLE6ZdFS-nClby!)3PY}HzU^NRa-&i?q<@NV?1vwQaN-KUV8SDY{%bb>3O%N zcVxGJA>b`)-<@spcJM!suD?5b>bl^6{`|;2*#mzF{^#Zi_hx7Q5`5q_hj3zT?F+zQ~RmIVC*5=&#w22TWGk-^zZ-K3R2&I5%tdQ+E8qDbnY%R=;L@w+*<{ zmYb!QRSr1QYx8u;1Cu4wF;^-5HaAISZ&_6--QoGrfBpPZrF8SxLjToak1f&`8$us? z!nEq?l5axa`q)!d(}ruWkv_e?vGb`$*m&LEy(Wk5kWQ*{jW~aPddGD9v};t?g*|po zA3QeTN%!uO?)J{rdj87hHPR(l1bjrB-O>@`$E)l!!WdkJ9s7UO6~@b$q~=?{H{3b;d}Qt+w`%bf4=-i1YgNkhF5E zt5jE=>4&759|s9PyTh^R+(AQyZ=Cmsbo!^mh40_v@O1kZ2CHnJSB^^`oj*jJk4>(h zo_x_z)%(T27%Wx8%|C*f^w=$QUGqpR@zDecldNA(cC>9RKI?R7ePT>w7^q%eO3xBo4@bsg%j}zYNo8jrk z8;=!Uxblj0-MXVycJ+qg>8Qhx66Y`b3{PJgaHQ&5-+Wm5<;pt3-H#oaE;;vL;p*Ft zNGp9^Pk8wQSEQ}Kt)sH-4;_`>vCDzt+-JYhX{F;1R9z3(7?Ym;b#39+!^fn{Z$Ch| z)<1~qA-%L|b>TffnUL1Hdpniw)OkXBg{`5Xy+*!rO?vIu1U}M>(9!o zY_-Lt^o7?p*Yn={OiVZ4wWaVU$4p53&-z)pnkP0)O0RGJvvN3X|28>&>xZ9|+j;2Y zDd`(!8-$x5IW_Gz^zXtOhfPffmVYDs{xeh4le1r`?A7(Arqi=uh_l9wDQTUnfg(?M*ie-}l7K^rpA(63!hmGrha=L&75`&PWe<_9m5m`@U<_Ve1x)^Yt5N zrN3;mSascGYX`<1xKMb^Q?t{(PrN~R8$ke@iSG|sI6wDd)F8!yi>o~>AE$egiqf%D?KSQQMl%~S?OypUaGQ}b()iYJ+i+z zZ*Mj?9a6uq>RNW>ymY@adkeqZZeDuP<-LS|9W*cPF|&(sv-$JVgJ0+v?DO{Aw8my_ z#d))>(WrB5OVzcgqn*8YO-SK0oD&r5G! zy{kCq?>s+UxBbqlYrzJ)`)BWJ!b__!NWVXHYvDBqEJ&ZLzq#!AJJ`b$<0&w>mstC^;BPHE? zzF(^>wl$lJ6PsIGWYLGVur?B=jjZj2X*+9EVcOK%I?HdNt?eDiq7UzYy)#+#;hnK} zNtk!Z-Wg%u8GDz6d6(?nQ(4|Udnd&?-rh-jS5+79s=dR)yu!#wVDsP+5G1`4Dm9L(J!>E_{ypB4K=y`5a+Ce3AJsm2Gdn%Y0g} zkNGt7b*c+rXFgCEA85W&7~g0Fcde7p70QzFwHV-o^$h%hMCr-wAHYQYE zj0tV5D9l*V#)QI*32m$>%vjOJmMY8G(#D+PWXx$}QPss*)W)d7j8SduD$Ll`#F{lvW#_Y3@lE@z&2)9U5uG+EG^7f+Q!VnjG1jLEzDTj#@;H+*xSbB;$%#2V|CTV zSl!0(!i?cLRAFSVNdt!(s|yVhW2jgo!mQ zHc?q(6N_2INz7ugjOrqmu^2~~7{_8CVPYSPiG+!XELKukVkL{A#7PWgF_-Eh=CW8! zm{`nWE@5IWi^YVA#VmGHSzBLD)XR)5@BG$7QP?#9dVnbnKLyH-Oi5V@HR9Rw4 zi!sGXjA=2c>LMn!SXG!<)nZa%Vp5A$g^5)ywpCeTTZ?(cNz7}pu<9ZfwisEM7};WH zVPa>CsfCHDE!I|9Vr`4T#YqfqF}vy_X17>gm{{Ioc41<6i{*uh?735b)N zfaMBQ7r6q|i6 zDa%<2le4m1mdcXLvK*H<$#GduOm&eHvs{@lxiZU%36m4ET$wPrGRv*0EV(tyxrvjU zo8{tE7r8jg(Fv2Iv)r99xjW1036s;aT%XF4>$4o7ILQH8&QNucGqhZyFu6p_848m# zv|OSvxkSr7sw}xj%SnopoTTL{RTsHR%V7$W!?fI{Fu6_3c?y&Bv|Omlk_)vQsW{1z zT257UkyEu?t1!7%%c%;JQ?*>HFu7LC&8jT9SHxz57Z`5p0JBFUdY*~oGZ9Y`@h4He>`xMp$tIDWNu&*6^S3%up3gY+9O&*K+5&p!ToTbIW3 zF`a8@-U`gTRXm4P%A6N6lx1G5+ZvmnGQ4@&*=7C81MafhBF)qBoO!x<&aRX>K4d7% zJm3M}*nE@W<&W=@d1qq4Keatf^O8JgUNWAeEM-m;8Ok#6+2p{0yRPY%IdYuMCE4>I zb{V62STOUj@tkZabGXP*mU-UBV{HD{@MEhMXPVw_b3=xkK6{Vmox#jI$8*r7%vmEt zS?0B0+TP~74Y&DlMP`@ZY`(_ud81Zoo*m3Qdpze}${am1lw}@&*>an&G5p4(KWCmA zH(B_)Ftb+FI*^kYQa= zyhf;$HATo!mUTy0z1>Clgh^eJRTrNreCWqLve?Lul zWaB=`vze2GS2XUgbzjJ^?kipcR?3<&WGKtJvYo#x6YhJ*(By!xj}gA6^_5!Zh79Z6 z;x%ujtdT>8vaF+f_HQ;{V7T9^(aEUW_7i^Vim_VP$8*;8#cTXZSrdp1Wmz}4>t;I( zpK{wZ$y+0<2|u;F*6Ithjxk=-SjrkmWZ-8F{{!QH$$)QtXiBp9z^{dm`+BO@ZStIT zoADaXQr3JTLs`~^*1c<`@bF(}Bo}XZTKL?}uGKnKWLT#fuURc+jVm&gWgYA#ci$xZ z!obte;Gb*jeh-*&iEy^&yyS=D&Jyl(r`Ea)vkp04 zlU&LgW@O-Jo%5du)DWKY`TXRSn}06jdAlZI-8GnX*YO(cQr2uELs`~!SKanP;kQ>W zNN)daE8#kuUB_DV`pB>rJzjHO;u`g3Ue-9v!Ejn#!qmmOde;F=o(+9US(A?pW%=!9 z6Jcy(w#xDxTd|J-j19r?gGxA)j?0Z569|(pYY`#?Z zpY54KhO)?*PZq`}o39qeSF_Ix8GJYxesC#!#E_vZeTVfa!t^QD*9gO=@YH56sE6aA0IOGq4A!+lJ)?8(N<;YyRAu8I#ypMVPUQjbVft!+_xj+gM2WpY8EP27Y90OeM^i%Ens4 zjJ4R8iVR~gF#OBvx)*vDcbVPYbSm4u0v*hh~HF%%ena4CE6k)bTH zo5gg(#B>(x2@~saZU8dGfMEE+rJOl{3}uNuEhZHvCbd{qm{`?fSYcvVF#KSPg@ymw z84Jk3kBr6C!o<`TYYP)=b1noj#Nc4~!KIujfedAd{ZFnIaLvySS$3n{)5!BRuU1pu z3{2iE&Y_i(b3=x*%FB%lxbg$b%b#x$aHH*hD<@Bg40*yhXIM&(5gE#ohdl70fUg~R zVs`bS(57W;Iw>!T40+KwM_Niw6&cEscYXD%@GdPJF(rHO(E;y&&3xs7ks%Kp=Y&hi zAtOUs^32u$8oq_hZ`tfNUxn{$_Os6@?~M$3?>Gm3bqP6hWGG8seXlCv`|UP(ZFc8X zQ}w*&`mb4gDNLR}&iR)zM}Q3c%p;uBGx(w#J61_I{5C<)5C6ED<~5LEUL&64C}mCr z8Okzma_;xRmtOWjt#nM!;FCY!dVkI1Aj3RPJf~C291t>;WuEBXmqTB0=y6A;wRa4C zO083m)w~rl%v;5CSf$K)AwyZ_#hzai`m#}vpO|j-OFun-ZOTcSr$dH$x_Hj6lsP_R zD9b$HVQ+`Nc+wx+rCsLq(DShmpQ(9CWSEzX=O{~=(?o`{%zMtA)K2)#Dd(hjZD=KY zc-mX@u*fhE8_&s>GKY%{Wtr!Fy+#w^X$uFW#~&ZYRQ)d-qhDy_7k6WGKr#{$F?6OL+Y|lQvJuOd9+lu7BR{k9N(^m?t$(^#E#6!DshQr2J~13&9D zx;FVl__J@PrQa-lSGeO&T5BiFx{-JdNhxbikb$3dDT`i7g>QZB+Vrl!-z|K9R%_>k zStk>(nJHzB4Knbv4ySedslu)8yq|L$jTT-yU2EZlSr-(q5h`U(5i;k{H(M3X3v!&79O=AZE*LWgnxKAtouTSbzkus zuu|5HAwyZ#m7Q1CT(SJK*5?~mP5{h0H}hSp$g-WqCL3oe}1pv3E(BcZqeI z$ncJV;Rlzp<`Wsp@^0HZFU&h{--0mT0_#+f;Tr+N4=!bmD>9Vj+q7?1m~Ym;WnsQ$ z*5x9@Hx7m$T*{hWWGIVoF`tuw@j2#;gz-hJL*_X?3JgEElr_xAP!`{4K2sQvM(abFD8HrY~k60W$Q_VEDnM>_I?=vWyLE%plB| z!NwB8j3wANfed2|F#O$N4Aj23B3_rM(JvGQsma(OcIfWT>+E`SWv8atvg&CuQ;RlzphX@(? z85`S}S(q`ijirSdOSA6@8OGRP_`#*@nL>uLjO}gAFU*+VVgX@d0gDlYi4nl?gG<>X zh7A0~CKj^@6SG(>BTOvAzBXitalr6{OW6~L3}uO}Eanm>=CW8!m{^Q`e8>=^f#C;R ztS9`>_5dP7S!66`6eec0SW=i+(qc?uVoWgnV2f3S|Jj~LWZ*}}VqRfl-fzYQOf1Yk zO=O6X!SI7i+2e@}Wr@vq`6=K-uiLkreW^UReW}ahH2^=^IVQHwKRe_&)O1BL@GFx=DuW-UkbJQK-hBAz7TPojF0 zNS`FqGl}%qT8^O4T%P;yMPAtIgeO79>V#j|>ZD#_p7DQyXZM6MU^q;FVYuV=+H_q< zw06bUe*C^B$JWoVUdC*h`dXU*gf%&wdCM8yyq}zf3+9a9%=p4NtS>Y8jlj8{=UPw8bCb{T9C_mrhR67Y;kSB) zsn_%oMjzf)*E71OAQRnRP*%}<4YsJhOq@&m&(GSQuszFS3+lo)+?@cnIx3ZvAd}BGYi(^X2IF{9&(Ue%h>gIl680(?|c{&m({JFY6yOL$$TpFl#o{duTSynhmpg8~#Hd^snmI=&Sne z)WpUZ>%|{%{}}5X%gd-8^D;4(-FW`U5p}a&Z`m;$@U7*BGyerH^LkA_6Upnl%k%$( z4)M1WVafcfzVUp$|L}X!lm4CYOH^;>U-|updc`kW;b*L_OsKcN^l=^jmEWWPUh0Z$ z?)73@$I>TnXW{?uJyUUA{toc&MRtzs{g-~%c{{_e_tWewoVW8o=sPE2Y;_oi1OYhr%A;Y&UyFGHmtz{LRSB0N^ zY^$$l7M*V`<%|({I0FHmO*pmgTIYvEbH1@mTsA(dq}Z7xu}rb^OycuTV*ZNG3*Wfn zF3lIOzGi08`QlQ}gnc_= zewXPlyy<#?QqF{dC$dk06MdL>$j{MdsS6y}8<+iuvt^2$A@dJ1Mb4jz&#Q^~E4uFD zq7H{k=X&jCXblGXvt}S(k5S4QHSk~`cw$cU!9Mvl2C54j%fw~lvu=u=X%ov7I}ay5 zKPTp|=(?9)b?rU~v&nmHrfCffc+>STrJR`q5B7m4=0qRtlV2mDy1=naTsA&?r`Q=g zu}rb^dE)bYV*ZM*3%z@7SQ|NOeG{z_#Xg&^7cFH^Jv`V4o|qGTuupytF@+x-%fw~l zz4^uV;Kwq>_V360{bT-$u511Cy;G(0jOCMxu6Hfv3wUaM(e=`$oCyOD_JJqnL?7&vUqhn0 zz_CnRHa=UX*cmdhOtJH4;`3@^{)(>a{_?ylrSq&ByJ?L#{&Umy-ld%30}u9rC+0*S z?2})^qq@McOk6fT3#izcKe0@)^Mc~@g<}4Su1lXj=~C(Z=;a3&U9VosnM?3sA9!L; z^ua#)HB_n#9LvOIs7dV!Q%f@GI6+2TamML}~SA2d~%wN%U@9V#RuVwqy+@5Sf!#rzfBSF(D22kHDy$J2`LH!0;z zJb17VJTWKwV4wUNRMiEJW#Y2&*?Ps!(2He?oxc~K*BA3wbYILN9l}1BK1(_k-7izh z8HVs+A9!L;^ua#)HNdhDIF^aa#%CcGJM%D>DRy3Be7<7LU(tOrBfIP*otw`bp*=G6 z@0;$IDdkK~c(4yVF(>+9pZpqf)dh}a;3*M5&QOI1`@j=(q7U}Tui=+{z_CnRHa?5B*qN)bOtJG?{Qy+(VKu+OIZl}b7D79Q*aPt1uv*eAb-LUn;-nYe6xc5bmVa$}id=j+Dj z@y7fW-B&fU-yPEVnX!|##|rywy5FjlGm7ECKJdhx=!1RodstK#IF^aa#%CQDJJUFp zDRv%me13AwU(t2x7TYG+gt)uddi7H7WPu0!y69Cci$Ad<0h6Vc0W#hpH9qQ z(S0!%+v>LvcNg0)Q_3AW@L->O{9fRU_wvNL#r4KzQ^5Yv92?`SEjsGu{gp>lW7=myPefDR#$AEK}@$ocKPSn7^X?+H7p8 z-@>@J*nYQC?$Ch;`{c*Z1KI~JF!f$`+DO0ePaHK?whmNU%!RC zM6vyJrQE>;5BACDHwv8bUcXqkxZb#Ie3w(PJDXyeV)s2+4n+EJCV9+X(S3iGJJN3< zuT^Y6U@3QI!GnGB`LP0LyjL;SEv`2%8{fTE?2fHirr7;l@qJz~e?|ADTI{diLSCZS ze$`U$gn|eAVH~Yl(+@ABx>+70VR64=cVuE9S50zHEza^;?L$i|yAg z<<2a4uundIFL1_t$z$E(dgHS3-CM=(*otL}-Om-@=N0o;bYHy1wi)6J;_hPm?-z^tD|#-0#kTq_#NEZtD=6ho zF?g^~K7KE7#%C$Sy2bUzW#hZairqmL%M`o6EWYn7=CA0v5Ek3&w-9$1J1?S?JI>(2 zKKb~)z!{%q5$hJ$8<&mmN-K6JS}arSKDGG%wV1!6=W^KE5B(O_r4&1_qm(<>;K4rm z^(_U?_$-lFx47Q8YhG^8`w{BN!g+ zlV9Ib;Ec~Yh;@tWjmyS&4HvspIF>1PA8~wtam-)Qa}R9okbVp6nu?u=VE2P0+_&}5 z?sSF+`{dV06*%Lw8e-kzdgHS3-O$DEfR1H~-5(v_Hy!g=^xTF=TZOYP_U-*n(eoTi zxq}-X>;q5C8J{%~>lVwzW#hZNi{05B%M`osJH8)0=8w;mDCJ&>w>}H@dGGtXmX&g5 z1@}-eUfT3diYH6BSDm`BA$4t9FFES`IhNuF$1-u*_+TDi<(s{Wk#GE+UTf5HkQRQ zL%Rq04&U#Z`FZz%=dU@isBRU#yX1;B)1>pFulg3f)8yH`?OYwR&%_0jGxwY~TkrgR z+fB?2xhvdpfA$quXW+p;@Whj3EEX%zl|n?SS7pa70nvDth^l)=Tm)k&5K3v zlzE}Cy<=vd>-Joed2P{D>D>Ro)tN`P4CA6l{_sHt9_#~8%!xkOCx4E#>;sNv;<9tf z!dT*(+RtVN)|;WaP8;@2rtUuGCryWXuRfiLWu6-o-rKfEzmj?FxuDOx$G=rnw~F3< zbIG&eOt2%j{4T>iIP_ne-ifp0jT5EY`iWa7SMD@XI#2m|%jDHj!6qMHSUG_Q`@j=( zq7U}TpW`ila4Zv-U4GzX@qBmH*O~omO;KH+@BMY=)E#ZCYxeo>k@cBargw`lcX?mi zA2T~#G*M+IPu{GkZWX<|=dDjhO6MDARV#X@Ppw8~L({GL@|wv*xv{}Mb@xm%4aZ8K zCr9s|z=M6@i8;{+`{d72S6$#(CN8_AWtfY6w`sLxuV&Y%uBG*>CFdmeo|_KS>s3o) znfF?aSH0=BJ0{&v4Qfbb2Ixp?DZ_zu6F5B16wKLt?A9FJe_8CNS++h zRdsdQtz$B*U3clwd_l(~mbv2kGbR7rg0qrI)7uO8pVy_RZrrbg4=MHTr1$o2B>6W# z>{;|qrR#P%QMz?&c4@NxBaNl=$R7QZ0p~WBJ}rjzP2j;k@Wh<)eNVA&u}oaHQ@zu~ zbM>+3C0%}Lp}Lx^IxpGwrIym+!%^oavCNup!`xgIJ7aRfy-ihiv!^dAs#`_x-r94Y zKC;i%t&S>sCs)hsZJx;9?Zr1YP8z>=iFE$t!$!$YdtD-Z-rloe0uT0qC+0*S-k-mXcLqIZf7yZLPCc4XDI$)GA{OXpF?w@Er)*h~71IHy$t5B7m4 z=0qRtlfMTExkEvwT!S+cmVbU1EY^CXrze)ryzZ(jM7 zeX#va{2xZq{H(E zUY^7<=~2f?{>s{ek}Ah%pH~*ax1N6Me8x{vIFI1&(FnvOjKnka%jW7?E_z)m2>&H65As z?|+DNXj(opiDgz^dVu7Q{(fXKbLBq5t9Kn;RJV%W-PZGoD$=>yA4cmQH{PF3?{u3| z)nv^7G#foJd2ydA(z(v$3CVWHR*^n$&%P#s2m8PibD|IS$={=-y1=naTz25JoyBwD z!f{F8BX?C@BkGJ#YOSat9iCV+K8a;|yu7{SFIhZ3Ic&@AgtuOJby3|adiUJnl|NHH zx%TSuMen3LVc)eG?DN<`HkO~cHbYKk*Q2K%B=BG#cw$cU z!9MwW#8ekJmWj*WGV68m4BUEJGV#i{RM%!prX}mndq+C-J9T;z%RDgoCCTsj__XBD z!=4fzJz#oK-70$b-+=SxNaxooPt`qud|#X133$hyQ>5FH>T{Bt?w%^0*X}zzS$^*{ z>9gUeSqVJY2cDP{eXvjd9yiqmj%DJqZ(g=UJX5F6Og0>Phw8eh;kC*2tM8Hy2Yq>M z63g74ER_5M`(K-k{b{c7n7ghms+-+aCmrUNcz5CTL&BYgm-LygdknG9rgs`%+OA1x zyOZW613zviooiTL>Z?mnmOe8spOe6Yec*{X(FgmWPpn%k6PG>g<)Pv^>y+6^hm}{U zu4$F$BrjcHb9wfS-}LC5B$hdUhYKZNwsdx~-AO@*MSILCs#`_xUTpe(CD}8rGE?_3 zVxLX#Wc+CGiZXOtyJUW{`ldI_@IT3O^ODV8U!`*=&R;t>fd~7*6LX>u_Q~I4sJg(h zOkB27yZyvd=?`<0>TBxAK2v^}o18T85ZUL4N9HB5%(1<8ko;By=O&|H-6(yoymxL< z-70!_nDrn!zS~RoA#Tnwzy-L`AL&DH>i!;u9=_2GFRW)QSwW= z&r41{cW2>u2Fxp}8~0=K4sdT~DR*C*ZaPl``hczCd-+7g!%59r{@x5zClQmOMV$ ze6=vXx|nViy*t(VR{a+GX0cdC_92$B7)SOY#))MtrjR@_g~b}e#2UqPtLWXk78|Dc zXX46Yck)_nDEkl_TFfZ>5Hnhwm|_!RNqE5d__V+o-xnO~7S|h>wU}2t#Jm;@t1e<; zi;<-RF>)+pF{$Kcz=M7A^A`oq_&(oQx47Q8 ztj&pthdB|OD^Xp{mDn7LbYKo8ma#bt$unnRa~Zr5m|T%Xvy?a-Npwls@D_;lV!n{Az(SzOOmfEv`2%YdKr-kh8U1uIeI}YdK!& zK#n(-v7D;p$*EedRhV3BG2JS9ceCZj^;^iR7rWEha^upC+_>e;r87Bm%aaG)ESC-s z_Q~hx3!L$N)3I)Gy>VH~`HP2~zs&`xF6IJkjzBsvM-a9|ZWX=z z+vZmETbP&O9&p~DP45J^xfSWg+=|V)NN46;Y@Q|9#O7k)!9Mx~ z=8VL{oRQ5XsV?S{Y>r7fFvk?j*qn~!nbWbk9%1Hsis{Dv=KRJ|?=H8wImt7xSL{x6 zo12qv%+1-Hopff-&gSW)kLL1>2m9pb2Me6>ee1DqalK$KTXonO!pu3^T%_t^F4E>G zr2})6v5d_LN}f4En=2G%uCSPH6}_9@<_`2*n0F|4XT8lGNH^vVY)(NsGpAtl2-1hS z26*_5`T2_iC;AYl=`w72w#n|N8za1#tZ`J6;<`jhU^9aJsJH*ey{4Qi{?m)UR zcVKf0(wR90n@5m7%r)2?gm8ZTqQHqh@Ssnu8}hv8E{|=&HYXw;=0t3+M0GJ&Vsj|c zfjN{|#^x*}&zyzLWe78uQB1dr-W_jiOQa|3Qi|OvZ);1W8*58!&53ko&55lukv^QoDm~ zZIX0jZIZ27lFqDIvUN(*hqX+$#z{E8KB~ZpKD2e{@v!E~)?%qH z)?(QjE$P4-t$&btF37Vc%GOG$ENi8T>2~Ck;WvKwr-w65Zx8pFH+}Y=Oye=LrO#ul z7H4eDn{a-en=tF*;^$y~7c#cCO}eqR&DOk0XV$#gIydRVS~y!HC!AkjSKve+c+e-- z4SDS2^4JG#Yxcy$nmt>~r@C0nXKVbV18e+Z8Cz2)dDhg~T03FZ+7;97;Wxu?|J%XS zGDnV^D;<8=WlW~Yf#GiYu50>bY|W&e=hsOJv#v6J4(4|uV{0R&8*3wN&7^c@&7`f9 zls>Gbv^AE(`SqCvPV|8XePZ2^$38BPeZaQnQ#`Esw6&nBi?yJ(MpQbmMl_bOHJOrU zO{T5Y6lSevG2MRIb-wDo^Yvz#cP0k>Q`^Hb2YeIo^2c|{*qU3(vo1G&4(4|u zV{2=r8*6KA&8>81&28Ts=1L#d;@TQr;r#mE0w?;wgFdlt$YURu$39?NGb|p~4BJ{_ z)x}z3TVpI8SYsT^*qUC+v!>V9`UsKCdm)#bXbz2kg=4EG> z*_v(XmS3kW%)0LQIhfytjIGUU`3*779AVdd6jKUx0YtekXJMVO>LASCzkhyzOz2eYV|Dr+zFG zm;K7#ZS34)Y_Dau??8CFcYjuGn1N(b%|wfjbexo_0&ArAUczeAY4 zC-HMIzYCeFwL;rnasSR)+gBp{ymZ3$S=&n@9a=80Djsyp?_nu$q7OXzdrtKn9M=o> zvbOg`xc98P%QtKm?DJynCFQn{M)v8j^v3d7rtbGahh1)5S#JATRJQx#Z_A76cE=TG z=EiBgKM8{mUuLB-6u|say=0o)S{F~b6TGk5q;y2pm9y}r7wfnWp&Am9_ z=F{5dW-ko*$J%Xkd%YWQlaJ5H_1S%>c=lg@M();*0rULh*#RSe)awDmQ(kSDBEKCjcIz<=r6 zT?+N?bWzuWKHcB!TF`UX-Mba^Kko2uh2O<<|Gmh&9pG{M!0&dWUbiRuxSi3{?T`N6 zE^&K-C+st%(P__p&>+SiE$)~*xpw~fs~vJ(j|%vbY8`T&PYL+2&h2wkdk5U&@pic? zQv)8-)a;xFJaS#z+`2CUKK!1xxq`&jdU(dWB!1HQxb{APH-=)d*E{B!$_PfrbaP=~Yr_w%})3i6+P*{Q&D=$|_m z__xb+Db)MHgJ$QvK5y;RwV>xAr*$ppzkj!`h2O<<|Gmh&9pG{M!0&dWUbiRuxSj7X zJ>CB3Uuc(n+kJiZcMZI~z}NwKu(uc3+Y9XN1@`s=dwYSsy};gH{+#x5dD;u??FIJs z0(*Oby}iKRUSMx8JZ zz}{Y9Z!fU77ueei?CquJQG59}xJTvh_1)n=!R|l7?mxlqKf&%l!R|l7?mxlqKf&%l z!R|l(IsVh-@tg33mSpcK-=>{|R>g3FddL8aKSr6XRZKaKexFtz8-L zjU(FU4mda96ZdJC`#K5u{SVH_RjC~CAuqMb)qHfA%8vV@b?(G|0q0I?o%^gtz^|`v zm3v~@P|3XgSS$Gx>f-t2?}z9)^5@PC7@lg@pCSYQG3y5lQ}0Q)2aG=51_X?r^-c{K z{l7UfV1Cztx&iNA$$Vq}`GZ3{7vyWK>QdktTC-b$|L`Na7wUbrdXIuW^Y8Cb&~wc0 zJq!9@mFZddT|D>Si@e(b9=8wtZa3<6d!moq89m+p=m|M}H(=Huz z-*gPP(u3`DLr)0!)Qj8Y4%#!|!<)9v)mb}C@((sSBe(U<0pB^GP42PI0iW|u>)ecO z0vmYd8liF|Hg;973#fxeD{Jr-|gF@ zpy%sX_9*Co$qhXUzl-Pody#iLz~lCT-|a@dZcp@aJEN!DAN{>u;`VZU*Mplk^tJ}?13w)5w-oy*g9U~fCHw;kBq4(x3Q_O=6i+kw699OGLa zIipfT_bp)eEnxR8VD~Lx_bp)eEnxR8VD~Lx_bvV$-{SK47O?vku=^IU`xdbK7O?vk zu=^G;zY*U8cHaVa-vV~u0(Rd5cHaVa-vV~u0(Rd5cHiR9@hvWoZvne+0lRMjyKe!z zZvne+0lRMj^Sivg;`h_PLE6;6L9l;=VE+ce{tbft8wC3|2=;Ff?BAe2=Noi+zCo~m zgJAy#!Tt?`{Tl@PHwgA`5bW>g*6UZvXX10f{yu~KJqP>y5BBc@?B5I6eIVFg;$8OfWpiiqQ-3xlwUempxf3HfR z@8fsz+u=`K2`%kd@Pq6z>e~$ljdHg5X{U_M{C)oWb*!?Hi{U_M{Cz#*0 z^~+Z@`t-n+4K}aQAvf)@fU7>ABw113vt! z7P+@}3V7p?({d}u4UURk^c?xC>IMwY;Ohn#_&?bz zVCuc)oP7(E}Z5it5c`nSs^!|yuzqkucE=~Q^$GSjsn-{->a1)e+3=~>{v zYmc*YUhg5p&nf8BY2>*DJzMT~UP1puJDykgT|D>Si@e(b9=8wtZa3<6d!moq89m+p z=n5{3{gy#`u6thg|!~;rX#u+U4#&Kj7~-Sbua#z!%kOoqOfY5T|cHvSn^V zzkquleR}Q<>pO_A$2Dk?+j3yQ-`#v#Zo;|{r=M`yY5Kj$@cij#^0B$epPC66o}t#a zA_ITNMgddrh`$WdbM)DDY{2Mw!$|?7|4;h`%sdkMcZU zzTcz3f6CBag?fK@_UwW_uRd~4LCVE3P3_n%<*pJ4Z&VE3P3_n(r_|E?{c{;lwP!EOhz+Xw7+ z1G_!JZfCIfUtsUoz}{Z|oZsd0{4TJ!JJ{a`u)il@e}BOKUV;661N%D(_TLM3JAmCj zlF#=$V7DjO?F{z*3+(+G*xSpW^B%f9?;+UR9qjJ|*!x+qzdvAqufYDkNj_>Xej|Os zd$l(fd=A)s5!ihc*nJn+eHz$(9T=a94+MK(26mt6&+#oTk8c6H?*+S02D`5YyAKDu zZwI^22lKn=$0d{RBP5gWJHYOv!0x-i?$f~T>%iV;fxRySyU+CJ^aU>Oc5vUzbN9($ z_tjwc;b8BJ!T3!2ZgAXQ{u{|7`ELiiO~7s|u-g#qwgtP*!QS72y}tu{+xc^Tqs#Lf z!Tt__{oMfjI|KH23GD9}*!w%M|3=B=f4gMz{TX0qox?*uP(}f7g=F_X}Y6 z17PGJqbu=g)u?{~o7AA!A}0(<`j_I?~p+x5Obe2?GV z(jj-(BLR>4uwCxRRRPyKwry_n>Vx&oesy1)+zo949(Qi*+=j&g@7%Ff?&>XruXuTC z%Usv~0YANK%Uou4z;}Fcy2j6Z`#j%udGMLYf73AdOn9DM5-|K7s}3*JdvDi((Wm9Y zfYEcG*8)cWgpj!8z;nUL-E+?W>Z~4xdYdioScZz2Q|7N3Ao1EL5+s2 z{zdW^e=?}igJb>?*LbNzZr%Fu{LX{g=XR<#STd}IsGbCTSN$_`gN6kBdF3{_-p>Tw zeB0JqR|9AJwykn?M-5TgyH~f&o%ngck3HN{HbjQ!)t(wE8RQQ-Y?v@StX)9{{!i8g zOuc_OcDSCSPvgr1M$ZN}28{ma=K{uVA3q!LiAQuQJiq<5&INhaLO9QoC%P5*FaExJ zq28U=_bBMI#jQOHdM??$S3&=|4SN-S7tj6oBJXy9hjmB%F8JMU)a&*{AGb4ly8Y4L z+vVT!KAdw;huos)!#noe(hj+kSB7_N>xVn!YQGcSv0EPNkh}lG@Qzh_szYwzn(&TY z^jwGB($B*?R`9SEYUK%pU@0-5uNK=KmTv zpW3Z`u6CutdT$5p+dfyb%3!^>f2m_R@NEa{y}kVOwz+Y;4;JUIUE1av?K4>4!jFC1 z=C(O#u)c-UhPTZvuQyoV!gpia=6uvupJ;a;y3T&gb?#BR92w;N0_2Tca%*iZB7R`;R;_a%>^(&G9PmiX+?dM(=fZbd=IRX!oc(@jnQJsOa1PqFRc`$7 z!1?EcTICMEGH?!S)GBw@h``yhWvkr%BLnAxW-W8={~9=tJf~&u?lpn)`tdDu4L=E- zZ!c__J8xa!{OEy}xdxvG&X1N`j_9+%dEt94b6cC=z+W}mEBFoGrPKcyFg~z(kAU%k zpA8KdAJ||@z_k0HZwZ*+e%?a?!-<|hy)abvM9+oK50yR9bI0d~%AV-?=`%xRPxRc$ zFr4VQ!F(5-=y|eXII-u8nPK9@o(I$)CQj_R!?DA}i9Me?YM3~&=l*{fCQj`6{o%vJ zi9N3~e+Vb-zI0LGq}^ZpQ{bfC+bsy3wEJdr11If1YgXW--7lCCIBEC((*h^&=QWjv zOHbakHjoP6)i zuMV7i@1sTqPQLfHwl>MX_tyspPQLdG1_n<2(u3A7xL>;PvA~I6`r)C#iC?L6FBjoTfZMT@t=pj5jgRm*S#D#@t^NJA2{)!^Pdcy z_|IjJ22T9^lV1f+@Nb_4PVnX*1Wxdoe+iu6(Kbfnw}TH|9yq~eRu}Kmcc*qL=sB%f zr-Ghs8g(k@d2gmuLC+4ycPi-lzs3Yw)nPl!JbEc z*12HMYd`K>u;-e0Iv4CY;tiV<%-eJIom~s<-uZ^Eg?8^gscWI#t6kN#(C+69>{@8| z`+9fHdAq;Tqidnvk36`0;r-0)+P(08*4)^w@P7XMMYqEHIrYPCh4-`J3R}0Fe?Rwp zrd#3tysm$b!guuAnLP^MQPT!J3g6MHx;+ZtQT0806uzVDw(3#%j>i4ez3?3!Gqh*n zdvDdfXW@IVdqU5`_g>@Ro`vtdldUE5@4aiKo`vuIf$w@0zV|f^dKLWAL;LnB_@z%b z_AL0NkJj`o_@!m9^(^?M_tKsPzf|?ko&~@3$kJW~|5s-XEc-_ebdI{SkV4e}taiAEBrBN9gJO5%%+THti+THti+THti+THti+THti+THti+THti-cKKg@P7I@g!j|OA-tbH z4&nXuaR~3Hk3)DreH_Af?^Md-ri2e#yt5_$42I;+K5u&)5pp9Pah}apNUh(-||)ik6*wZ*ML3V0ec(- z_V@_waTD0%DX_;`V2{82IdO{16Q_VZjstsq2lluR?C~Jj<3zB>k6?ZmF{WeUbe}_^ zU;ALEFrPxdR_&mG>DNY`9x(md3xfitUpskW!1Qactq+)f?Wt4VYT!8m_&rwu_8bD3 zoCdK!*mDkG&qaVeM*;TS1=w>M{+!s~<%#{lo*Mys&IIha6tL%5z@B>ndrk(7-N@B| zJtqM6Tmjf~2w=}GfIa5`_FM$ma};3DU4T8O;m^s{xIDQUu;)g=o-+Y^E(Pp47O>}D zz@C!<^Sl0???C(=dA!WK=W#UH<7=?T-C&Q$!5*iBJ${#bKCTCQyzkG+W4Jtd46x@7 zz@AT#d_KSu@9Uc`@re351bzR!0E9MoF4nY>9G%-9;3nO zF&dm6qrvGh8k`=Z!Rav?oF1dW>9Hi79!tXMu_T-xOTy`~B%B^g!s)RjoF4PS=`k;y z9`nNKF)y4R^TO#dFPt9p!s)R&oF1FQ>9IMS9-G7Iu{oR`o5Sg`x$DW8&Glr==6W(_ zb3GZext@&KTu;Vqt|wzQwA5&KJr@V3=i=b>TpXO9i-Xg1hH!e$5Khk- z!s$6fI6Y?wr{@ge^qe7_p4)`ebDMB_ZWB(=ZNllfO*lQb38&{a;iRu2Cl4o>oIIRh za`JG3$;rbBCMORkxQ^xI;RKVDhttQFaQfI1P9Iys>0?VceQXJ*k1gT!u_c^728Pqe zz;OB)7)~Dp!|7vSIDHHZr;mZ*^szdeK30d*$LetUSRKxD@?&*4eXI_rkJaJym;z3Z zDd6;&0#1)9;PjXRPLCAgL;q;gnPLFxv^q3b; zk9pzrm={iudExY!7fz4O;q=%XPLIvu^w=CukImuq*c?ue&0SA&u&yULSl5#rtm{b* z*7YO@>w1zya6QSvx;@Fkx;@Fkx;@Fkx;@Fkx;@Fkx;@Fkx;@Fk!s$5~I6Wr=r{`qg z^qdTwo|A#ob24yxP6kfT9l`0jBRD;G1gGbY;Pl)PoSr*^llPMxES#R>g41(caC(jl zPS0_{={YVqJ;wzn-w`=jI6W5!r|06}^jsXAo{NL?9Q)qM!NTdeI5<5Q2dC!@;q;s# zoSrj;({qM!dd?6|&l$q$IYT%-w+W}`HsSQ#CY+wzgwu1IaC&YNPS0(^iGTk8VUHod zanpS?zHXoAzHT4v>-NFEZXfLH_QAexAMES)!M<)E?CbXZ`S1Il{`>o${wMD3^*vm^ z4~YFoz7GiO`+&f{4+!l0fWW>F2<-cSz`hR%?E8TH`S1I--Y@I}!X~~CNVfVX`?h{R z59j^Dc@Egh&vO9#c@AJd&jIY`Ie`5<2Y>$WJ`cyw!0~fbbRN#{=icbN9Y03}oA@~@ zU_VC%Ozw_znf&?xiF0qLi!ljpx9RyR-i~_y`*}Epb8I-j2%C62g1sHV-j4qK-+dkq z{Th2Gy{r#Mx|F_O5Vt+1Y zIQYI@uY z>@gbHV>EyM``+sR-rj0&FV83NUitoOup9BlKj47@bCM2!dXDC=Jy?AlmDChdi)HZ-_KkM?ed>~<`Vm@*bC|VdceNl2kiTR zz`j2S?E8kmzMlyE`+n8`bNf|)-z)e3)?PVpFZ%1>_Zt7dwb%IfeU2LoYxCHH>1+1D zzLpRCpR&)<_aXY)QTE6Ano_W@H3j<`RIsm21^b#+@b7yM!yZFlyNFGEO(WRXI)Z%- zB-qzRf_=>-*w<2m@rT}Cj#;A!{-3^v+3mpZb^CzbZeX`3*zF8<`-8n*B>#VDO)2d~ zyvDj*KZgPA=P-ahUIY6%3}8Qp0qo~6fc+c>u%E*K_H!8g`S0fr{rAot^0m{yuXP`+ z_x3-1t^4oi>8&iB^TSzxe(nd@&;0=VxgTIZ_XF(be)#kMljrIAxn6z-2xmt586aRk z0|e}6fPnoB5U`&C0`@aNz=Td?B!(F9i1Ug}{Ek5ZKQb0{i(wV1C#C)bkI2 zzgOaw27dNCZS8qTu%G=7_Osu?e)c=q&wlsk|IT|QzWcRZQu&if$!7Ks+^o^$WSNxW=9{lI>RBFTC`TYm<(bt`Oe*fjP;Lb{`9meS3a# z-mK4s=T^BPY4_?n;k{}uOxo0YSGdI&i;`UPCx!cVx;eSE(T&0vo_uTaYSRJ22mfhF z(*Cv@!Z)_OE$Omj3+a}}%g`+^Qx49T70z=C=j#&A>mZ!hO*pT!aQ?Rl=YOMc{^nCK|`wRM?S@wW_JG$kcmxJ^2!g(IyJilNRJ~5d-F|pkhLT0R^V;F_IGc8p0D5Q*WEwzys%K0>8Qb+4&{=^>1Ph ze7wmy`EEVFSsVGIbDonQv%odd$z~sz_Zl@tI;U+gFduSU-zMhCH;0~=zkAEmYt#1K z?*`_lJUCSP&)j@&{=?lLN`Ktz=jLAyyIJ~^);~Z0`l8K+-*_$I2`5Nr;Xdc*_jY<- zZ9iK3!hG7M?KA8*UwuK|x9ug;pa0Vf^IccJT{_=Xsm69%BBS5-BL?MHZ$3wc&m&I1 zIA5j5YLega)R6qqZ5NcCtH%w_yG(jVZGZpErTM`V){_2>{fFm|H0RP^DZ3^365c&BwG-{+m-`I}!YEB(W^y)+-%b6(-yZ@Vmi zb?p4oS@FaX`Gec8pte)a7?p38$Y7^)3FNvh=8Y z=w{1F{_@}(TgH2N`|Df$JYe+IdDm_oq|;%}vH5^Ux(mPX{kVMVxjM*)4yWJH5{KP> zzE*w`w=bT*G2d!jTj}rf?S#D7LbFSM*~`b~J%5-(eop&vwBkT6?wjX^{IrFqD_=Vt zFh0M(`cm<{rrpGR`9TjUM|)jxV}8gh?+TCTG&bLU^pnzGd7WGG)qc87`k%DAP4kU> zb?bh+<{|d4K689NVBF=>->lU{%`tT5+VS@M^S4K9PCjzg&N z7}srUP0ANs>@w*`+sO@mHKVis&XZbd-OF#?tT~LGdE4BQ-_Y(1&F8SAwkKq_C4Y`q z+vs;P`p+$OON*UoI~n_DtdabmxJNVn4%&1gYo{6g=u0+l{_y7fhxw;V{`5*W=cja8 zNA|lNc?;`BZ6l8*HXq$+LVi@Qx1>M+&Er`Y(uus6^cC|&`jN+yes_IgY<|a1Q)EB# zF8xWzkIpyhw2Jg&o=89PsJrVQ#?b~(%$zz>L|AteB z!AAvvo4gcsH?(Jd!-+BQZes)!l0IXMO~Htm3_|2Py1wX z=|>%we$+|fsH@W1``B~x$9s2@JZi6SHSE0ni)((Lyv*)x3-29Z@AY8s^LC|$ES-t;p41z_J5fPGg0_FVzkcLiYI6@YzL0QOx0*mngDcyfbIGuU?pVBZyheOCbXT>;p4 z1z_`8u*c=KS^AXyb?;tntKyJQ6TXQIM%tyfH9q7lo zC_~?T3c2|X`sOCc&3Di@&jOoIp<}*7TXPe1%(KAeQ0SPC(AInhxp@b2^BvlnL!o0n z0yghJ-+Tvs^C{%!JLsF6Adhph;$WUdTk|P&%y(#Oo`Q~f7T6pLee)gk%}v1O8t9uh zp>Mu}jyVX}`~n^G9om{hAvfP?Xgj%~ugU0`@6gtq3v6!HU`K7uM;iK_jK29-LtEK5 z-=SY~lZL*Uk(+}cH=n}3`3^ef9mvgh&^L!d$9x2A-hqDPu|(h83c2|X`sO3Z&3Di@ z&jOoIp<}*7TXPe1%(IZQx57b?n@`c!d;=chEP7LdSdrY~F#s`40NDg<~y`CH$lfd3v3RBj`;{}&3BNScOW<4p{+R-I_4u_a}e~+ zchEPVLT>`^8PF2>kMD;P~p|CE7lp*^)TU2-&<#$ zjrQm({PxG|t~33)!-ba~yWTo~J^V=FPZsID&Ld0o6CSd0?{((*?C5(I8dKi$uQ2)> zOgvUP*eMS@UKslw=QvTAejhsFBw_qHxjb1IKaaZi6k+^tKK)c-#&y#4I%d2*yPqcc z8e6a4BEM(&sxA8a{jze4o!ie@sm1=U8?D&V?_9lCXz^#t>C3nH`CF^yTm0YQ-Q`-w zi<~$xcJzr47(2ubjD6w>reER=#vkGj#!vDB#((k!b{@gbBiMNaJC9)J5$rsIoky_q z2>xezWX?EWVCM_$e1V-Wu=53WzQE2G*!coGUts48?0kWpFR=3kcD}&Q7ufj%J6~Yu z%W}_K=L@;>1$Mr`&KKDE0y|$|=L>wz3R82hyTLpCJ@>l%TgT6Hue$}m|1tNvo4VC( zh1cDL?dLAM?#?=B-ooqd`h({$yza*KZdcgLBd*m(pykKlinN9K?71$Mr`&KKDE0y|$|=L_t7ft@d~^96Rkz|I%g`I3I* z3+#M>oiDKS1$Mr`&X?t$x6T)G=L_t7ft@d~^96Rkz|Pma`+j!MC-e1RXR%SmJ;v=< z*iiKoc_Th$`(gF{E6E!%ZLxW2+q>?uoj+pRLEeaM2l+q4_|PbKU-p@Py?((n=Rp1J z@n_}$ar2r5d(DEqX2D*wV6R!Q*DTm;7VI?(Zd|iI=OCZCSJw0OXZK2M#pOw`5&>@IQqtoI<`YwuV2@8?^&+l$X&z1 zuHj(UaIkAQ*fkvN8V+_12fK!YUBkhy;nJVE=V~wT`Xwe_zhJLlu+O?+pLM}L>ww>+0!9MGPebxp0tPA$~1$+I1y?()7zhJLlu-7lx>lf_x3-;ETOIseb?&FD1UOG7fye#lAdsCSEcsC$zGZ47T7tW!|bC|f5P-*IsI6l zer$(+Y@eU*m%rN|+SyO+*?;_)(9V8h z&;HX7{l&PDmoYB%s~8t{gu}jY^eY_x2#24-^h3O`ljdzNVhxV*TAw%w(+_b(C)p=% z!u;g-@P{}H)6RaU3%S-p|k3p zUskU_xI&K30e5^;?eOhNIXZLQ`H$-K16Rq>Isf<9t2T3=CY>wp|9drM7;R&Y5dYj<1W+qrIW^8rtwRM zIg-|fbiiqC6pS65)<(hDiC=@AtieuZJH)TSpS;1J-2M>1hH>Q$53y6mJj6~J^ALZkn1}dN#XQ8HD&`^Mk`D1>exO7Am>=jwe56DCm}lq^Kjs-a z5ohTTKjtes#E%#u9E~G>JSkLu*X?;m2)|Yf*ok}Ox zsdQqUN+-pc^)4Oa*AQpcyL9NMAz#!D*&%+;7ydTno%$mk{B_i3&-AFV8>?_aP0Mx#~HwObXGwp&J2?K ztP=j{tOE8~1?;m5*k_dnxyBp%74kUq2>YypJo=T~XBFh(r{v*(4LNg&&K0~5IKePw?3<>rbvO!)p=vUydBOLaHqhI0hM>zZx_8Ag8F)qtX z;)p!rARO@#j<^Z?3>p6D3<>rb66`Z1*!gN)gLe<=o0$u&*?RlT9AU<98)W7V4eNJi zU9EFZ*F&vM;^Vam_Syt{ZH8QHGxWs)!RCPA*pL2~>gvBGr|58Y;4DJkIa6>(ndSEl zIP;1-pc8v>jt*xE&N}GC-kqZpd%AQuD{*E*C(Z!U;cUej3p;UUkWQQ>q!VWh>BQMX zI&mhEPMlSw!r;Y`8V9v#jaoPE(D zcW?o8z;Fa~z?^-<4so;{;%GbK4(P<0(Ef-cgg@dA=)~DlI&tRoxWpaMA%2`?@h8r% z(up%|-RJsQS2}S9mX5gtcH+z|oj6NN$J_xO;)mb#Mf@7_F7AL1<8GKgdBgk>cR+{u z5ijg0e*B_*)wx51oe~}5M?TOY59Fi4pQ^#13LWxEUeSqhNhii7ofwyN%muI$@sWc{9I$+i4 zqywf#qZ9Mlc9_q$!+e%btPA@iju8HcJ76c)mvmx%d0gTS=)^jePOMYu#5z@9vEHR) zjzC}L4%jglU|dl*WXIeA9diM6qW(z7+yNcp$N14<+zsl7iY(8Uf zb`t(S;jHrAZ!hW&lYCuz|8v#$-(0MGUAM$z)juY+&yl}z%;bvimxH%j=K5;n$L9*C zpH=!@IQ_j!dcvt)mD&p@du6gKOi4=pSx$e}&#g~CwnIO*&rkQu-|Y|W>?ii@KmE{O zj0?HWmZ4w8xUeG}_JyNg;qXV8eo}j3`XOG}p*|2taE#ab#6g&Th$A`?H{sMT@f7Co z_J?-F5qZta+k$=`auz#-4Tp`U}pj&Rr)j(&y1A7STF-t2 z6He{Q)LuB*E0bMe`r*5&*r6ZG>Bsu?V>|R?`}}mj{N4W0&VFLg{?kvxxR9$(hQ4sv zsbXB%7mj{~!yn=BQ#kw=rcM&a7#HKUK5-C^_z2SvacqdEaPo&Z3)7A`qJusBzyGFQ ze79Hm0*5>UhrV#w$&u3!;{iv%!r_lF{SX&)=!ZChov)B9U*L#??I>T!BW{vAU&x&= zF#XUTOh3dC?0hxI%LaX6=L>n*ufWl-u=9mH{FL1JLhgKlW4zLdIM@#JSvcY*9Pt#6 zI14*p*!*YtB9G49AF=a@+<63t{T%E(f}KaO^9T~jd%=Mb>ZAz+_Fz&?jG$hFo&UvoR`2#0;)=vO%W5%zf!n?6s1 zeVzkI7l1@`&^dwqeuzQA5z zV6QK**H_4A*2xr;KT{|9pA)Yyu-6yZ>kAxt&%s__V6QK**B9993+(j;_WBCB)>r6j zeSy8cz+PWquP<<{3;E;qh1}~4?Df?k*Z==`eKpw8|J!(dA@};K+Y#TFj@K7*uP?CI zSID)#z+PYAh>z@eeIfVy0(*Udy}rO+Uts5pIsdP)^N5b~2zDO9&Lh})1Urvl=Mn5Y zf}O{Z&#aRvCe9-=ZoOEHN!SH#DknS%Y9DcEZb?DYlq`T~1>fxW)KUSD9ZFR<4a z*y{`I^%e4&buz`o>x-CpeSy8cz+PYMA)9XVYc}Y~bGXmQx0>`@*7}F@gg<|0mi&@m zFBHCPxjFLLCJz?g?4o({tLGUee9lYr<+ne7vG5`fbj)9x#E$01ARe>?3G>D;;M^7&6Q>UMsdf0g{)uZBqe&8Ms9ckF+W@Zp!QmA`$)1;Ts( zuy#Ii-*a2=A*-F;qLVGyUzoN}?{k_kHka7?L}B{caK&SV@nOg+{eM2JG<8$9$ zb<9{USpF!<8RN6(9xcq+f9iI;FfmzW%E`jS>YNd02ouBh*9;Jz8QcH-*z%mKRC6?k zdCuM%zrG^O^WV1V|F$sC*=x7a7sBXoa>~oueC;mC!PkE_E!%Ci!NTV*^KQ0Dr;F?I z-#*Jm4ZlqI^sYZ<3y!)%IGtg{GiB%H*7;@cT_yQ@-8$xdXIx#!W4h+E?KP^7SM1dy zKmFL{TlCFmu`~C&d2ajDw_HDWzq75iac+O6zqDCyKd+x}%iR7y{nVB@>sMnzKCr(q z`lmg5iZFI=nElwgJlX&L_rAjPJI~h#3ggc&bM7mQpYt5Jm+*VZ|6NzwqmI+KRylI_ zI!@!Ye3KLh>l2?AJ1K6qe|?Il`z6lyhxpr1l+sKN>9kqYwQon{Ta4C4Xj`ZC@PzQ+CsLmrJMnN?$cdN<)8)hY^Dg&aC4A^!9rH&vxLW!rJ<}%t z$BHAR|NY{v^2yI%Ci!oz+U3XHK2rJzweOstepy}r?QRR?=Ph%k^uPOc{`}sR>OQ|X zrG5U`HJ7XHiCcEgA3pXas0R&nPdjq8e2$+k5#ILfHS_1szF0O-d9ioi;|JV24IA^ZX zcGJVx&6!uo&v<;}yi>2bK5bjAeO60f+uqb)I-^=|B0IEwymRlIISgL4U+;YCljpYB zne*s++xef}G@rEBX_C`#o4E%_f6Cb2Ep}+T#gk`Ar~AVjYeA)510Jz=5_Ptch6AU9kTWFd)_}@I^^-3P6taq;k_ci@V29*zxEw@ zzCx#yr9<9NT;c#>=ER8Fi`@jhYOaHXZR>&XUc5lg< zCu3(jNc!Y)g`(aUd2jvQ;nKPB&gJr5HrZcocmI6xeC$no*6pWx^69Fo-OTN(GYt? zcYa{+1J$-+2h#j!QShIQ@+^ig=4P=d#?w3uLpat2Yasvd#{%~_Ij}Q zda(EU7J1q$tjzr$!|JigJ-V0 z`nqtwh>7zBcD{uF3)UUaSTk4U*>2`aJh#mpif6T%TcPi}0p`&y8^K9 z3c$WA0Q;^0?7IT6?+U=aD**eh0PMR0u^cLiYI6@YzL0QOx0*mnhB-xYv; zR{-{10oZp1VBZyheOCbXT>;p41>ipue{y7=0yYOBU*{<{ik*cW7%4g^u|M*t`RM^Bwff zr;wZPpl@!1+F-+Tuh za}cok1v=(Cv^9r9ZocETa1i$e*FeX7hqmTiU~?%L=$k{KV?F{l??B&t2YuSYt&p4Vpl@!1 z+reKF_qsd*Wse;D!*6mk>R5%zgKSkepgn0uiT0o zUQzkIa^qIMtnz#1PTK3@%I}ri<(nau-z&HK?1L-6SMKTwgDSsQZi(M6to&ZNzdRI&3_sXSrxKw_xTzV%<<@d^^cd}G|uUvX3 zOXc^3qpWY48 z(r*E!UI0#34gd=Xk5l{6SaTbpF3rAjr|4dHFdwRBf<@d^^XVh1IuUvX|edYJc z&9d>N%I}p+&vmc-Ub*xP{L1f@OV7!#{9d^acD%Lnd*yz->Xypyl}pc!ul!!Q^o;$= z@0I)Xs0o$dD|gFh6Dq$~?(GiaE5BDRJ)^$zd*vqYJ+AV5<1%JS{9d`o=De=*d*#w|-7CLWF1^2?@_Xgd^XeACTh-z%5ik5Ku&a)(}VP38B>UH<%)mESAZ>dE1i-z%4%QD6DJa{J$K zW##wErRTc0_`k*CmsftTTzcd(C z11rB*E=4uKC71Oz-K?JjDJoPh3#>y>jUp@|t7l z+&_Il<@d^^ceSW4;eUE3h~_G7)AQ;zuaI|I;GD|um5a7|k6ZMm_id&3zo-t-HobF1 za~ND(@4U+Il?yv+``7koCx7bim5YA$Ub*y6nHD?IR_~SDc){d*rbL3rdoAv68E5BDRy|aL|BmI~svPs?Zd*xPp z>XORul}qnOV7*8u)}8!B-|v-6?_XeDNGH~*aI9No17VwK*D z(UPz9z6{od@)dPeIBKu-qfRR3=^Y#``HH$K{pCKpt@3;2q7F+x>ZEYgRoUGC<%yNw zD;Kp_I&GS7uKZp(?;YGXdann2uLpat2Yasvd#?w3uLpat2dDS1X-@~oo>+gcT-z1M@i*Mq&+gT2=`$n`F{&=>YzkB;|xu=jd!_@j4Gd9O$Ay&fFn zs=rq*_Il*r>%rdZ!QSh^-s{2M>%rdZ!QSh^&R64E?vL1cMD9F-oky_q2zDO9&Lh}) z1Urvl=TY*RXSP3mW^2r2Lw@yMIp+(x^96Rkz|I%g`2ss%VCM_$d`UiY-D#cvd)FOz zDdwu&;g~CNKVuHXos78^`o1dw`>p`&y8^K93c$WA0Q;^0?7IT6?+U=aD**eh0PMR0 zuh-QXlSeV&iJkXx$g?VzAFIxt^jO43-(8KD0Iw6XluTM+`I$1`3`N(q0liO0h@QAZ@z=R`4n>V9rVpjkelzI zZ=MAzIhY+<~!(^gMiI1&@tbktvM8O^PPsa zdN-W820G?Dv^D1fn_D&5QCstohJN*4IrFcEwtBCe`3^pqn>6&L_sW@rAUB`FzWEMq z%{!2r@1SoEg^u|M*t`RM^Bwfft&p4Vpl?2c+-Wl;@1SpPg1-3<`sP_+^C@)9cW7&F zf{u9>*c=KS^AXyb?;tntKyJQ6TXQIM%tyfHAn2R#pl?2f+-_7uHWZsxvRf3MuXcVAxmr76YOj@#%y1bon^TUOf-Y?pzvfg4uY z4i^b8x!UU0*p5?$_uqff>dAZO%+X0dtMt2Y`g@u5gj2gRwHHqI%4AnK{lD4h)Su;< z<@95H`mr7Qv3-8JU;b`?XlFmMXaDJkyYUO=`n_e0f5b7~5_ybQIL0d+_5{_{R$GC)JT*5If`&rQ*`!O!(OXF%7ujDi5 z;i8^DssoxEQ6Iqn74wjOJr6I=W?g66)ywNn`;Yjv8Ov0gJ^fWP^5@oAtQxcQVI}y0 z(>hhtuAU&gbTLOY?$bAg`N{8fI}=Luz_g=17<($jvL+GVM|aI)8w>yiz?<++;uEX@8V2^dtU~|Fe8CPnbSNgP8CzqY>a6Oc!IB#*cWM?8fi&h}G$nYP#?j$p4fu-6*c zYYptR2KHJ5d#!=J*1%qCV6Qc>*ILMD*2xr;KT{_sz1mM_5axX&KK#Xfxi@NJA75_j z_6cvJXYzjhB488P-Wi^ zUOhwp>}TV%Q~DkvJbmEh*_s0f3BOvMneBMXb;9(uaXFJTF=I4XL+YcPlbkL_y z3D?)@RLh$!Px@({*7cK}bkA0|lkAtapZYD`Z}O+KKgrM1ekT7*`=7>DdR(kE`erO4 zZ;tVzFC2Et7%%pPqhI0hM>zZx4*!MIco~;)jMsAFV142v9B~tlcnU|Hg(LpLkr&~} zm;8@B3R4rv@4sa}pmXBW4>f(i=-kcV@vDt)+GXVF&CH(@pWZ0@e$j!FZ+X?eO&_ju zi{#^1>y_;?a)#vhZTr;Px8C`9Gjpu#h>NptZ+${KTVC~E(qFN}<_X8Onq2PjtaQ%Y z>bPvc9qX0Yzi-{88L22GL9Pj@bx^&Qh+Iwu@=UTV9wbXNc3!saa& zyh1wLtaC-vhMNwr+gbL;)OKCz^q+B8^BV0pmd+ikJTrNVb4E&M^)K3#TP)aFI?Jr{ zbo0i)pF0_!d))VP^NXKcB%S^<)-2a(|A@vFI%}iz?7rKTM_#+Xbe36Xt8(Mt=aEkI z)r8J<>z!AAeBlC(I!%l{e3s5zUtCcha_Ux!PxK|77<;2m6Y&Y3vxXQp_LV7y^|4DQ zav`1YSvnCz=|mo-6JxL2spmpEF$bg*F_cc^R5~$dq!YQ2PRtF-Baf2DT#`KIK-Ms4 znpk&@>lD1|Mn`I%H?Fn+i1oYjmP@8RsQ!P~;BgC_S#95G%@Taa4#!o?ZF{?LdQME@ zM6*}O_nNwCb?+HV3-goT>vm?Z&;!$s_F(K`7fc;9(fT?b3peA=)}3J1p7W2?DHGg=Q^;@dtl}j zdSKssgX7#KdA)9LBh2}T{z9K~moPQfcH-P6d7Qh16sD2PrQ3&b?N8TDTr=Pj|O@BvEc2Ym;kG9F4`m5V{ zO8IJ#YrLVKBM&>mVP81<6%K!d!%yKfF8mjcaaqoItxp_;@t6MSH{vGD_~bR zQGcWpbxGLu5FP3Y{eh#t$xrGK{nhQ%>mfMgS%bcC*vXN*9)hD^$-^IE*F$t%55Y-C z^)TeBhv0~V?Wi6ikGQ#C)kEYFXUQY}^3(Nj?IVuLyuQH9ch&_wK@5~Qy%m?9^ zC&Dp*guTAd_xb{pFZv6)`U87?ftg?Q2ab6z?Dd5_)`jG;UWC2A>UQeu3mozc9Qt{K z9bvC8;g7J_7dl>F;24*5V!YPZ`a&n-BYDJ4*y{_Oh_mEgU&tdb^56L)zyAt5 zkLWm$VCNC+Jc6A^u=5CZ9>LBd*m(@O{0se=buz`rc_b#zBiMQDm)<+GzRK4kNpHieC%f2*aaqoItxp_;@t6M4kGKglKKcuPh_i5NNBo6}UmBPEcfRUt zxqc@3BlfyO?sW(Dx&wRNfxYg)UUy)xJFwRs*y}FjGwWxH$)Bm8*q|CKx8 zf0YZzkebkl|403Qevf1w+BV{tW6E{lh}(akZ`O%^|LMFk<-x%* zE3mmd*jyf*=9{=Y*jyfLE)V8xL*F46mk<4!cbh3b=JLeETpnyL&u5^%0|fhS5X_w% zca&h?C4zm&2=?70n03wF95}VpT_t$?xWfdKFYZ!9{=en3a>hIJ{E_wEhCugUnej3 z`dHzG_I&E@Y_D;`O*db@cB|Fuc$FJhY`SUZy3UXT&T86v+Kti~yXp9*zdt@k_^73y zXlmX2df^=}d8=v7-L4V-{DM!L=34iv7JUDFBU*HZetnrRZSR@4{_YZNesbne$?5C( zqw4QQ!G}fuF-UTJo3d~n+e!wELR>`movsGSJ&Tl!q{IpsQwNVVsb=t{oN?U z>WyRS?@u9y2cC4f?9Ytte|~Iv)&b9RVh;0M8oq}I<{2P-pAXD4WDaY)fH3+z3o3mN zU(aVw&%P?t_w$8$c2xS_eqDa$f@S(Xzi@hnR&)AZx^Q~7R&)CPzcA0HO3wulPS4_M zPS1A`W`9Y~gRs2Ga-Pv;eV)-}J3OPy_IXB^`{fy3E&klMc4j|$Mwk8P8C{Gq#+9Y# zUkLL|uk>6DVeF*mWz^-#etM3EF#V?IYY5{{dhUiWex~Pf2=k1w^!yItbQaRxzWPez zwVXIupZM4gakKq2uG0My=N5lb{Ozam68`_0oRW8*d6T|ZsX36IHC3kXOll7BY@765 zP02r+WrcFN8^;Kz=Tw#H`_Lo-X@%$AJ&|{4=?@nJh0~U{Y>feT%z>7P{|LT($xIapo!A|bde<{zkFm} zKRsh?a{BJQ^waaen$!0}g}*;?k>*8CzFBS0+jYUo-L{!j_wBCl*FJ2S+ohA9H#Rwa zpI`Xt-m^^pdyiY{I{Wo+vj5B9@b=oB+Sc3h+%k`s=a$*e+BNsCec&fItL+EhzSMNb zp0^68XEHUV@1r^nO^yT4EyGXN`&CmPXj)-pz3udUTW62WGePq7e5R)KJy`k1bIXVW zHQ|L7ZfH96hk8yInfuqKQA5Yo``uyj?5;0wlumj+Q&ak$t?=Q$yxg=*pPOWJ-*SQM zxR>g=1yFrue5&gpXZh_S82<0 z%a~WlkG^R6?6BYK?~b8upAPkRukeht^j&4?q*^CCwB;FQ%wce`O2=%;8|v?-!Om`5 z)!U98y?VA%>r2#@e$)4&rJuet-C~Ef*N&;b&*h_2dS!b}uD{EMXS}8FT1%h4(s!^m z7M^XEzOya)R$I5p+TK%t7Z1;SOW*634tY%916RL1&n$gET>3oMEq!lXI^@0M7Xu?c zQ<~EE%%x8r)A!G%&-2XE_tGUN?;|GG-@Wo$w?R$$fU_m%`F81h?9wNX>AUX23IRtXWe0ke9>2WzJTPc(_ikX+kfNY+nNVo zevag<>-1~_+nnp$tW-^lBl&p+v0^~>|jh&ei}>-6jc;h}e&-~84V^)d2n zEpmtdJkN|cGgqmT?X65j6>hJfV4yWfzNS`{%e4s6L^^~{kHrt=IO!?+7m(~4GwKqMhLU_X~+Le9A z57)a4ym#%rdZTjXi4v_5+%*n7R?vDbsW*Mq&+gT2>-z1M@i*N0qteduei2Yasv zd#?w3uLpatmpt}*u=jef^VN8k`y+N9kvorI=TY*RXSV;cGh1UGTk@OE*kI=i?0iW+ zbKNOE|JCb`XKt9Q@_Y|-C7#`34#o32%&pM(T>;p41z_J5fPGg0_FVzkcLiYI6@YzL z0QOx0*mnhB-xYv;R{-{10oZp1#@rQHhr0r>?+U=aD**eh0PMR0up`&y8`f^i9b0qPXU{QkT3Hc(cgU%E6LRw%^vz9>oA01+ zZUr``czWEON=2OVcchEOC zL2kZ-zIhhdd*zJtEG3D{gi_JcQ}Z@z<$ISAPN z0v+=m+L}WlH{WqvIEed#YoKGkLtA(doC|DjWjpX4+M18JU-%CC=3j0Lw?fB!hqmS> z?hDR^+#CeC`4nx+<|AP94)o1;&^Nb2ZoY%Q`3Q3J9rVq!z~)ov znD5Zm+youw2|NoqXIeN2a`P$Ln(stg@ebtZ!*|d(heF4E1Z>_BcEoqkPv^|ha4Y2I zJLsF6AUEF$`{G$(^C@)9cW7&Ff{u9>*c=KS^AXyb?;tntKyJQ6TXQIM%tye~UN{K) z<~!({Pa!woLEk(Dx%m$I=2>9#DRj(tkege9&6^tc4(}=4;e%)H%Yzh$fA7A`y#A@} zGVq-2lh;4ZjyY{f;nOxhFn{aKMTCE9J2oGDa0lUWJH3|g(|=ZBe)2nQ`8#@G+R+}2 zJ?w(%hyEJmWrKbN4m-kOUpV@$)$Pb1;qX&9{1;B2RWF|Uv%E}xSiegC2`7K6)Sqy& zU#0$p`N{9$PYu2BvzGc3#$M`A{?iX@9G#GBy!7KZ(2wI2_H*>3-vS)|2-A<_Pd~&F zoyL5DADe5*;)0VOmHewty^6U9J|(={%RP$?dc7>%Yxy3`*lI-EO+La)q%gwCp@+H#A?1LXAvI!_-j@FVQ=NweD&>LtLwkHOSs>so8Ic()Qf=8=VJ^RL~$0w$FhIe+|%=` zw!dGv??$bPl}^4y_^jz2i~Ua8Sa_C=yA=DcThmzPpQ~FjdaG@k@aOQQI~OA^{7U0} z@qzZm$Y1x&k#98LTt%y=M+yJ^zR&X$_kL1%p#vVthkWz3@TBEOU|1;*y{8zr0wHvm$=HaK`zMT!Zsi)@QD{sD;oqp7!nuq6J z`g(TR)7>=>Z~o%7?AI&1X&ydy-z(XpZMte6K6t>(S+@nc6nmz5*mK=J`57B`lg)Oc z_Q+rA*F`qRUb<`Ec87&!bH)xk=Wjo_pllv|$By|M*L0H2`v-5IpRw2ivN zjs+00z0tg~`PIBv<)^IGS~jmb zX=J|H%k#+QhG&k*U;24&**w3)3;Em2&LW%djhLF>u;XtzYjBBspU!`K^QW9OxcRkD z=3j5|L(Uq^7k(lie)#m9HTYD=$MQpd`8H<_e){|)dGoQ~C(ZT8W!dBKJA6kQ*^PBurb zGe34pkF9&4Y)&50sd(hg z{bci-6Bj6E>9wzH4*b1CG4!oIviVqt4#j83?IoLSzFDmJ?X}-C#(qSrp2c=={gM&S z3twEMc;?U_Gve8M)$Ya6H>YRB^ZD7j6~D~(T}C{YJf=%=_{HC3#Pg_AIu|qAew`_v zzb#R;y>gExY(CYdSMl~7yES2R=cjuXSIn_<6E@dgyhm}{lRGqFv-_8e6tl0ieG@i+ z*{OT+RJ*@5Ve|Ukx)mSZyG;`|C#|tqaqJflm)M!~>!QW7Ydu(EXP2E8DcY=Ye~F#D zmgrt|z3<)wXTD)wi(=w76?S$yvU9QOi(6ILS@(^F ziXL}uQOTdX7c4$me)9@DKdsTJ_{-9pR@j-4&OaM|v~h)9 zzCw0>eYZ_<#QvAdPOBH@E&j6JaM`K)wk{s2T`D`12e&G&ed?0Bo#$pL#%=th>|EC6 z_x#FJACsNEPyHpoqVFTJ^Y!qb@=L#bNOpR3`61uwhX-Wm#X-~ao2J|^J8gfPmM?$k zce3;Tudn1!xBo_V+CTJC{@G<;%Fa@;t_=gvK3XZ|Bv<)19Ei0pKmbDsR*v%AU8MZeFLZ@N=g z*%>}&&V0KkI?GP)XXnUod0}DMx#h=cP5XVbxay7@f>~QAdHRk_{r;aJVyt2D&&hzbi<-@~!s_kYkUtccQx|{6xd;ab6t3Hd$ z&aVCcUaopici9>E>~-a*ZM&-9X)nG}-hE*=**X83Y32A|yQu9a>%UfZoui9%uKW2f z)v6~gqJEbhw_)|osBY?O>My;kb5H6b`@?3eTiy2F!m^()zHc>X_HNSu;G%V^OKS_s z{uw9tsm86`MQu+Xmsc;Xy`cJPchDZyQymwUogaGaR&6$5LD@O`)U5hslTPyC_Y-%i z9_Z6ac6$GHr>fO^9o6>R?{=u(nBGA;-Cr4A-FHJr^*g!UW!3wiw^v_(o9&WnjxXBE z{yC=%tA09ae%XI)t{bXTA8RZ9hxQ&?&9T>fvj0`5(bXDV=2zPdz8qZLKYd>HwcE?r zR`)E`Ms^OHdvLXRr+L+HujQ|)uDPqVZ2s{5)z#bMTFK76eXgn&*kT^F-DSTktJ990 zTl$}@`dBs3v2&>3r(b`#8uRgN>g&EG9;}Y)KCA3cUHty)*Z))}Hw?Al|K7UEAy7c^?v<5%^ zz-H~5O|CsB(t%`~7s^49o`l_1N z>TUJ4@_^5)AAfj5_P1W((`xS9rpe}s+k9NTH}7k*iNE-b&-jS1to`SH|Dam$otM=Y zKH@8N;JZQZSJ#~TlKRC*e5EGfBfe4-@DX3B3HXSw)P&`~ZCyL({yWvzo_}jq8+q;R z>T7(8_vy<`lKr3NovZfY&bP{D-fGU;5p&%lo8+H)fS=@?+~en8?wq|=Z8kxDk#lm7 zpRM1Wt#;@d_ALw6-ud`U^)>yf z1!^nxJVW*eFW9km@~Bf~bM(*cYoFhFvTU-RSXcPT8e%Qs=g70$)ox$)MD@iQVlCn4 z3s<$RwZ8s%^~-u~DN_ z&)WW<^{m@}ebL$vy?e;!b~i3kyKde^Wi#p%Jq!QhR=>3v?EWc&hF5hj*(rJ#?PVMG;Tg`TFRtwM{-c zS7)S%t!zd-Wi#R_n-NdhiFm5*btf)bTj1`sb7Hbz+FSm5(V97NI49ZvYQEKT#@=IE z=h~FjR?QjvQj-?0J@op@Ib)CcskYxQyHM@ceOoV_G9hK&R!R^scpXMdFm_HzHG*Nm(5u3vKi}Lc4ED& zZI`p=s_k;^1L|wgH*?fJ+Vwu!UvtsfYs*Z&M>gMoc-Gok4^^_c|C6)SI__G^<^^-i zsNOntvTQ~zm7S=ivNPz=->P4CxLbWiEtSovpRyVCQ#PZ1%4XD0we4{GN7XgczL5P% zzrA0**x@tTKXTeTRWa=&*}Qh(Th+D4e;}L7y!vK!TkSpB+~C^Rt9y=nM>b=hlAYL_ zWM|Ixr&Yb?ds}_Q-Xxo`AIWCyN3t3Fk!;3(q_*7#R8=--tAhFY{kF~3N{7x}Fh4(h z^sZ`|A#)bY&vQP!qdIuyISS_IPUqcT^a`QA z+uF}sFh66jm(AGUWi$47*^K>NHe-KR+n*mfuiB^WLb5-8*>kJyw&*1Lb8U4_b?tf` zWpn$_&Z=In+RNqxpAM+by{?^X-gHI(>Z_I8%4VFSWM}oq&a5`uVt(0=bChhx*-19z z>?E6UUXsl?FUe+{mt^OzFPEy0xwePwFZ1IP)&2J^BAY)=TD*Ga;%>6}_t_S!&ibK? zZ1#GhN44Kmon>=_l@_h`+HhgnjB}~%e818n)e2iLB>QnLmCZPd%4VEJWi!s7vKi-3 z*^Kk2?DW}lkMi4oOUV8wkM3H&Fko@nJn^xe%Jnv`-;b?4WQX#ss}_~b@BXn}dFa9Q z`>}PZi<@`(zTURitizfo%~`)&+y3Qk%PU{(roMigWk~Z5kJRlvdGUVC}^&8Zje^j@*LaPg#m)o{}=Qe!l3!2~DzMJ&9lZm^^vf&Q1Y`EJjxjT%z z%Cg}uv~0K|EgSAm%eaH(u2Of0aaWn_wA{g3&RwPTxs$XV;jk|p{c;a!e}uzN;qYHL z?qDtV9VX-Q-6nRpgOyIhT`1$?4%Yto?i4?Lr;0u9VC8?@!S;&r`fk?xRgBAbxwbEP z^jnK@`A*n=N>2Rf51qz*#eG^W)fUM)2c+5}%-)}Bi!ghCsx89o{i(JHv-hXkBFx^O z?qK!ZymVhzOLuzJ?@zp1K67hl;a5)Ip*n0#2jTRbziRg-=N6tg>al9!g}z$zC2@ zvP|~!;F4vsmj{Ty9hp5rg0a+0n0S*B6we!#$5#OE7Q1(;C*Ep zcM-ggyO1KdTbc4x1a~Xb8Mp|(R;K(E!O_Z;pCUL~netNvM=Mi)ir{Efnny+OEbe}a z;8xuC6v3^y?Q06?JL9qs?fqVu9W-jp=6qp*w zXHa0~C!axqnV)qs_Z9m!^_BiW2~B%860WHZ*0Y{q)$eC74d`O52^Gn>~t z=PR#w&TL-qoTI$nISaWi$!63g*^Ig*n^Bi!GwPCTMqQH4s7taL^;0&Ze#&OlPuYz6 zDVtG0Wi#rhY)1W*P3CEQ_Nu)*K6@38&t8S&vsdBx>{U2EdlhEhGxmn_Fm+z@o_IE# zfvNMF_r$Z|3{0KZyeFOwXJF!~c~6cS&i~YT?oJ&~?oJ&~?n@m{?n@m{?n~uo0}mqa z+<7|h+;ckb+-*AV+-*AV+-*AV+-=Hc0|%teb3f_%$(^L>JE`;>o_jypQ$Hy`R@R_kOa;{>DCs zP4+kTIc&1OvCmQ!Iwy5s7_*u&2fn+U|o zHY1)Denvbi{ET>3_!;r6@H66B;b+9NYRJ26a;|CE-+jmHyvt_fT{a`{vKe`oP0lq9 z=Mdj@dw$B#n4hv4^HVlse#&OdPuYxhBtK&vY3!V9nD>mGa}9PGJLekgGIq{2*k$aT zYp~1MW4-H48|%GR&wI<~8q|4zmO-8OXBpIaf0jX=_h%WdOR^btNj9S{)$o&Z4SB-P zxRoQs?iU+DSaB)uL0& z`OfbsJaYP$)kBZA5x#rsrB&Z4vkGr@#eLPo13yUo<4XPHcQAiP4@^7SgRzHQF#XV9 zgFI`{&%t3wn0}Id;pkU5{3*~6KZV18Vg6q!^=EmO{IGtW{1Z-g^3HzTmw(8K7yW_Zo$4>)^poH1 zPmTW2fp^j$IN5{0%YS$$b+tiWHt1Ji;zxhrurD0_3Wq;6bW%U+4;=nWPW-$UBEOoq z%ooq+m=78s^M!ed?U+BpF|Xtk^Tq3k`NDcY|AE(rScZcK?UpToa4(VTZdVffMTK`juh5vqL`Q_NbdCxBg6tg^eR5{l#7v$HRd0uhm z6@ALvUp_m(;g^eewnZb(taHW{eKNP5@x)PCgUzg=udKm`tid;M)iwFKdh)XYXB}P{ zQa$v=iNy_H56JdPc&)A{6~$8nvW;FHQjOd6q~iV?2V{Ty>b7d?lYNTmOJAJ*w#fME zuKV^WUU_y{wprKF)zq!`Pu~X^nzf$w>Z;iHpyHvXAz6nnF0Zel^_Dvmzz{Icr`>6w*%`xZa<7*xLh^vLS{hYl`w=sUQ)=ZtHsx6VAE7@7|) zr!9R`)w|rcs7@MIp1Ir2)dpSnDGvE{SlKYHvSGaCNe?VmTlAJK6rTp1J$K8}wf+08 zps~O8=n}Oro>{plpBk36K4bCP%a^WRw0>x4w*DJEYjaIlyZE5TknHGpderv+z9_bu zJ}A5Bk{-1;c3Hnzf4d8^{y+DqZBzZFcyP;evz`-s*2dhoX|cgiXE)j}581hAZTnL< zDX#nRoN|eqden~TwPEq;V&|7rCiJKcow9Dx_UjAFP4@0tn{q%_wEyei^7;D~tF>Eu z&Enf-hn7b@(yKONt5u6Tj~P~8cJY$6i4U$+y!P|3vf5_9+EUVCWg*K)>n;jfFX7zn)ZC6QW;54oV`{l#~_pUv$$n>0XP4BW-ZLh1o$Qjoz zNA6KO<-`wi#x<_*?zJyJej{gGcQ3qqZ9vZ#bH=sx@w?aN+2zTcagAPjkJ@URJe)JG zT`oGaw(7|rWsIuOq_#x;G5ezhMznKk?6-eKA9`yO4p>eRnv&)qsS z+kLTPYmbfTpY7dhNH*cb<7;31GAdj1?}M^AcRi`LLB}$Cb-fF+9(SBtdupAj+4Jk2 zo9(vr8MT`ic{AJM+q1LIpC475I((-l;#Q`(M|no-#^zq+h@OF<>g)b)jq#xTGPtk3@gKj=HzE1 zc6^$NPx#Y}&*4uqV~Kc{DYjYoRwm!F@U2X~W#LU{TYoucAF>k9hZ?l-URhqY1%-br>+brg7mF8_0^R`O!Hj8;%rFomhysgr_ zZM0v;x~tNRJ*$@XtTOhjTH3Q3?RyW!w=DLoTH3R+*t2SB z&&p!Ys--g~Y0t`H&#I+8%X_zS7yB3E^?pqpvN%7~I6uUh zp_a}JK5x|0nZf6f8t0HWGt@Yr#F?SSxh2jFHO?~)*yjp#eBPj~&mq|K`GmfFZo!8} z->8j6s-LP$M|^WsaYZ$FGIKTX+ThTk#x~-tLC2W3jW#pRew=C3=OF*4?*;ff0-Lw# z-=ZJ5iSHDElTOC>2pVxZbLKzv>z0q}xDaRKeA-H9l|7-T2?=E;;X}qcQRvid#QE+Vx*&`0+=q zTmAK;A>vcxx7fLwwnH7y-lkvm^`ya)r}HCcN9n)&>fF_^c?QbPz$rbdO_#h-_Ni6W zBWlrc=ls;X?t1+=|CiIYSifB4uSawKFPmGRSKZ>$2qO z;s{4C@L+cSWhaXx9N&3dHty6D#1Wo4e^9o>XUB>o{F?2aUH|3L;s~qG*ExG;ct3H3 zuRnOUX}b>n#1T@ga>pu-J@?pCOmfGhk)Ng*=8j>CZSL4Ma8mC({~w+kd&>WmFQ>gb z558G`I%8Zu@QHmC^MyaSK0o-N{T1`OYFFjkUUZORe$D91^DavqrkGDGFUd!BI#Mye zx7)D1-1Hd5{Mc?o^GQ1&ub9Jo(wR?jp1XIIPhNO0;YpqE&THS*F`Ox#1vNL|F6k_& zn8RJtSx_;DyQH(AVh(pnXFYzbOyh>L~+1w{e<`K+oSklmg9uexvMa59r2GP ziv@q#QEfXvzDzOO)%(b1ItLcPVL6)>!C^U@6~SRSn-#%fIhz&1VL6)>!C^U@6~SRS zn-#%fOKj5z^Y(_fmMgk#wyZEe`5iev;wxt}IBq(FDxPrMbOu#C;kfAxs(8Y2(-~Cp zgyW_&sNxC7O=nQW6ONnCpo%APB3{&Z#?APt55$AGP#=glaYu*v5l1j_CB9&CZoW(& z$Omo74|&2Sb0@enXZRwxGiUfBxHD(?BDgbW_#(J7XZRwxGiUfBxHD(?BDizO+-D6C zH|8Vr63jehzJj^SVJ#8Q!`d8IymZu1@#|+EI;wa-J@W~Ez4u*xi!L8tCVsuij|Ugm zpEFYY`r2y`D8_Agt@!oe$M-FEn{lJ~^<_QxDgM6E&EnV8TGl)`kLx&MvbMuraGHZ zW2vvH&SunD>T9aA88w#rn(AyujitV(I-5~r!~XyD%o%>dc}wbRsyoI3~3-)lhLvYG42* zHfo4$Mt!TX?x>ycTjr-~XSxSueo{N(x6Ds!C;XQAN$rH+GC!%E@LT35wG)0DoSphC z`%yE6qm~LsotK}~&QwF;@7xm>sfNPexhE`A4TZmRPgtZH3V-LGut+r&{?0vNk!mRX zoqNI})lm3*8GDUl5_^Zn9(#&n5_^_(Vh<9Iy-7IsP5BvnncBu4C!4YVYFyM#?m>tr zwUc`g;z{k~9)x&OJGloTp43k6L5L@{lY0>2N$unwgm}jJLH1)$7mmGNxPjZ2)Xr2x z6;Enss-cP}wKLUF#gp2ZYN+B#?MyXP@uYU98mf3wJ5vo+JmW0%Kjqs07S0}LGsQN} zTEcM#6OQwtVjgEU#XQb(ig}zfHFoN2sa1c;eNA;%F{i$!I;)sd zUsIh`%&D)b&MM~c?k?XRCHrxX6<)n++jPWNbvZf{My}cNzp1+~d3gH2#LLQ+ZvHJh z;ic6izvTH7^P?_bPI$t|yYlh9^bCY@%>AF{Prf^^al|44?wOV)Vv1zZ>x?_(`d#%ms)dS zsfu=Of*?5#iXd^wISepwcaP)@5+nyfksKrlh~%7ugdqrm1Q~)NL1A|9A^8bPkf0JI z2n+}cC`uAZ|GJ-D&$i$=|2f}x7)8#@b#cuzHPuzMs#dDCs&_~3DVhH#XOiRl9J0)% zE$7#)O=W&-%X%za=DoJ8$HHY!ZaLRxjbk0=T${Cnb(nK))(+NT&b3)PScf^+X6;}d z=3JY#gLRm5ZPpIfVa~N#JIcDyEqiPEt<3Y?vL4GnW&ZD$^;mu@>r1z+$KomLMYpWS z!et%lmi1UTpCOlZr(4!zJzLhJZds2dGo5LVmvd&;VRYcnvi^3P zf3gm9o{m3RhdEEjpRB{2r{ho7Vb0U>C+jfh>G+d%nDcb}$vVt=I{w5@_=~*_?WXD4?lwOEB*x&b7GI3#DRG5Eb$>u$fWPkhiKRMxQ{4%(Jo^E`SeHn zC76Cne+4tn7;o6gI$YLc?G;&v%X+N6BI|HjkF{519WLv!_KK{-Wj)qjk#)GN$J#5h z4wv;-|r zzP-zw!n0*R-({{rX59CU-ng`DeB5W1T!#Bc9Ae zaxWR})g9~jxT6f8*Z4MkSmVR+ZH;ducH)Ux2uF;BqyNT<5co-@Xg zy8IY-aNTqKz>Pd50ov2=Sq?L2PiGEQ+*!!yac3c)$DM_I9(NYxv+ zp(>p(Q7gio1^eeJoiA1C+=;q4pNUm*XCZ&aorU}vcNX$z+*!zA@S;(JpXCZ%@_W&nlgZR_V-^dOz+gI1{Gck2?#_gsJ!A&Vn;x z>ixL0;7pi$Kkh6z6Q- z{=AAi3-;$#+*z~;)y+25C5aigng`QTD)hI&toqqpT|B^ zZI3$(`8@6{3;8_mEadaJvyjhUx^eD-dCt~Zef7s>HX7Jx&OOKx zR6`i|6xFJyy;F4`)7?aMf4I29JGv_GZYH*9*@(?bOWUZtv>5J<&Pi&|%_v@WijRyX?8B@K2_^vfchWa|xe3 z^ojP#FHJ9e%M6orr~KUCrMLRyXS-h?b(io#<;-%9OV8@jFJGcNY~lgo{hnN=d)&H5 zsxA8rS+;xQbYJFfqPk)ACA*(mVDT0_`FZnq|N72p!WXUgx$eF@-66cdy_0r_efbUH zsTX>>UEq#syYL@-><`;bcA8W8rN#DW_q}Kl;qM;)m(E@@4-?LD%>5^FBK4)nQ;c16 z<=jg1K-^7ee8t^_##h`;Xne)pgvM9gO=x_@-Gs(h+)ZeFMINWI5c!(=dE{~G|B?5J zC-Onz$R&m2ZbEiOE~#fD$CS*J%ezkaU;bWCI@2I$;ch}cPv;NhEZj|~Epay?pU2&V zd>(fb@_F1%$mel4A)m+HgnS-%6Y_aFpCM=AZbJS^=P=|f+(F2<>D-3(g*yw;(^(Ta z3wIOpc{&$jP4t-+Im<`>u24F2BWK}mLjFwWW8^H{O~{{dHz9w<-GuxZcN6kw+)c=z zC1>GoLjH`q3HdYbCgjg_en`&3-GuyE{K4IXe3H%;+0Sq{As?pmNxui7y;eG(WM9PH zgk+{ORdSXt>u%&MUDn;mS^mfGD5W!Dau)6;yg%e_LO7i*le2I)p*>;TO=wRTcN5wZ z#@&SWgmE{aJz?BUXipe-6WSA|^KEh#?k2P!PUqOf3~XHXg#YGuqqx5ym*H+gxlFpJu$`l^^WXK3Quwxw+{gDj_N{Wsh=q6} zM#2$O;pjhYK1>?!)_f%FVeSW-gB0 z$M=;UyuUZsb0`5A|FmnK4gx@n_sk={?5N~E z+)e20sN_D}P3Y{X{?5N~E+)e20DBVGGUgUdW&&kpo>xJx$yNPb( zKHN=oBlqFG&TiyByw}-{+=ur%yOI0wUS~IQAKvTiM(*SLbk5CuKkl`uOD-8}nfw-O zoN%m(!m<9!&R7%mY^;^?XRPCDSKLj=pPU<&^CS6_bEBx&syH`_daa6cqo~)aI5&!V zt%`G_sMqrQzmgw&1L4>+2&Y<$@$!ziti(U!Um?;Z^49w$m*02jP9D zIK92;{)zZKje5c(S8s1$WoqFacfG6gvn%vF8+?mfd7W*69U)t5UU8TK^+gtq5*bl`&jr~*nR@-mIpSAs2{9N15#s9Va zU*b|bE{tXWR!RKs4Q==D;Rwg?rhIM>-H>1?f&&d@sP42|E_>Aypou8z+9jOwP}k0ho^#Ul>^O7Sh@GBId08jrW$pvw$vIkj)-i?0=a$0J zpY?3?TjA)>J=}XI`ooyM&A5Q>J};b}b>Hqi`;WRB_ifRm&wm)_XUAESQ`*b>uzI%m zg!fy8i?4X^Rk-+}!SBQM}ERpdY1n0 zXNk3+r4RGIr2C|64E$cC=%pX>zT}5-e)fM?pHO34)GY`z4>7+$4;wy=KX8wqp0zIc z^W8N4pLR9KjP?qLA3lupv-Sx*_LXqNOV373g(KF&5yuZ>&f$qWbo#&FgLbS%|9|0b zi*@#scrQu2_}&9|eCfLkRr+2-72lN*Px`(?mA?DnZ}Qg2iSJ4X^G(|L{z8${|E@$8 zblpp)?@(Bd?jO^4EBFR3-xSt8WBSg8?G!!i7mn{rnC|Z~z|VIjEXUt*@HcivkMByz zhWIA0aC}!nIKC?(`{TP3|FUoUMn4>Ucke&s-97q885e`!ZRvdz+}~BH@kxv?;TT`S zF}|o_DBpk4x3m8x-))K7*QVTGjF;c*NOf8KMjUmv=yF}I?vBSty;joo0lnj@AImjt z33pPB8SjSt%YI`d+mLJU5`DbX+9h52cT~n%`sPX!HDXDHV>!QZMzvaSjIr1A6A89>jZdbytc~<>Et}o3s zt_kyA zKl0!6iSbD7N7gmo-`9wFM(s*?obQjs9IJYjgn5^o-^G%gm`jCYEUR5H|5MZQk^Kfy zwjt^Ay9Tmze7tLubouwnRJSv(cYpF(R>Gb1evs!nYCn9Aq&}a{wZ{2QP3k|n&v;H| ze09?MIR3pj>N^&znOWupBKd19s z&hUK>JkEFSQvb<)#(QSTjJ>pUrFSzs@oot9Q6JgwS*7u@9-x2czIVh-A8bz)4!XD_lZEfMwerH&186WTLCtaO{$N3uq zai6X^HsMbCoqCl{%s>D1cfHcxvFj`J z?ElH{UBr7#8f)n{F*@m4&Ix&^Msr=l9B|SK+SyF7x_2GI5RZv#5+FP=cH#jGj#oV#^bC-FMB+`ucYywF#EKB z`a5qWx9a~cS;FIdf1%`${++S>J_ToM|CZkzOZITa<=;2UwvCr}J(8{u=#BS@bk-5? z8R^}VlHd8a(KuT(CSUufzmvw?z`VdbpYS-}=_t9Xe}m5Nd?_D~cfPcjj(5J)$5;bd z3&{-=9_PD4!K3rBggfbdB4hpT8EX#f4Y^^$ey@kK7tU>X-$(CZmGhkbJ5~vEK4Tuv zZT!BK>zb512S3;{<@4ZIEW!qzgC%U4%AG?O&vHIPKdO=s$Iw1z8t)J$)GZ zczF*lw<}@4qeOc>_Jw0k_%P-y$nWlX?8{ft57n-O`RxVXKWd13e)ll?c0=qE=FG(J zCvs-uXE`%r?9_~lg#DhE`ci(UFZ(lL&P;emjDF}b$g`Ydu&y=4eSG}hTC5RGoS9e` z`R{mrpES2CVZTd7d%e~R#~$Frm@^aJ!;*hutrw29M(s+NvxR^94sWb$ihIJGE%1(2 z6K4y4mh%MGO87JO+6q7Sbp3Z@vp*B&Y{5KUbEPZxhiXgg5BUuQ&K5qB--U}kq5P9{ zjraGmlP=B{_zhddG~W3Vj=jBbne+Vnb$(w=K1n>@+lwB1SH&e^?{yWI*aK_qCqLx2 zlY_HQhR1tg#U;IipT9ff-*%JC{62o{lhv;h_Fh*q)4TlSzvK10Gm!%-?nxIpzV2q2 z=f}ryAS7M6jsER8#X53x;ll6lY(wO&_%PeXZ|?E?>WouiUeVe)r>3(02%(v|y3 z!afs_%=9cd`*{7PPn_@RyFy79zpv=;^NyF_%t^X(8+|USJ{)JB!ey@Ww}+~PnY;ci z-yzC2lsVAfJj%9lF2Oe%)Svm?g^hZ@M_T>g{N7R0#koXZFMF|=Z<(w8T_o3dYyK?r zIcKWstBJ?wrRsa^+x#9JnD6)b8*ru%z8}|n|L)`bejNKM$8PX@i@onT9`-T*-Xdr0 z<^8x1yr<@O*3vgL6;tTDJ$}Mye`mAc{LM|h)9Po_`>mDV`SQ3nkNe4o#(tI~+2xI@^uk6n)W^uIC?SrV9chs_VA1^Ts>yVg`SWf&f5O!F+aSzhugQW8uRGNy|~=`gR92O@?sDF z{ot#{Y!MXyFHBFVTbi%iapc(v4^p9 z%HhvS4)))-V-FLrXZP>nJ=XY9pMK5Xf7IuH<$Krm<;*&8U0?pW?R9;OgDWpI4;#_503`0{+1 zV%N<$jmK^pr`=2# zXRL9uKi0TB)`VmJ)I8(yI5Dn9&5*ZeWT{!Nr#MCY~oXzW#9Qq zv*m_8eE1w+Z!TYYrXGEt1DoS7`Hb-BwU2CmHF9R*J7zhq+2XxfgtwURq-N(kXA_?N z=~J3b9-mYA#!F6X7Myn;;eG0FHya-}f1iH%iwpJnHyXB>FmhI0b4g+3uRp^uVe~$9 zz_P;27JKI0eYh}oPV~e;k6!Fw@8(LFb}c$ZE&T8^tM%z8-7?VUe|XnL`*O}(eeS;e z!>*XQuXnS@r|aAEz~`rIZ0Ch%f4Z^#^Y1iizg^JXUij??e z3OzrMz5JWa4{u*Y^ozO&HV@3Yu<(@^9^4Gwd_mzat#nAgUC@ucao#@vqpuAWM$X&o z&Ml1mpWoMuJ9-~KdJfUC=L_GOT^Kv3`EjqGVE;Nz57VxTXYAqi7FoAXKWnbl`uuYq zvwUC9Mkf#Sa z0(*RcJ-)ymUto_f(PMmpJ-)ymUto_f(PMmpJ-)ymUto_fu*VnJ;|uKZWjf=_{ERQK z#~0Y+3+(X)_V@yOe2E_83+(X)_V@yOe1Sc_z#d;}b$Cv4hFY`0L zz#d;8@ZdZ-OylL_I!`k0JWql> zPl7#9f;~@yJx_u?Pl7#9f;~@yJx`iGxDPp{KTqNl&y!%!lVH!2V6ST#Grk-pPNsgnFE>8+AIRkE{6 z_UrdEqg{1sZ=L*roDMwbOnyVJ=;)-)Jvm2I$^TV~%Rr9TZbN5pXF2U2#csRqtio^q z@UhWvojXMMtj#v-T>a`~!n+OqZfDpUf9=43&^mW__#X_7e*?qIGhk#O3yf_12u5e2 z513x~EAtmQ!pJG|g^^$W7e;6Kx4I|iyPcv#7@b9jFglA4VRROt$bJfQWuWtf>?euv?|Kllt7=6(@vk9L%(GH!z zojbkos&kI&+=Z^uip#*bV)xtyvn!4p-1588*KYn< z;n_FesxxrVl)_(}?t7h6fBHs6tm|p->y-b63$0WBO}Oy3l+$Up}e+2{b{i$ott{8f@uCHYm-TP1tyWM`f1 zmydh)%mv-;g};Jcbk@l~b@Cf}#RIL_Q}^V2ui_anGE!VL4(5ITC+Y{Z&3KZBC#-h+ z*5jg2^6=r+Z~xxw6UW_tdv)+lGs?!oQ_r>Ee8QjYzF&bC+UACVmp}EI@Tl)CSzSH$ zDPd&H{qh~cE5G>tivQt<#=n8#-E=%Y<9{2lWbIl{>K$_w8UzG%|B ztKV*Uv+&6m{iy1m@{sT@Yn)zP_QoHC58U)C)%o-MP56+RK3Dy0y9ruk&VT=T14W-O z`V)P0;_oCmog}}L^mdXxon&Wc{hLQf@0FdubS548yxO(S!tZw0SbkRFA>W#?Em(d4 z7an1F%Ci-A@@(>9C;7IMeBMd1=%g5RQtU?Om=^rM?E^#3e|>;{^0SK<7=6@B_Xv+V z^up0Y&fiyk=4Tg=8a?G?r-;79_Ky~xbwnR^=p3Ch-+ga5&;F);d-Sx++@yXr|7-6Q z{%ORs#P*waZa8`2o8UQQ`w2VSU3;#04qpE2<=I09=##%`59~a8;rgTDdEl2XkDhL- zjm7iql$Vreueu4IL$*J>v&B=_i07cGZyCM#7j7A#5C86-Zh7|p(eOO*%iTNIe&t#5 z%(BG(qgTIjg3<7dnECed?BX4G4w`!T&Nb6d&_UM?Z(e!R*!@4>foHZYuPe`fO+2$K z@#g5nGkld7j_mQQb!vI`F!9{*=0c;Bu7Oq8yh=PXer+K03?!Qej+y0F@!UCZSb4Uu zYaq2f^OR@%Hdo1qRnk?ZwpS?@1Igy{Y~P1fisL|PdwI4Wiz@Yjf#k#TY(J(|>N5i= z7UkJ~->6a?3xB^a4WvF$r9Sh4J$%~R59VAYKOztNxaC}V@0a$3gM0O|H)bFGao(#F zJMuEtL~;{jauzW81i1;AT!tJ6Oq*=%$Vm2U z|J0MCoXhQ1js_k6RzyDsv}{-lr5t9_&C>|uy) zqKhY<)!wg%XVU%;er!&Ap8o!DwwGs;ti<1DIlX6*^N+n^(W^aPPv(Sue(3Qm_J4pU z*=)La%ujp5hBiH0c=~!f@Ps|;+ljyLx6G5;i>|&854~}F@xwc$`l|3sr_RxN>+wy6 zub=yZ&M#hBP596opX)5}*5bnLs2SVxzi^?o<=^P9b>VHxGr~niTVx3r*?l{UPUs!@ zp`!x~KRPT29bn}1KNuQ1!0_@67#YX{BO4vyXqV|#;;)jND#@1)o-H)#0ONyXr*uHa zXXMLZe3{w{zuI1OB1afG$#2rZv(Wgro}A~fQy3ZOfR5}OuM*RG{sm4|8$a7URCu9n zhL!#KH-txh@7l6&-&UA@H22G^39tO(d~Nw(xX|ch!iBdj&s4}PGTI_bxX4!QpckFc zJ7DPOFh4rL$Uz4f`TP%t#=n8#MF$ue$O0o99bjUY=vCq`xnW<9bihxWl3wY6UU;Pg zjBk?tiXC)(nc54#{eYa>a?kvw9~i%48yJ6}4~(DC2gZN=$$$729bo9_0K<3?QJu+S zPs*E|zmzrlqq#ds_Ln`(Kk}oG?mYaT=WgTU44=3pUkMZ6@o@)1tjAt9YxB*UH*Yr@ zc%(XEjn4^h_sT}~*p+4w9(&n$>XYxDw1;Q@dA-;Ef2!f<&#~q2VE!FGFwgNk7Zecln8h zpZN9d^`Dk_p@xS)`8$|@hY!qiJP$@5a>3}trbO=~{uUf^ghRe?=oJooy6}gc!ePHK zdWt^NJH-z3W1n!5gFfLRpY~X9%iqJEE_`8Ux9Af_UePD}(Nn(9eJMOaS9{T8KcL6{ zL67|wdTX8ydm1o$?0@v&N9eT6as1&a4^^L;WoE^6_&Q&z*P45J;s4tEy!y=BCJ~gTJ8DuIPt#>YsJ$w>AAD`k}^C^h1ra=!g6}=!O`*gWWiC-qPG-EWb@_!3X*=jd_& zSG&=NoHSmrpYbL8@gIJKC+Lhj^S9s_U&0|@IP?mKJze<2PT{a$IL8ZI);s3>8ce?_ zF|E_uQKvPfjSM<)%{g_Ni)zMt%q^NDV{Xyh8FLH& z&Ya17qPaHamYT61b4!uapEFHoZZSXehUEyyoGHv4!{6ZvdzeFPr*POW9DUMs&pGgG zP7gWEnc_)v7kWIWsom&r8`UL_qL<&3Vooq-{I(k%J6&g|KdvKOZG1|nI(B8@Qh(i{og(vh1 zhdsjRvH!z<(Q_OxdVI#Jx^x4@^wbN!U0pQ!8p88F_3LV?Er$#5{hP_^Z_Y4Om_PYD zeSm+556p8s4@Mqx!SomOB|3A9`GrG{aL8}r3BAH$k8s#29QF%GyG-vCJIvoH_6Zj` zouW^;$Zv~2VgBUr=;hzx3p?AQPZ)VcpKxhc>-}@ktHduHa)d*E9qmG|aM&Y^9{V3X z_z`~EMZYhxR)1kUfKzxB7QaNhm^Xy+ zAAU^q4mkLQLymCBZ{fjz{2d(j2#1}*VZU&W7nu3F%%vI!^qUe>tx>T?XzhwMLTg&A z5nAhFjnEnxYeZfC9X{5AI@Ug6=ImG_%D?y5zB=fv1?CqHIl@Jc^ubf~c+IsvtOd4H zIMzPlXrt*~JK*=4B74yn@>%ha6$%66Q*H_%r4f+ar3+nZjYeFl|JilMjx1VqYsQf z&FcRvKXAA;Qv6TM3O!tRIA-4DU;hhX7J`r~8;BoB0jvd&s13PwL#|}*F{vC5Zu`Bt0m-ucp(@&}^hfFBE@CHlQ zH*EZd;#=&h-=1Ww@GXaps<*lS=fdUBy8K23X&?H)v>Sb3{DD3& zenKA@|Di9@)!yK5p@$sdkS`p1g~J}; zT8{L=6a8FtkFT&t;|uKZ1@`y?dweCj_E8>R&^^Au9$#ROFR;fK*y9WA@db`{DMrTh z?Tj5q=#C@UaRfV#V8;>cID#EVu;U1J91~q*&2fb8ID#EVu;U1J9Kntw*l`3$yFQWg zWZd<)sRp2p8V2>%R5PHv{ir3Nrbaal^oOWnP`{ZW`K6l9_!WL!=8^_jS%A;+dRI&9$#RO zFR;fK*y9WA@dfty0(*RcJ-!lMarF3t?(qfo_yT);fjz#!9$#ROFR;f~(6tWa?!aXl!ktxoG&oz}HF zt!qV2FTchQL1$evzkHI`HOm)0t!uVN^t7(o{sx(8U4!m*jdpomLyp%q+U0c(ySNE795Ko1a|Ra)d*^u;bN}qw^Wj!%kuEL*Q||z>XI<{2+eE z3%cV4cD%rj7ufp{u;T@Gyb`^W_*<~!1$Ml^ju+VR0y|z{#|s?oQjCmq9KqoS#n*9! z?l^)SN3i1vb{xTuBiL~SJC2DyIPQAmeQ?~BPD%er{Z{ysFz(_UvQFoa-23U?koKl? z$U2=v*6AFwPUnzyI)|*&Ib@O3KZi73^JF@Qv>eT2=^WB}MNj9Dwo~+U4ypMBeb`^< zK8J+g_cgRj=cn-a%pY9z>bw=~Gk)pxzx5pYjbnGI&75ypV zu6Yvd*nu58uww^y?7)s4*s%jUc8NYX?jm+Q|7hN}|Ct|zKRoWJ#e_fVMuby6hU!76 z#e^r-Z>WBx{9W{@8`1ob>OfqxDtf9LFusV<4$k?e$V8>TWoq- zd;7wZ2zRePxjpCX35E9@b3%K?e(!aV^WxdZw!81}j_@Np9n~)N*>{CE+T`$d^A#o# z{~A*q+)g!OV&O>^`)2#6tv@Y1)rQ|_NA5M1@M)Ls)qbI#LHL4I_iVqr@63I?;6tIHxn+w&4Cz|Uk_1+hL zS9tDQx2Rt{_yN@aH|8=AwXA$K0s=l}l1`}XC$@!sxz`IEh}V_)yvlWfD#%*;#>FaUvkf_`t1^Z zv3X=a{DN0Z?04^pXYYkiZcpF$G2vhQ>4f&#JsuVR zO3R(nE^+g7;y-Gt)7se9*PvW`xk-giacX~m%etnPj z!ZrRR8^%1lf8P(E+5a%vNnAcXV&C?n{r)We+1}fw9d_&M;y>xSz1n5(e@%8SI@5vj z1MS-Ofp4~#Px5#1Eccl`+K0}6ThD&)wy(8c7&5V9G|xTzwlAIao}Rt>#=YCkmz+rP zJ$$E~+A*v3VmHlw+p512uPa7hd%aI^;Mqz$uD97T*_s$Kz*8co}rNxh~EoPis^kZh)xxIb$O7zu_+@(En|M~Uo6%*~$uDIEf z;vtUv&%c7`8*aW^yY~spiT`KE?cP2x|6<}H?nixgWnucsvM;V8e&Trb*hc(|HhZa6H7fCJa_qtFrLXsNZ7}MH zcH=YG>d7ztWcUrWWHRqvz3$qgcg7ytj+yKWdUmQ$AK561N zXZGX8y!xdl7Zv|+ru%Mt;Is3JpLuwlgBKD%^CbO&XPH;8TcRg(+IPOwzVg;QqBHkC z_{9Z;fAZux?ThCPZ5P~X+Qw@K*lRu5YdzR&J=kkK*lRu5YdzR&J=kkKn0T?)iymt| z*lRu5YdzR&J=kkK*lWG$vDSmV)`Pv)_vvM=G(T%7*lWG$vDSmV)`Pv)gT2;+z1D+i z7i+!fvDSmV)`Pv)gT2;+z1D-h)`Pv)gT2;+9k0BX`!IGK2ls3r&plg?V?VxSj}0Ci zcPq*dAJ=jBjn#%U&Q-7a{fv!sr5AoPL*pFkMJ}UtGtN`q@0wE{g^A70FcX-x06g@H@`}JD-Bb`3}!IPl3mI7T7ry{LXjacWwf9 zt^vRECitE2z~dYQ?EC^A=Q}*>916Pg9Y0GBVqN4K@HpS$S?63}=T??OzQeQ5N3558 z2Y%;YewN${9_Kqe>)gb;$hn|92Z8Q z!F74K{O~_rm-o1)t>1Y2jP5Pde7@cKj4{F|t-5-<{}MkHUS^TK+Ud8vM|j6CoYX#X z_ankTo9Mgk%yYjWJi+EaX!ra5Tf+DLVs!hJJ11?Bxx;I>w^OY+z3^e*E;W7Ad|vqL z``*>={rG%+`sX)Uvd_QrLbWh*_MU1LVdS5BsJMHOaf9E&tVtzBSx>C);p}%J%I3$nKTxykO*aD%=05 zDX**CuG`KVUAeu`?FabnALQ6?$hSYyYd>R;{g0iF3-;%D4PRn(y}(wz*gY{@D}2Jx zHQIY0zE$`ePw(9xvgBRD6CHALyYw>;314=>h3)WTe=mIHO4qcHegAL5+q~MgGi)(w zgUspH{aJg`Eb?ZV4#x>tL_JogAcy!A=#_1}3!c=3h5 z+y3ya=Y;?F&!O*QY#@VFchg@@S=pXXpY-+0cK+pv^DEo`qlvCp|D;{ZkL*-# zFLe6>e)|VG_8ao;PxRW)*kk`=r{jYCr>1!2{>d05rXGV}k3q1@f)T7zBF^ zf;|So9)qSc2F=eH1bYmEJqE!ZgJ6$Au*V=6`?r5`y=I|(UR9qQJEVutoN|Ts(3{s0 z{h(LA+V1%B8p7o__1m>>Sy}k5i%)C6vDFCS{dT&bJ^hVkgs=Ip%iG27TvYg}9j<9# zn|fa1D`vbwb0)g3`u>mG6Q-T9PhWqNDf;{`%{P%Sa%Mc@^%{QU@7R4o7`=;a`=l`T zygTM0VeDLH`Ui!vf2l+67p6~|{;Q#{bj<&$Ew1cX&b?zc=ve-`xBO(Z_3rZ6BExOZ zB-^wDwsWf6W~prd7w2C=eG)sra?3iE+Y8-(fZzT>j{Syw`xCwPGxpg3*y*@ne~#DI z7p>VWcKREN-OxX;A$;zS>-OQNRuf)fhb`J~9=)>g+e_}>&h_ROgm*muxOU~u2ZV<{ zaz=Z~!%GQ2@Y?z9g_kZYeA-o)wEO;TsPF`ec~eShni|G+)k zj^&g-(6RhmPoK48y|?Xr~RP7xC49Kfj#a_ zr$3vYeh&7y1AE+oJ?_9BcVLe@u*V(P;|}a`2lluFd)$FN?!X>*V2?Yn#~s+?4(xGf zI^)j#j61N$9oXXz>~RP7xC49Kfj#cPv@4H6k4?vpdBCv)J9c2l4(!;09XqgN2X^eh zj-BbAi{SSh<=DaF*nu58uww^y?7)s4*s%jUc3{U2?AU=FJFsI1cI?289oVr0J9egz z?>RH)3(g}3^SfSN`Ekte2ItBDtaE zFHkV_nOB*j&%f4G6A2^doDr|r@F4&0U0x7I?~4;ZDU3Z&Z~l-lcCIz*0b%SfziBGW zSTp_CkN&x1{#AZ{MaOcA4?32A(f-$sw%&8E*m$_@S#IcU1Ge)|PtR7_{!8~*S$Q0G z7CDvM3*CNz-~K_4{f2z|6TS8`_SpZ}>9}Bjj#oZE`Pzz`HA^3`kK*`Jy-9QN<$DVs zchE-7BFF6|yx*`dHScV_r||H@H)!^pVh`bC_FTW2X6s#rKdI+1KA-udotu4BabIQA zP1S!^IQZGlm78y@{xj=3&v$0{-j~#WE*SlX&f8mWsQ&Zi!(Z%daqar*KNCFpa%bX; zHqx^P?|4S%o=ewLU;5Q%f9~8idPB+C>d)tNHk)Y!$vODO3p&$2y`JREH}JjAbZdN3 za;ALhvd(QwtS>naT{cbU{?*r&oW<`N)%ot8UzD8F9+q~BYZPzs==Z;0z?VNSt8j|yaRqng#@ikVLoE48< zeDsOyt|mF(S^jII=bB(u$=Pk@vqm3v>q?Sy>5^jy>cv-)oKq&eYV>patSC7@zx3LH z4L4dra&El$n1MYHUtV%%z4MC$SMB@-$$9;eH-=BYKqWZ~Jhwsh)y@dXnP-PnhHo&3++XVO2eQ|-RVVv;k<7E4!m9x1?H2ShX+ot>c{4loSFAMs#^Ktc_rr;H+`eJW|Mg(=bArlu6d6+ zXVm^zR2$7dujD*D@0y}B|Gd2Rxx&mp_pN`TF!N76-QmK_Kc~I4Lv`bM)A#Ku^R?uB z{ppRXGhQooAVm)LtX#eYi5%>y51gTI&wY2y(6{IP{XgCJ&q8m^(6{I91t#nJ=l$Cz z>-%TeQj_=nGyR>D_x3^0S`p>Mx|5D>0`p;!MzFOlS`p>7v zJ|;Qz=jHBrt!A#K|2+8ilafP!UipfrC5Qg}+=XK$hyL8DelI!n=K~(SPjVPv$2|VL z$VdflN`p^>wmvPav1MJwtGTy7+(k6d6(oc z-q)V)my*MHf8v|>OAh1xu`7QiIgIyxPP$EUm~*zg>Nk?Zcpr7_&m@QW=aIktTymIy zCOPzO$zlFk|bKh1gwYKMw#a3+XpIdg`qi@fUy;f-L zpZhP{wY7h4S#jsq{(14R9b5b7n~QGWI$ocuPH63)9d6pLb-Ydg9C zMUQSBuSX6zvUUIY<1XK69k2OzKB9I1x%z=~TKAu$PaoO3|J?r4nXUWJ@G+;i?$3{| zcxCJU^ZhS>yLEq_a>2`6_viBtytH+H{@YO(x9-nF|9D~R@%6Q}f6}@?Z@R{JTaT~V z?!K<|_*(YAu4z5K-a7FIt;g5r&%3hqc>lwKx3nH#zqoBw`*w`?uWjA79`C0QxvBMd zpWx~rw;t~kee1f`^Up5l{8#Joe#8MkYCZofbHS~x=buRy8Pj_HdE~NA>-p!bb#ByI zH}l37yWP=x{`uC@KNg*Nqw|&9g_$>AedcCi#``Zf>VoAUf>_E7x>5P1^)4Rfq%Sy5ihS7_{ZxP@$&jb zyu5x9FRx$3%j+rq$LkmI@_I`D@p?-C@p?-C@p?-C@%m1G_IgVH@%m1G_WDkL_WDkL z_WDkL_I`u$<@KHZ?EMDg%li$+m-ictFYh-PU*7*P-o4*oe0l%Fc=!H?@$UT(63cL%;x7`*H0-7$R}?|R~#xnbRj zbLJ+UGdHP@s7ZB1O{ybmQXNr~>WG?DN7SS`q9)Z5i5~Si;*Yu=$%%R%$&Wf8>5cjy z*%Ng^vNP(1WPj8Vsa>Y0I-(}k5jClfs7ZB1O*&_8QXNr~>WG?DN7SS`BGIFcNc>Sp zBsoz>B>7QCB)w5bBzvNcNOn3dsg6kPin^5l1;=?&lg^8pbY9e?^PSN3+#BA9`z^vctKC~C;fOqPxUALctKC~ zC$c}zoO|u+)!PWinV4{#Wi_d$s7WYQUOQ z1J>5bYg*%LKgveR+F{!cjBVQow)epPF!-Lo=5Vd&PRHq{zvviU6AaIdLh{# zbwp~H>FG|qNq6E+x)X2Gop_V(#G7;{-lRM6Cf$iQ=}uhqxDywD)DcNe)DcO3)DcN< z)Dg*^s3Ve{j*IIV%ALE~6?@D71;;+KN&Czu)f6?Url?6ZMNO(HYEn&6lWK~ZR8!QX znj+DoR!96%!y`FS+avi=^CP`c3nY7@Mo4x>?U3w`nj*E)^i)&Sq?#i7gKLVKR8!QX zeP)wtikehY)TElC;{Se4k?2uVB>t!=lANe1lKiMClHRB(l08vVBs(1!?2r3#wJYj~ z`s1$DtMtbm*y9fDaR>Ie1AE+oJ?_9BcVLe@)1!{4KklHr76t5D6tHViz^+9ByA}oP zS`;w*XT}}a;|}a`2lluFd)$FN?!X>*V2?Yn#~s+?&h)4w>W@34eSGEJ$Y;IIIbFts`S`~_ACI~e#WCtt znp8*Bq&lJ|)e$wRj;Kj>L`|wAYEm6hlj?|?R7WIw)aQsl>UJb2>UktT>U^X(>VITU z)CI}Ts27s`QAeb9nV#y1np8(r_PYH#q9)Z5HK~rMNp(a`sv~Mr9T9R|M~_h-6RH5y?)+CDjqBUHQx;>PbY8IwIkyBNC1}BH^eb5{^0|;ZN#$ zMfR1?F+K_BOCMF-;|{Cg4lC}hnsjf~qTg5$E!#!HuVKv-g#XVY+?$Mfb zkJhAnw1#`MxYujA*Nc0!hI_QQ*K5+fUX$+insl$%aIY8lj1BjUaj(~KuNU`>O}b}n z(mi97?im~I8ROow;odXu85`~y0Y==_reYL!f{XCa8Dig!VUMraZlZ( zd+H|LQ#a|Jx=Huu4fp18Pu-+@^CsP!H|gHIN%!Ur_vUerFMHU-lscJ)d-J%*mpyTh zFMHx1U-ra3zU+y*0{JKI@nuic705qPS0MjHU4i@)bp`TI)Hx_#QCA@UM4f};6?G1Z zSJXKuUQy?uctzcX`cKq3C|*%_q5czf7wSJzccK0hbrd#RJqW&CpAnMOim!k0%bs*}`QJ13e6?G{ZUs0E$@fCF`8edT-qwyYfDH>lRmZ4Y%#QAZ@Y?MZb_O{!~ZQe9I+U6cJoot5pOuF3vMbyiKPvuaYE zRYRSX<3-(<{X?CVd+i7>b~56QXN{8>d=~0ht^Ps=Kf4w zocj-TXztIcF0M&+aZRd=Yp9F!_@YkF{h7KrkFQjx*Q7eVCe`UR)aiM=Q&;KnMV+3< zJ9U*F@6=U#yi-@{@lIW(=O5}SJ>IFS^!$_R7@Jhb*icvL`6ty?Hq=#m{z-L}O{%MG zQe9<}>M9%RDm_1AkLN?`Dm_1^I#1aXbwsi!>WCWb@p^%OJU?TP*Naql+N8SECe@ub z_{ZxP@$!0sf4qLBI#|Uk>WCDts3TImyq?m3ynYccucxUlSN$jIh}3_gj!6B->pT6~ z>nZ)m>wBsbR)3Bli=N2KxYJs9(k_dkqx@5fSIx8|RyBhvg6bwrwfya!{>$?qNbeT0u?;m|^^7MSi z>ifIFdsWr%eJt-)%QuFad+)iY?R}4E!Dg)={i3~cg;P4vU*G%IcIVGd)q=0y>RSC~ zGWf1%&Tr4U^hnY9lfU=mtkc2=<~g1RBM-UY@(qf4&=>T|^uk}8zx+0HZ8=4LZTaQT z+Iq{s*ZhVva>{eH?JV+Y+h6pQZ!jKt2|Pis5`PU2Il>`dIP?mKJ;Gt9aM6SP!qG0% zX|MV5gE01@553_xVcLhjum?X2;}7&fFY<_s?03ADSZBUw$ntk6cF(Lhf3wrmcL_tE zruk{R(e=l7z`Lx~X@CBmPq*OF*Id;OS$;L)vz|D+-RSZ1eS$*gPyP<(-{AxE9M6lV z$U`oe{(|nHSEd*K+WbXMZ8=4LZTaQT+Iq{s*S4oTSKH1aueSX~kK%}~pjY7FufZWl zIOGe5Ug5AuIPC24Tz@?F3rD+5r@iLK55nP}9#7A2!n6;4VGn*5#vkYl`-zL}|7Woy zj$7SxXS>;pCw0I}Uv_i5`khm>;MuOfrrqi3wS>1WXFQ{KIzpH~`FpPqtkuE?<~g1R zBM-S?+DKmsdS!ayugzcd)Rt4^*Op)YtgW~Fdu@BlbG7X(@@m^(^wj7>SI{eP@Ympw zBOLODL$7eyBOG=L7d_Z7%os#pw2StdA3q3VFZ$pKzX{Vm^o2e6Sr~ty4|j--JD9!V`WLJ^U~1IkP9{A8VZF&or+Nu6Mn4R%?x8hkqP9uww^y?1KI;S?`Kn z{q+u9=4P#N;Fx0>Z~Zk69CNbhtU3H0dd%U%tT{Xnoizu!VCF66=%8zj1IOASdaNlu zo>=4Hi8V-cuW`^>L(m6iZ9yN{Yh0pNiN6MWjRS{#(Y?k&4|_xpJ9|8_#=#TqGF@vN z^zeh|;h!E)tZ|`NYaF=PqcslfH4Yqck^Nrd@)(@u;kEmF73hQW=aHV@*y{=xKYlFd z&m22&tce|Ptd%X8y#s44IM!C-SaXGAEf!|)!1M5XuL7p8vR4VZ_A21m16YpsD$rxk zAiDP|(7jgyvll=gm^}jez}~AQdX@NVu=grp?^VE|S3K+;;Da7^3VW{t-Fp>qwAcLF zt3VI`h#r0u_Fe^^@U!UNt3dZ&h4JVyn8v2&oWVKsY|nM%DZ(FzIkTL3DUTywJN0$h4jPUl`&(Yp}%OoxQ{K?L9f8UFC21&Lw*fU=oJoo zgu_nZq6hnhqg|%cUi0Gz;qZ@e_)VDhp%1;Z8+~CX{ueIth>P+#$BX~DJR5$tor)Lqe-ezi4 zJB}&t9dO7Ob{wHQjy*Yp;|@PKj$p?z`RD(7+<9FizRm@}Ue~~}M{U8*1;EY)z|IB0 zu?H5va{=h|PxR^8-d z#qmSi-%N0p@I_yktsQ$*4}a^a&$QQV*28+|~yy7#_-*V+!O!Q~I-^w?gzqs3 z_q%)(RG9C6mv4gh=;gcO<(r_weD}M26I7V*e$O`Kd||#>TD}b_Jhptxw0z^Uhs*bn z%Qr!LxO_v>biUJW{*oL1Lr(clyXEtpcI)Lk?Y4*SwA)U;({B6ucB|VZ`mskyFZ|`( zsKUr8-)`*Di~RB}RbjplU%ufgj6LPstHRh>zP~Qacjn7CTzj~*t9-+?hf8}+#}DSm zKbC{vET8YFTQ7dLJ^0^tDlTFFe> zEyH@x^6h%Jmv7hG&L>9A)J`{T@7ZIYpP=3PsPiOe^2z?*Dc>ZM4Sc)ae&E~n*vWXm zf9;9ehi^Sc{P%qBubsUYJ6rTCk9faRzJ(^+_;x*hU`|-@sY%xn^^bT;a(I^S*wcsA#_M11+<*6ReL0it(|dOBw;u0YyUih@qqlq; zPyExZ@^W9!g5}w@?> zm+w=GpK*tLo@Ja~`clug>%X;lyWRG;NkI&&@T$k@(3h(>QBJB)gcM}iav?q4h z&o}MyGkukLl2}9M+x3puZ_Bsq@h3dYt0$d#fG~4!`NpUCnJ0-mdii#}Q+#<=dj-XP%@#@GSG{+EexV>hqJX)*d_85u!8qmhY7c54&gicJc>~ zsQF&A*AB4Pda&1eu-AIgW32~!tp|Ip2Yamtd#x8P@nWqPjJ}UtGtN{Gq@jo$go&t6bLcE;sKzBX@cHRMx^BrR9ya~GV z9r&G_KzF_azjG_F^C@_o@9?a16L_3wft^Fa<9vi?o$o+*-T~eD4$nG=g2(v?*m(#1 z&UfHr0ad;FVCPWqJKurdxe3_0 z2K>&O;CH?Q4|xPR2-x`rJkED`);Sb(=R1Cu9K^cFHQ;f+!?Vu0z|O5KhkS=;osU>A z`40Tfzx*t@6+F&&c-Fazb&+#HcMbyG`4rDO-+{+@2XyB<@H>Zs$N31@c?bN?ci?w! z1>N}${LV+9JKurdc^26D6g0y_<56!aC^ar&$+DH3!eDs<Y(_S!gXfGJ~v=@wC+AIEI5A6kGC+!7eKkWs(y#({8ROa*>~;XhnHG@#H*K%6n%=NR~j+FIcEtkeAg-?_FU&o;pv}U zZNw(`oG!e>o@$txB z;ddP)jNVa)94(AJH|%wkFm|4B)se#3zt~beOuN>fyob-8V#z-J=ED~4^Z#nH#~L8^OqDjskmb1bc1-du{}KZUlR71bc1- zdu{}KZUj4aV9$+U&y8TujbP7>V9$-FGdG%_xe@HS5$w4U?70!_xe@HS5$w4UoZ~gq zk5?Y?xf2eP{8O)38@Iyc4r1QiBzwzdyH|+CdnS*`cX!+{n+y@*x_BQSV zVD|yA`+(`h-TcPH{ga-Le3JID9>2u#!+qeNjcbqn569hf<_F6Je^@4SOV(w6&pH1e zdv6(J)e*h@LeSs@CqV+if;-Ha#@*cl0R{-}?gVETV6eeu(BLk^oQA<&lOQ2j2u>6T z7Q*dk^?CN~`QPGJy|?OCy&v9hzv^1OdaZtX_uhSW?>-+IV=Vul^Uwd=`23$f-L?>e zTbE;={#h4$4r?^{H^}T?iU!x+_AbcmofCd~CyvkTsS}RKAKz#8+6mX3p4eyh;0aIs zF}cs|%@fXgD2>nT*%Qu_JhRX2QSucI(x zFnb_{5u4c?DU6uSo=IWkV)jxBBS*8xQW&|Ly_dr16SF5%7=2~-Y6_zd&F??L|EF*N z|LmL37dEKKC|ym*u1;#NND%2{Lm5t~IN{tgOh(qHQSFzU#Ym(-n?J%nSD@V zZ{DN%%swUIANHsAnSD)CcW9kVzV($tr0)E$a{3a7e=RoVU53x>gA%^IDw8i)WEZh9 zzyEvjr`wRjxBG~#Yu*of`I`3&UYw6seC|t|s;ktk(6N-y>_ZbazyJHp9x92!yqEO) z!MxXyIHC2+_r-l?ADYBKS1lH-HZ6lJ~Xj8p4;bJ zaiF)r=3R-;?A;Z6v}N`>O1XLG;v4x{gp}`zD(7pzGfe85 z_cA`SUsr6PquEC)<>vj4?*~0c?9F>0pV^lyHqhPdI~B$_G5b`-9y*$Rq+)O0ANdk* zn=G~Uh?A^8g z%{VdpRK=%xN9OCd%$8Sana}s;-+5Bkyhrny{kmd<>kf6H7wn&mTr7Ufdpe)lmn$~7 zPR%}HVO-Z{U#{5Wx`Q9+g}TG*+Wx_HYW4|>eV4`we0Q$ee!z8Y_Unp0t~>ZgU0kPT zpRo8G+$fRn!9TWL^DZ(7eGVI3*Ji)2aKrjZd^2;+6aVJ@W)QSP{N}x95c(No74syt zM!9)^8brO!dsXRA*kE2Y`?|#*bFbNpEB2Ttp*z|&?`ngn7v@#7uUqWbmij5^+T*EW zk9pYa(G`2llNb-Ei+R=T>lT~+Q+^4WJ#ea&W9~J3bcJ)h|2-)6vCwGj;o-dl%zHhU z_j)kz^->(3I;YlykiUd#+7T&h-xL zxwZmxJp~)CcTksW6WDN_1?CzGHe8ROF4sFK=eh&sT<@SR*HEzGdIZdM2kg1tfj!q# zDCc?y_FS8woa-IfbDag|dI~mN@1QQ%Ca~c;3(PeXY`7jlU9NXf&UFXMx!yrtuAyMV z^$3{j4%ln7N9y#pJrLBL#Jz=rD`)a4oq z5w?r<4(z%9VqL7QV8ite>T+$uwy@?xIoBX4=Xwftx!!>d*BvP5dI$DgL&1jY5%C#V zcfg+O9oTbig>tTUV9)gk%DLWwJ=a-auBTwb^$zNCZ2}vvvrx`82+FyhLS3$RV8e9> z%DLWwJ=ajM;d%tjbqDOZ-hn;pVr_+Tu6JP1wF%0(-hn;WSzxZGV8ite>T+!Y8?Lj! zTtmTz>k-uDdI#lPcc7f>9n|F-3N~DifVl>NJ=Z(1=Xwg|T<^f1>lBo8y#sr$v%p+W z!G`M{lyhwb=DNwfckrHq-|)fz=e|5w`r-fUeYsT1O?vdKwaT0s5nTMrCVjibcf!;4 zW*zsf0)IW33B z*{yR=vp&h@|H>3&05b+KV*oP-Fk=8S1~6j)GX^kY0I#aBLASfQTyp7?V1r)&EK>ON z+x7ZU+Lglp<=mjh6<;NMZNvusSGCo`yW(xsA5~u?9KLg-&QQSi8`<>_rhhQ~gXtek z|6uwDU-~&pXX;?vdUay0+7i^AX*FTv4!SoNNe=z-n=^vbH;sM=b!xCw$W84_sWAkF+Wes9cwp`r{b`%|!oB?mboUnXVzKKVO#fi|2h%^8{=xJw_S2$uc$OLB z-yHLy#}u0`oT>Ug-8p2M@Xfwa`oZ=vVgJ~@`e0tmg~sgByN*wl@=|?w>yTNN^R?Nf zgF-Ejuf0`#@t1A>w;Mq%(`ICKd4JaIj=i# zvT=KL*t<0fytm9At#_{#rVZ-S222~UJI{Q2c%zP*Y_ElGpKjKt3P!}z6!xyZtc!M8 z7tFd~&Y7s&`>&1qb#FTtmHvLCzEU^#yaXF}j$&Q-VO=omf{nf6{AT7Q#d*)nSBmqY zna338Ni)AG&Yx!9Q=C^#E{gLl+4T>me=z-n=^sr0VEP9e?G*1RW}a8P*O>WV@g8LE z3ySw9bH7l$XPNtm;=Rn=Uli|g=DwqN?=$x!#e1UZH^qA;*^L3r7{H7H%oxCo0n8Y{ zi~-CTz>ERh`^83;iD3}(z=#tdf6V8#q)%wWb0X3Sv53}(z=#tdf6;5^r( z)#C&9+RQr5uTIRg_pgx5T0I$Q?`!!+YxQ!ZoqwYDYL#^AGU=abN40vi#Lh+4R%=yo zi@nbtZK2huJ@)>a@fW{3xW(R=`&99(>ND;AI_dam6}OqakEdI+Ppy1qdD7M>b$)=o z?~~m)!Hg5kIKhk)%s9b}6U;clj1$Z_!Hg5kIKhk)?DpG-bf*pM-Rm?s{~nd^fSseZ ze6v^mp42k)#e79}>w;Mq%(`Iry7;y0Mpfvd)v?yq4QkDgRy)o=@K1K@f>{^Lx?p!c zH1nk59BbxJ#krSr0{oNRx?t7?vo5&FU)xkrk5MwNlH}R0h7=zmd?{?ZTAps0@XBmE z)b}}t2!DQkhq~W&knrB9o$A%g0m8?3?ovsv_K(G`e=z-n=^sr0VEPBsKlr5oxXSWl zbMe1&>j@QqX$xUJ^Q5}IwWaW+R;SdJgkK3KO?X;On%7!5S@>xczvb7$IbNJr#VfQE zK3nXJN?I{QcvAH<>UO=3vDj@F%yz+S7tD6SY!}RS!E6`IcEMeTYE`j{ji;r#uAi5) zaYmKhuU5CP@lXDKzq-4mmBe;_`T>_*z+-xf4m3tmhzFU@S4L+*sm9jRE2OU!b?!;y{HZWrYGd3_|12Z--V*@ibFk=HV zHZWrYGdA$4?K{-7LlY$aq^WkOI0-Fhp1NJdD?VPz@8#aE*47&*y!zfY^|H-a;gct} zsmkAcEBxZZHkF{~m{{!k2h%^8{=xJQrhhQ~gE4;2jknLzmkOUzH<#FF>8~H1R_`|3 zXX$){POJV~XG#nMuANeE7S0mhoZ*!EtMhE(`lU{)X{qN3@AjQg@n&0oRp_|d@X+$6 z498T)RQCS3@7)nqII-n)j}EK67p=|AJBQTF9+sE?eo$4qVf|;#a8T9A6Pw-m!Hgfw z_`!@H%=p2KAI$i{j33PS!Hgfw_`!@H%=p2KAMD2Ojt#PF19s=PWB0eIFyCnD+kdZb zQ(Y6p9uJs5IZoWVVAch*F4)!mLvsjiVDDb`gXtek|6uwDe`rqNJPez^>K#`TLz~Om zq~802s@$=b!cQjFQ@h8s5Ptf+zAE=` zGvQs?8>;UrHI2n?yI{5pX1idv3ue1uwhLyvV73cxS2Mr5Q@w$-yXRGY^>6t`!iQcI zP*2h|5&kr&kUFJpY}0gMb-O@wDX%lAsJhqE=2E0(aTTm=j`3TSR5>qNKHt5xx{=!U z1KDjC%yz+S7tD6SY!}RS!E6`IcEQI^HdKW(+4v7_Xr#U?Y4h@xYplALu=x%f*;w_@ zQBQJt(7Cb7le~^_ivJp^gdf!sUR0@(s-2>SaNVGWYGJu*!rwosuQn~M5{un-!E6`I zcEM~H%yz+S7tD6SY!_U5$fs)J;MX$F*B8yK;@|yOxNoUUs%Nt}5>K&d8P$e19|?C2 z%BV&TjW1lYLPiy_D53D$r5V+jU5R6{>mN-2VEPBsKbZc(^bgK`tBbn5a+kzb=14a+ z^ZpLu>!W+9^mDffUryLd_1(W&xJv!rD*nI?!q*z~Q5nvy6;7F;uWEE>rEv4keN~nd z%Y;h~?5pA}Srm)icEM~H%yz+S7tD6SY!}RS!E6^iym()ABj zm1XP{;q|JwYPn#7@TuQ=s$^-$3U_bbL&eQ7O8D;y-PG$ZhYI(c*hPIcX`pba&flo& z)%pvEmhPy2AKXv)(?lUEQx03c;$BdP!Al+s-zipE-B|Wcxa62%wmA+=@{4cBc)W8<8=YQNo-FpG+ z!Vl|$Sr^RvIO_g#DM&TByixl3z@ge|?|}&64~>7;g&)=hvo6@3S1;Gds!sm=m-sB) zExSt9?UC^4GoP#LZEg#H=y`*F;FEs9^aG|Juz4obTyL87pyoQ%tP?fYr)K@Axo$P< zO3n4GS#N5tbIm$bbNy@9r<&_x^9-iBUM9Qkg4r&Z?Sk1ZnC*huE|~3t*)G^TH)^gW z%{oqVjcL|*nrlz9?$cb8n)RUOTGgx*HP^6a{iwONHS0>vHLqE3YOaONI#hFwY}Tim zYiIKethuHpyRm^88^6+EbCp0R7~`3Vo{5+m&z{Ke}-x=|v#HoqI^ zh)&bla+r!t*gn3QDC)uqFW?eArg5CMStOqsLjPPUDi5hE3Fy||m-MV1b1+y-= zcHTq!#Bbkf)J^%>VSTZi<&Se5(c4p7&RG1YzV_=FvAIzFm>zM@^7udGL3*UZvS~saXL3o!LlM7o; z6h@!7?>Q+JyD@_qGng@h88etMgBdfJF@qU1m@$JHGng@h88etMgAsGayWtWu?icYM z&lJY}qW9xj!nj`~yg6GK_lu+Z=Lq9|k!8|cVcai1Efyh+`^BVa%h38wws}%ccH0HB zT`=1Pvt2OT1+!f++Xb^-aM#Yq^x);T-N@EQb&@xhmsdNYkK~#!@dOn-th?o~+#;j7 zPyK0aj-))O3x`|&GjojYmLN8}{=xJQrhhQ~gXtek|KRMicI#JTZ2!-T+NFQIFhgRi z5O5{ z_4#9ygjz9fVEO^m517{i=RjN|DCf8ZU%YZm zf7H*GudaDqe_1`Y4eHVcOdE;qf6PU^#(BNNKj$m3I}SfI=4k`_jR$&YU%8qxuEG*^ z*SW4#7p^s{tA6ukHQ{;Py6AURs|Y`x-&v(V9bxc{|Det@JsuN2K7i!c^2k$Q_eD`U0eYIo>;a?B;)XiVnb=J0%z4iAg zED!plul{#*QL*WtYk+=KKQ_C$fSC)Jxqz7qn7M$N3z)fpnG2Y?fSC)Jxqz7qn7M$N z3z)fpW9AL_av8RFr0zb#=5_GYXdM&B=3eRc7~SQXW#6%H^@=#QuZqqbs~7dMeR#+> zPA|!1`?kx$ak|MrWu&j>WgV|Sdle*nrNMaJG_}>}`)1?y{^I4OJfz5YeXT)7;VC!A z={l_{$6_~5FyjO>PB7yHGfpt$1T#)B;{-EKFyjO>PB7yXZaYpVDrv{(*q3AVpLJ?T z%)L5{)sxHG-v&pm{Z@bdw6>I&IypvfX;D|W^wQD#bbtH1;>X{P)SXJ!m-2(PhU;_l zEdQHysQzNU<%k~#>5io=7uq{O_ZVpFt~%UL-)m)klHJ(Aj1A1#z>E#d*uabp%-Fz; z4b0fUj1A1#z#&fmte7xPFE3YBa!kB+oPJ)*UdtcSnswoab-}C)<~8Ut<|~e8l#@~J z&NJ*Ql#^jk8}N69&-wRUcqwc7bBize@8A7L`1I#j{Ef8b;)}2Qvwv-Eo<6$e4?Xxw zYzjZV>woj}8{zSz9{9gmZh!M3yZ*uS52k-G{e$TrO#k3y59at|VzNlzHs~1c-#y)O z{PaTKL;RcCClhY{>u~>z`bmUm4j$v5(<`y? ztNG*n_f97i9#L+RzteyO!Zqql^*8DlU%2zi8UD6s_z-U`f%fb z_&QY)t7Ebe@$}nrR^N{ce57Awwz?mh9!IaAAmP zU|el!_@_7C$ZlR><^^V6VCDs8USQ@0W?o?C1!i7g<^^V6VCDs8USQ@0W?o?CCG6NX3M|`3EP9EB(pq7xM<$tqW#dFzbTd`6PUFl)vpxJ10z8waTAzg!TWS z@z1*O!@6MB1yc*e=FSOZ*9IJ%bfubnwp}pni$0B18P>EFK5}Kb>i4R(aG}e~RNQMV zgfsrJRORX1SU4o#QuVd@uT#|hBXo)SE2wHLcKw6tA58yX`UlfLnEt^_Muw_O@m}sj zTi^aPMJ4Z;3I9_Z{4ivSs@XJ1`0LD5l)qIQ;S}+vsH;222!EGliaNY!mT*YdDe6Um zRk7Ih52k-G{e$TrO#fi|2R91cuR5kqFa0pN_yLu)#b?6Jq7SHYU*{C=k~K#C{_;!V z2CZV$fEUGt=l6_JJHPM=A8j6^S~aRH+&)u`%2vC!@UtBURQwx_gkR=6pk`ie8H?Q* zz>ERR7{H7H%oxCo0n8Y{i~-CTz{?tG)#y-viJ{&}zj}3HxbRo${OZY=Z-s+`qt&eG zmN-2VEPBsKbZc(^banbJXBqaNb1L! zN%nk-`m$?U;r&TMRbG`vczuIV)$&p<;q!+>RjS7Yh3~bSs*2VuDcm<_n0gT9v*ih< zsl3T63ZIQTU8Vl4s_?6nGt|2i)rGg^4Oby?Y6`!sJX5uesv*3i1OqV=9_{@23o_h55iSUQ+S*!~`tScO- z3!af|rcU3rt@jMSCFO03&e41Ru-u{Y zT)n>3Z7J{5CPIhSi_LD#V8#q)%wWb0X3Sv53}(z=#tdf6V8#q)%wWb0X3XH!i5Gb> zcSyNdA1G_%FO+JD{`IZRF@5}{`r8Q0Deo=S8IxI_xM`Wr*v|IPxE9Ox(Fogzr|vA* znRnT~eO5J6Z;P>gPIlXscmnN$*)Evvg4r&Z?Sk1ZnC*hoTwbNu?LIBK_y(=g_qLuA zZufMhUcCRLaQ)zwdgT2R!oPM~p~n=m{9t6Hj#_kF%6}QYT$e0n`9=3-`o{BPQog+D zQr+R6<=GXM=#ufRO}`S0_234U*OXbLQ=hP$t;s^Yv$OSIXxak(>Ps6#gGclA@MJbN zvKv2`@q-yZnDK)dKbY}@89$iugBd@V@q-yZnDK)dKbY}@M~`2nV+z=7a9q*VdSG39 zZ7$orTGwmxgY;FhRBLpr8s7_7^sUjwie3^^Lj;9eiiHuKGn` ze1H11`j5i+E_LD*t0&36;J=tmD?vFjg9|6uwD(?6L0!SoNt z@9lkxWt0BFd!i{_vkK$=(e`Fpgz;W!SDep;@xCcRpUlE|4>fsnMq#|4YI!`pFy32z zdn~OmeoNoD_mf!cwhLyvV73cpyI{5pX1idv3ue1uwAz3MT zN_N`?vt2OT1+!f++Xb^-Fxv&QUGR{2+w|@^d89uh%5T$pRX*VktGDTC3-b$?Ew){! z>snB_`!Cyd&G?0dJ8j#c`?oJ5d~m@|J#uhS;r?@X>3rpj3IDcax30Xya-EHP^wA5k z*^L3r7{H7H%oxCo0n8Y{i~-CTz>EQ$G}S)6a;uHuV4i5bub<`CrTn_sRU3c#5?Y7c zvw2m^ykBRJwE4cgvtNg%EhKsEo^U{)tW_WuyZ*uS52k-G{e$TrO#k5e4|nL_v+R(u z@#N?2I^?b8q&K(e4&!!7dEdXc>hKMFgj;3bs%v)IC)}*(7M*6P7S3^Vvrb>(U@Uh1 zgXtek|6uwD(?6L0!7myf(AC!4cC$?1uWMJg@vL2|b;F@MrQK<({W@c_?ZPW&MC&rY zZxwFbYoA_F$8x7yQ9Ape*zEcT(?6L0!SoNNe=z-nUH@+1l3g3HJ5D|{ZfOJi|2Z#l zuHd}k+JN2pJo$u8ddJ0+(kJQ5ZPv}dJ1YDk?N}FnSQpH?V9p`9H<3|Jy}*SM9@M`z zJroSi_|akg#g!A5%O2Hpoa=m=$ z9>ltchjqcM3wG}>^A8-=rO#y-pAGIE)kiNVsm+<=oG5YDzyuu&4X6Y0D z=@U$!VEP2pC)hk!D6T2YbGzbN!#vL`u0hOmzT(=%JpU`MS~hBE6E#kG}LzbLM`%rlkZT8!+*3}(z=#tdf6V8#q)%wWb0 zX3Sv53}(z=#tdf6V8#qK&ryo&5wl)UT&I|IgyQme=z-n=^sr0VEPA}=W50Ej#)=2u7k|_LUDa$ z)*XuLCbJ$$f)aHBV^dSiofLC0dZT`=1Pvt2OT1+!f++Xb^-Fxv(1t+-!puV>%& z=Q^*|(mItThBC#qNcJ|)$08Q0`P%MpIh}HmsoU| zOc$%PguVzC=PnDK)dKbY}@89$iugBd@V@q-yZnDK)dKbY}@89$iu zgQ+RzCAZJXt_|3|j(DA-F4?sKyW?|D(?zOTJUdoXO*dn#W?AXC4_!N~3qPz2W?is5 zuYO1i+Q8nOuUZ#4pjMBzdl3hlGZWr?RafF!`0$`=dZvN!nstZO!|2As@0T7`e`IVX z{Gs`l{?QiwgXtek|6uwD(?1yg&F@aq7Uo;?yOS{HVe`9_Fy?3TyOS{HZS%X6Fy?df zyOS{HdGouIFy?>ryOS{b#Qg3Qi`{m?Y!}RS!E6`IcEM~H%yz+S7o7i4wCZ~%pR~K_ zs$Uh)@}+S6zqN`^X}Ma$1FGw)fKBokRrzLKvAG!Mpt^o2kMQ-Y2UWgSxnr^GA58yX z`Ulg$*aZB8=^tDv&2p8jPa5%mA!xa}Gdi8{uBpq_=n-~b&HZ?hDsjt9Qr=>Dr0VtY zr^4ymtWYsytuC!fu2ch~tzH{*u2L&DSRLc%SglIbwfd6XcEM~H%yz+S7tD6SY!}RS z!E6`Ytllh@?33kwT(fQF%~UPM*>7nlCZ4IPbzCduZ&rt^hx6>Ww+s4(s|WvWk@8=9 zhpXO0b_zdQ60SbKyH~i`+i;aMs}}A%VWx`w_@HpfGPBg0$w!2{ryYYY- z518?Q84sB8fEf>%@qif*nDKxa4;bUWNs8@3=!ebbT#h9ZUkP7&cv__%omJi&z8G*? zwK`Z%xWkoGs%N&=!t>IeQi~1`6wX}ir21~?1mUkrolwO>rwNbGdtCXi&Jr${>X=$z zZm#gy7f00O^>c(<-af3tvdY8tbU!*vw`q%Ffi{1Faj33PS z!Hgfw_`!@H%=p2KAI$i{j33PS!Hgfw_`!@H?8fhoJ+f;9cCWi-C6}qb?d-m|`CXQ% zKGWXH__-LhPrW|jsPcVIg=@U$!VEP2RtPAE`fgIhrl>q99{EcX}4gvgu!`t zS&qE-*0*O&5-BfT|Ece*HA#gpPP*x9mL<7xyH}Td<9@Px4u5}j(ieFlm6VfR|6uwD z)4$jR{DbKqO#k5BiGT1_-dRxmKmFmNZ{6d6Jo9QF;na72 z3qE|YukhZSe+QTE+fR5}*gwJjw_7g$_D%4Z*_LzFe;-^co#lo*$9XUfhrZ=OZ<@Cc)*MY%y__z2h4cDj0enkz>EjXc)*MYZ1zZB#_SvBLwf(-?z3j6=`mXzZ&)3*zgZyt|e4*Fuv%$Qf$9zTpvCjr%*C&`h z!So5HPq7d91dpEfi5jz|gTzxLIIXHO!2X^vU`INoU)kRi&OJ)6##L)8HXW{HP_w(V z5iU9?qe{@-{+>|$P(~Hqs-={Vj>@P$scL^isNFiFnp(Q4l#|_d!E6`IcEM~H%yz+S z7tD6SY!^IxTLP7DwVi)Tyo;|kMcR33@ymFs+95l4MXfc@&1vj?p-=j_s$`_yM}2Vd zf5C?X`^+ouc@tbEBEG~=cKw6tA58yX`UlfLnEt`+6U@VI%w*RF?CO>2Omg+lqi-a( zwk^b)L1kS5yi|qOV(+`+_!1M!l?_VcA z=@#6xiq*Q$Uy;FS&e|M#y`wF%TNli_VAch@*LAg2Cw*Zl>@{9&!b#t2ed_Y{ebBQOg~`y z0r$w)SH+*XK>Yj0_E8;^M2RXCA;l{*)Evv zg4r&Z?Sk1ZnC*huF8JT1eO38>Hm?zHd#T-dEdO+`hk8`ha>UhcYEHQ2*SEWa?5+Np6DLxh8RwNu0Ib`(B4uAMse%HGS? z{MJrAh}TuhGp%c{R=l+Lwa(i@RFmU9r2NkN4yrNviR*l$Yx$oIYYWrjR`yuB9 z#6x!dfawQJKVbR+yYqZdg#l{!#5vN>e{LA4M%A^yUB~G#Pz_8RD&@^O_gC?+j~A|T zthah{ezb7G`Q228$U(x?1+kIcw!mx)%(lR63(U5_Yzxe`!0tW5y~fF|4cMHsqw?i(Gpqn+^lUR`vh-d_t(+R{zO>}(@^?~fjO))ZSl zHEVAj^1#}YUH@SE2h%^8{=xJQrhhQL$^Ck_ea6Q3&KD2ZXK#E5{q*OQG9Kjn==b)y z2;WUl%V>W?#`o0CGTYyl@tt+@ml?z!-(RO(kx3ZeWhY8y*FN}OyHe@Tq#WOIKT4TJ z7~gl7pJN%{@bddsvKuFuae^5qm~ny`Czx@987G)=f*B{6ae^5qm~n!;y_}%m)jB46 z6>d0D-xz4mg3B^;qCRl;oRq&FI#GXB{CnXm)hFtYCtVTF`EY_>w(h!cSepsD*~nY5 z*!2&le=z-n=^sr0VEPBAZc)$c&ysoS=xH-;KW9%^OV>zXIZyl=`ffI>OHAQv`r?Dk zqDzK|D*AdStK;@cmG$*iR$sE~A58yX`UlfLnEt`^4_-B=zpiz*lkJC<1NFJ2U4#qH z8LVf{?=IZFTyRcwUr{dR^ii`$N6;W$(DcpEw^6qz^+N}KL0|e`y-L`;rIeM_4?Iz&9W@= zbG9Xr@PJARWy!kSlu5&$(aD&-d zb)6;eq^}M(%Br`wdo3KVdsaO@%M0PY*R$%ifBq?)Ix?H?_RrH;?D_}OKbZc(^be+g zF#UtwIN1-l?~q*^uzTH6U)Ymf8?Zb6$tZW{7Bc*}_ZR)y$LZ*7_Kd_&@|kl#UfJL0KQzD5KiZ;yF#Ut+A58yX`Uku7Mzc@)>6ByaeYX5u z^Lyuw5YdbGP4pGntqW#dFzbTd`*^z?4fL*vaPiqYlhWG~t{3L>1N@WSx?t7?vo84O z2PO6PtCi&1?D?*=4$Eb^SH2*f@mxhI_q7hzr+={genL4tu&lMoJ+FeU_}cQhF_rY` z6jj8Y?D_}OKbZc(^be+gF#UsP{G7l$H>P{?#QL+q**IegCD9>)y);9MB-6+LEG9AB zj-Ntb&1-+FpRzQiKEJ-Cl>h!$Ds9gCjK!{hF#Ut+A58yX`UlfL_}1y!y73(Qd|P|N z9G$)P1ZgWxm$`a;u8G2t|IXEkvrH16(J?}|{BpAJsl^d`RMjcM->r<$>A$hh%+H5J z=(*#jO8K)a5qip8yWgYf+`0P7>}gV-=k6T+&mg-$WOK4Px=|HtIY<=8(6Ns^q zBl#>{GO)L#__J{B8yPO;=P%9B@k1?-+Bsbp>|{B5`80h#Wo&kH1T#l4a|AO-FmnVm zM=)~)Ge}a*=5J!vMZDPH*eeV8Io$MKWSY%Zd)9m?!TU(xY)P3JUz6??vvN<54>7DuTB|cxz_BQI%T-E zdHrcNy`oTM>CbGBGwX3#?OYd}F@xUQ!|K>?e;QruORM9D<`Bk!co+kiF@PBZm@$AE z1DG*@83ULxfJZsw_CwbxZD7wi8GY!^QDoN!Y`$66JZHn4kD+<~hB-Gw^IQ&do`&Xm z9p;=3&2v1=`5T(&dzf#=HP8JZyZ*uS52k-G{e$TrO#fi>?%T}gW8^-F^C2Ja8!wD= zBNIHGER6Fc|F{z-jB_T_e{1idIDfM8*4a{yb17@Kj1b0ol`Ff>7sff3e_dK2jPor+ zrY;o5xtD)VvyAgFr~G7XQhs(=ryOMK;>^zy-KpK^Wi7 zmHRKHFutctT_dqDzO(C;JB~2)nzi^3*-t`t+Xb^-Fxv&QT`=1Pvt2OT1+!hS`Nm)K zJQj0~ism^j=6n^+^IOchE1KuJnDbaP&wDZFv}m3KW4_tfJRgSa`UlfLnEt`^52k-G z{e!DkkI+rSm-*5EyN1lwmA+mf95rK(ZoYVx@Yq?ib$#C&;WLwF>CcPUeN$V^xBRsR zSnmBzxPG0$a?P)2=&TP{i+z<&({6)1T#)B;{-EKFyjO>PB7yHGfpt$1T#)B;{*?zJxNFQuE<2l2!9teN!NU3&q9fsIZ2^ z`UlfLnEt`^52k;xIZs3LToH2~h~{}C=A01Cb4bkjA)4otm~%xm&n+?MjcA@{V$KH9 zJm-Y$`UlfLnEt`^52k-G{e#V!B%0^snDcEk&(AUE-e{hyW6s0TJa5OGlcRYKk2ya_ z^L!q2c8BJ}cNBv3y-sHALc71~B z6HK3A`UKM_*q!$(y_=#F#XTC0{wY{KRR4VazHmgrP@QyWe2M4bi79%RFP-q{G*fhV zgIvPA7EqV$`UlfLnEt`^52k-G{e#`UeZ44J_X)RslIMZe9cNFM7|v#j(HHK_6z2UD z@sM3VVEO^m514+y?sJYgvqkgF7IPkp=2KC6&j8?ZY+ znDcWq&*U-Z>S&(TW6s;rJj2JF!=rh&51+5l7TNVFZ3TRS=@U$!Vju7c<~0kSWR&wc z0i2-IQN89|5&6D#Nu$I1+^0dp`THK!pGQ>{{^QgE-N2mZ2K$Fy_UqHvLxkxE{^SS~zriv>Lg&jBviW z`_!L1%L+G}5~a#?3=&@6Z?EdG$MP>N%>TM>w4AcaZndG3<$rv;RGLw?Zju^1)%6b6 zXMx^3)SI`Z#Luuj+ts`VHipm5e*zxpX=76dwy9L@ZOl6+Y*Wq478ZLl`igmhnHQLO zfteSWd4ZW1n0bMj7npg0nHQLOfteSWd4ZW1n0bMj7ue`){)Nk)!(g846whZc&vlCD zHkju+#q%7@bDiQj59YZ}@%#t#T&H+0gn6!0JTJmrN6Ps&T-a?F%yz+S7tD6SY!}RS z!E6`IcER|+RG#~R|6k^LAoyQqo)d!qYv%bO_#bDUD}w)b=6NIdA61@1LU#Rw=^sr0 zVEPBsKbZc(=pUZ%5%>;5##rF{2;snY6T*S-DTD*xSqKNdzYq?5mmwV3GaQTEcEM~H z%yz+S7tD6SY!}RS!E6_7zU5auhryhmpm;umIafjP+y-;rg5r4&<{Spaa~{n342tJJ znDYu0&xIhn{=xJQrhhQ~gXtek|6p@Yg5o(0=KKW3^BK&!3X118nDZ7C&vP*6Fesk$ zV9sYyJpaL*8=!bD1ljcurhhQ~gXtek|6uwDGk46NZp>uY2K*u2-T5lT7Y9`JwFTvy z*;j31RFgybgx}vjsIt|{Eqr_BVRgT8PT}tt9aZQ5$}UVlh=+c_^aG|JF#Uk(2kegj z56u;{L0;~4J?Y^lH8@`)8Qa<8Y*i^Ud@9WO8UD#`T`=o{Sr_b%TXVjI;@K4D+zG`q zD>x6pKiRDdW?eArg5CKxW7(q$=T5+nIbTBIJPNQmcS7Nu3NXi#%dQ_V{RjvAfawQ3 zu3?le6uL{aBf}@SSkv3mZ)DgPu6IT++1F2=0X{EyTK_h_zwl3KPwA)|1BLG-KdJX` zA1Yil`w3m>{wU%2jgRY7YsU&lY&@o?d_7V4MbTrr&#+M8pYI>lQ?5@Jo^|%9KGJr! zSN`AKd7gcSs*8o;=f8H#h2dXkSS5^h`_x%0jCk_iUnh(>H(b~tjQCT(+bE2@%7$zb zF4z04S3Z8yInRF7^z)vdLL)AC{#(_&=(T&|kBeSBUAtYkT)Q{Umiv56ZPUxd?R|vnpdt7JrTmEs}aa}8PrIbIfaay?KlJLlQ&`RSbJC*|Dpp8qE$FL>>Kv-g4*PiV%AUYy+;U(}4hT<42kUMOe2uxCHO z5BmrH*>7l<{fT(k&xn)#kNByJs}~tMQadoU15-ONwF6T-Ftr0yJ215aQ#+O;ciKZc zFtr0yJ215aQ#&xV15-ONwF6T-Ftr0yJ215aQ#&xV15-ONwF6T-mP0$*Lpw0F15-ON zwF6T-Ftr0yJFu%4cwNJy-neZr)H3=c^&gheS1q>`^TvPuoyCRGw+a6#A&frX)2);+ zv`dw!j4-sDyuYk4v^zG==at8=sXY4;amowB&yR~M2*dxx)RlyxooZZJ81WQuQAHSW z4$oLs7}^C-w~V}g-DMfMvmAXwd-N6kpbzOEeam*y=Zpv1F-~a5_@N#1LOJt=J^KNE z*gx>kenY$LPsGE1Mx5+_#7|vZy~xlMxx)rb?ZDIyj6OtLU}^`Zc3^4;rgmUz$8zLO zd-MsI+JUJZnA(A<9hlmIsU4WwfvFvs+JUJZnA(A<9hlmIsU4WwfvFwKp&jj^9hlmI zsU4WwfvFvs+JUJZ*wrhLqsB95Aa~(Fp9lx~N;uGm!hyaO4)nP&v@===Lp!69a6mh+ z+~nxln;eA$V?a1CHiQFXMmR8*gacztI575v133x@au*KtiEyB=gadsj9Ozr&K%WZ- zt|Q^V^(7q8&MRlW0j;GxFb0GJV?#JFW`qM{NjNaZgaczw*wu?nP0c)`skNDBgy{$6 z^bcmcV8#PxoM6Te4vbat$$VK39cd38!R$9M`xDH52DAUc)CEkvz|;{;eZkZn%<%x` zI019~fH|(ffw@KE49qRU9G|e^xTQVDGyRx(SeWA<<-9Jyyk5Y(j=;RW!1Kbl=xdp; zD_nO)zT2z|6}Eis*d{%ryX9`rHtIa*EH@~zQUBBUXR&WJ!<@nU%JS5YH|T_WZ%Fy` zHS6_&sW*jZbz84b_qZjjnyr^LCfY*z0(Hl;|1;|^!tm4fZ_DsMblY7iN4ve7{VI%j z%KdB^ab7NWPs$O0>EV`v`3$SsU4WwfvFvs+JUJZnA(A<9hlmIsU4WwfvFvs z+JUJZnA(A<9hlm&9NN(y+JUJZnA(A<9hlmIsU4WwfnB{WZ7rdO)m^1=EtH)ftX@7} zDV(cP6_xe(6~eFk)mBd{L<%4OyP@j-W~p$T8O>F_0*i&?eb!oaemY;c^PslsUE{gJ znZ~zQiAI}!2F8E3lIFXrsnfjj$azyd`wfRC2*XdsFUJbQ|BfF<3Zva&WrheNo*^5| z{(IvSai(e5M;P(9uiQ%*d3`mjr*Myx1-$Yx*>ZXI8-LH@`MKFEgXe$MrPN-#E2<{< z;wks!W5qbbZX{BSe?oyoUS23?zOZLMzz_Qe{@HJ6m;H%&*w2WQ{g3#mi>ntIno>J3 zwF6T-Ftr0yJ215aQ#&xV15-PeBX`=PPr%d;Ozptb4ovO9)DBGTz|;;*?ZDIyOzptb z4ovO9)DBGTz|;;*?N|=&XbanemurJPBHGfPV z;k1b&)W*x%gy*%5P}Tm(;FaG>l*+Sz)+Vtq{A4Q_R~Y_RwtC^m^@Vl|=XflPc=9K{ zBaAph8vi7W`2QEikM?Nxiv|BlwJy>_>qZ|=oY zcVH96I2Uzpq!|C)-3`6GP|kc|&whX(_7D8C-_S1m6Y;R05hwc}@lzL9FETWxc3^4; zrgmUz2c~vlY6qrvU}^`Zb}UEkv`3$SsU4WwfvFvs+JUJZnA(A<9hlmIsU4WwfvFvs z+JUJZnA(A<9hlm&9NN(y+JUJZnA(A<9hlmIsU4WwfnB}YtevS3?@l7)eE*Sf{pk$L zA3d6(TV=BRW9Aw9la?Qg&B%7s^=D1&H4=GXn(p*TA}PrEYqfIdbm{H0<=v{E>yD8Hq^fYQ1v^!~fhj*@e;W&As+{74baWkyXkO z=kjM+gc1L(k(QBHX>+bDo>8aY%I}pYoLA7ZZ(F>u=O@*7MLhq<9~Jf5)xQ_>;z_Wj zxMrNkz9`|v->XguFE5lcU)ZxB;D`MK|Lixk%l>}SNu{zv@O#np=pO{pE2+JUJZ znA(A<9hlmIsU4WwfvFwKp&jkfCtzv^rgmUz2c~vlY6qrvU}^`Zc3^4;rgmUz2c~vl zY6qrvU}^`Zb}WZ>w1;+JY6qrvU}^`Zc3^4;rgmUguizEA_wl+*R=a5w^=)1-q%3tG z7?~}I^Yv{ zhu0na^SVR3yzUSWuRFxa>kjerxON zj%K^<|0osBcz%9XDVlLUt6wXc@pm~@Cz^SoocY3@{Qy7gANXg#pkzVcyp$?#D3ieH8a;nD;)4`!~#cAI1GD zDCd3;*mJ)M{BXYt{Byqw+U0%~#KZk6h?DzO5WlluMRC81d2iyCoA)W6y?M{#`7!Tb zJpbmsjMuJt@8iW|-urlQn)f?i{N}xnmlw*JFYMV5@WcLrfA$;NWq%?b_A}yS|090t z;_5|)rY_SS<@5ule=yqxGafMG1T%gx^8zzpmOFb_q<>J(egm^V!R%)+`yWhQz|;$j zyr3hP`huxDnBxJ=aRTP}0drh|Io`k=hhUCRmOFb_L`Rf!oP#<3!MrZOyk5Y(j=;RW zz=6Evc`T5Za3C+?KwiRuyo3XJ2?z2L4&)^q$V)homsf7`^6bs{6b|Gi9LP&Jke6^E zFX2F5!hyVm1LIIQFb;(S<4`y-4uu2bP&hCSg#+VII4}-{1LIIQFb=(PGY&m_GoJ_t z#-VUv90~`

SXv3J1oaa9|t?yLyqSshM-+xro}KoZ5k@9hlmIsU4WwfvFvs+OZtk z(H`1?sU4WwfvFvs+JUJZnA(A<9hlmIsU4WwfvFvs+JUJZnA(A<9hlm&9NN(y+JUJZ znA(A<9hlmIsU4WwfnB}8*yn(C5OT*p2Qd1??57e&Uzz<>!stV@pGp{gYxYwKqtEdk zU+S9s7x$|`JMQ0rc4j}7*r1&IRiHKZtH6)hPv!YH`>BM{uG!-xjCjm`Dq+NF_EQNX zezR9f7(XIqp#=(eMtZ4TegcnXFSl3aY8%B5AB#2%9$_h*$?o;{(*n? z8`@=mA|CcL;$;6Le(K`tMTVx-4ovO9)DBGTz|;;*?ZD82do!pV%BdZg+R@(GqauBU za`;Cdf~g&t+DYAjc3^4;rgmUz2c~vlY6qrvU}^`Zc3^4;rgmUz$8u;#d-emhLpikr zQ#&xV15-ONwFA3)1#(op?zj&yFrKA6&{x8NJ`@i0t#IIa5e{5O!U2th1KN4zCP&ZS z`yTJ8O;6%Qx`Dx0#ipY^#xORFvkO! z;{?p{1Ln8_2j&)uEiktTb9};vPv=5+z)^#bN~1P;tCQrGNVQQRkH z_OvMOM>2a|6!$5aJur&kenY$LPsGE1Mx5+_ z#7|vZy~xniW!j^he!%n(X1id<17@6H#t&v*VCKtmXU~}Q56anZVD=}N{S0RRgQ*Lc zdV!G_bOcjhFm(rWJb*b)z#Kndjw>+78<^t|%<;)`XU~}Eh;oi|FvmZb*9Dl@3z*jt znAaEB%qRF>M&nvA^9;V15jOJ=zLya;^Af(75jOJ`zLya;^BBID5jOLrHou1mn|Tu7 z%LtqK5Z}uPn|Tu7%XsBn-@%^iJNPlbKZp(do8KRV(XRRZK^XCv-yeh#r}_Os81b9m zAB2&Y`MpTk%rjoOnSVTcGcS35%zWkfH}ja+u9+vjc+5QM#cAe4eD5Rv%{=Mlg>vQ# zd-enTuz%p6{f2hgpNNP3j5yiE{j_`%Ez%zRny zto5XSP|kh>vp>P?XE6I8OkKd#3rros)E7+M!5j}@juSA)518W$%<%@s_+G0k_2ir;CP z?->=p-!$JjDt^~#zL!+|-qU<9srVhJ`Cd}-yH}L+yHVKlds6t}cdziz?_SX^zk5YI z{O%QT^1D~W?|k>F_}#1d-q0&I-ywST=KDm?kNIxV^KZUq^x8GwOM3B`?>}SNu{zv@O#np=p9jP6d+JUJZnA(A<9hlmI zsU4WwfvFwK`K>6mLpikrQ#&xV15-ONwF6T-F!F+SU}^`Zc3^4;rgmUz2c~vlY6qrv zU~0#5Xh(Z!2c~vlY6qrvU}^`Zc3^4;cJ<0TFQM*wAwfCZ?}p_`pa)#F{OV9V-Skh( zg9d!0n`B5RHrcDi)fMYl{-RW)eW3S!HgDoSTA{#9u&O+Z?M*OLsSVmr-KC^r| zVPdbmW%rLg`=6qccz%jJOseU>z;DUCc5lTb*No?<)+sdOZ0}E@8GqQ%DKzs!IrD|R z*AK=I`v?BnZ)lhOiFnx0h?D(~_^FGl7a5vTJ215aQ#&xV15-ONwF6T-Ftr0yJC-AN z+M`dv)DBGTz-SkJ3#N8pY6qrvU}^`Zc3^4;rgmUz2c~vlYA5za3&u(9P)_Z@)QC%szn95faj>p3%ks*f2kJzJEa#X$Kqp9b zU*Xz3)3(39In?rnR{eDAe=TR3)K^cM{XlGTJn5rP1U(d9G_{ZZ_&3Xay7$qyS3UB| z_q2ZO*}qEhL>PX`?zRm79qT@oa|T&j!Tw%oeOQk`V}RvQ#d-enTuz%p6{f2hg zpNNP3j5yihJFtr0yJ216lIkaPaXa}ZtU}^`Zc3^4;rgmUz2M*Tj{G|;NUbl{3w{Np< zkgYu(OV{-h@`K|6N7hNPu64Ce?Skv%ez|(eKdfIXw<_0HeqCX$g!E~k{P$mLBygai za>>JMq*SiP%Gr0=|H;m5;+M}!*wn9|@!Mv~XlH&*b7i#u=lvGS==ZlLEtO%~rLk zzB9w{9Kjs*(Z*TIn7f8HoTH36t#7M&%9!hN>{_6VIrFox7As@U%=5`IWz3ml;;!_| zZ{Jw$*MG3a#r{G&kG|Nbu3+=OxlS#llEiI|8%-voh@OJ8gq9#+7C2dS$G!S&p?g>tjvMcCc1w`&h%XU##tE58e@I zC*BcgKi&~IE|hb;s82tj9r_3D({JdP{)9dBGwh`QVLx>V){CrKd)k4i9hlmIsU4Ww zfvKI=w_3nvFtr0yJCz^Aefojgp`6-*sU4WwfvFvs+JS@h!X8VGqPO)P!Jg8YKW`~xuW4UV z$Jm29{?839$KF)i2JXM!*t6`k$K>{+p2>}Am&>`&58?0wOG?1^z)DCc-l-}i%UhyFqP^c(u6 zKVc933_Iz6*iT)8^&&%4Y6qrvU}^`Zc3^4;rgmUz2c~vlYR7Vno%P`pFxr8yz|;;* z?ZDIyOzptb4ovO9)DBGTz|;;*?ZDIyOzpJ3)q-|XJCsv9FtuZSXa`0+&<;%Pz|>Cb zd)k4i9hlmIgZ0|_MdT-0TP6`ak8)htQSz_Sjz3FWG^E?FiM2em!HAGv6&%OQx;kWU zw?tb0-JWA1hdO#6e|KQ;(EpM7^#wS}> zJGSLfEVuQeS>Lu3&30`2(QM!L8_j;LJ<+tsjw_mW+Hu9uemkz1pmD`;yr@qp8qT+NZZVvP?LBTdKihlXaNf3ag5i8_=Xt|< z-p(P0^S_;2Owe<|@Ogpye2$B&@)qcNr4iBR}_E`|-+j;ZvFxqdQ1z{YQeMW?Fyr@q?NCnbz|;;* z?ZDIyOzptb4ovO9)DBGTz|;;*?ZDIyOzptb4h)TGKeb~yv}1if@2DNhsU4WwfvFvs z+JUJZI9M;c<}~@d_dB~5HGGe-YgEJc3%hnTeDAPpTEq7dyVf;)PqAxY!}k}vmNtB^ zv1@6=_Z_>IHbL(}hVMtH&-W&@!}lq)&-X0!%l9wX!}l`S$@ewb&-XZti|=>#-N7%n z?-YK0`|jhnW8Xpi_U*fg->-dV@$Iqip}w8=-N(1zzWey&LOI8a`t$?Zp?}am{f2(& zPuN30!%q4i_EVQ&y~xm%+JUJZnA(A<9hlmIsU4WwfvFvs+OeGPchnB$)DBGTz|;;* z?ZDIyOzptb4ovO9)DBGTz|;;*?ZDJd>su}O9!l*{PVKwDUP zsU4WwfrIt3dn|_gnRf5RaNo@C$r$dZ*}WRWeKxy?W4Qlj_jU~T5F=-?Qwu5)<^D%kcXb>hrr8+Tr&*w9oH%=$GH`U=P3F!A^d^gZ)9@?+m}+*>6LB zx&3D3*SFu2{C4a&Ccl0A?aA-gev|U;vER0QJMFhE-+udT%O4lYIbPJKAJ7i{gZAk+ z^htl{$JD9uJ zKISy`i@A>WU=F06m@{cV=1h(Y`;zc3^4;rgmUz2c~vlY6r%+pdFanfvFvs z+JUJZnA(A<9hlmIsU4Wwv7F~ss2$3w9hlmIsU4WwfvFvs+JS@h(lw`dJ`-zfo&&_% zo96?uCg-_9tkrp*5NmjzGsN1S=MS;w=eb0@Bk;T;-Vt~{6XiVLi26MDh<12B6YcYS zCi><1OxVNonXr@RGhu(w`Aoy}nOI}99BXgZ$2$Vs!CIZ|V-3%Kv9_l@cweKPco(4k zct_y4P|oq9KK+1p=pVFCzoB3H6ZX*0u#^6W{nRB`FETWxc3^4;rgmUz2c~vlY6qrv zU}^`Zb}Z-lOlpU6Y6qrvU}^`Zc3^4;rgmVA3)+FH9hlmIsU4WwfvFvs+G%~O1<#RE zJCsv9FtuZSp3kIqD5rK{YNz!*?ZDIyOzptIdSQ=+|3|={63@M3uZid3u?NL-^4Oc= z`FZSF@mxLjvUuJedt5w+k3BJ-&&Qrv(7AoX^ZcmKbN*%vj#QI+wd_%bq?ik-zq82&EHv@fI^BV)jIeF^yw7GC{OX!G3pokBAMULxjBx} ze*3$Q(eLt{$-Q<)giLAX7Z^8OY6qrvU}^`Zc3^4;rgmUz$8u=L`p^zc?ZDIyOzptb4ovO9)D9f1*Z$}6vL{LE zVxHf>+%fFcVRuGlP}RF(%PP7vA+M6f%*WL}|+c6$D}R~hYB zdwEG2{a!rvL>czP-~LV+cIHm){`Uv_d*62dx%+VchdD~*OQiRyEf28V)(^10ZAaLS zZC}{F?N`{ZwMS@=wNq%PwO?qz9hZMD8s!`>>eCNshyFqP^c(u6KVc933_Iz6*iT)8 z^&&%4Y6qrvU}^`Zc3^4;rgmUz2c~vlYR7Vno%P`pFtr0yJ215aQ#&xV15-ONwe!kV zJFmWK2c~vlY6qrvU}^`Zc3^4;rgkiccB~KWz|;;*?ZDIyOzptb4ovO9!Fm<{Ymq#R zy+!XMGU^nn5apMX|8sd{yJ)%5&iyv!uozi4eXF+f+1P+&7`a_pz8A^~A=@t)K6z&Q1;baa*ttOJdSfiNVZLPa z#=ds;rVU^lKSwg9asR{3TW*u&|IPhBclw>p5=(>_ z!R!~zezm^WFPQy;*>CXJQGTiXIQ2s?tFOHBU`Cyxg~rO5JnlcRy>muLzOIgc%o8q^ zesNr{(ipkd&HXnvYyZ*mQLaY@za^thwgYB6V73EhJ7D`;gLc4eVz)L|E5y>Z&9FH6 z&D4P|UcuwFPr`bRa_=&A?sX3-mfQLP*0=2l+p+Bn+Yh#x zHUy6a%=%!q17`bR_6r`LHqmm}>bW8i1-4|&2(W$S-% zubdGEx_}248f(I>Uf>Jm#~EJpYzJ*xKWjT+>wiNXtuERQ%B^08y4!0;+d+A7o5AIX zPldivhYTD3D@GlAt@^RT?7d@n@7QbG@Sd{Qyy3lO?*+qq(B314_olsf4DVTcPZ{3J z_Fgl*$JrP9WjUDj!E6W2_QC8IOnbnzQ|o*7gV`6xPG)(&h;6D1%E7_q;Mm_pnZqO9 zKL6i~qs+0Fz(UohL?{-88 z=gc>I-G9%QClV{rW!{J?&L$BsH)xdfHV|692?7On5~rR>?D?AfO5*{tl1McEspvNv{R&nL?4 z3-+)a%=%!q17`bR_6w#xVA=_${aWsP_5bMi?d2o5meeO?_^Q;g?PkZS^;&<;>4150 z)$xY&`^;$V|u&)aTq!g5TTq4u=B65I4h z?DC&3?_u+SW^i%jj@3+RzFfRS>!d25#@q;Bu6*mm%%*N&rE-hGIn9<_tCjz&_F)6t z2eW-J+Xu6KFxv;SeK6Yx2is3ZdDi*Ag$>FRss1Npykyil+Ur`_A3u)LI_<)bgx#Al zKsis(wP6dVe5>62;n=WDv05qTnp88aeu0L{P5+1;_U`Li%3bf54}E&f<#oCrCw|QB zevTiOxgGPWXHBh>Byrimm}T|<0|(m!rafTV1ExJ-+5@INVA=zwJz&}crafTV6U^|* z=o?#PMn0z_8Ra`Vo{)C-dPe<^lOB*E-??kG>G>FW^V3=_XMNORef*a7!K@$L7ue1x zek{SL`{(837w#I{@cnt&FwnFzoaEWzY)D=Dtn}Tq zPRnCOot7^l_JM=Sa{xN4U;mzp%}&H?$mV*CARTY}Y5+ z4%n_+w0*E$&uG73yUtO2z;^wkc7pA?NbLu6T;SmMEWZ1|4}A9l^W6u`cONj{LBM>E z1OHFHKhkgLm*WC+ykPnPO#guCH!%GPrk}y|KbX3JdHsNcuead)@xS|;=bWInd2=B6 zzk4qFznP!;ynsFbe?3EkpYQ)2Yl-0X(*Mm`%U&n`8qaEn_X2&s|97uBy}tAr;q|5L zt#6gR^{ukEzE$?tx60o7R{8(tUBKQW7_Zh3ewXC?8mm-{=e*L{7>%T91R>c8PB_zGfOreG4bX%QoqTh zqvrBP7nf#qlVj#Wg0HkZQG(-U^b8k=CvoI)6R&Y|EzkD+xG7wwrSi!_CrqNU?kw); z$|uaPHNMvJ-)kH;qas{iRc;(Il}kE)(C3ipb-jVs>CjJ1*$S?m#s|gxS<1B^RdSbE z*2wic=7(M8=Da3a|MZ02CPM~i=gx2Tm@hB5HaFDYYtCG8ZH}wI&!jHmcyo*WX28|@ z`rGo~9x$QT99RABps7*J)v0Z-oul0-Xi8j%XOb z^d07Mba&;$Teq1HF7{Ne_q#n0-+7So2cK;=eG3mzJ~wW&S(y5J;tBRnB^O zi@DRGkMho_t>)#6Udo5=Y%=3Q2P^-5d6Vf7e~9w)Gn-8OZyg`oyv01*H&V+JCEsFV zC2*W!>}C_U@CYrx{pn`2qQ-FLWw$q(7tMw#A3d_kl>cU^a;CI<%@?0dQHFM>ModsX zm;Z#hI&Y$K^ZUomKkFlvbM-lHdTyMg-0RXY^LqAV<@ITgncv&Fc4`(oYR0FSs^!~5 zkC?bq9KXzW*sQtdcwO2(lD9RrKs}0 z(BU#KeR1XXdxuNCze*_2$TUJeei@>Cq1FhgpTgx^`JurG*;Tl-mbWf2LN3)Rs~moH zxKwXaUb$zEUcPN>cXyW1QdP8k+L;JfbUgihANjhN<9s`NN$1|~w~I#(mxZM&YC8!x4wpZxI$w>O_$tt)Wjrl! zmg-sH)P48=@v;dX2fj-jTgyibx*Parq04E$GXJT-jx#UxyU(e)=K^xDoa zaa?%r>+8tC_6d&T#Tyq${rY1qpLBP0p!$1`o8%i2m?ass{KTI_0%t!> zubgDXfI#Y+X_Z5yZ{WKMsg+|@?GqTECZ%$!mc0Y7&nH*zmY`4Iw<$@LGnVKZSl24C za?@M=1J7%IpgifjA%Uq~5-Pu(IXrOtcmm}CrA7zZ_KL6kMfI_PIz60kH`M;kA4{p# z{{)&gb#-2^k0nhvxZftN97l@QbZsV|6jz$(cYP%q9#2}7bvA5I9bZguXWNnr@#S@t zv$%hVhuZJjUhyP(0XN3P1LDe?Qf}<;=ZPcFGdQ2@n-EKuZF9bA*2?M-$N8{R znOA|AFC35i`OiRJ&*#OHM3_s{6RD1g{|q;ucSxnY>w^fB(_~a$T`R&gK9@uJ^!^Bw z{6Svj+bzeMf>nwtch5e~+>Hu#kWIr{-+<)^>`Dw&F^Lt3e zFqDTST4KhWY^hxEk^SG_@)pVmE-W-XUN%+E_tOFs`%)w2bWiPn4BORJZk=nsX?~)* z@~kS$OsV*7lyCJ~VFqSwuiSgkDs%B!SLM--)|e)BzjyWjT5Dc>KV13xw$0{l)p5#+ zmu)h?f9E*X^o^#)v$0zKXyOL5Wsi%azI)bsljPnQEq@oa&iv7Pl=6$TJ5Bl};mQl@ zh^e!$r*e&>0rT=qf90=I2h77ELzP3qV$9?TBa{bKu-`#mxpvkTjWX*uxc0mJEGF^Z zj#}sPce_mg^sSX&wOr%0nbrtof)sL{vD4PthiQq8j~x6ic4JbCfC za;+wNOt0sKlxKds$87y1RQX`TJ*G*W^2)8!?=hLHRa1VpWw(iUrH*ongmWaK#;*q2 zwMjNtc9(RVFZn#V_2!zEr-?UThE8{!?Dl*~m)P;Bbqge2%d1*vc%y}KaQYSHW7ii- zhHbwnKdZP%Hto5r+^yMkzpsgjCrRRm=e7LF_mOh&%1_F9Qbo$h+ZU9JU7je%USCvR zb9SO^O#QR+nHLk~^L(z&$m)?&D$MmY>|~^blyEk@>N83H%;0RxUSYDlxZ?Qp{8MB{ ze`kNQf>UM3Q^#$}Pm|Tf+}Nuenj)DKp3}aXww*5Tr97ov>;6pXpZJ(^%Ac0Xs_n;> zL;Eb1+Z$bZ%STIO?yjR+UNdZo47_th`BulpG9;hly8{<@Pf;v_m|H93$`zl8ufnEI*F4nmnL8QpjNGl^YO$2sbxF(ZdxUf=lv#P^?t@bNR2Jo0xA#kdm)Vq072hX6 zEzP0)ZucH}bTFs#_K~~gXw^K*iIPXll8uFw_kI>5(LEeDEf$bM7Yk~6=^`SnZx>Lm zlwp@-S(IP-#r0hhkt&~Z^|d?X;2HPZzHv9n_Nkv~`SjA8M3&}KZnJEYjGvubxn!Zu zlDb1)s`6Pazcj$cs;zup`EB+!vTWKV z<>PNwOVZ?5mAl1XBZ;QnP);&(ooqRKR5?wl_0n+VLFH`rdr_J)dzEY6+agagZc%>t z%Vuf)#&M#no21R~ZCc*_kBt(!W`}ZW=dz*ej3g@6$Tz z;_R1CE*x=O@}NwMcSBmA(OIw z7naQpGAi45Vc8bzV`cj;Eb+T#P`2;FGG=``W&18HjSstPz`hI1&_k)T+|D6}bBMi9 z4ewKX{~F%E_P#c}ukHPAc)#0uz;GV0^Mm31VCN0PdBe^phVzM?XAI{VJO3EYKXzU+ zoR{o;WjJ5idCYJgv-6wb{ATAs!#U8-jfQihox=_1a67jf|2a~An&Dh(=UBrz*3P|# zbFZC~4d-M#R~ydNb`Ce3!|mK|IJet5-*C>i&jQ0|fqh08J|pb2!|>T*pDBjV6#I+2^3)bI?8?4WEzpxoP;^wDY0id}!xM z!+Fxqy@qqIos$jcWIL}K&Z~C5HJoqlJZv}*+xgjWezxF5ozwe-JpDr1DqAj+jCb zZ!_&f8B4!WtpVB9 z!%lmT3+%++mwjd_WADq}@5u8h4ed%r7V@5|or%Gmp|_q#IozU=+3 z+N;p_rWtE3(fVx?j35|*o9{B z0QU}cC+;GXu(5lGYP8V)XZih)w4F4~7Mnf8+<2Q5U1EC2I6th-zSJyU(sdu zV@f_>tlVx^z^uyR`1eo6^eVVW%ae>1J1;F%ezQ-^y^IT#i<}hmX~Ox+T~>)1@#kFS z<&DHlelSNl<&}V$^SiV2S`XI9;}>q zW=E5DQ6J^&@7kC$?YbyG$=cfNe$-s~kJ7D7r86y+`>ktfhM#S%9MYww>3{QU<&(o( znnN$YQC|MIrMVlogL3*+t<2&V9hKW{YHjKr?yUUoSZh;pe>3I36LmMGd${Xuz?&{+ z`)7`SzTMf}FX(vs#g1lbq~lk=wm0?4HqzhjPSnn9EZtc7=+|vc@sUlGkNnlfY<$0| z^3~$~P2!ub{@Pu`%z$lfbvnKnDgRVGq}PA`+N0!3?_HA z>NiThD*S`;h03Gk{m~bcv)>yj3szlL9@lK7G#GeI`Mn|orDNG)%1fu(bMYtJx;jgG z%c(@|mGe&hPA1Llq}-};KN-qHPRq|U z$u1@GI=`)L{fS)t)cG^p?i?~Y!uk1p+s|ZE&;43oUT2j9;a8P2B*`jY+`p}yVo_%4 z_}3%l=+s%{nQzjXa@wsyM%b8@w zZ@($mXpuzWj zMkz1)dzvK7I9hq)*VCo(=VO$Q&7CfTDuyesTryqKeBVRsQNTL3w@RsgkdRn`6tTn<9tpeg~dY*^*3_qNO913qOmL(1DIm zpPMN0A{-CeIzjTbbsV#Byqr$v_|%Ycay)4T{p~Mzi^}GU<&?kur?`yE;kZk#5J`8c ztd@s14U^+PI(|2@l=Lp?>U=t*jFf%lxJUnjvgj+MfPQ{fc{u1B+ zZqg}9LiyPH9x)`}2huuGA+6J|Kw>%ko8w>OC6$Xgi)eZH{A6-^by4NP(Q^X)HZ=L6fu_@)A6lIr z8fezGjMgbVVrZa44mXxL?}i2*TMy_`9B~q{|5x-|A4^!9}qbBKZ*bT zhxCboPyRRmhcx)V+yDO8-u-|7fAfFsgJWF$8muA=h^q`nY)0mQL(E3RVMaM( zIU+tY7%?6Zw;7DskBH|CModWNKKnOj@?!M~Vo1_IxPR$4#E_&v5kr!GMhr>%A2B4U zi$1?>UI6$R&o9KE2P38*;?jc=>kskj!H5BfIQC$~21I;&Fk%KG?mZZ>1Q}EP-`MhT z)hCEONdMsZNWUTWApMD0i1agJ57PgLJxE=!K1BW$_!;X%D2QlmDAFMy=H^i)?KM}Kzen!kX`X4dt zs7r9}8@zuZpAr0z7-GnC1V(Hzx{bC`%Clj!G~5yp^jExp}tmkq3-s25MB@V zIuTwc_WIF$d}znUPSkvSU>iG8^YMXg>_pAS$8zR~L4D>*Lp%TGbkq6G_rIO@d|mAG zOOV$FKD6_saGtdDr*QtX^Qv%OweziTzP0nPa2~evvv7X4@qYi!eQEt^pX0tC?DO6C zkA3d@ezWTV-=B7!;QQIGAAJAYb%n2sT_0+GXXs_uA;NWtU7rZoCwAQ;T({WujBq_; z*EzyH4=<~s)4SlpTindQu>f%^aE2-eu?zMt*--1om-xBI%- z_b)*n4fxQ;{MUTzV4Dj-^RR<$jsVTi4z{@iG;cfDzNctDcd*Shpn2ZGHV1*`e+U1Y zOTD4`*5;V-{bO@X_HSxkVgQF`wRI6z_?$KcL0q0i!tqSe<4o+%NfHT^^w_) z$McRc)zJ>(Lq0nEzRh=K|~FdBJw@ z9AW!-zOY|BcW4iuN3_$vSNitbnD+j-P|oq9KK+1p=pVFCzoB3H6ZX*0u#^6W{nQ2P zL&ST>7_mM?TyZeghln>0#`+L($iY}2B0f17>qEpX2V-4_c;;ZN_ZTZ1>qExS#`+L( z(NPEGjJb{ah@;MS5MLdP_7Qg-jD8W19SnOAryUGC5x*S_`w`b2jBzn$IM!Dzx9^pH zefwVNw`1Qc{r2s9rQff8uN2y2-z$Z7+V@JK{Wcc5a9k+ocv0W?gKdZYLHqO@`lUZ% z5B&@~>3`TyUGU%bdC@(>Fve0{PnyRgdMb|?eab{#>8(6y!fCT>b3f&L1J0OycLpgp zsdCmFTQN-e$kVeXy!j~Q4js>#Zr?{J58HOmgkPSZeDc&ebD+f(zx?e@xA%qmX)Dgv zazgBfzpri{_U$=8{IJl@KfgHa+n=TAVSijG=Xg<{en30)589{S z&@cT7d+2A_N&mxs>Vnt>moi*7@L_?K>rKA=jxQZrXC`)X-0|63^VuoKwTi4Yf7Sg( z>o=Kb^NYQ7Jof!HCc(}tTK?zq)uz|jtICr*t~SRzUsE;>R{Jp%P(I6C_v`4q}e zY4L|+wBK*jO)W>iT^rm|hCQWzaSS_uD&?NDu)lbJ#~9bRiH_g)-RPIsZ?eg+e<1H> zznv?OHv8@WFlme5@8YyueS1Rex`uYn*}m1c|F>gX{c)k3<3)Y?0qxK~XrF#Vzw{^U zp`T$V{SW)83+9bgwF{~rtd6EuKgU*Ilj5mktGj8up^(*SGhn-;TY1{r2sB?e}Z%ci$d6 zZy4HX=LbXk?Y!ZS3*{Uy>eCNshyFqP^c(u6KVc933_Iz6*iT)&afvq{VqD7JxRkwd zDSP8m_Qs{`jZ4`Zm$El5Wp7-5xgD2Z-;PV!8<(;-E@f|A%HFt?y>Tgf<5KpnLuKze zRQ9ezW$!vv_O3%^?>bcWu0v(-I#l+qLuKze^vkV|etoO2vUeRSd)J||cO5Ew*P*g^ z9V&a*p)$r5^!zfMC*cRqpYRXoRrrnbE&R!O7=Gsb481sSLod$f(2KEpP#*OBGJGze zouKEJ33`5+py!tfdVZOp=a&h3ewm=>mtPJ)us;05cHlR*4}Y>>_?h-VFWL#cXg~Dg zxKPgVqCWkAcIY3pPrspG`V;oh&#;sJhhEeLdf9Oq++QfS<5l*?rRbcWu0v(-I`qq}j(&Zsud;U?Dx-aSJt(7Jdz~o59((;L!%ll$ zDZ_s161Mo$=pNDTtZCwE^`nkYcHA&;>yjU2bliJU=8%0&3kWpbdvZX?iH7-=cg=N4bB+Yaxl^=T=_z&*P9OU*=Mt^2Z+`^~ZeXm#5vI!>_*}(I?7i zr&8B!%4mPu>nzIX_v+5f%CP6&mQ2d9bKx_0CLH!(8|WD0D(?NC>+;L7(Ja4vcV9H? zzv%H-G~1al;=>rW|IdO?W7u!2r^RAu&o9r)#n8@YHLJ$Z{`SYJ$8cOI=Xg<{en30) z589{S&@cT7d+2A_N&mxs>QXDi=R&eCNshyFqP^c(u6KVc933_Iz6*iT(BF6uSm zT5i8Q!Hm3q{T7Au`|TuOS-@}q@cn{*zw)GzZ%_OUg?&2@eNx1?zf1KZ{mod=QB){9xWT{ z^*pfU1nK`(1LZ}#$IF5A^_4$0<0a)X_kXuISH?+9!a7=>ZSgoMSG$&SjS1r<{@$26zJk@Wo7_x~f*znaYbhXw8Az3^86b1&LI z_V}4H^lIAC{kH}7bZhxk%VFpBYmb$oSMxvJ|DG_eWXl|5yex+wSRejjJMbIZhd1ORu?zuCg#dK5YXP)vq7Zx4qxasG;_2~z+L;s+C`VIZkpRk91hMn|3?58g0 zHWo48f4NlsQ*vgQdGV*)7s^qtg30t`v6jE;QO!Imvq<^yAGJ-V*YlNQO>Agt2=?nen@c%nRLKT5dIgLZ=UqacE3p3zF&ylM^d)$ zDZ=-9`<^0v-?#56V)vu84$6b}Hza6(L+rkd-@e_qQAWRZ-$ohs*nJyi`<^0p-$ohs z+kG2ljLYt`DckolzudmB`StC4oZpUpzw_I-?|s64?fal_kA1K7?X>TezWw&S(jOPf zIbPJKAJ7i{gZAk+^hYcHc%BcG`U#W$49y42;X}vuQcT%X0XE_2D131HZ9-=*52FXWD~# zgLXnM+7G=rE|hb;s82tj9r_3D({JdP{)9dBGwh`QVLx@jxPrb{3cril?|{PZW%m1^ z@H?9QZYcb|X1^y2zq{G*jKc46_WPsoJDvSrDg1tCzgJ4o_e$aSKGYBTUMWG}D<$ZA zr38Jil%VgG!tamvd!_KZB*qo=z0xnY-vRyl_WPjUj{R=vw{O2E`u*DPjJ`eg`=f8C z{VwU-Z@*Xi<3c&di~95f+M$2YKK+J%=}*{0Kf_M?-+r(3b+K{G4C9#DSY(E=$ZU)< z!x&{Yc9~)9G8@y(Fs7M}b!Hgr%*H@7jDcq3q#4FZv+>gmz#N8M(VK*%nW@w%Jmd)miEw%hJ|(D-~}{)j26b-H&6m`aU`D@RO-F$34Tc`VnoX!G0F zl3Ly%Jj#^#Iz)M4kDaE?4#zhd?J()rI!;z$yIE7t@n50aOv*v-w;z15)m(1l+RW2+ zi+TOVeS7+T$7VC5ma`$NjUB!FTW6cuy~!kRLMeNWt0;DkJg9-;i}BO9mg(HP}x1CPto>*JJn-mx+9 zhPrqxqjDdU@*AgUdF$ForAp)J$|aj0ktH2wDz9#ISbje@OZiOYL(+QeY~^%?56W-j z9lxLLfQ0|->LmMkza;D9ep@Z)J}J`CwFx^X&wZ-#xDem3S-j7~u;xK5z7Jk~s*D(Y zucNXlBX-}d))|!%({Emyw91I}SL$stWyAnX@kK&q#0G5pX)NXVZ4b)wQw5ag)!8qn zJ_=FJ-F>fQjjE{p^w@5x<;9`B*M65Azua2OZQNI3+*cb9Ru~V~#&i|NbhWWwg|S|3 z3|L_dSQ{Hw7#r5cj1|U=wee|%@o8uMwN@Cn*2bO{#-6n?X@xOqZLC^htXdnxRv5$9 z#^xV#tpU<|IAyrm=Lm&1b*Ab#>*H zA)}?r%ks)mlSa$2>!HfEr;L?VD`zNItUO)nM=ns_)_0neYrfdkpEy+-&RwcJZ1NPT z8M<8g#OTSAwSbG)x537(t=h|R*KZ=_ReZ-)nopEW_m*k>3T-Dy-E6L%Si{E4>OG6J ze020UY5c={Elw+BhvM$QqgBQBbmIKAzJ>K`iTxpzdqSmR~e1R<5;pT+c zHXrV+n`5=Soy~Dfel;gXx<$G=pWPMtdddW?b29xNIdgrIa{N3u!~TBZ_C1zudeZHtC|F=BHiB0q`RjllPYP*yg~30C7OUglReuh- z61uy!dxuTD`c7!p$|bbU+fjdnHvZjx(|;HiD=bBQ_b$9FNy4yL?ZdRrz#lG#W-OUY z`C!(Ip|7@lqP*(G+0Y54-M6h7{SJi|`0FDr&prD{=r?&&C|9q%FLY;_l*)xK?FyaJ zCAD&z4!c7CT<-QEbHCmb8gVJTmRCxCG;~~2_uE1vkA^OInq14DygVAZ=#1myUnUES zsp9so^L9)SmUElqMYrFC?ik|sw~N<&6#CWjMEcvaqpyZG$e2XA<;!!S!+%byeB{H9 zVc%9rpxo{EMPVsVx;;-DV?T^B_HFF_Fvi}u@$i7IrS{8R))CRZ`mEM!zxUVr#xj-e3NULv$M!Q@yxnK&i=VC z;+jhP+!&))#4*cLx_#PiX=0nAi=6#?=e`Zw@5Q~Z)-;_NTfDxuIe7esX2^y%$_2tw znF_sHEBD%x+Q`e6%BSw9F~cjhP;PS}t(nr^U55qxq%-k5eWm4v_oXv2O&Ti?j!I`f ztk_UF{fQ*zulwI9w`lafnLn?-4L1ue!bT2a{sV{D@LoUU6o$IXTMR zUrqDuHp>QA(em%U*<)UR^`-LcdwWg&6Sb6=ui9_!#ne@PH~*k{n$CUm@^aH?Io5|Z zkBqXHUq;!>JEQF7qfz$q)F^xTYm~7*w0Uimy?i&Wj%~ktl5xrt_UtjE>O?B9h}>&3 zW}2jYX2?FXcAw)D;ropVovh_cmK-nzM>xKC@Sv$T$MO2Rhs^WAj=zm{#M~+5c!51f z(QmtJr^)l9rb|-Cz4sk6=e&4d``aHk*J@4F_RHTqZVrAiLAheS6Q*DO@yh?KonvNx zQB^tT$8*f>822sXrvg? zx$)5S+4hN1N!vW0Y>ufq>kH)__2-xdab5e#C)n~TCAA!DxpX(3uMq1v?gKX##6a%) zz>OENkrP~r^;}~(pUuT}->f63reLGqi z>&YXJhbm*8dA6fttUouWaEx{7rCUR^4%Vv!Zac<0c4kUf2kYBM-#W&+H|`&fu^z54 zcbNVb>*QqZhbv?Ke5vLLWvr{~ed)d(V7)!N@hB~?T7HiV`rG|>L#bUd`iT4O%S>v^qVN@Jl1iR$=l`S5a+`gQQPGF8K--h*xMxRozuN&m#y+Th2zojw#vd}?i%>y z@D{26&aOY~b9VQREwbodg!2BMwn*p?;mQrNZfcw_!=6kYvpoDp#YNCx&bJ%mnuRYv2gw z=dbojo%cp6-;8xYQnquPGSxvjIm_{t+;;zGzTGLJK)#*b zR{3xykz%h~EAPBk&TN?Cp2a18t6+*>b^LSu$|nAgjx(jKVjA~$9P>dnGwVPTfuEmW zt8Pjia?g&3qiUG#LmFxMqd#k!Qh&Q=*0wCQ&B}6a%`i7jX;b`?`|alyLQU^Rj%|!X zb0vl2mQ`|_>y>M1J3C(HHh-6{qrC5V9`i7DJ>`!=@|k1e+8i(W&98YHYI*fO1$1Em!$NSpO;1gNR zU*n(~nYwY-1f?&d(E$;y52bTgGVk5`^=x|xi_!j)H>uBP#< zk;=y&e`^w_8m8Q-VP_LN?I7hpMs_r>KJTae?Wp$VtI@rci?#d4RIb!hIimR2=E-+G zls|f}wMn1Nl`p>C!o(@#>UX};%zU@6uhuErySs@y&%Kv@dab?rb;&j@FL9uwnRI81 z^5wyuO`2(&lz&Rl#dP1bUb#Zet|ne@7t8%pt!^gmDfe!eEPi)W=lT+@)39B4lktdq z_dNJ%3-fZ}E-gP?y@C07gNv6NKB0z*`u>uZM`iuOgw1p35Uv+0Z>}tGXHJUVDs9@o zbJxtG>ZMHA>F&Lwz;~t0tZJF`8i;9K#;o}t z#BuAKIpyk@YDvG)@-IVbo7tr*DR+Io)_ib$w!!tBv*tPzb$piczBB90r&nhxU+uHr z3`ywtbF;zJuQfx<2V~l4x<^k}ewAvI*;&Sh96y@MOo4v9_B}$Gh)DZ9d#)CS+fwzipp%tBDoq_}QDyrt@jXdv0tp zAN=Y#=GaEldavVSF&j*+UXCZodK3GNYqRi$b>`Pbj>B^AFu8WSem8ux(>zJ!c=X07 zbGnxs<7by+%!A!?)P_vs1Lnvi=d0Ek#5^20Ps?)+7V~1D^IObLF^R@5(DLy%U*!FH z&WDwjiOIXc`Qf0AyFO^gVy%`Xj-r;Pi@wX?It4w3D?UP8UBjzS%+pM`$5{ulb+ z>LS#|>Lt|6>L}FF>MPXO>MqpXUJt_S!CpVY>&ISK!s`mTYqjD0#|7hKBr@Yf<&}R& z%aB47l+#y^mUgYjD_`v%C3iQEQw|KYL^20LL@F-6Z`oyS`Ga-6#WZIsQJ$MwxcV*^_zt23fS* z+1WL)TRJsz^T5}!_ekgU?%G~ZYmc;9=*Byz`yRPB#?51$+U${wUEMs^`_n!0Q8PDp zF@HC5c{6`EnEAWG%-;=W{%$bycY|@BCsUdSn$Mm2yHP&<&SnW8d|%6xbl)m758qRs zdVZTcJ9$^R;rlzJ!0bE9|HRoTD~sM%ejL413az>6>gSG7I2i8zZ=Z_ z-QYS0f0SRctkycoPyZlyhp$ntvf!NL*|AnRb?LLxchfrMSW&0t%TDW+qtcy{4A&g* z=y*cfy}v=rnZFzDH$5LCZ+>#^jJ~l&X5@2yF@HDeFn>4rXs>HwfBZN~+i4emB<$Xd z0m^xLt_@o_;uyZq}4}0bDpEsmiA@H^P@I-}*4KsT)|S z++uJ}vn7`sSBVOR%<99AnZFxtGJiLC!})#Y!CU9Ix0jD-&Tf?3>%?b!otVWpT^%nM zw)W-a$X51pXDfR-wUxbG+sa-JZe`{HM_fOB{M}&Y?*=n}H<Olq=P1KD%FbPebC;dd4CgfF0Z04z zFDmE23+2c8%>3P`Q@7F>bFbS&_0JD^!cFC09w_(98Da8ubv(GxSQDPdvCZFYu2zUu z3cno|C%>6GFro6}wNJu&j!LRr=U(@)Ld8B*E`D_XvbjA|vOK_YTR*`1wjE(R%ny$C zxjq5&nF8iB1fVs{AbDaa`ItR>k4w&m4@LO-41Lish%ykZ! z>l`rGIbgdk)pZV->l`rGIbg1Hz+C5mxy}J|odf1N2h4R2nCl!c*EwLWbHH5ZfVs{A zbDaa`ItR>k4w&m4FxNR?u5-X#=YYA+0dt)L<~j$=bq<*895B~8V6Jn(T<3tf&H;0s z1Lish%ykZ!>l`rGIbg1Hz+C5mnPV5s9J^rV*ab7kE|@uX!OXD>W{zDgkMDBqf|+9% z%pAL5=GX-@$1a#TcEQZC3uca8FmvpJnPV5s9J^rV*ab7kE|@uX!OXD>W{zDjbL@ic z_ioLx3%1|EHODTPId+x39J^rqjb3x?f|+9%%pAL5=GX-@$1a#TcEQZC3uca8FmvpJ znPV5s9J^ZI%drb)j$JTw?1GtN7t9>HVCL8bGsiBNId;MJtcB*-1vAGkm^pUA%&`k* zj$JTw?1H=e>~idanPV5s9J^rV*ab7kE|@uX!OXD>W{zDjbL@hdV;9UEyI|(n1v8&1 znE6b>%x4NN?d3BCGoLA#`AosgkqTyRQ!sOzf|=VC%-p76<~9X0w<(ypO~K4<3TAFo zFms!NncEc1+@@g6hd3_>#yp90bYRSNI12~H9EdY=V9bp;I|s&`i8FOz%%wPM2WDMTsWgyQf7~eRM=M>ERzhLJ7 z1vCFInE8Lf{I(9}w{R@-`2tWjt}N{c5n;tJ3E+XNWeVD z0_HguFwe1od5#6lb1YzHy8`Cf6)?}PfO&QW%(E+Co?QX+?26X+ z&aQxYb_L9{D`1{o0rTt%m}ghOJiDTGyt6A{o?QX+>-GjZfyxfNQlJS(yrD}h>cK1A)IjD#7<=^JY%U`=Gr>inoPR8!4 z-2dbpS#EQhqW+Pgb7VnuN97XstStLtUOd!6Uc4z@ou{35%N*~w^?u(a`@A+MSJ@>` zy}tH+FEYuqACsE21tPO2i1e9xA+oCh>QGRS~ey`jC%2;q%e3w_Re5#8#-`PVtjad0oB3+d!jh;zvBP9@B73DU@U<)R z%~yBbyF;%*%grCx-5T{(vQ_5M%q9kPQ2uO1gfi-<$-F`t?ezR{uQJ-N_VSW4`n`DS zi8Abozx|!^|6%XF^?)6f0IhMPiK#SWrZe zCLn^KU;`DUoqe`|SWs+W!ys4ydyEAv*naa~vp)OTG358heWCZh?#=U$?`JaKS!>ps zJ$q*MVLtfz`$p^9nH&CJvV48x26Gy0-)h$lRbEwjs9#n6&`zdyLi?H8msXwkE0aIL z&rE&>|1m8rkfR~$mWGR24X6*ufEp7^6Uu`c?hznPnDpY1QGIwCZ5A z5@y_0$NGy_!t}Y3(Mq`I$H-_UENi=w)j=!avYR5Km9Y7e$Y>&zTE??Yv=Vk06q)jk z{~4M3dmd6RZ)d^C$h3d<2a&Nmey94mKZ80&#?RaOM8^LfcSOGKlT&~9x4ZN587fDE zK=sikP&=XhirSY}9dQW#s>q+&wh0!A6?p7Er67F<`(IVllSF7K# zZo(a~Fj^$s4GV`mV-xO-RXKObsy=tj!nDKPvoP&*7cPul?!vYD!5{9zh4GWSaAExC z&Rdv%aThL(mWRsG_)vYcKhzGIAZj125ZMiP{I-!l;m+PRxt~jaXe0l_9lveVuW-k2 z8}*m^iUaK^KD4j6VOR0QAH^9z6@UC!UQFvJ+%-+V!kxwmcN)WJ{czVYjMfi#Aj4?= za5plH)(>|k!)X0*mokjj4|goXX#H^aG92z?PPl7Y<=i!``rP3R(++n#!?e$x&oFkm z3mV2B?udr*le?o~{O3+-n0|5BG>le`%F)nKeYADdPPofDZyzll*+rvA{)9WR6ZskL z%1-2exI;Vd7v<_N^%V!&QG94$al@|Si9d=nek%U>ue_k8#a-_7E8H2LaA&ynF=%OV zmpF`;7I%!pXlZfxIEnIMjFuL6n8Rpkakn`f?mSPp%U$K%g|7PC|xw9RnU)4(FaL0RIjz*R0qg|zT!d>xs`)FOs zE*e{860oQ}M@to20FqMA4#tzJk0#Y8|6+XM zr;jFWcRs=Rh9ANmu)f})d}Qs8dHt;}=wwVgccv#B)BcK&PBF&r=bv>p#-DLdoNA1p zcb4z#2A(7xh^UBwfB6leTY{PF*>i(@VrhiKK|8{-o#5}0v|775IF zMvDYyoTEhoGyX3PT6Hkb1zIGqwCZ4K)xkVpH?DK9)u9|M64ghG1g4!&4|&*__J`jy z*%-S69(v3ee^z#wYK)(s_Mc{q|ErFiZcM+9?jM=)sdC1x>NB3z4&z+yGyY|l=R*GQ zyvR?UBl*wsrG8QVhwbh$AE=LJAN`^o#fSD4H|#2&_@g-Er{a(Q%8R|fg4PdhGXJCX z1M^-$>j&n2fz}Vqdjzc?nD+}>KQQl|vw~I~%=-(iI#^nDFz>InGe1vNKCj(!W9rY? z>hH$1^U!@S8Poocdp~WA-L30AZj3*DFPvtKpOXeoHpc%;hdg9VzqTGc$(Z?H<-8YE zpZA5@;XR`EdB4am?;ZKW`$&HBo|6B(ztk_vA8zx5*`>bXKs$;L?JI8BRXp)WamG)@ zAODpX)=_BH5kuBjXlcQ$yU@~tSs$XM1+z{=OABWG)-`C=!P2U;`eA*DRvj#@I+*q0 z$@jmSm!qYn`eR@Tr!R)8d zs)N~Qp;ZU7|3a%yzj$`{xb%+4_jx9({i_#-FuT=e| zzT!YTX!+4!+E?7Lt9as%;*6h)KmIE(VH}!P9qoiXnkE_?@@raYaL9Y6yod2%T6L6% zabj9^a2P+PRR@Q0Rn@pcb424!T6NT+T;r4a8n?8g@l5*~=h)Tw#~(cx_^Iaw|MeWv zFFjx3xy#GL^O)C1`$O%7=QnRZJlDD1@Vsa82W=7giROs>M~g(y7v<_N_47D{cJzGF zzMe1a>iNPS#Th^KeBr;IuQ1P>Rvj@6^Q38_!D0S1tu#2ytEQm_hxyjD)!;A>o8}rE z=4aDlv-&~1NAq@=&oj;EX#EuC`AqYFnCCOS7idTC3)nW?dbhQ z`+9$2SMM+U(fbQO_5Q+ty}!ab%Czc;b6AI%CK?>pC#IDKhjoi-sKH@9V_J1^Sm&5l z9URs_nbtpHU1VByl!x__Y1P5fs#CevSJc(9LXurAH*hV^Rh587Dr6U{97kCv9!hm>o5NPVpjX-Dy) zeXS3%tMwuNXnlyES|8%S)`!xnBZktdgQZmmOREl+Rvj#@I#^nDu(ax6Y1P4DpOT-8 zQm*|M^|h~|9qqqpU;8iYYX5~l+JE7v_Fwp4*nef(f1&lJax~ynA8k0bgJzuCM@vq2 z(U_AzVPBd18TOC4|6yO5_lt7vzo@VMm$d4LgS6^kY1P5fs)O-U`!8wLQO-Ej`3B=t z`)J0k_ScMO?YkN0+K)5-wNK}{(Egq0Mf-Z5FYWiGRfk>5bv{6Sog2`O&J$=~=M31@ z`3C;zTmnCJUV;CG^9|Fg!xrOH<&0a^XFRJN#<|*O{L3!Sh5X@pk)J$A@?TnY*rHth zrM}`oJBknOD{k0TJn=_y#!tl`|CJYefBE?#^S{oicrWPuiuZ-iwRn%{yo>jX&cS%^ z=zNU#kR@Tr!P2TzId?y*K6gLD(yD`{RR>F}4#pqueuSk}2TQ9C zreECs2urID4tFY=Rvj#@I#^nDu(ax6Y1P3i_lR0`u(ax6Y1OHmyB}4byB}d`)xpxL zgQZmmOREmXPwsw%rBw&>?=rY+8kWWuEbT2=nq087x?pK|!P54ErTGO*3k;S|nsKnS@@9 z7N$OT%&Hyko`q?jJ85C;a#t;kKW~M*aAEx9Zd(}tx$_pLU)+TYhdXlf@^E)UC_N8HjEy~qj>MIVk!(F)4p?&Vcg|W+B zxG?^37cPvSia-8y7cS+}`hlhO154`%mevm}tshugKd`iZU}^op()xj=^`mmMV^kmQ z7+6|Au(W<)Y5l;``hlhO154`%mevm}tshugKkzrM^#e=m2bR_kEUh0{T0gL~eqd?+ zs2uGW)kix9mevm}tshugKQR8F9Ro}22bR_kEUh0{T0gL~eqd?+z|#7GrS$_#>j#$B z4=k-8SXw_SSH7h6L%FnmU}^op()xj=^#e=m2bR_kEUh0{T0gL~eqd?+z|#7GrS$_# z>j#$B4=k-8SXw_SSH7h6L%FnmU}^op()xj=^#e=m2bR_kEUh0{T0gL~eqd?+z|#7G zrS$_#>j#$B4=k-8SXw_SM=MA5(fWa<^#e=m2bR_kEUh0{T0gL~eqd?+z|#7GrS$_# z>jy@|1uY>MZ5K3#U}^opXu-%&Y5hY|{lN4WO&M5PKd`iZVB&^04J@r6SXw`@w0>Y|{lL=tQTdBO>qqs`(1E4(154`% zmevm}tshugKd`iZU}^op()xj=^#e=m2PST4{lLT%tshugKQQ@{pVIoFTv|V{w0=|{ ztshugKQQg1^#fy9@s!pN<!3jcOX~-g)(j#$B4@~=L?!eOef$;~eA6QyHu(W<)`i0gHEUh0{T0gL~eqd?+ zz|#7GrS$_#>j#$B4=k-8m812e`e^;Y()xj=^#e=m2bR_kEUh0{T0gL~eqd?+z|#7G zrS$_#>j#$B4=k-8SXw`@w0>Y|{iqzR9Mwld2bR_kEUh0{T0gL~eqd?+z|#7GrS$_# z>j#$B5By-z)wMFcpqq6{CqJ0+xmX9QN0ytpH1N0hSg6ER69L)~Z59cI#J7{*OeKb2{7tId&BMlDPL9;{tOS41eI^U4S2j$ZKfTalnODhD% zADtsfTZD4_M{@+GU)nFDy`p`Yv}33f_Hm|Z0!upvmUav*?HD-h6HPM(mUav*?HHA7 zze#=Vm!%y;9cjnF(vE@gNBd=I$51Zq7?^%(zbx$-%B39xOFIUZb_^`-7&x2*WZExF zJBD&;$H3B#QMvZZ(vDF(+Am8xhH`1gz|xL^r5yuHI|im-XuHGo7i}h(IG`;K6CX6k zVd91sIZQm!7=np2+Cwn$N0SI9UuYG<(q>XQ+DxjCW;#qeXuHF-kG4CEU9{a{{6X6t z#!s}CVEjkh9j0GsyTkNX<-|etiI3VLZfc)+$}ahmKg3^tk}vr$Z6<6{uKrSAaiAT= zhxQdW>?)r4qd4QI;*bBzi}x!l^w-$qVC?ZR_P7~)JdHih#^ejlFWMwup&h?Bm4P$B(g(D`OvT#-U%Fv#FeOHr3~x%{a8fIh%24pK~_jV3%_? zg_$8RJhlXEP4{ z;+)Mm^ow&gWBL{5dE=1BygcMLuOITBw-d%g-hLP-x!o{+a(}|O;ylpW^m9UEKR?XN z!#rJD=+j5Z9(Emf6=gmi38epF!4e24km7B;lacc zjXan*qn!tnFFjx6OXH1vp)E)q%JqCvA8kRkgSH?{`)K^Z*hO0q#vil=Vf;i}5XOJB z1!4MywjfM@RZbjKpZKU9;->bAr|c4E`9u8WC;5{9YiK;y^o!5A7>%*i}67 zM{&ka#UKBb7w=b6=&!NI!Pw(t>~S;pcp8&0&CecxEBCw@d%p7W&@W@pud(Od*vEsh zj}v1bKgK?;jD5Tr`#3cA{u+B6j6FWa9yeo;r?JP`*yC^Pc`^2U<>h*Rd48?j^KR_p z!Pv)%v5y~PA6Ldc-i$-PSVv_(4l_M>p?;?4F|@;a%<6>pGd;h-Zl>ot_`^EN>I6So z?-_@Fp}}X&`zvVh<>i_Wsjqp4b~GQ-zUD*hYCgmt&4>7@`7rd0^{ur}zce3)Jm%#g zzj^(T_q?4j9`g3XILYmX@ss-###QcT7>8&Gnl0X6>KEneFZC4%+EILHUva~(;)y?s zGkz-m_^-T3!;5@L!wZ&%7c31gc!Fzq!P4-8r3(g2w+@yT9xN?9SXy|nwD4eQ;la|v zgQb55OaBh$&SBl#!(GIC_>EFT9zk_!k67}z3>EFT9zk{WJ2TT7Bmi`?q{X1Ctcd+#DVCmn% z(!YbHe+Ntd4wn8MEd4uJ`gd@+hbPfJJmLO_MECQcZ=$<&&^OT?JLsF}?j7_^bSIDW z?`Sh~{W}fgcAzk_dmt5){WQSm){-bS^vEw7Gz&8{0{rv;50>Rh&ao$Q&Q~Wm3_5ME97bnEE%Ck#)RXYxi>yuMoy0+Ts%(y<;r_Z(3bGC15e>?K$ zYpXYX5Z5FxC%vncYFzVQ+~T_GX;Y#Ffx+3{vf5kSV0`NtL$echxzYH!JBDU|JFu_uz2k;vo1S%(@rp}_Wm1?WzWoy{JV{A%UT4@8uGQ*R|B&0 zRgqs>aBEicrpSMLtbg{$Gb6uv&3@Uux-rggeb6GCyfDW3f*)IE{kD(Xb>~vH*^BM0 z&2q;!*}PXH|9oBB?2^{8&JM%&&Dwnz`JyZK$nH8Rwt3Dwf5^J;6xW{%_u46|SBiYt zpl!2y17e-;wrG}(-8HU7n|<6Q>)kZA-)6JM+4S>celL1_lkBivVty-)w$9F)Tf_WW zwM(i5~X&#!OXe*K-ZmN!OT_KzL1;UC2B3rkmQmo@t5dRC{; zAGXczzh_0okH6H;?7RuE^WzyQFt^^3>?hX}kBy=DR1NS$!^)Kq4C+XduJV*Y-;>Oxp%hFH_^{M2KLJ8jg7X-PhXp@SAPqu zv)?<{Wc#&@zRiB_>g=O>(dWyjUzP1MIP&6cduN~2jqzOfg$8*gdd2vSgRjrlzajoRqisLDE*pK{A}e37`BmAu?RpvCJ^146uouoW z?lFh47N2H(bJK3wX&-bp-td^yvKD>MG5+IjXJjXKkM-NNJuB=xoZ+0ao5^^CWv@-TRG$_D6>H2V*Q~f@Eld zz(Lm|L)QZidLJ2jA8^nC$WkdNZO zgZpfo(~_B=o@`^_%Y9Bw4tlw>@nsV`C%xyNW?bspIk{r#8OAU4?wmaR?ODd-|Is=5 zV4ZV}H^1-HWb8NR8h3f*w50tr=NrHK^XbXHUAh|o{M>2Dfpa<;|FGeO$vzkT#rVqa zyCze2jQscI=O-WS5qapsbCbaXB7gVJ*-86$$6NiG8+J(^-sc44XU{k@X?fj=#&f?u zJ$ZQjj>bz`UXj#U8tXs!c(3HjDUmOH;f7@L$MGBY_Y?Ysb>yF|{*CPhCs(W+ZT+s# zpycxY$65KGAGj?!_%H2^hgAnAbIy+SzsUw9U(Y?(%9l^MHTmR<$n_rRpA6|8x%u6< zBu~5@dGk^==~;h-)$jNH)TH)%cN@3cczSZ}>yh`_W=3-OsL1uVt0dpFj69-2n*8a$ zcy@8@`)Sg8M4<@{8!_3(tptyV^IlfBw!FCN&2Rw>srs-ILQN z#5!Y=?n#Zg@o(?%)IDkSacuLnce^J?)rz)Wd-B5Mx%$zE-PgW2xvOUMZAHHxNuM_( z@7J+sQm=3Hf3H(7O@7)a+C8A(wD;U(&zo*B?z7V~Np<0E#%=3Ao!sAch;gr#PbN3sKiK$$cjhGhwjO9a zZs8NjUn@5mzq5RHvT*#h#=h>gzW93B*w?PczNR(ywXU(RfsK7_Z0u`hV_!=fpMU#P zNwRWl|d^@{JZ6I+Z+E=lA2>%ndBPR2ga)c$sK zi_yu2o#Q&;_OnMN-EWEiW^?|G5y@Ha$9LA4WLPq>bDVq6t2-!J@7nlpaytzhm>l1G zoQ;|5YY$8gI%9(Is(S_`9}auKc=$yFk`I1*$oRc(1Cnl+K4$#Ur~%0~OQ#!m_`KU1BImr3QG?ZmL4c9Jy2MBps@5nVd;Uw(g1~}0SZe46mI1jps+MRVQGNE z(g1~}0SZe46qW`kEDcat8lW(9LeSK+T#y$uKq=?B4w`z#JnunM&zN~2XzCd=KLkxZ zW9E&Zsb|c5f(9tyMY51Kqv=OvW?b)E6aI%~gdeDp`RCs)*Y&Un{bh9}?d z@~m;Q_9K$Vy392m-)dyC@!V&OFKT{A^4Fsy588KB(xPVMF~@~FRhB<(byl7?I$69T z@_Sc|Nm}d~>wIw4UCE4*k(Zr2Ho0ck*#1#%#wAz1AG!0VxSoufbXmfx9dRww$rY0W#6YllYOwf?AN+4qr8uXjf> zvvut6YYoRHZ6ANr?B4nNamnXPqCZ#nxjUKlhv-kOmgAF|o6fg7?aJemJ@<(5tW$q{ za^fMcSo!Fw_auL6|Eh8CJ?=>^IWopMjHOItDdZ?qjzaD-K(1 zG={_2&NQ~en9nrk!?Td-SqRTare`EPJDHxH@JwZTroyw9=~)ZUV5VmJMBeJ9)Patp0|*Yi6gkt7AO1QLQYwq^|L}18QZfX2kP>bL-X$dS?x+{J|bIv--Qo zbxWNq*U7$b8`mxC|Di^i~-fD z?pw{8{i=;tMV|+La6|Qo^&+3RYoF@yEcWsF71vbf?-2XG(S$3jjgE>jDP@;d|9U`- z)mn%3tlqL|T>CZbd`WfHYcaOn*X>#Td{B(}R;@0rPCPZ{qT{kFswI~w!NWxX3!|7UxyrVbM@GZ;utvXl-}8TEe^8sUf=Y}K0o3RJ#_q$R^IZ?tFw6*|H*j$Yp=@AY;lzF?8C0eUK|$r zhYc^ww!1y@(ARoqXY3t$*Xcd7^Dl{id-t4+vgIenHpgDqI~&tBp1;+8xOcYVumh}3 z&Vr6Oaew1k;fzRUww%wLcV#^Pe2 zw>0LwsQuTij5$Zz^4pTJoiA;i7<2CQ_+I-Ma~}2P(d~>c-o8if&x141&&q8Nweo)J zotJI@#=*vi-F8m4YL^)2VdtKm{di#P*Qd94$r|pxpVc{h+b-G38|-Vm$wpnWxeKD* z_d9gS28}LT`Mp1N$(CKy+PLq}XJ-dqAN}9;*mJWskH>y3{q($SVT;(`Wpggb{_<^% z!z0gj%U-D)x#vGG%zp6mb7@I4Hl!sDOG_G-mNYCaX;@m)u(YIMX-UJy3#N@2xyDL zVQpzT<}g|Y=$ON39H3(kqkVvmIgBO(I_5B13Fw%^VQpzT<}lg{=$Kob&_3Gbu(Zoz zX_v#&E{COE4okZnmUcNT?Q;0EW1@CBEbVew+U2mc%VBAk!_qE?rCkn7yBwBwIV`rKPbn}($~4NGqtmfkchy=ho_)3EfWVd+i7(wl~*Hw{Z~8kXKPOs>(+ zhNV3XOM4oY_B1T*X;|9Ru(YRPX-~t_o`$784NF5DmZmu@O>|X7u=JW?={3XBYlfxQ3`?&W zmR>U~U1?a_&9JnaVQDwR(r$*O-3&{+8J2c4T+g+eVQDwR(r$*O-3&{+8J2c4EbV4k z+Rd=En_+1;!_sbsrQHlmyBU^tGc4_9SlZ37w3}gRH^b6yhNayMOS>7Cb~7x^bXfZA zu=Lqs>9fPqXNRTF4ojaMmOeWyeRf!y?65T1VQI3%(qxCF$qq}C9hN3LEKPP;n(VMN z*7t8Fj1i$sf&2 zew;MGc;}w;l8YZ6Xx!t?=aN+;ZZn?L__^eZF0sv{_I@_GW#hqCKD9hIS!Yn>Z+Cqr zdEmpy6B|FBY*v4W)v5gWWU^cB$c;Xllk7A<)*1Nj6Uo5yBaiuPcCz2%*gk%0-t#jk zYsb%vjQt$R*w2@Y{oKje&!dd}oXXhGuZ+Xon_PcWoNvRNoE+Rba(G81J>KnLb;7$N zX?H-JZ^Im(tY{nO+c38$_Z%PR+c4)ROGlk(^~1X$Y0@Olx8WU;9Qj6UGrT*Jmlwx2 z!#gEu)I4%{*CbaiInMqzyn~YR+mXY&Df!dhvCd&{SCc=U6W;|jSEk8B$DD2TTh6K^ zmF4FdA9Kiz&CIyopks# z*GY$WcAa!sI_a=<(qZYO!_rBIrIQYKcb#-tI_a=<(qU=b!`)Usm~1d_gvD^Dqb4RZ z<_$M~;^m3S4ohw~Uea??a!u{XyCe@K#~nS)%CBttaB^W~sPT6VA4#Sk7P)1U$w|YS zkc$2jdf0zMDO_cI4j4 zyLoxLo8QUnuf6Q;yq(vNcspb|*CW%f9-H>Fa{8-s z;-LD(N9_L`ze@nGf3Bjw5?tUSWXBdk2a z$|I~i!pbA8Ji^K&tUSWXBdk2a$|I~is+>HkK6!+dM_74;l}A{4gq25Fd4!cmSb2n% zM_74;l}A{4gq25Fd4!93{N(EyycaB|ufIQodDXbVv>D8|#tqMz!8~kS{&_m{vvGFi zbmnd2+m=sbJ~uwL?KI|j@7UoRXJsbM9k#{db;tG;e3h?;p+E zZ+TzHhub}QpUJsDoxgY__jA)qrRRy+6nJ*^N04sd)yei;XQ7Q zKjA%YjGy5>ZjAroJ#I|D!h779{;Hffs6O#gJH$=x6HnPC&hm%&%TMwm|CKND_@7vL zq>l0kE03`92rG}U@(3%Bu<{5ikFfFxE03`92rG}U@(3%Bu<{5ikFfHnay@s-Bjw5? ztUSWXBdk2a$|I~i!pbA8Ji^K&tUSWXBdk2a$|I~i!mG(+8{T(bZtV4qy&Yq3-`MRM zyFbS6r?LBQ?ENzK{u+B6j6FWa9yeo;r?JP`*yC^P&zG_1D=*hN>#Jo_Av(55_)D zjD7qV`?xap@n-Df(AdYPv5#A0AJ4`<&W(Ni8~bx%?9Yp_KS##?thFJJ|B02yLf);u z@<_Sz2rG}U@(3%Bu<{5ikFfFxE03`92rG}U@(3%Bu<{5ikFfHna;-C!N6M8)Sb2n% zM_74;l}A{4gq25Fd4!cmSb2n%M_74;l}A{4gq6qM$IJ-t$JyD_*Kg7W{^Y%>#!U{M zku4oF%Xo*KW@OK87x}W4)3Z(w&9w4!AD*5~-9Pe6Cr-~EUiP?^fAaOTZ2sWLXWTF? zYtbR{?)9c+*X8<_^1mUh-USw|rV;?7r~nv$@?Ju8oY{ zZGIOSyX_XtwK~`xKPWPGzwQ#5KAv=RWMa5q+sMT5!sd~QVe@Sw6T{PMMJ9%OzxRx_ zPYm~-5t$h7)-N*o+Pu^MaJ_AwvijJ1f1f9fu{G_`$kGjz8o1DTVFmI z8C&0d5t+Wc@W;r+?X}Ty{FASLZ1IHIB5o%Qj7+|2{1}^?a9)!c5|T_R(5*yFEQId*S5B{Fs=*NcqZP3JGL zI@s-UPh|S|{4J4*;iFeXCWh}`7?~K}eR5=C`09RF~(J?JpliCT?Ht7~3RnDM!rg~s%2_>+<8*XwUYreEW~icG&=*)+C8zh2oVGX47d`H|_@q%FLnG72Hg(>xa{9RRuaW8Fhp$Jbk8^j3ZPLdx&WubSHyQXpwk9on z+uFfaixVPaYsnHV;@BQh~O;F`$9uyLoz#Bj6bk%{5P>qRDR#lGx#{5xiszU=dAWco7k z(08qzzO^9x>WBXfTc+b#}a=W)Q ziHzN5_k5V!y|i^?>|Xr$4|2PMZim5t$g?cwuB>c@T*~uMx|!bx@p|8^{hQ8jg82Wm{ zV(9A)i=nSKEQY?`uo(J!!(!;`4U3_#H-1xFurmn zueblr)^GKG;a&D?_KPv8cox{^M(y7VKD6O|x~BIsh4;0!|7)HJ6#Doth{7#yZ@;^aahxP^Fo_zY%VIcSzw!ob?i0_?k4)MLS&0W5Cwz1@U zXY0G~oo#OPy|c}YzIV2{(f7_aH~QY$=0@K;+uZAWXJg+xn=Rivn=Rivn=Rivn=Riv zn=Rivn=Rivn=RivTVH(d{BQ3v-$z>veIIQx^nJ9&(D%_6L*GYR41FJMG4y@3#nAWB z|7PpAdT%mE{hIw^Oe&rQws~0Ras?l3o?O#s6tw?ao%I#^_%Gv=XIAGtg*t5t<;D7K zSP!p>vmoX@oi!DBjXf{4S$sBEcg9t;`=9C)hc$iXR%mmL%|*pF3vBbS&JW3NaX$2O zF!RCB!EBE5b1<8u{2a{YC_e|YIm*w$Y>x7CFq;GY%+2O2KNGV#q&VmMnV8L2ekNw~ zm7j^(eC20iHedOfn9WyyCT8=MpNZLgSQ{o-e0X3NjS%$A>tnJqsPGh2Qp zX14rH%xw9YnA!3(u{bBkGckKc{7lT^>1SdVPd^j0c>0-`#naEkES`QQX7ThhF^i|4 zTmC1u=X6b<#W8-?bYF^X7TCsT;^&Gs|9CwAcdZkclYh_9UIT9tHXO|O`O#;&lkT7Xuc}6zsBZ3Y^~<`ZBz7t zaqj2O|2B8|S+vbveim(Wm!C!3+~sG{Hh1}1w9Q?97HxBvpGDi;jbu=~GbeMKLCtLK{h>iI47 z*W&zZewU<=ztuNfew+7ryQji$c2BY2fZeypQ`sTg$A8nYeC?;Qwu9PR`3H|anYBLQ zDC4?^J(;~T`Y_`G&&4slca#8Y;Ov-~0c@{_#Cf8~qcef=j^9;u@|!pbA8Ji^K&tUSWX zBdk2a$|I~i!pbA8Ji^K&tUSWXBdk2a$|I~is+>5eKJkH-M_74;l}A{4gq25Fd4!cm zSb2n%M_74;l}A{4gq25Fd4yM!$12aDmm7P1V{gaU+c$Q*#_o@?`)Ta{8+*Tuy}!mD z2V;+qvB%BW<7w=1HumSp*q<+B&sSa^=99dBm`{v7@5VkJjD4IK`}i^Tab@h|&Dh7G zv5!wpZH(6n_k7*8*N(>9{V*n*)&390hgI&%KDcUk;|KbU&8GF= z%Xr!O4l*@A4OvFsLoP#^IDmJhIefaL=$A7J?a%LiCK!16(H3%@C~nEM%s z#c(w-H-C!pSq)oWygX-~JK2JXv-jQD{V{ewjop7^@0YRn*VyA=?C~-7xEcS_pAcK~ zO+FN2V&(Fo5JM}M50uLXSU$k=0hSN2k2mv2Ou2mcWlTE$VIJQs@B;(Ndfh$Kc z4vn8$GLms<{PF2`Fb<9D)*i(;G;aR%D8`}j(A&dZiZ6^Xe(}=Lj6>t1KSh=g_$eP? z`2foYSU$k=0hSN2e1KQuLzOsqxv|$b_I8ZDePg$4?EV563onIcq*?QpnxLDg5p5Nm=REU5%G@nv}I0dYJKZ-%kwV z;|$|_dQQytoN%S_wF@51-WYPD@ktFI%(nY*fbpt!4`ffTKg@V`(2&}2-U#Dfm*2;{ zXY746rjM#aob|W#QEk#k*`kl~fj-JN`Y502qxwQ@)ko(t{q;J={Hb{~x0 zH)HqN*!yDaeKhvI8+%NQJyymZLt~GvvB%ulb7AZ`GWOgVdrr%YVcCUc7nWUEc466t zWfzuRSaxCAg=Lr6$}TLsug_u~m>{2ef zu!q zPJlHhz?u_a%?YrcaTr^_#kvk##dYRywcf^VagU(A4CUI(z}m~e+RMP&%fQ;pz}m~e z+RMP+N1HP}zsAI0doJ>#y%_n@9*sO|??!&Lrz7v$>oFd*2lU+i$N3q5it~@=M#_JU zIaz1XwC`tPZD2o7GxjqvV?Pr!_A@bKKNB9tTRAZXM?cL3}Kxm!a8Gwb@mAVzjpqtI~nM^?qPucd!I(Uw@vpj5EI?Q0P7wG zSobi%x`zSQJq)n!VSsfH1FU-(VBNz2>mCMJ_b|Y^yQWZHEz~#mc8tA!W4CMU{usNT z#_qqd_siJ(YwU3__V^h4{T0T3uZ6MScVX=JU>NJZ8vNINHL%~Ok=NIKK7Rj(mHWLM z#(rOivESoi?Du;Z`@J8=^y{~}cSv`9(J$TW1?yff_`mnF#cz4K*Nd3wUN2bpdcnHa z3)a0}uc^`)llRF!p=TjQu_|W4|ZO*zZp>*8PY0tosjP-G8WZ-7n<#w&m^U-blaa&C31$ zH)FpS&e-pZGxmGrjQxH&W50LK*zcn=_Iv7#iQE6mJ(iq3{_+fbb>G7LyN{i9|C-;$ z@Td5VN#A-X|Fyq25eL386=Gtny$R*oo50$ez}lO@+MB@Io50$ez}lO@+MB@Io50$e zz}lO@+MB@Io50$ez}lO@+MB@Io4~%`v_5L@S*T;V_P;guHjUkuvHM``z8SmE#@-iW z@1wEyp4ipi6aF>6vuGbg``QP=+6Tef2f^A0!P*DG+6Tef2f^A0!P*DG+6Tef2f^A0 z!P*DG+6Tef2f^A0!P*DG+6Srp|Ayb;&=>84V9!?-_Iw$8zKlIz#-1-@&zG_1%h>Z} z?D;bGd>MPbj6Gk*o-bq1m$B!|*z;xl|H5xMv=1Uj+6Tef2f_cnkFIYU;-GyHtbGuy zeGsgD5UhO=tbGuyeGsgD5UhO=tbGuyeGsgDP@&w$s@FHxK8QNn2f^A0!P*DG+6Tef z2f^A0!P*DG+6Tef2f^A0!P*DG+6Tef2f^A0!P*C@{Qrh~JL!w|L9q5gu=YW)_CfG} z?>9c)#<2E5#6S!MX zYaaw_9|UV31Zy7zYaaw_9|UV31Zy7zYaaw_9|UV31Zy7zYaaw_AEa{KS7<$kZV z^-=pE%C!%IwGV=|4}!H1g0&BVwGV=|4}!H1g0&BVef;NfW?x3RKQG4q9NBM>^zX{~ zJ(BMFfOS`Af$cX@x@(1U-CYCg-_pYRw-_+{i{kI8*lSR(Jr1lr4*YBWmXG$er-QYp zgY{cSSig0I^;<_+zjcK5TSr*Gb%eby7F+%9j&k2;S-Ho=Soh0ONB`Ec$3YF->~P}f za%u2ZDZFgg(dD}aH!@!PViv2OqSq@w3ZEls|j?rwaAg>2Q1b_zS-@ z-s-3!$hHh(6_UBaSexHS)&tsQV+IeQUq+_HlvNuR$gG`1y){QsJ84hjZsoD%Y3C)z zTO4_3`SMHlH-6%X5#_gzI>30~aYM@+uiVGDXRq7J5A@pGc67L z4=jIR`2))zxEO~b%PujIU08Nu*@a~nmR(qO;i6rQ2Yk?YfHfXqjR#oc0oHhcH6CD% z2Uz0))_8!6u`R~m*DaO{^_}|aJFLFL>N~8y!|FS%zQe`7E6$W_Ou`zguzV(NMONG> zSKMI54OZM>#SK>6V8snq+~8u|WD9>}3zjWdwqV(UWeb)qShir%@&Sjvh4~GKy@mA$4tophCmi+`)_*wcEi5i@*jre<;IOx_IKp9X zVey5--lEL7gu~v#*3-nQ=!2MY`2))zSpLBB2bMpu{DI{UEPvo)9EvQv_$j-v?834O z%PuUtuK1rB?Q3TrPo>@6y+$>6ZJ zsIXRp!``C88V(M7iwbKyIP5Jdtoh)ux2Ui_gTvlpI_qZVR$}%#@`t^M>a#~tJM3N5 zK6@J3Wv?TD*aOK=_D1rbJ(K#yUP}E9dy5&YoAHNz228AqK8PuoKd}6PVEF^f zA6Wjt@&_))p~$j}pRxoKv!%gTvgIvd)9U{9Ms`Bg|

c)$mZ z2Uz0))_8z59$<|JSmOcKcz`t?V2ua37~5j}l^5!$@38s~tM9P-4y*65`VOn_aIx=- zGvykSu*NDZpNU(M6*tNiH&}6l6*pLMgB3Seaf1~%xEMFt!XMd!Web)qShiraX8uDZup4~L$ z&p15OX~?T_c-GS}4vfQmkg{&WhcHj1tmoh`SEZr<#$hf=Lk^6?9FqpWjl=CCxx#W>7uX^59`nDf#QN8>OTrXjw@VLnJ%%UVp{yfkHvORS1M zh$)vpu>67L4=jIR`2))zSpLBB2QJ2;$g+!{vJ1;DEW5Dm!mlq=)OT2Yht+pjeTUU|Sbc}pcevPh z#hG%ANmyeQme0hk$ch`~iW{uB!HOHKxWS4Wthm978(fT=Y~hb=!LkL*7A#w^Y{9Yx z%N8tK*bQs>l=TW6*4k-UZyAR*c*=T(@~}2fSyRGc&7QKRgu_}sWlaf(HGayP5)Nzs zlr<$B_5>+wN;vElQr2YfJ|iAUhwj8cy?;!L&wi)A4A{X)*md~(!hUGIXpJDk7%V$_V!^Kz?S$6SLc466tWfzuRSaxCA zg;!@6ACx;-Ifa$$LizMUeT$pMC*>NSu*N5>@d;~u!Wy5j#wV=t32S`98lSLo4STN5 zAJ6r_+HuNyUwF#SK>6 zV8snq++f8GF2+r^3cgus>~pxW&+XQx z&-upwE{JyHJJi_Up((K{`XHuU{=o7FmOrrkf#nY@e_;6o%OAKHha$@^F_B$Zc466t zWfzuRSa#vn*~JIt1y;UbjTu;D2G*E?HD+Lq8CYWm)|i1cW?+pOSYrk*#=n>&U;kLX z6d&p<-upZ+Zu_WB=x5?BBwS{rjLX=K<{Bu*+{b z*&93aJVEF^fA6Wjt@&}ebu>66GaVWCv;Tl6RVU0HsH_R8`<*eP@FiY+fM z!Cv3k+bL7-?HjvYWB13{{WK1C@ZUJZkAA6~{;EE4Fvef(VawxYO#iS)IsL|-`$_!G z&(I!uG1fUAb)KnpTiX8nBP;O1$K9N^`ulUnKb(CH^I1yyjNhN0UUX+$WB$wkPdWcP z^m52Hz)er5I)lO)?toFly%d#8(_pUjLkPd#6h>-mB`kJew$ud(MnrH+pWV;?8RK7NcD z@BBUW^?bp4zP#L?FWASe+Og-0av$ebuIGz#Jzp^67kjWjN5*=-3gx9jePcaelv6VnJztdT`QrVkv-;py{_T%) z-ZR7(_HQ)*@-2pTR0sa=vw4Qa`Tyi+Q~CO3etits_o>x=n=6bB`=+UODA)HpSbxhL zP943EimY)$9iKz&ovS&Va-VZjSaW!6^S^5(;-EPk)*N1lkG)SlZpNC!siQd@)*KFN z4kwSr{CZC9TVZh?2;X$-(P9>WgXL_deF9?@7h>n^@XZ9hmqL7iZ2KtbXtz zB}SBsX+QMEe$NR9-%|Pv2j5a+L4DPMi{-`oA%-b&p^lh#g3Xlv!=b&DKEuIIN-U_a zI&iVPSl{cUh59M&xGiJHA)Z#Q@j$u81FZ1?D__6Nuby|xSNHoU z#!2|zW#2^M@D1wU?iisw{BFU%mC}yt!^Lub`_DI2%8Ts;AMDJOcEWi3w>t_b_d535 zB-N*#V!8jVjpt%J?gL}3jr(BiJ{Y^t_Ip3oFZ9LARiE-=JN}Ky+VO8v#{Nyp*uTq^ z`CHY8i{+|Md9fWo!?$+)3|Vad#)^LVxvsUZ`m|Fl_cLd!Q*0;rkkV(`AwTpD4nEkw z(SU=`_U}a8XR8kv%T=H9Vmo{r@uoc3Pl*M8tNL)UJoxo*zez6qZ3=rG zW4C4OZQA(pHq(MFD_4EWi|u$HtsU>9vG>u~V`y!vKJ66CRiE-=JMUkZCZV}SRUHUzY(h)>iBrD_J6_ow=I2-z?P2orW@YPDJQyKg^eeb#pk(w4v5yn4dSm8~{hTsN(5+@#v} zhht~lGJd`Euno4T*2-#D9vi%>GPCZM)fa^qM&S=rKR=Msz-JfpPijm@jizxr0?imyhLmW)1Is$qJ;{GKyT?Y3EU`z;%#V^(fhS=4;9>TzjZ%nRSePiS5p|w|4zBp(><*TC_S9ibuy~=_8Kdba_+_?JVuFq5+7`INk z`P-XT+gy5YWrKC=rYDczw0iLy*H`XoR+4_^5!OATRdwvJEJo6%eRd;tTDWD^^`frP3NYSC$|}E{8868E7kokH9mRA zFDgg=ZF}QSw_iKGdB%6#_-N(mhVL7nIr`Sh`C)8~oc(2m^Rew0Z;{qJ z@9WAY&%ZWf_-75%GmltR=|8c3<$>zxuBh~>xpw+tjb|$(zkab& z^W_@p+@1beS$E5Em8~DGnO=Y8dg)JNPOltu-@55>H*b<&{OXDsN8eF9-F$~F(r#P! zoPI>l4bqDnH%*sMo7%eLL3PrvFW)l#V)%ijw$1CNU0a9oc=(Xg!r#|VPd#VDwAIH? zlpfr)L3+m~-&GdZ__#D@=_cthPrh2Y`K(&y)1GLQ{&V4dmCx%nDDO0_aoWH8MU{ES zH7VD8aP#!BW$RZq-D|7zy~~=U_ubQXM(87Xu`|Gby!L77x{I>P5qHinUDRQ2>BdE~ zDwkAOl#Y6HRH<~?la&qDU%$NSfKH`GE#_8U+`eIXv+|d%$9*`ja?ajclxKfGqE+v% zFIBqMZ(6>+=G`+kUA&+&>xC`LM;*|za(M68D~(QST;6@RewBgy{=G7M_D1D~4^6M^ z``O~kz|L!xn_u^KCGGNVWsf;;mkvK@t#sx)%PJdwJH6Cp;zsEn{XeYCxu#!f>5+}o zs}BFPa>SP{OQSE|GCgP1KP!JZWP0l*UvJ(TpSvvFs(k6Qwax#V&umiuZfY0fZrg8C z{>NX(7(a7h?eZI2KWp4((-kH1JNDdnEx)%++cJH(?~=+M$$hO~@4Q($_nJkOmAmX* z>b}j!>HDWItejuIqBL*&_0r*ozE=5r>F&~{y;fG%K4d}V_S2s!eKT`m<;QL>RVMxU z{nFwE(<+_&JYTu$p|#3SetTPGQIBUUpRQY{JharIGO)wbm0I%}mS3*asMOeZPUYMg zP0DYd+j7RrgJxAep1xI?T${|c&7e#!LIbN#548dU4NjDC7!8wAK!&OmU*Tg znY$CuRGDXL@@qTL$1=~<)bF>Wk7b^z@xR}eK9+f=<|NzjOqF@2c0Q;X&s3Rb>bR4( z;+ZP(OttO51^LX{K zeE!EB@;uJ^u6>@zJ8S$o&ttbOj>+@*&!djY^Z3g7N9K7P+w*YE8?DFnJ~Yqcg!>N8 z^Em9y1M@sS_R0R5H!54KXs3Cja`5{5YTl^q-lnbQjdWnAHkvomd1se2Z>0acxRvIO z^ssVE%^PXs3$9Qf(@wWvmgjNugumu_9PscZc^*%F_ToH`@BDaSp2sJfbkFlRc)PB7 z9*694exAqSe>peLW8WLj&ht2a_*r=#>x?}k&tt1;r{#Iv=Ht$J9(!+iN}k8+rk&`c zR`s#Gi0kq^K0mHcp2wdj^v?4*WOA=OkLy2wZJx)JF*MKPQ>%vLdHnXL!FeA0uRl1?V~uSG<#~K` zuiNrG9^HCip2zpv4#@L3VC=1V9($(oI~Vin=JOxU^EhYWLwO$eTs$ey^zUZZ$2x}phrdAzs7qCAg_ zPW*eG#|zJVGtcAlzb(x3IP}&x@;vS}(z_bB0Ko$> zh~Z9f=dY(i_t&%j%ev>>@0@$jIUloD);#QY*RI<2>|Ise@9utI+dO8`UfDd3tNqgE z@lb~sHjicc$J;!*4}Na*xOC(*o5$rdpV~am-|)odagG0Do5zsdk8B=$nGbCqqpm%$ zd7N|izRhFt$MzuQ&b7Ipv=cKrk$h6Km^?D{Ut#i)&TVHJ+eLjA%d0dwCi_K$jiqAHW zo!vg!JcgF|X!Gb@^@Gi0!CLQa9s}yVvw7^g{jJU8#<(<=kNWU_Y2YKSkM!T-Q^QAG zAL)|^r-qNXKBB<)so*27k0{J56@0|?5oJu53O?fch^EX<2_JENq@8q22_JENSvRg)_FC3qhzLa zUJbjL)U?j4J0>PIt@CRB*;ySctF>b!a=Bm;a@=hfP+Gr&i6UhNQ>9zLq`>ei0w;iEdQc72i# zKC1JoIW!%7ROeNncWL3HI_ESWofbZ-^J?*uY2l;hyw@?>H;2faFRNMiNm4ee=N7}R zXEA@@In{99llk}FOTl?~O4{^l4)5p4rT;u8y?LqfS#8?AEP9>z^ya9+^(oQ1)Oy#R z8O&S57SiE(ZIb;L+*z zM_r3h{H9E%PycNC(w$yf#~f~EtE##6axaq^xxC#>zlXW?vuBfYyLWD;@5CJX@VC9# zzkg=4{ zHrlDK8B=slZpTBV(BxLki%!j4t(X_ZF1uPW&#xP#uwtICA53AzJg=;j(u#R5y3dYz z<9?Y`R?G+X^h;&Myw)dYYAfdH_Tto5%+tBdX{?y133Jj|F;6F5(poXE_ZyYgig|tY zTNMxLp1`#s>8zO7zaC3x#k}s`@1wmw4{7o62j%yl8zUnHBS5l6!I$^SJhx?}4{`6r&S8vi2Zx`Q0OH z4-%bUJ+}5Bet++YwFfbue`@VPT<`ERYY*a%Z0|uv^xk-D4+@N0^TOJLv^&#YT6++M zj(=tCL9}7?YikdpbOYa5dk`&a`PSNl^apj`S$mNFTMe~7D;^E~gS7|gX~I5Odyu>i z4YPdICvOS2c???{Ve{B)Wu(nx;(0f09*+*YX`LmganC60EI~cG*k=jtUb`6UEa7pd zeyp_z8BfZ_S$hyi6}e^YLAYmJplAw@a_tJhoY&&P$5N zpjn|dk2#8k**sRrc);>epZD>A&Evh70XB~#o(0-GroUy_JYEc9o5%JnY#xX0x6k(4 z>m3Je9$)$%vU&VC`LNC7lTk-(9*to~Z5|8uJ!bQ`v*~f0$1gQb*gSTsqRzdF$BUIt z**xaIddlWe=M9#RV(EsBHjhtNY_fSAztqp>G3(6DHjkkLx7a*(>$276aqM6AHJb6M z<#wCL55M}`Ji3(JVe|N^z)qXTqj`4OJQmNg+vf4W$K5uM$sg^pdF*vZUB4(EuSf5* zc`Q0+zs+OKE(o5umO)pe-iF>2a+ zo5wOgZ?Ji6kY#CX)5$iEvmQ>ddHgwQs?Fn_<6bt8gZF#eJo@ai@0l2> zw@$ZtOu1x+&11&#J~odo!)Dq%UK}{f=27c0+vf3Pqd7K@nXAsVc^qC@-A_L%jPjWytmEcYqPJ-t?Y##3wuV?d^Bz*&$#|p`Qv)9$~ z?;6=WmcG*1=JA(xf7m?cpWDplQFynod7Lw-rOo4}Us~Hd*8Zuj&0}geb$?Isc+a(i z&7)8Cj*3Uz3mSPVx6NI_kUTbbbZ0?rN zud29Pa3{oLoquKSSu280*F2>G|MVe*M&B$#z+wB((C)}y3NJbxNIeVAS2*RCb=1H5 zHiav`_oiO64l5ktE%f z!rm1tlJmQvC&lk+&)*#2^aZo&YqwUR9QAf_qvz@MhWZ4G>a~Rz^i8I>i&#ZjIsp~(cU1AESE!3RMPw})O zU?g`7Nk+YA#8bbXy?DTZw%W?o52>|hEB33pKd|Qd+jM1XV@~Wj(D?U$SLOU}&NTcmt@0t7Wp3haLpXO)xSF*NyA&)y5%f(lW;@|xjbL7CcJmFG# zzO->EuP&NYym)lkh+Dp#cjibXX0N;vxM}7Jem^j+cv7XIR%7%kZk;8asJAN-UFyDu zOFvI7LU#W~jT*1x<~dwNsuMG4ZG{b7Y0_8T`f@w%%esl56?n|AY6O$#Yd=0RB!sJ` zyielN7T$d^kcXW3N_#hNW3h1=_gbD(j~naH4NG})n@kz?*d{yKTv&+p(pmKe`FC^O zCHoEidNzIki#>ep^B;i^o@Ue69NWj9bth?A$7R)v%{#zbgVRyf6&dvz?E?92U>ox2 zoJxO{pLxiwd6cVjVtvI0!JZHHkTYj@k59<24qX-+QJE9+&Zv@!=k7YBa;;ygKRLwv;Xejmu! z%LXaD;Av@YQ8`56whyitm$O7D{Ji7WKwcZJ@SvZIX#=9JDBQs7o>t(?Nrg|X)u>Cy zy$bLCX%w}Y4Ed`#wE0AkW;~MSRNDK?9CSoJrreE`D_`T&M~`~gFT&w!zeHo&lfK7e5xeE`Ephg@^$lfw=< z?31Hka*T%@<0QxU34J7tCjxTIU+5F$vQOAiSoR6~3d=sxufmYwvjjVB2yK92!@-Ld zee*bXIa(=jW`)j_?f6cG16t3fuFaPy9O}NAX0#lpaHl;7Y1r$^3Kw2`ffl$wG|;xs z$Ow|>2BS`I!YM{Arg4d`DjYDO7v)?c+spr+56DA5 zn@BNqC_z|BnHV`}i)#CGeoc?++f%m0r)*3#( z3Gv|DG7nctl@KRm+xOzy6BFVmUAM)2dVNA%?Ty&W!{pf&aWQ~``Es{}IJ|l_im&R| zHOQ;veZ=pET=xK8f9g3$r)sV8KL4s`T<=^mhCJ8Kd)(UR4~4&$3+IMAeH7j>{{)}j zxK-h{UAFSqpc4x3=-p{&Vx?dE3+XV3em(dy`Pg?;|G;n67d zBZYt38mfiujAHrR>xQ;&8dX?(htABY8&ER$3L`REH0>E%G4PMoON>{ckxKsa{p`GJ z$~7gQF)9l;4Lzsit9o?e$L~)ndDlm6_-D5RO3tBs-S^TMpuaf^1=+A}r zELQSGft&fyfZGc7*MvvZbH@()@l@BLUp$&D13IoXp78pioK$1T41 zE=a>TtIof{f1X*Zp{hMi0cLwJ0*21@?h*~@%z{;x`&`RF;;ANN%9xdCT*tw(1izxd!dk9*{$ z?Ye_4y+ zC-mVr{DeOIc8!fza-W%rIMsk~CGWfUy@7dzKIRqk2z|+$abfg5C9ihncjLm97$v_Q zRnGuV&_|wtC+Gvm&q$E_o)7UT7!j-F<#$~0aM;%z_O+AAZz(%he!rwGA9q9PPi=Bm zbBv!H!S&=v@|M~9I;1^*rU}+QxnEqrEwJPNa{*xd*MMS z$vIMT*(b?4QgYcR$rw;_Irk)EK*{CYljKavC5I$AQ*y~6;oq>2&+%{A$LDAdIqac* z!k9Y~`hy((qd&;eznm*2haYmTlpKD*-^+cbR>lAEpM_5aq$2kz3G!0`GpOB)1iZ!V z60O^3;U)?fD!-4y#6*Sv+_8>cdoNYElJ_jS_(R0-U@hdF-g4OB>n{WH5gEV8w$n7kUY?O&EXzKW+{hhltf?0e2>F<5 zGr0BFmr6b|^%P^9P=ji?YWgY z_WaA7y2Jwme5#iFbpUym@Zmp(`BcsIa5aq?*@ScS^Qn3?%Rb82I~6yO@?RPU(WHUX z4VSq-Rek&2P`Q@S_Bjo`kdn~0^q3&J?%$Zu)~Crn+SFnN)tu;4bywoW$UCz70yd}m zR2|nnxss0`>{Io`IWNs$%F!0NS$6k(s&xMUkF(x=t>ooA{f#>79xA*&xEOb=8m4gB z-6MHaox=(r8NY_*pTbhc@-u~{F3UCwOB*b0Y3NJZRyhSM`-j}H?rUs6j4C;0E)s_F`Nh;-$L z=PE1wy(zZzGB~c>T zC*=ICPv|QQee?l2?4S=|*vB6*WcUmix@ZFo8&)5%jXog9e-1f0^vPj|9QMi4ukIL+ z?ii=;7(d>Dv>yFnE*<_tpCFfg!j8hSPu($Zy6jhn4rKTY7`kW!3>yw!$jO)7H}zLX z>ZqQVytC{$=1t`tAVLU%J^C{fm81sb;=@mBIpR@cUw3RX; zKT}xh3fV?sX+ua`3QOCHFX+oYA!lI7(FZW}(FZW>pbuc!#~(0c_zW1jXafuzumud; z=mQvhIppNfCx;z!*e6H7x??=LW1PBU{EDxH@et$$Ec=AM!m>};QCRk=JLXN7{p!$% z44);~VT@B@*nlm_VcW^qk6iojm1|DEoIE=C{gHPv&XE)UmGchVEs2__))prQkC0<+ zK>h+_%|KoQ!zcI#j5P*14~(@3>jN;>B;-6W)+*#Yu(Yk#Phi=nT0bp0`mprT2QciQ z4`A5GA24M23>doT0~j{Y2QbEuK7g(D^P3#&lBKWKPslNLhkdnvLM~;BM_|l>W1MRJ zgdB5*{Vu^y!un~+9rK{pPs@&D-qiXDIb`S~!A`>Z2@D$!Uex*t`8U6m{tv$FIQcKl z7uHW%*Q&U4Vw`6nx6YZsI9uWT1B`PW&R)Pc@8N6&j58X}YQQ)H;%o$Loil-P21Kj? z%RbdP(~_ePOCNmz!w&iYhJE}2Lx#_Qp^H9%VFP^tTjxw*^y!eRbLKaFbYNEV<_vk4U?<_6X~`Y)pw5|=9ml+>b0*}Fp^pSR3Fk~;*gzk^ z(l4r5W1+(EYh|MO3a5V6h}$&rQ8>-jvplft1cfWs$Sigh=%VnxCDnxdQ&`G`{7hk~ zD`XqRm$V_IErq3Rn=jcX|CbgU(UATz8mK&96J6Qw=3kWFy3jBEt{vpyH?i| z@=swY6Y?{KrLK@|2==87dGD*0!qT?l5pvlldoT z0~j`73mCT12QYYa$jPBk4m-NTzV7H(y~hQ1q^|B5r@Z%Nk6-Z!9n7V}U+7!&06V&6 z$1!i{SIHqm9|?AH>5lm)IesOF?H_z8-v3+j1@7=2A7XN@O9J-X_{O6}$^^V^zy^=5 zX%ld^K?Oaa)4qvMRp^x2yU^<>GjcTd=xI&I`{)dyYT2X3TK=2mySQkA%hO=LkE2TV_dKW4BO}f z7=1zqZJ`4nfZ;dB3XHMC2VnRF9khiG<_H+`in##B++dD?F=x<0Tj+oTVDN^y2FBcj z17L6h9khiGI0i;sfJi)|0bt|=VjUQ7COi=VB{Qf2^hJB90NwqK?iN2BXOXG zWv(iW+(q6(4h$X3rp!qOMqkpVVcC>@DU80LgSOC-z9hg^{CjE)+%{%Q;dQ zc?=!chmPbxVdSWsYlV@=k^_a2$IyX&=tzzgMvh7@6-FLQjul28LkISuBV$Nm}4|66-FM*98ef}3?0~q zj?77gk)tw~6h&g|*hd~a`eKJo!_k-F7&AM3VaJ%+ z;fvCNedMuYuGldr?3gR1gYhGe9bB+u&e_3*(t&;Cv4d;j;FKL)D;?NJ9y?-5IATUP zVoB-1KJwTRtHKeJ!V#-V2lkQ2j$9Cqm=}&*P&%-WJa*)oaO9M5?y*r*C-v> zSF!((y-YavEaBM8gkw(>j=fSi_C(>>E0qrHBX^O*7Iy5p!m$@C9gJV)`akx1*tGU^ z^rbNJ80!dZB9E~KS-v>V4DdzCk;l-1efWzt&YCO7nFMpC!+kMe+@HgJF<{)c!+kMe+|R>3H(=cVLm$A_Jw{88 zJ}iCo0Sr6n0~q%42MifL1BNd80EP|p0gUmZ58!WpS#ouc@teN7#|VtEJM61_jF3y2 zy2l8NIdF_q-D89tbB24u33d|hF?GV{1cnUfB1ZF)z{|2sl=y7 z(^cC6t|`UuDSVX8ME70)w*EBSGfm0=bjv6fc^>?G9LOyw`u$y6D-$MGY^yPefckgrVm69jbm*h>zc~@;E4?^;xY)XFqwqHyBlw9&DB(F+e^8DR> z+_~?|_#@1rj7K5ki7+QJzJ!c3!d%I?``g(=#-)-$Shf1D6T8E_lE%xla7;Oo;Wul4HHF^uKpjbe=7-UZ^;feqp^pTZ|Ly1#Dvc z*z+(poaL}yKn{PgUO*r7@V#>{_E)sUxen`v#TV8Kw8i{my?{;dg7pIWIM-plfE+wx zy?{RW{oWZKX9cvy84v3P`a&FHy+B*U71j&bM7-fF0)3qEuwFop_{4eveZ=keu19e0 zL0g>nuwI}qzlcl75vPb(=p%l=cP|2Yg0{#TtQY7Dd4@beTjUM$ z2R4yUSTCTDyhOf1j{HL&LLYhgz56OyFVGg}Mywa;3(vdC^Mh)O^#JPyY+{{o=zBQi z9uEEQ-Xn61lN^4LW1Qp|KRM=s9R8AH9=?0O%Q64t;ENpdPYzzl!7n*@BnQ9Wy?5t` zE8P)?x+AW1N4)8dxYZr;sXOBKyZ0d-`Jy}WOLydp?#LtEk&n6~?{r5#e)pcLV;#_u z^N0=kf8DVT=#KS4=^&P5JB1N5@^gg|hqB#w?+-iHH{G!w>W=kIcdUE5WBt?}>!j{j zKfimg+p%uzj&)vltlPR{J=Y!kg6>%Vb;rK&-TU^A{YZE0U%F#I(jEJh?%3~i$G)aJ z_Pg(X2jSRfb;rJ}JN8-KvHz;?M8FrW104Ic?%2n_`+W-53$(@chvU4VJI)Wf<6NOT z&L@yt=Md;y=acV#Hze0Jb-uzl9p@;FlMq*O{lNGM@g~;~-Er=Mze+CG56pwom+Ob_ zIHzGgm3>^V%lTIr*DH?mA?9DTmFow1Q8wlJp*zl#;8Drt`T>5GzFa@>J&v-8dk>EL zONc8SbBOB|$GI1ArNb||ejwg-_$Aj5-EmGvd@8wIKM=P{U#=hcPDk0qeH6#NCgh8f z<9fw$o=3i@wsQSI9x0o0{m>off8?E#%k=~KsPyIff$w*eP23Z5+;>90EBUu|K)2Qn z$gOn%*jgW;hk1Yu>jmV%STCRt?6}v2^-AfZf82LMTZ~t(hpI35hw-5;#*1;oCj5Z^ z(8qkhPsrgn{D(f~!*SmU>#)+tyy6}d+JXnU&a1w_8|EEt!2|e!P4EL=p%0$HALQT@ zyh0y5JMKYYe^L5~7u=6RTf~>+dKvqXYK!Oa(6@4Lo9rvTK zZz_G{0q#wqE%L^39{~HTYKy!<{=g>k33&*8yXXsT>YK1%H45g&rvkdI(y}Cxr=M59y zSyArS0XD{G4!L~h%YJU1ozJI3{=a#yS=szwJ?D--aPPX@ug|59{hkMV4Ayw8=jEaQ z?b+vl>$CQpU>|<{sfM#U;ii1iL39?5^UPMsMz_&m%`R_=+YPKod*A=XV{%wJKm@9Prer= zA%?%rxi$X3)$ZbcyH%^~sP+9(YyGW88sCFpelR!qt_9fo9webg`ai$cTE>Rr2s}D! z=JAYxlB0g#QDgt(Sq8}w=BBxPE*BjAzj&6x`rgX%eb$ff8Rd6*{}sPybiPl<@vf2| z?~svv;r%ZE)!rfF*z5nv_kG#>IALx5$GPi2^*vzp_w&y`&Mp6O?+5$G_#J)WjHJ#0 z@;zz)>FLZQMulZH1KbzJ(!Zr&r;q=ZYfR@m za=+KF)AxVoJ-Xk!&T_s3|G&%cQ{#80{*``1{D10iYJkW8>A#19-|72T_+1-$ZdWxO zGFJb`{yx#a!tYG|EBs#Azrydn{VV)_-@n4|F#aq2o~HZ1!0)2|EBwCg|CHY&cK$B& z=Zu-exu))Br7rcUjB93b!y}vd{@p#T`}<6ya{laQ>%*@-Qr}D`%#1nAYM+`Kvo^Vk z2B~tI$qpvveG5OZeD8zly|^(iO_CVz$T0W2Ju}QS3HU~=e1>@QN2OEor)t`)!Os;w za_g@4RgY0PY;<}0+U1|+c28SoGo8}9WxjpG5Dw%H`XF8h7JhXQuRjuUBt(&JZH#FW)OJ+9V_?VRD=6ylb{74$k z(kG>v>g9EM-pB>-?Zn`57t9^CjYF`JwsRl3XcF?^4lprey~5-|T93 zX>*-|?lhy2a<1mStEb7_JB_v@;bq~}U%K5sNPu+Pq$6tX>u zIj_fFW3cyCa`Q-HjwqOy2b?@k1CF_vS*LgAlkPidauXM`T8TOA*>f>vxRcn-@n|#G z$uXG1hRENrK6r=&wQ_XiYa;VR>_s+8glkP^Br@yFjbz_gH!W-SMCQCcvAn58N@Gsj zucEqFEEjx!)mSw0i*S#NdknlpjRKsII&z^;NF$(|fUZdw$k>-{fHx-iajJ0*$NBV>wTY zx8kQiHU=I&62qs*z7basG|9^DmMbx@gRR6a?+En_1n3iiY1tdF1E9%}Cr#sfAh_PW5 z-}au^@XCeem5-sgp?5{#s{Y!+>~Yj>4R?36A zc8?Zg7GB^#_utXVjgAsmjz{pr(j_&&B{#)@0ICS?sdN({m(c9lVL}HoPPb(1o% zLoSN`eRfm9cWt@#oC~7cx|8%ZMRpEZe_j*_4WXsmHyBApuyE}jMNv(P2L|0dC(`7O zqo6B;w0z0ViOKn5DF3G<^!TT<;(CiPD$=SRRV{x;1P7g^;Xae8X~Q5<;&T9bC0BXDVO6SV~L#sccP*wccEiqVxHwj#KCJ6RrRQN^w^DmeRhhd=@Ai5E%`yZz0|+& zVKKPW3>N8pNn3bGa1cnF=Cx0%20@)zF0i)q&J+3XszU6kmzlU#f|vCErnB2TIlR3m>L z-jiyZ_&M+@^=iD^sFQE2=y3KXZF}h*xVz>S(LHG#og3X+i|@TzOqd=+i)MV(Hcs^u zHEV`b#R)Yj^YTq%P5EFN`e*_T-Mvu^y>3vV<11)w$OiEx<$78>X&-I*xLypaJB>1B z4x$QK){A;Cnv&*qohB4rCptGxPeXr=rr;WD#hVRtwbHVN=5qHnA|P}9O6j^qQ-ztU zMZmCG#@Ex=Y1f8TqTH#poM>neeF$7B9#8m#>weiszh7A)+}3+@>EsZ<%=G8qP(-J7}LfFBPK(#Bh;S!va(K zED@Vh$8p^PJB%~i7mN8XZgR--+&uZXd=4gY2wy1Mkqd?`6e|Xv;Q0k-^G*4TLDr`` z`KMHy`E;%YVr`ctTq(&Rj;u0Y+-yITv$eX&F-_-*;|D5m-zt$D*<-GF+9S%i^?NMG zPnjbQ_5aCuzABdM?U*f+FaGQiUG@f_3!Wuv?YW?JekR|+7dKPvppx{y_!0Jh>myeB z^rt3Uwz8hpM|AGDkaAU?$Mb%fA+q%Fr+_j&ctyME;&qQ>G`jrHykOuoad*}g@_BO5 zSmo_4KIOkjZCY{QVLvZ1G$xj66{@bSzcf|cyc0u}Gdyh2rS_;?ZLD+}O%fqNAz9ZTXx@@C0MWsZe^Ib%eOS z)Rp@^KSR@g875psL;mH?0h&Kxh*+F{DtDN>nudx&qU3LDI7Rs>)G^sW@o-827rjuQ z?pO2_iTa-9kQvEn@?ZVLx@=)wq0C5a%e+2fPO=zYlO+2wRK7SKIDV~>x=>G1 z-zSRKjCbcF&AW?1xv%kFpEkU9Y**3I^%S?=f78+m(@PQoW(89%9J za*sM4MERqmxK8p5JY{fuQO%DyN1q6Ou%fMa`S_s`pE#CZg|rrp4_7vlUy0>3gy5x5$kz_&RlsM7?-`C zD7-tC@`n`C`uD9PHdKnGQgh?9*p0u6I`1N=;jT)w{$fo*4=zx)qQfcKr|P0~|AW-L z*iuSb^%qh5Pd{3`WEYK^T~(a=V-~e|e}ZbB)Wzs#f6?WRA=L4yCbBHbNz)5O$#ap1 zsQhA!mOr!HzdKeEX4MuRzx^IV`F2$hHEZ-V!i+E)cDtPTvs+^B+36gWOj}kgdr+I# z9uFk5N@-DW$Rw_HVl4$uDJfFBt>RK=yr}2p;^Ner{rq%EW15ttm~ed+#Pv8eWh_xd zoX8!@xob_==Cm&)KFp5hfdwlE)Y?)|=m7bBZ=D^4ai#%uh1q5EoNTV81QFT%$%d zF=h_1h?_;?}d?s;w^HPt33vaSV`HW)8`2E_T zKd-V&$Mj-Yp?oxE!f~E8J*_xDtP2%Bwu8$bOD*;;oI}}?F6OD3Q;Dj-ZlUz$2XU2V zDa4}Whbc}k%YoyPi!bh%XpeiS;kG5INWVLhe0Qcdd~UmlKEqsm_wD8A7A+{lx--0I;AyUPD&hQ)AL0$gd5&-A-o)8@)!|ti!?=OxI{y4PF*m9m z!y7_Zv0v}r#!p$}xaBZkUb*Erk6q=Xc=6XITsdm9R%&DjPi(u8FQv~(>2jUqZSps% zYlO9@6vub*?HseXPtI9XtNl`5d2l-4E9^&)R}JS>)xCIc-Gh{~TxI^ebP{_7U!YxU zZyCX1W7+3!1U>px#E3pPjLVmar7e^1d&Ia7;C1_BsmS0n+WoIRdFA*UbTqISo!j1t zn+(28ORM*#EG^scvzQ|^v)=+*U$+@g^4dn>zFX;bfkqrTX5oL>@2CIxt?>VOzZH%e z2;56SP4cyzYc$|SdGAn~NqGpkUAtHs+_kU59rJ`zvJT4?zUOy}CiE8xI^B24m=9BU zM&3o#HteCop~g6p_kt9b_kyU(kfi!A!8y%IW-=OmIfY)yC#Tt=au=;c?^JrHhB?iZ zz5D~a)Jdt2Oq0_LXcc5s?4L}h3pvcTh0C(%)z8#%ZVvNlmeCx(txqDdM`tywjM&VnlBW}YZOUp64)x*+dR9@WUskjAl-fMnH;2faFRNMi zNm4ee=N7}RXEA@@In}`T#rbDvF~JqSXMCA0i|H18Og5pZO;tCtx%=<29$oI_!ZZ7W~1r>Ql$#bpeSw<$)YmBS@Wla}OTqTp)!pBV? z9P-MjaX6!yy--fwGuN=dWA!qcgWZ49?*tss4uxbe-;Bzo$1kf*wOeN}`)gVCLJb#D zhsgA1r(UUbkB7%-Ysd8F3b*%k)8!#`eUi@n<3tGgbWf(6L(`eh!nV-!^qF*@cWKSp z0|wE#7CH3hqtlxEZl|QI<#X%BOQtoqY@Dv)`{IppX)GW0;r-IUM??Ck{}!JbKC<*t zpFB7O_^Vl{r zvCZSc&WUXvQ`|{p^H{HEBAdtgx4sICN1u;hgvH~sq+f)^V{nSk!s4;B+b3c17+T_^ zuz2*Y`axJc7OeGNSUd*QdnYU&yKa9gEFN3CzqP&-*FTkbBP<>_Rd_8d9=thGcxPOg&Ew)Zp*D}@7hSh`JSp!BSv(H@ z5@Pe%qgROKqn>K~Rh!5CURP`$3;JBPd7QcAlFeiA?u#~$)s9@Sc`S7Dyv^gLbHO%` zo1@OzJg#|j*5+~N*E2ScaY@eDJdQ{gWb^pA@M)XJl^&;T9;w<%o5$cM_5hp5@c{>H9$#JBZ}YezcAw2-jeC1-9VPd!C zqn`cpE}O^WVLNRe%iY{z^XU7)-{vtQiNDQbqfFav9xJ$Svw7T~d#lZ3K$$Hzk2~va zws}1Gho8;k^A?+I9=$qlw0ZnEa)Zs|_8IGK9_!6rXY&}jXsylTwD)Ul9>;cFWBDlZ zj#_Q=cy{6{n@7!SrOo5I`73N59Z64>Yn`84hCG8x`N4;=? z**1??ip{cltWkQV&Epo`$L8@tiy1bLZM#mld92lIn$6>JPj8#Ylast`9uF>`YV#Pp zeu~ZGSHH3u>k8^howR!AxX0Xj;%;$kNk0){ruz6fqu)odYqOyH$9+$Q3ZSy$YyQj_Lre)o2 z9@DJrYV+t3(AnlO-@}eJkCRh(uz57IwzqkV&DYlEvC4ziHjjl4x3YZH`#${B=JCk; z<~EP3T$v`!=$9TsN$t&ExvX^=%&gw$!zGToPW}=5gPnS~ib4 zU)8XAtedjB&10D=)odQ;wXb6Hc&;beJU$!jVe{BPuWa*JA!8-WM=`2O1)Il<4a?a) z`Zq6Q^Ej?wDVxX7YfIQX#vUqW^SC>xh|S}kYlUnc4}2_W^SG&a0h`C;RrA?A7Oj)V z=CMWF+%}KZX6LkdT)i{9&0{#b+dO_bnZ@R@^{mV`k2SlvSw8C1XJ@o|yty*H&7;_q z*5+~M;nX&dXHBh0WvP9La4Sj}%U7^LV0>i_PP{v59OR*XQ}n);VWDnfGj+ zb56H;&DJ?**^zj*&N=OpJZ0;gb20lvw$3@(%G_n^oOAKeEw;`%>w3qk=LKg4t*+kHUNPbqKIC78$VOr)Q9H=iSioZ-jG)98!oPoDSZDNc4Svwn$P*rob$ z?rr4IqkC62Ue`Io4+C@SQE#$qQwJU79$~rlC&lk+&)*#2^aZo&YqwUR9QAf_qvz@M zhWZ4G>a~Rz^i8I>i&#ZjIsp~(cU1AESE!3RMPw})OU?g`7Nk+YA#8bbXy?DTZw%W?o52>|hEB33pKd|Qd z+jM1XV@~Wj(1?6+gYN9E!}n7jGa}N?(NL2R-aMLG%}htANht4ko%U!=2{j3;ehs1) zue}L12~&^kqeLgx5o!{)rCv!Bd<{ZPLcQt}X+!d0Rg#rWOH@t5*G8Lp>CPdlCZU~vh;zIxuWAyGPQ1wHLT+fNNx0P_l09nV)KHUP zwv6SeZxb7+NeEaH%cJXDGEkF{KF1CA|5%bylTi2cCBCnFGHMcvygtl%c_E`FVMurR zz1C)bMoq$r`*S(T%43Y0gxh1g^ZUJ5R82zEfP(DjaZ}YK6lrA|OYg+0nuHrJ`vUJq z#HgBtjm>LmV_hRuO~StQ&$Z$`&#Rh*8f~jm@_s_qBxET+mO4G%plTA*om@`-<7cRv zgj|>QP}UbMRZYUOgQuw6p3JHyVYTlyYI(rdKuvK>e*$IhMI)a zm!j!xhZKaGgyw#sRBz~Sgqnm_N6%11=c$C6gxQ-9klTVagqnop^;c7_qXC4PgeK9G zY4q~5swUwVxBAqqa+s<~@IIcD*1E;0nuPI*hiPr{#HpHupglhY9v%^;Y7)|9U2k;y z5Ta@l{`xf=zYRI5Y7&ywY|AgV?p8Gk@80-u`F_h(O@e2sO?*1@C{>eCWrWGs?rW+h z;kU9E_+gs|8fp?!ctvo*c@;F&Bvef!zccJ}IS@4oRf1#r%dX=FY7)G!+~5>%3o~jG zPA0y>*|-;@CSmBtqg<`od`3;e;^Eu*qVG0FO~TRU3%J>fBaE7a6Rv&v)%eS*CSmKS zVw}`l-j_j5LVS=B7!a#!5>AY|84zp=uKRri4&b+sy`Q z5~8&z@>@|a5H$(O-Q(!9XCDnU3CU~3P|A`ngqnnS-!Q7Xu@0doVMFbcnPO>jv?J%Pz!JIsh!>eCXH3?p$%kb7Sk*X%)!{lp5zj3juCSm@hG{&XDv8pDa@4gIL z-Yt=;CZYJUP%R?WB~_C!dt_NU_Ue$TNvPgu5UnV+Mb#vX$+ei;jGm)v65d|lK{={+ zQ8fuQ<{hW2_wuTmgpQrBQs2+}4Adl?TYi(;tz8_5ngsWcv7}{hs-Y%f^~M+~_Ta6C znuO0&!YSX`>V%qv&c4Bvzt99iO~S#yn9gTkL8wVcwtYQ~d$E^LlQ1{gbP8H`TGb>x zUfGw5mxkPfj=bxP_{kg!uQV zdF$;URg=)^YGZbvwO`dF?7HQ}k3X(dH3?x6YuUZ^Bvq3Tcs-EY`PWu8326tM<61u_ zRy7ITkB9MNy@&kH?y#8BG=@JkXdQ@}gc5FX>@#GmftrMdd87F2)tro)g!(N)c*Cr} z7&QqG?w{bkeP%Ig64FlI#fAI&F=`TOWLnC9PB_S@N$4FvjE~Cugs4e)GpG`;N))MT z627L3GyJqzRg;kY;?IW5&RA8Ga4PbtN1vWIR87J`*K^vLhL=@M0*xw8E4Lm|H3_TZ z`%=nZx2c+hBfNmRKc1&*64qVVPIoW#R5b}z9v`KZZwjfJgqszv(AQ;04b&ujd3J+N zq&X9anuM^cu{8RGhlZMjCKQ8fv>-W}jy#y3*gm`+pu&H3=zt_n@>*{Z&mur6%*}VDp8lCc!+km6A5=uWAy! zs~(|4pGv5jgi4<-(ZVtp4Adly&~DJRnI8jDlTdkWEFBn}M?+15%Wtt%=|Pl+nuN*~ zBB|o53WS=3Jq<2Wz@njqnuOx<2kGMIC4`!Urmy@cz-1SqCLww1*;HuK2|`Um@Y@db zCQXQ{Nl4r-H@$p!Q`ICSTI;VJP7|kU66(zzsp zPSqs*RqgrRBhj4Rg*BhMUqlg`~h zO+vvgu@qh;xrUmAJF{Y`OuH)@Y7&}%h@`e3N)c)jQq8|aJqr#X)FgOqKTN;oSwyHw zc$;=B-TLA$Yp&{utP|%_MBFh#O+x2+-RSe3E2<`8wPykP)cmHZNmyQ;wH%LQRZYU# zjoUm52FIwHgyz%g8b{;8RZYUd{V$APOPyCW3Hw@9<9>OCs!3>)WgN%N-=Jy|S`_l- zzcSBIH3`WJ>}A(PEmciIv9G6irN5i1NeB+Q#$Q(~(@>M(eLISS-Tf+~CZTuHIBq?5 zih-I0*MrgAvwKQLO~U%Iq5QRXBSuZa{Yht7#wnvFp-ig-Joot;Moq$;hpV_}hCoJ5 zg3o}-yejmps!7P1s~#`v5T|tH<`ZfXn&;h49baxE)Fe!KI-gEzM+r3vUb*|w<-L~) zH3>IH6{Ut7Z>XAt;D}S&Pe)=^O~S7^qC6Vpja4-XE)`1|Ek%T?N$6eau5r!lf~rZF z-p7OcJe0o~A!`zJF@o0wY*IA|nZuUy#U(RUO+rxd-JD@ZJ5`gg&GRHrIGEvbs04YFW#Kx zag`@CY7(+(fgEeBV$>uo$h($LlsdquNpMN&#k)G6Q8fuwA2edOo}sEHq5G4Re0Wc^ zs!8}XZ>mwOSe&X!xb$gJoR87L_X-l>H(brT>f_GszI+gdds!8ZI`A=HdXs@bC z$aZr&)oSIdY7&li*+Ao_k5e@X&)+e1yIxJzBy`Mho+_PsX`m+I(8X|?v%9{5nuLBQ zV(3{bKM&L-G=COLc}f}@Y7+W)xk*(Y&4w)FhN{wumx$A12f!T=gA5KEp1lngo4pX^MLgscI4y^}nha(_&Rk!lNcBwDs#^ zRZYU6+8+X)-#h=fUjA{t{NsB0$My1$>*X-<<9hkW_41GF-U(HylXU`cUJoUH{N~s?;V@-JNN(WXT3M(NvdN`T1|hY zHEH9jaHb*2wM(~>D?IR82czR*7ll72%D~}nZwUJTAA4^e?MYRg{WlG0H#0QdjA2%s zK}5k@RccfO6%rz%pn}FJA__)P6XSpkaRi5m%%U%LhW)R0cv%05mp^Ga zc1}L#;r->OfAg#G7SCC=f7+KOCgHozynpgH_Z=xd;Cr`De&U|bi?{yp_a}GVWAr_E z()+(Ox##*fEBrO5gx|IY&(`G3?*H;^Zt9tH6*;pP=DY@&Yhljmt#QgZo3qaWpFTI7 zGx_SZX>*qS={Os{c^mPo*F32YR=RM_Lpi&XGr{wW&c2-8*_Sgt#iYymz+4M&ALkp_ zIOQBq&J)k`JvnDw=WKFrFwC_u*QU+NHO@hA-a~OV`t|Ys@3(oXc){K$%*aE;pXBU9 zY?gCWXPjdm_NUK7hcjKSE%}*_Q_fnYekM6fku#8^>`IHW!(8inn6_E%*Eo@X#UcMu zE-~e*c_`=7uJD}na$c>@UMCNnrOdT3XC~J;<&4@HXR?dSfDJ&Yadk85GBt#Qg3+=wto7H}e6Mai@=xfop#PqeAhZtkB?=h%! zJx-f4epMEaN7<>I*ZTbEzMKcmd?K5~k9bNenX*(nvzhoAC&s&&@gDz+nFHb)F?oo3 zk$uKsIZL`PXG}9TRhFnTG4^4ug}JuIDd$ZypQtR+=8RLN#asb%EzGrPvvQ3SZJ;=e z_h=h2^FYl*Im5ayXI1y*4C}s}Z7n8U?rB^LbI+`C%6Zm(Ip?}B=U87Jl}F>9Ha%fzf@Y93-usdi_LR?gaDUb8Q;t6+21hf z#<|7YaIH9WOpQ~n-MQG@xuhlbwK`ioZLYxn&U-H&(>nW2r|lfNMd_kxzP{GT=$;b3 zyu@E#^I7V1h3BD{c9|%3tFzR}XVkyKnd_oWCrZ1|ID5VH6P?@6wbAY~Y*zcFT_#F< zO_X+=k%!XHS9p$m87~v1&+80&^27bP#wp`*#+mhH{OY`WuI2t;ZB{PhWulCui88)s zQf^1wa3+#_bhDfh3Y+}E0NzY}AJ`+vFb%;0i=Y07=4Dfgopc_{bm zrrgJya({2Q|N6c!CJ%&_d-wkl$Lk7(TNj9}3#RR0Bk%A0{#Q(#vL0y4I$=g0s28uJ znzFuX%DSte4JZrs2U8Z9YhmiI#wqK)rmO=S)>ouOdzQ7<44c({jZ@ZXO$28u%360uoU#sY%KE%1>vl2qz?iExE0=Y0Q`XN-Sy#`<1M>)V z#hg*}NKZ%h)|F3z7`>gEy{;PDk{}W#B-71Uk%d%5Buhm=^_imm8axHOq zzCiuJ5l?9)lb>p5HWNSNlxKjf0Tj;tKdupzho~3X=N``U6w>AXU!Li)Mp9Y0C&So> zxfbTy8Yk9rDhv1j@{EzSlhWdT4s$JBZC0*vcrHVH?*BZmfw}+JJVbw$eeU5r=b|j! z|D&%fKivOgY^W^UlVR+@Tnlq;jT38ZUCaGH#-40)|BrE{w78$cTnks5m1`WHml2=) zKhM!%?*BCpF^|YT_wbl&lrH!Gn1hrb?*B1osVp(ah_M56EzGqwPCOIPwcP(>PLxgV z|1sYwE$;a+*TP(zHY?XSJjWys_kW&m!rcFB9%6o%eeU7$OhD;!|Briv^27Z<=6#ig zdoqk2m}_CKt#RU+fUf2K&wD1?n)`p;zm*pEbC_%4YO`{U!+R#;bN}Z(6U_a;<{|E> zvd=v{?)OTU`+wZCl^^c^agSG7;yJ)+Fm?`J@9@*ORvg#XIOSTNGo($ld8Q@ywLDLl zwpqE@U(WkW;&cBm%(I2*Je0cPxk}dIWU1T9Qs-i9a(^!MHX}}HQ=b3GCinl+2gKOn z-d@^b2A4YL`Hb?+{lB!)j69S+JX!koWa;yhWh{uv1NZ0BpJ&7=V~yu>Dhv1jGB(B7 z;oe@x$P6xHf#+r_3-|vrc4p+E%q={JRJz>%%Usl#IZ8|(xIdS9W=5Pc2lBjBHo5RyKmLPcgFb}NB>}R@sic{Z`MD2 zL-FOif415E=rzXhGp=q9JnQa;`1~%3f5ZHpcre#-JuG`+7bYFjE8&wReh=G@*!IPw z6aN-FKLhcdPqFhajxoJ;q?h57k&leuNB+cNr;qf;@H4LN(>}kEUgl>Yp7S|GdScmo zTbzM2mTO=>fgP^$l1|nG>16%bexv-4>5847R^gFO)_;_X{41RLd*8AjDgNia^~s5e zD}Er}={@T=f4u)n@%xtT+uXTe5P#}}A8J0b`x#<>`8W3YyW$0N9oG|%J?z4ylkMej zmDln6Vn=NIVy7#1e#FkF*!dSn{cRoTW%y*Im+|{ZPaJmo$hSD`_mQ5MU;gd<^olo@ ztB>>)j=e}v`6r!hFNdqVq?7ePI$1xq-(cVAik%-Z=}<4kAsy=L&ijsj4E49)r=Q!x zFIi)aW`~bHM|{q$A83wvdnexS)8A^Ap8N#y%T8FSJ?M~)#r*PbuI2BKK$I0t0!nL`aSIaDR#dVyFZKF&&Bi$ z{>`->7Y&@_3(oNc=lCk&eTgr&9kJ~X#BsV}=SQ65i#X1|!gG8%T;mINzfC(DU$(FD z1-t(%PL40a8JAoS=lFtie3kH~#24rIBHZ>{m~l)w;T&JE^QrJ0Uxd?M;Zs}T|N5VQ zn%HEICy5`i^zWO!mOWOyewtcbF9Y#B2d%@19!kvF{ zwij_+UWL0J(vI4TIIcH^XL}LudR87>|Ke;f;$(Zl*&ifba z{HSi7PjTMAh?Dm(IPYJwGu{^z-}j5rj_+T@$@>=^`O*Cg&ifaf_b)igrSVn5)ju6y zZDc!Q+ZX5kYqTSM(ZYHEg7f~h{3Ab^ZZA073(od}v%M7V_JXs$;A}5A+Y8S2g0sC! z_+*LS!`WVNwilf31!sFH-0KZE+Y8S2a=7%D<8vP$;A}62yS?CSFF4x^&h~<{z2I!G z5(ik*LP>Mv|szhr#ruQ5NP{(`N86esnU^CSHQ zTTdyDb(Zp<`inRYS9u-3DR#uEzX(tL1*iUkQ-8tEzs4i;A@#_(b9u$tUW8|R!P#DL zwilf31!sG~*#~0g9L)mR# z>~zJ>kJ$MXlTO$b$J~1=^@tspH{(+eV%Lw@^(KyVsZVj_hk6!s9rak+MQeG=l>I)( z7hyTR#=noxqu?B0aE>oH#}}OA3(oNcXF4T(63+1j=lFtie8D-s;2d9YjxRXJ7mWVO ze((ON_H(}#=lCLijxRXJ7o6h@&hZ83_<}Q?60W+<@kMx!FF3~+oZ}02el&h^d=Z}G z3(oNc(_iQ}u-jMcc2^nQAH?n_V)q|0{epgs9rrge_mu4S?w=W7e1m3&4*DZ z*jk>@urIALS)PKVyqEWLP8Lcq?h57k&leuNB+c--#*e4hy6a%6Z6Zzou7et z&gT&6iLn>yDgUIy`%vOIT;(O5tOwG``mz0n_)fQlogXpjWc`y4^++7*k9wqi;T(4l zjkVP^?*6xqwc1|1`=;$4+BY)2e?$8a{(F-dCgex&Mdo-2Vf! zZ-sxux&H^w{XcN-|ABM=PYKuFC&w4({vYDlzV=z={-4o~_WLQ^`4s2=AL8WxAK3e6 zGXC7%Ul)5LX*=|t_G&(~-?*n9QWwDaz8lW>-EitVINx`daP41peC2T!dp?#97pZ}SClG%Z3%~sp0>!Bzsy7S z8N#y9jDLUV-7fXu`tM=4i}q^rZ!`jH&eRBS>T&PGlum|IkHgl>+P9f{obc4+aO!b5 z^>_(?Xus>Y&-TBy-<5jH_B!(I*NAUfWykiexBgs=?t9L^-7fyj-A|mM2dg%Ot%Xxd zKBVQNPOQQIS7`bFPWuw)-Rs{o@y*?ys6LQwx=ZwdN4IxPy!F}JwZ!?wu5WA3dUS+D zKk@UBmN+N9<1Njf+HDo*mQ}voTyXOyio#8E6%6i_#e%N|FKwc z{JceRPQLQS=IwhgQXKwHJks*>nFc%jop|JjbV!dlq(gedAsx~q4*4bD#L4GH#38@r zn>du4@)L*WAC#Xsl$-Jshw;IfAr9jMCJy5RE_No1oylTnvgD^P`RPl3dg8cTisN!A zj?1Mut{=s5{V0y>M{!)w18KRQ2hwsq4`aF1UW()PQXIFJ;<()v$L+2-Zg<6T|4|(G zAH{M1Q5@QQlEo@bFCIO;L&Oh$X89X(GYPS}}@_Q?G7(XN>vJ!d0MQQn0d`xkoe)_0K#o_P7qYm?V9cl4*;<>#B(j!ieed3T# z)T82%->65$@$^cil0pyY==hy!!(`9rpYBq2hC&aoO;-!%r8-?-2hM$KQvDCywiexLzFg`mie| zok*|4Ch252>12G;Njs#I_W8|p`FrMv>oT9%%lwm0Jd57OXA6EH*us(eTw;e=7;MtpV-U%?|RNIL$=pD z&wl2x-yVxquD4(G)M3A!-X}hG`^OHuo^zRai#KjCoVfY@Vt)BIdEoEFgSn3D#bFP- zFzJw`=QwVP)s@=Ula5f(&JkC5$V}Zj#KRC_$A#O z*W@S1JNe9cfc)qD5cyd!UmWA>G>~>N9=@;2v?uQC5{dS`C=ZVtKC)^K5n-7kQi85X$=oj=4 z>V$MWz6hruDxC2V>7|_3rxZbLmfobrlEhk7KObf`zz^(KyVsZTL~&-`#*<`a9F|7Y*@ zz2@l`{H@|szNcSshd9Ff3^zBV>hu;ig=h;fi1KmUe3V z|H@A0A3MpJf5k60NtZaJmGR*WPy4g&C{8WoitMbj)h68$n{40WZ@6%O&C#25uUP3Z z3cvWSO}f=?*jjwe%Qo#kchR5C=Dx(K*YH9;ur3Zy6R!wVfUV=@O{pCcz48JUl3n;E5AKUGB__o6T^3;3V^@neX_dW5x_WoyFKAZaz zr(WCNeD=@V@4V_i6u)r){a;_-ZvD8M6wWXIrVkL8c(b@Kaq6`_c_B~4FWi$~@a{(6fj&X}!aeJ^h_NO*rF#@c=Vc7$>v1FLCO%J!6qEN&Lb+OE$Zti`=$jf3M<7cnm zOz{i%B~HDzfA?13n0U$~wp9GW{XblC=foeEjNwoD=OxX>_iv#%tNrnD%|~zgKe#V( z>a~5u?@Rn-;`eDY(wfY)A`g=#Kgrn4IQ7~-%Gj6kCR5%%>m=%`&$@~_>`Q$nQzsdx zUfV}|4W+%3X|EyMG}?N|wvIk9l>U%Rn`WGPZ6Ez@DE%#&{x)QvjJ`T#UyVLIl>VGd zpUgP*+CIk1P{vC#<7LP(6=QA4u@+-+DC04iF_m%ZwSA2Dp^W!r#`}tD($S$;?+n&S^2%4LR4v95|HuFqt_mWm~V$N-zGEP4ml^s z?~rqK#2w0fp3Iz_aq6{wL*7%O97En~qO3!?A0=~7$vE}eKI(F+-0zaP z-%aH`G1_4&@0HP3Q{{e|%snyV)NA|b3sdEOoy`4uD(~shkEZfoAAN1AtOt_0r)Qjc zZ6AGks;oDXS#M0`nk2@-RIXKGtW1^lOfqYdj8m`eV=PWFFEig3X1z2uy{0;Plc`*5 z#aN#z>#=0kR2ipU%lt9Lyo~+A%q3II(S*l5G{yW2$6PhVygZAUt1?c#wvV}Rig}s% zh5MKUa#%lUITe6ob9D>x3$=PU^Zu)5?-%m{Y)QI{KDDa6z;w% zc7LAD*(V9F*RpFZOz1Hs?K^@OmxlXVw^sUpUtr3inz??DfoS&NT_)^;*`?tdSJIaITjW?zNWK z>#^CKYbwI)wXB~tM@M*5IM;i!&e-iYeL!gT2buvs^S;U^{T?X))jj_JezY( zOL)DO^|R)5@?SXD+p^=ex|n+f_X*+`&NaF0d#x_!Uc|gi{KBah6wZB&Ihr`!>zJcw zacT;}>$R+((L0J?IQ5Rgt(C;wt4n`KPE92H)=Fa50?f1S!oO)m3epVo6ty<>8Ab z*__Xm2(Q<&e&%_X;up^6T?$8sF-K!R`WnyEW^+ChBfMVA`kCi-ieEUN*C`ww$sCRS z7%MyvoXz=6kMMde>t~)fDt_U7-Z+Mj&nm?+)_I;eoAa3@;q_YP=8k!pycK4>*D=o$ z9&6){IU0_+sw?ZsWY&Zkr(VnYxno}D+QO_?JDw>J&T|OnXqaaeWj&nCnl|IqYgylt zho^!2-QfA&G~>w{nT@gu}r z-nf4E?1irtzj))N-AB%Ssra7vFYP8@yqEYVTQ2La+HMc=Egx9cec{UIi8r`^S$EdH z&lMjTePg5d{<+w7D|UT~-4+wnq1#Bj=aCzC%l3Mkc+Gah?x?@pS3LRI4Z3%3zL$8@ z9X9Cx`r7AG>XgkV3IB&PmUVC0q!r(_c!TcD z7wslq_759$KiK@Q#1F(XzZV|-K5^-9&3~uAow#J(_b#@{_gDK#4De(arg9%P7{~$%X;DeI)1-)#|GVQH(jr5cRhJ&_lHl7{IJOL zXJ0$=)km%0J?$eSKmOJw-M22hLGfRD(2{P|Gj0<9Y}F;*+I#*|{Ka9t?)$I3ReZy{ z*6Z$g)g9vRufATl_$4c8UfO+)^}3&|yNdWPcVDl&>zId$pY!$gx>LWkNPNJuCEd5L zTP(i#T}!%GT(X+@$zRx@d(tlJiOYQ0@cfTwe6*e4-H7Xac;O?~?vV^&KgN0UDQkDf{BYz`p0IYe#{Hw6!>?Pb z`~2&6(6y_6V6E=b-JUG|{J*c+Ex4c)|NhD~yQduR4Dq+_S+hH8m1l`xy?@+mUbBn% zhI7~Io`1q~#3!${c6asJyNd6A*plvu8}<~J`%A;~NS--T-WAZNB(lRT6gzW|0! z_~Zvx?e^dIj;z)Ia7zaH)P|FNJu;j&|8|Df|1bl+U(c=3m)7IdF|{R!e1Kd_*i zoH|jws9UMK^Q|X|-+0tY-EX%(S$ylAt8}OCeyX^ve;S_G@=TWUu4w)9vJc(gKIRSo ztT-3$c~5)e+s+kVKJmwPxb+)U?QE_>&f6~50N zx3^2KyFmP%FW=s7f69g8BcFLkyJ)|!h#&c?yV~8J^fhr=Pc}S1<{2^NUD0~-$yeXf zeq!A*&J9=H++Kg~zbO90uDGdv)5Avo{Jl4}tDbn7!XG|$L;LcbNB;F0*SD8Fa^&+* z`bGP@zZ!Yt{^#vIUmE!fNB^wd_~OydhNt|b{nT1l$j)7NT-Uy)y;6Mj*RN~${HJe= zSGni9_NDiHNBp|of6_kro8J|`_p+a~|N2i?iI08c_3a_6Tq`c?^M>cyJhP^}D_Wl) za@aNP;={+a{XbuRb$iNJ{$26Eam`ijSAYMLk=MJbeZgBte*DkB)Bf^~>lFUC-}!dC z_a!55d(oBco4-HuhktNI`_fIv_@^EHt@gx4qs=Rx_b=^j3&*t9ea~g>otyqbcJ_Jn zW$i_881wn1?y~k**WRG;&EIiZ`}A{f6z}rym$e5Rag%uR;49h>zvDJ>(K`*#*Lj9c zc~_)&&ir}be(T-8SDc&Py1ae&UcVK8?6|MA&;0v4#B1JkVf);hZWrHh@dfRNo;mVA zUhw7iu)BVv@U71JQv2##M&95n=eIB4WQ?=xzF%y&y>a9hTybvu>%)Gh`0e%Qw443o zo#I~{5PapBhsW%5PJ6&p?o#-j?>eWwX`Q>p>s@h9`?NdE?>(>G?d%28hDAR%MFTb~ z(vLT9_nG#-8&}q~!)Bjq|847q;)C`*x&6l3D~b2N@TB(2eMY|O^b^}N?;g|o#%E7x z_q=T6osK)cz3{w|_doTx_V0#~-?hWB?Zej^uYKJs|EazEv7`O>yyD~SS3f=SHUILl zcC~iQL-&!7wU_>88 zKcYSTxYc#-`fD84-ge$-=MS%VZ@c|=BX4!}q3yQUjL+*{^!fL+&wuU69~$1(p8trE z?>qk=+Fe&3d7aDuzJ1)nk-N*^)-HU;$U9FS)b9W2(dO&k|AuzKM@RnN(gWK!ZMB;6 zu;I&I-#+L2BR}@}uW#4>^D%E%9QOM5{0m2Z*K-eQ`yI#Ud*%5?Q=U;YD|){1ucz+O zUV7=eO6x@%J-5BOUt9dtdv|TGed5SFue57Bb=CNM_q*x|?eR;-eBS!c+qcJ^Ha^cO&x@M!%%@q=^Pg~UOc8PeU9an2Fof!Fbr-grx3)WNk=65};-T!4HAG>tb z_Snrw-uuZbw|A^E^1rXQpgnw}kx%}`ubb09KJpK5{Z;eBAC3Int#59w+IzJBu7A3r zdF0(A|JmgA&1YXV=I2?jy1qH~MNU}!=yS}-)B7%do@ zP>dD~O(;eSh9(rF1w#{x(So4~#pQWsQ=UmSD|()Z77R_OYte$C3B_o^(1c>NU}!=y zS}-)B7%do@P>dD~O(;eSh9(rF1w#{x(So4~#c09MgkrQ{XhJbsFf^eUEf|_mj1~+{ zC`Jp0CKU4=A~d0xXAitrqkUKOd>Ablnox1jf}sh;Xu;5gVzgjrLNQt}G@%$R7@Ba5 z6Iw7dp%^Xr7Yj#53x+0CI9f0?p%^U~nox`u3{5CT3x*~XqXk0~iqV3h3B_o^(1hah zyq!MGGY*BX=y^L@Ff^g!panw{iqV3h3B_o^(1c>NU}!=yS}-)B7%do@P>dD~O(;eS zh9(rF1w#{x(So4~#c09MgkrQ{XhJbsFf^eUEf|_mj1~+{C@$|Wn4{S5F~%SFiimkO zme0e{f}sf&jus3}C`Jp0CKRIuLlcV8f}sh;Xu;5gVzgjrLNQt}G@%$R7@AOw77R@& zMhk`}6r%-06N=G-p$Wxk!O(s5ofB(1c>NU}!=yS}-)B7%do@ zP>dD~O(;eSh9(rF1w#{x(So4~#c09MgkrQ{XhJbsFf^eUEf|_mj1~+{C`Jp0CKRIu zLlcV2`%2c3?9Wm7ir!bE1w#{RjfxfwO(;eSh9(rF1w#{x(So4~#c09MgkrQ{XhJbs zFf^eUEf|_mj1~+{C`Jp0CKRIuLlcV8f}sh;Xu;5gVzgjrLNQt}G@-b>|3xFPUue8` z+-oG}-9o-kK?{Z^R5)5NG@%$R7@AOw77R@&Mhk`}6r%-06N=G-p$Wxk!O(%>mS}-)B!qI}E3B_o^(1c>NU}!=yS}-)B7%do@P>dD~O(;eS zh9(rF1w#{x(So4~#c09MgkrQ{XhLz>pMb_^Kb68)v_AnY7@AOV(1M`}#c09MgkrQ{ zXhJbsFf^eUEf|_mj1~+{C`Jp0CKRIuLlcV8f}sh;Xu;5gBZn3YO(;eSh9(rF1w#{x z(So4~#c09x-g}<7?Dyaq4*Ry!O(NU}!=yS}-)Bm~~UWTl9WBg|BFT7g{hhq2izgLlcV8f}sh; zXu;5gVzgjrLNQt}G@%$R7@AOw77R@&Mhk`}6r%-06Y5<9S}-)B7%do@P>dD~O(;eS zh9(rF1w#{x(So4~$2ev099l5nfwGRyccbynh5d($j}{C~C`Jp0CKRIuLlcV8f}sh; zXu;5gVzgjrLNQt}G@%$R7@AOw77R@&Mhk`}6r%-06N=G-p$Wxk!O(dD~O(;eSh9(rF1w#{x(So4~ z#c09MgkrQ{XhOaFLkor`6r%-06FwEah87G>C`Jp0CY&G~Ef|_mj1~+{C`Jp0CKRIu zLlcT!7O~4HcG(+jx=zGs!O(dD~O(;eSh9(rF1w#{x(So4~#c09MgkrQ{XhO03s@Q#4?7l7b z9#Jt`Ff^eUEf|_mj1~+{C`Jp0CKRIuLlcV8f}sh;Xu;5gVzgjrLNQt}G@%$R7@Dx9 z&e4LQ3B_o^(1c>NU}!=yS}-)B7%do@P>dD~O(dD~O(;eSh9(rF1w#{x(So4~#c09MgkrQ{XhJbsFf^eUEf|_mj1~+{C`Jp0 zCKRIuLlcV8f}sh;Xu;5gVzgjrLNWWQ*k46?eGd|sz1i$P$vxW*S}-)B;-CdX6N=G- zp$Wxk!O(NU}!=y zS}-)B7%do@P>dD~O(>4{gSj7`_k;h}{qShP(1f}cEf|_mj1~+{C`Jp0CKRIuLlcV8 zf}sh;Xu;5gVzgjrLNQt}G@%$R7@AOw77R@&Mhk`}6r%-06N=G-p$Wxk!O(dD~O(;eSh9(rF1w#{x(So4~#c09M zgkrQ{XhJbsFf^eUEf|_mj1~+{C`Jp0CKRIuLlcV8f}sh;Xu;5gVzgjrLNWW`*bhf} ztr5i54q|HxFNU}!=yS}-)B z7%do@P>dD~O(;eSh9(rF1w#{x(So4~#c09MgkrQ{XhJdj^4On8d94A()`nthMlo72 zG@%$R7@AOw77R@|a%jQOgkrQ{XhJbsFf^eUEf|_mj1~+{C`Jp0CKRIuLlcV8f}sh; zXu;5gVzgjrLNQt}G@%$R7@AOw77R@&ww4!rkGI&`U+iZBVzgjrLNQt}G@%$R7@AOw z77R@&Mhk`}6r%-06N=G-p$Wxk!O(|cca3`gu|J7Pcc5u*h|6N=G-p$Wxk!O(dD~O(;eSh9(rF1w#{x(So4~#c09MgkrQ{XhJbsFf^eU zEf|_m%sxu?Q&L_(qZ9kto!HOx#Aw0LgkrQ{XhJbsFf^eUEf|_mj1~+{C`Jp0CKRIu zLlcV8f}sh;Xu;5gVzgjrLNQt}G@%$R7@AOw77R@&Mhk`}6r%-06N=G-p$Wz8>tuf? z<@GaIv7gO~{mfR377R@&Mhk`}6r%-06N=G-p$Wxk!O(NU}!=yS}-)B7%do@Q0!;vVt*qb_Oo}fpUI2S zf}sh;Xu;5gVzgjrLNQt}G@%$R7@AOw77R@&Mhk`}6r%-06N=G-p$Wxk!O(=}j8g6tWE z(Sqz5Rh-a*>=}j8g7JP(j22|iDB);9_Kd=4LH3NoXhHUj!e~MEjKXL^_Kd=4LH3No zXhHUj!qHb7_Kd=Q$1V1|Z?WHri_wDY86`eikUgU?T97@XFj_D)p%^X5o>9Wlf}sh; zXhHUj5{?#R&nS!*WX~v!7G%#Tj22|iD2x_l&nS!*WX~v!7G%#Tj22|iD2x_l&nS!* zWX~wKJ)KJ)KJ)KJ)lf>S$Bt{FeXOwHv zg6tWE(Sqz5h0%iS8HLe;>=}j8g6tWE(Sqz5h0%iS8HLe;>=}j8g6tWE(Sqz5h0%iS z8HLe;>=}j8g6tWE(Sqz5h0%iS8HLe;>=}i<$4ux z*)s~G1=%wSqXpSB3Zn(tGYX>x*)s~G1w#{x(Sqz5B^)ito>3Sr$evLcEy$ix7%j-2 zQ5Y@Ao>3Sr$evLcEy$ix7%j-2QP_J3#ok*e_MSsAT97@X#77IVXB0*YvS$=V3$kYv zMhmiM6h;fOXB0*YvS$=V3$kYvMhmiM6h;fOXB0*YvS$=V3$kYvMhmiM6h;e%CKRIu z*)vKwT97@Xu)oz3dylBtdq>6IQz}LavS*ZQ(Sqz5h0%iS8HLe;@qSQ@7G%#T;b=kj zjKXL^_Kd=4LH3NoXhHUj!e~MEjKXL^_Kd=4LH3NoXhHUj!e~MEjKXL^_Kd=4LH3No z{&r04J-}k`4HkRPuox}Ko>8tv3$kYvMhmiM6h;fOXB0*YvS$=V3$kYvMhmiM6h;fO zXB0*YvS$=V3$kYvMhmiMR2*86J)x*)t0J+d8rL@Qb~-U+g{qVzeN8 zM!6O($evLcEy$ix7%j-2Q5Y@Ao>3Sr$evLcEy$ix7%j-2Q5Y@Ao>3Sr$evLcEy$ix z7%j-2Q5Y@Ao>3Sr$evLcEy$ix7%j-2QP|)5iT#a+*xzo5{Y{4$Ey$ixu0;#7XB0*Y zvS$=V3$kYvMhmiM6h;fOXB0*YvS$=V3$kYvMhmiM6h;fOXB0*YvS$=V3$kYvMhmiM z6h;fOXB0*YvS$=V3$kYvj`xFndnoodIAVXBGlq}fGm6oI>>1@+v>v7{O29NdiTj&FID&!JFeO-zin)z z^N##|d)!4wDW5NS{Eyn@%{X82%fGpnzY`DUI!f zkoMzu$aLfHL*^&0o63BKy{XK9q$9tkq~-7)cKiXh9kK0;BOTHeJ3nLin9r$_fAKS4 zanos}=WwM5yB-wo`bqoLn>c={Pch{tJ+7rbs27-eigGFc=s$E|gy*-b`F@b^RTW;o zos>RC6B7Tw^L=IU!`T;qkMbY6+32rQ{v+)l62F`2H&Va+8()aU&t%Va_CML%4=27T z<&V++DhW?Nmc+*or{aVi{BX)<@rNmYpY~Tte$sy?>7-vx@}K@TBR|uAI5Qmoq8T55 zjA=(~Kb&HxD|UXw&S%TD&cE1xI5QkSoMP95*!7e4(|>8!r@|>W={cYH;S{@Fl>h2C zlJR9fnSF#e#V;k?W5;pCzE-@V@09%wruvV+!4&%&Ofh=e?^xMy%Qu(`M^F15EBkHv z22BFvb1`v!$>48%(jk!4&%&OtHVg6#E-YvA@9-`y0&J+|2d4z23_T_x^@d z<@GnDVt+#__BW(re?uzvH>6^JLn`(+q+)+VD)u*|Vt+#_=6QhM5%>OvRN?-HRLt`L zza#Gb4XMJ*dLw-o5Z=u7wMSiR74H2Ftjg|hV8#9hR_t$J#r_6X>~CPj{sva;Z(zm# z23G8EV8uMo@H_6_-@q!|-@uCf4XoJTz>571thlU))0YL|&0Jp_S1nMu_cy#MyT9QT z`x{=dzu^`88(y)$;T8KEUa`O775f`rG0$WCj=uLdybAX>ykdXDEA}_MVt>Oc_BXuZ zqSw;53E|CL*KSp-7ViBGvdZpnkj4H6S?q6+#r_6a>~E08{svjh^Ca&v==}|{!u<`h z*xw+F{SC61=SkjU(EA%?h5H+1vA;nUm*)xT>xS@Vu0LC-&r%Ba{)Sp*_czpHe?u+y zH`HRDhk1`g?{BCT?r*5Y{)SrYZ>YsQ5Az<0-rrCw+}}`({SCF4=V9I>(epgadn9^) zL#;UFc~|;ABD|UF&%WxjzQVn~0aw}m4Y=6ffR8+W11|PA;9`FRF7`LzVt)fJ_BY^S ze*-S|H{fD_11|PA;9`FRF7`LzVt)fJF3)4}C5taC!kfANZ1(>0EV^*-Z`f6Kf5R^J zH|%16!!GtW>|%ezF7`LOf_BZTef5R^JH|%16!!GtW>|%ezF7`LbsJ{y}!X%+5HW^*x%rb{SCg@-{6b=4ZfJ?sorDL`x|_P`x|_*zrh## z8+@_9!58y9)q8Aue}k`Zo~L?`P492;6<*$F;cFUSd4xA}{oPi5mshyA4*`|kJ_N+} zAt1I70kM4ui0wl_Y##z*`w$S@hk)2V1jP0sAhr(yv3&@L?L$Cp9|B^Y2YZhY{>Jf_ zsPMwgTz~gk-!&KR?E^vO<$1REIQ2Zw_8zC+J`fbgJ`lwAfgrXI1hIV}hAh=LTn!tV*8*F+Xsc%J}AWYK_Rve3bB1q zi0y+y9DB_0K_Rve3US#_mA-ZfZ|3^ms=Ak~aBm+PD!YAXi0wl|Y#$n8`_K^Ehlbcb zG{p9yA+`?fjwEv|UdO_{eSoO! z_5mWc4-m0^fQan_L~I`*W1P_kh}b?r#P$Iqwhs`oeSnDV14L{eAY%If5!(ld*ginS zWj|{A;wHSA>w8n{UfjaHeVC~1_F*En4->I{n27DeL~I`>V*4-=+lPtRK1{^+VIsB< z6R~}mi0#8f9D5Y;VIsB<6R~}mh|7NI^vzCqGuQV{*S+F}d;4Hf+3kZxY#%IQ`(P2< z2aDJ~Sj6_hBDN0}v3;=DI>jMzS8#N~UFJiCGLX0CsGQopq++}j6^${u@M@qr_@4;-<5;D}?7D?V_3r%IotHN zV1;}8@X>QQ`|uIlhmY7ke8l$QBeoA8v3>Z6?ZZcGA3kFH@DbaGkJvtZ#P;DMwhte% zefWs&!$%y?LOIW6HaBzq+r9d&V&UFCh*VztAQIaLk=Qxb}Wu76uvzojkQ+lP|MZXZhG z*dvV(C9!=diS0v4Y#&Nu`%n_whmttnRJDlx&G~Q%o)?)dKd2FJuE(;RCfD-659uq*gl}d_5mff4=AyHK#A=GN^Boc zV*7v+#~yEdK#e^5fD+pWl-NF?#P$Itwht(AyerS|@$)P&!sq@h)ZhOwYp2T=%_GeGL`v z?E_6^w+}S2eV~cs8wY%#iR}YTY#(T1`#=-h2b$PE(8TtEroF!QfhM*OG_if4iR}YT zY#(Ui_{ISrXk(lQ&r9Xocg_+eobQ0=v~Q^D3#%~S>*K>sWw#GEv3))p(plSF`IP`0Pj>N?_Bi#=(%0_FD!rX zyi=jQ>;q72AAsWcJ_R3uV*3CT+XtZ7J^;n`0VuW)K(T!Q4y0utfMWXq6x#=&*ggQo z_5moi4?wZ+#j~03Q|7d9Qm>sTSNbqi8NH4Y+lQgpJ`Bb7VJNl_L$Q4ritWQtY#)YV z`!E#ShoRU$48`_gD7Ftnv3(ed?ZZ%PABJMDb!Ri*r_5>Jxz;I^D}6AkjP}7Owhu6x#=**ghD=_Q5E&4@R+lFpBMiQEVTKV*6ke+XtiAJ{ZN;lCzob zQ|7d9XKR1T#dqs@Mm*oA;6qa7wGT@4@t3o zNQ&)4QfwcRV*8L3+lQpsJ|x9{Rx_LVK4nh(9`|!L%9TDaRYv>36x#=;*gi1D_JJw3 z4@|LrV2bSnQykx?-~&@^ADCkMz!cjDrr16(#rAK1jv(K|1p2gH&uE zq+++;hppIqy=F7tr_AZI!@N(Aa^V+oKxfik-lr$F4_>i-@QUq&S8N}= zV*B6~+Xt`MK6u6U!7H{8Ua@`fitU3}Y#+R0``{JZ2d~&Zc*WjJIh*-DWlo=M=Y6o0 z3%{KM&v9rk?}HWFhp^Z_gvItDEVd6}v3&@O?L$~>AHrh$5Ek2qu-HC?#r7dAwhv*k zeF%%~Ls)Dd!eZ}Lp3QupGN;d8^geUSgmn9Y2jGN;c5^|u?83%|#C zE-K%r;KNzvwGU^peK?El!&z(}&SLv;7Tbrj*gl-a_TenH4`;D`IE(GWS!^H9V*79w z+lRB*KAgo-7JN9*X1-6E(`VQEJ1NT56z2OBd{C>r_CYPS4{EV}P>bz@T5KQGW1P_k zwb(wW#r8ohwhwBteNc<-gIa7K)MERf7TX84*gmMm{+4Yv^L@&kK3kdhOY#-WU`_LBKhql;0w8i$J zEw&GBaomgXp*@@VK4ngy{q1jiDOXdN?^EyruJYOkxY$0x#r6R%whwTzeSnMY16*t$ z;9~m#7uyH8*gn9;_5m)o4{))4fQ#(|Tx=iUVt53%*FO$F18PIv3;0}?ZaGbALe5F zI+)FTpVIP9h4R|(f!KZz#P)k2w%-G>{T_(z_dsmF2V(m@5Zmv8*nSVh_In_<-vhDz z9*FJtKy1GUV*93;&3vDN4|c+P`(PK_2fNrl*v0XE3O?Ay_Q5W;4|cJAu#4@3U2Grh zV*6kh+XuVYKG?i0xNIY`-F6`xOz#b2j|O&t|?)!H2w_%h`v# z*goXN_8~8}4|%bD$cybmUTh!oV*8L6+lRc^KIFyrAuqNMd9i)Si|s>RY#;Js`|6p^ ze4oZ9?ZaPeAO2$d@E6;Mzt}$f#rEMZ zjy~AtyS&1DpVIP9h4R|(oY;Qn#P&NUw%<9i{mzN)cTQ}-b7K3Q6Wi~c*na24_B$uG z-#M}U&WY`JPHew(;&^}3@*ai!7v}pE&LAMX_Zb9YpFtq@83baVK_K=S1Y(~-Aodvq zVxK`E_8A1?_&$X*2u2>yAQ1Zu0=QvCkk7+n3{P=KGYEcPfnOHg zN3s1nitX1?Y`>0T`*jrCucO$09mV$RD7IfmvHd!V?blIkzm8)2bri?@laBW&;l0mL5c>=TvCmKt`wRuK&rlHi3=TvCmKt`wRuK&rlHi z3vri$%1Rcybh zV*5=M+i$AaepAKvn<}>7RI&Z0isSuB$9oj=T$t}uI0J(4-e*9FeFlWsXF!O3287sW zK!|+?gxF_5hcu&)^XI3=Xl+;1K%^4zbVR5c>>{G0u1f$86>q zTjzbtI;Rd_FqGYX^~JGo8Nd2s`_&iQufEuR^~Lt9FScKOvHj{(M$Rtp@C5_gufEuR z^~Lt9FScKOvHj|cslc2k$vYL8^CWqv0&|`u?^IyUljNNW%z2W$Q-L{8l6NXFzP@;; z0&|`u?^NLU7NFyu$}HA7ivBJ@=P2T9DdOlHMSLy6oTG@ZC75#*@wEhVjv~I6V9rte zY4}=F{5X>kUrR9ODB^1gj_(3Gd@aG8qlm91m~#~IwFGmHBEFVj&QZkI63jV@_*#NF zM-g93aJ+Ni+z`IwsLb~%9q&{kyyrYj-l@Qxhsiq?nDa1srvh^xCht^W&co!L3e0(! zyi~e`+F0soccDckZ7kO@6F0sq?Rl;2^vCB0{xXUGWxx_A) z*yR$tA2wWDn0I;|?^Gh3?^8P7slc4)$vYL;{ZQz5-#+p~Y7q?0G}%c|+`ZL+p7&?0G}% zc|+`ZL+p7&?0G}%c|+`ZL+p7&?0G{xU)!jh71ftBq;$@(zqMpv0QWNLfp2g+-W$Pl z@r;;q7Fb`-2+OrrOS!z(63_KBR?1m#eK`Y;Z`C{ATTtHlbVf-z%danI{H0b^d978& zbN!5ua#mws&Tz!nN1p9Cug=IQXL0uBjLzQA`qZX=)+e6pXH1l{R{L@WE54Fip4&2h z{VZBM*UxAuXX*CkjNRVvO;kp|D-qB2GY-mG$$dFP8DDdGw(`6>BcPmx-Ip`6@rBs( z+>QS1cg^Ct?qk24b>5dV(DBuoXQR(6AN8+z@GSejoNp&W zl)cZgdta`~=)Jh&x$dJo`f#6pIQq6UA#Lq_<0_-~ii_vEkL#GD1~egMjJaz-6T<$k zK|G&)M8`d7Koe5NxHk=GLfGHki06}!Qo7nnDx8e8Yhzgy)lw%Fu#S zXhO;r>*y&oA+t;OduKO5tA68l1x5e|-N1x}Yfj0HrB`*H%ct1Ghy;%KR_i^WYkjm(LleqYc z^KD9g z7cifEd|3mkjMj!?zU@F0GLOwCA6eG;Dwnmtc)t3W@-v(%+R@K;#Piihlb_M4jDB_} zW^X>4kb0O;K92khR^{@uS@C@J5#(p=Dx;shi`g5FCZv7mlaC$0Ls7Z>Zbi)AYBV9` zWj{5V5T5HkYW$8&W%0W+F?*BKFADpS=ZlXQzXMen(ZOg!+Ht=6Nbx&vmC^6M#q-t2 zi1#q4jNaQIp07SSyhlZ4^xhTmeD!hRJxD5}_a=#pzleF|Bf@*kR7UST6BmCA^UBA9 z_Yg`WcyFP2zWONe9#NIidq>6d^&5Zh0ah8kH&{GhzmfMIZA{qn^kC|PdV#4Y z(u1kLGfup8n-Z?_I{rYo?TBq(O#Sii(T?&nhL8E2BAoimcG>UDbqDJ3*r#39T>qxE zhqYgP#RUAhpDr3Ud-kpkeB!Qu>i0YIW8$N?{aJtE(|d9J_VI6V{JoEO;<&Dl>szi3 zdy`>TOgfQXhEHTT>12G;Njs#I_W8|p`FrMv>oT9%%lwm0DHq|BE*J58mkT>$+ZQ`s zvGXH#J_nbJ{EH7>Z{=;M$5LJ~=}?b^lMeL=yWYf+F7+wq@0lO2%Y2ef=D)UA^1^o? zm2Ec(=e2O!gflHT^8jbw;LJ1Zwj1Ds*E{@F(sQ`V?)XX%&borL4&kg@*lpLtZacBt zPWg{?)ON(lHZAd+Vn=NIVy7#1e#CCOmTT!F*oCuCI(#z2T@Q-m`bqoh^Tc<3D%|xf zcKwUPp2igMYkL*$OC0qV@*45gUnm1y(o%n+%!HS`^(D`}+m8HePNq)bQg-624Qxkk z1D85fS@}2NZacBtPE4I)ceFFzc9cuwj_}gfX{RULZ6_{$hH{Y~g*%@E@tuEhjys3b zb_#brh+RKvU-js8RgbXSPI26JVz&!@GV(Ldla*sEXWKEiWZN;8r)|P+JB3FX^>4y6 zZ*b-rcH1#;WZQ|e?2b>{DLm_n@T@~P>lSv~DG%8egl8MU^byaQ8P2^R+pZ~g#I`SX zx?<-?oPCUIo&Oeg+lgIXvFkzX`bqmL57)Xr74EhZyY0koJLNyyj%#zx5bfCHS_1Z( zfj-lC%^>C;&OMcIuNlN%GmPP0+YrZVhAEi3@`CNKl2qgokl%6T=nSq ztnn1?`bqn&@x-oAvFlmv`WL%hl>gdZ$+3o^yt($vc4Y08?byO;AI@}Px1-`@J{A7p z+ArIYbzQcjIP1ajbM2SyD4SWI#L0Swv;JYXqvE?AmH#Lg?a111x_wLhq1X}IzS!xC zvtJS4?a10M+fnRx%y6aW__(i)5m~=9nbf`z$p?<`! zH*us(eP({BXEE1hKCzeiukDrhS^Db#WS{Z9o^=}IPPz&9+CcMd-qQ)sdpex=bU5$n zaNg5l`Uz!o`2W+j^v|ETPP_ZxTsiUL7;BF?c)j*dANlSCW9=6kENl1v>c37f)(%-` zllCpck0%&wSABAEyVIV#HN-#oNn5t>dG!qwjJqFxb@ld?H$1=L+GAeusP>s}x^03n zc-l^Dw>Q0a&jveB+j;wT^-tVAaZ`-PTYkT!9S(SLgUv-J-WTonaoN1(tex9GbPJo^ zW1QZ0^+xSxx4*o>{#lnTXy5+DPssk!CvDMQb@Q6pXyL{)6 z2K(=L*`oG`hny_?SMK%m=Co#z{pUSt`}PgbI#l-mc=4L;n&+J=`{!JBL$k`GzApPu zU3L9-uUkJa`@cQ(SIyPGzC`v{yKCe2akrl@`^(!qn$_NLh3sRSG^mq}U$s^HxWjtc z@4tCZbJaoLmwjxL2KDogzh2m0GI^cs%XXwe{cN~oar>jiH_JY@NrU>KZm1*dfBV$6 z+t;mihwNjUG^iiyhC0GNwn>Bfp>C)n>|>iWs2}QvI>J8fNxNbn+oVDLQ#aHR_Gw$% z82i)>b%cG|mNv#dbweFtpSGoqu}}Y^pJAW6p^mUm+tS9^r{B^4uut34#@MG1(igE$ z+tS9^r$5p!vCnv6{9~WCrH!#q-=vRXpEz%idkOaGoAgoa6V81F`}9rvDE0~G9^?E^ zX8!4$^ik{+hkK9nKbiR_ocoaTKbiR_oO_bg-S|77Mr>c7wWkN(qV|B3wfng6K&KI=dFPoMoK>c7wWkN(qV|B3qVv;L$1 z^x1!+|M%JdqyGD>|L8w`_MhngefIz8KYjL}=>I)q%>Ad&{uBMb&;B2_`y9W~fBNh{ z(f|AG|6#k&@f-cW&;B2_`y9W~|NHF!VY|=q8+Fs?{1g4Z&;B2_`y9VfH$%=pVSC8& z8+9|}{1di^9KTUFL(V_ZwnNUDVSC8&8+9|}{1a_ESoCKC)#$%`7`?FkaK&q?U3_l^vxmX`DoiA=g;VyL(cgzwg&no<15;B z$oVt+=8*G$j4j1sd_~_Ja{iC8rEuCe`sR@He~c}KGrpYvN$f}89CH4Tv86bSFXw-9 zoPQppaK@MOKRNcF9Td*^a{ec=@A~h@`KM7F#+UOyiGA09U-CbReb;|q@;`}v*MEd;S@yf6t$?@A*geJ%7r6j4kFL+4uY@`!Tkd z|7G9vkL-K?l>Hc6%>T0Q`BU~|Y%%}KzUNQbkFmx4FZ+xw#u)kc{3-h}wwV8ApE!&$ z>c{iH>=VuyqkcU9%Rb?ZG3v+nU)lHkFZ;w{j8Q+n|H?k$asSHvYm8x^@VI|v{x!y2 z{~BZDUvUm=GXEN5u7B1KnSbuTS^umbGXLCvv;J8>DF0snsQ>u>oAuB7LHYOkC+nZ} zgY0|#ll9N~LH51=k$tbP#JpZsplzp$?WS@H@W6bjp>*pN5tUq)9Vf~!r zm-T1PKdhf+pS1~NjP~W;$QWaMac^ggVV|`LV~qaEy`3@U`IGg(>~n8tjCuZK{V)5h ztr%n2=ibg3^Zd#BU-nsBF~+dZ+JrHNeb!ctG5RNK6UG?!Sz9s2s2|oNj4N!io?={) zXVy@RCG4BON^-BQ1ybu;UM~?TBq(>~zJ>kJ$MXM>^zReCK`FoJM*s7v;_P z)PtD(k{)qfZ(_KXz`h|A&4-_xl5z7WMVB7b}{x^2J ztzGcI`(^*uHEwTza_k3X|M)$B+kW8Y56S-I!aLjTe(_=1|G=`}w+9}2lghk&iPZH#@|mNv#dZA%+tpSGoqu}|A>7j2Av+LkuPK7EruihcSfeH8oj zP5LPI>6`RX?9(^tqu8f!(nqmR-=vRXpT0>S#Xk2q#vArw=4I@|%*)t^nU}E-GB0Bv zW?sfV%)E?!n0eXx?@RvslK;Nszc2akOaA+k|GwnE&-_RI52gNxQvXA#|Dn|XQ0jju z^*@yQAF}?V{|u%745j}JrT+}2{|u%745j}JrT+}sf1>{nrT-75{|}}A52gPPrT-75 z{|}}A58402_E5&}P{!|2#_v$Z?@-3?P{!|2#_y2hH|l06^UqM`pP|e@Lz#buGXD%^ z{u#>rGvxdeZ9A0tb13uYQ0C96GJj5$`E#nwpHpT2oXYt#`sP%b|EJ3QKUL=csWSgh zmHB_F%>Pqm{-4VEKgQM+<6)eCRuzx)&%?zUUk@x2kMqxJ;&J|2T|CY|Ylz4BXH7BV z%lYrIA7hLB_t=lIMgDv2$JiqOJ@#X4k^dh1F}BEmkNp^1-g#uoKIU_Ztd^*>-g#uoKIU_Ztd^*<>8uUv)tAFv-|i~1k1@BSnEF}CPGvL9oM z{v-P_w&*{yA7hLDBl|J7=s&U_V~hSH`!TlYKeF%sFZ(gJ=>M`GV~hST`!TlY|FR!r zi~cYBF}CRcvL9oM{xAD6w&?$|@9``9*d`6?2iv4U{a~9ks2^;T2K9q&(x85@O&Zh> zwn>Bf@%$tE)D3ks_Mi7L|HwXdLmiF%=Yz~YvQOPmM`Qo_F!PV>Q#aHR_C0^fK5a`I zW1qIAjmbZ4OB-XKwxx~9KW$4JW1qH-`E!c=)3&rR_G4@@|4-3>=$rIW?9(^tqu8f! z(nqmR-=vRXpT0>S#XfzLK8k(%CVdq9Xc@*B_TjjH$vzzSFWHCV{w4eD4T$@f?89;Y zl6^StU$PI!{VVgYG3NYp|IPe!|IPe!|IPe!|IPesj5+@rW6pn*`S!0;Q)<5fq ztbf)IS^umbWZ&zDtbf)IS^umblz*>(vj4FD$^OIoC;JcUpX@)Zf3p9u{>lEs`X~Dj z>!0lZtlwnc>o?i=`c3w|e#`#P`YroE>$mLxtlzT#vwo9(?v0Ew>YsaK8NaMQWuJRv z8NaMQWuJRv8NaMQWuJRvj$iKW{~vqr0j^(Bo$aec4R*l-8Y|d{ibf-H_6Ug$V~IvY zEMTv(D+Uvd1q(J53!;LtfFgi`bny^Y-D)+lRAoAI`{qI6L>@Ox=gGb|22*eK?z!oaOnQ zvYgJ{ee!ev9ywym7rR`s>$6OE?9)(x;<$R^-kq-U;2}1Qb}8;%>5hAc9h)TiiG3m+ z-vIprSN#?D4%2`1Bb@#`ZW*sWkq=IP!s$tD?E%Z@m(4B z8MZ!%ttaBdu#v}lwM_qI%p~(m?Ih0-SC&{@#UUpalspIc{RKF&qp;)3G)x2SkI@%=uz|AM$O@|53oF~plK zhB&mv5TCXf;?@?9E5m17a@OM97LF@ZI`M1BB@g9L9_+ZXB`@R3#KenH9(f#BCU#sI zK4I#U_&w^GxIXIND33hEl{sE6=@aQg99rZkeTZ92xos&&^$`#8Z>hi1D_(AE$|Jwq zoBYH9irqhA_nX-LsXDlyQ_sZpWn7d#j@S9ACqqm^A7T&s5O2`A|8$H2@h^#y=tEq= zVu*|ALtMdPh>Pe$T)|?9iy-EuJFbJ6m&6q;hPa5u5ZBRtFF!FChPV!5UJ@6v7~(pJ zc}ZLfF)xXWSPXF;iysSnNDacM-4KXi?>sSnNDGT4rPt5lr zE@d&q)e!TNxRizO<)^wAqi+%yM9fR#QWn0KpX!cm;d}XpeBaAA`p5V3t?u2r@8w(F zoh^JX-;h7VHFe+1x4MH{_+Gvt|Bb(lYwEt2m;52Fsrz1D@`t#l?tA%G_lDi~@{&Kq zH7$HEulf&hO$*=4tNue=)57=isz2*b%^At}y}ac6US9PlkK@Yv5SOL3%W-9Wh|5yC zaRS@xUvN?JKTf1 z{}b0o{Sz0rAm*s%nEHp99qvaNUt*4Gj;ViqFF(=$zL!t`C$10uNnBzl=7_sn>rdhm zJ26Mx-CBPVm#DerxU%kh`RGsL64C#}RiZzMOGN)C?#}5S-^)wB@8zZc$mZ_f`jfas z^gnTx%-_U?qW_7jWd0^D6#Y+JCG$6Np_*G+e|#^m`ukp9^NW}}`pEM)aiOd~iECBN z8fDNw#M}|P!1(%JUiJ6A{KWk7y}ac6US9HjFR%5Dv1N?uAK%MMK4Z%mBj5M(#0D$o zj@Sj{*ZP^bT*W-1qtu_VWsDhL-^&v}%=($QTw-3hmnW9E)}LjZKk|J?FZsTsC$6~k zXD$Ap^*?dNwf?NV3&8rHxZ+xW*4_(9{fR43%p*FwTz}Ty7fAhyD=7V0dv_r9C$6CM zXZaoh{qOn{SCIbiOZ{2CUx54}#(@1RaS^FM@doT)iHk`6i9KNdN?b(rNAii;WQ`d5 zpSTG2uf%nv|A~u;{t$PO{wFRX`qQbu^VeQrl+5<2s`Ml0U?CME@m! zh^vYIsQyD-O6ITR6SL{Kl+0hrCuY-eDePawMN7WdAJu<|OUe9I{k{GW7nJ!+Tn+md z>kn~3nZGmrGsFe4f3befjPDRv!~VtkLtGI1SK^ww*B{CE`YHKdeA0q>|Ej;&Ps#WCFZo_SCEx46Q5fWm1X^xe9|3P#{QMK ztn6Q@f8ye@{?F(q&pNIw`>*Oxy5q{S|Em6^JFYDIujCJLeak&=8CORAnPcgH;-V#g zh>K(YA}(6;z5k~FiHnwe+dtAD@4u@55Z4#`C;cxQ(fUJNboyU5qV zB;WRr>Tml^`fvM3{XfK2#{N3xBaR4W&2I? zZGTGs5Z4;}P4aDjX8j>9I`fyf=&V1)MQ8qEe`ft5E?V+!^Jo5Ie`YmNOc`9oZ>#ugiq@%1@H>%Z-P$@iH>>%VP&)fs(s zTp6+X#6N4D_t|8*wlB{h%1=BLdapC%FXOTnL%h~vh~rue@m&kYUoFp!zl;Z43~^!$ z$6qNA zCY@j2%eT6h?7o+8b+6ioxQ>PICw_0;_FE9Dr8CD-jzVGEFpF6|qBgyx@{IdV+&anDO@_jEa`M#HzeBaAU zzVGEF-}myjVSIfre;dZv_wu)4e0?u}8^+i7^0#4peJ@Yk*TVPm#CYuo{&fIcbS!ZrJuBi@*`(f^6- zqyH1vNB<|TkN!_wU-!Ly^e1tNwP&rxCDxv`7MECi)>>R*?OAJaiM3~~#U<9BwHBAy ziTUF0obmO&eDptYl?&g?NBLe|crNSXh7NL4PFQ`ZEvuBl*^!nfecL9es#PiT=;@ zkM&>jhq#nQ?O%yYiT+DIbIWll(f^tL@%){K`78NDTutV$>Rbw%?-viK|5a6IaRpmAJ}2#8onX ziHnwe+n<@gi3?@_N?a)OH*ulN-^7J>+n>^Z+n>^Z+s~43`&sgBKdb(>pR@iXu9f{O zajo6=Kn@lT$7gIMT>3oq(b$oPz8UJTu_K+n9NMd~Oa7sMG)|<`m;4{5 z+^Ub5yp%yY^{o1fkv)#rarMnI^6(l{#Rv^u0A21GDs&sWx&Xx3>f+R zA0~~z!Q|x`7#S%8*_1&#{~OX*hWsmooN16h4dvFi>elKr4fULc`mc>0eL1w3{OJee zOw^^yM83Gnq+Bs+{Ea;1t$K=)QS}!idmOuAOfQ^k)o;v$-?zDjPOxS&u8bp$?l8VE zI>ord=oyTSLp@an>GWClwal-i5B;DrB4_9~l|edb zlmSzpq5n0%NYDI&X&3VgW}Rj&h1nxmV_|d+or78LS%2Y5V-Lzc%ibhrpJDwaPxh0g zoD1y`_uK!o9fD3UR{RfL;oryjMXB^>-Bb>g3Gmc58jO3>bIO7Os9N~;3oN#0>4h~zwf(OpZ@MI zt$ujZ9UFYsK3`mY%;9$sf8f<$SpE73?W?;mrue`?hKK+^12YvQs;wxY7Gpi4{?!Mv&v`??zx_SlI%recq^*g7D# zZiuZjV(XIFIwrR6iLH}j>#Eo~EVgcot@C2f1#!xK=c#X94b%VUXC1N@QHPOJ2h!6I zaQXpGKfvh+IQ;;pAK>%@JoZDzg7h%`kUk+jOnUT<^f2ka3;h}E45toobQq2f!_i?l zIt)jL;pi|N9fqUBaM})gt!QxO9h`XwXWqe?ckpjxE{`(3{!Ek=X1snA>(5w!I5Od^ zX>iswIBOc5H4RSP2LAu7nd4fTwVnK7+GUwD{6Af*$2!1~2}dTJ^&igq4`=;{Q#Uw! z5S%>-&K?A34}!A?!PYmmD>7+gWWtdNM<2jZ z104GSj{N|~et=^?z_B0T*bi{p4tw2GpC_F@8Pj8@kv~kH--X>Z))`J6;Mjg}Y(F@* z9~|2cj_n7>_Jd>l!Lj||v>mp+J;SkA;n=Hi>{U4SD*W59fk&CP+dE~28L!`j-9FYI zj!Zab0XSy?IA;NPJPYJ}L3)^arp`mU*2$cYNDq_WGG+7pPtQ0*S=vV;lk~`hb8doj zZh~`ef>Sp*=Qud$I5_7xIOjMx=Qud_5^ao3I5OeLgd-DdG~;QfAb_UeN#_C)b}k2`zy*;_wayzc|gUcKf~4-sGaOJ85T?^kvcue7hP{{88@ ziqCw`*H#by(9Ytck2-7h1s}YJ_{X39>guz<^OxfL{pifqv;K0)eX}#y(tmNQudL<& z=SO{cP0rsPe#V;of4J-!YvpeBk}s{*=NH?2X|0~u`u-Q!>VKCnesQf`q~GJl&r}`A zzvc7y5+mp2)#ryjMXB^>- zBb;%BGmdb^5zaWm8Amwd2xlDOj3byjM|C(`}Gw-ThV&@lIj@a_WE?4aOh+R*y>o0b@#BQ(H{UCP# zh}~~u_ovwXEcQGSdwz*MUTf*Ko~-4s^+fD(7h501))TSyM{KQno;n0nSeE~fsqkBezn?c-wFn{@gi`RSj?q2D5({!F>_bLvC?r=E;U>Ywpq9M6k0 zj^xQW!Wl<6;|OOQ;fy1kafCCDaK;hNIKml6IO7Os9N~;3oNyjMXB^>-Bm8T|v9aGdUF`f~%Mn|? z*yV~{AF=BxcKyX}m)PwUyC1~vAF=yQ?EVzHpT+KfvFDfAy_C0Cbk}mt)F7+t=Rf3ww{Zv|6e0;*8@k?#iEWBt7E@ zXB^>-qn=%^8+tb5NP5N*&N#vuM>yjMXB^>-Bb;%BGmdb^5zaU!J$7csk@SosoNyjMXB^>-Bb;%BGmdb^5zaWm8Ao^=$EP0kuGRnCac_<35g&Qi>c4&Q z#o`Zca`@_JcVC`m&UpCYtM%}jb9wO`p>Heh_C;R_wb!P@#DVwwKYEMqhDXk^R+|IUVHYA&-lig%*U>L zbFHj>&-mtA9gcqJx7O-*>W99yR_C)W`t7y0T=Od5UTdRyW}R^!v7Z%Nrr2ePT?eu2 zCU%|0Zj0D$6ua$W_lekjC3YW*-M3=*x!7YN_85shc4CjIICJyDbyfCKqaQLK;mk)k z^AXN`gfk!E%ttu$5zc&sGaup1M>z8l&U}Q&`4}5!NY^+zzu0obmM?a>V%JCPdWv0t zvD+nfd&TYtvHM5teiM6r6MNkgdp#7#ZlNu)TVSuNYx!f>c^y`|*JrWUZL!yLvDbOA z*MG711+n)FG5zqHwm);$qg^@Q!8zZ-7oO9X=Y^c_=#!l9;GFN^obTYA@8F#8;GFN^ zobTYA@8F#8;PHGHpV*MzhWuj75nI04<%(S&vFj;z{l#vV*zFa&AH+WYihV8?`@Agn zIa(Y)79I3?eqWOl|Dn(OO1B?CZ2!QrtltBF=I>(P#74><3a1Wm_HH

ae~~eiwG;SWh^07}}yb$JQl1wk{l77mlq9$JT{o>%y^h zVe5(JZ z$^YL;|83TjI{dn^BRyv&__v`ynP14yoPvMb^Ezu9WsPgyZ*#q+tlXKx|C{^V+)b;m z9G45{?iJ46E1bJmICrmb?q1=diwh@a2~JE7e166VCH{wU$GDgCGv4Mm z5o1IB$9R(eX}k(@;%|X3^nbokYe@Vp^hx|JaQrQB{4H?&EpYrTaQrQB{4H?&EpYrT zaQrQB{4H?&EpYrTL;5`A7sua1di*VL{4H?&Eqd1XeQ^9OaQrQB{4H?&EpYrTaQrQB z{4H?&EpYrTaQrQB{4Gh}2=_#^CH@vT{uVg?7C8PE_`>`2dq{`lZ=p}(Z-L`)f#Yw1 z<8OiEZ-L`)f#Yw1<8OiEZ-L`)8Pc^TIKMdl7V^a30>|G1$KL|S-vY|G1$KL|S z-vY|G1$KL|S-vY|G1$KR6l+y}+qLb~H9)W-N*NRPh-j=u$_p2UN})Soyp zn066A2Gic8(+|l{{}4Y$9{P>=G1&Sq_Ph{#zKA`KTG{)0FY*b`*sLGD_t|~N*S=*1 zzV3f~p`UrJYftctk3G3x^D2KW-t3-7^$+g(8gc#G>%YbIck+qrIi44nyhX_sKj~*L z+osA(`byF%C;2HSawsSA`8VbA_tb~yQcvWi{*=SJfNmG*3%85>-R(k-*z(0LSM2(T zT~9IP&|k=T?nPcsyOK_OlVANv9?GeDE8YDju5#&5F@H~e-2X~PUh046%j~r_UeDR= z+5JX`-csYW>7)1PFZ}kA;_vPF;C|=JTx_D;<967oe_-1ii0fbeTU>wdl}}vHE$Vr3 z$y=0MG2>O`C4D97l#~3F6FHO<`TU!5`FrZabEzltQh&24SD#V%Lu z`iNamG3At8@lSrPb|szmCO`ckcK?VehkhLTQ(X0-pT#^!KavM|^dnq<*Y5IQt^7Bi;P35tX64&UeB2Hnsqs2QT>nykL@q3fgd5YBoC zQx5ACob_->*LXR9C%xK*9C6k|(p|37T_17QL-J%jgdgw|wM%*2-sIPMNFMi((%o<3 ztcT>udI-D!l_%>V={J4El{LTKw)n!zR@d2l-t;A>uE2*p^fL1o9(vaa-sT|}op1Vx z{lqW*+SmGhu5i4#{_XYO;`)29e2x6|T(9TFC2vu3#pl*~Smh<1@{)f_e#(g)%87jb zO}YF%_2IeH6M3mWM5oi`it}zUG(L&E9ta1 z`RNBS<Q4<;jD*4y2i`-JLz6m#aRzY&w99& zqxD&NTu-sJxu-%TaGyMi*%Q(bk}DlopR87IP(i;yy!=#YkoO@Pk#50^0?np zF8!JMXnyf5&(V*t$3^uY_OEH!zb3Dr6Zwbz3;SB@JL$vzrG0??fb?PiVn50LH8Eb^ zzqHSIUz0t~zQVJ^{)K$m^P~^^7xhs-(!C$)*?sGr=E2`M2^ObJQ*+8{h9i7`jPaE7o72eSy$PYVcYpDudad7OkLvtY_VU{Ki}O&~w>p1mysA9q_xVNab4}#b{~fV(Ikcbj;ryj?=r7X${ugWK zue3M$bN*5}k>h?-9`~o1zo$OK`77hHpsb7+^OW*wFP!m$EoXu=UU0?>rku*BJQ*+2 zGhQ%y!FV~n_R(i2f9i^p&JjPV!Su{Odb$gSaeh|BV#O^mS^Q-e*>gjo;dJgl8c1iDf*7?;B!~BZ;P9B#l zc74Q@Q_qWCe=+0b`IYu2f999w4gF~OlqYt7irvqu8|BcC23-~Z|9OrN`xIO7Os9N~;3oNpUMs)Bn*Hx{H)~YRf}y8#2*639|F6dmFK$4cmQ$yA>0j3fP%afCCDaK;h7(9gf0bo+wh=O4!_Jl@y9z8ARgKJ*H@ht>U8?rZ3u z+}FUluYoVT4?T0DA1=HPy}5K|ybmoqa4p^-T>BvB0HwpZ*M@Vi4d-4P&b>CAdu^K4R;e*m@{FKjXDn-&jx3)!{r|>(7PptMo~& zx3zBT{rL;f4K4@7L=h`8EPdxP!-YcG&bOzHox zcNSy0(HY8(&cN~E!13Y0@!`O(&jiPZ1ILF0Z`3=cv-fzN?34GOw%=m&YwtgAa?@QV zxZh&m`CH%rg!tI6KW{#Jk1ZSNKf3y3=J)J$2XXy7*ME!a?{no7*K@s|7ni(Va>eLI zm6!A>>6DZFloL6W6Z!m`a`}7e!*i)8@=|}wsWIEy?IOLqUE~*A&g^y}U+i+lu8-LD z6jKiU#j|yvwKe?+yS>RzKZxBwV#=W(T`v78uKLi=VxCJqDJS*c>99Mjjn^~YdE0sS zyKSnr?0Nk5^X}X2E#CiTe?0GW*oVZ|e%w{(1FrRRG5_-4l*`}A2lE`yi%TAIVaAK{ zoIWMJ@=wWMa;C^B`BUWAzb)m~-&^Wa&$ZOEMy?3XSdp#^4u=koBZ^H*!?4Rzlmudj3r7`cQISH+z01y;ILYZzE?W-SWkQ{--`lN8fp#{KGt2srhxV=NIXjcPqnuO#eha z>xS64V;`4Enq>==qBEP-R&U#lw7AK`+n`+DJK`U!

=sE3T-Du<==EVy0 z*z+azSDu<*2YY^{y-FYEBXU?blPJi-l%0FF;kB+x)TXxes~9XZt%hJG4FZ zK`&PRf%~@CI;34=@lvJVd#ks$#bsVDUb)sm?WXs6#d_{Tp7GgUd0RcB`~&xr*XkLi zS2?Z96IWeY)nh&PAov+@tzt3O(`S?SeJt@=w`ec7rX*K;58jL-HOt5##C z`~&wI&sJlm^cv?@<1H>-Xr%}1xes~9XM5?|R63{p1NYL$sdP^1rKeNrtGIM|Dm`A$ zeaJID+iR{cXOw^7Uh`?HIivKNXDc<|#5EUJYEG`_KI9pn?abXFf0+D>$Yk!OEavV| zpD;3$XMDCZcZc?dX)p6o^YGm^CeV#%DWY zHLSN`*4sI2GUJ@J8eJIH^Dt|2@{G?)zlQx{HcQvCr=X|VYtZFkKMG5ioo9Sj^JCcW zX0zr>_C)4c_DbgBu%Cw66O(6rwmbid_h0hE$**+gF6)K&U+S=)Ba`&;SQfm(o4fV(Y_t&X|%uKFj`#jw%1Z(Kn@A zSH;%n^&FifeSDVvmpP*R182S{-E&Rs`M91lr$`^4W&dT4EC0Zm?@IStA@+K*p0g&9 zK0eF-%NnKp182Qby4O0f*TeOkHI4M~S@vJnSmhr$>#fqgR*Su!ujj1Eq>s>3YtdNc#9J`!D--@`tluE1kKE zeO%8@%-x|r;q2*>@4a5k+^u=5X9teGp>*ah_A&CAyF-75W0Oc`^(Xd>n7Lc?R?iL` zduf@zw6(;g1K4BhIW`sP=(i}BA6uIp}5E!=HQjN$se=KUe(9 ze>$mcchD7ANdL!OKG+U@{<6nAf@#~NLP}~0KJBoj{_lMh-$NrW0uya1% zj{n78;?*a8s$J&~-Yg#G%Q%lFw~;)P+bDJ$#cre6Z4|qWVz*K3Hqw^KZKS=E+bDJ$ z7o@w5Vz*K3Hj3RwvD+wi8^vBvIx+|D-+lbY+Wt>{8|i)TlRnb^?70VuKe59}?RL+9 zjrc$JJh5GQezkb(SDesxKIRqTi=T0PJN=MpEh z=f2<};{SZj32naby_fm7Jh8oH^S@f==_j_2?0Z-7P4+mc?ev2?iEloAu${Z>9mU7~ z(TCcK4E?S!_=rCuri z%wL??-q+N((?4DQq;}D3sn4f3UiFl=?6 z+l=)7{hJ=wet7bw#eZ||qCM*|mlU7-=Zp5-yIexN)iaK5H+sPzh=2OsW7=LXzL@xZ z?>MHt@^u#xf8zbev}->8r}}r^pSnqJ7ybEH#rJ+=uetmc@%wg}+t0py zhWO8}x!RudBKar#C%?Da{&w|?O8?i-e4w>Gmwfy^Khl2o56fpSe#4KokKcXC*k!dp zD*wRKBft02w)F>;XS&%5C$&Gn`@dTwY{DsnbX5>@PYP`H!k^F7h7$&K5XeD zoqy8X@%uUd&3n7^ma6~s<`*v7_cuRVa$fw|W7^pV{8;?(Lyl>WxTN}Fy4|VAw9mfd zqV&mh<~5FOKigpw@yYuf+wO3*`f%E9%SF5K&o8d@OPsuDciu*QKJ9k96WbO~y}Z&t z{=E;kS3dD7V%sO{xqs<-?`uE2=3kQDxBL2$ZS%A4Ab!*34{!4he+NwX@lQT^c>CrJZX*8hr{CSS zK2ZMNe)|_3(Z2W28!7z*cRjN0`m-B~Z+Y$aw10i&l5hI&?`bDK!Rcol)gH3nlHYOV zx!vNLI*H$T)?w{4*S?MTl%3zzc6){Tb~^Rj z?`oI*!H!Db=WXw8_j%f##d{ocOuOEv?zw#SJp9u4y#B%MlK0t*JpCFgZ)&Gr{psTU z&OESfeeXTQfBCQj+jllS~l^y9Dd#`djaM-fcD7_rFZ#wN~r?>sZf$cAzqQ0H(a#H;++RvV%JimC&TiV-qe75+gbKlw?xXJUyKJTpO ze(BYH+PQ!IdeZwQZ+LP0^k(~s-~5@q+u^s={X+lY)Anw=K6GEDzi!*T+rB&M4x(T2 zdV9BfUgKp--}JtFx9?wjAMstkw|D!-Rdi?3ANRbMv={FFLZ#pRjF-0C?zy-4j_=&3 zy=q$WCeM9Y`|9*I5o z_1sHOTj?w5z4Ww|zKTmvTj{H~^t6?}ic3#h>Fbi8^?+9TDlR>3rLW@B(^mQ_E3rLW@B(^mQ_E^r_aHR_l(q)|*!Aj=0vFR_l(q)|*!Aj=0vFR_l(q)|*!Aj=0vFR_l(q)|*!A zj=0vFR_l(q)|*!Aj=0vFR_l(q)|*!Aj=0vFR_l(q)|*!Aj=0vFR_l(q)|*!Aj@bT_ z_1tUUXtjTk-fQ1zwSS0f-)Oaeh-=?ywSO$r54d5g{X<;)MyvfpT>D0={X<;)Myvfp zT>D0={X<;)MyvfpT>D0={X<;)MyvfpT>D0={X<;)MyvfpT>D0={X<;)MyvfpT>D0= z{X=X&&w8F}|8HdnkUrJ^-^vaU*Z$wi4iMM=-^vaU*Z$wi4iMM=-^vaU*Z$wi4iMM= z-^vaU*Z$wi4iMM=-^vaU*Z$wi4iMM=-^vaU*Z$wi4iMM=-^vaU*Z$vbd4~FVs{Ox} z9ia5u|6ADsV*DIs!>#9Db{zH`>AmbY>^X7SaoBU>vg5Gl#AU}#WzUJrj+@G!6PFz~ zJ>}+0E;|l;PU&UGO=ZuC%Z_Vh&xy;9Yh}-g%Z_Vh&xy;9Yh}-g%Z_Vh&xy;9Yh}-g z%Z_Vh&xy;9Yh}-g?GIefQ`zIK>~hklvd3H5<>Io(TiNB}vd3H5<>Io(TiNB}vd3H5 z<>Io(TiNB}vd5>g%f)4nPi2>j%O0P~E*F~eA0 z<5St?%l!ZFm8tA#C5Kk>U<@xbJbMmD{-BxraE7V>s&R} z`AS^ps;SOb;yPDxz7p5Diu0AY&Q(*Luf+Bnuji@G$5Wk?NuTO`Jk>c_T<7Dd&dK6B zA5V2o7T5WBs&lfq&c{=olf`vDp6Z+|uJiF!=VWo6kEc2(i|c$m)j3&Q=i}-9TP|hR z`FMIxUviy~r#dGqPo0maIwyuSfBV_og|a;&QzUygOPS3)s8R6y4vyOSXVo~9P4Vwmt$S+ z_;ReP9bb-hHFr`PNBlbF(@}fz<#^4R@a1^TnegR!&6)7!c+Hvc<#^4R@a1^TnegR! z&6)7!c+Hvc<#^4R@a1^TnegR!&6)7!c+Hvc<#^4R@a1^TnegR!&6)7!c+Hvc<#^4R zYVSxa$H*ODj`xm^FUNaF$Cu;1qvOl*-qG>pc<<==a=dqRd^z4bI=&q59UWhe_l}M) z$9qS|m*c&o-uz8voz9bb<3j@(^p9P#VK9>AAl8(_kh zV;f+?mtz}X!k1$kV8WMU8(_khV;f+?mtz}X!k1$kV8WMU8(_khV;f+?mtz}X!k1$k zV8WMU8(_khV;f+?mtz}X!k1$kV8WMU8(=D1E-^DBcYHav2FAm*cZl$Cu-?RmYd(vsK5J+OCpOGhgIX)v#_;P$kp77=Pj6C7X@fmq4|3+fKM(+4>?Ca?Ga_sBq_;T#) z==gH%>*)A$?Ca?Ga_sBq_;T#)==gH%>*)A$?Ca?Ga_sBq_;T#)==gH%>*)A$?Ca?G za_sBq_;T#)==gH%>*)A$?CVI(jKB&uXH5_E}A|&pxY(_St7O(LVdECfaA8 z6?grKwHvvkr}jN|^whq`j-J~0*wIt_9y@w!-(yEl?R)I#seO+fJ+<$#qo?*gcJ$P~ z$Bv%b_t?=>`yM-bYTsi=Pwji`=&5~=9X+-0v7@Ky3TL6YGtA$P??0eaI8*jeW=y>y3TL6YGtA$P??0eaI8* zjeW=y>y3TL6YGtA$P??0eaI8*jeW>d-3273apcav;k$s&zTvxo&c5NhfX=?*yMWHV z;k$s&zTvxo&c5NhfX=?*yMWHV;k$s&zTvxo&c5NhfX=?*yMWHV;k$s&zTvxo&c5Nh zfX=?*yMWHV;k$su;AtEkgQxLg|M#8F#QyI)or(S5cRCaMzwdM=_J8aE#+v=#cRCaM zzwdM=_J7~$Ozi)@)0x=+eWx?A|NBm7V*mG@&cy!jJDrLB-*-9_`@ipWCiZ{d=}heZ zzSEH}2OEyMVaJ(e$N6qfcAW3#WXJh#PIjE{=48kDZccWb@8)F3`EE{jobTpj$N6rq zW5@Y!u4BjfZmwg;`EIUb$N6rqW5@Y!u4BjfZmwg;`EIUb$N6q9v6>pkx?@dj?Swt< zJJtz%+;^-K_PFm@C+uE&Q-oE*SX4f z|%5^^GoLv1gvV1v?d5|xMb25F%`PeZJ^5r<@LB1TvJjj>hmIrtx8d^z|ZVSG9GA7Oks_#c(O{Eqk^m8blU z_#a_>Irtx8d^z|ZVSG9GA7Oks_#c(O{Eqk^VXrysS^i`E$dyO_WBkZ4z8w6>Fuol8 z$S}Sf{K(?+ALB=c@#Wx0hVkX#M~3m`;75k><={t#@#Wx0hVkX#M~3m`;75k><={t# z@#Wx0hVkX#M~3m`;75kNU$k{hd=7gD>BQ%-cZj`rh`o1+y?2PccZj`ri1FocAAn4J zIot=p_;R=pfbr#U9{}Ua;XVMyms5L(*n5W*H*=Fuok_bzpos-0Q&ja=6z~{<_cMUI)gP!@UlSFNb>_*fs$DKzt51 zfY>&G*fxOJHh|bRz%qSl1Bh({h;6^EXX10P!T&sJiet;9ZCiG8*b`)nol*-GrQmDp!1vCmdwpRL3`TZw(P68mf=_8ECS z6Q9EwnRMcFI3tUFMi%>wEcO{$>@%|1XJoO@$YP(7#Xcj8eMT1hj4bvUS?n{i*k@$1 z&&Xn*k;V3JtY_kL@O6+*d=9=2v3(t4`#Qw-b%^cj5Zl)wwy#5MUx(Pf4zYb5V*5J8 z_H~Hu>k!-5A-1nWY+r}iKCAUid=5S<(uvQ(XC=1JN^GB%*gh+e$FS&8kl65HRno{7)F_eeVNIrtvM_C1R2dlcLExa6hp zQEcC%*uF=xeUD=M9>w-OitT$8+xIB8?@?^uqu9Pjv3-wX`;gZ&@j3XANhdxBAF|j! zWU+n7V*8NA_92VyLl)bIEVd6>Y#*}NK4h_d$YT4D#r7eK?L!vZhb*=aS#1CRdL}-H zy8zOO&*3gW?7IN5?*f+T%ew%v?*hcW3lRG*K4<%&Blew+*mpW&-|2{b zrz7^Aj@WlPV&CbAeWxS#osJm)P1$qnnfM%hI;0bygHK27yE(D%=ET066Z>vX?7KO! z@8-n5n-lwPPVBomvG3-@zMB*KZcgmGIkE5N#J-yo`;K)z6Q9E!E9u1NaK|e49jn-P ztYY7>ihai__8qI(cdTOHv5I}iD)t?#*mtaAd^yC;Qy<^4ihakr%)h*275k1=?ECTc zOneSL9ny)F7{oy*mvb(-<6AfS1$Hl zx!8B*V&9dE9rLiBiO=DjOgiy7oRh_lc@R71LF||Zv11;@j(HF}=0WV32eD%w#Ey9o zJLW;`mk7$5Ig2U?3f3!V^`KQ@j1k=-1mW01tvMq-e}jzJRR%PF6Z*fB_A#~_IvgCuqglGrgwV#gqf9fKssm&1Ej zv}Iu8bMQZsPJ9mjN3mnc#Q1V}=ZZY|a(L$o#+So8S1`UD-noMDkF!T54`=L*J`!#h_nz8v1Ug7M{e?;t*h`v9fm z%i*0X{x5DW39!G zwH7H(|oofK8JT7l~|l;e)mD_cOS%cw&L9fvEO|V``rhz-+d7K-3PJXeGvQI2eIFM5c}N+vEN}?&lA2J zpOJ~rX+9$ppTj#W~~nieuqWu zcUZ)JhehmnSj2vZMeO&F)-&-ryo*FS@j1MUB=);VV!w+d_Pa=8zl$XHyGUZcizN2D zNMgT>B=);VV!w+d_Pa=8zl$XHyGUZcizN2DNMgTJww@>2XP*`EIlNOw9^!L&r%YTv zE8Zy+m(PlK%EaZf;+-;a`K)-SOk6%I-YFB8&x&`-#O1T%oicIxtaztPTs|w_DHE5^ zig(Jy<+I|QGI9B=c&AKUJ}cfS6PM45cgn=Ww>W;~yBz4LeUHTF@NOXaiO=EPKrwoX zzLH+PN8Sw-m+z5x1I6WgxO~XG<0&p5GVgebS#MZ(kW)Tn-tiQd51Ds7#pOfh9Zzxjka@>b zTs~yp@f4R2nRh(JdB;;ceDj3(oO}y~_?+gu0OE6aSC{<6=kTtsxb6aY zS65tj0lcd#uDbx<)fLxW0PpIG>n?zIb;WfTz`MH3Jj-`=#dR0JySn1K3*cQ{aoq** zuCBQ50(e(fTz3Jyt1GU%0N&LV*IfYb>WYVN!sL6Eq)+VszSAK-hj*@(UUxdYb1kkr z9p1SXv;SiU@NC`b@Xock?sRzPT3mNJymKwCJ00G+7T29l!w%rty3^sEYjNG_@Xock z?sRzPT3mNJymP%wU%qoKt~(vxxfa)*4)0uxvE#7kkUy||Ilh~dFUNOt9Xk$tuJRL~ z!@Kih>^R@e5ud}m^Ge5#^W7ZrIlMcsbnH0a%@Lo&yYtkC_#EDy7uVe!@6LvT zcdUE^L0osNd;>vTcdUE^L0osNd;>v@J?=YJ+2g)rl|Ak|R@vjeW0gJbJ674_*yYp* zdmOtQ#vb<_EActacdW9Ba`L3M!9KL0t zbk0@2D}(^=0WFU$2{nK?3f3gj~(-%^RZ(dbUt>>gU-i}dC>XTF%R+qB(8&V z|3+!opp)nM&8XqKIveU+I&RkjJ@hxS#QwfkC*A!c#utJgmUMg}_+eqsS+VD=*mHKt zzh~c{@tjrN{4FxEzeOhYz9Ytez+D3E#ecwE0_=T9?0rY+y7$Q|6<$!V%z^>+y7$Q|6<$!V%z^>+y7$Q|6<$!V%z^> z+y7$Q|6<$!Vt>O>?C%qbH|qB^#_yu|`;clc-*Mzy$>{&^J&FzW4T|wwBL4QK+RHa4 z`HnMfAHLzRp}yNNet+Y?^9_0X!__DDhl}kG7uz2$wm)2Kf4JEGaIyX2V*A6z_J@n@ z4;R}XF19~hY=5}e{_th~r9WJ3f4JEGaIwD`D}La4eBa)8I?Cfa9kK6p#J^mK??{vhz(-HelN9;QtvF~)mzS9x=PDkuJ9kIX1EB3c`#l!pc z8|s~U-%F;w|K;xj_-tf%ni+#5)_T9SJck5!`t&4rPF81BJ*mvt< z->r*%w=VYGy4ZK?V&AQceYY+yJ=b^MS>Hqh}iKVV#kMw9Umfge2CcbA!5geh#emyKCgGT$9M4mJHMyk7$?be zjFZ?gPGZM6Ez^IG-*+D0Td#fXzx=HS$LXnEj?)u6PEYJOJ+b5Tmi&A6j_~-dx4$i~ zdh&Y_e9Im^->C1^j_*hNyZvhK@cS2umsYytrNxey7CT;Ad_j2^b$q9|&M*Jv?{_%n zUu|^Ezxaaq{^s}|?tkaEMf~21+UxgL#23VO9?LJ0_f`2FfSJ9GIbME@nLQ8odst$= zqf@q>*zaD6FNp66mOpCkeNX>RirO;#-b&sdlrL)|y<0cFBkA_)ojdo##JIbE#O1G> z?PJGZH`~X4fqWm$`mAiwGWJt^CjTB=)zAG{O7T9FJrTSrrQQuH;>BBn(ll{_aul?0x z`?1B?bQ>j>dyL8F_qe!=#kTQ1g?NaC-ca$+V;sBhq14{<`fa$46f-==e*6AWZTG#T zc!;^(P;s_nytMC~)n4C6i-$PX4HcU@#uz)^KV%JCPdWx$Y>Mx%6c-6s_=XR+) z*!`e%_m9~9CZ>IqM}FE(c`*G!c`*G%dGHW7xM5>i2mSn&-{>6ldBetI59`ve{Ql{% zj&0a?3WojYSAJV|*uVI0?S_0WX0SuX-~1ha7kINgT1<8-%lLQ9l!E> z)5AGs!@grXoHu{vx4eh*>4tqzeDE`jzp>s2zr=?9*1_Ok8h^ij{Ehn!`@N3Auh<8F zV}7fpm5sMyzd1Abll$Oj&hMM3?T(8RJ1$P_xH$0z@w-XGJwhMu7xJ4RYS%{n_SbNK z)Q5Ye{Emj&?zlMdM*4o;aBtX$`^5bAgxb4Nzri@%7x&>FIltGSwmU9P?6^3waRPmaAINVUs9lbW6FV+Wd_n&f?hqf+hq#gaE`ZwTxHz%n;=~v9?>P@~L5czA zZizj8h$G_el(;yhZ=`RM5Ak4qh!e~A=ZP8Hu;0}m;sCirp0Vv{?+`bLzmB*#r8_Q8 z?C-RT{hfBPztg_t<#*b}{!Y8t-)R^7JMChBr(Nvtw2S?ncCo+HF7|iY#r{sa*xzXv z`#bI8A;uJj=;RPQ7&YII-j6#QwIq*xxo6``hNr{L62fi~VhLvA=CD zK0klo#OvEk8;5w{KEw%c*x%^!zNWShao~N358trAGi7^5Z6D(Q@z>>d)9}}A$lpq{ z9jmqv?|t;)eGvS08}j%5e11{eeXbD??*ZYj+mOFm>2s^vJG|%BhxflW?C-AHU!k_! zk0Bo3``fU;9c(|9+H3!nczE9vf8B=s{cFd?slE1Fiih`n@z?RaR;BZ<1GXLZfWOx& z_V-%F{$8ut-)j~7d#z%BuT|{twTk_{RS@3o5U ze-=9~PHca**l}@U$Hj?x*8$s(w)0IazsK7BjZ>xj8>eD_<5cW#oQnO8Q?b8sD)u){ z#s0>r*xxu6`x~cXf8$i_Z=8z#jZ?9|aVqw`gV=F#%k)jRY1nqOYk04pZ}szCP^J63 zpkjX)RP679F4LFa1r__dpkjX)RP679iv3+svA+u{_IE+W{w}E4-vt%>yP#r!7gX%; zf{OiJP_gfu#Ey#-`+iD1e9wX3o8ViTO82)k#r~G2*x%9=`&*hzUVckc>~Cp`{Vh$g zzojYmw=~86mZsR>(iHn!nqq%TQ|xbPiv2B3vA?A$_C2H6adBebONxi@c<`Gke1B5u z{{E!c-=7rw`;%gSe^Tu4Pm2BhNwL2_Dfag##s2=J*x#QN`}>n(e}7W!?@x;T{YkOE zKPmS2C&iA76FV+W?E7f(@ckBk_lIvbD&5~~6#JWvVt=zy>~A)T{mn+Pzu74EHyg$N zW~12OY!v&OjbeYZQS5Iviv7(-vA@|U{_*mgjbeYZQS7(^vE$;zjzbU+-|gYItN6~L z(*2!7vA=UD_ID1&{?4J;-#HZfJBMO_=TPkL9E$y&L$SYeDE4;_#s1Er*xxx^rZ2y9 zDE4;_#s1Er*zqLdTHEsdCH!>_+m5wv_+Asgzs9!#mF{l?iv4XsvA+!{_O}7W{x+c4 z-v$)>+kiT=^Q~@v?}2jpRyV)*0Q0SGe(wS1Tix}I5;5QEe$I=Qz6F09Q0e|QpxECA z6!Wcae(wP}jw2G6zoKE=k?y!7arrkIwjJsI?wpwK&GQ=xr2Bh%V!k)eZzPb;_vZPH z1eov5^BV~;-<#(*5@5bJ&u=8ad~crLNPzj?Jin2k{Pn$gej`D7>U;D2Mgq+D=J|~T znD5Q=8woJqo98zYV7@ocZzL#xeQ%!MNPrzbCgxp-_^HZ&)v)czGkl*7e_g}2Bc0z9 z@NY!&JD82%6(GHSBeLo+1BzbimGzbC-&3c&Rnk&WLK zfcZTE|3)OggW3390n+O?A{)Oe0M~CsHhxzCuHT4k{H_38zY*E^T>-d$BeL=lULwF&-lannz!F+f)Ci~r+xQBULk(j4Zhspw__LAzrFrjTz@B@xSr$r z#cexXC-PE%${E^4`oirZe|Ni(Bes08 z%N4smV%KwayQsey-JlR)Q9I%Ps&OC$MFj9zr(2+ zy9JzQ;mCwj7Mwc3sT-U+!ydaC_SlK(W9sDmjGZ`rMSA)WPT#^FyAIcL8VlHCr}}5? zhV+#o{{&l(*z(0LSM2(TJ$8*}U4OC1F6q)$^0*(A?*55Ph z$7|qe$fLfbt|fmOWKKg_lgCbZhPq8dohOeS^;g_DeF_h4CqLyWedsIXQ=a4xeM^0q zFG}~=i9L3-vHrfCcknQ#Du?=!ZaHGh7Y{n4a%eyKUC$XFbZ^SMb2?+EJnjdv`zP`> zX5@E&D&74o_SlI%F6bof(mFYE&Do3{YfHwCd7ZHnr!3Mvc1lm(NKc(%j~(kqweh(J zQMS{w=B)Jz=^i`DOdpb-zJ=50u*XjMGe%1}Yinl4j=doHr$LU`^2O1arJS`jJoRj( zNB7`iFGzcp$NeC7|3p4xmvXhfxIUfs!yY@a$4>Rn*pVkT0~}idw$0Gt*dB0f64*9_ z#v(Qh>9K9#*gP<8WG{ER_HyUfUJPfChO>9Wwi)!SZ3b~{0P@&oP@R`H!zKq0>FNjP z7svJ(C89F@o8C{8~(KjRoVvHjNilRO?r_x9SUG|8r#M^!ICo4OjvyFJ4%|5YmjykX_r z`~I2uexKZbWv9dLAb$U8`>j0Vowsef-)++l?|J<8ZTIc=7Vm$vKW;l6_95}LA9vMu zz_orZu79Wc@0tAd_o?!U>$$0(U-I2Hol344{jc(p-jhx_$xk_vLphPpzbTi$r#?KF zdLl3Nr<~f?4|cmqpWH6;i!DcN`C^yb+%D=Pc0HF|{X~C}=Te{D>R|d2rktcx4*h63 z^pDv6Ca!Yn&(w#07V}){iM-T*9Iu)S8awp-{L~rm^&4VO|H{p;(C+%kQ&x7Zxwg#{ zHfuk9`Nvn7YiC~dDs7izKe@tO+v5sXZ%>&&zrtKQ^);Ke?e1}>iTqEv#dX@V9(L9W z^X@apUb?;Uv3HqxcE5Yxu-*2F-&tV}9=zS<+t;6Sj|n+D-1=ti(y#uHm9N)){PvGF zZ}X#fosjv52mGwY@0F7I?YG~${o8FWHr=)6>32@svR(8051f$y_77d8?Rn&@CI4jy zUb~(8sYg%9fB4TfX>WeiYbF2n*Q?(_``8{6^8aqPKWv}b;|-F3%FbVz4xVPozw<3_ z)*gGiXG{K%Pq=Km>=6e^{$Zz{HT}U2kCXiEFMg%A^EvO3{2xC1ThnRZJxTH}_3u|} zH~#*6B>$N9gXvO_Jz4URO&Rpb)gF4?cH_OeyN62Sv8Dr$5 zU+5X~=^Oe8`HU@NjC}MC{X;%u%NQdc9YhzA&)71?$VVU1OXRbzGXIg!*fPe*M>o+? zW^-sqsS)@dynhCNc~A?A9DQ{sXyuL zNv{7Q^{@W#>3`*^y~_1pr2f_aJ^f$xU!?xk|2_R*^YbVfAxP)|Cj#s=uhc?kN%hb^yp9Ne`k(a ze|q$%^uI^{OLouvE&b`ypVI#x{V&-)^SAWBNB>K9&-^X@@6rE~-7|lyZ+h0B(*GX) zFWEiwxB6zz`cty!%-`ypIqOf!o-==|Z|1B&HMVos%#uB4{#M`2S$}G5=d7RAH*?mX z8rwPRXZ6jT^{2*m&iYxpIcE*8zL~TB)Y#5hKT9{~tnD?nbJow&%{l9QjqRNEvvhOL znqPBkMlYFPHMVos&(h5~>wnEH@h#n)v;NoIQaba?^%Um)&z~rr`Q`dAknjHQ%k^hc9_E+pzd*kGzYq0aAm9Dp zhx#v&@BZ(|xBf`J>)(;@{_n`Q{z$(2za!uJBl+(Cj(qEn>@lJE6X@@sCf{!6~sPsy*j#riM#%q`{^_4oQI`8Bs# z|0SP1%rW}M>%Zia&K#qEy#7l*>C7?u$NR73d;OPu@-WBfAMd}CPkQZNslVnJ@=34# zEA`hLbN_3OQGeyxYfAk!$K3ze52-)G{>=J={haxW z{h9R#`&sg_O_*bhFMA_%jQPdh&KyHNwh40#{bX-vj(PpW{+E3AcIKGZPwaom$F^dQ zA)mdSIp*~f`(N_0t(arT$2MV(As^d{Ifi~>n=r?ak8Q;qqkphRm{-Weo?>26XKX0u z5^}Jcm_Mr9@(iN}y>OA|S zt3Rf_XQ$;^n1A_ip5^c4gL#hUVdNnfrX0$1dQW=g@5x_s=Ey1ebL7{*bIPs1y6 zH>aK@Z%+NI9Qns6%jq3VP3H)!mh^8Eu=UbWp@#Lv6V;VU<~CLAdPI|ZamjAKs^rB;q6utS^HWdGc=iG9;`hJ*v`6XW zyN-Wjd-i=FJUzd3@)^e+)b9M#M@;DCwhug{owLPbCv@`Z&wEEZ^My~G(8+gP^<8b= zW{(M--1Xw`Zr3{NZ>IfACvW=TSGTh-{yE9~$qq-fm%QO=)9Xt=Z}^1Qwkv+;OOk)} z9S>~Z``fc5|L*U7V|({r-<16Kz4tBcp=bV!}xdYe90TXy}ju(=Su$fp8nGIs_m}ZsQ-h0@$z<~J6^x3{@cE)-T2%aHR^xg zf8DQr?Rqz9)c+FOy|(Re(zcEI-{4!XYcD$H=8gIvaL$w3$v?ld|AEkxd!YAK8>a{gF)>)F0WDLH&_U8Pp%yltKOJ z8~Oi)E8Dr!#wu~|I(MR+W`HU@NjC^zx9YsF6iH;&4 z-9$%`k8Yx)$VWHPQRJhW=qU18FPUS=M>o+?I;&z>i?epFa4PZ{h0^-nFsxu2mP4`{h6abrT=sEzw~F0{*?aDgZ|Hh{?CK{ z&x8KYgZ|Ia|B^jt{+9mF(f^V?5A$~(=I=br-+7q7^Duws%-`ypIqOf!o-==|Z{}hB znTPdf9@d|ESbyeW{h71=)Y#5hKdW!%tUooj^RRx-!}>W7>*qYIpYyPO&RIW8H|MPR zHMVos&(h6#SpVl?{hx>Re;(HVd07AFtp7E)X7rxko<`(@g`8Bubf62H0%+%lgFZtG= znflkb_p zf3H81@A)hFUVkK?zM+qn`g0@JAIYb0=%c0nY|Hv1`ScBagnX}`lJE6L^1XgaK4Z%m zBcHKljHy3k%NQe{v1N>@KV!=nBfsVr>%ZiC{gnKgTde<*k8Yx)$VWHPQRJhW=qU2h zO>`9b=q5Ufe9kY-G4Efj|B_ESa}51~YyXmbxb`o}him^@%CGNp*8U~=*t)fUrT&^@ z$S1w_uhd_24Ef%FQ-Ai~)Svw~_17G8{WZtj|C(d2Kl^X`Uvmukwja{}*bnJ{?1%I} z_Cxv~`$6@${geL3evo|IKhYoTAIWEJ9`pzMNAg*l2mQhRk$l^4(I4y|$+!I``L^FA z-}am8Z~IO1ZNI7hw%;V5y^%Ra|JZ($eD+4>82!WEILu${PswL*9Of_fr{uFY{vY<< z14@fx+uKLLEWvP0U;t6Xi~*Rp8pMQIR1Byfiei=n21GFelEgsH3`iI+{PJvPj8Q(% zM#h-xLpFcb@_DvL`osKL%jel1=@0W~EuUw*=?`-g#u(-EY-fxG{bc@c`pNv?^pp9& z>1Pt@C-Z;PPv-xspE9;svuOFuO&DX8&)kYJMtqoCMf%VB#q^)`i|Ie>7t?>%FIv9z zN7gJ_CeJZ)cVvxBezoTGz)^0P54lF_6Rn+nw5BGnThFlN+Gq{#qqVt|lda$JvD~M~ zpS&q6hxMtIuWY$b*e&-7w%jK;)L;F{vE=uHU4Jk5YyDs;M{}QGDPQy6Vat7jE%ynw z+$Y#_pJ3ug9AS&+!Yp6i;RjnhVT&hh@q{g&u*DO$c)}J>*y0)4_1l5quN=xDkITwe zws>acl%C;i^;92=Cq5QWILal%U+Wjjv0Sp!cw)DB!WK{1;t5+kVd5z|{@?N)LEK)( zQTy^9$?B;b>Yv9R?n^oJALY=mltX-!L)?_3yfPo9Ty?5OgZG@Do44d zKFUG$As08XK1uEl9Obg&uQ{^VLoTkBuQ|Bbqg+|)qdB|SLoTlRNBKEYPHB!1_w~Q> z`vu#dm3%ob`Eok;YiY?7>!beUmGRz~`$|H-oY@`rC=bobQG1lPX1|+c0?$uZEl#%S%bazPyutF=9iEob0=i^I~}^Y1o%{vPYJNeffm) z!@hiiR)l@|ME2c$*q2Xa?<@`b@(JZfc}+g-%O|o2mxg`$gz}@jCLi|Ywfrcr$%lP; zEkDX@@?l>-q5ffCUdxa2n$oZ@ul0}en$oZ@ul0}en$oZ@uk}ZNWXx#!VP9U$5Bu_3 ze|$n-nUC_aRJ%f6nUC_a)E@H6sK4dK`6w?-eL`Lt^|!n@oyGU~5;pTwU!guF89 zuX~>%{_M+Z{naPSD@)1QVIMTa-}3sXzvacHVR>&*!VPD?*kL4xO|1GbQ{$qKG z^nb_RIq?bm@>+h_m)HJJ+3fv?{$qKG^nc5%Wc)gQBlLgEt7QCIUMT(F@+uj>mKUmH zix^RU*q7J(hkbb+U*y~oqcDCgFBJW;yjIOw<2Q&8Id|kP(7s_`Uds>r@{aKp_T{zw zurIIWhkbcR{ApX-nD~T!c`cu|rHv^+?8}oItT}h&E>OPcr{(2p&Le%4`iFgaEkEqb zlRu1pT3#+WFP2Lz`jh4PQ-0W^*Yd+2J$c2_e@gTJ(SOS;7X2yx76ARXykgOx((eMS z{^S*C&Le#^)1T7s1+4z$6-fUn{dRzy9m^|_{*!%2K>VY;0*k+={DZ>x1(YA<81VeE zya=m5`34q$@*=GMpxn4low(B$J4%{ z|7-bCj)e6eEkE>sPkf@h4(tC~ew5c?{a?$E@@lOAX#JzS6dS)UX$s+)<5W{mLK$A z%MbdgTh{*Jijz|llpUQ z$Sbqwuht)X$Sbqwuht)X$Sbqwuf?A+ruA2!EU%3EGsZ0b z_>&i{<%ju?_8-O;bHosT@}jl;F#oam>l`ukAM&Ct{yIkt{fE40EkDfPwEQrC(DK9l zN6QcMH|_sn{-g1a@+xiqqxBE-Hygh?N6hp`^P;u-mk)|8Fn`wa z!~9>%5A$a&Kg|D4fAY)`gMN}1t>uR`i0Xfo*J|^BEkDXD*0v3KW#~V7(d3oc{9nrt zYZmg#Y|gKBray+fGII0De^#9jYm-ddvo(nNlMh9oW(^qfuXMc@mD>3o@}l@H^1sNJg2@Y$-%}3xSIQy(N;%|TDTn+kWv=7;P=Cvd zOZgq%%|&((2Y=-#kBj@V{4VZ`e7QXSQ9hW}Q|+Pt%Dj^!j`)ZBRSt1b4)IYAaZ?WQ zR1R@g4)ND|hIUbo+spP_C9f>CJyyvpOWFS+*0RTxvi}3i9#hKx4=j63p8X$K_Gmo& zKd|JLdG>r@$t&}cSEej^Wxslt8{SEJ-gkv}mCAqCJ3xM)cb$|U-nA;*yJGD2t{Ap= z#jw3AhQm8vz1H3pW4Cw3u)Qme?E3D`-W5mX=zGFYzOub5&dSN&6~m#P>SOPUvD>?1 z*xnTfe|=XB{}u1v|2z8$`=24lAdT`0(y%X2-d7s-DF<+c2z=rD0!Q%MbhVT7KA<*Yd-@yp|vK<+c2e<+EoP@`6NjbYEV}XU|Y#q~(Wwc`ZN6Yf7WMARpy5rD0!Q%MbhVTK}*w zujPk*c`ZNe%WL^zUta4U zFH7HtguF7Hi-x>1<&amV9P-N4Kjf7uhrBY+cw+C9_T{%iUK#b*y-(UV?8{sIEiW#W z`deO{XKaPMGB5RKU*6)+zP#1n^5Td;`|=u}urF`%x4gbo;%|9{uaEwdguF8PkL4xGGpjT&k^aNJy!9XU<*ol%UZM~C@>)JQQ|vv{Kf}Jf^?%E& zOvAps^?%E&^kH9K%MbhV8lSK)ujPk*c`ZNe%WL^zUtZ%w&KkdgK7@UFtv@+y{090E z_T{zwurIIWhkg01{Qt^pMSm=>HDzoOqo6;Q*NXmFUMu=zd9CQD<>jJ3me-1YT3#;t zX?eM+=%?l7rlOzh%bR{$Uasa0(#Ggp*q3+o&#*7A`W*J<9sM)x%bWgNUNQR5zP#zb z%a8JEOn>sUZjN6Gq+>W{`J=%~{ z=%>;l# zg+pGMa>y%F4tZr>a>nX}yfWpGSH|DP}R35i@uLVP|9H%_`;=LCPer}BNS%=qJ@bUGdl}~S2d%;(ijm-Sp?X#e7 zezOM@lXxIG~^m=Nj^0~e0E;#(&j4OS=f2sZ6RtJ>&Z#nhA(sEj_I;gb# z3*I`o^mn(NeMo72wmjp|(t18H{m|0-m%Mmr>3v~8@AIiz2mCLZKSP;vTAw>hnew-p zJx7_}-7G&Z^OyQudD)}N)U)-7`O4J)+6zmRxv$5EXUzSYoj92PIEjyyL)@%<;%UE2 zoUJ~@-|9)bSpBWNI=2N{D}{2af2p!sdEA7~8Cw`uF(! zp#?8ok?{$QA6n4j>5MB6esIAVZBJC6RX;zlV6z4%DPMH^0}Fo2ovhq-hX)q4xcU_3 z?oZyoVELn`DlZy%|AO;so~}H#`~3?x?|Vk6ea?@~OZ|_!%d1S`f%9LN_%@)f1 z?pE)eqfCALymOVQ=c8wxr%e4D&&rtlx@u|0N4Du-YQK5=0j2(r%pXu%&b!SAmX_b< z)q$nI+b9`STAv1e1}(69ZY&wJ!0KP^xk07(h28EKe~SaPbF$piG?CJ@LIV?e*~` zKPuB+pVj+Wnf98{y@JLTdy8*2Q^tQ~%Sy_WbAC}}Wy+tvVsmAFck&xsC{v$SGqzNw zp68#kl`{2zYjVci*VfNv%>A03IG8{2v2uu;l}|kFcZsvrhxl7PX&0+M?Pd3c-R>8E ziv#6Yd??@I#_w7@sgK2(dRqLczqQN%=KHdKX!kgI$5)b=t$nduyTjHWVCyHa^&i;! z6>R+twtfg(|1>-8X#TV#Z2cUz{tw%@fNi|MHjZE$UoiK@{leD1u(dmE{Q~?iaQ=z!o3a;s#qh zVT&{TchQsot@>}zYub)`w01P69eEC7ryY4d!n7mLO_+A%c?#2xJZE9rk>@W=JMz4P z8FxJIV0(_6o#&nT^Spy8hvywk`8@AnewXJROnrFX!PJxI9Zdas-oe}>_Y2c+%}#$d zfBLzVL;tt(85j1uj2EkqJ(nrdp4YHF$IWi{i@(Kzax6ZSZ*k*yEuPfJ;!Hg){?y;v z#oCVXV)qMM9AJwNY;l7vp0LFkroC*wL3`Oe#M%oVYe)09`HZzYcIywY^%L0o4{ZGk zw*Cf}oo6!VB%WpGrDl)kqQ>}_R}OZYx5GA{hc~S&|9I}dyUjQ7K{uG^!{`a~d>EZ!o)4ox%=2M%iFrPZUNO&yH_Z?K+WFz8 zc||s_{+}?fFfHX-Y|I$p`Dl7;jJ@7&SNnxkYbG78?pqKzA2IflGiGK!ZQJ%Qv_$zQKf*nK&6CRC_(86FqsNsWI&y$JVcMh0>$^VS27Nk9`QTIgxS3<8D%abs zySwCuNy-In?sB^pOw4?~y4g*uIzhQs=j+^QpNv;Nvejj-)nl3ca4QG++7YhwHkFTjZ5{T)40Myz?UEM-HvydOnxc|AwY@ z+>q0sRr{6??CV}@nBDIkYxZ|t4_~47_Hz$*wNG2Ce8H(r+>y6@sQmoYquq#3Un_r{ zG<6#%|ERpiAML)}y`p@-TQi@3xUp-{Y8&OJt2A)eY}i(Lw-ai);)|;&uRV4<*JEH+ z!x3xduM*u?(1JaJ2#@ki)#O6XO}Cgmi3KMpYEAE zaPl*1Klq(r3VylpY31|kKVERe+NYEYI`3W3v~FgGmXzT-wsO`eo2K9KxT)-|tXCfJ!_oe=ceDO*Mdv1dyItSO>eI>j z6OPI5Wx#03D@$Kd`$_NC^Q{|ZW2er+`}#Xx%*JD{9qRb+M=VgEtv|2hn|_-0+k=Yg z`sN?aReS9X2l|dnvvKr~j`jUk?@d?x)FT@Ei)s}qA2#V+->zXcMyg-i#-9+z&a#Tv z`SYL1>?d}+(fe~U|BFxT;-Bt5S+CvL>K?!7ylKksf7#t%nPy{ZQsdr!;w$sie*97Q z`}W&q6BqC+0tfklTrx&w<2d2|OB9rEZ7EIQ=T9awb8qdTzZkVki5(IJoSz@kGQ-GN1i zJh}sm4taD379H~F4lFw4(H&TH$fG;zKlM$I?!cl$9^HXOhdjCiiw=3!9bwU-Ji3Ej zbSRJRz@kIMR+-pJ%sqBuE^VPqTSyxz(?;kHKB7Z;bO#n4^5_mMI^@wESaitWCAtHP z4taD379H~F4lFw4(H&TH$fG;3=#WQuV9_Cu?!cl$9^HXOhdjCiiw=2o2NoUj=ngD8 z6BqC+0tfklVV7G=>PG)Gx<2rW{^#{a_~Uvvi+9rEZ7EIQ=T9awb8qdTzZ zkVki5(IJoSz@kGQ-GN1iJh}sm4taD379H~Fj{1CcvqyJe(IJoSz@kGQ-GN1iJh}sm z4taD379H~F4lFw4(H&TH$fG;3=#WQuV9_Cu?!cl$9^HXOhdjCiiw=2o2NoUj=ngD8 zErZu?DT!c0L++RY`}~abO#n4O3@uybSOo4 zV9}uz-GN1iQgjCv9ZJz1Sac{wcVN+>6y1SEhf;J079C2_9awZIMR#D)p%mSLMTbhz z9awaz1l@r}hf2^LSahfW-GN1i3eX)`bSQ`Jz@kGrbO#n4%Aq^3=ui&bfklUMGXGH) z9m=6Q*hPnO=ngD8ltXu5(V-l=1B(vj&>dKGD2MLAqC>eTwz(+g%th6QXF}9Q4&C8e z(IJQKz@kHvtF>NPbjYDQ*hPmNx&w<2IdlgW9dhUnEIQ=S9awb8p*yhXkVAK1(IJQK zz@kGA-GN1i9J&LG4morO79Dcv4lFw4&>dKG$e}y1=#WEqV9_Cm?!cl$4&8x8ha9>C ziw-$-2NoT2=ngD8vkpUdVAf&i4$L|X-GNz$p*t|^FmwlI9VYW1W!7Qn z4tCaI=nl*}4BdfQhoL(#>o9Z&W*vs^z^ud29hh|(x&yNgLw8`-VdxIbIt<-`S%;xJ zFzYaM2WB0H?!c_W&>fg{7`g+q4nucf)?w%l%sMQ3wkFXtH;JCbN%V|P&>gO29ft0} zti#Y9m~|Ms1G5f8cVO0G=nl*}4BdfQhoL(#>o9Z&W*vs^z^ud29hh|(x&yNgLw8`- zVdxIbIt<-`S%;xJFzYaM2WB0H?!c_W&>fg{7`g+q4nucf)?w(5`pY^D-GNz$p*t|^ zFmwlI9j3Y?%sLF+!Ol7i-GNz$MRQAH?y!pv(H6?0L$r~y=um?0;KMo$-GNz$p*t|^ zFmwlI9ft0}ti#Y9m~|Ms1G5f8cVO0G=nl*}4BdfQhoL(#>o9Z&W*vs^z^ud29hh|( zx&yNgLw8`-VdxIbIt<-`S%;xJFzYaM2WB0H?!c_W&>fg{7`g+q4nucf)?w%l%sLF+ zfmw&i{70E}7`lU6c377IzT@FpnG@Pf^3$KZ zMtw&7IM|;ulfMsNGe2_S5T8`bDerK~96xNUTFMWfHPKZVw5#&)E@R#2pH)(>I%$;q zq~a3o+pjhp;cmL*X60rN4tIMF%C2qMy~yo%`9o^={pPxjP2NkM+I@6}BCz{Nvd)z7MW?yJT3jeOq+t1GXmdaNJbcYEcM z?N0aA_u4`Eyqhodi}IQMT6d{$|8+IB@ALDOzQU(lDX-nEgFm##FIxUKw|DT>@5kqryxBK*2<(uAVwZdcL>IF}~y4 zZI$1>@dSU_);lZzW=B-Db=_l7cOzjs9J=1Udb%FBcm!0NU zxJ(1bzIvSBZ1aqFelh2pmSjHLRzBEYvO}il=RUf(A9&p1dTsRvyZE0+W3UpT$itNM}6XPVF1oADFf*%KW#v_=l2zotKr<>dbdb&b{z9^{IV$ zzGUCMyD4ARqfg0=8}3zJ*ZYE!`#SbgK6%bIC427QN4ZniM;bo6LuP;A{@n^roR~ce z9v^Z`LEBYX{TKf{tKhxkI;#Iqd%aZ<)uAA&TP~_|F1nXoQaP*h?o}SjecY_QmeY6I znB3Ndos@5yJummvDOvrO*LXa))2rF?0%S)1GP(VNu2;rh>VgSO9} zai{J4O|It`t<`?xc^h(D?QxcJ?&l4;s7-TGTf3+axTtTqNehqCYrkE*muplZ>nD$% zae%9LL8A7zPH*UXU7Gc`yDBzu+isKbZ9gCHx-W02KHW||!yWzoABzpGVARVTr@^pG??KBHr;@A4~L z{mM@$537EYd*Oy`{?l^gZSIyj+4J-t*Wc}SsWwS{ZX4CjZTMo4@=YIfb$xsGP;Sxp zZa40O%apIV;1>7UkfzEVwr=kt&2fR7MuIy!e(ebu@J9lE%N zJM5zx_<8egZo7q7D&P6Vz3$P1LghpD>*XH5@+;+2TJ(0UzuP56L+)SJ!~N9dAmyX> z=;mI{9jkoxKDW97=d@7nyUq13(r_1PyNfj6Mb85F!~+ZU+7BCD>^hBDs{C{R%U!2q zKT@v!^tJBfOTJOwdU<sICcJZp_ZsPRJXV+@S#m_`Hq0+8ePP>8iT|dz*%D?!rdaj^yJ>?U-)N*a!tFJt@ zN*&kckwm%kq5HYFemYtCv%34c^ocW-uj{hEdurPG%H6J(eW*(>QNH@vTJF1-FIC>- zh+SRXw2gAdYpb~$<1SGCa&$#kv1<$ErL#ZFjdu*<{`{@I@BMR?P{%Ny5xxNo} zSMJolYwpmKdn#Yv@RHnjyY^6C@l2B2vQ;=_{^wh1&kF@xx?}eD`Vkee0IWjrXeHKR^FsDhFG=hAeS2qZdhE^n`^H_4R(qww{e0E84p+XsSsfqsJsXn(-{BkBQL7YhW$tSc{^oe@W7#ke#tR!tNp_!BmKnD11$WofY+@bRw7&)zr3{c_Rsswew*nd@%v*g@GnU+m5~wt@1>d#AWw zEgGnQwT!`(h(YbnngG}4{XD*LVV3k%(D$JA5**$XDP z+N%y!Zh8J#H@kLo<^0>D-0*(=l&9??``48+O|G%`M7P~mb8?KGc27U-s{T}@d|=TS zcj|T{ln?r((5)}b=5Oa7KgMnT&M>tX-CXRtG|KdRRo$8Hv^Qs~{hFVqxn$3*{Mm~q zyA3TaSNj2jXS?R_Hd3C{beLQIQd{K)wTHS~`x}&hX*$*|UbbBU^>HJMecS7IQ(nDz zlz-y9H?;osT(N(@^Xtl$&z<6*t57Y)e`%Ge(k|O7x4(9l?|ZiPSn=$^l!B4CIC%X*yU7xsJ?VH^`!ry<> zqb2-Sw`Yg>^|h<$Z(aU!p&!(;qVg}_4fmG~&+N6=KJ2eOW~KU9cz2xtdh6xN&t5vp zhj#*ryqmOl0!j2vAc@`yB)k)t^tR58lW&G@nN;6$LQd+COnRbHvi)7%mCxFLqnovV z7v%-NeB<``;TGjLF8I=|?2*|&e(int#e1F9{@CKTUCSEnmFIMP!wub`weqqPmb($p zH&ed+_P@sOw8W4AZr9+M_d zKjnruo~m4V_ov;6Ju0Wz>sDIgrq`~meAo@oxeNc5D7Sj#Mb~Hdvz6C8xYT`m>=nvS zocfyUTf4LJz&+n_JwCr(x!L@6uI}K>{$9yf?y!6BQG12<-?@*^@2k9g-B0d~9mgrx zy}VNL;k}P4_t<7jd*7w;5AVk`&f)!-#y`9t({}OAnxIR`Ni{c1UfjN^^72*RyU&)W zb|od}edKm4%zWCvz19tw?9^vbw|CroZS~z?GU&q(rXL)&vXM8 zH&?FJZju`~PPICjd(=d?aMa~$zx3PjZbIMdmB$`7!96*ulX8ug6WzbJyGwb|g_GP4 z1N51a+){0tduhGCM@?o9n(byUctCyXSD5cMo-j~(*wn@DvB!rf*WTr6xAn@A%3t03 ztXn>NqVl%&Uv^hLJwy4xZ(p_dy$O5c;r(zDy&q2G-LSnMPIx~&;qGO6?R`~?UG7x8bG|<@Efz?&)tAD1Y-(9k>1H#mZjZ z&#icEiSnf#_jMJ9FIB#;-2txl=+~6@|MpOK@ni2QFa0oa?K`hizPIJk?$ZZ9RUTZc zsjIl*JLPWJ!RM*QB4Z_Bl@0Fbca0=)gjRxWpqe% zN6SZtM0b?YA<-RWbVzhZ866VcQAUSEca+f~(H&)UNOVUT9TMG9Mu$XqGP~%I=#DZv zB)X%F4vFq4qeG%Q%IJ{jjxstVx}%H^iS8()L!vv%=#c1+GCCx>ql^xT?kJ-}qC3jy zkm!ywIwZQIj1GzJXspm7(H&)UD2jP1`mXk9e^B4kM{VInchmEjlE+ql^xT?kJ-}qC3jykm!yw zIwZQIj1GzJD5FE7JId&g=#H}LP>b7?(IL?tWpqe%M;RRw-BCt|M0b?YA<-RWbm-=X zj!;I2M0b?YA<-RWbVzhZ866VcQAUSEca+f~(H&)UNOVUT9TMG9Mu$Xql+hv49c6S# zbVnH-65UZohoWb0KI}d5EY3&I+ql^y8{6`rb65Y|c4LT&cql^xT?i7Uij~Crh zMu$Xqa$)}CMR%0ZA<-RWbVzhZ866VcQAUSEca+f~(H&)UNOVUT9TMG9Mu$Xql+hv4 z9c6S#bVnH-isqlRg`;lhP}q}V{zF@+9UT(gQAUSEca+f~(H&)UNOVUT9TMG9Mu$Xq zl+hv49c6S#bVnH-65UZoheUUj(IL?tWpqe%M;RRw-BCt|M0b?YA<-RWbVzhZS#@aC z<;v)g=#DZvB)X%F4vFq4qeG%Q%IJ{jjxstVx}%H^iS8()L!vv%=#c1+GCCx>ql^xT z?kJ-}%yo!4nj`;|*#l>;gB{J0f68c)=#DZvB)X%F4vFq4qeG%Q%IJ{jjxstVx}%H^ ziS8()L!vv%=#c1+GCCx>qb&0uFS?_Q4vFq4qeG%Q%IJ{jjxstVx}%H^iS8()L!vv% z=#c1+GCCx>ql^xT?kJ-}qC3jykm!ywIwZQIj1GzJD5FE7JId&g=#DZvB)X%F4vFq0 z#1n<1_V%-I!L#(@Cbcl5qj1IBx zg3%$?T`)Stx(h~!Sa-qb5bG`&9b(<3cF`f$T`)Stx(h~!Sa-qb5bG`&9b(-DqeHB_ zV04Ie7mNfpQMu%8;!RQd{E*KqR-36mVth-=zNY`D$=n(5J>@xpxth-=zh;n<1_V%-I!L#(@Cbcl5qj1IBxg3+N!b6AV19b2S1fpQMu%8;!RQd{E*KqR-36mVth->mG)TeumDgKO4&QPxS>NH>R>PE_~cO2%=E6nC3onIK{x9NJR+F$r&gnOux z?$;+Bt{v(2Jgk@6-+#W)ozwp~<&Qrf@8&N$UiqH>quqU1WOJV0>n6H-uVnM3!(N{5 z4jpiT`aC&knp;uufbzXR7P*So+^0ON!Zi6?OxZh@DO(r0vtP@8_w6;a-0I{Z^;y-g z*i~pbLb?4(Gu*jfj#XZ?`BZoH-8Ga~3@mbWdel{J&|sQt-6eZ3v~0>u_sp%W)L!kW zS+2)%yD5LY)kOEuxQmqccyovwdutYxwF8H_XJ6kt^Z#z7TXmf7-6U7KSvu?Sun?qUc3$O1Cw8NpXc5l zc&OSho;lNXTKulg@ph_T?DpFBdF3;b;qLlhu2HTvaJZ}5P~SHuANDGCeKss@NI7R! zndP?GS#!>l*$u|KPAxanzH#`OV_fIH%e4GkyYzFf?Y>C)t0M-u4%@C(?z(2GyR-HO z%8jN^b+ zKJ3>dvR~uFeoZ3#H9qXuB(h)Q!+uR7`!zo7*CeuEV|xdQ?AO?yLL&P$w%3rzevR!x zB(h(VhW(mE_G{9xUz5mwO&a!V64|dw!+uR7`!#9UuSsOTCJp;FiR{;;VZSDk{hBoF z*CeuElZO48MD}Y+!hTI6`!yxecW3tPSW?dSW%_Me=WM?wk^P#2uwRqNeoaBxuSveS zVCP)euSsOTCKvW=64|fGh5edD_G@zc@7~?h2V}n{7xrrs*{{ik{hCDfYjR<~CXxLb z+uI^mw&z6*Z7+=2+8!A(&xQS(MD}ZPVZSDk{TdhcYZBS7abdqEk^LGM_G=Q^uW@0& zCXxLb7xrrs*{^Y7zb29W8W;9!64|eDVZSDk{hGM%*&d>3V?EnjOxRltc{qvW;kb~8 zlSm$p3wbz+iR9t9kcX2<9*zrnIEm!pxR8gFNFI(0c{qvW;kb~8 zlSm$p3wbz+axO)87xHit$-{9W4=0g49QjUA^KcT$!*L-GCy_iH7xHit$-{9W4=0g49NWuI zBoD{-xD(04vAyp^@^EZVJdr#c7xHit$-{9W4=0g492fF%63N4HArB{!JRBGDa1zPG zaUl;Ukvtq1@^BK#!*L-GCy_iH7xHit$-{9W4=0g49Lo(zBoD`O1`^4`v0Q>g@^D
$;_`P8v(B1cRA=Gz9no+in$HVj zv+!unT{y8Wkvwl_VP4BAFdX%XI=MH=pm`EV3KS{6>c93*_*+Ce4*vas5_OwBt> zN|U~4V&Pt2aguKb;mb_iVltji`_|E2n@lv1HzHmB9-go#6Q>;YBC{h&v~_+a>P~(| zo8=zSIQdMxwkns3b8P6t#|&K3yPT9Ctfp<@8MyIu3ssdhbEkR+?&&L~RJSqW_Z=CS zTh~QzR;UPVGcqu2Xbbs-cMAXgNk^3v-%0ntT9}=ij;ZIlA7y|YC_GF@g=sHIb3`aC zzLt)0><;DWBtz(ibZi}SoSsD#Loe<%@(EI=GM?F++n$C8EWAXwPaV*lmWDM^?&=zR zM!Ll}4Lvr63kQaEz`C<(*f)79?6IkZ2(2{ic0LPF^*_P^r8J!1c@G}wzkw%>sd!?O z1l$9HKr=BFFAmNFzrI%R%{>(-=vKgAOHDX^EEPS}S|Pi4xsb(DvHvP5OcrH?*~3zC zu3r}vPg^ebuS&uB&Yk2U5_aB?|WNEWs(Y z6kPDY9rmqBA?llgN7*4*r16Cmzi@ZZju9|&LIWM*exZKO4#LiHdTV@(n!$7YbRu`^UE^WS;#l!C+v2xv>h z%I@1#A*4aZ+eCERw2$&6B{0=15#irp+OFIP-bRTir)naazU_pB<%ww5?4WU-b2ot_ z648FvTVds=HaJ}S26NZ~c&$+lUt->1M;{YN9{K@VT;5>QFF)?Cjs@MLZ*ZX7YcNjo z=U$FCc+j>0u6(!wKL)(PHAPjRw_p)GD@{O;z&4n-B3&?hk$^GxxgT<=x5iWZ1Wc~# zgj>HZh>Q0pVD<4v(EBrxZmTAst?E};b#f0y$R^<6!ZdiRa+`EN#pAJak+7)y3FSw| zuPPQQ`R)^4Mzt-{N26n5q=InZ@TA9GTilI z=q~COium8jdbl1unw~up@yV>u5UY8NMqU?jcvCW19QWk!4H54ZghJT)7u;nbVq={h zgp_7e+fNDZ(^(G_yT8$qED2trpF%(mci;F+aP-A_!a(kc%e*APUWXLKvty;yYrO== zzpEGhp0tqlSP5oCt)$oI%1Mnob7Y&X>2gsnH77^o$CV*8qu>?Iy3d_CiHUSp?Jgyp zipF1;KT+|WlQeF5G~${%`h0C7%~g!X5$8K7^-_QsSNjTkWJ~F4FNc@g;$PwG8@&5& z-vi-@>nn`jUq?IJCP32RS7?0i6X}gQ3EMSZ;q<0NexK+C&Vyc|^_39HfA|V?%DLZW zmJJy_&4uolFY&PYDw5w>4mWLIqH1-6XyVJ~?|WZjPmkf^OwPQFTKE#3SIiN#io0N3 z@0Y0X@Q3iKtQlNCy}(;(yvJtDci8jz1zvb!2j_a{z-F@-82TU-oC05fq3#Q8O5{0; z2cD2W^99QE`wUAGj=`M2&+*I7dT^OH2K3)O$3@Z(a5wi5<_14Ul{6{LSehJd#vL^W zTiU^VQ>1u)<8vIpsus?xtI)>@&(Z5&5%jI%xxS7lG^3PGTkE1{Eq zQK)&?5_Vq6qrT^&aQdiaV9ceZ-YcW<%z!ds&Y@P49~Fg0SEL$SxI5-x^E3RQvPM*N z>>{kj4Ien`>2d844>f}Lr0>ySronG8OC&m)AbWk zj+{G{S3N~^<-5%i16m?JMf*Js)Lf!S9*$2@%hM;gxhRf0hWNrVntb8$2xefMzh{UXqNs`wE=HjGjz&0XJqX@uM_^}3CzQ>(Ec_W4ffszGpk8`MlGpwi zhex$R_>45sk$YgwTdN>Cd?EF|`xrMw6u>mS8>DjbF(xIvhHNK)a?yH>Z&m#vc5p0( zC_P3SOB3kRSitje;XJdq0HViLQ|aq)R9TrK{LSEQsoUXbyz!RCuK@1-ITnu3{#+An zaym($g`?KR!NhpZi3Wz_k(|BM^HT|xmWAQQx3}rTp)~S*6^4lxPiaMc1j#ybH;a1) zeR=6jGWubdV_8bZojd5z{4o5e)kMZK`p{sxFbvl0BHI=FM7__Uc#$*pUr%IebZ}?O zq@Hb5GWdhwWgdzF(UtV?lK_)Bp1Y0tPL-XPW$Vd;t=`jak$?h+p;1hz&4c)mXIt66Uhv2+~C=h+aVXk%vzPykH zsXZNG(3lXcYbt~4)=hAwF&Gc2G=o#B3~YN7jLW^cK-{e*MBNF-`)j43JNTbO;Y2Y0 zS=|b&TE2;aOM_A6d;gkyB3!7R>wsV?Sz6~o8EKe-Na>KBBOV}jLf(xtSm>>=hKza!qP z=pfVQ4>44k@6qPf(`T!P_}JT!Tyl$P{qBc&S@sT%zmiPH=RL&DT`y?w+ECir>mg3p z$sr?cI~rXSh)Em2)AowBbSpFvbN=xRRAQItZNmL072Gp)afaAydmw%qB&8sOQG)99 zKzwA{Lci0SgeSiOaQc*Tic($;hqD7P>O?NpyV}64fB?+d`igS$LO}mY01oo?qK`rn z)U6M|rAtpx@4`>8W?TUNl$$^^ZR%iu>jR#1^AlgVcJMvv1DrYZzS{dNDOh?x!1#R+ zh1mTa;C%W4b|0Mt|Bb7IrsWUN>D(z8ji117_yf%HybFgfB|>_=KXy!whE?^!a4o?f z%SXS1R%>gR=H`#f9+t!GY%K^s;*Sd1Ej(XQE7S}AcyJnLmpumyn}_)0`1CFaU$IbJ zTj7T@o-~7!_ir)gl^@1te1lc0I%H?(he7wUL9)f3oc8;eYnT0m1szbxU9+{fF;-RR1^ zR2Z0ipXbvK(ChjyJP&anCm&Uy!=4S0cAWc69IV8^{1L9?)>$d(2|R`*?Fn zoDejhGY{4GFsf=U9Qa%fqv;;j{JaW#etdvo&i8ObkS`3`8wXbo-@~3~V_@Cz0FY?h zLr0%{Slet0OZwl#xOr8OVWAGSC3jJAbsNadeJ9+Dx{I;4QgEz@)+n~Uiyq2653g`c zytMZ&rqwkr7>EJKA(2*i9JRJH2a#ABnF2W1Nq+1}2 zODAPhFP!b92ja1>baks2ZXY-hESwst*EBCoopn}t-`PnTf9~M?cY%^3PbvL-cL!}% zGDRKxHhK|w2N#T4OfN#KXd(BF1clusUF`zWUv~##!UHPMdQB-4?qEO1Sn~Dpqx=p} zoU`QvRV=tpYg0YZ{YW+aw{<=ZyyuA-t^CYfl_dT;<%thN`Fl{`QZjOtCq8}2ucMo$ zg6&98lu8@uTjLNYuk*k*(-LZ#yPxm!J#bcQDxEs$3WaVS7XG)Cvju?&!FN!M>A~uz7(yP6;uG5ialHnY=ruxCX*y-aRm+#0?AlIO{pq2kM`? zq4DoR*naI2?67dd=eKG=Wz;NKyweSJT-#yh?pMNrS#FpfFNMW56E!x=xN$bT6AUjp ziT4Uzaon$ZP}fqT_Fz~1+Wi?Ojyg=MuDRm*zi;8LtOqUM?1}@1hr$u?wZ7x%M_5 ztFI7cN4HYenA^D3XgQsoRzatmZsC%1Rur4{j`}9u!ViCfXnJ=vZNGa9=RJNyS3K^K z%*k80)%zpw={Q3Nm)*j?&uZ!1$0>AR*e$%T(m{EKp<)(ycVH&>h0Zt`Z5iu=CY;B= z&1bElw_I>-YaQKm9Sd@YT(I_BF?WX?hns3H7%P)Z-QIT~cz_Fr#6BXQD=)$Fn={%3 z+0uMT4rsk_##Cc%D)RjfudSW&bb7mZfM-Ms^qkT2;$*SAqYH4pGlm=(FNFQ;g1vIi zcq*w?P}o}rKNiD4TJefw0cf>^{yn`U~G{v?#pj!7EFrIslKchLI)4pI3gQF?L#{o}# zw}LXuceL@01713~0%}^zsc3}*y0=vcgMahR9wi41^Xe)X|x><&8w%gD@Ib1y&Znz$MoKXxX}`D}}&ONwZ+>qU@xVvGIT1 zx<$xAwoenZY_h?hzS}@Sp$xuHvO(KWCy3mf35$PNz~O3Oex-_d;{p1qW(#GUIsD*ai6*V#8ryG6Y0yzi{G)hM6y>_eU$8{W z0R!mz^G53KZ;8vjcT+;ZR~k}kfunZaA}gbG3VLCIGdDh=4U?bHVtWe|UDC;V>MdHe z&jRL*`B8iCIOxtZg!boPB79x!>l|*YIk<%VxM^O@jDWsU6gG%uu)Dj3nj>=Q}2up}DDrpy}NSQJto^ z;OH<=j%$E{X{K1=tPi`Um%xhqra0xFD-5}j3d7HuV!6{Zu>1TN4y`uDmE2Kx{E`!F z9c79wbIM@goNaKr=qA35Y=Xc=a?p0;CIj-jS@5HP~ui#sHIO`f48x!x}H4V)tEoI3*Ewx?jQx z`%aVV?~l9};SwG{Jejt%)xyNmi}=tmSoG2EfRXkWvFD6I(fa(1Gg^ERHH>_OZy_D< z@bd-y-FrOfM%BSS(+l`$s}aNwFNPy37jTrC7qr+XL2~|iy!GoPT$}$04x60E#L2m^ zyr(S`PU8NGrtcsbwg%p%p2OV-T42??7D4IEIdt#E9d4J#3f0Qzu%fvO9062gUv{ zv01r;61JVf1)HYQVDDP8`f(C_O+HH*CLgKN?Ag(tTOc*n@u`)I~8`%LGmC zqgc7FnfAZ!0VBWvhoe=#(U|UykYn>7hQw#l2oDDsy5K*o8}*!qEe{8ougAH&&z;0c zDd1;$9RCYFL>Xhgz}6YZ@lfUnT05`->T?Y-q4}&i$SEAfX;zg`^d4Zfg{Kduzk$?l*jJr3iqvJBY1)|qO;4&jxrPeH~df{b<^!nLZd zP&7P^;{P1PqjCFSqE883d~gu`E)IdM{TgYX_Ca(};4YfjPV(z8K=paH61Na3o$@t6 zzI_!hRkl&PmH`eGARnxbc1DNZ3otDl2Kr*)vU|5zP861wKyd?)P#ppGexBAnB zDt&(a7tqpWH%Zw+AD<^wQEAX3vRBo|VRzc7bwP$Wv3Ni3xGSZQe|{1x>;1U0sgwFE zofq8a>_;!-M#`}o2pit-!9S%e+#j_U*N*N-TmLk2-}N5MR5>ChPVR#JC->mjmoXZpR#JF5 zVh^62lqWQ3v_ZeudRX{F9S)AH0wn`IOqycG`zQ0kzpoxjv;yG0b_^VUwHvQm#DVl8 z_tEd)jZ&pTaCEu~i)44BduuhMpP36E9__+AOWNVKcC1jnbr&w-EWpA6yEXoF>!P}O zCwQ1yi;^H+d}Pr8i@qw*iFLZTIQI)^HXWeqmYrzTFBQ(+ccT#Ro!GhcF-Ga`>=h0g8ZMZw?A*oFhNji5M7P=+S zoVNR9R=5?bVvA@}?s?i^ycJ(6aWCSc=`?-fR;>QmPDAvbiely#G)j?Dgil5E@ylCK zzJDjJzw9P_8oLEwnbuRf>S%CE+>CbGp9%Ai!p`HHQ9Hkq%yg(w z!}F%|dv8ShvN}O4t_6h08?at;C2Vux4xlX?@OX?hH2vVS*+rE{2fQ`%7o{HSF!x*?D4R^6XRr?YOFqH#$0sQJ+gg+;Btc4!7cu9x_~Bs)%((uF z64ck?{rxsj?3_y~CE7SWbQNq_Qcly&wee|TqaeDpkj+eOJbPJ5a8;1fj-oXv>dz8w zc&`2E%{4gqrBs~R(oCDDtl{3Rbu@JGcPdF=jr*?Kk<*MEia);^%P)rV?v5AKIes;M z^hqY&_n!2QyBGR57L)fJLw*mm3eRZO)4ZTDR5^4Nb~JX-stcatwb+$dk|w34>tCwR zFkFd~ez()O{Sm^jK`XH*XYgYZr$KR)7JeT4kyc(i2b=V?(0{-ia@xzi?ebbknn5%t zL;}5@uHgMRmSm)x2TOOXKo5syWbaS`2EUf$`9Ec%u%i{`1TM$1_*-JVf$uUlEyuu> ztAwepUEnFz#K)RFpu96`H83<_MRzWPww|GW5y_2RY9uIO??w zC*DZ`CpC9yTgrV17y0{W{XqySUy60w4Is09IBd3GiW1HPCEc(SHmNN|6_Uc^9m^#* z%9h~KgY9r`1BtV(xer0D2GnHcQ14kwQ2AOR++tVg^LxZ!f8zkY`;Z^^9t>WjN)C0GL}z{^uBajwuiv2J`3eF${;^Pt~}6oqHS80HfyUi=x1H zx2FL$1NxB5f+n(11RQv5C*3(-N|q!b)i`tZGlPyD5%Agwo)zEyl(L5ixZgI7`ncVu zq0t&B-&sQ8`}R`$9t}LA)kw8}22pZP4ct-KNymp?6_uW-Bl+_j-#B-T%w6huIj)V0 zHByC@-D=p?yPC#mECeA?jbG0NB(#{o+4XAJS^b(K_5DHf$6{>R?@t~zui=XSVzh2D zp>x>zvDtYr@t3GI!d5?!9vV;yA2sOX|V3=0?gh06f%eNOpx6IJa{$(8mpaQ z&b$RE_g^V!9oY#j`SbC^f+pDQ-v?G0^Y4W&XrHPt6sXKc%j;6O9+oN@lBbG02DibP z@de_ZOR89sQwe{L3Up?SDqbIv4{e!dG&Ff0#%B;@6a-M=nR$5an-ARWj-#-V^YD{! z1@2!fB&*oDxclF1h*qnig@@*%$669R54O|6fpf7oeHm{wDJ$AH` zPLFTGxuzMY;!r_GPRk&|Z3b5C%p+xm*)L$;#ZV}?Iu%FF%mD{u zJ2)_YDqdau9d7Sf2kVok;PIAbV9%t&o)c5hyR-}b=*|*mjGBTs6{Ilxrjls)W-?xP zX#wlvM$zu*WNg54_#L*2TKZ4M&Ca=STHl5)y_|&R#;?F3D1^!lCSlJUFW9P>MF09s z!p^W0U@7@T6fqH*@dTK7zK$xkO~k5W{z8Fm2aWnS0T(7OeZ|jlninhY^ z&7>ajOL*{A8CP((!Ls=E0G7&F^*Wmp#@T}~R~f&oeL+8agu$NTF{r8GN#P1_VT#!p zG|oFp|Fl2D$EjnmYVK%~Gvki&tkGz6-c6j{zY~639*y#!E7Xti9H8B#(b%-_sSxwA z9S)_9!t%w_L0_pB=A9gcU*4UE|6+@P6h~om+kFt+62S1yNc=oa1pj9bVgG+4@ke|f z1h-j$%ixh{R#X8e$1epgze7W_R`}H8tKh#+36JcSLfwjHjcxrn%YUN_-mY3NHar`F zzrQ!Z>lj(0og;7s&pzg+Zz0D&!|~nsOsFb!q<$g8F@0zh1Z{gv8JyD(z2^p_`=`>X zpNe?B;Q&0!{X#!|6mioR1?aG7pqDEZ@ui8iu-m+oGFlX{b>?n~`b*9^-&4R-I zC7i9+RKTEfbBVQ9)4s}KxWeTsT~R6|ZKq)veaV-K&Ese&48sd+W9aXS0J`^mD4sLP zr~1ie6l^mT6Gm3i-!66D_dFCQ3T@;zE>GN6I0WmhIENG*Bl&1P1cN4bk^Q_Q!ibqe zu>YS%QdRB;A94m`AH`Byo}mks7Y3tRj|?Ik7pNLP7_a3&q02szpqe=d_jlf+^S{#I z(Ahz__m3VO(D@2uM-0Lmi-GjbxDjT@4#f3?&x;3}I>F`mKpe<3<2rYxprSAkv(++$ zQqMN6DAoJK$+YCT-xRjQ;lB3lc@gK^GGZ-X8J*{UVluO z{{hDMT!*-S{czu=YFLyqAGCt{ap!6qq;o!Q*rtBy9l|}R<83vz|L%(}v7NAK%uNvk z`eL7cjbM3s2(_*5%kP&;V0OYjTHV+OwT7pG;(S+1=gj+7=Lncm`jnis`k*yu(d@rv z(9PQ3cvEHv^ocK}RnEO}^0eL%&%MTv7xzY-vRl}+iL->?WaPk^cjY2+ za%C$$R+Y!d0-zMjN=pAAhbiaG$??g1vb-UOhDQQvy$+GqEIHhMHJ%)Ge5gl$FO23Y%*F}q8Q)SUMPD-JNXGl`c%i?aGP71Yf6!wpn z#XkcYXm$1o7#iObcZ~T$bHWe7(<41`(xep1eeVwbLwn)@&2Vxb{T#l>$lz*s2U?tv z1$PZ(aKoRCWTo;A&dST+#iSl&%{%7QB75LpwoIHJ)CE$#9{4#xR_L)@3Zb$+(BXHv zpgz47thfAQBY$dw@6rkw?A^`wFSUX%jql({(_c2?T@YNKCgHs}e;MPB|DVbCV3+3~ zw(7=5SUd47d@KFU4tv+a)(ul3ch+wOpqwSTa2IgN?jZ3}5Y!)9Tk!) zqb+EA=Fp+%oor5{HjveKTKTtwJ&<$=vnO&t|Ar2>cGpzlXLA=V3~6UWZj2R8dr2u# z+Qvo~w1~Vj`@fS&Ns6C{QSNaI7oebdILMJ z-9Z*7f`!Gy8`$60T3UN_GQ8Yh&y;?Dq>}xoVQEAi>pLZpK6c-Qt@3qD#Xgv{Z$v}$ zu39#Cgf)2|dIzq7HO#(X1v!5zho_CzZ0q-GF}$G#@|RY#qHF!dta(y6=vBoA98ec} z$8yJXO(m;;_*eMo*bJ5PE1B1{4N&3w4OC4kSVDq5q;1Lu!@P3l<-ogcQl5kPjB@rr z_Ra#hs-$bzxZB_`xVziw-UoMw;O_1W4ueCGAb~)z1W0fVgh=mmf+e`SyE_EPAOpAG zKD*by=db$fR^9vETlLL1QC{~mXw7~0?#-_m$G zOIGB9II!d5P5$QeP zvzUJE8lP7wu^7JdjmVns8oyr3OH40$Ph1&%l~*3)BSJ@>6lo4$;f`C|MHQbA(J}iK z9{l@J`I$9eQM&JCexk^2k=v)M@ZWuj_lD}fc-z&cx zBWuFpRYq*Rz)xj~73CToaIF4xp3m6!RBU}%n)R!8o_mE}7IhwsX9E|W`IwM(qR>&3J#w7o-6l>Ey&qm=Z>FE&J-sW5J>BJZ^`1G+Yv(-^nXAVKwlwc) zo@no`h}{d~*!1zI_@uG}9bZy?W|xnh`Gf6c#(O=_}>XBl*yHEFwu4QzXimkGMV#;$D79;`jeqxZgMYf_|Q zMcy9aR}#zjPf`zdq^W;|H&`6U9>v=pk$6=M-#+968(-mc`CTI;(Y07 zemTJD2$@w+T?{dSO>t;?{> zeosa9{ReofDhC~@QpJj_84mF4J;zqLzavhJ8n~ak7EFt59{fqE$OF!1AF-~U$tP#H zCrYjH5)~E;{!73cv29yoQQ}@CFWc+0*pbgGa-t)Wr|BoZdujRID)Z(=@OI+8n3?s4 zm&cv-_>wey7Y-1RRAXSV6=_3$u0_H?9J^eKpSIk}IQ2wyEW$L?p_v+v^r z7mX5~t6pWzdWG_uzZR4GqG#;huD$%vhM|#1w#Ks1M0@#Qzh5F+$nP6!-DwZsIAft> zW|>c{=avxOs&-a(_}oi&{KIZ8lJ#aQ4%}qLs_*8v2m7%`J7QR6|6M#^z+ToZY%81k zYA1hN@-#d4VJ^E=c_&{z?!Nray(VnI)E&I`q_^zi!XJ)0=eP3-;h$M6?r>Zvww=e8 zk7GU8CXY-saT~uRzhi0OXZd-^BU|~5_YYaaUNuE@x~;t3jB~8U!|A4RHAYQS>y6I*}(nBt&UtA@=>f^5zJTn<`QL(yb$Rg2JxuJ14QQXH$=v=K|Em+ zf6;pPVR2;6dVb*iKH=Yav&epX9se2stXNyoTO=y7jt{*2K-8O2Ps9#i%Uid2Csyo# zA35?+AdmVfKiAwYcVzk;f&BT$&!Xj|{Ep#+0(ibM??mm>v5q!jYxuB$2f}|+ebyrW z8on|7jA*~no1JX6ntvLzPjrmh%=+wD#T~1ci#7?OS+j2|Ise>WbRT(xxofZFYZm1c zE8o9h%@?oWd-|-53_kLam3`*V9|jGs%udF!`%ZtpYtRaqiyH-4=&0dKOV}`Wb=5WYOTJ~CFI&l$Y&*!D6a4s@AK@(5_YExg^ip2u^f}gl_)Jzl>r#HH z&?EMH{~D}Ek0soh{XJXw^pPWcuP;yPl;?{{i5HYxanWhfGZA)p4o@|4wD|Mu6_GE)9Nsh68c`{5zgRQKoBvu+e$3Z5 zNaTx}%~vhFAewHRCb}n^&E10^i+y#txZQFVkGuL_1SGo_`OAixyywt3G1u#AM9UvD z_~q80#p?QP9VMH{&-sp%^*ba9GnY;0Rj%I^ZI-lR%N|VQ1ro{ctIi_--dUAtyhXAQ z(X!VLmT%!y9@O1e?0CmxPOI-Y)A9UY*DhY zyi-6R8!*q!PMD+l=-MteDfc>7r1L0#qy8oKar0!B`~67%%ho5XUABts#H0vY>+q z+&GYL%z2#6h+ZTDyaw<*M|ZMcw(b%qfA-^-A{Md+w~vdQ{(X7ED(%>)FLy-d;(d6E z#VJ_Ym-0QoqrG^|lzkn0a(otX<9hPXvEdPWRK&~7|vW@XW> z^b?V=L06vl-4u~*%|(&qWoMow^Lo*3m?_ExbmF@@MTrH$0phc>Bft5_Wl`>raboiM z_FUY2Dy}>#B|i0S$1j(S6+w=u$gJtwa^Jmi;@sSB5z`N}=40l566Y4qbj6;qCTMXBF?AXIoC!;y9f^5ugM zu+Di`vt7Ar@bQ6H*&g;AdlXWQ2Pb&W)@&}qj0RPC-04`>w^4|rQ>?*f$HcMqzOj}0 zdd@Rv{KS^d^o^9?XvSlgyku$2Y~tRTD!fhaoATMKKH_En$~CH}Pd zR@N?Ws2F#s0)N_E{$0OSr^V}b<@xARjai|S_r;i3WqB?CZ;k=G-iqq;%kVd>yrbgr z&tgEe(!66p+Q=4#;>3XaCHc#D&m*s%dMA8GmEb?m)Dky>9*R#Xit`xxx&98>&x!H7 zi}G(TH;SeO!^NZ?Mfi`=heWbvD@2>0h4@nAy1Yj>L^Sg)$lbYKh@8FiiJ)Qy_>(Rl z#l7~yk(aLI)7-G%k(N8cQ%;A)-*c9#xF_B(>2_}Hh+@O71vI~!^cLmkOa%w>$|CVl5;oMtCjuO z;SnkMr_wLk(d;=`@l+}JhDRS+Z13fc&LSC~c|4ANYqv4HX78l@V&ac1Y|!?|xbKPi zIZb}v2;7`%bS{T?Cq&WOirpPIpb zt8`v?mH)xw{;bC4j(j9qbo#~yzq;?JRPVhQvi=YD={0 z{YD%SLr^p5NyW^R1Ij7qOWsuP*S)|+>kqw6OzbJ*O-0sJ=eGvnlE zogGz*``nQ4+r^58ogy8kxXQjYdM5syUxInxzr+%)xFXh{8^d1bzQ9%%*e^!yUBi;h zI?H_H2Z`-Lg0(z(iY@y&RqXkEfu;O-oE5(25b+}(vj(}2vV^HFN487wfxYS*%|>)S z88LNS99wbfAgkA~vtzFO{=F_q_p=_wld&bW-mtMHU94_gYu0VXUDm#HB-;|UfaO_w zg5?PfWA9(?V40`O@A*v|%KG<`&lN{6W{+xwu#wkqvw%~b*qXjO*^IKUS(lM%S>3>G zY~vaEw@yBecZ9{?!rrfsV|P0*idfccBRg^814~%{NaXJmf>_5~Pua-maw22US~ly| zCB|k=63ZX0VL8*f+4Qn&MaD*}SUR7ztk*%8NaN$rerxwTJGb67hpnwRCi2SdPs0D$T;}DSM!aeDTC{&N zn+<>0QDjedM>NYbQ+`M6ViCISm@pex?INFfe=Od_R$=lxS6Eb~i(>HdsjQ5b7aRCN2xHTF=9jxEtB@{0yuBJF?{(H^ zVZmeN-(R@G(!8w6W{)f>Qs#Ze-uhH!`G(z#?A7@_JL|<*bisO&+2?;|4bP`z*DF1Y z$p0f1-;&{+1D}Z;ls^~WpC$*B|2OgP#fvhtg13J)Gn~5YSQwR#t$35sT(F}RD{?&r z+cqh=xxB_|wmN@e_Mp^9@hrh{`I+6Hj#Zz}h+{?GvIV6-I+ElF60;^I<^2adbNpD_ zQ?#C!fe(+k%^pACjFYJ`?O)w zuS5DZvtDb?hUOSuWn`9I=JURd*yHf9$j{?*nAHR7u=gwKh#`*5=E(4BtWYCA(Y=34 z^Ydp1tMcNISe@aE*t4(#yPe>LXc2u$T!}5k=JiQzzP+|ZOwUx5y-SNZ^y3WiFr7+_GU#WQAYCD7QIV?xo!3=)aqC+kf;9%5Bi9t(4myFE(L} zDz_1tHeie@w?hl8#~4*^-&YRA7*%dR4_l2fM#wSpyAdleMu!|DPjP7(#>nItdGNg@ z7$cKo#>)+$WAcYwr-p#&2&D$MxB-6UX*NuMo$Z#zo?If0X=O zxyA9gd|y^`{B%uzmfYgF;PFx7*gSCzaopMB5OLf;eLrzrw$w!&o5<&eG{-jQ!inRI z)M>e1BVTr;=6a2cb)@2YjpRO%g6lQnYMGqtHS+7%q+D}6vM>qP9P?#K%r(b{YZG$K zv9~h;*Bm?CkH#<_9^jxpU#aGjD%`wyKv|O*pq3LT8$A^1r5XYWXs}slMF;$7<#>l)xC(dQ5Vo7{;j9A7$)J9NX>dNF1+K??4=XKiZBs z{@S4}ahwpp4RI{AycKbrn#+qg*4*5JIL6d&P8=hjH6@PCMmHgjtG_oQjuYoMB#zt4 zH6V_mC+iW%Jgw>y#|gJ;6UU$LYZ1rxS;i2@)8V6tW0P9H5y#l$BZ%XoPQ!`gyM)7t z`fd$Ea*iX^Hl6f9E+amP8|K( zbR&-M?sOrJqds;fj!)-%6UV%_XA{T!`DPQx3Vmh~$LYIf63220XA;L`O=l3tu*K7f za(}?4R(Nl@z8ut|9csSk^;@Efb@5FIg~v=-am-O*DRCUycL{NH@Af5*gA@4@$6C!66UTSHi-_a-s|$%^`a%nd zW2&(Wh~w2LAL95Uz7KJH(_lVvOuS|uah&^nE^$0iaxQUvJ$w#v-1Xg?ICfgNo;WVM zyN)=vDY%X}Zt1s{IQ|h5NE|mO4kV6~ngM$CTGs6UQcnR};s2<5m&J^aoZF z$0`X|633#ARuISP0sh1>`o(hM__fq>;#g$lvj5`vryp@#zGxS5Jb!N|aa>$zCvkk# ze+O|aw|6^ne2`>2ag1oOjX3u9+e#ek-q=DMXBXK*9H)-oOdJ~@+(aBlCfYBAdWv@1{24MW#o4-T6ML@Z$ZSd;7|Eoi&kAdzt}|_Q#~+=_ef%aYy1%;uz3mFLB(rb`Nos z52z8xp=Cped&F^lo4drZ`N})QvCQ4u#BoH) z+r)9u8^p19@O9$&{GEJ{&)VnYu6T_&HW_!7IHpZ>l{mVV zy(5mFpS&fGVI|%Y$K=D_5XZKWuZd&Q)US!-?Y6Io#zd{tfBLac2bN{ojY zy_=3We(_F69D9~ZM;zI?w8U}Sh_uAGR{TGg*nF&*-egad5V*#4(GR zg*Zla%|aZPCC@?}96R32NgT`1 z%}E>sO6Mewqt53bj*my?AdX3X%|RR!M*m72`}O^mIDSv|D{=g|Jv(un+$KA5JoG&q zal93fjX1_u&qf?uCCNq{x5;Nj^?E!urXX?LoL&CiC~G~oa1|hqU%C|_j^|SpAdY-@ ze&U$EWq#r~?PEUT7_=%Maa>zFA8}0bEH80fF()r^TwF3Qam;x&4{_`|DGzZRpF0n6 zTzoJ$ar`hVH*u`ryaaLV{YP=)SZ7sn;`r7mP8^rrFGd`P%qvD5ua_xC9CuwPN*wdZ zzY(VEYV{mNiK8>72yqPRSA;lLN>PM3mfBgEIEuD~iR1S_3lYaGYYP#_QZ)+^$Aw7? z5y!{p$`Qweb6B#wW4Hi%=^0E0MYs%H?#2`@NtOfz5pT}bQtn4}CR zj=t9!alAB{5y!WA8F5S!?I4bQ=QxO?yJcPCc;jmw;waYCA&$MO)gg{4AJry~4}EGA z$EM|L6UTy=YY|7kF|~+eSgu;caqrQZ#4+o@n#6HiD*P=`&-)!gyK4}~(j96L$Kmm6 z5XbrJs}skd+SQ3;q7>DMW5{RYHw-^=>Mv4Ky0;#i|>ed2iPMm^$~c4|H1STuh<;#fUK z{@qyX{J3szUE=tMmltu&^t~l<{1niVI0jU2NgV4wZb2M#Eo?y?z2)C5*8A12SDF*Y zvtyeR$9K7#6UW!bnh{5@LCuKclhnhuMziQ|NFt%+mOTdjy=gK4dZW3K|Oh~tDKUc~X%JTKx{u5~x! z*!<6~#If|+uEgNS8l&&{%>=xFGI96`gi#Trj+LJgQTi25~#x(3n9E-i_K^&tN_8^X7 z<$Dmvnzy?X#~IVR6UV@U-HGGAquq#O7N2g!ad4Z##BuJALBw&uxPX^Pc=AZ%m{fl5Uhh{!4v!#??fQ)%j%Cu1AdaiT zhZDyU?S~V`2j7Mf$Am${h-19Q!-!+=w?m2JAB%<($9ENm632;mh7iZ78AFKU^+H34 zK8NI4uVis{sc6%mqjNLJlI2NBglQ_Cs&ipTqg=Z4S*MH0) zj^W2=5XZf%W)R15!)6f2m9=IN$4wb$5XZfbrxVAX$K-d*SnqeFDLI!o=8Qj=IQm?e zLmYbq%^{BaM$I9P>l)4>j%{vGZUb;y9>=4{^Mi-iJ8uemI{vCJLKR z9N*2IPaHRNo=+SXmzqx;kN=!U9NS-!BGEh3IT^DiQfUY{2d$Eqh66335g z781w1LlzRpEY%kh$ITfQ630T%77)klkqd}p(A)*YF|gAD;@De$$CtjpIxEov;<)6p z4{;3K=tCTv&G8|QUtcdFj>!)#A&%pgEFq3fdo3Z3>nbfFjy@@u5XV|~e2HVJUB1Mz z&lLGxZTdMYFJIy~s)#RfEb?_RaeObot4*IDU$0(F9QO`iOdK!OUQ8SxWLiudUq4wy z90QIoB90A8Ehmm`6D%i=M=vfTj;n*05yy9}V1#PQ{$6~wV>_zL1!Z2k)3c(056zC`Oj`N`5Nh+{(e-HDpx(o6otG5r>Q z;utgDpExdTD)cNYyLjy=8w5XTay z0*GUgfB@q7W<&sSOj|dAIOfO_KpcxaTSFYLomfL0r_1l8)$d#RCJZKy2`&c_$EzEH zh-0y_LBuh0lOW=FDt8cZ41c$tIKDl&o;XhNTTdK+^j}XLL-=~)I6l>S;yC8cI^t;T zT}K?d%vwhr2ew^D97h*fM;r^MTt^%)4BbQ=@7LNy99v}CL>vn~*+?A6MQkLFy?x|& z3tR77W$(6;I3_8(kvLXOu#q^Pxx9fmHrcv?IL4c}fjAy-yn#5z(Ycp}o>a&?RX6(9|INm6~nK*t+BEK)%dfzJ9HTfOU z)_yhPmQBPldfq1DIP~2P;`n>?4&wO6ZwGNa+-C=I%dfSL&+pOD&V~^)siDQOS zTZv;-nGoW5I#CF5bY9s_9Dmugn>h9!x0^V&Xu6v?Cds>-IDUA)i#QfLyo)%BWxI%@ zW8g00_|n)#9QUQ(MI1x!?j(+5LU$5J|Jgf<=s7UYfDq!iyKx9{>=+VG90$w{CyqDTgcHYI zg~N$sg0Er3@y(eq;uyRxj5sbF5k?%3)(RtzZL@?C$15-Q5yv_1eZ;Zlf_=oXX}5jE zF=NGj#Ia(seZ;Yr{JRNyJvQAMN*sUA4<(LU-wWax86${ek>!Fo{@GU$#}-TwM`v0= z96#KTB#w9XL=wl$Ga`xO#fyE<|d9c^0|p) ziC7nL>=o@Ij-Qshh~vmXF5+0Is*5NIk88M633qY zM~P#V{zr-9Jo)#b^z%7m(j6s^B_AFkj#)#G5Xa^-j}XWE?T!$~t|gBU$MipAh~urZ zF~srOx)|aZFgk`f?r#u798YDBA&ysHMiWQxGttDceEE~av1Zbf#Bq=OJ74-at65u4 z5XT!6P7uc<%})@=3HeVD$G#tr6UV@qYF>E19la{4Lb)c)@*H}hxF#ZMXQ3#Q=le+*=muADTA{hon88J(9^ntsw4UL`v} zw?5b*KU-&vtM*3V^K{Vn*1iyY;)Y0Q&0-VqCQ$N|%}zCKeS~p)~%F ze|zi<5$Fev*WvZhum`))@B@EVyF<6j{!I6mewel+?K5p({-0^T^7l-~BVWgKoYEfC z@k>9EVzBHeZP{1a@~gBJkJ470O2Z!f*~X>YF<#vtc~Bbh!XNruc~ctW zgFh=Ce! zPcuIqO=ZR7(Xc5$V`Cn{)YW zveM2bRruiz*-iA3|L5}GO3U9f*-vTtIwoJQw6w>hU8TW6`qS+~x5JO_4?o%t{Am05 zzxIpY>v-@w9VhJR_~8fs5U15H*N7Sy`YUbOQQET4t#QGx(pEf5TX8B4Khmz!*0^*# z#;f}y4@z74QQFFz((r?S!>^17dDd|v|4PFi@@V-{I-k%w&(Kz!9NLOsY5ZIJv&O61tvo1gsxR7Ev*P^z#`lrXB}V7xDZdRC(7_ur^XS+eN;j_|KNq?7uF~@VO#a(MANhMG z`zbA7$K>mkmi8RduF{@pxy=+Fq-)b?q}@$MS3S_gvqtaUo9K zj%%Ft+P~}pRJ%1UjeLWVu zR%y$x8kfui{F-Suc&=UZ`<_!;?pq8?o8YST|Gxd5>W|l?-S7^3A)`;9sG`tl!+(Em z_gq_~eJ*2A{k2A4tu4RkqvoR3&j0uA?^J)wuj()3*&<{3AKJB0{*+VDG%opXp&Y1n`*w8OR>m(oMiCk(c=BM-Vix7krXEc?i(>VvV`;z9mZY{-o* zes%7_YvuQs7(Y&2lYeh7j-T0;&A2+bHHRLwA-%Cb&1$7P6-sLC4m_rG)~s(ie$WSP z_?^ejYV{gu*nll)*oF^i@UpcF_^|q$Han)xzG?Go+TwB9;&j>KcMVNHUGb7W(Jo+L z`b2*dTKaTJJ4#ERE@@wB=@WjHMjL*I{^*O>=r~~u8n)pB8oX@n%+??I(RPqGZ6CSQ zew7c{K@Mzjf{Tt{@xoeu@aT7=RI0L`b)9&Ev9jY%r8mtSDu4Gw>CI7{jQv;h8|c5f zW-avtjW+zwW9J9QYoK9czO)4m+wcJmUbc4A*59<*G2sLKrG1ypugeyX%ND207Qb3w zc&+q_b`x6qM1Q5FPuNjf`hEyik#2f5R6Dj(>BoFRA6x*kHKR-w*7V?Cn&K%-WnEkAqjF>j$U_c5QLG50agp)nuu1C2KP4jO&&8fe&nEoi;I zpyAWjj(My5tMz5sQR@pDbKm9{>q5t))))F7c^qD*-^aEjxpK%Dqd)peHAZgW50ua4>a~#*!w|ae~ zKA`p9Pq)K|?hhZ(umc~^u#X>TwBdKqdhZ7f8}I?G_kPgUxOBVP`&s?f-VYkF+w7~o zAKGP`+WSEx2evqs540m^wsE0dj~D$p`XHCK{9p{K9rp2qK4^mvX!Nz^U+vY=4%^@k z-AA1Phbir0P5Qr`L+xi+I-jaJf;}zx!!9(&f|#Lo%zEF8_@H&n&^l&l9Wyj+z!o%Y z!w0m*Lbv~OzK}W5a}4>>a|{~!m%01P`2y|8rG38P-q)eeoJ-eIEcC zw&4#N{^7%F$N5_KSN8$Xjx({%zPb;9cG>2##iQ;6pk3Nf_W_`BM%VXkq))V)x*cbD z-5)-n^?d+n*vAjFz7GJ6zVHF9?*l-?Hhe(q`v6uu@}T>x`v7Q1>^A$#2ij$u@&S!p z+Tv6`(5~+TVBezevq9s24(?w;>-%ibxc`IuUC_8Mgdb?M;djtj!*~reY`_+@zRv~? zUbc4Jzta8HeKyOEy3YoU`&~A_F8Dw@?t$6jRQK7?E^RAb9y@=}_Z`3sc?8G*u90iB zYmU&GBedoStvNz#j?kJTwB`t{IYMiWR=eV8^;aCBrJaB7mm-I9j^myzasn>DjjHVY z^0JD%R3AUH>Q|?8;)vQxk8D-fc`Tx-(tp-#?)>muTcvCJbaWQz*G1_{7yCN9cI&D1 z?1R5KA2|9b?f>T#XUTgW?Y(HW)30f7)n5OFkF)!t?n)QAy~H`?Ku4uJS6$&en5>o3 z6`rnfZduz<>B3>_oDWY{Q~LbEU}wi`<(1ykb)z$7j>1YuW!>al_#vCp!rbOudbNcU zV=-QCab{jROX;DBgPh042Ps{++H&XILs3dE`Y_8mbmdj0|E$v6S)ul8rMrYwbjD`; zsdQZt&pEe2lB%$|?ZQH%LU0PDH)U_e*G@>Kw0E$>wfA63rQ;nu=lVV&nbK3Mc}9Z=%vUr_6CDDB6&tJ*xLWcazS4n$VLD z818Xjy;M_ z!{Hf9_iMS_*>!oK(j$A#cfNfdp>)8k@y>o<&MF-i)5=*Y(<7yuZ7Sld74%VQzprnM zA-?ex>kd<98rjz*QrhLL&O=&y=Fig>C0xI5Osv|E#2j?ZSnZh`O;2WUw_o{H*|}M- zrhCf4mrBq6IKW*#&vm7rH=gCrQRlGINq=494!pWm=>^kPxzG46QaVqqK=D<@CGasVbwRCpzspN*uNm<%C{R5mzpLpBF z8L_sO(*1V#an9;jU+G18hdKi;Hd1;{lCjRd$D1g3GS&mwKC0gE-372pD}Wd zbIejtO-MM;$C<*fuIk^s>SAY#x;2zOHDalA(`lx3zh9O+2Y2w)iY7@{I6vhruG+iR zUFq!BHJ{S9y2ovEo7-w2x79#ytAX5B1G%jRa$61Lwi?K7HIUnCAh*>(ZmWUZRs*@M z269^s(ZmWUZRs*@M269{7 zlTZFP^^>K?b%J#MRe+*bFvZS8Q|+Tpgf!)NdC4ZEmaE+*Y@_t!{H$-R8Es&24p?+v+yA)opI8+uT;Sxvg$JMw$@DBS~G2H&9tpGd;F$tUEACLvfgd=^PfHBzhDn(%lSXoCeQx-|LWRgpP#nt zzG-X!%YMMN&-u4M-`U2?ZR7g4+_Tx@x7SkB*8Z1$sr@==)26M4|8q_BoMrxRu8IGg z2mcSxgZ4d}O`Ep4YTwJ5wtb^%+c%oFeWPjHH=4G6qiNeWnzntTY4>Z>|4;U)_C35! z+s9@1`#IQt+^E*C zwL5o1f1~N6Fyl^@Hts7={EgroVaE5wZQUE?_iqgg+-H24($*bXYK3to-aaGwm$vR% zpZtv`y+Vx?4cfVT`1%_=mdo!RS=i29Sbn$GvJHETuZP;XGvr%t^t~p(r{!%s_nMi0 zMzIsSjRsPe_VY8c*V%70yVTNsL&iVkuG{GRtff1~-`Dsu*=6+1=jBfSd5LkSlxcWP z^>Xj2?q^hsjWi}CY~?OKY?)E_T!gVMxRtx(_~l0SW8ucjuC3kSt^AFNH^Ph-W!t!u z#rhlG>BEeUKijx}I#(Ez{Pr1XCbV_0th&N@_c_#HAKSWbCRt%PI)oaX>a=qY2=+G? z&EIPM&l&iWzgW3Vy;o4X+8U!@?FCA|uM}Z~&1kQ5vty@? zK6%n9J-fwiqfFwN>OG<)U7i@5A2k<<;n9|7#(?n=CiK(%kBo2OMO@H7Utcps^2%a+-PK>|;19cuw}nEL4(qnW2-|o<>7!qI8CNUbR62G-4kK;5$4Z|(8^Bv1e5N$s zceAydw*D@g9hc3%%jVZ*i^pY)(`Ad_WgC~vHeQ!44=!7NT(-QqZ25HA@@)Rh>&gG1 zOJB^Ti#__p@K`hN9gj}F{FNCV&%?ClrzdzXLi07{b4qIL$fKh7tru&ac1b)T^Uw$*e<44-e?(DtY&S(kI&Xc2&9@rF6u={;oM= zT}n?EgIu$3Mtb@e8|s>tK3wVfn}^BI8hF-Gm7>F4$Gt+RJ!bAs>VN3Jye_QJn*hY_UD{s zv2 z%?0txaT(x<_iE+1l$Py=%!AUhzajIZw6tT$yeTd18#13tOTUI3m(nsGLyk*n8K)t+ zC@tfc@9%~xEyra@j?^y4Mg8Ttl!hHSE~Q~#j!S9ymE%$x@yKy0jX34Flt%n=9x9D- z>2}GH`b)lKN6tgCFXsdKmGi{V@yPjO=s1TL8%puZc}U}u^N_}icAW?G*ZF}Roj2Im z`GjAcXT+oPk2p0K#E;y87jlW5LLH8gx8chK;O+(E-9at95c$Q?9%B6ra6iQGZM zCvpdkIRf9h9Wgte5giZah>jC;M8}W0pvQ$dqQ{GNod@*S`GFmsH`v$tgkPO!#G~_%I5ii< z&)XzY^;14?V9fVQpmdW8r;X}if2iwD{edTp3zZ%#UFXbEW6XgQO0O6mVLl!|JN?}j8`p++zyp=K=k7eqcxE4fb_D;aBGw@#y>` zPR#}J%QdWgVJ^xwtTbwvT*FFZP0KZ`G}g3S!%AaK%QdVt*0fy1N@GpSHLNt&v|PhV zV@=E2q%>-*IHCJiak+n~0*q1d?Y50}3Qfb5^YpBwQQ`T0c5x=atN@HBM zc89G$v)N%b`^@H-+2UcgIGHVeJj-aslZe~K%WZjJw)`+#-k2?)%$8?n%RjSmaoF~U zF55oDg=;^?iZzYe1dTO~+60X?joJi_HH}&cjWvzh1dTO~+60X?joJi_8jRYc+p*@M z(I2${8g@`4pkW`i0~&r&Q=kzKY7I2vL=A#QO|tC|sU0;;_eX8hc2M)Qebhqj7d2AH zgW9R%L`~K4qXz47p$6;mqFv_!{dIm|N9PUpbw1%&=Na+n{3A}y1@YVVhc47Cj2CMf zwG0|-8np=;YZ|o)8fzN02^wn}wFw$)8np=;YZ|o)8f)6Nk8)vc>vpVpX!J)dfQB8^ z2x!i)=swuAg=`^cO2i+t*MkY^ny@~`8!cqzZ&rN@hQod@*S z`GFmsH`v$tgkPO!#G~_%I5ii)^ML+3 zKd__o2Kzdn@T>ETcy#^|r{;qAF|N2giR79-r^W@1@nT%i$OFa&jcX>x1&zF6T+qlT z#szKh^7NPa$GFgL@yY{j@ru;#7#Fm~OKFRj(iShJEnc4f9$rdYyiC}!cqwg-OKFRj z>TmH<+Tx|O#Y<_6m(mt5Pk#?D6+gH%Oy#>Cel1>VycREpc8izN7B8hOUP@cMJpDbq zl(u*&M*k_i{;47IUc|pw4N>=Pu-3p1bN=tP?r^=vxNsK4bsXB-H!5xI89jY?bl zMy0KNqte#CQE6-6sI=aPz&`dNxL!k}9oK7UYu~7}wQp3~+BYg~?HiT0_Kiwg`$na$ zeWTJC7p~*5Z|xhEw)TxmTl+?(t$m}?*1l0`Yv1VU@7Xsht@k0YZ|xhY9s3rvTl+?( zt$m}?*1l0`Yv1VU@7XshZS5PCM*RN?y#Co6t9$1EHhW_`FKEp9zuUT#<1%dHQW|vz z=TNj;=QX9R^P1Auc};2Syr#5uUQ^mSuPLq1*RW}w*Qg!mP_$d;HKncdn$p&JO=;`A zrnGflQ`$PODQ%tCl(y=>($;xRY3sbEv~^xn+B&Z(ZJpPYw$5vw{+{!i(pH^R+B&aM zJI>=6mvvrK+B&Z(ZJpPYw$5vw{+{!i($;xRX~h4Z!0VrTKAt-H?{d$_&I=lI{_nQ# zaDNr!lK0Zo{Z(k}^<>Rb?bz$dnx!=E&B&UiH15sFnx!=E&B&UiH15sFn&s&)?~Tct zr8M?*GIvVjnj_adwaZ#S{bkKk8g^vuP#X4SO;H+tWv%h_m+{CNq%`7`HA`v4FKd?4 z7?*Cxy(rxudp&Ij_pY>k+|$y2aj#3qgL_~)PTU*Q@na9J$A!I~9xvK;9?)Os2X=Jc zU|;7Ges!J^kIp~hl-C$F7R3LbzzghfKTWfP22-$u25Yc`#+(E@Xv__;gT|ZzJ7~-$ zu!F|^La>9@a}pYJ66|z4*g>N|*g?Y%*g?ZS*g?ZD*g+#6u!BaNU!5q-`F*med%o!aI=8}#Rb4^NNITuGUT;MX?bljv2 z%?0uQC-4G0tYys(8gmk?p}`t+02*@ua|0T419Ju%a|Z07F_*v&8gmltp!J-D#+(E@ z-41rp=nr<#umg6`un%_7@C$a(hzIPT5hvI|BYv=h)@uzKOm%;-)^;!lw0+DC?H6-K z$Ah_~8% zg?*e;eL_6#Q~n4u-Zt^{KeHv$7?^CZ>c70a%NX+BV}H{0D5GWWKC1nwd?wkwqr1{q zDjYH{xH>7lWWr&i#jv(YAMlDceBQKBx^{T9(Y0%1rJDpr8-Kp2tMs6((Za zVaDK;9vxa|ukqUjkG?Qtw{dn_S=E2>ogGH~bQP4&(Px{{w_jzYTa?^ld>z4+u3dYR zaWs8(rDGyC80`wxQ99wWVB?c_L!~P`QqS8f{r{UC&Zt-;;0V6Z;0x~1;EwqKE!VV~ zC(xKDm_N{%KbTk0m{*u@(3o$ShtQaZn4i!XBhIM0UDhD#FKd(1up?`h(y%XUnbPnp zYn-RQj0a~<*g>2)i$WuQoKc}MF5NC`4E2{ahU~~1L-uhd)_!qT*74vBt>ct6hT_Lr zT#rlE6&f$vbso@P=LdFl-e4c=4spV-&NJfC`A3|Z3*xu)g8pX>{_EBt_UoSgnEJei zelEq(&kM=@zJYx|`p9#Dp`RC$=K}-h1hmU@gQ1@nl4nXoo{c^IJ)hUm&(9d+o{!eg z)fhN4o=Y$;)h^HCI1FVFf$!6eCp;8&hS(5}XdcAW?G z*ZF}Roj2Im`GjAcXT+oPk2rC@f_=pQpTG<3P#@%(Qn7;uQ?P@!=A_croK)JHlS*52 zQfX^Wdis0jo;`!o)}BFWYtNvxwP#S; z+A}C^?HQD|_6$l}dj_SgJ%iHLodbzFvZyz8mw_PhQ^%4*%%sg17~As%o)rjXv`(d zF=)&&oQeLQ)Xt&N;O2ZD$sAz|MoL!;e7iU^%#DlXgG~&b=7#i_otwC#c z&|s?jgSEDUIiT%hZfL)lGdLULwU|pfPRuc!?a{91BsAuv9xvK;9?)Os2X=JcU|;7G zes!J^kIp~h#JvpINBnkP(7K+W5A@$*-64+{3+|;LkI={~@(7K*B9G9>EAj}9ydsa# z$Sd*)jl3d{(8w!t1dW_wen2Cam^Zo|^GWx|JcEWE%s*(@$Gn7wU(8o%#DjSZjW{vy zp%FjkJv7Fp+pT*|6Ei*}s{^w;@; z9i2DW*ZG8BooB?O^N%<+7sUUczzgiK1~ofqFa>L9um(G5%mJ{2#@qlqXv`U~gT`C} zJ7~;Fu!Gif5*l+7>~uTWL8Cv|LBkH%LBl@SLBlWDK_ecpgGQWS2aWi_4qC4@XfW0N z!CKqF9MJYLH?&{O866Mil8zH|OvkV1BhYpo=K=k7eqcxE4fb_D;aBGw@#y>` zPOK>%zn$0Lb=}EvxvYAE`;|&dcG%k~Epy_Mxl&r@$|ZBCw9KJP=2mH$TbIna(lX~R z$->j$^K6FFk`eZ-N=tSw$&}h9Yw9oOfYPud=Z4a-FXxQX@GIw%r@!af45bmLoRdl; zemN(VmUEKY{iIjP#^940$*Zj*gE=gF^J3oadxTq7dxv z?CX5Oug){#!PAjri@n{;uop+~qxDeVs5K&b-VID?R$dse0ziBN3`Sb9i;L zZ&&&K1+q`ygxoy-@~+aC78~ZMLGP6=nzEL8BljMW?s+&b(A~=%IBT=g-y4lKr+wU| z^ratt%-5|weU8`dtojs5lgWub-wuR`sGOOdt!MQxzi!_n!eTNz8zydRt~wVYmV0M$ z#(ZpG4(}Q+O25kD%yO-UnPB2E!Bb~-POHMru%y>T-ji9JZQF6P>WPP<EX7!dKSpUP>cQ=vEm&sMvB|t!Z|flF&r^$4m{)(_2z2T|R9y z^UB5;vGryaXO%#1Zt{x~H@9SQP6%?EajPT6-27Rb_sdr|x0F0AzRk$uY+BebC#5?n z)=$gqEc1bxKeAjAv3{AHf2QT;n&1%8Fy(e*&((&e&yx_*K1(=nzNvwk?0l%wnOfI2 zH@gn0czA8Yyz%X>Y7bgyn7fvRh_xRxJ0F&7WVWlYN0b_$*;#XUeUt4wEmCdH;#_~0 znJrK45g22SZ*9#>11^dZ)3Z1a-eYE_HU~xKi!z?AhPmv>0kN@EX6Ll4hFM}%h>ES$ zg(hai&^_Yq^Gwd_+3K6SZk-TK9%OQ+`^?OY6~8E(BBqXc_fVKPli{WDy<<(Ytkeq< zcQBT9s%g%c@>1#O?A6Wp9rmjDN42VJc29m@RG1RZ8=Yk4&7U__yU!_Z4#{~{^>12) zo5{Z4SGs*Nr`d2=xLCh2v(xWb4KuDrxERnXv-9+u8fFXMaM37LW@o}3HO$e~JY&r2 zTi;yLZJ$WfGLy4*Xe~3gN`y!?F_ZI1@fzl!PWM#IB{mr5w6j-5vc`#>*BMuFB7Vf_ zOdlzd&z^5ISXABYl4ie(;q*wS`FiXLrBnQ1=8Bq;D(1;UtD8+?&nTV$I5S^2JRnN! z%H)iU=QRI_I;4CB)-uc%pTd>S(Y1#8sOov8yPslajyvIE;AzuHKfH!Hb-Y{bXmQiX zm7}UTVd4=nf8j}^_IPd%EVxe;Yp~il{IQl9Hy}*u8QW^A*P{2(idW?mYUsx>@GnK9RL#YG-J( zTIS%=`<2es*J-Z$9-?%rF)htrn+~h~XObIc^Dt>gzBbhtW_tbDt8%-hTOG6WoonLG z#}7u%4&2KYXPw#PK*)y)RKcL z=4s0fv+a{;@yCW4Muli@_B?S^>G}1!`Jm1vfiXH?GxKt)!(!Lb{>FmRhI#G7F{P6f z;O4|md&Hwm8JxwowKA{N3KN|Qrgf$}SJQl$;(*fkGCR$-A5JU%@-#E+w0Nk-d%C;R zd_OKutj+n0^KOPZW;nmC`rJrhm^sP{(YSU}r_YsYX71TSOzs%p=~`dS{Fy37v`O^V znCRl>uQg98{rQfJEvsA9$^X=F*RN{U>wR7636j_AJMk z`Mtp%HTD%14Rd^ovr0df?Jv*XQGKd4H_U_M4~XCM{x7P|IxMQ^Yv6P!rKpI3Gzv&c z+&N1rr7p4Tf|P_{VPJO`3Swh-7bXfj*Zzvw-ISt;ih+%RzB6av-}C5ypJ$%AbI;7& zJM&@gSvB#?ZIFmY`)}g7m9iK#mYt=;1NHoxua<}=v1QaTT*vPNTa%|rui|r(#l}Q) zMHxLW*Ys1529efQ(3S>oC3&AfT-mdf=C*$&Id}-f=a0|eI`i%(dj`H-NAAel@7amv zq_Xk6rVV1JNhhd|>0Zg{75<{*pObWW&_;=Njh{G^y~~_Wvv*nHa0a>2z)uW2d7U~u z=r6g=+8H$a95q|g%5SV(BF=0&MZYXJ^^2Xv-sO~1st8j_G4?;`RjD?CKJCB*1nJLbvkUDu^+H^|NdN&nqSuT zD{dJeu3s;Mq6-WJi$#``2~x&@2x z;;&L^$OcJiC0jogC+VH0B#Bj5fAOZp1#0%SujKOr5T8U`MUH1>ZSFPw{;S6bl7#;VEjf> z$JTkbno2C+Y9$e$8=Rm*{yxcpEB>Oxjx!X>)=Ng$NW|;0rF81+G)ck%_B?A*`o}=q zFXCf>_`c*i)xY*eQp3jZZ?9NAMqlLa@o=+`7-?yayrIldG+gU|Y`dm|xHQfI_v?VC z9mLDJ=Ewz=j^f8f`pE6`eg4_&|Gw7lku|o{t6NL4dM zqv+JKi^!d)Lt9JHsjrR5ohLuGl{jRrwaA^v@Je&>kkUcq&g0QTL(GVE6}j_>+P|rn zwU@}9Cw)^B-5_Ib!JNl3SyKe{bi7yb3k_uMHk{wz_QQC#{HG@BDS9DawA2)bZ;eGR zU!WDLUe$FV-S=o(1>y#pDBaB6pru?por7%WSNe^K6-- zF0OgfRpido>*#Nqy2D1~Yu$~mt;IuOHX?T(MYC4os!`U+#w(4)S@Z1hzJK~@iI(b~ zSUx7JiMBg$BXZ~YG`qEULdQnr&U3S^sd)cG7m+*9h&yWHiaA}dkNF=h#UU%4MeaQN zNB^Pj26iHM9us|Su~nt5$em|Ll(u-k)D~mYZZH!^Jhv9P^IV$MQan`DS>(=hELU9= zL%L&|LBG|-h4ZaN?hF|j2I3UP+<8nh4a6@+0`k0Wf9Ua5));@}F%vP0%{6x(XKOXF zs@e_9pKfoWb?Gixzu(y3)VV`9sNP)s?d6Ge=CE@aH70Q!{b$3`gW!3)RHrW40o9 zo>7amMOls=-m5WPOWa?mip|iU#lOf2%fs8MiD`SSMeaN<^5){AY8#RJ$zvN`@#1TH zkvmWCIt}sbNNbVr`!Ai1#8Wd=Tz}F4ujS?Z+IH7%Fy@)Pb;VIvU9o;?eG}!(+x#DM zAK=W}=Y8bu|6b8q+lu!?TjU-{xD3iI5td{a&n{oxTLa{sA4rY^dg+KAkF>@)Pm{&qGZ zcb*t)eX*jiy~v$s-f;FeR%93C*UsvqS*eZ4_vlG!y5i{^SL8bN-;_TOyzhKY9Y z+PkV+<6MwvprAhgnY_F zjkyzRhdGZ-(?~3vW{rJ+bxf*FqbBxA@xVHpMl{h)=WRvqJnzS9izdCCaNN#$s);Ua?zr8ucKao|ixCoX@_%k{g#&aXSajMou@ubLp)Guhn(f1 zC3ds26S?y|daWhaU$qsv^V}GuEq3s96uI;CKB6XGsdC41hbc|;>vS8DJI^X3J+b?3 zTai1@$TV#+Wum>vo#$GNrub3chW*W;?YDKVzGykXQRL2(vPMn(+bh;|4@buseW;pl zNsu8&ju&a-^?2kJWd&6CKs>I`!mO3lNh(9mJSx&1G2zHx##Ph5_xiuD&5%T6J2kuJ zQ9b<#e+Hs0%N%2nEO{s82l)Fbp) zyENqD)!Qhq!<~oMS$iV`ooATgKKgBG5<1U~#JbcuK9_~LA?-elriIOwl%Q$;nN=H6< z*oq!>8jft#)S4FToq+tqOq-rx6oJmueo!>EJ}gD&sftXaHt(hAJkg7XQ)9~rbe>@| zV`*t68!P5KGxI~~lI=0*70L>)UhA}*B{4a6KDow?mU-QOrV+heUYo|Z0Y^XD2zYZY7R|56OGQJ6XHi_IjS5o zVXrG~XC%k^eqLVmdh2*(c}qvSBb_~O%z2(^kE8j+BhY!89Uez><0H^{<}4UXdmW0# zc#1yd(8(5&=sXfKjRv?yp!0n88BL9X`e2>aqnzltK5~4QT~oSYoZNYMoc*;UaBsb% z7(v?{mtqWe+o#g%qmjtd7KKr-CMovC<5)H|Gl)huObDctFH6yRg%%(G`1G}=#rbsFp4sf;mq9?ra+`v7O&KCjQ)7ilCq&*qFU znrRV%-g2UcYu@w32#S|L)xeu~!Mggt#P}R?!s-Q>Dvv!#C)Y^s7 zo-ZPCY&WFOqOwbJbe_mgo>U_#0-a~W;uvajIuc_$9v((h=0~9O`0b9y*!aHBW8-o1 zK5~}5R`s#oD1km69D$zG?Ujr!)Q&`sijmSQ?_}7=DK~woSNjO`9O=bax+)?PxxuFw zT~?fcd-`po)%5L|2y~b|b0^U`rBdXp`;uv)G79cn-Ed2a&U53y5Na?o0zJoUos5cJQOGx!2h#;?zPR(a z2V_!XO$D;c91omR-giEy{n|vL^CZ2UO7|R)qVw20q|>}-k?1_1vqI^Wn+kLuo2hPe z#-BL!oFjEkv|>v%^2h)DsFovZhj~lD&S~@{yO#T&QT!~rqezPUAao$jJSfFFU8~b* z!3S0OuIcgAvU@a^pY0bw_ed7@b;XZ%WOK)zN8L1mPJYeilsV5b=LmYuHwvGVSF?iYi^d3ap4P=u+J8kXIuH9_ zyXnFy5$HT)tYp;cffU!7Y%!6ZWA7b*XTQV-(w*xfaSW$-4yX03FWh-%f9+3u6tep= z&v|n%owjA~GUv(cUEWuwVy%J6H0MVYI*;?dK>A8I0-a~q=QtX1Op0!k7Me=;&xk-i z^EH~TSP+eT$kCr3Pl!h6G5_IDbNWW$I6N8^LrqUf(RmIO^`%#TMWORd-5f}--H1Zx z88AMGUKge4JZFy#qH$D;&f_{_5beH`t&PliW*qjT%RkG}c@FLMpdaEQ(Rt2xoIxi` zqR@Gc4iBd0>{;T@(`tPNZMTcX&zz@fN)+`LqLBB@V0Bi-VjcTp7djv~0-a}6))=b3 zDgvEHclQJ;ElWV>IZqwvrjBf{Va{`Jdn{epAjLUav^<`Q4w2|NS9|xS7dk~CFPs}o z$Flk5&SPkhK#$y%qT7s1Polf-MxpaONe!YMn#WoQm5NebRJKV zL|;scK<8gzDJ?+Tsa*0k5|}@$VA83cVUOpDy=_qpTIB2FV9t# z%WO9azKb$(eQwuconXl7@csR6Ui;z>qgCZ;XSV;d*Z+NOr;Q2NX2@Kn(3!aeKU4ZT zyGE$BRQXlU3+BY3Ar{LE?gx^6S5uJBS|*ae@7rKA3-5dK)eK+xlX1w>?ZJYNn#wDp z2F@0E9qv55&hHna(0L{gA0*_r8-&iYtjh{ve_j$gPlD@VVd5bLI!|NzW1(12hR);k zwlx`fOyxZ5{k_Pi5q;2kz&bOiFCsre-FM>IN5c{3Ao^O_8uXHjMN{DeH<0IOgP#<2AwC$ z&WS9EkfHNT&(k5(`pM9F=6Ba7^Bq&sdGbSc3Yt$6(0RJqmIzB7WavCCOWTn*tNUS_ z;}`cQ%GT`vQex{**v0#Tdz)Bv1JCpKh3Ym*$YIlC2#r(_9SbK z0>|^Af)I6y%6SIgb0<@e#NoA1+=7W>y8@kO(8b5X+_MUFo`cFqLf^#-bRNw`<-(NS zi5O31&~ag~eH=PZocndb(?x;KGbpTD_+%P~b>6NBA`XL9&Lgz&Bs@-xpT+rHl%o%1 zX*?G!j><5GKcG%dbyD%TCUfGtU5+tlH?I})H>&0(<3DS%avbwXcFvP(t3}G#eDP;k zS)xytD-_6HWtGCvU#jwE9UVx^ehPG+obHvv)mAa+05cx^5PTb>(Ru2ww;&r5<8a@v zICNDglgAaGgAV`MhxIkji;V-*zMRnlf~r+oudkwY3am8yeM)=>CjG=P55W#@P72 z&tv0p@;-8o4Uu8Y-_3N%r9aW=IZeZj$h==Fo|@B&3|St7&Xa%KnJ7ER&~vu-Z$?(@ zsyOFm8#4A*f86Wq%2o^0MyMRd;KCi@+)NqzjLTw8(tomwkKeTDw-5n zXI_?sMC?n)eLu@GgDm%vqw_p7c`d9om80{xKdcvq{EkM?F+OKRZimZ|Cokwo?A&5- zkKX#FQ7C3>DfgdYkG$}C;C<(F>S4xQf}Qh>+;&}9_*90@vwz!fVP{tvI!{t;d-5z< z-;W%gn@oCEHB)tORA2m%B8<-$kRTt*x#D2{-kb;47v2ZHL0H)i`N!44$wT(u@pra&nKcPvYb+nb>_)Nes*o++@-p=UrYq$<#P ze#KV`o6KX;d7^gS7Z#|;qw`d??nz?Wvo(!5&zA+w$Yg)j9Nk!^ON`ZJs&k$Ltx5ZK zDsH~F8F6Cs%bn+TJ6+N*ONMS^e?yCGnI}W%X*1D^ly{58a?6>1By4sJI?smVpM(;%h7pKtX>KJY>xOj&nUU|KVI>nqsmD(eOpfYom6>< zSFw_uRI1K@j%ikraj#V8Ic0H`r0BA0t^PAfNuo^?a1C$pTJg_b|M#_~sj6>Pv-_8m z5HMGM_uWca8+be>q#auOUEfIbu2x|~e8E+E%bRgfb_?s#9B z?kkdh+ZD^Vw9$me*8YQOyV-;z-=7P>s zCjU}G?Cq|Zg}l`D=nC0?Ssx^^s$P(>g9vZ^ZiN{3DfpL=dm`b zCT|@4F`iSN<;2iIKlfNbpD1_t_PdpGn1QcXXa1XI_v- zL)G`$srs+TmLuMH-^jFTa`CujM|#uif9v6JwtI5FdDYE>nfo$7)7M64y#G{TWDX;hM!i*8td;qzBy zQzC1J`A`0#2D0QC!M&_|NCi358#>R2 zef1a{-}iZJJWk$6&Uz!=G3Kcs>PYq|H*_9P(|U5@rYmxvM{miO>n`X#{%$|Whc9mE zJYvi%@^!r{a&F^0GRvhG?&&QbRuW%dUvwD7?@HpQ<$>IH?h7(n%N1Ft`V+Z4&JFw9 zcvlM?hp5Ug>`{k!6Cd37&G#5XA0sbxp4!l-B>H|gbe^?KpOO=U+|YCMeCx??Cs*W> zZXe10Bv0I<(;qw|OLbM>w*Kq)2j`UcozH24sesONG@+8TzwCj|Gw<1RGGFS7&ePE0 z1G(zviswA$Thw41`;N)KZLQYQgx%#X$VqFylKb6RJM5fCSEwXWEVqN7^HhgbkdzOe z$ZxA_h;UN%ed_S9=Om1M2jO)D=a*#fOBcMh=Zr68=3-au??f*RxY^)>y!`WLqOr{t z>r_nAfZ&Jj=sauRydV`U2L5f-aK%@$o6Q|}o;&aBh<6=(KAH2h8T6LCbach%q{06q z(JOaF=ee`}Eg7EXiq4ZYRUPgnxS{jh9$8PWA9crdW^G6vv0?8We`nWJe-mgqf8~Lm^L^)Ya+$r$+pIx8HJxh0V zo+Yq8eLV1)bo%3h&f{qNnVc88q4V4tQA36}cSGlSIj4p=vvK3jW3uxr z(bZOc+e!%hL)`WY=sez^E69c}uIN0@y+0B^KTq_T2*c;Zsk0k;&PBgB$q5Bzwi%GDWa=m?@?XRISOwf|=y|JzAA2B~s#R@JtLCHGai zK(lNd|7kNnT@Bke^K*x+fvWuEs1!GNORF$f`J1&D+}n8{`GJ1`wCeZ>`G|2Z_&ZK5 z_C1t)g;%Fwurcm{-2G4hm>QTOcd7v3b-45JI^`$K(0K-eKcwXuqVu$P>I=G~G|+ka zeRl_?@n_6oc96Tldc7x@!`y9XH+cU20p>8nPJlyw?^B-7v$TH@sQr3Oc|On2hB!!2 z+{2vG*<*$w^Vm558U7G+Q~Ub&g0XWSBfGqfgQV}O@?+lpz|5`&bC?(Q_k^cTuP}!> zJl-8_%o{L=Idh^LWJEm29OfabJYZ=s8!P5K`UAZn`}0H06V8_q$Pdy)=egR)1IBgH zK%ePc;SR9#JLW2fk8^{j;^!E{r!gL&zV1Gj7X=4^#tKbzp1#vPz&KDHokupy9paBy zU=H)uN#3w0-U!F@&|m?&eSd^G%z?jrp}PGG%wgVR-~kp#USJNhYppw+da8}iGvkaW zj5wf%&NDCC9bEcXVGeU%j29?BKEiRkaU~MQcK?F;gb^|~c+leu=K4l4uK0N$*;F?a z)E_iq{6Fuw!C9?x%wgX6$_LtoJ;3s*UHstQx`$Z*wUR*75Y@F0QUYPbn@^a-d^pAp zu7!NY9OhH3{eAmBVGi?lHt(Hn)Ul6-6WpObtPyjVbu-;y_Jog^!`wB=4YZcr$C!Ig z41kyY9%62u)C4e2zJBsJ7yfR*T-mup+~EECml)6SG4Akmdlhn=lNS^eHek#xM!12o zK?QP{x(~$p)L{;Dzi515C1B+U)72Ymj!wdyC1?e)!Wu&sqEhuNn9pl|bMn8RG6 z?+F`ntFXVR;00R)YA}a+R-z}y#`k?58;_Isk@KF4T8z25g$E2Qt--wIL$;paG4%;@ zltVX=Zh3?`%<<_0m<@f7dCQ7?4>-Q38hJ=TH)yu9IqvBWOMO7M_gBnAj#an;omz*y z`lvhHUQvNOaD_KSCEv%s%R2>up!)#J2Ve68$@)i_$NT3<1Ptl=9&?zVIrblhQ4{R8BV4*}w;5?=ttCQ|w(%NU1~qOx+=< za|Pxwlh@wx``vTQVZM;z0S6Af#9ZaV5$@ofR)gFr!V}D+%aPA*WA`m6#~fzw0Y2dO zrv}F%&d3wme5=D8X2aF)u)?+ibC`YJdc)V@6_~?(>##RGc72OE%+pV}K`-OCn8WOU z#tqy%v$c^qPydTPQ2+S><}mjy19+aoelx<(c}z#S!LKQmn8R#P?*)hGYs$ZExwmwO zkn>M5Z@FrbC(N8(iM;TI7c6P>0PEy$^Mm7UK4A{?UiOSNMSQ^==47^(UP-)ATDW9`C5dIhxVc1E#iqf_cm4$=$#?>N)b=l^&2$UW+-*1K7K{u z6&}A{gslBF0ahdzA+M^7`Dd^H``Y%U-LM^X>p0M~Y=>Ou9Rq!*KT-1UTz5-jV0!DV z$QgYT;d@OEvfk;;f9~7fa}C}r<5*a@A-q&NmL3hIx7 zpOx@(a&ZzEZ~Lg^Im}0%$YA$0eRQ7P!)0uZGDGLt(>w;g+cYV84)d`UGD!STspQV{ zp*{w(uTmvHOQ{TsgDsQ%@ON8VqT-=fFhQR=JG2k%)$f9A`a=$d=6^7T7r8RKgXd@NDtQj`la+GVJ0lUt^Hx{}EMIj_$#a-{ z#>B#@GaBeTYGY(D$y5uSXBvyY-Nj&)kL^u_k*B=ycUyY$IPlq5rR3*4kE>(A$#}ey zkJ~lB!LTyW3fG^rpJJeW4=Z$oW}jo=AjwzqGoS05(;&p$4d?e^msqHLaY@N@n6Kw6 zV3Ykm?AOVa@$g?mG1gDn%G|PG1M-~sBp7K<3}9Ok0hIE<4!&kYvm z>t5!#x9;c~1JGL!`?7e53>KL_!FYaOjDdoKZLu%0R_qzua1-Ni_g)SYB--da(^>sE z<3D(>HhD7W_PYbdCYc!nH~lYRdDcb+{EX;`&hv3Tdmb_k&;j(P%HVy_dnM0dUZoxb zdp0`YzW@2W9BwSIM(*BDj@NP@;MW$J7-Gz)XUgE&;6qAY-k|IQHH^9QaOUOQc{ua- zx%2S$7nM{ic@Fd8>oHK>)DFGHJ0=DeTG-*94&&eVV_?l4XIv*&u26uR%TXoIVO|^A2cpfsDR~a_HcqR!tVuHXHut)c`_e!Q1>D`Y1N-}P zRRYvS-$X9{B8TJSw_}~Uy9uCsNei84>`)mTHN1l3W+zPhp*P3m6*ePhdq1GG;y7=&1Ub{ z%9~35&K_Xzops_<9K$z7F;HV+jLs9bTn6si&CzXi#>$|kmmcyW_6%1n(?)J!bKNrP zmXhZ%msQIl%uo%TCv%<*s>kY~+dO0SmtX#*6qF#l!f(j_5pFb7EjgtQ9(s!`B#ynzc&FbC|z< zONNm{o0Qynyx15P9#zM8S&cmpm5p^uezvnUE(QiWHzChw`MT2&RbnF;nTDPU(PoZ`v0@n|9!2}&j;JdP>X{OUOkZqACCh2)Dg(fzxIX` z8x|s)(kO^)z7F~4lRp34cX!cuyl;-rOfc!#7UKcGF)-?}E%K`$S-|V?{gl@^n$U^x z-)(I$9040j90~v3*0|bCXnf&G`0utXbmL*p+z`Tlw_hnPww6Ukz_;Mug#T_!E{%eL3F(A8&liOhUX+a_ z+;!d$=x`}H5pI1^JsRILTDF9>|^$${&1tsOv0U~ zs8kB-F?|XDw)J_N6jqrg6aKrcl(SL@YI4Qc29_qlu|3{||86TMG!9}@M-uKlRcx-` z&)tG;4ogacoZ23QuRr5E$l%Dc9)x?&FUA=YS0ZO;C?NZtfbqB9t^lu9QwevT#F0`c zGhcw^r~N`3uE@58U?O%SWXywW|Tfs82BfV z@O+-T6;g;CoQC(ZXY-{n4nzJP91Tssry~CxFNHt1Lka)gmX#tJl9nk5_Y<345%4~J z5aG@vYD(e6pa8=6eZ|Ze81k(}gcj=0pl9C3d zY5lPN*cK-IRg6|!s@?H z9zeMB*tU{lZ2Vo|vGF*0A329S?u#*-ua?4V{r-eI&pj(C%xpUZ`37s}S=~&+`*`T3 z6k=MY6Ye}45~Of%(lF$@hTibf*qQKeH8m=3@Eb7m+Z+Vl&~+lQ}&RGK-{y|86T=Eeg)$L=gVFt;6>t;Y(6~ z!ks6=LJI$N9fLefTMAtd$O-qHEf*so;`lt|c5fnZPI=$?oK6f5Bs`y|)F%cK)8YvK z-PZVl5s>m>B;n3u_q{h<&YVxU^JMmog!PLT67D=p4@5!Gn<>bb2S{P_l>oxMr6!f_ zYg!WQ`UhftOcAMj{PP^0yc#@fd_)VPWYcEEmJ1kmZzz{TBAkq}YQpK#|fGMB=oz+_x!3{FbHef~t`*X+Gh zR%hcFF8kOUCi%t?p2IvzBN99=#1ekCV?HGUMD{Lo9>w0}cb=^}QdmqBg!@dz(FoYNVIbko z6Q|GCpO7)g2CPou`vq7h{bnR|s|+RlcUy~O(GYUK2jRclx@;+fVEd(nJ5N9MH$sJ1 zI^oU}(nktQWhppEri-ND9XOP5=UKzXxkqd|vJfi;{mQ7G1c+S()8lu~_0PZ{s4q1ZYMjPPH<95^v zELJ)Kcb?LGNARl-#C!F>?Sjn5lk>DX3ykedmL1&L?uaZXSo<5jkjq+ig72Nu%#w!1%4eUPM3d_GcSiuK#b>Pm^Oxg`b zJXHg9o-%ic8Py!P^H{}O!TAI&?Bl)tfp9#~2)OgSziA0t?AtAOp2Z_=p?jV-aOb(U z-xfL*sAFt)PrRXZwHk2eap~#~e_A&K?mS~IS;6l=*4So9o&&VLq7K{{-gR(-CzsWM zJI~6FPLO8N9{Kc88~F7}4ae19zUe%bej- zcMagqGwEs<==-S^*7@UM1=A*)0Cyf+b}t?$kDtdWF4O?-16MnCfiWzHgZE|BXgjES zp^v3FHg<*_0|Vq^ZdQ=kM;o~Fe1B>S?io6Gui`oz=;y3~tkiad70!mp zSHD`qd0P$O&QoOW2=Cmrfcr^{?)I?BP!G8C2&b)~GFBbBucr7pI z*KTO5g)s~L?P0>=7Fd7P2}@+&=Kq-c0B7Dl?;~%&_@h2>=lOl#3T#s~fICmioGu_v zR|oDq9qgUq*HbOzbs2V$dtC$hb27lgi#k|eZIul?)@+8{_ofxNw@}BiRV2E=IIR}I zooCr`OQ>_#1@1gYd)YwOANttews)<-XQM7~=eeX|gR${npW^Ag|)++$L^prd|>m!``)N<0qxDIahPrH0L2Tnu+Ejsb`a2{jddIY zZ6Q0^0Lyn-Siz}>rr2NgCQGsvCIA5~`;kf~h+bkAC z{!?w>&a)!H7B-GxbIP2j<9uuQcD@-tCuR$+U}3%B!=75ggIT)3 zohPZ44cu9-jqhpq?Y1!2&;WU&n-y$7p^syj`^E}3UDE{aJjZX_gE&A7xaW-iX$P~} zyUaPAy~|U=Sv-t)eXxbVkIjKQ&u?!lNb0Er+<68x*}&3kTELxWcObB$!!&ldmq0LvpAM95&Vl?mRPG?O@NB=D?lDiM3yNxH)j=aSgMA zxDlGboku><0p3s01nxY4;vJyFTLa+EQ=@JLt9@Glcb-8dmasic9k}z%Y2OuIUv386 zc^q@Cz{o}mxbtj^vj@{>y1<<$;-NKcDQ$-QB+m-&b~42}ci4Cu+G_xJp6E7?kaS5M zxbqCRb^@bZGvLk>_s$A}7qY#EIgj538<_H48|SE?hb`QCsR!J7p7gSYb<1>+yPjq5 zK6^L0^Q5wOQy8ZW+IdJC*4`DHEF~#!W&usnKrU~46u9-T3%T#UP&hv}f zLhO89z~8Ey*nn4!25{%;nAI6<8=3=mo|!)XdWB+(Gdjk2eKVNZQ$W`9)`ck}q0K*g{omKtAN0d^#zj0PRaz3{XI@uG)5QSf z0o#ko+N_?)o2C^K5}`m|dZ6&1`_61o;Ju#H)-e84B=S8+U0CSZ3%SIriSRnyd3YU7 z!w7VqmD-vxbWbQcPuR1MWaw6Zbe`@(EdQz_`<~65=UT-zvd=aEoo8GdB{};t1f3^* z$w4wTw>LV^>2v$ZWUq8|p1eor49Vid6s-HCk>iG=scx~$Hd(@GE}kJc^pfYqwx(=+BF*4d(eK;(^3_G_T&e|EU`N}Pi4wcvM?p+_CkKHTS#&k27tc3)f=Sj=!WMx|kI*fu}TQRcezE|Ll`G_9v)|ofdu!~dzUX0%k8SZ%=bG- z9B&3-Jj#W|V?^Zs4`t z2l%yBiK>{*mYgTE6GO3nzmS8-+s@_4$&Ha98@k;h&G)Lfp!GR2exD!K{~mCX7{6fcFkf1dR!j`;NN{W)FS$od zABCXvjNNyT41VK>&eJaS1UXq1fc*`~E+!p3{Ly*V%oZ^=zVGwcc$~bCoRtoK7;{PA z(`31(KYC7$=?N0>Ld7>%D~Zd=9_Tzb4jd*nv;EL>UOYHSj)n&yPdHdYKG=ugo~{Uf zPx?wE=rFX^O|px{%>Cy~%d=!x`ygb~ZpX;t;NIAGotA9L0Vuu8w^K?F5M0Te6q4QkmcZ%3;k)YdX#+)NF?ER6i?i5LW+wRB%N{*6G zRYB-H@AZpFN`oJcL#vn*WZfwVI#0KyXGzE5LFhbB4;PWQ-a+U*p?b%Ng`)(WXJNwy zV(TnH=SjbDfz%PUHZtciT5yz%(ho)F89e78v6#))5av9_7I#SU^gwi;6#wI7e2N5p z=Jn9?giH=Z&$$wEoSaDYNB-8t-lGR$SV!680J*`QRqi}Po?j&{?7rN2j+oydRuNKk zp8A#hNuM0HRx{^WTy~N`H$R-CA2z3nymbJ2&USkxF=hK2_a6u4Nut@=51l71`7}BA zUV?7(VC)%ED+xm9x%|6`?2Qe_^8G&x$#3@Tapxf}7l_{{2|7<;#u;+U#vh$W{h&w| zw2+|lsQFzY8wLlV^V}?9&)Z*K5o(i!jsZD2WNeQ#WVfw>Wd61cWX-Inf^1a=uFuUU zJr@>8(vaV=Gwk2aNyzf>oPYNEzpvFfn1Jn6Oe+$c%wmy+3$p}AmXpEHm(-0;_(t_q z#ZVgPRB}GJKbBi8eNyuGeaZ0Yc&`pe!%3$8804O$BhmL!xx~)B+Jx8P&co{@Y#4#g zBRaJpl}`tt^IWj{ASe=((0N*vpB4&=W6^nLIV=>Sx+~Cm?k;%bdu>KMI*-G}b;rM% z_C@E>(VS4C$MSgiInTM|UdmHbX5zi%cWxu|y^QnTp#B(JL*1K__WzAQ-ZwfzIoW;^ zvWaAk@>?y-m0`|PvQ|?#|3r??BODDD49gYhJP&qF7UrE~xfkr5r|a*wLe5?`R_vVT za^_)Q?|FUDEAC~>eacOf(RsT5`A;~}Aqjm(NH`^Ig+9nbzHSuc>>DtTZQAD!!m!?| zIyS*wOA=C((Rtk0mkN-Wh|V)NTPa-fibdxU*XH`(J~a^gxG4X#pmih;o##a0N1q=h za&(^Thh2ok6LNGOCp%X`u|5T38q_~Y3>(V=*FS*v>M{;J84@2mcJW+ zpm=LVAFS_uvBF!kTQc(KO|d0?53uKrIZyk8c|y&9vFJP#UM>`VZ;VCf`E)r~c-B1; z<4L($A_TB+d;FZ|^~|+`7|+Imo%58quW~_RWBw^K2{g z6w=sy@n?8Lbq67QOf2$1$$TNBbsX}$a~{5W(_+ziw%(mDjMh+~1L#;s3#mWl=sZtj zzxzfv#o@kxGkU$S#9hVa=a&imTJ8h<+HK7h81v||7-8z8cr15HwJ7GyoyYb6nLCdo zW8OY@o*LGEzvT*ap7D=Ld^`EZqPG+dnj=INuy2Iyoag7}Rl@t*a^$Z&{e`ms`XOKF z{ZtrqPLB1jUT7t}UBlX8&eN*sxbKd4eQ<0?|K1^}O^8S5Y3e`pxcW_&8^q3eXpw;+ ztW@<^`*pEzvuAR2p7(pTuk1x$A{Gxx5*oX`@ZH!ePxe>3Ur=wI!1WD zN`cNZ^x_EN@k2R!&d~#ULih^>^2nW=d<#t!xJMT{DTE=rJlP9G&Ot4|gH!T`Z1Ufug%_0Gm7RJm$L{ zggvbk=sbIJ>U{^jRN!+`YPiXFcLxPJPtuY)-{Rj1=sZKG-Y+hzl%w;^+pi;>5asxu zR%f^fPBUVW51bt7>pfjHo_F@2_Py<>K<9~mkSIiaVE1L7V@G=l+u1Y2*{~r%xX+$j z&HY=sX`YG6jcEvFJQWg93d6*T^|Jo!1#$nP6{^H|?8x2NA9UqkgotkY%MgW|L)vFJRH>3m_0b{sm7^VB6m z<%z!NJd*~_FZs#d9qv5$mY55#+4I29!<%ik6AFA3=sAD<%6-SNeT_R$kg>Vo%jTD# z^PJ9e5L&X_9e&PJq2Vrc>=TR5^JUB|-_!jQvE1yYT8UYJ0-a~c>{MX_YlolnBxkw_ zH(0(7Kj-Nhq9YieP@wZz-W(^K7|GUTcFq%&Ho^Bp&i}j0mpRmLh{`u&j?AS#Q&m25 zCS5`$Csm$Pe&_K&`}p5ZVt-cUMSZV7QjQ*{@}*5Rl7HG9+AJC!W_WoHHI=E(b3RR6 zOm8evog=+++)DfUg<+kGA;t8{sz_CRc^UmX&Wy8DagPWR22u03!;uFLm`WG)Q#r;k z^VyWw;rj)z)37WHooC3x{1 zwU+8g!m!*Yu9*JmD@W&{*7K-kT{JpRRY(r~xF8svr)J&`dfGM(`VqzbJ%Y+t@sv;u^Eq@OAT0V0spo&b#o3i%MC{7>AiO=J#bux zZML0$ogR7E3)i0$mie^%Bh~rL`%d|^cXDs^1T({PRBxkdJX^n-Po0hgqw|D5*iDZF zhho20&p%4l(p2X>i8l_=2iL>!+GL`nj#0hPd9>f;)3c*`q4Rt>mQUw-^+M;_Y`TaZ zyA+M_K%X4Cyn_^-XW)c9T6D4}I#2T5MRZD>>b&dR;bMAvvg(|tV9G&^lRFQObEr#C z+*`k0T};ykgklWd16R@;3xkn|glwgKOnPF>uQiv@4l7h=r_0Xoq!YD5(Rtd^RaC;} zi$B8k81vMjE9e1suENXP%|DFHo#%hdorg1TpZf!E z--Pvxf7`m9vXzdR(-XbL&1*5;a8h-?G5c*Eot6}e``5|bm9+PUL}V|`x%4T7VEyqS z>!?v4Ylk_{?AcqXaZv=WlM7ERpnrC&&UuE+K19n*L(qA~O4id2tUizJ+VHKkydfB! z=dJe!jE(R6JT@LD?+bEa2*%vSYz>Xo4METGUAms?9t}n|$=gKXPcS-D9Tx z$SYfJrwyIL&~sjet)TU1LXZt~4&$8izVkVy&7|l&KlAfwaA7Dq&z0N)n#ap?%%;}M3QBljw%R%{LA-?@xt?51U2tR1!&hbHDx_k$7G_n!YPpp#aI zAs;kbPQ$l_Vx9B53+Uqws&lYi32W%qb-`F(GH@5Yb|n=1o3A`ZTNeZ)?=Rm;Bj2j7 zbrFu!r(Z+Rc?{mJq8IiB zHf0sj=0AI)^RyhXi1x4Sh0bHxE}xFP7mm&|#qk7f6UX)%<~#<+*3yPes&z6WdJS#A zI~YADyW?gG@(^Un`L(ooe+W9yl(uW=p7$Z>HhFrh=~LEU{%xzZ`A$0TNGO(1k2^*? zuLwiuF}7Y#Ti1u6^Ek9yO^197M(5eCwSj)z5RT5XzG?}*#^#7SPfG4iYBswouDvg` z+lblSyP{*{N4F6_zEOR*`k>Ge_qzB1wl+GCd{G| z{_at9n=t3N%>fi6nB(iJ`P)0XF88_Dd1vi=*7K~zI^S+_L)5vvYah>OgbrpJ}WI4=v&fKd(&t_X;&Xdi*<72m{JleWx>4psX4Dj+tX6TQl zJ3r@UkrndbFo{~#D3AO)&4o_nGO*6G?wu9=lxvAO&kc$KdFH!Tq@@;FV9s-rSW>sM7MSxy8(GpC9<|W7qF>BtGgcLIo}eA3boyjd%y~9A z+Rz0{El}sdRZVI3ayz{LJbPzK16SB#ZjjA6wTCJ4d*8ZL^SCnlKWvF9jrA*sIZye@ z73k`fWwE^GhN^VcLFIj(?8=p?=BC1)ckJn@*S47RT(L8w-7DK+&a>LojJjR2#hfR& zx*3iCqnZ*&*_6I1UlDVj%bBKha~oUCc}{mWqm}lTMVV5ct5cStywB5QT4nST?w{c2 z9}8^o*=iAHMn7+|ME_?GwxH7&Ds|ab)`l(`WP?8EFEXPgx0FK;tYSyk6t~2jXVz5< zy6=th?oj$MOZsw}E!qu{%&3ohIpn(z73lJ4Tg-V3|1hJ0bF452m~qXVc3EqNInUXi z)^uFIiul}5-epSl-q<1Ueq@T*LOuZ3nr*W}pFjU;PAzz!hw^#RRgfXC5DYmFa96G$ zavspXcCIPrJRfas=(hJZn78cjXGU{U>ftl%thXiEj;J;zMxxp?LM7WV)PdNt7; z<@?%O(YC={56^kr>)BAV+)9}9?2j|0tGAZLb)FQ%D)f_+Ip#cfBdq9$a8s~4V1`t-S$^h|{cnA;4zZA#;7TOvQmvY=hAltbRX z$(F``DT{S)y{ZNcOe%}zRl8QBe>Jwi=e}876WV%vdCYli&YRI~W6NXC^W}*dEn{Pj zdCr`4E83}!De{y%HuP(j6+WXcWth|4jb)Kbcdmjlg}OsboeV2t&NGIY(#4imnDcC_ zU_qM=HN~7~SYI1DWK~&Q=do*5m8Pbb#XM)-p6c}EkaEbU-q=yQ7F-X{dEC=XY0AAy zSoh~VE}uqOBR}eEPJ0t;1dHkLyk zR?m*E+)@^0ob0R9YXugV^Ef`Sppiq%VY{^{u%mM)T42tz!`+hF_vbO?IZxjwpvYPgJxWHE6B8*R*kg z6>aHni8+tgG7EYuwH)R=ol4lzN5{)y&NDIFmiq3u#++wG3v=3Rr#0q0DXq+@-e7)j zQrg zHN98U6!|W1TPNP0@Xk*{RsOw;C|k^V@_8Q{yT%T4o@4wOTBlh#%z1XLtx0R0<)%L}9*p7rW$=S7XpMIPI~ zCw<}*jNGL~?;q?YcKw2OBS#IS7na^dZkgYUT1A~hzU=NrK?ZUjkl7?(!+l%9t9|Jr zqhq*lYe{=IYT0lv?%O)ttRtN|Y(4JVx_8ByHmne>fp?gT9_~QfY9esoR-+=_Xe*}> z4ZOn~G0~kyubYDVwtDIhr(JLKLR-TEW+Fq*1049rEcEBPTW@-9e-Ltq{9*K_=P2Z9 z7bZ~C<%@COR;SM{^u0$S?%SHV*O}H1T7&zx&Mk4K2BqR~-lQSr_X_E1uho{AQsGT@@CGcE@|V(Cq%9SpITw zPnyyo9rtb7@o%k~6yJ^ewsr=)(z*JPxNj?cY)9(rpN)0A|Jsdy>NpqoZ8;@&rdB25 zao^S$a~C>!dpz#j8vDhWp07jEw=0`E)4%jmao^V7#;&wlwS~BED|4zVr2}W8&Z;l^ z(GGDNa1X`XH_mj;(ha!3slr=l`t9y4@l6`$-s< z4<6Q?KGV!b`P;R-(rNobkPRof(V8ynao^VA3(oY-%JsN!tIA)_bePe4+_&}alr#PF zQY!kBJkFJt3QfU%TRVJQ=!MJ4xNmDHk4wF_p(vwC=t2MBaw!J)ZRI!VKxY=) zjC+^<8tp>6x@<%aFYbcZV$Q>_&9_~FKBpu&)6ZAJQD)faZpffhFyuVIpdWG`(0{AX zLfp6Ya)2vs*De|NUbWrgOkZxp}uRBx6 zhHab%Ga?t$_been!_a*(ggnzqW=|9k_nfKKl?BKhB05qV z{}83V4c+PPp1%|TQ?K;E(Klir*89;aNpL5NN0M$APM(v?VjgM!|E@=y;^CP zUFiC9QOIU5UFoonE0ldkOP%RVs|e&74ZC4XG3Vhit>Tx0`?iwZTxgN3MBKO4f15Mi z_aqAUZ5b_gr9<0<w|kwy5i$JtDIh( z={@O4olb_LjM>Q^bc9iY2Hs&d$akh?zRtsT%ZlhkjgBqFeOn88?Dm`TnDU&b^5_oq zUa=_bCou)C)aynx?%SF-vjd$vKMeP6J-X7Jjwx7-`?fqDx=`Erc)ZWV72)k!bpdjh zd)$Z2h1iC7Tk-D;S6_+ywk9ofrmHNMEuFto?nLhvmU2ZQ%Uhu?)Ce@mcoIk1)JrFS;_ig31=tMJO zmtZ@j$S!nP$z>XNhxrJ zt#)&rY43b~Z{#`8+Q?3HWz7iOw`E?r8?}tujQh4mhw-srBntO!9en3Xo4;Ri*c{kI-3sknn@ILvDdEDZf+RL?7!Zfj-Rj&_ic?k;7sQxZNPn7E#EoQch7@y z-`44-9@MTPf7bAvM?1`gex0`zW7M&h3!T;|8uw}~PwPPS%ETe>9O*)n4=u%gTjrHq zs9SD4?$5f$p9S{I7vR3FsN{~cbd4}9kM!t4d+c9{`?l8bzGr(W9`|i|y?3U^au(yh zt!}w4bj`UW+_%+{$FX^r1-Ngk@5zqzNzxMBW8U9mFs;;a4(?TV^%_j?uRDbM!7G*? zM4bW}<2`v}iT*!4$JIH>g#5;spL8(nPmNdqiTm7>%MJQL=ZhU{(%`+F8Q1*i^m$ns zzz5fOQqAX3Jcq}dpIg5n0)4sIa!gt6MI}H56&jyK^=$l7!2yNo-i~Q+yAl-AfC??dD@)@O-{%2d5U%PrbYK$!Si{fz+N=i#0t+OJk)v&)mHG-f-T!qGm#25oj#xyGhyFWB5#MAqc3E@ zzOB)oo^;Rqj(9%L#8`LgLnH8fo+NV*`f=knJfElR7%zIX`Sun#w;j`mdd_Os0`_gy z9MYSfsoF3DIJAlnjn`Ms2znInPG{tu#PfN^pYf#!Ui{et_HA|A--jmV4*vu8ZFPw4 zMbj@X!t;4{&h(&@b{uXAb-c7?I4zj6E)(``ElKyJQyMsA!aK|rx4P4_&zok#zAdi| zcUr!5otChtj8^DJ*M`5`3%_j*<=rCB9c;Q2g8wLGcGl`L%M<6V7d1M^)d zKb~LfmU!zBGQoZaf=g*>lBD@E`mfbLL0} zJn6_m)zF9dXYTaXh%n@}JihvlC-97>uqmF@eqt>8KQ7aQUiE933Gee*UU ztX$C6Sst&yjJ9TgZ)?hW(E}$}VELn_o-`*rB?EGvo_1a|FwP9mt8r-VK{qZKqMXmO z)}5A)X_o=d{cYF1X~z}e$mL&p(MSARD2Hn+7?i{FcCy=f(ARCXc&5$81aD->c?3hw z0}T4{w=J%J+^H};pXaK92ep{2&49e6$T3gqQ*Cetyw4Le(3{TNR2|P+p}Fp~y*#fa zl=qrEhH0B8#AUap3ifbw-xvXVx9L=5y^HSDDnF?uyt~_U;SjnhJU9b>!&;qW8J@zUNmykAuM0J--kY)ZJ>pHTTXq4(EK%bGGO0U=Zc;* zrhaY){I)frh$q$e_ro)J{P@`4?lm8|MOzQ*lu`!Ild0T^e@7)c1G&LyZ;UC_9b$U> zyn6=h+p=HfO>YI+X2QO$*QGtESBcqpKFY{#UIvIjj7kc~3)e0*tomByKn^JMRLr#qQ)uF*y_ zPa5tgWx{V;S{}Q8OGe}QJWY1G(-AZ0;~2ci`|avwWAS{ROMBdD?W8~Pe4biKK6J&9 z-grLGLmo%N?alB^o=Iu$bj!3@}lgg?X9CS;2q|J%!>~3x`F5OTsG@XUk>hw=kwg={kE>ZBgUx6I$p1w zNq8ntx5Iploav3{^R(veTxQc>8L)3Fw1FoLSg{1p=V`OugI=$c ziqGHb{rR}Ql&Xb1Bwgc9D=m-2@|s?Lw0N;D$Pd@}|L`1F=Oi2EcE)R)r})$CYmvyM zyZHSeU)XaWat4tne7ZXmdD@`q^pb5Xa-W4$=*ZcdkUw`0q@k~OAYc4Cgg*0B{Lgmj z^Fv(<^S`kC5Efwg%@uek@sTXEU zEA!v8fG0e-u5B}`DRN*ylC~$`^8)3*+ICv|k50(PPfp9MdsbonPEii=-yE^Ld(%#u ze!H6>=ehZ>A^(r_tr-FxKBJ%j$SGZ1`pl=q1ISPe-|=!U;-edtqB`lt3M zb{RJneHd=EP*bml^6p$*?D&6d@4$si!RSxzH)dLs=gR(tDQ#N)WAF93`u0YD0uzc; zhe^si=Z2AH|JZNtj?a|eWEt_H!8yk0+sUGR|FQLO=~!bNQ=3}_Q_V^B ztc~1~uS;L5seF&7G;KvS9`z~sGmn3}zOHF)3Uhfo>&molpK285@=>1VbYx;x3Um2V zCrZ$rnKdc+)5J-i4&>hef-_jC;a6?*s?90*(|`3B?aH2=(4We^4XC8oAMK_;(x4EmNSau0ImXcjnyw$G+t~?Pdu2@U6;%%;$EY$n(Ek%J`?gvpLLnBKq(;WVdGj z_;JVvK}Y|wZ(#B5hv!!#pACrIV`xLzr4``upUs)F*^^4qw>@{lAKX!KX z@bwjNO{`SeP|17fI^-AoLw?9N)Om=@k@A_43r+QJFI}^&qXqVV-CEKMh((@U<_{?{ z@eH!ThZ>UJD18btjVqZ+o!rVJ7udhmmLY^${nZV+n2@LCd>b1VY?y{=+nFS2L;i`YnE$kWhEANURZyf5mQL`$W|HN($TaQrI~jkTZi1B4-8`IWsWqw^i@GEiA|WmGeNr2ha)U zhy04&!uA5I_YN1fXSuMm+F;HCK8QIBu$Z#|!W_u2~kmR#A(lQADQYPDJe40eGbhX)opJTT<& z>TlhuziC@o&TqH3FX|bR)Jt>p;xOcvK~pvHyT>69n-TT5?H2ZpUG+D43;P!EuEEM& zsrB4DnZQslV3;S1f-Mcw4JpHvk5^VhsUU ztRVo4H3VQ-Lr||L6t?EzVV;loq6$~q(SE@OsQHDCjn+th#! zU~W^B!)*X_n;NhI%x!AG1~9j&0UN;FrUW*CxlIXd0CSrX*Z}4>HDCjn+th#!U~W?b zHjuxr)PN0OZc_s`fVoW#*Z}4>9l!=Kv?bU8hPDJ7z|fXp0~p#8Yyd-B@_HddTY?QJ zhqeS8z|fXp0~p#8Y#g7LMnt@TMZADTynsc#fJMBJb@2ig@d6g{0v7QC7V!cW@d6g{ z0v7QC7V!cW@d6g{0v7QC7V!cW@d6g{0v7QC7V!cW@j}+c3s}SpSi}oh#0yx&3s}Sp zSi}oh#0yx&3s}SpSi}oh#0&W6c!52LBg9V4U>nLs9Dzj~fkhmFMI4cTkGtRFPIsS# z{`Py^O>z+9E~V=VX@BVz68!G}=d)$VgRA;#7u;El{P@x(?X})>kW;$a(dj{Bkr(rK zw)r12FQfe5khv`7*JwZ|*Fm{1WUiYwHrZMk%DGJ_*8)R1*bwqy0~qvx4Pej@f51=% z{{{@QU;`L*fG%Lr4K{#v^%CV8mApo!2W@~n)JbI*Z9qAfMH|4-HY)$6eXFM?Lpiji zs=gpE+5z-PLJ!yghPH%1U?>9{iXJ<(0Sr1+anY#b1q|=KKpoW#@=y*wg0H~PKA;~M z+70XiLtVi(FtjoF2@Gumwt=C|pkBbx#t=tfZWGG!of#+x8$upz0D~T|0Sx-#4;aee z-+)0DYyg7}&;<;-!3MC1qplp|sFTMy0)y`={b&Qqc^TROhBi?7i8i1d+6>~T=uzS* z%2n-vHiRBkyP*vzhcd9C=uzSb3_8FDFtp|Gc>QO^OMPb4zjD6Qubd_IubiLxD`$KD zD`%3czr#}4dFkqJ$Nb&zy!^^{Wd46!Kx^1G_drAr$wBVTFNS_f6&ok1lJcw8Mm* zx3z106@R)-rrJ`8HBr9$GCOL2ttxV-W~S6MTjA$ZiqreSO56JH)T7%zHbI%M6TfID zjZ$J%yMz->m{<(UuO_vi-6|{Xzw&6EAKpjJPgLGb%|F?J<{invI9jH+p+o(TBM&u@ zXm;Lh4uHVEheo7@I61~Ak~WfyHgIkbVwPqYE$TsL`KBM#>y z(3YzD5>-2Z9!cl{8^F+(@COWKU;`Lrxu3|O18hJ!=vK#372n_Ej`w*Oi~rlkosYvF z9Q!cVMoiy@?A~Xp_Nkw8k6OOyt+s;s3M}_=Xhz$WnU8F|YbfP^$h?g5e?#W7lwX7Q zK(2#wUC3NFHQBlX?~~jn^$rcd`)AO$UG#+Yb7W_`%~Zcv0}A(t>1-wSVEvHSg{6aE218T=bC$bt=E&;d4pLAN?yz|bE=?0})} za4j&j3FridwgP*=P(QE-4DAZ`fVnIMd%)06U=JAD_4l~@e?RV^Z6S8*n5trpan$tz zjH9k^U>t!(9Dzj~fkhmFMI3=4j=#s?zdi!QH076|Kgz_1Pp zYlXnDJ_&1iz_6wWYm30JW(jL~z+zn#7}hL*uWu{sZK-PiAJ(@= zUf4-iHujY_&50v1$99v5R=)DRMhRrn-JRqFFLw`$BMpXcB|~>jmuHqwbk`^lJE{AWRv-EWc$Y*#D3E#IUy#Fta8mF$8WjG-7KSt zjq`re{i2(Ey-^Gqb6X~Ta^2*^35&^xS&R&<>MonUT|#a(pu|1IT~2KiM_LzTl4%AW za@}!DiObmxvSyu!+-qt)u{oAb^87vJbdLlw{dyYd+1N`qDM%o5P18uPZ(i~@$7N(j z++I?8nzx+TY8iR?b`R0K_LgrLEh7$odq{6*A9=*O1QH#&n`okZ|Zm63DdU>E!kWPq}pSWhA$LI_b6AOCEk{ z8JUuiM*0VN%YK~_$+%HzhfIhrXefcL-AYjLXPaqP}*PU$)eyf3V!8axUo_mMu-^yt;cXd5~}u z*||;*xxVBTa`nd#$-@kN0x|<5ACT@V^$A@2w$B4{c!NIi;XHWs1CqBxpN!yqclrbJ zI#H1c?)QLQOH-~jk9oj8M=Lt%vxlsGykhH6gBM=q=3ku5oKJy)ydvb+J= zk{9PrO>QgvjAY-e(bo_UahJnzN>nsRd!^3A5N>4%0J74D+P zPUo&eUVPe^-7dctdEBT{tmw5>$VWexV^OV_BiHbCgQAI+L!EVU-S;#lJKUJ-!E6n}8Y%&!Y{9oZc1sUok z%6Bw7Ooe>!zxGn0XJ+6=D)d`SNTkB9Z;M4#__M`kHWhweIXaUH|2HiRq@rF~*%PR! zFO-XR0C~|qphvVD=ojq?c11gbKcfA?PZ1aJUmY*ty2<|)J75tzU=cfHUF?8G?0`k= zfJN+pMeKk@?0`k=L^-sHkcYMc7O?{su>%&d0~WDE*2NB3#12@*4p_tvSi}xk#12@* z4p_tvSi}xk#12@*4p_ualtb)AMz*fQiPLtoMJ7754`ZQoGu)k~3I zU3y2QvT?|JLq1^t1X~BneWc&6#(Xco-!b~T{IClPkwMR^;3#C!f24OLGT1#jb^$W@ zQ|rKdWbm_vm%`wGvnC2d9Yy)NWv9Q(H|=xmyPi&A2fynd?I3@*o3$x}3V#m0-b00- zuA0>E{)aEz`Mq92Uw3@3FO-XR0C~|qphvVD=ojq?c11gbKcfA?PZ1aJ|989s<^R-p zLF~l1gO~z~u?8&08n75^z+$Wci?IeQ#u~5~YrtZx0gJIF%ApSndFb1~Vypp+u?8&0 z8n75^z+$Wci?IeQ#u~5~YrtZx0gKoHi?IeQ#u~5~YrtZx0gJH)EXJBBhp{H)VXOg* zu?8&08n75^z+$Wci?IeQ#u_lx>-RJ6KkFIyd#wFujkPVh{QpG3MXB^dCI9bR`LL9$ z%l}Ip+bgwfq~!ng2W*r|Jy!DnLwysaiZ)9AZ&GcMO@utO6|jgMu!tS7h#jzq9k7TUu!tS7h#jzq z9k7TUu!tS7h#jzq9k7TUu!tS7h#jzqohXOc33-Seu!tS7h#jzq9k7TUu!tS7h#fH0 z%UPHI1Gm%V|Lzf|rJlO{|E}vXDOH#Me;9L6+O5m~?d)Y~t}g!{8=E1OwN&!|33v8L zOLh7GJNr~=sxJR;I&~+GJIMcQJlP?&x~Am+P+p~zlK+GJMqU07dK!f&`9J74?4#uW zVAp7zlK+E0Lv{H-_!+3n|H1zWy8IvNCCZ%!-1siPch%kRdR7JHeAhqq;M4DRYr4Ps z?oT!2H{bnCI`Hnh|AR(<_+GDZUp{=VFO-XR0C~|qphvVD=ojq?c11gbKcfA?PZ1aJ z|989s<^R-pLF~l1gO~z~u?8&08n75^z+$Wci?IeQ#u~5~YrtZx0gJIF%3-Vtc^GTJ zVypp+u?8&08n75^z+$Wci?IeQ#u~5~YrtZx0gKoHi?IeQ#u~5~YrtZx0gJH)EXJBB zhp{H)VXOg*u?8&08n75^z+$Wci?IeQ#u_lx>-RJ6KkFIyd#wFujWr*u9>m;uoIHDG zXX4S>6Zvg^XL7^K5BXV_u4JdFKl0;{?xcv{Kx8@Cjf9sNid?CQ7YQyt0@;0vAKBP? z6tY=!e{y=+Xyk=$29YtP#~{z1IGlXdm4|K`LyX!e^2PQ{ASFsDdTxykB7c-r^fySK zPA=)}`ZfzDYs?gXuIvsWcf1upN1hHPL%Jyb&zu%U##k%$I=wfHjDOGx?JnizPp zCvthq3T=_?_Joilmk4qy*Wa$X1F}KJbmC(F2lAP5L8Q{lrpTrDP9X2&njkMp8AE)k zD7<3QaB@snp44^_$$Fv4TmRutXmv$T`>B2;x|*WDfVbPLi;CTGA#TLpPVr}AXm|4H zisEONu3bsL`-=ZH3ObYD@fs)pr^X9ncdXi69BbovOo6NOm>Tdt3EYmyx-0Jkz`c1N zsLcB$uq*Ey2Y8-ac;5rA!TTQcN#Jt4Pi96bTrgz} zIdw*npY1n+Ouf|{WkL!jlbf4cBCoABon%y2?5;RDix|{wgXN!whmh4t?UC=tgpvlM zJ0frP3?uJ{cSAn9BaGyZcSqj7GK?%9=!1N(QW$Az-3R%VLnt{nrayA8{9y8-!(ik? z>t>Q`bA};DotR2qS&l@0JTZ{4d!vvwSpmfH)@bC&Goy%){ut!tM}`vPZc6#3>;YuZ z5#`#hU;2<)fqYEzcA#Ot#B}Ts$b+Qrgtzye+YiOtMzmymQlNvg4)FA6|yXko&qmv+ivSv1;vy*Ft$ut3k*h|J7Zo zJLqxVHtDLto=cJ==*pFGL)yPmf# zyAYv&$8D$YcC$8<@BXwn|HpSfBg2|}_rL9(hTrRT{d0rw^@VcL4j?bu2lR+`1O1{s z!LDd$@JF;i_$lH7{{J2ebLD^6Son9}$9|8sx$=L~SX0Lfcz@m;dMgh-hpAf!+ii4?gMat0EYVm+$Vv>{R9~9Cvcw><#3-A@^GI720d_} z1P1+Z9|H!vaGwMQf8ag|41U7>5E%T2`y{ZqPXfdJQ^>=8Rp^2HtQMj@}hk}k7zg0FWM9AigpHnMEirEA}-*+I$mjMMX`># z7t+ZS9qY}yPaf=5%KP?cuSqK14`se}X|K7W<4UhDN=KdqV)>Y570J-AV~}Tlu^{~u zh9RGBT$1#CI1pK$sz>S>^+#^%@>IG!Vn1@sohULtb31ZX>m*{~8;@MaFO6(>pNd>r zlTEyPv_^L$9K6-f1S(&&b@SO%xOf> zn%l$J$TnS(cWeq{Z~kya{SAH%DOyOI3scZ3l49F*ACm+hlM>; z=8tXb`7$?C4VLRw^epBYf zXXbTgpUl0md|}ltEb@yok4{?Jl?B8q^Xu9-y0bp%%6z}&Z8tWegEAj?iu7V{Yb*2g z3rGCeq>jq`z1vuSX0lY7?>`(chw4LFn6s_*u-gS3l&89wBV?$6m;mGeTKK7jNW4u3_wV?8eFeuGm4_ z!rTYO#clhp$ip{=vAG7W$UEzWv7?ookki_Rvh_)=kdvMTvx+Gi;jN;ZbY(bL}~Mby%(`*tCcl@MWtg{RE!78RDQs@pR#WA{&EaE z*h^U(nUNFCY|bfbGH>k`u~WqxpnT7WNM_r$269HTc}%)k3HeR?2o`bP26^MfVD@B; z74rI$LG0L{%GyHu*U_x}Eghd4$jZoy%+q7Otb&^@%C~RTgAEO-jQn@2*FtXP+loEVtBPDX(3$z}v_l>p z-IX;wW{q5PtQWg8NSR;fT<~WO@yfg#@~&+GO8LBT6WFGYihOyS8B9}2nRiE8hp|yv zivANV=dgx*YNO6~r{}XpM;ary%Zg$eszKiIb`k5)y*+YT{}@(9>V~}UZ4BGk%m;b& zt{B$il`^M0z9gFY)EbH9bvG$)zDv$L{PNW&XQ2>^}49 zro^%3z^m*+Po*w4t+QDxA7!rU?P{i!!GkY;4J5bk}x$(q4N>H#dL&sJ*tR zj#pky|J@(>xchhYhky52-d!sJ`(eiWc(zZ+Rpv*q%LdBac`q-&tK$m1yh7C-r1G;_ z^24b~WLo3Br1+I&8fdaX&CILCQY^m}a**f7gOO>6YwT%#Yvg)69<%EcA|<%Cykh}d z9Nk+Bd^Y6`v&%k6fh*mA$=caBVZb*_K4eX|%|O02>pVMkFA3TGXeP^Qu@6~Zv7GsS zxP+X4D1doP%0ZSi_H0(IeB{16Hqu20-yk~{_pYfbmsIjZrH82W6O~<}@`tGWBr5-j zs$N7@U!rOUqG}(aYB!>4XV$oJ47Pb_5k{i8hDeC#*>iaCY>PNLY5=%j^0fw-bhCtJdE$7 zJa-!T#rEMOA^kRT^zKTeW|=3*o6Ocq{pUYJzQ5kKrmCE(1N(a zj^Vt)`J85_X)AfYP9|sFR#wcefWWnOoI7)dYtL=l%I?}0kX8KJp&Pfd+Pr)tzczXE zR%XPxo3lR|xx+`E;BbMJi0Vhu0vgL9V=po~Z>|L8iIbkPV;B1qy=KMb==GOaO}BXx z$m~A*jJfxcDaZ`1_k_*18%W}x9%idcEkbk@8 zBy$=xi1^(b!?u;X%8J~dFTu5sX1`>PbM{lX_Q8#(%)u~-!L>f8PqBqhGVt1oF7a&i zmIV@A`|a*4)?{TCg=^O~ea>2roxhnINm=2vbtRdz{_S~6a{eP1HWy7K_9-8P^a3)=7suLXIP zU81TlDPH#xUOTZ{bynA~0Ivmkm0hB$FHyBKxjFDPUJLRnyF^uAqH1TNimBQzQPr2I z+L@^0OH_SEU0R?|9Le{szd9(BLGRt<5f>Meew`Va+Rj~`Fd~+8eXJ!{weIq|M{%U_#!T{} zkB7X^F`g`0m_eS_@RSn=^F8Am)5)zeUUHDL<9B3oB;QR=U%Hq)3}s|xJ$Jcd{u0uyDJ88JxXX2=I8yaPCizs- zL%z@Ndr?<1Na8jRxpzQ3k^*dhWl z+lDDJYWZ(m2Fjhdj9R|1a9ogdcTfnn_(*5rXt|NQ%iy8YGt zMBVq)eOTRp)YlgFn~OTuKQs9A^Y1e1e)2PeJoF#+??=F*kNwOb4}DMFm(+a>a%s30 za%sr7fknOz4EZ+XNanhlk}-dmY=>mcR4TzPYqWgaOJ-&NBSroRi_Ti(+}_3Hsz*io%YIzDN)B z6`f&Q-bhQUDja3|O44txaKx0Sl7UX=HLW4B*XcsLx{&eHi*}PNa!rNj^UfNz13|eqL7B z&zI)p(!1eG-~N_m$lPlweK>WBK5Ms0;WsH?=ml;^*_ri z&WcPnarDVero-$$QT;!--IvKUf1Ms%d&1bU;8`*)8g9rkdmB3jJWQsx-X=`to77C_ z&nTZ(rO3al5yj8DsC|64ct{PD%?xgR4>9o^;1y#XH`*+~$T9LrRT`de!m733Lx4XvSkIm$ZXqDkzV%9$pJ$9R36lzFr;_@3?Y4$@ zX`d`($Fh4W(}hbuQB8ocV}@R3>a|agMHNxXGiMqywSKkTZ&mbA&!~$ZXl#ta#{&vz zm0JoIi+@Vfizv3*y?LazE2;cZvsy-7FQT$5seB_UpNXn2YMqj*zS5Epif?m6a-~xT z6h0C2LMk;x;WmzMr4xn<*RAwPQnevbwJlM#$q&A%%9#^0a%_8^pSNyUoYi|}l|I|k)-rVE;tV0X=p9p8`gqvJc3_#sBBx)d6hx5rH!15bESh-n5haV*uM zBeLUS6UU0TB;+<-OdP9yYJjYk&(AhNyKrqN*VC+pFUnlw?5F30Jbs(8W0eFyn(1W1 zvTB+*7HspQee#O3iXjTu^3Y?k=_V*MxB4ggZLNvpjV^6y^9!$$XD@F{?WVp%9%0{} zIzIeBP3oICwzyW8hG)IU@~lH0=*pL$u)N8dhIAMEg5?{Wy3lhozF_&y9nI;-GI|X3 zxA5;t4^8@t<+fWKY4}BbEQfX|d0Z*4XV-zIlq5)`=Bvo7_Ra_)hEF@JdBvmZbGKI$L zSM;cTQ}ZwR`Cs=CN!8EEuZ&04SRksgKvZLasKx?O^(#r$--xOo5>@{s&^L5_KvMM+ zWL;m9RDA&Db$t)Zb$tfQb$wNW{sTHYZzx9KT3vrb8C~B-8D0ND8C_pR8QoYw8C`!v z8C^fea$Wz#a^1MV@+JeT(pQJ|)z7;h+Gpm1y#($Xul#=ay@06ufa=*H{oVFd$3p$Q z{<}Gk+6NU=m7i*sRCbxlE>p$&m+nPs{c5{^H}_Nfpni6%+W&`p_zIgMXS!y(eiEA%36a_3QtX~q*1@StA4*XV$%ny(zyiruhMDc zUGuL}>h1*jRk<{xwp)9>A`@wr#?(F}Hc{l)TBb4eS%q3B0}^vERBm4W0sHXGfIO@g zA@{m?pAF={OSX%cBVX8XpV?R1L0a>32scbgV)5RK@hrsSr71gFZy>Tm^jVhtxheAJ z(>H$jE%opI4jZ$nD0vq?M~qY@pd*K!MuH9%^whTJG5+>ifvNYdL>&udJn0` zZT*#5_?lk5Ica26Z6DccN+LV@I*p7d?=8qglO&ArkPCd`*};=qviFF)ytCL+mRysO(p}u;X>qY^OoB}6eRY#d7%ySo0sF|t zM|@4#b}@V0S;>dT)Q@4ebn_h{aYfmj%~=F^?8vAee(zTQ4&En# zVE-)Ixw7{8V}J5!%v{+tshw8cZ`J)-{TugZo%|8~cADWjJzhI2{qQcjx}U52|LDM? zj%B!S4~-wu2K|aUnr)pa_nPpW=2tB0IGc0uinp|2kAdSb&SyNo($Ovkj*q!~#jkol z)KOh`^<1)*ZjGX7<5zUt9cBLbpv?#B#qGixOS6C?te1(xr8NdjJttMaKd*kTUR_^x zTdCVb{r67+DqKJBbfqI{Ux~35PwT21 zzoX_CC6|U6I5y<{e@0V1QX|K}aXshO`k$ott&2L&;hbVtAgviz)Ug<6!`P?NLf*Gw zybpi%P*UFqHunC8adA%0r|KA~W2g3Ctw%jh)ni0GpH<&0)MH$IPf*`y)O|qRH(u!c zd>ffBsoSAt=OT`9F77#guTcB*wT)6fa`I!kxT?a#lB-zkAP7 z_n*Ri9;LI}r)}j_PsxcgMc^zM&p> ze|L;rC^&(AZ15$mbW6vbKIoBZ-;QAUbYBBvtK$rIUK+7_7nbL79;)MHe(hr2wIxP= zqDysLdCPrzZd(@08*%QCuJDS+l&;Xpq;X!Y<2s#^X@xjN|H6P|8m!YF#APB6Qq&X8 z*)mh%kDKpPbDjJ>&Vf4lv5P-Z^%-B{>@RVy7xYPSt{1R4*9%yj>jf;%^#T^>dI5`b zy@18JUclm9FHtVeI{SSln{xJ@IM)l>N1W>g4Ci{O&tw*7HH&kYK}MXzjI29{8Caad z3@pxJ1{UWq1B-K*fyFt@z~UTcQ7+D=26=I2wK#_vWW+hlz~UTcU~vvJ^8Y7iXshq@ z|H|`D{p|R=_u;~xcZJ=n_Z&V!%H#&imv?`p={imv@PHO}?^4Sfp4x@i?!5l-hx?5B zTD45OKNa~tTz_HrD78%XBZ~SbarwgTZ)%yPFBN&KsoFyCjcS?FI{&{-(H44NRm*hI z`Tu9Fb%oxO)iMWk?U}2$uF(6rT4tY4o^byQdlsl=V&`RH`&8lbg*`{qGRI~q^1-}4 z3ws8sWz_wlu;-;ShGVb4&tjEk=Q?V{)p&rS8UYMG8Y`EiDYKXcVG zAL|{(_G!iC3wvIxW%TMR^3`7I7y7JM%c$#KSe{T=e=e*a7S?|Xi+f@5Dr}speJ(5( zg|(r&?xyYb^Y4l!$WgBzu}UisN;QW@%Ld*#%;?==sp+7(@(Y^t!*?QH-G4=`x%|!7 z_gT>)&dA+nKVhSNs0PZ(oIEz@K?nBn>=N1S{UuhzC7ksu5iN(j`IBvbm&`u-M#|

0wp4G~oCOJQ2=TC*nFV>7s^E&i|ov;pj!je~*vCU6AG%Kc*JC&O!eVqLO%O_6KBRlM_BfqRoNTa7G zkl!XwASGLBk-f((A&))RBOjW-nOs>Oh1@-DANhEF2y&;mGi1*E2FMk1|03UJKEnFm z3V1|(uX!VX_?$;l8x_U&`8@R*iOu(updAL~=aD80deV)9Bjw_nJm$5c0|Oqt{4#5m zsBl>PWnvVn$Q*8-M@~0?NnzbG-2WbPYU_j?^DLKjt|x1td}+>OcGY~pRGD*Zhli|# z#eQ7p4C8B<>h(Gv8 z9+|wmIqF~e)SS5LSo5_Aak9OT3I3dYUYa}^QeO)^GN3Hk>@^yBSG*|+suPP$yI7F> zTel-8PqQYgwjV|gD`Q8tZ@G#*v7i#MshooxZCaf?p7Rnp-@6uB98iF4a-j}cHug30 z!|wHo=@^AOmkuTy4C-Kc+~KKYyOF}j*VH0AJgZ~*&3!e9elc_8(FN7XjLz@S|AP_L zNTp9Q^2Z%jN$uRcbf}A!V->PGMB(>kgUArOI1Q9PGM+$A+9>>>sU4}i|1IhqTYsZ; zW}m`w)~BT^2Io=!%E)cfm3^;~XHMNLwfbs|?fE)rqcmfu1#-z&$ zsENF)Y@)QTVtwS>3u2`i-I^fVmxz*zv{2%5u1kb;E$|O4pRguK8Z<>IKM_4rDp=YS z%cF}7k_>7!LSB;DOUfEw8+mGQPwC^b%E*?3U8S16tdYNNZ!76tY>f4)li5zwVn#D8 zuQAZk!VL80#Jysr?%)uO2pEQ=^(v{<>na z#;4y?EVsO`)yVW7^0TZ{ny`wOkw4YAr7?VR1lh0HQ;l}XSq;RoAaSb}qOGa@C^xOlqHl zb(CH8*^w$Ike`;&XO1ySJ5=bb$0|+F#rC;iP{6-K)J+TRvnc;L-LW|mdCl&}bkwuW z$leF;(=FD@y`|pnzo_j1rH?&~yGXOsa#5z@$dlBtxf1IZLk`iWA<8|(yxBfF#zE;1 zuTswjaB<#Rhr1XK%LduqpDq?tPe>nGtgR>V4V#HqX(nw|`%@>(d$Jv1R+R zY+ajlZ_|h6+P%lRT&mxlMd~;;U1IaQC_X0??aazi!mC06xkIRM{nkxXv%zKqMbhbEEB6_vhZ`#6fs)G-?#NHX4BLj6Zw<4Mu6 zN_&o)^e5RjM&Z<$J!Hqy7}S%za1+_{a0K$<;v0#5uoLpS4jahYIBR5+W9v!!<+G@> zTjF{$Af*>_+P?MV70tpre)zVYv~C)b0d>rb+d#@r>z)bxZR|$!$Y4FPOY|mkIR1kc z%7-0cq^gdyik&9*toSAwDP9q0CTfx-1YlVPU^nNOT7Eiwa zLr(H5IgD+M{gMH{w%W)?zmx-4d*7bE=JF#;JRt|aX*IyRO5_oB-hSolQ+C=QTy}_Y z-#gpmDa)-BE{Fcf;@!hOCJWcXZ!lc%G26iA_g9_nL+hvIj`gaejw^P zrnezdwtc;cbeTxm(wup6kD`l6{avToto3u`r^f~o`#)~7rmrI86Fuxn)EKmX)4K)n?yem8bIGh2L6|?lZ5myau!7mMMRb zk_|4f`^DzS-;BJ-UHLdWYcyA0)^sA-WqN=etTj*0)XpU_ThiEue)Hu;jhB*91)JHk z{R`y$R>`FK@>Tzby|;|cDp~rzfk6j%cXzj3-MBjg4DRkO!QDM11h*u(1W&GR+}%A1 z1Hs(~fBIiLHE(m?Cu=d!xz9QGhcjzs&2JU8tE#Kz+ETl>`c`;`UYK^XSi5(Y>iJ@( zzTChq7m!X3_4Uzp(uIor$IGjm-RJ4X*RP1W z6Vs`dV|?_!9-(4S&bq4EL@!-D-6e7H&+2OH7cZUn=p|9IO(nIU;5?me>J@QqdL=cl z-aK9O?PXzKOa42r89&^A?atuitCMcNt76oCI?M zxh6~nuAZQW+(@ZvUwfdo1&-JIYVC9{D)vO}s5M?s>{!xmkNF?w!jQ~rX&E2=YF3E4 z-KV=s@okPCI_Q*&Hou0t_Sj2%Jh-HKhfGv4zRc2}j_g;Vzs^^&Q_j?rSL{&DuKKA8 zp40VeX{Q2J6v^9=hcA{lk~LB z&DFA{*Hncr6ZNIuWmW2QVQQ!U1U=<+)BdiquLmQ$cVXWTxtV#dE1Frmbnp8=Tqj0$Etx9X9*@Pw*Yg*T)ywpi z+~6~BAN??{&ZU0sUU$m5Chd{ul{@M=hwa$xYsRuU935Ogu1xM63%1uuccEgg_;q}B zqH|l-y%}qQ!7r=K`QdlX{=It_p&u|cK-tIII`(hnhyrIkV6*J2#mYX`*0FzgN~AhR z`l(`$QTDO6j{TbzRM?4s^(jwfA8YH_zjtpU^e>cetL$TK9s9R3TSQLs^c$`0V{IM# zcQ*5`x0J&T=65`9fj7hzs!UW-+CC@VmuP~TQ7W9c$o6q6*_O-1V&qs={rLgnE4|04 zG#Pdh_qab=*)iC@{uSp8_87=|<_yKqb?Ho1CVwb#g`zW5ie!(7LywrX>-9_GJqf3( zoxZjjTKb-H`=Yf%(AKG@BoM=QgeXE>N zkB>Q=^I@>E<+dIB{IE~Nyy&*=zz@gTI`+Bck_i2Eaf6h7tgU08mllhNr&GB=Wglzn z*yprIjzq+NXNj_pwRP8aB7@-6HH`Z5{jke^>O6)OTASpBDD9wvK)6&?JVVpXRs{ z_OZ5(ecdrB-KrqO)6BHdKGxQ;uUUf3wGZ?MuJRWFGg}a^IqENF9z0kI^66&ZjLr9l z>;?~A5+Ex6R*UR=4_Ym3U$)JE=6cHRqbja$)L(^?tQN<=S0KJpH$WV(lZyEMIe%ft zZ~Ohb*MR49y{CRrVxFixe+jiQsO|C}u7B<8V!sIenNKGO`&e7YzNWUXTWxvr=2s}^ zdw-uVY@5|CJL9&#{~%%O*mmse;^h(g`R>mU_OZ5(eNBDTYcAz*t7)TstgT~TkK1e? z`_EkO-!S(IFs}0awn}uGnwH|}U1XI|n>>i4yjv;WjcrfdzQsz>!e<=u7|#_y^wBRJ zs+NGAnN3%UWC)7{gGEMyujJA(H>r(cywvK(zXIO;( z(TsJKeXOlx-!JOBV{;XGM>Q=3l}pmjKSWh2#XV{YPx z9h)eRR#}MKs%EP1gfzstsw^PM9U{J#U{Uap+}nv;&zc>)x3M4b+wW6? z*JhbcJbU!`;1B-IiRTp=7rg3AZsG}E6N2rS?b!Y|-1m;Q+R0CwZM)oduI$+C`>{2{ zo&0;=Hno>8Yf~E=oqz5g+0@BH8}CQ%z^Us}sH$6;2Od~IkC%w1&J;OGeB)zOHL<9( z&POrNIP7@r{MgSy>^Z(`)l;%Fylq%;{yx8wuNf=f23J|)#Pi3@U)-zCW+eIU%JJQc zvg9OwUOtuk_Z?2VPOi)5{u1D{ci!qE?wu)|JWOw0!CmT&!$XSKaocg)@%*Qr4Ykkb zoJYlZc-l4P`gzL3o@yI^c)n>r_uLbqAG`W$mwl|QV?Q%3z&6)TblJz+I`%WW9dnKZ zqkm`2d*WdqYwOt0`_2YB>kOV7dV0O4W6MQfm1$NB^oFYS5}PV(e?x0arm!@0(fUp1LWj2O;3cB5Q954-Jl%>T~kwihGj z-N39{gYCB4G1$+PqZD)I>FYQ$$UfHAv7bku?(XFCrmKR7eXOlxKg)hlAQjEchL6g- z>|<>m`#E?({t~1gcli+4{=&tHV=n9NO7NRAXVawW;5zf5Aj#X_Z0_>9o`-nb!3M6$ zrLz$i&Rff6`?c-=Pd&T0=VqyCZ#^(a7BpGs%5f_e#W17kYFF|J$%!jxS>^Jp=B!uZ z*izT_n>k3{^UDI)t59dXx;$*2Yi1nhe6Mzt8LrqboPN1eWrEAji5>sHv*sa5H>WR> zr7+*Q9(RGx%|=E^_(NTaU9VC;LVsy!GGQNU>)5p}ttZc;9Nx>GPT0rVI(8k%$0?5f zsgM1HeXOlx*N`l^e`FW>sN~1N!amm4vFlHA);>!5^|NOd_OZ5(UAwY-?jFiXt)*Fn zeXOlx*S$>2o0rxT)XcQ&o}GC0?i}LGt7OC<9%K`h=KV=FhYiXqZ2PvIzgv4VI+x>j z>aL-}j={EL*Y*V5bk?_)(MAjVSX;-g3(6nj=%Zf9KGxQ;Yl`f#RN-|#YP%epNQ_iH zh+D2sB0Nud5r1r!T*N51iMZh8R3c^Z!^CORq!V{@UL(H#IipxU?>_OQRN2Is4=;$z zHP2=C7IS`&c3;XP>^SXs{!?{U_H)L_p2OPDAMJblk=_5#cjL7?&H?jW^^ZGZ`R{Ms z^(Ol261(n-WhvjdCvWuC*PGrIt#-U}$K36!uNnSNJ=?O|@~?iL`!mmd>^wyFEGDw& zgFbs-x!0R#g?U@wRnH&2b}!p+o=@Gs^TU1ef5r2H|Ec@=_Ol-QIgb5|#(w@{KU=Y% zn+*T0Jk7gtsi&$U^-6hQ?cKL=yn0^8;riFSm3>d%zAtUxhqv#~+xO4yd*k+fZ~LCM zeSg)ymuuhi{JZyT|L*-&`yRM`f7`xyZQqx+?^Q;2KhwV7Xx~e;@6r9M?+4oVZ0-A6 z_B}ECp3;BnzLtH@(7qpN-|MrlPybWb%l174`++1Eby zb&Y+^VqcHg*Ae#l|Ib{5MD{!0ByUNoCyc4atCV>hu64j$MRpGGph?+a)FL)WH&xlk z+UExLv9?Y7*vRH13RlDifQ@zE&KemXIg`4UILw?+U+uoNu z&xtLfy4j<%xUq74dE&iE(TI~H^?EKjMW$zpLclQys z+v`z&qj=G@n|>6_%hZ5v7TMSI(7toLf7q|m-k;On)AD%Htpe{-rB1d)*!vXOdmP#O zpV)h1*zZK!dx_Y4ex|9sSJb`qo4#T8hyQo(6>sm0W$%||eUIb6-!XB%&+@mwV`Ak~ zSa}xj#`w@)a3k*=5UDeCBHpm=x|ryhinwCd$6|TVbQkuEd$Hq<$o{QGF!)B+_u_W$ zgKqGNX0OD75k(Yu^~igoRNj%qeI8yA!9`XOFUcA#%KGdfj{A6#@Na*GIKJ#B>OOox zTyJ`IadP=<;`PzixB|p`V(dd|$=#N|vg|0!zOwu(D;{OVsjT>w)h=bVS6O*bR(_O~ zH}&6qQosKz@@el$E6U&4F0d!+l->R!X{8+kd!mj`9U!KT+99wf>Nit2W$m-7=JxZZ z{cKZ=+plts>Oh<^?=|JqDJ5~z5f9aE_cRywydD1Sm0H`oc`!I;m$&M}@%?VF&*~TI zk*lx*U%7o(J#I6cIBSpdDq*7K#GfwiR`bhf;)mxJs>FX>BCasGkIG)98eoNdt$uHR~xy#ZQmK|Z)7nWaP#UrdZg%!WB+9j;^3M&u7%8#(}X6Ia4 zIagNBRs117l>c>?52$@re5hY8c^^BMezUG0^s$;IQ;|-tqmR`3@RX#psmvqQV#{<+tZoquotOvTsg5~X1Vd*=(RV6V`h#xh+^_LUr3pFU zhR(ImFIAK72i(xf-TS4A)~|?y&a~e5)U=XC6m;5TyQjvSEv%rkaA~+2k!B?6%(!tu ziK8P(XNdO&mAvQ((wUOxf=Zuj1?jX%8LaBPSx!0~ZUm`j-pffRyl0TwHf0a#91B~d zs?^*=Iy*NkQUz~m(z#TBk(%7-3hAWH-%r&|c!hKhhV)fU=3XY9+4cIWxYr+$PPZ}H zRq`1RNT*QE?CN2R2c#4DIGegK`!(q-{;=BJwESz*nYVAX`{}kmBKUEjupDj?1#+vf>d|Ji>}cSnU#4yM)y)VdY0y`4Lurgq3GuHk*?MD@1}LEvex-X*BtBEANClx zV*aUpv+X^)yHuJW7FzF($Y$_G7lXFV=+D3kHX; zeJHvO-R%ZH$Qmv_@5-gX-=AF*!R7i8*KToCG-~Zj?Du-Jc#&f}@y<40VrRe!;-eos zh^xhK62BRiP9$t{kND)-rLIQ%9}@RYGS1JEyDfcX*-@5#W%*TBJj#kwS@A2YUCL^& zvhtv;{3t7L%F3tx+x_3)V&`1qpZYDf=7`XjqMQ9VCh1n&e%$A_UFH~~#8dO`WWZfv z?}hu|aCA}9?8h7E{!!nyV;>tbA&O{d_DH#u{;sHDxI+(Ly~S|y2*w`81tNSsytqr) z_RGhQE@EbzpzlNr7kS(NBKDj8Z+BD;7x#8Y6T{7QYy0WpqV~AsF7UFt4@J0d2yx{+ z55x_xSH#&K-4ktc9&zu3*@<5C|dBD}q?7OmH;sY_Q_g)ubE13C#=-%rxan7gr zMDaRLh*x=s3p;+hU3PoxE{R6h(eGP^i^BoYL=zKF$DZNh$>wOHo8do({}}Vnw9(Fa zWcvWy@h3NX(R6Y9YS*m$v=2$&P+yIGNS>O#n!z=8{UJWd`@~D4+!fDvT_7%1F#Lyp zNi*l0tMgv-j+_6TAKD&SeggMDb`4hM{k!<#;=}Vx#Mj&16WAjKez8aN&%}WDjyY!R zsRG8HDz=?Z$G^F%X!9-gmb3BkPNw+5gAh zN65BgkL}3Du)Ppg0%Knw>=y*aenGppIdke((QtL5v@_SL#<=@~ z{U_6%`PFOPogeJ~jGaqm_qw{8IeyFQzADt+S-Z|=fAB-h@2Wd%SKWo-Dt$L+O*{Sa zp2`?{k>+Nc!S~eFQ4ffZRS8#hV}2%H{rS!hd9(9x=grPfWWMa!79Ty}YHQZpV$&X| zo7tRo`1Oki>iJk_-Tt-VLv?+pvz{lL6Ry6@cGhk8vwN!2d}lpBRN#Rs-u4%9)~x^S zYlW+MaifdO=67Lytnk0RhrI18GMo0;SaQT!bFg1M_JHCsV2=%Z{Mh}Qqv3H^MYH~2 z%koe?X?NW9yWtu|AFA>Fj=Q=V4y^d_hdlgD-t700Bio|^aQZ|@6j@2PI@ z9c}Ns9@%|$e2)qD+s*fwgso%Wlecy3d-9Qem&(?+&qM6rouB#EKxDrD`>ksF*7iU3 zt!k_9{`NO4>~Cb)>&buj3>>ZhU-k@)?AsZUeJd@p?`zol_V;rOblo622M*UG6L<;x z*<57bBHXuio2c#4R8OnsE9M;ACMJ|=s_zu?6;q8I&n1uigWP_WXMbzYwo}17jo6!D zG2LH?FH#Zv?zs}YtwLhrF2fqQ`-R0IuHe1Uz3=i<7xX&?A90&MVk2{#edY zS#l3cpL|5vAs=A0$?{7+AV&_YIE59z$a?d`D#uP5$hp1HcR_A^3M)SXJ|IUf@dt(s zJ{&s>=@>9BQl*3#jkTY)(!5?Zma<9{x#)ua0WuZjmDvv9aY&mFk5H z`dgMAbDKY6Bcr@RZgkE0UL%ql8_L-7fZW(tg=6Q-3^qO?4`w-hfT0f`VAz2VFzn+G z3>p3n3|$-ph7I@t!!~??aX-tFdszD9Bf<{(0HaNoU-AJta$v*7&feaG2`O@>o2<>t^WP*yo;C@);jRNV%|l| z8;iyP#$>(p&OH5o*d5$1_BZPD?N3U%^JaKV94+r8_nj1Hi4Pyz=r(`EM&>sEMr?H5 z<``mQ!)eE3LfI_(6Um`jK)T(T|+}AAaLXzxNZawVt|N&iUeo*}Joi;a8=+ zMDJ&7#H*v8`b{w}F(Rkg1JrQ(2J^+c5^L!k_*h{tal5uZag9OqBh|lY?g!$WxkQYs zqE{n9T&K+`ad34X;<7pSh&63z6Q5YHL6myv*jyUZSA0+E_}V>tp7>tb;n_3iMH<7t z2eZgd^r!2^q;I{6tGCml@;4W8j%g>wjfi+U=DhNQ&Gb>%id*r9>UOP-FUxP`eg2f6 zkAKXMG&cL#`k$P9=n3+dpxkbIc#l_E@3_U`C7;40~R&b=WDZuBQ!UNeMr{$KmoZm*pmJ15OAj}eX1dg>FycZqcO$B9!T zJoTDicZwYNejOBNHq`FZL*A5M#0*NTgq^E`Fsg{MV{*QLbaHlF%X z_$e{q(HPfEqyJ<;s8|&Lk!zCS`dO}vrC*bZv4$U3za;978|3Qj?Wq%P2^H^q^>j5@ z;i+p~3l+!L4|2J)jMB4Ys3=iji0iePNBORVh|Xo#le|>fTVmpx8^n7TU8nI0{S1w+ z{4iGSx%M;T{D(PPBM!~q4J9v&GlS|8_pfwBBn+BNoV8cr4}ERVS$n>K?bvc{8Kpf# zu83Pkj&G44ihE6jMR3uxH$$jyc6dyP2MP&)`$y_1VHS28Pr>Ewa}bfc4Fu9@SU{*7DZqBt~aF!k@@?ja&|-@&fsrXP=83;Cf>YrYuldTivyu7(J?Ww7gv z;Uq@q-B0A-?k{`H+ikShji1SnJ*Og@JH3YtaiQ-P+zJy>Q}rY685SnW-|0@ABrr_G zD&C1WL&GppwNqQ-#AnRd-qVu!YK~BGXJB*U-@Al})f<`-pIdTEOd2%AH6?JQUSaIJ z_VsdA^cksdoecY_^~YY*nh$U9!aCD8QJ8RVZ|}O%WVl{s*0*Rc+q>#T8Lq#j3lq6F zH6xuu#&3a&&55Jb4iO7Kw;+!CE<}VLY)!m(M(E#OGk+$A{V~O8epq{Lxjn8fjqc+bu+mc(tP&FGdSZ`N`&fI8vezP8KeDlH&js5~q-&kEe*WFH z)Lw^ezxMo%Y|h#`ww)i=d~5x;_3hsR`}e}0U-r5Y*&MWw-D93}EjMF3;cq{V^TS4t zIrS-4m^fhg&A3rIFjJ`5XZTo}QM!HU5K-$*DCsQS7a}%QcuQQP$*rGSKY!+T+5UaE z=bb&@_n#c>x*Re}M=u{HM5)0pxpkCIqe4Z~i-TN&eMaeGZGZgz`q|&C|J&~Za)q2A zS6SXVZC@1grkGmMY5U;?*Tu~6&7>1^ONf}A$%nXcXsB4S;0?vuKH7ER8~Y8#S$K?D zpZ#A`oL6#P6S13yl8)$gL#(?L;^;iRF0u{{A)N|d*Tt;&$4KY+?wjK2$YZ4QvG`4q zCjT+g8Gq}BDBNu`>6}U)A`V8~Ogj1J-V#lNH<3>6Qny5=-QJ{Avtp?D*2j z&U0jA*j_8b7PfUYKRrqxG`~|*dbM_)2py&ITUj+#OV{W}4%_+pnK5I>^E31Mf9kh> z;i`VFxi>~>T{BF04(RK8*L{@k*eq0R5AEUd*f2`F#)pbn8~VB`R~w~&EfXp-*XZF| zZ1j7_4-?O#b#pB=d^J2&R7lm`mDlJmXdNmNKkMR}Z{(v-hl(+Obau@%TycA-SlGX- zE0NI&DHbYLKkew6YUG~7&9U!0yB@C}rB_Ec$HwUB8gJwoTZM{Ct=qc>8vbPVv0u8f zgUe-fVl)d8xq9?;y)ki4%MdCaZ|~u{W7sD_s2JI*t*e>Qe;gPhf};0uoig&aUqeLh z7TsN241akXBK%snaaA-rNjipz;(5Bb)^r=Ck8}_-@n*J`t|n%DdYgIl^l@`no~NVq2s6Lz zv1;qvej_{9jx(~kVBd4F?*l}3-EH5yu-U#gx38(~Ywbj7o4YEs?55ur2@wsenf1rK zdl;qLE%7d?Swjq8H*KFCX4V$N>rLCUt~ckLh6kDT3VA49tsBkdf8^#h9l32kvSX3M zwAH)O8VEal?B9*YwsR&~OP8;S^NNYT^&ib$IZd2?CVo2}+kRyFwoN;>;2G=nn5s2o z)07_+^V+26RENH+_3!K3kUaa|0G%dYYvLG%19YEKEs0N^@Yg3qbK)Yi{Pmg~O&$3t ze_bwmW8&yb{B^qUhQvwl`|ItOej|?6G(aZ`uSb0Tb%5@iu`Y45&8zjnxwVOxPFbV3 zRI5dNcGz0|XZ4!I!$z&sZI?JPbDW5oi{LGMNIdD|ZIpO50Ye>pVYp^o&M@o`jieT(T?P7AHG-)W_>W*0keHD`vr46 zV2%^~vfVyiQPh?;V=T!P!MeehsuaVbV7I;=r5dr{S*4q{cX;|WtrKUiPV(EQ_vkgn zoIVX&vsbtFar&C=z&^{ttPf^8V73otzu>TJ`*qyCQz%Ym#EHI$o?-&U;9KI9Zc|_) z@$i=?^^G!66BYN+0hg-%ytY0i}xX_1#x>N^;Z@)O8(?)gp;+OrpeSgO$$BDME9L)M) zwgYDSVD<~#I?7QR>xW_>W*0keHDuXQ#fP9ATNGegen4CKs^+hd6t z@)jE>>gYXU&=_Ebd}@X9dUC3?BriK{oUYqFHSxqxWA(0yDTxQo8>`B>ef zZc<|3-^S`HX%iC%3>mBce3F1T?&-1m_w(_HJJcShm)-c4IKlgII&O+M#1#*W*WG5v zB9FvkPtIKdo0nA-*B_JTPN;NYu1`q@~gEzFRM z)HC&vTu~_IltpLh=J~!0^hJ|KvvtO^--s&=o}=RmN1l52T>Z49qu+VHmtI;ZDji#9 z!aTiVbTs0Azj^D6>7x^0{nJ|?`0Vsom;OFFPQ2J8AF#(q?_3Fi30+%7P;7yS6Rm+tc+9nA%18p9@Uo_CzFk$InwE}JwN#UE{`;bJL> z8^-d{*-E4$ZqVIZ5BoI@ahrAXbP7LbOd{v7179o$vp$&ZfZ0Bn{erUwOwt8UWhVQ~ zkOzL9t=ms^sVQ{(y{CpF|ZuW`e3#LX8U0F3+8yh94DCL z2Xni?+($N}zc?OnwOe!as*sEn=Zuqc^}ydV{QqKRIqa}Ln8zgSFhkC34&=;`^PGa5 zndLlw>@mRW1N51p&wUCxGvq_NbkG@&J*WA|40+M0{q)moZ%KaaQ*Z72>>csz@Sb{5 z)Az)`pYE;?rFJ-Ae^;HYkfT%eY-c@dAuQq zeof*^8~duGD;g5}rRlE<&uU3rBJLn{Gi@j01zm=!z?i*=PsARrdLg2=MBvH1RohXSD)N|P9XoxkYh}Secwg$7YBXxqF)qo>?uAv z<%_+db>PrA7Zux`z!~uKA7!***=*4f*0hPql0?-dDx6Nw|ttRJq}KEgX?~use8^C zL;UFVES+dlf8rQtXY2gMTN59dF-OnZT!lDIp1Hd4l03xMm(A5e$0fe~WUdZ9csUq0 z^ThMg39if`zV+Sce@{bP?dV)RKK3q8L|T;khwU9xK+@rY3~^p0)Qh}X55 zsjttkOMH6KEd91>d}59Pak3oD`e3#LX8U0F3+8yh94DCL2S1Ex7ns`%<~0g!VTPQ4 zJ0NFVaJgofwn&i)JWN>A7KPPUUFQ@CY*JEOj6UAJg{O=P_Zd}zhI^JF4IgMJmK7@r4 zSI_C`ifg_L3;PGBPIEoabd&h$+C{D#n;gHtjN9Pa_~;tR->=lJ^;aC`7!VK3!K@Ev zJ7BgCX1`#L2h4GTIesv=3(V~WH!9_ljT_ab@xV-DU}{zQ+nCbSU!^BhlPyNLi2ZU@ zm(>?b;=bLg%N1wJ5^t$fUABx~fjIA_YO+;+XPmVAR#o0D?Tn>v7pusRX{wRViRP8% zlLOU>i><6E{j%32F1xL~j8nQ6af~HpWx00_@9ib!^Mw3#Lsdt>x0=2nC*kv zFPP&2bDUs~AI$9nb9=#@2QcRc+_Xg*`K((y$|p1OnW=0sxnxEnivO&uge+7rF>#+% zrDWTTNr>MaD=pJDNlM(Uf=doKpNzQDFd_dKlY-c{yOe!fr6R5$zl==QJPk41M+__n zvp$&ZfZ0Bn{en3jFvkh@>vTXY_@y_siy7^biyw>P-aVbz9z75x^7kgrx+h!|ozjPR zV1YkG)8&1M1I@k_bG!E=eo^ka*m2L{`6(`owQ>8CeD||+!t<6RZ}!J2(Wt4zN8=tB zUK1QUk0%@!b2>TpIR?bZaxm+I*$$ZPgV`^b;{kJ=V2&Tm?E?Eov=_{43v$8?Irob_ z1|W}Y9p*Iw`pnShoZAc?UQ5AZP%bg7fiqvOX7v`Q@7y&RP+?B$M2*xh{=|SkaQn_pXM-#ahOegTk5-cT4a^#O~6b*zO~? ziI`aqW_>W*0keHD`vr46V4iD;GiO*?88R~m`OW{Xf>ezP5!>qq>*H9KgIOQUcEE|> z4VU>UEG9e5khhpVUiw$_r`(1Q8z);Aad=I?u`>HhKay`7JVpkMb9nQd(elfSRV42@ zW0bs6%HbBJM#_TiSCYI`{txu+^q zKb%c5oBRAS--|iK=03kvFXj@P`~0%sT`yvDpI=rwG>_Qa=a+udy@}0zez~Ni53#w= zFJGH$4BI|pU^$re!E6W2_QC8I%<+IZPVlN{yQtr7hTju;_DEml^w;nsT5jCp^kYt` zW%RjD{}!05WbEcnzn?komiuEmW8=%iVEKHu!&Tk|$?WeP-uZU73@_@8E4B~6EC;hb znC*bsKA8Q2IUX>_2}Zw|d*IYx%xD+-&OG<|E6?V+&tLgB&wYrIPxIV|82L2MeTb1y z^W29R`83ach>=h8+=rO$BLbEJrfL+MeDUBzOinQe1Ebz@%FJp zFAbJ&#yaP~4Sd~l_eAF!XXg+lE8lR=hv$~oGVTE9nrP@{Eyq`@NNr?0@Wpa4>x0=2 znC*kvFPLKk&nU82&Kg>sVxH7vpL`o}K0oF8ep%;mJ(Bm@d{Ca;)_~Z@@30I=_&c#Z z@7U%)&Ue;_ob7$PxdCc#=GUwcK#P%3q`|!nbFzbWa4w&tO*)N#m0dt&S{;fxzf9*9| zzK`ZZF%+#kM(&?Di+E$oF|yK^$;3(Kj*`pfjwNn)eW;B7atN_Km)R!lvmDI&V73Eh z`(XA9=6JyTdx|)jS&sGGX6V@G36cGlu?~*q-)!g;2)@l$2luDtV%GL=_Vx!)a&bb5qW zlLbD+AWna;x*QZGI`M-UHRPpxQHi79s3GI`{7$}V9jzhvMgL4(_4gVwaI5niA=lLE zGM~?DlJDqJO@2D%Je%Nn5F5+EtPf^8V73otzhI6B%yEJ_elWKS%B{=zce*T z11U~s$m?Z{C;c+@B6>;D zW4^Q^c|-pwvf3d>zM$e)@$Q2!GWPSjc7mAKvY*J5Ug-ozXO;$b{zeD0c@o2&o%5$d&n?#@5H;7#wH;RVsO-;Aanc=-b z1g*P6%=)m&axm+I*$%krw1;BkFF7f1%&_Sd5U6##NO4} zoV-oFAfkQDPW*Pw6|w(y4&oE>Z;C!MauOGxA12xzayVUx0=2*zQMW$a(JDj2L(hLe301ud$FbL(c0Pvc#@l1W4fh~nq2b%gl$#sKl2liPGW_>W*0keHD`voHpRvj8K z~i|roK*cJ)xgy!eADa3)$#sbwCt_wfnDxPI2h8@t>=(@OfH_Vu z#}DRqfw{e4&I6e91LnMec@056nIY%+A!ml1=P%^Ukn^~LoEdU^JTpTlvi{|{hGR{A zpyYZ&Qy(a~&d}5cO0GY&#~U9D`z!~uKA7!***>^&j9AjQ$p(5(&5Rf}#keo#Y8&WWrvP!^%YTXs_X`mReEcGI9L-PM zY;+VEZD4ldhFzk`R@qV!56l%^F3TH}c+id*()Bfr{BjJ4hvi__2eTb8+Xu5>FvkPt zIKdo0nA-*B_JX^%O)MrypP`T|X2=V7%p+bG4kCGv;#ow+JG+P{&q^b1KG{K>YfVz& zYO#&@+@|;)LjuXuBgSlN` zZZDYg0OtIFeOH%~cT#^=HY2xQ@2bcl+ni^zt|OJ@!OYIH+Ek4y$$i=0QM*R3uOOeU zG57wBe(6i)QDV{wyYs=*$4iZ0GP)9~@f0TGd%(^nokdwq| z&3guYSDqzy->Df}}8)%|PBIrDB3vwg(Caxm+I*$$ZPgV`^b;{kJ= zU>@`TIR1HVLe30*9(#~8L(csUIWy$E=0MI2IkyXPX2?0W;CSt8$mS`+Dd%SvRg*q- z9}(Mq&HAvzaxm+I*$#L?hp!^|<81n!WrnYWP2$ML`6iHjf6-X7+{f|6X=28ZRo*&0 zIy9P`ncmSUaw>{^)8FAu?yn-rJBJHY_#~PwnMlVDsq{f)?=p#a$JMvudfmyyzs7$f z64Y^i>$AOjCH6F*O7ff2UWvhdrxAY+dnKk#noeBg$!k&5X9jWlfVV>W%p@Ka{e!4G zdKR(oyN@Dv9j9H~7PO1yVAcn-9WdJmvtKaB1Liov96y-b1?KjGIS*jY518`?=6r%V z&tT3!c>e6oa?AOXbY91de(W7}y}Xj}0<}Ha`}OkT`t!t}u5OSkvp76?#YVY)@HvvJ z+M8s)&1Z@0U)v-zo;gE&MQ)a9Zk#4QJZ!VfbNv)C+eZv62eUqy?SR=nnEiq|9x%rV z-g11C98hj0wTl_;n$T~n{H@joilIleZSqvz^~ByCwn>jN>xdKhY?Bu-%dUEU%Wlytb}jm@%x|4Nc` z42YBEVAcnZiLe7^`(XAs4^r9!sqMk7JniA!j>ajQIjncTgVU@7pW~r`$%|to9Ze zciR@?D#Zik-ENzR?Y`q>`B>OtIhggqYzNHt!F9fE(M9+8k{xEqYc$%W(;Rfx>bbFZ>m2i(wOY>K zt#^!a*6My=ckAAxoVB`dsUY2Z`W&*es!EU^v}`VMK+YhYHqeW>?ycSWThKg5-f6e~ zy49Qb+VNewt+x+x`d@eHB+cg&FVDAAyT3WywB!!`c9;|A-9p=Si?a^@mT8;b`QG6# z@wV!hFCFIi(H542Ss%=Hz-%APe!(0MnBxQoM8pr~c9A@yy_NnbiYL?~qYWgUlpukw zSGGTKtD^Dsy5IT|zg`G3JL6VFH#U*C`2m6&5doGb^k zKA7!***=*4f;k>A#|h^6!Q3t|w-?N70&>C(Ige+^nIY$~0XZ||ye2@-47uG#X6W$T zw;B4}N8qcA66nH%I#S=|DxXkKJK3Jt9y6>DJ1hsYKA7!*(**R@QF@o5{4>MX;ZRSV zH*PMHSFAWpcV3s9cwFn@I`PQ7#P9Ns(7QbI6X#hqLSLU%(2?&Sq04VAOgv%I2;J#I zQR2?;hU?RR6ek{?(Cnpjp(OFsn?rS)`K5_(wDZ(^v$}}uZyK!6_Y}l0j}O#SdPrj5 z1O0WT)K1JCCt_wfnDxPI2h8@t>=(@OfH_Vu#}9rN(JnBzm*f$70CRr8oHy{-ui5nN zUU{g$n34ZqTjkN|Z&svsy~vSE7rNr`fj_hBi+vp)bT_LG-%^2eD!bP%6Flx$X2_w^A9j*L|l?6Hm>kpJXUN`YW<#)+>GT5qJHVML%oej0bKD+RJh< z>x0=2nC*kvFPP&2bDUs~AI$9nb9=#@2QcRc%y|QIKEa%4Fy|i}l%l)VJyTN~nIVrl zvZemLV+xXYAKzL>y_uZ2!os#XiNC|4f$jC9d&SNNB`O8&U!+Wl%y|*ch$v{ zr6OjVu+MTZ>x0=2nC*kvFPP&2bIcfH%#ibZft(p~jsbFJ$nCMp47uIc%s7_U5St_X zN?uQlUt-9OzU1}C%wNg#+RR_c^WDr}$?JfbzmnGnGk+zo8)p7WUQf*YmAuZF`73$- zG4ogQx@6|B{A<0+J3{h0X6CQt_07y*$?G1+iI`aqW__?(56KRg?UOvhFPP&2bDUs~ zAI$9nb9=#@2QcRc%y|QwzLPvYnISi0K=ODtV@&ecGhn%vO!62uV@&ec zHe*ckm}i@?&vG#9gV_$4?St7bnBxJPu_Un`+KjPe#-7Cb2{vnsA#|h^6!Q3t|w-?NL0CRr8 zoHsD%6U=!AbN<0R#?UX!kaHXDzJr{{4CKs^^O^uTGvtwt2cD16XNG>kI#E=)LXz%z zGDB`^=H0O#rX=~As2SZ4)@35jbvUPcM}gc9rzzpiT%s`XkOkGcJFNKKJcsz zal=C++(liLh;t5~>7G)(8gbOp%iJ?R*B~yne2e?0tVKMw*a3H&SPs`6e9;}y)X{17 z^sak#R&YlIHp=Q;(#%E{o$qY%B+}KA7!***=*4f;k>A#|h^6 z!Q3t|w-?NL0N*R+c8B-7AZ*4MUUx0AdcFOa0Jm|)Q`;__B#yl`hFa184DpjQU)*CS zI`0(UOYzLT|Lb{@e_wgaz5nb5;$Oo~y0d<8m~Fxr%fYNqF+|t_vwbl81#>)LQxl?4 zr(`o?HgzcqbxmMXYoxda$kZ;uS#L8i_}alMeK^HE$! zWa@kr*B6;OAH{V?rp`xkJrdi8UzUSeAIx^ZY#+>i!5j~m;{;>f*f4b$^$RoF61Tda zJ5yt4oV*X5>&~0q89$*##=66bIpb=NPbatZcE;PBkXr6p&75&qG-@gLg(Ziaakwg% z`^B(*#IH+dbcZB!-dkt;h=Jwc*b(|*wgYDSVD<~mu^O_Gi zGvvGuK+X&~ueXphvmE(kIp@|MKc?nNagCO#xl&xaWsh6dhaHxKSs%=H!1nrZ-e;S; zP$Flo82)O#dqLoN>R&tOtdC<^4rYBY+X372_h_;8>fGh`WHa^n4JvT_Gve%GgDRXp zocLp_b*g#z4dSYw0@S_qPCV~(tW>UFPmp|2?8Rzb_yOXrC+Dg4e<W*0keHD`vr46V2%^a@q@WtU~Vs%^8n`jfH`kq&L^1j4CefU zxnIC9xx0=2nC*kvFPP&2bDUsPpRe&= zo6Ts8d3Qkb`;X>*G|lg+nfK8&zrSYQN7MXXn|U8i^ZRb*eKgJQ!I}5bG`}A={D{{4 z-W=P9UzUSeAIx^ZY#+>i!5j~m;{>Pdms+16w1wKmjCNfg98*6jv5xxd=-8OLM&XM=*|f@6K@z6SC2m8aI>=Ub=l@yNd6&T zLVfhO!<$Mb)};~#lKgS~r224fhXZ>i*D966UxugDb8b2M92>PULJnqqFxvsMeK7k4 zb39;<6U_00xm{pxFPQTH=KO%O-d6hRN#~s-X5_OoiC=cU$hrNeB8;)#%hSs%=Hz-%APe!;xP+We3G{%%uD z-DH~|#rFJL3|+R!GGaUbEQcM|2lHAAo6L~gIbnv}o?qtu7tQa>nD<{azei)v;bnZW9!2X%fYM=(@OfH_XE**CzA{b6k8_F_L7u-VJS&3n9T->}D4f4r**RUM%us)dWfZ0Bn z{en3jFvkhz_`zLf`s=#`&brYqX2_4HS+Bo8tVsEP{&2k>e#^NB<>$3Qe>+!#=XrsPXHy&}8R~vNB1ks6mwB4Zh z-~E$fxVCP+-qYa;@q!EMbhoIti7$k%)xPnr68E{XMt47Yj`;n))p}U#)5KK*0`%-> zr-(Uzw1wqh)(5j4Fxv;SUogi5<~YF|KbYGE=JtX)4`9v@nDYkae1bX8VE@P0%=h5B z(KuvAA0@oGQ?+c`mBwM^l)=hxSvO+O&057;(Vh79^!+Md;~vD7<{wsG+Tr`#kE@;M z9lmn%v`X&fu*ZS(%JqxGaYkKMyRtiW*cakqIhggqYzNHt!R!~z@qjr_Fvkz(HrkB# zazEM(oyg`X#|-_P`{pb8(K%->x4E0@5~Bg-q{o3ws^N~B#Hhvi__2eTb8+XtK40LgVb%#fSs`;zN?Og)U`IvGv>E)jQp$4Cufl4`X5sdBe^cf)Wb-w7c%uQlIw^} zJ&fe~B2y0|x$cPLM_X79W_>W*0keHD`vseNB#H;jagsbDelWKS%AO*Fy{@- z`2=&G!KT(ia(xRkx0=2nC*kvFPP&2bDUs~AI$9n zb9=$2Rz#w%$!6rl)U-&hgEI9!3_MlH~d* zQ;#IMZi?;0FU!HK4`w@Hwhv~%V2%gOaf0o3nHm_$H8Z9LMsh8UoqyIx+gT1~eK6Yr z^H{POetEt?&J4NTUS{a<+GR8Jc`bsR8FF4*AZLc$-*>rwG-tkmoEh@0jo0c+Rko14 zx?H2Xb`K~cTi4_}t+z){PIp9C(~Rnsgc<`@tU%fYM~NR7WY8hwdLTBUiYNsQvtf3w*THDc!eT6pA_Z$CJ8H|JcMwXP?wEPa51!)JFX|(&q7>w@iBcnTTWuOj~G}EW_>W*0keHD`vr46B#(#_ zoMU95Zud&j{-Vr~Pdv3&`_CFr?YcL0tv>a*GjaWaYxT$Tm5EzUU#p|)ti-*}8o5_A z;vlh3x9NMtdFSiAx#tme262Na>-9%njQB+B4Z79zy|kBUjJg|jyBCj3A%|=0ZPFLE zPoQ{iw%n|HzRwl}dB5IUbmejdh&eXI$#O93gV_$4?St7bnBxIAj))V?@q@WtU~Vs% z^8n`jfYD#q{@6x&V20e=dm9mJtm3hu@T5F=P_ScSKjZTTD4u6!8+P*4qjehtb zGjX;0tM&U@MTqY%_1CHW%Mr7E#Kv+k>x0=2nC*kvFPP&2bDUtFQ;46L<-86<4u+i9 zYVf;?hjorgg=r1%m-wI_rd-53Qtj8-W>q6j-f6FXzNs;Bf#`d58Qq0=&1a>%)E!1_ zj{&xicvuc*eK6Yrvwbl81#>)LjuXuD+Gezc*J{X_Avb%}Oa8tFGvsCue97PAFyFb5 z{QV2_oeRm|#W3Hwko>(2^PLOH-_bDNxsd#Q4fCA~$=}^D-?@(5jt8-^9L)M)wgYDSVD<~> zO-F2=%gE@%(h!^HHL`V(Q#)#&i!5j~m z;{==eB4e*{o<}pIU1;OmgO6zqG3QaT?)>}2=DbC|nBeUFV$Nq|*LBXGFy=f*zD$3U zbjwUZHdzj4eK6Yrvwbl81-~w^SI$|OpT-q4@_+qqkPMw%jK;vKkHNBPL5E{US2Fcb zr^b8QXC-^~DndHNu4{QBsZ;NL%x8~$*}ovk*$#ZM9L)M)wgYDSVD<~YL|VouRAy8P(0Z$1FPjAezxJDY|uC> zafwxjWwno)i0wIL=bYv6#rj~j17`bR_6z2@gV^3oF}_Bfq2H!za}UbmC7t>Td(5yt zj%7KR^}%chY|j^FmSbJA88M)CVoUcm)Lv%jpw6V|7w0`t)RJYp=`d=^zJxoBnzZ4m zo%cpjOIB;J!>A>T{>5R`l9lsw-ZN#J@XK;A>x0=2nC*kvFPP&2;~wMCqt_{ZX2k#G z&Q5ocMz^WGJ{$eqJ6sOmjp5~v@iL6$*$0kw_Z;AG-#e1n*MAs&{4Ss%=Hz-%APe!(0MnBxR<{9x4lWUClJ z?PW%L(f0B?o%erHm$k!dJ;jE)tXH1S`@g8m8q(K!{}**x)yA$N9n@tl+2-^S>aw=S zbr^M7D`z?V$o3Hf%fYM(n&gMZ~XqtW!&dE+mdxalP8wb^-CpOB>XyM!v+WQfyY)TF)om_aRUX9PdNCv)v9= z_LSo*b(tU);&Ry4Q>)Qe=aJ6mbNf}2l@4#Kc0^@a;&AS5C)CAb4v&9vM%~Hk9LsSc zW|o6lAIx^ZY#+>i!5j~m;{(O_v5ic%3UssLd%!@f0 z=j+btZjxM`_R)(AICE!Y9UuL)fHSA2`+Ms@k~{P6%+-1N@GXZcJn_<}M>uoy`2D%M z=39q9oS&ml3TG~J%!r@mVAcn-9WdJmvtKaB1Liov96y-b1?KjGIS*jY518`?=6r&A zjbg@}wVCHK)--z^gAT7VkaOSJ3>{t*z^DnFn9o@&P!o7NnZx!v%=)myaxm+I*$$Y0 zBVhliR|Zur?>dVA^T_e>~Dp9T$7_fI%n zKF4@9x{1T1zfV{1#yZC)%IU2J*K=(4Z?jn4JHD3eBp#wJ_4tK9as6rQ zRFa@o#P8~CP=h+HAl@)!gQ_2A8L>T2xh-fH%fYMTMlL96aZVN?Lz7@u}I5RABm%#G`UNR2^fECO*{sfl3x<4Dq7k57d}MV~Ia(f1vXJ zANJk^`m3q^|IVB#nM%o=A(S$NKIc@1+bmJ0M7SxHgbW!=NfJ^tNgC0p8P#V;8A8&4 zXwo2=B2tEs=XzcHypPXwKfnK4&sxv#et!RZ{oQL>_iJ72>e|sZ}>d&PrZLHmOH(h%b#vgCX~4+@*Y=i z9acXa`MQ?dhAZ1d)>!x>IV^oxc3|0uH7+cFVEGBlf7qV=f<5oKZ(`*3>>BJn)aCqL zpS_1V^Y?!C9_q~B0or@0Gk+gw@1f58-JrdPI`j90_8#iY-yhn0sI%-dmgKPXVcCIY zAJ(|A{DI{seB8niTK{;w*HKIzPkDA~cGwpP687?*!_>zr`Pu*01z&$F|7kB`4y`eEC5LzUMnxx8iNcf#o% z;@^$jS>f$)P|xx%pIc^j=v1Mc^Yg3T3@04Ct8?d>Z-m>YNB+*vsGYWaH<#BQJS%+A zeotrlhR>42(uZXSmVH>`!tw`}pRoLg6&I{{VdVi{oPkXmxqq>{vUt&%rNZs!<|1#UJqmcIK;W?^>2oXCm-ZodOgY}K1dErAC?_h z_F;_+%OBY6u&$-CoRM2Btb=)Ov-K$FY(2_3TaR+i)}x%W^(g0TJ<2&-k8+lM@*_Dc zeOPv2*@rbQEPr762{(DZUwZXvuln^XCa$kG^-C{n{i$Csi<|XJhySv~dCYfx)9-41 z>|F1;zUioAK5%Z^rEj`m=XuUMKG8QlZdLrdzIWc}o6ddrEtg+*aKCh)&t^HxK0Zhe zOCOdUSoUF!3(Fr^e!}GKjI~$z8oQXdwlsb%ow9a>?;RXkc4qp;gqNIuUvA%)Y(C5R z>iM(M8(*B`-1L*z(=Pvr`wmUMdn3K{w~wOEPH&~pPG01ER#jUwyzxWlUyge_z4F+3 z&d=3)C*8KjZ0GGOyqkX6zv%qvl6TYDua9$n>aIEIFFOu#e(bwB>BLW-aIReYz4W{D zJ2=Z{;*uPeJ}f)1?86!tmOrrkgylbcbru(_cwyzib+Y`x${VbF!c%q`oDOQYr(Z8( z@_*63&!y`d#{2T-D#Oz&#>M;c$Qr}aqh5{ocQ9-j~PrACgwwbzi?0>i;n~ z9o4jwbA>L0(|tQubUyj`!Reiy_jZ1) zi!3{gB{?j8Sax99hczx-ng=m{mijD4zqH51=$Fn3V)Rv0xcVi7(nH7X=sD@QW?(v_ zZW-s}>}-@;lfU!1rSy8&zs0`fu=HWsfn^^qoe#y5bG?@`zLn0~4-I@X-TKc1-M3yt zUr `7TiIhQ_mB!{IB%MRRs)9~=?>J>>TGcNm~Yx@4;@|(vD4%MF8=zQ51gTt5+ z-#h<$=8#b3+jY*nyf-9l-To`*b~g_Vr(6~H7aG(W7M`5=nag+EX?UpAWtFq+GnVAA z^kLb7WgphKu>67LC!F0k(^4iz%Q?^6DV#m`I%m(l&e?OXbN1ZpoIUqCXV1OP*>kV6 z>@%+9u=HWsfn^`oxUl?zmY=ZgaRl~#N}0H9pCYhN1lvAN z(Eg6?;{@&d*gj6sevs|s1nm>qK2Fg7k?de!a#;GX?7*@QYh2j&ECTyzrR;t-o*uOC zX8U46`(?H-7POCM`(i=+Yql>IwC`s7VnO?HwrAvaurE0*eOPv2*@rbQ%)Fs<={^^ULL%-^@v+jB2x*}uqVd=XMnH^a6VT}vRAJC67LCoKPA#wyth za3)?`pD(cA2iv||LHlvG?^e)0o$b37w0~#&ZUyb@*}hvr`+c_WR?t46?YkAUKPdb7 zAUQ03Sax99hczxNe_;6u+q!zf{#_{(i>+5D+V8XdvPAo6wqKTLf6eyG679R$ep#aZ zINL8vv`=UIWr_ChY`-kgzMk!uCED+^{jx;+fVN+jXn)Z5%M$Gy+J0H0{Y2X@OSI1@ zKk;93So*N+z_Jf(Tv-0V@)MT-u;PLhFRVPk$`7o(!M3)aYX44*-1do5?f2OpS*pD= z+apW0r)GO(srK4zk1W+5ob8dN+MBaIvQ&F^wnvs~FVFVKQtk2C9$BirKieZqwI^tM zWU2NFZI3L~9-{4$rP^DxJ+f4Lj`A7*C5NRC%ML92u*QYu4=g`n`41~DSn#<*Ms9n8K2IVSBQKr*Z7;8&y+7N_D`-!! z^xBs`b|iJB?`HdDiT2}czbw%{o$Z$;y|Vo~+b>JBuV?#Z ziT3+!zbw%{pzW6>+8?z2vPAoawqKTLKhgHf674hEep#aZN82w;v@dDv=h2;+{KVkU~D=t{^!pZ}z{J_c^tbD@CGpzi>4Qee)KG^PKf8Q6= z4}C6QoGgF1hQG)C+J9-Xrr%-CcO0}lnfK>@&d01-o}6E1Z|8K`@}%0zot;q6FqwiVqoTKkt@tmXY zU-6uy?_%+sqwi($oTKk(@tmXYYso(2N)AgOmK|93VT}vRA6S0E+wDF$S=eTj=U$zWNWMEQa@h_~CdtuJ|MMgJCbc?Dbp1EF zJ)QiV{a&nQ*MZ6QJ;%CS_8CiZSo*N+z_Jf(Tv-0V@)Itt7xx-{^NM?ozJ*oVC({4d zo|Hav*?~*@xySAMCr`Z*za_Qd_!s-f?;4w>P&<`+XaAWE1<6!_tRk2bO(U z?zrP#>3Ne5a393To8G=hI-$u_zn2|(@$TucI`25&*t2{(_r@j8Z$H$U=#*!SCJ}f)1?86$@^)r89 z`3c{@s%d)nt0Rl0Ozm0@Zk?XGVp0)q+^=O?W!_}x`JG#&e^!_hq*b<_=sGvP)-3HXYn=0`$6l2V`fZG}>@%+9u=HWsfn^_VoQ(_1AD3r- z!W&QSmYy?olE)<`mKMFANb5Bo={}tEU5~WWQ_-IWNAyTfxjOpU?ySetX3tG*T z+3)F6{VvabPnYWVdiHy|RKMes9qdaEOCOdUSoUF!3oD2JnorfSv}e#S9aoHw=Co2q zU)L{kF>+mZ$i>Jtw;&fI*PMo2jJ!0@WuGsmRaQUXIX`!wkgiu(zoY`4pMV)^C#HCEJFY3xZ)>zQlZFbgJ(3x&_ z)>zP4Z;FMuB!{IB%ML92u*QYu4=g`n`41~DSn`!tw`}pRk={6*wQQl!?pEmI|Dw2HTlsL1&rSnPov|oY|RWL1&-Y znPov|qS={cL1(4e8EQdisM(oiL1(MknPov|uGyJoL1(eqnPov|w8;m2lN^>lEIY95 z!x|TsKd}6Coy>n&alwigp7_hq!1-vUOit|FvA}t1u$^}nbPk%GcNTO$nw@tRbZ(lR zcNTP>nw@tRbk3UWU|(`r`mpT4vJY!qSaS&eh>KYZ6X&VSG>r@$V>ag&N~Y_ zAI;7?3pzK=&N~Y_PmR9SIcxg2*pwWWJ}f)1?8Bwkot^0xbOv0zWg~;mhAYjX^!c}v z!_tRk2bMp?D3)B;HFBMqSo4(u;o{Xtc|Y|0=;`psjz>Fx_-p?#qeJ8oNA(Ze*RSsK zhPU(!zn@;i`L_9e!=#6fasKuEzTvvxYC3=PZJ!YO9_zeuVxMrr1#$oSph0~?yS-}X z@(GJi%=N4FJlPpLovIg{v47mq#F=rw{w#IIpOs(Mb;i#lM%Hu2|F8D1?@U}zoDuo` zr=Q8?-R~Hf>%V;Zv$>t}e?FVr|7OsjeB9;-56=C0q?7#}OXg?mVBbQ?{I9!Ua2^+O z#f!f3fF0!r`^p>RDxdhHJmaVGkN>JmX}!eMSMkEi1FZbO${VbF!pbwO{KM3dcwy>D zys+vhIq^!LcwzMetUiI&Kd|}=R=>gOL%1}?EssAF)^B&T+yB1Vz%Z+A*jm zZ*cfBIl=A2TfV97jLxyWPjcqpt~LEbaN($Urp%gOl}9iI>4EnA9?)? z&eZO^GbcNH?Y5caOzj3&pP$QnT>5FQf6<=noUv2kr(c}0KmYu#{kfEJ$Jm+E%q{ry z;0-%Fz}^tSZrdD-DwkbSNZjmxzof4HXPC)b+%=NeR8 zer;y)qOUw)NBP0N^2WHzC;lkU_^JHkzv@z2FR^-+c-6zi3oAdc@&+rPu<{Hm|1fnV zUYI%(FRVIBKEdLZKJmip2UvXqtAAki6|8=P)rW9tjP&hqx5mHArJpO5?d)T54Ys)D zVQ2dPxp_UDxh|Tn@8`_*^2rm!qP|^6OIyaj0p|J|d3gNWV6MA!Z;5L%@TRZg-x#CQ z_qezR!8LgO58vlDZ+Q3je5?&qw(*?f!~6e;Yc=@x?Z&vrfzQ21mUA6qS=BJsh;P02 z+%bN)Sxle5cFKFjFMgUI-~|&m6dx%++xeqpxA4Nq8O}2rA08&Hf7yA?{-=cUJ4|wJ zzgyFA-cIA4Wruu94oe@F9a#2ZjSF+{UR-&p&l_9Xj}JADiF|RB386>p$Zu4i7!H3w z^73^P!%vOk?=e5r8?1c7$}_C| z!>S9cdcmrrpAQ}NQb$^)$Yz{(q}e8S2zOuf`^ z)JuJ+dZD8_N?-k~x+7OV!0HoN{R6A7VD%epaizNMOrGkxGyPQ8o!Los-I@JV*PV@< z>bf(3QeAfzS1Lcv|5VqV#g+dp2Xe)WzVd(_U3b{mb;r26?(j#~9e(P%!~c@&E-kt4 zJjSe!Ia_@_-mLB(FKqqb@xs<89xrVDkfZ(-C2Knyx7G5lIzanMXo%+$`7o(!OADBJj2RAth&Ie7pyu;uIo;9 zN3MQ=)hDp}2UcIf>Ni+@2$%M!;-znu2Uz)ml{Z-Vgq3Gl`G={O`cU9@K5xC6g;#?HjB!5RBkRgQaDTWs7*s{ZV9{Fy!{{`LVsCvLOZ<@o>FtjNSw zVVmDvt{ACfDS!N7TaOp{s^+(Qyztt=cYC~Wy(S$zUby1R4|u%ry;pVic;R+^9`tzO z2QKd7@xmYX?&9%EPQ215UKl&X3uB*nVa6q17=MTt#!upf@t=5M#S1GBu<`>dZ?N(S zE6=d<4^v0^sd^z-9bwg1`qUj(Kfvk}m~rVJSbYVn-(dA2ta{O_iWgQMVC4r^-eBbu zR-R$%rGBGc>O<8F9o13#>Sxs*x%vTCpTO!LSbYVn-(ZWYsO!$;MO}BMU(|JHc8a?0 z%zjbVosC=6b!Yw*b=_H9Mfqv|7j@lPTt!`X$Q3X8$^&+E-CranY za$R@mtDmu>>kj+6?ig3s9scOLv;OpWv5EgB*PX|UTzP<%A6R*Vl}}iChLwLHDGIWz9}-(4N`&7Wbju5rfCXRo@}8UGKR z5t+Cee)<;^W2|G07oJu73y&8LZPs|a@bvksJYKlmZ7V!pxMHj29xps$)>4lbp7zKR zj~5<0XR*f%U)p`K$16GUN}qUP><}-Eed2`~mv~|PAzm0ii5JFy;)NA2tUSQV4@@0p zNBKmqJj2Sr>suY=Cv}wnsv|n8uk@+A?9dOe`UF=0xPI1Gu=)*FAHt>msd(vIZLwZz0gq|rLTTg-I1#wVD$;C{(;q3u=)*VJ~{l80p7RFGs%~c znSaXc^Nh=xm$qCVnfdDDd6AjNF1~1>>oC7{{3vHDFtxp>i?c4os@#e_L z$4?yWa`b<=Zb)wD*j1T;2Eki-|GT zF~$os{}3qq-nhy(eqiMdRz6|n8Kz$9H|nK6RK3tq9i^{+R^5@S zA7J$ftp0)3SFrjGwzv{qcP3AC-I;!(>(1;Xy6((=qU+AaO?2IvKZ&k8iz|_z=6|B= z&f-dR-62=J=qnG{(RGJ?U3ZMD>kfZ(-QnlN?7GAMlIt!hx$Zp1td2QbeLdc+?jA2} z{owJ!)+Zh>Z2jZ$!q%T2FKqqh@xs=J9xu%MLP>vmywcZohaL4f_I2GcuC6=$(RFA2 z>G8UK^S|V}^LUXf53uqBD{rv!2`kUA@(-&nu<8Y?j*@GhQQeWNA7J$ftp0)3SFrjG zRv*Hp{Ykx4U*&-wR(@dR4OTv3No18K2*KXQ5~hPepcO)s~=$X39SBs@l)54 z`VG0=#}hqg+I=w5bEe%N6Fq0zeKXN>rrl2yJ!jf|HqmpY-G383XWD%{(S6zO*NL7p z?LMC9ITN|=@968kj~zW{VqedhjH~BN{LynJe(E_B|4W`Tlal95k1^IU#tYl?jK>Sx zbB@Og+w+*m3)^#%#|zu@lE(|%^O(o$`a^#8cwu|)@_1o;9`kr5*K?XZhkLxpv7_fq z?CUv`arK;uKYBjIPd#Vif5~&E$BRwn0akusd6e*nJ>E^r>=}8)%y-gd6GyuIf*syT zuc;aNw&riAU3!dg`LCbNPOE?Pg7Zh6XQyR$h`jNv+3D#=J@4`ZPnezRtX|~XHy@ts zpYzDD+|K^Rq0ZQUbF0XV`}NgBT#i3&KOO9hpXc5m8UI_I7TJEop7uHBFD6Fnh+O=B z&AA>g@<(=g-{XZ}Uh=-j3-8u@p2rJ+bHaR&7jFK_e2*7?WS<2dFWjop0*@E2+hT#o zD>?B>pLk*H5HE~<;)NNPcwzh@UKl@#7sh|$g%vNXJiy8ith~X>C#*cf)KUIWNBOCG zp`$v&sxPd%%MSejt50C{53Ig|)o-x+5LUhDNyQ5*53uqBD{rv!2`kSq^-{l4FZH47 zg^ubdef6{Ij$Hi!t50C{kN?}OuVD2XOk8WG{KI>gc$3E?lZSiuiA;WuyX);+3{PH)a$Lzg?IUg)Tf(pNvL?#R^-u=)g6|M9-HIb6&F7yXn;Bw>z)e^__Ia#Jikp9r$)yW9|LU+cuh=zWYKa=RRZJO1oY4 zkn^TmZ>2Zi{fP6jwQr`~mOk#>Ywnxr8_k}~~idfio=~5 z_vZ6naK@h_){b<>&(ZToJLCWEe~fV^u9L5gznxT!sw45jb=%JMc;N@TzVGqE_dh<* z#Tee#0@xq;^EcAHcx$iIZcqJ!Z=@T!E9pZ(tPrNYW z5-*HD#0%pm@xu5|ys+Yhl?Pb)ft5E{`Gl2cSow#kqx__f@?UjCNA;CHb(bCb0al;D z>K|Br1*_j+^&za<(W{CVRvuvG2Ugx-K|Br1*_j+;TPn?+# z?LO|DJ)h)qd;ZMz?LO{|9eX};#=bqrIy0_4-#X)uJ@-1}r#%llC#*cf%0HYvH@bc5DF0PQbW~sI+w+_2 zs~?c7Phj;AtiFQPZ?O6hF6~dnORp*qu<`>dZ?N(SQ!n*Z_FmwC#*cf%0EmU z{`7byCtm4my#hO0$G|@EqQkgaSHT~xt5|<}yy)P6$-0Wii(Gktl^8qbrcjW2^SbYMke_;I7b)=rsS0Qg&S0SHT zS0T@=GoVks^d3sRY(8;0_0qZua=p)@ulHQ+u+D%T>}y?xakZ|3KU!D8PrYB`f62N^ zC|OtW7*$8DtB?n+tB@b!MTfj;U4?vVU4=YrU4{G;FZ$Gxcwy>AyfAgtx(agQl|J#p z*dbmR`&w6FT&=6%kJeT2lX%g`|B`hTj~BV}04qPR@&+rPu<{Hm|FG%;t6s3`D7oTQ z-I1#wVD$;C{(;q3u=)*FAHt>msd(uPZ7iFKAuG-Uox$RqQ=6XkEqLAA{Ca?7cE*UB%uvgVt5- zy*21P)ZR~n)>Z7iHE3N0x!z~d*LyB@w621Et*bDu)>ZIF>nixEbrt+CSyu@q>na|j z>Zo-Udw=(Mk=uK{#|zv0zQ+sOI)KLu+xmdV3)}jG#|zu~gU1WoI)ldx+xmmYE4kJs z(ARnecC@a7eXXl7uGUrXN9!v1sdW|nFIiXdco|E1fR!Iud4rWtSb2t(e^_;aRWDd| zl$`oXU+XIB2juD#Sp5U5uVD2XtUiQG`&04Kx5@*o{J_c^tbD@CGpzi>)JuJ+dP%On zRefbgeXf2$u0Da)Kd|}=R=>f-rT4pRo=lNv^Q3b&PdaDwq;ob;I%o5wb2d*pXY-_U zHc#eqJy&P*q|38;(m9(aowIq;Ih!Y)vw6}vn731<&e{B#%ZZn!LLr*k%cI%o5zv*N|R z@&GG8u<`~gpRn=_EB~w^rYg2 zl?Pb)ft5E{`Gl2cSow#u`LodGNnh`GsylM^1FSxQ)jzQM3Rb_t#HIC2;?;U4 zdC)ox`O$hNdDD6(`P6z2_0oDK`Da}V`_zl|J(zmg`&};AIuiP<@1cVotvg{~>zRzJ z^-TQHdM18qJrn;+)-!pJbDN4$b<}z$dC+<$`5|6($eY$P$*0yc$useyL;kg%Ngat7 zIdvpnm^u=#)-&-(>zVke^-TOPSML0N25(rn_aSe+7{3EK>g6ueI}C`waT_ph zo8oPUmhrybqjUY@v}6b8O84DaY`Ltw^Y(W=S$uwK73b?-dA@i=`y-vdUpu+D{n$8H zH0cwHKd(C5<$H8~E&n|N^3@l#&h3e=)??1Kt9;^*@~nR2->MJc zf9X$;m%ddVVC4r^-eBbuR-R$%rG8UgkgHxWa`mn1D?93Q?5qD7SJwsp=z39K@o&{{ zu*H_FOGgK|dbjtIeU6NrR(>ZrX?^@Vu}4?Ene5dgakzb+;xeHPa?!jPTAj#Vds*5!(5L2 zKbFV!OvXJpjf_7pOdH}l_}RHhWc(j`KxE>2f9JoL7^$P;g%5r91CJN3uML0N2CENY`!DZL#Y?X$53uqBD{rv!2`kSq^-{l4FZH47g^ubdef6{Ij$Hi! zt50C{53Ig|)o<`&$4ySIssE<;@Td{vlgEyZJoV(U$=Dy>aCzCSMkU>PMt;8H3rV@% zBA@is@Z{K=UU!}I9vPY}nKa9}xZ{vy?B_F`Pu_oU^23gizj=R9a?#0Vznbg+ ze8UW9?96#OIAj0Tl|^U9?OQK0{!|ImU5=l>G>we^6%UR~T&I`&i;0msDqeVKc-iBH zdmTO9jKi^=c#|!VZ@O6(DF0<@Sj~DLIbhgI}?{U`K9xr@N-?u$p$%$9` z#0z7Gcwy`lFU+{a3*!&*!uUzNF#Z!StaxGN0akusNi+@2&-Q7s^W!}2Uz)ml{Z-Vgq3HQda2*2m-Nj}go(+>J=X~NlJaNle$?DpX=O1`#veoY&yZokcg=G1F z$Rn4XkX&0S^7|jvOuDvTxA`3&FWf0@ z@A1M1*ms4AS90Q&KJmiXAzm2!#0!tKafuhkAL51alXzkLCtlaj;)Rt5SowjKH`mYd z2`kUA@()u-`AHq+zv_sN>MMQfE<5xCtUiI&Kd|}=R=>gOL)S0qPsK~!l?Pb)@qW(o z1}mSi@(fci^&9n4AF5vHsE*QCKdbJ@)ekWB(siN!aXVRG!Rj}7#-Im>Ejo3D_wbL; zuAaKhF_C*!Z#M1Vji0)F@j=6;ZFw^CpD!<%)_M2H%f9<{+6y-?cb$c2>^l8|mzFu7 zcW$NWhkUuz`MMVloZftw$cqm;WcuuCOLBR&GZ*LjH@1$~J9g?1jMp{xzgQiwYsTH> z)X4bL^VN8b<7b;@k@5f0s*%6=?Y?1C%m2m1NF9-jP5)%#MQ(QL5HD=@>kuz&?B>pLk*H5HE~<;)NNPcwzh@UKl@#7sh|$ zg^xR~;PGa1&qJo~`GJ);SowsNXIS}%siXX)j`Cl1L`U_NzVd(_{=Tg#V>KJzn}&d4QE4Sb2k$Pgr?|sh9eVdZ`apFLYE#>8qcyqdv#J`k!%iUEq(d z7xfi()NioO|3%&J?0PKferNMZQTIE$evA42?wnRdUDtNK7j?h0d7!BKoy{jj%?~zj z6m`F|`J|}(9dgYx=xhGLj_!BZ&+m6OuI_jEqx&6x>VAj+CHK2x$^Fh_q>hRgwt3a# zg>Am|cww7|Jzm#ec7n$X+q~`Z!ggQqcwxIQc)YO9{~j-F_XUqva@{Y`*L?&#y5C_x zzu(!oy5HfC?sxd9`yKw5-0wVI#!?<&T~r2a=VY`*M<7W?PPrgtKVRIelF_$&YnMudcU*h(xTq)?0L1Azuz^OS=9TTJ>M4f zerM0UMZMqI^K((p!}gq9)cc)1KNt0Whg{Fq=<9hKJ9@vve*S)Eg#N&nSJ;mdN?LEljh3!4ag z$K!?VJ;>vgT<=Hd>%9p(dcVVd{(fiU>irIX^nQn*#EVV*FL}T7c#$g)u<`>dZ?L_O zp15+>c ziSmhDd4`pLn0l!XRWHfax2mt~sL$08$kivX`Uh5D!Rj}d*tDK$>n%mCXWBYUQR|tu zK2yxsGmlwb)Ox0^=M=S`Y3n>it!LVLQBmtZwk}lEdZw)x6}6s;T;dybvBO|w)HoU7q)dd zj~BM}I*%8&bw7_6w)H)a7q)djk5_W7XQHolLhNWg6Z`pkrj4uhO#IP$CVpx?6aP!r zGd*6$QXXLC2Ugx-TYt;#E6>Q4e^_;aRWDd|l$`oXU+bCb2juD#m~rVJSbYVn-(dA2 z%zx@n#Y^8R53uqBQ!n+2@`+q|hLwMqdZ`apFUi%ns;}&*&(#me)hDp}2UcIf>NlAA z ziC6l>3uA|PVeAtx%(%o0;}7w|_({Al{u3{(cwyxMR(@dR4OTv3@&hYxu<{8j&oK2;zfmvsq3VT> z>L`8nv+9mq{Q#>^VD%5IzJk?nFz-A6xb|M}VVtrMB&?PYJ=<8q$Edv6<==ksU( zyvyZ0w|^1ZJM%nW`|LZNc`x{M% z&e*?UXlrN2op5z4XZ)FVMN4P=Y&YNrXZ)XVXk_BrX-kXvZ?hPwqvC~m-X>m{_XXmG zc|Ipz*SF_(;)QvhCtjHM1>%Ky{wH3T_XXmGd0!x2$%$9`#0z7Gcwy`lFU-t%|u<`&aKd|!V`dL0<#TOZrps(znV3to(RCXL*B_Pgr?|sh9eVdZ`apFLYE#>8qbrcjW2^n0o2D zQ2)4{tgm488@&AkpC7!M{0UbWY(7kd>H$mb*DyqMP@zf%H3}CerBEO`ML30 zVEt;-W${{I9qgH6?0MF^s&3cZ^;rj7Tkkq&Wn{kwZ6g`KWmL{;*9?{pAflL+20R-d)L317^x$2G3!gji=1^Q;)Pj{B3_tv zD&mD%zan0kbuHqBSsx=_m~}AXg;^gXUdf49`os%khj?M^6EDoT#0%pO@xu5?yfFR~ zFFg0X`iBs2CigsK`ko(Hd4rWtSb2t(e^_;aRWDd|lw9$u?#QvD{9s>sV_fAEf0SqS z8~;{)2>(ledc5?l@&GG8u<`~gpRn=_Q!n)!^->?IUg)Tf(pNuYM}3Zc^*`h4y1*Y@ zFX}7osNZ0l{}bKs?0QUezq9!y(f!V@-z2}^*}jjiYrEbP-S2E3NOZrm`6SW&VDmci4 zeCzSTHV=Eeu5bG?y5HHn?eQYF`P}1$?Y`jg!Z!bVys+IDJYLClzd&F25$x!GhyDD1 zXXEOAhd;XC;iv9*_+N6r^LQCcd4QE4Sb2llN0WW!8M*Qgt1htW1*?vd>;A5~BUeAb z>Jyl8l~47R+sXP3Rv)^4Nq;I{`c`>>l^^ftEN``kUA@()ul^`Yt|x%yW1l^ylD z`T@D!$Mfq#{o{7BzJk?nusuH~dcU*h&qVKc_FS6i{m!0Oll=Y8{%%C?clLan=>5)~ zdlS9i+4FOv=V5zJPV|0f&(De8?~v=c8ht%)V@L0I*w5eZY+SwH;g8<$@Kf)1_+RpV zmz2EUd5qLi@xt~V;qk)ue&O-L_TJ&~!uCGm@xu0=;_<@v{^Ie%_8#Q%!uG!7@xt~V z^!-(f$0zq4`meuqDLzr#XGteFCe0VD%NOeuEc|KR(^({rLBm4Z0qgp3^k)qA>@i zm+ch)_HwtIDyCgl$G@vwwa0F0pH1=aCmSr=Aw93jV1LHDdF!pymyUkM`KjxFOD=k> zuk*Y6{ghM~+{?N5B^#5*-QyYy@?LkubrSS1>DD>7v*v^QoU#9M`}m&7xQCn?pMmk` zA2-DJIQ$&6PkeU8|LM0~5HvX;)P$m=%$o-;U=})ro<~b@k*a~VeAkujD6yT8JBor z{2^W#KZzH{f8vD|FRVPk$`7o(!OExWXL*LHqx?}_kgHy>>L|J5Ro!KWet^{{u=)p9 zU%~1(*U$P8R=wy|#S1GBu<`>dZ?N(SE6*_XQom6z^`Yv8j_N3V^|R`ZT>Sv6Phj;A ztiFQPZ}5r>st+ym_EhiHKawTW2Hz98_PR@^f6(t0m+xI^;Pm?sd)c|dPwz}$dCU~& z!^VF9YDyhic*#s0lr`n#NQmsX0`GXA88^maLZelh+@XZ)}He!RxZ*#D+I@D~#!bwn;U z{W`>p-0T#H7dHC^;)QM80`bD;Pl0%0i#H)&*!)k37q++(;)N~V{O_WX6R-4%7sd|p z!q_KXm~n|0#vkH^@soIA{3l-c`xiPMLcE#W^N{I#eqiMdRz6|n8K#c%M|DB2dcmrr zRDxdhHJgeXMx9UUqU;5MIrEir7SowjKH(2?Em1mfGsozu=l6Pzc^yEMIVLJjBhZ*QFT>v*{HfEE{}V-_9Y z-20^q(=*mr%;hU~D4*;9cx72<>>N;iD`)HvYqF_`pNxCV!CyP$&rxMpIpgQGjg~m$ z|CSRMITP20k3P(q7^$P;g{$`L?D4{tn|Jki;Rm-o;_pt%B!VmA#)8mDAZ1kkZ z3m3}t_ITmFcIe~r!hM_d@pvUCUg;Arj2+^Iu}{1(;}S27Kg0{;C-K7gPrR_=g_Q?b z`GJ);SowsNXIS}%siXX)j`Cl1L`U_NK6RHJ`Tw_@tvH1I=-miTa_N^A5bsuW~QF!jz5w3sqS09DK=J>3uu^3l!So*N+z_Jf(Tv-0V z@)MT-a28`qT;dYB`}SYt!Sypg(-M7`XFfY;K09YVJ7+#SXFfY;K09YVJ7+#Sm-;C= zK1d&y9a#2ZjSI^kSboCtA3kv5tMreLD@Lx^OM1-n(D}ltp~fRqTwh#j2i|?cjIi|J zajrk7UkIDpL|)Ld73nibjXS1(tqlxsp0MI zSNp&HcG@f9*wLRk|FQKeVZ;faJ72ov%c17eYn`9^XiE5T?ibFx-ZDA#oBgG8pS2T1 zw+>%9S3h+^IOhAvoTY2u!FRd*#0QNFYg}04!W!50vvFaK3u|0h z=#=`IpIvJ{=jXcW-;z%oD^-l)W<8(k8nm8Ib!}SDr@CfKeU_ZMNFSCRSoUF!3(Fr^e!}t}E{)gb zoc}U*$;pGwjj6u9AVw}7Y}%Ze+WpI~3!5`jyMH;`oSEAFD_%!WE==wIvNnncDr!+2+jD?qALti*Y4~r4P#vEc>v{)jlpPe_;6u%YQhFF%XxyMDEv` z@=&S+XTJHr&3tptd~?oxbIyEo&U|yud~?oxi}F}6=ThG^E`DlUSmVMP7uLA2#)UO5 ztZ`kQja$mZYtK3K&;QLgbR>sgJLSFPi=XBPc)`RC$s^@wJAahymcB4@hVzWZho_U) z$M@wq`=4UpqMYRN_PaGr&)aFdbE!=+KFB^S`>^c8vJcBXEcSN?%%mV(r3VD9`DNbzZEuovDSHD`D%rZPkt$$E;gO%(y@PA)W0>GMcK5m ziWTo`TEpreIGbC%$NvAkrZk7(!@qk@E1f?z|1+-cJFxB%ulqlgp&J9D7nAb zw<7cVOVItL{}DaI)HcKGVDs)zdWKtex!U=MfA$KmkNxmuXL&MUv^6+V6aBj?3~dWFO?jZWnwO@H8#&Tl=|GxQjDhVypwo(R=X zXy*LYh904O*LKbq{P}oj^VkE<<2OGR>b(At^V|VF!p1XqEnsuh)sKh8eJ^mnuftpc}} zeg2;Fx<8)^olbt&xzX_6Vdep|otq!gCyW^Nx^vlXeL}_cuR5=Py-yghP0{(dt!@qL zKH2De_YK#D{onr1`RA>hhhy&f!THR2Ekci>KRQ1@vt_7SbCdHWb6bZuD*fcVVNIKG z$K{dV-rP3y`!?!~d8}jcte!^|$!Di8`xVRm^nmkO6Pk9mOSe>o{+&cTe%!+m3bK z>i#R!ORlew;(zN0o26SV-P`%pr>{x(crNm%6aJZg{YK=+!}aO3lcWB(<65L$%2agy z^xl@~34871JhejWG_AcfbN2dENJDqp$xc-^-4onxq^r1`F`_kqMqi-!X-J8x`b%N`6-0j}< zmW3xeuUmR|TDkAZ&P%SnD}D8lg7bwh-kC0F6Z7!>JGZCZZcJU?Z&thXz)I0it<6$v zt!=_u^Mth)>izKdT6!Q4|5Iz}fA2ZQz03cUJxA^J(=*yDhqZ?eYi}Lao;$3)cvyS% z@ZW!%5%;G59e;|4U;iP$9kctF|E8FGko~Q1@$cW*#^1o|Z@=xn zod4$6{`UBP{5Q7LN#9x3Z^M!4H{-B=OAhNd=CFQy4*&fvf_OfZzBNHk_;$g6_qPbR zzVv-gt}nh(!&vq=_J4n~#qz-QrEkb^ed*gW{8nAxoZ&a@e0ztyA^&%NvxWPYzUyee zIr{tCR+e-7O;i3&Eq=4CZ*AFcpz?2U@f&A-o6CMPm4CAf`M>kqR)2p3@FTx2cs|rO z2Kh~^zCFlqUG+^uegpeI{S83gzjS@^+c&6%nq5Bu>8@hk7zQH%vs2A%Sd}9q}eM8^KVts>e ztRZK8L*Gp1H(dJG7Qgw@e9mvaO6Gb0b}|1JecczZqx%K+^KXvXxccT8{#5xt^qbO_ zuSCy>_D!U}zrAn$W6!<$H~;OqH$Mx&zR~nQ{_Xw0&nW4Wa*h9|oKeExNc?@4(|^`k zPCEaNvygPAIcFqs_B6f6*-1LnoHLblra5OV=}dE-eTF_~GjS#w{P&r6F%O*K_1|^o z-QQ<}{%4&H`u7>iaX!=;&73`_vzxQ)!k>XTt4?P<`9-)GI|XCrz} z9@)julyuI{Qgr6;Z*~7Nd8+%D>8HAX*_no^?q7D+VXFI=^}m-S()`Pur={!Tv5 z+tzQX^Nj>&#a4?aXVJW5>=qcgDV*f$q$>b~d^*{@9u6&iH9(sXODp zow4prTsChwTOa0f>%&~%`Y^X+eVE&~KFr6pKFs~GKFs~JKFs~MKFs4nu6WT`9=-%TMYe|EZVaLaunxS01pV{9s>sV_fAEf0SqZRQ~Z_b)jB*-mo*T zQ_fx|Mmq~T`rwCx1HIY>TGU1 zvpePNb###HEOPX97CClw7CH8H7CGbUEOPwOS>*Vsv&iwkOU~JR<($o9&e{CtoXvaA*?gGGb-zYm_i^ml zyx}_7*L|OH^*n$-HgC8Ne%id@jQ=)oI1`u6^Um3P;+)Mh&e{CqoXtzl*?i@k&125l z{N|j^d(PQ>n9KFNfxgZ2F2|0|^Um0}dES|EZJu|=ADic$@zdscXZ*K$-kG@cyphc( zF3;u}=WPCQ&gLcOY`${N<}v4Nesj*|J?Csb%;kFCKwr-r*s*!Tb+B*qhBM>Zyy1*L zHg7oNr_CGA_;2%uGjZ8G@0`si&e=TUoXtPZ*}UYO%~#IZJm#FuZ_e4g=bX)lx!mT- zT;JwTXYAO#>WqDxZ=D&}=3!_2vH95=P;&e(Z&`c=-@-}qHCXU6^hyQ`zV`7>{Zt~JUi6g*>?l9jSKb&``NSXP89$YO{8wG}uh1$v{F4D5@5djuO_DDo zuWEjKQf8lLT)uYj-N}~gBiC!vA^CV-w-Xhq$`$7y0^2ugm34-@Gc_?thOmXXkMtSG?#e57<$Du&=x^uJVaL$}@f{|M;)ESX@Qb%j8ALO}{98vs08E zvtN{b8@H%&&7Y$DF+Yp))BG>We~YWAdLdW6&{w^%qx@iB^8H;S4M?Yb-Ky0h!CsO!bkb;y{PNm=7FN- z0h=F+njdW5@H5kydy#8CL|^j^b~GPiU-Kd3YCgmt&4>7@`4In0=EI`qLz^daxy_%s zzRmNw9h+}+`!)~fp?@`*pnGkz-n z_^-NfeRchIu|N0HpUbN+ai(v-UKg2uUR8CO%jxqo-&^iX|JPl#!kO#h>tk0tbG>{! zZ;dn8(T09sICFh9X#aICAARY!x&F8VzjwyY#IV5``&U(tzxiU^ORC26=<#RzoL^kW zudi)3JLCUrvmz5$g>8OwIsGZQUtgI%{VY55x$M*b8kg%r{&2m>Pp%{R&-JCakSkvF zl?Uu7KiF5^7+3kkALSW8m4EzKU6|)pFOw&dn|>mFvy;e<*-vEO#!WP?`IE>W^D~j3 z=6@ppEv}>_u0-*ouRLH!`N6*O#<TUD-YOFez32+F|P87Kgu(HD*yPey72qx#g&)( zJ$g&~@o9}?B46BOLfWHsrQ^73^P)1MkGbNvr`PDl`rq%r+8H~|Hbln$T@yZYIpemyWQ{Za z)Lj-CKNr>g+~xRx;ysax>(L&OYmRs^moI*6Y_8wx$1%B`hR2V|?KkN$Iv=cVf>RWFkV$xS~< z-|Ph0G5bOGZQP)7&7UBD%+DY{&Ho_(Ew21G^2k*$^pywfs9xAty%<;Z!XMQOKUFXM zFR52hy{wM8-0GX_TitUz)(^RT>yvz3>z~{o>%-hn>$lv0>%%-Q ze&MSLJ)Lix-!}|?b%67)=l2aqUjKsgN8k1d-<>(xdE>-BVZt`EoDUjgzrU_NKbQBo z^wV7bqCM9+W2eGTzc^!m{`p(`J&19~G~U4(e;&MHXJ`Bz*0P*4{*SC*-kG@0SP}XC zr=Q8?-R~Hf>%V;Zv$>t}e?FVr|7OsjeB9;-56=C0q|@LaKU;^vLH^fWFgTA3x#C4% zdBBeHgMH!F)q2J?eC%|pUT_`k zA2&2{X56noOP%p&<(GAx@$-n0^_=nltNr8JK5;#9Mr7iZoIFUM{KyV@lYR23amlm% zA^-Bz>yr6Ty%ZO6#f!f3fF0!r`^p>RDxdhHJmaVGkN>Jm+pR{2MY}EZc=!5gbogNO z0_V*ij|oE$j{NYDv0?O`^Icv%|HW|hxOvVOe)3{C;QjZV7p3DuQrbDWp985J6y8pmq4Y-D)#?#OqXKQinxHS)w?hK9QJBOmm`u+aal$i06b z9B46uJL(e-x+v`h@H6cG-^M(xbaL&pd92 zQ2*Blohxs@T{vT7KyxCnebz~$S+R+qqxVW$Td#gTx>G%A^*4SPye}i z=nY++r+mDzxcGvHop;*x$6~n#-JGlb@I!IN6^}SC?fygY&Re=W|F+_XV)w3(Iv@MZ zhT^$>9&_IB`HjW2&*RP=w*9$yLB}4>{WkqtEZZQ)GX9+x!)^8B8bX&_Cx(m88{;}R zZapcycfn}q-q%eEb?U~wiE@1=g@p%w~Z%vOV1fPsYq{JQTLH_R`?u?aq2UZT8#**Kcq{kMxwQ$2p(#U5~WWQ)8T4^nN0(*Lb9Jxi$}`Z`F@FAMVg0 zZMAT$%U`a2dpfXLl(!t*Iz4qow15Aqrs>_U#(#V2u~(&oev3A5e63m9VOG@t;(=?@ zDqBxFs-@6Pir*dq>9| z_e#&3bU;ELI`r5hy>7-n&Ntq$dwSNV<(*F)SU%mQVOi(0$CpnlkBQ$KDPOaEx}bHu zAKloqd^-2WC2sS`i+4|l)p^I+zRQv7yBzktj&xo2y$<`%Myl^@*!MS5eSgEg%aQ84 z9QM7ARNw2c?|7v8j)#5UBh~jkuH565w9+*L+_#@EDyBo)cXgh!Z85F?X?N!jADW&% z^m`BIs>`RP_f3j>J@4%@Ep4>6kIVP1GBrK%-u}*IpD(6WRzKi;?mi)1X=lTbpXDP$ z`b)!`oaY`L(sC8+IA1wEqz{xk)%me~XQYeAoa21!IWyAQ;~F^+J!3{Xab8pBlgrOY z@0xwR^Uh}vFC2L30_S^w7+vT;A@YJglL|GOn%$tR~L3k zCM}%fTz2Ai$&hyMJAd>3?}bhe&5!@K!ncK)e?*&q4qaB5IWOATX~mqvAwNg%ar^$s zQ*X?4{S7BqPqzJIy7R%)(&UDRUv_@)z6+ANT_-y?-{#unrrjnvuXz2oWb9FqlL4KR z>Pw@}cDoNw7PcAXIyJivOt$YC_q^Wd_H^>|8RK34`H_8-S{)`jm+kOmk{liXZM$cB zB;TDj#pSO&-935k)yPNm>YB8BCUT$47bnXfuHiZjYAs4W*e-q#r{STClVR)Ec<J1$SEt&Pt}=`!P$JNv&qX3g^C{4#qx-*M3LWZs|qIse*!X|kr@VNs_+ znWTQrv`7!UTCPfAhc7ESkJ##f!WW|sbUxzE!wXYtREu1>cHyAfwVd1cKf7>s*OQ#5 zzjRGu*0*(?8^3X1;kd%-&WGRoc%j?bXE|?m@}R=wzn$ZJ(%|uhrRjOjosOSXxO#`k z7u@+l;rYv>PLp+?6=v2y({-xt_hVtp!uU-X{2cR0tldu&dKHd3H1@-%$95{LI6n5t zj6Tf^Y46xSJ(r(X=+Pwh)p1*$R9HChjf8m14m+Z-{+`#IH=KMxVfkM1+dE4pKasyH zeY5(dg1*Cf$$3wu)z16S=i6JV_f9|jJ#zhTd#5!QeB|o|M;o&&1I2K{pQJZ?tSsS^_{i7(sMUP{&_*qbWXC;?VtAP!eqqg-p=)R7@ZtF z=^5t_FB_F~?>E5thZ{#F1Mhy?d8^Y#Cljyf?>y(jG06`X_j4XrVO&zRSzqVZex8ur z{$L;Hm#&?X)O#=5uT*zxvb+$v&?Y1u%~$gL+x(fy9z!EfI_s_E;DM2=O?o%^;O)o{ zu75vSeMtPbW7>~NF5GdD|JzLs#w2$%kL&ywb|01OF*V*FKdkdY^7Z<7Ki&I|p-HdJ z@t)i6>SvPA---9)@`v|M?ra$E*B$?SG}+WC-p5Zl?7^htWnJIs3`|le3PB&j8F_<6Dn#o6Kp){T_W| zE~>gTGIP}LYa)McbJx9<;wuIkxI) zk-08Tc`5oyKTmlw`bnSva98w`{%?Ov%n#SaS)HQKTrUGB#j&`KChr`X>uYF_zwF;V zd$GsZXYBC8ltS#W&$fHAu-*5u_YS?iQ=!dmk#G5>d12gpu~(}eaDL(QKVm=McKAt! zOUgyQYw{6=bGC~;e|6mh3iG~>*TuoJW{2OB1AMI7!`=*M{d%DDw_{!pjV?XJIr(O0 zm~hr%&L7|KTDWC;HRlaA?3>k3S9f0g+0^jq!^b-h`*m74^O(qGw=ITBcOU2S?!Og7 zo12bxK7Mfs@9r7@M)&PLGs5@n;=5AesqvxHk0-d!=1)e3TI-H>{`~Y&;rjLQ-KyM@ zQQ?KzHC=wuQ=`Mm7SZOzH;oBh--u%kyLN2&@q_5Yik2^iL61k98}1z!u38`Y{7*)N zZZ(c@J1^b(LYTfZ#=BwSb7A|vV;*jQeptBq=PIuAT))BLuGPCc*Bw7N)Z23}=PQ3Q zKE8tU&Mk+8sJaO_un);{JJ`>OYgSR@KCAC zDxW7C)EX9^ocNh@yPJoGQ?6R;yvut-!q)A-a{l$qA)(5*>zpt9VsIEU;(O-n&I#+gtoDC9`-wTB<)}}c@7j7!_MlH%$EbW9JJyzZ3p(-v7naS;u=- zJbfJTQqrI_(kUQ_!@~lmwJox$?+F351a`D}>sMx0aKI+_lJcAl``c=8{k{Q&Z(k|tOIcHFYYkQRs z?VnCZ<9<|5GGRIu|1D0r+wkdhBIz;Z@{6a_ig!;buev{-?iV|&e7^Y%TJ-FK@~gVL zY4eR`s*@mAp~{UW%9%?Z>@5|ba8ZR zrmwuX*ddB4607{I_(5v+-ZABBxnn7D=bx2ZyzwK=-E>B|@%{bO;NR2AP0#J4;gwIi zI>+}?=QW3wU;MI%`nPrds62`H(9QK*v>Y5FQo-MKsXq{I%Uu=Y? zoi3m}_ZOe)=Pjsw=Lys0432Xo-9=MYyE=o??4~|9^J|?S66~QYNAf9umU%HfsO`p5 z=KUDzGxRMjPd7Y*c1G9BU% z2feBMXH*<#*_Tl{)3G>?yzlht+dU5R2MhCQ`Ov$Exz3q)mFtx_!n?*hy}DhFKm8>i z_fwgdPQK&Mjz3&^_8A$k_^vR{o+x6gTVQI8C$oe07xLA8N+qc>Ntenfk&{@uB0({LF9v`zZb2vV|Y} zZCW}W_s^exmB>gfPgC}RpXaIT>w~%5c}x3puKqyg8%awk&wJr>w|Hfg|EuHkpL@$H zXB-vb-Bmp06?1p+--Ah6^!bSC^P=a6K6cTaBBtAj9uhGm$=Ez!Xurh|!Y7BSsSbhe1; zY@*9WOqUZKFJd~L=zbB?{X|!cn64-~WW;nx(NQC&ql)h8o9-$)r*Ar^=%T*qqN1Zl zOh*;nHDbD}=(G{jX+_tKn64|jv2VJu=*+(9%%V&Crb~;C?VFA*y0>q-x9H@)>ExoT z`=+al4)2=|FS@;Ny1nT9zUlm83;1RWh>hTzjUcvzZ?=Qj6u#LMVr%$jYlwa1n|&m9 zlW%sD*e1T&CStSrX0wPbl}nBsP?9Hk8;_zS&k{ zbNOa-i7n=vEhaXaZ#J6PZob)WVw1Ajq+<86*?nRUve|=TC$iazVn4Fkk78G{*_C2% zve}zrhqBqBVxO|vr((CV*{x#Fve~m@=d#(kV*j$)zhW1&*~MZnv)RkR?<_$-34Rlm zgWpQ!;5Sq`_-$1Vesh(B-(uz9H(ELP?N&x#rtgU!NTvsh&PJxQi7rQ`%ZZLhrsIk3 zN2dFUPDrK`imphZu2}jAnGPvBCz;MEx+s}0D*7#%ek*z}ncge9E1B*pIxU$_E4nV3 zt}8k)nGP(vF_~`MboB^|>YPBw_+7HqgM9Q>kIPI&OP`U2yiPSoMN#(*((<$@WGRj?kpGs3sIBsxw3ia;jIN#36 z6uYRj)`=VtKgNhs%3`~b*=}Ofk=b-&myy|JVy}_eYhuTd*>Pguk=b`*_mSCsVkeT> ziDEyJ*^gpZlG&AFZ<5)Y&=b!6wo&!NStXBf#%2qYM?O5v9qYSypnnXM-|lMPYI*#t zalENU8|6Yd;`oP+A1j}!aEQkYEUElS)q`BPQeNe$(Xm{mUuI?W^~wDQ%CK4Dy<5=3 zGXneKO748husep|$f*o_WW{*r(}SH-v{HI4hy6kYQz^r)DcUo!D;ImGd+m72k1HME zyd#S#_ei~u`}@(#n=|a;+~cb$ztwgZ-(S-}xk%JbF30Vamx;aHzE*!_@k_J$rNv*( z=C2l?Gn>y@e9>&aXz@|A`KZNr&E~rnpEjFMJ6D6{{Bz((g-v>U;&kon?)n(6nrXJ{ z_l3M;9TcNHs?U5bAG1jLUe*QtcGG3bIqojtq0?3>KRdUON0wZpT;<9lzL#&Ea@OaI zd0Uh9%84>BW zCQs`XeB$%mRzTW-bquV;JT%pKz?4^s%)^e98xs{jKUc)Ch z4c9seYOUs05AKvkow(+!`13Kl^bYwtqgV2Ce!ncr8=P3djb0n8yxkLdy8o!$_1JQL zJ~_Vj+ic8oevNY}f7(mRPgGX^{k!FSHljAzUCCSCcxuX5>XX^1ZO zQSLoI6-}7XTX}zpl=MyfUdkg=q@dd6dn$ikJUOlSth@4~<;ke(N8OZ<_ew^yi*`}2 zJtG+nOV>$xY^vmRBXI}it{0P2-M88)*L<~(itn7ET)o~_%Cv8+@}$JuDDRYU$~1i& zZ64&_74~?!jk*n*pyl05Z>Mf!CMqwivYmR*o20xX-*(EpezJ0{OWWwx_9?Es?KXP3 zVXE@ELtClk)M?6D-`GlNnoL)YDYS(muN*fjwVD3z?_|4HbQ3i_=J>Ph8)?fE$1jp? zpob3~_vkZ;-k$fFw(~>NvDEf*P31=Y$I<=kj=!8bo|4w6<@#DMfp(;>t($Q!^X;YN2RCBy&5S;ch5+*n3F^ zo%Xlp>7-nC?+HKp_0Gy?4j=X3n(X+-rbGUg6OKQee!!p1jvtNL;}>e+xZhg#6U}$+ zR8GIcUo_9PpYq}szgeRW+UB85EBU`$m3;Kue%xZd_SLZnxXO|xJmKCE zmA^c*j6201S3ddca-Nawtn$p0E4brpSCr4KSjjuTxU1Z`^EgK*FK(A%fIQonvagptDG|3YTo<2i1MPztN7LNlFIjQ zt>gih+&i7b#pXp`mfx@CusfB{)M&UkBrGJF(; z9!yk*kHUX2Nf|zh9@i!-!$lB*YP#OPwc5x$Rw0ZE~#>(hx)EGB*$WXZE=UNWgW|U~544Jo=Y^9v)?H~Dr zVfB^EPuS0=FV$79^7cM1ci}VTTvvQPd$_i8&4VCz>~MSc{|-dA?H2i=JSKtM4UIFo%-s_ZK3`oxtFF9V{NhT*oXal@=E2!qe}6D;G3yk1sm|$@0Vyfa>~fJtI7-SZ4G(AkIbvr&DZjL z#2htgfpU>aJ|}LnQ2D1r5#E!~&BKdZJNW(t$5kG0=R8jwZ~1#0UoY<3KipuMpZCar z9`+|CTk5aB{u+Ugwp-$tdiuKZx~@z7l&PF8ur2#ie?X4JTHc`FGXG&#XGcW3t?=7E zORD9Gp04sEi;^qHzQ58xe%j?L$vAA4zkb*~?JJMB$}g7ny7KeSSNKh?Ur?_4&l3Ol ztnOX^le`Q3=r`iDym#W+{)+2+l{Xxo;;;P8z1uyuc#Pk&@HQ=S~Kk7ThHIEU^1 zIDA3&UK>6ld*2P;k-Z0pPs!eo!`Ec*&EbQx_v!FW*?V@hZ*cle@5V4p6i6w|wEP=!rL@dTYVh5ogrw z9m%=FmUBmP@v!CMksLj2IeH}T3|rnA$w$MMk4AF7u;qM_Trh08U?fKjTaFmX9mAG8 zMsmuq<&=?JGi;;`k! zksLs5Ie;Xe4qHAQ$+N?jXGikyu;t&8ygY1qdFqtT%9gK3^7ydj@sa#KZ25g8?+;tv zAIS&AmJdks1hM4_lKeqz`GX{{5L;d$$v4E7Z%FbGvE?C>{6uW|i6n0kTiznEeb{Ut zv5DAhBC(a&Y$dUw*lZ}Vt=McUvANi6F0sYfY%#IX*laYh-Pmk5vFYSxRUh4BV(YQl zdSU~z*?^++v+4X|3$WP&Vt26F9b%8L*&|{*u-Oh`Q?S_-Vr#J38e)U6*&t$@u-PVJ zv#{ALV#~1EGGZ&S*-BzVvDr{!6S3JuF$*TJ*-BzVvDr{!Td~XW3wg2#^lh(%(tD*_7t0x z%_bFFmCaTa8Mb- zZk8-=R^n;N;%UF#xSlM|R^o5T;%_A`mn<$<;&sX5btR6MERI*=d&%N^CGM9j?pNZ0 z$>M=iHcUbm|15FQp2bB=T(M_y#S(AqS-i2tA$t~wEb+;n#V1SLvS)G263^^eJhQ|( zdlu&`@z0*cKTBM+XK~RIFYQ^pw8T++7Dp}d)t<#yOWZYC+_l7Glf`38oHkjUw#09f z#cxZjI9aT?#E_H4kV_mmSsb{;hm*yJOWZhF+_=P(lf{!uoH<#XdCyDB$>P!_UY#sn zea6z#bT#9@KJ>}nTg%ddt&R&E_2|_~$M0S&M-`s_qjk#sT!H?b^IUoG%8K;IvZu-! z>U~JNb3ay&{;@Lc%kfBg^5ZJhcjJBKVr>d~kBV(q?$9!|H!5nZa?HV`-j=EplvBvJ zCXv4uy<<$e5Uy7I`6;(HHr&sMH{<~47Bw;1KMhvR#+d69CVTnW6VXO}6@Ig;4> zIGRwflp7C@NAY{*QC{-=g||7juyXg)&%Bd2 ziYgym^S4)eXA$KtF%P{{P4X#^*#CzY{UDR_U&U{GqYfrf{{46jD)8Gbm5r*`pa*YU zR$kik6Ph^XqH>ZtH7Ud4v&xaHH7R-QDdo)BYEkzE$CT$MtVNmn9#+0LvnEBgcK(E& z7eAqxf%~*PS?lW5B;9r8pJr8~X|--ET}Rh4J$h|u|X)sz<<^Qlp5$79YhrOxq@mR~u#la{?-U3vSmUDSNq z$I3e--}tvxUHKQ?ms0(ePR=~LmQbc-&9zQ~VoT`D(#@2Q#4V;c&-vWm8^4&A<#qFL zWYA)&5as47YR+QHa=otBPkUoAZTk5$hB zUPkMx)zI=|{g>0TkDQ$S2d$u%bDW%)bMK*~yGCmr%wbfz;mR{4{-;He5y}G|9;OTB zMk@b2@G!-eAEkW$w>WxG!2R!o>~R!%;&^CEWWEd#0a@E#R3gAU1+$HiGE$p6Toh9}cnf)bp8JS&HJ6keZl)bC2#k?{Py<97MDYrWR$QxI(oAMWbJ@#s@ z?4Z1)=X3Av!tNV{nU!98kI%K#^16%TQMLWemAh_@Pv5@yTzOwy6fGO!${(IcNFOwJ z^{?+rOzpn@LhBSB^#;AU-@X6(BK3Oj_V6=WK6dIVZ~Ka?%F%6Bdv#m8xWTqJ*LYuk z;(QcItL>zr)hjdh*x2`W(fF@FQXbiPH~n4j6XntO_fX9PwUxWB-A9Kv)={3e=m0HA z>HKoRxu@m98RhD`vr9QR)0Bg=PB}OOm4mZUIXE+wgR@i_?VE2C{hH4cb<97B|24lQ z+BAPA`Z7N!WHA3HWHY}g&Rg@Bihq^NzbbxLGQX?%W6Aun;-@9^(~AF=%zrC>T{6F} z_`Yz5o60XfD>9#z__D}+S>od&^Kpsqi_G^WJ~1+%nE1-bd}ZQ8BlDp(9WyL!KegmJ zEmYC@jgQtIKz~%3qy4sjeE@x5&-s@BOfi5iwRQf+j6Da??4B`Nr*z?gwEQdQmup)3 z8+y03^UHM^JBTinUZ{1}P8>`x9ys3E=Udu7)cN9;^%z2V9y-3>e<(G7&yDwuu7l}G zeCH!AUh7-hGh)29vpW5^^x+E^Ta{+gAeuL6h?ciH|20KD?5q4qzOU$~bzPLbtKU$O z$IiDrbM*lFH;3~re>duDdV96wO+)%p%p~V$zObS>8SiCRNZj zGe~^w@nNNv)7@M^vp#)KIp5{^6p8Qnlb>T~Y+}dNkIth%S~)&&d@hYkSzPPq{Cy6k zd*glO`l;qnp&BKW_cxeLD~^^_zB_3F!>4Ms++@g`Q`s zruAFBs!G?&xc4~k{9KJbFZ`jFudDeHHH)gK+`Z#RH2)_zmPL6#qK{@f`O6HiMokAs zYn{|53e#Urojg0{WT#bYYiW6+_;1pa=(@`9H%m;tFS|X~F~tinaeKFCX!aei#8kIe z7q#8%&3wI^*1t3SfH$%2m&&n84|$V^cUNxw+Yzr`qaMoJ?j85~U2;4rMvasuS+T8ix4})81J7;tC z^QxS2@_W7Wd;ROUxs`We(e^G(e5cX&j!fQRMcX?pdAAj9@3!QfSG2wJl6PUz_AX4` zkwx1(GI@6vZST(Hom#ZLQ`tHmC||$mq$S;Z!-@4ikA8aD>HMP_RE-{-?3%Vy zHtzlCe-__RZc->;^ihdbMf>+Iyd9k<;%u($<=>|{V^ir|eVV)+z1bv_@{CSI-9OKu z{9%8Oe)~3^a>t6%^wo(sl^-80Lzx?DZr?;8Z@Ych zfPC)uy#w;R+jkJi|8Cz$ATPXqH-S9w_C3Ye!;`pI{kI8YsV4d57ygn>dHu@?-1@s5 z%DI+|nn9JjCaJ-6Nuw5 zSU%d?amm)>_`}Pte!2$Z`NbQKvz3~_)&Iz;|0{7{Y;j)_55^V`Cb3v-u~-tL#TKI_ zv0H4hTN2a77SkoMUTm>m5(CB-117OyY_VYyGsYG(Cb48}v1Afs#uj5Hv1e?tXI{o} z+&6zbl@s%MZ%8ubuXax3o#oz8Zr^hnCrOrA`Ruc)y!YP($~``t%BQkMDVG~Qh35~B zuiS3>WS(2}HRX&GCh;GoT>BOKOys2Ae;(GTVZ8~Q?bs{j^u@<>lR~as^clQM)&C9N zdnyO-LzRQ~q{_kjQ{~{js&eqYRT=MU&Gro5&uTgPGTTRNA~u^y><%`&L+lYYdqnIM zHakV^7dHDv>>4(^M(iCndq?abHake{BR2a;>?St5N$e>$drIsqHakn~FE;y2>@qgH zOl(Xx8&hmgHrrF|J2v}H>^?TTPwYW9dr<5|Hak)5M>hLW>`FGfQtVAOdsFOCHak@8 zQ#Sil>{br#*0{xN_N>^sY<8~Lzijre*xGEiw%FioHn`Z)Y<9HR*KGE+*xhV)x7g!s z_PE&TY<9ZX^=x*%*!yhuzW4#y`~bT@IO5%Wa-18bf9jvu@W}fvRjl%9FC{HqzEgQ; z-F&q1!B*wNZ+{?nw{BGKo3bg@cw?Qiytk!^N!BXgn6t*KJ?NZr*=b|ErTczW{w8Tn zZ`!PD%2)dS8~y0!4dpqh3PcZ{e9JguEOjDQNB-Bh|CKgCi=evuJ@rxdg7Z*9fNh7PZyzu0c z+;-0@<%d6>;)SyRFt<~8|IC>SNX(h=h`y(J@!Vy~g>Ikb=zo?dXHI!W-*=-6=S*tws)9rc>17tYbaXV-4uu02r zY~IcnYHw5?S#$?q`Dlak<1;(BXw&t|ITuCv_3`VJPfYZA>Mhsi;Tg=2yEsn0ekWhd z`Tu?4TL$zs<(=((FyU3@dpoxAdn>Ogzl^_)mzDTkxj~YxT=a(jSJJ`b3m+S$O{jB}U-XPh}%Ccuj_Or6=C6fKDEPIS(KP$`LBiYZ& zvL{LQv$E_}lKreKdl)w6|1x8|K^^7bf0ctam4m*N0~wS9*^~pBm4mUkayLe0{9a%F zZ>xuXAMBgPvtIX=6OW$8=^yM;ZkvA^FI%xsxz3`gyeC_%@*n?A;UQ(>lv9_V!o_|+ zqFlS}WL}x(nDUQbPvXOyjw_=t#MYuO=x>Ov1w(&BY%Li28)9q0(BBYS3x@uN*jh03 zH^kP0SBsu@>F)~4w~9^R#fge5pZ|FrXUUOEdEHNA`Ri4wl^f(8%U8?2ipKv&Um3$i z@1IpJ`DzT8>abpU;GnU*dE@uWD_V@>^V4f7ADuOx|E`)`d1n5JyuHh!vS?@BKV!M< zz7Y{{t^dYxm$Ba}-+nZnQ;qDYoZ#35E?lCy@{eOD^7yq?lrt5a#Kqhv6FaM*5%t!=g-!Yc;D)u%YeT=H<7z1 zYoW3Yxi!O2@#I?{<*UXH_Nz^NNBN)f{ry&7y{CM1d2jzhxw6XJ`}g#}*j!QhucO`l z$c(C6!Z7=1KU55JY zll50#Uu~qHfBzumy92)WTYc|jD|u(U->=sYEx+7#ir;#sW4U*QaqkM`mwQ(j_pX5D z-WA5ZD`2^Ig>ml+Snge6+`9sndsi6uu7Ks<6~?_QV7YgNaqkM)>=dxs7htnHz-Ett z%}xQE{Q@?-25j~Y*lc;Q*=1m}*T7~sfz6%*o1FzV`wMJ#8QAPKu-S27v+uxW_kqnG z1e<*dHoFyUb|u*CO|aRaV6#ubX19XPo&}qo3pV=~Z1ytP>}asr*I={v!R7}5n>`LT zI~{EHJJ{@cu-W@y^87zYy5`MPTzUfz9s(wwNWb#TS7s z?g(u0NMMUo0$cnN*y5VN7ViYMI4H2iYk@6}3v4k|V2iB+Tg(;MVzIy$qXo9uEwIIO zfi2bxY%yS9iwy%?%oy0>-@x+hXj~lFV$Z-9lcpTRs(~$r4Q#P(V2gPJTPz&dV&uRU zI|sIyIXD+hnkPM+~;_i^2BYG1$IG2HSVaVEcX!S+oq*uK>T+c&&m`?eQs-zJ0Yn`N+l7Yw%V zg~9e6G1$H@2HSVXVEY~!Y~Lw^?fYf0eb)@O@14Q+9W>a!j|SU!(_s6~8f@QRgYCO) zuzjx$w(q#X_I)?lzWWB-_uydrP8@9CkAv;Ia0S4@8!Yv9X;5-uLs-r_+Xrq_)Z^ecO8K3?gFsgX#lpn4#0K?0=R5& zHv-u1<4i*zOns+ub8z$cDRU!0;{OE*da=&bW&P z3}5tSxr+u2A2sfx0mFBVyJ*1hY2z*$Fnry(iv|oIIPRhW+Z`-myPE}Ucea4-E*G%f z@dB1JT<_uo%kPEWp$C@V3%y$pEWa0e=N?#oFZ3=xu>4-=9erT=z0kY+!18;cclv?l z_d@TG1fwr}cK{Z>OYbcN+ueX*(RuXFK(O5<2(~*0!FKl`*zP0*+g*iVyTcG{cN>E3 z&O@+#cc6D6DhGEYg6-}^u-)GXwtF4Hb_XNa?q&qrosD3-%MomMJZk;m?nkiQ2?@4) zDZzGMCD`tk1lygHV7rSFYHg6&RD zu$-}a=ODWvU^!#;E>N(Xv3f@+Sk73zI}|Kutll*W zmNQoGAO**hza8IB(*6I^yHGaMPmW9eQ9t_Ty2)DpR>nEelxwPTx+jOCFJ_#soOj*B z=mEoLDn}(x?A53iOREKq(cV^;5%+|FN(@)Kj1hxN-}a(-{L z)9s0S7l8K5@86(x(C?LZHwW#^iT)<xyYl5)g%`v-=vc~kSh>`X zSbZ5+#M+VeBi6q38?k;x9^d4Varq{v$nTr{GA{pr#^u|1QQzhP?b!UFeVaG*Yx4-s%<3>UdJ2h?kx~J@kZ0Z)$B=XHAC4ja!h9384#w3d+VP5I>%#KwWmbpv6Th}1 zY-dUOrD6M}rz{Hlt?}K0P#!4{GffCH}q@s z33+UuA*anhrTfpz=H1Xt`DB&k(P#5ESFZ7K#^|E^S}1?9G<)>2uUjdf&yg$oM)@zo^4tm9 zhV^Ir?Ud2ZSwB05{7tKO)$)Yj{+{#o9*(7a zyOm4*9adl3*34_qEAm849vN4}&x8`9b?O zZ|K+N6Y|(RLr$B2$ZzW+`_Q-NOV-i1b(Hn>ZGC0keOq_g55DaO*(bj36WKq$?H}1! zzU?d7Z@%p}*@wP8UnsZziTbv0(T+V|Xg_?uq+ff!Adfv?kkg(o$p1gjmv7IPJa=Ka zJda_0c}~N2nOJ&EzA&*>QR@T{q0%ug0}jP;scUfy}jZy)BfhkVNo#ylVX zft4};Pusiq*I1X0AMVm}tk-Axb}OU&&m?=o`m5!AxwUg)<6dR7|6bR9%IG&m%Kgfa zXY@qJkaP8)jv@cpLI<=C#?`WdV~p3zF%MQB^JDE`-mHDhr}c|@HhD1rCMVX#{*5&5E0~c;jby~-W^JGkJ$2e!YG=?+QGSG?c=<%esPYOJUHJ>PMn7(KhDGd8CS%{i~2SXXvgLU?c2PeUz<pV7YUbM$NbAM)690Xgk?f&BIyVO;in$#WN$%kvo4m*+HW2fzE) zzC71qzt9s*9_SAyr<@O={LnXSTqw8kqQ1=o+OhdT`!;Xr*X9%Q*gQi{n}5h}>k=>C z;9SvN<`B-J6`yYFK~e#?#olTC0sRFQO&%GSZ*q$KzR54+(wvFGxO^Kg>f1b^9h)DtZ}WzJZ9XB7%`@b*`Im7; zY+c~rxW2ivj#qL4v*d18mK?z>Ih~aycQ8w?XJyGL%#s6IS#k}t zF-tCKWyxjCl4Dv~avAfFL!-m;Q9Iolp}yqQ)^fBXIklD1zU0(aM!%9%TN(05PHkn# zDLJ*3A;09*R>rs_r?#@>ZVt;Or*l|eay^IbNDk<*eaQ_S_A5D~LwO{ZbSS6fo@SF@ za!-fjLb;6>^=%%|j?E9+w|PUqHlL8k<{5I@{6l_Qmtb6sy%CI8IhY6KV1AT?c~cJN zQ#qJt<8swpC||WM>*J6%E5k94)&pPFka#iK^2jyU&C{s?rD39!`P|hG{y|y3ZtXD?4jTiN89?*`>58AhRL%%kkkjLg3a@zbuep?r; zSD99;^_(x)?I@*wxk`E1$e(EC@s-Noj5|j8Z!A|XGT=CUS!1bk8uwo@$o!La?P zI58AhRL%%kkkjLg3a@zbu zep?reYudXpjAsh_vtuR4*tZ{l;~4w7+pmtX&+oLDul2G254`4lgLp39_8sGSss7zU zt%K(%VcSK@c)svm8~Q@|hwnIFBI?IWv{cK{PT|vz(f;u9%d{N*wk+!WjgaTk2FH*y zUfLB}2l8K$d!^7m#{cru^xiER~yqKJLj!b?$Up6k3 z+jvpm<^k>4{GffCH}q@s33+UuA*anh|Y&^o4R8FY4PopdFhZv~TlkIl2@CJyEw^4q!~2Rd?vqc6)L z4z}FlV9PlUwp`?3%TW%t+~r`)X%4nr=U~f$Zso`oZuOBX9BjGN!IonkY`NFLmXjT9 zx!S>&!yRn7-NBYa9BjG8!IpCzY`Mt6mZKbOxy!YFkkcG&xz53s1KrAz+uiCTw>#K! zse>)YIvD*Tx4YI4aXEmt+za#({cw>8*uUV|+cHrR4x zgYkSJ_cYjYYFjySPg{NDo(7{GjKP-c8EiSA!Im2uY&oOBmP;CJIi|rF7jjR7Eypp~avy^&CoCXt3py219=2o(AKa z3tKNK*IeO2ea#gPmUaj^tijU0<_ZT(znUu?Eb?fsa4>S9o18K(GWjhBI_jX@)(iD* zz0eMFPh0!QJq<>`$UO~)Jjgu_mT_sWa4_UY?rAW_W$PvD7?#WWhV^CL!**mpgzd{d zA?sK6PbiP&G)McE>l|!3(5>9Yi~2SXXa~8%Q3vfKS2!5`B3C#V^4L5>PUH$lIpnwX zl5@jP_xiu~-1+w0$@A!M2%blIPJMe$<@xpP`IYC|x93`(ci*0OIR|_@2jtxF?R=1P z!>`%*j`oFeI}cIc&O@|g=ONm+^AP>oc?Egw9D|&89?H4l|Ic~o+j%JGWLPfeXINj( z)vz5oZ^QQG91i=H^Es49&iPPIIp;(9<(v=4g>oA&>f1b^9h)DtZ}WzJZ9XB7%`@b* z`G@?rE?6(q4>4ZTLv+0Y{RH!4dJE>w^cl>j={cBZ(|<7krWavdOkcu!nSO|J)2~q9 z^e(hx`WV_bJq`Vu{swtWuY;VX??Hak12Hbs4>4XV$2?el%#XE$d9(I0pVlwt+2q0e zo19n|lOOA4<3hQO7xir((2mUy+P8T_zc!zc$L3krE0}-CZ|fp@lxO;(=pmlzA)=pn zrk{u&_GXJ?}dXeZ+p6N@XM}_`gl$(Bt z`lcVEowB{_YddKFdewSizqc#ab?u8hCA-y8hMZ+jeWncgH}!OkagDCySoFrQT=dDX zzUY}@JEDJj*1qVaVZWlUhVqEs8_FqqZz#X$z2Ue}ZsSFLn+LRG^Mm$n-q5ejC*-kt zhMYG4kl)q?cBS}j80Tc*&ruHiJj$?7#s8xm_=S`Mf01(FM^X;_OUi-YNjdOGh2`cy zM1AqwXgS&uzl}257r%`%`W3&8GUO4zjWXmEzl}2F7r%`%#wC6><-nh#9Qb*Z1OJb5 z;1^O3{6)%vA4xgzFDVCpC*{B&6_%U-5cS2+rsZfy{A|i-U;J#!=vVw~%8LKLFW!i61~Y@Ea%x{siT~&!8OmACv>XgmU1oP!9YU%7K3)EEhjOSYP}A z%4kRY0Lo}z`~b@6SNs6VkVpIg%8*n10Lp=XMj7K0zm0O>A5aeb2FigyK{@aRS-%`b$0&0hq0%#Q>)&A$Zs&F_S9nLkR_F)Ww$4eQIghwaFI2-}x^680HZC!$WXwMz?p*@e- zhswczRu1;La4)(Khu+No){jVH67s|o&q8vO&%E9v$mfLw4Jdau)Jg3UR^Q#;@ z*UG{3t{j{L%E9@dEO)_pKP7ek_B?Y>c?+^RPM7?wH?*i_1|pW%G+Y3Z6bB=E^k%YWS~S8*}p_wjn4>tTE^$_E5KdDJg`ZK>8l zJ8dMl6Y8UV?&SRN=yzr^=WmBRZ;p2iIZHoq4EZw@T&e$yas5G#3y(e$mQ$ufVf`_` z9SGYg@J#N=3fhl+wL9$hSjU~AJQeQvp`83G63X9oZ6q8Q%5A);Z}Wh5Y<|$b%^Ui) z`Gh<+&ydsRAM)F}EKgh8n~~us9pn7`4ZO~U91ltOxmTl|23i=7I~tGxMhSU>(l z$7rX>&eK|s_DA+Tql|uAWpwdZkmr|Kjv?o3FC0Vut0m95`ZBJ~)g5nmRV^$(p1opN zzw6rQu$|?XN`&qIbh>ER@8dm%LV3>YF5sD*$8YEJO#b2@=L^S$avLw|+dQBhn;*1q z^M-zHJ|U0IGvu`Shy1oKvR=Nemz4WfF7%4zF~b?_plw= z4`KVVPr`m>|Ag|$J`ClQeHh9w`!F0A%5A);Z}Wh5Y<|$b%^Ui)`Gh<+&ydsRAM)F} z;BG8C59PV@?YWcZ(YNPOo>SkRQ+a-Udw%7)_U*Zr=iRsGUCsgD&H*_ed^;cH+z7u5 zK)IcVsBh;X+OhKx?T6=~^lRr83_J8{Yos{uhWK7>h8P7}ija`-T z9Np>or81tcd_{YN`p4FFjJZneV_pE*C*Ry^_9?#?v zIX#n8f1b^9h)DtZ}WzJZ9XB7%`@b*`G@?rE*O`sm#kx0F6$fC zmvs-@!S9H*FZ(3ySN2aR4}OnKPW(=p{P_K{aiQGCi~2SXXvgLU?c2PeUz<JX;U?tm*ETLX@7l6mD{^#ZC}mCl&hk9b{Y(C zNn886=b}XOc69yJK&^jqO(&{9dZ_ZQ&$`m2-lLQom+VG$zaJZxr;C{s*8gnmbY--& zrO<3;v|pofj57M2_Sos4kZ1VSC0Y(S8@}OmNXTEksnZoPt_(jpt~s(`Sbk58AhR zL%%kkkjLg3a@zbuep{ETWe3rt(?9#rpL0(fO0PF?2{AQwQbU9Hf<>}3*QI!Yj!}3*U zvW4|$49=&Fb~>*wqKx*-7Av8Qe!n_eRvGg2ZtVPxkn`du=VOHYWA=Wibug~UJ)Qrs zf1N&I`S|7C!upZE?ZbBNJ!=`Zzp-i4u;2B^8iewE(yK0+oU__}MkfE%EuV(tLb;6> z^=%%|j?E9+w|PUqHlL8k<{5I@{6l_Qm!jKdah1!dJgnEm(?9U?3XXq%K9d)ANTKD+ z-kHh6+9y@6-F*hHs+&mptK-x8_$Tp|pMNr)(>-|>jdo7oo5r7|{X_Zh4bymhgI|?% z%#*vn3Lg*4*T23utbf1iCS|l!u+36sv>&r;mNNRiy?&xH1`@W|$ky)m+m10O`Ind1a?I70 zTji87hj*@#GUm4U0#6xpKBRE8GS;rZL>G6BwOfC_l$K-ddcIjw8RaEvy&u-+>F+6{ zoiF|^s*LtGj(ArY{l56Hh%)3!SfQ{oSAK?zkd`et98(3vSn_r&{y;eH;0hnz3gtDA=^Jm-TXu5+}j;vEKhT~HA4J@-H|AH zlo)xGu#S>PiIGPMEP0d|d6dACM~RU~2`qV(7lo)xGz>-Iakw*zE zd6XD=l)#cliIGQ1>$KX)$fE?7JW7l_N?^&O#K@xrmOM&~JW626qr}Lg1Wws72_ugZ zSn??OJDyKamOM&6@+hHP@+kSpqXd>bNbN{l>8V9BGz$fE?7JW7l_N?^&O#K@xrmOM&~JW626 zqr}Lg1eQEXj66zU$)m)`qXd?`T8z9}VC)Cv@B&K?FGdb8u;lP!SK4rQ3t+M2Z zC*+7nx#Wl^dx3fbOa{?`ZG$j*k{%N|C;-hq0GQwUheAwozVC zWhZSo)>OGi^_^65Z5`#YnRn9pRn?W7MVP)#QBhg$aiRh>e%3uH_ak}BR!&uxyPm@P zW91GdI_zE1a=BZHKK}c%vfQ~uM+Z8VyO`*}rC+sN?r5Ul-f}E=H_;zOT)dOq=|r=O zT+%vn*AunNa#30CfTF7LE-1_0P&D}JIc2#sidr8&t1Nd(QSyCfl;w^oDth9yvfMpI zKfiGD%UxK}cCRn)Jh3~n+=UhW`%A}iM^^OO zBTjy~J1e@&S8j}Qr&e@=hmPg0t?13sZcfmb-Tj4oS8`W!XE^R-Suox)?rGVS)Sc(J zzh%xw$GF#}+7S2d68F9I?e5Nb+ynDxKX=aKewfXZ-8qlDIPAV7+|hC6P1io|04e@r zvCawZ23gn1wTU}DDlBq+;jWLU7p^|;0IAU@_+PmjWI#s8|H+*pFRr_GaF!6{lUcW`+*=Qx(Txx6$B9Lt?u z-eB3&c)sK=FYlLV_rG$-mskFXW4Zgw>oshe){#5Gyxh&FE6ZJB-k=EEG_S~WTEC?KwtkISfKeAz{wIU(EJPFq#fpK{snNeCo!6T z0bFjKaN0Muoy9X^H2(t1A8lC73E#@Dv+gtC6pfxSj(S3aD2JL8lE@K@xoTC`L9#&Yn@SDSMkXG#g#vsvXZZ~drvvVg%!Ls zwy5&&AFkjw51bx&{@Ql_b(H(xM@8h`?;i?lorBYM^244^KYaf@b6i@d6Mp}%go1Z< zZ6=QLIpf!^uZ7QdaMgERJ7?SP=I)UK+KzX353jG5SNYzmeO#x38*j;l2e{gEHxI#m zP+AA?@8q5+<={>y<>0O-<=_q|<=}28<>1aJ<=`$U<=~DfWwihIJ{Ma!ctI>DUUovy z+w!vya)!dEls_GMh%47Pt$gCsINtE|ta88jhxuXFi^{PR4s(YUzba>ZewZH&cd^;A zrH^o}={L0euhBBbK|d*1o3xKhl!{YMd0-FEzP?}iQQZhP$-7&5Z8x8bytYgE!X)My zi*_o{+q{$8r*-9pkL}`$)m{CUXLj@U@_V(;%*TuP`BfJaj{SChx{H_oa#ai$nBu;- zZFn<=S1o&}^`BRr&spyMp`7fBk3-hvfBOc zohOn?H$y=!pZkl1v*vX?X~8}!*fy7zkC=0S;{TUj8F{<@^;}=Fj%4?VA@`Qu{e_%d zb|)Beb=h5E$l+yoh#|Mv{@`vgA|?wt0)=d#Ur9!&=_-+&&s!`J{5=`}?WEzo(U3yzwK=-Q;ZEYPn-6ap#}4 z{8{mX)a<=u%8QE~qNpOV$_dlO(XE-zb{=yfj$-#Yn|eyW!}Ki4e62I~{$bj1Zh~?q z$xC?u6KB6SUNVDPRNCcZjcz}lK@B_os(ilr3|jQe`IlDRpHBCSoz?R4i>K3ycTXvI z8$O**Bt52_WWsbR{#%^#q5ae8Xxxv=4Rg+*4A=H57nl4~#Wvkn9(;Wc?JO5h*Q;>- zd6Z{u66MXwVrX8^w95ZvSwv0NzOB5x$U=H&S61bA^%qe05m}U1&zw)`lV?`0@G^#0 zG|i}-Zg>o39-Lme%=|%#uB`@+^}*%W`gzog3IEcAm(yPxkD~nLy#0FyS!SSs`Z#*%=~d3)$HsXAaq! zBWDrWSrqJZ!a4@~Upd&T%E2C14)(Tku;-P7XF)l5MwEkRM_JBfvNKuEYO=Fh&Tz6b zT+Vi~vt52K$bK*6cZBSBM1Bj%ehcI`g6ua!emls1JLETo>^DVzYsh|U3P(++%x9fn zrS9#C)H=QMGei!EemlbXSn}rcSkQl}AeMn~wFJuWy#*zRB2ZftJgj;d8%jRL=X&dT#Zn zulMJVII^4vEBQIUuN>EW6@NZvm)_5xpw?<`_25ovjCXnMHGFc@aFyX=v$fpi zN$%|^@6l}?SFTV*IZx{qeBt+t+YM(CUCpF$vzBYF;XI$)ZB|v|({0sO^w7d+^%`CS9bT-Sm0A0>I^~aO8F%QkUO7?brM&2%=&(1C6 zktNq?{Tz1}@X%>1mG5O;z;8EQraY?8d@dj3zJq@HB8Jxwa^FGUT_3|$Gr8}e#s9$O ze-OU}n_ohF3v9jx@j0;h9K;vF=8F&?1)GmTd>3rKi)EtYwXfA*WhfH0lgn{?<+s}I z;`?hFC~wZNhjWjwrraa-KJM>FD?hGufb)(lrVRZm-n#{ru_r&d|3KFfI#T!A@w6Pe zQ_-G@m7!Bn!Boo7wTf0suM8b*#rUks(9MS5$f*pS?Mm)^%3Uuer@C*o)935#tQ1tN zcN^vWAEc!354TocAD5Eyq;I8Mu2W_jFs`9;boY#u`;z0kqtesmUX8STHNQof8a7rg zmg!9zH?WDaw=4~HxZG5^{-NnuYJ0h+a*sZf=>Fvz6UWzzZlb2g95*Vpnf~tYIHu4Rio9}mP}VoLQko`?&mG!IEvGtLX-V5{ z^m4;gZNJu~ZS-pU6y+uPwo~Tyla&`%*-pLZO;YY&dOLL+Gf}z6%Wc$ckn?BK^lh|x zkn?9wO1zEoP8p|lqB5nU4RiV_k4=@FZY1uYTzf_`8kVk;^6_5DXm-&q%8!;OqpBZu zQ~tboa$50Ocjb{OQc&&kJ(c&DNJ-zs@1@*(ekz(Up|^7BYH5fr_fgK4?M=G!dtc>4 znO5?Dw<`HKL+;;N$pbEt@}kMB_|@@}$|=*W=Dp90D1Xy=H6I)eW!yz`5@$}>-{;Eu0dQ9k+W za-Nawtn!y_p{6+IzdB3&nCz{_$%O8!|;}>esS^2~12mHzG_{OF~{+1Jt&m2DLzctx$ z*}W(H=+_-58Fbp;n#Z-1Z})Vco;THYDy;43w@*+Q5gCl|*kzmQq5kZbfu;lEBAV(xv za(P6MBNB|hsvr7A=Ra|=d6Adp_bY$jYh0x4%md1QZ66pJ5fiJNb#2Q?wW?0PZ87De zNT;ulYI(8rB_p?Uo=`rvFJGiv-qXspU&|KB-2S{W@{8H`{<{h`;IrQ^Q5hDGD#Z(e z`v=nZ$jB#puha7LeG>BBk}H&Bha}|cl~*cvzn+jQ*IK1q^M^$I*C(r$7tTw}o6D|I zUV1MHw@bNJc~$?UJorb)jmszJ@=aX(PYb2w*h7xjluFH|Q?A$gcRo$a2MRb|-{md# zGdO-RAU#jKR6-Jyhiy?Dw|biL_>ZG_^V;dk=Zi-1 zvn?}}bIE;vXAjp_uJZOiE_dNG<(9?wa+gJ)D*s+ga@*~3b<*V6&2gn1Pf5Is%O-VP z^C5Fma$J7Gem;GvuKsVTw}0dhhSgVw|6yWW17-Y9NnS-|_#d{HY^4nU!;BIwl;M9U zT=R2f_#Z}%anAz$4+sBktmW`OoL$^V8U6>!tEi0jk%t<475yR)H5he}hZ>Ckom0v& z+C&~|l%p@?p$0<+&bHsqlOLuTZm21_1lMjmRg&j z9%@D&YOv&?X5^s;OCIWQpGzKUMjmREOCD-Q9%``Up=RWv21_1l-jmR=pn zp=RWv21_1lMjmSL%a^(7O4ot}?(jS(-D~)c^88#mXu&k+2TT23HoE(E5iRdn`fZwg z<6Y%CrL)qsE5($vPRv4sUlms#TQv)vDOyr_SF*^DN3r6Xtu$ z2@k(b{|zsvT(x|5I$x}Ua^)vE=*El>lzU&xMc3C=RNnh651r~>N%=wE{8aRe<2ODp zNLepBe(jrPRKHC+t+QQz-?)p@|7k!6D)D9pEx)(69Sx6{UU?k1p&eyh{a@F&raSxJ z((;Nww4^kP9d{bmoL;-=_`t9I=$)kbwN9ob-6>u-C;yDSJt=!e#}5znqS2j6>wLPV z51r`Z#(SYvKiZWmTFd{q_%&skUPgIv$^q2Eb*xmWKeb!o{DCqjY;z)GVH=B#k!_4J zcDAw0oUqM_%oW>Q$sDrHq0BAY+{#{J+e@+*Y-=HF#I{DVc5G`WYs$8!ves;CEqj1% z56IqN+Z(cH*!GOj?JcHi|);)dy7ua zrjv`V&Zeu24$r2;i=NM>=ZpT&rvHmwz-AYS{>i3)icZL;6N;`Vj>tZ`Z$*b>(;-E- zWYaB0=Va44MHgk$MMXzt(@{ltWz$_nr)AS=Mb~B1bw!6~)8R$8XVdLPPiE7TMSo_~ zpGB``)2l__X4AJt4`55&MPBei6Hd&8`u9ht1v*JBZB=l9&y$m<@@Y zAd8)lmEKi?xs#46+!EZ(D67i_MUj4YHUGiRB=R<&YQ;vKSAE{UD3|keCp% zm=K8-A&V7}coMRB5{WY*i!+h<6SDXd-1A^@DPW69kXQw>SOtkIAd4%IcmuL{1BpW* zi$jq31hV)9iCZ9xTab7LvUmoGb0CXzkhlo4xCn`tAd8of7!0x)42jJki_MVu3bObL ziMt?+yO4McvUm)M(;$n}koXO<_zj6y@ho0N;#kPySR@XFEDl8CL&)MoByNN(Zbafq z$l^&P&cw4g6Nx|ZEdE5|Qap=Gk$4r);#DM$#j`jTiEr^NzD43*Jd1mgco@&(VI)q* zvp5-vpYbeyM&fEbi>r}%8_(ixCO@u1eK$IP^-r^^(X?8(Ri97Rx;iyUcU_sP*PsV) zTvq=5cnvD>+b-pu7eAqxf%}y2&8$gLt(_e)KVdD()c3HKXUTWz9!zgOWWil z+20Y5yYukmr^Ty@4|}Oq@~4?=h?~9QC0nijk+|V=`N?1IjQ9+DD3QGVp$N+z+)3QQ z4gJd<+{s?o9z`s7a3^sGH`3(}?j-Ku29`UxlemK$Snl9X;tpKJFy$ z;|7-dxRbb#8(8k+PU1dpV65{?JVGq-LK649BOPn?5|0pL4PW9BVyx{;JVJ~$e~Cwk zu@@lm2r>2uBpxBg-U04;2T$z-h z?ViNl?!a=ldlGlM1Iyj+N!;xYEO)ynako3L-0hyk-R{70w|f$Iy93MJ?n&J34lH-O zCvmqsu-xsQ#NF<|a<_XDce?}2-R?=;?G7w=yC-qCJFwjCp2Xemz;d^H5_h`;%iZot z-0jZvWra!H?G7w=yC-qCJFwjCp2Xemz_SkfGQZxP7vux?t+F8hqf1s0cdor_a?XC| z5;whU=VZ0V&mw*|+$nkHsJ_HszPMwub+6Nimn8- zBbIwAlNHbTmHg%Y%H$*Eej=88Et3oG`<__tyG%B@HhK@3+=H3?@!8LrF86ZgkJ+I< z`N$ob`A;>hLo9b|<~OWRk67;9%n#>g6U$wk`P;9_A^x^_MgF5-=Mu}^o%!caj`+x( zp80(qkFebJng7L%2+O^J`Q1<2hxBrvVE%UhtV%5R73MFVQ;}HiG0e|>HmZx&-F8G3Y?=kc9`~2er;(j08oqzt(tBCW?xGVp}(_bf^JY#1YLz3SNR$sco1Ctk5|aPqiaP9xrb(U4^OYQ2ch+3kYlL7jULubMY3`TaAe z5-%J-B6;hyQ;4s)Y*cdJyP|cK8}1sN{Haca`@B3VS?!M`a zwU-eebnHdRM<-rIyz{x^lHYG1t+7;*IJe2+(HcniNf#&Gn%=t?PDu7@UP$`l!Q+!T zUq)*h_Yc1)xoAR!@40$ha_twhNpsHRvB_13M!5T-W0K8Izn$raHZ4frG4wX#>O)2+ zZys_h@mITzPQKbNT4y_JhtbI^yF_a*&vhQ1{IuOn(#YCNMjly{NxC%|SwBg-^%GfF zNxF3vS#L?Y^%hx&NxF3yS)WO|^%+^WNxF3#SODA_3+M0OOztYKzJG3F*^Ml)yHyziU`0@Znddcgc^^ zt52Pl{`8QD{>Cyn&oUNV{_gay}vL z&L_yZg|s`jAmb4a^$4s!k>?an{Qxrnqo7a`{*((b&3w7ayME6RK+NoCjP-UmXU2NFn@eN8 z-OaJF-tOk!SZ{Z8a+$-Y-5g%#_Gve_mpOmh&G{v!NV}Lq;)1k`3nX4hyLdt3h_s6% zB)&+y_(I~2w2M0=9!a}+MCQP0HwTuvaoWv|W&W9V^G}(Vrro^s*=2=kH(!-`Y&tWK z9b1@o^IMtsrro?(=EG?>AC`G?+Rc+?{+xF6XPH;0-Mm`n+i5r7mU(#E&BJAWo_6!| zI>T}k%XhtP(IJhdmH>CV;*Lch?Kg$^)8n69)Fyip@fp{xS+w`zR}fb%sGS;r>1D*n zJbPqnV%DX^4JH+&9)IW(;(s;0Db?t~i-}jQT$Flv`v|}O`OB$eZ=Znllqol5(+z#f z@JSi|DN}CB$dfX1ri}b4Td&ah6v7S~a>t3PeOc+$-4iJ$zX?cy#!-9SA2;8u$# zwz-M;rH2n&++g6%#N8i0aPc7nXA&Phq`~4(@@^r1^uT==fA>;^$F!-s_@3som_F&} z@{7IWBi#JFH7S>V*R*$1j($d^|4TVO!!9XFIsOwbo}Y5%w!VB;%E@!v4>M9u&RuIw zO*#2@&z_QU^+I~(XJ=3b(6>ML8e;I-Gj}>M_z(U0YGRao#?O%tK%NCnBMdp`UUL;` zApd6vM;P_$xmScyUzZL&IC|*E@qykPf9TVd3q3n|pnoSP?Be7%_DWf7Y?m^&OBvgx zjO|j!b}3`Kl(AjP*e+#kmom0X8QZ0d?NY{eDPy~ov0cj8E@f<&GPYy7)}8dK6Y^1A zk-zGY<*IHekLsLqsx2tL+KBa1+p)eb-Pn%$aeR#Js83g}u^sjAX_&Fi_he_a;1)WP9E{GJSV5rG0({_KAGq0g>>h)pm+WZKF-g<-}yhvb?pN3 zxb^}$T|0vOu6?0iuHB)&E**Ms^w5vv1HC!^(5EXGdUoN*bDyYYzO~z zwu65<+rdAb?ckrzcJNPUJNT!w9sJYT4*uzE2mf@ogMT{Pp`AM0!9Sht(5{{B;GfQR z=m(tb;GfQRDPueMr?VZ?UAr^3BOll9jO|#iYj?(Wl+(34V>{N%wL4=w>cP<)+fi?h zzp)+l?Bp@Fqg|Z*)?PBUCUneA7+h-1J@?kBi^twL2K{{M=>hLA?$_a5;(2rSDOvr@ zNyMuMCQE*K`B37WC!A8UUAH}m*X%f`s?Gd?6V0a7oAa*Li!Eq z2_D$D2?%K7a$2)uHBYn*2iIU|X1olJ9gPy2^LD5*_9{9g1%Aoo+?vc~0kI zi#)Xj?B(W531g##u~EXggQDKq3+H`(227VbmeRW z9XcC9x6Ve;xw8>$k+D&aw(sW+`~30}@!Le7^XujBQF0;i>2DsBzx^Gj691ArG{4RD zEr@@vdU^hX_m?N`@ay#a&a>yEy(IP_gyNEutCj4e{e7Aa$kl(9w1*dk?YkutVO8C#@`EmFo7DPs$yJ6nL>*#dl= zEx_N|0_8eeKptlc$mwhW`JF9LFJ}wX*VzJkaJGPcoGqX?XA9`l*#dfYwt)VfEfOsz zys-Gkx=}1y?}*8ZudP#90$)Akgv%B;pI$`#{^aqCw|ikO@lFSfSUl;4V&XjyJbUrd zDR&SL9CGU7gLa%p{Nu5m7ME)g;Wg8PMK4_+VG~Pk$rv{7lcOTsS~#QSKgxM zqxG2&o3F~tF1nI!`XlR+|10W2@^A6Q)1JSnT@4gy|0xraw%W z{xD(sL+IJ{hY8ysid_~vyNJCOJ9~*87dtzed3(adSqaSZUF>P%tb~cP5+=?{m^dq8 z;;e*;vl1rGN|-n+VdAWWiL(+W&Ptd#D`DcSgo(2fCeBKjIE(2n#x!vj`M8+W#91uY z#jqyMqMR<~HE|Z}wWVTYvmS+d#cPQ&zKb7jt!s%XI}b59W#=jun>j|xVmlA9*wPqm z*Vyg4cS2~~cme(yY{wLfEsenmGuEUmw&R7t&_iZSF}PG6&77*#T0t4F&!T&%0OI5%bDT&%;mI5%bD+?0uPQzp($nK&0ZcX2Lk;o@BQfLlj`54$-J z_Ey|n2zxGWj)c7!H+RAwjhjyqa;9^YpiHkkqKQ1PPU%6N{Wnx&n$AL9uHwTFKq@w-At!_`s%(3IWjA;KiW%i-C zx8nBx%sv$NV%%P#*@xoZjY~KCP~7Wre9S%+_lDdaqS=SyUXt5GwEIwIKDN>A-Ns)Q zn?507`ig|%A)_l9)TN|x8z#KUo{`FbKQg)#}j6JPndB(Vdev{<9}LL zDK%%_O!ErF{%&7jqvsW7PLi)=sYZP{`IXZmlg#*0@{OX1G zU3Grgw$?q~1&Q4YSKi+PH2zadb}THY(KcK>IorR#|L1e$JCy(Xr&fGwj{F`9o&U+r zH_efJf#mmVy?f#u;TH&B|FtInp56Sw$wD{IzoV$}6(~p3>!BQ_&qg`QCmZD`|7?6~ zx!L$#<;g)ll`{wYRQ?>4lUsCkuGGt=2U0IbA4t7&lus!2%2EEI)XS9{O1+#sq0}o| z*(!f1^{O{B|LFSEKzzUM!M&xpAS)#%meZ=2DLn)=bjz4&!*4jn|^boTwd)^DU0;xM}mQEon#i zCF}*iiE*rl*atSR4`7@D$LJH|&8>$q1^2rCD{R_heqr#~bsXDgHodj*yo0OBoPAt4 zf83A_&)JrmdEto^Yiai3OmbE=*F7Uh{e^q!oT z=I(9r9LT0L#G1Dd>B^H>%OX}8h*dUXm6=%ULacQp*18j`PKZ@k#HvHevrf0LTI9QX ze6b|xIbk4u`kQhsL;T@aq~SMUeB9auuv?n|)|i=dJ&mP_-P#0bqjNQ4 z{3bHFbgoSxMPq(P!?g*dyR`{mw>AOn)+T`6+61s$n*es@0BJhwsr1BdZ2~lIZ30-! z4T0qYd5GQG1QK89X^oO4JcvIHU% z`Tx@Un|yA%w;(vB%M9k7w0A);;N8)@XQ_9y+=H#()KH5y2I(NkLVMS7`IAa$dhAKv+5`srmQ%sc(Ln(3b( zX~DejSFG+maz=mBi_X%bJJNst@Es+W6fU7`u!EDoV#kk@7vA2Sd7*n(U+CV+x!~G@ zWam>JW!`?Na(>^(+K|3_`Mv!go3?a%@SGl?d&mj9yxsU2@4e-Fkbd6>8vADy)g}Ft z4}Rz+?%dhw!Gj)Pi^D%U)vMj)cIG{Pzz+UVYkpw4LyC{|Uw!=>(zJW$LT}H#uO&Xh zpW^inCPsRwQNy25lp;OqhkB|X`tU>WZ}QGuZ$SAYNss!Wo}f8@zXAR=)1IYI3Z0KO zp}y+FSCJQWLfw$w>AQpch0|^(z2;4uvI5Y^ANe3J>;NAI-u3Cnyp|&y(w~(N^L|*T zw_j4>I_8DVVSCUEUk~z_ylL>yy|S_Yb@MX=lncATUrkx$3HykhLZqL4*CMaL|B-oN zEBG$*svRM32%Cs)$OkrokAg<+4q4agBJO@Xm_la zwo~R^d(9oevd?QXFKi;VA-%S1(!V+Rkf46eyC@re2OY|VO~f|LtNkQ-BF)(gx)&QT zulB3N(iYJ7k{-H;-Ju82I(uoqO8V!2>K9(q>nPG|KTP^a_ic!^UnR}Nrw<6zb89eN z`(EO{r-Z>6k*F*0F|I#~`+uO&RNDZ2|KU@^R}LD7UP}dRec@)p}un zf@9^jFxHD6WsZkWv?t+k^c~v~b1CTJ?=WYBoMqkaP{x*QcTsuU<{TS(T=w({IjE!b z)jq}_U>OU1j0eDy=Aj=427SvF$Kn+d-r|wh?~vslRddgC*t`-52@FF)Ct6^Dpr^?<=4){IZxd@r%KqCxNzZT zb4DE1jQEX5s~1ixtU~<3h?a$Ydaq)+cii8hu*koZc=eUX7e3SMq1li@aXnzA$p+TE z#L6=V=~@=C%0R5L5v$C^S{GuiBeB+DRC zxOfCu$5YbiIP1ZtE^b0z7w>@H#U@DCah&uzz7xB63N$X>L0%J^V2&^Ij!#MNVkpp< zc*J+{4$@uR0iG`2ft)6W@?AUvdKY(q-o-nSuV&&Y-^Dwicd-fRb>0Pk_jEo+?BXfV zxOfM7O>E-1I171Q45jkBc*J+{4$^f#N&UNc2YF2l<-2$U^g3T9z0PBuoGza7UAzN& z6PsX8&3H%kz&H!o#Z#!4i+7OM#VMfC`8mrnF_b@D;~mhu*aX191)Ogcu6xF5WSD5u3QO5L2LE;+zY45$|H|4(wtp!-siIJmShl%z{2G z!^g!|$m`-A{BB|sR~F`+zKcP?$HY@;FZ5l|xVQs6UAzN&6GJ(>lc$S2K=0xm(7V_Q z=`P*@e-n?OOvXE)cX1Z5i>Hv+#XHDrViVCr6lWnF_K|!6@|t*xu_^i&&C9q0JYBp4 zdJ{vrcFKCWxC8Vq-T}Rft&r~G9q@Ot3DRA>qx=K(S->uy0*#Azkk`Z}u3eMf#ZaIz z@d)(Hcn9e&?f_30@1QIbL%DvH^>Q%?=v}-6dJ|8%ewFktP654(cR=srEMON;fyTu< zNO!Rnu#1~8X2D+3C&rso52F7Ne~&*pqY!=%4Bv&_fZ>;s%|Z77eF*9BC;S1!hwvLP zXpsjPJirSWyxU(tG6xuclAd(w7%PCIG9MrYAM_1K2Y>V{z$jCGBSx8$hZtp|uLX^k zNql^zn~O|(($J$HaeO$ID1XnCE5B#tK^t{)`bK`g#s96%MPB(sx~nhSG}5CoGx}j$ zL^|pe>5lbczZUU%0BeQd2VHu`F4P&)cf9M#IT7u)Yr7rqYM)cqwp-lk_P@k-woj8d zlKmUjIZ5$QLozdaxdYbgThkody^&D!!x7IHWV~ zK|0DnI_Tw#bl~ISaPZeMSgx)oAxo%vD5onU;vMa2fXJldyej!aM#Bf^Rhf=DnR0!U z0Ukn&^QunH%zBXU_M>wepc;pCS6`lQMXHnuKKLUaqc@(DMLN<@2C#g5&BL`Vl!3&E z_c%wB)vNaWA}KS(Z_)-g-5RNA{O4cCib5WN3l^PR;J~LJt{b1~4I&_IY+@#VK%k9`65WwOqkZPJs5 z-ZOkW!{0OIdPW}UQ!{dUKUK_&F_Hs^#Ck1#GsM9 z0qPz|UZX?L=+-kjmvS<;kg+3UBROY~vE6_42hjmOzw;9$R;%+hW!T=&^=kcN8SyU3 znVwC5rrac^U)gy@DVj;We_~y3Y4pQ->ATl%NIf*%@7ML_-SN(&rEWd^+UI}l*|Kcj z6Z+gmnlrnWc(z=d_rRRDNYneCA>R7(HXXl~G^4L9POdMnp-J0vO?uLl6&UOp8k;vT z>80`-87xhyyrwR;tia|qIth%-fz4}lyWYIU2iBX{_(ovMwRvq>mfq6XboipQ0rt-^ z{yXSl-Q3U23Cm=zj=tOZ#Fm#(n>?*?JS3Ha0XMq;d)Y0SkqLt_E?jq8o1L0qD-gRYq|=Hhy^ z#u~nfxv>9%^~ORi53v~HBBpCBLwb#I$OmPB2Jw)_L|m)Wn2Yjg3`IFLw#vjq$gAs( zAu!@UL+@fP@WFZ`X;3FqF3Uh(=)lP7%7FY>Z!7|hD+Aw1H+o@(tdF`LV{(9SL5=XvpL^SCg6o;O-Y6c^$CB3uRY0=G_y zZ~PzWx+X-7^+&gkh&gd|jsjHc#%oRII-=4O+qEU-&o-*%y7rn`M?^Vp9TDZYb;S62 z-uQW5cfMWDlm_N3I-XmMpXU{wxU=PQHaLEsH-4Tsex6tM9ncoc`FZ!A1UxSgxO3^U zF3xjaSf>ZQJ68`JKhGPT$HZ74KhGQO_qw@|%xy4#;T#EjqHgXa-ViAda8s#q4U`y5?VpAqPJ3KFQxf z4|3)JbFvV!Vvg?Ctu^Ljy8MJ#kXU0xVvQY%^><>8T{z#@n1&eTMCU`xKGu=gG;=1^ zVzr5{^~E|paaqNz(RtpokAb4tc+1(*J^Q+?#jIEKuO@fHl)b$oKg7RVL!TYX5ZPn> zdXV#2wx7)G?`glmeouI0_5#;#r2{sH~J zoXv9W3u|2*7wmYUd_vUMjxToHk)JZ-k;+MWm7my-YZk|L{Cn9Eeh_`u-!>hE^W&I) zo6;5Av)VMqRK&I$Ta6sj)$g@nC)#;K@YG>-)8{@rmh>Bf-@dVrzwg0#2S8TV2I5fY zIZg@vpJI_Y6#0Gd-w-S^Cq;hJZwP+lf^Pnc)ylKJ%XV+&&-WS8gwK`>c-i_C}lP!O~gCifAr}ch+9qd{2^a8BF-7w z)j#&$NdHY*5A-i-`UGuVa@I)y(O3Hs?>%X(-*xN|yuTr9m$75~AB$eYyDPHlcO2$- zS$HLFJt^l*e_7>MiQ8UuoZoEUsv&4B#{ai+nW+=43+t|RB-Xl952_RDL3PEts}6}( zx735`oLFr^tTrN6+YzfxiS2xB;r-qDZX9S*b?XCfbuvfog0g9QA=Y+8tnG_f+a0mC zM`CTK#M*v|wXOXQYkQ2+qjpNXxypsEqtCWGrnnj+{)jO&5bGiGgIEu-9{$cgkXg5h z*RjQs?Rt@2N3!cnx*o;(4En(>wT>O{K}0c#m?^V%XV>)pF1E9CREzEW?c}#l@@Hr7 z!g<;mc_;dB)vpxI-=f&U_7j=xrIQ;wPSYi{iZ@3QIHFLX`u61V_ zcI{nt#dOsnvFg@?G+K9JYYU6Zy4)r2e1iCkvTXyxhJvTvTrzK`wv-{)|U(kFZysM z@#(LQ4o`W#HnHdpdnh3^vLP6B(dX|x_dpF|`C~iAJ`npr>;th6#6A%FKmPA`)1=W8=DO{}-r z2Vx(HeIWLM*axf+jPu=^eA&-+`Mem%?cdCiwwMgC{rewe@i~GG!_ZYUFVT5B=PNp& zcXOA`7I!#XK(=*w%gG>fxy*jVreNsI&3i4DI$@8Ddeb?o(6YH|vHWehRvs&-m48EYVrfJ+oNbW437>V?>PloT(`WZ=SyGqGdX&^L^Q@oL z9ll9Di%$OQGZm;KtIB`=9825984TvJ*y>7UW;;@uU7JEa=2e-A#lDΜO>E8}F}0 zeu$TpK9;{NSIZ&2mD9>^%d*(oDE5c{9e|E2K`Z8iG* z`Pe1xDRk5^cAAKF68p~|`2c?VGBe-)a|~_%o}Y|a*b`*?D~ov-%9MWZcW3>Op&Gj+sz){a=u;1S#B4K3F5d!*5GeZ+X@E&lWlIAXoOj~MU5)%)_~ z|GdAC>A2%g@43^v^&Y_c#X`^`53t_f$NS51x1QYJm*dLAU3$Ps$2-~_J?_#21|PlW zj{MEt;*iIW_&gBc9dE!WQ}4OU+zp6yy}yq%dVimzFLg(`;g9?KC_|K%k%#Y+15cD` z#<-9Sg6ab*JQ{e4W2ZMW{; z`M-yWPHz3^Oj2ff@E zPno6OxG$bKN_&kMv{HBCwzZl`tQp;b{?ZEz7Tr?xQzlt@kc_qpMPRjc(VQ*WOca zbQsvY#@2zcMPT!;kKWQ)K4>%2CjIEUEb#B=Zc$kqlAgu+jfR zK7>9 z=karir}Uc?;179`hTniei#)*K0bao1eb*OX&IU%AlAd(wLhm_x;X@2Q!k-xY<&PL; z%5TIdQ_3JlnNkKZ%9JvQ$G+LT$fPF?y=VA%hQDXZ^^828k<&BsdkuFOl&keZx~nhf z1FaYM5Ti_^HAi2gG~w@G4@ zbLa8(iKq12HN+qIAPv6(gO+&&g9msa9lWKyIlw4i(mj_h^u(ZtjT|50?*oIs{1LOv zhDljum+*XbE@k_KfOyLisNu$Qwhu(L1lilRNkdX10q-#ckq zdgOZ*iPNo54))JJBy6-tQ@`k{7Qyz*)&!sl&Ym9}U9LXUM|Qp^Skm@srk~gBo#2{g z6`8)G!H>Zn6(=)&x86I3MV(dz;B#+Yjqs5psxZA-x2oaFCoW<7xjhaD>-DQY2mGr) zwpW<@&I4)CxAyZu?;#!ZlAd(w!k_8jFMK?tgOA9=bjTy+G9BfL{7i@ZBBu{}$SL*p z!5{UNdNCdK5}hy|IuSiE9eOb7$>V3`Gkwg68;cAd&(M3OT+i_LjGUg4$20Zvjr_jR zgKz5V&mS^3SM}x_{eV7Dy&>J{(>HbjAE$rc*wHig@{QdgXQ+DfjGv%hOc%X*#+Q=D ze=w(&&xVYLhy z-!pcRG9!D5F0sc*dW*r=(8qREJwvC^&DLf|$W+$$LK)GA_sBcHMLR9Cc8BuHy4`7| z{~ocz_ph#2ckY?|+x{Y?m(d#Gn^G z#NZ?Rb3gxcP^kcs#X;waU8}=hegSG$K`#ww>xsNB1yH-ep`!&oue}Fp%BRSdxKQ?Vi zn(F2E);$&O3k0~g5H#)HxiG+Q@ITPXS~vF>u!n%(KoimO4iA=T_8lZ&8`7Xm$O=A? z-Rx6@kQIC&JL(J?=s@-!+`b0ySp^Mr057!d!L}37;5Xsp89tePAJJXX@ez4Qqw;Y7 z1-istMou2l9ciFTyH6zbA`R*#`tebg>c{QlKtH5`e&jdOsGfbu3|-1^q=7DRH%?S9 z+KV*MrIbM$=u%`QjoO_wYIo8=m$-{nbx>-5N_0mW_>a_&G|;8ULO!Zj(f}Ji*bgEN z_Ja(cq>%^vM@}Bz1qB^Km!@8&_P1(E)LO%if-d3f zpn)z;zv02xqk6UR&}KjbU7G#}b|(#VY5K8J`-y17-~(Mkhv+k-?-<8=h<#x5`oOxj zRo1aU9D|ol3=V&YZO8SQztQ>$`!TKyMD00RGm3Gnhu8=HmwaHH|LKG-#m?pzA8~wf zpJS@=J%|%$cPPHD;xyv7K0LJe(+U3~{`{(X#SeQGB+ob>-}pZ;eg_>e@*zJk_<=7l z%8ANjdVQBJ^z|LR@Tu?k2>%9-zkD}v<;w33oIH}Rfs<4CHE{AvISov`kS=T0<9wwj zRzAeaU-GbCD3@5}Ayzqw!4KtuzIoHem80@9^>y^n1F`CdSoKDX`k|iSgL+FTvm7YJjHF&I{yR|@FTW1V|HFviLk8igIFO0CaKpNz8Yw+Ob#&*>uX|M<2 z(y^B6=!FJn<4A+O1jk>#Gi(1?hemnehjmIPr|`=>%Y^#lcYHLR@vPDlD<9G+e_}1y z<>y&F@KHILuJRK{dl*r9T3@EC9vq*{-izvu>8Kyd1AnbIG4z4*kPbbeJYZ`ti`SbmCaCra3Iwi_3|d~c^>*aS9Qa!to#zv*ssf$#0ws`$uqlZc16 zJ+S!Yd!Hpf?YWx8GpFq!dE|ZI@{Ruk<9E;jBOmeugCF<;qm-yTrq_4rLSNs}3!nOq zkMM8c_{(<#SFZftz{w-|8aO$HUjrw=)1D}TwudZAomm4{g6 zB$jd@KXJ8vvMWdBW$Nqbp$B5s53%Zv81+LvQ7-C@@>EXfpBQ>Vc}TbRx@PWek}s;` z>&<617y-_znOleakGpetgZp1RmKfjoKX~GI&;cVK@&kh( z_yVJps63|6b?HJs*U<}~V#i1L7d!s)UF^!0-;13*lCRjwDg26^{8COat0m=X`drAM z^u)?X=*ET0pIFN!R(Xh3PGTts@)Hlg;i9Qgd71h;dgy^z^+T+BBS!sD9%MkhQJ%^P z{Zmfp3FRSuoxNx?KdNKdj|-|xmbc~lmdtojW@ABgA3@}s7?&{ipsqST63c%#`#3JP zjBO{1-IQ_sud&@Ye`l|-0el2D?7jH*2E8YrQ6Ko@b~iP+q4L|rbN0Ea!OmWe(2es) zH!5f_^xPAP@s0l@9lwJP82OMN82rE&7^OtzF@3H}7y7x5UicI{KEl7)@t5ynSFZeC z?BtPr#ZFG)SM21Ma*9zNWr)(z=b&DoCssZ}$9jQ3v6f4$@(`<>#8M9ACw_k9#Z#m5 zGWB)z&;zmRhZyxheY9NYlNj|zc`7ILPdT9{l!x?n_KNBz`@=avWj&XcJB6{YOdD>A zJ~O&oxa|8(xlGwh4z9jEspKDY5nIGwxhh;Xt}h9viHyEF7GYppVIF5 zjB#1_C(&KrTdqIR=gY)mI7bxQZd2A({u~w)}2^&Lae$XRvl8Fb-Io8i+`hY zn$dFs|LGhwXzUSC+Sts#CHEt?LztCXOMS8Yzi8juXX2?aUK_Eap41aW&r23L37O9 zlfv$|EX|x@$C+Nx;LNU^HTG~07w2(t78mIscFYcIm%Eif zXMEjR>H5nT1Q%VAO`Z?bs2tw6_bbeMd9CWaa_~YELJAd8jr<;Nwa?T+Q&NN5o znOlax^!_;Lyt;x9nQRB&=ahMN9_hP3*gE*%=>=D>fR$~^d~*eaJ#ecpFey@$t8tLC>!kHkTM>BE4|X4`BZORHFowOt$f{g~HsWJCJ1@?qW&>-6?Z zDqP3BS}vZ02!${EMU$83^mDIl?0?<-%mC%WZtz!A7J0%xICqcqv+r8u75G0gFMJl~ z^pRKX7(!;)1ZVR>51ZipK4{eLkVSr@pO9YdNdB-1&hmqg+MV=I?QxG+{h?Dyk7pjx zR>5EG$g`LFR?6(7!-V zZFel!J^uiD*a3YCXtbS@UfVV4wcU}w>+?`AZKtGv_UhMy6Tk0FdTrOF*LKHxX*;EC zYp=N@SoV2s=7ml0tOMlHc1`*>Cm#~juXz_`!|$L&xv&YIhk(p@{sFdDd+|5$f$s5~ z1ZcEhC6=~;zL)gcPqHk~I(uoqO8V!2>K9(q>nPG|KTLY*it#=!`K*gS%X+Mj&Ur^;u#S~%hh;U^%X8N9j_u6e$~H6Biymc;hY#P? zn88t6+0WTxJ7&(&WzOmSw{tewtgPEz?;n-v^j8RXD!X%ecwFdX0!WbPp;C5c>d5s>a`z*cifNjS5>SqXUea9Zrjg!>gG9B!nRB= zT=?0X5l1y6e&f;Vg_8=a5PvYDWnrJ*t61(G_jf2P@-HP`edY0m&op~zHh3zo2dp&N zz?zp>dFCKp%OX}8h*dUXm6=%ULacQp*18j`PKZ@kELU|%yfOM0JNPb60d_G6?1lM= z&LMplkAOzUQx7yc&U&z^i<^+{;vLYt*aYc1j+0);cVZV$fyTu<$ZKK~%<(aQAiayB zK!dp+=6uNO;vJ;BxC7~!Gh*%tIZX`ZyLbfjF75!mi+3Vl&BRl_i+4cpViVBoyo>yG zK1S@~DbToh2YF3w!e?0#XQ3`7Ry-z0Oxjuk%@H#3pMaK|tf;9i+J!3h6H1F?sonww8sM0{s%_S;z}JVD1j=Vk^Ukc}+ax z%0@H#8A%eNIx z^YR@G;OXKW(3=>_wNuv1#T}q`@eb%+Y=v|e?|{FHO_1*59pxXO&jNPw6lh$$gS;j- z;q&C^vq0}+DA1UA1bSw?gLD^nfG1)g{D!*Zn)(7SjC^d_Ei{VM5QoC10m z?||OLS->uy0*#AzknUnDU>7%G%!0k5PmDLS9zv&C(Q}NcjLoNq){oX_EDPNp`mcJq zEB(raz?E9}|I-XC#udl`!nSH=4yGB0%Ve3>s{ z9XQ?}5#Mm}g3QeVGq-npG4cLLv@aQ=9l3Y`{$pa0cz;Cqv*P`cwv1{1o3jw{{z> zZmzTFSqrDn%=6=VHiPLh<@?h!E%E+Hyg%~4dIm}2r+9y)unOYJcz;CBgJGR8-XA%g zYw+>@2+x?s`yw8RKO)b(6k;DE zetsmnhez63{QQV0A%1=&etyKAr^0%&IiuyCBfyy>_uK(u7FmPlIT;`Hc*X+fnULHqUZ4?rih;(iJrla_ebLWk@)$M z=o$QYe}tjY|H88>yq}oo@loaNd(`*BDbf4S2j&)fm5&?DIbQ1~UwacLpGJK1Nj3e# zhmMTqey8R6&ko$5_^Q*o_}`pYk@$<-`}_ay@FJhlZF}Qz|LRKPi93HV#;?#d&37PJ zyjPu3e&3x>AVSM=d9;zEBX@2Euu#P$y3pP%jI zce|mw51m~0U~~VgqYfeN(4(6F#H`N5-+cS7m;A9W@!N}T^7eaU2yyY$THeLqMDJ6w zXVQi)Y37gEFF~3%^D6m=zH@yZ(n*Qal0DRy@f3ud3;xxRl{$3{$F@oH_q;WzDx zo9yv}_v@Fvi2I#+hxhMm1`)Sf+1Q)aGt!mx`Pj2%y2YEqb92dN?PYn|bXyl&M_YHR z6I-v1)xRxQ*Gs84`;I~3nORS^=ePAeEu^>Sy>)Mt{%@b@6Ptw2`nFt~Zs{!_%ior3 z<*{;F`PbEJUHP`m7(1)P`iV60chLi+UH9H9Z95#N?D+(3J8XOQ-AdYaT$@B2C)Tz@ zZ1+&?T-ugv(=EN_BZ6l5+j6ZuR!%Fwt=God$I520_OYy^_OZm;#}aEFORRk?vG&`) z!<)iW`a?e3jrwg0A1j;XY13_8Y#nXgtxl{wn@j&XSD_Adu0pJH6=I#M5bIopSm!Fl zI#;33>s*Cc=PI11>0E{LG@Yw(Y|?qu@9XSBAJyV~me`2)@vDzy{t57=iq)}fbR$nDnUnN#wC01W0 zR$rxT>Z`=+tMn7~Rn}2`)r0(29&M-OsqK_l+bOZOQ(|qW#M(}YwVe`o>NGnOdv0xQ zv+DB8io}O}=)tyG+m>w`w{73{3AV4WeTeN_Y@cKMBHKq<{aAT61xNirMX>=sm>WlU z+S-Ef%_dp&lhc139^TSr4DtHP`p@(mHzsUsdyVNMtCfu&GCt3KK*(XQ8MU6R zK@VA3_g?sMvchrEJhs9yRns^9E1JjdTgeMLOpfNd&lcPfd^|N;zwKD_%V79E(R_8< zoV~-lCmhXjYUd|fhLzj4AhtYhx}~>#EPq?BmB;e5xbdkcreB*I$^4IRdIXg}9!VLV zJ@Jv?#8&4JAF}_B;m~rY5YHdgAbdV(MSNY&cHz{zb%|eZ-7~zj$}jZcWBv2PD_^>o zxW|kO!&#>%iHpA(8@~DDE%~tDp?L-2a|iAj{1*RJ@?6z#V7PkZt*q#@U(io(SH>;th6#6A%FKt)16w~Yz!y>L0#6FwU`Hthbzc*Z6z znvM*||NCslBiDX7ApFNmONn>erEA#uqzd%C6?MI^)_}&uXMVJAxN>21Zv2|j-v@V} z)|=@MwJr|oJ~fDV(ws)YtplR7@pj$S%4yRrz2#&1+j6ZuR!%Fwt(UE@)q~ZK)ti;G z{heoq!(WN?dCu5jVV{GppgzyNY)ts=m#e7H8z+wq@A+^L^%-6|GTiU6zSQBVw+##{ z_Kfb|8q~5|c>L(-O#V*K`Qd|;8&X$&Yt#u>eBF-NmTS{3z2#&1+j6ZuR!%Gbx_ZU^ zz_!s3Y>FMTvh4W>i?wa~(2=%HVr`qm+BS)`Z4ztSB-Xacwxey6SlcGsk+w~?BW;^( zN7^=twT*<3$KtI`PHn%eyT#g;nXYY_SlcpnqHUR2+cNc|ZJGMfwoIL9TmD1+ly$kX z7URplusk2d=lyZ7BIU<9COPv#EN4YfSJqd~iuiIygc#rWKk~}QSGp|ZbLXJIPtJmn z#`>o%*QQ%~%g6G!)1-HV=J+at(>>$*h(z& zX66#MT$^s`Eg#F@mTTp)a$5P<)hiye;MdM?VjTNJ>;th6#6A%FKF;&k}xxkD_$7gOI5l&q>gmoWXYe3j%@-pH}Yn&W5dUj{(D%mI* z9#znU_?4`E!uw?XS?dlRp2I5)WUhv*E$^l=S?Plrb~+LC2$8|^9X7uRP; z@g?8*t#AC+H-76Izx9pZ`o?cPA8#ny3sde~g)OHXJM-Z(192frZ`P7SwzINAd}^wV>~?bepCudB5C zsPM{KrxMqhJvKb+r*7;IKOH$HTvO`}_91O<85Z7h(&g+o_B!IMaCnE6#8v`Ltow}JnfaJe?I8`FM=)y_hI_AeP;))XGZ<`iPLg|Ik!c9$mvU( z&vomme|MR!{HT+A9(>Bkg7Bpgm8j=6UtbVjzS|VyHq-ithfRNx_=_1`!(h}-wAZHQ zU3AY?nP<{B1UotZL%FoI%1o>>6RXU$uh#u{SnK{@@ln4ePxV{!QNJZtzooCL-_nQG zZ$0?G`Yo~gE%mH^ORRoNtbR+ZeoL%=OMFHDw(wixCt6I)V5^6%S$=!I!eZ^Cs6*|$ zs5kA?h_$a{-L(%S*1nNg`%Gf(ONq6QCEk){!4I6hVjTJHwxkE~CCq!B-(ueD{1)?G z=eL;m()V=UORV!=Vx9LA>%5m(=e@+Xy;y8%Y+lRLmSttoIXU_3T%9uO9G=+Lv8-*U zaa@3MG(IBMxQYF(##7X}##xk8<1b>3%UCas*N8QaBi8tiSmQoojR%RXp8qbgSvfU! zrmi#=rVcfBrfxTu=H>2V{3lv}Kt8>C4f7A*>q_$3>x(n}8mWI1hXYUW`*y7y!j6xf zc9=hTQZ!Gyee^#5qjfqlJ>2^XuUW5Xp4RmH+r1a>iRNj&YUg-ei++Dz-Oib<%v(|( z)CcpG==;yH_)q4YhZfs0p={4iP)7PP(3ULA*71+9=!NH0LF2I48s}svcUhku-I8U& z2CiNkg6-Ou`Z?ROwmbH9+U|(8-BEAa?ufPB5o^06)^H2<=Fc} zoBVLXh^Emv+^AOgdDZCNr7N!bCV0MSw5QgrK~eB)b~NX|XGnvf@q}p3|96pXYnIc- z8WwMDw%*u2$@;Lw1%bpf^f5U%j(2oN{$}29Ea%KaId{%oeXsV<0c@ddnOOUx5a||g&2n1#ZM|%Ltsbm?tlq3X zt)8v^tzE3WtbVLdT5M@-Udz*#Wo59kS($BJY#nXgtxl}2tbG^W|EjE=MC&9LZ^=E5 zEm;=)+toM5k=?f?J=nbly9Z(SChVSt-OI3h9Cq)+?uppF68j!|i!F`KYkAtTtPEB* zE3>VOt>e~aJK0C}<@^T65!pxf<@^S*?1TGqeuHC;?1TGqeuG%{!F@Tu!Ldp9!F@Tu z!7)qr!F@Tu;h}!A5AMtP4Pw~`_vQQs$3EEy_vQQsvFwBUa(;tY_Q5?lzd5m1gmklI7_P8Fwj^B(VUieI2dXL3piT8Rw%Nx16U_-DEnMd_+o__Ap=st>nrn&~5 z4;sbv#ht_8&7skK6j%4zF+AwqZcLxhs$tlqN-N@LTDK4HTeKhXqnGyzCtkLObzgDD zpz!9w^N8<1esnnE^Crabx%*CgS-T*>;>Vw^;y-Zi@x-gnJ5Vl(K9qRzlurI(pH?S6^nyPA zVNZO{x_H+N_V>DRHu0$Oqy2UlHz3~S*RlQ^pWT~>vYLD|+Q0OMTCB@sgNOKoPPv8H z+Nk&R$zH15un_dO-nqi-)&DHw-SaE@A5G{&{PW7j{soUDiBG${o!?<*9pblx?*1Kf zwj*BAzrVj{`{+3s%fD*#YrKbdzJN5Zu6W10y!9ExZ6@#OSF3m|@%O6__Q&sf5OJe6 z$NN|8v^#PBooD)mue?l|)7K93XHSaGhA+BN&LU0u7svT@!C3#XN*8fXckW>${p)u+ zn|gTY#{vF(1xtx9+pnwNqeTTDb!>W==O2H3W8xEk+1GD7rvvd_v%dE#bnQ+2`66J31_?b1MgOg+V7TFzl`QKrPrs+V(nSx^o6cJwpi;JLT_cY*8ZD1(q48= z*RJ*2HDJ3oEaLs?I`pb;cW2(mCiTj^$4=^%dB2_T!Mk(l1HwP^K0GNm^PW8Yoirk6 z=Dm8d_MCYy9eiZiwR!cSH%+GxD?PFDp>CBwv6f4$@(`<>#45j|5whRUO)QPgYkAtT ztPEB*E3>T&>Uc%}a_mcO-K|cnuB;BNZdD#%zSsM%LHzc=G*9@u)Yr~u?mzy(;Nv<` zKl%QgyMwC>qxU9G?e=T%{5w&by0US0_|Q3RY3uVBwh8lh$|0U~LXR*}ltp~c;pc}3 zKNj63)%S}F!(orMWS`LU*RkQPRi|=XJK%)TVdZz4upPB2KPX%@aX#@6gL{T&pYbzs zx!fbd3dht7q03tD=7i0EJe+u^S=)sNKGvPM@b&wGn_oYV_=IMOVAkRbiI1pSxn%gy z(R}9W!414abdP$$ne)6QXGYH^?r{E3Uis~Mk$%y6b^Wfd9YMU-JKS#^<`M_Zy8F$q z+n%`F$n*T>KQ5$fH%+|IZ*#Lp-08=${th*}^1hv)7mW6k+hu!@dG{v=`TuNROuTk- zFTcmgXl`@g^mhJDQ|tJkvDnTr^7i)9eHKM?s&~)t8B}>^B;STls_i^V_bC>~ie1gtzlUk-b)RxzDTe zLuAKpyKLtd?%jht=k1x}A5q+fcx9rkfAU$`#I>&M;SX+?MZ9DC^Zo1Q-Ag%h-@MRo zwfiB&NB=U`zvc5!7DML!Wq#H7$_5^AyNQGR{;4~NtM}~XKal++vDLq|Oa6=l{dRq$ zx!f~7s{1#t>Ewe?Fm|nX=)!28Kfn8<-aR`m52I- zUprf<{7m0=>xH|ABcHT&gic+1jN4#a`hfKx>sQv_tRF&uTdEEI2YWexMxRM6G?_li z_FcA5)4qrF$Y=VN-=3@5qT|A{rS$Ifbzg!KF}kv>XBIWNUVA!Ry|Tq;Rihuqut4w57&QX^lSBQ?P2X? z?WgjD5KQGH)^5j%$8j%le;;LF`u|zgdUdZr_A72P_@y z4}9fL;#GS`anXL2hsiuAYO{ZarCj=}mYYUxep~KmO;*c14WDr+i!>-pWFUqN`uk?p z$!~dTU0BASVNgoDf%gu*YY&B2#t;YE4}=g z?I4SzIr4+(-tJvaNhe=9TI1vQuTAF{kDzTH8Z#v5motF)*0Yuc%d<}=ek8qf`1(On z?6r7slW>tp8N+aA}LV#E*SHC|q@AL*l{m{vzX_Vb$fAvG0a% z|0;QQt`qIC9J9+QUjHwnb?&j<=6bW1Mtc$O&3w)KHMbk$~`mwa4MsxLZl^0f^>k3QkK zXQStzZ@i(p-|g{cp7jcsL=)f)SA_Z|9wnB zDLy*{5uclK5`M#l5ufp|p5WKn{T0&xa@v{xziyBCblL9$|Ce47pVK;(mecs>X5(+` zYjAkpV|`fPzOz0HK6*8J4&TVIb3_j=?e>ZI=LL&E*nyi2_Qn!e$MJ*!ckk8kN5e*Iwc$QDN(QmXHgwoH1o zWohHYXyelMiP83@Phej33DQ>(qpy%YgcyB@^ex2bTcpn+MxP^n5%Igy7fGK$j6SN` z5z#v0WpfYr`##;8=}X(!_kaDUEAiTI%ljwRi+JV@Ugov_D%!_evv#8Q(aRT-=D3>< z@ze+T|FXtn3m;{`&&5B9)jx^VKPi*?C$ah`@o)XJEOC;O2p&2jIrVkHHA0C)KJTQHDX!`Kb^x>iD!$Z@Dho%n?O&=bb zK0K7Thw&A3V#Yh)jDx-zAAK`!`er=!%{c3u@z*osvS-HYCK!iJ=)2Lo+5~o)exDcAL25rYj*)rCk?Ql$yu?B62SjHN(9by@4*6Zh+i@(zc z)-kY_1KF^if;AgptSh-S6!|aC9WWj1DOj@s4c1fSix}%EShGPo)>E)%1B~?)+c%;N zmyR-kK`&qU!}E}ta}D6HWn`gTU9$n1uX!jZ%0OboI~ohI9%a%qYhIAi@X74$piU?Q ze6+4kp3EK*bYtWXWetPpDWFSJ-^^Mg=!G5r_?)NF8_H!m(nKC&&}ts8e;K=oF2|8Z z_qTtCV>`C>q35mNj*v34B~XkbEyQ}*TJ^BuK5FM<7H_Nl|F&8$=ZVrL*{4STUq80C zws>>RRW=u&vYzvAYz$&`WwF$kqPOcmn`@oHu3gx^^nY#LW@}hC zv+dgAja?^%50&K_rfq9RwvFDGIdJmznSBuBhe>0Lzic1MtSfHOeL$nzQhSAF?X=Y1 zqFFmFwHImDPO-nhIfU*n5bOQ|vF;3|pltn6=S+RhEw#qc?i*Y<+T?xx@zT@tL_z(yV7<&oM-s)ICRH-E$)tdm_OopNW3gG2+~~bCW3O;M zc%$YURhKuYzp?X;P4PF_a6{+g5$%6ZFZ%J3`|q${7S(mb*HhfN3*`HAypFF~iz|~g zQt1ceon-io!`i6_g!Rj^TqDJtxvbYn<=p6ButxfypB+@4vM+*;&06bbTkDSPxH;Ck zVX5`6H{jRk6Vt?c*cyBQR#-Py{1IN?d~Zwj`B_R9TW;kH!AsNK=-oGV5D z|07@AF#j-oIZi3x7*i3k4r70aeIWLM*ax;AAAltB^H9(N&h)r5KKOQLeB`Ih86TWK za&f23hcfSt-@?yB$(ktM8-!16J80qWXS=u$gx&rq){1_QX<|KWst;skElrM-{xWKF z8-iuuB13O6cu0I)2#K(!j4=QhV*z?nAA^&D;Ee~6>C{%Fld=W?XiIUcd-26I1Rof8skyC&B5POSZa z+yBX&H@CXp8p^dYh-{hpB=(cg{^1i+m(2c^>cG`KbH-nEk~!lqSVOz5AUo&=;z6(!%J4Acgl4GT# zw~C%k&%5Vq@3^y1W4%gd*YvB7j_x#Ec7L9KVYU64ZgJM^+J4tM9hm;zUEBHREb2~t zMf!1XeAnpR*~vy1dmkS^oaw!0m-F6VSwP%bo|CN5HO=>MSln^O@Nh)S@zl=;)B1-! zroKpAxpkND^II!2?@>+i!n#F~JZpEV84ma+lJn>8Uj;iq5y?Nl?wp`WK~%3!UuOr+ zilh3r@7pr(5qZBRbZGIKg|{^iFX(*;ardUx!WSOxOx)Bhs}vskPV{`|lY>?TZ(n*Q)7#aU9xQAT zy(jwGwbg>#+eLY;jV#`)&Zw~O&ZkfhBfcCIHtH5VuX*3ne&G!>Ut@a9`rX31)60{8 z!>c=n*SuJZctQ6=!x}RWB)+(R?J(!q$X zR-2MW?Lw?}Ay&H(t6hlIF2w35#A<6|^#Nk_4Px~fV)Z3r%SU~Z>FTS*>chn9+r;Yg z#M%~!wT)2E+IEQ1w?N;~XG8Hg_l&RPjj;A_EKBsfR{=%P+|R!D01BlIG#9N;cbGQXud`cyV$qZD-q~gA(sE_Hupk-LWqF52 z;s3LD9$;40=o=qJniT0Ef($SWy%%XWp((u==|y^P!cb=@0*cZ>K~SU&O+*0!DfdKC zQ4y&EqDYk@3W#(8`M-ISGlpf|g+<)e|DET-`I-4nl9Te~{c>{8y%A~d;pY6~#V)bIL%GepfCE0mM))?kR`}NLC3( zpl;G{XO~wW>Ltgwc#HS)O8Fr&>5u~C)p)o5=uax}9mJ`A9V}N2DkgLvt!dUvep~7t z^42~rWV>ErQm22ryP}+QD1zL&dW1}0zY=-mgqx!BmqvS^{Ct@h^169f&E&y_#pB^a zXp`&8yEw~b;vJ-Wemd+u-yZpRem=-w`T3(<<(G^4D8D|ar}FEG`YXTwxG&}37w%WZ z-S44Z%5Mj^AAgTWJU&Ebdc(vcIj8rMpPX67HhE?fK4+|MlAkJ5N$%`u+9XXdLcVvt zBJVd)E=;~V-n7Y&>TQv@k7<(;jf#rLl9)C*_v(StC(#GGZKr)-&|6#Bqz})$%uDYX z`^~@p>K(sf^68T*LMhfUqanjVlfQ05@p70M6nuiR( zA)$H5|B1bB1M_3X$iLzYXtRs`mhxT3cf$Yvtmd7Z=ltVrW`EsHuCBb1ZPhGu6M1rO zLbmxQ`J}90!MwL=%%&{z#zR$@-r$YPqHfC8Jdye+@eC=)9RGHuUzr+4u{`d3L?K{oB z4{_Q08P?7E5Kq_E`WCYFIpn*wx4xZY&-yyD^?_vT8|hE1&tzHFmy)fIWj(F$C0n0N zw!WHdeK^_rcCz*PWV;rS?HWN2n6-m!*A%i{YshvDV%_Z8M7C=d*==XH9bASs&}*X5 zZEn{}vRy;jCU$LQo_5V8+qIbWv1>HhuH9t2rjzYjPqrF>Tx#H}(4=O3TFv0wYb`;x z8iQ=L2ia;8vehbNt6^AAt8K_u^YFf`783g2twtiFeYB3cjjh&_+TLm~vejl}tJ%m_ z%aN_d^I2;@-$rXfvek-Yt0Bo&TavBjB)k3SvemAvztyy4t98j%12Z41jmcIsldYB} zTa8V&+M8@OIoWD;veocptL@2F^OJ2XK-Obbx2yTNBUZk(KX&Z3|1{n8tKm)Ol=QE; zvOdg9dd0-Q&)*mpJc9Rp>U@4L{rB>DutiQ!jW_!b-6CVX6m`wMMEQI_d!xsh{fb$Q zGO5@#W*=jHn=)!kH?zMnp-n?|zNgvuI6Jqq`l^cA52^HOl$!L2*(Y)LPh4&oRZi8~ zl8bd7F`%((zc>*&ckZq#{OQe}zL#C82dJ1&hLBzRhd(Z^QdBBN`*od5sY1^cBESAi zSrxTBAKA4Tb~)S&>@fHES=ekZ_UXRn+KJzLuWU2#yDFC}y-GZ*7SsJU)^)fOzWMcW z@3CR+q_$4~OoIgvaHt^D{qpsz?6({R-TBT)gk@1GxJG?!JM$pWyB@ zxcd+8zJ$A9;qGI&`y1}Qhr1u*?vuFtC+@zAT?^ReE{FCjDoH)|?qt8B&QH1ja{Co- zEbqqnZtU;w3AlR&?jC}>x8UwMxO)-q9)-Ji;qGa;dmZi`NWj?}araEzy%cwk#oc>x z_hj5X3YYc#^<$0yh5d^Ewf%>?t&h9k4(;@wZeKl*+;|_)2qd0g2%U~+1QO3L$aqE| z@%(~}X9N<@FL*7U5lB40AmbT<#PbU>o)JhqzaZlofyDC*GM*6#Jij308G*p_3o@P& z2t2LT(S-UqJhbHDe;?sxwG z$$0bE1%0j0ce|%_xAxFr|8zgWjoJSf_F?cnVhjB7`9HD`qn{hnZ-?5afZq=KSsoeV z@Go#itX-QX#PLrEbIS=?}PKtlZ5&% zf?D*i^O?s_^;}?`!@~YOyUz<;{=3epzw3Rudmt{mefnpd$JXB=rM>_C_8WiK`w9!I z68Eh6PS|Y+m;bKg{O@{S?wobm?bFcwt;BT=pD)v&u_D{gRFUmxvOLHCkhM1av;5MX z%vsmQ?O&JwuH*dgdSC9Gb=mFH(ER=1pTBP3xg6@p7WA?9Gp&CCKm6}wpIhT2vuC0I zYkr1FpZvWAH@$w%3~_PRov@C{FrIMD{eL%tJ62u(Z`I+?@O%EV65UrmyZ8Pl)PZxt zj*$?vA^d#^{Xc(gcE^&-f99O}yO!m)r^|o#{hGOZXJfV7fz)ySKg4Ek|DDa$(%Ux$(cI$92 z`J1)$udVsC{xJ8U{~O{^pN7UjXbgnLKxhnv#=zfo47geddP(?t2|7ynItuzq`1%UE zOZvJCdP(|v3_40Wx-O3IcmBUuuB+?*Laf_O>ak|;>yFv>1?_Dgk!|0RZJ&~DUz4B7 z*m;qT|8==8yLGsi{B^#5{vrO?&sjq46KbE(7zmAl&=?4ffzTNE?~Va?U)1g;`Z`MQ zF_P`xBiZgrlI>n1+3L^R_jv6Z8&zqdr z_Q={_R`~oSa@wn%<={=*$gh=6rr%AWwEdrO?jr8IhpDG|m;0YxhqZ4%!uHX1xD)oz zsNC;!^6s2+*=?))T?hMInDafv#)to%+QA)H_xstL?^m>Marw`zgMCM+r)yBIN0hwS ze5B!hL*?ax50TyZ<+8i~bH9C~Th@kz`Na6<=Gou2X^X|mm&`N46%DV5%m>Z0!a%%m z+2c#|46#gYDQ7*Fhdw-Q-X`+&OXeA+d+++bbQ_qT5Qo~~x3ib`drfiYyUXreyWe%d zxnHdLX58NiyY>A4;3v^G^dEL!{9AVYmCJwE&y4(C?<*`Uo&F4?T^sHP>k;MW|L?i@ z!u}hkT#4cMdwW{{4O1hTrj$PE%!R;eD$O8zOfmFk}TD&v|& zZ}wJmPA(!3#Jf}%x6Mh8_iK#mSL-I<*}MGUU{yWS6Vw22)a#|XcYTMPdRYr~J#iT8 za45Qx3QHeBerjY6)xAbVa)a0hRJ7NeeB;DQ@7mIyr=V*lyAFMA~)H}&Z;IEy+`&b%jWrYF>z zU>@c<^Nq&pi_VG26FPKLmj`~tHgtJZ{(-9Ct}aaP-7ZEoPB4x!Y4^j?YGfT1)c1RO zVU%jQa5&p`!O705SBmZAs$q>(qnM;h+dR^*tjb?8Ke_Pv%xYKvs^kwQUh=XxZ%tmg zVTq?28!dEsXEE>bUramS$!9wL!R9X3g1hsJck4$(_PY1=PpF+k?GPFRp)n8|17-}| z`u&Xe^c{T8cR=6EckqRLwBIwKG5W9kl>N>}scr1{LXz$GMUw6JNRsW?CcE0zj#Z}H z?~5ec?~5ec?~5ec?~5e6`TSA!`Mo^vrJlAOS?Bw~Zk=7W-#28+HQx+i2(a!q2fyiiQ{oO!h``tri`<+B&`&~t3`yEDPw+?rEty^c8?ROh7|GTZfTc3UJ zp#iXf0C{LBwPPU zwmyVD+U0+L?jkgnb=&`|J~V$1*@W65GzLOrAT$O-V<0pJLSrB_20~*XGzLOrAT$O- zV<0pJLSrB_20~*XGzLOrAT$QK{_11k*7F{fGA}^|%k6*NQvu zB%Je3!awh1eFNL-ez1EU$>l%lywlyDxpM1px7WILcKMGwuXQiyvTm7o?tENXMmh6c zIrCkgi{o6rle1fYRNe07{Fr->cC51g_k(f%A@1GCI0L5eUJFl`gEL?X@3kP~44A@u zEyy?nrtn@1GR}Z0yw}1%1E%m^3;zrlzK11Qtj@>HALj<*(s9;8;T;#u2j|li-f=<3 zxiy7%T##LRoC8tLIXdN>qf^c~I^~?BQ_eX$<(#8a&N;fcdw0vale)S0WtqOkwxMv^ zkZjwKY}=4*+mPp5aE?y5Az9bwnT!{4t}(6+nZIoxUTfQpZ0k&RuXWkBA@j#s8r_Dp z$5|TPhGd+j(QQb^SsLAjWSphZZAivh8r_Cu_ukz$bkpyo&aVAmh4uaF{xLrx4z)vQ z4BYJ)xZm&Rz#NrhJ3q8g*Xw@2tH8W(=$12r^bdc=JsQ1t|L-w!!H&4ko&Oo{S9q;# zO}yvo{(qkv+7Eig%wL!PjC(YC@BZJTZb!TmDeg1WAvSaMzugWiraUEQPBiaA=<{+u zSv_@tT5smAdX_xnayoIKsQFBf>wnxl({BwE11}q! z#0^G>N|Vgzfrd5tKr~F!o%wt_U+j=&6LzAJZ-nmrdYR6*K#BaXepvP~Wy@S-{7ixH#%QWht-aWF8oauw6 z>eH(aDV@G&X*pGLLN4+<2g6l(cJscaLoZ+P5`1Ca!_+?MBCq2P^G<>n66NroS~!IE zDNYn9Tj{!ak45dtrNzT*%)1J{Zn#3Eykg!J(Im+OGB$(xuFfUta>yqanRiR2Fr4(%)2XU{u(1+Kl20MX;EOr5ZUg z@Sexc>lTwAZP`k$iui@>_NmJ&>lOA+Wi{`LI6i-wH!0S9C(^_wH@&S#TS(m|FXoL< zYr0n=_jpVTLpcw(gKm*pLohz~oO{)*S@nn?J7>BqG_ zv&qKaKFR#AiwZKYiX?jlo691vJVWVs~gLQ z$iM>;Lf1LfC%xs)%8SU?$F-6z2AX%1=)e89eZ_yP4tDOdJyRE%D&BjzA9??tqvD0~ z?a39#rITrr)h1uMTtbdWT9llpVm&!FQ7UrTH#^GMZ}zeMgD>}&^Im#^y!O>-`SJMO z+&>5ojgcE48O}JhN2!5wdLr|lk~P0{mB)r|V!u2e-dMIMmRRcc$X`mxdiC;>8~pmX ztTf-e6XmVhmqg;mt(ktN=_28MXx^c6(90u6b}{p%W5>06-KULvkFBSS6YC!8uXO%z zytzlT>fDK(s%$d({m6#o8+-H0e(wj!ZC-dvR(UNe`H0tCE}s7Yc~9rgGF|1JyvL1w z`pVu-Unjf1bV2`#qVSA&|zW8}fp?{NO+J3mB@nUVRnIt=PuB>2S# z#-Hz8*VwC5bdV{lj`9vYYu1QK&m>SqziYzuk>zr$d@0M3KQCWdtymjQ{@{gHYV`AF zzU*n=Tg~dTg!NfjZ-^RjCLdYrtQBqcQIp$r*2mhDZ9Zh1ztZhv%O%_Tkk^}fl5PFT z_P)q&|Nb5y5(T};Qf6#Cw0NnP+miv01J7}eyf^=0+7O>+-b@1@AVdtCZMA9Z@d z9CEsmZB%&upAGk|sxDp5%=-82omXYgEXbd>PNb?XXiUB~Wutd_b2oDBx-Gl}=LeGC z{k%*t?Rw)&b$PzN4aFm79kk!OD0R#1UD-mn8F|HoUJBoN$NoahsC0X28{K~Yjd;W_ zTmSwu`tH9GFaMq5EH{31+1?}Pru|MuGP+fNcO@C${jT)5)P3!KFR1-H)9v`Af3V|| ztjFg+#F8Ah?s#^`xjX)Cxl)&lpSbVRbie!2?W3=oEW>-Nhtb}SNwS_dD9_JFqCB$w zPJ1%SmHPj6LH6%teVsG!q|R5{=yLkMT*luA(CNHiYfrZMC~a-?C);w#_>-;=+18V6 z>+jp>^2l!Axv`ZlU+*R9vfTE;|HieO+n#Pa+wys>+b{p0H?n1dag5pY`y>nP>cV+$-!pj|+xJo`ou_?YCE32ml5F2^ zNw)93B-{64lHKRy?spK__ifU~zE_iM-?vHbjQ4X^&e((89q;W-md)tqk-K+#tEzTp zdMUi;vs1K*Xhyy zZsPaeE8E(VKMR}f#XjAaJnV9~7uaFeJgkfJwJ+Csy7@GWDyM2~$;I^7e<`b?mggg{ z>s(3|dae-JwW)I=S|x5ApPk!TeN|-#c|x0p>U_^+v|rz*jM~zz0C`rUOe%IwHFEiUKYOFcwIO$ljP+8~ z?L&UBMNUtRzx^KF`@OP0%u9M@DD9uWF)VlldlkAJelPvEYyYnP_W#3u=^p;~e)xaX zM(Nt$#k%ufwf}9tgoU}R{f*J!_x~BETUI&qeG~L8_IoJE_B$GGWBWZ0^a=L+9mw{3 zAISFmAjtN6BFOgpBf$S3=2Yk&&Abe?L#Q1>V<0pJLSrB_20~*XGzLOrAT$O-V<0pJ zLSrB_20~*XGzLOrAT$O-V<0pJLSrB_20~*XGzLOrAT$O-V<0pJLSrB_20~*XGzLOr zAT$QV@xHy)}&{v@B2^(*8dH_O~ao}8PIY|mmb zf0t#|elpSI$xI(nZ?IhYO$G1#L&cT;_t6K_Voz5pLe4kfTCiNkJmj1UqP*T8Wg?${ zXq8v`&4e-Wvd#zj zlXd?1C$)_(6MrM?`rsO}E)!*tZJFeHkIY)&qz4>(;p8Kn{Do64@`$UCbm}Rc`paV5 zu1D&+;h#?T?^oOV?V$4^>oT2olcw!>U%Eaz5BystOj{J!Z7H07VVh~21aEyZ-CY$G&k*VV)t`Z5y8b+q{>+h1 z)Sq+0FS7m|mHv#9PS>BK(w|+@tUpJkf196SI-T=hr|U9wy0*tJ+Ub0B89H6(Z_5bN zY5H$E9Y4xm!+QE(9XX?mI2oGx(wD0`RFn<>-_aU%}m4JG;3RZjb@#P zDFg2$MBcg#ovurC(qkR_SY20}&jKg^1x~pOocb(q>bbzF|AIp|UPx~8S*p|h`_=Y- zJLr5Cus&!@r`>e9OlR6}?Ysc>WV+4+^(X7Rf3NQxKcm+^_Nn&Y&KjZDKBjB`?W_^> z*Ln^~>$cgDWQdM6Q&%Abx*K#yInaKK2oL z{kZv_{-=F}PSbzWtZmITE#NbL@^oH0UFSV6+2^s=r@-GX5BTY@7n-#_@*(Sd623N@ zoGJ2CuiE1EU>+#tX3`gE;h>C5mr zfe0r(;MfZ%AK~OLoN|RzANbL@dWvhw%9#4pJR`>JKg#<$H1(=TpY&1k`&DjgW;OH6;U&YoLrUTS@f_wst4E5B>sJWFo2L+g>7KI&J&A*E(b1cdvEEhUb>+Uh9_S z+PgMxx*m&|1N6@!{wuV@Z`#k%g!e_OYv1jU38SZthIcfu9yc62@FRbSR>wOm7dRUJ zZ===GmRciA)1LajW~^zQ;M}k7N4BSKW8J3K{+8IsiB0t1X`^l3esTNjANmn%UR*zt zZJAQ1+kPb5n2W5-#NWs;(=iuWm+6i}{~q=II_bI}eS5A0x-9(M68pF@k^Y-D&}E_w zzn-_mR-cSM7O8D?na=&*5~JadN?YiBoOaXYGF_Lc?^)a6N5@=bU8d77EZ@I3V|q(p zN|UDl`$wevV?)osyXCn1)%U@BvG;c;%=@tRcgg0y@%eupC-K@l=P)h`hG4#IH_R{V*l65>}V=l%SHs-?LxZg+{C+4zyX55#PPRu2Bd}H_Jq>g*A-xzDl z)9E@cV!DlGXm4XK=3`?Y=5J#n?$z0ti}kTF6zgeYtGIYb=Wq8Lm1bQR$KH>*bUu2& zkv2LWa>`{H`dZxvPCflHbp7>y;{t8tm!W^_bQ^Q&`(hb>KDrFeI^MD|m%cAuALil2 zT+Bn~<>sx~?l&?$)OUZqzSHy7_iG_G{yo$Vp?3J=#(=;6?$X+l>#5d9jt0}(lIbW@ zYfG}$M~((l_#4x;9&j`m_K|+u&yODZj^6Xa&!4xS|L)5D_dP~v`(cqkeLvsq8JfOx zdGlwXe$*pOk4-&BHQO;u)?-=6Av#@;aW@wDbNf-(!1SM{5SvyAwL_>K{*Ge+v53ySTW4_ue& z?mfDDl3I(~I^D8|dAGVKbY3NNUL|y1g=ZQ==T#6th0d#l&a2pU<(B7s{yvd&X5g0d zByPHM_TUy9=d42Lyb9);J}2XxOS$FDiIW~WuY$J1nJCX0W7J<-i`lV?Um-Sa@xR&* zzwL+J@4e`b9ZUV`d(n{#Cf)bF=>LXRM_cN1%JLuQ8NQQEpX=cKv(FUBIv#Rj6a7qq z={hcPViTRlbZzU#P;PAX5Byznl$$&&-cHWFHC*D!0@^U!qm9yhIh8U z>2;_b#d$T z=!J0Ax9UQ2mQ-0(+s~JhcihaZ4la9#TQkbHVa z230HBM)Kxv>DBJmo5;s{q*JR}eMUa8E3LYe_j7XonrT&tJl& zx>P_ld#@DJ)fWZSBbiNlo=pYR>*K6VwPNbv>f!9`lLd;YZxXyn-WIQzn%{Ujx#Z@e z>eSFhaP zs-+~K_^gon>W#<9?>Jg)0wXx2I-=aT9V?GmO-p}KIz6IxX^gDDoFLXJ6 zx-Q4J*Rj8!k1ogm{EYtXmuvoR>Z7mo>#6he>#xfhBc|$i&G552NDpeZ_MT>&5838V zw&ila#@2^y>q)ltC*z$AIgy{A9@Ooq^SA9lw(UcDLEodxeX>JDJ~`xyU?-x*GRt8p>4YWP5Mfo8>2#PTTe zQOu)4t4gsBt1A>#=?fMo-*~g2O1`21d0J#4Rq2aJ@?%~hwYYyK^4Ye9RqhHY$ZAJn z_3n!a$vKJ^QEJAo%zxOJBI>bLXURXND5^H+{*s)jXHhk~tRfHops4D{+KFTZ!Nk1q)aNqDl;}Zj>)V}HC@5<`bDy+ zR~sxPALtpbMlM-MJ~%6@%A0N;`Pa_b)YSvC$(xR1UHI`e@^jU*tHFU;WV`N=Geo3O zZ64W9KJru=m2>GfvR%K(c3mUe^^0uRHL_hR$=BQ5^mfz=F#!Y^Ne6#am@1q6D z$mtJ$=M}Dyl)NtENpJj*=JR9ylmFoLdn+;1YnS`U+tno@IVS%Fuib+9;4R-!fHp&CmG@?JH~eCb`4ucoxzbAijvo-OXXdvUYMNs$zj25)+WQ?e!*fbjeXmu zF~R6MhPzE07CcqcaN-{Q0#90-CZ9bMc(cDrpP#l$An>x`Ws7nK#2Uker~XoQ@;<|Z zcD`ITaM5trSF)5HA7=c2j?tf&-fP!_iyc2&Up1adpILGCh92jQeMay6hLhhIuKPgt z;IQ?EpIV;?u=A zJ0>fneOU}!Z~FAdgi}PduBNY_tvx|_Wz2Xu+-=zsd#m~8Mi|&)e*9;8P9W5RTGm#Fy@r-=Tx=6GsKV!X6_7$KSN|oZt9P@Dg3#KIV=1*i@7QMxrsR| z{5gxcFXHBY%k3ghqBLy(;?1^+B5e(K&AUw;?rV5g>zkr|ZQ}#;uel+1Wi>vec-?Da zP7UK{HnqMY+OLeqe5yoW5PgPQzx2&nG5ZzcuX2t2QH)Mz{Md{2z8C8|8~?Vw>2c9# zK@whDEbOq@ygeED`91qZ!QRGCj@|H;=y)>))6?zSEe@wJezk6fFU4c;8csZQr+8Z$ z-wPiu5%17fBi@mScgTo$B;p-1)&hwbhm18sBE}(OEs%(D$XFvJVjMEo8i^Q(j2K5E z#vvodk%)1~h;bxh95P}Yi5Q2B7)K(;AtT0-h;hh>aU^0KGGZKw7>A4)MaU^0K zGGZKw7{}ODD<%=+P!}P_k%)1~h;bxh95P}Yi5Q2B7)K(;AtT0-h;hh>aU^0KGGZKw z7>A4)MrK? z3Y{l(uY~R;L-$JPUNUsAgzhCn_e$tqGIXzm?j=L_O6XoPbgzW&W&Y5;61tZR-7BGc z$7y%M^Y4BacCd&$tf61tZR-7BGc$uatxqFcUq`k+jck1#+4@W}bgzK!m3k~e_e$tqrbG8i=w32( zuYm5Q4Ro)7?j=L_3g})kbgzK!B}4ZL=w32(uYm3)L-z{kUNUsAfbJzj_X_AL$k4q4x|a;yE1-MHb`2%lwUunw zP_kWH$##tp}ODp>;iIU1L-Cng^{*hSv3yn{$J!oArw5|uOOFn@8{{>z7>_9pD z|75%WufBp!iQarhp!BnYndaF6**)BM+N?Q6mtK>@)qMZv3`3sY~zO5a+|$ zN9yhR*F?|i>?3ux?G~-;04A z*+(j0>*FFYpM9hX#y>1}Y-Jy*b6@WlLwd50RH6635)c2%K2neF-z`3Qg#Dt9X8ckV zSZO%l%R9vnf_aXnSe8m*kQTRCgAa@KC;XaJ=(%nqYr z)KJ7DGcQmBsMisXEHckrl-5FJjTTbLT4$G|PR!KnxcU|GNZ=Hoxu}jRtBf~pF4Oyt z4VN=3QJ<)Vsk6w9A5*ue!4EtxzhCqYZLVC&BuCVGm)tBYlUy3hXD;ecsf=>(OVmZG z>#huPW+Lh(^>B~$GJXr{D0Q}HI{9jIK66nUzf3C|<>oUN^#kIO@89J!7v*RQ}@g zA1voH7nT0$BJ%ChS9t9z#3Kvdi^n!h`E+49Sn!#P8n(HRygKbMrk5^RNG6)gXD(_r z;*s)i@R^Hx8}Uf*J%wm98}Uff{>8{P9%25e5qETsW*njRW6eoaZV1zDJmPXt-hgWZ*O^%uvO)W$`a$^+t;Z;7wBM+?LKD^SgUJDcJsSb!o&J^W7yqbb| zB={cp;Zm4f^j;*l&f5|W=UQbaab#eH~ndUO#v zY!LV1RX@Zd=PPg@UU@x=%H{RA53fof9+`NE`|zqf;*kT>X7L{TBOb|df&1{PCgPEK zBe)Omj}22F#3M(|KD^3@c;u@-Wti^7y#Cl@x)byIV~^=hOs&RX4z4wO0+{0wvd7Zt zv=N9$3YvX*rS}%{n!N>83h~J7_}qtAKW0lO!zyqeUM;DRUY0z(iPxrInL*a7YL9T)=WXsk zsIO*bm4S@&cx_(9BlVBWCZ|O_Qt0e!adR0|NQ7?Z==F@5Leoc<3C#Or1sUNzfZTQu&NpLzB<*F>B( z`|x;%)?VaaoR{ez7wsXYoXbP5pRvD)5QdvI8!E<4$<6e2kBt%qpXNTQdg;NjVpo%# zOb=`vFETadzN_k-e6kohHwV)bKRi{eF#GVThc``>+r~Xl&Fd+aJ>qnN;RW*=VtI(1m!2eS{a!hhSVS5>}! zCOFyb!>jPZRf1W}KD^rYdCp*Fvk$L^{_x9&XU#smI$iRW4Y|xdygJ`Ie8X_F53h!f z*|}~v#<(8m!{6LkrjFT%SI546z3eEn53e3?f4*#j{l#eW{r+r$Ic6VTt)C(TQDz@r zObX)n) zEOZpvU{6)8^>`UUOjQMj`wmMGoH6TTFonO_Tkk-XP)$~WifTG(V&92 zv$bIxkMLfgfjwwoGBmIU4NSK22-(IXWE+o=Z9GD@@dz2Z*MEknb*~5A%XH{o54x8O z-RnP#)VkM$?qxc3uLs>rhVJ#Cd&$tf9&|4my4Qp5B}4am(7j~nUJtsL4BhKN_mZJ| zJ?LICbgu{9ONQ?CpnJ*Cy&iNg8M@bl?j=L_deFUO=UJ-Oy$ZV5`2PpP6m+k@7U;7^ zWawUf)`*O?K%X@tJI`vh?$u|Fn695$L-&%Qdlhsq8M;?N_mcIqZ|Gh!bgzQ$B}4Zr z=w32(uY&F+L-#7^UNUsAg6<_l_bTXKGIXzk?j=L_D(GG^bgzQ$B}4Zr=w32(uY&F+ zL-#7^UNUsAg6<_l_bTXKGBkreYea_bRnWa;=w1cgOLooxXx*#N8ZjNZSD!T^LzC#U zMr7xVf!4hWx|iwDy$ZUQ4Be}sd&&B&1#~a<5_GSE?j=L_;#|;lGIXzk?j=L_D(GG^ zbgzQ$B}4Zr=w32(uY&F+L-#7^UX}&jtDt+y(7g(}mkiyjpnJ*Cy$ZUQ4Be}sd&$tf z3c8o9&x+W6cm>_7pnF*sbgzQ$B|B$Ml;wc-xAx2lwXS8o53hBvK7T?R=w1cgONQ=M z(7j~nUIpE2Y|ysQy+U6L-K(H`$VvTa-Ajh< zRnWa;JI2U%?2+vlBipe@wquwK-HY>PGsw`r3c8mJ-K(H`$@<(NbT1jYS3&oZp?ei{ zFB!U5LHClOdlhsq8M;?N_mZJ|6?88dx>rH>lA(JQbT1jYS3&oZp?ei{FB!U5LHClO zdlhsq8M;?N_mZJ|6?8Az`XVxPuY&F+L-#7^Ub6LRWawW1T&32%{`pBArhVJ#Cd&$tf9&|4my4Qp5CF}2Df$k+k_j=I1WM?l< z>s}AKm+8>G9&|6++0)Z|O8WeX$;X^OAv=40TKDSnCrpR#_4hor?)9L1nGW6SLHClO zd;Psrt$RJ_UZz9$deFUO=w1)HmkizOLHClOdp+o0GIXy8-Ajh<^`Lvn(7hgXFB!Vm zgYG3m_j=I1WawTGx|a;y>p}ODp?f{(UNUsA2i;3{_I|bQ^`Lv14&CcP_mZ7GWM9iM z-PuF-wH(v!`4cj9ufNBxb#D;5m+8>GLFis`-wxry-9f_>zN!$sJkxObZ(0Y_4K%#C zVaMRHUWOlfw{~#eIK$hLmkd@}Xn0z}9>GGL4Ci0_Y_Lo#!#%nT4km0A#{r+mee#6p zo4z3H&|&p7k$Q(|lOtt57X!AYW%{&Jzlg-qX6zkXo>DIUW)J7c_jt~JW&B)n)yVv^ zPX7Aj98-(ROO0032NuP%g7OQm(dTFWv5-8I|4~oRqYuB&DRY+_L++F&qnwt&BY(al zp=|l|S#rNRN5%1@CT8s3?;WxKk;j$3Hf_q@qVn=Qw|hKzn-YS^6QWLQvQA6ewBZ}Xb0uD1KLOV?Spnx ze!HPPJ-JV>QT^-N$=lo=15vpyAQKi%-B6N?45E-`G+7fIcwh-(6fYsiRe0*GtK z&NC@LHe|ZmLVgS5r}2Th-Cy~88TuSfmnuI;$|IzScZ&PMj)0U zBbE_}WypwS1Y#L-uV%ZwHLE-EjJ3;4mPE7FA=U*v#(@ z3+r-nfSl00C*Sq5y<`^|vtTPZ(};Rfy_J%AmaHY@`O_chuW|x6pg=z!H zZk?AuJ;vMnU4N!8JH0tLG#E`@d1Ywe_;8a?iii4%1{2M-+j8#_wZ@osD4`O{B}tml zK3lhD+!Tk>O!T=dJP4Vr@uW8{J{Q`nxTo`?;$&tvLy(&4d_>&aiIrIgw}b%T!bSdDMk z7qz(=?ijs=0zk>^n%FHdI?VF~r4^B=lXU=ZGd_>M-^3}tp zZJT^vRp!L`V14g1b~cqa_di4~w7sJ&D)zDdne(emTW z>)9qf>JOCLs&^7PpUbcHk*!+KBR@Q+v#efs2l-U91;HLUW2Cluac*p&PHw|j#|;rf z(hp$z+qJfck{h~^2X{{{7r)nloIZXr*(qKL@~)*-Wyxik$-~}jD$ga1Pd>MbJ0?MwwCo@+I*lqzOoa*tAK4@AJo1`%I?D=4 z%y&UITUbwi8)fE~TYopbdAp7>JkdA2HfvOWIjYB4^42!d@`3M;v8-3R#mItHUtk?_ zz7i!X(Z_wm>LnSM6! zmf&-1jm^}j2M2~dXZoc~!)Ha>nWkTc@7yig&NSEN#dEx$ax~$!KPC*9%eGf0%NL8u zhS9~zQ^q!sC08UTmtE9JPIz@U?<@PrC|O9Edw(Qbw9I+*65C|?4>7Xw51*ISZ4%u$ zMhL7rVYzJJ4T#7WZL}wzPm-la?_qa z7Dyozzfhm{SD%9ZnOBOu|CL(uQvUShwp}{PMQ6Td{j2uwD+jlIojf7oU|D=?6>{gx z(X#7TYk2SJ$41N6{k~?KbVr%rMUC-v+jf4Vqg;~sYx4Y&jb#7TNt8~1DWZzJ{(2U2 zk$q3dVmXSCn-xhTpY-aG-TJ%fsjn54wUd>g&D*DI%l?hhk~@`XFXzSkj%B@fw4aPO zU_5!&sc4zB%m&sia&L^BHX{Y=d?4Xa*=odNLf5Bp2Yd(n^pRxoQG5CM$A`&D-m4?S z%cPOo=B;wYWcyFecx$%gQCa%^8caXlIKC_}rYU)AyMy9D;|}Eg>&A%Ed(ArK^3XJC zWWQZ?X!GEqqB2=7<7b-gsVz_UPs{Y#+1tyEwZCH>3heDC2W%Zr&VM{wZe1H>{SSW? zBflJ$jQ2J8k)d+=`i!2gXTiQv@`EQvlAqbvUM}u=nB0749r?;{6X>M)ILqgdlw%Rk5}nHcI$lNz1`x;IcDv+P&QSw(8zU&iyKh)agf)RFOx6S;#}ZC*=F(ijdoGk5RoJ z%fx(E{Su=h3)SI#UkyG|unyO2Yr}Hy);?j&j_Oc0vvyZhb<~AIW}F=IimLakm_99) zCA->K<4M+Mr%b6H+G>2Mdu@|i9pxkKO+Mjc>&e`6jj#AF-xIRg9&;}{QfH7y&(vf- zJy#wUAAH*0O((p4+#!+I7>6Pq)sSWlEXY-q-o) zLUMHv<4+2;tt}^{OUG+F9NI04OgH|g(Ww!l=TPI*UatO5U_(+WX?OK) zy$=}kp6uRJttzpKJa%Dk^~&`{@k?+?2iBo61sIJd2E_=H1FW$V`t;jEI zeNY`q-ke;ySt9lR;>P5=wSR7TKn*!*_PBC}RZ!&<P9!kDjd)s%OuK$bZ(`nZik#%3MEU}7g`;>gQ_O@+VxA)NI9g}7w=R#k| zL^;W}j|`i>_^0;e{)s*IN#s*@Uqy3khq2$ny%g-XNbI+8j|KZJ68kOOd(rl;O%=yx zwza|iN`GvleI(jP=(a-pNVE?b?IZm;a<}#v57Hmo7(db<^B6w@<45YUFn)wTNAA`h z?JxbYjrNylf98qymuP=7+F$x}%VKM42-GW>&XE3$19^4;3ozT?=|eY)C?dH6Ru!_EcUr?mM;d-y}9YkT-Z zvTJYKmUV;wk?=oc_#X-XL$+;h*!0CewTJ(?&EB@H)a?WRAmAU!@DBq1fo$8He7E-2 zxA0mIJ_r3v9t~fF{`K?JK8ozxV?4y!V?6v*`&=p8$QD=6i_-<;E!fbdhrBXyohbI! zg4jw&2FMRK_7qn>J~IF5@S*bJ%?#qB;g{xJ8XqH94Cod3Zh6l!J|8KQW?1~lfwD!t zu42Zaz4PnVTkutv0g>5bUb`#Z?~mA(~k^f(>smbIWvP1!R3qw>k@nP2odZN$#8 z-7>UMV-K7cx;g~ExOXC zTe_aA|ATADC9ZZ*%Qx>QcX!H)*QBPp@NEXR;e+6dmdigeR6ai|9qlKcj*(x~*ht?M zzjd_C|IBgvxBlk_NjbWjr|ZzUYCm~;;^fa~s-$aI$%ZyO{}XQ|2iy%f_&=1Vo7e4$`_IW4n! zhLQl!XL2<$&ux?Ts416yVEWzVBX6~nopK!KwNJ~m zQCa4}Gt?%vqGJ;@DaDw2Hhk`jH&tK2Iw1ZEYxXef8ljd~!@d zIj3=H*|Y!bdC50FC0EwWDwnnI8@nKVeYx(-6!PGu_ha3%hCk9(imjW)4`b@TF#=o` ze0fCuH>Q4^TfH($av+~ zZ;1bE`-S;2-wQu|JTN+alZAWne7iu!YGP)erVH(S7f)7id<*Zxe81ZKY+yykCJVD% zj*&NZkKV9yc)NvVzlfHbe*8GN;H6;;-LmS)ezM<}lf700b}!W2AKV5EpQ+%VdB5<_ z3jUc4|E%Dj$?(q#{+X?COZaDRdd(?w;Gg5lf`69q&#VvpvxI*pch28bPWvG~`MC>~W%h5f zkP|d5B)^0K{>u@X{P`5!&CBP_N?S>f%-DpYbnTXSr@Z) zl~?+1W;?jNx7C3SU!RDPdVKC(lhK=lXR(_1B%9=YKf*j~tMvXl@0aF1m~Q9zZG5)$ z6z_aNV;@yGt9NFrS@(w}ogGY7+T_2_DeL^o(}C1ansXGF9bUb2kc|AU2J89Y| z!g*fcz(eyJ!5=0M|IVvdux@Oo=%#XG$M`C|-!~&ORFKs8g<~i;)&fYY3 zcj7*>$fgC}!`sr$?|&&u?w%a&t&6ET*DY)Rlo)y$i%2@ht`Tx9+R$g+o?j<=R3$4_ zQ%X%{3tUv&X$ZX-+I+N?>-p4MXXzH&M&o*^Tc!W`Y2uQ($(F>4=D!T#(O$! z7N6$m%Jc)<;>qxS&B&72RftbHy89ntRXlc2!aJ`XHstEqiT9;K+y=^5C4GZ3z5m z*w%sRE)U(n0SvFB~G4!YbmZx%UxSQV-3 zuqjb|d2@|9YteD|7Lk9sIVbZ)t9c^D>!uBDf6?CMU%PG=OC!26ef^wxa@)ja#%5O< z*}A$pkI}^`>uk}|^2=ofY4a0!mu2__1^*+ryge-!+WEIhkd z4!11$90mU)N+l|n#OJjg!;--Nl!gCMx_#h(1pE&f{zt(7kl}v>{0|xaM>u*Tj^Td< z{10v5e+2vw8U7~#|3ilVi7N~KCkX$;boie*#+X-_UsBfx^GjiVkukqK%r7$LmxuX9 zMjv^YU$-&lmxuYqbj&aKD$`$>UkdY!>26t=QwsBo=`Lf;dzfG9u}LEz!~F6vzm%>U z=2sB&i(LDmPs(C`kuin?m|wSX-LqYSm|slC{PHlr$e3Rq<`>y7>%_#7k70g!m|yC~ z(0vh@U*v?*`y!zE72*r}XT%o@@dfuu5ML<77u1u8FBIYnq3a2~p%7o(#)vNz;tSd% zzEFrSm=EF$h4_Mg*ewe&g+hG6ay28qAVc#@#22hT;tPrRf{ge=BEBFazL1D7Xb%l0 z5ntTKh%Y4K3)&;TkccnHh%Y4K3$j}lVhV})g6S?}O;K3CguZvIUkd9N8S9tA`bEb2 zrLcZUZG$ySIeI>hv3@D6U$n>irLcaHv3@D6Uu3r|tXT@{7u(ZitSJKPm+GIaVl37# zf%Qw}yIDRK>zBm(r7p~v5{vaqV*OH&cRCe|HB0Jv=ZRG17r2b|OJe;}osYj9i}g!j z{Zd}4im_O~1lBKAquP_PZdq8r1lBKA!SB8B+N(|v*XOCkOu zBmPo|zsQKc6yh)C^w({S_)8)FqCMg-h4_n%_)8)FBD-ZF=2D2iIL{cowNYyM7BJzL1D7$3x)WC`v8b96ygik8S#Ze ze8GFP^ZhnPe4!9u&>r!HLVUq|5ML<77Xh8WTNYvph4_NyYL2puHP^%X&U#{f_prW` zvAzefzLT-Om&N){w*K%o#`+$_`p$H$?;h57GS+tw>pR&k3v0TE^_}T1V|`ax-<7UE z)^~;Vos9L}!}?Cf`tD(UC)@SnHpcqyVSQ&h)^~;V-Pr6(qp-e{vA)NZh4o!weP=q> z_c%sOT^8}X)b&C9E)c(y5x)z>?_|X90`WW9uBW##;&*}go#}|*1>$!y;`adJca!dv zg_u2v_?_u4Bc@h}-&KoKV{;&WSBT%$tYlB-K>V%{zpEr;r$!)tSBT$L^P5YuTaBTb zo?Ms6=btJ)9ESK^A%0hj_Kb@_{H_qct6|$j4#e*Y@w=)%b7T&;EX3~$@w-=I`06Z( z-xcC_@63?ZS#-OYpJA-)UyV;Jj*&Bt*5!O@F=mLooIDrjNGt5)6_{k^%cM#jWwr6< zOr~q^rcZi)kW4hB9BMPVTkHc zB`51Vtad+@wUfEuhI&lbj22$9WsqUm89?SSFv*_O88~{%E_|UWdwkd2NES zJG}cUB6)vp^dpNTQq&eKNluUQ+-Sj>0<&jr63fdItl2$%J{jf?mQOY)OI|fDMy}k_n?CKtp=gP) zJE-fd?b}*=H@!uNp|atWl)Uz})C1)1%|pmoUli6OUfX=k5QX)~)A?XMQdp13Sa%fG zBeHAnrei%)SdVCf^+;hoVxCx!^xE-9uwK{veEws``XaF&F(0f)66+D`jP*!jJtAY> zkyww&+8*l>?cH>&M-uB1ZLl6mtVgt|fbpN_>qbhqVfO{uWZQS1B=1IC*4#das`qX^ znXY|Grn~lT`lvm5Wcx*eHqo!7l|Oj3$#!nuGh4qQbv^He--3UucBL)zNfZ9A*Jo}| z^2o&9y_-o)yfz{_Hn_}w{?WB}(|5i-+q+)6FR$G)XQ$V;p@{)=!$0q-no;R`c7C?G zjLiNZ`IQH{$~AT$VAq-z6rq|r}it6DqoulxP!tUekKR!m}-(lLvwRh78rivfv^sTuz|JYZ8jcXXT_s;gb7qaqS_2jfmM4*3f=J{dkW1_-A6JKY~n?|<#(Cm@A_HKH%7M|D=+nv`|dTp$j z(95(x{Go#XWIFt(g8wALe=7J-GW?{1|0KKiZaVy@g8!rq{HKEdB*T9yN9X*<44)|+ z-Srih>h zyTrqMCqFXgn1}gJ#=KUT?_}5BO~-uqFyCo|`R-x9lQEV&%=dd{jBSDWu5>-`g)x5v znD5L7^SvzQI~nsmi1|*&y!J5P$*#Sdj`<$Me5VcOdjRvDjCfNa-W0l?h&L7DO)}z5 zg?KZd(-BvyIs@OQ9&qj5bi|u#(!~_K7V)O){qtZlw4y@1dCv^(DiLpbx<2>9h#w{5 zP3D7mQzG6ZBi@vVH`ykLD<$GhvbIOONgFpE@uoz)NgKqQ67eQ&uwE;y?^4$j>$}4G zPR9DKR@-w#SjQFCccE=udp8~HyTbZT8?5gN>pSzony#EU@jqs)>C%Z?|6|5_EwR3{ z9k9MjtnXy3?-J`f8SA*f`cBsNSl@3;$NDa@zB3)`yTtlVMm#PNzf0X#h~FjRcXBVB zt3muuMw~7Xzmr{iHy!c2MEp)0#P1UEJK46wJ+ti>rR#YwjCfojerG<2-xcC_GU9iI z_?=@6ak~0H_Pzrwsw`<66GlW-OehKh-9{8dMd@=4j56kk7*GjD3@8Q!0dvk-#{ejF zn{%d5iD}GPQ5405IbgyFf1SGBvv>CY_J4Mt-JSh*etaH>caG=QsXA4ss%~@py?Fml zSUq1oj`#0?_wO_Z@81FM-$@SMKXSa^q`1QSO^)}Q3Le^)iOz% zyx-(_ze#iOev{+T~{SZ0fr}>iN%L{JaS8^Cc*tpX7|6F9CkO1nYy2 zIpgO`fS)gcA?2_$evSnA`4X&eQ6#}UKOfFlkK^Y{fS)hH%CafW`1umx=S#5d@I+_i z8Uo};B0Z5G36LL&;uiUl0Qr#!BR>)#KN6h<b<0{M{$BR`Trek8)kk0g*Ei7@gb8Id1} z@XH1XI^=pHtkz#Wj=V`mo`kT;1i z@+JZDCJ{!i4?unrkaLiq1dyMEF!GZC@{Fke`IsLVglJ zeiG6F`AGozNtl$0{3L+uPeK^^NdWmt2qQlUAU_FV zi0&*OA zO8|LG2qSL^Aa4ob=!enpXq_OLvv-Vz5&e{SzS(mS)S7yQ)^!=y72fxp&0*bik7V{W+fk#&{&tJYsV9)j=T z$$v-D?Z(SArr)jjuIRf3EZ_9eBtJIpw$5srqC?kYgVE7J(XDB_t|A~%Id}EKHi+rN zN7DSTDJjCWf#TDLHf14rOFJ63@T?Ch7u*T^b?O9L-`Nn(>=X>+=02f4EaN{6_JZ^F!JL8^5fB3 z4cjq5emug+j|a$)M;Q6>0QvC(4kBaFOxfV_Exkv9*JH;*v#<^l5N(Vif09w2WXVdTvN2qSNpK;AII$Qx!v z-Y~+*8>U0vFv7?i#*jCRF!F{mk!|c<~(e+ zkl93zCLCKZP3JLD@k^s-dSfYPMSjaUUBr$d5i}=%=?x+gpAC|GyQx}=Xw*jWk@Jf( zu;Wxa8ZTD9KDfVeC!FQk2~OFTBs{)JFf_dJg!aVHZWwede3)>W`xvO$Y7XI2*bgr} zrkqo?{_61;iDSWfyK=6BTMq)O3s)35zFom~f)%Z`C%z$c>Qa~R-s`2{WsYL|eb=|5 zxosegkK1`r+*~+}aEswng||l8=Q&w3j4g&Lwl^q$L}znP*^@)7rm>CLN(?vng1K~5 z2wgiJzps-|es2f=_^!9+&!2QAjJ#(8dD{phZ<|2gHp0l;2FTk+70&HbCAsiaq3Q1LSR^m_*(-K;AYc^+Db?K;AaO z$lC_U+s5TM^0oo;wh>0&HbCAs!pP4C$lFF(t-pF4dD{Sa+h`8*wgK|C5k}rNK;AZ5 z3whfBdD{phZyO+Q8|j9;ZGgOOq%-oi0rIv9sSonD0rIvHM&33+-ZsL>+Xl$n267Ja zwgK|C5k}rNK;AaO$lC_U+eR39+XV8q5k}rc9r8vJM&3vx@35!pIK^$Q#M!9JT)Hapa8z> zBLR6MX)WZ91muk*9gsH?kT+6DnaCRn$Qwx*c_RUNBMBpKBp`1j*@e83fV`1}kv9^M zH&MhfJOB#gX~0(m0|BX6WY-blj88)-z|NW#dC#*tTz1n~U+oGZW0GcyrX(?z@OUbKcQ)_#-+@jZv$fz=2*`?rT@_GJho z9~vNs8|kdpUp^})(|H-lcr1{u?a_m0|WB^}wepM3y{_1h;KLPtsnuGnP!2Xjk_MZa#Pr}%L8nOQ*jQyt$`%l8ye=_Vp31k1su>T~C z{U^izlQ8z59Q#kg*ne{DKM7<1$+7<=jQuCa{*(3)`%jMjCt>VAIrg7~v3>#8UoK-6 z>n~vaC5-h~VErYG^;cm1CA_X+ni1))?bG8moU~} z9oApM4ay%eV*MqI^;cm1RmQ(yER9m`Ww8DVtiLpl^%t=I5|*|pexiOF%1GzDf8w0s9kQ)QJF_0SrxiOF%1ONIM;3>QP zIf+GTxW5B~YR=z*|IvF|3n|m==YIxsm7IS9|6`v?ZS*-KwpA%Z?}oeYkt86#0^tsa zw+iDWd&2sMYsD(PBjIj0jtGx>U5cX|b4P2{EAncG{9rk}4M)>a1dXO06L+^-O@wpzHfT{G3V2Mw{RC-_J zO`KDIgpX0`;PbE^!0|gYE^*57J2c-Tj|Y^jU+Opfz@rq+IZQ$Bkor-3g!S{LC1mSFSC2+EQev zD%S?!-hTabO-S8LdrsKo3&IKLqp{t;5w4AU9$e`?Vd;w%U(yK6J-<-nF=6S8Dh*!} zw#E2KuTlo2d{g`oHpLHNON^gny(3{yjG3Mlsu1>5Vu`T55;KI`DX~QO^U2y`$0k?8 zrad8CQQ0fP7ByBF2j#Cv_%80rXkUCUGV1eH*(<`f%AOFufO{3KSKh@Lhp}<(b4#+t z6f=ZPu|)XeKxY_O5_z~#<~)pQ7k8MEwcNwNQV;7(X22hcLzuH=kLIA8tO&7(X22hvs1XaEu?q z7(X22hcLzu$M_+P@xw8G2xI&(j2~`_AEwGb%$$EPevm^|$v+rB4C9C9WBf34F2eX> z=A47^!_2t|&zBC*7x^8}mk!StVT>h)=Zi3&FNWufFrF`l=Zi3&FCCsQ!g#)Pc)keZ z`C@p!2xD$!m>UUW%uAgK<5`fl5XKzKFvk+c{3&%NjQNvc{v?d~Q|e3@^QW|hFy>E= z`BTXKG3_~FlP?Hk{^XcH3Clgl{7D$|C&&CrSnfIIPr}j{m_G^Q`C@p!xRh_&6T*1D zIGNT3oh%+Lgh^H49qR%KGNCbs@lX=wTYj{ z+TjvO^@XeI1y|Jz!lrsbbCxLeg|5{^Qr+RI+C)%TR_cq?jbnV$wW``Aq z*CrWb4D%1glB!cGXI$Ch0H(Z`XXbSVg8|OP5GR#DbEwe^QFV{1#*8>^@6MF z1y|Jz{_ZdJMV>E)=ZmgY)h2nq%(cm^1Iv0Z_Nq9Z?zyjBs>^oG4<+nfX**NhTk|M8ZyG;5*NMx&awkkDO>2T2mvT@(VJRQ~5|(SK@1gM;8kcLLEW*l~%AUF; zUUpH93)Os~k^?IFpjubTBbjopN>5Pf4{N;I>ZQ&yrd0OI`R09)GPs-}<*4>eu1n)` zP5d{)I1NmDVIkL)dnB(_)>Qn3dztW8aSn2hTU{$>mA%rBG%j^f+55ZwRM{)nq4`o5 zmA$|7*I)VZH~*^am2%`?vmXhY{76{tfy!R4vRC?%=9v6QSlX)^mwu#isiR8H@Agx@ z&nkU>=NGlVex3H%Me1zwqd7i*=Xd-^kTc|7s`l-7@gx6D&cQ#@kA$V3D!-6yWy%Ee zT>Rf$oVzEvF_0SrxiOF%1GzEqFNguI$dLb4`X-ai+;Q57+&#&Shuj#*je*=4$c=%& zF9t4$el%{ePJgR*Ku+#xT*w}#~feal{ikHv2gqX#J8LHk?l{;TBwqo1Mttr++p zY^QiL*-qGGJII|f*-qGGJ7JUUg#R5f|CauLYh3DJ{`_w8w(;=X*NJSgxik`%dc+g1 zmKX@GMPCyxxw;KRrIsiCOL*6Xj=LHXUe(zK0*-Vd+(ma=9Pg%l=QPx5p1Al%`A+5k z1|6ht{;`<&$L_oSUpAW0ktw!mKmXg~$7C;;yZR@|jTFQGgCGA)Hj*uB-~BDD&QWUo zugcGVYu$g9{D17MBmcJ2&-`C8@ITm|dwz5KHzxDmf1pRrJ->hBcVoHdH~0SQzu+D- z_x$FbU+OWiub^0vbtD%nyO6sNx%-eC1GzEq_r(D67gw8)pHC{E)BHVH$~|-XDt)FY zpCL0p^Ch1lGe5ItdWMX0vwTj?{Op+gX?{izJ@nf%Yw|ktGiXwt`PsBSmA53C?ZENh zp52qrf0^f_oZp`Hlh2Tu<>Sxao((iTLq__@XUNQY%4f*T`pZ4ov-=J`vt}BndsNeW z!X`OXdra~Po7N?4(uc4~Pr@es2?rf>!)F|oJvZ5Fp8wl3hNk_YanrsLmiEc@@Zafq zK)Ig8azEsH5}W)&Sni*Ej!};PHO}=TJ#YKlvxooN{g~^o|1N*!o;%7*zdiH&Uz$Jh zcRW@JGJF2J>w@yTB&9B>v8)w;ln(fN7PM8lulgfuuGucNjen#Lrk;mO|NcE#siAZK zkp4%#4{H2J>Y$FpKcZKWeo+4W<=*~}(?L0VruC_>%Ef=CJ(1p|e%PGP|E>2gcxEwA znB(|Ax2_VyitV}h|L=XkT)F{cl5*Q0k#B9g#Y*J-x9@|x2K_PpywV&0r`9!{ck1W=KKz&S{;&7-zf-ofE?2(E$GN>aZA5N7 z~cC33m+R~LtKd)#!o;!wZA$+{Z2)@7lcf!|_d-Dx_9H|eO z{ro3h=u%U{rJHDYwK+WrM{dl=9j++v!1=Y`0d}xNB#lom`1ohSq5Ues*8(*OpID}Y`eh0e-stWJ)fyis-ByMT zfyHEIY>GX?rr0BFiao-n*duI;J;J8gBW#L2!lu|GY>GX?rr0BFiapZJ z6nlhCu}6NCu@@b+gFe@medV9kkILuh@-$Emp?&zX`BC}2oNWBl`cY-0tOb8cKdNH& zPwPij&iT{&@z?|V-#E=mPI6}QWVVYR4_~?{?;w4!ZY1Grra zJlyX|IJ0gYsGF?3Td)5eYxvYqdH3M2<5NV)QsupT<(AD9>7$kJ6ASNjWBUZ9hv_z` zo6cybyu)zfkREJg_E3^pB{qqDU90p$WoG5$1;;g~@#XEDxz^Q%FhA6c-~Fn*SFllm zuH1Qn@(x39dTE!d<$Ihx7qksW;nLItJ8!ROKAm=LqR9>;Yt-Ll}Di+2?>9#~wiT zIfStXkbMqe>;Yt-Ll}Di+2;_(9zgavgs}&ZeGXyl0c4*;7<&NO=McsoK=wI=u?LWS z4q@y8WS>JAdjQ$zkZ#xm$UcWK_5iZaG4}xcug)Wr`v2K_?7zyZv=3*Jr&kE&Re_3=;XM^(=G)A~{7QO`mP;^lou(N(pX_shBQt(%PJr@7a7x(zt(%jI~z2-RD+(p^U2cjS@rYt zm^s7vgp!xz-k&?jx<8KKOEQDwPLFQQia(CwfiC%DW9~oqa_S$&%igH!FngtqXdfBI zcYN6CaKU-4cr`4L7Y?>`ESL6LTs+c>+ue0_Jk+WpOmeKn7uD_JSaPu!lp9%u+q4_$ zIJ;{%XglCn_S`VVal+{k*zGcqX?*55F7G-HPM#X9TX}ZABVQ5&=RZ6(J}o!jF~K() zJZ3q{&l%S6bP*mo(Q#+h{&1zBEqF8>>{!~R0|Xd7ASJz(kSDr<_A| zkzwQDZN$X5BaZzU>o^1)W~RjrOFz!|bU(1!T0XwWqC&jd1_tYzHi>7qtMhe%m7(;I zfcUsBKKy;lEYVpvK7L=dzC87+LFD~9J$~c15xlCdhRBy^UVM#y#I>7X_8sP&->}-J z@^|T0H|NI7XRqb+<@5Ze$D5u}=L^Ee#mi^n<#XIqH}{H{&v47X`Kx=z%Q5+Ho`p(a zY*-L?Yt3RO;-m~It4A51I4N7k&7kzP(`C*xjXTKS=gBp2zJq-B+a$*k<& z(`;JTQ9iRS*Fb$7<+GS3JsssU?k4>m=&Gae%`4*uFVNxbE#Pkm^~SOD+4{Yy?kpY7^el$pH$SY(Y5X z*K{#Duk!x#5&Qa!4}+B+*&LtpS~E8J^xqnjay|Ly-yM^3jXyFb<$ChZ9~qN!y?=FV ze3-bAV(;xQgPjYCIKuXgo;h2TSW38kPIZ@wsgnuscj@JFs)aw{@K%#u`c$q-_;bt> z7as9~&PYzJI2X5y!wJ90G~mC>KNFza{LOMaL1HlOF1Z?u#}JM5|-Tmi!5ayHx@#gVStHTn^^ZOopm0*?=%4;Q><=^bzJJG!E%)wI< z&H5CIU7Bdt)4E-JqFMj%Hk%SB7ID!@U#u7$!W_%Z(8+UJ{NoW;c*zN!Jg0j~6ytsE z-s|K!ZQZRVPnxox=I@W|%dBmRFnMO*9cj+5TUs)CZDsodtjn>=OrGB-lLPtc#m$(M zW0P2b-ybxbNjXjr#ah5=Iyyjm*Y~Fv|Y-6ezO#pwl8(7!=)@~yOb?uN!z9DRh_DEY5V39oJ*UPv+zbIWy$@N zvZc*R&TP)4EGbjUmNqN-a~_j6OPO*Hq%0{@%9g&7GNrGi%}QQ9$)s12`-RE)kTPYwNZ&}A(pNH8q)Zt*(l=73^p%VoDO1Lgj2kIa z#*y@mlqr2BYlD;-YBeWb#*maLV@lQuDKpw;YP^ggDO1LjtQk_K_mtuBvSvt`A-q$( zj3Fsg#*|7=qpT%TW}oRE@hUxyvaU#(&E9;EQ|W0`>1mYpM#?O7VPc$WKaDCqg=#-3 z)=hc})qV=qep0NP^b{(;8&&%$RDKt#{S+#{3zgr6YCnZ4K84EfLKUAv<#(ZqPoauW zq4K*>og<-&PoX+T6zkGry7hK8;J682f~! zOpJX{ zazBN6Kk-Zov!0kcgla#9c|TE4A!Xtjm3}9g82fTRNhZd=^gGGK*q8fBGUa}v-$^FM zzVtiE#MqbnNis3^WiA%dc8q=Lcan**FLN=;#Mqa9Cz%-gGCoPBDLzRi#=i7B$;8+v zSyHByjqyn`G4?^qlD13PGS;Q-GCrj&X}gpyWl7sH_GK;xX*FFNSV@C(q_f)CuLqDnbKF%X2tIrGB1IY zDSahlUFwN>UY>W7Dfd9ex|AtnO8Q31l)jR&F7=c#C4D1hN?*xXmojBc$yk>%G0z*N zZ={~mSD5EXrYX;pOc_%$)}>5So+p_yrev&3nKI9(R~SOq-dtj|TDNSRqFd4IojMu!QfHa-ow^5+%znnjI=`EW&e?fx>tx(Zon_9S z-r1XEu08r$SK03n$t+ywo$hM$f~1?(c~>^IRuIYj{?eMY%kDxlOIzL2vEeSH=b`p~ zEX8jO$^2+jkwq5Ok<2B#MzfMjwvo)3Cw1Aikw3`SqpD71bB^>NnY}dg*sb8EB=hG< z#aP}~b|iDmQPV;?a6#VRDT!j@<3+U!{*6Mr(*S!3<0o+kPD zlRYclh~zW3g0jD&`LgDq-n16l!Q#hf(OJWvY~rb(X|2RnCAsQ6vRiYD(YpAPqYWen zZIb<%`J8f94q<2;>43JfIvX6}2KpC&a@CoYJtWDIbrtO-IcPT@;a`Vzz@HrLq%)3o zbJe+)eJ075wO5sYINC|}qTO6|#>$jZKic`54b8X$v&CZlD&gG zlQPa_@1V*{T$Sf#pG@*)@1V-_OqD;mD$mOv-kj%UpKQ*bT$S6oDxb^#+?=<$tPA*_ zE_z>B&G2vZ&f8bsZd{W%mdWuZ6{_RAxb_kral9h`b>CCMjW!qI@~@mD$K<~$a`rOi z8V`^%q%1jZlC8|iY~-XGH>&0fl^mgxFI4M-N*`Loq^EfeK-n;zEpbuwp|$Bfy>c9N zlJ6*!c1byeaZPChVO$gBUpYsP$$wMi>=nv2WS5Y#OWO@$nv zHncVz?LD9H$c8RZ>e(T}GYZ-B`13BM!-4{_SvLxZCz1PIxhLs7I zXIn&+Lp8$Lg(r${w#xfv&pgtIhJ}=O)h;W%+*mD3!Pnc*^~!px#8}>8cXX%U)S_z_ z&-Y=wYPk?zxL`iZxT3r>_B21h8ke!AaqFXLtg@>G;dOC2tm(eHq;sqN#rdf-2MLe! zx8to_EFxTcnKSRTw^6?@Q$OW*unvrxBV89ljvRJ1NlJLn*7MzS7b~5g>HO8iBQ7P{eEw6 zuyH+IyJVyT@9U+!8`(x*l24wPL*tdX1-E1+NrxH!*V#x1MYr4EHqhsy=6&1T@d3%7 zeb$XT*6KsoUa41;*S_3Z$bGH7yB2gep=XB!6kS zSG?T7OTw#HRl-xUei7%&*Cw3l-9l7*OYbq}my4`5dhMk>=RGf0(}f37?C}DJ9a+8# z8k!$fe>S^lr@TY*Ox0wTeBP4A<6<+}x&ik|hkbf0u20=Y`07M^Ug0RckD6D1T%DJ! z@y;mq85Hiuk0&p6mYD2O*=1Ei=3EbMS0-E(&!+bt^BQ}1h?ixH(|AambTMV;N0RUS zAwPWCaGLPWZe?I}yOo5?|ELPW&WYxiIJ<&0qe zZf>UcHuJ)3iwN~TS6!g&^B3Ib4tKAT{Nkreg6>@&l3%qLJ_j*b+2>*w7loUL@?PT0 zdt!y#{F*eU!igTDQyyjATSHTf&iKxEY2(F+(q5qz>HP9xKjmR7*D3S2f9%fA=B%Q% zsxC*r{dA7-qcB?-J>@gu1@Za7qZ6HF{=y|qB&XVw%+1TT{!V{>?-1?z#EI^3FmaiD z&pdDOu^!CR=4BF>FNyVT?oh%dENXzY^G3o0i&cRORVjz_pO)J|t2`E5&L8q4M~s|K z=ZLRqmm+GNu1w<#9XE*|(bWk*YZ)ejCe$VT(yF+acT{;-XaDaNjCort*m>nd-NkBk zXwI%>E^OaqE#WnuQ&_`gl?cyp*~ND3uqIrs?j5$XRW|A7am#`y&b~=_qm2zOnz4=W z_Go+FM>mP^oD40mT}VT?T-7@K+w^(zO!4+#|_r;{W;{kK2VYsgFPUVO_pmgl%Ih@$%J__vL=BT8z7& zqngN@RCvW|<+Y=|z47%Bd%soL|CoTuEbk!2clGaDvy4o|Uteq!z3gjK{pHC|&l?|A zryR={>-&fc73sa}{B4Fou-=Nl_7zMM(YHR34sqQIz>YJ=2q!cz2aj{+5Vkzz0;w7& z!oKb5Ky-c=vgPQ3da&%^2J%boo9@u4o${{TRqbP0yU$7tbee3zAMIL0*KW^r7yYrpH%L=&jUT=DlvT=5_A{1GV%r`mdBD2rO)uH& z%FpnX-!0|h|LyxwI%KD@c@KY{(c_1Bv81}#-v!@?n)FWCeTfjkh+C~r7pdCyVox`J z{yqJq=#vOyqmMuLeY{!twz(miF@GNUVxG9~^GuXz=+Adv=^;AK$r9rl`16C-)?)DO z9Py!%KkwRhgwZq20(v_8^Bo~;z5H%xi$Uf5d5g?=U7@rrQQF#{mpV~`WsKaS+k|+* z(ri|?aWz)6gg;-A`JT-<5YB?i`*UN}2kchwwd}c*Kfk>AEGw%$$o$Is^A1;bv(v7Z z*(1ERrT=nvqSa#-gLq;1P{4-m-fewe@lgAURVwArD`mG9nfFs!344FOZ1oH=>D+PV zTE(9`Tuv0<7i?yJrTux>gCipA$XsTD>$bj@A~xptV^>lCs#BheMO%uqWvGAq0-wdW z&Qo>sa37M7X)?as4*YfZ? zu@?1-Em()`S@=LyM*V-SK9*Uq^TOT5pYN@;nz`KFD?HGT;~n<1_QzL>#yI~`$VE0f zeWdV4Ihyo`?9${KA{6y+9sZu3Tn)xg4mck1gWU>0loVFcpI3Qk!5^0J(RrbsuOlqD z@ANOaUs31pnpGft}8M!zKdVc?-7U3 z8oynzfJqn+2NItowOVZf7f{cb*gCpuKYye6X@2~bE@9>y@fqXl{rV=XUZuMt6XVUU z`((DD>nSl066)*N0W`k?-G!>=*#@@?jKoSz?irP9Z&=p2o2^O>b@_GLX# z|92;zvzycBGB?z}-R=~2C~Xt7!t?mHOEUX0>o~K+a~c+;XJIc=>HL0uGlSK9@RIFA z{h#}{W!vX|VZ%}X>>l~ppn4X(2IheQg#vT~Eb?%7%n$o>#wC?&md&D3|ILN=7}p&A zz#b!x4tEkuA|JCJsDG^%_<8EpOYAk~pK5{2MWuTOnNEd$51}q=yzqEIzXmTw@x3023cW?Dw_EY1fb94bJH~u!@Ksn=RU){wL-djDgt}Fau@! zjPyzJ!~0opTx(9^D4m1-7jYkTc=)6syIS<6*oM08EZ&h74!$L8vzTSgW1<@3 zLPi5~U$s#PoO5^GQPy+(Z1D)MO=^3KEzRyEJW=L`#24&J=fYwnu4RAhGy9NttZ@+P zaI&xkKR2$DS3cZZ=R$dSxXz$EfjaY}*=*=0d$tPk@B<&&kCXk`bkyJQFoP|BxP)y% z+c(8sVNXBoUd-x8BAe{}mi0p2Z0~xp(i^_9 z3ApD$84q>uR$1^vsDHoxRdgpWTkuloqu%Lxj5}6+XYcUZ?H)Ib6;Ece9E`~tZXP1J z!F~1#W3@@X@nSWcWkoTDkK;3P#R~0V!%+WW?+=KdRxf9-Q0IJkFN^Y)!&o@t8ZM8; zpr2fr1L|L`_Xlx#?;c%o)Zh2h50PnH=rtYnzm{nM>z)0LM^XP;-7TPYk-Xvp>M$hHYFPqcZHC8ALO4K1xj_P!jk9rZ5|I?cEVYtJ3jzt6}?jdh+mqAbpL z3tO$r+3-p9KsnJj%Q5TbPlXZBcsvha>jz#FBk=5(>a&O~N;ZnZnA6(a-Ns(qtrrC_ zhx}6I6f0hMia3q>vu9~6ba^vz1jmyc-Z1yfH^xDz|AG%+Sz_J>#s{dsbEE|??sDDh z1nU3ku?3$Maz1)QYf~fz@0}oi>hhJD%%z=3Zoo7KW z_pvsZ8|_Q&V^O+`%p2#g&AW;vA9~0b%6U2@j2-cR&w8Q$7wu}YB_Tgp3g+Hsw~pwV z-nZcMQ2%ST;58%Kg116F)3^L&oSg8La`>t)pN+}mU$Zedp8v>C;_%ix>^{yvcwnl? zK6;XkLpcpcZV;C;w=zeRKlYFigC{LuuDI@=AJ;`Yr`{|8^;uHpnW$LbmMum-y-Q|^ z?V$^Ghf)6zopOZr>+6jG$1TtglQ%6ej>7qN`W#U>Un${?a(rfFiQzkXiXXT?2Ub24 z;@W({aowWY8^Y%J7GaC~*-8&$DL*L|qn;i6CJ2k}cZ94#k7K6^-%qcED~>Pl@e$h^ ze-%AY{~zza8RvJifKuqkyKZfbS3X+6MAScApXgQd*B|0%T(^I$(0xgJFWgX{$(yUO zyLBE32h{UG?GbEyt&74I^$%aQlC3LqK-5FOINaaETmx4NJGF;RXPq+|(C@uczO(D>Wzt&IfA2X99;2(RyNh~`SZBfOEPSaui~2X~ z`Hj`JZo;19x!9$D!yc8I%u?{YM7Oxh`uoJQZK(h4NvBxUktFsI^^EdQ2$BiUp9VMz=EgY zeCtP3j4cB{v+tTW&NY@(kfL9$0STrv* z$p`a8P@X*S>e?>jRMdZQ`)twhepQi%xa^$|qU!z-;f?xliG3`3I4l?EFn{jBJag&t zF5!ZCbw$1Cn*zNgUOv1c3#rl@9 z@g576SohnUW4?tBu|^n^{SNM8U(&9yGZ;} zj;yg`QP;Csq54>tYpm48W?1mdTK;^K#iJytyOkiW{`SXv>PKd`5GuU!B)N_5R zcw4Lkd*tEIryhSHs&^>DK2kFT~Js)5Tc451Q~IRa7grLCk9J&pUaa6s35Q zD2wC!Vz-NX;g`ioZ_Fo0mx?y+9ttDkxU3PPQS(f39OqQt=q>`YzlvfVu&%X!XbiWr zfX==sXN;%u;7SXaf--A{%=J2Emn|&YV9!>0gYM@$pTx)3=%WiZtZ~!}Q48nHj%&{< z+TRf^yJG+BI+cyhI3=$6`|}1fVwt7)9?`rT_Vd&Bv$zwhMTgG*94ybV89OJ59-UCW zK8VE)PflAXR^LOk=s^LXhKYct}MaRbVM#^2e4FWrqpf>7u6Ijq&|onFOy z`ST0m7JSW`GrCPUe|X*Rto2cMmfRidokb>FbiS)DyuUx+n3y9Hb%j~}-q?Fw&k_R$ zcV~K>v%b4-u;jW}juL!FbO#bhVh{@{r}=TEA2q zAud~dV1an;mQ#*m#`hm=F(7h19`L+&_Xq2UdaiSc*WHBotSnx8 z+s26nWjtUUuU*h_Bx~bwjy39ub+*@P=J{<0I~aiX5iy5Y373WJ9^xtuuCZIkhp>%! z?Xz}|q%B61EzCd1N+jT(e5{_uO1BIYVJOqx;t4y`Xt`L8`aCRpiCJCUFJ7WP_9u6< z-OaBGk3j6rrY>TalAZ}qTz7MWc8eL;my0E6``J+! z#mn$Ok%?;!d!8ZuV~UGLc&)!SOKk4g$M^)t_ixG(EgIiA*dF!d3o!qv{Dn3$lZ^sx zWF{L0+Q>{c3bc`#Y!qlCGubH6MrN{6ppDFAqd*(E$wnjE$W1ot&_-smk)e&uWFtcx znaM_mHZqfq3~gj48yVWjOg1vKk(q2{Xrs<#BSRZKO*ZmeKT@pb`Z4!B=AOsgy!tQ8 ztL|?cj4!Z$ea6oZY&tw_Y>hSa>TC;GVmlD37453Evc1V}Rv82C0Y7Q|F3w@G6{Dfp z?K)ZqpU=7#H)5dV*RtB)OKgmHn@57%zE7HKg}gFw>!SF<@Ht*S$&On8PceMNJ!j^!zpyrP?RdVp z(Q4N1Y^rAVnJ~Wm(gXJ7VOJyF^3j56-UG?AgTJWK-hjN?9&HDRqlUVsS=p55t}LS;BU1 zYku)VfT3d(J1G0cjbBI(HXJV90Jcvo!#5ueG{o4phm{{+vZ?2L8g9JC_X8KwvnpBb z4WqM1K*!aMS$HfrY~K_KI*)xPA|~*T@N+GR`Gt^!0|#XBZfLUOMY`RELA>xEnA zwrQ}|FTEx=d~kp@WrMXv>LCN0@VT(8PZTSJxgt#!>&kL?*X4YRi= z8~dyX=l)Nc7`jdzB`nSk;j?l&7%ne9Dr}GT4jMe%#l%U~d=0SM)*xTu=d{KT6l7!(QihI73`T`Dzj0;|S7KsT?6#_xIo$eS1fl_TOb zsl`u;BlpIFO|^TPqwizHr1{ZsaCTAculH^mS7Q7HxjShCf-C8s86v^B&Qsg^Xk(W8 zZ3H-WY_0Vvt7q$91j5s`e%jPLuUK@6_E4x)fOg@GGTf?I1IUUG)_%@%8pRW;TF^S@eYO=`lzE1*zj{kD-;w48oL9QW+Tw-4xTXtt&ZeA(NCm%ABcI5|ZNv%_4tVR*3Nd`vU=)~gVAa_ei@ zYVd=mi_bIH@4kkvqX$E)BU4%5JU<&cRU8YA>c7>6+^cU$XdDf#2BsxV)jAlgpT@w1 zigiS}+XW31T*t$RfpKE##2b3AcOzlnmM3Cby%qWbt%D(|YH4V~YU{6@>HtmC>%i{s zn#89zo>1o3pCOg+by+>95|m!w8@eX-*3?P*E>fQigC$S4Ys!DzFMJ-1gD#_9YCc8x z79pKupvNp5?epnNjM=_1kTA5G_SE-9I?wmxAo7P!yT7eJyOwu2oJnq{-9K7PM-+YUcAwePwZD3Mh^k3XV!OT4c-9)rTNOUf?jPHsnZ9^1|5Tw6uXM1lrq&fdeyXhtpRnSfOZnJlJZxzb z9(1x|V&+CIZ*AR;@7-NPZ-1`{ALTWOUkhBWcPep}*>o7gqfTDePoF%SRk|0&$8|4g zh&_>yWoO0kwbQB?E*6`R)Ozc9?mND|;n653@%&yGzj@xr@OIBHVr6_k-uZ^FVSc*@ zA~~WHe`C|v(C2^+Se9(euk;Hxv^ZKDHr=YsS3e3e?EKgg%6-JoMyK~S#5wyz{9GgJ zXu`jFiSFlO;9~Q# zTFd2*MysXKkUp-qcCRi)_wdbFh^o^}TjNVK8+R-OB0qN2o}2tDTM^U)`jz+BY8DsZ zu2a0Bc84JCh7wM^ZEAJMHUw+)Brv|QCq7?YH$ZDKyeqFh^`^La)K44sZ2B0-Ft;yfiigXDmrsFpDEx4F4JMmZ*NB%0d zCm;OzXZ?+7`MBq{A>8;jLBFN)F?M5WIRD)8q26)ZXclojnpYWPWhmD4m@a5%3~zPM z*^sip$GEq8B(M9ek)cwN7GhVq5xmZTHU?McEn-Mw0M`d~H}t=liTCMk`H!doL-F0^ zAlk=+f8QN!XrEjU+E*{nC)foUY^$_|i%IWTuNA!voB9X9!Nyxz<(eH0=Q2Ve;ujzG z*t4mjToLqxM@LDxYcQVuU~5=(FB*RBA10FfebVpV7!I1OWN~TTA$^q> zL*Q+Jd~l@gX#Mk7J)!4$2S{x4FwrBh1w?K00;ge%oMZFXf{b4~!=(#lG*how!{A;0 z;dq0&nw-ouQDe<0h-i9F(=cb5_*gUwx|htSJy+IFbjI4_b)us7QONVd^XElDzh>^* zvW`~FGHx^sa&4jQhQE{j>^Ts!Uw6@t3{PQ}XS+ghW^b+UrD8nOf`hI|ur@lZI)5DC z1WB!ewYnzWyk03wXtt-1wxn$jes|L;VXO7k-k1`?-PcVJC-1b>_Bb<^d#p`04jSO0 zoi#I>f4W^>S1h!$7B0u|#Gpp($marD_k)q#B{GpkdSB5%nUVa(q?fF~n#CGpu^=uw zmEmL0Icb(QXwUa-b>l|2{4R64G{D@_n%A58YhuD=JD!-;hhNYP)K~qH#eDA$=g0f* z(c7i(V&z9f@TFtk>g_zcu!0j}xVA$n!|R(dx)_HTUba{b16yk_>U)gi)}6RPe{p~q zSY#MqeZ0M4Pf(I5G6H|EzPYDiSeOOaH}c{AHU=7AO|A?tw5~kqSg_&M&PK4dc}f1c zM4+Keg-+1k_aR$1xQAhQKtCwDe>J=CsI6h)zA*SATv#0ooxx}6co_e9x!2$zts&_{ z3{)PQM+~Y{!cgH|6uh1|OW420<7 z4u$djv+YIdyT)4Mv+>A(IM(IqcxNp>1H^j--O~A-E~QPL8_nNq{aEe67Fzel5q$je zSk}xnMRT)s7@zp$H5=V|p{DkbKyGuO0`D-zMsx5(Yks_3L*9G9Zl_5P>+;C=?Rj?h z?8KmUw%l=D5ce5AQ9q#VbCwt}l55K*>lfACz)HM{yuA;FvqkQUMZrS!De{@ zUAg|zyi1s?VbtzNM$4$Nyt8FSp zy(5AQXS+MYf)&+x{4c?V5yv?6x>l4|&**E=hWf(xde_;##(stsFc550=dzn8S{Y`4 z9Std~3$d@IJq^|OMZv@^jgww)s%qH%Ed~Z#RuLsn6fs;#9S<%0t`s|~rs;dLQBbXN zy2xm?PQRi?e`t251hkpsrN3_983w$s1v|O~B#yk&7*cDug!8kOyHvki1)9z51+TRo zG#7I6z?eQm!RCiS^YjpiE+4|7i(Q7sV%acZ_ahoMt}m`FerK=o;i?!2e&V9_7!jnK zbRhyty=bf*RlhB>iU@^X4sErTOSUtY3w_~BdUtKkn-8pcXd7q+0ov`QEAXkG-Qjgo zu=cujeg1T3Sy=WYP;1qo9Y4SNjfkt!OY7|w$VJ*l;XSp3w#0-HeDScRLijb&ItE8_ ztDox`cekvmjXDy;FZDdHTX(6ncK6`=QdprEZ2VBzelM|07^gUUFuQ=a@Uv5%K@7At3_l+FD_jFjG zf0LNX?mLX;rORE^&t0*YO=%m&k9W;)xYwjKJ`X&BhkdDJ*i`83fuGt$@x?#YGrSBe zEuK~$&HH_BVbCWm7SF~G;PobVHH7X>6+fNo!Vk6WW6<~(hnZ(}{BE^iL-N@gu%S#< zKB-QyA+_^Q5HmkNf9c=HuryCkc>D7Srd{0Cz#0#M8Z{!Au0%_NhJ{1Ldgpb6BI_C4 z_eH}%V?ATLp7w?sM`ED+lBObILw-ZYz(`1WxlwrZzNjA*H3Hrl-iVx)3-nf=fpFu(R1PO`b;|#KrNUU~Io% z^J2<&5ppR4dV0Orl(T6oTKy6OBW9P@Zu}8w-10pdh8L-+EuC+lZos>6Xz1ERTXWwq zR;kxeNEz8d8+8^~iK)HdmVGbn3(LHGM~#*cbth0;=6V%g_;oF)0m0hADUEsSqa~p2 z#Q<$eE{Nm&<2Z)tIsT$kjXg zF=>;S0ndBoiA4<6WHrXKB ztPbKEUHuG0{ho`kSMB-k>wOJpd~IQubwfUFS+L>J%ertgs3JczImi&YwH0)9_{usj z@HZ6e(+4KG>}AQDI~hKQ4u^R={8&u&=7xLj5l|p?hOYA#SHskyF|cLhTH~c7CMPNcQ8m>Y_NvM%-2BLgkWvZ?513-EetP4_0`_K(~WQJbV(cx z?WTQxYY^`oKSLZ}|FgFB{xSS*`ZwcZLj&#D;?exY!EIirOFL@IX2$TxKGoUW=Y_N} z!^iU`^VhP4cW-K{4-VrZ`w`O|UZpvc70kE2F3D$vxNBC#cjU#cxN`ebUM|~9HsUq! z`Ect?n-U-Fw&&iD@pt}nyX(hy$ziK|4dV@lY}IRy9%AF?jpOHPKG*ke6U?eNh~e$0 zmoR+yh}E4Bjp4=SXborEPd5(qj^H)8&fpZ?O~lL|&ac#JXUMl|k2nzBhg<*B!%%$3 z7xDE%E1pt0(9o@6MR;A^jn_FIY)HJ?06wg+<(51XQ;$_QluM0)!;c;qoj;c}EF2OI?tLeT%WL20 zH_aalqg$R49=hH788t(|m|_W)();O;|I!`4x;n#)yvGwW7Bz?OYdFN+FX)nfv>N1T z;tTB}T{PwFi@~SW1L5+mB^v$N>tcPzXb2v7RdXk3o>;Lp3KD*{)Gk<6SRDTz1NBx^ z*1k%1^m_bsJiOWNp`9CR&muaHf+JcV?d<=<-dR9bl`MNdxVr|IK!RKFoNnA@a0@oL zyGzhva2W=N!2-b-|6&dPcBy?fVWtt@_2>h#{- zyQQj5?e5>_i0;+f>)@6R1Bxv8LsYL*PwzR=GGO|Mr1Ei+Abqq>+kmGV^T{`#v*_5- z+6IKhuPm2{=(@p$76JL&2Fsz1_NePy>IWQ^-DKiBJyh=76$8rO94LR9vEBLcW8r|p z?}y7mk6JpO&&v?-bzz9CbgjA=wJUl+&YOc}k@xGxvDC-?d(P@9lk|Qq@_nA@-|=}X z`SGT&tXevif1%km(BWscy9Ir5eXl+S!>$?f;Y&pNro* z^pcJ}yI1z;uv%29H$-kJ@NQ-J@p58dc!+#mC3V=ayCofMb`O_*7v~GBH|x0be$9ch z{+vI8!cHmhyUE+BjIbl=V zu#u}B`qb>ivUJzhVKo-i*NcO$icJNYggtH4LF=qDMY{}S+b8O$*OpI3*^#BfVpbTY zkL1^-E^p5f_VjCrPWvvo+L10%*tjOc^ybX8_5}U8GJaq`ovzRo_0!SiE3?e*peH0u zth=YLva;8Q`g-E{Jo@zKaVy%y5&B7iiaKeskvWr>%dY>t+EhP0P{Dum$(VY2x~{rR zk7fQj?;TV{at+k6-`(_o-hYUiy>YnS(Jf)Xyl1DJOZSlt@ZK+=Yq3I(#C?Y7JH<)` zlqgsRj@2Q#V*2RnwgF;C z5$SA{PG>Gp#-*c%EY{+UO8YW6AnnFha&h8~DtKF+fMsoZ%Eg^)si{xP25eS?<%l0T zI`b6FAMo9*5cyN3Esj^uQwPkC79tPM?Lt;+J<#?o?dy*i=e(&U%tUeuKxXC_;DB0)0wFn)VkZ1sed zj?kOpUGBaz+0~;f!>-O1+s+J?bw5W7oBb$@nEf$Cu04}JZ2aiDL7nyvlLLDe4trlC zjyj#7zg#)GVpyv0C#z#uI?DDv>xUh1o>x!iHI((2w+P!XBY{rvLCWb*+l1X}mP?l$ zkwXq_*)}YC?ee-&qd0Qz$ChEkYc$bEyHO6<;)Y>yo^;m5M~xP7M^y={*=c}2SL2?e zTajX6bz2SB{YOT3erb^Tka8LSr+dg{L{VN=zwLx^r&D|x`X6%(BuM2J3DBzHjCnhPD9 zejTKn&kzB*Z?zWn8}-({*Q*7rAZNR7oGgm+uJyu@HzNM-xlYQv*6r$j6`!(hElqjX zIt}IKy`QtxL3!7@-{vo(;<${QcdgqWe*8b=oZv{*P`5%DdJNK93ZoGd~xUcdg6pa)`@IBRFqU|GD?RW8oSf zNqN^gXq}%U|9&4ydDnW}@-N{j=X~P4Yn}h$8E3z{F9hXX>p!XlD(AXeoG+@|y&bIf zZau+y*ScThg(_G4Eu43)lilB;#?6@{DDPSqdHS1r^s2i!NcW%r$Q{+bmcO99YyDTH z*J{(Loes*o)-ip)sJk0~3ZlGgoixHn?<(EUNqN`$MP(oTS63g-yViZ4d{9H?R^z;D zJ#o+z)oJ}W&YRU8HeXfks;}U@Ydv((LG@#oJ)C!~bKGB}mS4N5DDPT-f0W*h&is!vd)(;n_5u+wO;Jj-+uYD`wU-JUzUF(=XOc%8tJ2~%KS2?p@RGzj>QQozFH2APM zzI=?LylcIy!F4gFTX{u!*ZRx5r((_zubh-Krtd!gD7vK$a#G&49y7^DmY#Yhi1My= zLwawh^T~q_%DdLN3Vs$HhUVwIYu)+fOL1mVKhBrd@%(O!4H5G=?^<6NbxN$dw~h0z zb=oxB#GRC%^(^iQK(EqnyO^4m#dG_K}o# zts7?F7nG!%kEFb7eJXVsr~m4YoOi9qTzT#69rl#-uJx%$71Ym_u5-?wj^;a7?Fv53 zdDr?$Jj%_BzFtt?wSN7hQi&T*7nFCcgR@*v$s$?^%DdKCPCrna`ll9@cdb7~ryP}~ zvmKOotxI+Is+!-sR*Lej^0x~X5)t}V$p?^^rLdZ$`kYsz`oI@Yy^ zO2?hbdDpsH#6=abb}i>!>;AX38no>o=UwX#J3>{S9ak0QUF-Rk#;GlbpD4<^)?3n5 zRV#~rME`kG`KvRcqmQP%YdvyuJ?Df+KAQ5bb%kongN~}toOi90uHESv^7a+yUF)-9 z0bxJue-5DY$&r(QQoy~*8PMy``aKzdDr^W zg57jWeleGW@~(BKDL(Sv*#{2F zyVfI`M~K5kCFfo1y{Ddu^}|MC{Qh|MhG@KZ3FlqwkWxp*uZzMt?^-`jw^0lTJ|}Y1 zJn-(?Poiqy`-1YW_3E*0MX_{mIqzC$td>E%fAxj)u66pZ%N%LqN0XFytyhISD?R_| zSI)cEJ>G;kH+Fl^dDlA8{sgLa_D7s|trt{jptdZ%%z4*3>)1(Z*M+^DcdgfktX7k+ zuN0Jbttsm#~~L)79dFBIin>vOY8C{^kc=UwZ^ z`K~*U?)TA@cdbXQPvU&J#z#}$wO%tMg`tH*X+OMX#4m%=UwY914@d_jc#(@ zwa&ORL@ZB!ob#^r&R)NWIt4ay-nHJhc9;0re3qiTYn^=h8BscJXGM9}S|zzBPWon3 z2kD;k1iTT^if?dI-nE`K;EQ;htA04;UF(!Fqsg*-%ti6reVi(Pd8JqAw_ zd1^coly|MiwyrPAFMH2<*ZNwE1Y%f9A4z%Fx?q)&j(ahpNy@v{HG3xyU!uQo-nDMo zY>6}M_8ZQ-*7KiaP~{rm=e%qEqES2LICzfpuJxtxpVaq$;hcA^v+mfaqAgk?DDPT_ z#y_g+mmei4?^+k#cSDt_Ed=FV>nYKmtCVjZI4JL0XPX|OjwbPUP~No;4fE0c6Mqb+ zylcIP@&kWZciKsL*E&YnC-vahBAj=vD@A*$#&j9XdDlAV{4JF&{X)*W*0JuMPz5*d z;Jj=7yWFCxsoyy7TED+MN6lDzM^WCj?m4Q5`ZMoq&b!u~@A|8V7oR!rTKA5=+j*Ay z9OYf>wq53g->vSWDeqdBjHu_x5bY!9UF*V2zB*3LdBSgwTkkt_2yE0MDB!B73E#)Z5u9%K_8na%DdL_qWvY>mq?~4?^467_V=fP z@~-v6Xca`z4dh+xK|5bNe8>Ap%DdL_hYCl_t3HzQu66O(C&IJJ&zyIy1EwEv)=%_` z^RD&gJNeY!s<%1sTAxYYPYwI^6z5&*RnB>;d5vwHcdesu+NSnao-ZixTHk+oQhj*U zS5V%yzMS{An!h%mpuB6{BH)$UfAWwc2bEK>&1ZG@=Aj_UyVg}`4jy>U;iSB4y|kx~ zj<)2Llk%?hweXKBZ=(vFcdaiTdaBA@7{htjx>AqpYR#!-oOi9)O+Ks|Hd35-t$!)G zUafd}UQyn)E<0zsO1|!aqP%MzeNs!c;n7>pyVlner&0HsedWAsefPo~=Y3jxDDPVD zeUoB$?zvw%?^+i>Jl-*U?K{r9)_?jY6Z<|t-&v+d1m|7rnRD(tD?EP2dDog= zZ&iao-r&4z-LT{+b+hwP&b!tv#x7CK>TKk^YhA5txSF16rl7oQ{VCr$bt+XmL3!7@ z@pt#tqgxroSi1jr(cY>(zbto9-nHI(|BHI$A1#RTuJu~7#m4U%=A^u9{p{UWwZ=aI z=Ur>R(eKstZS^_tS{JGCNaZg-iSw@Ypp%!?#7e66RyHCB?wV(5@b(2(KD%btr z73E#)g#HuM$8L`mrg3q9~0`$~mnxU_(&qJoH>n`slYg4?7n7H`le|eO60V0ij91 zbf=eUM3I4FZV`Hpw{EH5*DVxT%Qn|PQNH=TJUd04;$*`Y-mLl*J0sc_rtvj?mbx76 zt{6!AGY555oA136=SouD6XaCe>HUl86=?pSzs(tMosSGEPqx<0pThTN^pSrBksVvE zzGG3u2Qj=f)iK2fN3H2k#U0UHA1zr<6!E(uCRC!iH{U4nGVW0^<~y>lRxB1%l5G;L ztB{@lY^P{AZnltAexo9%MV5_yL=)mfSN;@d{ECQ?q;oj!CeOX2orv};8@!p8id77&P^w}FN zABc%lCaGkN$R6%@Nu*!6QjKj!zEAS~qFty`Evd{jlzTGi&RNx{F7>5uKZ$sEZ>#ad zJ707clgqqN$4SR`TVXLX?4t^&&pvH@&+*rtuWIr4w2m*X8@A_f4xGGhP=KA=HcWT<* zM(S7k?7jgHm8>^Sy(gY?|Gc`La-+IIIxpMrRzU#Kz7D>jx{&k(Wg z=W=tIod3+Z!P=Go%(=nZmH*7S!P=Go%(=nZmH*7S!P=Go%(=nZmH*7S!P=Go%(=nZ zmH*7S!P=Go%(=nZmH*7S!P=Go%(=nZmH*7S!P=Go%(=nZmH*7S!P=Go%(=nZmH*7S z!P=Go%(=nZmH*5+-e@;hjyKnl^Pf4#o9oDVvz+72b>#eK&hh3ta{e>tcyk>&|Cw{V zxsIIw%sJj%N6xq89B-~8=Rb3fH`kH#pE<{y>&W@foa4=Pmo}O~mk@KH9 z$D8ZO`Olo=&2{AbXXUCR=Rb3fH`kH#pE<{y>&W@fe?P~+pX1--@$d2Y_q^)Gc{Rh` z2!8KLzsY;rafRYkS!g~FPIV}#&bF_jF0Cm^O4V_842clyXdX`Z;({}4#aH4X&ChS{ z=TsAh-50~?vxmyJQk8~W77K{$Je;7WZaO3?(0Z|~$})9i{U%YmHTk5scBsm;7KnSa zb{x8KT$Oq=N}Ql;^{RPYRSl~pPSSeO;KxTQ%kq>$P&u{AyjA(SZE{GGFRT4oE!qDh zXcw*Bo16RS&?J?@7f_i)#`tL8_s>NQvO`K#3=|)R{vo;&uedW@9Bp=3d?Xv=(8Q%; zVE;8@PF1qWW9<=Ln@<*5CHY_9T@sHP1&h%oX|1{cKotHywOCw&{I6bbMTX*690N;H z4C;7(C*I-W?-k(R)zE+{u{(ih~ zA>_PQpS8aq?^_5t@9k&p??^Erb@AqvFK`y)UoI$*I7Cvw7#~5j!Lwo;2Dxdes z!JdV5UCGSXr27H$HR(RVd`;d%kab*p3WDnc;Q-R&#ttm4mnN^!yb%s z*0Ne+`bO+$C}*9TF5G82@QzaMGadMR3HO-}bUp*0Re>`g_&f^tnGSqTh5JkgKEJ|! zrURdA;Xc!W&%1D+>0r*m;H%JiGjtvcUxS(DxCSxn^EFt`~4W^CB7cz~xru^I!O1 zK68f8Bx2_Ch3M=aw~nNFVmY7n!|b}I zX6ADEY#?SXpMJr7P5K*{{={c3f%%$L7T8>qp1Wj0P_!eB(l+0X?)oy%U$oZP|H!!JbS6guVD|g$OYyRVT zoi+24TwC{ADP7p?wYX``7ssmiW?#M(sRxPvv#{^3yuNI!NYmHs5%;p>LvcI^`~Au~ zH{#2UW4G`eB{MwCAQPjsx%enh{2eE7t3qHG^jSO!!c zD41s^$So&Sz&a?CZOR~5+{OARC(n*A-|WJ=EXz-SAQqj(dMb0=-6DEq!a6H+3>+Xn zSH!w3UsuK+%rrmI9)@IZ*mbPts&C`p2b69S!|W^A?!cbXUtN1nUOE{)=*<^1cfGD# zD(K2b!yhj83fe&XLUNf$*Uk)j`NDAFTcJTGo)|8bYI~4)X!!RkM}o2qH~eOQu;a*T z!-;1HI)UE_9+`W+4DeB8}(I@oZZkp7PEs~X;(Yn0?xa>&X$jECRJK!j~+VHru z8y!{d8J&V3t~rvQF+8c{El1zohT9Fg>jh-!^|G47oKGi%j250<88V$V&??I3q&IErG?R15;waz zCJiUfnnM)IVmL!df6@A}*$2{RZf-GtyWuptexVL zA8#rWRX6ITmpAGK|Z!cnZGCbi>M=?Ff@bTX|i`~o2 z+WObeqs5-_W;~WWFif=S0GnAR{;sbG>1A|k&l)5C6oxy_8Y^xmFkEET590g|vp;Q~ z!as^5Z4Ea%IbQ5dVt8|hiDJ?f?1wBjw3{T}EjQe>&14ac_Uh+8zopd_@uH5|BX@qb z1>#5>vwv)|nX|>PZe|^i^<{==o!aR9nQo!zeZ}ncdNTPU;kU?ei}=3?-yp*;<}4Pz zzr${kKjmC1a`rP^cJnf^wV2_JVavt+cUf=`dlrU@@EwMG&R8K%rZ@ZFemTEcyl-Uo zcTL@UgQz(vGxUeYUL#6hGIQ7Q{aZxs8HNjN+A8AIG@N_!HZlGh_J5XnGw%?YyBJQp zaHlx&J{`(=>bqME_|@>hSmEMGC&RPoUC}*R4OhDA6kp<{hW?9*$Hal|*oRr3Y?lVFL^gF7!|&9U2Sz@g}?$5qaW(x1M}10x!e`_lxyJJj`Tt&eeY- z`t3FQ$0o`AR%~fwIQ+p|art-*=-E0ETqgQwkvG5DD>&$Q3|Z-H1lFudiKEMhoxXx^R`ZeV+r0x1$`w;4Tksa# zX*s@Yy!>6Lfk&9Y9hrCtu zII`=sXW(T!;>hCh?tt^nO(=&yHv8ya`5IqVKkx|h(3bIJ@*=mv>RCeBIT(AV%P$oZ zNjdfwSxJ}`tvTNum@Pwr)WiQtr+NlbpkZ~_uguKy~WVDapN$}g}DP_f*C%_41D*5%( zaqx*rsbrVQ$G{=+Qp*(?%zo5$#-^5=Rv(7Ej87W5@4z8&%o=HAs~ZQwJ!hwp6W$#F zkNq=^+>&JnIMucEa$B!(@DJ0{(Vj$mz~4E1W!oa#!B4YhkZUS#19$I`LH^hXew_Si zZ3a31;%3N$(`S^!>Td#<9G_9PIkOR*>upAP`{o94sgjxG=VxZW?&m`?$<1HZL0(N| zlH=zs25%{yO^)yl1z+{eDr-zz1&;eXvz)T*7x27+*<|sxi@;g8W|L#KECg4hy?Kk# zevaJ!Q|n}xpJ&Vi-`JR4UiC5ibr(zGC)3B719|bPelkX)+2G$t`N^5dXMr<>`^hs! zXzw^GXZQ|(+4ssM@bkSn>0O!W;4J%d$T5NA!08|R%ZGtKfE#8GkkN{c1sA9rAZN@T z4eqooKsNs{61@CXfNa-v1o&3DTypHM!@(o_wg4Zg zmRCMm+W~xiL>`&6P%m)b^||FANrS;>`{tF8V>AU1qIdO%yln&yKb%+I3axMC@$$*I z_3MBOR?8<}`P2g69-mL{d~WuBzfSqg@orXyyw9b4^6sh1;N_q5$$krRgY!HtAY-=< z1b?YrK(5XpzA>Y~6qHAjrvZz5sh5SkCuG_W(KH1Kk^#?~UpL9j*)25zKX@x`Vmy)FxnV6KX3kw-vP^nA?!r z7R+r+Z4Tx(r)LD_XGG5q%+HRV5tyG5Jv%TzJ9^e&e%90nz}yF@Z-BXPP@e&FpP{}4 z=DtLI49tCu`W~439`#8u_etu*VD7`zw*|Kk_igIKVD7`zx53=EX)J(wEYKJM^BAGA z1Lm< zFwYemtxrpW{FwapmcNsa&T{NeGc}}A_5X^HR&5dB5 z8)*&%^BhQXBbet#noGevm(m;y<~f$;UNFzSG$(_3PNumU%yTu(;b5M_X>JGe+)i^o znCE<2Bfz{y(Aoj!wS(3OFs~7`c7S>9ptT0fYYnYIU|xf0Z36S!L~9n9*DPAgz`T~x z8VBYzj@CXfuYI&8f_Y7(H5ANiD6OqVpVn4dL&3a;(%K5ZVbfou#g+ZbeffZ6sS8w1QX2H759wmryJ z0kf?_HVl|;7_x1^Y}=5{17@3tY#}h)LS!R>*+wGU3Cy+=*;HV*smKNcvkgYJ8JKM| zvcbS?gOP0pX4{NxIWXIDWaEL^#v|Jg%(frdgkZJ_$yNljtw=T`m~BY1Ex~MClFbQb zo0Du*Fx#kPyMozvB^wpYHY(Y!V76V!)&;YzOExf=ZD6vE!E76o%?xInnQUn=+tOrX zgW1L=+Z)WbH`(N1w#mtc2eS=Nw!P%}hi!YZ;UQ-mo@{$C+xFxOK!<$+@)5x7BarU^ zX5WE)3NZT=L-HlT>`Ri531%OYd`~d@p5&8)*(W7m70kXW`LJO2Vac}zvu{g2 zFPME^@{z&pBa`n8X5X27WH9^4jv-KN0nD)liXnhGhCs0eFvk`s76Im11jQ)89HXGv z1(;(O6w?56OoL(_V2*WA3d}IW|Hu6EMe2D8>Tj7z@Q-z#My_7z>zVEEIbI zbL@p;HDHd_Pz(pmF&v8RfH}59F&{9;d?*$K=2#HLh`<~pqSz6bV@DKI0&`4>Vo+d? zK~Zc9%&{qoL4i32MX@O`$EGNj1?E^5#kjy6<-MaJBrbPIYvjZJ21!YDAot&SRcgz!5jmm*dUl= zgA_9abIg!piC~T;Qj8JIF-D3#f;sj`F-b7TBq@do<`^c$Ho+X*q!=ccW0(}%1aoYY zVxeG;g;I7&w??;1nANb8MVq>0pkfQ;Z$VF?Nc*gE{t2F?le@ ztNb%He+vJ@RnD7< zvBHO3H9EU}-h}tPV7Q`h3}?*W4Bz@Sf%DLQ!_TJpItP$%z-v(IF8)qmSG~$qD(bAX z#K_e(hcm$(!>4*za&{yifb~1at?f*5%{-R_tCl&tWij$N%cnYTH8b2a{{Uz86GkWQ z^Oerb;f5a-UF)2*#&G8$8=bGF8t&U-yR#B7zADxU!)*trS7pfu zVExQ9Gpa^^nlXOyVJX#Uj2Wjz^Au8H8I8`VHvVd^GCJEn2dVz^4ChKF)w6zv^ZS)m z`AQi+JEVeYN4^1>|b3Sm}59jiJEF+FT?LD*H+J}8t&1kj{4=bnF9|e z?XDaL%=~ud$F{23L^EGaeA83~95y=3)Am%g=Nf*OxwlHu#jwiRS8d2_xLxM~syg`w zd_Qy64p#Ta8m{|fnCjNR@NdsU)HFZC*FKC;b;$={{n!yB)y*_!{_p-~s`{A1%=5kL zO;o?dF*?&%|Dc}VH0#Lo7t_?@RfaP?ovvQ=GW`DG3{@|U;jtkzmD+9An!+h(se&yH ze_1(O)yrY{k0oNtO{8b&?4yDZtyX>khKmhetFAlET3pU&y;@ndV%)8s-r&|jz@dT9a!g!dwWzzs{vn({oog8w;EpA*aI0hZ&MfA8l9n~ z_ozwf4gcb|S3N#s?2|f)_Ni`74euGfU&SNefa@Fg!vVFoqv3#Vhg7DFhRfGGto+Ux zo9A(fBkJrJ!&x#NRr?Ah$7gedTu>QTrvRtxbVdcFPX*po<)mtVGa0y6^NVWh6vH1& zT~Zr^4ChXJS^c^_DRdqW`Ca{9$Z&@nSCs#nB#_UQ*Ho!ShVT1cS0AGr-uCLc>PS8S z-+!!=H&o+?@xa$d{-tV+O8~C8;+|@pDG|7={!>MpW^~%ud!(8cGu*-Nv1)TIE_80Z zeykQ%GaRGBQ11^8>^k-_lpW!q&o~y@4Vng0>%?ov{tKobDU#j6r4Y#ZCN~OQ) z1D(x5UsSs#(ZMele^e!cV}g&of2%5n7@Yw=UsaAwhQs!MRs9AT`#)QGAN|hp1@`}t zKYVnA&u4IoA<^{6ea0`ipDMbp|LG&-Bl|_yKNmIp+xh6aQuhy#pQY~^npS)Yj#n+N z-W=~GctxO!peWAMr^arKMy#y<*a98Z@R{TJj1AH>s{ z3O)pv9vEMTUNwHxt=I|l?Kp<-wMd}n7r6(W`P&lcQ!Va-ztZ^EMj4a$wOEy6fpPkar)OLLYc`8l2=p3cW0`;ii5mwH&)2@|R80Y9FWZe~Wxf zt*`%O{M?T-Qt5IF_dzGy^0fNGmc8JQPtxl5$BlnIsJO50R!>7-W1X+w_q!8ZB3nBB zv4!!wOV3KD=l0nR`KIgX^zm`Kz^DDv>lyQRf@jkAc!!3p1@G|BtjFIm@qv@iGiocx zKo1zd20Gb0W!48~tp*ofomp>KX5tTb{vvt0Fvy3|nex}BtpMlPnMHqy<%&yW%Bt5V zT@HDV=2>;j^vl32=4aKP{FZ`4=zC7Tku$+>Q|HhsrHP;X6yHxDSiBJOuoOfIfU37|x&umvYbkcWIA^#ywPMxgf6mV1ep4M^5#BBl((fR5}CPF?X zBBw5NYyx;(L4UpJ_;_&UcK+JgZ2-7+=G^*W_YvUFBA1?roF%?R_E5)Q+5Z}f1O)*KhYU{g}%pbGP(n}<(NEL3~C21vN4Zd)V&RO z`PDpnNSoH+P4qpv2&n*mRx-bim8TZ?zz_NK>=TW^(U0fV&%2fbr*D~G7i?Mvd~0-m z9lf#umkZ0UD?TX&&hTe`-E&59@H6_Je{8Wp@UFTA^xZ6l!6*6_(AVP^1P`25K=*u| z53DJVAja^d;5)4f={JqifgfKjsLSQ{0~fAUQ0M(VF*wiALOMpJgy8tI3+W$o#Rrf1 zwUADQ}^0U*;*SBNmyQmE;u)>zA$HL4LehVco><6*yy` z!g^G@?chsOi|G7KP5kzF$s+n#1rw*eb)~Rgm1Q$@QYaKZ@fGbfR&CRZB!JVH6>iH$+gKNJI)DbZzfREET&%TR#f&ZX99pZ3aYnXSY zUV`}ldCKu2Mr@y%J_{ZGER_l7GU-}iz82jBnD2q^4b1mO_YCHHrn)%!T3i>ZBbe(* zZ35;tp|%2ZTTz>UxlO38z}!~UwqR~sYI88RIXw$7KMQ(BV17pQ?7;l&=$V4~nbNZc z^RuQt0OmeGeFn^ZhWZki`x5mTF!veiOJMFx)b|Wi-=jVW<~~V%70i8=`mo}J7b+(>gKnCDEIOTj#s(i{usIhN*RFwe;}SA%)3 zra2kRb2819p2^d99~49ZY$Hyw-zxttZ<6%(em93}Chy$d&-J zEkQO0m~9NQJ-}>xkWB(+n}lo?Fxx6*!+_a_A)5!xHV@fCV77(G<}vzY^N=kBW?P7C zCotPiWK)6JrXpJl%(fQUU|_bv$TkDBZALa5m~A$)<-lyqk&Opt8;@*4Fx!M=D}vcp zB%2V-HX+%HV73*>wgj_nNj4{#ZBDX9!EB3?jS6NPm26iq+pc8Og4w1eTNli>F4@3F zPBt*v%wV>e$(9DQEloDF(IK0eY-upt(qwys+4d%z9LzR3+3H}n)yakjvkgzSJ(z8K zviZSm^OG;2d5&UVfP4fn`v~MyfZ3-YUjxj(2Kf|V_9@8M0JE<_z6qFp6Y^QW?6Z(B z17=@_d>k7#{?)=0OnW$#Sp+8L!j6K zm}3hRa{zP9fnpJ0jzv(60?aWAifMp3ra`d|@EnSDP)q~NF%61!fH~Gdu@NxGMkrV2+hhObpC1F^ZLeIaWroH8984DCP#{m>b37z#NOC7#)~nbQHS-bL@^{ zdSH&}QLGQlu|A3cf;k3AF+(uN3@Mff=2#-d48a^Tq*x-DV~G@d1as_>Vv=BvNm8s5 z%&|&}VS+h^NwG~Z$2KYE3Feq5#X`Xx3#Aw-m}8_AQw4KOm13=6j5Lt|_Js=9o6cy1^XlrWiPwW8f4U2XkzkV&-6u znNuts%&~Nev4c6rPBD2f$K>t2eTvCL&M|q4)q^=!Z|l69XyVeN#y@q|Dx631{MoK@ z7u6zXav z`q<+x4%UC&IZ!t~+8g%p@2vy%_uGwKTDnUCUG<5vseYsJT7T3b#rmgPr_rg`nDs8x zyO{cBVl!9Azi^%2`#1AU@3m{xhX!U`3}4YnMJzOZAeG-E=RbMBhTlWMyB_?0hyC7% z{XU5Oo(R1Y^6mW*`V8Kw;rB}H_f2ZlSVr#?@z01z@2BuJSn7HYMKinJLjm)-@7GXU^7~uRVIKcA z1iX1g|I#_W7%sEoZRv9nhO>Su5oB|xzl=O(xwAn#XpddKw>8n$1pPqgP%xL>GdjrD z$wGUgviwAgQjSD@4gYyytfNG7!#8WJkHnQ}-&EF*L1)45``vKrD|;Qzw}xY<+(Bo= z|3fEpKEpX;zjibjI}D#~lsmDA*l*tXs!%>#WcD}m4o3=#0nH5uzsw^BOgCIBy}yXC zbas~-f-GSl39LHEVv%0_#HT6~K3)aCy3szyvX?6~1oGKRd_B^dI#g`!Ja zXYTOEkni~=uAJ&@06uspp?r6*E_hb@WRbY)@$VpynI)y{G@=f;L*^8+R-n;;oH4ny zb&8y>37v+Hw6gi0YT#PcGssj6DuYK?%@T>vSE&g3$L!f<=cJXuJqu-%7cLrp<;W^+ zo%qqqK__W!f4Om`0N1{hTc$5n8eDI7{zyE2Qwhi~lrJQQPAm!D+^V2#+@=(G+|UBj z)>-6N6!P+S17*)Kg}}Z0mXOWP<^#ulQ92TT_00qMIjgc4Jbgn~|d1P2043f6a zldAsE`SEaB`MG0u@cJYb<%|KD!Eee}iNvKTXNI5eg7MX4r3o3q506xpZANAS$Bt7~ z+Byx#riJ{*yqYperZyo6^dvBcs&fKJLBo13W9r8_G`pNz=XMz_bqw^D* z&jP33)>qm()9;Rhyy=<#a%zsD;4GO2%E|3Jf^XIt6p6RQYie||(ivXoTYyJjA0#U* zY6I>zXOOgY#%HetdEZ<^Xn*d)hSLs}l`>`m$9)=^#pEQAUl=${p6tkHLiqS3rn4Z1 zmG=c7%Q#F%(mDCo!8+e(8!k(CJO!@3X}G-nBosU;AS4p|P5TjYzwROOanl*#UX4k| zZvj}A4Ux9a!?zOh&)Y*}i@w)`_*#h`gvfd`9+hUUMQi?l;oWZe4+%4ZPm_&641H$O z|E5D_hO<7GN!M~R^R?(6z+vMcQw_t87YD2}> z;&!%~o(tssT&T^#+~)Kw!2B$19eSpa_oZh_&)P6OYw82wEYweIrhWxE_bci%VD2;2 zm%!YYY#r*8rX1>%)K|gWSE&z!xu4ri;{tLX7u4s$+~;X5fO#y~Iy9yr=P^ZN4a{SW z#vqu-sm(N&A?I;TV;0O~mc}xe$Fi+Ma{}Z%C(v90=DC9A5HQa(Hq*QWInPTp=YV<6 zp}7dmbCIn>a~kA4r_o#o=DCjMKrqjfHq%_H`MLAFN^>T3c+RA`6wGs}twVD%^m$IE zxf;xKHO=8*p66|*bpdi-7ii80^PEp>0hreUTZh&Z$azhnwFb;<4Xr_7UZ-rPbq#V} z*J#ZG^O{9#8JO2HTZh&}$azhqwGzy0C9R=gUT1Blbs2JAmubxf^O{R*F__n4TZh(k z$azhtwI0lCJ=p+Ywi9e7y8?2yE68R5v&}%Z1ek3JTZe2C$k`?#TLsLv3fVAVwsUMI zy9jc&i^%2yv&}=c5SVQtTZe2a$l0bMTMNv#7TI86w$p4TyAE=;>&RvUv&}}f9GGo6 zTZe2y$k`?&TM^8*BH55&wli%eTNHA(OUdR0v&~7iD41F4@4~ z-^fn3ne1vKC%c+#W-!~#WJ`nDmbP`sCWoADaN9rhW?mjtsfNxmnTb;u_LvrkICDwus$@?pX3=h{quG34wQlg|rgpO<`LF#E!` z4*ArOvrkRFHkf^F^1;FEr`t@vJml=xlg|!jpPhVpF#Gbh&b-e?KBYjy@acCAPhRmL zeAi~f&!$v#+B`bM$n)hN;p{rY@V)(Ao#&PrPMo`m)7B}K)yOOE2y+%+W$M_p&>80s zX$&`_y*g}uztFU2y|xKd#9_lF#>G}6o*S;eDw?u&vfnh%qDe?*btg6#A(g5 z&N8}kBtF-~^oP|?8>p@G47bc$M`gZZ`1iUsl&v$wVfx#Y{hgFgT+_$?7%@zZ-f8;k zcQbyB#LKsv{`_*qRFyD^(V1F(vWnKuaN}nal&#Z{&TQlLt{%H$qB=))A68dFIzE_Kew*se0@m4)bY4nFadZla~f7&~iulv_HAN}b>Q?R&4 zId7R7gYy)R7l|V>H-tP!?Sy*dal?OBPN4VoYXtc-8DHBvjcU|`{I_vQb-OlZO^LTD zrS8$rtTp9Nrj5ii^Hqm_NoRVU^s(W=`_t*Bt7<@g?uf6pb*UrWpBdiRK9@eK%0RwpaDcXTa%?FLdD@hegH)^p_|1Vr z`b=mb_)eRmk+^NF!jMOMUtG_keOI_`<7X_ccO5DM_9^oTfQQB{uWgJD^ZFH5XkHE2Ow9!q%pMWp#`d-^Q2ddtLyhPUa zI!%U4;1;zz>K&I)g44F|9Eta*It=;FD_!*SMn}PSTXxY;<{SraxZPRXIt4d4A)k7r zn;u$p3%Ki|9(uv5)!@v*y&`erEi^aL&*`bXb;>v^z-x2&)|VQGfzu!8rEQ&d3FblG zGkahCsO~gyuSNazpA&xoulE@ciIZI$4*9+p19a+BBf(df4$v+0jRA+$rE|h9o!(ix zK>jXZkj_}M5ja6*I+wC-dGPJ(Ln3kdM}d&X{V+rq)+NCw_7Kky;8f#=Xj`Yrtt^md zK08!5Kb#P}ZTc|XO1yxt8eV*OWd3*#@@R{P>$uMAU^RTW{(ks<@aJZvZ|N)?wFdH| zz9D+*hf(0mgF^J&LxEsFI_J^m#g|{fAAkF2h^{;_5p=Fy4$+-*Wd)Zx8KP~SKYz{! z{X=wa8!_So%%lV6a%`q+Ir#bVb*W4+mr2(G^R;Xpx@XAwo~bTit_#%>%#OYg>o< z4CLHrs4s!JFHs)@b3e41`Yq(#Z>dj$xldAG1#@4ub*Rrn&V8Q70+`1FjS(=9Bb#a5 zLC)ij#uS*x6pb}7k2PC|#w_GKW@#*gc`VZy2lG5&GtC>2^SnWG0+{Cnnk&FOSJ*l< z=RnSL4$Vbio{MOX0`oj(GtGOD^SnoM8kpxan(M$k*V#HWXF|?%Ce5XipEb{=G{=H@ z9=4h0ZOD1vra2kRb281=QWGgGBB@Yw8nvX9kiL&O~`rOq%{%DYa*?cU|uV29a?iC=QWqsVlc18 zv_^w@9k-d*eaLy;r!^hSYdWp| zIWXIDWaEL^4z!uAfE!vJ_Y$2VD>d^9r9TqXPr>*^>c^_=fMZrGR)_&32+Ao^-q~;tI&3pIK9=?9e{A=xR%=(;{qRn2#Tfw|H zu(iLj>l)wo!A2R@zQHJiuVI(XJWkByeX!kf_rAfnN7w$t^f&B-4IQqNbzRBV;Bt7s zW$Qk_?M=*Wb}nJ@2UZma!y-)88z$_Dd( z)OVa_3v*sE&q2r{M`=!i+zB{x9exb-;9>{yB$o2 z_`4mV(hlrz7(W4Lqk!pb6hUXBfaz=$L1&|Y>1>oBIvWK{XQMdjY!on^jiTsm6vL;c zyZu4>|F?69;On^j6t@oq{Y}23`P>#T`+P3H2ELSaZ))+-M9|rH?v`3{{3-iNvSgCD zT3#{xD$G{tbj|WVLf&Mnzb+mp0Q@vXL0xdoLc9kt=tU9TwqH{|lZeaGr++YIme_Sm zZIN%GUw2bX{nHDx|HH4-Qt3RY7DB!^O?G+@w*lDyV_u!=;w6+B{IxKh5tZtjuT`Uw z+1vK!|ozZM)~u!M^Lk5!*89G)-=RXI)LKzYd9^Stsem_bN|BGH`Ipi`<4_ zZbQ13lXdu7bPxC}-viwnnD3458O--gbpdl-sE#Oy>u8lJs68R4_7v2f(5Lp4)Sh5! zPf6_wruLN7o?vQEN$rXIq4tyqLdve-d*fg7RZ*tpBfI=p_{frHk}W^}M9@ z9HsSqrS;sU)gPqQPhflgFRp{Iab4rx#s6Ej>Obslx*yyN`Ix*m|4%bt1Ml+CKmS5D z>&%hXKhpa~|4RN=M{ZYleg75A*TB0)^v}PHd93nyH*^0#Wo7C76E^WSt^?_6*8lJP zZC;|k|5J9~59|CBHuILNe41~*UF#dqO}1h=&l^KKAI;$@yT%n4&*vp+2KtFAqdi>Z zc!gj2?jt{agwCG&P^hQuX`9&kSC-e)iK^Dko-%e)?KPg%UT*EzY}td!H`Em`v8Qcf z>)ZA9l{G!3h4^pjR-AvtAz9x_sKC; z`Ig%2_v5jC+FNYb*HiYiO>BLq5PJU5exW&PJ9pL&oj2yA@D{hfTs0{3i!*+4=$#2~ zv0YzJ+0!<$_3Pg6p!Yv28`|{hW#KIz(0-$1Pp8vpt3BY}eOQ_OwlG{e53Tbiy{jEpPq%(cRwSFTv4dnND;3{(2Csy~Uok ziLGzf*HiwOkKUWS*^UIvx;;i+O$Ag7?fQDkIa?3X$@8{feyC*!}i|W`s7~=%h&b_Qyf5AF#)fzr)^^E+x7L7$-fqsuk974IDoWb0$yRe zzMitDZDQ+_f9u}50_6k!RKw2>YudrQTPubHp zvGvKmRhF&m6(&1eS~j^?*wZ$#_3iq4%4FXv%hvS@lN~NCo7^jG*Vj|_v`uV%ia#hT z7U319IEl1kCSGAr+r-wl>+2~~{K{#?vb@3+XOmXU%`0rz*HiYiO>BLNKPW2};T5Jh ziL_!SUSUt$#MZa#>nT(GN?EZiuQ0{gq!n}X3fuMdls#<|Tc7-EZTZ?>VTuDtD<YudrQTPubHpvGpncL|eHiUSZ0Ukyg%(SJ=}wvGwixddif) zq^(>guQ26VNh{~dD{R--Q}(n?Y<BL; zzW)>K*#Az9AGgqNO`KNRTU;nbOnI~0l+dL$nn`c5-6o!LRNC$5)CuK;F_ZlsRcNTa z#r@;m7l{hY2yNcCt@IXq+9tMsRN80lxb(7M-T{6;H>|F`#iLdo5T(2Q9J(&JtMnGz z_4Sma(mu5^=av&z*Y{0Yd_9;32w6}P zT6T@4y~Tsi9}PO$dtqq$$05>N>}i|W`cY}0G|o0MFgV$=YnLA?Z}IU1Rhrv8Qcf>qn)1iVyBBSN@!OdA7ji%3HjBVih&4_x#XX@rOunv0YzJIV$b* zdCqWoG{uVLu~J-gdW(T;-r~9? zU#jAg7 zqtZU1a=4r_GFs@koX;HI;$|^?_10BChURqCl-^>yzMgVa+Gl6uAu{=;q@g96l@s3L z4SW3cz!RfG_qQr5y~UokiLD=%_Gy`XfV}ZKbLjSXKL~Ge|DTHLEk46SefkGVZ?Rop zPdO^>GoyDedGcWX&`!Bm3vY37$8vhq++LxNr{t90Vo%$|){jd2G@1}i_4yEtW*8cIP_w=xYAqf zX`9&kQE4B#e`(dlD@^UItv2@x+x7L7qtZUq|D`n+yuvh2wKZnF!k)H?tsj;4q4`r< zbE#LD=6P++`CehWzMgVa+K1L(X|2UxVX_mnWixn%J#7{sh5840H@&&xYpKyzu%~Te>qn)1==%kS^<9Hkn7#+m)^{RaVY|Mba#Y%f;-A8b zg?fc4POGh$tykF7HnH`i(moVFcUZA>uQ0{=wH5RC3fuMdl%vu<^!l@@9%{5U7lB%zGu|dcaC0RyS|=sRN9BWUl7)J4PIgT9z44w(ILDN2Prz|4muBa9&}`)6-VYo>$n@HnH`i(ms?wsjOT| zuQ26#YAff{D{R--Q;tgeQ2wp5a&f)FlqamMoMEr9r)^^EN2Prze_L6(++JbIGuKwm zxmVb(ucsW9_M!ZLZM_TN6{hzTl=aSnSJ=}wvGt?UKJ<=>w%#}K3e&qV%6c!xD{R-- zQ$Dcw=TP3;pU)HEvrF9PZt|HX?(;bL907B7fjNuReSRmOjp9Dn)11SCvjlLasrwvI zDv!(Mvrp)(fug$doI!j&oQ>)_E5)tPXCCmGqojv(3vm9a`#ekj*L4;P{%-V&YS(?D zY}fsR>n2&iXSlfK4!#fmKi?PC3(RL9xXa;sxXb7Ixvxuqm+t%F_TcNe?%#dZ3zsDW zfBS^%ar?RJ>(b}*6>yd+Uys>UKG=0#x(44X?g#9;PcWC~elD@s9d@57Lua7=ga3Yx zI9mw)@!#P&@?jU;Z}`{MZ^5qq4Ca1k`d?A>NA5SQ&-LSe!)*GmIm3hdHTN5qTjP#D z<35MjEyr0$E`4Q{19p`U=5gR^PbvrZqgmf|pI~d;(b-9R-Qy19z%}kz-#zZQ9QU~6 zdb!6P&Q;>;x$XzoW46W}&Q;>;v7CQh=McN)IAh5gcahFq;r4U4o9ntL!y0$)`-I#Y zcYKyp4)--}{`)zaGrj&@o}=q|X?m90>bE>@c)f$%>gPPp-2Fe&dgK~++*c#5U#@Y- z{S#%m&H&Tacy#Lv*0IK~yL`x9*X4dl<$Rk5-1iB&>;A!f<~QlO<=@r|*SLe+>gSk0 zcsy|V*0_kYPFdrK@BiDn#@C^7=g*&Y$x&ZxoVv?F`?$&nTm3}4?uY)3ye_-O9ptXD z2L4ZdcJ?}M%{lz6dCrvFKHhwGd7X!I{;Qvz%Rb@f=w9!@*0`g3{$qWy#vQK<7>E2> zYuxd=fbqa`Yur&euro1VTjS2H&*RHo4%k&b*cx~4`{DAW>psEOxQnzd{HNB@WlOv3 z?w(t?P2ByH+ltq8=(xr>*qU3o&7sHbY0WMC?A&t;K0~%N_fNMRYrQqMxXa=Bg!=}s z>0sA&HOsBJ#eJWUTXPFNJJ`>V+iZ=yUh=k`;m-Tq-mx$GAA^K!C1#O3^_K1Z4--F`azcWzsS+s|#QQ2oEzDpB@>tav8u zT54PN@7QkO=c28C?)I}Fx5kD0e)ze#?-Oj?#NBDj!Vs;(jPu$8|qoS3d;1?jKBR zoFD1_H~#xMep~O{@neO+tZalPE*?!Wo1)_Uh2cW!;OgEj8libk^XNCs*7)MjbHCy5 zpWJeXrO*A)T@Kh)KG=0#$vW0N;J#1DUE>Z+-y^_3W__#Qvc9`Nb2;wsM=;J@{h#Z_ z|99UHuIIW>T#uRCiLYnwr>M5#nYf;%ub8dz>n;c)a|dTkl-o4l{|65;*y|1v^f#)B0`v_)NIbdrZ!#wSp->A=hoA=!JNwRPE5B^VG$GKh+tzzZ! z@fo4FRo%H#G>rjHJ*ZgNj5QwvSRT=8Y}lok_rWg)tO?7}F;5r2d2-3 z(dWTb-YP2B-;@(;6>H_4|ZJ_?7APY>psD*`=@J+(0moD7nrZl z*JC-~7hjK=@0YK~%=O^wF?0R+ddysJz8*8T2Vakw+ljBo%wdtl`vkl0KNpwds@FHJnXrcndNL65RL}OS7Nfg@uar!z3tg=be(*KF zZh5&BIM$&`dTrgT;C|8D>r01kDlYSN=RvyHw)SB6by)7^^QQ}m;0#0Yxe6IKh)q*_ zf=NMM+T0wxd$OM#mc9a*{+0B9F#TPU9+*BS>GQY_l_#lO_cd7uKQ6i8|G4zQu5zH~ zDj)2+uKV+RKVa8=f?fCT)}fL|xaEqk$JgTf;_ETfk9L>C_2BEVkn6|SW2V1r`UlMI z!PjFsw-aBFncHt+P)+I&-{gwfr4M$M!)3Y42fMBdra$rhfL-?q=Jw<3@n`wR+x=l= z{G5(Cox7lqWlQ^`Bk`L(=wtC_9&~I;nh<@gRr*(s|Hs~yfNMFe?Iam0N`?|;*n4LR zb%eCPcV)_~6f&z!DZ>#CWhhfbnKKWiy>~KXtf>9HFCxk;L^%fsA@eN5@jv(d-fQ>J zfBYQspW}S{y4ZK`e%8I_XFbFFt#9XE8*+`U&}_Nnll!;f8rx%9o8+xC`*Mx-OWGy# zN1wnoR(sai!sIc%$@zT4hDn>&_mcD4OSev%)htEM*N!+QDH~Wu&Q-oTC)s?)mgHQp z=XJ>u>+DU=(bwLbY}dO#Id^URVPWJ_-N?D}hub8}-9Db2b2?p+OzQPTioNjm_Y;!2 zBUdHoQq!j=mzQlw&J*g-OYUjEJvl$?zaSY=Z*OvTx~XNdN}J8e+4c34lT}(=PR^@m zPfFH$>m_p5EO<4!cln0od~*2r$!FWPAm{uSn}<;yHX-NLJ=P4jG!5i5zQlORX?%(C zlGFGS<0Yr@1>;SzXN@lyZ;Cx@e8G6hX?($W$!Yygtp7#m0qb{S{U@jOJF)(g)A}8( z|KzlO2kSpMt>3}=pF$5xrDUjuKl>Md&MAN5R%p5p!hgDA;-`qVKkjf~_ZV+Byoh zp2%tIDA;-;r>%GHGxXi`A2B#h{{`%aeBL)A2B+yiVvMKhKVtOV^dB+$u67o{sdg4z zI}5Iz1=r35oN8wRPPH>}<4I19X97-*X97-*X97-*Cpk5q)p z$SJ)3MPjW8Gsd0b|{xoxpbPlM@*0 z9^(m&b&oj$#=6HGVP9h1W8SeZvF^c%eTn@EPV7tUPs|baCH5ycu`jXi!HIo|bq`MH z59kqaLVsZ0gA@7#>t5rTV%>ui`UC48oX{Uw_uz#7z`6$~^c>bbIHBjT?!gH?hjkB5 z=sB!=a6->v-GdW)4(lGA&~sS#TAwM_JvgC{vF^bMeT;PvPUvH-d#%qD>mHoY$5{8^ zgg(Z)2Pe)Atb1_c+`zgAC(aG5dvN01z`6$~&JC=4aN^v+x(6rD4Xk@`;(Wup2Pe)q ztb1_ce8aj2C(bvldvM}>!@372&Nr-kaN>N!x(6rDVXS*_;vB}h2Pe*9tb1_c9LBl_ zC(dE4dvM|$#<~Y5&S9*3aKc`|x(6rh1+05;!d}3-2Pf^X=QZb{1Vb<9Wn&@7fv9Bd&Yb&eXLtb>m4+jc4k{Gj-#cy75fic#>1&Nlwi> zIW_O()Vz~Z^G;69J2^G)>BW*@7hP?)IK7o_B%PX-^r={PEPH2a%#VmQ~RBq+VA9)ULvRT z5;>)pGRzU|8mxP?Q+kP<(o5u&ULvRTCpo1*$tnFwPU%l_N`I15`jec}pX7voc76){ zFWM;HuQ7o-f5-bl-anEb!?NC=0-y6!_;=K(=R6-IPb?muA>t=iy~Jt{vD!&2|0~Lv zSnkWBKKbbZ81|g4A7Y(r#5&iAb*>TXTqD-GMjKG)TH;~?!Nm%Kiy;ITTL>=Z5L_%G zxEMu9@|XsEf8(i(X~gI7{i8hm_sBymeqz;2to9JAoy2NC{C)Nju?Aol6F|QZ(}+BX zX%M^E0{VrR2A{iF1loz12A^BM5Yu4$71L;ny7Zj=mHbWWSB#BBem+;d#ENMUtDVGZ z|9IE0I{aI&0j#T7kN20oA8i74{F~ta zmhk!Dn{y938yG$xd~#1#zNns>Zm+(+cpJ|d^~J2|!A$*KKLPVIMcYQMu4 ziu;|M+VA9)ULvRT5;>)pU|%5?6=Q}`FOgGviJa0)Xbui|VNa^g9B6|@r=z6!<@7`_Vn4h&xfa|8@u1#{$VOXzv{=CPgd&0{;^ zo5yy-H;?UvZywu8p9-AL1`f^!W^50>pT;xVz!*>X=5ajXo5%5_?*~q2tJ{93Z_ai) zTOE21zImK?_~ztvwmS4YeN?T_=u-seQ$WwdH;?NRzBxIaPl5GGUmD}-d?8Q*oFnI>LC?cCC#Un#pyxC6ADqrdgPu1Zl`&Z8 zdHCj0FENIKb~;}YdWkU<=_UFq;FND3^%7$!=)3bJp+6bx0jGTPs6V663;oGh4>;wU zlT*HV)SvLp*-or?^UZ6(Dc`&X`V;HjeDfN#Q@;5)aLP9ym+yD_=Ht*#`R3y=?=FTA z+ld$g^n8pV#CFE>D8>+==VJ^3dOpSwpyy+(BaUYxJs)Eo(DO0Y5yvw@J6)_Jj%R{) zYTkJkYu?GJc~8)H&3oeJot&EY1bx@MlT+(6aqE+uTA$?9`Xr~;Cpon~12|pmi06j0 zmtu@7?jv%Vo{upu==m7qiu;J1+DF0dceYdeo$b_qC#Uv%$mhK-76&~aV{vi6lT&($ zoYG6=ly4rKULvRTQotO^H)lKLo0C)elbq6@`R3%rdRJ^S>Ck>; zx$`L&yKnx;us17kCM<5>yhHmY)zOFXeMH@^zl%L*YIT>PM(AbJ!eZY#EXKG@9?K$Q#L%lwBVgE#oh0lGg!^c4E?>N6H<6|a%zA%243pPKxZXTm= zh@5!z4Z(x|kPAi*omlk}*oOKyvq>z5Y_ZO|m};E6 z-#kWVw$|?&8~@Roj4=ePNn*tmIi40nsQX-!**|rkSF&LViZ#TTD&_s2!q_2Zk^heW z_x~>8d{j!~P#TBdVh!XReh=E7E}d((xPESY_5b5s^K1W)dKUO|{Eu{Y=W~bumuzya z<4_ut(t7x<*1*gevwm0G__R~+Fdw7NUt4Up@jZ9H41X=!%y>V9cyYy751!T`zDH5_ zS$m&n^yj0`OZu3n4NF}f)5l1q&$;jY`Bj>`x_4l39|Gss=VUeJeC~6&KYmx_|6}gl z{$=~}fBzOXDws+jG+KsM0X0w%G zQ)IUe9Z|i{b$b#&c;+G1*Pl6zc*b7k)rWj=4e{=Ot*sip{LRE$zINr<&YkZd9&qF# zWjn7wfp}(3{qhSw8%uoNDqYJvt#k?Tg=-Bhzcd|4yvmkWlz;nmN8-L+#+9$s|24K} z?D4mkKR2$0#}+Rhnn{LOWvlUAoW!b&SZyFy+lbX>V)cbseI!=ji8Us~8Y^OrA=|TX zY!~WsyvJ_uhV!hjyTEW)88M#WZ*jK$`%H_&{*Yb`_^mhyvEm@a_9w(Hi51f%R;-g) zeX8cl%}2wlA}Lbf%^A!-3iC zN5|m)xVk$o@qD*&du97yKb6))O}f zht{mke#LuNA#dY=d!{&FTfehk(q_XOS+>W3CBx1OzGA({-LzA9`EQ?6#(hpT+b&#? z^iGH6poe^{CUj*;j&8}FF@YpxPP@) zd5NAZjyUXW)3in)cE#+0V=;}&Q*8U?8%DT^jW{qb&m~=i5<@3%!+<4v&dfK|2#{)+QA2%mH~JVm{jH>_7z7dbIMHcuIz_rLAF;azlejEUPG*h%PIc&*}}L_*|u*l8=ubn zpbg7nPHb-2e)qY-?A4K*r)^iijeW%5A%}Y7{hpd@EB78bbr&b+J$|kaGSaK$k?y5@ zybl!ZjQ5p*UwW1DPkwV)cG*EYQ(k(Q{L+)e(yNpiHe-{lIIb0+yU*8UhwPiBuMNJb zi1CAslK=ia@}|hG*X6ty`#V5+j{T2!*5|SLeC|9h&12nXinykKY5x2F!)C*rm2B*? z|DgFA8fMPuS&n%#T^*p)flXHj=xbnmmc;W3`mW;(yOqDO`exL9wVQP*e|OHE#Qm;b zx4h#9_293CxviEhPy4S$T-I-T*@~?@6K_1WZ`sIZyAa=c{O0RyKe#9HoF>awUGRN( z;_^qYt!kESOI&@=`&B3HyfN`B545ZvQQeIAt&=)d_w7B0^^U)Lhw7Se4)K@g_o#ks zqD#o&ZOG3Nq2(L0RXU zz{ZFDK>6rHLB{zbA^JOb9{mn*Mt=u&IUg!Se+2T;?|^*tcOVa&MgB#I{to1$Zvy$~ z??68KS-{bsf=u*xP}cb-N%XTIAAKmbKl&pf`a5_Y{SLL0_v53i^PxiYM<5^l4#-D; zN9~OMREYi#Abu9FP%(a!>o{uIhae+OlqZxYuDe1te2Y^U?5=$k^n zs4V>sa7KRzbvYj@?o;+F`W=vu{to1$Z-wX4-vNL0P4GPWJL0FG1swe;$V7h!Wu0#l z_cg~P`cRN@{s`v;z73v7zXP1n-$7l@hl+ZY{fa&adFM|>y-NA$r$9dXJCK*2 za2=u>i39U z|55$f-)p{_&w3PhVNeJB9`n_F)(&>pJ%l=j`?y*IYB@9Ms{gL~(fzGL)9-FH!! z~zm&Hm|F7#*j9qD7 z@)h*oHV(gZ-~7_?spF?jr7`|L@WMJ4w{Pp)^LzM8aWwvj?`6SG{3SUH$gg%u_wpTD zHD`Qbg$CP~w|(Uz;%|@GyxiW?CoUA$E+4k`GS!f`-{tmiV*7iU$q`$*GAmDPd}YQ< zjPbTM#phM=IqHe>s3-EEp2&~iv0nT=wg=^6JHZ#*pVxyL*)KdV1C~6oc!R z5igB-D8wpb?g{b9m{)>~&rkW>Q_Ll~xGUrTKHn7cN03p>mNJUXGUl&XYk-Vmzm(B? zEX+A5eoGmjd-6G^m@@*8&qMjVQp^)U#^;`VE-B`QAcGZx@xb^1<2U{djK7PgfZPWD zW<2=*a>^){P8n-YU0%uBQM|>rzgHGRk*wE|k}>e8R#!5!w^;LEu4q(Qe4Z{1If7mtj6A=5!zv$1CsG!n_au z7RS-&hQxz+(tePyQQj(b?P0uK?O}XA=6WC#^Elw~`I?ybfsD`T#2gLUcN#O)rTNMrqj_hWHSd(syi+FTaloVXLm8io!FO*NH+g)%CgxvIm)0|7 ze2zxzIkpGi2^ZVL?}tX4wJ#{6{Y4q=uh=i-WGNGKG-$K-DP??~#ph^zE+*zy&}N^n z@%b0&4bG|0(fFK;^bcjE$Cz7`9*gS-?-lcX2-B4r)*F5nx2;l&!~Zs)TPx*Ic<%u8 zB-gG!UqJlt{w`TQcSEzS9%yUvKl}{Mp53&(;=SeGsRHgbc8!XQhaOrDJYoB06ldEG9z(w%51S4B0uQnHiB)ff`i1rotDVHC2jc~qL8msn zARot}nfe>$F%HBUA7YIgvDJ(5jP1cV6Qf*gC+dmqUpQZR-|&B&J*Ka@?o8)r_z%zV z41WX0&*Ijrc`bSTtmFf38+8J{AD#H;ejXU(_;cnIGSL^noa=1G_kv_Pb7AkLI*Sv? zL>~b%(RYB1&UDH|9|1D50bqZo(H8(u^bsHveFw-yUjQ=EM}SQ99Uv2Z0mwuj0W#5d zfQ)P&v$Z?o^Fy$O0%W4^02$d%l!-n9WTNi?8H}YpqYSX|kq6lR&VI?3i#+rZ#6#af z?V)Y0_RvRAd+0krCi(*ESKa4m^xhHcioO73qK^Qc=sSQX`T~%V4V*wG`VNqh%^c^; z+CGso(RYB1Z0|Vlc-MzAvent1=nJ5(=p&%6=sV>7%6);nUkg7AV}GNs1sUPxKui6Mcca zU%8I}8O;~l6MX^5L>~b%(RTok)=vhR=p#TT`VNqZz5ryRj{uqIJBWw-Sv*DTXYufT zFvvt-K<%NAp!U#rfQ`DZ zF&4k{9i-oH9)GL-TjI&rd}$m?>Z>D&2aH&% z;@;&RBi?J%m >^gZ$Hw%3){Y_^icQHN$bo%N^kd1KciuIS#ZY`Zh^_d43PeyQrL z^YiyTCLVZFb=mAzl&RXGwz~UE%MrJ^?9=MGQ|6KL)8Yy>8!xz(xZ{G>H6L%a7x5Vn zSJYh5@?yS=BFuQPWXjP7l_eG@vFfUTjM_k~wh^n%#Oe#N`bez4lT%|ttg#~27!ofW zTTEI$XUJ_K*M%p@f8jr1Jj36B@w2$&(s?bp&M3W`u`TD|U%9It8H6Yu!}_U~Z$_cY?W99TQ?9wErbJAd%pzq1kF>%ba|_Y^@U-Xnyv?#`c>t4$yu z?3`JwE-XG%4Lt~3&g1;q;nRtt>S8vX;uGyDx0zxA1~QhucLy>iT_l=36z^0V8e{K)DVbVdBE zE^zcmpiAQSEI^0E&)(*`CBO3r&*SH9@!WlnL*3_dRkrT)w*E7@{&Tz0o`<~u?5*;W zY-iMGXj}ZA1<1$mM8I?9Jt?oxr&C8NkI7s{{GJ7rji1j&`<3^keEjYP$oS9a#?SEL zx&KUVDL;~*-TI6n&+$@R{kOmWr<5Q0&%Fx>`U^j$caX|xr~bR&-IUK(DL-Q0RmXfs z>3ij_Ow3LweXpE-Pq*1xrSFx?zni=Cy>j_?UMKNxBJ2@&M^Nc|<;*WJe<5)`ROx%= z^6%*`eXksijQ_+u4jRt)wahkH{5I_)!``fk`L5sN9jy-Sn^;U9KMVT^oIk7UZ+sUh z+jfoHcg$v*bVjh;eoI_TU|-1nrSLv3LTW`*#;rFQ40=>f-ilC!hQI(sy~s=eUoESmO|R zFh0Z@H)4$^vHDGn@j!iOoA<4LG+&GL-K`(Z*J8V833eCaTn{}ksv20Iap0ZL@y<6q zkMG|C$Ji8bj9&rAJL`aB+zdFz+<>>ga!|SbMs5Mmac3j3-rFbEJNd-%y#>fyy{r!y z@9d*KV7(7dtoPpQz7My@3fI;^CcY2v)Pvrh^meAVKfPV*?NuYHvtzw|E4z{V z*zBv)J(f05-rn|hxVO)}-L83|ZH)P{aiqUin!9>D&%ICKeGMDxIv>RQCi2l(_V>HH z(ppnDcMJENpTiQy7~!WhKBaN^*VlmJ3OsWnMl9%G!41m3ONU>7Wf5fujQ%XGn7>L2 z{ATsMw0^~b#C^}2m8KmpBHn5I)bxoq6Ns0-?uK;ribsiUP22Ck5^uZ4#uhL7i1@ju z?=0@W`nSaScj8fJW%j%fpPRhJi*kA6Ng|K&Cz0RkO=7*)o+P%%+L^?5TKkjOe(P5f z`(735iCshMe`!ga*{`C|=6 zq~~{kVG)@Ty}v15zy4Q0DZhW4^$P2)`Tb9pZFtMBNt-{F}A+m|D`Nt{#jYI!OQr1 z`CNVRbrJir8WTQOn-?jovHi)iS_3~>R%?SYzFuF}*X8BCOnh$pfNK_O^>@G_uZMM& zFbCsbKaXs_N@G|W!_pckt%1@S_+8cjDp`15Dxa9*sq&1(-sV#bA%l!!2*mbJ#1M!T zLm*ZRf%r#x!&08t2F=H0G=2eN`%`&d7uUiaGBL)*F-F-xlzlb=AU1~Z{<&U|Cq~b$NTqE$hf>V?s-e`@0@2M^0ve-uZ_>7@Vnk1)9|+K zk&mT}%WKzt_ndfe*BoVBUK{nsyf)esl-G{;ys>RAuZ{BIp&<_-uZ?~&4-Kq5IP#v6 zhgkf?F0XAo`Q3MrcX@5}i{GV)=lXn&wQ1pRI|8G<%4^4QqrAp5wukjW-sQF9 zydbY_f9E*H_X9Adbr^dNe=p7B+yB<{=+C+m#;V27!t=j`^ARbH!yj=R*r&QYm;LLP z;yU}m%Kk$9YvLLU^Tnz++IeWh|Ao=VDDw;PZ=)AVw&=gNEy`VCXMp!3JkI}K@+sg; zU@ZP!eG1K^<)`v@x%DnY^yLG5a>&RBqE65|6~yXS)D?BQMZOZB|L7eR+#?#FFSd7p z)vwqt`{zQvRMIW~5o_{))h(L41oP`-9XhW9p8ME{tMlXBn|#O~n3vmEZ3( z6bsj*Uz;VIPt>m+hlSsNQTlEX`#zM?cZ=ko35t3E=M=F&mvyf3x&BW4Q|}7K)w;OP zO?@UPLw!CrE3{4U*{ zbujOYDt))e%B8!rKEFS~olV#yrMt6AcW0IE&Z_&IY~ANibp{2TAHT*{w|GP8J1J}o zf9+XsR zi7Cdx-9;SrD&kn-kbSfCwZS*>9+mjM9OUC2#lZ2q8ZoxRW^9rb$F(A7{N6^$Jo(LG z*<}ZnzFQ>Po3LSidt9&Hu!oDh&#J@f$5gMj?o{G1_}%JuhulqkP@4^FDkjwsKic(x znsGx%5uZNi%$oCd978P4p2XrG|IvrDU z1D-GO!Zdu2K0vCMmyv9TffTVyr5rkzJPaad`wdL{z+UH*fZFFcs{4o z@}d3QJ&51_exq>Ei(3*eHN9)NwZ~e-C)7VI%zorm=J-DAKPVhK=`do9z4fQO*UZ;z z$IlxQwpgc0`D1qz_?@!RV>)EJ_uf2Q+I42xlSg#R1~geE9CucA*(xg> zmbJO;)nxE}CzgHr<_Xyu{Vqu6th`3qpue1!?a}hp!qOd1TqhecB&%vVv^a8`CSyNb za8lN5i=)%0`Yu^@>?#AY6(`J0t1mvN>V#yk?8G%2XV+bPb=B+@I%n5Bv{9Bma(~rH zd#{$QR@fzba>v)Ix~w@rz5nKevn$s6rfQ!XuS{F*e|&bw!wsun?XpywK6`5R(szxj zCqBJ?;k)TWviqAgseac4q?wrT4!bRCsZxpu20zYl26lv_Zn8U%;bTg{bM(#hhFlh zs&vIuLvq+^>6hJZ9-DnUBy^f{b7kYdRIa^qa&l;V^0vteQ(s)?yH>}91KymJe46f9 zHg(>9;rnJwhCf|)QQ7w!Zyj!Ux+1){#Jy$bO<6lUf5Ud6!9QLq>-^5Q$&QyF7+Rk5 zdD&a9-I~1r#h=4&^BR;77`$l9Wva{$-jTDuJ^ zv|9E7uERCHd9bi`o5oy+mG695*z|}ExeohxSti-(`E9rkZyCQva_lvIxeoh$xqkBJ zDJO6pZg$L=LaX|H$a(JW4U)Bvx|f_;i!RB4SC%5@efuAoOuV;@oX1rTOAcz;nVdK5 zaZR$`(7nm|*)caIFFw?tob%Ruudu{R-N-rj;;oYX_P?2&!_F9y^z8X%g8j1h>$fK3 z)@?z~rFuV<9P!+SiZ%3fnJFP}@!`GfzKY|>(Ba_(}EeI|8aOLDH;am6s?!uI4m^8D7J;rU(2S++;VWX40S z$T|Op%aVTk3?b)|56@1X-}gRp7Sje{wPtT5*w=eJvPw93*b?OY?xc;vvahX7&ZpZK z!nMQJ&fB@yuF0m4epZ04XtUc*N#%_@kaOQ&pCy})y_lTUJyr>4bhw+GBh&T6wdXyS zKv(p;bh|Kj*t-dI#ZF#@=W{n9=LL@*A09p`knm~SiN25f z{Lpas=~q>v?@bRF6mC4BrV@Q0edhy7+r5v(ca?|BuWB4RUU*9pJokRTVYp@0Sw--4 z8MFcCJ zk8{X#@B1yodqZo;({T1i;i5K0@>F-!}0D^LV#c zlKLI)AkP(jmkpmj_9A&kHeNm48onS;a+@&fwAC{7t4(%B^40qn zlV|wT#pHmwv&i$t$aj)6_Nt$uUz=7n2z?r@l%ZdpPH7n$ciVtGcO6p^&YjkYJYBEt zmXx=vAS0xN8OjaIbbF7oO}JV$!(+7CC{0YKTXCp--bL*${K``!+VnF z-BHbx^z@13d2#E#lDF<(GUL2Ib7sqQrV}&rY;xhpg*o3WN1ijTT`8%lzX5sPe0<%cVX`%OM)ce!Y4=cX^2~m+ zXVP!#apXC@_KeDb)0p=S#m9@4?N(c!Jev=Hr}BdrHzLo-F%1g$U)7a7Z3ne1R6cbm zc@8+TqR{V8gUB;w!Oq1?w|$W9>Cp7D;#Liskmt&cCKbOrqaArpU#_BfW&Z&w*8h+X zo-FRM@^<8m{ted5TE~4@e5A=CRU^^dQ@r<;`SKo5IecotvI(AGe^6%RC!{W%Lx>3H-%!%px(>Ec% zeP?F6-0kC8w$pykrdN*Kg>}v8bU`|)*B9j3sMQ;3ho=uEX%A)PyNRdOyheR_I% z*@omfq5iz|p7z_b>}UNKq$BF>P5C9)Y?{72DPg@UZgXV186(HDs48W{FvK6Ober0li$8$C$&4VS@z3Ym&;xrx;g8*diJDrt+!qx z&$+!<$sYW+Yc|mKa?OHQ(|eb1NX{pRf1iG~Z42_uf3bNss>3FE*&b_Vw=@lG=Oedn zlz!TN9oGBM1{bDZKX`U}kgc)SbDm0DwttZPXJ_B1w|w*g^~onmvn<@bG&#{;v>R&` zZA4qKK9^o`-E8-UYp^b~5pBi(y|Bw>S?Ibx>qQ&UR_GSA5p9KTK^xIl=qR-DYHKTW z)YZ%HkT!a$KIE#cYSmvRr@eTakT#^-JW${9_%U zotSgXJ=(d!X?O3bQKLh%?@oM}^_z_NKfgbPo&eoR>%zC!y$9kckpr_DI=p^VSv=cfB zx(V%sPJ(ViJI}l9=(NuU$JC;(_eM-hFIeWGTJT@>Nt3MCF3Xd@^GzFNH?6WUIgjbv zHGBD$t~|%hc21jr)u#q!J6(8acEFm46~S-5SGwZCx7C2>AMc-(^*Mh~5p|g#mfdsj zCpBoZ`C(bR;)>(YPV>XEE#EC0hjyADmTlg(avXTf56dQevg0_Eeg4{`(*9dNQ;E9X zc;LZw)L9!8z`w;oO|rgA3@U*0jZfNTo!ehk0OwyW+b;XC-h=`;HJ$~O{rl)cvUm2L zQ2@WjlRW3Ydt$cDUULelOJhq;jVC!Zo{1aJ#EoZyvS(a(XnMrgXR)ql{#2WG{O%?4 zuX)`v*{+qX6SQ;n7VBn@+_iOrb~gJU$-XK-fSg*NEc?|5`)9-E4I#hQYJ&duyY!f> zJUfqdX|0k|>yw;XpXAi~B#+i7%a+aBD{VgU8P>JWN_V6e{e1)SPage!`t0yQF9k%kbl`zrl(ULc#NF0xA-hQf8y8V-01G*vc38)AF!6*KW)uy=LgHksdI`v zI-AJz!m=A>JCEwjI^W5u^PQYJ-&ywQgQgc}4B3bL7hkz{dggX_k^l52N2YflzC^%23Y{)a zkLlEgoKJsRmA*S?Q*z$&N}3Mqx;r^#N0H}|ub)iU{;)6kWk-=ywi7vJJCRfN5;O)AzcqN6z-k@0eD0??TR_ zYWk&*oqHfTWtWoY^X*SbpYC=n`DK@qQ?@8MWs8zi_9r=If09%7CwYb+a6|3D&5tJk z!8g<|Uf(5;kDYX5q1bV1lf0dK9#LHBkUT!N z%+1R#*z2ldO~*r7*O9GGt)0F>9%tKi`IrpLmVo5l1HtIQOGB~}cU7%@+a4H7E`ORN|yv0|{qiop^q28;M= zrWh=-VzB(2h+?qSkWmb_23RpzV#Q#I(H@JP5-SEvtQagYVoer^B`qjI-Z#HQ({Y*>5_T80|$&IlhD3 ztZ}32_zv7Z-=kFkQANg5Te4nLe_ZO?;JIDu~Ik76fgN*ln;`J*@+QFdS-@lb!RjMFe&gS$H@-8D_EJb8 zUoP+5cJ{kZHrDeL{gr%*aS#ta|AKJ?zvcZVVmwiAhVfK;GK{m@nPL3Z{tWYiUd8zW z`mNW4>B)lp_sn!-0X7`gnCZrX{B+pA1^MZ)e-ruUuzwTz=BepM+QC?3c19HBYva2{ z6WCkev~wYmPYv5YkxvcVKan2|+dq*Xo!YrT9{`+oJ{IH`+k5Nz_p*Z1&csCiFZ`ZF zJ}>;9L_RP4o8Szs(1r-v?hm$nQ&SeiHd^naxik-z~HG3G&x6 zo1Y*bEwlLv^3gJzpCBI%agHD#Ewy!&$j{1b9pN2n_*R*%qafcZvvm~YPi3}_g8Zq> z)=`i@g&0qeKV|cNOfqz*Wy>)~%-bGYzdWD!<-<0Q%`d|oAqTbYYEPCy2O1|PEO4`IW_O()Vz~Z^G;69J2^G)k~Ff+(+cpJ|d^~5jnMwU|+?31p6xPBXVjVkyHDfoZ9c? z)P5(Y_B%PX-^r={PEPH2a!N0eQ+kP<(o3+}qFy4W^b$Fxm&hr-L{8~Xa!P-aQ~Hyf z(x2p%{v@aLCpo1*$tgWgPGIF;Jh9Z=LbR0 zBjy?B9dXV$?}%-Z)A>Ho^N4Md)A>G(`C;9ooz4f$ppUWc(N5?0VSOSF$#y!w4|+cO zeT;qL{Lnr^ERpSWJ}>k<&ku|z&JCO&((_#R+DC{Pa*kXa0D2yAKXT%H!@5U1alT>Q zgVXu@(DOX!!0G&b=p~-VXs3&NKrit;2B(X4Krit;Mmup1W8H((#X6ur5l@Ty6EU=? zKWR6B)5Uq9KWR5ef6{IMr{ZSRONxC}pq+|$RY=bx##I4M#kks{?}~A?1*c+MZNaG+ zS6k`%825vokFh@Jd9HicPQ>D3J5$%r)U`8}p69xESfK}V7zpM{f@^O4@%<}OOKcA~!jwk+}*T?((&`v)0Yu?Y7A6xV(j=9E= z{C)$B^)7)7ew;96o;jyI#Gu z2cH&hU;dQ>{=LEbgTl8{4&b|NUmZ3ujIFL(1bZ1@)^nn+hgBEaaJkyx+h#a>W5>Lm zz;6lX@qqm9PvglBT*#AcB%V$8D5iJJIV$f%amnoXq5BbUwP|^_O8J}_F<1Lh@W|}S+@NlJ%~qlwC@u* zzYnpEPqyB|Im-4?e_tBjKf9>o6Dj7!<8X3^?3S}PXW4bv*ezT6`BjPUUHOo#*J*FF z4ZXfNE?alqYlt`7>(uP<9?gl@|7=J$z{PIU93&C-T2Miuxh+x zWPOI*#x~THpOk$$A#dAr*YwYJc>VDdoEy&BD+}!#k^j5F+hxgHYZH6^xohp3eb}}o zpMSr@!P#e5zss`ijyNvcZPfL|A2vHR`^(9z5hvda$p#*=T_yN8Zgxs`^AjBs;4WL) zyO)n#LcH#%Dd~Vik0z(bSkI8f&kCbY$zH#=oSYktADG>_##rLD`t;5EH2aXadxu@J z^sv=fruXDcvX8guM11*eO|z3b^dx@o`VZ54I`<{6SuiAfevL!ewszkQ$u3{11@X?` z56PBT`O40y*UR|!co|dM4-3^$fA+m!9Nv=}DHAo+Or@B$l46 zL|xL839$4evEN5Jr?}Uk&+VLIS)6Nj78C1CVH@h@XBM%}EMlEm#5%Kxb!M?`I>IiCygpAqo#hAZP|3QVRDKS$v4pLz^U_I&QdaOv&K zls~%tv&n=bjtDE%)+@hm)fK`4UH1s9ww+&g+IyRXjtx77PgZ@rZ0+&8h86=`gs$t} zRCec}Lqgxr<|SV~a9Y`S6ORwe9(Z}u`>*9?d(JyG96hgoQg+Bi>)1Q~!QS;RUNE5c z#x-^t9KLDZE4?Lof9wWV9u>;Qr0K(5dsNjfzi&8WjfPp{k1nlxzR)E++GM?~?cga@ z55K-4?|*D|X6vP@r>)a2>EHd7?2&aF zRo`>>%X$9La(VVVjn7R!jq=8mMjqqOBEQv}#d@thS!|EBGmGuC_GhvE`0PULm-RQR z>+i(lvp5bmK3N3xb)eOfB(;he0T5z zwIi;6ve5m8)3V81K3jX=B~K7vdgQCME8h4x@hcC#TYJ&-j}d<`YIyCJy`LeTvhB6C zGcS0W_`Fvp)P6GNDdNozuB?6Km1lFA$9mR&HY~?q&--)jjmzfv%N2`L)?5EM%KT;E zzEit3&+$12+%)xy_h#|=vGrb=+ImWkXFaoY?RKZjD4T-SkKBhCN}<+ zar|uzE8`g2*jC1|ZP0Xnxd`LJ-;yi;v0yQk;4nM7mgu* z_M&qN+jbsHeA^di7tS70Mf~R$XBSTHlGh7v)PcQu>eR~%pYJt_7{BpvJVzVRR^TyT zR~5cJ`fTElpBh_O>aW9y58dI$Li@YVC4RI2=)xXfyHf1vQU_ctQ`a#~iHRMnCAiLPm3|0g;V4}QD0@JQH-_`pe13xA)p9q}2p zQwpD-xg&9tO{Wwt9lSF!);{(C_^}?bE`hO5v0j0(hp?A`XPo?4VdINGB7W!7nT6(K zza(y%%q)D}ryk|!?>nP#<%>%Z*W2aM!o((xiEm!%kwU*&D-u_hO)s4P?5f1r>)7+) zhpsi9OAK9WI+qwa1G)n;&;if|z|alQ5x~$}&|kpNCD19r&@s?8z|eoDXSW1~elFoLFN>tg$85 zyc26Kh&4yVT0cd!4Z72GC^2-W=}=I4kd=}G#yF|-Dx_M7`oGRXf9*A z({w1Y&KhE!9mG0Qh;?QW>kJ~+*+i^!lUQdNvCcSRoxjA;ou)(c=cYSNhY~|~nhqs~ z?lc`r4Bcrulo-0xbSN=&r|D2)*$>1z(}{J~6Uz=EhVC>SN(|j;I+Pf?({v~?bf@W1 zV(3oOp~TRgrbCILJ57fY%N8P*Z9^=Zhgdchv1}w_*-pf=&4^`d5z7W6mVKDZE1nTUoQhMF;2OdDO;x6qa~!GM~>q_}oH^^YgWB zzYF$nKDWOYOpe&f6|6k5@fD1h`pVi>xN(!`%b*YSyb@UQ1z_r8}$KWJWwAn#tHQSW4tfu`BAxh z&i+cii09%V7C*7-C02Wg)lOoypZL%FEL|Pv_n%?;N|d*GpAzR?z6_ts=OV@#YiBJn z&R9EZiE+l-SxbyF*3MdDoUwM+661`uvz8cVtev&Q^81M8#}S*|0soFzz9g~y!CWTy z6N%+Z63fRVmhVY?+UD=oZudm4H+F3HUhT3^=Xj-e->rS(*&LfLD%yEW`SqSzx%k4_ zxqhg(VEN(;kL2royDOF{KK(|nPx{QMU%chTT+j4=;hWm>F}eQPN5jC0t| zV`7}cb{-Ss9JceA7~H4>d&kb-qMgUY_>F(#IogP}0^=OE^OzXtu${-mIEU>#CdN5z z=P@zPVLOkBaSq#gOpJ5bd>LYl6UGbt=r{TgjPby@0Asu{?!Xv7j3Y3{72^wxImg@s zV;(Rcz?dJ*6EM~e)(|kxVLOkBaSod=LyU9S&SPSn!*(7M;~cj0m>B1N5jC0t|V`7}cb{k?@#T)s(%1N`>2t+z`W;OBf6_a%ipPC=3-OMVXB7wE`Wo>^ zr_Cy!dEYWDJGASp;wsCmLHuCzS;fD0X-C}C&e)Ov=tzt+9C{XYOBNR76|}So?_bTHC~0^TgVZ#L&TrE1@iOFyczU(7}i+0Ye8Pt^^DnY`T~j zIv8;!JckZOTnSh@fmnN-SbLvXx`kM}f>=6)So)1vI)_-gh*)}(7&;hnCA0xL7;zFfKo^92Sc-uRl zC=A>8=~_IWcfzc~uI(Cg-|f)-!NSxN*C)?vt6y6fG4Vp;K40%xIP==P@3nWGUpZ>0 zXZYN3ZNw&1j51cX7|R-GF>+d6#aNfMp%~j>Z7asMS(}To&DNJihvnPYI zGlR251I{1lIO}h4Hf?bBb8t3oaJFu6c6d-H=2VVvPyQs_(=a6Jm`avBs8Ib3v?mC)QjL zYmSJuehO%tau&qOSr98{L9Cnwv2qsVQO<%`ISXQ~f68l35^JpzYabCSXF;r-1+j7# z#Acr(XF;r-1+j7##L8I^YtIsEZxU=2V zV&yD|Wj_$>OefY^Pb@oxSUC$~=2VV&yD|m9rpr?{7rghR@x58qs#* zbN60Hw4L}|widB$Fk;zk#Ig@_nT79}L|cx}WoHsAXF;r-1+m$&$XO68XF;r-1+j7# z#L8I^dw!1}Ytnxm#k#{jwU<;5`YyL2?;6&$5QaWdgpT@jkDi6M>M^z%KKlDPg%7@9 zZX%>h-dH%d!Enk9+-7p&^w;+!-r^tA3vcbxocQr6PZxF?d1WnlR=0fgIx7`;j$BZ9 zrf~T?BdD()|NfD}U1^g7WLB=dw=jKLcjA_Bk1dSPh7liGc3$E9<;M^oe$3v5NoP(X z-l5qlg(-vRbA?{}Utc-=gs1u3_pw+tw06!^`b44qqYaARo#*j}c#(Jy?9|q;-qv=Fyb3;yteqawJ#)Y z|I8W12`kVa47)wPQ}M!sr||iCeU>ZkeK~!`@MyOYwGFm?hR=N;e}vxSIQRRAnOf>^l;V&x`?m75?|Zh~0331a0Yh+RwrJ_~XaeD2~8 z@L7aP ztPL0cfzN{61fRS34}2EnCivXNtl+aCH^Jx1O%N+LL9E;av2qi{%1sa}H$m)TZtz)< zo8WU7AA`?=+ytL1H$kl21hH}x#L7(&D>p%`+yt?56T~il2%iPH2|jmmLijAmLGZbY zE5c_%&VtWfEEGOV5$7((+{G>7vmiIY=gLhGo6myW1hH}x#L7(&D>p%GJ_~Xa#L7(& zyO=P17UU-Q+{JIp$-^l;V&x`?m75?|Zh~0331a0Yh^6O= zrF)5`lZka+5Gyx9tlR{#audYLO%N+LL9EkJ~+*+i_fj96zJvCc$d zoxj976Nzp%`+yt?56U53*5Gyx9?B3ak_7b0WIB_?rV%|+pYNC#(ZZZ9N*&l;ss}qr2IA~Pb+p?uAI2l?X!xN zTf9Skb^0fd7r&Y@mu=`(?~dZW%N$ied%Ao%q_|9y+b8dB(x5nd^b9`7`&al(o$l^S zaHpQ`?n`i|p6>3$9e0`T?yI|N&fh`j@22y2*7>{a^ck_L`MdA@op}DPJb#Ct zzgy25TzBW5zl+b`(N|G(F+Rs+pL1*SgFF39K1F@HyDvk1y1Oq!eYhJCcj>vi`|#O2 zd|nQB_wl=GamOIW3H9mjz6{^PUVZT2ad#h{$GiI=AMfr1kBu|$?gM|kyASooyZg`{ zjLc6i`+_wxb4Jhd3D>=| zoSw7qeoVx}vGQZ6dO5ag569fkh1wr*zv7&ICe*mO!}TPf5G9>wjOKZhYM-p>@wj<^6|Orq|qXa@gjP<;o|2 z(<7aG`rt5rz2(Z6>3KxjY}-NMkipCT0RPOgNi1ueN#wM;l317VB(V)v*DsQPqyExa zz0>yzcfI>zS@jEzvRjVcEA%+`y|Oc}Y?{sQ(lgxE@SUL#^|2aCjS8cg0iWV9V^b%ILE54)an{5p48e<<+1Ah z$+GHuW__>Hm}E94RT`_z#;Qu=kl7gi0RNn_n!C*Au1a&7*_>8st}~nKDy@Oc*1!*O zKJPzSR%<)6wOy?>pV^wP)?UbLFH~!tXSPRvfPZFLtZkOnnkT3B0_)P6XB#}$zWB+q zSa%pl^d0LFbAU0yI>j7dtgwDD2N=U2;Ga>}$_2~;<_`M_bAUO;KEoVfuC4xnIlvn5 z_~(?h^%gLWSbNY7m;u%5O+4I#9;>dOEUW%< z?`uq`6Es%T6&eTX5RZROS$C=_1Al0>IG^ClMjNt(^K-Z~ z4yAEeOltu5?9f&-{u0jhPiY)VKJ@ceRCh*QKw^Kes#Lg1d_{xVtEWyNfcoyC{RZi!!*oC_}u9(%0p2?{=GpbLMuW zABx}jH_mg60pxy+y^Jr5KA{hgN88Z{V6@%txg$o~?VdYgwB7ExBSzcpo;zZ+-R`*~ zM%(Q^O=903UzdN5xw8B3D37_a`|pS`S9bp$G3Ltdzaz$6+5LCKm@B*gju>-g_umow zx;*ZF$Eft0r*oP9dv1~TeJ@zubEMy^vvGN#vD1+yy2W5c$I`P=c z__B7tVsLkj26xwJaCeOcch_iecZ~*j*JyBejfQyFsNJa;;vJ{HF8|!_at!Vc((u{B zJ4l1OgEY81NQ1kBG`KrRL%f63*X8l<%O4poUUPbav1Tvx{Qg_qp=AP{h#!er*YN*;OUwfZ!ym{y} zE8jcmi@S&2#;i!5S>5}DxlKM@qz%3<-?n=y_6sd~G+^1ACu|+=tIY5Cy>OZGu>L*y z-M_;Y)DPW0&+i0&`0Xjla(f<4`76KQGkI_C!NiTOnpQaSxzmV!T^<*^KUCQK*<5D% z^?M~B?2wnmy~wyj5aa2wm+@uCUUz7?qwn9jRy`iQWUsK%$IE5lxq0|@Vc_%mUA2Cl zcm>F`)@xuzkR4Y zD!-3+t+)Fo zkTTMT#L}^gU@zm#YA*+joAf`i-Q^4YpWwOO@?r_}E9h5l!~ zc9$>oKe2C*uggETJAQHAQQq$O#d*iQW_SGJyvz4R`AInMSg+mji}Q}y?)b%d$2NaA zcsrbT#J(<%rLQO>eMKxCNKTKvj4vx4n_+xBmcHe4>04sIPCWK9zO3vemX*CkEPIJq z_7bt|C1Tl2#Il!&WiJuSMk4lg`RB3^DI@!kSoR^Y>_cMNhs3fEiDe%W`?@@qy-FF` ztHiQ_7r|b}mzAx>d6a!l4BOWFz_kS1*80FT2HV#9kYXNT+gcxpVcS|C@_Nm-wLUD; z249zNCv01rGs?rZwK*dvY+IW%V%WAeXT-2=ZO(X?FKkPGQO;AV7A#~*~5G;dzjd-6OX-&FALk&_B_kNw&lIv)<@X3xYrx~g>8#_ zy@6rd;$ClH*tWRW8yL1N?)3(SZEJg;7`CnLb7EhYe-7Ig_m!h8Y+Kw{4h-8C_mu;~ zw#9wrz_4v`UpX*rTijO;4BHm>l>_^_Jcey+I+rrAZB6GA!?ra&z6ka*zAS88(-&MD zux;&(Nl`CsTRUTjVcXgnLk!#2&KUB;wzV^c7`CmQF~qQK?TlHZ4XCU8!n?ui+6mj% z&Q!|7wzV^r7`CmQsl>2t?Mx+xZEI&L+XLIy&QxO9wsxj+-@*1YJxh6yVSAd+<#X7c zrgMq?JbLV9d|7<|fZ0qe3)|CdCSus0W-}4P_B5M`7`CU`OvJD~&1NEo?P)d>F>Ft> zLD?7Bo@S#E`?~yd*q&x1vMg**vk{45dzy_%4BOLeL}J*U>)n>G4cMM$Bl0fBI+?)nCr@_r>UB7(2uz$_& z%-6Hozh-xG++hEjExQPYjT~isS(DG4d>uCV%*ki5F29yMHqJU3U)JBZ@3HBYH0mGI zEoszCrmxbdlRfq_zO3!L5Ou8S(%^Jy;&f@^bZO#rX|26Q@nkLi{W^^)nU#Oba&>}7me^UE`{5xIUm zHs3unn~%@Ur_an5q;B-zW#F-w@ny~S!1wQP9eQjwQf9UhpW`?Fjr|T;$o&|58DG}U z_rz=t%9~A?;JYzU7WS0cRm8BT@ZA`A4tomUjR6dM3g3+Z40{USjR6dM3g5v4?Azn( z^3P#U;X5-R4|@vVnE?!Y3g4Ll40{USnE?!Y3g4Ll40{USnE?!Y3g4Ll?CbK_Y?#Ds zBg&W!lbFp!Y<5w>Y^g=Cm+@sGi!!LoWALF2o}(U=0mc}k9Y4li#+Sw3#omCt$JpQ4 z!+4H;k39?wy90XR$JopGvama_{vZ##!|V@Y*d1nn5X0^;`-2#EhuI&*ush8DAcoyx z_6ITS4zoWNX@jrJw-a`U*&i$myTj}cV%QyKe-Oj&F#CfTc8A#?#IQTe{vd|kVfF{H zughcXKkPB|7yA->3>bSC`}W7!%lNX;4bTykcNqEuIs(t3SD+(+p;MuEevG}0FN^aW zXCdT0#+i?^9M6U0cZJk_ACu&1PkI?&7H2!o8}N9Ha|ve;p5wg2*#nF-4QJbrv6t~> zB_EtTvE+#*Ppmd9g1w9{tM$Y2*ZN^utsi2oA7ZT^Vyz!ytsi2oA7ZT;VqcekuKhw8 z?H6M07h>%fV(k}V?H6M07xu;1<+1iJWwd{Zr4tsxUdETzI?OOH9%~))xz-`E)_Dqf zkG+g9t9`_Nd8~cJ=h{caemp()GQOx>}w zb@}HyA1R~rkyz&=vCcr=MJCi z+#%LkMq9;WFXPMV++=$^*15^&IyZ^^czWz*d|BCtEGzqv7;!|z6R|!KM?^dk7;!|i z4~Y>+L_87C5l2Kk5g2hq#1nyK6B7Hn{BzmEltJ7S@l%vV+!XOsV8l%kKLtkI6!BAF z#7z-D1xDNy@l#-5m&dZtDI@!wST_G6*vt5`vSTUlvFunrmmN#&`|Gin@nvPZ@|^Nm zb}a28*|7=wE8BPx>}7me`Gahm{6S*#@!<~=n~x8Fkl1{D_=CjeqU4 zW#pSjdBi#v!CuCfl`qMDDMrDvict_NMnS9?1+iij#EMZ6D@H+VZLVvNuggDIOosA` z$q*|hL#&t#v0^gBipdZwCKKliF_}fM{AE6uzs$1o#}~m~#+Q}9ALZfu6PrBzePWYG ztRS`l@q|UNm+@t7|03o_9>v^<6>}q2%#BzvH)6%y@;>G~i524|R*aX}x5wAzpDU(KdBwDe71JhGOq*CSZDPf=i51f( z_H}t|`WA6f%9y@Iyp-5CO`!>FV+iZ_3+aG4#OWZQOwrx|p z9dX*6diJ~ak7b}vy?5%{Ci8bK2d=Q=MEgbUviQDfvwC|qTmAGai3c26&fZicCSLd2 zLAG0mFNsID`7r+Y!$U0U4;{TE-gsC=;?gBY#4R4?cV3$-=X{fM`rx`OpYu~|e3v(| zlxKu;sUL;u*Lcd7g<%GVgH@-piS%&Mc*OttQPCF#cKtDUWybx_D zdlYfg20umLzv=qxx*;V^8X)i!IhFCbohRXy`b#V6Tc_ie0i zp1%Gc?5}9oiKb=gGVF^w`yFrYTsNKg-V@82?f2&p5Bu^UQ{+h3U#+kDFzWP@>#rg6 zmPE_c2V8%h`R+Fv%LlstT9dgl)n8Jc6UwE29O?_5IM5OLaiA}JZQv{N z*dUL{X@i_1zYX$ByKHEewAY6AiXLpxgXqTw{fORd(3|Kp4*C>5$3f4c|2XJh`Xvti zg0+tOnaZ)6H+ZW3ZbAjwyT{M(#zsB+JF(*!-YIZ@4P`iXA;cWuCbSFeQzaHj(9 z7XbF}`xDEbsdqyC`~ED)d;hp!0QKdaQ6s;IaZdp57eG1g55WBbz_7C^lb1+tcB-7~ zJzt;L(*dnQo<4E7X8`5$lX?d>+)IE$FF))1@6sg>_Zy%Nbli{d^y|e>l1rA7Ii#*V$YXYK7u^NUQS{!Ke2w# zL-(C7*Y!0WO<(iX@@P4={JLFeuRF(0wKw!*N^!QJ_%x@;(Y+kq3Op3;hqfLAke2V(?jVSo_eADZBOcLqCFs z#j~D1vFA%HA3+{s@PQst-^))deTQ>!2(j-kV)-o3>{G@a=WgAPx_@=QYkSak z;^m?I+OD*{$+*M)A*`d@tMwpsQu@())B5!NMLJslzQ5QP(4UMuv5(*Oqp#0C)%~vR zLEDL!hdTFi5^H^sr-BpRIy?K{(1VYuIbZ4Zzm5w;A9)sUs<bn;7(a^)OM@wS=+g`e?2bb@zi+H<4BLM^z7FPbU#Gy!Y!cvkeRZNyXRU) zk4-&hy{B z>({>X=hb%2%A2x2Z^m;`TWj2|oYTwkywq099vhEXa}3V3<=?Wn(F4VapL=XujDIM1 zWy^?B7tf#^G(Za&v|HRVKF!f-fO4GovRvv%p}z1S1|6YK4Epj9XUiyqJj9Skco2i9 z@F4a)iQ67_d$uaiQ1v54CsOny#aC#gz8j;z{?`aut%LkyluZ^r44 z?Seek>1SD_^dG5yq0UgJ$l~Ybxw;MhvVB)%af`J4?z^X3-TPnZJMBBexPVE9gqcVPHV{B}Q6Q62-M96W$gUw*M3=)gat z9P~X8o{xF|jE}5;hUYechok*#oS@26XCRPK(ShG0FX4%^n!wk92N+3RoYe$5Q)^_Q zZNgj!U8?q`&UU;mL5p<216X*b{3Xi31Lg8#{4+fN1P>HC+EYWFLftDZO3mpq2I*%| z@0&{(vb^pw!_p3l?;$o5K1(Zf_)Wy!E7eNBbi-xD&o}RyF8_$7EL}b$mb&Tk49=;I$S%j7d))CCV<&~Q9teiho_fpTzE zl%K)e$3BJsR&xaAK9<9Ot2sh^c505WYL58L90xrHf34;S)DLq6 z=!7|f^Bn49eo%7+?2{=027O+NcAbsvL74>p(_D2Xi0G(I!1NDS3>N6LVjf z)6E-|O3wG~`pulE^k9^JF!x2iU6}jiv((&2jJitynEO~RJdtCH^>!GC#O_?qmFE_B zIp$~j);C{$IOmb;z9Mc`p^p51k67$1o?Lzn@zXQs#rOxlD8pyKsOz5TDn8?@7_?9h z+A|Mbm*wRYfBSGoD3|&XFzO2(V$eD0j=PADNq;^*d*Rc>FI9Rl?sfSa#Bqb!@z$)5 ziT6+M77xDr8{+g&kBSed`U~;Zciw{cCFskrK33%!s(z&CM2dc-_(n>eNXZ%PI`lLr zPwOwDD>r_~c5R;XV|4T(WreNH^V|VZM*&+|LmbP^@m4<&BXS zE16^ctkUgXpH()n*JqV&#G0>uR`b&Jbsb#}Ta+Uy6;k29EuCco*gf9Xe=^HMPv zvFB+}4mv6}0biDbC*}&&ksrid#NeszP;7Eh! zcYetA+waAx_M#nZi*H|UutD2={oje5KKz|Jd^Y#^*S;3^fiHgN23s#P>i#Y)>wT=} zjo)u1Mm*uy{ERbv%q5?3zmatim-yJh@0l^?GKgb*tYHw}AWi^%#67a#nC1DQ95D;a zeJsQJKE@#(AN!ELkBPWf=VK+x<6|hw>0_%@JOuiFztI9i7F9pQT%Z$TF2+NOFL~fu z=s?LCctC#aH)f+w;DO&LS9&0iKu75<#9ZX7^c-R?(f}<@8`$qRvOMWK#>@Lu-(kFp z&*WH5aH5CA2J+el!d(0Y)|QwTv2UC&F+#{0!FVpH7y)_xdTplHYKI_Lz3lZZt z{zjYdIqCu9IXn*xdY}vJc!GPXT=D=@_0xbo9b!+P*z-+ybSMw8my_7bPYf=?FO*jm zIYRw3k&js9O%r~^LO)IT5#u-h_VT2oo|iLS_z{Di@T2_TGk$Uro}>G6wikSY9>6E) z$J5UOP0u&mw+r$RgHO;u_&|@SgLZ{}#2$y=FR<8u@cTFxdmMg$!D9a*ob}?j-;c2F zb9Z)*=luSK1wFryBXkrHH+V_ASPvM_2|t#Dp75jm_$-{A`*Q4Ch5C`AL+t4j zd%gyBygbC<1HGUee4sC2w9DI}QTAz+-5S`1w?m`s+$j4uunTX8#*Z)9p@Cg^I}|z? z)A&i1!wy4z*ju1O?CBGGzOb<%53!e%*vn50E{@++v@6&r+7;{;bb>vjT^L_{R@pz~ z3F88ChVg=SVSG`3KfY%9c7<^l>QfJ%4zZ_C?D?kqc7^dC7IJfIu=ujdXur^rXCxkk@HdTtUvR_c+Cp3C$c2VF|uSa`=jH7EM|Y`doe zT4C-Z_I!!GJj7m3VlRKFBh~ioJLPle^Sp17u}Yt5rH|<&y>H>3t@kb57xumm``36L zzJ>e0-nU@P8_2H8;afs|_>e${Soj2=9QcxkmxtKw;;5_|olzYC!ULImEC$X2G*taW`r*h+vYZr3n$j9f>A+Ijv*x@(+_VT21^6(s< z_wuK5_>gNSxqa}N$Wu(^{Q3Iujc8XYN6^zxN4e)q?ByZ$auP#NpEqN`=K9O~OzYQ682hus(})!s!|pR*k6S*)i~-^)X+e0z|e z``RaHU!i>n>@4JOX`iEgk@ivAcWIyI<=MjrYTxM3(pX2g z5%vN(@W0f@J}0rXH+5DjALUuB=kmGoe~$R8zUPa6`j`F+{hlxT(*M$5Vb1~k*u-L= z;7^+o`^3ICvHZqLDZ@s}w(<{xANJK1cf*5hLY)v|rNxO8YTsSIWOh zyRauo`Grq`?Ny5Yus#j_B26f`zPo1Nkp*;T#i1^qkk;wBAiw%fa^pGX zvoBGalshdXdPwx}f46}oe)*&GbwTZMiEm8#e2ty;C;hmu^keW=|MxKq3dx-4?S7AS zUQ+(QZ5w(G>DR`z5x+JL_JX*E*vB=*KCU75pA-AICWdYKxP}gj)e@K zKC$OZ?ByZWcBSnN&$}PD7D;fThr|Z*+6Iz!zV=JnUui$4{hRlP^n37!NxYVNKY}_D zy}_^3xBK-8@$a42{@Uk;@ML*CmJ^!Lfcr^w`@gLR7qja1q+Vx=Zm=E>ekpbT&i}># zC-KW4dlx{**WPB?FG=4uGth^hLy5i368k*_#$|pFff%u1LA}SZXWv2M#P>oAi5{F5 z5U$8_VZ5-h+2BvXR}c5X%c&0#9jtsFB`F!nb^05*te0`x1HGQgxKqf*z1t;{Hj~@oa?{RU#^b3 zT{eV$>GPL~QHIY#AM3eI&v|+-)N`bdGdV{JjsLh0?)aqkK~nEt=GXqIYFFx=QoX+* z?SkyogTD@j+YXGNfDMvmrX-fUnJ~H^Ib?_g)Hz7BDiaJ+(Ho&fK zQ8fbo)O54!pT7q=;;HwGP=4 zbK8>1aiZWup~+2a>+%EJt+5`d>V; zaQPKkt0^1$A;^Dd%TF^V-dmT?LieG)AzvSSAHI2VMw?D6`E0+Z4lsRIox%EL4=Q7R zs_ow63c3DX&Iod%U$)d-7j1o`H0xJfR@3y&K921Q?+JK4M9>3p)9sz3O119gvuy_# zHs}2K1Nn|zaJJdFX(#J6|8Qb-RGFKJ&or~59`SUihw|mkW!X=$KH7(NdOI|*L(s4F z;rwXuL1(jmc%K1vh95iF%(>yk3}C58zv69`?bv0GfQu{o%Q{*If_?| zI`WTn@GSZPHVk~o+Er15@zrV1o(`YgR=I~+UTiL(_3vHepuW)MnqNJe1N!OL)-+$& z?H_|L`VID~c#$UhNBYU4e9+=2qsitcKI`A#;IqCTAurw=#5>TWgFcaQ!8*R*A&Y!Q zJ7Im_kED-2k-nk)zTa8@`O*(XWgqX%`r#cF$m9EwynMg&*<<#b9^GI4cs`4MgC9YC zj8QjMSI2el$f$-g{JZJklF?lUJjQ3kyD^Z{k2~@W?*O7c`T;%#b^JIbFF&qX-;X=e zhc8E6=*N#!)_?K(_u>n_Ys30}T(iC(cWjp*r+oJ3ISb<#zNo}!(I?V3tnbG)>u;WU za$N10#gq-7qaOI8Pw-AB+MN02S?+x=ai2~${$Road@qCi{JNgY@44RX z)fC)Z?{cD3xz}9N{1xVU7x%lq)0o{U|0Vrcm20hiVa9U`2bkTBKUD&@vo-A+vlczbWB6UVrF^6)6+iN@G$X!za5{}pk^V& zYv$eZ#nR$Im5Hkkc(!V(il-6Rxvy8%nI&5hFB)}nl@=4)5pOuO*t}W0+YqNcfBU?W zwi$8O($D9OJEsou`zy<4&B!WA{K>cmS-pB}Am4?Lo|Tntt|b2c+O}Ei>O6iQWbn8O zu&+}U*gs3`X{Mpv^CI>#5PR8(z0AbEEyTW!#J=ssUMIv}SLEw;Nc?;Bk3I@<3b3CC zBlK6ePXXm29s&0ADeHuI2YnjiCOjMB9n=r83CjIE9-+RU--$y!g*qYL!Luqh!5UxI z9XnV*#89Y%wI0@dcs9g4C=YQ5%0s*ZzAAihL7 z>xX#9%NgP+6XG4zSFuUzULn*EaTaihr_int@8H=Gr=X5spHmMihB7z$cn9@EYyuo& z4Llp-CeRP@4(fy$1Q_+;K~N{W?~Sq$L!msxJL*})CV>}X3iu_)J9rlHF4peAA+}O< z_^gUY0$;=|@M$SJA-2M^A>P5~uu~tK1YTHknh=A4j*6!+UTC|h6XFig4Dk-?s~9Tu zJ86cv1NB3^gZd%1LV1XHKwrfp;K_ILQ9s04z#*Q(vmxHWvnns4!01t`K*ieu#HaKg3oj5AhCU2(byuL%ieZ$M9LeA)Z2=5bxkw z6`O={&H5pRLLC*4Fa||zgYpn}fM$qyz)QtY!LPDiAqGMH5bvPAil>5KW&IGRpniyV zP(Q?3z#*POoe=M!Jj7POA#TE)h4JKm5}cQMaC5SYCClB=2J^Q)tNamF4?Ca*akckn zSN(b5$;5JpdDV=JbCs3@~Vb7OQJ)w*m3}}!&9^HHZ36~RwAs;l19B3Br|Oq^y1!5t?ZZ#lr^cQ&_WMzW zJ?pSfEq|u=sj=6Of2e~q0DK0Fx_AZ{G(ZbD&;|xi?3V+f9Q)|No~Ho@9mH_JppX4{ zVDOaBh~>}!`2ACOMtHD3cw!F#W#FmkAP*(bH;OOHSdO|%PMjYE`T03$O1o0$3gD^q zfI1d6Ku75fd|3{j@)@yI`#0Y|H8s?cYQN&3U+DX<)OT%0tj(#vYKnpGHuij$_<_%^ zUEcbf9OB9Aisf85>OtZ*BU+U)exGDGP(K@F9nI1vk*R^`@+Rn#IO)56ukSFw!k6Jk&FPr$ zSdRHt&FQ~cGpIS;%Hyn$`Bu&8zgd&W-ny*2@KbQ#XN0_aHIHMh0$Iaag;@Ul&6+{4 zCFC>Kfe!TA18V}%fzHA^6VRnz!zevKH~1IUD#TbH={1tlGuA4s0~)GdWPRlNOLU2K zDC>Z(s+07c=)>#PLN|ZTzJp}Ht~C=3ec&h2Nur0muz_Fwr1FjM|0%z!{jK)HYF^KMUrwp(Das{Rf;%mshdHcGqb!}BW!|Gd`syq^GmN6p>8S;HtB$g}+u z;YYiI)%;c4sBAJ{)+ErK`zg5fB>1WR%9r(|Z>iv^5%ia(*={%Y?TKuXV zQU8N`6L08T!BqOZCGqV=8kyHO)gfM9qKCPE;rH~9YqpFvMW4weR{Jx5seKr=Kl7K` zH_NMjKm3F1Xg{sLJv*b~SKDYm`<*i{}E?CekVPV&!P~rXxsaR*MeN9WS3iI@f1TiEg^K zE$J*d^SFzsMw_? zNavFDFQX3k)g+xs2Oe(lJjN90HU21rbf&ehWbi!37wF-6&;dO>kMRY1cpl>m^w1vA zLHqDL#v16MJ)nd3p*^63_MttXgZ804po8{7zn}wsqdlO5_Cdd(1ARlkpaXqFzn}ws zL%*N{eWQ;-2Yn9xf)4bJ{stZNKl&SV(EsRf&_VyBzd;B64<7_NutD@U=%D{m4m$8d zz@P&^1PnUxL%^T|KP2+x1bI*nI`By%PmYo&N68Z_dEy|C=!bNmACV^x@`!$7rJq>o zhjhGtNC*0n{)!3I7g z9dAFRA)VPJ){GBl;=qY_9*Qk z9Y4OT>o1Nk((&VqbYPF7U($g+N_$8L_9*s8I)1#9jvw!&hB>-v5w}_dlcqdldU49oUZ8AL+mz#r{YK2Ioqywzv$r1Y_ z9h571a%4ONd2(bt1bJc^4?&(-=_g0Y6D$41GCqTTVzIxVpIGcK=qFbF6)XM3s=s2f zKhhEZ5sUqij`UY7_D4F>U$L^ESoK$|>?aoc3-%L>{gIB?Pb~IFI$}Ro*>kMy$0~b{ z#r}dl$9Nug2zq$l+p|^UD^~Vw)%c3h9@rt;hxULD+K2Xl4%(;2d#uKnRpUJt`y(Cb zTkMZ?pl`9iFy5{5Kd~C`R{5V;>@WBqEA~e^=zp<4(n0^jR=huqmH%P6_lGg+xbani z{0n=*7yDp@&x}3d4hk2JQ3)4c_Pq(JZipxJi$LhKaux`&`;$3A@oB! zUO%J*dsOom^g}wZM>T(;zevaT7wP!^A|3RXnorSRqyu|Y^C|3ybYPEaK85|5U_bDu z&@=2&&8HUr6zzgN!k?mDut)e)=*QbL>A)W0-(7!|f;}7P8TJVO?)qy8#+PyZ#qmWt zeteM*>=E+~=)fM~-(7!wkMT}Aut&B2!FVSf*dyi}vad zi1`@pf<0nB1|8U=T7%Jkl07<%F8t)hK2`qG@p&l*TztNYK`xBXV=>5u@%b$VxiCKO z#UK~P=ffD3`8*kex;}r#fQHYjF^)FdB6L!DL@Y= zLwV#GmV>9y7oz-b&&}@>kVnM+6590R(5l92{{j0dtb?;D z*`o~gaZX2!vn+LvM`MX!x8W3)<*G$psQRYeP;E%Y9A}>-(G{((yS(r0;Wz$k*o-Q68UDL^=JQ z73J4$ROMkW3-yt6h1?|2K`s_Ccq+aj2MqFr95Be4<8z`Qf5-ttyHJiCFqSJlfKCR= zK}YEgd|3{j@)H9n%=70PA zACY5O`2Kmy>GOqBIX>Xk_ORPS9udkz9uexNz7tRAgghe94|zo3OCF#D9Vj^i55AvJ z|COJ!eY?m57`jw?03GTIbd=sa5BL56K67-Ih3`8h4b?ByCF)4-(7eD?-A!Oxu z94GgRNlqtz3NDUY`shaF$8zpQ{!4!3NA+G^x0-KPfyLdw{a)fjv4_MMF6qZ+>}%w> z{oXvc0`A8GTTeRMOpUwLKA7GglTT?s*f-PrX?mYc@4xANIqf%s9fF%G$G9VXV5_Gda&<-e!?CQF!o5) z{>DDJzm!+~?$5Azrs~hFc#i7Nt*kn?;yJ26w~BFY<{-z6;MC^9G~*| zyn>*g7<5!#LC_EK0jM9J=fM8*c?Hyu&vOXV1N0%3k&=4c@FF^pLY@L zhjhICkdDf`U>=9h1ED?pybIco&jSheOgi44E%f8<*`i(k+&p&u#dCAy$5W z$V&<1i*!_83dfhvli_&xc`0n4&yxw`opk(oCmnxoPI>&fIpskfhtHGYc=vfb!T*qs z_dlfL&&^2({>SGL(e8ZS4*ieMBVxJFBO>;BM8rOih<57ph?vLW^N3ik8lH(NqUXAxijW46d zJMtKgg>L{)c%Rpo2UP*dOR%KAhiV zP`3Ank@7zVKF#~X2-uCUR9+?gA?vvQVqPWkJSh+Adw&RdkVh2cK^_tOA>@gaJW-HG z%@>ddc{|K8QS$}#6M>G`59xUQkPhZ&HGe@rqyzn^`3wC;I=;V1$M+ZMpuc<`5$#9K zU&#AGz76w$V1JMY^Rw6w=^zhC?8l&8upihT^aFZ6kBIZLn%_g7aIj~i?3r{xPpvm# z&&b=MJ*)Lb$XkX#40+38e36dWBgQ-Bfxgvx1LK|Tg1(_&w9Aio%Hzj7>0rF8H5l?L zDG&4w`-6Va|7txJ^13-ctMyo<)?i|9zwXVb{fFedK*rUd|J_yBcgcA{a$bOW!2SF> zp7q#HaGvOgYeG=Mo>9nM!k$ssqw;%3tcN|Rut$a8VUJ24PklcEo(p?UpcnR{oV0GQ z6#K!U9Q#tCzSK$GtAstoKp%c9@D+KmcAz}+Tq?&3zCOsWZNryy9pdW~dpe*+zX*Q7 zo-eWd33-UUoWx#!V*mXSp&acE^;2_>(1Ctfj&`6u;Dz=DzVf*RKa@is;0FvnfgiB6 z3w8M08g#4!0m+|>NXcu!)P~Y>F&v*wC?Lq&!->I<~<8MD^iTzk+JwL{Y{n!uB|3{xG>mb?-=of^~ zbl)Y*cEOj@=lm6Xrdv-!i%H)>3w}N|z<>7nF2n*&R#r=gywZo}_4;Y)JBn|w3f$qo z3hCER?VAStV2hIJO;*k){_)a6>75s@C&q95jXL-o^?>mlo(Bd!&; z3iX9fR-hyFvjTnjogMhf=h;CXc`iH1DfF^~{K6+2{J__jW6YynsE;`X?E)QQPoLQH zmFL+m$V2SqBo;o9pLqP_BC{O7RC_~x=z-YlhuG_l80`Z;FAwxg41EMSp(pTj@`V0k z+vxMem(u65x$>W1+vJ=7bbQ>HF9`ps+Vz+6pJL(wN~NU0dpss`N){-Reh`h0v%$tR^gh(uO+}ItW|=Xqz!uD2Rdr4657jh$OZXO$Loh! ztyO|PgFF`eyqwmrRYJeWS|y2_-FQs&kmw;lYyevQm2Q6TGsrrK>m6{Fxh&uJ8Pc<_ zPY193o}=9zmjyRRiymd&f}g2IV^@~{u}{*EZg1Pi9b6asc!b#RlM(yalj}o2z6Ado z!zDOaZK4yWi9`>H9{$`m@auPcPqoSSr!T=Cf=#|Z-Q684V>fl)r1$0Yex08m86WGt zS-t+m+9u2lzs{T7qfVWd>3LSqzj|Kw@^CKJ=X826#h-t%j$fCC`l)k3p_AI{7W%1k zL*bh`Pt<$ndM{nCKf`=4-xY=LogyEJe1LfiS z{(!^x`k@Z?7!Xr~X82x0l!xyVME&sHe<%-U2dE#uyAU{hUm@y*?-Rtc>bw7v?@v#@ zKRx;Wbos7sj1j-L#__Gbqc9HN_lL2Qe1G~0^mF06|DZR&e~9nU*Q@;*t1;$x{P?v&1nk!g#C|PdQ0~_l#D48TEFYzEa%63j%GJ?(Yr>OfS)k+B zJbYH?0?9{twq}#__ps-d%4O1fAp2@RLVx(l@BVUJ+}gJw`pfZ4?HO|2`Pb<$-b5Qq9 z?@upta|~Y^;vM+X@;l9w?@u4g@2O9|Ki#b>xV+$hzwT@5J-!e_3pVLEFlfecOOe6T~>Osc~xxvr(EGl=LI(_5@>o_8p7&b?{llr;E2HoWA|643F z&kw#WH#oGFW{`{rr-nS#gL;qBp7K_e^!4WOEa?2O)61k!-aLbN@Qee~pD4bLxPAS1 z(k4B&n|OV-JJPZn9+{2$XJ1|~?c@6@6Q{Q+S@q0mc#md1o!pYV%HU;!1ONX1)8=$E3M4=dkQLKQ1C}@MFd7e>7=NJnfnE?73yH$N8)E z81Fw=UndRNKTGUs5_?|hsN-cI_OcOsnTdT{hx9_rirDLr_*dPc+uWFS z`6~ZDR}HoOdNHhn^C^B#t%D=1yTMoQBgmh5c9sp=`0?xeunxxhp4j^)_?z%PGO^xg zk&jaQFJ4a8(eX)=e|Q+rW0U;D`aGll_|US^ioOGl%7fw=^%qYpTz*B?>Ima;{qy%k zk`GF~h4VN!PIvGO#^+PvP7Km{_~ywOZ91*wvpx@vyviO_#{5*)%+uytyp!3Ukq`u=@b)){{6U^C~27nu_)a?m$Ge*d0q24q8<&^DB}`nH}~dc*Ck@1M<4 zykgXmf24zFB_A!4yfo4|WbLY`!T9QU$2QR6v)d~7Fw2Y0<+I`aTs$ju=@)_hvv}{= zre9mrd|kJH48H2@Ebt;t^pErt^Wp|AelnVDe&Vy?ySs2}1T)K~G83GoimaTc(Op-hN(P(Q>bz#-N^{SY^Seu#HaC&VDYs0TlTIw9UcS%{%f9^xJK zY>wiEm_l^o;vGC2VlLniTPZqxR>dQMFJczNX$JDBXGuTAJNR6^8x?qA&1n!9NyaT-@`G-mVA;zEk`E#8|Hr&?KX8f4ObzJqnRqfP_ zX2iSAes;@`U5Ibou{8c{;xOVHGMmMvqKU-6eDLD(sh?#MZ`fTj8q;es@mcovC|Wj> z_|YSFME6(kO+2tiIaBWBR(s%rlwrehqiyLMZlr%ct>zS4?(%PV59^NmGVM)=bmVt{ zKXvJNTc&1T?kjiRIoN)1_p`(Y_vm0(_AE~Mr}SxTPrR`99yqV)_wVv_)IPeH^j{sf zzggMD^~J&+RZRVRT_4?YLK8Fcr)sS8<&=)*lp+Ta_lt&@R~tP;nX7+2&K&>L#e3kq zqM!9eXY<$rg~_+$@{7&bx1S)d4_=>OKHc1kxX!zo=J@8tsN13sPc}c+FBV}e?AK?M zd3@L{#HCN}V;b%HWDlGl^edJ<*Ua8|8_F*rSFwA2lZ@ATw(Qw=)qC_ ziK}e7Hag{uF~sYZf0XfE-zmgndR>$=X5kI`ReFBxGje_;Xf-fTNJ&+g3^>2WdUt*z0nm3=Ju4y}KXIki_u z;@s5He&EnnW9>~{FK0h~a>{snL&-sV^r`Oa+&rs&W|uXm+qR>Qr))!RiER6AHHi1- zqjLGI3I0v|o(X3Ni#{A^UQK_M_=yVb&A7IQ7})A3&onlrKdVLj&&w;CItR3L-TE`J3;=fOu%<^Ymnj6=fJc{_cVIRfA%J(H6 zGrP3?Y4v%;vi`?j{~mZ>k$FYUHg@aoBPoB^C;QsNzy5%_9Z+_(efCwiW;kfeWV>K+ zVV19aJJTM~swC&Nil0ufcN~3A4E-M%4YRxJK1Te;ab4{vKe~LFI;GFFoqAQVsPo8E z)$F%@n-GtD??79+VJG4fURn` zZhg47w&&(qZDSo@9AmZ@yNZ4E`L5As@~bn6wg1sLH_vK+B|g>!A1l7s1mCNDg2uUd z_L9e@n9j$(#I@)xmya=%OI$;l+x^ndOnP!7@y9o}F)Ic-``o^(o|$+^LjzlCSfrGB zzL{IMyf=J(^wensSgvti(XU(oj(E_$BT4`L+dqkmpVx=DTl!Jfc5r@R$@BH?aZQ{b zSh(|CTX)G(th08%K6cWJ+t`**hK{snj=Ph1!rPN<_Q+$2{n-fL+0i(^`M!G31heaw zHk9GpgNK=Nr#?=6-`QQw%w>fre~mZJG?gYDM|{ia)lJ!wrxQPZUQtuz;fsj7E`2UK z>B+&wGtU?qz5Bp8;xZ53lQFuU^Q$Lyn4hz;s>A&b91{

gv3?|JwM-OWd;>{~2V1 zU&lCyz4dyhwb^lE8RAzf_cFH^`YJ~GjKL#JleYI0SLrd)+_bU@@!8L1n)EI;=qHc4 zYKmE0^j+Gy#(72G+l-uZ6)JRauSs^r^qQ2R!@VPH`*I73=gD`b?sxz9#K)wcWe>We z65F!mrW$s@mWa4Xy`uKBRnAAr9uD@oSbpWk-tp!+iEgI!h@XjDUwM{!_qa+1 z<*!^;+srz(F>&1sN|-roFCf-FR^z;)ul<0=+8_4+;eq&}V@FV)XKs8dUefnsC#Uk& zd#iJIyRW02(|TI8@$q9S8q>Zd@%YY>X;`Z!@fBZPWN!G>?JW!{In*pTZ6(Lf#;Oxc z#b-Jaw~#UZY)?1FHO?#g&(-c8UGsMrUuVuAn^Ep6=RZGrYi-VVD_lHY_10-|^{d9R z?G=Z;5|24#5b=&_2isa%?TJ5lwx<31l?>u3kF>Bi*FKi`yV>3B&%0c|Ynl zS>5nb+S`csgUq*;UM5~!w1YWmdvVIP=*mKOcIk3Z4rN`J^m1f4k4?N%Bw&?Z_amBmZ*{LNCw>~!;T)9U1V-VYaOJ=iObGA=0 zW9BSpd$s;G&MW#)ZF?xbagdAe27LNsJn-V~w1>?vReRbt{+i`Ud z>iMG0L+o=kR}pXT*wLHY`4v_^zRu_UD(bqTSYec8c9t>v`Jkj8n$ie|~W} zZKlYN18jp+-y|L|=mLAxmJ;mWz4@6xo1A){8gYA-=!nNAQ70K+y_|8=5;s3;|F3aw zp4IdCh{p~z|7_if`dRW;NpnfRw#3@zHO|em+V5@J+0mr8EJB*CXACt>H^%Ij%oY>O z!_7Jn>otbPzn6}z8<7{31zVCh)Py)x;!_jiQ;Azmh+8F|H6fmrIM;+YSK?n2;$Ml2 zqYxL%IxPzEvc~z%SJsMAh$SV)j6#elv1dkzJtZd12{Ea}s&R-_C5DYd3@fp%4Y94n zyf(zV5)0c93rmb_LyRo3vkkGctbuKasWtvH$hK-#cl-9!KSb#F^L`j^>uy*?e9Vgz zZS%FK5U=94<)Ytai)Ex@W;y`=i(X@?PJB8(`eUFu;p>lq8AfSf9=A!XXgpTV|v%i zskqXODUG#$_La8iv1!hEHy(RIf3~qwvD@P@ua6{dbV&Vp|H700ZQFk@9qsot)^=6w z=cl8OD!M(l1rIKYDim^iak;7Ud*=n+cfS{3P`s`^b?35RZ8o;VI2U)%zV=xAV?P&nf70m3xZhpf*+)+|x<7t+n2WnhF0B>UyU_KW zzB^97H!fRr#QM6u`(j%zIypVs^f%YWqJ`&0)2F#TgyplpiZ0vb_7Em_D{l@Pa}L{k z--V4#>1*8{*R0MLm})<`m~@66U_Pq<7Ij|j`!VME*QOJ%zh{d1ddM5>qnX!cnnfi? zvF}PhINt0&wpWCHZ+6m9Q}V7Adtj~eKZBgd=ZrRWFTIX(e*0lxGp(6Bi|^LzJaa_D zqiDCq@2+b$_H_2#`mw{!Wwo6DUs(RFsO>XuUg&tuwCI>?#p8VaV@pX5&I=9V!GcLFF-_I$32HCU>yK9UzXHS?!Jb%XGxbffJ{%X!!zr_D&+l}QTn^&=|Yn@3v zWpz{AwrV=@EhDfH6Yb*d5&P?xA2My71;ZF`u6uEkE!@9y z48C)Yy2PeUa_iU%$M>*tYj<{e?lmp!ecg|>sB`p>$J+zioKF09*8^?M%iaFWs@YG+ z#p}DZ!Be-jj@zwuYXgn({9mPwmrht34ZD6A^{}AL{^p8~U5F=-NjEJgyS3A+bI&v_ z)*Q$3!E3si>zn^fJs;d?gxNOm0pimKO)@2)aWU+&e`cBvpTBe(wDkPD6HRo<$?UIw zm4};^V;&|xtVUOp`MJvzD1X%%W<}#PgZdZkSJiwoyBTq*QoExrKXfH-IO4(Rs|TI^ z%sl3#=$xv~uH+p}zJG;hHQv|TrR9I5%vaIi^1Z14wOfxcGrnwJi|d5v@PEczpik=$T83(b&yNy;E+q>-GJ63f|XBxk6^a;9qJ zY?WBfT8*5!63ZE^k+WE0Ih!@Ie@dIwIIrmU&uDH&{8X8|eyG&lRNQ|Td9~<1!sN_# zxg1?&Kj)(QZY+E$W8s<2PjM`4|8k=FbXf!1f4yGA&G@6-yrXem(O-H-L;K6>dIq|G z=Eyd3K3JM~*Nc5@_QI`{VZf&&ZQ97&h?|y}Y#(^H9C4%FnfBEtcRh_~-@AX3yTPF~{gk-&UFX_ws~k<8Xk3so9CO29J9)_SlxOFi?d{YV2UDJz zHBPgI7Mwu*b+K}`^SD;TZ6e1HzMM1$`&=RynYdJllH5l@9!N#yx)sGqmLeOIRH;@@0f9-?wt^Q?-Ir5%mjQi@mHQsC**qvid`(%xO zFCFdA%hhdT4*dQ|>TqnUj;2=!cjm6=DUEaU?4x&|XNRnGzWvd^_qC%gadF>C(?{Fe zzn{&veAjS_oqowb*v3a5$h5C7Igf3B;hpie-_hNv=lebzVza+-c}gQpN856UlkLhr z#%2|+L7AHzeXQ-b#_dbAANxc6{9A5cV*dvh#-pxs`w|CKt`$%0Jc;#njQn}6lT-I7 z?kh6??U7@npWbk7*}U}5sA!*&Y}Y-Nw@1ZxxE$EJ-c5%_Gq0IUe0cpW z%L{+v=9h~*of&tmH<9JvPF@B2&G`uT1>f8mu??9}hvI)C~HP3%iGtFg{& zA9S)iRv)kj-dE)RU_@hcZ}Zv~`n+a+dvjg`w+Xe zy=!N3Joe9-Vs7~61&&kQUXAmLz8-^@T-nYxImy|;!Dn@_rLQc$hyHcHN z=ytt1q@8Jgk;_}_TBx5H@aksjYHwpFH_vJv<_2Sr1o0JG;ooB=_V2fH?D+RyiT(Sq z>^uLSEc+CDHi(x%N8`Mr@AuegZ$6KL*ymRe`@9QcpN~Q8^E4=%&)*>S=Vio*;X=L# z@XSNck-Ir1)^>Rsq?6x#KU_Y^EZKQn1io(<9ce0Tc6)c}ReGD}YVBb8jFGL)Sx=QQ zsB`(1b7&WZw*1a0*_T~rQ?|V+Ra}O;= z-EM9$%C^1vR${xjkKLK(=7>rsooBN;A4T1o^Xl8LpKL&U!P7_D)m>cd|IBq;;wx_G z%krtKZi?T0X%z9&3dQ3p3nvq=Ew#S!!0m2*tMPwJhW&0nGa7Q@M9Max>#}H0KexvI zaL|6{xy^2!S>dv(rf=0|th4Z^re^ksX~f5U*V$D0VgEg_Zr2~7@7LG{_S3fM?D&Jb zoo%c-Xj5E!v9p=azb$1iyTjSit%d8^#f6-W-PrD2TkhJU`Rw9aeQb@Y?o3nTyrO?` zjaH`Sh;roBx#bDwk!hz97drM}bJ5oJ#9gO67u~gHF!A!9eWSTkTnzZ>Iqfpy1#XVk z@@Smj^ffPybwB0?W1Rk;{1EMLtMoX>)}C0N`Z;saMfS`NMTvEPX`Gv9wGYu)>oe|t zl6iXWDde@Wb}7@Sx_bw$=wq9r8kad6`@Qw`Sl)2@M0-#3X7nf5PaS9579K;a=N*l6 z^Q`vsi{^h2&0FVu&c{m+H{)x!vluV4Z>((&s@a&h%G=G&%aPk3+uNA^BQ*6oSz?VS z#2ONVL?H%|*dz+EiNq`>#4Hlam=McIjAKHKBe9POv5&+=Cd5P%E13{0NepE|3?;FZ z39*<qeX^vMw^ISWMwRv&^!lvLPOkIK_rIMdBA5;unc)Y=~|1;w*{38i)8x;<7lzWfHH& zAzqU>E)H>=#CJBtcM|v65cf$uXhS?GaiR@zqHeFo`?~zPEgI{-)>zxE#3nYxCK9vQ z5VPc_4*aIfVf2}~!CKD}qnQw+N$h4q?6x=mlbdHDi=3bFeL(+yG3O5d-Z8O%ADP&{ zr%d_%`^&`sy=G$nzB94-e7py}2hMN4WpYN?a+fZk%)d10Vc+`lJK`V4o@Hw^tVDS( zDqhoW8}H7N4tlAm-QCljG1VUWOuVJu5GQlr{_$Hq+__j?h4X`cy{s8IE&953drpZb zGd|hr&Le6TpB&wI*f`2l@5Xh}=O4K|&#Q8ZnUmML^Zn@!YM9!m7}jaqy}9}5RW}#U zy1c7dbABO~YpmOnAAA?Ky~s4*T9kY{o;}#yxO^@3Kk(dfX6o_diLWc3Y5soX!;F_t zXqRdByLS%b=n?7T&57r@cTz4`G{n4jyt^mxo(7%FiJJ~I7&o7u+SDBJO!^+UAo(6V z;W+dDn`csnGK+RarN8P%e9No%M~yBVK|J)H>d`f0+?n;?>wfuk6FC>;xbJ*QT>Z6) z#Ov2T9FI6`IPq&o>}QuA;r7aQU6f`shM&Rmt@kyv_k3D~ctGK9_HUp4GXkBT9vyB6 zT=*dI4QZ3?kliN|>+uD=q2tApANE_l{h8(8TmSB@T-$SQu(p#+kM3m5VeYKqjn_My zZuJUV=t_?ljdSxXbgtr*|A@6ex$*m+cKTgkag40m(8}(bUY7Fo{kX1eRN-XeD<417 zj_>aF1m+g|IR0R%JJZ~ozs+O%v_tRbiSz4Ti(t3DUHQgWY$g&vPx@OP8=djv)oz@g za@EG1uco;()15=FjVrYq!#Xd#^lm(&s(AK0Zaq_CNB8*Sm)v^h*vs4H z%wFKu8&_QTWyZIWTW@^Qe|FU6w$Xfc@%x*jdw+JZ|J?DV&9FDmW4YFk#{0Vbx-A-O z`=52=ICIx4qi9!c1`INHzWfsLx2-NTg|9o*z=nr>aH^?P;BzHLx;|?de%ZV6w zILTd3#JIyr?s6i=9Zqte2*-lPc}4%Fizk?&eJ&vVlCMbqK$D8}IlnwV*{mB-g#A8i z@F>&V+(KO8=icV=Ep8vU`!}u3^L@%1*uw|^tYgmFb}I2vUmt3YIQT;1v*x@KoqE6^ z;{MYoMEy@0w+Ajr89ME3W{$nqtutS~I^D!W+6Jl}p6;UNM>F_NLq7k3Jen{Mo$E;z7-O6OSBUPWH@O5r6nd zBfGU)ojve>OCH?mi2Yym9qx1tdDOVmG2~a{PREdUjXNDfJ~r-j40+me1{h)Q6?8Pt zEBXT$^fR-|Z=!u>lo?~j9qjG{Sv7Ww+4A)JwAB%^mZ{fl4Clw;XO1`7rwyd7KL5^O zb85Ng_P~FHX3KMm*jZn9WIt9pZl2Y4{!OP+_N`)VsfQT@x5xLq<8o=V9yHF) zv)Vsg_2%)W!tm26^KDlYHAh`{5%GliYoqtib?0Jx^Rd5|j-Frczp`4iYsMtDYs@SC zqx(C#^_3p)8t3L&JqAxcvA_BD!*^+K^B?PP4t>Dg^P}fGjdSy?o>QvaoN3;Fd;rH+ z;q_C@y(?C6+`ZLcoT>bfTTAcFSNvW&)3*#Y>uTk&Ei>+$VD28(VIz=BI}%1MCSH(c4<2;}@yOE; zu$@loOk8|{jnC}ua^oBB=pFC6(b?NOS6z{F?I^dNA69Ke#>bo7`f5WoHG2E)v3#~q zgO{QYuXg)~8s|4(xjQA6d&ww++)I`t_mUCIy<{13FB!4iOBTt!WW;hWStR$85zD<~ zM(!memV3#J+)G9*_mUa8myB5M%rSB=8Er}9{N}6e=kW^v%$a$h+bgI){f4;kIWCuA zdFBW4h`0J0*xP+oOWTV}wjq9YL<9T&-1@}b*R-*#svk*wS(kqHxeMQ?onLzIXxrrE z*~BH~-LDsCxqJAVK9y;&`?N8~OT{xM*w2T%`(A$e$58v_rsdSbh@(5(PJ<7y;H&#r z<9$Vb-KTO-nvr|b*haZ0&B#4z#BxuXk$cjp6S*hN$USNFV{%WLk$cjpL%Ao-$USMq za!;C(d(xlf~*hi-<9b=|HaTWWe_s{|6 zw7;vJ@N4RZR**-$4&e3?|0K?{CnTT{(W#m-|OBJC-(1; z6Z`kdiT(TL#QyzmV*QR`t5)~nd&*ho75(Bx z8b>R#oXyYg_h7VPiL?2QHGhiAba7*6+=5Ex=VQ*Y;CW4<$Q*lpP2$0AI+(*I6eret z(>Sl_Z@;H(&X(8Qn)cHzZQ}3maBJP!@l$b|u5Pd9lC6bp^#Pr!tCyFh+XGv;y`2Sb zHM8$M==OX{4e4rkPb|bb8s`W7D=rvjvz9NTy|w>%f<3#J`wo{Q-^jG1?>U;|y7P~d z?F}~+q76UMceMTZ_3Me-wC!itXTHA&)-wMQ`kGE|u=^ygBZOo@{&ejhUwQ@WJ$NWoAq<&%XZ-?I&mP7<1+) zZe6kLgaPKe1@8S9?b9^QEBbm|Z@G44bn$$bzp?Z9o1&&$M_Kgw-saHUJgetfyjv#k zn2{#lEt7Z5i1qqG$eck;w?-xTS{eN(aAH$^P>P36daQ^a!LREFF)MJ)GCMRMO1 zvD`Nm$$eAAa>s>{`=<85c|~968Ol5o$vi?{GLJ+uj}Xf|63IM5Ec1x$$va;y^N5jo zgymwlM&^+{a9+{ZdYCk`uK9fA$>jBBr}NA)$GM#U{SNGB2IshUURrJ*ZJxMp7H#|T zQBzFg`I~9mk50`rEo*1ewm3NyLHW+h5kZaX&bM8fOnc5nlaIio#S%0zbiY;e*LBU9-Qc- z&bH=JF8`!U?WXqOH{4!O@h6V6AKi1NMV}Vl`g1&KZa3n0H!X_CfA7{LjmFlAA8qLD zAN6oX=zpi~hSL4D@3%|0@&AvtpBeb=&#trv%AodOScpxSY_j@2##<~P_G|nsfh%LhVYyM74 zjzNFdC9%H)li1&lX&{fkGn3fgrAh4X*d+FMZxZ`EIf?yUoy7hQPhx+!C$Ya(OTXdwj(HJv(CEcHl>P{wVK_7b=wBe6fcS z?qk8;M!2U1dmiEb7VL$DdtIf@5542MkhCq=bUxt@-;hMZ20~cr^dI&6Is9G z^^4=)>xUChnfYVf?W*p?XN;_5d$(}0cI7Q{RPsnomZvxCV2_*W-Vv4<$I3nf$BxE- zW;tIzZ=7vjYCL70TPf4dYrl}|sQcw^-7Y)tShxL;(3iV4Y`9lM?i;b;z7e^H#D;rF_`9PuWk-@`jjNA~ zYOi#AViJR>yUu>ae}ty?OZV?T(H1?iCC9~uHq#FMv;oJ(s)#CrV7ojf+&$s>35*l<^m+~E_4JACABpE%s@ zqt{m&{}Gyc%xbLX>qTwei8ik5PoKHvv_nm?%P%Cp^`#o7*OG|%+~v*8g)dbh&YsZ8 zTs-tZ;=H1>y#6J&?TcBo)#pC#VV{})4e_gIwY0C)u1H=Jf2?WC-|Nnl2fSL$R?q3c z^31EAizloaOuYTh!Et6~7Z)6H*kw73#=EuauGikoIOz@-N8GaL>ZrvHE|2lfrW>L{ zH@dcWyr`7PI@smCEW5a#Sva?$<2(91)BKmx#I5e_Yo0%E3uQax!qMi-rZ*7xI%bMF z)QhkF=gJsF4l8Du?a!@Ui%p0wdU2U$MqHpqPrak$Sx?s>4`o(H-A!G`-E^YdX2Xdwc&#`>XNOd)cQh`+{TS(;=;GgVkl|1J4>*&+fk6`NogRm9~S+xIOJh z#(W$Py0s7MxP1tL;kerZC}d z3c0hwggYzt<`Z)BtoD0y??fE#osjz|Y`Bj??y0cho(gSC8vkB8&@=p*`}xoKg|%wx zdHPtPXN4{?WScU13BS|Im$OfOePT}sv2h6P)6w)bU*9g$)N(>kLYFcp<1W=- z7}wMlev2N7MbH1|ahLR6YOL*ZJ~QdNr0)`+>E;N`QJ8}ImS!br=1+1(0m{0XQt8Gc!n6|xSotYYgu&*!%v5qB{->LXZK2O$}q6DmSRa^i& zgzoTzbse#{Lt<}-#NG~xy&WiO)=YX5urGb*5iqhxsvy&1J#h$A!UKB3WntchAj}wMw#9N!BXKS|wSlBx{xb zg|&*_=k)F6Iz;b_%CaPt52N={WsIcGg8jJ(pT&Nv+LuONT*y00^2GjSz32Cis5kj2 zIlmJn{4b0&60nh!q&}Oo+V?NzPtf-X`_n*QLZhPNc4qwMw#9NqlDVKEj{b zXC~{+)ERp6K7!2kNxn+K&!p%Iy2cUNuF?PP4#s4inXEIDb!M{8OxBsnUUae-ot&E| z=LpF;g5T@rxqv@=B9?GF^^R3?jxd$y0*TK|d}iV^6Q7y*Ot%jy^FoYxQs#>A-2ue^ zYj+MO`zp!4O0ut#?5iaED#^Y|5+furLJ}h+F+vg}Br!sguae}eB>5^yzDkm>lH{u- zdtxp&l&!+lopL_MmFG=9b|y}IX2JVR?BU{jSl#dcjO(5>Q@&r<)gLPNDfaZ=U;M!_ z4@GPIp76NcyQAIyyC(+8_k*qQ@7Gk9dm1avs!Cp0%l8RiB{l($BjujP+bg>7FFr-S zzqrJksqei_-P5S~7DTKazDF3}vGrirpZT4_xy9jG(T#zQ&_>aXfsTMhHwHQa7Tp-= z2v~Gupd(<>je(AUMK=+21T4CVpd(=YJ{M#QeC7R})LoZ8CM7Q!UwDqs=2e^mIl$Zf z{?Ay;EV_xIBRnO#iJ>E4(M=2;0gG-dbObEAvCt8)=*B`vz@i%q9RZ7OEOZ1ca#^vP zc|e+PLG0THzK}uehu&^4x=>sp}SolY`f5exs=}FvRLwVcj=yQmF z+|bDWKlZ)?%&H@4`wkv7xH}9G2=2`7hTy@2!(0d&Ai)9zhrtQ%E+H_uyUgvz-QC^Y zZ5a6Lt#j_A!*2e~J{!m`-{E;+UTW%ecU8Sr-F>?6Oq#Il|A7D9c4nR{EX%&O+F5iq zxon@%YX9>_k3@?tR=-0g&Jt1V@%SJ07tQQ(#y>KUeuuebJIR$#PWsBHPwgmQJJi1R zwNL$OU%%!UOu4CVwqv$$_8b4mPIElr<21)_+GW~H{**p{7C)U_R&u?gnV;spBN|5deI)aqk~x2w^O`x|ndA5I?vL%pcYdFjKh(NE7t)NUy2-jZ z)9{?qwo^OVrNA`Cen}h4wry`R_9m|+lXOnR<9`wD?EdU)JTKA1eQ#^H1Yg{xJ?bl zU$#D=evH|Ial&)G)YV@)GOoL8i}%El9*oo7>+3$)!HQ$Uq0GC{?2}lTB`pH_O0zPW*?^d`qB0mW?xiSHR>R09@W+G z-;Ydn6+V`bQ(eX9z8TZkf9vbtCJutrI$SnssesKKYaKPb!!vTi_4hI|#I2>>|;Bdg>|;Bdg>|;Bdg>|;Bdg>|;Bdg>|;Bdg>|;Bdg>|;BdgH<9cRAddDmID(E15^f%VjfSht{U{BiQm$vdI}*26rn*?eQ{ z%y)nFegPR5#J&Y`u;m5E4~`!k4mcceIN)%=;lN+c0p3Sgty=Fz9sJ+uhakCoS5fMfQd3Nxf zXtBxK$Gj_&RhFtCSe_+bC0VL}BF4*4HJ86uJ;*-X*tCm`^`;tQ*iP^CX4$zR8z%Fc z3;b8MZ?%no|J)v6Ti#K0mSO4pulL?Q*DJ<$y<%+FE5>%cVr+8e|3YoF zZTu+yw0$cP*Z&0nm37jr!?}hA{q1%5r*Y*n*}RuNY;w}6!|=}g^}+I(BmdBTaOyBT z{2|uKP96SjJ$x_Q3%F@MI5UmYjg!9vf zKV5!0^A0%Y%sbY5q`z`rFxUTo|GZ;W7N^GkZ}{Oq*~6O8e!6@PlD@SQ)?GgA%u^5l z()U#G?R)RiKg#=@zpG#8z1&~TAJp65&Iz1*dd@vPB7}2KkDOrNOXRZw=YDJkes^zw zo{2H;3&Ss{AXGR0&wdWeu9-aVnxEk^Kig$~=F9vnn4N3?z%i41*8Fb0b09fBL+8`S zXXqGHJK>+5G4J-9pK-He$NF~cc+7U}7}H#!PuE^N`~8@ju{Jqiw=bb@_siHG4`bp; z_-Fm>@w5D=aYg9d*_wN7dwu%2i|%VDycXGhW4ZZRHrvlE$8!cJ!#~^T>j&e6jk$Bh z%J@Du{b2gX^qc8V)6djaxc_Z?HQG1hWyaCOAG%-IYuSo_|1~y0b7W#Oc4kbeQP|G@ zH#uN(!{m&~CEIqcA%7H?58dzT^S9|fhQ-4_hg%SLEI+P3|F3Zi|JHQh#?t>Y*!Bb8 z(fQEau;a`8F!9G6gU>e>NB=cH|0;bu2bs4Ynq#IvP5d#(K->dw+1@{cp-Y^gXFmMr zcT7K+_+yU25gRKrmpg*`D zTrSF^@O=L`_06gke^>9$@^a;lDclB%e2>^=b@q@!LhXW1=91b`fa5&&_z~O+y0fz$)2OJLk3l8wPwXNe|cEs<_ zTb=#2<&!_~gUdDbtFm%MzEu2u6L-CtO_tpm!15F?W5}bmYA|l}>wdAePz%OGmiH9T zu5@I)YRPK1dTo8)^_%nKybmh$WcjsxZB(^0ofyxrxI?Yl|2^Z@Q=;i*LACw?f9QU< z4vec*)9xB>F>$kfJ@wk#Y1}N2-b1H7@Wu;#V^9aZ?8FGZXFgy+Q~hk_dB&5PR?%rn z#OHRVuF0>nR?NeAdyd3<;JAv6TYP;(-EY*G@rZbnRHbz78GpRKewPc}H*9j=H(FkB z-oO1TKe$|p8!EAXR!a#@6DMir5nCR0X8HVO-@2+FJTDhmjKh=LSl{qroDy4+yhK|3yHY__~Z5E)B*VWkM~n97pu;l)7n{MtqDwPXN@%|Fs+?6)~3L; zc2-zNzK=g_zfOICzyE*r0edNf58)Vl9bde#2lB-cdm~?bv1jtd9eXJsAF#*r@dSG> zAAhhX^YIFMH6PzTUSCdqu=&7w_>Y+92yM(4;TZ3VeDxgfkbHF>@0NV^AMc!e^8(&Q z`Q{6}qw>uocz5NSU+_-LH}BwGmv25Y@rUi#sSh>>r1cg5nm*w*q%_u(;TZ2qed|5E zL-nl#@ov?(KEyj$-?|a+VtwmLyrcE4Gx6@$xBkRCUEjJC?|Oaf)sNSgQy*+T{9%0{ zE@9DzLsFwI2*dko-@*OyZt;O{@)U;I`6;dlEA`xEp= z>(g*dYet1V1LU-p^kT09OlwRx_A0=%_7vEw0MnXOV6Os9YgLK83NWoMl zs{qrQS7NX7KK`)%I<*D<{(Wuv5Iza#l0xL{;t$*JrDM`}(W$=#y=S+y2N5572S8_Ns-g?`Y!k^N`$lrxW8esuic z_`&3W%aycKPaXG2AD%-^Z06gwhduS?3rj-ayK!53>W0U1u)eADF@I+4$N0Iy{<9DH ze!s~F{h7~G11iw(X|?9zkNNYr5j*;s$ozBr?YQ%r%8oB%JMIC9yQyP7YwDQKnmWK} z1AiQzWZ?Dfzx%VnKQ>RSX#GCl%{ow{YZE!^-eq2IoA{}#x-8`vo8w*lMjiQZeI&-k zntm&9fB&5IO&wEi>J#52)g|WPKfzpoXgtzamu&3gDxNiUSZ?auW8her*tUiD8ur*2 z+hb#WQ^%B>`s5n{J^0bY2bSIQwidbxgUbPi<)U1!FTY^{HV$wc4)VDdq`tMB0O>6<#?a#NpbK7KC@|K5c3 z^LolihrZ!_+%=2tOaFYB@r)-0c`4jOffKh zR>sMmd@mNv%EkCv&KTnGw!DnXrA_SKThzj_llAjXJeGsy1>$5=9o(51A00eMd1_~4 z{N_84ICeQV<6aBSxffGE=xfu?lp8uNv*a(E-SD1zVfEWJNkgdSOjNK`c>Ngq2F}|}VgFd&k3ga(}f2oJYzUhX3%Eh^L zm8Zc0!1o{J)hVKk^)il~SGRwfNdd=9m{YI18^kzXrY!nl^#zQ>eoC!(Oh3%HTaoyB zL&fKeYcGhTS3ila@$9(IZmQv(lQ15gZi{L#AU)$^UrknR19S5DL-M8<*B4lR7||(@ zd#&xC0gc9b3-`~?I`In@RZ#;nFpg7nf(re~^242gy{f>p2rM5n=e1hW;-o;o&r-(K zE0+Z`-u5_+u5}}j@#03=bgNwl+4enY^609qT8BVCR%l)w;dW#mf4^(Fv@3sS#v#wL z=!>V9GfvegrQTQQD&vm*V(LCiqG~*wB=~`vF)S(L!>csa6Kh@7rSMmoCKR!1WsfL1 z)Yj;2HF73hyM^lLrh1ImRC=QZ-!92`R{eB3LD5W%qa7@!yUvTqILnZ_dPfthW~Dvc zN)Jd>hWc>1)_vYp&wa3m-@7fn(^D@#osersThU#oZSo7_Oex#x))^i#&UmzeZqp>C z#Iv)nmDStExf#EXoK4TmWBu%>{E0r(6Wjg3@+?KRsz}QEnKFl>G*G2lS$7LkwYW^{ zb88Jwzmv@W;d06P1r}tHpG`<>wLi3!+}rpq_Z#brdh+0j<%}<1Xf1zDSd#I&{9Wbt zH?Mf_-Q`kGd8naBD$Q^#W@7CA&`p38^z?sGGmZY!0#W(RxtIa3-ql*FKtvmP6`u{AZ zytO{_(<{Xuks(f99$TW$kz~sR*1UW1Q5t#mha4>b{Kvww>c9ky)Agz>r|-GPwx3wt zP##FPm~lF98=1U+4aV!Lbdh6cOr#jNT(wH0HvSe1;v4 z#@OZ?`@!ZLW1DXrFPm>X9-D8BZN4$K`KB=*n{SM5zA?7>#@OZ?W1DY`ZN4#H8fV-b zBd3IsQ^Lq8VdRuFa!MLGC5@btMovj1r=*cn(#R=kJL&vC^*HY6-^8qqpJW_Q*KP%_%1=2T2Q}~e$>$^D_o>H`YEH&azpf4q{?y~R zd)JZw196Ns`%{l2t#dy4`H}VxpL`r?5BSN>k7@F><2Cu>3)9uEGF=$2$W~Kj8)mr)h(%(01idYnC?Td$~6k_^2>m6cf`uZEruCnCIW~8S*MEJgD zcHJ4)I;!-S**w;r(SackM5+_zSpNBiWO8bXoQzZMEhG!-IE?*{ zRh7wepAeYOOMcxJ=WfQLC3oCyP+91+B{LbxNP_2E5_09W|Th_w9e-)E{a9{TYJX$^7@l} zCqQcnGq16>XaCba6niwrv=7A|jWO**u}5P}`%vuB7}Gu!do+#_?L)CgV@&%{?9qJt zQ0&n-F0>ED9*r^WL$OC=O#4vm(KKR2`%vuB7}Gu!do;$h55*phG3`UKM`KL;Q0&nd z(>@e?G{*1Ev!7@jf45%xB;)wry7!ZeBY1DDmp;ijzPAtkB;)wr`-D$2j_!Vn=paCGuFtU%tv9Tld>x$zvv#TU$S6oOobl*|Bvj4gK{`FNu+zISb>(lX{7aH*+%1(lM!6G@sAe<-%oo-JPmixaGmF-V>i$I+2%VRzsignY-*2 zXMkE)F$F*CnY3CJY-{yZ^Wi0Ra>xrFgDY_)eXZvK#`S9?(Eh_`GA`dEt-kz4bH+Wt z&8pXBj>@?G@mxB)Uo5uQwLh;GPlA|#=ga5S?E=yX*s{4rP95Y9VqCXO7JXpnLdHkp zrPe3z9Ag|QdOV%#_G`vp^@yOmO|UqBY3LYb~3kKuLeim;m#H*^Vlu9h{i+HmXL0qX z($VySi6LxPjlRirV4Hr7Tb0VJzdMwG@r+El^uZxVa8E#fc0I4Y-FOrG^K6qm`b@Oi z3UaYLn-+tD8Q*=AM*pam78~{+v_qijyG$h8oY?_ zV92-=v#T0ETRd6Xtg1I4i-n(^8sd&NB0KB1nsWg7Iba*;9Eud!D9~Ni&vV-0sDfvO$AsY|E?rdF1}aG5OgHgRZKl z9?d$D=hNAKi*$?=Hp{6yz8lBoFWwR*5B zlG)1NVL1+X@0`iS@}N~wXfJEM-@y7j^4He;jo`Iks%gco{c>2I1!}6OFY*0oV_&OH z8%r_HQai2Q*E2KYZ`K#p6+`b@+zy)q!2~>~RVC{YIIi zJ$2%Z(Rg3{dS!Rrq2olx>kGHnmy_RSd|^Q&-7GYzMmrVyl-G1V%^2s^FM_Oh8vTpL z(iQ4kXWX-1>{GdZ?8G{G?);>3RI%RYB=0`fTY8tZcb=1Lhx_~U*7 zNV!CvSm9wz-_qTamtc(hn)u8I^hu`a3uDsN^bC(5_keL%7drTyjCD5|{|gGgD-1dM zfE4=l1%F*=2YmpeeY+1AWcVKB^hevzxX=dLg3!8$Y`yo0eTcfDZkU_A{_cpbrSq zcB6uHZ>hP|>h(NPphqM<=(*5-Q;&%3(_5vOrI^z&L+o#0OKZ@yh zORc!O);G*i|4gaK7EM9f1ALM^GRsrTo)@>vG z7f!W!I4{O@|Ax0F(C0CN^o7H7{IkWII1BizGYkBu-cE)Zr+Zgj z3H>228g;UN_U}qFu32%2fAdN07*8nD&Od#JA&d{cD&=1z!(_&*6DRcV-6oi^_l-AW zsyGWQ{bNZoMmUrZpLf&^l71GPzj!>xp?RXrUjA*%Rggz0yDjhR6>A0ZYeD+1-T~t> zN#yUG^H;nhjxJ^Ss&Oy8{y(N+`K{n@Rr_Z%S-!YJK2>LH0+wg(HB0qqH;Uzxmo!(4 zE=6Mb*l0)9iAkMV{(AjjRj|utf%g4JhN(-kwAIf1X==%?l`K#3B95N&RUDR|Ou0yP zebbBO{o|+9!EI){G0qDMR;y)^60`i4%BU}-?alJUz1FHy{&(Fx{$`nU^r^GCZcK=? zLA}bBnB{%eXW<-1J0Z09QTmrlL|gm(8GA}9P}_wJXiJd1eVtyQ%l`h6P@KL`fODghvlCl3gfW+ zGf$;BKbPg5%cN7I3npcGYB^fLPUypK*a>~u-8=qDmao~f-VCQN}zO`anyWI6gre~_bp@)gTr2lM1E zU$PhDXH53OF2-c<@7nb70X#W*crNSYI(j2u$eAIG2bZYpE>)~J;{>h7x=o#-C6{nq zI!0UMHua;PxKjjn&APnoch9bF8pjR!yACtm=Ck#8wq^OUZ~C~+XUm69VfnC|S={Ec zJ>pn#KNRiz0P|Tx9%4RgV6UNLK5NQDjJ~|)v&PuGM!#Oe7O(lN;Ww}Otl_KQJ!|+j z#C+D&H+4>|IEOt3<#>>CeLk1*$>f{VG!evj*6?%cO72XI6TWz)qO6_jhW?vJZxo%^ zX0Z1Ix^Z)V1-vimW3{ArPsXoKoKwlxu4NoeETgaI7^APUQ=Tx+TqmW9yXp<&I;&=4 z--*2weSR$#t(*Q4gJXdyEd8Sgm${b@f5^|4NSQ+z?ThZox3YZ0&{=~1GA0@Ab%Gef zZhD3>wIQf2FZ!jn1@%44wu|;k%h+DXtv)=o?|F!J1a#02`T$1z_zP^w!hK77x`!-B z8)yqUXq(L8JyrZ81N{xT*U(q!1Ns=d(Y`YJr8P|Wc$6_tWsF}<4cO;zwd10_L%6-r zr#{#&w8I#_H2j8sS#HUGizAJbYKF(&Q_;vQq-o`^BzDaU2a_?N$n3-OJfXTAyI8)M>|7@_Ad4r#DSjIX(a@!V;@ z(ARJuisdCjS$_1z7Weaa?-zofI3^JP;b#>{0>lO zn%z;g-I{{;gHIx@QiT^pXS`$eO+|n4{z{Wf)AtyYE}mgbZJ;f@@6yz^jqz6UvUt!MJ_IMD~>zP5q4_S`hvkh=|iVYDNR_Jz@} zG{z&1aY|nw@Y#{napzd$$p^X5Ug-P$fOZ&DpVIJ~q<-mpY!}AE7`il0#%Ke5*mm)| zLtye{M*7Nf6Qgbz`c53lSC)^%dG%irN2))(-bB1U^t+V5<6R$q#?hzrF2xtG|7-7T zKfO3w>kzs>9Q>izAw9b14F1^bkd-R}DeuD9Cm&?p*l5f0*|uFDZQV$DNADD!*kS!^ ztWp2%HUHliJ7>NFfB#p`ww(FSI^+9aKcl?gr?0qO%KE*LLxXxVo{^}aH(kumj2C>p z%KNfk6UO)ZL{eR%lw-W5?iY&wGA5a#?=dD_MbEg=CbglcEymQg`YPL~^pI1Zkb8k4 zM;|_Y^Z|@^&<8Nu$6sK`@I7GYq7PuSfwq9rHu?Z=8RJy2A$J@4ZlfJxv@eW)g)tss zj8hon7csh2n{AD!FXTRZq0bn;H2j111@x&;^vf7B8V_UW;u+|m4H`dVwC#%*`7*;l z!`Lqv`c52eKmWJI(YH58ygtSK_y94+d9On67Vu8UcyIGR_kQeCi=%Jdg1mFytGIAS z>%aOAl`mfJzgLNP*E)|4sIWUA)e8$Jzt}%uN0^06Uy2f7>Wtako!_Tj&k|K+J7E2+ zq1olPxi<{3^v^`=|jU6z1swdpPzMRd@;R83^jBrx3%v64ahZLOg>8xZooR#W58K9zc$mBbLC3En*Cen43D_8RXy;xB?9BfJ4CGl&J$ALk`Y@i@@L} zI0_8TnmWi6$dMD^Ixx788~{d6m^#Qq$dPl%C1B(hats(bXX+3RfgJjjtBjGm$Xm#P zO&#h>L5}fIn>bhFHmNVh=*!e0TUa0V(wG@z%w!8=*kbCCuPhz%C;5aid_ulr3}2Z# z6bqIkUgUGe@HxeTF=AorP^?)FK2S^E<#)!44LtJ7x_(q&z49*aj7=ufu4slh( zC*U)2k})_*TxATdnmUvVEJwZ&=NW_ZlnacJ3#Ja`8q1N7lv9k6Q9HI+ zN;%6IIZJ;TBaclT8VAdfqtq5-it+hy2KLQJ0mjvOUlGe#a$3>YJiO&#I^%aNlLOUB4!iZNs4v8h9O%W~u>afLDR zm^j23d2H$sk6Df!B`#X}l*hzT#>it+hw_Bw$Wh`tW8^XA0Au8_sY7|la^xuG5@X~s zhCHn^%y9U~XC!Fg@uf;M%G zT+>EQX(QLPsbl1_HgZ-QxvWhcqgH66CTOEpXj8|iMcSx2+Ned^)G=zEHfowSYMnN9 zj9RLVnyHOis!biER%@dsYok_cQ^%MKv{Cc5F&Ai4$CzuhF{fx_uFv^$ppP6i)@QDe=CTwpo!*wn#13Vr0L zv8F|?u^f49>X07Gk)y_%8M(}I*6mvQHLLO7CV2nIAb;wSZBS*1TfIjjV zYY1TEv8h9TWI1vaYZ2%mkFiDpMjo3w6epG=N3qs{4)PdlAYkONsY5(qIdT+hDd-@N zvBm;M9-BJEGnOMqu~vf)@)&D4VC1o>Lp)|VaujPp)~B^0)`-B!V^fFngyqOltTmy7 zJjNOn7P?@)33_T4J(7vHnm3BS9=<3t~j`|ec%e-mel?;RuGtFrHILEm?G3wHVL zZt=Y;qhEZ_Hy-W-ZNfLk_+{P$Z)RKL3BS7qySNXZzTqG419IFcvhEe-W0~P+-`y>4 z!-$LT?v{+QXvZvHpK}vN%zWs%^%>rNF^7jNcx&NQN`y3sXvKG%RvT{8=j!oHoJKjk z&Azm7gg%44U0Yk95AE!)z2EP)KEpeD&}Hx7NR~X$=HuRxMJ$~3`EGCP&n%re*CMDh zAttMwmwHZt6mC~v556K_c*iisW{!O&m)gsR8gJFoQ=mbVq<;v z)l>^tiC;&}i*4zA-LRV4wT|zw$!Sa5s8j{`XOhdxalThwms$9J^Cs$W`^?-e&+?(Qrl`bUTc3wr88}N_d1m3ZD`u#R)A(nb%WtDjS5Nb$X8l~H z7pfGuEj)epJk?{e_1WhX5$CAtk@$X{%rs$*DmFa{>yKQxS)GWQknxV7eQMf|@fgS6 zcT|n55})z?28Y$VFB34%{N#WdussgrHC`W7}Il_+GR}rXzGtK^{;7sjA^`@>|spyX&N768n32tGbTGU+0U5#p~+6hWVa^! z8IwOW`HM06Pm>=RlV3IYoiW8hQ=Ax6+%)-}F~vbsJQ!1aG{u!M#aUDQ7*jko#g#F| zSrZQ!6E8IJgE8?%6Q39pzclfWG4W9opBNLrH1Uiv@lF$8854gs@scs|R1;qr6Mr@F zn=$cS6Ym*Q9%#xF3xAedQ(kcnQ=Vzc6ULM`n(~J+<&&m7WK4OfDc=}V{%OiX#*~+u z@|H2>v8H@xO!=)T|M@fWR1b9P?=xnyYlNo!F9J;UKvP{{9jX)1=Q#lSs29+I9QDGd zk9q-&_E9f@(J$%+Fvf{`0SvoPFMu&l)C*vYAN2y5>Idv)IqXHffE<26yk8|nox z{E2!24F98E03%+g7r^j8>IE?3f_edr_@Z6_BaWySz=$vE1u*!4dI1ccpk4rjSEv`j z;34V-FnEP}0SvyOUI2r)s29NCC+Y<-c#C=g44$K20E7Ri7r@9D)C*wb7wQEt@&)w* z7iKHJ22vaH~}MW@H;T#fOr5SK8PzY;*9tKBc6yWFyagz0D~9c2Qc^oJ^_PY;2$vf z2tEOWU*H)qcn7`$gTLS#F!BcZ1B`q^ z9s(mTk#E4rKja}W@)CIqj66m@10%nY|G;)VV2nHAs27l<9-uA&qfQw50fs!l&@W=N z?>72%8{>2vcDaplx{dL>4L=COUbo=~x8XNo_){4E7e>5<;eTPoMHulFMjV9^Ut#b; z7(5XMuY|!vVem>Ad=mz5g~3l@@KzW+7Y6@@kuSo?FJa`1F!D$k`6!IM6GlD?BY%aF z*TSd+*w-=#=quL?@B!-xqdo|u&Tzee4t<~N1u)hrMqT210Xg;0^#Yj2%k=`7?BjX? zOylKx0Zevqy#OYEaJ>K~ySZKflRvm#0F(c?UI3F{xn2NM9JpQpQ{1>-08<>eUI0^k zxLyELoVi{AQ#`p|08^Z~UH}s>xLyDgU$|ZX6Ti4#023d%UH}unxLyDg@3>w76Mwm0 z025ESUH}t+xn2Mh-??4@W8H1cvs^DAr#$0&0Ze(r^#YjkiR%S0O4 zTrYqrkGWm|Q-1sEg`|2Q=O*lf&#*}RHP#PYFCe2j0e#>41ajXx1p2=93EFr2+BeoY z7$?gyPGcQ~ak3oaG}cS-gFrjjuNdnq_<{A|2Vwn}g%aOmvJ_73omQ($}I)izEug1Ou^?`Lz zAE1YL;W_*t7~e;|0LF7vml&fT^anZmN4)^XcwrAP>_fc(#&|JqVAz3r0Ste@PGH!L zdI1c7z+b@dAL<1#{0hGVBMzt+z=#|C4vaXUUH~ILh$}GSjCui#cp|RAh%@R1Fn9re z0D~{67r@{b_y-I=qFw-lU*H)qc!zoc4E}H#p`X&CP-ilAOV zjygfSp+DBo0CKS72ZsZH2M7L+J~`6Zukz0jqc0xB$t%4B7Hx0sM!np?la ze&wnfGHHQ>++ifcb6IWkKw!7JHF{DH=Nn7LeB^49&3X| z@U!JA(%nFPWA}QoYjUuv_dHO~8@yfA?=oIJ4GYwLn;sGa7N1exmw|d#$$`SJ>kd`) zVW5sVWtO<2ma0jl|9V-72-dY!k}H9-VB|YuZtB!(?Cn4~?2G5(z<{UTj1L0kw926( zL;U&PS&swduK4f7$k^z8m+VIuaPEUG0vyED!cak)w-^=o;L{<7mG zvEk};b+Cp<2MyRI<`?m*r6f<)d9jFd?zn18`lU|}6{pMHQK5umhE^7BtG`q&DtPoa zWul51W8SGV^la^VE!<-VxpXmlR@dAUvZHjUDnR-J>t6I$UVcwap)rJRE2&P7I;nDz zT~l3y)vZvk@>cQar$ZO1b-zwiwaR*Qu8q6Zx~T0`M0)nXo69QewbaU=Z0x-Fsp{oF z+#9XBM@QZ9R_X1P0=m)|zMSpS1vBk%4@X}U->5wk3yBES*O-hCRlQdIgeE_Xh<8?P zh%`?$tm@GfU7OX`o!dqJuRXdg{XG5?CohO6r93*v_dV48k&nd}B)=b+O^Nj7?I8wJ^@Y#RmHsB9Yr*{EzA1=*-<8wJ^@Y#RmHsB9Yr*{EzA-A){t zt4>HBezewd&N}CRc)glsJpE1)iesY!vjYZ}ej_^2I{DbBeeU}| zJQR-!$IM(%oDMlB63{w%#k}4kLEtuViS`j=V+D(@o#%=6wDz8)Hie{Cf{?3x73C1<-mUbBg04?BQZnlyK)YA!1G2Eh-ZATcY0_@nY{W zg>`S!Hp4~Eud|{Mr4!yxVX8<8kN$D=DtGg>E?uOEM_+$3 zIbfW0>0wzty2b4(-eJ*RtGlT^dP%jn-esd*`bG+mK9%MR@4}y5x>-7pt}^%wccsa% zRrw^e{y+8HUHj;L)gX#TA9+|pl<0m=jeZrVPkh}^1YF&&Za)ds-9@nYb=FdK`dOfk zy+1@O?K@tzeH*C50uPB5Et{wlw*&Qe7jKBKbV4=$VxS(r?S%-*JHT7$QlM^9(Iq|G zYXk(-zO{2XKk1FQ#(gL>P!?piFqj&?$np|R<%!^NcJcg3U|fqL`8sv=?Y*J9&^KwTwyL=kq_ zC2!NS>E;%9?~3Oqr_lcQSi#VcgahekCe!{m!-8|(*^wTKFRusc(1yj-tjA}?PeigSyd>wn7DK`P=EgBfx5Eg zqPqt@`)bh}HGIX0_M;TI ztGYfLrpD5WPHyTg3l1hD^cDHKyB2f3qHA9VTeMx1Y@q7ApR~dqysO4l= zl7>0d;4yF2A$oRlzy|OA>VEnW`Ju);cgWyuE`5^xb1ZW|civ?$R2uSI#3%_xp9DA6 zL5hXTzlq3N|FFtUevW%!oVb2%jT%7yKl6H(C=oD8HGLDPYkzk@#3=ZKDopW8Mt4ZY z+)tt6(z7#WKNlgZ$9mV&vs+`kWR25%i@5KQy*2!#css{^g5EzwkN8e}w>Oh$M|>!| z?x{%l<4>X^={Ni3idflrnrKArtXZ*Fd|56;#Jd-$Z`NHV23y4s|NAO==?Cuq^lZ74p(<9iMDD^A>l?BBbhg}Cyu~ROTAp?3Hie#f z!w7H78>-s%EUzY$PQLZ`)WuVSRS-Q}@bD?seceLUj@n$ibfZe+w^I!!KD0VJQyuGf zLG7S142siRt;zmab)m6!=#pPmxe}(P)3g5Dc6m#F?Wgw>A2z%lA9Ad*OW!9xY;WD# z-9x=pi^%rJOJj+gYj3G;xq&TB|0_4X^oyoXa%i`Rkr zZj*gt%(EZWQu29l;8js0Ne1;R#bRjZXCh0$EN=z!^A985iJ!gx>u(Sr%GC9f-Q*;9 z81Z2j$#V`*BMwolTit#py6tT(?vVahjjoA+?vuqC!nf}37t=1U6SGKX?adV;|ANCp z5+9bW8!MKdy(!`nAC~^uKz!ZwrKnB%YDipBv5iX(qcQaB)7_o_D?b@TW6KtCNJt&O zw_+ZRIn`$Et-JoQXiK*A%9cmnRTsrwvhkM|L26TqU7`uue&WWjDo5!>q6_&Xf5eTd z?aZMfEAb&g$&>2*FO|e2^5NKs_tf)kVeVjhw%ya$>d>*=?r+KGvu?X|LprxmrCILD!oiQ`>5 zK5=irx7FNhysuO_8pE!tQAF!Xca)&9i7qw8i1EkOLV9-J#u1{xsSuTxxLxh?QZZ@9 zbk&t?TwZIBSQFe?6(HNc9B^4&Dw0)|CZE(3PsNTc%e^n@*#^(vijkdPY?wtp++5pF zK6o<39Y($_^qEV#%On-W$mcs^y%6&gH5VNy7WtCh5S0f{5G^Q1VJQxY7OmEZvJ|^t zTCWy)haMDTDW;j{Ob}_a+z`zv*7-{`6H_a_5IacUrIUyid0o;E?Gzj8K3v&P#-bWh zAT(1*-MMeY9OBZ(jZ3|W{GN)X#IaZJvZ^n~To!_!t^Rcvb+FMM5kk)vjQfk)cy@_+ zKx50j$g3{w86gtWn6sxpu9gh1Arg}EBOHq-UdVI;T!mnxm$Y&o{Q& zrglu-qGD66?w4_%+A-velEjCpqXw#|4Iiko6ubSSN~ke4-l(4R?14kqz2Bzx(_1Lk z1xrQts;w?vn&ya~G8S_0S^QePrgmzd4|B&keODzQor%LLi`}zMszLPZvH3&AFJ-if zLF2h!VzD?>@mDp4_z*02iF@gT)IqBGXJ=g$Lu%z#5ov5GpFI|}%5U*)gyfSL+ir^F!^es^ieS?JesMdM``3LU zGqrOo$5eIx2l^d0)PDPN8`R`GqeWce!CgvXAOY?VMh9UMy=_NFAm2&rE$JCLKNC z9ZAnpVu@RamxR=z@pLclCsSr??DnT|F6lyR%jwZYO&b54FJ6h3-Rg?nWY_RUx5dtZ zqr`4{cKx@``%9mK&GPsLU8XSMj5 zM29NxL?-fcsdDq(-&3uxNB(~h)U-&Zo$rJ{#pU7ZG2ZD-o{MG_ulfU0s@=)2i*)qt zTfdfS`iTQ#K0W(+iAk#1i*k@ggblpS>+7yU?UbqI(&Yo2hg_ldW0m#OkAv2EyAcmJmwBshP>z=@@kH%Q z(L=?gXCwE$q>`0%J9tP8TDp9?=syX?gPXBLI zk&&;}TJleXn||u)DVL5xKF@nzcz4iTeu?~9K6eCnzNT-~&y;s9GF)_T*!e)Y$p0gU zeI=s&a#sCJ&*p77K=h2eRi&i-t#Wg&cr#^=ib-`o!R@W$?vnm0AH}!&`mC7$oP?V{A-i!JW>);zPBGIjos>Fv0+5O~q(aXB4P(4Yxz$L3lTBlOYf0O>Th&!>G z7)xUt@$8Q1*J-$zOwXQfcR~!@yF|>V@x(vx75-gzi{-?JQ~DP%T3-?uslF}#zMI&z z`iU4#K1rB2yBNFltvE~1wmq`eEo%D7^yI_+X|e_^PUn(YseT4F7~sv(=Y_aPb#+KU zBDHGY4Y7)1F}!3`btod;>m@%Qt1w%r#03#V zW4PI;mzewAV^NdFwyZ)vv6R+Av+3DrfjiuD%KOPM;=`r>!vZeWbxA=s2HkAu-81T? zXhF7LxfxrvYIjT2BcJ@*xxVV>e^fl6XB$=+qZYneC%Tgl>t9@ovIJnUbX&A@$lqAH~Ldio#hgjLYeaPoeAG&0U((&9UDHhl0Otb5e zo9@mOqv&@-#q_zQL^FzAg(vsL)51Rstn;gNJtHD^pD%(b){~ZO7M|SOMI5RLH{#6} zsUn;eCkS6ZF+i-Wc3(uGeus}LD^kulCCZR3VciCc_AfSy5j3{mu@;KbEoTWyHSLG_ zJA|iRA90?r*mqvE`@$_&QLOune<5@NuQOn!( zU7#-3%OwwNj;an5o?PpdXp^v}YW0~%KRA9{q*^>e%}7RPqf3v8Ba4=(VTn9CeR8kp zmSeX%72Bh`(C@gJSnr~GL^%Dlo}y~=M`{V_e77{e$WLdDpJnvu_=69+$8DpvE8*C^ zE(9Fy?$Ys6dUU_lg}lwrzgB~idvue7kGug19;g9nJUYUKVk$NLj-FQZUgGJ@KC0)E z9jbm_k1lfeS2eoR5|xhRmG6eAX}w0PfJ`3k9(+VCDAP>c$?Vak0dQ-Gt zRNB{PMMTn{*|x9R-}bI};`Zo7&C4sl6EDO{diN4%T@3Z@QCic|d!(~zMtBb{cgaii zo~OlASID?G@5DLMxw)dAJ9_WeqG@q@k2LSTyVQ+`qIXG(*O7dp-1RGB4!tj$*`T$^ zGi9ci-lfPv+24uC<7X7<^)ygUE$t`!ZC~xq^E^+)8-T$)`B_4CO4Ii83^GrNh% z2|O}ox=Z3q*9?(6gGZ+ByGzt}dqt;|9+|A^5>bBcei5DUz+RKY*v;nzy$g~#PxKMl zR^1orGkWAJPjRuf)oZaShey6_{?t9aj7vr+K)=7KuXOj>?vll`d*qkTSB9h>6DH1m z;gR)^ulL>>^;9g&=8;1(rB~TTUKcg+f^$TakRtMcJG-kj1S_r`YVWrH7j&$XE&J9;)f% zJE$I|JTg(m%j&D~DNUF|OIk)5i{Qdcw6XM{_7 zluJ)^ElQ2&YQ^R-6?Y|5mTy?L$HQ#+HoU%{C;&iy5w`{PU;=l+t; z{qe3C=l+t;{c)CxbAL(a{x}oIxxb`yf1HWq++WhUKhDH)?l0-wA7|n?_m_0;k25%& z`%60a$C)_J{Ux3I<4hdq{*uo9aVCy)e@W;5I1|UYzoc`2oZaBuU(&fh&ct!CtwGVQlsHp+)0q1ch+8a>L-HkB*?PubE$NfFABPoAnUj5sZ^g`xRW4X zy_}(bnYb8t66D&~N{x*@40jS_qegU&*|G}mB*@(J?yA1)-?`~df-Fz(wyTZ~aMPUx z*^o}&F3tDz(wzi(GM%4J_wK5f&Ld=|wr`YNR$S4Y1i4_u19j?)fr{=V$fR_RnefnD z+)0qDu5D2jGH%121eta29F?fgIowH*Dem=Cv06UFodg+DRjT04Z*V6;E~;|Mn=`qe zraK9;PNF*@6}G!H-ARz8g3LDN zt%#T~e+b=4kX0-B$s?@>yXj7X91-A>*H0uCbSFVJZudgWYyO>}I|*{cw>N~UG(pgv z1o?K)L9r&)YTQYXPrPeH<`V~TCqa(9Jwd1|*KsF7mU+-zJihfDcM{~f+{r|JKbNFC z33AOZ!`v0>_({5xAnQLry1txWWw?_dTMi0QRnw2eodkKg+Hs|7*20|x`8vfN^|EMG+)0paroB?H zcGh&$odh{xq)Q(T+Z9505~MEdrzdqj?xi~k@<2eCa?cG=bSFU;eDhG{y4zRLodj9t zz&Vv8`)oyb66As8+f|00n{g*WW^FKEEgXIZcM@d7WIwCi5gy=9g3SGGDK+zHDDEW4 z*M)9+OT2Mux|1NIXN~J^^T4I)PJ-N;KZpBd+)zb#5@fEYq3&mS?eYSI|*{#lZB%CS2J-ZLEb;SQ{+4nggXf`d!LJ39{~;FwrCG=n%S-ARkFT`SL<%H{D5)6{((l7W}!OI|;Jvz?Wj$xNimBNst}l z-4ab|j1_bzL9TgxSi~H^0(TPR@|^3%o#6erlOS`PnJmg?y@oppGRe#~;_TLExRW5e zbxJEX^?Zjr39`_w$?hn0=0$fBWb>VE3*Gwl9quH^^v!?uX87fqpgRdNFn4;jblg=z zcM|0Ils~H2bN1m*g1kI&iuz*v3fxJM?)d9ff$U>&CqdQ>II0TesgFAeGE3iE%71EX z+)0par@mB^5C7<UeN3MRyY9XIn3*%l&66x|1LimD;IlH`<6h2{J;QMQZfOQ;Np`xK{ksqNE9Ep8Fvz7y;}3d=9sf_CqcIEyTTXb2(5oGJ(oA!u-i z5G)V~!2|F9@2)dXz0A7bx-iep`rf+^Yu(F_N_BTtSM{!{{ohrGV-o23mb=c@64M=y zNuW8|esMnk_*=vz(7~_6o!MP~LQDeH-?hN`v%?L>#3WGdGY_5RX^cKbAasO7m~&cNDyW;nn9N5AHE zM%Uz+6}G)aZf*6ftQ?IvCV|qQYZr2>egJVy0)5qHw0G9+XNXClU(X~{SySA0I3|HU zo8C^ARBv8jAZ&mXjLw9gY0<~-!O{c&1jhAB*h^oF-&zl7)j!B@vdrwsDSOXNt zB+&RVH&nh{3lzsBQ0{?0sc4_?KuiK1ue3?k9`Fld5~x+@>FRCYyNF4kHHDk1=Y?J% zCV{+l<0>_j^%U+8!O7ct_mzpJIVOQ-W!w}pebV2ENua)6j(NhTJW?E!K-0DqcUCOE ztT-lt22L5}bcwMaF$vT@>2hbR!CE%`lw3Kq!X;g|%P`zC;{-2ThMF$r|8_baE@xvCDwBv7+6 zzdHr*OmH|Rff{x?=R~`_1~Ccra~Xct#r=p$para7joxtuF$vTo_eiI6^v8%vppNm2 zIvW=KjhFUQV8h)JNty>6-$!?PkLfhJb? zOBLz1*uyai^ihSkD*k6xOL9yC^=}+ak83i|%P|SG?ebgoqHspVF$uIG{ZnFC}8-{Dt6p$h)JN?r#7oKjZY#bfztH)QoZ`+HewR!Ropfzb)M&l zNuaORCRWcX1Za*)pqKH6dpp#Qra2~o?j-9IQnLIT#3WG3>$^NtetWDqCV|xA0#5d6 ztYh-~d{usgvpf4i#3WF|E=!#4*;z+{eQ2$npT|!^Oag^(JL^2GPzx~$^zEJd&b0D> zdpRb73U7VsgvTr9<(LHO%^J>t9FJcmCNWqoP)l-)oj!B@}?MFM$SN?&R1S%Zl zI6ZE>Moa?DIdj^hGDIVeNuYf+uU_QplT_n-8Ziml(^K_)`WIpn zsBXE8s_0j55tBe?w#@c6WLwWM2{dA9&k}vcb9@8me{p=7Cu8@&6vrgcr){!2uPWbE z9FsuDOZ0W#)H;Hg1R4^5z7xO6cZf-#jzhOQo7c@iOajIF>XZ{daSOyG(CGtroS^mz z5R*Xh4?cHhH16T$m;`#=f%i>UofE<_3G@w*bupSA@^DN7UAyqN6S}*IGm_u=sf>@E zZuv(#9Fst2dS7uaK3nQ=OaeW1 zHRqh?6=D*o@uDZ5Pk!Lvd1r2QsI;g0Uxk8wd)uGf%H)98?;lEin{ezs|C#)x4|RO> zyYPdxZ7AQBRD|^Lv#L?X8pVW*ugy=-6T81>QK4oM%6ZrQ?TN2HzT~t&is7+$ZxE~{Ul6h4|4a^ zSF0DM!zOlBsLNNG2kD}B_6T>W*-dZg9$O=Qy3<%6uNW*`%rUa+apgGH zmH(vg$7jWdxxZI+HPLo;uJ_4CG2P!K$yYczC9mcFhDe2ZH=KCe-QW9|U-m0!@qG8UIg0j(=L~%4 zw&~g!Tf-k8aoaR_aWR!Nsr%a^tIMrbb$@Fq&q`kGxoVfPvT&2G>2;eWxrLji3(;Rp zN+A5WdVT##mlIOXzglB;-nnS()C|H&@>Qa>zr2)k4$Re(Y8KicJYqsGinH4h-uw9w`lHwlY14zZ z!YJt5m=5Za;OH=lUuuSM-n{)uow+JJ<4t>N7T5h9oMq>0(MxiFvu6C>B9!cm`};C+ z3#H`WhI4-lrhb9DPVJ?A3HO|pXTCEfmD{FCzDwoAc;mL|$X9Q6H0$C1_R5L2In>Sa zeI);%9ha+w-?+a`^UJPBs#gp5cW^omOQQ$na({CtskgWuJ}QyquUfON-k9s0l(WjI zj(U083BvPR4A6yQ-;p+L(_pw>(z~#<=^7oTZzQa#P`12V2J7_ngYeIBd+Kz#qRBfP z8I#XPIG9=Z){OFc$~6)mIv~3~GN6%gsa59&zMDSo{_KnIu(Yv*M^@t;B?9C-m^pgk7?9U_gRZ?XQw)i+%io3qdXN` z?wiC=aL*)9f}H4Y-8QZL_je_;MR(ge|KDlU`95wRIM;ZAn%&&(8}0cFj2gq-J`=Pq zrQUv~fZS(N&Z0W?_@u&h3)j{OyjP^0{mORGWm8QTF5R@he%&a#@RIApbP~@q>BHHs zhv}=CODmLTZ^t3}kNO*hr#I-Ox8HmvoZ@N=oj86*X`^OGD(aoH+;8V_^jx}fsQXRb z+#gRbaopbrOfm6i_4dX<$$#_PFqQ3|`)y8(AMSn8%WcyPCC7L=4RXKbUv{*27GCcr z`PXIq(J7tK{q|RC?o_l` zQ{mZ(22-77ZKX}O%n74WDNjh7IxB`#-pr#N)OU6Mf%ItHN#TnbJJaTbpU69`|EwMz zil0aL{`Qg-bAW3bi#e*!> zzm9R+w8*stYV1VUR$uD!wW?`;2Wr8_n`-CknsV)x&B=A`3a-r`zPphAq>nomoX=QO zZ|ibP%GqOHJ6$|@ws7`}{q(i0iG}NS8Kx6N8!c_x{8^YTH>!X_9fu?vs{8j^EnIp= zZ+&s*U&1*Sx6)~Y(rM(${b?1wFG)$^&|P`-w6J=@bAS9qZ&&V^II!3+s_h>GB)wMj zF{=3#w@s(qJ?nk4%x%-&zcloeD(8;5DL!lH6sh2j#q|sAaL)bNRIYvb>LZGs#~r&D z4a`az&j(5R`YNSq(d}5m)uuJ3bbEJ8ITKFoMoy8=!n?{3qA#aSkv84iB8;kU*(`0^ zG9ZlhHXQ1pE)P?OQpo9_gx4+TLf<`c=Oj&{HKd(gauV`n&*D(oniYlLtjb8OJG2m< zJMC{L_@iFJBQk7qK6BhQ-8!J0Q|N-*ro}xUd&Wc`E_t3Wc;ij8z@1YSuRm2?U*18| z69-;aCwJ5qUU?{q{_R##;ZIT&(DB>2bGEKetLYt=?n^ln|J6p1$ht`Q=b*m2%;gNi z?Jf@0-S=hMfifR?8>Xwx%c{T|*9_H*y1Bp8dU;xbtRb!q3fxJ1>3fyq@5mvy^O3CTcb$hos+s;n2K4KNeoSq9JWx za7fCjQ+1`iUk?=S-!YWV{QZrzX`VD;G-uN+Y16MNhtalM-5u2B*qcylkzk*2<0Rc^ z=cCw!^qBV>QL^uYg}M?G8g~~CJExs?dXR9_2dx}6%5BrsX@`0mn%_o0>Fo6mnd$zv-Ipats^hA&f4dKe$Qs`9TAgx9Sd+Jbh2( za+W0RBV1w93a4)C*20UAJ$44ZsUke@Wg2R~J+E-g>?LSb>_o!*m)51vlAM)t=K8b~ zZNEQGxc0aK^sLNHY16eGhg0Suj)JS+#P#ik_q^t1h+54Odw?l>RwCL%~FYC5x^;~m3 z0WDn~FmQ_ZUR?KE{%K)TwRV!5p6PUN@0h*rx4f?H0Z*47+;%^f?=$DflrD15MyZcD z^ASBF^gfA>DttWmFOZd%^#yb4Tk5bOWKXlW{ zShvMHnb(TvXssqlTPNxirduc5Dt#dQ>2TdD&Txf14c-pa%YQf`+@yOK{kT~?jr7yr z20Cc)JUV1*Md7lIGU^@6S_n7U@>Dr&(^sU-nXNaVyJ5xplU2*&NHrCRQ zKX&{4yjIbiOT*kT>rLKi&fonyNd66fTy|3QuPr<}Z&F%5zNm1f0R<>9K`P<1g{xEl z#P08pm&(zWN*7xwWu951FAa;GUikWhq12^iXi1cREYHm^H4b#ZeP$1(VojC`2Q2JE zzpx&I^hLSaP~Q!y30&q?RVp60xNz0m`RL-tI>M>DB&JVWb`TBD3k79 zEQj#dg-O?%{IPJo-x}(2+Yd@P&sOQGA7AV*{AgsTo_BJkwCPt_!t^cgJZaMd#A^ZF zQ=u-suZQYEm-h*`xz$x4trbTjy}`ytIzgK3!odYf>Eup%;b-}>=(;~O6W%i^nl634 zhj5N0TUE>XgN189sHL`UbK7*_GLJWNo8gka>8D>kKMZr{mS56%=Xo4=&RL-9S!eO| zx{~KiM*c02=f#D8{5>zFIGsj#Wa_Gvbm3zu=QllC)0^@ugs)}jLp!785!C>3gz zLFUG{UWbwMz5Bbp2XYOgsSW2jsMoK1`%;_EcZAoTYfE*0N;b}J(M=bVCc zb$%`3M=g`l<3sI*Kl|pI^E9qI4;-9trqgogFiFqSEw+>Kj@zcAyPpleJ77*tHJ&8iyHQ?__MmYtic9#6z=N)(2PO9(TGj{^YJUB#nl_xi~-J4#x!SPBo z;pKBFXPs~P-2|-@9(}hL<(peVc=47YG@Tz&hbTiT6Z-WAy4u$wdnhpg@g}(RD@a%sUdu^UJ5FlshzN=Hpdn{?JHb0$6V)e z8MjUMv`X&Oe&x35$kS!RJ!OVUp6K24sAczi3s>v8Qq9fQTKLSmKUEo3ML154w3-Ix z74F%ggucEgq43N*b@ljyXQZ5eRPLnjBpoL_VdVfl=*CrP(~W(H>k)S=NSm(P6sDJ# zs;f|!;=>2)uZnFGuD`m6o|gP0jr8tAo9PTovIv*DT28AOrG#&+3D(79G!{;MIJWj= z=_dSR_+E7}rrV}p_3ExlRdw66WWX$M-A`RUb!e^UQ1ej9f4D%Xb2vd);asN=Ikjgr z6h4_aE*<&F5k9{z2aO+|Nx1Ej3KX}`TPf%6i_Pg`+RefVmiDBn6DtXyi93YS>`N_m zEO0!G?x%e!bx)LSIAyOr*+IP;-RVyaieD7|HBCo4a5FI>{Z-RCl(1ob;be=7(e@_Q zggyCF(=Ywn2yfc=z)5nfkMN|zOPr&d+_sDTdlu)R@xye8v8}{`Gj95}IvLf=bZ#HW z)M}9mx#r$yP4?f_gmdow=ZsCI`+rhE?pfktQGIA*65)GCYU=|hFG)GqZR?=FiaAyI z(CYp=ciuNruZl5;>+wzFNqrNZXMZV`SE$RXLPPYb)|-T{{MA#B-u1WemPRdfoKqP! z@{G?_QTMIkzUPf4a_Y?q-S+ zGvcx4@pQYCvv-{yv^G^k;iHuY(}TmTm+_x^tHP+qlJipcq2q?r=wf3Wq^G?zfEI-Q zA{=XDCrbbOCxrCZZR!!7&m%nlRS7zg-u;f=q)A7geDC^UVpaRgX}rY!?kc8U?Yv0k zw%x;61)Ryx-0w8U$WbAK+YXca%(;gwUbum3*gz4MjZrl~G>^xTQ#j=633G<8l~b?tW3 z!d_=vm!^_G_qFImBV0S5ph7k}8Y4*3(?>5uhd+uX9GsyE9X`5C%9;DmZj>-?d*MZ+ z2GQJeUr3wo?;S>iPKQgI9=ko9P8A;Ep#0I!4y1XfeimMmrwcW{5RZ^PyK4g)kl7vA z?hN%%)jumr`ZpIdQ1BlugirGs#d%x1<74c!8=Wb=hDiFruBDuxZ@6umtkNGLDXzM0 zI%{QgRll}7{+@3-UERvtLGlkta8>=BwzlxuwMq5#Y(<67Un;BN^?f`6@I%il$Kv#B5m3}Ul?WSuvpqOSD`Sv zlDLn9`-iDedK7R#_^(x6>A^2?2U3%3>F@>u!b{!r`x8jiWKr>t~FfJ6K%ii-BZ_{CwJ^TK`q$dQPOv{Ij2^X zs4M)<;zWAe1b4pOr&T_^yk#0m&)vVO{$lbYDd*uITI&&MmJ9!0r;qM1C%f?J0Yml3 zCQoIaAINPwAyI0Dx_tEMFun8h`NEyP?5ppE-4)I>y{-0?O{tORm&4U{iZexoljJF= zOTMTjoa0JToi1Sq;TSWos`5qq3ulQtL&g8aUB66t8ABbs>9%Q;1ouNe4I3hP_LLy! z@Q7Z*iFJEcv(ygZyPE*~XrIv_NR<|S$8pe~1|4We+483MmZ*qxegj7i|FwVTk) z1A)S~iT$ZS?&&Ho!`9I^{hcHSvg4{B`ALBjZ3ezqh%vM`CQDL_ZA66Iq9t^HG z-|Po7uE%|h4f$ZkJwCKu@Ow76+I+Jg%(x!+F*f9b8Ta_mx^RDx@|$n=gZY1}uSTUV z|ML#wvJLR{(+}aO*bV#I|CM&ZH|uMc_hxPv2c^Jw9~F*DyI9|g6BUliIBQ=UmAY7V z%!vv|W&UGd8=nMP_hsvQ#JWJ<3E$(r`Cpau-$}RZ41WJk>H?eh zzHHe^tP7+re2@3$f2Yj6;8;Q~!BPw-)t-h8bnqx$zF7QR-dNUu03X^r859X-Uh2N)?ALD#f_cah8>Vk1TD*V3lgnyMkDs^G|BXz+z9~FMzdBVTSAC1}+oqcUo<_z|=sLh9s`&L_E?&NEu_vWa~8SHDL(k|9Ff;p}4+j(#P z-g1Nx^GOj^6_&Th8KA59Y7i&zxdQj?uxxo7}u0c8YI;=@Qn4?k` zYuv|LUdn*KqrmVd`0n%G9F@9Q?+`km?|r^ETkRO7`9oCdV)bq4fWChI-fVqeQJOzQ zr7o8Jfet8jfjxU)wrpUO<_}S+%m0j(xQlP>^RxR-{qMp59{hd4-v|7C;Qz;cfUL6l zSzgA6tu@{E=)czg9{hd4-v|7Cz~2Y_eZb!b{C&XR2mF1&-v|C>9}vH^c|U%Z7vcA# z`uoHGRv*Bd9H9&3pR^3rEbUNz>R5gUylF}=T`t`Q;WOXKUSjco3`mmlpSjOPp=wvpc>{`_A|hYr@whSdLbeYwBz zbN;#d{!{%k>B%_Qn?-nsrhSF~Q~i_cmGz%#uLS>Sd+~S2?=hm^I$+bEg-t(~cWe5; zu=y^8`I3Lbo=oEJz-=#nml2HT`O^QJ+A(m&@xXubyPF?U{U2$^f404(Z)p7gKVhr? zDci+;W5qw&=eck2nD@_)HT*6k>=>T?Pksyjc8uB_$+VZ)cE3$7C-&z<=6?T_O}58V zoBi$hzcYvbhuTrU?)*bGo^Rp1)A`?|a%RX(iPa`7dH11HuvXy2WazLVN)Jq zQ%+%1e&O7ib)av(#OaF5;mfc1dBS`jeoiT2zCY?CjKA@3JQx4n%_rs5{5&Ze?uYv# z51v!zSZd6LP+xhEU_8h79?X3lq?`K_*gRL*lt&oP!Fxd-Q-0xElb&StwU@u`{-13- zZdUyH?^{d$x2{3#G0tXxJN`d4-nq^7U+A0iukYObN$`pOCw!{>&Hp1l@c-6!^xMh* zx9p@n#@P&?3hM}%!~1jx%xV84{#)GlpPVBlJ$Zorr~i4MRnn7{*f%yp<5~Y%AEP_J zEV*>TM!d(duS#zS{Cu2nijVb%PDMuvms}ceW6X=ag?EiAxbfk``oj1d|HifW@5l$n zb+{gk`{BM|_c^FlM0#E;zp%MaKBSxb3!CQ(oAL;oatfRB3*#yLJYRZVE{89FUM`<7 z-zOhGPnhqYkDn)uzwvLB0skHOOgZ!M^Q4@(A3skR&zbmZ%aq7t(l=Q7h0T37BHi3y z*gRL*lt&oP@x6aM2k#NrntE+CYdriDX_Ah#R5crMKKzlq(uaKOL8SWFtc7u%tU-Ni zNwapAbhD-wHfwERvj&&7Dz5XbVc%WL<9YnYx5k&Xu*olM?jvmOuaVz8SJ;$C7|-GB zg-!W|@er<;Fa1BhmjBF~|3AK#H|>O~k@=sro!!33bL!Z)o@QxZqb&cMZMT_2-yp@xPnP|8`7T<_t@-NABb68^~kyZpnlH zj(jMOug@Tl(Z|ibaDO?|o$KcMg^ zpN{XlAOCm!k!J&t$M-E+_raOgzWXTaJ_>nEc@*;a`mj|V$>YAa5t7H(w~@z`L*sAr zek6~t&m)g{Ka$71XUXIH7LdohXUT*2$Ip{IroA-spnUus$z$4G^7y_T9*F73W%GY2>C-2Z<3@5kQ< z{C(j6s}Eovsg3dYH+Y1eI4w5EDdEq*!|puQ&Hrz)%(qPbe}muG_PO(0>;AsF<5`io zP=x`M?%)K>4Fhbx{CEImfAoc<_nJMBt|cESe6x5c?dvf(65Dy~YbP$~PIW(1lHcYe z6M9hDQ`;o{``$fie&+9md(`Pg!@F&a#C9J0+HTF-P~j{OCBMx@zGzE9>)qb~Yx_+* zs$TGx}xwLtVelfxW8RzbAjj$==R|F((k@+-H@`kj4OP5dn1Zg z%KZ&3o9#UIwJ|1_qf0Te%C$D%3#vd{lVz6l2jLZIdd7^x(W_Uc(BSlu*v?~L+n{~{ z8u?98$#3(8jD_gIZ|-mW;BWjJeE@lp?_IX@*w>;gC=>GAjPjyPNJl+TCNS!XdcMnc z9{XCnOT0(qw;Asn?-c212fR}-+6wLTF57wRYta|bCy?J}^cVCAq@y39Pk_$V09tE~D)FxOZ4-U-)N`Q8=3LuI|s2)6Us*K&I)tGyza+e`V{l-o=B+M4@- zvid^=+j;D3xxXo^zeOl zZ;ih}WqpqkZ0E7BPvbN?M5zPHv!_MNK{2gf6Uod|w+M3Tq zu${-gmcK=9&6gsWzgG=Ai+l2StYLq_{H<$iJ{G}t9{XChB^q`a*V@eXM#Ih`o$Zi@ z{ROkF(y-C*vYp4imTjSiT}FPJ*o;UMs(_$uDg3 z3!5@TVmpt0t*NiV{cSe&m2^{IVe<|nv7N`h*0h)8x7oCpq?`588I4oBkY$?L79i=6jL+HkOX1tJe zo6UG3>1MnTHsetww)5E6n(8PN^Cd|)^Ce+3AB)6x9{XA|-;?|{ zoB5ukoB5uwnNLPyJCA*>nXgKIo6USx(#?ET*vy9`v7N`h*37qk`7!tQ-4k23&vOt8~rZZdF*S=dQI}%jQIlWEbfDO1ne&ua}C(&ciGNkUu)KzlHX>`cVK66 zAIyVbf5Dh5!A8H!b{_j$vtE|`Heo%zT~$V^G(=U z+z0be*k3T_s<6@TvYp4i*7z$Vzs;C0!_MM9{5O0Z!kBBrMkC#3JCA)W=JK%1$Zs>3 z7d{zD=X$_bBaF2IY&7!QZ0E7B#aaY*8ToDI_YI$tq;osK*CdR!4s0~?+id5tufo+syqPK0Qh2?*P6&VXQS_qmkcc zJCA)W*0Qk6$Zs=$ukcAqI)BITRSILR3>%I7HrsjZYuT0%>@xD(%=U(0XOYf!h+u!g zSnI<^zsq(W`&zbz1iOs}zpf_s==v|bkCG+Ho3 z_6^%yK4vt}kSp$aZs$)=@W$`x^6zn~gvWU0^5QB#db*w+F4vanu*%uHtGDpg%Q2~N zVfj7GfEu3{CK~OYVYnhmOB$H}mF#i;J^m2d-KLUo#_dBXN3krzf1V#gUw&Rx;k{4Q z&8f|qx5Cc%`RGN7;?g%ah9smWx$6nH>~_^Tn6iU#`_&Jf2gTY5zwMToF0QW=iQ`|p z?CcFS`A=?e2K8{ye8@NOkW)5uSIPf${VS)!!xq9lO68@Cb4v&xiC>q--b^GshI&%c zoLi)9MXn5|hw*oMQRWL<2T{{Dt)(uZg9cK)IHQE;cdbkDn(%ZJf-UFJyLSNztQ9wj@bq>ib}(qffOgGVpU zN>}5S6OO+kHnmUFSh&E6Pbfuyw;lJd2&6l8%SgJ-BkskbQB&OfEiztnj^20A(5N`- zr8BE+OUXZ@Uot8%rIv8+pGwojazVlg; zK6Iy|{4Pg;Q@$r9NU%lf)iPIEO0qf|Ay18D0hDf4bK!w&dpoQ4xaT^4_stZ~q!#Y` ztnhTQH*+hOS2juR?Rv^(=eND#SMNvW>rP=+{xA2td(?iS`Zce6_T$Wu*6Q_kw_Tjm zcf4Kdx^4HYb%68h%VAQ6$w6zJ6Xo4L^Hq%aw7ymYNk5Xj6qP9{zcCw-BCsoUY=21V zGGJ>D8h3ZA@bepCG;GF0sr&k{zT7Sg=bm1 zBu}$qbtpy3B*N*YcB2vB?w0bT`-{(W=$KA8u4lf67lZmpdg%NX>Z_}6+r7TICS>{} zx83hf>gn|P)$KF$Hr;W4+vlEHdb?q6`nz?ATwA|VOKR8WrPO7*ZcF)(-Vxrrc^H-0 z7e{z!x51QXLOmtzQmr+mO#i3w%R`lE(U^1^=|7*yPq%`L2{*Y?l+L9uAiSn?RrSwOP|Vf*9`AZ6LU-x zZnYtdYNV|ycHqXbL9}*DO9$l{^=UKOyz3(ZpH0`0W*l(O9?Ul|Eq%72ilirLx4_BY zyRYz1aqov5y6L{RkJEjkj*K>aK5&w1n#}!18de&lI#+YwXXlT*tAO}}Xz}m+=lJ+~ z`vY_4ciyGq#c|uH{&x>mwIXfk>iK`wme*-e%siGV&+U8^rG?_ zZ|l@yl(=m6z~i}MIWGTfwYM7$-SDG| zT{G{>7D0{a%JkT}Q=COBI;Sc}g{EfJKSldt`Q;&%>Bsx&bV%^Fz;7lrp-Hu4$~(9D z+Jv%HrC2tdvEl5Xqp1r}xf?}wtED9ZE2j^kR*Q4%(A$HSRbE=1UJpvCo8K+EqD(+H z8r626Dts^d%GKdR=xWLmYE|A; z71isRXjRu96{*(9j5Kk6=*r{WV^P^ljcN46I4j4MsqaK+Cf#Y->#RXfE^SZ~y7iLw&Gc}!iZ;x(T{i#q+aq;$ zVQa~A>GUW1N$+~Xt+#!o`=@Cpym9|2^~Kpv!fj5IT0hXWpULN*4_STN?K8!$j&|Or zaL?E6-S#8uRKvYCcZ*W={C2QhTX0|nn)6*I;m;HFrXSm`mA?A+Z5YLvv7fYo=_uCxf_jW>)Y7E8!L6B--lk1JT@Owb?LV&ZhqCc z9Ca_7Rq}5NsZP(LrxH%ow;A=w_L1;6N&C}rZ$8RrSRvO9Xxl^ z_D=L|m0yInrU;>7t8x?47f<1{l?D|OK63h!^JHrW;i*SXd&Yj{jw9FqEUK>j;=Z>{ z_t&d2v)p#6-0lz6Aa)zcADZKuYH-&*dl_{?eQ8KOx21cDwH!$jix`9zA z)D4U}p>AN*33UUbPN*9gbwb_1s1xc2Mx9VMFzST5fl(*a4U9UWZeY|2bra?~p>AOG zLG-_O8GR6a5$WiI=!;yzy4~C70tp~%#!`6dg z<6-N;u<@|I0 zOMx+m>cev>Fy>I0OMx+m!dwcBITYqnV9a?j-_2e##bh6E`Z?uf%y}{Qb+-Sw5_4Y6 zeIGpOumW>l%zc-%9sgj6s%P$dg^Ay8U<^W`CATV!x{x^mAR`o2V#wa zwaVgY(}S=^!CIws#vVafqhPJlz1;RdtWmI5S($WFHmp&wRw?oIip*G}V6Afb%&5g! zqhPJ_?D^PbSfgOAvOYB5N~|fdoiM1sdYf7vw!B|sbZ3)Jj5^GB^ z)|6OVg0ZH=+7gU4CDxW;tSPa!1Y=E!wIvv9N~|rxSW{wc3C5ZdYfCWJlvrDWv8Ke@ z5{xw^)|O!S0OqhSz{l_ffZ+pxF8~Z50DJ*p_yFJw0K*3WUjP_B0QdsH@BzRV0EQ0$ zz5p;7(O=m+Q9I!!Pf?c zj}5*yFnnzAwSnPdgRcz?9~*paVEEYJYXif_245Q(J~sH;!0@rb*S73@`4u;}x6;dt z{3Yo&&%V%0KO3}8(hpP*)nf__67JExpDtd|^&=&^+(lp9bXd~&{#I3IIhb0Wbv-yx z&(URsPv-qit?trJcv_+=s@*f!ZVw*x(9_*<+b&OVI%noHw_Y{wKX$G(cE8Q|c^#V8 zJf~b+aBl}Xw$z`!?*O^?Kv77e4f z3FArnLjE3gKyqo9&u$N=phw}tS?+Kdb5@l+a~F4{FJqh+z7wM=6@Q$@t=Hs?)To_1 zM_QTZu(R=H7fFx3EZo!Kj$5yWi`sbR&vn143Ad-HcjIx>NuOP-n;vsxPb9uNCsZ$K)XynYtLf6^ z{f6l}(GxjeRGqafcDy0lJGPQDuSWA_sY~?J-Gs+<+(e&SQE=h7auFjmiA?1ycV)0*(W~tRR`_Y3{2^Np*S1sh$%P^YxW^jguX{vZ~ zZRBrbY=w+DhWzLxI@XQ;&J;h>4<&L^_Zkk}FQYQ0x!;&n{a7?-UT_vqo$l25wRUO^ z+m$7Ghfq4TZlE*dWRa}B@(-YlO(!}j!**ujdXZJH2h-YX_gT4KgnG4owJs~y zi%_pR@j7JXdJ*b%@j=|ITrV>9%EI*`Q?JZiFEaJY#PxDay)tpV!cDyva=pB!UW>S1 z%G7Hy*GrpvE#`V@Q?I35FO7P|ZoO+M*Gr>b8G996#`V&uSB{3U7H~h*RzHkj?uXjy zhuZ3g+Ukee>WA9uhuZ3g+UkeO>W5ydA9}5R=ve)btbRyVKP0OklGP8%*ALlNkYzU_ znC%8xc7rUtL6+Sh%Wja*Zd?lvB+G6%mfdhHyWzF$hO+F2vh0So?1r}NhPLd6w(N%X z*$uYy+OqQz%ywQ|c3xX{UR!ovTXtSsc3xX{UR!ovS$1Aoc3xR_-m&bwW7&DK>^xa^ zo-8|0u=B9_JT4Q)<#(CKWx}|ObRL(<8kcz;5iu^4H7=7iE|WDbJJz`DvBqU(jmyd! zm$fx6YinHA*0`*#aamjAvi6P3Jde`8xs%O2kJ8pWN?Y?NZOx;!HILHPJW5;hC~eK7 zv^9@X);vmC^C*usk8-Se6j}2qvgT1_&7;USkK(y5S@Yfq=6Nq!^Io#%y=2XM$(r|) zHScw-d9P#5d&8}Hud?R7%9{6TYu>A^d9SwSz1o`hYHQxBee+&kn`o>}(BEw4b&AG1 z1?jv_(bhUeTk8~Uty47CDag<36peKXnAa&9>l84rQ#95oU|y#vtW&_ePElB=fO(w~ zj&%x{*C`IxDPUfw5Y{PRUZ)V&DPUfw5Y{PRUZ)V&DPUep64sUPGOsHM>q?~ax{|Q2 z1oOI*u&xC2x{|Q21oOI*u&xC2y3)bA63kkPgLNgC*OgwZE5W?3R9IJnd0nZnt_1VC zQe#~S=5?jUx)RLmN{w|TnAersT32doU8%9IL>~47Xv+@}!R!anmLEV{egJLx0kq`@ z(3T%STYdm-`2n=$2T+zDKv{kOW%&Ud%MajKegJ|WAjO(5GqE3l;0I_M+B+-z0SJD8 zic_xyvfqX*zfAqel~6S*|gR5hJujLn2mS0p`eo<}tMYZJ@)s|mW zTYgb(`9-zm7u7z$DEqOs<;RX-_G4?ykF6~~wzmA(+VW#-Xe#(-*^jNEsesv!tt~&c zh9CP(j5PDvkFDXyZoE0ha`t0u__4pJHEt#Qu@(H-?Y{|H$y&-b__5~}inoOQ*be;I ztN*AM$bM`Ge(Yy0vIVjqo1m#=FF!jQ`>|Qia{bt>H8_^;5W%cFkfl2ibcYm;0+=nm!9)eB_Z!2{i)@y4ICvF@OtJB*4sZ3XKN3c5p@ zr?pnH?x3MNbl)Ael640S-QkA^WtXw;pe@}&Te^d`bO&we4%*Tkv`=^7I%!KMieRpj zwsay5O=WlaI6+(|4NawNy!Js{Ck;*Iaisx4Tqg}pWmCE&L0l&dO=atum)W>Z8k)+| zuuLnsP8ym@wEDGIaGf+XmA^+cTF!OSmQJKBoycqHM2@8sIhIc3SUQp8(}}nbI?z;h zhvr{pGxtHq()GyF^~loo9G|YoT8iV-^;k;@w{$&a>3Z7I^|YnyX=p0f;vZbjeNaPF ziIuG33hsj%no7N5(Ux!@)X-GcZ%h!xeNaPF>H4r$5cfe1O=W!f0YTgcwNKY$o1rZo zHiFq^XlN?6wiybV3Ycw%2bv0)ZH5C)1-V z%r@S!baMxq3i7axcc7_&*~UB2RKRTGJvyIo#RKRTGH8d44+jtF41HLsJ3sn5?ZhhY02|SzB=q z+KO|~R-A*j;vBRU=b)`P2MtXH&*CvzTX7EBigVCboP)OF9F!I35N^deI98m4W5qc* zzBmV-LpfGlN(A#9%CX{794juxvEou3D=sD6ic3*eT#B;dQnVG9qOG_TZN;T%D=tM_ zaVgr0OVL(biniiXv@b4&=e!y^N+9bgK8Bvcb6yQi1$qk4c{MZ@=qWts)zDO+r|_It zLsNmC!gF2?O$B-i&v`X873e8E=he_upr`PhS3^^Qp2Blp4NV1l3eR~pG!^J6Jm=NW zRG_EuoL50pfu6#1UIk4BdJ4~ZJysl%W5p3U&{UwOu$B@69R+#{uUCYJvYx_g6bG6L z^b}sBI9A-3W5s=Wthg@)O$B-iuTc~<73e9vM$ynzpr`N}MMG18p2BMs4NV1l3a?Q# zG!^J6yhhQ`RG_Eu8bw1>fu6!^6b(%UdJ3;mG&B|HDZEC}&{UwO@ES!!Q-PksYf5d! z=|wQFDYX@+r>raaeCT{)6-U*p0?ujv=yhPtvEdmO=XcMQ6^qfYG^92 z{@R(9*OUsHO7-T`vhkYI3r$5ADw2)Ylpbg*G1f0#&TC2!G?lw6zhA~$iWi#7si8CH zus=X}ib^?$eE=S4D)DY)U%@^A2bxOyis38R2jGFGvVTC173>2Dfu>SW$6v-i00m9u zV1?<~*ax7XsjTUjG8_8-ELKvX4z!amx|RJ~l5j71(F?v3abx=RYcQBY2s*(a)? zsUV$wq6(S{n0=xOnhKbGq6(S{n0=xenhKbGq8geCn0=xenhKbGq8geCn0=xenhKbG zq8geCn0=xenhKbGq8geCn0=xOnhKbGq6(S{n0=xOnhKbGq6(S{n0?p^n##M(K5PX| z1?lX=_Ciwuvk%(~O$E$8Y$cisBm1xwG!-PX4_iZ10kaQVpJYu1%sy-lO$E$8Yz<8X z%sy-lO$E$8Yz<8X%sy-lO$E$8Yz<8X%sy-dO$E$8Yz0jP%sy-dO$E%FgMy~=F0cBl$vYLLVTetc?i|L0tQORVPO+VE4&Lml4`k}5^;pj5c4|U$PsaKeO zsOCj`u)_31@6$AER+@h3{kh7xm8Ks$Ex+Em!t_JhU;4A<6JX~n{ zAsw!NXNl>Dl(Bq`<;GSJ-igh|ZqVK@v#l_8gASb!UuNtE-6;9>Qe!tLSItL@joqL$ zBWo>z-GHVtqg%A)#%?%q^W|S*?1uAk!8a?6-S8Gz{mn{aH`KRR#;i1UL;bjN;|gOp zbnLVBmm9mGqh}6TV(f;Vc{_PVV>fiBwh6KryP>098j{V}d1)`3jh&ZtW9NlgOM#si zHg;Z^wG`NSVb)S$=Y?5Ift?p-Ed_R7`WR~|u=B#KrNGV$vz7uo@8CVNmI6C3%vuWU zJRzO66xexT)>2^Sg;`61ofkIaawIn6vYY?p28_$XtfgRF7G^C4f^k{u!deQ(WntD*FfMD9pS2W>%fhUsU|bevEd}GUFl#9o zmxWnN!MH4J=1!5=%%ddT%%goO4!V!gv~rk*vzAZSxdn@O6tN|3g%J5 ztfgQcC3R;l1@kCJ>X^DL=1~M@Ed}!^VKa{sW-SHtC}A`2jl^c&E9tDIVBRatS_1I<6&uJ}3g*317uHfR?-gb(1@m5w@|$_D zu$lJ?n|ZIWnfD5td9Scpo9L$FiU!+k)+svg51$5`b&77aJ998=DOjiIpd59BSxdn> zMQ8i?i(uALuujp%XM7uM)+zcP?F%;R6#e|z@nEw~(cSKx4L0i(b#MErV6#q9Dfcc3 zHtUq|%t=QFn{|q_G=0NhvreJeVL`!WokAxqs#cZ|wvVgUz~9b@=m}V6(1NJEooqHtR}#u*jKUv#!)vZXOCY>qL00zZH- zYbo#p2(y*~KY%c6Dewabvz7usfG}$*@B>KSV=V=K0Abcr;0F+9Ed_o62Yr&Y6!-yz zSxbQ*fRN5w3j6@VtfjyYAZ+|Lk=XccB%QSs_-%w)OM%};n6(u6ZG>4%f!{`+%UTNj zHo~l>XlN=ZgYnxaFl#CB+h{OrDe&6}vz7wCjWBB|@Y@KpmIA+xFl#CB+X%Ck0>6zg zYbo&C2piv8BsP9FNoOquel}s_XA?GlHeusu6E=P}VdG~LHhwl?<7X2#el}s_XOp@c zKbyQ0<7bn1W&CV}cVhf(!p6@gZ2Y2;*!V>y-S|a?jbGGd*Doq;{G#$);};b+eo-&V zVEm#|X5$ytNH=~_VdEDSHhxiI;};b+eoN`~E$OVKz>h7=S_=Hw z!mOphk1fnv3jEl@tfjz@EzDX9{Mf>*rNECZ%vuWk*ut!(z>h6#{Mb@=__3j>pzg+x zE$_AN*33UUbPN)84L!x^dK!9)(e*@6F}j}I)9A2~ z*yym5&RPm|SYg&upu-BYmI57Cn6(t>u)?gRK!+7(Ed@HPFl#B$VTD;sfetIoS_*Vn zH_xTU&|!sHOMwn6?}W7!=&;haSxbQqEANoC6zH(RtffGQ6*jtgBsRLaq{GI;*5f_1 zmIB>en6(t>=EAI{KsT4?vX%nfTp>SeDbUS@SxbR#E@fsd1-iK~Ybnspg;`61ZZ6DP z3UqT})>5FG3$vC2-CUTp6zJx{tffFV7dCMYk=VpJNV07XAdE2?V>9w#Ovcy@#+Zz;8EoPljL8_A!5EV%%#AXLt!oj#vBTBDKO?xm`i~%hr(P6j5!qMQee!X zFqZ;j4u!cC7;`AhrNEd&VJ-#6913$OFy>I0OMy*Xim-`G5jJr|k=Vo$NxF$65;k!} z!X}PL*u)VDn>Zq2)>05hBy8e{giRcgu!$oQHgQD4CXPtniHRc;HgQDK=P~ES+!uAk zoELLnFk-!+srVRc6|jl>k~}8vOBibutW}T)YZRUKf;c^Sx2&ZgPEQ!Il+aX=2MoUe*u+&z9@bJ2SLq;~wG_lvN;+#Ph^v(L zWi179mGWHHQV>@u%vuWKDy3|!r68_S7(M{_0&q|G0N@J%!v_Fg02n?1_yWN20dQQU zFnj>;1t6WZ6vR~u!v_Fg0MbnyY$P^uux>fsI9Or$Y~Z`WweZ=%cO&;~s*lgmKB~N_L4__Pd!^Z|+8<@2e#4Sr6_}JiULppqH@U?;AV}q{^3?CbO zZD9D=;A;cJ#|B>;7(O=m+Q9I!!Pf?cj}5*yFnnzAwSnPdgRcz?9~*paU=wE^iA|ij zq_dWSICEjvQV?e@%vuWK%!OG?L7cffi?tNQnG3U)f;e+w)>05>F3egA;>?9vOF^8u zFl#A@GZ$tp1##xWtfe5%T%N^R3gXO#SxZ5jxiD)fh%*;9`vM}d*%u(`tfgr9vhf~R zOToSXVb)TxFF^9JmV$i&!mOoWUx1W{wG`|N5N0g}`vQbnOToSXVb)TxFF=^J6zmHS zW-SH#0)$yh!M*@t)>5!9K%T`~3ibsEvzCH=0m5by8 zL!N8)aR{4z9KvQFhp^elA#C<>2%CKz!e$?bu-V5UZ1!=;bIm>uVY81z*zCKB#Ae@( zq?>&=!e-x%u-SJbZ1&yAbIraRVYBZ>*zCIzHv4Xb&AuC9v+qXO?7I;*`)-7x5kXTy z|1tY+gw4JiVY5#v5}SQel5X}%`T8ODN%{IA_DM+|vrkIc?30o*K-07OA@)g0y4fcs z3{B7Khu9}2>1Lmlu-PXiZ1zdXv&=pzVY5$4*z9GC#AaWcq?>(h!e(Eau-VrpZ1%Ou zb6HElzBXaAuT9wOYZEs6+Jw!%Hes``P1x*f6E^$WJcnhMg{&SM{<2Mo>Jvh&!7D0$32M7fXIhbZMS`w)fAK15+?=9ZnuK14}3`w)fA zK15-&4^i0cLllN)ZrOS4LzFU@eWQ}cX0vZp@|b<2!e-y7Fk&36aT)tYjkxQuq%|2gYv(H!9?DG{i`+SAXK3`$8 z&sW&&^A$FGu_LkBmo4dLU$&If?8_E5`?4jE*_SPB_GJs3ec8fhU$!t}h^%=p_GL@D z*_SPB_GJs3ecAF{#1L8YUhK=3_ly`K-@F$wU%s`8&1N6HgElhz=!MNbdSSDVUhZl3 z(aUqqK6+uZk6y}V_R$NQee}X+AHA^IM=xyl(YyKGee}X+AHA^IM=xyl(F>ci4kEER z_dwFkxd+1L+yi06=s{CK-OafN!sgrqVVw14tt)Zvfux&r4}{IR2g2su17UOSfxI7c z?t!p5_dwpKIrqRp8O*r{!seWcNNmojkaTlSg|IoNLfD*BA#Bd62*>@+ITZ?Q&Z!VK z=Tu0U%{djq=9~&)b54b@Ij2I{oKqoe&Z!VaOeHiGJPR?E&{V+YT#-m@&J~e##K1yR zL4L%*LQ?@F1{RtM7%{NWRKSRV_4#dZ)|chC!MP%m$DAu7Y|a%CHs^{6BL)_l3hrsn z6_NL5&J~gOY0ec9MhvXaZ)47Zk#w8QIWUrL&Vdm&=fDV?b6|uKvuyd~#-1B!DoDqk8%rm`IcAcMJvY!) zkOzBips9ed=LVVz7<+D@serNP2AT>Odv2hqfU)NWnhF?uZY-S$=a@-4_S{%H5zaA_ zbnLmYbRwK%Ch6P6dN}LLr|aRYFH6_MxpR`A zwG^B?CyYH(mad0$=Oi6_q@bzbx!eZ{nhF?uq@byQu}2D;3fP=GM?mb6f~Eq-o;GMI z?=tqZK~q6G_OwA$0b@@aG!XzAuS*HO~32N9YI^01A^xsJkY<8iK|F!mrqQ$Zf=L4>9P#vVjyDq!qEgr)+< z9z_LR4f^_Ubgr)+<9z-;2cg#=U5a4O$GO~8GC%8sUV%T6r7tXj6J?qTnf%jm2~X!wc=86 zZmOhXkFOP%f^$zE)fc&P|nc zjvc}|w~-iovZ1NqTI|V&rUJ&EY-lQA?8%0v0>++fXewar$%dvP%zLt-serL38=49j zd$Ruzdv5~oS5c&YM;H{4Z2$wJOh~v%040bbqRBlC3<4^GxPh$0BA{%th-@Jd6qHRi z0TKw?afO#jIoC=tCvdO7{c_*8k3Yd4Y$*F*OC!3rKn0KrPR7N-d_&mOOKu+a*_xxZ!-#j3v(ysi8`F!($oXU*dUo)R?9*|S{{EThq@y!Er zD$C4SYcAhBAg6Nko~zB_n+N1n-tbSqdokZUAgA)N<7W=>%>!~O=iIi+RK9sYPUX%` z&!5US56G!}=FE|)eDi>u$_qcc`Bb}8@*U|q;fn80u{$N-k**8tc9ZQ+$#PeAg6NFvOk%^H!8@f zEcNqK*W?=&$q9jb>6R@3gC(Z;GTk*pljC z`A)lRBi|HBb+CM=U3zG_6u#45c`n}+Np-M%r(NxQQzX^F@|||I^G%VcgS8kN-_=)p z#uj56CZ__w#n||+zA)c_A*VvS#n||+zA)c_Np;J7S6}UX118li^Id(7pKrjVx@Eqr zuXerxlj@fFuDlj@fFuD;r>w!9&yLZ6KJW)C?P+WBS=ITbM9 z>>;ND=9@j_RKR?*hnx!7Vxond3Yc&9kW&Hk%^q?pV7}QyP6f<2d&sGP`DPC}6)@lI zA*TZ7n?2-Iz!Gmgp|I!-EI_k+-?ZF-4J%WA?$WTnBR1NX4gRde?uoE z(aWUQja~px1$32YMaob)eUQUI%&|=yjmifnEoC9q4tS*MVLK zdL8I>px1$32YMaob)eUQUI%&|=yjmifnEoC9q4tS*MVLKdL8I>px1$32YMaob)eUQ zUI%&|=yjmifnEoC9q4tS*MVLKdL394I`GUhc6#a2_4_w>-zxvY$KF>rTm5pqPkQ?o zcjjGCy&pRBC7ac&PZ<)ne^&cH@bk}juK&Gw_+5+>z8F8xnKJKtQ_vxA*ZZ^HU)XsneVkv|pDS#C#dw5$oWeZE zc!kfK@#d-Vj;zl&`XdKn<3T>cE;nI&F7g!izZd3r$dR$}9C*Pz$K*Ko**N#fzs;Qa zS$Pb`H5ePuj4|iA+;IGF=A}6f=ALC@JOf!}8D`nqcnZ&B{PrByF6PME#T?5k*I#xr zeSGbj)L+5$?wG;NW6ZW+e zw!betkMaD!_T3%tT44M9x!-q(o&6?kCSw|xbv5g-{nbFXv(D$e;PVzw-aC0uh5UFH zc&n}E#JTXCo_D@>F~{e8-`U#5yau*3uXWaetQ%QpOh5x&a{C~i$+~yg+0z&4d8cL5 z|2?yIc}<_|J!tx3=k21~gDc&-w^-9fj@ZtfO$Y^S+L1 zcfUn=QSHGMAGmx$tQXk#Yzy|iT*1D_g?;Y}+q|#|!eKM%@8gd?)@`=1&o}zZX42o~ zqxR5$e=dHe+FgFav5)BE>!LB+b0k07&z;`+4#zxyz2@snAEfq4hg{lx|C(Kdzr4-U z%}MvYUU+2JNoD1YrwT85^Csn}OBNSi`{W(V4e$Pn)_LMB2b2@WZz+7$3P+WfEq|lF z`?Bw~$CSJ7*BqE<`C_?j!G?Prx-R&xZRRdmcd@U3|XLA2|rS ze1v%pa`fjSPhlGma_;(f^4B__Ig=4>Avg4f8|D-lv^fFD$MbKC1y06-}w>o-+cQD zW;^DKe~oz?mF*v1tuXgbz3|t~QI{Mi{%uFrDYMpFz95IaKYu}U!@Dn$n`gkk_?GK7Cyf7w_?MV4uDo&a+r!+%|Ef(+Y0g@1 zfAPc3Gmts5K}PT|-2BDOtIr$PARoAS2J%5R$OwM8c?R-9HpmEmxOoQSM>fa^e%6z9 zg&%I70Y9=qM)0$?tTFt^1{uN6+Oo#*BO7D{KWobx!;gNUXYeB%WCTBJ%NoOv-l2c+ zv$m`;{OBOM2tRAf8pDr1qL=WSj*sKafS@v&jq#iO z+mOGFe>BE#@^3@_HvZ8VzsbK1`J4W_Q%$?hW#|zv|)d2Z7X{W z{WRUIVZ%)}ZP*`M+Zy)MbhCzSx3z7 z_}k9@bl(hSfBE=Z_+9?ux4qRe7xtHre>BNo{679s_+9?u_wkRy@A4PF>rWp4DEuz} z7JkyP+d|7()J_+5X*@A_YnkL!>4UH>ccas6o-zw5vFegBHz z^+)`!|Kj)kD}L91@%#Q2zw5vFeg9VE@AgOhuKz9a@%>wokJ}&d`~DTb+aK}!{uRI5 zAMv~W6u<9Z@w@#IzuQmoyZsTr+fVVk{Sm+IE$pZGZEs=!#qah<{BA$RZ+i>-FMhY5 z;d@J@C{P-s9F}MHth~mc|!7qW+^bx;MHs5rRdy4G5=^g%`ev5y^KB50! z>Av}DyN7;g_wF8jfZb1*^?UTU-gWMRz5L$#cXqGcbFJ<^%Rl*d?y3Ae{lNT=--F?U zH}10C^VGg>v|ImmqrdS?3m)U27X0?lY4Ke9`)M&A``xq{r}0gT@!NBzu~&Jnw=34+ z{e_*!`pquRFYM11_VEb&IEC#wj9+-_Qm2gXo;R3p^hXZDE+1i+n=td^d5nR1^E@!} z;CViN)>Xxi^c!e>z-)e-rg+!@rSQmht_^l{J)yER^4vGvK9Fp|Jx1gZO6X2BA;vD zwsF03w}}<`z|Av|58OP1@x#qCkPqBE1Np$sGmt;rJOh5Xc?SG&^9=Zr4KnI%&dXb5 z)Y+V)TV&MPoQqpz)Y+VCT4dDOoFBKysIxf_w#cZnIlpg_5&WzzYYabY%NoPa+Oo#* zv$m`;{H!f&3_okj8pF@pvc~YUwyZJy=q5S}Ke~yI!jEpEqwu4f=qUW?COQf~x`~d$ zk8Yx)@S~gPDE#bm_8a_Q>@xgd>@xgd>@xgd?6UX`W0&El9lH!a7`yD_pOMBtoW?(# z#y_0K-=y(3Y5YwZzxJ5Re>lm1ILW_B@^6y-nj zPm}bgN&3?y{b@pfO#g?I{x?bgo236u(*Gvue@XhUJ%;>E|4Zn zV1G*3A6r}PG5Bq5n`A$mWIwgX&`(=i?J>r0YpXrR_-$>q#~8n@Z3+8nx~V+|zv*U^ z?0=K&zxEjXrkmPh@SARGkHK%csXYe2?X42_A0L|i06)GmxU)Y`3wQRXibQV*JBt{7o9a-3dkg&$zwIsbNBpk;;&=TQzwIsbU;MVW(0}pU-a`My@A_YmkL!OyKCb@-`S|{A zkdN&x_OJNi<{8KbZk~aB;N}^~-_9@XG5GEL(lg-q{VRUAKjOE&h5ZpfvOz|j{#=ax zDV_dYgZ&XdvOz|j{yd2N(fE-KGD`MS{I<8SpW;mrP}kA^(jQf5lYx81lLK zurifBhWvl9#T%xw$9(*pzcGH!-xxpVZ;YSwH^$HT8{_Bvjq!8-#`rmZL;m;=A%Fab zkU#!I$RGb9CVuzdG=BHr#P9x_#?RTv9%Fqu8`)#5FK1)gzxbcA ze{0&m_@Cl;|5N;&jqEYx!`aRrgWqI>|15sa_GEwXpT*DFp6n0)bJ!pJ=deHc&tX6D z|HY4Q!X9J%_$JAI)?`2N|HFRb|A+m={}20#|1W;iP3|vY|GB?}{pbD?_P-|k&;3RG zrkmVf#E);q9&`K8{YCuGs`Yx#>qxDpGwNfhVQV?({LU`ych*X~-`R!z&Ms_!#hqQ) z?zaDC-S6j?A8)ltU5p^#dGlS^cm{Xme0R=w>U`JEckp~S=gxl9jkj8@mHl_LySm2$ zW`6Vo`#6Q|Um3r!&r8_nE9~zlCaq4()@)9OQ}#hQX+t-+xK;Lr_l=nOb?2^=~G z4&C!U)@?R*DYUDe)B96bruG;!?J*ay?*;XVxzipp0f(%>A@~1I zSM5F?;n=hE@$p9=<|XX&jsCI;^tTSO70%ClAL`@s6m~fayZkjyUl(DXV_eieO|!E^ zn0vL^dSUL>=8Fh(uQp#qn0vMPBEsCO%@+~oUTwBmHjjI?omIlzt1Z4c%Cm@f-t|n} zxTboun(EMMs!yw_Zmll)Og)?N4C>r!s(-6qSH`+&T;20#(;jtn^pE;Fc%tqO{;0>} zxlyObc%pufaYkJqgCSv zo~L<59bL#Fc&GyucDV_=JcV7(UH`5QP~-G<5zgziDD@=OBq%THwFk@*3(Ob{UH|Tk)>u6J5K}~fLHPv-c^AdFtHPv;r zsV<_Xx(;eyqAsOPbrChybx`vXbt%-mv|iUi%}dm!Q1jAyT}MrIDR4(!O`GaE>Jrb? zrNA9^HPpOBT?*V$S3}K9)TL1K5_L7yyhL3PH7`+@Ld{Fm)ll;ibwO}PT@5uaQ5OVv z)YVka%iH~V5;ZST*93Re)tLPm)CE!V5_L_;ChCHyd5O9vWD|8k)VxGp6E!bUm(_Y+ zUiq0+*F?=r)Mc@@QP)JxOVnji^AdGU)VxGpmh2CHI(9YHHBs{tby@0ze~rCOby;fX zE{N?-by;fXUWj}=FE9R7m!&@37tw#u%MbEb+#S(>&&v;TS@_ZDKl{n@@*)4I>ys_# z{((KGW`{f|{L~zgyY=x$U7Tu;$ldz*qb^Q0N91l9zvty+{81ODnj_m|;`h9~_^CM} zcgy&xnX)}5erk@$-7qCE{E>U}n+&Sa-yuA25FE4)2%ZuOh^5XZr zy!bsYFZp<0UgP(?y!bsYFMiLdyCvT^0)m z#_xG~@go~#g#0}(FMiL zzFzj9y+u3n@!Y-m*;}-upQ)|@`yX}1_&@4{{8L?l>CfQZftuE4CBd9+97Jiq% z-RIXc`!jgIpr#rF&abG8i1AZz!1)z*5ix#h4>-S~E`swb>N;Zl)Fg!bsf!5xu{gq| zvTa@$!TA++9h_fL7s2^uaUIol=xp)2l#svpQ(cG77OzW@ZN^43{#2JD+l-B7{HZQQ zXCr4M@=0|aq5m3xs;de87k{d&3H=v;s;de6BmPvE!udsAbVWX?E=Xr1XJoQJ75zzd zHDP}$>r2h1*EPldZIQp*AMv~WtjYd}Kh-tqZ0C$eK6ZXZT~pY9jX%`|h5Z!2+kf%9 z{S?33e~sVmr}*9eYy9j3d_Lq)&8F8ih5Z*leYi6)erh(oF00bc{UOMap6D2_@gc^ z{D&BS)WwDWAb$6MV*J!ai$B%%h5r-smyhWBgZ~rq$A8fH-Tx84`)?utsOt;=NAhw1 zP5kcvg#OD%ME>soh~ND;@w@*ie)oSge)r$R@BXLw-G39m`=1)W`)}fR|5NrY)wPEI zCVuxn!~RG{=#TrK;zu@KR~G)K_}zaF`zaq0{dE6R{O&)C-~E5tw^Y{}{=dacpAP?7 z{O`7~*4FFFu>aCg^xu7car&Kwy0Yr` z6xn&do5;5N9Yp>2O84kgmsL}}R!wzWHPv@jufNj0k9sKTqPT~qIVmoaqD;fb@Wx33FM^;*F*jrLUE z70*?>k4Kp2AQ$@k_=T;m?CegCYL9xekVEhwA7Pi9u**}}g!6itzAE;H zZ8g0S#)g`%2xB)*KjdRzD@`Yav5BTz!q`Excf!~{vuncGINnP{f?eFDiv{xU5!V7o zybBz0FmS}jz!5hC+n+xp21vI-UDw(TQBz$+ zO?45<8G2nro9a5M=j9d4^t`N+EkaKoFTbG2znaxpNUi_Yy7e6^elacwb*c|2M#qW7}#d^sZnvBHnd3o`ZGxWNq>Unwb zdtP4ro|hND=jFxkd3o`BUS9m3mlwb1M*?;o#;y3#*9fjZX z^0J@kX4rrB7W;wmv$w$R^9Z}oqx}Ovdy78q^9aMw-lE-o9%1%Zsw?39in@XrKXnB$ ze(K6%{0;m*ev54l#^1p2*Yd*<08+ z_)}d6=a=0lRM$~cT}O5O5r3-d;QT^=G=BD$*L7%bd0hwRSJb71{x^(2)umL|fAPEi zOFo<}UY8R3Uyx6#OM#oZ=mzv$ycEbiQ=s4}TH)TV2^a?iH-B)s@ZT zUV(mEUDf%(h<8@`6Uyaw5spiP*%EEsL`A1!!YL0A=h5VzgPkRd=k@2UxKF+Vk z>&nm{>Y_t`qArp1E9w%l%~6*a{!i#n)Fo{~z{~ zx@g%?zrRpd7WWtN`~4;CfAPAqxW9z`=l&A*zj$3)++V~`?0|EJKXLz~c7yvSZQKRp z{%8Nn_cGPaU6A`GeYgwSKZLmpa^Iw#yCC;XFn7W3JAwS$?7?@ZXy+NU(%=5U|8#ff z8DRMR8M?dseUrZ`{u_-GE*cqs+&B3~XKJV3M12@z;-TI|?aV1XxAF`)kwF^gptj4n zYxkWidd;Ri=1YHJdnP>mPdrI(s&k>8Hl6{tKh=MuyF1UIvE!aCY_c4DGmO7WefqUC zdDwa)r-E$$XRaM1>(&y~<4y{_9C|tY1$99Czmw?f9!n6t9D05DOXxtyK|TF*?Oz=; z^K+`%$1W@?|LRL${K>rM+Nav%+E=P}-sZK){9*g)l^n_L;wd@V5@%rYv~kMZ(wZw`Z9(^={eA z_g{5LS$^)Pg&+LG(dG3Yda3Z?|2nI@e60^nM;9|*lwVOl~#gX7a2dPm^;SayI$5A%Bxe8|#wSE8|5uhAf8z4mi5LeD`&< zrjH(VP@ViQmk2+8#IAM4Yn~L|?4ix;wZ{uTCpE$sVU*zJJk z;`Tw<_w1NC=J_tlF(BWN!=Hm~oY-)!OU7>JW4_pbVLumy{k#adagGT4`6BG+jbdUDNEpHPfx*q8vk>yXkE)d#E{@J{Plx!lviN?4hvfe=&Qg@tY18vxmaA zUy9j7;pc)gWb^E`H9Jtu9%^i6ABx#SVY3^>?4hvPlVbKzV>6pj%pQ&za~}VHh4bGV z=fBtP&#lZWV;`s5ef+{cua^EkUtu4!Fwg38F7$c^|5rHk*nHhJ9@ht9*AtDw^+(wC zO4xNnzSDETndMBZ$L_ujQXrQWIWg|X*2Mp!HdL7VbmZ3fd+(=wUF726ix^Vgzud8- zox6ARHy(0j!9U2|k@MksjKTiC@;orPv=}EbofyB(%g(jIf5VS<$W z{z>m=4(=C!rT2yZIKId|iM`tW>2WWIUI%&|=yjmifnEoC9eA#FVB9#5X~+jzly{JP zA6c|xK&$>Ua#dbiHIm%Vp369PmP5vjx2q@Y-bHyX$MBz%&7i)eAXUc2ofGV_dSUz5 zzgSKo}dcEA5m<#)0i zGG3Hp2-z^l{}^|2{PX($IedMePL{nKdO7qu(Ca|21HBIPI?(GtuLHdf^g8h0uLI-8 z-SMf_PquqeWh_1J<_gIrKWv z>p-sqy$5eBcSW!5{MExglr96Y^)Au`Z0?c)Hp;)+^(vef!FO*S>I3jKStJZc*sWO1FN) zz7sUN{$%Udp0X%(W~E!VoWCe^hB+a_-#xi-pr22#_D=)-+~=&%5A^e+pP4hz&r7a7 zZJ?jC9yxfRpTB!@#y~$0-|Tq<{d{uM&`;wT=%?`y z^wXX@&`%rBKtFAq1O2q|ODFjThRrM5TiU~(&_C=6JYi4Z4|~FMO*FD6jK}v;Wt=|# z%J{qQ{3RhX(mmPtQJQU9el!lCxgV#_YR(9lLK7{S~aE&bxQrR|op} z=)W!;=;!|14g9(?af5jS{ao^I&K&6H*S>PtKtJDgUm57E9gs>%K4iuUyAP7FXG7t2ySk%`U$k|HvTb*2h)4IPHHXu3~bW7jc!q7SEL5`P4f< zJ%|-Qm$98i~SxLUI(5N9gtt?vhA@1 z(SK8+*N4BD4#8tOcZ=Gg*;X98g53anA+OM8{cv&#+FyXz<|3F#c;SY|% zxljJ>lgAxUzVO6V>Ywqe*WbUq>w>SU{ft}oExXLPL3qu5-do=D-EWV-b?OW z)}H!2>2<~zZ?I!oeEQ$0{nzh!S1DV*KzQ^0wkua|z4REI`{duA_>#@bkJg-|{uys^ z%iot^JJ4vGEoAjoR%w#eO4fV<|R{ zF*x_hzqPp*o3r|7Z1N~JXSJK0ip^QrWLZp(V{q=1e`{;i*qW(-#vP1(D#*6iJ+4+EV0;Q;48`M0c9vbO`wda`D4vd*j-7+pyAe1LPG{9AM_ofiX) zKB9AQqNnH_7+p^1(E#T@`M2zqblwdx`-wdRC;N;&17}ocrY8`hHRWjD5eT-S>;I@5eDX_sPHY{jUBQ`+iru?{{IhCu4B# zlYi^>O8ql-d!=@_SHf-&$Kc#2|JLoT`e*F+R_$(Yh25Ty!MRWVt)Ca_pRu18YWMR( z*w3ReIQPlF_47{sGxqaN?S9?~`*}JB=RWzjeqKj^&hFskOc%EPob|#s2K<3BIQOw< z4SwtXhWcl0^Tj7oyUiD0Mc8DBKQjjBKKZxqFR6dVwqE#DYPa>m*Ag}zz#kifbD#WM z_xIF4W79W$LbaQ|;VTN84&zUb!MRWVt^2F$pRw&1d|I{Je!7^BjHyHXDLJKL+PM`M1oKIrH0$kq2|89XT;)u-QQFBV%yxlYh%vv1a@> zW7d;3qn&kT&A?{ExlfJ3xljHrx`xj2+lZ`n`mF@Bpd zdy9Rd_U`T(XCn90F_`_w9;1K$E&tyAnJt<2`2U6+PJQ&}&GnDJTWg;2-tWG+S?L=G zm%C=3Icd{vhnjZ5(dFJte>L>OJI-i!Y~Ek)z3T3vk3avmX7Ww@lmq_d$3tJ-XSH(M zE4C_scl%d|UUv82m*;(JsI2gD}e!3x3u7=K8k|O+0sI`J3gIX@2tEBi7vY zv03G<`<=XS-iG&G^z_XA%h7ArcB$VFjU0ON+sfT*uTYnG&*3BA{o1R`TQ=XIe)(nR zj2ts=e3^2{Hudux&l#Ehj=P&RcH6Vwe%l2j|NNy3o2QmPq@H^2M@K&S<&&G?p~LDH zYg{n0+Uft)Y`E6}b>Ba%KF{Y>H+lMwj|E1*eU9~$?d5ZQj`b%C4jJ(|*4^hEJK}S! zb65TJh|jV9Kj_o@4??1=qIOBw&M<@Cmo9AD*-jL6+ zeD&(%hkTCZmhW9MVwFr~7YYt$f$x!xR3l zixq6T^N!8w%XM*v_e?*#+4|~3)qkIaU;Fd5nmNaGzdh~SAD(`w{rBY=!-9*KY#zU2 zrtsote6;z)#}5-eVd5jr{omhB_;0VATAqAQ7yo(UlDCwHwq9B7^Z$5gx$%Q%weajR zYi3#f`^yQ}4;@jCeQeK84zuz{Ln@PSutQ&zj+MTP#yerkg<^?+9kPkrJ=W!e$j z2=9FTea#cIy0!SnKi=NlwAwyuzi$8MmGM8@N%&VwzOtPEyVs1t|4>#fpa0IA%VNJg zcJ8fjzOQ+~1$&fJU;XSco!)va&^1yWetOv-A0T2ru{2^O~*ab!#`_>eZW{K5}%O z_nn(wy2O{}PaiV*&)MswN#A_eilbA1FspuPjenWE`t|P{zU9b1<_4Bs(j)u)y#8}IP;vfcyxuDQk@ zlgj0HzrK8O?R)2b_WZ5NlDEIOAj6DLJblCR@S(3#`|Gz|rHngfYvGNqeMOnG?rVjQ zJA2ErVEGBcU)*A^a@uEqCLMcX=OfCAXYVb1@YA!(8J}23d+?J#I;gDu)A^d?zANrt z&VJp)!mrq9t@6VsHm;0e-isb`jczBy}8(vA6_`)@or6DknmwMS84B@*8O(E z>ptC{cT@MQpUr@+s^E}CCxo;j)c6m+r z-%Fo<+aBf1N8YRUr$@Ig-+gj?q5pA@yt=HrO84JOKj*+{W#X>W)&A4%OSyi9&euJE zo!!fOfA)}moAI4{zNI{I`O4~l(>1Ry@7$u}dFqrmmC5BLYXAFjyOygD{=I&C&clb6 zgYP^`_~IRAl{4Rcx_q!-zW3;|#+B=|jAylWxAM?oj|k71wN=@C+-jBfagV*A>~!z; z!pD5?(&o-5yZ?UREc--af z3ukt}y>8nNwyS@!i}$|fidVF^uGRJ5DB)9||H<}ML!G@{@vOVr#m?yL_D08C(%ybr zx9<*|^TzfM4|Vo={Pmxn@vo0|YdYtc!H0t4rZn$)Q9)E6{=^%~-Pf-!e89QemD`u(eP+4i+sg=lX4zTg;KweP?!DsT zgUgm%%xM|J`73Qzw)t4Mb~pWM{W5FSjWpj=uJ}gtv12>ke&C#@x%v2RFC2gT@zW3S zwY%czN$q9VbZb%ex}aTVi*D^6U+u2;xX*R+pMLHW?YwX8+Ht=2+wD^y>GA?stTnH- zxvAaeI>0u+*5;{pn_sng3fufzo2RhNueEs!+x%Lar?Aa$*ybs0^J{FL!ZyER^AxuE z6`QB9&9B%zB?p^dv3UyH{EE%hHb(B@Zcp29Z2V)GQX`4yX|u+6WW^4jk1 zW_nsoN7bIO>1i>2RlDhFF?|&_JuRlM!ltLi^i|mOw3xn1$4pO)>1)f_OizpHtFY;5 zF@4p%OizpHtFY;5WBMv=dOE}ORoL{jHGLH}J#9^2g-uUe(^p~B(`x!EYB!COO)wsWJ{`Oz$O!0jV;ZWKE|hJWy( z<3{Y5Vmup+WAp`vEf-$ z?cAt#e$?%L^zalr|Erz-b-8s<|4?A&Yv+G8KcH^AV8K*7|Eu`{_3Sn0PPX&Enjaue zJO8Ws0m63vx8?^3+xg#`A0TY!{|xg3gzfxq%nzu?-u|{V?fh@d52)8H{iUgP{ulED z>b@VIGxh$N|4_^iXg3@GwyAdh7xM$!LpHu;ik<(({DAhb*S%nho&UxBfay0)I`d*X z|BLwn&APYTJ7VX5F+V_SVdsA_KS1Y~`EkX3xR!ZkY<^rZe@^?${J3KNoPKM5Trq!6 z>u!ErF@H|>)BLz%{+xKsk1OWSXa>?KB zRmJX99Z$k`uPS!GQoG%&irufoWB00J_bavAy{g##O4#mI#qL+acCRXSztTAEURCUV zC2aSq#_m_bcCTveekE-8s@CpT!gjA}mz%Y>u-&Vw-LHi0URCXWC2aSqYWFK)yH{1a zU+KAauc~&x61IC)wfmL&*!{TLJ$Vea`*F2}8_hezaAGdZ-7PkBG47(=_+x@t)d$O?IkBi-th3$S^?4B%a_v2#sWMR7> z7rQ6xxpqG;c25?z`*E>*vasEci`|p8c6L85c28D2u^fwWjKRcmEZ(7ZVmTJ?5GIym z@eW~PITr5_CYEFIjyn01t4|=7WATo9{mu*5AeLkCj(Xfb?K+WIj>S9bALcd_iRD$Ej{3sAj=qRkj>S9bj^}K6F|izrchqT@FFS`=j>S9L zt+u^n4zV1IceH!&x7G-;9E*3fJ6yicMZ|I}-l4JC9BZ260NWgEnqy^-hi>uGXZhHFT9&j>U8|cW~GrVmZm?)MRsNvN<)`oSJM-O*W?{o6{zn(@#Xp#@mBp;w8AD|>3pd=rlBp;xJ4?rvjUygm6F|izcIogTk;L8Dt zYw_jaA(n$L2PT$-F9$YXuHwsqiRIwSfr;hd%YljI;LCxD z<>1SKiRC0;u7)p1EXQIx;gi?!&xz$EpS&iYyyBC?Nh}AS984?+pBzjq2cH~FEC-() zOe_bV984?+pBzjqC;8+}^2wXzlQ+pHFUcn_$tN%P1bWRabG5ulkUhh-H~g$BiD3CuIY|k(;c~{J915T>$=SVv8!>N#Q6tvD{4A!Ubp%KJ ziut9ORZTIgnqpQp#jI+IS=AJ?swrkwQ_QNSm{pr%R&9z|U7cc9O^R7H#H?;w?c?V$ zKVnuNUGI!J%#WDWsgEo@pZP`13f)9U*_#=or|2u~=xK^QHYxVlq}b!a6nkt_?6FO; z$C_e~HN_rliapj8d#ow;SX1n=rr2XmvB#QXk2PYC*qanX9$@TEiXqn&L#`=?TvH6W zrWkTfG31(J$Th`~YlNyO*x&Kaym8TbZW}!)RfbyDW_9YPN$}vPE9$T7C(UTaQ>&9 zPMdN%(^F2TNjaS+<#dK4r-L7dKL=;V_;L7iwByH-n*-y=k(&eK$B~-@o56Iev>DM{W*`A4hHuj2}mC4vZg1ZVrqeM{W*`A4hHuj2}mC4vZg1ZVrq; zo^q@Mj6aTFP9OYna;#wdadNC+{Bd%uVEl1%tYG|ca;#wdadNC+{Bd%uVEplvW34I2 zT2qd-O*z&!HFZZsl+>uoclHEb1LzU z#h!No^*NPz#~JV6f%=?EyyK3uK1h8|CEjt)0l%j{rxNeDZto4L&#A;acA0V#^*NPz z$6H>wV1zga@s5QPZlFG=CEjuOr9YxRrzPI8q&|l^)_1RX67@OEvEF^$WkWv4`q>??qdtc@*6j|u zjrttsSpRkTJE_lMj`b5azKZ%B=BTxET^)m6SJh4|hxj8hA(lh@5lk$H_#>ED4)I4Y zu^iJ?VPZMNA899+L;Mj;EQk0bm{<<+M=-G*;*VfrIm92q#Bxkmg^A@5f25sQ4)I4Y zu^i%$U}8DMAHl?Oh$DmD{s_Cx5hj*H9GO1Ea)={?iRBPS1{2F6jtnN2LmU}QEQdHU zm{<;RWH7ND;>ciPImD5{#BzuugNfx3M+OtiA&v|tmO~sFOe}{uGMHEnabz&D9OB4e zKRd=?KReX!XNRz#9m0Ng2>aO~>}Q9@>1T(qpB)X)^|M2mSPuCB+KJ_m4*(O(As+xH zmP0-OOe}|d0NBqCVLv;B{p=9-bAJqWA3*Ky0|>hhAnZPXu=@bQ#B#{%Fa}~d(m|iRF;j0lN>N__q51E$!|D2)hqZX?Gt$*nI$D_W^|62M~7uZ47o_PVI{2Sbh$E zVmajJz{GOM&w+{Mke>q+%OO7pCYD2f4oobE{2Z8A4*5ASu^jSqU}8Ds=fLjE2@}g9 zKSw*U9P)EuVmajJz{GOM&w+{Mke>q+%OST4cK=-1eR5%9Ip&iKyH74mEQdTRza^GK zo)t_ihde8oSPpqsFtHr+tYBg}%oSiRF-I1ry65&k81%L!K2(EQdTRm{<;Z zRxq&~@~mKDIpkTvez($ZGxocc`Vh+@Urv8wIpoX1#B#`&gNfykF9#FLAzuzAmP5WA zOe}|dIha@u`EoF^9OcUm63el>mD>GoB}^=bd^z2T<&ZB26U!lA4kngEz8p*}hkQAh zSPr!gV80^^`yE->@5o&rt9PL8f&RpDsCxht%c1T8Oe}}G2QaZ5>K?$va;SR%6U(9Q z0Zc51x(6_^9O@px#B!*6029lh?g30Jhq?zau^j3iz{GN>djJ#5q3!|f@eTFQ*kc`P zCzeC~3jK-YP`?5umP7ptm{<<=D_~+d)USYvLjn`ap$-X5EQdNIFtHr!kif)ps6zr1%dvS16U(uA z3KPq*c?uKDv3Ux6ym1Wn*rVEs<(R$-6U(8VjAs$cp`Hv(EQfkBFtHr!$-u;Ns3!vx z%b}hOOe}|bGBB|m>dC;wa!g-^iRDmFMmw<_>dC;wa;PT*6U(8V3`{J?^i`Nx4)tWT zdklFD_879-iRDliNPl8E)CGcx<(SH@)v zN~;2 za;WbF6U(8#6HF|}&JST?In;O3?zsSA&*O~2p3_mg=X8WUrz1=(hdNz2iRDnI3nrFB zoi3PI4t2U^U7_&*?}$p3@QboQ|;PbhM_P(`n)KoQ^QD9O`sw_uQO* zo3ZESw7-bum_MiA63a1vPU}uA$NV|jPhvUd&xwav4)xaX6U(9A8cZyQdTTJT9O|vX z#B$7^6DF2p{+uwe9P{UdiRG9-Crm8I{5fG_Ip)s^6U#AwPMBDZ`E$aaV;zG%$EtQ> zIp&vZ{KRt1FIPLU9P`VCiRGAIE=(-P{BmJpIp&uO6U#BbT$osn`Q^gIa;TeUzQl5< zn+Frip>7^bEQh*zFtHr!=E1~r%rBSiC6;4;xz>(Yj``)1zvst0o-S7|?74DbVmZA3 z04K2=-hTiS%i;Y8FtHroe*hE9;r$0Nu^iri029mM{Rc3y9NvEb6U*WK2QaZ5yI%lpFcm141u5wBfo-f_@vBVN1GJpANOsn4Nyr8(oQ z3rDq1H&LHM4N~*Om3LB~Lk&{1(|dn7LM+E( zI>lmEBgAqnrc*3tH9{=MVmifQRwKl6ET&VAIPHUTh~-#Jrz|}5{)xnLET&VooV4~3 zu^fx(lr^_Kc8FLGb9~#mbBDYJscdn>SBHq@SWKsxanEf-#BwaA(`>fluZM``Fh`47 zO(d3MF`ed)Hyt_IYssV!8G9|6*4JyvguRwb*lWr3TdyS(CYFZJa!v5}qu)q5tOe`net$6oA zvhsHyw08dPgXHY*J_!4}55oTLgD|li-nl}CV2kMp+Z~yAScLr@7GZyfMcChA5hj+C z?#LzGk$H!uf#2U@(Oih-q&qV2u&CYNVG;IsScHk?q&qV2u&CYNVG;IsScLr@7GZz? zXbiSk2k#;kug~FKq~i5Cyo*%4K8JUair44xE|PfsT_j)>4^VSg7%*xyAGCYHlHSI8O6oWabGd4ic=idpeancA6O zidpeanc9ivq?i@&lr``W%SkaS-YL@@iRGl274MX(o%yAh74MX(omdX@^!gm$DJx!| z!#icg>vMRgO#RW#6nh+C^b~!)>jkGyA(n%_GERRtP?%UwiaqjfpxV*X6no^|K(!Og zNwG)X4OBaNnqrT<8>lmjSWb#P@@}AHh@Pg{Bku-Q#zrhB#U6P#Q0*2s<{eM{He-t+ z^Ny$b5X(t1WZv;qJF%P;LoO+X%sZa4x5RQ%44HR4wWh>!QVf}QJPYH*-lP~Z?|7=6 zSWb!|^Ny$5iRGjiGVgenRsXosWMVnko$c@c$rR3tlnWSO%LVYRu6Q^%QZ9gZb=A(f zk#YgNtE+a-jg$-EU0tG00A+ByI61NbfHf6D3b&b7uvEGOl3c;{O4 z;`~oJosx1oymMXPw44s_Tnlslr<~5!DW}6b*XqOhpK?09bFFs#ID9xbGq&6u@6M|o zKaO{<=tC?Ae-4Zv$2(VGVmbJ8U}8BbH^;m4YA2SHa&x>pulW+o!Jp%|#B%WGz{GO! z=fK2r@aMq9a`5NC#B%WGz{GO!=fK2r@aMpmW91tNW3c5|`38d8iRIvz)1O!lemR&} z4t_b9SPp(Um{<;eIha@uemR&}4t_b9SPp(Um{?BAvGNUsLOZdXlw;)^2x=#mlX9$l z13~ThV^79QRDFoNrl3Cd6`5uAFaKRK`OrC*{idmWA4h<)mDBiCnqWJn&5t z^~u<39{47S+KJ_)ng_l~qIP0Aspf%ilBk{gG52J~!~HnbJd{-Pz&A-WM`Agt=7DdL z6n;xAC)GUgO%kcYu1K%W3J6zqL+3DYV+{>ibfnEoC9q4tS*MVLK zdL8I>px1$32YMaob)eUQUI%&|=yjmifnEoC9q4tS*MVLKdL8I>px1$32YMaob)eUQ zUI%&|=yjmifnEoC9q4tS*MVLK{wj5#cI(Ff&+f5=(aWLJiCzx99C{t-b)eUQUI%&| z=yjmifnEoC9q4tS*MVLKdL8I>px1$32YMaob)eUQUI%&|=yjmifnEoC9q4tS*MVLK zdL8I>px1$32YMaob)eUQUI+fC>%cSP+v%l8*YDrleV6hJAA4WjZ1v0ajmq1H z@bk}juK&Gw_+5+>z8F8xnKJKtQ_w$e*SABxzp(RE`Z&L^KUdiPitz~hIE8tR@d}?e zsBzwmfEEJB_E`cYnS6?uO%kWBZ`9(XO}X8TyIM z6t;i;i|xBtuD`79^XGowJxeDS>Au@)t2uElJg4WK+f41jY;&?L^0iZ+Y`ffMs@-jm zu-nYAEq`*}nazxO4Q#3RZ&_34so-pr{kdwlzZ&RL*0HR6hn+ork)C&qxBD}@#@fZ6 zpxy1K=IHh_=F6O7zJqht?Ptsv`zh@9Q`qgNuszex+eNnrSGsk{`980~`sQ`d`jGV` z>yQ1Obu92?eam|2evA6}e4{@;fUx}>`3Sq*g!6gi@>9FZKlF33ze0X1K5+ShSTAs_ z7ub0!*!hKHy=eFGs6Ez;_E<0PW8G$}kIy&y%Vv5X={eZtrarMRX!m)m-R0lXZsXVf z>UcWe0etTC&UZNG`Rg@bU%LBm7fd?j(&qcu>>}BGd7G!3lkR)H@W`%{%E}v06<+e@ zP0CT1EH1qE$vc)C-u)HHZ{jTnloQ5pDSXumN0pZ?f2008SNqz3YvHc@B@5 zu;Ctut_!|vo4E@XUiz@`^c~J!aM%6oO{0DGwZ|`5a_!xP?Vk(m--Ye(7g#@G``u;s zdtu|d%y@-_M(Y|i9^PK3)=ORyG8xL~s`giizIN=+N zKdo0hdr|9*>utkxU7v+r&kOBgPrzYMz$Po%6L8oQaM%;?qjmFko$20R_Qd+tf}E7xn-Yj56d|FYu#Qycc$k-P3#uDWWqhQ0Qkdp0fS z9llh`(>aQAZGFGlp+eJ^=lS?BI6huMQ)ee1U6 zv0cv<&w1xw(cHB1>|yrfQ%}9N{L5}9h;!t9JCt*$KP}GfmwA2j&8LlkU4t z{8w(YNx5a>q{18zSYk%A`JEpT|IN3rV76nv_}7@XQQ7|C)e3X})C+&z9CgWY;@@^; zoib~^*NBtSxH{Ke9na z@Uyn8G5qKkdImqTK}PViwyZJy=pFh8KWobx!;cQ4i}16ytTFuPBYFux_J=bAe%6*X zh9BKTN8zUrX9@i1COQf~?VKy{qnqd`{Iqk%`1soxKe~yI!cQO09v^=jCjU0%Z~D`Q{@D0O zWBexnHso*m(}w<-{M(Sf=}#N_WAYyj`J4Wzv)jK z`eXWEL;p>G+Rz`<|2FjBxNGcR)1T4MAJhLf^xwE^>|fLWHuT@PYwTas|2FjBxNGcR zlT8i#WBT8Q{u_6V{cEzRVSkLfjs0t~sbPPNyN&&8vZ-NzY;9}UOyh22|C($ndkp=t zwXI=4O*U=VA6wfR_S0n3hW)X%t?V)M({!_j4L8}eVSj9GYuHcI%^J4d*0v4%X}Vd% z&fD6yVLwebYuJ3-TNS-zf7#l$VLwebYuJC=Tk6C9GTp3U|7~xno&9CH*@peMy`}av z{uX}I%{J`6?Je~|K0f}ovpzw3|qUH&cnu0P^;`HSE6NBpk;HOXK6u0P^; z{jbQ!^+)`!{}uVT{cl#rLx1Zv-y@mZ3zuQmo+up+di{I_1_-$`t|HaSVVvqUxh5Z!2?JexT z`02wQ^YaV)U(p}h*<*fwVgJQXJ9`ZI`}r$=xBud&4|@#x`}r$=+U@)jzn{P2r`^u4 z7(eH4$RGbf{Pbau`T5298}i40i1Bm&ir@W*7(eH4$RGbf{OWjQk1>AEcJ`RtPkco2<6E)E;Kw&%k1>9HEA|-t_$KTzxBvKv;>RDsFM-qa z5x-D2-*k|BitN1U9sZwwi+{vEq5r=TABcN2@qxHU5ALnpYnOcH9zD3{=KC+di+eHm z+PE*Xce>}zF8O|)@7?)6ZqFe;5clZ8{XO67Jw6ck=x5>pW8(wsa-YuegdAtc@dtnI zH1$vM3LmH1ef+|wE_KTI6!&1hYIivV&mew+{CHl94+wjFpzELFGaeu4#-HK?rcXNS zxf__?2y+K8T@l9bH~p3`fv<0RER0WYx+RPsZ~7#R?`}FFjE`>dBjGNdG+UT8jQce> z?%m+HkAvf$4vzaf*!~RSgdUeGH0HP>{~ocAh#Sxn@dU8_QJet~@dt3kCBPA{07o1H z9PtfsJO||MlAZS#b{@^&`Gx(tAs5CY?Bf)UxFY~h?|JT`)RP-_etCQR(4z~{$%DRsNqg#P2ackX`yKg2`_RUhkD`;4 z?wL^6KK&P?=;S7MHua(NpWmXBZ`yGCI&Rjgb~jkOY`y-z^~JxOZ1;h$G;cqAsQvZ9 z2adwI#l|0~yX-N|?f_dh3zxaL{lNqGi+`t8|G9nVIWKSF|IS&f)?co{7 zocST~&)ItGdhfbti+|aD|DpbNr#a&P*qN)CZN6OmpL$^5I%)K?;y-cwkDEPydCU0! z_Siej1|Kc{i_c%i&b^DpUw?>yagF$=PipMU|FQVjy>;t4@sx8IsUgB*4vJKaYa6G^9_qNDKBj$MWyj9rEwj9rEwj9nJLVeB&ev}2cj z{4-+wv}2=v{KIMd!)g4(Y5YwZf0M@F#Q07A!y$hge-q<3`41=gH%b0Yl7Exr-z51r zA%D}K;m{wGe-rXI{b`c^G)aG&q(4p4pC;)~6Z&KNKOFjR`qPB|nEp3O|C^-$P164+ z>3>Q3uRVtRjaz%n^9!Ebv@ zdklV)jrJJ)CYvVNA3N6v_Q%fkf&H;_ePDm=T<`3Ut*!PL{3aXiG5Bq5wa4JMwQZ99 z)E+}WZEdy37{9Hp_88;0wbdSD{HB}QWANMBYLCHhx~V+|zv*U^?7#LH{HB}QWAK}9 zYLCHhx~V+|KYlZM55MWA_89#5%Cy6ee+=&IPZu+VAK#sJ`0=N~@Z&>+)A(n=k55c{ z8vk$_|1kWvw;2C$8h?|m1V>h$M9?2pFp_EY?Be>8r# zpW?T@h5ZyiYs(tLZ|4{GQ~Y**VL!!h=NI-<{C0j}|Hbe2Q~Y**VgJQ%dkgz7esmKZ zh2PFE?7#T!{KEc=-_9@Wzxd~DyUY~!81i@fFa8&7a^e*B82WSO7B@{{kD;GSuDjS& z?#=KYx!X&ovd57BMvK2${s`he*TL82V1;hDtiq1`}rH==lqTFbNGKZN}8A42~44R{8{lWhcKejpP5B`t%vCW}B?!SrO{U7nW|0aI--!y*r-$MWK-!y*r-^B0!o5s)C z$R1;T-G385XCr%z_2q12kFma-jcNbZw14qG#qa*7_&M7-<9+|)e~O>8oipC;5B{_G zIop%{!G8|>gZ~`%2md+jC;orfAN=RApZNb_Kk@&?Z)=PHFZtk`u*c9(TU-49u%Gz< z;>WjQk1>9H6ZRPTiEqUoWBmA5>@m0h++V`}bAJ)P=_dCV@#9;u$IyTLDfShd&#Lu$ z&g890(O!GJi^&!)IF9`cy zpuT0A?*(Ds3&Qp+_JXkQ1!3O{(Z{;Yj`oJR!5L!%$C$w}7k{qaUjWD4!66fH$O;^? zOzmyzFYG*(_RtM*>_M=PM}1(ckQ{FmWui#lqaH%@zxDuQp#qn0vL^dSUL>=8Fh(uQppO`^UZ7Y_TwR zX^U@;@+{(=T^yHxn_Y?H66Xb{xN%K!Q{1?wxUt6NabwyeZcP8E zuY)Jz#_&hnnCB9QXZ;yZ)bBCQsOw|=)RlGPeqL*ySnga_;(fb$}YPuS+-nXX5-;dI=Wi)cMBPhD9}brG%S<%iK*&&xOHd8+GZQ(Zw# zbrChybx`vXbrChyb+oB2qNchIYF?r)rA>7aHPv-c^AdF_)V#D_*Fnuo)TL1K(t2G- zO?4@7M_o;u>N@HY&(x*B9d$L-yhL3J+)-CU%}dm!Q1cRXHPpOBT@W=dQI|r^OVrg+ z^AdGIa7SGYH7`*Y1b5WcRL{%X{dp2KFHzS7chuFG{Tb8+QS%aYO~@wdf~a|kx+Y{3 zbwSj;L|qd#FHx7(dR|`nnN-(A%}dl}v9?jyM9oXoWl{4IbxqW~L|vBb4?Zt;HPtmy z^AdGg>VyA_y-jslYR4DG_NKZlwR0~-KAx8sf2zw;AN+Cj-}CZ={1tac^xyOHgIpGV zH2Tke`c79DriW>1s7ut|B6rUC zJufeQ&&!M7^YY^NyuA25FE4)2%S%3|JhsgK|Y?Zm;GmN(T;pPcQ1bS7VYR~sw=?$M_n=gkNP10R99g7GkABP zrn&;NKZExOs*k^g-{o(2`}NHJ4BjuOsm6fwE9xR*{L~w8ennkGjGx*A&abG8;QT^= z#Gh&sLjKf6g#K6@;ZoT)uZ!UPinN<3`cwI`!pPGlzAMvNU6xn8M zG~-WoDYDJjXvUxFQgk+QMk1e7*AeT1INRMwZhgYBp- zi$B!`h5Z!2+kf%9{S?33e~sVmr}*9eYy9j3d_Klc&8F8ih5Z*leYi6)erh(oF00bc z{UO( zN#IX)ap6D2_@gc^{D&BS)WwDWAb$6MV*J!ai$B%%h5r-smyhWBgZ~rq$A8fH-Tx84 z`)?utsOt;=NAhw1P5kcvg#OD%ME>soh~ND;@w@*ie)oSge)r$R@BXLw-G39m`=1)W z`)}fR|5NrY)wPEICVuxn!~RG{=#TrK;zu@KR~G)K_}zaF`zaq0{dE6R{O&)C-~E5t zw^Y{}{=dacpAP?7{OdLC$Q)K7;ZX(-`etBKlzjcp}`)0hK75C^d_r4{csr!n1wEE=xqu-;| z&fZD)&8Ro~lly7Dw;F%ct^LV8*YDAB-yGbF{T?0nP5XQPC_eDa{W{&d^L;$u)BU;A zbnj00`h4HdaR93;;~uU4K3`#%L-54=bbk_m@O!lS_&vJo|IGVze;VIN_h{2s#on;3 zrZ>XaP}3D*?5635d<<-*>4Y#g(R51~J81S!7~5xdO&A-;dx=P}i@S8OK>j`ATHuIx zfg=tE_V|^4A8|9B)d;Ci65kI8e<5!Xq zYfKw|BCZ9Fco#V0U|{FhZz66+yZuo-4dCNcpNPNF-u>yG7x6mUB97-BkWcXcmtw`v zr}rhmi$YIQjX_Oy1vS+bRL{#(S60axdRRKL$G@(rE}~6!9W~WOP%~xs3DuR=RM$~GFE4)2%eU+)&&!M7^YZxYZK_MD zsjh>Xuc%9@sV=2@US9m3mluDkOR1?YML9!qhpca^OHs~{+#xo>^YV(tdR|`qo|oq? zqMV`E)ljoWUS6@-R2QV2q1Tn!Sv9B&GMl5ky!bsYZ$2zGM|pYidtP3#UUG&eBk`xY zCglvhE=V~;uWPEFmlwb1<;CxLdGUK*Ui_Yy7r*D_C7)E+q?{qSL*(OmdGUK*{{Lg| zEx@Zfy7q6}io0tP+@(Nr_F%!?CAdRyNr>W3fl_F30!eUp$k~IpNGVXc^}$7c5+?0_%T^~&CD9R_sryk{afeq?B6<>ugSo|vDtdvPegeJ>7Yp7y;s zoO#;!;&A3^-;2YUr+qIDXSVjeK9t|S7l-)U_xccj`(7W;Y;i7c$KSr!$9Fbyc8l_B z_xecp#NJEfJDWJWMft6Bd5({DE^qfA`(7gYk9{u@XU_J$M4UO}T%O}&oy&84taEwx zZ=K8A{olS z82+tudG>Fe%i~@#=6~*^@K5tU_feFe=6~*^D8F?s&*jJ1LcfQ9>x`bukFkYxlpkXY zY-t`IKWhGoy-UyUd$56jj4iNMe%vdd*u>tex66-v1z5lAdj)p+aj(EGzoC`i(8_OU z@yERgyZnY0fA(+1-$41T_#0aM*}rx#0_&H3F9Pcq#u)q8?nT)B$3Xe5{=@#YdmYm1 zKkT2@FZ3TSztw-Z{Mx+~yZ>$FD&AwR<)8{9_>g+PxZk{^9so^ADGw)-U^BkUjqh zw68V)uzzd*;qqJaC;Qj#1=;f_`?uy#_HWIf0_}^jW!-DC=TG);&7bUFyO(9pp91|y zyO(9p|LotI|JlDa|8x1R`Jeq;^FRBidu7phmq2{1`JesMy|QS$S0Mg$uPhqx73iOI zuWTvaD^PyASGE-I6^IYrD_e^93dEo8l`X}41=`nIf7w6XD_e?p46FS1y*PXQwaahc zi{m>x(1`GFt-p5p?R#;2=g7KOX0N~OU%S_5>jyjj_Psv7bEL)JzSqZN%eq&_V+$G) z@zL(}+4{%sKlZ&udgqG0muTxByZ_kt5-~U1_Y!UWX7?Z5i{|p<&KESI)&K2#mFWNW zy-FTiTK~82RoeQE<8SFto*!`M3mOsexAZ6bxAZ5+$I_oXzAXL8^MiIT6ysMwBcgpR z{mlO18+pLLcCXde&+OmQ&+OmQ&-VNywE0IMM%MgkKqDglmVUP9Ps6%bX6t|UPxB}A zzde5n>t30y|9O71^gsKz-dTA5xAZ^zx87gu`5*V9aj(pNf3fF(yuWbyY5l_ci#`A2 zUNrl+-dWh^n75zBe%4l&3rX|a@1h+h#?NoRqdpn@)XRQ%Efa9s%YLV=@_eJ0{jNLa z?Ie6Q7{3Ew8zH>xcjMwi_juax%$Is(O>TcK8>L5C@0^0{qpf#NL4N4-=+rwo`H!~W z)hXX-`yHOj6HVn2u%mJ=wcq)v{7db<0IC=6mGNhEYU!qCZ)$#|=3i?0O07InE2q@T zFLMmK`i1=&omzciZ^r?C?D)XH9XI4_$5U!?mRkHxtzAsJy(o@RHd7qp*!9Kd>uL2h zwE7xaeT7zEq1E?;_-pkQT7AX;Xvf(0)#?jBc75UBt}pVn>npVSq8(%Vn^s@Lt|RKJ zrK25fd$gn7KR<}4mhT7g*UE`@w979Ch3`$-d2cDckEqr6gLc>ZgBCaBYxhsIquoEz zj&}blm|@55E&y>mIYU9x~J8v3s-no~^!@OY1@GXG`jJMBWr*u8X}sBgI~~ z!Su!JIlx}$!S?zOwsis6)(c=;M}X0ml(z@yuin$9&*Uck@b~R$)4Kn++4UH+H$GLXC8zIwas{Xy?1^hj*~(fgI&-}F9d z>p|pY^=AR5FZ6R}tN$}w!HdZ?_yT{$X*SM?s8h^V$&6BP$Y}GpkdWxG7h5xWP2vsMpmzy~lzuz&Sw*EJd ziQT&Y?)7k&U$vw=4*$+^pfwloDLkjR!trW^v+ex-vz;GdNB?`urf=!*eKd~I>~)(M z&Bn)yrL<=WtZi;a1l(~@{lFaucO2Y(z}*MjeZbuZ+4_ug2{}%{aZ)s}!Qznd;0v9eKor z8ReMo3@j~{RLaP_rCI}VJHZ*1SJNKiaQVK>cU}jI3$0JZAddTg4i_nYsb_%C?h6vP z;yq*jGG#|mGW%QR#hKfSjd`*N*o^Y3Cnmmb#yoFAa?z(yf97kx>y1iZslR*p@Qjz? z`CfgNMaQ8_cdja~{svIxC||SAQ1!Qgju|`5?-F<9XP;(!X0DFt!JKdFDN`I(eK7aI0Vl28h|^Qe4if9e3}p@r3>2ldPhqb4eu!|z zrvCm?T!!(E&xOvb_SWR|<)?FsAhyU@$iN!PxJowVuqYm ze6w0g$HhTv9;k4wpfTr!njdbhTy0Fs-=3c>di#x0YJF9acGHRl8IpSnu{x*N(Kl>S zuNyT*x00ufuE#tgTJGv08gDIctY4i!;^C2C5&80)m?L#E?Ts&CY+1WL4VeXZ4 z!bPeYv(0nsD&%QWWw6NEDZ8xT>78f)n%crB=Pmm`%aV84++w16x~B5ktH*guc1|U- zU+*SoeK9#-)xwvI93=+H_SGKd`}N5}V`|l4d9O!Ck3y-c8MR7=%iyFxD?f%{A#GGm}Z+dn$Ley;e~ zux$?6RgJ-|C#DGMeUp=*#Fo=6-55p9htxJ`o$QK zORY827bX^;cU6DecVXOoBEE-OBjU`jDsqgE$M);W`-$&wt!DqPzwIyT{FILQQNvKN zBX}3b>dvJwasSv#6EWGAe}G7rGl2xBuii#f&7GWimeE`k8ScZJ;q#*6>3)Ca?yL3~ z>H7_1PSUTNQN4}oCzEqbca$|0Pw6<{dG+fcw%O34k-0P5KxVIY(Prm@-IBkzS)M-1lci@?FalZdul(nhZfVBbQq^Ymyr%*hAtx=#tdCXI*b{*jC2^s z8M=&g7^g#*kq%>qE+ZYr3|&S#j2XHtrfCmlPr8hB7&CMk=`d#KGSXqp&}F2qE+ZYr3|&S#jLQaHMmmfcx{P#~H)0E2Mmo#@Lzj^bV}>px9mWh@Mmmfc zx{P#~1NP8mq{En@%SeZD--9kA9cID?x{T%{X6Q1VNr!PdbQ$R|eipinbQt@DE+ZYr z`9hbG4ioSRT}C>L)1k{qhcQE!kq%>qE+ZYrpMwTnMmo&Iv(ROv!y zF+-P;4r7KcBOS&JT}C>L8M=&g7&Gg#6N8zd%SeYYLzj^bV}>px9mWh@Mmmfcx{P!f zGjtj0FlOj7(qYWdWu(KHq02~zF+-P;4r7KcqxFLsx=d$UZ#W&Ai`Eim=rUSkn4!yD zu_1lH_RwNFlMdr_=rYn_%+O_|!#K{+Wu(KHq02~zc|(sumyr&0LXSb0&A*)6gdT$~ zBOPW!k3pA_4l|+0pvy>yu^xjiBORvn80j+7VXViX%SeYw=rQOr(qWSI80j+7VG?=_ zx{P#~gdT$~BONB8$Dqqdhe_x$=rYn_5_$}}jC2^6AG(Zm7&CMk=`d#KGSXrE4h3CC zI*j`>bQ$R|wt+4q9mWh@MmmgR1zkouj2XI2i|q$oWq1y@fi5E*#tdCXI*ffnmyr%* zhAtx=#{D0qE+ZYr3|&S#OhS)Amyr&W&|}bLq{Afi7<3uw zFbO>dT}C=gLXSb0kq(p4W6))!!zA<=bQ$R|)??6Rq{CQ`L6?yZV?734Mmo%d9)m6; z9cDt0L6?yZGoibeI4`myr(R zbm%hDVa(8Fq{En@%SeZ@ALugDVeB8ejC7a@KhR~Q!yF+-P;4r7Kc zBOS&JT}C>L8M=&g7&CMk=`d#KGSXqp&}F2qE+ZYr3|&S#j2XI& zbQm*q8R;-)=rYn_%+O`p+Wi5O4r3eEWwX_@&}F2+`X6Q1~Va(8Fq{En@%SeYYLzj^bV}>px9mWh@Mmmfcx{P!fGjtj0FlOj7 z(qUX4=rYn_%+O_|!?;bM%SeZDTSJ$T4l~fc&}F2qE+ZYr&q9}x z4y%Y~q02~zv47|?(qSgjq02OV^#N-dOln$7YMSi>{+PX{tEJAQ!??`QWu(KHq02~z z36u@GjC2??bQ$R|X6Q1~Va(8Fq{En@%SeYYLzj^bV}>rH{V|mn=`zw`%+O_|!+0)* zE+ZXgB46k-(qYWdWu(KHq02~zN!UP_kq%>qE+ZYr3|&S#j2XI&bQm*q8R;-)=rYn_ z%+O_|!L8M=&g7&CMk=`d#KGSXqp&}F2q zE+ZYrv4t)p9mWh@Mmmfcx{P#~ftW*=kq%>~{V_>8j2XI&beMn*bQ$R|X6Q1~Va(8F zq{En@%SeYYLzj^bV}>px9mWh@MmmiBLzj^bV}>r%-tj+R?Y&-V@B31F$NzvoX0Pqr zNS#TCaoM2DNQW^)myr%*hAtx=#tdCXI*b{*jC2??bQ$R|X6Q1~Va(8Fq{En@%SeYY zLzmJ17&CMk=`d#KGSXoj6X-J9ALDTZT}C>L8M=&g7|%J-Wu(JQv=MX}=`aa~E+ZYr z3|&S#j2XI&bQm*q8R;-)=rYn_%+O_|!L8M=&g7&CMk=`d#KGSXqp&}F2qE+ZYr3|&S# zj2XI&bQm*q8R;;N6?7TtFlOj7(qSB1=rYn_JkLXykq+awfG#5)CQvWvGSXqp&}F2< zn4!x^hcQE!kq%>qE+ZYr3|&S#j2XI&bQm*q8R;-)=rYn_%+O_|!c z<$=!98SgVlhhEe6kR{$>kPeOJij8(IfO(Jeg)So<#tdCXI*b{*jC2??bQ$R|X6Q1~ zVa(8Fq{En@%SeYYLzj^bV}>px9mWh@Mmmfcx{P!fGjtj0FlOj7(qYWdWu(KHq02~z zF+-P;4&%B*myr(R_JuAZ9cCgX&}F2aXNGv=`d#6ACsiR*e7%u=`d#K zGSXqp&}F2~{V_>8j2XI&bQt@GE+ZYr3|&S#jAI2|Mmo$uIibr) zhY2ur8R;-)=rYn_%+O_|!px9mWh@hJ7xS8M;ho?1dp6I*Y!Uq06w3hIHsMoj+zz z?Z@`eVmjlT5`Lh|a83z^F2gw`7`hDSlwjyGoKu3K%WzH!hAzW7B^bI4=agXRGMrO_ zq04B0Oxcqz!#O3=q04Yi35G7iIVBjn4CjuC!#O1wx(w%(VCXWO zQ-Yz(a83z^F2gw`7`hDSlwjyGoKu3K%WzH!hAzW7B^bI4=agXRGMrO_q04Yi35G7C zIfxm$OlO=^!Unnw=agXRGMrO_q04Yi35G7iIVBjn4CjuC!#O1w zx(w%(VCXWOQ-Yz(a83z^F2gw`7`hDSlwjyGoKu3K%WzH!hAtx=#>~3x#9(IVGMrPw z2D%LAlwjyGoKu3K%WzH!hAzW7B^bI4=agXRGMrO_q04Yi35G7iIVBjn4Cj$toU-1SUb&&mNQa3PBX3}T z%m?R`@f()M{+JWzlsgYJ!2XztbIL9EreS|f;+(SOfo0eqlQ^ervZmz%=rWvBwi|Xl z0=f+6lndUCSpr>#bIN;9;zvT4;hZu>*%V8l%WzJ4r0>;5&}BHMM0}vja83z^F2gw` z7`jZ0?FUTzV{8LmhI2~TLzm&45)562bIRJsD=mgD!#U;hk;9fim*JdpN%Odo&}F2< zj6^lNE`ct?Ic2*^5fRX3IH&A>bLIl*GMrPs-g^i8V-n|--v+G4{+Pr$Wr3Iu*dH@- zPMI>Y3--rMoKsesQ3v~DKBU9M;eqF{Kjy$W<*L%5*dH@+PI>cM^*qpJIHxQ)C|O?U zGMrQXTQq zlI&0K1udpC&M9ks_mvlP8O|w7g@t=Tm*Jc;-ubLv&}BHM>~}A&7jzlUDd%6_E=?=rWvB7TMXy6S|Cam{?XmnFn+k z&M5<@9f^c4!#QPvip`^-%WzH^XZq|Y=rWvBz8ZKS3c3vEl&c=!j)E@3Ic3}@@uH#2 za8CK)e70!lGMrOh?>8$7x(w%(S)$iQL6_m2@=?u0QP5>Lr(D^jaTIhJ*6tQYt|(|R za9fLUPMM%qLrwr}4CK9>~=ak6~ zcl3ZRBOONj+O<5P%WzKl#lv}?&}BHM>~(6HCv+LkDGwyO?g?FnbIRyf$-SVm*Jc;p=VMr=rWvBesL>-7jzlUDd)vW>jhngbIOD> zUV1{8;hgg49htnK%WzJ4=T|yCOFoZ`JPW2S)zI!=FIc6$vqX+dt&X`o>I5h({+2@&-0q8 z*-y=YCbG+@gv{Q3TFXqwl+HPQx`WL6?vjZzyj|N(>h^lNZm;|CEd4n@yYzCfY&R+a z^OLio^5=JpS1Cdp%vZ*Zr*RthDRpZ=aeG#g&HfzjeV((p|lGtPj{{PD(U@^W8CVm8sk7>AJn{ zN3$_B8$+`(G@piUuczzwx*x5MLaU?D>L|3B2;E*!*X?ybS{n(ijfB=lLTgi@+w1AN zz3xZrV?yg=LhEBf>ytva*VA=--H$d#gf>QmHb#Utri5;-M^z?%ijYD5r11AtFzreazp4`HOg!ZZZ$O-9?niug-Z_jczAu zFU`Sq5gTfWV@uUu-{MU<#9rE?grD}s9y`}0@?}0VD4$%~EhV$Jv#Bg~e|(8^$FWiYie zNUaP~D}x>rJyv?#Nv-Xq)^<{BJE^suskNP{wVlw~PH1f>w6+sk+lf6_5{O?jC5XO% zthMOh?4r>;AX#+j4Bf@a<2#Hw>5@lJXw_GYX%=Cm3Q8W`;rT$(>YI|r`k85>&*cme z*RM};R+^kHdVHsFQL0ZRIWY2B)WtIeM3(xYGH%bOQE^Jr-NlZf^3IWmQLVG4HTMSx z$okO}q8`5(Y2Nl4D4(X9<&h>ww7F_TcloY!h-bFR=S{sldU}p#17w*3M?K0PUtwN2 zI#lLpR3mD`%W)ix7iqe{j=!)HTwzYk7tZ(my<>B z_vj(gbyoY{Q_iOmmm<_&%9c7_Vor^60)0N|uF}G9R1xMa9uCnlTPo%st2PzMTCU}B z@!RPB!rS{akE1%HdWdSxRloh}N)mCrsnwr5PBPYS3*mmdwoN``&wDjr4ScZ4@%)iG zcbHLmbBtadJ^g(dWfPG$!ci)hn)4gv%wqiH3}T=DLG_J86Zidf8_k z*d|?EG6Cz%u zy>7nyp~Pa}^<71R-N|H?g$bgza?wyNYOj4JaD|vk~LTT#JTm-^xr>aQSFX>MD_P6 zxeVt*L&cjMS-AXl3f2>a)AVN^eRRE%ufM8Svqj?^^Vcc9HmR2LZSF8t-$E~)19sG5 z{x(52=~1sW^Qo-~<%SxanO`rwXQnEp&Ms3LKbobosJ-_C38t8DPFp^2rFQxz@nQSV zw-*)OwL>{pp`QhcA_H>p`ZE0o8t(~maG9UK3K1_0bY(t2Vwl+W%QEIn%LfR(JbL=! z3w_zf^Kqc)UMWBGqp2aHZ?2!%zwAx##Aj1E(2g_Cgp0B_CL7?3IfjaWChfUwD{H?o zo>*tKIeU$AJ`pNb*^aL>Uk_3HvDxC^HphP5hV94AiZ8q6e!+fT2X&A&lBqqP%TF82 znp<+Q&5JZOWuA2Ej9`CrAvbwc<8(RFLq;c6d$!$HTs5cm8_4NN2SpmuF=|{JXKRXM zIZXB+xS@}jm3l1mfHVQZdsa2(7e2va&$DG*uQ|EHgTXhFs`04@X2CIPtQ`n0 zC1>o&!}enaRF^k0q+`xBu94KrAhj|`tqf8tgVf3(wK7PQ;k)8Z7g8CVD1*=ClS`-! z2FmcZ{Od?6gFqSDm#Y{1ln$EqV-Ft?F_B$Os(yt)^<{BJE^su)cUa0 z`mogcu+;jn)cUa0`mogcu&MQ7ht`J;tq&VoAJ)f|KGvi*)`T|pg*NsLZR{J`*f+GX z@6g7+)W*Kl#=g|XzSPFP#2komN^_&c90;a4P+|@Q(;O%<2ZCu1l$Zm-GzUs;4wTv) zD787z)aF2^HU~PiInbfa$%bAYJzZNn3~lXjXlsYJwsx4>+F@#Iht$>%iM0cDp|wL| z?Eur-A+dIVY3-2O8ft25sHv@?Qd>i%wuVY=4VBs&Dz!CKYHO&et)Zs2hML-%ZtCUH z(>3j3YTCopw1=r_52W(_lWD26Ji}%+xfPscA4%(_m85 zU{cdyQqy2k(_m85U{ceBQZJ95u4z}PX;-OfSE*@NscBcKX;-OfSE*@NQ`4@drd^%T z@X@OiMw7NTpy7QMCW|5sZ$QHzS-;YQG`s-~zdgZw57O`kG<=nE**r+YJD}l<7MU7J z8s3D4ANnv!6lr(~4WBUc*d?UlB{ck)4WyrkhJ-YL+Z z=^aPv<D|Y~yU(mcOFih_$H2SK?rE1j=-tP_yU*zBKSa{I zk5Or@((2#zOlrEqV~?sc=+I4c57`A?wods^S1GCK3P;RJ%4_tF)uGZACZ8Nz@^84p zzBQEpUQ{kum}0{IDL#nRAM(?pNv%08RJg+E7jzQOe*X%NsIT^Z&puyay28uPtl;>+ zX)-{#!mAq$kSO=lM=K0hIKhOhT-T17>k3!c6`#6ISp9rlo=8t$=?br1wu0NMmfryB z3jY;tlzDBCYX8{{Ojo$>o(9}T&sPNrSNPw1{S9_)BHhNnpROtNEE4Amg z@>DLN^Qp=?*nj7^wS~DrX(zuuejo6StW(%$;*3Lu&a1Pk_i<;Y3_|B=o946qswsnn z&RL!|;=FzhNh@@2zb=C9tKS+ZbWYM$ox$xmlSb$qwrVlk7mXPxbe=Ur*^gM0M(Awj z@HfyGf6FpV4Ejm!frK9{XMQX_y?+J)`}~(12%Q)C1#)^1-#}w>`>xD)+x}$e>6!8s z<@AYP`UssTe%*r8y+2DPbbfL`_2KQuEv3_UVpgS)*2b5Rk&;GQUq4UiuYR{+C zfwDs9!cCQZo9$H$od+&a_LaJo6*^~YqwIewSjEseUZfgF77a*uN=bs-OysDU%1-SI9qz6k^Y1qr#~MRSGZzR zQnX_Gb^eKkD=e-z;JVaX86;g{#PzRSAOBhYrwmbhM-@_xak|12(v9Igkm2;4E8HtU z`CpiSw9^%C;W0}29~LfLVe%;vJM!;vh42iMJbGJOF8|$y;ldRrpBx|Z?{tO9C&!=sOIP^+8lTO#gq0Z^|Ah*SF8ZvC8;;i2Rgi zJqFcfKS5`M(hPkA=c^0M46 zVUL4_D}3@Z)&Hj~T<09PNolasr_zegGFM?guV~G8#b(p%i^~2%H<4tS+Ml2MG(>dI zRG#a2??y@CcTwq?AH3=suGr+8JC@@%_qUW6s&h)Kd`s)5D>ibf+M{k!vXLxMw-A@7O}`LXuemzgnliANEVxvi{Y7S+V7g+n zwe}94qZ&L8lT)X6kmwH&zkkm0`zz;CM!{q?xjZR$(OJiYr(FK-gFA}mhllezSR*W4 zj2*XtYv-w4-~F&-5!Iue{P$zz&tl+0CR5NpA{w zv-TIR*c_Q#fS)}TQAwQfRej#ON0jLbZ~A@?_km3b2Furz)Y!33imshisQL)XsC3B z5BFF5nM?YmHeKPiSTh4qH(@mt# zqnfEReLu$|Q|Hkc)O`kzdyS>e_al}4}oIv4G&>~pSbEOp+zP1%p!_rTP7`>#j% zPEqi^aJkRwC#eF8@BCQ$z$ce@d`;faP3rt|Q4fheP;tj8^Wb;&nd9HfDE0KF71jA^ zn_(@a&PS&AVf$OVOjGCLOHy4hPa~=G)kn&{)8VbA&c#~){=1W|@Y=ho-{yOG%qO~n(#bO#?Kj?LC?*iA zt{c3?b|dNLg`7Z^n7je%7(jc7nn`y?WgsY>0jh2xP0(;Mgr^i z`roBYIL{Bw?gvO$Y%X0; zd%4vH#g%@$zTmki#fxxx>#Nc1C$d_AOPrvdDu27?qfJ-%a9!oUZv6o13Qw*P!2Py# z_-MlwjyHBR$7D(M0O1N}O*WP7M;#p^&b@3QR#ZP;u-)LKV&zG7_E9#nzxn@XQ#56q zIIy`m{)tiNO!Y$bw|5ky?uCn`b7mB{dHje^nSBR~(72G-+a_A|@5t}64C457T@xsl zl^ViralgO}<74SF-nQmTZAgGmi|NU!=Ro{q14z&O+xtTh(VQOlTY` zc22Iu`QF%A-~$`~H>p`~Kcc&qnS8%sKbh_g5!JHfW&2Vd)y3*(>MrrRbSXut0UOwU zZ=!IK@4DLS*qEW2I5A^8KRf^HzGC>g@Q&`rbx_px+mwuWbj0$d9G(wm#d+t7vA2&MS}I;%B#x>>_pEHL->2 zSGkhO`UQfS4_2&h>gmntb5D?O!D}_7o?dTKIHyl;I@mdQtH7`5MV$mufP1-;z^ae4}g{Ms0D* z5$!lVtmLm|`|_%PR(_aXPT!^ae6k|Ve+%jjyiiiQa05#HIXkOnzPO2ai7T+rn1Sj{E+kBZz|4JdM1^9Gb&DVGMU^vT|Il^ zmnQPUK9%mbFR47YRXzK3-4W-sUCJiY$tH4MLuIpXSTfnAaRBF4q}XV~6{fouY#&G6 zyZA$%3M#JI(3LBo@SU>-Tiz)#|D3c?qG-}z0McJ-Har! zM;gZd*M-7@14N}aBMpDzX2g@`RTS&Di;2_r8mEXK z&hi(VYgQ8_o}VoAT?-G9uU0iN{@KYwzQmg|`*Zu&&dT>IB;q`r?pM%Vi&)leHqZ6o z^gXGn37wyA9mMIw*32{J-B;^l&fo4Edipo5%d<_*g(Zc~UAC+J`Jyw%8#<3Z>BIK9 zE))?uXX&B(f7MB&44wDgb13^|g@w-Rzf|_6YmGE?&Rx=A`zmb;3!Q!EEBn>2Mi@HN z-3gABb&ui?neIXe#M8P*!ED{5V7Bg2FkAO14A@)uDE{GR>5c^ZvF=fDIjwsX68^1w z6n|(#_bAxjx<|om-J@W(?olvX_bC3*hVD+VjdhRW51H;xa5=4e6o1J7j=I#9GS5n{ z*4)K?S36x{zXrYCP>jfc0?dDi2vo*7MZB;fduqtBD@U2}%@(zF?2 z;!~b&mvadFnKUt6bh@ZM@9|AoKjG`=E713bB+n-<%pJhoQ7ktqbPQw8n&Ot@Q=Sb> z8P0wZtz7GHh1)e#_K(-ia13{f zs14@Fd31dYY>Q(n%*Ga{Ab#VwiO2hIv--)L?G=Abd@QIG z+h-p8xok+kFNbI6j`>_3d!qbwX|&Y5WN~KVYt2pelVWKfnYfkWh0%TFjR-EqY)y!yyq)07|o8JT6i8fEy|-*%UkTdeeil)l(XA5Q6m`t0WN zS54eU&hDr9$3%VPvQ%n)>F2Z7=?ZV|_#>|i?;>cvpP-%%+&rPk zoCUP+;+b&`ozq`X_pu+n$t85&=FyeyH`cyk=sdCddG?>~%kDzwVMSFxmk)n&=se(Z zH}*5V;w9soQ1#gwU);?hbk=Qdo>g~yjz8}vbUtN$7RT6vj~zNUxvhNG>YPJVtJ$6N zS|4`7_*nY&5OrQN>1a2hb9r%QU1SLGRn}oRJNJyzxD0GLg)Q${CEz}6cH|5;e?CS`g`u1woX_0 zzz^!a=;?*w(iKkDX%hFhZ#&K=?_5ubez^2*SnYVWscof+mk`n*x3 zzc^Ub@hQ(9{!01jP@U4#NSKG&DSS22W%krxQmuJ=bf^v0z z<)_RSvz)HjbnBw-?JUbWP)<+MipRy{CE+gdsYR-PCS304aD|_2Y0mRQ_69-174F+a z?MeD}Yi_v0r;apZ{}FA1ge#n}VGze{b!2nX6%HNKoX6UpMnTdQKDu}S+Z+1><*ygj z`N*X0?d404>O7X4X3i@!eXsWL1KzYZ+oufX^lyD@8lUoPoSy>O&&)0TjN2J&GZ*#B zAxid88s@hYy~LsYYR|IOd&@+j}uJwW3M(3IZ3Ri4Ci>vh2H;(s?%6HVe+qmhiM5P1{?vv+c z2g^m_!`T1E23^gMr7tSpf^FWfN+xw4no<32m*;N-rOu1q+~slx4eTtdH%`aTM*B7T zfTz{2&go6==8-zDDOHi54cHkhb!2bpN= z>x%=0D?DVPYSUY-&O2S;6s~ZKe$BW)=WmljxWeLvD$h8v&EX3FE6>Rl>GQoY7V7xUjd6uf+*J0)xZ5$Q z_LSmhH&*&wzFJw8by1VI;nEeG)(e#esP|n%)2F^SkC#Skg5|_QtJu%jC*dw}>g*5L zeiD5adc}PeBQ#U@^ne%xo8-3yfEWib2ca;<`So5}&7U2ZS; zafPqnRQ5G1-}Wi9t|UKOt9E%2H%9otTI!WEm4x=NoU*xSPx(OhuZ_JsxuiVypt z__)MJLi4aT{_Oj35qh+E63+Z&@kZ&|0~ZYe^%MhKDf`O{&n;JH4ddpPKm-Ze%V9h$zvsX z{@5_JzpR#HE%TX;Z4q0JZ)mn^a_1CvcL4w5|5kp|vWtV~@I2Dt4}QVlj=dRew-cos zb~@P`wmq2%+Yk8{wtxCp*!j}W1=+DrdQRBoB!9v#KjkAzl}zD@e37SJM>~I{TJ`1e zWYw41${%^evFgig)t8xmg!(dD^<}o|%S?Gjq8#vJ)z`L1eVOS;s4ufsUuLVm%+}AD zt@?5~t@<(}AFt@+UdT(2gB~BtkA#gLPd(1`quBWC?V`8We4l#x?KoQXWuI0Yn8^>~ z!)(RP&NsIISU=}+Cm?S+2J zHhTNgBd8arTlHer`-xRAPPgjCWwz?YjC$F9Qm?Nb2R%NPe~B{d@wCdr>3aP2c5#op z*miV}JL)iczta1g-VgsX$DNvszf7|%3S%2%0rh_dDqIq2cdNNX;U;XyqkX>5BShQD;)KG7bFl zt2vVVc-mu{{CnDCo$~dx+ltELX}1-X)6;G%DnG4p!zIoA(Nr%x-9Wl!Z@}L2BjCrL ztKi?B!;r649)a@Ma~{fRm0zIzH1{v1{KO^a*c4WMksfKqK_CuReBj59n?T&GcnZYR ziZjY%#~Wg-?>npYT zq8;t}q8&Z{M?11+(dx_XZq*ll?D}#)(fg0yuk`+=_d~tDRyxPQvgi2dans{z^-qqo z9)G=E^!B1PfwaPKQD$AnDSG?r?M{AptwVhDexmmuy#N5>kB=TV zt6m&WJ`afGgoFSjTyFDIb+Y{;9H#yBIn_}zYan=$^^E` zD8cZf#Vz)%7kSdp*oMr66${iW_RLttY&hFskNAI^dy!6gvkmNZKe~U!6y-s_dU+^` z)2;f(mS4qG)$7o~Cb1e!l_|Eqb~_5x0sgJ}G9#XPobfZ*&==~rrBTBQX z_qe}O4{zFd5$|iZPX0^uaOb_H=spj=_2AAf+`j+FyXQZ#?YPWnKdpbdH9y6J-q+Btxo=~D$1wlqTtC%w#L+8D{b!$(I8*MSaeyCY%2Q}@6O=FgjO&H+FvFJ0$qXOJ!>Sj2Gox48 zjJC5G>AJn{NB6JitCvSFr(S-&UX-5)%7Z-hIOy@wua1-^gGmBwyIq}%O?JnVLaAG;mV7nzZ#7S9jH zixz+MPk}NcX7;>jorki%#rcD_Px7ao|I&G=y-)JDo&Q?rp%VSk+W%qxGtZvrJk;JN z`QV&Xd%r`T99x`sY5OD}oWtUs5apz=KRmBjX20uw?8_kSuiE3H{(;{~qp!d3%-6b; zfY_m4f5{$~`kghd*9Y(5TH7J69NRx{j|+DaI8Uydo89M(?mqD6_5o-Dd?T*bddC{U zS_fG}SvrL5V)Z06k*z18iR^V&U~RY7Ux78>T9*aZYfFd3uBpfu>DKzr_SU-3ek?t} z{w4!r>$|oq(f{yiF8{}!rs=C@MG&q)_PjLoCo|M23k4oJWzgN z=@7Dw)svjA#ews%{a8ALwWOs(IA1N!ww~m2A`jg+m}2RPfANjBvl;2Sz1EJlUgfgr z`Re7d^pag)=q0oZ#|{kN)_Z|nCcGEe^)+pKtsS||kd8dHcKjgzT025NOW0d|hne0B zY(2@b*X*I+*amrO{%t*J<;i-|?w@u!rPWtZerdfIpk7F4?T&P<9Vs8ylXm~)_#jWz z4P{2((b^I3JDiTbgVJ#GmK+I(;9a?)~)e~F>Q}i zY0VpKkMV2GhZxiN8OFH89AnJ`yzgPpO_(1xWQqT`?~`cj8qZbMe8^?A=0h&KH6KdU z33WqV)La$&ek~9Sq$4)gd?*n!?fn|*_WL#LIVLKWvGL(G%=T~1hn%l9A98uL`2Vl_ zBoxbN^1*EZ*4hqhH>V?i-KUvhrgxIU=69uxEr)C+m)G1OzL$DGPZ zb>+PddoANOLK?ocwG8Qh$=-;z#}%75`l=QODobp9xSdco)Jcoy2V+EwzrB`m`RO@| zwHj;o*v03D{nhW<+P!h?C;Tn^jsIT3QIQM6^_SkqXxAqp8alUNb?dIP*z@Cw{dj8?>JJ7u#-2Z2L zYcGiT&)o0Q?v|i`+V_HR|DT!ag**kyjIw{qewQ@{*_SnE3e0oXnB_U!nlovv^7{_P zEYI22oGH|}=Q#oT)}H78KlVMP;-xNzPowc?@9oYtP)!GhqZK1Ute6x*q zrh~RapX79uQS2r%VhkP&>>2s7mcjdv0X5 z=0;}B>)M=;_c)%%R9ftukNG!tuG7ko_qhC4y^x1J=kt7xbhXaJ?vG(^G?5PfT0B3P ztF`#s?>P3nEAgzgKN-tf+x;c;Kdo!A`=NT>^_U=zDBGVk|0i1gZ6wwh_(WV)9LsWC zwRPl^*6T^%uCeuj)Y?w!eOT|?THF1@>-GN}yPEztwe#*j?e}CS_Dt|k_&wR*@6V&Y ze{~(*=fZ#H?>_MFs`IC}bn_qb2~{f_pzR?%m?<7>EhHez{n zsqFpu-8``w5iNr5srU5MGo#z*D#D*XI^z7O=Hp01^XNFKXEM`sQS>}B z`HLdI%*ciEv(r88bmU{(b3T?IeOV1Dc8Fo7MGi-aZiT$h#@*jJr274%WzSbTJ=S9!O?p2V#*gXuYzf}3D-(5j| z_`hY(Z24h3%RjS~ul+pA!)%q4*($$nL!MQBR()-I#KE?S{j3WsZk%q#li7+NGva~# zP-d%Ln9;6C)7ue@HQru(vBukLuUg}kZh}^_*Iwu|TQ@;-kR9tFXc1dCL8I83$jXy# zkdK{?d~AEH@wOl2WBbRycE0N8syukkE+_oi<)`{^46J$~o%cB`ds`n-S(H|?{BydM zFZXe)Jj_-(nXU3OYx^mPAL?t{$G%%z@!@nUZp@T#>^r&@XD$Pk6Y*z;KlruVb7H~W zk>Ij}SD6K?4RV5aPKh*=fBA^H=F+dtYB`GYcqr>R*6fn2BQyTR|COKOChWj?4$p(( z4}QVrdheu=bS#Ocqj9# z4P%&3J-hD|hg2Iy#K{`dEV-KRrk@&dgT)xtvzJFe4wV z4JuY^4ZH2MJ}GI8pud^0(fY8|`nJ^iywt{mwE7!AYxOr~ZA`(BJ=Wmg9)r^AZ`QN1 zV^-3*Fs(6SGuK7ylPELBwPBSRKAE+?jWXMP9%aV3W*cioj=6AJAaj*Xug${a3o`f38Bcn& zUg3a!k#q6ox$fC_f+t;%EA#Z;>;(7i^~!woxP%E#dgP}0xaA1u?lq5?^>#%w7Ybcv zmK*vlb7qf8=K45SnH%hHVxAuHgt_>j}q#^RDY_ z9k1f3^p30Z83$IsVf!!Z`WuOM-D94f{u`rTpEJzu&TKI{BrusD&O2_Ld%uu*ROD@= zX`&G3Rt;Ync}JCG&h$lGk?+x7u2-AG@kPREgJV#J8!_=jj}7BF4#_vXGY0L=XdwNU zdJl|mf9=X#CHRc-CeAm^tIL{3`p7NJYsxG#rVT#My!pln^Hlu>%t6=hnme}jV{Y{L ztyxQEV_tF~o*dJ1Ea%mHTYOnD!%i+k&I57eh!NMhY$KCDGp8P?VWJFETU;@pmYU4` zOVWMj%y#RTb39#aZfW`h^Z4{Zrlas3=J?mW%(h-CZoNm%ccyKx;u$ZGw~xJrOJ&ndUd_dJoU{=-!%FZ7|DFs z=asSjk&11`+i^w6oK0N*3FqRA6!U(IM)_Y?h$nW&jpF(yJN(92@j9=8bmRG5BVRui zpLWep8Oz_#;q=WzcNqAF4bt#4Fl_M*7(U<&4ByBDT(5tcNaPLPa=(f5P%*{v-~JeL zXN}?##*aQ_)+&C~>4c+U>9}k^@0+qlx*0Fo=bme!##ec7^ZW%}jrVlSWtQHy=QUxE zJxian{G3~&4^qE7p>+J;@g9WVo3QGI_ahT*&DYF-)_aip-HE^VJqUHN z--$r?yB3!V11oY{w2Y}M$FI%8d?-;Dd41a*ZqxiT2g}^0zhTeXhe@tnYU>g_EW#( zV3}~lH_X>Fca>#>ZZOY@+fZ()n1RcaU`1J3r+pdb-m5dpwa@D_H~;3gS)ySV=B_X1 znuAXbVqTXli}^U0iph!{S$uN*s$#OIW)b6HD|Pq5t3#Agp@xd#_4<#EL@7G)v(JWS z6(Kq6GADUbUMz~I{#Tcod)UnDtJnez=^9$yrk ztlI9|uG@?}C;D>wxQsQ8?Wt8;FMD*@XWczj-!SOz7Ipmv!McC)^(k*4Vj7gbi5Av4DhUzG(j?7d?Np)nVI+|2RW~!q} zb!0A_>Y%gtUiG)B^Earv?DtszKHqwt3lVKf?vP^QN@H*Kvt(2XF`{WR=2WAO8$ZqL$-H31NTcec0OsoncRA`_ zQFXs`cdGMU+i*@_n7^<2=uIGV^V0{+EO&Y{x0;efmYvv=dC_NuWdF8;xohGY^4GX| znCC5TCkscZc1d5mzkEG=9hY;$uwdDFtzb_3AY6K0-N)m%ZcwPa-Z_nOQ7wKK|HuJ7w^<~-?nIvqY-V&M#-TaNpgD?}<|u>aC}x_Y44R{uX^s*!M={eJC1{Rfra4N`9K}p? zl%P4vfKQsE1kF**G)D=VqZ~-r$EnWOLqkN#rv=#lL9d~r&i;waH3sw%Uw4wsldEv0Em~DC#@y7*Em9gam>)UgiCvlfnD6xKh?k{!qf5J0_Ey{A_|c`Y{Xl|L8Np^5K!sO_cezbD%7-crkOkwO!=MT(_84KW-$Ggr}9TiF>!A zO#7f1^R*ngWky+p`AxcbvTdjzbNV%V%sKo0nX8rvGEX@InaA(=(Rpf-8t+*~=5ZwX zUXAx($5$}w?hR&}ilIx4Y_rvRz3tsCV^)A#_qW|nD~2sq^GWhr#l_wk71{o)6g9=Z zow=B|?eP!k;@{RzmOK9dW5!U>*KK4;9`cj%2^q;(T?=Mq@ z)={qGU%GbxtBw60%R@wslO6`@zH9qH@nXkf=G6Y3#M9dknLCxPE1GuADqwSLLkUsG zQGwZSPHGV?nlLACbN00fPg!Q?G3MD9o5>}c zlS`yO>*XU0*DuOEHbqWZxRcU{uim{dI~W}}J#nX%<^b;j%oT5xGac8}I6b^>Mog>c zYW#*pr8R>6l>T&PnPU{qGnnm*AH8L?9Hqu@s6>?lf}eZu_xliDKVXG&v#eyo^ypFpjTiJqkp2a_s|y=e9cqhbrCv5OoX zWt3{KG`4?%1CEhL)R;YdW4yC(A2nvrx9nwZEi+6YuYy>-`9*#&{M4X>v`Z2#=*%|=KYwQunC zxHzI^*S4IV{Z3v{J;+z_%Sxh1#RANSPP7u=g(YJC{+Pd*9ZOlUo!w*hKX1&A3kea+(iSw(>dVs(6nDRjX6}Bcn|Pi25_8J_EyRhM$pmal zEvzQ0JiaV-SXHBd!pV! z*7Z&&_tb90>B}k>k@vbenCG>vA_M1oF@F})OunpM_z z-ceC3U%xj&6qTrmB4Qv+i>RQ20h!)_2uPBggMc6?Ip+ZsFdzt+b7ERCqZpaq<{U9c z%sF7rdV8uoYn}Bz_xIO(?_JM2=W#8UpHrv0diP9yYwy}sUDJCq;m^XDu;tH~kaT+h zKPtX}l*{yo$eIq)F`?hIdhrTV%1nSKYg13hhjmf)>?ubYlP@;B%N`s+=klt2XV_Wf zPudBvHG!^WV+h|JYy%UkX05vkRLAQA(AB9V!dqceFa;zx(&U^FP_w|G&zI|98{uta$~nVz-Eu z_tm8MG%#I2X6i&DMlpC2K(YUA}||ow>*^(x&lw zq)i!XIGFnMu6Iw1?RHVkt~W1{6&6y>)|kZdUg^2y+Rxh$@)Hl!`22zplO7ggQ~A9_ zn*DKpFFV3JM~uY{BWaAW%{UCVe^MajdHs{|*P5Ng{)%&Xm}lrt_~|(bRzB!OG~4cH zA#U!iK>Bt-L?&MNSwnc8I2IpYY9%~J#S5FybVd1nb4Cuw3Fn3pZkVZyUo^%Oo`2#I z|LHKD3)f6t$UmEqLCP;VY4GmT3JL#yc-Tf;$iK_m(Rsj;^pW;3p zsFs@_XzcmRH^i&|lATqd<(d2Q`I*MF{#4t&{HILX&d|&6`42s5`+2Q8*k(`fyJq$v zlvq%EQfH3AAET(9u7&<+xu4p z-1xt|_Wj?@*Uwl{0F6gze12zc8cdi^<8!806ujxy#>)HuB+eC18c<&!c-tHlRjIG< zm#qmmRH(0?nQ?{fmPO<9;K9>bpJRXW=aa9C8)nmS;7hw$*}R3+*XP@X^E)0uYz>KgCY(1u#Z&NSJhQ)uKwAtvh2$sc8n7( z|J=Z_9`~u14?TF#Ds`uE{+>gc20 z@%ibtNcg^+YSuB$6;h+AW~bJe!`$&yvj*QZz$Tb#)|$D@ZaPRc8+xsrwfjUh`z-vD zxN$kv?3=NvGRrEe*&UKde%LOmSsVBL{B1j`*(vTSXkJA%8~03vjXkMmC1wt|Hjip{ zxqT=GXDflccRnsk!d+eVvU0u{pNCcleF;zABSABDmT308Z4oM5eN8mGTsaH7ESXLE zd8ET6>{5M`aB7M-Ivk^#UEEE#27zgR|VJHupd0=af**KKr$dUr|Ce+icL2 zFX=|(bM@3QHvZpfd_HEvP_~0E)oj4=_3WjoRI}9wKC*A;(zUbqoB{0JM)Pv_ylfyo z{!dQqyC3u@S0ne`@+KZmwb5AO?$&I09#ukYwtXgOc9s(1zw7kx{7=^GzcoIemsbG2 z>}Y)cu~QnXM;f2EON@aT49zn?Sl|aY4AhB6uB6(-t*JC0)ya7vU@*;BKg#P0oo#6z zd*dTmgdz@ zT9xpJ|K!`NvSqyVBGq+5>nFa{k>=-%opn(eXx@Iy<-vIWHyuwFZFE43yL1koo)Lgw z?P&hr`e`ig)TZkK(v~#rEu!o4LzMC{d(=2quKglU2`)K4kLZ2JdI`4n^Co&fpjm+T zUkxQ1St{(y9cZzD@NEBhT)mX~!Is=$JdvbAv^II9GisIhA-wPIP&{Zz_o|tm>xn}j z(A=8mLWqvr9C>6nmv=&<6-_Af_9b;%+5VvX-j?v_>nwa& zF@W&QB5!!wNXIU_7g6A){E9rIQfo4l-fASA-!~WZwoW1J>Qn^J^k0$B=kH_1-}#?B zZv0z)eS_fZJ#DD3KU|sy^A)MDPx%-L)g1NppQ2r1P!{#|5n1M798a}*{J92HO{Biw zTkA6W;u!Vyd_g(OD`kVcKX=KvAP!weef^xL*|M7z)YtoUj^HxpD3mp@# zK3BopgM!JmbCxk^C9xyC?5qR&?V{tr^i!eOr&^Je|9G2(3Hx`k@_TLCm4`pxc@VyO zQiA&LjEVMNcM@Bc>nw%6iJ{FOx4%VyQZ;=r^!r2l_U@IsBzbUxeb@Ni7F8;0^W zmpODt#|patq$uhMet~-i+{f_W-z2*oiQHoeavuP7ym}!*f8@ zG>7ozZbcBIOrPuTI{m|c?brIB{p7;;`2S}=`G2=LwfV{dc-Tbe)DLUYKy@9RQ)e1P zfwDH$>_M3;Bq&hLzErk=k_V$e-k*;z&;)!#*Svb{yuyBnrJ5bRV>)|b2aV6WeZM7+ zETNj+a41Z6cLmk#*Wsc35~V!SPHmlx*FH-%oBduH_eF$|^6kq^u-))6giU_fW6Qli zIY7G*>}b-Cl=qV*V$M?;(dmx&x!8Ve7~zpiB=|);nrQZSc@a(txk)s8rzs2TH%=#g z-Z~}@Yh_mme^Btn@FGo=KUa;aHSWJtp9+(OGo-&oC-?x6J*dcR>$htYPrRP}@^9XE0>qsmdB zJi&tSnRPzksGvo7VgERAIdqlS*-uzY)OkIFu=nyp=o#FZ@V`;BllJT~m49FVwmG$m z5T93g(D*z38f4BqCmgiq^r zfq^6FzV2f$Ua@hTqewZgwu9A?CKJBAJBelA(fGXQyZhqE1ghnWuEEXb->8;TbJh6C zb7_1&B5xW$!kPN(pr!ly3qz=`b*_Bndt^kAHvPEnc!~8O9MIJQpIoBjN#)_O_-wWz zDSsFlh(ph)67D3OgtE8S$#cC3O~<0U%L)JV&&Pfed%_)(CD>vzo#_2sjj-1xF_Gwf z>w$c{w_y}7{~V@u$-t>uiwW1QjKi1v=z4d0T@W&l+M~SAL}MrHeWx#Buhm0vW57tl z7bolCjW<-M)(3y`Qv<_E`JqFH`QZTxgq7A!=Sz3e`25mt9lp;v>c^e$Y;M+mOa1sY zj~4N)`XW+a%Qu!?okHXDC*QZQ+LNeHKWFxwJ;u>I!1p*Um>lUt>aQ&^g&kLc@cmB! zKH;W>zoz=YK2JJUsBMjg)t#S{XG};-fs?W=gj;NL95)s@ z9$zp2uK#W0hQ|B?7`lDyVAAt>c`XA&7-K^yZ<~P&f8DNhm^o+GL>vPKGaT|#4AVSl4~~= z9paZSrfcObY8~)OUJxlSZ|sk+XWJ5faeOQ;oKDAqrOU!FSENA7)2oxQW7!T?ZjW-e zd<@v{MEK_|3F@?}5bggwUx?$fXrB4OuM89y&n5kT)sh&zI{7|fS$9vos^1Oe?L_EU zVfjZ(!rN`Tp~uhhgyRq2=gZ4t2%9{e%lCdm<8wZ$J#TS>>UwaYqL^)^x^_u)WY3%A zllrj-x3e8~Bopo``OPX{4yMUL10m6|QCF8~Eg8lO*)roqI)G(K;1j)F^x zZ&>;F{fo{hb)&^4po zx$#)4KyzpcrGEI4rE5&9K8;5A(=?CWoMC{wua86dv&&Y0&}Gv{QY~NVw3M}INhjAHnk&4At3~JLzLM@RGL+8QgU$>G z<&nck9Z`T6bPw)Ictlt%-0`OSaPk8(VbRc9qS?cqh4A7@SHjfK7OTtc{Nr=~@%u;@ zIX?YYYPN$ApS%2t&wq7DgL~&`d>;Kh8Y&;r_rWbM_(02HO_28n$8cM?^|U|XsyC(( zmIZ{f9%;bT7UiRt;3DO1t}l~dRR27p_X!0O zv}!IPdOuT~k85;+Xr!1+$8|c(2%k`o!?NMm2*=zEL zHMhhyr8GW25ITj8GokUhYjh)9`;q!|qr{hNTo)Rjze&@ELk-@fO~teU;HU(Imz}hQ z{)znw&ouD`duL6;`nD5c*VQNFxm<3iKyAtBzA1ex4Pb25x(4eEzdB67p8k_y&vKJ4K1w1hsNj1HB(vtNi;t9+jU5+d5Mk>>M^rqDsgmt2(q8Te-_a(WZuLh z{3a_pCQSR@0iQeyByDz_XNuKF>A2K5*AXMC={WGrDI6nz{3JHJX{4aaoo$4>MdV|_ zRXf5u&m_pyUnB3DEm%;9s|?h5x&7(+8K`-ku9wxEnuyL@9+7h6Zyv(=Wx6P@leJ+O z-VYg0_*>UZ@mM*Q|T)%D5#p6ps- zzn#2Irg}GPd@_mf+|I(8Or@cOjqQ!$La+nj$C~!=>7$5npWVSQM^%OJ(~3ms_l_ra z>bK=WyYeu?9rKIe(CIt>L9_e+@xI>8s9l5nv;DWtsnZ(@;J{vER{rb~;hpZ>=09u4 zsZmgJiN4dl+tm&FjHU7UwVM{uTXz)5>n}N?1uBNrzhB*Vo!!|uiIi*jRk9vKsgEu@ z@=Dy|KsEd1?g-gy8P%-C2QPkGHI2{H9C!1BuF?3s*jo`b-_ZEnM$ZVFyvC9?k8HF> zw`v+=+!+^yvqPxwZnR0jul7fX{Tq~X(R*GZ;aG18Uimzi`0IB+ig5Y!CepW=@7cJ1 zToLK>t0a@rZsHljI&b~)wt8ox5jZDC?wA?jq1*bPimo$Z=HxeiyLklRt%tYp15#4&M9sQHn zsojj!{*{`|72@-)V`%=oZ^txnKS|^BGQVh8I+>oka?;luL~pb~-Ul+zi^1!t8Q~{= zL@?%f-LJ40rLKjBp$Z?iME#S-rLdL=u(eLCTlf%fe6zg|ZYxtFm(n$R!lkW2G^k|z!*VXXnVd~$zSuz-P!;aKBaDqkqZ376; z80dpzcWMz{p)wJ(Wpu7#)GZZzkD}-5EbO0$ImJP&{JBbWBv_xdiD-O?u;+Y@!EmB+ z6{Y~A?^qCBGzjmA^etORwKF>oqc!Pz*_3O6*iM_qY>+g82h)BW>?|1UHdNh`HYfa`W@8*#5{u6J??g?vk@^(}PHQGqpsPDef zpvSiA(Q#k{Gn*Z%lSS&34micm`#zcQyLU=p{WXN}X|vuC<3e)+!ww9GNe*<*p6KWX z{oHzzI_qP?q0ii(@(&cAZ3SXNa4mJ?`99_pV4z8&gWdH-}<5DAw$yd%79zYBbGp)t9MaK>7S&uEa> znKoA)JjPMYV#5XYMn7&Oqf$)IXMMPQ=yopOW(LU)<58eGin^(VsLF zZ5NFoyj8Oc4rA&3S1tD@zhvAbQXX}wlJDD>>a>f(bJ=-ss_RNU7xAF2RM(>}2eS8v z$ZavE>z1tMj{A2Y){Jlo5p}y2NS~AwL-z>loH|evLxvDb`P=h zdRZQv+Tu;0Wn~e}KYZ~&Xx8>$pxIvkO3mhNDF6eYF?sJZX#h?%CV#p(3OWv_F}Yc- z8?1Yx2lDnU3`;W8$e_7b0$^nvNxHeT*vH___{IGtn8Pu z?A%GJ*{7G>_`-`cCTCYP@jZj-8hWjw0={VsBiGKn(hqk9I}*M>70~;xDPa@WKoq@I zCG49s1*bnc&dO~IEYHE4^_hf4j08t!ONqZWHy6%04Ov6__Vcmlrclh=tn^+}vyNVVK~ZWX((mCn0mi*B;l?Wpz@=A>k7+co<*>Mz{dJQ1UxzEt#e2t7Etj1++PwWG z)w07X5nm##m&@C?En3LSA~OirOKLnUKfH#mMNp$&NYLaaAOPIyHfIeFvh*KCgl|#U2$B57vYYV zp7FkXG_5~#9iO}}mGI9qPQ1TPK4A^@$+DNinGy0f<5qCuKE{;0+fQJ-o}l^gPKLrB zq1AM(usraAeQ<-WyBSXC0jWFP$+Z)chr!SJ!wDNJxI*$5eZqTIg~Nya^!(u`zY?Kk z89g60=tK^fMx>JG`fX7JgOuO@UHfu#gg?a~{Qc)^-)P`JUi*LPUH+Z^b*6FXtO7W+ zna0~wT+(2&JB_zBiX!1^42`#M&2@oIQ+o;hKtbW_$ieWkW;EeNBh|sG+>daN!{^!M z`)Rzb;8env?Vx(!`fImX_XE{?LHYt&l^fN2|N2zE=Mfrj-&uB?UtB@s?cA!4X#FIB zv{|lghMDOs;qA|yu;FPR!V1w5IHc=0qF;m76ikZUM7Z=yK7M;Ng78K`*IgHs5?z;B z6r!_Nchb+j7Np~g9J=O}7#odaOka?4|1R#h(}w!WG>0MhZX5NXKbo{~uQ1P-Kl_u3 z*Z6NrafH7l%-}^!XuPc*d{fr0g8FEuhB&dse5zmd+6nBu!&JWkYxc9T7Bt>o`9uY- zmKyC~!*e=0Mal)s$Q7uQ8O5&jauqP~S0;VsSq*sYxUWp2x4 zjGlg)*gU6Q4zAre#F+NP8>q;xDmC!~wD_LG=>zIA~&@pr!swypr4>rvs?Dj#mYvmzYvtq3lk-}xW(yYgS4Uz>lte*eq_J`q6hl-qpK9OjZw&_uJ{KEx~k>72$-M?(oKg?&a3> zc+D=D8%4^+j_cUKW2uBce6(T97E_&miR&t^yi9$rq445HQXtiJgmW1`Z6Nj0tAfw) zvXaThqburU03UB{>L&|sTa>u0b z9w=|eZlfjUh0!&ps-@j=zoQ2!UzGKle>EeDaF?WYeEfbIS07au^RdD{82PnYVO?dl zm#MC8n5W`-LDWZEYm~7;mULfAk zpU$y4uW2mZ>{HAdUZOfJU$jHKRe@^REpn-BgDqtm=HOw0a4H2ZpJs&MAv2Er1R0?fWNjPM-c{DXO` zSrSX%S1!a)&-6*3?>8bH#~)ikc<6;FRGdWfOBPOU*vGXe%KLnlg9Um@M-jeMrio9! z(^%SX>t$ZNhWgXB$>n@SJE}+R{IjwyjZ~*=4wZ<#guQF>b^^jDv7;ktEdBP|A@;ct z2gu7+i#tHyVL^l)9ZjK!nl0hqDUL8=Uq8Yhox)+{54!dg(l-U-3$_uPLsIf#cQPG| zq&JITll6iB;EVqSnqA}ikJs$~&KEcC5qz;djincTOoM^GG?uP@8wI8>UXuR5z{nkz znb27JdEcQBe0v1Q``*4;UEur^FT(Neci2fwX)HbbQVm-kLu2VfHOlPiyM?4qX4}u^ zlDky1KE?L@Yk%sa&)IF|#{{R4I*&Gg<3mP75I*hP2M5H{+**yP7*&e~lJd9q{ zjj+;#csy%*p4eGll#TlLO9^`(EW!0Rz?Bo+p#-x(Q#WO>HqpUiMZJo z37ZTE!DzR3D6b#qGzN#vpzA&=VIu5OXHUu_`l(=t^}&R%{@%|oG@$cY!-p}vZZ_3s z@$U**pzv;(yd9&*DBjRYwd`@Wn6)`fHSS=2mgPLD&t2H7GgLnDC-u8jn?Z~cOZf6e zC#biixwX?U?bdyn^+evuGD(ufYRt9U#;RkCC^3NxBp(gnL zd7m0uuCl#N;z;>~_OsXnky(U8U7w5hdC{18{3ILMn!QxN7a4EipZGS3 zuk829Vx6Z1BFK?TIJ+B@k_HS94gFnBf6LuBW zo1S^n^9gtL7tSWVP1j|hDhIEbWb$(RH_e-ZyF-o>9ycctcT819d3o11z)rDr?WuE^ zA#Qv*mX!D2sDOPu>Dtqj++F<2-*hf)u*i$goSR4LWW`y_^qQ%DmDOH|KX_36Ze(V$ z8ew!U?DzI6`_O>;ZmR}OuzNs#xyUf30tN`3OU1f#LllTQ(;0P zM>yL`I7_z9oNxzq38Y$V{SW^4?!O>r4*kdb-@nJqfAO=j0ysZ}>Nj9`8oWD5W9Cwy zNO+?Bo|X6K>n<+f@_@$7+l~%`3*SeBy!^xxHCXhD#>_5u=h&sXbPoGeNy3hKlTGRj zxxQ6w*_mqAx@M(p>~PB6bFz5SyV@X#TwXtBh57>gkR+M4v0s2I}NQ<`8%Q1 zpL!-7l6@3@2S{FC9xz)hi>CU$W|PRiRi%E}^VU)J%Ht`d&VoCt@X(*mb6=GYfQ4^Z zQXW&`1Y@G9&s}O70aseT5j$%RrND^an+QKTnGXjZj3m73U6JscAbb9%*&l(PW91QaBbjxpVSoK+puys%@_(Zp|^73tk8L;T&0>WZ_;rE-$ z^$7nx_a*17`61+dn_o2rFkgetm)nBUz~kLoQs1B^67KY-zPp!_Cn#EX1Nm=wUiVSr z`)Ca%Y*Dkh`N9)#N|IyMjf zMX%L%JtKZ=L9d;&)R(pBG>Ft`TC$T@xO% za@#&@>BFHDdkK%u6~R@DD#D`{4F(q@AbcWm7-&?Y_^;n1o%`*KNY2BAvsI=ieI|8o z4($dsnQdtWE*>~43Pjfv1C_B?&LferNNLpUZQ zft}F9jPMNIkK*h&`nj#zvtaZ`Wh+vCqvWA1Za*z=>N1JHJ)72F*?t4>P)XZa@%T2c zp-S7I9Ib*E@B^{Ibzl#)?|PW9rc{K3!)Fsd;B0|gDvSxAE4M_iDnDZ9;iZ;1yr;cP z{=8dsgx#+rb$K~|e`AWrGja(Zbm@b`zHK0!;IEC(Tdop5@1lUJlYbL-Xt~Baf7U|z zwYj}F@}F$`5I*%Zi%&NjKsf$^CXaDL2+vCECL4LolJLRs+2W-PWxWnV+2ky9Qa)69 zHtV}bM0nd*85`N7C*jQv&)FYWI}+aCxg(6Ncu8zHw?Pjq1Cg-HF5$aYn@xDw9&`9~ zYY^eQt;0ZP)E4r*a$Dv4kpKJtVQjzY*jjnnD~F*tFy}j|Z`*SKGSY0)PU_)a!u^{F zTW{!u$96s?EdN*j-?Yspp4PJh`E~N^<>m7B=CXb_mj6Tv`6kI=Rfx|`CB>Z1ApqX^723J5dPCX;Xn5! zZTzu^@EH5oW!W+D*zOWh!ZitK z`)SCoR9-b%AneWau`%XTt5oZoUuVKYvnsy#B~xi@uLNLj9^rLt=1JW*MZkB}ul&`S z7o;mRy`U7k;+_fW+-l(*$M?c{j{V+Ra90ibLT}-BKc^XZaQ&{egR0BHIHxRz%S*n* zu6r4WnihrJi?AA2J3AAvR#$MJ8V%UN?+Q@UuZl|%PqWDq*5fOJYPr|%KgrJaE5hj& zb=*o>4Sz2#6Fu7Ia4+`WH(D=Sm|K!xIW83Ut_%eG2#%ST7d>{BZE|{@!c*8gOL_yBrWTsSW9}n(H;5@yUd0#S(AMBJ3 zvu;-~z2bZD9YlpNwQx4`=9R9j=%NJjd}0o$6F51TXU7_-U+ z?1YL8@N2GNe)*qar35T`u2dEygTsCCCvKV!LZ+NG>Dbb z7>u_EkJ%#lQXIx4xB9@`K|~rW%v{kbE#TwC4w>C)JM$ z5NtfKkWX_2si)m!cqKW@8wReFDp-ZV?i&hd(zjJQHqag3-|2xn=csdRt2NYo8H|pH zOgZQ*g4S#H*z4FBE{sTxeSOKkdKHD!)l#^qhTZJl!%5imq?lXup@coV zEE~PergJ)KUD?Bdg*bobY;J~@qBv7HKjceh4Yy@ey=<89yH}>+bzIdR2i|6MKI%=W z`n#M_x<;GktSoaLT#yy}m5wEr@j+mfM(9dCwWMEP{Cy>RY#mT>O(s-O~Xti&7- zPq4;M-BY=%9%C?}*aW%UQ0~PFUz}8{f!008a+WyO4I?tSUlj6(dOuEqa2x<+dENP^SbJ#YSK<|tjOC&7R@8^n!2r`4Br&&P+e zo!A-oriIz(O>!??eUh6R0}vDIfync;Ji z;dk*4w(ml9=9qa7eAmcl_YG_noo*a;V}cbyN`{aJ?DVl-j1Bd7Bx6@*AHQ57&kZc3F{Xz5fu&7 zxIX6_S+9G^n6kEn8_(sk>5e(rVb^rd-&(M7Yaw14QN>;Sw#25-2jLx|!W!#X7X00IVhW1!|Cc>;8$#l$H0P0E?>DL&VWFif2f>GsqKTag|jI8KFH+m z=CT;s$qd6z`f=)GgU~s;1NJ&OgtLxMz&?qG`F^jpIj%=GM&B&sRTkWm9==$J%loPD zwLSBspM|yB1MT~YbpzMbuilxDy_Q(BW|eg&uP3GBm!-?u4zDJOen?``{LmeC?ahOt zM~{5*vZ)5lJKll$xr4>b;{)JM!9Zr=MI-FK%K-*9x-&XXDyUu?3_l$b7|qWI`2{-@ zAh&BVleVye|9CSC%z|e!4+AgBjtb|BTXm^n6e26c>r*7a2;Rx=mZykNIGMuYmx8H}=_4%|863AJqnjHz@uypI?LXKW*wmo?t-V7@kd zST}|dw-e54JNT5v-};OyWI*T8MXc+^`y%h8Lg>__#ctD{CK~rt0@K58HII0;(j=%M zAEvGu&3h>Au6Gxu31hsJA7D`?ecUA)*eNghRoXYCp6CHTKkK6QwC>#0wqdZp`)~{h zw&oO{b%#6+5BxmDhb#R2i~aRG3=hqU=MITZvem<;;H^akT(w;t`*Cn4p0_IJo@H9H z<9_Ai#*j*`+rVP+bcqBL*U#Y!&-uu_)(N@$u6117FjL+zzW}$?)N%StXY)D2x##d&y0A?*K1+7@2?ki`x1h;KPW+O(?=rRwXSGvs1K6!TFiNFBr1#_0t2lE zF>RxbP|<2E*o8YWzUw;UwMu`O`68SNoc53p(T#!c)6N@7|_ej=aYcA~5 z6a4Au_3WIbsW5xb9A>zAD|<607B=TpGVgUdLY8G9L`*Daj-KiZR>PdYT)&Wcls+7E z>W0B>y~)h{1LI&_odN9X;LD6j42FQIDsX=IXeP-z4l=W@vbBnRnT6leK+R$m8*)I2 z=~|lytB!iHBjz3xDL*TMq$ADZzHiG#j%^aSpS8XD`$JXHn3aVvvtMUE?6s27K4ILw ztX;%UJkm~jqE9juUf9X^zCTU+$}k#M4SLC+Za5-cHOLp7Y&3D^M@8;pl08ILh;T|o zAMUqkFf3g?8okz9bCJ^SPyrt3km|!3CjVl)GvUZq$8${vC)pCKDR}B|0k>&aExUY7 zCeHRR=e~ptWk(8U-Cy;tqYLV|U+KR5x5PY5eOt>_ zzuwFbS(t+93#z%$(l@-rm?#{#at3$6wHro!9FGUbm2jumnd8b)*4S-*BDb*05nJc? z!%!VRu2>d?HmlmBP1-1KmU=v@v|i*pOwi}nC1>DsPMAcvam=Ft;I(5k)WJpNlh~Oj^OrGwsDED;7eAS`~Bs2;Xe|S^}!c zwamlkzr|j^3Sm!G9i#B3ip^-rgyr38n9(lR+3+)yz_IHrW^1G-gy{If%}rAom!76@ zQ8=eeuPu{tNnoK^&kS1nM>10kyx`l0t}xnj9MkXh1W3vIz+T%mm@#Qcgd``P4cMX0 zY-6&)D4~pv8~;cYGe+n?zTMdIoz{vXA4$uujWU!1WPM~6VIp3xX$aPZIxnr5ZLtSfNf@Pr41ry@Lk#mGd;R< z%EEi!n}qkiAHNvJ-L5qN%Y)-^cY6G+R!r0+9hr96HP-ZN|<;ULFa^=7K@Lg{f;Hm|6 z+=$GXyhT(zR}Qu6jJ)6_;|ydkeo0 zHQxp+lhZi-X@_c^8SJhX#%(q8MFupn{(u9QksOWw?O*W68%?=+i<9x`xE*}5gBsVj zBnN%JW%4?Qu1l}|D#XAOzh!e(7E0d>xm>SBip{3;`%6=Di*Tx4tGK2Am$g-Sx%h^Q zVT-?AHksBX6^}b@WH~-vv@j?JUuQmGr)+2zozC>frc<4T{Phpf^JNZr=B*KAAMeE^ zbhp5c7e>Limm`@07J9f--yQBw^JXMg3ixtv7zEkJGus}W_9Rklzjf8$j zlNd?aSSY?>2+!{aGG1l@uw{EExTs{yOn(>y1MKgyrP;6wivJfl_$S~i@Ke}8dJ=-R{d-D1vUu<_=I=<8gPL9+<_JuOX53z%bpBUVIp&wV`G7w4v z#lm+j=Hm3bfm#nwR4er7wx9US-cy-?5BDZ;-S-_}<31zGhTV274 zl6tWxeiaCD$!yM3UsL?^sstOR&*AE=>}9Syg|m~U)p0}0gLvouc^F?@%YFX2kDuB* z31g4W=6aVZq1YxA_hwAz#y0Aq%U(Ae(^ky&tg*nvuu(Yeaw1n1{3FYHdn zQ6)wUitBBeN+I32Wvv8#MYFTSrZcD+}s zVh(yAZ9XNuk8^K-4dXGI7jJl21jxysI>DATg0H+_1wBSsg7%8ZOrhI2Ff#28BPxBF zySl+JR;xYOZW+xaD8|8@Dc9JffWFL{)-IZ>!A)EaIQgI{ zexB>cmBt03*MJUKm1x7Q7S7-u@#Z=|a+W?<6_tSR~e z$f@K9l{Dw&sY%WD6{4(zDr=-?Vlr2fiBZNi>=mOJQOx03G~;fwA(PIF3c|dwyH{6u z<>uDGwg7pUk@V6q$U@xPA8!047-Mnh#O-|J#Jd~&H^=J*=& zE{BBQ1KVH4bR5*MulH{uUU^u{9DSnCeo-z2%b+@DNT=oODM>nv{awu@|9-}rZ;yu1 z?lTzQ!0vD<#{;tZ7BN{iRxsg=C5+lIk-6^Y0gBVR!;LeJ%rhY`k~roKdvl2iW2Ku4 zy@zdN*QzTqNln5Wt@n7A^V%!YkCnh)hf496stD1~5(y;VE0m3>m~SG>$cGL(w)~M# zmGzM;(}mc78PDwSk?O?7!H8{F_>rPb(&sk8Fup|v&l|jyURga3e(yEF(6?Q-1M< za8m-FiXR0Q;og4L+>A=;KIXRsuMeo>+#gx+yF>-(#nf?e1{{CtTPhxIH-`&te8zt{ z8ZG?p;0#W5rz?K=>WP_VCES_M=J@^fDBR8@aglnCSST_?^E-jug24f}WOFApKWEED z6~7ZI0yEd^)H+Qiqc?8r?t$VHEbQ}~%)SEM&Big2CUdzo$Re5r}>vzg>(ONB%4Y4?Aa{NRpT8~`EiacUOLHlE|{qEarhp_FU zQy3_etAf&_x1uv|oUr4)KH%1<%iI$3`HiK*dPT`l=J$!-xb2KH9Qf|aELZJ-X@x;> z^Gp;o&g>@NDRdH?+>yn6FRJH1+NDALzNt)mmk@r1W*(#`&14juih1dfFm)O0{9J))e3b_+=Uv!kzYmF~Ye?Yj+AZRd zOQwphKbAnJ_xGE_dnt?Nr5A#@pBCToc)vBym<=%>iuqz~Rq2V_Nf2hbo0okmlXiL@ z1z$V7;+uyal`iSz3;HRVc=)v@Ii7KVn(@!a|ur`TVQCu8}Se6G{jdF=PQ8MyIM8Fy*5HR~wM&tHfux$%Kz z;x-{BSIMsCmKr8D8+{difBL5oN8L5#*9*TX>D{A_dy~4J|6QAkFMX;x)7S6#@SsS{ z5La+bUktD~Z5+Wp>w(YT{|FoeGt$Q;Nq!o^BsLGjEuCQ{rH z&-Dz117#DLQLnG?--F`7&OVd;tX3%w{SkXv(f!mB4}< zHH@k5G4Zk!MKEQ49n)DjvoTXRv$3zNmf0H9#45)m!x4{aMrQt=-QpApQ-fwON@2QS zXfYmkd@p9^31_-iL_T=UDz%DrR<{#?5N=V^;^~ zq1v;VT+S<*xb9IA9`97c9UoC9v&b?nyqzkD1(sW4>fz)=6QH@8io-9A1PYOWw+S*H4wIJdvQ^fcrL=60knm zwg3;zAIuhORGSo5rK4oaGS+I>WRd>pSd49LWv`AqBsy}!7oYoRfOJrM#vcJKmzje2 zG{dAWXE3eE4iXg{8Q0%xsJ+n-rbJ9&4rtut`@D?-`wdx4+LC&{hd2$M#7tw>4DsS` zEy{z50kfDb1{-Be4+%u|pTm@7Xo*J){m14(Ei)}kpY>5K6waopV?MDJthI24XLe#O z)AC5hu9GD~LtZtL^SzDj+8PO3Z)P%`erUp$4L z2f8v(#-%J2X0%s=vl$l5fKLfvcHjW(cUhfz(KiPwzUH(3VV6W|Zbi^`>4i99Ri(&T z7#C|+J2ZD}?j&M17lQW8j(ow^kkwUJvO(3Zm{)b^Abs>I3AS7o_MfRwm7Xe%hPZvt z`7Gn}QqN>Bkd5eyFGgx`35nKlG1VMBzYOMfAL$3lagJyZ>cTD9qzbn(12Lp}0(WA` zU3P?eEP`P+H+;lewlOyi-}+4BemZ!wnX~fHZ1^nhLHRbZcSi}{>N|&v*{mk>6LLT{ zW9qm^t48sngZVf?tBy-s*}%)fQgKA*YK|@V#2<~EfEh=pb2G|&;I~EYIJ7FCtFRx5 zw!4R*zFH)=c$gQ?tn7*~&W;-cF{pC)0e_*Z0rybI9Ytm>;cMnRmp*tr#*6n%NzMHx4>YI%UQAOH=9bc1Z@*+3`+tx2+-$f>gez(Tp7Td$4{I_t5u@-%l?A+*XvO%u^}-r-fiI{1ncqD=^W5+WP;8RUjC!$!?>#vMmOh-u z+^87G+yBag<9%l{`&W&UH8e|LbhldOqwOv6_REI09W{*f*%@|1 z)MSX9RLS(5)Dc`10^#AssZ8v~{@_|?3*E-2FsS7K6^o4_*~f>udoLI+9%=_y(}ytK zXD5Kc{zGh+shyemn{(irZaQ1G@USRbRRYGBw~3!z4i-HVa-xUrD`ba_4NRW4=ECOn z;rycqYSNH`Bskb-FModTa%oy^7#tm?fI-pkr5Z&}a5t$ho*2`QGukx}l0Vv@bGNbF zy9eq}q~nLjU?SJHIRD&vmcI?TUg;;R3n!Bldp!wV@ z39cGe$1Qy|jGxd>@F^B`+^eEgp<4qWeqXk@#-;4iB7<5KF=@Z+#GyjbbIbia-8`))4= z^ZC7(OQjzqI6q@yvqY)0bcB#2*LUy8Mr<@Tu`S8OE_yZWRlQKr@fDNMPwfV)qJBg) z%-9|UhM4Pg$3_CdEGXSlV-hxw}bi}!R4hod|oLb2|S(76(7Jln$w=iEG+tMt){j>}m{zb@M3LQQ2}GB<$&8yOo1`4b zgCHvp-f6+R`WnR)*lO6wulJuPE#)HMl)+ctzv;P@>+Aw+Ee+7k&43FM_F*0$WR2sC z?YJs0Z8&wn8;3EGT=d{pRwFhRCoj(Dt|rfCZMSFO|DxzD9HM%@D6WViCJKrQf)Z~KP)ZbpohyxkfCz|`(%qd)O6MvDCd!W8 zV6pGo-CbDNiDG>1-~0Uw@OI|TIiGW`{$&NScNayts1F+_Od%v&3s>HB0G|aOWNL{V zuCNLaI*H=R{`Wk8z9Jqb-!3Ml1yOvCM>ZIAR+Ids7TI@OF)+VI5~Q_Sbd`$1SeO}( z-Hf7PF4?drq=}e(;c0=;LpthsEqNf3gM%gk;C{V~xUbOyrTq?YurZz7xkRCHt3IS% zTtIq-j=DQL2MhTD3$n^38pd3_M&&mtlM@>4=s_~(afqzejz!7cDJe{k_rX<4W%H0zGThQzVV zyw(&<)20hKI?5I{tAJ*v2TDzYSd+yII(%~&zL=TKo}64wA6BKJj&(VEGFO|9KA4BF zwT}I|_u0zquaL7n-NfGNsqkTL`S>SG!oK)5^BEm!xcfi@yJG!_uMdg9*ybu$mpB5) zZ1+S@>mv5#yb%@)nyKNbXtsaQY`kMW9{rkK*rl~Xp2+eCe{-20o8K=9Cyw32t8DAb zV$S4X-1a&AlT|yVvYldl$!5!3WJc028w&8%*=wTf2THY@H)W!CYZ3i6-GVcE9D}Nx z&(nRM_j08zzW6kGASAc(J~ocoDU$QgdKW$ zZ-;@MyEV~mkA&Racj>AWRbsO&9j=x%P*<0S-1`Ih&^mh{UA4M`oBT!awN|xs{*2>w zcUk2@q`VP-d*7C}=+!B(J#+(4zn4gd&I<*dw70ys(mm-`!DA{EJf@4~qgbxLIoR%) zin;YOnBGBEIAG$23V*!Wt?vKmhW!h1>$O-mOz#A3$c#guJq4^!at-yIl7Vvuma~}S z938tf50Ag8VV+TQMAh5H=+UQ9pYdbgu1n3`Xalr@@_DxZ{`n(4$*kVCCL$iRQDh`>#6a<*Sf!W2T{=;Jr16 zn-Istn)qX=GyFX5LVQFDxFcWz+)fH5Q(Nxxiw;GC_s>icxOF|R_A&)>D@%#VFn8Xe zBL{9nH97QUr)-Af|ovd7?=pb)$Md{_YmUYp9KkiSybcoJ+AS6K8)@! zN9m*GoZ25TILnW-Zk;iS^UE)Q!P*aHy`MkpB&KA;{izYWeCpk{*PoK0>(4fRf@+2| zP$L|shdtwi`|;9knm&-{J_M_i{z@CQ?O|-G4$f~M&wfT2!Me;DxJ+&adpLazz>PWR zzh@rX{PYjCaSy`HkumJ#%hS|#M=TcJ&1X-h*VDVF({a{|#q37kNz^Jo5C8V7WjD?3 zMJM)&(RFeoTM|?+vsfs`Lvtl;Q4sLq`MJ0$M#6m5R`TyAq@iU_BYWg_jUN>ijmOGs zS<=OR*qq^yo7R-G<}K=YDq}YO-5_R9L(R~&bsAda$Fa-noN%q(1e~wp!%izNK&w3p zn1^K$!x-pe?M5_)1%dOazf@CUDtVj{3;yrU z(6O$n#IiLVj4c~z>FplQPIz0FJkY0}dv|hHJH>Evwu`9S%a@Cb6obLmYT3{~t8|T< zb78cnh|hnY)b`so4HWvV;BzNCN?SKXLx;mve%%GBROygETnp%jM$WIKhQi!^SD3#m z9hI5O=V{sPJnGbPPp#FY<6<&KzMh}7ab3TuyKp-)5Y$Q_#`Bgy-C|Z zi&m!KO1DyWtl5+5m*-&2sA?v6twR*>vj7)OY+%JbLu4kx+hnGWguUA}g?EEIv#NzTuS3vwk2lUzD`hht5WMefgOa0Z%s}XH+i-9a zJ`V|GwO{9|TloOR0nFq@Htx0v;x*o#m43QZ zfS(qglm*t7NmsoS<2IYq*28@JNH+)O2K*fXM(&dVLaEfKthjeic) z9M39FBo~6|nLTvy^s`)s?L4$;7S4(!InqAS7H2-;;6R`TdH+h-v;2MrOd4-N?!6j| z4vnr5u)&86OaIQ>k6#2Ugfr*arky;^NP?C3i^z{v8T^pUEC_0=AWL!w@jY$A_cpkW zoQ=aywGU#r^0ARvFTEs^?Jj^D%Opf}K8F6DoDE(3nuxV;2Yo*+5sJ*~$(w{P)b7(F zFcMc1?F*yezvb@m@JA8xzBL*A-dln0#ANc;!4AGu>B8C*eq_U4Z_qw81U~875c|2| zP`s?0j%?K-OXHJapW_xfa%+Dw@Mks@UJIa$iqCRuuNOe|{o|tK%cWeQz!uS~S3BL$ z{-?`}@}c?tDE@Ha(@5$iPHG9agf(?jK4BtnRJc+< zV7t|&^gEY=9g|Dhry4KH;&SkhOEnAqxm`3)S&Z5L)idY7Pn|WwIr5+IT^%;I=ik}n z;-zyb$jHqPwajN(?+6@Db6fwo5DR>~r3Mbx5WD%wI z7^4;wE408#E9zuT5t&&PQYYk}Le6&m)=JjSSShQqG^ad`0S-TY%LEAIem> zg-ZX{i_vUhqG;;ANo~ve=isqE0o4B9FfQCH0hQhzq6xQFan1sJ^8LqO>b>V9XW8tG zgOxPFt$rd2$v4DF`Xbno2PDH>8Q&z$g%(GDvQ6$iANMu{T;nr{iI8x;U#0r=oeFgSFmUz$GeZw`a^N> zX-qwNb?qxPZCC{FsKEK$90_0d&V@W#39)#u2Pu9tVVG|w`SZaVjCe!nH#>}!Y;=Py z>Z&lP){W?O1;W;(fAmDiG_oNv2CTMUq-JXBWZkqhsBTkaci{_n|j*|-@-)@}t{s3P>*JT7L{K?Z0rh2pm(>8yD*Maffr zeB>Cy>Zk{13|-iuu7zkA_#eN&j$@;aBw^mj9sH<0KcuiN7u$2J_=Mprr8|BJ z+OVE=r}$NG+m1>3*k|Av>fzC>tK^Z2Q;gQq)z7QA(C%P#dD}yGUi`q7-E~IA!y1s@ zM~g@~LsZKafz;N4^zI*uCrrHIcSjiEQ*ZJ18Bt*CFDC14s`&W)49MwQMOM9gB9j;P zsf@hZKy+3|i#(SKUfog&S+pREZuHCs-`|a7sNorUd99GQdQ(G;J`Mn@+6B;eYZ=)y zUK{$mIY75_7Ww|h3f|nA45hPziH7`KIDJ_e)JHjybA};car+~!57H+lLf_}{HSP54 znZabnnk*Qil}0lZ?{L;*3P3;dhbSs#8J8rmKM}@Ht+v=r=1P_dJKe_JmQ8Cm(d{=r z2PS*_@jAOVwk^Mw0!dse|DYgU8Z|i_E|O=wcIg%AW$(H0&tDl+-VS4GUo0W?vl05d zG-l(u36OWd303snnC5wTNbT~&yE`J-^`fg(zd0I>J9F4SgB7&VF%A2Ama)i7wv?Nf zi^V%?*qL#mBI6dZpm#N~mHs`lF;)fmUf>*NI9Bmz@-pzz$wt<1`2~LFwix`OU&|J4 z>5n1ae)#o#8C%z`g^xEl;PmEf=AAbKe*_z0$(C?7yKD|dwvIt=uNzZ36^OTv{Nr7I zPi4JBVsX^HbG*l`F~S*@jxuuz|J(Gdbk(ptJfvX8I|sE(Csm7ab9S2SkY$9_ak&_$ z21JM+x60byPtQX+egYnJgo}1RECmMrdDXOb_(nz`b6iDESmSusyMJ4%l@1Lwu;Aiw#)R9NmRXdG^*>~dbCQ|k5 zuIONO0q6)Em*34`8n`DLOh!vc*YVACb!jpTkv5QR!H;RUS_JH~uOSJ82Eowf^I`A5 zGV)SM3kDfD!qfY?E8|Nqx{ua?1caN;sytK@Y?&GtpRL!`fj4jJf2A>y-T1_ER6Jp-BkdT9U}dd^<>U zOA}E3OCh_wwurtF-qMExD%i}G!|B4Td@NC_W3E+)t*?I&qi){@R`cXXXVDWeF7%YJ z{jI?3KLUUQBL6J=)Lf%q!^;nIuJlfoPS&h2ZmnT}D?-D|}7 zQ*)tc&X1mreu+XCK}-aV{5GE3J1!oTh8?BSpX<3>Hv_OHzb|Muz2Y8ko{i~I>hSON z2r}vUbi6ml6h`iuOitX;!WmT#aCEj4sXROweF}X*5*0+&9DL6II1>iLkEW2XgLd5;sCN#HwX z4;2LuA+9-DP!p9wW3N8ord`R0N45QFvHlvaR=CTKOk82DY-q*3dMfOby~fMl)&}WX zug!sqa~{0ZXGL3=d8*I_x0a6_lhn;$n7x1YL%)qLq=%-vz^|QZ z`0|euE3UABrHLlE_og9huF{5!z4ka~u_H^)8v@31KKP6eWZup%X?j=~>gc4fA?Nnc zl&6XKd|we;jal@UR~DYXT)`$~C{V>C0>kWE$I?iV^?iX$h#W6rB*T!uGd~aG6(#KR z`mOvZ<76zGUC$1N_ws6%!8mtj1!IZhP-5VU(|QY8QKd0%3A4l(u1W0nNP8T(TnER! z@n=UByixi4P&}yWz#?rz5e~fN!PtM;n?a7zG_s^c4Hr1Mz>#b(vdr{1Kk{4<$Xg|l+O0Bv*4cRQ z-cUsDcVzR~4p|__SCY=r?_{bj1rQloPrfhqu-+~3Pdm3X5go^&)U7rj_6qaT*3eRF z?UD(XLYqkW9i9%YjfX{~o~+UQN)3-Lg8S-K#Acx~l+K$A)(hTCu zi@@`q0aR@dC3afwFg|HCoE+^$9vg(fmU|!RrD|;=zL*S;v^LQ@BYt!9GIHU}XP}ps z?d0wW?>P06*`m>p95_qC`x>RXO{O%+O1H}*2h6>E`TmKg+U~U`L!|0v-to4unVhvxYovw&kefl!Dfp)O?x-Mpa(`C^kC&4kxnHb00vw;@FAnJjjTxJKd zfHyB`kX0BSvd>^oFG%T*fhm|@QOfehyVKnE9DKB)nk^Eq6@9S~{)ZUYJH_o#^up}q z;ZWW!PeLTZt{=hUnPjCyGUD}d-T(mZ)=cv6(+IpGbS;MN@*|u5KJZSBA+XRRnOvCA z&JRsV1dbGwFEJ^+^1&QhP>6LI%&&7bguR9ede9)~NkuT)V#_@wsT-w+#J_GVPs(7ZZ zFFiau4$}WS$=|-$A}yaD1bfZ@^2uS3rO|&}VW00<#Oq2-(q;iZb4}1}wh{9xng|-} z90e}Ig?;&~01j_`aoNdGW`FJu^>`bJynHr0REnBfcciMv#y!dWCbsrJT9VC&sN#OxCS>D0Le4CGJG8Dn2 z|4%NZzyXJKYk|%^buxR9G3InxLcQw@68TjXz5Bbt*XLeD-su;=WXM7|H!F@w=0LKaL{g)er?hvd<9%&K*KFCjVU{ITe0U)YM)8&xM&v zrznJO*pv-7e>V}o@a@$7Q4+YAH;|owUr^P|FaVosQr0pIF0Jr_3#O$+eHnrCr8Y3v zJ%iW}6nu~h1GrSXh@4$A7Z%DXLs+I0S@|s(j5qYq+(iZ?jD*} z+m9!}vRw!Gz~j}@Q~QG9@`_LV*IQSl`(Q3C%2h_y1Vz?oy$JUHG{D|yJ)we-fZ1Cc z-1y#}Ef_QmUjFn#t%e}x6Y!h{J`O{L6KQPijIA`uHW{^xN|;=G5OsW%jdJx>OiTNM zXx+gAeDXE#d}PN224N`!xO29`5R0UpzBxAp918=8hkA!s>Ct z`?jAdIpjJOQ##GzLYOHLJ=MUHL(cGeqzf7GRRKS}_JyAh77?o_kNC|qBH&J9HnB2a z%|mM{yw5Ks^oYB_W9Psy#cHzb(gE4}F9i^Dp`Ix1I%R$EofyuHkdWLGkhwB+VubR=TdBJJWt~k)^qC z;T)xv>@a8HF9u$_QFQEV3YXX^hTzYZvXNakbq8(AgWF$qc>M8Y<5ryvSiY}@&-hKG z`|abPO8q4NpnjS3wf;gdyZ@6P-1n~3aF9FLHjc*j-GkZf3D&S`&18J|RgZ~xaUgNA z#a&|90j8A4aUhk!?+Y<5iyCQaUQ#v&ec23BdRkE#f z`q0W>`KY_Hj(Ho6wg$n6T|KgiJ$Ae=a}@feuQo{7Sl>`SZdEo04VAEsN?ZA-vyyR_ zz%BP7Px<-V!g0?K;eH%87&rC!VCPoh?Wv}XZ`~d6zaKel+&c?AtzaVX$B`@;Tru5y z91f)(O!r0rCKdL@ZE@4s%-9&TK6;VoHOH~jm(%cY`%>Pv{JYfQK`xd@PUm~7_e;gO zVyxCLmUSD)NJ};f-JX8Fq8oRQw|RNz;o#kd)PJ$2ZsyW-{88UP-%dB-(sP9!8Mn?* zvHU7-#*`p5^Z83(n09d|p3K1|x?^A!6S8}kXP}Cr5kz0sC)TFA_@}`RGbQgauGzo^}6cdY+@%$Ab`;)V#k{mkMBTKa`fLG7z zi1XY7hdv7D$R0tb!bNXIhvpQ3+j3#H509l!b+SR}QxhrtwS(STD(r=w)j+~;Kd0iO zVUWDNn%v`uK;pE|{6317@b~j(Nd30Qz~`n5{L+MV($_|T zklx(~Lj#^jckg$F!|h{nSnF_>nP~|}(v8t(ry-lVMbJ6#+GA0y6LV}C4D*-zplZ@W z_H|Y_EeH$8-jFob?!ApFC<$lXUm+uAA3;l#voW+^6)R|cA{v}rfGq~~Z11YGhmQ#! zacpQ4Qyuh6c6LMoPFXGFGRCL!W;?P_?M4&pzhw^}{VEZU4QXJPY+m!1x0?zYt9l@xbM2kaGNTBf7Sc#f~sEmDjJ z4pfW8y=&TR*X3eat~EWI7Ond(HVt1`FQ;Bp?YNsSqj9{-6&lpCkvn7+fWM06U`fPt zuD;0ywJp^^Fk?uWh6UDknSg556jD7=3**K+!W;Ejr0~5WHf)&>wr>}a2mB+xpIrpp zSf5T@c5dPawI_pdVF{UdJc!SKm<>~+tBBozYqA_^0sNOzPj2rHx32#o2J^}$@?l+n z+I%@5t_eJe@qk?FZJY&E(Aek3bkJP0MEG#No@5_?N8kJkfh#?Np7v!pbnX)J55}cr zz-j{9#5SOBmr4Bli=d;;5U!jEA%6GW;YZ>q*kJBL6z(hp>%{-4-v?u2cOnj!?K?&% zI;oJZtPIc%siON0-g0SogwB7P3A8r-i1txcu?B~;J-R0J~ zaDKHtuNG6@w&ZduXsWH^JFH!$3sj@w-rno{lRlfJ9n<`wVY)p2-Thj6%4asbx~`7j z+LT$+&S_BSV}?^wj9G8R1W=B4!dX{lvqXU@-XgHYbs-@v&Ex?+IX)6I9%ismxi&g= zehN8`bI{^)6^k8sOk{qy05=?{XLxgOr+JSUO|~_$$n`_{303(xM$l1z z%`f8T>=ATSNfXMrs*vxZ_aL(T^e6*GkixF^+#PFT1_QL8_=K#$DyxL>1#w+pgcqL610BIwfF* z?soH3AMqIu`?KSwtu3111FPGvjm8e9HxE&N@RFpCWvnp(>?p2a$J(2 z!4xUc()H`PuD4>?JM_G@`~z!l+uH)T_3*H4TB3*U_lz7cI5&^4Ub&^sb4?1^1_}Eb zWr0%1tVnpV_a47*=Wb~VSpY|x1l?TYv-IRcCz$t56OC4?vNey*AeBtRxr$R+VfJ|F zdutX>_&0}1zRN?}F+c1#C7j7--=x)tqHyJ`Y^JhxHJw_YihBLZ*!j&)RBNHSi!cY)r?OvNGx3*?9;(*`u^!cV z=ypR1*Hk#Nv)Li|Z0`p??UVuYxtf5_qYv=St;5*H4?@rO5HUYl<&o5PTRsM&B0v1? zYN^WC|91r}?HrkJE)70WfJ2U+5jj_xwVl(-LF2azsP~Nny3aIH@VJYVnmh{QzMYG} zYt>zJW@tOtZR3k4{tW~}$ycuWmLs~+iC|YShD@)fN;m_R zvzo~E?!I(`;KyVNXP`w;HXY=W1@bH{66L zc|apH>5TMcT!QePj=T2MYQ&)Ly33~JL&}cPeD%r1wzG57Ao$sGK132P9s4C5Byvyq zc+<1eEq3!jyhI7Vd{tygP9m5YXejL3)MsZ#=tAf=JGADUSk9xt@G8m&RaOVF^P=Ze z{#6)yyJoWE2R6_V^(nYTQpP+EQ0i2ci!Bps*oufMkx`5oU+imSUPgyxYkP!Uzm-B4 z%G^M{Z*Mm4>u6%@wK{lhn?&ps?q7KQh5vnd5$^1%V7aeVae|O5-+8r=oqQy84~(?L z;l~r$q6!D>cUucpYkgTu#C)upKM2RV0}G}R*mLy}?-;4ge%?(+x%-Uofc`8^DF<)O z@aGTIoRc0qU4ZgCPRjyLmrGp)4aBU9Sr7WxUphiKU;AztN@FZLv@bMeVz_fLb&49n zjhm2wFTWn9H}h(_#q)zv?(1jjV0eYIil2*nW++3|2L&>76-A|I`q2Dbm+aG=BxKWO zLisWqveIe^UU`rs!|g<*m6%KsVsnKfr}V;Ka6@V&IUU<3F+Oqjo#~<3{yfH z$gS9CG($ZcEHBoOqj?HKrd-IUd@3g<7NtS6i5-qWk6g#8?b735;O(0B381zzdo zkPi4}w#IPyOD&1EZZwR_yiPB3N~E6OaUT-xgbuwC0J z%HQF|4P79H*Q1+cku?oE;+t6@ZcgGyH=0S;ImLqW*|YrS-h?+i{snSbUU6Z1}Wt0a<^whqrnY3@yEx9)m$ zeAR^ZM^4ZpN;UJMz~Ao{@4ohov?qEV z6b2|^d5{vL-z;FtA7czyZo%?$$HKyHS2VNdipR zxl_j8)M{bP2?ta-n##^>or&=cdYJjsi`86OfUIl)9=~bCeoc$V7sW^T2N(LYp3m8M z-!qW6+Pqs@wn2Ha)Yd{AhNOT89!uLIJD{J5!d!5{OxaP zkRW(EG^`)*Ab2`v`VGV*XoP70Eg{Dt{FXm_bfM&tkX_x_M2aRJpstS+ptrM@tk@?9 zt{MUGxnCK%psfo=tL?zHESdN}vxO6XbYT(oBm*S=ptz|_+o-8+a=^;-LIPC(v6ha|5b)*-5yw!7|affA5w>g2$UHVFmr=C zdhhlW)h2SPsBfm_VRVB z|46eub20USEnl{yRf?~~m}h>kv%ph9>aZjqoAQUyv0GDgk2(lFNhX4hv#F4q^e+@o z-g-szA|7&@HA0Sd#TYQm8%L&}H4*Y{7Vu()4GFLufmzo)A?$l7F>}AeD-MhjGERlW zZdEy-AoRd|O{^knKd#7nHWz^0*9J1;dA{hUkn`-7NQiD^1g%KShI3j?q`K<_y)#$n zFI!$i+zST6E{TxubtobI9rR(5KER7lab)W>C&)WJ0kXEZk~4pTpgi{%-7<+I!=EKV z@9gc=d+|3;^K&lTD>bJxwOcrC!Jm0D!QWc(>_^?AG5K)w(pcX2`tml98L9AU?^^z{ zZ-w+&YzU~m{=o0s@LW2+$OZa(sA1Xp@hsBE2&R?KKv{`BJCrm`(7?U$XnF*T8+ncH zPLD>dK}F11p@`n<%tUpyYNqkBUG)2R0bX-&WP2{Gko7oiS$FMAv+-_t; zjnDHTKV$IjFClm1KNuJDJ~%Y6nEgC!i003%(P2#tGoCXGsh$QFT$#n@v@OB|WncNN zkF^-Dkb*wfqgyXw3ffx#x>>P#X*EF^gp0GNjn9* zO{LURu7T6IvLjVS$MRM2Amx_kpwVDp(D(Rd|y8pe>eC*?wcr5 za`rq=?#96BUq$5LjWnK0vfw;c6SFq42`r@7uVuoL zvPKf0BWQKYqT#7;HCaD(80>iH1tv*FWVpQ%q%NNU+ICT-z}E#Pm#Km2TSs!$E(9D3 zKhh};nq}$TnLY-}xoQB)at>A6nKbGnVp48FFL;2I|OQk)B z^ibh<-D6i1u|#_>RkB~pWv2!T>}wzRHSQO8V3Gqi&eDeU@r1O$Ca5d2fz>K=h|6ms z4?V>X^4jCcp3%tH6~@E#OC{vJsUQDDL(p=+)DQ)Q*)r>0Vo06dMEZHY7I}CV!0ko} zNw2J>WIzT)Tx=lEKX*~nJrS_#UnQA&Lm9sGnG2s(#N>|hRJi=b9E83N(lyT=4jPPx z=zlZG)39&|cJ8LWcgK*sMnWfwm4sg2e3zTsrvT2y{u9md%i&5d3A%)irffrLl&<^X z91w4F`MnRMQlAcg7#7+OZw%|peE!+Oh=;nkqE4S(kI;q1VRm@0 z+nsIwD+ln|AD<3NV&8Whpns1iV9kzF_Uno(-F-a=-AZa%;UN{#nH$1Pp4lYK$$k0H zAM!D?P{PiSU&5amnvPD94eY$;Gd|KN9N)~UWUH5t#_RI#DALYn!7V(+;OytJ`~-w=LHS|3q>qnn<|0#jn8RzkN^^_zL3 z`JX1W%^8q`mwNr_KsPl`>KTt7KaoC(-@z$=T!8OA1_=8X*bO!9Ts2(CeRfb zMAE0ugMC|+1RrGv859%++aKJb@8n04eIql$QDHGn&^^!H5%v<&M`uNuMFE_0roar( zEtL%&eM@J&LpEsHMDt4r8%VR|;^3F>DgL+MDbEu;<=cX%jPDd!>}o+*5IDE%GGk^i zYXbPMa>9}E-t2_tPnx?>VBMCaG0#(5Y0IQ!JmkNaZ5v=pe~-;WliE7=?UsRc_-`?` zyl7%QLF)X%e|b1{mV_Ocv7W#7BL#mfu4nK3did*#A-M5UIV1hl@#Xi~*r}b(xL-4n zzc&R9F8ecGHE;ZScPL7(PiF_uMdRh>E4*IgFk!aI#KUI`_?d5xOBW3nbRM6bvU7QJ zqz`9^@#qQ&ctHa^YF!piy#+UMvDZV`*Yg*z_L-UJ!fZSRBYM-PFME`!O1Fl&6^ zH5r_)n32s}#^b7;vp`MPmyA~X!pjc~hVQ2{$To*IUgnYlU8I~W->Sop5cV`n2G)~D zAJwd`3YzwD6$#-FO`9JvVO2bGg9sRpFIb_S7h zCTXw`!IF4G*gRc0y%wQ6DItw0%lj)aTom`Qpz|Or} zA}aI~@U>o{f5YaW>}Ai&4OiD>!sB;Eyh_4sX^>4cME<mI>JKN2V*hE?{oR+J0+$D2sy?tN6LJQ2?JuOplE`$E8gK&VbB zBaN4|!SS#?oIaaEls4MHuM`5+o%4wN8b3%i>kpoOQ%K_Fc-U7Xqn;Y_q>pP3-0Sh7 z{Y`dod-n_7JH9hTNlcUbF;mDgUJy8gza!eL&!s~?spq{}v~;0&1k6Z%#Aha5m)g{N zz?@7K^spPn2G^KFM*dVR{ASJ4sz!m^8FyShViEgy<_S$d9*)P=@>%ZMM(P)zj@K7e zvYMAaM0TSKP~W$K^}V1c^Ex9&Hz8Bjw`VT@x;_V=RWvaTjl;ZTb^=b!u4Nr#<+0t_ zA9t@QWdS}Mo>*>+U+a>X&viR&?AAer?;cDqH~?jKa`doH z<{nqR+zp3JRt5KlF=V2V84kNO4X%6#Qg&=4mK_zkP}YZ#ugmZAinftpq#-6rL#p`~ zi!vZ^L=`z!{76=vCFICDg&8$9NaVa$3|ci3ve0!Qy?HAe?m9J*t3^ktTEBSM`J#q2 z{u=;FB@1Bni4wB*jvkc9&4ez81TycB1IV1UV5y!PxjHrovR414zE26+<&XrAcJHDG zML)S;YjYu`$eM1;U(1z!613ZC+pKHK`*1o71vbooByVn7(e~v`Dv0e@@lNig(t$Ri zu>Ig$-Ts*Ue##i0=v!iAk1adiI~?41&qF0HoUIDFN&mD*;kwE~ zb~dY&MmcAqb7vJBpm0(oe?{=S)f(Bt=~c3&f@Wp0LijzdjN>IEvvE|PCbsncY5wW1 zSRsp1!+zdZ#FOpwv7@_~-SRO&b#sb?dSaRD1ZSatP7@2~y08bQ7h=}t|M-wqI;=i1 z8O2sx`1{j)rJ)vi80}%iyDBV~eil5>z32LNiZ4BByY?Ut6RvAg`D0ACa=+jYoN1-^ zepho_HU;CL)1PSlomX7b(%E>dSRL*YP4d=b3U1A{g0e>rBv^AOK56!bkadyd#<O({DrD&JJNO^NJZ% z^UMp~z|Z z;6s}QP@Wn`igS+frdNcyVQvW#Cks2Q4rGJFni{gFJ4*IT;LN`Yx$L^g`=XnR3&2|N zc{5e2=+Tl47~Z#$?Av&cb_sjr$A?rAnd3-!t?CJKqlB(AnJL&gOo#N{VdR{L8$7R5 zg~dy4iTRQ+@U4D9)z~;8Ih`i#=4+<c%PO zg8O49zH@v(>A{(aa7m|w|98Aq`hW$%t@C|x%*4Oa(bo2GFG2@R-|8`?gB;ATw?&|N8qMqYc&fBhGZwYw_WoFSv|p_Ye`Ln&YZ#2ibXPQ~BTLzrl` z2io0K!N1FaRgM*A)ab{2sk15*ZAeEjZQ$<|-ja%@6ky)rUfC2;s&tu5$nY(&5Sa$f zZp#VJK{*v~y5iPIZl_!V9vDb%8;1q>0n8c zJtR+^OU}0le}fYNFjFm=Ozvpsk9a4-6s0oa+vUhRPRNCe$7;#3&Hr^?d?JRmOPk2L zsDbqD{(Ml$kdPz#%VuRvHHAYR z3&~jvPsmXn3C2y-EGOKL0dQ)2~=D*p0r=_Snt@OzB{o*zAcDPIDpteJ$dW=3q` zl8Las!4d1e%wt9K{?HLwL8!bil^t=|N#|80;olc!EGEa2{&zeV>u1-oDHm$2J--R_ z;)Ny_-a3k3JTo6}3i*2ZJ*)Xqb*Y#t^ex;R`kpU-6@t8F1+y(5haF>GahQG%BeyN_ zyOJ^183eLP8eTYM-f*-lvSh0UL}T%v>wHFr5{t{u#GM06c-ghnQok1k*tJC_TlvFF zYUL+n9-A6PH6bk;dmuO zuyQmd?!PtgVVg6ExBHNdLErf_fmuJYES)G^+{EA8nG7HIFD82j8}gw6d7yT_js)#q zd^klo;|~03B73fD(aC%spoN4?nYNKW%uazIk9v}>)=Tx~1jFR?a`MY^Jct!$!`E?H zq)Xiz-n32z^(B5p;kP$jFB<}zBBqfy@i8!}{UV(pHk3(2w5H zD!Ta6feR5>)=LTk%X%e2`|+qOaASEw_R>cBP(B6%8ZYyOCyz*_@!rrLI24C}8NzNl zTR}zn6pZjNXU0M5aB=r+d=RvNRW0~Lznu)m{wFipS=Ux-d?5u}i_4k!G7W0`IuD!e z>)GS95uLHZUFEDNbR#Gj^O44RcwxBkf9%-8zh97y>#oUo_{RUkv`lw!d+mos;c?blY^y-x{>f{u`0hzR^nYr|@RQ2WjA|vs&Pk+c;&HUKKK)UMyCyC!~ z`ZKj16vyI)5CGn+*f~@vX^Zgw=6a@O7%WWLq|UB+E@Aga2M7j71=e?mDZ9RHgK#)w z3M;)lfa%__5JnEB|Jwalu$tJx!m^We9(2?Vm|s+{++k!z4QIq>ckwA z;(l$E8fR#q`%euN+PlPNEplfaZ%1K={@YZudaP#4))io`ZkEdQa1bv*9meyQD();!?CB7SATPHAbE zAv}K`RogM^swXSg z4idV3zAZ2R>&G@vIV3cZo+sB?!mg z%9XS?^APRPJh~@bnMdwkPNzx49MDckCwC;aM!c2|1`*{(U8D zJY0@W)<0C%p)**gwBFq9WIxGu%y4#WhY4RcY`Wz3L6f~(XU*R}aF9BVdI8xFocOfg z+a;sj9x!|F7M^z{NUGX;Li{b#eH2FyN%fl7WJ$xHo6_E%zyJB;jcht2P50g}?)(}z z(|-pJ%RTLaFELTne(eJdvc3z)1_8JSMkqZe&e=> zeWly&-1zoer*PAS0+q5A?XQgJiT(NntA5tf9f`LMO+L77tALFb@FKxR*a$TtMfne?Avy-}Pg!DULHjcf+g3 z&CFl_kg#ZRCX6t3V4v^q6LK@#GvChhSld(Egd598vwKlSY+@&Sq1}ktEV65Nc1D;Y zEKagxQ&S3IymK!>tB*Si9DWo=hvz6QcW!0h?X=eqe^g`%7)bS=hoVSWIc8en^!xLzxpvt z8q}dByWM#Se|B)a^u?D$t@C=mitm&@>nx?a2)wy#_I~NEa;~`J0>y50s5GwdyWDd* z?QNj(xPC}5zU)YMz`Y5PEDwFbvrp~$RqcI}MpQ?>b?96^bD_WF{=k46O*P~RQFcQ^qaGb#}vZQ>65v4pdR}^X^1f3 ztR6owYBKAE76K@n^K&1UGNU~DKTFpHynn@ol^+ifR_Dyd`^j`SlxwhH@vNsDo<{37 zZnS5wQUUsv^so2rVZxKUVUWse?D?`lVUuMS#>QK))D>HW*#3sh zH_w3fRND%RN6e+?T}S3O6ohrD_H6amFEE7meW`Wb%-VJe2Hlx&lxLUtv94e8#g5CJBE&9W_)qBOOKYPQ3A*5@F{g`eV7zjT%`%Wf_C51kg$fbOQO zcgI0|=ceJ3Wt#ykYxz`O5@02*AFE)MbS6Dz#3m`@Vmx%DeVaP&yQK1~6TxJ?55H3z zEX~n+VREsU?tr=yDt+6ejn8&$<&BPE(&{Nkabpj6uC5j$<-RY(&axd3IlEW#Z{D42 zinDpdVjro%&xnV3jpo%mmrL9G&g0Xcw&#=j8B01-9eB7|CJvp}K|0;clm8Cbjjoz6 zR5Ne+@vp;P%0U4(D)jc}Hi0|D6JDRs8d!MoE#VGeS2ZeXkU5RVC#T>~TQ~OL;6dSH{%=@6 zXcb$Pw?{C%-jhunYt90udI@hcCa`F=k?ih|rNU?R1+1uAi@j)TBz(H+$j)fIhQLqS z!l7(W)+OH`7TkKIoYu;pt(X)q4(v8ZxkL14eJ`Alt({=t*nlm}HN^u`AaK1IcKr+MLZ1SlY{C)XCsd0BX+$mbg@x*2+ zMW&MDu> z`*b}hc@$P)%Y7?(ai2Ys#mYXstL_ZmS?MWl8Yptr&SCu0?8TBnjy2&ld40(k>5Gmt zpY!k;es$86Om1x93+`^h?sH_7$!ve#Z%Cy4?HZ`sRrv9Qb9cmLeO(6(yzI$8dTxh6 z!x_qO8#?2@H66BeeWV-_F`qk~(Po~Tw1pMZCUCQ3BiWwkhC*_Op8WY0bJiHWL|DG# z7rx!SihX=YcP>pmiK}P1F|7}Kgip7-Vfz7F**dy|@y!}HljJIY_GLnt@HD^>LcaUZ zzhpv%wh3`yoaV|}MI8{FzScry&T{s8?rvddYhC)s^mI0<(Opp4Gd8K&5H?68KaZKDo%{iGvJ{ymPZ)7IyOY2&30 ztGlsD*JtzSi8j*F4F%xUeKilx@|MQkj{?_)?%edlrxb!4cQX6su!%uDC>pC2e2IVPu@dz6p;kQd_c76cg^KlBl@OqPE zaNLx4^c8q~**s~A_Y&UDMV)^;F+$pTV?9685%J-s7Sh8B-n`rBMYzrJvdZt4Kkr*= zDvN#lsaj6)<8`$^#UU|m^=h*``1Pm*5Wdhsndo89kNnJnuW!|f*CX{|y;K8yM1Pa4;*2+cg z{8*=jA;KP$L1H|eo!&<8`;!YS;pz!**8D)IFe&0L*spP6qjm=iF&WL-`Hf52tJnac zexj1Kyf}$!Ay*+cc{1BqHjq`*I)l@MWz1lg8XLZLsPLx3g}Gk34bzJi!VbFEH|*_9 zaHRiLNgw=KO}Dn9_+NXa5A848G`0n+_4bQOZt9KXnkl5`+o6F-YDN$k#wUi1{=UXS7#eaEw?OOu4iG41)VUGvz@lGVbOZy9JG>A*_q zjI*!$F5ErVlU=&APr#^T*)-LU4d`}AuFkEZP*!COY|=UgmKJI*WSw5YH1(_DZO%Yp z%|f~d@6iQ#6keuG9p%eTH;jaq!=jXFv{%chP~9Xt=0Ck|g}!Xlu|7DYPi*Y_)J?3w z6l@v}RnDuI7KI!mO>5jb?i(9*Z?^wT9 zN<01v=BqhzSLf~0yvM%qz2g>cu_8#)NWUP)^z`Q~HXM>V`NqhfNBHxpw2rENVhbu4 zZsEi49FoG$zeHD8CqDRYko0<2Ti&{E0Y9eLAx(HhXXP7=d7mea(ziBrme8;_x4vp7 zO)<0O;ls;N6{aiscy8imQ_kWwhaal9_kDTVq5kOcJVZ5x=5NKoW5!1xCC6GU_vH~; zL*YcqBR#eFjr_v>b8xI}m@-MZl3%p?3yF_^E60YI@zY)VG91@m7+E)zpF1hCaXx0k z<^vkseDXr}^sA!~ZT=MZuA*2h-60I~+<>pYZ(&glL4sfuBG0k$XRr7nVRn`*-p`}E zcxXNR)$bi}%h!{wusbAJl)ZsptsR+dry!wxSvz*1>wMs}PRH1F&D%QE@Pe>N~2pjghF@wYtuwg=;GGoeC<~O`EBs&HwGimQ+u1QE@ zcS)tU@QDxWJ9<2xaQQFxb)YK?5wGC-n@3e&w=8FuE$h)Sty0y)a~ivIU6=K9muNy?8~U!HcQ6p`4sYh^tqw_R3_jxF!)s~3)IRCkkPh5@s1?5;Y?Jr_ zeSUq@IKHrYwPf984quqnm9Ka)NxJU2noq0yj%TxbNWBib^FPBPv4wV)Dlu^@uXx`I zzckyS3Z}aj46jz3e6`*aJ9eNCPY<33N_91*r}YMIAAb|R%s-=?n6!+aKGlr9eo(K} zTRepioHCFWX$J{Ltpu*wY!X|qKS%I+(1KsfT|)b6Tm)5cBKA~sVcvrS1h1F#ae|{a z+dU{)2uU`S6VRXCv?I5$Vj9UfWeX?l3GZNKJW*b5z1yKXK_>XV2w3(l*86-$}H zp%z?yu9{>%b`o=crsQUqhf1>VKqe2K!cElXN@Z!y*vGTWc!vsCX}<0)SVeoGOVxKt z>VDI~qMHwIb0b(vYO5wzWYON61EEsGmzLNgc`H9c=X~4p!`NPO=Vwhqq;BEgQ4zYD zhpPojKB}(Voz3Afn|!7BfH6>A7&V-0=W9 zt-q%99=Djc^J>L*B&ZAhH70U@v%xI*^$0=ZyDo1(XBxwldBTkNdTeL2oaq_62|96C z(A&e6jsLVu_-Ql&hu`yI$>R?QbWv;K(sF-x`U%xD7M-AR)>d|9S(vb3)(O}Z?ZymW z9uzvp{{T0I9qVtlR|uZhgQZWL#mZd0h2?w3v({@yu_-n-!qw_|tVduwwj_SM@bk9= z)3tpIk5ui2UhCu_JxEVfquwxxPXI3Txe7c(%ZYzyld&CM$&mFvOf2R@@=J~r4y6;vKi~mxc)9{>BjB9 z@JVAOU+>`|8R(yf!OJ!(~aTwS)Y*Q(df_88uyH*^i#X?azxr zL&9Pbb+_=VKYUAo`gzydA})nZ@#+6o6Fjrn)|5iCc0tk6HQ z7f;_clT9ACSg4NwgKaL`GLINfVQl;vG`hEmZFAitsHgSC^3T5P!M-j{_AGh^*0Z5AeU z0oKiHD0|Rhk#OPeLT3544b$0dAQawkW}zuh;Ms#V!nw{~?7jUu@aTG1`D3j=+vgf2 zb{%Y_EKc`hT3sH=cv1gs<`hplgA;(xhb>jX*Bn^o#tb|g`a~sNna2z&+wuKh+eyo3 zk7wnlNAbM_jikA`-Py>)vuI6hsq`YI7;a3n6xUH1#+L%daVa}MKbF>ei@-0;QntT=2Cb{ydiw{VV*BY>Gr{z4QlFp?L z@6YdaoW^rHxl4DgCvvwxgLvVJ1yW4VVt)TmOWtMHC@HPwdVX$05~|H^DP?7P@yFv= z;BFqTiaYMlSFW>_-K0UP4_-<-^Wzm{$0!GnUpO<1YS6W8+97d}DxyHsWM z6Ix?P=)k&7>?pjfH00N`3|PcyV+uZ|; zH)=w_0dE$qVFemi7nR!{`!kz;L&f+$-Ia4X`>~gLHFCkxA+cW^Jy`XvL-<*>L1l4& z4NJ|)L4z*uRMi<4%-ypy|9P^D)DSj?o$;XaV`D)2x~3C5cf^w4Zf`3^ul@=}i|qNv zoUKxQ?}HHi+=Ii}KxxG9-{LhBKmKfIh}88Yli3}*6L@==6ghn%E}HJm54eU(iz8*U ze7T;NO$wG&qttoA$tAqQi~woX0)d~EO?mUf8>AIUQ#gAvfZxxykP@|QxJI95{8{c` zNws$a?|=RVCZBCknNRTHPhU(y_9{lDq%-s{e2Nk~M72?c#BSxWyES0Yen-9ibY|0v zMZt*9{>oIN)!e;2AI>cJqU`m4HjmZsM*IA`3mcXCyfJee3mj%D#GKOMBZ91$#!)-r z_Sg?NJbf+e`^8@v9kLfw6E?Gs*87CpHE-qf$NgB@_YmRwcMtJ-ApOsS&W{ZBUkwpK zUTnbdP(h>gAw1ZzjxD;pUr=^z%{pZ+V%BSS3ZwoT%-pvz7H_s*FwLLFt_{|u{ZzAs zTYNbiwXhBb#3+TQcU;+<37291p}$JUPd?1udmL<^bX+-u-c9}OeN1vDmFo>0x|M0> zbj1y(;jwRR-I)D@Xq;rcN7YPP#cEsq!Xu&osmfB#*{i}HyrV^LY5Mh%OddIbAL%wl zQoPq@qc+axr@PxrJ!{j!(A1Id`cCJ7>b67TaZlbyElAp3oFK0Lm9;dZ#{Bh{!``kMEQ z+%sYgRKEOMe?54Sd|l6d)+X+48ViO6<9XseCEWPmpJE)x4hxglszYjO#Y45U&)meM`^hYkt8A!*S6g(EZE7$mfMrp3740=6`4yI`9?f-U$x zfrTG+5N>Iivq#^1vXcv^3wo_rG10aJ4BPe-22^cg|4lg!uZ#L=jVeetpvDGV>yH*XV%1c$6C#SRY zsr`6|mjk4B4~MWf3BY^4qqC)B+OVVj7V%59PLkHD$8booj>jbLklOk=La?b9Pnot~ z%1GTQ>TdDp9lsxv4EjEozb5+eRkT0+al+HRyy$8Df^_16Ycp_ zaUQ>ZW}8&La5OhMX~f;e*-QEDXY(`Ao!2@{k>aB5_(+Q)d~~yyq}9ru=i^bVY{*f~ z_ua~^hO|TXTf0=+Kj}`1sz)ZFX_2w6K0e%M4}-mVrFusiHtjpwW^Cz3a%&ID_=#vOV9a z$im>#&XNcH19lYs3)b1=jcVB z7aOLg*d&CHx{h;SZD2pLcL*jWYw_VCFV-_TSkTU{Of<=*8g)^qP#aMx8V~Sec1Oa5 zXsbX-kKW9>Y@>btIj`Xc-J>_nmF_})(Fntv06>?=))wB!rZqE%~IyOjl6+%|#%c zd)pm{GjY#xIq`g*ln8$xU&e`qeKhnP6ch(zJCfNrstEKt&%^b^f6|}|G;TD<|44`K z4;w+tX1tt0Ja=6bEbDm4geLv1QW`;T{RHtm*=QMA1zTG+gDUE`Sxgb=+^_@#qE#mE zz=vYmlX%*kPK5b$F2hj5p1Bwe9@S4Fj@ms>ctM#*HguqVyJwDoL+*dz7xla6!9DSy zPaQlU{=hs#lRv5J{l=z4E zXFDnQ+OLoAjU{?#zj}1uaaoQgY>Gx1Mzm1kswV8wTvSDF#KnYN|KT}49CI9fh(F5s zDjI#hi-qJj78HUz7QDp^ggxxM1lzk6pdVrT_SM1(`IXp@uy=K zOa(tf^p^ZIaqYHROd_oPc0*{bQ-Vhb8+TwE{F#x3Z>e21A_g4iKE|eVBa z(U$0013rMhNg(DB&+9fnplsbtyh_*(v{u(K=dbKZ?OoIqbocoHc{b_XnZ`|!%@X5k z(x>`SBg94(?39Q8P;@m5YzW(G)>x=BErBL`7cYJ)#=NTqbE3z{M@-JlRj}PeSJ!#U zX}=rbGGXH$Y2n87N|;O7zIjV<#jJvV{pzG1!Vsr7(2@9mL|ntP-E4=8JQ*b{Ohb)T1V8WUd(;Q1@p_}9sr-Wl0Yx?F**j2~u zaOK$Vs83k!$6c_icLfe4Y~T7oxqfQ{GU8XiVs5f*rGiH_VSnEh)%Vrmdcw9HGK~Ib z@dpPHwp{Xryvl5BMcC5BXt?_ADHc;c=cOb<&w-b51!0$d$N-h`0dyp+e5Mc#M=rpg zg#C5*FRT|^;b-EpaBGCZ!Sm%Z!mf5wuwAK>?wu!|BT0?$`oTD{CCx3ZqN-qHtOBY@ z&Vz^|2>NXabEx0e#TmeQ(wRnT_xgDc+N)gw6=Az-o&b*_&mo`aB_VELppy$biN|M& z9(?Lo2GI9pQv2us4%~gaM!`-Jf8f`1@|~IWkVJHno)RxsmqI1+A2{KT z-P3aZ(U$oq@XPLJ|FG?^Bx3W?mm!k)Z@Rz3*CxRbMs)LAML1->CCnzQ+1n}{Wz-<{ zpuQZwHsZy0BgKzI7pN)d3~pcfAo15Nr#V@tLS91jx%^_x$exMK2z%>XCXVz7!U4o@ zN}s52JiLUji2mw%66c#e#eKxjm0oxz@oJ^I{GJl?Vtmk`!Y@0vWSst&so|3!zB z_wKAw@MNM-#2*)vpVi|o;yTeiG*x##kxF(S7kP%y@GU{Rz8pWg#qM);OHn)64$C;dpfnBW&*@jd16}boow`{%aL%wM+ip zGZe?|yb*@Y9Vc27J!nrARP<>ElL+gxxClJjSV1Q7UwHHm`ljxO1d?BNj6+D-1qdPj zv>9i?+BzAWh#o#_7cAZT2|f|_uk%#U(fJ8Fgw5SoDMngW!(_thyqG91Ki3FNeci$@ ziCYaQw}>`5n<}^6T?-z>qp^N8TGf=mbIQZl$G2c?Vm2g_%=R;nV>^1Lw;}%5C+^@H zuXyk$dTx0d8k#?UV--J-DtC5BRjj?Zp4}L?Nn8UVwfi=g-@B=y`iTni6*3d5-tLU%-CE zZ?fzx{xM6&DMW9#+=cTzKB1C$9%oF&pVdF`G3h^7`>(unMm0VsnYs?9^1ySA_=b3# zcYHP}9HZb92)kJ?RSXZV#S_#nYK(>g%|AGk`t|R%1qNni<7~nvj6V)Oub<-<;zql|7Z9YykCOR&y3fRkf@h$NWm{JT~e$EDW;$MF%6CP~|g1N-A?Il9$yNi%d z^zi|wVRGRU=tlIOk$xcb{R&O_IoVDhirN%TZjJ51$D;pk)}g3Q7k*;?MPo#|cO7Ko-&W=u;+rl;WC8_l#rk0;xdf9-w)bQdthWe&bfJ73?_bcI|W};@LxhY(e+;S*iaoK zM-b2TQ)PJ4yg$Ye_Sw*Hn0sskj;8ht`Y$oe?kFB6{`Q08@kYTNOd`5lKq$t1N&olk zMsFMJdnF$u2`g1-V|iR9&L?cr0w3A+a|0eD{tta4Os3CP@JmELX?P+!eX7N#8q!WS zfPml<%q46)~*%GT1=9R()i`FvANdOPn$YLBh7Nevc1q_8}u4 zp$*4(;TJKH=%AQWSY?@l&q?N3=7ZJcU$LHSeA#a}c7Of{+fuu3>}^^5TpeyB{=ey( ziA$F&_&uWgBt(dlS~budMDHN>y&=e@9FqyVIAtB2F8GGN)NYe@1Ts&)#2dsvrb_~h zufB${M2|cA26EjFVLs^=ce?;O^kB%+&dse&we=T#7Pe5WEfXf+Rpl1#mTOqiw$f(Jw&w|W38b0kD5o#9#R{0nhio1}Q|>M5SSy`w{SsczXGLLt|4HXisuBwJ*ieBSWF7rpi4~ix0P_ zinEEoe?J93&_!KLCpx*Uf_tWQmTwcitW7PJ^nNcl+5Wz|1ZM?~#-i z?cFB7qPxK(v1u$U*nS5uN5!Lpe7j$W#^>hG{=L7v_S%M5t+UXWuvJGG)=vM06A3$N z*k9RUQZ+6mZ0BDK|9UoJBYS)8cX_A35VL#SffTa-}M-$fV@MZCyvm+QivyS zfiHXZ{&aItL_BO#4{nh9B-fN z1wKSK|5=YE(h+ey$-hFi(z^!{_nO|nHukK?2TS8*Yihr9vlIus5-@=Hcm2#kvvKao ziGCgP9BsB7$Nj`JZ^Bj7eRdaZ2RU=K8q3 zTu!v@Y6Y_>h%|2UNn9%ZBjx*8(TC)O?yG|Fy_&&R$}zJ=MG!a43Wn0VSlhwx!0L4{ z)DZ3Fp9m|rTn1y3^Xk$GFunc^nrczaTsPR#kON%_>l~s7+o<+-CjO}%&x;S1)Wch< z`IR@bCe%~i|ADZ6i7~Rx&U!E-`fF!BTs*w&A5Wi#P3U8m3u%NMwv)~#o_h|Lnq*qs z!>+fkK+}6riDw2D-#Y+Jb<{_zA}lkof}12C?5eQsRW+DL^w}$ocr9;|=s`TsdnvWqJ00&5f4MHL|Bnp(_g zjR{-#aVy47_=;@^`=Qe)oH6MS<}_i?p)8~)Ys zA9Z`c=ZbPHARgWRjbTD^vCFl}Q&s$!fg6q*Jq;bmY>3)D=F}f z`pWgZgRAbwLjvhAI+dP#hmXJplH<}R8z)}%h9r`6=gKdfe_4cRT2pfQQH2!`>cs&> zr&l(he~q_zndGFcQ}8X{I^SDMa*X#iV2gHp<)-(z#KOP$HB%kukUw)8eqcq(R0LYD zn6W4e&!66go+PKg@e913b_^p)j$Q`6VXVFJ?>)=PG#bma>Ax{OzcYU{7tp7_E}qzn>ONElG9;X zxtQTtjRLhteVqWkjDDjF@jut_gt##|XhbsAhDE~DxK|iK?F%Meg(;bLF_QSLk3I(Z z^%)E&IinjsK+D^Ea3i&^Z&n1Wqvv5Y@ps1xdcW(8P3t*rr%^p+dQm<{?JKPm%=~X` z;&1Zj0jdqMi>8<~t)C3bY=oEI`r;6JrZ`@&f(1t##oiPny}Tkg(#{fG*3lSWl?jgr z?guBzE3YF68zx_Zv*hQas#EZ2VG1;@Kg>|`0q54)aFBSO&m93-7yp3Tddk~NDE{)R zgL5RaWP_tgFUsR(#DB?hk8Bd$@UND5%e!EVUj+;%Z0hUPxT5uUxJuXq?h&{|?KONR z-+uGIfvL&2Adj$r*1STWwUID|^e;M^hx>cjLjkQZwwzmm{9HG1ccJ=ZUIVV~8!D=i z?fq$Ojkj%{D3XotavjFI+>{+CALgX~!4Ex#<8#8UP0Yq+&AiZz=nA7}80r&^UC3AK z_Fu;3>k`qHu#r!LadW44c!t_PR#;-isUmz${C}UR;Z64{Y|>wFn<;BwXv9t=fB2Cq zlfV%QK98`>_nT;LUxSsTPv0+-;G60vRuJ}y#cmkV{1fVsf7%#Hu&C8T{7cx&Egpg8 z?^tY4*x5Fpq1Ef1xQ4LT`uv922xBy)zHGYHf}zI;nG^QuCc^anST$f7CG=EIK~} zbJD@Ri#rUf&4C~%swIXgp>Sjww05L17<5VOZ&MG36c^vu!N#Lp70lmT`t z?dZD(7U$<-68X7>@-T=&Y5(SgW?OE;=~p)~neJoOw zyh=DZy#s0yJ>gRW-A}kvenfuAqGze0?eN4!ecn z_J$Tyv%!|~q4F<->J7i>-VGam+Oq`=cdi0mYNr!$V#1CFXe50Cp7b%1oE0pI^l3b0 zEq7be2sg-|R$YI|ol>je7}?&>#1LmsFM(V;`bN{k6+`EJgRyJqy(uUZ3-#Z?2=cSu ziwn52oc~*gH_pG0FSnhCj=od_KYxp}FCK)cZ?8%2PPJwK)Q`O(i!jmsK5_IXBo%KiF&l=OEwyx|CD&pOu?IKGYilb z_jgtB0+P8{Jw?3#t`<|spTFz}!r4`27(hDA{jmbZEzZaJB*$9}f-XAmF_rw8HTo>L zUP{J|WMe_mT^K1`MNP8t{PI_jy*d(`;+r-p2mapQjAx18aL8{kP?+F5k~8;L74+z# zz#C*ce?k8&hTU@0_p&*ZS2ar~CjO;-=$+mO-Mxp2M&xs4SQR8uEsftM2b?a%q)<=@B+|M)F%Yxu2e|%0p+5M{o)Rr31cR^aO)2M^o&(GxPlyBde zf<`@h91+nUV3KI3zXzT`6e!1XJ*r2fj46!JK)ho$|FXF}WvGwqdd|T|) z++-)M;oKp6FYG)nn?0z9{>1amWgvQ;E`vyGn$yO*;>c~^;6B;j@aqWb=e~r##BUyQ z2kW=T!z1!ftJQCD)#?yfPdU)2UWC0(7J%a-vQfPX$GEnJF_gnc?Hlpt-ZkP*%7G>H z56zWYFA@tWpRety!D8cYa_~}G>;C!^&B7<+mnHO0wBr*-Xzc#y+X2!;Tz^o7Z^%aD zcd@v-@*%DypV#f(juQ*N;CA9K{?8Ci?Mv_->2Q2Wy8Jw$7N3y(u-fFrdUFNOA?!5U z4dURx4LFbVnQqz<9vN5SM8a-yu!R7Fd^Dn%rn-f}qtodaMS0tJH69jjy@O3UmnEmd z*9L94ebpT$Zd*uz0QQi8d6|mdSLU zS{xyok#0#7tKbW32^F)b{)ZwMK7Ro?FQoeI!bf`(EAw)?Uncn;;&A5+L%^9wSp==nRVHSFwD1yf1ScXda^ zS%XO@Z+b^NvB5-lfr9NInf7zc<^G!*VGr?KR{t%(Xh2wS&yEUtf10#hvMSrf7z z2h98r=F<4Gi3!1;C*Q&wvdjPJIlOr?3I38@r9m7^zg_@Ssza{Vzs2)c4#HrH`-HMQ zJQQUQ-z+GO7Nt07>2NsT)PAc5mk;_bZX+9w{2I|PWU1&yacQ?m!9Of-p7@By>FkDj ztgwre&#$2Mz}|n+ZkRUSo=f(g`++$+GckTXt<%3+t9Id`z)yIV#zN}}RygZ*5yp|d)dAhG+5HM^Lw(hD zy(cGrtiv{BP;Ma(Dz-+C9SF_;^MkmbfR3{-+v(Z@iM$kaz2e- z4r*NsusP*J#-%`TpZo!bk&S0(pMn14pP)PC&mgM=(22YD?>mBVMJlvcM4?3UK&fXA zuuh)%itHLV^fx3(BA%gfw=kg!UOP3%D6-Kgr~#7K9F%|1SkqggVDFs05>HZ0=h1q; z&FXPtA?42DCgn9H#QS*S8lX4+~u-lgo1&!;akV$h$TLHxtv31al{CUBCnaM6%&rhaUhwqM* zSN3Xv8j7!?urDq@UJlDB53hc5#LrXn0GsBnwTE%d`ZQ?1oz@|PZ{lnBoA8UqUBvrz z{8bVPNtFL{_ZMKs*=6vUm{|0z5vNhCM_9Ii zHT$ZtlCXmc=fVliVq8nH9vDN6x>F+h{m;sp@QA;&q;hlx#xv6|36{k>BThXY^s8j zL)9US@*(kO5vX6B3(cu^x^pxW27d{Hra5g@H-y+dm%xXfBUVl)z>U_}-HCtXF*m4> z%7yEs!{S$iL4H#TuW8OqT5(4#eq0AV$i@+}mdU~Sv<^UV8UFFK{QhM(FB9f6!FZYR!*A(@&|OOW3Ym?%=rmc!;AsF-m`nW5$I*BaKrGEX4ZG zi=dYLcGL1N8tQ7nb;`GoH1EFO?YMwjMmBuxjO7;HgvsgxSOrQ#TyFbJ@(oH>a2j1EF1-%ICC7592?%#NU z#*|*oS9!ya8cd>`_jdoAxPJiU5Y>|r@7Ibgj2dwv#eKw?cA($(FMcQNQKzMl`M3b@ zP~G*iTL=vL_!b=~=L6v}8 zJLRp@dHU{l{j6+4HV&DjVD1%X6W7srY4e~Fd=E_)htvE&en}O??^1^oWTVZ_BDng~ z3LGdd*CIZ_8P{E~iSlQa>r;p{JPA#;`sRh#;k|qtGH4z%e|ZGb3txg2&Ht+{{Age8 z*MIfEuCLQz+=!nLK;tf~sx6Ef{ug>tUhVI5N?dih9!`)xzE8K9l+m}q{-n?5$yTym zcq2R@|96Qil*8B6z+dvG+R;&XJp2#*rsv=`l>-)-pys#?+G)Ycg`*Ucg z^8m)uTy#wDK598%fD-cg(d4&iGbaS5k(`o>|8TcAgdrLPZ`U84lr2c=^#_N2MdWr>3C9??AUCfT@aSOacxjFN3>e0@Cg7l)~9;wF;0bMH@F zY(R{eEWj3DI^TiU%t3K+l@U2=DPNaC9H@b_?@mEnM8=28*?4*%`wxq+H6T9(B zpHDc0#)9@_YaE$Vi2cd`_f30a#G7(_Nc?ZuLwSx^hpoxR2_YJ?&_ThQ)}k$@H5Uav z1sBQ2G4CFWWvmYKX?zvl>IeI5%W){_+3);fXscC->NJkth3|n2)*o>^**LlU6xer2 z!HFa@t7igS$hn3O$wmi7hVl&L6yZ_utx6)3-pu?!r ze`~+5Pb7#}!s;N7Y{|Ls!`Ojp8h?^+bt+oUE~^J8dcJ7d_eF7YIhc}6?*d1B`0hWL zLHwP+M&g6EuON8+umi#Z=-@llIV@ z^vphTg+SQerQ%(Q0xnYL|YH?FehO_cv}RpMWxr&D5kXIQ-#uw4hvC zeJ2_7AH^W2XMszl3ackR#P<~Iap?hQJnS>-ki7?bo1${oFPuZUoe-NZ513Jdjf7pN z(OlN0XMG#;ZO_ij#S3nYSWfw)R?r51$uyUd4nva`z}}2PtfjfS|Cj?{T9AP`gcWCB zfxQRs;VjC5gKb~Jz&}UPkH+b%t=~W|e*?avd9ud34Ay4q;YEr|TitpHkBgJdC^ycV zD%gf8s>Dd@SB>g_w;Pj0FY>eQr7CFON(~NB`t>TZ#+8Pb;oUjq$y)o!QIareq<0J-14Hy&902@NQ3vo24@}l#vBh#keKpP?Y+ldS@=JPuKTbK;amak} z!{J7>rC2x|ZVA)-R-rZ7uJg)@YT+WhM7er$OfabLc!y)i-gEaa!@$0YSU^0}yT5>_ z;m0wOa$wZ%TsSq#4WCiYTVE>$7xlroonrAVs}7tK;^j|-&6uKKF00NbDoE#Bv_IB& z&qVPw>9CFV+bjuHgFN!Xsk24!q~l!BA*>~Q25-#(u%Q@Zl4X%%8K(yepnMr>8#BwCVulDMs0Bm+LD~T`(I)9;7IhM_FC7w*ed2KUME}T zJwAg^UOmQ56ua*e0`c^$5BQMePs?43Go}=vI`td#Sr^rwmtoU>h6~qH6KyK=fTE!lh!o!!2J_)TT_HB@E9>)p z7ZmjWgvUv@%d1X-=JphHp}wxx+=1%x@t8(-UH$eFx;;CBqbYAM^!f^xqx~_Ma-&Q7 z5Ab)Nj$J8-TXgzM^?X}AMsh5uE^D>nn7oDZ^8tO6f97JB=t#bGr@TsgBZ@PKzI~$# z{zuYPhgJ17;j3bIV`F3e6bls2U|@^gVz*#77K*4y3!-9RAPOiT0wUZqNJxqb5~3g? zAl=>Hd+zt&Jp0VNXLfcrXLipDKN%71kTM{jn(?=v;i#8yLn1XDFsD7hYKD&YnAUnWOpNFVrk`ya3PrJ{bZDS|~e!e&70}r0}mbyZA zV6S)%X=g*)DBpZKhiAXoL{YF?``RjQ?cIr_*qnT3Gk^NHQ!oI&&n#Ks@PNPayYPXr zC3T$0DPkpLgHwz6aGe(4!?)blrSQTuW43_~9p;6wVT?0(MIF~HdBJ1cLwPM^z1|qJ z`O_3d+$Y~i;BSFNJR5cF|LUhWJF||*!EQ^!Sw3QcEHDK8?=~D00;hir$NHl%L;oo!J*yvmF4S6;pY-?Mx4g^C03@eRn9F3+S|Z+-3z z{GUTB==`lA91Ph(u-^v*2XQajr2zBlo_1U1BY`sj{qo!aO+kuZYz@ab?!{(dBW!YX zem*%R>(WTnch{^WI?~RZLcud}yGYB8-q0KPSo^__RE+bVVJP2MbdIj=`9p4yon-wV zrCu$iaL~&>eh@ZUHz;C!vSnShb|EiNim7c3yDk3JY9i^3dh(urJXfWXTHsqsv-a}0 zTUm-c?S(kAG(Pf`4nfc3>hC#T$(vHq7GGb)a+jlabP=-OZ2$4n#XD&&WcvhHa(G@Z zMV{wAZ_Mdyj0F#TOT>E5=&P073bJ!#4VC`*>1`n-I94KZ0p%#F|Qt8z&|1DbD~nrUth~oto%Z! z{^FI+vOrbvd-a|o{K#qM8KCDbs27IxsbzQY%sjb-N@Mf68nW>|wJ?vkT z>U3s(_+hWMkvMyIWDUr^`2x?aUo<|&TgPP9X^VWAse_*rd`}x zluPk(*RWBpnUz0G5~ zBu?oXs5{g>QtW2Ek~TB zw!pDoRE${COezBYL*-glcd8YnoV3Ii&HOCngzy76j2K_$!{GrJKt~2PaYp)8(F&Na z<7$vg)g&4~wy|e1s~BnWCSaNxrSk#zQ@j^A2UNcCsZ;n5H2BxW2XNPM9xVC)f4NTV znj6Ye?!nB5X8g%6iEo2nPh&f)bk62^z_Cyr$@Zhl75Uf`3qFg{&+GX-aQtHXiJ##! zZ6MntC|v8^JXxR=`;)iv5LA^L*#kb{`Vi-2kJ;TrkI|Kd*g z)+r-LnztyD)qt~n=6f2^^p2&x3!Cg{DwzC`Z=yW$Xe#n=uks)8d%Vx5HpxpAIlZwK zRn)<(t71*E_-!M#dhRH`0KXQ-|DBpw!LV<^)sUK1R}onDP}60+H!R5&2LoL-{bEA=opuFW7Rw{7x< z2dsAGGi8Dvw8ft@JU!_Nc;tKH`P@3ZSpeC{7P%bzbG^d%=Dw(Ayv;+>9Cz|`Gwa%} z5&}TKm>>)6WmF-Ta`gw|tazkTy0{&(++4`}e#~Nb@K^`_cOc^l|YkwI*J{gq-a znAX*aFWY_MdyswD_A2WhPvw=6-M$L{`EoDj&fq_;{8==4SI?6`w^?N`k4JvjLC{-w z8VUL_P5cb9HjdqKK32sVko`|%J0-TsW+|`3qRftRr^m9CkNUUNn?}s`RpjwrEdENb zKiKno$UZaAB5h$WOSu;JS0T?XvM)<#xtgX;q~vi^lyV3)5m))6KS90_^TI9UaHj82 z7uJHd46UJ4CQU*ta88ZPr{4RQDRQy&2PfeTLUWR0@z(hw%};nuGr|8M&yoK8iy$e- z?9Jr!lv|ai$f^&e#(Eu{#2_mzKuaOy$>?S^c2zgb$H^<>(r;E(BNF1FjzL>)oD z%k0Cek5`f!z8hAyn>Et2NCsMYojqTj`i-RfEGo}@*v7<%dV=3&?l=B3)n1X0eccbS zzw>)28Q=Q3zmngt?MqT_+aH4_Zf|BLNI8Vgn`MEshR>7NgSJ21z)wjo27s=&DCPdb ze{2ZZb)ElkRlD;%53*YE5nR~`@jUP(y?@Q#ZJ0AaUmI!8`^P3JVm%WlF6Y#$JeKZy zbTn=fmw&5aDMwC4b-Eafb37@}Aa%sO@VMfx0WS49Mzsj8{@{~#m2MGX8)6`^Dp;zVAMO%&Zo9apua9OI*vmSngjL6Hm8D{~9|y^~EJfir!M zGSR|H`VRc@1D^?F>>3sO@kh@(YKdEA+R>2RcH^?>f_!W(&|8Ds@_VOhS`7YyA-a5L zNxtH4)Y(rrcvfRFNptbx2`_lk!%%Vne~}Q#svF$s73jrx5_rrFOT`${?sGQBHS7I< z4|1@Q4{zy9?||9QwUKW$ISP`Gbw?b2fmosG3%c5;iOW;2h*B=S`qgS)FK@@k!5`l* zpAS7>rtpEjzR9eiagz<9!|A!9?0EMDp8>y8nJZ`A4`fLnS7l4?otD7%;0Yg~$Js4% zSju(mey$Jiv8ZHAU@rahNc5*Y-U^(pt~aUba577CVp9ueTALTb^C3I5Dv7&$zGL%2KgEhRr zj5b4d!KFM>Lkw4%Uk0ls(&bkcB;}%vJ1wVK``pO~^k(lzWce(L9zs@(K1qYbbj4jc z&`Rb|L= zj=ubtEK$BuVTz*5YQ+`Mv8{sU$~Kfvi=RLLO~0PjRQ_%dKQqI(L)D zf#<&cM|Mec;bhRuEuV4gkTC88Iz06<4|Mv?Qa-Al)nrbMF5&0Ed3P#U{5!gV_kgGG zkG=BM>tulmpi_UD3iFRQvDA-xFX~IxyDIr7>bU&tUK)8Mi+iHH?UcLp&gv`Mfd3HV z{@)I7MgIS^JF%p{!A_CqZ_qEB5^}e(2V`SzRZ;J(u8Me*Np=(6+;>)#zS|3H_(^`P zC=Qt+T@>umEVI#^n;Y{wtq^^RLFH!cmnYZ3vAgW;7$jJ7TWpLY!Y^zFbMB z-g(>xXJ3(*Zc(WD4{in>JKBZ1-VEXwpr0NKCEHIg*jI{S;hf*j)r4>140B6#A+>uv zR}t^%Ii!vzibdicl&6fr8L!eXaU^I4ZF_Q<(0VKSQEV+m)s_pi5&Ozl1(a{Lh#s!T zIJO{}Y<*1eOcv}g`6I>Ru9nXR%mpi*C@1?9>8?W`sWPUGi76B@5B=`OE=p_oM-MsbC3hZT6yvZc`Jy`*B#K$ib-0eQ;qFiqz-agGaMwb^Levwj23$9I~939N> zH|pu(z7%2JVzdR$F!iTQ5H!~yo@NQIHn8JZeaQ@R}5p}65;7gFTN^4J9M})_58(p0F2yghtW@g5B&GLiz zcyAZ3hCPLT@jS@RhBvRmm^LAUt6h$9-=$b5OfTje-HDrkQ%^MAC-Chida zRFnbphLtQ(C(mEL7?|m6a2N1cS0NFYEfIe{Xe|mafZ4jPl7l<u`b{``Cj-N%36)_?eQyay*`*cfLYkth8LVh>>ikR z&mQIWIFD8a|DX?AoN&6BR2Cr)(%6Pmk!#W#w1(GXal;m@1Htocjfeb}txVehn2E!C z3GK0eJP6FW$$>(4U;||X(@IAf|InzUqu~D&r%Tgv^T`T0nRATj@zgY01v+=oJ&N}D zN^QZ@c9S~=tP`mPFpqo;CXF$#XbLcIN5#|7JJ!?*<$Xdk=-s{}lnVa-?~2Lhj3)Jk z&vbZHLnkd;Qy?(Eoo%9dE)Rr};2C#Uradv{xt1UF$wG{4qmQ!K3z$Eh8>p!%NL&ca zg%2tzb7w!^xeROLr}=cI{c`>QOq00ZB+D}5g`nHa_)0SWd%P2v0YBvA`p2DZfEn@O zB^?|V!d-w_G1Qu=F$y^sYClrZU*K;wV8CTsF=^dC*zfss6$i@7X!1=z#MPgpN$VxvJ?FC=ZX~^v?iZ5 z-~)rLu5kQ;-)s+j`z`nRtUunu!gp63_TZqEa_qx#=4=_lZkjK-kA!(7fu}yR;@R-A zw`((bhw337kG>E&v4lTFXz(v!2G!MY(Uq1w40H+dBInP#BW?wz_CwrxI$$Q>0?aa; zzm3QrCX}qjxOWKmqF#pydx2Rzxsv_U29PZXlyfQk04ggcRNS_ZmXHpU{Q#Yt{@QD(V z>^3Av#`)uG={GP93v9$0QB7n6%qjCP%BMNXw7+0%d2665e4dHB6Ttj8D^hS<)zbb}yOnks2Q6BTrpTwSTc^CLc*}tIKwW0h0IJI9bD8?;OktZ{9 z-~k%FHH-Jc=4%H{qZvO-I1REo=8eK0{aW@1ro-J^f@W*v=AvBlgq7B2_@_Gfb#jbE zy~WKu0QMYcKY+VxRq|q#+aB1?g;v?z7j4vb?M?2Z^ON^O)^xNhd-M$Ack`m#ruNXe~ckNf^WYVS(g4`tX7TV%O-de2K4Z|IRBsdmVAMe z9f*5g*P=+$KP&w#kNpql+rXJ+t<5H%i)bcz{K|ieH#O>M6=Wazf056;D$`zx@?Qay z1&;|hX9xeNP0fO#RxL@kt-hvCowk(FCFrnem#w#PJJ!JRx3nCk3 zSK1=gw|63W`{Q0bWH({|ZvSNkJ%a3p(i+-7p(S+yf1)aKKdw#}bU-Iy4LNdp2hkp~ zhI{Mjx$-YDUHa~f5?VJygQuc=oM#&OEWgC(z`t0GAg|^pydU&|2oD-r6u`$p_uq4$ zzC8HCk05K<(TMC-)3`0{aHnQ5g&i#5MBt3F=}BELR`C(&CWP*f<^`A)4I-FzoeQQfxoK7d`>!3$bW$uoM_1DFaPi@ zV5+sY=Z~FZ`5k0qonCY2Z_L|3-{~L3=X<;IQP4-HeCM_;ZTSjtt|tBE(_fBr0qFiq zig}=tz?H!Cy^K5iyIOMqFl|mYvF@LHVh&`@Y-NER0`26-K+6y#Hn$oq_z1>JAB_J;Jz&rB>l5*h#8Q&hJgt8ei4k+_Xee}6 z*?d;?FleUvkloN|6tMrLO#2crA6jk@TKsD!U6fx7`6J}@ucvs(ZcG?Ms;Ol(6_|?+ zw$qSn*>n))`(jM#@w{Y(FI8TCN?&x5uM62g<@e+r<&FQOBTr8+ie6ScriUoc*7`-o zUe~DwaK^38CHwFVv<-B(X%*CvHI$x9`p4JP@sK#d5qj42m1#S*))w3#+w?@HU3qVm z+yt0m?Qs{i?50?V@?pDcDQtD4I8DM_S3<8G)!7a-Az^HC z4#?&|ab&M=ktBm|cc+=M(Ys{&hVOngT**V4^JqBc_iWF$++DSXMBudiY%W?RH_=@1 z=qkO?T>l(n3S=!r7vaz6Mk)dR?4HAESi1_E0a=Hyhsa`BCM^T4mUEkw)V|Xd;OJj) zrNGx8sXK6LoC0a+Yd87^oFdgYia&2h70_+r@W14C<&+|?IIw#$#r7vU44f}`+h^z@ zC7KTU>9Z#C@wzR{2Ie!Y&0?B2X+41sdxzsbv6{Nr3Yg0p>gghX6F;Kdu4M(8Y7FN> z@b`a^LnU#WS;{@m?EDkCF*kW4=ns!@SGDs~RsxT%oj3KI^Pamv_NMk@T9y&T8L)rK z7ZY0Z^%qNXblicp)MIcS4~4Axm4TGqqms=)cYhrsm{~V)DR3Ti?k5z?mj#-EKX8Sc zy#9tPa2o2kv*d~Rc~lcSLr?u~9r^snYW4$9w^AKG@V1aOfwR>AJeP0%!-qhxS$UV2 zV}Nr4rqwlfp4L|62IzKDJ%qpAf623evvXPkC-=5yec&&BnaTIt8L%q&i&~ZP({@vN z7jQI7YPn-bxwr-NuT9PD+SyRt0v^X_vcL>AwSaxV?1sDW)@OGL0_t0mRL6~fvjlaN zt4}ZES1%^uO+|cn+&}jIy@%|9W1^JAF9i!)4|;Z|PuyY83zGWFW@}H*Pzj(&=(8>5 zJ}(r$&~;$0ZFhy0UjC+zsIT&WOSood0gZrcxOaEHA5cYcpf7HHBL>+vDlnbulH^@Z z%CzIapS+=^P=xzwBY~;$-B$>j(MYdRce~HM$>F~$%9d=Xvz(S($fq~J3Gu&5$E{PT zH}+*Wk=x+r^BHf8U@W@nMLgpJT?D_bJd8^AKBq&#nXd7J>`lxl9Qcz}vMGH0PVzuq zmSvRD+9zXZFmSxb*OS?*-@-J|RMt$xGL{J{z|4Lm)2>Zv2uO#mH2O8u+OgNgEvT=> z<60`2S0~;;xf|y8gnR1T6a2%(4BE05Z$tp+aF=+x_{@gefga-&L{m1qupHkF{rZ~r z+B46E?Dg0?Bu+#u0GOXwpQFx0()lFxZ=*4ro}MaF`19*_?dWj-8rB8Qp6&O9vj>`3 z+LQKt+)jA0UKS|%*z@m;#r#&Xz;VD?uic7!CD!nJl#7p7^7-mKpkDDfBY$Z$TNn(Fn=F75D( zHFB@h7|05?L7aNXMKKnob;13hPC;agHuBH0;AKvTKY=zIu$G@q%cDJzT_$VC3kKHE z9>|_PVIj8s(nJL)kMS5UAAcWr9if9>+8kkFSDCgUWV=sF6qMZS=_T~(YB7Quzm-!J z>f#xyM@D;cC>^q~;!Vo?mrQ$s8B+g*mODp~H_EsF_9Yo&GdbYbpAkjMT^#XFG47jW z{G^u)Z;<4x^_4kPWU+}f@ZHs|D`-l);Zy-xbFX^3_BLMF2Fx*SW!edG^8_hR@Am_l zw%WHI^8LWfd(%YMN8c8Y!OkD?|D}FzeK`c>Pbr6%>2KjQ@Vgl#QS?J|o(`O&8$;>F zRA-j_yjNdO8gCK6Ut!zur*`zZbsU=jXN2A%dcQ7{rvk_C^;8PTDdF4TZ{?6HJiS%N zGl5fhc(yPEXN8r}`QrZ8Vw|2V@FwcgSeYe;e5qq&V4C?X#P}@&-kIpA8u%|mXG6JL=1Q~4e!YH?$y)*-+j~Vr09O6 znK}X|e!*icTT_|#e8?`Xj}$I1Mcf^2y0rCF^6Xwp(i-5S|0T-3k*4rf&Gk=c`uIqN zY>O9iaxQSEP{_9G98X(5*w9Ak?0fzn6&LQN%cx7h(h3@Ma41P<9pw!Tp^2l)LTOeR;| zQvM5^8pj;r{)0Nc0ogv|w+Ts@4<4huomIKK8h4i0fWK2_ia2XoJ?{n1KgTINZ)7Qt z2hZ~^XL!GRxQy)P zA9qyU%VEI38ehu4-cMAlk#dncS=_rwTm_ttN1D0i-;-hyaLk{|0_Qr-38+B5R>oo< zIe4?M2eJz$)br=5X+j<_Gmn?^wy;r@hw@(PIeg>Z7Lsf=qB5EHx!Q-Or=amK4B9{BO!Zp>rD<;`$;~)Tz7seckP@**(jfY-&pLOUrzUc zNkXc)eRe&ifPNRfN*tNjOwu?L6Xvd|hyD3NVBYk)Ah@h=R*YAtUlt2zwd&|FF#r4g zAB}BSMhU=Fy10jU@ju!D*__?xq;)rmZh*er%871H52HNbY})XF<{b4RY3&+>|D)-f zJ)~>sQ&ab*P=3@kItxtapSh&`Z5<_n=hw3ex~)Hi2sl$lG?4P`&w>uozbvfSzra1XN&Gh@itAQzYxk4i!{^l|8AD<7) zh+pBp1Nd)m=u4AxD%l8_eb>Dg2CFvmcF@~PmI$p|$O0ATE#dz1va7Pd6yRj1q>E$P z*YgVC96TWKL7ifr2!8eZ*I9SYFV+Oz?wb=ASbSnX=-@p)j5~F9VrhTfCnSXrPrAm* zkZpD?WV^ZZSQ?)bkONSOcQd3tbp_&hp1Li?6OavWBMUsef3YC#J@wM-xX>e0(1WaM zP$_$^nnVQtf7@_w(Bcry1kQ8u3qQr4WIoD22Yldyj$SkjILk|(a{G#KngN`1`>u1a z!7u6woR$qM_`sNaItPBQJ6(Bj_iB>%)Ccd~6Biz7qFTt(m3H!K?4zXl?(SB7LCLWh z?|x%ly0K2!bhnlU0>|T?K(U&|ioKZQ*$Wgp@egGJGrZjc3c~r$bKn%QH+c_!PX>_H z84*p+#gFJKWcPOZO_lAg(pb=y(+g?c`2{4c4T{dz(DN&;$piEO)n*E6c}*7NK?KvMlfeWFywk5$7PsQfi|fH(K-PYc(7P{Aa`0@xt0%mch0a z+pW2_ES}vV`|I>ej$aqT+2G${CURq2cWw!K)0=NR(axSFoAmZeW9=1}_!a2jheaIc zGK;$cr_Yu;_G%~)r9H3dcv)cIx0A%R;OTry7C81$u9kF$xoJxSYwn8_wxB$usf^XO zj3E`+VMSghpUyi-pFuZ7$8oQ#w&V&u3r~pre2_c&LN?go1$Q0ti8g?q_MaISocuux zfwP;ovSGg*MIYCFFpMt_te_^~sI7|RiDV`s}K2re`I~ zg%H%G3H!*sYd@U67`5;~GJm1Ce!X}7=R;ChO; zfd1F}3w3Pgz-r(zo9stPZ{KlC3FpdFda*5nf8y-1wv8DHc0bq~-}+mvM>Yp?SQ-yo zP8d!Tlqz@zbo2T8Sr|FAfkR>QV9jB|klDx`0nVgB9mO?RvpxmRe?b}IhlV^ExwQK4-+!o}2+-3PKNI`l?uRdUe!9*L5MIl)S3vd=+X06uJ&sm0^h0zWglsL-zG`nRdQ$kX8g_Gh4{C``fM+Ge95iUrQk_Ex0S%_nS@u zDHSc@UyxNlnM`JerfiS$+{_@dn&84k;P128nc5nLav#t=>aNqxiNClN@Zabxq#xZ1 z6|t3V71hEnk6L~Xear``3+lLcvlV*&<7RooalHS9cuHQIWN{(#^s>=*x|`J5(XfQ8 z@ZD!$FSDn58V8`gypx}BL~I0?Lw4mZkv}eV=N!b0rfp8(st(rt40c<2FNcTj*5eJ3 z%?_>NHm2Pbd;Au?npx-Qb@35+=DOfsQp`B5{gBP_Xyn`7J%ky+{57$H(>@QQzG$QL z`fr^Jv>w?xAy!Hbb|B5+6R(&X<}Hr#t=e9)}{fF&4UnFEb99&K%ZPF4O3W49M%*HvB1U`5$32_&sQwRGLFP7z6x-Rl=Yt)@SvRKy~8UjI!$&R&P)BE0l!*dt;@YE#OrOkU zhOD~NFUl)2;b7FIbVn#no#V{GkUhA}g=!HiZ4KF>&uxTniKg$*D@XoJNsTa zi+7*W`5kDdyhr?}Uo`hbyBH?;^McNASr@W4{l4>{qqf`vc4!X!$Lq9r^J4hMdGku% zAJk8AhwJ{$CY~+a5s#r>9X(}%7k;ePREMnp?k4WJ&{5EV{;Tg)BCnu7^@DxxAh&tY z)!p<7`;psLvHWNf-XKL=PsG}J<^FfH3bM(?4>7 z?nFwK)%ZssVq}Ak3;Rzua}L_N=DQS!SpTVA}du*-)2W^bu7HF?E%lx>;BM2|h`fjcxs7bL-$|7ESHx>spy{6r0hy3>ZEWKHr>%t%+SsT6uEKvFdQc^F^Rvt0 zxsUZI9kPL6zOz_lL+hbWJEZ{j5Avim==tvNW8UN%MQ;VH8*g3WI~8eoI|F08p*pv- zDxpP?wJ`W5p3A7GW3c(5pAqtjmu1?+VIQBP%Y>NzGHpvO#McHl3YosOv>)Y%H!h@b z^+NK8tu|l1NrCNt(plI%H{}(b>K9Dm@RQ~Jkx%l=nKCsoUqAjy=N8mmk0l$q}&TE<(U}OL{RaqCwu`m8Fbs7^8XXL5BLjL*i-q0SY9?0>zv37lxOsZ zcftM!stakr%0li8JGUzCLT|OIId>E6iFcmoq&MviGlO#krQ?>%)FCeEBWD zTh%{J1Bwz)ds9%a4KQ zxjx<^*m_O)tBy5^QZ=VN?Ll_Xp~fqZH*{Y^gVALQL)~W zU-V)7W4>eq{(mu!{JkoY3V@?Ot!$iwErVZK*gO=*KWL)S({V?ju?_9>s-Z`)`Oo&+ zS>C~N+)mV_V$}SO($j0I&?Sq})%uFD9 zVojT;Vc$JDlfIlkg7+z~F48Zdv6UM106q}rQA;)>YK6Ia@R=RWw0ZOiL0Wrvc9Ch9 ze^>k9iTW;1Zl?2&`l1GOi|U2*{Dy4N515~_%SdO?c zM!flsy5H!>O&u}c!-hLlR&vL)`7Gs`Snj*Vj@~KUWee7d(;azPRU{8WyJt-F<;h+? zd=K^A^(&J1mN@c)shAgRf3m}^o2(7YMOHaHa@JO!hJMlROF2g5QQQZ8RiV4$V1NSzq!*^%yB*TzvTD!A+!s&`iu8EY-c6l zJR0W}{f@Hb;7nSAHd;JtCc7>vAt~?W)076$(6*L(A+Ic@!%0yO=N?i#qROY+%p+L$ zA4J167?x`t9IO$5G!GUSBC~_dPNK&XQwkRAFvJ^`P$?70`@6x-W>qFB9`EpO# z`A?A}DJMp<8QNls&rJ$4{>dTZ;PcAcX!gk*mTZ{nF`CTX%6S*+^>fE}A?|lQhXV7H zaWA2*APf8he^xoHBwjj%H)r4{nSG+gSiC3vaxC`6e@1eLkrnKUJ`yuyH@kMp<~H!L z+hc6l`FK1Vz;2xmz2U1FBB!H{1xG@;bh|T0!v0!|lX$}$3qCdmYv8;8IP3df-UmJ3 zyO(i$-w7OsHVrve&-GVQ#8bHM++rwli~5fh_#7N#ZSi+*w7Q!75vvX;2q*CtR6Jy&jZ14NT9uT4dP|u^ITb&Vn

HqyePhmHukT9~n|D2}52kvkGK|!6&NgRoJxkWbV z?Ak-Ufd4k4j275TpzatO)lMMS;!didvIDjnCeya=K3Xt9Usz!x(@qoJ<#Djv739R7 z`14Gh23vLBg?BkDI`Ac6Mx_?f4eL2<0N?mKI-O3t8S;1N<~;TbZT@ker8h3Rt@9)Q zCGWTobUXO(DP2~LV6REYrJQw(R4kL(V>n_cmv_*mrfgmUKWX$GL$fcI^F-)oWfv#> zYu~`9p_`fIU|}Q9FN`o=na-Ii4x5a-k*Evqeu}@;>v$({X5CuIH(wR93_f#XyCIKX zoX*McG2z-h{;2+yozad#8t+)P%a0wc7wi(BaepykVd6Q9d93c0H+?JLl~ZhC_Dha=eda*@`?M+p4mVUyWTr zx$uqelTz3;%!F(pyXN#q7S6lUGWgHwjxMZK6+{&npC`+$_(oy^tr>w>fYuJy?36>1 zz|6inkoDav=?Uhe!npfl(D5e9K_BTb^quB$oRj>(7?nBLQMiM5mwtm^&8Z{VOs=7Y zz_Iv`NFGv5niDY2FFHz=12Rby_UyUJhUS>Z)BWvOleBlG-f17HHOA5{9!$HQzo!0J zgCUkn+vInt5aZG?*WdIt{R%mwtrKH$Uwh+PI*T@{x38cz+QX?O){RHL)YF^TAHpu^ zHlU+Sd;JP6p*!f?7BcPQ2Q=h?;L%;vNO9f#MKkzw=EpJ`*Y7``3?CTS@-MY0I>Y9u zW7?t^S~KARPeL2j#QD&{cppB5`9jshkwP#oZNzv|mTF8&hf>)HIQ6r1sr}soR{IZn zUhhjb2dj7y));2*{RCdo$k%{l@@BPW8T$W3_+IAXd*ZeSh-9hf&2va*}v%{7l*j=U*Hd37susS?f5cq!p{C< zL7kTp=3D0RG})8?93iazd*e@I-``BTF{VAs>P{hJ@b6Oe7q>AR zD6)GV=>jwC=q>7|lT3S1M>ULXYN5fj7V}Q8?m_gZ)P=%flMgKu=m*wIV_^UHUo)wr z+95iH`X+TOC6%n{T#CV>K`+{&`8buT#kClp81eo zM_+D(@w_)Zq$wvq^L31?munD1|D4L#AgeucH93vQXJ7c0^_C&jcSI$Z&xRjH`v{XS zHL^2sUVgn3a1Oas1<>>4Z5J^G?=706pDw{aXr^zg;`5Mg)n^?KyOhV7nBS{9-Qp=G z$-E6?$bl~}xc*}(H=~W#h059Cr8`SG1FgS(<*e|#JOO^*+AfVxM_lHG7=OZc6!3C= zUG5F~%(^OevG0p~7mOiG8u_TLzbImyj6%$6%zy&ULY6rS-o+%gJyMCv1SNa6~J@Ilg^_} zg$yT7I{1m4FkZDiZ^0WnC(#JB`_jq-eBLyRwgGe9;OQJPpp-Jwtjv>p0FduzPSjW#N<%n^=$sUu_9(6V7HWp^s4Y+%my z+J@g}=a36**#ERC-OoxUX|4PG;4{j39Zn-)!!b!8Xj;Tux)0wtdLo8~r#aAg^smmo zsdTCID(!@CXBOwt&xfn27```VZY4Qr4<;Yjq~NZU+Z-uK=g+;7^Sp1)K*0lgCLEV( zM|KaD4}hP<{AwiGv{zy^#z|zTletwVPDdTzJuD)ND|7fQ{5C`PFL|Fo&1>N&N6z6M zfPtMNejRPkv?~5JC!#MD^ms+xJcIG>1Nx@9HRl@q$(tFM$&_>Z2zxmG(BTj~$ z-)k1}ijg|J5OY?yVYtitG)r`ZeJpXmxV}avUf%%wA8Y1-$;XAQXuCrZ)!dNMk#Zn= zq%xl~e=MU>_-@LXRPOxPm^`8X;R!JuYW;v7t;2Xb=>vOPdr=5pI~YsX9V@?0P&;XjObptG-Eg3vago;Jg`2MiiY8MYOqihAv>Uqc4B^GF5su`R~5 z%psL@fLX2efZiUCp^xyTE1kTk-tPm&0&~gfFdFLkoU}0>T0c%ApA+V^4g3cpvZ(FO z{WJu=RM)eVl1!)3OJEk5)Y9%wGU^YWJIzgWx0RKUzZz>HBQ?ivfHzUHvxamr&KcRWXxTFIl?c7!crV~ z2r#Rr_)~-JTmAsd)$N=pdPo>whu@x;n^W?EBtC~WYD(Hq$DU>JN{lT7bf;6->=G^m zW;Zt(6&TdAB{1*%mGFA($2)p0WX|CWI^8{iH(URVh{ z9e0I$pZm>$uO5$_SEv;uA=f0{EPlBfh_5qgTCy8x=b4FVh82Y`xPzU@%=Q=(e zl_Si6&L=+=bFy5M{2@DE^A8)IyhsaR!^w5gd}hcaMLyo~PhR-9<_DUDF=yKgd-lEl zjodJXZ25MaZ7Tm#ChB!&{dBHODxoxtt2V~PV#CEcT7Z7B@yllMb6qpp!pFSBXKOvg z8ru~(pA8&@!)uyoC;T?nsXeW%ucrR^Zm*NG>BHk9nvZ@xyxS>KyYZLCz@HOt-lmly z-)Z?0%rBX*X!q=3nuWfw*hHjDHE+lj_!CXz=~#_5Np~nV_sO9z{#)rfbes98k`5>J zr^B%GjKoHAQ+*@kqA%}9{>+^oW?DcyYV~JYtR^H`nNrlk3pYK$aiyWpTuvW z^Pns@4)fen55-w&5!ubPiQu#HQpSOC&d!fVL z>pwWL>=w@g{@aLLzO!pR&qKSf0^Tv_9y}AiJ*BRRPefUYQf|NuoJWn!pR6V2ncT2# z;NYVnf(c|dHkPnn!c;m49c~z9a@op5Q~?~FZSj2mjt%`m9mi*W#5**uG!EY#ROiBT zhX#=`aAJ>Ib6$Ep4MAPzMIPkkEz#$p^D*_w9C^J|fz$GNk$B)-9hJjpCbrx!?uuz9 zDTnRn<@cIyuVmU9uxj8NKo{{^*#Ze<;Q&?9##~+PdzO+`5_p=AAU}hY5%%7Ly*B%v+l^W>xWv(rF&STa~r8))eBKN zqthv@f)3r-0=jKJTR=T@m+&0aE7a*X{nEL@RiH;w^8ra_l>oBc>r(tK)0_u){>iA9`}F_UtI@a-%!b?fHPGmP>8E;;1byXnpJC| z82kNr=oZ+$N^Xnyj0~aMR2>%M;;?r^dHt1v+()I7jiH;3={o*`7`N0GuD7rA_A|c} z?^1T?`Gk8qMDiPaH^cTlZ`$n5`Oqi(!)LbtjJN{EqF{_$-Dg~3J@EXvQ-J?VFXl(k zt)gEwn=a|bF2FQuZsh1kFBS2cPj)zmaB-DO=g;=||Cn$6SYZrwi+Ekn(^n@5Q=!}E zCFSgIIhqQfo7S0Z{yuyMO#o)bf*-u-ff>C=9cP7oV!J>m`VQaFs`B9aPXVM19C?*J zUtIBxETEga@>!1Gmrj<@t?8CF&;5;95o80Mlz80x8X5?C+cqolGVaYjhyDGYc9p-v zdEzw4cABpz6nw>4fckFkQ7AmyP)E`lrhVgNDw|bGXW&b}dl*pc`%Ky@>GRQ=R{e~p zK`4K4#)X{xf=GHNc2-#+{o3J1-Jsi$JR9FCd=9^|RcydU12A-LSwa%TiIlvCGT0NS{)%&{W0Nws&)R1g$OICtz z&j%G#>JZ{Ks7q{7Ivp}S&Br7go{Xg)4tIDe%B}rH+KT_TjsU+(m@{!jh$3z^%*~us z_9yWhv`hY*9TcRQ%~ANSm$oW(o?gzHsF&ftU&3RY>1+T!x_O#Vfp_!UppMQLbLE!E zU6Aw%KJ#6S4X|^@@p*R?Tq=5&n_#Mu^Mo)O7Y*(!ft#3I3s#CvHC?PQM%6+ ze-C*ackJcTy#{x@(J|-RWMKesb~w~?Rav4S*<5o+IlE?$qCwzU+$)E@)@@b1SL{)f z%m)te%3Q+r9UKxB}-m(mf;l@-VF}*JRpm&?mg|qj1Tu zfuuV%3rCNn$!_H|9QEy9za8(ZWz$d8SNY&AGOzeS+MvxYKcgb+a54Z+3qwDeWAKh< zg8#?h&$Q$9Lt2db-dLJSb<>R%_rkm<<)03ci+vOLmu49c1m-OHZa#YPpF#&i4Rih*n#7Xb*7kN{8w%sspu2v< z`njDKF97DHsWE(f-UBuOj_$0oPU8&fU1JMT$|1D6i2rdtOwuX<<}Ig24%_oaknXuSJ6Cbo-X63LwCTnI&RDaA zVu6`o^P8g&8qs<1>mlE5H{GXZ;5f{>EFWz`S>>K-{QbM^V5WWOzi>vTde)pbaxe`TxcEwi~q98svjH zHB$&|m0({em}7jC&f5o$P@_uoQaTOHx9j&)nst^U-jq;eK^-0^(m>#k^?X4pe?ln$ zIO}u*$mzT%Np}ff9{xi0Pw$g-AM?W4GlNweI?8-+k_sG&5F03AKcp-Aik6Z zO1Z4ERp&+Jea$T09X=FaAsXl7z65ZFJ($WB$dQ)v@xHj~^G=^k?g-2nQ!7@xnV`6f z^i<;|ueS=}9?;XwMb63f?p%#_kG%ht&vwOIZNOa8`w#8}UEtxs@!W?P=F<6G4xIHH ztGUt+cizBLmf6Uk{hY;e;6x*adBP<~UIX1;;!T@nrJaOpz}(Q-!23_hg`SXgwW{Po zhkmpIm@~iS@p_$A)QEDSE`|4o7*hw(LE4{L(I^HQrSdt{ z3Ul$G^lIw*zCB6#sCv_yNMpxiVJ9%P%yH+k;IUSF$Og^Bo0+2qi}kSKGKU5VI~ght z0?+D(3L2p`h^5@!kd}Fr7`~P}0keIDvuSuB(8i0upgjmkyz_}$P2(R7i75UPq>jfbR zIf}W^?b8!&`5WAemU19Z^syAnel~FyFrWLk;6E+#zgJ+6e4)vAtc$rAIIHcB^V#&j z90!^TZnH4yJ6D3IOy8Biiyzqxm<1+*d@9zB^?$?dM3QvJLCNk0ha#^1Kla`Os;XpJ0L2_p%!+YDK~YfV%qGA>dm=k!8SrjvJc5M+A2`XShM8Nx@%W=SLzbNnP5K^N1J?w40^Z1k2dHuEeqJbH+IMq=~QE~Pto)FE4oP0owdZf zMCS=#S4Fe^boL`2Pp5kcHTIOiX5#&WMHNWhkq0uhF>E8k{P;8;d*7qda@d^l0a&cj zx;^{hb>%2%MDVe+i%{7{1}|#gI{F^88FK;HckQP89ICY42Mz?shJJ**&7FYlZ9=wx z2gMyTjwdl84=y#V2(g5xQAi1R_S`L$Qkw&GKK{|Auc9~METFu|uj4=(MYMIKd`YiM z&!uj}Z_w*Zh%|49q13(-<(;hZpN`3dCn@3$oQ>a#ES~DtoX2o*j5qpIo8I;}puO#F zWO1jlrYE4|*HE;eF}zj79g;4;#Xx%Ay3r)4OJ@OATVT=HmhkCE7N!tvbNZp+zq|+! z5p0;)Qus!81Qws~wB)4v;C8w%hj=txd|ZkfQi9=xGx>gXbZeA{EElz8`v7z|PQ!up zZsC|!7+>=PCK6na_JJc(BXAnQe#0+gOxv=$7M_*v)R zVLe=!MtJJ1E5tK3Vubxfv(2b5*^f;AjE?R7d4s_nk2nj~0 z;{&XQgVToV*mu|+Fe03>?@!>(nW6BQ_-)*94d(j9^Vk@}nq4q-Xa=zSnmV^$Nb~#( zVFbbNZAMBVIi)a$@Z=7UG7COIway67yw2lqy-Mwkx zOYNV8yTF+qaiAbPP3Ed#dbNkZ*1_lALEzT-ENmgZrn%C0kh}#>&^(q{rcj>IXkd3Y zR8Pu<*=uWnNbfGUDTSUdRtOL2-Tj^vXElF|dKZm@cT5q?zmL*rf+N)#(D}Y0GCdjP z{t5QCTZ&`o-PR`~Aj<6kM$_{>h5;~c9o=V1cxKI}bJ&-My!Oa;vUO-RevLy2&)4D8 z!J6(=U^=IHon~NpG8=mlp7hiHf>^B>LkN$jT2Le%r2H~!<5P9K^eBaDoDwhZ!V9E( zd-HK2@e-ol4=>(K!)4UIQ&m?S)h-S<5T23ij^eQI;XDtnI^Cz5V&Kou4(sX#qkVx7 zvfSi4ccQWG9lF1maH>6%aOFZ9WP6edV={4{sR4E(JhEFMCbo-~+z1}1qa`2p6(yG6 z)R*Y83$#$M9Gw2QN^nh&J%S10@p_VnC9^Am5z#hL|2tZ~7q}jHRFR6Ig)f8ogl9l_ zB+h-eABGSd6oS~^;}SnhI*R9UVqhS+(YqdN_u$K3FJJ@Bd&*AA?V~y)tUkt#jGh!T zoDS?;dps^rI(#-CrV}2!@vc%&f$~A<`IL`#0pV0@q80H{ZTc)>^KHr>A%3r%NfK_} zD&Tvwl6FS$xLpQpB%G~HrbF(wFYtr*{NnjicszKau#3*E#uUFfGD;f^>D^v?zd+R< z(}9A|$p-rzI_B;Lw$@}s+ybb56WWsvMEjE$I8BO#S7dimm~Mhyxv_B6p8O;3+aRpg z8*p}@we{RESYIy{{8rHVekxb!D&#}+Wpt)H+d`0PQ_c287tFB_rfV+@5m*V|)JwdDSN8mld-)%o* zT+~9Sx|sApLKb$|&>SWc4JO_tI7-|q44+T-pXF39Ghv20YbNc@))eFRx|gIOvuKZ9 zmF`*zXpa4;jr)ltgh*>-cTyB}eTiS}J+M2`*7Tf&sScNs#TzW1;DcIr!MJofoqua= z!rRwk(T)7J7qSN7rqSQ<aSXN`2*bY9=$kbSfY;Nn;%=Iw zq)snD+P8=AOW#K%fzFs2m`n3@zD*8H8PN#Mi5~06B{1Q@c1a}s4av4?r`R8`c!HHU zc6C*0GS%E$ZDl2n?%0p&Y|#C=6RpHPiYk!1E)P^=ti;kSli}=@ukey!2l7q7m_fGG zNmgRlL_aw3(jV?kw-POMsWyrJQ79g7CGOeu8CI`Y1nsH49{Gc2#WaUkW39x@;1XCo z#8U{JVkO=q`$sC%=a^2VAi);p}+$ z5v)3N8XcxtiB~?JhqlcEarI;?aRzRI5{iKV!av%hKg29aLu-0hK?TL`P<|QhW5s%J zUMrT;e9y49617)Mm8RXIx^KkewZd9BaBnUyqxOSdSYc_8FW8vy3~03PNO{@fh`y!R;iH?hgZRp) zIIm$II~3gsHW!MpWJicVaqQw8y>xU;=ncB`?$gfi(9&Zg+#;Ok93P+!*@%bGcse)RZGmJd8|Lr zS(r7c6x77K|Bd=^=SU8#ktL38I0qv9C@+k7#19AHu2Ter5|2~%-hu_aZ$f?I(Gw!! z)NU`RLiBi^OM;$xGnjoqR1C_6F-PmL+8|;@?@}l#wG+l!T8X)IMzfhHtC!K725v6| z?E6~sCH%n@bD}#}#BTJigY8>*>gtYtiJoqQ?n4{DbJ&jP%&wpUsoz7Sby-vgZ2%9w z_ZUF!XL*@Ie11A2!M0EC3n#7=A=O_JSLjSvBzS4bjp*HN#apDOUrSg{qWE-fGqgRJ zjYib|&Ja5Uy#%D%0^0K%)8LfajQWYcJ9sPki6;E7m?g z6&a69P4mz(yBcZ}@A`Dd&TaECQX3kR&>56>{4qm;G*(^03vk+p&uq^iR@wCpkH!vy z(e!TQ{x^8ZZW}x#dUAB`p?BAdP?hA(euodL1_i@*nxn<5*5S=haV&>j4AwS6t1cN( zL~!h!o6_J>#XxJQxOZ+sfF=2{`j8CteCQ?UI+Os}-^6A0+JM#8ES4)FHdwqAmTvz9 zb&38?qmMzs+;HeeG8Wt<0E{+Yg>?jX6JEl}*B)R*ZN8jL27@tFSA^cZ(JpD06$;?R`V6T)@z~cm6*gInz?JlF^8mW1X~a&P zO1zl7k|0cZ8AlV3A;l-*{J0Qy4i&4-SONVGf52(fUUD&@n!U7_B0TR4&k8Llw$`2S z+n{dW=_j@1S=8_DZKoyk)M7LtdQ5KU<1PD4tWEEhxGzVKB+5@G`rqW8z;_cuu?o%I ztKkyH==mZQ028yjyvDrroftv*57kV?3TY!ypWbcsJs%s1*-}-aruF|cy|`&(l}=t=3~PeS`bO?w}vL;%=6=b>^7on^h?aw_h9R?*xV}sx9MDkg(PpC z2Og(;8pFVraNg|gfOQ6bfoylHft~*wcO75bSsjchUGva61CE4nDy+nv3MB z3!%d2&)A0APZ_5R1{<<5g=nzsyh~XBsRVO~wmud^)B`9^BZTD5tgfa` z6f9H;UejcFNHhA*Tnq?73LIUSC!zMcfy6-hDAVU5YcdcUr34m4z1|jbFc}T zK8OX%!xAUnI|Fqxf?zd`=jTg7aO~3=I78#yiT)l^e-nJA_BX4L4P$>FARoGTwM!A$ zHG3l5Azqe}ogwS!0mXfq$Kg;4kHS_zDWG{GdNK!{N3Ebh zoI-Ri@qdVhOO;6eGI7REy7O9R1Cn1`>_&H+Z>`^*o%=+`mqqx&PnM=on-*k~?|s}{ z{ei~k>r<+?-*tyTwOqvGQ?s#drY>}#_H!P7#-}$I!egQ#Cy(kz2uI*D(H1@N8a|uh z4~>cDcG`O}?ap&pN4yL+o`QQfdFy_SxGG!v7?IEN zPsO63kys}#1>NXfb>E<>t0 zCgvT?#I*eONV%xu@(Oh4X}nUpLOj+X{rx&~L0=OZTPdsoRtJBEcS-)2HS;@#@Lf>}(?DIt<5ZR;kdL z-W{u-A&sDVqZG$0>c|bHCUmb~MUuDqTTO%q&9p@F?~C=0Rsh%BJP4xpecMiem}SW< z*Hx_l%mZf6dkMPK=EaGtu%b=?^rCk!=Z3*>?_)5Ca4u1O0)x;cU_$LX`DMYGIj!Lg z(Gb451aej!6l{q$`y*Q7^7&~2vx(-+UUV16${W%d;^kU}3~2Jwi0>H+UdF-soOM`8 z&o@iKU};L{0U8sf(M4#LEn^Ig)zk^wpzkKC7eM$MRv84x{J-Ha>bGm~XQ3de0Iw1~ z7UQxMJtzj~6VbWy%W&!H=Th{hISR9?jz&~3bT_sCf7EP6IX!^#Mn#jB@3DE_25=;t(MKL)>rgt|6OY07 z&tbO)_gQ@vF~`as&so1^`Qu_`Pr&mvDSwaNHJI~Sx~D9J0mRGxL9+TL<@Pv|yq!K` zD|qjq+;e(9S+_0}w8@2;)P84x4NN6pJJ~|TLG!#|%qFUFO!!Akya~%!+=7kNZ$$eD zvj5Zl>_pGNmx-`q(rjSog-Z8w;Fw{3m_zhWTUZKTEmsMN#MdB-$zO2bv^s|7v~p@8 z-1z)VdQbRY@A?kYlg&_%-u+-13!dLLA=SAO8#_==z@)QynZ|R+xHFVj@&H|EoMUY^ z!YiY97(?yN8?gO*I(idqLNRWqCKlm4;>CX2c7+esPTfWG*x`_?w7Y#NuBQ3z5zz>9 z^>UDEB8iW)=i-Ed1SGq(7_EN@2fIJRRzzDPpWC=l?*?8Yc`GrB!oIK{BZ!y1)4$;D z+E!eLAGt|2yWDH>=YDjKY;wd}@}u^#lcWFV$Q=(qSN60X*^{72pIif<%%b=-UH)njE6CueSQGrcjN)J zbh@Aj*f@+a>ZGnt--a)ZkLk?a!u0DUkV)hAWqk`UZJrHmJiF@IL+RYl@Q!Hs^zI0B zbbSJEh_;Ri{*V{q2T3$9myKRP!K^(%wOqst(O)SZY!aVGi<5aUB(5@_U$LH+*yW?S z;70R4hVm&cPOTy>B6*OP6u@Yc6p6`6hi{bI8*PD1ekR?GhG&7>u?F$dxrPkOCR{=X zlD8;ZZ}@Ed7|rSV`7^8G-IaJ`@_C_hCrG_b{z1aCq{|iI*}h^V`<~b%eWO|S398Xe z{Vq2+CROi2aWKSVW_vw+R5c6PcQM`E30*@zBKuwj?mUiN9mDVl@wK{@8YeEif_emB zYxfHKyYA-So%7HXl%|d0-($^n`FL-B5vwgGF6gNx=bLtvrqX!&QT&5rW-Ebe(TJWW z^U*XcPspUcM(j+%w=f!Z5xge$6%IVLi}^1^r!X~|KlFtJn#aWfC$P%+P*wv_^mTVe zN1Knp^vpA-cGx|J?sX#`Jsx;VM!%K78{%=US97yvv{qFh9#g)a7d$VpI2Dqm2OS|O zF@vA`k|(Z$3T;1tik`nUJ_S3bhrle7x5AMKcdK27xiqJrbfTgEfgP;&k@&_p6_#fY z<$5)K6s@t^--Urh&j-5K*L;5+p(oK({Y#s5Q zzF!FQDM3%7?f&e#>O-{WFeRGzpS>;RHYi52ZHfldy5WF;AIR3JRhBMzacLYjrn%Vh z)CZl#U^J#NQ99j2>ysDoDveds%s1FYwUw`fLDkdH$K9N-k6{f9(eUyIDU#^%TcRZ& zs`N$Ol;o`v)sq?WaIC=A*$HoRv2j`rVC!$^3twr z=b!@dXc+budR^Yk_cLuKe+Rj)!1p;%DR;nn=nKJ?cuCkuwP8!HDFotCdl}VXC|xLh zA>L;t`1>Mjex&tI;eRN<2QV6A8Mt4&Z*m|K!_E@P2<2$I;k^*&P6E$21Jm%*%`g1iH@2t- zK2OaBwm*L}Z;EvE1KqDc?X$aoQrJ>nKsJrl8UJ`;W3@tXCj1u@%poM}8?gQVfUR3$ zqFxLfA$poEz5u(Wdk{!;_BsCu(uSV~^67{prpH0SI2V4tNQ?LZ>RR3Sxx=_M#W$|@ z7gWUKc{-cE2&%7GL*vu&UYw4Q$71Gl5r0&D0)b>( zr#uufLhys)1$S9YthnHgCnTMIfg_2RF8wBgLDytt=c&~3l>ndTAv zymdVP7|%wWLUtZ()aU~aSFGaa#QsGYc*Lb6KR=$jS&X;qU6RN*A&#Rx>IQfHfYa1( z<;EpAbjnF#GSO4}VJ7al(hk`9wD0_n_~nu_Od$F@<%VK&!xQkB_^SBc7i)N{A(!T~ z==m-@caZMSAUeb2N8#w>Ddf*1c^H!~seSX|J>d+irYH3PEpZ2pXYRXp!Uysv9;R{L zo?a*%w$F#p)V_`X7|8CO0_;3)J#;rXFM0*+oUWd51@;Y6!&REc^--a)zu5`!r1|X} z^btIoIq~y;SaYhq{H-mw0}Sd%wS3N<5GoOE`^Z+b;PBdjNRl6EYcbqucA4c4i&m7c z;X0xd-!m-1c<85Ijm-WK689KXPfp<;YCmMvB`|-AXhwJ@eA!O%_R+}f7%nR<=x&a0 z$m|=HvQmU+>k4oV(PL&;U9h4WZgxax{%DYNtCJ0#%@J0{OS|)s*-y0VPsYGdx-*I3 zoR)j=(Z&}@_4LFK{(jg?>n=vn_~c}SV;{?-SdDNx%>9hLQWkN$&Bm_TxMyMuq&h;P zp6v#g-)>vN)UZ2iob+N?mGprzP>=&p@e7>{%7jdakq|hg?5VsL8oBhuy9#b9BYQ*E_ zIgV14RVh9q-gow@j|P`>kl8c!Pt8WBr-{hyoU45g;O9dTNVzbg!@OJgdiG8Hjd(oJ zG!mx(*F&9|gB_(2(R!?yABox(``AfS6sl0bMG- z2btQZ)aikhKBWWIff1Jn2T6xc7l8q_sUA36tw%nF_Vn(YB6p!p2HE8Zr$KU4xN;#I zm|c3^iv{4_F99wS4K3{sL*s)_!I@}NU%3MVwXef?qIp)!=g>8EFSmPls`C}DE9%2fh%BN2fv$v?xQN+Ar>nmYjBOK)UNlEx$?IT2P#kWj_D{DM!L%kBm`8A_ z^(~<#-3<{=Jl+V%GAp5Y4-1lkK@avzqgR(8^CMV!wMMsNS;+hg&kC2|o^zkDI>}Op zmd9}9u5dIV85^E<7ialh#hnBnZTb=&wLP&XwW+Z=8RH&}=Y9>(YWZmUxB^nl4DIK& zXX^LcyVq#mWG9RwUbM6j z2d%gaHY9JuyPZN~!w^i6?jAHg!G7|e*CYrXa1np-A6FWhOg9PFxoWVOh|Rlz4fUK0vA#8*8%3GBxB zLKw|ylbWw#g268ChuW2%0yAyto=WOBEG{2}-Z?@M;k-eyJ)_>X5Rk?*ydB+t^vF=6 zSOT%6Z$1ofR4Tos_B9fc;jzg$R1ut0_!4Sl?8dLeBUMR(>z}UR8k$Fo6~|%i*f5H@ zr?v8;1B`3`3C*be*}1<#;PfoqMLas~Ix6^EmtYs7ZSn)(fO#~JJ|u7bhF+Bh%q>Q$ zA1hvb-kEG{lsirDzWi-1PO^;0XnLMC-y2WOdW?b8zS1Ze_b0PjnRK4|5sg*)Zbw(b z?=$8bHY^;B{pelYO9ki>^F`WB^z5K|R7L$NN+*cUd&Q+#%Xpv=N%W7Lnn$(#tHN<= zKgIbgR^B!R;s_pG?*-m_um`9nqV>HD=rjCA z?T_QG6HX=~$RYF{xw32dHQvpSZd zPOB*B@39{#HbYGBbQ>z1x`7X<-U<aH@mM_09u-;jUKPH{*6N{>0n^>I_u^ZjjQKH=!_YkZ__-q+r({FofE7bV|gf^=w&PVsUfZ2&%Pt5R!<;18;7i z^!*n6Ao*F>+zWf{i3Exj6ixH2aYtej-=ntJrH!>0<$^Cgza`I=23{=%M{4h~Jy>zd ziSmb;yv=jQ5!A+!av7J57_Rt1ByGeX7K&U`cY{n&#qj3^mW-W9-r^4g<2!vHmg6I4b&SW%4QtVb z+UwJI>|Uu0RwF!f>H8jGeqEyay<&B;F(l^&1vDlepG+^oo!JM4!$ePS(i1tYe}l&K z?skh$SZkgGv?ltYK{z&6AA=brW4`UKVtvN|pqw(X@hlGv-T9KY(HS`oN5v%bcW)?2 z`I7!(IE4wul3yn+k@eNhu!*pn_N$ph!^^W-LjU-DV6@#IF%mNKQh?DsEpR7jEqM)$ zm*i@`khEF?L*nuNg%DWdaS|Bs;qN}cDcj}jo(r+^#!T4YtPgCgrsoz@?t@BTV`xPB z`{aQ*e>S$&Nv{v`S4nKl?~=Zs8)(4iqQ3G2gsxkGn~BHd(h#toa}wLr+Y zDj?E&#$@dI#qqe!GZ~re4L;(5rQ2V!*f!C?@hZOP9e_+$D@26hju*#Rop$k)`zLe~ zmLikwhR3teJFYb{ncuaRYGXSdlBSTnWl){rWyW!4>>K%w)@PTM*9G?N+@^Kg+R})B zQ@69@@QnL9{;kzd2*%(_KKvW>o^}xxPh|dWPTH{z2h4oKzu8{v2H}xY-}tv2crQV^ z|E2)gH{QfJPrYcqmiV0L9I7)+2%O@=N=ye1{+tfB$);R4o)*Y1FDO#K7;PbrhfCRq6OQ7g~)Vug|~KDk-NPkTHoS?KeQqIJJ64rGLt*eiWNXUU zJG7q-n~ino-LtgM9YHy6Yz=xgyA)y68i}nYD7U#r~Sb8221*V0ZTWlG96BLW=2=6&1%t$B@gKy z-kmlA+he#d))FmUpR3v4BY^4+x7iabu|0|Vv@{6()}QZHD)_~~Z>lYP53_ASAY8wA z9@i3`4QealL#;=A&*SUm3SXYT=X;@sHB4Z>(+_+_G|#8|!79@^jqRNbVoemwsU9WU zQ?<9*B{fl(uzLr@jTKwqXQOOnd$74z7h%Ar&-j{X*mm&cDAwLd(Nk^(O9%&JKu}mHIdO%{}SJ$R^9K7iM1c|y{kjhHFTFy zJm1qMt?z_m=v>YAy88{TO0~BY1KR^H6ZZu?COazI8=uxcDyX1@#hHu0U1$rV>D3@A26IaO2<=R%=Ui)OrOIZ|w%QSI;#{fuN`{JVwZZ z><8Cp77MotXF_)^(MZ3OFqFo#X)i6Ypm9ryodxu+@M*r>J{9*OluW8@Ho*QqIC+dYz#qm zhT7R4(b@Deva{9nZ?Exf_zq-eE@Q7${LOwCj}a;o3-EZ=bcvnOg2z++m`yrV4u{sJ z23m5(eLV$sri&qa(gxp({H*6}mW*P%iTn(>r`bzvFu)T`sZFlmU2Ll52My?5YvW^B zb5uA#ORjpl7~dy-;%CfpQ(ECevU9Psr*e{)Bp)sTb|%dXsix?DnC#RVxrq3YW>kul4Hsc4^DJJJOx5c@K?t={1C`95Vr`B}1 zd$=rS!+K>+*hc;XX47-Fv=o}XEyXC}vA$EBx*g@1RU|wu1LCCZji`P#@n~jmj?UU? ztoER&HEt`87!-rdmgp;9Kuo-c%*J?m<0DL6b(+=27ay3#q0R#r9wT)A?hib^xf?QD zIBtlwR3Q*DsuiOpSJa9it@TNAN*!{jm>Y(ym-7nBFgHrrY$O4}&6 zf!S;=>}v=iqo|%R$yMT#%$ED zT9=Rvo{*UBI`~Z{#CC7TZQAeLKf(kvXKw5M)G`dV=N-qp^c^j)c?D{(RCC*S*P6Rw zpVKSKfhXI=XERbx- zFZhM%95P@G)r3w#FM|6w+>QPouUNi@c-7zvUR$EZdo+(LFNC7oh!e5E|;l<2#1-&5$9M^M!3H1|oB zD5%y}=soVMdfRy`ghLGXVRdpH0GA+*`?i!j;{<*3uQQ+5^!;&)Ax>H{^M&;cnJD!R zDn;fao1#?L3 zkoo53d`Q4<`tx{<(2jOF*u}Il8W8={4XGx~%S{sV@pYuLzhUV{1@rw4npA|TJA(!0 z6Z|qZ9cyIt;=aO}i{D{dn~mIuI4v2Bj3jdg3K;{{{6ys;|v_n%Og#3dXjjz)cyd)xe$m zf@2Qchf(9taUbzUD;4a|dcb|h`lfDR^Wh!$DKFgG0~&{?b6@l3zz2fc!6IZn=t_2n=t5zV#pqR{@geW)T{>@vP!EiX&HFB(VjJAU7)V-Y>~`d*5=I!ur%(wMB9ttB6x zm7<8IvAX`H08fAZD9j`LkMSGorw-)4`=)Q+pmWJq@FRK-&%TEppI_j<{@qDF_`To} zj{#^peLdDW9mit>!YXvdp%kCQVg`PjdRzKTaZ4t>M7cEMPH0tF|ox)uT^Pk?3riaug0+4~KRnWA`821&?=EfyFiyWWE4}xhJrg z2VJ{l*d|QiF+!6m4l8hAMPM-!j%~EWW6pg97CVtSL`y8Tsw=UWidPiRwP9nr#9}QD z%}Iq*Q-|{yjB8raaO1-c9-Hy7BZA-1%RFWyaMmgCtq{UvIaZpl1Ov+tJjUa^a|e(p z&Wy!=v`;@TIEEJ^iwQZS4DLIR`TVF~)2-f;jaCV}_ewO7+T%%zW78%cXDF9ppY|Ww z{Xt@#11IpHPbhvNzQh7GX0P={7NgQ7@fFn}+l4H4#pzWF-i#f|V}u+io^FP5uEb(p zW}1_oFT9n+VqmNdD7PS`gRq{)IgjGk5y(vAl2`k9Q2?F*&iV9C2&aPdrv<(}&-1o<$bR;S#rOIVSa2Pd`v+Fphg zO)de8HCp>L8s1V}ITnLt-HYz{b{fL_J#oAM@}GYdR+GH>*icSnx5~n9`YxVUpt|}~ z21v0)zdprRwvMdAW1seVe1)D3rtp}ku{~aZwdWpmrEwT^+8-QrukjeFYhRDRd5b4J zw(4fuLa2A{Gat`bi{_xP%tjWA)whj@&@ZY4S&UYL7QNMP>3d|cTXvNt=>^4)vY4)2 zDJH0A{)5k>810I8AG}8v12#SKG}g0wge*4f){sCPefd1Hn6Z18Vo+z@7A_~jJJYaK zt3Q{YkJg1a!ZB82v1k3rCw0)`x!Q^J+XdfJeD5<&V6kfU6enBPvo?=mtI+5RI$2w@ z8WE!ZfGAuwZ9k8Bt2X&Ix;fwAv2a;!4xzX8Gae(i>bfmbr62xX7+-9NJ#2CSi2kkt z8>B<#rNCnC>QwbqcyG}XSq$DC|4?D3Q4zbxQ*5-X4@6W;=ilSnh>cKO$gfZ>cB9|Tx7A4=dR5cMx8IkIV5jmf`inZsRjs( zrF=RsT6#h8+$_fOW0r`Dz%;H`hX=Z2l<*c=Oy<%r=P;q+ePpqk$Lt?sOqdc`4CnS? z?{V0M4P0-BH~fK5s+e+pE=fhGeI`(1v7mwEBW_qUPR(LO6XK`_NSAFwd&0TJH5>Et zoAH>^hd+bR?DBqrlzjgi#~KG1&did)N(4i4ExI0 zsYt5(y@KNDo6uZz${i`)rSHLn5i@(Hmf~we99!gl6$Fu$bEm4#9M9vk%L67K3ZV!?Mh^JVs~;jduHZ9F)_|d=u8yDlf%?Ut{Q~uiKl=sh7k~B()Gz+*7pPzS*{?wT zqVsy%r=2WSA0eB$$!aTcRNe1ViGM!6B|5EQMqmJ)Wm*vZ76*3W5A#>}mD(sST*0-2 z1JHdP?dL~?Nfp~!Zd_zDr{#*Z4a${*FJ{C#X4hXwDs)bBE^Kp*eSG z&K;U_hvwX&Id^Ez9hx|+63w|obMDZ@J^l+ZrJD1j=KQERKWfg8n)9RP{HQrUYR-?E z^P}ecs5w9WXPzH#%%t4&6@7#-x*H{qa`c|1lnNv2=0hWbhouh(w+5*&mfA#h+zOqW z#X!P5s^Oz|2DY_$0PmMl{gCT2yr_B+{0Vk$@d{q&)BTQ=Hz(Kp0>P)ILl(jJ3bWu` zur7>uqS_sesAgxx72yi`Nxu)(5)W>^pwQBCrMjTMej2!JB>v9hz$p}8U#B})%YJ_b zESJOoC%~@1XeSQ-uVA_d=Q`EeDf|5yuviZNp8)?~%iRCfxN7i}iPWDy4!>lVeG?j( z54vU?e#)Lk9{$(zz!ChuF7#P-M8Dj3R$ia~-iF@z{rPc)w!uHzyUHfUyV^61KiA1$ z^Hc8Kf3%@yzd!$P+RNqeaQKgFB7gV4JpYO3=W|XchnF81&glI0ob~$)X1x4@e}Arj zX6%`A?O7Y~Cq3+64l}+@jI~wlIsJZbQ~vqS_x?-!pU>s8SN}n0`FDTf z$bjZtzz6F;?R>sMxdFr4hXTaHe-9R0HX znMktJu%9b?jtrtcS$hssp9~NCAIC%ZIZS=BemTsZu|8NE`pG}vVSFLO#U7U7F4Hl` z6(i4?yl`+EbWq(5`arCINOUw8i2 z^HqM0D-Ubt@!xCTQf|KfvONRIi}KIjkI{NZelYg?EA|X!>p1N*4Tvwkrn9}_pRs?Y zvHN|GR~|0omGi5aM;ZpUZ~wV>*P=D>e{>G|E9SBMd}-h^xz&t=W*js!@E;=se4Q+t z@3Qq%18c@XBLf;4`2V8}+(~wkWA8;!eukFTzXI#GST6-_aN&06^6<8!^X2!EFS*^h z^RkKZlyTa;&6)m!d~9}S4)5RBM&4vIgu}O+YRR6eGF$nXPW~8uaWQ}1e(N;sReLpu z{|ubvY5rGW8WWMmN6p4(YtMCJt*ecJ!Ft~v#l~yAIoyBtOmRg>28RbW8!CcbE0MM7 z8fGZ&yapU@HnW;&H+U+Cm%fl;l%+j~4aQFb=LxGhY&1q!SQY8Q;f>>J;^edII2^bA zD4t4m;_#3`->^!|EDjILY%VvgJepb&>1z9U(9}*VS1sFN!Oa7##J&Sq|9mg$!;jsJ7gP7y$%;B?-tD%Loj>A1K z)DaZXWjevAAtX zQchX73LIXtc8U1*>kTe@g4r5zlm9>t|1%!{-T5j{|Gxs$HzklB7TNb$9;Wg6U7wS_ zl1X3jaU*>tlfL3G=_{G^6^BV*$)vCNn3KMeNndf8^p#Bdio>L@kn|OYNnau9D-M&s zl1N{1nDiBpzTzn_q)BIzq&<3RdKBz?tU(pMtsE0H}XeI=5<;xOqek@OXZ zNnZi!D-M&s0@7C;){No*ehkaY%UF51{JW%|Mbgil7t+rn>1Pg; zekS=J$zjsZK>C@(q@RKGGlxk(1Lc^Path<=qBOMyw zZ7bLO(L&5RaS=|P8ztx5%7e7uropF5cJdaw&s7y3Elj(yQl8prD!f=#M_4*(y*%{o zJ7LFF9pUQO_43-c?*)%mJ;j;dJk)*Ob{EG7^$=Z60@X>KOvRPkdx+|-x#~j`OvTRD z^xRrk@?2mlYL}Rb#eV&z)=E<`afqon%WJjNxnU3S+lOvq$h}9>ve~`F?)hEBMsW>s zOM~9xoW1SDUTwBuM5Er~QQu~wr{hEHYSmrL>5>Tw+TVYu*h=he>RFlH(%wiX5l@S74^of5oq8 zV9mK)BLf;4(8z#B1~f9DkpYbiXkaXnI zvfOC~v;NEFWw88T-WUDp5BUP+X<&b2@BYmH<@7Tg<$3vk@rbPbPaZk^vrqXKo^pA4 ztY7~8XPyFwsU6GL<}e$l@^eH!8UCE*be4P0@=boVXZhN{@cbc&YwK~PIGx)g54AT!kl!*Z5eM2(!gb-@b?{uvTseJ zCx8EbHF}anmg(9uomE!9LZc_k#)O7OW?%HrwSdEHeJi)d{fo6b7#5A5WTWu!F%B9% z$@WC$_9PlTNs_D4lfTyp`okWZhDM_&nQG&||0F%H(UTfI`Hyd(oq^dWpwW{WJz1s; z+5i71>BE1`%WoyHKHx3#-snL@fJ*m-?|7;(nd0wVF|1l0{ z>KPc8J^Slw1ODpo7cJ#{ni_vJ4a!gd!0$G(zw^1c)~qt0^*#4aIN8TRWOF)6_dF`= z*l@VQgc8i3f@-e(M6aRDXgK_MjGS4y2Z!0e z?7!J__IK8f!R$TuK7$!PhL^#tAJ!j(S^ta<1~a-CeGF#wGP)Ve_+b1nnDNK>WH95K z@y}p39&B6~%*Kh07lVI|pXQv)MuYwSyM5i??YU;3so7_0_L-V}=HE>({oUx%=t+&9 z)aXf#p8UJ%rN0|J8a=7elNvp#(UX5Sz4UjZN24b-dQzh&|7tyXqppkGwXwTiz1~-Z z1?E)G+3c8dwDkh)*JZS9+`5UX(5A6GV@DUP{IRhzclcVlc|kawt@>Us`hcB$JgdD3 zw{QPukUBsvk7v=nWwPIbHqE2#JaFjdHL|_lLuH3MfIdnWxlgYJr*HR|BC$411F<&a z?yr-FKUFAC8&|_qdtBs3`z-ZZpR^Y&4A#qU&yG=c+@39&gj&juesxqYlPk*;bC;sI z`BdfUXDj7Ch09^c!7q9y4l8A|2?a3bx2t*~V`j*18;XG8zjNJMzOQu_;IXGlDs|wn z*-yAU{dLckwGTaKEgL7_1H-u4K3Z+~6nQu9DD3&bg_hiflDR*1a}N zUX$8X^~9=$eAe|d`oDRt9NffKzFVmww$Ld)eQ)$S*~-QUj@Sh0g$!6L&u{4>r|dIS zF79waI(U1XY^r6gw0EqIRW~n`T`W?Rh36lmSN$|>bvs_!TRBS(9r6?&RDGv+d8D1} zI?F|_e5bkcWa2JqV!|3ZIck%#%Bh}M$Ie+=Ie)(Zm_Oi&%*}7pxTjw zdGuyIzw_(m0Z~=tojwK1427kABv0oi*~{7KuYSvNp@E#`j-QEG0)vK@U>$X-t zK4GN1J+q1G-KVBY?cQ>o3tY?mwrTA~SY+Jl?q~9!Ab#s!u zby9uRo&~jJ=Lsgl$=wBQV*_d4rc9QjqUx!{#Wm%lMTTKBcjx zliXzS0@=eiQ)z4(g=@Rblui3qQ=QtJiRIs2(W8re@n&Py`3(xW(+qbwHZe`_LDd!i z1wQ)oIm2)M6aSVL?eSx99p$n!YvsW%<7B&$ja0Aw>dArbwzAVhE!9%_BW~;6T>jc$ zTUB}Aa9L>KBKO`uSI^_n1)*-s7_3?4sWSTLJb7W4HkhYVQ#s(xTDiCHQh9&7=Srhx zzBtOl31(X->3LpUDT}6$aJt`JWw)A(}d$nykl(n_XX3*Jq%7cR)RC z9iMx;|AKY$$!srhnUbMb;gPev^I|xd4S26teAZ5$Ym}(y-B;DNO`?nJxOcw%H8n>$ zFaISP9b77#9DA;8ljV!wl)dCZPnxM3PcxA-Q`^c;Z|bQmmJgDT+|!b6t7j;C478Ht z^=twj?K1E_QR*U_^|%WQjgs{YS1y*vK0T>6-{j=8CDTQIJo_G;x}2ytT(FnFZ?7Y7 z8eUoTO*uhcG5dpJQL=Yi<0KckmTe{Z_3j*{{>^Ffkp8=I$qqNAGKKtir7xs&ORt_j zdThOXZrwKAuwsq!`Jv@h5BNMByPB@|eWQbXVa9E2Q*=@3S$T;(`Cd)A$HWS%4tkSi z@9^vD$~N14dZoL_d*e*;NN!8zuKYD})w|v02A`U$wvOy6$BogK4No;tIUgS&+c>t6 zd(^0->g_X3eiK?x&Q(`cW!sOFpX+>8*PnIWXH|lWydpjW7c@>#*0q``M>l9GS6N&~ zWzc?@+)sHE8~4AUG?=reXWd23So0Z9I*SUCoEsV5h&*#bS}1 zSfh#DesxWi*|kx!->i@7L5+NU@@Ou4t}vCH25O(4e$PdIe#1YGfGpsrH0{`ut>?nr!-c*n=HtkMxMcz(MObLS~<#5r(a0!t*)L9J5D~++81E?iFCc#6%O)o z#bkNb*Ltc~hib~c+B4+q`88B6%?t77_ex@J@iD#PnbYLui3vEc!yDx-X^wopMFn}v z*$n0OI#%*c&t*9Oy_NFpmX)&2h0hqG6|H<%+g6@6sFK`jYL2r0<7x8vE!y&tjg?e& z$4!*`HSHoT7pk3he&`}6F1!ha8&maO&0Zomp43Z@l$xp9Tr!c@#MhP!D^ya=zBf@e zoOKJ6OD-sD^jIQC`3#Xa+;668)xV9ru*Wy`wM(~rHh*@JA2qHfU-a4ObIy6HTr|I# z{Ia&UPv0LSft zc>8pJJK_&GE9=_uy~lIcTv+L_hQmvz^n?0~%j(c~bDV&Q{p#@NYhO)}6Fz(nV0(#q zB`)%_GoE~3(R}YRxjdfYi)FRyUxm~FqfTW$<<|vvaIMA?jwfm0Z7APn=$^9ukIf}d zNLW0Zw{fkW0?jX!-G?yZ;sJ>IUWQYN6)?f91#csS50jtmHR1l{um)@8(Yk8xLoZHV zFNbJ9;_%Dx^>T3+KkiQ-TGQnZaC!QBVOjgDq3dP4u~m5cA@5w|H7!keU%v6ZWb6Dg z+LnL&g1a7;-M=9pcfd=#2JtorBHGGdUsmVv%;{5PMawmuws@nJa^y`1{ygTwInX^< z#&4^7p5T~U=6~-xW0T_QHw)fogLf-=bl5gN&Wq?`wCM7K5GSMU}_%=jwDFdE?_r9CjH|OE#G`pTmBkub{^4 zvbj#{KM^d(mE9FkxL~q8bL|>na~;!RrJVn&EM_1(=)M&5x(x2U`o0t})q%IU9I{d# z-J$Gx!JuqmzB6(f^t|o=AG+Q;s;cLE9~VJs8$m>bdq6}b6pOgCMN&a&5D*FJ?uKh( zfQX`4#0|i11r_fZu{$uZv9JRRTYl%xyxyOMYyG}|u-3EodS;(zde5G7xcIAH3u#YY zeIdTSE0oxmAIQNPxwfQ_?lf@g>NVQG%$#2A23_js(dlne^9pL8;Hbvxs?f2dYMg*V zztVQwkW+s2h%5d5_u3p2)@RsWYnf(MuH6=;x|3&JmE_{1-E_XSr}bTx?#G_?3nlF^ z_{%3YcpUv*9k1m+_{<6VtRP_s`+fCY;zxa66u$J_pYQ|b^v3-Aw7=Fj>f$yo4v;;! zYnUFZyr+rqADblNUy4+Jx?m`~Y+nrF=*eGWcdi*tu+JYpPT;i4$}Z`@tm!(USgcEw;nZolg*D}U3Lly$Q*!maVD1TWt2i~9ypzI^>Eev9WsqUZX{JUnx` z72)W3nc)t3`dn=fU;KEe1+l+=IT3f))*Yw&dl1ew-+@?5aWcW@zmCQ4GW7{A-{Oet z3)YZlId!FD&0hCimR~jl-^-=?ujzFnK_u1br&%I(%?>1-wddvW^|Y77 zPo!2jc3NIb#-ZUD0p7iB4H>K2UILu6wg}1kC8R48U+a-Y%Dz}$#0uN#{Jk4n%HFv( zk=Q*=E%2f-JqXs_7=$+!#SvU8KFgl}JoM)Fa+&{8j}IKxZKCtH~k7lE2-J zt{cnq_OLsQsQ=sO8S7l_MxJ~6qz3M~eU13pupkBpC;@ra?nB(V=W~bHo6bk!kUPr6 z{^+g%*BqQh%0@dYVdEK8Lu+k3{t!X?Zji%3e6EKf;T$?*hhLuPB7RIy1z|>;A@*T*`aRTNwoF@Fo@8j^I;g<Rlr z{1WvD{MRX!aD;(%?A!Nr{nrZH%r2gNoNxke#p7?~V+daDn~x{{p?$Y}oTg1~f7)(K zzXxH<7&`Ye&tGEI_E7ta^IW`|Y)brp2(reVp0%Vs4{&4Hp$A=ab~@>>b`R-Vx-RIL zR5|=7UpC(S2NmL7YIN>&P2l0u`*b|aNYua!M-L-Dn+HtCf=UO1*Rec&z@7Fl%pHi^ z`p_{j%3T?I+;~d#kDeNVC&)z;4d*HZc+*Ha_E@*QthdCE___LB85?Y*?Yt;y0&Xd# zbE+b80b6%~wxMxzB#yi1h3)P=5uZHR7n{!y##&|_;z^r-u%7iXc+;z2;=`8L*o8Mz zuzYh*N#4)R|6td3F?jgxU*fa**I2FcV7%L|L#!6{gYE8fS-3WSSzOHgws3_kLr?s) zFq>y@F#vXj=Hh#e^LWvLKFFYG7T$1jjpRbP5`M7YI-6bpRg%Sv!3KOqR&MnoNk?-5 z?(V1ch(FeBt*Bd8*BkaVx!|gPzYX-|hr-n%6Y$#oQiDOgE z*`AZpoPC*iXR^HH*{P-Mb2%UE|8|q)UY9z)>7t7#Ha(Y27&{IBSzv{IHyHBT1I%EL zt{q=?O zQw+C>hj>}B&TaX)*>t6N;M(DAYUN1$&fA@5Cz=APecW(ESv>DU@nE>{(+8jaxj}MZ zi5jl!GGUuH+e$he^YO8Rsd&)6YTor0F}l1j6@O`~=7l{IBazc&c7pR^iCRk@zS$6n zYl=&GR$=n6t!@$?*KtAO9WV~d8+5T2@4iaLe-6S)Lx*7J>emwU(KE2~+rwG<~Qjl4wt3N-0m2Cgz#$BUj=ikiY*@Uo3_c%w6hg7bkm zy!5P?SA5|N66j^)KOUt#vmW{AV&f&&`1==$XF@DiTcLr&zQ2_upLWASPUralbjB~w z#k*Amyxp@rk*0q=?5ADzO^s+4zH~LyX22uni7bIAzRg-pi6jXx65QIM?Npq%+n6ultsX zN5qu#R$necuesRf{nwE-?k{d0Io&H3C%p8LIIph#O#!l)Fi|4qo- zg14jYWw-toVDq8#^}1#o+FYns!Ftu7Bxff3;r|zw`H$!PJ8}MPL;P^G!8%Dos0#KR zo`W@eF5~Sx5r>A}O2C7@hnV zgZ%J7yiRiXmI^lOm5480N0K3hN7?Rm|DR4-JM1#a!=jG|#YZkVup{OrV~ub#NoDG8 zcGb*qJghxUa-{kNdn3mPmo9lIF{rl1N;+A%MX!e>;rL?qy+SY+mKRBk!+x>r6o%q{ zA;*}CBQ7u{B^meMA>vIsxf_Xw6k>ga0I`AE59#C2j#y{bL5a4uK6dHa%AVJGCo#@V z!IqmpvTx6JO3e0#;*>8#*(Fn5C3*4%xUOdbzV9%Dr>&xc-fSqqyNBBFRPU-HuUAQU zxuJzbuWldv(bA3UyLw51+h82Zon`KfyQ~-dXpv21kU9>E|0ube;PcOT(9ns;8BfK$ zw+~OD_^SfEYnVV(p{65!Q|*l-_f$%rm-oRsP4f8H*DsQa`GNTL)$45auCEf@F9!Ps zTH@YY&q-X$&GAXSIGnde%wr1Aqw>F@c#7Tzp5@{Wq@5tZ*X+;fk5OC3e|=nlBh6Nc zEU%bLFRsnSr?rlY3j`i)(hY=-zBWrd>qcRZTkWj*%}&Y5=5YL`#1=1nCY2mnVT8lm z+Ss?1oe~}ENPIY|08f}aU!0lHpFN*piKi_-Cs~+fjvtQA!#g${6jx?tx#~E#gkelRY7L&yPerp=+|lZ+#>=pVQX;D;ezvdIA_FKv{Z#5`QzS%~XP({fsUM? ziO(P3ED3ly7!TprjjdmL>$NKEuwJ(+4!cg8A^DVemfg_94NnW%EQzlkjN^xXWslc& zO5Bf!;Fk(nIC^|J?{<6}k zZqLPoB94j8AG)z8PK9D~-aLt8z(;odp-gNJ@{%v>m$K}rJUrd3K^&&+$ZoePz)oKl zi&sq<%tmtYtGnDG$u%yX6-2*ghdt|*7_Xm;SEmbbzr2(B;>C;ky@nOwi9MEyulfyP z+s`KA*3njy^=l8Y?2deH%=z#V78szRdUiNDt4Xr3(Gc7J&BJ})DM{vJj%O9V6ynxr zDv}C?!_s?PI}}`3mAt&C)U;MZfc1B&N-p)=$?uL&ah$s?s*=+iOq#sE6=LfbDw5l6 zjneKuH-3&{EibAWl+DV4xeFCAK6Q?Hr4$I0RNQdnK0Rjqs=?4RumC^NXN4x02e9{& z0I&0H-So867)K20P2xAZ{sFkVpN~vGJbalwv#87qlngrA@7tT1pE)5gWPc-T|GSq# z$(KZsafbZIIjj4C)q47Y8PXmJOZU%byXL4F_|#{?(ezgKuklOfhE+5a_nL|$eP%F! z<&5A22=Hc@FYIxwQhLI|A3u4rtVThgh|Leu-!}ZCYJ(4)8$-0EKeNFd{;mX18>jsb z?yf)JFy%*ow!u>l*%5xDydf^QA;8lYn&^$S(cr6SalgM79>weW(SVBly|An40A@*g zKhQQSz}Nf7>RV=MqA~vYc$3_DVIRLSY+Onh9%wgESbP0FTda4QbvgQx@#+%~`}RCw zMjWU!k1&@p}q5`sCxx$tC)M`^KQgPK3+SHgEb;I10}w$Lzz&Uzzl% z1W+pCa6nzM)PeQhRIlCP^i)HWEu@d(EDg|BKX+<&rN9TP~|eVXI(aV|GK+{uMm z&h%O{yx58?nxBY(B-og=^zCuiEZyqdDj>Ri8SMz4( zUqSD+&N|?t*d{{Nt5}&h*W40_e2U%IO|H>*}j>e(t8+n_) z-atFY_+pn0E;S-+H7vu<-LUI_SmvL<{n9Xz&j~9Rl>#i-aa=gbZYY~v>4LQb$1tX2 zhQj7!<8Vj+`OJW+lVDwW3RWwg##@@W6+N90%YJcJGdMLd2gdyC zBz72EahkhBpEg~uHfA(mrtKkDcV|wU4EN!5W^lNyJO>YnZqZ-*c`jNwSAaj1?$=XH zUBS2CA;7xrmcqI}Go__C3eR(N7wRv*!%9EpVC?@FmDOXdG>Vn!>SH`IG)#wkru0fkjuI2KlsIK8LSBA^8~mtyGBp2 zN5Ef^nv1JOw+O|#GR*KEpF#@+k$O1c?-dZ>u0jI{!@ zZ3%eXj%=Ql6N|oC<>Rie=Y<0_%-FRx9(d!yj_Mzu2H+VbfH$3ay6MI(V|-ym3ZC<9 zvrzxmc6NQW2{yU6jJd041MKo)SYbsiQ*w41j0y?EVNS<+N*W)~XM;q%SwTX3Ro<(ll(Za#;Ahq>}y8+Yvt)xuEK|4G-6TOUJR9$Ak)d*04XH+hM!o z1FLK<8sOK?nK*D{f1Z3pG1_dAg16Xg5#C?1ooy=3!9Hy*`a_(DG{3yp7)?EK2lY_soy}c8?-pAd|Y);g>w8@b#xSE0o#O@Go?7xM*H8c%F&x1nk1R;Bz%SrWLbz842 zvyOjzN*dQb6L`8MHOQqb1E0BkLO6VX8EekP3BPO437>9S%Eqn?#$`4)csA)jP}ZOj z{N=?}-n%v5P={g)cIdZR_-VloRuVo7>uCyV?w(b`H2I;3KqExjbKW9m?MpA$~oB3Zucb#NYx zmv)idlyX-A1Ye{%H0kjm7!{gH+G?drF$z(j_f03SY-H;!=)K9a?fr0fKQ|W8T=(YZ zdEnG*EAg4ACx9bG-Xynnc(VYyb4Fi(LVn-=(Q^UZ{9s7*T&~K8Gwub%KKi==iX}A9 z$>c}D9&WzNG&kPbj#QV?Jf6ofb@uHTnoq8EIM3eRN%MjG%Pz8)BI!Ma<=@Ev!&V&b zuK#x}<$E2z$gX)!bJw-brL4&tniEztdW=R)q)h|LdeV4L>%BiTKBKw2nAOVQ z(I=Z|YadpC%93cVazOhM>4(HUHZsi@I|ShN;Vr4x+GhfI?o~l@gT;;Mp#IgHlpQ{> z52#uJwiDQK@}q65-5OImjwbzfa1((TsxS-&zSy)rp3032g+|`$oc<6*PaVGe!Wt zzt$7`3At1l5dWUweI;SgUxl{Y_S-_XJ%>Jvr`IO!uCum`-a!lw2?D_=OQK=HX>+LL z)+?Fj*7Zx#mx`VQKQ)^TzdGm`o3>F7RdVMM8Rt!dA#7LhA^5;Abuf;hcO}DyhC|X~ zT6cDCF5lbhInm}N4u@5nMiaiyH$HeZ(0i^ipRS^^DMG?AWzxV^hu#;w*%c37-O2{e zF(zg2bpn{}qy3)xn_>Tl)4E}qy}SQ4pJ~0mzbQgX&V8lrwmJlg7Vjl^hi)>wv!;3b zzbL^NJ@v8?K*ZwO7;mJM~36J9QYnXBq9KhAU>O5ssanFC5}>?lKK&_q-tV71b$F zd56XX(Q)3f+XqFNk0cyn*A#HDpzTwxsL6I84~p-%5N(6ErNG%ZdWU{+%_Pvaq8j4k zxQ)w!-bJ2!Z^wG|r)#fz;YL;pv>oz~SMsAwYl$DTyi|yf$Rc=sY&M)S)g>DGI!}Xj z{`77!ddEaqyM89I{}`hQCiCeW=~8~c=e5&uvchKx`?)u@8=U;Z-}m2l@l(0);zQQh zld|X!1Ltk1hJ-Iw{2r%h-*ribKnjyUI9gASp}|SCP5K9WqxinG9|NZ!MK}A=HJNuP zo_#hvobV%jU!t;fCxUn8>cNLkwB5eXmP2D6(lvQ{btzi3h(|aM7r9%&QRW1PV@s$T zP3N-PDRU@Qo=WUKe@4K;ChBL~H$@bkME5L#cRvWLo=i9`v&O>MVyZ!F_j6P|nAQvJ z-ocM=r0sCA)NaE^N)Rc7DED56JPoFKzVmo!npydeZ1 zX>)~;Ky89wS-HYKN9w=g`3C-P56WMAdLSFzxPkQDPV;mKTtwT=;-V*Na~Va-IvN0| zY14NS?#SInnJJVrd7L+jQKIdM9TM2nJL#HJR2&Y-maf&?J7eMQcX|&vv+OqeF`Lev zA66<*;ZMiIn+2NSeT?2o>G$7-%(%R_tS$rUm4U~-6C=ajR<2JO2pKF=IRfFkRbmy^n z+Mr<&96cRx)_WozE7gG=XRYy_{Vn1ze@vix?`W(fZWi}>%7<-&0U&#pO@{|qPh5j! zSW_hfo*B}8P^+>KA}`T#e&G-UB~f$?NL`-shn}PJu|dU>?e6E5RvPh>xhoqkf7n9s z>8&Yn*XAX`5hKE(JLlyj`adqLw#Gw5of^^O{K5w`|DL6K(&E72Q3Ht+wto0DfH4qFuIJnbo1fp-0*W9iXpcbgyo-Hrad+Qa6%7uC5$Iu&)t-Sr!CcjPjkS5|ad z=dYvfze!IGl}|AscKzA*@byn4E8`eGPXsL|C4yBC7r;XY`W{GPfe-k$ITQZQ{krga zDjh!`kL^LOj(162c&nqpL42HG#k27+ z5#ircj)Y;?b`ae0BN@WC(>>R{hdQ)%DuGPfVy9VPTuJxSK~dMxdXq1#%>K7$C`62= z`|_<(;b1gGp767t1j3oQ)x;-1B@O1ErfZIHkRDhE|2Llf2e6CKP!hBC{Udv$7UjSKuw-WzuxhaqmyqB~aRu({O{~{8z#it3N zpOm)StG*Zbt=DM$^INSF{ZD5Tr?cAr9^ubiQV4zv>D_wR<#<^7-~Dw7%Y*#)?+9nI zeIb0g96|qB5 zaIa?#=?gc%G*~20;~(XD2r^b&;>-GIz`;Vex#t;a+YB!LU)QaytqWZbx7nt{m?FBi zOxm&l{SQy@PuD#14vy4P4R>U+$c?oieQ{bXA8wtX`%$FVO0?pEHsRRcc7dDo zDZiv%AIi-bVz&W@f9l>{r;FxX)t3ieFq?I)&%(YjGk-U+E1fx z-&6@l*WVXjrP~nfXJ-QVZhw&J>8MbTUpwqAF~A zOUI$lkJC2Cf6=wVW7l}JV<(M^R>T>wZ+#4?wq5yPz~$U!WgY+KLHOX|#ElI8BOmiC4NS}ECe;9aY$w_)yjwaD{_g?_mi^W z;NblPkGPQps)c_EZsE;=WV;~Z=S_1DSUrHw_sg-`=$dgLv43z?fW<4Qy~h-FwC?0% zQg->t2zbR%4Y~(Dqv#Q|?{w;d;bHVxQubTvWEgHv-xcW{G#HxAXxx>0b0QROr0rbT zX@fqD&?o%-SB@Zl^osb`YMKi_Zqa#n;idx2+eFVA7Yq&Ir{Yq=sk)d6aVNJC9O{<> zF-3GPH(!c}t-I(Md0|czZ2Im`{Ab$shUIC!32wUM4<2gGq->v|3830WHJtWx1W#KU z+t`2VMC#6S2>p>e{wT4e~@IG6aZ zU!MaHPDc?uDli9*gwl31yz&W|rqZ!-Y}Ilkxc`#$<6qxGSQJm&ZJY97SiEHuDck-y z4WNv?zQf~W6#-#d zvxpuGTV?R!?y6+Z%_}iLj`sP)=NO%A=o!#X@aIS2Fs+QX^Otf*SoUBju?Hy>z=RjH zkM;)jhEb&-*+E9d;-`(FkiPO9`@}L%tl%972d!(^9ff?c{LD0vmy2O9jO{Ca;GFXh zE}mb*TA$~O%crJ6yURJY$H!Q4c39j$KGiJ)L1CK_v&TXKHU=5N=CFKbd4nw&Cs(63 zYYERXDGf5hpRkgRt3?)75m0_ve*iby+A{vp*hMe%axh$!BU(_8UOO;%Ho8yRyo0 z>@BoMB?eb*PLY(qxsJwM^uQjLTgB7&4*(hV{1126e{Wz69$}jzu|9DfS;hI|@!yt8 zJ{c;)`8g%*{_zsgYx7Ka-piA3Y@?umVXFYNMwFq7bt`zi>oOqa`AD{8{sK`*VLq&R z^^U!tSSLq96Wz&3tN7cFlxp|pgPeKf+CkQu}93IrA!`54vc3$ zZ488gTL!X)r;|ilUIkEM9E3|I-q{rLz6VS*vxiCjRxo;*2C(4@H61T3t_L3eNc~fY; zMF2_`9^jy|nDJjR5YmE1!`9sSjFB0FpmVR;KiMlpV+C_zgnuSx?ZjdqyJGZX`wf(A zCdb@;7!B8s-axxSj_G+X8nlENI6Y;zaEDVF3Kk6kgQH>0kJGO3(L@(JOz$sh;Ley+ zBHeK5%_r4f0|rC9iVbdvG7~;+FoBu#=Hkx3&o}lx^%`C3e-cd`^OR?j9}h7(XOYnP z4KHYA98}&uhW@xe;FTLDK+6L&ICEzaQ>thMFMoVP%TF3G#ovSByy;%F+WtCs$tyz@_y^gi;$80IrA5>ci zTMMe#hL$?fii$L-H28}ImZOldE@&R&Prp(kmjQpqUgX-7(qcgVXFL5t~)hnEE z#r?9H@<2U;*L1_{{=-|k`PZ5JoE_#}CNkL?4&yzxqKo?u@S4`AfVK8}G^2$3)=wM; zJ?BboOshlm^4|-<=4}A1xnjjg_bGst2-y4XC8CMBd2lNAB|GR#sc4&4ILuDz3nf=( zFvpd>p>mELUU%?X&6Na0P_v6=e>rUwbxp{D31eTd6-_He?y=!uyMGxQJWnk0UzG{n zwROi=BO0Z7HpZg;-wQz)o6U~fStW7}$Ocr?z%J}rD+)7Cf`RI0cwyycq0&VwIM>8u zMT|gXfb-#V=mqvjYn5o-hgeX%76306sWGK(3UIIgV`Lkk&dlzJ0JrlcNBe!%5_)zD zU>5g2_FSp2==OeJkavi}Kc;F`MVH(|$=AKG(@f9mqUOFZYeg2mpFUrFA!PxYo4)`V zl%?}N7iYnCF6Yk94d(4B&4%N>1guq`8quH+S@6ETi`_f3K(zEy5O`>O<6n;7ukXs8 zWg7Dwuyyk8n%U2J|Mcl@!%lSlK94El?)_(bF6FPBGFE>}q5zH>d|>BQE*B}x4ud00 zU9n`5QH{lyA@HbiHXhJ(Q00a_a!_xrgV)q)i4rbOheykPq6aBP47Lr17|XseDPRUu zX66lpKAEB-D>Yu8O+IXTnaAIz#?$|}kjt4HU6D$(tVEA@7s9d=8n{VetjMIs4O$BP zF!N+b)f@{I$c-9+&(7zIwB0CwVYS5ORFBb}}uL)r4Fddw)HAHm% z>2#1k+#qe0juc6L7Q%*}yV#9^b)qlFlR-td2ab%&7Zr$u;K`PK?EXWwBH_y<_$&70 z-a%SaZC2PHrid1?!#jkc-&3>Toy}b7s`@9w0h1U1?fa10HHVRoQ^$fYWd84-R=!3})!lm39x&PvR zI6lE%G-;+6Jbt9aPIx+3)V99>T1P4HAKk6dd-Om6adAbgc9BS=-75$Gv7I$hDd zp01D!6DgQ`!Cnh> zTpI5#N?+y!Sw@bi?7ksys&O97{A`O>Xz25#L3!Y^NC&@PttkpyGaVLuwZ}U*H`Xj! z%D^0zo}igGmQh?d8+5aJ;M*Q~q8EulP;lZAU$~=2Uq8JNRt~OU9}cb)eLa>Aokl(I z3g>*$vC1IW-sp)3Y*FPNfN%uX*|} zw-v%}X{ycf?>&T9xO<}RJ~yZolK7}{H=W>ZBXyv=pV!%;r0nFr;r0=5&YrkBGjF8$t;D~ z7fZIIxdRFaE=|%#k0zxO{Nr#P+8S&{aPmAe2$=kw#ICyBS-5t{BN8iijERJw_h<~f zHf9R6U7&XX3KanCA9*a(Tw6q^9n)fE+79sw z;7D*j;Y^W^MknQ~h~08q8f;eGPJEu6o&uq#8VOeVmK0OE`Y|j&Iw@l(-;b1*1)BpFR6ZGeD(=r?~${enQS`*wDZwji#lL`J5 zKNb#q(Yi0baT4teawT?e6KyD|8Aq^R*d)+dr-@~Lny1eMfmaK8mP%C2|LMHV>AY}d z6yeA1LU8Ny1JWiBk3>RV*?3a->Bj`zJ4MEXGn+pJv_y#b2`S2hGnF()H}V{plZ>VP zbucRvY?LMt{x-P@5NkA#@E_jE0{45=zTRX!Y-d+0oWLiQO`CHg{k1n)tuFW$ynkzQ@@Wy7|{in@Z}X(;xu#O=iST zg`*V&bvP3|tXdb2$=xH`+9IMr`#YV3&PRHn7XxF7{p92v(2b?JEJH4rB|pudlzl&2 z5iW&2BzmT-i-avHK=`@&d9Y`s3wf^JZf@OJsX^=$YzsiXo3`%wMNu8$Y?_h^uZPj! zdbT#m2QeE&+N!-q0PuJ-c~<-F6tHwyNcfQ{S@3zlD6%GGbLZKDk5s?oayhip+n(qY zPBVaBrZjIHUK0lcN9z$k0eAAjQ8)t2`l7&pDjZNzB-kk5AI8?uoTtP=4_;2wBYsY7 zasqEIhc4rvF_;b|k)wzPl$Z~lIX7s1s|#V;8k$FaxIPegGoO)XJzygK=~MfoF2ql0 z&!KSt&3ocUDJ~4uyp|C^3*rT!lJ%XIy%`K&p9~_}(x$k>@XlmnZ@7{TU(pQW=Y5YM z;ABYq#i~LPic0zr`vZwLDAv3s{$qR1gB>^B?2$=sL+9Yxm&?zJ`szA~1C z^XW_;WR;C1_}lz^SQs;q=$!8A0fUweAb9I54>%E!N;rLwWP{wzCj=+VkAQFa?u0YC zbPzoAzf0V7`uSB?T9snaBdE5&x(Zsu(^@0IV(NJ z!_dA{NZET+jbZjSQ!HzTfRWa)=lFai!~V5dptV&<@Q40sV58ET_Mk*_hu8`whzfLt^F2idmG48n;i{T z26UlX{vzIp??Eu&LpphG%F8wE)K3C}zc+8Tv3^bWK`-U2DD9k-==401013}$5N(C0 za^b?p&jgpL(!&?Pz^{2X2z?wx+R1z#e;) zQOXcM6&?1_XOBD4UnR_i*9Ej}+@C%ydP2(%zu9@z%y21rR>j#&*rt$8%Jx54z$Oj3 zN1pqXySqttFemn~I!idJN9TgktML#j&LQ^T4`FNkWL=X-c%s;Lezj6zKfj zP+SO20Ul&;s{bi~&%fuBIyO{hfhCulmX)1(Y8w*h(O5TTYCTeFP9}Dwz6rH-Tes*uB#l zQLLsh;d|%jLr@&GkFY<8F5RcG&FU+Iq1d|z;eT2X1YV}O1iu>WkLIt4OAtdn1iQwgouBBh8zHV}3fCdvAy8zaLf3eG5j{le~-)^vr?A(tDPh!os3O zgumJ`3y%A(W@Y+6dSt)?kt)FtHxelpL)L|*zI)~ zv^mSOvS%4REr6pTs>Ek#lP|nT9Z&G`iV0A3lg8VjCOL4{rkRvA@1Foi_xlje_RnhY z&Va^^3(gLOq>*$kAJ}OKse$y2{CbfYJakJTWu4A*v6+OPRS%ilLC6luzu4apGB&6X zpA&8TAggE!;oB$W!3%$Pg0<>$!JErT$uvI`dqPSBBKX$nQJ^p{nQ-pj%7(fa8Yj43 z>5t|Tx)fLNmIrU{2-JMyHjW!hvu=(6Xg3nr8 zfR>7Y)aBCqEXck-l=wf!-Br!WrDHFxUJ1halt1^p1>Ag3+u5*}A5^UiCw^`eJV(c_ z(mqN*o(+@z$HMJ9O}rk}li}62Dd02Y5-)z$NHD!H69Tjz@S0u>hM5|H5Tf&j_bgH2 zAH4A3OgP$gpBLRr6SPiD0m=AFyb~EC|M6L!V@sZ^P-}z}KF1NfTzH!O``f_g!mbFFoJsz zA%O5tvI_W?8?Eo+{-0UDg>=2@)i;7|T@*n$W@nzD3LSq^R)O0O{gwTR{nc?re6ohd zT3PUrom|Ev_RYr~!0-%R(;QoL@uyR(Ca!(Ng7F0x$! zo2_W9a%5{A8?~Yj(dNjVF+Vxbxw)by4RR*jBK4|X6b(uNh6I0--Xex=aI_< z_w(H-Lr1TE3*G9yN4@l@Sbv%&Q3?VduUwx+&2mSU-*Cil{x>)&nFQ7 zr+D1|h~Vz7WY20(X*$|?m(KnD7Dl+(o1RC)PK;rHSkpE+^?Ef*4hkXsUL~CwX{xd`Q(G(<4U?lb!rZW31zE^&qdQR;LbL>FO1Dqg|`P1N!hEv521O#sD^pX zE--)3WMcp1Fcwyn(y@9Z)Ce_wr0q7hIT88(HGHMgP#rRTWVN5lAoT3I#Yz7eiX{pi@6Z#WQDRZ{*? zIDjsM&~|?LMit-y)%oU$J>NW0r;jU$yX47jL?1GrG7s9nOa-Fo9Fop=mC; zU~*rP8Tr>2_3l{+FKkqp{#}3h-Eo;+E`+rzGOa88P+e6zIL0V2BYsz)?mh?U-9fxr z%C)F93cHLn1C{X)Bn$Uh;Xl`6pwEG1iB0BJ7MUl*5!XqK|A@V)@Ux>NDZ@ zmhH%O?FZ(DX$o}rGw$bPP!*n)sQ)m>Vd_S(=KeW}^cVMiT#+gi_WdYPk@({7oH-+O zpk4c}=3j=G-aL&=JL;+eySvyV>1gU$F5 zNkPMLc5IOV-VagYEv(An+doQxhr6dTMw6xJ`ZjxbzHt-d@q~e?Kl?+G-%rV)8J;*j zQU@Ns=#a#3pN{9$yTa!K2P79R4#6TW)?d2hft{bF%En|#2HK5Nc z0erGa5*0V!KB`;G-H94?h{m`I~%_5S|@SW>WPPB&W62*)=8%6^~85?9Y<5{J!B?Jj6k% zha}|C06cM11gtV$C|MH!g#F^L0iGR48Iw0|;FrgTi$_JwSc5UpUFQq^Sg?>!lJNUn zVP_vKfYd+h#Rm^4v6?su+Dk2&pe6fJ{D3%k+sggV@MGuMi}@k2@q7lu4(UXL>;-UU z^cZp7uZ_}q=LPWg`vLuw97BHl;BaVbEs`A0dCAUw!{yu+moOifC_`fDTu9blDse7- z%_>Pkr+(;Ig$t9362 z`WpNe_v#VMR``ww@8&Jc)_oJ;|Al4#(>VW?od4$JB+wdS&D0wmM2q61;HyJ{WNZ6f zcFQMk80}XtX&BrGk9$=BPJdU4gI4rp?~b{P-sdXU>aUN&3x*2d(P2v-@8LH7{lAH@ zcLtw{C}>3AAKO9h)Z-Gf76W|Z<78OsUdKF;8w)$Xad!g)i+Ov`^gyshe>X0=4;iz3$QB>;nQPU3^g`=ymb!omAZ4AVF1C3-Nc7wlhlni;<&0IYQkVGD0R zvsz*Yg1m$1bj5e(aYzz$%t->dRCkGV@j-SbmqQ14CrSIAooo`n07l1%ct5{tpq`&& zAmD=+bL;UHl(ZlRrq;+wPUuFk@%0m-O>Hx?JJ{l%@i05oll$&*n?&(Jf1ExgAND$( z6#G<|vR2gz+}YladB1=~c?G5r+P;Gs=V=YU)wICSwTb!gc?KL*2!P&>ilG56&gEi1)v+V%KtW`Rmv9V*Oo8 ztO-v5Pt2{w3A49I^=(7JE+~!Z<@_0)ddj`Kvwfj{Noy*tzze z^q^5FMDI#tH0nR2biKL2vrb?}OnQsrHl@RUw=t4(m33^>n{?29ZY+uYyM`^h;SbA- z7BR2#dczLONwBiIo|$@X9Q-{v1I~QiCy|D5|NFf@27Va(FnZS4Q1yHdz zy)VSTy;a_f)|#uR)iw`;ORn)^#@VBun?}H+QTrIVIa8skZZ14}xjO1&lkXJU3GEJ!b0iuS7C7RV*;~K=^YB|)aU-k z-$ABviX#|BWkP_Qu0-q6ayEa30KOac7RxKAO6N4^L+z?vJfB58G=5_u1Wopl6c!z3 zAGwFZvr%cxR`t)wNInBf6%-kb@HMRN({zx2>CN<-w3aAeR6XnUs0G+HP~J-J+S&vsR&Q}pv_gLxr5^;Ts(27i{0Ta*hyyOf!US3KE| zx|QUvVaOK&K5Ddu#A)>xQ}EvjG@jh)iLgHRJ&Y`tVvo6V-q&MdKr&{QFq*3{~#O6AMk1rxF4f=n5~H)(IZ!Sj`%z!hwbtI zvG*QeQ8epSYX@(@AWI<%Q1Qit#!GJj-f+DDZWMohg6ciOD7?3cEIf0_c zOugou6K2JnbB6gM=lh-F?Kf5E>gww5EBqX_g`)<{DC1+# zm2`$)hxvJI&hT6DxnJ z7!BL2`Fk|B;}lpV;q$C3`oYBxwr4WiO_HERJbyoW2#$u83f|V#ey$SrteFyS=HC46 z2~y}cm%lD}72cn_s>a72IR82}SL4?b<90s6ec~%wp0~Y81{)22O}<1L1s}+s59~*F)JZLbIaUX{U=(GWUEoL>gh!gthe1vb?_>=^4 zZt?30%|lh8fb?n8_W3eW) z8{swpvINJXC4E`BXI5)SF6FO<-FjAXb=*b3w7gFLZKA(o3GcsVuTX{819PS)$iNe} z;>L_MCk+APE&Mg?Fg+Fcym2!d6WY9%LVpFnu60_v7I!B5cxZkG_YY8noaNWRXL7;d z_jW2PZ}MRyr`49fc0P1)G0t4U%MV{XRx#r}zs?{pPR4b<-6FmTxue$vrsqJnYP`pU z?>ovz=izyW`0IMEkqAHR!(R)3J28Q4;>P#8XFV(MNMHVXw$SOR;#ub%%>NHB$u|pb z@av5c;RB)Y=4hrre()#kQ5(z6UICKb<^5UtoAFxc&;))Rz*2mRTj9yCc_tomMuq#F znM{h86TC0r*BrVHwTIsMyq~Ev=Hjol>xY+D_uc(k#;>EQoY9B&XL&y>%*%gi54Jay zna-qh!{FT3fsAeAo5L!yKbYouih3KxzY<%?KED#FZtHNv2@;tSIcK&sS=-)PGf#boa1>m=zmKROV*^Q|MM1RuZPN1Gb{s#LZx8eG&*6tTyl=t2O>sMN z4M^klNH53PWZw*BTgz(P_6^?#bRIv$9%OG8Enm4(D%qdU*Ilpp2i%NneA~OQMhxS8 z`F3TQ_7tB8=kq*r%q%SB`2Mxvm@}x5Ye}l-N`vK+noTVO@2RM=h=)vajYEBI*-;f9j^J~ZIDVnR zSCe1kePh^*YkZbJr|7Hn<+{J;WlXv*aj#<$VWIzdCwTc6!~1e!WbYl-zi<6wiN^Ha zj6I(kz=bs$jIHMfzzBq)w@mdvnsHL{(mswITRk!krfzJ) z_}j+m@Z66-_wD<>8@n_tW94~jnVg9MoD$@ANX31DZ)pA&;s zH*(?DiLBmzK9O&Kk!wsUzq=|E*VOjYi8bHdMC86BEw^j+O0lLXpPvGiwp^$ElbQa) z*KzPXdOYLF)8k?D9R5C|`5f~8)GGd-b@;96aB(~T9`!cb$?&j2CX*i*7y}KXc>U=* zHIm~MJfBxSsi^Zag!t(hUC89~x<^6zNPdoCG;sjf)~@9aae9V#KbA3>lWCDqy@rqR z&X=|LRP7qD>8V)~3rj{QvDm$n zM}pTKejL*}q6>w2H(49lPu@>3<{H0Gqv!EN5FYzuCO;l-`Z@}hm+|dW(x9iJjynq& z5f>{CTQ< zL!)0}7y8*H)RO79IoTC9xbkD>i%?To6B)qD=bX`is8GI-D?jauC&lyg5W9s=AR94) z$&BmM5Kdh=$l|gv2!jKWb}X(c>m*p&unm*BHQfhF$(j|7B_(+$epblqESu@h`Q7AW zneNv};=6*E*_K$zB}DLhqP$m5hK^*-ogUk}Z8&W0*MsTV+*S;BNBMKd_JT9m?ht=1 zQv;(RHkH@uIwnyetkdq&224*i85@(yhaad;Zv7DOIm(YAF57BwF?q&}mLHpwArC#y zx92f44@qv3wQgE|DQ+Q7ZvK+hg;H1Y&7CF97+<<910P@emT#gvrNz8Vu2; z{C$&2=Q%jzz+V?EsVT%+i+Ef9W#N+48otfX-m(T44CBk+ge;Quv@>LSZhQ5HCRw}> z;rkZi`$PG!w7Qiu#xv+$BnhP=LUY>)l=~rf7<+%#dW&dIM66lVaIOu8wM>$^L^QF z!T|WH-IkT#+}sD$jd(pP8*IdjPT8^YlcLVxR?&iSTk@@gd5d~7E)Fn;GF3jVwLVMm zzVm#38Z}sf9mtv#_5VPHIW&0Git*Lde(=?f*MEP-2E4jQ~iEWn*&`8*uznyR?feLt(a$rqF1Lo5D%lXLge*m=WucC60mQJ}k+ zpSMhTpbxiR@wtt9dKyb>_d0r3A9kO$j30Bpq{o7nt2a9~=zRhthw^izaX6Ukpvs@K zyc;^f#{j-PjBA6yXgog;+;6J}KDGDyr=~i>CbB1n#%{B}D_EKtF^-?z3tp0E@MwAG zHD!2I?Y%0u-Q6W>^X@Ra5sSyes=d7Y-NwD(nm?cC!>f&9-BkV_{mZ~9aIbdHfOgl7 zcr@8xWw2zosET~oZp;jAgwC%KC3NwJX)#JDfV|V*d&)@gE4ad4os%T0sSNpr-Ex&s zbmn4F^@x!$c$_wBSH4ChBj3#s>a=;|2EI?{6c4%A5fnE*;8TlEF8|~;2E<$kq1AK_tJ)1LYBeVjZschq>rw9F;T{8E*XyyU#ZgPsv>mT-(;e}s z*ZL8rr&o`~2fxIlOLrTXnjRd1w^vL;-M+_}8tysF*rS$({%8J-M@0`BnC49$fjtgP zMHvg#OoP5|!uvPABHV4e0c094HfpoBH@Fq5!nB23 z+hRNv+_yNQ4#jK4Rzo_0>njH+o0V!(tnC8na$lsc{8N1Lt1i6qTEwlDIE&&EqT#1Y zDtEb)zDV0Y7M$O9fCm|d#zp74fVGYijC~!p)PC(qSY#|hX^WD?oejOfE<%cSTI-uS znWQVejU9!rm$(<*zZ(zYv{881Ecc>2HSw^GTtj8`A7tA4!*WIY@zr=(o31M(xCs!S z-5qHTzba1qDTWfQP-NKA-E{BZ(>SH+2(-_mt?B%84I%Dj41(w(rfTZx`09N(eAP3c z$htfcs(N+D_ZRvV?dh5bYt^0bk&8o%bQ&c=@(>jm-|S#dg9^K@X*$YImr$Gs@jbyI)SHaW}ji|(V)OfO^8ld3;(ou7KdPpz6WikC+Q7NPaY z@FmBEQ|Vl4VtF+Yo=r1C4=W*Xy9c_z_=ec(stCs3HpKx4M;AR= zn*_JVUy)3&)-%~PKN$`L{3P!_YbsuGZzOE#umUehIZ(LbL=?c`skq?0b8BK6qN5L`U{Bu0-}GT$QY?knI=Y6Jz;0R zhFGWL*rE}qR*AkSA#x8^pWnQ2v|BiAOCF0BR9ToNj(dYYI$Y(>CLa=Q%?*L@ z1;)t5JVtzdTuS5y)bvzR}oe9_sk^&0Manp{K~QWEz~_f15it_`E2h zQ84sU*FbL_ti{1^1HfFfKf0`;YI@hdB^=wbi%a-2UvzQ*WGMC1K{^|IiTAAagB=sx zKreq|@x>Th=%5{spY0MCLBBZ2YZc6i-oG-DOpAvGWN*?nrw!u!D$by+9*@o(9d5eE zDjYv*6^_~kb~9aJwikaamm;%P#-^#Lhe9i_he9W(NzwLlDU>=XD@^+zDI{y^;CJpW z*Cg|bXuaoncxGmelDlM!jmL7}+i-`(ROgv-I=Pk^(S+RJ9Byq|v)~yPwucVki?PPi zM};9|4ZPVtEw1IP2_{>DrbD`lDbnvYQyeqDI~;B~0htH7n6@&xjGtYLL{n$_na+Jt zj5m`#jq_Su6py@P22pPLxMIzPLf^1ypz}}e0?{=(u(+zFkQzgFj zxg%t6n2OTN`k0=YwHf!yN#L?$G(<5j;(~5<;Q%S#*?iQy`wuO#A+o7g96U0u=-e3?HC3)mH-`HrL6ud^L za1YA*m{gyg4l`G{aM7NnCfBc!?3!KA4hxd(6J zL|ru^AS=#^Yqq!8#QH}fJa%}(rM-S2db@fY)NJ-ZJXU2aPwuDax^zPu&R-NqtT2OgOv|T+%R5-K3d38QSN3;tro^Bu+Uw8YWM+M(`k8e8q@^1p#5` z#c~hRhldW}u-2xy|Ig7y&9)_h*@DqHZe^Du{qyl~)h`k0JC8EG_T3YYH{Hz{S}qht zB~FG*2bOaaF7*|Sxk277UC;u(mUI@scuMAhXj;#O--B;Rdqj9;A~{l#hq_q2t! z$Yob7SR_B@Wa0Nk!!C@2xtBu}4qe(5y~ve9x>IL#>v4rxNp1&u`&YT&J8<0?zmYl(M98%ByXy5*Ccj9`6dNv$#AKO7dK$?CzD-PiSQvbi|g%eEm}dogSU=bz%8}4 z5nVqN4JymLxR>gmO_qxj;n0Aql4b|<;J# znebR_7;6Ui$M%QIDK%n`>sqi(BM7kgpjfr^5f;iEX*mq$G`=K$uB!?gXH9{TiQB~~ z`?urpvf*I=u~?ixu@O8ttp#aWGsMxM{lRsEE9WrxXi3t^M6iiAKuajXd_DZ!i6fSZ_ zRdao0ZG!EgV`Zk~br0Q=z9CWw|2_*le^M4d7!nKnOyA-K^8>}Jy~o1MHjWB2H-(8m z`HptOX&GGCajj*;V`AWRcyn~1(=yrAT?1j_gfZ|XL?+e>`hZ6~8Vc{m7mLpiSB0RV z9bxL8h2mpTUBEXvRnd)%ClxVLcsN^vX2Ft)BuLUxY)$lnU|MmvX%G;SbKgB2$*8JPHinsNkU;GDVM1Oozhb z#<FIB@+@9NxYkgjE!Xy9Vn*dGmBGd9jY{;)@u#o)n1sowb&^ zt$l$Zyft{o%@z;e*cWW0Tf>5++2YHkeIdYeEV3)fmCf(=7Wcf;6=p~0i${&H1W%~p zDwX18SI9Ny`1RIEmcCWCL5zPy|V2ZTe~J8Dj63 z{h>-l8@hYX6i?3f2jjvPP~@B2vc3KKLP2?4~vfT$@BA_CZPF#?1oY`=kP#*0Y^> z!qO;s+~mB(t#wd|u`C&yq*#H;yDTxh=fKgS9pvYwi+7y&hNpsKvyEi9dX$Oy#@a|Q zzG{LVcU~_$I@s&~myeP12Sk6TTK#%$XL65~Tgdk0$AXT!3RG^36g%x421gc&;mzz! z@%iW7p@UKw7SDbu!foRra(4t+SZ)-1FIs}aixx$GRx>#2rNyJD0`@v zWG74E5%JBn*0+a*U26GE`8&nOYssQnR>|=7h?eB8>WbooOHvp-(vTa|Z(~XN(jeHOIh$ydDBFv26$z46*EnEI`GQpBb-XJiM#C9;MdH*bJAD=-*_t9FpYj;bu4aZm~yFBWhn zqK>kDbE3eYbtzt_WGdcc5eb<-Mkr{+TA5vNuV30j>*f})x#xVb5!vhbU|uE;{HY;U z_{PBDW0_pTd-}3ZJz}7Hb4#QexLG#bzyktaxT6k3cgh}M8|XrwT~+3$$&#-GgYH{P z;GDC>-h;ZrHD_1QXp$oiJZKM*kr+>C)LA@-eCJoubS_>(_A_Lxje#5AuPbu42a5)i zcQC(QeTs`66eN4$8VYloc0z_hJ7hP$I>O0Thq;0#BV;?TPJ#iWUD0Qo3fbso_AvKJ zNBr7+yXdrg5;Rr6!7Y3nC2R2{7+Q>ZuXvLo6+N{`hGVu(xu5p=B_GK5fv3f<Ju6GkziK%2dR2{KJo41$AlG?g~+;6ZXs>#FRpw&{C+Q0xyhm?p~eNKWK zFAj3A4h)mw)?u)rVj6d0fU2x@P8?|KY{ymhcH;6?Qy^%;A}mYO5-Z5}`VKUV#F~=# zqEOP8p9OI^C3wHcZEhmWyS9(JF=nu=t2_*}oR=wPD2YVxdysDmwTs5`4xdDqvf`lH zC|EM5#mC~Ld@010U*YZyohsY3Jp|s5I>#*4^!4X{ZDhjv!DanKgg*oY)(;3Mahjr?S- z$vd{Ux;vr7vhA{AC!8U!NP&y{yNad9!$DQe0;dn$DDurtf{RB+OKv;7DmGjxg-_$2 z;JKP3!~>R&1DBQixb_BvWjBt5!L}2Ju$6&#iOG{ma47FE-v8aZ1i>UQe!c?Fy4AMi z=B6k(wR0SvdGB)ZC-O~7aE5b-&;%Oz?S3iGq20VqQZF4 zaxB2BY}%FNmqfvyiyC6G!VC9~&n)^oaKl`GEP8*Sc;%7=5VHBY1pLY5O|f&QI5@m! z5xx`IqQodH8je-1#`AK`N*20A{=&bLf2-^a#Hl4dVEvT}WEH_md7DdW5E zbGdzETQUBYaDqGXv;pI3`ro+klP)qJ_PDl0Rn;ip36SZlyAlKl0WdHO#^(20qG>VL7^{71fwsm-Y=!~;LbI%W96f^T5_KX?HN}t)Zj{fI51xItyd5$0OqFEn8=j+s3M87Ld|T?jEKK6~oM(&4mF^EotTf*HduQ&x_?<6rq18v;=^)RG zuIVXm>he5jdA4F#M_#A?;ggE$PrMH&e3bFtXx_KdB(nPJnmNy5#sO=XSq+e`l#<%lHYD=+BFB2xSG-wsRuW7)z z_1AK|(M_N6@x6QSR};Q3+;TdJ^Nwh;^5?!+aLGl!PMsg!$312@VdY6-Pw{XyHOAFO zukrC6d_Ubf{1XmPd|~b6;Npg$dFwUfJ=;`ahV(h#mWmof<>|YO zc(>pvD_4xth5SYe#vjME0g2gG#xCZDF#k(2W5atUaAC%B#$It^*j=)O@q`v;(5pC; zaaAJ=Sg<*o@y(uAaQyHn#;Ot<*tL29V|{}TurQztW36i)LF;a7#_eC(!8MPMtS?U= z;Q)U9<%}Z|9igSx490VPoWL42WZd$S6W9z}T;b7$@;oxuqHC%A82E{l z2liLc@;Mn!S-W7=PPn2BMS87@Nq%aO&=Q#`!r$ zU>383afPfM>`L0r*wnHu6gVGbJoc0xdA{{Ln3ivv?XJg zaTjnOZym-HOHN~_^LmW;m>IEQ(1?D!o-XZlrP8j)6E%s8)lJx z?ClwcCnw{z<^1{1oV@30<2B+A_>zG=!XI`Fpc=l+zeX~_GanW@J`j7 zpsEFGqQxKc~>L-iEnq$@gT=?Bc%;+Q^Kzj!-iz5DIZo8&EwCk!-1rv|QK+{VWQ zwH~^J@dqO_G@_WF!>nmyi6TZtu=2?DR%n{mAjXaj$apO2#Msi_7MGw-Am3R~8W`CvlcC-Y^)9LCLx zEYLbrV0^hsAH}tQ#rW+sHPp$f8LNx3;yc`NSH9k(?rh1TNCeriM$#)woBvX5&nmBw-{)K-h z|96;&3w;=9sfV1ZHi*71_XQzuPHT=fCYOkgtQiOnYgEwculb^ZgNH#}+s~Xwrv)O* zwWELG-^mMY{T=v&(J0h#_Xm;coF7=o_sWK#;kvIy;L{k+KJ1SS)t`!nw$TD^uMc{X zcTdz{o&GQUJNdsuj6xrL$h(OTq-%)#4?3+7@{i!@$o{9g7-neUeOnWezni+aLca?R zm>-YgJ2w%}924{l|4v?L>+it2&QZuCyODU$`9e;}e%>)CGgL)vu`!d|_Kv*wu(6u> z>4M3ewj+5?Dy*?sV@!`<_;>PuhZu!EjNBwa^DB>vG@n}|A+OErj^@reE9&=IjMm%q zK`Xyq7KP%rXwF1`@=cE0qW4Jq7yg~R(AM99yO*EhmR;>H`r#akgnaa54X4*|f~eQN z@n~4uJMQIyB+>mRW6-3~MySR7Iii=_hX2C9lm9!!DD>g*qW2Q_p?yrOEs~LtA739* z6|ihk(JHdH^l{_1l8W`qjMUFck=^EE$jy&ibuxsqkkXQhZoMI6m^nnw-cn+p;|a@MJ3_O; zyGpucclm{XCoi=1H(?pMr+~;k1!Lk*J=f=oyMEu>+W+Wx<#Y?CzQoW71`W9uVl1rlDc?}%X0~}LB|(jQ$cMwDK!xjo0!^A zYS2(jY+`D|!r+C7*aT|B?AsX;u?f`1q8Xb+#3oQ1fqPR$#3oQ1;@7q!ViTy1C(TMs zh)tk2=sihd6Q~UmS23{()CP&GgxCaXgTz%rYy!1G;wm9Ff!ZK(l@OaiZIHN1h)qmw zkho;TCZ;w>Try%)L2b}+isq8qAaTiPE~yO?myG6;+8}Y2&|Fd*B(4&gOKO9}RYG$~ zZIHN1XfCM@5?2Y$CAC4~DyF#<*4OX2z8?Sn^;myi`}aD()Ao&<$O1WrJ-nvs^=+WO4g8fhK=(n=U(ft_v*+FU{d+cXUnO1J@cZH{N@KZ*1N?qMvd5Kk+n~JDXye?iUUzZ1}hcUG&$Q$svb7ry9n0Y-rFrN#uUzg;D=17<`$|RSjwKiGZ5hgaA z(Sg0KRtw^#^~lPpFM@b!J+gA@iy&TN=O6L@QZIsd|JQn~iyedH9fEpMTwd*EO8e=U!sViRuFpe#8~Eq7fx7eI z{yT6B5$7l%HAs>(*)t+?$bH^4I$Rin^m~ zK(#T#o-}K=wx$u71OaWAkV^4TgL0hE1r!@W?a(uzGTynXvTqx`P}{0!HgT4 z-{h7a@nd{ati#Sv^jLbnA^)G1lfNS($9yBlA#yxpq7M^ z6TcAgk1_EV5x)^FCvhMW4`UJ^B5^V%aU&8xW0DV!htiQmxuWukIFTkNuihFe7E0m-VGaYe4gblKj4o3v$#k0GR5BU$uN4$ zT1m`~k8b#<6wbF-tJ3RsQF7^366newDRy4)<4!l92BHV!uvVL;+^wwfa873pw(Wa} zv)k(r2@@{kr4L?kzU2LIQNtU;@yCr(R%kmAhqi)jYdthV{t4TBHU+V%32OMR5}&?m z3-jljp~+@T@Q@8o5OK*8Ems49Uirud4UFC)A6DiLaw3!eotN1(b%}e} zBPqoED3-t0z9)&6CV}U}Pl~w%`*EwgOoQ8=f!N!B3AesS2smFa#-4_l^S?0&x+k2* z;oa_WJ%@A!?Y5tBYQsh-(bxiRej?BNjM73)%hVxyl_A`E(GFd+uf`p^S;M&mGc@-4 z68tFF3D9LLG<={DmPfe#*5}{F@+akdOZ@ZkSv4rKiwb#9Vx!7TcNoXB3SkSc*{nRT zai)8y_aes8Ju}>0Bn6CjM9+2CcIWvR;f1xlm+;+Mt|DCG#>?D`o-5y9%XbKG>&5HL z?wKLC>A~A7ZJa6ZTkAvP%1rs)Nren{T#vjxhX6KmGIbr`! zZ`J9&DSH1XTIsPmy=O)5D>+wGtCQTY`*$sFf;zo7Lhq3z+Lx%;-upti9i{5@o*2F7 z>_nbn@p$VOrQ5zQ;w{J{rvN_?xR=IO&Ikgco$}pq$-Wpil3Co~*sEv*K z%QC2b`dhADnL*3w-(G~D%b@JPhrN8+M>())Cn#6|r_pI*&dL*kl4 zb4hKGxM;lW{vC;n=7H)#BrcjCsvnWKXx`ZUI}#VoC%b<~;-YzG_wPttH2>`W9f^z9 z3!6*O`g+;=w0V8q{X5qksb$he>HqTo>iO@T2Yx)!ntq4wbNHu@C)CEjdOX?j+RlQG zS^v!O|IVtZ7XRw;|KyGK+jn2*KoHcB^o*F%87HX=Ol76g8`!lssnz=xgmQx$;^lqzA zd1@o#bn0xXhuVm{6q!c#(_i~HC(~#d{oCTU&C{tYJ*MoLT{_i4b*&ufn@)988zipu z?QMhE{yh>GEobw85*L+c^M4W-)x+lhB(8KC6SYC&N~iO4YJ2ONHv8Hb`8mR6qTZxKwEw{Tqpk=9$g^ zNnAAlZ2nK;qV>Y&|Fpigw|&6&@734cziZu*S|)9j{xAQpp8wu?;K!4dDz4^qocU*t zCuGiQ{;wWSx(*shs7+#nF||o-Fs3$%4Mb(AO=5#FwMlF+rZ$NU#?&UU!I-z1!kF5mxubfhO`1E( z)F#axWonb=jxx1Lb4Qulq`9L^ZPMIPrZ)N95k17Fu)c)cyoQf)HIY#_<&TXa$8KuK z>+~rbiOLu7wl3;-M`zmcK3L2%MFrb=-v)gD$u(Wb`#iAi7A}g+->45KPx04@l&jO1 zm@C)rMF~l_#$9UnsC*!Mc|vOUuG}JfdCJWAJuUOdULNh*y)N&`UY<|~eh*CK{vq)C z8NWB?4B5*wvYOvBW0MmPgR=R(G~dWxo}tNe(#M9*~^pLp5K$xgzV+X zGSdO-+pxoakf-X**sqZ@G&#oa?Ky0s0~%}iJwFnYn>hL>zZdAs&iU9gh~Fdh*7?4o zvUcy#@ay9xrnP&DraT_Usm}~!I%mA!&wbr9gmFNp#^~lPes5BGz7=}5l;5+IYuO9! zFX8txt=1faTw3yboc75gkSLnp`*fV-Pgr;L zk8<5Q9%b^6t>aOsTgRhZw~j}-ZXJ(u-8vp+dhP4)IfdL)r~m$Sdpj@LFJjl-)GA$5 ztX(T)&m&V`X*u~v*FPE4wMiNqEhJ?$H;joaTX&`9Li;Jzh)|J!s zOv+TA{D=Pj)1I4t=I2IirZAn9sUK8-ZH$bmed;$YC;w=SjB8_LTwBJtHpYMWOm)!% zsqWSv`;=0qHfj5yM9XRWpj;axqD=J&b12L$`5TiVVsvepG4+$^V$9o2Vca9ch3+k> zE2nGAb@Fs=nK9AB)_AF1YExjB{+-ECS%IHy4VlVQ-D}PyT2QWSlXdY@dB(Lifl5$4 zGFd>7xS0?Pe=yKXjL(exE@SasgB#ZY3j6%{0zmElo8^D;9;hUglKnE~^e{HUUj* z+!B>4w^Zxgtv^cI=7?-JJF2}I)CnDF>xXpp{nYGrTOpOGV5AfgtakR(P0mv@27PHB zqh{P~K6frT8TltCtHtlUAt{$i(RZm-%||yy5uy=~5}L-VC1{6Z%l?zl*8!8%%<_-o z8M_0Jnj%20RiFk8xY-58*K|?Ke$W91q_ss2Guo;Z4DJJCdp+m!{GO{iUkQY!c`LY^ zg)3BdkoPrqS<{@$scf$LHf1^tH&;^3-1Rf{=`ATVI^Gvw+toMi!Jz~QIJg_{knc|W zHheN1%2$RnOO(?;ekI?eeq{lRpIM|AxOhOq7%!MN(kngTvX7TBRRLwzMhia>+@MtVQ#OrI4t?_Uav9E>Ku)!=xY@S#-sEy#=nrg%*P#ZsYomV9`f!Zi-Csidjf!ZK# zMupe}YJ=lm5!m(O7 zh6~4b(yrLKdyv!MRl;++@LVsP0|@5^!a0L*E+L#_2ykUmZOO8JGx6mgLz9+9_>=zgXzP(y9-alwM`0lzdr!w4i zDLlUEjVYhJlK@;sCF28GlOd>$GSKqX?!zH)p#|ef(>*}hz>9IOmLh0+Z4_grQ(y5} z%?QSCT5ZIeos$?ltnP@(vviDyZg0?DP|gYDIe{KdpdShBB7r|h;3pFJj|6ccLA*$i z2PDW3668&oTVXzbkr(O_>KED-`XlsH=)W*7VZ6dT2=gP%TU|cA#UITD<-g=#pa%=| z|5A?ve}1WVf&ag>6G6Pcv@1bAg?WR4k)tKF{e&)&LZ}(fn+V$q${QfQJdc#;58-(R zVa{j-JGO706h)mM&Nz#3prCx;Grl~Il($snKDoj+6Mls@^$T}{lt%!f1+O~FR&}@rywZ*M}MdK1?56{Bq;wQd4Zqk5B&LM ztPtc!X!jR?g!+Z@f_g!M{Qp+JP+rg;{<8e9J+Bh$D~9ZGSH!6-EM;vOz$XEpxbxCaVd`kpJF(f}G7o1@Bk zT4=hhHYoRPi01wfqb*B}A(z|1#pT+gYn|Ie&t@K6?(@#*GI<7nQOSIFOrF8-J5#QR zyOD$*{!royTK2&1&!fRH^>&UK*VdK$YrA-_P+l$Mm`6I8#H@IP2p5X7hT+zD= z%4k^!HJEv`EowYp59wWM1p$5^IqRL~sF|%XEV9|farX8o?u;pnGR)?*_Btb#ewOfH z&`>U>RcCZf&kEvoEw~rk-B665HJH`BlX&jwf{r$@0d31N$qH|GRGDZ4qvlVL%wFOC zi_b#;*PZPzr|rzHgNOWgtnte${RvaKre3LQi0sZkVJep%w>68-`Tm6eM5j=O>LmXEL;wGY zsUO6D3v!&xpYWgfER^{Zo&Ps7)bGDoUw<{;zpDQ)wTHjjNB#rx{w05C-Tj~1j8NvU z*WJJ0^^R~}C!EU(=Xf=Od7yB9Nb|$j@t?)*dB*|w(B$ut{|TS;3`hCB_OLw%LSB&? zh)!g@VC8#;1tX1-w-}#$IT6{tI?Y%pBP`a$M3of|EX`^5L!9sfp(PS05& zcgeJ*@4I30)-;9YGPeM~#=E_wjn&Gmgk*G_TrShxxGQ3d|h>ncPm#c=n#J4;8 zqj@z;ysr1N8LLS<=@}p8St}-tYB@#W0B{DA8 zEf9?+dbUNrcxL6{{$uBzp8AZ6`Kl9x(0aHz-~ z9eUGTG4rwweO8*)X(yZWYiTTlNWE13Z|a4N$%uR##H@#Q+`>Vpr=zuNRk*M5JJvq& zibXGGrE)5ocrAT5B7IL{blB0gR9?+UwB}=1n{_&urOfW(*&Eh+ydY~UPfF#F3|!?4 zze-U?=<%xcT}y@BXMPAi2^ixx2LK`{F9sxT^Nr;SOv_pM_72n9 zOVviR^2KA?aQW%Sae0I{x_SCE=brt9m1{oqm(0+;%*q?d7I9%%9jMHiAFa4_aceTy zNI}QW+pVMRvo4>M>+(stE}xX^>g#`HUXSG;>#3^?s)yD^#!5`y^`)dl>*8`T$M~%-m)&<-Muzi z*2UXLd!uDtykSFp*9!Z>|E@pQwqZ`t7m%PYAVFV1g1&$R?TQn$H%`zFIYIkGw2k!} zlu6qFN4d70Fs^M&9BpH@ZGe^6wmnu}+h$mKZCjPlwsG!oH!IU^?GQb-w!JZ#+P2MP zYTFN!scoxFrnWD*Q$4lqjmgxub577cnGd!7g6WKVr-Uk1$~a+8{)Fq=$xXc6g7U1_ z%@tie$()Mx({H3NyCOZ7&ql9V|7H24O!_s;CzT=n{g=A9Ox9DVo|D&Y(Ehk2^rDHb z!qnA_TM-|L<~isq?zfh42Mhv{c|dE0v+ql;yoEn9xT2#NJWU(b`9s_DpRgcC5ZDD; z*R{T}v8dK(HWt;!f(0?+I$Nu=m#nGF!78cU)&T zUQ2K1KZBo#EnY+VEgaJCXe7R9k5-$zLQKPR6+&CjKAqi8WxjrhwGoyZ5&3mQK7z;PQg`jIVr&hL2;i7_Yw`4VV2EFg{Zm4N;2-U|CgzT+TXPe-EX-H|g)X4&?Mkke6(>1i`;C~S%mGaml2I~Y0f z@=7=wMGofq>aJ)+*4CH|S!YAJvAq1U58Y9YEw3kW=up(|IIrJm`$QC7>$BB!8*~=< zc(=5UL0{n-^I>O)5L6P_lIisOw+%ghLyDyb{9AAy))nn1he);li4_@KEFZ@u{*(LIO*R+B9lTY=SE&QkSYhgdF z@a@3nW)4p7NXSAN=iy0AW=x1B2j3$2xm>$aPFrOx<9^9+IoXrmj9VBQ{9_zWB=spQ z7s?Cu2=$+|k70W3oHDrvpNBFoe5dk@Z$dx+gsc1VG5&ONhri0gJk)UviA$*G$zwkD zABF}nOPSBfxRkeeWNoe*8I|HjwK;4YW{HKz3d@D^LOnwL<38~@DSod4iM6?k>6D3m zO{FO5ZMIw%FO$&r<3idGc_aDGh)Q>)OV&CbJ+?twp9i65s=0FCn5Jl1`9$=|d8yp$ z&>3!Ta4d3)$d|u&pT)iEm4xp4i`r$`o-$@O_AA;iO7}o z3&YscT;;}CG=ubumzFa)?V9Q6Ea?|k~2RGuwF6EXxuSTn|cd{?bdx!so>9KUJ z#zL&O^RF^J_tWzc|KI;JhsN-}jmmw;{Rz`|%99_wa*%c2Mwt9yp<-B<;n(faLw#ph z^gtPZSZ0ZynK(ly@hseDsXls2%6+;6J{rQ?>QnI!FRf8#$4CU zLOs^pS7PLI@#i_Im#@!NeH*B6 z1OMIHfYlv-Ot!u9o}1Z0kB!OiuN~s_2bi%j+2nCH_dsOJ#^mm^oVl5qj%-Z6mAGB9 zwf0=FXz}o>p%eIVUUSDguJ00kc3v1i5V&s3`SZeBlUdx-tM=@?a9l%$eS?dhQ;cfX zRo0zf?jF2Y@h7}eRSFf!Wr|}tx-Ngh2K(`DDnCzEivEaIq=?Fg&b!gY;18Jiv6ISE zU;czU5d%%Auylp#4` z^-J>8LLAMpP#=~r+~F|FUt%aY(v_~EAr`W-q5 zuIwuNuf)%m^keH12CEZ5cV~ab-4hca{?Z`EkNpy0$onCTUzjC8M)z5m&dIGpV!_el zl7jM(tYjz{*oW<_bY3lmaceI#nNE*FAg5CcpfZ!q27>B9d&cHDuJ8@}Fb-U<5B8hK zGS;8-8i$olVXT{7ju+;~Gyd{05Ic@eW_;}2T?M%oVB9Ed`>x$Rr!($yT$`I`7tJ{7 zbv9RKHG%QvjB1YiJcw~kY*REc2Qki4v_~csW&u7i(SBjr6 z`F!3p8s#3>i_hn|3T;l$D~8EerDSs3)rcRY9+meT<4)q?jHh@sLhCp8Vr*1nh#ajQ z7$+TcK{N7NGk%xS7xg>xiN$iOd^B3vM$TB&d@|ZOHjeQkzc|z+`w`1SBj03Xo0R2F zZMAtOMIWC&Ww~1Kk&LVh?=YEU^6ntbnre3Jdff?d@+QyrdJ|CB9A2iFe8cO%+q|Vd z-uk(EeH*B61NCj7z75p3f%-PklgwRvyw8%;x$BfPSL|!m3DU20KxczX*!|p|&6ZjQ z$)njm@*WcxyS_P|!`_80GOM)MT(q9NFDnI>FYaTx?Tr?9Zb&C^er1cgk~#1WqVp%2 z1KW@}@It~iWDXoo=D?E(N0B+OeqgSG%3G8 z4$gExxZxJIMZwTyf4qCflUq2%k(8fC?i=>i;PrdP!^4vf?s^qBaKAml&?Y6Si|M*M zI4pBKoPV~WOJ(Xk{IS(|Xl2m3i*RoL-uwlQdfpLgT56(?UejUH>MVIcjW(y|5)C>P zE9BO@vN?C_2_RarTz)`W&3#l3fX34n%1g#KMTJEO^7^loPuI@DVdr_W$Y$EDW5dfMUG~mcFB}vGuL6Fi<18$|{NyhIT2wRV8 zfQsv7iO;G2Q0U$i+Ij17y)XBJMXAkTflF6z%qbt3pwS#I?U=}ooZB0w-fIS0!!x+U zU3iki?h0RawE&~FW!&mHZlHBh6P!v8a)*4K!0N6RO8Os%&+MLubVyKgx8XZgRWvlMYVi#bO@|*YXK=43*@--HlV=h-HR+-Oh6SW<@+q58W(ZLB21UI3yWFiE_Da zF@MdtgWSV17wfr{n4QJ4yVr1*tuLgdy~gXTyTR(yckuA#SMcE7AuxM-N~b!WX!}1| zZO;E>)x?xe7Ynao@5&I^SAB1%BJCQs@Ct#A>)Td!U3e95ObLO#lYMsgUvUjPd4#}% zAF;bHmR!S|Q3$L!@Tsyru{Dm^nn-N9j2;XcHX7EE2gC}*--=viw_Xp#@-rG~40O8Q{S_jyqb zZ=tkyjbt)XY=g6opI6oJQ#C(m$`bJFXp|R2iG@`F^?`};h&spqI?AcmLwV&Gzw^nk%x{p1p$T_W_ zPYow;v3DWoE4gE+Wu)O|?L($;yNbGyqI;t%zjD}a6l1$g%u2l2*^ni%gNhZHf*|63U z0}QE@WIB*I^ocz=F2s3OXG zFr^2UY~)4y+pTqjd7ZtX@AO1d&_M^7zPl&nx{_cTa8R6+eS0KK%AIIhbSG7rTRsYM zW=S$ty4zHldMXxzS0|a&hUrFKTjr(Z^>zF}V9x)ohc^TXemAoNluhdic?JJ>{H}bv zJ`$1yKfF#=-jt1kN`ik+@n*`>ld&*C@W&*jQ+|Ssv$gN{ucc2=K6*_}`B*9ptiikw zSc5CtjHiC$-Zl)Z!PancAHhleT=1hcm|trRUTK~{{Jw?4&>DQnP@Ts0=q^UE23wOt|Wv*7Vnx=m#P!$p*8sLwoCV>E-2%C zEWAEggXf;>NP50+{spYTyiZz#V>|hf9@CD(XbmnJ*bWPe=bHAf#qY2STtwiNuZrN& zeDH4vf~mB*2hPprirw!dnp#|{ zi|tDP^V(ILT+}(@+P>l(lo4f@s3*j=6-Ec){MOlUh`2UpR}bu3$Q9kiwQY{nMQ=sR zDQ*6s0ge&p+8?NzWU9NPE3RK~Nhu}f;edXF@qLYMieFHY=|%ZSEZ3&+51n}f|A{$| zi(4+ZD0rst>WXI;Us6g6p47gBaqy6CN}%A`Q8rTMD^lF7T~~CfJCWwA=~=?i8Z7v! z-K`z(LnmqPZd&vTLu>Hg<@e63-7ivGhk-R%kI#!6MLhd8kH)oPomnqW4W&adbHredU25(KZ(OG;0_?y84KDW++s~04hGVXVSTQzs9qfaH8Vwa8t z{}B#qKgUGV$G6citmZt!#-v2k!^d%8-jG+hDB2}(dJOmu8LG&B80#GI6V~+{zE;FD zNa$H7^lZ&lLzxv6h)sl^#LP8Hk$@hUF7#YEkPRHuYNM0TGhFciQpV?maiFx)?mF| z2E7&Uj*CV^NZUlykkM}Hv?&4b_~2C2=bW3=&U^ZUOQ$KOW@(Sq(gT}<`@Kn~*>B3@ zu2=_1T`|ezo9K;4wmwug8YY|C!vL(fb*XaQeTr#cjv(y*DVNeeTf8Y|O$?f{IGRhl zignTcILz6os4BQu*;SqsDSos&#mF8bgfgEN%(Bc_<%*oNSn9WRZ=JmXFE#QQop-_X3Eb)xC~`Z(NVE}bGbK#e{~bWy(O; zo_*n(&@g7lYo)~FK$s~sd~2{uIgu0v=S8`m#f-{fkq6sK;PvB{8$}RCLGdE5!RTR%6O`P&7{$-L(h3CZl(2(zlf7;2s;w)OBp?~&IM%#R$ z*fSx~q?Slj3O4e`U+X5APS3fiOrFyj*C_F(J$CuQqoFHq7aA5VstX&p*kU!Ip~{`^ zFsAf6^}cb6DZ>~Dug_LdCk~lv8agH#)-^V#c?u0}gocH~@+x(Nh66KWXdlng->iCm z?Cz9AW9RC<5bV3>g!(!y!Q{SRDE4@k2Yt;`Oa(vtVy$;o@nW^frrl!{9AMW1pRb){ z>bAZt4z1G%6CEd;zP|rMZFV&PJ4c8y-gJXHxosqt4U9Ln%IB+w%#X#@afv45*K_7o z+vD(cg4pMI?_u6yX|EFXyzA?@q`+Ly+v_LP5L1FFV8&1^n+kzjg!Ivf#r~B#bgf?gm z*7Xb?T_SbY>nNDMS&Y*;?rP-v5iq4)l4*PnRoz;yE1VVMbcJJXtWv=MO}C2mMq&-z zT+4yVN;~BJ6V^Ff4=ItF^ePHw3C@L^-PP}FN5Evk`7FPx?r`i17X@cNvA>w3vH{u( z&W=-S;2q1@EGNdM>E15I1rkjaHjRX}^RmF06;n-l)BM2WxALHdO)>Re+Y~k)X#j`2 z3f$KTo=xly9qgu>MmNt6QMZS~mp1Vx!`pqzoN*CQG*6<*bL0T!?4nqh*GK4iarVcv zYUswIKXTD+Hy2Ii8cyfkt%M5=(^riI*Y#Q8k<;zly@y3zJMEOzz74IYIc$Daq8X z{$k}yT7UH2BIdEJkCYW{+Th4ViKdI!ibLfS&4mkZyenY*%QMi71w{N+0@R&wm>j~xX6+I^3dwi}z_v8{=wj(r?qe^Y1lo0eqq z`3^Aa-E4}(jI?09*f&*uu`f=Zp^C44xHYVP5>xs}9Spw5mPBE>|XpIij>tR&0 zDW;K1O{~49GbZ1iVmkafAD&n<1iO@rH{JbwM*Va@3@1NHFwJ`(tA@Rc!F{4XZ(jc0 ztZVMyVzKzXLW@s7fw_jQV^Y-~DT$`EHzRSZ<0EzO*m%=`+x>C!gcA5cXlQY!HEv3- zhY>=LWxKak_5aiY7jKwmx<952mU1tE_UDsL%_BOBcU0QA6YDW?-}ooic^Vgb z>ydJJ6u$nLY&u$Yn;QCAzwhXex%$?t zB0uKp3onYKay_A2&nSUH&)nTZ;92h6kSX;1TC*!;zN`oZg`RVJ8bglD23R8WG(K7# zI`wW3wS=DS275SqxgXRMdNLfJDUTdg6tiXUmTo zbN)I}ZS&!jsm{|-IRB}U8X(@o29&P>`HtqPCf^+-oXo%OLy6~VwI|N_{(TY9_x9y` zD1HAwK)fT+_y3EEcL$RQQu5#ig)}=YQAe(5r69()YX^9D|ebqNjWRdVzdU!b;{p4M^|vFg1@rhM{DqZMZ1riK33*0 zL4RBG3fp^+%-6*Ej5(C==1vp+)mgm)Vg2+dHMeQCdM=_jbgQsSUE1v*>hQ|Vp|IOC z_3D)@xU85nB<;wL#ai3rLCL2cYG~ij={^E?WF_3z1{2F;KkJtw`h%;$0^qDh0*`z3|1M1@X z+~x6BmTgMZ1y_6-RRjm8+dyx}3Yfms7R$G*2#rkzaDAr8;dE>agSx#{zm?vs26y&@ z%Wiws#=nND##*DG+_;IV)7I>2QuQeK?Lk3xQKyOK!N+3Z;oKQ!b_OH-XJJcwS-u&P z|DX07uKykEQQ~ZHsiTfK8~o2OKd0#bHT-AiVj257(77?$V!Ux;@fV6b7pPdRei$@- z3E_;UL0HSP5Mf8J7#y|uzDfG{sB!3W*jtr2_@MaaF?cuOYokZv%RIIy?KTy9;F0Jm zgpc?)#LL;65$^ci5kKwiML2%*XLZTj0K#XptXEx%M-x6U%|)ISM)=Oev#Xh1Vg3r^ zQ5Zk4a)IdqrW2TcVD$o4Utn7$+Eh|#bSl$H%zjumaW5aSdNP( zSyuKYBe2=Ama6pGoDhKzZZ=V+Pjq+?CX_R%(x=?2!Dvj}MLuCIM_^C8?c|d-b`bj5 zttX#gub$YzKO0J(Ed{&drCK&9c}|G$KU!pYM?S~ew8DGqDwEHQkOnwmQF-#|cd$O* z?^gq$P#LqDl!n{*|gG{3j% zjn!?*r~cSSYVjkZ$j7_dI`!nsA>?!8dy1M7-%3Uz8BMRx6<&N=K_evkN%T>I0!$LB*nPxASb&#QdCSU(T*f9L$+QXRFkcB6NP zzy!=gtRDXm z0@bQH8|V5YsN-&gLj0R5#sYUIs7q#rf@^mtW9ZjOs!#J!D8Apx*sID^HDgK$)ZF82 z%+@Yh9px1QjmuRvCWTH{&)g4&F%zm9`!1fTa{VtK6jUk>^1%1EYr>MvN9h~1E}ved zZ2UM*p1F_BE)8E(Wlkab-fhyP0#09lZA0IznaJg73}-I z;!kz|v-qe5YE!v|-_?Nb!^#s*`{+XJQCY6MziWU0d-$Q{tZB5IHJu{Pjt==ZXHE0| zR{o+JtP(!K!iQfgwfvp^J?X#ULc8=SAY8Zf3*25A77? zMI82Azba*vvfB{3C=z3Jrd)0nGCIabW!qmjl{yQ zOopcWIw@nqBk^lRv%#i&2W7V4{H?3mF!FUfrM)<7X{@u^(5_+!;_=jZBERqDM^xL9i28fDi>9ADelF!Nhm zLp71}*yq#mdbM3H8D@xlqJ!Bx)XVydYUuJj4%g&Y49C}d8Y15R?8E*449nk;YT&u( z$M2N=6&8CWM%hk=Gpn~-gFOy}K)w4Z_0zqRl|RL&^MOgsT_H0)z~fIa?;C#?|3~^Q zzc#p4ywd26o%vUnP(0A2u993^!P)OC;`fF%X$*#im08v4@m2X-2w3n%wsn(tZzTJT zdgfIDdy)yC-<7y(_1%Jsix}f2?$pHf;=5Ei*VPx_r8e->=BS3PLeWr3o4fYj3Byyv zwK=VlZv@s}=t$R^ve(3Qvs?+UDJ{OUi2%Yy9cy4{Cv8q^Db7fL?55!kY6w19rQwnr zLaZu_Ya6>mJLjsK=+~z%Yv*5G7H5dfu*}=r#TjDTEa$*yh;!f}zcz0-m==b9^R)T= z>7#JGX*nN0L!1x)+HyYpx@#f0TglA^lHt#Xm*bY)( z&kYy9FS*;$c~p>Ub2bbMOh`2pI2)(#SP+SIr2MUPJW`Uh4Uek+@;7YSWD*DyuQMO8%JxcvRQK(D8Az9L*TD&A4z z`rQ=6Au$()yw`lheDdQr9RCW7AF=pRt~J=2`G@;hesctuW@b&b2J^B1XISjpgX^AJ ztHd5Y{u!40`?>NqUM2tC8oc;Wg4~a?DPBGlR@!zW+`eWcbUb#Ia66AdFlMWzRtPGtI# z)l1~k{irXpI3SA;vbdpaJ4-xqm|4SJ-&V&=Q)#kyS=JJB-F-_j+<3MRuK2!>aQ{cc z@oc)*rpwER;^og>$$q?MB&K%plKYJ|^UQJRZTKR_s*O#){IQsI`4m;+B{M^D^QR+( z&jt;{>m##L3|BVy!=~lS5WdsCB`z)PN%+hCTKMU8Yt6^M1bQ{>x)Z+I`x6p?jYP;4Xw z4+$sSyL&j4o|{Q=_|hd7&P-1dzcXZGV=ulDbo%&&Vl|;vEcNrN+L)qt`72yuYh6(9 z!>TM^u4oN**%Swln;bJ`jBqtugT?RrVqo6JRpf8{{uxeuf7FmyoPF4$OyVAEu;qMU zIIwT_%4bb#$#dzUdiZB^gOXJVS4jy|0}nV5eq*~st+y@@;ln#KRq-F4J1lG{{*AEk zMR5&b!GVIyC^-c;HlG)S%$=tN0uS6cec1<0S z9I^~)w{R2g@XMkUW;Zf_h4CniUt#4^85TWMhQxwHFGJP~+)sZ=(ezN+dVQt89tX)o zSd=O2Kvn8q<>Lv9MmcFtKX_p+b42ktvN}OZE;T7_K<$wRTwq1@5%`5#^w_RH6 z-~W%aot$svT1NZdf8l?{;a`2=KerG3a}UYSL0bo2IOC>nO%Bl338gpb??Yv=7*nbV z+0zm$qWn)9EjGe(FT9DkM%pEZ(h1nJ6um6^)iI!hn%2bNga$TDS&q){tVYcCN?I!932wLh)C z;&&fcviiz)1o`h$3y&MC?@w_SuH-MZu=@VgUjL>Y_4-PGy}nW}X_h>!zCZOJR$tkU z&xu29d&=%j)bLl9#2*-Fg-uD3vaK(6Yr-8Kk-NHs7NGZ$>Jb+8k+ram_;`d@7KCuc{Uq-(tYqZa(4%T3)QPxBI-~V3t z&we+Y+r>LX%H5K`pZg!d6MP)#?9DS%YVG{5z+3iZp}e(-!!g*_H7ns4`(yC&5)Jp= z8-o>cWFxzsIR?+o((F5gyY|?pCa7j%MjcWbB=JD+Yn5-Y){zM zIR@<(jVIi#WEjpLx|*YuET1Cxn|2P3fhl|P6MoSr z26~F`7^VGmMe%KYhX}%p%7?@7j&lk3@)z%&0yKQ8Z}3lJEx$)akk{UJZ354qQiLzl$H;QIiDo#-aJ1Xd~%%dt=;({ZvHXC?`qk> z{m;_~FTPL)-p<}g_+0H`;954BaB_pPus%;BVdvDc;EPiU&+seI8MK4kTRVdPNZDn2=Aj_+7ju*Y*-_`=mOI7^T_O%<2%UXn4NxNy@L`;K$V= zkF789d~~f0XCr?n{AEf>SXk~N;cl(-{8aa2U((deSw@QET^}0?Tz{(iz3hiyn;Q(d z#Hp|{jwOe7PJNqFL;W%?3g0hVVjR2bcQwb&K)m^FxzVxO8MXD)AsFc0$`~IulKjK7 zyQOX@@2|c%8;)78B^qBuJuwfx9fLb+4mD2n%S-o4;+6=s`KIkvUYXk-y(SbV|F;X;VERjK-^>)=5|;t}2EEN|x2AX@XI1h!(+BX* zu_}ZgcWH>_CRZZt)1oo*a*MQ&BzwUbzG{sLLkLegc~*7l(UvfdDTYUP214Gmz0C#N zr6`9gjfUlGN1A;CmMc{kj)rWPW6ew2E>(6E4}ud;lg)nrSftp03xHyko0`|ZTdSO? z8wlNowK2OyuTeUM1;VzrzUC`0Rwgixh{B&7jNg zh4HFkjFQl^10$SM{q_{RgT$|yvh3sY0+Ins8>!DT_*Cu~T zH2qiHYdB}s-#68jdQNy3-@S6~GGo)H;_RYpig|L+d`hS4(b#>>MRTPrO_Vu)A-HBy zSJf$?v*IuM_NdT>YS||)^}dK}znz%7`*?vcCFMmw45)QX{S1-Hz4gQJ=!=Ew`M8Ek zimT|ix67(|TWD+VnO!U5pW&d80P6Dt+Ez>bkKpy;+PZG`!cEGb;X><5sbb#1=e4Th zyq9Q}c*u+DIQT{hvX^R86~Bd*Bs{c9RZJ+T`ERaY6@83V$zHLeGd>zukFZSxCp^5~ zoA5vEtKj-Qtq6DeUKs<9v?jdmab+xYsSV-x7b|0l$x`ddj) zzN$5Fb?@DT^XIF9_Qss+G+ofr$#q^2DmQn@fDIKURVTYRq|B-C z?;Qw#U0L60+Cm_oj4^>5Qlcslj@UkWL*|Inq_h3;T}o)Z28z`AYlCWVGCi7fUaQd; zs&+P$PlYUd6wi>Fy?CWSUZcb{X=C7*GS6PVgb0-rxFz zZ?D9P*PQU$Qc>7GZ&kv@Mo0hTGxAm;9KWVLH0k(@Vfx`~ z>bwvBP~_o}`c6~h)Y=ciAa_>Z`ZZU?nz@_=>n~0+OxO}=^xo|c%??~uO1(tmMK>?-a(0En zz26#>XFpS(Z0iGauNO%>CH#ZlPBM4~olaXP@aW284B-pQnkEYzU2A}0&gM3zFoEaQ zH5!_>8f^*}_*Uh-2FNneG)~~mybJ1Y93E`$u+|^4y}zpbayLdTZ1+r=@sDmWbM9uf zdM-~GwYd}o6qurh+D=#Urw@Z}9*xzbE6-eBszauFz(4wDhk?D9sDIoa2tBGSRqPLB z$G89wh*6a*`wglhHAF~;%w+4_v%!yv){brVk~r+@s8l@t9O2CsJ5(yR=q%xu&K)W(j~XD`7^AyC z*cH&Mmg(WQSR8j{oB6YdfsA>&N3%UTo@du=Psw{xWUrj&A=>Bf&4+CYY3(>zv}414 zS{r>6ZFIY*)^-V^?Ra~=X6-v9UGx7a{N4I!{^NvyJ)atCME4QkUSXZG*KJR|4MKOv ztDb2t7-G6{H4b{Ld2R4pWMdxNSIkAU`a*X5w#_koZ8?hX&?!~1_cQHT zWl;UxSiqqx**7L0QS-$QBRp&IX!Yw3?YV{Pbz z*=P9v;IX3}#r~^}P51Og%HHikRIdr}P}$yzdVq-)2$_n+*wqZL_rekG2=1!DV_mvU7fJ=l-0B^Ye1K9KqTOicixtg$joj#CO<~?EO!7ZSGcUhD^ zfgh^E$0-Wo%e!+y*^yldA8&e4DP`n2(|CSJpR~h+SiRc!;bcOkapuGb&? zO}l@=O;6>_CG9?4cf}UvdvWdE)#&dwFt=<^s_(~^mEd`FW5Va>H-R00XnR#tzV-w= z8}XYP;;;3V0B{?yk?_5W(eTJld)LS{a69+sJe;4G%k^-bTtBZDuW!uuTrf6Jn`bz- z%nx)=X(Q$_zw+8VRzb{T9(%NTETMKEXkJm9$EFNy0lnI2^Vs;eRUs}>o5wg0w{w5a z!})o+ykBwL?70_=%kG9U&O4WtgbmrX{I;q0UMjBl`;z@wSc=lI*l5DpcGXnw)Q%?X z)2pxHq$Q^<?LJ}JHLsbk6xB>d%FVZ2<+hcGXf+qpmI;rzT@ zu7~U7`gy&08*$9_^m^qC>A^rcb6hL|E=#qTa35~x{=83GgRPm9xesr<{|FY^6fqxC z9pBq|Da$WJ5zef<#*p*1c28W{&Q8rSUTf1f1?H-g7iewzywqLw?kKHIL)RC^-h;F@ z<(%Bk{W%Zk=jC!ewFVASF7}B4**`hvb-y*o2agOXO!}*T@yB-RHJYoPe+|VQ#itTp zwIdd%_C87Twy|>@7QvY`Z@csi$MJ@6np-Aj9g5Evo+dnXYbX3I)Q-vx`K2zNz2i!F z^^;;aA)mJQeP-f4)m&sC*>?|}p_XnJLfGfb3v*?ow!TX0($9E(p*A0K&D_rYIS=RO z<#Ih-C)dyG#p}!Cz~jT?#^cG`lw-@hMC-KYpQ7RTSqF;qyRSh||HA^pJz*d$ym^H(qa<|H<{Zht*pPpf^yhZ&UyJc@eqJuu z!*yEp)BMb_Wlo@Ww9L1JE%Pm5%X~}y#4_I!w#>JLIS;pUf6l}CdATWhJm7$M_LFho zn2&|{`umm0)x$N-M{~f;72OCA>+J-KFEt>1FtRC(dsv=u@6J7;=yDsvhg*+=!S{EN z=G6}(A&Xxt!ZsJ;V1B`(G)5Y~iGhtBvZzu+z4jq6&2I+bO-}w$u9~(+x^l}0=4H{w zAlJt2+@JGseqJuu!*z1~yk5M%<5?Vde0U5w=Iu56u`?Ww1d7j_lxFZO+>!A4D!pL( z@NX2Kv{R#CPwj1lmy37L#V0f)T;_TlBrMHNaqFBB1BK_&xdTYcQV^tif`u$$q5${Wa!&$r{YZ zGRKeo$|&(qv^DDBQHzzU^R#FDVJ9CdyBcZFGL7pN1v_u;89(@vJNVbGLt4*%X$wo1 zYtQ(_at?s)soFEXPe2ev4$+?Ri(Za~mIJhBd|no}bAQgm`FXiq57)`{iZznTk%YwHKDf!n!1=i&UkT&{=f z)4`G5(zh zk8OEQZ8b!DkFFdXqYgc&?Y+eNZZwxEr0L|^xSjiR9?s9p<$AbIuAkS7*O$kE$LE&; zahO;ukz&Fz?|Wt1?^E;S*S?3r?Ah_s?(P)l&e<#Dqw9?b&pg`*Puo`}{AN>k{9YtG z;j7t4V3**16#vP75!iOqAi|uV+qpmI;rzT@u7~TawbKi-H*f>lUL1RhJ%Nv{ijaN9 zqB^*LxI5tntBd03kJ>u0dHO>&p{X{9gmqY?rXJGfmIjwfsCA3SkpG7-`3+OQYVGUg zS55gxe{C+>jw_V-exu1J*YX$2l6qP$$O*5KkfU>JvU3gG&iy$L=jY{eJzOW(&+EnO z%j0himScb4_E~y<@LyscbB_63nqFY3VpmOz?Ymu1mDS(0SPh+40ydx5V#WQro%?eh zJ|`R*w%uGSi`GU(cmJwp>8Fj&dcl`er_jOF7Q06jM8Az42%qw;jTJU&`(wO~I48Gr zf6l}CdAVE|9pT@;a?-8h$+e?_w8{D7Uxj*OWQhWrgEuoD&j%EI_Y)d&V z9NJV?KF-(r?XzMll&`T`zkRvkrDA^5mwapkO2N9ptq4yYTo1B^)g+vAWGC2uO?#eN zbb2ssd455Wocpqhvqz&R5`LW$3$}O8(%MOx90&c!h0#2-W@!X0&flNv$n|hL_vbvE zpO?$^aGhK~uNSW`kAv9fRQ2}-9E+I!$d4EM{HX8$i+z67-wTL+e$?L=h<$$4-y?{9 ze$?MDh<$$4-#dtXepP=TA^Ep&yGGA1+|KZ;0j8xo5csPdhM#3DATd>0}y=jV3r&v`gM zFPH1#I(fTD{H*$1Q8#+;Bij)rw#1XLC7y&W@g!`CCt*uGsefAHN!Suk!j`^4{@l*} zIS=RO<#Ih-=YqJ6X@x`%nAFd4aStB|cvTpr-LbVlw4Z;I+RNiy2&{XVM7V_b7PRrj zOd5A97sWyCkiInTX3dX)f>X6|w>M(A_|3BeRF{W~y27SWxu~pXGZpCmtSVu%Ls@W2 zXhB%5`-hSvxDVm$byg`e{s<%-ajmjaV3xLj$hC1h_vbvEpO?$^aGhK~uNSW`j{}d- zpWWk5P3Z~STG&usN)K!%-c>mg9#Fq3ysZU<^Y70MTMl+1e0tGwCF9Oe&8I|+vd}J^ z@PZ1vjcea%Yv#QR63o2@YHi2)xt;qDU_6|km&^5VopGi>oHAb9f99CicggUBs*U?_ z(mDP_F6_{+E8%sytKqMa+P<`BSPLxeS(faL8ur2H*MCso;5^*U{W%Zk=jC#3F0cFI z@og`O-~Lor5}=jV3r&v`gMFPH1#I{Cf+<^2c%V=szxuXSz`miLT=E$zO zkL5ihVat0)kQ%riZs-1-hx7AtxgM^Q>*w|2_2qFWd%gn<@hV8#IOZ{Y_^dE4_3|N~ zUkvxuUQXJ(fFjrDsn0qDlRc=Vy*kxbdj_mH9fFS!<)M zrT-D|N=ZX)E&VC8B+Ndot)<`9stYU4uEfbTa69+sJe;4G%k^-bTtBZDukSPfs9Qt3 z?{hq_-*Cv2c!1h>P_77g)N}-4V_T6^X`Vy<;d`Dq@OiqK`pKXM;SiWJQk8w+UCCik zdj2uOXI^%JVR5-p+Bqk;bAQgm`FXiq&%Cj5VB0*FG;qw@y574%aQ?Rp(%*M;DAc_$ znQ)x=jmuU!FH&8&Keuy#&cpjT$6cECf?nCbQQbE`ZUV`(D^T56E~*5NJmfbSHa7lk zvOwO~euOtv+p0YHK8o;w?Osa3lTn1Dr@g4(;G4FVX#UPwwGGnNTAZKTxj*OO{JdPQ zhwJ2hp#3aw=ri7d^qhau3Eq~pBg{2$e{SdgoQJoO*ZWxL{wS5=pE)%gKJ^HpcH#Ym z`*S<@=RCX}t-*W@T7!98TZ08B==pvei`*Eao*yXk>l8ijPUP1qdOn`WuLC_#PvqBu zp1&vZ>p;)z6Zv(Z=lhBLI?(d~MSdOV`GF$84)nZ1kzWUTKB36313k}By zd7M9|OMd(FN9g-xZs-1-hx7AtxgM^Q$Dd=7qlJ2Ypvd1tJ+DvX@1dUWC-V1HJr7Xi z@2Przpvd1d>v@BmhugV7=i&UkTpnkRd7l^gb)e_niTpZ6&&Lz_b&8&+C-Uozdj6is zuQTg;eImb3)${#Cex0i40gC)O)bj&HejVz0gCf5U^?X8+Ux#|0p~$a8J^xVT*P))5 z$aQi%_vbvEpO?$^aGhK~uNSW`j{}bnj~mx%4d#8u8Z6sR-lMd?zs7v5iTprS&nFc5 zfvD#hiu^#-^ACA{E2!GZXEO}_=a-S{WizI`4+ip zEwp%DFvKpKL-QKGF{!&dj6b|gyM3Me4S_Gi`QtjJ>Y)Wr*nfr*Rgj8qC|&8qD=ugL!Og=JmnuHHuKoWAk>wtoQT$ySC>3ybo}H&NHx0KFI6n zi!$aMSM`~s-n<`5{LSW_GH=_W^|8JOCm8buYkh2l*DxiqN(A|MPCBIQ`=EUfV)Ho{ zWH#wa_VJIZLeIGh;VNZY0It;fOuLi4;p*%U)TS}51L1X+by~ZZi-tc2Yx%wTL>_Um z2Vd$-ZDWo^L*zL}RpM`RM#GUQ%Ly;p(ii5h)N&Z^CVPX!RPDKA=*1e~{=7a)e_j`E z=l-0B^Ye1Ko)=6f*U#(4>&xT7{2Qy{f&x*dP8t zy*E$W|6IMj2tHiXj^dCJ;*N`F)*+m1YK!TgwfXbf?fy8h*Q_3alVBeaMKj+eyvO!j32XJB0VdnhGF}O;|NzR7Kfdq z*3+~6+0U_fyxmTkPlnbF!^F(-itGb3^A5&r4YX(ZClA_V*2F^8CufG#!Tht_2^X4S zkK1atC!9F;it0Rm5Mi!?+qpmI`H7#E%k^-bTtBZDukWmEm()_C{<1C{^D%qr=n19Y zGVNVM9p6x8RFw9vAz%G@#%n zo~El?c4_YsX8*cL%^wp$W%0hm{kfg{a~|2}_3wjb7LLK%9wn&{bnPFE?}FwLE?Cwd z7j(Eqn719jmfN{M=i&VFS{Zxo@2@fM!`5IPe`~Pi-ULz)$6~Gi{Fb?$3ERzom{8BaXSYdtKYX(Tduh`SH>N zVXXf>8k=o)2E*qba|mbbjDg=LYk5{3ZpXoi<)7%R_QZakhm&b&=I-ZCx} ze{q;fF@I5h2p%7Eo^WPoU!46VFUWqiB3{8ce`x2$WVSDlr{6Ut`vae>*r%Hx;dM!> zdTZeb!e5IGR)c)C^#JGRcJ9x4IR8)OGCf>p@WugHvBCq=%rWnKn^s>?7v9w7%+!W< z`0`>Wl=a#%&ILQQ(bfhf8+qfj=h~Vf@<<=?TdnV?FFhXuCsLp6(>Vr546!E-Pn?2rS>}AgTm!drf6l}CdAVE<*U9zsdhz=5erpZpeZv~e z>u3$;ZM0$GFpPyG6f3vnKwLa&4PoAAxIedZf6gN`%Y9L5Uyga*E&GtvS1tRHRIX(o zlCWhTlCWhTlG@s`52?!jW7&r!Y}tn-Y}tn-4VHaK!j^qV!j^qV!j^qV!dxe}bAQgm z`FXiq57)`{^Lp|6@;LDL@VHs_u0h6uV;=Lf$5ivTJKFr&@5XrbNIh+h(O9|=D@-wj_y=OE2)1sh;&1MM5kYiG-0E0^YE zzxVc|8a1ppVO|$*=l-0B^Ye1K9_QZldkv_lcyLV;*zMH-_Y6`Noj2 z%<`&TBMlrX5K4*%#1@yU8%q^hLv0`okeeM-=3+QvQ zm|GNmt`>8PqR-)CZZYa}JFg43bAQgm`FXiq57)`{^Lp|6@;LDL@VN1K@;LMO^SW4r zd7rTc^FCk=7M$|^uiig@VEG)Xzn8SUZ=x}7dEZ3X^1g|%<$V+JSl%}gw!Cj5Y{5ENUHj|Ade2*M&C3B;R^=f<54wRPjut#0Pl>Dv92b8)boo(o)7AIMfZ7Frs`7fiWpX5#5teTo=dx>Y4*`R}OPqKftt%NmFwOpww!8b4zeO(cN#aC~nF?hf+8uR(O5$62d&iy$L=jY{eJzOV`n>Cn^cWbbW zmH6JOqMT=}!Mx9ioGa9Gv_#Go>bYCI-*SI$=l-0B&j|}=G*drR(Autd8AVM_&@hiV z_vd!*&w2Qmb(|G}%O3StWX+o{j>F;DhvwlO?PKv~>&G+?zu6Ol?WSq(AMJ|!W6x3A z{_y#$?Xdl*BGgaDt*MQtdwLKq>r)8(7VJPc=ahe_D^zX1+U!1A4LYRFS3b9on}haf z^VPS^Bx8d<+I*Gk*V@*y?A|j9C&O>$buq%;mFzc5cf{4l3lKiyItXXn*4{6tB!yrjRXd|;)3q23 zEMQCHdeDP7y#4B)LG}$^7PoVM&cpe6xm*v|$@PmI6?u*v>Eu|9P4Uf$cGjH8*OKSL zkxr4vCC`f^Eb_bLIdX(W-j_UIj(9{qm^^omu*egW=g|=s`D5~&I>MZv+qpmI;rzT@ zu7~U7{2W{A2r|x=atT|?C2T2|u%%qWmU0z&t)*PTmU0Pmes1UfoQL!Ca=9L^Q?!-% z{$2a7jbr{DocxAQmMwLPwo+u-63cJ+WZ4qSZ}?={63cJ+WZ4qSZ}?={63cJ+WZ4pP zes1UfoQL!Ca=9L^bFK0~nY3yEmCJG6$#Ix4N&CJsZEGwZYIcg|Oiu{IF6Qy1&DeVg zmI*ya*nU)JOze@Lc)Gr+k5^CEAUt_?X)Lq1CE>d8hdN<&AHp-9tyN3-XwUDZeLd6- znNeg<|9zV2sQ8UjS@-oT3n`I)+WwOBk@-q)mtc*DY2$Y8&v`gMFPH1#I=OycFJ50B z2Ob|jhj6^wuME7e&=O_6KIVR>6gsTUW7R@al!cbFvqlc8tlXOyO+KGO=cl!>e6QE} zT1~ZeEzQn(xSjiR9?s9p<#Q~@yxrftjKePpn`mwf_&pY1E9a>Xa35~x{=DwiU_Peg zw>A3rGVaIcAA$M4Jvhz0L{@l*}Iggw(WgpT0tijUL8b8g4kMWkP7AYlnYjf1&X=RjgkF>dq zm(BgTo%?ehq2Bl)F1^f@Hz3OQ1Sbsf~3(NRxd!FVj)$sSR+MZ{hku6YZ zRF>ko*{csOEcjlP#^|N2ZSuWxnbL|Weah40}XT^xKTu?tlMx5n>`q?t#EEiQjb4Hxy zqUvYS@Upm_`*R-7&&%a{xK6I0$CKk0cgjH2o)*+c&-p6Q&#f9^hyGom>G52Ix3wG& z%WMzQec@(A1RUHpknoO~ageL`Fq%Uy4~>QXeeTlQdwb4MSQnc}?b~XVKX{b8L3q?| zA8@W)nEJrt>+aC7y0*3%b;BO^e)J*xo-Wsw;LHAmudPl{x>eTJ-esQNG!_rj*53Wv zjW*X!)YjfyKeuy#&cpe6xj*S)I=OycFJ50B2Ob|DHy%$OXRe>)r{)^?B%6WapIONc z$7gmTT(;OHbz%Hq!Xfjgs>K6C3D3mmW~YW)?#H`1m5jrWY4_ZeN-dR|*|dAH+xsob z@3{lW|MnlB6vqm^3G=eJo%?eh&dbW{1Cr8zD zctlQ)s^|8IoE)>B^TV&@cJ9x4I6uFZWAUzE5qY5~=W3A;W7P9xL_UmJ&z}+bFshzc zBl2NXJ>N#;!=RprBl2NT&(9J0FsSG4hj^py#59oDCtnxwy;E@xvm(x& zrnyL*&zvUCohB^KZC1s((}cx&&Z;Mse;mVR0@rigTw4i}RvU zoI6eH6LF3-igTw4i}R&XoI6dJYv6Y7&v`gMFPH1#I=OycFJ9l)rDiJI+(Sq+$0Alg z_Lnd%8b16|fi!ov4T5%`ml8IV=noG&JS805uMIRkTby_@M%03BGdu}Td{PKbt!Php zV~3kcR@ zx5Lh_IuUMD^StU`M?0ghLh^WZXwxvVyDU3uUc66RQ`PP=-k38?TT^ju+|K&xT7<0IQkoTDp#8%+NFvv2U&isv9jJg-q5#q$w}=QYCOxe3Jc8e#D~ z1>$*)uz1b_@w`Uy6whBEp4SMA=Q0q_YlJyJw{w5a!})o+To2bN&Pqjb?mFq=Sk&>y z^Qky@7sa{jq(_{)i{jjM!s6Ur6z8rJ7U%AwICq_R#JRgD&Rr)gd9HLDN#9m*JNM^2 zoS&D==L(LOuaAP>qwA}(RTiX;f-m#85gswo4;I>HMQN|}dn4%Asxsj zYFeRa9JjF+wbv2XK+L*i9pNu4dgIl~9|<>q(i}HG(AqJ2T~&N?N^3{X&+Xiw^KgD% zF4x0#$}y!!!5Ylx>Y{1amBpydt69PeLZemM`=$lsU7^#Ex)fi>hOJ=x@=}ETa`Xi^ z$G6l^%8GBMY;D&O=6!(kb36CvJe;4G%k^-bd|X?D#l2qUu8@9?Eq#n)XUS(EY{_RJ zY{_RJY{_RJY{_S!cDLj+5Vqtq(EfuZpMmxtEcpx+D@#5DVM{&(%J$=WxSjiR9?s9p z<$AbIuAkS7*O$jZtf_wF6LQRBX!%Bi^jp5sAZ+N|MP$Jxp`u|sA3%jvJY^~>nqkLDArNb$Hck?#X5?xSkItXM-dk592Dy);t}f~ z6zeF$VqJt{9Yt8ImsGKiA}sm!^B=gK`*R-7&&%a{xK7@mIUfAD5?+4Wh%}_n$%6R~ z`w@0uw^en^97Wh6rmmW?U)v+f+tSAL&2nz7+g4}gQb;uUa2{^w{+x&N^K$)M`=R;h z3mT6c^FCkPD@+|aA{=EKd1anZ_b$-hrw4oG!*my4vX{*3f-$E0gvWmH#@<;S2y-58 z=l-0B^Ye1~*s%ulm|KInPHQla)#ChZFn8k;T6}WXMwidpe4DnfFuHa1A$yOT_tiKY zK$wqN&cp58pYwPzeqJsgJG07MR979)_9P3&=f;7Lx`1pu-ew_UyL#i7tXk;eh$%uo0Q(9ZcPp#EdB{Ei+wcdla^Q!V@fq4EdN*j|I%*x zcf#^IdA+ntKFKRFFN@o`Kj-26yj(%`Ll4)<^;>d&K$gofpNB1ZSv22T^0Ek9^0G9n z<$V#4B`=GxB`=GxB`=Gx)|>r-*S>a$KBGyG4fm>#d+P3 zI1E`nmDVZ^SH_~(z;m>QIU5;@4LWJx=oPCn2;1kmMs>7zXpgrx*c0cTukKhqUme13 zi|z4h742R#^8Quzdd)#(e^Py_+IfujUSMPTS#!5l+B0lqvv^~R!Exks&2h9c(Hu_r z!13eC+6?Wi39ggdxj*OO{JdPQhwJ3}dA)djc^r6rc-$(d6qLVzjk5oUu_Dez)-aFx z@)Q?1Url@7ulA%BtUgeZ>YJlse@NZ^gkn47QxGKEEhKzsK@8O2mzVH}E8;hMH{_u< z`fYV2d?@0h%ChoQ9|?VSrxD(;uRC1%U`raxe`)~RJ)8*p&vu04$;}AIfBK}9DBqiK zg_w29QV%WnsbY2)Wp^`eEOX7=&iy$L=jY{eJzOW(&+EnO%j3Y~!{f%|DdYWj-jB%G z>1|{U=5vB2ClKUymYhJsd>-ch+|K-Tb_8WR5TK&+|K`e5o>w zaQRN7l&6{6c-i%Rf^kNWHjWNVy<{FTR~ugup7HAc$KIR3`%zSR-~a6UzVA07I|<}w zC6N4^gg_DqTf$C4Ana?{cL;)j?29Oypa?+_6a++6a$7`ET*i5I7RT|KXExt?=i@lf zILRpFx&XknvX7Tdaa-FmwfT8a>4XJ zwz_=R1DBUaeCRggPdMWGa?o?`NBSRM+EO0)joH>dFZuhc%V9GPv1fhz&o`G3|L7&- zBr~B_lfTr-(S8rb@@-4{6v23>{H6M_x;4)=a#jHls~_7jK%rJ#dFGo zu3l{X&le3U&(S)k-CG{{y8CF&zWI-q{P^!( z&S$-U-+Jvc*I4}ctQa2S$8=))@wxGR;(NyTSDVqQ-;R9chhy&({raN6U-Scv{(;eN zF!~clKf{=Q43F_+Ix+qD-1t86J-_nYRmG=QZ?f`=d@R%Er9Z2``S?cr#=Vy|75}ky zrSboGd{MlAfX~za#?a%7M_%k<;qQIrykdN(H!aPWP7IInV>&VY_}nPlk*~_a_8Zz~ z!L`L<5AWTAEIsk#3yX7p`MmMZ-F{Lre(*1h|G^yx7Tdl(sU*(dyfn4Ab@g)NAN>2y z#n=DqMB~4A{j2r+_TFs#|9bBM^+OK6#`u-JKDuPDpKLLH#)rnV{8jhsjDPxqCtL1) z^kU;bz35+B_OJPRYw_J;c#I#@iRs7Z#`lTu8Q(vCSNz_X4>5mYxpah&ZCd1G9sJR` zCzs2P{i&7vanEcl-yZEc(ikU($M~^KJHnH~Cyc(8;f^E1vy_0VU-X`6KRMSv-GqljUvml_wR0*ZsoeXY{ts#n0}0+4$xkUtQdF z$HB(`;Okq8e_OMM^@CrUeSPuE@BPGZ$iWjYFN$y6*+Tjce(%iUD}(;b_?UhSkMUzV zG5z@5Ht!SOQ*ziwKbdru@f-hX<37df4>#Mlmn|cTM`s^q{Ab?#gL?5Nry0NZzdlgk z<42bo|JO@v^9eo4IGT#xvfK}q zhs`LbciZ3iA0E82-1NyN;|JZdvAp)OpIM$PJL{tI?@s%;=g+!p%PD_3%lP=tM}+Vg zKc*AYkI#+o6W=qwfBdfay)hqR{=|HX`KkSe3hfJK@(}rGBhY?Zb?pmQARF3;tI)n+ z#%q7BLi>UluYJ1;?F(kS_VX&VFPQP#=c~}ZV0G@*{$GXm1v5UTAH!q(m`+STJ~zHk ze9xGE2-1 z=P`Z^kMUzV(&e_hk9^hsn2t{S%$C{@*YZUB&z9N`*LdwqTWUXC@J$m_YSc)P;A zEySsCukjV`HNL{VmQICxjjwR8@fGehKBgbTWBiy-Og}z1zE6Bl(og;>@mbP8<3CgI zEtMaO@s%Ho@s%Ho@s%Ho@s%Hom1E_{VtnPtVthl*({1=M~i%HA7mG6 zN%k_?#g-&Hn(SirWM7kAte)&{vWpeT9v9Pz;W2(pC#D~tE17S#Gr}iaRQX_7`Bwfd z##jC=##jC=R_>L5i}96zi}5j?7#`!tbYlAPx$%2D!t*W2vj6R#k8PT4TlHiMlWnU= zHZs|^iex*JZL3H&wJ0+&ofsbD$8=))@wriEWb-PLjZ8MLda|9xHYCQ6;W2(pC$Sx<<>sqj6bW`RQ~wh|Fc8+#_$+Frb8Q>N~I%wtm7TwrOT~r z-3fa}V$wP@W5<7IrQx_mztMq z-3jAknzGHchR66ZotS=nZhW6;n}|GlmF5M@)>b4NoNR4HvdziX#(S0IuWW5avgPSq zBpaW8Dw6F__tle4Q0di^tuQ_-hR66ZotS=nZhW8kp7H(Tvm!73d|m4~SU$_{R@ZtC z#>?(jXgvqxWp^vIo`dnSyA@i`!TG=5P-s1eI{6^GTcPzFjF;W5(0UHW$Mj=(j4%6L zYdSIg_}utD@jazi*Lu`$zl*$d)TP$bw)d31tR>meWG`z;_BGkdwk5lp>}5-nJx=zr zda~2WURF=`JK4*MWY?3utVs4g*~?^;attYZS&{66vX>RfZYX#qW*z5c4PITYS&RN87Y)WG%^dCL38xvZ={N){<;(vXPa^ z1}7U?nQU{ik(J42CmUIrY$jW3} zl#Q%RHpd~~=_!A9@2g^Xj33j9>Br~B_lfTr-#>m={N9)kF@Ivd#r&kszLR~NV;OaX zrw*q)=?EX&eA)8qT35vCnrwM>tt(=Dtot#343F_+I}5r=)5%^|B>SE0Wks^<$zE0@d!OuO^<)Q>y{w+>gR++`O?E@s%eEzZqU>cY$<8Qy zSxd4%%3f9`yQJ)8WwKYsJ}Z7p43F_+Ix+qD-1t86J>&bw?~30W^C9L>%(s}IF`r}p z%jc?f9$e((9t!{Pt+UFbfAmL&Te_E5l&Adk2IC){wWWM({Zpo&?DxN~FTXtc3#O;~ z^mi{Whrf8M^%vhh_RMnFQn$B$^pB1x|9J3Flckt`43F_+Ix+qD-1t86J!793`S^`m zKdsdMNA^BiKdnXk9~rOp(^|Cuk?~qTZJYK#GG6PaE!F-<#%ukwy7oUZUhAjTwf~Xv zT0gDO{zt}Z{j@^+9~rOp(+cf>WW3f-E42TS<&V}+E42TS@mfEv(Edlp$M=lkF@8)Z zrXQah-zUCjeE;}e@q1%F#Qcf*R>^-!8x#4eeX#Hf;~8IJJmV{j=W!fE8ed^N<1373 zd`vTj$M_XiwD>Xo_}utDRoi9pBOhg^!Z|H`V})~!uW*j@j-xD{3g;MK;T+>DoMU`U zKZeKnF`WuW*}d_(@qOZZ#`+ccl?!jFuj}jjiu(A!S^A}OU5~Nx7kh8J=FKgZ{-52r zs%2fDYmEPkNiVki<3{&?`@o<6TTAcGCtG;&Cu7ThJ?dcNhxXdHT=4z9jgRTa@EAX) z6Vs2+jqelRGnP@+*VuEbzQ*_{Coz5ukMUzVQHK9*>0afkyY{m*$H*u4KP#WuYtQ^f z%eP;3U)i%qUe+??9`~W0{LKfpeQmAh;YYvorKL~)q33PPlbC)CkMUzVG5z@5_&)JH zk*jxtD`Gp-5kAUNNBBzTV0jpMJ*##8Lbax`#i`abHojWZ*!XHqW8`>X%S(x>aICSGjum;A#&)%W-t*Q*bHV|4MiKRU$1 zpP9J0_|muL7$4J*;W2(pC#D~t8{a3s=e+d~*1vhTzklRqiz#KFwRbpc;lAa<=l3@L z&f3`W|NEKS!LNStCoMmi?C*c+f@fPEdd&TQ{_=0Y$>08>_L;m{U={pcK-4;CZ9jK{Os~OeSICOm`)6j@nbqM{rFtXjVjapyU547 zulaN>X`Y?t)0Judo#xY(XIfg(mX7c-Z*RT#@^X*Qx=-D>+cuXUfBF@Zfmo(7ehiQCV>+?!^t*LL{ieNK&L8-% zRiFRVFJ1ocdwpEXAN<(cfmpBOy)it-kLkqpt2y#kHzQw-c}v%u8oAw%ONqe+uud$Z2cboPa+m`lp(_Ujs(_U}!TVi;OAJd8H$LGfP ziSHTTKYmyI-k1+De`3DH{EYb=^Iv;Q)zkiHk&pOR`l?cLV;K5gDJynpkO>S;eU?RQpB`=DvR zv!!W&H0^h`E$y48{mxp_ernq9tR?NU7SoC0F@8)ZrXQah^Qt3!{FaXJQ8u*SS&{Zf z(|%_~+BZ%6ofT<6HRM+I3G-)&_r~xTKc*AYk9AFZy4BMjaN5(Yp7w@|c^Koz@EAX) z!~4+I`rq#PQ!e@zI@n_CoSyxw`A5Z;tIwWX%}XjS`Ntpd&CFLS?jJOLN;QwE_|U-P zrd0EriW|xsrc^eTV(DG?O{wNX)&KAxADdFmldAvlrmZ#y<*_AqeeC{0&!q4c!mIc# z#IMpRNvBG`B>n2SCC{zir{sOA_bhqO>itXJ|GPczu=y{i-1X{R$)=<5r;<%a@t;yU zW*bsETa!&k>2FOo9X)qzvgzo3wkDg7-g9fR>FE9C<9kCf_30z0>AO-m-<#r-4=Ek; zC#6rmrRS2L_zLqrhC>u@(VwyH%~dG_m5fNQ+&N^-{QWP@7y}!!gGr5&waE0{NF#k_3@ck7I&U3 zT>YbuZk^GzrC2}V*`<$P|FOhxgRkPW5U0Agg?ppnT3Dy@}Vtv z9^(GeF`XD5J*=1&!FW3ei}@l`q{_g3i}Up?1&{bcivz6w(pn^F@Ka!Yre(&jQL!Bx1|}&C6*WY_t=s{g%8@6Z!GsJoq{-3 z`o>q!HC{jQKE_w?X?*qmDUPDGDX)?=V?OAzHGg8h#r&-D&+e_t%gQ2_OFQLN=UK6Q zt90z$s`QPoo@;#dKE_w?X?&EoD3kGfV?HRI*8GY27V|UabIkv$yzKqSzg+KH%hAd` z%0rZsC_hy>mO8hQx2ha1Jl8vKmtwxf{EYdW>z%LrQPtBVhqMhQOI5u#zN+uW>-W}n zyJ{aSylOX$&;6aR?GW=P=3C6qn9o)FX?YmSCHHrZ->UjsC@<;9S>ML^s=gbqpXh&$ z&;6Za74mC4+_FRdC_-z##r%x<9P__wKdn!%a7*gnGtN|IR`oi`XX`jcKeghhh_52< zQXKtdoLRM#mWMGvtNLx>RXdsF5MTNvhZ$!|imH0rf<#sIw}h|iweeMbH(o!{4j5mx zpT=jL>HcOhe`3DH{EYb=^FNR8UPy9SkdHc2J867X-;LK#w3Eh19F=kA4VEV{A7cK* ze2e*6wV!sc^0iPrj5DMBM7fIcmdAH_e3$#Xj58yii8v?XpC~60FVX*m z{=IcQ+l(_a&aChW7=`gmw%?Hv*?wp8P~lkPD|~CbGAQd+lnE71vplKr+Yb2?^DX9Q zu6M0|0<4Rk^hjBsDY=Sr66Gh?yH-7I_E(WG=nq_%+GqA7Fka_YdrgJ=EWE;vR@br} zp;iAt-lTkM^=r!Y&i%o%ze=lL9OEXFlU(nzJ~OtTv0aVrZET0tp0u{lQGSFQTji=6 zkDH9;dY9{6g#$~;OY*Zdz8a@zJA&`8WOydmyKKM9`pm4)tj0suhgR)m8t-I(74;+8 zjxgC|BaiR$_%7n@h{Gd3kGMVJ`G_|n{*U8=Y)8m?l_*zH-tzb^kMHvM&gaFn(@q*@ zi|uM`Z(}Yoh%#Qaf&Y)4QgWW9>pVROA(VR|-+1bz<2 ztG+NV-gx!n*dLA0{+Zc7v+9pb9x8b;zN$w_Pm7;}@wvZq`%%O{)p*?UE!Vr&c831i z@+8kU_jb6#dzL4;-nIHo<@tAx-}3q@$_M>r|4d~k!Fjn^gPapQA;*Xk#n?ROH4%D!OZ zh&aB8zUBU|6<6o^2&xnj7v=sg+s&)~!rF?eA2Gga zKaH>Y9pkJ1$oQ(CGQR4+60XkkfRur8+>z^@``br(%Xaf@zpLs+sp^vIi}4k1F>EY6 z%XqJM)@NqDN?xZu>W+lH z^_OvG#+klOav|IF;4S&h>TL#m-@^~b2j=@y=GW}a^zaYe?N8D~a$sPr}kNTcd! zjn`%N&r~L;{bU}E<%!x==GW|yKQZ58e#U&x^)A=DC=XFiqWt_m*E@Z?{%$D!+!6kU z^1S0(p7Hn%USlZsDYtYY{)xCq_q5`rh@(_4tV?P4s=PQGuln2Sw;yqMd{zvP@nbqM z{rKGYKJh){`=@V8-|J^+`+25$f7(CZ$B&UG{@31Kr{7wAHGg9|>iDecTMC|AeWUTZ zq%4fD^2GQmuZ*wq(D*8E?VYPUH=cCU_jZhL?19UBsw^k_eT{T}o9`UIC4OW4_LwIz zuk^;Pc^LCHzCYg>zOO_4Z%a;oSMu5Rxs7u7eDb=pbN+@xGV@gWJ@GM3<^OLKKg4HA zep>y{B|oj}W<{+U92CwyZmUIf69;0{xo>%sN_m*^lxL2=Ek#r(`Aw5z|YX# z`e_b-OxTm==e)?;DiywdQXycnN{cip2U!H0F=pWo) z|Mrs0jQ`~2L+f`Qa-H#NLsS?2xsm^Mr61FI^HbA`SI%E%&%LBekK&mdjyL}Fzx;Cj ztuf~r|AiYasvq%{D~iu2=^e_HSO4AK z$7RpTzQ}yehb#kG2C@uf8OSn_WgyEymVqn-Sq8EUWEsdZkYymtK$d|l16c;L3}hL| zGLU5;%RrWaECX2vvJ7My$TE;+Aj?3Ofh+@A2C@uf8OSn_WgyEymVqn-Sq8EUWEsdZ zkYymtK$d|l16c;L3}hL|GLU5;%RrWaECX2vvJ7My$TE;+Aj?3Ofh+@A2C@uf8OSn_ zWgyEymVqn-Sq8EUWEsdZkYymtK$d|l16c;L3}hL|GLU5;%RrWaECX2vvJ7My$TE;+ zAj?3Ofh+@A2C@uf8OSn_WgyEymVqn-Sq8EUWEsdZkYymtK$d|l16c;L3}hL|GLU5; z%RrWaECX2vvJ7My$TE;+Aj?3Ofh+@A2C@uf8OSp5Yn6dAB3)s-HTg! zUKQSw!WF+I#n*3TN=NCJDSe&G^j!U3DxRgI`^xm5O0P`sujiDny!`#CJgW+Cfv@5l zU!_A@wJLq%tLGZ8pLieRtM@cs&*A-zKlRPIALDtXQ+;oWPd*s0pU5BMt9&z_@8fyg ztKSQqj3+;M9^vE@&x0rb<~H}U@`BH0m&>k_n_Taz`bc|_>s@QTpiQA|pRY#^K6g95wJ#p|H+R(EyWIQe7yjZe>c?JnhUMEK?;lqD_>IGj|JtHOMf2C^ z8votn*A)XU9ccXDHl1C3>$dM$-X8RWD~e%{Z!v!Df-S}Se*BT8)^AtiCXv2uQK%o_`ge`3$U#alDi8h`Oo ze_B6s`B}#Q;!kg?|ILOgj6eMTPc5C>YfIv{C0=n_QXJjelI~TSWlB@eD$}#{4rO`= zy<3^yP48T$ch09)TW%@>adzrpnc~Yi4QC^iPuat*n%0uOCnetY7-jecMWzmw# zBI2T4MlKKk-OA{PXT4rOxz`0Idtd%sx8m4CPB8wQ17{R})^~s7Pyh1DqVw=3q0I zd*GaUw>gec7hmMwC3eBRqO>>8UM#NBF4I?jT<#-8;|O z9k1V)g!kDkuWu~E_wI&weQs4Q_RX2kd6H!y%RrWaECX2vvJCw8WnkwxZQ+HB%0us) zYdB@tgJa9@-+Zv~eb@Y=WzN+n8NZ!wuvJeO2OQ${AvhQOT8-LcOy;@#g?zZxX8)KR=JjRdd#Ps8HOH@;7N&-niFyCMcwzSUDcE8prV|CMj`R4&T5B9)i&tw`kwzrO6qI>B)M_g~w zy>)KZxwmNVTA$in9eqWcb)F}#pXgkj=ZotvI#1^X;s%J$*Lk71fuaj^ULal=LT(|M`55uzh%BSn|!s;=|MTA^c< zXkF+1#f=s%bY3QIjOhM4FBdmfbeYZvh#Mz5t~OqDxvo~|Jid0I&d~9-38E8fO|^q` zZmO-+8QN5vSX-qtbYg9i=%m^nwbeTBQJbPObdTC(y({mzujqbyOWv0EAE9p>ZePgP zEw=CC?MKEVrIYACl(sM&tZ^*exmUDefnvkA3mOCp&SL(OkCUMBt-jeId3hiYQ+RLO8 zDcnmkK1IKD(or)Roh2Ecs<6&FI++B|5=GK`n2dL^TGB;vI-8VJ1EyL1pvHJDp+3x1 zZJ?%fvl>HPs_FNd?xPlUvRXFHYF1}a>KiF_5v9ISm%NtEwEDHD)hp^(kE(vnvbxkm zl$u6eqL%g6nYy-@)vLX&E_wZ$qde_f)v{)*OMONAD@UnobFD_rv%1t@l=?~;rM^*@28mMNs7r%Isc+P!A)?eb>e5hA>KnCam`N$Mj9N$iT4Hr+gedimy5zO2 zZgpvtDD{oHG+LDUMlBj+(nT$!)=|HfTa6kgN`0edtq`4{^Fda}s8!@qA7}P!L67_4b!l^~0 zM5%SuFKQ1pkDBB4tFByJq;P81V13yb{YG6HBRWp!1^Q*MDEUk++FzwX{?Av~Aj^Se zqT}@oHH$h#{o|XLTU}bN@*H3_iTc;9tNxY?2Z$b^{Gk^0w;Wj^N`6sunnj!S+a!fi zvkp{VP13PaQnQz&idr;BbdKVYYbzyfv-JzLsE^ezTPz~G8>?@nXQbt+ z=_~0O`{?K*N}t$AM>kPwd>MCtYV=;$R%8$-L)sn*nVkmWSxyGjyAX|2{Vsdli= zP+Iy!teg(fud8cobUj)0V4V-ud2;PA{k~dswZaZpnl;ghy5n$h6GfZ!`w{y6V9|qh z$C0{cis+#_uhsRTqDSbw&T@a9Vjm{HlkQxnIv*x_m|`8JIO}Rh>z*S;*Xn$X zxGAEP-m&`n&Z0*t=CL}~igwo3aSA_Hbgk|=PTbns@m8M4>%OVA6BK%+=#jcQ(aQ5g z{XVU>Uf0Kqo}lvvE8`8i`)Kh;D{O<(Jg#<ZhdM(t$XbE4>aoljA$6GUk> zPtmbK^aTB~Nxz>cdZO+)Rrk#hMW#;E^+wT6I-jm`>n6HhaZlHM>qSr2FQ+T?l-e0O zZxZdU^O?G1qv%GZa+Z#nqR8giCaY&F&Kcr2Dc0HIHr38C**-_tXNvEk&~tR0Ry$Ys z?J0`XpQqnW6(z;1wm$oG02-_ixs5X6-_&c^4|~?Ak@T+N*Z4 z;+-#gfzFpm?s|&$RP0N1=LMphb-q+FE)=~`_gt#D=hrT?nthqB_o`j4u!}@5Qs@=d zlU$*6E)jo$;$9){0?~^V>q`B4h3FOHuhJct)vmU-;c9Vv*RGMo_ZID~7}qGq<)T;W ze66^vMEmIaS{;|yuG95pqTGL-!mg@aZ|%_ax}HAwS+h6Jg@d%g>DgjkIpyij_X9Z=VsO8zM_2s=mDtcA4?D9-yu->>iw>fZZB@6-8%;vT3y zXg$+|;uh5&QrH8vht&!W6dkC09@cT6D0e<$ecL0tW1rfix>{WOklp_w-SwUB9N|rP^n8&oa?hb^e@wd$sm?T`w2?tj@11 z>{ZcMb+t`B=Sb0!x^tUieopi?om&ibwCIlIwNh6H)V`qDpBH^y=P!tBslB1tuZx0= z-q3xY6CI`V7xh~y`URceRR4I8CXw2WRb7AuLB*31@+rKwItMEHD)aX`@mAVQmz00?Q|a)m?Xd)*1Ts zbWz3uj;4Bc-g~CPPolA6VkG3w>uVAZr!a86s z5Y~l4O<nep@Wta&hm|Jz%`*iFhd;`LAv~|0okA$-Z2Anm>a2Dg?gtoTFSzsz~()*Mq2n(FW z^*x5mKv=hkAFT7ehBy+=0%0YzHCQpgS>U9*l+OJ+77IHKX+>BM7=8g;EfzWgYkWWl z2n*x|&bnK;#}SsJEihCH4;H*c4oIn;&=m2Lurn^8@P>{k$bvz*o=5lQH zr0#xH=m^~g2y2Nj6Icvv^|s}Rn4UUz-MFwQ4+=d;2cDS|$YL2y0v`!U9u)u+Ywc zu;9n(44PUl`l`+eXQ8bDXDt_=0bx1X+NR!ays*)D-RTI+(H02n0K-KqM7PIT31Ok_ zdPB!H!%JTf1#NxNP*?+PeO}ne(N?K*!dVlgK>%lcL9|Kdx76c)xfNld7kbMuSHfA2 zupDhU&YGkc32iyTnq)`{JzGLs5oe)CN;qq@A?(qT&|xY;q;<5(CYW)g%8A-W`3_YX z(GrZ+^Eg0X1rVONl)*0<|lPGv)g*cGSfjWb0 z(SIjB9ojmi1i65s8A7I@$R%hV$~RMEpyY+?8mV)mtahS*qz0Q^_ZK z)PC0MqAesBU1zwL|G4 zkJPt<6laNBtKWKvVl!K->+aIGp*viss~)1WbzY}jnl03aHW8%QQxq%OQ997hp+)=`Kj2wnA!_=i^n@^F)u+ug8l!PAC#B=?OXpiXN}46C@$?Md$14MDZtxVwpQp+(2Qxh2qwW z8zhRAZoRGt3O%B?-JoNL=z3jk(68%7vEH2|x%PIP8xabmHpQ2-!Fe&4iO$s?h6g%H0)uyGQr|6ec#cvX2 zoO7zU5kj$Oj!)CoNKx!$r|CFVs1;rE>AD&v%6R8=9j6(J9WBZz=nNfWMVIOKGgQ-; ziSDm>XDW1@=ovbnsqiy|SQ!hQr50kjD5IgX^vgKW&GK{}r+u1S>9(|O`1imuf4c{-YeUe8m=`8pw2yz^>ne-$Hj^}L;PHw z_f^bAq6>81Px1FrsWSFkqS#YK7wf!4G3JZT*VR(RSRlGU_b@GPKb0J9d!c(Ki!M^U zLcc8%U81o46@RJdemXBx{JKhIseWIsyqG9TU$9)iFBL6xwOqdyD#N<&I6!yQMfcP1 zD|GKN>kqI1PgE%!sLw9%Pkb>@R+Q-MLB! z76W?pgLT(Rl?=VcA=Zx^qR<1xqvbe6+$yzkD;0N*j@4@0I@ws4KK3x{Ul{j}7Qb5e z9j44n@z<&CS*zcUwZ7?C)%n5V>B|@u4^=yKgkm43 zxa&mM>FRjhb&OgZYzMSEv{CeBC+LnrqF5;y8?ROCLwm=lnDKBYoi`|Uf6)^a&Zro> z11;Q1)}n1xPtZy2N+-oWS-=9rQ#>wkN*DLH)U1ODCOnaKz>t3RpbUsbLVUM8iOJiw9%ctv_RtOA3E7Vi; zRK>-Lahl$hUX1!bQItB4Wvjnh4tm4!`mL)dJ=b{ar^Z`{5Fud=JGPuh?Bg zCn#*N^&Nwi(m?UF=Yy4|ThPWy=4ioa6UV58Y1N167^-p}EN+A-?Jj-U2pzpe>8D2M z=qpMaJ3{yO6z!|HBb3T`(NQ{g(tBW!pQ8HMS;s=rPC9oHw?MSB&RxaL7ww{RH*xc< zU7D}2>L$LsT8U;+dN(jfv!2t#D7|M-armV)Z0PPg0D{4~NiR%ULg}w5dnmm*5&)(5 zM~0wa1LO}%do|G7t3lQlA(7MceS_34A=6OwP)IhEwwHPWMc+kjfzpOk-=MVfBXz8> zx_6-Ri2i~)yh6E84+2s=KsmQeEd=^Ex1_rb9V;`vl_Spa;_AxjaXL>Bw^Vez&LG#N zqV$gwb%xTP(%wPoVQKZC^un~BQ2J{muan9G$?0ZXchPRj@lMKnO0%=_8vlx>CU{~a zkNnc*w-om7usnI>h@Megdsv>lcSKKHoUHuYV|n)zpyZOD0Xo&4V|gS48ww~MiE*EU zh~@Fi7_9n$&&JNMJpLW-H{h5auN%kmNOnT;NWA+6w8iob6pyC~J~fWzsZj~VQ^(L? z_E24*2BKYcdp=km#1OGO{x4Ye(WSRV@kj)?y_3Ef=|_ixE}A|k`D9Q-+%qGMjmXV? z6pD8fBcJ4x;bSTH%pm{VKZ7wAJ{iLaGfs)b%+cxps%4BA(`F?RIHh~5}J5_6x7#yE}AouRklSe}rJv~9~&!`$lN-g)k=haZvq?%}yd z+ve5_`XPM%XxrTT&%FWhQ*!%9@)pFSDR~j%>EwP-jE&vH5YH$2LHwlL7ZD#R_gBP| z3Qt8msOWj!)5>i)cw^yv<<=edhs0A0e@I5t?k!0#>AsWh=hd(sQS%r-CfgELrsS20 z=NNuujGgf)OJ1Dr)rr5E`*o}O-Swj# z_kkK{39B6TIJ}>(+QA;T zz4sG-PwoSita9!H1-g6Z-cRoL1V(Ak`>EmgbK?nbNLcQ5)kK38|liTCm<~w>nCI518 zkb9F~A+D{L`ISN%_(0)bo;;!OBTv5Oct5!()HRBUm-&_Y^;(Tj+V_5P|8jiI-S5eL zpgQLLgnxNkzbDX#dq25s@n5@ivHzzLbXL$poX@dP>!>r50v{oeN?Ht$CGZ=NWTjBVZyI0g#bbeb}tVy+|rvC{(P=nMq_tWSIjpiWJ6ETx+ zplUSwLv)foMbXA}H!WRv)7UXTuCFi@dPVeNXxsYgemn>Is-}Rh(5f*D4;`axzQ%|j zZ5qB#qG-7G&@oiBi>~%CZQXd&T8$TG9j9`~X4oX^c2DK0@^ueUtdLDQMvCsCt0r;y zl(~JtEh<=6(yULsr|_x5#(-B976mLbU_k5#*ln02j-3tb0v=je7od&VoDFLM{$11r z>}*hBEhmk#&*!H+v3PbDj-q6J=7Q^_nRV=TQfBpId+?e3uElOUpC5g< z&s^}C{64GS_2WLP-?isHt3S?Jz>bAvVb!8MCt695S6-v79IXQ@HabU6efux4QRTtP!Cf`FQw5<6v;$#dx-MAgG>WD$Z|4iSdl2C4}ZfU zy4UAcd)D@n49U?0I&;;RnqXdfZ3d=@o+gv->UkVnkA#`a5nV;(jZ5}(yUUSS_e z;~lq>q?sYUiUKo5+)C0>`v|4o)=GkJp|A7MPaGCVEGNDS1g(tA5K^_HWyDvIz;Z%c zgLJxVx@81w2rE$_xkxbOibP`>afwg!b+A<-Jy2}*(LO>Q!k&OtVT$5lXTWwa+3uJu zZi?O0MdjF8p;%VBs5Cq48f#}4m0V|CH;GQvbKTz*`vKU$t4gu6egnVbi_uxv=pWnq zpLVi#rIX4QKM2O=cyEj|iNxEYlS*===qP<1xVfA1u%9Tt2;EFe)=hFbP&_^d-4vs% zebGqK!Md(Vh6jscO|Gdf3>8IhQh+*Q{@MCnVqio;UL>I~$*mjx>) z(5_JeZpR{@v7dD0+q>GAQVOj0&_k5Guj#szD0z>CqqivIlbYog9tl`OyXczs6iNs_ z3;c$KD27Kq-aF8qNE^{pWy3qrV)RfcVIRjX*4@etk7G)%uRX=Ll zSZBR2??5ZuNonzBj6Z0XcneCslfIaDrR+N^N9kk9;clXXbw#OnQ?64#DEn?I4QdP$ z&|RfO8;BhAP`OdhD8-&CTb@Y|*h^*3yNtHCqc`kr@=EK+TVqq|`;Okt-- zH{L3};V|*<TTT#2ZDwlby zMjh*}{N)V?>7dsbsHHaRF*vU^-yl$e%!>NkhLll`jRiURz z8*rNL-K3CHO;b>lZKjv5@f)qlHq%Sjc!}1eXXvGCJVR^ppzEdUL#2J#Ad0{2dY$oY z!>9Q~`Pv;Oil_34x?V32yd%WnALq04Pn0*^T3rt@eZo+s>aD}sl9+Q8>TSdz=^4(^ z7oMX~Z!hpr#_#T2g?igDKs*wOziEHb0rI{(N^$zhhx9zr^Ay@wd_Q>#;RtEKuPYU@N(ch&%0W6-3PW5eZiT+-O3^EIeSr8CDsw#a3VrGR`d=f|uuOEh z{?{nR0isu#WYaQZRma*+@9BOc?w1ex#M1|Vef;*_kKg@6+$+d^{gHlF{BVyU_ei1F zrY1nq;k7$vt7Hr>sfhUNgRiiF+{N(?o5B`iuq81@Z`W{~cyJ;3t)4K)44` zniqk0hmR55>&iW@kbh=a`1&v%87VM2Xp9%q7{SL2K1N_ArG|GN2+qd{K3;HdGkk{9 zjFO#=6nw=N`quVF3iNyUGSH?m0>e|Hi@0toH#{P`SUco#(yyQvpD)vhll%hc4Sh}x zZ6b4II;$jTC-DlUoaxoTB4A(IMAliMv}qY>ExRjpuy~L(r9DK)V3jDP4X&og;(cg0 z>6PJWpMUeurPcPHy^G44=MJ~$4zqU|CZ5qOUp-U@xP|Xc=!LHaU9l>Se{XkPCk()s z53uhYpzj@MxkbM5)r=bGSMb&)AGCH)Q_O>-?6;%!`#`ms;0fB)0cv~c+1BakFWO&W z$LP1gqKuxH0WwIfI(^_;9e7tW{$U=-5ViY#6w0iRq3R3z=$ck|s9IzC_7ij*p&qEW zIQpXAqP=x}ioUF;D7e7;rIS^jJ=72N&^7(z$)e25px=bj7a@BmDfj4|kf@WCvz^7` zTYaJ^GeI`%`9szBby5g^R+oy>vf_UQrNv#S5L!;!*M-&!E)ZoV0PXa?);7~3UaXo< zD>z?m`4ysY<-ww3C_CSR%QQbS!T1R@^ z1FWw-K->z|)w6ZI%zDdZ)+;Vk$a1xs=PI{CJ!3`jzursSIJJ;_sr}en z+<3K%dy6uDs;LJ#NR9<1MJ^A8ne&J^nx;bG2vD^@Y0m!6_<=7`YeuF;tq1e!Tb{ccUid7|g(jh2em z^?#mnYK+P17?Vu2Gs6@@&Wy1<8Dn{ZPKa-31WVg7#_E9kq=WA8MrSNAMs)zBhrFis zn2=Xrt*M73lGU1!Oprck5U-~(q9AQ*{}{<7qc7SX*7U2ZG%07+9AiGmL88pLKxac= zutXFs(MpB0&KP6sRXSEmPSG>5UK%q>_Ej8upM|1W6PV|+RMJ2nMb8DDuaG%PVU;L8 zjB|9ozbGX#$MSiOemg{bvwmScCbS{P8l@gnf5#e{8f(}Nie#KN~vkufo(KUMhYRMOPk(p=fL}`uo)-Oj(K76$( zQ0G*Wx~YabryAl!dXAAi9jV{w)7Ppd9I0#i`n9SFN9r0RuvT^8NL@2;j#+ffmfKU@ zOx-g_&jEcPTa7Vd8pktE1a&a_q@IC9=;f$qt_c8-(6^x(0DaJUQO|s4BG`i!%b1tw zYX*WokSFRF=mW{3et|w{S*c|{BhuF}^wkVOA9(+QL%<%s9wO~G8WCT^5)V?O8P8JC zhp)Ow%T4>o{7sMu^ESa7_%zdc;rEPYllAu8I*s1O{i4xz;_r%X2ft{vm*{+4TS*N< zuFzJZLtCaRkO*yvuic3EI{HbFi2LE<<;-kWG^}Wzz#z;lInZPW?G)$(DMD-IYcS&R z%bIZLy3us4QZ98;dC`;iR$kHLQCsQf=>Ms+^naiOdO>$ zw~O)ytpO{uu}T}r0iQ|l#lbej=Ql#>dHfez0!KvX|7ao50^;*YoKCu8Oz3G5<5*qw zmgII4ceE%oiH=nWHLka0zmr0l@5DIgc!jJL&+H`n(i8Pe`m|08r7b*BQcL@Kst)G* zz?~wx$#QFo`c6iC)W|88uX~8n?oQBA6Rjx*B|r%EcY@W^306-hSZ_N)F*d5U9HFOQ zsB>@iZPfY2t^Mhxk|V}3`&zGxY+WLWqgVBQ*ZWrb*+nLE7fHV8VVCIWExMns7FZ9v zK)u=(;^~Fw>6hM;?#;Shs@`+6=w@9XWc}$u3Rx<7p(j1idQ$pXTGF$1eSr0(2Ut%^ zKT8jLuC=_3Bk5t6OH$7>nWY~o)Ki}?dcHy*vby=8D85)paEI#pPV29SCm2$6C;zsI(mpQCK+Pw0AmqGAcJ+)TW7R`X(WPvh^w~G^(XRlp2V1k zci|bXkL_wtqy^*YNh`bKbNz`to#*zn?;#C(GM?I5ly>a5*_N{AC0{l~XWCubTyJCP zu^8>plQJIR%Vy0oP>mJ@f@hw+jAxch6-swEfd} z{#>5tI$LPsd56gVPt1qkRsO%z=l=HcmKxN>O8ec)*gO5kUzaSsGud8YW2ghHrA3c4 zLOm@l@PRt$VGmFXyxdyhgA|VKnVw*owZe>fMyai(7g?#}Aoa9vPo#yOtZ*DGEo z*RRurHkKIH+0Q7WE^=YIC|bseLNVYV##w!JJ=5Bk8A7Ctzb5IJsMd=aZ1lA=g{v5U z?V)2I(R~!7w|<)?%E$wBzo#T*p?;$!o~>4Zaa$)H3q=>|H^vCeeq@x;S-&!;mC;NO z9dksnMs`s+vc~w1wtkLU%6Yo(DvZG_W!6sUCY~0a@mx0@bCnYJAe&g_X!X%KVXXth z4$(pBF&?1h#ll0|jD~W!wZHUhw9~Y|-rs>3z|!dC23os_^@(BU=dS0`bH#x!WNU1ofJY(|}wiEF-nmMmTv zyIS{#UWzs68>`y zthvGZ8;sW$>0r)1Z?{MXb%cBNQ9Rb-n4x=o&5eB(Z>o64GyCe8F1kozzAndpiZ@?% z75l~#-L+Vy>FaOotC&kw;$uabOPE&VSg6=_#ak!|n4xt;NCG9!Kb4MUL6JbFE?z5Cwm+vPOSV zUxkCUJy`dfwK!%gcG4fyHplfhSR-SgMz*Z#af}YM#jHcrcFhgi`{Q)57ROLYG3#y& z7WK6_SmEP%9jwSPTlb%+7(GR4E7STL$0=;RemhF^D8=5Om?voTN^5(Pjy|HS(Q%Rv z*6?P94OY{@zR9W{8+G7UJzIC4ta>(Eqh(t5Q*`tbJxN#iTC*Yt>v?R_!P=Cxrl%?f z+#o;5DdP-s_C+VC@U2eamA z&Cw@!5oIKLh7MK-Vl9uRrXEU(-hz5e`;8s~TMITB!fCZ>{XzT37yFybpQJFd!Dj7P6v7!tRBZJMo-aWb!KfC)_~btXXNL2QA*|n zwSIG2WfSRR&OlE|4mzCm);c14tYX!yFl_0)MO{K!{pBRZLC(vvQ0}D@f)P-N8CB8^vwX?;AxI=)6fS;R4AUH5(mKe@W6p zg|arxsiJ5MPg9GyNR;(ukj(+2v;n8<7$mu4t(Y?u2N^`4h@74(y$iMfO#L=U`k2KE zJxlzVqUeIo()H=m!BE$kTYv`u^AFC^uV;y(g*->?=zgMTbI!H);9Ru_!^EGhtMf!z zaSFZUc{-TK$vlPgt?gt^!Z3~ISyh#h{ZdgZ0<6f&%J;Oan{|v7JzrNBss*l#qPx6M z+y$a&f0(7PS(+%c2p5SPDV-Kp`->IxLQ#IZSZ(tD(r%$wxJ1{Zq~k*K#k%*Gh%VFB zrE05}iK6$sOrfJi!MK-MA9cCHnTdct^m6@rnJ9LtE5wZzrH{H&JZrbE&~I4Nv8iLD zze=IwMCrk<7Jro}I@7DwM;s)IMgD4CGoRrq#koeu1X21f=6tfIE4tKc6^q%UD|Nn3 zp-rOnTGxxeP81#M_3A-Zi=sQaUf0)3!*iYDY|$}E6c0w`C~Of$$8>{YF}L(!o!_J1 zrigCQ`90RFv*PP}OeZu|l-2TXw0{0ZafgUUe{`cb*B!Ci4}F5K_Jj6mxW1V@#Lr@^ z$>Lyr75Okh;hJA2IzcTjvW?vsdnhH|PaNwDu@(?@iT0ZJui5)kOR*5+ZQ0Yx9R%xM zO6Y;e6MW;EL?`MVS_=H^Xtms5l=hYO26^bF-|(PASJ6$^AS~Lz?s=BH1$XU3 zi$%dbY263W_rz+?hnCSp+dZ-PF4`kj{N}sCX6^5ZMUJ`OWb&;f_du}VS>G88jQi`@ z6U%qQqFj6(jrR7$qLitb?2HADZ*Sdi%AMNP-kw8!DS zs3wXR6ulCZ^&9D9po|IWr|6+ry)muS?dy}#XVKrVvKW2T(TcsNC_NdNXr_7;`s-tK zfQjhCu%NR7*-?sdoMO+iJ_f9Gw62bqgmn?^qFD4L&|`GZiHbK{^f;aIy&{C(YrW#r zgJ>qS8eAQ^BFeGb@XFHw4?Q^f5p3a+7Np*I0v zY|;T5+N2Or537cqqL|>FIija3>~u*dv(gx~oGuPr<2$0TM&g-@*DQLP&iJGeLT^M5 zLO;?=XMEDmP>X-2V$$xzpP{RBbUjyXJR_uYbudefnQQbH^bxFfh<5)R(Q_1&mAJ9h zGse0=2fYLR3VvGWs*Pv$LRx%ZwR@g;#@iRE{`3*;qgeC;^aadyqupo58ok6Ninl=Y zLY*&F8`4)4&F!V)nB`CZaG7G#-qVZVL4Z}{5}j$;Y5)5xR+_PPslu*Oj76f@LYR5R z>@|9Zt5swBi}u$&*XW?Nr#HA(vG)-T*{(Xg=B$&I4Sce_RLZxUrBeT&-mA!Y$!zmuEv`}=gUdtQfcHcWfEA$;QD>D|hQyYW9xXMbRDI zquynhDE@}`i1WQu?lS8MYY5z>c+739o1KMyRM08huU2e?=m_2OejUDp%6;PR*VO}x zRfw`{$^+u|mn8`Atqw7N~W%k;m>T5=cj?z8srt+}pqdGsP*az4;-K_Hch^|=Wo845pqRf+fNnwPr z*Tc(-|Dx!N3S)njPuc7=R`PyHzkXU_gd8l4^JyJxG>dJLV!bMaG)WZi^;d&(9sl8Rucb=xK}mfZK}A}3{AYI`={9)xHY1$C`Hx@e?>J7tlOA%#Ec`>IzxlS zD$e*DqVGZzhW-nG09Jv+2f!`-XvSPyHb$)oC=Abmp`!ROf}7dd5$^)G{L@3T+Z_0x z-R9WS5d^zTzq7s>SOQJhAkp@AcHH@%j^JZ(EB*oCy7u;TM9*@dT3C<{*p8hY(Y&BL z!@GiU8R&;S9hnD(KLM+pu^J=VRy;Ep@q+{RQh!hWv&-X3QG6fq;lPsvJ)8T8fdAaf zbf)@m%E)(lWc{+K>Y?#r1tl^=q_L+Xm=KK|{v-H{;KjXvU(>pM;6-{bC_N_q4V2!nBfhV+?8puMk^8&42duBL=i1cd`$`K>`|E4-A(gb@ z_?+|i}IWBeVrj$9ItYt4Z%{-BuXp6N_CS| zmV1ap1Ifx}w3)18hEF(c8ny+j)U0{NDrlo5XOus)P?(DXCPez&&v~*Wq^qu{DF=p& zk`rh|M@o{qDSVi&@Ex5dZi-60yJ&ZXQ~Fbs^V9SjrH{2_ny%5Q4wjU&z8R~AqSMEE z0uq{{8iE9Za;B)1v8{k$rmEDZTG{v084EHRAXeQ3k21z#-Fx1L`7f-+$nnwmU} zU-6kCK6jx_B9*prU1x>vidg8f&|DF#p~Kqoi91iv-;<}c_oi*1-I4mo3@qv`v%A{* zp1Y=tKgMP5flj;C@I7aSqpyNbt@HYa?|Db+A9Ebt3PH_l)ITg0UJL03 z-pwpkx1@N@a~mDLU>&P}U<&s@r|zs!&1rv@>aKmyJ5pXdpDXa|FE45d<;5suXXV8R z+FMPx3;BAgAp1snVMp>(bIa2Ig!1y8aB2PMDI0SIn2+jni&v{A)2IHb{agFx#ja<* z+rvBW-(q=nq<=#TlFG~Ndmx;)^=o(i8$BC6oUg}A-$tKCd+r{UATD}4G#+lHY=3UY zuKTzD+4YNFi1rYjL2M6ySLGFF?eDC-5+3|y;S{g6pf~;(LI`h4pdK_<~HC|BdeftuY9ewE}3B(S+iW zfS!q2;Ani2v|c)T3z4ANV%2s$chQaEeF3fkK{Njwgn~{EZ7egM(92?5-&2?XoDVW! zGyqaS!warQvy0|;x>`Ui>%P8hT61BwN-edTzuUck9AUc;g!_C`W^MQWiQW(1+Tk&t zTEUL*{o^QxF<}~A;LT3i?0)Z`=mQbG9~^Dr7tz)S0tD*)2dE9-eII{;t{u&_^?snV zz{ozDOFj^++2P}9AFX)H-PpsOaSM5ej8g~by?s2rt3BMk<)AL@e7$gb8)SX3YMUc0 z>SRauaQAj)$MwRg6}#KR-CG`?2kFR${=Kn>JGI8qs`vOllhWI6A7wJ0W;QfFA8`e7 z-<8QnrTDJ6uO=fG#@A^-cP|0(g5znQ*-5Qp4k%-6M%6xgri3X=-@VjeD=tzAbnALvNjGcD>rlI8=Qhu0W%9?X5gR!=!$AKShDqpM`Z_jpM5w62!VU6t2k zl>)0scT@RcRdWm5Xoa$-0OR113T2f6X7P{Ebx+m3;i9ZG&`W$zwJhWr9`OV8?UZS6 z9m7P2DMlYFg+3|?#=&T?`dIlg?}I#I9#~V8&&~RMU2pmrvmeF1V5xt2HcXSH2y4^^ zl}Hy+Y*ia{U~OV|S$u4!i_#x5-)n{}L0F;EF0j;IUtK!w2#d9f-EHu+VLu%FYG#Pi zcKbSr_$8bqdyua&O$(5Ag!R=BPuG2C=;-Kr)A&B5^`?CtL{>&TNAlzAAf9H{q&-FH z|IgJiTeczWQ)#{Fa~0Bd|5tjX%{tism366Eb^1)%g+LZ~7|fRa=R)yu7uZWAjXh-p z@|C82)#-P--ZZwUwCXf_!ComD_WfTk7LQlLRc3=qyTHC+sVqVC z%xM?cK4vr8elJ+&kz6G!5ZEfMH%(82C8=3fpuT2Ly4Ea7ZP!8Ee!Xez|Go~QuZfse zo$jktZq~tSh^!)gv+8tTS$}Rc8`67q#%?rE6by*1Xues8Zj!Z!G2ZRE3bFb0re$|MDN#mck4~F_963&c3gG(S6^@1cYYlttI%Ug8;em~4UsjbAD8{- zL0Nl1=-7%D%ff@LsO@^waWB}mYfL{X`wmv7r*z(arD?22X-C*0W+eh$`tGo-jJTgH zKa3bYrZzk62+LltPs_6Nq|R+uoqk5)ZC9FRjcM#dPs*nAtPtAsI_k3HJTIEoL1h2e z7t~|0#`G}7W~J$8L|FmxMYASh^LbW0YfOJiM`P7#Y(plbC08DVxDY(rRs+O9O6c7X+HentoO9^Vm`wWrfMh$GGR9pSTXx;CtA-<(vy|EXpuYl+~zrLw-zM?zd6lJuU);@eo>3vlw zV2mhx!G2ZTTUzNbt~U)Xep|n=CL*KWw{>)6y=lB6(bjiX@4~1c?R>(B4y(`Zd~e)i zzp;KDqsd*bUk4h&x38~S7;s7Qx&fUqiuJj?{nZxWGalEkOTIUtPv0{J-#bRnU>e5I zKBISt>I*Y^(~dNZv{{4AXY>x2?C#q4#=UMpy31^Y-=6P{d)E62Y5VIE(x7-nn=?oCPYu z+Y-MWR-L{^@xWPW)oE}RIOSR$c;)yW9|>o<$Ig7ADNxC;W4&oScG9ZTV6KF-u;bpTkoQ0px{icCor;mN)TQfwl+0g@>1%BE6s?+%4 z;H~uQT5lTc^oURu_~J1g+vBVc=~qzI5}~Tbjvh~_l^!mHrI1zeAVf+-t<=8;VVslOfk0#`GC_vSRXco zRTo9K3sQPkH16)P>s6uQcJ}Y#D9(|jR?Ge`J z6%$;vLbOF^){t%y^?g0q&12PR-`ArQ59a!+eg|jyO4H!1gs|co)4s0-tkiKH5q$|N9#^qVI4`d?$iTc zO)||yK~J030R`8hFB&C^9HB27BU;m$)j`oPbkS8)Q)kmN;fufwe)K)Pg!{UP;+YfI z>Sc9GR;EPT#JZHM{ev#5mkw6RWTs0m-O0RpFdScnt_Tdby$*@>5I|;qbPN{-hp|`f zNKsb3B)7;H^i#j@dZwLen9x6=XF5i@p^odBm}TSIrlebPZ4(-%cfO;U@4A78>2%XA zx&A5nFn3qz_WNzjl;<(lhqEQc-CH$G5e4l^&yw8EtF%Rj?`YOXcm)lW?`Y<`oB2)~@6nUpS9yCqQv?6p zT%jG>uY`ioHu+8)w+P8>5jxpXw*)T2|M*6so1|d^`S>1Z?_SU38Yb5^ft&7CJJHy0 z18tM_BC@9 z)K=Tn&@iDl0{`qQL<4Htsy+ulR@QB1*cY#_nbv+tg<7JXiQPH22@ic*cxOjF)9Z@wSm+JwzmuK`ebx5(XGaZFW5124 zXKL(g)}EfpHB7E;YUr8LP8+_j+4kC|gmZj%4d30&wM}T4&^dic{q{SV6!)LEDt~ zHJhecU^QtH50_1hdGUwI%l`-+YoyOPROQV)<~5>gbd~0c9imvQ@OHT9;kxT6Nk(T; zW{x{#r-Ql6 zSgn{fHcL1v;;jFkdM2!Q>>s;cmOL;{!dV^J*DN9|*DYaJOS{OPEo)!fea+fh@|uOV zKo)K7dA^rf)HZcQ&*Zu#{MwR+37u10oOO}vYQ$D;_ccQ&m9$N0r*^Jwa-0=+H0!vA zsj;tFvgDy>^4-nS{IKgy^8~WEK}e*(X#WaxrTJmZ?p-KUbfZyFM$#~Wwi3=FcCz8Q zwh2sev(nrVbD?dzRq4D>$38+^j=7j4mXOyV-RZWyq+xQap6i^@Low&;)>hrpj{BM= zJ<~0fRj)m56MLMs-Pf$4XG$6-$608mKvT^3+L^YA*YwQ~&<`ln>Wb3N0p_ce>!rk&}T;?A*A&*V5OX`3Fe^h|AcH`{93Cg0->ywI@Z zHS|n7YM2~bG17O0)v)R%4O83Q&D^TTtgy7N8JdBlX99n@RS$a}dZxzyvB{nXo=Wz- zvAWasPp?P|z>F+V0CT*s?SZ5kR=tL{X`FszPS#68LHJg_repW}n(cZ=vySVTI-+4h z7loc__xqYTwu-x(HFQpCM>BLwu5Dt^SaeIEw8mw}nr5UU1fudt{Mmsb>JufX8 zewhQ*+cJtnv&5b$jM$mc!b}uKhV;v3cjwRKo=lE~u2lSFTWjBwDe0L&fXS2T`k-gJO8Tg%ZE_7$V_(

7DACT({)fCNxZLZQHp&6KDtgv%Oc7Ti9s(k|)!y^-Sym>)NKI zXL>gpCMb%gCgNQQO46u2Ij_5q~Dv zFggBleO>-J~DGdy{Zvu@EThMU+W zC|dPS5+d3ttCRbRpC+Ewguq{?8@5k4tGn)Rt7if?p>1kluB3BvoVB-b64tDU&7zBR%oDv(=eB<1?#bkOCf7Ob=r_K-o~f-T zllzUk$2i#JN*(x(M@t@7z~ndnZuLy=$>bWQcjC{4CaHn8cGNbZXL1db>y{jC?M%0X zR>?I?Nw?(oJkW=GFC}{(8mpvXLaUU#$I&xIPbR#_-G}K`X@S6B31Kz#Oi9D!K1}X6 z?p{qv&lJ(tK9xUH(lfmiPbLtSqbcr`_TrY98ce&bIHFKzG7-`=aq5mxkMYFP3*re_*0JeKrK=$xY8_>LN;m(|1L!{lB~?lJC` zJl86@hAG4&DwAE7oD*?a*7XstYT{u)a%EQ(7~a)rZ}?3k_W2(Ykd~+{UWK=)cg=krKNc zq91b~EO!53w-n|OvS$k4$JerlB;!K98qFSG$?Em&mdx5Yta8s6vI719Ykypu$X@Tm z6*5|Jdy1lGLqFGF6wM-cusNdBb!HaBblLt`3v0GQ_ZFR{vwNI1t8HghPtZ2Dg|DWCOtUg;+Mye%?y5I-jVC%<&=b47APHzf-Mf#Sw@4eGy@szJ z+R!Ak)Fi(HnN7PklM*^s-v@|##do`%f)*K{NooaY@kDZ(zK3_9$KV}!8{UN0H@z8qC{adzRkE}W$!m3#_)!XF zUuVh%pVnSF$p19^n)V*A5j=YF<7Fnc?}x<>Pwa6!#J&-`2Q`3xhuxoiUoG~!8mRXg zSiOzgYA88Ml6UN;_vPC6SEAMTefj96Ja5_M>epAM)W_{>XxqBUlZnMUr5Z6_c{9Xh zb%a`dW-s;>Z9cO-Uge)C`vmN)3!bDXES%IhJ6LGOz^Y!w$;)O3Bc+Q+kvYdvbv# zC?8reTj4kv@_)pfVaBq?WyD4MOkByZ={DsqDX_3XctCUdpg3}(-Adr%m^KmMA2)F&@oxL zK+8Ma%59iNzacM)&usC9UM8aIsXfH;KN6L{%?6~8Uum6|5_W;wZs1p8f-JTqJ zVowh5+uf78XL@qznd!-qiOdXXhA=}81A>ACm8c+s2&jlCf*@iR#Vn>3b6j2Xt~u|j zySk>`b^ZT-b+}*mAi>D0~7D<%zq}$q2^S znU@1e7t)FPml}1%a*d2C^W{vf;6kl7m~WOYq#C)F@}=ThQh}VR;#zVld6!&E9wqPU z$+g6IDWT$8QiAv+##dZRekCPzbFIMg$KzLh^4R-Lo|^7S!A6>6j;dL6oIHQDdvwJ& zdA+*8m^@3oGjAlmIfr^K$5O`dZSKVAp7@i1?l?J$v2wQDLBINSF`zy0jV$CNxVhgun7PpCt<0-Yc#0q9B@AOO z)NLcuFE*K*pr$0ona3cX7w6??^1I5yVAqlSTWU4xHjY`1`vwBXam9M#cPDf0lQBV_ zJehitv7n%?oSZ~k9FXEC0>uHJcmmM*^-VmNdJIoEHq(zd<_WrI{!^_)d{ zs^{p+X_W-NtDIK4h;uLHcyd|gyPQ=XD>wCAdw)x-K+fv(jG|}{$YZNBFqL7UL8}jm zmFgs}vk7ZceJC^;xs2Z!noz9dkuJJ*{h+R%bfq;K`;)3ICC0|tOnkrpwTW*Wgl}JY zr59ijetcKyY^H3&%gs`Va5+03^%@A7@Qzq74Gb#;@o?QS%| zaYp0qkZZW>+7R+SwJ5hx%of$6+)CNPN-^y(*NqJ&?^A!#Hp*5;#HZfQOiln!pmzr| zJP|lCXO8Nz*-6$G+;I?||P=;;MttyHW67QnS!^_c7d?jgH-1$`^w!Y$N~puPgQmg}ipSKv=S71)KZ{1l+R_+?y| zlMQhaS5K(v!Vc-8x06;E(DoAQW*vK?z+#{l%YJH}W8?aGPax2iUIX;Bl?C)H#7a1U z+I(UI`+%ObGoNxC&@&7?Ip+kl{VCjU?yGP$d9kx7M`0~_!qglrsCJ+^wsZKN`9Sk& z=TMFT#%Vw1-^Q6}o`p6Cd&iT}=3#-&!0PerUvo=lV|z^lhJM_|`>!ZG2hY(L%Y@F@ zW_sMa&zabe=TlsBO}+Chu1y3#>fCWyo)vM&lP|=JE%dmjxbq>tc*cC-k@K;YvIQ)0 zq_$DEf+bp!+bQCX9*7+jvyK26d8V~?JLq?<(?ZG| zpeM5}q$Wl$r0zL#E5JGNZ6LoUClZf5QOuK>#6izxIsg=p-I-w_xGUbe=cn26V!Ef> z1x_!7XL*)Wf1tcw-1LMfsY@(N8Ou_}vXrsdv(1#K$7UK9qty)LTl+F?dlI-5E0u@r z@@#SOa3Q!>*+c$MWi2&O6R*aDdvc%28DGRhPiFUg9r4rLy2z}naTSkid~1!XJ4L(i zwQYBKt1&Nn0NQe|dSVS+R5wv`tTCtB{Yu6rU=uB+iLy?gKxJhrF9%W7H$o=J>$M`( zd(_938p;l3t6n4}i~4CVpn6j?wLU=g-ezk3fbz>`YBin?>Z+-|dm@nB-rrW1DfL{1 zsVr0WY1#SA%Dz~qswJzQs2=ayR4rOlqo)?_N2ceChJp6 z+^P3L|AcyR?9zNGK7d);#QH{@e#L0SrOw#vg^@KpLYoEzuNc?r*s zzo;inObc5wysPS3+U8o|+TChjl}}&$Hn2eqRD*RS#5y%tH7W5>n=v#kt@6K~Z^Z9@ zY`>-2MDVQe()hOOr++Pf?AEMZYy-N!#uF+$U84(`wvzVtEC+S~J+EmsSEXeavh6V7 zPI`6#l^04^rQRCaha=0@Ad~fjDw!7`12$3LMZfx!IU>7}!s~$RvNTjP+(YqPL3zv( zls(9#LDb|nY8V57avM4Q0N^ovXac^b(t+Fr6$0<^JikrsdpEHGj!cXyt)Q3gj+x{N5pq45Phobp-uf^^agda?FI((Kl( zyKDnWQ))8O)KZ|@&31aEto2-X0HrK-QYotw>RFd*N^Mk{>IAA0buemkfR0{A#_$g4 zYCd((o$JV2R!7#hHgWgjOm|Cwi}_4?lqy|Gx(g@`njN?sdR`4&ooUd#!#$MU;JtKl z1RTH<)!e=0NZ=7r{EAG8UBDTcI%aTZJM`BDJx<}5W&t;GokDE}G_i?V|E!fsnbKz$ zt)NwT@Hz>ni@@yQe2u+ z<2xRBLZ)|h=1N9~A2ni)Mi@K5jM+R(U&eDomTw!tcx_f~<&bM~7bCewcGY+yex_eS z8zVHN*zq+qCuzlL&xpmBN=gfbv#G%(Z=vPGUP8KL+T2y z*Rf{L%qdp|nlp73(49El(ZIc-uHovbZPx&=nC>Lhw zrWUIvX-fn1u0;Tm1Y9oMhE%{?}mWacF>e92p!XZF;$!zW(1|@5~%z-N1M|?K-%%Kd1r)y;| z;wsd8p!D<`aSLVOlqsMez+PLu@Y`{03M~S?|JW@(0&|!p1bVXm&bCyYmhxl zc^`H6pgEJ;F+fj%K8x$o6wib{i`r3q%R!)f)9s?}`s+1Z^^WXqHfKSR;jxIIqXUC+bBxv?X=_(a>$7P zh}ZHQ{r!4~<$La&Esc+%Xy>bw8qF1B)kuwtXotz8jE(5MG+Lq^to<%W>W*${hxvNRSM-A7gt=6Y}zG&JdBnT4z{OR^TMJxVbridOGvcZlNZk<$ zu{1_Qi`-fFy&WMXsiWbzbZb_Qi{I~ayYAB&_I=dyeIBD)#wFD49V5L|1M?di{p{&? z^T~|RI9`WFFdR9bDKIE}0FgDPKhW{=IfZ%*DvyrOX$-r{5i-)!9mDpCsz{5^rH@MQ zlym1E`N|~c&QUdn?#}t{ccypB=P{>E@08MGJVnoq{Con%)3@d7#_L_FT4{5}Z+p_O zWA$(@IT2Wl&7LFyZmzpAqvNzq;_ zpjj!o&ehY#>p<;c&&Fs0DzQBkW(rXGY$VvdWG3?sVfE?p^j*b)L+RJq7dL{6yXn{2 z@228z`gQgzDt7jz<)Gq2>DQR1zZTL$3h?EgO5;S+|ui|3Tz_?%T-R-UAk zDS*D6az{^xf-AK6j9z0iW8#a#oR?1N3NhiuZWufx!&={lA(BD&@1r_Sy zl^W$A{^}F?yUHx7%U?J4X+EE4ZFGCn<-_t-y_@o3Ie^|xFO5I4Qt%fAu z4*YjElmXI(c;>r0!_I#A!6VL|;0Z?FC-MJ2le|V*qSV*puiyU#STvsG?5_Tv2CbFz zB34DjdJXl2gcWo%JvZ@oT11}g9A^x8HnqFu-iVcR?L(H+^<1yc_LTd_Jv;9kcRkQm zz!zrA>q1)3qJAUSi+~qm(`aX1Ou2~t@@}Gb3BPp{)=oj~=|C-_g4#29p5RukSUBTo z>rb2tG{4l`)7ETLwEiEPLTkcYP+^sS+=hPN#+~MeTGu0_ud@}MUv6o3X$>g1T#&it z0zPY@ZWgsZ(D_&f+6Q_?=VLu+ErbnW%*~##D)gP|<(-^0{;ooezY8sY6;N%z3tLO8 z>fCHqt*5W+Aq`!x?ppNd_4FKreRw(0)69+hUWNtWI;4Gk?>OK%TKi~g5qQ42G2$z* z6}tFbPvk!AfTQU@j-F%D^4-NoPwVkS)GA5xzPd{wY{<7w~N7VjEnAU8#j| z6?Vnh^q#UD;AF?r)DagF8zZ z|J{|LR)yBbF07@e@|!2}`%lGwI+6NGl!MvE(&Ey;>CEY3b4^vAKKZ5lLOrn3|tf$z$0g>J{CVNJQl1E%FdKv%E#_VVp$XBHxgE z%fq!#4vYq#u>yQ>4(6V{9W9U5$K&Po^3 zJEjg0oKvo)Z1EjK2T;Q3-Fb8!!0#=1VxL29r#7H84f(I6b#$M&=jk~Pf4%wYIaAJ^ z^A#%={@nSJr;Fjvk-S^nb}ZEy#ciei7>XF~SQ;_bigAwA(!=5oD@OapIjSsf<%=>@ z3|HE#U5nvHtBq#IN)2&a>1RY#xv8$}Y!BgHXY-NlYq9m=R<_^ccvSYa_*+@l;_Sn< z^h51y^huXRJHq%#!_iOLA0$o?Fy{n~b)H8u&jHUa6V(e7j zr50)Yyt1yfs{eMh;Jj;Vhn5~sqMo59Y4*0Co8u7q-C~#al;1Yf-#)e6+y>Z{>H|kKNX{cvevtC-n+Z4 z^==!-U$4f~XQR%JZ5V0Oan&}i)fVF|SI;)vVhK9+O5jS`oms=~q(^OBJ$oso6J31`wPonl zYtZ4>W=&o#y9-@=IokX>Y75c0*P*emr?w#L-}8ZL{>B970ksr1aW(p`?Xa2a9H3Uj zVO(bejW}%K+5yz=*vfSlPzz)m*O@>g9oxCK16?DxgKHbmY>9%a_^9W$jhWPk+Xi+z zhT^Q=vP!B;yN>=iias-E!1D*hapz+KMW2~-IFX{S$QhbMG1t!dnM{fNCo{cW&sJxC zBKOJsC^Mj%Gp@A&_536B^MYQw2X z5qd9%)0Qq~vwGEAqUE6?4D` z=SAF@4Rl^sb2aPMc@Z~e0i74IVkXde5i8n(&Wrfa25jf))>E62v0_HXhv`7APVr$H zP&;%JwW%2^^rm?xw)3ceO&irbx0XDQ>J%k)^WW4mJTKdMtW%m9d*`u6aV@X&XgY02*#Ns z>)HVMl(Q*ingKI3&y({QGgr@VSI=)$=l90*yz2VY+qbRr47PpSIyhuozEbDuZ2Pu#p4hhUS?4`$ z`<`{6?X}F8`5aR5x=g?3i>zg)rC+m2jDAVK8z}3U=dIK>W-49{+z190T$}SaG*e$q zeKp@*&9d^MHP3Wwe)}nTmMbmN_nu0TQhe`e6e-2`o=%ZceD4_)bE|ysHi~&8zIQvN z4LtR|XHv{L@x5nJW`ftgcL&7`BHw#9#XJXRc@D+ZvCi*YiW%h2@;r*`zMbXy6eFU} z_5#X$C{L<0p-SO>C1uo zRg}?0?nZjuU3IilYo>@~NaV=fS6v{+u75O1gC3e6~LMxujVA!F8@u zvv#Z6gH$f9>xnPH4sk_(ATKC0x6msux7Z9exSvz-6uF4}MK6nmK5IYv@@EzRC?(Q`Rt+^2n8$R|fYC-WgnV1(=}^ODQPF zHM$*~SQ#mAmP0E$<=Jv>^Va3%uBMQqn^h&=#Cg}7xsKwUHUl@)JDR881l&a196fXL zHqsu;({BKpxi^lwmYvb;@jyM9(y*%zT#vAZnrB=a*EBzC5>QX5Sz6+XtJKWWssW8_ zidA)>@=k1P1}g8w$mWcTE!35I;%h5VD{v{bDH)rm0*!qR=c>FL4ji7TSi7*2cUp=w zC{nT3U>ij$)*fo7NX1%3GbvKBR*|$U6>Dd7P^4n5B2Rdfiq(#UPbG~X6WtOuuInSEeV@j@dv?l_km6$0{Zgjq!JLk(2AJ;IStEstj+G^%`6}7Q> zj>hI$8$(?ya0Qs)iIOY8lrCzc@=ST^qz z^G%#3<9n|2=tnWi=gN=16t!Vj{q&(|DZ1vzQ$OV!?bO^!ubsJRqt*b%v@t6)sFh&S z4CZM%wVrwN>KW?WN|T6$_w-%qZwPN%#0`XEMZ^llgNU3&tXv<1|IvMqzv~_HIsFyk zyXf`MUEb^G{)XQrF8Ph|KRv(4XY!Lr`+ol?o`o;T-%@gQ^my4L8v6!MRpyjZHBE891JAqQ2{B|j@6Uveg8+|c)B7dGwQLmS8 z&!ec<%g^1R#<-0;)3h*>6Mz$F&*nOZ(Ql#F!PWI|GpISr?npA7`b*!e<# zn3lP^MeK>7b#2^LKSjjF#Wm?A=rx`|oY&{BU#0Rd`ni%NqVHm_-z+BUZx;*1ZT;=N zcyBRzI;A(`A#Ts0h_T{C8)Xo15WQ-W>W>3x&*Uxo1Jy6(O8tQS^2o`zrqUy>s{Ocw zkQ$0J(Fzn}mCdb`@yy0pYRy139Wk#tV1c57VBxdF4dV-%XlQ6LOr6=ELKzdQ*;Wgk4m#xPVMn@ z3VB(jS$H0H=n?7^o|vtU@klzwq1uFJajRqe={kjYcc^Bel#xzDv-tCM3hBqJpacxg zDaNR=4g#vD&H@7)fsM4}B65^=t{uGb5a19#lR5`NDO#41n>(9Y2j4BeO0VipX7Wy> z-9J<904QxZy;CzC_}l%V#NqU+XZHijakWs5+KY{HaO1C9s9LM@;R~(ww`5EWYqb|G zbs{x+^;+fB2x`vRVz9TF&leZLu$^Er)r4>1Twd0(Y z?^t?_!t|x4e@3pQU12VtQ5ZQ*6+M(ob?>#{NVv;_GD}J37)EB7c}C_$$rY7@-C3P} zn>vg-w7kuoJJh8826GkFq?N5&I(qlqL2fpDZW(YH?GEU1DR3!m*RORji>_9i$#qty zO8t6^X{+xmO_U|A;KL%|B3e_xp@qPOw3QrUop?13C^i;cr{^~b3JE=Y22T~-vyrzJ zmt0w<{;n(!y}gY-wNCk`JDare{^nLS(`sWD#cT7ehA<~$h?38}W|Rj;NQW|y+BZr^ z_i>V9jKdCNZnc5T;-3V@NLxl)hcol)smfQeK^oOs(R1cp>VK;-!`fKRv-qU`@TcfM z`l$3q=o_8N=(PdO<)6X`JC=^Tx|KR@LCc-s#Aq?0g(5~fa?KPm+TX5I#AqpTavn>w zki}vtcoIcib`;HB7MC4IJ>KGSUuy0KBi6jQP|x0=N(ZL`(n)art5ynSek@@Mr&`ABcBY8+~o;z;C+sBx-ys(~7}iF^<< zh2><%pwv3lVPn^x!CV`2%Q&`rvw3iXxl0XY8Ta-D$`#aFB42JGv@C~MN?FE}y4#Ps z&Oqqe=jo&@u5|zc3eIc5csR zlt)uv1piRi8wDIiTOF_o*hG6Cb@fCkS*=msQ7uw!Qk_!m(m9?9Cvn~vQsgW%X|?mo z%slJr*xupp0PT71rKHepo2gA_#%JWYm&#gcJNM4BUSlJ;az!cVkF!^*oK$&D6;sr5 ziQSRpvDy=I5P7fmgj_?O9F~f#p>B4+D9(TgJQ)1Tt}=o8cbqUNCIMGuUA7(Fuj zXW~RkXGR@n0l2C^M?a4K9DQJFEP8y@3e;7?6QuU04yR_JHm5&3{7C8sdY1Grc{Zi~ zCimNrJ1?iWzl@xu3;a@>)IX)qstYfcoOdM{sz*zI)++EeP6}}Eknn?fW`H{EYP@4& z)>_J%hrDO&=rKkS`mdO!P8@zV_2oJ(y>J_{Z!R=zeRT2?y>_lA4PTxdWhQSul<}4q zwo~L6a!RpsD6=8$>$7ZUq@_}=>S4@VWlfq}DRpak8`YDCOsC9X9<<)H&POow1L;*> zj|4B|rc)`?m?J4_3O(Yp97*4@oK4Q!N-=^qpB_ETN(i-+7K##k0X@z1sOP!khTi7H zo4W^x7MAkZ(U5!SbXve9|IJ2&( z(Xw+k&AD=Qjq|9k!~P|;pa}8bJOHs~IPYS7LTz;zMaw|VV<<(RqgtoBKnt*i-iT4D z$JLkxHPeV(smUqD)j9`K)Rgp;44|kf=_zrCQZ*%cVn2$pLE{$caB6t!cYUa9AB?4D z?$;Qgd@|0hcYhP9R6ZE10Mz7sZ+Fy^+ST*Ac|dsL!#BU4?>CC-@9OIv4=(!6`tXgS z`CIz-H)I^wTQ7d=_1E`r6d-)|+Hn&ZDPsgv@~`U^j@Zv+#`mt$4abI zPg64L-PgzO=!vCTHG1gv9P96Q%*ARYo!)w_KW9MSzYzfEL5V0u$c2~D6LA22_|l6s zQqb257g$P7N|_0ini72l_|{2naHcG&X(r<*4r(Eq!=Vi)HO*o?)k&30`s?&8NKGBg zgW72?id0>%QQAnW=&YPEH| zfxC&x_1062c*^x$p>51aUg;bTVOGT9jTGliPU^fhGB+dW-NdMmV0PrT&f8#SW#mKi zHWF^OntrKg3QxX@`czsmZ?60sMSB2qB~KXr(7c)9I+}KW=1N;}%tP~L9@rS#{g|u% z%*xn@=1puLn`dhrurITx)Tknh&enM5N*zL(;w(z*&ejB=dW3q0T812VCQx43E6<;r zgqo&vC0B5+oIgD?@(t%oF4DowIfv>KYOKzcoMtxj?Hua=QNOLxU(Yk9rzn9X&Y_y$ zT%dDhKDyemb13JY2Q&k{<)L|#pSLo;`cXFWc?(e9F8^-^>QhlJ)Pc%^b(uES(c`Sf z88dPaBV=Yj$Tg%k<7LVkqc9VgDWft*Va78%N~skydCJ`|~P5yc!3Jt#`;p}?WEjlT>5D!b=_ zX^p@}+UfwFL@hPVrRXbG2T)s(Ui3AnOY{dyDaO{c64fHqI{E^o4mD)G#A+aInUcgC zb3l62o{?!ztws-PFWTxnB~YExEKf5*)OIR+-U!V)etiIAuV%8IB7anek+udfKhn(x ziu_U9+DMVk)OMt^{>-gAm2Bdz8<`VvTRPJpGKAhKjLZ<`XEpt+D6U=^nkh`~Zp5<> zPZ4rwSf()bF8QN*2SzNVZaJe|U;gOZ$uXtt;Ed{PBdM3nZUghVoLUooZ9wyP5`86e zyNuc>dfS0bT;-4QLiyupdS?Phag}EVe{}y;sZENX2_7%uGwDkovNR{fyY5@sQnt5% zchZ~`?@DoLt4?VKPo+5}@oaG2J;aSIECiRw({Hq3E?6IHJ)|w83Pu`?DHv&xij6WD zd5}N$lyQH(d_{5Rv2&Pv+Lp2Rk{$qc2JuucfjWa+UVnnxf|8)hw6DHjpQ5-KJ21H( zSG3_Lp~vt>zn>dn{JEuZOEB#5L_Y^#@}k#sI@6(EF>W z$2>6Cjhg$FsJR+Txe}U?_N@Lf@k39Umbr7U{p(4jVyJVg{jR+ed(OLePAfBHdvcyp z{Qwglnltm(!J7}jvV@S zVoJ59%?RP6*yO^!KWMxBKmS zQen`aBV4Ufc>MX2#*B?fKW3S`Ta)X$%{w=8ZzgT*n_$kgwz~I+JyFGAlmY&a|1Z^= zmmZNAEq5(==d6nUN`3zJG`Vp1#YE1pWMbRz%8`rp+O!7JdCy(&D!MVWX%C;v8!{;25QNh3-0OatoQQXkQ3)4!z- zG6kq-K)WnfU$#=$f1#FPW|p$RoGfi;;~+z6nct~Btu;LE_8ZQnVOh zY{Z#U1}YE5TeU8Esno4})K~iG^Zr=8K~1IPPy7j9Arvc>>SA+bAynK%FRMI9T`|@g zNPn(Ok;f}PsYa!e8!q`liyYK7-Icd~ZGI zj<6%(3V`sjRK9cH#ph5*iMVk@eqsdt)LBsLa0Yw}{g%Fmzo<^)4g>lvBhSKT_7i=Z zKC{1E@kqblRTh!85lCq3FsQtA?lHj~+tu}7UdLrU>d>O!D?Fe%kF40_3=)cHVtXj1Atpnf(f zbuLhfmr~t#Sc;cYrBJOU^XB!jYA2aHKP%JgOy;f$3SXHizKLr)GdL1BlHN9EbOdk& zZT%`{_z$N&J!6wOk=jgRlWPOCmc%C43}`cnO;adFjHFxF7)bHXq$?1lcxTd;337L5 z(iIEM(6Dpp8V2J=?zt=fc6EdNTOoYJ=*82Y zXKX}&pR}y}i9Jw;!)4+G6L*eNa;ZNnQC$6FPMC6X9KG^8BQHiIBM#&2DLK{SmHTE& z8;g!eg74zEg|FWgU9Q!YmSSC>u^Adb+@b#*JfM_YN)yUdy?bK5GBvb5cLEDNRVq-X>PZwgl&MB)#R_Grk#{jniK3n= z<|$Lvv;I`x?Ar!*Dp7n=pGt}7IYvqjC5mt6IK-NE&#v&fw3Z^TQr%lQ<5QJ4$kmk8T6|JmtUIjLB2%wtj-ELI z@=)^t%vUvbudb#i%w746;+sEd)}*@HOg{6pKeK$~U9PEA-*wLs*HOxG6W?cEjL~k_ zqtD`<6HxAH99Hf+f~(q4tY#g<)p<3NEKhU3PVy`xL#|bT=dyg$=*%^p6tf4hI{$^$B0jbrhGvDGa zF-44s-wiBr+?8MYV|+?~LoA6oF_+JGktfP4#gm>g z&%|1|Sk0&>C~`p_U#9=5<0&7IdX*w;GIp+Il$y|(nrN?M3`YS+(O#YLSp8`voLL^W zp0W~zM}SZ(Bu>amSe z76u^qI>B1=OyiV={%D*_pb9fm&1Pt0mh{e=WuX^i5jC^H&8XJ@+J~Y(uFutom2{!! zwHIYR(6uTJ^k}KeXX<=sJEN|@wxmc8bMh?c4>rqoHc(%$IIdKx^Iy$itvj8`l|1L9 zXN*Lj#ls^d#z^#2JUmkJ$T5Pjzpy7kBO0l%vDO61u4BfQZA%# z`tXcM?EuH&k#ZrmC#oz+d9b;VdIOBC>$Q2TTu9$K?0;kBv0sAuT4D8T|A*z@efEYs zE+})&i`28`+ZZXYav}d;eXswWyZ^a3`M-1bKX>l_|G-bwixcudEi9x%^ytylCexSb z{*CUyW^_V($W>FuCG=NnBWWRN3B@`obqzIBEwi3pOZD+;C1A-fDlZ~x@PBK5E6+G8sOxLho>Iq%9InXcYT?u7JZi2& zH-6%%m09wdm8J*BT`bHm(5DkQosOEef2<90yquYyt2?!el#gbb#+o?2Kx!2Fa`oss zsy)|QR&h7)>5eLD+bVw_DW0hAUwMIyhF5WKb&o1eDyBSq2X6PVdE#)!k#T%{lJF*~ zp*Jw6wzZY3{n*sWs}sdMo!;|RooDUc&>|}RAtDFPlj9S+SZOOeD`DenL59^`=Ng)^ znUl@b_3x-vwF314nWbWU-u!xfaL%hf4eeUv`|9wIo)-{17OC0!o`d-dD^`o+e|7IF zKk0vl?p@KK(U$I*yK6|K$tvb9MOXXZ|M@f+JR>-{eqFh=qa^LhrR5KLg5}aiY`Xm= zS_bljZhj({mdm&^Z7Ob~yg2V+n~Im@w)@+r;-!?ARZoxnSa zmjmxC?gGA??|gG{Kk)wIEx@-FZw0=!cpLC-#oK{zFWv!sNAXVJJNe#%l8QI+Uqx{r z*P?hM*P?g>*P?hm*MdDv6W@LTSK(d7-RypwXt~$w-N3txSFi_eqW3A(?g5_9^&$D3n;J7d-)1qUA%^Ud!L`-Yl_#h zukLG$*8y+ldLy;h18?H`JZc5-My@w-_56|>fbK4P89eJ5T*p)NNVp%ZQt2}Im%H*# zpt!@LJJf3BUJfsNI=vIwx%cUCFL$L?T3rE0yM(?;6fNmQOW&YtnnrWaD9Tm9t2m)W zPn7VP>=rzda&?wo&&rbQYT(tJ*)p8+Y~Tp4!>C;g9L{wpwdVkbaUDYKI^a;QO0Mg$ zR?WYj1s`-JQtTCM7O_4DPhT?Ep@X9D(=1}M*rwuV(0eeO;`(yeHyOd|h1FcoJ_u#5 zImEs2qbq~9(CUSMT^cdc-W$KWGST>5A9$m5WQ^U@hQwzhcm44GC;^S!^~WQjtTb|` zC)s?_YAs^r5t&DizLPThRLbmSk+LRpW=V-J;0%gqn4FQJzL_)WKZE^n_1v7sCyUuB zx1{&f?A`IirzPyJThe<9zK5m2Q@Nf^&q4Ou)m!9_yGz-xxXgR;dXDZ%l;xZVQ__1P zwXVGH?sE1HF6oW4bv;wpv++uL_fuO5Jiv7uJzLp9SpS!&HLYY9w31%WXIhP(rEL*5y=A@8Bwz;4O= zxHHZ&^<=gN%JIPC`EKJ*=Dg{TZDjB2>Uac9iU<3De+~~`!M8b=E4g-2Rxn47r`e)i*=uIjsBJTj z8yK^-K=)W{0MFM0jbSxF3mbuAwAgI~+pOw^K%?BTO1=a$&7U_uSMse(fquJGVIGUL zA*xR|fFMdLPy`A>eXb^ADXO1Og+&gGL3vJ>ZaG2+C&okMT z|DC{h((BIp3CZXgV^>k0iG04Eo-66`bhBHz-aubM%HB%*3bdeGk>fYeb2;@ZfVXk= z)G|*ZyN&i`XhgRm{coh_QtF;e_EN6y^PiCEFQx72XPy)Ae4wYG$upjeo>8EkJQ;XC z*8=_JeBev@AGMqdfSyKHptoEIyqK$d`Cklt8dvx7cXxl!ISak1;2YJUZs$7+^s(E4 z-S&hw=8^oB&_m=RH_|$SdSoXLM0dM`nYxp|fmwIEgYWp`cyJYmdvv|BCl5A)=-CVM zCZ%>{Ntm0U+*Q7tKc)R^o`gFHY4ggh9kcZOkTK-jrs}{eSu^t@ld;Kx4KP)IUpk5m@m!3EuMdWe#*5)XRbLLmX zE?Ca9xv7zv_s6V)KQ!mu`FW(33T6`euHhM}_5n~DI3u=|2F{CZdB3w`J3J1Kml0q` zZ6eT-tnx6l8RhcT87XphWBO97m>@@2lT%mIPZ2pqk)h!e8Ot@hYc$X}t@}lrrC`kU z&@2ac|8Ru#(J0^a!VCo}1H}-1G?CR1`3#ZCpwF?I-zS20dh)O8cb^Df^{W#{t$ z#aLd9t?yX!hT_5>){RvsG&-~2+%ab;a479qBkJmFW2y2S*I*k=vr&@ zEad*Kuh#OE`@3U~xs%EQ_sTJMQXc94I8&h;d0}(rk?xWsb-7kr8Zr;QH!bz7Rw&7s zyVRkE(*P8I8-TGg+TBGaWvq5@k>S+E>S~7)v088RD4_dvxy!|9c$|FCOiD8=<%DXj z6AJAP$0KOJ8ZF!I(Jz#aJqx2Zuy_7F_qLOwT_seVxF*HWc5C^pUrl6KSrc+&<36@VPv3MIU>d`{Fq- zo(SX9`ZhjScjUp-V2nq|ceDa4Y2%3KKUKp?jFVDL4aYZAz66JsXQ?sxzn&T6x5w@q zKBrR9aq(9@rOPMwY#8&`eCK#dpW7#ncktc1<0U?K#7c~%xJtpDbj@mW2i-=X+|5-F zW@d>8&cEv*^gvfD<0GH#kKv)NpciKj%@(VJgOBI8cE^(HT#DdpRW@F5f9>H)258SZ zYT}+F8d{|J-HvOeIXKdeoR+!sZT4$qrHV&>s~Dl~;YgYlJBWD-`FW`C-0x6BsiF<~ z(6z?>f4@ijT%ARYj@+i2&*%CdY0&&&_iB*>m07- z>MOG-qk-;nsXaT3XPHHh64P~i%EH+5MJyCcT+<+piYsRNNeg0(J7tOa=5?xL$n%t= zzMbqz>)&YF6=zu+u5BmQ2@ z^27bk@{h{X+VUHNtZC5y6j-6}A94|*MFwtj^@$(&x z1NqK!pvZEqI8%7*wOZ7ysyuOhNRDmbyx%OoyDCFUlG5UHWn5%SR=JnHiNEA%IzB#y zzaOJst2uX4oOYGe>o^+$lsk5>M3HNn4Jsb#j~f8=w;VNBGKL3@lMZU@vbS?B(4Db6 z@k)7O#F}Ci(9AARlMqis#)}tWqdA}MO}+xy$#pzXYBB3u&x?6ro%G7#x`3{UpG0jr z^wY^_%GG7iZzpX}19faC(=(VNKkwwTDl0y))UlIReD>f`@ivZSwNH&)c}eEVOERr3 z$rNh--e|mG?rCG*o#)mq$v!eUx;|z1c(=FOt#1zf3+Y*awlW(Uc3s&*=v_IW4x{Fx zUZXd85&U2l{pv90?Wx`9Ij_NO%omjN)G`-xH_mC)ziDROj;=bK+c! zIr2ZTLtmkW-Me$mC zUYG8q&mGrak?v0OihI&4fUivV0GDvbyyD*UO5m%~y}(zeR{>v>UJZP0dQHM>#sA-3 z+{riGRosfpy_9`; zM&I6uzekVmOToUyz(xGVOQ^pTztmi6F9zO*A8RhP7XfcACa32VwNwY*Uer^K>m*C@H`bwZ!sb{Vs zd+ZwU;ax@jSzOVzQ{ume0WJcLqcuDYOBWR*(s1C&Gy>Q=&1DpNC;fB1lb*TWNzYvG zq-U;ox&RWu3^0o9&wE7lb$?dNs`Rmu|>x&m~DF5^2^eo=x%k+OG zeItFH{wLG_l;QzeeTy$8{hMFno-e2OqzCBvV$uitMf$&#&g0G}7hg#FNxwk<7t^`) zoQH>cD7AjYd$_+}@m~J3U-7>5Uf}!F`+y%v?+5-}`T+2Q>FG^c}6g{6wp9X$5eFpgV>9fGkrN0M$K79`O59#y3FQk7+ zjeL*0zn{!?FvVQ{ld1JhdfNLY{qTL0zWTn&Q!4u={qud3KKZ_BDA$2G!Z0vL6$a)= z!oVC!7?}O@=!5AD?&+8Mrh$Ajk}CD1HX!u}_UDa)Cw?mRFFu?;1pG+)Fz}=4BfyWP zj{-lQJ_h_m`Z(~D=@Yx%7UV&(BGp z;3_;Pot-{hJUN{QJdZm*S$v{6JAIOJFnx-a@L<}OK3#mO*p@z1d>Z)K;xoX%FFp%w z=YKz3v=<*L9t3`v>)&yGu=oJ*?~3;WKTteB%_v@wUYK6M^=8WR)BEUue{l_+ZhQjB0hJS-e9h_bg4F z$+$*mdKb}*PTucb#m|_7t?6gQ-*f$G@j0$PEk4inr__E{{G|8?T0f!uwD?!rThqVL z^ONG=Xl+gZTzrAnKU4mt_&I%B(=RAT0)Ni+OFY3BiZ44==K9;>H^naCu5@_%kK(t5@bI)VX+>QFygXe7 zydqr=yfR$@yeeG@d}g`|_^k9y;MM6_z-!XgX?9wYK3L4Ae5v?iF^BdSi@9kIa5m4X z{^ROaEiwI`(}2^8%Tf#F()1(l{9^ILVqTh?en|aC#hT>W`!&qyY#_VcrZwpq%<&q^ zoZ<(?{4_89fct+~Y~edDO^POy z0XL-ez>R4Ga8ud{WPhqOi|g7Hy5F$kE5(Q%yk&GooO_mx)$u~Tu1ZEUq@eL#acqwOw)mFX$G)8wE<_QcHpcuGmYX-E!B?n z4RqrU+U%&BIud&gCU;S7rDha&IMLeSTo2G1PPA4}$8ovWnDB67wj*dC%l#vA+}Kq; zC(*x;o@0SiQfpdG-*95NQ_{X-3>JiIa$PerCda+Uw4Qf-)&ru#*WKz*m1;Mchh6+ zbzEW8Y#dRvBY{VA9mh8w4V=VvEWfLtZXA)^u{jz(Hb=n6=BW2rqQYD0H#$6)81QzW zvEZ@Xy%U)=tT-wim4+4D({|vFv;(*^4WxHJaDO@hcmiC$9WCyxbXJ;MoS04oo|H}k zo}5kwp2DYRrKbR&lAfH@>D_NcZC_iXu^2{i7kjfD^tp}Oz09@Fl#@;sr#b>yCj8{W<)M#`vr zbDsf9OF?Zq{mo?9}asMQYj7i&59^dV^x`v%^x)e{~k?IFh{ ztiW2$?{~GgzwVRxyS6Letj`zz*NOQv?NGg_j@wY6K08;*#;S0wWWU`pcaI;Vm+mD! z8Hkn4*fax;+}9YJR-jQDeb2lMC8Ai``L4lFx!1R@F$=b}-)g+4ZS6Px&bHOE#qtq+ zL->}RmpWtA^X&s4oM~sVd#3e$n1AeCJICg)I&#{}JXP(l;Wzn9{5JpVmwJ4^lvey- z>VNyo##!4;|B=`teu+gwajJ?c>wnUJ7(RJDZ{nnQr~gZCB^HKfD|{BN8Ls?a&_qoy zlzxlw+=#7}k6G`=p?)R5QxBegJiUhc-t@rf+52nw(Bj+va(|wgXnJR)di_%JXfxF0 zQjwizBtze~RH?sC9xX4H2RM4pyxD1T>RQd6*j?X08fb)K5FAVYu<;f53YXjK(^lfO z06hapF4sbB0US*)miuM6&U6sI3O&)Ti*%nO&+A&m6UJW8dbC_QsW;5?i5h9^2O9)e zYot8|p6N~`de~iO>dqrA{E~4r`JZyvbDG?bPKhE%)RU!W%iSi$4t-z)DKmk3$Ock8 z%T143A3oIs8W^M3v@f*r#&xsH88xK`aR8E)cdJFbY0G@Tf!Z+TD3oslFN*R zSWRNoPAw{SHFCA1YaY#la35jMh;UV8wJ(yAs@g9}xmE3>q};0ZS5jV8`!4A}b^k1} zU%6H7)})NkOR5)CnG-uY>2)+77CS#FJ={aNnfZ17w0kbM0Nu^kU6?&vL)qnd8pC*3 zGYmQ@!+B?SHdsn=Pw(l}mNWM5emOmlqS<|2%x4>LMjp}jJfcQJ+ylpP)oP2Ka#m4u zjNL_N4KwZui=MRTPCK)K?zOX)nrq12hi5%7_UD<4J~)rI`}V}S!?B-_ClQ+u8T_{s^jc>IZA+VV=FPTLS!c#<8y|AsY)hLy zy_`}$7kMc1VLkV9TCuK*&A3}aBflu8lwRaS#?g#q7}Ic#kkL(d-kC$a4^UllF26n$ zIF$B0>T&=z$@x6(aG)p4EZ{9h06k4+VaEA|^te~NIKPPEUh(4mVu~X#&M%?3OT5_L zNpY8Wv3)5;j1t?IQN$~;eK|$y6x+Kf(x}+Jf+D4g?JFtbmDs+DB1Y9|t)_@qV*473 zcqPuSrHE1D{5pzwCC;y>xVy8Mzk%XTvs0;gf@qvvY!$GQZA|v#P%4JSlIhJ$qbnXMDqG zr?})UqT-Qyt2<+e75d@C72{jdw>y%m&DLr~o;PEPMjZWbSG&c^H*v=qi*;3EwpbIq zY78~^LU(PqCldF`^VYprjZg26qUKg8*|gW)o!&Rmf*$}B|Fq}bmr5Mf$`#+6fy#uy z_t?wbHR=Bjqf5@u3d(SB!ueTA5mTI> zRTMGB`B_a7Q=A{qxfWCO(0C%Om?CFdM-fxxOzSCPiu`E_ZJ*i!7tPTD(YSvRxWSlJHd zP@JvSs!h#vDxSI~(K&S-+;v%enn5jgY4$vcHtI7nhPCH8bu`?uz}a*(;$#%}e~!Hk zoJ~i=eW9IAN5j1loJ~i=-KFJ3j)prbn28blD#)ijRU%e>iJOjt`i1xzdWfUpo(-|D zwfG$SIXD{bg)O!_8tw(*F4^w?;J(@Jp6%`sv8(oIdbIf*8+Y7x*DoWE?l0l_xW*&L zQOvn97e99H_AH52V2!&~#10mokE_4HT>MEC_iS2AE%pYlfdOKuUJ6fOTMr&@pyuA< zVzeF$_Z%0;^;@_XxwvnBeP^z9(vtsqhdVUN|NKu+)0O|JEiI?W|NNyciu`XfHMyXi zPR_TIC!54`Po(A>#B;j_M9JoPzpeyPlC1@*!zju0t&9bZrLBiWxvC`Fz}Srjx--j0 z#&i^L6m9pfZvr;a-kfJ*Gd=E{CB3N|c%HxrKAT35XPd}z{+8$a%4Ozc{?dKQukuRV zb^rdyI^S2myO83^0o5tL$}2Sjcc)(jJ*gu|Rf~BWWl@~wIE~sk-ceqsj_b*e?j$pv zUU%A`#(%vF^wvb%YN>8LKBkuI_Gh zv8Pv@6i{UonOmX-WVVa;f|i7NBiaUGb1D5Ji$VFX9uRx!YJF*IDO(=$De!E~^!o1J z>Gx^hY3J#IaolVtJ~Nv`nP6{v=(D&A{ZIWZzJYk^CG5WC!c&rBFcYcyjqH36G zjshaR^H32vZXy#$acC)NUG5TZp)ZOS}$6+Odqwbz`+M0SkC-Yx&pKINGS$789Q`K2_X4G!`0@Y;2>R1KlUSj%2wJ^g&+Q@Hu0;_owTHEpnZTrOk zh|Oll=+Q9yQRrvlw%=qfkeKfGNn_@FS6Onkn!l)#tem}myT2p?4CjLWB%~^NG^}s88^^iI~^1f<+JKx2;@))J=UCe#{7%QJ% zjMEx0>ql zJ&k%35w=mq#k87=i-@%~702Pr9*swPba6cK%j3B2&+Yw5eAq|*Dk7c7ay>xL{&XOT zAqSEeav?FhreZIjUqxi}DxyVa5i2^A=;=7_I6BFH57Kj1I>=|wN@oKP0{3z~o4D#; zB7zt44QEh48!!4XL~AdgucHQB9ksCs}J{fHtlB2C!eIKSiwD<_uj{=pa9|aow zRpx#SXv|m1`*EO=-w`>^D^yqd6r~aPNv_6u8;S3J8fcuikvQUKfkqa|Gc1i5HkC#d zo61pKN0(nDLO7cKQRT?e$m7VeiR+lsDBYOy%S7wOaL?#+MENjl?-t)9 z+9QA6ktXn+{pjgi?xbf2@ltv1&ZKPXPk+C%fB6}rhyBa%5NkXl|S*Jd*kmWIz}V{t$2RY3jcr4*X%@hscTe zHSybx#Qryt8S!g+KSI3s*W^k3ij0Y067&5iSrWellBrVu2hrhQl0ETpt{+R^O#hMo z6ZmDWzaU=xadIer0sIEN{{{Re*RNCi9q=1me@=Y)6U02X5#L;!HmAdYhY@XEOW6wC z$|q}yiESoJ=6C78fnVp^i~sus@Dt=_^rC!GyrE3RowvGKxDHhzs6lf`H$Q^i~n8^Jc{cqYBR~|D7n9bxcE`P8Zqz=YP0D6 zDj7YA|1HWo(Zm`N=^7Eyg8$%G_!LlnC4DvhHhqQaZ^@VY3h~A%sSd2CW?(Z}R8uLf zz}7UG2=g>zuWKkX(rT_V(vSGQ2Z6sw6#SU$gXxFVf0S4+PwbnskBDe<+7Z#}I??L+ z!1+X?>qz0*zy(C2In{;8^FQ<752hcGdGh<>2Yka1)4$O7AQ5QJdr998h1_NI43*@sUy zmVL>u*+_juiI0J7nO1Uw1_B3?Q=`5%7C4qHp}|}SrA=i&GKeCjE?0e?xg7H527u0$f7gMl%@(OMy$t1;KVB zQ>2-^kS<^s*&@x1m_DaE|8ZD3jBK^T%Hd?I9me->E`QE9|6BSwSy>-UzvjCi06stl z*RLq=1-_RIu3ypjp7aau`8n|Y=>xzI(E25xybt(3`u?4(@cn$Yr5u`u0f+G$Td8jW z4k5d08*pp6t!zv~()Mz2Y6LdYyMy|6U~4fr?F8;9*8_K!uT7K6$-p_~r1CXsa#;hu zmg}oit*iskkY<$~3YISn|ioDRH~zI*ue4divsEN7K31>QrR=-hH9^?Bvo z^7b^poClmo`(@N`2QDb*mv^Lv@@46KzG-@Se)&c+LeDRs!u83Nr<51aHyt>= zoKc=vz9YRcotHnmlmERV-I*4Z3(KeS`3&HUvJKc)wwLE}=XvFYwA#zX<)ZS=^rZ6b zWX?W`{&UN7s6VNEd0I^W5imC`p7j+o#m49AU$W7Z{_oY< z^2KE79-zLzJh8l$yxkM&IZ&QdzKDF@lju3IJh{Au?5&gOIjKCH`pM<4@`Yr0?V^5o zxw|wcY&Si-%01L~mq(P(Cr9iE>U+u~sUHEnIXyoe1w67m8h8}&rgU>U26%M27kEs$ zkN3DK?JHMt-AB(}dREgq7PzlGu3W?QILfi*#pOk1zvB3EEq%vRjw_!BMQ zmCpoTSzeW)TC}@#^dZZz57(1u^&!_#o8YwEdm?>(iYv-1%l<$$@YDJ9wBi7}9`rGj zk@kLCeTvJ=D@rZu{nXE-{|xeC_S1HMj^6l8^u(^`>S<-3Ubc=}-|T4_T&&`IJ?T$- za24M)0C;J6S-GmXth^jJi2pIt)R%0UEx;y|4js#xF^>S)Qkx6_x@Hyo*d}A-3RGZu#bb3*q4s`dOUX)9L?$gtYauo0=?rk6k z`4ZqIw3igumCq@c@J-9{!d+ipS9a3l?im+z$5MLCc7JYped%69?l^QYpDm-u6WiRA z=!WvS-+lpJu7Xe>f-U_^}d@=BZ^0smgpWgz!rF>y&yj1wY@&)As#q2_8 z%=3Zb#`1a8Zz^vD-dx@Ue13T|@CD`bOMM;>kPA5r_+FqHle4JJq`a?qKUecFXHqi@ z^8s@5iyHAokI9*jNF0Npf7E_915qa=e0I#6Ekh=Q;yC2d5in{{4 zqtblJ)j)SqnooH)@O6ALpW3y+YqKBQouc$}-wkwcD%K+u_W<3AiuDM^y+C)LVkH9E z{;WhOUITQODOMuzEu7SaHAKD?c2U2gy_^WV2+4905~dv)d;)mW3RgRU`a1a9I{4f1 z)Ynt%DlUPRFDah}d;siQ27F$5L-}rWmHuB5G(DRhc3Do>H!jFvLx$lx3)bn7L)7}L2F34ebe-h?&QhafIDdIq~=a);+R>xy@Bmq59b}*q3W5`cJY~dm9bH& zeira>`qZ}i0oBHK)9-$3#!2_k+aIVFX{K>M;B2l(zzb#r_t1X?wLMVvoJ`wlg-0?Y zbAU(i=~1)?0o5hVOeSZTPvsZNo}=k)1R7m6V|g%e9@k@-_xZs2w9R2|g#L{x?WJGs z&e-c-aAqO!7(Us@XG4LDXv-^xWG*ojxQO<#d^QYdWLAzb47ix&(fkt~zhBj9MPonQ++9$!8jDfnJ*;wEz zuBXx-50ulLN{@T{okHKK(D*8#`RS+e*~H8rCji&bdpd1*3^PW2Ivisy@HF~Pr+pfn zbse=c;3w-cx19vvT~Ey&$0lc9JP8iHp4wToYnf|L1{zI1NV^U^i|avp&H@@!cI8wZ zSci9=O=$scr0;Av+eV=A<#T{)<7e~fIg~BHE%dd6X*0oVGfF%cVip+W=@9M&Hw!3z z&!=ZD*kSJiYIDGmg5E`$b{1uNS;S`@^vEF=QQDb*|7S7xxq{X+yE|#m14^NtnG!p> zcLw!&T$gg^VxSt=GVV9S!5oI=+-**tIcLkcV*zjhE%Wmh0vGZ>E4Y6d^C@p%$^Wzh z7jxfAK3fd*{6n+%x`4~LuIBy~%tsfWuVKXMKxM%iK36MPNox(Ctz`CG>AIG(iWw{T zPbI-*V4drFde;Eg(AvOfD}d@88{s|$u;70-Wx22^ONvcdc5LDft*%x4=O)Tz=3yQG zy_vEBewX;qEm>Y{$#P^1y=&>&L~9GRO>nn$+`X0i*1^>h|KsX{F+igw+qr8Ta5Mk6 zouZw#k-K+ruXfsDw081e+u&15oWuFg(ZKCo59hwkz|FLFamNlgQ{wJD(A!9$QfUwO z91h&Ubq}>saHXBxdjw?{a5t?Z`LEq@ogLh96g1Cj2Pk|vP+4{qy(59U`26V1`_y-K z!*>$bz4RXiRC4X*KZgR3;<}gb-UaVDlK(lDJCA{z98KSGl)XTu+i}!}z)gJjim)9!4+$F{J_R1!64F&<_uI{4Y zelX@88)tU+3$tpZhbh1*(4+Yj?n!ALMFTanF3hhm^I`$eJPgmf@q8OIG1MXE1C?lw zolq`hPRCq+tuJ+T5uq~F(HAOhoxjK)p2ahnOFW1&lXo7Jp|W1P#8vq2A>>TrO##1wE$1I&HAIa<;&(JZ;M_to=$H;*+`%wuvnYI~1<^svB%o#FM$m}6= ziOe7}tH>N9GmFeL^5l4Bu{=~iM+5WIi(&?VwLU;I(T!L;o3Sql>r-mhy<2?rlZGd# z?=R8iCo#_I^6MC*N7LmU=g{c8b@@t*SC@B&9!-}Y#YmfVww(DsRG06m#fvfO@*|;y zZe8Adx8cx(=NI+V<;{;93O$$~*Hf1tOv{|Q`Cza)c4pkE-XAJn0w zj`NASwRmYsT^`>9wQgNr3Ji@twD{2IA6=L4sl|&C>hg(k5c{=hw0M*`F-D#Anz`pV zg;k_AWG=pA<@hu`G}Z~liW$=$bM~A= zZLpXFIqOs?GQ1`+tInj>m-82vSOYC*IIK18H0?EWd19UIW}aNGrc5zcUaqD*+Qb{m z)s#>h84~?c;TqYm%EZV&bk?LgC1wZnqIIZr?qH;qLRyZq z7;WW`5_~4(ZVqlQN?YcqLM4(MR;WZ$FAyq)618dIiB|KB{FXEFdlR8$BxdBXnUP1! ztimze?TDIlI1cEjPtP+T9*kjb%#vo6EVb4=5^<`DYd&20;i<%q29ZIot^BexJdF}N z)woh(8g<8~75tb+dkUlB`k+_~G>u-z$5oI6fbKS`jv{_KO5(P5zoRrI4+MNuy44eXuU%BIMgujEk3q{Mfbbrn*}(TzJpRz1=^J!M(<{fB5mHEROOYD4~HkJ@=fWd z+6O1rA0?;OEA>eJD81Q3vFH9j_TB^Bieg*Wp4C0cIcHd8kt7OcGDuJnBB_qjqcfVuI{d? zQD4;JeEf8LF*WsXyYQar+?1?T#!&s&aZ~*w`}D^Qm8_Hul{}R!)0PZXAvd)@$Nq?$ z8Ulwk5H?6wN`|U0eNV@y za#I-}<#<=fPz~p7S*fAm(8wfh$x3B>RK`uoO4-khqK7HurbbX6f$SeKRKL$nZOKYy zJk>UC>W{c7N4m`nRmMt*j*q{`O*!&zW~f^7v@>qXnZRa-Dr2QY=L5b&qVoY+Dbe|W zJd`$9TQXGITR9v4cep8g`$C4wNZkKj+>~>+%?#E5yWCVE=iprW&u~-DmNT{^TVeiZ z+|>V$F8@c|)Rwxub7vVUXU_jBH?`$Dv-4ybs#dh4jMw=0xG87LG8|gFZoR_ntZo}O zB_I4hm79{4(gT$YmHRs6q1?BzB}3)fT*gOb+>}~w_sB`f>)G4MQ2jACB{S72awVI& zDfRTt3{?l_%raDe%uU(1ZDy$c5jQ0twKYTKzK%b~O*sl}%}~h&7qU{0Mb6#Y(5hS; z*_xY@kJ_4{l1l96N(Vr0Qwg{U9-Q$5JIrr{2-su5lJaK*zOq^#^V4tUr z6SjJsr;p^Wx%ZH~fHl%b*eK~Exohqn%I{*y^bwXldPkP!d^6%k>YKvG&@J~CdAHo# zSSxkI0`F;T`JTb%?>SIE#LrNF9*dY|9DSJ79k0mU@QJJ^Z9s>1tyeh0jzJ~G=EYY6D4o%O=-E&V;ehQ1TXR(RXi?XXc`WxO0 z+q&-2=kQ+G&OJt5pTm3MN&PxVXc4G)_4}zmh+WGK9Gy?*#iuI1=;LEDo1!TYJ{;k*Yv)*qmLH+TT#+o>-Iw}+niSYH6%i5*VQoZi{5#2>r<*5_gab2WG+xwfu7@ullN z%5%VTv2#5y^un6;D(q&?CiSG;lVcZfq!<2qF96TNR%b4ju5&r-EYjK7$zF*3GUR7r zJu(k#l8ce`%3Vr%4t6H^5oc1Lg;hvzybR9*^)%cYyX0wD1y9HF_jFJ{ zveT)b8K#CQ9Gyzq8xP67vA@;(F?*jlZ#GuFy`%T!+2s1q+#3(XM}k@pAC8@{ergXR zosM@0%M(c|5kv6R~#Id$cjU;`{J z8-{+l0?z9Z3P^n^_vKh)j`WKjV*6o}*p|=NB7dULEA*&9mEu28H>_s`Y9Zm||NidsO{!1A#USc|*_7KQs` zpC}h!3@nbNVu{c{R}`C5_LY)~VaHgTS}Bh7$5OErScFg4#>x?Y`(RCKWw2`OpQ}o_ z2sW8Dv7s!BtbeXD} zeh2I7cd-Hg0Q`vjUFsiUo&G#WUmy*}YJCtjE!GEPss01C=SW(ue?U!(^}*PszXY!1 z(;tBEk*}ll9M%vlGFZvEvSwCQ_;r$DeBK+b>kjfeR>bUvStXmzRQPVYx6XpTtpfIdTc32hGNUJ z6kM3oWBWqV)8Nyb@i0e*V*9^_y8hfB$HwPjB#%;l3_k#CD6K%|{@xW4SCX&7_Gei1 zFfa@s?yD*5rTkt{Pv>`I{c}I470|U<(hLJ#ak(121}mCtDPP6shJnM7Ud3k~!P@0I z9#?2Ux<<33S7l3zQ3o{?d?UWZ_O>_?>BWAd-*w`2&NW-y? zxtWr2F-Bk=b1P`12IE>7g>?>gJ#(Yo(YzQJb_D4D<1@fBvC27%^68X~7I6iiKb@{_2ansZHL6zIO^L%~TocjS)F9m3~Efz!wj zp>$}@2neHdMjRfUI~cj^F(-4CgGtkJ+Q*H?PVHps$AQP^j4(SIYo?Q_p8y`4Guo{C zsEs!}hBO*Wx}zu=uVM@qbAJKd9qo=ocPP69aboTON(X`C$;Wb*t6B$=d5 zP#xvQsF&PG{Wiw_*_?L?=ZhPt88cu5kPI?Iq;U*+A zNwd&lE=QuyG!s4PCQ9lxFQFUVMEwTvS~QKhNQ^r35}L`C;EPe~d6C*nQMP*L?8(lz2y@tphl+Q-vx`2{8$qVQ(Pylq&@{a3{7JKl7q?DqnR8GJ{Pr~=c3m09J2LM#~B8y zqYR09$q@9Hk&OL4ID0Qr543@vLne} zU%E2(x8!IGQcJXfR^-h&V}Hl}SoYWsl%4@wldBVTMr+ss$@Y}g6FQRbi0m1B1$3mo zJGckB$BsyLqr5vBS4T=}CeNVTv<06=Gie95qparhbkuyFjyjIMCDc(GMZH8{6U`X= zD{)RmQYEy3%H&l@YZ?D{C9lBQyMmrkl_P7TPSg~wp(^F_992(fOkN$?+Mv!xHZ{RD$6^H~#hoYJ5=O3A2~lth0i$JqY^bF06S zen2}g7K?EV*5Hq%E}#8A9{WC5hO7L{@u#9rR0gjVKU4lLSBk5B$ITHt z!D8qizal9@xhNV}DN5=j#(W8so+Lem#uF&1`8L_1Cz2pn(-!k^U z$&Bv}(wk@l8_743o(Qj_F+B-->~%hq4{ve&iJ;GwuhAObqWl^q^@K0U-$C{S-e|t0 z{t5Ug`o}v+KBoK$I@XtHP3k1h8Q-V$czBQU2WUEv2Q{C^@n`cPsE)G%eMTMS#i*CO zNc~lP1Tp6{PRrwAHR%y_f=8K+uHw9p&;mX}wkkWuk;jOv@ghg`CG=QWNl887C2~Cq zJr>qeUWsn>5;~N6&0}F5<>%0`UP4P!GcmRfdPmT^(4#@`LXQSDpGSk&+3L7nMlbfcwcPwF*~goTtBp<^vYOIjW7MzT7nl^C;SbBp0F~U5^f>Ub8A(N%<;ttn1N|R)#r9Rt9yG%h5Yl24m5$ z3~D|rgPPCEppJ7c`i$|q&W?J?+0-v!>|Y6gVI=vL;V-0P&F|7oZ9?fUw zp*I|dT%G7Vw1(p;ABARg9(uxgoN*$u72ymdN1-R3gC?b3vm%^E`E+!wbI_8Ohm(+~ znJf>+^jaRKq3J9SYCg+@n$Pl}jxz;)MjhqwsFxg0{YdmDSr~1?9u6ZYk3>fqMR_=7 z_wY%UTxnjwxf* zne!&X&`m_vnbZZ=M}A2gzQJ)FVrl3^$<>2_kvtS!#mM$3 zXg{NcPA`tRzw9CA{(FO3G(HrxWqc^em+J4;6$fpUjL4_0Q!|b&39_(D!giE1{&h)c zN?HE34|!8Q(FlPnaA@c)SE^wc1hR;wzbLMSl9t~=|8Xth2T?iBV4ZPcyT&(Qu z17S-pR(AFQc-Zej`Pc{GV1EE#CfyH%Dku92=>bsb2SIK$^Y8RQWM@C1{wXZ$$DI2r zM?MCB;_SB~$NE;}RW~7fBWxnQ6*f}d6y$ebg;9N#`kT~V4ex?)hIhbs!`t9H;XUwe z{-Z3?wQFeFCK;RA)iW)T+>z`4?#x%D-k@u7N8I0Cl;rwBO-jYNYc;`|@!q%_xdcg1 ziLRa*KUy!=?yA#YskTL08R_LzKa1{aE<@5oru+5uh^hUOyZrQ!syAq@o1hZNbENY8 zuK#(zIqn(@wipR-s3 zT4z<~ej8iB2;N4y_C9OVJ_YZ*_gP=F-hc0N8B*q<)I0Ak%gjUVw%=Tg zyZT>$pZ_Pm&#pjad-(Nwn(z+0vh3SS2MEe1DD$27ebW!U=lQ-RB;R@8w3OthwAjd# zv}<&yuwH=eiL_3rL#j(l&_+QY71}jwkx+}I$6M_YYLfJ0;d*!tQq9;7vIzHDF&5f5 zx@xB_f-S~)Razk!3BEd9h`yAKK;pT25;ii8ZOZ@5s4m8M@juh2tZVK1lr0Bly_4Q( z{ZI4{>lv~q#-#SwWmn6tkX?VvEC12evhT{SmR&i!ruV^nWNY=>-a9=G8~4QM5Z>3U zw={l)eq;TQvTw|OkshRdI{p{gf9H4UNm?(q*|!uFWWU|};P3Za|NcMD?nCw)xBQ;M zt9m!G|6|Mh@vmO9kd5+cg?BFV-s_Xu@>l)+Z}z!(hvl}iU%Tbi3ZrEBlzrBYXWCu; zpSouD+X{be;Tzyv<@@G;yY=tP-o5NS%s%_i?m%|U?D-VF6NT5${`c&f+10WuZ~c3= z{A~8jea2fp)9jx6iyeD1ALYJRTmITVcTL~AEw7fni`g}^H}%h4XUp%+epPnO?CQUF z&A-1(oBz|zZ&Hb^{v+SBteq6zi>-g>zj{rtmfiot-?_Or$=?3LzA1Z-{=&l6>k}>P zSA6fYzOAqy%C78h&F+l7SXs{c{a^U6U(>7E^XsvD^KUEc6Kr$Y@7eOo*>BtOH)r=V z>ov1qm|e4Q>~Ylb>Y3kdebyI6;{RYQmBR5!{pt6|r^4%GSNQ#N{>*j$%sGYM^^bmY z;W_{4_jm_n<+W@o7Dw8xzuhr-Yl-9W)_34P_x@!6(Ux~R`^GJw#owQk9o?)e{F(p# zUpeQ0_dff}^qTIN>i&bf+MRxl za_-R6-(!7HkHY#b)pw}g1&xtyq-;H|Hs&*Rz((XX$c;u!EI#%b%7ZpRSJ3;TOhOat z#$eI+qk5Dc1l+$@7(1JofA9(Ve$>llRd$Q$>(Zz&#)i=^r0Xd9XVw#@EO1kHIp`Zx zPnSkhE`da!ITho2OjGtl=t)Ok&*fQd)LV!?d78qYl%}jF6LGt^Mk)K^x}ltvy8zs) zAiE*c;f@g3jMaOx*v{Fm3*(g-dsueGl}e+Q7{x?3#FA_2+10WuWY^#F%71^g>{|-2 z>D96;Z+T6BpXs=vR&mfy1FbqZMST#vFIgz}{NpuVpgk~g5WxXac!_O(FwI&ao7@{CbN zw|Bp-eTZXXkvJ}9G0Pm+8ZyE-ifsorWn?l!Qo=}96?9i_LP{CIs!(!Yr2msX*d6=a z->=t|Y>%WPU-P(^&r#GJ&+hY+@z3#;-T&tOi!JI*@e*t{QGZJ}_bR;|X~uQ;eC<_c~0 zR{Q???EE(0?ScZM>v;8D$c?9yMcVPW5ipFjWB+Q@3nT5=f9s>sNIPn|M%yvA&Q4rw z$M{Xgv(SU7-)_VTBkW|px>Z!2|c4q#kMx)S!ssFQM zmtIVp^IscFKo6$=|IW(vW12_7D%;TwAcO-Xa=@{-?roQCN*0;@lv(|mr+~sTCQMd$m zt`wivdTw5PepNxemF>Vis=^bl$}`=OyHhnjc?2lWWDN=YiVW>1Dq% z&$9-{T5!K=#HVg_-ir)q=F_?vT&>VmQb&ABfHplm^N?uCBY8d8!K zXvkZj&p6}0HRoMuPF)Xi%|Yw?$H*Oe%h?qhOJjKqAoa(~kN)8M@y72A?oU3Dd%YW| zjpIN{1F*R4$2s^cLWZ{@r2F#B_5`(~+&9`$?#ol|NVzllzPt~eL1UEc%Xvmp(*{%< z&u(B>r23lN7yC@DGqvtCzM6IIIrjyvkB=6sTBMG}rdE&k#eoX%*NK!SV~eXDt@f~oVJWM(cYV4a3{FI*740N!Zl`0vdm8yPERCn~-E*-Z zo(gJ7JU7}6&y5ztbEB2;T+SGb+-Q_%Mvp6VqOI^8j?TrlS&uE3A(?~a^QDw8r+gWx z-SFku3!jXQ^laoaDPNB5^d*#M@csHj(Vlol^wTnflGfK}Qad;Le9`(@8)z+<&qY21 z>*!g0_999bV;6lcxz^F=Vre}CslHo`G(Cg*T;5#msN0gy<;`dd_9dT-{cT@x5P3m? ztvXJJY(e{WaPA%vPzsVT-j@W}HISQuDEG zmWr*cVr-XM)Y`MzQmfJ$+eEZav-Ryj+q1>mQmcc`GFtH)Y@N;#Y^g?dwDsCjYsUYy z6)ngXYfH6tI#;o!+B%)**ivns_GY$JTcx2>{q?6K4` zs;$$0+LmhTv@h4E*`Bdo+B)s~ZJTFBvh?>V+k{T10#N59Y4~Xs3)_D-E)HZk^E%R`4BY4^(jTdT5HR8f#YR3JX9NXsf*hWs}ZPm8kmTK!X z9=$E~c<^{ysV&uZIGD41uLs8#bOx>Q#MmZn!?wyfv`O2oEm1#9wpd&0$>7PfJzM2$ zTA(e~R(1*P$X>#BX-hS_`i$6yZLep>7HR7=TDmROnCiCPEBNdzTI0pkY>(&0mUA3v2T=RLs&Qm=CT;9O zM@Hw;TJ$+GRwtgC>I9je(9+cF(_e}`=Ta_y zo1a!AEJD3P{I&{|)dl^|it*bjQc@%IiBuwGOn#-UzBkjq)xNV*<_+~f?|<|^^v-%O zfA8J%zuWuo&iEo8LYEyUlN4_SO~SUGsme72ieQz<=%C^R3foZT1HK`|n=% z)_Jvz;qwjjY57LvNwQ?VkNP_A?*0%$VF1R;&mnb!INgXuFW}tJv zI&uD3hw;7zW%bxDps~7)+_)>~jII(oq2BYI#Z`*)w@PvTW(?2{NSwb_iu1Qhe7-ZS zNb7dT5PgHF$rtbzWZuE+(?%WLGQPiI9Jw3Dak?buRpMQ7G?Iwc??<^mdDEz^H;wvuQ?#prNOI(&v%6fJh34W+ zHHTh26p4PAa&f+zL&F_G*|}&g&P8)*xuYqMB`*QWU6kZIOOVEa&Wa0XNRFy`&X7fO z8=JH{&&^1{#wP8?+ufCt9FQ@Wom*s)fQ?Qnzv0Y7@9nZ5&P9w%S{OCaI1n9a zD@H3dzO6AzjdE-32l*CfHkCmc80S5{)$%INgp5uqPve})I4fDCQr}+ZOhzhoe?k`j zS4Pj65aoF{vq&q(T**8rmF7*zB9;1X%kCJXR10ePyON|*+)Eif<7I1cDyt*MCxax5 zXB-IaRb}yvRH}87vq$4V$eA0h)CjTLgU$twP3m)LM#*R^&3H1dV;Q4#JDyonN?DB0 zZO`j}*7M4CrO5YI;w|v)w6#{^EpWb~?op9HDjvsZg}KBBI#4r!as zRvMj^sIl1Q%kXZv^7yZR*OuSn_xfGs{?vCBa`W~x|DE5v^>=v>x4x^zko;%ePg}FB zuv+Vu^S-TDB-E_zmEAXGPwPn4geRlkXoTO!@i~>Gk8MibyX<^c-qu*Z&RerNtnYw& zu03k~*t@#J%F(Mn?~7cS9=hCzs=uhhd9EzD+{W%!SMPn^+|2c2&gqvW$FN?x2& zHruSgFH>{y9#-Tx=J@aY4|Dvo+~5As9KY4N_an!zwq7%qyz7n;&KL9|NmU=_Zh7$w`5o{qAS&2i1$aE(EqNEYci(6<`-kWUh?K;)wd!FqW@SbPFY`OV+^&z`lv!r4&9EI3R0*PeCu1bqv0JU5@C8bOYyXI)Jp z$1}9<`<~-TTKCTQhKBfL<)M6@K3Tn5xf{dQ;_eK0p6Jufw<(G3C5dlP67PA!-EWB8 zcfh@nuIKp<7`5HE!+YsUwrh^Qv-V-Gbo-tUqUA%*+PV|IN2CvpZGm^IUaWS5owZsn)t5THbz0dLePX zVJuMBTJ{0eWRD_066UrSCD%@R#TATRaJIdWPNCKdhSs{gY%et4{Ua)sckPANYi!U# zpfL#4iwA>)(0%(;8VVZ2vp=Qb;4pOF{*-$1X;*$^YI{buwkO*EB+4?mJxPc2pUMgc z(m|k%Zy-$sWqAXsCny^oNaH}G1qadrXsNC@b?1y8=%hUd9FhNuA?cVyq$czstDG`k75Axmshd>6>KVQ9Q2MB(Sy#XIz0a zL4yovj%ttr%`#AT{U(8tO*untGN6Ha>{ui+(!OVEmI3|MW5*#mHtLrFj=D7U6TstP zqDxac2|N+bxiqCyz?0#ZOH-N-PJ{U_O{pE%=?JzU??B!$t`T&MI(NsYXLpPmcE_k& zcZ^zfN8Tq_FmjQTc89Sm<}%Y+9Kc-Us54D92QPgd^7CM))nL_Q&xf7PQECRtQ0FLZ z56WEUDAfn$we2P9(+4=Gu1eCooO9}`q}rgXE>%f&L1&}(9@S}$r^2C^i9C8481yqJ zp8;Q9hIAHa-(rhB6+DZYo-nJ@i`c8%n`diN`e<}UQIX^JJbKGi&#>h;=Told?>wc%E7(Q1ZC)}(nmS&I`TOW=@@4w9eLwN@_AP@LR`@>g6$Z}{o{Jb z8azZlh2Q8W@ddq>+}IRPP-8E5H}xOOTmZ0*YM8$5V(Z=4e%lIH_6|?fApKVjo=dU#pE0D?Y$UW1a88&_abm1 z_!eHh7lIFfZ{yGV0q}nC9Xxs858em9i#PB4z@aKImcn|nKUcK)D?*>1>xA)!P zUEqiK>b?uS6Z{CT;CF&|fFI*0{0?vd_zC{Q7l5~epW;3IcJMavGrXAJ2HpyOjwkY4 z!CSyD@GpJ~cr*AVe$8(NZvwvpzrs8DjpSeB`}{_5KKKou&*y_TfZr04%eQlzv9jPTJRe12mH8S16~dOi0}5R!K=WZ@ZEkDcqRBVUfZt(=YhZA zuYDfq`p>UKk(mp+YV;eg>=mH>P!50XmxHb&2fVgl2D*Zk;Jck3EZC2wcyhlKbk#YJ z*Z0}rCAlJafw#XZ5`5>2;vaq%=zCub@9;B0-~Qr6;+X;321?+k{$kL!T@wHC7lF3< zQuwXE5VS8SjsN)zK>LU?__jYEwC^a3XZ!O&dy{f_&OaA)C9FJt_0IwAeJbF4|7_5e zvWj@=KMS_b@aJjmR4YS5g~=#^jBHyB`{dCghES z`yQGQS>Q;}k-90d3yuKYaj+ec3#NjO*UgBGFa>nH-k!J#lR-!7=3sN8EI6{Z2rbE5 z1jpKzL}Qo)I{LOE_5%D|aP_n`u@?>j9iew1>cYXG<8B+`EldO*iFYK@!UWKnJk z;ya86T?O8Q=nkVmd(l0Kq%{(BHMu>JB1V9&FLwYt5Cg(B=#HTidB@-ibtfW63I~0G=@`mqH7EQU7_ELC>#Ajch&SD+Q$B% zduVzRVWS`DzL{Rc*60hmGom+9HDc^8w6490r_l#=?R_62X`q7z*V*?ao(6ev)x8hV zH1-Bvb>ENJ8ofbR-TM+-qZimS*N=D^GI#xgoZbFJ<>&#*+4Uz*$6lbE-2mcubO&YY z1`@ra8z@^hh)8K&L3z5tL;~po%G?bhzDH+Jwr(hKMLL19b;F1Z(h-!W8&2$z4xqaW zMi6-2p-Vj&6&QHy4>Z=X;s1v=gNiok{&_M@o6}6dkKg)QNWh)wrCi zwFcF))SX*_8E02KGIerxvJ6H{ma~&@Z4S!Q$z^X3sGdWjo1gc9pS8fQpW>qQb6&2Ba8c?oGUJ0$CKBZdZt|GXu;H=7( zhT5RBD%Tv;hn!Wp+E5pCR;Bh-53C8+$Q2YcjrYyjuN!e0s;^p%Y4?ii+4=cy=>%XWp3MX&tz|9bmePhb>( zl`9>Uc>}#yu6I<4Y_i<4Tylqaud=Aa9pk-n1;p5*>YM8NHF)#YIy+NyzoWXRYa+F1 zDQck37i!aj)I;6bR)?0QHtPPix^boBWZ7JI0pC5!xWK zp`d->82e4oHaiyCFwlO|RRz)hb9}t7<2j=PW!H$t^NIHK+=IE&0rZT6>Cwk==7FS9 z^z;WHKZrD%5#T^16G&qi84f}+ku;VO!yevMo3V@}KC44GYYgaapF>EM8Ex!!4<#MI zD0DFAPa?Uu$4FZ4y*q$WYZ8*fNfQ{&4nsbfG?7uxeLho22Q&Ij;EGd8RY2bbqi9TE zgdE5@Ddb0S>@d(BM9zW_Wz;p=*wGxH#AtjJa`zFsSIK$su^c%Z zG{VNQd`C5KD*16-{|H9=V>t78(vhHZ>l2V31s+F!BC?~=8jj*hCy|Z;PoU=RzGKib zY}2Q3#5qnT4A+>>CyqgLnTGsS(g|oZ(~+M>IuT9BdEx0C zIROnwjm5}rC!rag#?dol3pkT&SEp?BwX+zv_6MCWo<(UIy44wc>TJ?o1=gYvnYe*x)CG`@aZ<3iFoprhnPeBuo746b)E zvUAWJjmP57!?QtmLCr*Z9;jwGle5l2>zqk>7U?3i(F$-jTkc%t=V?(ZmnA24088k&Oo!? zk88|h1HXpjm!sWZL;1Sc zqg)sJlIu8YE|R&(uID<&xamWFJ(@uuW(?PI{tcunnMoM&WuiJw_9{iP_Zxj@}h}!MiBcW$v{%*SMShY;WddH*<}9NX9U{ zlbSITZv}7X)Av%ko%!4XK7Sv_7ckGe7y139JDLC84=#+o=|aw^NBKVTMO@)tus8W) z&bkvc9^!+@?q#mInDP?ReauAf9snPtW*npkn7`U9FXMUz;Cvw8LyG)Kq^rQk$&Dhl3Upq- zhT|(iN0K#h3|YfBG@!haoJdl9VlChGD2%~su4FvT)i4HYkv~iQ3Giw1b=02(pCMmI z=_we4b>Mo=SOY#wzMfJe(9!96uDKRe+kAoZo(7-htQYv)Q?LlnbM!^7whmlN{t`!? zg-Li3$;+fHR_HpIgqM)NLRt^5=gO~g&F4XN*H0M;6 zfv@q2cS*)FmCtyO{horaQ9Ny=gkEy){ zzQr{@CcOveVEoiiIQ};HHnmSV@*bSSrx9g1KIg~>pc>}ql$ydksIh-R`Vi*fGtT*v z^by>{hkV+&YahZqe2L_1(kCzvUm^d7^eN1P42O|oKZSYtoNIo^S)YJvv)@tr92TMr z*Z3ZNhp6V9{UvDBwZHPY&)_1y;?qBH{0q>yZa;G5Yq*FXkQ-l4{1%xpYQKex_?qkf z!qvA2za#&JPkaq8(V1)fiiXu0UgBrY&xP-~MlKk`E*E~~s1bGl3jUQ(B*93xDd}f0 zAi?T>61hwM|e6}>qh3rU0j+B78D9+U@ac*(YnMkGJ+@uoH7H}68IkPgU z3|vM9zNZSQEL=vFh-JA(HI9`7E0b3b>gLshx_NcJu>x#HMUK?qyoz8|@|t{4E7*)` ze5xj?66{6|&Z$MJ2D?$6@2So8tAZ8CjYC)!cB2+Y>jmcl_4th6&Z~)}E_nmas09{~H{{B-!FuEkDb)#$$m@j09Ipi$-MIyb-aa^cYtQv}hWluTtOIAYgZD7{c1O~#;O^8q@tNJhJ;^(B zojt%kIJ+~~*cl#VH;#0nz8gG9M?Te+v?Cmddt$nAtP`9_7xM00r6bshd@nxT0UpE{ zpGFq%01wiQBRxso;X%4{W-n4#uxr=}CZs2_-og2LZ+>}uIFT-VVsAd(1?dTOKJ0Mw{o`1_f6W266rX zI22bAj6=U4$rIXVt2pa#4LWc44VEWy#%>E~;~Ndy&b4WD#%`aYjiWR6;`~?kF3#AC^9$_N zoUxZ+j_S-m+w-?8rP9n*cOl=6QWS_p)C@UEb<`w^5XgH@@G&U24oE#}f=m_Lj~J_eMP7#lV5vCMt;qwL!6SY~qlm`CqVX1aV)8b`FL12<{ijqBm&!mBkovEneFR+h(@!AzN8bcxT=7WXlS?%dWb&<~t6K z@9iMo(ZYS7Fwo5PvmKu>(3G;ho-ojqvi+Sf(3G;BoiNbU+}~+L%WO}l`#9mAslh#y zi{204RnfcayDECWePcx}27O~i_ig&dj*Rc;2vA0*Gc9pwe0zrQ>|HUgN%B5vqfm?| zTb!p=JKnQ8U?pnqO>mc(E0INb4(?>|sWj$38QIHc(}?%7GWC=^&l7OZgU_Q8?_HI6 zC$->diL?PYklb}h?`k!$1=9LpOLF%Dd55cmYCH9LC$wIxh{Sc-%<^=5r0Q>Si_Jjy z=9J`rsL6jJCs`bh#Ws2fX(R~u4!WcD(AZKBjcxQ$?#gf^!>AofX&8KptlFg5UMEo+ zN?D$35~(W;Oa)rgVX@sE7TechylEAX*lG{sz7BzP*$c_x@m)KdQhCa@!NX%Kn;hSu z$-IYUVQLO1caK6(&>aVpW9yq7TilfR4o=~HD-Bm;WV0#AWqE9gQ)26z5?h}PQyCbZ zDV#GEiK{I38B?im2R5axO^q#dYHWQ+&~h5X^|%Y=2qaCx#yrm>VyirYQa^sTtIieT zGp`VzZH4$G<#lUwzrEA-;+^&h7@5tsRVMzwu3(qtN%~A0@SNPC?Ne+JpOZVZOY@X` z_k8~D3UMXhT~CF3+=|AxL#u#l$lZ@yG`=}S`3<&SSHO#MJuSYH_*r+sx--hQYrAzH zg{Yk-+A!akXOzRvg>s5M?EObGrd~Ao%h8Fc`?Op`GBC#%m?{;al-fE!#gKLQF2?+itt|8U{y*sWU)&#wqt|9v7 zR-mR%?0v3?qylt01Y2j_Vz+ilhp9t@pValB(#k-u3E8s;T38 zw~$mv1Ga6}M4|?4TdswqCVH=LMQtQT`1akXgQPaPtnX4?Bz4eV<>%`msf!LwyF=r3 z%&JdWomiG0t(SU3%B~*D)uZp`)PQB|8-uPMI`TIG8>8_$@;3#WpwYIb6!qI2dM&zi zv*7r@J=jdWmcF$)sHW@q-vVroHjDi_s20!)bj8p2&3or67Vr(mCoKAG!`u4tdy5s8uG?Nd7->4-LH57QnA^`I88rxG++ zbpc|)Q{O#wroTbQrM_FRZ$X!(kJ%0R?rOA@b`6f^yMVi*2Ro+k4DNyk>=XKc`>CPQL+lIoL8GWye-e}48lf8mHYEMwz+wrIe*b|M{9(b?dIJFn$9_Z!v*xixrg&yvR)(uH_ z^!8Ddx(3I)iD1_-F*puR04IhCVJxHKLEwaNP;lHl5IiUx7#vj(434u0fRuux@c7`k zJl=8`7aXt0AsHXW2FLNSNXCUR!SQ_zlCi8IYGXe-Xlp+j`50ChwG|scTqg~r`4-H!V4n;l;4O{EuAxPB8wNoC9WC;5F z(J=9YkPHqd1nrqmKr$#CALRXyM{+_qE*LBPI3&l1V}lm{$0DH~j1PW{lJFPG$ACr& zKN|c?I64>~{3!6~a8xid_)$T||48ttaAeS`{|NBNa756Ce`=Tx2S1ha5n)O=6~=uE zlBr>G(9ghRBvZoS;dHq5!-LHJ;m9Y4!zdpP>Q!J;I1Ao=66M3fp+U?4Ly=4hhXn2a z4?%KhI5_AH;9w+&gbPEo{6}(dxFE>pUx4JoaDLDa!1+k1hYMlZ&r=f44Hv%Tor-9SMv|ya~Q^0BAl%SV_lfhHM$>B

lx_3X*-+rZ*G}nrGd)`_Q4f1$On3J3|>qMbh3-y-?t0J zK3zay8Di=E0q5ZSP~fRpT4!i$Fc`30=hxL0bc3hb2tdba-M3N_24Tu|a0iU1s(b>o zM`H0IV-QmE0*>htI&UX^VPCb#0-MVjG>3bT$#02L?-%!N21>e?51IIcy%tTl2THEX z8Kw@=novW<+KgMK)mInZ)$HmGRYZi9{SpGNch<$P{gkjGK{ zkU5B@(koc=C01{ic7ulIw$v_cjlXCs=`lU+_6SWE#nZ0PSk~3{o0ssInEH^*D`=hB zNXuwpR6%lGFzI4G?ez#YAH#3Te_vdw{*n5_5yh@w^%DT8^4<07Xr`FmRL2+66gUtn{EeL8R=wPUga`jBfh zcx|zkORJX=1AYGKk`}@C`3y7vLLa@iKH(u@5N0NgY88%AGQqk#)Dj=0vX-S0^K?GL zEEM~49b)(GzO7FfXlA;+|KOi@Gg;osv>Gr`(yXM*7d-G>FCdwoeCob{U~|R&E#4c_ z1(}U3kHsbwW>vn38CiDMB+_RK7(=a(HQ2~?B(?PAtSbO;HU|8pf3AYzcV)ylI=$+f z4cHl4u<^M9CWh|9kz-UVIGSi48niIWpHkVX(y7vX4SBhKQviA&T8y6`#5c zLer^6Woz(Y+c7ohn{_I(8+b+ESOfO@*+SVNMX+^-4`g%-$0rb4vzD{Gdy3$BVSH1$ z^kia(_ji8ChGJabA5e5;9MT8Xt#>X|zgqu18Pg?;P8fZ#PS9Am()*qj;6rD1>Nb$W zU|eC+1GHsVj(-|OSZ^h)8fF4oVq=IOPDrEgH)zP1Xoh}+Ey?#hil~ScMm0rYE$FTf z?V>=Pl#jePCyZJ>Z}JAsxiw)a4F}Og(v|uS`;g9Ok|m6;zF$Yeb`{V!qhyU}(KmFU^{`Tkp_{V?#^MC#ESH$X{ z{{8QN{^!5_?SKCH_dov1m6*?Tcp9Ki!_S3dK_R5p;BT0(!_Q<;q7KhLKW>~S*AKRb$Loo{e`~f!G-{*h#U$Gw&{i<@s>l?JN*Io6a>uVMb0Im7%tIcfXoO52 z!-TkSbifT7Vf;u@5cVq#J=)TqLhm*06m}|toC%xpXq%yi^uxBiYI%4c{Nz5ej-YIfVGhCMmx4_0{SRtXtl-&pMN`)hraDu*YBlEl}=^@fw&C>K(rQiJe9YI9+{R2GS-`SK&wA?<#WGS4D3=`xK zs8^TfNdyZA{=fh2U;g`l``17J_3!^ru@a2!7w!3P|0-+11MJ&|*!R!*u`i_wh_jfO zXl@n#(cka-DJZfbVnUIq(-Zn-XN zx`qq02^l?>x-8628j_G)57PylB0|Df@V&rj{EeBAGnNw551xe`psYr2-A?cT5gtEz z`NGg@gjt`z0n2qu35T>N`%RdpQ_-EC1w6}bqG5Az zJ=?bB3rxi9iqTWFe#%M!+))v=jQjr5wi(?((zJat1^lk?Mp@lAqK68_MD1kHuN~G^C&vy|Fx|WaAxEU^*iA>lk&w` zq@S%i=IqFK)7Ora>-r}>Z{%^*DPA-`tL7Af{nY+%t%jgfuWLR;X`EdV#Vr*B4B2wP z(OXhx^mB^~O3Z`a{Zf?o`9nq&1ynv{5o})invTV)XF3)-S4&a^>6;=V$xd`Bl{WRH z6b9z*8FkDbtS3=*8;&|g^4B-(&3Ptt_B+l}J#0v}hBY?G1K-guisrN$PQ8XCaq=;< z_T_^GNi_ebmJtzI{t#4^K?*kbVUXS#ru}3MO!HF`9PtF`?S6YhwctYG8SAm$)CHh* zOBm9wpgOC*{DmV8^o6~B;l9C7zuy1+2jr!I#!V*Nln=ao@T}S+L6N@- zt;$6PHWpw)8j>8CWmOKFHs5|&9a!1^d2UTtGVExA4tatHuq|Qv`WJj2_D!O-sFtxB z_1nDHZ^3fyMgqy*kjo6Ww)FL5QtGuHFuh^cs-B;xV%qiH#ZiF8n!>6aikXvM_13X` z$Eq&kkgB?@#@PzQ&!ebg$%pBA%cyMJ2^GGv90W<#EjXkhTEv(j&QS_Q6&t$c*t)=< zM=>oVITYE4N$f$%2TcX96~LJ2M=jPr0A3@nV+7GP1Rw1)+m8O%Uq1|L@87x0G^QhN z1A-A`*os%|21Y=G(KChZ#~TF6>j=Is z>Cy$bj+xYjEXr32K@+jCydEE4{^FAaq&U7nKnE5PQ+;;!z92~WY>4!>Ht86>moJ)q zNd?g_rw#CRSon9KN1|{6JqMPyj8*)AQk#V&%)|yYE=chE#A9RY0v_o53(Hsz9_mT@ zrRybnS_5RrBSnA_G*TTS%a324hl%Ao5ROCxwy+dvHUy)WdJ@5O=E)Vs81J9qBF?0_ zoXwu<&D&!2r;osYsW2&#h*f*OC|H@m5p|tAugOf5^=fzpF$b$WZJ6N+b@& z=$OwkPz6JdbCZ`rRPpUd2iNaJFZDEr2+WG}f_NCPA^6;T7g6nmf&$Nu;Tr=d1X^VG;X^Cmbk_sxkPBKOc%i+#8zJ83``8RqJ zxwPxmBd4?ys~9LmQ6FpW6a(Aj%<+5iC7DK=gWQ>P`6F!uL?)|tfpp|Fj}@oG4${b~ zf#D}XU)}#n_KlUKfzP?Ga-15K=uvh#`AU{}mz2wAUYFT3qXLZ}RE^_b!1#iJ zud+w}i}cqwT}5O%$s^_%z9Oso6_gY?xb_wQP?OJj4Zn1xXP}^gi%m>b`lJNO?x_Wt z`rj$H3|q;5VVqU*9}-)n*gaE_Exf>>>4rgv-b(})Vo0i&;wdFR$Z^ItynN9bOZkDM z6+BRLOjL5*GYyvgs`Vo=4GM=vV8@^iG%5+@<-^=iqCjo3iZpNiPV`jI%V0Xb?1>m> zzmPoq3lc;io#yR}mLYTYMsP$a8DG5}qQf~*JW<9asO8_3(T2Ga2h?L|A#0b{eua=7 z)6mul@m`xWn=&Do&av$!Jwq~U#ZsJyEWxnXR56mZD&b11F9@z1Y^h`oVsGDyMMj&Uo(aZa@`41t$llAZ!;@@@$fLB zO(_R2wJX!*NRSF^qGKFtF-SzVRPw%AYD?X+?EtV6DAZj1P5~Rj@gnq9QSxj$#y?T( zzC_DLgRfl}>idhZoKTf8uzDq<9~xpvrV&=gaisyUW|zX3dLBbm*s&vHZ6KZ% zfw$V-srpb_ui-bGMhDvq$ulC1U-(@oFg*QI&ts^AONXwS!%)-w=+Lr!RsnCJAvTQS zN?}vxo6>e5Y0C32^*n|@*=+fMA))REs*+3$>Dg+#erUbL9ioYVETKj!MjB4huGH|! zmwFmQBC-WP2FO5#mO=8?YWo!l6~~jU_#~L1yM_N}LU0yCV#)qcoVBj35IxlM2&Oj@ zTs1Jpkk!>{4<+RNpi(=l(tw0C6R}_5jkE_1H+1GrFIArDdGubF^r%)q?_jZUzJkRm zB--k(LDAuI; z1sNw^!mD9qB*;2lig)p~R{S*w8KP95-a~dK8pOk+7D%i_o|vw_%~0s`@K#NcKaZj`{-ML>nKsv;`8*_AtPYzAc)#$S3e0bWW3K z`%VtO^$9hGua>w|on$ja^f9RfQw4|ceDt_d6hyqdJ2M!Vw2P$|K1X{>>!d-X~dnIRR*&zl26 zcz+5(!es33HlcylI8B)D5L&oS_bFnlFN$qoUB2USneJWCn zLNI)&=UEgnUt!S@K^hTMy)J_xq57NxCd!QT{Am3-bflrQ@j~=c&!b2vevG0Ic^|-5 zHZN^MD<}C>t-W*;lBT1WRO&CxoCJ^cJdWwLYR9J>vkf5Q7~}gE_Y%%dk~rH6GW=?@ zVPcY8Jz2-fsL@M3k0Gs($5iwfMv&3CN*fUQPNWf+{EQ@qV;9;|VP5K<;)E3TiaI?p z$#JGthLZxgK`5&qkb0qr-DvoZbbiu$g%_ZW2l5-9r6HpMD^0K-GU~LCA#=Xyq-?Ol z+A6EIBC_2S1dBSQmmST_2rygK=oY&PLwX4oxbzHUXXKEcOSR1q*)vx_pH#(=yerdp zM2mP3`)&x+5OgK-#eiqp)X8BA8C9dX<7w73)IX_$62~(vNef?%?O%w(NhZ?zM!oT) z&Eh}LrHp&6(C`FgbI(kG;W*e{yqZ3w&9mPlguK@=dOqrPM z3>Ib~5#wN^?WcKG(&wyor^K#7u``Jn)!)eY5+vcpP_NlS3G+&Kg%ZTiSv>C)XABw< z&nKPQ41b{I&$JqnJ7d_FN1n19$RnVwS;3CtTjVDD7v$hbR_NbgN*?~{OD9jHBDqt;e)1nI1h9(-$1`zu|#*4xP9pGPZM)gC(r+V6l(e8mnqmni4 zyMrFU7R~n```VAD@uTN@9?Nt;YLDzCV~=+Q1QY%iPfyJHshFC-2TyJ4JhYFyW?hBN zV(ER-`lVPZBk_Kon(3I!6YE|34xPrjy97XY&;26Ut) zr#E_#^bh(MZmXKAjr^F9o>^U=&DK0(J1aKGuHhK<>pZV?(xU(#N3!yB3sBf0W04FL zt9z`yDe1Q~6Y0R|nr2m-_SVQn=XUd;lZLPeN!#+aHI|u%Fc|orarK|KwD9KX=$i44 zAj`-YH7(knzHN@)|nFN4LN0Gk| ziR0GO2(%5yUTdsxWV?m;u3X!7JeZ5+Sg~xZUqR_4L=O;p&_`|ipC=Qzj1zi1i7AHo zcLAymuLn_uYlYXQbpmNkYVMZ?(C0Vh6WJ=2Fr!x~4?ycP5)`IRMTc&r;p=T1Uo?{l z8fg{(KCM)!)+ChlI6BbU90;4#%%scMuke75(O?R63?A!w9M5k+EIJ_q4Ghh=66{=_ z-|}kUs}T?Oxu+UA4Nr9!70)k0EEqb#_JJ%raz;4n2Mr(FY(IC3Zn2GY$|Q|%BZkqofB>=-K{J%! zUWygZWr_C$)b^8XF4XzA7`%s+s5-->dE)*Fj^ezR3 z3^65|W{5W2`W$)?AA)8vjQlsdVu+=zCDio8n_nG885BmdZxyeVM7l;irN z5H^ctPz-hpnV3YaSlV4v8np4GT#gu(I$A=HkZxaGbqrL3o?G(840lD(E(>E>q{FU6 zEIiaYlIbzxfl(c7+X6DT$ZUhnA{lV1Th_*<)`BEuA7Yla^i5&pJyww~9#e9#igu6O zA!x@qYTVtQF_XfvSIk%d>j_CElia`+Lb8xz0mlcR*?osvrl{x7a2yY;{XQJ=npeD= z`SzPYbGsqgS9S(R6lq_7sS_auNB3BC8Q;RIEay+Oj^kA(lniM5{!7;5?i)U%{cW>6 z`a?O4=~Sg-SA5beeh-R_NF1}O4>kNTpnbopz2U>y$SFG7U9{U4Q@f`XlHP>l`MX?t zQ>bXR_TW}OG~Lo z37o!H`iq@SH_?%uT}!;W09=ZuS)a{pQ6;5ad`*Y^gyp(7&Ia-X#X;kQ8^;}7sA+Ly zilAA6P6@suXcxQ_h|UONAeV0*0dh7GHXy0}CKP4-W_`1JegiGRQJI2Zi9H#FZAHI^ z5AIQ`?EN`r)d9umGy*QY0qvyD3EoO`ru&J7&pE2Pz@}-P&7)^8HuT#T0azIYqi1qA zGFZ-V4+S}}yrfYXSLbw-4*5-Q023dlldn%@ciy+!VCt4#qp}0;$#-9>R`w!+Ql%nD)_FfML>I_l zEtZ2tZYCxg#$)I16@@^JW3^ix+xI3{ucjYRDwVr}ojZKQ+Tmxb-kjrD<4)L9ovJ!F z^$@Do*KDa5`QG*bmQFP*zQDijC%&{&>JAA!zfG||{CU7K6wPrphK?(PYM;S=r7f@$ zm;6%Qmt3-g1~S$^l-_%dvRlZ~8;<3*+#x!h^cETI0Xfbs1lIn7B0axRaRzM1kPE7q z=@+`XIA(RG%I^=2vmNI5A$WeFVnvX{gKGH3yuYwuXQQDxQb`)^6pHQ|B-ePFCHuRUWD%g0f&q%`ebOHI4aHz|?*fyir@ICw)qw*R*q7VX%2CUbdB9kB zbq+=IR=8~SORS|WnQoATiaft$_DL$PO@5JP)hdF9;!8W)#FmKwFiXXVQNzdjG1JEpzfs5*%i*|*=5bul}bxys5h-;HyFI*bo zl6yn1onT{&mxZdWf=bYH@5ITBiXRv3y0XDI-htuT*cbZ`Sx>QDiRUtE02uDu8A%M^ zis3(TwEj?GZwK9;6vTAyYl!ldXrtCzc~p7x!dnh9E(D)KF?uXKLK@!dA7ow)xTChY zB#JaZC3bO$h9fi|0B5;1iuNgDk?w9UMrY^iUqI~pog=RLUo1QN^B>q{>(E?|_H{|* zIF3s2dkoYndO`&Iqt*NM57m+>Z+Zd2EGL{X>JeNP$3UM>a$UZKI^$&dh9k#qJPpOf z{KIuj31^Q<>COKNa2cM1hOTHzu`*?#KTO%uv#uXMr*?kQb7cdL=K-@Q2KIll9Ti8J zp&dsyr`>@gjZjN;9ISr;7)!SbU>3)KU7h*oHbnUyR-ocZw49x$rEj1jlY%Q4I=EUF zj85nvgL;ahPu^B3ER zu^+0iz6Vag1=R|g9GF`{lbwV;b&LwE941G)WyeV&qs7 zkL_mQY~;{5wT>2Jt;c8$jA?r{*e}(n=AjByOu(4&3)!|0Qqi|q#I<=aC}jF=e(2RH z4<7>N7!&0%kkED9yna_=x!xVL)eWLYb~K@)_uL#@>IAA7nx3K!E{kBKL~Yj;_Y&KO zdixb+#-J2_$>KwlCC7%OI6aT_ZLnhG`xv$iOVjyAsk32edgzFhgHF_S70M-?M9FwM za;9=`UrYeACS5aCq9rcI8%sVuePFcWGtTz!(8^cDM|qBV!|47K1d6` zs^-(7x(T=xOVd%jtz5L7(?~oi(Fx6E<3SQSvG@bK+SYJ_g~nvPrMm-`qG;Z#x$R8c z;Lfo1l}nOZ3_oLdjay;9V+%PTIkfl})f$49;OH9Z_t*OBa||5eU_H=C#%o9}+ym3U z(9de1Bq}LAa6z+CqmMCSe3XZEYvO(&A;yn6l`SVfT27aTgqKSq!>CsXL? z;R;sVM+lZvQm9dq;M!NTeThAV+}@@0l{FASoN>W=5Z^6v>NrzWQS7rotc^Lfig6w) zYLB&#Ct-kt28Tn*9|&dOP!PB5h3k+X*}%l zdp*aiT#j4Ot2`t7yg3EM5?C~Qt6#eTL_)vn#wI!k=f+Pm*2gmAnou&Zkjvso`&Xh> zecXXhPVj_ze&N;@sjAI(ILIiQ3*KWKAH0^GZRHhi!7*J@=t4%$%?*>qmA}kDFc~3_ zqK`NHBWa?ze!)ykvyOK3RM%;j9s?Wj8VAAysC2%?(r!TP!PE4ia-{jYeqk5Ab-dDr zivv$i)BF`N4^`zP%ae+uM*Qp(5$IIHnVkjL=UZ5EZ3qliJFH|V7<#w@%`!)d1QKMX zsg!c}lL}M|q3qHLom(kr?*zP>YTye8=%AW??~7QjO@m1R zcHo%nt8!#F)a<~eXb!7x3WfVNA2tIw3R`|%ciP_8hQYw_ELT6wum9ShNIc61-sm#S9PIl z!S()SSBL365nve6HcRBv!NLQ zm!SFJ!Dx@8z4sSQ1J+r&nzv}KE;M2F*1ozicxaT=NKdM1Zd`=a=?lp3YFSgSih8_c#V{+dkg(y%nF)W zut}%I94kghLVUKg)g6!Va|OEf8j6c+3#TQb6-l!xl>}tfNEx$ck5#$kNk&aK7P|Z! zZ?0Jbn2}hCY2Q|JG5cHJ5X<`Z33~3KXkcuN8aAJ3eqMX+6=duNK>h)fjR9RNaa*uMH@RUZ6|eDs>7q)vKpW+ZV=< zTi_7EYaR|c--JiKwjrv;f97By7L68*M#C90i{hMG^lznY`i0d&v9#^bpe3bMb@G!k zNQ2NZ6+M3MT3~MPEj$J+MbW$z{a_76jv8|~gq?vDx;B^hNfh6g62uxd@OLvRiVYW4$7&v-8l zXuReZo>Tc3IMs6v&$TKX5`+4q*okRmEWeFhu!11~F2fVGqlKuX_`l`r)EBd7$D%&J zOGtjCMYthCo{qH@rD4v#F^qZ68;IYF_FL|V(+`8jpgc49Ucu(te8sq+oXQ6 z3(Qqf?%f!6KS+nA3nJve8(4U(=lPXk!X;BOA5X0MpLgHxFyh!%>=TAP@nUyb62xN3 zl4zz|s|-Kh>DzzXycKg$lTMR!nSgWeb(i)*kuPc4>27Etrn&d|xs_!yTILT{UA`MQ zc5Qgwa^I-R4_1N^qMS?#xaayt-&7$V-s?7ErsHEiqIAcT%cbH6%E|XKda?Gqg z=E9eI(_k*0pagx}YDIQgILPAmfT6H#-%A^!Hs6AD7JG?UNB{Z$wrQ}PUoSa5lpmJt zq}Gm*=ur&|&wT6RQ0w&!nWbdFvJc)1&-jN-I=vaHe2gmR8j@=xa@0g$s77*pf;{B+ z2aH?UHH0ih@&yN$twLO^et)MSpnVE|9l2-l;D;vG;PT|U`>M+B61!sPaiN(i`XuyX zCMbX`y1x-pGJY>c0qDC%_URr#?90EvvFoK+1U;T8pCJ|@bmsASY91Pw{A-K3w6$-7 zFQey!SK}F#(_-jKd7#0Ph-t5(dVa6t%U{ql-=vmFFEGDPW`T5Oef5Cvsoasx>l_yff_gSgVW2K7V6@qhSUccq-E{wL0C z55NSS3!3l+w&;E>{#tyn8;F@sn(a}vV0)M)aH0LAV0{q1`dmAf%l3otB2hdZyPmip z>iTX2#F|%H$$?Do#Acp78h7tB2O<~l*Zszg$>ZEMn*wIus< zu^Le6Oseg~S>@xqk`apQe0u)0n%>?OX=s{m=vkf>V9_Q6zb zGZ~955ryS#Z$qPAXUls)$eB&uTfs_|A#C$V zmGdW64TgHbAU?p3<~NpZf|r7fbJ*Dqtj|5_w9gde;+9PXw-#42RIdA~jpyQ#n$EYV zDmPmS*QrK)(uilDDNr%j*z^1ho#e)~L9+9uLgxAxDb$poCVIy98&U{sABx_}ap*N9 z&(F|RBuzu>HfHVHP}wtc0?CEfx&g^_gw6-SIM-2IvgzApwPq#oF)3aDZ~R<$84OyA z6Qk&2MAt9`dIgM7CNR z6idhTZC&Lon^-Z2Zt!I5%LK~+Hp`#0!En#Tp6ccp5&zMW-FG->!!U^W+t^Swby%?%jL|M`X*RPyG{8x z7QJNgf6{S4A6YQcu@A6rtHD<1I;C#hfM|cL--Kkks?rk@0YtedtGVB;V@U(&vs!aB zdvngz+s?n0qvN{C_+C<`cAA_9qZaWnj7)nk+)6ePy?Dl-u_MS7)HlOwABs;ErR5O3 z#;EDeO3$c2NKP`%zqPm@n+*G0X87Jd7t5mW!BXcmSFA>eBxupf@%c_82gweV?-bG| zNZKU|>ZvGEu-kpGz1GvD)Ed_n!{HV@Y_R$L8t=howOOyaT^M~)NAy}ZAbEanPWtcx zY*@@U9U=buWFn(=Wgb&9UTeZ^AxBkM8P74KmISx~Mbh>QISmIH14xC($lPc{39bQF zgvQhAoFphln{(V&neC|@j;nfACuvrkRJYKFR?dbWjem4^@$w8}uZ`;zU z@S&bWFddrnkudo-o|%QzoRDM~pyI-&-EaDxSkozEslB_ox^a7=NM#*7)sq;echy{| zXt!#ii5pyBc3qfOVp#pX#6dMD2Fq+9ies8v>?x<g*YWg|u&KQMNq!0Ko@K5rdbq2$H5; zJ-kJXklu*19`_5n02(R;n4r64Op-B zJd#U=HNO)SPrDK_1kKvNsbcZqwU`_sFIEmWa_4tjL~oH?PGSh;g$UU1z%`3q&FWgJ zEjg<`dMet@_YJXhwbU<<+jYCv$9LvI5O+KOH zgFU#xb6F%Wka4NBrYS#^Ix(~Ut^1y3yRn%*{Sy^n|57dSIzH4)#0&T>71!Keaf;DZ z4#|*d*EqFpLRoz6GhBM+ouWybD*-S%J}a@g02nOI(sR~jG&Jq@bn@9J(6npVkDtqO z=`~SIFQ+-PVYk;Kk(=$eJNj82b`cHc<5UmFOF3IFgh6p$C;xKdjcO zM;o8I5NhR-cHEYu-`8{(<$x6DP3V)Pt&I%kb^^{F)neG)$4?$BcXsOdS)RZOAvq?M z=SO$M?5pLUhkIz?JPF;D6@}_29;ijoJARh}-&fe@7)NK_?L9iR09SUT+me~rZGGTQ&p z3TKR9qIDQ4!2O_p(UQTN))WnAL45R7_ajKVYU057P=WxNgaSrh?LEZ2_34$+W^{&R z0}Jt(sy!o#?ybI?eu^K<3F4)Qi9Op1nobz$i6rhtX_EB7W2vDLV*}={FunF?Sas#S zESi^$JPz`TR(-SAliQFB6Hw+r^g9XNNge}sJ@Z__c7kh2lJ_|_9RtTkSh9nP-fs1E zl?8{hUX75{*0I79Tq|l5PY<5!c}k{ZYXiUTu)(j}bp^IUFfdd95YL?y%IyL?NVa7T z+SoO}*7G=$F*_!t$I%|A--c%WoqJs?KEtlK+bAnZH%M-|g7CF0lIsSNn|UkYFCcAj zLB;*?$?enHUj9JEc8uWIe$W}N-1&qdpKlDom)cud6t4;7(tsD?-wvC_61}tEr3d3V z2A(C70yg>4s->$PA}TX)MW9lCY%#n*#HGnDR@h8Hse0VSaCXFJFO}L3=N&fs?egs3 zX!dWekuM$X^5KSo4f<`@?P%n{z1g|+^OW7t)EXkv%Q2Z~f; zNC7wT`TP&Bf8m4zCCwk63i`5=l6@gwoeptgh}eTS+EH7Mf8R-o9c$1-v{c9yOvIbz zkItG5_0a^agNJzrtE^o%VMyU6CX!s~4|oNs-&vnb?0E1%J9>P7U8l&8I3}DkeNLwo z?4${(@aYfOoigo4Zn1jkl*i9xk-MZ*nD_kC5(;S2DT>8^6N(vl1ONhr5@jdDLfD{J9>HWbC9tqJ-VNApQ1BG52=6vh2up?z`;kmayu-s&5Tn>&DOn$k+||!Y#qtg3&Pi?&llKtg6f; zCr6GdwvMN4b!)AaoD4=Ven$jz&8ecm{=$TC*0b*~0_VFUulOyXv%j_^ur}1-T^jp=lD1Z&!8eU_Gs2R_T8%Ca3mOTO3XRRf`kqERT#>Z;yKP&& z{m&o$_lx$n{6qca>{n3$rrvaYTR^7Sofh51{3PszA^EYEfNnLdsmY{xTlx&%_+k_cvG`pr#R zTHBdKa7)W;-|YUrB?T^DPqF65wKrU;DA7^QKNB++R7un(d-oNGS|9)Mw}1Qnw?F^( z&;RwmoPPVifBHYa{mXy+v_ka4!U;h2~KYsf&Lk!iI z+Sm3gX#@Kb}MbqOo4v!t%&@ZuA=(T0E?Z`&Ubui@&6pMtPh-$HLJOg*fk4n>)Y@S+2QFc z$?M;t)^^%j?(ZXcdOfh~{jF&E;TFwC70B)MLm;iEsdN$Aw5;`k90*#j*B^gieeA6F zt+=(U&rC~eJ8fDvd>KWIogNVo^A%%SABPv_?mX0$ko|CBz`*8Ci5X4{+UHx2Un7Hjn-ul1B$6JoxYb`al2eU;q01U;p@T#fN2_ zLHWb~_$$8Z>JAa=6je>9hL9o8pTp$k0G62kgpvvf^zst?n-soXI!kSpF9UQE?C|vi zvO9L;fcUfR{}ifz2%Q=Sa(vu!LhN+^PuVl==FJ`Tg3Uha%av_&c>sGXf^$pNa%&v{ zTy2e+@oT@QMPfU8U#&y`^#>BT|HT4D0MC2X-cJ8swd~qE%pE{V21R|6QiNxrvZmk& zy)jFfl9C4{+1@hv{B(H=Z%U{xOrPEX*#Tv{eQ=#J0P1r;J4gXsx+2BN+MBG#iG=0| zZTYFP%lOkGs(m&icy);qBz<13_QL}Y=TEt{TIfR|1QFZk7v9A?H}@oLc`4xd9DuK+ zXDft#%`k!#`aJujY!&%id9Oro3MY7CsQeuDNcL^bqSi4?m#BPuV%$RcIniy((_p!! zwea7cNm)5Uo|M)#+Hm(7$JZwk>IOSLXAf1+ege=)KQpLBRjnKbG0P&E6S7vagOOPa z9&}Z%>QKRpMgaZfDf}!jZ}a-IIvB(iJLhK)SBNF1?L4CZ8dqqQTQjAl4Uo-e)ccG> zEiGmIyJ0(d#JA2Y~4ZIY0+ z+71Kj*U6t2T^n_cF)lK@TIeIeqjJ|bs5^ZFe}#-TSdlWHNho?pmnKoh`|arHCQRm~ z{O^+0;zlhCq_pWNL2!H8A^k&2;NJ75wmbV9rE)hF{8?v?C_p`cp3Y0g4^riQc2yLL zfDfp8ref<)3#SKA;so#Fc%?~D&qGEDf=H@(MN7ttS5K;zpK6JzcKm&jm8m!8I<3@1 z>!$BHaOT)=R0e4&s^*JT5+D;Iy`{bW)5xOWfz8{WVQrB`TiRT@ zSn2a0bwv5+Lzu$uowi%wnID+4xZ*8Q+ghfdMePSEjqVJ1VF%*ku7qO&@ zQDy}r2!fSii7#*BK-a&{c)>6X)S+1X>CP0n;^WsR@+>AZq@|v1S(v8z$#ps(7e9A~ zU!^Gr2Dt97y*#&9sQ7`l>y5!bV6ai0jDkJ9y`u6lef00YrioW8&4JeP!^1Vsbwfu| zZ9#D?cETx6)^SagUP~wpTkegQSzq2mo2J7*(uTuWl(SqBz_7nAG=9v9=M`rs)`yaK zav+oaye15kR@8Yu~TO$M8;!JpgH4{uF0%lswWtw4Wv-N#%U# z7Xo9;lNV)oG&wEgWlAd?c;R|shd0V&wG8-yqB{yfgmjGCei3`l^#r|teR@=`T?A4M zbH#-c1o%idKe~)jl2ecLYS#=eSi7;Sli{K3m(KW}Bxc3zB}rFcwa@42K53%w3l#1J z`0sSy%Wd-_z?-JBQp*(?!zVOPaF@y%E)3G72F0egn|mir$7Cm z`l`cwFo-XfK&JW`cD+YLP}M^AdM)Ovj|duh`X5g*Xz9Q2QFmpHQ)waeRj zRXlxOuIeu)W@m#>k0ibC)=#3irR_6r-Cf4zC5hYLhYp?` zy7e8KT%n(NRi6-2Ry3i0L6P*=g}vm;UDHSUn($|WW;c#@|7YW!cJh3_Vr8yKQLHc7 zQb~#vg}Xf3`J#pYGPTT>qj}k{`!RQPnXdA+0sDc-B^kTy7mpoiR@tu${lWN(^T5FG zY2*=V!^a($ZbRhrHK!$!`wZIOjY{0=Kw8(@V#h)=rwu04G3(EzZlO1SOV>x7qsunAbgSDi+r0Lr`;l=!+PuQKS15z> z6oFscKn78n>$hqyB)K!sSDAJ)pEJ`c7xkkFAG0>~_|YrQsn7X+iwQ~#IjpmQ8!}{A zG(zQq><^M8XZgO}gz4?2WB7$X(74tyv+i7n4F5mUsG;_TM$X_BsQ!5TYc>{PT%G@Y zp=0#7+r#3iF7d2lVLT~9s0|bvm^p}Ym=%E5M){zr>^| zef#hc&nour3+szyzWK+{vmu#lM)f=A^u@m|f1X*j4JYUGm*l;)!jw9CoBGv_TIL-W zmWTT{h(w&Qy^O4H)KB`Q;^VFyR71hMuEp!LN|c%D(1T_x2cBs&nrntpXK9V+5AP7J z!>A4K=Zb6XvguqGbKY3*5$Ef9NXRjA?S5->MMqYIl`~%qFO-+F&XSgdQ&F62Vwm($ zKGw0M@xzJ1A12!6Vl2X>xxk~ttD*+|;VS%|>i3H~w))%W1SQs4+_8DEXj$kjemNYH zGO8=398O%qR{%IucK%0dQhK2Pi_1gFzYfo$eM;I-9$4YkDjog-*pqHTH=#kd?@io~ z9?J6`@t;$my0pJld9SrhQ6R4%7O|a` z)PxDEKlq4WpkVsi@B>;VQkF2GpCGM0bX%s@^(a}N5XA;>!FwI%niI$C1cLg{M%&Sm z%&B{6Nhgl-Cd@@UaVu_M>(Cv%>!e*F zMS7!(*&4h#df0K(NP{t583CqC9kZ`Bc=to43{H)!S=^0GhurNOqHo8wX4$Mmc8StE z?r4f5$AiuRg?;APA9pDcr-|YS80j`Tq(j+HDx|vqMi_S(#gJe3-AS|`Z&__;8@JyORw*I&CFLQ- zh$hMt7U(YHgS?~qpD81_=eYv>4YYi@`#gNc3r%PK5F>kjPlC}BP4&SOjzk2^Gvuy4 zOW&9a6f7^T;`p3S%HCv50}g9wd&gEk(uUFEVDY8OGh5QxgwYTFZ&E!P`@e%Wy)4fM zcv+_t`T4SjUWWzRiF^jxw=Q9&9Q^6TN{VC~S12Yg4K zRKt4lLi4HQ;_yOwVH7(+PM+5^bFPu6_}mGZNdphhBX8jT8Ne{1MPkx$&L4bFLofbj zX;@xU_5suEWQ!e4<0=T|{S9UKAiRn4q^!ZTm^6VPjMm>l8V&>+pd*hv1X98B`6ZA= zrq}Wq3*=e#$gc&GC;B*Y&K;;8s&UdIv=Q;Av;^^V<~lju)RENm%5*Gdmf_KsB}iNH z>^=YgpeLr%yT+J5R{`tz#gnnF_Eg^zW7BGhzVZm~`eY)-&rCCy&0QDvnt}B$Niw9> zY6wq;0Z7jf_V~d~vjM1M*)E-J2-{;7L!Q~Ey*hs5Q|s3%J2q%LY+_1SR6k$K;*{cP z=<79IdlaKnuDSBCkCl0jp%!rzXu$=RIkn`f60=rmMikY->zvP!V?1QsSNI*midL+> zStfvQ96m!9Z5#NRxc3iEV}kRr25&`?JYvLM><#NVLsw~dmAHQNhWXu(Uk^D~H_~V_ zLHPVPvW<9u%8i}CBOyqJHn1sb={w<91M4mU1A}36U5IODykO;hOkU>-Aei6I`!3K> z4jKtO90)!5Gxm7=wIgT6I1|#d>Knh)ug9^F;2{YMu!{r@DW3RpQS1H6p%QP%G(GNw zQ#|(rz`5iZNf6=|<3KV_@Ww+GJ4nNWX70xM0y2Ong$v6sJQRp~OyeLY$HPlGbvB&t zxr^nB5n3R1)be4;QYX_#Bpp=RdPj;p>QMpyB2qcQDH z0{I5kpoCl-#d*kY5j}1uFzHY;Un1(aJRMKCewrF6FDlV;A+YUibw^NAtIvjt31!ab zZTy8Iv4P6EqrJf$l!+6-N6{BN2@iY}2iyxC93v;i_z$o-^9p1F05+BPM{n^k4R+*u zC3h5$Zlu{UE#!?Z_oMtn)s8SfD0S6HcCd_O&E*75SU6PXRDNPW!sUEG5;S2XuZv+l zoh(|7&NvX|=1&|i(_Ca|>MZ-_W-YWxk!M}AbuskI(h*^(1I_g4da8_yGJIano~kW= z6!*-_Voe!YHZ%!9=mRv~a_zx%VdLfYgs~jAe0K`Pa-D9Id-1?t;7g%UNOl&LW;n*} z;?Y}x%M95;H^X#Q)2PrQ+(d*#1)NQ$K29g6!S(Tb#+j# zUX^cV*B*ryQ&y{=kg}Ui9O5_r6rM~sj0yqw0xL$|Xjau*8)WF(b4f$G?%!rK8kRM+ zVYL<9TKABsZ?YMMSG!c1VOB%&5G4~;5?G@T%bN-*UEd}%YSU92RYO+2L~Q^wve3>Z zF6mjX*)IPQng^(pwl`&;h?h~&#WrKp_Fy`Gk^G<@xWHdM@S&-Q;gcy%5~FaafVf)o zN2HMq!0)4Sa5$1|JMHj)YtlffV5@PfIX6I6u?b^(zw{`n{2~DPKp@#bKXtPM8AjF*Re|SA ziWLeAZ3Hr+ih-|JIt@K(3c{&d>E8pSD1Pu+fe?rYk`}y57T-0JcIK{i+{LGY+;QMW z_3zTL*-c}xgURA}$~bSb)xSWPkwz@yNZ;h*tkods!WAws=YE$Y72SkaC z>keZkob2sRI^l}tn3f=A0M_lo{{tgZo+-`vM(x^MvmMr~V1vl|3z`lgQ)AAQY&YDx zl71vVN==A*6Eztf3sw+67+)H@uUV|QJIwnOM%(Z3K5%_$ieMfe-n}Lom#vYzqMv}{ zCZgU`31c=4h(;!?-l(0;^Yav#tDWHbIDp2FjWjQD82_V3+#GhU3Sot^UF_NvX3B?~ z5?T(HBH#6OEv#|Q+uGia=w(w3YjZrjUx?AiW{fESQj5rn&_4$E<*3)TL7WKJ_-y;wy8nP+Cn3X@!>>mpBYtFZMk zuV(kRbwhStt&R@OScKX%*Xi9(u47xHho%%F$4KUx$mveCpd2nuQJfC>ZS*^DXe}PZ zE=S*L64Sei0+~~N!gHSFmOKedpxtSOJLX7VP{QAvD9fRm@HQy>dONQuchLmr3FZs5n*C<(Vd$)?X5twp=wX3tu9K*a)ax9z@k{06h27{YR31;1kld{ z6O@xjf&cQ52mlA95LIeZ1-KlL~9c zKbIoJ*gb^41gUdlU)~i4#{0N6rv-FDc326@DZ z+#Av#CxCrBQm5pP<#O`RaZ$)y=!o>dp^!hs)1OQRBcOA6ogK7syEtQhzpy#8T+$H* zJOQwTN<%(LfUZTRnL~grq2O6)BW9Ik!Z_+oWu{Sf=MWqtmi^?8G-d0|>wWe0BpRtY zpPKg}ZFUgm9@-kWg=hlb8nHyC00-NAK3u2e9S0e&do}`GINI3-Z^A+O0PW}BqwJV~ zDOzjns#bD_Yl6R#NTKPSlG}9K)`ycPLDXjVai}&Kx5hO|ui7p%5{e_us~;0K-LqQ# z*SgJctf6BYCM2ZHcI)(7YpItNC9)mZ*ZzY&BZ|f=`(X1nmSvBnl*3%ybS-vsu4l)bx&NSwz{BH6U+50$)5MWLH>< z!6)T+h^y0#Wpv3@MXEmm$fhI~BO$=}Qsu zhwF~O1;N`~OVAV~^|!o{4u{c^j9|fd*lX0VbWs@8V)g%H%MVHgVsv4dpmlZS% z-4HwGU65m<YfqHS?QFO*<1ubdMp;>v(X=C@tQmL=}=8p7isB zyf!If{zC|d9bCKcZ%HP+C=Jo*S7ll5qTuw z=3c=c!netrs)ag~Nc@hEY18rUQUH#y`m&M|!a3vSsjVb$sik|;c~c$3Ea&1*vT1uo zlypLK5Hc#;v_lr1K<6b32y>NoFO1awUeIU6jcZ5FT|-7ja!*b$DY& zp&Xr0g@`bU^u0uJnHQjQ?gN$yqO(Z7e!wx{PhV4p1tO9HXpT2DJzYr!6gNwtD6+c6 z=j&gxVyzHcLR1`(V#`P+W90$v;GX3S^K%G0N>K?aAwB?y2~VYhyVyk#d;mhGd6rZc zeB{jAsMPRfiuKg}JgrNupLB9^H2EYM%B)rnJ7i7KCFLKs1n^mK0tP^cGVTRv?mJ*F zO-kG0dMKZv?$ZYnJ@*mbP_bMuDirvfN4e9X?qEhmUlKdoe&!g10ciE3ml5+-I9Bbc zFNV9Ao{>dz!8wblmY)&=B~>aUvp?m5Z8q)PmU;e}{e>)6S4ZU;4Nh4n2 zbqwJIVw z(uAF|1W9&`MHz&gn_^V5xl%rht;h@4iJC0&E?z>}6}eF;BRhSduxfoLf*d}^q%)z3 zEEFr?aRF!nW5wBF4|9vfsTzyb^LA(X;}?^N&@*83aZ}I$8>OB&m_XXyQ>LIF6oj&C z0NhKELkl}471&6=id;vY2*7ju+AqYPpnptGFK~}(z%&>!oj)iI!i?f1Z0^LC%ml&unX#N4`LwMvMVr~VI9EVDe5RD{ z9EwXNd#LMHNF(5ek&Lgz8>5UAn=g3n;uPa-w02d?l3`jyrt8zmv?IfKzom?95|YEb zW7S2bQSOxjFof+9=#VZ8zTY?;(p>IV9Ct`xOM>xLv4(^;D3X%vPib-4>DqQL;~DYB&}pKR^ThsY`-pIL-74eh}=3MhEiV|W7j9);eTD;cXn!Xsyx zJFe6uiC`3g4{16-0q%8*|G`TUxohwo)sm83H?oL32855hg!?^Br2$Yty_&)XnGKDm z$!P>t7NSg~U|y@E3p^5+X@` z{bFPfJz$`%X=&rF2FoY4Zv%`f(@0=%foHE5p)?;4dLxo-m3Jip84f6;K7 zI9h5Tx?fYf200HTl5-~ybI{X+o;v&s&<;WoAx+bPuXnYl&8n_ix0F(*|4G9bec~LfeOk`3Z4H3yuJn|%tHG0x<&D&n83_G;sK3yB~%_ez#K15w@!pf6GBLyP=1V0yf z02EFhfwXSH${VR9zNFYeT7}l5X-YnED6X=Qs$>%=3*;v5VP9R?VZg~r6KMjNr?fBw zA}}rBONl-;Id_MBBkjeDQ6-m8HAe>oV2SKL;W23uG6}JkB#baxatCGWj(v7jH`^Pg zZ5sBq#CLtR7s3vsBli$ST8)-k;woGdMnJGH-ut8y2098ST4;QK-GEIg76QgXS*ol7 zGzZ@eU@jdp$GieV-OVVH9%;pDvmqKjH6DRf;SA0p<*1Gc63D=qbw>=($mWz7lnIxR zQiM^hNEE4s^Z`|!3ZpV8&ecL#f5LjqAsfdnlsRrBz^7uhtK&9=se_sn9H}ZuoAR=? zKu6jU?z`f&^RpVKjbp3`0I-n$*A9m5P(UGBHV}0tZI4DX?BZ<6Od@(@9BDk|j<&2u zNEpJ?kJubx^{q!^Z*GSntiGfT<&)CoREMQ&JzAxysSRDVl?OJA8?vRPPW z@-h@)5bd%nGV;7(z@r#o3-&;Ec)^!!zTRu6;dEYuj2L5)gx|-?GZG_~NK$RimUXV$ zGyTXwC4ovQe*tWmlWjO3I5&7Ccpp378K%bykC9R?ZVSU9=2hgvFfocYC#JTXKOoPe zK%7O}uugYnb?SS3kPYj!M#cS1L*kJ+nT+|ywt(Po58SAdE!(sRkFqa#AA9?_X--Xc znD&xMf)GH?0HA@(6bGxZFH4+!VrD~dap#c=n?+(MzST=qsu1u&F_sv^JCX2)0ux;zK_6`HEo?TGrTCI`OMKRcz?G9Z}t6gjF&1KtR zwkavsB=SyYhayly2+9_d zKSBLLKQz9myL3k%I9?xxG*AXY987Bv9%~{ZXb~`>{2#FvA?4tR`#HRp_9C{b8o{Lo z)@|Ir*o%oSC-m$DFKc|)6G+CwRWdxThqebzriM~YiJM1MD-D1Xu0CO0F`r)56SfNe z$fgMIGEJ~zIF~AjtN`4r#Oj$>!ncNXJ_^`&gO^iZwQ~C_w{3MTYfzdKRD)JXwUozV z$)qo%DEDx#OunQ~RTHnLG8Fx9vY74V;NX|D%k`LQxH%eP$ra2FE&E?Gi^_G($EB?ZZ%6% zZ;6n1-!WIdrEqJN6w*d&t74 zWu+|RjMJW`3#V#x+pTx2`z-re9D!|4K;w10d)qJ>o^ATw+iEtHMhlP8O*Dyd+S2I; zCTOFY!3*TtmtFz`i=;;#n2EY0=TA~xgC(#=^nn~FHKOT?8uX`0FgU%rU&3q=BawaT zieGY~*`2x{#TxMLB-=%vdTA-wP{UCt^^W(yKpW5sMAnGoP>r2MAPX;!M~(>KX)XD{ zcGF2_)TFm>Lgh0^QKLcN*)&-bhliAvn&NSs!MJ#T8E7(k6-!1X>NHJ!#T;Nt=mEnp z(2o_{H%`_>aC;n+b)Qp_%w?C-jw;)>rDKxrZL?H%>zJf!blGZQKs!N zT^Efo$HGzTCQS(x(6UWzCWZH40y)W_`{dk|SHTnp;M@Sr&iQ8FepK4IuTgextgkNH zl1-r=@Hlt}hWzAXc<{Erh`lH4z3!WnI8n97^r8Ydb~d(yZ#DB*&3E|#1G)vAJJ~Vb zPa9Y1IHa^v;f8CqF+ovcPc(#@Ud0beIGX*~H{X^tRM-v$=P1K<#FfAj2-W<9namW4 zfTMlVto5c!&lp`*di6%pjF8N`L2E_Zu#q8gYG3K*x%$>yeit)A(1|ERia3nBD~C?D zgm)7WDM0O*-=mMb(HArd;ToeHS!r5@fE%|5V5zW#dHg2qfT51RcX|@MHEmBE6t9QR zUK1*c1OX@)a0;~M?$9P+n0d;Hu3gPzD#YQ{P%>qv3g92I@j34LN;|h9uV>b7QlW(Gi88#B-`-zE0e#4&QL8Xv3?6@_Ih1-HlLa;hlz zlt}=ZD4;{wB#X5ip*go##IUS!S3v`5_%dKMuG;w%%A9TMP&VoQrpZ;$FLnw4Ne0Vm z{(TBIltxk(^+ z?NYKKae!hCaUG#7*Nw(((o__x)HF0XN`MTAytqQtC~$Z^W#s#5ax3v&r;<2DUkI&=hV zF*I}sag7_doL!2BiEkV+v9SVO(n>=xphkmFSuJ+LU`G*Gl-U@ebBt1CJs8(zSR^%Jp-V_P3&M;6ICXkwe(w8gEi{T4I^)V^T(* z9|xH1Y_-)R4D@2?^ck@uU(Akl;$;XGb2o~AO!n2wBT+F$e)4^cuPd)?@qQR1)tT*t zm#W$KsXTHXP98fh*2J`RuI`5uH&$(xtSh~mwM0kas7`1nj>f?vCq_~G1P(;mr@5(h zd;1Mto74!0Q!ChzE;`8i3Zx^8lNVBH?E2~(vNq)ck+n*Q>7s^Yk%;(;EJEk%Zm3Nc z&w(4J7j*3Py6w?FDOoo3>`39{f;6m9ee3%SYigg$7>1;2G*`bS+97RnK-3LQHjbWb z5aal2K#>@AEdO6GD^ScVXq`T7f}McYTCJfc23~9AvZ&O2m$F`Bb)rngF#2Ff%2BL+ zC=%5pSpw-2uU(a6v*K72hPH=T(sI;O(cE!B%@Mn(la$ntmEMUm5*~WTjAR_SdCCS* zMp0YM{`@BwZO>>(YMxj@Jch*@6nBxR=NfT(?nankJgYu!>hePD1QDZ*jxBvAXdno5 zs-}Udw`_;EFL>PpE-e-j-hvgLi{zYB&A%^`ed^@m>D>!Xd~s9gwu3sKm18y~5M8pS z(>dBEy^sTto z!yTm2JjWZct9`9VE91=jDiJQJL2tFjnzmRc>JEG@e-&voSW?4&am}j4nlQ~)APxRx zT8{2iasMm5QEnEGNC|fQqde|m8Ucd9%da~o#rh@JP&?mijq0v#xK_sa8iA}X+m>&+ zzUPId@AXKw zFsYPiCcyK7g{ibuFOpG1Q`pxRj0Y=em|=p{WPlWm0qSBe6Fb$*n`gT$01PU_Iqh3m7l=^o`z6b^S;&*}7)d-;ZC-y4T3;6XNdQzbJ zgTTX^4ecX_k2S-8qCevTMSgQxywOGLQZ}V-KEHD)TCkuvqm~`K7|Er1eLA^DN)W48 z@c9#`t{GJOy{EpV3ZhyY>vO20Z+SEsr}V~4--i%(V5!!Ya}Vd}gWeF-oT4b@&*sk4 zP|Yb@2Gba+#6TW0xvHQasGie)09fpZ{shvOYHjXi2%;)VyRns`zKQ-o2`f>(Lj=pi zKuSpqK0Q%G&4fO2Kz$?@KcU4r4%^m=Qf%c&!JjNQqWSYwZ>Td;{3iM3i6M{_X79>m zGsYUvuoP_A>OeBV13+e+*G<%0h}mug!LQ@*{^i+b0g8^S4kRVUWo#S7)VTyo8=EAF zBW0UrX(Tj4N-PAnK?#om(Al+4_oOMKeQBqZ80U^Qh(VR%n?ViT6H|dH&wsTJ1XZRc ze=>X&<8wuZ*!K1G*8TiJPYc;fqKAtle@zN@wX43s)n`KvW$VsnJmR@5V}M8qoPIPx z&wg&1pbcp~2_$Xu^w9WErQo->ae(Rn3q{TcvzdVS1k#W>q2Q*Zd0|F18{iCr1b@g&9o@*3_6OXX<>APR0Zv!#ns`5wWLlW3AyKp;q2Yo-X>;EZ& zY#xP9tT%^{uX47Hn{X69k|6!Ui&1Zm$meN_8_i)P#r2R5<;2pUK?{`T(t?p-h)3xc zOY}RPN)}x44h1DBG`S+vuODUdn6m*)jB9^Wd4f!}bTbR<`7yl>wdjczUG!qAYDFN8 ze~NqpHq@BbNx6tPCSf!FBe%lr!6K1P=3JKzePU##yHqHPfvr+t6FA1uY9$e;_3rIgNyj{F+P7$;o(W zwE4cE*wo)ngB;pyGCsT;lrd#_8U;Dd6ek=Jxh3F0-x<47G?0>m#Vbb zajNYkfZ)1H9#U)(-->1c^`;(X%sPpMnQsL641%MqM_=3YKu^Xunof;LeG&K84LnP@ z6`(=XupMSsfb&y?`~j;dWA~-7r5~_@^1QLd{Lb0;B7WQK#Hj5Sa}Y(w`(marO!?%p z8!UC@F-?1XC+$#=bhFSxM23wsEVwE9w;R+|QnRA2A-}a<`%?eu$&5a$8iLoNr9R{Z zEv*A-n1gR=!Ds5zvS!oET~Kd5dO@#l2zEQE1ymjo6CloLygi`<@e^YO={v@KN5{?n z4~Q2Mkc39~QnAXz%`nWlzC!g$Exh#||84S88*$N(TH>u+TJF!6VIJO>iyK<9#;qk9 z0|q6K<#epVHE%+)g|IcF)*XRwrm+zfqvMV*-puxB6-*aXq6Y%EK`SXqfXEEFQe!Q! z)*X%nS#BP|VLlYPbB^l2=GE2dg_R1&wqq#(SK;Gf7jbk8&FDVhP#V@ve1m_64d#Ja zkciKW3ID0g{KP%|CFLiUp+8Zf1eLk64E_8Bx#c-l#)nMqM01^tg&J7V*B5IVdG7>w zL9=}!5+1!ar)e#;X{cFjLWA{b1Y3tR(}7#wNS-Hjfsmv2rvp%DF8_5}y>VC}k<>#1 zB2~X+asqOvURoxzOxs{fH*61~B9|DYWBDjqr(jKC7rA_n+t)kQloSOGV|vhY(*2sm zLy8rU3*^e5D?Sp3Y4Rk^>ndiPpRJ7CJA!V?EtGGCPcIPcJ|l(AC+IyhzZd0CRzT8< zc&J%UHFcisCjHc6sVuijLV3fgCB))%(4MALH-R6p^2fst7s(`L`a(WETx8Ekl>ma zw_b@kXDxo_bjq4%TIg-i35$@_LeY{5nj=?>ZFM`>9){Gaj%FnnOidd_B_)waXqP6P zd6H#sYlA*@&lr(iUd`fRh(_JfmxDp>Y!HnEDwzUWnsnyL7LB^L=$Jw;u(gLFB3BLu zK+-`(5;SDmXK6Hfwr^r(ZPK;nrEaXWPs7R3H)|h*<0`6sxf0O(*k+P!bLHx{_R%(0 z2K_*bm)Pd1TwO}7vpg;4Im|xO%EJ({uR-Jori8MHYXDeNxw7ZfB?^%%b3QfPtXWwR zx$-a0lUum(E;#zxRai*`e2hI=ev^Z|tthNbd6BVYAVEpCx{@nl)fc$KZ`b1K5~6nA zo`rn=1{dQ_Qh@{<-f~Ui%8FB%E!3>+2PLnH#EOXvuY$ITSx>F32f=oe#1uKEM=>4R zcSGXRf@{pCc(OL&EmxpoBLU^?QcxE@6B8AVJr`n1irV#AzQM>3WECD5j|cPessXLt zlqZoh15_Gg%pMW7C|_tp0b<|aKmPLR1pw$1HWe3oc~-hMi$vp#~;-|$HA9%g$_~yDu40G%TrPY zi5k&-I~T(KI;kkZLypFI)C?xjQTzwlj6RV?fvgrnsh6wx z^dU$Ukx(ZEQnB%4DxHV(qO$Dn>ERR}z_^J@%g8l2mlT)=Xw2e3a<672`JZ7VBKkW; zwUD^FMg({gvej(_r?Z2Pt4mGZuY9t)jXbYhnT+SH4rNtXk$w6`zwzncOuCTw;wN&J z8Wo+hrST? z>pz)B6!j=F?K@l@GRb{S+gR=nmyHyP_Po%E;=$ViC^AuzS@^a(G3op*H(yc_N-WU9 zk0n;tyX<2rYYe{L#m<$;&VU)tW+D8LS+ny~I;r;ubk;V!(793@=zq`7wNJr&Gv&b6 zdQ4u$Aa+t(N)%ATlxrhvTh6d>E46D&BFCbvv+*ppM1H1$u)K-Ov$EqnS~6YD+K_K( ze975c%f8Y9Z{K2~a_d|Sq7!)EPLb8#D_dUn_Dly9uZ$XfpOspt@+>AA*RI7N3IY2E z6s|1!^C~?P`;%i0V8~Orbu0>jm1i-CM2qTr*%1zZZO30q@u^-Zw@vlojjXP%h}KyJ zS#m5UY8J|sYTGa)Le+Dx*3ssk7EZuVx+tf;ElnlQ@nXm=k#p)~ik0PB6e5?FQhI$Vh=AU&->g&8#6%Z+~bx1QrU_o^`?fL_iWp{JpquyMD znd?|&FO|=Q7RQyg-ZBx(v`LTZgjeMYSq%V?IKjYB~jK_VFkbUB_#%qMD3wh zP4)%o*Pw*l7N{|B&TO2==|l;@H)=|}34ja0@W`AJTSj_6DZ%e+Qo?v+CJyn|DGKtG|k&9Agpy`I; zd%zfJ%B3>U5HB8L)I)N23hEPLk8-6(U}!)vu;5&{C?uJ{t9#=MA=K>vV*?GP(XkZM z2_8W&P`cta(0taQL$we3fHZ0bSg`I1L*CGVOxPipi*&^^+87~XVUbePFQ2@5PxkF= zV^NSGf4eg6r5>NYNwIpkp@}M?_k`3MFCzr$bXR^E@iv))aLX)kQNSb5!m^e6EhT%b zP)LbQ8d`g@%gk*lX&51OGJt^xL?Ik#th|oG;P3V@n=IL58@7bh-_)8rWQomhT9z~v zs?}Y!x?8GkG;+=n+h<{YVQ|Et%ZT>p>15KVM9(ydfE%HV-Eh0;3t)~FPakMDg|eP( z9lSd;Dgm0r4{_4%X_I*JE`L4M?gb#BH)UKRiyv$%zy{wkq8CHn8esD)@=EK@Wy}E;E3rnzbWgvpO%7k3z2{xuPFCOuFxhj0a5MNwgjJjGq zMGB~8YVa)jTQCbPQHoMv=F7Xk^M#D|;mP%!^ z=3}O~;H4>BIK@?8luQB`a5mprlGfc_3;eZpeSwm#sw~oFwFcI>Sl=9Jv{tsxe(PEbtrB(DQ8C6G) zlJFaSuKntXA_mSdO+kjd5yCScM*e`Je9YnW5inAc8A^gtZiy!wVZ9tYz=rVH1G4)> zdw6fizevGqGXlXa9tQP_og-m9J zx)Uxwxe^fMMbg&PG_pkkz|eC}_GWqpI-srN$^U-e`v(bPPTfS4w zzEwXZM%%TTY(q&~muF5T3V!fiDU>Xwo;*@RjcqQAzFHan4|JHt?#O@sF=CnODO41w zAZSM7vk{+qlY(1b!y>{bDb|SXnXW@ODT!3|LgR>);wP09z5%)bUB@yrI^+x{xbGwT zNKzdef{gRv*4%}HYJ}wvp!FoCfPXZcGWN`b7luA%xchEn5x0i3aD*iJOw{h1dOq0IsSC0P^TlupobQwSznSn?u}4@s_5lD zCUb_qNPf?3As@tODX@K%R;Kyj^%-xiCBcC|f$Yj~l-%&W)%;ejwIwe2^i+v7N|Lt3 zmMW`nSuK_+A(Mf6l8swlwDH#)3(0oMNB(6Xk7zNfwvC8VX>%M}25FL;odMYz z8K?R8N`WxSCa>AcPWOp%G1$&+Z7=;U4rX_rk$J{M_B7aZ<-M>k33=gB^`oso}epv2)^vL0R2efdfBm(*zg4W0MB?y_T1{QdzyAmkL_R4CDXXPhkB zOOFf#tvWTlu!g$hUoP(0Ee1FPigEey_w(xPv1wKGh$$Q;_XxIr>L6fB8lWQ7qP)yf zm)o-CPR2RhVP5+dfGI5F~_c7%WT5=-nScsl3F4yYIWW3Wb;h;KZ!i8XeU~!Eb@lfQ%EXwpLG0X< zj*bg=4c@iyYFQUvRX70%@Nf|#nL!Y@dL2yNGH6%;2(>uzB8jk|s4|V*D9-W$eGA%? zbP<3Aaul(u!VVc>+L2lz>R?t1;2O0B7YG3@+?2BPJlzDtX%NFT&=Y6GVTfM&hzNjG zxhAvIIF#E#LTSU6E-BKwq#dO46?lL^D{VPKo(g>nOq+P2S%)MA1CpBGF4I}q!aE#F zQ9>BeeJSxr5=H>;a`#ysVxD)p{eRXSr-^x~fvl==gq{J4uJtga8btUm6h#O3) zl{c?EsR5k6hyv63K)guZ^e>8~Wsl5nxkAB#&JDB`(e5;As%3{lw%AO>4j>yb5@QL; z%HxMl$*Qe!*pi}WlkllXexZk_xsA2P3n{Vjt~KkCY-9rZv?=yUq=(hl>nOJd zwon*CCPx#H;U3^*O5?Er1_^f!3q!mtq0C58!M`tGUJ+}OJFo00?8VX*MNDi(+EH0J z5{T!P0wdZdO$S@R!_3AJ+sYWT5^|~6D5nLT`6VraG%MrAeWeII^<;s8WOf^-SG`Ql zM1-&w5J8-&d5Jmz)s3JI`;Xk^xIB6^UCpr@DHab{U`h29^Fwv5u!YK--i$(K^txZI z!PJFAwvm4ZrkZ?ov8fycek9N1@J3F~6EvmaNl$@IgpgJsE3Z*SlTQr5h3T5q+SDu8 z!bVdA<8d*XYe>=2F;Mu3tA?MzwF4DK>=jd@MvOis&d~2U-HrC*9$4D53-2f2_V`iE zyh;VY-f8Bhs4)4p_0`=HV)Pv`LCz6Gwa<|rDMhpzDz%oAEh%~|iX{Dm_gm4$x+IL3 zWHce=dN7}l`zMq*e4(eL)DY=A73Dy&C?z?U9Bbnga>Z6pdu~j*{SBq0 z$D%k}Or`=EIqn-$S}LPfe;FyVvwg1U@B4Qjgr|}fnmJEqtY|VO(&>kuPNGUoNP`&l z>8Z%5NNoCuz>D#9d;<0pZI)Yq@&$$%YyI^!ss@^XPSK=>NiQp>f;WQ4%k$JNs1%&R zjPNh?_#w!|as~h$)gi?v0@dpXLe>z!8P?z)^jSktg>#Jg!_d)6G+7x;2d%V(@Q~W_ zWw1Vlp-eI(Yolg# z2T_cX)u0Lj{n=iEds9@$UtodrToS>!@ym9ISwYWI7*)M~+Lj&;6e10d;jT2|7`3W z*rR1)OMQvgg5R1ub>{?>mR;U4Sy(}G0gmdau~;Xg-%SwH6S0XejZ0iviY;FN-J%{& zq@i$0pH`{T7a?CP5Wg2*7RV6^QzRcrM+I|72m~~TiUdEQ6`+$AcomnrkSrYR*B!fuRaU;7Je-9rG+S zaGT155ZIxPAt|N>ugA#O4l}t9k}(oHVwZJ{tZ!Cvbxw$!x~{kHZ6sb3h)9AB=BiCS z!NmA@RJ1peQb8j(-AcSL zYgnY785LX=!d*&Q&BO(X0UE+dYzjjqQovYaq>VKIq*V0k6W)@t$w4)*S4hcM;bhTYfQ{CoV)bxK zb#DbSBZE?=ald+MxD^#wYN&PLTUtW3FABvcI;cqD#@9qm;(g`SqogpTHVzuXzOr%~ z!BR4eGMHLENxbSf8a6282rhP?4un38AlX(O3vNi+29Ww@@$2YG z2fPkyTcm74VSTg;pL5Gd8l9Wa%jtEke7W<)<}{cB9wLdYo&ar&?g%nrOpL_Z6I^nE zw-ToE45pOyD#h`sHmfVAY!kkLkfrghr#;RX6zkjX+Eqmgwvj9`Eg4+@snw<-m)Xrn z){TtyXqj~JIusULsykefQr|GrXke{{%)poXprS`I-iTOF7f+O|qsMYtmSJEk)oP`( z=ew<(H|J<`v#DWs_;qH(w_6aIcMY*`8FQKLXj+bV7nAK!o&}gRyF4^1xgH zqmnwHM{xF_iCO?9tMLYO*#`+@oIi8ryZTF(o@`y|yFtLIwN8#bP;{Ij-jAik+MhV1-J?nh$_eM&dcQj_5$+dRdb~Q4u{%XhIGWx2ae-)p$h-l@-$8DtALsfvIgSNwFBn z9g`4LgDBsSaKQu>1ZGYKCuzvAYKya{mrj^^`GndMiHHLocbd)(sGxyDz#e1MWdK3& zO{CLIpr-UfeJPKJ{Gi_c1tF6!EChtcG-2V1+eHb2PB32Pgi$+b8F=C`@~VszK`7_! z3Q|akNps3^);_4()1GJ4R!_8wDN(-=@=dl&35ddzYEv80LIgb@L#B{IGfZ)zZ$seg ztGl73p(5&w6;kq5QCKXgbr4mO$}CirY;6ez$E~tUDRDQxci|^XQkw;56B|}^V|yYh z&>!E#@Y8LtE^ckzmh9k8zkg&uYm3@Y7b#iJ9qut_y7^wSE~ye74LihWLCjDG@T36_#VMa~5Y&xq}2MC##SVWB0;tQGA38bboFAQstPFUXKBFi} zpp2rIB8U^>MBLV^>4h_s*NHPj#T`%=vvKBb0d z=FZdSc%u!UjZf)rB?8Zh`96(7u0rK)KqBDtfQaY)2qkvq zEsAmiOaKRp01QcR>ijVl4#i4YPoGU!hLH~3TKaJjvuRtjf70dw$Ux7KT^fdl2n38P zSB-wXXZr!Vh@`AOr8GW`ch9sLu!wK{nTGJ!N4)g_5JMOOG!{`j%_C8(YnG8h(#R+g@84xQe0%|c?ndK0VMmzK3q12rlZIKFgmt(El-n7?EpDR!*6 zeZ;e6EI@y4EZa2?1Kk)Se}mAuSf65c_19${iB6cF6S2%8mN~6wagt zS9Fb?81}X1ODp)_sBwL>RLBJ-7jgwRuJ0+^3ZF7N%r+wXg3sapK@UrPC=_IWa{ z5GEUo@6kN8qNu*gNF+JM)6^{mGXyW_HRUQBOd-ojzXYyV88$0U;!aXaqUs6uWO8{z zQlvn;5SSiMCU<}Bxi_VLtH4&iODPW4d<+Tkk4xDotUlga<~NiyZ&$^~kQ7@E@0pdB z=fZIR#bWSbihC6%X>Q9@U|(Oo^3 zOioL!P&Hx>u|*FHJ67NKt)17^S~&+fOO%`L-}kOTDHk4SI@1q$5`uI#^Nr+wk+38& zhFb!_g#vej6gs?6Y9)%Kel)dNDeQu|H@L$~0Uu;5$ch>5rFfVG>VIY978cC#W zCB1yK!kffUMD+lE;kC#^Az(yUG?Sft5x`aLN<$o}>oCZVR9#6rRQDc>swo!CPD0iu zW|9k38@%96Fep#E;5?a|-@Pz}FBBetdCA`M65N~*Qu`_mdCcWd<4#M+NZ}!am5FS+g=TE}A85xYE;NMJEd~ya0f;Z}FCvU91dgvCk|!L%A&> z6#-kITP9hlNLeFd^ii$GQ&L<-+>+8Vdg{ep8;XjS$|7MXnRvr%8X7Wu$;;swC1YGH zDZ8}MmJ;hJd_syF{0Ux_c57yt`5De#zbxdXHltz(JvY`m4mza*Tm{DnEm;>lmz0A}KUwA`D z#aO(4@G^6W25CjmU<_E`41FBRRY%3=eI>w_`V+Ns4<=; zbOks+B2p|)Y$*AKhAY$u%yg8g z)<>EzLLAAlkoqk6pO7hbzMHj@lp?6dQ;z_Dz#+3OHGD7@s5Bk`$f?yA>2jK20a&Qd zu(XM&U0j`%90E37jF$!$m}``WSvI0BCpX`Co}SL$O+ zOrA?3uiyeockvr{g~tlzYHGWb@*Alnk{pvq3CbE{QY1`c9q})9Z zeZ8yg0XI}wEtT+eOMZ4&n8j?aeUB%ykPT(jxWQZbs#FDyvAXf%2>K#Vyx>?H>9T}0 zF7WEkw=asjUb%E}0DbA|QKGxrx+ay#Z#lBV427cQ>)p_{seI8BYqeKTz{;K1!+z9($TTo*s!Y*Y)6$3`fwnSCoMbr;J)<9oP+~Fr-aOJu z0TEab00;bQ`5$b|fhS@hcQ&_8i=|3TbCT?n5 z=v7A3f~?p_3a%I44~2UU245y8MUAz6>uBXmL#luoQ;pCR#=;d1t)K;wNyH2mY2FpY zOGBHPK2jz%h?O`{jDg^WsrBXqQtT8o?-XmU6ypVOWr0CWtzpcc!Y};AQyRQc+Cqd< z$0S2U0f2vi6IQN0MNCozfT?iufz8EifuTmiT)G9Uq(9)T0^4=JB4y010w-XW63&;I zxIiL-s88}$AMciuJvuKW#3R8w7E)3{dAhO>_5IyaQuAc3y>s^q`}&R3GTD?J_F+p& zZBxIsjs&b|r{46Pp7JW**B{kS_zp zaMwVHO6`S#zE;$JcAsjor`!4pEy__kM^ zvLU7AMlxWZ`7qBoMR#Q*Umpk6{2Q9?--rwBaDw4y}`aR9xcA@ z%qcZI=?>qKbU}*dn2<#kJmy+@P6aif;hdIpnzS+X4b>%TfFzJt1*AxFO(y^%7Rb0B zrcogxC&mN69bagI*63Efe5c0WvMYd376(8iI;b z23$F(MarWa2X`5x+k)GHO;J%AF#UBB7t&xPTT$`K(>)phV`e20ssTPG&qa(`;L;F4 z{to!N5Mos9;%Nw)t!{J}0O%iKVCBZZ8H(F@jcRO~UW+I_fxz^63W%NlKn}?krSi&G z6R3?M@r_$If5u6~%mG(xZjB{}QNS>QhI1H%Q(Od1qx`|ypwh&o7Iy$T3F|a}HBCf- zqZ|#gRz73UP)rWhX(MYr<`hwDTmb;-Yt6K=lr0s=wZTwQH6q|I!!0t!e6^`>Psl#; z-_Wv4ZG^Pg9=skcPsPk^3DyBcF?F%j8g@en;>dF$iaz;jYU8QxQc8#$B4{rQJfVC= z7Y&boQW+_MB+;?3tVGG!KFlUkzoA8uCgx@Ss#Gz6fdNH-eU#sP;IZG{e2v zYk4WNKQ|P}ZN!eg{;5ETuYa3y0eq3U<2^1YIf50}ldqssaO&y5k;=kggBws|x*oA7 zqgQhQjYW@*#%bxZsr`n004n?SRqoq!E+$CnQB&**X$eZPh{GHA1$GJ_{S^k*vM9P%OTG7&aN{W9>OwuDJG$drw>_m!BXrXeaQsk2_ z4YpL20OrvInCB-k^otK|p2d@bgI``w`bol?T%om0{r5|;T#H!D6@0cYuKo{~Wy6%> zL~XTKbz8P1P7%*I#9{=$(sxuwuD_7fhO)aCo{bB8Gy!O7zc5 z++d5wPAG&f-xT^4gi%tO!8tKgr2fAogm{DjG}HdEF9r3mxfn8-|jsI-4`s9193T0I7do&OYEYMX*?{vuvwe?UVlQu2=u4spQs=izpcVWvCZX<4%$i> zf3l{7tlFE7R?e5+OB9a#C}fFk25_XHz7P_&g&V`Ikmo_-){)YnAN8eo)=N`h+SLG0 zEOwyl5WaM=X5Nwb;K~$Awwu}rS517whYUGl$CEjZ;Du~!1F&bKgf@gU)Lp9zk&&We zUf({VDjy3Asq(?{N1&}@AvavH^0mG6a<{%LDhSi+YP%b9NVb8wdi|6%knH__YBnpB zxMcushd=%HFMs>v_ka4!U;h2~KYshOabkqs?lFF|8Wj`A^k_X&5&iW9bO`o`@C;oK z)nf?G&QI@7_BR-=2V!IBdPL3r_4w<6AF2=b*OL}W7NqaVEQrJ>3*umy1)(5VP!Bfu z7fkOQ#c;D=#uUBS(_b)MZwD|rIYGJ-hVGA+tNwbK461(JUr#xofMBwLX2DQofCrir z)NGMtheSPnk_8h?7Nqnsc0n3a`U{36pMj3_7tAQ8&Te=Tt_Oypzdy~m4p_p_TeDzx zO(<0xj-(r;HQ7)c?ocR>ZniCy8Js_JgwnhLPXP6r9ftRgNY3m~;F)BHB!Bv6nC_6Y z*U$y&`!FPD7Z2+>R&|lDFmj!VHNDC11T!AffjV}Bq-G3@;aDJq3>Gm9hAbvI*x#T| zIM^WAcy~)O9uw%89fsEqAIV5{s0-kN;x6QoRG2+m}NE(Swyx}H<4Vdw%mH6(|QHE=P*WI5h}Vh{wluW2%=)|kTndKpVd+ZrCH>p9gQ zu19sePj9HHsV}+ah)`xIjkrCA7muve;G4(bCFgZzatK<$Wi8SLd6lEj=}dA|NHqo} zToA!AvY1K^1ru|d;}tbjpda$^8v_MKLCDEsn8QV9JI^6x3=nK1I-xA8tE7L5>4Mg- zqzn2OAYGBE>V2A1S!8ORVM`b-(*b1fODH<@r@B2N3CVq-)Z|u7_jqyHzIZ{G#z+^m z!9^&Hnm1#FF=Y$jkN%3Ok)|`qT$qq(a9w7L>4NlQ_G#AmibS~SzB4O^IX`;Doh+tG zLb$3v)uD8&3_N&2r)on+111|QIRG*Y$#QuU$)O3ut(X$ci}QW9q|!|vhgmU9y3l{< z7!$8(jX`RrN!D@lJxprI7&RI97Yr{Tn6I%nnt>KZ7}Fh&t}-*w&n9_8wvbXZd`>MO za|aDy;uUF`>WfZ#Uud8+!WggUi?1PP@RJQ^LU9C{WsXrdG*RC?cVdn)q!}Qtxq>NQ zG^D04JE_eQ%Cx^?O0>=Eglqvw?rvacr@?N!6*HnWc+8w)$Z5S0Xv8~Skzo{lPKQ>N zo*w7dW~}BA-7&@sx?nn85G-;35JSnK5z**~ctNKZ!F*mK&3Mv)=RVbH=?Qc#Fj^;! z@rrf|Sh^yU7Yu9C70VM8T{kpckv8YSoYB~tvAkw!d~WiG*!?veb-*gM0NAs1Aq zd%QAFa_F7WtF(qQu{G4BJF{j;H}An)ZgWoq`>Mx$%}J7ej+WFblx9h(`CyYgAmI#b zm}zC$uoLolMGuDz&yg`><|4*>#GUG2n|MWwvx!%as?~5gctw(hgI7dX3|`TWElPP!)2dOqsf4Q)c`(&BN{Xqr zZ)D1U3k(hNJ=nfJ^kh)~97ALHV9KAlGYr+r$kuE$vq`Q%a*+5b=F;4<)B-72yJEOU z9&$3OB6QD4(J+6#e~^s-P7abK?O6PHmrTBN%*l?D{%HF!YP?ImPt`w532h*hdilp* z@04)8qTSzRc)v9Oz#5!%mp-!+CW+Z4E$)57V^L>jl~F_al2)O|OVS-^EMqE`0EXOA z^7oOXGwWpdk`~z;+HaFic#n1ta#}m(nI_vtmnsd$Y#9;CoIpVAws@1CBp&}@Zj-n%R7+$d zRmlu8;|9hn+Q-Xc0n)_t{=JELV=ZIsu`$BmFehCS6EQe-tVuRbtA!Wmz#ADxf?~RP zC)^z6;SpL03RgCymvT-n57XwI%NAZ9#mmOMiVyQ{6VikRA>lkGWq6)S5hG3w;aSAY zygv(ai&wM{9OWxIcE>APm65MFoHO`AeRa+w5Sc_O0yionjh8j!+z5Gk7kM_#*@(kE zIJ5f(XPXY1jBgI}%-<*4S8vLoUVGkjXd@Wg;^>Z7v|~R*MadH`&L@cX zXv;bAiiEa(&csw(=PGq7dB?$pPVthwL1nIDz9jRU`$w5CX~8EccNp?(ZeqO2hs6cu zOYV8HJJLWrhHjKvzDcVm^CfMplk%I#Tll1>dDBgv{H*7ENvkPCy6HJ}_95S-eE}g} zlB&sA?aTO58;^y74#g)IL8PgS6Cs|VJ73birIjx^JQ;@P>uf~4%cBL>n9S{367MdFG(YpNciZ%rp>&P3i zPX8eDB`xqOU(#bqQ+va+;~al4w#|3xv7hNK^~~hpUHWo$OgK+PjW%I-+vk+;lJ1w$ zXZdhyDBdMKKSrOY1&$N%SsC`EOVVNCZco0X&4A`h(j(aCc)TPo}aN4~`-yYz!#`c7s0Vx-kbct8A$k%v9o5hJ&Cj6Ow2ArSO)LJI*%p99_i&-;{(Mj+K4`1(M37&iZ*c`uW08G z|lg4W{sU`C4G`{`{86V-6TLoLw0-@nNvG_$>DX4>&<#W z@%8p~jrcD5zCN9GBtyOnFTLJ(8;iwz^j&!A)wx@v6K~S?^~DEiD=+biSC_Vluea|M zj4#gp;o^sQmk-;y5byGFa^6~e7kzms))4^8 z?0q90WL)V~h7M;Jdgm)TIZv-Q>0`t0c#pOTB;Mm_@-i*vGR^Z0t7Jl;Ge+*T}Oz{<)ya_b8(0@CRju>xe8!@JL z@ob?Y`HGI)sYsshqvHoy4OzXYDSgS6SqaW8=1YR>=yGbmuEN35u!4 zJoMQe@6q;Px2gSR5Sbrd2(qcQ(C3!5s`TOyb9OYp4JdQS#8t?LChf|(T>R$Wugt z2bX`L+J^J7K#p#qIo^B=O?r?Qo9|7TO`nemzT*{bYj(V%RlD&y4sObU*S0Aq7Ramh z&(njv4o*0*oJ}~yd$hIWctx8Yh*z}!N-B_mQB8I!-lN4H#{x+Tj9v8d(di~Be{xd2 z71M*f4NeanZ`40WQ$5`Exea%HZo^$4a{7kXxj@?7Kq`=oVK?S570A1t${6p_mb&8= z2X_x2Z+F{09G~NG*XM3spI9LAbB&D0tg(aD;)4W?+1I)09?3Ecrus45^?3|;eICPI zpNDmQVu5_vykyL5J7Xag$cHVQ$9o)H8R3!R(XJ2K_rb2uod*t$?F!HF{>!>PsX$U; za!}EDlNLi43gjIi_*i{*|7AzN#Z-@WeehETyFS$Z#tw-*vZBju#sYb;HIbAxJhE=Y zCl$!U)v+etqlM(fD~@)3?z|0TV&eE5N4q|>oIBSi7RaNmsHLnqTFhX2kjKH}rH=RG z;PFzdINJ5W@o{qy;&UAB`rMD!^@#=YWb3i1K=Sza;G6A7RK$C6-H@;7-1~UN;jWK=Q$F6Kb$xPyw3w1~lU(ewk5_?Th}KR$g9Pa#G54l+GlorkQP&t?(t?v3dAc~ zAY;7ZaMy?KPSe&9@6ozGu|NU3&M4b)R;*ZgA+Pj~o6rba8*Jt!Jr6bRSx!%T9AbD%p$#{5>Tx^%U4+Zk^ z%VJ96J&uOcK7NgMeZYUXqHcVS7ET+Vqjh~^fjn4DNxI3=qnVBmKbk4t<7hZ7QYKwtm~5tq{Wn^ z2YLSGI&9OMeYTjAc#osuv>;WTdmry{@Knm<<80xy@gA+~6AL7-R+=}y`cN<(&1>696bd9@4T~wsn9YiVAFN_Uiz$isIJlFD z4GwmFSaGoH!-|7lA6B%kPb`oJiz!K&eK@%6eWoE#zj%6P=*?!u!Ejnu9PIkA;$YW@ z6$iUMtY}@ITp%r`Bo)ZxFPGU&1@dSyCGj2y!)Z^yD3}huG)(O0pnAE5_#6kjK2U94 zpI9Jiwj3JNuu1!zb9|5%Q<4hgX)v7j^y@U-^*If9eNNcezKF-?XkDLJAWs%k5^vHz z&Xo$}$zn?4Jr0J`o_vI|I`do&)J{Rly!~)64z`-~Ba&ei>R3I-FQ<7d99;P2n^>EkcGTik+ z_Y9``YF(dLAg>lvk}~@``0*P2J&P%c_c$0%%N~cjKG)%{&vm%#bG5EdERZ*gDM^`q zJ2~J&sv$vv4!+rbI&Dn#aM$NH-1WIxIBiU|b$w!iyjx63y2-nJHZ>JUW*QBxJcGg- z45wwq;jYhpxa)Ht?)u!V>k|tkU0y?h3#VU?g99$40y%m*Eqfdcr)9+=}y z`haLNsv;Liizx{;BttP>W-}B>RveskKKSXhG1a48pTn=wt`9}I!LAQ8Rb6H?70AOc ziz$g&Ljz|&+Z79>#gwFb^wVkM6-T>1hr?*shZP6AJ_ib>hS#w`(rh_4dw)3G#&*k{ zC}j^$Ix~sb)!S2nJdSpK4#&~14=cKaTuilfePV$;T1-j2$-yt$pJ*L-UTM6?!Ejpk zINbH22y0YDYH3JLaZm#*H3z0wv5DS_u|S?IrX*$diL7&flkq`XOi8@Q!Eo9Ww#&Kq z@g9e}KBwWX&)Ieo#RAD&I!4CRgFG|(b*w;+o=!{W_+U6KD-L&k&cj_FGE<{@ZC#&O zATJhEk_zPIyFQoUuFu7~KCwVvEv6(r$SXj; zK5J5eB%eF@X8Y;1G1bFepX+ef=Q`Z=xmwpJ7RZ~$l%%Y=k*^plkT;7diT5}fPJ6fw zcYSWdT^|aj9MniHezUGmE|3;ek}{h&(FO-Kqo>oJ4)@V;+QWUg>vJFO`rL=RK6mT- z!~%J@n37l^8DrVMhpEXPJ)M@}Riojw2WAEus?&3P40nAV!(E?;?Iel?@?kM0@j>34 zd!GvA=;^cw+pfAM5%Y4;D@v@6ozGu|SfNV;3WDHhUa=vqw*-JstgY+L$$? zU7sU-xk3$s_YdpQW2Tot%503gqbNw5KBh>}aZoyFRDkt`CsS(NtU4Cl<)F#gwE1 zdFCeeoq$vzM^C5a5{`z`a;-k|v)-C|1OO9i-_ z%5+KRnCjuK4{6B3t`BeYnN)j9H3d^X>A60!K+9pwZ!S4Nuf~lc874g$>*XK0c^*LGBCl^SIDTxn~Co;wg+#+Hv2$eYEK#CseKr#;<< zyFM()&FvZ3^kUyEoHjj23Z{nFu|U#nY4lmVNv5-mJ;>qHX?bVF)!SpLhr2%a;jYhp zxa)JbokX!fJ}jmrWewMG@Xa1Ro%ZCX)5cT}cYPkiT_2wFgsh&<^si8VvakT40?%pNj;yv0B_C&JWz!`uyi#mJMEQk({O#X<|LxDe{qukQFQ?!B z@1Oq9Z~yWifBDPr|LdRs$M669w?7~L^xMDu?T_F8=`Vlz_uv2c?avfBZ_a@(qwJ$K zkM=(1YhLUCbNLI=HZL}B8lUFX);fiqjCOhT3`%+Ko5*B5qg|3$UN3K_!9Fd4c{Jz=}Nxb51v;=u{NG#?adJ$?$FfpzdDs>62 zC=7FR@+B>%GhfnX3i2iIE<H|OJjqLp zuA?82e_W$Q#fz)M#4F+$ z^v^NXmAnn0AiKw!c*)DbN@aL=?z{(OcA0t_cb;!D5|l4_a}3Xye7IJMcu6A1vF;F$ z-8*Ph=(@0?izH&Hyq+CgCSQ^VZu)oU7AEd+0^M~?lfU=!Iuk8U0a5Uj}n|X!vyyU@V+2SQBgb!xV z5&WXbJ;b}jS2aF=zU0Fpu;L{z_Cls^!SQ-^mM2~k41nW!=%P~#clt8kC6AgqAqscN z2soGaPIt)+I2VhS7KJ1~a-w0t@F!oBi7hDEUOF%}6(=AxX36yaoNlC>`n!ym#8Eeg znJ+m!YCb(|)SUVoq-w2XhVcX$tieD4IxuXMo66-G2)R)l`B|cj`f?fO($8u@HF6p6 zl9az$G8J{r)-#01OEQwuS@KY?>o6VR@sbah*@y|J>t?WWJCo2EP56z6hWetO+DMQe z?n1_A$;b>RL}5%pcGbmaDdD`F=F~5T$1ccLuAC%bDS8MlRD` zUM@BONYC<0wsG(-L3fQN{C*g%+%6AZDmR3uXZf(rC+Y2>b6~V`BWo~PxslGY$}K!g zo_cfMMtqiM>kP(AUXE6|g?Iew(jdQud6qKZ}2f}(e zx77CVGM{y`!rOC)JLdKr;wA0ayjU);4@Y>sOH9vb!gn-AyeIb(Wi{$cQ6;Y}# zdEC;$zf+I(akx0|Kh4`d08to@$Alk;I~(|d&e@1}dA5N6v>A>CZJ{`HtN{i%O%$(q zbS5`mkpRDc9d%uk>qu9N%aw%9aOcO(4mL^~*Dh4KoRgKW$xD~!LT3EYM5nPFXT`w- zOj&X808>`91586*$&wbsnlI_6j%RlV*pGe9M2W88IZi@hGMDYg{I+4qAmMIB5a0ZTAQuINgg6W_chJ58SX-hl2hnuGu-6> z?$nsv&>x~H*V>&!*uZr;Ty5?$ZQ!~bs5)Z+dx?!OS8`!epo=Hs(`1aa*=5%5a5+5e zOX6A9Nh`YIUc90;J@JaRDwD71l8o_+Cl~1DD>}}k0(s=Q9j7ruWqI_2@#9_k(dJQ7M& zg|J>^6YuhNafTsY@@`*EiI;rXSJcxb>9(=yhLAlcq9wNoq}x zlbCJhOOEcuy`25v?9iH>j}~PZ$`C8M>}}CE-Q&sj(xvA}{AnaI-s8bp z@OY00r-I@=+N&M!(dNJ6Jz9inyhq!f7Hb~{p_+;iY>fA4 zXZ^-2TG&>;qVr7S6@i`iIg_vGqPloRJMk-D(K&pvSzs=X5%ILpa=xEjFqXsb-=X@YQd4og@Rx{zHmf*HoLtmtCdctv}8 z;uUQHCtuO&-gHGJ1^T)-U(sb(n%2ZWeZWd#dwzt zFEpw=U(y!4)4N048JDA%>Wo*k^QQ9^9lPTd0WS}x`r#b?bdOx_!JIkU%51zx`xbb- zqQzdsE854!;}tK?>np!92}N%7*%@WQG`h@o-vIE8m7p6BTDV=Nd$g7|wB5IhjgQk6 zaiPsQ<|`^j?`hq5MLVN0U(uyk;uUSDL)y)B;|1rz0_o><#AMqM)2X*|^A9ekn`C6t z;DZDQgktT_Fb!(?7Qt-OSyfwu4%rai??GTzuWnd@g_$H+&4d` zBPQE-!KGxAdFPYfO^jDONQiqY=49K7bi7GB=P_Q<*0|HVt?}tbONN_dMVC2^SG2?J z^A&9&HS;5R)@raLpog+XbH=7E;&b$KNz!w)FQCMGv=g?{l#<}U#%kwFT3lMZBpJWa zyTnNwzNAeV=Y-oRF>KZV$Q*xS z0e1F6(0IksNboxrhfNIKqiq|BCGufyce>=mLrzlTKtqO8K>3pPX^HUFsmp`3+E_7X zMMrli=B((dscG)!aX7njYP?B1(k9=eo$eBE(mrC9uE=m8lUIvHl7TVoVxSJ9m3=g~ znSEidO?*y-mgPQ#CP1=Us^dy13jou^!z0K{8H|dj}Vb2w48>c7ZP1-h1H83QpzXv6BgZ)o8 zNeP`#dVW=Waqi5#?JpT`^6Zdm`6lfPM)4-?B>b4&48t;aG2JBPA(L*1PZA9@dXx6G z=X{g4mJ^?(Mf`=Er06m@yQCFeb}8SaEe>TT$#Nd7pDA;ewAt-+lYS`DF~haeB6V_3 zZ@fuLLw(H~v-@Bh3gS)Lxo7bvkAsnAAZ0DGEL7$K-;N!OsTEybHb2Rm%c`a9W|}ph z40JHAJd-lk3u48i^@1{2jU{dBFFnZB;yc=|UR4Njo|@<;~4{s4>|9tk^}* zXGu5ddmr*mo?KES-sIWk>GDkuo?_0ELUxLISifRk;BbGEG>Z|SSYJ@kFqSrD_rv>> z{Kgtb=g?gfaLej}{gb zUmU8Hqc>@N-guLMFw7=nWqz`6OY$2Ni*q2&V(wzTq7%vdB<;|^c#{v80*iSw`f;J_ zfyZc#%MzdD*=n`)B+quvOT5X;uh9+$PpFPQNzL!<8?p2xN!++irsm;tvtk~WhA_0w zc&Bu0CRYC>V+p#F^XxAfZ}RM>2F5GWmD1m1>|k82KN)Wl$V7jWv4?sa?oZylKbcB7 zBW?`c=}G!=o3WJN9>eX!-9F)*(tWq%onuRTx6hKso4mTzU%a9nK^?PO%@5`-hP8qN zSopzu@?pVCF}oi(7m20JL8%SC-5`3+L8fFM83kt89g@w<$Tr;&Iv4;41`7}|vh@by zO%4WmQpFh!@?=R1@=QxZ)S3pDNLbOyWUAGUhldLnQ!yuZY%Wf`$s=v(ebpOp(mvvs zujtfdPPTm!I^N{ng?8~Kxi^O0=_XG$hZ-w$5;x91gf8mwba&xmOt*cGHfD~WHJWbn zeAM9&tSuh(%wT`TSo5AogFJa4**X}h0MXDj)(bk4oix0O1?Xbil2ZYqXUJ`mzfY2= zJdy0u(Xqmyo-vp?lzvCkO`3(%A9)wA7HX8Tn}nx1$ecI!v8H&F_NBr2;@m9MDBUD! z7Q^j)lY?jTT~XyuB-4b|QPUmAO8Lz`oR(rRj`zVs(@7K|8^xbOS_#~+{ zIX#I&iR=SuS+it%7au3V^0Q?P26pCc`QIjTSAXd@@AvO&^(;D-t401>&G$)Z_H7qbf4^VaWQi+ zw4*m^pZ1M63GjIECeQYjynK^`=YL$`wo7p5o3w?TR3^`NtISigNJu-F-IwEF&-`?; zuLH)sx!BTB%9{%#MT}C5c{BLk8EQB*st(@db?}TsHfd)$rD&GZ^=AEOZb1@=od|IT zU!0rQlVP-Yy4ezXD&{vk|07=UV(U0DZ-#5$+jz}O&1J9vfw*x_Z+empCpOT;GzW&y z>!1Uv1o0fC@yuiU@UVe*y2*!~D3Yd^!0S709&d8+zp)#W2l6%w$z>=(C*Z$U*3Ov0W&Wtmx3u>Fqur?6i(}lN1;GWT)9g%H4yb z#q)t7R{c%JWIwFao600L`LSm4e6${Fnr=8Bc_nb{Ns_oRWXGF4*-4)9#W~qRPAWks zJNh@@q%Gvco3yae_;#av4ZqV(o)0dAk+10Tbm7Qs1`b#-e9Uf=B1ZMbbbBy-7>J!O z{xRMx{ybkScq#SF&lmfyae9)Mi?cZK#ktt-%6OA@qDY!=I8(VBe7mosVWY(Ht`Hat z5GgPYf28wwwG%~R-rR=INjm!{SW=n1jRr5BF=57Ki8b$SbR>Vi4Ugo{qhFo@JZU5O zSgGADcqwKMNs+-S=x(38h&M@6Wbh^*7Q7TQ=W%thU3$AIcbmHyuV|l=NO=PQcW?$n zkY2;>e3SP1%J3vX$2gHp1F_35J0~fo`|$tK_AV>hEKPdlz3g!f-Z;D0tk6^-kU$qu z;{QRD?nbIY6himjPkd^~5B1JixolgEllMsrH*<448>Z0hcQ3er*%R44|Ks4bK%U6% z`5!U$sUAx61}#+m*=zUYrT8Nh6Y)fLPhL9K_Q^}fikZOP0Hr3feWJ*b;VjK3dEi75``HPJ z)&7Zxr&1wE1l1OR+%Kig5NzI&0)dexP%$b+aNqZMlZcPrTWzK@ji{uvB^GtLA z%peW9VFpw~rm`$&_4Gh!$OJLK9?*~{X1q1zh2EWqL>EFs4&1V&Atz3NvyeGTddM{7 zf`e%^B+sPQkm;XpzC9_jCk?Er1NMBk4#fJad@_c93N~3 z)sPELBhrwW1k%i&4D}@2Qd7BM>|xwD*7W;imp8q-9zHbY%hPmnpc?%S{IM1^AU zJKbkKJqZMg*J{WG3umPAxZfXAaqy$g)1eWIrZtVtZGE8; z+xj$(lRT-spX%16`5C0g(zxN()->XPVNGN9vOG(;rjaKn-N{46n-R0%nabPCQjoL# zDDy_aQFXEo=Mjnw3L}v3Fm_Yg@7c5VeDrhX+KxJhz!@eOJs813LUS*8>y1VC_*`2xR z-Rxd*ww`78ij4tUCfDX^ec=sG>(lJc2DD~&Z#dOdpCr$Wvh3b?ww}G+8_q(pw>$G% zz`)S#&NSd=c4wzr_wDAHQI_3l90Sd(Wpe)&>UuJ)EV~n9>SlN9Q=8eHooe0e=9y8J z-3Mx3&F<91fdpB0Xa0OQyVH8u%(eKBk;1U-zEJb(+dVQ~<=IQN?9Kp5Vt4+diC~OzP*6k@**%3SeWu;1myt09 zAmy6fnb!i4_9T-70i~w>?yUX*3DQLJf)abXQ#uSMX>a$;p0?+!XxTkKD+NX5Nd}QB z6D+&ur+M)HH9weo@F$6JS;_9131J}Rn#c^01W3#7v~YryYj!VaqG}>BIFRAp?#aof zNRspQBNL!ARrhe1yL=h57J;5`E0&qA2SjQ_9JYJEAjTk=SJp#4t4a@fl0MhhF=3JB zqr8Lr&)=*$dyT5z!9Ph`5|sisYREB|FFw8N}|iOCT}$=X6>So7dCbh-9)z zArB;up!bkivZdLL0ZNM)(>y8O&apTrq!T1t`rG5KPpF80gg^nE(a|kR~$o+n!mYiQGO^GHRtf>&k#P z9+9kaE#%uqxh4;Zv17~bEy<>5c5B3o>O?dm2BWn|?jJHQERk6ylAk<1v!2N2JYYt7 zp{Ho?&5rvLwUF=VdwR&`_;yYb2#=D^Z=E9IFe z1HAEwWR+_n=SAioa;1VB%kEV0fSS~Z=zD5JEZ^25d16#w6N#>;Ci41F(9cTwg`T2E zB&%Et`Gvlxhs26-%kB$T4{1d7JvAb(Z`UH3vh_&FlT~GjOl35va!+LQGNY{CMo-b+ zn}H=kTF6tslf!@FjfceANz3kun~pUi`kopQvy@sSli&y5Xd=<|^h911^s`bv(Npw@ zWR+VXPa_Wbo*okOo|4^5#<+r-)QISNYQ*m9|GYMsrPM^C>uK-J5(N}0o)oW?@*q-m zr$)qLEiL2=`ko%LIZK%W)aEQ@5YhLvBDr8&w-!lm4zonA=z4l0F{fyyJahj*OL{~K zBWfY%b~6vzouyn-Rs}lE3ebkWr$)qPWG#{zZ4LsYiA2}a6Nx!RE9Dz{iW)J6HqURO z7V;f^PY>ChrCj#zEM;yD)ec&b%vQs&^T}S(B6)9_dWO_QqU))N%xp`z+*Zo-+~m8S zPSPV%6TcSnIEp}|hwRQ$W-wB7mU21J_p~CJwjMZ0Es_~D3y_w`OofG;=!wLfqLuO! zJw=U(Z9Q7Zx&P5ac4sN$-gFx*7y6!7Br{tJYymBj7iK9nk?4AQBAW+*jpag5(cYU2 zTaUDmXU0o!|HN3L%A3{X=+08!Yt+EHup*gBuyBxCB-8B*keWzzJvEVYp`4w7og*+}8`JNhb>CRHFcaq>)CanN1=zD5J?4{HqxnP!36N#>;Clc3q zTPe>2mhXDfX&#X>LR!c(TLFmlklk6zWUZPFmUTtn(~4v~Za7FSk}GB@HIe9gY9cqx zDOxGt&{Nci-OZU}&5j&U<@(-i-C4>tE0LNFmJNMRE0P-ypVlI|W0ukqxufgpiNxW- zR?2tu6g?tY( zpLt`YJZpnNOIpN)p>tAC@}q@3tFM4a580iiyiFkZZYw}p8{B*oPaNy4MKWswfj9QE zv&jS^behO}qsOyMS}D&WV&IKO>~7A?LJv~q`rcgKS<3b5&Qh-3gMmioeo=r$izE*Q zviByt-QXsAA~C0Er97cd(2^dJ!iZYP<9Y&-8j|PuSaxUsGUzmoh`y&r+$g}JMY4O0 z&sZnAo}Ng|DOxF?=qXCXjRyl+A>TgedwR(3Eaknu5Y(iU@(h!>KkLcj)rdI6(Te2u z!7QaElE?UHBGX0?DxOZ#O8J7GqDLgFTnjlb#q*HeS;}qc&Qfj*`kq!KldglCs711U zjL*hnd_0kuQ?ydPqNk`4+nY1DEI|iVuI~-c@v$P zw(kaVkj1;__KQikV>?17JUAM1QW1-$^31xGW-3!PnG5{*(%KKdPO5s-AD+6mZuX1| z3!&_X&*-7%vrMY8nLYbwBR|=)XaC@adJVbYqIL}#qoA2Rd)E1Ovu9h#bkQH4oNDv! z+3zp!74@`cU`|6`$a~FKH+zzK2^F3CGFz)DIHEazrAn`v%Il!gbxma$-p!toaYoG_ zK36gguESXy$A{bGrKletw$m--f>9jH@r-@zwl``v4eC0_-slmn3G-ApqexTy^h6Rw8#zem1t1XQ?CZRNq3r4WyIqq0dscFQktRu9l2LjCUFAH(K_P zLK)H@&b|Hi>I^neLM}CVvl!F<%XN z@ZfNJArGt@@>JsVHV=v3w}(VqRYRWWH+o2{==YG==H?->_gh19SDJ_9M60w6QexR` zYh2j;y;&QJTgW^jnU)$6o6_!zJmZUwk!d5(W`QM=TgWsby5O4I*~!u@lBoiP2V8$P zx{dm?Q#}$Yo{T_C;pDa=-d0s1`#Wqok^7!k; zqY-gtlt#qoOCxqKRh=6KZ8VMDjlgrqc(kQ)#}`&3;(MqOu>e^kX42ZTrdY-$Rpg0< z@g6gYJ8CqKiIe#> z>LljS%%f#SK$|h|4Rzi3XbmLr$Z4gyri-kd$^+-4Xh~YRS2PV*N_);Nbi%i5%zewm zv}Z|@9NM?5*JhpjhPir8BX&hw#Qj6rMvb_T-q45{qtMIih)?hR-uIofkpAj}96gPQ zudYVCsD?r#V$1erA&-kfb{g`$=pBoAiM+<#V_GlN?#K`mBH~kx7gJyY)$?6p&t7``r`A2;54~2<7ov$?K64lx7;biyCpq?l$|? z_&VITUmfIvjny8Jq+Ao38aohkOXT_?yH6vckLMA|lGKRtNLm%p5$OpLPw`Yu<3@3p z)Z|McAI+U|^GE?LXh|9D4rFFf^d9BF_F7pb6C!bLnAMUg#emP&M9vR6idHByFgD-y zB<3=uGvmyneIccM;@|*(lFcFXd^U#AEs<&YCQnha`^;z%y4@NwrIgPSBgrpvQ_4(^=y7=gGeu}KS`{;vFu)ODUT*HtLi`|?Zrvy zAKmW!M`J~wE2>^iWVU-hUqyeCFExXsew9kl|$kaRnbL>gRuY=FFZ}++3dKyh6 zmh9+)?$~ljLS^{3YBlF$Z z8EM&_L^6D~X7|-xWnk6#Bizz@>H@RX}{vuD8~aZhD?$l+QrW# zM5EF};+}X9iTybqvOPL`Z5W-^R3;(VeS0P9s6HAB(AIRkm!MX zNbDikki6~NL!yo4A#w7Lw1}>wJCzkg3O!i6|LR_)o!|&M%=REpoK0!%-&FrK8|l|Q z!nf7z4+E?#@BxqYF#Y(G1RP%tq(BC$qu zdtgVJCbIo)82C15Zf7z^Zd}~D9)oi&vQia(th@W0SEor3v2TGD@+N>xSG4P zXG%Ru%)>iJV{?~wXvCA$G~x@U5wW&IBVv?WBjV64jo6*BOv0NomX^kW!77c2vtK+S z#o=u^{Fpqc*?RHr#)E+1xU1w^bO+mxc&xZ+#Z~!X8N{}JMJN|CeTCT z9Ca_6k#>+HPbN-SERfk8Z_69>gPq9sy~t2IkW4S_I}Us=U}6|gGkwRXn}@{ox`)J3 z!Co|XO!H_mIc4w3jAs=(S|5x9Jxcus9Xu{hzd@X~_cth&0C1X~>A3jPL*g!M4avm- zUNldv;q+u?H}bQz7s$kJC@trm?`K^knk-6)ouxrfA}2`}v{I;sUs%&2OnuQ&+AL!zVV zA#wAs7tIaRpPI}K{nP@Pn5)#{p1l=dY!)ENa`)1nN#sCg0kb{*xg>fNL3vVfT8?&f zR6QgPq4J`cS@FOiPbT`Q1u}7Vi5B-Ay~+Y4MIpVk@7NXKF^~52XR4WKB#M@!)CuJ` zt(Wq^J~S_y2c|#$m!qHR$;{3dxaeBk?=hOs4DyiKck>MCr9EMMAhUqkp8j0U_Vj1` z3u=uX*n9` zsCr1O{Pm(aF#YMtL_f7aCgv)&xDWIyJtU8Qw;9zX%M07zwIpf7)mHmxwx>UrY)9+9 zlsu!}i{`}ir@lcG{Zvh6LUCkfTXA1`s(b;GEO-50tRHk#3z+Tc&-K%u{#-xks9MpC z;vi?hi{^sqPfg~6erkbC%vEY}U(l=ckT~ANOZ$S3Y5}u7{kbmf>CY_XB1ct==86-m zylAeN{`6#`pIRUjx36e%&$9Y_+LI|$fTS_7UfN?F0htBN=63eX1=!ltpX-L{Pc53s ziNImXme+eC0&ZZI>wRy`6m5cRT6bX0f-*3QJ)K7eK6lfZ&{;0t_AWb`uu6Y}6 zt#4cs1?@J&Hb3n)!#0n0n_*8pshdapCkw=zd6X^4?KZ={;FfAF^XUg|w;5tBwc8AP zTm<5goF0~nzPZqYBxmg`pFBrI=oJO4CPy5Z?*_)V$4t_I6ul*LnfM;XFL9r~GT%KU ziKpBjAFi)SM1Ts>WKOhb^=WSWa#%9AtT%i9a(|i|%X=OHCrJAsBV<_?3(C8`;^JG- z3uDN)hH+ni;i5dR=>{gX+)%MxqdXk&y1OmtHzcm>EI^W-s3Bv1b$>W}?w(27dOF@@{RxGbUs;q>O_l@+ef=Xu)^&V(I1nZ?>u zKL@6CG95q?nk__R!`{x4`uG$lQCO}3NpU27kM7l;AWNQ1%-rj;lB^3QeY|L{N7KQl z+o(r|LXp#^Pcu!DK;>#LX1Yn}vU@TyDz|vdlNeNBdX~UE>p9PKt^l#hW0`a-{Y_sN zxq;h#KFnmXfInUpubdXN3|h~d0Z&=h)qi@XBRyk!24T^U4SQVMhjN$8Zi8~y z-nune9zpS4ta! zN^c-#6D!#7n&~Gtd1>VlZ>alHo>;l=sZ9O$vlRKW#HMXeC6?EF)sbC5`Lw5J&3`#I zZF~FmY#+pVU6>EkUw->m&xh%+`NgZNwbD${DX0#uH1nW$-=Hjh2P(a|M-Kz0XF6Ik zp6R@j?bfO;JTbU!+hbxKfj-Vu9_BZ#3TdF-p;d7zJwT4UY^E{+F#Ta-cbg}3;)D}T z=EN8Muyr%n%rJ#!Im#d-5KS#dSxEG` zL7udcR_^0-5`%P*D-*yelHgBs(DUn06XRz7G?!2Ji#}4N2dYCK=F%QFOLGFn%{-Ou z^%G;k`Ux#XS$GQU(UG{3y7!#c(>?cO4oU~Do3!D^ir%y)GeKg~aQVA3HAh0afazA& z=J{E%ai(yZINMW4o<}N2x&>)P-&ddJ_93QgIoi-h@Kh!#@_Z?EAYp7g+tYeMBW4GP zdx1`znyDLc#*T|?Z5Th0WMz9ujOc2gC5{!5>9t2@kdkz2{hsx$pgp`K9UP9+JW8M# zzFq5&6IGI}gdLej38%UEFUQKJ0wxE#{BdGb%D-(FPpHp%J5wQk3+T?O=q6i+3t^Ynt0sykr1_X7v2xdJ9O_IS*h!lq}VrhwVLDsxO6!J{Q< z;`mvuJyIG7g5;@0W$dX;f6Ft={S}&6>~Q-bN^jl`VxZ#+n7G=*a%g_q*IEX$TaIQ@ zfpC~Qz!}v+0cicOC7Mrk7BEp4Yo=$AV)IQ;(t&a~p2|T{?aNxRi6>C~;${7edxIXF zrtbEiJC1+XHR|&~{XT4dWS*D}Ty3Nxl{ggZJG3^waMYH^yd!hZFVV1xwhX(Z`N-DE z3M5^2+d`2R0j&7NWzOw32+@LM7UrtCjdAdj!F(@nmB6sy|F@z*=pWT)L3( z)Ahwn_Xx#L?`PUwp$ms-Y8J)O0-fX`F%j+|F>CE1vCG9n;%EX7c~L>1m&|d}j0-QB zv%7j|$?6b_b86)gH!B=?(!?GT8~F;5#B&dcRZ|5>ax=6PWy?qR6O?XHs&}z>GTVzO zcj+P9HAnV_kQ8|;aYUPk#4#yazugvGr1|NVd&yi6I!$|l*0udk29oZir;_IlODkqw zFLD7rl^EtLK+-Fz=MiQ!E_xRQ&~yfpn=Z4!@dZ$lhQ>^@RJibTFFodkBX?wob6L~d z1b$Efl3t8uu@Rp&IjpGLr{naX_lgtXk?oyXQZ7e?+5=5fHSx%XwwGn5e%~&twl2uhu~4;>)*{I>)8nD#^UOl4XJPV?xOvL!x~)BSM{)*)8cMSD_d zg_qAUiAP>OGmM2CIennVf}=jIFdetL>y^(yl9{ZZqhn<^PTQYHHiLKDiWv<}u@Ehv zM`FG3cH9T9vL)H>i+-^`&=V(FY56=)dOJKM2LHVNJkm4?vZUYlV}3}5cv<3_ngS-< z$=ZWIf8fR1$K&qW0E5X2)45>0&O>5*wAP;qGEnf-KXK>YK0qdkVH_Z%<@4Nmm$_zA zvf?00g#%?TR?~T5^OJ{6Vehla;Pq!NCi%r$f1XK_5|6YBNlFIZVlST)i<-SGWqd3> z@VCLQjD|F$Qohg%)3svpq=&=}!dibO`q}RyTs!uoYFWC6Wq}=1z{KVNf1n4po_i&7 zUAPZW3sVM~fetA^(k&`n_YueVSt)CGGh3e9eVIrn`7&BQ?}Fb^*27ETPyEzUXifG^W^pDcB>E$!S5$JAeCY=dhJl}V(M8<`a z%`~073&KO0~WSX&Y|0Y40!t*|hp{&V|=t=ASD2bFR4d)e2J} ziANf8!wu|Oe@5cj-Lyp#>4Br%nU~KW_{CNy-V_gQ(pHp|6$z5%4aZ7N*fk12i_yAKiBk^QSpI&kWxY1o!<;3I>u5y z1Bv-ft3OldjM+GCGu)-lWY>9FO3)wtO^mxjtjgPt#v6{clN;;!>>y`@_jrs%4x_Drcmd}B1+-;j1H*Q_# zMmprqrAy2V^mvw~0w#{`)!)8mydlWErZW~3>G=X?j0QMQId3Le8LYGN=b1YHZoaPx zC--CGdJzBZD^5);U}8+b%hHOqg#}Ek-SXcaUnctT$$ek7%qR3q_sHtH+q7xN5hLnbxxtdR?llrZ&>xaFY$N#?AFyl7Ba0g{x5ha6-p6d=h|@Q~d*IM#JyA(W+Z z`*iQ0TmwmJ*i(rW^94u>{&+~N2eC6a)-8eA(DCGFSQBB(S%N8}zdV78=9eN=(o5kF zlV{Q$cC*DV2MfOaSL>yECu79X*IVmo-_g6YlCJ$tKC2^7C5|WaRAL99rxK^YNlzsX?Y+$$r`F@~!_!;9oD|X54`upmD9h?GCniMgaN#v-nADLqWdccop50Em zUsLEte%1YVB}>PdQ2DdSYaV4u7e%!_o!3Ebs;6_{FhWmf5~A(r$?KmrooA}Oy6HT* z0nF36V3t+$J#X+$$CH}(bf(?4{X949^xb5WN!n-8ZM)=9{xwS|=soi1dEmwf&-eS| zyZL_hzj5cqZ=BWhXSM=^wdBt;tA^UoGojsXIxn7MyVzAB$q`_waP)zCi?7^H&>;mn z_d!Ch>D;l9s6c1RJK^Isote)LQLh4>6YF|4opUEU+0&VondEUAdjM{c+|Jg^ni`;>pCd zT?H~R%dW{Bm=gD7#;EH)&CxzlE2Z{0QOloZ`{3D-iSCvsGuQH2+zU+4pp|D#Pv%6& zNG2t=56{2XWX|?(osfy$I-bm(EJV-rc~ThJlX=ktTp%<3lg+X@arBcWGvUeZE0nFF z?N=xpSjpbDOi$Slx^DKSFFd@%li5DEc}pP#T_Kx+OBof`Fxx0tmWiQrt2>j=yC1|(7b`8Js5e~h{~>-&;v6&o=hxqwNKo33>vfRA+c`Oe|TaG&-TJ%72S5?PAvW9*^C4_$wOi- zZUK^RkcY&P(gjGmk{%LGuL2}pA8Q+LC;HZ&O58Y8fFx7SLtbRX79h!0_mDV>ssKsa z%|l{IZvm1jKQv^TsPda9H&DM62^iB$VS|So*JSC(=fb&_{xC6&;vsR9n$~U?)-n6D z#EwBvWqN;}1=F7;X4DIiWN!HD6Ty7`@Wqpf)pB<4Rh$4E)@g^Q1QUm3+4;1=#L{3b z?wQruEt{FjK}vJ6e%ioY*jkVVPBmIQnaKe^3%n;2ofRKN$Y^uAm)b#{Sc106*18Zq~91qD>f;Eu#HG7$!4|DN?wBcY9 zZONsunh4eB$>TmfB-W`HAiE=_`;MK~o=SX!JS48bC_vtsvnSQzA+dwE0NEXU-FF-u zmDpDAsZ0!|n@Vgf_f+Dr{sJVK2i{XVJ`^y_BdQYJ z_k{%h+*t#O$;tEkI~*u4-}2`u#l; z;=`KCtd;}zXzL(Lw(j3Nd8msu3y)Mx0;d1;q-dYX^pNf4TgQUa^gNX~c%%T?FYH(m zR*+2Wiz-MaIxPM)ahFR0vR&A-+7?uYrgHtXYxd}(knyC9Je4@~%?>Kh-b^ey@?_!? z*860fF}z;w_k6{qr%q5FJPJsE`Q7>YEJyw{w|+NZLpQ+7=GGo8Ja`7DXHa{vFg;e? zbxcRnN?>&OS1l>EoYs?y^EW7l3}9*o?foX)-fzMsu>|+re>j?OK7x?p7{H$b&-*Qz zz2B1AXS*en7*99P<4QwLT8mNqDqwj5vi&*Fk`_{M+W9-M$lHH8_Ro6AeiJTDf53A8 znjaVy*M$ukp-*>mv2~iqi3XSV)v~A@F8XS7HphuGwDK>Vm7RPq-62~ZbetI4)BTA@ zW{nb^I^3Qu2NdYhqV$8w-*$?{k(44`O|3z)If1_2ic&0CV3DWtppc=5%oyNj3$_4B zxoHo1QCzbCNjJzt;(#Wt;$jzuj3)=9KqaLp{mV9SL5jZRNejUB(KW=!M6X{nX!3$? zTQ`u-3sP{0eb};F3hjj5zHDbAe8i*tUA@4u6Oiv7Gb`kuZ;?OH%>sT_lAI={TdV8bE;5Wg zRAx8#Gtae>OFJ0cNlj&{yy3(3S?&v!$`l~!#qf|geqZai9apn?NNlXrk6L00Ijkp> z%L@_4Cv+I{zb9%Zf9Yi&0*@1cO8jCB24cK%Y_NQ-;6X9Lgg z&v0^-{U3m-8I=7B0BJK;=?S7BwwBCoql@k#G1KkO5?7n+2PmVbLD;omCUy_;7_Eo1 zdMoGO8AG_Xi$vYaC6;;nv&5;5zur-I%i{^aY2FC~iHTOBzCc+u2ZoF$Gx-|Q!}bP^ z4~8G_@T5A;@o5ho1(H0P8xAt?WM**= z7@PVupP2aHg)t_btw07V09UavIne8L|VtCN-7k|_D_LT)G6(LpZPct3( z-Aq4F6&J|FOuxSA+=<|sez5&+ZNmdqu|LhM%;{$OiK@6jX1`gSAWFM>KWDokmwW>- z$e-qgsWAPfU#N-;Wa5ByebX}{p`Gb*u)5#$fvVV_=Ds^ML> ziAg3cn_S`VPm{~>HPa^!&MJ`EZx&~_FX&Cp^qJaM&>oiQ^Mi#B`ZP1!nG}*``s6K| z1u`#+r1;Yu6x#JnPofqCNt3x?m99U{1w*@<=?f0RERczzU4NQrX?v!xXv1nUQ|z7J zJjIZ*LtDB8bH`l9`ms5enM5@iH2J%VYiCafJ?mOLFC5q7A+eNNkJ!vW2XfU5m{?Nm zZziwG(#JV)`$vJy_K}Now2xezQAu#w^NzY|r9^Obi`Lalav(&G)nx zVq(ZkJJ(qjFma`bX8M8wP7jI8Iy@u}%kwvAnbdfs$>cp*p3Ic%f+p5Ch>Ic%kQDXs z(!OGKLID$J)q195O3XuIb%KV>Oat((yl8H?dD@eS6T}K+o>cL!#eGAs(nDgf*h~91 z@83MR{vLD30JLU$UbP(86PX?o8&wOCR95UobH|+so=gmB7s%{RFJ^ZvdX@SHrO`X5 z^(01K+7HZF7BIWRHr3L$ZQOL79%h18M_E%7BDYT#h&RH%=eJ!sA|Z#L2#H}H1l2nrY95q)B>5^`x^Jp zgu!G!_iGHdlGkp$l(Y3fI zKMxOvhr|*jFYOZ@)dD6?k=9I~*cs;`(NXn~nEuqF8J3gbVaZ$))Xi_6ynzCl-Ls0~ zOn1*J3M9@d($b!VW>nx(z{HHIXL@(~Gu;E|sA?*g_LhW@iRn*ICiCa@XD2SrvD0X2u@T7@7B#x8vqPb%F)02sQswb11*tEE3 zniMd|Lt=}vmv-)pD`2*#KQqsw-In29VOlgZl^J;MMUz)%X)<^8QwwC`L~1SW?fb3r z-MrsQ&UOeUI;#E#aYvwMdVBgaMatx;YAUltHotj#*1TwDIUZnoGSN>hkcqiUeS;44 zDm^3)NAc2rqN7^CY)^kK**5^07A;4aunHLr582+)vo9y6KRub~r}`U|F^Qq$NqJ~- z&#*vXPyv!GcQ5VSuvx%tPk%1lu&L#U7iM`#>^t(JIWYaH$sFjX7Rbb0r55*rUZsb` z?kF$q10B@@W_$W`8SUxMWul|1MRVdD0xy~q)1RJ9^ivCDVy;q)dtzMqP3yBZab2{Q z_G~$#+Li)ld-^jSbaw;c(`i~cils@lkRB2z&}-3L^8|q$c`~s~*OQs#0GQeK24$=+ zd6fl7vfRD2FX*TiFx%6gYuo{_iM1Rp=%{)~?EdtkxnlZLlbL>WxReDlF;}U@eMPU* zL*kroFYPNjss+sU^yj*@r$5&X9aSxwTl+MNecdqq>B&St)!(3u;R_v4MuHai4ZX?& zB&C?Vw5Na%lzRcQJ^i`z(m5?hJ36W!GK-#`#mI~1j_FTNCiCcq5bf-Vp?9++twcen656Uy77tJgQ08D*@F7#6iWMZyT-=GV< zN)OrJPr7F0B*>A!L8CqWxsLYqXZrf77E+65|KOv<3o-ra$wWWZ-=K&lTy!n&?aLtd z^dWQ)Fhg64Rd^5=U5i(d?g6lzwa~(=CvRxk@eW$$2-Yn6e&^ zEO#&MD>|wL%=YwWI-R@IpIatkc3;Z1eTP!Esbcz5U-T9IRDXkbccZ>RVLC9V07;g+ zm-e(40+|KO_Vj1AR?>`KEk_$Vsva`->vJT*u7=;kABv&ua)PgLGaJPzh0 z;q;hi2z@?Jk9mElETMpT($nTK6PckGSo3IHC`%f1ZWPk?-=5+t$O>u9Gzn3_r+_)h zt@fC)IidQ>W3C_4O9jmHei)ttu^uzladd7o=5?C`y_ow-uaW=ueUL%tF%Mk!T)>=U z%X-YH&vqVNABw1WIunBLevh&&k47ALI%C|Nj9_r@%v2rB9+6)KRIQehSgzoOUdF&iV)Zd=9lkGe@cu1M1^TgUV&m&G- zd(4YR9O`fXK@L-64lH`{-#&Ois-|;dU`f+?@(P9mCXZLP-+pG_4ri=sy5-l(diAmgi zgo;%KNqB_!-S0o)zP%MC-#-iD@lQB@VRlRANP^r*e>BdMeWj-Fzi?Oy_ATdFqb8 zkvu5IW1eVscx`m`U-PTI%sS($DcGr*e)V7TtN)r`{nz~Jzvfr}HNX0=dHW*zJx57N zH!YWA!F;2&Vv;GyWANyzdB|>?{Tdqvj5U?)Pin~Y$#tJ4mQ?7cd>oX_@Gk|A3(=V4 zlbN2+r+I&e@+`7Xm_&22-pcr(&h&IHc+owb3kEj}bn+Y@eVz;Uk$5_}@86#%FC{O~ ziEV-fI1p3V*Z)B>Fs6&4ie#K?@NbB};N>pD+o%Dn)yKqtmL3Um&#Ks=p4 z=rq=PDVfIh_vpZYzCX_ci~Rg~a>uQw^Tcug1v)XdTc8sooSsf@6ZLc^cnFq!fzI@v zcIzchhC7Z1uoVk*Vr;EIC$`6XI(av;r}M;Ua)C~atrh6RA}UX3++uh;Je?QL=`7HRv9$u7 z*xT&s$xG}CbmDBP z0-YFJ^K|llI8P^UUMtXv`(z4qVrD6E|2C=)~BXrZZKa-SrG<^TpU&fll1ypwDyp zU~J9Px!~YuPv?TMwE~^k;9Z~-V{4wy3~=eT>+YEb-S5$|rk$|au3Iu_7Gl)?JU85f z>iNz?4GMJP?Dztm7+dpn@=g>_CvO`m(1~4&1v)Xd=IOkxo9=sbU~H{G=Rr-h{yYzi zt$8}nPkWppbHAyEr$8q*crTg3>?-JE(sHHhuR2~+mmfm}_p)i;XVzi6JncLr!_zt2 z>mZMv2bF6&kF1UF)+1@I?C$Y6g4ljPGqj2Br$5gH2km&wT%&d#@xb8%otW46m^^p4 zfZ6}XA1O0y=g~ddwfT)dcC1bJ=Xv1X!~$l2ochSq(axh2_Z|3eKeJ=1o9`KR*c}f# zuJ&51BQsYh2I|jqEbTT!+A%2CRiG37E|1AI4Fyc>7t)wXPqf<%*~igtGn^mH9r|xy zaQ99D6Q?$L%(Xv8f36s#FVKnguO4&5!EXi3{#aO2a_u%lN*3>LdzvQTzkSCZPLG+0 zdUp&o^X1!ZhV#IB4*%^Z_DU5n&vu*Pd?9aoa^BQ``-MFT9&;@1Hp4mk^AqR5{DlAZ zq>#F8?{i{by{0ph587>p>w|H?0-ac6=P`MRbpaEHuzJijL96EX=vv$R#Nr@epP2vl zjQi-mM_0DJbjKO44Rgl++xPZaCvjnM)`_R{h1|@=xtRi;Sodt_`yAK(7(d_5U+bAw zBHICM64Md>xi~OHm$P=S zZ|paTyPZWk23#AL+?%HsE+lhW~PG-0_gur{^JY-+_ljlh8w={pKOLKT*eH zCfaXWWll_27a%E;@3rv6h?!kZ2Nm$QSH4uFKadlSj^J$karEV0taQ zx2JhChp652<5_!JjClF6hr~3mhwQfqlimg?@>HTl=(X^UBSkft$A>z~JtQ^_cu4G7 z^^mxx$V1}fWUq^k^aMV;yjo=*nC115Sd(1%a-13M8H8;j8uG+0We@XJ zy#gezdC~#w_O<;SPlc}16dV%Z?>fP%-n#=eD*&Wmi zBnS0m>qaoU>+}NIU8fhw_By>_cGu|zvb#?2OyPNRwkD9>b$WrsIz6w3Gh`Kv4y`j+ zEY$OmnCC5gd3R7R4C)T*1+qJ+7s&3QUP9vCLA^k7P*1Dj4W}4t(`dsX+8z@3n|f<_ z>(0vFX^{5UeCy82hDyxJdj53R=_TWbb$VK5?%k~$p|ZX7FPK>Rr}>jQiTtM3^V_>y zH}c{ACgI+167DaUgjr_L?U|=eqMPMBAX5|I-OYO@$WD%hmh}_6c|Bx*l<@425}p_(^tvcDK@q*ySMuym z^G1p=&0F|#jOlqX!cmeMGE<22n^yi@-D%$Qb9JYA1IcM#t=}$;>1j25;Rc}sB<1|P z6k+L~hr|Id9T z`h$d{KS-DX>p85a=f_7}(;*CwpH`U@ql5*>c3(2xZXx68FtuQ2J_W?>J!JRHzbvfm z4?9i_J9=G|$_o&7f0($)%R^$`SbzDF%yF|A1(J#d?3XV*wAw?q2MIH)p!=3*13BGt zt%Xx6K#rePnSrFOAs!No2@7A|J@YRC2`nbmlDV{-giBVM!^7*T>^BKBnWHim-#Ic9OV#30g zIknK^zWo?fV-iy@pWlx@kS4OG408D+D879%KhBqAWQuuNV6Z$Xj9@>1S zRcJ68UA$nFU* z`S9)uFZbYlngihVTe9$=hIgA<$pkohfo|W>Ou9dp6N`d8=7nyRzLgi2b7WAo`|>R0 zgW=L15t40*eH6h zU~!gpHn9WC3y}2Xho*AS%1+Op(J$*MXn2k~dMYy{s26h02!N3B6dScv29h}LAs4EX zE;;0@-a1CTP$+Ehc5xSx);b>Z{dmYeovdCHI(_lLJav zi&2u>KxP4wbW!2UcZwVoFf$A6nd|=3N4IsIK6tXO{gV`~o z^ck}7<@lU?%p@1OPjg%83hAiux-aDOUiuClQSi?!@^l`PvH_mX^CBPB(|Mir5M9AqsK%mR6>D)dWVOmiNBqddex=$y_$N?Vik?-e7;4 zOB%I6foM8Y!34*t6-X*DNFo1yA_4lvVS&fSg$$Zq#PYZB?v@cQGz3A9VZ%w5Y1D})M|SdYDE z77d)Ge_t{8?E~wQz4jPbgi^r7B&|PAtU@V3wm-rHr=0pHBQa=D@At)Zf;2H5<^}!- z{ZN`k6O%Za&X`H$!4xoYMr8pL>q@QuNT!yo53S?(j86qq!IOyBBs5BYgpq-Zl@3Es$Ps9$3t$o#6d$LwV-87tIsLB=~E2VoO{B6DJU8 zc|UPOxt638V`v&O;ax~S6d=*$^qAP!;$<@>FQMZ}$N8r%JK(@!^_X0ouVr)eI~oHW z4bAj{?^*$p(#u|sxcvJrO?0k0*DQNEnmDVcfVq?U@Ne715`Y3G76fY+O$^EvAlr?P ziE%z1*^V7Yic`m?QbvQt4_3=%W+xf3THue2ry>P!i!YC*T^k3I-e4=7M4=fE}FH=LwZI8U5~szoWW6cBhFVGt@ z{zv1&N5h{b&SdZ==fyi!Je@e&(2M)PO-`lL|1-4P2tp21(k|z_jvAsiCI!D=|0wg7E z3y>6r*0PyJHRuv(1|<}m-#l5Ip3d|zk!x4XH`_9U9L;p(0`LY0%nx+bvxB^Fq6V9Cz^;(dAu!CB&ea9}6 z+c;6N!;?2gYci8zg_~Z0q^PNf#5Y6pJf-R(<4MJNc|UM*i+|cOmxE%^`Z%-oHs|&9 z?fw~xZ3yRCz(m)@>yHyt^;(n?N`X)J975Nn0NI@uJI_hg89JA7@>XK6H?RIK&P3m- zOVHo-3*&rV-d|{|&sZN4cuyy{)qDNHTV?fKPh}h2buaP*vqSo_bMt=zvR!`+Tx#K| z#0drdS?8^?y1MI}80hoj{)0w+E$<0@ki1(SB>_&Zh9xr%1?X7YOnn|AvXcCl{X!9_SZ%%oFW7 zk9pyq)dD7l`#k2r$tj!Go|CsBS-mtqSR$&wePkDIzU|3xEnrSc;(5%7e9o(v&JFd_ z?T@H<(&#U~3?x~J+I`DmcGqqPl1vaS@H+-83Xo*g6d)KnE1rmg@0F)WOO;LN=_*rhHKEexr+qiJTp>u9=r4}}0?K&xWa1zIFGxI-rGSZbw;uDv9InT_(BCLv zVlS`9jD-xcf1xzdskEkh&Zci~Y)NFXj>`i($7d#~HuJ(|qKMIiK4|~WgLGM1x zgIoB<@@GkT?uaLnc^}-#i)H9uliMJtT(aJY;tV#I;}O{Cg_#Iroq_ zUN1viq+UNZtRpIbast=7L&rpypa9uiGk9ei4H?>&%0SYp6A#(FE;k>JmZlCz#!V-a zLyLPFlPJ?_OCa*?I6%c#CIu5MIFA`~E28rBViYiOYOXDPxy}U*56`1G>h$e4$ayXp zhPEpHUU^DnS`B};k8e+!pt~3ThU|`@oh$ajd!59g*jv9S*D4J<{W^)KxBGj^;oWLj_2Rqj*T{GWSZZe=K^8LsakuI&lP|e~5lC7F}!Oy?y0J7K!3m zMNQ_>J?tb@_AB_KU%_+gL0`+G-MKsubS~}G-0R*f$?dQB61>~Oiw4syOzzlP;OOoePUBZ0g}=! z9ulXgcpW#f`p&YzWXeiXvN+8nS*|-V6f&M3 zHcutKYufd{KKNwlJ9P2rb}yR?PW&ifqW!M*`?YXmwC4MYK7qcLT$AFd#BJjRNXo8y zNbJM&XNegSZO)_$oLmAgnk!~AJe{eEg^CA%Ew}!_)U~04x6LVWGTMtC(oR4xuon0Y z6?_4bd;$%*V?a)439cVBBzZcqhEo@8--QoQcjxcWj=gPOe`L!`&g;pd(W*0RN#N5x zBr15#^aBU`dPsaT{D)&i&a3wW+ZnwWaSfvv_arWJUQeP~pcA8A{ycv$x!q=#6HdV= z*kfX)oR;_uRe-BrfNVDpd1SrU?|FzoICTi^x^N+@zeEE=Q~nYStVq&&E}I|WI6Y*) zf*<_~KHawP;W|x_7&Mu31)lT#L(QR?zC%#(9y2uxfT>l|%qHu0Oq`YEKb;G)^qVpJ z9gW%k3`NIvKSO~eg=EDjBQ)+v-jh9}ulh*SGKr>@qw&cao@YAsGc@{Vw_h0_LQk-# zlV`W<<6N*+-9utuxfagkhVq*y;q;JL5L|#Hao6ViSU7@a)n-;>x4&#-?SI)uYA)N= z$BHBSwDmDk>jKiL@6d*Ch7KMMp53k`e#3GxU8$c;JypeeGVvYqkmzCgyUr~+{>j)T z=_D`jJErPAoq03h4rz~d>{t-2@8!_~3^~fBFwb zt!oZtf&>Vs7x)8HIsRfE*qGumPxK4?x1Xru^~FrRI!LFN_*C!$rk2hVy%!IO-Ju0Y zYAW}Tm~ry&WyZXME2s;sN7A(53Zw=?EMTv*E z7a++>@{pJx(qa8E&>`}dXkh-|3p~#-FJNL*pMTrtP71_dqEvH&)2c;@N3DBETs_nhVZXvk&H6u+rE= za?Hz0e3DKShS$Q$^D{lzE2#iU;;sV#bLA+SrgL3rI+DLaD>fe%Fu8i!fBQ*( z!Tt8BM(|97r*NPD_Kcwg)v53Lwouwhn{$)5DrgREIPB6xw)aTREq%t#>SMzmNzZb0 zv2;c>4i;&-0wymP)X&h44KD>cv1&}uah}`{?J-a6$I^G`M7zsFVsN_vN!2O-FfZIv z=`rI5=Q2N8A0BgJ(%NFCNCPjX$6PSu<}p`%E(@5Lf$*5zs^Bpb0mwahk|n#MA{8oF zV(#fYG5b=$oMh8@%oK^jd3sE)81$Hlsep-i*B%&CHWfb$)hkGqd_$tQA>a03V)n(8 z*_~hym6*`+RARW#L!y_Z)yML|l)WbNC&g&zl=7an4_rq?sFB`({mUB-AOHNXfB*a6{@Z{4 zuYda=fBfVBf%oSM?k@l?f9?T)A>JmGA~Aa@{_Fwz3yAxlCo{efe+x$b>=?fZO8phY zKlcFt3gVw@$}hwmvtmppumWSOG=5Wi_C@0Hb+doQnDOV<%NOGP%Bio;hM9nz>kt2CrRNuw9`VoJ@xOvd%=xXb zenI}W4gG?&H+=mjUjK#YiToyf`30%(V-mb% zXINus{ifXauTVMu+-drP)LLUrtpG^6v^2h(+ww)^v`4vp=s7iv;P%Dk|3?nql4hN z^%AuIdGXV4-)*0rJ(F~v*{!cm>hju!@|zm|uMhWfep1v$OXWA!KVL*@M09Vx2qo?M z%JL9ZWEB)3|GaqWi#@kMs8r0k(kr3alhQWOmRf0?-&DbWeYm|l=hl69&VC>K z?DxUXZ>G?Goup32WMNEB|0xKnUFPow3Vu=P1wBnU&s1uSett8@>5EDY8Dq8EEV#a@ z82X}8>!E8Qj@#>aVcJn6uEcMTNZ}0q>|FhM%D^3w^g%8RMIIE?-n?h7U{;>ZdHWDsabt_&3e| zUmtE6J}~L%zx$inXJ15WK~L3C_j@}o5=$>b=t5~Xe6V*SZS*lHC!s~CJ)1YanIZQj zLH_1UD!?j0qHB^3bCNyF$TEUw(=uz4HR!kn7q5?W@W!5WFsnelgOo7rBHGKgzYpdIDRJy9k6)I55SKPi)p%FKO`Z2_ut)ddzRy?0@@uEluC`+5aU>tW+(W=QqPYf1}f% zCl>Y>=tS?ffcedk(%-(_^ZlDn=HD>&d1mQryUbtTbaDSir~dZqn<2WtVg5FN>xXrB z*Ea*6egoCcXzD@xjr;`1$jDDZ#D)!yBq-YLytE3lo%hv*`!h}*>kC%?v0(*_x1EpJ zd0^#l5ij-F9qBvIh3R#hk9{RV3tzuuR;2)%ncN_z>HM~5`U4m5x8XlO6w?gqX^(Fl z=Qm>lzqFJNIv?jZ>t+8E<~M_2e#6v~pOOZ6p8Rb}0Ro6q0W%uv`G($!19$6BjuqNx z^!R~iU%*76FJQJiOvicQ!|dt2NItb=msU9nlMVgSre%{d$? z6`^~Szq@;s$`1JU0+}S9IstklJ_KayqP1XBVnipf^2AYE$RFo7W68cGsX`_>^M&L5 zX71!~bZRaC-Prsu%z`LkKFqTS%aIF)-FGwYzrMW!`pp`XzXpn~x0lfQLO?vbQ79mO zE{D{h=jTLqcg3VqYB^Rd`5)S33MQF$UZAo9o8I_D4(-=(IFdvQR0ea<*IU0kkd#~X zkeCN4KvKS<07*tz0kWSx-%O{U}6rvz@w9j=L&RwGaC5o9u+V#T3`5f z9Bt+4oFD4MFJNYU^>d`fe|suhA!1pe6FZ6vm{=EH`1Za3ZlD_~-WZ2=R@xiw}&7?en=V3KW9z{H}y0w!jB3Ya+6w}6>Kv1k2Rz|16yeoQjH z3v|X$Xr~j$@fPUB3`GI+oAvTvc8JGJ-WY7}3MNK_Yz+8Xu$#3&CkBHGm>Xr#3Ya+c zwt$KDdy(^d`O9jktHq3qL&k82h z!F$ZqoWWaM!K7eq1rsaoY$p0zv8&nZkQL`w6)-XCU%Dg0raA)RQdeu z)qK871<;)*)cDWe(ORxhijz<(pcmSAh0mW9tS(TRt{;dFR6y}*s(|9idvB9un+IKe zZIh&0hEBAA*>5|gG!SAVh4aK%Xa$qvfy=L~m`X}tJaMIfI+8wz_=x`gq&wSX^j?$K zEu+C~m(dI@YM0Sql8sy75mv+&FmV=A1rwhTtD7=Ui{f_$I$s#twD6 zIzCX$zZ$}nz8fo69PX!eMN)4_sRjSej}2o^g)`lMP%b13QO4e0cNa)HP+KGyNK*9$ zNU|9VklkgGBePN9jq_AuDy<@#-|V;liZd2K<9&i*TLI-rxGs+y#|tJ?rmeu&`zI-$ z0*F%ulT0RE$~Mx04Rls8v5YV0?H;7_n~n6piG2Z+6q61)jT3_o1x!rQ`T3ryWCOnI z@}qHL^Kn7uad}4t^M$*4(cQEyKjX}n`{ziT-gJ~$FnKecOz!#cHxr8ubzA2+F&^e` zW`q-NQ2`SR82!z>a3hM>Aepn!{%U4`Gn}Uu&kO4p{Vlq7suL=ZNfwybbBQX$X;v^P zB;apmHfn+-6>bssW)$ee(IN#parbB8W@38IYml^NfGlZ|A0N6!UOc(mqk>6QSN_v+ znvz#ahK+!{9R9#xQ>o}vNKqd)Nh0OjS`WP=<_VL1HpLE&1Qp#o^P;_1?%@6U& zzw8sc*8R&qaRZGO`H4Xg|GZ7?JM?7Yi1h*_T_S(kd89-E^PpFwaEY)qrf`We0pa;2 z@~?1qcF|?m*23g0ln#PS?BXn(Ck87cg;JmcH!SazmzU0TUP4dKMjYhdd-kRSMS$xb z;pIb|Ooh<<$evP&+DJ)bA8P*+C^26jX$Wmk)ZAZBPKlS&{e!DRDo45!^9x6cb;T7z zvFg19`UdlHdq&|%F%MGtdNiggQhHG6twJgGkQ9y-lME$7$(E{s_E*D3MWyQQS?d>$ zlslUB^Atkqajr;d|J;@wDRwCoj&!z1C9-20CvX;|biti=B~W6%KhgygBNal^Irw~? z3R1e@M3@St8;wON9BF?mW~8*g)HtA6Yg{=}+@w-CQk=3=B9tEIij?-xU=5#e2y5X; zGrRryj#iEoqkJV$3UZb}iTQ;i#hhD(Q0#54Na=im`Rj*95BMWplVop~(iIE23w&B} z5kv*FJ(IcI%f(+fQd|&OkkWMQyg(@yN*APbyT7hEXteH>GN=etf37eRg~`Igk?s^U zs(d|;7^_GrPE4*)is9nIkzVb+P~kn!b}oJW8_dVz?!uAc6za;?W5swuO1ETK+Evts z;bMQJ+vkO#(U$Q|{a+vV=><@-%nC<}dvyv@%G={AQo6mtd<+*CjufjoDo46gF-r-Q zf<_h4gDkVckscH@DiKPSSw%{Ds*8{8ZWt~u94RhVsvPN{Vuljv8_dU2mco$^iW^kE ze$wMykkTDD$rUI~v>e_%f24c=$ild|{WA-1&=;7$aq63h!}US4B#3HbsR} z3>O!Ulvk2^rN8e~X;k@o93Ni-CCjXEq}W7KAruGQSEMu*eC?+Gj^X0Mk&YLFM(H2w z_n!9gLN0g5jctV^oz#a{k= z94XEesSvtRMyDdBI8~%VDTa#+M~W-^Dun*phTfbiIIv}*LTTn=KEHW|BRwf@P$HBb z=Zch$7b1qK1_U#raHKd4w{oN})PV2l@9j4uG7Pu>NZ+UdPYX!=gQtsMkkYe%3;VL4 z7%uiwnvzvuQ$b44H)_C7tO2i3x)JjWNBTw$__FBJ_oz z(TO$S6-qM^`B_C3jcQ` z3h&>j0UuZcUZ6Cg7%(IJk@7I_5}}mND@bX^D)zh1Jc7D#r0WZnM(KX&e@S>)c7^#k zEvj&&Z`6P%n+Hc)k<#N0=3}_HaHQu8l}1@q1J+(eps)tK1WL>=9O)Z1;3E&|vk6&| z(icXC>;uEag(JlgWCh-5VrleJ~ zk-kv_K4X^mOX&+ELz2#FpBfR&{xY+GQl*g>sN;h*;3ZIEzLwGuN^ye{q4YTW7yrm8 zM^MleN^xXJ;Yc@XPpc66LJfFox87hrj?yn2=?gXB#|LY`D^mKx$dKcM;o`!PUj0F% z5K5Is7175U@Cqo73@IGx3pLDIDnwHQ>jBHQ*H~ePLusO7)5Pg(KbjgGM2gDvc@vg*D(6P#hUjIMNqtz|&Ge zmRUtgUl9O>0xX>>$Ewa4KC+Mmt~C^5fqq%YKf-#t2Tqy;I>Jg@#YZ^dx2 zKhkxfxIsZftuNGoA1l^?S185RorNQPp$7a|u?D;%r7w&O$rz6IGP7X55Hwm}r~yA# ztO2h`>2WjnsZpaKr7z3@KUS;(uSn?&BST_BQTIpTNC&m2Re1kG4S2quB8C-8ab!s0 zNMEP{KeD3*9_NCTZZC`sIW`Oz`y)+hF+?~Dyx(4^0Z+V;mL^sx#gQR}BYj~G__1LP zctuKI7#VVG7%naxX(DmYPhN%hFVuh^8`gkVD8-Q>g(H2T20YddS!NX}ePLwCv0=El zaHQjfpwae14fv6rH!s{L92rtL(idvL6Wk)ptRSWP3nN309mB=`NE0rF2uDFfWyEs7 z8Ijq&`Mf7br$Q-?3@IGx3pLh8T__1RRc!AP{%)pHBM|!+a1Ae63 zB$Pb8Bn2rwUKkk?t=C^>mVha+slxjgYQT>;`S9jdD8-Q>1u1=@2K>k~3YJ+#N?#Zm zavT^gE*xnlB|YEK3h!U20Y46`0k2SsBSQ*D`a%tOM!At?R*}*dMur>*hKmbFI;lOa z!uvOBz)!3JFHm~o$Pj;|=NmQPC)R)$q%@X3DCo+OVz{_)q${(6)AmT zWXN%1xVUhnli~&i-d}IjfL~YxUZRxDa(|@P8#Uk;&H*n->Gi_MkmJH|ap6ceiW^jT z|3(dX=6Ur;BQ6{nQaI8#YQQh70k25u3nN2Pt$kDS6f-Lv>G?vX(e*|R_=Pp#mHUJv zLkdUwMh*CdHQ*H~ePLussx2sD=#O-y+x1!U3%t)fuYR>Rum-$BDUJ*&9O)Z1-~(&G z3sO2>7#VV8Z~!pBaHJdcCRTX=Mh*DD8t@XOWR@3>^o<(ufi>V2DScsN$T2WnTsYEL z(EYmfjT-Q@`u69Z2969V9O)Z1;7N`{9IhaxndjBd{E6XWf21?L^X*bP->3nfSOZ?r zr4!di7LN3d8t{oV;1wx-V`Rw0aB<;CQ)SmLrEk=LPpkp2NGXmCDIDn=HQ*C#z$;Sv z#>kL_OX1Bc9BKUVekpyU20Z@g3-<{}h7^wUjT-QYHQ-)KvqP$%`AK9`#84k;Fez@} zHB>;U%&Y|3pUXWzI5MPgq%YKfhfuQ2DpLBw$dL1c;o`!P?i4qu2-FKT;HeAg&*cV` zm|r;37iz#$!9tcGNf>% zFVukFTe9IuD^mKx$dGfzaB<;C(@)g?;;%2%fS;M?)t=4^C^5fqq%YKfXYD#!W)&%Y zVPr_SL=nTnkxuGOtZ1kgYQWDGYrqSXZa6Z;AL;f&4fwfX4R}FHbdZ!jZmE1AcB;174BR7ebX4fvUPUN0OejtnUr=?gXBX>=ybtRkf^j0`z< z3>O!UG~eGZr7zTgpF7ro7he1wM}`!R^o1JmbH^I+ij=-EGUVJbTwFNPl!UcQY36zL ztGxqjzzb5E9a>SK=!jZ;#?3dCPYQWEoZ++oNab!s0 zNMEP{&)1V>R*}*dMuwaRhKmbFdQ#k=qM=@>0Y6h?_riU`ks*a6eW3>YOc4WEW)&%Y zVPr@K!cxT0AL;pdq0;DlqXs1^M#QiXM$!xY2ipS ztiS!mKi{YUKd}b9p!H+x_aEsSHQ;&j;U%d^=?f!6G9!#4h6O3jSf73=eWM0Eaf27` z6OIfi9O)Z1;4#eLB`HYh^}@)IGxNNFQh%h$y}%tUXsGLr8t@Biz)O@8^HbgS4}bj2 zzx_Xd`{N(~_)q`tpZ@(n{l`E4*FXHvKmPe&|Ni&C{kQ-8U;p+${`kjS^MC%gfBD;g z`1{}g```ZMkAGa^K9D-8pbnh1T0-6FF)g7^Dm1L1&W*AVCDeyNu+WoCSY1*rv zS*4ZWwV@I$5lVNpa-^6#I5*FHEV`?F{-mr~fls)mt3YT{@Nl2*zsviyV<4dd%8lQ* zyJbm5f66mzKS=lgiV9dtvHqk$>7=)>qWQB)l4Q!;YS(d5PjQ9T=sr-WhnN4ezkvTr zavKQs?7z$To?nyFk>VVYw4mvWnglNhmG>%QPtpNgIdpkZ2X@3%D8&Ivp8W$mVhXZ9 zw*Hqdv)F+51!E%l1GrEXP&Cjhptwc00(w!>e7nA(u5v%iCLoLG!k(5qRz0is#~eZlt`7y3TlSQ%M80iRz2B{{8t9;8z%pl7>H zJ+A)t-C)u?U6Io4Go;i`~hH(gVtDc4m#8dCK>A$OsaLQV3PS?z{G1>!6Y7e5zX{FjMJ4+@v*L;F28>C z6jfSQ8?4EMB~;Yfr3fent4g4Bqe`G;tZ5x}Ppx8Em5T2MrSPw|00W9yii)IWa#j0t zvVK+^5s+AxKGqEzrG1)m{UrAX&vcg1Yg%_45#jHDN`8S?6->HR6-)~K6fkj;MFo?R z$rVg8&nnWCMV=w$={?c)32R1Plb?G3Q)NmA6vs>zR9~8}LGTNd{=k{aKb4=KYA2wy zqNGo(&nThd*o_M6h0Eefs5q~*g39^i5-J9jDyZ{?XAw4aIT)z zBi)$*T3}WN_7kZU)ProHiU^#T1FN9s*@DDkL9Vib8_YJ{0JJVCDFz9sP` zSn2aCl;U{M!kMP5uAln@`*SOTI&e&21vUFKL8wZoIEtx+is||SYT^L5hI@3eyb4@D ze6I?q%R+(R$_Xs|UKMCfe5v0f%4l>7TU1V9om5+0LET;`T3*-fjd0+aR`nOSl|g4O z+^vje0;OHy)`6>5N~pLTqJo-ZeSupiKHC*qFWduILVd#=&WeN=%;7aH<}Yw-ykQQn z6V2fYw>WuQK+SM-DmE&i;xvc~D(^5Wp zHrRtkV^FBA0*b1-0E)ww?)a{=0QMzgRv^x%`xw_f0WmsMAG_KUWudf)?qf`d1!ICf zES`l2)EQK80a8m%S&PH}HLo z5mS7nbsuBml$j0jY^f%}AFILf=LZ976>8Y-OW{cwUEiHjk=-2D04ALWg zQUay?mw*1x%msizRRt6)j4F&m>qlFZSp!1xqzWc^eHBbHB`TN{p75CIUxpi6!MrVx zC*!PwNm5@B&=r^HRR|?FszN9((JK(jZbbBqb0W?>l3+hp2&HUCy18$1boPqtk62%=z};j5D)Iw@U?^qO|T7+m%_cR z*;_=8@2^m^L|t&mc7a=2p-no=KZOA$rLEuWU^1&Trxr}k6bMBfSUFMLd|Dy2-(0&Q z*>Fz_gkrXl2l7-n(UpAk(uq>;yg(?HxfR=aL(jaBG`e;SA(l|z==8jH?DQ;T z_tW4)dasb(zs`fa-9jry=6_Q*t|D3Kb%kfoC%Mw@O%JrrMhBA)wSbAkbSjvX->hJ^ zR}5Tf>;Mb0LMQR4B%;|-^K6+_P%}^s%%~D7w)a(3DtC+(te%k?oabXLfc~Jc$y>Z} zOZ#UgF;%9r7XZ=m9Sn!*JbpG+j^ma4%6Z?vHnOlFn!%>qhFwL)lr zI5JgOH1MrJ=nIuSA(Sk%3Zebs$n2$W4@cg+?q9e}N4sYlLg_8>_19_XCc&?OV(oDS z6gS=!KvO3O%=aygSxiW-`P4nqBXxo=P@017=ZB>7`MBiV+dLzoX88OPC};Nc^Rx^) z(+Z_8)Cp$G4S75zN=Z%&p!W)eXE`l_Qq;Tz%4Vb%sYJNJjIL0MC1cC40n09Oe)k-b z9ld|-?x1yCINq*s1X-UAw0gVe!t7=RlWMUlm~{ConEh7IHAtQ+bdrv$VB({n2TWe3 z@u9cG6B?NZWm3VUEL6eb$*hrnLRTWR@bQ=~^Nj&1<)U|_KqyXHs$i0jTlx4b%YA zUR3>6A@l`nJiU|stWR@7`>nrA=|M)l7n-_1aBV&72m0Uz){hKfd;aJ!aP z!hpM#(HoNzBl<)Gy53*+6wE9Tigno)LU-~Q3xwjB%?hCjKDD3diCGc*gogF)0f-xu zT=2?eY7an!P!2$Ziz?5w<nVg{aZQ0u|GOKkSCuR{9I9|b7i?-R zunFsRDkq8?B?^RI{d#n{DCS!E_>4yB)}sq{$rcD*Ga#UwP+ovgA+&w8{`Se@aWEZq znk}H&P2PT@IBTPzN!Iqd{Cqst{!M{UTuxFTbdNROF8F(Ub95?_u{qkGXoir|$J_Kx2yHJSyfLZvrEo#_ zlhT2O6FupvugECQQY{dQ-3S#zaSl#_P~4YSAoResmY&c9=MxuX^uR?|m9Iw=zwq@q zPOn1f3vR=KZbRYYv7NVIlpGi$ED(xwsS7r4_Ctd;ULX|bEEL2kJ96Q<^Ms}<6Wp5$ zq1f6{0o`8s`VGI{yA3H!gh+0IO$V8I6-wnxyja*mYU>cnoD$2yLGmynU|i1q=UbAB7S^aTH47)?XZU^m)tJ4<2Q1_D}-XOpg<^g92WFw zHgkgET>1JJf(7G^V8M7HSTHbHP+&baa}_MIj8bdY%@Y?*7sP44kibZpO22NNzcwoM zR#iko>4N4%WbsSN=z#SFRWj4q@f^nXf-sCEn{ zRy*n#einYU#|naZtDmO}>eW-KN9pS|>w`%SqYsiTA8a%(5PFb|`kIm@@hrIY1wyfw zs=|8Q(q14GYpDt+nj;M*Pl8{Nr)6nRur9nwy`b}!jXXxrrlmgsu`DkHATscc{F}nZ zzYu`P8$u>ofzS&L9Uat&*poOFRLRmGfQWtHAAnfa{s2TUDFEU9n`Or#e?Yey5h6!pGy}(1P4&@oE2wzEDe*J%uDr6*i$`UtrUu4zU88(i{kGs3&yG z8~S`fD}>@Y#R8!#U8V}5?UP?}o;dlXLMT=i6iyTeg;xm0Vc7*juYNCd!)C6^$78iZ z;p4HHt3c?E)e4@_j41)_R3Wr|5aqU{LJ0zIzDg%e>tx{Ax5l%X6u!RTh3*+8 z^!$nx%$)c^7QGZVL^e`ey1Ndf1A+#filr68km!9no7j2iX;}tNX{iv3?Gj!_2L>PtmuYMiDk%_(qh||IjqySN zA~r6(B889dUwxL9GA{%m1_mH1T*6wa!n-`NTEVj^(`4FB$B8YRg=aYj+U_;X3_p3+ z_Z33>C%-Hc+d>N}k2kVbzW!>TDYDFq9L5TvI8mi=nNp1n@}y&#DOMm~L=zg!c84*T zloIk>T0iaExe{_jo1{W$e+%dO;TBHqh2E3CK#x|wzCY}k@nLwGw1uCRJNo*LUB(` z1(R~NK5eX^`8`Ebi>^@70}~_ugBdt6+%yn=@jG%-J1%bgLq#c^ab~3WB0}z zI@=4bNaAjwNeW!b5K2(ao=a(r1Wi&Q6kU;ma?Zd=ptSJy`~7u~I?v0~e)b#A$=Slk zS56eiycJG#w3m9Wdse+YbE#mIr1qu%GNF6p(>Lq!!n}q!4gDrr=CQ$v{t9-w^4T@Z zC4l)A)Dz1}N~pNCqJqlP&Pu4*hf+ettV0EL;NG(m>P6Om1$E+3r4lM`K`NkTm^-~H zB~*M=OQ<+Lw1T=|t!4=oz32*RR)h3w!fnMWs|u~#hq{GJsQdkXKACGJRI~&tsA(O1 zfm=JS0j$t^Br@55t_OO*6C_DEnE=-a@^Nnr7G@huOlUBaBWjQZ4Y5^ zBJo!zh9fqe`Sc=GP*Xrb47=M~B&{oMq*)@=8niv*Jysm|P$9H`2zCgic`PMDNe>oS zkJ+CJp}1wZLMZ8!5~1y>)Uo2I@(Q6?C|fvD^auaIf^GDEpEH-e1_qQK7Vd>g2d^ z?L~q2*Vb=AW{4@sQ{_YtdPpj~#}SbgO0$>e*(vqc=|bPJ!u$T!xZ}b`j>?H*Cuo89 z1NZF~C`}a!h`#52!Vw@(1>UD&7s3VwLNS$4IZ+%fU*SE@lBiJH-wQgp7qr5A451fz zk4{eIM6>wznjj`md6{9t`g zf%h3B({1Nxpu}x>Jiemyvf068mGMYFy8K{n*eS8BUh{1ix%dS^-EbjY1r&P_e5uIX zGN{GKzCwOh4(wfxJsbZcUl3(*$ovb#fjDxO0gxTLTQFt zKVQ;<>|eyE3MLiXR74;18WqsI`Oha>;XNic3ZNHm+9-jNKoz9)!W2w}(#-yPW>kez z9D3(vKjrE`Xa$oLbV2mfI|s_70{TMr+PtuOts+nu;63kgsDNViUI~MqBLMc}9Xo0#xDaKO*rQmKwN_Vn&DwH1N>QpFgF9;5wupqc_ zpRkj%BKj9Sq!rNqDxMrE_GeZE3M-c@pg2ITAf*eg+A2`GeA+G3{j=a=ZZG>wwvRm9 zW(7>#-&GL(1&7{NKyleth4)y+Qv#(JPYINK(#n0p{?rPkCuK`2l(x?{${oeoMuq!? z`$sCGKgi&zfc97MH30Yy0s6X%Gbw# ze%2=bK5f`hRuO$1>0SZtuj0v(ViiwCpfJW$0;S+?;eFb0Sx|-23}Si~(+Z`yg{L6< zNoqY4TEQd*T@d|Lf_Epi0@+{1bAwV9PeGtk8q=M54yCxawIHSYMvSU_{`P`px@T2Z zx9smYxZK~T9XrY@_X+2Lmq3Y472abNPYJZW5+EJ{+^E{s$q zRF&H8HT>WAFlDQ5#7NJ%ahCVXZVsj!P*T>;p|Kdjq|C|iZa3V8*Lh-fL@{EY59UA ze4{xY#Y@+B4T49}u0e{Wl^t~yKJ9F0D)|1>dtqzupU{$mtWb*U)AyhyP&Q4<+*1{g z1j=$e0x0~6ET)2&?zC%=VrjZyXS(C{>ib)sIG^^7&69%37HGlsA>Si&uYj)aGGA`! zK}IZ99E#?6Bv9s13ZH1#AjQ)4FLYs|X!Cl(_vs5=3MQ*4Q(T`m*_S}s0YaGjPE|Y- z=mkmmzP@V^w2QQBkn;H(OTr7x@0sOH+UnsWHN2DcN=~h)ig;I_L zR|z%GVY`>2kx=PnhlGlkw$|H z)tz-{lWe6eI~3GLuaUPjqI;Lr8cPF7wo;Lsf(i-A1wOEsE7sSYmPtt?zzcAMb)eIC z=M-DfMfrl+!Xu^^L_<6gctJEAv{j=ru7k^m1s_01p!KtbE#U?0D+FqdD5VvguexD0qkERBa=KFrjo^HLCX zr!NXfs5I#;q;gS|#+*N%9|!1quR`Nm!hFS0T9X)e|DKk=y^YYnURVcAnz_MlKIr=$ zy$$ZCErb!Jt=g5Tr$wHMq3rrjGL&u61Vd@VvFRGosi*zl<2RyPuXF!-Hx+sdUkYuV zwz5*zQe^Dd@pt-1a99Ty!-OAVE!&_e5MczcKV^$_`1^s$LcfAZ6BY3>1*g~sO&U}B zOo{OQogI1SWTr}f2-z~o!LaIQM1 z&Za-^Qi(s89NwYe5iNFvoWh>qJZ*F%DS@&fRY2)$;R-0dSW`f0W<~*}30eh|-qR?c zJ4>W0p!7i%1(d#TD}dr=oh+vc=u-%~x0_Tzsi<55r8WKvD7~juKxv{+0j2qV1(fc2 z6;S$Eg#t>u4ho=XzqOuG1-Bjd&u5CIRInT0OB9-vQ!rWa_zd8|twf<0Jqji}nJAbn z$v46|gk0zw2!f%F-JU9#EYqXR{Q6FIh$1YE3Lj5Tq{7FeWdzCZ#tp6OpFhZWkB}sJ z1h=pBRRQ7SX~Q`MljS0nk1uSaD;P@84hkkajwv5cj}C&Njk&0RNh^_+k6->2W671a z=@&kJu#|!D@n{pWe8FodceuYBi+?;Ga$mpT;T;VEDj1rXnn%H8mw7^{YZoN-8cpg6 zA5R}lRNS7cdgJN0Mtju9FWz!Pb?bdHDWFtrB7w54xCF{5s({jitpv*UxDqH^N(IpU zfVGz*Lj;;m@EZz;L;*L1W8Xo>* zfm^V)ZS;_?Oj*N`W%>FA&`U-Z?^0hevUskIoCXr!u#K*^=t;#Ae-bQGlxz^L!zzAd7 zGdsTumhyKXl`*9+A>s+b_)PISZvhoAf0Nih>uQ5eg--Fr0TfU?l5yXw;`2XFgnj|F zvoNh-vb=5TVN}%0EKk`3b2(2tgdW79gm0%YO2MQ$+$fpw?QDah*h!CQWvgLR@gmyt zX_|uR`?Qbe?0cqZtN55^SbE>kxNxYWSvDEb_?8!-%%c=bscKFb(#oy@;+IuD)2kK1 zQ2zWcrZE;pdqz)-`wpedeP@|fW$w|>;l8E9kkaNO!rYg{zCLa!p4lP`lrW;GXM!bn zx6pBiDzpoiVkzB12}4Tjj)XP8&~}u9p;X+^8E(mb3nq76^#E}#2$V@s)GDNXLh=f2VVO@a4#6KMIG z-{_m7%82qi$oO85%jXnJ8$03(b5E0{%G^^?nqVjuI4C1}fqbmvVGOc~5G>u-zpB}} z&`X$mJYPe;K0fz5eg9G!QJN(e;yuJYWD}uSO7ES8A+2mJ5#s$$yZ;G>@>eC}%QKX? z#7UL8$IBS^HxbI*3eO6Hc zrPWaiC>2~OpzVU33HttBFi{Yk-S>Uv^9M_s2%soDT7PmL^l3fC((Qti^T=$GQY>qt&9RnH~R`GI<+r%{y|R=ilzL4weVH~9iP|dq6S)NlNc5M{DE8i4QbjRB1( z;ivHN^zfj}JiX8m45eoW1(O}egqh#g>z@ajqAs8L?SdprsAb|E%^R4DI?08zeE>md_FCpRxI6F?2qnzVQ6OypMuE}Tng`LBSi^x z`DU`-a6lnmD!4xHX)l2?hZ4LLWzH9TKD{DVETxU|5QowBY)cYC|MY zc7PD(zS0bj1iCyMjZ$Y?MXPuz;`4ovQa-<2ursY_$9vyW!S|`WT)|{FW{T@`$$I?! zRH>3hnfsmT1QgKDay$|!b0~#R^oc>iQm7Be?nJPZKbH~reH?R%p$aBd!N*;{Jzd+} z3#0-`8|^-&%ss6vkU&|EM**chtrRb%&xI(K(*9G5rHvgS1mACLo)k>BKr61lvki{| zy1r2sn!C_OS&BogFZYI}wA@?pQeK)Zd_I4JL$Q>;Y!UZ;^eqW9FGFpSaMhKQamnme}z^orR7SBrJWri;_(T4eX@;GFxf4s;`)OHQUMgT zx#a7Gxkr5}3Hb_WVmTfOlsS~(rDJ0grC3T^j4PJnKKnlNWjP+jQreG0@lx7-PqDN!d5B^ueWyk6{pAhT>ut~m>v2Az zdjJch3g`tYp2VAx#2pHtEXN~(vZGGiOVcg0iBc@3PxL63R<<(@^C{tu9Dj6gg;p@x z0GKUiQgd#mcQpHl*<3_Qxv7D*k`?PDn zg2@(W#r0|990l|O6%UBNJ_!#{mg7;pls;OJ;#I$Cqt~QQxs_NkZQAgz%>7s@q4Fo{ zXC5eMD^xdZNl{Sw;;*36&RNR1W?HJLpcbA!6h;6Uqzh)N(564q2yg+4Fappt}CB%K_1+&#VO??aFI_QyA@vOlQLyE2Z6)y#qUU~{6u-%^i=w2F3LZ#jM zBvdM!l~B1LGd^1z&IRkag}ycH04H>ALvoc?o(ipta4ukK5_GqTZs9ka-^svAsI+-g z__V#DV2D_nlJNb5Z3zWS`Ehd&dhD=;rj_irHg0L7y;_wqMP*z^VafX~g$H0zZSoK>*`O+zELJI) z>>gCXWTy)OlhRbdWOF3AC=y~!{~)2##%&TR4^vxsq0ZQ;u@hT3_Cch@qI5hf3{b`> z36$+p;%ih+v~Q~f$`Z}-tDDR(nFNob-me%+50!$U7s!Y+Qfp*0As9;Un3NIiY}X?g zO0Sp{Oty>y3wY(3MNbZDIZVsse+-jW1)h{B9ns2b|wnu z1tEk#ccIKY&3RA3e(Xe+`8yH{C<;*TAIOxw9xA3t6p>IXtw^ZxVa>EB)YEzsoUB6o zB0cqxh@$Q+JKy58f>4J{mV(K|8Um}ZFDYhAvEe`{v`0eR(2I3OcU)4qp*p# z6c(1}y0a@2;p=II&&xQpP8$T@dga zJvs}-M`N7j0l!@l@X>6C1pFKidD!a_P+^JMd2kLBf2Y@a!X65FDDw63)nvaS1-ox7 zZ=y^SEff~ky`64NgdwF56G(=#gPyRM>}XVcKa>bxPn*^WNAkTfA);U?Ek0H-*`lY= zerJbKWhJFghA9-K1vjg232 z`URC;NEI`MyfCEn_4di(;8~n2qT+_)r8Kgb2y6bJ3T7c)Hm(qb%va%8?;i)fAykHx zo*jg_=fzxtlk&4eocDu1UoRX;#s#U;3tBAYQP>Vj$m(sDz2^kRnsCOh3rhBA>+ zJP%RON|wY6jGY$6&wiL|ucW&iIccm@7nv{g5 z{P(|J0ZlAfDENNjJ%8g9h5E16JIInQC{ieio^iAA^_8vA3MhX!BOae{dSJ`G06N&Z zA3x?{SIVeA;;SidG@^j6&+ni!HJzvMK4POC@ZwXy6}m4KKreX6vOr`*JU@OOEgRjI zE1)!xN}x29#2t#((Ft=u=*@8WG+s9P$bn)g3;6NFILe(V?cLPWwIT^4!qijU z&X&XFxJZ}L^iGOzbqjrs;3@AL%juU&9|#mg^#zheawgkqeC0z+MdAT_JRNhQL(`6b zH8`v%bbA8oe&Svuet_QTBUEu`#cNR{8>hHczp>R{LS3)nDV=I~;$zxrduk;ig;j;j z)QG!Or)7V0V-(~Re~=`eH7|n}Kq!{dtHK_>c`qZgM33V9gWehlsP(qdv&55vCguSU zG_W%-G&E7aLLC5GRl>dsOctsX%;g8kitH%~)bX89#o%)TX zQY27z3$K7uVS@z9l86#0+es;)8}of--Rq5Iy%bL!x8)j?dVx9=m@GcW*Asq>R501* zRKZ*yoA~paLRZI%C*#O2T0lj_V?G)`nFEwDzii=j2U^Fo5T&4QRND|QFly-c0$03u zB_)BfY~PdGGj@zX2UcdPf?DVc>4ICKHwVc~3!{qntjXE@NthcP)k?2Co(@_;RGd!8 z5+ID~PLKQwXr^49zYzR>)LF5OuiycLYP%#*CX`h`X%78K>>eA{{YK|XSOHL2&JI3t zw*n|T^(vrr^CzqTs8?qv3SkA<^G=&;gj2ISUZo++O59fg$~G2?SJfLcHIML}5AqWf zHN3L~DBGaAf^iYRd_1f zuf*MI&J;0K0lgwxcdo=%Ms?#aeujN@?p6q`;_E6vSzHmK6-tAduL|o5dKIw^yWmz3 z(~z^30!mZA!r>avJh2d9FhzkwDqbQdt28efvOQK)TWLm$+L&*}R?r0A&Oa zMm3>8k?et#QN7^i8fL7&xt^fxY^i*IrsrT`1wd1V zf;ii+#N7&@>o*n~GB#wpCV17hU9q!5g)bX`xLe_ZWqBg3ZKy0EqpEmSp@(Z>UEM0x zZV0}L3l>5v33PoX5IVb!t=7t1@qY7yukN&7M**eH;f4L`#%o}eQH3Oq@JetiR8|r} zgaS%;R>G*}8_fg?qnZ=H4U67eHGnd*#(fp5D%)8rql(@)WWOrJz+4jBS;XB6pv+VW zl*Lu$`}qxnkh98Yfk0LO!L8bQ{VHDZpm9~<>Rwr3RYtYbzGs44LAybwYOcE>r75K5 zRAmwF>JLz;*Y2km6;PUAS3aMvs)D6xtw1J90o_0C~A-T@ZfWnxL%8F~1&!;&c z1$1ZEi^}KIwo-9W^f_j;AOC!`BwkO`f?O5Z{VAVMUx1D~f4R|ar^=W@W4n6kLsp&9 zRQP<}K3D;zr+;Bg6Kw#afKnl(;HQa}fh(X?3a@-VZKNrHZZuCRxYR~FQY)Y|p(ae! zM)OI^m_h@zd_loe&198Q#*_v=;q$q!POvo7hhh{^dikk*K5eHK&LrS9UUraHFxlBe z!DODVV6udVg2|5i3MPyA0w#YYCVG4<`RUAkSDqtavK^%I?K6$B+D>-Uq1ee5W(AX- zaum!NA6JhjE20qWq|d#_dy}B6dt$3yxQ)sLUB8T!w0;@EtuWa;NJC0@&grRJYb?E0 zc3Sa?*S5oMRgvH!?mw5Xn5_V1@h>{ zHS?cA@^1(jWcn4dmM^g#HSjpDRYjona zLi5EOOW+oot1;z6+y~H7p6|8e>%fj4Fl-3oD*P?OPfjS11am0P+6bB|feo z0bO3g;|fp~4Ha&6{`!qDt|y+A5xCWH%f^R zt^nm{?l`x`hLT-E*|@D}vd0`t@Yhk$xoEkqCA0h1jBkkrZd7ZsY;JrN04O`dJ=L8A zO|5Ap)TeoEiIRxG90V~V9zS*cix4Bq-Nr5Ogr(w#=>c<68R z%r05VvO&u1(^IfwX=j(Cily{isaQ(iloc%9=}Aqn6k@COj6wr6vPD%aeR@3V-uYL^ zvg4r6OcipW&Y9KLCLZzA;Wn6J*LGFSSTg%2y{}L+oS7ihW zUT?gAuuwt(?<*vs(%Ud)Tu(f&J>pTI(Ov~{!Nq<%BfN?VF7_LqI=_Iidt-+d#RocH zUw1fkXwx>20_;BUsU9haiXMH+u7bC z#~C$fXGP)T2m5#hlSL{8lX<;@$<~rEChiMa5Onk(>*2nT7(cu(0!RCNhDBqSQf(5Mh{K#NHQNFxWAYxn5>I{FrpBNkyT&tQY@up z?uE6KzZoqIDb=znm@M(6d^|1oR_2~Ql^9?3@a_Up$O$7_nUY(vbA6U*qwg39JE)D` z4(56M4IUmcRYwY@;@C*mlK4F3r`K=pT{sM-+2%pPT)!@(keh5B6g$_ao-*weBiOmTGbDUzd1uIp$+q^& zx3lcMaIDMpT^ZrDlzCr-9{>JA`=c~rBhKGg7ZQ(^W=L^L4ev;>cOshyJd_qjMP~@I z9Tf(kt?vPz21dbLzd*MO?gsGu3GpZ4+o|U(n5?8o!DI`xa0G3%qDY}q zUB7i~b^X>6nz!ZK65hZ}n0cyERxsCZ9UDzID|TM6GSQ|oik%m%OjJQD*m*(r9&f#@ z=Mk--Q@)*Dh6&qIXeLQWnu8O}CxT{d4lCLpV`a{*PlCm)J+&so@o_8(T;HWh|*W06(6Ok4B_Lcj7Y&;e^7#%%QtvC zdRg6{cp=o`NeTk0a0#U$_bnA>X{=wG(RhyRMB{dL+T~oqydZtoA)UNGNy5x`C_e6k z3SUnpX$t20MHFRQ>%Hj$QFp&U)ZMA5TbU!qcwrab`McfWvuCGmmxYhd>>fbDq-W2# zgrZkgYZI@ogA$KfTH}`>IL(sy?4a}OB+1(R(_6-<`VQ83r%?gw7oSiRL5ojIxU z?QDmyV6xnO{N{Uf7VZT*>ATYLb1j;mFb9oy>H#QQNWxzaOty@KX9<{WZLZ-}6c2T? zsekI?9J>Y)31ywdNh+$PTZ*=X@Pg&`~0}` zU!arUHmZ}4?{;vwWy^^$_gi6$zG5kV77!6J$fu2N_2c3+G$&ua*8wJTQpr%ZF^TW= zVJVw@#nSax>)W>eY8{wtDHYZddbKXBdGz3@V6rV~_$-R?q)|j5J$+a$UJ8vHF}f)g zKA-k^7dCr%=71c<1%l#v&GmbTOt+AdrEI$wr)Z|Ptcszu6`5ivO&En^Xr^zcD0VJS zKw_K64iE7)517mMqx=;)VLVS%n8uf<3+gX66w;B^N%;Ep^%t;{EqH=A(K18j+Zp49 zrk2oZuuYzXO4ZF0>R`Lv_^6h__BskCOTWd-i?@p2ME4K3aW{pogiut7c9nLF6V4)) zcNK`wQ{9+iBd)m*laMQ`xNf@-nzs0M4?7-$D&z`L zD?`>O!A-G`BBxQ|>(^^H&{l#q7l?}j@HFBDsY1NOPUc>yH$@+N7NCTAf*OeUez@Bg z3}s7{;-&P?Q30jz4GKeg!EP5-;e?{X0^MloM0|m6>!qI?HYV$R6y+F#=rFL}OY@ChIfjpw_8PTW4YxhP}nERC36_H{oFUN{c6K#B@%st+#S?;8?Uym}P ze5W6e_lb%i6-x&TBm$jinUgU0TVi?rxS<=pBNIk++ZaU!-s2fOk}Ov&r6*@$NNFch zW$tmtU(NfCcAZy7bf;&MIPW)<48KUQF@=F%so}tDVDB(oDNgZa>c?KuUv2-K|YA= zAB7PuRAeN~eSz|Q`I=vlGP(~MkM{*@>3vLP?$`I6$b}wql)0z!9cAum(+S1WopDr{ zdwMsl%>7^-6$~Bhjzkzy$U?|sBFsHxA!MhkSh~LX0D4fQ2WZ7%C@P$s^JKI2~Ej|LBYn9`N5_HK}@BKZob6&i_Id|F;N&%%|PvB{% zj~NInN-u2TS1euMh8>&8^$8yIOSr&GslHYj(VZoDl)0w?TCtQCdJ0PvEm09LseDP{ zJxy&2pyP_2#GpF~!J$TCmoE}1Bfj9JxFaK53B^+SnyO+ct#gh0J|1CTe$pE>v#Yp1 z)W!FYj|ym`+o<@4XV84H;!uqp^A*tj0u{rcPl_s*UZAzfTx%onX|Q<;W8$pQrZ_NP84iJ*1OtKtb^^x6V6Qx*M*r8mpl(!3s9`wttvUw8t zM7uC3u20|6RX}MezB2ba%W+Ad>+iBr`NNJnikH$-I_2}n`kiS(;)Lu>8wvX}~9niHES#nN=a&NR~|7jfUu^vPBQla=QQu8&t> z$=pkzY?_q0uj`ZWCDR;_WGPGTDtx*?5nA#EiqL{bqsSU1_&!yHDws@frMNz=9~VHm zbXD+D^tB?2BL$S^cqCBfPy(OI#&$f4rL@C`Vks@ri~ByVbIE0ig2@(W#r3JmRsv-Q z2xac6ibn!vIUWg=9d#5hrLSHnmi7yFre(b#xD+Y~7WhOfDFxTBH>TcGKrc}7luGL} z1&69sxh#RQqmIC*O8X@#mgWm~rjo*oiB~Ug^%G^^Gj|95D zKDD4okDN&rKGFJA<@2G7yMF~ESlVuEXBzkYMtd76nCzBRaDBY}K;~Wny+Xxb~7x=WJQQH047c51eJmOM{rL;ad?)&@G3t9Ji8!4D(egV3g{Io zo_#PCkHROK;}Jk{d|JQi_r!KQilym-ooQeHlzX}0DR*G91zK=@RMn8VS3qf{mNNI{ zf+Rei3SPhJBKr60KTaXE$2v201 zgt^C|gm|e0%5ppkDDA)|cR6 z#WQGMH^rf7jz9>vlNx(4C-%=J6ddK>JhBQQUqGr|3diu*oZS0J|q3MRYE7F-`& z{pI-xXhYaE30{g8&csp)l;wC7&WWUeGnD;@Rj6KEJY~j>4zLcBX>wH+ESfVA6^*#r5f{ zX9_5P;TT)DSZ`=NZN5GU4^WolQTRl=20bM#g5QtIPqyDJ;dj{4eUTl?)8ui~*1_`d z3Tok327;}n&@I1$y0hS?i~#ayY*7_#t-O7bf{JGDB>pL=ylhE8h1{BPOF^Y?b}2s4 zc;gGjR{n~#fC@1y*{Uidu=7ojVr!%OH3gMkb|@pzc^X}?6?Nbj%vPszIcWsA5K9<= zvC-qIf=Uanlo7xtWBqJFFUj(Mg01aFTXsmO^cs0f;TPrGjXtWb*ot>M)QAS{+Wl|Cm+cx^{oMbC)w4tElmF4w&mzFcju}QYlR*e!Wmk$d*Fnd5Q z-@oD=(<|23a>XeQ#a$Pi;;_qN*K3Lo)GJPLtzL18!{zb?r?}RxIK{Pg#VHO_TAIrd z7`tC_ifj87r?|FXaf)mE6{olcJuz7c!^uowvYobq$#O0VCfm0um@Kv`m@JE>V6qEQ zG>L|1#FB%1qD=vxPPb81`l3KQle;In4-AhgFj>Y`$PS}?jB!*MR9rW$X8yj>_E^G1 zZDq!bdlJC-M4<@*`FP1trUy_AWgev%N?WxHhVsos_+Dt=r~*(il%9YELr*juLyjQ0 z?rrozI)(T-Gv8Mhsl2nBR>4v8`f?{EnE7fNo~cYXXK_c(^Z_kpL}}|C!BAS4B^k;N zsEVQVDkx5UH0>p!ByMP-+9F{@@i5c!I9k^CGD1gnwvs3V$`*YAGqKiK3MNY*D41-) zQ!v>PPl+MuJwei)3My`BNP0g0lKo!kE!`aSV7y2AjC{XhDb$ERmzH`w1J^wDQyd=Sc+<|`_8XeN+q?5rSw4s#Zs#IQ7j!S zoCub7TH`BN+UXOIily{ETCtRNM^h}NJ;xMF>3f8VrSzFU#Zp@5DOfsa7j(hWkytoU zETv7N6iew9q+%&;*{xVgTQ4b=(g)NOOR307v6Q|c7Pk~-d8~*mZfUR3T;7IR#F+$eSKyE+Id!(B3O$1calI9{B)y&CdE?PH$kyVKOR4xsv6Kph6id;!e*KtId9-3F z6$%MsI@{#k|9rtx{^*-xDJ{TKEXBK=_dj2;ls4K{ET!$M6-)69$ovmpL1tnvY%8f)O7+pon9`?Z6iaD~P{mUE(63@CE$0?2?ewi%!P36X zKe|`LpjcYiC6{6;eP2Yew6U$EVkvFEs8~vc+=``CbS+p4Op@*pEFH9TPqCEN@hg_n zmm3sIX`z{7DJ=?9ETvBZD3K&gjaRQu(c7>0pU&!O}$Kw}Pdp++EKoL=yt4Sc>i)_x&`(?V{rQ zfk%sot@&xY8PfFk+fG|zggpSD>yPIErN?u{(tSArU@7hFDOie9Lz3@PKxtZD0i_Rk zD4_IR3d z{X`|yTP~k{G#OjZD2Th(Gb&-1vi|e2OSu4aeZCLR{?dG(;QWcUSQ9{@#aKV4+xmOH z+5hMQMs4i^Mq!b>{r@mS+R8e1p>yDULXjTHu|2l0(wDa z0)164h*9l=%tXS=FzfxaU67eb=(NAy(*1(WL_$l|3oN}LGl4eP7sRN3L1rT1Y_@(( z`vsYa1bxc|mR^vVNYDzew-hy}7l2-onHX1OCQ!qE!RKF)nE;>GPZVAQWJ_PXcM(3G zR$i5iTZ`D8#FnTERk0PV0f+-AsQjrt36(#MCX8#Qkt*D_t>e`arkPbh=?!YeTn61L z(~3R?w6m^t3Mjqnl|Y%gSC}Ylr^&6P1j;&qN}zNBgc2a=QmB<7pC7(JM)xAB@KZj2 z{X5vObbUSN1Z4|~GN!bttTLu_m#TnL`G5q&wLYR%w}-VkxbTmq0IAO;I0A&XJ0xRD&+8QZ+MeZ+tnewBdk& zNt5!*$I~Q|GEIf;O%>4f&((vZv{$uaDK2`Jhdp!zB79PoXxgz;`TYHYsE^J7vgDOP>5o+y~?9zywe z+-=<-QDvHF7c2#oHvg1B*|AIkr6r-t8ijhB^%F&<(aPsj9l!GVS6prNE3URWz1mX7 zbX*Yi$BnI~f~6Qz;-|tYg>oAL8edK!3n!-?1(R(gq>sPg%7AykQs$nv{Z&9|@uCFE zvRo1} zRBh$k1yx%By<#=J;A$(Q>mgZA6xXL$Tgn=>GdEQ%-PvlYfYNSq%IDLoEy>dLd((_i zN{;%9rD)E2KkP}MEb0rZRH7wT@#S7u-X^OD~A} ziN3unET`ytcb`xS=6a1xo~`8W8>%?e1y@^nHfURKDSazY`F#3BvI07o>nm&21y@@* zJ+Hso0x0uS;q$i}yVVyaYD?@MN&;OkXvyeHx;{Wd7QLRP8-3g{LgmDA63XYN z_5I^AHm4VSKCJ~)K7V6=DlF0S` z(+dt}Nbi%+7Z_FOvn~=SOYth8v=~fSqS1$$IDdROEs43Qg2{3c%ExaPtfpw~Oh#0h zdz_(`uTkZSOE|pbM`FIPM3=%cyvmqfaS4Y){R=+-fVL7E2W(p?D@Jb(l#cE3L%M^#g<2%b83a2u%oCucI+Xa$_dSgLf zv6R+=NuVt13lR#-{spst#eG?&_hrhMUeM<-*9-a_0+jiwuu4^IQ0{X-zMNKC3#MSQ zW0~^t7j!wyD1Rp-s(2}VYE}YetEmLaj%5lcy)RQ1zMZY6X^T55CW@SQgcrwf++q3y z3AMAi626~idgksm_K*`EF=K-&fwEnn@bzQ;a@x2oTp3Y%xfKURmkP4<#Yc3%u?sT= zljbCpk7t)~f{*SumX1@tp518+nDq5h<>Tq|C=w`3$S7aG{R$>g+(T zeES7KiMEVU>|{Yn!Mxy5Lp$5d^hq$40iP#oedt%gWV=S?;|Du{383gVN#;KO^@BDyP!i3^ zV3K2@#NwNT+o-a)z81{Hcm zb}}jP!~qlmY}-56oS>npWBqT^P{Lwmu5x@@zz@ zv~|0%oIt5cg5LbU2WP$|#w7)mDz*fI@<(Ka1**}~`M4CQV1XtRC4nwKmX}7AKyf-X z+GtwAWQUWfW{Y}0?X)Z`q!5>okgs???KLcb?lgC#fYOR&36y!h0*cN4{k>WIG7B&D zup^YP?Bnv`0!z#Cv}u9rpDcTE=I`rMXJucXIs+zKp{Bb9S16qF$U$capft^;u&Fc0 zS3obQo-F(+y||P1^|CV9$@UP6oopo$c2J#ac7zQiUe+MlZNZ;9E%Z}BQ9gJ-jwqjB znVM9w^nyyaf=na{PQq5VQ(?edY=etwr$uQ3q40X{{mEA_=N@6HAf|NMZBlVkdKOne zX}d+i^G`hb6`v>mK$l`^V(Xr;LXQgyh{~V^M8f`=za}Nj6TN~_FxkdT!DJOA!b&h zt=k1hJfz9lMpxK9Z|j>xz)&VJQw*g|)#KL$6%sRY9#ba2u|1UHru52H0p)GAli;MN zZeH)C<$^2M${V%{#J{4qD!Pm@jaA&E%K9>N*vaNzv6Hb$*g_Ntmk33}IurD5W2ZcY zPFEbp3qOowVF(_^p@kwFNageC?Wi#O^@7LfD$Y4%F^&6vy|F#Hf=OLJJoUT>s1TiS z$|He9@F!dntano0u~D(KvQ4=H+L)7;cowdr?ackfRN?5(4tav>ukY+oD?Q)~cGAuc z%G6Vxwgh@X&ZOaa`1}4O?8{oZU^Qt}Qmt5uQ||rG7wFV7qmu%PH#F{B8u$HHn0`aS zWak_OljUKg0c9F>;o_;$`{uYrzc%{HkK*}|D&O}fVTo$=a#*qS0-<*0{XYelLeUEu z)41>NH?}oVFxmR7d_3)|DdY=x+O<#trKfShOQHWI>$AY8y|QDTVkxcg79^3c$Pot)#A zwi|tOR%p4^Znz=7AMzzsdPk_BCiDkeZ!4aVAVgJc-8OcoC!r#Dw0;Eg6)iFwn%G`2 zTeC;z{SiPxNA$L|m8Z$LcQ#jMtI(@G1r;~DWCSEs+K)s+rLRXRs10w=6CX&RNlYx! z(1(g}D;%PM3AK3Wbs*f9=t*~GM#X#&nQdp?42WHY1;X%eeXqrN>b?~y{ zFk6Ai(rF4N+g7CckH%;s-=?7Adg_7^D743;WGhbs3bR$IhC;EmUc#*@p;_;*aMvqPFX0yN zZ>-D~@A0dk?w4?j_fM5<<=hGCbkWfKv`x%0o~ZaN&=-POJSli%PK0C(g%PgP?lCyK&gmQ z0-cw@w^(tipjyH^Zn zKk@OjfpGX{d4jSfIxMOHC~dG5mVE(qu+*0TijIny-FwT40{V1ka1S)B(;3*Eu+JAJ ziq~HXYbh%E*#RvYOY!-%!;;|qvr72>?8m8JX~$aybNv!kapu4O?ZOfTVJeAt;mTu7 zJ$C@>boBZ)AN{)6njhco@S;Y6qdRSRD@@d$S%xd_QFvgK45@<2wDSrkWfQ(5bRh{R zrJ`J63$;_3ldwGR^ysL7QjL@1q&Pj^k50nmQ-PC$xqhF&Q!QG!z5}-pSDbJ=J>d%e z)H91t3Mdt$3r@PerV;Z*Pt9>B?X)kkg2@g}!lKuy0#68{ePK*2e-&9DgH#e{VJf99Ug== zAK7Q(`3flQ_N&kdZ^7OtzTo=w)U05xPeMU&K^8q_K3xIaM~#-=`Q zX~N53WK826O*eWsu6#aKGRLnou;x!o?#0o#O97NEQDHs-lXV+VFxmB>fJyJ#<2Mg! zrpfQmlHyOa+wYvk*a06WC#GLf=rq{LQTTi;CuE5dJRi&_6D5JJrxPZM1pK(`ryHY_ z^6`l|l(6XItqij0D-N~3-7ogf^o*-mS{a{|F{SU8#_zCGqV0YqP_{V{e1CasUd%mh z%`4bR+Y1ScJ|0XUOKCg{m(UJ|a8!sS+s2aG0-ZK`HSfR&sO{G8}oZSrVKSPX>@Jq!64?_d%9t#nPvC3HQ=)ily|F zE6@r3ZprKmS;#`${l-H{$t)Wo#Cvq+C0{QXN{{#oCM(SmPWXksgsXTyDsz{oHc|IM zE{PON=}Wl6DYxF(jl00nO0S0n*RN<&cz>eeZi+YM$vi2B()(e-P}-bUSf7!FBa4X; zNb3bs?Suzr*9X!{rP|7vu5Y6|5^mhd=PM+om(Ggsua{LPRHzU)75GHE5h$2!x2IsT z%%%`W(eM_Q+}rHM<=?3#_Vq%@L%=6fuYl4TZ(#@7sH$25WwRgmsCL2KIO@{KG%0qn z?Xz%EfMYY+Lnw5jN^QkSX_2o2IxYyKJAJoR@O(5QB@-3*sGZ*ADwu46QZU(;Tp7?S z4*1xXkbQ};gW9jS#@^`}SD@2QU#(R>pB{3BB?`@L37v!u*O{BEGQS>-3BpCu!g56=9g9oeHZ3JLz@1g30PUm6`8sg_@_J;3W|{gp*}Y07WUy z1)x*_u2`B`#wgw&dnCL)L$(nD>UK*kSsr%O4XXOpCsJV2v`N%WfqB6^Z8ut*r_2-N zwJcda2Pj6=4Hr&x zdisMuynOxY|HfZDVdE#CzWL^x$Jg%x{o?cA{o=ESpMSQM?cZL1`t$$%=$HTP;kS=p ze*D?nmtVg7_@j?L`t9SlZy(>`m!JOp;pOYE9zHw%;LY#x-*3M9?#uTNzk2!lyWhY3 z^8I&jr)j@@{rfj>zxn>J{^7G<{qi3HRzAMre`E7nK1#QbQvUIOGXGZ$7RK}IuV21@ z{OaL8%L-Xy6zy9@SFTVKh_rHI9`_Hc)|Aa68*T4Mjzh8WURql&FzkmFv$Jc*&|Hl`f zq+aXOJ3zxn;|pJw!Lzw`O~x39i>#P7`Nx|eVNFef{s|L6ACpT+RZKcb+H*&q~) z`q9X|qv&Qb;%Hj_EBx~NPygFzAHKD;wjs4Ye+6^&`1aMyufPAL*Dt@pXU-q~U(*G@ z{o?Jf9^b$G`s-I;{`SpxfB55TOw4r1FJ8WT{1o2&_P=4mr)U1_?c>{yhYNGv@q7&~ zw;(%&*>j_r=$bpJO(@dhyBox8FU^ z88}!y{UKs?-7t7~!=i!OZB{VcK0foKl_pP;Mob2O%2eOwwn5~9H@){c(kFko((oKK zyzVfC5ft5JV=!^>1{49H1aefpH2tu(R(jm%q45KN{#I{K5L$uG=A754_h zY(3YE60iBAvUR+AQAURAbo7^POO38kqp<`u_`{yC*T%(7hlOo}n(~(Sy2D2{B;alz z&rUhmiESD85Vd2lR}ORw+KfkTU>W{DG|vS_&p|!$qm?G_QIl_ITZWtl95};;>yvMc zHZQfXu%j<5Rw;Z2d>c+)G0s@5Q_4$+xd(0j5jWUT@eQ{C5BDvNUSTqx8maJ#+kDTp zq}-R9Jc1^pFCs29Z&>k>JOtyWf#-g<(m7Hz0OpQh1)&g9etDGHe-y4z(!k1`rn8i> z-<~`M%LZr&$AIt+d$grvouUEoN7l9(eF6!geuanUf%Olu z1^I^`|KU=@!?Eyx4%R>BugBqqJ3I({T(KWA>)|ksmEJIvNn`>^6>r9v-j6t{)jREFB1kxctKSBUzIZ ze$p$f$EV<r(f9we(u^$@;HDXe|5RWkNT4a!IO>%hhyow4B0`@owQ1?rIL#NY3q)(%!Qn(SM?;UNkv7R}bILBT3Q`1G?EpZ(_ZU;gfwzxg#1Z^+}kdi~X_FXyi%v~xpN?eA%*r?lKRZ)UQs z%+$_LBI0j8ASRE9=CPgh`;%Ohyk)TB9k7r5r6Xm zv3kT^K*ZmCK%6-{GuKE{hHb>(d_deiBA%EIBjRs9Aa;j1@1mlJ^Umx8;_!&@|1hHA zO!B0eEw;jtmNcFGZ}Y)^z11DdnV%!ke)qLFc}_8 z!=BBv2kDPEq+!qI*)tztk6JkycldD6o+_|sGVTLp_UxH5sj!uXJ=wDdDZDtOVGph| z?N(!Izr$7<_GHhVDzIlV?l6{~J+p8rY^7mO_UysMP8`y(=jp2TxNXCYQXJB-Cwunb z_9PBz*poebrqnh%mXmRZ>GAAo0(&OoK0p@Fo+hwoGVTEB+0z8}OvW7`J$t6eAUu|a zJ;k%93GA7SJ6P%2Gpnw{RvPvc&z>f*XEN?!rH?&Rn-R9su%~$TAcYc#H0&v!J-fi3 z$+*LZd-m)CdnV&PKvvJ5S<(_6%gML{q-W1AuxB#v0O{F->+HCdhCS7@XBXHr8F#SK zvu9T2gvZjbr+W760(&Oo4pw^h%;L?km4-dlvu79BGZ}ZV(z9n)i$<-Sj5|Pj_H= zY1p%S_6&hNlW_+tJ$s-nh+ApcvwQa7W;YIL*t2`~%vL4gu{7-2J$oR8j6)js?4CVC zV9#XSVR}4!hQOZ5xC5kP51z${fB0nF0n)K2-30bb#(jY7jy<^N5v(-q>5e^kx)Som(X=@;nms z2hHja(3;WlT@WBVwMjmVr&l1LY%R`rt3W`Q^mYpIXmampr{|HNL1dL9W%1eD|&JG~U) zsTqBg?~{86JG~YG#aeM5P3|2rJ&y!2!qfZSM@-KnL5;i;qBaXdYb1a$)H+KioEo{$820(x;+OwS`hpU|v6 z0b$bl=T8b0{{7HU16^A3_VBwuzIy%e-(P<7@aym1Km5bLeEQi(H`F=*YsNX%VJ@e2?>pz-RHsG}r|9yskCowJmytW}(ZNo`S%fIURXT=RCF)jbRx*=J0 z!%0lbzv}sC&QjbpP@(6J5% z)v#n4U*g>u}Oe z%cI@%$ci0KVp<+~wL`LMhm)9=M_%sm)T=T)o|Z>m?|?=lasQm$JI;}hM^^A~^4l$s zcE2CAiieY!mPfmbM^Ep?MaR=h9uOw&nvBMD@$s~phvY>Mv%O1r4Vf~d!yI|l0~(_J z1mzSSPaUE^jQadEzEiW}h}2!w+N?U_B&KCs zce}sYj_WY$CowJCygp*H`iPU5mTld!?Wv7{$|O#HyNz02CxNcu zf}NH}UMTU@lsG(|mPcMGfp$%Tot8&lDuM260;c7W*Gix>nt*9}Go2czpkW zcDk?Mp%v`I7hmHCr}GzRs%XE=N3eOv`++6%Gig-Zt-b<*)qk0ZU?(vR^AK1)reWSm zOv5|`R*z|zcM{Vu4}sNV8s?qEG|WR_b(mIPaSqe=bUnk?f*5M?k zWuDhpY*t@!5);36V6$)RuvvY@NleS56q|TQwzkPW3<=e+UJ^YvNcXt2zaQ-d# z@T`ed*KV6XMOk(2Nlbf+@?E~rSogS_K8a~hQNGO=8f3>YU7N4XpQ5a~_MDwoU5g&Q z?i6JkeVxR#rzo$k-K@IyB&Iz@`Bq->e|h!YfoZY z9{Fxxn^o7I#I#vG-|h>ShQfGS9{GM>n^o7IwA1p)H~e~fsQkkz{~V@O*P?g5^LeYT zJ&9?vdR|?NM)L9TwCdW;t7|u_u03g|<&js{;sq?hPW;V*M_ygKS#|A6J1vjAx^}Z| zzfNLW9{Ijscuw*szWq7F@wdL+=~)qZ*iAnxB4fL0+wL_Hph1_Tsz@#FkRw zM$8`^%%SOUMfTIrnBYBByLt9kxVDt)B&Izy`980kEu}h#Y5Tk)C*r={mQtO>w1*~N zO10Tis*{*D`B1$G$(B-`#Kf;14miG)YO|$OCo%1z$(KZJwj}B#rad(IlBoFvZ1_ri z9<+|%?vr@-iu0tMHu>O7qBdI+brRF^$d^QIwj}B#rsa_@iNf1(@$s}*oXCkd9@&zp zb9UO6ugHmbOp|;#iD`M{OQP_Gm+)eBPEs zoy4^9$d^RnrP=s++L9=|&+YA;rv0#SIcX<;?Z6{{#ktv%sFRqMN4_KqZ@~(7S|0h5 zsLghOJ!z-qkv{-z_KNc)rsa|E0lV3fsFRqMN4_L#vn5d{F)fdLNmRC7V9#OND^7$- z>z~<{M4iO6Jn|(`*_K3|#I*6qmqcY-5_J+2zjok}?*yA~LOim?P6(5JJOv)vR~!ke@szN& z)APs{JDtR|Jo3d(*>;3IiD`M{Tf$~r>~s^qBE|UAL`a5hgw6G%dET>$cblVbWv9<59PzO9+!5Gaiq+EnPyG z^qBE@)NN~6ycO*+!HMvA8Xjd|x|C=6L>SZX2w~FO8IMPOa___Xi7@Ffh0-OwV{I`# zk8Eq$b3C%GVG$<1odS<$q2b}%ed$sbN|(BA4T~`8?G$)q-=syD^q2yVY-?DANslS; z$d)c4OnOX#N49hcVbWs?JhG)r2$LRD;E`<&i!kXhh0>*NOP3HPJtksHbPchkO9+!5 zQ{a&;UCO?6DGQ}b-L{6!zBOzXN|(BA4V!)GQWi>=x@`@ced$vE$j#dJ@ydBQIXfR=j!=6TfzdabCQdt$6h$ra2!WOgdk(;?Pbv< zKFVIanyq;CB&OZhdGTtt;?j#dJ+@AcHog0uVyP=J&9>~y7eiz#hB%37N$AB8*@_`fVpgi9(gfDwql5rnE15=kGvQn zTQS5*Ov@uLhR9Y7alkwV$mhNg&wU{t-$AgO&>-`eFacTlUgNnh#BY93d;4|bxsUV@ zmnB>6Mm^WN>pxboANNbR}e^~1i^FFKIbh~jKIBT0 z7rZ~e0TT63lXJvVSvHr4w&n42|135+&XE&zJn!9pY>tk5w|;y7@b~WL=dYk=N`0orkC@KovQVqk?b3}~EH|D)tx~tg zZroydOr)%%x+GhxlzpvIw$C>m?m~Zh3)E+7{4k!rRw>)1`y{4Wx^au;za2;D@VA>| zH*T>!rl7@}sqy2tdmah3O5Hx+gj+0cCpZ!QcFQBbbZ5JCpPVDhBY*5JLakD_wMw|f zvfo~WTBUBEZ^A8>#}s&EpKr>(R;dWJO5Hxpgj+0c=e&9OAsn2WBU`J4TP%+$@W|FG z;TFqd3Ous4O1Q=Hm`1*E^4o1Z^0i7us8#B=RtaI!+iA8yC+)O6^0i7us8t%aRtaI! z*(ua2jmf>kTIXw(icqUG?88ji*D4jER%zIWnX<1{DnhN&n0123Z}&VBYL&)(6zz!V zc_h>-jrl0r5!3TXs8t%XPVk87;!zQ5mB!@W5!3TXs8t%XPVk87_H{+5RT{Qd31QOl zNT^jBlY1ZRM40rL@pv?BtrEhd$DB)1EOrcAt5kfgQknGwwpIyY(qjrdvb9RZ z*D94+FA?=mTdP!jtx}ow5@AfsBVVgjglCq9tyMypbmJ-1Dh*q!RD7*c5uRBZwpIyY z(%UKU$kr+qU#nDvTBTuYm5Q%bDnhN&u(e9X*D4jER%zH;C4@;oo&t|-ty1x|N=2wu z8n#vmVba?v@W|FGAxwHqAs$Wc9b%lXRVqTQ(y+Bk#n&nop;l?wM*GFrDixttX%ukp z@a?`En@5t28F}j+j0k3AIXNa_@-gc_h>-jaesn#PsJQp;l>3?j12b zkAzyKF(0`&VtO74wMt{w2_7+hJQ8Y^hOJdXm~?y>YL&+1-oZ{^t5k$qrC}TGBTRZb zh4azm-qB9aBcWDlOzs^qJ&%5}R_Ukn^TU=KAx!#j7vhmEH$s^7n8Lo!mKzmcZd95O zk8JN%gh_9w5RWGJj&tOBWXp}FW6@HpVatt*FE=W-+~_2x<&iHpDz@C{B&Ll=zTBwT za-)-&__f1$`f{UU%Z*NAS|0gwqhiaAPGZ`4}^5sUw zmK&YK#IGHA348`|eErOn5SUm&6q>FKao?%!$L-BfsBIp^0)iV^YXDCAN)nWAv2$TNXr~3r+ z-d4|mFzGSDi7=++k=HX6q4(;T+&l2y>lupBdv#bn1Hz>Lc41#<^$ZA;9#h!YP3|4P z-S6uJJ;Sh4G=xcOXBG4e!|E9jCOsx%OVpRFo&jOfV+#2?t7kx%^q2yVteyd3(qjrd zvU&!DNskFmgvZnJ$m<#Eyi*Nh+IZyk3{~j8I;NKB;PYP3Pz621uzCiBNk5*#`Dk+Q zXs72FkW_8Gvc`bzaX<<9Y^Q+I^kZGt{`A0hr+4VLZK_p~m$Lz_jtm z_g<}WJp(W;k9_ad8rL%b)AGpoUafIG128R*eDBp7*E0aq#v|W*wZ`=fz_dK_y;o~o z&(LmG&rrOcp~m$Lz%)EUm~`BncdD`V6PSia)$1ARyi*Nh8Xi@zXQ**K1MD^$azxXMmlCN7d^YYFy6%Ov59DNk8x5eH}0jj}Rt3W;h-J)9?sk(qYE+ z4DDw14AtuyYFy6%Ov@v$XQ=Z|HR?-N&rrRdp~m$Lu+#F$>ly02Qw`f`dF1sBb>69l zF)fe0o}tb=)i9>zk=HZSxSj#yX?f)J3^lH20H)=U*E7_(o&lJaM_$iR<9dd6vw8-E zNyp8&o&lJaM_$iR=bdVF-mRViVba?v#3QR`s9w)d<9Y^syXBGBGt{`A0hpFYUe8eD zy;p&0dF1sBHLhm>rsa{>Gt_yf8lHE{Bd=$u@!qSj)AGpc8ERb5&~8@GP`#d^#`O%q zv^?^9h8ov10MqX4yq=-P^$ftY@yPdHt#LgAFfEUK@6{UDGXT@_$oF2YaXkYtEsuQf z)f(3`0Mqiw_g<}WJp(W;k9_ad8rL%b)AGpoUafIGL%Uf$1HzWf24Gqqc|Ajo>luJ) zdF1sBHLhm>rsa{>Gt{`A0hpFYUe8eDdIn%x9(g@Ojq4eJX?f)J3^lH20H%#cUe8eD zdIn(Hc;xjAHLhm>rsa{>Gt{`Aq1~*W0b$bdD6VG!rsa{>Gt{`A0hpFYUe8eDdIn%x z9(g@Ojq4eJX?f)J3^lH20H)=U*E7_(o&lJaM_$iR<9Y^QS{`{lLyhYhfN6Q;^$azx zX8@+IUk=HXI2_s-y9(g?j4x|F6<&oDj;9w$PS{`{l z12!rGrsa{>GhopcFfEU~o&gRlU|Jq|JwuDXC5u0?Jo5b+nxJP$R?mPi>3AgQ8IsjA zAWVA9IFFLmGayWQ%s7vd)iWSWddxVFlGQUHOnS^XkCN3hAWVA9IFFLmGayWQ%s7vd z)iWSWddxVFlGQUHOnOXkBA91LR?mPi=`aO7L$Z1Xgh`JXk4I==f7II`OnOX#M^?{( zFzGP`9@+j32$LRD;E~lcAWV8pfk(DK1Hz=o6nJFy3<#4RQ{a)+GayWQOo2yM&ww!L zF$Er3Jp;m|!xZ!k$?6#p^E{@&BdcdXnDm$ekF1`dc|AiD^bE=B8JgEKG(pdhY=4I4 z^$bnWGbG!ep?N(+6Z8zp_Gf5b&(H)tL$Z2?=JgCs&@&{fXJ}r}&;&h0vU-N*^$bnW zGbF2LXkO3I1U*BtdWPop3{B88B&%m=UeD0t{Tbln=6uw=o}mePhGg{&&FdMOpl3){ z&(OS{p$U41Wc3Wq>lvD$XGm7h(7c|Z33`TP`!h7JXJ~?+Az3{`^LmCR=oymLGc>Pf zXo8+0Sv^DZdWI(G8IsjAG_Pl9f}SB+Jwx+)h9>A4lGQUHOuASs=oymLGayWQOkrPV z^$ZA;9#h!YSv>>7q{kHYbym-SFzGRceVx@aAWS+;LC=t^o&jOfV+#8^t7kx%^q9iF z&gvNuCOxKbKC*fSgh`JnoR6%Y0b$Z(3g;uMXF!KPCwJ*L1T+n)hp(qRgEhGg{&2$LRD;E~lcAWV8pfk#%)fH3JX1s+*F1Hz=o6nJFy z3<#4RQ{a)+GayWQOo2yM&(OS{p$U41Wc3Wq>lvD$XGm7h(7c|Z33>*+KVtG=UeC}3 zJpA4lGQUbuV-k2o&oQVm~Z!bh9>A4@OGTV^gI&u49V&l zn%6TlLC=t^o}qa?Llg82cz?uxyN^eLo&j&iSxg^~1U*BtdWPop3{B88JU!F(p(eC> zJwp@p49V&l@FJ^QKLtHQvU-N*^$bnWGbF2LXkO3I1ULS=oymLGc>Pf zXo8+0Sv^DZdWI(G8J?c$I)1z7k)UUIdSdm6>3JmR8IsjAAWT~S+yy;DvU&!DNslS) z>ui4pgh`Jn?CWfQhUWDQyP#)Cwm$>Hq_KU5XGwgz%;pv&K1K+)#VHflao7FQQOuBCu z`ZH`+&ww!LG2`c>&FUGN*E8%we}>KK84xDDopBy*R?mPi=`rIx+N_=dVbWv9^9-BS zGayWQ%s7uWt7kx%^q6rTZC20Fyq;kf^bDKTGc>Pf*oFQKo7FQQOuBCu`ZH`+&#-$v z!!Gn^*sPvm_j-n1=+CfOJp;m||8{{#R?o0|J;N^aXV|QsVfT85UFgrSSv|w<^$dIb zy$ReCn)4CDq#sX#M^?|Udp*N0=ovPvXV|@-VHf%{Y*x>JFzLQs=+CfOJp;m|#}wj` z)idl~&#()6hRy03cCTmH1wF%N^$ZA;{@aCkWc3WY*E8&bo?)|khTZEKc0tduSv|w< z^$fe9XV|QsVfT85UC=XZR?o0|J;N^O88)kDK$vv%F6bFHt7kx%^q2yVte#=_dWK!l zGi+ARfH3Lp6ylN9GayWQOo2yM&#-$v!!GCKPCwJ*L1Tt7q7~o?#dC44c(6>|W2X3wnml z>KPCw{kID|vU&!DNslRKPCw{kID|vU-Ny z>lt>TKf`AA47=Ae?D6*|p!>7uBd=%J=bdV>Zep`~hTZEKc0tduSv|w<^$fevpJB6l zhTZEKcA-DRX7vmRlg^if{tTPdGwfc^unYYeHmhgYy`Etg`ZH`+&ww!Lzg^&w)iWSW zdQ2f6Sv|w<^$fe9XV|QsVfT85UC=XZR?mPi>AqdiGi+ARu>1ZDyP#*-te#=_dWK!l zGi+ARuzNkjF6bFHt7q7~o?#dC44c(6?7lz4F6bFHt7kx%^z$z8$m$soCOxLWBdcfF zeSd~s&@*gS&ww!L?G)mX)iWSWI!r;&u-X0$2$LRD*w}LBj>|W2X3wnml>KPCwy`2J&teyd3(qjrdvi%u$-=AR@^bDKr&#?Rc z47;Fb*sPubVbXqk7xWC9)iWSWdQ5>wR?o0|Jwq4zGi+ARfH3Lp6nJFy3<#4RQ{a)+ zGayWQOd(%q^$ZA;9#i0v)iWSWdQ5>wR?o0|Jwq4zGi+ARuzNj27y2`7R?mPi>Aqdi zGi2MJVfT85F6bGu)idl~&(H-uL$-Q`-Rl{;@ZLnWdWPNW8M>fn$X3s=dp$!J-kZo) z&#-$vLl@qg$X3sQFzJ0M&ZBJg47=Aebm6^;Z1oJg*E4kCy@_n~3<#6%+XX#Cwt5DH zNsk$iN7?Eb5GFlld|#KXo}qg^Ll^W6+3Fb(CcT~Uc$BT4p?f_;7v7u5R?pDAo}mkR zhHUi=-Rl{;pl8Td&(OV|p$mG3Z1oJ?>lymIQw`?pveh#nOuBg&^bFbR84xBtrobbs zXXswf&;>n1wt5DHNpEL-Uze?(0b$Z(3OurU282nE8Q<4st7kx%^qBE|UAB4#gh`Jn z#3QR`K$!HH@q5^8^$gwX8M>fn$X3sQFzM_R^bFbR84xBtrobbsXXswf&;>n1wt9x{ z^$cC;&ycO2p?f_;7xWC->KPCw{dfvIvU-N@^$cC;&ycO20b$bHDe%bZ84xBtrobbs zXF!KPCwoi7RRO=PQQ=w8pzh4&`1)iZRjXXwIv6WQt+5GMV%3p}!V282nE zDa0eIXF!KVG%Gju`Ekgc8pVba?v#3QR`=w8pz1wBKydWP=x3|-JOWUFWB zUeC}4Jwvv7hVJzYUC=XRt7qt5&(H-uL$-Pbgh@B=f}SB;Jp;m|#}s&E^$gwX8M^S^ zM7DYcgh_9wu&=Xv282nEDe%bZ84xBtrm(NGdIp3^hbib8veh#nOnOXVUuX3U2$LRD z$k$mtL-%@yF6bGu)iWSWdOL-9Wc3UPlO9vxk<~MFuV?5&e}-)J4BhJ)y3n5?TRlVf zdWJ6O8M4(gAWZu46nJFy4BhJ)x}aysR?mPi>FgBxGi0l0K$!HH0*|bo0b$Z(3i&## zXF!t7qt5&(H-u zL$-Q`?)3~q&@*JKXXswfFogFeveh$muV)y7o*`R3L-%@yA@pa+R?pDAo?!^@O=PQQ zK$x_?G=%piveh$muV)y-dlT8}8M@aq452?mwt5DHN&oEvkF1^nVbWs?@yO~K5GEa_ zpl2vn&(OV|VF-GLV)YCNlitpFJStYt(7m2v2zrKM^$gwX8HS)|C|1wVy`EtRdWK^4 z4BhJ)hM;FCR?pDAo?*;8)!_YRv3drCNk8v#9u=!+K$!HHaUK<`XXswfFa$kAv3drC zNoS|fpP^Vi1Hz=o6nJFy3<#4RGrq4YR?mPi=`rK`x?=SV2$LQ&zOO4*&ww!LG2{8V zV)YCNlO9vxk<~LGOnOX#M^?{(FzGP`9$7uZ@Op+J=oyODGYqe17(#!BV)YEe>luci zXDC+BfH3LCQ+RKpSUtn=dWIqNXDC+BfH3Lp6nJFy3<#4RQ{a)+GayWQOo2yM&ww!L zF$Er3Jp;m|#}s&E^$f%78HS)|C|1ufyq;kQ{TYhYGayX5Zx{3o#p)S`*E0-3&rqzM zVR${m5cCYi>KTUDGYsLqiDLB(!|NG_pl2vn&oI26VF>*hiq$g=uV)y-dlSX#8HU$0 z4B@?rV)YEe>luciXDC+BFua~&2>ls~)iWSWIvxpnhGO*$2$LRD*wJhSxI;p+7^hdIp3^Z>PW`t7kx%beMvkp;$cw!lcI(cx3eq2$LRD;E~lcAWV8p zfk#%)Fua~&2>ls~)iVsQXBa|%hGO*$2$TNXg?ME348!XghM;FCR?jfJo?!@jhGO*$ z!|NG_@ZLnRdWPZk3`5W}6su<#Ue7QDJwvg2hT-)LLwIkZSUtn=dWIpqH&LvfVR${m z5Z;?8R?jfJo?!_68H&|2AWS+Q33`TN^$ZA;9#e=%R?mPi=`n?Uoz*i8uV)y7o}pMh z1Hz=S6D{xYmQnQX%<372(=z~5h(}h>Fr1zNm_j_VdWPZj48RoPk<~K{r)L1BkY})Z zhT-%Kz!c6$R?mPi>E~UDM^?{(FzGP`9$7uZaC!!OyTBu>XF!EPeZl327vm&BnTU-6*d6WGfGf4RI6-AHz#et z3q%5=th523o>79fp;~PNKs}=baYMD@27r1-39nC7t8M_OXVko64Q}tNl{Wy?GfH@W zqFQ|eKs}>`2Pmo)H~`c$O6b^7t-=AIo>79tp<0OpKs}=bjYG8>hlJSaVw50qs8-|v zP|qkqnFByQqXeBpwK@lYdPWIChiZim0QHO#ln&J@9RTVXB}g5r zl{x^_GfL1pRI7CWsArTQcBoeD08q~;LG4hj+9BPX+ySr82{Fpb9RTVXCG>BoR__2% z&nV$RifRQ90QHO#6c5!Z9sueYCA4s;R`LK)&nQ9jP_5e zst162MhUWqYGn@q^^6j957p`((#;7U@b;p>C@XvbsArVW$)Q^113*2a1nEPy(g%Qg zMhS0IRI7aesAtr?fQ|0@toQ+-o>4+KhicUi0QHO#o~Ni*{s2(VD50N2wfYBudPWHX zh-w880QHO#IyzLVfJiqdfxye70;8-10-&BzLQjWkH4p&xj1oi;)rueh>KP@dAgWbC z0Ms)|kU>-{g8-;!)Vzz0($wl80O}bf2qCH!LIBh=N_eTFS|tQPJ);CEM72@~fOKP^IA*$6w0Ms)|Xz)<2 zAOfJCQGz0(T15mvJ);CkM75F#fOE;CzNPq~S_!|T27=<&S0E)jcppH@41`DA08w2VXg`I!^ioY?Sj!{?)1yKBr0d5Gap#(rZqlC^6%_=4Eu`YX_gr_W; zl}Z5AGfL?F(5zMhpq^1e^M_`|5&-p#61qP$tCj$$XOz(Xp;@^EKs}>`{twOSB>?If zB?u;(6-)rsGfGfQG^>~ZsArTQnP^rr0Z`8RUR#$!}-nh69?4;qhA&1ohOJUwVUMm49IK=AaS@fg*dW&**}gT`Z2bD9YR zPY)W`AT_6%Ks<4vf@Y#Q%>*drLF2o=<}?$@YbKJQnP^Tkk-TOi{iJ5%-~alvzr1+; z@|(vOpS(!7kMj2LyFb2q{qWyke)I6_@7_QB!@qp`*+;mEYXA7+XD_~e`|6ul?_d4L zQ31EwL&Nld$`bD2C~8or#w#NQk?iY}3t zl1=2D!*q!}m&XI_bT>cK20*_q& z&ZX~Cvgx~XbL7%@E_(;e2@~Xz%ig)<9WVtRx#XS8-2qeJk;~n=)EzJd9=X(=%iIA| z;E~JRxx^hX1s=J?oy*$+Q{a)y+qtwIFa;jDw4KY^0aM_S%i6i5T|&`F+~-}=&gJZY zDe%bFG$Bly9U(9U9@&~Egh`M2Q#?BE-QIos_RW|7mEIXmqcXLCoKw8f7&u+!|?Hh01S<}~ex zsCd#&{Mv_I@a9C}z%HeaZ7Et_BAtxOc#GVsO}LqRly9vSRSf zX~BUxVS+reTJX(D!GS68$V$OCrvwM4z$2>!-<%K}m_Nm%W2F83`#6il$NM+0AO86G z@~ek0Uw-@W?#s82e|q>Y-{(;N^C6v&yjDuSIVCx)GEAI9$)luIk|WT%Rox27Ph#4L z=5*w+(=hQQrj2M$MxHh+BR_{}W#pSvkpt62w3C>YiB3cgOvA*Jm^Pw04LL9k6Hj8| zZw@PllaK>*!u-JQlbHCmBc|UOS_Sz@OdHXhfE;!jCZ5E^-yH4qJ434P$jQcGr@$jC8%Ln^cK%d6I!4LoyM!07UVruK z%XvA1>zL=egkav^?55N6UBbbap6?QZzGPx}dcI3I_|o%TLd=(*?-G8{t3KZ)eBjal zx9$>Ne)AEU%(aL1(Z9TU`}pwr*RQ^P`0cCLe|Y%x&Fj~XU%r3y_H1&aHP?6p3QV(` zM1Iulq~|pc%WeP^fAis_hwYW!N(0nvrB8yItu#QrEX!tDPlB2=DM0OJ8kU;P^hr<~ z(2~ou0@R#JPlB3L>D;pVi89C1lb|NO15kS|-IC3;o&&X+R)E@rDL~D^^dzWB@W4&& z$rPaGWO@?RWOx8-ul4|HQamR?&CwK~o>4a2dJ@zz%B5Rj=}$50c<6ii_M3;V-a;Vu z@YS0?ygR>0*t{%0$y4tq6SF@l8Eeg^RRQX$XY;CaCiu!@^Qr)~iB*h~q25VQM?IHW z1*oCkNl-^Ums-Vz&-9ERQW)nzZE6*t@2O{Vt0zGn^;~ilmKy4v1a;JN*;Rl}oapD{ zZ;o-trB?xJg4sz+9rb*Nj%4$zCqZ2>a|u>hY7#>yL0vHO9XgWDu$}~U!OW#tVX43< z*P#PZ)&(=0V?Al9W0Xs>;<{5{lufc?C*v6g-dQc%oxegu4cj!n$hYsv} zY>e_9I+D<#!%O-RJpJbjjB*`15IjAoz$n+D1HsdSngiF#*>^F@$@(Em5n`0<(1GCT zEfscsu0sccrvtUZ{&S!2g#A7n5BZPG~p;52+(FXMH7y~i2y~ci{eN? z?B&Oi03Ds9s3loY6pq57fPzB-K~eqLaj5~P0wkJnl;3os)mY57MCgxu->*86C>$k3 zKOu^Y;$x^a8hB_WPMn}WxT7}I@lbeDblg!J>UbzTDf*D3 zj)VBSV@B`aUO&5u?*neA_@P60{Lh>B`cLubKz>8T51qQBsCh3a3h%MvhsGVpmoF#^ z@3G>C`tt`wk5B)v==np;dHHyW?zyP+nDwv~%UM(P<*fb|KlXb_(>mCS)hub+ZyeOL z{{u2{>Grv1V}P5Xr_ma?=0Z9i~K)0eU;RsN!C?jtN>Nz=O3pr-o> zYgp1u_{giwRxDvjGvOm&!m3!ol4in3zJgV;fF-mc;Uizbs-#J)uV2M}BVU=SSeQ~f z6F%~Vsfu+eX(oK+^<^uTrKH)v?x2snyllm)lr$4Q^6Ih`i&D~j$VbP3JgM`OI{zzi z@BKs%%16g9tM?OJ=hoEL@;0bxdCLXtJ_kSgFQ{pG%k}F%1y5*N-cIZ%uzVeCr}~!r zyq(xjVD&nvX?Z)bpTOdEP}A~O+ru`E(DSss4QkrB^`y>^r(t~EI`%xz3O4uTHO8%H z1)IC^OYmK?`5)J-&k8p8mUI|Ez5(Vp5@wrplH__{rdWheSPnR^h}3G{d%UJ<}48; z(T9fp50k$r5hRq`^IW2q=fP*{dCnq15*?mE>+5?*#414&9iBl;)K;SO^|^EAWrAW~ z-^&C^l#cTIV}qh_6bc2Y=tsg)UMNV+Jssthf`ToDqj-!3rGkQ@`m>{>c#H+Lf`X!O z6pyi>SWr;Z2grhQ(V_S;mY^sc#bYce7ZenQqj-!3^@4(;a1@WRpkPo;6vtS!t$=6h z$5;-c#}$urLq=I{on+6;$ENz4>HANrLWp?!p$(aHz3E(UI@g=d^`^U_bZowKR!qKI z%K#{;xwq}_#GWTWNpO@tJD(YfAq_Zxwc)bq5NUhp^aaVZc!ADBd1~5TQAHV>Q)C4WzBjAysBc<7!Ht3`7y~892aHKSC ziWmFt|0U~9=h*EWyPadVbL=+QpPgg3yK%uecDt_tgcB~Y9K#709B|RNpfCCizMnYY za*o}OztK5%8@hezzwOxV+$&U7(Q~hmOSU$JJS>=>dxd}huD)}x5WDZ^Ug6IVlS1vk zCLHA#i)jD#+$*$a>Lu@Dz0`lrUg3Fj#g|`y_2g6G9~K)66RsA=oi z!FJj@wt8}E+FU58Y3ta!B8r-}jvdsrb?o!ziUTKo-du6F_7QuR{QPP1=8BW3`9~5p z`?l8lnU2%_zrXyGO0&PdetG%!=Jxu<>t27l7om=xa9(kHn(E||*Y%RVJqsS^hWz?8 ziIOh#lDdCu%#A%YN_X+ zL@obcur^K~Wn_>Ox04%14tyQ8)_2Nqzl=49Cf5%&zbExvqfj5*`1Lk-S3aZ`#H0{_xCxoJhmh0!t_V_%#R(R}rdaZC>evH)zFBKlt)Sn&Rc~lD5^$tD7?#9SLO-po*-PukX zA_p}s(33OUGbPWIJX7+X2f=tf=EOd0KJ*yp`tR|1+E_jKJkON;^1HwEOSn-(>66$; zIaBg)d}1;sPcHnhU47nMd_Ve&F`Z`(slWN}tRZ!n@tifJ?q*RjADw6V?tFA|;rCJRa|__ofr+^>8J)F7wg_uuwij>k4!*A4gIsyvtNmI&K1 zP9-P`PKEd1;#Cfcf>Xh}td`npT~HL93O2PQ+I@D{i3LUVnd1+IT`h^)u2xXg*1g5d z`?i)uyUu7!^%-j^$uGY#B-m1LD!4L4Ej98hC~Co=uTS#J?+giw!cn+1M0lAM@ra4~ zr6K)r103bIh6F|7C|nz&mKtmk6osR3Z-_(_j>7%7qCoid%~73$dc2qFEygdrDnaLD6EI8 zMkLyG245+^YDC*tw4UEJ5^O1~hf4(1QVX-7D8dZ42uL*HC{zYf%JSFm{le%og`;={ zZt*K{gI^zx;uW~XufRQs9=o%DetG@+hnwe@y1aUI`O{_I^#A?h`sK^ZFK(_s^l~44 z_uVg^UR|xr&*FVu_wun@LX8n|%;wA9ojl&xVJ*3!K%7KvkQo$(FL{w}@r!hO9~EdR ze94P+i(jN0Y^i?0<1@v2vcA4WVo(&mM4=IhnlFQ*@Fl9mNz{B9e5Ob`l!=q5`7+p2 z_!4#EB-(ZE%pMfgpV<$^L8cdq3yQ)~s1zrNKjA2>Dl3A$ud7}vF4j_%8&L#P)RHbJ z3P3)p;#~1HzEc!iGErp|4yuEty_LwN{ zj48Y`ruv;RK~Z;dXu?t5g(iy0TP+Dkbr+f_&Y)JmGbZ>< z-BHR~e*J`_x(ltPn7mcLGbY$lca*Z0EloHIcg84dDcXm{gZ(M)j8WD?)bETreEnni z{&oBPyr24hm*>2n`tD8a{l{aYrKR=#o_iyn_fsEsV9)!hN8cqIe4O`FAKxWkHI8}n zyr24SOlITiGfuTRVLv@9*Y@7{3rn&zO)W_6kOf!_y|k9D(a>x0?*Zg$cfl%h5; z4T@r5%5sX;uU-p^VqnUv*J`zaX;2gcQ(nDRt4;NSq8OO+>b2_S6oaA|n6jK=^{dx{ zq8OO+>a|*JU>X#)-d3*^2d32qra@7k>S+#&_teWN#zaw0QFBm=CLGl-Ks-8%<%X)4 z8w$2me`cbb>Up`LpeP*0azoY24FyHvD3%+lUT!ET3P%-A^}O6rP!x`0xuNRihJvDS z6w3`&FE7x|YO7N3q}NyiV_LQ^yIUgr29(HGG?#yI!$%%G-^i-1W;(hMoqVb+C|SLrWKa}yCKi;eUQjY9ia8StN>(pW9u)PSLCYhU z++J3FV#nFkG=#&;V2$`!ER(w6prH2m+D7ff}&W3;L(@rM_*#1IQpXH5!lp^z63?# zC?0*Oe)J_Msy{ovr#$*n{pd?j6prH2m%1e!g`+PDPd-x{y#`wfNAW~U?NhqZ-0v>5 zXG%x;iI!kX;V7PHseYm*C<;gML`(G(EkRK@iYHpCpJ<7R;zUd3iI(aoT7sf*6i>8N z-d%h9K2Nk%KhY8tg`;?)rTU4MpeQnmCt9kXXbFnKQ9RL7{Y1+_^tb?f*3UTW zXJ8I?*3rJtp&p-)E=O)>h0wn(b)EGy4#W+L4#eK2vwp_iyM$Snj+fdPG59=fjCfWE z4fJO##?^}ttIrCd_xYf4?c@2dVoZ%8wYICe%-x!2P}7Ih7*R{J5BNqk^_jzn8Ut!+ zYH&QP=>uwvr={6#Jlalu=Gac3pi0vwsKMvy!)c7BrD=UnP}BOJ>D;Eg-?o_iRCnxo zp4*gv%f<;Oy0xvA@KN{P!AIvd8m{FHs$^E{Ksumo`~6rn4O5(Id&Tz zW1eHTzur^>XMvD=_Gn{Uybh}r$SRJ;sN%$q2~gDO1J zId=Q)Pq%#t@#iOBef{mPKl_&_pDrs(G-5wnYh;P_f^*&NZhnisY^}c}GUr@(yL+DJ zy4!spc^(fK&D(SA_P4R{x$buG(Rn=J_U7G->z7YH4UV(iM<}7FaaNZZ^yYutvD@{# zSC{ASUi{(a^8C#Y@52@O)_xBEFi})FbH@)SKLOmgq#h$Q*0rC*H&NfxER&xA4vP9T zMElchsjVRgMSTr<;tAl%PXGr+ofMpS0(kNhz%fyr0G@aPc=8j#K~Y)Y_(OqBDwCfN z35xo@rV16{hw}3wK~epgwG`#kCO;n%6!je$9c5ulZEG_q3P(CO;n%Y$+VY^C6R;4~dE5e2Bsm{i&Z135vo|JRhRX z`SEAkU3h%?c|Jskh!djvjEOR%{Cr68>%&nzA2RvXC_zy;3hQYF>uEtzI0_(}L=zd+ zU1-mgqdq?$5^O0P#q%MPpAQL&!ckaLD_B#DiDFGn;R#1M%ytm{JI4+lsvCOs@e-ae zY$)S9v5ar=GQN6yAD=L6y_ojlS1v5$TfB^KP}DuH`JO+!Qu^b%n*aty^%-j^JYKwv zZ%|Z!W}+B}7BAx)6m^dmmhsg+U5T&n9xqpz+3B*Ngs6MGu#B&+i%E#O#|z8&>IR8~ zsC&GyjIS&#a|%l-C~&io#K>KUlo}U{Dl}V*Np#@kspoa1`qg>Tbz|C>+K5gSuNXAqq#a z{$TO?gRy6d`h$h_2X#;C11&wK=83YMDBFp$ohaMg2(fn>k1c+m)zS{Jd!lT|?K_)o z#NMTT1nBTQ&+X9T^R#hM@Ok>U=tSA>pXdKw+oA8@zI*fR_cynf_iwMC-Mou0Z}jWh z4vtgpKr9;g%}?Fak41tGB>HQo;(-*k;doHghvTXqNKqS(2St52uJVBp^_!m#qQ{Z* zS?1y_bAheov&_ZV3eIwtx%m2TIOSR9;w*C^9()q=qZPPOAN3la_laJxdHfG7b8+70 zRprEFWgLJtBG<|nGrs=!mES@-3-y9EWYTk4B z?${fb=I|=NZius0{)(+}Y4%ay-J(dao%+nNoxW=(%`P*lsm~lWeTiS1bu*7BB<#;!lt-16F%zRJN`!Wk)Jb(wbS>+ zSu$}#$;6q%6RH@jX>3o%N)DA~AIBLF1II6qw z`1KncHD4th)m>zQUO&Hi{^4JK_Wb&-PEuVy`pf_H{TDyGe6&3M=K9(1^?!W-`8Q9m zuGadqc(8VtTchFF`N|yI0m8@E%v-;>##9l4^OadPstV6GdiI0PU5_18-Mi7Ptu$@t z8}EO%sH%-gbv%Ktoy@gSRoHf?Z6~vBR29D6>D$SC8&!pIcN%vx<3?5C+?~#y%(+oj zSeF||vu_+lRpBk}9L-b0TYER;@qOji(L5!*wRc0BD!t`F994x^2{X?QGe=e7Ro>)jx+~V!89wP;VoyHqpHY3UaCI(rRq^tc&ji6{Z{p( z>aoAR`nc`ui`SzJ&)%JT>@s=(`t0|whvp-DH?D~?Fa7@YpeQWJ>I<`1UkHlAfxLfx z_Ua2kQ5cZb7iPbIJtzwQvHHU7)fa-Iupg^0%wByVCW`6{GpjGmUVR}b3iAP((d`NH z(fzbBC<^bf`oiqh7lNX26mRF8z4}5>6pmu`h1qZC42r^0tiCXN^@X4)9L4GjvsYgT zio#K>zA$_Bg@fp^kDNZ4*5M8kH5wGj$P%y7aQII@yvVrY4o@XAM7>5sOcXU56vz~{ z5oJ&mzGIDs*=sZeMd3TvXqdf5Lr@gHV~vK{YcvE!;XBr7n4Pi-io$omY|8948iJzm z9cwhqUZWu>3g3Z2QA?FdqrI*(D3cLALYrN<8Pob>;-i0ZocRlVa7_MG&elm2tke@^=UTTS|}Up*Bz zv0mzzUtN}~tG-VA>o+g^-sR_SUcG(!;`;UN<@+CRZeCvg^_SmXN_d-c@8hpy@5kGl zXJ-%(aq^!GdU1QRCRfZTjf+Ne-yuW=9~aTR+I6s{7)t>|R77iBG~7~*rNALdG%=Ry z<1hQ6IF@n{G5Gb7eXPziJBb(*brMlO6vt9tohK-Yu@qRuGW%U~2hroO=MlJkq~y=u z2XDt81SF$cBx~KjI+|VtR`vVf%|yAYrwN0ia^Z2nNtkePm@p^`N0B95oFxp3!cjyC7e@($qHq*R z!o^9#gXpn?JXcfC)zrHufO3%Yxte;erk<;*|E*S2|8m6RuSY@Z7vEeChd*YW3(?_^ z4@W*!TVV>Lt{R_UBt?LHae%xp5In|tN)#h0)*f1%ACHOl(U+w@M^cWD2St4(rKuGL z=T46YMSUctsTD{>h-)v7YsW-^YcIsL7ss`OqHq*(?Zt8JpeP(gTzhd`J17cA5!YTE*A9xp zQN*%vxdvRPlC<;dr*Ipdg4vNB21hE$fv4f)ev!kO3VlNJ2 z$3y{QD?E`=epy~n6pkW@y*P*+6osP*VlNJ22Swp1g4m0L*g;V^iXislAa+m`jv|P? zIEWn-g`)^!tLpvu?4-N!_?{BPUL3>@wiJ#ch`o3&~Z@Z>XG!0{BG6qP%MMd2vo zc#GqB!Dk9b5yx8`#|w(WQK$=87RT{|qWZI=qln`zj^o8df#WGW@k2R|7Zin~h~ue9 z!1%8ZqHZBkw>VK3Y$+Ut;(%pwqAnVl$h6p6aU>-z;o^=C&%k*HgosEdh$s8e{tQBKqaMd2tCb&C^qK~ZEBiMqv! zx}Yc=MWSx;`hG!CIEqBw;zV6g6pkWMw|ITOpeP(gqHb}bE+`5|k*Hgos5^)rIfTEQ z0C@l7_3v(@Cjho9Q~^}P@@?+_wYxR;0|N0Ns3lQ-=IA?ecdK)EF;Q@Lidb*y>fBvW z6uu*Ow|W)8peTGt?rwGNE+`7$k*Hg}3Sdwaz9Uh$dKJK+D11kvZXGA;wkuQtRK)Vv zmxo5*Q&j0w#8OnLG%SiFBT=`G6LtFfa1@EUH9^!(AnFvc`1%Q=Zt5;PdY?qynjq?? z?m`pAKJfY=QFrVhPf+U)Q#y~mo}gAQW_K{v%)QXF*40_->K|I`>KAWRt@o$j-h@Z9 zQy*9zUTMvmm}s_u_92QMg|MbRvNBbypsh|xM^)W^nm4hnHsOz|VtztSdUZ}Zs)`8; zLFv^&>8L73N+jl1C+4E67%CB&TOFATs)CtYc8-;tnTx9WU`g{LyaNu+MOA&Yq=^w# zWt011ZB*60rI`^`Gu}eURZWekDw~YA)xD*;5mhtZLdjK4j;LyLkmz%DZ)tW!RhxuF zRoz=F*|`-ZQuWF_j-yT(Hm-!{R)^<;Z3R822@;+_l}(1<0hCD942i1!JKwErMB55) zk)KFxba#z#S?IhE~pBQPLWF0jJLWWkI$7L-RdA+w5{+KNxIcZx~M9= zMU-xJlrE|YZ;_>2ou!MaBDVJQB`=0INjWp1f72aaC)72rnpeiUkMJl}IlwDL6-XdnVI%XGDg}2Dr ztRpBiHcdG+;QB`=0#NFz|T~rm`B67Dnau-#F zx5(VB&fG;+;VnXUt3!8DRd|ckoi3hDtURHRog$TQmTWS-o`p(wid3q~CgZB`7QwsK z!Mosd1$n1PMO&S`i>ks~MDJEd@1m;k7TLSi*}JGJyhZqKb@(o-3U86VTb;g(s=`~u z?^eg}qN?x~`McHmyQnI1ivZs00A5rTxka{a^_q53Rd|bVor*>z91FTmk?P*soURMD z6=m%dsZ^CshI<#(wOh&8ZO+$4+X`ks~B&5#hyR`XSb5G+nlqDsv@@t+HD_n2KToL zNIPAS0LMCM7i}xNMJ{9W;&o9~c#GBRwhWh1x*?By8{{%JFJBjJE4)Q6W6N+Er5n=P ziZS7q;W7#;87Wfv4kWx)P|8S=3e^mkQNU#=QmHDNj3!L!hCDo1MJiPjxmEhBVyg63 zkxjfYMOWo%x~DEPjD%TT293CJenZFO%cQmHDNjH|l06sc5A%(ryeEq*O}3s=|n zH{wy2tl;WeMJn5x@fNrYMJiM?Tt)$xp-81_##`Vr6sc6rcndhMB9*EcZ*@Z+9ZN1_ z%WxT`8`4ziEw5}8bS$_GMJk^_##_C@n6;JO^4dnxw!&NFGPVqtQMw_mt@Kug%P1X` zGF5sj!(|k385_Bb&FdQlpDVbGja^E~9i%%2esC43|;5Ax)LJmEkf9c3TNy5+bVHgdy_MlI3b>4o zT*j8+GDrR*{O{CBtPD+()QL zrK)T)ygq;mNE^9~EyHCLlt5CXvaPbocw6Buav58O%P8HD_72cn87`yXQo@Z~#+KnS zN;jmnmEOv583kO%MlNH^a2cf=^4L~#8C!m=f{IkUuNf|*bWqBk z0COwDWt476Q>C{uTt?}jl&LbeGF(Ohm$8w{*t{H4a3&8fV6>xr{BtWfWX9s7QskGF(Q%J%by$j4i`u6kIg8 zk;~XJTt>l7gNjr>0Y%Vo8se(Kja2f87Ty$iXFmfN7DhePe zQmLv48dpVbk;`ZqE~BDeh9Z@1O?a!KUWOu-stIpZa2Xr9jF#atYB%KZeI=LCGF(Ol zm!U}I6Oc{D-vM}wTt>^(%c$To6sc%yhRdknGB$D{nH1Bz6t zCUUEGLz*hRmEkffxQs?FqxEgz;Ww*;Qr1??x0+ux6&nv!)XQk(GMe8s6;<`M3`Ht` zt&F$8WhhdqnivySa2bkJsAjl~3NAyDO4Uqmfy-#*GMZmE75ufpWi)abEmJR}g3D;+ zGFpbqsNgabseG;(Z-L8bshaT?xQxbn z87;$QRB#!JRJ1k2WmIq(ja){{a2XX`h9Z@1&Eyuij7Bb_Ww?wAE~AmlXc;b}g3D;E zm(em@Mg^ClNab@)tYuVi8H!Y@X1oP1Ly=0=jJLpLG}g;#87`xO%V^{>T87K0;4&Jy zjF#atD!7csdKoRlWmIq(id6hs87`xO%TT0JHIrN5G8Cy)P3&(~a2bvDGFpbqsNgab zscdV;Ti`MjsZ`B)3tUDcm(em@Mg^DASTCbxxQq%eLy?Lnkl`{axQxbn87;$QRB#!J zRJJvSfdpN*z~7$Yrz)mr=oGG}g;#87`xO%TT29xn^<;Tt;KPjF#atD!7bBE~90*j0!G8 zk%}jf;W8??3`HtcGu{H1(a2@A43|;CWhheF){M8nWi-~yXc;b}g3C~(vaOli0+-Rq zWwZ>JQNd+2av3edWz-Hz9eWpY87;$QRB#!JR6N%Vmr=oGC{n4KS%U|cp-81_##`Vr z8o7*?;W8??j7Bb_Ww?wAE~AmlXc;b}g3D;+GFqlyMg^ClNae4U854rbP^3~dlUulq zN|EZSdxp!X;4&Jyj6K6;RB#!JRJJwaEpQo%RH|mY1umnJ%h)sZGAg)?MlNH|)XS*g zG8CzN0-5<1xQs?FW6y9I6WmIq(id3{U!)46iG8Cy)P3&*Y z;4&1cR84qmM!k$iE@RJd88f(yMlNH|)XSK`Wi)abd!}B-3@$^F%IBK!)(kE~kxJFX zm~aM{p-81_!do-yWhhdqn#ipgTt*|8v1ho98C*sqm$7HKj2T>pA{9>{bC1akE<=$@ z)kJR1;4*gB%h)qqhAz*t5&TXrW6y9IGq?;zDxW~cTi`MjsZ`B)3-vN~av6K3Ud9YA zLy^k1X1oP1V<(rfXSj?RT!tbQZOzSfH}GInwqd!}B-3@&3Qm$7HK zj2T?UPA+55a2YeW3`Ht_tqhkjgUe8)QZoWwAa2bkJsAjl~8C-@Um8uzU zfy>y*W$YO)V+NP8lgrpM^)hB~89TX*J;P%hx%8M=tb z*9oPX@s@KLQuVbAsb;+8T!vKXtqhm3IF}(+dMm?aEY4*}mARFvm$5jPAys-SQ!it2 zE<>t5Ce*K$@s@KLQl+>0Ht=X2lEt|UsWP`RT*l&DhE$nb87^aSE~8w5%TR5ljJKT2 zkSe{E;W8HIGNejxWw?yRxeTe&TMyr3^1uJj&;R`7_4TWpC!ao}aCtrR2?XN%kmnWa9Ft8%=ekWA_ zZ934aYV@hZqnGn64sS@52K1sDK~V*wwUqvIb|WY%&zdOh=jcXIRF*YSy3fgtn5csr zdZsj=gBw9nh2gQK;5Jl&%)A#A)n`nU*7Ivlf})B-6Q%Q<+6anjlxd5PzJKxjCf-{*;h{?&X+kGF`Zs;Nw{*axTmkUVmopOv zMPWkl9TK&%Wl$6*1l}Q0o3;f-VM5Ry617=dP!uKv+#yjjVNet%1lu7|o3jN)VM3rC z5;YSBMPWja9TM$2cYXd%gS5Wo(VfHV`vM4ju<%TGsny^WwKVhvb_TAFZ_Qyt|B zREI9 zErp}NbEu_VXV6iObEu^pC_2s&YpK&55~ZWO%0^HWjsnb~Lahl$Im@97gE>(2yHA2G zMMeSTP)idTqCNR%1n z07vlaBcs4?sHKUFa(qKAWkz{fjbKZWQJ^=}(nLl%yrGsdqa5A{wiFo!c0(=gI)fSI z=!RO#jB<1%)>0=oBuYnlMU9{+90hPg1-cWCa&AKx#WSOv+X%K483k-ZElp&UQyXe2 zGs>xrU`vrvfHu_9L`FHYp_VeEoY@Gr6d46%LoH2YloK0jDKn~X5RW>_fenemQIi83 zv9IsEhD710$$5>SC>%vxV{%+0C@L2oBbv0v}XZA|bQI2VZL|3OYio(-( zy{En@Jm~$^A&qiHNMmwHBiK?nij2nOj7Crtjv}HldFhOxC>%vXWAe%wK~Xr0fX3v2 zMo<)vBA+q&eI`LsIEr}2Z%?OHm zMkzdDQ%5s`qV6b#Cq>8SQ7gaGCq>8S zQ7fPfg(pSFM|~@p4235}`&%?Nk6M9bC_EwRNJi{E1(Bifq-Y|e0Ax%AGA0Kyf-Qxk z$YV^-V+2J#qZFR}`UyvY#!z@tG~p;<779;_CL9IKLg7i#grmGfMp1ZDG~p<(kReez z$}x-JudhElWR$`aEp^NyCJM|#;Yrbiqr5yuQFu~R?ilS*ygG(NnNf~e1iwBUh2j{x zHY?#MuZ^LW(ov3C1Y7E(zKNK{ZLE#QaUQZOsrrgCNdLKf|*#o@P%5+j7l&QE0~Fi%*2#nCRQ(dQ6@4IQ-YaT z!AvMT@t!7_i51L*!jqzjd6d_@(ATG<63oO3WAi z*9`_&&%sPgWF~YNaaHXszX)@QS3*Nnb4t;geX?e$xMiwPl#fzkIaP7;e@C@ zb6i3qGa-61A&Rv=G7|#G5~5h^BQqg}CLyZN*w=@ngb^e}vDQasLOZDmQLOc`v_(lU z6C0R`iOhsn{)bz-ftgTv!lnskV)MEdMd3-&aYt=l)t*u0{Jekf#={!OB#a1@z|l3*q_FcTA*iIQL@Hk7ka zc;e+xFcTZ9StvXyns5}D356#`6OIBiq41<=!ckx*6rL1KI10>!!jqy2M}e78cv5sc zqc$)T3QvkA90g`V;R(?MGqHi0P8J!V zvH5Kx5~ZUO%)|y}qL7&=31(vRyF}DdIx4|TY@J*>%=ikKiIQL@HZT)~%tT2r6C0R` zLS~{Qn28O{L?JU#63oN~W}=XpC<$g_12a*`Oq2vOv4NQ=WF|_2nb^Qg6fzSf!Axvm zCJLE}l3*q_FcXE$L`g6c8<>egW}+mRi4Dv|Au~}D%)|y}qL7&=31&hixx7OmGf@)E z#0F-fkeMh6W?};~QOHb`1T(RLnJ8o?N`jf#z)UDS5zz@|VgoZ#$V`+(orw+1L?JU# z63oN~W3MnmxH!6U;;dGokSG zp1&rTi3Vn(keR3nW}<2&N-z`6 z?*Wl09hG1vnqLDVQ93HYOf)bP3Qzt}635Z&XQD03k6AjFS!V@h`FcS^Tgu;`e z;~CY!Oej1lI-XGt%!I;|q6tTVnNWCAbUdRPm6I zs)3nMcv3XsC@>QWPlzU%i3Vmu;Yrc)QC|Zyq41<=!ckx*6rL1KI10>!!jqy2M}e78 zcv3XsC@>Q`uujp0qrgm5G85IW^XM<_qx<^}%tR$KQT;lPps0`fDw&Czs58;POjI%x zHNi|YFcX!`L`^Ug4a|hX6TiM+=Mj6RU?wV=iJGW0(ZEbpG7~jXXQF|bsAMK;f|+Pw zCMubUnqVdxn2Abeq9&M$24QW zPlzU%i3Vmu;YrbiqrglkJSm!R6qpHxCq)yE0yClTq-bIu1!h9wNzsI(z)UDSDVlH; zmf3i3Vn( zl9{N9Iui}dL?ts(6L)hoFcX!`L`~G0XkaE3p8WL_jsi1L$xPHlorwl!qLP`Yi8>Pv z%tR$KQ4`EW12a*{Owwd>*xfnNWCAbbKDQgPBlxQgnPCwS$>Zcv5tH9<_s+PweAKst znNWCAbbKDQgPBlxQgnPCwS$>Zcv5tH9<_s+P&Czy#H%*0G)VoopH{;O z@T6#B)CXol;YrblMt%SL|NQ*VPhMZYx_R>HldF$)N7Regm-lb4pWVEB^7AKe-@SPC z;`YTKZr(rn^xyvctvhA>YpM*1ea+sy$NEi)TE`(#|C$oDuNf58 zpWVOY67`NlqSkQ)MXlqIsAslBZC)7^wT?rgp4k$$%npiL$01SgI3#KvM^Mx{4vBil zAyLchpr~~m67`NlMQHkaeOFvQCh9xh67`NlqSkQ)MJ*u;j(1QLj>3+&YDFa+CH z(qn2~zj~^zt@TpB{OY0y_N$veU4H%M<@1~8m(Sn4di(Ol_3PWq_dnj;yuAGDFTcH% zc!YYW>#jGZo!`uL2z5<+{{DPs-JO_}DATU9TK9$ziX!bmOsbHXrCm@I-UKlzQS)X{ z6ln)yQlgf2K~Z=U#H2*cn?X^e9f(OqXxF*xnPZ|(OzPK%H)Vl@D7*<`QY|%a9$I>| z(dVCi_3rxh4>y-rZ+?1x8+FNs7h2W*{Dl?}KKw#U)Lv+bde}&G_=T3Jz0eZ%;hRK< zUucQi3oTI(8;K6T&=R#5TB1IDlj!gZEm3=+CF)@#$bR^R-gbYXCF(D&Oxt)WgrE!Ai4hi?+4qkKXX zY$+Ut36WZwa1;<=PKYF$a1;<=PKYF$a1;<=PKYF$a1;<=PKb2EB;hEZ5b4*aqkKXX z`}KhUb3&w+CL9F>m=hw2CL9F>c*cZCq7OOh7-sF&tIKaR_IrKv|NQ21`{q)=xP0^O zg$9D3J->c?d-Lw{(e%mu?@un@fAO=+N8f+`&C}_sOh1c<9+=`8Gc2{zLa)DDkFBn3 zyU(yRYGLU43@a##(8CN%Ej5bpD~l3JD6gnFz6FXMICBnn57DPG3wut^k-B2&DK-(4qB3?s=DFXMICB#L1qnc`)<4x2>b zC^E&%cpWy0BBRI@FXMICB#Mk8Q@o7dT_;hw@c8nRDPG2zV$~poqsSC5<8|01>W)%) z!u#WQ*GbeJrSPQaa7Ibg9i{N3s0||{J- zjAK2&MBPyfnc}6>jKiYtD1|4#{%}UArS7POOz|?#6srKIJ8B_QymXpz^y`BuUdR+L zon{;sg`>z6FP&x_7KNk86ffgUv7RX$MW%QeXNn~XN0BLB#+hP?!ck<3mvN?8qHq+M z;$@sEmM9!Wrg#}=iX{q1kttrrnPOF+g`>z6FXK$HM3GTsikESwSfX$gnc`)fDV8W4 zMW%QeXNn~XN0BLB#+hP?!ck<3mvN?8qHq+M;$@sEmM9!Wrg#}=iX{q1kttrrnPQ2; zQDlmjai&`ZvZ^}{ zM-dfX#_z6^C>%vpcp1ODPNHxWQQ@WY45Ony)L~P2VtDSTaPXPJQACB8@w@Bv_2DR@ z!i%HA!Ir{NM1>beg@dAS6j9-2{O&q^eK?AB*cL~HgDusc9abh3p7`}06^@Al6;^ms zG%=3?Dy;CNsN6C7@&grCcv3XsD5r{acN-n$R8jDm!cl}U7Kbo`qHq);jKv|0peP(g z2xD;wBPa?-5yDs;!U&4OQG_rShcJSo`m>{>2w^M^VZ=lMVJJNDo;rjP6h%f6!dM)_ z2#O-32w^M^VFX1n>LY})ID`=tg`)^zEDm7=Md2ty7>h#~K~XpgRJuz2$sMCzA0P~c zCtoSKV^|c90+p_o_HR72AEoP7^qHfhK&7iFp+<0{qJS_Ip7{C>VZ?qYKo|?CbhR{* zQGhTOQ0Wp)WE3Ebg%HN#5JvFp!%<`=mT_i6_u{}&WG0qzW%1f~ug;G!5~w$?E5OqN?_j>P~G;pjXGwqN>(Q zO4WZ;JpuboqpH?TO4YkbsaiJ~RkeOns@_jZ)%wY(s&$l7^^Q`i)=@@Pt*4Z#_mon# zo-(RxU8PjLtCXsBl}FX11wViH)B7JUzkR9G%u%9NcM-yYWYt!$e;MhgBnktPRa>1^ z3yDr()ih~=|D06|io$+m)mCTKf}(IAS+(`UFL>Ag1Vv#!vTCcdYC%zWkF472tXfbM z)+4L7I;$2Gh4aX&tUltERApqnuR> zin^newG@45jB@PDrgnSz)pt5Q@YBneH~(?jKVGT^7vH~leiQE6CID{AXST#bu#Yqz z9a~J@x`$;C#WO`M1B0S&L!~oCEdqn0ZbOALMJ)k?qHaTFGes=`gQ9LjMKeV$|AL}! zLnSjsyUtxF92C``*{{!$Wdd-U0Jte}(b5FqHUV%`;!@OX82kDtnz<5iTN8lWgrb>B zT(&gfC;)CsT#6HrMH7w!;HJc-Xu?qd+?2QwO#p5a z05>HrMHNz`-Ur~O#HDD$Q2^Xl0&Z&paGL}uRswEo0&trExUB@- z)&$@-0dQLhxUC7mO$*|l`vlz91mLDML5MP=5`deQ?;y&IN&s%E4h2zWR042QfgFf3 zqY{9dYS}=P8Rc6pv0;yIxs(-KF1jqMPmKnLlD_34QD&5Hxx`uuz-=Yqw)&P!P}G+* zR&2TG>nG+>0Nhq=xkxlI>cd5&3Qt6|Z@C1&J{*ND7qv7o>cd5&3Qx8)G3vubqY6)o zCPsY#+!US^?T>Nv<=1D9^C)b&=%%=YqkPMyC_K?p-*Sol`T*P%o)k@t`h3f!C_E{e za1;PHg(pQ5j`FfuYAGF+0Nf^28B%z%r3pu&%Fs%{ZA}1f6RHfY1l-mH;5MPk&`Q8< zO#p5astm0J+|~r(HUV&33An8Zz->a6A%!P?{RH4Pp~}!oz->(cZj+Z?EecPzG~p;z z8B%ysG_f+#U3lzI3An8Zz->a6p_PE!ngHA;0B#CTe*Hv7p~}!oz->(cZW92vm4Mrt z0Nf@3ZYu$|H37Iy0NfOwc%})!Z35u75^!4+fZGJXZ6)9)ylH$efucYw0k<^)xJ>}u zRswFSD4A#}=1~OPROvY(ig^?PxAj55?ZE9%81;e6PfCel> z;YrcNT3>hJu|Fl1u{o6yY$@hZgfcdVGJ>L5nIMy~Ig=3-l?(0bBcnD)GJ>MWC=wZ) z6B$8KIEp~V=0HYJ6pkW~u{n%x5Vsp?UC<;drwAdW92#Uf{1T8iPErOzO6hVv4L5rX$ z97WJ#bI>9v3P%yN*c`M7it5jfjv{EWIcO0R1!%DnwAdW92#UI+6rQkYq9{-SGqI7G z*!phm;A&3+GokQgOUFlj1x0}ro)jIQM->zWQg~8yeAHJ^6iDGo(eY7VK~W%uCq>8S zQ3V%`Dm*FLU(K<#zJj7a3Qve8n27>rLg7i#@ljs^GqI7G*b+s73YdwF%*2*pCJLAd zg(ts$!ckx*6rL1KI10>!!jqy2M}e78cv3XsC@>QWPl_fS1!h9wNzsI(z)UDSA(~(& z3YZCnCq)yE0yClTr0DqSc>yz_@T6!WqrgmTWG1!*Gf}`yC_LHHgrmSrY-A?31T#^< zOl)K(wgfX#z)WmpCbk4KQNT=WWG1!*Gf}`yY-A?31T#^WGNTgAgl;>6C^IU-OcXE^8<~kM!Auks1=`3=YzbzffSK6H zOl%2eqJWv$$V_YrWnE6r0%k(tNzufp56pzZlcI@HAD9V+Cq)zUC@>QWPl_fo z3e3btW@1Ye1=5bT+my`2mS83dmG^I1^Qg~8y+)))5DJeWDI_{{7inTeLTNU4IE z5aEtznqVd>n2APaq9ra;s$eD>nTeLTNU4IEXk;c@qRvDGGttOQv;;Fz!AvwV6D?6^ zqJo)dWF}gInW$hU8kvcfU?wVP$2;6D`3^R4@|?Pk*KM1T#^=Of)hRdxDv$s58;XOza6}qIMS^HnO%$WPJ;6-W?m`pAsBcd&6BW#a!jsQ5G3x6sw3cEXwI`T~iVHmy zo@{Ai)Q1Z_6rK=GFcUMF356#`$5$q1FcS(-ijMC`&0r=Jo)jH-)C^`q;Yrc)QQr(^ zqLG={6LltLFcS(-wsd?RHG`Q@cv5uSQ8Sncg(pSFM}0Gx356#`#~n3;nNWB_G{H>F zU?vov6iqk^%!I;|q6tTVnNWCAG~p;P6ADj?CL9H3Vka}P_ubmTiNp+MLgC4lCL9H3 zLg7i#grmSrC_E{ea1@w{oy^4EcWZ~AsXlW^Q-vp5nqVeoFcUkOi9K;Q#|&m-Co{1p z>P*aFCU!Ctd!o+73}#{{GqER_i5bkqPG(~7yS1agKA4G}%*5VzYllVknd2)(W@1k; z6Em2Joy^3ZU?yfT6FZrSJ;6-OU?z4l6MKT0n88f!WG40mGckji*vU-n31(sjGqIDI z*b~ge3}#{{GqER_i5bkqPG(|HFcUMFiJi>Eo?s?sFcS(-bkYfCLiZ}WP037rxQKbw z`(P$^G7}#zVjdPnMvC}RmRuns4u}x=w4+PB{Q)nm zeFp&Z z9Q7rbi5bjZ2gW3}!;%$(AM@1!iI=GqES`=9s}u>|`ePM4gEl%*0M+ zVo%hWn88f!WG40mGckji*vU-niMu&wFcUkOi9Nwg%wQ&VG821(nV7*$>|`eP1T!&% znb^rp>OrmwbzSGKW=>4hhsF~1ha^!8@}Q^6Dbmcy^s3-|4ypedd01 zM=gc#7BATmX{kh!WWZ0<(%~eND0~O}M4}J*?!gdG+e@i<_6X(J`csw%DszcG9`K z)43nsna2i^Qnhzasy>RUyW_c0ReSlQ>fO0i?d6NA+S?~p@6V-bZ(mf^UO%b&KuW6i z`bAak{gbNq=u)-!FRE%Upj3S*B~^O?qpCKRlB)OVQnj&ERMk3lsrvLpc%XIaK~-S7 zTCcH5oK$Uoa#THf@HcOs{r=|m^5f0*^UJgAx0mmL$z>qykB6BM;n znlwW)KT6aFL_twF3ZW#?groe-h+0ZVc_sy0sy{mpG7(8?X~I!{W<)Keqdbvb z%Fm2wGK7p;yw2vKr30xs$5T@kN$hJD?U7i=p&%drni92+L!$mQB|6-3NYtWOqTX>x zv_G!9+3DfgJvcp+sQ&D}6i6zW%tQKCBR0OX(6i6S~~8i4=aS$QaZ}7U=6kuj>6FxoyJNy3P)o!WksC$6|AwA`q3B_0cJ+|6|4u* zV`@&Hlz)G6`PI#zF1K$k^^0#VpFO{RdwcWl^3n9ktpDZvFMjsX_n&|BbehWav*@%_ zi&56wP3ltZ8*4Gjdb|D)k4-xzYQK#{y|>f7NA}yqME$pssQ)$+wcai$YQ5d0E)`$j zf19AFjUOcH;|I0Wdb^;gjUOcHy`4n+i*q-A2#V@6_s*24_jVGs@k3D5dOL~w_(7u9 z+XY2!{2)>9?IddBhoGqSb`tgRgG8;j3yQj&eT^<*}Fh&@w3wlrze18SBzOKK?` zg=0%QybJqsEUdsiklfjxDLB2}k*{CAE}}8b7wAmcmguwxk>H5*g*kmef)@ zYW&!et}KV6aBN8}O*qPrElmnfIBNXZl3EH!;nZ06!@W>6H4BAdB5n;8_vJc?}Q;%sJ66pkXB zxj35{6vaG>Z06!@W>8drcAQ6%&0L(#jEREHT*ziF&SnNh;V811i?f+QQ8PC}KN{V>>}nWE8QT#j%~BC^CxJ&f?fkP!x_L zwzD|46BN~-9W#p9&f?fkOcdCT!V|BQV>>}nIEvWL;@D156pkXcvpBXB6h%f6+gTjj z35vo|#C8_Pc7mdC6tSJfv7MkO97Swracn0j3P%y!SsdFrh#vQ~K32Kt%XdHi^!oYD zyS}^iTlWqcUwz)l2W;{jF6cj?7FdDCqC~ zhnh(DnfGDG{ILx#sk-k~QIM+r+ukKKMCVwqn> z1*s|gJ!h(Ep(_(zvR-f96X6htf#ns&4<8OZ^{eBaN%N|5aI# zzm{w=t_p8)v0rCNGpg_wSNnCCG@}Y{ak>9PeWc+hfc5^F>-`@JB#o&vRzpcmq`kU)_x0kv_2?O0GVxAWM;Qw8L8vftylf}n+V5yp?rRqau zsdkYkRWdph_8%+pf!yp*bY zI;d)%ma6BaRNd1-Rr9n|Jug)|*)|-4&(-r%s-Blp^}LL=)$>x9cDtvg>UkMdg}0EG zQq6eFH^$XgddoM)qt8`e>3(!0ReH;J#-pn67V=V0Amc6H8&_NDE#DiDwiVt&UaGAb zZ~5-H+DdOBFN1FuyoJ0}3Gs}#JTKK&ddv66gU{7B$aQx;y@kAtJps>4sWP{GhdkO= zJXcj1o@2YjPkO{KMbqdeGD-zl$3R2wv^shQaFt#YZ-TE0~t zZ7ZyWy>hiRV=dn-S6gW<-z<-|71qLTx!RhsmT#Alx6Y$a0N%phxfVe)-tx_JwUyrT>Sey|PhNqQYCgdmdGVx3GP#Ct%)+1-DoI zR8wg!-#(8v71qN3xtf}>me>7MTWKxdK##T+*1`_D+M2PJZ=tKLT*>e)^k`e<$77d; zJ#@8IE*b6yd=p)5mqLf=b|wiU63&2+Uj6I)&c zRBdH!`EGi&t%xmbr)xhf6I;HYuC~%!zMmd!t5;{LN>s#_Z>UFA5nI?%*AvKi%PV21 zt;{XoQjfM3xrIG-wKbDlUJFBQWp4SVdbF*`E$phRt(n~NY8YxObIZ5YqiscQp&W+V zn#nD%hoQD2weyHF-gds48-cr6MLT6%kd1w^%D;@>&s5Rpb_nMND2S zBB}~+v0B9B)gq#*$SszOn7mv>R2AN0y@<){MMPDRTPzqcdBKRND!j#t5tCPph^ivD zSTbVrk`Xc0)oVu7E7Y?Tabde#Js2KcdtAL{L{*}CZ0St;_@H?8f|gRnD&gcsBccxg z)lb4N%wiVW5-H6HSMnqL%EflrX6G+6?>QycE1Q1)3SB{9b z71ly|0<|>}TdUV6P+J*WUY{V?RxeN>RmPSVD2S?hY$;LUEw4}zRrT0XqEa<6BwPVy zC{d}J@mBvzhe@0gm8yv$;p&&GRwXJ`6Vt8LZ&#Hnrdv}6%2*v@lq$WIfihNy7^RBo z)|7!V)^14qwdk!3l(7QJP@>}3%0L+_pbRA{RWrHe#R{qtm8uzU0m@LMQZ?f(FIS+p z(pwoQWA%CkQl+;tP{s-PJ}X4 zku{_0W5S70hN@C#RDHTN5z0^n$&9Lx2^Fb)2QuFB>IHfS=q-mbg5xYu8H!Z2HA7{r zpfV;>87h;Ic&?x_CQ=zXexFg*hmPX`QW;Z*%2+{VOr$b&WH8fKc#BlVl%XSPNXuX43)8h%9u!HOc^R;^*RP>E4`JWGFDI-6RC_TLuIUf0c)K|WlR|= zWAz(YrOMpOP#G(z3`Ht>mkgD$`W>ulE60QxDq{tep-5$0Gr8rru&S*b6K1H4)vsZd zD#wHwDq{tep-ANu$mEt^#HzN^TNx^21(l&{i)d?x%2+{VsNx(|Gr83bc}y5m8Iw~P z!Q=*(p-5$0Gh;$8Yfu%bRL$fTuna{iRWsi5!Uk$9y_LZ-R$v*5RJJuUCiKzPg0 zjEPvrl)*AqznE2RrMEIz#tJNBB9<{_u#DBOW>s71tqhj20?U|)WlR|?WA)2f)mC~d zgJrD1GA3dfQwGaefn`j@GNufcvHGQ1bt0BAWw4ADSjI#wW6EF|Yd7REV~J%<87yN3 zmN5~_m@-(#+6`%KWo~7#j1^eML@Z;R#Sq_vf~mBBJrU>Os!jFQ1JR$v(uv5bd^8&>OUj8#ReR)s)=9!vLUc7$(;@Qo64I<9eJX7;b&6{^Gu3tX+G#GFg zhn}hV^J9ndKkVA!tN69UnrvZYjBPP>#)*-!?}{nlI5PHKvDiy~rlw5{&bg*}{G4k( zFx-Cd&TXwK%XsHp^ULqP{Q9fDcy*?xIqLtm)cpMA^&c;9Uur$(^8WVv_47Bs`(3#7 z?}l@B+9Jg|xu3J^i)oK7bhZu0>?R(wD}Kx_C~E6xRU4#isjZ&{MQxNIQC~lsi&s7l zirV^_M17PX(LOM^TR#hmTAwCSpIb}R*3W{XwjwQ2Uq6$mtw;w&ZT(E5z9KDATR#hm z+Dt&AzJ4ZATagZm+WMJ9eMMTLwtf~AwH0ZJ(ouf8E+&e@b=nuj%kPKlf}(H~&(;+$ zcpMakqj+I;b;ZjaA4HFfa{o)0R9xQwc>TNEc>jpgciK4RgHPBFhwlmx z-xWW6clbIF4tm;#vv-AO?}`^h4vNBdJbG9B=v`10w&TgW;^mNoqOctg-W5N17Zb&~ zyTWsK#n0UZMPWN0yDNU|E+`7y@zh=MQpiD3*p7$piXXZQiXzB(=C1geyPzn7j7RQ@ zAGr&PBFK2+uK0<&peP*019w`O7#|#<2(l6uy_6S0KD6}MKVH9jTK9Rq)GxofXqTs7 z_4DgDFQ4mrpU>aCdi(Ol_3PWq_dnj;yuAGDFTcH%cqfX3d&+7w4+r;pm-_f969@Mc z)>O6i<_{Q2Ko#!f!M%cmd%?ECo;2ltf7@D>j4 z1y$iK9^5N9xEEA~w|H=`;NV_R72e{(y@G>#K~;E*2lomN?gdr#XZPz}Rk6%p%cgO` z-USEul*?4jcnb&j6wFl3cnb&jl+0AMnOyV>02WA3nal`3kUZUseG=zb$81yQB{5D=q(=HE2yU& zd;-WV9^5N9xEEAKZt>t=K|ST5Dsqbl_X-Z~1y$iK9^5N9xEE8!!97JP-T~B84ywXi zJh)eIa4)C|Z()a0*Is7EguX>t6{&mz8E^R>rBvxH=V621av)Z!%q<6EqpI*0h*&+> zOm5-eUcok{R5Q7SgL?%`tW-0(g@bzqQ0!bBiVZ$jr(*SM(OXW%MpfZ0V6keeY%<(y z87!!hwRa<+1GMZbC##Tit+nN~@;^1BZ8>_ZvyybAL z+R8DZ!?DrlirfMntF~sm<#?>xinR>gMws}uaBxqN>c5umVauq(TRga@E2uK6$Soe+ z)8#uERg4LFa8K8cWK`iT)>GDv3mH{?=r|_i!9CTQ&!{4|cyLcuwlk_26SAJN>I-L7 z;VmBAQ)$(VD#nC7xTgY`~dTQ}sPe^sPXHRCPZa;-?EYQ|eAsH{k(YQ|gLkoE*H->Ob~ zM4zjBOOeX9X1s-h%8FE~X1s-h%8FE~X1s-h%8FE~X1s-h%8FE|I`R?xwZMERQmL94 z6E+l7R-{rj<1G|aR^3~wX1s-h%BuKD)r_}*bSP4(n#nCN9g0+{X1oQcLy=0=jJHrw zS&>TBjJHrwS&>TBjJHrwS&<4==Q@Jk0@$HQrE11oD5$JRrE11oD5zYCc2q|@qEEob zgq3VZb+#j_irgaHQ627xsv@^YcT}f4qN+Y7RHX9P%6O|&R>$Nf-%*|Kh_=xMkO1LQJl zhRbLus9ecq)C`x=x*@Ht%&iQU(NIvilFO(WE~BBKawV5hGh9YPLFGy=qh`2_hJwnK zTt>}s84X-UC6`e%Tt-7d;4F#1exs00OG8zghD^k(FX1I)o zg35|is%FN7;4&1cRL$fTxC})qRWoBka2b_cM#VMPu`EDAWko95n&C1UxQt3Jqh`2_ zhJwn9RJJuUCPYDHMJiP@^DPuqR-{rjGv5N2p-81_|J4Wgw;Bp6D^jVN@fHdyD^jVN z@fHdyS8^FO!(}uSR92+2t(h?)3Mwm7p_<_`8n_HaDpfP{EfiE%q*68GEk8M~K?c2* z;W8Sy3`Hv2n(-F63`HtcGu{H1p-81_##<<;T*+nB442WsWmIw*HN#~za2b_cM$K>; z4O~Vgmr*lZMgy0jNX4&};W8QuDpztDHN#~za2bkJwl$Mm;4&(?44rC7B#fUT*R+7% z%5WJCTt+3AQN3hYaD4z=MkSX~Gh9Xkmr==O)C`x=P*Ay&%cvPHqk+p%r23mRXSj?8 zE~Apmm@`~PLqX+AE@RGc84U%ME4hq0!(}uSRIcPQ<_wq7P*Ay&%a}7p@W$fTG6sc6rcne&HB9*Ec zZ-L8Dq(U{rW$fTGW^x&`*W!qc;CFBtGr5e}i*ZC%Wys^3MJ{9ZY8+8j-`|?aWz1fV zBdRJxT3hKYTy))?_UOLh4lZLRmoa;-jc8kCNNX#-<;6Cls=jwTlgpUB+D25>_l^~* zbV0^j;4)@%8FPlq*uiDY zT!tc*s+ln%xQv-x#+>0Yc5oSrRJJuUCIpu;lgpShT*eMALy?NMX1I(UT*gc;W6p3H zJGcx*D%+ZwZ-L8Dq*68GEpQo%RH|mY1ujF8O4W?Fz-7$jGIZa~_a1>+p(r;{lxKA-6^umxnxQB+P?TqNtFyY53P$qHO03{) zpeWDkR)rMhS>5WaZgp0-QYnt{*~VGjs)3>`q$tnoR%dl9mEuTv3l!y9-Ri7vbyl}J zt6QDbta1>cR=298C{>ChG1dk}c~-YNt6QDbta1>cR<}Bqm^oz<<*>Q-lUtFyY*S>5WaZgp0- zI;&f$V5IZfD#bCr6LnU%+HvdHS>5WaZgp0-n$PN1XLYNyy46|T>a1>cR<}B{^?tF`{@$efQ$ki`y4}xKZJ#fBW;3>)YFRFMj*eZU4vnI#Mfc zFPON#tJ*hS=cL#DdaPEjRP~|zx|dS*Gp$nfGp#{Yt4bzSulQFq8MT>LNENpiNY$&7 zN!2T?2UYc<;}gK`1yc31K|xi0$W*=JpH#i#Ur^PmKu=uXm8w_#3#wWbXsP-ezr8?hrMG&q^x?Mp?FAEWFHl=E-tu#IQl+>0CHCWOb#L+Z0<|^cEx)}$ zZKbz*vGnn_y0^H#tF~sm<+m58t@KvE#QyKM^;q@sf8AWayS)GL`gga{aBEwCw)eKy zee3?1w7g)CDdH4~+EbFK_dpW0rxX;m4oIT@kR)mkDJW|Fk3_xyk*M`QK~al#iF)@V zQR{w!qSpIJ)RSE%={k2e-NZyug1)c>z53sTsO7qjBe4#QSD+8J)M8zt-u39~Th|j5 zwVp?!sN-9_{(Mjrj$--w;^pUqqHq+e&lj&g9~6b73LWLe=Yyhf6j$ep*PaiG!ci|qIk)#{8qc5sJ-M8#Y=wWm)ZqI?Io8eV&ls1vi6S!Zc9RmmWWN z1F@K>&jR)9(@{PP42qhg>J_iByYflkLG+lK+tux5dG+e@i<_76dBv4qd|MWjY}2t3 zd-NY{_-H_0dC4}ZdT*vn(e2p>RsG^ysrtj0s&!{kReSm>H15M-sak&)RrL;S!4N^J zHV%%edXKhXj3Cwia@@VsQB{5D(4{RHBuG`=)3~blX$wXPQngV+w5{H$Ef^+9RUOoL zTfJ9XFiw!F^=ikq9xeFYf4sf9e0KTW%j?_AAFtp4sKsrKS}$K+zkB!QkKr-v-YdP| z{~mQ_Vd;6ZH}cRQ{QRNSaa|Z}FQh~CA%mj!K1vj0)_Jq{F(|4(v#*bYoxQ5` zLG<`roSP31ZaDmsS*q>^shS(2s%8hNx*eqIz4KvG z{a|;Xwp#BjRiDF2)qCfls`buN^+}vmy>||(TJJ1XpT$Yld*`644LYUj(>SU6$S0@@ zZ(-DVZa(M2RAPb7xfJ~yypw)a56opN2 zlI?M|W=KS5DXA6|AR z(S)PA3y+;7?z+<*J-u;*j`FMS^q$gDe$`#<>-!XE;uJ?MO*qP@I1;6!e2Q~u>2c!l z`OE7+Ufya7cXN4vd;R+Po8SE|+EKQxFa6&C0xELoeVVrOhkt>#`J$6V{TGnvaGxeo z>(grCqLVh+M&A{QTAwCS{{__2;XX~G)~89-qhF%KeVRnAPm`#RswFzyr%BZMG>Q74 zTB5^!nnbNnlc6I^3s8)E!l>=%~IoKGvrR ze9&hOHZ50lRKJ~lSQL($d?8We-h`vN3y&?G=%{`-`*2I)sELm1SF`_J(PKyXaov{7 zcRzNZ^IeBLzx?9zanry0`isjyzr23^gD}ruh;(`J`iIL$Vk@3%wQ`T+oV&lG8u9xp zs(FOHq93-h9-pK8J1SLwN2O}-XjIi+QmOh&D(Jyp(x9rprBd~`RI2utMpf-Kop|g~ zs`i>jRqZ{Ms=udFwf8itYA>o({Y90ky{J)D>-(kZeZN$#?~kfl=Py<7{H1E0e^k|a zf2n%!FIDUPqpH^ZOO@VooGPkn{l8S{E$6ACs_+(oDzQKRAA4`pW65z{YyXvl@fw2l&TL9rRpzVMO7OhO4SF5QuUXwqN)uLrRpzV*X!y7#G2|pRr+Dj zB~>3FO4VP!imEn1oVCP(jw?9VxTtCaM5%h1t5$#cDyrJcmsDxT)$Dj%Fn;=e-93D~ zuAP3wxyHp>;jK<@t-H?qneS??`jFL1Z>@>9c0-yfy@hj)i&p^N>h#vmTXE80`%5S?VneLw|K7c4ckAj3U3X1YfHSf8}fJs2EDZ<-r5ams`S=oSyyzy zZb(z5x3?*aFgB9*l!-tvWH9WsUYtpy9oHE;RCgj6{u#6ogS)fbYbN^fByxu^H)^w!ShpB`uJhBQ@rYmrUPtHN6|$Ars%-=7^5 z?uIClH`_elhLu8^p@D{ep zXmv92)^5n-{ffOZQcb+I8`4ziE#E9tnuFJFO?Zp_a~Iz&Q&mN7T{$N7?J`wWcd&*cM>% zJu|l%qk<~Dg-tW6)xA}$72aZFfW=Xc;;#jkVB11h^0#O7Ofef`+2}I#3@)+u{5{SZ5opA*mL;nv?KmR~uC`j=>1RA3z z3P%yfSO8}bMJQYa4x^|FTam+H zv$CQpd_@j}&B|)3;4s*%Oyr+ORZ$hjB8S0dWqWWx{cCwY)0xf6RI7(oZLG4}@%RuR zhrwoLMOAo<90r?}6;P}x*edy>dau^*PM)3;3TjVf0IEW6sh>Nz+u#C-3@v8wG^pT^#Nf~)xD)irD~8{6F3Y-Dph5Z)AuVl3`Htc z{WYt21w6MDsZ`x{&U$N~j4JM?s|?kzGlMl%a2SeITvu=y zMOAo<97YF+QB;Mu$YFGF7)4chiyTG=hf!4ZF=6L1DIFX}Q5CsG4x@v^D5~nuj=4n+ zql3dJs={03FgiGlqAI*a4x{@~DYX?6buq;iU~YlKsMQJ%qw^f&4i2NJ3U86a=-@Dl zs_+&$j1CT?s0wfK9ODiSqo@jR&CD%u7)4chYi4eN!zili&yL-n(?}J`|;^=o8^9bZDTj2T><8nGa0v@%1^6; z$xx)iTVOJ3R{&5(CzR0vWfWE6Em9dBR7O!1-XfNvBMFYbR`Kl^{V^1&ysk-Zfy+>& zQg#2%XLAc&Mkkli!DSS$E4)Q6ql3#Rs={03GJ4P-W1G+)qm#=RI7F^iE4U0rs{dL8 zTt-n9xkWBxpg%@Y72aZhjFE5|6SxdTDz8A|t=*8vCn33vf&Li9D}dZ0mod;Eqo}Gs zvsy6+KhPhes0we9%NXd7QB;Mu$YtD)960@S*$rt|0J(KLbKtD1&Jchqy_IkoIz+%# z$z|M59XMYryhSeKcI?1;Rpb`AjN7>b=T+e?av8US2hOX)TjVlsCl8!gg}2CM+>RbN zuL^IG%eb9Aa9$POBA0PHeBit)yhSeKcKX0+Rd5-KR6Mm4E~A0VP^3~-HaTCbdrOf@ zRoUdcs(VY3O4T5@8n_HaDpi9qVMBk6K`vwXNg%cHYXg^|NM)_E$@%N*-cqDeRW>=V z>fTbMQq|tKs#n0hrAUQp!e!hJx>8*sz z&_R(ZP6LBeG;a2bPK#z?q~wj1*JbRm~9 z5-y|dhBQ@rE8#L4`eO`o86)8`8v0`lav3AxG8(uHMJn%sWK0MyLy<~V+2r&{6I{k% ze~giE8ErSD-2=?6gv)5)G6uPfk#HFeT*e@mF_Qim4P3?`moXA9qxqq-I`WX-axUX` z!0D4Kd<|TNA{BR*a~V}t= z%c!ctTjVl^a~V}t%w>?v7|vxBuPe9=MJn#Bgv)5VA&*ZNav3AxGTLrPQ>C{OE~D*+ zG*x;l;W8S|Eg9r8M#5#Z-H=u*b1UI8+HOcwWo{*0Mnk8JK`vt?Tt?dsX|*!9oXaTA z6N1Z7q{0QxWfWDxWejo|16+o_+S9x58@LQbDr-&VGIm2AuPeEX0WPChE4)Q6VMgx~I$YqSAUq%C$p-APgm5d3|FGG<^)&2K5JEyrD((VCzE8#L4xC}+A z*SaQLMgy0jNTq5r2aj`06sc4-Z`Js$hJG1?T*m5LMpYHwBA2n^+>-r`=IN0pxQszA zV|6a0S}SskT*m5LMpYHL#dAwm=Q66Q7!#7qSQ9Rz?V!}rTjVm@0_5QjR zRl#Kpav5vFWz66*6sfqbx9U#U>SMx{T*i8PbA7K`8x_y!m$8z|SoiJur(FOpLy^iW zka!DRh9Z@!d#awk0-jrnRH~Y{s@K(XOOZ-d^Hx>Wy`@N{YQSa8IJZQR3e|+mn0G@S zGFFjF)nH6G?}j|8lFL{VE@R#eX{yYvgv*$BLz*h)GS-C4n9(m|WxtFy;WB3Q%TT29 z*GjyFei(|3GS-C4m~n2&%6=JZ!ez|hG8C!!wGu94 z2A82orK-Je6`xt)G8Cy)O~!=aGFEaKYr-P^3~d@fNs@ zmHjf-gv*%0WvuL%u_j!`3@&43zl=5EGG=fYE4hp{;WB1$87sMr6Xh7PYot<0^2%h0i1u1YRrO}LC1T*k_N87sJq znhU^XtmHD*gv-z&6}SS-t%S>%!DT2?@f=9bEt$b(tmHD*q+iAiE@LH^v4YDe{#x)B z`(>;NmobCOP^99zg3GAY3NAyDO4a0j3tWaGm8w1_EY^zmEpi#Fa~ZX>KxS|mid5F> za~Z{2;Vp6*t8*E}Q8BoTm0ZT^Tt-zDxkWBxbuOc-irgZXu{xJgRfV_6WvtF+RPOk9? z@Bj38_lvu??_Rum@%Z9jAHKW$>>q!;yMKIq_u^l^f877^$Gb0o|Ht2b{`YsEY3q$$ zeYG3%QG?hqn@QT6IzIKHBT>8f67>h0(6L?T{RCZ2)Yldz>d!Ta+HMxO4QzTi=sA(BvF5;Nz@){MNxaENz}&+61Df-qNokUCF;WkiP~#! zQPiGj67`X|MD=hweM{K`O`<*!m*{Tbv-c?+g*8Qq29EM2MO8{i`I2JknxX^0MCmAB zQ7nqWQCLtE;CbFrldmVL(HI@&{r3-*9v_g?FQdMwRkuq0Zq}0Q{tKS- z-Qshhs?_ghiJs4g#iv5sGfag_^!(j?J5v4l^)VAF(ewFmJ5k+4Js%``J|7mJ2i4d2 ze30n*e9+;q$Cp%z(ow!W?O1ucqNK1h^~@=4I5sO5u1=_sEA zEsENROQLj?Pk|mpj}OSN{`U6a^7-XYFYg~OKiq%!?Zdmv-%ZahU*5la_vVM{BXiyG zu6X6U;?)`c{l0u^Oes+tRB67?Bj9@VSH+^J4XPySrje+brYNdE``|>0x@jb8ra6cn ze~UIAFTeTfi_0IrfBEv^Z{!QNLoEQKP6`v7)FwW@b&OQPhIFC~Ct{iTYzkU*CeeC~A)xiTYzkq88jm zQG3it)E_ev-F4n)Y*AEycDS`QnTBiXM0QOSK(^-6C~Co76t!XKypqRWy-!|I6pkW} zy*iFv6osQmW3NtQ7e(PH!q}_B*hNt|iY&Gs(&uj}pxBy4{>FjaEhe5#}->Qg1E6pq?_s-!3iM`5Z&mD*6aC<;emszjnT6fTOw zQJ5-`=$^SJAALZu6`p=e>3H`*6pq4Fi7E{owY%_mOJS-+qJg9KMwKQCN9hdG;Oir! zFjb;T_aFT152eporO2qwr%Fn<)D`fx!V|x~Pn8r!;V4X%TsNO8DT=~Tm@1Lzc}HDA zUMoEL_0K!%3h-LtNzwC;y6!GK{`%yux7(`3xm)TA>{{W;O3yp$3hG+nNzwC;y6!Ht zuaAt{9J(&vQu;F!rK6m=u89J0m;+pQ0nP)2nXRYw0==o9K6`1wLV+l9MtczdYM|}!URvI`8khQ{- zqJg7)Nnzfwq;TDQNul`l;V3LANHlO12y2BWzkc8-UsBN5r=xsHq4@RnXGceouikt~ zp(g4}3aXTj@+F0$C^8C53fIk-6pEtAC@d*RG{`8h)f?IB&6gC4mCA+39|}tfsx)wv zFDc9$mJ}o!WRx!{NR%1nOA5uWkBq{Sf+`Ih1+03*l7d9{;!X~FK~-;9Qn+ruq)_|% zfT}k_)tf`rMNv44O!ekWbx{z_<~Vgx6prHQgPYUTMNy3U*yL_=n7SycKRZ79$Wm|4QrAR*Qg3W=cUz4+ z>wS>a3Qy#|lhnmZ;V6RCn}gIvQ8Y^wdMT&ZJin=HYM-igl z9HK6Y!ckdg`AqNx7t=qM7@n-kPEQ2^8mPu%?8*sdswjN+R3=4;|b zQ8l96pkW0y*WEw6osRRPH&D*7e(PHlGB@$ z(?wA@is1C-;B-+`e|B^fx#`Wh>6$38X@w^o<=Avl6pkV_y*V{q6osS6Ol$!&aU)ZX z*Obh}7BCYxGQ~tWGvTf5ieDd&A~UghC%d9397Seg3z&&3`q(Kvc}oTFQD|eQ@TBPe zjZeNup^Kfu6QTh#aRoD>@T92Rakf(Quv2(aRPHz}3P+Kd*aBway1Vdr^OKp_0%qch z26hTheto&)^w)=@$V_YjGjRnoq3~p-%A3=bBBRJmY<{X>&HG>`6rQX!aFlN^nH8QU zx;zV*39U8bmU2f)G;kC;*C{+%Y2YX{uG_#&s8YG(?5~gW1QnjFR3o_4q8RmonNX#H zqjqxX=zTB~5>?)ut`r#sWY+xoNdfrhBm3K&jU?w&+s#B%s9kuM_((x&UK6Sd~b_W04P;vn? zv4NS8==qFVyi1)(CuUT@Of0(#KYV?OIy0e414lVCAyH zLZZy5fSFjFnYb!E@s#r3bhTgKnF)!~Q2{ftcxO6^(ox=-u2`v!`Xow6d1JbwC>#Z5 zLTMXhlyAdSrF2xlOkf+PMCmBshFSdjHrFRnIx1i$unkk9bX34hU>l}H>8OC2z&6Y) zw_$2n6pZ@3A)Q3&sDPQkHcW}qQ2{f7ZI}|JqXK3E+b|`{j0%_uY{Qf&9ThMWi}#|F zC><3r6N@tw5~ZU8W@2$>LZWn3z)UR8Oh}ZD3Ydw-`_KvSW<~|f#Nut}BuYmG%*5hd z=p;%<1<3r6N`7ClPDb(FcXV6ppz&a z6)+Qv_n(s}9ThMWi!&1vrK7z4TrHxVnb7VAIx1i$7H>W$Q93GMCKm5KCs8^oU?vuC zJtt9SRKQFu-g!=8OC2 zSe%)VC><3r6N~o|(AFM0DqtoS?;{{lIx1i$7VkJGQ93GMCYIfW$BY6qp~8OC2Se%*A4@E}>%*5iI z=CrSkjtZEG#rsT1l#U9RiN*U&NR*BWn2E)Y|C1;)Dqtp--G#?rAIyZNmxGxJKm1RX z(oq33q27L|l#UAeOsKaXMCquY&xCsWL6nXPmh(mR4E-5Fca$Shf3+FpwEPQ`$3c$6)+R(?FUghYG18AJJ0WZCUi~d zsDPPJZ$DH@M+JQ*)Y}iDaMZ0C;MuS5%!Ix^95n^ZgnIjVrDP^<%>YkV3P+Kdm;z>E zab`k$ui>aE=rgf+p9zV=QB%N7EY3_w6poq#W@7O^6B31^rhu7PoSBd)95n@fCKhKV zBnn4OL7$0RW87ozlbM(TX5!Wu*F@>4fSI^8#yyIXnV14*;?@|~L^0}{0%qdY7}rGU zsDPQcHO4hjIx1i$ZjEtGl#UAeOxzmdnkXF=FcY`NxF$+R-Fjc2BN1+maZQwt3Ydvo zV_XwuMg`17cV^=HjLgIoFcTfjgu>HTc&C7wxHZN-e0_x{MbD4=I+zKCCq*@aJDH{( z%!I;|qUUEOy7!s5Dm*EA{ynODp9zW5Q2{g2!AvMTS*b>Fr?07x`V^iN-Csyf+7!%$ z!V{taGtt3JC_E{8oRy=wK!ko~$%*l=qpqDm*C~ILiA> zNR*BWn28Q%Vj?p!1+0)-J`)1p0!M+FP^gPEAfOiTeY(ZNhiWG1G7ndo39CNdLKz)W;76BC(F_D>=0%oFvnV85-=+ z)JJAQM_mM>KG!#qnV14*qJx>3$V^NDGtt3JOk^gefSKrECMGfyQ@~7gFcS(--24GE z(ZNhiWG1G7ndo39CNdLKz)W;76BC(QWPlyK0LQWPl^VP0yClT zq-fwMFcS(-iUy7XGokRLXy7O?6BC(q44B=8aN8f#Kb-mE$B1R!AwkKCUkJ! z`8Pf=6BC&U9S9bP>NCgnC^8c*U?w`4iHXca3z&%xW?~{U(E?_ogPEAfOtgTR=wK!$ zG7~LeCOVi2g{R;AEnp@(n2CwZL<^XS?tLcITOAqI0%l@(p9zT~qgudB4DT~>oybhI zfSDNHXF{SF^|gSR7~W?>q8RnHfSDNHXF{SF^|gSR7~W?>qIi#L0W&eY&xAxV>T3Zr zF}%-&MCqu2nb5J={yb%$i54&u!~0CAQaUPNCI*;^iOfU`n27;qLg9(0RKQFO^qEk2 zQuO?L)BrP~@TBPZ_oxA8Lg7i#^P|22W znP_AtTEI*UFcXc;L<^XS0cN6+nP>qsF~CeTG7~LeCI*;^MrNV~%)|gQ(a21+fSDLz zCK{QE7BCY7%tRwI(E?^-fSG7yCR)Hu3@{Uo%tQ;Ai2-J!k(p=#GcnL-qLG znNWDL(qPmFWR^%tQG%im4UE??fid-vvtyIi7BCzyD8PfARCn&z4XAaR1F;^k2UI z^&dV_SLONV)!(eIzMd<5+Y?D6eoLg=n(0$NnpE|n50^r!9!XNQNUEypL#FDPq!$V6 zb6!)`x$RK(P?D;JQdQNwAcEafNvf7gRaG;CRNV|xH8WII%?(m@H%QgoP*pWMNY(8i zRkK4?RUbOu16bFUs*Uxks``+rdNfJZqN%E?51A^x}I((0-((S z&^9RMwg!chc3X9qxwqHq)e(Afddq9`0i0CaW$ z^dNeCM*hQ_Z~pS|c=`6>{`uvb`?r_xzIpfX!~QDw$=oh~y*&GLsXjNwdD;)6{c`?@ z(-f;c;`T?=Q_oF_+7BX8f5b`D9&trc`#~h?k2s0iBd#cFKZr#A5hqc5#1%#D5hqc9 z#7Wd1aYa#k#7Wd2aT2vhTv5~>aT4`MoJ8#rR}{5JoJ9Q*rwR7`zJC9RtBLvyh(tNW z^cj$%s6FDeuahH8A2bw2;V29m^z{Qr`K}RFN=Nyip;)Q@>@aNC6blA|K4>V4!ciDB z=<5fL@?9hP`gD{J8j6*|Q5ZC+(!f!^YebdOQ9fuWRtiU9(4f_&z)?PEP^EB`4yikD zQ{OeBP0etWP8177;V29m^!0zrQ6E#&*A4XCq{ly|=IJc*b%T$o36EbtrsnBe%J*98 zVa##p$J9K3O+TjQadelZ=BM*mE?<4SuS~t$SF3*e#pTmg|LXT&T>kgV``3TgdeyHU z?%%z5{pZWigm!4aY&VeFh4A`s*3vwyEuf6 z*(j{2>f1O}D~4fLKQ6SYiZ>hV<4~e24yno} z=YK7D3;Q`lPbS{-4IS#*MQ{0rj^Y*Y9UW@h#qp2t=%}i~TiDW}EAW%vI=*lTb9ft09bAPI*#v_oyX_7virNh*QGd8g)Na6{sNH`O^*Jk@ z7HjukNpyAOK%##8Nz~r3i=y^qzX~V9HFe^kC~7yKM12-mmDRvN_Q822z80lQ4Sg$M32wN|Dyrx<-2e1|MXa0Cs~K@44t_%^s3D* z$JjgkKa0Qn36gI3&QOW^eJ9b=_nj)W`%a>M-%0fJeJ4@7?XYluGkq``=NXwAyL2YBzpQuzG7$S%$=bUwK00JQhSn1)Su)MJ^dtC zrS>G3s6WXidiqH&QG1e0)Su)M4IJe=LnTT_`OeVdHHD+FGgOrZj`E$Ms+5lMouS1_ z;VA43Ri!`WsN?hTp>VNS1^8Kq%=Iz=q^KZYrXhD9TEdSk`m-~i}U%z?v z_T`KF*N>O4zkPUkdHKKp>yMXKef3a(KX?;6G&TCz@5lGvtc(;Ss?Qv~i5;2}HE$M0 z;Z5w&l&E>LC<N_+wfMVMDN#F<3kAu&Tn1(%#KEjQ^xO?&X`HOG% zy_Y%?>Lc8Ec*GS)UkJF5gHPO27I4LDih%nFH`+D*Z-g5^ZteCL*8k3}-5-C8|2eA@onaK}gizA0_HPk3{#U|EV_!iCVl$)aQ02diwoQqW1nM zQJ>q9=;`-IiQ4<4M15{YqNm>w|n8Knayo=YE7#C0x8wgFOU+2r2wr-)GSpk6`lgLCe^@G=srAyS(B)Fs#+>c z1!hgEfvJ3vSvVn0<%`VKQsFABGON_URldrsQt2vRWv-SATVa`5r3SY0WoDI1TRE^+ zEY;VUrAk|!UuWJ{=hZ}hGO2u>xmqf0g@xv2KEKecQV~^HXqISVD_?2W1z=X4UujmU z$SSNft5nOX>Q#lUu+%Koz*fH0tnW`-`BHPWRM-k@%_=pp6}k{BMnSiE7vf^6XhWJsT$Y{ zorq_4BA&eyarIt>t=Niq_EyBTktJFY&um3Jdn@8%spv(l9K}`jUc|Lh(TjLyFXGvI z5m!q^TCo}N?9GUar6R4^jCl3~oU5f`5Xf%Cvv(sdmWs4uH{#h(aITh$v|>Br*^h88 zmWo#^wj-YX2zI+RnbOd(%d3eqma9 z)5dD4uob#CF0*%StX)-K?^dZyD_`%fmI_;8!CR#UX@!==GZwrhnxqwa63c7zFx~w{8Fq0)5H5SgNmiOO>`dzvjKIzUHmnU$m94 zc~?t?tFP4h5;*MN&0k4&cF5tRXX{%sM?uLV%*#vw+ z6Yy%Ouod^@q6v8Es%|*hnLWT&YGA7kM?13zxKz*EYQxdaVyp37^-a0es|s6jS1wwB z7q2R8#a+2NK>X;{YN@alx8iM)nb0D<< zVOlw4QN01&R%{NWQqKsao27|y2XFTgP z4XOsV0%f5brD$TS{XRJif|R3F4QvI$=+uUzXth** z=s2_{Wuapmj;h5{F$g4Op|%=F(PF8fEUu(1)K}xES}PTl1&_vDa5QGMRC)1uRY_Uk zY|LV*vZ9I7R!&(IMe%Ay$Rg+}ux)@Wu7oUtt^yL36Yc9Ws{+Pi17mR|V-a)}P^It` z5sRR!fJEUbA{Iecfo%g}!L9;J&{aU9vf=TEB4KfL!lHJc`l&~H_%WygzyhZpNtBLq zz@k_w97VnYrydnWm2GxSIs9|Jq9_VS5wF0hM@3OZn^nrupPzbE6osQmSK!p6q9`0i zx&o&j)kFbT@YJIPjRA_Ha1`MRbfqeaBBRJwpet2T6d6Uf0$r(!qHq+^3Us9^io#Ju zE6|myC<;fBtUy<)q9`0ivI3_b6-D7Ff)&>Qtk?inC_H_Lj#H0nm4d6_sYeS=Jt~UA zQRFJn7@#N$M-i*QsYgXoIEq-s;#fsd6pkWQu>@4bwgXPbCqIu$T%4*XRtiTEs#pT3 zLPHc(ii}!` zt_o8Ts#wl9I^R{{Dt0!4f=PIhT!dm1imh7X3eI97XR+*y zyB~6^cm)7j=ol?{YhT>`pjx~K09xoMA*!0Ush6bHtE%u8NsDD)-aW61 zF(FZlWnbPsuL^GwwOID`-SevO7FmnMJ6cq)E4)S4V)2d^RaJP4u*KrAMNt*7g?5DD ze)X0XRaO1nVcumSZLxSyi>fNdgrqGN?`ct0g|~=XEZ)?jstRurw^+QXMO78vB5$!c zZ&6i+x5!&8&RbMf;Vl9eivt%`Rd|cQ#p1w4RTbVMaj`gYQB(zSp-6?doVci}>hF%; zVq=TN8(UOW;VmK;i#N8Ys={0BY_T|VQB{Sv2wg1R*`lfnZ;`rCx6~kEfL$n3c@HGH z1@1zTO4Vdc2=GFYO4Vdc2=YRa3RQ1zQT(-lUMNzjx(mJU@mf{Y-yOY0_Ckk!C#vuk z;fuxLi)yX#7U_${>5Hl=yhZ$C@%9!~Rd|d2Ef(i5s;bB>0vL<;x2UQjx7grfaRQ^N zirgZCv3P@vsw#4e494OeE{dvvFchiqmUpSMz0Tt-z@e|PYf zB9*GL$=SEK2^}vKsZ^Cs&a1k&6sc5|P0p*jw-l*Vl}*m8y0;XmRFzH6tGc%osZ^Cs z&a1k&6sc5|P0p*jw-l*Vl}*m8y0;XmP<1Y&=mKyVid3rZLMP`kCU6;wRH`Q4LfZ>P zDpeD2q3?wvm8yxi_T6U3rwh4^?p#Lo*MhgmWpqDYq^b&Uk;~|Qyhv3Q-XfRL{d|$C zD!fH5qx<7Qdw)_EpQo~ zTt;^;qgpGxMJ}T|mr+%Px5#C5=Q66Q@D{m@?p#Jy72YD3(GxCX0+-RrW%Pv0n9%>C zlgsD{mob6M=;Shb!evb0GCH}8?p#Lk*8-Q($z}9?*Zt{?MF)&dE~6)0#)J+Som@sw zxD1_n?awT789m`Lbm%oyIVMcFj0rt36sdR;CS1mZ9vF&LswQJXG{I1$LN(zsCU6;w zRI2Vb{@F1hx?m_$shW%l(FLQE%jgN0F`*5HB9*l!V?wmS=;Shb!evb8gP}-et+L7a zUklzMm(de0V?rYgMJj7e-nVu`9!EsvGJ3*gOgkuLs`OUEWlZ2Q6sfoZ370XU6^0^} zs)@IDQ0jOE$Yu0|%b0NDh$5A>Cf?dXDXW!p83~s$p&N!Gm9-|`0+*pkrD`&l0WL$4 zO4Y<$;4(V7jP7TS6h}nhGCH}8o^TlxxQtFNqx+#F#ahu5qm#?%370XUDMlxk(GxCX z!m%TrTt-j0jA;j@j@}}d(GxCX!nq@zTt-j0jA;j@tX6s};W8#1JkrT!^n}ZpaPWvC z6^>1~jA=KdT><7+!evb0G8Cz(HQ_QQ96i#>W%Pv0m~iw+CzsI^E@Q&kBb{7EPq>U} zH{|ixBA3wU}H>A}{ZzWvDgwsblxs0B08Pje^tCikLxQq#1GCH}8 zk#HFkxC}+Adut?I#)R`n6sc5A#)LS3M3G9>WG-VjxX43d#> z84dk1I=PIIa2XB#GCH}8k#HFe{W27(ysomz+4+Hnei@2Xs%pybyej4i$z_a$%V;|& zb@UdwjFE5|4gE3{sk{P#x7rR$S*^&ek#HFe{W27(s5Rj-8n}#3E@LEIMnk_0MJj6z za;t&MP^3~d$gPH>NCvr#aceqya;CK5D3U=gWB5@dwfESDvq%)FyaGXPHJnAFNTq5p zm(g}Z9$YZUWeh)zq6ei;p1 z#vqq55-y{G%TT1U*2G)jG6uPfk#HFeT!tc*wI;cR^GOt`R84XVT*e@mF_L~64P3?` zmoXA9qk+p%q~Z!BTt)+zp-83b{xWp-O&(mvAeS+cei;p1h9Z@pJ3tWaGm8wZ@fy)@=GDgB>G;kS% zT*gSaj0P@4k%}vja2X9;h9Z@!iMPOI400JG;W8Sy3`HtyO}qszW01=j3765pWhhcv zYvL_%8G~HLNVtp!E@P0(7zvlrz-1^>aRm}Cqk+p%q*67>EpQowT*gSaj0P@akjoee zm(jpwC{lR^k})B;j6p7ABwR)Vm!U{yt;v`WT*hF(jFE5|4P1sIm9-|h1ukQ-U&ctd zj0P@akjq#TE~A0V800e6gv)5)G8CzPUDu>vMgy0jNTq6$Ti`MVxr{a8G8(vy!G0NQ z!eumY8H!Y1fy7(jG6wr)tO=LVz-1^>S!?1ga2bPK#+q;$4P1sI6}2W@#tbe)kxJDd zw`On|gIva%a2YeWj6p7AO}LC1T!tc*S0Ko(8C-@Um8!v*aK*H%-}KpB9*lUxiy2!P^3~d@fNs@m0ZS}a2fM%$OG-6 zNM)^wx4>nr=Z-L8L$z`kwmobCOSjlCq370X0%UH=} ztVzF&8C-@UmA_V!Ti`NQav5vFWz66*R&p6@!ez|hG8Cz}0tuHfgUeXSWvmI8F@wuc zq_Wn;Ti`NQav5vFWz66*6sfE=$t`dhid3p5xdkp`C6}=#T*eG8V&QZ;$s0+*pkrD~E};4&1cR871EE@LH^u_j!`3@$^Fidqvc zV+NO@NTq5rPY5n!C6}=#T*eG8Ly^i_6K{dbSjlCq370X0%TT1U*2G)jGFEaKYr#_D{=+BFp7r_XcfYuM`|ic77mqLg_2Ij_&;IepyZgt-cQ5|s z`^Wtsf4uwh_kaA|=YN0qnYLQ$XZbL%qxN!sg~bZn6~3(_Jav4aRP`ZK^(!n@zrvLt zPOAElsru7P1oE!)f&VJ0ZobN)E8tHrsru8asHzVgYsD&uRDIN4RMm$})t_Ec^`}=+ zRUa}{A9YLBN8LqLeaKY(=_OTvdKFdmAyf5{fmD5DP*l~2Ow~sQQuU`-Q5D|8Du+}9 zZ*9KHq1KJ`7IvQ&YlXM4%F(V^<*2FpDu-&Nx3J1lRCRA%vC5%Z6L0w{hniQ?Tl=Ky z>8FdYa!8fl!tT@J6>x7|vC5$rZ;?n2YzXKAE>` zzs$e=^0GX8wg=?z-n`sn@z-x&y?y!O{`KSK>u(<(US9t1|N7&ll@oCDv76dp@)z>4 zTkQw(p_@ec@bgw@MNxnDT`_Xg?hE^UilX>=FmRKo{X9icfAU>1Zj-1z`HG@GsJLR- zCQ%zy6h-~Hcg3i!U47J66LpwYzdj#(4$~Gz@zeuLt4i&ucMv_==&QfIeYkvn`P0k$ z$IB1*-+im0vO74^NF6C2FG^iTV>*qV@zX zirU~tqHb@A?mF)WjYU!Y*@y9hMBUyJwde0a^!Qu+`w;#=hWhgtf4Ce5_g9VkHMqYG z>2+YmR36f+7Xy640fNq+KYru=AD;ScBnqE!e4wM}&x>MsaOLnoC(j3>?h|E&z1?Zo zlli3f^)WbDI5=2*a8MMrTT?B4{nk{ac54}%K5xd(~TQTsCM*&oWW2Z_>AeoRQQQaB3KgTB6v z<%*(k6rcx*+E}hA3P*u?kZ9m2M;>%d@e-?Z=7S$fpE)`T#6#0D^XEk!cu=Kulmid7 zYwEnir0_&Wc^`_Rs12Va>cb~}{lHO9J4lp{a@wI-DKZMMgDMR&%2@|hinrIrS%+e! za1>AnRT?G4IH*!gwdz#) z^Y^Lq4HBiJ{5+82*N3BkH|Xo{Iwu|Fbb~6TqnvK2RqAkqMCmAp8;YWE6xfEgINMMZ zMMeQ_kZ6!mPBu&n$Oef9j&iU;qI8ruoG5;MI0{^YDh(XvSc591qx=|4pwDh)EqC(U%y3^U3n z&5D&GqcCZvN&`n>PJF?nnM8w8pVJKb`W*H7oOto;W7Nkv@x|xFi=uE8=foGE6EBJ) zqc|t7^W)EFl#>j)rpzdx6R%Z@IdO$2UU_^@yeJAsaZY^kIq{+>G79Y_)G{Z?DDN&Y zDLnc014r#HJU;r+Ttbxwj`H3Ts+5lM-V()Y3P+)}genb2eco9@m2%YQoh6Eu!ck}} zp-Ok1lcPTGE1^p1DDNv#tJK>{NR*E9<35U_a1^>qsIya$QQlNSCyX(pys1R7Qe+f* zN~qGnQQlHQm2%YQEhUPTV$_F@5~?&9^?5@HRmxGHHJi3ynl~-<=DK+eDpJ>S3WR`RAvx z7oQ?frF2vzl#U9f2o~S^ zAW=Fhm?F4M)E#drOcCho2afWM52}=o3Z@A3u7O*MjtZs-ZWDF(_35Z!ieT|60)2ft zDwrZzoU3WiFh!uo8G)mGia?@tR4_$wo2WZpQ%n)4(!fzZMW9OQs9=g<@hJj{(ow+_ z!EK_>zCJT5m?BtwyMrpFqk<`d+eDpJN=F4#1bWwSn_`MUtyqGL@+ks+eL5xQD>FXQNa|!ZKBRZ>8N0eVA)-0 zqI6U+MR1#_Gf_G!m?F4M)R`z96-*J_ChAO-85K+sEIvh`TZ)bfrU({qJgGCb_#PEZ z5!@!~j$a>B1nR;RILg~js!}>Cm?Btwia?@tR4_$wo2av|Pe%n)1dC4*s8TvAm?F4M z)LEr;)K5+k{1@+0-f>cu(ox=Vvi9inhLaM7qb6@SSrheslM;oaChs>{6h%g%-K3g@ z1sUbtCUs~XMt#%X-0tkVsW+RHC>%9;v&rJu*GTbrOQF}KzJ4$>;jJcBDI7KJo$XG4 zePk3mO{&u1J<7LWs!}*=@-3LfYl`T<(+p__a2ivu#t}P-Iv8m<-+65j~0`v^!$5N_YRY)6d5)7-pgX8HjOP& zI?A_R7DeGG^q17vKkumS?Il$y9pxJ@ib|W)mC{kcwu8M~^MfZl1 zI#ZX93bs{r-&P?}Ix5&!(S2KmMCqttTSfP66%wVRf^8Mun@LKPjtaI_bnhi8Q93Hv zR?&AC9&&%ewhFb!Ro;$O6jOzTSfOqk`kq(f^8Muw^c}#jtaI_bl+B?^Q7sh zU|U7^E|L=e4@CVvY9ccshBpxPnTd(agxJVH)Ze2fY^%@@b$(`|`?d-ldQV3M%tZHX6%wVR z0%oFvnV85-OaU{|eOrYprK197qJx=G`x-bZU?w`433XYaXy7O?6BC((fyIGtt3JOk^gefSKrECba1tKUBa>bTAVNPl^T^<*kOA!jqywMuC}7cv3XT zC@>QWPl^T^wku zPgWXa6qt#L%)}Hh6CKRNL}p?Nn2GKOb?WQWQ2{g2!AwkKCZ>Ry=zdJ6Dy5?WW}<_c zn8-{_0W+Zz! zXff%usM_(lP037XK0Oe1W?~{Up?S(c6mxxKCNxzOh{921CiJ!%h{921CiE5%h{921 zCNyRVMBykh6AG9>6pkV@p(ku03P+KdXaO@Zz)VbJCR)Hu3@{T4PsB;UObjp+3Qvj# zjsi2G@T6$qC@>QWPl^VP0yClTq-fwMFcS(-iUy7XGokRLXy7O?6ADj?295$Vq41>W z`HUK1CKR3!4VZ}mW!!jqzbqrglk zJSiGD3e1GUlcIs6z)UDSDH=Em%!I;|qJg8pOej1d8ZZ+B%!I;|qJg8pOej1l8aN8f zL?biN0%l@>nP_AtTEI*UFcXc;L<^XS0cN6+nP>qsF~CeTG85{5e|~@lW}=aqP*?dt z)JJ`d%tQ;Ai2-J!k(p=#GcmwSG%^z{U?v8biAH8Z?V`_LQ}mf=WG2*xHxTvrs77W& zO+y1we~)TpCe$}E5cT({MrK0&=mJrHk7{Hl)R8O@)n^V|Un4W2210=-97SeAjadRw zpP6W6CR)Hu3@{Uo%tQ;Ai2-Ip$A=-Kf<6-i%!E#3qG;eKFcUi5hN6L^z)UDSDH=Em z%!I;|qJg8pOej1l8aN8fgu;`efuq1oC_E_|I10>!!V{taGcmwSC_E_|jQYS#C_E_| zWE7YQg(pP=M}e78cv3WQ6qpHxCq)BCftgTvQZ#TBmqsF~CeTG7~LeCI*;^MrNV~%)|gQ(a21+fSDLz zCK{QE7BCY7%tRwI(Skk`1I$DtGtmNOVt|=wWF}g`Objp+jm$&~n27;qqLGgs9qR)iFla-!#)VjOSDy5?WW@6o4Xrg$JngeEHMV|?UC%^uAN3DK*r>3Ow9yJHd z#0q9Y;fYEEW?}_1q41>W`S++5%!I;|qUYbERxlF^Pl^VP0yClTr0DsXi51L*!jqzb zqrglkJSloUqgF5z3Qvlj&!`p5gu;`efuq1oC_E{8KBHDJ6ADj=2F%0?WH{;O z@T6!k>H{;O@T6!k>H{;O@T6!k>H{;O@PufQWPl^VP0y8m_nV5sKIaV+e3QtxVI10>! z!V{taGqHl1P&2h79@W@08YF$c`V3T9#^GcgCu#0q9&CNnVy%)|<2VkR>&2h79@W@08Y zF$c`V3T9#^GcgCu#0q9&CNnVy%)|<2VkR>&2h79@W@08YF$c`V3T9#^GcgCu#0q9& zCNnVy%)|<2VkR>&2h79@WW`BC2nWVX`Zh2V3Qvljchm-ELg7i#^Y2j`m0aGjSy|aSfP>4a~%q%)~WdCN?k= zS27dVfSK69OkBxKTmxoe12b_YGjR==i4DxemCVF7U?w&&6IU`5*MOPWz)W1pOk4wI zVgoaw@I;&h%)|y};!0-X8ZZ+Zm*o*ee)I6x%WuE9e7fpi{r-!~|9*M@`p*x~FTZ-YfA`|`pD#aCyQNQb`1AJj zyI=IXg%-~6_%O-dLj})oeBc-aU z51FbzQ>1Fol&Y#eWUBs9k*YmZs;cl7M!r%_yyZh*olZk<`OvpoE4+oVuR59}-txh( zYNfY)@LR0aN548s$Fo|sCf@SluT<$RAO0R|JwC7h;mtRHd3d~h`*8pK^3DC*%Xi^=63n(<=Ll8{o(AZ?>gUxCHW~2yGx&bHv8(kMCo>4eJ_f_>{xwQ^AbpeE>qSvm9josWHLDjz;dHFNOVpfR6h(+)^mff>ieP6V`{#5uJdN9!Km}XouE^?`1M(C?9KgcF4_HRzklwOW%a2KPaeto zz+JNT&o8yKEmsKJ_Z1=dGu_s-??3b9R+UATfwz;aXIWJiE(38V zS$A1g7Fh=7PO_e5Rav+U)SYA_mpON*cTu?PM*IXf7+i*KMXEM(nX`AQ7Fl+qeoj|= zV_=V?8qjykcAL=oFj%VnWH$=-C=32hvWd%X9IVM=#JKrMPsIo0jf6E>WZC9@i^{Ta z87Mqmgv4bx8rG^smTlgqC5 z+Q?(BMexN-$<}1s>W#IXi&3hn~W#KXqeUgn_=1iX!A?Y&jgH)~-E(6u4Y9p69*QaXfGVg^{ zt`;r>*{5nFmpR*~YUwiXhg7Z>E(6`CY9p6$&3BYGsM+Gxb+U6NES-^=#?EJ3yU)Ny=^K1s{weUhs8t#?XNwRG9OzI?t~ z@0BF*gR>tyCl<)UW$2cqix9cY`z5Jbx@_;%@}F0GBm%zr+uMiB=a)adynnp>aR1%6 z5ASw}?(*gRyLWGXsFDKf=GRXB!2H^2|Ak$>sA!ipP8sXnkwo`zeD<2^ zGasHt5~ZV@c_>~}8z)JWj&kCmC<;e`chJ`l9OblwDy5^Gb|_W~M}c)vrGcY9GL3eh zf^iTi`BRQMrsimmm-g)W+so%Kzkl`O_4ltX(=XdU-Cg!wT)%qr?&0!(v~TO*H*Kj` zVJ~mm+HkCgwmtb{WKn1Gqd6-}*%GxujYR!1B2oL&MNxZP(wBOZ zA1^?$RCtODUo#fIDmkL73R7|2OU=oHQei5tdZ{`2QM7th;VLeAsXO^mwRlzGDlU1c zJNZ$xS}JVC6)&|XKdKf>g{`>Wg|j`1rDC~@hkGpQPkz2s->Rogue22wyK48UZ`G43 zqsrI1YF8C2T|C`G-+wReeNsvhGW5Ed@wNkxXg?4?@R#@Gt*~;5hNR_to z#jRqgNGmRF;fRmwRfVm%vV}7~ilxFY@}pO)rNUNR*1{nl#ZqA_E^6VBk7}u~ z71y+I%15zO*orG!IOU^QDi*YO%*TRbK5C`Nrm9J(MONFht zmZetZ!M%#5EFScss~V)0AM~N`&o?V9WEHO}Y{hjfH7h?}fZ|n!t+b(kE zaS==1%8#nWQei7DVcoV!o*u4X1&e2WEVmt!A5?3l`WlS-e$ZCF22;GMz6c{#+R7JU zilxF3n6}G|>-GW0uiubCo(Wz9<1o|3XtyJtz=BXblHL;a1(y5;m)5;g= zilrj0ut=v;leF@4KU6Ah<*RhXQei8s(y7$MR=XFEQ^8oKlWLGwzD%d@&-ry6;|q0YLHgD z6|GdH70&*smMSlrDr|+rKZ;isw&F%)^>aL?b+uI3iu;gp`bV);q!o7|-*!5F7_L=I zg{`;=8OMJVOGR373$i+xpTDX&|3l6HkXCA8epD@$it|6z_8RY2YGHm9tzA_d03ubS zm3o*TRg0yihGaM#QdmQEETrG2_PypuoaE~(N)DDP^}z;Qei6` z0isfaK_JcmQK=XNs*__-Ds06)$7Yz4%E zr+`Q`u$7+zqCTBWtJ`%vxo&l91aL?z9s{CM16%nqASx9zf$C&_{HdxpfTtDD0a2-e zt+3CSeUT-a*vbzA(FLHb0?Ojn0Kk4K4gwR(0w;l}RHjuxS>PlP9eu#GN+=5)1tL|Z zRX|zbC=iL#RtaT+vp}TEL0~{x;4Bb{(pCv&fx|$g%Crh73mgU_QM_BBC35iz;4P7* zN?Qe#1x^EzC~bvZ#rxppNq7mzfk>6M3MdO42cq`Jv{gb`;5-ni(pCXwf%8BlN?RqA z1r7v}Ds2@|7B~<@qO=t@6Blm)q!lR(ZOJ%hU~Ra9oy0s5WWk9bMO*oiAi4mwm2V_2 zmg<8*9tpB&htBc)7fS_Y!81Xm8VmwKS%_cs#ueJ4la%UH7CaP0r3QmQY#`>LAQDa9 zt^8CFo&Q5y`TpVB4S?OlS`X$`O$LE}EQm^FTKVSTVyXUar3q%1nhXN{To9E?Tlvo6 zVyUndDT^!i4c8u4pe*zrhzsD`hHIsQve3|yqKU0QStwbl8rTXuhV=-fXksf+7Pg6d?N&U#u#mFQ2Cm?_imk%RQI;A^S?pG{QaK33M&X*R zKw0Q$EtKl}glo0}Wx<`U3wF8|gB6qox4KF-uobolbE~UF%~r+lug@HRDnb_6>RJ@_ zi9p3De<^cSQ4~W!G8Wf>vDkLp$-X|b${CAdr81(4(o+FqvF)^ziPBS!Skx*7VR2X|aH2^GbTlK9{29*OA#Y*8Q@)g(sT@;0*$X8$k zbWs$JB3^+F&_z)=ig*P!Ko>>fDAEwV5v{m7T2T~*qexa@19VXojv`rc zb+V!;3P%yFzy|1|C>%ww0*AWPM8Q??P?rUVx)ep>C~_4z)TJm2M-i*Q2I!(F9K{yz zi??_$io#KB@V4Roz=kQmUSwrr1^8TZ&Su$|mQYuDhyxOIb=) z+2p*cdrM(TRoUdcs(VXmN>$n9ysCRkaZ1(GskL8M_m=XMsq8wWCgl_bWvzRTFRRvzn$#Z=L5WbZ70Xlc~~M z4p>z00eFjmg|1m5Vj+AxP(>pPMJn#B^N5A+0d%rZ zq*68U7CKodQmLAF3#}{`LKflylIsd@5wg%CbD|1wk+N8vvM73MH{{W=q%5?=kkkrq zv6;o<4cqre_)|pCerLg3#4I!^cC59k3U9HSg=QN9Rd5yyyR|RQSrlspXt5BqSRAw{ z-UDc7v9O)R;-E#fR^%4@Su9RkR8`?Ek`{}T7FAVvi>Sro4K1pw@D@>v#Zil@D!fJ3 zV(~WZRaJP4ti|H2MO78vB5biZY*ADNY@tX+7C3BCRn^}epM<0>7Vl|MRmJ-jX^X{s zT2xixE#el7H?^p$!dt{G7H?`%RfV_6TP)tyqN)mSk+)d9t3_26-Xd_ZIB-!_g|`S? zEZ)|lstRwhuf^iTMNt*Rg(4N+a^j+@s=qsWi;XQ7Z){Ojg}2z)VsYf6stRwhv&G`f zMO78vB6P8MXN#&TyhZ9l-BN?G3tC$!Qh5*9n6O$ayv5!Yi*pxMRd|cNEfxnas;cl7 zn_DbSUKCYzeE+@B8Q>l%o0_2iy(%MZ%S0*Es_{I z1t(F3w}@ispq4}x-Xe>!IEzuev*0bl7>jqgsH(zSq%r!w4E$lXyr>EsLy_v<>iaVA zc~yPr=q>UX{aNCz-H@h=dBW~}E~-}m-Xf9Foye%F!dpZ#x+57?Rd|a`Mt3HostRur z%IFSdR8`?EQW@Q;jH)WUMJ%H`mQhuOx5#C5=Q3)ln$^VpN^d!rQB~F79bG^!qdS*T zRfV_6Wpw8&QZ*P8PUv}|NTq5pCY*Ld+OLJVjP5-zs`r3vOOeVe zka!DRh9Z@!iMPOIC{n4Kcx!J$W4{)?nH z%ejnVt>7{gsi@VtjH;^s?pQ0ijPAWJs;cl7xs2|;FRH5W7P*Y>Tt-#Z$Aq0+Mt3fw zs_J9HPA;Q6mr+%Px5#C5=Q66Q@D{m@o^TlxxC})q@7KgzJ1AxME4`I)856jSPA;P- zT*d@0qm#?%&SeyTEpQo~Tt-j0j0qhu6sh>N5-wvx2Mk3jRg>I83ye-KqbFR3jwtmz zi(E!exD1_A2~~~>6E0&y4~$MOqbFR(w1ZMdZ;{LB370W}%jo1XdctK)=z`J7W%Pv0 zn9v2IlgsD{mocFYh9VU%NVtp%Z7>w6R872vJ{XErswQJX^ubW1QdKrN{a%1Z7>ZP? zChuElgrP{KYLZ*%grP`fDYoIavR<*$|G)^13<0?e(1%b0NdNGF#u5-wu`m(j^(jD*XWaQ=uQ)vxPF zxQq#0MrWgpk#HFk4j}2|GDgB>OuHeE_W-$!k#HH)Zb(yww?@KcOuHdX74KUk;WDP( zkfsW6jfBgXc2LSx;jNKy8Pje^Q^ot%NVtp!E<=$D7bILpL%$3~Dpi9qVcQLPyaMDh zM#5z@^vh7BvesZs*mgr&tr!!Igv)5?m!U{yt-)MI+YM>8(pw3a(a8H!Y@Cb@-v8G~HLNVtrKei?&Y#_;nw7r3isWP_`E~BAe z#vqq55-y|RSdu|5VMgx~I*e_!wTt)+zG00_%gv)5)G6uPfk#HFe zT*e@mF%mALfy)@=GDgB>G;kS;R6GZgei;p1h9Z@!$(Rsa#vqq55-y{G%TT1U)?`cw zE@P0(7zvlrz-1^>QES3wG;kS;RH`OpLU0+1RH`OpLU0+1RH`Pq1ukQd%NPll(ZFR4 zav3A(m(jpwC{lR^5^sUaP^3~d854rb800cW(l4Wd%TT1U*5rK)T!tbQstK3Tz-1^> zshW5TT!tc*s)@J2Whhdqns^Ibh9Z@!$y^4w3`HtcllLuf8H!Y@Cf)*YM#5z@a2bPK#z?q~1}jFnu*dOHmE8C=Fn zE@Mr&j2T?UN-kqfxQrQGh9VU%Ncv^W;4)Tn8Ee92%-}Lsav5vFWz66*6sf!dNp6A5 zSjlCq370X0%TT1U)+D#UWhhdqn&cL^3`Htb6E0&0m!U|dYLZ*vGFEaKYr)$e|(+LNfNYL6nR`lCpy z_9&{V>O*#2eS|DkA0Zd7t3G6^K0=nNkC2P1@D^rGrJ8ulXH9io=`GBf7HfsKFl(wk z9*MVn)>O69TbMPi)#|gR(-pI(sx|SJ&zee=-omWuq1Iz|&c9s$>F%;WsUP25re8Mw z!yn)5Pw(fqfBE_I`?rr8+x+a`|EI6N`1$2$%O`)h|K>0HFJJ%q51%}H*5~^3dv#hv zZF2ei2CY#UDyk8MKfhJQK>wm?YK9-u{0ADdjU146rI_xt+&D556n8z6K` z@$u;!Ac~@RdSd^BDz&F)QPc+}S8RWfs69N3qIh;<_k%=towL_epE(T7H1%dvqY|}8 zXR%T^3VRnJb=q8g?+7xRH`Q4@|6<(TJA0VT8X!Or9`UkEvY8Cg?+7x zR9pdHDXBU3_QG`>yI`e6=RpVFy1j87Rk2bc)xcY~S1wbfw|u3fdIc~h#7c>34ZO8r zU#lXOzgFO_1^ZeRsZ37Ea_KE6w5qkjTOhPlYm!^OuT{0u zTTWRV%&agjTgycngG_qD24ddmr|Vy#YSNtNDmLaV9@ zZ-LP2&z#Vzs=`|!w4|DN%lEZv;7M=!zSe53@D}#9s@B9?zOPla(p%ndyjm-~g?+86 zHSw13YgMiEmiHU4)(UT7U#n_Oyyg2^RV%&a`&x^&`o31F(p%ndys8RsVP9*1=KET! zs_+)}wMsSdmhWrTk{7+@{l=@c!duwas#+6o`My@wN^kkT)@rTr7WTEO*2G)BuT{0u zTYe6FwN`iw`&w0N;w|6Ts#@tS-`85K)%UeZmEPJn0-c?MUwmJyUhMh4weJKvuL^Hr zUuzffo2cqT#}PdCwMtbsIbSQhg?+73O}yp%T6JCNt$iEa`C8#E>}yr6iMM=Tt7@gU zd|zwzeucNNuT`}s-tv8|s+HdIeXYe>eP63o=`G*aT2)1EVP{@{<~#GMs_+)J=1Dd2 zmhWrTR2*~5_vTe=g}15Lzg7nGkuadKuG9Sx>PU8 z4GE-?Lg+oxJ17X!qzi&{xHG6AN=JH=E+0r!0YQrJz3)D=a?e_KCfTz|qCU^{`SX9T z?HT4(QfuN|VxDCm0QnB=u_D@2!3&@x-F+IhkdT}DCcY{6=MD@2!3(DlZ_ zYUc?Wq{TC zR){X6pmiBwwZ0Xi%P44F23W0ch3GO0T9*M<>swlN>zNN|T?SaKZ-wYG3R;%|R^wYy zh%Td`bs1naz7>V&G74IkfdxO~TTzHEqo8#eU^Q_o3eja0v@Qdz#oUMTHn$;SbbTIZ&_VNq<66TvKrsAx{OHgVD)7+zGZb8k>0`T%W8bf>N27b zT}DysG9do2z7?X&C>mV`LaJ7#L?OD2qTay@Ns0BX5M4%5*Bb|`^{o(HMp5rz1*`R~ z5M4%5*Bb|`^{o(HMp5rz1*^#kqYzz2QCH3ZtH}wY5M4%5SIz;ejawnQjH0fb16CWi zLUb8Lqsu@@HC_;+%P8u4^@z7?X&C>mV` zLaONlA-asB(Pbc{TGoK|t)i}+Q$R?ytVr+LU56>^$~j=Qz7?X&C>mV`LaMbj#J6<4 zaoB3(R){X6XmlBo)n#DocSyVHoG`Mw3~YZ5VbwWdWOW(Xsv5$ob3%kv`?dnsw~9uW zfskrgLv$HMqsxe_E+Y!jWfXP2@j_&E8BvHXqp0hRgVp+0h%TdObQuV#wp~MfOV=BR zt=6|fbQwjX%ZRKlBMQ-F6m`9E*lOceh%TdObQuV#wp~MfOV=BRt=6|fbQwjX%Ropq zwub03ibj`#l0lX=ByJg928z&F){wZR>x~ysp3brctQ{A1y>YNw-wM%X6m`9Euv*^= z(Pb2kE+ewKj3`8xQPlOuVXO765M4&m=rRye?b{0REnROMwp!l`(Pb2kE(0Oe*czhC zC>mWxWOW%)h%Te3D<&5rtILQ&bQwimG8wGaw?cFoMWf3=NVV-661Q}{4A^RYD@2!3 zG`ft)>N27bT}IL9G9s(Xh(dH3MWf3=NVV-6;#)?S5m{YE6r#&08eK+Ybs15JE~994 z8IjdxL?OD2qS0kUR+kZl=rW2%ml0WAMiipUC>mWxWOW%)h%TdObQzJ=WkeymjH1zH zL{^s(h3GPhMwby;T}Bk5%P1OM212Uwtq@&C(daTFtILQ&bQwjX%ZRKlBMQ-F6pbz; zvbu~YM3+%Cx{S!`GNKS&M$zap5K_(C3eja0jV=Qr)v|`fEu+hbtS%!8(Pb2kE+ewK zj3`8xQ8c=Y$m%kp5M4&m=rRyeZM%lVEu+goNVTjXa~VdL5m{YEHbj?EG`b9gRBdZE zM3;e5`+5f2>N2t+x{RXHWgw(lTSLCLj4lHq)v|{8meFM(q*~Sht!~liG7wTNYsfsI zu9s0jNVTjX^Mtxy23U=6WkYlsMWf3=NVT?x_?FRSM7CZ=Hbj?EGP(?eRAXz1E~8|0 z83?JCHDE5IWONw_sg^asw@OBrfskrh1AMDwbQzJYmyr$8Wt5CABeL}}vMqHPs^H?# zttatRmCQI4?VsXbbg`rhYZMTBZBqp}VM!O(0IPMv5CKO?7uEo)b;1w;*Kxn9EiP^HN**xfFo-K9N7>7 zN682{vR1&64H0mZjDRC+1svHB0Y}LQII>p2kqr@Wl#GBQYXuzH5CKQY2sjXXO&a&j zQ8EIKtQBx%TM9VR0WMlMDrP26>>SZG$v3(cU6IHhMGB^~^$>&#$!!loAjRJ(Qk`Oh zwCxldq)MF$OLc|~(zY{fkgA1vkm}eD(zateNYy$#NOfojY1`kfAjRLPHr0_Gq;03y zAjRJ(Qa$)&p(krsF@W3}f1^lsat+e97YaeDzFVgtw*)5cm}EQD3e&j(zZPcq{gF6UJcT=Jqo18qfE98(zZPcq{gF6vJBEz9+e&- zdrGcnCQs=cKXSsTQN9BujuBR_lCwE5PPS>=Rd9;1autwjR{?3;t^!i!Dmj}0gS2f| z0jY8okm>{&q;0zjNR_LARJ#gD+YUY;RjvY39ehCAwyS_txe7>i@BwMtt^!i!Dj?Ot z2c&Jg3P_c!fK&$`khXG_mPZ7DR0SW9>fi&?wu28ywMW^^H=k`k^Ti3;+M{gZ3(^3O z(s^&r=Di>d@F<=3g4B9c`)My8-*}YCdSPiRk4g`evpCTy?|-5bPEJ>&QPvh{#t~tv z?P%VtPILmP8jV0|+RoHx_9Rtp2U0T{xggvlq4gxiWj)ydNX=;Ef^gfUYBU0=8I4>J zZktq%Mj$n#kqg3Yld91Oq-HcSrI|h3RE+>N0zh8jmumFf47~qfo+3TWV5akgE9ZX{qrjGsz56^2|7-!IKo1r9H}|!XQ=g z-ILUKlu3m_s^YsRsqrY23WHR|cTZB|Q6?1zsfzEOq{gGnv@u9keD@?Z9%W{Yao}Qr zN9l|?YpXGXRK<5cOHIaXi!p<=l}Dwc=CDaqCy&nTJr>6ydVf}Q=+F8r>Jg|ZwH(St zq+Nt9Hp}pct&qw^3T7q zfmDrUo}_v#E10niq-relB-LXX&hD}=s(p`gH3ig*(%C`I?U-!$?VGU-H3*EQdMxvM zd_9(BQG&pdw(_X-ST>6=Rsy?nu6#t^;wqPS*R*bXD%?*`_MMp-r_r z;;c+M%Z$O;k5r2pL8{#mq;01b5XGou9h(reJAzcXqo<`Rz=2c;IFPCU=Sivp97uJ5 z11WjhZBzVBy7L<$BS=+%^R!e2I9O^uO6wRsNmYOYss8+hr7FOAlBxg)QvLZ0QWfAl zNmYOYsSa=;4e%(fVFao1DEBGb?%UTAMvxkhLQ(qmyOf?#!s?pwDEBGbwx!0S%!CqF z*IId0I%;-~8`OPK%Nl3-nNZTZWx=Xn4_MXf@nuybUJkRk)>bv*`Le1P z1Xexd!B+Kxd|B0)2Ub1ift4;fW6bkq#UJ$ydSKOAJy_MC=gX=_J+SIg53DM!_hnVX z9$59T2Ua!g`Le2U53G9J1FIVMd|B1N2Ub1sfmIEBzN{*j0IT&ay<66kRqvJstMx5i z#oU+G_?Fo%o6qVh=Dw`Px6E!?u!i`S-YuKUn%%Ns4e>3#TNbR=xAbmV-xe^wWp>NL z))3#)yJcak^)0erx2&(NCT^MCvamJ8xAbmV*lK-C@0Rto)%cd# zEel&id`s_^g{{`N^ln*STa9m--LkMX#JBWrS=efQOYfHTwbl5R*)5yT>fN%Qta`UB zY_-0ncgy;+8s9RzWnpWGZ|U8#xvbeO3)YahrFYAM)#ikHx2$gqn4Hk;mW8b$IicPy z3tMeYsCUcy+G=t_vs)InhUA2Lw=8V6IicPy>uamY3C(U<*cy@(>fN%i)#ikHe#z5T zJ;4N4>sxw)$(PmmmYHG7XY~w|FRRH3%@h+@Lwrl`mdzognrNu!n0#$DzGWtvU~7nP z>D{uh)%up6W%9Mv_?DSwf~_IGrFYB1R_j}Op2^o%<6CB;3ATp#mY!*Xt;V-D{t9gjDTYIj!XPwbl5R)i33= zl;4-t73hVt!v%lM`AAQ%weL%~ZJZ;q)0JMPhEv*6YW!1igkZNrW_}(g;Jpc%)mNmq;%q9SYRLcrCX?G63 zY<2-4q*~U1oUqL1PtEKjq*_+EN&B{H-$F>WtRcQ-HUc1|T2{D8`?hM|LP)i&A--j{ z0wAOsR=pL#(+kXA0EAS_3O8xH1sz{txv#BoNYw|dZ|N%Lo~*ixIc&AQrB9dlWi@fjR58!z^y%`xtj4!Y6?3qL#4TOL z9A0nZmOfqH*H+_OriwXi4e>2q#T>TUxTUL@``T*amZ@S6TSMZOK3yKRTHn%D%zbS& zam!ROhpi!T%jh!jX=KKM5M4&u=rWKLTGo)brK^}Dp4gmFS26c&S6#&%tTrbM(Pfl% z6?3p!-wM%Xlywzzu-dp4qRS}jD&`=yz7?X&DC;WbV6|~8M3+(4Rm{O^eJezlQPx$= z!D{1Hh%N)0{B+#1x(sZM2*}=yE+c1k8PJ@Eu$s7Kbs5lyhp?KsWpx?35M4&u=rRye z&FB)M%P1RN212T34T)R2iaA`%`c{Z8qil2;2&vZAkhrC*n8Q}X`5tM#oAT}IjHGICazkqgmflywzz*lK+%M3+%Ex{RFFW#mG1 z8D(9?9JX5D3ejbt{)mo-R+o_r(Pf|pgJ!k5j9iE=162qNtIY{RbQxu%%Ropqqf3Y` zqpYi#BO$VJD@2!3HoATUxD}$yC>vcy&gwF9A-asRu3`>bZQKgc zWt5FBBWHCPxe#4O+2}HIR+o_r(PfnN&L1SjHg1LJGRnG&IasZ4h3GQMMwgMZx(w`U z2*_V`6?52XeJezlQ8v1aoYiIILUb8rUBw)>THgxMWt5FBBWHCPxe#4OSywTKt=6|f zbQxu%%g9+>1}e1#^Z}#GKuFc2HcAVGu$s7Kbs5;PAHr(lmepnCLv$Hsqsu@@wJi|h zTe`$zE@yQa`4C-3S=U$utH}xTA-asRF0u$#<6HR2~x;$FI`j$Rj-fxYwVssgK ztINoT=rSt$ba~ineJezlQ8BuVywzpoLv$GxeY!lBjBMNr(PdQh>GEK;z7?X&s2E)a zYSWsY6{5?i=+ot4tM#oAT}H*|GV)fJkq^;jR49~6M?N4^nx{Qj^Wgw)Qw-utxsOZz>As?{56{5?i=+ouFYJDq2mr*ggjJ(xlpm1Ek zH;mC`M~G1E}#z>T}IyOGEhIR6>GY>Rc_t#?)@_?YBgm-CR#U(|FRv9(qnlm{y21G z=fo*plQL^1|I^OH*Uqd}7`Scci2VR|9=7d3R3*=??OXGzXy$h#JHMN?^Sf-BS=GD( ztI9XPs^1$}^?UPV#UJ%#F<{mCMiw8Vs)fB+&HOG{^_U1&{oXuT@keP}&HOG{b-v-r zs@6^-JHHE7oo{%u;*XTAI^O`R9uqxT@kfeP=Nn+v`GzN}nu9_M=zIgLI^XbQRk=J^ z^>;E@^>?x-EB;8efF2XUs>ei6R^wY{eiy6(zGdcj(E`@D%>1sOt$KbJtk$>8{H`af z_ANWViyBxVzNP1PBRjtf))3#)^SfZRzNHV}aU<9)$5%7I3s&n}`t%)NR_$AMeitne z;#+!t7q(j8(&z7_ZB56;s5~W;?HD;RGj#0Kabw0$9hd2elp9W%)Roz!s}o@{84Z&OqjviATQH1 zX0X{iS})TzX1!@upe@)Uv#?eLT5nq8WoFh4v_W2` zr_Erk^)kJk$=h1vWoF(C)&_Z*o;ZWG*30yUCU0wvmzkL}SQ`|}^wb%wwXsZ3oq1bp zVwsscgSA1iOi!M{S{uvsPO#R-GQG*k+gcOL%q}Nb8x+g*HYZqXW0~IOK{MBTCz=F~Co_QZkFceTOF4 zTo&!BqO5PbD)-0R(m@ui%Kd#=Rg49z_I|Lc80*WboFA+@#DY~hzb~tbuwd1`kNG$? zC*#Sg(^#Pc=c@o{87)uJnFRQ=n7j^ z4(rRRf-6{c3JX>hTzy$p1`AdlTfrLQTRMRStMx6N!1~&1e9PpoursvZ?^<_1_Wir>k zLle*fA#qD*t$15DZt1Mm_idTDWs+9d8WOj3&I(&?+|oI#r>$mle&3-9eTOC>q?(a1 zWOIJWY|igHG@hq`8bEj_?8iGau#M*@-0*=GIJSrbAI2U2{|L)^lMkMIlu4FguX))`VLL# zJ2V035SdZC@6ZG-JNBC;D{Iv;DutVQLKIsH$g|Am{JujIpfNZ7RV$7?-=sPr_@6ZI)UN*iJqRZ$zG@)#C8K~T5+BHO% zQ8u~^R710@0lJK`(Pf~nj%5vrTUuL;g84Ql4AEuu9hy)!oAdh)P3Su`q3_UyzC#oG z4o$#0L?&+a9h%U0XhPqi34Mnq^c|YecW6T2p$V+f-tJC-a^Il|eTOFW9h%U0XoAsY z*rHk}=ol~u-*;$2-=PV8hbHtLn$UM>Lf@eYmA*q0j4q?^(1gB26Z#HKz&>L=tBVTH z?SIEsbO|^tMw)%csPG)Zs`nlD9h%U0XhPqi34Mnq^c|YecW6T2p$VafCTu@p#C}~< zGNZdXM`lKJPRvXmF{x`>X4R+zwV*QxW;zDpq-p;%5%dZ0kv#z(Wq8!Y73aujwV$YH z4uA)#&QUMyXRfYmmUA+PIg49kuKT>`AJ4m&-4Wz2*kSD3C z=M~w*-$AOhZJwm6EDA`qL;$2p+U7~Bs-l2YE89Ryo*9STdXnO@o-#%t)dhz@stOKy zlB#+`Al3DTK&t8ud6KG9ULe(yQIH0Bl-^kmQtMHA1=G_~<5A|+cUT(WQTot#SZX}V z9Qy8OsXp@^q{gGnneU#Y#-q%U@2Kh(;8FC#bU!sGzJoNtqx6CAIJU)j6izQ_-=p-> zB}k1&ne*N~+thfJIqn^gAK+2?w0Br)Jj$H*p0YGu6|(0Dg}%dvCifqFNdK+3*>0<$ zTlOD}BaBQG>^p48943!ie9CRp2X_oOq<`m>DU-(RJ#|W#ZdY@dJdT91e%p80kXaXH zwl&NA(yWW3T}?FXJ8Z}vChym-dcQi3uhIJ_P&-mZL{Bg1J8Xy>BvVPjf7f9{v;3a) z|C+3@He>ohjpP{Tlc-@d6{%-3in27LBDJGvx&7>?!kXfW)Mh{B_P-}8tSGKX&G$rJ z>y14hUw=>Fcuh6ok2Y=pd!nMNz(qJ+(~`FTg&@1#pMQS}N z;0wJ%FI1$~qXNFrEA&D|YCS683%z2#(DU{SJsd!lWFzl``bx%|PzPFj6E^j!_{52tS>??j zRo(s=W!Mx7Pf``1K&mr7 zkaGNJ^F`_TE|40JDs%*R6umJ0_RV}3EDi7|J>LaOjYkz&udVIJHy%|s9#!ZF@F;qr zdVJ$i1%39l=iA3+iqv|PuAb;airR^YX^PZ(ls@^|lT^hg6u`G0r4PRLBsCsorlN8M zJr(6iYCOu!M1izzk3yTOj1P}*J<1gZYRgSQYCOsudJRk4_9&2=7-h;Pg0yXq0;%yR zGYbXMwmk}@#-q%M*C6E!Z?{eHH|frA4!p+xc$M+_bt!tGBDEf+OD1}fYL7zjRNqjr zwCxyG?$8rZI8nmJD1F+sr={AX5In7=0Ukv!OtmS3rzLGWM&a?bMjYpZnh_Eyu>(g}+@uF;u()xQ(OHGV2@_SfHo;G6?y->BOjZrMZ)-I_&eI1W) zJxZUx?)UimtV$e-Zex@_tJ0Iy#3*y}I!Yo1#3+64IxMwWpFVfp(^BJ6=G1jq8sJg- z%yn35JxZTb>1nC)C{qp*mIio~K5reCT94AFRC-!!JjxtW2}{Y-rbp?s)?umjD1Any zpQXAKB1o-A=~9TEq$Wn0N{G3FKB3Z+)OeIBgb30AkJ5Dzah$UCC|w89(^BJ6=6Fh2 z8sJg%!t{7*PNxKEK-Q-Zr^MsitWO_K>G}93>oaFl!qR}OPajPQOKsMtkEZmr6ql(s zwH~EUrt~A#2UEgQ>rwh(N>5VbQRZCATtS~p=}Brl${b4x(g2Ur=c#84=2S|M24sEo z!t{$Wr>TQ9z@zk8>af(tD1DZ?XPcTBWlmCur2#QYpGXNyZH&?*KD3DMFGQgv>0tv^F z+8Cu3NS#-oe^DOb=6Bu`S~QAU9T(g2Ur3M8Cv zZ#_yYkUT9l9%VHXh4wWQkmQUY0uDk0RA0JV;f}r%C#mr$qd0)2?R%8d z{iGk?C=NhM5Jk1~n_SlYfvIo*%4)OwUw9C%u4Jjy5zU}^gv z<#a#FQtMG#ao}mG@hGD>z}CtDk1~pbO2vAVRvh?Qs`tF$h(_yCT5*sfO-IdWP?Rl= z8K0Rvv2#S%B;W1#P|PcTM%f*GcTBIV2+2m9RfGho@@J6h2nkZ<&z__zLV{FBNRYB= zX85xwDgLIX?}1eNGe}j0^dwdO3{o8-L8|=OlT<}WkZOMhsfv)Eq{^Q`sv{&wl|Oru zst5^E?av@p5z>=X`7=m$gv5#sdD?vYTIC8-?av@p5z^06t#U=lDdSN&opXAU8jmtL zCoB!{D7~v2mKu-B>73KkQsYrZnkQa!|hR1I;Sq-u!k+i0eTIA~_o5a-vXI%$adHkzq# zAhf9(;yl|_B@Jj(>rpys@FX=JWs(M18sJfSng^EZqyeNVY4EgEB@H0eNdrh#(%?y| zk_M3KqyeH)l{EN~>ZAdr#-q&E7*A4_hDUa53@lY?xF@Mf8bGSkaFD8`Aw`;wnjM3p zsND9KMX6%63VEwl$ZM^FPj*qN7_CCyY8CQYtKdnh8b52R1L6cf)%c#Is_{Xp8y}>q z@jXe^HxNj5#s*Tp#I~|vv?>0k=Nky5`WpzOYB=+>R1Ie!)x#M`Rf6D2s)jR=>I4C# zYB=*GRS5z}^>7AKHJo{ps^JWzdN>2A8qPdP)o=z2ud=}A8g0MGtPhg7U4Zsl~j0AE%Ux6JB2+BGC@(IJ(sCT`{Q^1Yv}*otjft#9e|dtX-L zTV?^jn9~dRzN{uEG%NUE4e+fp9WvdnW(gmx0dcFWs|H{>%EYalUc>io0TZ{(B0g*l zh+Ab{HvqO;-_oo2zP1|QGRyd|H6U(5|7G5miCa0nj_+%$@h!8EU(D%+d{0)rlFubc z6ASc8zAvlxEre9d8W6Y2x_ST?B`s@+Z_y!BzJ-u#SwnnF*AL*bq-70=TV-890IW7{ zaqDt>(_T?WSyvF?!lbnoZqh!h_AP`|%NpWax`qI3wZ5fm2>A9_?OO<`##UWKz>`&1 z5rD1Mw{#T&UsmH=ri?%_r^^WVvg){%Gj#;O8sb|l=aKd;Q%C@;A-<(62^0`g?b{0R zEnP|gtk$=5DFNSh)j1(Tssz{}fUm7OC(LE7Z|R}}zO2T#OjQB2K!|VYvI1xU>sz|4fUm8_w@h6D*c#$ny08Fj zwZ5eb3wYY9D+_?t`j)ON;LB=!%aj%960M?MWrHcy`5K_&kt&0oz zwg4Pb*=l`DR~PVQHNIua3!nu;azZ+!vem{dU0=Z0Rui{OfdSYWk`vM)m8~`>)D;GN zZ8dSrEZY}z?JwIS*VgOy=vmgc+F!RPtMM&UWB|5?_!b>9-L7Wk9;_k0rOOPU8iw_) z_LuJ20>-z@+C6Ly$q99#0oZEeR{M+hwAJ{QS-pp?A#sZisos{2TkS93(^lhKX8j(v zhQuv8q_Wkm_?FRSMlM8`Q8u~^dqQc^oKWi9vrOEwx(stfsV}SX zEvw5gXO#M~nz&_k8Rn2uPgbMLu&0z3%_*h6tR`-m4Q*fz@hzjvu;-M5HN>}!F2f#F z3f2(cGP(?VQYlzNd`p)hDA=P)!5Z?tWpo+#tWvOs#4W8*hpjelh3GQMMwfw*YR0S( zT}D|Sh5}nn+`=aPfKl7%GVFP!MeNiKVKu&Gbs6TsQcsUHx{RFFWtbC7eOcj<=}gn= zGR%>szO3eZ%jz=BnWet0W-i0(GR&c+zN{uEw7Lv)YN;=)iCd<7-@3Ce26ZiVsse@skU7M;#Nf;=Kx#H_f|ecmr*gg41`o`Ye3vG$BM#M6SvH< zqP}m-_?9`*p_mWRWmM>ps%Kf>3eja$j4lHQfSYy=(PdP0i3Jq$Hs4$3SW(Y*HM$Ih zRBLNMPFOLz41`q68jurKj4lHq)v|{8meFO{V?~Sk5M4&a=rRyet*s%xMWIxxzapes z)_}NGF}e(dRLdGLmr>D&JD|T>-wM%XRE#bIA=TI#qRXhzA=B+@bs6~(T}Fj9PZX>5 ztq@&C#pp5+Qf&)__?FRSAf#H>5Z^Mo41`q68t}bU(Pumq@>Z9T*JnI+fskr# z4e>2~$^&e*z7?X&s2E)aLaMPfM3+%9x(tL=%Np>#RiQ(sy};@+u>Z6DT)Sd)891ri z+8PqK=#a`*>sukZjEd1^N4^n zx{Qj^Wgw*5b`6PJbjWlcFsD8g^C7y7iaz!M?P`51M3+%9x{SOz_W`zs$~n>M{aqE0ERXgjSc) zy12qjbQu++%Ropq<7;nZiVPFDn^%)x4I0}ItsAW=rT~D$n>m`dKsovU;!nHENe*IGP(?e zRLdF?w~Q_WA=R>m#4V%Cu+;*Krdpuqtb@^I*m8kj4e>2gF9RXfwm^t)nR*!rsg^aw zw@keZgjB;CQZEBV^0mj>dKso z5Z^Mo41`q68sb|WtnKH7VAZ~bkZM^&e9P!E5K=8```=rzRr?k~s$~uF zEu+goNHwehx{S!3M3eF@gjCBK61R*l10mJ2!cCgy1L?x1vpg~Zif!LAr$w`qBCq~w`V5!;g#m-TogNcE@; zQZ*`jlBz)&q^zI2yON~dF zkMykBJmE*GztLf-@hG!*!jsf^l=(!5r2!tLcTPlh=LARtJW3a|1gY^TvvI=n@o`z& zqs;d?EDi7|{do>cjYpYn6P}hDk1}89u(Xv&?Qz&11Nx6gz?$5D@NS3nA2E8&*pZXE z#^b+40}6TmZ=K`1`Va0ubn@h`aeI$FC=>NR4C`E}>#_rK1M&k31BwGm1Ihy`1MnG) z6dCy}l22rcNb8V;Az?yxgH!~GJc2w@WXKw!L4;rs>OM&Epqqop4XFs^W6*j*m<1J8 zt}p=lB#4Qi{DDjdni>dTpjLsj1Ue9iHlVP890J+}2n`_9!4f{!+Y7lKvnNj+Gk*L* znZ3tMnVhLc>p9yeO_L{14>WS;WFD_Gh4CUK!V-P!1HJI9n3MC`(vE!x0pvGRhbuku610C078~ zxUR{g`wzw^L8Dd2j+ruLY*%LQ31gB%?AE@4xk1R+q7rIPln{Cf__~5+}>X^YT#RdBdPnSb5unea&2j!LD-TnB}ucpL>D2aORGSx%*Z z6XxCH6tOyipY7vdkZ3$k)G;uZ&FnB52XAcNIWDvH)G3*@b{@9vzz!7VS=&Ba$Dnd9 zo8{@sc(^>I`Pl(zT-*!Vz9K%POQ_(0Mf`z#S z3UVmc=6>w;V7*@!YO7<7zhe+;RP#;{eH5@2HiuuL0`{FWd080Y8c(;~Mmr76Mgy~j za^eH2e$?ngplQ*U+A%FEfgXepe=H~zi}=Lk;edEDh^F8_z5D|~qVZ&n50ky8 zPMI=cd}ef4=g7>6&WV}HBPMlC%dDDs&w-5*Hr2c4&ikXYcs*u|7l;rP@&YmRwssr- zFHPUa*Bycp4jaa9HFTHlCypI6zALl+=+047GTA|e^6ve6xlpfuQXEhm6y-2n;@b^l zRSsY4=w_u}zjDash+}(cugAipqDE+`qb#E^i*Tc#bzopB;|RD8+zR;?`dNfAtjS1) z{8sm~RviqF*z5WJGl3>~Kt#1luSP)ex4EM)2h! zh?NnwFd9}6ZTRw9JRBDfLY|K9lOI%O(-lg%Gx{Nu7i3&bQ<{O%AcWRpk;8Hp<5v!W zGnehv7kdZJ_Ol$$lQy2H+%W}b{3fyLKhyL0K!{EV-N@UJ>_9Zi*8?dYAVh6UI+*pe zd_6sBKwC);Ur#is*nu7LMN}tZewizx$#VnHEnx{}WV3~0sZhqjDQ=)Zwu5RVS!707 z3@b$Z&ExGzTH~LCa%Q;kcI3^>DvRhnh7D*QQ=9+V`_G#`n06v&3{9MqBi8^SuzIG(I9YG_;X%_oNhU_eMBEi?P8k)=F3Fok1f?VNGeq=S~NQmE?nmlkkoA z(m8G*M#N&KIB@4NlMr*qj+vO*Zp`?7GQ%c}AKx`%%7jUFfM^(u25Mn=({7{_gc(N9 zDz`?co?+>vahZ{m#vIU<898B}$-S-mpZI#=l0u{9XY%>-pUJ_vFky$F#!2v;Vn`>z z%@g|GBMLf+&9j=1QBC^{60UOUyPhtIsabqNAUZHi%q;oh0;L{${_C=@7BNtLp)nzA z6$80A(|E+TMjhPO@1-<KRzKHsyE_hV%?WsTXF%g~`re+LMT(PltzV zGPU8IJaSib(8J9g$3aZ26tEes3|&9Y#6v&C>4+UEr-59Gy|sng^u+dAuDkYfo4GJF z^m=!kt8J3_w@4|uOI(i%?atoJrlFyPD1^5XVQB}ORQN(#Ob>Dgy64b27XbZy1F6vRrN`CZ+e<=)fsmlg4+B&1}~-rE|=9 zW`Ils?YKG@ItYg@uTR4kJ%sX!uh&E7!b9R25%Y35oC;r;m`%bra1tGHfDBeGkl%2} zocjW9^_V@;|G)a%3QvkpNK7deP-mJ83GA!IN-@I!!w|SoVW`sOCsTfM-Zlp*v5Hci8u1gR!JHT%=AHQM0g8N#y}Uz;=1I2K=MyuoDYsUwRq z=73&HHti3~94K^>+5V&$Ry4)B$^7)4#DQ<}=rQA(415g1WlV}N`cx;b#7i?IQVzuZjOI;ygwMdML>UfeWJVeB(?%*d`@udi8uPhOzMx^1&R?)6CMjm_2z z^d~EivBX2QSTSHhjmAUGB6n-DWbi+-e#`P6jc1(649MJDBq~F-gRzO%(r130m zMW_FfSHQ`^_+Sx?``T(B(=f z3uRNn7ReGTyo7Yex$|@k*Lsq@1Z5eW-+Q&#=~`O7 zyq-*?t+9l8Q+5zC5J;L(F^uvVgy&>Qt277-nsN?89n{3kVx0@Qc5V-XDalYol97oc&&geg8HP{9Y)JurcS^Gs0W0u?DB$waLO?DIes z1(ZC%jt6us?EHt=5PRye0UiPo)Ovuz9J?~0-o}mxC?KI@hV~yCVd(0if`?`u(lUH| z;U6@$kpEzg4gVmk#rzEfp!f$_E#?CwC%eTp6y8#KOX)4Ox0Hfl7=|td|8N}^sv@l9 zKzo3HxDGS#5hkc3$Z(-s#Xnq!8M_G6S`oCk5oSanbHYDdhp$(t6Yvk$;oAX&IuyRR z4v8D4l<*JNA!y=j1OIRxhOh|YTzslS28`?QG9n0cBb2X-P;3eli1>%=(88FT!9QGw zMvlQ}Cgj`VSt>@3N-Jpqn^r=(70T zh`@)2#-^tZ$Q|8G8bJFm7U7l37=RUI#5&fhZR-6e^-} zmP*$m)g$S!3U#jwwhYdNK{&WJs^C+(13O+SjJM6_bx}(fT4gE_5U1QjK;DSB?j{-_ zLxbEF7EvPvp>5A%K5LIPo+!62q;i=}yAI4unUIOr&EmgoH(~1dk(dYIk3&axPQ)y4 zX07CZ+IjfenY9W7x9uFUAAp;j=_uxUO$W@WN9I6+96pErT0DOpb0m0?#Y(meZ59@H zG1=fkG<3)~G;7AZQtG*TvO&Hn$ej74llY*U4bLDWDrB}9o{@Qw8Pguws5B7ro=UIh zZ2ksYK7F&-%IMdtzjDOH25{)P-K))F>ITCUe}$$RCmqOt=n%j->$?c`9VTW9SvYe? zk4zojDK8oykd-1--OWSYoPCm%)*frRD4NvdS@!+%WnhlB$JA)me&|xAQr-RLot)v zZ0igxrmJl=VJwH2VH3tdwA(p;N@nNLU0q`{J8iUGCTj;zlbx`Xg82yrDWRUkP?Wf;j3{8<^o{o9k+Yb2 zYm(eI?~N@xZ<`~>Z1Fdi5p2A~nfTkBd=O}1k^8tI5Go726+P6uwXT+9J?j-V%%6J> z#{s#QUp7l_dbu1r8ny#L@=~U9w1kB`a_I-==cjqzXokAB(CrlWWs z{|lnHi`_^ZqPZN?q-P>s;d%(N-d<4+883e0hj%J@>3Pha)Fl}vBCgN47L2v*`}QGuuub zJGKiuK#N%0+quc2*PMJGE|+lc1A8vR^FY?`Z8#DezuYpX#cR-_MPv%*C*~7b^Z?Y% z#SYA32Q>VU7`X2+sM63!;NS&h2jx=PZ4K%*Y_tC$AHv46#z&aT9-zTW<%MojWCsen z;v-x>#`vO>T#1E)8;{d|8qp-$^h)`d&djDPknLx)K(+v~ry^H#@x2Py>UlO+OKm*c z*USU|2l^$8xHcYk*wC%9<9MI0%s6~X_YO`?-WpobydyUOVt&KKO|QRgx)&IU1ZFT~ zwu3n{X6^BUDo88vF^LfC-dg%AnH$BE9?A238xK;(Fp+Gn+hu!B5acj|KngIWNk)-O z2Ve-CyD0@mbPVea=fmT<5uIPjIKr#(9|#lN@Y^DzU_sl)|U4up69ov(%A1 zQ|qahIs9sR>NOOxD;)FMd^g;DhpE3LqhkdE=Y!~RJ=1?Z<62MRFjGfYNkfYnhr%Fi zkdMmQQWgh~K-$!i>=7QAM|a6)v1X0r6O|6I(Y)!L15L+;DAR!N94-LC@nN|P(#%Jj zPG$ByOHbB-N$l1x-z!`+pF@W|y*^u;M5JB=7ajxC&mD!vhUbFY{EPjV$OAA$;;B&A zfliOa04od_7?EcoD$RHd7LjUntoD;17_D9vOK9WHYOHAh61fD6u(dz;EqO<~m?@4d-b2FFNkDHou?itlse%kK|^S!sE*zX7|(x{&} zL(CVdK0$C^S(DEVOkp*BxDM=8#YX4Gw}snM>-BBH0@yQ#g#Xg%1~q?#aoL8{nJ4Bf z#@%?r*)oAN_lC#dDRx#0Z#?q0os*_ya;07qD@{fPw5!kH(d4qGJ(BBL*n`i{cFcs) z-Ab6k#Xn5t;@rz5Cd11qEXA2})T5>bl%6DFHVi0p{)4enK|!D<9TUS&t7MNQ()~sh zychfa%#hh4y4i1ER$oCGAM>RQDSp%7#-M=FwuG-{tkNNwZMIaxfmMGJGc8U&KzM#a z@Dt8GH^ZQbsO=&I7Ft;%2dfW|d%Mg8>u`C9m5~~{53ZhP>q$a}jqRM4)QrkZp3*sf zwDdz{V$Ol`ykzYU4>} z5y4v|%xac~^C)WKrU0oH+Ck6LVC@&z>EBQVt!a9Ky(T@A@gS3=5=H*X80s6tzr;3v zhoJCXk0OJ$BO8x5v#FY1uWC-EB0Wp2NJZERddYF-Ypkps+jy8A4w~4N8JZb|DvOzE zos&mHGlXhrnXNk~O`0%mZiO{Eh#Ef7-SJ2=fZ%`Di}^i^JuFw-c#{9Q;iKggXpc}R zkuJBMdt+hU#^cXqYGf{rfvAFot*rRgP5cyM6UYEc1uV}bxqk_@P%#+<$rBclQ#w5s z@@+iCe>k;LAD(WeSh^q{sr3>uMWXTqv*nYsFQ*9u2qIlDeUZh zQXAU5#>>VR3}%h=TA%ygX*&8Bu#q#VFN5z-rZ-0n z&3*>KF;0m{1YbqWY_*qtVQiT3WLDqN(PE)#F1@LgR2K6;?04-&hn{q#tyk8{H_Q&U z9;tmZVSckWg$0dLaYoPM04KvfUSq4Al6yL&=gpC%5>}vWb`i1?%!5LbOWA)O^}?|{ zjY2jeQ<&85n0gK;pxG*q-KqJH^Du@W=Vqnz%Xp zB;M*?uI1-?)Nnmh|J?5;PcqYqEE`|h(|g6?-eI`eWxYlTz5u-n<<<`Um$kWLPoAQE zf5Pp}(>0w3Z}z~w|Fmi1fxR8nf)!Yt1seh}IJwm{?sGsL7bwrz0 zoi#qMw%2=1USp3s!KI8yA+fPhwu|xM&9n&hx;+!C+;k~V+y1LG!~UE~j8o|rc7HWn zZo^ZyT2JJbQhCC*vaSEf!zHpi?;U^KD;xN59$gNd$H!BfbxhPN;#4J;IgoZ?vo9Jm zE%(Dap%1G06Q|&4Bvq+GuB9waJm?rXF*9`R)Ny0RPaW6T#>xF38%{uVBR7t&#Z8RR zfc8GbWiBPnT;-P7%|~mwQG(l=<(18mw7K^nIcLXLr{y#QEE}Nt-Z><1GamnI4zGC7 zfUI+NPKxm{TWp`>u623MZ4NsazPU3xn};L>3MevhF9!X968{b(H zLLR#PEQXb6aCe+$0UjJv;?B8n(st-uS?&)aSQLjSCt@uu)1cY`R(Xq zg>+iX{2GPTC-m_4MPV}?~?o4%};#2 zMuXS>6j5qM1#$(37W*#QRaN3yO8FV;$jHlVtEc`49uI~q4*u@lpKSGj4ukrK1) z2q!XonV!3x#pv0SmdvFOhS^%3h!3Zxn^3BVuUXGj@E0>v5wR$+j6^+IP5XoFob0|F zev=jRueIx!#j0fB=}~v|j`Gb)D$O20oNW)%lc~&npXl6sE7+}v`d#dYYTh~7yTi&= zJ@rpgiFCS@?SI3ruwV%@i=XxGTP;P|y+YX>*ms0ip=6ZUq-wVv@t2k=O4f3dN1DZW z&_qT#_j=yfcxOF{$S{gwnr|2F^{(bnR;3r-n7PUKG`*^I;-9KdJB!zZbk>e`p!P|7 zVT{d$>FefCJr)YuoXEoNXX%1pcOuI>xo{g*yeAR(Zd#Yn5hqN~1uz>{5=TmR=4uz#ukAoq*2Dkn(yXY;@LB&^?V} zr=U^5zgNwn-o3Hu_uFji$RKKK#S8LqdDO4llY70d*_ukC%VM?!+pm&^1dhw01w0|w z;?eXDYqwi4y&)1aUmV9;?TBQ>R_|BZ>xFt*%{~?~{X(;$frD@ebs|`E0c%uzymrK+ zsp71&r&tM$((^ELAiLv(t6k-I3cF3l?VHz|WKt6qsS2*M@Y5#g9dC~<`yJ&XmK-aX zmPLIIXu2wxoh?8Q#+p^AszRX^#3-DrK$!zrf?=d1&!dms)_D}GLe)oXZ9%QTQ?&g?DplL1DX+V&W3dklD+CzBW*(&?mVjiQ(M(j zgMx**<#}e=@my4gGfy7THNLC=V8|yNn%sZzZin@WenGw|$4*XZV`C{|Mg0EicPt`rX*;(!0|I?Uwy$AQGZn@`Y4xcmaht+)fbBBMn z`VQ62KTGf_|J2Q5 zMJ)FsmU|J)z1%g8dlBPaHQpXZ@PkgTJkbo#3pA{kT_6o(neA2Q5MJ)FsmU|IzbJ>{MH!uFDdoIDe@3b|> z*3LWsBWJ^#TaT;#{FDzJet4O2wd`RZIDFlq`_+ED|34hw=G4)(tM~uA!-wxVvbO87 ze{=Zgh4-qxc>Vhh|L~?=Y7c$-p2Ls+_y@I*MkRR1n>VW!K7ZH!UYj_yw$B|2e&WM& zZR1~POq<0vVzG@_Y$F!ih{ZNyv5i=4BNp3;#WrHGjaY0WhHcf9Z4NiCsfzvh+p0Vl zIIHr!xK~x$0X9^nePCNv+6^{Wr9JU1RcU8DV^!K8&t8@Hf;Oqj`@(yy@}2TM3QpTb zEVdDgZNy?5vDii|wh@bM#9|w<*hVb25sPia(#MGB`)E|{^;14}eeZ;OM%Mm*z2 zxc;BMp3frJ6U+6)#$RTPKe(nUocPZwN@GrVE^VTyEFMi{)?)=>eK550`mkX3!<{d#)PDQ^`R;uke|Vwx$frMZc!xDRYRj#h;N5?_cI~Rp^W5)u z9?-vb{r%@UeD7f^)OOo7!B;K*?OOMD68u!>!nI$`li(4z%~N}Lxdh+!lfQRQ+*4!P zCN>a@4a8ytvDiQ?HV}&q#9{-n*gz~c5dU_Ci@UFVpLClD=JnDCh>PX!?#_`(-#BfF zr@PPk>$$EyrQfEn=Y8dRV!57Jt|t~>h=&RZ{Y_^*{owfXv8;qbMij;bxQ(v=QhQ$4XZ<*@|+ZJ)Dhx8i+~U)~q7 z+?O`UeTn71#ByI^xi7KYmssvgEcYdr`x482iJ$+*sqqIpo$l-r%-`R->6CbdEzfZM zZJYH@iT@s*>F~2xoE*HZ;ODkkB!2Nn$GG21i!2s!7L1qO{78q7 z9JOG4=hlZiJo?fF<2M#L)ZyO_T__&-{6P-iw*JEL;SW!9`0}$CiGTUgRE3?*4SR^i z9%8YFSnMGddx*szVzGx<>>(C=h{Yb_d0#v-et3<n7{DjhsE!% zmc)_Mu014vy%AF;9(+)|^u*-%gSMC!FSkvCN3Ap%YOxPI;khu>R#>G+;MbUM7)S8^_BoJA-uBE>;vfHbpu7H0$DA79d+8vDx7hWx zc>JOr4&S@P>G9-SBZoUKIz4{pr#XjD{Kgr0_XUUNi_eI6{$ojD+9~!Bi#^0*53$%o zEcOtKJ;Y)UvDiZ__7ICb#L^~d%=T&ZF4Fx+Ft1PhvS4yb-yq(0#FFs>Ki$v0i&fwK zRy=)+2@e14)5YQu_fB$H{4xEvSI56x?u@wW zTZcO=<0`L_>-o2GJ+WL*EY}l@Z}M-CJN4-J7fb%sabDDUY@7uT3sbarpRaAFVC>LNd0`d%(lBt#3@m z{7+taur~SE2f1rD{nrDvhaWh^;r!hX)c*dr!yF#8!GpCW7EWS{VA?765Q{y;Vh^#{ zLoD_Xi#^0*53$%oEcOtKJ;cZT8{7d)L{<_DB&gL&3y1VwLu9F-d zweQ`v&8MF1@CUcwT^lg{6o*f~^`6>hr=IHYF}vSe`^5>TIeha)f2{p<;^_+WzQRu| z{KUdfEd0d6Pb~bzcb@oYZIjC`boL8&?|1u0YPZ~&UwR>mLlM?|)2!S6O+zde=<} zzWoOq)N?l{__D(`tUon9!MQVs*MGKlf;*4gxW3Y*4bH)v)(3r<+-toCrfp&avDiQ? zHV}&q#9{-n*gz~c5Q`1OVgvEe&ljo>{$t{6g8BQu2QOH^v9~yaN-Q-D=+YhubFjr0HMQzJEx9&pGk4TH#}j)11V@Ni3Yi!bvQg#Q*rs)cQQ7 zBs)*N#A?s^Zn}!l#*}H z7q*#L-{8pPn^Z9GC7i^LvAk3MZTYFG z^>e3R?l@n&_<;Jv2a|8Ng;qYWe&T0WyWfu-c5r>t0@pe$@r!>eJmeG}V&Nec9%A7k z79L`WP2?Q@mv?KY?U2N*FCP4`cEz(vJ|q2{*U0t!Te+TCt|yl3iDhi(-<~w#{@Q7S zj&slQ>5UK8PJjAXhxgs)q1x%=k9Ig6o8)iFBY#UQe@iTXODum&EMpz-E118x8e{L? z@0scw`z7Cug88?jPJF7m>g41b^R?}stj@D<@*R5h!%tMN+d27G-Q~+Cs^7!dwf4O)RnPui64$Od__gW^ z`2-I*^8czwJ(|S6-{0|e^_ZU|c*RBjR=w`T1h2RKht+MbP4K?cKB*r2nZ{}RiN$_m zv7cD%Cl>pO#eQP3pIGcC7W;|CeqynoSnMYj`-#PVV)V(Fxmg1F4e|%+}iE-Ajtt%xp_)F z`JDtmamCbl_rG55Y>tN>5P$K>6$+<0iG`C`IEjUmSU8EN58om_|H!9Z`wM3K-1M`} z;&%omvHOzxCh@YjC-{4JZWK>gE{X3;T{tY>b*lt_K5b|`e#Zn~zSH{g{v8SK-ZYL! zzMTB+-n$QpCyz|lL_&l^^#ann6xM6XC6}RmcE{CDAyCq^~C9RPWS)Y zJ~=3U^N+uDoUh+7ExvI|5)0(LlV7eUk6ceI*AvV2#M1ZDm^`h<4H*M@yb-n= z_KNj;w>f_>uNTbgUw?k3`tL@s=YIe4zVFr-xNn~duUUJSmFpXycljN}%N@IN{mk=6 z+(~@s7Ax1k@$EYuUf_oB)_4BKJl*_#&s$fjpZZY7;dw@_SkI1HFTwXOUoXDDv%`12 zvuypIi^n>A+@F`JFZ1#t4zKacrRtfV9qsUh(f#T>4LDZew4KCaC$ZQ`EOru$oy1}% zvDis0b~@a!lUVE|7CVW>PGZh!i=Be``#m>Z(f!D)$+L9b^poyemOk7)%hpF6*WGpK z{tjRD{-o}HoBzn+r{4Tw_bP91?(l2J4e#FK^~m8e24b;+SZp8`8;HdQVzGf(Y#v)yoe#g>ef|pbx^d(D1K#Ui{U*dW{J!Q#|LT5a*>5=f);#mq4&Gn^ zhhJE0k=mkbd{bfa3n#H~5(_7>a1skAG21G-{9b3LVA`<72CH;G`NsXu&LfXrv-{G8 zA947t1qvA6UD7w*(ja6>Fu1 z61;MLy;^OL*ZV4GRr0HTt0KV+7Tzu?|1~$2Dulp+>2Q5MJ)Fs zmU|J)y@=&r#OZ#r`|b~QPu~AS_b%qWyWaizzVABx;I_Z)-s-o2GJ+WL* zEY}l@Z}M-Yzol{d8sc>O3+C@KR;Mv}WX$33g86%^@pJe=x75zs{Y}?b1@roa7P+Z* z#yfAj-%l+6y0-U|?>oF#zZ+^FfBu2P$6RoI?Szd!aX9nh^|k%Z`rP5EkKIsv^p9UT z{MMu!YY)Gc`1rcF-dsET_M~6^{G{7z$M2H#w{u>;v$pSTNk3ft{JU!14<`L{z-4#W z=07#*xAVRHhuXZKCU~Pk57r)CcwyH+GgBU|eg2!|cfo1pO#eQP3 zpIGcC7W;|CeqynoSnMYj`-#PVVt&)@`o@i}KMUr&LrzZXTS5?vlVvsH16ea<6gva zFJifu`@L~5V!0Qw+>3aV;wJUymO5#08uPi9JZ__Ue!ZcCiPyVgSiS!;U%I^FhKq;R zCtP-^!|}1}*9(;{hxgbkuCIT}o(|u&!I1h+cbx0+8^ucfg=gP$_`YpQ^`+J=I?f5_ z7V1}5j&=BgmGbrH@4iK0+9Ng)iw(qL1F_gZEH)5}4a8ytvDiQ?HW1(b(YX4Plb?2N zE||aX@~w&WYu89(#~I(4R6pYTPq=G_-9Nd0-YI`__{MFf)*syaVTWHk`GERszfI!N zo71M%7ry&m_q*UUC$Vr63n#H~5(_7>^bO+cj~QQ|_?zLbPv+*^z5e#{j|}1O>31sE z^F7M-#Bx2cTu&^0n>_p7cX0jDTW)v!7r%R8{nQ12<8b;}L zd&!u<-v#q`8SD7FVE*2!&rm=1=~XA!c#UBGEp(*S=Wai#MobOrq0xyBQ=7W_O2<1) z&FTTur#nn7>&k~6?Jza2Uwr>?hpDrj{D%V)3@z@sPsc0F`^vqDcFLzDjUc_=Q zV!0Qw+{@Zf;B?nF z?&Yp0mg|X?|3VWx-%4jWo2iu*EaRkWla%k{8h5?pY+T>qbYmcFJj({8mBbobMYF{LGf=zA4N{l zP4Ql$r=ks_v!ZRHzoN~e%VN7xyCv-@Ixe}F*vWel%e{!@Uc_=QV!0Qw+>3bmGy2ts z@4J)Z5zPDEFs)yG!LhqI8Hq$A{jz+by}4w`rR$r# zxtII>Z+kCOzh~c0hYxx8JM}Mb*;`@WSNNR`4Sr(bCl-EU;U^Y;;>GSbr2hJ;$$Jq@ z`&YQ&u=;kZ{KVb&va61$?>;@j|9tbv`uFZiaDLvS>kHqP;5C*zrvA{S3I1TUW9!ql z(U|uVPGaFC7EWT}Bol`D_Vz+6x^@;!J73%Th1&FsS9EsvzxA2g>&L9*@E*H8 zSv%^w?>anUpT}z7|IR83lT-edSpJq+{+4*(Ee@|Q@%Fs#zJht*!!A0sKKamj9Oogm zgX>@3n#}EdcKw0%U#|S`DzCZY_yg+u4Ee(0>P}PY=Pi}s9oL#v-{UHcc`xB47EWT} zBo@!MrBzzx%)P%bP-qY8U zQ?4hL>xt!hVrg6c?Q<&~Reu|EU&QP0bWDA%7nAv)`+qyVe)Ba8yWeH(;x+QO{%GC5*N%w_4*%mXZ`8i} zTi#)@!P(QWfmm!H78{7g24b;+SZp8`8;HdQVzGf(Y#^2~lkIT$!)MgTubt?@i1%A) zn6p#j5wDT!`L}YtU|uhrjAg_Zo&0=l_g8X`M=*citoTxG%F%gu%@GT{R=eiK1gC8i z%=^mq#Bx3HzZR_3F8k}sjz=(m-}UX=YA>FY`2G@0-dtPl=#0DO=Cf|7J$~=^9Nztu z>uLkHUe)1u`u(zY;gYL6d|dYG+E??e>F~;5Tv>a&-`WoMn|5Vw#lkuce|*K2wMTaw z=!Qlr=R$6t!rG;{_9V_ zzqapE2|i}xy|qz`B>1wf-__3CPGj=O-xAB;63gGZdyTuP_WipOKN``%yze1@zO}a7 z{Uz6iZ=ZQ*t$J$N;XMw%t2S_zCjY#yn7a>Eh)2#nybJ z_Pf6%Jc4;&;U^Y;V&Nwieq!M#7Jg!RzqDB}e@{P)VE!&`mB##A>Dy_{YqnnPvD(mb z$@$kRtNy7rdP0KdTkX->+gBwx{akWAdE|Oxxt>_ACzk8e_u}s_p8I6&{GF3NeBAGz zsg=qF*XC&-7tFtv>xt!hV$2B-Nv+*D%-^w(X~?L>Z@rWE!hWJ52mI;_hq0e%$h`-x z;?{$(pJ>S0V`GQ0pJ>P}8z<{)*iSU1-}=e=8uk+nIq}A1eGU7Gh8%cyvL=PO;vuPZ zD~HqfC6@aV%YBLEzQl50V!1D|+?QDHON_l9vD{ZMf5$$!_`@p`+pxbZUSi8b-E(1o zS^Vy4;~d8RviOqYf9Npwm&GSMuz|zaUl#x0Vyiif{blh5t9`>^>@SPI`urZ(ZrEQI zFTKmb4r6~=yzft+xr1$s{bg}=-!IC<*k2acuUU04G4`Rvi|=u&!f88+#ZF?elUVE| z7CVW>PGYf>SnMPgJBh_kVzHB0>?EFlz74A%t@eI3jcNZr-(9czw|D;GaI}v6eSP)(5d}I7HSBvGzAa))TQNI7HSN>HA!ZB#&V73n#H~ z5(_7>a1skAG4@7Pzue+Cj#Dsy$DXh17iZt?e#f4#>T)|K_r;#C>ahp@(fy7+U)AUS zcAvx8^Hn|JhGhO3`-7@$-J)@tlUO*3g_Bq~iG`Cm-EV(?%;weV)5&_@-N)=$eS3?S zTswEy_O2dy%QFt|_rm_w5!J^X-gbkds;kWZh{M1C-ig(XS9{RmHFrI$`u4ByPp)s+ zoW2*^S?)zF_ac^i5zD=ZcFJifuyFS%E>3*{D;pYuGr1+|{XO;4eL(W>~Er+H5 z(>A%DJaRp;Tu&_56HC0{-=_PF;Pf@bGRCGc|F+fmFMWpB3+DB$#=}R>x}-We+u`D` zVE*ktUcIRL+h~xBiD$fgVKrWQfWr@-bz$|1w~~DFrg<)^K5$o(XKu0T#nsNsll=4S z4=<_i{mUdT{o}~Xs&~GW)qkpZwQ)3ez^R zfmm!H78{7g24b;+SZp8`8;HdQVzGf3+SK^Fx4i7~0m1wo+W2_%(!X@SLmMAYUh;5< zp^cB%`+3D-XyfDk>x(!HZG1fcac{VFOlafd@7?hihoOy+r=PU2y9V0$_|vOO4nrFs z|6`v+9EOHDzGTAH3a4!#78{7g24b;+SZp8`8;HdQVzGf(Y#@d{y!z9}|K|F+VD<;> zeW<>4?mMneV(&wB%fX4p0DB**KYaQ%_dE7JR4+OCC5N&1p}OFq&pW)*5>Heg{avzV zDwy{YPGaFC7EWT}Bo>&6UK=kQ?^jB2p|W87(bz5A^}}~uAU=Jo%@yXogp*h}iG`C`IEjUm_=Y8pj;}a8 z(U}OQoezC{blmUZ1>L>YyX%a{Ue|lj*_qRjVoE|^?%u)^?_Uf_mSMz+w;Wx(}8=twzat{CL(PQGtZ!GWd{fizG zzjaJ9uXxy+N5`K$m&_~vc?9UDiN#LhbsBaOi=D(`C$ZQ`EOru$ zoy1}%vDoRZZ`etkwoNeGGu;OS^LlA>;+F^@=PmPa0BgtFte{gF2i|;+d39JUYkO~m*9>WM@faNqd2bHk0D{pr{z*Yj`XdSdLeaMu&d^~4fW$bZyj&sXm} zVI$Y(V=w$m_4vnzJN(+O->)9}VS-;h`(M=y-%qX?{nb42?cGUi65k|`aFSm*iG`C` zIEjUmSU8D=lUT+&@;|!sSnMPgJBh_kVzJX*->{Qd>?9UDiN#K0v6EQr zBtB#6Ue!W z=<0h5CU~g>e_UO=s4?#)oW#OOES$u`Ni3YiZ)|f$^@z()cXkSa|`W{A|)K@FTCQf~*fafV189@NYkBK3JtOJ|7G z?Lm#5AyUr=HC~3W<`4M=^S*K~V!0Qw+>2Q5MJ)FsmU|J)y@=E8BbfIUA53FjFMXcB z3+C^w#;aE2iL@tq1d~VlD)CLLf!q)So%4yk?Z-lay_wJPb}BFYtH$+|Eddj*Z8+zKCnx5 zuTy^Q@H0m|RegHIIS&8kTPwxUqgy+C!$q6MyMOwNZeG9KauecL??27u8@sP@Tzuv;D&uOEBur4Ezl>Fv86 zCjZtKJmxU(d-St^ahUczKItQeY3FPINNUH?{{Dy0zaDM);_3xgKmWRKIE>$G@;k1t z$@So=3lI3~!jJpb<-V||F809Ay4VT(>ta8itDbtUx;!thmv$hJv=8~E-FRPVPue5x zOgp9hX}`Re-Ij*#c(IR@XTR|J>Ye!7r?PNA-*N6L zKIhJmOc{$rW-=#~AsPPbv-bVHpY!~#_jmo?_wsmN{#UN6tB>8j*Is+AJ)Lv*UORBJ zQYmh7{ZF1gH+d}Xc;-sygLZs8-gN(;ov-cnc>L(Lt19Uo*8QcDzs|>jk<;qI5YH3& z*PZ*D=b_vSYX-ld&)4Guqi5}J0>5GU_pVpPeMG%ZYaIB!5qDM6zus(eC4chaZ526- zf4Ze2|GbNDs+2q6oEs|oeEY?9vGnZz`-E8fZ*l*GO1(%|eaSC7AV>B=zU)T1vM2h; z&gd!oqrd#J#{(H+I z`+Y^uHHU__f&8zlhW0?Y&rJ@DJ_qg)+6H=d8y*<_51A8~dNq6_@XYOgsHD$*-Jj~OU?t=d=*Rn0kyw~Rc?oMKZ~W$v%@}#rRRY+Es3T74~H#@RWH(2U-HWi$dP@J zFS}8$?1?_IGkVJY=r6x4nl&O>RAr*us^?83lY8n0-mBNBWOTd0C$|}$+&?|=qgBQv zJMS6h*{g0FldQcU@CMtAO->$jo6FgA@YrP3Nnw1e^VrzrpmJP-Pv?(KKH2mR&qMl< zUjmbVzeV9ZJ97RpWs2uP{?n)2=}ftk)(COQ(5KQ}#!H`GtDDGa;N8qrN+T8W=m=XU}rX1=uG!`dMe}wo|9) zow4V2@4w)ToqvArWoPVv&zcLI@yks;7CPgv`oFwcNxy37JC*!{zYk}ikkf3pk3HSx zZxY@=P;RvwKlgO>`RG8R_v!BGj6Y9adag6$(&t^fIWu0>JmoZJ#>0chbaG~V`(*PD&WwB2TDEs)Jgm9n zA(ixv>+V;{-*oTD89DQxYU+&q4ZhpWnR561az|(MIpK|Mozb(fa4To@Z~FTd&eUtd zDS;VJl+HM#{ER=6!?+~*j8`g`aZLI!zDZBUJ?YPQsCtpE`jTIEK#uH#eA$h1Wl!{x zozYYFM}PT+dAZw!YrT%l*P9+3n0fr#j$wVs{JzfHVZSl+{^s+q^!%&`rX4ZPnRUXU zXN2<_tT(RTWrU}*-k4e%;>>zu*S!W-(oa3|GH3D+xbPBZwJj9O^IzjrdevqE5 zE2KZ`4b_Wu)tCIT19D^^61wx(=(Hvrhg{=tzKEKUYY7ke%S#zvJdiQH_DYg(MNVhPuU;+E_=`e)D@pjhCrVWEux-e8@CD z*tn79#*Iwl3Hde7AV=d5@-;3|uEs0$(Kv>l8sE@g;~w?WcxdBfCEdo)lJeWQT9O!?b-NLPKyFFPPd_Hp^;^#s9Qpbu9kU`WAm_Jx{vU^W@ih9ywaiBVX%z z%GG)veYBoOPp#+CKewJQX+2MUm5v>hANxoSc9VSUsdBNi^uhkp6Te7*{H1!4uKJQ+ zc0i8ogM8VIa%E5Sk)6>~_D6sDg>ggA%Zw*_E@Pb0^BUuip5qvo^nAy7rRP4zF+C45 zzUeuU@lel?jEA}B%1qCjPvpv0Xeb{@?|&5l|9i%c1BOxAN}PQ z=4HK)V!qaU59V>b4`F`SdlKe-y+2_+p!X`Q6ZF1?^@HBSu-?%78P*$mA4R&}=a66T zd61*`QOK{nkFs+0J_>#GJ_lGrvm?^S

9#FZg6QmF8 z2kFVWLi)4bP`yZ3eaSC7AV>B=zU)T1vM2h;&gd!oqrdzzwf<+>x4jSccL=+V{W!bs zw!m@Y53&dfIzYc0{9a_T=U63$x$HAMWX`mc5o8 zzk569Y^~R_S3YU){Erz6vJLJ%s*-+Kk7FwNpW5L#XXG@T+rb(6FSR(qnR18p3Ga&0 zr%(TrJRLpfwC?DP{)1-*re3?e8+hB>zpSL!tG%p}|LH@&tH{~0>Gu`+6CU}oQtqH9 zR#x<>z2B-#dS0{ZFPZfJxbH8OdXcXBl3#W}j_iYc*^P2#PxO(U(Np$EfB9wiZzg1Q zT3+q-edvs_J1b z8=nvS^wWd0XRe#z>H9AplnuJ*I_DLm24!1y2r(o{f1fKn8Gxeju$Y1l8 zn>?Lz-)VWXGy0tHL}2vnyJd*)ivFEC2BuznoFDj}OK+^C-}Lz{mHdZqHK`(J`g)Tq z@*9r3vr=yL>!)VY=lV_Wsp#3D+PxM1&pzhfO1(%|eaSC7AV>B=zU)T1vM2h;&gd!o zqrd!O?J%Bp^zm*7^J9EWpTOqdc;jyao8RM350u+^)9>SBW`=fd?Id3Br_j!={lwY1 zoq|30TNT%>ezLQ*w|LCsr#M?XjOPtGwUWMW+tVxg2dvrE898s>a;7u#N7gyZ+1g>e z@3Ch)qt8AkhWOj)*>AIRJsth`y&^F6`s|Uw*6%9m)*mbRt)EupSpTiaw|-qI*ZO-! z9~(Df>1pFeEd6cVsML#e)tCIT19D^^+F^Xnpf#OIpMP*wXY#kL685Da=k}Y{@pR-LTdTS=<*s*h4QKRO^Z2lL1w9X` zzrLrV|9WEsQ?Caf4s89dl5YL6lHdAiMUM5~ihS$Wm2z#|sOV$kKt)d*A1eCWxKXJW z>8daJWe4QQKFF8dC|CAGAK4i_WqvRL)b{!wv;9HQ#5L+VKeNSC(Phad z&O3J8Fg|oh1Ls!{+b8~R`qs{$-F{O1=#X8UM;*~C{_u&to!^@|G=8n_e$F@SHpXHr z9O1lU$8oW~>yduydZ8bYzgoi!D{_A9ez`O9H#%;xGvzLSe0W*ThVjA2jdn)Q-F_bH zjQ$O;3*T_>JE-b5{kIPLA1pmpy5&!m-|Ce~j>*p?-^$HYuGK4(KBi|TJx%{i`dhuS zT)i^Ym;AB=a%3Om%Wjk_d!mo*jGnST`pYkS-hFlUYjT;_cj5C_W;=8a{OTIxvgxJ3 zFP}a-yZeM-!>!gGnRVK=pXcBCw_({XoA!5}d)&~h!~KC@YBVIfuEPLNf8yl9*_+h| zI-k>caCZL_fk_|UdyuD-|GAxmUyxIML15%JJ$s1fq1*?*3XDFZj~nXg=sDt!!03PY zYk{fPsUHU(H)291{pzD`sN}zP*-aHW`yV#3BEN9lZIyB-{yM3m&$Z3&sOWjeiaRR$ z|J-zPrCy|~zT}r3kR$sbUv{Hh*%N(aXY`c)(O-V~`SL1vwEFcYAG@}FPvpv0Xeb{@?|&5l|9i%c1BOxAN}PQYlpG=m-#W4AI-n9{A+%X z<#%fjvD$;RlUVJ<+E1+ZW9=$dyR!BctG!t}jMcwLSN|fv`WJH4zmTu~MY-x<=%fCH zp6XxdpX*<-`j_>)O1kyON`C976*<;_EAp*hSIV{iUeU+Kfr_3sK2-F#aidZ%(p6vb z%MQqqeULA^QLgNXKC&}<%Kqptzi59B>k949fweye*8Ut=`-R{?vTsd$jgX_gMzHo8 z!TEhnf5zS|qX$k85k zSbNlA?NNudM;+E4by$1UVeL_ewMQM+9(7oI)M4#Whqa#^{xi-%X-_-ywWl4{o_1LK zmSLRt zhyRo3^|VKwaqB-D+U7mSBNd3Gs5V@+)A7ZSg|SKKO;s2 zWhq9t&PP+$A2}DVv(?Da*=ks4tKq+L{DFKN62&b+XT>dn6}JS=$5i=u$8tfw;<3Pr zH3a|F;`Zd@$>d}B{C8sSthioqK33JA z5zkQZuP96Luf&R%m5-VBXT%;RZqdOPizw(_0ijj_Z&8 z$k964*3W)75PIr9Ao$O|i$`~VP?qiufpy0d{8zX;N%xzekM320|BQQQbXN=Vbyo|l zyISBsa<35YqjWFcpK(7O@3?gTvhEQ>XWb(P>mD&!_lUu|!w&wR-Z!Uv$M|jjelgv* zNcvy-zCzuDhMu~|4SuM6UmpCQyq`{Y%u%lHn1gkPCagO&Vcnq#>kds=cWA=8>l6Op zx+hw9jG}|?7=?AmD4f54R`>am{y)8YH-BHP?pH<5AGs%2ce5f#ceBE}n-$jGtT1a8 z^>@}4>YLn&!~K=y;jSF+wS@o39p(1^xx~H9$kE-kug1wG^;NIbX*B#ZQ(UY&Pk=(Q5V)xetPj8s~+&O&r-#M+BjCnWg4TwKpFL`dyz;Cvzk-T$C z*h|p7M)jm|_prxchlcAWZ=D|YA-q0ron(_k!~TT+UDvU@EW>_=Zj;tYmelC$Wj(&{ zy2-9@^>%)wRdstl@9Eri_luKveh+)_)_A9X^5S-ZyDjdQd|C`#eg0+1SKEZWdE@Tw zlYG=A@cEbaPU@Z?xOdy0N&R+#hm9SW+`duR<2SL(;ABwqu=lTY_|T;5#IQfm-UB4M z`@r5CB)X5l-b*ChS%81-eu0F$4B$mmMkm~H0NZ^833ngBc27aVod~eqm5}KE0(-ZR zaEAivwkl6LJk#8H+k?g@J--Zl-s`lG{MooQW0 zCbzc=Jg4`lWK#RU!$*%!Ce9Are*BnZ=+N-nR|btu=1$tp<+MFcXqb#swpussQcdgq-mGa1CQHqVS3f)!KbsY{U$xX zbKuF{<7~Gd!d}V_x3C`R@wCD zf}FXRZI+#MV&J=K*3Qz61Hay-dUjuxz^6S@C3~@c;Fmh=m+ib`ILkci^Fy&b%s{xyxOi zZm~(TNjnF&_w(7(xp#ZIy`RsfEuZRa@8`2A`vSrS-%_pOyUrH-xAgX1?>JlR-_lKE!uM;7{aYG*{$fwJ*uSOuC%ols zv42Ywj(pRZ=L_k^bBDft+xz*H_(kY!@8?tE8o?HKC?(zzZ1IRv;vm5mrzj;p5^V8{ zQsO4T_N_c6o)T=|&{N_p!IY)gFBUr`B~Ai9ehX}|R#M`+z!rlg?Y?(?dK2?o@hVAGcP*{x8kjqnnyvcE(|NCT=B&WH z?`m^dbvuTMrA&-BoS34a}WZKTP~3 zCF2m)rEV7RCnHM$tJvWlka#JC%bWXlI+QyO0qL| zEy@1e!6d(MHv8bN7?l1Mm0LPI&L9_A_90EE;bof0tM^d4GwC zDWo_;u;K{8#O)!z4QzGvI6|=E2*HXY1S^gZtT;lj#oO^XLP{qNkMa|r2UZ**SaF14 z$|cSZj6THwffYvxRvaN%afHh09!IF0-{T0u#O;wB`HpnO5rP#*2v!^+SaF14tCz>vo{}a~! zPgwguVeS8fwf_^={!h-r<^7+q_J6|K z{|Qqs_J6|K{|RgVC#?OSuzUw=|0k^dpRo3S!rK1{YyYRx+5f5h?Ei$d{}a~!Pgwgu zVeS8fwf_^={!cjXuho04!=CNG%U@!z>_MgMrCl70%JWRRlV~4d*9@aj2So`E*?UOI3`#$+{e%~h# zYo9zU-@)1^4{M)1tbOvZ_Q}KAC$Dt&$tyqmMo-Q=!069;2bg+k zzO#9-l5X>3B|qnPBuBpEw>HmK%C-5oqL0oKk%x0b(qHF^l&<+s=ZQ#14(A;tpYskd z<#OHuMjy^Q!05?&2N?Z1?*QlhwfgMdXn(%@yPVz2`%8>Zb?y?@xl35*E@93;a!wG| zxl35*E@7R!gmvx`*11cib8b=jInM|qhjWgw&RxQk%ehDxeK;=(>)a)*bC>X>1H-w? za=M?pEa&%gm$1%V!tx!gbC)pZC8dwfU6QVIm$1%VDxGteu+Ck=$l=^2taFzz<;tEq zcS*X=UBWtd3FrN_`iyf}XZ~HzIOqK(#-}=;4(oh6tn=xx&ZomVpAPGMI;`{Qu+FE$ zI-jm|&ZjFs=hI=GPlt6r9oG4DSm)DWoll2#J{{KibXe!pVVzHhbv_-I?_ixzhjl(3 z*7!e~Xwod4GxVsg0{1R|mH7*5mEK zHV%6n9@xfbkIw_!xb1O!U>napo)1j?BI5kO#5E%R53G1cN+;ft@)Pd}Mh@|XVB{0; z2&P=(9l_{BydxMriFX8}Kk<%W>P5UG*yh1Xy3LQ3{5Ee^@z!AE5El+cK5^k-$|Wuwj6TGLgVB??a4`B47Y?Rg#D#-x9;~F>{8-6v z^JYbkd`EtpXDj8}{9DmSapB0LxNxxI!YQ4&aIoUS!N?&l9E^P8!oieFTsRnghzkd! zCvo9m^d~MHocGu27>r?m#or|cW8Pn4e5&}Fu;ORJik}H9ekOdL#kX8!_qo7|p9w2| zCan0Gu;OPbo%oZ=Ph3h^@iSrM6UP#!T;f~8ik}H9ekQE=nK1PtekQE=nXuw#!it{> z%XhHiXTpk~2`hdktoWI*;%6$I_?gO2{7hK!GhxNggcUy%R{Ts@@iSq?&xG^-S{#H!8vON>tyXBbwTVOVj7VZ|AS6=xV$oMD)_!Nk{v6=xV$oMELCr&sxj-wP|w zFswMku;L8EiZcu=&M>Sv!!Y$C&M>Sv!?5BE!-_Ku%XhHi48w{u3@gqstT@B4;tVUD zIK#>>J1EXD>54N9E6y;iIK!~w48w{u4Cno|I;MBn6Z?0G>7DnN7@sO0JFIx@u;Q`9 zipLHs9y_df?6Bgo!-~faD;~SjiD$0-#5so*j~!M#c3AP)VZ~#I6^|WOJa(9R5sw{K zJa$;|*kQ$Ehvhq1@z`O-V}})w9acPcSn=4EPCRzyCmuVjca> z^gHfrfOT&Lta~ez&b<}N&%G5ea=5nwcKLR11x&fzTLGgF_g28@$-NaY`g3muOue|b z0;b(6o%XE!v~$Uk@5oQT;NA+D{vv(ochZx7C;fGA1^G$m-U^ufvIBBtAD3UY8|BKL z=p#F$r|ggZ@=M-d%zdlxh*>jX&G2`)BPQ=JG3|tP8u!S+tlzj_24-Eyy)!WDJ?^7{ zSqE}Y4b1wG`)gpwX_t_xmWF`*D;^*iLK-yy%!@5=W@@>}##e?d?6BlK7QqF(BE z)*mbB)=w+>t^Zc!$alz>?_l{3mhWI2PyD_}*v6Aey+~KTBft6`a%3Om%Wjk_d!mo* zjGnST`pYkQf7#r(`fgV1ceWP#Tinf>_m`OVW9yk%>ls_;_`SNM+xo}v)rDoLDqSLs@(kzeaK4HCUKu=fdx-Y3|52EUJ+ zJof&<@9Bm~*Lw-_>wN`s^d7_Im)~ztuHLJlkKTu%r{0sGzuuovFTGc>_bruldk<5| zZ|`R+a^yR7v-dfE|2S;#c`EwY`=W}T_P(g1zr8Q2)QfbzS0TUbfE?M!<(J>9P_FEW zKC&}<%KqptzvTS|>uyl$t~)5PiSDMvR=Tqi8|p4gY^ysivAOQP#22~~6CdfWOnjHS zLo?Ccn&j7=o5;~!oXFQ5os_G)JJCmXdZMT9`b2--0ZP4eHz;*iIyO;$Y$Z9^Q1Y>@ z%Eji=2VY1}d?fwxo$5up>Pvpv0Xeb{@?|&5l|9i%c1BOxAN}Q*yuZY>G5HRb?_l{3 zmhWKs4wmm=`3{!vVEInz`i>yqkuKlC@*OPS!SWp}-@)=7EZ@QM9W39$@*OPS!SWp} z-@)=7EZ@QMoznFkLB1nhzJujESiXbhJ6OJhf(MNZ) zqNna`MStDpO1*T)D|5ZlSpz6PYXiw)%^>-#B~&hJ4C%w#Lwd4Sk^ZbzR4>w1U-HWi z$dP@JFS}8$?1?_IGkVJY=r6zI{Uyey@*OPS!SWp}-@)=7EZ@QM9W39$@}1K4-CVvS zUA}|mJ6OJh1rCoIprx+|7vVcj9iv$^h;<=L6NM#TT&nOb+z@~o{p zYVF-oth;M@HqYH@YxN1SbjYteaFL_Cagnb(b17GM>7tMB*hNp>y^H?3lb3qwu3nyP zmCiG-^7AY#IXojvKF`i7muG6}!?U*Z zQ}#!H`6cf!F+P>=VEGP~?_l{3mhWKs4wmm=`3{!vl&*bZ@*U~&9W39$@*OPS!SWp} z-@)=7EZ@QM9W39$@*OPS!SWp}-@)=7EZ-?z`^4ls(&al?zJujESiXbhJ6OJh^Zv@m zT3H<%=VRZW@K=tFqu71;QSsAY#ZQA3KMhv=G+6P|V8u^^6+aDDd^T9I0b#`kgcTbQ zR%}36u>oPl280zG5LRqJSg`?N#Rh~G8xU4(Kv=N>VZ{c76&ny%Y(QAC0b#`kgcTbQ zR%}36u>oPl280zG5LRqJSg`>;e>pZFtk{6CVgtg84G1eXAgtJcuwnzkiVX-WHXy9n zfbi?(*nqHN1Hy_82rD)qtk{6CVgtg84G1eXAWVB8HXy9nfUsf%!io(DD>fjk*nqHN z1Hy_82rD)qta#C|Vo<}19StjXG_2Us@YEL<#M3&AcRi2)Z9#nF{#QER^3iK?n`T!y z@7r@>T&?Li=Ogc16u;VLtn=Bu7ss1kG{$+yx$nkTKM~Gl-+k$a@n%f}@6!L1c)-h} zJkL|JzK9218+h{?%i?Jx1GhYSdEEZqz=|D>Zi*cZKU9t#4J&puyk+sgq_KOXU7QfRnBQ`z9x;t!#U6(hdmL8maai%jVZ|GVf9!r?a$2>pN3QXVi;@e!47^~< z#YxA{!+ts4l|X*ozW^W5`{C@Wj$tp2?oA+F_a?w6*SbIZVbymrJm{wB*@y#wbl&2f z>Df6~t#ZEj)%&xTpZVSSvkM-~Ui>h`f!TfLjO^-1LwuN}Sodqdx?cm{|G5iG*N?HW z!T7;;7nkOp`l9oPqc16a`1o_qx@(C%x-SXVeMzwHOM-P@60G}@VBMDlTU_GO$`?0s zKQ5Xwx-@_14V^76acPrMO=pWsTEL7#>*yvt6lSDJHn7f;uHNyz!4ZmrUy9m4sh z1w%G04R3Xj=Xr7Knx(I%?dQDp8Z}CrPH5@;X|uIU7i|_f7v5W=^u$s7I4_ES&Q3UX zZ|4=ef0GT`qnY!!A1}#%U)I!F_a#xT?n{FERr@fz`<;+SceIhNyOZEyPrQ*e-zUh_ z-EE}n?lxF=x52u*4es;y%z?eEjkfjlVS7%^ey_5#-lJNDe& zdHm*gXE*iQ!}-{D_hv^NwU_f%8&A)A{TS@2yW7x5cela1yA5tN|pw#KE5I;@#wUNJ1c4_IinIVS5 z&(nLA?rHR^k2$l3Us5_V3i;#XE-GDLC$R3L)|(?&sp3fJ}sW_+`jdIxba#qIX|`K$hgfm^PIOo@v8WX2f|oqYub2+hXdpn_Y_ff*Orj6$IZtUgSnl`%n z+{D?|w9&(DIyl>!HmcR?Txafv9{FG&XYP#db@f1J%HlpsWa>UjSocxFZ(ejz^y{eC zJb;Ac-6W8!0n?+)q_v%UZLo*t;0&mR5R`OS9Q#P!F9cDU2_4dU^$Lt7p7NS(ODexVJ|Y_VSaUA@51 ze6nUdsu1$@So(eR*~4Lt^m_7Xl#E{)^xyKWXz4pYIN$iqOVN(^EO*Yoe^~v#D4bjT zE59$wzo%XOUOk*?{VTs$&wtNa{r&MSpQHck-yb;(!&r^Kv>$-)u-YfU_gU>9;JdB% z74SV*=U@2Ft9=N3|JDA4)%!HUIUv3l%RaOR*^TeTvM1k*WoNz@%l>>XmR}eTIrDtS_&%upT6{OuKCadK*~0k|zB9@`jJL8I-x+03 zzB9_sd}oyX`OYZ6u-@RT1pZ>Zq5Y+N_tCynz6WVPD&L8;PnGXS+P}(oCGBhFdz1FN z@_kDCU{~+^4d)S9&&Y0kpOQWKJ|#QzeMlYO}TYst8-}+I-FE$?f z89@AH{Vr3#v;MgH9GTg~#`(Y0IWk)x`dMlGW%F7|^P0_fCCzs>50*3!+Wc73{Aly$ z>hrc{xBv8cTlRv=U+g)A@fUj$Vf@7&MHqjvcM-;4>}iB;{ZnGEBW(NVN;;2k`|e8G zU&r}q_Dqt8bnPc3|LV8|zE84ZXIr0F>~HJ#lKjGW$R0v$$au(JHJI^`J#4V8TQc^x z!M2{s*z*S4IwxZ<9Bk{Kj6HI&?Y~+bzs2le>*UhEJAMo64fdX4XVx3+ae`TIu=fdO zy}_O+nDqvGrC`<@tK(e#XX9Mut~2 zX>-yxWFIR7#UxFcHla_hQ>SY9r((NPmWi13i}D4-KJ|?^VN`k_c`aq$8-%m zuhGSE+bsge8(kJ(Qzh_W!w1Go*9rVkz&O1ch7Z2Mxh=_aSVLKlYalbrl=O!ZVormo_MZ|sdu${ArxThXQ zzV^ejr|7}OA9^}_ez@bFJnRJ;a7keH2rc>f15an~&{jtWW>3+PgWvab_8Jwhe$Sab zNK;0=>&)Jyt$MuU{KnavCMs+9hqp;~T)D{8cb>Fuvi;IGox3O7B{jc&%lV6e+a(+Q zw%GZ_^S4WOtQq8tTW7nZ^(I07cZY17oK`QC`$fD>@^zJ0nF9hH1bmR5$&kaKx zXma+=an0)kU-0&=arHvjcY5_(x5ra|34H&C1CuG2hrQDsw&|ZVdpzu~?y|IRvTye) zUaw8IzBD;#zp&TnsZ~9bnQwyIjj!x;wmtLfA9R=h_CVW9uYJ+%v47#N>7L%QaBy;4_o=>Dt<^0ZlezaTh-ga( zJ^PQO%YJPj73^XxVLfMn%e&7HgSZz^ERK9Ro-luz>(k=sm*RJ?`_lR2*ItYdD+HUjsq<2N!om+d{kHXAj&BI-qdt2XjH zn_5iJ=5N$>e)7Y|;_+A3cV6?^N8($jZ0>x+?EB(_e{bmg(p9&`7w*}_`P&aB#*go@ zoAZ_L-4Z8tcX6I~)h+RY&%z$mhpJ4BpPwD}rncSs*0{^$uxIt^<+sJB-V^q+K6CmV zaq-ac8{AVOuzF^}*fo=-NX*>_@$%%iZx8OT*sU^z&))Yd^L0 z{HND^HGY2Mu=jZ47ca!?&k20V&CkYX*E`trv^e0Y__p-|kNEYm_=m|M&#+I^xap^D zJkPI<9*u8&?Lg-%X3vPziw|&K|J?`T=(YWvXIwcwzHU`(=K*)T6&FW@{O8{CaXkFh zkpII6zK;7Y5B$N^KgG9v9rAShy-MwOA)vac=nS&>aUPv)>8+df|tGNv#*x zahWY=4@$l}J)DWy|CGT=|3YXFJ1-iX?9e*wr5~`>kYq*Iu*be(G9+1fOD+FxwEd9e z#W(6WU-rS^vh#>Jr^gLipXuDG-f8i9EC1oVAZs44yeoVMzu}rz@tcp1 z^7N(a9~Af9W2Ez#?+=f+Z7|&VhHa0DFBuZz*Im=|gt*aV13kUvyiV~iJ6-PFY3(lY zg->7NZ1OY7@AT2d>6#5foIvBK!u3weq>ueJ({D{?CYe@Nrm{?jOgflunRGLqGwEz~ z$y67sd#1XZO)}ZUY?aAY3zqMby?oS0u5)(&zS*L+YB?V}imtJ zPk89~?3cAScOF>%8GOTLvGt6bA3mOiFu zEIm#CSo&MNV%5v)8>_x%hgf!K@!G=lm@mTq+imxHI~_Yc?5!=n_)&V}W??+M@sg$K zwhyi8?Q{DTKc(+)Qq}phDr;qzwyx&9c!wI(hGZpeYR^nSxQ%({Z&l6 zo!9=J^zc<-KY6Qe*Q8JEA7UNbp5$~zm&KmP);6j3D%*bJRQru>A9AXF$hJQ@)&6AL zx14Io^^<3z zbN#`MO5<-l&E@oM+o)8vcG0=o{S8YUs#fuGJI`!T8vDW)&Q-c@UfQ#3%fQcVTH5>T zus?kEmz$L4+#2?W4|}^_sor~GfB1Iy)G2LoL$Jd>lST6<^B*A3jLY0E6@6!N!y;lS+qQ$lgq9{0|PBpIy@`tcMRecR^O|>9DST@BR7N ziHC&s_7(TNlAXKwYR}(j$qU(CW5Swk#>8i`3Fn9P-mq)uW}{CZ;dwTFcTV< z&wDf5D(m5S+Lm6=Ccb`w^Klo?&o12OBIn`vzMO5c_+sZZE_pFK;=!KIKfXUNyYPYD z&IkYWeD>n=eVm&<`F!@xvdf$g`1q@A+%ci7U*;{(rY!32>DP?>IcxUAKb-enwQi~K zOvv+VVV%-#kAys*99yll^|v9<{0?iCuJ09i&%@U!EpH!q)R5n@o%#e`-0u8R>;5;p z%x@pNxKyPadp~*b;?ms>Cwcn)Z7weTqxx;mNAbf(WTg|VX zl&(9?d1=kM$(*OVIIn+Iy=2oSr#MeNZj+?R`<m|?a8Tie1 zHIjEu8RU7I*QlN}?jHK%4h`2$-a37Nr@uaKon(_kL*MM*b)BSm#O0peZPGf)k{W%T zAK!P~WY@QPJ3rE@dUE-Tp|5q_{o>@E->>uZHQwo;ytrN9Zj1XRpB4jGpMP2M)i&3A zo^ki~Nj~Zl`20(ICw0#c+`Dbhq<*`=!^RFwZr^Bv=bzYRa5AX*wa%r(hbCPohW8A1 zzA~xXHn5$?Oujqr3eRI_Bom#Hw6l|m&Q98y%0y=>?W|>@vzB%SGtn7LJDZv4Y^I&r zOnNj5^4CnROgcQ%+~se3(D>e1H2lMnaW)$`OlY(!Fj^e)cR zx{OS2Zxwh>?@`I5_JN0w9-T~_9k~7YG0D)O;kU008k@|Ww4497?TO=(f2`NUdG3Z+ zBp1%y!@0@CE0QlKgtK)ct6rIOo7BwHS>vsJ>-WyA{XQBK_C>HJ{HFhpo^I>mY_ncJ zIkR5fdCsrStRc4^7MQhV+ie50=KNveFCmYuMGyUXl{0J9ruzhD?Rr?}pFN#5ZQ5g{ zGwW^1XAQjc&80p%vph1A2wSRn04cdu1h@+>&X{Z246^ zI(wzxUOC(Oo$A}BzyG?zd9Pn;rS>NxzoixJ-<&OP(SGA>GKwb4*<=^33}?#Br5AGf z3pqK3ocuzrT+_9pPn6R$%IP0P^i?p}M2>Gm(|I+2cz z(G@P&*STC@=W>0`UUO7m=W>0W%k_0G*VnmRU!}X>k%R7(0hjCROkJ@l>DYiWU~H4q zllpqP>Ko*E`z*qwQwEHUDMNB714cf7VA3c9CNIB%k%2528)HXUek`ZE-^=;EJ;3Om zlTZ6pxn2f&ut82wFN1XaB0rw6NzZh~tveU+=}E_3m^Q06)%ltx-O>{_`O&%b%dzPb z3mQe_>2`3E+8<|2OYPsBEpO3&<7_gDCd=7m7p)9u%FLw~a`_86Ifb13C|7Qj(jqOMb%rSuTfmfwjbO^ec5t~~O2-b$ zU(CrVVmtCvX0F^crw{g*p7=%jdtc+Xv=Q1TTyBTX<#y;yTce$mr`!%BxZDn%%k9v) z+zy?~?a-Ne(N_2^WzvUX%TGIWF1JHx%FLDPZIt}wb|^hv7U{_T|MNK6aonWnsEsD1 z>nuL90KfRu)#+PzzvNth#hCP{jW&r$Z@yq)x?9uzoV)ipGqpd?mX_MTIa}V;e&cL1 ziYCk1WEZUrXZ)2*FXZwUa&n@a{3uth=~~ez%IO*9^!NT%t{3UWa=pm!Oqu9ft{3v1 zDU-U9PMOp>$k`;q7BFREBbYL=9bB%L(u=wL#he`M=6NVHS1xw;bn@o(#4pm{`&ZCs zLZz?KzbU)Zk)^2lPXnBvT9rnl>I`+Bd;YAb*XtvlzaIW@RO&s>#_vIsE*O4)bXDuC zoHyNnT9hrh+PU?MQ=>KOU+a9$-czEVUcHt+?)_r**jpJJ|FUE6f1*9K8Pl{td+YUU zzx1hn3kBL+{ThSQ2i|F2puG*AH9S41{XqrVTiSL^I&9ow1=`#DYh9Vve)$3aZM*$1 zN^e+nM1i(<$E5M;Dd#=na&}zRC#^lOeSvnk|0`FeXAVBHKs!8R*wyKE%StYP!%GIH zEf0Ch<=;JjXuABu=Uo0CCyz{<|FlMgZaX#Xl5RC)p3DFKi&5#QI%`Mh*|^Xx-KN8f zF8|3IW75&bzU1=z&l;2Vdc8)3{*!v1pO$)W7@_~u1A3)bwXPGPf0y<9rOWDV@A7|b zd{CM#sT-mH((n4G{W|U9@*h3>@N~`k8%OBB^DhI^pI+TKLjS#Q9+<{`_H_9V%s3`p zbiqC@zwqiw>9dC?F2DZ`T~d?l@~xb-`8lmz{*#SQPff1Nw{p@ID_Xn!-&dTGR{eNi zm;Y(4GgFi6@~xcIfIw{lXG>+-Ff z)a>H&%}%M=#pRowQnQQ8H#?=~SC?;oE}C6jzS$`?zq)+$bJ6VL^36`E*~R6Xol^6w z%Qrt4&95%s{9H7@x_t9<(b}BLw>DTbzq)+$bJ5zL%eVGeG{3rh^K;Ss>hjIcMQfMA z{_nIdTDx@l)=rDoE?vI0)1r-`E}t>g+NI04c3QOY)a8?I?b792J1ttfbotg!i#E=> zeDc^h>+)e6XI(y=)4yP2uFEGqr+>l5Uzbn1jlV7*&goys>0ij{U&z_Nkkh}AvwtC{ ze<7!TA!q+W&i;j*{R_GF6Xon*$hDs+Xa7RZ{)Jropx%N-L zQv0D_sr^K`_8;Zif0S$gQLg_+x%MCB`frqL|52{}N4fqR<@#@w>%TS!SH_Ab<<>}>hj&pgPgZ{N$Uo6jG*x%*T&luN`Pd{T^Lq7eCak)HyVSkrTKVw`j&tKTz z<DGsfle{6+hB`Sdf!1WI<$fut%FQPyFjClq5^fTrag z^66*H>!JOufn1kQKVx1G?PqP|x_tT>^CI%;XUyxN{nYSz9r^S#=5^%L&sdirpMJ)? z9@1WLAq5W*^^E&eBXRJ$*Pd{T_f_(ZJ>k{PC&sZ}dpMJ)=1o`wc)=$W% zpRq1MKK+b!3G(S@tgDbuKVw~meEJ#dD&*78cm_Z|{fu=L^66(h4X)-pRuk& zKK+d61mu&4=LF=#JSQL@&goy|nF0Bv=kzb~{D6GYd451XoYSBASNb#mO8;Wc{>7aB z#hm?%IsKV`rGGJJf7TDOKkEnCznE)3Y0mz|T>D9L_GkSd`xkTVhxL!kFRy=GKK(4$ z{?lChVg2Uzr=R8859=S7Pe04Gf7Wju1*=JLSe7*8dtmS^sPNWc{!4GtG_vtp7EB@|>dapY^}SPuBk$KY4!9_|Nl; z#($n)H2(98=ZHW^HHz2O!t+qj#mhSC= zbj$Bdev=bPj>&gMzWs5gOe@2gGVM3clxeb@DbvbuF4s%xg@T6nX+v#R>WGllK;nvp)X!A()%rs@5Y&yL8m{?b!C{q(~pMBDAv z)VP7y7dhm4ddS3xJiH$Zd1knL(vffZQlz zlu9?`OCPI?mx~`^WX`z!VY9@lzvz%_1OFluIVzVt|CE1I zB;AlNeUOiT%Qo?H%eGRvXSu!m~S;!hBIa6()~MEIlq7BD$DWjTrg$k z%B2kH*C4sybGE|@aWN%_$gMtAA}^KFf~!IVjzVami7u)cG_l!@)& za=o0XZ!W)o=PJwb?_4lt=E}v+(kIR7iC;V&zfeYy6W+bI>+@tZWM+8x{_(uWqem_u z=6N<;XwMPJ80Rlav!Ww9gz>-C@R`w0dtKw{4eLD+wV8BX;9I9fZ#BHZdCzKhM|U^5 z(RpV3DN&6#0@JRneOdeY=NR%vzt???J$Lf>)b7f0erfvkv@suN(05q-8=POLT`0cU z_!{RYe|x0Z<%ZGD-=DKiy7-$g$2FY4d-~11(>?vwLyt+Hx;}g#>0j-le7R9BJ<8>e za&n@a{3us$A*YXxIsfdZR+j>Gw7NuA7iX(WWMj@&<+_uuI!3v=W0y$%&g45=eG68u zv(>j?`Z!yC(bL)Li~i15U+U#-^);Cl-LQkwv5)d&H)rgYlb`0wE#~y`{w_b}>X_#0 z?tcGIwX3RoHZ4$A-M;qhHvCxkA?f=~4=B)v=WH@6y|iuH0&RHvMpvXe9nh{o z8~*s~@#&ryKj6Pz^vs3nS=Emz(4MEXzc$^c^DLM1(B#Y0=UP1Ba)v)TIPG(7hXQST z)7P&{Uv2uV%lviFh;+k7FSyK^dyP(q%v>WvpHuHSC4J(RS6t>x=Z#ArxqO`n-L{*4 zc3L~B8KK*Uw_TK0ZU36f%wD@PJ)%SH2tAMQby>Rju`ONB%L@)ociO97gwCs)4M=bO zeg~Ix%)3XYZ6?)^(7FBYgVQY=H*uN0-|U#)-DL9!J=g6zH2t~H-Y#?1g45HcyR>wf z9WH8;PFTO-GCLl2R(jNwHZJpvBlk(?AJfuh{&x32(yF!Fxy;SCYMm||ysyh_dG`hB zCS#6snbqqYl&*WiaW3?Be;& zPU&N(pXKt`*rIWI{Ls@}{>%nPr)DGnt=TL+a6u0*YwCO3r1i41{I_)*e^4~r`ESjZ z>6Fozc)3mM?~oq0{YC!UHFo&2Xm<49nqAY5E&93+lYiJbeZK$Y{@b@3e_u44`fts~ zskH-_Z|$PksYQR+=d(9>!gt$lmB*4~TOzP&7K??r1vF2~wb(b~Gpx3*ujwjSzuK)a%i^)8cf)!Mqtw667;F?{dzZx>>>I1D8*F+f_lgwqv&}*xcaqNiR$d zdR}zq4h5SVTqf!7%?Nrf?Ymo{-zPm?=B~@GD~ug}mCGExWRJpqy$85%Cq6#0uxM$} z`LSP{6=wc0)b(68WJ=-di>?ncYqThQv2c{@xz@;g3%NE^*l+w;m-*3W(+jzFQfU9y zm9FP0-#=8ywa+NmP70ISUhVR~{Ap$(*FK|M+bHDv0)5+cqp#=MMwIIp^mEsfexGX_ zQLbOm=Y#KT4Cs)yar^XnV!J5UW};jlVJz^vFg9#Cp`F{UOOxHATpx)Rop!wIHfek_ z#t5$$V@9rzL=Bpq;<_!_GLCY6Av*Qi(_Nn@UTPJg2V)(2?f2$cUhbFs91u|+V;$vF z24fv%E}CnI0VjBm)!jh_*+7~hbc8$WGbQW-xZWHHtuJ2!sX8l^I3 zM!9j`)+?1UGs=zgQEr^KwM%9EjB?|AlpE)x+`JRz#`!2W2SvF#D9VlVQEonpa`RC{ ze<;tJQEoo+^zz!wxx6-ua`Ta=m)B{|<#if*7R&RarT&B&NkQmH1HCMpHw&yeLi?%7nBe8wycyYe=;hkHSz!GU+EQ)C1lPgl zO~yn2t<9SS)*_*e)r(j^p&R|o#tPTR=1s;%mt*s0fi+5Kd-WsMRp?3ov$4_T*t|(w zaryK`)-ItPZqC@~zqNTYV!efK^h+B9gKh6wn>OTf=%cI!(T6_D+KY1OqpS-lmp;n6 z5IfLES$k0yeUvpK^68_j5xtJKX5<+One0vfeGXPu5p1pY@f^n=aqx%_3{xa{FXWlj~;lRhnxvtSwy!)|R>UncBSNW!XH&+S2RJ+S2AQub0hf zX|8>;wsaj>TiSf)GHrfKbA2JTxy|L+T$iE;wn8tP+x)jS*QJz)eJGzYXiJo7bDP`H z=DHNQv?aCoaZ@C^AXQ+nvZyP(;UPz zn&ukbA^5W`{RJ++v*JCW-epC(XWM_*v$ntY`{#SPfB!T1|5>l{`#`U+-pl3Q4O)6d z2i{dy-X-SV74t6Q54^jmywCYR--V{UE8tym?p?>fyyw9;|F8E6IsNV3*njZ#so-X^F&Z_&ryf@DM_TTsp>Yw#Repv_JP3fJ#m&N;G-V5=* z3+8m418t$0TV^DdNe z4CWmveZTCBf6*bA$H%(zZ~eVuStjj4W%+wW()C^u)_X=5PZ;w-=Cbg=YF9eteP zw|Ykk>m4bKJl>HiopD3?bAIHVs_gG$8s+l+g>gWfxBs70_e#C|{VIC?QQzh2_y^nS zKl|yQ(C_|j<4LZ6;dk{r{JYivt39aCj#z)~be(;Qv&i3Mt*YsBr#1IB^Xt-8#S!Zd zbzZgWXT`q9+#C4h7mKUx5BW*s-(d3c8yFeLf{{%bFnu|f-XfR3kdsr$$@en&t)+Px z&bxl*WxyuG%YaR`)qSnoVJkDTvRf$KbSfyn>FR7{B0sRnrwsCt#=iwQL%j?b8I%Dd zn=;^Xy_7x+oyz%(IXT!(@{750v9qURgPfkloc<|g=-X57TN~f13Z(PBEB9@VZ(C-I z)!z#FZigNIx4sqHnK(aFh7O!5<9r&-c{R?b!JI+kY#MB5;`|Rx8vh29m*2q12t7=Pal4bH-D0IAiN<@>icZHM?OmZ1=*|seNk>-{N7~4*d&O|AO@`9@e*b znD5Da&xZM)Y`<~ldotg@N#}bq-{N7)%%%Icc+x2|C&$0VlTM%J56ri6`a4YCoSxp+ zNk=x{;$h09Y^9?UjE?9EBZoS``W6pUrv00zQzo_`oieczto{X;>!o!67GKWq-{N7) z#C9-c=E_ZT`e1+QndbCQnZNjLdH!kvGq*5)!ptp*X&m%Bp=E`OM3Oa=O%eg#%N&iYaEYDxFkVBd11d|_K zVdfU<;2h>JXUe3`q*ErgfUylWg3I%lbGcqhXZ})t>?1kMU(S@7D;GO^I(c(?GJi?` zlrqL|FqwT~>DgblDZu+2KR*3(^QW9|Z!kK|Zrm^;z3-O;(mOV5;rvsBZfXC{otzgh zI57R;ls?Xrmp4p%Z!^MqVvCQ8ogclzd554GdB}w+hw@;`M-Ldi z&<{pm^oFSi^?|7$^@OQ6^@p(sc7d@I_JXk=c7(Aj|KU@{E_l`!X>`>g{hc3rc2?A9 z@nGkkk3JGDUozbJpq>v$eV2`L-tn3HqrO{R;eBdOlY62y*S(6qRzN2GJ2$q_H$9#4 zfN_C5tH;3qoiXsw@H;YTSF|toUc&6_WPd8mzE1XPhCE?UEX=-6{=n?(WX~r|UVZ~3 z16eS#kNw7d9`@R-dzX?X8DI1={Md-;YRN-ge&t zZFRd%$EG9uO!ePJyIzp?UFX08?RJk9SEP-HOm{h@7cWhpUOdC)9MXJ1`pdhIx|}BU z2B%HVneB4kS#NmSai5=D&OgSTk}hcZq|15cnUU#l!>UB+bLhBk>C@*|jnJp|r0(f& zr>qm9&t}UnN`F0ny$F349@aN~`lrSbb=m&C|*Dmox8_F6kESTe+OsKkk$sb$oM|bI50Bq|a~B#^t=b z!5(Sv?GJM~{d(-3R+--3<;=XSkZ$$eaW1Fh#;wyqtxj+`qXw*-uGs%1mvhZ``=|H+ za*E68+PP*r;I%Vd&er$TO7~fLuFL8BN!|3mdKbBzlR9sj9=YCmF6ZHspDLd9YcH2` z>V*x`YL{K?a)xxCSM0T-ugj@A_SNDw2M=&L&6_SPKC$Bvm-EDJZx@f-=2Dk4;N;Vb zuP+?ta$ei$gW~L=16Hg}H7V};h?{eP%bkM9@s|7hN*Z8`{wbg^1b6bAjBHkd#IcoaPEiNqt zIb%0lqj22j;kS=JxK^RZG5uVJ;~QO7*l+Y8*Ws-R6ACLg?crs8HDG$7ThF1c&zmc5 zC``M*x97j$$%hN)+|l3jPd_9roY8-z>)Ge_W)#dbATs1oF?Ex<5rtN+%bZU5>%UQl;-RQ>FN4lI9z3N8w zPr1N<+jrS|(WSixyUa1W{$6-z#_=v^*^`?_HK+7;IeoXd-88zb%Q^CeouaQcJ;&uVd1bq3VChJg)AYC9 zqblb$b2S07E@z`^NrWDZ3Fy^fVOy8O-{`^kfL_=IIoJt37%R|g&1LOE9qn)I zf*kCG9*iOAgv}t70 z#`nEqAD1(Cp`E+5zQk|oTSx8M(q#^Pb!bHYAwT`;k~8*mnJr%)5iKkn?D@a=c1*;a zNPTTh6)kUlnCIW+g)2NAJ#BsEjGnf>az-~>UpZ5*t*_9th#d4pCgs{%3q6a-K~K}I zh#Yh?eTv8_>r+Gy`k4J)4)!;FipW79v%ky1{$_KRgU!vhE(hD14P6d4v^JKa4{gls z=5nx`wW}0;Xjj&jQuLuMS({1Ghc;vFBt;+EiS-?qL*KFXkfIOm!TO8Kp}$xkaXIu6 z>lZGEeqrt3<f>_gL-u=@ zL%*^5xE%V8)yL(~SFAoRhdyETaXD5$+PBN`ar^GeT@LNt?CWyMvCwb=5LonJ2m^d9NMY*+vU(s&EGDEwrT!$IkZRfx67eDvZlvhv>o%e%b`88zQ>sDdzMk=JYA%^eN`-Q_Sg8%-N@C?N9b8=Im3< z*{7KESDLd=G3T!|=dU#9uQcbcG}nGoYk%@rnrlC4uKlFB_LJt?Pnv7bX|DaGx%Qmq z+H;y~&uOkbr@8)>=Gt?b>tAWEf2FzpmG=E-|4MWHJ<~^MsoGpRogSe+0wt-+10$i^6&2c>~}28>%4EF z%+>E*|Gn>B_ZqV}vwae2<9jzwlMCN1J^9>|8?N4 zPu#x67IB%U9aA`Y;(MN_I5aDa*ybJQ7ME9zK7aR3=Y9`v7cKwvb>}S>?jQB-{HpUs zYo8Roa>fhJ4aS`l-MGy&&V83%6cy(@;XLKtOQLG$WzJ&{?-8wa=p)Yk&pbW4bKrx{ z^RH+hHIDCdUU1sp(LEFHcD8y&w?1&Ev(>9G>ek85RXqjGway!FXEuJO@ePgA zJoj7UO;11c*H-CC1736fY2-=i&AnfC{_foK)6;7`?>w){<>?a_Jmq}B*8|eCo}2Bw z@bms@*L`O>f4`z<`dGCY&cnuZO}B3~-FeP7N2GIW-{U-_*Y4>?x83P{M$h%qSE^2S ze(!>(i^m>yyYs#8o?M)N?Ih=4c4#td}>UlUK;eSv(+oAxy1+0R=`@fad+q7Y}*6a<^-(Ftm-0}Hc(v9ZKcfR-9 z1JnBPOU^Yi;;^|&Q`Bz_b*;^wt7Xy zdlorcy`lr=E_Swh74C2JuCvvvFl+LA&Q`BN-y`04wtBT#R41_2Yu1DxLw>7Q@uW5X zKla`O+KMXa<3%xm7!WX_h>D6?QAfRf`lu*~0ri@}Fghj-m}e9P6+y)eW-y>&R?G<8 zK7AB(M6Y7bpNctP&iLwAyZ`5Iz6bAfp4VAA%UO#xzqN05Rqd+1YwzBtyM4`NtY0(b zi@7#n@dh*A7>6+9knssKJ{h+# zSIm7cldJ`2sUvm`5=4i1`IGznFJ0^N#rlGas3!F!Pl83p0P2 z*D&*%`3^JRsRJ-|fcgMaAE+BJb%S~WQ%|TfFm;Cd157>qb&q-oQxBiN`8m(&F}sXzIR4u(exBX^Z`l`jO$}pX?lZF=zIfWXf0v2bR{2xT z6K;Dg>)2(A^Qe=4&aNmu=DhV&^Hr{WVQT)!@g4K0hcB7!^6At0SCbacS6Jxatlw&l z`Tp$}&rj%ZNjC3=Pv-mYzj(gEYL#rMIi}=~4_P8#@uyd^RYyLa@4DEMdG~F;&*E|Q z*I4@FkEJ+Yf33e`D}Sc-H_lhLo)hzR7hW&Drq{X2QE%Mk{PT$2lfB*??>z4t3ndNP z27Y_}fpu?n3;g`?b`@%`+^ z$&WZcpS+s=bHT@*KU(6^Y`LYUI8T1{)@C%oPIm3;fnqt4c^ zq~Ey@J6pe!*IPa4Z2d~w9dVzt^($HJ^?RJHU&%WAR-LV1$w7-&oULC;Wu6c>>sJ!z zYka>u^Udp5OSgMAs~(yUq8g^UwD#T6%qhC!7~seg4wA%RJ?L%S}Hd58v>#^R9b7 zm%MuKROcNoz9H$_=Q-ys>yJpb+v|Dfx0h;_?C?zB&;IuO1`}=!{P%mVZMfybAb;`C z8)gfSeAeZ^*#Eq2wqvnJ>&E zn0dtff|*~;JD7RLe1w^g%u|?o%KU|yzszfxdCh!>neWsAm^wgxfT<7E4VbzS*U!J! zyFdPV_t#lLr~J=!RuJDC9SO7NGapnR zOFLB`Q6Ec>+!xMstdFI6kGaj;?S8y&%zWXTYT~?IlU?S%!`p|hG%y)noE@F={ME_O z#lpGPatA$<9MCDm=lY@VCAao#aQV@bT9oQf4>ChLG-i$Wgmb6ej=MSgZ0n$N#TLV| zFG|7Ii!Dppx5I-EFW>oa!*g2){(9T4lj5`1zs|;Ot@(qWjsLf<*Z-~i`{x?t{S2-DFZJ2THShE@w2hx^nN3^!4nITd)^3l6MYg-$ z&(QX5x%~!lJ!!5w5bIpuYDjU`mz=uZc%Ahn$9#8}&iaz)hfma5UvgiU2A%aKcbt{! ztS^b{XLHrPSm#C4?sh*n9y@Pot~u^=KfCNWSLujXA8uY+dScZu6XwsNxWYCmO3BndGf}ml*yrY)kF)YK z9;>kr%{jkj6_a=z#y&LXe3@1J3gEjEPnTQ|?2zoDgb=eb8Mf9cJ0sXbM@$)}PxJ!R=Z z=e8?;?>ZlPZGr0K&wq3tH(|l*RksE1Jz$|~Y0tnHgpbeHphq8Py-^%jMd@jpp>q}XEu|Ag7N5%Gr_Vu;c!ip`d*cR;`+d|%B z3oEt-H+#PNUiwYmbNdhMzq?(ZHgRM6^d8-p z|CYM7r)oF(RPv@L4LTdqS#Ui%3z_<~>Du~q+)__o6?A%gVaw$UAL`S2R{1Hvd&c|j zXA?K3gEsylU#(T}fAHSl<>~VOyDu~Mt4Sulws9u?8!pRGgS3jX`b>nkB^!9$QFH~K5slbOVu~7AvhT!uie_OEn z_<@0^Y_LG}(=`I;tIl72YreouKGdg8+?Y1WG^S10Hl|HF8`CCRjcJn)jcJo_jcJq5 zabFtKcrJ@?Xy2GN*Ssd4nuB8WYwo+Pq9(wq6|iautlHx8Ma_ZZx*?{0b~QwOq#lZq zSDlHkjrAAo^(Sse&+O`w>Gv9i{OoE}e61LH)v@?mn7R?g)0y_>s&DeSh)>Ob)j({i zHo~fzuxcr+8Vk!e82_XBAzULYD|ya zY(o0!@W8LE*^nN!K;SLztfV9R&v2Q)RjcVncl_-9VELZ3{X0K7_gZ;!x=X9T7Y&%4 zPFmr|TKf{4{!o+Oz2EoF=viyjch2a4@%6CQVE3nTVEj3$64oR9++(-E_&;cw!1U{e z`TsZ9dmn>LecE(wz4tNbtWTS4)u&B9)Td3p)u;3^_*|dT$IzGhw5gAwJ@h@uhnNIC zAyz?uh+(iBVjKJkF%N!*Tm=6^j_T8<+|{RVoPK?gyZZFgj@J~qt53^sjVW?x`o9}p zeFRzyST_*XjgxcR~*n2au@W6 z+y%QKcflXU89zhrg8#}(Q|>|^l}Gxh{5DaXw+iZ}Khf5B%W7FY*IU z3*6zv&+?ut1-|{lkMl>b3FE&s+m#hCb*QZS~HWzBw)~8K6>(eG%^=Xq2^)?3Oo6Uuq&$jQfK8C*3r%inf z?V;~MKEx#G39$cjZII; zU44rFkUQJ=n%$7Q`V@ac?t-5ocftRVyU?$YyO4`x={G+^}pzguM0&V zL%Y_yrkDghTJM@-80>1jYl?aBQ|nz*j(jaBa_8${kvm@>i`@CTS>(?2uh~%K&ez!@ zcfS4>x$||o$epj(MeckZul38;_ga5#-LJ*L_5-!}*gl~aH|%P?v%N|!&bHsE#ozWS zwYEs= zsph-YtFqQps}E(Zr&h1ZsvA~M%34pYUX@j6tp1d>o?7iKt1el+Dr-HZUF#|GT2IlV z^%VVDPqC}@6o0gy;-~5={;S^FdYVS-X~AB%3mLEH#kF4N3!Ps73tPS}6h8QRQTSF* zO)h-)^`+>Gt#`FPhIXw-O)&|2w0_P+_Z)y-?vpBYUC3w?_6th0k^` zTB=R&hPx6!!@em3V>iu&GkF5%~U#d*c=a~9Eb z=3x7`Us1#3b>X+1KR3-g+gsM=T4rh9z)rF)J4rn5C0hqZfr z?tisc`Lo{}(l5;~s~g3Az1NLD^_k3n>pcbi()?<=Pi*A;vvv>CbYJObbbpF_`KEnK z{eSfLL|db4zp?(x-&LFCx7}ZJ57@MqsOPuN|LAWw{FbEOdBu8Og7$y+H~psl$zS(z ze}?4V9fZ2 zdH4J(qkW^dyJZvB`yc0T=NXb+wBEzc(^k4J;~z4#@i!P*u7S~kE*Ra|fU#-qb!s>H zMDnJ`89k=o8U6Op8JqSuXKb1cXKb2{5_+&{Hk^xosl6_ePa-`@q(6!5CXqi$fn4~pFY{RFIzeH?=m`Dck?eYYX7};dl{m#iw3nmAA_=NM0!$#EE8KpC^GPz7T8(J^!JmB_w zlUvqpXrO)BS077Odi=Xd@Wd0If;SMGOr2!xTGz?7rr-6TfBfVr&TW?%P`B)J4>{kw z!`F2u4X8MOF?`+RsgG`Q9(2e-$=Ab1IqhYz$_ z-<^@QzB^mrGwZvv^}T_(AdhV1a~Aa_i~0zw@5m@7T3Z^v-LM4cGE9f%jb~kue*9?34#w=Qo|_ZMbQjtDXB^dSb(|Q+l}mZ#oZa=zaM<-u`a4TTEtoZ|{5QFAbBo zdtw9px%I9`8IKI)0;U@^-yl z=GMEm$R@ASwE>xqXW!lM{avfL%pundv1?DCgr01VZL@VhIm>0XT69!HeR)(J{oQo) zi|yL$8j$ID_J-MzUnaQB-xl7iVSKkICn2-dsh8Td^JmCxwdfMr%H=68v)PQ(CM`4h zhX!Px{oowCc0HH*+rkeuL^2yZwa*S2GKY`Z&#v9tWj349sv)vfH+G}bUFQ9>I>a({ zkuxo2$qb|y$$=AkGT{H%gXv|nGs?En{tZ89BuHEBsYLWl< z{fvE{GEdY_9Z);W-!zvcBYD>Az|&o4ajkKa|Hy>)>Gt1(n@QevqcfJFP9aatHoMM+ z-I_e@g%9{YlT75Z+FeHS{6GI&yT|nSTH~5s*IoGR9LXnv51&aU>MuHzaP8sQ#-&AT zb?Cb<+B>(pv$5gLRTpsHZP?b?Z5`)y-nev8He;1{UGJvL-J9_bTeR^v7+J1?(Sa^l zx?yZud!5=%K7o-pJ2uI?Q9>+WY$|rxjPv#G23u9? zHu%=A%_F@v{_czOom<^mZ!tXEdADIxEVe_O zu`^?p{hc>muDj);yEAS44V}nx4U7(S!RW?!82i?qsNLk9ktavAqsR0+qu>5HW7GcT zj7_`78JlLq8JlLq8JkhN#jqxCv90MTMfxolHM^Fhnm?AinxB@_n*Z$oyA=JRUHwJg z8Jkgj&|g6woAeFFCVdWi7A+AA7@JXEl3$bGb<%As3tiAAyK?JC8(MVR)OpYX7i33& zGO#kB@yhJQy#{2DOj*_2Ut8^yY^{6t^Y%4Y{yaPB(D}T5O82EIkFK|gx3^emwaQNO z-j|{Cz!x{De6VkOZy$d8PL;Qx>*ejA+_q(9v$-Z^=wIp5BR$v1zkF|f<>hsLXrTSN zM+YOH(2l&d*Qwp~dpr6~Pa-|$PYHSaF}o$&v1|T&JN}!W-j1KvUvHd)BL7QK97<7ty>1k7D@E}^ zUU8;f@kGD3Tinp2_?MzQVz*MntrX=wiSk>D#tHp$d5c>TjitJ1{Mh~MU*`s#4g6Wo z4Y>E*ck%8%FS#d$x!>hp73O}IdsvwJUG8mR?sxeI)5hOmWVr@L2fAQ%Gksv46{wwi zaLIFT4x@+rXBhqV&l#Kcw-W8xKs#-b zKivDvPtFADkU=;9{nnsoY1-9a#w`W*C(_Ok*Qo5T*rW}GjW zvjzGXGxD_K3ps%C1^vZYgy#{)7yiM-89!lUxdv7qVRT~;#wI?g9bY9+++g(3HyHiI z6vn3gtpsC}7{S;irZE1S4QFgd?f(^LKIF9Mm-749ytA16(dXTa*7hHGI%9p$-I$|R zs2q3rn$CNly?W(^c~)^gbIJ89J(pSO|Hb?7u&%d1^YiTUKhzHk)9;dpG0;`kw2x#&r;;S*Vv+8w5z|!D-P&!#%2_^ z5`8QBg+I>NjN+d}d8zv~`91g2PCf=c+Wz&1uG5$EF);OoX$}28T*b%0b&G%Au+Bb< zy3EF3?3!(M?2<0?Vc)&8Zx`v}GCv%8NVedp`CMj3>npPbwphqz#vFA`_CxPQU1smI zZ_dVb`#NL1&3X5f?BYQ`XN3#!U=th2 zU=th2U=v@F!FPN`2H)`&8GNVD$Pfeij0`cL&&Uu1#so6N5=Mr(0wcp*F+FvWp1Md+ zo%EPLN#suw`IE>W>zB(E{c@S2UoJzxEIuw%#K&cd__z%5vA?-Y5oebv;#|TOu{0Z{ z&@azdDfG+pMRG+Qy2M@ST5yHV!4z*Nz|{zV&^h8MiPsi%UHjXC_ahBPVq@Bb}nP_NuoF> z7CXf`;cvtc*(hHnY!E|iVgng$MtLt;>|6%lEp{%0@6q@vS?n}^N)|hfpAs=D#-Z1c zkgpY-u|+JS@r)jgXY^=1<4;zML;T5#afm+|dhjQjU-Zjmihj8a{fg!(@o^bq8O_rY zV-#D&k}--cV#yfA7O`Zk7vqq8RYJc!UoJx|qxwVMU4~dPhds^~%czbqeq4rFMs>{2 zkuLI@Nh~>Ypq6r;!C3^%c?M?`Fy|SZUBH}Y@DHYqzro0I4U7(S!RW>Ytg|4sbKW6& z&R$^ja6ST~-~Ksc)Bfg+P0m@6!6s)uFg7_0f{T8s-Oqvwc|Qw+u^H(vMRrS(Kc&b| z&V1ZwY;qP9^jt){`is0XKH@7f_#VX#yWWmX`YeB<`1@H9?bwX>9?`n?*M7s|!ye?1 zw%_<`e*L-TSDY`H^Vp(>I5WSQo5eZpU+3f&A8H!4k(f~Hs8g_NBTPLec50_KN}k#X zt2V;aV`?L;+6YsRqxjEsP9EnAo#c)GMZcT;^?R1ZgWtF;Rtd4;x353K?^*Hhr1-`E zir+omPyNmt+QaX#g-jA%Yh3$nG>M+^_>IrQ%=$NC{ho^-zr%Af-ml{K*|=Z7@%fqX z8#F%4{}9_+ADi*Hnp!UWH%R?XZFc>4=OS*-zx8>W+5N74)Axh(n|3**+_hV)>h0GZ znSa&q80Ybw_sDnOW3Y3}54z{uo_?~kKS`IG|=bz6JB zG&Dc$;=`OjyzAt=!>floKi&0|e33PdbY5|_Q}P#1KFay=`%cbJf8n3b13n#^AJyq- z=PL#spYL_V2J!8K#d%pHb&b-;dvLU1wr)V6vt&*PdKj!x^1t z@4LD)w%SxybH;}~HVuq#7q{&Fq;qJe@2kJu%i9@y?>t&|W=t-7Oz?qN z&Hw0T-cAhbFX`z_Y#-dIhchvMpyj5{4s5$Bio_v(;TH%`QMZAI6b&Wd!J zt%_`!4;A@fzE$L#`CO6DvP*2GzhJiun~eJd%V$`9fz?M?eTNkjSh0c?L)hZ%u`SqR zUdVVZVEGKIFR=OutM9O40xMSVzuRBQGiDSAcy@WQd6BBN*t|$pb8KFuszo+0Qq?G% z7pdm5&5KlX+~!59xo`6#RZXyYk*ZeMyhv3;Y;32hIX31~)gr42scMdm`Bb&Y>OiX6 zWpyA`O|v?Xs@7Q@NL2%^4y3A$RtHkmOxY#2((myv?85Q~md~*I0;`X(`VK25uwn%( zhOlA_E9S6r0n2AteSy_SSbc{T6Iii=|K0vdo-w01z_ZH>{bHYh4E9D zg%xvHxq#&}tiHhNBdor|iV3V(!T)Z5B~Pq=O>iMyk1g4(jH5u*y9h&XIOoK)kj!;hZPf8v4Uln@$hT%EBWHu|I^Qgr?Y1x7SsCWM<9UacdOmup^E00hE47$2aNi-9 zls-QA6mJ)|I_k$%wqV(UWeb)qShirP4T3>@LpC zyK`1q)|vVE^4O)FnWy{Cx717=+k#~amMvJeVA+CY3zjX|Y*l2-+AH$G943SX1Ag~nm-lw-C|NvOvJIR!Uwkn%N8tKux!Dy1WwTyxFlMXot$^Cj2Z zw0V?k&f5ISHJ5GP<(lJG6LQUcs|mSkf;hGX%N8tKux!Dy1u6UEL|(NK zJ*t`LS1rY^YApV!_7W4-WN~auK41%$Em*c-*@9&YmMxh4YONtJT7$@!)+X|(HH-Xe zEhFz*;}{QG`xuj26UDJDShirp% z*ckjyV8+ZpR}1?hajYMfepvcp>4&8smVTF?&0d9h_ryvaJ)X>$@f!tZ9<6;)VCL5W z*9Kn0}c|1-r$y75srs zX9YiDvsJ-=*nFtaFW7vm&|lbmt`LWqWBsuC=K5jjhov8uepvcp)~{&%IMZ&q&dED$ z`N|m&u;nploWPdfobdx&-gCwkY~vwkyumgObH*Voo%BUIVd;dW6P8X`I$`OAS>L1i z>x?a%BRTU98Jjyf^AWZ=l`~Ian`=4q7q&T=Gp}Krn>q6xwmF+q2V#!(!_p5+KP>&Q z^uy8*<9}2?ooUA|bx-otLl`~ONf`aqPZ+z@RTzJ$w=i*_4#U!^KB~q_C+*S+OD8Oy zuyn$VpJ@GZ#uhnZ-9d)ju^z$XlywRw*Q{SKV}NxHW^AzD!HgN!!I)$Hu=K;y4@*BR z{jl`A{A~6r%sbY7WSB4P2VmwA`vjQz#r^?i-m$NMnUCx@VCn$-5Li0ti*&-$2}>s| zov?Jm(h1KlJ_EMdEnn{F<2`N*AF_Xb$~6O=<1rw{H_5}2hmo1p_(x{Pvr^Z|wG%7r z*K!oC7quE9dD%i9o?U&r;Dc`2(zh<*I*k*t$@{uM-^J*We8DacTYP4@ewojyd^X=w z^~L(@>puF$=#e}uc^H{l?N5+V%(+&%z@KP5*YHcA3;XUwUUP=51Wji@5Riu zCR375yS5}-=EE${9wlGca(P(iS23gi^Re5e&vfqNKEw02+rt@o-EWGyR`O!xVf^7N zBIY7KrJwt)rudW=|DQD!pIM$A(MRObLtl`Gi6Q3?F&FWvNGGwCEpjxgvk_u0osvhV z?yqAm;*%>T*7sboLVi~F{>UgMl1Jyz7j7<%KKwNIUyS}zzoDfG14G^GzUaxNAMQER zW#)SP)Y6Zw0*^TS%+kiYpW*GFymfA=7(g{l^ zES<1)!qN##C;Z?#>!+`^2;*E#zxrIzHr=Dw$?nglCoYm6@a9nG=caW`dtMZHqtVNx z>l_?-{Xr|H$L|$*yX{v?2OJ%Ek1xBW1I7iGPV7o2ES<1)!qN##CoG+C$HD#5LqFQv zeG}8Z&wB&XE6zFC+mD}dRQmZn2RTojcv$*H^+4yr>-JBN9C3j2gy9FKXKmci`IFcB zrTt&r&$-8H{n9V@4(BA&iGJyXr4yD;SUO?pgryTkXL40>o?I~Tr!NO>wtdZqcb^Pr z#ppSt@3u9cdw;&QGj{up>Fta^?;f?4Gk(5*#Foy|DId@&-_Qx;Gdf}EgryUfPMDl_ zzADUXG3|_{&TFmicFEWKF9s%$AM^-wpZvaYcwq8=)NX+p58KRL)CU`Tt&RxSN+@v>G$G1Coc4nTwb9*Oe>H|8lE1j@(!qN##CoG+?bi$^yB0t5nTVE>li@unAMLw9G zihMKu75Qv-E9#5+Q&Aty&x-mkorMps6P8X`I$`OAr4yD;*m9aPPGT4c>dmQGkYVd;dW6GkU> zGG=_HFRH7^s|KP+wGsWQnb=h=#UIsJ{8a6gPWgaNSUO?pgryUfPFOl&a;kMoOgrO> zb&bA|FRel3QEL4c>dmQI*C#Xccsd}c0d zU%`CQ9)NkIy#ez}dj{s6_7coT?J=19+IvVRwxko5PFOl&>4c>dmQGl|*Yo?no;QH? z90IK86JR~J0Kf7pp3Ts+5X6M~tUXo3)FGw!RzBPFd&!`|rJm0QzUA!!rJhHhPML z{1U9^n&9}EA2GHh1M6B?I$_y@HuXi*`;o z-YD#8XZ&lsbm(z`Utgkky2T}dZ@hN1wBho=BfED`D<=m&cA+%=e%rw8H)gdrmOqS1 z`2foYSU$k=0hSN2e1PQxEFa+b87e)OMa=cQ7OdyEU_IXj>$xvj&x65wPAq0@u@}{z zd8cEKPap2x-{;5|_Y6+w*x(T7#}6Bl&b{TK&bLn(a zyf}+{d-YS&F$2Qc-4zd>oL>0!KV3$)$fIn*vIWZ)EL*T_!LkL*7A#w^`WrK2Nil&H zD_Ajv6=@ zZrbMF&KQ{0y^s81Op-@@faL=$A7J?a%LiCK!14i>4>0vg&mL2+n&TN`>VuxC7GsNg zqI)9d_`BzZ`zGf8J}U*LCiMGeRqrpgVzZwEQ$wCfgABE$&z*s(Ik)c-?vJQN_3MZG zCfOp7vIWZ)EL*T_!LkL*7A#w^Y{BYd%#0;!IL}?f)OMc7hN<~Hrwy|f@ccH+8o_hj zuyO$_M=)#U@BA)53qcI?cF`wlQhdadba-7-boZ=i?afqY1kT?vyRhlYirK> z4%?cWv+l#T7U%2-U|XYe_6e}9-8uUQ*w*x%eFbc5eXg}$wurNA!LkL*7A#w^Y{9Yx z%N8tKu=*G?W6AbN{@x;NdnbRN5w<;*zvl?sUd!Kqgl!Mz??uAO1*{yw*wXtl=+}EC z=-2xu=+}EF=-2xx=+}EI=-2x!=-2x%V)@YA?*hwz#gP3xOl;Zb!^E8ZKTIyTFM!Dr z_X{w&<30i=r`%t_CL^-Aw6QLpqK6ZJ~(H&L(j-V^mf??Z{PMLp4(6?2^XP}-UM+@HeK1nyg5 zY6bVRFg1kxT$tLz{Vz<-;l3EA7ID7}%NB8#Em*c-*@9&YmMvJeVA+CY3sxUvW_&6p zuwn%(hOlA_E9S6r0V_u^Yh`o4v%~tR_m9NbVh!cJ9+*&A?91+!=1{0e3-!MPU99)t5Pn7s$*U@&_U&c|T(Dx90a z>|thg_9!11C-MQ753qcI7 zPniB{J`xkXTStGz#85Kg_*z)k7VOu;aUE-}Gx_*;g#To1WLyz9=BCCltTFHHwnzF; zt+~I)?=`Pneqg@gKf<#p@Fk7AczSAr%HZ6cvtJbou989bmfZP$65UbjX(Mg z8vZT67yl>kwN;bxnfgOLhgHL2TOa>pXE+wyW`BOba#vFBET<*q)W(cI*Fhg`Ecv-5 zY&F)O<$&#XPk)vJw%-^asZ1F5mb3BJ*wKP>Ng;is*#qapo;=En=Q&v~~nJC)rw{?Fe3bxi6Ry=B1J<4dW(@qNeiLMl@azG08QVN305j%!egI}J@LU1R9N~Ebn7PAq2rzSs z=M!M&;5qMvch8xd6E`2`?aY0i2SA2%UG3YguKKfuv|C;EXA5Eb?cSd)gzYzdf3^^| z-}?R8LfD=G@MjBQtE>KdI?P$F?iXwi@4u(hZhL$GJsq|^zyF>N+r5DQo(|hRg8!Zl zQyX>vqJ1Fk+RGK}dpTHpzv9~e*uBs1@mvIJqH@PtshsK=X8PD%&%o;)Lv;R{XP)DC z26>mKIo=cGooK!PXzwaE%eNQw>@@w-^UrYnytKW`+3ep;h@VlncP0GYL+si+6#niZ zZ0}b1yN9s7bK&nE!uBqPzk3Mt4w~KpiJz0#v+l^m&&Koqo!*7v9k=FqfAF&3>6;9C zMq1B}(-&CJRP&7my-#iL7dOkd6!bmz2gAK?--KP=6J8r-d}F^ zZ#C#yeSFsQ_OPC}hwZ)NX8*HQA) z_xL6QG1NO#ybIYJ?;(%!WX!rGU@I`f2erV8s!71ndku%2^< z^_(-T=bT|Z=M3u{71nP|uzq8L^&1nc-Tw3R-wCfxd);X%T z7w4$(@A12#e!E1!&Qam!dX`@2sOZ!=s%+_f1pS6iyUtNzy)OXkeF0eS3&46`0LEv% zgP?O%+VxvJtl#2c{T2`Fw|H2;#lysWR=@j`BYv+zM(3!o&QW2Vqry5zg>{Y!>l_u< zIV!AkR9NSzu+C9oouk4!M}>8c3NyBw_wR%o40;mSAe5o{yqt^1B%AI!7(I_S+V_zWYaaN<;afYLu>Kv7R=^Pc-IV!AkR9NSzu+C9oouk4! zM}>8c3hNvd);TJyb5vO8sIbmaVV$GGI!A?djtc7>73M5XzlZ7^)!TpP=XE*5)H6sr zN5!trQDM$1_5KuRn0l{@vrWBk#hItx!{RJd?`P>86+Jpfg>{Y!>l_u8c3hNvd);TJyb5vO8sIbmaVV$GGI!A@c5x?_#d+|FjtaDUY=cusG zQDMf0o*`k(=-Cp+lAbwXjOkev#-5&0VNB}T6~?NbX<;ttSr?t7VoT?!u+C9oouk4! zM}>8c3hNvdW)5=Z1~WG~i-Vc_dap|7sI==G71lW_taDUY=cusGQDL2w|5-?cZ62Z6EI6S%qzX?%!F3Ie*|AYcS^(?DJur^}#yp zgLT#i>#Ps9`w0I&Ds1-`{(V%~?mJSxH3!@Mh<_gy=DdY()4`nQ@XZ!jXMM2F`e2>) z!8+@Mb=C*#tPj>%AFQ)JSZ95(&iY`T^}#ypgY7#r{;e?BzCYvN3WM#tH2$qH*uGce z-wJ~{2h+E4E-TLZXt(e6`S(|0`;MP~e-*ax`}y}*Vb10F#vsgjoxTSce-{GgtPdHT z^@;U81fBIsC*M?rvBkF*VSL~lj4;0OZAKWM`DPBJb&x1Jaq`UVtZM&E{FEa{t3I_pCZW0G%X!i-hEr3o{J z`NpQ(D!$7KGv@gwC(Intw=#6rN4w7YV4d~BI_ra(gM4cgW^VEgQkXf*w@G2eX!2@V4d~BI_raV)(7jX52hAH-zD?2KH7EGS8(k+HahDouJvz= z!F(4;-#X)aLHY(7-x1Qc(fGcQzL~~vF8Y?5&ic^9`GES)xq)KBd4giaIfG)z`2*i; zw|UH2kWd4)>$8{vp!g7eX!2@V7~jLG0FF! zG*8y`-o%O-L<(ptu6a1_XJ$!dmwSw=F zs)q2LQq>l|U#gnJd7ZwitZ%uX2j;8~)>)sJZ@<7g>w|yGH&KZRzvG}sXMM2F`e1!? z4AwWtV1088);GssVyo|%>8y`-o%O-wh;J^zI_raV)(4YoeH)W8pl@a}HuNn`#*DtP z$yn02H+9yB9-Z~UI_raV*5|g0@4Lb}>w|UH2kWd4)>$8{vp!g7eX!2@V4d~BI_raV z)(7jX52l9jtyGvgp#2Q>LHiu)hW0@bM`2CSZ8st z&f*HLeTV1Q>}j=^E_D8%&l1GGym(g6oW%FqzvdoU^5~Sj`ZB9$lZchR z6G9Ai-%V_FKTgbbzc2Yhr^^?%TppG@Z2hf$2gCa7&n_~4V4k;uk)aC7c_yrL&X~DYGO(_NbygO$bn;vxj6C=9u+HCNmQG|~Z0VUso#D_f z=2|^3S8&F&bFj{ZV&+<%5fxl})=p;&w2Qe`=MOOVu

7p(WJ za5s$jOmJ418Sa4*p8?JcGs3+v;1`24!o}e}nD2|gi^E0Xet7QtKPO*3J=17-wECo?hH%dzV86<40nWwV72cEa_bAg zJHmpn3_kmIa6z~|JPh-F8+d!TEi8xIz7@PJ+!|KEZQlak8g2J>qLdZRc& zSn8$7ml3^w18np|NR|?P{$)7pB}g6$4~AD@qaQ@FggEc7!dx##@*r{4UxS-ogk&*M z(O-v~UKrkhjb4a+5mC+Ggr|N0$wDHY%Y)yK#CYeMV5na~azAm;;laa(@D}{^hVV8_ z^adm^hnK=Tu+J|c*$`f&{1W&s4D}1(i{XXv9?bOf;0xjTAosl~U$*ym@#b>Z3Y3GDMT;IrYG@F^_w(?O2=Y0A%pwc&Gk<+b4p zxaYOVpAKs%uLZw^Uw$fl1^fIIQ=;iGupKLkG@mc7s81MvOuL3~2*gYSj+o;nH^Q6oZF>WJJ-iX$!q>sq z!t3$vd<}e+XYX74D)v{Wab?d?Bc>8UQ&w=ZB?`@^)z-M{yZN1Ne&+y*cs-FR$=DoMI zKMk%8PX~K}wcr}we*1+r;8VQu_7_iqPll&rKk_8_1n<55%M;+^y!ZAykAsi#-rEyB z20j`di~ZE2;3M>I_FRvEtLfdc9?hQ2er*l;TKcS2u?JiUuAoP=XIud;4=Z9{xg30$ ze$AfrVQ?A!nmz0?a4G$oeeP25A^J7@;)lQ`^l0|cOTY)|(d@e)1Q*kz*_$s07ty2H z%P#^K(xch?F9aW;M{`to0KA{R%+cb0kTEKbBKLv!GFCad+zZ~rSmk(g4|q3YmE+Le z;9ZPWj!%wKcQRHvZrusq!C2*Zb_ckCvC4670eCy3l;hv+;BAajj*GW}w=zmOUfv4c z!YJi9dJA|nqm<+8&EQRpQjWVffj2TfITGIp&S!jboSqNf!1(0&eFJ!XxFL?~*MrwF zN;%$N2VTqgq#kfBh~5$PgKNO6(L&T1t_H6PS4U0aD)7p1Rn#!91m}e-|E77Uaj1XX zKt3PcVs6w?t^h9&S46Gla`3WndDLbu1LuUxqLwoUyfn;-I?$!y>~Lw+jb?+FgxOJB zx&)ks{-G8%3!E8dMeS-PI3vuATGtHl;xHp>V;6%Lg^Qz>b`f}CxF~9G7lIdr3!^@F z0f!*juN!nsjvJO?~GoD=m(waK%Bn&rjh_{IrmMZNP( z@QiR~)JM+%PY-8AJ@s_(v~YUVUrz&1MW;PK2E)X0wqk7LfDrhXjAEFo&}$AZT& zXPBOwMn0Wc!7)+S{|k6Dvjyh>M}tQ(TX1gR4B^PX%@&Si&Ts_t1ZNRPfK!<#IJ=k% zP6<=v++zwjnc0GKlF8uV%od!h91b4FY{5CqVc;ZY2+nOLfro}kan5rncnI?Z=R${o z2QyD_j&v|Mk$Hl1r-|SM=7G+pCV&Sq4|JAw5O^T-KxbbEg3S5itn2{LJ)O?h#)Izl zbQU)bbPuSryRqOH=7G-l#(?e_bsp%f&%LD14@ZISF?HTJ5_IpW^T`pQds3ZY4hLN& zappM;bXCQ<=uptTtG; zD^bkbS*^-pX$89WB|DJqHtreu0(Tv|_9c(NI#|v<%JK`{LH91pJ9Gox(<~p+6?Ct& zJVh7KJ<#$Ooxx6_bL2HTf$o`>?_dQF&ZT4IL0I2|b793Vw-cA(sud|6Yl3G2tMqcs5wSvJ;?{}=n#2==Xz zm1_tqSIE{ifUT?lH!iO}EMCFiIKBdSJ#7Xu2Cx|npgf?=Aih6f2{Xp9DU6}Kp-f^E zm_+$R8Ajqm1bIf8$3`%Z@{cl-4PhkZC1olbz*Ndt%3xw~7348xHVa@j%n-+ zd&-2?g$b1ptxYaNS}F3U8E0BCa;h1ZS|M_+8Pi%map>~&tt4;~14UGJ_`Z<7xuKr#UeV$z*QLit7e*YUK_5I>#{_G-&Gk{__ zb@?~Z<<(Es<=+6+Pu1nsO;c*lCDcvxNVGszH!Xt1xx_1!ibf5!80cJL1GBW^pmPZ| z)Doa`2{qJ`pmPZ|)KZ`;t&gCgmIhsEeH3l44CqShV`zb8LHAfcj&@iMbdB{1w8nDi zmrroNo}^SBee+4~<5Sctpoc!i{ar)7Vw{0hLStRa-G2t1wGt97<^&% z)kdQCt_LX91zp)(h<3;xK;FlCXpswfUl&m?K)YPTd%T!>eYDQSyx$K}Z-6%XAn*MW z>J8CSm(U&_qTU#E7u!;F)+V4k#g?JVHU-_u^)Nc_cA&eimZSSN1KlCD0-bn!(ABV& z=*rDO*NvSQ+5Zny^v+u19YFb?8}~@JH%yW+Jo)~m#yglw$F70wf2z9=@dDhPL#EX zmHX+8q*Ja-}wapFSid!Zd($oO#) z^&XLt>Iu3dQl_dG=V_D1)d$%r+Jk!l}w(^-sUv(ZZTrHs7{TI_7b zx!KhBL%Y3{@$XXVebIX7FfPua-j8x$#?s5tefOu_k1_UgO8wE8FK4Wsi>^F?a(~9; zxs(Q?Vb5i3z7pMf5aof4;c|Y1k!aO?9J=@rB-%C~M`vXi4 zQ>h;SYE304dLXEkm5k{@pw?G1sS`l0vSe5%f?8{xg_e9U=uY{w(Vhd~jwwzch(m1i$Knzy>R zJKv8*BUeXvpL>5ab#-_5xx1=!I+D}S`d#fg1BpI62capRiR27s3GN0u3(1+x9)_S< zo{hxa?n5Y@3u?tU6z%goQ0qo_{hSZFx82=67l2wrjzEjO5Y$R?B--sopw^S4(0VTh z-PJyd(hPLuQOt-&GZUJL?mU{A(irNq(5c5TgBnZy5_Ijc%&f*ypN$Sajv3c@>X)LU zk7p+4`pg{4?p5!E)_xfh_por8zvn2cJTUWzw2HlPBD%maI&CI9!P`VZEyASi~{g_YRhE~2G z^Xg|$>TmyYP}D=E8|ya_t}DkLl6Y?@G7jV9X!?xrc6%_C^IP2qI5qy8wG z?{;uK&8RH`JW^6KK%Q;fz{Pe-aJ21zb{N>Q6-tm|f%4*`3b1 z^jc8McD3HMQ4fBavi9u-p+1aN0esanQTKfo)V^KacO9sGySndlQR{t<^19smsP(Q# z@*K>Wn(p&a_kAAudU!SU-4~F%i(Gy8MI`PSSKoaJi95%uQrZx;-j_jlj;r;)0&4B9 z*83``-Md=vYoK=TS{}a+YWMDLf;T`d-`#QW2D=Q(!ycBU^k&Ze2pd6ni@Q%@6Sy(A z2|c$oTx2QgZ$*9gZBQF{_dC1;Y6I^+h<8D4;I*-SFXxVl_b9)cdp~Nr?<09H_d(Qj zKS1(+?nBBSL~U2=_Z0S2ZCC5}1XSDA`aOUE{OhOWpG0lfz2U!6SKHP4{a5gdsPBG3 z`SaYDl(l}>;`}R6>v#8KyZhUH;6G9NhWu+7=pQM4Oa2WE^beH2BmXw1o%?spH9Mh0 zxJ%nL^p2ofhI7php!R02xwi+^N1SW!396^KM!yHRJ9#&74|4SyW|<`Bm*k@JP4ysA z`#o(+MfZNVV^VZaNLx~MupN1!=l-@xGQa-re65Ct=57=B=5CGv&<2Sf#Vdh&9M^w% zMX)t_1@emMfvqUDAe9GOk~gPR4s1cbJ*6$9Ig~-SG`@pYq(;qaM&6W?arCq=Z9=Ie z*p$36r4nEh@QYr>EB5y#+Jv$A_)q;zH?kp=H<-z*o#%4;v0`j_)5>Rh9 zbtna}F1h}h0@}DmF-Sld$&V;BX^+OCcdGv z3N?}X=DK&M7TA&}QVXm_-5Gi2`LiYOmUDHz(zoDkat^;e$ygBeD6wmZd^=E9p+31x zfUJVMUYmfj3Ni(HtCv-fK`5IqlP{kymoE#JCNG~4`BIbuseC@4FG(#=3i;ys64Z*2 z^7&%aN`lrCj+M_BrB)>0fLi%{3O2~+$Q$IpO@Cvt>swNT{9h@5oBo{slKz_hK>7{* zE&XfyQ>_2QkzdpAIHN)SM`S;w-&1Rl|AxFl{=@X^^qcfUQiJ>_ls`gQji_CmUzTK)X97$%ckbjce6X|2r3i7MT3-XK8)e%>bKa{RY7pKe973s=!DdmU2 zmE;d2TL~(CkTVMM%cw0)mryInFCs6}tAC$)O{+sW(YuT5`DZ%?l!)yv*Z&s*MOI$SCd~xnw`!|uS~B>FDG3MUX64vva3L) zSCC(x*3DnanRWSez5JZ?Qc9PkbHH=bOCru9KR=z7o|9gj&PZpb7m#LwvyfhdY$mAm zT+XPQzmVDm>3P)Z=FcXtn?ET%8=MB7luk>}B0oJnBRw;nPI(%5Ci!W|&IFa7%z1V5 zr&61qoA0j!K1*b=~3zN=?UNo)Q(M$qjogusPq_W$Ai|7;JiBd zzfe0mJ(60T{1oy!`2*7_;KcOsbaFb8GzFZJ9+*x_4?}h^X<~XPwZlQ{2XU-U{t#*h zrxU2v$sa&oCtsVqPJU>5Kw3LL0vwu-NXL_pNynz+(vg%$faAzVBO3=Q9maXJ^P{MZ zOovmeogYG8JHKx_B;sK5zUkm}-*iAaFddZkqudu9MBX3SAW&%^&ZwQ=pIX0kKWeq} z`;gbpcTV?C_encbszrGp@@_~vr#;hNY45ZV}vv|HK(S#MBj7tW}a--}xJv@5k* z`A+1u^6k=2;I3&$@?A;o(mm7mX@_(-Qb({O(mjxM0F~~{8MX4eQ`;@wg<7qATk=}@ zW@+1qJCV0YcT9HzcS@V3JEU!>wIsDjTgOssWILuc`9!V!_MA~O--;tG)8^^+l(!?V znXi*>2NtAF$qPtz(ne|Hv`JbYNdee|ydknCpwhaWQ8V9wTK%*hwVL_bbVHQjxTDS|%-k^eRMjblGitC9aJd5wH^@*4S1lfNd_^Iw3U zCSN4qlYf(Zn|zmiN%;%#JMyoQeFrN2jPt7JzoPbK@;SBY`A^8J=QkyvfbS$9lfOgS zlzfnUn0%DHOZpi680q`SJ_41##TnJ}?@@aC9fxMBrlWR1m8sZDzY~~r7vUrOD&q^5oIvv1B>vaq#hE zX|g(b1X)#%SIe)Uv^-gb>{0O1WJR)!GpgoSQd^NcOs#7EA@ZvEyOW2&`@p-C`;sN( zi;~63gUS7r?*ktsUx@5MQ0YCKS2h0twfmEMsa4J2MP4;OKe-FMIk}VkX43rR_GCeF zM{*14PVi2ox5fHx9JwR8ku$31Z$)-XQYC*Q<(rUI$={IN1YVxp0L}w1Pv#}plV6iu zn_QP%NqHW49r@MBt^<``!Fg5kS5dn%nMT>OlmWdi>Ot}SI%D)@qFsjlk<}E!Sj>K`O_&+PtH!xNzP5q zAe{%Emz8YGiIe#X#Gm_J&RnAW%ube+RIVG8v98Id6KbG>*$%)BH$;rua zq*K6Cl4Fw-kev)F{R?MQ&L2F!D78xYiR6{?Ba?~Xm}CO^7}Ch(faJjBpkyp* z0yqKbcw`5GN=I=JrY8@%J zPj=_Liun%I+9wtAyHnl+S%v(r$sSthknfP}lC(_PChd})lQxuh0Cy(e3E9q| z(pH>NA-^NFHc4x074j{}E9C1ZEh082ZHpoU+>q+U{xR3Tv>M7c^*JE@b@O=^(pf%TH=NiAe`L8VnWqhhWm zwHiq^YOEfSSIm`2DuboL5=rT#Vp0jLM6G;Mfm#_->7-mNl|xoBDam;ib7hg0NlH<} zK7`!aS8?!{P&}!S%O%B<;z^G5OUNfhlA=i<6$6VQO_MyeG)jLBzXYQEQVYp%;aAE( zhu^?2!_VM1;V1HMNMEu)?}zYX_?Gk&_!Cn1?EMHT{faXx#GQNJvK#L!%3qLIVBgyp z;0NHl;e+5VJa^fB#?HCVseef6^Wa{)&p@T_wfiuX=X1_1-{Vv7vxBZYd*|Kkp zuYoVKhUgx;jbT%Gi?zkKslQI?ZPp$)lD`?HuW(-ZxE}dB>x{2Z-auZSwYv@Av*23R z>|9xNZ`+IPS9^*2I!Z6Gr|o(2^-=1&UwPK<)^p6&Ke>x%BCesng1u_xa_kr*Uk$DR z-LvNYv?p1Ge3H8R)1CyayH-{%?oxAK?Mlka$;+|6=PtARN#$6_dzg|t%9gQy=Z>?* zBzKHGM9tl0i&^`-pEKQE<{sDwDBnk3j@7MuSv$Oir^LD|T4h+9I)!7d zXq90l>Z90h>ASFjisQ)8w9|zpx5(4E3p$jtTBu`U|Mk^_T#+JpC{wqKOGUQvpbhy6I_dPOPLH1-DDv!)^HC$JOP zKDaYyFV<6fP}j!22dgLD$h$_VY<;O*7iygYycMi{Nm%<*@cJDowSm_!$r^&YY}%6c z1ovbG!re8yhjyg4tRPr&kInAvk7>jC?y+eXcA`c+3-XdM^gDpqfstbe7Ub>S9iu0N z)}Y=G^jOdgY(d_HGfKk!H%HQx8vG-W2oQ4wBknK`b|* z=FXNnaP>7fUv|F^yH#pZu1;P8rd*#D><%H%{94GzSA}D*M!f>1YVh#d;#G>$vT*8n zo2OO*?j0{1@ayHk0KYEEv*$tmeaNjBq3pg8_n643mjsm-=Uf;}&x2FfTSy95?vCyh z{Fb~p?6tc>^i}e0WWj%h+m#P~* zBX<+!ji4T6Tt|2hRO(*lVyrj3P1!xp#aPLB6I@4Lj1?4DHl8P~V@1T(j~7Ur_9eZ{9gnEMXID2@O^ec=74EYma&5!U@6+46O2tG>b zVe%?=E+2;KBTG+N?j`C8Sbtgi$L7 zRqVE+aSOej{1$dmZ)4B(HjeZjrpGXkZ|2Hv?9}3UmtEMKIdcO?BIDOmYDKDIcllaM zm$B!2EflR;G-Iz~H~4bWHBkMeUCz0y*+0IL(k0x{ihX5cyI#ssEB2}{g`Pn!y^#ED zsGj52WEW)TP(B;#UiUeq3)vSxpOV_Ct=KO=kMda@wPN4>ENCTpD>ML3r=-6-tlUWY z$aBa3B+_Y6z1_L9ub({6s#{u_x$m#Py^m7Xb6zDn4aZVClvIiCf{{M;R(lM(3)*oX zK{_1W1+@~6N@vvxt;~+(=m_*4R#09}UWtCja_D~0eW2=1EJL&6V6-s~;dp;ahoFJ6 zjQqfKR$b0Y^fUCGSb;`IC7K)`p|m%71$vcxLzhB#gz9fmjgdXkGTDpcT{yC=pTylL z8=rMY?pNDH&-*)3UP4~MPQ?=FTJD zS+So~Pq|;(wHnF}#4vUu^g%I<-3EPMy7$nKb}};dA_h@*C&TC<1E6)}(mv!}p>^z( z^kQ$M8%gh|>Xe1I)E<=8NHbzceZ81RmWg&`+2}61nJbMWwBhOw0)yT7T;2e1-Vv%Q}6nXYk#naFVa_QsX7Ge|?nYctnCPq<_ ziLZPfgyIp(Vli)n$b6Puq~>i9iTgQ!FL_0_7L=kQd%fZ{-hT%eMnxv>@(M`H>*TMJ zzfw_|i9}RpA{3R`9o%zk#chnMK`l;x>}$UL5qn#aK-uH^j3$SbplDjwvwGha|{m0b>UaS=#HtL$O$l}8d1 zb3ZuC!~75NiB_4IM5}B~#Rbs2K~UC$MXaHG54g%&(3Z9Q@;ejiB2v*R6PIAt0gY&t ziLcz6P?#H`H&Yg)xv`=uTLo@W#a&uNtp?FJ8I+O138C97W%$1-n z*N|UDer3WZsxmQ&s%&M&G0;mvP%a0BSV{RZkd@0pT`uRhUrc^c!YI_t6q%^b4&xq? zit0?1WlhC0aEt2fe6W@^ATn$C2j`HV4LY%m^9PVuXZwR#RA;AEoXYRq8ziGTI~{!G zjD*Cj24^{){~|I`ory_QXD5K2oCK0`693^u^5ZIMxS~erQV@%pY>$dPL0wMdyck7I zCOT1*iB!~NqAV-HDR!hRB6B#n%u(b=kRJ{@v5@og$!oHCAQm;*Ar%Mn4@6&r8B-HFv3fIt!#je4=$WoxF9nFKEjC;1Sa)??-8Gke7YQ_elthNClpNz$Nev z1SZis6J^;0v|=LV-N9P+NVv?>gxV|xofyk`d-3F42ke;uCGN_7xqVTY;vG28(Da zacN)i6EKW+U^eaf&Fw&6+9&L$b;XatG}S|RU%Gwv7ciB-g0cLSU;Q<3jrO22f1&(mkeELuyrO;5fo`9PTC~qZ zTz(I7@h)YpB!3M$^E>k2kpCLV`HP(Iki7#|(E;4zi=Y|rQ2IIl;wRuOKO=vea~-gJ z{CPrUegPG+=#Wr~4ro-XKm7wRl^=mlyh-_oAT2-2wP^e<2+R+mViz62MMNw*qB;CB z^kvS7yNJGgn}4znJfkD{%{M8F;Cv0dVjX9+coY8+!}v1);)@_H|3dzFLO8Up6_xo4 zRK%iVLMb|;kNYU)&w{CFANzTJuNvE*2X*-zBx=zqdmY?G z^yN){^&KD?ow7GLdL>~uuYgzF!5Qt$I)QxL232$VMbL>`DXTfHuJnuR@tAdBRpJz# zGx3Yg*^S(z-B{zs*QbVmR9L4NZ^AQ_#( zY#!m4tBd>y$jrl(wejklY2DQsP3XJ$)m=DJJ6$WUvq3nzWcPr(s2{zSe{d)H9SObY zl8IP!LBIA)sCvD(f=!%3S(~{V!DMbGzlr?Dgj#e#?{gJb#V)!e+(pge>-ZE zfSw1wvIYcZ4gX{rI7S@^&3OrjIUg#Hp-(e0jIP;%ltnPQW~cElL|{%O-y2k;D_G8H zoH+&DW;LkA-kjN!yenA8o>2WroCHR(2W7FD<3M9hAU~e`xP)GGO^5}ax4~G{z+K6I zP%C#O2#h#Pw`@nWD7%4W>qDR6l@V<{eVvnSSIUTg3A7w3~ zrhvvwBiEzil!Rm8qlmmmCi*fFbY^^_6ZsF@a5Oe2wjEb{W}QGf;99{oI)ZhC{~~=E zX*Z*`{{~!a$=m|bEi1J`kecnKh zC(eXq^vW`>ieU6gdVW}8fW-6z;rJ_OL~ZoesgI&w|Xbt|NN7J8hwKtfJK33a+)wD*3 z@h6-SyXc+JjNX|@Och#_KjKU)@R+KE-~iZ=XZd%)I(maFa7I! zZ01i$2;b&vACQc1Cp@E1!Z7-PVtkdedKdUTsKvXK^)8@Sf!`;5=0Blg8hsLi(I=r9 zeL!G-nQ)k&k?Uo-57^DmIrCHUpCF&S&6&R78E-+~;z(WEzF;rk=YPDyQQw5td>5+k z-|vxsHz65)6Nb?j6yqiC`6h_Vw?Qjjq^!-kHt63@_{_JU;uu)VkoQeU%)3ZdPgCxf zu#Lx|{lISC<+tmX;$3i?uTWN_xgVIuW6(#)`+>cDhJSEBNBux%K1*55=4}ueBT$KF z^vlFB`hjBH3w<5DMQiWZ6MZvbGH*cpb6wrRJIMPdR6{hQe?m6;CsgJ|aE)6zqy4t_ z+%NJE#CO(#W8BDj;}7)*>$o1O-St!871vSL9$WkDr}*tpkUyS~40RSoF$R$OgJpb- zlGfCZfL~lr`C&@;L-jrWK*DN7HU=aFV?aVS24r`G%B%(5Si|{yIMRxGE&o7#=MK<} zvpIhz`2esNy|3$6MtUp1w;ufCOz4?htp~|C19avV&Wmc)CnTdDEaPO#dcL_1dL94g zIL_6B(p*DX&+=C$e4{?08TAR-s86Vj{&w)bldv1(9bLw6Zve?S9J-Pk8Ymh4;4n&B zdo+NVoX^qOpfl$~#Worep3wlJaRBAhz+KJ&x!9lb>6BJOjTdkV z`RaseG$4iV#npic$q?Tdn6R0Xz&Q4xd?H8sN;-*ubv*fTU>Zv~zZ3aD5RaXpM}ftx z%ocJq5R^uH67d^tPmYF)Z4AuBGX{dc80%pdvogFtC^ zTaVl<1&a{Z7)%HNB>98JlzHPsGPTQ4<}MO`L9#Z=Vv9L>A+^fns2 zWfbKizKhzMS;AU273HOhnv6v~5;?k>-00L>QL=WaQl~!Sq)LM7offfP+H%x}U$Zr` zQhAh@b{rWkdmAK<&582TiGOAs?uqPqmPdI}i?-0J{b!8wGLT+ulo$K58tp}tmmwT! zcPPeXPh7-*_qzRY5nsV4?3MVLqlEW4j_^B2X&!U}`MA`7#NOudmF-WWadT7um;<$+ z*<+>K)5q+y(%JMid#+S%XnT-UZD_U8rTW$zNj{xEH8N3qrh4d7d+PAiQ-_gnOFtWy zs5;R@k`}Z*-LfrazwgZdbjR5EMn$wEM{h^Ijat?XlsZ5Mk~@pFXZBQAd;q0(X(nyY zY(9W9{YXYS?oZyAk{(Bmfvg8r{iyaO?@h^A!FnP!YOr1`dz0(QvI?r_O1Y~lsHk~& zQe{F0TY(K$g4&4_R>EtGr0V&%0vT#+l)K zjcwCcuzih?Ynq|~Re1-Bz8Q z{=NUCFa2O5=O>Vi0Per{pUkHBICdQMozg$)5A_?^&+LcxuDR*otIs7_rG{iITxW|)(r~CTnO$)lqs}*uLwn~)jvbknopq|x zJj9MH@3HP2>eKA!QfJ%roE9c}w)HtJOo*wFYSGRFY>jfetiHZ+9r3g^=?~YZ{RMiT z_GxP}>bYKX{XNEMZkK9m&s)oX%ZF9Z|J(m$A=JIcizgzH$@_8R#`vjl(zxAHx_|bpn|I^%e+rr2D1(aKq zDYwWaTjaUT?Faw(b)l*B^Wn{-jn}z<#Cw$Km0il$)4 z+D{d|{BXzV|Bd&Qu$~W#e{24`{UhG9;l8^6L6ocL3F=&YaNNZiJN8Zj1E{a}Kl+Z) z_4si3-hvnPZAHIUe|0drV2jArz*DEN#|?;=j+j8 zQ*W&wRDCz&L-d8J3%5OaAE=&f)r0E|Ri{pE>0VI1HLLO66RL)u*6lr@>hEdS-W{rT zpH}YOp!(X?V{})j9(dLFtApyBS53bzQ1$fG?(3X%`P4e@g2tU%eCi~3M$1l}J++jL zv97jW2a=K3CnSA4HT2pgeLQuZjfbuVo?6iD(4bPg4o@qbQ&U>4Ds`sSmQ$Nr?Ob)L z+knrhLsy-2>D0bf!%97Dwc^yxR+p|7Ws!6BwkwlvTm{tjR$ER>dwYPIc6rjY%P3pQ zX}e*hq3iD$p3cUTBhu4RdGdf`ShQ3u!mVKfu} zpZ~Z``nRDSu8#oqdi^SD%BtO~cDON3)L5KAQqNtzM!&8xP1Jq#s~giq%}86r$R_Gg z>V0|g`j(rzzAbG-+jZ*tmR7IRwztjg2kO_`Gp3V>CZ2lCjMQtQC(TT~DSDXtn)W&S znwpySMYTA$U*AXja;z?!gKeYMP1XT-Colv#;L%Uf$=g@f`N2vp?W!sIXq=s_` z+9vdz)oND9RSjpg`qg1plQ}e&^^sjiJK1*n%C@zPAEY*NHX=_WWDXbQ`?WW$a+U4rd zhi0%^!UJd-^@T%+IJAjF&p5RC)kO}Ses%b5y+!FCsmDJ#&4d1LHTss+Ywpx;}Ke&<2kV|(ZrsO{r?I2vlZIUhO?+MY9^TS0AS=R@Z~ zd%<+5^Ps(BJE-%Zy=EG87}VYr{yw%%y=*E}-F^F=^Wxyta)T)kN$qLh?8I5M^*ce; z=(qjt%N?Ngsb|zvcFwoQsK@VYZ%^t^a?V%JRBitLsoy#0x8Ycw{Wehb`qkNQ4OOpS zo&6f9di`qdS3}k7SA*X)OE^nUjbETzXGaWe_a|;YV&vHSC_9}jaM$m zr|oNdHSpWjC2zWNInEvBYVG$>-bfh+*#St?ds)htqo7pmCO0v`N4I|S>M^iHNcg? zH9<{qR|#jEV*M&sE>{%SmQAf+>WI5ukqcDrO7}S1x<%98#=Y_G4GFSh->qbKP>Da$bya;CPtN*pR>5`1<9%=z6BDQ(^t& zEE)DtT4*e!UM)AAWf$-!t(¥4dHZKb?^$VKCVkrS0z`eus?IvvZZ1*lOK^sakPc~ znseeLMv^nWv*N@wvg{>}Hu)XB0)n(NqA8RPw~Jo1Mn zyFodP_}zuYU|0`2fB63#ZSU1?FgOjruitvpc7t*nu4A@g(W>$rMQb~YM*GWW1iukI z!@d%|#@V>&O^&&um&r30y-%L8=#`E+`HjY$hCSFd!=CNzZM-j1qxTg0?hT^U2d|8KyK5QiZJ*HaJ@7gq@D_ zxAVHxS>1Nh(#PKDd|22Exjtwy6m~}TAt@zcBZ)dKmG?!IF<%san z1a+n}&W-bgGhjr%Y0Gb)&6zp0S1ojV@^<94{Q5bRv;}Jqol8ESQU~Zf@{Z&k`1SKC zbt3P`uU|lE5venDA$b?_&deT*DAkd7NpndZz06tDnMHnnIAv#?ZuBjhA%=RU2=rF!(!x?HN)KO;j+wU0MqwA68QK(d-Y01NujSl>Hd4o$)kW&FOMgaj)k5?zKYUu(38nmQ_`d4D)Lh(eH6Ny{8aLfLgi;qrE~)H z1ddKi^WSOIuP;h{PwJKOB)lEyq2UbDD(LAP>D6)-9v}4LpjXRP+1Zp%fu2Qv4)u z=f{%Yi;r=10sb=dgmDFF0#y0niZnA{!Ce>Pk)jQ?UPZbDdL{YQlrDu{MScw>eT`mC zuD{XClP`CCC25P<%4;eQks{f0dNLNGkRC*Iv zuENX4O_XmYU7LJvT!T*y<5uc<<68V~DCOLm){9%IdlF^+h3J#xIy|MiUfo8z0na11 zC8}qUJCaA$J1E_RXOBA)y@@y7m3*q+Ma{QRzLO*Uf!u=ck6W3!@1b-n^ltLC%$v2) zT57$QT&j1I`^csGaJ`>gs`row$fb8u--G1RyQt|QlAdE9Ol8+RJ;zSLJBbp;!=$x% zD|t9ky{$Y-x)1sY`D2vshdxUFICVYEYyAlW%L&F3`dXQqeb5<>o|HGpDj;N zO#UkC5MJj=&*6RM)kL48c74%EpXVKKB#$!srFj9*Gmtx4eqq8+{Canscw>8RyfKKSO#w`N@&$hxoH3 zeH(uks=pkmK7QVzzUk1#+R~w zkoB+p8T|F=C0YN!5`WpF{@a_C1YW+It%h0cJ^bPVa<6Y>>)UC&%FDFmX??T_De*F&V7h2@$ z+tmM6ye#PtT7S}(^#uJLj=!F~N`Ec;F8SB-XrvG6?{V~Xd>-jZ`uiMx18+z2U_apa zThMQDq)()8;{Qlq?}u;+-Jo5m`$wdIgZ_~G-zj|u`XllmQ_|n{zmx0v`g_nHlmC>` z_n|)_{~7PtKKal7KJ*71{fuirz(Z4a>eEw`RDapOB$w(r`H|_Nq&4PvpOW{)YPhM4F2y@gCIv=fv&)7p33fjynX4%OONGqp?~A(e<;m^S(SIzBiNs_ z9KTvpBY9TfXG^L#^NL*m=KACMZ#;47TdNiRxc)n<%Ku7DRk^;z^v?BHe38i~SLgpj z&DD79`k$;Ommja;E%;K$Q<;=k;Poq~zBU}?cm%7UzP21y;1R5nnrb-W+wopIRMt^&u@x{?_U!D=+k=W@^txY5G!gcl@sP zh4v@)(9;|>_2*o7e9-l$Jbd`Lc+d??5D&>`f*$m{ViS5HmDIjYCwTmvIGEm6=BJmO-2uM15P455`N~VCoyi(O~@64WZW291Y3GkPn3prS7fCrNgLiEV*<< zzBn68S^^!;(KggS5;~Ha#*uG@H@#8RF`m*W=s5BT9FKvHC!a_@2JeAmsBaQSWAG=q zHT6y=Ey*TxZfnZ=aGH`gATLaz{%!Exw+%H-#ed&6L{OMY**FU0q2sA<8fhYQTk`G5 zC*tjIyF@2a-wckVdM=zn+A*6!+9{ivD=*IEEmQJY)I1eBlYBO%ZK1Qsx2H4>I-7hB zrR|{Glh37O)QCCc^C-=L&d7Jd`{G=V=26-ie~ihGN3IMyKNstspNr|w=e;xW(x?~4 z1)R}u<9x~sbFrU=xzd}_xIHtAH!tL#1^7r*k~13jY|69w6^lr7pu@R)2d*xHF5=AM zTsdzsrMZ+x5U*Rmi*xX?sLZz{SK3>`J&Tj~#ko+uDlQ@I%z3?qEy$-No9 zbx1-Yb4p=dk%W{bmBR2FN!}f*M7bZSCv;!({VDZ=?nizA5?l^dqC9|(yIs8zpio0h_qzd{ykEQOsworV0RM0Of=8VkVrAtbMm!b0W> zDeTN7g(-iXj675>e<^t>U!4k77CVR9tD&coD|wxYEL2bJ=Q76Xk%i8sym84(nd?j> zA>}V+E~)a@MbujZy)c!};i!JCS(3u^-FH5ckdl`^ z{MH}?DS3qyb_MTfjdUc2qZC#H4T&t|uR+vZ$X`lcg%oxb<;|17l(|Y$SQ{jvLC9P; zFfR;hR{jdfODRnG>*~MDUrJtjK2!?3newgt;=V@dFcMM7U(UMvv}`JQDRU`n z8L31mOv%gGCFPQr*qxGBduT{uA%8hzKSydTd4(*dzfI+@7ZOzpdx`W6RB0?EuR;n7 znakY_B`@W#XL;kR3D0{qA$hMd<3Gn4<*(Pso0r0rzY1CG4ay;Z8SmvKj96y}bQQdno`SIEDbu*|RWmO|PJ$?I!L3RCj>B9hSNNM7$! zvypg|ze4ir0+;)3kiOB-(SMh@3i(S}%y>RhrLdOeFJ-Pm3i}py{(!U)`hCv-Fk!Ag z1ps`OBC^%3SiaN?r@0A$hs~^K+26vCysmE`NnAws}&R@>j@Wh5Qw=*w1*^ zZ%8{J4{ej=FC{OdDH&7gx172&q8){PG`W;m4 zS^4XC&B|XPc`1eIf%x|=$X|>9E`Q12X1N%4mXD*>ki7CFg%y&QQds5R<*&bF&B3vWnB}0+l`t#AQy?{D|dzb z)e*Ud~wDSs)8H79=!%y&WZ za)+XjzwmI2T;z^Z%aWIJR#W+_dCAND4&|?1|1Nn=O_GTrPhhS%Ed}z?~)e z%l*AV{+d%Jf4SGU1Y~3$bTLv_N%Gp0Ge)LblJ5md!+D<9%cWA6dTrg)?A@KR`{S+= zJxJ=~iMRA5xqm0Z(~D%(rFoQkC!DHxLX-MXRv%Bj-q7!j{qd5YOLy>Q@qY(E-N6%G ztcSXHC#u;1t%r)B4uraQCuTbc>Mour@nEQXu2-0vk8@Zj4q!I83@>g4t)Pt2j97WROvK-@Rl6pjPzxs6zJy>_h)s7mQ z_<6M*wq|{h!{3Ia9+5J|IFfp>N-pC`>Jcea)&DDMK*fm$fMKn*{NqRkJ^%Cozx}I9yDc6r{_%PLjY#rZN53cU4 z6h2JLeVdm1Fb%J!YFYN-+l3EPH9yOJo5rrcJ7gW{two#n9(P0_(4q3(^n(KolOj~#mD?hl40wz|A(-9&F}s?Vm*#{1F74qd}SE4!qR zy}9~q??oRwG_l2X)wdCgse=;prlV{sW5|&g zUYWydvnzpmD9(?LvObJ5XQc4*?3kX+Y&V1Rj-^TbOJ_`12*+39F?u3jz%l12Q|H0C zOHaWQ()bD=$&N4eZuAE{p7G_Z>T1zH&1mX)%C#2$kzFwat%R{7NG-E(~z)_}e633rf z?%_*Xk9?uME~02(SD#Hict_Mws8X}Dr#epRz&m?dR`MmjIN!2!n(I1K)|$iluoFpb zSZB+QB&|8r80tV$8 z4y|*!i9*XR)-`*^2ldBYTC+mWFMM;CYYY}^nfigQTrK1%Q$%Jw`2dXHVsW)c_DRq z)f6qw!(A!cTP8Albc0SJpFpWQ6q%ELJ%RE#QV*!>f}BiuT6Y}fv7}zmZOFH#)EgR_ zY-2gHb^9>VoZCl}`a#EVBDSu?pqpPa)X7=t-NBv2RicP3QMER z_6$wkeEm$XPNMw2GJt%(a)7dd{J-*nGJ|q~a)Yvj@`5~~5`}BO>yOm=*>y?k>>Yez z5xqs8FxGB)ME|{Ofh%4}I9pM6rEpbL7E%IIDpE#LGE!Pnc2Z(eic+R>RkC$mi(Rkf z6x9q>@=|Mb5q+vIQMF3#g;KRmT?3@@7p@9Yd61r@xvB3eU&^uAQ|HnjRMv}Z#e`b#v(0=3tC{2g3b+V*PiPDtH7rh3I9$P1pxxK6L$Z<_u26o*Of& zD_6+o&dJWZq0wISD0@yhU*!4~QC{SKoSDnH9oH}AhFG~m%U%g1^zL1`oLwEk&ZJ5P zO6AV0wy`5#?nLR@S=IH+xzbs|`O|qpuGcx!h&9e4&X`7}adrvGIpkqiE~C#l8@YbT zr#nA|9fESO{Du6w_N>m4^6>KaVZE%Rou^q)I~CV0Q4QB$zeao`znkAlEW-#|uDOn0 zr7(5T%Vn`b=5l@W>nLgY1#ORrPGi&-tq(%la+LMudnui{icLy0OCfWGg{xn+Gi`61 zi`Mn$J1T{RL>AF#oSO!u5#@JQB6H?)4HxH-Qz>LIXSaI3vMnJ;SWi3H2GJ8;tK<@$ z6>Sq|>5@biQdrnSOOoaI_oK^uld z=FDH%9fzH_8gCPLDI-Vv^C^lyaAFWl)OrHkf^s#hl-Xv;#Uf zIlpCRTCN_Nk?%}tF*^!7adjza3An$Q1M+fl4aHwPWK=Kjj z(d@&yWjwbJdM*3&^g(IFA4CoNQ~n574(7Tx4g2!MAv`w%>Wr|Q;{%}wlOIYe5oMjb zjaqmR`Jt4I1z5$=3i5-Y)#QiqMCjKXf{x1})N^>6YmT6wRHIo#)OP5>+;s#c?HiW! z%#mEx0^tabj^c@}pw3oDb4`l}>srb2Xy{So$8b((7zag0uF8CF7%AwMC_lxou)L%B82oIujPVI}vT$X#mIIIEt-(__$g(VF38 zu4v!jjJt|-0`wT}T}9~_^j_LhTFvo^&=a{^>j&)~j;EGWIM({XS^HFuw?+fTS^PB8 zYUpaNpH4EiV=c#O-)Q%63iqmgb1IrJ&i-do8VfyxTeqaXD;J_`<4Sl1PhJe|z>`;yE=ZORmq9ynd?o2(=w&=}73m_VQAM?ZkX}xm zSCb~886zKj4e3hgmE3!6T92>g`XqE?I&oHQoU5SMkY7*fYII|irf%Tg$!N)3O@1R+ zw1jXCzlpN83Pje1Ud7Q(l(dbI1Nb=4O-WigQ_+yQmLsE%Y8xRha4YF1sMZu(Kztnf zaqhm2yVS~&pSYdlsn{vpMt&!Aa~EhAp1G4}Zh;!z^iE2*p*eGBqIKkV^F(Oq+>W-4 zGWI>xv@Ng3!Dy`TIcR+X;MuH5?&XS8I{65?U*oeq_w(q>`?Iy3ij?osa0T0-9Z zG15a&wR|2UJ&G=kIyjG0dH`x%*e5ui0hL#Kl5<)}D2IH4^cYl&i%+H})!DJ!gZwG( z4gH-b(4l#PXP+j`f{JBmKk)<_HcH-FOgstg!IRIB)aWs`?K-Y%`S1)!&+^1qg>(rxO&+E`P$lv040aUc;ZSHyl+K2pY*5W=%-{%eJ8{F|} z(n9D$u6&yGHtV*#CR#2JB`++R-A^ejon8CoL@HPd`7Tui)Fdra$DuXl3mX>AH-I`AXEVM`f&meR6(mMFGfZqN-Tm%9EhPVKpvtMXYp zaAwD}k{eNXB>ayYR&ZMdpC!H^pEVphYy&=PM_N62tKhR*=CG7K$~mmyxtj7>Tfqs* zBQ)l)Dien#e^l^Ua#+D_?Ze%p;e_@iZ_H;YG0A6*hO?2w3T|uv#49!Cvs$g^v&O*X z$Q{UMjakoO1-Di3S#nHrTP^WfTf^(fTLqtWXyT6w4y&3c4_(h;$!)DjJWj!9)ilFr zZ4ECZXK@5~Hs!EdC*DfQu;8`|K5HzTkUT{>pCxA{pL7)GS0>IvZc9EZcq@6Ig4=47 z_^g$TGdV1&{6#sRB_DMh+)?mZ@;kw2oj~c>#Ag|8`*@xz=dk3IPJ(xmqY2)s;InFZ zel;Vx9kg8;w-tPrR;cn;f@d#OD_`3o7TZ zv^edS_$)alHKCj5wr*wyFZe8ZiaSa2S=y`0TS?^+?jmU`D$k`3^zBf&t$PwTB%ie% zJX7#lJ-IKqt$P#iBcC-Lj%aP-t%A>zQ@D>LpCxY<+?E{H40s+no#3s4&(bRO{=`+O z8{I4MS#k}*ZOLcNgx7gEQF)xke3l%+W2A!53a+Z0&yvHM1(y@Nm23VdNb**4WO7&! z!WSu-f0Cr#sC=57(vwhmE-h4_fXZ{pZOLcJVFkDK49^B{^&}jT*xWjjyjAd7!C}c& zHRiMAo8+^$ho33uvqbt{WW5`(p2I4*t^U*~pEW0OM{}VYa$EHq;j;=3>t$A2c`G%f z<-CHQl6QKIaszLElO(q#=k+Ph1aBpuC0^MQhb3?I8a&g$#9PUosY@*#NM3MQ;-2zZ z3!viLpH6&PeZ76A2kqz>?VZL}Z~Ayw%J%x+T6K}Itz@2SPq~7;Ra$?HIoq1DD}Y!|Tc|U%tF4iF^(|Fj zZ=CJWN!Xg_-PsT^Yey~eX5yP-*Om^qYN#O@KG0fAtI6y5nKFsI^QQWKSIw#w9#D&eOibViy*s4A*Lv@EUFk7 zqWfVj>1&i@gn?p<2+jv*l0%D_+JSV-eGN{$v%Hv`SfPt#3zamI)QPh_koyrsQDzviE%y^2w5AF$PpI_&6GL&g1mQQsnhv)(C1 zb2G+DM((J}m@hn52Fe&K9(PYQbWg{6>r<1of?1>&RPE6UN`0WtA{A*|R8X2oPim7m zqt=XFWwQySTIfWMCNm$jhPH+Wk{7FGjEehCA=N-@xHgqD`UmwlZ%b0^MBTh;Bz3s- zhqxVMVi;p|D5dF)jiHQHG20oW>5Nnn;F%;n2`Tf;A`OBL;_PhB%;LK^ALS%5>hT=u zZA;Ir$~k$GYVssYtf` z9H?@7C21a1t&2*M8W>91l}YxhOmb8uveaVEEKaqGrw5K6D0>BOaonqYP?6>!XYESv zvdtHel;YI5MODk7s%sJ3_6`k?z$}*>fIw zc4_*GOZk!`*e&pz?Lu;&A?Kc5Y13g)rSV-U?ZQsQQtsR>_4(a7cK>2&+Q0BU?mDR7 zpL4f+8SX#0N4O_3<$+uqo#bsjC}~lA zP-=gr?q!sF$OSxzh6rb8j?}ePHBfpf=B}my9 zbN}U(E`}=0Urx!L4d;rFkuHT^%GoP8I~^*bekI2tpI^bw!{r<+pI;8`PJT6a&44Po zUrlLdlF!}8P)fL#bQM&)f^}V+BPe_ zD`mTey8p2~RNLm;)7d-HJbVXF-HJ4=lzs>4c4Tu`TlYfdAbo4q>~4p9BDYhzJI&j7 z^Q_Xh*3S2E_D-m)^F5U2CW+lWjlSG*FIV;M(?bujR;{kNc3k z^)~eYce=BoH2*+a7aru={3OHQ2X);qWOe0uC3g2m`jbDLR**-yYXP#eyn*{8`g@8! zk%yDqK7jikV=Wv2eJDxa`kYc;UkH^0cp{yBl2x-FsoFh}Cn-G!eUxjT;I2hbaobOF z9MZeHBu{Ys6f1KB)D`+EN=oJ0ML(US`=@zs2g-6OPm`8F-79~Zv{TwK(N_8CRMtn; zy2J~tqc-WSq5q2W_# zTRL|+7lby8`aqlGFVh*rk*URk-f-2MQA4Jwzs%5-mKO;rRjnp{tcOOl{Z;wYu_Je) zri;?5+EHq^*xT(xg(j71gCK@cNM(HA(Z7hg5L<Pw!~?S zgJZD&2d8mt;xU5vkke=j_fYU2dV7>dY0P!VZv^jA&TokOs~HhohhwKP@3A4*Aul5D zp?<}Q+`pRR(5zSm#}J%`qqD?s$bp>1eR3U>pmHhl6I0+98gn2UavdA;8y(>l9N%X# z>g7G;I)Vc!=RL&zH{?1>oQ9lx9`HkQ`8gm`NZv^kLA=eT7M!{)Z0tX=%QqFJ4Pt1f@DCaul zPUJVbL4)^@50Uo>e&Y&w1^JJH>u_!>cn`Ub;6OIUd&qAD@9{yo4*3najvL`6K0K~N zexu+$g6ohMY0P!VZv^krl;5}$jzKPD^SBQAjo>{BPNSUnaK10Nj)LD%A4C45;535w za7_pfq%qeazY)C0V_bK)U_-8>oZpcDkn4D4J&#fF9>I0UfqWuy8clf*xsKpBN}NXU zAuVwl&rp**hI)S4CXQkdRNh5SLk`5rgATC*v@*R>MoRYpv_E zmVu(iVLMo8t*Q%I=&ov!AyV8st?Fv{ia?8WxDJQap!%y}tY=adny#j*2#uK6HhdS?`_NY{*HIOZ z9teM=_G-DlYDAz3P1Vp^72OLP+@_X-@&jQnsMc!E$|i0U`l=gR2ez!QTGCXl0<#e7 z$w4nl=(m`iXn28v>os5WTjWaquw@K9qBptzmdBR}-Y~2p3wzwc5?BBKu5s#@XdNzZ zs4j`t;lUMZ-=hA=`;U)QZjUQ2q<%?6nTW_pp;_|Y;v=$5+#lRp^7aWRI)uQe&-f5$CPpqa9zx$SPUl#=cKU zD|~bH!5wKzIwPBmGSR;nYmP5Rg&O?ogKN(en&6=oUK(ZZWqc`hl}1_9_+!nFFGrS9 zCX~I5nW6UuWiR!!nvSm+S&lMM*!Lg5MGi{+Eq4~w-qJ23G`C`88E?*!77^&w+-iP& zDRrs8<^F;_QaceNm?(7_YvTRJA9G$-XG?n>wY6NO8_3nxQto$6R9j1F-ceRQzQWFD zPO3p!&N{r`nO$39*L0;m>vz6)6)CJ_!>%r@YLpb+-E>5V_4I`*K`P(5FPV|&Q1N>$ zb+vr&y?%~YB6UslYZP`NS}!Q0YHjbzS=f%a8fZULSkKrC-8Io}!5z%uN!C^3l{XH# z-gp?sBnayoIp>h{wN)9JR$NzW*Xoe^U2&DQ-33;r(w1EuAY^Z?M4T^_0zGmW z59bWmvp@z$r}>~zydXTl>j zV>O4W8&k4miald3ncTT+P01DnY3gIZQGXYnY2z?30CGzAC^po=B*Y^ z%~>_+VfY_!&$Ky~OrdRC*fSZyB`ldj=eDUmlb(f7VK>gzDy*8qk}0g38rw4&ou#Rs zZBu(DcLqb-b`1zyQ+p=&^a`t{uxHY?DJ+@7s;RJND%Z0WZ!4^t!k$SRrox^n^lY1I z*tTTVq>Yk@ntZ|)q_AqzhAHfsLfclWrohsgvte>i@EYz9ZQIL0#^i1`X313O*}9u2 zmL|s}qNY{T_2h*;(+9C+ayKw^ZVP*+4K10pa8l1!&%*NQ8`?9uUw22^l~d)tW&sMoSteQ5@l1a-acjt@&qg7MOHcVPL zscri(RK3~8_DtnEx1nd-*s7_qJ=1%!VUjyh!*&+-Mb@G{(-Y{+x;IkC0*P?&o*qB!k$T~s?f7lvUwYg+rply(69}i+pu8@JzFiA3O(CR*)xSD zlM=S}OqK9RYOsY3w&+)3&!jbzF(Kun3QH!r2jyX%F`9qFfdAYD>5X)*r)PfMo8HcawX?uo8o zRBUK5zA;Ot*wGA&@vv&z(2}XdVW~}Z7`#!rC6l|JVLg5NplQv9Y&m_NeF5FK!pH*(p)Yy{g+{9aLjtx^MIIK?aW`!kF*e$syT3C-aXEz?! zOBccqh241YR@yKXcH?0&F0awpo~bd1RkC3U-b#C?!k)>!&1;zk_YEzXn&Y;@lBt}}>cNwRB~w^0mD@9Iz9o}7 zQ_b5mX)!KZx+zO0b)y18hj@(DrKu&8w&H~iQ;D}KY?$N% z$}O4Xrqq8D33W%&vQ|w^EyfF5@xng5uwgRdUf3;(vAWCXzN7X`T7;L|Fd26*_$)ao z?Y~R*OwVy9_^cNbdRy>T+AtM%;~QEs1&5{G)2pnN1E9@YjLTcigTqq4M{Dl|&<(Ac z!fsr&tFeWXwoTfK7xqkH;Z#_RzfNsoH(u~r<@QV)S~7{31#eYYHOYU~*Natkr~io3 z_e$fVSL*flC@q;ByJF3Cw4d{VJ){dQr5;vc;nauo+AfLUi0O!}sYfk(r0tTL)gn7# z+fGm+r^a3n)|{!~?P6GMNUalpr=L?1sCFbVX00{aa*sZAwBo2G)j{Rn zYDwB!wBt&FGyPxnm=n6@E&0s}o$|nzHpgR*x?zPScVJ6mQH52vesjWCPT))}d&~(` zDR8Ee-<$$l3jSx~2vcB7fis2QoDbqLr=0UC$CgTdbDG1JHuRVizH-8z`@MS1312zk zH%E^-ay)8uh2I>tyf)8QPT)-HpBMJrVaYAp)RM=Xma(OBUpZmPEhkg5=WdEKZO8?w z|JBrQPVhhD;ZD@WZw^}u8*XQ)@Rd{WKjAT_gfkV^+wwWh`OOI%?m(3`^q5obD@TN> zsSS7GB`5sm6uxpcjx&{f<%IW~jeE=~_#buY3XeJZ$_c+Y&3ViT{>K@=@Rbt?Q&@7V zXa3%CrgD4kmarwYwwm*s(->#chmIUk^JtU!k#VdV`^r&Qys+dhp-N4;ouK|`|h2ReeB+a-<iJiRgPpHOJ;Wwv*GX?V0oZp;4n>O^A(|8ZBgfnd%VG55q!C@61 zbL6wsV+?Mq*w1U~nXuTyD|yc;cJj)7Lo4(vi7QX{46aj@i~Z zplw2%+EOx>jEGbll6pS!>#a#`5|X3tp@@wLPj{$Dj_8oy7{X#-97+U8^uTe@ivFgq zmi2=?j zZ`M2ys{X(AOWj-ZEmHNL)tyrVI_v}04ArB}tb{yD-MbS{l*(~6kW1b7GuE3P9Q3~L z*Oj_A=)RjYeDCX{LB9`E(N8nZn^E2(vYT-Rj5lBu0^<)DhoFc~V9d87YJoA|if9JL zd>fTo%^lVD>};tU=3Z($_Dx+Q-BDFrEHoh1g-h+|d^qpeNH~o&NpR4zt!qcMK@Wqa$ zTDupI z7JKJv-sv6GUJ$$NdOA`Yz0gT7yqD+`MH>+y=lgQSuiBL_ z63DIX*^bmU%}QGE_+9mg)fuYaoesR;_*d#RcHr1~%-C5UuB}C5-}~hjP5$2IEH3oT z<%|-ZvHH^f{^sUvElR%k->a=fOSVjop9cC%SX`)u8@3kZKDHd25t~U%rjp%7L_ITV zjM}Ses}}LjN>)tv#!>X4uw@Fb`z4Eua*HNgT3ZYISopUMy9;&Lqra%nu7*fXUsBsw z??u+E=YC@AufwieFv z<$B>CmaRo&D~pm|cwuW{D~2w3=!J)sMYMI}xSZ;UmurE$`i@TXL3y8PYH{IgQCL~H zmT#UGxZ2|O*uu&p`t2xI`_XBvR9Zx=u`;9;} ziF`Yrno2u5!%XLyq0oukH=R2sLbv6d(YmHVjlwsR`?sUd=<942{a_GOu4)!{Oo2|} z%53hK3Z2R`+jIX+xCWvoL*>rqP#OfC!MVBIIU72Yd>(ghPk(eYXd|Sa)eP>N&mA+M zb2ztvJLf{TCtsL)<3gUA2Vdh(cd^6h*jmIB_0YLIy@)g)?;zXrjRaaB?dV8&RkmnUBH!{x!1TIi+N%x zX-B9YsCVJno$y&DU%V?%_JrI}MXnl<%6(S@@9vi9RXJznKJb3mGF58ycbUUdSm(u3B4B=-+pF_w|^Z{-L$D2)UW zFJpV`v)%(mN3b!q=MN@{m&r39!rkql2a$`Q?FV&7Q@>V5_>k9KPFe<)2VS1`IG1z0 zKS-LR`B2u%Hc+{4ePijd;t-D1;BseDu6qT~E{Do1xyvb@CQ=t(wCd~KLvO|JcV)~; z)lgSZEgDIac5w3D zgBS+|hte;NBB-JD)S0!Key3Cz z-st5qr|^~JhMk3L=u3swxmIq$*=VC3yjyrt4OvNkrwzR<{Hw~lhu2kQsE9DvmOiCz zY-69Gg%$Z&`d#>J)lZHyud}cmzirb%o7g&y+fJ*+u(55fy@G?>u+>~kqothxoZqxq zY_7fJp`+EBwp7?DHf^sW8dWb^Wn=ACYAJbbCEJa+SJ6_+PPW(7Mr{l42lF5}0LpIb>aZ~!u5vd`hPNO#{nKq5rP_Ew`n$3Q7N0gBoLh{uf zxR8kDOg9y;!8xGVebUQ=QLdH6Ln>DyFOU^`vJo1zCXc8Mjs|C~4!T}$ zhgN!X`siw+D>H;l-&h~r9@QQ`MAInbcN%w2K}gXwK`Q2FS=iSroD%-@}|oXU{I zsSKeH^`b1VGlbvQ2P%g&gnrWx+LOD7(&IZomBohg?K(k~zlL(H3u}m&?g-KlW?^H} zw&zL*=3Qgbwo5BjJI+K@;}NvsFwV*+j-XYCahy>a4jn|^hBFaSbvQj@7{@hGS7osj zIfdbj_F&Cbg<1?zg zvFwd^Z&Z6@*&FZPsP-ay#=CblHlDpP?u~HY3+jsFcQ>lNG49)vLhRK!XQNve*W*wO@6 ze5LPgNfTN7mDY`LKZzAb>3RxD3wB$_ma5}R`pw#;|Jo*fgEr}_wBb9cA?%lHL#l?_ zI&D&mv{~OGY67?6nlUVGAKR`y)V8fn?HqiWJ5Ayp@+7sXKh&n4P@CFaZQkyj@67dD z-qMCSU`s5_#xa`gcbgvzGc3qAZac1>xPBX5y$&KNSr-=MO=DpyOE(u0Q~A5lK~dvZ zX;&%uP^9OuAYVaA|IvDmZaE^RvT~to(tIq;qtdvESeS(c`B99bh=N%}#4NWRk9bX? zebQ1y%&;8~on9sVO=+AsMmH4^Gc-=hV_|M++2r_c90jwf?fB+v_7<@)ogo_Aj)!J% zM8qt`!ZaR}+9Sd<3z4MY{y%Ug&7(r?u~>VZz&e${mC}`y+y&)rm5V@snGA$ zzNx8YQz;gvTE2y5Z^XZhSeV9kDy*D(QVJ`lXVVH@SdgpP`y5xE!m?>|EXYH@cOB2P zY&#y-OiD#XM9heV*;wObV^-tJQbj~ebxlIEHzHpa+PubbDs)Yn+Kv}dFxB@h^m{|^ zMENW^204)!2?)4$DX#jrDssjEE_xV{8tia+I`uo9g!(bA02r<0YNmh=|#oX0QHy z!jAj|c>AWBy&GCkwWQNqiZfnl_J-}0d`b}ub3+R%{b5He%!rG*VMNT9^?OfAcI4rs zM`^0%h?sikiMW`Bj~+R!k_D9(#0>8|5f`)Ef?T;$Pd!uqZZ#ej zM0KK6*+P>yrj*m1$m+6Tdvs~5itup^72@iq0?K6h}oQGZ%a`yL#H>ms*(ly=0(9Q*^U>U zddl^CwIDBS$2UitS54rEIW9N#5*$`bcI2;=dFR=U^Zuh_|prOGlhTkf2^R3cIQfs$6XXH>DYx9QQZynF6@!JDlaNktx zzSO)sIKjS&8f8nALAnPz07k5m8ehw3(y`;eH|yPjXbLPNxxcSP@z; z;gk-78UxJLbQvq8-{VNqA<)Y8t7Zl3nwZE@oI3;`D$A+Q$W+T&HIJselC%PJ!l+rI z3@fmHIgA>QCG7$=0-5ot4#RJXU;KFJamnwBHd! zDV?3HjHTKmUqm_=EaD=laiyeM%ji>ON9cKJjl3kCS%MbLrJP-YeX!is<yc4w4PV4q@)MCE69x{rSCdpUTIA%y@YzNCM{-lbaY+|HR{7Pl&>Rw z4BCd{>qxD^89qi$*ORV#520EszJJL*K~rw{h+UR<4_<&3Fzsu`bHD-AOL3 zCBKW3KI&>Yc3o`Cie!vw<3!!Us&zNzdq`RetG&OLx)wrjCwE13UA%|<-ZXpNM_$Xy z*N*&ts4*Vyx`J)_b<)R(SV@?G!N9kS@~J$I_Nseu4dAX zBkavW3B7c>V z-sxT;f0Z+?T>7|sjicwW>~%j_tKm6NZIWLn&4s?k(Hm*qc$2&nctU4#@q|v$&g5@V zdKLO9^0zqise}c*3VoHQMGRhN^?Eze*Llll()#mR=x4Iek~(Lfqx@OuXDNT4^5>wR zOXbeg_zvl9=;z75Kuz02-{H&`KwV}*-PQgA$Dhu=nAWr}k$1`dCHoTe%bfXQ_7zH> zhyDxsyPW%C_EnDGfxg3&U**c@vw!96m!R*Ge~r?=K>wBe>sFdz1bI-Rp_f@DGJKu&^t%KI_&VM79ewjCXhxD(|eA3}dZ{xj~F0sSdwe#X5sp+6-5d0Op%&M*01_6v@r-{U>M zB$xhx_xy@n`Xg%n5AOeY_G{|=DfCyI`8DY$*>5=e3+R84|CVz<&3?zxFQC8R>Hp+y zGoU{u|4**}H2XbQehK|0b^L)``YWFMBk8x$Kal^4duKp@Oa3R${T8Zi&Y$@W{{fZP z|1V0vf&Q8NFO+@<{V($Wru2L0U&#N;oqx{$#_=DZ|4sfkN`K7$hqM0${VREv|BW+w z{$D(i=YQd@JpUiAR^)%=trhv7cy9$tdwEycJJZk+Qrx*AAsR zuOP4H{tC`ik=NvMQZ;#Z-qxBU>0fzw8{U%VZSvOSZK=63Z_81h*HUT)ZA;#cXKV8I zr7rKsaSv!8^8TEwgVyoZ{-kNy0Iv1S2XMVdUQekPv=?{P zbFOFJK;AbWNa_#m&;0{Q+d>;SHz-#pb`bCFoe!q|e$d|JgSpZ>A41+QA4(bk9YQ{g zQa!Yur-yNFKt7xr2IV8Te=u}7`ADub$8E*-}8vE)+qw8l~zMR^oQ+vM`s+wk7u`M7)=-Z_pmA|FpK9YL)VNTZ?S z$tO}81D!xViD$RTCv&_tbRzi_Y8VHdL_U?$c<6ZUoyxg!`L^80FCekoz!O{N)3`Dr z-;Oj9I*oifrOD9k$Y+pGhHlIKGbn9KS-roRxl-j!-aaXx#k;0JXOhpRG!;6Pnr3ru zO1?e$w0sV^bQ-nJAx+QcQp3!A9!Jyj`8+!dI+uI_$1|Wa@+sK@u20Vwa&0zrKKUX_ z+d~(U??7n|bP@StO7oyQkT2oM$=MR>m;#+gzJx3D@*Q(A?HzgV+w*zzsYTcc4JLP+Dv>3W1pPcPMX-U2( zXLp9~PQDkVrO>53w-@Jj&i5wYCEtg%8+32-k5JkJx(79Ugmb%5R@Zf3-neVNZ?2xy ze!OeI~MSTZyw0FLYr}oVcqO=cmA8I^^D|_b$Q^S7H zW#or&c2af-S3Z(2r-lQd2Xl2fY5)9C@&ob}qywRck{?EXAoM_t+mr?6cq~*{f$&aRVDD)`um6TRMk0w8cXOGB_7&rqG>Mobp}*TxC?mKnfV1AosnNi>1^l)1aFU_yzU6(Ole$p3s+vz(cwhcFH9r7-jQj~o4?-U&f0EKe&?m@0LH-c*A!_|3x%6Rb`XuSm{3&XC4Eh+) zJc)l)wCeg>KX&vdw{8{oR^XI7Nlh9{V`ALqR=jfC93p_nGdx0a% z>Pf#q>FNB%Tn+dadDm0fujHTR_zkGm51*zq z209{pn=@~7EOm_kD)D#(=Bs4dRu7jAfum`;dqI&8}c# z`+!@0grv=l2-&`*O=EAOM1jDGzbyp~tKba>k_rSa(6|D76OB7KVQ|{nh`ouo1@_h$ zbvuBX19dwzp+tehtpMMuNXVO7LKO*tTaggB!xCLa-A9lPhKkCGu&Ez(1ZR#U9g-yc~5CVcQV|%>Anq z5L%VM(k9Nf1RB_z zSk!5tSyfOGuhS^CjKHb;b22#F$<%rlX>~%~RwbluHB@}Bz}x;m_Rc%ruA=JSXYbo< za?^Y6O+qRm1rk~+NeE4lt|&+ck)k3N>?k%+P!PldDhh({D~bvhK#HKeDvDsi7kgJM zU7Y;v-dvd?3p!dt?yd1Mr25wZEt8`Z!HOF3%pJ2 z?TwpIH_})W#vw5m`+u2}VqIu$NdY}SndkaqvyzRV%B%KeA)d~vM`Y*gKV{d`Cy_2V2 zKrxfC=-Y*~-kwmmb3xPI&eO%)%v+rCwmoPE-X>mkF^E9-sNSjEKNZamE5je58_k)J%75FGcj7`Mt3d&`m zYF8wB8BY~slYWq=evI+C47@J6&=-n46 zp8@~+0`vxo7~2=A%?VRQ+Qi*%;@tJ%XvPAGv0V>>CU$o-WjE+5f3U)W&@omc2!L_~(y_X`=b`SM;Xx#<9izk1F zbKii9)_jNKWng6bpS}yuG#omNZ}=YNThPGaMBOq1CmMGjM|XpXeVb?hfFlvOdw8k{ z+&$o3_wwBPDNCVZb7F7b1u^?BPZWFmF6fv@+m9*tL4U-NsM~#@TlevdpK@e7P`97* zjGyzYCD8k+f6np!P*JyEfHIAMiZ=a%)(^qKevzms-LEKOa=)bhHMN+W_?$T0PoY2M z8NcD2Xq-5lnB31n!G4>lD9i6?Edezf#ZyJ#q`%;K4^VyuKK4MOzv3Ce*b|om8RK%{K5U~@B zTMsQc5}8|HX`%!&w~=-uN6laYJ3=?|WRbazl@>6JvCy%6hsd0iuYeXjsg2SAZKW2O zYXB(|lM8&Vle!T!OdL*pPO8=31@g8dR0OUYyn*Z{d`k-$SvTJ>Bw=_%d8UZn5b7T4 zHmF!#M(H|uUdHN%(H=qRf_4>)E24Cs(eegghTOzWCfosEFK9s3_fNTB3B~ zb7FNp37;DVA|_ThE@5xuI5!NWYy?)ZSltNP+Q$1fD&SB5o&!H;JQB zpk{&CO`^_-U0`)%d6J0TSTHgz*C`y2r#+sdDSR@nnCkPPVg^%rzK9*?3emYq&_L`a z@f{*|lZuSk1y$? z&f%%zcG7KmYCU=G z62b>Y$B_u$BIqvE;(3ce&=&E$jOQ)pxgvSRN z{7Rm-D=3@j-EJHOp0@<-ERZ}Ay*0^BTEnyFRYdKUab`93?$~pzUB@zG?K+m(G^m!@ z?tIsBJ{9>}%bDGwyVKqSTZ$Dp$;R4)^J_V?g74ge&&B_=x@u9tJ-KoZusBh`j0n!+ zioLO-W>xm)dU3i{{FaOkYIW_Ctgd~M)wK_H)?Ci4q27n<)_~v5=1x(=)oENt{xCB_ z=-YHW?Ma`gJ=*uNqiy7xh}~ynw^~=_t4I0&*YLlm(w>%d9^b+$-ho~?--XmYg#71H zXAEsjsk4*+S?cUMn=%?Yi+T>NQPA1c+tL~dokKmBmOEE&OT8Vf;n2C%^Joo&Zbvs_nW$?xh+zq7)Tzst3wuH`DzZ++^X@7gfm^-${S8;JcLw)7rcu@>*4iMQ>$ADRB6 z@82HrKl=Xd5&OdTZ;!;*^kkK_GSac-my20nu;DA#e4RjJk{^{seZoy zqvW5+L5|Lm{6o2Hbozg;0dyzX3dh~4zg-X5#kh2p;1G&=-sG*Jlp*wu9A*yH1NrYc*Y6DmAXy z^`=r+X}S(o>MBh$yGUK1Fl&%9%^LH)xnMmvkRcH)k&CGeGw2U+KP} ziOwR@{Xi@oRnljIh05{L{proyn+a4ol_{+FDHO zuvm;7c!=^S^iiw{ZKd^CEJhLh2%AMqQmg2P*d%|4{+;9dv6ub<{RhWdZ1-ci{ejjm zlEwB5+P}m$(_;HA#iwYy4Kxe%iz?07RpPqM#VO#KZvd}-0~oCsZ%c79XN=W6lUj_o zrFbdrlfhDreKhm;D-&94q+{M;?u>-o8VTvj0@t**7Gm11#erbW$APw!`KfRx>DJ-^ zu;$~z;*aMjVoCSs%mIwiBfy-WN!cIt{0Lg+syZS?$cn6+_sTtZo(B)Dsk9eH%bJVI z&z?p7Z1`z+&Z}#-7dyZsYF+A$J5csv-r2R%S*Wdb7UnloKU+v!y=XOa6WL~prJPrP zTEUs6lvT`JWXmX4az@N!B~%@fSPy2Qnamnml@ND4 zi?)FeN6HFgVaNd5-DKj z3o+i3Rzu|>J|T7mPHn6Frg(^UK}%iFwdv|*MdJ0Ma)0sPSgb!R?uUM__*3zH=&y=j zLVwB8kN9L*aWD0-;-{SdUh(tdXT`6JpV0m(^w-qC;M}jFp8YZPPw)VJ3(NPW;%;g^ zP9yLceVd~jDL3KK`4VStDDL6h4U`-459z1*BIO?FJ)FIrGhf8}b4T$tJU(CJ=*twn zLto+OtLf}*)L+Ic_9-lBJ#SKNYCUhG@C;suC-8&#zOKVNcs;Gl@WNe>Z}I)u*ZM6- zpLBdFY{vPJE%wFBfN$?^b}r&kMH9g z{Rib^_*vhXUI3m&U zpaS~-PlKLT99102Clm1IpN!xB5RN9K_yFSyUc^;KSWLioe+oyZQj9=26{>|eG1-6< zvG5Ke!eR~O@MPspgo-xoMm-5zaX09GT(gGAjAs&)VT6Z~90zfBU(Ov&1jhcfo{^$I zW`hD4H)I6NOp5V3pblULD>*lVGP4k2m<%=AXgc=z4$z&j!lx%YemciH)83Igrc-7V zeO%iMol89x+6O){6)GOmS4^Sq11VU<)uIie1&cVIM{5ySfXCtwA`9EoUSEizt}jGS z*B9cT>x-X)NvM_$$(FeIeetzPJxOa((e*F}gx5a6PEm2IvOmRUxvwq4+My z>xSZcpsX7TQQHk5W?zBcj8xhHrbaYfaWB$pLvai8XhU%;xb=p@=+X^^$oGaq-m0!z-oH;g#|nVznz}WAS#VUa3l{KdMr`1-Vlx zjis)XdUYzLKAcKvoOGqsZ&N9a%d3?7Z7StOcvOng$o`_#yI7R^=!(*4_@Xodz9?Uh z->fLl!dF(5#=94#s9;gP8i`hvry`?@vblI+r7ZP%mZfV9%JL|Dk7fCMWK~(V7OZzD zjr%Lh(~(?dsXw+X^~5%m2O)hLxCU&p6hCYz+lw`v*H79|8m-?@u0d~VC=bRv+)y6E zN{oi`P}X2Hl+VBe+*mF`jx?5?#ja58_{LHTzOmGHZ!ERi8%yo=#!^eYk>`VYmg19* zrFckVsW-5()aTe(>eFm2_dr@Tl_C;Nr5Ht1DQeMFieNOAVj4}QC`VH%=FwD&b~Kfu z7fq$OMN=ta(Nv06G?jBIV5_BAMN>H)t-Fa|3%Xi%fp<2QBavB6r8sMI`DoDqT~|C> zG?#xV)T-|?;z(|%kLK7fquRCE>v8%wKS%(tu)%Btu!X1tuz{=t^6dh4{hZw z$g{TcRw5DF%FhuY(N^A^t{;IcYAZ(~o!ZOKAdlKhBVF1{BVF1{qg&cbqg&cb<67Fw z_Y-f@UVaE^)n0xU8P;B2N4!RRIU0G@UWyWTl*adTl*ajVlw*-39pyWbDIKLTQXS=M ziB#$+jr8m&Uq_TvNBR2Vb=g6b$=jfCkajUwtOFCf0Bqcn1;vwR7%qq963 zxzJf2Lu6TJd2DeE)Y!Go(x|o0ay+u7vpfpv(ODV|)>#?>)>*!csI1P?c(2aV7_ZLq zG-9$kOEK!Mav~C=tK1za&{eKMQgoFflwGArWLIenVpnM-Usq`iUsq||URU`XBI&wH zqx8B;qx8B;G3~DMP^40KDK6VxipzGFBC_43_-l8$9K5u@HU!gSyLE z$dm4JGBTyR6a(+=)pqG9v{xR+HhGw~R?EZ5Qt4nO{|je+%)Bji{;s!Lv{%A*dHhz( z1K22fo~rhW9ue)8_TqP&?3LebvRB%e|L>`^C5fO6$o5KWvR7J@rE(Y6h_;OON-Oq? z)`<2>Yw=l13s#HvO4u%1EiHu>&7H~rsCV*fo2-@=Y!rPtS}M)SQfW$-N>j2_uEi#~ zc9Xr*guS9oqP^0Dy`o*x-)dbgk8*blA96w##A3UU9vhR?3lB zFs{Qh!%$c)W-iid*???V3st`Cjb#$Hi&l&F$~tTktr)GA-ICR^F5wbkwXDM?8OUl` zmkbaEPU;lN3c)o?U+ZfP_$LFV;;duskdVu z!N$>o(bCa7)eG(PxVRJS8&FN*K@Eg&ZPZDtd_H(=TK{L49A8!hhrmT&q21miS~>6WH_?tSR}tPs0T@K zJXDF$lPr=`pr<4o=Wxy#vwRx%#Syem#9nzm^fc;&IUbsBys{ zNS&GJS=%6kmO+el8rGf*&NfbT^4g@A@wwDkmb%{-c{ znMac~^JubT9xb$E9z_OraF;&&M=5t#)+GyO9lG>aXluu;OLokyrhuK3Op9lLfOrSupF91+zX`FdK^ZA%iwxcf1{INjqjkp&hfK(2m(q zXu)hKv|ToE#ko*zmkous%Z5VRWkaFuvH=;%N~J>EWkaFuvavW7RBU6R1+x(wE*;r`7Y%H{3HWshOqS^>HSVBwg+lcIX1NM*>OeI+`m1MyP+aP}s zaZG1eGt|j;sU+K_Qi`b+<-y3EqBPE>)Q)sWc=@r6E}=4ar7nNH$7CY3xe_zmWJ8Y!r4tDIWn@ zYrx83{aE=hmP%tOBGymP%u?R2q||(wHoj#$>59CQGFe&GheFsio40 zRydKis97Tx&qGk{mBwVRG$wncsr)sPrK$WL5~K+m<$F+VlqNLO@zCFZe>EkGqzN11 z545#Qno8}Grev2iCA$QR4T;oT-h;$xMvK1zdIJ)qxfJDU#`5?YR2!u^*(lBBy-23! z^1rZ7n$fApV$+B`wUi=TE!Z5_LqCCC(t_pjCFpfnBrVtt*Fe97tZBg}7>ylsZK7gW zt)&Q8D>ldbpci9dw3gyyt=JzQgleg@mRc&U$x>-8-;1TvT3&{fX)VRtTCqsp12rWC34Pr+*GD76?muod=)8gJ22YOi!8OQoaKQt2oUL4I^#e;fkU zUg=2oN=LF+I+DH8QSOhu(oqgUo^)WX4uKww-03WhGU>!3*%_+s(wS_R&SblEmOCLw zI?L%uicTzMBm)-tOy~?GMQ54fa(d0E>dqLjK6Fp&wX_ zpwwzh`kk8416R{tMQK4(T$QLE#Fdn`h9NU(~y# zXRH(bQLmF8v##Vr>jv4-C$$S@X!5XiC!gC;&=0*=`r^#$tye4WA?40t`tF7^KGAzDtgoqxt6PlqRSna5|+0 z>Ue9TZsmE7=V@s?`&|vRr*du@t$3T$()*pp^Zcde7&i~O|I%-0<3F2~yc^oZFS3uc zF|;)Lc*+pYcc-_Y??jtqW_o+tHTuroL(p-s4LvcFV@HPn%WUeyIWsKv#4LJmCdc;8 zEXJJ?MA}9pQlHJDFFk87&VqW}nEsbuQvKrEAI91kf8+nPZMN`%+wyk)Bzs=tdY|OI zzDuvre^cRYdWU|Wgtl?i$dOO?&D(Q&X}zaR?;kaSBcEfuP&~&c6iF4pX2i%`#1mln%oNm_vt|Ir~iA7G2?U0n?LY#V#eMz%_l}ZbpLBU@8YOB zZx8v`oZrb6&e}bjX7Vf-I=CWseRNjusjPrQm)Fed#&WfDc0`)nS8}u>&GYVzs=OJ= z(Fi1w6398)9>vkfP4db4-yKt1I3CT+Z|sCJOep{kPCI1VYB*4dFeXU`M}Npa zcRO8}cvbn}cnlfo{-;Ktuk(&Wy_=_Uz|;6FuN%?CUaidqO?(F%!E33_HxEK%vn~sqMVtX z<};;GZ?C%nx#N%f1i6Qh)ct{C&$ZYs&*&C+@YFl7l(Hnr+Y$7Wo&tA;TS{NJ+l=|l zhtpf`SL7Z!tUu>Cc4QmQKQYQ>1@-dOGsB=pIZouv3VLfI)V&tK{xJlX(033zXYK_*d@v(@R;+-0e<+?me@Rf9&o}eW_2~p9XI{rHeju zHz)h0lQ-iYWbSa&NuRl!ld`>oH|b7f?ugUD+n!3>-6^Iq(v1n)o9zrk-;p43X1{=XsrPTxcRwJrREkTw3!%KsPdD!+#<_1D(C&!@UipX%r5 z_pqh$ur=2_)xY!U&=d!j^U86SmbejjB4*m7-aaAunw#0)^b$`|Og|gC- ztSnPIG?FbMl8v!%Ptwn|2fe-jTfb{d^K|`hk1PB0TrFQdo#pe^{LZbp=Be(Nt@#a4 z)-_Lu|1!`R+tS=W*cjWIcd|9#^>lbAwf|)>dH8hrFZnlYX%4CVFI&@h`TzExXP)YQ z*_!{7uc?(M{eS1y{NJbgzdRj&Lw;9V8XNhV+V|O?_y2!*S6kCxGtdvjpv7WlQl>#? zP|u>}?vyjBXD4*PXnhfF5d`D(r+^0ZfjAf~*#{=DE$z9K$zTO@6BV~Ga#AX`VdSJ# z9K=I&##b0)Xy4F+7g51PhrPW2<4UV&n zRws2A*v)cU9n_tmHY;egQ+I&WtfbXO-3~Id8?9FAHqe+=v|6ZJL19+YYNl=hd09iN ziMkoIWp`SQ)J<0bdqvD+l~G2{ zdwVl}E~@UQCD+yN9PKacO}|a54`2;t3je{qb^V=F_-|rSE9oz>Dm?=JW-%jCII%AG zkM@_;?;@>VAoh}WY!$r6*za49fVkRt{+GXA%*g*Jrj&R6)(=v<-?#YW5=Nxs+EE(2 zev7)sPT%hO?Jm+Y84K?B?T8gynGMwg=6>Ifh}iX8ylOW6AReW!tbUL0+P%LYYyW7+ zcU8F5m<1S)+IhJD=X^}bcxauy_qJHidEoxWYMOt*vv!bFRpzc6B zGx4KuKn|53{m)bQCw=su|5^@}6a9z5q2i|UqkJlrALUc2{OEs>%8&kTsr=}#l!|~Z zO#CRfj!nN+%vi1zOCFW}n;a@X%BOOu{3xHwp(3X8sT?X#%BRCO@ua;nY!gq)r#+i^ zQa&BJi6`aLA)9zoKJDJblk#cTCZ3c}J2&y9eA>aNlqXkmuAT8K9|mVSmfINJyKyFX zQZ8s=tjm+~Y4awYbo@7M;z`GRBRnY|1!u~w4T(=hJPSBr8;<-`zHmQ}vhk0o_r&{icyEB2Cr``o_^OAIKr{i5w%=EDGJu@m%^tv{{Q* z%y~P;uDhPQW0!cc@?BJUTSj>kExFy%?<|mKiAIj~u!=P|a8|EF0nKxcvQDqVs&vrYJBK1*cfAPh{1Qh?_`s*9aT1{60ww(a za~J`7oxu5Ph}GfU|;bqnY1p}b#LNRwF_syDqGsyE%)yBp4TEp;!&ew)P^$8s0F>U!%w z%FgumY|c!fwG-4e*&X!DY^YjT2QBv*cV^X}WA2M>Ijd~imQn8Pt5;{o#82)y?mS&^ zb`i8f9lKSBhsQZ?2gbLOp@qJf2X)VS^^qN*N~;E1+rtU-`AnT;AyoO$#F_Bt*j9$* zRowQZeyh=`S4O2?3(j)AxBYKV<<;Htnk&Pd$Ly)R(p&y=wsZEgr{pH%MeHwo$)2<) zhNYgGM*rA{_Mm;_tYsf{5j%3t!Rnz9^cul3Oz_Mtsxf5}t!$4;r&rlh&Ro-&@t{+dcp$#K~WXMfsj zi&L*v(#*0Q{UJ};E5sb8zI0Zy*W^BXN()(@a?YAZA8pTBdusbM-?5S@^_;yH{k4#9 z*1u;o&Yt{o^-$&6p8NwPo-%9?{-r$Re_hL4k@F^V>~7w@)V{yf>CH-&uD*S#oM}Hv zgB!=E{#;4F+0&65V0ju1Qn_nP;yp*t(liH1KOBgXqGG`H~9OO(R4Xr=)4EaJ^ zz&TA`aD42@XmI>HCKl7r$}cm^m}h1PwezU?WgO?76jn8Jv^{<2sP0Ik-9BBI`fffw zC8sFE=KqVE#N^5G8`*vJnBAbL)sP2;QH~&%ujnPBhdLhvQlWnXvu_~;~b*S zHGz@rh}Hg?$e0exDQu?D+8p`XOmae4OQGe-9eUD36LgLWeNb*vCsaS&lX@*JEh#@$ zGxRCmr4^<==+o2;Kr$Ux2_CzUej7qZaS|;e2Sc8kJxi^l=9J8EVP8s4AlqiW%WaO zND1i7WuB+)IiuwxUukJ8>+IGdkFp8CA=no>=D-q}&Ea!fi`hEC{cR$FwQ zjq%+`TbblMEe|NK)QXHiP}Zp*$~kg}aSK&_UOsYFseQFKeY8*Fw0+>X>9o}-_u=|& zD$n4$5;}w9XYiaE(0w?!FJ~K|&!FCy^JW#16Il(*x2LtSP&s`+%D$Cna<&O7Kbj}G z5jvZC|HP&4;?+cZ4)y+N_Ba5#KdY#mQ4XNALgifd6Kf_D!~vW+kTd3JmVa5R%ey*= z(henW1XNx=h;kt7a-G3kht&?9M|}uq+&4`v{Sf+MKJ;LY4&}HLdI*k&OIZpu2E%6lX_4kEA||^G8CRZCnRE3aTY_G-u2r z?aXs@nsbif>=;%U98G-;XWXq`J?B_BaT)X&j*g{u46Edney)`p3tdiqT$-JZOY_q4 zd^VoU9!gI0evE^zq&@+zUkP2wvDrT+kmW;3dm?2L)Vb?KW{g$P6Vj)d=nJS%;f#C3sU4W* zqz|gLa4I~rH*{|}=u|$N3O$ATR6cbVIp@PUj5O9;GuG86D~!?w(D{s*`Lq{OwqqPs zIJ-kSy92HHjD-qk7bo6XocLui*KWrdXNbj=IrO~u?8tQs=<^Eq?9A~(s2sX;;>4Y~ zb{6f0)Vpxyj!^B`UAcZIdQ!c930JEb?o7ReD|UeHz|m5!SOi_fJ`J|o>zC0#OZj{^-bf!*S+E@ zO2u9Id^Pv3O!7e8tB?1;hO@gtcjHJzVI_1WS8JJ8pcT&T!Kj!3RbE66!9BQQ1??5w zxd+AUf~&c6FYa1PpD8u==AQA;-MMyeu9^T{MZFJKtcI@U9%sM3n7x!K`*P1%=-$-( z^4adt-8tHi>-T{^gDdx=tYr=>INBfH7zNdu+n;O4K=&*bW7 zaqWT7137v&cOAlv^DNFg?>HkV*AC;39_Rto?%{j@v(6!0&>%rTlUh=!44LL(&{Ri4j#Wl9XbTC{0lH$VrqIsFKM1J5!-kxpop) zH$W$IZW#Ze3+kM2=0|61`Ap#^mVtwqq1x{=ln&<5%zT3Shs)M^h} zyUI1+om6?}8Q@LGiM~n^o%s7r$hA;II^YAtMZA|d01|dI(y4+Qs?tA6eEDO$;Z-K z1sy{@j@E98lUMQPRx(3`z2=OdUaanHEbDTpy5=P2CUFqun)AzYdRh!b%~h(b?4`AY zF(l66d?!`HI_pW5%TsCXoaWG-(#SI|-;vV+)gO*mF6)S&d#RS&e=Pt;es+*J|;OIgy7RIKdH_ zb@{3muTCE^%Iflt?5xE*;v*helvm49+c|TG_Hw-zFGs1%x55u{TGr*|z|iQ`;??El z%z9nER*RRn)#XdZiCTO_oev%hE{6;h1uhq9>x|@`M=W^QQkzGFixbwyg6H0nTLLeQ zSa4DNhy|aJ-lT8UH#~SOc#IQmy{(A_*G^oW-gzL1Yv_&n^ocyDKToSt+ueQ;h1c>7 zJCr*CJACK7l_47NxXV1BW@QO`;WuR27Q~ zTi2(U zQ7C1Rl5sKor2OfRNQp%$dFl}<`AutCnWGd^CN4-^mhl=TrnsPzM|3beEZgzE?J;Gy zR4MdWSd_A;ib&OCQM33j!|69AwkyC~_oe0J`Yu;_`Q~P(cWFN9$SyseGxmVvU<|Uu z{C{Gv6X|>3#576|)b}LTD+W7+mbRp;L+s}nspqxeCow8!zyazQ(-`ggPPXA~bV55h zqbD`c)@^trdR|1))KMItz9n@8Eqiqs5j97-qc>uWw&6`V@?E7D@%z(xZyqa~)S{GC zA&1nRTzIZ@%2F#n_sYSqiTmR7>h<-{>3@w9abVdPI$Zpw$C9HN->{F(nG*QM-ssbT zZ-`w4vLVW`4;s3^gA8B%?~HQH;);FYWbq7j8&M9ijycpB-*B8|d}B`1-+d!u7G_f2 zme2N2BQ+2YF%40Uz&FgcdO#Y%2Qc2nEdu43N1gGFjBL0cRbU$Swa7&WR1P^fagkU@ z8}0ejVi}##gQ*YU(}U6U58;gXMHh4-M~5a2@X*AW;v0ve3=)Wkn8q;d0J-jn zq&ppv<{(jy!?6QuQI1`?BI6tKWEJIbKYHh^qo_qWmQWv+w6%>$kZ>ZG=rjfCZ6U4|1`J zRu$P`uSc$9-^Mf-WPHOJUzB5FLN-J>)^L0hQbHV~7T?gi5#JEy2z=uOoXIGMGA3gh zfp2Knh;N8^D4E1GL^hOGr&6|oI!B0ah;oP@p33oFaEx3ma<~oDIY%r}v`|?oXW4ch zljGzsrKkKOmx(aSWiz49mSTqTm%JyJ&4O=~n_`CYms}^8%}$&pawxJWekf|F%obOC zX5y@7s2nJAI2WFh$K;}x#9y8fhml*v3`G^i48;gV7UeAYNDWWqQ2tWuJD9TvK}8wG z59J{_P%c{l=cpaZKXRE|C&!5tiVBMi27hgzxJ52g<9s%s$z^Jx@?D^a+b2s~&I+4d zjY}?D1V71t;)aJMZdwdg-+C@wBZ??iE#Jvu;*4^Z{56bP{@N+=m-wOR!4XI`c}<;A zE)yM;^F$2gFZD&aOr8=`6hD-+)GtL5cqsnWZ(JLZPi54oi#Si5sIZymho-((${1q7Ew8T^LjaFoqUpw<@mS5^;S$^%3 z_$%aB;PbmC{&FU)$LH1X_M=qgmvdm2UrYHcUZNvK9aMX0}rMIPqo1`26mP*PQ*#ofbURoj6FU#&sC)d@Xb>S7gcM?Drf>RetTsah6|! z)jRtgP9Ig}*9?vZl3z18djvDv3^*qw*G!HxO0VvbKI2do6UyK;<}?~%U@Nj z{%FnwPgPNRb&rh9Z=3i_oj4>~#^=?KGd@2z@z-`7XOupqn7T(uvE!NR=D|Pe701&G zE~`p0`R@ciRdUth^9wk8B6HmWsK`>F^nuJjpEL4TVDf>|Yu%j0d8L@P!AZ<+J0$*+ zpB8Z(XnaQI7bPy!qR7a6NUp%=7blJr2Rnt?Y)ANLr%n7duq>O-=TB6AZ7#W#XmXj7 zE2P-g$S-ZjkXf6{GPS_)f>ouM{;&g+%#y!qrI_+d$rVy8%de1JwK7YIrWZ^fmmH|% znxFVfX;mw~lyCaN^n8iv>hn^HDXprqY$4nu*Qq7$0N*Il^mgg#Ql`mk@|RLfE|asA zWlFK|e^upINUo4sN-}wBN2qd5Uzn0BWLB*dQ*y~adcKrk`oEN4O0_J%lvW|RYGqly z1FU#bjs{9I>RV&46<(JZ` zUWzHRsfRoajk|Q)Zhos??~;#q^u=p87;9zuM?aqb!Fft-_dR z=S=fJjer_`DQ|DjC=h8=pYR=+BTBu&>`BI58gIFPx3HQsY7dQ!FQuFOynr{dhBIS1 zHeZy{nnuBDsi7uhE2)3dm{H?PjUjaesq1MU zX-!oat45wqq`3aX2w8dCm{sMzSda0t>I}xnPD%Vc8>(*5%lSU2aeL;WGI}cefFepN z;y*-kBKkwCDo|w6N25iIzY648%PR0m<4OXT7B$Owwb)vYMll92qE)Jhs(7myT_ECO zvXQ03XcsX(Bc^hEOpcBb1I&24F=>Is8!;ssA5k_&v^mR5o%8K`X`t3}qJ3|klZfRp zrYHOY_VupxUqk>IKP9TIH^KO+>}3%548MbY7b`lPKf(tTkw@aEIU>o(sX(laRLapy zV$#`HEe@Tdos5V#;wfUFj4ibPrOtjvR~hwWAI7s{XFH!{?5N-4j3(l%rQlQ7@LL=; z{-TJCa>a@$w{u+NnsIE2YdiPFDixzfV{|w+{m1eDU8NE@wmt;kO1z_SjF=cHB80v{ zBdL6IzDH3`$Bq$25j$$m9kFiX(?vrg(#jqQZ$|hx?3?U~hzO=Y%Z;?keQIBhWTZI) zGx9Fp?pzRKU<9KfJPyto&KGkTEqWjHLB`0O%iI&=N!`PFG*+y{DBW(;D0S>PhpEFj zO7$Z+ZXKV_d3t-gDX~^%d;Y8MP)yi)-uEWYInVp9jAWd-iK~oobcXk>h&emY8w0s* znwLbUjg^$YjGz>;mcN|m^{>ibF~f^>xA6<)t-!#IJ2W~oxJn${2s7t-f3N%$ah=Zg z{=dcPABw#@&&y#E8EV|2^RfKpDl+AmNWF1~Mwc2{>PiZuPK`{|&nEV-7eF6@@u~XY z^cswYj^^07L*rTXBk0F-CoCfq^*$Jfu8%MLt9m7j;BX}Cv)GOC?s(RV;R*%)8b)kP zVqELzFdBCKh;NN%U|jrj$nC83*R_x9ysu`*esxzt?st>9& zsu`*k+JBC=HBjZbqfM&JcP5V!=Ip3OP&<378LAboq;|CF*%#Arv@J{HOsf9kIFqXB zI2TL9zppmre7j2;byD#eWxQ0bQZrN^R9jRtjEILGddb;G$vu?5l7Dl2gqmZHoRHJi z54w2k^1k{+CvV+3L7gKamDLBG`yxg|-Nkvsxkb&UmG|qMqu$d(-#8y@lQ+{t&QTEy zqGqT*sLrTns6MF9sAi}>sLrTnSb?fDI-46wo8_&t)|uZK+^AY*vc7s{ic-Tl-rm(0 ztsGVcDOsG?BlnoIlF!aN>gkmZ{V@1TFWKVMXA}5k>In9n(ojx|Xlv*6p2Sz~;ia^+ z&nNMJoe!%k&nEN#)yDNYhknRD!<<=2?;D4#zP=!hCv61%&N%{Hx!}mtUeHe)QR3?E z^V8^*vy}P~NiKic8}^krSFL_Hm7cLbgQt|i(|E6r9sSUH=^O>>V0xC7hqWF%rEg@= zRF_j?D}(hkE1zS1EB$Zz^?yr#Ro5^^j7vnWSGi1XlGirpGWko+3NCYvYFJ+K zmb~U1r?#s+3;uE*RJJL}zaqn5a9KTn_2(?3-;IWMhBfX-OS_i8)N@7noRj6O zum~2wJ?hZ%*Xla{GLPSUcqnt(8n~zvK8lqD@|QZXc2+HyY5&MK&d0SJCug~;NIt6N zIJrqLxcnx6&4GvHsl2)*`^Cd1lFOW}<+6}sq20=BT4V*^;giG#d~$#L%P9P6L`Y-@ z^a(ySG~|dKai*5vLkEtS6D4%$y0K=e*8WlwWc_w9`%CGP_1IebO9|wRsh(VGe<`sX z8KHGQ)%KTTF|4qN9(p|XmztvTI;<(jOMm-Id9974zF2F2DXYfxlVVCMrP!E$QcUY- zAo(Q+Z7#*+FF8wo^DVj(GdRot>6@NA ztuE{S*$q%-Y6qnW>hJ2HMCMMjcq+Gz_fy7qa$j$+@#$;OS=A=@q)fpZqKzyalc#Fs|Gva%YqM7|p%V3iW=p_QvbBFP}b>vJbujZH@i8 zdm8w^YjfNYbsvy_^|b@JdS7V4od;6(PCkKsp?dlb;u<|~#;6gh1@ZhU8`P5`^D)gFXoCD z&_0E8rzfd!I(M8(yOsJSoP81W#nfkT&phahs9(yt7qM%VlH+BR)1mI)`!ZUmLSM}1 zFXvNtxq2DxS8%m^^uCn(OrA0ydIt3?8SCxPcCLFR*STlb%c)<*`By?;n)c0dzpPi& zIs6p2apT|U0&Wy`>lNP z26lOQJ)ggg`(6)KQofCHHv7K3i7U?G%-f)Exd|Gd1f3ml5=R3K>U76oW`(2bpQ1Pt` zn7xKT&*k$AXt|@=`5axqu{)h9nJ=X51br7r@8NPQ z{u>JQic4s{8|v=P@8!Ckp%+uTC)>{KZF3<<@8`Y?+2KZQ-~-(A9%v8ue1LKhd){2k zwU=_$#q4<_7JC_Y?_BvHXWs|Cl=?%=*2AE~xaULM|9x#e zU6)fXV~-!P!;eswKriFyqg?Sp=y0z7D0BaC=!ZG?QO;h@9;P4R$}1>K*~xSSXRoAO z&VHtsbN9#66R+a)rR-t%F|NIuas_*Cd&S2oS3^Y~K2Et3dL^Iy2UjnHUPbMGb<5c4 z?rQG(1m!AruM?ZNhHI~ej-*pJa#D zYq|P!e0n|fdX7HN)hnSQS)b?b73|#Vv%bJ}pJM;k&vX6;j;@1V$I*?*%rVe0+|glRM8C{+cT(0uCvfggteXi?^}#zS?1j;rBYmeM zYejX%a&Av2ydVZ z?aXo!|ExA5M$^gMqQxXe)5XjnW)V@;A~oG`zH5&~bz}9vnNHM{wD`=;ug)aGE3zKh zh+Ny8vkIs`iDQj`cSLj4eZ_Xwj74q4cExaV)&lX~96=svsHpEs&bfw09aqaRFgLMW z@!p&*L7PzfZz38}AoqoZbT(y&6?%6gW)t)AuTNel&}QyDK4~|{GyWs8L7hu&D>SUow$!ucp&hATJfG{;twPTV4NIFh>shUJ zde(e&AoYk^Jxkqc0eX>|#i>c>Qd2UnP7UldxULP_#uKx)rRJrEwGb^w{X#u!A-a%J z4Ozod-#MLf8dU8}ZR=z-p3tyf#9c2kR(R_7W*o%O8Hu-?F3>Q+*96E&=} zplV@R!%_!%8|7@Mn%6nZQ9aNejzhx=Z7Vda(6-dGc0%*1)v(mg&g0&5pz3PpGs_Kw z4oiBL8dhjqp<#u#rG~W=nvnWV)~$wfUFcR9a&{Lqo_A5dn>lefba>LL)Vb8H-htku zrgl-%*3_xglhjt!wst|Yxrq9bq)miwm9?!A+^>eUD;kb^je6FuXg*avOFinnXh&)m zAE2mbh0Yb)*8BNX4Qol#lrDqT>RDe{|>Q)~^J5oEl28l8bs%#HE>l%(fzDdsto$FIPV+DFot)4Z3t3$(5r*c1H zCI4qAYFnS?OlVl4ZK-FiNSe}0G^mMOk@YM!EOjb1Ed7+9qlBLIS#+SRVXZ{(scKkX zNIH~S(<-!|(6-dGLg%^>X*UT?X%bhdZK-E{kt@}RRzo+}vqTPVK_>P>Cnr5i4J&J2 z>Rh$jmU`A2bR@AbHKn!CFL6$7>n5nWSk|`sc#2xqt!PkvN$1krrRH@jT2p9SYHn&! zdq8ia4h<{oTvL+%6?)c`q+z+DO`S^(>#Njvay+Hd+v~`24>S8yl)}|R6^>oqqrA}` zZeoURg*sb{yR<`{P2Cx#6Y4D3lxDIfW|1MZol)Fbtq1BHp!75^kQ^L-#m2-{?yTls zT#ms;K2t`zrrN#K+-0q#?(NMe;S+k+H^OgPhL^K?qUqeJ!;>b@X{pO`a|0p>vEXBo_6?Ao>PBsgA?RJwfk1M z!~POYZGm&;P!aNGcxDXki2KoQkiX=*k*UA5DjFDra=19HJU)W9R)|RJ)5}ldn{r*Z zqrf+q{Up9wy~d6j-+1tJzeIfsS^NS;`n+LP5^wQ+@xuxf;t{N(tnk1LFs zC027gf+MeRUV*>m{<626)%wR3%2C;`mFGom<(My(7m;l{_u7*eSEzS2d$;U0HIe@P zWl!Z;KyBqM_t#*4EwgKy$x)=hImftT(S*q3m}8F2)S2Uwj6gDPV<*(Op`2sVY?9m3 zGsXr*oRHB&dLp;oG%uM^bQt}nC&WIS%Pebjlu=W|nK3i=v0c(ZoC}P#ij0kB*PNF$ z6z2=GnHmq&3^hJT{l%FjM{yaaYqU^f;#0G2ItM9ZbIg&MAC2g8hVl*T!7)dq{A&iu z9pIdZ;xfidjAs#ZoZ4qZb(urSOrlB>XQ@T>kUSW%CsR3R=1Q#^b89Yx8rzj)tcCC({eQL%{^Pn!FPa|f_e5sLT)9*6_v2jm}k__{A?8)y{hWXp~;6EtC z{3mPqm&!2Z*Y4?ED8H0sN-k+gFXdUtFQwN?dPn&sr%6M4t)$+v{1Q!3ekrqN(F!Rx zxct)ht^87w)yl7_jHIDSe)aH1YUP(RZoL%i7uR|#_Kv&dL^o!{clk;2$ zGZVb#*|ZO%%m!cCmOGw94{V$8n%PjXtmpFC9OxX5%(0}W%r!ViQ1p%+PW?Pu&rYb# zv%pcFM_cShzt~*vIEtQ~3%U{>G3SP(dEV57+8hST;@VGhA3X=`#+7KU06QFHMjx3g zy^a8PIga-6lq11tj3+yR>yLqMM|~nsngTtZPfw&A4b@I~KA#^0qVoJikKswKBaynM z>}1OE&=*jj!ZS~RihPRB^g;XJ0nwS`p{^i1jnDOhxhnI8)Ka}`FQU8v>dF)`nv+0I z#A05|(aGQ~M!B6%IVIsTr$SHV$uFTy22DAIC!N9Pr-0O)#@#RF=rnK`J!LOT=#4(F z7lE|AC?PUpu&;o>7D5+r-y}AnUu*;F`QTO*%{C?c*ZNa_H+=H@O-_L=e?Tp za;QEr{a-H!U)i3kUQ2l;$jO;J^L3Po(3f-cI<9&-h{$XC^eoD&ps%MEk$DwV)aH%U zQvG6Q^R(AOMTYfoy#}gOc@s~X2z?Fpn|Z=n(6hPn&6L+CbmlCmh|F85#bw^W-TJrQ z1l6~74$sv8CBl3zXD2}4Mtv@=@gN`P@afwV7V~ymZw3_+pE-{rBBMV`Dy9&c^99&4f-~o_%6zLkdJKmj?+D$IJ3c_U1Vlvr>r$RK7Ah8_x9cMC5D&4c z_2tZjJ3)8ij*sxH(a=k&Kf)E4LiK%pl+P|p{;Cgve~9Z`!O>-)C0EeClJX%?kSh}v zzqu+|3Rm&u%V}TEwO4aiuhz$?ujV^OK|ezMaX!<}brto0P+yU77U>l{?-SJ0E4l9z zn{bw0xb_-~{w!^iPx7QuP<2&tma9QHL}sp~{0H$yUImY%8Xy}FiXe4e9gK{iBdzQEC^!AO>H)fbZ_ zx`C$*2T!?<`UbAhll2Aa8~HrESJ#7ch|}D}x$6_E@;T_|c+$<(($90pEy+^51xde* z_EPS?mFEtF-avgTSKI)-nff+9yAgT|^_OXhq})b*`zAa^T;&d)tjFqh>N{wOp(t&? zLb(MjB)n8g!>{rkJKZWy)(6MU((FH=rx2@8#Ur zp?C4jduiQO`3|3a1Nse~^j&J{H+jbQD0f4@OZ|Q7yPZW0 z_yP1s)Ia6(`=Iynyq{6-hu+WKKjYkgSAI_Y!^$rxKZ5?8`j==+tDvj6?^o!(9Z+q- zUvb4xpg-a0S6us}%CEWV$Iu`1q~B0Wf6DWIOD+8w&-)#<^yl31`=pQkp6CCv@&M<4 z0sR%ve}LAnDu3V!zk&XqPyayqb>)v7{}%cO>OWEcw(@7n@1TF8evqgA9;(*&VA2C0 z;&$T;p#s?AEf>(tv^ElLj5=DKSKY=Q~yr+GxTrN|KOPq zR{qJ|ZO}hc|C3MtTzQyJ9)v!~-H&kZ-=Ght_Fp)9l%u~@)=~Zr{X6%pv`Hg zpz5w0cw#H`pVS-p{GXMLeD*MOJ$0qnNV`%z%#(`Z5$-NXDD+6BEQ;b$=%d`xQ0&3A z4TZ=~W1-d9SZv^#jm0{i*jSX*O+`bo9=e|AHuKC%(Ofi9H}kZjXyK?RS}7&8EO-j% zilVL1W7x)%8;bTqjj^3i8fiCj)WPQsMF*v+=%h45JE*&;o1x7-qnldV!hJ({S{u}S z%0oGBFNPMPB}4hVm3BKvJ$&9)^iVpAVU$j2C(jthxsGBubyqQhTH3{ZBPc_Qkvww< z)Qk_K3iZ`doNa=RpdQU9L!d)=#u&;l=rEo!hI2i|SnA=$IBMx|?ikN=Mnd(3PAJ6I zCKPJI6ZmXYF@dW_Ku2+IB2OM&Oyt^;#U$#{(9t|^GG#1u5_K>2Sm;>p>!nO6`grnq zsF_^)3iGz~73Pwd!e=G4mwGDCoCxisp30|vP*=Q9hwZS>vYaL{iw6#I{(5>(E$1y|%gOQqQheOc4299G8mvN1nx!8?lh#e5L%8Xr5Q;F4Sv3r7V zLwqeqFlgb4#*Rh?YXvIlbEbS{bF5CwIr3`b7$Q@?Qb)Vq*ac-qWZaW#)#uE7Mlcx3 z5c@~u{C!)FW7s+Mm;bB6e-M)p1upnUq8I+Jl7C_ps`^s{|3MVQ|JBHU5H0b4HKl*l z47I=fM^bxjCACz1#vP*EEh=`163_8}weycee*9k@{3H8IG@+A!B95fg>0&MyO%j9X zW+t}3oZpS7-GjEXbL>4Le!VAcGqy$^SNqF6u0~i?^XAQ@ZRWg@*uAb8okJN7olQN4 zdNlU&99nZze`zg`Va$m`I}T&@_4qUn$H57)ua~=gx%1vcsJrkjOns&;H<58@PifIj zO7_xZsQ61Cb#JnB`qBuLirGx1o|3E!BTmG9BJRZ46I)xqe~9ld;#~X%ju_vrqe<#p z_ZLg;jfkL$e6%9)t~s<1{pV8qHb!uD=MYz4ItqM)1MMFYnHz&w?2Rq$A0j3i9B52Y z|D25xaU`Z1u}Q8tH7d#IB*)FdO?>Zoa_0~&{ra4ZMw7?<;fNF;v~QhboL!t{9Kku3 zYU^?~#@hFR_Ye7>%!m0`#4mDgto^NdR*e4<^P%g!BD%}fy86kS4}B|<*Rta==R-N` zvEsUn=*rPu&WAY@r?X;?>xzgjaaHGyk^dSU&Wetgf#$Id ze_gHX&Pn3TBD?a9JR~YDCMhl*Yn{Y0BAb2er_{rn5$hF0S;qXOjb?mV4{uMbSERTA`O3XNR!4hYm&A1V{cP8v$&Jk&jU9iOC&0#AV z9s6I2yo=O}(?1paUsZR$a<#7G+BLfi_yt=tAKFVH6&(les$^FGCwo404y?|K)%j3q z8JtkfUMrs{T?d*EmBx{)B;qJzCX89JK8J1Xd{{dZM%<=zWc^M`F&{WD)bFRHK9%Rg z+L_Qkb@p*TCC5X|hY@EQtIpI6BHMs#(v+p@4O#OGO|ZJF(sZ^gAl zz^((w4(vK`>=WqSUBQvfMtEX+D;c#uJ|Wmgb588~D5xm+Nfg&~h+_|qU>hHH3graw zW#9d&Ngor^v`>fgPk|bj_7aW*!ET~0&RvgS zi(LnfU5{XkT?dZ+3Z8R%!lPZmp?B#_#!fTzCDegk2bwKveFn&~81}0uuG$FfI#6p7 zY_aQ?fgS6WGD2`is0j9JX}MCv5h|M941Hoaw(*G>!Bz`+6HjV^27+CSU5jQLU-)|P z<&0pT1&+Kqg1smq*m}>-O}uq3Jl9V9O&kT9oe}Invp2`FMX)oPeID(1qUDHV>xC1w zZifbfEt*}AV2fP`jvd%_#<4SkeSSivFMw{(6E9{i-5zvVo#8!{PUyQhszy^YI|qV%LFVU(Q^=0F-$FPrN)K)gR$m zUEs@?QrF|yuC@s5I^)aAt`R5h+QkS#FWLZZ{TPk1Y7JnT8mwaW`F%(*!At;$Y%Qe21Nv0yjmQ41XKjO9=i_IIuPu^ zuxnR7-b48Y=(1Lh*!2jg*ma=Ufn5iVEn0my=&}fQpxGkW8M_V~`##Vy5o~j>-bdL7 zj9CpLBiQ$H^h9y&y?CP7^(d$o+hZZv8N0q8WLY%39>LxVO!}AT(tAQ(H~Ooj+lyU~ zrX4tTAlPEpfnx`D9XR&j2=*R4F=N+SoDU=$R2+K@?ZB~X5o|GS5$ud+*W=jY)fvs+ zBca*Gl8Rc7OQ`h&;L3xc*5cKHT?bwr*ma=R|3J@Q3$FYS&-o{1JXGvDaO`>nThuxb zY_V$*Y%%SOUv8M~xV8B8x`bnkV6RCC zw(%^Dg*KE3_5^4xf-QC(ICd?9-LeV67P}V5u7D-C&~7V?duc0-?`kVn^BwI)is=Kp zCYp~c#IZ%YGmb5Sozd(L+JRtqZ9=m}u)8@Yjtxo#t{e!q8v4*eZM}+PgKcgVjvWYg zpxJ?A@0M_EBXdNsd;f)Ci(Lnfoe}K7uEnv(f-(==gk6hGkD@J_J-%3(aO@PlQ>?(g z6SeMzYGH_Dj{-&B8U#DAYjJFm>gAx(Scjm+TB%dOh{w?u*%rYD^WB73*CNQ>lsM{ug81C0*KXX z>ZsbG+6G}U7+YIwO9aXhmPX*c8Hq9DpJfH=K>N-(0sAE7k)28VuhMKMT}XG{AVTKz(c1tqq26 z$OYnbdEHvZ^Qt!O*5e!IaO`DdIZEZ&$!V5xXE6KS{lPrrPGSYel{Dv$Pjk9ax8lRi z$(D&7HeyGPX09}5$u}VKJ(fOGCvQ)E*G{`N=>+w;6S|VN*_E`-Zrb*h{h}YE2da0X zn=%zTm1lJG?6FXDE_8F;j$BmYJlR>3jgrc_leZ>ovN`^1^Cjysa*t4bH#uvvx>oD} zVD53VCfDan-cr_oHP!k||K>*Lv3b^ZmQ`hPwe6`DMO;cL;Uw(AWV$ zOVhYAse6eIlr>okx;}Su&i$`d9r^zCJ>`7==Kgml4YQJqVg)(tf8678x*flig{x{pdyMdmZ=#*sHM~?qJ;h%xBCacT2 zr>L30p8Pm@vGw}>g||MR(ALDsZ%y2_t5U?R^)=MSUF+A2e6D7ebL=^`s`=%d@t@4m=N*S;kI!>p%!hd<)b}2gU4G;4qs1DTCL?QC zeZEO&oq;mp)#mF8ACWfT*5vEbFIJmrGUvk^EZ^i{`MS(OT%WZoawDi)n-9L zmqRsi_3!!UXZp3w-Bq7;GH1dI-;kaK_4x2LY>Rw}e3R3VGor4M?RyUTrK{^|vv$?z z>(a|$tVsW?lg*s3&D!-p%QtBRj<$*GP0XvIRnnY(dqkx4&zEduPGn6UC||NZ7d_QR zq!>LII}I9r5}A_Si7-|R>B}~2^1%6$m0CG#vVKNwlE|7oaK2<`fNIvsC!Q}^F4hkl zS(69Pm#j^q?^XYrR*AgWN3GXYo|6X$%a^<=-K#|OZtwDGW+Hc0Qsg7gna%Y^Iu^}G z?kc9*tmO6i$Q_lAFn12mYu9qFzr2bwvXX0&R_mzGN3KLr8yPqgd1x=rD@HfYWkjfltIZ6D zyOgjwFTT1}HJ|;kWHZcTY$?keVLgmT?F%Ey=3#y51&H;AvDz^5k;h6m$L{piTKvvb#PM;?_08j<<2jD?noYc^akO3I9BVgS4da??ZN?UgHlp)qE5#@; zan!c-|DAb^YtuUHOctW?Zaw@*|9=N9|CeZU2W13w1fMxC^;G_y5AUhThgYAc#j&2V z;^lmJkDUoG^0Y+G7W2HQJD8!RnOYC2d0Mud56=uOIUk-mTTWv1n71yn;ys@_a^nq_ z74MWZt5@^k={q$~Ue1SS=9kFR@^~`gnFBB9X>ol}eYO_;LOCCvtA8SAi#hJjz{jZ! z$+_`PPu|qXhZni=B3p}VhawYR&Wfi8HD|?(e0Y%?FLJh2^WjB?JoB`e2~V$DVtrmi)5V)^jQbaxZJQscUFKD@|{7a3Y^PJY+g9C$f5OJu@xMUlBysu@~tz;mkJ z6j||Z=hwyRBB@#K?npk^$d+fe7W1@3hL*^RXOx?sTl3*X4!p?I61nmIoexjT@!$FI z_5x=T&wo1Q!y70Q-T|QJ=E-|1^Wm9sII`l^XTmcF-sTyH%`R-l;G7lD)zn(5wVCkD zIQ(3+s>p<=mXx)v&GX^8nz}wKUg%lX+;}IUrKlT)h85bDx$)GqYO~^<2-@-jw2D)b zW|8yZ)n>wryu-Em@QgegC?B3EPUIav9o@c~56`^AFX6Knrbx9@l5W*MAD-4tCYI&%Ac;NqW}f z%ZhgicbQ%IebCLb;$6!551~Pr4=*wfM^?Pryu%^|k0&3V`cz~bR?m8J^5Ll?8QDF@zow5rgp%$^q-R?dePnearH9&bLp`b>C{8!z$>t4W!0 zxIQ1=K$-B&BV3;kPxR_W@TB@2#Oh8rpgC=xA@2sxnQ_?c!@bnEq74}X7kP(s#^J#- z;YAKSHLO1FzMWzwyjl%QyewzMt7=>IS@A;KQmYC*>#Ja6cc5)W4!p>I7n)b(#uGb> z?87-9UaSKYcTqNIg}TQ;JJh+eg;~zEh|YE`$&PAa#u!4|nWF_uq6ex)(FhhK{^NQ^ zaWQk?iK901xv>HwmILL(Q%7v%PNI^yf;F~`Of#g6r|#{2D)(&_TZ}b!c{f9m#Jppx zd$+nH*9v;Zy}8`Cl?WZE@e_KF2imt)3uqd4kf^v`#KHG%702qod+Y!GeOt{vC~oUJ z%KL?cchfymL~HYUM%QKNU(lxz{tG<|`WK8w5y!3Y?(G?KS54&Io54yP*PSNU^654d zQCcy`*n21T({z8K*j=(At)VIDt=R8N&y2|JxP;TjdYV9RMQqLY7yGh=uUC9hKd`Yr zwY~*?5KUf|f;dviURHdExb%U*jCllpva9Oy%G{xjot;QaOZCiNb; zdN4c*#>bh*N&kcMsF|JW^G&)YOn-y>L`~x}X#?kC^iJi>G)AXSokH8#DKp0R(VjwI zm9!>9d-BN~ zEdN-E@mQHsU5_sJj)5vY%yQ-a&+2Lw_{i1hYEc!g7!4i96a6)2`fQ}-{SBLbo8Q;K zdvD}3J?W3;n-us}+-SCK3c&70+V|b$P%eN*M_#SFo;k5R3!CbH~jkBvJRi6jiP zkI~Vb4-DbB#7lV}BYimGtI2*FeK=d^x2f)Clsz_s?PC->7>P>^?y+$Wi(QNAGwbUO z9c%}qymwLL)DOQ+WY!NnA@5@(s!;2<+0s5nc?Y9fkIk0%G3xKJF@M`Dzyn+vSM}Ib z_c5yV+vu?g?@jjGn1{c1AEW;H^|!Q-QS4w8nf1eaQ|q_M`StsIY+@B$EuIkGoABF2 zPB(Wps_tWC9=9rzFxU=88BeJ7+n8nlJZ7otZbns9p^7Iw)(%G5Zxg!~ZOLO}ez%>H z$7V+?`6`~^u0-Z%Q-0)qjABot!FDrx57+-s{5FrzW7B^hqpkPb|j*yu`&Bw;0c56 zW+a9%_?||AB-HwCL=|fBgxk=vH{ZLcHk*FcS0jdy_c6LXd2C`gqsRvrdl%Ja*4GOZ z`Stb7h$IZQr_ooi4eIwXatEWxvftY~(0Y)6?_>1ueT-ti$p4*vjQ(%Qu3P1RQu-kW-lO|71_HGZ4eFH-N#V|i>s!wSER z8dmIPRNX1kthwr3`dN1Pmk%fOtnl8%9+BanAJ&iWs&FGBeu?Y<;`)%AQ zaxlM5b-zfn=Ds4u$Ls(#UT#Z%8#N~*V+P;HsCK_d_Z-TRFG zv3F$FxwgEgQ8jmNPx9V`-zIi5imbVzZRxS8-_7XB^4nB*Fp52mE(D8t?0t-kugSX^ z4YrSwyB1xN?Co0b&6f8u8hi(%@YvMu8u>mjC3lLfdTh3S2O}eCF6Zv|p#zCleS{-p zWd`2OD0VOk?@f-3i6|NE|Jd2cD4CBC2{YI}MzLRH=vmd>j2>$rqb==V6uTVN`f%JK z(p?{8H=|Ede;WJziSJ_+J4MEBMzK?*$Wh+G=&}7agYRRsx%VdfZ3f=WC^Rf_nOhPr zllL*I#>eDcBdb0fb*{m@H&xB6FZpfMtzu83?6C>&P3&V7I~aw|6&@S?IXNHi;5!(( zYh-l?qwKd)PYm?P?2+0bqE9{0t-+~8ncQn=JXEhs$?=$kruFyO1U9Jj5OM2|2x=uZ zrrETSd90hZ^O^pip{#falhT7el=Xczplg5x%d-zrLG9xCI5MaaaWs(7Ioh-hI4PZXVXHz)mD z&FNSlm*@N?es5#?+^fCE|6B50zr!eFpY88yqvdz|3;Zol^!ManVr;a(Vi?a7`K<7s zhVvcn0Z?!}BKGoF9c26YD>QMuTm$2GyqV0S*4019cJPofuMUmw>CcXMpNM+Q<+Pk(16{laGI zBK;26c!&$OP(){4O)MU3|Ck%d+IKEe=z0B!BDY>uq2ByC@tIHadhdShYaUO(#0c?y z{y+BK0_v*jTOVE>hwkp~?(Pl&>26dEN=i~vI;6Y1TSUZ01ys7byOH>w`JQ_QFI-gg z^LOw4kMWK(=CjtGE6&<$&plVqO;Qk)kkE4>nIp*~86?@{K)Qn{@X=m%2_H$Z1djH^gZ?WHh-8EQD=vs+gZ?XC*uT&Ye3B3!CL8q62|y$pBm*?V8wnT) zlMtHirDsp~Nb|MP!pas6WutqfvQcTNoK&_LVWpxnQ)yLLIjL+^S}G@%jY>=9q_RVZm2C8V;2%1LEQ0HT>`Dj}UDPk?d+XU0h?UPm7OtvLUdT+!S)$rQt# zk&Yv2qM9UmqkE*MOp-?RPjX3Gl4Oc%lH`q^f(fgCs!x)%=wUTTYx|^qDOakwcyK-H zlEEh8920FL(h@)A!)+D)=}YQnA#JnF$b6GhiZxHFSNQs?GQ;waE*>+gRE>& zi$<*(wN|uyBdA@e+&z|LnQEN``~dOEp2-GAO;I7fE_U z+LG1_NqR{yk~CA#;8imGs{F&hBcZp0@(=3azxR%W@~5Zv{7s~{@4uHneEy-g@8$B7 zHhcai#=x^AX`miM@LeE1PdU@Gq}rx;oa&t30xCH@Mf!KDnecs;P&vcvia)C7*D2@A zy5gU%X9F3q2BBB*5seQkEGK{vy+Y|T~BpRx}Vwvs&i@$LOlU$C8&O>{SWpB zNLr|tsXsu{LiJ1i0lFKibLtP!-B6uVe}LqK>NhTAf~19XJY5IhslVI*f4RR+y=&Ty zKz;7e_amv#9r_{{y_@unE-F>9k4^Uy{QhL<`;^q@4t=+h?t(1mP;V;O$EJG;^|Yzy zOa)0Z=ovgD{!`o1PfG<{c-ti97$H%W%6hNIy+y!`)F zKm2w2&oB4YU!@c1DL?O#KJSZC%{=dsKJSYLbwa2|`n)e1UMB>5dLhm5>b@w|%yZ2^ zb;@!7)H0G5q!D1K?-Z2t@O>vLTc`&`5=i|hl2|I+^B&ZTeW!m*Z~tE%(*@;?WQ?Tl z#W7v5mq4{cZy4!Pl5A?fNJ2=aX%t7Ahjb1}#D5>tz1-jUBOU&#`k@@3k9>!e&Sz^dH<|_{%RZ)8UfMxjM|>yx1axWy-vp-b1Je#J$|o*-q=jhSBzSV4 z=E6valV%8MayrQ#`lci4box3m$qdPUVi4(YlBgsg(%z)cLtj27%^uR>q_sktoHRRq zEtxE`g}$Op*3Lp-SEjvI^wmo0nM4nh|37P+Lah?r5w%jGuS*8+i|!@(&E(J>g<2*0 z)^hNU{=97pwMz6YXPOUsRofJ5mFRBhzQVUnuOkny6DNGT_E&Nek`Njbgdej|Z9JEj zD0pThCojqyNyw|lq$Fw2bNlOgq0o#F&0W&?=iiza3Y9rHjtKR9UOiq5U*_Pwhk8E$ z**Qj%sOK|{&*vEF?RY-Z`06>v@cNeeJkMLDWUqW)uQOJC`MFa|7ScJSi)hSF`iI8b z)UT#?kLsEF)uEP-dKT2i(HJebLzY@LYWWO!G`gm=^iR*{JYVi>y{bK>{6np3u=oDF zJ$;=#U)4AJqj^G-hgbE@LcOx!7>9afq1nRV3?Yrz{-|#jnjxh5mtfzF<_)PoL9;LP zemx&e(>w7xV^ylfSIuitJ%t}rQ~#6Z$Z4cUGcPp%LL)u8N9sAyJPpm)P=A5uZ)hHe z`tLNaL-$CtJk-0P`5w}o!M-T{3(X8sTM(3Fx_6p4qP8G-zd=c+u?Y1*sYRe(Da}KX z{08TzXm*MunA(Q_u4i6HZeN~%ejRxTuP6U*{J$z^`1UubTY_^GA*~XcC;zMGPWe2a z5qkA}=AZS+|0@6Rb4~wb4&+ty{C}j+sUDus_S1-rw?Oz%96AW6g1+fEuj68ynF|EpF#{wI3- zp>>(y{MgH5;a9yERDU6@8+`9VGo{bpyFZ%4e0gs0-x>@58+tpWv1!(xG&s#DzO1)H z8k;{W7FCu)gg@mgW5Z&v8iTgg(18QQ$7CGTzY6+L+{}0$l-H1E>&Ec?($|rt z@bUlY`cZJ@h;NFi=+ZuihMeRnYZ4I`n!7)^*ZKc+o+E!}AX)H#q@T+8=_*9RfJtS27 z!T+UE8~G@A>J8BKi|cE_l{I=s&qwjEnmhWdz8~fAd_+&rou2iJdpxL&&wGIM#Hnqf zzTS&{zkfrnLJ~#mCnRAZxuXAiE?qCm)!%vV=AUC({hJyQOmxt-^w`t!NO@G|x)nS6PS|2lF06Y~K7^nb(8 z=hIsm>1mU$BgqV{^pUQkcOj(lLMweV`X;>>4{{M)*$b}p z(KWr-e}4|)b^A#F_WBXs9qnNVt|G+e-X_pjL*SKyY^{?USM%D8a9l&{^@| zKABKE64Dz%Z5HY|zj}W4&-%=vd_p})Q+u&3 z`>TBZ=y?V2D>VD@>NSP%^Cz!+U*Y>g;rsTX9uM`CUPtHu)mR|d6ASJrquCCUKzdRy zj|KiJpI{D@8>OTfL2C2qi3j(jkv!9E)9aM^b>jTh^9oUy-6bjD(s~}P>d~$f+8;pcF=Xk7@}ltw?G2}OL0TQ8l}}nPq%~36+d}g$wBAEw z7Fr*r@d(Yt&^!&T57C%~?u~RY&A8KiJgr~S&P=Kc>M7FPJgsZe>L#t+(t0PY>C)aD z+M`4DPJ4D}?+)$Yq5T5k-xu1gO|1j?)|J!Rlp;exLV^8?M z-G6wwAN8vDJ$!#Y{P^zA-uHjIJq@*_w00ES>-gW>)8HO^YE}RH-t|}ASNQhgkJ_D= z_0QkQCw#m7vW)#xS$(;Er#CIM#u~ow7ycdjJ97mznh(F;`d97I>$YpJ8jFP=6TQ60 zDbzO6{n0(s*f%sULFcIGY)kktV=#ZJ)mQDFdcM{`y%N$qBqgD>2Fi!lglVONMrIU3 zdre6uXzhbeC(*Nv6jl=I&(PT=YClNB(R>xh70pxqkv@M>lhbY$((iw)&tKH!v>S%> z`^%b~_Rx@ie_4~$ZX43?e^;OX+hf3>ZV9b!#K0YJ)D=n8U!Nlj^&VfBE7~ z&GfE>*AJn0?a%g9yedxUeGJVL{@r&xcwZzFWE+euI;I1qg^e(>P?#P>_8Q54VFplo zeA|WkNEtyHVDF9IsZ5}Zu>6)R%>EnonzEpGMBfvlo>EpI*(jo(QZ^vj8KO5UJCLl* zQLiZnkgWbtA1P;8e<>&Y^gW^YxXu;UN6L*hCmznJ$HR4=us%{AaOg`y)JMt-qVEY& zABnzsmlsxTsEw2x6VilbLG(Q#(&XhpWnqJao@{wgIam!RjamUz9+uijYRDdB1zgcH zB1?v;fvLeEONQldq()? zFP<8G!L_lD_IiHVlK-4YNTu=^4=%8_7~7Sv$-O zP8P^AJtMMiNVYD?+F?d;GC}G!d>O)?TKcf(MRpA{;4Pu&Mbl5&RA%eT$X)@DcsPi2h+je?DUT6*2yb z(1-tt@p8oYD`NZ=G5(4ee?^SHg5$3Uefa;DK8$!?5zi}P{VQVqE2901m_LkIuPhn1 zA0VPXAJLzW(1#KFFhU}QMEe;BdnOkl1}Ztd|r=E z>IFw(e>^`QI#U_`)ZWYI^};_XI-^JP8_|K$|LfEqo!6t&d9U6z`cKa5(HXtas*3rq zlX?cH^yvIvhOjew!Si~-vwL)EkIw7SJN5FZy%*2xk!_98w;Sk-o*pL>Jx(c-%_|3_ zFMravRLK4lS;C@ktdPwmI?Eig#YCr_LpGYoPFKiw6WNOi*>obSk|A49WD8V;of)L_ zgkPgPF5vI(#Y-zeN#2~HB~ypOIH8rtUbvXSpy_12_#))m5|Qb zlf02tO0u02{%fjqCX_6r(8+7Ef)cc+MNc#MPd@Bv(lez03VkJqo^$BSgY=w3Uvs19 zOtypQ8Paop@jHg}w1fW_v=c&B3^;zzEhUfzNV*HMWe~D*KsF(R)(=AG%EWA#Q1n}QfezNQ0QBFGPPj+3Nmp>XfAsgLP{?K=+sP01F)1w*@ZVG#4Wv@j*>|$hKxL;gQMswqAd;wrI_Vz%-k;l?4E#s# zg)A{q$?0CgzrSSFj3g@#T(TBPw)x01AK9uT+mU2Tl4^)-`H{^Vk}j$*k~xwtvT#cE z_WWCr;bn~MqLSo=q>CgiXoDxbZ5)y~sJx-4AJQ;nO_HoG1;5=KUJhTUPF|D{ zsuOB!o@*z1r(e`dR3|TLC$jJKI(jK+$(EkO|DK$Xg)6dONN;6O0|j*wy?ta)lipDJ zZU@WU#6GntgscZ1e~RM zwN8gKlB@M9xNC5g7MK?2{}&_961`Th(P`LE@GsWuaFvGr2>(xdJ+9KQo$&vtv%&hn zPQ3xVH0%dl?bP1`f6yDjOT)f{|9kx{@H?HIeXYL&exttzeyhI$W`mp8Z_%4|9=};{ z0_KIA&wr-30Jk74x6k7@>D-`=IzRaNe15-Gf2MOGWFv4R{-uEbTyNC{z|Zenz+b>O z2e$AzeJ-DdHH5#pZ|Jw_&vhgJh293-rW^Vk2v5TrgVV@2_S^Lrx(TqcZ{oky+jUc5 z6W`SD&|m6iz^1;L&jC9O&HPt-2RPZ;SGoZ>&3r-Rl!ldqn}$^er-82mtn8}-tN4H{ z?2GtFz<`V-3;Dv{%YZBbEaHp$$lyehk!5*b$U9lo7Xx~@QNW2TqsR)rypIZuBBRQR zz5@J}d_`|%F<%_$;2LRVabR&@!fS*^m0H&Eb>Xk;>jCTe`oQ|WlJ93r`!c@2?Pm$g z__F?E+ustF_2qnDg!Z$2Z7E;c53nEGa=>!9qdwsDwS8VE|8 z6hDZnzMB6*?1cLhI6sQ-!K>!K2UYh!gY%R4PE_}A`0o%>-R}bDXYnm~Z}@LPHT-UH zc8PDmtKs*+zgzqQ+#?=?SHnLRU&DPY>Yzp* z1oT)u6+3YC6!b(q6JO%$8R#jx5MRQ_{b{0#ibM3W=za2rjI zv?G9{>`35fI|?|)js}jkV}RrASm1a&4*01ZZ|k_>b{H_49Bym7I&K(nnEk}o1*eXC z(|uxx+BaQoxb?uP>uR~7c8INokfF9dIQ3k87hgt`HQf+9*w#e&5ZeHp`mTYCC*#W+ zuBIDo8^YhfHFR-hJlP1?&^2;#WL()8*vK_@v1J_D1lZU$aj|4fJfjSXS>X9;BLe?#C|h-%^`Le?g{p@*#+D#eg^JBjI#*e zYtF&lYrbRW!f>zIXHFu{3HB}fj_otwg7%wLE~bnnSD_?L+$n^fWZxiszxf7qz%^|ZAsaCm_E{2RLcd$d|u-U=Bg8L=g!48`h;IDKmTyz;jE(fk~ zQSAwH(nPUQ?MV~O9ycd|Crnfu9sX#*W9GPt0gP^A*rVo{xn_>y`Wo^*0{;9|>s{P+1Ms)&PyQKx-Y)S#LKZ?Iy8StP?lPTF_0ytw7io@HYduvd`HXgx@r4 zK({cc|{Rze`G%ae_}ra ze`dRYyV!2vZng(_ko~}xBA;b$sY@Xf$j`-n^T2#Aw!&Qk&QiC;C6_7WHu1nbG~2}I za2JEK#4UEoWOBI(xY#XnNo6uQ4Y1Me{BBA_HbQO=y zhoC2BHbQ5)+3p!?xr_KvJTYBBPfcghMG!tU&&(Wz&USNLXYtH*5}m~yH`jFnb`+h& zTsIHyT(?NxR>n%?!yxTAF<{m{yeu>9K_XP&?2z_ocV4c zaDkf&TqZy@GPP!0E$`P%FkUx5yYZ_RIFFL1B;#(ZZEiQmL`;CyR#n1d+O z4)c{c06c&)?l6nR5^>qKa4p?st%1sv=%tkXEq0__+vCgbF zGsJqc0k{F&nPRP3XJ&#wL(GDIrr5@Rw~y@Sd>emczu=GU@4(;fHog_t5A9a|Io$31 ziG2)wjIhu6L;JvfhVX}W6Mt%-0G}Xi3x8nm+bsxxU^nt-_9^fw!Z!2!_MY90@cZ^B zHN}m0KdZ@Z3UG@1N$paT++?>4oS)T?>L)ec{RkT8Hef>JncaYVHu6k)@>!)K z^R;G{h|Fh+*}y2c(ug0MuTg`-1CWI3GeQDxFz5$ z=1X}u*WE1zX9>^AE{V$`C%Y`J0I!Ivz^me#_!9DU&tAvXHBnLy5^GgS`LP%P{{S%% zI8Y1%4iz5**Q#|0U8mLq*Q*V{4QeBBquK=Aq&5RLt1YU8+@d}Mex|kpx2n&9pQ~-a zZR!i)7iv3jyZRFNCGNk3EQu5)AJX^>Xstx;y!eX)M7PRECNjtx7A0kr@O6sxsQN7-7R%P-BcgCB?w)tmZ(W$vRJ65 zi1ENhaIYh*tGkX^AG$lLx9bJ$g_KLxL@`M$RSvbf6seY|1!}w)Cl;uMaPK1K9d%dr zalPF#Wl{Uf5Ob-zrmm~5?i#2Yup4TBz8Wiri}`At7zM!-?OkatqS7xK&M3f#Tm|EBh;kKF(_TwP=r*l@%jrY<4Y zLVigt;PZhC`2s#$jTEEAY&8dNDfx*Q3LGXr0ge`9fMdik;84g%aalqRcEx31*ALjw z^#=}eeSw4BAU8r?Vi(y6{1^UD&F3@uMf}@*z7J*CtM;k>?qfGg%~qqtEYN7NUlo`A z-G1=*sS8LklaE9WBh*Ya8vi#_&4N3NUjY9GyTnGS^N2Nzk5V__KY+CR)eOWfC1>;V z;9qAq*eF#P>nb-yVbD$BO>s+1M=aclx{lCu$YVA?h_naPm-bu!9p7%hw1nUB@A(&Y zyCwXdf5~?s^h>+Le#5`zhY{BpRerK{2Tri_&e-2`z7A2ZT1Ve+n~Yk+By6j z^1sHev(f5n#6)cS75|!lj#zi?=b$_GFmgMjrXs&m@(#NQX}`lBLhg@%e^^aHNGZ7$ z@ow9#NO8x`rW}Af_*eWcV%}kQ*#q%V%&~*`4n7C`*>*1cbAW^SAbyYC7Z1ce#JS7n zfiu_6vqSh`ejj{mdBAym2C%q10{#(o6nIn}10GYyfydPe z;0bjScv77Lo>HfQr_~wY8FdzT7SFqwJg4UH>BwmYAI3l73+))tBH$vs7&r`9qxoXH z1ULrnD89rl1&)S0k}tK(fTQ4!;3N4m+tshL>+OfWt0!Di-`%gVYwc`Pn9VY?O(9qWooQy_Y7YFfO=rK+ZnB+y7q}e|v%Bx$SKBpq z24dV2Gt5l5Gt4b=#A)r@_~mwm{TOljnWAt^J&0haNGG2ct-8;?`{1+{MP{U7C7zvTYfkn!E0Mu8-CN)wuHs8 zLR<%&+P01*dtSBdo3X!VwWYAeT+`OFMS(?O)Abwott-gBa|K|#^*i{! zb@dRZuB~TFVO1$98)ycZuiV#gzX0cZ zx5EuGgUt?v3^HH3!Da|>2i&~Kvz~p!*08zQcK4+lVzz^ZnmBqmf6K?wZ~3=BVn#3pbdulRr>8qZy zXRNR42e+?!hNs?IjWy#;Yor~b?yHG>62Fi5_f&Kp18Jk{_xw2EyZ$}j1~FT!HfoF+ zYx=0Zs*KEs+RJOJqwaFE>ZrwBY@5puE4$lJ=U=!7Y673gA0W^BDw-bW$NFeGI^4Eu zv>9XCBA+&@x9Wp@cDhf@FtgMB0QaFPDkt!VNc%uV)x-S=A61X_!-3J@wo{|bXwwck zv{k*3x{QpXqv{d<5mG%=AAwg!{^)kPVdh8Ba1$9}BYk8Y1@7;N^GNkXtTOT^_oEwb zegcg!k#uA|(nkV~^1ryB+z9gvXr#%HyUS;*;r?>7&v9Sd+~+PI><9;RBt6OpK%@O0 z_lp~8_JBqiuSfea-s=F|-L9Q_OYL@}P}be1nU5B4Fic5C2n zb$MZhc&l3tcPswobGH`UHEx%CTfL)px!rKrfwR`FbGfm@VLfo2`x)Wys9)i}qkeP0 z0{4R21Al{?Qg%|Eft^(sU>Efv@I%!V*j04{c2nJf-Bk}@57bLa*%LKW1Ule%RRr`H z_*gvwK2cABPt`NvGc2eT!9p7caxH*DOTEEWLoIDUsn)v!sJHxfqpOO#+X(&!ci6R8 z@2bOYFWgPwZ*+&;yXrl4$i1iD2Oh@NX7D$;gYJFxfjWrr_f-|U*==!EY*n}i+y||j5{pR+>{?;OI<+B5bn-1ByjAMDQ~^qf5nUSf6uob&dA9q0%7i*|q? z2ps4y*i#5k%!&kh`QE;8pttV>ECRP^;3MA)*vl6Q+{eE?aD@VWd|zKE(AW0^7RFVv zKu`Y>@FT?g26>=v)j4L5!z~3)$-s422{9`M`uYC8VxYhO82GUt036`Iu@wV_5K=8r5&vBc z^sPN=ld^lc>CyqGhxr@G?YgTPs22FvRt0@$Yl#B3psgutiGub` z_-lz8@D;K(L`}F=0^iy1fmPww7NuDMU;)HSfqzI2``}0Le>aim4Oh`tg6|EaE@The zBQ^!AgZQ;Yb@2u`)j@@A<-qs$2VfPrw~*qdtBg2xL^Z@JY*VtsNL49NIq-w61lnnD zBhD>X6=6keRm3W669g&+b^>?WA8jhcPl+8-hwy(@L{(A5Re$XDWi2?}&KiNcVuiXdSXZHj5+XKJ@_8{;eVkbt7pKanmBDkq!N7YHCl1JP= zmkRG-N|{RTgM1d2r2}OGg=LvQSzy^fIbgX!d0_cK1z?3hL7+vA7sgvCbzzVKDy@N9 z8=%ovrwk+x{A^Q#cG~3I6xJTU){C5H5R4|Y{u-opj$pb0i))Pf- zF<@P|bNwB6*Uj@4aPRZrpX=xO+wP8=vB}mBj*k8c;#r_KX)&2(j&F-}c z5SkEs#gYb+1!nkiw!EEzd}jLkqMj&b>w}8h_$)~vX&^r0Bw*7KXNHf*QU#I(;<40$ zRKO$%8xQ_;AD5*Gqz=RdKOXzkm$l{Wr{ItG4McHU!Zr}~;U05GQ8N<|`l*k@vIf!w z;viLAHqn={W$i@pC-~SbOCW0?HbUdDhN6TmX&Z_La3>+oL>~*Gv9Vg5Iglj~6G&ez z$`r^PXe1hnlC}}3lx-|Z+0wv9a9fMUqO^^HI5Dw)oH39o&`PuhrzNNiuoc`Eq6~6x zAzH$1E++ZOzPXs}rvO{vs+njmrue3yslcgz8n79znuw-inr|bH`xC%v{y4A+-1kHq zal*d~IthFaZhLXkp8~!McM+c6HMakpF33t*pRn6eGK&s}dg*xZX zx)uI{y9m7KE&&(eDxc1;(*^Q@(gzCbLNX69Z=jGatn&o&2AZf-xQ8aHsXFPJfKIuV z$ft#Bsm{A|t_b2Iw$7*12l9e41RAR*Dz$8-uDbKC72>p1%l!&}$t6V0B07)G5XczF zgA^G8jZ|aAEUB)ztF9#Cw^E4^C!x-*GX`R?+=!boP)c2PS6nH?DXAK&Mu@-6U&i$^ zVx?c~%c+&1@~Rj(MMVyK%pdhR?HPX-c-Ef-p7Y0m z$9xW39C3;|e{TZLjzAfGnx$HaQH2h}}FS|YJkNE612i#SDr7y2mfhwpH zNL5_qw(Z1Qz_-NPz_*by8&Vwc*+7SVNyI53N{VvWv$`6oE2!0=imDViB}E?FRj_sH`XgPGM8TRA&e=HBDJj15{3Q zwwP$+V4B_EIO<1jQE}S z2Z$S;6-CZPOi@#f;U7#5Q%<}ADlfY5%sPwig7}^J`-mHzeF#n${vpq#GwbT+4O3oJ z2UQSNSvBNR6;#Z0Md*jTE6=Di>EhrOGu2FWQ$cjM^wqd-w!4kSy4r5Q9^iDh-FOC_ zQFlZ9uDloi2mfNbBDAON1%FS(>0zs|s;s!_Vm}1`Bk+6Lj}iAH8wd9o8(2UT6me`p zQ3zN_6c!nA$NPOo&^})uaX+%1Z5O2N&p+n%Z3EjM*a_EBSto=kPm`h+9y0l}ZEX7hKd|(DzYkE} z$Sl4uB65oa!1z8PFoCa#vX?RyL8XDEO&MSrQx;g(lmnJC;;CuM5k9Z>Flh7yfl|&KI8~@zc_69Yv0ro!rJAi+V#1bPkkx%R^ib`U$UyFK4 z0)Jwk#8(g%MG{{P5|YGMg{*j_qFtBo+V`wy@7eclQt*@bq`r!&Y6kG$yontEYHE{# zlhh~kl}#0s9_8BW)B5;6w{S>{ud=|GM`Q&rx5(o2h`hk8aFZi`GN0U6GL_9hK7cp1 z13}H~ySSJ4cxInhzssk#Y3wfefA+iK z-{trCR5rEU1OIOS3;cV0X7R)&v{`_eMHcbcJ#m>tW|7clg+GhPDt>p5T}E6dvKd7t zxY@)b_q)pmepZn|WE6>PI`Pmwa_PX&Ceq_Nu}zPVL^iG5g8NM?Kl59BTKTpA2KbHt z7Wl3I4)~q_9{9cg%omUaWqV#gHs#HL&3JQQbKU~jg0}>=u|=J@Y=w(ydAI|e+&2)e;fEVe+T#uZvw1?n#>`xizGG& zD5>R$j|oB6hPUMc$gwN4HE#od0oj`86iIC|n^WX~t3`5~0+_-oA%%jQOC+<&fyu$m zC350QfSVF1;c_8FO3MTf!<06aea2JSU;H!tMJoH0KjXjnr=TBv3L$(tkwQ2x{1g6^ z{{Z~KZ}oXiWFN`rF?kJPBp>jNbO9+?V_+j)M175VEULcpU;Co)7g4!Q9ux4nLEh&> z+Po&8iQ*&shFV~kXG7fxZWE+!tP86mDy=Mrv_(}hwZnhqQ{vxKhz43R#Tw{_aGN4# z6I~pk#Z)0x81ZwN+{XJ{AnEfX=X@r=iRz>H`dTr~>gxt@n;}(GT@WeK$`a~Jzr&Y6 z4#iag6W2%e1rR^K$!T&K>2rdVPlf+YDN+gRoiB>C&2&9oUu%|BZTDaLq{yL!DxeA? zx40&bkL%+ip8_Ta@=!hpNc&<)RaDnSI?a+HRZ^8qec`wJ{79Eprbf=GL~3EY_3=z> z9|wqhOm^g<&vm$O9@g~AGD~XsTbRLx#ang#c;FkiY zq^_mkL})_9Phb+77(S-YVzQdFBDu%{tch^VGMg+Wxk!Z2geH-R?qm2Gx+eIE;ZI}| zn`l0|PlDDa8ZeqqY?6u0h@VVkGMPIjJrBX@3 zPr~DYmrBJ0rB=znNy_7bms-UIrBQK_Pf`(AWH1>`a)c)1ad;Y)R>eWAG%5u+$$314 z#uf2IdXvGVL3mn~29!?42PdA0FVdOxCM9B~;0fT5FA|8fCY?#k)9`dEEhxQ8h0v5d zA@~VILXpNGoTpbAR63p(Zfb<4;^}z?l~JYV>EI?3sZAP_2r(0itO&`dvVtieeqxbCq%^5aI++L0G@Z<%vZ{14tI7tPo;$x-zh`t^zE8 z)R}n}JCq|q^>SKiV*Kt)m@RNX_SoK2OZfpSfAL}?OF8IyiAD}3bZ6X4atFpaaDqI zB~%Gs5^fb9L&OwScuWxs7)!(k#ui2t=OwsM8Dv030!C7ifss`dU=$S<7*$0BMpMy& z(Nzp!3>6a?Q^f+t!rf+&v2nk7@swKVyr7oAmbw+Nm2M4et=j5B2^3wo5VTgf$`wRcBOa`9vf+6xx~(^fJ*F=!0paH#8c?b^2+wQJ8Q4s1-`4_1HPx< z2fnXA0Dho506XZ8z>c~Tu#@f#?5w*0yXX&fA{RhCCPLl;mCz+}8Ds*N5E$Pj09MAo z$97eKm4W4X1zyEf;H7v~_^Y`2x)y(v&(m-6%E0+>=jw{QG_Vq{2&~L20q4P8plkA4 zz*>C1o})|iGJKAn3wI&-3-m%=gV*HMTsdAISRT1A0%xIKq~G8*_-v#o11!VK@`2zi z(gSr=5lsx#(Zm~kmY%K40?YDpd=U5p^&lNZL=`jjEM1Pz1XXi0bv0Mr4c3uFWHDGr z7Eypv#2`IGS9fo?8G0t%>G};<2{;4p5FHSa#1O|fxomX>&EHvx-2+lTsb#ZkJIJADeHQ$Jov|AZj2tQi-BLxB}d*F zWp=n3Wj^qWxw|r>%p~st?*g;A?Cu`IGs@O7H%ihhu}Yu&1DPl+kxL!?gQr`Ftf|zZX#AD zSr+_uvKeCK0p^iC*nXMGWp?`!XP>+wZz4`P#3?JABD@DXfYAN&fXwJJx$6keB+DbT zoNR*d9_*mZ;4->{2t6RL$?FJhjF29z0^*dHhY)%YnBHY@R}r2`Rs_F-Y=l@n*kSMw z$$L7t%jNFtTrMZ@9^AX&+|ze;9+%ra&^cWW;C;Avz`3jM=)5kEd#E4i9Kakdg}V*T z9erCDb$Q(*ox-IAK7@M9tAT@lxl z)s(elPu2)!>&a@#H{pL%)&|y=b%1qbU0_{V4_Hsu2iBJjfDL3rU_;#16a84Hc27WQ zTx{eS$HX>;Twxar7~8}$1zjN*6Bx_HGzDBi7Xuj6#4!0?0T&$@!$ddvTz)s2rFVzr zXqL{UhySoVB1f^&jPQs&D#w67nvG#;T{<_CjbcaTNYF7kmZfoN-B|F)un}w|J0?ef zjsuU&6Ed0^t;gtS$UnM?X2$4zZXA26pXhN&HI|KIPjnhLoSl#-<#41vA)}g6dbEy; zRME_M_Dnz3;}L%xo6XM43vxEQATP>^Y&bg!JSk7fC}yM{rK2EKR5J^)F3MS;OL7k4 z&t`MjIeA`w%9wekKSgfi*-UmxUY0Z2EV$DUI)_bTXXQCLiA`juf6!6G@TAq=a-8C$?^`DLKnz}xqD)_al#Hpq>@XW;t)3v2{# zl$&Ifz%q8nM+t0ZTUeC97PgGJz$Up_x`2nz+SR9u(#|3>?8XE`^tX6eyFLa_?IYwsDVvvGqV8~*eoq*i!^~P@-v`? z8x5gR1JME-*(Mep7%i|&W|P_Fa^Nz#6qH@AfPcAMf~)LuCHyPoVq9gHtKeTLM*vsJ zMc`$ZBjFz*7vd_r{E?%M`44<2+@C-{@=*vKDHk9-yZkwfyNiE|8ruc`&wLmE1~qsP zDYDAZh&f8mN8IdkH~72wZvM6WM$Q8-yBvei(ee=DWdk0ByN7=zzXpDd*ki#RBj+M+ zc6pc|;@RW{ei%3hyzKH9zC(Tm{0gzp^9$hjW;yW8dZV^ckL-Q<0sJ4x4!{nwBe0|F z1neX`13Swuz%KGb;D@p+u&eAQ&mpI5@>l+)+yUHy+|TlJ;50WIQK!w#2DXv4FwIT$ zKnqZez;B58EB}pemtV?e2yJefne}V~YiU}T7=f0cn1QC?G&8MC%s{L_E7KD08RVKx zHUYn>X=2u~^{lmt6^I>Zjaab)d-)e~yWERBf8#9}4~RfZ76@=4542#-nFz>0bJhZG zW3!g6V~vqR6Vt}T4#WwxF|FaA=4X(9D;6mb2()661Cf9Mq;JMB{0KBd9x~7x{8p?r ziyw#_Xv$PT1DnBZi=5&B;{@Uc`Xc|vrmtDU*0Ltd1U{2Zm=2gg6ZV0?&2HLNlF0(a6Fskh3;pwEGy%Wc4I@(bWzzK=Iz?U1Sw za%jUEvABVFf&ECakH2NwnMSNP^66uGn^kNzI{^NE{^+z&}II1kRMRfV1Rm;A}|GJLYZV(B8ZQ?8rWq6J$p=K~4ltl#_sy z+ zr_cqVoxwlFPxB9fUD${0BtOOP;$9B$4(upD20X@(1CR3)z!Ur=@FZd%;YZ=S$d3RU zvUg2;(~!Mq-UYsI-UGHr`D?PsCX%ViqL|3QZl)`+yXgk(VY&l*njXN9Oiy4h^AT_* z+?s4TTY}(GfgQ{T!1wWgZz80td6Ru;x&XVH z4^4f9HemHxN7KR7MtB!fk99H~fgKT62iKiV9abA|UDnxj0(L@JU4(QtzvxH&4*ymE zq6zQt+x$2Et0uh7Z}C0)A%6sX#DCGd;ok#%z#sCx`Zs+Gc#B`+yTIA4cj^250pF+h z>Px^&{4)O;oL%~7eUIPg`}ID38F-mr;Rp17O?ZW0yH_;r3Aac=0t`Z~YC59>p4uYq%2w`G_0CEyi(8F*D+0bbKrfsNs| zWta3t-46BIfwf~tkiH!|s*eDV>7&5o`WWzpJ`TLWZ}N8Ru)e|H0;e5&i=EUb^ardh zy9m6X&jT;&3;J#F-(qjGQ~IQSpMAj21JCPo`W<#!p8}pjjQ804?3{iVF5x+SR<}p! zJFGo>my!RBJ`Fsp&*;SLHcm$0##yv9?3Nt_Ow6`om-sE5o*iU!uwQU~q9PlqYl5Oc zZYr`7dZez%l9>@YnMn?;!i}K0w$yO9i-S1FxLurK2XRjIG&=)4#ZKc4NlxVSNSwvF z;YZ>O&JsTor_CAQDRUZl(wqVY>`63bk${nGWME_)1^7sK8?Z)B!U^F?b|P@1odBF* zKLr{&*-o;zO-9%gxCOk8Q=S=Mf8Y+zZDs;yf>nW=COxbW+yws?&Tif@nb}=X7Iwp= zgI$6f2)&6@t7&12;5s-raHca0YzEvz+$`*xNyE|t(<1Cwgk)t`!MTR>zQ4l17j9N| z1)QtqGVlt{@9qUB8_w-!#p&FACL6m1{$-rg-4Fjo_%GqK?g97@!Oh09d&GktKv-m zSyKTVI)$GG|5VnWLEVGZM2v6bsFP*3_ zkF)#5{7F+Bbi$Ot72ye-|1If{9!8!aK ztQztu2b%_I;L8I00y(hSm<5;(D~vhV6aEIy%RdG_!TfR!oR@#ftNTX4Cvbn~HE~k@ zckmx$1?4Gkg!L4%fbaJ-P*{PTJSo)HK?|441N==b+U0j)C~O6?5jc&p zqT2+VhBgP*Asd3<2&=M9!D(P~!p1`b@Ec+swHY||!D(RY+gz|A(E_|2*!P_aEB!68 zN}2;Z&szeo@m#*1y@uM#@2~OPutjl==YiFVYdkM(T3qA#VC&)=Yh$qH?hN=^mr{xn!T323teB!-b1@r%a(+8rFrpE za7%znVs^YV+~Q%^WpQM{uG=+@t7-{ix4m7afjLDdEhxQpIgii&&TN$D<(mQYT$fweJ1Ss zP(Y0}w9MEmVthvIZNSEBxYB3A4igE!!m3vW?0m3T-^!qc&x#!>0-+MCZRvG7?GTG<9j+^A;qU4 zA;#mxg%EA97cM{Mtqa0!4Qzwi>o(xD1?9sWc3a?Ea0&BaKUz7sgn6;=tUM?;Ft?89 z%Y&CkQ;QJSPXNX77YSG##PS!p<~Z!da$E=q-+dOL!3@u>NofFJKfk1M#QZ8MY?Yn?45b zJoXix$5?6rT*7l01I}w>;GM-@kh2)O%m-(top0a7y67PA&fxsnXtRKAE;#dWTCEONV&?$o+Bvo^)@+CHy11sZYIXH&xO2iz zsm->t;Lf&m5^WaxIwPvv8_w1n{0-fHT81UrM+FXE5)Aa}Tqk_w{oA0JMxJ(`~UEBq=bN zPO95smkZ6BF5?gNQoaPZ45x7KAQjE2PR41<)?pWVe^?xf4UCO5NkzdahJENB=LHtvna{Ed>`|QLTZgo3fz-Dzg3zKk=XVTa zxMc`kV7GAU?QcQoI^GXbY(~s2I4O7>+$Ht|#)ds% z6Dg+d35uaNAqADLHCy6EGRv)!?kb4CMjL zKTW{=-6A^yw9uwN_$KT=*u*#TiI^i;XeWY}+f|6U8uMiP`2p-c*vK~kQ^1`hm*d>x zB)J0T94BEmVYyw2IIA$PwukTMCtVSo>^SK>B;yqJd=~~5#`%#G;GD$H@c_<9oyNZH zLN+mST#r2$DdDcb4AdUr9=;ND5-V{^bTVcrR@&o;e*$~VBjNPb8SG^*gnj;zaZc-) zi-OZ#$G|_1UF2uLpCZ@Wb->ARmm{|o{~vqj0cAz8uI;MYy}S3`12Ztd5NBY98HSAH zoP!w@Oems)1j#u|R8XP`F%l#wiaCoQq9Pz5Am*%?6POXf|9QLRis$IPo^#K+YyE4T zwO74gb#-;`?yjn@(id3&d%^CuZzg0j>&?VeYQ>ve^%go*ACUhhRy`gB9}FG{?j+}3 ztQ+pJFW5EUoveb~6nh|eBQY_U22Kn0E=C0tgVz(IIDS1b8VS%Wp8X-@JRZU#MHXSB zeU0?j(Qz7sBxz}mpF~n53;HT4uO-TG^d#~nWkP(?ZouY12XqSRnU3fb)H9vX8mMQE zMO&c`wX4t`hn_<{Q^VcNlhkmFd8Qg}2`e)-+)~zjYPe;r`P6W?u;x?4EoaTAhFig! zPYt({Rl^$YKD1VAxch_qzz2f+!F$oSt?pK_%2?g);XSLnTUnc|?rvkvvbtN%8fSHP zJL{m;-5soqR(ESyF|F>jj#=Hk$l70Z_mX`P+{s#2b^fJ>J087`dZt~lhwu4XY&{k` zUT2?8xXwOhuZoQeu4Y|xJTknma`rWLke)&d`;FMs_8IVXj;`eFRjiCoKnnO8){@47 z_`?<-{n$ONqx>q26v^jFm^W z=tb`H66^76$+wQwZFU_i*W2yf*yF+4U@qzNSeG4z=Fn)uhlxF0^&-0urI2G<&x-SN z;5z6Fr0ik0qJ%9;yd-i%bGXA?_AJ%~j|XG8$A^hAgpZJUtl=IGY7!m+r4wD#J%R3f zP4_5z^VKN9>c}!~L0i9?+lrokHMiOB0JVPoM7ZAl1nZU0*|Dq?f0P(Y_&BjUR@9cT zyZQGQ*dbXL%mLR2>w*ojtz5Z*mCdbo7kPHGqC7VCapLk=O}9R{oIJB*>9#26zD$fG z{Yh3otGS(|?P6!8rn{WA=W(3Nz;ejW*cXZM#9NpX&_8NnPDER)g*l!YwUKpUo;#L7 zo>^RV8M_MO$=%v-guG2FzcDg7t%$cq621 zZ_c$X{HIwZujVf0ZZl)j!E6`2Naz|o!@7JmcM0j2#+vzGv&zls(c5+!+I>vsJI2CQwZxUZa^ZX{r?c^bU)5Lz8 z_$F~m@GYTBP}y&aBu`~O5BeS2TwQ|i2%Up`WVV{w@6ob6IrtvEug*bpn@>t}TY#)r zEjNL8tK~jL%chq53@w{l?sIfiYPnAmUx5?(vbEeK_G@ani`l8EV7c=J~B$+ zFXphR;urXb4YF})Q5Ow)!dq1GB_r3Q$ znzEO3pV{cSHbE}-Vx%lXo$_OY<;TPiiOFcC*7PS6YWQz@Z+Okj zx1@jPed`@Sb9PFy1`>=@&~B~azlF7kX675xzxBTHeo7obO1hT&3j8Xu58Rj74<16M zy0$xvtaWYo3)0-Rok{)zTI9lOyZs4^6mS|PSm+$q2?|{d>jZ_)!#Y7B2`Mmz<({c% z*jD$a5`HpoW1pg#nU?$s+Zof)x&6u96>p8rfxF{vurMGyt8L7k@m5$KxRdm|u%>!< zysf#1(9Yb;k+2<>1lEw}&iI;mOVi4nW1AVt!8b#D{aj?-n;BVHZ4b6bL+*}vee4q4 zLC!Vtv+djb``P3;#}4DGUY_j9bxloo`wkW}x^wnyq@sF~a+ZD9d&fJA^zKM%zf0^) z`=0l%w*afH9n9_A^N#o#_I<2soI(1T_LtZJW9;GBbTowz6aOW4I5sVLzzm7)$EMEE z*pQfTA9isL#b%&Ke2AQfW5z@J4%s_{)uO@V9Kvqy*VyS978@G-3j7L-I6ucOK@0e2 zt~wO6p7D~%Gc$YJfG`y7DZ^r`b+qV%J4{Vp%7g);a!qs1R z1Gs7+JJ3HPS3e*ox%&e#+3z?In~=N|yfpa}(jUH!+jqE!Z%;u2;B)U3!e`z^YG2}!Hz?mNzYkBrnP>{9e0Pv2NC?B{&w z^&;m5_FK}wi+vj#jYW`t*xvcb>&Mw%_DZBuI+)vdyVc0Xoo1VuZiL3>8*+Y&)YKU4 zk@O{hKie0pKOcKvlkyFcQe&}h(#Lj$DW29#eU9y4Gza{%5k=# zIUYH?M%WPOY8zvJK(cp@!A9mdr1p;I{Dt;(B#SQO+CE6|HN>`qwUcO`%_X#pQRoth@@KkZ1A*EBr zeU3EF$;cfxFeejkLssZYzFTLc25&{4^JM5So@xNPVP_%})x~y3&Tyzb3(2UVwmXth zLrEWogl8AhhmbPV4zXt=E439}LX>ulr~9(_ zkipKgBei@eB~?D$(JmkEXqPwXeo?|n46Dbs_z#lB!cC?~dn^efB={(rcYBv^r)A4-eO z=j;OWb8sCJsy}npL3Fm-A{V_a`CL-i2D#p?$#zJBZzWy&T-%bj#J42dBRRe$*#Sx8 zEu7tohSx2~^X}mME%D8yZ$aB@M{-&GS?IF(DrA-l9G2OUL&HWp5@^Lk*|XxI)LC)l z1LvW4U!Ef@+WYg-)}LqQg2kbmxPEDT6PjAf;)jCkk*z(%)BYStr+=;~L6~Et&9yXM zlA}4MB;iU>5{>K7L0TFwMeJ%*inOcDdXAUG*Q3R>G=4a^0omQd-1AT{k}op?os;#+ zCGjkB-(<45;%c*j^)43bEt%09tGtgU8XIdXD%;>}@=V zcIFGwxwaBoT8qrJrZbY9lWb?gbbBn<9v6F&|B{C66m*ndOir~^ zY>s!GS%gN|BJ{grUKQ@piJZqGB|05F-5N-NPPZOs@?ADLbG&S?9HoqOC)%_%$u$kT zUPZZP4>FNc?H=y=Vls{nL%yp(&TOxOSB#ob3n|h)$qwY~7<&Op#68LKq*p+XAx_Tr zq<27y4Qa?^Kw7>l$Jz2;JJQ?7b|>p_Zg;XaXUpntXfOoiY0KGmv0ceykXGA8p54hL zXYySe(%T|%l_cJpcpJ1nQp8&k$GRMrhdY{=lXa0`93*1nfI}r)6vXD693WU-1sBOoxxmUj}YI9jg-sd_oDrOIro_z zeww!v%321q=<##OIkpQ9mC zz3(I&A;bO->8~XR#^=ZP1Oo{#1~cQbHZhZ{X2su5Hby7lZF0VYWrfDX-byw>$7Pm( ztU1oi1ZVk|f-|vaHVaz)! zMmEArdUp^?c!QCA>x^XB=j4<8Rfc(iP|WNCcOzf*0@e~_YrKTFhLGvq$GVA097p&BKZN!3Q{cII%rm6w3qK8?3?$?2{Ib^_8}OYFX+(=JjE)(so$}WwTUfHclWD=J>ciGyn>>kiFCLYEY z$peY4arv{_%F{jl#Ydbq(d{y7ET6 zTYO0T&0r|ujbJ)obw*s4Po~FZ^}n)f$z8q-TB70bPOydl+8V!~e|`Y_YmeahB!#_$ zE$Cp#5_&82E4~cg<&9rYwhrx{w?-@Di=cHv(u1wBR6fa1;@@RUJW1G$c8+8V+ay{; zALVZMCmu~aiuaSYX!A_)+Y-k6(|DHY==Z#e<*4I%yJm?577I4V6Xsd`sw9X#i|)~@ zoI3?P6?_frQl}(d#{yNmgyb08p$|0Pe=PABURNID{*Pku?Oxui3wch#p3m*cY4HG` zG@Ig`N$Ha4oERE^Bj}uX13Opk6OvABpJ)d?ne@)+a}A3Rjjv6t#gofg?)g}vLqc+l z9ndHmi?xA(`}pR`_y%xe{7LYs_(t&Q_*39B_=WMw@l56xVW>rxK6j1!ih| zHBZu!`;GBC5=Q$clIJA!tA?YSwvjwfVQFz49$`8qM*Ce&C-jy^`zLVrM6Bt(z#DZX zegYN@*OB|l#Ckl%bR(rJdQ6=XUCn94yJ2-|b#iKaL*fa1#B3nXlZp2zuXmHjk*lle zL7vkRBjUs3JrYymw~_M+a*{i-0dF$raHa>={Cu+^zFsN#$QVKDI#Sjrx)VP;F%sRm z?un(z+mch_%dl=GoPy5fEm%*Q9AA$8tI6>dSjQ4hM(1)RRYg|YtO_k8r7C(zXX3S^I;m%Z)u2^KF9b)SuUCU}r=!DE9a=z2l|*HZ zPEX_$F91iQ&6nZcOD;}kU?=K&@J4J#WndfXM(}3rL}j?e*on$;>Ez0Do3MqM=bpt< zW}e%Oea$?#C9xUYn%Dx$@?xHQhOeLJcJuuQB#z@7)=Z2+Td*eom5(=&%KW>*HsRyo zpHgU0N{5}`4>uv2Kv(^xuW(nH=_+(EirW6?LXMm85MK9aU491B+4 zz~}fsN9;ND!^WYFSeu-+&^BwDm=HgPFh1S{Y>IB#F^Tc*VFRDzOY~a23X`PhJOBfv)y1#1F!1a^8-${(ksVSmWOT z?dZj@q|lLTJ7F{FSgtML+A8Q2Uzc2ztcteub;%t5zjxwz&gZ!fo`;Qs4qVmI%O__+ ztQvV2CGYh6<6+=V?%f}61sC#9xA{Hsl5hf+lJZ=8uIk{m_u?%2RpzRE^z^E6RdvF( z$y@#N@YixH`ET>@^6&I7O58;l9_kPF27BS(pdwGuD^ZB;q&(M-`?UA+xKCyL5><~~ zim~7sbWJizxH?&hJLJaZ z`9twSFb{j6LlY~=ztYb|GjWCAn*43hT(8Ep70FpCHXr+*L$K5-p9agxwZgB#`8?N( zoUOea@>GoFC2~1e6P@-v*OK&B-U2Ls4#r-md@0=G=W(_|B9B-L&bIWf@a2u+3aoz) zN-X0H)`UrKfxS`rbhr{Lp92$DVS#i2IDj@H&DmvsdBRexqFx0zy9U}7FDqAL3v``H z#;yiac!*j@%6j~|T!q!pCpdo^APn)MmDUrxbEcQzfZpPDKpD|C9vs9vF z;wHZo;YNQ8IX9avrg*GaY?FD0v(jb0(a$2>;BPgV_|VzP*)4eG*~HoBNZE?lmlCne zm~@XPefQu?{B78VS0U2QA| zIUu zardf;#a=b9fDU>QsRO)=yeZ@vgtgg9&XULB)9MvG`*?V`dd2kT>_u3I9mH9~SsRPT zUdDq=oLn!PA)Kk?u*gfkU(knV!H4rNnG>nFL!{qtJorFEL zO0ExQ`+9rvNAtSb>)wYR;_P8}A?ba*58UhK4fBE93++t`miXKo=1udVdlP?AAL4o9 z4bzMC-rh%eBzenRKpeY)=3_jWylp-r<$O{u@M7rMU+c#R3;ho`E00m1;0xsgr0G9# zd%+LPUi>nA>h_s*e7Nj08ED?`GsV!z-)AgZ`|ophugSz__cz!i_zs$hHTLhoAE24o zbN>N60L?@y{{VOpnu$lTgWw@(Chv6!8zU$2))n2!*paK~I%7w!qU(ZQma0+y?IfM643o`lsY23L8dJLJwl3)rSR+(rv{NR6RJ~uz$C+S1; zqyM@24EzCl!2isA3jPS4kC%ZT%>wU7?CdY_=0oR^GT)nrzlJY}e__4^zcgQ&D?BXm zgA1Tndf#Ky|4Q!)XynsD{vGCdKjAy-Q*)JfrS~29o%z+>^}eMnhI(mu z>KTgt{cp|e(Eq}0^31_{@lY>?t>P4Zc`he?HdeR~;#KN$?)s@2&iN!3i{))+II%?H zGVf>nNnJ*s%drRkGqG9TAv{Tq!0K^;CF20!IwL(F|2ZSEckCx-a(0%N&X-99&4NQ% z5g&!s<9K2e!Ao4~H4A29<9U?lB}Nlsi7_0-u)usN*2J4~#idw%9z)7l!a~0U^*24p zag$9&*CeE1LiBPc=sdcicTbl1aX<20{+FcquY z^+}uRH3;elQ@n1QWftunbbdy^UR|iox5&DuHi7ySN-I&UC>}Zw_9YN|N@DtB4J&cgR~2 z`@K1wIfe7tczh~Jj(1%Sma^U@S59yeXHRygaz5L2g=XU+swDZ|BUg5CB4nQ) zl3eA3S2+7Bmb0+6<&NX*@oppM%LN+=WrLSF`wBL*u)^hzSkg_(G*yW6iF)B<-yxB4Z5OfZui_xQDf zn!!E(-Ow$hZ}qqMC4&-ybhSIVNv0+C5+`8~v?bWuwF29?)?iz#e@-&(TwAa`mO3Yy z4z4}e5$l(exU!?W*RL7W2=3({Y6hFR=N5c~l?qA*_xUw~>fpW5`|%r89jqQy3m)*R z1y#ZOp$}rQuMm6y8cRLH*NLUd1f_{T%~x`y#Lx}hga=3ujnLA8N5~3n>RCKUTGAal zon9&{h!aW$Cbb!#lP0yrZ3dqu$3uQ0_3$BoB6iUq!Z%f6;HNhG&-#9<6wm5&b*bPN zd|hsFzu?~zEolECe}eZgVZ0Zlp7l5R0lJ{iqHns(?Q|tmyWK9ANDk(O%7)J|85@VrZ;Hu=x^3G|mYp%=RcA8wiCEP)pD^KOUB zAn)@ojeDlhwS5uaYG~Y&Lt4%|TsmR9OQxRjpZ1gJL_gyfNo~V3XA$zJrKByr-4!LJ z2=VQ1n=6Hnw->>Z&3@fY z`9{AyDHT%RC!h2;_|nsV(l19!`P2`|4gM3pwDmXmWl1TQ`Z4*0zux~5o&6{Ly~$Fp zZ0bOAy}!;sfJXd!|EJ_S|8ejD^kDLFe=YbE^qb^b|1t0&bRyO=TDXa(32!ygH08}E znr2w4oM@V35p*Kwn!6TQM=#}?5t?Jqy#=&sc-#uyi@o-i&?c!YzFm{>TSp4LNjm{cX*@#S2R;BTjmOCcz=xov$?*{O$GY)MN;UPKTCr zXF$ujGoj_MLw=@vKiPrr@_w>07U$njw&(kF;lDbk?%_`NVh8*z@)eTOB~_SO=9aoD zU}36C>K3=m)kuAv+@Gw$bzg&xp#`K@Nfo4)yIb4@)7$j|FLb@ZKJG%Wuj>Q$bA7@7 zt{-?27K1040ay>7UP-RIS$59zPIF;pi48F=ryHSME_~{x09nbkPc$6wjj&Y=s zLbwMU7sl_wf9G^!qwxJVo}3HFd4-#RKdrmLyYYB9(M=$IKIseGj6@l}_YCq+$M4yM z1ZN3%;&E;wdFGL4zPp4xGw?)LhS*$E=DA7aB@bbZyMpv96XQ)!te%fI=VA4Hyg46x zZ|0J$(Oy_eASo0m+^H~2RrSP6L+}VoxGIY;a()=CA@LTCiyGgm&q@ZuXry* zU&WKv7s)-Ozv%7pWUG80_neO}uezx{-V0tmESA4Uj?a^?d9Om{z3g^3g|OQ7#zuV( z76vL|qrMmM-sVEA4dh@yAP3vy4||^{KTAIBy$0RQeO~Z(d-bu7K9~E?OI*NJy|5#Y ziw*ofMwZ6=7}*l@ z02}Q6uusqkY=jN=^UO+W-g#VgKGp;(r}Bueax2}Vo~)%jia)telRLR;m)Dc@^U%JQ zhqa#OR=3LaG`G21!PR)Q>}jUpVf0+nAhpvw7rO-wu{_WaOYhV0tk%;!=6!-ymB;W) z_et`3&hPX_;D@ZIS?hg_ZI!ins{1&(gY@UUai$zKVw@Qd9cM1X+ub;GIo|rlnc4XD z8)xR=?`)iz>*j!E-CVbwtK@0%T(jL9X{Nd+<;aD>VkB4KiKrjbil_PkU5oQ*i-9{MsRvTgDHE)EOji<+!py9uAT_d|s@*pwisN@*T0jLySzKSYw^Xo5PxPP!I6~68gCIEOV^OjIXs;8Gpt zX+6#Dc;UP*aXTq@c>T?F_&)1zuE+OTe{%!A&-$Ai@qO0c+=TD5{^n-9z4bSXxN111 zeM4fnS>>(th7-G<_^tQ`9ByvIqu_9}8lQy2x%X=DdhUJ^*Y?L!!D9T#$+o~sa3#J0 z2as|R)&z!`72Z&@+`9!_;Vt(DnkC+1a4FvK29jq0_63HTTf9M}3^aqxGHZe z)r|G7!FSVGZ=t`Bl{TArA3F}c;=Rxd?j7$9UKqa+>=W+;_Ko)iTgF?0t%$e8Q$k-t zbFev@raxNiPQt#mbthvR+q%wJ&bF=#y4NRRp}IZ(w(6PF(C;gX=Bw=Mo)*YX?`eT7 z^g4W zKCxQtK>1i5NI+{7YGFel$x$6bZL9>OI68(syA+rtwJz~v_)@Z4UXM`M)MwYT2$&A7 zPplr2jOoN0vWJ=urgPkgUET~ZgX6|X1Qi2|aoi-74{Ab6W78DLpG+{5)Mm)}lmJU` z+&q-}X--Nr(;}4UX+cVJ(-K*oEHI1IR!HfT21|3?I+WRIO-d`Il_i_ghR_Qrz!Y~c0nMaGDNjr?r6uSs)KiopR*qgo$Ld{5fu%UI^tS409lb;aFqzqU?XYh2HIddY7nN^hUogoukVo z?Wl55Dg06C9C@R^FP-1sB`Oh>PE;Z)og~lwx8UIOtO8hp`zA>%&od>7qlQIHBQwL-(x@y>P1RUTBd$292`~mt z@unrglGLd*un51B{7;$i8OnrDsQRi}tMu~WbCwUEs(hF)&QoUaACh772x>igAN^Yf z|Dp1Y5j_4`txV5Rj3+BXYJ%g;@R^Y6CRPGeX=p5%8NOM0zM$SuBcuv^!3uoC+%Q%N z%;igKq@*ve@=&`r1j{dt|8SuGU*krN6w~-WjV+54OMx0IYFwBBs#U4Ic-*lPsJ0&m z#Rt?D&b-$f;m{%dIzBSmkj z@1GgIMfB}6Nh!_~>6`28B)|m65%-Dek@#8$*CardZ#o!2BAsVa z4b+pVUI!dmsP3$P(!Z#-sl@fHD)*=k=$U_C2a0m$UtI@Ov!j~u_jRD;ucaTAyJ|#M zSSzwf|MNPKAC^Nt@0et)pA5(S0WsA{)jQQf)mzn2)l}7H)ne7=ihPS0s4`J)R^8V3 z$stsvCW}9n48L1R;@Q+kl~*Z3NuEvLFpHobN?)`zK~JpjT85z7tgl*@puR1gSh=va zlnYx~c~IO-ZLR_+&QhG1+C_2xLp9-#>YMKQ`&y@3Af8hsd^d5JqidR;Q|~EG@W=H{ zH7!XF^#y-a-&E6%)H>DifRGNVrm5By4QpBk_gAe`eN#*Ot-k5Wj_@3{mcQjZ5zomW z{YZUNoBbosqbC*TiG?Nm8|P7p9pO1gxJ`nu8`U@Qpuewg5zi5~DNDIUwJzd65zi41 z6~_@qy_ZU);Mba#__e0#-iffjsgC_^t^1$r+mV_k&Z&1hQr}ckM{1o)P<1b=b^p8i zR)N|kP8!uZeHGQWsQ*4v-^AIHl&rYi?`xV$@{jo2|6Jdq`mFMc>hynC-;U;Q5oi0y z>YIAOZ0eGFN%e`@v~~568l$Su)XIZKr0AAW`qAh@qX~^cH0ID4L}L++F*FL$7zD|F z&S+$!da7}O`mnN~Mk*THmIEt8qk1R4BfhI|X+gtx6GsyF38=r~GvYgn2OO!d&kS2& z2}(MRBaJ{xaQ44%n}7DLqE;F81yL{X$8GcXoKsJz{`$9C?Q{Hl{;8+_V=gNG8P#XC zeYKgRYxTc}e;!?*|BQeBJLcZ;g!7N}JAcLpG#-k^IceNE8s{9{ z?;IKDsQ3A+;~b6XG}=_#(nv1=^-kzclB!X;Mm%~C@wsA@km`0cYSY*~gSS*GRgbFD z)5ua|YK^B=w>7HP7)qn;-?yWqThL$W7yf7jqA|95!9O2|ME$~%(a689UpTrQ{b%j; z|F5;vI}g7ivxIPk||pTZP=O6)COR2PndE3))N(P#mKLv6k!` zh&MJTv|v9$9I_dqIr|LalT8WDj@p%I%D#knTVp~K_A5#dYZ&smhH$Zx#7mIc0KQfV zEX8qs;tkjXQO{nFP@f$V_33rP9=tBGdhDO5?>>frU1H+Lu+yR*ymmM?s7baB?`VPW#LOHOi<4RtIyTRl#bYMjVA;Rd$N{YW>@nP{9@fdLxaUpS?Xb!8A(oFVmXRqRg;%4G((M&d4Ef9~>`a#quB`FW_ zK=G_-RIY#c-~Vs)kNS7bpre1(Tv^;zb>hhXYA$f3S2;Q!rHR98&Y;`uiXK<^T8{H9OCx$5dO;8lgr$`B1F}R-~0^m0E430L&*f8=6D=R7;HN zOxdutmL;V;-(2OUS)5vVHdON@@dj~#l3be&W^<%Dhep#X*QgGtwW$16`l|EquW`FFJy&2iKoeNdxg zkC@gTe|sLifAk%+CKi1MeSsri;~| z=Gm&Ika!haiKD88T#};Qc@dWX}4m0xOI@HM5 zt7JLK+To-~&O_c@hZy;cmHb9Iyj94X>j=_^BePL~I}A4R8Y@|j@^++=AJ>uO8G($) zVEVOFj4UypLi$Lwt!10>R8mecT}>wT61$ReD)Jne#JZW{*s?nf?1ndyVpz939Xt)+ zAsN`aI|Do&jV;NbJWLn>J_3CdNv-~1e~um^bs+dK^f4sF`hop8_aLc*z=xm@603^t zSRc->B|L@=m{PiCw?6$`L-Lt>p}U|xe>epya0L=cq4c|^k(oT@I2^Z z?vMwrC5+aYt<2xZ~zkdY<7dX$U->q6_1 z-+~CHU=6OGarS2{`4zE+*fhEw9wbj?g@iTW8Y~zU67B-!$)%8R4=8Uqg@pS+`QIrd zJb;c%JrlDBu?1KJEP@@%gQh5!Cf_Cf9qa)fH0ky|;_qT%?kD002pLvgMRoc&u`Ar zhm89^G#`N?fDaAmw z+H)z1VuWR&q}7Up+G&wYSvvWagUihdFoUB^(zWX%$+DuPt_(Ty3ON1Qq?SN(?Cg+F ztprz^RdDm}q^3fdvNWC{C*)|WK-uO=Bix4Nl^@XAk?%g?k9^sMq+A1j550{WQlIWx4gb0!v3z9-+cXzzSa&y&Xe7ZJY}{1$oz|7^gspz=I;CMfx~1yF-T z;5XzNMOYN}cv{O|K)QSmTI2%1=KN^FD0)$?C^*hoqyzVJW(;98R)Xe-eaJjeYlJyi z1)2wU9*g$YesDke#-VGp58TJG$9eJjIZ&-+=O7a)U8L~@WFJY(LH_kijwhh4^kujr zk%P2xbINrh;S2B!&S@n!2Wj=@9KUWZ!zidQ)^+q`Wq;mq5Fx6m4#!}GnunK|g3&fv`Bgtw(B2*-b!GoD#zrgLT; z;c@8*!u?<3OdQSCX`ES4SZ7`&%|}CZDrrv;)|)*X2jGj)4WZ8B2F^ZVULZ9A?twmu zHqaDs3OS_rm;g1-+DQ77ptOZ{k(NY5RT?Kx@dYM<7jteWXOifnHs`n_8ksx6ouqUO zrJXv4a!wtY-JL*+?2~jPoCL~dNJm0vFiGAPXs>PsrIp%(unpXX4rdF(4sZweZb9e> zK8=QJ3&JLF6LNMf2%AA^z_w!M)`GcU3vx;_OEW~x?%FWZla!ZciJJel59fvL7=L9^ zrdn-MD}4YC+?@OC>MqPTJMw&8=oOm612Szh&Sl!>oGoq}!zYT{Ch&>koK+vvf`2Yy zTT+ut(0{a`&u9q0DP|kNV~UZ#IDJkDh8Y>87o#sKNj#l+hW(meiCGo#bSr&B#@WP+ z+HYwEtl1DR0&i|e%+hLL!nCn(!SA6zfR@(#19$*x;g1KvgHQ`UJqY%sXZ7v5aPR;O zta^r?^t^aX!>(fw($9tKBT5%?3Thkv{uobioeS`s9L)-Gezl2}g*mm?ahbe)!(DuX*h2?QLETu#6rZeF& zE5TLZSIT|vr9usifN(oP3Yr-xoniYz}hgaXvp~5bd{~W@};B2U@kDUyjO#PilI1!u+olgwE zQyiTL7n@J~3+j}3%$Ly5317g8zJh)h9+&1Q3qG}vdiQCV+JGMYdipBa6Kg;(ej|7@ zv;jT$&EOJf1Nw_4;4)|f-fS7IVn28Iggbmn+t@+;W8$CC0-q;dj~=lB?NfYfSIE_* z!(Ez|ES|SJ>2y%o6tAXVO?>d`*-aFj#Hrf1wkOfsRh zO(l5C9#ERdmEcG(fzolVL~2Di+AG9fgH~chDTz<{yQ&S==E!k;J$NNOgQK6h61*Df z=!dQbWgpDZuPg**r^_)OS_H~|S{m1C#!>^C0=0HfgIEI8tf>YuNv}$FLNcwAY}L$3 zlCAyd$3JA$^&x$|#%CWgZuF{bC_8z?Z zUB)Mua`Z0z`kh~S`aAIGx8dsI<8Q;4--7dtcfSQkev>{z{QAw1N528SK`$|dAdT|Z z_)5|%e?8>LmEdQRkKPIujzF^hIl?G#D|9m>#A?a*gP*~GYQEWP0!q>W|tCcOb!upGx2PW_@RRgPyQCoP=2IGVtC zPMTY?NI8*Fo%)4)IGV)RZZdCiFUOO?d!Vu*S&0#gY$X(>mwFsr4=qYRv>udAg`)H{ z8$el2C`w& z9%D9>POLiPsB}>4c-0w86$3RpuFg0q6V#4Gb)(sMb;eMonDa~iNAl6RU@ph<&{mys zTvg(d+LesBytBzGTLD~FYnRdLrB*eM=jY%9Cx8q1Icm7&d?!%-iVgcF3+MZpUk5m$ zWQPXw%VO3r0KAA_7WJ|}_%UZScj!;-BjTFV6eSD+hfsb+2~YElbNN2ieo-RA= z?Xozd^^dHuMQ4RAI*aF3%_vRoEb^;#OY@&u9IK2=^DJ56GZZ6kiMz18wX2j#iq zs(@B&v?if%qSb<8++Qn^S}i!T2CLN??Kf#v=8xB4C5NFW(5jLCL90Oe-nzRa)AYS{ zcdef2d+YAnF;>gc-L+z=_NBY4mg%c&omcOzbt}~nNxi8I^bPdhdQN>AeGffbRI*W- zMx_~*q z?<3`_8mro^vQ#bovl9P(`Krc8?ej>h{M)jN%3W=)WLP6r)+*_vOJ8NL-R{5sZKJlM z@A1#IozmfdMUpzv+PS{3zOq_&B>g1$6v@V^wn!!}0jl;D;oC?~OFT=mNRr|ZpGhM~ z0#bZN>$zIv6`xTpR^3wV5pUAUuU34IZog`?`d9t`5vdrpWVKnXBB~{;%}Pp2Em>_= zvLbr>NDA`z<$I)LwNs;(9JNPrES2A1Eo+r-)IP*-RkA8;m2?`%QQM44HY(Go9Mzt+ z8!o;ZmA?3~q>%r5`9>wHQa&PG8SPK~)wUB!VX1CvM?L!9(YODr<@MKUMN|`_vQ>Rh z9Z`v>ru-|~?_cH5QTaw?^v{*D`c#!{#DgP_dt~QB{h>#SA(vAP>_WQ3W-=q2N(Y@}`C9blL zxO&ubqw@V%jBTP(jm8iE{XTEhe*d|a8@2i)T>7`RsrIPdq^Kv2IPKq;Z`5{G%14*) zznectz2=eeZqyPZ-WiRU{%WcHwYD#=9*uH;8_E6Oj&1&W$*TV>!P7>4wOXx4MG@bP zMjsK^(QHEH8}-mpDMx*F)T>6lc+{gu?fU<+eA8LmiRL6_n7^s-j&w~VseMG+E-L+U z@Qrllb>h9{c+W^nCX2Y*qO=^!hrM`;*`I2S^j9LuaLonPvrA_x2C5ci6STLjS)WFA z+V@tkT7i&F9ruZ;4oKT20savWkLEA>y8qhwi#U$TRb^QQs(p9K8tTn8vn>Tm0#S2a zX~_Jhv7r(#MXKXFmI5V%sD3?@_m&QfzF;PAtM9D2rfP%s)8nK_%2j+%-%cZ8jn_1* z)ks;jLnABc^N8cCE*0l~|Gshf-;UEFKA@T+p8Jor{UalJy;C$wi^gw%ZOr%E4E`VC z^U>_}pC6~`JvD09I9~D&lKfHG={sal547r__sO7)(>Yd2W$!Fyq&n5S3R{6QVkx5>vUU45OMLZIMViOZ6ctdDRN>39UH&`^xuk z=h0F5{(ZZRN+%j`MWqvsv!l|9#$H-?@Tu40gh#Kd99;*ZHJ0DkglKI{J%1!0qi6VQ zYhU7%8VQR#riC0Q;u{eMQAtH|bW!^fH_4+@ikrl8%mI?f=e2tKJ@e*b(V9j#4jJRQ}6sPvC6!6PkHrGIp} z|9u;eO8+0>&(S)`UteR4B-D;bdzPRcMeQ|eyHPtc9pgM)0ogC+}keCZnLD08_~m+Fxq=94{ANX zAt{oD(b`d4(kg&j;cpQ3jtxj}81BhtgIag5PstPmi;<&!xObpk^Bnf;)b{HU>W4eF z71<+9=eQC_6=@Uc93KO%%ML>aQgg#S4z+(tkQI^q7%AFU(GG}8x(@p&oj9%>?u?{3 zt{wKsl4?#7SIwveSCFiZAx~v6ADSSwW>|Y_!6ynx4LH_bUjphvnM}vNOcmnVn~AYc zQwSDvEDodnKuND@e^3^1s&Xz4s-F3z#|c$=hg{yGJ)t6~H`3F0;9E$VS{^H9<3%!} zop>_6mEO25=dwY4F+Fi7zPLulZAi-w-$Q#xdSm&>tN=>SOHZly)cdvKxE!bwRR3G> z>wCyAW;yCXWPd>QLGPsZ)Ei6wK=XhWpx#99tT&G8nq(I=V$r+mO{;~qO?6MTQtwV|cz9;mt`%R%Z3i-z@5d)@jL zdP9}v5gAYEv(*n}2I?bE(4DVYANc`&YmLUQ;cX;0W2|{eG_lfnEXjlwOH-)YEZk|+SgAD_x01* z?O#k>a%d?q#hD_crLoW7gt(;9mVnFH@o!3O8FB$li8mup5wI!8%|e-hboOnFvfFw) zUqrjE>FmYc3uZv2#h_LwNwy;F=@uo|9UMv1L3_C^IJygL4qXGilk!?Y*|g-^3~&up zQZ;Kr`HSMAbVhOZ6<3ij6Iz^lDUKl?m4Rdi9)G}AP)UQ_3Q8iQHL=ymVzee+5_yw| zM=hrfEax6=2${&i_267jXh|eFdV-~(C22Y0X>G}siEK&b*V+Z*-V#gCCQ!aTp+0)Br$9^<80-DYKvN-$+ zj1i2hZ<($gV<)MtuETkwTuTur7n*tl>RATFTQ}Q7jRU7gpedpPUGmxP+DjK z@;#@KBDtbDprn3IC&*@64Y;QIm}+6)BYs(n_!*?u2&I$?LCFKuhDy>!eV*iIWdp4? zv>xf=b9KQ;!X`RfE6iJydr3~ECb$TWR1d7jKU_zAQOKjNg9C{ttIvwVX&P{DA?Ip= z;@u00Rfi`nBrbk+J^ZU7D2Yz>i{f>X_DsM>8ggz49H}APXbJJ9#FvCTYAM|6YVwHJ zT@Al!%sELAi))FSiBm0uPu)y>F-ObbQa5v)22H_<#My2qeK9ERbq{!Z$kT2FZ{)1F zmZX52fp>&_Ofn~ni7)1;D6~k(sqTgAG$-F(q-bn$7btn+bohvP)vbiP;YqiGw~=xy zyhl>U8HDtZUrF}1CFfRhZcWIYR>PB4632TO`Bss(8eX-Mq*)L@Tzk;jyRsAdrQJa z+QQrV!I#>?OWF|=kLn-tt%&2D1HWlcN*~Vk1bf2O#GND&BL0>|+S%~04x~t4T;odd zI!TI`hKqFI+|ZC?4FiXUoC?``&PN=tH~gj(9A+^2dVxcs;!eZiO5$wdWWC^D$C4sh z6RntuzextA99%@aYAj(0yyQ4y;&S3r134?MCF!B#!O`Rx0FH%tKj`*8oo3h~|Cva{`$gxI1$G}TYgi79SYRKhAf+NW}jkKw7t10lXiXk7X$kB+9 zUrmF5olFi%Cdo#FIG!YyD#1w4N3 zRI-Uz!jr_u3P_s{=juj^WScbt6vvYUa}~xh-8gq<$g$1>&xG&H`IXCwYn{dj=X65% zkS}#-JTxC379-z$_>;JqMuzyQ1vOICN``b{BAv3T{J%z68d>Q{(m{>0^b8rGb_>K& zi-B4L)!mANngwZGnF(tBp&B(^TvF=~8dZvSY5k!(^;CRLtIsv4k6FZPL2FX)N)xLM ztwmicLrj{E(t9im)tI;rsL`NC%tG-|jje^^uo`*SqntHYsYs|#8CDEYC{NoB!A4+b{BSn{8-pj~tGhAS z1e71~CSX(WL_CW(1)G5<;C;Lq*c?0_ALY%#7T|IC&29m<1dqkDbxW`e*a`pRWx%rF zMR+7H3zh@>+kVjg=paOem$lZp`=1|5#Xd2wPxp~H|e&m=YkIy96yA7TeXhlDccgY6*b zV6>x35gP~{gdSBEu>sJ5_G>h%2G|AA0ami;3+#O80xMbc`F0+3zLoU(JUbUU&q@Y; zuAKv&YbA?5$Igb%v64uiZ7+w;wvtP~++GH~+)6tAGCK=;nU#$CEISiA%Suvxro9w8 z(;h-1@=|*V^inGs@k{Is=p{&zA2u`a(EAH0neyp&8gx2R=Z4r+=rp9!EwL%ksmQ83 zVw0g$kZO++yBIpzzK#6)#r78H#a1%Ax7cOSTkN|?@Gi4Uq08)hNc1kXOQ1`wWPg{~ z#n2^I(!h)D&CtbGvcfmpo1iyaNfO^=Z-m}tC0l%>y#acomAvK+_Il_I_7kKxueaAh zueYBfrG1@U1ijA6kIo`{Ep(BUf1PXXLg=;j3na%E+H0T-?UzW9Ut_O^USlOyezm;{ zdbO2Q`BnBx=v7woga7W@u-JM<1KiSXO)YUu4&GU2Q3ZP3+LlHs@6TcNjE$w1#~S3z&Jl8Rns zS3*}=$xN@bE1)Z_WT{u!<^2zoI=msn40|El6oUY9E0< zY9-_Sh$!Ah2U zx7`KZZMB}T%kG5kvXbTAX`hGgw35bt-tK@tZzYqx!)}M}u#(K)Znr_VTghi{v(G`d zSxIR>XSYJ1vy#=`YPUeQ+N+V+-eSLmZn2X4{}QX&*MM4$`NDn<{lZEI;B)&K^m8js zfY0ow(9f*&0Y0^#KtHuwh55vO4E@APo8n{p5%gm#or;g_htQ9#G%G%|A3#5}T8H_- z?uC9}rDd_#z7O4NrEBrNeGmG+mBz(;_Fd?Eb{TV_ckMgSckM0AeBQBdL*KDlzj)ie z1%2B}6Xh-YCiE>UZIw6e8_+lHRAw1(SnH7Yx6>H2S_~ad1E(`WHSQNX9n@_07kk*w z054&zc-S6-9=4hKod@D6oK=hft$oQ-*<7S@3i_6cOEqEvdVimZ2Xo1sOR=%qY&3Dqe zs_gQhm7R2~@?0)7&t1SwGS^jt=DJ?Y7%Sn)t{13vrHc5w>J5e-F7OC+AwICQiY4Db zeL$^c$s>>QMzvinXl*B*u3D}p zw3gFMr>3g`t?8sER>M_?)^O4ytL~~nt2=3tRdZFL)tofPsyb=QR&@u)rd(OCXcz7bX%mAmCM|#2C<6JO3b}#63c;BWY$%S zST;0=c~@;>TGi5w>lm;usF_$@P-|J5q16MmdZjsAeXug9xm;yXyB?b3<%8PM(cG^9 zlm!jV2CIPDv(YTE5FEghcL|?=0MDwLtLGoUv#Lhx`7h#GRnztS{drck06l*{o>eVF z&)=6PR*TW|_X(f>LQw5V&o5Lv)AI|}{`CC93uu?x9XLO%AwsoUt(pndnw!wNdrz|R z9<4=RTrDU&tamDRNm3MsU%!wu6~elyIv{zJDq%@zjxO7sk&TaHoYM@x9H_F9E{^t^ z3c_-UN=W4rl~5Km(wjIXY$ZwFLH2S6hHYYC*ct}%4SJGtE=L22oeS4c%NP{4i9y7A z5I={bLB!6XKTw+(9JYqR#LgxzZOy@imh=#68AHN0F@$z{CULdbA*6Pv&uC3-XxK`I zhV5f$*fP|!oJqP`|4?FQ(4({?re5ZBP%UOy*j9#xt0luoJ&m5`R7z<$>C&GY21gkl zwjr&FbtE3Ggoy(U=NumH!*((vY&j#iGLIDcEKuuXBf{0N5#hSm$gt&%4BOJkaK%e2 zRa$2kj~q$tL~sP>N0J{}sgP2L{Bp<}M?w~D%JPMJ4fV~Lw-2qQ9!L$-Z`|2QI{ZZ9P-#vkC^;$$XACva>y@-Ja#l7 zCT|?_*df0h^2X5sD!&}!jj~WLu6Tq;$}flPUddyJ{Bp<}hdg%3FNeHw$YY26a>yHp zJa))dnY?i{hsrO9ym825hx~HL8;3l0$S;SyamZtb{Bp<}hdg%3FNeHw$YY26a>yHp zJa))$fV^?EgLWV$pB(boA@3aW$#+8o*~{Fq-sR7d?$wR#@v# zrPj9~$LZl$J|q0bXK z^FzR)Q1ParA?L^ihjDfU$HTzk(2<-S4ysO%A}tpbXVU0-I3wj_p`!_-7%8ick0F)| zYDBGde67%{4U8i#FI=~m1&y(!k0*U>xcXfg9LL!S9FGIXLnnraTGj^UpJDEgm z0yq(hw^iumu=PwPtuk?~z-w$hk#V$I*A&9V%!ek^uC$Ur8Jq&0#@Q*%holW1t%y%2 zrgijbq|M;$G*DbsGo@+ZblT-5#HKStI+3(!9bWS##nt!CYe8jn+?u^&LvjJ%t>|v<`L#HbDB$v zW>bo5jeG%TwbC!^B@4pd{0d@KnM-x%So5p-pvG#llG2%ZmBt8H!Y%56ap+a>b|1Ww zl&gqc$y`~h;a8Kc-MXtd(*B6d}hFLVaf28f7m7mx5ZgUq)yIE)CO*l5ZJ7 zwh%NnU(Qh@@Rl&1&XJ@TGC=K9tbpHYmrwR|RuYzj%gMizbnOAI2-79EvXa!s@c2T$ zc@_A!WIXFoCbjrRhFD!tySggXdW34AxVrXv3qeUQ)hAC~o=iP&gRqZi5cUp{{R7#3 ztVX(ah#Qi#KL4nGs1ZFyB~ZPytVPxYkAXHOPeXc$M&xNi$OF|sH6f>bW65@8Q}Q&X zr%+$jjNJc^y|<40qH5Q-Cl=k^aMPibNOzYYsDK5M7B+T*-Kf~z9kksdC2e%qBw*?KdF_u-s=ys|s!GuV8mhM-w%{W-HQ zvvE)M&4_9QHsU`Xz`i+D@@x*|oc_#}1CS45s|L!;IVjT}2GMi9t^UZgZ3Z&O4dMwo zBzsy8$)1EmveysgsEji{{f1>vxnVrN%F`dnaal!cg8gY_A05ivp~f?Uts*F2%m|K` z2M5xQjrnj@7!nM_A>Y&bX++16+TF&Oij zG2F)`L8}19aJ&lWyNpFz3N)HDmaPmp2H99%GZNgIb}T)g|7!o+a7I~BO>P^u6x8b2 zhGV&=FqZ3AUCwXc2~?N!yKV`p%lVDXzsfTMtI{_+-YhM13cG-26PkV46*SARCVg|m zx@G^bIbyZhQ(sfRs{_j6+#}Nm)bi?bwe;lr=|xZN&MT=msCMU7;#JcS^jcBNYXrI~ zNMCvdTpfM6&im18%!u{lYVS`k0=@3FXPfblYQaS8H>a;|=0Dvc`-fW4lb<2|^$zx4 z4eV=cdB>UqmuI}Sp>KAF*%fBDsaNN#-Z_)1Ps>+g#-VekvvC=)aJ{?2mF{xA+B`L9 zJu{x+zvH{P-d+n@b;W35{XO$jbKO4I^K;!k*Yk^N_)WMMb3NbdC)e zxk}<6$7>k(ykj|>)=XQ+*mDYVa)%-r%&42UYi{l!dX2!rv|5LGR&SokE9!SKZ&%dg z(vMcu$7QarSeTh>ey)BLb8Fp8#$Xgv-(_emUYI> z=V9+1XJ+%7y_^2E`Or_#{T{imBlml_5~;JY-#MQNod@$w^4#z7zvuDL*HP&Aa7_OZ zkB7dFLcfPsRH4U1Ux%}zeh;s}LXSt$`zyb*ih4ZsbrkwNe408R{(T;g=G;w%^WncX zUVqy|Y?&paaQym@g8#hSnr*p9xCrS zXGQO|q8=*mQAf>t(|flDcdz&CU-M8EeSQ^=mm}qf`4lTUUVpEL%DGAp)gQ;J=<};+aDD)_Lm*wN-I=_YbhI5ZvN5^cW{_l7c|51IT zs7LXy=^ML|`xHgHlMNL`GsusMqDgG5Gip2;X5%=%E!kz`$mr4wJ%nsA)?;8VL}sIn&ho%mnSnM$W64Y#P2Sijj+;X^ zicGk{$jyigkr`$~$c58`ZGK#cdb3v|8cx>PkSr^1FgTcVyO2j#A~Hj*L}cb%pDaVI zMAVsm@|xKrE=D$8pDZh_H`tqV+mYQ?GBSIvWYh~;mn?gZYnXkWYV4Jax|6NeCCioT zOx{=9xKz}VmiiB5X3BNu)nd4E+TON%;W_R2=}IZ`vr|AKLbmKuHX=4xiyUNy)-(-tgA))>5E?7?Ng zYb$2?Up2Cv(LUFlji%q>+CCDZ6?}R84q4Xa<0^e-(s&K z`A%PQ)Lg2M$P0Q4xg3m@$f5d(SDRP$QDnAPB{GP#gkNH>5?NRua?}j3x5!p{3AtHI zmC5XSi&vZN^%mJm&meh;(YrR|ZLCV}&k#%z?k|ng& z$!;QpiCn4sIm`U1`^g0|8gV-~wc3_2107x3FE0_wPF7dIM{cn{*43E9un&ub{n* zwibC!w<6cOr{C^6&OM(awK5N8ExdQvATb-L7QW02Gt@Vs5Abq4ju&(8nH;H|`B`gc zKFRYz{gL`!YvY$y2Rnnk+ITT9<=yqDo`+ZX4CLn8)WL_UKUHt)nVHwP4t`^;A-%_S z@W-Bu+$VxW#M$FBWQ_)` zpBSITjV9v%Qkyk4)+qC)6%b3>nWIK&$DuWi;%IL5%hx|Ti++v6CN#>YMrD2GFxs&k z(MP8ruMe`uXxM!~By=#;&Yt6Mh7EXqEheA8Oo z=9KH7HOssydf*`5TdlG;nyxwLYEVrxJF!cqVfN1SsHSLI9gsJpZHji(4$77L5-wUk7|IHGy)vPHjqsF;j}}u{UP*+QZ=BS)F16>5IBIgKIiGb=#RV~ zGHQ(3dZ07)qwSOJtAD9mncLqD&8R1+hE$L9^mlYa-W3^D2D_jUbwyj+ zf(itxF*1#+JsMUg>J_#?(vG%X)C#Rh)L+sz)2ucJ+oCnKLpN%ThE+E*x4v%F0^Le% zN!uK)sV*8;^9=Q`s4+Fl^rdEG_cy1fwp9m>sQ_#cH_osjZGE&RY%f}owNlZe)S1+h z>c*_ni%c!7cBJN28~vzuhH7Bd(1~hCRcS@m#wDA+8d>y}!74Fq0cb_Af^tM%3|0%Y zp-SjbmFSnHWz8OP`bF3^(6Y?-F9nv4;k!f!g8Pyq2^v%ha?(@UgdQ9hw6I>V{eb=z z)BeKqE{cDq{|nF2AK0sr=}GEDHPDRAjdu-V-_ts)`n5ez+?cJO@6@Ici2#(S)ANP~VvA7OX{&Qgc#E+W4#fmFryUMC;Ll)Vy3t zpbENZT*3N33jJ#)1yXS!Hr^rGeTA4MBljt2E8{fBAA%IG>|h0`NL zoL(jNE2AgfN6&2XN@z_FWOy&_-RxCDv${LON@zlN(syl`yXjSA--uh?CfiI$GG&qkC zUyMd{K9Y0U=4LulInaGIsCk)IW#rq;VdLLtW82K-cv<%5qW_#h?=-d(vxs_G(EU8F zetf2T9iQo2*4mwnjddc&%b*A4G5#{>PRFr-ESs4F>Qb{oD*%r|X0Ab=d0>6=(MV)5 zFN1EQ@AE+R%4As!2mV)HgP9KIMwCWpItaAZTAW2|UWJ)(Mu%pyR~r3l|15vQT(W)W z@0)2xrO=D^;v929_6GN+Z{|p;EQ3TWg@$ByiFqaFn3QC{RHiqT%=Dv@Xj9XXPR?{A zb6iTIA+c%$STf6^Q4g~gej;}D4#-MmIXLQ2CD68Z%5ZyHS8geRMl?P{V~>SdKjr}i z_Vwo)a~z#T5?%FT8~S6Bx<&^UJljyTBYWydA=8~kMro#9xlSXV0QzR5>Yvi%K0MQm z%vVjLK6ow%(GFlU8f&ySL8{kS-K!UvfNEWO(2XbeLehh+bJU%^1a!X}{qAT+`uI9U zYG8W7yGAkl3D}8NUwDj86r=qZsgFVTjkkCBRYz)rzGTI;D-lGT7lTFs^>7=n(`&77 z+ZEQ##%lq}^zMwTKigbYef%xiTJZa8(X-Cq{MP22(=3~Rhw%)n&HquGW4*FD)VOAx=pYTi1{^cCVD7SUgFeW6^FNuvte(<``NN!MFn$Q35&;6fyKfi(emA<=C8#xHAXLZgf%`bEHZ~xU@?O5tETePp#2Bueyrd zEk^nBxL?i`V~lJI?ipE&8iRwmUcJinTvyVpS$ICioSM(6>V6W&QT)TPf z%$S;7HpVZEshNo|6dcMOUYIZ7m1u54^X&R)#y>1?Q6amI*RL_MJYv?Ie_sZNoQ=mg zS{_x)bC6mxUdGpq!8vNbG5Po#C zcReg#OTDw-V(idg<&|cnCC?@Cn)5g2JVkPrc?FsST_U^odSw4n39hz0nra-!c%}cG z86C0}d9`^(8qIVa7^9hb!o1>qVmNA>gN}tBwJzD1$~k2`RDWI0S=2eZ2HJs+ud$`V z%o(p4IjzjHkjF|ENv-ufI-h6Sc%>D_@%2-hjbrR8pFQ&X+&=VauSM_WzjbaY-l^~t^Et^+On&#-Mdu1X`S-KM@8=3veUMMx zv;2+n;#r#@1G3y|a#qWrSGcC8-&-a@S0|2mzNeq+eCB@?c&*G&zDEh(EnnZHEc^Ld8wCXoGaFG0(X}Y+WmuQC0Q=CD zD(lcE=zN6Pa z*18=4>d|nW!hzrb{28uII0!Ua^fkS~v1ABNvVJ9tE_9Xx{maJ((9)-@8z2s|;a0=N|t<5|WJMj_b>f6NC&3q~Uu1*5_T z^v1-l06B*K)^IPl9^_ag`gdF*avLOL@%v~)Z;NCbJV9E|+aWQ&=6aLkkZgyS$auqe zB;)WEy@4G)0m*oxc&`(I*dECQJWQ`)P49qYdpHVSqqk%HDpvMR;Es5pUctWJ8PrRq z7yW37m*$OPhNaa1uVP7qGx5gS*6&slI+8ni9J%;S~ClYX|OyL|>k({q2opFFbv&|F;j4z485N&F>p)-|vfjAN+$_ z^ZOy+7cZeJ2=0$$KYWC&oCUff;4JU}{EDs-cpx|n|Dvk~9t7%he4O6Fv8xFl0_vAE zMsg^qr&3SAVc?5MMbKoP)nr|G{zKv3OneA{-AMhtJj3 zW={Z*$2aQ=vnPTl;G=a_*^|H%@!A@3IXQM+)syL;gooFaR!>24GCp5@45uPF1&^?v zhSQLoia%I?!|6y)!z+9Ty)$ChZ9Nk_0}cq8m*#?J!Y?4p(pmK9!aHy)y|ZI^9X!mw*?;zW^&9cqKlK%VIqlm(jlzz6P?$LA@GR#Fyd2 zfWraShAU(9(XT{u1-uV3R$YbU%J}NoHFd8>a#egy>{`3mAh|leHa7SDS|r!NM{ogN zkn50K3r~T$@z*1{4*mlDA2%Sm9$tg<=-n6_CAtZ`5!M5Fw{8Y+f(^k;{ae7BVM#a} z|H!T2EwCrZ33MBHE369E1KbYY2HS$w0(XG7!@{8NWIlKY>roRY2h?D6pjjd%^N`DEA1FlzkCz7Qw5m*gz7m_<+DA3n( zH^~5@p6COywHps0zaQQN zD?1)U{y_W?{RiWR!G}O2RgZu$EX3A^JPJMnFM}SM$G}J7Yp|kZSuCg2GWw6f>|h1T z<4Bgl_;3il<*}>Tt%zOgZUz12Fbf#dT8U%@j00A_tU|I9CW34gJtV7ODA1Sl1d`P- z7wE-VgX9Sq4XmtLi)0N<2i6^~L$VeI1nY6uBUuMCf^n}6NY=xcU=`0sBpYB-u<~aU zl8rDd==*sR$tIW=^!+@Ajxc=ZXNS=nl!PTIjMe+>H4#vrzL-H() z57X&AA6u{V0{A?f0@LWd7`qDLOW=zz4p`arGWZfq1e5U?y#l@rLxFyySHV}}S7W_L zuYs?|uf^6! z7!6!;_ABs9m=0Wn_G|Df*bs)(`zAJ9^qW{O%(wKvfiXcF?>q2Ym=yG2eGh&I!@?je zsvp4bVP234_DAps7#Z|(`~?08Q-hw6pTVDCaL`Zk3;1*VORO&?O8T-NC33pPAmjmH z44OZhCVIS5`U&g<`hEhE6jlPgJ|&O@*b20`OCl)&i-CTfQb0FSOrc8t>0>3Rk$9sb*qEblIn?;Z4IzGoC11mYJxT38qmX2E79{) zi+)X53AAZzBdG;jK}&jd67Al)iB@r4`gLG8pk^7q1Fh)#^y|TcpjFxcNqzVcv|1Y? zX#j6R0k&Pqaxl zr@t9o2G!}cO|(hdC0d~E=(mOYK-;rDl6G(+RK^nRfTTTK30jmLk#vAVA+sfsbc9<$ zYpWBIE#O?x+S(FHC%72Q>*V~8%To2|tbw|=I z>5-T-)dNZQq-UZ%)e}jNq*tPy)eA|_q<5md)f-8#q)(!S-v>$Wq;H}Zpf8d>Nk961 zK}>|GKiDtnpPWZK0PLR(NY14l2o3 zBRLa1lf7Z|hk~cm4hM&Ur_qi`PNf~eHar=boSd8jo`P&7+lXYV8`7WK41#dt=zPPR1s4l4HSRk&R^=lWddBMz#&x*ks$} z81}Yh+a}pAIhwug*tSi^B}cJ0j%~YSd~zgv2Z9rmNwgD_S>U8(7ure50pKplWZGSl z{lUq}6xzwje&Cd3D(#eHUvO$Njdp6X4>&EEPCG5x8=RiZpq-xV1u8v`#Y;s;T!@&_)V_r>W4H8wLUjkceWLyG? z{#GO7C6Tyh$|!oJvAagarRlpCnpuoxkZ9wN!73|@qzu>lSZuR$NXl{_jHOor>uYRW zfxgU!<~3GC;!2s@(yN3GwryM)^gbJhomK_({xh0i74*I|nqLjHMrs1R>R4hE;u@fL zwv2H#LGN`l18RZJ0W!?h2AvzswyXnMDYY}bx>#j9$MvwsCV~@VSEDflfl6rh8(@j; z5;s6%rPO44WXWKyHKK2&)YN!NT!4f*jebGY1gmUn+=RaC)tc4N6p58mW`{OIVrKWQ zSZ>XcSTAJ;Y6~P*N|}e+5=jf@WAi3jAu;l?2ffx5*7&JwczbM`5}30)6(%64x8_nQR_QA8fN@z+;g1#WtJG6MZ)O{jkmE@Qk0set-Ht z^UahQ0QN^0FkfaMsE#0;-5^liL6*D0pgM)@cSAsR4fAb=g6bf$~D{4b}^db#q95ZRdxv)rXj+ZBnm|1#C>hQ#Qs40gLCkpo<2yFHLt z^)KVyo=B|sza5)xCRW+);B83v!YaEX-V4dhXm9$~_{*rb5BE@9Smyy z$R~F&w%OhBA)r=~%yWl=+DtOi9R_Mk$y9eZsC6ZS-4UQxm&|rYf?8uT-f5?4r9F)0 zb~LCZ_Xw8TF`#zdqgZaUL9IO*_2yueJqA98^jK`OW!Q(y*gp=d>~ZYI$Jsv~t86*; zn}^=24It?qaMpJq|QXkV)scO|I*Lr%M^u+82A-$Hsdw%ObGP2Ohz8f>$7@Ta`P{?OR>s+z&rK>`*&iM{fO7>NA~Z+ zD*Fj<+E47?jaBwDUbdgvzlZ+a(Y@Gazu=Gi1wY(UaWu?K=NFT#0 zE0a8i#GLGMSZ>RZJcd8AJeJ$zNS5KPtbpaV9LeK&G3CQsfn+(}%}Q8qE0L_g_gNX6 zZ50x8o2p>5twyp6k7-qGHnO1DUxRH{H6iny{k7O;)snSH*5GZefz7rK$y&UyHL=;& zBUy)cwiY(q1|;k8-PVRTZX=Qn_;lry+l0g%EP3XhL}C_uJ^1IILh>ZOVR`AEM)DLs zWBKZyLGm=dHrotrgY<3s`sv%kIrk1$SzEAe@-`m*_OR2vi^QC`4p?sQA$gYwfNXZ} zBYBU=fGl?(AbFp-K_@J?50O}huqBq;M@T*-&LCUf$4Jb>>w@L>36hVAOLWC@`xMD1 zL@K({`wZKxYw|g0G(%3lFF<1&J+R-t1dVv~#D4nCw;Kr zz6Fh|^u>Pr4m94<5BrTc4Ex_>vGq%S0FBZNz+U?iGcsjYU?PekmedW3b4|#AC6-${;uYaxA^F@iy3Ehb>kCG^#cZTdX2zv~4`LSS8RX+yrc~%AnD??Xk$JfR%~b?SMsA6*QW+ zBNkaT&?w(dSY*|~YQ+C`#v-c$8XKI5Emkw0gcVkkehngsyI_UYLP9QTJQ*vjHj-Mz z8>e7})j?95IOJ5Uu)0X<5TBfe6;=<4`K;5i!s;WjR%ixRSOX-+Gk3)bYlx%)k<8ta zU6V#g8pZ|j?pR?3NE*eB<2|s&8Y3wnhPfxUSra5iHut30G@gmA)->J=>#Z5slz8Ue zSar?8X2di1!P;v9Hji7x`(g#Q1dVU*hjrL0-XD9h75$dPGY`OyY>lK9@yuD+mu--= zCZ2g9cIReD+7Qn?2zzvMB-T(JM6X?ZFxF~2`fZ719)cCy9!WbQnTKN4c0kgeNakT! zyB(2qAd-1FR`3=`Iugk|oZgo45!lFE(zlxHNNnfMNQ`M7g;m`Ji80Niv9`M+F{XJ8 zR(Llg#x#$i*CU>djoyR4(abs6?mdwh%{&&Hz84asna9%W1NH`w!}{+F_92>iJU)Pa zVBff3d;%VV{$Rhje|#dIg8^XwctCs-9)*FRam($o+^jh|+Yz}&jd$l$L zz4pC|n}XgMUfoT=#@shv?~TC%?kDeq0?^z6?~g{HnFZcA4Z#N7m)=he!1~;;-eL7Y zGZ4K0>Vf7Tcwg29>u}$DzrvW$98f2_k86WwA$Wh+0?k73zOM5@YDtlh}g!wTVnLWpR^865u z$ewRLk-m?HXU{#KRNqCzvge^suy3QG*>ln-+c(jW?D^@l?(1l9_FVND_*FD0d*1qN z{4yGtJ%pV?T@fWzTb;y`S>zH4DLK@+Y8K2tKPn2F*h7 z8U7Jy7J|?A4?(jKeCB@untz}!@IGk%fjYu_p!o-C5buKKAE;Tp1Db!J#_=|&UZW=R z7HIx~8p@lX`3Gt)Z-8n^YBaBdYENo9uYqb+YCx}oW*(>+y#lI#sVlti8wy#T7;sf9fcs`sg#JqM~4s|hJnFs3B%Rw^_)U_W6%{fp9Uj~|Upl<#cXwHE; z`=g*a2kP>VfDdCmsN++MkXaS#{?s94HitIBgV+J)9B3;%0Ge~44RJqc&VjbYeV{o9 z+8p<=uN8hV zs3$<{T;_Un4z$`Y1oa$f&0hfOQP93WAJo&J-G3fvw!s@ja?b_LHh3LB!8}l3h5mzc zKz$hc70w3DHqg^>7O3Y#55!zhkBFX$GeJEidMwTW^`PjFy8|aBS9yHrP56y9)*#>%Ujs@pL z$7X(=IpFMQPUi2K4eEK)4|EKuM@s+D(V(6x{YFQDda(2-9SQ2$($91RsK-nH)8U|= zF#S@8fqKaFR~-uG*#^sKAJ05$`nL|or=`D5kJmw-f=zCqd~pqdaOr*deik}Zw2aQ*TX#$)cdaIdjzOgUXS>2 zP;b4S@?oG}d_CwxLB0EW)`x(4{q?mE28{;jeIEoGCD1EB5HxzAw|)TFKN^sE@%w}Q zqW+n8zaMCZfnNW0x`M`7jAnEJ%`h;^(HS%vWAtN7&?wEZ@f_M?v*?X6lP!po7}YVB(h)S; zV|1khXcWk(OMB4hkkOcSpiv{EG;Kj+N=9!s2aPou)!7U*24$S54QOtG@t@Y9F)O1( ztw1vjj2g8B%`GsR)B-faz$jC5(A)x}Pt8Dc3yexN12ei!>VLs}W7lB9PPKskGCw$mG;`3hh*4mDQpt z@nqU5Sq#&NVwGre7TYw^SUK7yi+LJ>tQ1YkVxh()D@GHEj#i9}SXKbdEijT<9yGVW z2xmFa+yWz?WkGWbjEI&2%`GrqS{gLBz&L6t(A)y!t0h5m3yiy#0L?8hDjPtf!A5Ig zwM2DDBV)M<7)MEDj5h{R`6FY$5qNe2Uv4~#c64m6fDz-fKyw9*B+muS5-`GiCRl;* zR+`^qj<_so@Tu^N%5i1zb|6LtS4K+Pg3X#Q^URy`4FhOadUJk7Nzm-|<{Xn1yfnS0 zV6&)ZWUY%;GS#_aN+Zp=^lKrlO1~y;W8_U3*NS{LRmHTmBdfG(N7lMnc~ga}sx;?W zc~gO_ipn9bk2>@l(zni~0k(4zhgB|DX?TVyZj?_(tpZ-{M&W%&yRKSd;I=+lm8$26X&13fBqBSBcJpC@%g0a zZz+C{Tr2VZ&!50PeTx6nfBpaX?ca>~XaAY!UeOWx=ikHe{Jm}^N3wOkR{zSGoURChmYuFoeDqR(tG*q3q>+);XiG z)>h6xZ=JGr=rZ6B1+CMz=G=;AtD9xNZw9uYwT|1`Vr!wb#jH7Rfi!1o&a1O?26L@5 z*O|)evaP|+nVq%Na^7dH2WzqaY`pT3a$J5tUfQybTJ3Dq94|*IuN%+Du5i=}$15Kx z>#`lizcyYCejP8@oA~SFB%>&ZkMy+EuLIwXdYJ)jebi4{j z$~thzOYXKIj9)%#MaQe?7!_8Y%RQ2h;9riEBbamVig{(bV^=t8R@3LT^Z5umYF55G zE{>gdS6)9alYq7KA-l7@dmN)eo^tQCKe9R0W~99LayAFOKsBPk}W_V(VufV$ZVc7I~1}xE1?l!sL|H$d!7&>Z0vwKNCbjPwNk3&&@hoU?VIZt}d^57Ub zQr>$-*>P9P~fs-URP5JqLQK953%RN3xL9L9dlwhE|M>K7gEwmte+akNmwxH+JS&yB5>6%=@dfhs) zxtf#Sy!ITc4tAj3lB2Rr)uGp!d#Vo4VaH3~wR2$IY&@JD^J zYTb}Hy53)#v0pj+{qi_9K-!(VsX;bJR0bWj9@!n%19^9TjpOB&SBX2T5yuMHdU9v^ zODnKdm5^=7v7Kh*bG9!;SIJx8iHX!M|IHeZzGh)g&7 z$jh+hOgF9p zI@g!rO3KH`zB5J%w!ztW)y~GI7FdgY*;Z<2<54pkI~h>bG#s6}prhy5)yT%K17or! zaz~1qyKF3F5OXHXHAB7fZ8_?bIoBS$AaSJBs?-nFE9+;Y)*u@%pUKt;$w1Q}8?}bn zc;w@?8KdGDx;j#$Y`lCvt98f)+lY~H{2ZZNOKin>^klzfHinK+u5YwtBziGoj*6P0 zPk;3d{nCz}W0a3q6Gld@Pc5-|HY!w_W}~R4p*E-{<*3QwqTZ;c(TtJm&k;vWE*P~@ zN6qnZR2?;Sb+ur*+XgT`r8p(-x^PW0S0M9#?ZGCGoA;}1 zZn8=_@>IIA-Jq_ZQ`2-rmHkjY%eKeG92vIukvSDmPiQaiX4rd$2f9&1b zBD=?1&>PNw@0`$*&1xxUhE{A=OVyy)CYwp9bET!~73pU5<(BiAzB$)tZIJ3vt}JJd zwrs93<$TeeIifD;m71@v+yRMe&N)kT%;p5wTb9+%=j|439l6%kXghJmG~y~Rpw}66 zc4|!Ps&PIcyzgZvb}sTRH(t>-yJD!H<^B7E{*SKFmOmQ?@M`Zt^(wV1pX0uxv%Pn& zbGoci&i}q+KHCrDnsUv9W^BW=_aDyx zU|e0Ka9t7a2{m;Y=)8NJ@Bf)~D!kvFH(dYrkL!y3t(9-JVZHZV|2AJ&BwrUx%h!9j zaCIy#R@cRHHuH`Zozv9DMCYr*SXGo=f!<%PFyKq4$?7>iqS!&RmTpUt!EE(EH0Zgty?j^ZrtUcilNxC-VQ= zlK;#5%N47v*Yo~z4Pn$Es~xJHZrnrpMTny~*` zP0-bZ{nzsU&`Le;GBsY;5Oz&r|2yXm?=RO7cHZ!btRCwc!mc>xnqtly-VLrH?7ZPh zQLf42>cOrfJS4jhhJs%E-VLrBY>eOgz;%PY>I?6${Q7VDH?R3Zn@xVhLL1xh((3j( zQ@Hk#W0zm^|J~YRj^1Bi?O7{Ue}s&US^YSBj+f6SpPRBi{!gzhriaJpnrl9LoqPQk zt_4?gEuF&Eo_#v^&&JT_5DeFBj*mVWpGmIyti7mLMbtCns1>e#Z-%Cam!bG z{-0P|tWdAkPIV^D+4u6REZ4+yyGry5^jgd{`uu9mt+d=G5WSKMZT5e4Z87hzoO{vx z&l$`ogFY?qO`jNl-`ZkYXwIlI+_?@=&XuTs?^9S!SXMWg5!Hd!>784gY2=*D{Tg1& z+Q6bSQf~XI)0SZN$}MAk7tUpRsanxio#kEj+x;bLYSFc-^h$Y`xu&}RdEsj6>X|-SWNlRo z&3&0_n7^%6rB16>>6+@!j{m!>ssDC=sVT}Sncro9et!+m=EZz9b!SCwh^f%!C+_N!{D(fjyyi=CoqK)84yGZK@J8teRUtHvK1k+4E`Q zI>g>(K2xePQ)?UgG?9DRyUb@wb*^$XH=isuxZ2g$yz*=E6!9r0=X0Ix$>OTRL+Q)y zESIy~&v4iP%3J8wl^qj%XDHrEdxlc8CS+wlHvz_D51oX2h0T9Yg3 zowzNV4B^{mXr|;i_C#mvar9hmWgGU!Gt#U@#+fnzB(xJ~wN;+I#zOCzJ)ta@M}IqS?Xw zvAOQg-kh@^G9~(G_vdaY2bSa9{n_>1bg<)ygrisZr~BLM{(a)0xNO+Xj;(>?qfKkJ7@;$F`U~CG|T%K zjvo=t=B}>{YGur(=NbX#hR|-c0$^*vQgFb`qH7?J}E@$;hE}+*RJfHSL=Ds>$9gbYYc0PC^?Zuoi0K9l^Y_B`)Edi>QvMOY1sa7g0fRG3Q)H&(*vxrM;Xvv@Yn=@N#;WP<>%_g)50& z5?#sJgTRdM5g9Cxyl!B073W_LTB~t2ZQ&Xi*Kqb=>OHQcy$0!()PY#@aV_V&j+h$! zwan5Ds1>;u`SonqfYyatZKD>c*uBGP0niAJNyOvrMYfWxq8v@?Q-c9s|Qm~Rxk=IeaiN^cmIFa;dHjb}gs6*9Nczn$$CDrc;W zxr1#O=n89h&>K#5O=Helz;-)0pLQX=JHR_Qx)9mzpxNt-c#bp%wO$v|n@=T=l{&6d zGM@^c#q^i3xk|}G&R@bd5;P-zDX&@t>ib#BQ>YneCD5Hb>6(L92;E7~3ZkX#-G$uB zBANg-`qn?0KJ80)4*sW_HRw+2ylYAYbpG3fH%q zLm#$0YFULVSdF4DTfW|bo}64CQ1|G^X1r2;pfg+bY>qRkqLz|-8l4}jGdrpqJZJj1~=oFo@{jutuFP9mRyx>km|{9!*$mfc|oS76wouClK(b;iNCN` z_REc=_%Ha|YV*I<$eu#}d+pixcd9A*Yis}4fA0UA|3ZIj(M*8O+3)vvsz?21#~M%Z z7y5gQoT%yLex&@D%8jqQa`&c8f3qxA)^8ZBO?bZBjeVbUZFQKx6joH_3;+2Tc8ftl3$>w zt{Jb$S4gSNcP@e4l~T-@cfFKqpuTi9u~z)vQea8WQHyHDo!N{tT7y;j*UBKN!d_MW z&9d|>)33t+UXH$TE+b^Ek!sx;cgZ7WM#d7poByF1Ft+abor}uzqlM@Fc8>W^F|Y7^ z|4Y~ZFv~SzlSf~U`kcq#GmRbp@1Ns0Dg0J){r}nbDSA$+>|e;w^w$-B=l_&*{4G`} zpuNYd!M3XT0C$3`{#`hgH36>b976v z8*TH@3|Vuwg0OR#6efbZ(2n9&!@#X*tAxs-QYarPh6-RM+VaRMg-)Rd@6svsr0qm+ z%g~E{r!bV)4GUYa*C~vqKQ#2FzXiBO=oq#}HZ)8Lllhz}Y&(ZWp#|TdQD{lqD72z& z#C}2O!z((54zwM^7+yCN92$m%zDPQRhMd_5Y)#u9S%f)Tdp7v_9B|<4eM3v`fO~v`a!; z+9jbK?Gpaoc40C9aC@*l`-?+A_7;c!w2Q+4+QnfY?PC7v!QdeF7SkI9Zi8%b*p_y2 z*p7B_7)QG}jHf-E@3$9t810vQ=daQ?)A#u8Z>DdjZ-MX7p2B}~TsS41%s+Gr+wtL4 z+T+57;o@)+cnR&&@J0H0x|H|$0!(O^hLm<`2((K>3EHKhB<<2rigqa@PztQYI4ljd zX_xZ9)COyEWGTO}PFNHs@EsR1eiOjM`JRiyZj9xkusiLdum|m;uqW-JFq3u>XUqhT z;M_&wNZLi=DB4B5W_xfvzxg!2`*Gn7e&d_z8|nMBZ=@g4zL9=NdpgIC4X1O~ap83& zZ=|oMAJIOQKACPxU!(tedIo3A31@KDv0;6>G2M`^=h#N@DcZ~UKQ0KDg-iKYE@Qhe zTuysIxPtbAur7U?v(}~0(5_3LrCrDV`t(YUUl6WjJ3rhSZV$JCchKG$K2JYO?+hRD z*?01tz5u?Iz6idYz68FKz6`#az5>3Mz6yTKH@!1_l70++ntlR)mVTNp!87?)3&UL6h2bpPh2d=4h2b39g<&4;Le7{I*7D8QrEAmY zXxF6A)2?A#n_k5)I6qv)c3yZmeJFh}y_&uA!qsf&h9~&m&!m3M{5dG%dkdHOiGB3%xyOjm%b(v{%qbQO3f?Sh~+ydY@#E(lt_ z3xZbf0)Fwluz*j#3A~oQ1>ri{1>t(y1sq!l-oW01a3k#kzTb^u3Gccz)ka2|-o`h) zF}*px3A}~22H(9B*0x@2ZSKn0-!+hEpI3@*NN?vAH>7va-jL3xy@CB3)50qCTAXt| z@*C3Y(*?BGf!BizY3pETSHK@&UAsQt3ZVA)wH&=Jm2q6ZpdP=A(hJiI(sR@E)APU! zXwOYAqSd-@ij8jk%Jo*8MR$iQ(#zAk!;5F&h;I-*B;KKA;a1oz# zcUYV*0+*zV!MkYZ2R#JygT8_JL67nLpl4%#(6cc==+T`Y^oPt3`a|Z2x_syPp)CKN zk+`OKi`szm(u?_y^U_Ob=cSj@&SU@FbaRe1!TYos?K$aX965(=UV1j)`!et{_Kniz zkvpSx1-yH^%azc81 zdR%HGv|BVgJ%Rr0^w@L`cpPnSyj0!rFd0oXD%umTlRi)*pjUIo%ZKgXFN>(Xh#!A+$y>!oROZM-ov*$1H7B| zo^T3h-xH2V4+oD-j{uKKj|5NUJ?;sorKf_Yr>CWxLPvhZrqG}F+!Tx+ZwkhZHw7cc zn}V4Un}Siza-s$kvIP9iyDE-6It@&PC;T;=- zrhBFPbLL*@KIz`zzO-YBa&ATZaw|O6#zT#Jj-|gX?Z{{*=kJxyOb?))na-k}nI1@M zBy=Rv%aM4y_e3%?-7`Iib`Nk*@L*aaq$7xSj=+yTo>nvhygNttNOw;Up*1!-jHsqj z;@$X$hork9-#wj5d~tHLQ#vu-In5)F_lBwIl=R*(Eu9KZPp5(Rgx$ay>2z?{bOyLv zx@)>I4CVK33=??Ijln4E#;^nN(~ZIS>c(Ikbz|6>=;+2^>~#Bd$8?8u`*bJT?fJx= z(iy}ojcghzok7$xk7@2gJaShg6F6u4bV53bc0#%f?SynPt*ch=LWFV`BBIMo*TnmT*#5)` zkEA`C-hSXwwEZ}ze|lf&mG%UCr@g>FX>YJ^+6U~H_60|${lKj`_r5SD-5MO5jsfqb z-4Kk~ZU{zbHw0sq8^Ubjj~l`q;*A@Ek;x6=IO2^P!an>D8^Y0i`tigTH-sL%N6*x_ z;mJ{_v~#*;YQ*s5s6)C%+A-~rcB1WoyiJXB7R0k&tdNb@OZxA z=A6?u-JI{)BQ>hHA#6r}^VE3ahR}xoX6boE2RDSvvuIwUv~gOH8o9ePs!zXBT0d== zHUJyZ-XB_}Ey31lE3i%48oZD8{?H+*Tc z(mH%*bFex4*Kx*0#PlxWldj|3i?e9p`cRv5>ZCWYw?5ROUpqA#xIWaRUn?~ZxIWaN zUo*X#7~lF(oqmnf*x&k4jehmi*xdZ6Tv{P5pDrTeHa{v&zg${6Et{4B%h4|RH8wY& zXr2)|V{l988)dsAD#iJw(^6?g+EQsH+EQs{TBB@t5Nk6|SQ1I8v}9U^wggxbtV(+~ z$8U!R&=})AwBl_<7XwF2q#>%zUf!@6)E@3k)64@2R)@Bo~J>%xPu7_JKs!E3lKJRCg) zXW}yW5x+^kOTJB(v-eo^CH-%bFO#p6ufT6;SHiOR7z~V$!JfDh_QmBeGp?k+n)cD? z3(o&C`6BtA_KV~P+AoqHX`kTuqi{Pu3eV!_NWMru=QsSAdUNvewM6bZ(aC={-?=$m?YPQkLiDsY=B{MUHFLp$H_*RC)b7N;kSG? zdLwx&c{6zd-pgmBSCY5cdnI{?_Lbya+E?Mad>TH@XQEf5my`F9z0CGX@-mWFqL+}o zoV=90Px~6@Jq07@tF$liUeACp!mRlcy_dlkkiE*gzmdGk>)!%jPhJDxpnaWJJ_)nu zYqT%&ZZ9Pdh6nhr4~F-X7r_sZJs3VrJ^(*TK1|kzP4H;04Nt)krsit7umyPjl8v zwpGbjocA95=U>u(!K=Q6FZ~00Un6}Ne3#Gqn&a<9D|pq)WCfr5bn*>H)`rhG^K-b? zKcxK(F4hmD2@O{|@@|VMDG8 z_wZH8?a6JhBsZYnkgaljb#fJwtJ!W%uH@)d;2pH}Illpn$<=7D;rOk|HObA%P2erG z*RX#J%*zdVhem9b;8U)~*;nvccO+Nv4p$~OaQ2NbCf9%$xh_ZR!L3}Kwhmj}_+iHC zisWIo%abQUBi`YOP>FB*L@3}Lp9qcP0yvjz@`_q)b>eIJ%$t&HdDrW~n`kfN)tAE% z-I%j$b5@=BI*weQT#EcMSfraEzl8p!uuC_ke=+?_l8eBL;ht`Wq$ArFFk-iWg}Ni# z6X6VwUc_oc?ZBBGVa;wydm3k)4!hZz9G#n-&#G#3lM86) zvVQ@5+?_bTJ!f`+?fciuJ#8+> z&tjVg-*;!u-wcNBRxoaR_BkAx2OqZ_?q}0KCwU~C1Y`IkK@Rap!YQzdKN23MT^+i@ z6uvrigFAe6=)(IP%8?V3A@GW?4ntrX?-mb@htMBPe@HwS9`f$+c^}HV9maM7oZgS{ zn#0*U0XzZz@nO7Tbr=MDd5?Gy+hBOX4@Z6k9OQGr<7kgy|2R0n9|?yf137b0JUkx8 zs|L^?2>Q!Mf{V9oDfUCkdj>^<0 z%ib=?Cnxd+t_qXr?*dEtZhXo_`je6=@nqz(^o@bhd~X=fXL5XR7|wU6CzIb8nEl4^ zUNZcR%Q(*WgvWbpUcC>m+!s#8eQEcOr(`&lc5iz7!1MiRme*&R#GsPJ@AQRQ6s6!0EUu zY(;-mBG==pFp~aO$sU{|ALDe|m0=e0?RbwJl3n8&$R@y6z5}f0JHT>2p8kYnH>7*S zyT!ZG?oPW$#%MksrtZhWqoF77IWjp8Udff=IG849!IpU({azd&3A6V|Sjdk>ejIF> zGEw&6RXvjvIBR8?17qbuFlQdbvEH0J0#@)5$#8hWhr?0chrQv+Y#1&Nj%Ty6@)!)| zgJBdOO52w+hJt-)kKvrzad+OiM{**}oh!r9NRElSA?co+1h41H(3O6-)8f>ZMlI5`i2qq86HIykui>4k9%&T-Ytmb7wk9vTl!`f+q1+o0rp z&ba_))C+0PgJD!$8P13M^i=j*^P0}^ez&4+L)#fX@Xm0NH&2#@$3kK%X{#Wun%o4Z>}7D?uu|DuaX7#3ffAXQyCU<*~x2hMkBB$?F}5g5hmU{IKKh1 zhOmDx3zd@Vk>9{NZ?e9&hk3mt4DB6ZZ2viaJS+bAIBrKf_MEfX{n?qYr}fX&-^rczO7dqd&oW{0RN);w$<5 z>)5V`rPdX}+wz|6lKXkBoW=`jW4>tx_`oCDA9(GL@FzdYYZGJ@;0&(-U-|dQe}MOR z5wEz9?fy80xx6gw;xd@0oK-&gj&r_;4|x%1EaN?vhbP&df=T=F@IE}-@6$dF&-C)J zDLeKq`|riI`L9@U2+8B&85pUThj)<6v;7RM{M?U+dw9=#VW0Mu&mw;Z=Iv*}4Sde> zuz^iJYS%I=!*?m0e8g+MgYo-A+UGd)ZP>8ihN1goSjoQyKcZa^ll0@@o{{gJloH+{|4=w@meJ7V0c~xxuY?czO2(ruN9!fmvUgovhko5;4ez-&evS8e9lq=3 z@MV9>Yrlf)`vs&+;fG!vyM}OS7~li#o$TKYoAgrJl1NG=a!cPGm!MxVSp|Rg3b@lh zm$x6C2{*5KABZCUzt`OS-tQw$?A#M|6Y-{JiU6L9{FVxHJ%hGEA zmZL30uOV2Lwluv)U>Vv{^a?;(XG_v+43?rTL9amoZjO6!2*p|0Kf z_q>)ouYu1i$@2>HydFMh8IX6NT>57<*BkggR-V5^jkq=A*3Vl-Z_T_F<1bQ&ZPm85 z*{hQmkiD1`<#Wg@wez}qYwSNya;5?+b#F+DvK8c&#(!DSoY&r3XKS^s)wuE+$ZjB) zL0$!&*GK1-(o3kvemIfiK&FF2jsuwv!nE1L7V<-EcUr|efWTXYJFB~ zzdozAUk_ivM@T+NJ_bKcJ^?>V;1aY1Yd zH1y?^*Z}iIHLyln9juww0BfZ+!P;ppP_B=);Za6uZLq$6ZB}2uHr!6F_ga`FmVs7t zuMJmH0ltk80KIYd7?VKAWXG=LUIXXEis|2YD~+5rMcI2cW-KThVNq!V3()52W}tj48{u2&4)%n9Wn;!pvoT|**_g4@Y|Pkc zHZm3)U=8XHL(7`5mg@C2S=IKMVAb{-YQIkbPfJb(Pftz*twdi#z4}GqCCSC$rO74W zWmLJZ;q{k+)~n|=*m;e1Ub~&wY|Er0pNICQe>^N70Z9DjF!Df4kHe{UnaRWkW(%9wmM!BRAq{B}= zVLl5yC^-;3I5`MBglhIDf|cP4y;1<-axf;VcW0ToM zxX7#uF02r?^0q(qw*zT&&a#||?1YTXY<@VHcbK2CTFno;!;Li`hOC3ZLt)9955w1? z;NdWT&CeLd=4T9J^WnnU6joE6J_(+I$;mF@lw>kEi3;-7usBQst+`%JrT0j1RI(K~ zIvE9Sos0&pN-xTWX0@|5&ws3~&N>ku zd{waWdlePtox!e27qDB>73`jL1A8RhLF>a;F`hkst#NJ6UW?>v`2H49!@Y{i?pyd? zH^TXMHIk-Cnq_scR>Rg!taPnMn=>BDS}1p+42?xO4XvHFg1Tshbpu|Ra~jUi7!R$u zw(hzyZC=5h*KFrphYR36ydJK>>tG#Rm@c5Lo;0P-JFoX%g!CFX2<0TK#y4zA#duSW z7HePvihYmKgzx}|8X<}H=vtd|dG9GkLa-uF8OOskr$Z7y1K zU4~c6j43~+Y?#(yTZwJGc3!z1^Jx_lnJyOwSu*9ye2iAs%Y`i5xH80v+?NZfJzvTG zigY>spXsv?59UJZ$XBwz3O3AzA+ICeScDxluP(NJ*ec>LXyr?lHFbT)f-1vmQFc`8 znXPL6nzm@2bQT#oX+E#0S96tv$sr;mC;TnBD<0qAM^ojIC&iN=_ z6yzaY1aBuJk@0pef}M0Vk{398QO2;kC}UV%lrgL>${1ExP}BZBb@M;QKY%~QKY}Z1 zS7i0)E2vI?m;U=yu&)T#udm4J(N|FA{$VUP>!R>BvUjMMevMk`x6`-MoL%?LG_Rw6 z@xSV-UygHj+V?UR;+&1QC{wL9-d1|QPHQE(_2gEY%U~;y?HlRqsrBbpp}$3Iz54%S z?>(UPsI9i`M>CIm@4fflF$VYEjg2d|aqnPbAPF^q=?M@>AoLn~Z=v^|MoXcj5eOx8 zQeH@a@LiX5o}6<4C%~KUU*Er$*IC-qXf&Ghj5N~TTld`Zt98F>m%&yZ+c$~d&R^ia zdYj`HNXs#szJ7m}|MQjb4tY26mHlJIXM-HFH}O6GV;sK+lPph-ufcyB{!xLQ`7yp0 z_dD|R)wo}e-&~Zv_U6b8d~;+5z8QYuzmoGFHKgzG{Yu|&^?wok&i|J|7J&5K|6|1R zEX%emU$pGcA5`LE_Pck#et(?UZ|wcj{z+n4nB`)Yso5{~{chhc_|y0Q567?n6GwC4 z|GBvsigGt+#5WgZB6v9D#f-GP1`h?4S<><&JQ%7Ji=^dEcpy|QRv~>K>HC9>#y7*P z@F>T1i*<^%i+){yTc}r*r~BrzFY?p(_kM?;*sdEC>lf=q7Vp}Xn6Gat;|Y*2KrRCr z4elbA=UTSwM#M5J$gglWabjnK3Li`X$=9^(&ZVnr>{L9UeEw{r~-Hfu2z?^XftO>GaJOZ=ERY=)29x2L@ z@ksGH_%I%!ov(|`1s8{o#SX>xu$*^9UQot=ka!L*p+pzXv@doc$UNSeqprjyMshhR zWTv=`SndoNG~}yD{Nvq=@|B-g#=0TS zBOHz5s#}W3a&%l64WIZe#bZbx8^*vYeoOIa(#M3caEsqkJc{(uVO()6=_5%W6~@Cb zeoJv1=_4Z>%OPRvznJbP7iF|LJS498#Bn40j2twF5zAdz?dOUeDhJowOWfxCGD9O1VX7ZTrETts{;4C&_2Cw_=$xo>!= zxEY?Jhl*RmW~97F4;AG!dWdsdBY)8PuxD{;aY=Cnd3%Qv7yTk?k>N<5BiWHkJobAO z*Ax?Dk=#Zy9PLHCic))pwVb;(GTpB(E~mB?L9YB&#dXECSCnM6j$Z{mx(FU%#wT%6L4QJMdrIg$=Y%Fdde+lWOVN-D< z>BXd%gv4Vnr`4iRkug4TS0%=)>9AeNhb1#si5q`2yz(+z$!{eWm3&pQRxKnxxVTqw zQ{-yjD{|-`P@KlS7KdrnGd=7ZcM*_nYHpB){~M91U%vh=u=3x=mA4`f;riPm$NO!h zHo@354d$;0X{%{LmVdea_a&CUN*1eG)F+SC?y!SBSezQZ$+fqY?Fu0K)f_m*9xP4? zhZVm`{v^_q!{NolNKYg^31+efNgV-O`fZU3U3pvNP2UDD`Y_JQdbTsMEM{_<4I`FO z{kF&#ejVfF^UgZF(YbT#w?{HS!rJx;U+K0>GRlmL1 zmUO!^{yRDPW$HhR_?*bvFN0oB_y-@LT-Czml&=b7`{hMhX>Ny4@PT6eAcuQZ_#du> zqrEx|Dz_KqK9m8mK5=3>lpC=PY>5wWO=6r+y!0~K++LIeQ6|Kek-M-}WHW3HpP`)f zMHsnjQ09JGqi&GtJ}=aP-LP(`3G2ok#oDCn1etK|fEE9$$ccY74EeRluN~yZxuaN< zbgeRO#2Tb)hB~ms+)+%-hcX*B57)+>1`;1);@Q8BT?ei%%C6Wn$hIF~ul%rZKP>8Z z6lI!eMOGw&00B=sc$goqN_)hrV?E4ZZ{C{zPfHNM$B{omlo#xl2o|@*QD_e}g>vPyYJ^?~HPMEZ~LsShIkBI%c4dcBX- z5c2LUmiYEN!Epa3wY~?>`klq`FudLe&#N4-_Z4M9l?(N~!n*}oiaNu{erItU-0S0s z<#1Qt8Tr~}iT@?n$R_&>;$M}q(#lTzRN-E@HlHH*X?Wy^Mz;B#;CPqg^&NPU2k#l&DMfTFTvel1{tnYUfpCIQ+xSHHKKn~fr zBj5d~$hUr1@o~;R5qa=OBIU+^HuB`&L;k(+rr%Xu2xIy};`_*X9H!xWiRW{?pp461 z_V&BrCWarkjNv`;y(bRf`?=zA*wz)m zk|&Gw?eIxoO8#YKjPQv){yNUcL!J1l<)yxaGMAR|%WtKQyNibtj)2wso}&8$f1h|8 z+~{}1neMq$IX-k7>?une~cNf10Q~Eu~dy4Ksd^)j=_UqtT_sXLL*8T`hyE=_^;eYd^xe4?B6M4uYNRgSI>;QEyz@U5&YkBe9L+LD0>&U z-$B~XU^n8~kr(@s$a;TJWOzTRj1xcco+lRgw2$vi)N(WXmapKRvWnjX>;Fp9s|ai2 z9sp}1^Z1RCCtbGm3*k-wdgS4kpZ$Co_T}MEJ9#J0{d37b4-Wd{VVF;QQ_D3kcU?{UvbvYHyR@dgTV+Rc$JW~PX}>&ne{T03mQBrl zhusx+7t*C&W!*n^X#7gs{bw7IcBk2$NHsg)LyuJ2HyAG#4h;1o%Ahy*iwpX{Zmg+`ZRctSh-C4&ycDlzh-N|t# zw3T}hy3-%5ttX*J>>urs?K$pEKe6A)$kYd!dR1Hg|J2XyZ~gxDds_2*OTV)f&m{eR zpMyQP1=8L;h;-`T?)z-dA50h&--M<}-wL056J!&PeRCQkeT!_TMo8bTVewrX7F*Hx zumNvl19E*c>mz+j?FaRczP%%24;c}Ai9Mzc{l?xiD)JqUioMEyR*SKs7P_W~I?mU${s#`YT$+qGNFNyEO66V)2aSk4f^u2LrRXPeTi|^Jlj>a=mPve^9aYkOj znF);Mj+!gUTY_A|b*spmh;(FKP2N)EQm%H-mq|!R-?bb&|EwlnM{UcIGlr%Vr>*)Apg z@{b`LfyOYKyB!<#vtvme#(b-eb{uybjy#n3IIcUCx%n8%e~a3VLLN)WZxOaJM;}lA zw+TlUP9X0n=ItZ7!rA*sbdsaE?j+6}g>Et@YADB2>SRhBhg7>fnX*SCkK@RFVU97y)Q&TvNGv7w5JAo^{PdEj6Do3YtukRptCq9F6 zCnHbhUT1K{iAeR|Gbwutn%H-uR(3k^*&Kfl`8`UV&G}Q%OTJ5e=TPdq>@;&W`R5YO zKwCMLtJP;tMWflBJDpEB3+awe7f}1o$TNs9;0kw;`9Aes$Q9p57dxMlKj2tx??U2> zqyD2-cn;}{h%bry-zAhd7rpmluDgty&qvN9zKqmG>;a=CayfU{8F?=8f^&M_$i;Z{xaakXnehQ}a#8Tew!s;0A1lTdCnrj&5S_ zmm8`3F7j?<2N-qLyE$_c`@r1H758xFW^A*CTyYL{gk^Mc{|tL z&lR^|h22Vh4-oD`-pkR0oVgQC`T=qt=IBo3om~A0$M-}X`!3`?lzNnV-HX&Zd^B2k zk8#&Q>??C0@nc+bAM#=1A92O~SZt3{{>Ov|u7M)HZ#VI}AkrlJd`z8i4#6dCyVy zDfXv%g8H7P>=W3OPf_2mIr9`Y=+o5q8_qn9Mf!8D);9e)mijNa?suH|1@`)4uKPW6 z-(sxx0cZ~|P>%g*2m_G6<>(KT)l={*YJD+U_%CwJ^Xww?9QEn3cn+V&i{$)~@EbfH zTEH)J=GXXDe#iM&$o(DikHoJs!xoSQYI=?P^+Ucu{2JH1fP9(wPn7)wUX>TQ;&sZs zh*#u)cqmhZ}{E*LH@J~vH@ITa=h4-l`3!hLv z4}YhooSkd_UMPltP*X8{M2)}zIC4*!50M{ozpD7!{)sQI3iqiNirlYy=#3Uy9S>V? zV{lh4Oxw&Mx4<{ z+K~Llgu3i2(}z!PG)A^0ZbM!Zyv6!j+mhEfvDZ&LNC@3x>4W2xHd3| zyk4wD3?yeTp*MTj=-nT}Dn&1Lq!~=kPK3T;XwWY{H0T8%%69>WSmVQ0$rA+6VQ zXHxxHo7su-!w3Udcj-snyKr?sR#1kKvnyc`Ya|1ydpKtXA_sHD2y%xYcO@Rl@i63Y z;!)gjC@V8VxW{Nhm%`}K8M|#Xsm{m|oEbxD*Jnl&kL8M?$f49dmN1<4A6J9Mb2OY) zqg}aTLR=G?$ni+_(izG5iJTuECIx-@lY*S~leq6F)~zN`elmCNRG3U^G%H+VxOxg# zjA2b|5_g+Q7|Z(F6!NEYG!{9Q`lb^mvT8SuI%aTw94mIy$(cp{lUNn&h?Th;^>#!~ zCf<#5lgXb!Je#r;kyE&CHmNDBq0QoMa|lyeXPZs_T#lw9r&6nHZ_|*|xOzT$(~;Au zV?mIWe*t%Nb#Ml?FC=s*ETpXa>CC5$d+W?*eQ_4`?ZFkZSSg%MeTz9Wo4s@9Qfdij z<{;;Aw3Ku6kc)};ByT?Z-?(0|jC(C0y@0aIDX|c_kb5mBv_~!_Zv}NOM$RW*!PWCw zkzGdlRU9p5#njz>R+G0!Si|vB$vYS(z5@r53Vn) zr*wPd8sZI z_t}SQH?yX_59zI;ITruc&;n1uR*pB3)2y%$`|fNdy>DoVpI~27dy{TK33ue#8`%m^ z!hXRuoc*{%TVxyTxl5wl9Zg#c zS~(X@Sld}S4;@v1t8zY?>I!1z0(88U#7fr#R&lS{$VKQ#s|bscD>+)ty_R5=u8vY$ zdu_C=_2Zh>rd~(v9;v0BQkO>yc_nf=ci6xgZRZWtr{7(v9jCQC8@ZBruY&WwHuD-} zMy!WlJ9-Uu>!n|Vg{obw9laj8mRPU*daTv;)UE$~J@)Db?%+PA+RGcMeLs%0pf_>H z{Rp$LS=BD~Cul+MMcrTHXfG_(y}5%H^cJL6v%X&~=q=H9)W8Kx(BNk@+_n_{vpi7MP!jX97@oR)@uGHDJ^KN>cdEV1F4OCII(v0H=^x)0CgY1 z(E(Vl2U7Pojt-1g@l51F+~dgTPdJh@2Vt{Tq3)xYkE>vzYEK_c&{uybbsxjgp;)w9 z(#I0CowbXPBOH#ksttWSL91CC`CA0-Wo_thM?Z-c@(j}3h_#T9MmqbSK+ujpft-^F zTF~0a-yxNDUv+=gW4Xi02_E$p`J$ibb=PNR`nUAw4k+-&m?sUQhWL=Qm$xdDW6R$+0N5Q zYcHRTmuV^%t@Hjl%#k&a)wzS-e&wm$=RAUTv{v=`q_m^8kuM;122!i~LQ>k!+S3=2 zIt!`Q`~y;2&}Va(9}uP>wVf~KUfR*;P^)V#TF~cG>!lo>i*C^R zj<1cZ%^kFswV;1Ut#@xEuKp@gtKT56c$Er2` z1ZgegA0r9Y2u%g8i(cTy#EVk-}=aU+{YDdzA@8?Xs;`jq8bPaB>sXY+3&e?sbg zr1o+lyieU?PTnts@Bw!SSi2t-vheq4L2EVV;UC;XJ9#8hzjPjL=VH{#ifCxbrvA7f zT17khW9rsIPWYIQ3nhHaC)_EaWVDSlY+7!I)WUW*SS@Hh(pu20jB>0st<_wcdlj)( zwWRA1w4keE`_?5@6{+o9kGLAL8uisD)^^sCZa_#DbWN<)2GL%wNxdSMw4L=!Yb_5i zG>-ZqyQ&syW24rlRuM$Cu~4;?n-a96wT_z+w4=3=n-l6|t!hcPAT+>QZ9v^3qO_MA zgZiIHo zcGM?^t*tgK=^g}a=MK~%qO3huYY)=Bg1%_&hUs^kPXJk)et>r#QSE~kd zN3H3>Jy7O9P4xfX?Lepj-+m_;?dZ$qp5W=M_SF3 zqrE(a`rJcy43?^XX|3WR$g#v?Otqc0p{8@M@mQ$Z&@%`Vuu&&)2Qje|uuvybs|eVM zShL#2yAdX1t!hcnCTK5fJo7=IqrnJF51ysh_#*9BlQq&4f-dyQf41= z*7HAVM{kT4v~nZ=-@cSdw(};eV?C(*1%0;r1^wRpaaOCjA6D{yl?XXb_n*6)lQO71w)W6>HN|Hm`K?SdRe z?gY}~(UqO`CKAL63@0^-d3`um!3a{5ndwI$)homWOh$VeMQTjcXSVO__~KrUjP_kl zSc2CIrM&%&;sl6nd}q&CkY{t&;p-_ z6A&Sg&;kh|kkA79H$(^|w19q(Z*WJw9Q)uMDd7YXWitgLk2X z6PQjq;RM92mT&@kKN4EttKtOoft*h$p#}74OvCRWLg0evE%{G4frJncEm^_|h!99< zff7zYzrxRsH;PV{St8K}*@OE`gq5V)TE-bR>&zd>w3MYO>7 zaRT~35?Y`#PM|LLC`SlPBCRjvK5Czcui>*efpUaE!VEk}sdAiv2!VtaNZ5diXn{wW zpX%ao&~NZ4seAD?=qD*51n%SLKj8#K2qd(?f5HjWkDiT$6DT1BCg5q%Te5wefCzzv z7Dxzzgchib6A&9v!U>2Oc!v44K2pELGo+rtyYM7;DWL`QmTVs_kUSn@1`CNH~EKLO^Ul!U>2FcoBbtSb~HQ@QVih z8)63DLGx&Y)MM}tse}`F86Sf)ync-_ND&1ICy+1$dNkg|-%t@VAReGHa-f76(AV)7 z&X&*uO}MUv5O|lnd=Pbsgci`t@fUm#6>$P01QJ>xVFN@9`~^>g*nor+C?N!re?y$W zC;TEk8~Q*hVgvMOj3P&^rV!L>5>6mt1}dTj!~}d)sEipXp#?rFB%DCP43y9Uu1r-6 zO}T4Dgn%B65ru>h(ASaUfzTtOFQbUpL9{?Z4u})TqhBK-1oUs{|ENPK#|bp!9(Wqi z2I~d=1|_tBI$OdC=;;_yDB%PWW+0&jK8q6&KOkD5CccJ>I02CZeno}1g}apF1nT1( zDWL__B%5=*Ya!tT5@w(>S|Is7K8q6&MIc(B5#EK0Xn__5{Tq5h5;j2p#xA7wg?urb zK$(97Z$?50B(y+foIuNh{tf*S-GUy2?%ZP-vOVz^K?{@+0tqcp!U^c{5JjM;qbr_< zUeU|ZJNh?TbEgtcK+Rn5#xP{U2_%Goo{)qM(8tl6v}l1r_&s_d^?`^M_;)w~?WUpp zqJ$9Gxllp~Xc3eU0%8CXLLi|9^l}Ww(;!YDVFpACh!fa_{L0t>(E{ZNfx-A1w9!Td zt+P>~4fifb3-IL=R}UdaZ^r1Lg|a=gz&N}T;snGDh!*f$(}Wgq-M=zsAfW}?aX-Br zLki*q^m6C}nL_w9HbBgP2!SzpG|I672`x|&A)t3-GQI{^{7Yy7EzMa$8*>)FQD2Al zm!6Ix$Qi_<1*RZH3w$0itN2{X`*Ybv7!wBk1hEq8q#8}Mj!i=Gg^LdUu{bLI{Wr zNH~Fn4M;eF%GiK}7WgbeKpQ#X1S(fVKn-kXZRCrw#LvNY7AbH^ zL<=N@KtcVYyz;Jwymx&I-M#fP@gZDWV0+5dxwGzBoeQI_gUZfrJ(i6L16e@~y-o1jGiE zBLu_;lw$+#i0Mxw1nw?F2#6H8C*lM|2>cNHH6a8NHb9(!*nnHHhi~H!_j7a`>+uO8 zkgx&b1U`)rxPx{2gb)xLASNJT14PWF0}?7ggushs zmU2P`B!qzWZ#g!g0k*3s1hD~1aRQaG0ip#&2>cGqwIV{`1?o;XfyxL0t=)>)067h` zn!hMQKzzWf*tKs*DK!2b>*!0oV&6E;A! zfCzzrZLG~(!UiOq!1fRV<=B9P7Wlu35D*)XZ~_S%kZ=N(5dvZZw2d1gMGJ@!Na*@6 zhY(2E0C55$1e#zwS40Si3aE$^=)lpJK?rn?HgduSR74AuZ~_S-kkA63#R(*YfM@}6 z0wU@YPC#rxMYMnjff6<#;RF&kAmIf5dk6th0SO^61S?vkeZtsR#0H2K&=T&C6gyCk z5D;CT5CRDskP!8i5ds6TTK``_2qbKPH~|p?BUqvT?;`}n2Z*kpj?`+Ngsg}Ym`Tom z7a<@vK)n5Q?phHcAR1sdY||1>Kz6PL&-;tB$u0^GO!uU%N>^?%L?;smt%bAmVlZU16iuP>4kEzpzWsz`AHuH9FS zYxmWVRk1*NWA#*zEBG~#;smtLYa+!7xPo5`DNeu@{Mtx)AoL{Ej%)XIkhRh621cBK zJ*qC=qCu>;3?@|{DMCOGQhj`3L(pJ$A|>mCJP?i>@(Rc`kk~sMEgR#P6epm6vI(Bn zU68}bZAx04fZo?;1Q7zxhRq4$1oUsWz|%bvIU=G3#2>aKh!z-4s&(}6w?>B>LwYp1 zZAiDqlc)9w28g&VsW$k)#*=D~l(EAVoDRtLNY{@#B4u$c*BE z$8YwD_#|YEs2iWcIDWlP#TM6kkRPQ(d_o<_oe=xRfY>+c#HZs^@@dtg5A}<^$i8F0 z=|t`%q))LXy{&KTZ?))g_PhdTCLw*A_D_3dAI=4iWonQOC2+noJ(uqikuqguc{oY0Lopa;2CcrSYJPWZ+Y3BE7g$+bOFd&y%WuSn`=wnWp|YP-ZX zvZZWETPpQdTS~T#)c$j=4@+a0qnIsW+u4$7jIu>+oiv&`x;c6|hUt^E9gF-|_J>Y{Dg5WYasH=M_#M89 z{+h}BR{wK<@g$yvzs~0|k!RM9bX&ss_+*tnC0j!2XkgnYed@NKaty6yODk%A;k&S^gtLcsXT6IV{9*?0P$Y|pigSK%U;ugq8^ae-v;e;{t zgGto0E2&Ay;l!=z70y5S8#l$=0vCiRQwWC{{>C-;?nKf55EbDT|fLGD61ae1;ZiPGy#$~RCJ zrp~bkcBT&vroT9z%U9Kf-r=b0DBK&_m%N^YuE^dT$t>td+>^LY>?w74js>2g&%7?d zXX%r#NATH-H>*$Z2|JEAAgD_?;x{CSIdnc~L=bZ*2B|SYT|$gd6GCI2hh9p1OB3p~ zhkC!lSNckp+c6GRi|BFw?JAbu0{eP@Y4YMkB z{Ld>W2vKAqHCY#DoOpl{kT_FH?bEn~m6$NGfr zxAxfdKU9r9)@NhCO}(YOui8sXJvRLhHOqQz`X8!sH)m1%N9rdvxNGVs_K;F<$w_~i zev*2Y?QL&KJ)}q*+Q+unPkahK3*Vpr)K5yi?$dQ{ub=qqN^gXH`pf=C=bu8HdE{R6 zf9y_>d(9`*gCO^szuFm0?loJ@8Lu?IIq&siEORF86Wh)ivKr%-v!NQ0v!?T>GinW_ z?bV-DKgLjXDCc44U}szBXXj@1=0T(eGE%B*JCoN%I(KUqIlDX0%V#J*p0m8%YYmWU z1lmRF2QujGLeFS~RCCZSQlC(>7#?Q6%~;8gcBpbxkk_jX3rz z_nKe<8gcB`?=`_8G~(E=;%hQy`!&6zxGV9ln@=H3W_0&U{fXpWjhsX*7XAw46_l73 zSKgIvH|F| zs=>_s1CC`Fu7-3j*4C=QTrD=BH=!4^nX~z*ICpD{Id5MSXLI=nw9B0HM@Aq;#__@@^r3jO!zKR=7)WVWtupFlHVqr2Rf)Rx$;n) z2R5fM$H$X8ANeif{h}tYU(^BiBU4nZCakIAvrxrxvR zT+*?m_KG|kdq-T&-lXLu-Nf0AguY1qgqtH@$7agx4a!QcWqDHifm)KyV+-LZ%o#{w%({(ucZ=GlTIB9Ll+s9Pbo)VTRy$ki%pSVK(~AVvuIt z2uqRjyLOAXvTk6@mXlr%j!Z4;5TxFZw$c0177xfg()vl-Mn6g0=qG7Qxj9kCT8Q<$ znCsQC79#bQbRowz0hw?*khchpY7dUpw-%vW?GZJsjxjA~PB-pdh&Z+a|M^hTEBOsW zd55$ksuQ$`)HAg-8u1o6!srER$h)FmsxPPkZ;bk?9-;cYH|nwag6i?!I67%5)#dGR zywXb0a&tt|X3&F^>?p0w?cdjXRld8{)AsM{y(-^5i}xzOukUopX4(FIzsT?PH&*`D zT7TR7y(J%m_x}I#z7=ix`a!Q@{h&9Im3UgSUeIR+Du7n2=ULb0X>pM2j2sPEp>J5I z8}v57*T=7`OL_V58id9L_bsUlk{uqrLT%D@!n=h=q-$9|hyZB}+P@aZB0%uPkggfz zh0sQ+#@7JDkorNZ!&smvv?{VHnE##WB{h)MDX}xD>S1`H3SSNAKdlmma&~9N;3D4# z=xHs6oyZyL*bPQP4}2bmkh2r-=*U7A1`z^sF!8`b;JXCh`4D_q0qOUSvDFqW}(61np2j793Hu1U^?$O{?oowp|;^^MnLzMI0hc^PGnB8*0kW?nv@ zGZ!%09!2_S!ZhX(zj2d=X&O?0>AB>b#|VB5X}N~P_c>O`K6EbQ=&|IBz?{LX<~VV7 z968RWqzu1RId;T2i!oJHre8G9h~vgtjHx0tXAx#HpM8szW5`)Z*^eAU&g6~FqLeeK zz^r;YQl6yKh`-NR`E9P6$Nczhq-f1k$@lBT0;##=$m}c6(_H4?lfV{7cml@qpq4qh<_@{t>bG_*aLNny! z9Q~0}FM~^Sh2cp;3*-|Vy+r;WkpA)IRohV4n@lU#K$IpWL? zMz$iqB{Nuo(yigUc?$Uyxd(Cn1?0iRZOCsOk-IM--RGq(xVNW~?n2WxqUzdm+$JLH z+D0^8TeJaLaK!ljo>}?;(pw@9PFA$vp}B~alMn5;XfD42OD7-NZ_raj)roojHM)st zJ2B7Cql?Javp+}Ap@WFg`x>Dwa(|9wKWmE?@^z#vXl+3bE?~Zu#YpMQE0>W{T=yfK zm7VuTq<L??mUV%;&szKxcnNA|t}myx$|9=e5^oTdK4Y z&zEkM+N-p3--0%AO*yUcr(=IPsR zrS>XsDbX6Xmn|qF!uE2t*H*K=5)Mb4gxZ_yydo-WseZAITo+F5mDYl7snlwpZ7<)Y z4xef@(Jdkg%3CU-0eqWEZ&}4w6ZP^{-!I!Mp(Q^1e)&d?_*AQjkJ;Y)CAtQ!@L#Q# z-m*`>U*&IB!apVCM(HhU!rN5&{VH!S->d2sTCMbEr8lkAYPODTm)^23_I@P{Rq6c_ zH)Bh=LQwu@xk4~7jwGMP5$V1EJTy_l5jiS3ayUAC8cn3XLIjcTh!_+ZRYYHjOG&#X zeHKmhX&jMuSwa(uKlm(~s2=^uG1-w^1d+C(T6aBqo@2PUl*%|F$9empNGqR=mYlY{ zHmqZYUL)Uvas-iBm4qWIM-Vxl`Cfc^9FZ&32~Ff$Q3)?3F2$bb9N;MJ3SK#~$kn5S z9ZHB4y-i{vK8^Si17a^th%eDZjuc|R65^{O227t)V_HVsS7pT4XWQ$Ge2uk@CsR%^|> zmk@dhtydYRSKeORd%qGk&-crg`m*nrZ&qq4^{5H)y{aAGwbW|08OwZ+5<;(p))SBC zD5noc%}$(N=lHHU@;L$q^18&aw1nBqI8HcKXJR$2img`ues%lT`(?|fH>eYuZlWGMO|@w`i3K+ZK7tFw8W%)Y){|#vh!EDrs0^Ou9)N#L5W$sk-_F4V*T<`n8WP{wo%r=t zd5@}cthcfnvKq(!zUs*891kPy80w1rF8r@Gku^CM1yu{_ys|4PSIOP4&Rxmei>waE zBjbBCk{tIYb8H+%aDCkOadey?N0V}u+&OYAvt~o2c+GKfwjD=~>*J2_;|Z>hJBCak z$T{X({6vDBW3I(dBDg;8Y(AOb-ek_;QwWoJZ=9XG#?hlIsVU4xuEKXCh-zpP^%VD z!t;rmDB=7P?oX{ar`CiD6i=a*QU$5MN9=@aE+Q#JO(d*gHQHYfl0C0Fy+9;|s0p!& z37IIKLexaUm)D{fXnUv$)uu0Kb)=prY9e7G>(UGCl?fRsY9gU0-6K*By0m+ps0wYW zgqqL~sdeRh)rh{}J61w#Cgi55iV~XBH&_HkLYX(C7dYyd(4gWeN+?lBk};f-mCkX! zgep~k)@Rq6zTo)nsHIfvF5yz0R}*4&5~&iBRRo2&iG*(zVJ_xX=?MH)u@j;=ZJX3y zUk>Y1Lb;??`+TfR3FRU_)%N?pxwh+@RgR!2$GZ4tl_OrhI@ZN^s)TqE18+O&g-~C$ zrPOXZ5PvbO%U6595(2mMmX)x%=`E}Le)(plw=BI`zER2Mufbd9o27l2@WG;z{{8#q zo24!4TQ-Dr>HYG}a;EVuOQ_|9V)kuIxaQKEl~B*VZKd}sy;;6xzF$pa8`)Cgl}e~; z-?qE@jfL~^nV@?MU<6euhV$w7+5|kmay7sRQzv`hiN4IYVGAnSZXyb zn9pl3ZG3%fj*5QeP(st|;c-;7)wD%Q==;yMSHkJrYG0(i{(Ix0_`ftNCe&X-0B#?f zmPnxXojI-{DQTA?~)Tv0^&uBjQS392os6RH`iGnV$DR%a~jU8}aJW~e@>&ZuUn zCaBJ+PS_y!_WJZ}M@9R51D>1jm%Y6qystNjjIbO9uOPfNv8zE_iYK3Z!>TF3fR4Y`+aExjb$0&6|^+dHq zHAD5p-UKy6^~62|HAD5pz63Q5^~9uas71RUw@*W4jJrQOgCvc5SbQ@2I_mMH+#fpa z@x60=O6unId1^j+_x#psPV63hm4y&c~g^YfwUaxe?OmIVQHU`-_jJ zKMWzKd>8UD^beo2{tchJJtXZ@J}^Fc{ZY1pyO<}oVfXzW82gs*xXZNt zPd|s>fw&*I-%e3$69Xad1;;Dtxe$w4(%d~T~R&&}T zyR>VzztUgscO0@W`y2cv{!X7%6Qobg-{3Ftcc!Q9^Br9F3;jLmi?-yyXjJw){XMX; z(PsKPY}tytY?u0g<68Qi>9^P?>>0jO=@+J7RO(~y_?|2qdmGGn^knzq_BYxWMP_Nu zxtqGZSg&2`k*Noko?$o6+2`zezT5U_ckK2l+vnVo-hNr~Z`j`*DMrOM^IJCC&)w|p zks{9Qmmg-yWJ0QI z7wZL3$52-<5Q}El7Vge{t0A?2yK~%w|Fs4w?OvaNtlkL+9grVxdP9r3s0jR zvOUjBySN)qvJSE~S2;g*qfd3AgqCnO+Oj^<9@-kI)v12emKJV6K3oRmcjc%XZ)QVM z?1Dh9KIpFWpw1j?6?dhVb>_G^DZe0ULhM|n^qg;vZ-~FWVmjrTSNi@Um8qC-I^kXX z4%(;dldeil&I`6iRZ3K&4iN?V22&Z&mP&folGS3Fu%pbso=kd%rRU?5v^7f4aL02_ zPoVUC{%`f49nX2kbN+w5kNN*O&Zbc|jk{@lb)0p~Ei%^YQR&Lu(+=5z*g3cZ(s{~R zO4NnxCSBr;<4n_rbXVe*#I7KBA=Mn&f;q=KrWFR)_0yNfUAd1d49=a-T+TC{xx#N( zyAV5@c4G!|9%_ti!d%svROPv~DrM6A+K{u2m^(W&zomJ$0Y?qXX50Ft8 z(SteDnY9PAsmIQ*UZL*lH-AmILQPCPsR?EEhtwy)Z%kfOu245qD{9WQ^+@~GZcAic z;@YHIA?py=BGnpMo46*aHpp7UHAuBZ)+DY@svWWhaWzuyk?b1Gb5LihN=W;MxVMNp zzb(}rq zs2%#@4t;)yowCFJ(tEhWuH0cS@9=Nz@Z0S0NA2*l?eHJ&@b~WUWAE_K?^t)(v7WMH z{cFd%-j4Ok9qX_=)|YqS0sjAhbEuM6%d6&9^6JFzW`EA!%ihiYLj1Svuf%^NyqmSm zTj#CvmU$cEnt2V%)+AKPi^Ns(cPRC4_Cogi?04C(iIu<2euMlS@&9o4ovaomi+MY0 zXo+l@w?MY#=y}TjI(t6*19886K;A#^mk%V)^IDXzjm-16spFmO?d*Nxx3dq3>yVq} zbvU2rKgoWa{V01Y`#WdeBD|for|uT{o8-Ke)umj>>ryt$o9FGxedo+85YaT=X zgt!Cw&GYB77x^!q%U&XWj@0wnVE&iB`QUsI|IuJVzr17Kfs!2w&GKg{`CRsF_DAAp zkk4kFIMXceL};2noc)x#A0|AKjn60M6Y}x-B;p~|*atb7_?GO4+0EHb9QDZ`%6`Tb z4`q)NKSb)`Y$&QrM^p0=#8W9fEuWP?$e~d(q;8*RI-^qWl8^7!>0M$IopPR}mo{ON=O!ZG9@n;ny#NIaWgb{X=!*(u2HW#2`fntcy>T6QY( z``Ky8OS#8v%3YdG&RcQ!$+@V%$+^sCqlR75z>lJsT@N52~$UizeDm$6@NaRsjKag!5__{%~q2JtfDs1Dw zJUQD&I5O+cTE*nNKPB4p{X;+EBRIP)JA(i8l+3S_Cg*+uw`<{R**CJUXMPj3YhmAP z|7^c(-|TC|`;z~)Y&72z>{=L2*ahj=LUZy%vqQ2u`8Tsek%wj9L>`_UhCCuW966hK zQ|>oUn{vN)+LZg9)27_-FE{0W+q5Ykz}>fI2XKe2gnhFy)V&K|7x*QUUmFc8?2{eH z`F*m3i1#72HS^1(VSHWS_fK20gE_N>uury`^p8ZPb}Q_juglhEyXWh( zb;u3bdgR7z19DTg5jn>=_uHn8`9$j3nEQp(#@w%(Hs(|Ls%c|B4L-u9*|KcUY-zTf zcq#QS&*s6Dw;QZ}?td+}-|mGa7F?Xz9Ks>XsnEWN#;%qhX;%p7E zTyHbsZ<`4Z;U4^#YqC8Ei?cnSxqCJTIXBxKIWL=w zoS)6hHsniTTHBB>p@t3lo^aP~$d|!dw;^8+Q{9Gq1-x{Vv#HsXY;rb@crx`*%QjN` z>c}p)9=V>QN#sw?CS@~;<)K>*8=cH=a@DOWOeB9&HZhw;JTcpi*xkwHU0Vga-2`$b zW)t`?cgw~jCm`qMv$M^G75oRADYX(7zm*(~BY%7*r{9KrEa`EXoPHbfF{H<4a{6t^ zN0T0t9Rio&L4}>NowK3YynHUX^YRhdaOB8r1aee15;-~>m95X^|68BS{I@=r^KX4F z&)@o7p1<|^R_Z(y4#R^AgR&vn;A~K~6Y(Hw-YGkb+yf&s5)ZKw#^d@t@zKnW~~UVvzDY=A?N4aGFdoJfP+)k%`*t=@)qQ`%;e=Oy|_>`i6EURh9ak&=P<~6cfSq; zOqRyAC{PPHmaB1XzA*o1_&6-gKMDUt7P3!}3y9a`vN*2EWpP}S-$+SW8gDPWAO0Rb z2=8&tN8$d+!T2ue_rjmUhv6T{kBI-w@kikSxEj~wvQgdwC#B4d4@5r3`?%`UcT)j_}7IFWIV zlz1`xp0a;Lz8L-xenoB11i4UG=Q6SWyzl~N{t$ji{;z_3sjKrn@?VBuggx>_#H;e( zlJgb}s;iLhG5#>;ejeT=Et{?Ut8W(MYkedo{Dh;Q!t^YYbVg09^6SE4p3ZgDa4($D8BZrCtjwN{|+=;xK*j>U4@KqPN_G-#p6aGn#4AAmISLMvg{3`OVhTpm>=_^TJ1)Fs> z(l=Abo#AG}9pU51KK(IQ{WEe>e^9uM+}pzsIe!Q8j&NJ}kTM@fuIdj8w~}{Tkd6A| z!Y!n4WiRcO`HK9^uq0ocpB2vJKFzq#O61DCdE9GzMSga;GF%bP=G>LYvxv{2{F&^W zU4ybsC|~f zXvNWr{QIO&53M;`k)KBT`|Q=-nsg(|H-kuCm zmgYg*`wIgdPUwR9K-Rc$fJqtu@iZn@B_+SjJ$xj z7k6Hf_agKr-Ik+X>>1uR9Lp7_hT{m|Lmo@qFZ2z|^PZtS=X(-*g>BsB$Z$O8zlZ#8 zI0gAV;vSUg$&T6mC|{rZHH0l4KJ{=Bcl<#(f~&TL0i0i+A5Qv+Fp#6=c>_7s!-bT& zC>%!q;b9PGmgnvo-XnAm9f-$qye!`w_RN>&TiBg=X+D;mabX|!9A27_Aw8B|sKL1sb%@TlsJrihqn^%MajM6?%2!nZ}Ce`4&UO} zoWdT&`|{uHNBCygM47$9sJKt~C~6xW_t9RK@6WkI!~T@|CObVZ%lFI|A{VjS_7F;M z-}d3SQ=hHvw0PG;Zlo%oMN5Jra1p%ZsF zi8Ci7PY&N<=Vo`6?m})iWM|?NIeSw08vo}Z$V0-xVGgzJ9=dYATR4HUCx+p1U-aSB zJR(fv?3}Qide()t#OuP>x$a>0+@41MbmZ)~XZp}^AZHFn9vlt|D=4`(>_R=mk;8}& z;Ov3yoW2V=-ynSeJ9)dW_-e|nL9QU4#qn(9OyX7KtY%N|S>&uFy((1HOq@rZO`TiQ zT&rgAeyFG)sx7HA)kb4UdP|y*ozI+)(ya7{;N0^fvrn4Qldhv?seaiu>X98eO0!p* z?<#8JNh?a)SYF*a`hr?N%+eRhDM`q%9=9A?dYA(@pbDn!hSqTUrs?650%o z&bNhRIi%UH;#`?52Q7*LS(;(fY`PwuFJR*kA&Y2@>(MxiNVVVfQTtsVwcqt<#!bjk zTV0o{6RwLo;ku|3u49rbkiVXI9eUfloP9IAfqW~xiF`Y}g?uNxjeHlaF3t2>GTJl! zvc6^Zj5CMx$8E%EmQh!DBxqG?TWUjU!A`?6?S|gJ0o}bRvU%1F*&=I>Y?-w{YQJpA zwO=+w`(;D4UpC~uvtHyh<(I6*j(H=j&DF}*qU-z$`7B!0TC}TYkML zYope;mTO)wnXh6j)j zp;4{L)wkBg z=y}+L=VE@g8vW^dH0`UyRmf|?)yQkZHOTAGpH@eGYBgHgy`I;QJ8GYVzM|HWJZot*cU*RK zK8aXgn;y4)@pS2r`&#Bq;C$d5H#ye_H97jACPyFCZHb;Zy>iF!AE?QkN(nu1d*OrIi~lcq;*RFdr=jJXMhQKMlk?=0 zO|wk$%%)k#8O3?!Kw^EhdTjN~Cco~K=z*LPJ&;qP2XadEKu*cG;pLo?A4<(Dc^*fj zK^_qfM{Yx>S&1gJ4S7^J5~&vE%;)^)ys6h!-|Gp)$s3#IR5bwg0QHCDpH1FaH3{_z zwT`5J=%3X~dt~&(9!0#Bv+6E~6L007hX?(zQ}Dv-tKEm3twI0t6f~uk`92}}?$aEa zJor=bKTpZ0M*s8F=zpFX{m)aQ|9NVDI{xPs=q?-44);R)S%HSM7jkph8>#-af+w*h z&bZFItK&?(me{ocR|s4QxG=7Fs12wStfkyV4j`ZD6%@>ni67-=@&G#U^IJk;1HBT!{ zY7Dyt*O_j}rm?;-HJ=vO7pCQ|FHDQ;3)6Df7pCQ|g)Bz{n}-IuAk0TD3=5Ep!a}6_ z-Eu6AJI-Q!3`p_I=*N|LEDqkg1$5PXp8@0DNlylw4)gxDl zrj%)UYJ2L2YKY6x4qdI8mb-@JO479)O(K7CaQ$XlK9TgK;2O!ad;;l-!PTH?`FPS3 zLR!UC-`X`yXPsyot7@(jO^@qD)8jhP^tetmJ%4}|rDf>QqtQplhB3%-VJtG~-OGv7 zYUt21T`%c$>UOSQx{B!DuA+d?5LQf@@>b^8us>23N?Y=lw|!2(FV&&-;xR?O^tFoi#3t#7)PmX*i>o(M%ghz) zUuQ|5?pUUAt68U2>a@n4R=7KGua0GUzpKTr8NWcBR*{qaqfMn{r6rVBi(lgWbD7qd zHd!y?w%l1OP8-fuWY>~kitEbHu=3i5vu(r6uJbPC8MMHDYK9fO6pOkUvISOmTKm_cYY;>L zyqhJbtJ1K*Cs1dYctu&wYj^taxJXpYFt}ABm{y8191iklkg68xk^1VuS%I}!By&+ zc@@%CgKO0@^CIag!8P)ktVI4ZO4rI~#kKM!*rG*j>kJ>t68tL}Qm;uuLgKmVg;}19&`>gzJ((e>@W37D_YniUO?-tkG7vq(9yRew> zR>4*ICV9dzBoCT?w~{CBca+jYr%x_n9TFCzGuP~vyJp`c*Mp`X?G0kRZ*SnwTb%!{ zkdPCu=;FKP~(c->KeMeX{y+#dZwM#RtsJAEErCg%Uob54exvoSB_JO#UNfUf1NG z9S~76`c(Ni^0e2M=PGu74obkChm9%%%ovhf;VV(2b!a}^%uGuVNMZY$Atq5|` zv}RTKd~&a44ae0LS9BJ!(zB3jD&rI6v2mp*t<5N1u_+-O>QXwb@mv)5)Ve6H_K16E z0aBn1cR8Cn&jByMzMA=2q|at0za8l_NuR}fetXg-`UsfOY!0`J}iP+X9dPb2)a+eqLOoUBK$>d`gQYU}cyfRzO6-6iUrw z1$RO2y6M-5_o3ug*7m26e-gjP)yNZxzrp|Fn(Ehyw@_xEGQ@(2gz>DyPo?|;lyHUC zmD;5o&u6`S9xLYw->{jhwyX%kUPvM_h+!hV>D3F)yMV*3pVg?6h%U+?mXg{H7VBlDkFAi7EG&?5MI~$`>dn zrVN7pZ%=$Y3g?m29((k#d^Kbt(sHVo4oB zTw+p{GquF9Dz9qdT$N9@86!htSe3ae@vO=b+lqI(Ke6nvt&#nR<%*RV*0D12!^-q3 zN2<(Si7{1vRJnZR?@FAgi3_!y`BeVX4h4B(J2G;}9;-}z=CW>n)%KFH)Rt1(cD9t# zZ@WwFm0HSH8y#D(#ONz`Z>hafOC<(YnOMu&gHwCS!z|lbsntsDB@1lD_DU_4*n@2; zTP^KimD)>|U|XuxYBH_K5-hu|OlvX&%YZB2nry%_#+dpz5n9QXdP zm3t7}`@=eW5_-h`(H_~JX)r}4ynKT z1biYbkUpJ3|9W0B2Kyuj$EWF&ZOZfYDf^x@LHhLF_oy+_Rw?boVQUSewHhMbpTl-- zfOLP3U1|IJNZ(T5+j>ZQLy3#qUg8@rBe!q+DEd%sq@#f2LM>!1j@=KwCbA~Ssejr# zYmjzKNu!M8PBr>;HI5S_?*ww(tHqIOBEkI~9Kj|LobMdjCKKGN#Sw1`VKVcFV_+A; z6z)8gJEqxREMpr`U5;T(n2*LVGc6(Qd^Il4Q%c{eWrPWFh8oYTGmTQqBlc_sc@vm* z95q*xw*={~;;YD;h;(FKP2N(ZyPd8fZxYhccMV|*qqIApuI2omV9};i$GV7TTNm+f z>-ld-#c_TLatcQqC=1?Y9pyI?R)QYeK+YzDbJt4hbN_bdJ!doVV{4cjS9A4d z&a7qzpUKtxkh>naH}O8)X(Vzz@m9)hKyD`9m$K`S>!@!(ayKEtdZB4-q^A8jvk|>v z)Bj=bJmB;ys{ViP-F=eHrYDAh#udnJT~mOyBsg%+Ch9tgdo6s5x}ASFgc zL48Hx6~T&tB7z7Oq(~D%K-B;DJCpnFlaN3ni1_~V+0UGr+xM9{bLO1ioSDNrj^N4x z=m#sfek9jcKtDx(6mK{Tx;6Px!T0ZIzBGZ+^bqo+dF~+SK^z^!6NfV99mV~}Q92xY z4Eb@CjtIVGhd~eHttW8q2yFrtw0f0IKsPy(_npGM zN1~w|%M&ZPS8e4ej!xy;anR#2bxvJ(uS$<(wMpBA&YponjGs?s>fTa?)6+dhO+u8t@xC zpEq5>6X)YMb^&ktEKghjRfqZ<*DirxL2i8MPh)9Z!qZoA?h-7DPxIW>T=_Ki!)08* zhHqU4)l>9Z-aZEU8NPHasR4QwN7wPp70|26ujk&+qTgS~nHzZLRnRNQZ{+Ni(Cf)> zq;xf2Xg6?G|Ff&n@VDc+n}SE`&3t1teqh&<-^?A?LjQ~W7Vfs$$hDiHx08R7ua1J=OumM@ zZ-L%H{w41I0(3R`mpOYYbPf4eIQIqU7kKNPoVyizD{uNL$9F)#LjE4ZV;2e$IUps&)H4wD^0V`uRSdzt7$G zLcd4;eMP;I@g7^k(?7vmcnMUm z;fJ{I0qBp&AL2h427Q2BU$F z(@${MPw_wdCFg&|(a)ei<1J5d{B!7&`-Vb)Mg9zT zJq{}M7;pLwcRdEK^f>SPEmt1LOYE1t>33ZDC1}$VJfR=h6ChJh^4zmrc@nHE<=uZ^ zv`wK2?|6=H42C{U{v6Ld4gEd&^E@L4_AL1e-1i&kAIM+ioG9Bfy!%Dc??L5W;OZYq zzXQp8kuxuI^gHP9c={Da`3#!z^s8L|J=9eNukzJF(C5fsdcmJ96GW1Uzy}{X+ps$m^$+?$7BujYuEzZ6QeS`chN&}O( zx&AWrW#0D=cl-(Z7xKUI>>JRxIsaGE>!7fI;!W?8-h{rxkyz&&;Gyqw<{#)VCD0O{ z*2C>BsOu+^^ew)Uq<`biG<}ozrK!GbY5F!#XX#&fQo?Ucx!3; zE^jYz_HWP<@+Nr1{XJ=#7Wi7zw3P3arTx)G%TiZtlz|ZwQa!cE(#EeER79{k72B)kioQ3 zINJrl7snHZ#?7% za&-t_=$#B9^@8@~Xef90h4$s?p*+_MKe@qtZ5Zzy0PRgaoGbmA6C1`E=g0a(`}4k0 z91ntyARnEIdXDCcgVQlw9|#?i_DaT(dO`w3Y|qhkF(RDbI7;i>~!dK?%Im$Q}IHZ#?$k;K8;!4ncSuS z*-YkmTVZc4;9IkpPws);xeed!0i8j<4NuHqrgsj{E#!$g%uE&gaSPxjqj%kE0#9vNdzgt+D)eOkG>IBi~)X{PXtQxj3!Gu3engVd*aB zxGq`36I(Mcy^wb-p|lWR!yWnZPNYTn8ZP1dQcBxFcOu_~*7|`EI;nC#VSUZu}3-fOB6>vO7;KW^R91?qA0Bo$v)%!khNw+!8zjcH-&1NV`Ip zakMwrc7g6muE)Tx%>27*a$nx8AHeRsb2+IRx(i3kxpx;l8h7P=`;qp9?!(dksmSjB zsi^J#e0LdV+VhtEgD1fO+_fh@3;T2aK+;}NJs=L`{{8V{*ps&&L|P6#fTIWafd zIe$p-)Hnd@`ohCFe<P&Ud;)tGMs*v>R6P;oNa>x)AMQ5&cq5 zcB~zYt?RhIl(a4O?b1NEMb{SNm2QU)EUqiv9vwB{y3ifaA@?Ac?ud@Jj9j`H?Q2iQ z^c3p&z9*%nSgXr8zZYL$2wj41wijtvv#!B^nuuvp9FRuG0@`}YYWf__WsY0_;>RYpv4V|d?6j*h`vb!5+N=O(;QJ9%rU zR`zL>=0ml)b8A`~`E=5W*r{5|XOOg}wUM=>Pl299?%FCXXzk^*Nh`5toAMXK^eQaWRlM8zi&a>tr}J*{|I@K)&)}`D^*SS1#b-m$B?Y7Ya!30tW|v_rMXzB#dh>(c(=27pTRo4G+5AD$JbKQ zcGkAOj*?chmh|q(-axO5T4XX%18iT6;KJ(4V8MmF=o7?PzV}n@HDS z$6ga`XKiGy>FcmrZw~Z2-r+2rR7?3*#@%vgIbYR+z7guYlh*PaY}8^qT1)v3(&w>J zKhKv|bM$$v*qeB_>$7gcYQ33vyFTk?EY(|hpX;-3!A^C2*G|42+MGPv&f3YdDMxGC zIWeti?P%@guafS-I=zE;J9~Qv*6eEDtsT7vs=e$S>l&=pHN4~N9Ie4xRg3rrqhL#D z3*Hy4X6@)%l%pLz3;Zuy(9xQ9*7i=U)jRplJtSv$wUJ%tr8OPrjPD8-v{v=K*sga& z@8*5?@vUz_wU?vqoZHdg2LAw2T0n^+Q_ca`Zo02 ze8Jg&>38_j4;ax~K^@tDK(odj2;eGlj{1_|tG0KmVw4Jr8T^IIK=udgy6O8L^pw9U|LFo}}R;_6*nABq#X{Ax)|!4Kd5V&Dv{v=6DQQ8wO3f8qKgXi|HRWeWk3+Sme?v(NTC4fDeCr7; z)o43E$(w&ingWe>v=(%yFR&05FW#(IrBO|I|A(^#nb zk-Qj?>=*gg`d0H4P;RZ|DbPj>T08k!EY+8wuaN!#)jHNHelA$e&qH6KtZn=P^i^_K zglR9U=V%YV1Z__qE#*erc`|1vgC1)&zl4SQ67SZt=p}5^mwBrzuU^KkeTBDbJHH0i zQr5#q+xfL%J4bt2ZR)S+KpmhJyf3$%wVJh{Cqc!l|Hid9f*t*O@GH`qj=oKA@@}o- zx1id~`Z>Lor0HA1g4U|e(zk={tR-E7-lgpvt>$P!zsvheQ_YySZi84I@;7t zuv@jJ|IRmDNA~xmjIU@rYbm>SE5T;vqtF!VxSU+uS?vy+m9OTub7{&<8`rgO^)Qn*;obU~Nt^NoE$C+0v2CFGx=EYyruIPtY|pp!duze_bK6;@`n?vk z7P1y}2dKVu(pG$@6G=N-8@V$jZD+0ODoX93+R)m@9iVEPUHERJ1znMjOQId!mD1Qm zJGuiFY6rfcJzNRZMs~%Q7IY==)`IQ~)l#k{?~I+=nJ;M%cZF&xV>|Pu9zmPMf<|}M zb{-2Aqt1=zdVq;}NOYwU+akBwEwavUXLKmi0isHkw>Ih_8(y4S{MkH&D`! z*1{f3X&6-7c^qHVj#l&6W*&*niq)J%YdTuiTGRT%j^y3i!=s_OU#xbt*70Ogw5GM4 zC-ZJC=&{(WQ=rp$|2U|YvQ{xWT5x47v9-e4HYdg>9t=hv2 zpxV~@aBDj+;H}!r3!z%a+RKZei^=us)>788-Z@y-JM)!Bt9iS0c(Rl<3>q!yXgh01 z?~1)D-Jb94MqG{R|xEl%_>%QFlSa! zUcvVdNyX(32}s}}9BV=M;SSet?i+09<}r;VEwm)y4#d^dwY_*PFVvL zr1p&4a!UtN1!J8&qu))3;ESMFhy5`|cGgd!5==q~(3#W;S*{$YA|d0EccY-AIG&2+ z9Sv0iPo-p>dOf(NGp;m19bcwX(pz90rI}$)b|z*01jchbi&1<$*1!Zxvl-ndK-D7j z3z&_rG>Oubpu>C=SVul#3dT?x z@Qvsda0pmP^bI&VpdyVP0tbU7=vRNb;*t9d=ns&44n(ZuT+WDSoDD4_7t5Fr)vrK5fmKkk5&Z;C zhw4|LpMY3L^b>fmhd?pD5&Z<5{m;DxL@h2OT>!?AdkbtuIeH7|kVm|@# z3K0!=p=nMoqA>>=eFj8GqUV6<#;u?ZA|cUpKyQIBfI6(eFpC1F1-cr<@~yS0?zwKKY{2o@IA(-R-g=`7T=>J z)*&8}dkcJ|_E6_vWeh>xGkLV{5eFI#d@L<3vVYF&|mO=eFJ_56%~1g z|45WW+(Z20N$AGB1@sCK<#=)}zL9$iIPb5wz*Ari`rrM5B+4=8KY}i7%tPQ$T#X(A(JLT& z2;{y26+HJB^qUGWhUg*iD&Kl5=n~OeKwRT>u!j%w77*)*9s;N7*DMx&p=yGawyif@QlG)+4O zZ-M9=kfalm+(ST5fOY)@^biosD20lIxUNpDLw^8Kj?%UGM(!ujA|M-;d;`1zZ7}x@ zP+Jq%8;}MT@bHm^b;6QIr<5xNp=D; z8JFaK0{RR@4}s_{(1qjn;0mH2`UG@@Zro=;Zvp4ss`+BEpTO7+dI;zn5d8#l4}pky z=qIot-vE6E^bqI@%235OdZ*$cy;JdoKB>B~_{LahvA2MTNc0(qege^FAomt1_7l)I zpwU~P2PlKS1bPdIY-rI8=39;40_x{t91YOuEg%LGeFkzr0X+nww}5^EeZd{{CCI%6 z^b^RDjbd*B{Gq`ZKs1uvTR@9oT|WW60@n2w&^I9W8ED|D$i@heg$?@&h;KB2E_6#q zL$%Zc}|-U5wSNAwUV_8EwN0?}t+ z7T=1<#>nKO@)L0Ge|A7L8odRyG#8}Wm<#x#D2Mi!=*CFs{D5-kClGxG-rrkbLw*AK z59lqhRX{WrL2LO^?kAx2C*m;z4*|UbqMv}i0b(6`3+NlLaIIHB?jfKLK(U8_{s1By z+Qqx2TEx5YmFN#JJkcM3mGY_B$nKQ%4bUH851tY65D8hv7ezcoLiXfbBjT~Xhk&?- zdk5%0ptrzM&;rqkefh550$RAD9K)b{ljnW{(L+E>eE(D%Jogaj$&MUt_YjDt^c+~%Pe2a=cOiKLi#GZR#NA=_7T6p=f#@Ni#T~uw zi+uy4x4@=(2-q`kArQReFloX?xWAZ2l)v!dI&_HfhpL~@8>5FeFLJmfOCS;j{YDI z0lfl>{RB46LqPjiPy3P3=ye}G1oR5XJp`iHee@8}Hz4{6MBjkuC-6ZY0{R9-KY>OM z0rvmE5^nSpX!H<>J_8@lPe8ALMhjYR0d3XjGqA2Ty}8~3+SAczV0~|a&GQh5z5&rs z;Qc)W*7psFJ_840sty>TU$i$9IIfOM&zB zl~8vtaAkcb^t>6+860&khOoLA2xC>gv6sT+YyO63tB_~tr1`a++43DF3 zq^=-&6Dd_QW>17pi!mWPaYPyKn^0@{+=O(%>R8bPi z)nBC1cSJ-o<3Fv2){gW;rd zXgSv!I9q^@As18C7Ye&G~S2A#}NKhF1u*HTJ- zpnd5FDWwwHeG1eWs}eY58q`_25_o6^)R{;3hj7mbXID#t$9qYbJ1*h*d7PQTS2|Dw z^5h)yj@&l~DyLTRQO-kz>0;-IYZC>`IzO zYfhmgPfihC4m>%T68JAiHBfm{?yZH&lX7ewRGySqdjuYpGv!Y?ww`hi+CU!dN!yL3 zWf~~i_ZmV!v^Ux>?Vt8i`>S3*_F;Q)?A84^<6b59_Wq&AM=3CXGyQ2L_whQpLB%9O#RK|$6GUMqcua&^dBsWdD|CgqlVsKiooDZi9tBWVNWojZFd=iISG z{#Fhu4V8=bu@tJL+|pkES?y)(+W#|X6=nNH7xK=esvzY`=t&+s`%*#=^Emp+DJe_n zf1d3?xg$N*9@`#T0cU5F+CtmG%^9WE&^B;zMk%EiRYPmZQ~FRXRB4k2Ddfnj>{6zs z^om|kWnIcMCH%L_!z4(^B*@hy$kilB-2`rL##LphGF{1D%9H-ami%S>2TFWn{Qdv+ zdzH0HP^GQXch*{&t2~~$R`M#LXRMXK%IxVueosR#D$x@pQ6H%D6baI&AJn;tgtH|` z9ahMP@g_m$45I9KlZ5dm3FD39%rMUM2%}6KZF(SKCx!NQ#B%JaNw&!{!E4!9QWi5Rs>LTRP0S2N6G@n`3TyC(wM*{Qpet=9LJGZSysXuH)T|JL>~ob zX`94RU2ULC;5NM_)f61V z4!uoMdQMxY8cj-%Qo^dmq&(jNDrXn>Uo}vVn}%9Y<78g}j+M?$piMZg#)n>S{yOq{ z=8pB6cYfQI?$y}9u5Ir|o_pp`!hV~K4K{`O*HZijGVlRC_gRHb?h5y=&_3i<`(H0#C*3qAZ1B(cD;QTZ?t3Q@6PnA}2Iw5}w>k3; zo+Qojba)H;b~2Ay@zMC5>)me*l!o*#oOg9i3p^s;gu3>oC0NcIP}k(RvgFUuHPHa4Kvduc-ZBd6&fqtYMngx1CGE)hy@;mJ!t3l!xlkci{W zVvqcS^N%M7;OlTzb^!hmJK}ZVDih-?EJ+^&nST+lz8CTSJCHlB&WyNl74brrhKM0C zZpcpAYe|eA@^fYh{>VJbA9-faYQE2)R zL$eRRsb6L+hpV%nu_o{(JPlvsUHkIft58=Z?n~(v{1mPxl7p)`uFf9itb0!Ho4uU$ z<_&#_Te~l3>xt%YA@PYWq`vAo-#at*Q18qYAJ;&yAx1+F?lFSV_2kAI>Yde5?vXu` zEawfil#y^Je0q}oih=W?jW)#Noq0XcwpB?l1)G}D~LvN5cfN$c7JjhNBa{QWq)Gt9-A7c<8c0? zhm*rOULN8V?+0DZxz4<^ifAmZm;Dsy9!`$PTwi-c=9=0gxboAal6XIzhyv7&ykm$4 z)sa#qF;`rbdnA!pev)(u5lK66wIh){4^69~)x`xwiU zf4~#!W+$cv(h2F;dCP-g1^4%ZCUjKVA~6a}v*dW9 zfHmVi<@hDLEBRMRUt|6Bcli%oQT^Q{#`98xKQe7eIwHN3I{gv;%|GJqCcL3punkT~ zn# z68C?Zh^sNi7q)+BMnb12rn68e}PvXV#=^l2yc>S(Bc|`O}H2&AH?x z(ifAz5<~0V^hC~mF*z}F@9`5e*ZrT!@#^HAG$S(CJKSU3)ReEDKxFRQlM_g{B`bN` zX+)bbUgOHl$c-yAqd>0Ai~_kbGhXB=(3RQSX-SqrGu~wko71xI5)10y5PS2!^ewKw zooa_xC9j6Ktj0@yHT^Qroym@8|6glI|ty*DJ*Qx;eWu`wG!t?j(Zz>g+q|x6{?xy+o&4%^TJb@8xFV zjQ^CVR1Xs?>~)^_Bgwd7MrZvmqO{yejFx-3J4S_jh&z8uv@TILq6ktj?L^1q#vexLlD^ozu7IfvsfW=4*Ch8UX4jMlxCl^&OJbQ!IETVhPI zhlogK^wLZCiaU0Hfm-X&+q4KpQ2S%~bP6`$Tj`L*D0}X_acg1(x~Kj(lI$;d!^O$1 z*%z{ldBY{inIU4`nf$J^Q+MaMmGvUGvXY`7+|U`?nfJ!XbmEwQA^OvgLQKlXdCwUk zQr;Pqew@0e#}`;<;_erHc~+aXE4jO1+_RVy7@&+w8JTac&m0=Bv@tR%N@>z~9;He9-PP_8e zUI9lD=hI%*f;L+7=b`T8F@pEKkoM#r(GF1-_8Lvy8|4(@cDeJ1yJlWRULSCmdhQV& zspIGxuDJ{6^{jC*M!<~$L#by~%r%@jFIh<}s`GdcYmA5+cSg$IEF7PkoJw>m_H5yJ zLGpa+{;V$$0r)WPI-E6Nhm$X4h1c`Y=ZP`5HCJ7arRBRd>4o$N?m8W69MSolcLkL= z_o19|hn>fXx^-w`thz;bAU+2*;;?(#uSyT${GqH_Gltz(Jmo4Vt@3S?KM-elTXr@2 zLwYb*4`DUfD&l9k)6OdBsr<*<{9{2XMu#0=wBqLl>)stppG>zSJ&~^9*@IcnwjH^9 z@|?rkDtEGRh1Hqte6$_c4kBN{PC3RCaL1l=SPi&6XXggoU@q^R$4a;zIOA@f2eQuW z816ilbQbu@cw2BpTt61T-ly~k2byv*kToqFn zvv<#(Qv)(Gi8XB}a&!`DB`X%)b;%usmqVA5pTd=uU^$Zlw&Oa>lR0w=D7dRP-8rgp z=O%Y_ayR6?Su?pSr9D{dxEre#ccZ*4tfX{@rahCB;j@*rm66WQq~D%}e7b{vbs3h$ z<5GdX7X#Z^U$`>BQo7}lrJVeT}{niSfZ{#UWRR>og>{7J61bG zn`dvRJB95ECNKs3U>f;UbaZ`!Phw~+!RJ?9ekal{P%YP;D5=3mU4A*GXzPn1iYqd( zuGM{(1pQqtehC=GG?0%;0euj&n6_3oSBp7mtro+oMRX;#_9bX7>Ws&R7;d5!lhCN6 zW`7`es9$S`90bi*)Qf1SO>3pBfI8z7b(Uk%S)z8*Bsq31+A%g@7-IuMF*cwSV*{=s zE)_MVW7eV)4Qp`+@d>fesF_LC)I=r3Cd3uQppFJv5JebG8iTH&*10Ccn_Gis^(ioi z`CJ%owz}C>MdFIk=b+9K}@Rdt5wZ%)bqj*M3 zb2ZksI^0E>`qo8Ri{#QwG^#f35oEJA>FTvO)5Y9#5w?I4-fl?Mx^76-u5Lg}yEyB? zQ|w0(kn4z9-;Vx!TWYkp%dj0TgZusq`~L#y4dhkWFx#h9!8WZ5mPu8xE-vKy1tAXI zCBbsoF6|Pm*v`Sy=$zfguj|a6RhjXZFAVYQ?npZY4Z9Op)$ecTxOXPH&>O3F5g3aY z-i@hRS|6?~O#1|+q)$Lf&I6M;mq>sYhB$zq=bgQHsy9^Ir59;iVz(NPwP&zn`ex!o z+H4D;3#jE5K}T=F|8hs#65amxv=yn6=(R1$>v^gtI_s5OF%I>4(DSmZ&|fRDIa+g9 zWmeAdmC!4>@9Ipuzb4o#+Ehlx?S`%9%wRQRPA#L3BTtW{Hdt`AT(8fn!4bt2MGvb< zJ<>X?vmRJ2+A{6=QV06C*vz$j;TGcYUd8v?abBHUZMq$)qZ%`%Yxp0o&f-YeGmLnS zcGbz{L4UoRn!FKovL|1<46FY}=#3yZmyxc?u1M8!uHeqg(=xu&44wNX?B+|kehtXZ zrGZ|9-FY#0UP1Ipk<_a}h^_-^(7GQ4nlM0QAswEMz&aiQ9g&JOXe(dB{TGAvs4=+{ zsC$=)l@90X2rvmP=}`f}8kLD)5nUGqOU#0ttD+Wz$gcv0yAG<{Q#+^%V?QfuxGE|# z7g;P!ZMJv+KF9BM7l5vPkh?Irna=zI<~wh;&QV z0UT27co28I!_~j0>dUvFFW-U=`+45_PC6dMumL>M*v3Q9YHx)OCLfB9c@uO9xme~T zu)j&>1hgOq6y8^mU$k6Z(1n^Vcc;8EfnFnKsvd@q1o_ z{)y<*+8AxPzb&@bu;lveRdnBB*k?C#$E#poH*n?#tdAxE>wkr-uVOK&-Hu(Ww>h8l zGG|^%=LT$bE(q=H?0IY-wNEXk`5}t(v@j#&ip4bD8l-p@D5Z$823}zr()M zUNbKAZ&S71-%{4T8^Qmr4}&_>l%OZ+HQ+2q2{RTYVV1*Li^X8A+lQFEJ7iHaeJh~; z?yBY7fU^g2t|01|TZNe@*XEB|tLx1O+FaD?oC*0y&@>yM4d|QBAvlxZ?7=&UGa=4P zltJGnkDB!SpiRG-IIG}1gVFn(8_DNM-eI;Q>g!vhb&m{Mrn=??+G#eqRQ=Z34)?@% zeX4U5&QvS{gVu9nHWq{Szyi{5u?>EUefwvwzJb-SAo&ei_^;6Ap9ogo>zo(G-Zonl zA{{Tuv@L#au{ zpsCw&q=oTJ`dT8o`WjdMlsv{ee~EqiOYGCfg4L{5@eH=bGuYp+CgP*7a{p_|&qECN zpL5S+Snk^4sNG}Ur=6dU7b>5o$F%O3^XS8QW?z;*M_9duD?We#a56kWeIOshA2fZiYq4)5u zGnvmhi{}mnp*#%C;~vf!k6nc1VRA8$dzhCW*Z-Ewx1AT+iH;Kf%hBthLbQ)-dr#}}(ezIKr*DF# ze3R$g*KiedRrW_P?^WRBUngq$eIRW2@xLC3{by`5?Z88L@)2y;gM9=4(TSO8-bvv7 zV*0-zy~r*Ar-5@DQU1j2tE3aM19E7JAbs(;u<_ zijn6pO#Uam8#GpQ{L9I4)PhkcrKe)iUcf!>Oe=QiezbRk#vadoBEl;{RYWw-=c;JU z5#$$h$6e5i$lcR)Wx9s@zXTE^ig6z4d~mXh6YyD(>Xp!y=?{}Hf~Xx2zIr?e?5Dk! zil*I_M&#gJ@QI_qY>wi2_C-yWJ~bd3&X#;9pdun6C-Ii6c&DhF2;EBVI*r*B zXF={G-5X{^?gIxANpXK&5jPP!aWyfxYoKC>?j|F?b^}Qy@kY*`PWIcy8!Dm@(4pZKuaz33`FP zczU;%GOp{RXY{rLBe#B|qexAmdKBwrs&`8CE!6{6Kb7cDs$Yu!rurv0M;Fv*P;cbs zXrg))>y6w34OJgQy^&j@(Yo`Pe#ouRedC^EdMWCk+!`I)h-7*uw*`$IK)D~OJ+wc0 zUrH6we&l^9b%6FI?@g&Av=4bNN|n&wr_>qRle`C|Drh}<9i=Y8@~pxN z)l03G)Gb(~UBC;B)mFoi-o!POOQ^>J)Ed(dTVI$Ga{a|psGc!f>i^@Zf9pNgf731X z|1t5uJf2bS81&SA^a^XTwofQg^b6a<{~r(kZ;?MAzx4-QvcC9(<*a>5UUWI5UBCMd!*$ zO+o#{>za|u!2HDV%1O;Y`^5K}lgjzpmj7W(J#68JE&XDPeAproFg?9kDG_@>5p7MGx5tU!f$QKwWeq+{`OWR z^_i9&wdVfjXgJPfwjsrJ^UcwJnsL2d&~(}bO-KLRmgq|*JX68FaV5QFxxNGUw?*Sp zlj=w+hj!q|eJif|H-Py`mKej}9s55u5D5YHB&CNr-wFtFgT{Y#Gm62OB zWzZI(mdZHmxaMvf?uOBZq&BEtXk9etcUp_>xS#cFl-v`_-8tMLsSQ-$YU{_?QEj>3 znz5EzkXu*ozvC_+ow(Kl%6^5=B-D?q%&e=%`e`1@9k?g%gpk*dTw(pV6Gz-{B;m+f z>Huv)ZY^~VwOQQfAN?O=P558?yjErGrT%A@8fC+#lyj-&lk4BVx$X5q_c!DJD+_hn zY_q?${<9zSt@U{+=K+7?2k})gFU4ARJ}TP!a^r?%`3JpoWABOmK;G9bl!I+i?MJz^ zL*Ubjz>gJ_l|9M?ds>vJ74%VgSou{3?MU7pUR4UPHkN)Vr`Xe*!lUhx1M;m_XeZ9Q z&aV(SxE$)}N zR-9eG9zKW%itpbv9*Y`)?=61zUr~;&s-(4Ml(5!VKDzxgdPLN&`~~(Gy?W%Re4Lcu zt-&}#I%YQGj3Z-{&_YdUik$5Bvw*s(FTy?n2Z;E1NC zV4Jz`j^kfbp0;nbhN?SspwymT<4E8**#s&lb>vA$vNG;)f2=mp4qU0^_lN+wqmN^$ z{m-4V+%G8ZxaC-AyvDe1kfWT9;^isB=^U1 z|HN1iQIm?=fxX_k$m^j+_)Y#gYruWK;;&11o(M&u2COIRL=D2a%Jqm?S5c4f_xh`> z2X_%uU-Gxht^QtXBjL$h|LPcO$@*HKe?O?N7t8XPwizB!H@8*sbvG2xbH@CdG-}3)fn|HLbx5}mET@ ztNpr~nvz^jR;D+B;alH(Fv@I*R)&vfAZ@CU6M_u12&pV>F=N`Gb4b;BSiIN&| zTi&D2TgJF3BHWcXHNlUuiZk7LTL)+d-s8@9?z~5|tfYo}Tj1^JNL$CfMxU+WOg&FG z!FSSlw7odvE^11#Uc93fRIR)h&(=UI$$Rns?s%lJPX*L|t3M|3s`yT8s1b2{bKDJD z$9sEIs>6S?7jN!EYJp#;{Nk>k?p-PW_2vI6;QLw5FY8Cyc^IucSA6w`w&lO>$Ggg) zow?qRvpw+}H3n{f-rNUjf9TI|sfRYFKKhfo;%8dVuXArwcb${t25`Urr~SF&-gCY9 zzE|I$ha+#;yVb(p%Nz2ZydfXi`<0vp>d&#omX;^|MdIr6ga3(bDThSfh<24DQ+v+% z3*;oZLOH42)$VLbT|4%ud1+ay``fzOQogq{S8WaXtPAgHPaVif-FQO>sM4}K_YljB z^Id6GxvGZbzKSilR>!k?&^G0HV-i<#!)S?)=)7qdwf{&Ik50y@8uU-QA!s|3`ah3y%8o ze|4etQ`*6O1mzibknKmQju!37|I?pT0=4(`C%F%8U#|40)Rz`_kJJIwWEr#_`2ddV zpj8|V;Q#Cc)pK|Ncl736e(U{tV`KM3>F)?3*W}}ZGB(=lp4IA8ia17WNDpy;%0@jT z?)taB9-{PU)I;J9fa~ia+KTxoyfHn*9Rt_ZMmDC0_>0s=;`pnCh&YG8xKSHX_i)$3 zTqlWoh|j9)+mB*B*k7y%wG8>coU4v$>LF@HYR<}W<)gi+gxsE`9%8TezlXMekG>Ti$r zV4XxHqqrW_IjjeJtMhc$hO>8#d}V2K^bqe?0{t`iMDcfv%dPkiBI+PMq(pLblv7$# zj@F6#NP!wst|{$o4JDhcq@I}nBK2SQYgI#b4_9@V#;Z{m+T7o}Irp#sEv;HPEhEMM zQ`9H&Sw^nr&>SjX+3Nmc5yiYtlt|(+VrC*V%4hFzPF0jo3`;bmg2Zk~qyikF4WZ`m zuC|_)FP)jy+OfywM3moyVCxm=BHKJD!f;HQyHkW>KD{kMD@z~Uv0Jal>NWsE~1V<9mD@w8Gbnt zKKY9L+!k8N_d8KiOKHQANM#pjSALOLWd+pL7wRXSp^lZ^_)0sd=xKNU!|G*6@}RsCuL8 zJTj=3w4)w4HP;*g?fH&jt_bNuUdwSSsO?fqimOMuP_E%hUguFaj5?@2$p7Ba-~ZDV zR|gffRtDK_@{+PfWI%~#J&TyQi>tE3uQ|K#nC@t(Kq{ zyOApRujNPU%KEYPt&;*&d0NdIxZ2K|65G9gh5s)^RPrqzP25x;E5x zE&qXIdsp(hP$PBxKV2z{{?w6bpz4@)q)KQFZ|=dD+`m^_SiPb(G~s_#|15#p>ODB? z>K$96p5Kr`<SJ<-nwYjlM@qJm?Pb4kEt1+>6;HQ=s)u#u zX?Z?sU+Q6M=^dfgzuX(Oba_wSw%$5H9sBBdXA`J;e;sGrKy8~Iyt@lju3>Kta&;rm ztMgf7Qu};;Xu*0)u9fP_Q9UK~I_tJ4|6w__3wf^5*#q2TLS0U6zgK9BUerlj%C=)K zO71{m>#C(SgUWYmOzQROfxY<^bx^f3ZGqaLtGVxU)Cp}PcZODfkJdpA_o*woo4>rM zz2I+%^3Apr!&NU(-o+M;V^FSjE3+M^8uvu@zqK`ON5?7KQT!pwV_Q-Y)oXv}?bV*6KHTRj zJ}tsN+-;lI@I>*LwXw4Q_lFtlH|JTkO6R@o1+6GKHaa(^6mCj=h#0DWS~pPxa^!c; zOY|UWI1$^Gf0QW^)m6K6H1(In9l0G-l_LH+$9;3#Eb2n$@2ATZ-@hr??Yj3je(S@W z-`sZD-22saw1s1fMEz6C*xFVfig=23-Z-Nhabk5PrChB4IDe}h5bIwZ)H+v!yZgDa z&UR>*)YKH$N7Sfo6X&sg=DqVS8=EhY2jXZ`JXh^^)R)x=)}Nnl)UQPa{FM>okJ_2? z&HC^+tBb0m`Jej>;xAEyXbwkN8|n@%p)I*P*C5o(v{AI@tO@0nn1L8-j){uAD(%`M ziL@x4d2tR^sVcVQe2eYjJoLJA&s_rd8qr2A#Q7Svz1C1in65mTK%KYIuI~hO{-!IX zHqbU)QI4%^0~Oc*C#~$Lqenp*?HKj!jM`TQXgT<6FLWKUZ^deH!O6tHLI zaf|G0gGn)BkulPYV>C4M*$u@lvUP`(ilZ03U)&;Fbu_6sdeJ`K#pW}*+4>Rs!~=?B z^SOUnV^lulo=xF+{iuACkRrzFt7gx(3DDvQed9UKWAiB`@(6unDdn;G+_5B&&^LzC zmiF3EEX7Z5dpRmb`y`Ij`CPbTyW^kN9Ot6$kgx-B0>4avPGkg{L_VHt(uA{9IG4b8 zQ=sm5Gd}D#oG`|u9J{k#0>7jjkAXIXU5yj=nVZ3RW%U?#wNYx1gpOh-o0QUU=m_?( zF^1t#=rDS%u?;hxQ%7~5x-RTgHw*rsO{p_f%+mN*>Z~)NGr7AHXY^m1OI{q+v63_D z)bq%z=?x-9^EmEE@12*35;&LVZr<*1BPLM8nF?m0-0P+Uc!#Mqph za-SUcqHIUWC}{&Ji2#TuyW3)$qN)J4=%M2gi?w7k?_ z#g5gjN|04rFnTRTPek#6UX+cRWed0BPd&<+^&wFAt1OOp8RJ{U`f*k$#)EU+k~L^u zI9D8N$+OmvHi)%m&6M!#tuO0DoUjh+?-lE)hx)tL{hx||+a&6u4P2#WI1y@8#z~x+ zK-q|4V%t+f9Zlg%8~97>X*_8HT&HCv@3n@{w6EOhx)oe!ZOD5q;WO*UT^C!x6V{l# z*Bsul4&|hBxW-zQpPIob*0Y>c26tHVa*w;)L?2rB+stE~xdUbbzm9;q-=Z8n3hM6V za{U;n(aP)@W1;SG?kq&?KXP`Qqn6X09qkL1qn!OVDyLku@hG2iugKgy=v>|ub@SM# zKS}Ld+_JW{?b~*3%f?n-w|#Bd*vjj+uPtkfwpiQNwr`8~XTW!%>!_gk0X?7vfZ%24~mFr4;4qB2Nie7V^%h2M01BWrH5@7t?iV&C;xj- z{=Y2zkM`&}T$g7ZmuFK8{ys;BS=52Q+uE5KYGejfIj78$+CQuXsdCZZFSXYF<vjSg~LyIBdT1lKN8 zW;*XU3NBTOihqq{gi)?K8XIHLoroQ)hr`|WP{;FO^aOWWcFZ42f5=C)A@mMMQv1kY zMtnzG$F)I>UbdHb`ani6rK=;_fH0Qzhbna)%c56PAIeJOI2R&MJHz3qs&AA&GGg>b z0FI@eYp;5rGbp_|);r4g^x?RMvU7F5vzp}WX20+s_}y-N-T%!0N>3>NWB=POP=ATP zq6%vN_t$lX`pf;*#$d5Vtc^;jHDxVzgj$2vp7l7Knzeo_pw_sx-5zR7*b42Sj3p?ZRk3GHe-whk@Znl?4kt1aG&)Edr^6XcKa&~cn?LD~6iIY)k)2%W%L`D_w& z635Lbi>6K?moKM4Cv#SQoeG`GaTChU&rA#aEk73mhs*IZ;Cs2>_@>U(&kQ{z_WoHM zr=iy*(3F1Vc;1))sTJ*^pP{>!w4$9vm$cc8v#!0@kJJ*{lIy*=<~&+&a(&hGY!kO~ zW~MFeqaWJ_&1vN;}bb0%PFr37qW?e;Dso462qZ4fKHVoUMjuVl?=%^o(&F z*Ko%;{^aJdq>kaZlDp*f@uYD)t+eo69eHbK&W_=@B7C(2|A9SZB56YS|CBrOx*Xn~ z|GSE7{`XbkSGD6;#@}jxvp2L2zgf-G`1WFOT|;fPg(~M-leeK3jV?Yl^j_;&EmXNO zjWm^dS5jL0t!brd&N>RKn-1fA%g|o#&e@XMsNsAqNp00VI+Z*#pmIU;z!PylPi4_e z>Qt@~M-xpO95}ECXXG^{yFBPjzMhkEWm(`V#<@aA8L3>a z&fW)}(>t#T{h=S!T|gau`atbN1(Kt2Dfw*P)dM<*d={lT=pm0JI{gVZ*XFQvAiEh)9d<%CX9TV8I9+)@d@$VKv*93|(- zVIAQgc}6aZsIFsG183rRC1)!ise`=*fM>| zqerA|=$w8Za$D3^x6NbQdz^4K&g|R%S|R%S`jpq<2X8r9=76<3Zk+miNyS3riD>qwXarAXm zc5HT(cC2;89Zw#|?=f6$;CDD4I~tbwFk#IQ8LJZoR9gsIioCE+5^a zK4VJ^h4UQg9q+Yo)Ol=`A#kT7zT>@X(A0};p}}ylqkq(zY$s!tD~}SAGo5Nyw%I^x zv{-+u=Z>g@*^2rWtMAp3^l6GZTGSGA9~u27q8_JSrx%PZ8TC7LzhU8cXgKHCT*L3K zB_9%=Qw~(~{#wqCARo^E?sx1Z`dQU+b|m=-eu4jy@TAr8yfApd}k)sKLdnUq3${|-URKQ_nT$9^G zf}%dvlWTHd*&BX3>Ia6M9h_uIi&{?`lnoKA2PJ0gfRpNn!_%Gxiy= zgc;mtkD3m(f2y_XY2&PzTD!WwTEDt`9aQbUAFZfupmwhfq2-{}plzXDQO)r{%C>X+&{Q64&$X=gQ1FOBk0omMMNd8qcQ^`zl?K?Qy=hmjALF*VG-= zaA%UM0d|9`7e-Cf(J|o{svW8m>f53`SH7pzg_@%Jp}sKkPDI)#aK?JF->Dy|DXIHv zU#LB*O{zJm>8eSoLn;Z?DWkTf_UrtB`lZ_CSZYj8Q(M-zT)Rb0vjIL+d)7i}phnf) z?6+g!IW;>qbA8eyPNEH?H9nfwakPq>pnj2~Xh+citxUbawcPF7&YNhlXel_?u1490 zbHkzPsqX)8-<5CGMu&u+ug)qype152cNA6*Xq|Z0er9h||FG{xR7xK>H5GfOGe!1T zQ7LCEl)VL#J|?!VyiEhb|4+4h z<&#oM9bY6WmtV>=rJCBka?anccCY-irqu4OXKPdKURkNcRCd}om88m4$6nh{v_zS! znN#3rPN2F{1%Ogl3i3v?L&#-=BFN7rq+CePpCx<5xQxmxb*#NBeA z<8g1k<66Bca#x2rg7hTy;=fT}P>-nM{f^a+yY2ap)hv{d(bK)2-=ikt=v%+`*IDbc z0xx!h8yuOtbJQ)g%*?=r-Qf&J>1vK#zv#FvUuqvaGS_hA=qgXz&W_sZjA~2jRccf6 zf-?Y0D)lGpN1m5orb3lwYD*)aYFH8Nl(VML#_Co|KXqIAPR*%D;74^4<%KA6^eAyW zRl|~V)nJqwYEJeAH7vEIF;IKDy3Tm0dX74i{X$)+K-p1FDN*3qxzahj-+txzCQfC) z@@;Cc`ADdiYrpbY<*oh7H>xe$qx_OuwmmBLEH(4IXQ{pCJxfh0?^)&ihP-EKDdauN zF(dC;jw^Z3(&DgZX%zkB`lI!eQ6>EEz{Ync! z32MLUNNdZ(YCx56gB)wm>IC=5qiRf@;Wzoxo~4JPJu7Nhj@ypna--w9qq}HoKT3}G zqOA5MHT3AU9<_G+n0-kq580Qb_Axb7seLS^wIXt|1)tCLnsxDcd+@p_z3ul=+YvP{WV2$D|yQvI+Li56!Alyu5OC8T<%ScB3| zsTXnosELYADEX9tvG1xYra|5-1(k;CHxUKUwf(&Vb8Ba8j6@iJS8Fm(f(J< zR#GZ4qvbFE=`ZDchj8fS7wA|2z*kt21)M?`9r!b;>gizF5!A`@qbl+jVvs?iKa z9*fsRNh}uQ9Frq*#BDxl{mT}y?zMbug&ZM^)~(~0YbvAdq-MCW@k={QU0b|Y{cuC$ zm-d|2U9KNGiYXI|$1nB6bv47>;&| zCe0#ttF5|#v^8|=aK`^=o6y4Bg#UCK?pYAxyv`)@YJt*1+PVPUhTpL;{IW%%{TGFn zU&Pgg#9#Gy8>@9XkyWh^W3o+i`wdqI1e4MqZr)ZAQL*sN)?1 zzwE%(?TOcE-5besGVwR%ogD+$7|C-IWm{=S&h9{rP1|rWS9c7tIwuk>Q*K%k+Ib13 z#grFwv{T@(ow&M$vK+A!rSZwm`ZAVVzjp5*r={!p>p5Sz+bxrzB7hv z15qs1|99c)Qes&;`><<}vc|U@L%ALKuC(YVsPcR_N+Y2a92@;|RI)pLuL7#X-JQ~I z(A~Ia56aJ>9PLYA?gDir*_YBj(0w>sPQUI7b*x!V zXv&p56f!1?{5BIpND@{FV6fyjXxs3You zln#J8iW*b3Ux>}x2U^SVLCA_)sN?VoQctKO_zI*$52zOG3a)##j=TrlSP#$nl$K&0 zbSn8Ij%%P=PNJK&@Rt9T7L%CaM9LGw@6vAS&Tn>h+i|BW)LI%F>d+BqJmv8mHH3QB zZgQ1)1NE)l)Cp>PbtJEZFUC+BO^Rr)RIX4ijHZnpx1;scj=Vi>tmIRg=%+E9^02_Y z%9=K`m~zw^w$@N((csV{lv#Rc7!guGchMqIA(17${_T~HN9EMM5?z@%5Gvy2Za>aH zI$tc()s%KnJ}6I{AUj08if183)3P9uU4tr?CiWIFxO^6}re;e!d@|ZW*=!tiXEi5L znhq6Jm`G_x;Qs0GxLAaIKLfrNzme}}!s+&E`Mnw*x6jM{-Qn@El+|Xt29B57L*#X- zvPSNfDv9KEsnSZ!O$5#!BHwFk+Bf8Q^)35`ysm$YeM26vfV-8ya(sLE+8!du>x-l8 zme=*jR?5redNLUUbwKDFa(XMcTg^ni*AvJdBFDSik(!LW?mBAwiJFD$rtK%{8m_Ll zhp2;;A#c=_L=c)HXY42HEKQIw>Qw47?uO*3td8T}4Rw_Dq0W#q`j@BV8DoBpr5Z=b z9T+EfV2svfu==kv7MU)qZw~l8#TSVCvU*p60yd-?Vk!~T^#&R?+jO{z|l{$`h z=4dBcsg|`r+r z%Dd9;-8tTkqg`piZj{wuc7q4HalAW6yV06mDbJ<6JN%%Z&2aJ&=rnUVGl#SXywQcT z`uz<@o0-Fz*IBbzqO-th2Va8f15 zgUB84rgK(p*fDMz$7;y~=>?8zVxxNX>-E1sePus5$>_MEV13~s*ZoWg&|VxLOuhn6YDwu3@`K@|7L*PpKLk!Xl(^gClZV1dhb4zY%gIk5KOBB)79u>C zLB;uuAl(!y{&yVlmYYDu1&!lefR>UU4K0wDggDdAWE>4Y8LwKD@hG^;DA%HoN5W;s z;1=&Zg8$vU~ZcdX78~l)$jX^c}Y3m3@R@v$IGDdl0Bp;R9>vOi}~xyU}R4I&rKhbkLtYHSt~CL*)qDp$Als7#(=Q)~KZ{FW4GN zFL}Y1sD{cBainsbiX&Jz+C+{}Z&Rb2Kt4Y3f-O_UvAkfb=wT=?*eZGo$qTkhB~)Ip zRXRfD1>2+pREc7nR6vy|wn=-aTreZFzb(_2vh8on=-*)b+cK@8w!baY3Tpe?GA*ID z|J>02woh})$`aeB9BTX9KFy%Ezim?nwf(gSn?h~>1)=2~1qzgHd9A=ws4c%Rw7E84 zM%gxZ+)1If`L<9;rka}AhwZ`c>Gx6gVdscqPnLILAMPG_C-&iP@XPSfhiyH%#*xFG zEZ5kFZM|I2u=PfTc9Y6Ku@85otu3qd%nL+RwBoil-jZ%l}!FH?YU_( zIZEW%p0?z_TP7=OtwFsm?ML>FAy8$rePb|GnLR4VZu`YR%1Uzk#Q><1Jo=6)SNl;` zhAUV5Lhbj;)jrUO!pTAQ7I8Txf^yZ>K+5n5L3&G-uu5;GYaP__+&)taRfbOv(%YU> zO1c(%YKuLfQUr->HJiHOg3bWU&7$V>>~W-pbfYs8V2d=>JOE z4wRMKO4R8)UVzwh3j&YOR9;REfQPkkwiXC6pbdwHY#~5?i|= zg(|TZLq*0unesaJZ#6EhKXooOt_{iSh@5*DeEy*l*9 zF#QE!U89u+j~52Ig;gouZTjBE-X@=?fZC3Rer z`p?PhjsX)951F+|c*sX3ueS*j`~SAQ-hy|2Tys#LOnj?&KH~lHtu6Br>&_`|k=Gl; zum5x9waB&jwMe#ejhl~O|10p2P4^in)~`QWpMej9hx}*GPkr*`b@Wr)l=)*lK=l4_ z?Qiq}`7rHSj9(YyTc7OtW3eZ#Pv;k%aU2$A7oC9|#IZWHb36l~&M}S*vx}nH{VD4w zBBI?7>KvmpkbR-fF^&ndi`H*%%5se}kom6W>e)Rxc8)Rbf9?#VJE@3)I0IP+b&k<_ z$6Ba!j1$8gqcf2D{M!GWf$R=dUvuu!)#qX$?gZl=%W?k~ku!B|_hi-*6C3Fal}DU= zboXXwI-Gl~gsM|J_vr4y&RoTPz?^}MyM$Fxa;|Z9m}zwGu^q=EA#=kVqw|h!C_BgK z++%B~z9G&%wt_m-I6urWI``OuvPg(?kIkWK))5g|5M~;;33H5MBV`~Y&NMpr*c2*q z9cLUDg_*`}!yKbnb}5Lqk~&K4?ZQl>QaeL-JJaZ_V+wWbcD~V>$J{sMqmtEn^XT6t zrnc#_dW(P8N9W%az4eUsYMUAdHu~u~%ioW_r>B5D(8!)~M>75O?1A=s{q^jDwx9lb z_CTeC{(82pk|VAXuMRRqUmyFS(nMb$`=N3~Umts;aztMrd!rIWUmts;5=37gd!rJh z6V%@5%yDI)N)h{^R4L+qQSKk*9#QT`8@=|F8v5($ucg$`U(Y_NywG3I*?;AQzCQL$ zoUaE)Up7U7_;8#(nl|eOt;sy(&XH$pfzP z*s#x@t#3uYs z_UlcT%l2V+as5~M-P(uU^+Rs44gY`fyM3=*HU_uS*~r@OmCLyo^(RFxH>{P*mH!cP zIrpOe*UDw}U&m8-A5-!wr;UVdTife;Lmh)1O?yFYYe&_SIVG=BJMNz3?yhkUM#o@B)(%kRukyMAYTtEab^li7uOq8Fw<>=fS=&M#eU;bl z&8ieODu6OuDeQO~cY1R#8Rf51+a2VUzsl?8P{&>6bvaZith{apRSGMw%b-eOcieXe zdE*1j3sP8lU7)NKR$iAvmBPyF5~xyGDedZ9$6Y0L3ROGa2CB4m_g?7q2CL;m;a#`e|d4X+>k`nvJQBZJ@Drtfd>6u0RXdnejE(Wg?m zI}I88@3(h0UG6$&y5`JLc+=&syPUZLn(I|QIdZpc7;_yz$0K9^FUei^KTnYmjcEej*EW4SRO9jP75-LKGnE^BI{-S6J0^Mn2(b&m~gQup0(U8`D;J8-y`Rc*-l zK(1d^OPYhmN@Ryq{%@SoPrkUE*WZulhFd*6GP2#QqT$A%gCKEi_Pwg+d7OWqo4RA1L8Z_U`)fioS0wqjJ@HvC#qPgisAz;AFRMorDz zh1UyzF8m4lcHu4Zw+pX9-zvOH{#M~HR(5+2zkdf6vj`F+sC`8FX`T1FSxgNL0{Cpyq>Vn^ZJ55r_bx2 zUJvgacota?uRGksJEPC)?p`;zyLVcj(cQeRa5wLiKCQcYUEr?XNqtIp@jAm@yc7DQ z?(B7fJA23V3Ejy%rjLUi;ZELBeN1=sI=~&hBl@WB;I)T4c!%{7-QH^lxAzX|!@8Z< z7H;Pq)Q5CiuMOPRJD?BhHePFQzdoQ_BWvUB)B6#%f?Iog^*-IoYYDgV_UOI3rPl&( z>Fw5gbPKP!w@dHV&5^b6cIsV-n!(Mz9eSs3<~4W^}Tv< zeQ&K^r|WrZ^jfekT+dsr*XX)l9k{NyO0U*+yxQJMy-L?cR>xbRS0btf*Y=j{6}pyJ z(_5yO>zc@Fc}w*&L^a@=-V(i3*YK*tHN3@oiLUM~(u=`raCL8?UZkseRpDyh0=-aI z^{ROD^#WZ5SygYIo{y+9T*aHK=jqB`CAhLTN6*!jyxDpVSP`z|&C;`VMXv%}(VMAf z=?dNqJrgVsSMa9m8M?ez4leIa)6;c1uPp3ys-C8&=&8D_SH_zHPDWP7D-DoK|* zvf|z-JsMF_xR^ImkJ3fGB5+Y}gdVAjc*FGwurOT28>WZr!d@Y`us2i>(}lc(u+JfS zs2;3`=z?AWZ!kCrSphFU>~o+VqzCAMI=`3C8vyo4me0!z=kxmM{yMMMSN8++z%a*+sg&}?4^6_p1POL<>mBxf<2Js^m4#HyXzjho9?c2c-g&fU{_?> zy=-uHuZ!-gvw59$7ceWF&FiE)>#SZDIIGuDchXtB%&^Z6x}$EdJLt?_Ca*o%4p}BI zBb>==tJ~>}UK`yO%m8QfTI)7CgO?u8;I-1Nb$YL*ZUv@;(|av+OP$V33#ap%>lQk# zmj?FPOgGm}bu*pDOYJoUn;=W=rGis?jdc^9%4?(>gDK%uUPIkTr}R?5DZK`|p-$l? z_v-5gIytfwUOinOQ8GBWS6A25$-Jbn&pNuUuC43nq+SxQHdqT;5-%~F#H*=m>BL?Q zT@y?MC-$oA8ak1e5KiP()75oCF9Gbcs;;K1=&Cw_7vHM_Rz?=ziwFCxq$}%+x{{9P z#q}zJ6_CaC;=pme^16bK$&UdZl$49TQnBuaqv0 zCjX3hN>| ziWeD<;uX?`b!0D+S5Ozyk&s393h07}BEpfp{JMaS=tY1ddiivI9l^`1^MT>v2wonY zSBLk)!Qs8!I*$(L<FkI+IOJv3 z*|g_5*z>aJtlD{*br#UV&da1TYwHngy^K1OCeL^obVhBEk(XX)K%`;grPJxP_LP@a zr_&0V_R{FIh$O7M)H;opo`9v7N~hMsOQ}HdR%y0|)?{?Gk@ea6vob!;6+|8U=3Y%mtG@9rD?-Nn?g^fwnn#{|E^-&}MZ zLw|K&;IA&4j;_DBs5%<>8UEs;=&1U$`viY>k#!XP$$f-)^SkbAQD-*z9> zCw0qxP#?jY@GbXVeNZ>u4fv*er{1d@?z(%c-l^-zZn!tk{FT+>dbM-=9c9-DG?wNY7F1d@a&!_5{dZM1Hi|&GZ0zO7| z!JUUMxJT--I`1B;N8ma5ynCP?s&nove9qlh57b$APu&O4z-QfEbx)mfr{Od1j=HN( zyHoIKcU#?2r`#=d8$1c0ayQj2b<&-HPr4iGraIw{!zbKzbweF@*VJ|J7<}AaRoB!p zcN9M6uBfZ(s5=55b(hr@b;KQpkGMz#*fV<$`?wC5RcDbGKE_YNNQ#;)bcSIdkJCN;kht&~8+u~o{qq&BFHYL#2*Hh}Aqt#m8km2RC{uU5F_Zmn9UmLpr?)~L0J zmch&2YPCi!b4%f6Zk1ZCmbxXd&y{MGTA@~|C2p}>0WL?j*e!w=yJc#*TI80hW#B@1 zkz1mcs)cR=ywELHOVk24A70=Vsl{r(Tc{R+^Wgbzfm*2Mxw-H>H(xDKbKM+xuA8Uk zt2u72ng`B?=eRj)uA1#;!L!|LHAl^IGhv^z)ND0V%~CVn3^&s!vKekV45}Gwx|`;v zsp)DOvgvNBnuchqZ#P9vRa4y*-)^#+qNcdXZjzd;Ci|J2s1UnJ@MJeZA#)SqNp8GC z=EkY<-~@Q08>_~t32r<*!HrR4)p$1!9`8o0F>0I}rAC8e;c;%H8l}d%G4NP7LXA{o z+-P`=8?HvE(QcR;4vvCHyP;~B8s$d9qudZRRE=~aV4s845H&~*RwLYSHwYYvY`7Z+ z4|fC9KsC$_b^X-%`l^0vh#L$KaeY)@HQ4o5eZWERVAo6aR)gF? zc#!L6>x~m?lzv~D0cimKX)z9^X`?;>Fo9gTOzHGVzG|RayH;>(S5MVftz1jEm8+}jsg|w<+|t!ibyW*jTh#%Z!!2AbRa-T8&EV#) zrmCfyxu&qs8mgwMu4<^Ju8FG-RzudrHHLjwRn=4#RaG^1ja(J5GO|XlA>7DSQk7Lh z*8pzlDymAVfvcb@g7x7BuDq(C>brVyeOFGESM^+7xSlJk%Bi}p4qVrjQDs#fR~xS5 zN~BA!xdA-RdrVluI`GeVyc>} z3i~XgimJk@h^p$UxWZr|WK~>cS5OsFm626(1yn&qmEg)Qzbc?Axr%Tlmrvza6$0C0xqdart-TaDk+!`&hHYdBr2cF3+Ho*RAQCaB~*#PJaAr@ zKqXXpTy8jzi?0%>+%6aFGoFgC;;MKmm&@tmf^m@LbU9$3u~i%uOT|_>Ty_@=jEO9} z%Le<5p<=4&Du&ADvbyMCG-O#_7C5Vms-meZE;F3PMNv^zW|s-h>>{fuDwE3yXL6BL zWR=lnfHS&?Dw4|J(!&{C1Qk)Gcj@5tF1(7M(zIu}lbS7}`uIIRn-!l^VaHJrwU zQDIeTmkLhpLMn_(O{t`9Xe^@8t&>-9>Zn z!FR}_xu|e7_g21>QQaH)7K{Q%b+6?c8O240qqtY{wT$du%2!|{II?>oU&=@>A{@y* zmoH>Q7r{M~&t(K;5#3Yy3{iMEf_oyL%J426?DMgFA|J`eGMo$R9)S;$g>_-zu@&Oov!?=6$z6?1J4!OJXp7fl9ecq9Ge*vIe_yIyXPkL@G7POg`akUh3*#Ia>{a-hohRqZtM&?f)y|dk z)!!{kAG06u7k$f5Fp-47qIgXIvp z-wu+4!F}+4J5Uai`|MtLpB*3v%Dr|Eyw~=Z1LPjN8{T94$^LS;?JN6%yWrinkL)XV z*`4q%+gtXLJM9j5r|l(s%N=$*yu;i6rH``9Kv)p7i!kcVI*-37+8(^OuWJlRvc90wFdfOgs zhituF2d}qnWjndfu7!QJk!@vb*+#ClYiw(<6|yyUHN3{Ql&$1y+d{SkSHY`obJ;?! zvMb?LwwY`$SK1ZuO50R6lPhc!*%Vw3udt0}6S>?jgO}Szvawudm%__zL)l0!wM%RR z*-$P)w$#>_4G=Acm)Lr;zFce<*}AfxT!d_~tt0CqS_m()wPhW-&@O-%+FG)9AS=q5b_P7tmX{Ue3|mf?2dBd`Y*|@OPPfzG>9&k4E2r71 z@HAUmmXTBK6kAG`mQ#>TwIyXKM3dnuwuCGxC)-KzWLsR8kdy30c#<;&^ z31uSL-FAb!+XOP9>}I>#_%ea)imaQBC*vdP0(Z4>Wjxu%c80syI5Mv6Y-7tfU?;e< zjU{8tPPQZ5$;OniWJeoA#soXS9c^?OLw2z3;SM&Mj4s>TcCgQ=GMbDcqsn%+t&IXk zM%LE0f!o?hGO}!ABg#l%Yq*V#AS24wwiVpkhL;g!E87zG8BT_mVP!bk(zdW+!7#{L z*yeBx8V$t0Km1e5h`J^N48w|~VyQP0+e>)Aizuc&K( zi$7o;xUT&rev3M`HeAR46u(4m`=9s;)`Dx>AL2hz%hrTz+3(_qsA+4!KEH|Y;;Z;3 zYS`-bEBFOjbz2RtZa<4JqMH3AK7&=^YWAb}B&ymfa8>(3d=yn|W&2)y5S5WtvG2rt zM3vym_N{m)D%px~CHqFa6%}m-xT1Y6-iQjeJY2!P60b#hTMjO7Uy4_voGlBNvoFL; zQP!4$%i8DSg(zc7+h^jrD2=R)eJY+IDg~FePsCGE%9eyn*~j9EC}~T;CG8{eSd_5E zVV@7hBk@2y6vb^Z`vAO;te7nd7qj=oeNogFfs5L^;+`mC?})o#VYrCBE$)cIwh&y{ z-V(P(AzKhGWN(UFqM$7R7qmCTO;Nz+x7WoDksnzBdre$Nln>5tuZn9TpUn&Bvsc7b zk=N#d^V-YeipXPg!+Go_aarWHx!~OPqPQe-*_?1LdqG?jIc*L&r#&w&h#WRMoWq_I z=S6m#4bE=QigO~H%?f9;XT({N)n>7$#Tk(WSyp>WoJN!x&SFoBQzEm?1ZTD<#7U9K zW`r}@QzW*D;KX*j*dY?xgm5CeO>7qlZ2~x< z-72<;1U5dLz-|#+MSL3%j&C=MEh3(c3&*pY#AXrKZWNoqIB;CML2MLpY-~7=T`x9> z*ftg%+pZJqMJyW=j%C-1bt0yX0mrm!#99%?)hHWD1!E)&Z|BpVTqWS5F%BBEU)mVy!Bh<349A|lxE za0I(ZEEeHyI5@mrC>DuuHY^;@E)WYvSQ`coYv+pvB8&~eVeC9HUxcg&hwNN2Pk7eB zo}DA+3TG|s>})YdSWB?Av&3vc*1%+Eidn+g8Db`=VPmI@8A4kHYdcL$7s^Ul*{Nch zkXFFbP7zauupAb4vX~;cWiYps#ALzjKbizi6qCe1`b!hR31Xu7OMl?MG+s;)f9N;- zhsKHV;y3+*f74hoPW+;u@Glx8#)_XbT8shzgMZQ}FAXY)J1d^Pv|lHggT2Z;xTm+oxw-&W9le6iAVGhencHaNAZvzzz?at=pY`@ zefR;j6Ya%)x(DBBD*XSyIjT(z4;woK%uTmq? zSX`mY@D*w(8i~tv3BF7XL_=|jF2a|nzGxsW(gpY;)f4r_1v(F3pt_=-I8W!`^HfLF z73b(Ie2!|1I^ryyfzMJcQCpm$nxYnX8a_icL``v;PQj;GI-N6csyYJG_Gmiy~q> zZG*Q{AyHUtqpk2ZDkutxt+WO9SwIvN`9%S-g*H=uFdwqbv;PsSKE$lOg$SJam9AYi4q3mEbWNT~omfgsD2+%fmLOY7sYMz@i{T}dN~9KxX%W1bQi@b!5iNulQ3{b#ETjeS zLP{=Dhy^qsUO>r2axtHhie%tCcs?Z&NyR*x3(up(B8iwwi9}*>4m_6F_K2WBgqL*j36r0co&Vt9_;=om zdeS%WE3%%{1MW#*_*dS8y2Cx_GylT7Q#bm=Kl5(Ly3&EN2j)B)~DulQ@;f!f0z=p}!}+fzH( z=L`OlKj$xaJ8DbM!Dq}1M8)^-=p(p$)Z%wV>*7TS^;jO48+=?FY$Gj!A zfLqc-{)o4r=5Pyoz#sDF)C_J;_xS_fjGDsD=pMh%n^F_FDc$AwcoS+2H=#THE^kbY z=r+H@8zE~VtNa?Thpawb z;a3sWh3nB}eudYiI!nNouKgVlQ z4Y($q;b(abI?d03)!`a+il64ysTy3JPV!T{8lB)L!K!dII?hkd zK9BNa{0KkFD^n#p0v<+Ii7L_|ewbH8R*4SsLx?KC73ly!$SY8J+RqR0^2jRCKE5AO zIk-IS<@ zrDz-9&P&o(z6~q^m!vIxD=$IC;S#i&Z{fvh6W^95jbI0wz+^Lcj424|+q6bNE~^E1ZpH^Eo^#Wr4HO zEIylOq0Dd=n#pJJ%#?{{@R>XlvdlD{&p?zB&P3Drbe@qiz!_;OpT;v#dN>13;Zu2f zN(ZN>$$Sb=M`_`7G>K27?q_;{X@ zQot!`EFZ^H&=@`zOb(}@(R>U~PRZcpG>VVr$tWqDj7IWNJSioClhO!2k|&|Wa1t8M zNASdy2u@7H_;8+x62ggSC?CcXQUW+34dFw10*VhOpuv0yk5BR7_%w(Q=J6;l4djD( zTx9WR02~J#2>0g$cpQoi$Dw{aHpK$_!!hAl)R*_;F)0Qdllt(!JO=gVeZc5&4C=*u z^XL=}j!r#!FCLAe!qKP)@5!T56gVn%=RJ57iVXYg#=G;byc>^9k*F)!1z9AD2uGsM zybF&=5#Wf_iFf7^C_L=5Bk#mJ@Qyq@g`*B&dt~7#EF6y7@%B6{wdL)=FmPCE!`t#O z6oSK0Yu<*3$fH)gHTRH(s3mWO$iW`9;4Qf$OU-!;Zjm`^#+xG|*iuv8j1w7{s0nY% z4K?OXKn)ve#2a%>3f9z+H{yyU?6U!H$m{b4T#}&rU_E4lI4r0xug5ttm{T2Imoxfj z>VUO*9sbY!HMPN7yf*)9{=k1tO^{@r|oznhA@68~nt!rx2glVKbg|J4F708m{Pnn|A6eHDalJAdJlgv zC3s2x-n@f-7Uv~+F2A+}MGj~mTo`K&*cF&~a=@H$5@0zqc9lv94!*@&? zo|fM>sd*ak7JS>J;;H#9a}&O0Qu0*%rb)q5f;ZrsCOJ>RZ!~=hw|O*k@9n zj3?nq`89LZBmom6yK1h$S4|?Gm|rmoc_Q#Ke8nW-3HfDn3BGLN^91~oxd{7=$K&(3 zJRZMjE||Dr9Ap>FdH8~f&ExR%CKitko`cVum^>CgXU@XsObi~ApEc2W4Dbwm)K4YTtX#BJ}Wuow?{1md&CNhtL=p=l~MBk|_@NpB4hv&!4QP^i#9*&3MVfj&W#DoDu$c~u9uuqSNxZ@r_Yz`R*T4aaJLHLj% zZuvoDIDrS?gGO`1519S%0i(F)`^`Ssr{szYF8MyQ*9ed!+iUi~dky29?=idKJ?0-{ ze7D&J`~1uPu|MoD+hul|Kj3d14V?Wt8vlZTE zez5=8R`Z?x0Jp$f%{TU)Z84kSE#@ox#x|Qx@MiOcePx@>XZ8i$2yZf<*k`uUY=AeK zkL(lMU_P*q;Cgt2dCxwu^=2Ks-n?V)**dcp_W72*V{h17w$`jMZ@|~c)|l1s8uN<1 zW~;+qCR=_LGGxnUVFw5Z;<|%u|mYZepa`S{eWy{P` zc$s<3p0K6n5qk_SftQ+x>=9dH7Q;)-1NM+DHuu>Ba1p%N+++9IBC`-)WbU$iY@xZs z?t%;8h2}Q9!xotN@B(v--DdO6Jad!XV)KyAH#gW#M04SJ<~qB<=9)R?8oSQsAe(Eh zvTKND!*k3Pc9qRGv*6k0GP}ZNnM>?4I1`>_F0xB(rkMfHG#A)KHp84}7r^Q840Dd1 zXVc9zc)B^u&ar9c3_A->g{PU*>oH!`6cR;Q?kfTf_RBesF)Y zimhh-OkddNO16rvU@KW))5oj;mm}+Adc%FpGPa!cHof59W+_|7dYPVZFSCR#Wj)Pe zwgl_}_cV*xV%EcShkKZXY!T~jy20Je0=AHKGhN|sWT6X~1@_q!fA_Tq{@!a9Q`z(YyCbV?Dw%Hh zTd$RnRW@DmmtHHGif|><1%K(aqN!jy43jR zTMk)y(;k1Lwwx&omox3~w`{`PArQxYy^THr6|mNX^clBPNS5^M?6j5P;~!zD~pZ1fg4#o*$m3HEx6na0@J zEoO?s#Y`jY=@vCb;G(7>c5{oE2H3tWVhY1WOnvO)7B+?8!loX!nG2b^*kUeZ3c`g< z9c(ifGzH*-rZ)DN3z%BiU@leybchE3kQCXcBG zRz;S_?Y?nxlCoS60%$-C+xE#c8)7xzc{DKVJd*-k>xPiVV~u&Nn94Y z!`V$XQx+_PESt#+`z(!J^HTnfxyfQmfhGMNbCVg)VoG4YJhLf|&GO796P(!;!)AFV zlM&8jiej@oqbb6Qf*Ih9rZ9HOGnn*n22%*zEQIH0Jh1~nY3^^lOJ2; zX-z)tkEbS(Fr#7kJ)Fu~p}oP2OKOssOxT@If-I@Yh>iIq zCNZ4EWWdIJVw1?E$F_VTWQk2WmL5?;IFU)q@Is17VA5b~J^`|XCN*~D6PWmL0+WiR zX7Notlai%k@sPzgDOgHGap8C-IZMIfnmBM=lZ+*2aZFO|$Hy_T;W#DecC1f#7e3k%=4#zO@uo)lSM1!N7xY&@7X5wJ$ zJ(`IMM>Dap?;h1efuovO*mRF#Vq&j7iir$IF)^^k9@#{KBb(^hUyo!W!jVig?5syL z5#Wd>s=sA!!ov|v6o32NgoDGI$o^KkiG*$Sa3(Aq&P2pUdsq_&4r?Odg`_Yh1cx!< zv85g|9vm{^u(|G;u-Iq!jDtNB2HWn=SlF2mHsY-z*cuO8^JE-$>d6?GjK#*iF&Z|8 zu$!-qg0(T&-&aOsuU{DnW2hBd`_c#);{@1>7ly;QCdGa{Hw?z16dUu*{L>u70h9gH ze>DRq<57pd`Vah9Px2;vfAnwokDlmF@_y@I@NYfAo9O-0KjB|GsZOHfh2n;ig2|A@ z4aI@uhLY=KI!-7y94C}QC)cq`=^5D(u_EL?u=zMkqD*@M546GgL5? z2Ag>WQHc>M5K4=Uy#k?h*x@UHdcjcsPS?*dxpp%8JdxT!?draw5(JX2Zr|4lrjZM<_cs5wnMK zU^g*4VpKypv9XxVuY|IOa$$=xD=OJSSwgw7-IxWHtf9=IJlJ~7j7pYJrchq&L1qf& z!)9bA)H8=NhVo-$G9xOPLK#8@utS*vm5ibEp@P`0Odl$QZOiniX9%SW6~+!`I#kk! z(uRs)FEcGF=|X8jMX|4$CR7X?oM})`8%iB2j-AfbsH6#{3YEaFXR1(1Y=5RgJ#{E0 z;#6QMY=x!>mByZEiclGBj;25*Whgn~6ku6wl_mp|hmwWLVbe5Os62L0lY+@YNkbK| zlbQrf8cGtXh%MD5p-R|WO$;UpB@R`_K5HT{aVSx!3iewQg{orbH6fTNlrU7y--QJe zh7yFTV>dQIs0Q|B38B2ugt_G=Yl{BLEov2iO|9qiyr)bW3o)x~bE zKn4G2Sv~CPa#kPvyBu}=&t(m;*UM1h_zh}^ZQnGgF#HBJ!Uk|^RMOygs1c%6tg*iz z%$i_hI3;5LZ>%@fO>_#@Og9CaqM97B|99A%>t;GRYoVL#WMFdqLbb$Ra#AoEexX`n zUpWbw6u(fdbt}YebZea$OoCslw%Bz}1SZC>RXglJCt~ff51kN9gx{=Ttv5p7E$M07c>|V!XU9pWF7mSDBvToSVjswQUZ&`QjZO36f zu*n@8jDugap4jY;1;)njS}*K;$6~#)1s)TOgB5%U+jy=VEwQ`9vzH< z-?;wRERP08$8X#K?3zaf{TDU{Vh24c8-%U&D4_rT#$arzM+W`ZIfh_=Ju(}LjrK^O z|BlBnY`8~c!?E=qk&VC}d_+_t;a6`Y_TwX<5)r?8qp&d_o{h#1eR$L(;1_T-qHt^s zHtfT)vDml|%f?~T}yk1a&&BIFu6;Q8;lf`_za8MqV3OHdb zz{>~a*h0L7P!4tf)UgmzS+)poB$NUDH*OZ=?S#^x|IW=4ys1!{Eyeo^rNGiSc`U=b z3nfASwVUO5kD&zUzj3nyuQU_~{Woq_;^l^7Y!%*eD8^RfZHHp06vruK4c>bwib^q@ zLe}CPh$5&I#VKSR-iIiRN)enz*5k#9LZ}qRS!4rVk|>BuA)G}v;)RI0~>i zTxIH&Bvs~TCsY&fs%#Y-Dm zz^pj0?86HjnZYbLv+T#q9GSq(IJF$WiyaxkOgOb1#5*1tz>GM#9Kzck>A?&*yBx-w zAL+pKIJ+FdTOet{bU42p#Ty}gz_d8!AJa#5Z?F$e`N#35NH4HA&iE(r)<{pV7tZ=8 z@%l&)uqV#?r|>FCcd!S}`={|*NjG)|@0WB#+#P5Avv}8}D?5jmPP(Gr4X6I|cmbsg zDqV5zzkrufI-}AB=l+X$DWwy;gx6C#q23u^0GIKqN=H;W;TzyGq7Li|-dyRxuHp@r z_Usy7WNDAM1HJ~XA!^62X~rJom71ntGkiHb!Rs|mz^3?qc#2nT8iP&n{qPL$+%#s-@$yY0urayqePhY=|$4*LY2*K6``rb?PH-fG>)-cyXs5dxtl8>Y-jA-xcri zHcwqt>fyWM1K#YZ!#?5_pE{`5#W%($yzWyQl{)yw_=Kny`;1qAYJ&c&Nnh|9P)+s~ z?*i3e{#!pa5ZA=_#y3ROng0?{b>_bfRE_y>2312`9p4;3@pe#ERI0JX%s=rgMx`oS z#Qc-cB2*T$h0H%8Eey^~3sGOh79d^-`X{RS!5M2l;syAU_s?GQg45VM)aSFg!6|Jn zD)ZQ!;Pf^pIMvNTeJ-1gcn)ZA=9?9q0%rxM!&#`zW;26R<4ja$u^GW>at10h@rCc7 zHK(KEfA9Ne&}pblXH$c->D1t~Iu-S4_|EswvQto*itl{?j5`^XDQptr$)JA%o)nyk zCxVmk&F`O;Cx8?2&F`O~$Ac5t_~3*+J~(ra1IOe0-#?L$1;^q0-#@934NmZ5f;0UX z#AEUO9}Bkvql0t*C~!1x0sQZQQNee@$l%LiB;rwQ1mcmP|8+4u_}& zAAFPV55Cg(f&1CM;2VA~xR31(zU}vbd)c1g%YS!p7qC0HBiN0~9=0pEJJ^NFZrtek zHw!ya*~NAs-U<5m4m*PTi0$AGwmrC~*amLL9iM-Tu@&6Lwg$HwTZ3DVE#OwRCAbaQ z3~phYgS(PV;AXZdxI@_(+^uX3Zd*2@vI)0-{$0!lR5r5p!5z(dR5sw&&%e7_hst`k zHn`bY8{GA*MSUGx6Wj!?L1isl9o!JDMr94||NQ%-Rl$wYD%4lAmBCHZN>u#2LH`D7 z1u84q^5A}IIVvmIvf$ooS#XoJ4E5!>6ZCJmmZGu@H-rAo*Ai5g;)cBuqOZZd*q7j@ z>@(sopns3{DY#kt6x_IdLgh327~I5tMCB9vfcPWm-_v~vZtmWLA8`Nf-{`#q z-?MkP>1&N!c>mt-ZEzd-78UI=Dl8jmjJLD!5yGh01H(#rt=TFN0gi zm#DvDFA%>3{X5F%!L8+U#4p&h;5PFaD$m)|;Fj}gaPRpP^=Ir!a3A^vm8ZC!_isxd zqw<733T{y!q4JnL3~pB+qVfoL^!}~u15_U3j^4kGy^qQR+|m1Ywf9iDkDGe`4)-o9 z_t+i8cfo;X0PgDt;{N`2aQ}M?yp211|91E$c#GW(ZjEn%H`$HgPWeV~%X}TY!LA2) z(AU80>{@U)eHFaMt_C;PSA)CkE8tajCAj0h3|_%)zJCLLIk*$Q1YTyBf*bRT;3al3 zxJkbNUSt=7d-e;#&HH)q0y`hv$e#nx<9^@2uaCngw z7UJ0GiuqlEn5e`;Z_Mu&#Nd7xAqMI((IK0OC_49h4AHpXdx(ZOI=W=D5k=*GXCf;1 zI~Gy6-@}N4I4Zhj^AJVmexD-}7#Te?zyA>tjD*hFLbCv!vxUebaKCF39*ls_ncqzb z2Zl%A%Lj+oM)clT-0ST8EekVzT1|2oO!=ylsewyEZlAuCg&F@PIP@=Eqcda-m&{y-j zSq$WyalhB~54|qN|DpS}8Qrxl$p4}%wgufazi0Lb@n7~EU9@fJv28={ch~$L+jitX zncsW+iOMhbAG&cn(PP_*{72BM`@#Gk-VfCOLyyhx?R`h(2m8kSp5HfAzO#}+FR&!v zhrC44DJ+3XN%XT1ngi%=PuN^W$!{cdhfRC1x)eF0I9px2un%z?hQ z-viDT^oFw`&W@h~nPUpY(AY0eC0K^NTbKxYCoqYLi$r!#_?&;|GV z))|6+b_T>5(FMPSJblpZP9Jo^{f@Zb7r%pUdD@_Bo)(pK=!pB>^faiXMMvE4vZoHZ z@2OEwgTA=ml~09AYIMi_o_$JGQlUHk#5_i){4w(6L61Lq(ECr0dJ1&NpP_S}ESL;P z8cYl%MeO&@{Yio(s3b+F+@CW@j7k#p%l-L-M8QNtBGeP3Ywpi0Bt#_nS~__H9bz}A><@n=L@ zf~_#!;?It>45mq1fGsiS;!l}02V3yw!SqS>Cz*c|gN0&^-&!Dg6u@#j~X1QRVy z5I5zG5jO#KF!f?E2jkDaH0BM1DVc`BOiY7ddZqy?{tS%8EKL1i!lqs@b5jp-eN4T0 zn1!hu%;nSp>tgoBpVz4k*1_zHKgUxGtc}?hf6AvOSPQc+{`5}`uqI|-{HdTC!L(3y zum&bz{3)VpV0BEu_|rvI!D^U;@u!ZefK@RElXo)eKHZ7R?nikA~ zO$Dc6A}tx_!=?liV^a`M#VlHKP^(Ws2!qk@UL zQK*c@bXpcn+Kmim??$3N3Nvb1k&g%_^M(f#d&3crz>HcBO!5swWjJQka$?SJC@RA+ zqvp^54GAU!hoC+blWKV|DL5FFA(&S4=LiR(G8mI;c@Yf^rVIxJbB6pwbt!YeiA*9ZX5~0()bEtvIG9 zdj(UKJ;7d>WAmpidw@ML$L7ysb_aW4ip`(V>>kW+b_2U(rp=$}>k(9r^25Q*>tR%m@I%2w>>*SR^Mi;FfweF%djLF$8C8Fpc0YK4 z?+>PI_ksKQzF_)xFSrj=s`W6Ny9eCM_XLx>yTLttcQDbr3*60j1@pc;!Cia@xD#xI zY2fX_l<;=MJNP!l+d+SZcq_P#Zw+RPw}4yumSE<1Gq{Cs0yl%rF_FA6m{Hz{coQa7 zTOi*MOfatpH}LhrWb-<3J?2(hW8!%&xQ?$4CZX4WYx(M6LV7jgHJDg!hso(xsI2BI zgNf>usI1~Ef_du|sI276gE{QwsI1`25HIIT!DXO7tGxtV%9jK)+>5~_d~q=0y$D>) z7X_2w3&BNvVK5QC09=TP)o!!^^ryz>f%7r9>Q9r;1?ORUwI`;`=YVrDz3NY&&j#mU zdexswp9Rjw^lBf>tj`2zVS=?UX4yZ0Gx>*L#{E6`fxizX;NJx^@$V47$9(xf8h}~z z0hm62!w1no%$g5G{+bV_L6|ikg!~mBLW41DJ{b8+J`@xAFHw2LU+`fx6cgveX&5*Z z)#rQ!4X5X*yx`CHNE$)UPYcxtL0yi~J&=PxCO9 zJ`ec?zJTUqDt$ik^L!yKz;yZo7g~-qH#k2^s>5Gt`;r@2Y8C1^l(}>T2 z{szk_zKoWFOEIw?9h)tuz~!_I+a1fX^ARoBhlvVC!=}edT7gZEmDvA?670`J2BTop zV>PY9rpIb*enbkkZX$w_us}4*a8V54g+qcP1yI?LYu*@v<2LZT@V*+897uuY<+B}ZP)v6uE>17r{OLU^zx z#ZeK0A?DzI+J`-m{n!in#}Ckc?13CW{+A!b=G7m5hz^1WQT>hh4|tdkVL#*u9mY<` z5k$ZEQ96R1kfX?d@?&%qJ0ZuA|HqHhG3ZK;okw0W z*l;TWmc*9VMQpwm2TNeH>ms6J!CqWZuo(8cF4HCKcU_^&;AL!m6%ID*3Zqg4n_XA2 z?^Q6^yDNye5H`E6VbiNXu$7k|EP(y48+0A}T{p1rl`q)k%M0eiewV-Fmj}#?ovvGm zat9lLxxn1m?7Bm@vDtM8n_fACjlmpXPV9I2n}pfH9N6!=Pxr9jbszcvcsuVnDayUe zSMHgbfg!^XC%_Ct&N=5CCFdMPf`AArIS0w8NEQTCKqcplAOaFhfaEA3AP6Y1-&5TC z-h21m-Ouhn`$wJnJ*Rtmy6br=bk}pvDGC+?r9UiUT||*sgt{oou8UNKtxKVc=({eV z_bP;f@e<0e%d`uC1;Hz!%jmnVhOU5D(0=8!u7$3m^14bpFFMI<=)11b&O@CSWtX&+ zxvBG@?7A7cfy(O!?IcUu%OsdwD7&P|%n6fZB~s_K5-ce;6Q~nWc1g*Z1114w*WJ(^ zR9<&z$5Uqq?}hH7^16raD;8boJyc%zXvbJmjmE&lqVIYTx{ucDKJBd5!_Wh?UJqzz zL3jEPt=B`^nW?j&?|OtbH4}Aa^j(ibkI;HOq8*Kj^)Xtn$Fwt`Zv7Lj*PpceT2Dhy z&~rYa{RV2-r|3DK((Z#+_8EH4XS83pq@;ZvrVkp<=b^vRbG`^Y2mglcg$nlts?Ha* zdj=Zao-n;oa++v&d%*NW$!VeK?H;InyTkWD&nfk9H<<3II;9Hk3eyc$r_{n-V7j8} z^r$)qisDXSXSAJC8g~k`#~r~=C_JS}?f`Z~;VG?hd$5DmKF~0?1KXqUl(xAo*barK zG|z1V6?7Z0EjmxBqg#V*&~~PvY87awTY|07c}iK`GSFJL2-Mdts9U1*OcT}uls3D0 zpw?~%Hb?U*6?fA>*WHx58EQ}Iy_*CI@Fwt0(R@l7{u)dZG@qHM8V9=Z#(|Q&QJ^qy zMBNzWrc19rXE^Q zsp9Lv)I|%LKvg@?%+~^IqX?CjzE+^Fp9|JPn=S4A9B{5RC(z{22Irv7mR5fjINO>P zX!vJ>v(RQs+dnf<`_BMpS~CI{fa%~2YkJ@gFg@@KcpsdOPFp?#)4=zwX@S4MRB)O# zHECtH&Or-O-s_rXN!N!EnG6JbK&k}v^& zqBWj+0w@oKao~7sT;Q!R793}d4V)Lo23`zfz_Hetz@uR_IK~tQ4~${HDXK#TxKS|b8)h!KHX#BgwgH9YW=crS35crWmqcn@Ycx^B5qybJRlx^B5t zyaV$tx^B5w3=8}$hQYssx?4UMLt%!Y?w0?>+kqp-+weotc*`kc2+Z4Pyyc_u7R(Sd z-tyNN95`+ahJOpCxBNH;!3;*}EuW5ofpf<|_(ABs)pVhrkXvk{qx);!$#d`k=L+`T*Do zACrCHerum4f0Mo7K5MTf_me$VSNu@+Q17*NTix(U*$uPD+GWW_Wf#nDydUJQvJ++( z9uRU}*#RR*2zjz>huMJ#guGg|!EDC^LQXDQVYXRYEIGVvf!S(pw&eV>8D@*M$&xS3 zCYa55K*%p=YMmuto3-FN{2=6avj$v?AB5a+z5v%)Us!U<`5gQLKM1+!d4#BA%~-nEjb^348OpdPyI1|5b{O(h!u~oshgI(sBVBaaf*>g)phWOb={JK)ivE zhplvhqg*{7v}#<}Sb?UaGT zU5dc@E(LW;e47sA=M)wA;w1;8aB-4fUh=>}FBzB|FDLoyMS{uja+2>}1Q>~x%GtyE`H(EK7LMe_X`VL|H9zI@pY0LU|lIh4FBAlB=Kt zk`v-{ zm=`!b$szG?nCCb>UBo%@FPOjad%A?9;xm}P@OzTq;!~Js_&r^wdSc0q@lWsxo=(}Ud7AKXVqL_Zam%OxS9m!!qZKD ztU19XJl*8enh55!69fO&1TfJ~2;5zBfC)Ie$@?`sm;+}wdBSE7Tw>$F>~?(MAsZLC z%EnR0`ZYdH%i*(+7XXgzy~Uz3s&C1TY6|FY4Z)e1v=2au)7s%W=3TOfMW8 zb5ZrMK-^Y%DK3kEidD4@ZIrkl*e&bm~OZ?%KNwrOjq0+<%!%GrVH+k z@=ERm(;4^1LR1}XIVpDlJL2OghvoKQ2b>(`yxb0KkCUSuncITxaC4MXa~rTNeva~S zZVk4<&r$x)t-#j!Im-RHl`TK$mbQGNTT-{e)lvS@Enr&W>L_>V=C=H%o5Q!j-%)PV z&0w12@K_O->ZUNwaCoeQhjkOXGOpH5;G5#}D9`KHV4C3eC@<{Bb~QY*8^gbb=VNue zvm3!Q#`Cc{RYP0;+70cRIBqwv<;2~9x*`6LwW#Xb^69Q`%elLrEl2Nq)b(+JtgE&y zzwf%Xe8B5~b#a80KX`3hj^VYb>);64kgAp~Kk-_&9LDF`avq;cT?=Q`*Qn;$@+F@Q z&cR<*e&w@m`IyfFXXCUgfAg8(EWB3bdp-l4iPx(9&}Z1Ka7dqS%Q=0zEid)yFf(vm zZA10GEvNNq;QRQl%7J|s$Q{NdmTTv_Fz{~kCT zS5|rJzYD&HH>*7N-vQsnn^lhd@7VI_9|pdIL#w>|hl0a!XqBh`+u%?fTIKaW#FqR2 z5L#1kxAw!yK^pQSS#QlF+c%R%XLq>V5Ve>b;uhCdtfT%CFJ>ietc6*JAF~oT*1)XAk$FDV7q(J5J_of&&q>vThr}#22B}ZgAxB_2h<%@g*F2|Qyxg*O! z+V*l%NtS}kaA#gYTFDY{Delb5GFf6P-DI)7ioBD>)Jt$@UPZOgRvOAe>P7f6D=TFI z%tCybm7(&nt!$N#;TPc1tjv}9FdyU5tSpv~VCLh~tfZC?VLrmCSqUy5z+>&lP03vxOeVPChEk#h~aZeO!^lbv%F zyoNLT9x`>V+Iz{`xdL9buh{#@;JFN5u`k=o=D7r3wlCQS$n3dfA0)-+B6!KZXe;CA z0(jBBU@QCQSMUOk?T5((`qfre(0TAzeA|NzA@Dq|?aCH93!cNhUCBddZDkSt0-nXg zT}eeh+sZEbnfezz+?8qcldY_ypWuJS$^9hNkG7JKez290^aJ&eIJuvuI%6w836FOY zl}-zBbywcfDeyF|?#f|037*2$UHMEWZRIw751z!~U3pF?!0&N*SK8BY`#kwi$89A- z9fvuA!@KgLj=>zq<^3W#Qs2QG!{_}HDN{%7%j8ZSh5rt>_bcR4eG79Gw|Avg9fA24 z$M*!K5cIL0MU8VbYP8pd_s{j&NwkG!{+c8DCfmo~Bw=Y<_cKHLkKm*g&llNJ|&4k$#zfd6lC4~2|gi} zAtgz8kHJ4lWl%!iBk(b)45`V_dt|2}QST4%5eW@xN!oh|{y{>6a`+zF=}G2$06tVs z1G#44S1>g1_pAv>@tSdBE5 ztYivSb+VB%SOu&~o=P^V%1#VPgq56FKL(8RW5F1|GTAEeew<$srjk>^$?nJd6<{io zt&+pf?w5zDK(6Zdale3bG zEXI;xDRNeF`?>rQU`bL|^7y&^;$R8VR`U9J{9<5n(pK{MdHtebG16A@lLuJ@EK24| z0Y5)=LGmLDgGESQDMY$tA&|-`OzLDoA^9ssNTVzO79@YAC|Q;H!2;y36eGhjADEvM zmf|E_<^}UPd7Tm@U*-YxlEPAwM9kb^9w)a`ioDERU~VUuQ<@yjBrq3QEM-X9%n2qr zIi0ekZzh5{okXV`*_??^dD1#bWT8rMDv;ut159voI2FnG%ns&ovOAT?{)~4jlL;D6 zo!yCZs*n{L2NUnaI#o#$jfIJGVw`FujK;vklFd?`{LySMF=VvVAeS^Nj1pUFl2@7q zCMyXowMa9~43mYVmfED8W`a>}i!x9%!ek<+r7qd1(M~r6%OO_J(<#oF(PI_Hvq$ z2-^$3H+f6Si|q;1i@c>4?lFGG5l*JIVoAW5lmz9oQ9IS z+z_S_c}_#A8aTs9Wp3aot+~GQF8R&%sT+{$^e$CBN9oS>9OXUNbw-c?U6;BZ*-j&< z>Nq3Ghpr9QA>U~f>Cv^F(d0?j0&A1@G={Y4xnM0a)5elQJqMgiYT7u`spmLKt)30e zAvHOcX8W`JNzNR9 zHaORx1J3p*ldm?c##de-t>H47MfyVt*t!iVU`; z{t|x#IFbyuW&Tp?PyA*6aBu`^Y|H&m{P&zs{T1MH*!P?j{&N3aXQlrs_$ll=&MJSU z{|?N%q_VB{SNX%7&-~TkD%hdU=l*B@P?%w4vwh)z?!WD<@xK5+haKXq_1E}AVBRL7 zZJoc?e+y;^32k5c>-@paSN@maI@m$Z*Zx=jAeh1Aw5|8Q_6NcYBBgDEzute-+30To z*TW8QHu)R<0WeB%+w5=h`#W3w&EO{3e$G~Zi{B5XKZ%Lk{H^{zn0_QCZll`kZ1=bM zd%(TqChqXJ`@5Z;{tj>l>@H`Qzti94?DltoJN1~e$KUPm6hnIAUVo3j17;@~iu?S% z{&tuhWGL?U_xamkwv(ZFz~Aq0bq@Lm!2PgWoJ0OWe+$f3@)W=E5BZy6wveZI*#E}g z1hbhu#UuVUj?ovckvhhXX>;5FaAn!6)BA8 z{ImY2;7U>$&->^672v0&F#hVF_m_h!$YQ+U|LT7NE+>oeqJP0(27W>o<0b#1ztp+x zUji?|E}>ouUhyycOPs6z6@RgF&A$p>rM<|x?qBm4!I0KSy$HPFU-uV)C>Xo!kB`|05W38lB(#+x~|zN@@I!YMyh)|IMFA{Q()Mcc^YVcl|s5 zE$}u;sQ3K4{!Q=}d8ohp_xu~+P4ZCh`@j3w!5hwX=YfCUzXo1+t~n3=2h@M~5B;m) zHRr1H$p6E?0$z2lIFJ2D{$=orbJ_XRe@y+v|I@z&UUn`yPyHwUMevey(Rt=S^)G-I zoeR!i{xknq@B(S6fBS#==fPh|OMUMDP5r`u?w}1$zbE$ zcsG5-2`4HdIhZ0M3QW#p$DNcBDI$);oFHR0RYb~&V=%|bSWO*~D&jksV`QwRiAWuB z)JYqW222h6E%i|_T}0Z5Z=LiJ=^~EsAJT*AX&-iC-8lC!%n?#oW87Hx8<@jnuf|Xv zaV=|{1^B)nZc<@ zNqz?YMP_hH(vqKo&&Ui;L0a+?@F|JGQKTjR2|gh?I60ZgkHJ4l4o*g9@+0su$-$9i zCjS9GB0o5S#N>zIALIx7Bqu)rACey&PIB^n@Bt~pVWcPj4&HY{q$mGQesBo%NKd{; zhOh^^uIJt*Mc4&@1MfJdkt^IVEJMFPThyju8~PR6hOrF&&R!(kG4xxs18?IDqFFd|~NJGC% zNAll_fQ5N1nW10ulksRI8vl$`$qoIUA7$v5{3z<=_yZ{SE(J^!ZYlaDKP5~G`~;Mi zmkK5&ZUg!~KQ&A$TnO}gej1q6cogVY{j@M?@Gj7=`srZO;%T5?_0z+o!|@yM{KB6FCNrK44pmk|Npjgh zInL-_ObjR|8r_SD1?5endogjKJZp3>CLWZRjZcnUb}%0A2<R0Ofk4doc;1+;DU+ zCeaA)!cZp|IjQBFqb$87P<}coNZQK<%4J9QVse9W-qF37JfIwTl-rjV%wyy;lZ1=8Q>XJDMP7vr48lem8LF* ztAO(J%D|MyZ9wVR6|D`*JxX^)>wt2T(p}NIpnRruSF|1||0&%Ytq;nNO7}(^7`iLkfVw^|6S^zf z5T*eh6iVG|1k(_23Z?NihG~Rbh3<{M2Gba2y6%lOfq4y|tRvhTZ3@!_CA;orH-l-4 zpVqfj%?%~PwJ>x?y9IS~bn)L&wKQ~JyA>#ZF5TB|4a%`g_qE%Aa`I9}U0YBNU%I>9 z4wUDYlI_}q@&eO6?hc?l!gPh^uXCb^ALK$^u+N%^ALK& z^uiB8vk_j0>5Wf<<{|Wfc^yAB%|>_wrVs84nvKvG<_)|TG$)}SOkbQCc2V^=G&5m< zv4=Ff0o46*a@a%lrm>f-yMdsb-83^{5Gcnt%}f{!$_Gv}6W#*l4X2q2_(+hhH-!2v zoF$aHhra~vp@uT~hQhp!6U8TF^$mj=imv<{9(fm(Kb>Zeya&p+PP0dbgYvV} z?2!@RaP;h&LoyN^fzDlXNJfEj#M2y-(V(32G>2piI2ygY=8%jvG>2p?^%!HEp*bYu zV8)`j*Bp}ZFyo8~hUSn=fEkZYUvo$%!c0KFuQ?=>U?v)q4b3E(3^NJUzh;t5ftidO zfM$|Rg_(j^zzk-ROoN$>CpvA^A=Kn0FhBY)tYl-n5vw)Vs!x|%) zqqP*CHuX~U;3LA8fts(i9F&8k=4-70x8N->fO&V@V7B5pFo0^iq1ksk49&aSLA@QPf`L>! z4b8sW1-){Gi;m zZ()w$2%$NXM`6B2*{zwA-@zP3@!g*4xY2=`lgFu#p%CxL{K*qA$5D=VV&>%cFelKJ zcV_0~Nto}^n|ER6h*3^KNy-t`6DP_TFs*T36x)L zPi9g6Z1iIOUdvaQDa$zMSE+g1;&7Iqet@2#@X&Vlm7RZ`k{qZZj|=c&)3$5*D> zuQ2D)>1&Sb1(;va?`w|hMVJfd`ZdS(63j*P{z`7U408z|fcjKd4b6AGN__?20L^#3 z26NT8ZYT%tI?Od31~lvS2F!I_2sG>UCd>`o2{h~V7R*gt3zRl@8|D^n2Acc&8_aFv zj-k1)cZ|ZM*4=^s4G)CERCf&}oZT~ul6-cL`Yz51MX7!_ijj+U-%wK8ed^zh2h{R7 zF2OwHhek<~)gDqmzzw-1)gMMFa@QV#a!D>t9@}G3?#X4yY5NnDtFrRjo`7;&F2|hY zr{EJb55<8x)Q|ya?4vdXZ7nTO=sIY|S1| z2FgcU32@25WcUMU_IMPS91nqfR4Gj5#-#-1&0QcYe^@F|ZrugRnM-9BB6%(~C@=41 z%p^|(rpDttIdl8dno2lJOPvNEaLw&c2a^`x10|xRhe?Mwf@bw+fJu*Mf^yWNVKU$_ zu6(tOFwwXxXl{Qdn2dOlD~~NROeQ?aHN!s(OlFkV%5TdGlLbY#=J{uX$!f-!%6p4} z$%c+wv;AXXV$3*dd7~>OE*_Lyy3*sagYh`3XQ9erDq${%shR%?U=CE|&qCS45<&T} zOP7%oOf++v(q$xp@@YHsxW;;btI}O$C_pxEx4dQxT?uS;>^X zrV>m=v$83DO=Xx$W))NVnkq1r&8nvKHC17%;ISZmO*NRRW_44_n(8ps$QF>YrUp!P zQU@MW)ikBAsbxx8Q;WJLT5Kt6YQxk*qkRfxO&yrpXtz&M)iqCtPNCjDjcU7|d4?pj z`k+z}lyKGnR62sRR1HDpB`6oIktr2bBkG1|$$ue1tuag^l;+Y;y#~`51^QX4Cg!=& zS@h`V(4jXqrJ`yED!D-_s^*{)9i*RX0V?U?A}Xqupb{XYpK1jv8R9bfsn(zpBd(yF zYGX<{)rPt?*%DGtwS{Se?tVAQsdg}J&Gytvq>w(Y1K8f|5Gdn1g37Mghd!=NkXx`JKIu7N(T8`#zC7U<);2gP>TPXbsxywP>yfn$k870+l`@h2vmQX(ZA% zz6C0$L<+|tpz=$kb9@_AuE~bbdeq??Xb&}|a~uXL2W3-eBRX;^9N(cHhU$DX)w|}F z&}KB~TY@AN=^Tff+d^Bxt*|3ZDI7<@3`gOAr*Z=s?>z8fFxF zc_~uIpibQd?h1`YO+TM%95@z~QgwWwQ5{b`4psgF+7kk$>O^n?ntdr%CxH{u@=K{Y z8JvX1UrN;};AFJ_QmRe`r{D=7rRp?L88*_Wz7HzfMoQJ`pfYcyQJrCa8d?FafSqYd zojMa{hB?bz63<_G%X`P3hwq?W$;W0?6Utfenr0P``*Yw3#@!YnWs z1uEl3FbmOWOJ%$mW)a%$=~PPst?^QD3CeD1jhBH+Dw5Xt6L1+yaA}Q~2P)&`)SsXk zm&$kr%yP8kQW<{=vjUB|RK_b|K1F*jmGLUH;U9t@z^o>?$`xaDASYHy?j)F=K>lf;aO1mHJ?*i5T zF;Gck148{#bt}>BxZE4S0Vumq1bz-DV2+~@R}$FwFek_^Ye;nx--d>0#~Yy;KNa{n zoDOouPE(&khyEH$^D}{~!w=vYRO(GbO;D&eMVbC%;Og)bs4TVSp=K!Bo1d^sKkjvS9*{y@iFkM?7nQtF}V&P86=pVW`hedi{}>j})C=)vWh@)YI?I`O>Z zem#SEihf*qV1L0pLtUPqoUp%P{xY8j-YL&v{zi>nkX*4BFwf1Gfp^MFm=~CN7bcC& zunM7AH!XRmm@o#K_oAeiSuiGA_+q4**)SH9t%{R*=D^r!=ZjOhmV8t^&_!imf+}Rm zO(hHrp~07%N|;ree6?^e426C=+*EupoC#X;x`_aN6#eqLi3B4^c9hpmGB6Sc0J+>G zx0C{woH`j^0m=r8f=P~tfE;g9z(nCKAjg}OFe&gHkmF4%n3Q-C$nhpMOe#DIVnZ?b z6U5L?YsKMvlNKfoo(A!uIQ$IaXs5TbhvM-$h^L*w$`Q(r?m0W{XiJVa(J&d%O(%vD z&`BrI&Sd2bC8D2Bq@CHa$ydt^lL_Uu6SC1;+qAP!J4md;nY6lA}~%m_lT% z%2BEaOkuS7a+E3xQ-m~DWq=ifDT<0;zEZ_uilOd*LRG?&yHrU~nXb>gr(P*gX|M8_ zDh-yxD?lDoWx&#;!^&f-EU47j7v6KP99R~&0Xa>T2g~6?V1!2RkJR77rg4$ zCEUQOQ&+=F;WBPuHDIcfqpyb4yx^&c!Je~sf)5(o?!K1>Y@0)jVD+GnEEKeZ&Nk2e)Dd7jX)&?%O9*U zsN~?g-W~5XP>I5F25SN;Y51^r&ua=Qf%phcZq2}^sMNp3$*s9{6c4xN)Xm5+mWNvl znC58SkKy6g5~c-O_~UrEwSs9$3i1i>xYrt{6{`8~ac^q_(;7|vN$-2FEleA<_NTm) zUOSk!R(nhCZS7&&q0K)-T382|_GtEhz{9O0Oa~PG@^I?})6wc|{e*{GXP8d-04SNP z3ruJH0e{flc`D^?>P)3&AF;p4Mhu_Ggx@iza$EE`0rA`k|QKgA3mPnEoiK_u|6$Cd>eI*8A|{8wm3z`s@98@eP6* zh&uZKUVMXL2BF$Mh!@{mFoRKZAMy@*Ltx%Q>-`O0d~d@HK?A-FFTSBLO8b^~;xJGt z;POs<2ONf?d^y#-)(RXH-vi$zM_fLN!@>8^p|8Y8afG!B2gMQ8!_lp;#zAo;%n0=C ztEom=@=+WOjzaS;AH^}?XteNO;G;Me9D`DR4L*wFz_BRk*W#l%9vp|VejPrF6TtDP z@4v)HaUwXunrMB6kK!ay3F}|uqc|B<^7?vw6sK4l@KKyXJsH*ibbJ)2!YHYI21!)Y zKqa`(#P{-ja2k#Qv+%u~4l40|HoliL!09*-%%+-Y&A|h67O2elxp-jC29+g04-d>a z)(3cC&Y_02lBXj^i>`~ZeFwbJW9#tHKyP^tC{@WY&MEyM$JJ~b@$ zd{9o93&4+2Lodb&b0N3@mGlyvFc*OfQBN<$33HM4E*_YR!9}R50|sJzE`qrFeT6==Z6P_4Aa zdSkp*;7WAjo9wNHS!1oUrg~GnbueqKFRf|bRPRfeb=Ftb``$F~E323HJ~$2bYfHYe zU&DN5t+!ssU3NXp*VYEB4~bJ7VAfk3sW*Ufnnic-ZIlL|w5rYECTp{$6ss*(e>`Tl zP;a)jQf~nVkb1QZ+-hyJ-t-1|+re$t4sbg-(0kL{3GTopV30S^+Xe2#Jz%gm$lDF> z!d2icZ?Lz=8sfbLz6HD2dfOY~?SK zp}=9V2dx(5MID4WU>&kr;s$&O<{*9utw@>r2Ided=GLT79ftV^jdL43fseo(w!XF6 zl3DdF%n{Vk%Cb5N^DT<$_Fg;hJD8*BsXKV>y<;%np|kElb=>NRKky0gI4bN;UPteH z@C178PE;qY&R!?)6nGLfcNhGDPg`BRE?^hfGgddRt9J(GGPf!WPgYg@fq#Pe5nXvzs-LZDURCcG@Ml!#)xB!oS@0Ls=yGp92cAW%Uel}L zod?gMVXx)Y^nL};qivUm^9Ar%H1Bo1+TKO*f_2fV>(%itffv!p*YoOnm%&RY=<9p+ zyer^kl=Tg~`rcKmq1OOx0DH}9SF2DS7KA^$j%sa&^81 za}(`dd;JD;8{dFJRClbxULo%;cn4R3B3@zd9(WhGfudd! z?|1MXE(FEMg}M*^j#|06SIm0=-bck;!Yl4Q1RtPoF6ou<{s14MeJjn56tn5|tURYJU%HB&Wn^y&_Lff!oylkFfXQORW8z{$Py%^5| zO%&yEUaV(>7E1GYFV1s78wGlHFWz%O2W5H=FT3Y~E{gR8FNYTbJ(TQ;UV;|}hS0ey zYbqRMQiYx5<@9_o97TLCFUgAleU$RKy)(%J+{+%X}v69W)#ZlakkG2Wq@nQ#Y%ZU_T>wAb~oEooN3> z?m!|;0vheV$sNcElZbZvIk^K#Fgek5zaX(G7fcdb@0a8b>;Wmc9<9PirV2`7#QXiLHQm|Rm}FiaIZL63|)ML=X)i<;^^hCxe;DTumo!Q z>m)>!0!yN=zd=GoX|R-C+P+CbL>aI&O8i^oM3e=~pwquiPDDBTH*zA%QI|#0e}|li z@-XG>3ie&nA}YX?NBe(|w1|o@73@m(@1#Xkf~kmCzHu&FM$o7p3s$B(wCl*N~pmAHE-&;WSM4|j889IYt2BKX4iVU5>FoRGue?|3{{WVECL+tfr=nSDo;cRap zL+5RnAt<9alB6>f=4}+yo5;`^1~U{r^=6WE-hmm0&RR)2@4~!;{(1}5d-hh6bcTcP z*~9H^Bx09hWf_k_;l6nNVgCw0%;7C;7J4wFhO=FxbVaVXFiQcbiMk$g0fdIE~|#pEANf|+Pf zwwI86G#O?R3iqWXA5DRoY)`e9k$f~2W{N${{)GIaX)sgm_wD86AH5GV&7N+rApdAO z%=`8X`&06dX249hXWA>tKbi?M16BSiQjliB%(Q3QtI0x|4KoWZ|7T<&&9TRkf;0zy zwmsJ#PcGG5m^t=5djh#s^I+zpTJ&)|F zPhnQrE2%#Pm0h*cev{OyRp3f{l|7K`u+`uyd$m2t9q4`ruC_n32fKsZ&%w{^&+WI| z!R{B}=k^!&5E8`J*l)W-z#*_}?V;}5?pl~N_BwkQ31aJD*4kfEuLIw4hq+&YU)o>U zN)!7U{K{Sreht3ozUyuP*V`NH;be+!1UJ|l?Ga>(Z2~uYKi_}$#D?p|<@z1QyUc60aHJ>2eKci8=Q zPq&A=A7-C@!0zStbPvGn#{r^Iy#?zeVd_YLq3_Xw)tzEnr;er{j)JMbu);{Ig7eP<7F`@6@$?@%1qa|gJ`!DIGu zyS`h`Jpmp^q1?c&?|u)SK)KwIJie3Q_vo4%xeeV@;7Rn(jon7>Y48*}=-1rF?iuhj zD(NO<^Zfv#l(w6?P23;BA5c{{bDO$9+0Du3`-%ET`)9j_+uZ#b<|owIEy?El1?Fe8 z+sfuU3-b$_ZYA`cgE@=VyN%o0Jr8pZC3qXE3*fI{ThjV2+U?x7V0*V6*w(#ZU$RTP z?cGZ-7tx!Srn+pGaZ9^b?6Phdu#9`zzDj)sEa#SWuYp(XYqs(euiF*e@?d$`8`Rgq zif#q>CV0cXX;*S9y0^fa_AR@zTgkl*-m-7oRou$%Z{Th8^;O*}?j5_DTNSJdd)Kb+ zR&(#d+(E6c6vcZmcTw@zbZfZ3!`wrkTZ4^aEo zb?dl)z&u0?oRciYM=*b&5l(V*x{qNVp&icUCb@sYJVsfZ+s)-Zf%y}~aUM6f`xNF0 zdgQ!r9`_l{Q*_Gt+`R5zFwami=XdkDf5ZHRy19Ux-+d1AxBY_pIatsw;JyT3*e~ru zZb8>@3cH2CLa-*afu35~mlkNEvo7iuac!rVTNEq`>o~>TVy**YJFY|0rR%~tD7Z_y zCAbJIK|AD>a!c~lcS+h|s3%G>QKS^@aOyBHotqYcb~>iW`=~9_A!A8TJHpA}rgtO3 z2-M}#ZU#3Q7>V{gqZ{oe2a};m&*Wxwqrl{7)ia~)NC8HnWY2=~BPEyuoqJZ4AgREV z=-;!U5J?TDLKh!{awH9y8r6I(ijuTW97>b4)M=b_PP`lErh`fAq<6BrXkTE`p@Gfe zW_L5dq(>*4;O20nVKShfO>`67j4;vYYAu({QkabBZ7r(Id^xh*EMR8TxQ=VPS-~u* zblE&^HZUvdUC(vh7%-a?2k5dNQWZwm@(|VbA5=xqyZnKg`w>-9bTE%lc|WEqhCb#o z>hC|PildwP6IJ*VsuJjFo}dvh_%~Mq5&!|eFzj=nb{4c7~=yLu-buN8Q8J5y$ z(w|e6b)?=Y=e%THj-@Ob_Lo%U9Rqbw1;=y^w*qx}H1B6=Rb;8)R6?P37CZ}E8U5Bd z@Eq+b&abqpuvA7UQWXvUC0f;4s-exlOsfV+M|=hgrX+%51H?S|A1z~5LmLih6< z_#5rU)Qv!CfnGyv^$mEJ_G?sk(H9?qYr^sxy5l2M&CqEb0gupbj+X0N@LSp~(0CmM zkJ4_5_Uk+FJKC+#gdGEq(QfUWpw*hC6)NfPX|-W#je7bdt+p&}&{j)t){dnun(NcF z+OxDnk$r|%2bT6Iwa-v>MALQ#1-G9 zgQ9dBxQ+H3C{4G6+iCYjfw}|SLAxLN)Sci?+Wno~wEDC3Ll3)$)&Q3NsAc!kdXr@U zD%yRt2C}?~x^_RUK`aB&-X5Sem}L-}+=H~EWsg6U*x&~ZBdpz|xa2@Lj;CS#$))T=A z;8(0CffK>6Sx*Khf$LdMM)$einF3A*KV&@>oC1EtdK${nkHC*;zmKAHJ~&@GaAyIn z=`8P~LtjX1E^5?;;9}NuQLHWo=dqr_W7EO8tY?BVP@~VKnhnlEw?3CDCMFyDuB<51 zl*}E25-c;Q)bJRVY-rk~R*U2@GQ3$*fy()gWJv=`xke&6YBJKv`Rh3TE*8whT6x_O zppv|8gUPv|i8{|iUl#_3@t6Z|gKh%jI>` zfF7^ovPAN_`Y+t-XC2~o^}ig}{P;(klRwqJKS%t(p2Ka^e>_LeeDzm))TP$@)@ysL zV`BbqUPJ1_SFhsoH=*D!_5WVIL%l!izn<~xUHtd|qfein&!|tX?UA1Cs?VP(*y8Gq z)bxpZA`4t*`b&LD5cZ=@r{P_ww@?YfrXd?w|F={yK1$Jw zLF1xQ8E}cQo_ZechjdR%Tfl#oZd+Z9*;xymIbz4Fgm5Bi$`0h5mP?+?B(Ih zp}f=fmFmtw4VQ_>Dg@(FnmiLtoJMLzmI`S1)Th$zndsx9VJijOws7#-r0ui#OojO@ zm4oeHnMW(31S||&1*S5et5EQ%r4Lj;RY60S4)o9tYFkJ{s2;3}o-QqjsuV87;;}u_ z!lq%V&eq8f8-_wLf6$lJ+2VO=g|mdw$JNnEs;8^d2hue9EP27aJR>EKJ=-s4X1eO9zu@B{j(Gf6rFak@m4{02hWR&HB3u6fdBd`Qm zf_+HiFb|j~7>C8!S5msbBy{chTc%WsMpkA>PPigEIp%s zQLnw~uQ>Wfy{Z1HNPnoOUiF%e8x{W1Yi7_>>M!#@`b&LNj$ZlqUW$S4< ziF!&$?J_~HIYEDwp{M@W{iS}=5hE9KlPV-OUG;V zi~3GSkN;J#>A0c(`tQB-&mL6Y{i~;n1btHoRL>@(ZwmaQ@6>CB{-f8lPpQAuJL(Cc z_A>R6dLvuVU+PcoU$H^2Ri#hVlj@r+LEpUUuWIy+deWe`s|CIx+yKIo?;`pc!#o|P`xi%QWOIs)rl|Ej;z(rY?*sh_leg{V@q2ffO<{O#X#+K+Jm$oY0pbRPZSCEHSKXlc}8T=pOHMH zK+s<)=p*%^_Oe%dQxrX=-qT*DUennuXV4=#>7#7a>aUzZzvN__$5CtBCk9(DG1#_= z^Z|YWL2o4neX1>&m93S?R!s`}Bq`YbNx}9`;uW-I?O=>+8z!(d(*^yI9!%sfwIy|= zN`TK!D=FB9+1Yvtu-b0f*(wRNwUu->OrV{L-c1O$Qg%Llj$r%vJgRfwtF4ip&#&#-#IFA_F8TpXCdT1Tlk zK4S#DuEVr7b==B9D~W9pPW9@jrQ<;kw!4m9HmEa+j$}IC=V1Hipsiy}4p8k%yppbb zDzdIjWr3AgR|)>I3N4F0SLYoaX>ImXooRG*b=d!^QCAOMuSW16YS8lV1kk&viBCX? zcdvJsKr4)`kU*Wt;`531X>=~rr+M{>bv3GUn66;7eRMob#vY@qlRUw;(h)B?dxN%g z-e9ZiSQo{9px)8(E+yk$eWdeEDn`7nr3wc9rK449#=3e<=an>!di8tZpxReVX=y6>g#0BRfq0Ux0SPL}@5`+HImel^F{>mBjl(wW9 zY(1OprT)ql^pv(Cz9+O?wp8u_)&JUVLXC^OL4RrM=^9l1rLBkWNzhZ;hWMTY{Z%mN zDQ!vIPZ*`if-Q-^Nzh-~hRK3$n4ImUv0XIiDQ(H*!8T06_R_vmJm@cN$rQmhOvTny zuayjXO4~41unqNnLH(s|n1-#U{?b)XTDF?@R&B|2Y%lefwq$ya{^~Dn!whUS^_R}- zx~^A$Riu@X@vZ*Sn9s!c)_z(!=qZi-%#3nfYiP6!)n8SEp3<0)VZ^JaH1cB^-_--u zeyY(feAQny|BwCks;9JPYP91}^N;>|)l=HP)L(eh{6~Mi>M8YFzW?ekeV6$6{!&l9 z>a~CN*Q=h={`If^!mZ{XJ*B-&ee=&Vx_T;#UeW%gF(36`{q?G+w3n%GUR@Waq`!0y zD;4ybt}Ijkf9tPTJ*E9i{gvfE`b#~f>k92(|L^@}vS(>8O9=YL4ED0bU@x*j?QiOv zS9@7f&_fQW{Y`zNy-fY5JxkxubQPd|DHQaYJZE(7Qm@HvM(1|*m)vG_K3A_52zm-H zA((=}o~8Xu{imMN{-yI)5vsyL4;2aaqF23EG}yCV?PbM+o=O??ka|sfoq9-aGiice z({+jZu4J%B$!$hgFxt!HHlwq%_Odd;zLY-L%gP4(QU*}hQQFta1$$KaU|;&@cWU)b zCiW#=$!TA!81zu3V2{cIYJbz7rSDw24pdL++p(@ast0|h{VIk%N_(32tJq-AlG}`~ zMsy^s3F-{kG}wolu+E7CjE;iMV48wD^1TL^24|| zVB~1uH0V2Bxs_rmjn9n7-**VcTXCL|pWZIUx+G($5Lk%km7vxht1H72ECs>hv^w%v z9YBrJPQm!>MBUNo9E{J-Fr9+Y*%^1*4#DfN}`Rf@6@rCCE8QPC^<-wZKgDdM&UP z?UcMmOR!}y7Bw<5vgo@(N|;ojj{X`w(JUDm<@yextHlb8T8*|0EY-p4JVX0KMNr>A z(y-{ao~k^iJ*0B5R|xfOM!)Rn_noRdqbnmU7uz6-staQ;iBH)TrW;Fcwo^{n&WydB zY=v$xd06LWTPDJGV(cZdCA!0Qr0xXjI<_8M9#F@Q4lo@-UAyYs-+>;E2TL%zoS^UQ zU_4l$&L+iJw2$iyqJDOQQBo|}!g)dcnpBF%Jg_9|I<$*`by=5&4T1XAK-;|tsBd}g z7<2JpJpa2|FrKRgV_N-En4Zv?L}%m>sH?u}j3*N`dA5415U8uI8u03knnA5=iW*b} z81-fNtFkQN>>s)^)Ls%!AL{y0=W+d3P@Y=nab0m#2(TjSw!F7?pw7QKo9k>=35)`D zPSg23ivFt1SgAsl64celtKSS_`O7wpzqX9K7^-Y6tr>UO0@PmJl2$9mT~;bxB?wz` zWJtxBuL@S>wR9!X0&KxCqyfCnjSawzw3~sMSf}BL(Ex0~W4a<~1~%o$6iwBXG1iF3 z({lW21UBS(x`JuK7;8*hS2j(+#1s~3{9M6o5* zr^#6K+r9cdk|i12QsXBg7$*_%`qfwC$7j(m^%j-MYw4&aUY{Z}n3>TP9UNC)T?c1i z#Ob+v+KUtOnb%N1aY>e^G+ z8TsieU6ZQE^6_bO#UI7;&u;?yPLP{VlRQ8j*EKqXI`Y5zMxpOZ|NN%m2WJ6&^LX_Q zro z+PM4$<3ghb_rG9VXba;CNIO?BcK-EUI~OBBTUWnuCovYZT@!<`qhG}J{XK$qj$rHJ zNk}_;u#NF5435Lv#&{UQ#sym!Z$sL#!FG)ewsb6f9R2FTW(&5l?taA3d)mf$C&Fe4 zwr&;}vH#kaHR@j76^r6;bhcD~Me#Q}uR64ofi7#kRwS>Y^RRjD5bGr1<%k}O%ps**I^nvdIeo?X-w&NRb8WN-06Sm>Rd-F zy)#|?=vb!rrfYPKU%hi}Q;lMMB5hgSPt#UVe`I0nXgjD^qS!*}i>y2&GpMbhZT9M} zr{1OROw2Je8naDZRqB|o-xzg7Z^XHwA?vw3ItM?8*{tWW%r$k@r{jJGo;MRF8l1&i z*Int28TdfxT#E;Zc*$lp^@e$02_!Uft>C3Zp zB@-v9W8?Y~reGEU}Yyscgkmo@({(*16x8&Vq05fp*TflQZHsy{G zjniNs9&N>=Escfn3vf}0roEQOqwyqsokthJFT`nKt=Y<0!_pex!rt(U;TPe?u*Pg{ ze8JKNZ^K^jI_fRPJ0dgK11_B*&xSUjd>G~BAe0Z|W>d$;E#PK+fpVE?jod7`a9!BU zU+1Lew>ut5Yi#8?Tg*h9gwhy!g6D06*@{=gCZ4&0b!H%ZA5_!&c9^Hm(P+Hg> z)Z6iS*uZmg@HodLQ%BMKJem&&hAhSoyam?tXbm$5j~3w3{5T8s;GOT{(VaNz)PVni zXDq>y;78U4OlE(`N$ zA>0p^;hk}cWjT17RuNOz>P2`?VSEx!!Dr?F?*@0{0g=_%gZo2PV=ulBS&e--KIlxd z%RInZo)1}#1149_W<{_f{z0jYN@iuSGM+)HjVibWr8cVaUQ-*@c(;dm{z06GD$v$B z?2ws_Au=x1E$VcOSUhlBU(T@L~(lB{v-19X}GZNRR(qL)+B9bKn zU!53UCEm==Gp6x(M{t#q`^Geuqh>OmABo>ijPaHk$Fouza-BJf>rRX@#EgYYX%yn! z>RaP6^SD{aIF9>9l2HurswAU0u2uTZQw(RG7=ypzFH#!WSf?}!8}jlfY{%Gx=h_lrDc(U5{^wEfD9YAvlK=&US=tbjJTMkFf!p^hNCjh zWw0UL z(o6-W!hcQQaZ;MPE*uGt#8)WJ7=@!yl#$-d0A}Dn)rA|4=T$w{m*AtoD4YT7@Vqg& zW7TDS*+_>++hrcTWYp(*^~?)ABg&}FGsfbkRfly0`1N|K3oU2NJx<}TGN1K|r;cpq;%^qe+&aE%` zU&(O+d=5Ux^)ETgOS}!M;dR)}?9Ow#vEZJ}bCMffP2H*MYIb8SAHn2C7qhEb+K|7X z&eKl=l#gLDmWQCc3zM-t0_9hjjO9;I9)-zRo^lTV-MA0lr@aFw#k=5Lyg0Xk_rUF} zck+(zfOmLoC*KXLfz{x)^7uVaj*44ZBJt;}%41t-MH;)QcY*pI&UlEoV>@gs{jTH!<%Z?rbsfNk&~i#OWhKE`)+vpv|}>;QH!JA!e%#$H}+ zkFhuS?cyx|AriOG%CzNY85w-@$!_e2*@y4tFEEK**XmB6u6lLvucMihr4yJ)OYWGu z#yN%CW(3O_P~MsmEI)$s(~Mw=#HI5T)%UC;@C4S~*FoSwJZAM9%ZDr<;2S&;ez2jt zuY*|z;Y_RFUgojv2S1?o5zqe+_u6?db6F1HMq3efKHvW<8uA`42kNfxTfEL-Q1@(o zyhx9LNAMo?S&o87@f-D7j)BK;8ueLDfG2pDK1&3CxpR5_IV=b9xvjwe=+A4HH-;FU z%`WB;UimHRE{vrGuob`xJWoEm2f>5JAv}}I!^$bSJf6m#%+BW9{Ou6jac99UWLbdw z>ujF6iRBx-jyv&;nLM%xoW*)EF26IunJ{wvT?{V9KR29b9|jNeUc>q8Z@{l`o(*SN z53V;hfE)0c4QJVeSM66+VXTF#@xTpZ`5gQl-`g;jHQ*Y&Zo^pCf$Mm#!8;lTb~1;8 zIa%u$29v92UA^jxS~Glx;lk{)ybHdI^Rmk_92}0@vdc0O9EroS%Q6}qjjOWDG8P<* zpR(o;4Fet4A>4mI0YAa*H^j06T!F)Hh-D?X5?9|4%W7~n@6zM>x@w=!Ht~3^@!)v8 zm_3$>;6(hFJ(kJfWIUI3wLcD=g6FcwG7X%D!?MRR9bAGFvB$E^h>6j+1%3a}w}V%+ z?erZcn)9u`U%Z-Or*Au%I3E4;8+;m$2>RZhjK9bLMzPkMN!{tyZ%O*blq~o*s2O${ z_-mhb1~7uP!6Wft3~PN?(hNKO&Z2pC8Tp+0)k)t6{|9^L9beaV-1+zJ1MwaKf)xa- z$Oi)KT@;&GBvBHJda)5h1S_RS29M?=*)5K zk(r-8+BlOEN47%kE3sfJb#fN0Mz?-OWIAWof+An3 zK{MLIm_j9xF@|!R9&CNxWvCV!{W1&DOiHLdloEPJ*|eLo2VJs+y`9PGvlE=Ml>H@~ zJrQiR47!Zt6F`W|q02cwo_%9d#GE@oqAQ^*IC~uXI~d*CqK++Ttvr^!;~3Rz*xO#x zcC{UZv=+LCv)kC;j@$`r=#d<2zt=9R4fSZKmQ`(Io1t1?wVZ8&YNypw?|fLU%Q;X^ zIWX_dr^SuWmEW5Aa3J23yP7#L=RK`U_U8Q5>cMaJ$O76q=Q{b(SWYb)Ils9tW)40a ztSL0w_dKzdWz7Y9zF zbip5L-q5)dIMhUps;;@|7>+xkJ11O#aR_D%zgqM7c{UlBy)BC+bnJ zDg))QxlsAp6%}G9ZObiO&5@ouw`Yv^Kz45?xmVP-#nn8)S4FOK1&`X#ey_tnuBkGb zG&HQUh>7&S8obDRJ&E6XxIbTk75t_zcoIA(FUxuD(00x_7mImbL#xW|a+)(g5rICG z9yo9+dktMYb&U7kWV{y|tqa{Y6)v%tyC~{gwXyR(zEYR?YF6TwS#S$BRmv2oGE;wE z%ue(eD~UoQDl?Uzp`(?5MkWG50R&b=2D!UhtD>r)k)I^@{JI#X6y#9Pg%WrbDNvnW!`DT@>e|&aih< zoQXQCHnzx_sI%%5D9%KkTOUtxJ{s|JMyI+G!u1eF(jAKgI0EX5mSd0r^PuxMHhOqI zbbgwNc5@Ul#an5mZf2pbrQ1RqFMuxK_-IP*;q_FAa(WM|lGpw66~XFIcAL%#(l z6?L%O=n6+UNsiNUA&-VVrJJ`Gn<)$BQ>_(BG&QYpEOKfach7*Tmt6zrstS2lZ|)pu z8%M@V#9UWW17{}A zn+BhSH(#_DS~;I-Xbz=HFUhpwMiuezptHdHJq zA8Nf-M#fyXo4@a3zl%HiqC>f;hxnF06_tc&0&@s99=9+ti&ehs7D`{5q1~jZHA?38DIO7!&I#+1;Ih<*9P-Z|U zakYcJ*{^En-0BwyO&zU_i}$1xM0ORw_XYp8NgJRecCd}EqEufr=DGE7+{ zFBpw$Twf2*ngE^6R(v}F94n%Co##xbGiPHvjRO|lyMlEJ)ODi9d(HvbiouQJCr*rF z$91S&YLd?E}E6btFId(NlIb-RD9>w-}YPb$sVS7A#M?u9gCs2n?&=qV?U~da_3v-~I z{Pt$3zB1QvZDGE&m746PMdv|JVqRrb$|_=X#7QSpjv-FyWaz1s)1arYJ)OST4plOo z&Yp4kYdA8N@+9Ic*RXdc#Wg=C@*8LK8!Mo@*q+Va2~guP{EoD-_I^Y9Joev0oTJ~6 zzJUH+1$_(WFQBv$+vuu=3n@k{o{?4-7#VaiY;&P7n636B`oGa2bW7^JS-{?_SmRt@!hE~6dy<>>-JCk!)Q?4Q& z&=t|wP|hW0(A80{Kym+Ej$C!}R$?fxg%^w5eetdK<`(K07O?_&F0 zioSS`cfX(gyEyxPs4*zdapsqK|GS{?Py2VV{bkzYPNHY-Bbw#|9NiCnnC%DHyAS$7 zTI&Ophl#SekJkDSXYPaEP1}8lwtWEl0OvkTn?3~n5a&P49$$=R?^>wQxF6x%Bhc$; z+mF&xH$iWLYo1R$^gQkMt`z-p3-oc??FCxn?NB3kUZC}!D1Drkc?vp@?Z@Grc|>OH zr!8KDXZAxcWBV&aiF^Wj9NS+(<{SrAHoe60anR$CFfUQoL)XJ!FVTj^m8@a=Nm}Ye zs8Z&Wl+DDK+(Vmv3XZx5`pIJVoogK)dl}YTEA0?D5@k+UzOlrL-Jhsb>2X_C8Jw z(2KO;%kb0F(D$-^89qA|dMYjYGUY|+)13P%ZS*YkS@`X%DJJKuwA~%-ucnp1O8Erz zDvrLE`t@tP+h^JTC`Vso@1xM?Irnwm`N~P(dIBQ9&St zgU1H0;B%#)*g%vZDmVuk2;rQB4MYWj5H3bjHc&y}gun)(f|HV`r7 z2tia32;o53pp6;^Ldda!>!n2qfep?@j$g|eHDv=EOylTauz{!`5JI4WKnQ)Yfv6x5 z!tk)cje}qVQGt<**Py#Z1%VJ6*x*L=+l_-_gL6RwH@u1sZumEBaBkB4BgY2sMv4~^ zLXHi@14V=|5H=7M1VZSG4MYWj5Jm$VG^2t*3q@=YNT7%iL2q6rO4F*F6ffp>A4XfX)uL2fY!>%m|MA+SN@GRs$ zg(5a+_!0Ch=wArCf!aU!CImLfeF|ChbQwYmIcn|_1gij%GLeZyC#0KG62pfVp zA-5Ye`xL@H5C|ds3;hwoKt6>)1>sp3%%@Pq2H{f(KSKBv^d#)4U9t=+-?w&27wBOjyEV;42&ztEeXYV10xWc@jyfx4CGU2*bR&J_yWJy z72olSFMmb!a?6`K-k=#9j8-h-o6D!r>`e&FFj&078`-BYl2}Be5F;Y7Z!BWi4IhWPc!T~3;Xv5HD8xM8AfgZ>BC$CZarkxvqY%S-kjEkp$8K=2v54VWDEbt_ZV>SX z#w89Mi#T+=fw72TJqU|I;Dqog7=KudNE|#C(I~`-NE|2@@nC%ljVQ#3OFUG&L31o( z(X%jGK81)yGzu|13w?bGc`V`$2W2-HPAp>4ZcvOxY(yO#s!u_GLGD=yTS3u!(1=LP zV-dr8kVhmMZ!mnHLPQ-D?FM3of$RoFpF$BEG)EyubmD6rix^Refe?zZh+#b_dKQXy zgNDVRIo=?!KqD5>6$Y+@`uU1QJUsCR5os{kI)%e;H+a2b5nZ7Ws}lB8@1`SjY zD;I{hPNCVSP+X_bKnMqpMQmV$q1P$&k2Hui3;8;Qk^2-578^AC6k?r1F&1&4bqWW@ z1|zo{6tO{byurb)Q#dqiV3x={>OlWO-*|(;)+rR@4I;*1<4B8CSc;tiT(5yP7hs};g}5V441A1L}1!pqRW34>#UMx;R=ix}7- ztOo~cHwcSC(VGwv2;o!Es*tZxh}8;uY8vr}`WG4qAz!D^9~I>56ap2*It3#Qnz6wz z#yW*xG;B~r1Q@L~~*c7u^% zgQ3?j4##dV@^uOgi$T6lp&1*vZqb#DIYNlli?Nb1U&9#Kpb=>hmV{Whn6F`U&BEYz zgW?*-kz<4KDGatwp%{zU9B>91b=p#v3%pA`XTP4lUjwP(gp| zLGDdBSZoleAbbkNh{W(U3>J$Rs}}vrvph?3>>pG8;segQ3v;#_Gk0Kq%%uYR+$9PJ=wZfw>L_w;K$W z-{8<<5gWM<4jgaLKfi&Q4a|9TE|KNtK+5wQj079J7P*g_;|)f`ZZP`!4TfVkh^$Ak zlCe4W(eQl=#aP6^21UC;5gQm?&^Pyy2qDjRG_b`W@*w5;j*9sWir63`4Gz|BF!D8w zMQjjj6N=a%)+r1>zd}iB5o3^NJPGUK82Cn4Tgga8s3CFzkwMM`}!1$D;XP}g@f@a zybSgZUI9n?ZOM0wF}aK{3BUBhyiyBQdanxeoHo1`UMpdiWHIsGzup zF|r;-M#SP8#=s1N`4onVKg?qkhm+r6FrUJq#T$&SPobC*u^4aASiKmTk@8gu`D%s! zYZyfZee)t7T)e?Ao=@TM*bRop28Yvb5UAkw%5N~VPvOwkFpgxM!eBX*2lFW$&UFgI z&zU^5-Qdt-5zUqy*%2dK^2qWcjy%6Xz&`AnAzaa;th)H6dK-y z$dNcueuJUy2F=(YFhgL2=A6lgmfxT`-e9nt$-{{^XkNoOnB8FLoXN%f2H{_boXN#_ zgTb(Y_~Ag#G@dm@U8#J$0Fe75_Q#e?= zLGgPEMQq@g6e1$=K;KhnjyD)ieuKv9#rU?u@Zt@cV-ZKoZV+n|iU^@OXL9pu1+5Bw z^CCw4VKHZNBRgWA7qN&Cntck5FDb;g6~bSTe@UU3>mYDKSP%NcK&XL8Y-@cQOOEPiWg`0)nK z>l6mF8@zV0h=b)tjLZfN8^Xb?Qz+UE2K(01Yqy5+(Ch}o&x<%z6yoQ|Zt(no`3;5> zi#YsmEe+qN&^O+ov4$~LD>S~lbf7hiv3fBOLIWH8yxR?$;|)g3ZZMMEM~8Er!r_TU zJe=QQEXE=p&hII_*0G4q*kG`{h(p^AM!rtrVC@FYv53vzVQgNf&>U~j{2j*8^(i#R zA`U0_QPFPDSiN|l+(*S�DyeuQ3j^hA|LAah<~O;|=)c8?D*Zv}521g^l^;=luk`zz`BCZLas9`oKVkdh z(!b~2k4oR+=qIIbv;9fwyPW?M=$~-(-O_Jy^a@vgQuH8dgk66<`EBzGu6}B&PR{AZrFSGX*=r=j?s~SHo{aWeQOW&Y( zzQMV#QeGy5gvVd!$~V$iJAYdGbGARFkG{_NmpJ+hqDWtYev*EnAwgZD@HB8r&$<7}Vj+{dAw^?R@xHpb`KuW*!+^+7p?_ETxJuYXsWhbLU#^Wb3H7FWJEt&;2TN2bue?=G>(e_d7V}7o;bqFF9Vt_f?Esyo_=w z-$uQN^M3Eq?>&3X9Eg+nM)c+EpT*u}zD{)(^lbM1w)F+vaW-WVUu8a%^Jh?|u=?RV zzHI2%ozG5Rt-K(ui}1_Vp7k5qQ&=tG*RH2>G=(qbPUWkMT6?GRHKEfJoyyTJzCm?* zN!!h|^!4IXiC;L4v%C3X+-ZEx@?^FrQFim??Gw1CldpfDkiLJpo9}yf@&$9hJwBcF zF2{4Ug)fC35AEdKCeC(2H?ut^edl*8E8KSQMd%&ev7P;`&|}zcx&R0%n^Og8I)Gx*_P2Yz18|+KDz9=0p;>uFK?q27@3RWTq-M%$5E8T%IJ{URgRR)%IV?D=6HTP5}?epLhAQ_ zelF{Mel7jN`1G5@slVDpy%Epwuj47XZt)$=+-p7BsX?(G!+Czxx%d{gjZgPkK3&}v z?QtmeR|{5B?W|+yNS_?fj2=)&+8e&x!M0C4Kc1F9zfu2am%P=Z?R=x*w|_i2ekFfS z{IySO{>9*`_+9%&jcyBwBh02Ohxi@m3V&^$<>=YwC+F=J?-KnGz3Xqr^M}*FgFQd* zWuF|sCD*njE;^X!7i*q#sXZAu$JVgcIhT#*^W)jpKls1+D><$UB* zeT#Uq+-WO0!lIR8oDZk{bJ=1$<@NMAd0Pd)M2khA_zS~-empaNC2AP&5-o1q`_#s- z1V6=iJ`ow;g+7|e_5>vKOz6y{xw_CKJK5_($IRx+@stzLRXaJqi_(c^nZuPGl;hD@ zyEvoXnud;<%a!9OJCNMFIkS*56|FRvv&SO2=OWLiq9+$|Whz=}9_Nms9E;3f#QDXP z$!Mr~oZXJppNEcE%$aTMZ!guM+tAQUIHLt=5}K^enQrJ-^!-xKEQ3x&^L2A(0dxyg z+e`=AXBl)ES9>_#3|+u>0vc>NbUD|0IlBqk!?qpmw*tC?YbDNZg!ZyE`eG$?CD+QF z-H>{ABT{8GSH@G?X!i|hM|)%gJ->!4HOhE;c75rn)W7TDueDsMQfiElqtLVV+EK`b zwVZ85m#(GnS~x$Befw-3+j@O*`n|=}W)UsmZ!DpxG3A@3lqI~Q&ss)V%6s{g<>?8_ z*;~dNwQ{^N{mM%A)$>Z;RZtOu63*JLqHd0mHHm}Pu%{obo#P{ElXhr3$Lnaf3DAjb z*Rgjb@8Fl|kD{#OeJ8QEf&Q8Voy76R)WaJ&vw_x>7dBBg(&BQ;X38ddMQ%EpvYEb< z;{xk!g(s)euX65I_O{UXGuYdnxOhAJ+u$2{`54M}xJv##mLmROPNw(Pfi(6+gB*cgLa;w&ZzNLqP>}v8N8Laa291I zzhfre9!kcW%;GKQQsz)E=aQna9%zNE3)9=~NpJ3(cC%-T*aCI-Y$;o2K6|#HE#{MK(-Tws+P1c|?QUz^1NMi# zV9(f3_KrPf|JiHyr2T4d+Qas@y*z`mEwzYrD_kMUl|Q-?-^eF&ko+WKmb2tDxl4|d z{~X^_INC(7IHv8JjfrRFV0m?78oT!2div7wYL6a83p!FA0gejCfW5Vro^#x{vF9jq zq}Zb&2^?vTCdZuPu*SBPJx6Ah?Kt)vw~kGDBF62~G>#qBEornX0qtF>QqsOxE+`F3 zlts*D)8M?tErlo&5b<_`6xmw>mk#JhlC)oSVfg$NqF) zb}e)o+pAJo{{goF}iH$ho;`#(4|#%bWC;3JszPU4K5J&)P#B#yUnB=>KF%0IU< zo4%7-^*-o+_*?EhF7dOxehl;PiQIELSNB10WqUMt%!eMwww^e-&e8nDfwx0%XSRMf z+j|oC*O|vZ$gKZ9=>3dCb!0bOyA{5?n;E=ZdN+Kpj@q2K-7&C{nf+b-#l2j2mj57s zeRs2hscS{|@57$c%C+~Uv8?6i!(40O z*FMZhewN=Hm#jUG?q}J5j%#8Ov4{BLXxc)2A_ft~h+f1g(TiI-qt;WV$_wf~d22gG z-8YXt@zgvxNn|DRIs(3#%bprAH345-b)@h&zL3yKMMCK_6 z^MUOGSt%iyL>oVUF@pdFm;=A4|hnZ3oF7f(-QPuU`u9nIckju$~E zv7OI35s(^oN*a}c<3;R?;5c>eJj#6fdkVZfm9iV|Q@$NRnFmiOImLOq;Y2m~T*?vf zjhI2qw+pUR2F{_(g||96AG47_0^)!<@ZWT}(bRohMz^P0IZ9{ICL-5usg^ma714@dL@nZ7t$v~waq#BUMp^@9v z_P>0*#f(9o&F2ixBC7D8W5RJ;h36b4TK!t#wq@)uO`~K9BSO?7o>`pueQ_EM+5;Uw(oxL5ms9&M;x zTbEi}O}{Sj$o#~8^JrCPL~B!<*Ey#Qms6E_YvH;RIPOk7Eq+`>AJ`)cIHML2e>nGA z4YhY1F=`5VS6rz?w5OCNtB?x2xaN#?7k#9xT*1~}8_%BYt48bPj*K>52(`tlT(bvj zZ0!jpq2u4)TAcdTKDC!yQeTNfm!y7GingXccK%&X&#l*6)7B$xU*6*rrQThyPoTw} zA1N7>R8x5abyquO0<9ufE3a(*iR`y=wLS6iWZvTlj_n6|a4ysyQ}WJ%+N*NnY^d5z zPMigmJCxKjq4JTOC~s9LEs2km%hNfQvodPl$=j5n8TD;V@8DZ$%kr&!pAw}7TCa!a z&MOuE`~9`W;x^RNxk0v!vy@O$WtL+{Ii>8%<&=_jE9YjWF{zwVW+|r} zi^{Cj(hRLHE5Qz5fLPKC_sE2q@dN~;(< zB}S0aY7Xtv1+{(Vq;|74XVLDqu&qCrxAEPz1WbY2CX-StO-k)%U(Tmj?KSn%eBMC0 zJU+ek_%tHM^A{62Gl6SmIH`xXaU4`rFE|Fe*q_c_Rf_fmYgDbIy6xnIb)++QRUrA%n z5vUB$HMjich{$LmWw@=k7EZFh`M4H+>`Gc_SK?t?-j=q-(*pC{R_ z-0LslV`Mp=0)q}L+ovYpnF^rQRhoisu>{Xdg4 zazi)w&4$+5%IV#VOZAshJ$$m-bEhMp%3PZc)rK2>K;Jlp0D2Wy|X+ z+noL#l5~IK#20SFm(pWAb14KTvD09nU4^?vGD;z(f|zG2WfnauN9ko2 zcPKSPh2e#-(ZlmN*UoP^v(k^#&T(5B6?&v*aXgVD_r*37Db7iq%Q^>}1^O$~zk4XI z6q5&bQ^bTyp`W3v9yyAl+)x{?qlgCOg(E3qLi>L$MKmY}tf7bo<&xDD zF`+!PiXtWyNvxz8W#yb;1w~9akGP~}E9+a*wE-Rg_QP-o_jrA1KZ z>dqFO-7hND>oIG|b)C|tID^UUGvYvTT0Wb}Z8)OG9LYf@jYg>S+dC%OwP8M9k4WZ1Kgr1cteT`^?X zyw=gSjd`!qMvWlO%xAxj{*XQL$$I)IX2Q--Lh8gUHJ=qb`il}M$8<^qC4PIkFsgjxk4;qtCwUqGy$X_HP%XNvY_Z ze+E3Ee00V!lhLFUbch33e!QYO!Wt90)<+U>+ zsZv|5DRr(ZE|fY4cFrRWZ@42aq_$()dGk27&ZFC)N3ad+)9iFjgxE$+m4Mo#UYz-u#PrX+f1i)C7H3F{!+hc>6)G-$a-k>OvYKQgwB;SdP+It>^b9DnX&VkJ}?W{G}W4b}cxqOaFNjoO*W zwu5m{N_!dHHHlxJ%>RsflsGar#&&C^m24HYVJmOu-}G{q)=ssRy;Xs#p?bMPOstks zi%j4-T2#~`6L@wT*Oe678N+g8|IMXOjFV7Ss6VFAi^}%S^n0D0ZDoHN+nHQZkE=~) zaE~5}*_?Hxd#0Nw%}6~Ly)}ax^>D@+!3^%`<(-a0=k8#1>a{qQqE=KU97EAkqDF87o&fxe+-ZjRpT2Y*`mZDa4w6CG46_o|6DQZP!#43tfQQ5JQ zqE=Lzte~hBl{L#LT1w;vy@gszg0tkSC9m?G-mb;;m#DU#vy0$`HfS5i3*m_I(D59H zAGen?#_A{~wV?IV7p?4R|7xXow1_$58b^;PbL$lCamwQP6z6(cV&+kdmQiXSL17kH zHkO2S!igJa`p%4XV8 zK2;uS&uHPS@^A)i(ZX>TM>A;CCG0tdwm_9qtrT_LV$M4jx6$KTfs`MMp^LfZDBT8C zlGP~3zzO0BqXj$D*gXb*=;b)qOXImGJc?7`?p}IU-Q}n~77p3PwaJP1CvbKLT+z;U z5@#H{>c$Sv>SvMb9pyXVpAPmXa@Dc!$OxV5C@V3V?A3$Oyz1Q0zkM~YzLe0vp>svL zxy}v!tF9H(hW=H0+9Jw%x!X3HK%2_-x&F;H??n252tiEcyl zcEWo_%^RaR^snPvo}B@wI{MYWGvQICg4{a`UR6%Wx3l5JT=UAA>fBua=9>42#DVjm zp>xH$BhkF|x}NkF-pSZWJ@|U__3ArLHd2QT>^Yj0Y8yCq+$q}}!?P*Mwhdf!v~J{m zGLF01TMwPuw(v15Y#p`L8i5xp}9j)v6^)AkY93MxkPUN@~IvsAF$ewd7 zHHY&mwUcs2wBE}2SO`_Kwlb=WkyyfB_`TXW5{)lSJijbawWz+l<UH&pSOm z_Y9uBo47HbZv2?^6#n|m^u)7x-ddvDY@f4I`<%_+o=zN_GVW|zuoXIv=blYDiDl#Ry&uy)lkvRxvAyPqkpQz$cazRWEd3ECFtJzyZET5A1n#60@@T5!Fzl5i_qU&;E{jT5{ zzeKr`h(9yYUzeV89eaC;;B$;zpT@}bJasX#ev|mi8V0%+~;!QmJDk1={;~6(ou4hG>xa*cQ5^v#nAu)jBy0O2iM|&AqM-yay^G zxF6X!6M7HNyr1K{i8MTpqX*Dh$3a~;_+XNm52hy?QFte3?&I7;{O$eF`}y04xc>pD zsN^B!?`){C7Z0buf0%3cvi~4**H}ZT+2S7I&WE64pGT1DbD?6cM>zWcd!?jJwSS3x z)Ta503T2@2&&mbmT?jj2VA z!PX9EWVT~l6l2u1^~p;0y1Jv1_VvMfR!J3C%UpL>;}!3=Zt)h*M67j7y5IVis7o7L zCAsrFSB~T{39h;kTU2>o@i*dk{5^lQ@!Q4y;oQ@j{?^|s(MJA-egxw>Y(<~1=Xl`f z4|cv0?a;Sf2D`s_-oLf&s?^8!wQXu_tEn!wgpu^t%yzQ1oRP;W8|QVdi-{V_BQ-qdulcw3r|&D?uz!r}sB+fd)ADM4e0s#d9O&YHlkzY8*SR zKq#>nHDJX+UG$1i3pEY-Po1k|XKZfabGR{6Vb-k=86nz8^cngUhBF5vEI&^p^5T0~E$ zKF{25(#`$7v{S=+Gllkaw(hL3hriRpqdhKpTu^>XI|sBPKH9k#Lkw2OGypL@3K0cCe< zda@%)2^TUt#!0@4*{8**3OSZPP5Bn1(6Q^7jM1sL-0>dIQj&*^_qx(S8c}=pn-ad9 z&gb5D|H2x0kLbeZ*_O&drLp`M+D2Kbe%3;19p&ec;c{H?V!iHj{Ka;*@g$$NWedM4duU`wq%5&-+GYo)RNU4hS6-@1l0L z26BL{hz+hDdNiKuFZjmZB}caK-{*zaa=o1IV#^xyAd>P8>>1IMwF`}?mQ+{DO(Lus zR1WE&*cO2p10&e`wq6T$vDWSd_rOtc4s>->G&!k+T?~_O;mU!am{ZKK*68u~--xKbP6;a;W)(=2Dg+!L)(u4bls%eacyc)=@p$vnj4X zGb6`r$|+FSi;3m6bEykw@)xV1dYG=l`mu@mrBeP%_NGCvVtX~`%|@aP%5SYrWnQ|0 z<7=>VY+$B)1!sPVee<1Yw=yruROXaNaeOVdjH61IaXbaOm+f_&F}I4AxJx-Z8G0Gp z>p62BRIA)2oSg){ltZ!Q*X_1eIk@Apur)liX14|~1ntnQLCU@dS;Q!V$-ua$@D z1-Y`FPCj55deX6Da3E&E+zIaxT=|FB2#s8v@@eft>Xy z_d;ta4Q)$Dfw;dBymua2(@I84{z?GkwnwcF%C`FaB+DzxcO@<}s98gHh^~U;C4t)^Y@l~xUHr^*(iN%ggqp}ytj)H0hB z54-lN&KY@XGjE(B!EBqODK)4(?pnZDr==IhRa-}Mtp~X$W;bp?4~<^9Ey#^^P_3$4 zle996Vx$- zW}GwQRtwp=${c@|Vs@=hb56eaRWga$o8RWH7U*}`nq}dIc-dD;%3&>J_X+9-9yF6|#uE#NA(pehEv}D?CAa)hlEfdx^6z^W>MH zFLC@;_FpE8Sc$#;+-1hB62}jdi|iq&`NbYidB+}3S;-zwnaLhbnaLhb8OxO5`;pcA z*($sDBc(mwm-dw1`;pT7IIGm&k7VA*v66Z}bU(lN2rEtZK}-D7b?jY>G~UPF4V>Et z-N*5b?B9^&_&DU~BOEKc$01E0;rJG)S+O2r?^fvBu+=@n-X`uE2i3y6DaqtbNj`5% zvU*dJ=bMtuS9)#2X7~tysXUV#H}SWdlZ4%zq~7Kv_0%@{J2tXCI?3XrlPo@(J2%76 z>$swZ*$B_Cg(~AW!Z&Ad_m(8Vw?gG3<+~bhJ-Yfdj<=z4PeYTRn)JCk_!zXQI$zCt zEL23GuGPyeUQqkG+WI&~s~*D+ijf2Q9*rV!6syr=ZD>c*;vGqg>)}v4=xytzoB-9Y z*Gt(6)i>@6n%#_lJ(3eC`Z^Y}HyJ7#UdW!_B3Cdj5RdJ>^;k={k?4yc~NcJ>~FKE~bcloz2dCJ9}F2VF6K8&q3%J7o`a z4}H~6(VwgTx1BNrsyq{Gb<^tIY(;YCK-JA=(Oba(_i@F1ea|6v%>4KHl>N`#g!ePf z&3X4N%7akz=viwKsv0P8v>Hgns>IUL6LUuKYuI8$*D;4vr#TOC2G*7C?@IS~@i$sj zwAShcR2FN8(avHFk8h&C&^f$Modt&(YdMpnS?on@h*p?M9M9p78dMB7hZ0zGJpAWs zHthlOpSsjYHMvwPf!d`8zls#+QNq(%P5dht&*T0&g|&9@>s09cbjF+?wyw5;X>5&p zFxEkwt;T7EPGhUy83*lT+smFdmmapgoN=yidoHAi_7-vENQhB8fpI&5BaxhA*s-z% z+6gtT#g+82da#%A?C4&`RWsKtV!IsbC~sjKD`M2xMjw=EZT+uhsQP>+d$y?-D}B1Q zs;xeUT4hi*{v7tAJtxv$6^?DyNwk*rKY~5mv+`Th-XHZqAEQMXKTmv8*ye3s^7bwOjRYUTcb$6}=1E zR~!>YK`i3D?W?p|ocP2@iioiopW3zyTH_9JkS%OWxh7m$88IB9AzN?>?Ky)sT+ZGM zq^I|}9&`pW)N3obZwZprNE4~h(u!i1-=wrikrP(D~$6N zXP{!Jn6Kuxde7$=wuoQjY@8{cFW#U3o#%@87**z)I)8T(MT>|v(O#mx+IneO(B|mh zYKiEe{>m8b>e?Z4spFi)b`4up!ye&0#ph^y@Na#N?cm?$vdX_zcKIx2M+sW2XWp)1 zm+`N>(@}BYHYvV)?E5!apT8~MQ~cfH{l)Xvz+<13+jgR_eN%hiH}W3e!`Xy?A%8e; z^Qrc&lHB{{3_Ta#?_A7#ykC2dJ>>n)BH}N7_u_lIZ(ZcP{_j<+bF@^Pi8)DFRpe8( zgEmO(V(sNz>tg+^oprH(VL^^M=Wl1ti*M(9#T#1lf$ALfEY@u}?L0lzO|L*Za>2Uk znKTx~y6MR@B1L}I%c*C_9+^UM#kDQ0cSUQW^`AsB9>uqqNRiupiw=t1ZjJO5X+`sV z)Okkwb+zFH^rLO1&te9(us+t%2pQ{R4XvB?v4+;o`dCBjW__%ob+bO!(7O3s+BU3_ zz9D_7*3DX2L+k229tUTQPtT7QXiLv;w1B@Ctq|`Xtq|`Xtq|`Xtq|`Xt?)PMC&oIRpfu=x~(GrhnLwNiF4MBFw3o|#Yk9-J&?+9%URfwo z4QZhau@6W7j&h2>WPgqH9gBSz`$NmFk<0Vu=MTi&%9h~okS!r)LbimI3E2`-CS*%U znUE^Bj|hG!-qybxmMx{fs4(UkVHLC2LPIF;)e`n^%s<=@z2^)?M35z{aPvxz1=Pve?WX1(Vt({kUUHR_Z$-nAM@7c-kwz03A)W1Ce zs%$XVh8Z_(6{V5V(D$~-^spLNAMqWX)Wvvv>(>eOxL(gW!9I-0lpGW44^g+;Hew*L zmixY$Gjm6t_vri4KV)6?@#+V1#2Itb4viMHuC{TsotzQ2OVOP3M6sA!Jdj9OI<*1B zx?KHwp&!Cq<8xwNgT8-dwwz|o#Fr6|B-XTM=5nY(ty%cCU9n)KMD(=0s@#-QLqEGV zVs-k3)toQ0@B6P#zp^_0idG8O{M-9^?kayp9BGeZnqP7ruqMq*)}$H9nl$HF z!}Zn78y0iTImVha*Kk(g%ybp~XNln=#h!WH)`S)tYrS?vA&iN;L-nibUA5n)r4|*#jAP#x zHA+U!EteYu+yS+BjGHm{hcPYA5gnb=xMw;?%7keg+e*&Ov^Z!{a8#6eo}*sjGo@{-M?YGYUo;7z}ku{L-V)Tkj z>_7P;;!pB1EcY3qVkQ&$&-fs5n)P*j#JL=Ad#pV2UA!7vGw$;!&KB>9r{q^W@;6E) zeZr0BPv?vht(0nMY=(EqcdlTHUh?guujEbN-geNY5;#hE>bQ&OC40(IXB*ge&h|n! z=v590;XF@yV@;Gu5gn%N4Y^vcyEXnOFtX?Cb!Dg0G$fVUsPWcn4du9cKuH`?0`iga zTgfdp5Fd(kmGIHawz+(zjCXC4F;zyss57wh)T2h5U;U+6|KVDY7OZO(ERvhj?{0)@ z#kFP|pn5E=-+HLNN^5=;RJ*b7unww~SRHmGR9mrij2x&j`;VL>FHYkgh+qo3BA>z~mYBYco_-c~bTfpVMA?IVT}zUY?-5(C#ogQwr*QWS=pMGG zaIaDIC$V>0lI{9!PiEh|tf#SOB)qcWbncje_5T$1&fuCc^jel<_RZFMHuS6%;jY(Jjqw)#&KUZ|Y|Sh?9jc5m+FgsUxo6Mi`q@x*%ej=dK+opd zdGz{Js3ZJ5?(W1RVqRKf-p|7?Vt!g<-t}E;{knj1E}oL}_^S&kQ}CAIrH}t+%Jopc+j0w|ybUS>F`MoL{8W)a_r~P6a)rjNl$)V9 zbHxaEJz2N#SGTcu3-lI_Z%29@2|bcK%y|1Y=-arqkNd_${gTXnj^7S7y58vZefakD zcHTj`9eO)w@8s?pbRS!D>+ZvM=-Iou^A4zf(Yx8(58cnTd$_v_y_2m`>c+0$#r8g~ z8wana)Hry*g0r4;em$oZdJkLU(~WvJF5c*Nquw{LHQrs%gZ|ZrxO*J*ezp&D_I{}G z?~ic(0q91ykFaN4yZ*UHxw{4W5ZiZf_93Xz@9$vmQ9LV~IC_ktr^PinkKuvajIT!I z@lNh&!He?_w(sJKU;lZOvyXGnV^F^c^aMJo3{?|8!LtM z>v^7}JdQs}jrtz77W4^@o=Pa_DURo}|0MT6MR@}H1a~||spFv%FFnn3o`gQd(bISY zw?OqoKh4>v=p}3JTu3`v%q^^;8b)2JO;5Y7h&g5@L*MV6`Cp0lH&I;wsK#@RWCnFL zWS--7BWLp5ud#wmy&LPu%o5uQZ<#0d$n;coTx91rx9pMB&fNXxoHf&|S!g5oT%L8# z{0EV%R;tccyGhl8d9K?P>>HC{WP&SQ^W3;bC@euPm^0T*xr^B|m#!If)ph37UCdtY zFEHb-ewpb|Jq11NbwPXCs_VMYDy}Uy8a#Xv=w}G=GMO%{q$DtZn}OK0jK)>((Q1sefyfVBkUjT5fh;>YiI$ zBG99);G6oF-k1E{XQ^jcrd`-1f2WqLt%J^i}RFiq?<6iKoav!ChK9#PZh58NI#T z=ylsX?;HQ#=Q($e*EH z(7z{US6)bs0a1=fm4B`e&a-v6{@?r(X3B|79!jO7kV#6`PKwz+T!$PP`o!|)2T?XF zfXf$Cb#Aa5?Bu^0|uP)U0N`RFcZYLuH>{O8+gP3@_(j z#MhZA%r=RfJ&uBirt6z~dMoG6Gip9b^Zi5y)8^dM=7}_in7JX%sgmcNGP`8tKku7+ zx{)c>tkY&HvQ?+R17$KTXT-7~T?rGP7_s>9WPYjlOI;3k+uDMA*HQv3gD9D|=rg zsBc1jtfme`5m>Qa5B;iNpdo?P1yz0(&${eU#)+~HRi0Sz?K5PapXzZNhH4w9PH%FBD z&F4YqaqL@nL%V6)GDSOd##Xd&1a&MWY9@3?f-NF`Y2%sVHj%LS+vn@sa1~MDGwUFZ zvL$U7{SrRe_7W!tLWx*7HK6V7o#DxfR(3Q7R<|~}zMH{b-@mYCu8Xq{x!2h`>F;*+ zqIEP=Mzru0YSlMCw)RZD$|YKM3U_+9`8CX~5vw1y`r41Sd|+eozdac}YCYu;>tJ0) zhVp>=InFq?<*l%vYE`vwjcsu4la^NdCFenruaO_tTK}7IdVGDLwxga!zZT#(1LPE?qtqU=y^YZg zf1&np$EZAGKSVT)JmXqT`$DOyx5HLbYP!-y%f6ACep}7ij9(2<>x*iYozof9`b+Y4 zvwmGbIcny2d&QVT{Ybu}QHbV*GagZyI*!q5o96L{a^(>mM?7cvF=Hgj#UfK%P8k={ zF6Jb`)sCu=Wg+`Qeg)541N&Z^i1SLhBV?=3E7R72O5?ozDZfT1EIo+f zU+m$$=qIwa`}F{`dMu=!j6>HOxRByZ&emMSo?p%E62f22|29T|lFNF8ObUBONFv|BUvNwr8|Fwd zve$arzpkrR>c|0RXq3+#udaUgT^-qGTa^3dB=afid6Tcqq^KoJo-;~I`KIOxoz*}A z+9%{?{kzIDWxZLR)FOIAjgg2*D1G&Q%OplctjTReZ&^=c09=8qAJRww{eF@4BVUcH z9W8u=YH;PCdOX)+T49vy{*_SGJua^@wSYI9uhmzY=i^T0Wv@&B{%Q1h%WKUW3}+_J+9z><4?P z6>9(3drD9H%^tO1B`|yz7hC3*U&Rvt@icqgiYj-%dTFW!AS-lh`u8 zmn$=E8Ea*(fXF%Kp8eSPT8$Ab@}&7Y?NfQujAL?+_(KV5pURWQAIRJCq;glzQ6ejk z$71Avi1=vjlMz`Lawz1O^|QVq z{c;^ylvzdID4sXIMt$rrM(mvJ5Gc^Muw_IIKHZjy*dNvW_ZS57e#!ML7 z5jaNP5?z}8Lv*7y6z`e=q$~YOXv2uEbxt7{`71HUFx!W#O~f*@`3+Z_xDv&0ySUoK z?R!hzuC!3vhN}os~dFyZU_Pkgf0Yb8ElP zS8gc@eZEr7xs;r5)P`0c9bjGlucq1<&o{_D0f6V zA{-wvo5|yHty59%6?tC0tt1RR97rL~#hL`)&IlUgX^et0g2s3nv%Z<{qpWiD`?kK9@+|Uo*)DRUl3AIo z6tw-6zP6IBYg@{VwyvYecD5gszV<*!Tcw+4BR*Cxl4nE^a#EmvaYb;B2trQk%Q^Cr zxWf09i^LUjj$D+_f8`=^g{@HJ9NSY|5xpe8$V)Lxwv~)W9U4p6+Bu@IwIj2KqtU*w zRmBpHRY$E{tZa%nDo3^)X)E{^wuNJ7Bzh+_j&C7<`g`(5h>5j_-V zAEFIM{Nb5{9E>hj|Mu6&1MA|xT3E@bZXR40hXqyy-dOdZL{(lz4y$~W|vgEuQ>$bFM-_FCGjXN)o@2NUd zw>{Nv&ft~UN=0Y(wzAsI8NU)-si-AD4W)L|LZF6HyJLJ~P^cFaKcZ4WW z9XWZ-i>Q4xs5C?`kZ7F5nmoFGprnQ1TeX zWc~^zkJfdwTPS(VZDD>4y`BwEsb6YQ=GgBIkE@bLKdhbr{Q-_R^F=6m^cze{vTG9i zqAq3EWQuxL*%fQs^cIP}T~Fd{QeUI?n$eI;dCv}vdq;QvC1)PU?&oY<2_S}YJ~mo* znBnk7%-+;=!<9MeL2K&_(S7?RW{YtqJXlg~eYtmB*`lUZTPaUOesYfT#JOLr!F10) z*8i?mL(Y^}IxVjzmS^Te)x`ZZ?-8`V`nbR5 zokK0v$Ne?07Bcnm!RTLQNa$es$Ca@C$9u^CzIMVx>+8NA;l@lyKF|Ha;Sny*ag=p^ zXFAHd+%Fs+VUa}h9B1(Pz6c?o={tut_C<-W^;=t@Bgz@KehAUBvse8SqGb`aehcT+ zYCR)e^b=_V*W01DQ4Og7BfO1rTX-Kwf3BVL^JvcBM-TVf&f!UyyYl&Xu0z$PeQl?? zb-idoRYnzcXpZg%x3Tx-;eq*iIQnZi_lOb14PpbagLp#BAf^y!h$YnJW~$MaW<-?o zUGJjUM7$y<5wnP6#42JL@r@Wpe4{_n*`cvE$_TxSVj^*pSV*iSei9>zpNLc8SacSpWQKv``Bsd8!o`#njcE3?GiJ!$0YffAu9&0OWJ7g3z%DsR0}$}#QReZ5iknm#F| znLVXXN@->fsp|&vLyaDf4Lr9Rz2`T0xQNqo9v1%(6mybuvMpwt4AC9f2IYw)= zY=8|tQl__aEHoT>(pMHKHGM*GTEk}+5f($+4T=^6akc(&`AUtie_XAt#y8eO?y|)i z7K27yf#W^w2FfKp3t`uKZQClhMQiOjP~6c-e9E>)|L7xUTee0XcNEb^`VXT8Mke!> zlZ}Xx95WYX{%GmkL-kEZq@fzvTIm}L8I|*5ZYPvGBaS^HBJ_fZk0K9{s8sYQHWssr z8^y-zCgT=FN#b2wK#Q1j2d!d8OjrZ|HDsgGF4jnB#qin20vdm!uiIG2hF`nr(YB8M zo^eS1{n|ym@kX0J9*i!qm5O%PgTbr%eFu+`9vE*Q%<~Tg59j>vNXfm5O4LAngU4X! z94qfctnBDu*CHPl$3k&GVy5J0qom|UIXPA}#oCWRCt81%oN9Mhm#7!?#&A`;pZq{k`+*M=e*Q>z9wYq|w02Pi=!n3Oh&A!t6Ke zoE7N@F|ycks)bn#f&HjvG!j`ou7%kMW$URQ#K>i(s_$Y%vps43wM?kpw7I$F$Nm*3 z7#VH&=`~ zD37(JIFnF9YfEt^p^ng&;!Hw~pcN&)!I*y=Apa_W@8x^j7QV0TVH?>Fwv%mV``CWA zsqJRF+SazG?QQGZ&e}~}7i#-=r}}quq@?TS4PrG%Q4W~3a47qU_+hl>Wrz2-hW2?K ztgR!Wa*Q03i?oS~eulTcCRWxci<;L#gojm3Ca;Q0wegDB#BPoCjY=V9oxP>y#HVRL zaXzbL(|+QtR>`LQq-Z&DR$H{0DB1d3P6o1>gkETjkOSF0iu1v~Iz_(CbI7V;w0bB# z)i83O(RU)Sz7cVbK1Y#pO=8vq>Fe-g=9;<@#cF%{1f`AIL@lAT$x%TbJ8_`rA1u%G zfBx{~q_VNUw6x~R#=g>038~CfS}GxxD@scxr1B=DrE*f)*jHLAA(dN7OC_Z8Ob!g` zsAocX=SsTJamoSfZ_jB<5fdxnN7^Q%HI4!UTjzX^8T)->3FN4-Z75;IAKs}*nP7i8Ir#HOC+0lI*w#Q?eW>fv4u%hvz4>}c zv3l@O%r-|-pU^CU`9qfaWM`>LNU!>I_5PvabNRn7SNjVh3@z8%_Xe^7#;?Y2`rBe6 zYa<^Nu|%<+1NrpBTP+tIT8!@Dw2QvheEWLD9^_tWMOe`7swV(z=ND9qFR|m_bz%+K-u4me9UFQ{PRrZ)Oq0L2eJM=8RzAybyVeoY8T4q}-v!sP~OdKX8oPaAMT8ef5u2 z*J2Pc>dyEg&eGoTdn%)A59vR*9ql#3&O`=^QID(?1FsPt3HFXr5E#D5S4B+QcP=Rx z$vGjd{LB7pVTQw#MH|az_{@xWz2wC6yU%9IGfUnUwE2RROYdlM>KT)1cD*er_nsN| z%(k~3bYMQd`5Yg^zTY5_>yCx`RRXQA$3e}5s)b<()C{OvU;Va#xkR-vm?O~qfaU`< zYoOoH)wZxRSryDCcp|w4vjAmk7L+_ZW(ahXy8SiFrG-J29yw|>(<#8Q)%Z!iC&CLh7j(m{jfm~1T znj2EfzxgBmHnJlr&mnFO$%UNpd)Z_C_U7!j!R3X>uYX1xamK(lTywoT3ihz=g7^18 z_i#LeF|ixEn`1}NF6b_fXEBESKF3auXR{yU?nFl739pXF6Bwc9<8+)J&&V|&r{i}A zBiekNj_czX>*nKh)SHXbQC?3Hpc|@`Fci!R@7P_Q#;w^+9joHA6_gmO=0J7q_8qasvFhkG zt7>tqns3z+oR8SXSdAR5`G|Ft#<x9Z2mPS569-qWAkP0l4J643?Gi+!!i5enEi0f z-mAZC%swB!w6Xc}*nD|xzC4Bx$K>IdJRI{ckNKC!;sGL_YD^xE$-^;uI3^FrnO}NJ23>5Lz@yOkUsCq#)R9rtJfhaZjH2cdHP@&a zMa?5>EzBrt9#LyyMp1JpnrqaIqJEpgT9{GPZ&sLVG|z%(EsDQ;ICCBqb8whXJ92Et zDtzC<{Mz|@O-XO+d%1=?z7!GPVvR2mnG?h>6q&uxoM^VKD?)vr=(p%e^PQNPC)U|} zr~8Meovm5EzW?yHvppQGeK_B@*v_NZzr~*Qt?XYj1vmQFz5IP$MJ?Bu6R(l4&CHVi zof#lo(qEfr*D+yUh4@CVQeAOrTIlg{mE*rld;`iSDLbLB6R|hATO5dwoT>5_HdzFhy z7ni;Z{a)p}l?zK3m3~n9K39G~xuo>N$`2~iOG=lPzQfh;R=!iYpmbsBH!44@TnfFk zbQ$!r(%#ayIscu?w=3tDE+~Dx@*9=CrB~ShcIB1Id8PA9FIGOznQyWGO66B7FS7ql z_PJ#oCu@U#xtQGhbl;iEI{2et3l zJ_7w{%)u_3zZ~t9-lm3iMvK_g7x2{RZ?twhvT(qxPH7 z->m%>^nQ*mFa3p~{bHzXyGg?ZcIaD!*5Igz~%4huQuu?|pgc zn$q7w@2@^m`Q6(6)kiCjR351QZtZt!4^;1Gdmm@+uijUEN9EDVgVhJBzf*gV^4qn0 zIdfn2-s)qOcU11F{&wx()$XZ2$o8D-GnJ<+dpLh@bx-x3mB%V?slK=J4D^}GIn}pT zpRPPrd296?wr5wLt-KfdUap;6eX8=F%DG&Bs&ZEKeU)dS&vNbb>U%0rR!-;odnzaK zv^~|6s_&}2vvOwjxyt*X@8iDHs!vwlT{(?=pRAlweShUS=yO~N>`WuhW5Co^gnA?m#%{T4cot{{m@ipUV$vR zAUmHk=Tgqg)^X;jY(us_YcKs}?Z0vVTQeohThkpEW*4yC$o2Npk=(g1JBO=p%`W0> zt#na#A=^#aMy{^q>XF%7xOz^und@Zb%{Fm<4d>TpM{}-LI-9F+$+|d;G|Q&5UCq@s z*;$-FJKMrteD{d!WR#ba8htFoEd4E}y5<;-kb zwl%AkR%Cxw`^(x2?pc}5;>wxOGqW?Y?OZ1h9ebx|vpIK0Hix~_ptISY%J#HuF7(vw z6t<^kM?g=>=CPHYlAWBLSN-M6`zz5l9e{^AbGo!S2?|4VrpbZNE(x-46oUBbQNO8dFzj%^Sb)m+fG?kG=ibzn1?u_xvkmadtcB_hpyy*JMEE{Ieq452^-pU*sohrn_q9KTzMbvu)t}V<1bQ3Webqmy{TO;X z+x^vj)gRaHsP0en$F)DMwbw4M?ya^#+iPvLE2@`QAFVxCJHI-CD|?}PtCv;Z$MJKu z@wF?fS5(JyPg|{{c3Jh(YDaAX+h@7@zFMtzRrShhjeEw|CUX7K>crYb)eE5)S1*EI zQoR^@Y4wuod%6GFT9x~2wdv(~aO3pyN!cFg$=OL+CugRYJInLo)Xs7}o1Z8B<(90H{X_W= zYc0^fXZtiyd#3iW>}u})80CfRMeeSYUd%qu_8-fYEX)3}{10sZuKdTfKdSv5&-wfE z^Vv20#q*SpWxv8-R7yYN>fe=rR=%V9$F-l8@2uWY{ikx4m9u{;|0CNO<*xEB=uUcd z275cRsnl~?d1|>QTflyA){}iS`z4Ydf6 zsO{6Wk7WO!q_YmVqIw$e+1(R+&ZWD%ySqCC=@gXi4wXq)U`26Li@REB~{S;mwzc=jb_kmS; zEhhAyd(XUt-cznLA(DvkGmfVF-H10Gnc*KL)@$!5@!oiUdc92_^QYIx^o4!RU^v*^ z=EA<@+`bsj*+=+aGMeUhC&n~nx_`^-Y&w}+UMJHV_GZm7;=T61@<-r#li6F|O|OgT zY#xhVeoz0g=Gyz-(eb@k#EZ`ryn-)@8_zq=HO2EzpyOeW509ar zitapyr(&u<1y1v)!Y9}&aL>ODD}*gfb5kK~XMOWY_qot{c9v4SN!$-<=J;9yV?F-e#hCJmE>1A`96Koe@H zSvip3=p9TYVt*Z0LdJ$eg2Z7WI2b*EcR*8u0r(7rQ_z+18XHzd#)Qp-L}5ZW1pQ1r z6;u3YVzU1OoZ?UR<8lY$d2zjy=(ye~bQRW&4y&+wOz4R*{%GG5WBoDkYkw>p=YI`H zbGKUr3Bv?oi=a8WDr-i;D(IF$f-nVafgT)oG`-9abT2bB9P*C6Oixn{-%(*TWMue3 zkRnV8TcSS;hlV}PXGjn8IY$wDnC_-Jz9Ylu;+gote=a8Z6X6g3BtH(<9M_BEokqv; z&Y)Wb9|S4GRADPPEc`s|Zia>3%yn;Ac-^}OyPIyNMp&I_t%FuUs_+ZEu6bV|SH0mJ zMZD@=@lrFNDoh=I7_<()42OqTyf2ZX9;_A+(&F9!ghbYKaXg;@Zaq% zW_8T#&x(;@FQm8V`EIlTFCl)zf1CfC|5CgVOYn_(OAzN}B68+1Q`kOe7i?6u!&>35 zaHHCw-V1Ao8yNqpHmO=+&2W?2i0(nmo?^4A!85*@nVPU>SR-7o%7^d4_gJ&gU%(l+ za<1R}rJTok>zG}y)~Rw~`EZNctVY6-#99*W^mcel!d>1@I09`3VH?}QM^*jhNeMG}|TU%$KWp=+#76qgJa@Vd-#&ny$JDpH+eJO`o85 z&{fR9vWWdrx@;4N+aItQzWuv)EBCBstTOf^Gw70>ls z-6?pEbPQhT=Q?7?phM6_%w+bZexW-AFOl}ak7}msB380?m3pPy2bscG`X#!v_!0Y0 z>POXCyw@V`;h$a4FxYS<)m-$QKa(@|I;V*|P{S|(paD`f~3UP)Ns&KemErW&7AB$P) zXZSO5i-b$n5>+Hzrk29O=*8hCZ=<(3-0W?FTfEJ1tG5OI=52*b&_%-{;S%);aXuEG zh+ot!<+#tj`IPY|;!`nO{h|hmIcheXtv(f5c{J(6!D6nOqXuIiB!-B2YOWfBWw02^ zc!(G&7O92mE3sHDf=kq5xJZo@!U%d@*qxUOZ zjQ&i_SM$_o#2hL_-+=AT7QQ1t zIFryc#L_5e62v$0Op~B7dK9a*_q)H^U*-Q!^wsbn`Udg;@P8uO&t8L|533slebEgV zH4K^(Bc5rB#5MJUe$3QI8U)RliEEl6am;lh-0(+xqlkZqsH^-#NL*1AuQ;YC5;OH! zTR*55^hY0NKCUPh6b)jg7;;P(502^Muo(J?f0)@4!Et>;mk5fZO9mx^6Z$0jgq{`t z=*{$Ig+F;e!bRv(LCN5xzNeq*tl>SKFU$+`hxuTEFh9&176^X{XL>WdU&2}F`}pP! z?<0A_Q@V6eDmbM}5n*;X!<+8S#&?GIK;PGS!Ust1a85Ygo94|4XQM~){C*)uiR@vv zaFoaqW`{Y$957dyGn^Yv^QL-pSuxE!t;+8}U#-fDgF7kBD^DZ_e5l-cUS0gJaPnh!J?rus8S0dLQ9a7P;aNVRooD z#QPdO#2bfhgKq$RyxTDHy>Z0Bcs21pWz`_~ExMw2(ZAqV^eUh`FyGkgfHd+xVfIrv9^H}ShOh&=6S^U6=r!;P z#%cyNf&#HxK}}dQC>SdgD;TR06hf*8`LP#><&V`4Y6XR3)q`rV5W1vy%s=Xv^p5+- z;0gb@U&1@-pMaPd)q<))DetI% z#4p8flz5_)SCXSr-VuJ9iW8@VSKK?}pZ1G;XZVQ)3@A$aDI5lP4Xss zcUUpW%M+^`)CuwsIdAMHv$x#e?v9)2{f$iU8pkRI6@r$rDnVuV0lHDFQcw|A3>wFp z#3}^kgC?=Y=oYccK_%D{-2$IRv8J)|LAjtQUgcrA;Jp5W_&41jZeh3}yv}(hc-P(c z-gj_<_q|uzE9J!##k}+WIlq{9!9Ner@%W4JY+vx35%0WihMdzki13HI;eHMmhRtK= z^jY0J)(qV+c2=K(&C!?8XLK2&#uG)oO2jDYRYn)}s-TN%=v!Syvn>CgrHb#sVIhY?KGGoaS%ZY8Y$iz5vEK}@`zN@df@x1b` zx$EvbIKb-<2YLhG$KF8riT5%5j@M=`R*x1LS(Pc4lIx2vQhH_3MZBt9T@kMux`OIL&d6$F&XiUqNM^xrzbB4bxwZ?Bhk)%Edu!@gc0*w5<= z`+NQ1HFPR3r59fm_G)m3!d^{uVXqdtFvmqaKlZQwNBhJKVwcpP`nJBTE~$vO^*jU!uDI@AH`v4L4tsh%U@xyHyo$c4Zs|YuMb=(YSJY+2D&&8`Ra z=?m(zz6EdLebQZVUA>d8zE=-+=4a=m>%vdbNvvJGQ?8!(K0Jv&&#DXRyt<+<>uc(& z`cI#Br`-GAX{4@KHTH+Tp{vGj>ObHmeG@iBpK*1)I^G#~8ogCrW7SsmFOPF8qkkFu zF)wybUDa3gIU=7|XI&ldJ@2eLgRT~<8oQyZA=mX;bxmJ|SMmEzZB=p8AqtChb(C6G)^f^}>Ym!(7p1bO?>-w6m9;=4l#%eFN4H2<3#5}9csOqt6`n)^m z3VEj)pHbV@HX0yrN8Y;a>aEkU8nNoJ(<*^T%^5Ga^LXySOUHH~CU#2IV74Y+r_@Dv zf!UB56WghFs4#YtnNzA(tR|xq=#wfDGhr-IY?s=p(s-%81frmKkyQn~OYWkp9jg^P zp^mHC@Upw)3VI1+yVWk05dTE6_hPkU$JKktF?GUSW;Q`=kJ_yg;FB=+ok$u>0+Yp( z!sM}JFhwjmOc_f7lW;fc#Ez+>st%Eksmb9CF?}wU-_k+5y zUhqDw6ss6(D(VJBVdYpQSTt5Smd;D-B^3F+<3zjfW`xtj`$Tx)3bLYNtYAkYT3u|ME zV>Rp)Ff^WjvnKuobEV#Q-qIQvwaBWNfZi5xtxoI!e<&dwI;kzYhH&Rg7O zu(NpWX0Yk)FCqgnOElw*&22Lqi@Desu4}&x@!%MA1FkE3&_Faq zXClVrun5tL+8=DGSjpHAHc3zlmgG!LY}{C!SQ8>QweQ*5c7n)kGvQyDqY0ug@;&@s z6tR<7^#e>ABnhf8Ti7;(5cv*TQPFP%4z*>7AU;y1QgZ5HBWMScn=x(WCc zBtjwkHJ;<#1e-ia7EB<{L|aeP7ukY(NY-GKn}}yaA~dqui1AaH4f!z~%c`&4QFqMc z^Nu2Uy#holXul`U1ehX79yDN8Lpuh~v2KjZ;HCH87xhHe;C&=ZkRSg7_B%Ykx1*UI z)X7H^V#4Lhz7JBtG(l>ZHb?{0 z1!-aWARWvQq!0S(95%b{r?cDsdH~F32k8Fj0s6=AGR#KozB;GPVf*S_HYd!1_dt9v z+kwa>+Xs7Jeb^mwdA!3&Zm*iCDpCa><8{e?j9j$6b#9vrrnR|YF4laaKh_uRC&&f+ z1J^vs{opcr8NFWk^w#n8c>Ar5ufMh5zwqUKSj>l1o|604#r2v z!6&Ycqf-RmF-{qz2$UXYzqU#zK*w}7t}2E-j*jV6LCRndkiW*|OJM40M+mT$}4!7Oq@+NcTKe)**vzN&;_=MW%TB4@t zsfVz3r`v&##$vSAwM8wl%k9Ln3(4v2cDr0oFQI-<)D{Vu)p`nXCc7yvi{+%~w)9fF7Oe!!LH@E(X9-YoY(+~?>awps9J_Y<7u zes=#8TitK)H`e52OV_hGU`~}oy(Kv*JItZ7t2g1>FqiVIZ*!@f=-euo@}X}7n~mA* zDw}#8z6tZF+$ykn5NWew$)>WZSK;f>sys?sizu5#y$oN4S+HkSkHkaqlY1m)x*70C zHxvHkesuqdEp98^%9WM0Rk^n%Z7Xz1+ZtWceuyq}Pe zg34-}S-l8fhM75U7L`do2w#Mmuw+&-rLD0s<L(^pkz%2=}G?7+WH7!X78u3FMXgjEJ4=XLcyM4?cZmANiFV;XaWc zC zseJW?9cFzjZ0#tm+FOH^w4b`JvWxuG4MKmc{#O5}kCA`jK+gLy^0)ey^NxpQ`34zJ z4Yyxdk7&LMRY_aXhQuprZ^=+qgcWTCzViD^I~)$j?-OD@fFGm3QRVnPns12ntx6(V z$q!@_9!pa3r@SRA*tc@9{Sto3%J@Md72n1W;sr?=CsrHW%DSKecbj!hp>(O2)31NU_03sw&F3I7N^8w_m_BNAKJgfOP;&G z#6zCN$MzA&uVqi$!@lN>oQbQsrv`CF_tg@2npJ&WXW2>ib$!qkxVo=Z1-{c~oO;Eo z*YcI@WqaDethlEJBX`wMoy;b+Lv>PqYF;w?O7?S|WJlN+Jp_;csUi5@RU_~ms$byq zQofMAZ7*9NU?1DteyNk&WH5zI4wKmtIzf=gCbkKJ z#5M^`V^hN4VM zT<4d1pldJN$$@SFy0WMwMysXn3=uwd?RbVhb_3C$aFm#DJQ}IKQl-QwH4=_iqhMup zDeg_(k|ExG8mbyPV`)%>3?aBM4|NN9T1xyg6hN)~ynA)a-!}RC+ zKmQ9o3=Y>{z!Y}44tcyb2!ns+KQavdlmEj1$^YP8`9FA1-i7z&J-N)CmC&i2QCIsZZ?3_K_NB2f&Z*Kzrcb+&cW1xpQ3OI`>#TQUmN`q`%$I>;bcunRV`o zdaU}}CrCfL&-_pQr}i|NVY-?#VRpY}fNiGHe{sD7}Y?Q7Q%VXe!eU)bk1 zi_VPRON4!9uNlH?Y_A#0>nxLgU|-lw%w^VD^)vg_X4TK_GnfV4N#C{qgB{V?n12eN z+CRlJ^;Gq>&(t&dR6dJFay92#4)+Gd?X*j$MO+; zA|J#1JO?>A-z||tXGcF*T%&xBJdwM(o;_x_`CNUba_SuVmgu7Yv;W#Ix-)tg_T6Te z8Kyp08Ffx(Ga@&|PAt33PVI=04?le10DKT7ahdazRxZPyXH^msa1FY-{$baVZ_s*A3v8tD44el(|=>lV5m^UZZ$ z)k3#~_0To&si|tHyM6gsWK|)Z$XpZ`L?V1DnF6Z4Zl?>V z{OGEzt)>d#Sx^_yT_Ua8>9)F{DuB+fyJE|a6wrlKLDg2L3H0Kh!G{D#^`%~MO8uF^DC)} zu(GNItEkGbs;UC-qE+xly@qeq8~B=My*x7&R8!ZTt7z()pp)tw;<`x6HQo@(IJz#H zxo%uvGnY^2g-tn1!WAYqNz7$&NhHVP8cc?6?(*t9y18qHPN9?QYodi~?(*msNN$}J z|0E_QGuK2**TUu2D~+!`7-%2z@`DeR)XB^haakn8KdD(|JT3Gpvl5*Sdot6?wbre4 zEBB#ByN~pTu#Nr*w&EVGHbTEut63*>TKvk6wv>LXW(=i&p` zk}FArPg?V#E20Xk51IYQtub%8M{CS#bZV~pnn-P~iL3CcNMl;NqN<2$jsJ(PzWaa( zYt0&?f>b7zPN`GjpW5Ve#Z*z156{+aomtClN@kfesdXw{+AMeLU1?rx%Uymv^TFb( zn5r+^yAH0NZ0Fj;_O8CX@0V3&)P294Dhtc2a_}Bn2J46^gY{;eNkPn%FpW;F-d6MOgX`!T$ol9qX1&`COQY+`Hm)sfi(f<8(RFeS@$Kj~nDs^mb>s%u#?`^6 zu5847C)Wt+?@;O3X=@a-;hdmNOgSudFY@D%QACs-!9` z3&|d?Fw))C!l$+@j=h8{?no@Vr5xL7B+=U#7eTF zye7Ap&E`5f;%1`Xkk@4pT*ZD(UX@$T7E_AICEXRqSLGGC!fZ8v$Q$?+F@;S819r7l;gypilB$t`x=Ar+ne@^b>$PX&xQ`#*wXXP2W&@4h%!cy5S zFlXdxxxg$$Kk^^?mE0r0qN@Naxr)vU_Osp#4#@rRpgaKg5v@G)6+-x()9GA0^WAYbsOdf@^(bLUg zc}Pw(N9196nBy7dko;ZFFw@bq%u#s+{(_!`&ondB{4Nj5ndTr@HWT09<&W6B;3q`D zAJIRXpZH?ospe-m#Y}~h%@p{pnGDC9Z(&t_Z{^nCF?#ENXU3zyH{Y4J{xmt2E1qD! zXFP?`R5?XH@gMusg>`jT4c2hgVNF*9)^asrZC49c<-YCGZ~fhRkKT>mgS_!~ z>WMtkos4(sQg{~DdzpXZ@6eOXM6*NxU?#zdW~cs*nK%A+EIag8j^6lN&~N;0`Wy3u z*@k_)UZ=NUS&x3>Z$Mtd_2^&q2L0OKsDFi9Mu-|*@e4wqlZe)#kc2Zo>V$Onc4!q4SEwx=q7OcO!#?2%`KA1k`B(mr$V>lMxshx8l~o(%C*jB8dhsbf zeZrscdg*VFoAgG#0iR#xLh+uf?G}nU?mbx7)q(H3y0D&mA69Yo;7WAw@Dt+n4p)m+ zaE(|E*NQc8omdOki*;fUXZbX21_!~f_TUCG{-%Gyd!3TD@7X!+*VOf@jmPNjOT5WIS4qlE27V z_^iceom?UoixPSXQd~C<$H>vLF+NSgM&VdFMmECII9w{0h~j#UUaQwiDA&k_%r**_ ziDJ5_UdCK8xD>ryEE7fbYJAs7C|Apw`i1|ao~d8@FZ`eMj~vZlJX8Oye_}kH@eDm( z|HAc5*R!K5W9EfF3wiFZBGPIJBs?rJwuT>@$D6-C@VcujLNAoueJd zIQbjgW_Q}J|)xxdRc3>$>ISl2Mz zg6CE{h1sckik>Iu%H6g>SU=otccEA6ReF_#a;4mi=N7x!&L+ZUJ4esf56uHpMDMZn z!+PN!yBmF<;|J!Ed5GR*=ju6dj^1qVaeUwW#Y_>s*47Q{glp~lVO>}+d>`&X-(~Ke zxoehlSMQplx(Hk$mWz2@6<4O`%XxBzUMW{ZL~kViCOcWr)f?^q@Vsl%^KK`(`4!tn z`yZD7nfZEwoG<4`YxQ!yLa&feE|(kd`PKf5&wpk?r#hhS&0la+zF@&j!0N zvg?IScOaM7dP1V|Kk=6xsD6y;v@iOY~B`G@@K07e^MoSTE7h7?HcgKjv?< zOZ;p8fh*8=(0`lVVwbpMGMN0PjLd+PmV3l*ELC-GlMCiCxnW+D2j(+*VS1AfrbX`+ zd+@BLbD5m5Dte#Ti>11*rgNH|{LHNq`}7F&joHUBjRDWegn4{SD=_7ii z`N|x@a#SDIqs&Ni7|RiTNRKw7%ppC-jE1AI{?7Q2KB&i?Q~PIb{x6PM6g; zc&(MzBlU1I&Wyx!zm6xfnXD$BjEl~WPY#(~me=Lc`y0JLa+3 zFZPMY=787_4~hfgruoBE(Aij(UB;JLO%@Yh#zWsSH?iL`<(a$1sJu=fvzW{#0bW_m zpUh{IeviX%B!r)BzuL=%u~}V?1}CgJ~dBZ zFZ5ZHQD%^5@y#gDnG7;LJc~YW&YAQuy-X)BnDZuLI+<2pG#5--dC6RS$FwqyylgI+ zh-qYMdBt2d5mU=l@{CC(Q^G6gRPKpM?b5i^=#)q*mzJX^CdIqs6s~Ld#H7Ra#3W~& z!X<;rT~e6LC4ouZOXi=LmnMNr=MrN{;trcLCZ$ZoII&9z6FG;M7dn>!9dlkN!WcF$ zjN@WXgmIC#Ca#Nvz8Uyo5Z(%cP{Nz&KY~}rhdy(E1~OFPpTRBkjo`I;Wo|J0M{qk( z;c0W5c@7n87J`ELd#2 zgq_31b`g4sU2HqU&S9r;sa;|tb_zR&%WTK616+z;ZkO2(p_OgJHeo2+g>7M5j*V;| zwhIlGP&(Nr{3vwtBhKe!E|(KpY+5d7t(G0a_OLzPF?@5n7?Q)q;V6ew_-Lu*3cK9q z77Ohfn@8jp5!cw&Hm}GdBCfWpY%a0DE`$s5llUunCx}CYJ3$VY-Q{F9m&hsR+XXhC z$SYRCRd%KQJGc{McYh<qv2RR27ax_!g2a*_>CT?55c|mko{JFqqB-v!OI}4cpbcgZ-Un_8#;}6 z5Zs3kg9q?PkW8i#M}s4b{|hp^G$NzR0FMPnv1D=?8E1BxU(rR=w2k z_Mq*n`l$VIzujm1slF=WK6@A*wnyL*JID4^-*TsV;@?a4REO;Ewuc(8ztugk_f-AW z96Q_gSN+iS)ol9Lnq_~s4Vj;1 zyJGLAx~d8Kd))(cB-u^gr%S;E=q{DsyNa{6~* zR;n2DZD1Sqkt%|vuqY}%RIOD}@sauv7DE@sUW6VrX+$zUD@w-S*TfhLrxq zj?$C$I@{cIr1pL#dq)pdov?Yh$hHW(^1H5E*qe6&gTt?=ksTRM4hM(<!Zs*%EXTYZ$MkkIq)c+t8iFYAkE$#Iud@ zD#oknz_Xq4O2(_`z_Ww#3dSpg>uwo+WsbW&blAD(meW7x8kXy1;qIm*&k6EUcLz7z zQu@=}Ae(+^aLh%2Q;*?)oDB07^p&~Fs%vC}?;`F=*6j-Za7*}Y5mf~&368$|TYHpM z$H*#Qf%g^Hnsc9WJGq7^i+pErkvfDUF#0Qa=2ifo1d zku|8`4jvQR1mrB-CF^Vl<0$(~ldWvXQMl(c_9zEUizwGji~BAl+u%O4_sA~WgC)u` z)8Ya4`(#gBauS}w2V@jEa+{vQXS`NpWG_8|PhFBQ+G|Z5M*D$@87HAOK1p~_CPnVb zMA)N>_h_Fms+zwGv8se&v}c$Qdm?J^lZA;?JcPWNFxo{-z-&T#R>TVvs<;T*JYlr2 z7@ye$^tj+y#bG{yqAH)!x6yhZ_hdBoFk^HnIjs>h0vmjl^>lzloxZxv#MEe-nRUr5J(b zD?LI-IdR``9Ej*|t`uKl8KJ+_QC3>?mp35ONpkk+Z%QDB>&;|)4QKXCt$2t0+?`gZ zR7kCwN7eXsD%U)5MxDlT5;>)=a(s;%#OuBgCzPSf&WU$(XQ^8V#T90+QUQ5`*&@8J ze(s7Of{F?f^29lH7JZymR1)BM#lMNK5Z`efJ{*t!g6kPh-NiX&#W6gOt6O*paS8v+ zepEFpVnva+E~@>o;wV1H)J0}5Q3)!9c~{{n#Bz3LzR*#P>RVR~dE<`Yc~o6g7g%+h z9yLeQZB`g@fo=vK^u$F!sxy7#iX*SxCH$PY#0o3U<8$F%E$b2Wmmg)mU#1$yi93Fj z3x9{1!|!TbocP;6ME?8V)UX~>OLde@woFI4TFdy*qbP4KT z7wM8wCAD7Smb#UE2D8L{uA|-K&-EI&8m@}2STA+U+$z0{9jaA)y0g?RWYr=*cPT~n z^+H{kn(vjo*YL$EwNm+1oAczqt7(sk)f}JqS5q18ixv1pHQUj9li&QUbXwYs=N3Pz zKR*x8Q~R}?*%fLVT>xU#4?8@TVOdVad{hY+RlJ|0qWB8W!bWB{(V1Wyo=e}oqgjgQ zGAj7bQaKmZ*q@~``HI>Iqq?IV_{E_Y!gll${Fkbz+W(Bd9yv|j@l_SoGe0 zM=aoRE##A@LR5FJ<{oTvt97&&w^~PgYpXfl=r*X+RQ_!s(rJG&F_)-abXtfb))Qv~ z)yLPVHTq1ib!*&bdYxMf*Kki4y?a-+2>-?ESGpLS@_$86!jpV{zm8SwVU%mOo1PDG z#6}hE9&E(-iNBDwi_{*vNyHIr@mWU=a+L43iOvU){RPY}RD0<&5l2v&tfKnlo8-f- z@o$koH=oC{K+o3&sb*iJ*SmFYjo!cx>KZ=X+~DT3b^(14qP>==Yrrc{iRbGECHT`-0=zVk^ znAd-yqI%FMw%(`L|Wfk8&+zjQ&)bow^5frHXd!G$Z3bCQg)<6jg&qc`WfnP9o&; z3;6l{J!Cn&!tzK(b>NTid8~3Uo6|4I{2o=%-%T}GK}NgP1@7x$eF6DNKU7g=_(N7b zB17Ue5wiPJcu$<2wK@Dktlp&xAv;wZUR|sGI9%y1#;d5UkHaf&m9Kd9J%W$8O65nL zIF!GY-WdT$TM6}y3UL-EzBDJKp(=0S;H*vJ`tU&C)0s2OE?+H98Sb%65R}whuOkTbcmXz zJ0U;oDfG3=98P)H`(*;N6X}Hbl%MVB)6}W@d&U#!nHXiRO%0~dHDoH1F+9$vtW))I z?r|pnIHSz|G`b~aq;q7(Fhdw+d1vxZAQ}CYBHBq?$({LIB=G-7MqUE{F8Oo`{P<{( zJK)m=tT@{9OQ7jds->o1DbENUcQw@_?pD1SMFe+o(Occg39&+Jx3`)SMZTtU8Ndb-d>d93OEW!RSs!P!0f zf|W#zcU=n;`u~y{oY4P|Ox}ck0`x&qiSBm?SzXCr%Bp3e195li4*Vzjv+iS3@OtQD zQqrZVk4Z)Er9LJ#9h3T)H1s>_W739c=qi_%(Lj@q?nVR5%wR?^fbl?j&CQ^zP=E6y z-8=hZA7B#s3H^UmEB0Y`=vH*8+Nt}QpXlb<51;;Yg=@vGY+v(p@Kewidq29%?as<-IUZi_C%o;SPFItiB2WD0Cy=P=p_-vT%5r6MWz zB(4oz?6&JVo}j85)0vCv54HYU+5@WnK+e98n<0<(`oRGKFw~!c}uZ^eN}ua z^Lck0JW{*1blsck$EXaN>c^pCXqxY+37SSHF-LA(IlluePp`x2^ck~yiXWHCqbYb! z^*ibg%y&e}`t9&(Pd;1)`W?=|FVr*qkXP6Y)>%#8F4nYVwjEh<73p%=Rv#1<{Z3?b zmW5^gGJYzqB(+QB+R^#17FSpW&ZcYaOkTMO#Z00mpo3OC9asOr^A``sC2kwyv?YJC zj9=RCOkQUhdTjlpet?P4Khkk7q4-E2V1MHyJll|iC+Jkyg%zd!E=Va@iq~aI&YQ}m zbnQ($dYaCmLvBsZUd#MMkGq8QkV-_v4~g^9yIj7vUJCaCT?SL&pVIwI-@Jrk!n^L1 z6Y!kqchhg_Mb{1Aw_a;jeW+`gxpdmCLFAg|dpsx5@9$?;wPLn4Iegvp8?RP4hQ6mY zVJ$jCji#?^)GcasPyO2%U#%qQ9z=QV^&s9G z?*k&Y($!fNbr1WR9;j95AGH`RraNynEK!fLadb-^&)V<&miT`_?rsnL+N=Do*KcLI zqb&-mhTqV8wJM&~!f){$@Atyv6%}kf(Usoy0Io#$wS__Hcl~`!)5~o^P==np^I&Oo zS-L#UgY)PtTrQl;T_{J#r@2A-usS)N<-;1}YnG>@R1JF6RWns#d2~g((^WOe>7tlW zBp0*&U;N}^4jm7Zi@EeDOfKfpc`&({Pk*lDVgVhvl8c4@0)M|~M%L(UGM72Nk}r8u17a}*FCnG-xS@Q zF2v*MWi}q~0YS9eKY$hW=s_6m|3|$A-=`O0U2--)rXyipx*0Yh-{TW{8a8>?>98qz zBA*6L!{6AAt>ynFYSPQ|H%2x6LG(Lp7H$*2i5mVkq`Kdn?uX6zEOap452GBV>SQWa zr<-PGyNElR*)FC#R~9OUlaZTLjb58O$X%-DXCj+@G0Z~NdnSA`zpDmLCNg4)>YB5X z-5yo$olE<3x<_O7Ninb;+E ziYoptq_Uq5dsNMxLuc3NY)-PwKVnr2_JM}dQ86d=t;s}xI`yWYCu|D3##Yp6>B(D> z9qP37nN30G-+_KookS00loSrY)(`*wetGVFTA0?az^-{korX@e1N|hr@4L>weevn% zm%}I8`EE{soYoB_rbp}y>XN1#QGCrP?gCJermrgtD^n&7IacB zt6S0~IjP7+C2mrYlWXoxtW@*{O+{zWPyNJHhJH$n#AGH^VQp2Uw_k=;Wp!)L@?n^k zI^3l6_D!S{>OrhXM2133JWA^i=&)Rkb-iJ4x_I_P_won(gZzYgupd>}4rY{q+=6Pl zr(X*H(&TfsqW?0rz2xQRwz+jK7-cl)<_@Q`Ls%W39EIxm*FbvsC3S1M0GHGs((|_@ zYfI^&{t$eIB8A9osG)oKHIeRq34BVD)6kthq_vpoPQ^htx|-I;*3Bp5n+|jJVFR-D zI?{ixp=;pU!}fF&tcRsOIZ~bIQ5WTjw}b8I)tx80Ha>fgakghpm%vCER|g)H$3e<$z-hJK8K$Lt;4E}J_{^oany_MC5y$_Hgrigwyoa=CO}tvw>KMQ`n3*2d@MDn zTgh&Tvi@3y)&GAN*A^fjKQH$!kB#yGKL~5Q+v6?vF2lbVvw7)oP*4|xpZP=mqIRfX zNEf9>pr9^dKleZLi(oHGr+{Jp=YC-CiOED`e*~ zoH6PM8q~b){MpT?gs*fA# zDPBSP4NRfqQ$ahMwR7ljH=6FZQ@#9j5tvHMUr}FNhw*#7l3y`;Pj?_ovn7?!ufop$YowDuo<3>$?3=I? zU0~lZ)5-5hUVTd{tAC-h-P>@C{|g*Tr`WetQjhh8eH+g5I)@c`*OAwi;(fAbXVC%A zvjUxu9sO109c~pg*0w*<8P2yqdp|)Boq>0QDahZ?hfl!#k6ri8vSGTwZtTO= zHc_@s?RWV!wM}QPHiv7BXOvS@+oZNh*dI(yRb3JhWt(q?o5d#4gns-vTmv$1YMVA; zCu#!Pgq_LyZxcp2>}|p*x4li+jm-BpVU!);ChW+)%I=!5st9?s8%310zDYEte}8uB zjMs24656%oU?#Nd$iYl#S951lGENBBlaJX-w55iim1swuK`YUiiiB38YtR^e$KUK$ zq8q(MTZ!&;9!-INR13F(tkUE#su+y2P&2AF)N5o^twbA_0cKR0sLS}!Wl|Z@>9J%` znW?{M?J_g-p-YD)y-H?_xQ!wi5u*CTjpA3vMR^QqnN6p%sMfBP%fh<^>LhW%kw8?is^O)bU#un*Nf`@^VWbAQ;Ls>}V{ z`8Is-KofVF?`Gf`fcw#dY?Nm^$o32S!cJkoFeT?rMfGp=O&~ew7tqq>Kw7wdHp-yt zXM2-7)z9`}zqTKBseQuHtQtf`Uq9P3?2j}s!`yqOA>aLQfU_J#I)vk}409L%uf6k( zvZDCfebuS%uI|%-FyuTl40&cq!!SddAq_c-k_1UAAP5RbR$$0EiGT?NL_tMC%!(Nl z6%-|_Ac9Jg3*wIAO-)$v6@@_kq_Vc0#wXA43s4K9d;h>fk7RSJY`k0ng7`s?u zG5~c7S!uG1{XF2$pwF3sL{idE(8+cLJKIj+XwqG92q#2$Vad@$zQh_G;&=}GCHSQ! ziFp=nlcQQzf*hs)V{rNI(#g>|9LZdwEboTpU7|DZw%<{c9GxEYX9dl4_6Wld$I&0n zj9sJ>`Pk9^rn_+`|3+^|VN&jn{={!uR-+tbzlYEOkSM0v^gJi}Jv`;fMDq56MSC3k z>1C(U^Yq|Xw)#zvrLPWFA}c%E9qge$x*3#U55V@&GkU<6D5(SN@t~he&(nfmbPwCz{zCu1>Ty8_bS%d4<-CL411ouEbPtw6 zr1|)04?6+-MbC`3N9|%J{m+8GVqDPP?)R&@Rowmbf53l?2<4g4slg78Z7Tie21oRS z=r3AU1QcgoKyf0=e}GLqBl-hYk0|>I(Ia|B^f9*D2Ma&j}{5` z(nmV10h6MKG%N?f^yp7)D{2ABZgnEfcleV7;e#sb-lK{Tv3(D@BJPuHaY*OVep+-d zEr0T#pyiXnNZ1|@>8`3SQCVG8I&oKBRbis3gte)#JC*jiur=(U^%U|`VS3o%Pa;|y zO_RXJc*NVP8pHv%RW*s|YpZGzxz|?JCR(qpsza<;Ta`v+SX&sA(p-=B76#0pNqt>} zm}Z~yUh;b>x%fS}G53+WF<$C`n!-VV#RU!?7e34br0rB&mFh;}k&O!s9w){Z9T!B% z8<;DF75lG1xc~nqhEY(I1pdS$k&U96kdH0mh-Umd*yEqVcKauT6gSyDN$sD(Nti+Q z`lqSi4T_$_i6E7j$rC|4_IrYsCxiTOgU7+r(@qIjPkYr)6@Z^S4kn-WO89&_sP^i2 z@HiYl9bwx!1`4}RC)H6M1&_h&(;0T5GvHBTS-Yst>MVGMINQ77RC-3OQgOjbY!&N7 z3efYj_~KX>au+=AEAXs@EA3f4zw41)!Kamm+x}^4SE#UrA6 z!FHu-A?#{#a87BxT>V4sxnLRjr_@q#nOXuaRT7o{yB-z&3zdOU(ZA6n7!^H*qQNM< zr}SdlEKzHT6#o-0m_N}D=uZ4~oJw-mMo;RB&Pja&Od_p-C&{Vctc$LVR&q|D1yISU zNSf#fw@f1b3QlF`4}Dx$b}Er3;Fql&D6sye69fvC!= z;?rnIC;17zhd^{a#u&ao1(fWZ<%OIb}TEHbIIJ+HU>6NtRu?hk_>WxFpd z1>1e$8`$m(TflZ-_y9`LzO*A6NkfC?t}vc8cYD%f3!+m?s0%ukelF-5tk`bm-WT)= zn$f1Yo8z{iwke)wM6~vXfu$wB66#Yln1%+QVh;yRTw$qcLTyvxiCa>8oqjH$6H$}( z+}YGNAu?7tY+6%aLVbp!)5F1M*pMI#f3}WO@0Mn@R(pJ< zRYTe|a$75jZf~v56W!hwez1l_Cw2up5K&!5l~oau zKa3?XvIdrDQdY|namp%Y*E}071q!2&YlP9q0bOE4g<;7t!kgq6VIgwN3Rs99rk|m( zwg@A_BhE0=A$T5!@#PWcN-!L|41-wLpn-cgR^Khh5tUWtR41aiM>xVxF@m<2gTZVy z1fGl5YA`G{Bb-Yx)?6a4-ZL(1b3Kzz9;MtJ2SMwsIwW*Mw-*3@>cYHK`G*RiG!(XiH}5!Y%dr-4^c27-+M zy`OPBfqo>u@i+ei|8e%9qK{*DVByOkO1LdN ze;KejwcrSvV*`kL6b-FCwEqFdljdpwj7E<;cY-n4?Vun!1rd}^J|o>t%RP?p`PFmV zVLjckj;!Y%%NDnT60|9(zo*S^Vk3{C$kj~she@Rw>m2(#?cw(8>9)suxZgRVzx5q$ zzITf2&)KfH{(`hPxe{6v6Z@;9%~7IawK+z_td7OXYIEHAo&2v{7tJ}3z`Ah}Wf$M% zq4DCI8|Ys6W+y5ZzWExx3*W#50bWAe$tQP7f9o7aFY8j=&Vrg+Wn13QRGyjskxD4)6<^#b z6D2Ma{mcIo{1r{LX|Xz4FMpCH=qLRXelDJA){UM(*GtyUpYW&Je_m7`2fB0PV6B>B$2$K8Q)n}l2!L;ig|*S+oJ||`NGH=~ik)o7JL8-?k-zzEcOs{p zzsa9=PJw5f)1dI9+=&Q3N|aw&SVv79$~;kWabO{MgrlY;?6*-<3ijBjNz@5oX_)Q& z=q}+?A*x`P^CWwjj7FYBt3ClfiAvr?XM!^cd;(>>NyLv%vQH2{I#G~yuh~SCP5>vO zdz7svpq!Mg#@pKwKYGr&&GFnJQZyi{;dX?7g@GXvAh#nD0TP<1NzkE**X6+k*bNsu z72vvC1TJ<47CL3&hh5?%!F#uaxY;DV0M9~afm2SG)k~cvPDQXHjCb?# zEFdCQI4PGoOPxw!B^d9Xa+W!QmEqf)=Y$3(O4`hKmOD>5RrGSKs-BB~92%R^~GjTba+yCWbN}oK~})*)Ya83UVn; zbLPMX-zb=aH4IYeIYp=HXNf?btA+JyED>G;hx4B?ukP+OXl|9Dhq5+sg0Sd8-VqLwx&&t&8s7=vVx9ScJKjQ0kMe67^M6TAMhuXR&ZCaU@ zW&zCfT~JSG8FayNg8EvbNbA$Gj?SUBrO7d$z)XKP?6)m~yHRJz2{LI@9|rifM3jC6 ztH3Sz-}9SwP6nP#ouSte721NWa!d=e9YvU~rUkr>T~Uu{5!9n)2Fem$;bOf9YZf#& zAEWTnoR%$MZ2y?ty)dyg4emu*qFInm`+B+?zNSGptV!^ZZU$@nN2s|pLj$4-_nYWN zGzof8N>Bw%T^PX&m~=SE3&5k6u5U&@;s|d>K8Ee!W@J07+k2t}m7qS9x%U~W9CL= zAD;b0J-q=F%5i)*BJb<_(S~{-otOKGfO^C312@B~@`pK2?FT5o^f4b`y@`q1Y=1T< z%pdrL|KTTdN!`VMx1tNv+ib<|BTDLZ{3mI3BO)NlyC+-V@?}kbod86M~n63&Y3lKwLJ}<;>gyJJ7r#kk0CFz z7XAjoJmR7A{OM|%%JXNa>EKM%Yx4YAY9=@v_WeA64&3~C{#L&}-UTl6W zma34sP0KsxCvQG_89z}!Uw!9^lFoN*^}Xjfh8`U3EHO}VwEo$fr{=1ky`M9yg_+ZJ9MTo=Ph5+5M3kLT9tMLYZEl%;-p}4#wGYelcd_la-Y#z< z+CbLv9JnrNbJOfc86nUA#+#rfs&A;><>leOK}=L(Qi&Tnt-kigsqx@=H36JJyBF}T zChlkr>2+G>ndiy907vqRq>Hi3YA0KL?L9~S`QRFDuA67cKNnmjf6a`geupQ@MmxPL zc&-waXjgru)JiISrhSj+byr&LDT)UrC!) z!O9>?BwjAH)6g*6&#%k%4|w~%$B3!^3LHy1lWnfX^yaRi=5`S6h^e&6g-`w}8iA`( z#=8n$Cta=bNLQmfmIvM>oyB%n{aM%*f4x41>g{@c8YSTM`iy@XJnNqUMY(ys7Cq+m z`n>-ScmW;dDeP-1cnF=8k!YiR1%3sSMH783(p1l;*DEOP35#koG%2n{nqj3(wq6O( zNH+N@6kW%T}p=XI3&0zQpV>Py%( zMxn0urPo3?r)6Wk%C5AHX`iK^q#seoJK`PoX6hEy&d@W#NvJxn*ORa<;6+N4=?zQPd>f50(Z?g7<^>==puv)t7?8vJQI!>HBz>2OqM>4}y=t55Ypj zsLu&*stsxmT<)ma_Jrwrn*M+zDsFZLaYU`}r2R*5ThD>Zer}AknZ+DQ9n z-9hwOQDW2=`oDX}yoL0(0PTd6-U;t%P*fKF^iFz9{1d2fETQIvC-H8dgP(hUf`8I( z5!)^Vk9)s+i~T=P?O05Hk-ykqLg^{mFGs=laiZj&^2eyh)t5mrBKE#yzr>ct82W|N zd%c>3&e5yRBy5wjjFwNqkWq|w!V11lEr>DtFGZ1Xj9N0g+`*Q$x=A8m3b zVjGW?`K1NBFohk^JXKn-Ou{vlXVGeK{J zXJP^>NE@92T9{%6(0-tPm{vti6$|N7YJx(NaH|t-lD8vCo5ww6A3Q=}%#k z>Bm<6b&CBQCXo~vDn1X!qrUWtGah@{Sw{~m{Uke#9+T`)`b=WmiZ&UYnKddEE{o5C zRP58B8s+M!4<(aUpnVeT36G%qvX&m!`Bm{&3lqQ*XxgNZmW2W1)1a)~9()Xb5^M*B z6{QMwRng56cJ?aai|8a&2^XT5Fr1_9hi=VhFkX$*FT?XO4yC7;VOw}aSFnBcBRbK( z$iCM4mD#pRn1C|MYHEjE$ zKSF;Ff7S^0G8~O4{Q8l{Js(D zQT+uRTaVJu2()~@f!AsbJ$>Vpr-yj^xc@3DlEMS@susnQ5$ZAhC9GSIvDKp}0DTP` z*5hpVwNnBmlo4?1_0{F=7=IHwm%<6O35A}oVBi|bR*#_@Bph0!*>0yZN(&p;C~8Nd zDm0qXx*#d65UvXxqF*L}_D$8Xi+n83B{f zE2!CxgAM2v{SqU@inCg+HNnv+Avh{ zZys{bgAvj@c9qk$>^rwl>@Z3xK6JKg`jy`CYecIrK?x(dJ(mAIhUra?8e}Qqob+ zfj6b2o(soGM_T5fBs7;?dp!@nllJ60pawJ_wvu*w0emg(@V7_fXCW+LZSk~2^=Bcu zLGJ7RW`D4|*?$8ZMEa2Xn*TcZx<81h>o@#2{UPpP(g*QNr1VSvtK?txU-KV!-}JYD zLr7ceMX-srrq4Edr!5%X74Ecmp{29a77gRUc#iu4wtdijz}8s#mGCdpMV zAF3u-y(^TidHGTKx#kr>S?C(NUHQYyw7lY7MyV-QFojFmM_uy+x$Fq2n&Z7X>-ZDh>DgI-hf}FpL+xA>)xO)F1+F8k>2p) z!Y}Ow+FbN5cwXp+kGXI8TYZV?f6Kq=eF+=wP45Qjd1^0smu+8S%`e08(wAuc$K0*{ zNNl2i3q{i}>@Dnb`!8Cif}h*Z>|wYlHlceVoD_#)ig*na#)!i(JZuJq>EUp&mh^Do zh3CD)+|gcmm~Cu0%H4n><|uapV{?=%ip#)pwA;({1V>T2gKp~AR&+Z4@qP);d1t|YymOwYhMWb@dS_sdx@7yf z7qQ+jBHy9?H&&5~;>a2BjCUHXjZ@y=;A!s^_#5e8qH>w&#Ud*JDb#$0Hlwl|u19_Z3=W(*zlXu4Q@9&8mrj&-+k0u#4Q0JU!M$Nu@E%mm4h3Dq zWAIXqbGwkg8)c?L=rgrJr|CP}2K(8zr6hP52A{U%4%>EN+whQWkII(dAy|H@nqT1S zsRC9tRm>6Cd@6%g&YAb5ZlN#-C-L#gIZIF(XO3TXvulSCIMY#-Jz zC*feKVNyxa%Lyx(MAH!+s+#76{lnHYHAoZiB$@=%8fB_lC}{m*YhlN2Je~y8Dr_Cb zoARXbF*U8@wzd)8s5+Dce}_{k%^c&rrJ>?lyGo;Tn2mZ@Y10Iq!$x2>Y16O~ zs-aC$3TtGVg$+>|ZH7`z4rv$)7f8eKI~Y_NfDO^~`X26(`k-iQ?S?@l6BJdaJ*aVHfSF;O{TjuaRJ6k~ zOko>m4+e#?13?j6*a{v%IiV=*!-ArmP|Oy!g8R^rC~k|{pM!a>XkE;Qsb5gkHRiga zH8B_eJoE?Vqu;T>6)mgVXe6fP2DuMD+QK<8F-0X7v;+(w5=P~RVCQ6u1ZrSZC$K{O{IMexN!=g$Ga32 zinMSkRwqoslM1^|ep|pM!y7WoO;$5urcWj}6Q25HH3Kz_rEZ;Y8CE--hG#l@7PV0i zeTtgeVJ@C&FxMxmT(^epqC4vv_HJ}QYuK(RkJhmFphQ~3-iuOc4ckrMtLxhCx*OPy za&`42n$OkY1eyv?hQGYJngUySb;?uRL{$&X-9)vV{Uxdl)OHiq(N^Q7cSTtI+>WR5ef?O;j~eGEG#q!kS_jiRNq8!#s+3-It72>1it0J^xhtyY(c!L0Z4x{~Yf!GPLaQ}yCG`S2+m)!T zs4A<~=wnx=el_?4-d0W>cy(JlwPD(A?X)6o2{&#Xu#Rozv~g;|#@oheO`79$=Un8# zewzlS(W0$W69(J1@Y~h{>%rmMmMw(Ew}=-07)% z=;pL+;WQ)P9PEW6ZU-j|UgHi>Etwmi@B52 zku)1m6DQm0jec)ury=amovCkVvs450D6&*Vyh!mTCxhTb61B zw{Dhd3=40T%7UpkOVQd%SM}j3PFD?JI!;%eod#eRIHuFp-LOcftFCZHr>lG5fKHDo z%G6WcP>ZQYK3z3d?9Itg-BF0iz+X=_is@rCqNb0N8B>4Bq&5SMklrYJG^D<_Q(yH& z@1;JqnJAa^Lh+>miXXkeo_HJ3_C6;;C8Bkb5YszJP@~_Ez#<1t=g~(qqpkAiqu80yDTOivyZy&Eav}KSBR*4Q>8?&D9t*d&bqHIXP-su z`vz)8>-FD$oGoiV4$8r;*jbO|i)bXe-QU3~n4R$742*v7|H_K1ICNxkRWAS8oW@F} zT(t;X#JZ)_pk6SGwaK&eLj5t!OL6ua)WJIQUIe2h-$f(QF??4&9sKIY$LCXl@`?Np zN%NDlU_R0U0RVpumCAho-l9}q~sDc$H!5Sm`~QE3SUJWCBypQ2<#EEPBj8s zgoZOCN=dWgp@K>RlUQ@nl5<%BtUx(O$(hZ;TJkktRt2=ca`@U_o>FtH1>d#HlWWEr zk@Bi3*bI~vBTc}jpsa#vf|cc3lqQ!2W`nX)rZLDp#;TiATx(f<(+F$KH7!o5A=Zd1 zT%4R}))WJaQL0bA0US$3NHekeDuZ891S~?i9>1%(XF~p$vx^CHTxJSLAAGP*eW@ z*X#eS>t(oZa#bslI$TS*>oCK$uR_Vi9PWv#lswGkUa3aOVjlNUHF7?8Of~MU>f{3M zr0U#r$>gHkVaeQ!Dda-#ycF)yRC4*aBU8C|Ymm#&omzwYyC%5;+`%=u%WK8%_u8a# z*VkrL$h}_(l<^_&C2^pP9(fBX49ciVCzY|4&PbCHRuq&`m_b^Mv6lg6P?j;831(6* z!C0*y8_f;C`glvmMz)OjhK&1$lw~Gp1U8~vhP=!fGB3!Skp*T^mKh}*%%&_eO%t#Q z<@nf)6OX4nbCb+O30ORHR&#QR%uvml%UY1Dz|7TxIWC7>5;Iy3s7Ym9CDCs@J;+*{ zc=lJGp5^ILo}(zo9_86pj^iuKk;wC^EXQ4j@2?-j zlKgUEg%d2n84x}=!Qz}BVSf`W#(ArY6#>&p)5sMD>yp+X7YE9fsLfR=2+E8u@11d6 zLz(q!#jc`o(A~w=mS;kZ*p=p;k?Wosy94Czkb6a*Bq_1`L+%~9lTt|Ko{~E(nN;4Y z0`5O~2FY7hz}fkz*A_ zTiI_9P+|p=@yIU`C0RL!o}k1`q~MWXE2^(@7xV%p&Lb6%oDorCm1DaPl*o@7c;wuP zj;b6du_#y{&TL1#@>?a9}Ilde4Z+LUT>2bHJXj(ly^ zk5XT*Upw;hyzIxC@OG5jkk*0ot}LE3?#@=Atc6U&+JJ4Sm8Yrj<&^AGqvo?O03&n7>G{8S}hsOy4q_sO?iLAf{Q z#qL&F8##p$GnsF~Ipiku<#--<@%-3*{RF-zx!31&kIOgZ`h3UD;cM_D##;^}VF8}z zvU7Q{w~e7kN&c_P@Hv=Lvo8#0EQ;c3kK(n4@CX=B!NF9sLVVmSH6jL)XDk^c-g zW_*t2+X(M?q^!0gW#ttqtFTCAEKgJe8Iz^K(wwD@v6*pWY)*WI{6=^aWDb1=3wiGg z$Zd+vlAB`l<0e|<=X+H^-K&hLf}qTg!rO2c->w4cUW?6=ui-0%=5iokwD85D!W>ZE zOeqc~`_15+SYhxD(k-NgnN#FDYZl)mM}qQgGK;T8qe1y|fmb^r3 zDb~%u&400n;Teh*;XmL*LCdQB72qmT8(Yn9S*`yJd0DkDPo(D<@s>97PP2m1?#6J1 zVkN&?Cadw)Q>0ogC)Iday^ohginM*2(J$@fsrWQpjq<+t5cVMdd6y^35RReK+0-qyycilIx&+Z;;(?UWz2TQ zTb7xpGc!*GJV{s^#%~wAWtgeDFjFPrsfe}aj_r!CG**V0tsrF9tiPv}!z@Z15OZi%%Ec%Z zXFOIT--CQH=Fn=Ci&84a-B_J`6EK^(vLt(|k3lJWIDS2d$KHV$XeawcPhphltFcZ|nR)MSdW%aNOX6BIAi@=3E8Re~{H@_y1Sv$n5n2jfZ zvVuoplR#M~Bx`mQ&r5li>BAO<82KTy)Icl*7cbMK}_f?c|sv^ee|B|4Go4r4MQIfB*jr|M{5z_oJ2Lm*X-2 S@tFTl=SuNg{^yKE)PDis9a>8O literal 0 HcmV?d00001 diff --git a/advantagescopeassets/Robot_Epsilon/model_3.glb b/advantagescopeassets/Robot_Epsilon/model_3.glb new file mode 100644 index 0000000000000000000000000000000000000000..ee1e0f0248a0c8cb3ef57ef235c17d16d45aadca GIT binary patch literal 7611684 zcmd3v%kE^!ao%Y^%D~={LftRi8ur2qYhl3~!wZQR83N29A&p=Qg5Saq?BADp>ePvo zQ5l(?S+bj=X4w6&>ijYy<9_+?|KqRz!@vH`Z+`P{{_U^7`9J^acfa|M|M@Tf(?9?8 z*MIoK&;RfbfBO4>`04lm^`C$Gn}7Vz01{i}ca^Upv1{(3y!e*4oO{`8N(@W;o;Z-4sZU;i(@O#qo509`2XJ{qVRy&nJH8a6aCz|BVm*-7m|Bj;G`0ay=gp z&&TzgK65;uPLI>|csO0Jw?q2W>3TVAf8F_tU(<1Z`Y-?f-<^N@-@mP*I33fGTX6hN zK+Ktr4M5VT9QgC0T)0MV|1%U(CzE7>^2k(qp1D&&IX<7~%kgwMoo~m}Bj2x~O8VU8 z^0*u?=j-uye?AU}OZw#Xdb!@8*ZbpsIG&zQeh(TAQRaTRw89Z#+*3t(GDVAPm=ET7 zxCVT-K9>%LacFb89nLo%$MJEvq&MTybdWN~<2B&46-=T`ai){Q{056YR=$~UKsjAF zYwgh(DCYI2$A7s!FSp0>_PimFPIvLWL9)EGjUf9VG)8H1j-Csz=`D|W-ut)jFujMQ z<#WSWo&kTIR;uWJ&$q+v@qBQy^XY!LrVBnE?)>W_kj@AFUP+kq^K`o(?#ILNen);u zYU!a~50A_F_&7grmnk~tc-MJrOm;%Iz9sYFbbj2g&)2UkU|aAUuGdFWu7~>-Is8H| z?4u-k-XaK)Yy;tbzMPJa$Mtc4T%TN}&TzloP#mW#I-F~k#wkgHY(asX?&uE~ak)QEy#9;NVTVh4FUQOAd_3~Q z=^C(KfG9w)?F?0ULiq)7*4Li|(i2PVc0AuM=jSnjd7RJKSf}d&F>+2Sy(G=)_`D!C z9*^e*-bzp&rz4W>4%gkU=>8d$xkUzmulaU8AsBe$kAuv|QVJlK zce29~>w}~@AD)4={1(rg@rKuOJwCC&5UA(;m`{%jH?4AzSGyY6L6cOo+ z)q-~|jd?g75*YmL%N=*@emURI4=kJsJcgkaJelJb4X^lwtAGW7a)DyH;>#2N{~#X` zKa-!<>34oV_QLgfyJAp3kJnpPkk|mvlZ3(ZcGr8F0p=c=GzQF>Bit}9Aq%$I<(cji zTM^st1Obl62kx*3=X}LqhD9Hz%acGw`kCtmkKuT|UvIKnQ$S?Yq&Yv&!J9FhcIR^M zm?fB75B^UF$B4MW|4-}yOd1agFXr^TJ)zh`4n+D8Yp4uiS3s!aYepY@RjFg-6BgWiAtZDL~-%2^tu zMwjF2#^_l)eD4aSf;4A@Fx+%PG2SkZ{9v4iHVWr*3E-^yA2hs`6NWCQ!Uy5qh&4QY zu?OSmrt+PQBDqFS-w>wMdya4|a5%Eu(XpdQ5c>g(twfO{bHi~zUalw_sB^hxOYwmx z@Ke+y(`5qqH;(JhZNL8YYP zIH-aLm;~sV#T_=3NgsS*%HU@rweAme8sBw&z;{Q!>T9`ID~tH=OV}L9RWCD zcJNrWwlOndnvGx!_jgR-UBva{z`Y4Z$4(0QVcee@sGf6wf&d zV!qXXx@GJz1QN!_k;pUw9j+N_$-sG%!+?A#eq^ng{6P+VxJcV$C**6m!>gDd_xmkz z?*u(_y+*dnQ9J85I06G)%fUeIQ z0jmR{jr@R)*g(W}czeVK0?&E_8j&Rbs?wDWLT8Ov9nTMp`D)18n=y-pgW(WjQM1erC#bs-l=;hZC*z-ZDBulmB%cwR{leh>z{8Qu=^jdw>} zAbU6P-A)6KVhK~5^0ME$$9n;ef-gwpnG?>78%1-y2S$#e42jql^8r(20ka! z8jU)`i@x0=E9Y%{CT$4YBWdyekGRAVO`dKqz~DP`az1oNX(>dk4?4!tC~1(5b)92m z+6hWp)$S_70*$A9U1MSt&LeVhlm^M~Mw*1!5q|GOxfirc(i^<~XG$f>W_HqOd<@}m zCA4vTT&`3O(Q~Y%Yow9-cWdR$wWv;NbD+C|#bBL|c`O zkhC)Y9!x8H4x)iK0xnzSGiaK5e~-oygd`U50`Qf1Ybehd2DIGz`jgp$X=eRB7%J{a zPxIVKSKqUA=Jga(eUvhY|2mjm%?2vtsk%PJJC;x@)pf)wc-Ke8Ul$+Fz)5}{&NiW& zbMilrkLz#so5%p{-2*~EVLDmz{N^a6PM10*m2det=ux7j>v0@umQJ1OHNJNKP6zs+ zx-kSOgdqq6W`MKL5RvQbcwMD;QXj^JWnPKRurVWuIYi4fqq5`s!HewZSi z9`r&Hu>yz=7-v`5=KMNMiGzm?cacgVQ?vN|)I$>VC6#!?o1Rh*#C-&g^V^U~yzzuG zWRI?dFo+2(DFDLIP~=G5g4hxjvW2?TN4a^PJx(0io+WHX0N^O!6M!I{q565TfgH2m znZ)PrmR)8k$zvHbyDuJL2Oqv9QeBpIT1xT`Ah)@&M_H} z#V;w?PHy!s6-9EL5a9u3MM9qcF~gQQ9>V19Eu`75?apacCw}%oa%N32a2%yj-tMlzdi}AQu!slp9iegkNllceY zJyfNFX@ETT`3|#)QXyPVh((el#|~7%f;Pj%AtlUz^Vf}Hx<_dOqkY`lc3H^bJtuez z=kv5kxSh+GnI7!6KXE1Gl!=Tsq@^g-_)zJTWv*+I2_ zwM+K1NsaP$we0&XL`ekecsb&smP~9^o%iq*hgq&4jvTVXp+Egc!Nspwdti( zRJIXSX1df`fc8;o;rAe&!eZQ2Fnl1r1%ayd~qNWC_*kL^mnVzvm=Q0mzmbW-}HX#8QC7Pt)gc2q6l_+Yx7VO2+}lMx=Rm?y5q?oE(J(tE|~~g1(CU zQWEMHfN8|S`9{;n>7w{z4i4ec;n|%iQKDZNdsY}nMS%+K>da<%t?iNvR=aw)fI~@B zC`AV}z9_{x1x-}pYS4I3n)1i}6DZ)Q=%NkAsRWEH0%}GbyNL`) z-%@!LXwX-PKV$&)h1iHG&PwqS%{tVT((Hm=F(tfn!BDRQvaHsm+zT{n3P**@K)EN_~MY}BVXYY~=JPuhQ?~xv}8)ZF^CZ}MB(eU@wiF4-9 z-_?_-9HP6#E@%YT-<=EqOddKAkppTcq`J!$1t;nXn6)4^OJYC$i0*`@a)e$QkfGlj z#zW0r9gmd-bm>z$g|R}0ddWjmQr%({c-90FXXwLM(g~2eF^BQcBoW}jq}$L(t*)qX z3e=%VrjGg$D8Zu~kt)1<*;Xk*Et=9OhV6hAn>%9^hsQP&x%i`;-5-V%Ch3hDCEa!> z2!o+ReL?P2@lI7f9_JPu9vwwPdMY4}MH9UMrxq;H#^ce{*$9_mnocP=qSrHW-K<>m z80JAaIDL7fr?9Yd;%;vdkkV3$ge(x!Bk31>1iS*|0{K;{sOC5aGK=f)W{0NfR3)Q1 z()|lk`WnV?lw)0Mb@4k1sl9(4bL7xXz#B*if^DIa%_C3A1|P{=25;tF3&wGXz;37T zB!Na2irgoaT*L$k!Y|FndmucT&EOw|hn~_mO2J6TDiBcXeSPat&Y(gzTygZJ($ra3 zk|;!Bs1=Sz^4x*5$D`saoJ2yp1ZKBoueSX_-{JIfN)DJ1vKdfzmn}ZNR?~ za+zV)XwXBQ#oi?cVzKg69;fVCtmI5x0is+b;gnw7vOzIS8Jxg6m{m55O?G^r$UyZV z_9v1SQ;nf^*$myoY39sfK%vXF+5s`&7bw15LPb4nlxy3bzFn*qK%|wvCxz(_2o#Hf zVa5p2$CX~G_jLC#96{kLq+zb=7^?@v~{T!hMEl}4FU z6+w8R$C4>K_K5LQajS9`n%XJw&ibz)5XyPm{hwtC)jL-_XeADgM++jzJ|I&Y(}c|%5VTQqF^7BhhEI59#Ezc_Nkg%7)geSibXKR z)>J1)9gy(`)M%iX5gz7C#!=hJ_ykQ+I?9Pmr`i*UgwKsBMA!^egDjyziVwLR27A)x zcFZ-{!_*0rpIZ&&9E!nF1a2txAXG@eC8wIU4zx()(bT(yaWqkzo8r`~&xu1%l8~$* zb{RS-DG}$63(_bSps53jT`#t>QyM!AhN{jwpKVP}6&k-A*K-uy)gXH`u24jV@Qx_O z)MJ{{>yq?H9gh_Rt?zjc$kkbC(Ak}LLlAmSiU9IQnsgiAK*J!q$g2~DCP}_zIvtax zfK%E?u7n?DH=0BOJX>~C@pFTM--AI)kclU8jnRh0PIiH3@C}0r>!`PKz*FypG)i5# zhvR5p-=G-AL%OW~c7kA9%ivX+L&0U~epPaR4X z-PLi}Qae-^5wNAwhz10;EhjX{Gt5@1Q^>S~S1dS49gM7~SKLT8wX0z*lJ>h3IZnom zO8Axhm$gh@$+ZZSrBQo3|3RZJ)e~xYlY5J3!-JR-Od~7SXMz&TzyhZCi`fl$k8phQg&$_~XP0VVdJnW8=z zo1fV|oQy|P47rm$7kh^7d7^8xBVeEjBNUWi7$_vT^zl3VUx>AcqB)*5R$8p^WT0@i zGTMF2Em9yQ7CwoL;g=r{Dc)k(G06w%x~InOQ<=3KmK?^S>4Mdiz}5iprBTW81sco@ zCGu)WgkCp(4Pi4eJgHk{ zps$2sBx)tf3<4#W^rIKYGX?ATitu$)826%V{%4|)4B}NROo@{-x+D@& z1`thxydK5rs7^*)=Fkh@qWWZrfOVeDKO?UaVHHe!e=u_wHJxg;UOqU3;Rt;My3pWZ z#uyGUdW?#BM88g;5*LM0wNHuG;jKhn7s3$}pc24-3=237WKADix^l-1E$aKDWZ4@` zem%}5qalgk^B-pKApd-A;?fn5pRsMPPfjT@Bf}fn!4{Ht(>RlIH)x%vs-cWq>Lwhz z(g?u#k=Mtj)R*7}Mxi8&MmGH|S&!KDgj5*KbH&qLRtuOnlf)W+*j9if2O8O}(v18` zrv1)%HROq!)qgq|mF~%9rE`f=E|qB#sps|k+{J_#B}`wx^rX^$4;EtN4^B~_NS@}W zFA&&y%$`y>0RgbYv{37?6hxssj4pg14(UyT|Mr8_D^S$^`rwo%4SKPoe1+vM50C~b zGq#orZ5o3pWAY6G4-q2;aOPj1OuNiR%>l-3N5;KHgefCF6SXwF4pU7LAWr)lA+*g` z=%)%!({BQsvaZ)hX^frlWH6JWsH=stJpFVYW}nhVqnt6bpco*c^E5pE^jXTg(>U_< z*(p+tdcP=a^oGJosrTPWr8ZEaM3#Tw0)l1VECF=oNh~#Tmw>;y@hdE)(yvxynd7*R zHhk{-pdmQ@PzXC1Dr32V{Ja_vHchBk~<&iNI)#S^$o?y0R5#No>0h; zJg?#h)~(eNvBjTC&uH=x9aqbIhy7pBx3U_w8cHlA+M2c}KcTb-Bea)a8N};EI-UIq zaw8Uz{bNRnmXPd^Nq+6{JUKKqY8VC!CrpxRx`;o@lFd2HJ6KJK4*Pb56LKP36$p> z-tRu2t{LFREBY3`c#F^a%91d{NUhLM$FGp@g>K_bC!g~Z^}Mg@qF&hP*hf8`-{Yva z)>7i4yq}VIpDwBk9ijKSq54Mmy7|vfFTnPhx4#4~9JbsG&SR!El-NqQtk4|+)kV0l zVO29Hwu-=Gs;vQHxvo%c-p8#-a=xGk5dq4;=9)PaqjqiiFU7x^^K$?{_0B&h-NJ;i@;%{KL)cIW2vWrx?1hDaKaKJieJPi=mKg zEBj@nh=KR3$xR<$;XiUXkz!hr&*G znl8MF>?{%1b>-VdgbcU1i=KBwJz^xZR}=Q5tSS+G zIN65neBtl``d2m8KN$--S^W9?WgEA|1RXWD;T zEA>l;E)eF6=>ilMSy+qp1N*qr!sDJjC&pAu*I3+57e=;P5H4RZ1(P~L>b$5ub6aMltB;-wCN+|1Cx4eCgd0p67xVss=WVCaG%keZO=7{c zkmdBH*4z?~S_6c;AL-N1>hug`yvYzyd!`M0bc2$JWu8iQC>RW}63P4k1KTVh^QW(m ze|S^oXY)68$PL!dhD8C}0!(n#?mEe_-A`C(?&nwkGOPCT3wjVyc@$VuZ(8Z^qfmjF zHyRQ}82~xY^Ab`v0&?k$WxfGz!%TCc`k&QHoA@VR#KcC@YU`iAy6YF8Ci}#+OXMe3 zeo+rb#{32LZxcp(8!1V9sVB6)=+}XfsBMNrsT(smU%$Bj2_Q)tP!dy@BkUJn#EAYv zta-xAG-vQ+*js`@osPk33z{}4j!@H|Ow#nblt57_q%Cm>4N^xZ!>3eXr5!VbwCQAH zqjUZyV7_jPcy^vno>~z!-G*`nIz^~Q?h`KHq>Z$Wvx%C^D_RctNL3R*M$N<)FM6V% z5_pF%I#^Z>Bkk45`U`3MRMje@56PnOKofT|Q^5p8vZ~Ok4`eM>Ulij(ra!GWFHBdmxk*lEs<-*;h^mo-K1x_Fj98Y^)7vk%h?tJ{1C)MG3$LV!}NC;(`9vG z)Vry3t8`_yG&3D3hSiis$|}hBNXGb7Rc&jU~*#vTYZckj%{O<^xZdDTq z8bKO9>k_iB%X(Yt9#{0?j6D(r)YkTC#_7>u!?8w^A+lS=EOi#rN_{B94TL*tn!~L+ zV9#pM-Sw3=C_jj@-MiEmSyKLhm_;E+y2O&woDHKSQ@{gh&&D_;t4rK>X^q8~YiXJP zhiFMzZlFypOkXq>@+ZkgbG-kzJ~WB-KAgrllSP*h`8WfD`d8*t)O+TAkCQ@*IzefO ze#chNu%G6fXk;BGZE7vT&S7d7k2c3O<&d$-)i9~|G0in#VhL-hnYuuvF?n+NgIx&X zrm(lE%Gunbm zv$`Jw`G^++1C(qNVokNF--`$Ty=1zfd7U@C8!-h+X@4A$uua#I<6+2 zJWjGORP{~>K(ev{SSH@KL6C0iy4K-a>fM6Fn3!%G$ci^6*$D3jOw+DOh`){`*%zsi z_>~@}y-sqI=gFSz?SO+(Oxl_lm+H5 zuPZI%%a*t3Fsu9QmF$V54GeQn4X+8va8cUV__$|$kHoLq1ux6#M@dv1_i}OC+#fL<+141Fb zHjj*6)pwx>r@`Y(=fJ{dV8!~2jI&Os>?`x@m}Ni&hWa2I7yI;GsybmFPHu@}-$(un zoUiIa%KW;(2;NHmPiOmplWY=0qS$}I)EN@`@1hyq!hzpevrSyl3z2taogpQ0QoxL+ z;;^J12TY_oP+G9L^v8J(VJ?K+BKS=8L@V#R`e;SutuFc-Q893z>IzmsYmzc!d*7)1 zPR|N2kAu2Kxyu!lf4CQ^K7)F_lr~x=-gL;`M=FXH8cFrxbT3%m1;536`-7asf}#1l zQfmQ_<Vx;)DI*PiJJYF$L zHvO+n;C`or_J5kuGQ$FwZvAz9jm9Xyst1WG8UvH|UGB%VrgCadB7-4m*Q{*u9(SgI z^Ru?*rumyP#i;(<{I$K6o0RFd*Zk?|tA#{Hf?eP5Yv9F^v#IQJnK`DfX&bDOBi>5{Qj!qnle)7%etVl z$|ZpME@Bj6@3xGdrJf4V%q{THRL-~Vi`X4ltKLACXlo>+cnyFakhazB!{ofe2}f1-(^k{`1@o4 zrla?m<_A3G!piRh%9@8d6Rtq#obE@=C%B>aacQ({9T)ohokZ-Spk>0+e@Peh$?_N` z7=xGVz*d4uCNy(XKD2YX4Z%9U%;EDs-VBF=7^uyJ$n3OQiWBar4;Df3It2}DQl3qI zo4K!))HAJHVv$Y@X8p0+h2$(Qa(3P+QhE1!Ns<~iWjhT8aaX<|9(`2Z0JokO;CTy}O*{&44tskx>9R!))oJNO=Y{;Vc+z zGOE+%2Vv9+(~imco-W2?^~wN1LT2K<3mee1oQT$2nyfBMXFMjKvB3MDK8%;hT&xkXjxj%tPwXg5Soh=O`hjP~eEoo26**By;&9RiRw*jzAkkth zwFVuPxYsNG5lI2>1ZLHnI{X!MH!4zgOwB}M5&gBuF~YFghR7c=3Njz2ifH#eDab9k zcVR3zWna{m(o~)>IbYMoe$)zm3E-aj+A;kA>#>M8fU&aPx5>nWe{BdLLr){^Wl?oM z0x4{uGOXvSnqJw*-B?}sdX>J67-qiE>-u4cTkh*b^&_+j>oK>q#m^{3y*l+o1k(nNB2W;JXr?u z(y^N`h$|UzsbY*nF?a@RHT5-UfC;S}H)_e)T$l>hX{)GVyR+$u&0e zNq6!Uh|F8m zyj>5^%9d2=z>uO2Q%vY~23@+MZ6@xks1~M>EY&=4 zg%po?Qoi5L4#)4g5vV6t&Ng3`o6jK~D!5sk_&iD02*aN05a`EbffoOukd*oYoS_S2 z9Vu;|Wri^~azL2)=3zuQrl)O%$t~wI$;OfpBb0=PK(u6ul?-}6n(NjoE0YYjNAqpN zD!%+J#w%ZJ)$ag|3o=)+qN6#|&NAn+DfXlDn!jW#b;+Si5PgY1!};HD$&!v{go1A# zhV-+-muiEA?<=z98cx;>@%3qid`X^i*~c*SlcRPfeHhK+C399G_qz0X{tkybzoF7G z%twSvGEMp{F~Qr}bH1@Ug?89fb=kRwXq&IS<>|4C>cLQSBA`rNb)x#a3k#!OEoFv5Zz9(XYEM=`auC)ta1Y0%Y3n6xx(z-c6`Y5 zJyUhk4(N`nVKwKgBx8_t?Eeg`&6P8CsuJ2>)K$sm1N+L8yM@WpEwCLgWsmboCn^mj zx2N*Cr@*(%!qRZIFLGzd6Izr4MYn=W=Q2UaB<6~=O_grxOSbXC6izEbGE<-t9BqGV zCQ|gu+U&z1RcQR-E|ikVw$C3;!N!#5c5H|Mwq7V~^5CDOv66b)hUb*EiNNU#nB0nI z!aVRi6sHJ-PQgZ_MLRZ+Zbe=rg0`dErzFG_bl3-t==9gwlVvBT4_^9~?TdRw=!+c7 z6nJ5d-^de>r?z~V=gNN$@#)Ar?#6NEH^0M~VQBGY zIunf~@v8bSe(y6peF<9^_>V^UoNxK%QrAgw9hLxD>GOF~u!s>j!K*XanDo!|J&4UT z6ms25mYXOmjX{(El5pjZVsMWKTPVQKHjpzF1?h$^X|e@FGI23)%ary}yNlMXK+Rcn zY?VRlQ^QE)a!GPih493tCv-<IzoUTv*Lb0vfR?Y*a>4o&sOonKwyE!IYc` zA-X^pgxJ`{fmk8{Nr3`e6GFOC22q03Dp_qJ;Qy2`pOa1I_5*Qg!Fg;+!r-Bu=QLkX z(R6GGWAfYzzPzx9;7)-9Lqaj-nA0$ac=0Ygh`WZ@J&}TdV5NbQ`%EfjoL@-2ok+># zCOM+%4HP-5*kw))#{=11*L82=Wo5UOb<`v9WctvhZ?R%Gi`cKg3r7|1;2EyMqZGV8 z-c0(==kafF=L1&gA)u8DC+cM-^tz-=LRgC5uLu_cHO;~$oy&;57rY+D@B!Ud^a4#1 zf&Wuu&wCOJ%o^&@=pVTgTR_vQ=IV6PizCt{JFi{lnDFf+aB`)-VvsRaB`{g+poh{< zWFjqD7Wr(X1$|~u{f_hr3T8m`rL0h8jI0V#~h`#48SHsF(Mw$;8v()^OVwe>`XAK{qnYS ziH(9|8%-R(6~2XAkSk4e^hrs^Xe$X&VeE$ZEyryuELCAz+M_X%C0T;{N5*paX$-HxS_ zxwz~4>}AVj*A;?y4z_1xP+vsZHGZox1% ztb!|VC}%wPA;c-zLR)i-jg87gdQZ&f(Zcduj!N%SaS=9R+axtrFY~<8xSg!%ePnwI zv~UgD7Me%4GE)^{+i`XRS0rAhfD5~NS8)34cIR3GEc;AH6D1=s$Zf|*gw9d zkORn?`mdD5mO!5X`R4s7f!d=6A2`l4f46W%upPfuEc#J6VU)lQdDi6c_ly(fy`)6M zjbaSK|F1PINpI2ru>H}GBgiR)+I%5BN*TYbkM$RW5jqEoZcT|X6S;;{B-)RE+dyNhqGtjvnf%2u|mOB0o!Rf*M;&+^Ha9ifb?R zp5d;icj#Xv;^?pO`&tvkABu|#*4q8376dd6{V%>K@#y9+eSK38Ej80NP+l!>5Ab_V zOHAAP`gSk(_4+oiyqim@^NjrHbux1L`!p$tX$7xeN!)#6Qkqj(!Hg@*h@1QQqG`Yz zXHz^}a;eMjojl1{;wT($RvPSIQ+i?-B-#2F8SI?j9rXvyYta;CHkdKbY=yM&Ys&-9 z9O-;h7fWihS>62jL5wFB9W%gys1$+C=k4$&+sDN{pBP{mV^}}BV*GqImyn-9zT`zK zZ{n<#Jkdu<<_|PdvT`^VrgydJc7OJ3>}JxiNa)GBzE2_dUt>OAQE{4SkDc>U>cb zA+a+93r;bWHG+vOr#tOx`db)hk#ulPSVIf=jRb6D` zYXfU@>xds@l5I?toZ9}NlD%iY5tM`0T_4J@X2GCzjkHp@C5igc@YJ7nTo*jh1&ORw zYmhaav)SQWnXv~zRvFG+^kE7UZL5PY<#7GnI7gq+Q59(I6=(Vj+n>rxyiAZrw`UUd z!m`REq9&^_{f&wcFbzvR;SXBOQVc@lJa4!I>}yk_ZYqSKvvF1B{L90xh+%3gqnQZ| zFrsWEl@0szfYu|H3{j9se~XXvHp5!4sRcCh9R*S-I<0!h6O*FR>}&99|I?6 z5WHwx2AEJPEx_a8LhC~eyCEIzaax$mzP^*Hh0~=o8;d4LihU_MOQ)*R?S3Q@i0h|~ zERSn~p}_#e2ic?y*(e^K11+qF4WZGcNU(n>U-XqRH2G-Jw(bEcqjBm5V$*C8i>aZC*~g$n7HEgWdnt#IT|`y zaKZ#PD!!+n!-@~&x$5!&PJ7A1qhqH!n|#26}HWBx&wT5~40rh<31j znhy{oC9IUbI*+|4AO=z8H5hzU$cT`p) zlUr>Q0kfhYzZO>()CCF>5rQcoM{g=coMH&?W&o{!7N_DO`Pr+wfh&aj< zb5(HKfp>!+=^<2u|3`^53{G0N>VI3pl@i=Fo2uA63vQ=Ogm+j_QnC~<<=gh+?{i+9 zwJY;1gU?Dp-(h%i8T8`b&?w;~{py5^z`-)xJIdH-%g4}!Sits8rPgHJA zubiVCXUZ^P@HQ;D^c^<6i!|r9(PS3cN?-8pk-z!rCpp#jF8@trU{D?sO6}K1wSYm|+}a z^DJ&D74C>Rx{S}KFEAUWqmqPFd!PbVd(vm8JNf!%b5dX7S)_#jW%HsRqn>ZQt<$;(;JrIdZptmsrwMOEqMUZgkcDFwL0m6udSQq10Hf zQ))CNQc2uK?@jH*>`owrb7I(ecDg=dlXrW$-k6rf(5v&Ap7<2zWYZAU>5NKOb@^dV zFhQfy0&FOUw{xSAsn!t?9XS(9{1If-JZerq6@G;40Hp6AwxuN#P>T28AYZQTxlVjES#g|C*r&M3wK1 zoug4+qh4pgBW4!CGo;hVJUTy6NcjHAD}@FMyQ04@?741WN?1}cNW!nso;7yD!Qy)s z&S?bQh3;w+j8m|&{k_hXZ;MN$!_>o!fq|G}vc%coQU;R{89QB$1S+#7 zSVf2AV9eQ*K2=dLkq)Dc!XC|9CnvyM<2j^zMA6q(dkdT=4Z3Azqre>|+#^y1tA-P_ zMiE}68eSC=10GJ3AwNIcVQAqp7X!_ga-Jjz(CtN%CvOL_5eA9^=9VK%G2qJYDl$)( zC?APUiJYX`l$^ti=f;H0Fb=f30!dOfih(M+R&hH_xl=Un*HBIaN1x1>WU?zXmjL$- zi#oQ#!qJwgjj)|Vwy;X*ZJQLLBn{#0vMBWxMo6Y~$7~hkr{=IW(a28(!ir; z*<=-CkpP$k6}4U$GQ)GY5eu$vZW(0S=Bt&rSc3}W=?K_^9E-I6L!CB=B!2I+p{ze7 z5XR-O*Z0H(R?4~c3C%>-m`HNV%ofb4lTkN->Vl}P&pb7&+VZ?xPb<~vW~D!MVd;vD z6Ob3Vje{d?7Eo?=0=VFv0iQUk%L~wVZ2br#wF#T2`bVX|)-Bhut>U>E~p=N=Qe%xe}m;&5=c}m>otI z);eve)-C{Q*l;kFlmvi#Y5P5VSUpknZc9M##b}2%eu-*B zm43_qWQ{qkR7wFZO69b8?Llma2HO+O7Tm(HRl;b52wY^9oY?bmA`;9JdXkIOE2V?g z&>6|JWPYJL-$C8${mGQDY;cc0Jyt6RLggKsnyO@b?_jp%3cs?j4-egE8TR6)^G5T#U`4i7P>7 z6=^erTVi|)U$$2}@z*)eh1Wuylo0v>H%DtxbgCLty3}_c?kHOl@`wcH8VC~M8u_UP zu9f)1(8ycVd2(xe?Pa(~3>lQ#18Zw;Mm3AoB~7+f64TTK-4k7Z5ey%SgU zS()jJjI~Of?2FtPc6`6hOr2scT++#`T*&*aK5GSiWcU2OiZEUlzVc{7Xkw03F)#MY znQA)nkSDG13QWy}(D<&)hQte zmTmPF1aD{NFJ4TSvyi^VmNH~gd75UJd<^JrR1q1TQ$ONfd_X^=YAUxhj4#{+WuBi^ z&WjB2?md8KLN$y0bT!Q|zOedhHP1x94#{3c_(7R|CDuYpDqv9q(T0=L%kd>&6=1t2 z9j0Ko%gb=66H#U|RH?Y?=sYdzYnfqq1oi6z#!$}&l^4a#vLq6cbR0d21X8_L_iM%H zty*RnT^I*sQQoFNkwoc{MN6uXOq&HM@HfO|@-sek7Oue7vvPh?jSAIiG?h#xkNvR6Q9o zp8X`sO$k{L4murJ0Nm1T41B^*Og}j*I!YIRB0Gs{idQcxHa@XpGhfswlajw~wn26G z=46YBP0X|hVIr5gsKxL24#2QHY?U!xyj7K<|8gwK;D~@l4Lp|gGR5G4N?2OD-8=t? z?Gp$1k9d?fY4Huj%c}i8@f7=InbuI?~vYW3#;kxsPu^b5NGNKg` zb)nrpea|q!V{@5+#EX4=Rk84qg6VtqTwutzs+nPQ2)w%Vd~1hvEF;%R5OK%5f~vf0 z@3VHu=!^o)mHwKtaZZb%weesPsKWqR(%1@6y4ybY?!g4he-c5g511-&<{SgJp$1fg_n3OJ42snf1OwOf2k zb42~=S^X&}-+{+`lR7-37CfG^rHoB4&wP#dfL{zg`ttDl0;^?(R|-xskbN;Pflw#i zUTV73A4e9cgiz-(JC~$5?N{2I%ly>zUaHV`&o0}oynY5!5yHEZIh>QB#ZwzFRxHh4 zQtl%#$x7$7c_L|;XheqFUmKZcT5=R_r7)IJPzM<$N2=;o4{>FhkV?n%=|7k$l9cMQ zrs)fhmyYpN$;ww~mmk^d$K|@X8RN(z_rS1Y+o5VC!|??N9tEQ%sfJ71?MzoZUG-qo zTI+N*!?+mBUZ>dGHc7YLbgGZQB!paKbb8asq>aXe-RB?+*Q2i#`*^C7j{;;4FV3gg zgY-t7W=81yFQomErQ5MjHEE77yfOwW1oFeu%${mdv}}T7;up^cV=E7X`fNvLY?x*b znwe>!BuYrT;Ri7^`qr3r7?{Z`Iz1EZ>v|t6%f=39=_`zYC1Ua|WMQx8ip;z5bgB+$ z={vBa)d-24*Y?y*GZmWAmqiCD3@}BC5M~MtEHm8rxO9ooMk_y=o?{|Hfw?a<%jXD- zZ9cd738QSM09;*M7zoS)L><$YLJJm^dpVCvzY7}{mK7e06u|Vm2!SJ=SlTQ>RE3 zLNv9;!rQY{vVeH*xYhiJ8Un`iHQ?Jbc=`xSNi|({`IVi*=}R0Iu;AtloY3Hkz<3P7S=MBZME&7?Ku3~m zK4)T|HVYHZMKw9{Ag4Sv5Ldg*ARVRZ(THX~e9D3-875SKD@n3^c+Lbp1&o?al8t24 zzozlND;gYtI*Ig=d>89_hFoc)()KqnCaI?H8GT^dkk{UyiS>o$^uZL+ zd3|t+kB<@t9oi)!HpkiGSmvC6emqIK6#TYF_4=AoRLYyy#e=HAU$roB4Xa<&=iQM4}ts0gaXnG&iR&(B@j%@ z3MJqgbK_XdQXq0m&X!59)W)WS7*buETgW1imXHq;N_EZUBG$`FpdY%Q!a54HP55(vUdS6f8+4!v1PH;Kv3V7*T<` z_NuLGBirt=n9oHVk%S8aVdH`<9uwm{7<`L?bJpUagiMiv`;}}2n65MQG1$VWl%bh- zEDQ|d1+>Ajh^2uQnN-XCG%Re5#baY*f>z#+BZ<168BZh-kmi}Wr&56fGEy749RMVBwXQ8#wmh3hahgh&Up-F+{4gi>8siDskzgirGYO%80sU7_W> zeQBgp32I!losMXd+Em3%gsaKhiHcO^hIHd`X^11^REe`{a!LLUg0XB@p%|IS{ZjTb zOtP;=V#afR`2qr8{|$?#b<6EF)Q8|1lOOcivPeWBdo;{aSMNJE&NN+XS)N>jNAx}w&PY^UJQrc9(o9EQtftpaln zMO_3X0+dGJ$i&VH@%77%x#MJFkuYDQo0+R$`3b*x$}5E0Rd%4b_@h%@aFQ&82`F_8~T55{MK)u_aT{ zd*ykvH(zDN5|?u`!??Q2O1bL-7cnP-pS*l*zZT_;6-7A?`UTC9W<{dNoU0iI)?QUA z{X?o8Po8%Pmb3|lQ>oFII$*TgQdM3hSCdp7M%5L&cdoiuEjxz zR@-V9QSvje(D6D52NDQWd3vbCmyiR+aNPZow_O_LV^+B!{K5U zC_jzQyjUGKstPqDU(GuBb8~=&wWV8v`R8InByJT+Nv!i0Y+`BH_Y93Nu9C_?o9^#t zlw?$72SHM!#+bc9cmne$B{7$WhN-XhT~LipWDQh7KUx$Hp#qD|e#btM@XjjV@6d#7w6}Ts-3L&msg;H24nSf@~1TU1^g&0lx zy}C)I(lqu_P$EXp0nvo)xe$C)p(%1vnT;%ghOu>p?%U5*<3;sS5jRylk!WHz7!`6* zRTZj!@mYtFg`s<+%e+HTeyRZIodFm$PG#$%3M?7H8uzc6_zN(t17SrhWYmh$B!Y&a zg$-m|!H5m7A#Vf+@uOZEHsx%QYv?reR45qnGU+o@uP}b+HTCBnX&5fAXBgU}X95}a zA*vOtQGKMmuq3c45mo6T$x)Cso<>;29N8#l2a#bC^#t;zkjT%{2~Cm# z6EZ>T*44hocW6Hht}B|)j%4Ju@?~UQ$t@>z=s8Br&_Ik2qN=@^a9j?zM1cgNRE@2= zBdmSY0RixoXq;2yr*-8)kjFf@=5tk50R83!%gNJoPsE)wI0oxrfnpaBW1XY8*~E)g zP))>G_2!)mpGYO6*#5}S24_vlKP|SxK*pQOg{F{>C8L-+Fa?O0#{Xf)3|oi|=?JH3 zwI9U})Z}K93l2pI5KW-#p6ZmCEnRHh4Gm)pHw$guHJYh$hVf^Rl++Yti6W};RtR82 zz?L`HctPXPqU@k08x^CfVTPNqi$x_uwANJ#~SQa;EoaC5q}gJ z@tZ&kY@ZvmA&C`gOg43HgcFkIC65wv;v!J(9akC9ZOCgSdPKY*iJw#eI+MH;k!PMO z?>JF@7+F`Szx7l#?M9pq(-V(|Bg0Z4lztL^(smNcegdNw5 z8QKl%fztA!OO$hQq_iQ2tIeIt)`y?tE2o8#$u8rgu)EaMs17QxTrR zk(0ShHD)8Un?kA78<5LS-{D=)FfwJes>sYsqmPQ1HpQnjOXnI{TpLQw@KlKbV*NPPCBb?%wXg3>vJXS+iuGdwt0X{b zi{6SH>pv(r%S0Rv>mq#}8zDSSguAj{tPs#zd(j@jigiO^8b!%igeiiN(L{CeVfeA} zR8@W?GlQ3i-@ud_x$Oy=CbKcSjmV^izsx|U+p8n9`pi2P)-VM*!~k#ymdeFIh%kUc zqxt2O%a&QNG0KdPhH_bytj<9fjtnw%BZqLnbB*ix%r#2)WX%gCVT`*(|wf6~x8H zB_%G>lCQy#raOz7g(`i@?Q1HxPFZ9O8|4({NJw(E9Sqrcs+x$@@H|qGxCkWGVCv<5 z_#GnbOcb5vsmT+mBQu)KKbGub((S~z+OnerzqIe0332$-l)*?G!F{N3IDt-BRYy*t zn--?m(OE&F#5xo?@a@AP`7zVFnKrFOFEncNuEMbmyl}RXtPz+tI<{bhTj~sqP!4Xxx zYa#=Zr9rE;-pw$uYc!n9u%d=c5dNTkNfDd;Kq#=Ike?Jg5sd~*q*=laL+gt5Q;${9 ztV>sa(Dx4AhkY(S1)y@RP&2C>bXp<kQhu{~<*%l9!SV-Ib3`1kWZwEArkKiOCSEN!D z!$trgU$NJDH|Vo8jvydfn}i+4)fM2!>nusutExS9?~r{MSyzCcI$B~+iqcTCm={M$ z8R1tmkX`Y$99*kO5JFeVypU{^(ogvp;-46=yk1Qdd5MLs%b!K&C0Aey{Pgbw3+d8}ZA zmM7KZDX=;P8wJFH8)I}Dh66~nxRK$KXhX>m%q3D9)WTEJjwDIPs$-+Ah3+CUA1L|k zAQ0Ir?q`%Ewe_Sf9F0y>2t)mzDppkwM}mfrrd1lS*b?cj0&BgUVPq6S)sb1EAwUrO z^oKB$Az68=AJRZD zT6RglP&%hkoqD9IFC&&kz=thcG(RNyGYqUNxUY#v4Tq}HD|I9&%|Yxn_ag&LQ7djL zHK@#i6^8YVCUXv@L4HVTh7}?$bNy=FVoWonDBxld7Dh;Vr2qrkg~SJLTTbtf*Mw;1 zU61V0)ENqHp^0*WN!sI@DY8QeWU7TvH(sTgCN>fsmYcdrQTKXAnGusQ5cgX}hDFbA zMiPU}O=7}ELPixWJ#(tOB81w|tAJ8yyPk1qQGReM7?Jh3(u8=_515f@wI0z6im<5- zZW!^>dOO3w2wHcrqrb%4|UleL5C#%X2Jc z7+Y6N-ys^|587bJed;6)L!vxQ?-70&SXWG6Q&1@%))DY6y;ecpA38~Y;qVxwdRxQc zI4|&GYE{rIhe_DN$i7u;-nqDb;ydW2)I!tXS7WOJ1Yc9Vs5w#$^~)O?X3B6twh@uM zDEgaV9umy?dP${GO2IKT^d#H^hDAk!91B{d|8!0zUzM4-V>Bxg%S|HOobz2qxp5pgtKTNi+06*DVqE%=yMhHocvmcadidvy+hFjMBGZdrm&3TP>9N_`AI4{sfu5(<_o~W z(7x4a&ao8dMKh}HSXDl;3?YtAniOA5B?-@@n^AD({R|T=oRDo~2-9d(B8_WINq6=j z;Vf!YQsNIwC0h~IcLsq8h^UR5$;gSHz1tZEhM(J^(r9L(pbzs81AVD&k=`ZtfK#a; zYpSRS{OiWs8HW~S2o251;A&X6DyOM;NxVl-C;E+2!4%P6DxRxEYrUUgY}8=a$!4%I zR1LXEbBs)^Bni8PqbFYp@4?Ur-qiYS9G7Y zvGP=u$`R>TFcCrCAo$4!0tCB^pksDgy~`N}7KZn&N^?%7l2ygq6!oD)Fji@4DjzNp z839dZN|K+XYH>Zo*f>*%2*IZ#giWWl2C!%QN?jmwmGLDJoiQ?%mf+Ll_9&2fFQi)@Un?Q+I}Md?8!8_5BZSOyg|$_ZTT zf8=!qlKD2eQSx?-&=^gZdSdIRDH=ti~uCbADB z>kINbG!qr~TDFd?RQ4X-N0Fgb0uyBW%%B;DBCWY9yUp_=2!PZ4L-YzRrC2)OcMTci zFVu4kuTU77Jv6>U!vi=9NjgGCQ)s5RQx7*fr@}R3cmoktjT3ALgcF@4?5HU}WSR2A zbgyTaXkn1wDm3q0Wai0#5;UM9A_v>*Znc7YajIkf+77PIDcoao1iyn!pk?=X%DGMag*k)NofI4qFeBu1%+6 zgbyy8!Ul}($${-U)f%s77#gh5@z!XxQ#*pD=M$;V$dD-1+^Xo5l%amB3Jepi?RJKd zb*;c8C5VB@G91}Q*-Uh0TU|buGM2dwnEF&JP$`71oUUgWSyy}?vv*H3o?WSF17v%R zuORB4?!&;k;`^HTq*6x}OyiL0YRRK1kxj;zd`3%gh-Ma(l0iO_!N?P^Fh2-eYWO)u z$g2-=99d6z-#ZnRn<|q=K@mjOc(mxDAz-N+Op8Dmr}6oE2B9%nJqqvdR9bN?oJjgW ziHs8@q2WEQbtE-K`3zZWM0)pvhQWpNw6{8q;E4uLDtXR04V~&n%#jc&+CaVT z4a0C1b5Prf(s5YA`8%BJ83u-#Q=1sJK3JesPu?<}xE+o9<>9nB-Y=gEf`I)HpJ#hL#wrzS9fw z1Y1?=djgj7D?L|g=}2ZLq7MV>itXcd?kVQ!*gCFK*LzeS2G$kZryv9gL9>X$bCftH zlHrz+UeVYg^<2e{3?_`6RcfQL`tw#r$b`R!B%*$w_T)5gW4L&Zr{5FY_m4%)JL)ZAQEpljaG zLjCfFM!~VOydxREqg!H0#n!{A7U)J3FKYUaUZh7z^N zui?s|#ks1;%4)u$VQkbx)UjE;h6$lgWS%JvL5XlwKd3z!9~7(P(gLmVeuklSZN^kR z*dCfE;cBwPm9g}iSn0LttQyWU{`m7Jhc|tU)cQq?F>T; z!~8qVR=8?%`PE^d0jnBE8Oq0gVVLVQqTGy`W*bg`xhPUMsVGnt)4QlNuQEh3DnYYfOoQw@s@hBDps-3XV8S z;M5oyS>|Y|(xFvStBo`d3J#Ba8YD)M4R!Bl7#fClT}B$kR;I93SWDm-FNb2>*V4Kg z)tnTzdp+aGB1vM1RwkbqMnLc}E%&4+k3qj7)tn5!dp*O@@Q&+5v(QZTDLL7$e5+Hf z%o(a@8`Vz}txBSn^73J9ec}Eh6zMA5Dza9}4e+VjGh!Yry8zKT?k2+|V#O>gn4BiBq*o;ukXsdy6EnIs{|7wO-IDGzvX} zDC<_SIhDpd9c^ggrO_EmG%|)(7WKNc6HTx2A!G=oBFvn-9_o=DK|ktD&>Pcq8-L_sMZzoC%ao5OY<`@9`9;= zQg?a$)J)e?O4WGRGfc8D;%^mO*{VjtI6cZ({nWG)J#KKcomMsa6`lJT1{coM-ipYw z!H_~hlEBo|5@jV*(~>-Fyq{rYlz-GUwoz-QWhohqKLD+03e|VeQo}L>+&%&jUNe4GM$ z4J@KxO#@1%C^lY64?{Y~B5*|K2{oRSvdXpzLt4dv3ioz~i53R^tzL7+iZJn!(r=6j z1|Sf$%k4FFve~&JNzf86DKBUkT{v3Xyf$YbjJ5}myVpM`h|e`Vb!^QyGz^Yo)rF*a zZ_XqiP_YM{?ji%|MKf!{nMX+{^|F8c@i!E_{*<9{oX(;CSCfn ztx7XT%<{_MWU6Ku-mS{fIaKQl{g-32e05vJ)=K(OA)+}Lb+T>W8bl_GXorYXUqQvb zsv-%JtIIp`ZYb*A3|Y_J9z@;=NiuPUQW+XSmZGn5a6RFF?_5%@xb14MA;*XYkI`XH zONr#^@A`4~f`*}m(SM`ZP|L+G0S3)doJ^0NEM%JaVk?M!j(oOEN<+#^ew~a`qBWU`gS#Mm2fWcQ2|tJ zGp>nQA4{HO7+O~zz}aoYxCW+|GHnBkiAgvtUWpSp6qBGS)$F})$HI(c%pcPTm==_N zdrq(f7ruuty>rQNgMK_-a*F(G%$J0WU_L(gTHE#Mjz)<`$3h@0t)8>%*7CEX1Cvrv zB9&U-qG>JRvx7XEQ@35Xmb}~Il7``Npbnv8*W@MZR+ZSD=-fL}VG0pk%rL5WNu249 zhS8}fty$3_FZbIGHF>T)R!yqxHVH0Q#L^o|II( z^Dc;8ZiFbYnc4I3nm#s6x4w0oWH#(Zxet=AimhBJN3Mi@4%+lUZ8?ooO8|ZtTvuMe z)#I)PuA-y5a8G@;qcZTDC_Lb1Ve3i@5Uo=`Gp-vUMcVa$CufD(xYBb>F{Y}LL68lG zGl^uB5G^}tsd4%it;|(~Syk$4PMs4N!injTmiAl;oCbj5oM9VkPfuLTh4r}EwyfQV zl}j4t%rH4%b)B=on>V8|!U%EN-ZZG{82jUPS2isi5|8L}=c+~#vW_Ou=0;``ytTX6 z6FeG(&NOtWX@!|pu`>6siGVI~bOm*p;5BKj5_K?9hJWkXIqQ=F=pL*pT)b<74;bJ= zb3UDqjHaLS{xA-@Oig491~d7kWy3V++;dgYY2X?L4ql?vTmnMHiY5;*6Ha|gG_Foj z=;DLAwPKhv?VDT|gIAf1RZIXshX9PXA=e)8n*B?x`Fx*6b_|Al6Gc4FN(;yZwAk!-^ry9vIa}jEK7> ziGjC{1;dn>bTqC1=D)~2N+nso6DtR;MPPEW{=e3dAOO-Axi>Y2k+K)f)vbC%Tlu2( zqnw8cV`vrTT!YR9jhi_{7d5LQK};A0QYfDaRcc1zjo>=9ZC}m!@97+n9!Q3=N_zz&$%RCB4e7N zKi(wOATyjLJNJLHr#N~py(g0X3|LLT8V;xvfGNtLty z0$-ODK1s91Iv*CCT}cH!xc#}9|H^ri&Sz8v9&hM1pd|4#& zsy^A$%#Z^lst?hfPDal(t363Lz>oBoWplsAo5IHsdtR`%iIW4$-{aoXC_>_h9hRqZ zHY5Smc}WKE4N#?uxDpb2ETd>Z=wDQ-zarFqIw8JpGdu?hG6*i$b%W7-s9t8|Q6z-L z0iuP1-odIAbngik;0+SKf!(zNdy4R6$V`{4sYeoW$^Mg+?o2~AbqB;nGPXK>FYp9p)6;d;EBhC)9C6qlr7fjkU6+3X-w_~~5I z@Y@S>4MzQG?74;_QLxUO=({uP?Xv7Az?e^x{<&<$JN$9!LS3&P2Dp?+_9e(uR? z;^o6VaX*@6eW2n8hzqBWQjk1;kKax>0Rxk$vPytgfZoCC0R4;NVQR-DqLq5rNhdu zzO0uAVLr`&CtIoFw+8A_Ym1bGhPXkC@9y2wFg#>n9iGvC>b<~hq`HyBadx_Kt%##* zjfAXX%GP6W?j31`5J_%G%K{!e$tjKzR(hZsjPgT^^Jq{_stcs5A@h}cvMPIe*F>=+ zH$<;87lwMxCc-fJ!r|hEd}1oaJSi(>7Fb5-o~w?|y(K~?kN2{KO7>;#2+xD$&4 zkCU1PJX;muR)k&^peKOwC2&e838L2s&vFj=DCY~<(~u9B7NZ}zhj;}5Pe?KxlGi+8X(y7G#&R}gtjs+U9*-ufJL z1f}YfGki%~4|%vN1%Z_N6O5?Hx+*-7C?7*&LiVbl&V z<-RE%pbLuN%3B^dnz)MZ0~dUQf|ssL1BGE4UPDa;kB@2y1u3a7Q%p~r2(%VunQKtP zhmp%bZgqaCl2cVg`FpTo`F1jh2$pFC?8-EN4|R)=ModdZE!pH$)P+EhPKIyOFdP|x zctRS7fU;y_&hj>PdQX#aO+BBNu1L zKUfu@e@|5VE0RxGN|x)C4nE8%uB=YMEkFrRa#*Y(qND-suuu@+vlM$ZgqWMCcOpt@ zJhom)5}%Zn`rIBx>!PmDNI~N4AH0 z^7Fl`HiQHc6jdkRQk_|Y$F~sWRFf&|->831)FbytCXLMplqsNSrU)1!#y#wrWuT;hFS+2_C7opYX=vdcSob*MdRJ-v@@DdEs3i0fJ|z<%-62z7qUahd?bgx z0iGs`Hr>)NzHnx_kuGdEL+hnv9CpWxeE59IKTx5i4%lVDPnA2pYl5$d!%MDEDs!2W zL_rD%v9hiDLu7Jlp-|X$p`LfFIyU!?D4n6U1kIq$k@V2bd3@pUazj0)rjY`p#FP64 z!lE18lT{IV*L1;=q-#S0itgI;B=U8wE%ha*BlD`@^mrv{Rac!uHdtd!*&x5B(nD=q znM1p-BtwrruEO(q;5*do$}^B5<`-{61<)^zMSOxHSfVkCD?S>Qvl3pz1Vcb+CnJVa z(tFhJ@T@5bk!dcSI^LOr#_Gy4phmRKhB6PT$MJu%K1Rq>(m>w@k-(M;koG$o)e8vX zKyX^UNAwkSPKtrBi&he4fYc8#rbV6EGHMo~P-D;bYZ?Yf&bY4Fjp)Qtr@)(N5RnO@ zHH$F}EfwG;ObO%0YTdsid`RkJG_+S07?W&jhHUlNoP=7)8Iy`bH7uE9GP2IOYQ$5- zuec;U2$G<(Jhf|mP6Cr`c#q9V7(!DYwD}pIg>*@xo_DY+I`57sc*6L>WR=ce<|7Vs zX4gK`c7ay|$EYDHRIynpaH0|EWg0Nb6N!neqloT0sq7fXCg4o-@LJVz4IL!%IN&S9 z>q;{man5d}P_W7Of(psM}abBE$TT}NR#rt zOh1_!Dko3_hK%7*Ewta#C_q)Sx9dFBs}j*9PoRo%yxK)>62c|sMud`jVdW!bOjYUU z-xFUgPfuK~@#%AnYG&{SnqlkjQBulCTDAL<2BR{6LFk^WiqO9)Y#~~5$wT1JB30*@ zom_noir%>Yl8Q(7h>UClab6Ekk!FH41ZN4DzstOFN`r6(Obp zrDcMm$YADmwMb(L)4f9hK4a3S$WSc3fJY4l+ck3)p3ey1Az)X|LGGP;M@UIC(Vb;X z$vUIJ1%rxopGGq)MiogJA{sbS#Pwkx@{LOa&xy%dD(=)&GwNOD(61}wK>VJp2l|d8 z31q>m_68Y4*%U3KvY8v=xgEDOtR=#PgHeNcMap+*q#9{fij)>L!H`a%YibR`Aui4B zxTjHo8noN41}WAcXib2V2!dv~yp)8RaZ*V;X=dip#tiD;lV-uAUttk~!~_VZuqc7J zKuK)XAXXwSn#>Sr0I4z|; z@?O(iBuZd#76VDzdtJkP8m1tuHYCTl0ZG7VQHRhmn~xtEwEK=mp%GN?FhqAes&*Tl zSR$c=e2LlpEAp6q7$V8Mx)?Qz(7qlD4Hiw&^9;-9yk6B;ULjT89qtm7E{I@jiXh1l z%|lrpp?kECtSXGVyUI6(2qO@xHhOwFC$$n&$j$_Sm4eUzq^ zi*m*CFb&%`vZkXM_r5L%>llsuv8o7Px!OnTiC_S~aWxlHBVKs@_al81REnaE0x7!Ff?heSsTMsiBXk3N?nSA2Vy&xPiiU>~BH}wp=vL}_ z=c?j!%VAAT^fDe{99>kCVBViwbm*NcK<89^n_6w9%f;lw@Km!~?Z7hc&sIaet7f)k zUmqy`nvoo#t+Q! z6+KVrI?xm58FFr~9m{kqy#|_9G5U>9rekT!J5;T7$2+v$bc?6NcXTwHB|YD9O{0>A zxvGIrZxtacdN-|p3q;c}*r4T2H{J3brlk^_cMko+iS1U(cx{^Q!Rp-U-I3{trE72w zK4Kts{z~^=Rs%-n!tII5;Irzeu-RG&KsXE!NknG#av&+?k=FdfnsbEp@NY&X>VFrdfG`FS0!ijQ~i4Gc1qewgzz z2jewri!@L0)0Cy{w5He5B8;1%PfKZ$JGEq(O~cXcJ1TAmpl?V1*eHTOp*5z#IHs|f8#6*6Y|s?1az8Z74UXpw-No$GDxOhzvoo~0Gs8G?P8x$iAwYAtWMZy% z=~qW+hHIV|S!Jf9&e?(iM|7nnKB;K$?&}C$R``mlr!*qa6XqGxzPTO8zubM_xO(vd zRf^oeYwrDN`5rSE{x#8LSW)z)C$KgM&A!$tysFC?>9$!pKudM3CpxZb7-E>8u(}Z4 zx!LuQMFdI4o{bTSi2hYEucKJ4F^W(lM(Wza$Wj3$l)c;5;T^2{4&BWm?p~B(d^ADU z@!4nSty*yp7T|OCzL)5!sFz$U*q|wT@?s3lItVz_P|(gnUzN0X^>uuV3(z+2Jdm3n-o<6w zPST#F?Fp3g$ZGLJ`v%QkwxxKRq8IuiUJKPwBn^7P>_2;1wq|V^r73e>VPA&A-57`J zCRx1fonzZm3&8CHyXr*^i_tJgu~UR*tKny(=$@?p4DD{qCHiF7KVGLapEJfUDn+o*u>E8KLbSrV1eA$NSv5i+oo zF2&a}Y!6*0@T-&HVNpd>VYxZke(msPSL{K6WTG z=|Y2D!GYI`AdjubfC0Ym711MZf8;Q)YI!6Dph!$voE*DRt;I-Xo7^I3{I^+%UEBbk{ zV4xfgtP368qt!9esK7U9Ivqoo7`K#fi^&UTn4S`BHd&x{r|>E^R}d7oud(B3b&NM0 z44E+WPB6H6F;ID#G^deIQKkUCm{X_#V+9h&3e}FI1sFBI=8nmZlu>LmF+G+Wf{5@B zLnZN*=R~DgG2X?h?ZU8%5Ic>r+X|h^URsDKWH2t-2F8-&Rn6hkzU0N#*V*pfR}r$I z$f2Pov`p9ikG}i`6SEm@!0>EBi4;7iY?{^(N(QR`favZrQ@aWfSNMr~p^@u+fk&6G zLBndyIz#>l#7?S+qB^ICM;UxfyD=hAGc7O2B<`g6aXVN#tYy{FXlFgQ_FEd&7L=U_ zl60pMnViQ3bH4}#rV8kp2p@7Ek*Fz<2#p4f=-v~PI?)rFZOY~bl*uGz5zdacf|NBo z%&kW4v!xaxR#*{QXU7_I$Y&L>6GwtX%`Oz9rCU!{M~IpiApUkzi7x|} z+FWKQLqr^YxP6WX#TvmL52{`K)d6ZoJBwBbU@5+pIGqS%ni`3F!Ah;A++mbMwHU99 zfR2J@k&konb$lKHzoO_deFH6FpP;r-5Lm*_b_ zUK0c28*gctKf|1b)q;e^5DZu>1QMAup3+}G0?@lB3{cb#VRIq`xBzofYfOO;)Vw92 z;-jj(A$%e2Df+qRsy{y^jEN0#S(@^ljWlc`ru0b*YU#B7LJKWKgpdgS&k`H~AH1p~wkU+!0LY1-6p<(_C2?#=R3R$rPZ&_(dwDCfDH-oxP z5Eg@5>Sd5ILD!X?V5tUUo9Su<9wFPzKPRkVLM9rWLbYtRvg&%T`I3g=g{g_1+C!`` zg&W(K*w^J{p-`p;GBg&RH`={HuY1=77M$d4wqVT6AzwHy-fBG@TEZDj0)}>!;V&Fi z9IO8FNVRBz6XKEOB#Z5Xe8X2hYLN<~Fz0NeAoLzpAy}o?e6RqYlsX|}ups}lZHI#f zgOiIO0D$nEL_OKS9bTVeN=*j~@F|&p(_;4{xz5FQec}sITAYgfmgeW-$Jf57R!T3H zdC@kX^etMz3_f-yvxQ`Nt6F47$c4ZSn`ZDsr%2AeECkW9LK!=E{sWX_ybWKjJ*m9N zIra*!O;`Fsdv{s5DjAl~^AtTy;wfro7f-q;=yo<@H z!ptdzleO3J>Sz>1Vv_Jfb@M>-u_Q)GS}JVv;J_{Dnr>+H$)SY4aS80=Z4<0Uls9cSJaGFcsfM*)5q`_gvLi zht_9xJu92|DO`ihgkVE>A~ID1hJ!Q*9$Ae#XBvIiey{)^4^AErX?tWyLP8BcnRhZ4 zM6nfRnFBAJ18=Fvq_n1U)zN7Y?NPFb40Q$vV`8>wnU|`4<|H#!gW2N*`O*#%ho4W5 zns>8E@;bN+vK4uWJx16)#~*Ol8KO$`fdG{nLZ^gpHGeB$%^mGZE$m)<9bQR0EOEkq zq^PyGR{S(Wl@kOAG=hD1l%^0(*6M8nNLk+zjbI0|Y9%qT5g08}6EZWSnBCS05$Y2J zg|9&YqAKw8l+vFBuPeELze&L@mOKwc6H=CQ5u3&nCjU=Dav9cMC!TvtEUH7V;3#T6 zz#Oq6yQ3~OcRG*NyH|zi*ldb`ODx28@A6=Ec-}2>V=OHuCPs7Zi9*aNUS;}b_Zqvc)_~_EYk0Xmsh0BtF)n;i@ z^Z5Pfc|uT=;B^%a;DR~wjg~cR81)kn5gfmkZ?^9aaQI(j zG|;>0ZEz+iM5spUZMb!lvcD3Qz9TEC zTn@O>lFrk40M52bJ%K4=L*na+YqnBu_pwR z4OE;UmE=&pghs&JnS?INNLq0TLpGhOj*elBq(Xs4Oomv1o-PfTm`bu!2sup(q)^Y( z#h0F-!;w>Q9=RNn%307=v5~SRk4Az(@fT>7zwm8ItJiQqIXI7c2xY-?UQGN*7!+p*cW3Dp zABNVMG{E*#p9KYY^l9Y+74KM8y1Dn0D!%b{Pz7Ws=Qwj}uCKe{J3Xi17c~gUe3EU0 zC_vy6j>cLvC#&L9u4jKq_&PGD)#u1}9Ve9+(d*J>UOw>ShbU4+b);tk~7Qc^X_oP^ne(5zK8TFW$?FXylqXtC{7tF696`dP!kXK-(h@apr^^9}eRwbwFug@rRPvBAa zK##1-W=Neb<&*(9#3gP$E-NoEDM(lJ4s&K-(!f>2-kk^F9LiCPQK=G+egg)}SCU6tVAH%!77WeoQEj?_K%`IG@r@S3AlJa zDDDV);pQt3NN?t(;3aA4K%EvzS#F9dANDv{7DQ1&@e;DFHzM% z2s`2Mh3%*kxb>w92znQq*SqroTtPR_1Q>?amn*=apvR8zscH_gX1X%iKs}EqN?Y(- z8^}ifgSr)xda_J%fit-koIz}IBGI^vlX$W-S@1-*;b($PmR}MB?z!r8b8d*KE~swC z-cTq(q&;2HFyX>v!A`+ZWlpx6k{Dv&>2cwHm&dANqawV#A#@6b3~Ca_nx5kgP%$1j zJ3H-Wj-~4*-dLQf3e7Thj!?p-%4ae~Pd%WhzBz>BvDB4-)o+HMY6lDOnMarJh@cDw zHe?;Bl$taCmor4UM?*Rqq_?u*3`KH50txEBXA0JnE`e33h<2{dG}&XtyMt#=-P zE6o$n3>XGCo+2OwNAV9Kf1+{Z?UD-==s71vfO(U`CRon$rKZ?kxSL(Va+}_v_F8A~ zj#VWb61PaAsGpVE<|}<{ECWqxvEdg-0wUnby`D3hZ+GAQeNh|kQb!=tmj4TKmhI#?&TgZP*5+{ATS-pIt!lxt%QX4x>Vhx_0 z$u=$`$&t6i53Vma;6y9kE3eb7h%&oIz$i3AjDZ#~u@f3o_9b6f@FW}Q9%rl_(`RF< zkqzD#R?&Wklq9f#+!lTUi{d*wh1DL?FE60V zD`JTR8r5x;{80B;0l4CZD9OXQ#S1`%pPBkF0~^KQQC?uD;G9M|_h1n^O(5U)$J@`Ow(3Y0pEcZWf?8i+++1(D=XQl6i5XF1Se^kp0mh_Sm%#70ls7$#yjyF zweryPwrqW=6V5b}py=OoFTD=VQQn>fFpRA)E5KOi{SXFq4Ny6L zqwb7G{+8G>=04GXJA{GvsyVk*W~xeaj*3$uahIShrf0aPs?*K6Af@5BHnymc0H5Os z&`%n50PZxL9ek3F6YpRFx^g^>27uB(fa^`^5EE>s=mAQr13$+KOJ^X9d#*Y!{({3gL+aTId|vr$+_=QJl%y{v8|l#?QZxyW`LUEg+8SJv^H+PI}%X|F9K z^_&iMDUu=Eu`aII9n}VmJq;MsKD*XS4@kG|=3n%q`xIBlZ|SLu8qzU>NCk(F8*PK#c4U_KSNwR>FXv?(wTyEl?D?sPm5Um!paB4X=6I~Wz zJ50GSKVTIc1rys{1?hc3vhrX7JgmswMhA69GVPwRH*yW;^nI|vi3-hXQHBvH^fs60 zf|g|JBxUREj#n^6TCxr!&;?e_5#Glc*)9oT5(^DY$`qi3 z+oWZ=BSdlZ;(|u`k}XYLez~VBmNdk30VDu9h zer+=Ij}?G(u82|-cAtYz^Ydqc3$p|}C8vC+-9z_(nR}NWYnt3Z@4xg~-KeT_Eo}|2 zy)kCvmB(lSvyf(BYhVk8|GOVD@)C?-27@Q_ZTkq)_p0h-78$$-uS`#H02`x6>TO@w zrz#&cBw{EbXF9E}x$H1GF1YMi6X!vN8K5Unl2_!^CVXbQLQsPde+IRv`Og?Q7b^N0 zxHF^um^w6*BS1de<&Uy+sym;v0w>!&GDg4yi^vNTYY3oX43^#DV~*_B!N}~E?tD(8 zM%j1*2`vZOFbSkhOwr;*Dg2>J~?kV@9dNCPf+m6@1{ zXSzN6e;T!1c0k5$Q5TPAOSVdM8Pk4gDyC`gAya?J%Ec}hVRC5~#z2;wnZ88&SGe8L zHNu_w8uP|1hYU-S8m^aB7u+1M#vIw74?R_!4vBE~xZpDD`JAR&m>00djUC|Cs&VbP zmn3Qr*ciEfA-gzi>@K5?pB3NCthvU#(IFXJa;$lC;Ua}WQ3lK^a7`q22$~TgN3n|X zDR)u9P6B6m(8OUc>Gt5rqx`|mzx@4w|4;wr@Bimt{uzVzpa0|E|NcMy%fI{|fB*Nt{4=vD za=8JS*1}9i?jrpl&)#7z6Nwyb-m2oilM z6G>vaACL%AIk=-_7?m?+R5x{F1OzDwzQ+BcUL=Tk8AInnrL(t?9`NSMTi_Z~jyXFr zsGpoUS6h98IiubAoaW1LY`8IV%!hWMBCId7{A6UpM7B}ZTQYc!SzefJZb@niyz@DY zTW;N`tLLQeibZayJx0jRm^m3ND2wyx{6Kn@1Envb*STl0<8l#jrJPgD=Cfsua zPGgqK39{%tUBNHXinHk;WiT%$Nw=sVRj* zIGJH45`~vmCUtWNE6Fr+oUp4db5fW!M$Otd4=9NZ0i~F%iLwmnLNznv@~Czw_c->4 z^k;KgnS}Ggjhb|zf~&ZCi}TCW@R?g2#-p)`cme@I)F*xzgS@G?|SfK{0O^JR!{PSuhE@W(EBFe zPqi>+kC5gy0a@Gu;GdpzBH`c;E^(TeDnw5QmTpS;sCZ%^5p(Z_vsdh#GdeAMk4U#z z;(2gM^S!K;_$FpBXYPnokOQF(hp9{G7^R(eMyIjM?HBb`9_4wA{iS;YgT4lL#;i#& zfi7NIX+|PdN7DHE_cVIBTmiFconucE&$H;gS8y7)T&_TSb0i=rp%<;rC8|pS7{-e7 zGlD2Hjx*Om3fCxEqrzJ@lNOUloKZUy;cohOgjr#Plc7ugPD*ET;~_~%oe&RlK@owG z-RvD)W4@H0^5%?wxUI^Wy;;(Ls<{L?!iRyzYz!XQQK2mp7noC6+!YV5F>*iTmzlZ7 z9S6<1_&hSSpGXshJKU?T$ze&Y>)0Gvh3SAL`vOSVuu6y^#LV@8(2(qVl1sOY8ZEY* z3mxi{j(5pQU*oArTy%_^xzhPyNr@XRd<>nGSop*hfjToNOCnu7lM=QhcGe%!S(zhI zpK>!Duu5nLse@zLr>)X5=1Spg30!jbp?O>7);plnxaBsC`if367|@KnII3@^<%(t) z97_5>xgF5*Rn(=Ybx)(0OBKL8-KpnE$EB5920{uyYnwc|NXHd8jax2PK=(KPvDVcQ zUnriTupk{T6rnJ7a)K*w^stcH=Q2n!RjH_?WK1@mvCo8)TiQrYW0uPll=5Egn#97n zq!w=Kp&H7Ydpfl3fUaDB?fJ;FuY%VKqjD}o;3WrXGhnSvet zlHBX0E0-PH*N{)zrV^IUg-d{hRdG46z%%Mn6bb!xm_`~mv2=PRCz#$J(pkx)4-&Mwnst=sNCb z1VW0$jOC6keOgjQV2x6uB6hvjJ&jl{U4S8Q4m?XXlo37eL@3CrNTXy?yq+^~8ogY~ zfYddkAf*3F_UlMnnp}G%?@K})_gM-gj9mnTbMYo z#*Q}!}0UAj<-(S=RXc@$60gf8)#;cOfd$hPc~ zV$rR0LMOSBxzAAo(h|;ti$;9Xz$73Etjw4J(UsT|c#psmGy*f{d`@GQ+bfFNz_HLE z3Y86No4BG9E5hUDUNAH2SF|KgP^Az1ksmrzwWl%5pS zb5TbR;)+m*L&R%wM`Q*qr=zRZF4Fs9ZlE!0lW>iZlO_`CXeH)K1W7droWL!DxGZI3 zl&W8%`LRU7{l@4f|qp&c`-Ca6ZM5+A}vvRFWy zauGPZYMC&_z4V%FK3m9BNq{+^hTKTw5z9uUAfMXo60c=)9|2rSM`c36HFg^JAxKME zYc>bf5Hb1z_&sx#WHgO-h|yQU^_;68(_jeteP0r*!z!j)^*ykN+f!Ldc1c>nCiFd* zX>J4rjIa{aCgJC^NR6>cWR_9A`kJ}ENDPEvrKF9~ z`$gmTM{`zvAgw`Y-1;64P{<1L5qej^tE4u^oCu4^a0c0@`bD@$O*GC(dpM^tLnDpv z(*`rChmm?F^cVhpVIxwV1b%UB8AUd6;hfj4r*X>#{HaFpjyy@XIb(kswOp{D!a_+D zNv?*gSm7lWD2hTLR6}W5tU$PjkuoF{gyo~)OS9ncCaG1z$I=Ongj}IQq&_Uekdt5y zg^kD#lVa&neczX&P+3kwHj2cJDE(^?3nToEIhz4$j21}{a-!UuD3V&{X=+OV5fp0r zSS_Qi3kQiXD7P$1A14%~)PYLtCJ7yhoi6-{lT9awFgYdoO9Jb( ztnnwt9BGW24;a@Nv^m9AIDix88lR5!^3s+|;YkUE^yhOLF(PDR#4Oo*m}J8sl~#O+ z@l5Ct3iDt`M&L56U3(kRAl<>7MGJcw_>C4V%qxXj=rM|am^)dtBX#}6L#a+85H-V% zQwsJpX1TaNrGnjYXDK#i?@!~E3+l_&o+)@-HMm4m0a5PM6d_1yB=rY4SurotUqw&{ z?-?4?6;e97=?)Lp+EkXPpnh?Um9z>MJnR z*W}RXq=~xttVNpyYmAzvGvKa(l;1vg}r*B~563sVb2nE;39<_J+tMjjSqDKDgq@+>>h%L)ncHGxp2_3O9*yySzt& z`!kUcp_Dirc#+hxNmx*D>rUsiA_-@GTbj90F~U~v)G|G8hGtYvQ8I{6Ou;Aa*5X_{ z2Xq>_+$K;07E)b}t(7K8Mz54Jm!KhS8&dE&QzbI1YtJG_K|{clmU8Z?=O~9NoHG2U zQ47QSxI%yV*Z=kZ`pZB6FWjJrK%t-iDt9UBG_ge6M}PQ`nIixCU;d3R%Xju~t6rCQ zWBGjRx1Zn12_#$$q7aUOmXJ0r31}^5Dv={m1%;gNU~_A1;TF^$C~Nzeq|~a%(3gT= z9swp#1n&BdfSz&<%Hr#R!DBs0DQc7NH3x4HFOLZZ`(xq}e};kdl8zPhj)AZMZczOx zYbW_>`SUN!FUybDU%wt%2BA(MxS$*87GGllM%Zy@-j&ZQNHf!Nu#{2bf&oP`cJ)WK zd;7z?OKf_;>QCWK|Is|hQV|w-8U~H+M4|oQIF(;B$I0C^DjSk0=%%P9;3yF0fFOxH zW`4RVDkxea42Y_f*}0Dn8uPi7s1j=XQ+TwRD1k?wDTspwcu2giX9`t)R`;9~cPT0i zG>_rWv0hZgw=;tj=$ntKfseH$10o|GF1T#RM#kgCm5t6{E(@AuB0WReiF^$=R9+^A zm6|~VqV)uvR}f33L6;f^-62})oxPW&1eD5-fFVSSj4&f>Ov&R*PF%X0^;Uy7N<4c1 zY>ExM)xn0zWkpR{V@}AL;3c;`?p3t;U4Q&9X<1{x?G9BmysTVEWcm$WjOJm&R!q@QQpO7@N?13k{OPb>5 zz?Bg-d55P(obx$Pw>TSeTj?e$fL?rxh|!J&B-QaKRaq0tZP)SkB^qAAmmu6C8iX7s zS&}0)o6?YIwm{k%o|JMRnLqPISbXV!B19tnN44f2^Q3&6JP#$!)UJpVq}9r@Z(FKO zN%X6lJx@0Z7RNf$Xp$>1n|sH3%qW{4W42RGIMN)r*k_j`4~ZtP=rNND^UG-lk4JW` z_Nc9xX!6MeYlvBYIDbUa=*FDJOf{r|>rhG#QPX$ys_4()#x$ETKZ=LBTQ+)~lnH62 zB=jI{R0PCJsR<21n?EHe+^FrwwUy*QIXG9 z^FS~7Nz)X;Cd#R4qQPTSID6+Y2Q<~Cvqyb!e6pTmbnHB~B5=_`OL}{lp4hl!|Jw;D z|HLs;>W}nsU2wy4sC+4D$ya?N)FQsV3<|MtM<+0>7scKY|~x zbW*WF2H*l-NE@I@Kc&*?id@9r4;pzWd4b>&*>bWk2BH$ zF)BH_NCLmr?o#Y>kz=kt;UcQV17*aocNumVf?yG|5wQr=HI$rl z$3^6#rJse>;^g+O6k&Q=18XbTRp57!05{`urBIdXm(~m)A<(1!5%^4A z96J#^_~H=s(Dw$Q<{zFxvFqY7m*6oT|e;D;-&EchP#)Sz^y-{QOsOza$| zkAM$L!FJ$<3*;b6(QcQ+sgGP4rl*rRa>er_nBP&|AsMF1WUb+YbilaW;Qzq2oVxBP z0e)KLz zWTsA*(S>K@I{-^H?D`%}9#V2cM0tG+McAdP#eGvIctZJXl%){GRmG|3Hzps+_%b>v zp|GkHYUAm@08iO5K@F_laY*jbp|Iry-!_{p-{)29r_2{oEcc@!5?}JT&YLnwl0S>I z?|zkrXrwh6N2laN@6k)Lesq)tS<5{hC*P(iV^_STE3`p`y5UmR)BTF85OzgFeY0o8*W&ATo{u%MvR|=tE6p>E|)r-21Wxg6GohI z=|f>v`ARSflnYAoo+|s!Yf_|8t%@37g-Z%d$w4uKg@Ro*2i}`fI8v<{;Aq%Si{MuZGNqu1 z7`>wPr)UKav@Ik;g=GE2@*eQ2KNsl{jy>}5cO2zZ8{qDW53#=*wlXKi)p5Jhrvq-| zN%@BmAI>)Kxe7^IwF571M^d?L6GQ=rDM||52S{=su90Nz@Sj8zd5C;%<9x_~C0a4) zBczoJo>LkSIK&W2w*rDHMn(>#RUwpXG9)+7h{N*d;x+l=u&7WpvkxcKtf3}`3B2g;62tk`W_bZ5jbZf3w=E3Ry7^C zGWc@ju^B(l(BsQcoFAPa%x5553YW4d%6q(%su2{Mc@+`EAqo;%+^jz{n`#eK*{gRP z1&3oI3f-X|351Q`i_gXk#N_sRo3hHlrkOTEMZP2tt%xQbX? zG&dLYJeoMofuqBvx27fg9dtw}p$`;?5L30rZrK)h)B|m|k33Vqr^v8HQry!crpS;| z$K+grM=Owv zjyAkX3g#ktq%J9N1h&XGfLqg6#!H|mn!EcL!~Qi(ECFY!x?24bMY@JpWoG4=j2nvb z2OAtqlGGw8=6j4}|Dx3o_;XlBvB$;{u<@J)%^tc5JpYk5WrkTss}XlRg_}`x1=tT z)W`)sfN3n0I3dwRTvjH25kXVYOQsYdU=!%jxAbwLYg7(CML<7sy{kBfgQ6Qd_Bd<5 zdB{msNz=t^ARa~_S(@^2cL+h2+vv&YF`1_*8X#ISLQ&%5jQ61OTu0RE={t}eqPRwK zY7Ci#bdBYpK0E5o*c*ohbW($&pBSM)TMP`RCrzxEL<|MQ4AEf&TFK4Go2!pa3+r~- z{WThfCOA$!VSNi2^5>{`sNO-_RWk2L7f96MyQgv#KL!+WyIAp4An46vJKYM{40_~W z876Jtf;&k`;rf<>p0`0Jqi1xp_So<@=>22KcN#x3y@BucA$xj|?IJkKp59wh^h0if zd(=)p#DV;v>{g&I~@+KJ?x_#E< zzx}elDupHz6_`UV1eGR5?r9woED9#_|E-8{nK$Xg<-4j^2@K29rR}q1p!99~50le& zWKmC4S4^6_1|QMK{wu+V22`K&L;dvz&sT%b{xE?K@~Y$usce%8utn#SvZ23LoOu2r zdx>&7QR33kYyff1wrmq+BC_JCaMuBs2&&cBq~J%u+9j&~?U2=+wR12!2nm z0SjkYPDaj;?bM^;xaE(t9GV)S?Nf{|0x3BRsr!`@)DvpzFDKPp5bcJANfL z^jts({3#hBBC~aO$$9@x?nx9riAy3J@b|x#5w2)GkEG7IBr%J;`i)M1J%-IE+5pXf zYWnNbsD+hFJ8BjlA03a2tiGFPLPiM7n3xo)FiW#c_}8DmF$RT(%p3PhNfZBWY}Dh{ zi^u|90y&S=N#rim7d<{kVGPcu6ES_&dECN2W^18v0<=wvvMN^@>hE`N;%C<$!p6;S zmkTpRNRky;KZ^xyzAJA^QH|SM*7p!|m$nI3mEvC$qmY+VJwhz`ahEzS zcJF=NvvR_K@yHBr={RLK8}i;@lNC_1fm;4UptZn8F9Y3;PuUQ{rC^hyaw`6dWa|bVGd-T z?H=M-UR0e{aWKx)F>E25!0?F2a_o9^Ru|wHWpyTSw7R04KJm_+))5pv^>tq9#KVSn z^HJob^T7bFRr?nk$GNzS-Z?Z`89COi(G5$a$zF^W3Z(8=@)rEw{hGGQ z_PN`YR!NQVW8>+NR|PWv zdmWwQQ!iRz+p8Az93A6Ov%ww?N9Xq-=(nqWjUyx73A&hcat=v z*fdpu1W#iGHj!H@Qlvhvn$DoCTfS*1r$4H)`9r+)4`s2DJ&GBfg7&6MaQzIhVcZHk zEq29W@M?cK!mIsm7DG}ODW%fVOVoMKNy13$fmeJeKdR{^4|lXyE?ghZNEZ_bqNu!) zE zDff}UvHUV($RRq10ynEXu0)0+$Vd~`$WV@5Z3|qatA|IJulc5tF8O8cd#RB2uTkdf z-;B)BnH;teF8fDSuD3bKMeTOw@x-)!JkhsF^PJ2Gy)SyYo2~=K;RU+*`1v_g( zB#h3_M4pV)InUt-v5k$1y*DyEH@S)I4`#$n)?){Hk6k0023h>cKLja^b-g8HAI^WH3ljCO{f}yHt?* z(^Dr?Pffyt#R5!=hCaHxi{!H8Q7XBAWQ~SSFK6_b{_qn-#LG?~g4i-sgDj!2L&1Vl zW+sQOpg33vKhf4f^2|KOL{*A9Rt&U}b7yn`$Gm1$rqJf{a+XoegUehxqmi|>#KODpRW-)Lv{{#c73C0@9 zlEGmn>bbaAK3{Jv-JP0t7X?R*Jj_4A0B1MA0D0eCC6B9JXQ|~Q2X!1STqPJ!+OV+I ziuwmQ&<7XTg`Enb9ea*;A*nHt#~Kk*W^)~sPf!TQf*Bia?{N4!a&&yEs65(fnJa8= zn0(jxf9;zTE4`#OzezXr-I-_=u$I9ICAm2r`i}ul?RO1IckRn@^sBt^Www6(~R5RGEiZ* zQqs|L#2$BWr3H)Xpw#|}EN9`2r#PztyI|BoCal(cb3%B!*IXewGNOKLOs(jkPioOo zr>u-~q_nY#HP{vBWtqw{9B%n?O3E3Ikx|YJf~gsTfUO#wa+hm<*@%p|oz+JhY~xFN^pyI__pIF?*J6_$cZa{+HrFt{)2dHje44fEQxzM?%XDtI zZ6_qW6=~I43arXmq(FFCO?G9+=)Z4NP$LD!(w948Em#aXN=h<4BRN;mNZf+MvNXl+ zDwx7S(sac?wC~O1!HDIIMsjIUypd1PkQ2Cs92A|W?3ne~7O!ZC zGk@NrDTBt{WA%z*R%3Jxhrgs5pmLO&2aD6Vs-Nby65h?&;|F2Z6z4R+6f72FCW}a` z&lDajHSBxSXuR35kT3-jv9HuNC6Z_%%6_H3V~w_!bEegjeyZ(bFR}WX3TJ%{+dx<< zvA$;Q#$yr@xq>WpNG(LZc%3qnbVMcFW#WP?Ag$n;Kuceiqtj}>E1rpDf>sFD4Eqjxzti9 z5-5ql<)h(6rZiH!za4%#`Z0p?mTJ10`bm->+S5q%S||yf_oTR#IVf3AZVEpf+uEJ5 zsYgAfe++*2Flk{dwd^$_lfHgRc=(H*K%|C#c-MWIM8f1RMyP_EMJ$gl&kX-WiQ3vbEl!+S+ z!nj#XXkH@En~S?UBGi+chxJSdc#wD7bWOo(dpKjcUi4E1VkB9{F)r+=zBABv!9~hM zltin)UXX!kGLK(YzLH;(jNEd~r09!PURtF=t;aH#;v~PJYNC;pJ6Zy)51PS?Sp*(l z%B?Pu3}Wy1C0d;dfascLv>teI``Z23VybSKFUA8D-dlFDZ0xi1p8K#R_IfC%=>)16Ag;BITmR^uy{*7I{34RaiB&5v%YZ5#>!ysMq9z)sU)xv<&RElv>5| zG*01#Q)_THjloQICVX40-rP&rPPbm9CNz3^i)wUN_c<;}N)2+(0ssB5cx~5%lr>VK zM(qm7qPkcz1{GwGIl&;NB2qoXvSG!`IqzM%_+{|>2T;v9niSC} zJqd_rJX|y$!!VeKN-Y5MM;;~6!EOu&&a9!V635aZhYT}XzRA6Rizh;6Os_<=SQN%iyP*?Cxsyc zTmrr{-PhcC*$DtX5)NQ6mnwd_To?@1q6@qzbsGO4EZ?n020=op4#(-DdQQscaKS`; zam469AQ;2YFB*}G7sFQ>NW@q$iW5jQF`^|IfuvF@jD1YdP)~oQBDYn6S7tpUJ?@196Z3hbf+kgGn|Mp-1?eG8g@Bj0E{I|dV<)4`^t}&ng{%`;Omw&c` zNO88PPg%Tyi?w9axOlu+$G%2Qmv%McZ4~w|-@NZ}eIX(%B&9-_cd>1l%}VNu5o3_R z$nwFtRc4^hta{HYJ1-JI!_JFs+OL2n<>%BLQ_{jrIkc3JOLRm9SxJIgz-AC!&S`y9 zaVx3WIfo$p9_UhuGjCQM75c*fEtw|gv~d`V6ZjsPU94sitRFo84b-z%>@nZm^gV88cgCV}SKC--KRj8}gcV3jkP`1DfJ-5A) zLyVcxrlO}rA;j908}g?pT8@8~>83dxaS<~(`ii1qRn@1?>FXp zf-awWL>%*}drmHbmWH3$L>g8842l-Cg}rtn8ik6lI*>)HQ47cC_%zIDSy?o&)mPzF zN$ifLg>B|8+|jXIqa2P;;Yh=8ijIHAZ2V!R%HZMvNt&H^2Ztb_+;2IVH?5uo50~o> z&Spi)k}YWlB~t5O>(zE&r_xLdUG^6(VGTP~vb-lpNlIbHT2&l`>cU8$SXB}*M3Vd# z@f`Xa=vU-oV*R*pQX1UG`2|THI+gUaB&|g6FZUT7#PuGj?P+^~#9QiLQaBRJ4cxdr zt|4bFed|m1iy}#nd~I*QbAO-<4-|>Z#+ztbjVi+S?4JG@_Yz(rL#Pn-y#Zt)@ z+uyrjMorxF*;E-bI{_L?OD7b%6JOOcVI02Hu>3GqLHn=RS#a_X{)1rc(Fp6mN1MO;Wg2($hy9;K}{tu%>ph4e>OpYo!YebM5DdIy$5 zlTcEiOLjDcW9uz4T=K zpkmoYC;j{(#0ZTC)qT_jui^-1V(MUsr2 zSN&LHNvwLg88`%}HEqt5_B~vI=%(v=t8DkMW?} z5pDd?g=g*Nc)3i;L7q2~REb82*1Lck;0h2~ECF2B1y$#@xD@L5?YRqC9e)j$FDeek z|g|{}YqQbV#tn+vq)A2O7)_BtstC!3f(==^-_?C%V9zgUt%pv1!*&#_bXLvqx}Qj& zZb%CE7~pg*d*P`XOEKJIEcH#UFJaN7&FK<71DX^>WN2A?CoC2(P#8al`7jaB%6VBV z54qwZ$;6!+V`&D@7-9}MZA?tTQnvh%ip0v|`fk1iwM5bq4{s3ASoTv~z_GYa2_(P# zo2|VghmMXM!IAc971>3!q|j#;O_e7@17_bV&-U^(CZ@irRzRDKll860i3@y@WQs35 z##7E=cj&BpzPX!}zp@{kzCr4mXtJJBK>mSs9`H5fqmQg!b9MhcM?d8Q5e^G{pq-om=PO9Vvy_+wOe;v5yVl{| z^deFc-5is03x%uNaIf?-mU55MEvq?PBe45TAV_bu#)ZmYaXuERnrT=MTjC+V?_6&I0Y}65UCj2L?>mUG*K%8bd0lSm1$vHKh1M0 zA3}H$=W&dpDB;~TXks94fM$-C5`qOo99qh5sKQ;Goi3Jp4JqR}Wa3jVh{A{h-JV*d zk*?5y^byfwsaM1o;*vhYv<6X(@j>WCyt2 zo){!IYC=px>MUM;(z7Tn6xSFO=8C4u#z}|(#r|31r{sGjIxlNVs759zt{O;&4cFGx zNao?2NGtCTEe$-)ml?2=%N@|=6o!HDdMbKK+X-fS`+(@}Z=}3w{zH|JM5q1a?|)q` z)$-kH8bq^fwttffqNLFFhX}zHiaPH~G43;LPK38>M3F+OI=4?r`PdCE%lvN=oA#@g zpzUv!2e^lk&>+>qE@_CcX0{31QfDppjDHYSO_l}FrVu9bOs%|tPLs*Tpi7KIvNs!v zB~>e`qy1`!rT-#_Yn?ZxXh|YFvYNHK*GS3lDxAV;H7h?n@qF$DkjkF1pi3pmTIFf9 z!Uy8{4hJc3arGiRzrWSWGMv|8fGzwu@0Xn0^NXnlN`!cPA^JwgTf`c2HwPR^dA zKmo=7M{r~*8bte{))dEzM9(ILi0DFWheX_6>!TqjnkHHp;i-vsOrt~ilT3F3M#MTN zNpuWbk`Iqx^v4*H&X`FoR}SiMIuwcBJ4;Dd%>%6I`byT3Azk#7%p>K)mc?>CodZH$ zfK#L~Oreo>Mpk~((#PkiMd`)dzsXACO=l=!?XQ=#4><_iN4u(h?Oe%NYnsfWb_|K# zlnbEv867;w4rcq+7_s6^I?tt0LYoG0;2B!U5pVwGV!|wBQ?$AUB^sClk)i{#rjpzo zcIZd!XTJGp+ze`H{r4)qzf zk6>%bbOc*vooAU*Usdz6;WNYpUlfjb$^>lRIJG`prHeN2P<8~sm>03oMP@57 z(vMwAIu~??mW+9EUv-w4l)sMAG;tE2mUkN5*dw)k)@nVj6|#PhyEc6=L{f%WN+sO) z-v|*BrX{k?#f#Z0cjAO=O%C(sAJhqby|~vB{o-XgrVS?ueS)XZIE$t{Gksu59HSD8 zPjQr8n9b=|rlV(yBT^omR|-p1eju1JmMWZSq*lu9Z6p}6Yfy?(CIL!nO@ygtKpRue zMN;4IFnW$~RP>%zHAR0qkbH`i!vsmBqI+ILI@g39D0kXR82&-GmUIR_zxQC};yu)M zPwcAx_(9_W%N8a0$t1V;T3KmK&NDe=m|#D%rN+c-%wYnyA5;qlf+01u|9#(N?npPhIo9c)Rk}EB{Hx)tbUzNi$RV3^9Z$6)?=JFPqI>)hLb-v9^eBIv5CI_tpp&>;XZ4VjC zkC(YaTNqjMMSDO;bxidhf(KjmNBbg0vi>1o&Q^r5-Xv15JCZ+tlS%;^W0?s=Oyldx z62ZO<$59>I$p+A?7o<^0eW2|nf_eN*?-Wi@7Z&a9EI3bg1WAD#?^vwSt46 z)jzaV1&rZ0uPL=H<`Ej^-JiZC*^{Cp;i14sw5!?@7DY-P|F|Acq&$Axe%C`DFxh8n=?4CQ5 zVjWc|^33+H$_A%vLb%mMcYcG*2J!ZfjS7E#{f#Ckrg+LMQhDu<77_OFW=jR=-j5=^ zHdWi4*;4z)D7tds@{c_hUmLFh2Kuz(BL7N?gp@KxB4He>LylQh0poZ#3hY1ow!GuZ z#LjP`QPu$#_NTwu@B<u!T%>}34^(3OH$qcE9e)+@Z?fy3AdwklFCwPKByIRCi+K zNQ&igr>oT1z(!ad>S@;HRT+1R(KOLD4(n2v^)%vC94aGD>g)Al`Lzdjz&m z*F9jF^{MC?m9cT78UK<7-CK+p%0Q5mMwyb+d=UKp`WsiC2fdgN<}{PKRSU_lr8|mN zDYBe9e#(IM6=XBz6{Iei?OeZtK|@?#t5;;m$Fq^cZxJizaLLs29|?oy@PcFi2qNSv z#uVDc%{ksrDD;Og`5|>Z#sowUSxp&@EH_hA=>1~cLJ1*I2S`$fK_PS`uyR#aK2h)?C()1dioq%^aE(nW1+@#ze}TuQCO+hpES; z$NwxMQJF(XlW(TE{xV{h?Qg#fTto)w(yoZI2XN#l7Lt5VV4sqA^6&w3#T2!^I!EzD$Ww@cgzL~JI-+XICCa}*T!l2WWQo?2qI#X_pPQ})vJvesS9w5?_UNhEJ zu&=@s6L1XiPoW~MdSg^Rp$Va}7nY92Jz{iRL~5F7KEpvjiAj{r&WT9@ij@$!LyTYj zg}Z!AYBAC9C^i2L`Z+|Ho_Lld4oo2;z2c@|ufaZvNaSh{DY7^nojUEI>UD5$O$MpMWv$}}!vf60(8>OoDwuQla?0;vP0jP)8gYKQHgGByDyBbz}#V`w@{rNrWD!G z{J8$CoUarl?l-jULHRn}2Gv;F;uFZc!ZbUPj0;SN1sz?w0?B_9p!49hfV2O1tY~+) zU5@T!z?E2+f=*EZGCH~wZX&!uE`Oeecq)2-7&=Zd_M?!TIkrrI#a=P$^|9x;4687h z1;6~w@_4vuanA9E@N1>Zxv zeJ&-fvhC@Eb6zK2L5Rtg^gQs}1YZ%&hJ=zBhM9hUnjzB44R} z%Stn6ki+FWa*`%#!2(>iH?RPMDTz#l*_>_*ze9@-?;QLzUtS^#bkz`>MYee%bA=D! z??j_88Pr$~D{V2(fCJJW7?r`1^rD-F~%#B-IZAE zO&7^)L`kvaKoa>ZHrZyO^lu?aP`!nLWLYPPLij+n8vG1k%Z3BV+Tb98BSWXDZ&ph; zM(>GblnP2B`v~V!7vdb!1?WZDn+QGH3&bT|(JRGVIqV=PE&0wNokx!y*OS8Kb0?sE zfMCm=-CJb*zx?ntcfO<26GJ}w++{G*ovp=;etJAKyq3q$3UP6w{}cgb^YHMF6(i__ zHe}HbL*Wi#@m5Qnryw!0F@pR3SAby7Ah$p9kIB^hvcp{1s1hE=IrSp=LWl168dadx zYZw8sHu->JrH0GPD<0)NU+JhF;~xY2ypMfIVOXF2RTyGz@-~87SHz_Je$Uwb18K zKwi|zD5681!b(X6-i#__`r1GF^%wnj$*DGocCS*MgN>*r>qw|hf80$rOrpy6z-VZb zGpukg^}JK?RFEPpzJIVr^3!(shsD(Xb{Rivrxl{~6-_&=PzSqYyi^n%|Dt)_GG7$#9Ixgm6kdO+Bix6d!pKRc;l93w`0- z#axCDT_l_m_X;d!Kk|bM#`0mg#E4ZXGMuIW+5mjOx4+ zsoIAX%7)F|%>m1W;!6?Ma&G0!%(TMgbaE(#ZcUAnLek8Gix5~eU_JPC#CmpI;YTQi zGcGoij$w0=^iI3dBd$f5;zbH*(jrIhdY%`3!Z}h=Ao&m}kBd{>Cg4kSz;ya1_4Ygof(C)=%K2JO7UB6RIHH`SXJ(><={}7Cb0S3ag-(bbI z%D}-&x|X5Ooph~Vt!ErIjA$kovQk(uDzZf0`~z!>bpGV&LJ9hZf%I_A3S2D7E?}TBVWPVj50iQB@a(1 zhZUjHG5JhE66MZ&6oG$CaaQfIq~zn(~JX&&ycBKxJ*oik)v| zeLVF%gkOj~mvm?k#%4x#@IAcy2XpWf`yMlocm7l>l96CN4y!?&o0(HcViP458e+KE{66l~ zZZiy%KHVZ3$i`kRwzmOUY^IJOht56B0#)v1tCx<6^DVteOX=kOh}9h8bjOgyCR6;j zYAOeeFP1f%3QkYbdkw+vs0QsE_>WAz+X}t|#uWITg6m>nF7P% zezuxP7b6iw#yc&`p{+{J!%w3?%1|5~zp)I79XBzb0yMXOjDzT`=6Q`T?qAD4CI9;y=Oa-NAocsus_@*mUO^U9X*MEKEz)=cB zMHxOcGpw_<0@IZ#BaSg_fDLl0`EVVWUwyMm#M{K=o6vX6>&Z(qGMpsA*FNU^4 zGLn~gNpFVTFHy^mWC9z~aYMc-m@eaZw!4uahS>0?#~s&*);UTqD~id(47#JEfY1>I z%VdPJ<#BW>M`qm;Y!)#kiUE%D#%av-Y3E#WGG%O9kUodO36@mUnflCT3_ zbiT_DRf8Lp;6-$sVLBn(S|uqWTj*zgPq9++j>~+z$bY%rj0)jWOvMnPbgtsyH^hy5 z_?v=$ihQ}7^FOw+8Cf!~syR}RhCHv-8U5ZKG%c`aEzOhYs34Nr5Dr>VkNV;q5eV78 zE|SsfNByY-TopO8xUJMuy2;b#WaR(J(oH6jjV)J$+QabVGELA&&F~b>A|sAmf-$>- zG=GO(k7>lhxpSLGCrm;~1})g!&}iP~;=C*&^zjlo`ngNZHWLwO-L~u~#T|5@z}id~ zc&%g0lw!(_=4rl_Hfc8*+%c>vGMHI)F0)m9X4F#{nzYX97wKAc$TubU-`Hq8;QRfB zflHH&8mt6j);GYr7$9a2ftyZ4G7I@y9=+4dVE+8d4w|BxIns`XWEL~gtUk%)rw(Yl z`miLC?!uj9@^Ed@mQzVtG~%OyVl;S}zxQHx-Z5Sc%r(Tzh!FRx4X>8Z zWD>^3Ab>Mn{qNnh86zBj-M0zi^5S zQk@;#k5i_PubZUc`Q7N*K;?*3GGN{$aY0vTXNX6fn@J)nct-IpCt4=YXE&73BIWnT<>q(~*ch61o z;DJ_yVD*@##~quT)QvbsQiCvaA*v+V!UOWx`Cn1+8K9L09ri0_)=k#GE%tu7N_|w3|<=~ZFF<( z749gdAWN;?9)7cqEnAhFfLTR7dD_NYZ)ruxD9E6uL@Eb2cfx_k=Rw8H1{Pl?A#LMj zgaqrGNI91}mPqt9EnL)`B>2+A?-ZT^W+oO`VB76&|0cy}i(yc7$Pf`?_RM}`^V)az z>d1hvC@{YXoSs%w?AM>hCl@uE=xEo z{Q}U4a7TJXaqBcvOSd{HmDeK-2h9kZ&AAM45k!F*uo6y}@4{E>DvMD%Vd z!mUMjMbGPt49;X38noKeOYrmu`qfj-tFbjb=E1-ZG_8 zTwR-jB^ia zQ5dyBt-hF1<9t9fh3!+`^nxEt32_d$+w|>B;kD{ynb^?VHT|wp33cqM{I>R$DFW9Y z>di&}Wt7oRdQ8Kc2_PwbVt_^RM?|xS(5|C1kdw%4F*Ax(E`Mnqa*yJ}wwIu}zyOi& zjOe+WdZAJix*Gvo8)0k13Q_C67qYl%)W|K4t$;Og*=uaZTXuZX1KW&I_B_V+CqjO zZ2(d3Ap%9O9|d&Vaa6T`E8m%-KdC9+xltcB<~$wQVcc_4hgcSo65eCXT5dDux^c&B zvRYBABY^bvWOWExrfHf94py!YJrM!z5HWd=IU&|$)+X%=yne#kkX?NUJcfg$I$3_0 zWJP(zxKF=LfTwZ3@{CBkZHih(9Z--qLd(|1YQ6j(xH77N9VAx3jDlLit|`s&6IM(Z zYFR~g-1Q*@F-O2qk4?Pfm)84u?P2c{E-+Z%biHW~t#D|WMaw8Ty8Vus(D3WC6qaw) zvTQ~lLqjdYqa|;XLW>I23>S8aV1SlUFG~WY!mCzxlI}2S-s%+EZL^_ndSitiqm~a# zuU5kyAf`|ng}2nqPhqA{n{!#RzB!uF&z3>Wup-lae08X>8Fni9$qF%Jdi(39(YvKw zKZh5Qs|;RN%N=%ADPl(anPhjYIxrO#FY3ca@01e46k=={&mh+5x#6wFXuWb<+z8e< zf#@K`X1i)y)yrM$rx0#RSSm?^#uExYWkH%d>S$I~$eLc!iVYcHN;z zY7|1${9y|B(0m&!>Z^=)a4H(D22ST+-kjYu%@m;Su#eTpA<^_jMm?XL|BCs2SsurjPM;G3P8 zWf>Q~gdM1qg8nJhW<$5ah2B}{S8vri1i#y0ck=LA>KgkR$!G|1 z^-9J!naLo3*P^0g&{JYY3?3aJ%t}4Bt7dJ?GmJlb;Lk6ms}J83;%+BsP7K0GtOtEB z#8YRF+qvzvRT(~g_Dm-l3$dAjx#^$>Jhx3D)ifz1br_7ZeGZh6tX?fT>&cL@ET_c7 zdw1=>XzmRlf;`Ig^UD8^>V7KyW^=d|9K8~E7@&B)4cE7u4DputL5?Hh0TQJS(_g2DjH*)8n zT4B4ZoY`I42K;)1?cyw*@_Oi)y+m$j&fYO`y{nWvdZz!5S!Y-Ga*R5HwyJ@U03v#y zPH&p6*uYNL>6Zo-8JtSI?#^Ig8Zfj#c-KN@sNr3fD89GH#C?7uQa|RQ6f)dH0y!Qd zBY{W{88)61R$}|(jsIzCD2{L;fIvy!_KY^4WRUs&3g-#ii?%NGV`bNizblbTxsPyx zgaXuW(}nncin$~8EW;ZpU-)_uDAyGFP8gKliv1^fWSm9rZX^Vl5vwvy!{L@`q+5Q`VRU}PoqX_MIc$5g%K?QlT97> zkQd!|^rv%*8>yQMNM`Wj6i9NiHcJL1V6=2Zi{-|`M?=J>Ir=1OQGrrZBz;3$$f#a| z7)X~+Da@kgpN}vyRciOgo4Re0ypwYF%?i-5oNYvd7coHJFB+E?#0dPTnAI?e-VYR` z5mm-i$~zc$&lQKsRCHXxM(6Qjjl&o(OEIRH5pe%SiJ(_Wt{#NM!SamUy)Yz0ep zn^5%q8yw?)N@Kt~fm}8AOGYBUc8^1ZLQ;zaQx~+f)8d!|=TGJwUST-Na3D<>U(BZ| zVufp~Sbeju2@jBgzl^-$CjnCCWbk?99gb+8L@T2P)g%j>p|%+B#Ig^ZDyB^jaam2d zK6gXkKwQS(KJJTWat{75PPTi35g)_xdSl4^i|_(NOJ6r_GdkwFRjF0@sOQFpM<(8zSDd1f z+~LN!7*X0#ao{-8ZGy`79F3ySU#=fm*e})xo%W|ObAc+@{h0`m5dtDHLc$*=9uRn0 z;4dtBjsR>)PY_^*gAh71|CoUEdcD~B@reRsGB`a+KVPqxwD1(~^b{(O(6{VnudA-g z$b}k8B${0$>s3xSnHvisfoJ1uGS#78&94s#(q=|`T zO5}_GQNCwyIP>9!`SB`agV|abb&jc~CHf0~?AiG#JbMnYFpb&p8?Cc)|3P@aiSB4K zH4bkF)R7)2RFWk-%jw`O>&@ZGB9b?58++a!y4B*OfqAgFeo`l7U>f07{MO0?I+!-I*O zBW?pX9l{P;_;bu+hw{R9>|c@z>>p$r_66B3toAgG4uNun_=sNm4jT+9ms;m=&M{wj z1KQj>c#o(jyuaIdVHozC$?m&12J(ljqUxp*TCGkH=k8AanJ5wAlm`>MFVJu7V2$Wi z$3loZJxXN)oB4jeHQ4UKbcEN@(Uhw?^VkVM+%NE1shkL+A|bULkdCktCiJL<=H$2} z=}xe8k`>T+~WJivb@KSXv>M))9U8AM{*LIX!XSep>T!RaJr!LlKbIU!EfOo?;y^hL-b>k zIJM!WK8092JWDl)tTrDZV4h>d_%ALyHS}wW=p6XOFvj5f0bg=6EgVOJvT6X)(cCef zNIW4ECT=Z!cnbdCFkoG4Gu1=_2b%PkOB|MvM$`#GFGj0iz(wijK}{1xST0QGFo-L# zHaA*Ly4p_xMM6FVp_sHv5RUzz{A?@*O=?8F0rx1*Ar$s*btKun0nLrDmXZJo{b_9d zE0u38UN-8!Q^!4$lh{NfdUthY1Qn{_87~6<)ZYGMELIt555mzB=dcL}6x6iY&-L{p z@P>m!*b^ViVKhq+&*CHaBt|feI7xS1RCh8)MV>gQsxp)j=9dDq^&>{ZgUPC~9WO|< zp9dZG^dS-Yeo__VTzS5d-O{`-RUJNryBIf`tlAZdkRcM!iFK+3 zJSS>wRM099U$q8K2e%ffMkm5>`bx&ifN&5d1&wXiebr-x1`A%OBXaL-)#C0k_K3}S zP`N0}$Mw0>DL8Q93O{xz4OvuXTU2_GtlaM`CYWqu&xM^G(NZW$+URtpq@Xe%k&XZv zAs|;WRTem;)ZZ=epD(Be1FG~B#8?4&vs3~h;s4y1b36inb4Xhek(RkPSt?>74;hsO zey7YmxRCi9<6`yKtmF<+Yr1xG#wbI zWFhnV3iY=iWE3gF=0?UV7NvL&sc=bxxmDWG8B!ovIWQfO3gK%GW=s4Ha z^DOv-njEuWt=ncnI>PGEGs1;t_#i{vaM&)vDysjmg4H_r;xI~sD7Bv7T#WCJ$2go} zJ)~c(D7A3QgI6fMpKvw!MkNCZU{K;kEz8%Nz7{d6fgG)d$3y;{_`IX+`vgVsZ}5RX zz{WX-Q`pcakdT@+L_-||V=tfxkv_~=NDWWjQ$hUuhQFkF65V!Q0Z?5H?+oki>Xg9d znt+UWn;-(8OVWPCTeWvakto&s1VOk){9fQ`-ooaOO*S@h)+ z8yQpkBzmPq{*+31#P^&naC1lz5;$*Z_buoYFJ;JU!-F`74_AsYht-0!x@ttiUyR`) zD<)N`I-Ys#ITs}$BJwNa8Q!Gg_`m0yTLFZ)-WY-1bKZOc0D001KqvbTRVaj=ha4r3 zE%uk~sRW@}w!CoiIa-C+nz6@H zfMWC?WaiT00)$&2%Ib&={FbE3Z7UM*;Pw z{-hXC>H?^Kc|BQ+6$*SYzlsgzgK)!}#-rO6ZUAHHrYR#Dby{96nHr(DrBRvzbkD>H zO}@s7Ywj$i6gQcCjcFlUN!0jTlbsY^Fbe|hjCE&-v_q*~1E|H3iomMdK(0C7I}B#o z@}M`B2V)MDi_tzEoEZUf?OG9gYXP$dl_i?R48HGA2W?NEEdCOMWtKFAslG_Ui8Z7Sx@USim! zqnvp#h>Ey-`aJ!f)QH>&M3d+e;(oDhsv68GFG!3Fg=1OXHb!dWvmPX6bUcV2r~|Bu z0ypEoz<~x>EdC91%S}~{!fC9e5^zYW0akL*qV%@GU80^23FV-qWBxo^pClFO|1na# zkLN(82TgS&6^>K~b7^JdNQju39w*n`AL_rbcIzv2Zo_G6QJpqMY@?Rq)d9u)g=Q$; zm|W%satN%9aSrArxt?LSA(pt-ezjasBn@07^V+d^NzA;XIf)nMaZIg!;)1A*)iR;x zno&iEsK{gD=2f8pz+LO-K3(^@Dl?V)55^-o#{MP zME2H!avm|yv6U=g8l$pD7NbKQ(89QVrEyXRFx@n1MJvoD8jU2VYtzQ~UXPh`8G*&-J_~w+U2k59Jwv2l)-uN`3xX+Bat`?^KjHxOR{3sBh9?Bz)tc|IL*c)U@%-1LIIYmc} zZy-dC8)x8JW=MDA-VfPM=_EF|GN$UtIn&-xQ|djf_71@!v2$a$qoiKx{cr@Tq1x(R z^b_#UV-sn+5up|aV)zB&lNB9JJ+!1cLdZD@%X#U`9(R&Jl8nmRTsMNKZ|-L#v+3e3 zdpa5|x8s0rS)=qnGLn+g9@#3vzD`ZpwM5C|KynaP6SDDld}1u!UowGN`??&mwDU)RqqZJEh^dI0ad?&$*~f$ zpDM9G?w`N1kb?{55SPUxAiTPLG!RMvq$BA`bbh%J=e#x`XK(;T`OF+37eslWgNrdU z!!tMwe-zvG#haN4M4Bi8lqn840V5P@@pc&U90FAL2d1%>jB=9Jh3V%Gwc6GY!wXIK zBYs+)l@$|0!-2}$#Y9{)r$?;CPyg=Q|=3u%JKc}$@F9XNKS~5M$)MBY9T1Fuq zqSd>b%jSx1?9gevXf7LTft^}MP&q?(#+dEOT9usMc>1wJXHlbZb5_2N{Ih=CPK=m@ zuH6$kr!CM{CkR#iGxS9}cW4qHymC8#=`?X9M=)=FR=>BOJ9LP^>J=zG+HpUp!Kb)p z48CuCy17F`@Z~Nf++@cN>A0oS2+*z&Ah5-2%}F|QVOkt|_juRNTCm_z@tkx}=JbIx z;|vdKaWMweni`$J3~kzhN@q#)q_T6CH0my{aTaf)(ioq{_R0m+J(H8fq4j8tP;EO~ zFGYdsCMvaf?L4<1$;NehA@EP_hZ4&;}wqjz+BbYx4x`M zLe6$B_?Qz{lYBikG(`o*)ljLr`|s{#Hy3;snf?&YsR%}K2FfpXu${T!F*;2Iw4aoI zmgyKPJWD3=AWUFamAa%6%vA6pQfhoFq{K7ohk~C*iVF9!>f6a>{Gx6u_#raxVf3T8 zPh&#(Zx)lyW=@>%K-sl-d9?%GxaPBnF;3uQlyuG&=q6&*lI%h=AlhR6tpn1{VY^;Z2!-1>1Y3haR8;~64I6&!;MY}oYr|CoZ ze=ImHQgXUZ7wMq}*l^h@d-X11+ey`FJ&g+;&tqJCb=EbM9^$fUGd+T)pY$yBvIjeW z{*x}iLtKne=g&ssCh-ztm%yM8-RXli1`I9xZ|NzMHf~U=&6qCWf2WH5@H*3uR5w#iq`_NnAy%JBu@XFa)HC83PXIZM6w8q2 z2{Z@M0nhaYs-!~t2_UDDqK58Mq);84b2p5krIXcc);BA8`+gY1d9`gz}WEPwL6iy-|n~{d45hL0x z9MerUX|ZXzPKYycBIhu}QJ5vu>an!ff3yEU^jM3R;W^LMpn07(+j{-MSz)3!CL-A8 zT5sllLk#`G1x{wl-d|LRGPH^r4kN@4kB076vkKufUNWO3!HBb`Jy7ax27zj0JI)o@6&sH#n9eIJ>o^^~%?>m*@x>Ue1ouS@Y z)#8=C=`oZoV7^@y975%+Z3=K(ojMR|msXv|XnsS|=F}R%l2eW8)M+8fP=Y zAvWkW|2*0y38#^HMR!&kdY?Vwk%^s}V1E`dLY*1rQ{B{fZr%EaA-PuV=4^jBk4w1z zq35^;nSTAl5F4C@z5JrAuhmTu%+{fZnVqn@Wau}_h-x{pjz?4zZ72Tq%AzD^fXqK_|y?UhH0SwEUgw7kK!w{=jt?8l*5d%iaor3*V7@jtWV|axjKsv z>kenBWMJtRUCrU(;eO7!qqg@1MO36wymrmiBre^StJBmVmpJCGTEA@`CIdn4Pl~PS zd;b!*0~v3cjFJd`q)WY5WgJ5FOF;P!FiAzNV*`P^Ed&Q zVR!6%*$`MTKZ(LSVkbj_F(?N(sKHzY)%+10=ye~HK?)KJ87wR^{Eq~^jyo-LKMpxb zAGCFPe~2WE$IM8D3CDU$O316C7p=?}!w7bkIHEYX zD^^R!ubVM^9^)rS~mu;GB<;9IR%E&Z=%8oyNpp2Lv5Q0U7BpKFSYUfcGK0O|V+)^I?r^vYG#Dhl@2>r#7@i`w)c|G_(K2*BB1$Cg z@b(ZUU)mXHE(^Wag|%fs;2Q<7%f~G(AVhP<;@%602gmmeB`DxwT;#HuR*S_gDe}Na z*}oq62fM4e0Iy4TknYBhk|XT7i20a|ox}CfjXN6nvX(OKNRg0@;;5!P!<7i?CuNx+ zF*F87%8802B_p2}@9yW<$0j<2EG1YEk!B;-&;F8@u6Beql<=*DbP`&e&pJ{#%aKPL znLJrlKpjQh)8Vj(!&dJ*BMt3y=bRCS)_p*U2`C)k8S}~b`(>w=gv}7|Q=SwXZ6ZqW z`z^lZii87{@uVKUL_E0iy;%A5Vp|mJel9?U-S()T(RlS%zWJjx!M(WxEjvQ>c42j- zZyKo0Kr_A8y`bvJTgxENrF;(v8_>d0u00qthT$PxL>9X&0DUSaS*+7Wnu$%3kq%{= z2{|t=S*6}xN_*$rSacezsJ7>X7X2aQNI|>Un3Eb(^w9%W!AtW>wJ~$bCFim`aRxbL z@bbsV#Mf5Zlkf#ItnwuRdlx*>CY&aI^ zjxZu3+}f}kFZM=LDj>thJ$vQ|NvIn1a*~8Uvg(eAbK85$ZWoHbX|xexor%}Vc16a6 zd~w&{za_F}{K&LRLZKee4gJB8ktA~QBXiuTEdD8W&)oO?%PUEO@eyQIEvhE491b0* zyLb_+pgUK!Q$q#cEhpdIAlzK`(rzuQwNF!l{19XL*iL;%H~svU%YtDJ-%G!d*ucGC z9@J(rdtpk4Z|Jc2fDjW8O*W!_;^1Q^=42Pn&Jxti)+oO3Yu8=CDqJ zA1NtQ;s;+L1U)BBp1y-O%4(1IXE}+8^#?NDiorMDhXtb7uszDO)vujSS+K7)-@u_AtWd@G} zrz1LoGz*=+4I4uy=#=7chrpBN7AQS7n9h@K1}_R!QdolH0cFT=AR4bX zJ4n$BFZP=J-in-`B*Y`M)LT{If!9I6p3EG(-`=FUx#P~qYI%@Q!}g@Ah*nXjR4!M> zKx;J~U>EwJun4vPMdSnD=cm*_%)~Zl4eXlS+l$aJK z=2YF-I9|czVA4qo1sU8y>Zeldg?UOlC^I5E1A32e67)=8Vex5ysI8I)8XPMeJ23>- zi2KnSh9q&3U?MB41b=msL1V>#(&1(_eZWDX0r{aA1;E%yenBR$FffLV#^v0l-ta--jM_(F*FcP=gzx0`IJcBYit?S5Ngx0rA;3jywX_b3fPh+z z1}vWvtc1iBd$9wCLjC6j;SY&P1Z?GzB7)+87O!6jNFWORBlC_(Q%HUbyRZ5 z(Ec@cIU33CMB{ej9!^*iN1ax~5|3&@>a7Li@aUtHEIYmCMN!+rkaX6YxLD+&$0|31 z>frM9%^~OzMPW5fDN&>I#v!1ah|oH=AZtIcVCh@ztpj5!=gqWpZYKC3-_S$UttCWS zJuzG%ZMU)3H?9)gC+KG>)Ap?0KJcLEcBXVz^4#L#s;w|;`2#K@6f+ix*jUJZNSa;l z1i6XtsM2rCH+>f>I)yYXxTB@ni1UAOuDBeu!oRg5c8V4b){VQ8rv@F-0WZbWV7@lt zgBSC?U@<2y<;yf8K|<3$b}AmCyI#kf6{*@On0j5yrItzY1WH-7{dlN|H!et4J852O zobiq-8Lx=}$88V;Cnm{R&7EydmMMZqx=M+mLgqX+nK z)1r^>B_mMjnp&Lkn=^(4?xfn7@-Genf1p2sy!hXUT#Q8~ zbhXfC*kmF#z?O+0N?i}}nCh|CsY&@+)YAoKr4fFPPlhO?x`11T6M8QD0Z+}KoP<7X zgo{!(6t>`3a4DtrN#^r<@y`QvoMSMw_{xS!ByF8Di@k_&F{c@WkPlJwXNgPqKsmbD zDvDl6(kA}S{cJ2FJ!etsL5c>4nHyD^uOx9?sw*eZ6A^Jk|L0%CGp=; zd=K*ZSvw-^J%;^u3p6ia?PB7KTbJKuIdBr-MC#60&2+iHvnDxIDAb zTWW?*ht$cia)bCqi%L>ZZ@J%G44+%u&jBtJtEjd&2ekaR4ri;T0v`b+^bxb|+6M10?j&PwRDE+GrQ4dLvK##S#cjUomBEwji_qfOge@lzE>^5Qx-4lO` zMPkl1%B9B43FH`yoZ}doO*3t{6k1TFORbQ!u0vJ%Y3w#k{r8 z1j7hvi7@n_^pfF;cBc_i>_mzokc|U&>dGOH>cA>?>Yh1Q1x5{6bf<8XtO`R1$#L|# zhQBX7JX2CZR%H63x(P!8zX#+fl~I8|RrQ(U9wKC?#kr$J&lQ~{bd|+zS#7pzii=sK znf5^2MvPW7O`ULu3{|z%0k74#OS8MVOQFwFbdgmOW4atk^=!p<%~o~2w#I#IwRZk? z%F2m=t$gq^4Lv&olbwD!0>opCw}{#iH)VROYHa%cvU9vNU-xy0iPP;B>#OTK-spIW zZWMbs?GTwnH)2JW%X<--DHJK+11aemRF8t2HTXeaXxbAbA{lssj#DniZ$ex(&f2Qk zz9E*@jVeb;)Fi8Bxf2A=(*!#?HM9q5fQlSatV-}|DZEvaaW)C?=JS!wm@XZz;CGNV zcf7RuX70^tQbhIJ?iFbQ`;_G%i1l7MUtSPJ}n%STt*ZD(UMeBFl4Y} zgGt!t;A0Z>d8C<(LafjHk*M9m1wZOH$y0&}N}ou!9p^AA3f|c$obr;-fuRipiHNnV ztfQZvt5IWf?NkkNYLV6JZFVCQ-lUJ%nYw=53AjWCV}dSIQ&?J4e)$|461UOqucwPR zBhGZ9*qMrl0;Pon1R}HHTwfJ~X!?q0^&GUtnW~cZStTXYd;=Xj!A;SGEH6YWeF{21 z=uOg}J_e}TxKdf)mT8VrR_}nDW@e^!!r&lne5pM6k`Wyjw}hA1aBQ4QiW&Sf-W2uU zpGDXb6Z|S`5zX(*Q-YzGrzz1v)t2IU;qq{pWF8l)IL5df2t_o}(dDFQsO1OXf0%bM zqfJWZM1(e1lexGgRQD$&MG*RG37w01=vO0gANW&ss`=@;bi5kN`2hk^l}>EWJ-FJNpi?&$Hm0TJo#v3ws4>$V)*5tZ zF>a7c(*lP(P*(@c)Qy;kE2g}O5bZFFl&;010^Mj*r#Oz|qzp&eO#SEwPIP4GkUuwH zgHciE^(;M9b2Cqj$!Ktw9RbzEle{#gn;1k><8tj78d)Tg7VO3)$&3i9F`1i^ zloJ&uJ&r}iDK6~LnFA~qmtI$-kRh}kAmb~o`Ht$H8VpPr_EYDR8_d!Pv{vl6&-L54 zgy`|NMI$78vhFU^Zh}BVPl|@E<|htRREawKKOoEVd}1~=2%^H~;xQ19XV^8J{L6=OfIxH~bX-KmU<#H_FfN~p!lLc-5o#pE8RgtL-yJsBPfV5(QbFM7fTO7E z3P)*o2)KBg3t&3TPVZKrs2q-JHC1MycqJb*XOJ?0(zi0U=10^R&USYTc&?u8j=?w| zo9^e$Htv9Vufl&1DH!>j`4rV*2cadlY zEL@NgWF|=9uE$1M(>Kyr^IxVkjBUmQMeMi(FO~0R&Fut|E5@Qc$lW6W zqu9@symzw+t#{>yM5T3>RS;CRzFCx_H2}5|ShFT6abZkWS`im_cYZ2k#azz#!*kvh zVWZR9cVa-Mr@Jm6kICeT&oYB{TB&YFv}rMyo4Wa|&6KUIQ3w3s1B@X2VMW<~scZ-=S>szv%^%KT!cZ_sAO%E02K+N1=!VBYF%Hq3Y%y`9iCLqY9 zDhUMa&z-{M7S4CsaS7a%`B*7UZ$guY)_-o1YpewKXh$&jRK^6SN>O?1HeP_|APVT*2K6Sx3{)Lk!=HFa32MMlrKy$2B2 zVf66`o22EJ)o|06|Bx^}GK>jjC&)&bO?_2_=}=)_?fteBMsE=*iII5l_>Mn87zUWJ zWM?Ie=+qgy@TZ%JwGEeL>B6+zY3V7?c?Ww=O8%l{E&61vQg=5lTJCdG4F1$3mD zVzZ7gr`e2sO@RhrxBD6gH0O$^EfYrf(ctZMe|M8N`=rGQcm^y-UiZI>fwd8ktUtzR z_$a)DA70~7976{I6GZWBBfC*M;LSrxd%{qwa26phO}(dt1LLmPoc(c_va;*lQ_WpI zY1V;VHlz;I?>+4O3C_UYKh?mVK6e7Pfl6Xi(t7e616M^I!pj~Z+PH7!!pk_YDG|tG zL$`J0EwE+-99n8=Nng{+lO=(+CKcV<7E;^gI zlCX9ntN>OSss(&UgnvnZ$iwA`E`rUUAq#P(h{p)4b!0h!-_YWF+Ejd>NfEKao@E1p z!eZ}B#aRcIqE%U5NlMR4?NeDPe@TJ*7<{?Q*Sy5(6I`RQ?7kT4GV&hDXTi%70r~me zr{yU7Sj`~8RsQnxb+hky6Aaptb>$ry$&hjJDP&gVna0N%!uTifA>J9_(>m;*5a%C+ z4C`$J>u4>z$1*HHd&^MQ7lWhACTs}@6TEtoJ?2L6vTWyK#=hqtf~rLM2r_Fq4({li zz$gq%DbiPRp^vOth{9dqT}hCG7&-`ico9Ws_+e1-s|TuB{nfTqZi9rAUkn`R&gLXu zOzj`5hLB*~IN!vuzVOV6b(h1g3Dz%NYSEfHnUs>Ci6!8}m|SFwNROjB;h}FO7t5%b zj>te6mfTW?5cA>8(IoMTu8=Xgm?+OKT2`6-l4L0JH|U<**BA=rNXMZO76oI$KsK4rD#w42oD#Gi|9woX3zh!-ODdMhe#`B)17^4}+y!a8t zdZ;4II*K`7Sx(Aib=WWpgqf+Fs&7_%v!04#4H#c85#mAFAKuC}g*IMxlkN9mxiA&< zBp_oSAvym~{ZDD;lDF%NYHuY?KI$r<&#=>EyLu@Y-%M=hU|1xIf&QT;LVhZ6urnHu zm_1MYN;xaQ^83!4Sac@qFNsAw%Zu=;Sti2X&R;4y+0I*#Cpk_z%zj|%1Eh%gJ1>8V zrf3nWMra&)azFfi9YMDep#rXst2HEh(a7jphM(EWT>PU%TdL2-K_2$Cho?la4Rr}d}jaSIpqY?`Kk zfx}1<06Z#-8mR4EaO0BmmZA?Twka5qxMh(e+w^g8GAzGlhzu7!smQuh%5oWUQE{K0 z_CxbXh20BDEP$9FQ-ZW(w@Z&@P}&cwH|^(SevJ5Bh3Ic|L$FkQ*5qQfVF9B9?tqAf zT(n%4rw!A~6u3(m^ercx(WPHT39tO9hpgAN4 zYA!FTZRG7DBk`ueA;8j#Aj>+b4U=F4^>sHcXG+#z_QcXBiZ3kcRm%w%J$i`boqEnb_ILH}gFNp{Qi9&?EEAbS9>Aso5?fIS-@MlNbUaORKfTYgiYrhr)R zZjXv^hYWgvD7AYq2Hq%JGoI8XUxjG6c4a%o)u3bMYARJ6qGi2!g1HZZmodxYdPrku_@IE1K0duf2nB z!3zI`D2l3X(U%!^6yUVx6eJIvjs~`kdY;-mJgaYWzdu0n12Wzs-^J)m*TbIiJqO1# z<$7iVF&MC@_}(f^bID#^etT(^o6SZ%qc10q#gn{r=!Fd;QDw1_Jac6uzp6l(`yN{5 z2rqM4#J|&rr>=V+u;MF9xmsP>;h@0Dg`Fl8awWgS6p&w^V&-e#tC=>hJi4RjF}o4u z7`x7fV&;6Mg;WtU7k59-BB&Y^gtCR+b77YB1rOQHXvkhu6x8bAo!FI)W=AU0KO!T; zmj%j*r$!ERtt0JSdJ9l?wqe7u)+EgVEdfBIUL<^|r*`_%LrZN?pKMg5wLn{h*<3G`XWozx(aaCMSa?w5J`rExKY}8-^0pIOTPNzOtp=J8m{$` zku&E)X3=?C59S)Gk-<-C%VA#ticl3=n_ozGEYOgi^$sFUBCmVZa#&*sqN-w`> zZ{-?%Sf$QlX3piggb?au`6Z@v)$RKp-cYTkY=ILLmK%Awc)qEinkAV$TqCxJWKO5? zD8h-nX3j)z4;SGz zpI8+rx*Lh2RbRVg4~37GxwF0QC3k1;dz3d{gw_*dGUh_77!7P|q`>^}&}Z!K*n++J z;dK^T>SV@f)rRcL1Vto|-II_I+e)otf8P>m;oJ6fTz*Wu`_#?^>chyH6{#g&;421< zK%?)CNJ%2yJsuaYw55JNBZs(Fi&okf(Cn3ak)Iwbs{jeffR#NF854XFR^bKIQp><5 z`D%g9TDHSjmS@Bp%XYg;D^m8KxL8~Nf<$CNs}6|MwV~YAlgs!QtNUdx*i?G?3XrXI-wW)w4w50eZT&3OS}XH zA2EBq=2Tn(%Tp}8Ygz&GF|!x7Qo-9~>;<#_`qdrF_hl4&r7|)GG|gfQXy$6o=pKg^ zl?+EuSNZv?s$^c_RdXlUENn7kMd+i-!;2LcUaMnVEdoVca+2t~+|f&}r>5a+@j>54$ur0*&Z-z|D9gdMw73k@`eYNH+X`;EsGi zviYeP1K8>ewCg?Uv&Jc2iny)&xYe~cteDU7(h3lm?S^6oxYaE-S8Y=hdMIw@BEDuB z?cMgE_8^bs?|fRc5Wr-km&;ZM+kw298((QNwz*QSvHDj|(~hAN!9}epl$0y+R#>m4 z=Ym6fi`?)!rkyD~Uy}Ov<=4@UIKo(^SY2tbSwkF#CMG;`h@&O<8UZqlaapK@zm*e0 z7dRtPCbV^gWUo|&_O*n+f0+?*5x26KW=u$az1#H$wi3OoL1PiFccBwt?KNF8~F6b5&%w z)#E8_n|d)Wrhh8N@sXSPC9DWyQ8KDgoW>2LJW~0o1J1|nADWK({dz{hyM|_UF>8}6 zs|xCU)a?C1vcB>?b351k<3&^pM=!L3R!0*W=sesG)ug?=m#De9&~lN!2*JoEzU)xn}2;x^V{@0+!pt``2N90pD%(*Lg8*k3hZ*K#rZ|m0;C$O3?3h@m@ z&@Goas3}n*+CqD`B;^>lY%q*DCDCAK;FXBsU6Cs8EnTOe1?0-8UW^nO1lpTF&$r)D9PP| z+5eC7L(=r-BcX)7Q=T3`GI9@Q#_7nLrF@2;($W0*xiPn&YfABqzF9j^f8M+((?Cu` ze`M^L2DN&gicSRu@eEBR7|`e?dj8YxZxl5$*oGD+`bQsM-+%w>x4>qQ+|kh&3DNpD z6;hhhqO&`TCX1v4_xirY%{nj+vE-XfYcpK7PhINKk@s{z-6$z9sxq9(4N+{D4r891 zaRhEYwB5Y!w3f-jK03!sQs~X5Fc^%*PUKYOdLuZ>*si_xgCq%KwwP}~beeHrOy<-t z@g#%3Xl7?1z%PZL|Mb`Q-{?Gi(V+ATyEB371`}k1W^D6|D7T@dtWrbA1Vlt~g>J)( z9Ci8Oj@R<&b|h>uyuqI9qZToaB+GwnmJhB$60F$ocbxg1@k4aO$%3oz7Y+IRRgQwq z4*U++QWkb7cnuOi1PIx*%?t(-7>_dVjNO=A>wkafYh+^xqdcyn4MX(Dm%AM+;W-1_ zlj+tINXc{NFn(@diufNxioHx@q;^lN00%%n?{8+X$uJB$*_2Y0#h|LWhC{_4G$KFj z8kCgo=B~Pi_Qqaj|~6 ze_W+42DpxBZn{I zf{E1Oi~LZX|MOt#Cd($NDZj*#V5oe6(nco1=uU?Kvrhr!#+>AP899T)^L*gR;2Q8_ z_F*c(jt{6(SCDvPB#Lj_^l7z zCcIGyS5Tsjg|Gt~x-duY0`8DzvV($QXRLz8y=P`@e=-Ogk)MlDoDPV{;foED36jj! z1VLPGB@pY37~904+XwV4DW^u%rX=(tj5zGElDBRl+li5N)BvTvo232XOrZb}Khl#B z&*8(lqqqpCn<%`|Ksk#OoCp_DZ$UNx_tItZ)9PyINj-=8*n)o>TVdrJQw*byA9Z?TLN z2QaqsDqRvL0Stx*>@{>nL;d$o6oXV1xEiO^@y*3ST-Q*i}j#i@3#&7zu+#FQJc2Qj4PehCZlw<|ul2_?zUk3mfNz(!2ISvkqdgioT4KSV{Dbd}2yP#bJ5A^^-JdPX^IGL4~O z*cWv=X5y|N%ub9*Xoi!oW_W%Rg}@9$L?X~T{3TRK9M~nHd4+Rtd50c=g5gXOqsxh_^3*Vk z_43LdVnjE*rm=AZd_Wko=)^6hIeQySN&w=FjR|M~GBo?+3*&?Y1u@+RjYr~9;C(RP z86gP2@w`HaZzL>8b1c_iN41p|E1|CD(o@{UG{=I$ymU5 z#0+3!&t3K1iHOsru{ z)Yp-yu_UzWk0=9{4g;nMUodLCKztySDcL04PMG^+PsD+DM^0@F(dc&)*y_vr)b?5C zz-MYPoEA}_DH>89MZec+Lbhiy7xb5(d1qrhW_13!`eIm(y^AYGB-rX$h(}W|*8D(hrJqS5&fY6vHSju=gOzVcRw4fuM>=O@&O>xYgB4Kw5c_TLGE@l&? zur|v;V%E1>^>|x~jO7U!{7>E>W|)l3l291Ba#(r&)8zx$rRw$Ix`@p0A{i$cGo>|F z5Q`t=g?U@pkfeVT&Dihu%89^RW!M&V4c}NQm{%xw zz84~7mld*1akB?TWmcC;(J}O0tH7{T6rR}xku_NXL_TI;CDKX?5YF+LO zze5;Ai`HX^Tn0gjH?068;G13{_6tS&M2mQuh)zV$E{J$$D^!F>iFcr&PzAK_Bs+sh zJ0~TZ$MRHc{TbOw%0Z?L(QJyo$nfb_xT*(*INulx(05na4Nq!m<`u>gIX9FuzO>SM z>0~UMq25XBINsU9m}fEu%6;md_Q)Cx#6Z><>*Ws(hY`%plTYQrB!u4-84+`#e}hnj z?mlEw_dP2vDuBixKfl&=&g>UkHPxIBjy0$deNvQ@=t?#gN;#rJiwY14(0rX)Og| zq)tH0`0W%sVvh5c2~T6#B(Cly@+SJ>e~l%n#pfw9Bjs7?9@Ee091^Gbo@%YiGvCCa zsH7E>4NgRn@k3uHAj7exr8dR5(3MspQ#3_>` zQY?nJ304U%lJ@ z+StfcG}4oG$OPU5xdLXdpm#NKooN)nh3S(oi})Hh zC7(%;54PV!$nUU(t^o<_@op%_Rq1B&1PBz$&B2yLJP;0xUms4_#o=rfP8d5D-vp7` zzA+se30jH1-|SErxqtx7*4t1KO0uwrjq9bBD_05Pay4>z6Tq-fz5!UPuVQ5x*-k>R z(9p;iU$-ciap=!oDuLL*f^nuM3z~NDIuz#Rc_eP4Oz^V%XKZWN3o)$yq0O9IBA{yQ z9rL8oc_2jT5_iEzqdWlW1LQ^9qSY+(d{SQU0C7UCSo-Ygm2a49YF z>ReXq$|jVs#u%k#OiWPp1Bb&;`aGxLLS0H;a06K-Ph*Cs`P3M#1R9Kpqlm~X*Moi` zb}cU%I&LdFM(hP9SwlRWckBv+LI~~>EhJG#oQeN~n5y%fGRkP&pr8e-1+36JqXe3l*6GN~_|5gW4mI0FA!0*u((+z~kjis=TJ;C{zq6k*T}d!=FDqf-!$u zh@@QU`+=RX%;2kh|NY~M9Eh9O3;{`ds#%OGHlkU(gefc+=)XqA6BS~NfyUiP<{T*7 z!^J4;>*90yLxdf9%={JPsM8&8k*CP4fRYWy-)xYoNr8^?9Iv3k2BY_r}62zNeA-l$}uz_{RdUQR-SQ*wkfnY1^ z1#8qRMg6&>3d!a)Ds>acu%xaAi7(;sC(q^b0o3n0Ax=G?r04TZ7|H3332F2qZ5Jwj zpxzPV^XsSV@WgCJ(x~!-;yaX`htZle1U1x(^F`F3s!xhelJZ9)P++4JfZB_3zxQAy zeiC4;=?GIYa)RU%RgvI2&W5u@FE^!DFet?`#hb9UHfF41HL@2l$;#uU)J_oqbdY+% zx5b#aslZONgd^jEl+*%AB@Yg3^y>pvsNjT#{{Q4@ByHBkQjR~aR zuu=XZ9mofn^|Xs}$n`OIT4k?hQ%#>zc>W8IFP%+=J_PKgqhSQEGZ=dLmxD~Drys^9 z(XvY;5TStGMs2h;CQMN7TWJvGAdY1W=Ap2OJ3lzfjNU^f0*4`leTT)4gS(AP;RXbw z$*Bo>s40pmriAQNQkP$UeK^d}Sc;gt!Tc)Up)s9+DV`U+y-|vURdog=7L$xZDy(^M zbl>H(5r|Q`45xswf>O+mMP}X`uiWQpIF@KJDKaXBB%`)iD-8P%-diInD_KAjgD(mk zTP2pTcpFrnCB-Acp+*QDAr7&8h`-|k=i8}OCI0Uw!cp(FV2_cUMF^3= zl1Nje6{2TUgk-W|k)a7S ztc6S&bqAr`B=$zRF15#SI%S7P;N=gyg)}1ZD%D03W8TD?dPDO%omeg!Q^qdw8p??a zMwk*64-aq!B7h@eENhy(LeCuEp#>GDr}md%$+pa`k_QVIDFq<-hmxXZS0%jtyCLM1 ztI>uYpZAK%V^Ro3G~)g5S2p#o8kj$7tHuzGibo(|@*+#sii3(jFxH2gh@X*8tFDUW zdikp844`ceBLQ26cezO$;=x3oyTvFwgGVHTifA>BVo8l5J0)4=4bg9zbIo?z4rFne z9FrQWMWPckbXOlO;l0R>Z3X8g9L^PIMmQiJ@&mMzb4ucF5h^&6OOf~qpEg8$7-1?sZ$(HJ;+nfoP?GR27lz4Lo$hNT@ObpR}KQN*#%ap@~643p5?iMHrE~#|6S) zM@rIbut}>kktvE#8_KCl2RT8tCwUl6a!sHZX+`xIbD>EQsm{-NZ?r>vlOn;+#2iQi zOr#Xa5-QZDb}XXOZ$zQ?uwz(0XGul%9}yu;D2y=3b)Zt$IRcwpjD|o=SeW=5WN)D# zYls*;Tu6?MM#u;^mT{$oDz&jk%6Et$ zJ{Y%${)b0VlzZNvMoNxZ(}Gl>k1#R*7und7tAaIYDZsu@)4(a_aD>VYPis&yt&r3$ zld#qPfGt7=RTR9pMp9O?fCBGBQZ}-{;l^6TYKmMhV$tclK*^vV3K0v+NbysM)Ka`O zVKg@6gfjfx)u*9sRABuZP$ckiMoAPP8foIqPBibdvf3%wh@H5Yi|HHKMK^U#4(Vn! z90vLi6J^-SP0HsKad>s=Mwup$Pgt13QrU9ITBh!HCko~8)9XCX)4k3;c#$mBK6mOXcH&FhP^*y;2K9#9R0}p-zc@i8%jJRE# zDux?#s?p(~phy8foHG&=FA&Yy^t-*-^zVjB5ds%*C;!jSZ6jP*K~{r8bHh(GwSfu~ zS!!12H_zrA_fcCW_zgHn@Gs0rgK=5;gQZ2@j*u^DYL&WfdvFRM4rPkb+OqS&Lr_6u z(J<=^s`_wcMBu1a6PcpM0D_CiBC6bT9#XL&oF9fY2qu5;rUw_+#2JXZHdu$y5Qcq9 zx0aVuGZn(XV@8*YL4yD#V}>-^l|M#yM}BD|C#$#5fifh}G2lasHV~c1JeskboR+t6 z^uih+lFq!7F&|n$mB2=H7ydB7?X`g5vp;ifY3O#P4WTN7oe(Hj{*h!XOu6M_f(v#5IhTZ z!dg@*GF6_UQ#5tRdkTr5&r!yDo5!2PVxwZ6>I^(~em5z-Wip}uR>*|N1rjC>)v=hw zhk=LGQk8*PE2gI8a5JRGNscQIO~qxom|q5|k}6fA8@5xJeTx~zkphrL8{Ut_nM2o zd9DTiB_hD%Jbq5Q=Lm%4301klYnc;iUmJ6xQN0`_m0eJ#iuI#4x#?-q4%eN;x|*tp zp)Lb?&L}lPrP(Y|tqhKif(#ffDX6-I^~i1pg509wEfc&&=;|<>C8O$iCgwe#hlzU- z{1A2xYl3=vKxz=i&@gPIqWAVO!?9#Z0uqCyh%1**jx3BR>6$C1R(X+Jf53|tP%WKl zb}3T67SA(qrZwO)oUjnhz?m?(OG{?+vTm4{;3(<=V*+Po*AynqlPD2y?F+)A6j;$@ ziyJ{qtN4vn(We0;#PL-a>G+LgQ86$G{1T!=X465JsEhi>M`n%)em^RU-`w+(!hvUo zQjB^*QKI}ca26q0qy;sR7)v;`S_#N2@9aK``+*|$OKw-f@X&E!CFDQ^AGCz)ccDVb zkL81<6|*zsV_-HZg-kp=iFRZc<6y`M{!kf$n9Q(73K(nhhw2c?6+*`c&FRR|xEs@AgfbO0fI#GR|cm{M7=c$A1kfJ2C)x~$1>Z2TM9EK4Lq821k z6bXTYQxd7j5Q_OojH*1I|5wGu`+xXTgii?ph(QRNlwGn*4l>4FKsyUmt{!1E4ZS6H zi5aH%<}p#5Z8t?qR9s&yt@h6H8Pz9&PBVG&@RBrIrrgqeGfq*x`!sD+Y^Pc&5>K@J zGK=}hWO9;geOWC|F#|8T(}~k%00`FcYqD~EQaq>EWFb^)j&kG+L#5|-RfFU3Md4|K zYQpfQ*CdIEq1|WLmB(`M84^oF>Cyy@O&iP90}^G?FWseQQ!^i}yfXhg?WM@*SQ4f$ zxw0Ln`=6*U{J=nFoV3g^D;CvQ)e~j+Rw^U0T+n5-kXk-!L@>n~+hdO~#N7@&u!exX z210yPPsm>`THBa%PY=#)O~p;X!Z}{2!IAFW$91EkPoZ-BsH@#;O(>QDz*0#BUa2g6s)~7rOuBiP$Pl%P*7VF z#*EqEs(el(zANjhH?I=GD!Z&vjhE6O@UjV4SQ~cYlG?uI%Zi)uZQ77%X2jaQuX&mo z`4l~B%rm(Qbt!J)M54-pd~7sY9c)kY%ysHC8Kw`~TM2m+!mh*gV(dK%ja*NF>!et^ z_Btt|{*P>e5J$X{D=JeE)?0frf2c~+kf=VA8g={*8)6gj!YZ+bcz%A%B*sYLI8vm} zs9oNS3GtJ$*+#r@9+y?xejcIC+BvXH=0fB7GugYq|0Z&UbyODC+=Fpo-6Wm&wJGu25Z_ygXtkw;{>QuznVlaZvvth@vd>m|?BbBWiLL zAyGb-Ju`x+RUso)fR4POP|PcVH1&b|Y8T081-Q&Zq=cxd9i^NyvsP7usy*2y>Te7& zF663S#lk7JPF=*Le%DgJ+r1q!+s_Tch z4GAZY5M_C-ZoetEY!BxtLBGDUu7uoIrpdUCK%^L0GcV?-s2$2p6&QP^xpgt*z6x8y zvVjh?s($8lIQTvBOpT`|ALd6()y!3^sqV%-s$GT6V@YXY-Bib#3gD>7Ht7Rftb5eo znJQbVqIRJq?>R=<%FU}g;Svj-^mB-JBXL{Fw262~<|SCZP_IgD2`02P30Y41`tfRJ z$ckhWtZ;Iep_Vq0c{NN;!FErq8(zkpzv@SJ)v}XC3Er7iafs)uT}w+4vJ^nnF0_Cq z(%tn(UVUHh8veAyx>RXpfYMM7@9Ap7r7q+ES#|G{!VXHM6G+nrT&{}X+0n|YMW)*z zMzv=xA?xmGN`v$1>b7e-UEQ%GSGGH2topa<*v@r91VO7dY#Nz&!BjSB=<->mZdz6; zL(VA8;nX9pM>tmMe$Q;(UdraNDC2lx8b>NRNl2b zT+Q&ot83-wHPV4SuZR4sB_9p&Gq27S#GR1Zqa~17OV*et+^Z1=QeVAtzf+*CZrKDW ztX^vf=k{?uYNk^6`viB^ZS*Ib)6QTUYBr&y6Kbp!8r@fq$~qH48qpVy+-h{6nMZZb z?yAS?usMBGAdm|GC|YfaS3%h62>i*`jSINn$Dh|G}I)^?U~ws8#9l;m%=V z-&UoY*;>~avU)@p-s~nzMT=v`FVDg<@1>gG=FEW`n_~o01IWttQR7~5k5)|X^ z0y#foES;^M4Mu@Tc5Zr6D1|s?*c)M7i>-ampf-t&pJk&dsv&Q5&1X@Frnp8&@^D>i z#@D1q$0V<74~K>YaSbeYTuwc&L{kPG8|`M&N$Y!TdUuSx8WXEgfMy{1dnwakFr%6r zFpbS%bE_Ntso(V|b2R*>>8l zq#UE(>pAq);ct_ZVF6r2FEjd|!C3{^H5ZxYNcy#7quO0Xpkg>R7Eq$SafJZgPmyEW zXm&WKTa#eU)=zCu64s0~SHw?7>c1J=4yY*JZbA9)B^a+S0GK8I5c6uj{wL~mj|9=S znz012n)~K-{-}2I((L%_qN~$P*!{EFnSvPk;}#aq8?9H}<^aq=6`-UI05?PS8?WwW zT7NxubK8`C+GHc=wG)%ql=U20p*Z8(xRE5CqtkB0Yb}M|2_bLdNJ4jGj%-1>0=(L> z!L%x`x{tn2Xim#k+Rkw*L!&jA)v^s%6lAxseDfV&Je=R!abz_Jwj?FddDP$3BZ)WB zjv0z$+BN!(#MHIIsVst}a7Cjr+Qo5=Fkyg(>fg?lb4m8stK#U8*)>astBL~9mUwnu zU+yVZ;DKBhcBN*Q09l(J6Vb8HT};W8TMj;|g6rrNtd!F1 z5-;6qSHkI42^Ylw7ke4y!vwgDvbKjKG;nviUN)*fSoOe^-PoOZjCk3<>MjlA8567l z);<&6I+_ff)^05v`k*QjcD5h34|R_eVKX2oMqFu?w|_W)*PVH7M7WhtRl9J#C9l4o zjqB}57Dldhi>u}>4E2L8E8bFU&T&IYnbkWEkF5!^_O|aPM2$pVXeS-}6|KF9>mQpo z+Er^%54l=xw9DdW4;$hW1#H;Dszmp>#K@>5WrHjDu)^9l1IwE2=W3>g zk$O;YV6`@y# zZwcpCE9i4v3wI4mgsKldkVb~=ih?jmIzVM8MYg3{?2WXLtgkn6%Z_l_k9i8D=J=;9 z$-*+sKS*sSZdB?7*BFsq=Dp^1ERu?lIQdnAq?%2aEO|Q3m@=u$W>^|yS-n?i7OI~<8AnQ}Q4vQ!iO5(xnI~9OMC}-5l|ZS{#5~VE zvV*K7&uHG-(9AvOa9HigL@L>|fq`-!Pa=XAsiRpQM3Yc1B9*xg#(V4%9*CpBjc$z% zpOHL{v}r@NJ23B!SDJ4jKFxxtOg`oDyy#*YKesT_ZUJBkc+l zOLvZ$vPG%UmS4<|(aMlR^jB&L^UAXmBb`C~nNF@vArOkIRtzf3SD5HowAFk?9h3jk zT)V#W2sQ~2hF_0q)fgYzx5_$i9A&gqo_eny52mVNpFha<%TMU#2iY~cpfL)VRHjYp zS)uV8#4hnazc~i|BD-i6&Kt7~NJBLRoZ4{#4tOTfiV^3O38jz%SBsF7b%;&e-EBR;Q0-bm87gd&WrEj$#AP#aK84=G#b$1>;$J;3fD zk5a7ml`)3hgxAdbk)US|JZY_O_BWGf!?oBY=vl}TplWn-eKzejPKTorfEge}F;o?g zG3~IQ#%b}-RBwn=Q|u}2Wz~-4G(1>EMtj~A!IMB#SWxC^5FtyTI3smckdKl3WcFN2 z5d)?qh}tCWY?hh%NF4{Mtx|1&>l zOn!PSz!XMso)hdaAzU_5YJSRC#zeA{tA*2$-=9S&*NR5TP+=OIOhzfF7lI#wQk7Cb zOm36zVLh4ESW_(3(~Vd$nu?j1@}?1p`GrxBX3hUSbYt*dAO;(aMcV}>24wVjEJS#- z9RF0-`GZ)8tPbC_(Be#uS9ymzOxMVAg(~D8_W?Hhf1D_wdmY) zj>aHKmA@fS7*+3D7D!w@reBsGVgu)>2R}mW31b(3kGZ_N+(!&Bm}_JMT14){Kyt%B zB=N9^@Cq}gu_y!vW+aQ&kf}u3GGWcb+%`s+{SQ&9xzWq+;WW3OR4mbA3L`X~Jjudg z$*F3>@qxA95n5)>G*g*CL}NzwWsK#FJ&=d9dbIk9?U`~+M6)(=CtP;yx*FHK4XnwBx+_QlM(2F!2r$QsoyH| zy*F`VvP#EVtx?tDL&AoH`sI8S^9qeim`RN$5U$_kmvlAuBeH>X7#Y7~!CH4aTPVka zjVi(#P?oF8u2alisvSW|)QxJ&%xWz=f=B^l`E_5s(u0p-0*1{acEG#Is^Y;${$?W% zL#al(D>IiVywTnWN8k_v=J!dXs3vfe50e(3kJ+!mROuh(>&ksM`bWZKY=Fe7VwanS zDiX7eoEi%e1s1Rrve6?O?VqIbh`KRF3_m*mna)wz^ukEqk3m@_roa+~7`V;shrmk6 z0w3#Mu~3%Br3HUQH;)Vub{pW8YgH!t0dZO`;+MfpuqM$2(i@s{y`wFORB#j%Hk9LR z;88%Ek^z=^6eAIk>V;L00uJ*OMk*lidA=0%{$PT1CN>_b8bZ(r=y7P z2E)?Gr`JkaRWcA;B)Q@mi2NWa7*%bMnH1+H*yc^5aCTvevddN@lQ|$zDh2k*f7NOu z$#m2bsa5<==!FGaEF;5u#OqW5LU@i$yQ-2hsP;BCp$cojEGlA56%*mcr^Ee7C=w*a zh-GTH2a3`mO5U`p5m_QBl7FsY+D(|&W_*zjpA=SOjm&o(QA5@o#|>qjvVQ4mmSx`J zaIa9ooECYYry^ajEgFCzj-uN}Pg!m%@&X~k=J-E!Gx3kYV2!P7EPu`W*ON4se;%^C zN+HM_$h$@>ArdqQ884reaAhWhGC!IWfg>nKq*Uiw1c-Rb)MO$2AVCOuWZ8fYOVSd- zA%}9$Gs4LUKpC1S9fT|=pX>tV6+* zYDaMG88A>1Bx3?ioA}Fs$cl~uq5A*Z|M$QC&wu+L|5K7qH3w7>;^(T_IJa!s-(>n* z>GiZm-QIzWP0E*u zLIob1^}jyf26hxI2C&ALE5o|4Akci#@a`4JqHI|I|tTzADsThf?Ba-)b&Lr$l# zzAKoWK?yAP%snPhD%n_(LeysRfCTh|hkdQ9skaNMpm7E!&JOhqyk?C8;hHi% zflj*^p?Jzh30ZH-YTXHhPM;sp74RANm4Rl#V#)B!)A zIMt`~~Ms105T;`jELZl}Yg+`F*)Oga8!YB9W|~mR&$8g`RzbO$17_UI^Wn=YrT(XC$@)hb&!}E7goBB0RPwW<_o>it$|U zQy^V!VDt*n(2$VaRi&SB*0Ve_T18{p_h3}B;{v<-s$DJ3#CuS9$Vd{j-;n@Hx8;}{ z)<(e1+l7)K_5wPVf$|^J{;hvYsc^_BCxT#^}v=5c)@Hv zf!=&4d$sFXlFwg}J=TdTeMqvvuXZqXt_LbJp{)Em!lfyLMgaPsOi^G|Kvdmrh>0&! zdBlYEQ*hk$qRIxGKxtfbUba3&`u$&Ya#F#ieBr1p&VqD<8>?XwkjcCZ|ur?VpjF*gG}I(9M2{y zst0L-Rc&sKaFCu6B}rAHF$_TK;kgM*n+K;XXcI=#Hi7HKbzaE?o71?>ndrT#6TZrG z{E+6jQVIQcl7(JpWQa|ayey`A{cAB_LM9`EcuAb3#f<-O<8v`YqST-siJbhOHZkP; zG{zB09+&RRNt&$`d6L*%i?frhpK_vgHZ6&%el;Lnf2Masc7UYKds?t2T26#Sh&d+B zIRts*&a__07L4>#%!(ahwBCas-O4o?V>X=K_^F+L($HVM@6m zTQG*ruvY9?$KgKc9D?*+8RLMI2?;OD9Cgnvv1;oz0LF1Y5=5&nI>#lw?lxVpgKnA@ zw}z?m5$S1f?;`xE3m7?J-%Oc|za~Pg{a>bV zbdE%VRH-`ttJQWqQ?F0B&9-iV7>`BZ3UWP5l9JZ`FHJJ78xbR%N}KNh7>`4=BGR}1 zJ2xUm=+@PDUc?rNR93D?6W{u`UW8k&7+0;xY1jd2Vhq^Hmi&Eg)sO;F%tm3zH~B*H z#*Qd)f6i7L9g`nkHJ!ZYnBW3_nG&> z8`SU3JhQ)3X$zoRtYlsp0m3ct!bXToj_B_*0?rM$sKQ8pvLT?s*AyzT7C{ir6}p$D`jVA{(`$M$M@O!oHZ zKyCDZ6_hr6OOH=7#{Wg&M2k;WER~z672^cyGpEChASPulLHJ8A*M!lid&&?^^s8jY zT3ba|wWJ$J!>-sWv(*$1n;I(m;ZPgJRAye^dC?qG%jJr!u~B5oyUOjiB|ss>o51!| zJbIaqw8cf@rgmPDatxTFV_h3w@C&rw^Zh@xBe0W;wn0WIV2piH97 z#lZv&9E-%&CGpNkE;_8QUr7=17kpH|`74>c#H7?cL=-&0>G?R=^xNLqa^A!uvp-JU zBjMFgp9vP4)ixoEvn4gM?$W`P-iReoa0&kcMkpvF7?wP=xs=Xl<+V=w^uTh1;Yp13 zcQe1J_3kepo%}MkzD^L?s50*_qp%<16`rtOdp)rwau8?oXqGy+7&~qqh#2(Qt3rYz z+Q6iwfOt8%ny!R0*NO}ETN5c&+Ix!ZNI!mE({d9UV}PRYtBTC7*d$ENd`@B|<(C|S zU+g|&KgThWOUir!251@1EI+EK7qhnLQL{gxk+dJHuS^3%14F7gKjmTdua)zsiNPC> z9?n9)+8h&Oym0lKkIvlZz(7CWLv`{*dHOKaD590wv}Gh-QE-Ae0obydwfAe8CZC-7 zZSedrWq5E^9_7X;Tvd5eQ%zObkD9($G(U?b!bk1!eTG208i6JDIj9X;qO?CtRU%Ok zc(`9g5S5wT6M@S5FXCQsAl;-r5k7q)OyFLlK{(q5F6(4ZrU5Y%{6s2yV2JGb5MrQQ zi)MeCW8ov0jb?DKK?qlq-4g*zghFMpKE`e`N*GT-DIg6g8Zq(hLzn@+1c7dA&N!^( zTcCn^mo&v6eL&r)oy98X(Ygs2~%Ii82tS#hds{T|R7Md{G zqDYu03FM?wUVIUhbc~^R)UZ%y4&@=C0GhQB_@8fi_F*rW*BC1M4K`&&CFK}m ztFck^avM?XLZkMZ5f-v7!BIZ)tsTltKBt8DLx#;7$-*)smB5|Im}{us!1I^PL+SwW zYw<&IyvaEyWQ^a$Y|$E0rNaL%WLT5w8;MSu1SAUS=W;I#s|MNjMwTP}AOl8M@i3|) z5Db^sA#c>D)c-qp7?Kolo;dTQPc}g`-~{P}AIt1=te^CV-faWcZB9eG@6Sty{ENAQ=ZMbIYV z!s9W?v4@3nWuyO~)Tc{Zx8BLeNuly{y;fp4D$AK<2r5%PD@nV`?7GLNk8DV?h(nKWT62$K6<5@ zcES0JI@GQmZKEXVfMPw-+`b$JJ~A$V!JDY&qJ#)|P@j$nMXUZwRxZ69?HU-1gwyT6 zeK`)1+8d7Ejy8obuz&_w455_lMQAeJ5suS7(&c0lj(k`RbFf?UcpNlL6UK+utS|CQ zCy{O+k7oPRU(HB;jS0(K`x=-qu+i$(OX8mT$h%_gq-9(d@R;8h153dXQ)|zJEjID;OhZtg$b_uh~=CB$VK8jk> z*jsGe#mA&&4uNQ3j!6-6C-)?c$T_egwL=#(=8$uX=C|8IHj&(%B-e3}vqI>+$2C}J#IZ2{KKbts7fS^kmFu%&{)Q;z^4=>313qFn)#YHl z>lmJZ8t|IOt}d@N-pCSBq?X4-VPeN+`H;xKb>XVq!Sj_^LIHP==jVnWRO(RObAVeeCGFvDG^7tHiG z+Jg`?PG_#cGh;jbriO`LUdZ2tGJVJ1OzuIk*a@xV=^ri1RR;=-Gb&MOK&oI3IjAja zY#1Q+kN`2Po4g1XF@wa(m}Tf51u6l;AJZOKu>~bLd15@ePZ&jhD%N2Q4Ab(Ha1 z&68sj3A$s5l=i@R=yiLvieuA<%*9aSn0gqPCs1EvDU@qJwNA^>sA_0w-c#Z!!L;m` zchcx=1CBK>{9y9#Iiw5mm}2Q!>Y2|^&{qeQ?rr3Q@=_LQqrGnzO(!&Nx=s0sHLM7 zGDRv{DZ-R2=VX=SNtaTCIpws$O_9tdjA0bpVzd$__l#I8LHn={kiOgz#!kZMH;qt} zLfV57Uu;_J=om)6eCLI)%_Ai?5Mv~7Qi&IK4Wu72GL6^nTLXzDmV~R8Mz6fb4rMQK zd9gDuvd5V}CAD*k+~P`huks0?Od(wYT3f3`7mJZ;nC-Mk8=29(OvAO`+1J-Rm)b~H z#fB$-o&XwlE!wwferMUJgO73~Q zza)Yfn!6-|dc!B3!^)G~58xgy+jly;5vn+*1(A_)vJ^Mr3`+zrYNo%@9#3}cGeGmF zj8x_AVO$V`zTh^SeI3^lCU69t&90j|Hq~BqgRfE*X51F9} zs1==&A(Vfl7HE$$%GNrpX)V^47fPwbv?72ubJ^!)D_dX=!Pr;jGvQqNDN?4AxEmE3`6=4>IY&+-x=yc?^a(w*{5v5+s_Mxm zdob5+Tb8^9jB9aXa5C^+BxN`cf+7=vXeM02+67gDF|__*+kqT1Fa2>udQ~t&iGha8 z^Fd#!tkW_q1fkv35R=scbiZi2t%m)TSV2dDiMM%kT_hx_>?5l{2%ZSNZ}+X^4Et3q zOcImi5(pquc>wQbVPi#*-cx}&pr!l5K}IZ(AT9e1=^G+Dv58~jseOi+9m;eJb2?={ z4wyGKeEOjdXZl@xW4gypKq+7vD^LCNN(NE!f&Ywip@rxqg%TtKl;zG-s&n?v_5h{e zCW!A@zBRH?Th#J}TM?Wqn*)_%SvIA+Sqm~SKCQ(DNsdh4{ zexvk$6+KVKuzID8&kUkNMy*hpn!jZ9X9{)i!Wl(0Psa6e>UYiIQkGz74(T6uDD|7> zy0pTs(AX)~SR-cG`hFP+{o#ruZ4XCc_IR8fqg|0cYiu0;i1`w7-M8S^g)Ie0D?Do? z#~C^A^+TcM0H%>jM7RVYEKd#Yc~9B3s1A@ zE6|*lXKzl2W}|?d@=mG?`Hu;nMPz?d5v^$m%)`VQ%VewN>}5{AsyOk8qu`gJrnzmE ztme~M@OgLgy;UnxTayBu)qa}_tlIA*{;XhW)#V`?}7n3uU;f^T|V!jBI-j+$r zApM0_+RL}htY+d0Q&DN7W>bMt`jWLhjwkW@%cRq25~q009_~zP89h(kQcO*AU$j5o zrJpuYlQoTFlvd2%oX#qGXi(IN|2CKSVh>K*DQ3A=M>itqu5PJd?4HwQ|ClG9v_|@P z9R}7cU=QMIV2`5qa8mve2+|>pCXu_Z-?Z{SO#P+rxR!)fNM+riYxpmTSk@dZajSp- z-Qk48lNT2ujfg$$2qUR4OTk*}>vRmK@)%`lNp^(DYd4=Zwh3KnFXfEc*VM&ka9MTP zQm4yi$?LKT`>2IBZ&WpQF&V81aU@_2m(UOAN7|o283uo>Z1qXdpKb!Dv0+gm`K7vM zLc{pW{QB`e?R6zNXDrWmMJ#nVmyJ2vK!F$ucI1=n9Uck#2ID#@)k`>5ljoz%!o0RT zPr+~bcq+VQm|S)Gx~!g!Jq_{%%5eBg6W*$Wva~f(5}@OCG|+E)B&hP!hRe?jGvPC) zW4PjHontY|CW)z&_m-W0x3fA6NS|T#4|~%|zuOszn@Gw2_eqTDFEoccGeCDBZ%m%_ zC3{^*8^9FIbxMX2A1h%E%4A!+Bq*dDp)_AQ@2fL|Jz_4SWWQ;^ul(aG#g`gUH5%iG zW$esFIN||pMp7RJ?f!De^CF4pUB1KrUvv-A*1>#RMx3P=PVb>+oAHq^1RaxJ_B>34 zcwnSkpsXWj4SSk2p@|a3xq4&5FaVQ8k>^G@G+Bz_1?B5R-=vjw=a!kfHM?o5*ussCXr<)-`rCyTOs7AR** zb7sC6!~-*w$Tw+f==j3~3JNCWj!%eLb_jgHwvdyN+Au>V9Q|a3QhsPgWtN8;;9YvI z+dmB4Ta!Nwq-PZm>8=Ow^Q@EnBy`NDm_P(UXs?_B`cA9oCnHl}4GNp!`T_~2AfU%? zccxxZx3LRo81*>`Dk2dqK+sT#MD-f=?Z??D$ol!CEQtA?lpdG%74r0Ea=z21w2Pi3Hx_W-yejiPe~a)OSCf$)DLgCww93$9y!W*jl880D(i?bOteoWxhY}HbhGmI@8}fpzO|%4iEYoy zp(I0%)+=p(MtxGk7uX2-JC`2Tyqc_ujP}%!J3n5zE^TRno3(_}>1qQ8EtjOKv4ego z{yk)^Zwcu;#-L(sSo#TL34Q(ESO`yG3|H$KmNj-L!y1asV=P*l^kR^;WsHxMx1ZDd zR#~)61n?=j?4Nv5f;N^u9Ov**5-Bws5moZ80^zTcEufW}r-?O+c|-@vr8Wnotj+fG zx_X}2V(sB)1iGX_i3y}eb*hx9;bmHpkoSC+?_)HLgZjS9az7Zqf8JX_VuJ^7vIWV+ zD(nL0Y<s{>-FH~RO3 zNn!N8;cny99ai&;%H$8(5ke3|b!`iEWH8EG*^eX|x9R3lc&bZa&DZRNg4n>FOt$Dpn%rE6`@r;vv*8BLQzI}=cuL5K{8Srr04dR2{I zkm4|Vs0ypii>3Tm)(ZbFR99g7#!>oAvOf^88oWdEN{+V}yCFr@Jd}$jAXBPfnKg16 zQy1}+STxyy`2WO02v*ZwbujJ#rh>-I{UdzHc+)SY2j(xq8Fhek2TH;@QL#+Rv^IQR zX8aJ{L9!%0kidRaVOmjBrxOV@t)IZ2>Pc~W(jyc#(SAy` zFkAGheY%O?rZ4faGpll4m?5V8JP+vV+oY>5iY7ET>-^D01-Oswkv6_iE6p_=PxA(5 zI(q%3VJ2z|Pz~W93n6Ul+7C6&!pH0&^P7_c%k0mb-PQKDizLS+svp2=6AHn20%89E z=0Sq)a8>ly0=ma}e5>Y-RlZg3GEkhS5K4ca8BlUgjr)<*q)=L`8b}q)XcRk0KqDaa zX6>Yas?NQ;u!UG3V~5q6I5dPTN(`540%SGlQ0YtTRLtc+{HmG9iRs_}jQKplzAYk1 znS&L5Vot_D?u5qtCXR9dQ6#fqN*AR0P3+uF2!*aQOl$&0Q1I%%?DfQ3m?}Sx*F*1s!l=9ua z%lx65^(CkK-^I(`#j%?Iv7ji;ZOa@;hjR%tMtQ@U=1C;WBK-w?tK(JbOygDMCZjvPSp!zdrw?1*ac;VV=4|1CZ(8zBK90(M67w?20pMgj(Cr#XM8y;3%;!Y?^juUg{7YXc zw)s0DA8qmRi6Ug|U1W|naaS$5A`!o~O@yzLL<%rLv=dazcKLEU=BSCnRzFqKQ5Q;n zgBXF9&)xvq!DZT29ssKF*puaw)fq0M+LN%pw%rgpWcD}~5|@y8jok^9tkGe`{3`ZI ztrA45v&QE~-Le<1O9n(?G;@|~^ONqmd-*zl`3E(CClG|v+CGztHz6+-F*N+0fob^$>cid|2MJo_=$+s^(y^2Oa3|@u#5Q}eq zR@n+(j36Cc)gFz9TN9;{I3J3)4ulumDpTMy^HqHpPeGuDeC=h_g7oXJyonSI@Z{#j zTKrRzb%$0&Mhbrh;hJK<1}q z?nGMA6WUXyK!#RIU0`UUA|aQ8AgCQS?(sh;QDfOojz25u^G8NfNEZ;OTuA?qyI5BlI-X@0~kS+E1HA4R8#-CiRL%n{itcQ_vC z=?|&3goC5ZqUe6`WelWB#t*(yB(%CwU#!Q?7|H57Q??MP%y>j?FVypBMArFpJ%Ik_ zR^A3vvm5OWeHjmV&Pm0(l6xj56?dFjS)c$4pSFcp$-mnVQGc zlcEQ|L<+W92KsN36ax&|e66HyONag?En&cu2o&H+hW04kljx6f!%K`pp`C)7ezqm2 zi1CYrph0K$Q47S~tIqP3e_Fk3qxSL-Qua}P$q__hHnNRkomMiektD1+I!SVXsiV5R zwAzG=M(gHg7GXu1rVf@bdHZu@HoLow{RC32-czE>KAE9DZ-v+PH=}Jbb0FG>KP`Z} zAMBpWs}CQOA^<@dLuLAEtvAaPNfxAEDa?#QWjURyU#V;S%KP5_$fwcrrG&G#7FsD_ zzab5TT~GBIo;fZ$aqL_;uWm@ec^$8EDx4Ox!rHCv|O5z0Wjl4)gWE)=!?!-wy>uT75*-6QdIr&3k}F{)&KK z{z^-<0~rl&1gYpx#kB(LTYs!e|M|h1BHK;m5aCU!QbQWH&bx_3a}` zBb|99&bc&P92R3Pw2J8LmTI4BOva+2fz0zyjv}zGwYi@q#YBN*V2Pe?O|l+*Wc`^) z$`FUe)usz|f@aiwsx0e4OF8c&xfn3z=cj`Bbd+P`EOR3TVPkHbp&2EOl&XEu@2j!L z>6x{sik_L8g;h~W?Hcui$>LKVI8kOzcwlMr>iTyzyhc?>r!_Gknj#nUl#x3uufID~ z2(7yvcFxc(OWf|A3er`Q(SsE5Vlx7zVMe+6dS(>qP@{ss&FGuz%fNV1?Wx!zOJ61rgf8tF;X%R~UHDGVzt&3R z%b`0TA*7wf)S53Y8wVL>iDP8rXO^M4=aS}DpFLWfP~C(Ofmmef^j!IoOtvrbMaX{K zZF*{!`EkBe`~I0t94cZ*LdZ8AB@KzeZJ(f- zqwj%6s6dYmZd?|QL|+4Lobak;I?8nA!O^3ZtDM1xOUz`SccdHtJ^`+?)A%YKQG{6t z+2i1>GUPj~G-k*NqRFkUt^NK?5i{1VP_nKV0QSH$S3eYWb19gzBpx{r2OlLt#t*HC z{mKWqJ5~s-cF}V6B|Zd^F=jl`cFAJ5WtxQ(^e3ca>*|{`&6xX+SFO!cNPP_DPkJy{ z&3%T^MUKpvX2l5UBO#oN`ER^3*<8uNiipFjYu}Cg@2V~r0)X}GV#p1@D&54 zm=8}pjjiL1-kK4PPMoN}ou!us$s^No7;{W74X3J(If{}rPsr%P38ZNhUt|Vde?wZe zs?~&yBq18HOt#Pgjmg#riixQ;hl<#-ixaCjk5W*1XpD4N4)SOtU%-zOPYq;@-_zwH zt24>^W5v)^WJqL%H>!>)5uPep;ss2!1X{M!);LnphoS6`a%i{nMPq%Z!H}wgw|cpYY9*WutqWd2?QZ8Nz_0vFx8wY!Al5lN40I7aKh*C8OG=MC8l`Er}7ltUzl|2uMmt)l5vs zLe3XiYh;Qa>19C_VNt`|cbBsUES^t4VMAio&`XTjK(Mf6XRHm`)Y`f^P=5RaBbn?O zRR=^4lbEgTwRJ&)ix&uzA=z{W+HnY6(>g?mmsmzRl{Nk+au}*B?k>o;dCsLx5~B2+`o5;i4s zG?>~sK{Xo0h+wL?gg;+Gnf(o|q5F<1;D<6Y`!#=GoPtQgk7iI6Y*p}hN{o0HR0ogW zmPI6qxtE?>!iF=-%+X)MyritN&t@_aQ`nsQsYCwn%kC&;YQbxZ?MNb_m|NdpS|<6K z3nJ<~4Jpl-Bd2a>jUSnRK7MTzcBCzT%w(eurAqrv*^z&WgOJyy(ykF7hENr}#he|#e%Aq=ZjVV+*Bb3JR&!r9YPQnEjn&1274TU1mqgOJ(g6bt5M zC5YWBk)3X64V)I64Fg+G(aqFEq*!8PYvG=^bnEYD5!!~>zkP2`HA@QIN8tMB)?d&X zHt0Sk+f!1K2x3)#^pun&)>qZ~tfw_pSvp2GmXgVm?1eW2_p9=(RPqrLtyTTlxYhNn z8_5{8f!3aRYyGL}s=74PAVSs~Box?GRdwq&GMicgejLllV*huRByrZOK$ARRthaHo zJ4-T^4_)Pu%e5mE2M0FE1mS8AfIvsmOt!9e3SH|1I5)H;NiYIldT-fGu06LLOR(k8 zGZq)MSeNH^e?x2NLccVYlbq}FxPNorhM;*>G5#?{xi%nSZ|Ga!Si<%jR#lHBWu{yg z3ZQ$WuJLci#dtj@eIThR@?XvX5ONDl<%tK^MQ@x_MUv79Z`t0A_0S#uWS|8mN`Jh# zThmc9!;^hrvgxT=r<|4@ylPLj@nqWuHDykA@nq+A)?ORae8#|LUYp4RWNY$|ZCF3V zJ(w7c6rJ$`>LdWklB7vYqu6@#{&#*U)NScFVeTt?bDj(NLS2EfajH+A(BEDD=Fi;F z`h&x*2v~B4a?Y{puEQBI*`*|DWh1IYnKc_If9SSZ)c|xX2BKs_OwODt5|dq`l@ z4`Xqwatph685xQD@oO8~lUcXT94ms>Ww-x+Xcm(ERkt3glVxb=r7^S#qV=chSt&%; zmTbICG)$r~vYCh0Rg#R_d;NTyQ)u(@Q&ZR3P_IoGlJ2>TfSgGKbR|-afLvrqIott5 z&X6rQ)z1Vn8cVyvEvx#Mi*~6;nhydIE7Z7p%GJ?X`ImynbjL)+@t0oHH`pm$eIuo_ z)fL(_dlBobYvWht2#Zl85qXiVMkYjk5t-$oidwgT{splXe9;<`A(m5)+PE}VDe^72 zwpiD?4y#EGc4W<`M{j}E1?_!r@AbZJL4}>Y%RI;gv1!q9i_3XkHdO^{o%)ep^S(YQ?gTcVkl<~3-nmW^XGMzP}wnmMA;R_agau~srNsJ1GJS&sKB zCjPPr>D8H2%pSZmN1d6X@#T&~=Fmn#te9j`-EbA|zhg$f?EIy&>K`H&FG~;xjStIM zXP|Yy>x*N2us@>k)dbBjJY@hOCy=5nYNr>IqzR2E(a6BgP%-YA=Cddf>>~uPQWr^q1|BJ{xLVd#m)tEzNe< z`H-`W3Xfx=dC7TWgUk@E&&?YXWVz>rhL`y;i0<2SIXz^?a;$>j_cZIuXKWIsDV73^U6XMiZwlNO$F;MG>UBNF+X#H= zTR=Euvy&|ENVI#9rNStIC3WT9YXa3#4{+5z<+ALXymDwHIuj#b8e^%E4}tD-$z)*7 zr<3l;)jO&$W|Pzl{51Q`h^_I1>N{gCo-{UQrGNlDQ8?gAY2NZ*kkPD$+1wMV?Ph*4 zp-G!?B+_FBoU?lZl6CztFV@CUY8|CmTx2Q3(m70+xz+T;ndrv$GED$QvSNY@YTp(zo%BGtZpY2+;U&17VJcTBy5(H6@z4-;l8m^VR6lH zVQ1*Sj4PbJGa&%`+rAr`aZ9ky;IenK+*`nyizu9S&w!n{utT7#+U;9B&a-sl!b>bj z8S=|^Z7bJr2NT=^>*Tr<$zOyONs8yBU^ABBDJke&&lyw6?(&j z0BAL&akq^^j09h!xcdsAzGHM9P@iR4q7V~GgZ%Lf_sw*S2GF)Q)KbYG z)ib!XsznBa>(1e)wB_Zo17;XPwRH3DVQJnS{$^eUaZ|;zMzgOdHSPjS@y&k3?9B+? zTQp9Qm=*5J?g%4u0~0sq!FqYaTbWyAW?y_>voCI;^_SDrdW}+HwV_L?ng#m+uC)zR zzchYYef-v1PU|@l<_HEt!-eGs*sY0MHJ09z$%(LA6L*yZF>oVMF<}bYh;$y~aX01k z7F(Bp=&8NJfs}Da)oS;o>YjrQoJ~9^M^@PW=GCkfc%phI7f=17YN77zubHTptOa_m z|EUwk@MeyFD>xd(CR?F3UY4+t#I4)>M;Q8M>#WQ6v5y z4Pz^MU|Izr?uK&^a-K;nV?JET-wCJS}Ha;vkmO+_w$<-9~U&u z6>;17wb+~dCfgUZxG9bE)J8(>AZDf)TX2@MAB?N;{XYqgL|O#y z{p+U&rvU&J=|0i|j~mjlTAH06e-B3eUTxHAB#fp1BX!P;bm}bsfY9s|&fv#XKm6Z?U&MQ*|HU`dlXQ+jG&Y@Pl=*0PtHy-PXzMN2GB z*c&^BmE|~1#Ker2qgnYQWcee^yoZ+O3Rou<0ncI4S(biP41^ixVg zu`P$Zjbypnna02p(LR5vxJGUBI#`ybcSd$MnP#ki#`H_`?pHLMh##ozXK=Bfj?vYh zgq40_;HQAG!I#O!UobiV-Jm_Bh8hf@4dh38X5E?o(6;1KDN4~I@i8wJ zxd_SVoA`KRi*)8i4eMkh?GH8xduG;277n)^;5yWF{6Gc-%T#Bt1zQrBbEaj;i5H;~ z3F>#Oe3q0gj+hX^J|p`hG#c4Q6dq~-EO8>B7|{R8zkOmyWqy8O2Ggs_1osa%UaXTW zEQuc?yJe&=Ho~!|=$C=z9|1F#N7m{MVtaV|q#ltdIDStMEu7gqBN=JJ%YXUc(m8@EYnfu9v+w2xo0)RnUT1Sh{k=9QGCTBS6LI$+6(iV&oGij8}yh zj@z0(LZE?}z36HDqc0gUi`c@x{+K1H)mJYn^kcEE-u@+xbFyBlf@1+v_wV3O|MxD{J>yOcRG0QBc&)U8N9%;1!pFmx{5Na+C=g zgZ#7wmP+V9l^rZ{OhqcmE5xQHxVW;8%{Ix#IDb!Pei z+F|RX$orc$>YVr_^ln;-1u zB$M>^ZQQeUU8czH7}>!3$ns<6Py=4fa*>P;TcQzWNS=ZW8d7TT zsjar@b{1dRQlCm=d=&A4DrJKT1{BtCiheo|WPmKo58_n>r-Zg-i_5 zkadz_&jkkKFjT-9zIX^6i+mmdl>=FKsuYG#`ZyxbmDUrQ7>z0vQt4G zcL;5ol|pC`o=^^zEriPvM)|3IJbo30z$B&qVzE9B;fQPwp4yCX>?Ip*8n{(NXmFB- z!coedchKHiZDnTi9MiM!PV=HMk6lb3P&~$a23t-mtG;D^m0p#k#1kf(A8r;4@!f&=M+ydl;YucZVL!S69ECfP_} z_)S(7qL3OSeM6Omn6!u{ijT?9tYZr&a70AYp@`qGNFCEY+rt#ReE({T05$bh8MNn0 zCj*2JJhaMFnfI?8|Ipo}&ARM+{#lnD@g&NaWC$SbmBVAf%`XH)=VIrjkWUcUDHaI( zoQa@tHyF}IWX=PLu<@Bsg(U?M7Eb;&?~^nd*(F>V@*(T*4DtucY^bRv zvGF{QD6?IMxmQ$uq~|r|fZ^C&M9?Avh-1gbWp7BSeIdCC*Ho=cCw; zBz8$H{)muxYU{|tauiiW^ECTflJ2$<(Cz?!Ni#G844Mm)xIIAeu|AxmK9ou~t4 z1ieBFSTS25IInLXm{OmV4W z$&Q~wx*;F6c!2I9VvL!wUo^1PFEnP#85tQ1xB;}RvFGH`nk=DWkJFDlni+77T9O91 zjI7ilF##^rB8$kvy0RGA3^Rqu9M6HSpT7s?3B*_5SNETx+|ZK2V+)nrH+HRpy5Bsy z9L*qhSV#D0>aVEO`X%~-X+>y+q-8Q|-c68SnSw>SeMb@Fm~N?pjOaYI65Ml%h}Maj zv{mVza@i`O+V+$73{1AqT$OC%d@Oxk#}-zX4GEXU0F_+Y)9^vk=(A)Ws%#n=?Xg#r zRre2-sAS$K4E)0^&Vte=)Sf`MGim8mMFHKf# zCL8)-+&8WoU%)agMyc^^pCDYgEOHTB#ZFEQnLZPA}1%fY4F~%B5|Av6DV2N0Qe@sdmHLE1P2O< z5H{872ox|TQ9>y+qU9)koX~Eh7m3p%D@n=c9#U0>p2bg8L@sOYc%E)VGaU*6Ndn`8 z3Z?{%L!G6n)V2(fC6k12qp=`i|~!QQPY*%y5|5|(T~mz z*&51q`L7!vQ*MAQOG$zps<%}I(}!}{nWIcCZlK&Uy#CD+$%P$CG42z^6{L%Uz~o4C zXM>B3FXb!*1HN!_GBi^RH)AOKH&oYmey^tyRhmAgTnvtyF~WcpXb}S@@|qdbROL>= zql-_)dB_tOy!2z3vfO8AN3?ScZy+lRW6lV=fr8^Y$Q)BTM1}Y_V-p{DLTOENGlL}H z$^o*>lrySn0PGMau_{?a7FM9e$fj5+#@4$Mrh;Ty2@o)evi3t2m#>@@IW?VBBQR5f zNek({*|yL?5o90dlg1m&5~L%KH+=;E>u3wb16o!Cq$pl!f66?`p~z0CZ5K6g9O`Q2 z4bmLBmzRo)U$q6OLMA^p(;T)syPJHS`WDAxWJtCo0h5bwOJ?j6 z)$yzNQKf^Q`72P0)5&&H|Me3@BMUgj7VB<0MF@4X^MqAG`NsQGg|Dr@Alvo&1hlYV zYXB|z*D?TAwnM&*qR*__OrvtO%fR(Z^HXzQtm##LLX@zRaZIN< z3|?HQ;A#nXh{PnYfR?KV_~?;LAX9q= zVM*qqB`rcC_nP3t!1L9J0^x`#pgiElLyV+OLHtKfmA!5q>m0mGGh4qU622H^68^TD-h zWD#6gq85YW&EY*_IugQ5ddcCZ0l3VRGhW0ZG`x~A-D2g|`IF3aWL}62IpQ1yWM{Nn z?{E__B^^ZVzbXW1P+V5rw4Dan24uU5l5i+SS2NFxToVPkV>v0?N@JL8kc3Y#`0nGE zDtVsZ6UNqOSezEq%yE=C7ssMRgcvg*$IyyRQirz0qA)q1Q9CN*+^C*hj+4VPkw-ev z+?i;dn@l|r;{zDxO_u^_AsR2j_-w4Sx?(99=<8ffkO+MMu@qej-CQOfeNz15i{%>>q|$JUu7jwi7Q z?Op0?BuZlS)>kL+$S77&?~7s`Sk1%dR$|h9bpj)yHHC&5TNqBLOTMy*E*umV8YOj6 zNh!V1u^7)u9G3D&W=4&{C9|ZUtj-uQ zOEKhv9!!2-18JTZMZ#l=;^YHxSx&YUGh7*&#cu`k_&m2hgKX~AF1|M`wlU#i)!o-! zXgwt+B@O@b4K;nq zjH65zp@mgy187;EbQv6kT+2-N$cjzbGj{JyEFwdsjipJb;!N$d%w+<)C^u{gp2`<< zTW7*0RNl9}9Ec=B@K`2nO`+j81 zoWtQGR})SOmgy^Glpok{{D0Oai-Zg7(?Y^^eHfgIMrg9%pUfu24jyao(ivRWsAuZG zvxoGY-G2im&`lD1C;XcQ}8MzIK$@`)*EQ}?q*HEJedxsfX{fR+S_ z(_O@SqwI-0r>&Oe+R69UbQgJ#b`jfql;#dKx7y3AHWjs)a4w>aL}XbnM3-=2m=vB= z)qUNk;@!|9xUfJi1lRQ!!IO+glz1auh@6`l;MDaOd5paX?e%G52)L_S`<{L*0fJyXIcx8>b3S1J;?pMObtepX(~Js3$Dc z*xfJ>kkLfTWC%@0W|71=N>Yf{&R_7ZXAxRhoEAfC`zARRb}>mnde;a9KW4Hwq(s{> zH6B|pg4-}!%##7Fcnfv5BWE$zFh(%fmfO-dV+)J72JjL~I?u$~S%FKF zsNaqf?O*F6EJV;)hJ^aMKay3~Gtv8i?pG6O?}YXMR~E6JR+Q{NOswUZ-Nc=vaGQ9G*c|SNHoe2#}93&)D&Mcdk9JpstWfHm34MyX!o+)P)PUI zvHr9KXAxI8Oe`cBxa=MRd`=d&94VTyz|U3)pCDyL(tsh;Gs|lFFRVd}snsnU zLRy=&+KlrFuxrf&MX01rt>y9fd68PNMeW>iU zDqLNTfY1{Xm6=Ttty{Q^u~!!y&j`kDnXE47sy1GySU6B?V0+~FKzpR7VsQ#pv);D9 zm_S4>T4_L4T` zcTYUBu(&LSMk9q9%+8&}7({jIe1>FHmQ^c>lYMUrmDfr3@^~<2!(RJs^Eig~*@p^x zMy@WtvR8(Kl~*<)sV9(y+HegRQ7ZJ*$ZZ*@u_6?y)F-=8EnkEa>q?L@Cl>oYWadR& z1ggilVl74jn(0ftFXmgx&SP|O-4iRirHvEi5J*5-oEQv%rbIFz|+H zs_*(O#ygk>>>0Wt^8X;2h7@o`h4z@~NB{M@#AhyCU@yjcx<8cZcAcTw8yR|Hr#J_c z%-vkhBGJNns}Pv;N=T6tGdOyb$H;)et{a$<_8aODfQl1%$_A|Jk6b_2_CHeU@@kx>l9;sm|o*kFEPcd)zw{)_oPM&X3n zq>vG((ye1?eeBg14KGU$CbI<2%aCAVL`4?Op1k|Qh#QJgK4=x1BC)A1P^`NV$6w(dXQL9MVxlX0hVxFt(+%F=FDen z)bn~~f|=Z}NROnR)xfEU#l(bW=b0tC_f+H3Uz%V{7gS^f$5d;d8B03+>+LW6Toi;G;>r~37m(epGjx#of>H4X&8<_mlgUhJjpdSc&&0dPBO4+U zBXydL#2cj>G_1a-IPaC&ba15)w2F)+J8GzVe&hV-`$sfJBZk#2#k8>AH7sr@7rTng z4Y+9Dd%*(EmVIj}zBPL_LtMS7*fQd(B4g7;Q~?(fj1bcoeMu@><-dNX7*iuVuE^pI zEB3~{l^yH2FkD_HSRXN^eN#h*NW7@4_F9B`1FH{FHKKkQ7xT}i4G(7l0$YHR4q8#s z&S&ULPM`S)TAJa9QESM>ki@; zo5apHXdq0)>-BY0`?1WN$_dRrI_F>qbG8b*sU54VN9QAjcKdx9(yvkB`UGQkO8egZ z9Dr*T_sbqA$?h-hF-AosYCSC%e&ejptptsLnSIbZvC}WiR!M(O|Djl+HqFz|C0BU5I=GHU>n#{^q(U zdCQiUOLtGX&bDm1aybFO!iV{=t8=i-mR+R06(5<4e)7g~o@K7~VDE~?kMn;c(Guw-)jFcDi$7No!zLy!qq`w)` z!%%^fcxdPI8?sD4e~`6jCR@sz=rluzSU*W9@SXXgtELJ4m{IiP2QT)5M3MakDS4L^ z2Vy3(V3X0eB|opB+O&KsX;1Cgg(s1m;UAPr;@75MsxM()E>_#|39@!VhNaSeWGU`S z^dzFz4v9)YrfB&zK|By1KZ;Nra%!pz`@-TB?L9vqTw>5S0#n2{)!syt z9#w*=21*x$)@75l_Q+~X2X$=A6eFG(i4b((EmOL8J)qdzf2aYa*PO9k40I%yMF{wx zawPe{2ww%yoQ)O8x?`7O_NiEoeA6q{-ZE%Lj}u#l?jVYSJWz;;p~I9umeQ=hIqG49 zupSGv3I#JeRmWp815uz`nBM8GP(%Op2Bfr~LR2lYDvBjC!w#G+o86L97vi1l0%@qp zD7~NGlx6s@Jpu(~90`>A`Qa;LXRDu;t(pk+d&1pHlyo(fT%t$qjy==m)E|<3UnU!I z=Ln)9TXnWunVC*j%RW+??XcBKXi`@F`1;o{RpLA>z-ymjb-+uiyVAxJ^B0HepVm5l zNKWU{)~pzIjt2ny1BfD0`+MqLSz&IesNuOtTA)-_U>N^7rnKS_?)Wde8Q?{v9JwgwlfFcUomt zJjBWr(nM`1`-0yW`p$%zX*%%3S*sq4UrHo#s;uw?yD$W9tQ&PgIEL!6#{u=(mzwo z`XPPJK3S6B_^}4yJ6RH@pPavx>Lhkc%;_N!O@tsh8wC7WMO1xZ4cBL=#!)C)lzOlf zCt?+@X6*}B8I3`O4|yOWTM3mlQe0Th#k>fMLi1P2#dar(d6*|4Tsil(46M5v@S`oKTIHLs%&VA9JD8t;-b4|aeOoPWW9)bj);$H{;PnwCuNv2MhM z4{X28z-0(j*d;R#T!~7~QEnxL56013FA53rvH_ToM)Ow2G$`j<7A1s+)eKX?{~DHO zE5BwEs#<4^$>%%oB)-+|(r3TPPPt$J-AUGLMPBblFs5N)l%u&H$=3Q#n>T49op4`-tDc6RE8uL2|F zIG8iHAiDEm4quTfs!bGPc3pcZhC(9pnp|L8<$}1YE_t5cAl(~@&4bnSpZ|>ASOpn~ zIU^DXRY4ghX3@XQlpyltA1Pw`&G7fDIQM!wK%rRWLykT}6TZLsuhkE+K$Or~vEH8` zMHmCU&Mq-8A?h?WbqU==h;?wN>2VIK5-4-Q9jZew|k#XRen;HmyWqGSfmdy00>^@kCMhfX{qhOI!s9CxkIJ7^U-{|OqxQ-OxDnGs@8fAk$QjFg%v z>S0|lU&z^CD!&>2p~7@4j?))JWQJf+9hmIBUnX@zsY*v-Inr3Ev5vqMOE)fC;p-9 z3No9Br^6?xdr6ZG5NZ4iQc@94@5QzgunM&9+b5k2T znXK{AjGS=6;A?+=(N6J8Bq=Ac8ZfD9V~y*$pFq~VYb-@Y9uAKREJ<6@i9V1&uxZy4 zEiO6ki#;J;)*;ewB^Wv*j%epI&QgJGH`;!k6t*)*CD z0_D)oB9|sRU!pECtA_vIQ_kxLj01D`D8gK(=>usKl3-V)wqN;|2XpClY# zeJ|l)NvU1uy*MZNMbbTpc4I`Q?cXsPngnqAB&8YI+7c$;$Kvx3owau>)(#%Sx@eA~ z?mgPP7@0=BtS$djb!W$Ajwo|3WDO3!K)`4>#36(BLBu*~%yhBWn<3I_=NwI<>F;9^ zOFT=)XEd}pJ_-vz&@-(pBXL!gf8WV6G*x&Vi(tZXs>@d}vWyN$R2=pR?%5-!Ti2E5 z%#AGKS!pN9Hdoe~JbCJVDJ{o@&WjW2q+7KD#+O1a7fG^+C+r(xkAo-Hu;wXz`}$!l zSmCxBPCm+5+i03hcO~lERm0%}lkaD_AO(>h$$=ZO<{4?-S;lz!8^N;Hnz8p!%<^}_ zO6%0Yof_-UPOR18LKKB(eLBaAkWE-gi+mT){cYK97?}DRcQy zxD&rm&QrN3 z#Hxuv5Obq|Cb#^cr|90HxZ{tqob~z4Tt*b-?VeT=fQKq zga}ACse<`*|GT3sgSi3-bh)g1Kg3ys07A@gbi^Tb^{7eEC6}x_)EJg?G1nKKiHm5; zMG$@e@EHzYNOOsj<&dE8oXFff(7Q;Q&~?z(quaZ94hdxqixQy(4iH6%TEf7D8U+R6 zq_Gfe?_@~9=KxD8TL>>=O#{*U91w)~h~v-oVYe=JG3G61lbrXE_m@`pKqPj#HT?(4 z2=9zCZ|`4qlgZ)8R6#1*(lF)N0tGxmDG;YN=V<#58SV2I$xNi{k|oCDW@yN|EchZy zGzR9=$cZH~42A#=mL(i_HQwDhLP|%Hl_a`KZXm@{#G?4XZ|G8$yDgh?L}Y_k(>?!I zkJ9c)St=PeQdntH4vsiM@dukI8Nz{sS2dyE0qdzm1==4m3U*{MEQB(=b@uzB?{rM1 zPGTp4AnDBT&Dvr8Bc%C8T=R^a1yAX`k%Mci8&UXfy>OpQc_iL$>^DNyEG59rCa9JN z|I|+iIUGKrnG0DHa-1pPx{fq0*YOf~*zYnEh@^Gl>lx87b2E#$2!)SX?j{;Xs`rCO z%|kv6$(l$rV7&Xl710Rr_Z-k$mJJVepO57?|J>0Q_*Wg zXCSjXL6@X~gQYu3fCWd65g{qh0{LZNuojD$q`KlE?Yd;c6b+Ij@$;EDQ~(R!B1u8$ zSHa(0KFmlh#0-o~@|!qGN+2!1AgPcs&)v{z@;Ct~B}kZHp!rcH1BC2kBoiaY7!>vl ztq7%$0mZZ$9m-5@yHl@dGq~*sCM2WumnS%B!tg7=_*6it&IsycxOXgMI`0zyP6-!H!*&+3 z5Xd&Bk0zIWktpb`F_?}ht)`hfRsfB%Ce4(@0xf>7!jo)AK#>yleZn@7o_i4(MLIAD zH7f|mJSe_D)c<{0k#~3J1+l({W#}Zh4pqJi#<`9M$$!d6C>QUWdvZny)F^*NzjkIGRdUF^r zf;*;A9|cyqaC<3h#sf1HpSFZn3V)p}K3eAoeoOK{M_$RX*l_Xgte^iVu zM^LqOar~M(N3SJVeXg(M^VP>-)Jk)88u7(m1+aTJEUBmt$-O5 z35s4nB|%OcBn5+W-FZ@#&S64gwScZXxYGMiBv_b58A!gE3#t5IkPlQ>%|wFc94mm< zU(fXoCB~n~gs}r5&{8+F(xh1h*HrG9%a!R=!{#FnL`VzA)DE0HPf z``~rs^n5-3NGdIJ97R@d(Tmdusb~aruOd{(d0D2*0SiE64C_H2FrB)G3S~z5bhGd*>+l;|f}{-a#!< z&uG!^Iu^l@c^=DX|HTmMAhyO>0mX$$T_={uOrQ}5+ifnrqOfUW6Lj~nh=${g(R8n- z)i}zI;)`WNCC3oq9(ujLm_u>s!LcluyPH*HQI6u~4KYatSprQI>XxuG6^=6!Vd_TK z(9jFFN~bKRiEj|WQn4lJ$fv*zuj7eUBAU^o5S{;mSW%|7Un01wnP{=hbP};#uDgvd z{3q;_G{kaQe_~Pu!XP%-98aM+)A;dt*Fu>YqjKJVR8Y5Ef=b0upy#E|)=f}C8i7s?C7o(l#zz`M+V1_(eZ3^U>Cr*e{2p_n(g-4Y zWiSGdSCuSegaw&Z3RG!N*DxSkaL@HqMhugv9G|Eb57C(wsx z5sM9^dq^wiRBN#MX@=zeXw#Fgp=QzL-8WRfMdQ6LYh2@%5CepKFoJj#l#}K$Ms)N_ zY7qS-8J}Fy0~V173Lx0;bK2(VBbnsq)>KJ!G&Zq@B6^bGvCx)f1~MlQ@jnL_E&wai zkbDNZ6lo|gJInbyV7KCs&KW+E$J8ydBJ0OyUsyU8wI`5^6bTX^qNV#rW@Bkf)IUF& zT(h*y7hamzNH8&qc=a8LjjgdZx-s1g2C?oXjSEn1^kz&H7>sFkiVcwpX~HIFmZ z4~0eEfoG=_CP`SshVDlQ)3&1loq36ij2M=Foo_5-Lz`Z|^vYGZ-5x7r!%IQPRQ-Lo z*W-NRWn}6onk3sDvRkSh$WmJGG!h}&)a|?uEeu(PL|cJ&OE%{t2HU!;B0V@J+BG&L z$wg0@IXbpTwW7?-Q==5lEPY7hB0E)PZI5MDMlvr0&k0Dc}CN} z3hgHfZcdP_hn7v)TEkXKdJb6jS?W)$$;QvPztMyP97bASZ{U5TXJ|rNudFv<-dbeg zo4(;E`w5=c z0-P_rANeWlgXQG>=P53d^*jJXn=$4GIuSFi_2AZ64~shhWD5#BuIb19W2ugoGvd~vnJ>0V}Gs5@5&w3vutqOv;rV8G$AkawmR4BkSow$m4@74Umgn~=G_N+Noa#x*^XX&Ymc~< zy;a)NK5W*NhekO!{+8nHb2*Gm)!jpF?Pz34_y`$Hr!`0(&Z zc0#Eim!RBnJ#-f%16_JipNCFHGlRgadW}dpffB+{^j` zPJ{H&2hGIeazV6$P~4(bX@&AYdm~82prHzyx>nR>wA>g$n@JQGu(1w2{ZB|uXXJrb%BQH#44wZwci9hrnQ^LTsTwn?sfh&%{ z*tjnwOwN^$un|3F!H9m4DyDBL4-h33*QT`e%Xm1%*pM3GNrxi%r2X^~<19E&aqc0h zE;y>W`C{~;=A)CS7ukVo2(%vBVB2aS=FOYBPUBqe&F%^@-1T!Vev4xH0r98<$zVWe zSIx!!-{K5HePkm^y&?e-GfB&gn2ZTl6{FHZq;EKH@MU08j(h+tCA9r#J)o3DmhJ|m zn&zbWT;yULwp%9{qGtS#jFO^RAJ$hX7EUl}`E=PB?MOf(>~wOqMm7OOrd>6@`V z{ZI=6h{wSJSdlf0P<~pl-`);dw*%5_ad7fq=*ttX&ZEq~@f^2P`sFDz)43GKdbe0y z$NO@v9MiAmnuRer$ThgOmS4VbyuqaOzSz(cBzJO|!>-)*^e5))r@$BoL(vCVo;MC(gLL$IpfBi8{ z6tAu$AIDaTT*e}#mX%|E>YB$dCshBQ?(+;Pa5`evIhkqu4f75=0=GKv^;fyX>CC&h zq#YNCHzS?MI{#Iu0x8Zt!}w0H#vqXX{R5)?8*V`De*Hui zoB_*;Iqung5lo4K9AqjXUaeqI{pW6P_4=Rjj+*xwJixpShzm#RAFU;tL zSk>E~K8*ydSo7eVel6IH`Lzr7%8C{Yu?RM@#KAMZ6-=%0>=zFJDjMtRXT+jtY*75Z z&{%mwhhXWtmPhQ2DjTf8X6t5-f%jSyo`~!H63Fw)sUdXe6qQ!VSd;{em z`WZkzUmBhU>I4TkpQuAQgEx7tn&XfC1K5)~d)ECqi_m}95;2Fk>uYKH!&j~*1g88j zKog?T#3Q_x3hTSL@b?k5n@{;O2=>UOd~0tI;b%u@1^zirLb>=Wb#xZ32e0*7zw3;_ zp#!%Ee)2Pe?CoeFSjQtvw{D}}d0qB5n%dU{%W7_u>J8xGdZc83qiX!J(Q$e51RHdQ zW7y>IKO-6faOT1R_x?BjK1;nwea>0n#cye{#fk5qd`(^PdlYVEt8QHWXw>wl1+&Rz z(IBcU-zqA1FimW5?}_~5!hCt2oP!D2X&mrSOtz5P{R0dg$ zN)&ssR71yksyEIaWZ&d^1KJJPN`K2~@(dRWEH_59sb`@H=zNF!t;Lf65kSvdQ(9xH|*e*PYv99Mmd+g9z&LsY#Cev|l5|NSb8tXW=Wa zt?MwoZ21r=Ct&nmE5gM=>|f=d5Qw!-Lh3nN&E4>&K;yOWAI`S&WM8lU)R*c&>GFDy zd!RNqQ2o(nAm!iHSsT0GX52Do^ki!F8GZ-+@<-1~2o1AhJHK90$h=1Tq$7{~h9(Ao z>|5F!5$v6MR>tpr8hs)eNpC7+?Vi#I=m13bNuc_;PpHcR{4qC$N{lQb!M81?&wX6% zI}R{9+H|+WakXmvSjXr4mn}wd%6GvmU9q|WCC-qjmUA!I;M)wdg6p?gi8dkH%})O@ zYI+FPcz7WA7lJ({p`(v8kgRiht~tO0qp#Y1HTdy}Mid#Rcqy!bK$shTYp z-k?3zi`gl$T*Lh=miT#ii5w40t)wDK@n7~(jP-SYt6i?qhZ)HA^$D8}5KP1B@3J^e z82^`zRWmof2UP*uMRHjjas06_gHrA(dREdQOqcd7h)~kDL2~gAh=X=IbL$GY!{}uF zgD871iTW_ryT4XBypd(B`MbZR*UzdctLu+2`(|nS=G%W~Sh>n%QuXY5D0Vd(r5udN zY>fFAivdQH0Qc#>?IAnuen~L~7G{CyBhk(yGC;yU#J(rk`4Q_Q4uDFo=Go+S$r6Y< zG@vlb?|ksvw?5o;o9jF8ei@D5f3p*SNK*>p4v`c)EOQrDnUuK;d19i_U8+8Y^s4H= zN~s42Pxv~8HO4r@6|AT{T-{|ZL9>0B=(U-PHkfd1md(fM(jgoDN{D6#_;I=W+W>ln z6~4pd=*;EA&t|ymY;1<_%?+LalabEUYp4y|E+bz{=5?NX1<|bLM3U&)BBK3(z4D5K zMJKEC<%887Umh|GVxJX;{Ccv*3hu@L-Rk@vu9eR}0LG+4KMZRHyq=lgkrU-qBw@`+ z&~LVY_;+y`*yW}!&c>5^5Wr)@5X1TF7_BJ>E05swbJb}YJTG!zq-gu@&W~6NT-j6d ztfpXK2YYA)*s1=|QkaXE4Kq9E!lZ(M39T;QA=H)5AJ+89Bm=5YNZb*zrM!l5G9rOs zi=?!Q5|>Hni8yDQ8>M;~&hYa7cD~eN(FpUW0i=9lZ)WLO?*KPh@N)3;^o&5~74Q32 zl%*wkV^Ne_e`l8qOKc3GUXtGAnka}T=FGF4GM$(re=o{%-B&gsK3mybEdv{~#KIlP znC~u)cKOc8#+au1ktr3u6m8}}mivGF5uEK0qyd;y2evi+&` zqmvocXT==hhT|OzGw=j`wAqEJk0^@y`B;M=GLdCZ++K+?GnZpAW>SLYpWireYdL^k z`6RcV3Nr9ay-J1&z#!E2XYB9wblS@I$NVF^%+n)x*&jC>@_ zJpdkc&z1z-gt;U^>$#boY~J>%*)Il?p8XC|#4?SWHB3PNzum3q>dwDb$#5`6i;|uNI%hQXRd&2L`JqG~c+#?Y(}EZW-yv>=PkxJ(Q2(V_jV zj68fT%TlU2l;v(_KpKOK*#wR1b-E3EH`QWh>{A)7gH#k#@*nbLjK@w!xZX17l9?@K zm_uo9ntAWc3^e1mc?)*3!a*}R+rgH6K(1DpIOf@rapuaMwXVC_tn4ktjL!eJig8Wd zkDvedG=nRDJ^$ZoM$CK`rpx_@W@gCT4LF9xSbrT_v(WCZe)&%QgT?vbEd|7>zrFY{ zt?1=opRU2grjEF>g_VNp0M1W)n?)O36mzb9ppP{474oit`XZx!#fewlO?F!NDA(o5% zzv2b_0lf;#y?^_+%_b=uGPs0oyglPz%eB66HtS7)DqaeivQ(vtce!k!7tq|$K*I9n zFyl^N=>rLWO#y&7^P@duJ{=$Q4;ZBTv3~n^X+&thNa3yJ!z`q#`sH71FE_dAw_4yK zmkX?$KVYW9wE|`JNjR%z%&X{+3k*_3?T}^-3u&1ZtU;i$Y zXd4jBXrVS|%PNy9KY20FfAxbT*~5or4(8FW`Kw-OZ8|~EM-%J67_^Ret>0MacM`(p zIf*CG<02szsPh4)#SFE{zJ7h;krEVZ9hwe*IXj&OdqBzx2mLf{5eOx)wkk0BpP$Zz znH6O98Q)6hG*2Ry^z~$&M005bCLgYCE)vXJxNg{@Jy-td`nj39{^VJI+0oR2Aw%_@ ztialu9}@4c*)T&VoNW3c?{i@bQ95I ztM=0)9}zyo^cGbqfcY^-vYwl<*238or|1uT}yhs_0vBH zI5>P~8}Lp)WuB>Go)4clKO3kq%=k_#7K~yR=jpbl^eiX>7@}Wa1L7(8UG+!*q2ZgD z0y*$j`5g8&X5$ACLOu5OF8jmy8*L=fu>2(H?0rK@a#DGtPB=c-b~uqCang6Ge}GHDZ1bJu za&<2AYw_T=Q@^rLP$qZ!%OBuYWRfxJLLkXCX{;5fESIz^ZIjM;sHU|ADk<|j@e)yN zR11CN4?W6e0vT@mgSnS|pyeT*?$&d%>@KF9r;y&~WB^L1g(?2}gHq~cR&F`Z^#bft z1|%h}R&|)BkmpQw;z9Nh>hixd+a#T_LjbMtC}mM7gfnv&aQ);(6-)BjtzeivNNT)h z3kqB%X^jv{`3q&zo9-u%csMDYcp87^m~zfsfoK*!l4Ru3!^P7aL6yqw=zXF-8|j|K zI|i3yo6=!`nBIm7C!LQPkJAPa63mB-W)50;v;FKLJz8YjTc=D(>)lYLP0}Gnl|PZ) zwo)D0kPF1?Zt1TNpQY_H^Aw~{S=mTH?4RFE!%Oweb3z1n``nJ7a^TO4eR53b1?(W0 zQ8mS~wO2K$o$?zO^)m`|ekb&hN!b?#|^143#Q<)U+n|=?yc{KjmVr@;Iy@ zUgt+bgF)$u@9d=G>!lU~0DH5+u{ym!6-h#aE*%4_HT>!Dm0GPYh-3vElat3XdCF?e zN%G3Xj{K)xSa~td4^E$XsM+c3a+Wgx^QT14UTT$I{qERXIyt3Dmy3f&r>|#D_(Zwt z+tJ8c>au)5!z8yXxv&>h0rhCL^0&bu7230Rxul#)p2hamiAbJxo2?~t^ky^DpTXks zyEgZ7oIXynbDwB_(lOyu7sxu&`~e~Za9}O&$6-}JW1bxPM1Otoizjf2EGD>x<1Kxr z4Dq<=(Cf0YO}uveLWNuyD9I`<+p0N`Aco3OkGzmjmdS0Kiw!PoIm)B_3vHaH&ncX^Dc!XMF;oH4PKCtB6R1L55x1K+cwqXgc@fJQZyTp|(zz0QSd5FE81&QaRXzqvL z+&{EQC%*Go)>O*A=qV$<+5kCx#endL#4Q`Z72%<0=O@o_pmW(HX7+Pse84I8S!CGd zDUM+%N!)32p%I$9Zkt^6%(q-Z1Hcv{;!7)Qs@G$je|xduF3@=9IS}s>89@1=;L1~k zk`@{uioy*@ib*Mu>O;=f`2iXa1DdT{y~cK@#7lS$m`jnuUKRSUVAFBQI1{6oTV6O*{!2L_vUfaetDl<|vs3qhJ)g*IfWCw~1Z-xUnZ zRm}A7Sj%!6mank{W0Y$fFp;?YjC3r6UwpzO`Zj~C7rr3dFL+SBHAcbCPx$TyCIVPo zrOV0d>jpo=kFbEONCQgbPoPtU{iltjgS4f5Ut`rQZH7wpfgu^*|lfkB><>@N1mIoX~S3+J$oMnn9apZo#wl$X!qT_PVdWR0>5)twJr zOtFXJn_GAiPwu9R#*4`9+9x{W@K*c%jC8{B1d!+tpNQ+7*t1(9larMXFBTjvK9x>= zwL`pH*z*iXWR~4QZdJGCDFG?=E+2^TX9QFM%+%KfK8V;aA70BD5^r)YZ?W8HNZp$D zY;0ZlD+=rz4L>E_bm3_q_9Rg$TLZZp;`V;!%da)r=}S+D@6=`30z=Nf*ub0}&}9V+3oJmb{n{kayOIkOqs zc{zIn@k&5;{vH_wT~d}h4>Lj@m!*6g7C$8rET^2H{-ts#doORwJAL@~`s?Aoh;Q-% z#RgEL*!Qfz{()>l?{iS-VxA78TujOWWC@DFr>JW9mvD~7V!f?a-5z}gQ0KM7S8O;5 zxfBeJSRNDX9d71o2iTJ3PetIakX^6SrRTHm>;-B8_@y0`Ewsq$RY0(E(qV9t1WUGD z-fV|jN}r)@mpXuIpUEsg9x?!f+bn-VZovH(GEXXx#t8XVK&km8=e)QUpFYcz(@OPv zWi?GyDEUaGCnZtQ(xVmN+&dxl`cpFua#K{Ov`u}>Fn(#@kGixUs8E78 z3G97jkcxqNG);I1HBbpz<+4UaUj&A-bG9YTI=8}dbWRGC@+cP+MSzu5jj5FV2!G2n ztqWl68|v2SaQz6DS@p-Vp%)N7;?zLN^qgzyBEUn0Q_mD28#sIu@7n3R>8}WwD>0;_ z(pu+WYfgVFUYI10;^l}Q{3QCL!Q5g3=TgOPpWb<5XrdeqCh6LZ^wesmbOrMsk@vTz&g+^VzRwv~LW|{{1vzV8I2y{`GO8aHjGMFl+OhHl#%;p@y?VBFA zbEtFKnJHvOc3=)p+tz{ntvo~r!bxTuT#t5CEh#$j)@>B}JUN7Ym=FN9#QBt@pzz#c zUED-Q2jLPL2^&=T7$>->V3^Tw;wbJlOgbKNjzoP-Coq!+ckI!EUgdn8=6HrUI zOY?u3fr7knGNeReiuxW)Tjd5^P&$_cy@k_UK^LZz{tGtG4mCd<411zRHfC2pocFtgAL>=^(d zC4@8?;V7a&Oh7MGh%oZ+q?<0R z?n59zDTDtaVEXPgocr!vybcKo1H){FbyP@K`8Xju)5}!<=Xuq;=(bC8c^BQ9;=M{V z{aV6#%eFs%06;gaLeClHpQ&!@#|J?t*@k{5CB16!S_6Vl^>T!Pf>J{w@(^|@9s)m- zvis4V@|AsJ9Zkt}oqf_El)BOa^WW{;!(-r0)M2F=)>&noon7b+fq}tk5h( z+Q6tdSH@@L>gpBxmp;MO3Zg zo@0ELamkJRFQKIxx(rR&V5Puf1yma{=wke`mjPbSn87A@*Jo+AE^A1~JJ^$qn^P_i>O@>mV?1=m%etna z2<=*|>UW=9Xs+g^<0^#Fuv{jW32s7eiD(8<`cxFq1c{U1MVe5)iZj|MKhEKR`^j*W^JZ*O zw9Gw}r=O#Ki~CnpydFZtmcOnP9~?6!udEL!+hT?2ns%FBa8je6A;74XW(=(^Sk%dlbVwAWyy5ok zIU_CHgt(lcO~BU-7?6`GwyerW>Nuf%)7@M)75Rh#@sx|XrF=OcLO1^yiu=M`jZ z$wwN}kXfkE$Fe|EoE+scm#NKU+k{EeTkZ6#N+`2p$qd5}h{ca2YjX-=Uk?feX;bGm z_<&%o7*J4z+OHZHFj)MhpubfV;BVV0-M^;(!iH>CkSpb+Zo1*Ahest7yWy*rm`tkY zX+O75xiJS4BZNFJh>}$!wDL)XD23COmvGHQ@IYYJO4@ck5SQ6{ylu8{3*{UP6+B46T|uq|4U*df8kQmAC=f=(|9LOLAX|cNgpq4K5unNE;6t;Gu$m}3 zVRkkJL)L-w&8iigC0zEPC7pkkFCF^>_;twS$4S;?%j&s$c<53k?6tHNR2HKn*fY_x zFG<%2#F!RHsw#qk}C~Nn%3I+K@R{ zyf^*H6~Z&YKvfa8f){3yxz@;Q1OLukI4kfY`NCCw#O}K&FKp2|>{mUJBhvy{0K+oY z7OF)}A&*RSFbI)0o2EfV|B}Qu9}{M%ER@`^@zJ2bx`igCeHO1zM0pbeB*6;Jl{;v* zC7xvs1W9|nK`u&Py^LuE8xG)`uu3g((UvoRN$eUn&=mQK&!gV9{^hv?gAH)nf2LBYZ;yPPr&)r_I0ogbGr6*lN;RTwxtf!Nz zvBy;K2;G3~Y6<_uIn>vigo;bXtqw@vOIb>k1isrjRM2foJmE6ei9if4B?t%&Fb7m? zrf@oj$#3sQ`oS?|^%GaqMGJ^UtW(HWd*`5(K-~q49d|k^!YdJh{`|El8i<%c|K?`k zl1H>iITn!a%R`uXuxBsRiHFrGht<1GbO6sZ@%VLAMMo(5-LUs_MR?t_5oZOAD%(~# z-)06nITEZnWpAIe$zG=AJRD{9k!DqgNJ@3acSP zYRk1;^3dU}M-jS6;vK&tgeoMPEo7sGLd-4}33;*6?_~s2POS7AD&k%!D^3PcqJI7i z^(B{69IA!xo!(pB6!;82!Ix&^Yy+?aQLsTUQ?NH|xSGP*N^=H|$7EW~vs;#O7!3|7?BB51k#nXh$-@3)wDm8%L1@ChchqDw zK35|EJJ_dYp>*OWln4fyM2pKoR8Poe)bdot3pOnl)$ZNGVP$yf*lS3DlS6e1nW)8` z(k#prXhHLH%wz7IH(jp`Re0R;`#7SM3X%;p4;nJ-B5FZTlA1m%HSBJ_GlSn+djRY5W|HTlVTh+PYFBhgskc`ara0toG@0sC z#Mh%^h_>x69bz{^gH$A%J589u5u4&aQ4IEpSm%^D|`itu{Hg z3}w1^2|p+e%e45!OgkCtM2N%%uf%7r@0Q)6N7E2af3?!PjD~RJ3nAPh<3WI{7Q40~ z`@PG!Y^9+APaMtVAX-$&gDQLZ`edHv)%vC(K>jM?z|$b8aI{bY=X$R$Kr}J{?kr2= z?(%)2Lw{xx5BqbN885ArOdK#&sZ9O&UEk0zUnRVQG(L_+CUT?X4;wWh3Xk?;nGpMWcsK(DH0ow4ek_iT)6t1qc&u7*Z zn5$8r-Atd90*(OPDe9mrmTuJ-llTQuDpQ4;D*4HyS)oMo6?+03o}W50DX9Eb^<09B za{4q@DAyS@WY#k_4tq{v>$dj71d4^G5#~K>pSKPc{=3l7b#z;@#Sfjz!(K+l5ceyJ z$ZVNwalV`$7GfJLjJV}neVMZrpYg249w`kKS<6pxn%jcwq8wjec2mQMvaih|9o_9) zby%K3`fSt;;jeiskS56k-hqmV`V%F7wq{K-nqI)M3cK0DwiosU(~$659U8Wax^OV~ zsC2}e#|p11O-WtusP|`-D0g~RVh`z?I8rwOA5!|nsn&NxF!8c&ys%j64o978#LJW~ zU7`tr?1JoPQ%-#r7nY7&oi7v_e@0NQZQ^q-fgj|i*{nIGZYAO;nOh*G=d*ZeacB6Bv&f$PMC>~A zPe4g@DA}kns^n>Is`lk$ur2gI_)ySv;(j+~s5AUCBC@NAh4#s*k8koLquOeqHip!V z88!;cxj}mEJedJiRHFH%&TPbue#mgN?0sE<(8?(>{~9nx`s>CF<1dPFolC@IT*s_^ z93@h$N)xP=YO|d`KFaZCsKHVz`~5o@gMeudJmOHjfD8+QuVcj3X9ZQUtZvRw&=}N* zy?{D%Bn!f=f&wdUG5N)#fO-)ItRG3KEj~+k;B<$dL)+q^ZC2*DwZ*zuX z_)WxXb)jH#1VhM?XNxZ_M$mp{@UljsFgkz0&16zy5vXBX8V;FO1qUYaCu=fLXzVGPmp7q#83KdD#_}Q{8P0)gGZ+4zF zLzJu6*EZGLQmA8HFAUbVkFX58uV6Po*NYg>=;svUa`pZl$>4FMZLqLSu*KDV=6}5g>A?iL$ zyPj2e2^V6O>NIX%o4W14>Go{%f}09kI_d~gR3{*%t45fDEGP`JiWfjz_eI;=r6^wu zs4`y>Fs7+-Y#Lcc1Ng3={=8?~1js6Ag^}EZ^k} z;z9<8PYp!U>Iit3)2i*7YaKvMnuopil!V0@JGqd<@{P)boA8q<88X*FsjtlwYCSX0 zORSe5%UA5C5G7DwYjaQPA$f*=ij8zzm2os9*AKSBV1p|j2qjAWz zizG0n3}Kcgen`)E@s{-mG@A8bdg*u$b&ze;$`6@Uc?XGz98yor1c*%Gdh!OyXilx@ zK*bhj$i#~J80YDNrFO~Icjn0k);bjYkjM}gqNr5olsSFL+RN*e(x8w;ccHH=_Vt9& zzq8e&C`w`;xE%C^32(&rC$uM1or9XF6Y#< zFOWtOp6@YIDpxb;^tar9i4UCB@m*xl74~_3VC_BLp^E1}lZvMMM98ao4g%juy0aPl z(EUoJlQ=y4mQK1P8-kO?2&~f?jPjsaL%DiH974;?Vm6{3)H>MLaf0l#U0so0^4 z}Zjg@dmGYX7NjoEXe=_{9_lWzK?mI>YQ-(Nw<@ zPs8ylMlBYotg!FpQz%b@-=*my)sRzz-ylp<&6;AK@0h4*%LRPte2Y9#0w=FafRHB? z^+{SYMVUjKfBumAWKuKl!g`OvWj0rqJeB^nnx=mE!b%8r26l;wS}p4^&pU}E%M`-B z7h%Gbsj&~vFKGzzndi!>`4IyJN>5U=OY~DnnUYh2awxg&rG9;F2r!2QI5${Z$jXfj^@{ow$jQ=|Y5WUm7ja{4zCOV>wTM+%?hC$+Li0 z4FVR;n7Hsp29TQ~n|#cCyKACyhrf5BnMHcmUy7%*k1>c9Vmc?FbZaTv9Wu$A0il$; z{szNXoezCcw+}uNKkG5B4ge@K-hZubCjp_T0ww~|?;&7z1Ki=y7vVXe7%~C$_ezlw zApoeNgvoVHmnaa_araXJaE=Q3g9J_7S(9%BDh!aND6oo`Z7~-%tOnrS4=cKO(+mr1 zvw-EQ&|k~v1WfeT8R!txL$iRwaDK{MI7KDybSBCvbtXDY^~BdZxVu?sP+*mmr>v~c zQF#km69Ibz6{zkcu5lmzu+L7oVLLGuatQKt=v#p;ip_qhJ_mO;qLtMbr{njE7c<}` zT}<>>uR$vk*8vT2!IqFj3*Z&qBWFG><4Tosq&vJ3Wqx zCs~;6QT7k0#lpyMiaa^ea+~y`jG+cT2Kq~&2pv5*AaDrUyYcWuIytg5%@6&ByjmwB z;J2@I!;reOGKWOG^GRgOxm0saMnP@nYkFfH%>ibGjzS4=7!bQ8;fJ9nRG72qv^XYz z`*xBcm{rztZnJjZo<{iIl7InsCDgYmro2a6Lv`YlzYG_ydC2gEY&12pcw9CtygNp- zsKa#P7VK0FJ{TeERvsSZ>dTB~$c=`P=V~8pK4(#zxmbIj(V)aHTd8O~^EQ1%G}pl< zGr`0gOP0&m2X1Q&w{3o>>6~4}+eu8K9oxPPOpb^4sn z&bGPKm#5K)$Y{=cwDYNxv9@p4P9t8{OvcVu(|;c z=tE;4{PTdpUaPZ+vY$@G9LK;n%g3=SGktcd-Equ1kqj}*Q*A@tlCN$K=@k6;EESEk z4~>3hxGGmh@W#58yI9$;fN2^AFMo0og_UUOXbfVk(@-F)COS!w_SexN% zGR~(ddQ;5~;K5SvbLcoNf;}I{F2l+C`=G}-_fc^h+3&`^>vUTm9Bl?zw$$9@F>$Kh zVYG?G|E^mMyYMf|-n6(&c&QdKfA6cWOZe9=$S@bQs$_z@fH{ik^{fl1l${9JnQ3M^ z=_nK9X%IGECHp+)JOHQ1)usDkWGkH#C9dMe?GmGNLA6~Y@O?!k%UF{#%;q#kw<|OP z2y!t8x%_m4%_%ZoijDX0OZ)mLW_#U4k6mOmK!JhRUsb1zQ5sU<7Qa|qNnOZ*_;xxB z!xkKsi{!AGYxl7mY6>Z+3mL)P@P#uRwdQKFrg23+(8J)0rE^K#?xE@g43ykU2zCV7 z$^z?sGquu4K^#OjlbNDWCt(SS5cYKmGmNni6hn*^u`l;qpE+H_V^}cHgQd>ZFm*Md z=t`!dEx`ua3s9VnqLhA1Y`#Jkbs?tEaPMi5uCXPNMpc>Z9lE|I^3&!>Pe(8=@FX6T zRN9t77`#L7>IR%P<$Wm|^nIecE=*WnXeJ;`7n8?XLFu&`s0b;vC<|V{mlu1KxZ>WL zOPo?xM`@*@sg$R5pkl!4NW4KA1@``HJq%`0XGuOq8ac8|Q#fqO>rnl+Ht2HtI^Ag* zXZtg!qlY8WERuAsk7M`HQ6DN_*1d~jZ>h?slC-3;%d}AHd=EjndmxoV+3=NKxJxby z9L@T#!fgYr70c{6ZyFS}AGs;7#CRWM*|Rv~YpJMH7b>g{t^BIm70gWCBaAAibcHM5 zB?9gNUfAy=d@d>S|GJCBjYEO8#Zg@-{$;by?)0sjCyZuIz(OKd`SC3H*5&w#d^;~_ zCxjdVmaauPIfrwRRTD$4oKp-}EC$M6!5>M7$}aPI`o5LVjXW#IkHr9~d--Jje4r{8 zxdc*h&q1$fFqEl~-cZ~$rE1rA$O+o)GiNn~sAc=~v1Z=0iwtN798$*XGWoC7Qa}93 zKrb-qpyf2A^)XIHu0%|KXAA3J>JCIX6RrylE*s`F9lVSXHXyC{Eyq~g5g7mzo$q`> zs2oyi4h$0~3!U8-2ehXY5VgZQ-0t-~HYo3(Bxs$7G4SrBz?QOjPFh}Or8@z)yKY{~ z#|Q`4y^U@>`U&x70BFB zkM0g@?tT>Sa#_)Kt#0RF^0SlhuKqRMBG=41ujB68-Ms@R zF-|JWDDw=U=PAAqmAC3Wi8d>2FQN^uU03KH*;$+Od=$;^(PzW6F*}p)Rb=aOGj(P8 zXkBpsp#7JNXIHWpHM^u5oUU&tmnf&KPps|7$(ucimu+Ii!3NWJ$ZjORKiB*nnRUo> z`N)>oSri`YOgzA_UISJ=JSkRQBTv?0B#cUA8XP{i)(A@=iN`W|TXYX1VjX?=#kL@EVF#kU) z3fjr{iEnX~R^s{)@ytfJXZiZN0fPXL>j0Lf%%3&B&4pVxO~&zTn*GsJE$pYp(W`w{ zBfICbSNwczQzs)!N3|w;;UF0MLy~5e}8&Tn%>JQMDCfG zC%(>SGM)!{GO5%zRo<8J{G7HCX$jcXK$w|n2VDEc=`d)0i0x937?Y-hxREwOc8b?g z@<#^>7EEp~!lQN5WO+z8NPb)az@8iU_JM;j$hH(8!WA^~pC4#wZ3{@YR`BVF6#9W7 zDD)2W9v^arBGv#PTK7*mlt0jqtNB~KS|Cy?O8DBRz;nda6;P5oR`hX zbbpec#t69L5|OVzfC+YS9bqW@Uy-C6^)%@`5^weVIejxkzKiZyk+@=+S4{C)+m5;{ z8MC(fQ0@|{!5ivhm6%uA`(_fkEt?khz`%A4WE)jZ0PpuR8k}x1>NS|IqtGQcrkA`z zzbsNMFj8Qjz}y%;72Y_l&1)sa)j*du2nd_NE}aIAM%=GImbb)_C+py423L^ZPaxF^ zHMzSjSDeZ7ihyW!tV5oi@V_lZ{WgcuOPm>Lr@%OSlSOY`WWHldw=;;#6QG5YNfV+W zXG!raFd{Z$$q$*QY+{ndbP60^SBFw>sLBD7zwwK6`*c_tpjuzI+DJ@Y2spl*wo~5+ zDK;E@W}%(>(lSywXiBR__X{7D;(lOk>KolwVGhibO9}|w-+1Sl2P}#eG{5s0;dL;u@Q@P(VEBs?`+fqqd!#xQu4ievJ7!{{od&~I%C$(6 z7@X^NqvF3%Cc;(KK9CUYSA)DhfQ8dVvs{uB(ipO4bx$X-?pFQYg(_N~>xf=~EZWRR zzv#USf(NspH8$@C>YHZovI>`@0ajG)bs=!u`TD(liqdEKI`s*|gAu{W!sNSzpatXnm|+4pew0DFh}? z-g=Cm@|Jo97U0Z5GmOEz*Ce}7LK~s+NxZlBjeIR02ey*JAhy^VED6;D(SoR9co||6 z*)4_1!V5s*K6G@(n5-oGnE=84PK>itAEUAcOaY_zU`$26N$W>T>{by#X88#lI zYnA@%xBvbRB}oZ`qi3yE?E&JRJ<43H>=2L)??2iG`_aoC=*wNue6`Dy+7-%v@BN!C z%85HMk#h%NUa9Z;b|1?5&non9ZhA#f}XjMuq^F)*5%n|r6CfUv<_4c zylNe`Dpaj36D=D^w#|cp4I~SUI-xTO_8#%8gsMu-NXd={Rn6HvMpkQ2RaQemKE)+U6jl2 zADnxo#CD$drkS~;^ONfH@%zqyZ6O7($!S~IB<3Hz30f#G*URZ=i>&{bq|yg^TYIq= zV1)0xe{ZV2|e{~ zy~U3dUw`<^S9Wen#TKC z%23F0s+iBw2ao?vA=Mc(P5!l|oJB~V6*8G#wAmH>u|or0%1O#7%h;64GWXV$B{fIc zcX5a>Q7AzC z2e18Wm;Ka=WKEOt49_xln!L;ST9N-}WK^@Q=&@JM>)iCN@>2}SFLug#otlnRzMSCL zaJ-_&yNoaOcv1QPqKsM&Z|iZG3+(5pi;`PJJ;4B%rEvY%>N1|wlYXekKtp|7lS3)l zQ}GxVXyboTCJ5$iG%2IDEi4u-X-MIb7%?lOxb;e0BmxLwCEytdX%ks~BMjKCIM5-^ z`XBw>&k7dW)02k~WBve6OB%1Yts}bsXsC}o4677V7UJlQLzr6frYIdVZ>sP=sOaEo zMUX-`_nshr)U7q;dYx0uu6L0V#5HGVOE8kGM=zU|&f&jMGDAv{&?{6c<8UlzII=ni z;U!8U|6U%GH<2?dr>^?UtOE{6uBUUQb>)s<^x3l5(0akw*~^tRwwL>{a5J!MFck3= zkv`!45BhXhgL_C3#t@H?9@kf<0@!CMK(ElS%0b=k;6^eNkDImm+INLox)gIJhyHXn zj&)h98P+WF&)rixH?C%PtdU?xW{cUF>y-_5+Y|LyIRI;BYgON*{z>J0a?oMcyKXvJ6;Vx1go``6L1D8HO#GPxthiaCV5MrZ8hG=frng4JMpB-V2q z-_TE8KAvLm1bFMUsS~4fVwEJFqW!j3TF~E4o6!t1k#o$zvA?waz2rrk#oH*taNRQ` zavaZXv7Szh#uY8PokaWT1L>x0{JR#d^r$=G{ZhR}{i4O9S>027#X@pIdbQ`|ro+JQ zu>-7CRI zX^U!N442X5=DE!gj#OwdniH5&E!2Dc&0aK~7CF4E1IE*6W65I`vUXlggT|@W9WC3g zmON^*@ky$BRiW<^bJ3aR4@odm;YMe7W?jS@Cuvt#-2{Hl1Q@Z;oJo9+tBoG?9<@&N z^4>_0I_3f{#|3Fy)@B;fE2oi-W{*>u3wPB=%>(WUPdsXp0OLb)I(Wq&hV6QF#>Hxs z|H}k47H!*FRn%E6RrCzI%rEDT!{1`(YbrF~G6@z}72?1k5=bHi3!YqTFKFt;qi#yH zz*$bmzT|W|^B3trc2bXkcbH%G=w4JugxQV6i{UJbfLjcg&<*JdJd~0n9hFh((iPU9jnP?UVi@ znhzoAq>Vo%+L$8cjb15F7V6+gqPf9;AD*UsB27#$?eux1LZZ;)&Xy_0lr+(15Fo+2 z%Cd#-%|n;>5%`4M%(7$(rZRtD964OY+|MIR0b_CmjHda|r zT%dX?N9>4C`uDoV!cu*f>!LBQD`jLQ$tc)aUg)AQP-EVbGs(gm_7uYY>9iHWOz?)& z&(Y^wZCS!0n0V}5m&@M;m*t#=%bPVvyE8^6C&Q(5T!Tnbhb6`uGi1%dg{CAqQFQbg zGb9voa8dbbG4!G^>qluXp97nLT+13W3_NrH7me8*=!~h|ZS8em0z1B|tT{-oUj@ZA zV!1jlhl7mDimjRCQtz0_+vdD39aDGi9a$UAa?5WJ^8-O4l*WZ zrhfHN!h-W;bjO$AAQ7}qbG*f7y*Lt=x2IY*P= zF3oV{U(UC=s(ML4f8d}pd3Twk3e5m>SkL%%2UVs?#+(%axerzDdXlV_jJYe>sm`uV zwz6)R8Pj`qB^Q-BacL5BkR1P0)gIcNiroC9D6emq^u8uvMKU}^2@bvj_8m8PR$8rL z)Udd4c3@{$bAPQ3qBY4(7YvcM=~@~C|6i_%(wEn6}zz{#8H1z!JGzWX6t z+>#jL&<38_yi)O!RWzi|^lJfVfTi`)z@ulqvtDUz$6b!XuO(6<(u?A*K?jED9e+nN zDDtT`h}JUQtA0w|XI!amO=*#>{Bc`4n1|SAWKWW?oF@})76GnGvxZlx>x|o`#EsmQ z77|f=IXRZOvET>(Oi7haT2syi0K*#1#<#kSsmON1KO6KWZT-c#<5W@^tRqQ`X4bCn zROpofy&R^mZj()23UiNiRZN+dYMQ50#qs>TanhZKC8Ct1V1sH{=Sj>B=Jh#JI>}K~ z4vc#F4Ei%`nM#aQkcK27z>3wQRHgO#VuxYPb0Ilwr_Bd3RX$ak73Yc&ZNT~Porj#T zmh#0wHKeD1f5f_o)%XBp&TicIW|qpk1+BDGSJ3uX^5503Un5_AHyDE734sv5LG*p% zLdgi(9;N`ILec*kB2rx#Ly@O5Ar5s_hlI;a+oN!oBkADh#_r+^fS)bx?L4WpxP5xr zi!BNHO?9Fra#=4zJP-iIGSwzPNtt&CS?`JvpBUv<~Sl};o z286i8i6^(38zs%@ay=|FdlB}4Q67cro$*h&t_9QS=-jm^RH|}AvCoS2)mn&XRProc zMte^!mqLP1g(82+O~N%EzVJEZTCfp&X8&Z0$7+gZ%Q zAO@>Cl=`fO5Ry(8z+UvY8(E^Y3_5R@dvrWWJ;Q-oMPJ`-YkPS^6W2#ZQBVy@8GHQhw-anD@lh9EY*IT$XG&LBQ6aDaZL4SQg)>fhbpCw)A|B7a5XC4wwUd z#yI{7DW{umJ6*C@n*jt4QJ=%9ncVOg9@$qw#1hhuJZ{e*p`{TO~+>KT`3bzQUV6#sPg%&ITrt)%=LRIrz=G}O{Q%U z3<=91`FzC(N1D{O-6|p4I_-5T4r|ZsVSf_w2MG%iL8fOv5~D8V*h;O)>rXds_G%nS z_(F{-+-Xo8&9S5ZJ@iLN6_ubOu=^(;`{Z@L7c#3Q9uv7hvqHj`0~ra^M2MbOE~RA0(<2NN99i0HF z%PfmjM2jhoy2+Lk=x&HzHIEzX@KHhyYXz}Sq%JY<`y%`oGZkPw$_ja98I)wX=x|O} z6sR(8eM{MwmwZs+QB@6k*QYkP#f{45*G4L5Z+%pi12A`8L~-WXMtgsX+5$fFNfqL7 zi__=tN{)Pf@^7W%NJzi{5*$Us^w{Ey45vIuHXq=Xhtm>}$gN8$Xgy2mmroc67vIkq?wrvYepe>XSWY)XG2RP$?;TV0r_)BJUsTprn*@{edRs*3U8?nk;XZ z{n5ama07sBxhpy!dq~ckiKz_9g~h2lz;=h2cc+74p@o>c{QQL$G_9)=l=LiSuS)19 zPY%|XQ)wv;tH;ORd{l(EPEgwsQrvm_k20ke#>a8{}qT|63lkTH}Yu+9@ravgAq*48u>k0Yu!f0FzkHW{2CPSJl)H*0zIuEbTWGHr!g0vB% z)?dj^&X|>!Xh73~5a`hyW`DER6KfOscDZX+E?rwwBrMc7#g=tI#7ZCN<(W(mMklrQ zuC;;>K&K*!?~4hW&0Z59jKB7eRZb!V+n-)Jl)~1=S;jE4;`)Vq)y80DfH$w_)f|h9 zE_eL#%$ptdOHM56>;n6>>|hmV@8>&J1u6in5T1@x-J2BGw~K;frg1DB5T}Uq@UEPl z$yTqP%iVpnTwSUE^Ixm|amt+b$9oTZ8Yn=+(C`{4v%DI}TtURZAv%ueZx}OmT)Dp^-qj?(l(P>q^zEtNv91=h|e5+o{G{16vSl~V# zxQz*YHUIL#w2AB_77(y#eYy{%baqd;Jp5U1~U=4$Sp| z59OOCdg`WS`Fu8yr4r&LytFhpg3)Y@$;&TaEb#KHkp>`>1hqftI zaq}Z->I(@0?MF?XufOwuSTNm|B{c>2JAQ18J*U1()Bo}rS}S_!f4TkX)Y7Nu)@T9! zZ>>*S$~uMNDdRHpF~@>|{;xdCwy6wiTRU(4Z+%bBo^rX-A4X4FlT$viq{6Li^EaP| zvnrVD7kdlbe|Jy0Xj-bjeeHeI(_isysJHv~4?>;84PfeCzNQd3X@_k>5iXLvdd}$& zZDQRYv?gO<)rpMz29Jo-ke`c68d7r6$o6}O3i-fO&pGn_a@6hb@6G4=U57{fgLeh4 zOl;@8O7Z2c$khK}oGe%@mIKqsB`b0lKX1hHu$%;v1SVCX`5!HFqZlQoyx2G?3lzm< zgLp2~x*TY9_-BT5a#^nhOhL@5(ikot%lqTCguE^ZLX|w?e~~a8t#qxh24p$)6a?|d zgK*^3&{k{sjY%wg1b}mHd0uV?gs4AL-#*)(_foT`f8m>`9W&6DC^Fn-iiL~hCv(&E zK#kc?evyuHxsdy&PYp)pFqjdPQpGb!oq2ELjm8DmdyjeE%oo3-K9+XdW%{T;Wgyr> z{eX01TV?r9|AhWn(X(44{T@(r=M^@agx!IFwN>@i*D`8`Pb9yqT;v}!&kUz%1e7+} zC&zC(-c9~pK)7l?yH1DkE?v&bL(H~N1lEKQS4WrX5w#%&zZJCL0V(x?9<$FNA4;JN zL;I7gxN0v?G0$cS5cRH{J`bpq8Gfg~(mUEzNfBvxukB#T1-lcwGH61ox} zS*WWY7z|8bqfHUtWK`iEj*tH=xhu(hb^e9ie0%Rfl`Kqne-N5#`B)j#Pjsy%0&rOJWN2=ZMmqU6Qk-CwP~m}UpcMsw|(gdD8ku)P@&{Om>5b1Zy&j6Xhj zkXNfR1}i?vxK3_N1f6)Au6(=*+4T5hQjYZay^Pox6V7;-ctJ&n#(K6f*8hLYSOI_& z(s8H9A|qcJ)@@;9*JE@!k8zrg5iA4+-l$1k&;8ROc|}G1!sXFWY0* z8^jDlm__cUxAU)?a_fvR?*W6(DVh&+G{QngTRVYuw zes7^#89Eusm_{ktV$?EtC|Ydg}vBw#l&IMfjmVh4UuZ_6myFu>(1;Iy`+y;Agp%MYhB=%=)$GCe&>9Cj8X~`wFN34mK+0Kb* z=Y;K*Xy{RUrCML>e_b-os)=85w2oQ=gDaP*ni6v8kV325G#H{DP0FY(TKu`TVcMh) zi=PWQywjTE+>f-yC9wX~=_y;bSMf8|Fq2g@n?O~?EbnbW)6b=ekDNF4`XOHq9dDtp zf~4^`a^k=twCp7ZMpEN9CW!kOXA$FAa5i$gY#J1rO-T`Y_Y}vHpN)eur>s`7j>zA< z8r+Rq&2(ti{C`Tu{s7l%;%f<0dOmBhi+&*x!G~NtqL5=cE&O$Ep`}|KL+rL-0HVO@ zrjimI%`0Z!A`5N+*sWgbp3@`@VIe(Wglf6oI%dd?&C1?hiM%KNfgUA37v!kb66GXr zXQ;i}L_#rbxA(28A4|vyXS+dYcFWt$?D+Gio^{yuIf|#jC`p?+CB>%0=4x^!CxEXU zAW0}ti9^x>G<*8%n0Jc~c_d9j{}xV>rq0jVK2&u;@mWr)@)GIl&-G&{Lz}o7#KO}# zOph6Y7Y|jo231*3Fn_uPCHL^+K#MH=(AfbS?Vcv?V*_I1X;Z%!7__SX{O2rsSx#Au zn$7AWDBj^&ve${b&XNxYhF_{)5BmTpfv?V!Ct8xt(r>SDZrQ6<(B zTLIns6}BsZv^UTS1Gc?A1Yb7v1WP2H6rUjm4z@F|f$8CIjoz2?76rfzpXkz-m(tzR zmY)zV-3mktMjc2AQO8i!kV%!H#b=@vG;%5O7xeve6jvbgcsC1@h3*h3|U3CZZ^vh|IW^o|k;QYbXAj{c39#W5;A_G#4F`vTH+JB@Wn7ymQTQeoDTPQTX*^hhIL)#d_iLTDeWxg+ENLAxVR; zF74ig!;1MvwDy61t=H&?JV6I6WoS&+csDYsnQ-?HG|*f5Kt*q|u;sQU z*=G64KsKpR*&a7MbJd<6&)oO}{R6_uFBcS7caaz2QlO2F+}4qP@+d{R+b6n9S3Xhk zDB-<*5Xh}xS@9@~;`MKKxRm;sV&3*XHn((^u6?6o-PK`Yx))x;TAm`-uK1Lir#y#) z7K(Fbwl|YncWz}WUh|iEhIB3qK!JtpSs33paVmu0+qLfmyO%F^=&pRD678~b$jPrE z^Q^s7IH=-TNwXg7rkumhtGsxva}eH)D#5O*F2hzw(UVwSR9B@_J8V7suKN8M>Eu7F zZsq=3A4!)j@d}|JU<2K?kMw=20@_#=@cw240n3|}Oe`b5-MK6IPJM_tHW03=?t9r( zmNs^PqMbj^qPv`ODZ4Y5!{TlN1dY_++XuhstRj){QXM%tz29rr_@*|5 z0*uwT>xQ3Qlb!OIG993jP(#`E{YgAfU@vGc0=75HYJeBf{CKq@VaV2}>(fewAf68- z?0x3(m`y^+%(~musalXQc2!lFb!81W9)5c_qb#fNm4N+sTC~yWov5#E)E1TI6+SZ3 z!G{`1SUyxyA#kvEC{`t$U0m>$g#D`>F6M=?pCuF=e#T1GY-D&Uht5Dm*oY3jH-RDO z=$DtkgKWU0)@*jImY>y$%_eYNkK77VcZ=>K*5_noj0Z7j)IBHb7L~g7DSVVs;neRa zXmy{h?;LH!x@fcLam)uF3yMQklqvcCUHz9v* zqSrUja5IzcXYlt{@1Dpu_F2_;Mp`&U_ySzcUuxtNBd~mEb9*M~P!_?Qu%^0m)Ch8Z zBIsF0nJ+!QY!mj%;FD~TY1eS)IkGj+4iB%j3iB9!8cj_jkWZW?n)%$I>Rl4^@R)x4(V+|(Oy_;;@Tf>7b!BU1HbI^< zwtT3&0`nN(#P*2n+T3aHR63NPZe$hn|M%x6#pgai4SrYi#TdWQ?i6e~gAZkUi}@3_{(*TK2!57K8~v2cXv#aanwD8)4OA)bwauTEB+igg&2dr=xd`Sdedw|u?NaULN-DL4avsrtXTTQ1)g?&YcXs)Xh~;y29}1Oc z9R|fUnnZ?kfZxq>a`K8j3D-`Hbtq}d7UInw{mvCvF5f7^Y!%mGmc=4KB=tE+O6X~2 z4b57y6nf3G7CY~vd;k++MIK`u{@3;Tgh8F#Y>E@=h1>ckSfvE> zZ>$L_Hsx0ZMV%3>kUC={+{${+61woSMApKcjvBHb|EIBx>Vw*s!%<%_E6ALrY{AWc zbZMBK4t#?{jTYu@YvLAWD!Uq!00M3qh%OlDj{;osQ+9aQLru6DPGMO99@{+%jw{3i#pbr9m_uf^vsVt*h7i+Zx#iR^3P(aBzwapqP#tSs{~ zN)(3w{{I#oz`ruPj>23X5^i4D6?vjMnrh3NgN693Jz#@*=y{!;4?1c$Tfv&kpBbXB;AxsAH0id9V_P zrK+&(V9@l*QZ#|A{3L9}5K`7cSusY&jmNE+R*J6N<* zZ?-CN6@L3AppF`|!$1977RK5*# zODc4nLn~HGOe~W-6rRm0{zSQ1Wz9&1pGoAui|82QfCq|g=WyUkU_;(`@Ffqrp8=XZ6i^=Nf}G= ztj4Stv295O0FCBQ8*@9Hc%I4r8ld);00ZI37jyM5BP*-bB3k||V4MSDkjq?5nz39l ziuA<`?h8@O;Q+KtC1rtUn;->wQRG=d_U;GeiWd%=^)=O*3K&pRus{5z*{R)2i5D=d z-;q<6JDlpDDFAxTYPfiNTFv}tFAMdzZ{G`8Pf&fcoFLMPm zCvhtkjY_6npR2gU+Yho+pwPlW)Up)wbBUlq258?FEVAeVzk++whiKl^QG*KFc4g=x zXniN*FL|rOmGz&3{1$Y&1KqqSU@YI&?*fJDjIJ9gGk=bUXIB#m9UaV#Ot|51)sOG| zbP{qAjLQA-3d;E3vN357hcfHn_ZbUDtQjh>1VgI-H!wf*&W6W~{CptX%#U`xqhg`i z>Flh998!h57--yI8Nt;y0tKtJfA1IuCE##x2J?|2TlU#ULgtyL)MG3abxJ{}%Wzbt z=VrCjIbSP26arlUF_EH(*T?#rai{-~Y%*hs0j@gviVNi}GZ||4)@}f-Ge0La;JP9n zKb*XrKb6zy*(_@hR6I%5&hDkW*U+_hrdcAivyzp28aQw>vEY384DSg8VM1w*MJ*RA z$S7*{%^skCqy-9WbLu}hd}7h0g>*iAZ|JYFn0)(NzivN%X#?t1n4l9ybU1en4!)C= z?;9$b+fp3wM>O%Q!i+E`=xWe%fLQw`max)#v+gcoO=R9o){^w) z5^KSX)h}Ol?g(fjzAxje0yL@?ZL(qD)Dg~|e6seJd`Ik#g)TaBuBt(l2vmgSJxFK7LEj!O9t+eYLs z3WkCDw#WSCZZ!X=3Ji<(&-EHfqBMc=?-EKragl7&-xA|q!t%Od18R&~nGz<53bjkH zAqa9;oqEkFDcr5riiMs;%&t^c&h65;FSV#dIL`AC>_lW$snNpDatyI{2TH6W799#- z29db&GU`aw`3UGTCLFN9wml{+az)j^I@wP~+-6_>m>luENpqOQ*|dc-e9YGp3St-I+3YEufB%irQxi39UY6@eEq9upnPKgOW=8 zI-ty6#}7ExXr`sUWU_Hkg$Y` zlrF*WVO;gqMvjz(xe*M&FK08qvMS&vAsw68la2^YIQ1V0xH8mPW8p-=_G*t3mRN|3 z1&Z(yMyc8sD568mLz#guTCWUWG*T^~RTUNx0)za~NUNJc!GhUV6l~9CI3KV!0|q%7 zVA%lC-pgz%{9eEnT7p-L7HyGBJtseVZKIC@QmdZ z(N+CTvb7>Il}XmXw-T&EukW1_Oo>D6QveJdIrMM^ap8nUh!?HDcCcWeBB6M?x3x4zRl^-wopg{NG_%O+AVd@7-r%2UR2FS&LVLsuT!DNiF;85uq@ zSYT|L%>ura4u-m-yqvpvb@ zR^S1TAQ0#y1P>bH#?E5h*<8~P?BLrjO*M2#sHDBAi#H^&fhO(ZhVyMF4g*AvNkMmalu<`kWg5- ztnmiI)xy4U&1gT;zI1iRuT+q~8VfJhxk-;Y3c2WZOQ~7h3N1 zLzVqwxl~$JC6pJvhD+>^%R(COkv;bFTUZ6cC8wPbFK6$5S}sv63NG8*Iq z(J6n-TGyLqX(&HSXq2s~@b#7K z`HvMA`-saYk)2M|h$(Ru61@oy=1qL#>Ibhv{>NYcSsQtx zrl@D2@4x@!$Y$DMd{0h$Bm<15%O;Il_ci~XE@!_Rs&mA8Bp5M)ylrQvmVcI?EYoKu zxBoIV5Z=I%YVYQ7`%>e>sIO0pfKnfHS%uv2#F^4?^)&6hpqLr;2Ot~GpxXLo0DoEt{BsM-}TZujTP-_Lff@UGB@#c=24yb%YE!5t^={Zx( z%Il)?gkGTN&oMG4-plvx)(_xdb8i+tB1vb?w>2@C1m6)vQ?VP&` zh=8lZl&%U_T&?sjp@UB z)t3!#@O^kF(7k|}JK(e+Tt1RcjQzcOI3@2}Jbs}PuUTg(u)oykLU1D=jE)~%O7|%} z7lk8ES7)5wnFrE1!wAU^nF?EtPM@zNo$)C32iW72C?Pdjl@JpykgtS#d$arT^E=F> zN+aRcj@w1T96xD6_JupiTW@JBp;Q4;!PM?AowyQf7IlcD@;@tKi4sH;z;)oD-dV4_ znfjS_UtNrIEJ4jDzL1#*W!<=xLrpSxHX1r!%Ai$8W4HaRM|kioHVx>3`YUC^S}=Q{J{#*M zWO+BU%K}1aRP5)mKIwfS#Z^ymIMiC}v~5WG+u>q+Gb}TV>oVKXI-z4dDgrf4RPsT@ zZ}KtKRD2Sf9Lhno*hWPBX%foN5vbA?UDqRvd-FUN5m5f2FTHEjpwWR0tKmx_VOejgvL;=!Q(ra3t*WinbG@~`FJor9vRNwx z`+>c-2eBHCIFPCFFDcQwxlSqS_XG}#B!nvy_LDSHW4Yq+@6;l>L!e{G*8Eg!-!Fk< zfJQNrp%T9rFpa;p97nV04FOr7_1tN<$O7<12X>k~Lg7G%jRiFn5tJcnAU8+^6gTTC zoZc|EtME9B<|x8khFv#oY-FdQY=KzIumP_#Jd5wi=wta3@o`~Ut|xLjoKw`MO96^o zod~%_$4ThGRNv|LbmMk^JgIvS(w7+^!qt9oNgbtRZ zD^rt{Eo?};cS|j$6s|$4;V8jD(jWL50}-nNa`&*qi6D1`NFfO`1~js*0aHjdx44jUf`D9-(tJ6*aym zBxe(DS%?jC-u26dpbj%ORF4mrQ)EOptnva@8Uv~D0ghQ)XxB&nW@JUi9Hv~3 z1D@DrY{y!nEAh!q4Ssp^%zg16hx5IJ^KQ*1VEg*oy(&Sc5r(bP_fn0Sv&MiiV4Y&7 z-d}RIRf(OLAq_XomWpJc#rmyiFiDc_p12arIKMg8x5IvOIKhdWeWP3&pWC;OM=fyg z)>6!CS#X3G6xXZp-c{Hh^R|3RbafWwaJ;x6=Ru2Rx^&Ttj*I4Vv2C*j_`$W-sb+c+ z@ehj}X;Gj_TmBj~qC!bcxUp%5Zh+;@OiL>NrG$%-KM-nYYvG_tZ2%vlJTN0dq!u~(~cAiTvN>zQ{5W6#>_gCW1i^3WC}s4Q!kdN=2%`S1KW;P@A^(8J3_ zzH*W^y>$&F-bm7~HE8)%`mJC(Nz`(mCiB)4`}|iI3EP|T?n&Fc-@rg;5^e!UF0Htv+1XTtfmB;=fUSHG%g!CHqbqJE?)+K2km z$^eIAE@u5sTZDXdG5HcgB?psTL-g(Ueh?;fW1p?`Ljiq<(o58pxe)kp`>eaA6UQp0 z@i;^jMf*%ZHr|Z84vM)R1tHW6;uY!=B62ddaAQXnx@mAGAV3b;@g3~y;{J%Ov1(jb*sM82)*J#m76d0l4)IEqQ0iFq{oj!(0H=fG!n9Yy};yx|FY9jzpTLD6sg;; z=kCG<8FM3@4i%Y#HH{kiwSQ#|LVqX)3yuq86RQs`&c}OgurSk9YnkuzTmAC`IcLE! z27T%gdp#_TT$2p3Nd31t#&d*h=Lv@>Ysmx&lnv4QwA!m#t=M2Wg3xCSad%{Q|Dzn{ zBGaBuS`Tbpms7*%%^=cVEf}%km@;DsSbA-=`^#lUA?>GLpWsvJfig>S2yWebKW8bo z?-l6BHv@;_F!6lrxd3!w5-juUy*^=6JS;enGfILS9y<(q|&(ZndRe;Ai!w1Vf#tEI@zIrgx(&agn-2+571fOfw`dA5Bo% zyxB;dvO`R5L|&y#5S?`~0WHr~dz{Y5Sw5+Gj*N6=5ypd?)_P`)IIhEL+Xu__ z2w~8RPx6d`588Aoj-ZA+pWx0<;z<@mJPXm&Ia3F&DHFoc`NoQ zO0K>i%=)d|z!4xZL#X`h6$DU`Y^zY~x8mCkI;5Un*W;Aja0{7J88@H78K;a2BQpX0 z&y)=cOUTu2YuizWz{23RMY}K#pUYKrg-b8K@$;jrIvgRcra(b#mUw~$_ZYF1Oi^aDdXl9)2iYK z!lHHyLVos^7`!W^L&jNiCb-yxBiX)I>gw!HM5aui{R1H(rEdyZj7$Y66_E{KoJmtR zZ!u7$R|D9nMWnmBrvo)kM65G6&SH4*nmIvG{`HB3D^qX$&0IpZpO4|yFsFTvWY>b_ zMMP#Aj-93)*g)H7pv5X8f)R@;6RKextV27{qe+ZBz^iJiAxBxj1|!c*?I`7GGJ5q8 zigZIWAH^CkLMCm3?(io@S2X$tLN-%n4gh%RUv_D`CSqNa(7%bTUNfF-7*s+77!_T@ z+v_8_y`7Fn_TQei4Q^+9DrXBt$?7vdtfKXCi<4gK1+eppnD;1&cahkv2x?ofd%v^4 zS{8&t^iYa9MaX)uO$|Z0xm-URGH^b&fP2n(+M_}Mkb1yt=@N(DgBGQHzipMXR&oJU zDTy~e=UzaZ{mv$&=#c4ca7Sq`9-gN@hvCbEGPIl0Y^!Ph84;J@thYpr41$UhNspTZ z4ExVGj8k8Z7R$mSm^uJq3$+6Qg^tu(l7$eMgqshJq&HazA6eKLFxkh?+|OoTXDv2w z0rLk7c`rf6g1)QYnakLo<6C7%svyZo&C;x=I-=Jk4LE4W)xux{{3Umz7HL=i^vAKi zTgI%41`1G6XbM%09mB%g=K6~1ekzg`RYfmoiMOm_koDnAdIWt}QGl0W zz3|whlX)}Jd?|lE`_gic=?C#JwfCDsZZF5NNmLx8vf5=hiBry@GGitt?_nU?U2GcZ ze{M+)!rZ||lS%Jq_=P4Spp$#?dt^*8~T@I(PmtkMYaX*jh$ zNhIfUB@)>lsyw_zjj|-R-a+bfiL1I<$t5Iw>wX6(;aSZ6T()-$`I4P!L&&3d1ZE&4 z9a?Q*3ZC~5&U#VhM9BEo%h$rb4obhC;UqTyQ$mV@DR zzp@5hq7QuQbRPcLwp^qH84b4@kh@ZnmHfq3WS>M@mZRkxDJk`%*s&QKUDuJNDkWt^ zZ8rj7^~3cd*^)kSIM{yY##Ok&EXrL*Hgi+pxAagU7N=KZhJG%bxK4@S;A~d` zR_KU}?pwlpUof(5Z3tnf?1A%~HB-&vxMx$ngpMe2u)n72kVnwGX-)9a%bkjUdh}J& z=JS1YQ3oDp-%TOc{d~Ph$n_H$jUIO7fRKxFV~&(HL42G7#HJ}5d4L-2!pV5}{WQWo zbTcFr3d>QL{i_xtfGmapPlJyGjn?(ZPd)3=CpgICWvPUqj;uq<7ap|;7;sH?BQXNq zU+^1kWKmT~o*ptRYpXfVUaS6G1~@f@(lU`YebSNBlbM~x^YsxIDhu!>a zqQ~fe3fkDH$S+K(W@BjGy9E*~Syu@ysQ)l5l#Q~^^t2tk{A%z3<6;_YDeaIx22ZM= z4--iP*Rjt^V2UjZD5u3H0{}aUU{^ru)}A2_Q=ZpLJ=6L1(LQ8@!6dGimlyABT@nb@75+ zZ>~JK3MuF$e&flvENtdj*41{vcQj2Aa1td+J>XqsMV)A8l_NCaen1P+O z95d_f{0`A0{G3Yyz_vM&tj12Frvx6WGUfxU$^}jd|31um+{ne*&x+h@s{C~b9DGfd zd+KjEo-eSR5;>40ZC1?ee@%dPMV1Fym&X}VbWzQo<6P45@*s7m6Im?QeD()pIVzip zwf?-2<;2PZA#kid)XgEwv$-AI?kvkor&js3J~xhjIZ1Ku67u^_5U@kE7#nI;BQylM zocBlkzn;gpCH!8A28b3c)tFbVq6ysKbQ~4!z)?7c_$KI}$?6-WB;Z;JW&a%V-Z$ce(6UWfdCAAUW{xjl-tWe6`zjI(I_&vm#;X1wBc z#&$N6a`bAaJV3{>?AUsevT5^cla*&Y>#{4XkWW+$Jc*DM((J&@+UMu*)lH$(W$vub zFPue8E^d_7aRbt@?7@?oXNBWt@>2$wK)Id*C{Ldy>>TSWuQRf+{!lt~gF`tn)*n;j zYy;4NS8<7WLUvE+9Px9Ctn%$a{_;CNYFb`ZtLx9<;9^?x10Oz(dgLj3sqqDRRy?nC zr#=VeBTI1gls&xsl49b>Ex@gL=aTMt3|QJiH=Cy3Uv zjf!s*N2BLA)0I9Mf;w%`DQ1uf5+5r2dS?Hjvg|+}dE`^wj&i@7CgdF1UD>4qSU!r&Gu0Yu=MY zAG^AMRN}s_ZyYX>H4Q~RK!gziEHHeFc!(o!OXA>HHSxmd&02#70A+*x`A0pJ{eu8T zt17f?XNnZtWj>Qqm`eB23Q6T}cG*XZ{mZ>4W&gPvWxRjTCsG2CW{$?M?bwNO8`x8!R;215et-jpYs zdedbg8zMe>xx<~lBV|+N=yNTdO1SSVIlY|9s|tSqPrfeOm8jUS{nx+#`#lK6SzE%huJDWOBxgBnu0V#AE9`ZZzY(( zWg~w6vA+L@fV0%C%TE)gtQbx!B6|pGl-F=fATaj?jnQ;#Z-$^7&bX}EpSlPL#LFTs z%g8W@TZ5!V4;?PDXb=C8d=kD%^f-B(mkJzx`Sg>6rkdTbx2IE}CDULz7D|VjtW|+o zFi+>w8XHVApU^(=>%-{Df`KWIHs=j zSeH*i@ob-6?hUV%J1R%wNa+5sEdGXn;1_BfbBI#vC?L`s)imqmlh4sgmI3iXVAiI; z5avC!lwhsT?5SFdj%L`8>sKoCSu+PJFW)1+Vj4P2WzsaYmMMK`87~;fI8?R15_&Ou%nd(N-~(X&FFA z@lJuyAR)@7Tt~m0uNd;2U`>~TNH-y?gwg4>+&9CNNa2Qf6_(J}ZD|aJ0|bVVHJ2-r z4%Mj!_!G4`vn*F39p)YH0l-Ptnx8D~C6H7qL}Sq(h&StlUc?Lg$0yhN3Y@o{yHfAj z4Wj?EbI?8zFXf&H&Td<;<7@FUocnn4&LC5%hQP~U7*raQy_RH0*Ry5WmEdom2a6JqPXIe#C$`&Vj zKZmWXP2XLmx;uyrNIO(2xg^*Z8ME0`4x}}hW7n)<`&3D~>mk4~3TB%&NQV195s_M+ zMLhSE0*K^d8sH+YqKQzCVk>Ne$b{cse$o*VD8kB=6lb=%lMvt(ig7Ad_3g7mR*7Mx zI{5jzAJn$2Xp+SAN0FWCw(6`4T+-?N;}_7xv0_$D#BvrfrJ#fI?aNtAzM!{}j2xVS zuFxKIt{}DtamtuT96%^ZSg7lkD%pKjV~J=8yGseI!^#7>R8$BQ$R3BGI~+HPP43|>9q5%Zfzm9|L? z(ty8c@#LAmb~g^hB&l&!50Ij~8og^zYbop)g;@Fb>MiepKESM*Uud_0M-gKH$*vcEz8uvYHopgfD%>99D7aI!*R-~39C zRW$VQ4J~fAa4^`3vi?JYU&H5g{w1tSznZXiw>3A zV-K!h=BJ@_ylwI4bLplI=FyZAdDmu$pH`-Iu2de=trl1LLW=Y-HM?1zlbDdQ+e z?!^BVTQy7%V?fbK5|{^t@2LHh?eSE(uEptQuyYXwU(ZCk)RcXN>swxV5mHI{kN;qX^;2-F>NYV?a zLVQ<&fPyS8O40U-AH}eJmd`}_5$+)s96&bAq{i5a;L>q*SSnpDA3k}g(gMLE3DY_6 zF13|kEt~?`57nRY_gmWM8->530l<`(soZks6~`B}gdzs`h4TAKgC_ zAUY^j6`)UR=t^5KJm=F58Br};OQxXq(y!kxL@&kHO+Jpf9b)tBA2cNbIzL-yfBMEG zv#{#22}1vf88xyYfJSgmcT`iXKYXGKKctPHOAFh*MZR0&$+;hxu39JnA2QV(fElda z`%X|wa%crDbfrZGO0$EljFBZCG!7)QO1W#SIfY-xHjv$+V6!~&U&F4A{CJEy#kWDo z%*7j}U!CPirLZtStT_2ZeM@&^5YF6&zltQv!JWc75HK_f^ zYNv+Dik;ifIkDwzj~=vENJtMR2Qc5@s0K4Iw~L4j@*v~ockV~9%6R$J{W&KYtAEbA zknXSapfwqt@<|AMM~}Y$={2h0y~d|{{EsmWY*YH_@gHPrX)G?dQrU$3n7a$tuq9YA zr*H~|Fm083hy;=VH@Mb*^0dz+fdW1p`k`Dq&Zvb>_@J3XOp8z{{6~Eb@Yku=-}lof zTD?13i|1_TYa1TZLG)`;4L zim<=qZb%rmyJAH?`+yQh)#_@>fF zlivvWAT$R(me>cvpOQ|O;90sZ6pn?<9PJp(GvXj5JbkIef(;~8Q7am+Phcoq$Js3)a(XMatyRiQ;Dg`7UdJCB{jc zTbt6!5t_LO57UUPr%tc{V#J>~dR_g%k7hM5EA|v42wQQalz>F|b5Wz#92=IxaJ%_! z**&EaUJZSQ_h!r4y6zc&Cxf!%(ufCNy%lb|+dO%6Y-Tl}gjJPjB1B2eToj)BdioL)`6RxdwJ7Dt);TUaHrA|bD514Y*dJOd znB2~6S1YL(D1;Bn{u%~KL+@2ZYh)1J}_K6 z%R1l@EjT9$LmIIwK*?4DeBzq`E)mO|)oHPw)0MFgeP5Z0G)DistqtxmkKIr`nK$Ow zJZ2dx%t+XR27}Ei1cQwwQ`~|@Zs?Vd<*2|?s(dNo4Hko1ayM(I!9a@OUh_=u7OL^D}sl69t|FJ^f{OFFS?H8t-e1*ks4y>j>?F_r^XC z0}-GNyAbKG1Xvb|T_5g586#+BAZ1HNCyS7~l+VP=CWpo3PVZtFN%I+JNbflmdd(~g zfK6)6nmyiv^gy^cSx3y{afEuH*GJ+V>6_|&fi{`!8^wu)?(2()snra!Qz_dCQNar$ zx2U~rKY2WUetA!2FeC#K`Sc`AlD)}i7*xA}E|TKZ_u@VLOv)s=|0PUNX0F`H1{P@0 zUWE+AgUQI}5f3u=`GNMPHE!oV$;Ei$;j*l;v1Cdj11WO!I2c~8$VYLKos>3Gx-OG( z9I`pQ_%gAv zJ3t(J3oOO4?aiKxCFn(Rd_8D@d|Q2x)^?IMqL`rPsjGw{ZmpZeO`dmIiO3HV3D05h zm6dMao>xqdBXEoOC;7L)Nirah>;gp{w?HFRa7C)Sksc~k0ZRo8Lve7+lnRb|7ALwx zxRRqiR!Z;Yvfn0YSwj092m2%~**{`nz|QP+8Nr0D*p1Fqj*cgoutz~BMTE>;BEQ*Z zxS1Sx8dJ+;-vXmNi+5ajRH~aa)-ymS$~kO*G#?WLC9OP_gfwI`PiaYkbGv3>mCa&u z)p@*V|AfAN0B>1~Xfa}zm@k7(L4+n4=sC*2Ix`?WeuB5be66Z0-t%RAP(=nJwks75 zvoT;#IK^@DvPM57ZJZ45<^$#B>pf=J$pMb|FfMQzpnh$(NC|0etoA1hTy8~-;K0@e z6vrk4cFu)|hL4#y%?e;lkQV<6CX0g$gON>b#yR($vK1A6BVe8j_@C3DL~$Zu$I{k0 zcshNBEV6l*TkXB4*-oJSEKqL$0@Z9lM*tfsZb?SBTwOo-yCcYuCTVCF{l;&$d6!PU z=Jw$A`G~^uS-#?gFCL~H!QOd(D;|IKd;)v%umqvJj(aBSV~nN$8JFFdKmuVbke2oUIe)>+IoLz=5GFZK~qv;hq|$Lc>=r zToTSsAL~8E2fhG#LN+25=07U5SN!I|gJ=#kv>jNj-;^Z)eexLyw3M!%B`>H}&auE4 zeW}8s2?CNNmV@!#K&%iOJB8N!EfCg;eV*%Fu1_3S=ZQ!1ipE5Wgt+!lJj&rsHu!5I zVnunw{b|ELuS9f`mDFYW5EimrLD)gSi@ZJ0S^#L@)3%0f8f&P+=3#Wv;0sXpvyql0 zZKOi&E$Ez@7NWapuzF&L$%D#d-Wt*b>zeq`J_f#TqzzhwtlabH@kykeHl<=2nXDKS0?Dp#t4c0UUe-(AN`v&Hy0 zJ!t=8{m(YW-%rT-{`^GIC-nKGIp1Kc<*C_*$9!lmg==|Ge<~Ue|3}1}5!f!rvpa~u z{1>nHhMfPOw|CjGWJ%6*-(`=*M&&)Tr-H_s9B`tMc(5DbfRrFLArXS!{d~W>N4S~0 zt+4P|QK!h}C3j_PGq?La5=2D8D7jr|2ew^actO=68%1}z)@xO?MZt0gF2^!_E~MLN z;3g5z<46p2tbqnndJEZRa|so#HLbl0i3;)-vbF6|thClN#&SK~h-%DAZeGz+##ehK z6(Y(JI#pifN&PNVH=6n_u}FgD$>%DcABcGg%`6-l^sF*2tZ5_}${#Yw9pV@DKx zPbk_4FGk*S{}A1O^&M|Olz8r#Z9P37;7NYhgO|%@`x4EB<UDvQ$k5`3>8?doobx`Hy9Nit~thZ*S3P);i=mI zRohO`<#@U;^%rwdkm8iPWRz}+V>~-W1-xT89Ng-BE)sNlF^lK#p{J7l$9V1{`WQ_d zRV$$sqz~yieMmijl`(#ofYPA=9!D7<*ELPMfw3&ahs_sK6C<4%1f=wu~+G#WMTDfVnBtZd#=q8&+f)uNTSw{k@T|Zd>9S>G+tZsh8jor zyuQw z6JR%XbyLzxj?44lgWYPtRZ#6s_0%Strl#VWFr5oqLTiu0Y+RN$n zs|)S7HP9uWpm`bE`>7(-POD=|D%Y_8#-7%5U&n4%+@JSnNwlwMR~Oim@~L1r!dM$J zWLA4M)}yoKlN_JW|9BsgS;@-@rH`Cx$!=J>q#o>-GHm=>PUNX7+=V3p?1FY3qWX5r zc+i!go+0TUYtMl=eMFD*ZAhlQfu58utl!dk&PPa-?Yw}u``c$iyK+N7!i>m*c8y_k z?hEQVr6aBOgNs!3==4-KX;&uomb_Q*j&GWwCJ{_XoN;TJ+3D`?rog7xx(iDNhmPGk zYbS@$s!a*`IIP4KDV8T+>ozR20NTr>3zca!t-8TQ!}L&>o~1)mdHTI>!jpxRD+<=d z@vWLUWDibZdG@((!!iq>6KaY(UGCr%&(6fucRW*U?(y?(57TZ-D%K_05X@^h4l#1w zUg0u?N`>BKDrshXO2rCCuNX;4=XS&=6wt8dt!ldWRwVNtgRQ;?9FwgSY~IAt`PhE= zIG~(NrG8_6s=EX-jhekcjxLXY^R7x=%bw^~n@Ygr318|a49P&PC{|aGqNTpT<{i#D z4snd3OC-q44=6EOtNM-ExNUFb{^h<@mw>bB;I(o=Qb+lgWGA)q<|8sn8t z@q+-eAm*yt_i0jE>X$UBi*A()5OD5?Y6#d7s|6kX&mnI$W&-pZEG$s!((~b=UTfO`ta@nrPv}J?7Oo z81a5;o9MYAd&7c-6-DZRD^=DajxOM^NIF&Oet8eGeDu#R?_y~3v1J|7Qd2e!8(IA8 z#n3^wqvpa{hCB+(9n#MQfu(*NKGBY)Y06vgy`qtEMVUI-N;iODbD{sKo@F2D?nq9L zbrX_l_}eL2{*4aJ$IwZ8JS1fWJxbXPvA^Zm=V;0F)Um?Z({C0y)07l4+K%Nei}tsN zY~*8MG^kxDG_r>vQ>LgP)7jdj(IbaXVza(kn?u3Vsby8h^&YNqi{a(2bDl$!Z6`P{ zM_mq{gb{GF(cUQ-`ELbDpA=|Wj4AG~bjKxs7RfB(KZs)l-Bh&Ck&OK$8~ESo;V{#Y z2;=UhmS=Uqsi_rwmfY0xmB0Z0#W)3no54EeOetRs>C%0v9SSy?r;RdM;p$kRq(AS9t z*@^spg>j~YvarLcR}Y*j1>&;_xRhVLMrJ&#u&bLv+xjP-);ySB4Dq2e;3+v6{<`XP z$c1Mu4l)gcX{B`3-lezBsf!@8BFg~?r>V16dM}gCDPev$hHWRL^I78u@;(#;nIUHD zJ}YClS=DV&s?MwAB1*w+25(31K;c+7_xBdw7%&zap7&Xu4~{x5SUPvTRLpiP2NK#; z0b3&;{C32g7f48GyC{O^z}t~~L_+%tio>PXG<-ku6+Q-gkICTFGGlpeT?py^=mpjB;LESY=& zUQSZi|1bG`@TJ=j&0>&D$3B2B#dOFev=o5T){Jb&ovZ6+l7)OpI5`m1CbeZI3z{=@ zJDP)*by4xdsr{RX$iZ`ZSinhes zyFdNfo4{slhOmrvoLXu|v848)@KeUy*;&I0J6@1vj2@^=?V10xMndi?u0k&*9 z1T7ehe^nga4=Gf9{DomSPN%Rfm&J2zX&6i z>E+IXMb+b(PpWP1j+o?4mZw@53oQjp~koZBwHxK1PO z@H>>Y9e%wce>yBA(%b59k3mgW?I^V0+Yx6C6q}#xU%Cee7Kk0=fDLo$VD^n@y%7fk zcu%$w6^YXB5!w(~^iFP|6=w#m@k_e8%M*HoRZW}`VcM2Ebwn@qL)>yFnv^)|IM~Zy z_=i++c{moPLcY%?m}_c-)eDJd-LVv<9>BJQq`pI%BzmmhgJXJBxcg)kHZ6tIb}@EQ zA|h4&v#LWEc9C(2%-mH`8Dd@YrxUVr_0F9S#qu^fris#B;wore;JolNZ;WyJ;_4R5 zPYaHoIUkGa^J;@dMTy9DLLJDz77j0vs(eWoFeaJ@3TRms>Kgp98u4CL2nZ*Ft?)y^ z-q+N?55*~XhYJW~wrEG73Qq{h1iz6Q{hwZP9z4Q`&TYcOBhb~w*O#zIf3p(9$lcv`(xML){aEXwd_h4PS&dg|YbxH6L zc(EIbPCIr-u@kGUVchkDev6~g+=Jjv*j>Oajna#ty*Rq`fzzzjj@Mj@{7&9ZqY4MR z6;a@9snw>rdc6uqhb?uwegT8A47loW4?kFAVSmWNvIeYDME((fU+dm6w>3$>EJj=} zO`3HwEgeK+r9&Q*q1;&w?%fL<~5TADa#3Mi`4Bb-aPDzzUsvf36;B(K;>;yVj7YCK48J zwjTtb}*m*oKSv zA(^ZT-{paQocuSYg#$v{MX1NlsrV~>l}glgbhrd@tereM@RzQ~u~8F_YH~ViPT)O8 zM(Y~_{mVW!$E5dYV7zn~>KI3_!eUiqM44r|vj&J1hgW=687`6t@YBHCgCAM~t4UdA z7=X{Ag-CG|P;r!7%Vf2+>4E}Kl$1qu4uJ>Uv1H~YGR|A*;oR@A^5Dpgm17=rW`)#o31PeCcDTj;5rw82Io``ZBtxWL95r` zZ5@GhG|CxC){W_bd2K>BUbMV)aW(LnNR#UPTi|8M4r#arBv>C`$8HF=X0$KBpM{VX zetZ<%DRxw|J{C+`P*0WK(Rf_CcfvcfojgDw#ru+*h~7xg(K+}j^1pJLk^C~J*hr7n{2jn^JBj^R!l((w zp_fI9oxD7a#`tV3Q*D_{dAu7N)&aeBasb@1I`!HpRx3s>+1))+gXCwR1-ud~53>$_ zy2R9jA8PeUEB4%j%-aJE{7W~$sBaJ_UUApqBo%$n<&XtN$O14BNpN_B__Iya@P=KF z#!m6TeYeEl;KOaUV|=`2#t&kPKm9p8BZa4$izATLApk|My5~?>=}0or47ylPEXCq~ zRBrhNZZD%4w74GU`IAijT@J1mDj%b0*-cuDG&d-cX(f?eu@Qz`c7l7j)uHpL5cklF z=S++aq>?Kk=+&`C{Q^fXutH=qIpX}usm1 zDD48UWlQQuoNQuJQxP<$${I=^s7VS#BxliZmttV{*{HkxP^g@FWRasTDHFe|#8fL9 z982V7KTz9{soueK3W3A)9E%~l0u{RXpHW^`X88>?2Rks}JJIQhf2!jbl`rs65eIGD zrunHA%G}$Z6}t=IXZ^3vGV*w3V?X&fdI@!7weYpbp}Wb{l;MZjmWcC1v>^wFN)arj zF!Zf;1ky#V9s#rg8BFTZBZ&0eI3bFw(z9cM&pzp7s`?ak87hz>k?((I0?gU9^?Qjb5 z)7e?ga#zjUR~$L~#mPh5C+Z$2oW*kwbsvUVI@DoE6+{jpr_)K7)W&oEKO_qO1V>pH zz$(^GsfCiqui$=Z9ID*Yyr$HM*%FK5%^_-wbK6)$#tJYB71m!=)RZ~Fuam>H%9!kkxiwqIur91<-;OTt8pd))&^}=3ssE{b()*d;hGK(gm_Y&mmx;na&a_L>{ zMQT40Ag|&=WreD7(k%=fe<=-06P5C9q%q(K{S9h#lWJVna%3J7{_^lgwqjPc%5J(p z9-BzdTQfyg=q3|NShSE?;m*3w0&?P>!ZHcl77gPFjBc$bPwYeoe7jB_$i8BPNF|aq zXRio25X6a3;5fV*=*B<7;jMjM#{$F{93AFLRC7pn8!>vvR1ntiZG8*jyiJ5SJARC# zV?j#$+~Y;W(Q|F-7Zz8p9RELYI1_+Dz(RMy_ZNr2b=8U_V6o1;j7F0P638DZg`wwK zCs8_9Ie2L#NWQ3&l8wOcYAd|}K=y`gHXg9XuqPEjFS~pQ(w8(Ikq)b*<%TRq29pf2 zl}Yd4D`F zu{J|r`1qvs3jBvwGJXaTk1Qwkdt4r}6t_val+v-3dn`$*ldz*?g^iw1Cz4lhOZYwfOr(o+BZ;j|&I1LvjzKzxIVjrM3OJ2P zfEa1oKtBf-XdU{rvBp6UqoDCo_=pHaswxkYM?1WI=sX8Jw+=k1=40-6MgkQt2c)EQ z5%-!9VM!iw2o6nIG(cgtM##Xjmm27TA|=XILlwDN!JHyHEe&|q{H_#S)otq-pcjrY z@XwENBlQ3*iWA%BRSL%(JYs|Z7Yi7Jk~s)`pxH{4TRJp~a#N0u*q&&Lra%Jf+uTDG zcj9_DvT#{g2?df3xJ5)+1vnb$RGP*ep-lQ+v*?G4mr@pynR**O)L2x%!Y6S+RLi2j z0JCzN-c{4pG2Ogz`lax6s{Nl8=S}f3IfaDt29##=GArj254iCE zN5g5(N(IJYvTk?b$Q1s0vXSi~uzV*}B+G;|Ty#9$M}u1|vU$cFl2Fb|C)}&HVr1~U zShIxbhZR?6$UqWXN*GVz{EAxNc3_~~={f$UE=*`zdvlJlMlhES7Y51X; zg}yp@m_pMtlneW=P|-X512}gVw0;qFjeH*hs?N+!FyKgb*6@fX;q-9HsRsDZwu>jPLY4r+G*s+ z#zzStTzc}<$kYcuG|10uYjpu_Ay}0!K7f~di3Ftpen@_^44JXRl zQj)Has4Idzu529dj9`t*m6wk($ERan6#gSmRGDv?2)sxl$rb~AE#6Y;aM@y}bsn>` zljK-@$Q|J{;Oc1Xk_h7(3EfL7~wd`JA$K;i`Q+>9SH^4hP)$vqskSJJjG_2m=|F+l9UJ%WU0G7)_E$u+2rlr zY56>^q~r6SP;fW-RceSkCenZ-wdONgbPyYegl2ffAt2+cGILQ~k=a?N($c~k3TXte zl$xY$Ur_!Pl*w-upB<$FPIK!zK9m8EDdNouS`#@%`4Z{Tu-@JlD^0XPP82mk#jP5| zBZR1TQUK<^=ygM;-m8U2v!G_^4Wmx23FfkF*qBL7i zPvMqVLDsQGn%F0Mw)JUxLiy|{FF{qCGAi1MwF1oz_`xjz6%r%(M9}Z9zzbQ=1~Z&t zC6!39FSn2u1~TqN&=qS^$R;<;6GY|32Tw!dgYF&D$(%g@7y*0@daQ`d=-b_aPBWXxfB@gkW_T*S&&m=yG$oPH*h>JrjJ zrA;9+;!fO890e&kf{6FqN(-omEH)ce+!?_Z>vHKyZfpuQl4j7QSgsC*? zqyVm^-XasWjDga5$HL-hz(!U12LzEQD(q%uG`0qa-JLt^F*whl>lmOljxq3NhO`#) ziMB0SJ}gQRcLGbY6qpP)kRdEJLGIWH&4hD?ooC*U`M#zmXag?`Cz;A(6=facT1SEJ z9;4uhfPo{QKzf2gE`0$tw$WM*wcpU!M=JpWJ1Z>up+CuZ7Mws{3Y7q?0Ya+~^(A-+Xc{D55FQ{-v4y-h$qm(p>+X(q z8l>$u4g)onsFCkYNh&H5g#r;fdj!C&G+*LWUo_xAa&ZxEDH)%hQz;hRM8p{b@xbB@vAlD;2CB&)njmu z9q*zF(syhDz5O7YND-MBghj5DhMVjYm(Y{_M#h(EvdMU$wop#8;Ut178&@xx9EZ9d zwC01L>{5olWHpbWcNEdwx`J-%slcJOHwiUU2dEmQE7hdc?6(hehi(i0o;tTR;HVIJ z{|?BPF?VdT0+*Xgj9{5Xik?RDmz2>`*E|R{6Upd-5XFKk*e5&}?#F1VIi0>>d@l`p zR_~W|3}#k+4)~qu%xiHLUTflbIg<&{B*KUj2{Dz6uY_}uPym`34`id4pmm-w8s6hS zWM3{BO-gHtF0cq-DB%_cM!*0!u@#2`32>U=7Y!EJT4aPwH~xRc8fHMw$i?D^GFx!* z{dt#T!Eq*1h91a?b+rcxIi5kmqp1WqVktC18FkWjDCL$KOJRQT?8RbWg-*Fix4|+A zjU19Z2|Phcf=qHLfi*6(+=4d{aaqWnpo88ct%P1tG4zUWrqQTlIt>agl30+T(?F}Y zsgVX!a$YSin@skeCw%7NKc`qHSL~!!S_ePv)N$aS_i3G+KVm$JT$GZ@J5Vbk{e6vr zP?^UJHj8yfcbC-nG zhU7QB>@+FjPf*~I7kHD#CJmo>qt2?*R#^)B*i?Gj89*(B9D&RH94vYCR>V;vF!>pl z1M%s*P)z$`9E!Be;$YH8iO67|D0vhd2SFMYB9&#{1coM#Ms`~x1lct_ZZZXJ_sKPr zgzZjDlC!FSQp)Gd*Wt(LLTg1J0L3Xq^(?3cjQc~jpWglQd+KH&&QP?DLjr9sDMc1h zp%6|NDzt3^SAv|r{?!no@tJ3koXuixC0jtsKzLF~x{=S8*6W}XBRNMW;(t;yBHB_4nx_FY3^Tuu&e8R2;$H)7{>}hR^%(=xA_z&2U&Gcw_yau8N z4ACVCp=&OY5N~cs1*$f$9sg9WwfDMWpcE(bcLWFLmR^#4W)fJ1PU?7YT@5ra%Y>qg z&udx2wM+rU%>*IGPOLA$vQe9)*B(u?qeJ;rBas+<(%`xEBu&k~80$#@P&Yhn&q6(b zEDGq5@w`Z)v+BZl?55HR} zGxE)(qeCvm4^p{_j3cc<%0^z&(XeYGFM~>ps3Qn(JS^S-ZF1rNBCNhg9LN~9WTzn1UR+}*Kq?$$=4 zp{=Z&nc!FH4XXMXe%tL0`OU=MlrM!Uo0#@#gQKMCF-|*CDoTdgSYO&P>P`XS_OS(R zZ_`Ceoe$g7upe*t3aThB`<;~W0QxAj8R!&S4`O@cxvAYun(bkxpkif2ija>GOFy2i z*D_AHlnG9|6)k|oD9wO$+1Y+Aw7$kr6*~%2>nNnXG9HDqJU^iDz}f^>>H-E?@v|Gu z@|@>k8Ig!h?HwkQj93y>4oE!oK@3yO-pe67-Qm5+lRuX7L34$oDIuRUPA23Jbl|Kl z);a9_%ANAS)-kbK)HpPRZf6wNLsK;=_I0Gv-k_aQvYHS1E#R6#Yz}^v*jKp#^_tbu z(seXwtU6}6!K~PP5-GrH;j~bwr=ODwbfNKs)a-9cKa*TYu-u7NptA)4HNJ0HnnHqt z$=r0>iiFAs?L)SdphmHqoKbq-62E64rYq*K!lA|5t}4`;=Mwc{Gj61Jn&&fQvv0#Q zU3BA(?t`ScuUSb-2|C>$#Hog@g)1JV?8l7vUDQlFcs!QpL@MW5S9~EyUwQU7RZUdL zIMzRd;XVajj^v{htIyfLKXTuew#wZ3;$(isdxSb({wkfO5SF%qM~?A7Hi z{;p)o6kbu7UZx&sT3eRB+PzChOTtkT4ru`RtKO&>Z*Yc#yx+E@-+j}?RW1UxJ>m{iT+dO)`f@nL@JQJ2=(=64gZs7Yl_ zO&(ESL*9EUZM$gRqgiZK-0b;#nl$l4vdD5&l95_q8f)*prct=2m7NRmNV^7#X_Y6* zEG{LIQR2N1-RNu6rm0z6Qr{32`YqTf3zPO*4YiGbbyFHpW>jQJNLtUD0Vpt+e#X3^4y19=ZwlxfHXmJ}p z9F(}5c5HYP_HHAKgg}>CF*NPC=GwUdP!^R}SnS{^)!|{Qj}#e*_leVQrpBAN+%P$+ zW{Cs|Z%P3L1x@nQPw!b!+6GL|M)9!V(?fs2pJk9e{14dKj9pTSA6A4H8mLb%nAf~v z?h+ibqN=x$n&6ILv6Ft&(XWC;Jd$N5{n+n(sfbTUbryXNI6UYvpEzO^=6GoHhH*=s z$xcLJR7a6i+G*%bwHznfLcQj+0u5X@74T_)TuKdNH_WJbQ=VoXbJP7Jm11jSCNe+U zGMQ!ju9lf&%QsLd9EOSJb4MJ)!Co50pB`plR4^+9`(Tuo>AsSNPQ02k(-tc_qPER8 zxSy$;!gzSJBFFBw;cw8Qd{6d+r^?cuo>+Fjg)Y?=hGUk$FCn6n>I|NCn-NP%+IQ?y zB04$mLo@AQ8tF+LlU#^j1w~$g*sQITQU~G*db%w*)SIh>(&Dx6l%iAqMtY{3alExX z30}^(@v0oR?We8SSym{oX-AO9DHb8Ofr&YuAn1vA-=|q1yJ?j%q}1LmNy+a>NXM2yWm#2 zs$aV)#X#vSOTX6*H7GU~Cwj!T7jO&$9KuY$d znp&wY)EmE!9Ol@3VEX_nr7W56KGun+EK{8z7G!me$Xkcli6sqqu#&J^ zxNw&t8}-c6%&X$?!7r}l_i4bOaikrpAuiI(sq&_|`SHTdVR?{bK8+!W*M2KUxT;rd zKY4>Qe4kIn=u?8Jr&d2Jq^ufn2s&cv?L3k86;xX=avYkL2)iCO(vG?Mn+OvtA<8`> zPUu{_u%OweBq=o*^Y8+cy|}?H$n40H;D2}x$KH~Q8g)XV*OI#5%uaNPOcjDeW5BTN)Nu&Qhb_ z^wzHG^2iFTW05u&IZAk+7^7M3%ETyV7%n`V;O=u&uY4URr1)4BjP}V~+hvhh@g~%` zyPxcp)lN|gFaO$`y&4WDsJ^M%z&XVPOGi0>HMvgM5Tr4-Krf4qEi?QXMM3_wd%LV`?_GaR=dP>5j_zdNa+H_l-dP+s z*v%Le#CyLhT+iHkHHH_U29D_-u{L~Z%7eMXt2ev3A)ocuI21xA_s5@ENh?`_A50Jz zAK{%vY@Le;K#qmo+f41n!psiWtMQewb#&UDIVxPaiizm?I5DvZ0@bcy-*;9Rw#foj zkL4qd$vG{$Ef?OTTc_0d-9Xh~o>V*or-8sJEwKzgskemFCWYING}p`q3YTD$zAmzO ztW1zOm_>!{cKy8lk)mG5AZ;IV7-;_h?g7u~ZipWrD6GN}`pA)Uy^aGbe2?XQuo~Qy zqkouOG8_Bbv3i7^jYl{wAK&B)>NWF$i!g|kb2(l}6A@8YY3qbuoXS%_7@NpQ#a>H= z>uSO=0*(kw{ZTaK8WFo4*$q`pt(MFXG|{f2hKOl9Xpx>Tn(w)ChPLBxfruE5EC=h& zIo!-obmi^Z;Z9~wveu!I1X_s7IsjS#=&z|gSIW3({~~2h6fy^wiX45J0E4(zgNOXE5}v`434GR$!>s(8 zRyT@n1ZV6@;tkto&Kr@;dUHIIp;&OllVyL9mj%;+8HO;#IZRq$$8)acEKc4slIfU1A)`jVOy?)Hkg~EOkQo1kd)SN$li$z|axR7xvUtS53VD|iKq?UU zqun0^0^H?_I0S{Ijgv4A$48@%3=-B1=U`g2-hR^v;nn(e9M13mSyWD=TFx~Iewm1K z0f)8JEP5Gl3YMm{Nkmi_A~Fyo23DQRBPx11(C6z2q^&*Pu$X028iS!BDrBOBwF&S!smSVGy{TULO6gc`04=|I@nekS?=tJb3Ns8X zn+>Z*<2v3q%h^yM$QbeCZAw`AontgT;n;A+RHQDBm)c8}b(-l=O_ZWoSszZ)Xq6O; zLlhZscb2@~nB%Kd2icOuIRB;<(AKu}vgdJW(LZbo4 zkXwGBjkdz*EC>;4Bqll(@YmeEKhs)qztxs`Nboh;pXg`EYL>8@Q%9#NI`3Qp(3i_rjFl|za`|F7!R8BC*KoXo| zY$`D*DRIQB;ynAz>jdF8-LcpYrbGQ(Y{8`&1_RBseR+J870k(!Z-wd+J@5r+p2ALW z#-xe^&I)^Pi6JpW{BqI6tI#vFlBFK~+ruo>7AfP?Yr(PL3Mmpws{xFOG-Je~*n3+kbLm(FTRsH3EB$- zig7-8Zz6f9rtlTmXUwa~ynp~fz+wF75x`FZ7CGCj+1+~Y5eW|SX&Q;Q>7Y5TXsbQPo`Kskbp#O{Q5<*mCI|F99%k<*0QGORQ?Els-U^E zDzumROuYUSbYBEWIRl#UY4T9Pj1-VMXUHRy}n7xnRDC+yg#Z`896EBh6;@W*xyf|glu5t58ACr>5X1{SJ5)_JYpp^i;YAz-H=txHsV|HpFwN8PwiDsaH4*zk5 zj&-W=f;=zr4<>~Fn=2+dMGJAt54}`t|0JFX2_2x_=EdJ-9;z&`SG67|7bts!D8*v(-YP2=jFe(q0pXftEm!sHOTxA%sAuKDW;E zVZW88>L%UMKrQE_YH3JeZd+VfkesCFCUZf0A~6@F8`Vs41ISWsb${9Dq zAQ1Q!h!3?D=^&NniE5dWP?JYRGI*S2GLbGy^smQ=EJwsKQeN+fKW-~iSCt5kP7I}> z7fC}%EeP*|Ld2o#D3BRDR=9(}Kkbxp1bDy-s8Uu>V*!c8NfZ|T7+C0>hrA9y^gCvt!CoND*g73kqXnLfnqVb= z#P*9<0ym6j8F-fwITma3@08WBA8hO*;I0Z<2EXV%WFD9KB1ff5X&gyZ52Tn_`5*K8k2_xx>mAN7d zZQ!B;3OPY-UL>zW7WpIeqUa|7q%uIfLEWkqqA3&*PEopL>jgemaZQ%F3dbSAz#G5_ z5JEagLrWIZilm&`_?ca(9g8 zCzg~M8$vl|6Nu+4&stWmOtCIz#{l{Pb zi<|;gk!kEg|BggyhV1v6SN;BY4l@~E@7ztE&cssj^EJ`cV4=RdrBJ2c}j5i}@` zjtQaujZM5y(`&i?F+HimH$)4SPHFm&zhFTWu2IidGwaLujA+Q{ljCuhu4jEgMo^FE zDGAEy8TE1uxblf7PdAt`;Zgd~a&4@s#9jy3ejBEE{A-v}=%P`Ng|b-sYUQzs)jSdL>mj19RN6PP3zElPPSuQWj8HBIDwUR4p94`2CjZZ ziq6G7QcYcZHr1b{#sGeLkB3U3IBPQ=>`1)7ciN$R237LaYF?mbsQW3^5yW}pI62Xf zCL0*3xRe0WcHSjLqrd+~&W2!x!i9UVSpN6yTj%l8{yt|O zwIxXTMR=9`4$11uU8GRlDX$a6i&utg6A_wPM5VaMg|gfDl>U$fnD)ebhBb7p@B^^5C1!*Y4ZdLp26%FO!MA4KN3pLhn(lb=- zPP;S0GSuweM&O#{)a1FSiDC{}e#;%8b~OAR8-bg3TB8W3&@fXLvx|tIPftS^C4+E>fA&se=jmVx(oH_G)PS`z{}pZjmMJ5=E^;@Qa6hf}AdfMwFGeqnu40mVO2D z^F&do>f3x6^0-SHC(J;s<}yUjFe&0EWVAK=rjSC#;RTl_&L|C;sbeQiIEMKx-%5-P zyA4OG)GIiK{U2i|OwO@!M~zD;Qi2g1FFT@4YppmkjBU?lEShv&%`c@|TskCgY%0() z`ZsYV>GMR<@OVA3Khzf<)h{adxthaz^@3?5kxi45_K)fVfB*OY{^uWm{o^11(|>&X zGK<{xJ`sPT6p~@U!@Sz)! zO#9FWVxG)nq*y+PQ-<(DpIIgxnXJ>QQ-t#|zSm=@_p&olC zSD(t54@-1_t>~#KoVX-q@9FMbuQ{C0zc0HRD=jB*I=vg{dBV})y{1W=zhAqN=V`@E z-cGN}xB)@B36|t7bo8f)A*CX*do&I@);{^p^ElEix~5Y?M}G(xatzOvvG2h!UDD=7 zF?RCDU?E2_j5%DaK!T=(yw>B?|GjL})z81esIlKah7T!sU_$ZP9@uMTHokjcqRrsBw~4}sC(2C@h&#i z5s8Zil+S8Js47fUSUy}3uXUcRVav0Ut88%biI=K)kAk-=scsxnb2EM%!gi` zCOw(f78Zvno=j@rgCe~*3sm%xKwBC%7btQRZD2y5>5Tye6SYgpYahXF-8nw;s{oA4lQ!kZWk7e(C8TWZI!ec8= z%!5pqYyDA0J|p9U7NQ$6W{d`&Pw4{Y*=C9qBbPDVnuUH(rjtv^=hL~u@nj!NisMQb z%=5fS7g45Sw)#WO1+fEx1uk6dVbg)O=!gvqE0!S#pMBSm1?wEx{i|*@Sf+e}WxB)} z{f~Z|PFmW(R--(%C1&2`2EG0ztPSYEGpGI-9*TDd<&%XET}CVwFpJpq(2gkGp7kow z+H({vEX~#_1&E3Nks(CC-OMH6^pE&r@cPig?$}d+% zu(PT2v0*rawrPd~91~SxDP?A-uHccniL7N=uCW%Jr6r75e1AEl=4!2eY53_~Gh%GD z$WpWV=XDgW5{y+aG_x^^RQ|w9-#XPodkIjoO^{jHT}cm9Vf69aU)7ZJH~D?7xM_dN z;IkHnGA+IRSXp=a+E8Dn{QCk`Yoka-mz1{MyqxiD5rN?+s95I!_7vTy~#dt z$(RLl^&8p=#8vjY-3JvgRXsEwlN{g8ot=Yq+a@8#pbYxb`%EFbusW@`ISK|Z;>c= z+$B!MpdMyAv8a+cS!oQ3#;h#Jj60pKtA{`CcQK~6~r<;mxx zw~8jGHf+?zo0M=$s#A}$h)$Xa9%v;AU>t`YYvno>MO1W{_-027%U;;7K}zuqI;S3G z5uJ2LO(aJ%Ak2$tQ;p`6Srhqr%xvXJ9Bqmi%`dWwOEwx2k!FH}lowjWjYTcTQB*`J2S>HD zj#THcnH>>Fs`8OVY}8_SJZa=8RSaw3nRz%8ho~xSw)1q4s4k3Rzl%{U?~=q-bg~)E zfH)42>YB}PWSquFXwBzh0&9F&@l%w7)B4Mq73_T0Smk^m2DC^A@h@gU6Kiwdb&Y}} zyET-cdtH`V33#(b19>RF)xDXr9rFu4sFP6U1DH}o$9!OoF6_2RgvO(y{ng8u@JlWk zrw`nYiRQ771;%;Z7m4!!3o0y5TyWhwCahj$wvZrB3#>{GoYf^nRt%M}*F`IjcFimX z3vpq1i~dwajT}05rUr+ zh@E(vMZ}hTw?iUn2Ok-KGC;CNsZww(TkLS~9E->-Ico+P%P$oawwf|2!svik~*x1t`a|Vxlyygw1>>uZz~nKW04hU^TMa*~N@J@+^$0ll z(3Sk>6|_#*Rb@AJ_nCsp=$y=;WXOy(3S6W`j>|`zOr$o{p4h%v>J6-FV=JXjjk3pt zI`m!a+pxL zfhZiFJ0^;cuu15es!ctn%;1u%cC|JWiA69c9MbW*Y^{zYtM~2FRamx2q zu5?L&-KZ=H;uJ)UhKx2RHb9Tq5Q6I>yrxbp(V0x#UcN%Dn5E0?H9vCe1QlDDCRB$BXCG2JM z>yPflaR0(^WHASPXw@L=vV9_SBMD~&J76rO6L1CGj$lAT-i9hVp)Lmkv}wLDq5Tg2 zY}*C=Gz~dplPLQ~G*qd*X^;*ZH;l=t*6ko2$1_AMNE&YVpu=LD^DKI$Q4!f+p7bYq zmJMBvg!HmF04Fi3D-K3s?By3RJiURa3ZBb;Jv%J3 zaAhE*RtBRh4du%RmG2O4-aq$4{Cb%%lp86Bjk-yv61dTzc@T3pj>`q+|j zT^JeENaC@9hC5)C(Az6_xF`hD0XpDUWN{#&&NiV4Af|kYLaTDLo`fz+`IYiUC!n#S z>)MnmNs`m_1XOzz3iyj>;eb?Qt_~Wfz&_8&;l~$2DmxxNsa%tJu6mQjc$ge2_56J6 zX4ct))-&}g>%T6A6q6GSJq0^xTIKyVfd*vNz;)pXv?)wWGg;wuG-`b(ElT_551U++ z%5Doahe&9BxRc|lna%e!WMMD+SeYr(Jx7i{iMFmsC_?G42PW^K^NQ|EecF zMvLg&Q;z4b1(Mu1En7<0m9IcLj?&Odqjk0<|0|ykWK{IHlp5k+l-YbwMxAW?(8huv zIIZP!3~0I%OlLI$YA}qbNHPew6e-qG0~DSfifa^909B{q5x?yLonc(} zYk)Sv&k@l;h6tlM3xC0}Iw(Z6sCynE3B4eGaBK;U!t@LGqPDL`%`vytQNEAH{Wp3CZ%k3a6442N!OM$ndFalBT zE~8RsQM^DxuB#ris3+kLm`;guimL#I0+hj~n~;4p^}d+VG_ys7kKs$05t9Ma*H^-6 zL$lJGh;xt8Z+vUMQ*7dLYMLuA*{roEA)0`$c3=Z3bW6do!=^jNC)}F1_g864?G)#g zxE@tMgSjtj&o$@8DbE&iSY^6SLEU6rp=%iCDtO5hgn;7+U+J9j*v*y@XW<(zR0|ll4_`mpD|PuMj%va0;Lohv!B2)H z7U+i}*%TdJqcn&}$rKN~tHcxWJvMN&38>w-Dr`nWbBwSd_?!R|z$Dl?@)@vxaI#QN z1wE`9(!?PGw7%v?1Nu2L$bms>*0_pzKr}evFqY4B<4^j6UP1lvc>(0~Vq)l>0OF4A z&IaK{Q+^$^=9g@sRUa#GNR3|xlH?#8j=P&gQ_bddTN+-HLY&+LM^DD?Gom)R2UcNI zL=06iV=@$VDTlFPvn`YlOXHk~L>C?xpv!m2n{Tc-Cr39Ny&!7vbSkRdbi`lxIINi^vSy)3mpyHA!=3BTN6%BCo-Z7n6*%ZGBpOiDXgbH}wsYcaWUHpCiE}k2r zQh5@l*b-Ez+{z%&6Oj~dV)C6NQl;n#F+qlvKX*<&9Z;W*sxM zS>ERblB80CqNAgM4Yf#!SLsN$fV4c4g_}cqHzgw(fvpx(Y993~WC~i2%;!QaV9JSGIa-RmpcsbgjZg^X_IjtcSB6CTiGYK@@R9 zP5pk06K#$DlfRNDzfG0Ad2LJg^I8=-Sn+QRY^vZlUD!cWi9RHu z@0p=|*bDfi(pxcP=ox6L_IX+4*%BnZEOzMRK~os3oN6oe9KtvjM)9^mlX(0WioJ5Y z>x|g2d{!LkpU>LyyEqQeVX^VTnu%PaX8Dq@KSjh4rBj42W+3c{9a}!L)gJI_K(;}HB6TV#0P;8qx0s}cacq-?& zpy-5lHKJM2>?Wj?^Ea;8^{YAvqCDI+YT~4w)v*I~7&zLSDh;rcrf@%Mpoo~=7oe=K zWSPFsSi@#1dmF*C-VP~?%oP|Y* zw8NvfHoyT}Yf~frYwGvy@KD!`0U?chPH}&8QH^h?Zi0s6^OU4?f6T3(k_I>xI9kkZ z;-kkwNcUXJW7%j1SFi<>JqS@pK|sl6r-vd+)>-7$t3trNxKGbvQx{_a|1kb281@pn zs{2zU+1m+5)w-NqmF`abfq{%2HbVJ!Z0|%uV4$H*D^U2E5&~){XsPMZ=UERVb+#x$ zav-ED?-M!}tz&EWDEPV7sA<(cEFnsofxKiS$?hjedQ$o#zqY9h;-Qd#!s9W?Wc>AQ z;-$ZpDj{12t1IbijW{w-i6`KN(g26`AoJMxbu8t3%~L4pH*eY0I}^6ebAnK|v*0dL zasoKPav-Iz^*2hodj8bl5Lii5K_STAM0xhnG5 zD`2M7Z)#U`7c|%W=@5i!XoBNFL|g4wdqfe(v7+x8H6UUyuBzNW*7($2u-C_*_H^E9 zNM9jihpm+Rn=tm;_NfALd6r&@rr_U_L`o-{4ukT3qlsKjwbB@p^%{9H&L#f>uo?mO zvOXbrPRIT%YU-%m(0@jcL4CfbvpdAPnGfJ~s_(&Qy($A~2mFdc9pVl{F4g>7iz-b% zTPp{t`OQsoaiY~v|U>s4aE1j~Vvz5}3jU%D#4Qo#Ww zdtX4ove(&3c~H_RB59sWT?aO?^GxyMheLab3oy{KLub1adof+^&wykomEEJE37}>B ztnkJV(l)Co`tX`V{G2d!lNJRwQqCVs#mkggY? z>4hOvefUN6K}Pr1F=bIM5M0;QIgs?~r*Ncr_wpPd(EH z&vQ-g$I`Uw|EpY+{GIrp|i*M-&mqMSWH;Z}n**TLHH+=x+si=Qc{&h6G zl+R%ZK0$FHqi+Mi6%-jwJzcean#58^$J95dmT%3*{jJn`VC>^lZjQ!Gj@|Nsj=lCm zBfwVR_C+n)`aO=3pW|Br7>gVpOXVKgPs&f9c3ByJPOuzF*+=$i2iVfRy@0A3<;1U% zO!hLZ?&#I}m2W{HL)m50)FRgt=IZNPqvhVLKu17J&6#Sr>dk7b3y3*LrQ0I#+GyEd zOHBy-Q10`@)H10j=;&rVz5-155{?E zjJze@z$lpmHHD9%0ZlFJco?vZRBR_E4FR;6`PULtyljPmr)kNGx&+CAmaZQFmKAVa z`%n}ZXIN-Gnra_rTLsMk6~q2glI`2{E3*iRFECPZuWeWTDg=G4zb?uxo|tJcA0^T@ z0yG)!@1)j)HhlHGouo{ipg7XdwgI4+g`%-;j4DoB4vIAT#E!9&r3=76RPU>M)@9|5 z(?O(xhNG_oXx2rckRFNQke)NH4k&!oU+K@(dn2EvAP6eXUD2qhjXu9$Ryo@dd5!N6 z2uAeluSDse;^H*0e0zG;6eU^s=tl)7@mu$H$?yaiAXKBBZ{`kpllF`Ea5u&^lHcKIgrl}0TBC( zel}#Md*YM`_TZnYKdBOZ$9EZQYbvZITqhxI`3Z)egtp#aX7&Nh2GCp|x%*+oI?A7a*g%g6lmOmgEc{0AtUlfdaC1vuqw8oRR)TF7 zcSwYaA}T&Zzh0P9VZUMM##gBsR}Qrzcp+Z{hBS~bNueq2 zqeN>*ye$n>(R_1r9?Q;>Y@~G=2Xq#G%FkkAv;i=NGqk)LMUQKDAN-;z< z1zwfz&rs3V^^2kC?^HSoS_Yq^Y03XnT*L=MA~$Jr>&~5hjMKMEuT1$aNQ%-g_>goJqe9vsO?jNtn0=yu+NW- zf(YChqkXC8*BzT(`IHWVsJZx(F2$2i5cKBI5AA={ZIi~lsbHVYH!4^#4@EV<92A7t z-3Eb{Lw%lx>A2BA!|tESR@dBXw?ua_}+oLl&J#yV=f(t=u7!E zS!fF4D%KAe2KLbSv0A%Qt%YkHXk)8}+b^0!mV6`@e;{F>if?VjJpNFr9}tW*sSQNx z`hfD8eX)U>leg;6(-x6pPlBT-;!w%218}Aqu3G(oW1ve-n4~g(`Hi7-z{nwtw*6Um zOc_{COui@L5P%npPY=Yl?~i%?5x+o}x@^ENZuja*%qyv9;4U##zI;Ut{kVSJ!#I@a za{`)Is;dJEi<*7`Hmuwf8EU=UF@6I9`!IYPw-IbTTc+y#fM7&HlaC|7toc#%Ov>U1 z6kLxCx!RPVHwa)KgRc`)!mj5!Rhl2L3*^rv3Mt#Grme5=45m*Y7QofAA;Zw=ERm<5 z$Pw}Rn5u0~T*V3iD2w{r8#^Fz=)i z)@?p%eqhcEqA7k#8K|41P;oDlsv>`aiv6Xu@V~ak4f_H%Yd?^2T^89Un^^mSjJ^7- z!mOslD~`5MJ>VD#qj{^kF~Gl++5>KCbHkm{3AvNeAz%!ZdKOUSC5e^JU^E|`rRW9{X1#nzqU2ZM7$~0 z#;K76!!C*f&4>_r2KMWF$SA^(+Ge1jKGL5Fai%@He8lww(611Za9s{DJ&DoxBy<(} zmWDDNP7LFR>C#@b_phXaA^E2AO0FMZrr)|l!)}HIH&47?bJlA8TADXHelNav#u}UMB1?+*xf#PGq+hns^zEM z8FV&#@5Lliv`D|{y&W(W-UsxG=y~F~nSX)@{f2J=uw947cUj$}32UZ9 zL5_Mh6~=Nw@{NVD@U{1~{bRHn$ewv5@^WNw>Q`Js?I!YZ^=HL%G09Br!m3YiQlgrz zPwD4N@;V|R`neu}2R*>cz9+s_X52mfumWa#e$kUAr_Hv0iZ26#5dmFpT>ESbhwhW> zXuPIgp3R49AL)wsVhRe>=YufW$|@D=}UIHt!Qr4X@h)+wJRX5CZI)!%sUQ5ZV>*1B#`2SjTW9}0Dyg!)QvbK(Ewl58QCs{*2gMh-2* z+RN?O80yO=;*FrKs`qXqUbqjxnXf|}Pn(IZL<@#riwCZtVQMBki&{6Pbjd;zD>p8%z)rJ2|1XV=oyb-cOW(5Q52^2|Cu$43^Y}VT?ToP#LHGg)AzhK z?;?|O5M(Kg=(BwkTVHBs*OnuwlWfzAM?_o+1)rrNgPvLC)=|;+y|X8wQqg2lzT5G} zF~(6@q#6qm(TxX8sS5TY(yeljqQU#f+Os@=)Qlw-#m!M+EtUihoaqY$)L zWvvrV{G7onyB6Urn|`8WE=14iPYsNqd&mqhQ$~|=<Ha>rzfaz9M zhoN&>_RgNYCx`bsK|i@Hphc4t#p9{>g=5aNQ_TcqYtXV6^YNyrn$}jT2s$t!5@PrJ6*$_mLn(AhW~IAzz;RuTDk588Q`Mp>9y+Jw0(uuV_Lj@mH?eBD7j;q?3vjN%IGPurD|jmk9iwS7 zF@*MQgo{>X?AIGdk9n*)J9E*aL2aB?IR#4>gX=U`VOSIMGY*t7Z26GO34GRl7h~9e z6Di62o%U-4+mNfRDVm=2WK4oxsEJUP?{o#Nq(I#Z5RYL!EtL3Qr+u3O8)mIv^$o@Z zX%de2_jKi2zSDarl@@^ZVu&&H*WWaY#;&C?K6Kahtl}xK?G-P@;xz`g4i0x2PSMeM zO0I!&UxYoCE3Tr5a$7-B-sOHKo#~&-tHwvgD>H*BJxVlAs-DXDx>`a~#CnMRV<&Fi z2VjfvlFI3Q10@)*^T#I4pc^*x0t$vcGjOyV;Avs}T0A;3^tQ|!EFg2JZ@etpc$4Hn zZO3%+|6PGF^IS{Xrng;{fV?)+x$r+^QVxplv9M@3BnJw!`}jYoTU@k^-y{ZCB+d@pRP+H73w8rqg)viJnT8=rW!7)RJ~6E@Xtd& z^?sZYUgZdi$*^ev%=NaoY7oT>IHuh}-61b5=3?_&B{Is9M1blc<^8=A_vLXkEhevY z>DPf5p9??@-b2TH*YAL%56_DjIU9#>aK`pqTZ;EvjK+`;*j9WGbX*TQs9-ER4K8qq;W80*vu#P?C?4o1f2Uo)dExyITb5dZ!l5E^Mv$A7zP2>0oy=etc0-VefPTkWTUP702*zrkD_L?* za-DCe6&!P!zCdSl1CMg711(+GKubM4ziDe5usB}Quq2L_bdL|!A0Jl>XgMk$mpgc` zYS}oz$_{LSj79SrDbukTFO|MnzfoYHD=7Ja2Q?3GElmWX^g;C@Y$$`(y^Uet(<3

D`*#Utz=+b3nRn1am>=m zv$(RQ|Nb35a34*(SUQn`v8CsD=`YVV(=O&(`pfgr1t(%+h&=6Lt|gwx6kK~|=G%GZ ztZX^|kShPJ!%Y@w;rzgu@eT9t`Bg^yMsIh^Cam{A&fm^6B)e$6hn=UbbX~?jWN71W zFtS_&qXS(qy0HOc)7tCQZt{ubO^-8rOusYw?VmF??QhQ5G#k#?G#e%KVAE_k7yVLu zT_m4GdXh+g64^~6f0D@0B=XP7HQ5?{dA%o2*ZrJs9Y|`hTXGjvoKZ){E z7w4;gm!&KFuX>W_Zl8Qf=O1r*rQ!Qg9h@)h(|YT}Ef?ZvI7v{Gi^CXZ(X{ z<8LssTmz#6T`;L)JGWm^by8BeT1=3A7Sic55_)ygt1Q_VeHdKSh<6X+%>2j8*j=;t3y8-Ih5#RiNHY{2-B4Y=r++R2^dJywMtk0DH-BD>^H{&+5sAvV~685f7O zYk5`Bv$W?_?NJ=aT|zst#0E?(`3KX+-(Y010iy#OFtLpDW&f@F68+En+p7TM&l|OZI9zN&(*>|HBcJ8^%_1S%owQxSE%Zr))^Z$0RwN>nI&L&&2 zYn)9-#dOsbx-0xY|1~c5l@})hG+uid|vwzOkmf7E& zO}1j!IGc`&>8eBCbbBme8!xmss2v+H^4NgUgAEw{{DW!ZZ!of41ET{QFuJh;6N{+5 zE|O0oJxQcLiR>nkKc&deQslqqF8H%7?dmV`3GHUH6vd|$#SObIL!0?i3VOyQTmz#c z%8So~6@HoEwf~9q5A5&6)yZ)7l%< zZt|JrO^-8r{_*}8=PT!VJb8JyyPeOz^0p*D=XvLYHa{=9=9>?k2k!EZ^DcY&+VgJ=J<^cvujVNV@y6*8JN9v zMSTM@Pe1udL)-axa+!D9TxHkZGzpm#_B$!t_03ydX3zrnG_1MdJ#~!XH=fAt+QtTC zo__L>?Dl`W<1!uBI;Nr5jV&6GDKCDXUAtz6%%BA}%5Gh_MTV{M-`+Us?PHe8km=TT&DfLb+Jrcuxo2$BZ=~8^0l#47ma}=8Z$HP;iJ9%U-w*gf5d&*AMKti-up#+!oT+F zwl`)U{YT!blRNIqSQEK75p&N1b3eho3Cz6=_c$ipbJJf z_F!ys|Dbm6DNBwva3glo~$v{y8{zQ+qX=cvikUR;a+Gs#3g ztKDTJ&wjP=p%PtdGBvxI_O#}6<$uZ7;ugz9{l!)-h9^$k&*h0>hh%T(O@?>QzJGNW z=R23XJbQHdX3i&0oR+Qh{hH2|>)TiCpR=`9>~Dwf~9q5A5jSaZym)es^K8f@sk$$(qwbte~U}6yY={9I5 zW}JJ##4_qH^4@o|i5_S4L~(N)TuU2&3woyEr!zXRK|8wRd|6IQT~``j+(Vt{yvm;I z+W!2X&exB*-S+K!IWvxy`(!icO+Q+(V*i}2jWOnIvK6}~L8s}cm@enV@)JFGw3|)Z zGnjU4NFEz7dawbbpMNlI{0&AH8!$T11*01qFu9A`lStm~4QqPb2J-YNvg4VZRpz{q0*Mh`Y%^z#pqqyKBtP#ul_n$wD@r5_eVQd{A+%N@%(3*Uva)*>L+tA zX67U9)EVY!QDgsF<18kslf;DB5F?nFu|I){CACcL)Humg`(X4?6Jga!SalLsorF~< zVRXm)lW5=a*M8FWZ-2!7q~+50#@tWM?mmKiv;X8CCzA0sTJ1Kr{5+X+;^@A^#z*s< z$>T$G-=zB&Tcexjw}Z(4neLC8?>v0g_in$(89q6UV&zPJe~;fFS}Z)M+T*B^<$+hM zk{-Ow;Oe-=MmfK@)sX6u`vhKp(8<-2I~MI@PpuC9D9FE9@D1(jQ|W=F2bLaKdc57P zow{pFw?+F6r_EWj`}IMA(KC3?AcOwxwwlXj#IYXfM~}Cg|LB3G2fpOMVb!-P!T-}w zKfU^1r@)7uc4l?Al`nSvSN1u(`p7#MI^X)qIn~$uT;TjrI-&_E={)a8b5;8e9pHS_ zoAXpZJYbOXxWigkr%yl8`G#ThSHC*xBvyc)o~-J=^+^}4e!1@I&J)M9tM2&Jn$C9)Ua0!q zw`)6p_UZi9D@Ly8yw;5Qs+W#ToZqapt}grPhR);HYF!=Qb5rNT_G(>ydO|Pfhqjon zdT-m_GjZ$#EFWO`0LuqhKEUz;mJhIefaL=m&&L@n4y%?Q3-d91=hW)bF9%kgp+<@0 zYhhgr>smOTn^&)QVYSs;VJyK@~gYvFi2h-r^&pcwt}{Ca1n*43A%?dE;#aQS@I9&P(Lf4Od(>SJwpbbfd7 zHq{g6sdt{;c#ux)N+&Fxuyn%G32Uy!jGy?-x(Xg+PbsVkh0bztLJ5{ zQ+91x>z5dvmKWCpOOLk~dSK~+xmN27?OJzi{VHocLQid-GX2Usw%}Ng^rHus9$0!{ z8xLjGUaOO3)nu!mWz}k{t7X-2tG8v)qGnc%32F-441V=h+|u@Y{9Yx%N8tK zux!Dy1*2bUAMIKbk=I&@9<8D1*V>9*t-1K4wV0S_jTXnY&oR($2nWAD^J?# zXlJW+(KibaO*0}P>r?z&sHLkqmDO)((8drW|rJl~V#+7e-VPj`ozX+B4VG`Pe1qj1EZ<=H z2Fo{CzQOVhmT$0pgH<=EMOKr`T7#@6m$f!&Od=zWuZ49jtZU(TyoqU#YnK@PalWkf zmS=3$*JEq7w|wEUdpKL|Eibt2Kb)=hmUmlqKj+zvH|fN#bi&dJOD8OyaGWnOeyV;V zBUXG=--v_OMB<~hQuPygF?xtC*TT9M*0r$e8`s(zUDlcoYpsuKlsLW?*0o};h4*W{ zO7(yxr+GZ5oxeu4=ZEh&@AvcC)$V-)zqrEs)xih8?d|h?mQ){K{;iof)&onAw-47i2=Hq^(jdwTF;!O}d{ zk^2YVMh}{=`rapjN4~OPtuNx(7A#w^Y{9Yx%N8tKux!EejykcrL&qE4&$`yfS8v?m zdgq>>9b0|#;cJ~|?0Ix`=aa5+?s3$S)k{vhdM1wbz|sRt4=g?KnvH|2Z4Yg5J*Pf= zQgz7T6P=GcU`X|-?e22UZy8cOu=AbH2ag<5J>rAgoI9^LqZDQt33;F^El`A z(!te14~D*oV_UFn!LkL*7A#w^Y{9YxKmXOd)yw(}ce@u~-m?1ft>M0Mjna(#nEeAE zx60Rf?-K&=vgOD5{ zw(gV1@|LSz%L7m<@tBV-w^tE z%BA^_r{3gz(D|3-)33PM`H?R!$?vV)>iqeYm*rbdx!w7|^RLLSc{q#{aqI&uA7J?a z%LiCKz$+C#!14i>53qcIfGH_gfzHiv6x@N2Ay)Uo!JEZ#azK=M^b3`0p z3+q}~*TV6smM-|Ff$Jl0iNm4-594 zl<#)+81LiwQPup>PFFg&o^)^i9M+9 z)*4~;ysWju>U>#iiq-#AYmKc7sn#G{FH)^d*2h$9mN>Qr%N8tKux!Dy1$wc^+=EW5DmIu~|f*@a~nmR(qO;RWBjDDAvd zs6_)`I6wVt-cY07Tm8KBgO|hns(yWLI^(Lao}ReY`RU$AhV``a+=Xe^okBg_Z0e}= znO#Gj%oeyJ{dPo{3#vdV{ zzOCbB?FVdqFKeG*wW6&3gE-a$OAjnPu=K!If67|BZJjM^O}F*8thL_O<+AnwwqBRD zH?VcQtUZIR?`7>JtY((A#}LQ1VA+CY3zjWdwqV(UWebkyspdPiMI6h(@%YgkENYR@ z%~%GG=h2sM+?Sr;7|y`&xO03uZTO`#jT7|5V@B7aN7ur-7S`P1+IS3zV;MNkm#qtB zttqx%l(p7qJfKq?UkmG6Sl7bJ7uVXlR@Rzm>s?uEWn7cR@wKq7g>@}VUheLCeFgp0 z+p`wA#+f?2`PY{^Q=hxHKHC}nj|@CwCXV&M(&O!g9$0!{a{Z69ZpyGroxJp^cCM59 z`N>gRI8#@T-*kX8_4fKXhC5S-?|k_(XX^7E+XkN*d+Ligwgt-;EL*T_!LkL*7A#vZ zdEEbpdsF;p{?50^qt49hZatoIX1?$G_h+3MKU;QxaVC!Sz|sRt4=g<}H2i)q+e1GVsiO!7S$y?tu6UVk-*@9&Y zmMvJeVA+CY3%0#bdCcHNeV*E$yxiiM#hh(Vo_@6N;?A}wPrLsuumj`PdM9NJ#9Sr0cYE*rw{bXoo%n4e);yD&bC)iZ~5m<&bC)i&sgIsXWRRwoqJw7 z6URQl@&T3)uzY~!11uk4`2foYSU$kDeED;B0%{ z^nn+qJKJ72z2NWPInOTd(uscQgryUfPFOnOIEHae6UQ>J>JoJ$uD#+|29E13b$j$; z?MhrrJwNV>g}q;KO%TV|!nzjLwQyX=Sa%+67it>o(XcfpyZ+hL2VILET?^}4*!-_* zy|DUU)jGm?l-3tpFRHb5$Ih=*!!0Jxu^w1@VCjLS2evrZ^jO`lYK^dZUe(%Rb-t=K z#p-{qwZ_(kTx*c67rE9Z%W1APOB~yRWeb)qShirdunWsBEW5Dm!m+l6HpmR(qO zVcCUc7nWUEc44bsRju!~URSm5+d5v=e!$lEs`d#scdFVyh+{pl^uW>sOAl;wv#Pb* z*4e7obX$L`TI+3Hu4)fp>vdIo16#-Kd6KYau=TyFy@b_}s`eP-*cL2Xux!Dy1aV!JJb-?af^6?|)_L^Y#EP3bUf0}8WqetUEz82QCu&#wQ z_qjG6!{S&5UaiaMyzgFT`Wm$RhGX(CKiEF-w6Xb@Z?$pWYyPY9$-Rdq=-ly+F?p}0 zkDLU*`sV0-ffq;ko`2zSm*m&%+NwhPx7{wxdpyzI`SMZcoaxWvE2ewA9@}Ue(R)etgv?Y4U~Ga&2{0oQR>XSue|QpQh&C7^;Ku; z(pnQ=cBWo641Ceq=1cxuUHGkp`gZvo&w4w4zW3JCGci8PPgs7!@)MSyu>6GOCoDf< z`3cKUSboCt)4A{yrsl{`>XQ67`BeR)KB&Lc4aI?aqWDl}6gTRR;z?anoT*oeKXpub zp$;owj8ElJ9Q#@L?|wQLe!}t-mY=ZvgyknJKVkU^%THK-!txVlY%lk1_??$|xA=X5 znU9}-5SV#--XY-}p80#i7Pt6#U|v6ZOgO7&zW1Geo3~ScI^1wa7&BIvR=8;VOdQ*V zWfzuRSaxCAg=H6(U08Nu>agrmC*_aH=kn9^3h{h|gQ`%=g|^-Zk) z7V;hk^k^)>y0&1y)@>EzA?BhU`uz3wXfE$~*BqtZH?-amnR`dKDIK!Xd^0ifl7TPW zq#x)zpBShisE&3%CXo^7!lz7_56b0P12fz?M?eTNkjSiZ%K zpBCqg9Kjanj2yw1mkN20nQJ8j>snayu#J;SG)|mjJ@B$~bgQ&qt&R6fO#ANpFI!pT zwfWp`x0gCp<~%j9bRr|hmSkXE3!Bc8^jmugorQb}o$&0&v#u@t@oQnT<=4Wo&l}&c zdF8>C+PKgA*6&qWV1>YkeRE9Z<7EO%9=noE3bA)#v z9$w~w((&cRynW@}7fQE0Whv*UdvB0_acdXn_pjP5opj1-&S!2jAbsoJ^_<_BaBBK& zhfSO>S>x>Vm=(8iUU~Q7>Bl2?t+nsnre95d?oLNJqvzYhPH;wl+nw!MWQzlKznpxU zGyZJ8^I6XLxyBFYIOBh(k>Od{X^kIt8QkSuwO7<`@)gOOo?LoNe=hxIHQC{pF$y&a6@08q;N97Jy z?qKB(R_0?qKB(R_=;+&s`z!xr3EE zSh<6hJ6O4cl{;9ugOxkAlRL?iJ6O4cl{;9ugOxj2xr3EEIL_Ca(=Sdx9XmZ`Y~OU; zrD^$#z?Xe6I-UI5=ia{ca%0nN|Nf=(t!=JJO9y=I+-dlA=?x!!>)d+O4e9*P{op)m ziJQ{u0yCVKntNQj%iS$}{2#RAxb(uI;T!*bw>YA3%7R0 zZkrwEbH<-J`?PV!&n*_8-x>egoD-OS-EmjoJNLVw)_(stBWm*P?moMw=hkP>sOj&% z-Dx$uJM}uX=FdY9om}&C(^rPp{Qv6Ap|yU|uKpsgIG{)ILBHaLUBwfB6leTY{PACT ziSs2Ur^+3y+`-BntlYuM9jx5J${noS!OET5$(`iM9jx5J${noS!O9)1+`-BntlYuM z9jx5J${noS!O9)1+`-BntlYuMo!ZHrxRYOPjB9# zkB{3GuKFn5abVy@+I^NT`g!1ow)`U9?cz(SJt! z1HB!)-FG_38Gkm|^ z{wptWzQp8Ixr3EESh<6hJ6O4cl{;9ugOxj2xl=oRmpn0nl{;9ugOxj2xr3EESh<6h zJ6O4cl{;9ugOxj2xr3EESh<6hJ6O3>JGqlQxr3EESh<6hJ6O4cl{;9ugX4S|=bsC zAM?g{>z%ES`GVuNueJ9+V#k{N11s(9jGj&p?&6I8C+mv&Zgx)@80I_v3>+NhJAU53 z@$N2<|0hofOutrpJ+S4p)^543$=evH>9Mg<({E#@X4l42%^w?+x%{*-nah70leK=) zuKpsgIG{)ILBHaLUBwfB6leTY{PACTiSs2c^6N51-u+rwxr3EESh<6hJ6O4cl{;9u zQ#*Z^JTZZlJ6O4cu}kh?0?qKB(R_0?qKCk?c`4K z0?qKB(R_YhT`e!~ch=^N#zudjGg&?-`M-5Lt=D{XS$RA~GT) zA~W09${x3j+s@uMcgV^}xZlSrtEG&n%*^bFY`^PuUH9wryYIiAkMlV9`CRXFo%ea4 zbFOhd*KsS~#PH&K#`3KU_r(~?H#EF*)mXl*VTbP1wZ43F!>XBPD9g7vocq18eAC0d zvu0|!eAB~`|Fig3`KE^jn#_)r@2oIK8TAKepBrgs#aUytpLD@IEywSks5D<0@_ew< z7;+BEzd*|&f6Erec&=A_7|R+aQZ8$oNPSuJMB0(HP^5iXBSn5!)=nYiku_LEPFaJ6 zlwa0hk>^4=pBMGn4`_$|gZ9~P_+9oV8jrtZMh9hkZUQ+HtM4ouyFsXH)r2d3`8)E$_* z15JCiZu^hT%edrEM-GQk)Fm(r}?!eR?n7RWe*4L}+WFB66UB~UF!gs?%n~isW zb1U3<+c?|M8{yH0H?+>W=~u&szZqB0aycy7@1~YFNp&gw?A3pi_kDID-0;-6#=P@k z_djoG`Q19_!wlPQE2Dh%qJJaxI}N&{jCQ8izN?J(uP6IY8Na(f&KUC4c=?`|L(Yz4 zj3IxmZ;kO>d5#*dj(Qv^uh%$aWJmcBU2jV-#_A@O{=J~rRRwwtAr*792o^ob9 zo5EB6O=(hkJ{QXQyr|E9Ks)Row9kIS@3KE35BnK%vi~7J^^#a$WayN-15JCiZ zfvGz%bqA*Iz|x??$>o%PWtVCoJ`-GQk)Fm(r}?!eR?n7RW~cVOxcOx=O0J1}(z zrtZMh9hkZUQ+F(f?pPnX15JCiZfvGz%bqA*Iz=`#BY|B`GV&-l=1F3LyjDO{# z@!*G_`85akXnFk-l7FM&KIMD8M*Ctdzqd1!gVBE0=^vFB*NgTK_8(9ld}EYfne>qI z{Eeghyq>=)?_V^^=X~^gqHK*6kBL<-d4vV&u6{&gVsa_5<2s|7iOO{f6IVe?lJiGvs9dLw@QdvA)RADRl>? z?!eR?n7RXN----i>JCiZfvGz%b;oi%JL{uQz|x&u>pVCoJ`-GQk)Fm(r}?!eR? zn7RW~cVOxcOx=O0J1}(zrtVk{-LXD&2d3`8)E$_*15JCiZffMTsd@RXA{dVBl zS7tLtpTyKNMqhok));;GN|{AkAAOtRkTLqa)r7@b4&9A!9;*!9)hxe68M?dh{L)By z^dn=`uX-#_%h67^FTPMl`+Hh1Q^xPcKC@gI^5hw13^}WuGlu*H@~+T2c&0*>Ct=_9x_FKSNIT zKjf!g66=c$olJCiZfvGz%bqA*Iz|x&u>pEXT96KKcYq-GQk)Fm(r}?!eR? zn7RW~cVOxcOx=O0J1}(zrtZMh9hkZUQ+HtMj^)rD>qB>7>JCiZfvGz%bqA*Iz|I-#e+}s9*VCN4-m%j^jao%W<5D436VRWOE!>@{Eq-O`g$l9Lh7gMB~$O+@e0m zGuq)eNBbQA_+7pikcaOJqvbW1Ce%QY((0ZF%$V+8A}m) zWK2fnlrb5RU&dtQxlqpMMSb=I+F}2oefArEm;DKO*w2uY{SW!6m&E!aC+Jt}BJCiZfvGz%bqA*Iz|JCiZffMTs%ylN7o$DF&3D-I3 zE3SXghg=t-Z@JDypK~1rU2uH`-ErLo-Ep0Xa<0=*pX)cY!*!;%pRmrv?{b|9dAQDm zoLpx@{zU6c$8{#2o#p5g)<<8l9rPjFN8fUNi$143&;{j$?kGQW$LB&hpBMGn4`_$| zqwOcGGx59ZPsqc5hMeqw$WOf_))yH%rS8Dg9hkZUQ+HtM4ouyFsXH)r2d3^=&UGer zhjQu;Ox=O0J1}(zrtZMh9T?9A-GQk)Fm(r}?!eR?n7RW~cVOxcOx=O0JC<{uN!_8G zx&u>pVCoJ`-GQk)Fm(q`tS{N?1tb6I8NzNZd%)mA17q16y3+%@Yq{(h-L6l&D9c{b z{oTH!vg|Qk`qpigW$)?Up3qWR_OR|k?k38zhjqy-)mN51tV>_CR;2v7Y*i!m%f23^ zjCKxwS5_JAXSh{T8NXZRN>OFV^TE+V%8;|-Zv~Vgf7z$`l<{0MTN}%sJyI@v`GECh zj~}od+4~1x&u>pVCoJ`-GQk)Fm(r}?pTgzXMOYun7RW~cVOxc zOx=O0J1}(zrtZMh9hkZUQ+HtM4ouyFsXH)r2d3`8)E&#AJJyHpz|x&u>pVCoJ` z-GQk)aAJK4hkWm(PDuUA|Ay4Nv>9?d$Zv%lCn7`0@guT@99K9K<9NfF7{?*b#1f6q zkmDBhIiArD$2r>P_{Z<^y?{J?Umz#nBgmiVy$ku?iB2QsqHE9kG6p=`k+I>~zKj{q z-<7fCDG$!XC@0RuC_m1`_*^LG^P)cc0qwAV&_4SOzsvrFJnU!4$^M7@)JtN0krVW* zbrSThx&u>pVCoJ`-GQk)Fm(r}?!eR?%lY0>cPOXsz|x&u>pVCoJ`-GT93&>fh% z15JCiZfvGz%bqA*Iz|x??%tJL(SQ)E$_*15JCiZfvG!iVtqBwwkqg2 zbB2B+jxJamJpZ=wzVsV{87-!3`GB`J1u2hDQ~tBmmLT`RDay4r#0RV2oupjO`=EBa z80Fn=doa8BSml~UcLXbZwDOGpJAx9gjfj-Dd2eu}{_x&?mC;V#q&<|;ezQ`YmGQen zUT&uhdE&BtqzpMf%le@*b^6RJCiZfvGz%bqA*Iz|x??$>o%PWtVCoJ`-GQk)Fm(r}?!eR? zn7RW~cVOxcOx=O0J1}(zrtZMh9hkZUQ+F(f?pPnX15JCiZfvGz%bqA*Iz=`!G z9P+)BIwAEd{~J>8(q_ov;OyqZEEJfsz zF&U9l#$-f(8IzIcLOGuo_1O<-hy8>0*>Ct=_9x_FKSNITKjf!g66=ecpkJ*6rtZMh z9hkZUQ+HtM4ouyFsXH)r$8x@R)E&yHJ1}(z#_vLRVCoJ`-GQk)FrEv#15JCiZ zfvGz%bqA*Iz|x&u>pEa!Vi-JzVi15JCiZfvGz%bq7wYFZuQbw42K}F`#`` zzLk!4Tlt1M+H>XG>S*VcZ?2>LSH8uLc47HOJKBq}N1z=UdxS*xWkeC*Lc4((Y z`?O!3*sh7n1B15Ot9hkZUQ+HtM z4ouyFsXH)r2d3`8)E&!dH>d7UPThg2J1}(zrtZMh9hkZUb;Hd0^a-bg!GGq8P`t0TWFb9h7^ncE|BVy!~?u~y-8p`6c)`s@d^!~Q}0 z>^J-_`xEl8pCKpvAM#T#iSPN_REbqA*Iz|x&u>pVCVuegQ+_(b;oi%JL^Mt zVCoJ`-GQk)Fm(r}?!eR?n7RW~cVOxcOx=O0J1}(zrtZMh9hkZUQ+F(f?pUAwK;5C7 zx&u>pVCoJ`-GQk)aAJK4hkWm(PDuUA|Ay4Nv>9?d$Zv%lCn7`0@guT@99LL-aJ*ry z!f}YTN}}-@a@?Xm-#fI!_YUnx-aGkSz88>(?;Ygidk6XXe&Mz|x&u>pVCoJ`-GQk)mh-)%?odwMfvGz%eiym}Q+HtM z4ouyFsXH)r2d3`8)E$_*15JCiZfvGz%b;okPchnuqsXH)r2d3`8)E$_*15wqxSQ^fKO+IVQeI7US06PKqBg+2YE7sJt-#y+#&q-evEs z_>NnQC(ND}U$~&vc{KB3e2H9EzM;vT_!Z|Zw)$zF>+z?y7^ld6A^!GE1$VN6=%@%>wb z-Oi=ZnCsYjO~a*ojYnK=7+(L{xKI0f;jXpD)6UcmYbTW7AMjS#dXJSSt6Mdk`j_$O zzLmm4sjdC2nWDlR6^t8|ej_Z_(|F`h-NT^`OtxuFx`glFu=1xhJBFpF8dn|CJ3PMM z>Kt0zHyoMIp1sSGPs4A!8NXd^Xn1A4aoMpW!ao)n=j#z2el*ee+pYbrkH&>BwlMyt+W4^YQIp}uxC!C(@%CK3d&GpJ|1)m4dVJWcz18WH zacMa7WOD7pnN?%MnDxdPt1SwfOg1j@;)3vaf8(gX=7w9k7{9P!cIXoLYU`O{mwr}0 zqr&v?(FEiFy*@2`f35NLkEew5{xB}|>!fgX29sw_^u(}KZR52+d>JM^Z+!I7@^IK_ zZ<2*Z-b(bramt(utp-Q(AU+gBKWf9|XBhg-(0T5bq$l(s&ZQ+`tzo5Of%rY+(1 z$5vw1QJ{%csoNt*Aa}+d=J?6u;+w6Cf{OH5c6^tuY*&Y`CJDK)dn@_fd zc2YSo__rFW(5u zzG%E||BdjCAChWc?Wu4hY#wFLc=OpC;nsvcX+1Nkk6rtW)_G&rGrrIS<1(X@_!fPP z&;IfxywuV7`zt^|I)-h=SJURIv1$i1+_SmSRC+zo4gX}qc4zhT`Y##y)Ck~zWT z>C)w&uwQlKZryK&TcVA#O-kW&PchEhJh`9m66&N(=F8o(c3wM|(zpH3%8x%xhOWb{K0TbtLDXYwg~ z7*9Br(VtCg{5U$JpFhTAIQmIOpR-&N?YDPoX7qKwFiulHqyIgJ)wvcv@0;v@tm}tx zLry<^qH&J7IsD(9jO%^+oUhfw_+r!SK4W|1j+L_c2cwNkl*#H#ZZm#0DvJ-&Jkd7K zw#w{Z?qvL5TqZy8m~o9Pnf$wrZQT;LJfr{UxN)_6d3@To#_3nS;Fs^S`u@$_KDM%P zw=Q}8kD2UQuFcNpyEHU@fezHd?E ziXDsiV&fBJXj#Ok-DSTuHAfMD_Mtsjj_HN{m-lTS)Gt$EzrC^TBPM4o?9aaOP@ng5 zRAK*5E~|6+Mk(K--hWyioGj@}=QZBAql90Y+<4W3;=awZ#_NW@;s@qTsQ*bZ|50`0 zAsvhQ8_~vPhrH~2{%PEQeG$L9s-0cTNK?e$-fVnhTwz}-%Jz3hUN7t)?KaNSv8;dB zTb-|;ea-hPZJadvRiAZ}wVC>UIsauBt3Rq@dB5ts@y)q!_>(p4c{gUS=!=gx9`jz5 zUtYktXH4LGZL#`Y_c%YHp7HhHoF6^feyhhS=l{3Oe(PjS=a)XbtNl}Be&8EFwU~$} zYoh#yHn+7r{?{m9qK3sybjcscy;N2wUHTe+;=>zSM-s;RY7$?Abzru`RsGYw#xvGe z@%er={%Pi$zVkoE*~eG*DPF#*^}9~1)f*C%P^uGr1c2f?rtsZ~oH2 ze{kBK@sqj@eD(syI|sh!E0wse&s)1teV=^Z73IF4)b~9GT~&T^qP}-cuPIl#-P8~M z{i5=}N1FI|w;SKy@V@UD8t?nOu|N5X@y(%)eBnpN^9MEb`Q0V`-zifX_!p-dU-|Am zf8n0--xl{)yhw^^I#GIsDi?%H!TT-M$fDQlcIWqUt&;02X)ZpLF$8I;(Sb z@Re&AH_O-Fzc$(U!)on(q3gy2KKs}&X<<17r~K2_|8&eaCc3Tf(CUn~Q{k<){>D|~ zH_Ns4n+IFI!6~DA`09tPoi{Ic^Oyf;{3z(^KQCrn>%(6DQ9Wz(qXWHtzD35j8}{)X z4;wEz+t+WrVtn&_KmYni#wjoM_eFlQcFtcI;K$T9es1;vUm)6^w|SNUe!|`pD(Ae$ z{r&Om##bx!^WDoH*Yfna`uH4sepj9v*T+{`@P~50=6(Ig-TqY0yKs=t-Rg+)OM?gc z$<2*_Z275g)7^OL+XH<1ImWB1_xFANFh1S1pTAntawpaw-`7{3Zv6h4K7MzaquOTc zR(*W87~=z}`uIPdJErC5PW{h!|H63P`TzMISX@~hf@%CG{TMhBA zjxb($WVkQh+v=R1Hp0)?XuSG^k-qQm#_VFpDoyb9n;3VzALF~t*{|iV&yMk%|K6uuHeZZ?__pz} z9^-xVu)SJ-A?Y~Zy83SA`JKl3|1#`RPI7LXum7`gt<)3z`bImneDr`Af2M=+mh0pF z^(n@KyNvfce>EnAtB)hcy%70^hwh_k3e;n)UrTbRP zuWlOaf1GPvQsQ5JDgK?7Z#g*De;#lA+UiL@=}h~rfj>|5pL90va&>~QlptrxoTWy&=mi8 zalDpq%`?rnN&2<&l}S_m{(Q#AQcd-<8XG5%nc{mbG+zJ06yM>I@oqoaXY9O5|95lG z$$r9l<53kS`!7HFM$2bEKiOZtXM8B*WWQkSW-afXXR=S4Ym4%WRVVvKUl@P)-E`k4 zqqQG(_H#e*-;G+QK$6e>3pb7H|1iV5!0ODLHq&>lXFR&aET5-_@&5d?{ir;~zxJH% z&-JwbeSYU`e|h%?ZF5n^Ieymj3A}o?KhtTwmftTk+kgE1I^}w?v;5>r#ygJ8^hrMd zO3M#qnc)l1TBCe><_uq={#xblO3w5t9vDBUHOrr^v_i`tZ=2~GbTl3i%=A;186Vy~ z!#{jr{L+Ur{Ku`o)cSc+&G1Ez7(d)S-ABE@Qp*R-p6;ukHufW@`xV_+Y551y)BV~c ztCg!QnC>S{GCus%bU!tx$$9I>93S^wf;{Qw_+IIaD;JyXFXb{WbAPV?s-$ttUGsb{ ziT}d7@#NU~K0{99&hISnxy~%t@^HcezqOQc%>xU3rXkC;JZ+|hKF^O|C{J3nz%PEu zc=z)Qe3eNS>ok4Hd|xi3agDfnzCs_1hdLEM$G^A0;)c@Jo9i3Bvqan3d~2>hc**#9 z^gO@kh51@O;mKV8sJ?NB;d6b>ImRn9&-L5x8dqIE$KP+eK^x)W{&@Ap>fWxbNu+1OwQ?r7y7>2=V_g} z)uey+882)z-`Bfne6jQ*zi^lF=KG6$rA@|@w=MPyV~ooVjP=XjGVZW8)-RlFIR}3J zE7rICV~)1pG5ZpKrl4`Y*|B~_^lU9poif%pcsNVBW}C(S=x4?g1~2k$p3c6C zFZJ^`8IS)m&Sz|6T<4cKKVO71LG})7W)Bfj1TW#!&WX%-8zTxZ~kveq~ML!B>{~P2-1ao$b#o_sb6q zQ!bffxgVa@c=gC-zG?QMTE6YX7k=NXLzHj7{Dm(+e6aHRSL1y7_(95NFUI<-X+KqN zvv7%Dm1CfC-L^~p*vH1jTP*PxhIP~O@6W~hd4;+wmm3u8Kfi8Vs8Fn*@>>rrKXqoY zA9u8;a>0#@{ZE&BDd(TR*q2HDKjq%SRbT0&ob&6&zE`cj%0135_H|qIQ?6Ac)~{;O zU-|fuSbw(K0Oiq#<9yR8U6g;jztq2&uB-9~g_rt2))`kg_JuE$+v?1owamX4_lef2 z{qAz#|6XV1Hg}f$hB=Mn9xwN|=XccdY{^&nVFf!VuT8tcKUv;R`C`}QzQNj$l_zXp z=7(NrtNd}YW&T(LwCCH|SVt(9kgywn$b?<3{wrQ>`|j{mQ7?B_;W zKEKQozc0G6vO5^-$9?#|a?Ge$KcHa~sih1( zZhX!ddLOpvZ7s)`y#3W%%Fz4Mp*58;9^wmG9gOX3g`%_^sa3^LovyDP#P<-MqRo-isR5YAEA zymyQHzM`dcu!-$DzA+9H**qWyw}5DcwNi!z8_6fP8svS*r~56 zV}9t8tBf+{jS;b>l`)^xJW)y+^UQ#{#+ZM~+%2i)n6F+~VT`%7{);8F9P`!FAB{1O zrFzfmU`~!(lV9s#-WxxV@?-Q z#ys5Z!OO~+pI0U?ri^*}orlJl&o3Q*MawbIAB`!ljPFHE+>6TiE~FfpR~g@nYoqfi zckW$%K^fnp%r|o@<2#jWUoK^QzZy1rUK!uD6Q^@1<9oNY>vPKZ4levI zyE49yI~o|{yE!SBF}|~z|I4Ozum z@f~m1FO4$3@4t;rtBmjdfo18Gu^u?NKfN;634JeRP{#Tp|D%k`SXXR#oJkq$jXoDL zD`Oqf?5ixwSfAv5-{izPC;My3wH)i2XG*0|#yY1_y_CvW7ZodzOd0E?a#7DJV;wc7 za8hNgub#V{L>cR@$`33jC)Q)-^4tAESf^#Jbw9v7hV@(7SM9z$tn0Rn`%lZU-Yfrs zG1iC2+8JZ*I_Ksct%LPpzdd)Av2J{)n$^J?xclW(T8?$*=wHt$WBqyioZa7tb?KSs zE@(N{t81FteO_3{)}MP>%dx)Qbl|Eo*1e@KT8t#t!#^Fe`~I*_-ZJKv*1`ID#)I3+ zSXb}NYjR?Jeqf^A#ff$JCp-SoI#{27^t$B_!Fv8wVavIJb^hwYc8@34|0RF@)#}T> zz`bU7ePX}R^ApQkf_=pPrFI`E_7^oz?a}(!cl3YO82gc$b9ZYw_9?fQ8)ILSH?`Hl zo~uYlE62Vj>pkPg(kGWnSRL%$o`3c$Z3p|KPS4nVDA+gsuaMn|gZp0I|Q@-EWuuuk8D}?*3L8`@zn;><&uo zE7xURuI1Q2&KdZnGWL~E3fR4G*oXG+6sP6bpXRT)M0t_yTZ@N_jAcJt|FPX+ihXYC zI(APb_P+(^*?m3O7sp;pxW7#H%a!UGV;}vfkTLex+j|*fKYp^%3~e801+O$S#(uo& z5@YPscTX|KnZuKBhHHK7>)U)kQW^XGFCRuL;~b!(8>5W#fi%O$DdXHA)z>k~I8PYz z(?n&QGxUw0tc>%AY`vx`<6Pp(`Dw~Huc(*aWX3thq|?SY4_P*%m)60#$KY@JDdRk3 zTkFBfI6rx~u8T6xRUSR;pp5gD6yLN_#yL#hBrTP3K9l=U6J?y+)L+p+8Rt2BM$}ct zInVxGb(C@b6L;Mh=RzHmzpLdqM{1l=?$(nz1ZP}_@>@GNN9tY380Sl={`a2N(X+Cp z#guU#wd-<8Wt>x;Y5kfq&aaaEU0xaIT30^~lyTm*Ytx&`I0xIhv$`_Q$NuX4wldDm z4$Xc?8RuzDE0~-(XS-A06LL#_|NT>$~ZqflP;+;&J|yZdZ2fr;k@x=+ndTbhkP*Yf-=r0|IKKObIUVr zFKRi?GrNzutc>%|;KU7OoXz&F_n$J(KVvG~RmQn!itx5F&Ul|`wMrT1sKfJrt&H>4 z-G#R);EHNATd=j#1V+)&1O``qmJm2nQAd2=$Y zk8}Gi2Qw?frckJ25oMg)cR5->8Rz+@*5p=(ZDQn+gB38&asL0GFRg8=U7*qcW!MXb zj#{J)JHo8I-zvktaBl2bW!N3o^hu&^!XA zB=(Nzl_n?bCQWzN-3obNAKBjT$QCf{CR@f9`vwd<%bBQ!S_k%*^vi!xhFzvt`iIJ} z*9?2@xp>rv9p~L;MU-LRDVn;1GVDH&n$}i^J*ZFjn#!;f^|=c;+2sWR+e z86KGou!|k*`-YaoUY31XF=g1%4qSRs8TPf>_d9_QW@i9Z`mzaZ}^Jlwp6&*YUD4 z?2?Cj+){?Ua$olc%CKX;^UOVE*f;zCa9bI6&!Ok9DZ@_sH060^*l?4lKCBEoY4LW) zlwm(@nC+x8Y{C0;rV627*jrCcepVTF*e8XbXdT#Riw?e{47=@!ZL8FuqZA5~O_J^iJ$m6Ty;KfJbz zGVJe5A6Hg}UA|pcrwn_2+4T0musE6T9%XWw5!8Fv4S`CnCr55w#4 zzNNfI`~<$(Yrh5mfhx_cefSlOFIYkAz~5j-WosXP2=(__JMd39e7L06f#1Rp{fjHZ zpW*tq_U!O;Sg^CGmc#$y^Zv&0i`aD882%O2UTdy(;79S_hmDlsUy-a$U1j)VgxT9F z!%w4P@lML{-}t#pcV+l>r1-jzGWIlyn7qD#K@H$Oem>gI~%Ue|OY!_^UJsyC}o=X4(a76aFp3JDLpe zdwDL4$p(Lz3Q4R@_{pSxx2ygy{AXUy)>#>TH90zVP!7c3W@&T#UHIYjePsOr|D1IV zjp4Tw-_98RJh{qztp5wYpgSYRD#QOLORCYz@C*8V=m=%_5&b!Sf^s$SFB-UXvNHUR z?(LhV41c7gmu4u#Pbpc;S<3KVDsW)7GW?oaRGO;{f2U2?tsH((E6ZDb_(!cNVC}%4 zYS7EpK774a?2OU>g+JBNITMxPXLWs>$pfFUOf_a|IsCE?rJt@0f34_$rYggatKt)@ z5C5(kZ%)#3_Kik@$=P1Mft^LC|W%$L7dSQh!{N*aYxk?#+bni4?s|^3T zF4MnKhTmPx!F9^;$6JwZgEIW|mXES>`0u5gWB&`kzIIJkYaRFj7B2LqGJF)zLv0N~N3T48O`c?;ir>>m+FZ@vl?Xx!FzZ%uneha>}asF%lU-+*!O0!uReyyoy zn{4pWoqayka`?fv+-K$RkKJ|1>cemLV770x4*Y3L&a^h+XS?U)jam->+s~t|AK;hU z;puuUhrjN&BgXLKU7gzMz`ytSY-9NSju~O?z<+p9M|)oQ34eavo)P}Ti<{ar!r%DY zDL-iY@Iy}d_0P)iPwu$yS7rDu-`#px8UD;W#~)FKpL5F(ep813^ZtTImEjk?yo}X> zzjW=(2ell2)YY2&q71+5mf!uT44?26Q@&G%-}S3mOlJ6F*ZpO`mczIF?mc7pZ|}Qi zb>P>%HM8j#{@$f}T08IqPm;r)7yjX;)9uoB;5WX$$xdbXlb3&D{Qy7nY)P#g{^zCJ z8pAI=Szh~J_^YohZEeEu{jK+{PvGBv`hYzb{N9H){Yl%0pM2H9$CTkeUv$o&%J8dC zzu=@Y{Oud`Kcfsk{H7WIQigwi-X+HH+mCzgtd_%{zg-rq4?q9Ti>w{^|ChL8?IT{` zt`n81WH1-!VqqM33K%5l^vWyS0Nji}m-ceZ*^= zt$IS`L0rbS({_Sb~k2sg>pP$ll#Nd40)#O2(%i4EL zPQ<@7Z+=|sAeQI1N~R0M%hdnK>LZTk;WisTh_4CTSpOsLW=Uhy5#n*yFECvcmpGl3 zRgE=%r&>b!s1xy{V~r8-^LKOmU&H~`{>0iue9)}@_FITEs+`Zp72=78d~M?gaYhq5 z*!V$QQkqis?1)#IQ2K9u7Q`{tOL#)U-)+X*i+;qx*3wJNBykN57p2uICS%2bw#+cUDpSZX2^c3rV+?&ZdxFd4j zESrCDcVzAy*3Y<8^8M5H?6^1c<44vfxHq$0Pvh$2-zeCzYNUJ%%W;<_>*J0~wu8Gb z**@;X8*4@j2p$D2`hh&ruxDGR~to&Sm^Zas11B5ykgH-j^u8FY?|6eDCD_ z3iy7>dl&G%llL^>dn)g5!1q_)>wxdIyzc?ucbNwQ&I2+(1e_ma-Uv8v$b1rTK9PAQ z;5;MqPr&&{=Bt47mCU69=Te!k0?t=5j|H5^WKIq^C(FDSaNd*oFyMSB^JKtzQs&Qq z^QX+K0q0ejZv)P^G7krwhh=^aI6uq09dO>3`8?o!F7tfAd0xI30lydWT?qJHkncsn z?}dC{0)AiQyA$xcBj2Nd-y``>1^iCQ_bcG{OTKFXziaZn3;4a0?_j|1pnM+#ejnw# z8SuL)-`RlQSy=-FTm#5=HsE(wzP|y#zp|DHxR#Lbb-?ene8&TR$L0GT@cS;`{ea(n zSq}tU56C(p;5tFp4*}N?vaSfYu8{Rc!1ac#LjtZtWPK8FeIo0efa@Gt&jei0$T}zB zI!D$;0oO&cUJAHgl66$Tb(E~H0oHlU1ze}e`Yqu4P1bb**LAYq z3%K5s^&AfVMp**~Tm#EGGvGQ?)}H~_pRz6uxGt6TYQXiX ztYZVNV`Y6CaD6N5-hk^~Sq}$X56e0^;5u2>&jHuZvaSxeu9o$A!1cMT!vn6vWqlrS zeJ<9fAz9We2J7(MnxF3;y zO2B=J>}vwMXQ{!#Xo zj{8d4hdS;&jI9o!0~)Q z&J7&T4dgt*@jOA!863|Uyu$IkLe4Q9&oSgY#PK{t&OIE@J>)#Z z@jOJ%PaMxrXVT0Y|%l z*b5x(1!6~Vv?GXp!O^}Tb_YkhgV-Y+?Ga+9aI{m1{ld|HA$AQ%yN1|19PJ%qH*vI^ zh<(J-J|cD#N4tsGSsd*wVt;Y8zldGN(JmwQ8b^DL*l`@~IAY&%wC{-B$I=l zkl2YF?L=ZfawdzRR_ z9PM0U|8lf{iCxUmE++OeM|+vr(H!k)VqbH#uZi8w(e5VpI7fS&*y$YYbYkywwD*Z! z&uvSv>xsS3(cUNaK}Y+b*bN=+hGI{2v?q$4(b3K*_D4tiqu3=K?UG`zbhKBB9n;Z{ zDfUfA`=;1E9qpcCCv~)wiVfG%hAVbbM?0z5PaW;2VheV(1&h7a(cUU{SVudo*k>K> zvtqY(wA+e3*U_FUc3ww2uh@Sb?Z09dcC-tNz1Y!SEOunqJ;9DF_GL%=ve>B|?bKqA zcC<%}o!Ze(Ep}~3ySCW79qrv>2Y0lCi+$YDJ}!21N4vS$(;e;UVrO@>vy1)R(f%%W zc}Kgv*y|nb^gQE|F_z5`r35frIqyK>T6*&48 zh`)iOzk&E6IQk)oe}bcbg7_^s`Ynh*gQGu#_>GIf(y*qyK~WML7CJh<}Bne}(u_ zIQmhDe}$ueh4^DQ`eTTnhNGW`_-{D+Z-`%qqhE*kdpP=gh#!cfABgyeIQoZ(--x5% zi1?E@`jd#CiKCy1_@y}drHIdrYn|XTBYr84ektOw;^?m;zBi7(H{##o=-(oKFOGgM z;t%8K4BYriGel_B63rzHMMj{ZyH*W~Ee zB>qm0{!Zct<>&_`{!xzpQQ}YK=uaiSUXH$A;!ox1PbGd;>^eq4@zT;kv5=-(xNUygoX;t%HN4<>$Mj(%d|Kj!E^CVpj(er4is=IC!GerS$< zXyVW2=+7p8YmResD=yxaa zWsd%M;-}~6rzie0P z@t<_`pAB|L`VWi0v7^7S_#r#`A&Y;qqkppaEj#)xi$AlY zKePBbJNh|`|Ffh2v-m|j`bCSsw4=YY_)$ChQH$TTqu;goggg3#i{G`Q-?jK-JNjdb zZ@Hsyx%h88`frP0x1(RT_equ;yuw>$c`i{HDW-@Ew9JNn6s|GcCBy!h2S`qhiSy`#Uq z_~ASH;fsI1qkq2m?K}GIi$A}kKfn0-JNo&H|G%UEzr+hT#tTR+gJUd%#0xma3rHM+ zV;q6RL^#GoNZf&A+=0X+IL0GLoPuMVg2XR4#xF=*gJWES#5*{~J4hUaV;qFUmpR5q zNZf>r#7zuZ z;ut3)@gt7$BNA8Q7*`_kCXVqY5{Kd#ha&MQj`1lHx8fMLB5^K`aV`>r;~0Y@aW0N= zE)xIZ82=)%JdUwE5-;NzFC%d@j&U>+U*i~GBXKv5aW@i=;~0-4aXOB1IugI*7{4QN zJ&tib67S;}?;~+Qj&VQ|ALJMxBymQLaYhnPG42fY z8IOi`7^jBz8NY_#Wn3HNXM7ywWE>piXM7xSBUYzctebB#!h1VFg_9EigAk=Z;WTe zIAok7#wX(+F>VR<1X>OFdh@{9pgIjevM6t-^6>zxK6yM zj045{%lJ^d*Nhv*`_6b$%ma)w#r(kdQ_LHTOT~P`cvZ|ZjAO<8!}wOrSB!_nT*_Eo z%vX$u#XQD1SnCBTsjPC{Gk?~z%+%divj7P@zh4IVy?l7(y-y_C5<2%JTXnemIAC2!C z~s!gN(Dr_mT0}_--;T8{b*Rabpd@7;}7Q8OM$9FXOwhmSC(pzSoQg$9J4@ z;#KAQ&iHYB_Ze4?^#J3|u})wdI@S-2Psh4~aqC!bFrFRj5XQMnq0ZW8KBLeyqnB?~ipF^8jG|#{2+S*D-GZ)_cq+ zfb}8s4`A)OCm}Zi)`!eLfORAD5?~F?91B=yGLHe)pUiK7bt&^6V74AL>^JZYb z!+aXpyD>Ki_D9UWfqfJ6a$rBjd>zoKU(D};eHrt9V86zEAlSz-PYCvR%pZb% zAM=V}KgfI|*jF-d3HFc7PlA0V^Oj&A$~-67pECam_N~l|g8eM>rC^`SJSy1#GQSG; z#mu{c{W9~hU?0sqE!bZ(e+%~G%=dz`0_LK@ew_JUuuo?m7@RpUrw#V?%o~IKKJ&@o z9DsRda6Z8NGdMS3UK*SyFkcPM8JNcg=MT(pgL4Vyy}@|}^WoqegL!gr9>RP(IQL*) z9h`?S-ww`CRwv}=!MO_a_TapQ`FwB=!#qDYpJDzVoZB!j5YBU$F9_#6%p-*JALbXr zxe)UX;T(y1ig3oo97;GxVxA(LFEM|So|Pr!V#0Y8^Bv)wig}Q5e#QJqIM-s{B%F6K zpAyc&m}d#+W6ZyVb2H{;!g(6=HQ}6%d7NQJJR;=c~-$g>zTt^}=~9^L^o*mU+N%e#`t|IM-#~Fr4=? zpBT=8nP&{=!^}U1b7STu!}&Awo8g?9dCYMB%=~6JuVy|poMSUj8qT+wKMm*J%&Ug; zaOPXXIXUyN;ryKW*>JATylpsdXFfNa!!yqt&h42O4mJhmti!oI^TOdgpZVfon_%uc zoc}YwoZ1Bv^3K6tz-!QR1q zda#=?FCXk9%)bY_3G?#7&cZx?u)i?BAM7&B`v-ds^8vz+!#sho?=XKL>^{sZ2zwCo z4Z=>uJcO_xF+U;fP0VKqTNraK!rsJuhOk31&mnAT%-IOL74ss(p2d8Luyb{2bw=am zVgF)&McBodcMbjUt|78*xi`d5%xIddxV{ic_3l$V?IgP^_Vvj_CDs5 zgnf|tCt){aUP{;#nXeLdM&_}E{gL@CVV7jyOV}%!4-afotJq;VgF@* zQP_oF3k?9|MI3cEJ*ro!IMe5$a6GtVmQ z60sfK?M^H;;~hr((Wt_*pTJH+;sJlN^3o%=-<0E#?D<9~bk4!@rC9!{PVE zyyEZ&W4>|ti9JZjLk|Bj<|l_=S*?V;t*_baKerwE&4u3Z0ONaj( z^Q*%zj(OMNFUNfB@S|g%cKFvZe>?o{nAaWtc+B?>KRxDwhyUK@g#7UE>to({_yID{ zJbVfvX|JofNEWPW@2B{J_l{1urGAAXF?lMnw! z=Ff-UBlGIRACmd@;U~#F{P3S-et!62GS5H!Et$_BewfVj55G;`3n1}j0q+ZdpJ(JA z0rCIj{Q~d{<-G&&7v+5f@FV3t1@JHB{RQwl<-G>*N9BD7@L%Qq2=J}t-3{@TcW{4e+z&Jr3}{<^2xu%jLZf@Ym&i5b)#W zJrVHl<^2)x`{lh7@E_*=6z~(~JrwXC=KU1#H(r}?p9TDodCvv>lX?FI{FZqy2K2>h;juLu0GdEWiNvZwUOod7lXUzix*FA4m~d0z?q%(o=mT>}4e-fsfGbl!Uc ze|6r60>5|Os{;Ra-k$=$ciyW4KY8B60{?m5&jP=C-rE9yd*0^)KYZTv0{?v8{{p{# z-U|bNe%==YKY!jM1OI>CFN1gi-baI22Hur}cmdu=gE#`-Q-hcY-noOg1Kw+ccm&>e zgE$4=gM;`5-j9R02Hu;4cn996gE$D@vxE2u-oJym3EsLcn#hMg!m5LAB4CM-YbN75Z*V0I1%1Mg!mEOPlUJ<-dlut6W(WpI27JpC*t_n&q?I(*k#NA)~HC$sD;m1KDxd6 zzKa^{Ecac}78!%u(Uv#w*E(+mx7J#&ze`J+2b-fU7vK1I`v-sRv|NR!HjNGrXR~~X zb4pGK`W1dx_eVurObTdEM0uOE9kd+vljrHJjCTI(K13PqXL^5>GJf~=jxoxR=k51n zlp$xy2NRVcf1X*BmCyfjx!|yZQ&=9)a;YEB`qECwcBK7~?aS|m{9TbJq&y;LNI6CR zkn+oOg^8XkxG)$xvUo=MAs6<7XKPCa`?knYF><=M}#41D@0 z$}c2e6*Spq`T9CHS`|zmX?grme(-I}^@sZJB(Z#eXlKd1l-kc|zj0>ETZrFH+tBhB zLY|~eEpH*@td-O97DE2C6OHj)>%TVM(C+g{`L}l`N9t$UHX+i^+QZ`_?N@nkOyqYP z*Bl*@XV0Ed5jm^G2T=AR?u>t<#a7t_D;}fQ#0+)ncw^uq`lW%dF0Of zLDY@z!t4ub=b6xtzxWvSBk@6t#nMnQd7fwXlDf;-2 zNc-^vjzxa=K=ne+!VbfCeltupVmkafk<+;KPt1Ry>%IoxO6siB+%a#Wi?c~|rM9b0s&lM8JiTrN# zKpQ8JXW%d!Cy?{oH!b%s@(DZ zg)yG%Rk7J8%=3|QnLi`-WnPW6BlB&feVK`&9BXY`o9#Vdp=OfRBay~EW zvmek7`v>i_-|)NaPsqc5hMeqwndc*Vk-Ngfr%SKvbIBdzA?|<2Gs@lKA?}3-%bnvP z?u!S@UF0F|kq65i4_a^CHZ`nd0& z?M$zIR~hYJPxhZOes_PIG32T7@;xnwoE^s)L;hOd8soWmx4Yc=9x0c*;63Zh9r2#+ z$ldXt?aQ6=p1&)1&3notchGyvDR`ArJc* za&kephOLeJ%^Mdff35%cNc~oC z#YEcKoMb|z{b`FQM1D8JOA{mVlo>VAQ_ig0Cwj_%@!-VBbD^Bii~8&bw8Q?<_7nOI zzsvrFJnU!4$^M7@)C->LSdxW0R`I+mvl*iwV(J;Af4*94jDCBi%p$Fi{!DSm82#L8 z!eT9lzQ#9?RffK5mS3U_eO-8dX{0>*kumC5Jr<|sXs6p3UnryfJ*}51<9B1l&kXM% z3*sTVvK^(A_Y zl#6~N^+oTIc4Rz6+Lv(>`CS=55qV@>MdXxm7?EGbVdS|`&gVsa_5<2s|Db*L8-ADl z33=Ghkdyrn`KcE?7w1DfFW)=#1K&sV58qSt8{c2_C+9=-Gv9agKj#7Hi}M5Y#rY8B zoKH}n^9JavnxM zQy%m`<%C`+KlH`tLOGuo_1O<-hyA1NC(MWVUG^vBVLwAo_CMsOUgWzRjQpo(ha!=Yyk#lp$xu z-wG&0{<2T=DdV|jwl}SZy{)hb33)WH87uHuS$GVI4u^wYPSf{al ztl#*%SRYaztoJA<)`yfI>%&CP74msepZ$P#*gt5W{f6IVe?lJiGvs9dL;ghi3aKxw zuUL+C7wcm^#&)nyWBXXY@prMVqdZveQBJG_DL>YSd@hvpc~PJJfOgnFXrKLt-(`P7 z9`-ZjWdB2c>ZN(MRYAv@GjvQIU9dKI{%zxZ={E#3T1?mS0dH*zQXZeC{AZ~xLGFW7 zlxuB>4_3cBNx7W&LG5-i%DbK9s3|^Hxn|KF!3rO(Jfr`Ppu}qpVG>a!ov4*Lh~ zv)}N$>`%zUeukXvf5=b0$a96%mz0Mrm-->=OFJRkk@iEjFTWe|cSW9%@`#)v zeHkZ_-<9zbkw?a1L{1rp5&2~tMxG1hd|uRNKcF4<587wH;dj}ekca&YIobb^pL)SO z&;2syf9}ihUEqEV-wW>J@Ezg)4&N8<`|#c2eh}X;?i2C-;{FleuSEMw$NeVib03O! zxIabv+_&O)xu1nR+~-10?tdYFqWyBf{W9i%mgBp?`uJY39ehXFKE5yfU3_;a557l~ z6W=MykM9?s3*~%X)Mr1S9rh2}XTRZh*`JVy{R}zT|B#=0!Mw2|ot-COJ{gqH81qca z=Ej(RhQ}LYUV7y0oB{LIv6IG_$4bvmICGHsutkUax(~v9_4Wa?=>{56EtJ*5kR_<~7EA!g9^J-_`xEl8pCKpv zAM#T#m=CEh%qJ|zJj42!f7lM@L$;6kioc6_jPhW9qnw!cC_m=IM9&rSc~PJJfOgnF zXrKLt-(`P79`-ZjWdB2c>IKh5ePKRfIp!JG$Na-~FfXxv%vbzf%wv=X^Bd*Fyhr&l zAM&|S&gVsa_5<2s|Db*L8-ADl33=Ghkdyrn`Kg!UJ?n*qW^B}PoB6A^!fY$nE9V;< z6@GB@E9Dz+mkjs!TdO>zcHVGEtu@Mf{>>0h?Ydg|Qul}P*Z*Fn{A;#j@i})H=lEe` ze1ZRrix*rFUi|A4k)uc zOTcH5XAJm^^6UYhUHT+opNNhE>PY%Civ2159L0W?{*Pk+i(UfiMf4R=U!uo=dKCQz z)UW70pxzG`y;X6*@1|4Xtz`7iwj#^*-UrBbzF?d(WIkSEo-&?ga`XgcJmZT+dMo4E ztN&O<8GRDhER{0)D*ds^dS40pu;z=sHe+9jzTF|Vd@%a__FrkEltmY}|8AfR9evPx zyfVfTWy2U_x#%uredwL-U_7vWj1&GY#t-GexT2gGZ+tmWj|m%vw!e@ zy^wZR0QvDQ6#HzGGTxDf&A(B`yYn#K%JEKhT)k1t@vgJkUG;7vq6#Vw~`|Fn%Zl#ua75c%#f1hkTX{7iWa! zZ?9Gv1|FRzZpQXp7fVbH)8E^s<^Il;F#gb9<)NjgNq+BNl;e*~53^^q^Xj(_%?>-? zvoq?g=@*8F^IpiC)UX9mwPuwYOczrLQ0&kRv=hX03+ z&vCCM^~;}`q+{>Hq>sbF)%q*P54am%>s?DZ|NWcc+yhyZ+odiRX*0!*ihkd~o?3pa zPd({;FJgim*2zLtO5afH8^XS(v} zy~F+T#WBjOvJdm0mE56x^7K%@Kg&+#l(UEW_79A!_wMCuS2?ETPg?c$%|1M=T;s+7 z|7vx!DO5;3*r&<9U&|XTN$E2$eop7fKYu@d*roOt?9s6JO;;0wVm!rN!kB)kjG2=L9MDLDzm+{~@9%PI;j$0W&j^jthmE*XQ@#Z+* zWSmFp%lHpC{$<<-9Jex_1CD1I=K;sLjDN@RFYkrpdm-`g6##X*xiW|PXdYku&{C*NuPm!szf-_;D2J5QSv z+&;TOdEc!$!J7ZARQ_ktykK0(CCV8-*c?03>*r&zBAETUcliF8< zrq!*^>Oal~_h;EyeIw`bpm1dy!@pNN5*(;$WBXC>1Hrrd(&=wixb}T;==W60FYnzO zteTZfS?0YU?+dm@l6fzoBc@Uz2Nk-W@CchU#xjT+r)U_x&?Z?c+J*M(C@7F#?X7pv9^xF zcu3XU)=?NIG3RU@h4Is=)G2KfW0GxR4FB+w)yFs-*2&tz_^i^@+Q+!9aoHH}QKoKN zv>lA|#~<%g#`rIl%GO zL(`GWd+y`6Cux0|_kv_UPE(e7FPNHts+bDI4Z$%8WUj&w{y~&xrY- z{ebTR`v>10_CLN;)EB-Z>`#1O*w6Uxu>bKrqF(TwqQ3C`q8{|Hcc0@Q-)oLre8)MS@qOnw$9JFOAL{|W7g#6oeUW)D zjN5BtOy<4t#$|g4W!?+dI~y}H?}dkdvN0p`UO01#*8SmwQOe;#|^W!?)PwlRMdnfJn)!{=#z znfJnypP8SG%zJ)bQyXtG@A<21Z7j*W7xrs!Ec0GiXNa-Pd*P0|#xn1PJ$|(Rm3c4x z;J%GvnfJoveQa#Yycg~+Ykod5?}g76pP@3yycf=>GfTNar<5-Hw#Lex>m`?X&-awW z-=B4}4%AhClKEMeJGz!~o5xArk1y9y?lJFK_tnuil~Z0x=7y~alzX2};jZs{LwQyA z)b8&$%PFt;ES-ABjpP@)4Jxbv{T+wD~-#UzmxKp<#V~uAC6LP8c1I2CnJ@=S)9dHT{l8`!?27l zX`bQAH?F616=x4oF8w5pbF)8HJ{_OhZEoCGd1L9+uF%z<%H3P1cBuw-RZfz5kgML? z`tVrnXgBhTarr@`+^k0C6LsvJ5w2HT<4^Jpll(KrThEPlFaBZmpA;6G-S@_GI(_E; ziZ`x(afQ`7aeV2VpM)AYM1nCxDkZ2Db$ZK6Bb)bzWk=>)g$+;o$3%y`$lsLe%V z$Bvct&;PesB*>|CmcBmS{aUYjgj4<1Lm4t;-}dy9wvz8U*35YJ`GbwoZ-<&0qd(t!$9@ZaH7sdD9qGe6 zos;VSqHkA>F_!-Ed=~jF&)*UmJY^8sJY^G^J!O_>@q89}M$c!IXZL(|w9o#RzVhrJ zF#8SlsV}s{en$K3fBY`>0(qz}$Vojye(G2H%5ywOUwMub=_}7MCVk~O_N1>o$CZpX z&+#UGsBy@T?O`#;V% z*E;f!`|6pRD$6_Wzt7Z2S>AC!Bt?B?dB^?EOm&py9rx=hzM?GexW8T2<_&qreWL?5 zpU6AzkNjuzjJ)H1;jGuSzP#gp?yQQ+@{arb$15qzJMK5usHQCMxc_xiO=a{m$0Yin zV-qS`FKChIq&m6?|sg7yK1jdtyoDmqWB63M!yp6~`f$?1;F9ycjh};tx z&m(eDVEmZKmx1wPB3}l^kBNL47(XWRWnlc6$d`ffVaFdkCm_`rBbk>dm7Aw`Z4jOP?NK`>raLQm4#z%}iFBl&&^1NWr^Qw{O1>++|o)?Ud7~YUHNDc%PA*2IG}RE*p%88aZw-o@?a9!FaBb69?nD zMot`zM;keGFy3wC*1>qXk#h&*^+qlpj0YS!dNAH_^<8wzIB8-u;(Y%$WMgvzau{p z#{Z7|L>T`&@)Kb^`^c$;@$4g~62`NSoJtsvKXNc(y#L6}gz*X_mlMV-kX%j}uRwA+ zVY~&&{ehHDh4F19uNKC)k-S`m*gPB zcwCZ$4C9GO&N7TwCb`V8d)(B>afb2MB=@ySKU0LCX59RnDj zTyzXzd~(q-fbq#i#{kAB7aao_Z(p<*V7z_NUVvSDA)&nh;{}XX1B^#78V;~)J|r|B zU_6D~j4wI5F|g~#By?lo_U=oLZVZes zIl3`0zU1h}!1$7*8w2A@j&2N$FFCp~FuvsI#=v-~qjdx0rHn1iRi*LhlH6y`zNQ z5$t+L3B4oO^^OvHN3iQ1CG?J9*E>q+9l@@5l+ZhZUGFHNcLcjeQ$nK&c8#WlMicBB zO$m)A*fpIJnoh85JtefBVAqC9XhXrS4VBP_f?XRbp$!GQmQ?!X(af$fmC%@CyK7G+ zw5MR#q)KQ~!LC)6(5ix6!z!U+1rKa`Ttf2-c0I0y9vAGIR|(B4*tM_{T3E2_bR~4U zVAttN=ybuZ)0NQaf?cO8q0vSb_x?tDo zO6YXKuG5v!>4IHbETJt1yS7+DTMTw>v4pl5>{?_AEi%|O$`Tr7uxpwnG|gbwG)rij z!LDhR&@_Wx11+I}2D>&|LK_Ws&9sDO8thtX2`x3)HP%w^XWtHX?X@(uMP}D(OK7!G z#&zTpI&!dUwI#ILVApU>7Xx4M5nn0TbGQuxkb;Gy`GR7))pk!mfXq&_9G-V=$pH2)p)RLVFN)UBrYgBJ8?| z30*|kbrBP~h_LG-CUg;D*F{X|BEqhVn9xOpT^BK-iwL_eVnP=Yc3s4TE+Xu@hzVUp z*mV&Tx`?oAIVQ9mVb^j@XgR{J<(SZNgkAeFq5TNECS*br5_S#AgoY&S8j=YON!T?c z6B?4RYfdIKCt=s3OlVQUYgCG6Um32jW+bvx5h zuGv<;hJYm=KOz3&SuIHK1^MqZ`Goj}R zyPju4&l7e%&xD>Q?0TLFJx|#6JkyLmnO)B_q36kV*C0)3kixD(n$RGHU4t~CK?=KO zX+pCUb}iF{mMQGorwQ#-*tJg++NZEG*n^NR!wND!mhcR z&|HOGi#4Ie3cE&Yy4^KeVb^p`H|<&rcD>nz-YnZ)(>0;#3UAt_Px^J(_+ZzeP3X|F z-F0XaI<&Cs&?ap+gJ14sAk*7Iq!lgbpq2I(C~2XkpjRO=#!BuAQ6E&V^k&H=&&iyVh<(YZrD6-h>7(?3%p^&0g3wdlQ9DIBKgjO)@8o~(;Vc4~W6WYSCYY`{3h+)@B zPUs}Vu0@>CB8FX~IH6GtyMA&)KN)uY*s4&`*Y4KRKbF47+}ELO&UH{p5sxGVJ=v3H@Z)HJ{Um+hlgl=Y-~Slv!dxLh~7R zjp&3%H0;{Z3GHauwWiYw?~e&~t?7i;G}~QkI-xZUyEb(~n;Le_>V#%B>{`|dEo;~{ zt`i#9uxno@w69^;#7<~p!>*y7(9nim-#el24ZDVRLPHyNZS91%Htf3J3Egklb-xq3 z->~a`Cv?AI*ZofDe#5T&ozVS;UH3bo`whG9cS83YcHQrU?l~8XqCf5It@x_mBX%8p3o|XUE4gNZ4SHUc|!9Xc8&CeMmp>o=?RT=*fr7< z8tJfWswXtnVb@wuXsyGp!Jg1yhh3XJq0J7vW_v=j9d<4EgqAz(+V2VNci4656T0-U zYriM7-(lB;PiVr!u2-MXtA|~$KA~3+yIy@luO4>2`h;FR?0WSHy?XeV;e!%-^|0&J zC-mxJ*Q-zH)x)k=pU|s^U9Ubpx?N`1t54|Fv)wiJ6B_%lYwRa9_F>o9PiXAJuF0R! z{ zcv!&hZISS{fZg*V;dueO7e>Mh19p#$ghvMK-Wdt+4A{Lk5?&jy`+y{TKw$UU@HMFm zg5857UFjYiYL16a>N%(`n?hlgi2Z7xmB;gMN zyFW<69|U%Pkc2-7?EWALe-POHK@$ETuzQ*$JWXKtG)Z`x!0u_1@HBzl10~^s0=qX# z!W#v4FO`Is3hZ7g2`?46f4|WQFBRCmR}$VUuzRv3JXv7(YDsvt!0zFa@Nj|M+a=-c z0=wr+!t(`oj~Jg9>J;q$H3|P3w!246!XpND@0f&l4D9|g311u7eP+zBUP88@9WzO+v2;W;?z%Dvz%XOgs46z_gFA4a|P=wSnm;UOX`U#ES=} zpLp@W92ed_Fvp9h56t-B0R%HXcmTnS4<0};jBRrnCk~WCYb9AKPHL>HB>kvOCnClZiCYb9M zKPHYyeN>l{BOnCl-uCYbvIKPH&_1wSU3`wI^#nEMM4DVX~U4=I@Y5zi@@`xGxK znEM*owd7j{<1@rvDV+-cFgeMow za}2*QnCBRtTrkfuyt-hXd-#aKJP+{^gLzKkBL?&Q#77L~xr&b%%<~o>F_`BtK4P%@ zh$Vc)V4mCfh{bk)p5r41^PI;=4CcLn_ZiH40q--I_X6H$Fz*q((qP^%c&Nd=kMLZB zc^~1q2J=3`a}DPGg-09Adkyb4nD-!_ZZPjbyxw5mgLuHfyf^WNgL$9gB?t5V#pe#@ z{fn0z%=;IQIhgk~{&z6%as2OK-tYL|!MykJzk~T6!2b^BI|2VYnC}Pt?_jzz z?p|35nEiKl}3Z^Cbs?fg&SHwyEgh2JR5{}+CvF#l!vjl%q|;WrBNABW#4%>NyJ zqcHz{_>IE+58^ip^Z$rPD$M^Q9;q<@k9efQ{BPo^3iBU|*DB0^E8eWZ{@;o>E6jf@ z-mEbHxsCQ57|j1K9Ja$)8f@X3Xlf50afW?llH zT$uR^d~#vtF*-eeX)yC1c>A)Qc@MmOVdg#X_Jx@z!3!8>{sfO;nE95L^Bo?{d<&k! zY-hd&Phpt(89az#=56pMhMDKVvlwQc2QOooc^*8DVdjPKK8Beu!YdhOehD9EnE55V zl40hT@KA=CkHX&>W}XUvXPEgb{GDOuweWX_neW2i8D<^~e`lEaG5noj=FPr1whCrG z4S#30GtY*#lSui{G%Gw+HoIm~=4zT`0TwD^+4%-`Zm4l}QdFFDM7FTUh3^T7C$ z!^{ukOAa${j4wINJTqSEF!RiKsl&`O@f4&c(}vNZ{y((Grx_8 zJIs7Ip6@X8PZhcRb9zI-c?{^YBYQxKNa5ejaanwlkmKs_ojr%;)1x z&vxeX@vMiL|L<{YF2lOOPMfrf?W`Ak{8r0g))Bscak*gD7na|yNigdUcbq+6FzXQ? zUHM`3hjog6EuRc#{o>;8LxW>oW1I7XS?~BUZ5+({$fd8o(uV%9KJw6&>pcLoKJw_f zuRa8`p3?F0y&i^HXL-NfkYLtjx^A}Yc($`Hb7qrSv7L39CS(2+%sS5Aqt}iytnaMb zs7)~IL9;vV9?W{s*{8J+WIXm~0b+`5tJH~d_l_EVAcWG zJ@w9D)(5Ar_ee17iQ^9ZAei;Ut*5*i%zEOOd!Gwt{c+XKp9QlnIr;Q&gIUL%aM~}y ztYhvm|4+fJW1jb)nZc}kUi|Tw!K{b=w&=&fte-C2XmT*?ryCqMC7AWo{hPlN%zEo; z$G;NHI_zUxWoCVL*^4K|cGhhNZT4C)>$&^v_+~KcyenS+ZZPY=1AfctP2w4D+&1@tIESm&XcJ|K zf7t$z+-KqJm)c$Zvfv4km8osuL~@CT?W@%v7LCW?>xqo`;<7YvzlZkzU!*ZGZXi< z#eyxg|i-4;x|T=$j61`}U* zO5eMJiM#9d%H6@l>5X0D-eBVN#&plyiPKwRKyH(`zT*zMJ<1U8w^plv2NNII>2D)~ zi4Xj4!`vU@1Gl_#bZjS{@SKH*2NP$wS^M07;tzX$I5f5sm$>5FnTc0yym>A|9Ak@V znTc;4I3u@1+~WhgjEuU(L!R?--Y;>IjUUVVC4O>+=ku`>Z@J_Tw?=v5EnA(NkBfNA zl^4jzPJHH!-s7SSahqS=^KdY6o-fXNGMG5e!QVfYw|kuDz}HhSaiPmD{B$t!qB}1B zOfd1K2Q2w)F!80wbjW3hFSRXlo5Z7bnULEgPPN@JxlQ6)N2U9tE^(~~G=4CcxYot` z=e`jKd&MR9#dhLjr}odsLfq`_jWQEY`^c;JL>c02Pxvh}@wYeh$YqGjedgHQ4)MCJ zZ_4{6j`x-34@6z!d!Lw;`#{|9;S+Knh!gJraV^RaCp@fUJ{IDHZlYe-4axn49ohQ5;Onma9_rDlSJoDpMy&6oM^Wg`-7EE09b8EaFOkDJs zO>-IIqIdu7mDo-k^^OO<6ij^e;ZMB~Og#1?eVz&?9($8!xo^Z{@AcAiv7PwsTQ|=A zC$4*;mQTcX;=MOM=J8V0 z9pe8t{5-cqUcfFJ=lzmL(6YK_0;Z%jI)K-oZUTp2gr+ z`5GfHqx*`JqMzhtwCR+uEAld~efEvmP9DdHJG>oCe#fFm=W!q(;3&ip8t{E-#9yow z@NR4;|KL=bkIxakYbi8-~730&c7@u|;A3TFJ zo_Gmqobebc&P%)EytLDK!K+B;5pN@%UwoH}>!Dq7J+#yHfFF~tAN-hfUE#;1>kU69 zU5EHF>H5TvN!M-oG3k1CKPFx0_%Z4F$B#+(h2Jmjbid#sRoq`yaer01zwn&W{fHNp z?o+?7tKz<{iu=0KeT~G^;+R`EQkiswnC=LsHLdj8A8oGn4X9JoUHVm#79iePkhAmT*XIB&s%)N^c==VOwVV0#Prh*<|KfkA_ci`^dXM9Or}sPlcY5#Rf2Z#O{O|Ogfd8Go zAN;$b(su>^clzGI|4!c__}}UK1kb+Wd!{PBXDWTq;PI#LAH4tcU4&O)@f}qa-%*vm zqwp5gcNd<6`X0lJu=swfito2d-*5iCSLu5X4@7+j`gdbhd^c9bcVngRMtmFfor!Ow zzCZoDw9U$oK%i{aLD!%_KegET$ss9DMGW8$f{~cBF-%%C+9hLq&@Z!{e zivPb<`hUS!wD{ktivOKT|2z1N>i-D8QT;dJH>&?B{6_Vkh2NHiMDQT_M%|DfrA5RcU2|Iv#7N7Mf!o~rua#A{Xmp?I?v|E*U1x0?Q2 z@p9FFE*`J?|Hb>Y_+Pf-f7!Y>{4e7ntN&{}XZ7EWA8zrVZpDAP=|3HxT>aPMldJ!I zd~!7pfKRUG2k^<&ya7JBnoqzdSMv<`r3LU<)> zz6c-ZVt&br`6bi*68_GbkHX(s^HlgdYyJv^?6j&JgU#Hn&wyWCD**` z5$;Q_`B-YrYx}_hNqAiurBR{5GENnh(bdUi0L5#254GR?MrL=GF0<*E~Gl^qQad z`Ftzp^R1ZAH_hk!{J&}b-`539>jJ)BU|KKmbp+Eog0C-_))#!;!L;t+>k+2)2w$f# ztyB2=g=zi5*ELM*8ou6PTJP}n5i8b5tXLm0t&jM6ifKK?*I7*KEWR#d#k!0Y>oTTw z8DGaSt>gImj%j_z*MqEB53*uC$h02h>qn;bBVSiCttshAtEMMm`t#kSMmudaW*TqchV!mExS}*f;G}AhoudkWb*L>a0wC?8Xai;Y+U#Iiu zc3!9Rbv-NA^{iOeGp+0SI-qGC(ANh|>w~_YXvKP>73+zn^+aEPG_61Sx}<4c($_Jq zSjV(t9n-Xq>Fb`Rbx&UpHLZvG`l%J`r&g?=n$}N!z16hd>g%v}TEjZ5ug{v+XMNq) zv~KI`xu*48U*|Qg^ZNR)Y5mvNg-z?izFurvFZOk0(>k)RFPqkveLdQW^=K>BqfP74 zzJ6_5zxH)))4H~=gIloIGY{=wrSOmPt&M`1-Ag%xoWrZ@_ZyD-IFcszzF9>e1|tcc&R zB7VaZzv1y7rg#sJ12M&cc-)8;aU)j5jhNy_JkG=vXX5cEruY+&SFxl17q4PPyoxDa z#p7E{@hu+rVv2k5co|-FjG93$BCKZ#5{h?6hG#1Wu~|?k2f>Ln|U0XDGtr!)~twIvm$QI z6u0JaZl*XlkAE}8zj?fz74dRb#LJoDIkJGavPS1)sJyV>X$Mu=w z`aIsx6z}KpfmXx^S`i;;iVyU7LQ_1U#~GU93_bqP6o2S(iKe(jk5@FsE6#eluPKhv z;~P!!jUM-CihJ~UNK-td$4Q#vBt5^(6hGWkJmND>v|loDUR3U zdrk4Z9`|dC`}H_sE8>K$h!Zx&342_zDX!S#jZN{!9-nMQe6khs$)@;Zk7qW;Gkct~ zDbCsBqOFLFwjwUt6c_Dr)TTIUkFPexS9?6R74g_s#ABP{u|0m<6u<3p-KMy1kM}mk zdwU$XDGuD@!%gww9ye}^8~1o}Q#`rHnVaIwJ^tJjf9`SVrnq#ES2xA0dwjbU@$FW` zx0~YIJs#c^5ASjErZ{bpL5zlXm=lA%3 zQ~bZ@1(@;zJdePNJOV572uyhdo_Ao%JMjE6Q$B*{DOf#Eq2*9h{(|QTqtTA?)M#J%YwTBfZS=FqgR>$J&XfnoaVc+( z<5fN#<5T3{S&@Hd%D-bgm9NJ*E02%!Qsn(vk@siH`{O(+PmuGg{6VgVBHz%8d_z;d zA=i)c6S=OGx5)LTd`7NABxi6G=$^D{yOzy8D zf77*UFNpja&o49OZ*o5>-;?`Pd7#|aMc$|td84MhQJw?JGv)c9{8OGMMZT&P`KqRT zRh~b}Z{@k9yjPxMMV_n`d9tQFS)O~!tL1s9d|RHA%ERUPsr+1?tIFHud8>S0p2N!X z_53nZ{x8q%dS0+U&y_FCb6$DGycdeRV=MBGO?k(>N0g_``$hT7ypM`}XDjlZP5I8e zzmy-%drf)Mya$UsYb)}sO?lS5H`3_N@JKrbDf9HFq$d|VwU*422&-ah= z>-jEH-aX$@MV`JDdHSY2eZISt*U$Hu^8NXKEA#=Z&<8N-1Ms~kJpsN0r8B^H<1_!$ zC9p!5z`s3ij{A=9Oz9Z#{V9C|zDuQh!1t>35crOjP6FSz(of*KSGo#(4@+->?_}vP z@ck@(2EMDM+rW2tq4Qvc&Vxzkf$w(dLhwB=y$HVl3w;SI^d(IC68tYnkAnXQ=~VFF zQRrG&p=;su_G4pw_)n1z2LCV8$KZdb(9^I&Ps8Waa$Ww9q`$#`lXN-wpORh&|5?)U z;Qved9{iU{_k;g6>4EScC!G-f@1!5Xf1h+k_#c$s2>*|TK8Y3jBqn_l{x_v(!hfiA zPWW#vbWyC(MKS53@SiIk75;yvufqRwp~qr{9*aqjh5u{mxA5OBT^Ih-3mq6MbYM(6 zF#Oj`H-`Ux>B%q;Ae|ZJ2c$p4yn%FSm`{*i4f71rv0?r}`ZmlM3hCi6k0G5L z<~<5s9V>KoOu9PElSqe$`IFll^m&+XDfE1-(DO0r`7l2t{U7FSqzlA6PoX1Zg^rL( zM~HbL=?*bpBt0VLmkRwNEA)#@`bEq~N$-exD(N6GebM_^0B&i}||$=|Nec2W8TOVt!BhQOx^ESBiPULWjx< z9V(L!74wSHtzy1WdREL&7W!9K=wJC-=L^v{<};<2#XP5Uw3rtybhoU~-7@KJF^?*p zF6LLI-^IMEbiJ65mEITgw9)}%{#N>6%oiXNzr9Z~Jv2@9pXD)Qi ztk5wt>6kGuE!{KbtEGp={C1(AW`%y5Nk5JGaOtfvPc9uc=G6<`HY;@7OuB8%!%OFl z`FZKTF`r-P#aW>jXVQyf{$KiXtP4nYj`afR(XoyoojTSRq+iFngLLg!kC5IS>lD(# zWBo$F=?gBE3G=S)}8~x=f+_XNB&cN%xO+9O(qI zz9aoW)`JSYK`ZnIO?rc@A4#8(btUN*vJO?~99p4sXwo@k-AcNMtY=9tk##QVD6;+~ zeMQ#Aq`Sy^ne-T0N0Uw?>ub_)WZmtABj1nvi}g6^J+e+G9Z1&o3f)L6bR$i=k*ots zXOi_n=})qrSm;$+p;u|rt7QH09}W7JtV{mVpnJ(WW}%a5g-)hPCzEwg>1whbD!onC zPYZocEA%-{`kbt{O3#yZ*v_?2VjNhXmHsE|w$cS(PbYsTF#sCcRVEuceR5y0&yvSqCq4R;|!kHR-IfZZ2I`*3+fe z%KCeu?`nmSvW_pESl0auU0Ex1Wlg%W#0f};miPhb(-K!8-CE)eq-RSU zf^=?)PmumCaSPJLC7wZgxx_h0N0;~q>FW{~A>Cc#C<>ikD|C9@Gwb^}*Th{&*Ozz< z>HQMFQRo9(p$}~TY|sZL-a~rA#DPd>n7ENbm)HtjVv{a0aVF9+CjLbF#>A@>ddODj zA)EA&iEoj9GI1}`RVE%rddtMgNQasD8R;_>$?8Mhezn!={>ADlASLnc7p#yKyfhVp{y79#ONl%{mz(RlC3jKML{yg!7 z(yJ%VP&)R+A4=bzxJ2pR6R#*eeBv0TlTUo3^z(^(l&(JUkkZ>HPEtDj#7|0}pLokc z&%Y}4{444C6Q3#lf8sXf3qYJ_;UiELJ_40|1c(cj?*Q?l@*^O=wD2#e3jcyi{sqLN z%I|;HUPs=~LWl5Y!f`0{xnK41PX#Pb(^F;(FgQ^_xe_<#A! zkQX4|8S)4UpPH)hsj1{sL*9XWZOBKE-wk;R^1&g0LH;=8HOM!Id)f?75O5O&mzAh@?Q#nrK<2(s^qUkzKr~s$fJ3;!KaD* z8u>SQepx&DIz>K?{GL2dM?O&G@5mpDydL>Rk?$ivDe{2iGev%o{HMq#D*US26@FFi z>5B2mqnaQ78W`oS0U)HYm+t~-o z^UK;Ta9L*ZtxjDhGkI8hj?I2X2$p0+!bRoUSo1-^V@1;m-r#RXWqSXOs&hRnP;pps&@FH zneBsNwQl1xzxC7L+HCtV%Ab1n&9y1-WbStIfZE3We~RtjeAcga*a<%epZ42LwZHB7 zOYo|9-Bf$9)vWsVgBF`zFTc!3nQ3R+d-C@c?e{xnPLyH4XEpgPnEuSTCNuqP_H}0Z ze}0SXpTcn+(=zkxgYT?wpU~vqdinEr8CP%Tt&JY4x4+xHSz0P zAFHYVH=g%c{kYh!3sS2O544BrSjfR zrFOjiO6~i8EA7|&Q>j1R&r1FD{#WY1A6KRG#daMp+Xk_5S#ESnsD_hxPvZbyz+}N+ilm2L&>8Hk@{_DJKa`(^GZzE^Kb$ffeU#m$EX5Qz(`Ru-#nMZ#! zzrDWyS5fBR;}^938~j|B8nckKKKJX`zR2wh+vS^l6TH`{?iK!9=B6JmVyC_JZEPRc zcu`yOk(t44zkTR;_3|fn$^XB!(|7lLFVp^vh4TH&exDnanf~m&PQI7vXXh(2)BoL` z%*=7E{CehbYyD8){`3RiRx028;;$;Tb9dh_Dz(2;v(GB+_n^h5SL)A%%coW9=gv2O zT&e#*?D=t}<6^sxm+~41+R^yXzQ&FHYCP$W#+iO<{OP~W3(t+tH{BSy%sfy2wrggd zGdCXAH@5TqS#;|4!915%e5Fq?&#T+_z9yLG*zU*m3g&s(e}gN7c^-~UJ%V{2Zn)Vc z_3fSZ&H62r?{?NXv7L5WE^vAwa@cP`{g;N{_uQLKY8w{|2z+i zd=fHE!%z<4J!s&h%5`PycmZI4+$po+sMQb4KNP{-_bTghYft>^lwiMqYo8vUHJALpt~EL8nAq<3du`X=hX?y}pf+vA zgM$6}P+NGL4#EE1s5M!4xBB*Fo9|FBzxkH!f@$ZKr#26!{UyI`9n5|={e0bE`g8E> zt%B)i+t*ePrvID&wrViPb<+YR8|qN$vY{IBCEBd`{|*Kj)MB z>Cf||{`+%2>A2Xgy%yr5s;lero*be{sGl zoiCpM+Rl4H<#}JI9o{2qpZAOQ%X>%t;eDij@}5%vd4K7+*skNHyvBicG(NPiabv$4 zPx_;Ark@&r`mggc#n*Y?zUk=-t*Ucx?rH0Pl6kZ9uChB`c_y|Wxl1pz{U-!JIA3pD z@9^h?uOHUi`n~r;@RDm@ZNEG>F?iGNSKF-%ObTA+(W~v|GhPe++Sq>=4JKvS9+y~^=sJguzh;e`*Yz}-A(-*bYFK<|DPM$y?$J5 z*YQ$b<3KwapJ=~f+}N+ilm2L&>8Hk@{_DJOTvO&765nYY@2$-$;|lNb!TSA zZT(G$MtR0_kx7{u=OcR$i|w4Rs}3C=%=v1+)reru*R;QltZ(lzJ2T~Xm@+E1)6PF` zxh0tPpE+uDF#8?uF@IcF^k?Pnnd#^DA7!ThtGCQCIULvb4Y55OueLJ|D$n?+9mY-V zGoIQn^Mg8Y|>A2Xg{sJS ze>BeYQ{zwnbzV3woi9I+_3eIs>*f8t*W2;yq29h{ri2`lII|{nYc2{uj@~q~{^W ztL=<~$}>J{hjCN;jHjN5jI;W~_^Y3s7xka>rQ>3|j+gQp2inp2MEecTL-wojq(2&G z`l<1!|2i*xN9li=?<@V6@!h5WHNMC6AIEo^{_psH(|;e|b^0IV`%wRhd>`unk?+Ie zzp|$PP0H&(ly>xgO8fe6Wxx8Lr9b-5rJwr$rT@kMa!vosd|zoh-(4!t_n6w@J5BBL z{igl$U8nx=y{CTi9jN~EeW>GNyN;Lg8VB0Z_|U$_js0po>5s;lero*bzs}1>U*A+) zW}6%0y>RbwH`G4aH}jJ}Tw9yaD|53)de=VxBJ-V-d)7`k&0{P5J+l42SJZY`>c-#$ z+h0~2_o+WO)$;w?!OQIy+pn7Tc5T?}nb-Z* zz1pW{|DEyYPpR#_O7`fPc-m{V->%y$%5VGCnIJx%Hv<|`lxNlNz$=k9w z5Zm`WyZQI^_HTON$NGLRef;Nof12$utEPVT-Eelj{~vXk zT|X|i>v$=zaiATI5AAE**ssQu{%D-(r^cWD>%91JRk!coF^<=_R|i~>*~?eUev{eT zsSdxpVca(VzB*uB9yi}_wfIkY+`KF32OoDxj`x4$+s$2I+d z%zhs0+x`63%lmn+x8v7Cy?wt<>ihNUr`{jG4lDK3ueVD5_v^5JTx{3zQeNXgI~pI_ z*SN7?jVJxlIMYv!KmFHv@#jW0WBAwc&*Jx8W#4A@`>}fL?Qdec->20+N6ZZN`?qS> z`TJnMudA`2{}}A|d$q)?zXbbpph`{V1pD)$I_Qz?q2teus_&)QLx=6J?7C2lGv)V~ zFMILO&WM|{M-S~ExOAf^!+savKl}U8p9MN*-yiz9+wx098T!BY)tNc2d+yKd&&m3B ze}2}>`*XG4jz4ef?fY}MzF&Vn*Zbqo?Rr1`IbZL;Kj-Vm#daMpmGJZrMx+| zcUnB(N0eW9<+JMT{CL_$!L+~B-@6C1-koeeq1&6$NO1RKfV7o_1}-HRvcGN$4hyQ z1MO&hXkX*Tel?!-N8?OCHU55F<8@w^`_FytR{!y~IIfqQPieRO6Pc%*~34?+jk`%68SkU*8qH^j*7D&Bxvoyulg!RIP5j zFL?60-?lyfjogm&!(#8lc=f@{*Hqrysi_@rzozzmzcuaG`%_bYyq`7o)B8VO{rBS< zujATajls1~K6p9$v-%o`)H<*DaqxdvKc%+*=N|ecOQA<8QqaJoUZ7wY{cJ4L;zWVYQ7Pcr*B@B}UX9x?oE1 zVIL2#z1rrr%-amB4Vr&)u=l4@f4rZS`gzzk!zz{Wx|QmBo0Z!1eO20*_n}fByl<8I z=6$ZzXFrxo$KuCW=@|XkD;>L!Nu@F2Jg&5Ozj$VHevf%{NHFJp&*8TOb3OFx?(3=k zjmLE|-tG?O`ssZ8eZgE;v&N4L=6c)z&vqpB2pU?)1X;!HmPGLlz5We40$THhfPQxAv=?`5^mZ zJRkE|1ekH2`N87tf_?mFe!5>U*NpnZwWNOfIjX4)=T~((?`o6lLHpu5Q6IQ|)Hkjx z^_lBU$HH}}W90hOv2)#OOt^P+j<}~Zo?QPLXYLD)Klh8y3-^)E7x$OWBln%oFZZL) zJNNGkzupt)j{92t){7HsFZIt}cq`xXYHi$%rQ+It>f))jRUgS-drxifQSHg^TEzAf z&ikTv(xv&maPPX`*N#7O`Plx`LUU>_UXuA9|A)Hsi(F>E5sRj!hb3_ z??x|mO=sTPJ^DHIgj3VMhAbWY^Fs%w!OJyk$F;p>)iph~*Q2q0`XSxYGq>jZvE^Eq zq@Oz98QV|pcS)L&@;zR=L1>e@9Yr4F(uk(5P z@4R<$dal{y!Hf34I352>=AF(uGwr_pl-NG!$aB&mM@$ah`K$BOCOhSM@-~ewOpRMS z7u#R^Zc!W7HJ|sJ1}$jwy^^no*6rq0pC6mAlYgz}-^^QNK4|wZs*XG5GPl3^VfAyr ze7$YG{M2f#ZS!^bM%!1biS6_CIs2@M)!q}9i0i7&m(N#|-dHSnooAn|ZtIu71J7Fi znX1bg`CHNZZ|c7vm+82?&!#^6v6zm3PT zp6S~2YrbCI?}bYDf?vaxu3^8nD_z@u%~!hS{a!HL3x1E7?h(ItO!v--*AJ;$?mRHA zf$LVer~3YZcY??DytSHsO1?KYdS_I1)CPGy<*;g4bx^uqOV&G>V#x^A`Wg8jKyO?@bTL;7>Cx@zz>vE840 z)mE?P?@WL0Rc%hp?9aXGvV$`FbIb(W?x`sdZs+KF|Z!>@HRbMTdzq|aoSAF{CzoV`{_o_J~#svFwuj+JWUZ?QqUbXgt zBV)Ti_o`P886NDK&pma+fd+o%Q_r`Ya z!L#%pIUwR4Zp?9aX0o)=~I=U(lxA2R!MuXg$ixvoF= zY6t(EuS0+C)fPTGU!VTmt3AE>4bdNe?$s9D;KpEo?$vJGvtO`3_iC*#&vS!3x7B~1 z=Q=K))#@|Pa2*TJb{!+{0*wjp2#po*Ae{@|Svq&TQ#7``Yc%G(gLE!=1vyc2b8@SfH6#yeEk67N=BW4v>9?eVTxdAoZ)6W1cuw$r8#l66Uz`zq+EI;cu?tQOX3TdwE8m-p=cS)# zW}N#S&_BvB{%0POne%ena+x3g=rUX7&0K!YTE3qCeC7csUTzsb%$orw7xA77yoZgSw4>$k)|r-sT$b=J_}FwOi+gIXCaa%3bp} z8+|)<>7}9_`uyC2&4W3{BmH}k^TM$Yx-hekThevt3Dq{lE#5HbzXc7lg16! zc+v-*N9t<)X;bHged&DB2c1Xyrt?dmb>2BfT_+s7t{=uw*B;}eYm#x(_2$=M(sjr< z>-zM2Kec%z-y?qSrzg+K^XGo=r&gXv&H3_sKW*PB&*}NSpVDo44&3kkv_zwP&G@~a z);;8(QQq(UbnvC;1^d09KI_~i*zf)H_16~%`@NsO>z409zxUH!&*Xd4@BQ@V$9Znw z@BOsXQXQkb-}~wLr49)8dp}*YNQYp*_tWD`?HTO%e!9Eu`oVthr41s( z+2Z$pdiBTr%<+3a4e7UKl=pi-4eZx8*zf(c+SF}={oYUa?Yv{K-}~w1aqWYZ!*aop z^(y7Il+3uP46HmC%D9hG*r4y-&KSou3J{yXILz{>ZD?G1TAu=0aoNkH*ctHM@(J!u8Q0uSao6LYQgRW7P(rmdx1r+ z7Cf)(S#{};>cXm9_8ujShSFPzbX$a zuM^h&4lCCfRt|E>>{n%A!m10aZdr!9+85jZYB|oz zcc!1pgNBtK4J&UNRz5YXJZo6_*Rb-kVdZPX%HxKW-wkU_;Icnr#?8Gx|1cL@dD*n% zexQ-B4XZ9(mQn6D+r{ilWnkrWQ%1~o_YeKu{O+%yuFt8Q6_y4n}p|7yAo(r}=k(sqEQ`2b4`0+vPuEbRzbni8@2ST$Yg@1>42!OJ!i`R8U6D zcK1a7UCoNJ9Wiy?H#u}IVAX}C69T&rb?Ah^?n50qA@IDeXVs-Ystc=b*?;)Y=xOK} z*{{mO(%*n}zr)gmfu$8wGW%5-Sh_KkabNP#je*^lJal7Vl`pxh3#%@yx@8&aYF}*M z`Y)zMBV8K$DZLt4IySKMZD8r%z|zBkrIQ11*`S{TOIHV$-VQ7s9#~@nm;DhlZtltc zhnhLk&!HXnZ4X@?SaspDj5K!GE@odU150~{GGey7&-?G{@RaR{qwbAgg;o!&y0Em5 z;MdwVHnfl6sk0Uf?IUf2ac{O)%PN+@Wb`g~6%|mt~|I z#&$9LQW;o!Vw4fHeXnnt{;sxI*^ZdHGZtPd^v7V;g{9{PumAaKq2~sF*?-m0bA#t~ zJ*zJLQC(Pd%l^ZEM)yp|$bMBGmQEV1`yG~cA1qD3lG(4yz|!}l%mO_&34K5K{slJ+ zeLq;`OD^lestc=bS%$jW7u)}8nt{>}q@U6igrzqKONS7aJ|QgKLRfl+uyhV#=^w(< zMTDi7808yu6ydTzV#e*-rfdD7wxM(mY3H+cYlZ$Hth#Vn=DG$gM7E3Bm&(A>NTiII z?QJ`+{kwXJWjkW(?s)jxp{WR~E-Z~o`0IgNhejpbz3o<^Q3=oMdRATfqq?x_mi>qS zjFzL0k^QPXEbT{F_d6^-Qdl~rC9_|Zfu&hWndR@^B{WOnm$%t1hg% zWf|&fUu^%Y>7Yszm3~Sq6_$o7ENxX-nyaw1SYc_j!qRSqrRfSw>lKy;EUYns%l?QN zxA8Bx`$N4}X}8kODXUeX=?beZT$Yi(E8E5FOJ!i`zEVca_8G6)?`pu7?TD#+`fV0E zv9RjG(%psszV6 zTOQu-vwwuPJgo91mvv#)g;lpKLtX8Q?SD1BdTH0ku{UVi!_vBkrGXDi8y}WtJ}fPL zSQ`7VwD)0Y^25^VhczZ}*&i|ER@ILALtTAo?9B;}e+2mGiD!jB0z9wlS#{};>cXm9 z_8 z!m10aZdr!9+85jZY91W&44?m0n66|mfr^~9}rmnAh3KxVEKu_@)?2UKLTq^ z;Icnr#_hUMXaAvBhXs%yhYe9W?w1;%X5S>Vzw{a|NP(eA1T`r zQ}@tj=Z8lLth%r~U*OvhzBD{v;193ABs^c>d0o${OMg@sR^77y@SpKU(J``Lm51e} z0_%Q<%yuFt8Q6_y4n}p|7yNM z@))9@@*aZaNd(KQ2$qKtEN>%No=32}kYITv!SYUm<*5W~OyIIVV#cli!k7M`|B<|q zXs6%lmxf0Yth#VnMt(_b7qc&wf#st_88O?}-?PW>dMcIeh^f2AFWtj;307TLK34Ej zZLbO+EBMzldWMe`Jg@6nb?J}l!m3;LAO16bPdY~StMah?pKVRouvw(P%67!m-LikL@REa77nV04eBUqSjE9|$k^QPXEYCYw_d6^fMp*ugC9_|Zf#uamnbqgJA-o#lb|2ml zUX8HImt59`RToy>vJ7>#FSh^H{2%27Nk8Qg3ClYYmZu~vuSr-Ql(4)hVR=@<^0I{G zaS6-&64sc&Wq-ts+XgeQ{X?Hhc~;WSrd|4kmnE#aa9KvamTVWZFO`AicS#vB+t-|M z{qK5TmhFhCd-NgKhd(B)y0H94;mZ!|7k;DgP1oNPexvZbu4mPyKdK9>ZrOkM&-ilc z7}>AN!}9Tjb-%;%mWAaxTQd7q8Cd?al-YK@{^36h|LQ)x_|L*BUvgPDj-{b4th!|x z>S|w6<}c=HD}P)1Dc@UIez>rFa$))B!t&LH<+lsVhZmMVFD&0)Sbn~+e174wKVrsh z=1n*Lq4%zQcxmUU);EPeFRZ$7Sw>#HY!|aHm4W5qOBr!&zrFwO`uUdah^hPYrv1b7 zH`-~a3(G?pe&@07Up$yOKdRATfqq?x_mi>qSjMuP^k^QPXEN^01_d6`V zY*;?pC9_|Zf#s=9nIWA9g{L+=a7Xu&c28|s!m10aZdr!9+85jZYChfa?53ac z@`mN{4a@r*mM1tYuW(o%;;_8MVR??j@*;=jQ4VWN;Icnr#%=L^2L7R+xV*(_=fQ6W zhUYk}x^P)W{^M*HvoDp2{WkcLM>~JQqr7ZKOx>sdHaL9D;cJEt4u5l4zVPt1j|>Z6 zc=*AehlVdaJg@6nb?K+-!m3;LAO17`>GEM`zbX&QZynbC4lmYexE<@h+VHa{kFZgT z&&}*tW#IdsA7Y!jr#0no96r>p@0|G`U5D9ATV+=Hvi-6yth%u3mSw1`eX)Id`yuxB zm)Azl;Kwfwwnw+?6Z}Ny!FJE6%v&}aY|E^W^La0sILM|B$b8K3L3a0=S<7OfUW4q{ zdo#~+UU=u6^Si^SK{o&7%v((!WNi=6`M<-KA8aeVo%uo6``o`n))NrZPnCgH7gn3F z_64gCu=)n8&#;aK)-l35c35Kqm;DhlZVN0u#CG^5_xZ}lhS(|HaxQc43x`^#-{xl8 zQ5jfuVU>s5cN%7|U*0dS0Wteh8Mt$c5%&HX1EP$W?W^`5Zex4o-0en-4!8Yg<$UV0 z9Wnb-8CZ4UtNuO8ns&M-+W&dxNE-@f+6_ILUYvu^uk9e{^g4YTv_ z$UOP!q1JxI9x*0&oHx{#yD{@_+YPn*SG+8?ud>Qe8#5+z(`AO*&TTG_?Z>wqYR^2E z`IQ}p+DU)EB5&_9)UJ3d^N8n%+UNtXjO`b#KgsVkNBdlYGH72n7Rx;!E`Rl{%oCAAC|F^nsxSjZV<|{gmu(fx&Dz=NMt1__a z!eyE5+mEzuYFEX%7PBvvfsg##E%xr_y`zkn?M?fPvX6%Liv9NaZls;DdgihnG5b{+ zSaspflSkXF?JtS;8?_p3yZt-!swduJ8-JU5Ue~kg(jV1@Rk!Rvyv_Hc?8zCuqtAQ3 zG|Da-lQkU5`&Y+E-&7t}d06G)%O;Pqj(tvv{Tcb^*k+Rr0xl_fH(eA#|k7gk+Zb;~l;)xOyN{71v>=2oZ0v2W33xZN-#bE{Uv zt+YZY*15+;=ZXfP=er*5nli~Ko;{Te9>8HxTstc=4So?z22UvZB z)n{180_zxI9XqTsfz`K?8MjVDMz}V}1<~idju~lJ{+juoO-9*PI~_Ve$zIXSXi`lQr!0V3~VN+f_ zAjv_cA zgL`!!Zs+fRQ1CT-47V+h$a)%2t~1&VY zC+qOg{yvkAi0$lm>D#hq2>qG=n4@C5nB!F$Sao6gMw_tq1*;FR`ljvlS>-tvSjPzK z*kO$cT=qw-ab9EJtSQ7e_gbz~^q=#x!+moz?WhdQIifDC@-WxQl>Ls0?PB(&GVq;? zkF_~tj*Bv4wtsT!7~Aj8W1|nfA02HMPsGb&l=j{i|bSUn&o)Jgo9C z&!}PNY#n{(IWzpOt>$9(t1>Xp)h}DMi!wY9H&~%Xv1w zt9`MZcghc6wu|HCowC8JS@Vi_O0QQfw)0LoVS3h+;hl2hB3UDgcgpB>wvRHrQxU>zf@V}~^+u=-XqRCsL+57dstl~Uu*$={NA6p8 zw>Z~g_N6i~*I19g?UApO24*|&m!sS49(~~baz(G*g3ETq>`P@})rEP#yxw?=XrK3B zx0SXG=KZ+zd~;vJl-IRQA5<4sU08Kt^&jTmnRb2FKH{G0xa8i^XWjc{dG@99u*$hj%P*=RSb};`? z|M+E{VE&65dr6#r1K_u3%J@W0t%m8>x(rk^SUt1hfIVeJc6 zA7J$jR-a-1JvkOw#~9lijvdyRz-52Lj2r*azrB$A%zyM^`?ii_;lF#Ov2!!+s0^&S zu*$>yH*NYu>*$-9eW?u0H`OJ>H;yu5w(~#L{_U*I#sAd#du1-$5wkCqfmIjge`#e@fT+Dt|24=2o(>{wu8RokV*k{pT=E3IQXpvx*FWWEc z!m10aZdr!9+85iIGaPnq*8OA7@VIju$FVbK_}Z0=2Qz0lar6?w%o)D(T$5nt49}Uq zWH57vtIcj2%$(u9zb+NboZ;EimJVjl@Q}Nj1v6*Z^6$$8GrxNFq`8@Xstl~Uu-b&R zFIatm)i+puhIK5kjuFv~pQ`lGtA>X!Y7nHzcgz2&0M%$e+ez~6$)`&Y+E-&7t} zd06FP)?6lDJ*9$KH+grh*XCmOt1>WaL#KWAZj@nt=jbip4rblwkt$6IC}AJ!8Gd_6bQPnCgH z7iQg!Heu}xRv%#2@8}z>KEpZ|SjPzK*kO$ctiF}ZxUo)p?lV8caj{Oi$Bx;Dh&9$J z$IZ>uRT)@yVU>qj7u)LKAEVD=_N6i~bLPwJ_H&dGvz_&_%{R$f<*b)I)HC;?Y)8z# zR0dXEnDsK-Y+|&}x?by-Uk+xy@AkDO2hZzzR$cm|y0Ge&{fAi#*kZNp>A)Jnw!h4Y z@htCO9V2~Hd06FPm4}HjxOI1C4!Rj-tV}W&yu#O$pn80O!#Ecs;Ma%q@`%GNW^bNB| zGciRi8_mtMqcX7S!YU6F2QqWa({YSq_N6i~YsBr}eJ09?*-m`Oc?;(K5+BljVD4Ml zj+lL^46M2^@gW_49Te>k^*ELdYD0sGZ&|JFh~Rl$&#Fs*R2Np=vi~q^-_MQAz8kEG zpK)^bQz-9W9V2~Hd06FPm4}I`8-2-{(NE&yX5D?tT+Dt|1}64z&I8?|4Dox99CcwZ zaeWs)aBi^5m+hBzVbz6Iw=6?l?ThWiKz4fm(zq9hf&BNZ9>K&wwl()f^D@LhHtyOp zm>9^#?$5p_#6Vv3->YLgF_7nszc!c{$mVBW7fcM~=O14mObp~cO|pLqF_721mzj9c z^$)o*%82Qw%D}1%t4&z@g4G9DeS_6!SjPhE7-1bdtTBPh{)ib9;$U|ek^4*>?9+WR z6GQt>tGStWR0dXESmj~j9v?lkZ=7o}`%)R0n5f}j<}zZo6A!t~K6yNehn(FibJ>oV zeW?trx-jvOE$2Ht`as;~A`f&5CZ2QltP_Igbv>&t{ZU<5b<6(4#Col9bH6z6#DF#0 zGy9&D_pgqTzNtK{^03Oo#E@4{E+73Q4!rlp&E{hEt1@uJx{vhy1FuWG`q+Ke3?`2K z-2+w$R{661vM#K;uR6!ZWT<-{};zr!NmMO zF>bqHV*Vd~e5YVy{y#Wr*I;7)C-vVWn3(^LZT1c(=KuSxIs_B*f8-VW29qB#X|?_4 zV*05vuZ%N^x^P*BIRDNI?;Yn_%)V3xCIo`ZSF8Ok0CM7D^5Bn z`d{9^I!5}Y^03OoDi4!0b?ujzwS&ofdVlS+=3@4%GBCMa^B;Lzlp#NB=r%)w$=jOp z;B~<&U$$S?g;f_;-LedIwJ)}ljo< z|1l+)9Jkr)zZXo7+XhWO2`0zwjE}wuCdcjVp5FwM$k{LJh9DB9N{U^_Hk=o4YKRJ@s z+h5Ja)KwW+bzzl<$!k09iqGO)i`kdTz~sFAa{aU@BW64KZr?SX7W*aN?fql&xhUHa zvoDo_RTn1T?U~10NBiXE9slz#!Q|`h^!4Gv^SYi@m;R_Oth#0YVRCuiIp*u=GdVtM zw)-Wxynl6!^iAbqm4{UxCP%pA<9j^}ljr+>yCHKi`&Aj3T;@w(eWeZM$wz+Z%Jm+A z$y0vx+*cp^|84$WUD{DySatt@``Q=V$?5(vZ5&>ck<-1+`N8CLU)+6YFge}*T0R*} zPWMMwei%$n_Z?@?7h^?E_ww5{2_~oe`xloBCa3%3w^|01)4kIst%Awv?s4nd!Q{WU zYCAV`yeb2$F03|T?F&{PVD$}FpJ5#ftYd_A?6AfJR^Liy+{o)c<@MF0|K#<*d&i2w zXaYR+%F=T&byWsdU0CH|^0=3NaG|)i#q3LEU~)V!`sK^Elozv|{O)t#{wmH3`P~Cs z{2W}iBc`s(z^V(A-`#byWyizhp`Y1gR$RB_r#Bh%pSiAK%IMmr52_2RF08t6*=KTB zZ@sipj1@VpJy%#MxV(Q=o_(o2tn#qR!)Rixd+MFhe{?OTulLAYOdnJRM!VzZ4wpw6 z^fxYEwQn%G9D{le4_5iI{jx5sy0Ge&WvHutv3)z&Fu9$fCdYI=DHsit_7gh> zqhYe-?DoNEm`pim>tHlYT8v&V7!8w&(^m;b!({iKErQW7`9JpFJKU-w>Dz`Qf(qu0 zI!26`BWJHID(0MXz>GPJ7{-hVR7AyqS(1W^0fd3GSCbqSL@|IOil8DWDws3MS9kUL z?bC-3-tU>~ndg0GzRUTC+n%cG>aOm6R_Imr^2J-Sh}#};k}N(usr*t?L5|E`jQMxPJ_8e?(H&S+R10q@w^x#@|m1Jb0_y9 zwIil4$-vTuuh{YQ@{q$mcKhUA+2P%{oyo`2Z_rrhg{^1l;*WG;>8Ad}FyYlRPYWSn@DApzi3kdJdDvX^*|uYrym?8JJvEV^>+sWym+R+UiR? zlZUGFuPZuBKDD3f!qSDMo64Z8zGx?B*R{_k+G-q;l9nkJQXL5EuwDmjAIu%|>>9cKTh8R{TKlxf(uHLcR$s7ufaM!3pJ9y!))--p9oC${sXt=oio9*DPkq;YCU4szD@=7J z=i9tyael4L4SC83L1sxR7~9$qRx_VUiY@5oWP^U-Bza#Y^3ZX0KERNm8e zTW4}q9yn%8XL3|doVb}YIV#6p+S-{Mm2+O$*qI!a50Bc&nH-gOT^gAjl|w#{Og_&R zD{kU4V*Hd0EL~VOVf6*e2Uxzr@)_1xV2u&h*kR2HocbeX-pEtB;@C~yXY!OTy>^@v za-3egLYylxb|eE!7fxl!OS#RGwH|9ReMtr;XWhhSc6J#t?c}TM^LtzOhkTW%o)hDk z+7Z*QWMJvSDqwlS28fUh`Z0c(q+geJo)NQ&g2M1r#q9Axz91DI+K(6;<+a~lau+mLn4!txpHb`@>I9n>J*nDfAv*^qOKS} zB?C(rmQ7fFxqRUREZ<=H3~MZ~#t3Wdu;v6#{Sh;7L{^p$85!0_^ zVCll-XRi6|9=A^(>7U1RcP78|<$Z283L1sxR89K`>#-yM64`Ah_Y1JDsUPQ2WR2&eS0IYNu|_)F3Fo*wvXD z1WoV0)tMRu+YY_OnHmJQY!jIp1bQKxX9_NZ07FTT8-P^_3kqj(d zIF+I9z|-r*H7}+w$-v|!KX%6ld_9P1ryjwOIrn+L)FXIu`yS4z9kGwAkb$KOQ;%Su z!=7>b)J}?q&(g&o>B7=Y{fEi5zRv5>XL7JNIWGE~?q7`&-y{!9 z9+o^z4VO7xhq#~AVfkucT?3|H$-vZ_S?b3pU50uwtuBdUr;f}THG{le@~Qn)7nUw8 z-Bbo$^+h{1cUr#E-(y70oh3#-?o7>{i)Zw8rsmGyckkm&&7BA4^m3-=&Wba8I#Y9J ziEScNb7!>=9`$x=?%X;(GBtO$-XqFTbLZkkqaErKowRCimlxxwWMJvSvI(m%SU$k= z4VKTa#sX`Mu*ME+PThFyI?FILN zIzbQrFw*%Bs~_~hq~N@;^(^wdKBxOvW5hSf!;*(3 z4^y-3iViQkpVS?D;f`?)n0_S#Q(Nu68M(_)AFbz+alF(`yK73E2g#@QQ(aiPuyj)y zbk!H_)R;SNOr4LH8grv340Wc)+*>RB-I*G5o83FunHqC1o$|ahHRkTRVURO5=1!kC z(3u)@!{3ffjky7fM;U6&O}Q^JHRd{Zigu{S*EdA_V*Hd0EL~VOVf6*e2Uxzr@)_1x zV2u&h*kR2HocbeX-l#Kp=n`?Rs57|OeQ^${QCK=T_&kWQBN3cVn>+cy7rkHV&6T%(!8x@freDdx(uJuv_ha2eUx(Di>oDd`XX@oO z8$7(Kh=e$3rjbZL05gzPEFM@ zvtRbHQ&Y8W**Fi>RNef7e|S4JRU54w<48@_En1BBc512)JYtkHHC4C&W27@RRadBq z?bKA=;^fHGRBf_m)TO5ClUqca)Sqp7N9;?CpOS&43(F>~zF_$P%Qsj)!x{^$F~S-< ztT};Gf5glib#=E~F3uZub@zK?tdE_VyvP0H)dq|m$-vTuB@a_awcQah)?)gS3`~v1 zvFlFq^&qC5`l|i5dfWS@zUtnezvZ0T5!07sVClltS3UUBkK8_WV3&M&sx$RrH@g3Q zXRTr6#rPmySh}!u;nZhpM;>?7JMJenB}d&7{ZIF=?Au?S>@4}zeyR&g7nW`+gRc6bof_f~w|djZ zP7U!TPJP{(8sZnvc+Hs_;?tguYl#}-`@TNT+o>V`@a~bRA%0TJ$kY%YwNGSfh@U?> zGBw0Uj)-=sAwKZuXrFrPYhDri72~I5VCllL39BzyKEUz~md~)p0&9%0#tv&v;M5;6 z^F|%{w>FJyn>z9}E5|iM4f@@;c-QAgj2+3q(uGqQ>V|LnMO@or`jQMxP2s*Y?|$@DpdPVdTa5 zAYE9xuyo_(Y$Fb!R_U%1@f$JnQ>mrQV0dHMUr{(WQY8$9>wm)40-;yF`BO z&WWWT+7<2Be^9!ySLCLv%`DA2ChE>xV@_%Bv!cyGNBmIgF*f!!_uk)1gU^XRi1AZ0 zuykSBgj*MV!Scb|3*TV*3~MZ~#t3Wdu;v6#{Sh;7jel#LJ+sebpPviwTr@l8m?_S! zyDXN?xocVj#*SoQ>B5qSH}2Uy`~HHsr^NIn8Tim0R?0ry_zPc4V%nenX4!1Yl+V21 zb5C9>TWhzO&Z!+SeMttEE_~jPmz19FJ;&{zFt=0bfM#DhuXA$eQr9hJHCV&QYi;9$ zbYbbj(uGr>Z(VhD%g_6{``PH%wX>F2L{9gwj_`geR#(-=hUV+)rF-COE;ClH}ysP z9jElFd$7kOANv9O-c+~R%5nX_aO^>KhkqFNMc)BS)txdo?w2FF-9BvF3yS@?{%-4b z*rnRuM(rkFD|xe1D?4VtR`#vmTJ>xG)H3$MPiOp;3@lw(HevMzn{Vy|yz4DHxNk+f z`&`KTSYVA2*4Saq2`t}I#!s8)T4Ds-Jl7H<*y2(m?kS@y8CbfofF*oiDG402mwsvXs4PSb{TTWh~bnL6MoMjUkF?~q}mM&~IE3$9x6>Jvr6>P#< z!zmZOxo+W)>%!KT>lQNZKfF`_JxiB-JjeY!<-qo(x_?AY_pioCUy_F<4@(}l->975 zJ=lI{^5l2SnSLb$+iz)w-+bil_b}(T6t>^VoZr&B6!Jt1nnS!1lM;eS_t*w-;l9HAYxthczc~>W>&d z?Yg4EH3@9j6&0>YV7n%%aGjGfb|eE!7nVG1e>*D4b&+#w2evg<(cdF6?e_Pj!rvy? z{=QWB+XTyI%Jd}}Sh}$NeaZFr)cy|U{0*hu{yygX4TTrBo~27)(uJi9r#{=>sc5g+ zo~mdMYVW7=^ecH-^04G#yC%=M&WG)~I!~_Kov|qy*zO&2?s1T}>;Ig42iWcla_$}G zx49r)>_``u?)>)E7wvWrmFqss?xAwsf7v}$uKO~(hst%oX7^CJ?&ItpD%bs;-9zQN z@3VWTT=#=^50&da(e9yg-9OqrRId9?OHL{wWVD{=DOxg_pjvXSMsprVadbx3@Ycj7HrRv^5i*{Gd@TLwr6EI&-9SD z=Uq9^%3ymAmh-G^ewz!@#g24g>CSIoebH{u40AnKv}cC7o;TVv!(7iHOCLXw>-nTT zGtBke(w-USdY);|40Ao_v}cC7o`2di!(7ir?U`Y&=cV?{FxPWbd%l|UEEj*oj8`(S zbYaW>&d?YVKzGiTVI8|OT8hV7Yi&U5UPu_GB+ zy0GM7dp4LS&%K>fJFq=N$o0HYOuIcl%z5?*+w;SmXOFOKrc7Uwfu#%E^TS-vOYJ#l z&NEWl?fGZUGg5eA>sh+=C0$s$aO$%?8_D%7#h#hudd8COU&+(27 z*xsAu$$J@Re2@%m?}l>TVIgntcXHkh!S>!K=iSi!HW#Fe9qGc-o!`FtqTSw+<$8~1 z@5pk!U$b{)x!$|kJF;Bw%E@6Bg^%^&)$*cdJkyt$a1|O zw0C5=-W%Hc#GH4R_#zvww?U{M5_iJL>?R{C!yEfR~m*u=` zgJm;i`jQMRUD)22<$6D8@AY!t3DR!w`*Pk1!V6o^(xory!qSCPpY2^hu6GCajv&`N zg>?T)o_-|{OCFXyY-bDt=N4c)ClHcz2+sH*8Q9K31kP+Ae{QoTfwK^>opT7Bg_z&w zf^@MXU0AyF+gD$-+nJD{b0c;pB1G zK{BwN{R^B?MBdKt1Hd{G{YoB|JS=&*wz5~?J1p3~dkV>SRnGVz8Q8w<3VefxynUY) z__hnS@3sQpcFk{dLAuzHE-c;o?W-@^?HjkC@8Ikkw{TbSeVl#c7WCbmed8ANJ)M2y z7WAE+ed8AN{hfW|7W7@-@pH4F@Ad2(x1jI%>>IbB@B5w}UJCl|&%Or?e0zvLV#X^O zSh}!m!s-i_53qcLdFuyoFbl7a18=D;`C$lLeGfp3{%`%XFVE%W>~7o>|F>B7>T-@f{y-M;A# z`tIAl=??lH+`j1!`cB-w=??mS+`j1!`mWr*=??nd+`j1!`VQT`=??ln-M;A#`flC6 z=??my-M;A#`p(_He-C_Xk3V9@D;Ze2ux!HW3ziSCe1qjPtg*lvBdoE*niDwnM~t8L zU4I}a0Bqm&2XX?ymJ=Y5XCP(lNCuWJEP2?z;|@t)0_W5YY~OeWeGe|C-M;S*d>ani z_uYYS!(rJ>nZ6_gOBc59yMw-Gx9`vc->}ne-=_z@VTTvCo~27)(uJi9r#{=at3lto z+BdC1-@vB(SMu~Ld06tWi2ev#mfgCun<-iH#)kzsUl7XcQOCGko zB_YYf_`TdE-ZQ2a&v_w@0@dL2euqOLHWMKv|IkJK<+Qt@^=Mtf5Ebu zGJQz~mM(1hyMpqSS)Q>#jxyRU|5zYL8N9IdEM5ANE-YO*_1SV01?4iboJB!7j?(=r zdHR(+EO}V+u;n}qCNt z!qT1JzWSowa#RN8v9uhOLHR8$M`cjnOUqFiln>K#R0ieAv>cT|`7YUnvEoWU&eoHa! zmaj69>k_tnm4RHBuxzGGUy^~P3tPU*p!}ScS2K{4lXlCu8OX^AFKj(am%gM6OBYUk zwp@Hcx%(_fUr=L3yDq zCv#A~Xv@hQltnDI&mmM$!t zu=;}K11#TQ`3!3;u*L{$?6BqpPW=(%r{(1ivlto6&m73@3|oHYKyGJPHdCfA$-vTuEkAQmK5EM&9mqjV zyXBV- zN#1*Be2@%mx%UG#0+6@-`GMT~u;tYc6g1*<_2RA<3z5CqjJjY&pq;>KBM(cwy^Vy7VPoSh{fPv*lV3%FS*$*n@Jmr~6m( z^ecH-^04G#tKkx;3jNez>h)O7ouE2CR&yt)zK_-1399>JHFtvQ0a?wRpgKWTb0?^N zkk#A?sw-qQcY^8-S>EFWO`2FqtyV}UhBSYwB+ z4w26ZocbfiPpi8WsM!Qt-K9XyCfI5=h3BjeRLay0s4)aDY&}bt zzN8CF7nc99)fNe=MPfBaf@+kc`&aVxD|uM*u;gK@Sr({+23y^+kkmDEreDdxR%b0x z0}lB|PI@R%TMf3lX@S~m^V?jIE_S2~OLuWg-(F&9*a&T7mB)u*!>b3t|Mtj1hW zJv*y07gXoYYRm=Izq1;1L3Q!0##~UnJgYGmR7cNh%mvlgvl??jb@!|uU!e9M{)ic` zWMJvSvI(m%SU$k=4VKTa#sX`Mu*ME+PTBO{Ky}3ZGI@s#X1!~p7vY9e{Nd}fKZ1v`X>g!ou zyg*Go+O1w*pr#(Yu=Olm`jRdzT{!jGYH0=4-m)57K{dJ3{VRF;l{_qYSn{yd=nT~T zgsskINa}bxit1B9)d5XN%0}a#?g{@9#pqA+THW#Fe9qGc-o!`FtqTOn$2Gw1) znyNwdSgodNP@Pt*sTx$j)oQ8+)pfO+szLQ$t)^;F9ayWW8dM+FYN`g+jkTJpLG@&< zrfN`~S*t%AsCA1!V#X^OSh}!m!s-i_53qcLs}CEfAqy{TJxiCqqzg+IPJOo8kwLX4t)^s94a#)? zN}hft4@(}FJiPfseFAl^VXG@0lDgH-_#heBYG(&(d?Ro5uLHHSVXKQBsGU8(%?0UV zN4l_d=eMuEXtx^TL3PHhhIml@ajPL7RF~XphzHdxw;JL>bQ-+(P}?1U#Ee%mu+?67U061~z32;;53qcLS57f0!89S1Jr3*_Qwz}cr*kNmUti`Dv z*lG#~)gKqrZuP_iwa8(sCmyIp4ySg+^d%Wsy0Fy~52~MTb>Ruyo$~+N%NM zgJj^=$Mz22J-fTh9JPL*Fz@O;oZtDSPpGttb|jzLPjzAG!qQD;&{bcwzw$}1P;Rli z$7tItdWGHE?dII7Rj;t;F}pfX`>1C);OKVF>ptHzG~Z(v=d~Z|86MwoXXn2f-_vv_ z=T!#x45xp#qx1RGdxl%zE<5kFL9fvI?aX<~RlUNGvrEp?KkXG}w`$1vDH&M0ux!HW z3ziSCe1qjPtg*lvBdoE*niE*QrOdpY^hoc}x@E2Vzu(Dy!hzegaUQs3-_Y~o9U3sY zl7XcQOCJ7i!^c9eXSesbi|I=;@MbIb3zL@E)@8)B54i5}aP8{bdB4Lycq}a2XnW_> zj+nkA14|b^>4$#dhE?}*`+M)-FPzwBZ|D1ZJRUmV+HegcueI%SQs~0cg{2FpK96YJ zFLb$cYxncYFCGtPx7^A(-M^BjFUiA_hb0fM-Sn}r%kw9>&!;qbJiL3b)!ngnF+NBJ z-lTW$(D>x`ag3+*3F{toqVt?B`i5Iqj&>xU+D~=i`wCrHx~UAh>WlV=w(1?0ed+`s zZ~3iW;eZLpJKuVJuW-WDyB|=W{qCq%N|Ep+s9vWR8@Yv z;~PG}@=fjdEP2KP zYmBhQ4r@+e`IfTgdGLpaxX;Yo-)(+=`>@%%QQ zY2H7)*ZBaK5hL^IIsL*-oeuPVyN-A~9JS9u&Z!+SeMttEE{x4T`km_bX+QXxQ=E~% zdS=5lET381_#j>RgDxyx$>2Y{!lM1dkxT9G-1ql>VP^MzowfHdfDi{f@oFnZGF)?sc&W{7t#zo%5afn{wBj^PKsc@?fjT{QaGI&AHw##!tz>(uHLcR$s7ufaM!3pJ9y! z))--p9oC${sXt=ojq8f{o;$~V=DOl9Eh2MGa^xLnd%GArl7XcQr!xHQXtmne9(OT) zNd{((9kR-qah()QJAYp;{rODqm%lFu^*zfuwIilq$-vTu`TKJ1^4GY1{th0w;?>Ul zeH^ppRn7}r&(g&o>B7=Y{fF5*-#yg9{bWyFv+n86>HbZ}D|!5sJS=&b>-G(Hzs3FJ zx_ZaFA=9s9VD266AJxU>x&FWSu$!H^FF0dTWXY%YQ(aiPuyj)ybk!H_+(SKnSQj5J z_fVbR@9fMy)R~7z=6>y^u{U`;_fWgFiOfAzzkWA*JNHn7SBuO&)XMkV;O*Q)?Xg;9 z?x8Mw`g(8Y9_reIBXhs`kHs4@eo6+GE-ag{`hw*HEZ<=H3~MZ~#^~+E*kR2HEZfNEe%cVd=uD z&s-}Gx#e2-nQO>?uV3Sw?qA8{o8)21!;*)2PIc0}d);TADNVYmM+3$O$-q1-JLJH7 zT!!aeyL=Ow=U``F8|_FwwV&$3(uJj)%Al*hXy=*X>L1+gxQ?QxNLX4rV*UEa0%rnCeX5a4Z zJYU_)YJ2047(XQgOBa?+Sbf3r0hVvDe1^m&x3z!xQ3C}+QtXz!qSDM3#UHwY~-qbx4F+e zGkIZ7SLby9N}j$X4@(}FJj{EUHXZx8&%8s~cImzi7#}19^KR&%hkLmU?{^N}r?)fj zect*kvgA|ysV*#CSh}eUy6TH|-jUt1UN0Xn@5r8gq^C3Q$hKKNGVjPnb$Zm>c}KR& zw~sjUj%?m3k$Fe9*0hJcop)rvoE({VWW#@a$lG~Gw#WUEc}F()z{tE$d};NDjGvN$ zr3=d@tiE9R0LwR6KEoOdtTDnGJFGc@sj}oGXuBp_*?_V2g$&kg;>AG(=Nk#hD{HA#+h>tO@ECn`P6=@3riQ4 zZYqPW`l6jPA$P9ww2zlFA>FzSaOOQ!+5;NzjF56INfae1PQ} zET3VG1=bj0jUCpU!166+=8bbfpS3K;V!uTfE*Y6~M15Ck$mnu*2pL$qu;gLRfjqle zlo8XHWMJMAxBRG|+Y!^w`H-bniT!duq~%tTQ#)e%k_;?enDZe$RvqN_ImhzR83Ua; z-*U<;4c9R8THE*_UFSjB6bcob~$Tf;exS0sH*LK|Y`9{*^p^NgkFwEP0r7<~LmPvir}O@Za_v(}3|oGO(X@ z-}Ob8;k^1!OTFaGIram`N0xkQKh=e$3rjbZL05gz&YAzaD*y2Da_0Yy){!~$|LOxT z#JywR7aY(cGH3o*=rr2fIrBfbQDn~i-+s#|Z|BVaz*dnt^FQj%k>1Xk|2cO==FI;` zr$^@dh=GSTWc-v2EL~VOVf6*e2Uxzr@)_p)1;zqvjIhQIYffPKmNN6kcON?zKJ(qj zS!YK7`A($f-iC~>WMJvSl7~6x-}c>+?wgptBm;8>_^!{QjF@)L|95W`=bZEZtNa#y zNbQK}OER!@Vb1>_c*HC21K%l}d;eHxzF!zRtKk|(UTYg4qzg+ImM)z7%-QDA?V_KY zdG7M?2wx}Z{*^p^NgkFwEP0sks+QmQE%%vkpa#rq$oL=`m~Xr0zV*7x^L>EFWO`2FqtyV}UhBSYwAZC$M}=nR(+o$3wS`KJ%Sp>*FHxUF50{G-Pxo z14|c{Jj{1(r+z)oV=bmH$-sQ`GGOypT}Dhh-@DD;KF&YiyFI;583L1sxR94ru+QuC;NE)o9@Tnb>^Gy_g0F`H{IvnI?3Dlru)SuBJ)jm+q>WK zcE0KUa^t|{kBQ9p@2j2AknvM8uykSBgw+=; zA7J?g%V$_)fi*^0V}~^-uzX9IdE>kOEjvY@`L4fXB{F#cj#whjgBV@Oz|w_N8NTCg z{nvLq)?)gS49qv4H6KM8G3|WceevYjFW-0H^L*sgj+lNW14|d?`|i$rPjesm4t<>) zraJR|de@g5u3_Z0w(&u_uykSR!l}=EyZZXR(NDf(_M!A8{dB(nYx0AzU>)Ruf!=&wQ zk;!3_EghL0Cf&c9>hk0;S?SZriVT~Qu zoWSxeW#)}MHg|0t$3-5S&o7Eh-kV(~He|P1$iUKtB@gdqd3fd?@S(?AOka|L$!YNX z7g0t`JNZmHOpI|MpUGN}Mo#UB=}R)Obm1#3f6Jc3KXV_*yK?@IpE{F|WrJ-ZFKj(a z7k{J+OE>i&CRf9DCq_TX;jqCwao*DXt1;r6ut4VZo< z1Cy(2(Feb98S+h?f5n&1mBX3*VHRE{6 z+qUK3B9rIs>{$&NUCF@Gg(VM@r)$?sW_hf|^d%XX96qz!e(o}2+R5M5c-0s?@^|%l zJH{)uBc?COz|w`u-?im=-?)A9jII0F*Usc0JL8H{+m_zH=G!D{i{m z_s-;99JgMyBl*;RstZdOmToG8uKJ>#9F-rv`K|8}a#U`+Yh-d%9v{B(c5+ls+bJ?R zDt~B6!Jt1p)?e1PQ} zET3VG1=bj0jUCpU!166+=8e4E%MXb@lb8FFE#mx;$9w5Q#)e%k_;?enEcEaZ`5cu|#_^Irf8WOAC*oKUsl7XcQ%OzRg(pOS&4 z3(F>~zF_$P%Qsj)!x{^$F~S-$!QG40gfX@2D*9wX}S3~d`ZwIil4$-vTuslW5} zxJ7;4QYUERvm#SJ=*(u37q*_Ii$BtZrJMQ>Q(I)rjnPkPj;wb=W!m^;~iAFxS{xy>Gr zOpUpx21KUD+`ti$sWJERl*rWM+oVbCON^hAfu#$}Cak_-`2fo|SU$rV3#>818au2x zfm46PjFCEnqxOqFQ)lqrM
BWwRg%~sl8L?Xzgt>cWcj+v7o(B#)$Sv89UlLWlU*Lm9eJ1 zR>q+AU>Tc5vIfxJDeD~e-+YY`_6*|QDQj2low9b--l^G>Pl;i;hqQOfy`{ZV?p^Jj za_?&IlzUWrr`)^RJGFB1DRp8W_fD-I@~M@F`s3cIwJXgbhZV`XQG1@O>$DfjdQW?# ztOK=o%KA`ys;nEe*UEZQd$6oCwKvQ9Q}6iMJAv_i0OMr+Og!t+jJ9OmtG!UGGg&8V z@6uT+_n&xC3uDx0FQEi3%s=ZU|BfdRA1MlhcO#;k&`h2SZ^PWE6Fu=U0&$kUQ z@9Fc+1I&B+dGMqm%zOHLYXS3~KHp%#yr<8%88GkZ^UVg# zd-{CK0rQ@I^6aL4PP;FXXD;oF+IWupr8dsVt<=N#kNc~3UnI|Z+K;vSDDKnR{T267 z?S4$2F}06MuGK!L<&C)iY4>&97q$DH+=_Egr6| zFg92#!%1#u?X28hA-AV z@Q=jGY?A%+MQs#kl?Qu^v&AjeU)lsc;?!R>$ljg@=sV`G_{?5`ljmQt?Z<1rAWuf- zdE#d?-zEDJ3;Fvq`>oS{mq_C;X0B8pMfSPF`wO=I3N}`r*zk&V8U~`TxYdg2nk8 z_5a7eC$_lw$9+HEZ?yeo`V>y=$+`3${l$H5{TOV-T)Xf-o{tUs{b#eMw>W=)j_-CR zW0l{Xt?%fID}zb^+lX#tq+qq*X~K~amEFGkG~1qZ*wYVyl~HB&;1eE^1;vXceLo&KlvW_plpvn z?oCygi{hS@{U#9ivh25l#Jw5red|Z^S!B!Ktkvj8@^@s*1HsPh z$r+I?e+N4o1LTRwwl)vr!0O??iEQ~Jv|W}*w(>A`t(Z8^W@#RpZxv3WQ;BJeRSH_?AesD92#;JpabAK!~G zj_*Yn$M+(P<9iXtysMJVgUN3P*-!CaS$xOa-rI@o+I*e7`<=z#MC@G&es89ac!whX zCSvba#NR~hos0OJh`oyue-o+jjz-j9;rHk0SA};vlHap3#y9c*$=(NxYl$$H)h=gi zXpLcWS^ORCC;QHq`v)J?b@ZKf&G!&<;}~<}_zs>i?_9+9-0WNC z`2Jgk_eA1*arW(Vd|%GKiH?3*4F8?)hB1E=Pu7jGU49eM`qRdCe3#6|UVO*Q#w70# z5tI0?rg3~%(>T7XX&m3xG>-3T8uN}un2%xRz>NDD4ta}nAdPufg8QHHkheHD(m3QT z&XY6_`Ga#NjYHnz{7K`Gw|Mu}IOMG?`K?FolDAY&-jY3eOZAYqR6lu3?UJ{ohde5s zEeaOWyynv5Pj^jpY@_cziGDC;Qfz{D{Bg5^@Ag z&LBs?|C{fUk(;P9t}$R+W5jY>&&PMqSYQ1l-vuWce)4zKlGw7YGk76%Q6OxyS4{OEvj-0I_$;*_pwv6x8*_t!HzsLGYe%Tr|8DsX&F7ap1Pu`RKUwg+a zxp!>Mflk&MvE0@^@t)!g9NwQWUsyZD_dF}CDdM|r71kQ@Jg83WYPcRO-i1!nW zJ9P4Mj zJIDH2@6@q=*1LABpY;wNYZASi$67^xG5-|g3;H+YkDvSSc3CqQv7Gg!-WjX# zTo~UaKOs+jMijf2js;^G^5DX694f%WIFgyL(yZ;hS_X+p28T zy*lrT2dqxG*T4sjvAN~Chm5)Q{oNlirq1r~I@8vlkABq3(XjtSXS9jYEE{~$wfLwy z@m+0g@C)sFYvXXSk-^r(K6IsbB0kLtxA+-v1KUE8C2%7e}ioYkYc!(W`&IAcfe z(@Fg=yzflAd-Z+T%F%Q7EN67i+@{{j(f|1$obhYzvz_r*<-|eu#7FfIH`Px()h==LOR~MTnleIybGZ&lplKh$GsKw=(g>q4n0~eb!|2v*7Fa2!B zb21;LbE3_0n#WU{#f+bE=^U5ZEM|P#8ea4JqBe1Dzt}ZKdXFsT{u-CuYo;we3#4;; zdjF0~*I>HG!~ch?*yymg>LzY>Z7qDw0dLjK&95_VQGKg!)olkEcW?hz-T0esFrF}V zX5G?n4>oRe{mi;n{}^Jt>5en&j+!#m_~|(_>N=fwqw!gnq;edjGZ&8Yip^P8;v z<7cLqZ%tpB#trUD)N{#Gx&+!%jPe`kO({_cOa zGyZ~)$g#z1FUfZYy7|(SFpw#j9>dqddKbs%1=6QmNE7>z4@Lo_3Ti6-0)R6+Tt!}{8c$|kUjBHJ;Y7*6Hm2EoTZ2OODFvz z{ftBWq95hsqKv;=?fSOa;BT`RXBy-0k-wi|jK6EGJ>3|8f6;21G5$Wj;Z$S%{r>zZ z#`ycjs?PY^_xs6Kj=w6$U)kfY>cL;tkH2acf29Y1r4xUpKlN8}z+c4&R@`946IPsI z#UEC`!0Inp{RpdnVf8z#@c?U_z#2cW#ucpb2B+gteaBdpzp&x}D?YH|1}mPh;tVVP zu=)j7f5GZUSp5sD-(ighSmOlN_<=R9V2!s=m%pjFM5{olB#X#T8ow}F=xdrfmbcvR$H*zg4GuM#GIpw$IrOP{1xNl z1+A_u_I&sP)3d|yD~cY=U1-3szgO+Je;oY|psQ z`L~@8EX&6|uy<*H^J}}5^@!0d8(7!EsuNaQur$EZ21_$6UtswN6LWlr6%$yoN;w@T zD%Y54@#gbm7adpFq+?7r)N|hVlWN*+alW-HrhL;Cn^%@T?0k!7i>KGA95cvyN?lgD z_6_H0FYI2q?pHomcmHg^%JzS7-mOQEiu6#fF^s*&F!g8*Q@_SA?P?68M`QTb?*`Op z46ie^agD}s>WdhEFMDV1wvYAo`|Hm7^K0Ha-1)TCpRO7G8|S~C(6};lRp()US+#Q6 zoC_@uv(DI}(&(?whwQy$<%N@+o87l}<>rl?cl=HF%7L>kF#FYJbgz6c#QEei_o-BW z=e%BZmrA!*&P`9J&6%I&|t#m3Ln z9bc_1=;OTOe$Q4G+~xfJT1BP(4Cif{kE*=e^j5!rBjZ<}_TwsFPPxT=oc76cl`C#_ zesaUVR}MSU`Kc49R}Nj(x!?KkRPKMp=aI9wnN`u8LOFS!IpP08>Bnh1z8v zfzihN0yo-qNQHR^o_g@b73L#&aea}_DPsDFId1i?ci6RJm7_Uj>Ob|3-xocf9%=Ss zYzB_)Q=Iz#NV8vO<1>m!<~h^W)l1)L<;-O&XD*XHa~X9~4|7?s!Os1|T-M|WXXdgu z*K}qsdt=HSX3t#K`6}l{^~*2WpkLR*suNaQur$EZ21~QqM_*w12+Ma^F@Y7Ul<{|Q z<1OUdY~vI9S)9e#!!7SQ$$S@6XUMDBdYyWkz1Zr%r+4-o?2K#h-F?(l7LdY&4dBZ2TWJ=8EjlAAGIVd&uS4YnS@k?3LFp%f4F9*K9lg z;gYQ5Z=9$6;i9Z^rt@(hotJ%ghx2}o`(MArFR z=eeVMWPLw%eq^b=vwfyGr<%q1B^y}R!m1NiTd*|1(gsU2EMH*x2+Ma^F@Y5;c&RR9 z*ZKV+H(LCEc-Nv)_8Vl}>n~SlXMTB|@!v+@khSS{t?{GF56#ZJX<%7CYtElb`?Gew%9whVedG#b z>hIV6a%0-f*BM}po(`QaGe+k+eJ?def4`-j2XFh#I#*7+MCG~4gMBXhP*0(HLj8s6 z5A7CeH|Qy(C-_xJXYi|#{@_=U_*KYX>=g&Sj0 zJMIhFz`7Pzov_-1r2&>USejvc#1~jTsvO^CPfTFN3RVnZ#THh~Vf6)!e)uWgFV`Bgg_1oBhL%TL+;GoCG63m#CPR6A4YfNIJu_}A|PW8}tF!j@SFzwQJ zFnZ`aIQV7v4$PRO@8Gn*n4{;;8fD{Cj1BYSyv^_Ndcxc~@*HR8$2*^LW`2CV$!N1- ze$48enIAjlk5>+NW*$7^_Jx@|ARAcM!m1NiTd*|1(gri9qZyVjuzXAz ze<`22tgq9=*pM@CJ@+=NM~r=V=FKiXtK^>W6SS08eg&Q!nr#Reu0TnnpCSZ%@5081Mz&9Hod?zPNRUkJV$}X_)w&q`?cHXx%a_fH!Q-6Q>bZ1r!KKcrUt;`{4XkTn z)d{ODSQ=nygQXdkFR*-sD7{ZDzteC^<3t0DT%4y%hp?`}}?>}n&c*9>0 z&$r%n+(Mk%z-=xbnP0MWz1fH-w3z3u$$ zA3m#Z(Wx-|%}-i7|E`bo-Zd-cd*A1L*2){^zx&v^-MKsD$F4rk?By@|#l%WBu&#ww zC#<$$X@I2-mS$MK!1586@33M5D^{>#2rIU*Vh*b>;Lz`d`beDi9UO8|G4F}o`cX`I z$XCT@r+92bE-JR~WkL98$(Uy)VSruy^`wv&ZaO_D)w= z%^6?bUE3L7RE{sQ#~1E3>cN+Bxih{TaDg+vblSlgUpAcYI`QS~dmA*T`sJ5w6bG(_ zRVS>rU}=D*4VGqDzQFPkmhZ4)0yAG6)AB`+bC^^1>-_XWjPJ6EG0!^pe_s7!OnLAn z+vc_BEmq8lvsQn>IQWvy`n_}TC2Mjg>Uhg^M z%ibIL*v6M1PIFFmisdghiUZfesuNaQur$EZ21_$6UtswN%Xe5YfmsjCT;mCAS8=0U zOblfs{;@I7-o@`1JY_LwPovQ@&g^x(+TWQylSy5i*)v)1t0&E#J(HDhcc#2`cW3O6 zXyr^jhd=d1S^t(7In(Y-dpa+wQ+~+?ztG0Du7Ay_0w5c4;vd0%#KEm=HR!ra! z&tlC@CYycGS!vVl)rB~YVY7*Gt_=CjE2Rxg`RdiBvwKf)KIVyL*$cy+XNEI(hD~<9 z;OKVQUB8@Y_NQ&%A=~K?=f@xHnB8?-126SygUwM}O)`6~ZFHtHb+*i%X=}!p&S>~< z-B;Z{`XbHpOE&nfYhl$1t1TFvXn@g)HZhuIgD&L!O{Rr8!XMRe1YX7 zEZaK@J}zHQK)>X%=#Q5?7yR-Lfgf~5hLHdvZr`2x#F zSiZxG3Cuil&hjyz1itxivlMgV7<03MLu|7hF7bX5Q_j9?*W=t@_FdQ9&zXJK(CIWdrM4Sarf`3zi00+F)sh9u2;hxRzS>-+RopoA|W1Pc1oAn&+9PZid;!mB!J)3>9?rgIU_pE84 z{&3G`|LE)G;hxR9T;d$=*=)tDoWng^mWO+`v`=-4@kKVUu7y=6thQijfTazVW>~(! z@)4HruwnuSJ;k6?zf_zn{jdLIA;x#v#Bowt;qs448<_IYciB?)&Y@4Uqvkq?zRs@R zbdK4CF_R5E%{h#jtjiP5Va#N^wf)#^DBu53XY7}`+nIWn`NEm{H{JY`vfb;Cb7p;o ze(97iXu}47buFwqVYLNI11xPSN3-nl1(uJne1{bi7;TCh@mz4X=WVexE1t}iHJiop z9~m3wppD-x$8&MspmIDHf7+`Y&&57%%JE!$^5!gy33CwbQV(;`JC`{#2Ms;dnK|g0 zKF-WRDrXLoeX3cEkFtSvEv!0WwFOH9ENw9JCYoX9Q+$D$XYmnc?#6dmF@cHOL7#ta z&L!O{Rr8!XMRe1YX7EZuqP|_ccCrW`4i!BWLFKn%U0G?;B2YPBn|8@7dPVU4Mv4*7JSm z5UcFTP$xDahGlt(ZD}83UdD=Cz1c%^h%>qRm@}Qp)$i}`9QrzIyP0zs57}4y z##|j^Xz@?tDI3NA;g|hhz!#YE(2v=Tqn+_({~^x!a{e{W_@Z)rkv+bs9()-&-|g|G z^_D(v@g+OC9NSrKQI75GgXMhur#i*>g1^|n#DQyJ)d{ODSQ=nygQXdkFR*-sMeT$9!w;DsGgEZ9GRC@sEvv)-!uw@x8@7%nQYw{hY&mQ9RngnRV17FMVe=tfSgq z;LJLz$yN>J-_8Dq*rV6>qD zmNu26S@!q>%STwg!-@$U;#u@RWI5%KO26LAEW~J*P1Il6{=>$l4NN)D`+xhvnSFq% z9hbIp_6MHa!kK-8=l5}D&*2xRIR@*P%8V8zPpgHFYhIQRW> zfyTVC^efKcJ}urT%3NfO4fD~&YdwE5m(A<#%zSj_?#|3dM|E~)KDuuOXXYc?r5@&^ z1132$AGLYZnfa)8tTXeG%9)R3Fa6Xb#z)z}x)xTQu-by90hTscnqm0@%STwg!-@$^ z+&&oE#QP|+#Wuz>W$ZQPQ^p2g+V@$`#udJ7bA~g%+OvwV?e`6U}P>snZK!fFea23Xo)X@=zsEFWR{4l5>b zh+B5#+*Tgvke_=tYOxTbSvFCB_SDAFKFpyo<*Z32?d{B(O$Z)+Do*a!xgi@mDsm zu7y=6thQijfTazVW>~(!@)4Hruwnu$RxtDU1AE4N9^lbVo^z^Gj4!f*buFwqVYLNI11xQ@G{f=*mXEM}hZPf;IeqoBn%US^+$a~@ z*p4>hAG;UATu{6`r@6&E%n`+eNzP&JDBgU~Im{`=r0bl+d{kW6*E!5b#iVWxJhF3x z&DTwxx%Q6tnpyqSdGk}wwDs^vXEfY(m9zYkX89-^eAKnD>a>`|wqSIk0Y)d<#Aucc zzQFPkmhZ4)0xMQB3LRVS>rV05AZMkm_DXqFAW!1586@33M5D^_M7bSj?2`Kwhuhl{0O zaSr!yF>q#?=Z&!mxvRLS@cbNdT5;?R&LP(oYn|pCa$s?Fcju5B!<*U8A!imN)^iTI zv>4FdIpo;l;ik?Z_ZDY2at=AUXu6bh$koM>%Q%M|Ui4kwIn^)5U)jLA7FM0G+JdD4 zmNru$FkPmosaOj(a(?_E>6DXVxU=wsK~za_8)Jevd4oUw+~5 zn0MVr;_%{fe!ml+b{jYow_A5|CY}!-?o6DoJ>8l3-+7rc{nBrcGyV1OFlYL4 zIWvDvAMeck_2t{n%wM~(!@)4Hruwnu;*Y`QeV-EjV3}vI3PaN&z1YcmvS)1)O+?lo6 zcGo$xHktN$n@uXZ# zY-J<Y)hWNiTvi-?zx&774^>4dCg>J+B*9iXEa>4LYYGew@`NWvm24AvGc3xFJ zX73!~9DL9IalUhiVRpvt&iroD?L}vPH`(vYhVlbfUd`&kezWbIspq~UokJgG&tBk6 zyJrn|4l%5J`QXCLc#sXOYhl$1t1TF9Xn>_no_ylOjygAx#m~vJ2Th(dNb!#zZidI1M6B?b;4>3mIhebU}=Ws z3oIXD`3@^4uwn%h&qLl_-TFmrF;8Nf#vEVf-L{6=i?L@Na_K{B*!W}}a?j(=tV33M z(wTLL%2|iVo^=RyQV;8p3$Aiz9Wt@6GwYCiA7|Dfl}(*lhaB0$c~SlHOE&ncYhl$1 zt1Va>U}=M;8I~`we1zpYteC)x6|DO)Wqg-SwCY1eE!PL>ny~n4IF&WvQySm zKN?fcyxjH1^(?l`*DFnMW*#5(o-_0N=qBqc{@LMcI@IA#}T)(@Bc&Y5+^ zSNl1$-cUK~5ZMR6%6h~xK4t^!T3B_$Y73SISlVFLDrkn~3oIXD`3@^4Fmda2osZ|m z#ZWei`Q?-Re!&-*a{OH|-Wgw}j&;VDlOAx!7nS3S?D0kQ;LEZfx;?&(UA7$m+27VF z$A9+QUCQyFt<$?4|K6Blx!7p74t4R@*P%8;N>4_T6{5M1G5kP@=uIr*}!k?@n$|W^Ls~3`S7mK<}1c~eDh=T{OJ?? z9^Y-FG5Pc>oOgZi_Wa=coCm&obH2qJk$*KJuUXJg-euhlEQZ*3*xi|WuJ7$k{iCjQ zrrksDaz@V^k2|lh{73oG6P>sC$Nc<~sm`e{V&WhhSl7a;6INTWG{DjZOEZj*_+lJ= zR5`xOo|wRj6|5M-iY=^|!{J^ijyuY8xH#=2INaAo)AhZ6G3CtZ^Op9QGuKa_>A9UX zzzvT&vo>ft!kIP0*B3gomgv~qnKeeEgPd7=Y~0P6HOc2YJF`~lx05q#n8~|2v$pwQ zU*}Z67$0Q=>snZK!fFea23Xo)X@=zsEFWR{4l5?GVg(aJ#%juGoKwbTaracnhlR#u z$diS}YRI33#xUy&jqQ+c3ypc!A-We>pXeT8-J*L(I;BUNWrH?d3#(38ZNbt2OB*cB zuzZ0(nY49w;!Zc$ZP4%H+UIwuW<6JPUh%o#WL@Tru<`-h?3NvWpYtZYew!V3lJnZT z?43Qik@NAz@3KSR8*cV+%bT3BxqUxpu5HoQnK~D|GR*90tMeddG_*O|8ExNZ4UEoH zAGyplQx3}>Rz0xlht)1DJ+O3&(JvePg5@u)IKYYzthm9cX3lA8GwyoxQJmVqI?ILl zr+pz#ZN#dRGhx0O;`MV@%su^`IYVahxz3!EqjJuikv(V8s24c@ z{Dl<z^WfsyRh`Y(g{mHEWcp2B|V%=kaB7R>lfzDx`%_jDC4)br;c|YecFK74f4)VPEPr9e z0akoq#SLa{&shhiIWpy`W^rl*>r4PxX9B=F69Cqk0I<#kfORGStTO>%oe2QzOaNGC z0>C;G0M?lRu+9X4btV9;GXY?YF<8FiugYQB!>R{X{jl1Fr3aQySo&f41b&$)XWDwGn==}QuI7xk3%|NRW6X3)Gv%=CVbuex zezTA5!qNky8J%ME%Lcz-`3ox!u;K$NZf2io4&&d>4rR=UQyZA_Rx>YO$j3OwN`GY| zd(Jh*hJ7>6HHE`|f}LLqhrDO!n!>D6Iqwu^?J9fLw5o@-F6X9V!y1_LRAJV}oU;nE zX66i1n6)(LvcjylIlC2J$j4ZYX4%842Uh*C+J&VDmQGmuVfh8iUs!Q~6(1O#6MGE! zC(Y8I+N3Ohr{Ce%qW{t_ozZ_;#rqEZW6yL(|7w4AM!)(O{Tnp8!Ze`2PkU$d@34w9 z`c;m8*=r0a=JDZsN@RGT>v6A@k00W1N|fc09wGd8+^J&dgs2t?$gd_R#Xq%y-qLoS6sroqw6d zmie(&6EA1p+~}9iAy(P1w{@0IG^-qzJ*;|Q)eoy(SbAXTgry&rU$Fdz6$e=HffYBH zxu(l6uGalk>Q6Px#_U7W9@XEIqJv!qN}RFIfJul9F% z{j$d|SpLF_1FZPKi|Uj%V$S&n*of5^l*7zNoF@P?A92nA%zVW812FTE%9)R3&wQkM zn2$K$0DI;m&OLyck2ntjW4BvamVQ`%!SWYY9ANsF z_`pG%omUWb8mpZ14N^{RU~(X52*Bh(&K7{lft)!2lLI-6044`=MgdF?{N9LSjl zFgcL34q$R1XCT1jK+Z;h$$^}i0FwhbO92kCweuEW`GtO!!?K4}53KrOwF^rRES<3Q z!}1H3zp&x}D?YH|2BVE{?a>^@gMGIShw)(Fv%_IL*mv%57!PH67!Rd=7!PGVVLaG( z^w@{-VBgonVLaG(_iz{w_B}ov#)EyQ4-+@~9hNq9svMR*ta@P8535~RdSK~6G;2UzieSqpJyf@zLSdD_?F)CLau+|F2lSgRk3n07gL0!BY)DTwh!eo+p~9#%cD>W9%uyD&P@152mM z(Jy=ag5@u)IKYYztTBL2G3C;qa4)VPEPr9e0akoq#SKPa=oW>I^zaqc45qHV))rXq|s&S`|vc0f445k?#5I>KnxR=X%Qk^PCv+QBj1FL>m?ZVOnOD8P-u>6AMFRVDg ziVsZA;p|6z5mQe7;Y_@gQyZB1f^!#R9PCU*IOw-?8sVV7ED!oi`=GyUH|V!>Ah8en z?R-c$=(lqt;h^8nlZ1nQJ7*FOv9)s);f3_a^60PG!>R{X{jl1Fr3aQySo&f41PVztJ`@zf$oZSaAUvM5E%)G-nfiUw9=Lf>fJDe-1a?b9PJ!kj9 z)Wi9NF!gh8AxyiRX9%l*#b}dG^}FmTS3R)mhtWy9Fgno#OQ*`wFMIrg5Qy$&d*FawSid&&h6*dvOauh8)w#yoxk>+zfu|4lv5j+`-SglVD2NnuYtM0 z`0fVgzEe5(qwKj))h_oh-}PY6ea-hiF!wv(0m0+}z7K-QCww;qGv4?v29__TIhMn+ zhgA=(`eC&TOAjoau=K<73zomI;s7f?Fnz%{7wF`E;kyi&`-tx~VD2xzB`% z`(6VMzjN7l9A+QC?|}I>gzr9Jz764f5Ha70$cFDnV7?9EyAqf>`Q8MkExtp6(ZKg9 zW*_>L@1aa{WR)`pQci7P?h(E}g1LA2E(zwI;(H~SdyVgyVD3S_Z-Tiu`R)nkp5=Qe zn0uM;q+srGzMq1*_xY|0CMWQ{6-=(+J1m&7%J*3?V;H~CuX0%Su4Bva zmVQ`%!SWYY9AL!o3ep3wdyDi`O!u)Q_cfMl2^OX(X`NI5e%eTxhb@GifOj~^W45NW>qRl>N z;~QQvI;Ed-SoW~$fmOfR$97>fqX$MaI>qRh4SvCB<{N5Qaex&cSaCD^MKnui=p*}1 z85=Qvr5whdeG5!^7<=}OFdW97eLDv8)SoOfFA6C1t^uW>yOFt~X zVEGFx4zS__D{e5F`G$8<{qiNXNm;)0%`c2EeDe$A3*Y?0_`)~8Fuw53FN`mI^9$n( z-~7V(!Z*J#zVOX2j4yoi3*!sl{KELcH@`43=No5OexX_Aum?ZVOnOD8P- zu>6AMFRVDgiVw^fAZ~EbX5Y(1{l=7&yZ9y|<K@GfG-v*mr-JDt5thTW;b*{9$Gi_}=*Y%)bjW?pU z(5HMqWtttcIV^iv^}wnhR=cqDz|sjzKPIUsh{tBVcO-}XBa(v=PTxWox`{)PJGBYjH_a&Y0hEH z+xOI|Hq#%=VcEl~2Uh*C+J&VDmQGmuVfh8iUs!Q~6(1O#e9w!{RI@m>Nf~?e^Nlc! ze!d-s(a$%{&RhqwGvtIIN@WtXep%qwEY@IIN@WY+E?2qwLIE znCCvu!i7Ve?TlP_AzxxSzQ`U{J+SJB)h;YOuyn%G56drD{=$j_toXo+8%&%zUlh$D zFWDKSaL8A7HYptPn4MV)vnJszQRhV`; za}`#X8V|CkT=l@JA4Vtb!stW~ES)MxzwGe~mcOv#04qK)ea*SPrZck2IVU;g z)CLaY-_Fa0!+l}r<-*~9u`_t#a39&(yl}X`?95&`+;?`CFC6YiJL4A)_o4)VPEPr9e0akqAbbN{_ zPj!m%C9s|2opP+l&Y4fyd=Kjc&YXus|Js@JaOihCuO1HL!OpRVSr2f&JSMFVX3E*l?4O)6-kCbjYwQ|mYv0Tn4Sh~n zSerCUCw;-$^=KAjlQMG99K_l6Fmn)R+QZC2DrXLoJ#!HCW5XQ8`SUPy5a-Xs z%t4$#4>JdG{yfYa#F_js^CRc>!_sCkkL9rJVbuexepv0o(gRB;Ed8+jg5@u)IKYYz zj84vzUsSX7r#30eU(Tq9(a-twF#0*u9!5WB-NWeT415^`YpG5mQe7 z;Y`kyQyZAMl`~*r=3LH(g_(;vGZto!<}6v5xtlX)Vdiwso`sp~Ig=J<4ZvBoFlz(O zu!UJOaJDVXT7olgVb&O&g$su`+Znm=LcYXue33n@dSKNLt6f-nVCjUVAC_OR{Dl<< zSn+`sH<&ncjwqUW_UEiom^}f`Acfg0;A~QuJp|4yh1q}L98sA42hI@{bB?HNI7bxb zTFy#^sgpBQVcOzsRTvGNxoY-t42aPw%^DlBr(E^Gs^9EmyD*y31EU$8V)V-fzhL^m2<{#%Bc;^*ciE?U(47Su$(hvW5@TJSe=ZG2cC9jY}|6U zGh^e4Yn>Sz_nhy{*qCyPGh<_TZ)e6vrxTnR8~smmW^7!4mNR3RGlx^1=vO%`dsy|r zsvlOnu=K#v2}?gLzhLGMx%-Vo6`C;nhtbUlb zIKv-C184i2ebB~P^kQ^MKjpCOVbuexezTA5!e~YhjAnF-(JvePg3*k>u;KtKKCt3u z_KRqiPWpv&@39f%SIW#^oNrG#^B3pd!^~fthYvGR{X{jl1Fr3aQySo&f41Kj-bk=;s`M82y~j z52Ih@=$AdQRXy?rohpZA533$n^}}ixmL6C-Vd;nE7c75a#Q~;&i4PpKWgDN+&&Czp z@}83x;?zbgn@~^oWgE8-^=CuQIMJ>R?Pi1L^f3;4vM#-xgU+n){N7d`^k>)J;vD?S z4m!*^_?x}7jdO@Ywq7S^X+wj`VcEl~2Uh*C+J&VDmQGmuVfh8~?YT6FDNi+s84t37 z*PlBvmoIxvot4W+^1OU!-#{^8KS8l#pFuHXze2HPzd|u*ze0UM`C7aF(PE4JS#LR0 zPru%Mt(^Mb_|%zpZ#np6D@V_HW1XcRA5{*^9#%cD>W9@XEIqJvsvP~Y$1hm^!ioc| z_`r%Ata!qTGaT-(Z13<3Iq?_kT6|17wSmL^n4K`quMPKO_P|_c`uCD=of&T`XS~Ut z@uqeeZ%16|_Kdgr`#Uq4c>pmS3>^g%t-_@qu-|8F3TGYweu3lv5j6=b^zm4-M9NXt2&hgLNJntn<)dorebN zJT&8Y9-7KI4^8%*hX(6BG+5`M!8#8O)_G`f>Z8i>QTDLvfmJ`Ov*}=+O=lc+s+{w+ zWY4)6G;2Uzie6*pM%gcWBvj4L}^3}3?dv9rA3Fn;WeFF1@JJNpX`_Y*Y@1X9PPt4i3)EQ5;U}x6B;Tgfs zvV+4jf}L>(hi3#k`wkAz2zDkO9G(&EtUNe8BiI>wFfrtuJy<%?uX0%Su4BvamVQ`%!SWYY9AL!oAFD_HmSb*sq>%S zS+;uKZZCQHqsvx5I^Fp%LmK$=QyXk<-FMmY+MBjqwyg7km6k2rx?{mIrUAdC4VE@o z+F)ser45!gE05Y>X@jK=mNr=0U}=M;jaa4H#FQU;XtT0k#7in4e`C|?eUA>Z7(Vkv z(`w@>&ci-zT3xmC4OafE<(pNn7~{O<#?7j`A34~{-`}NK^_}g87}M5uU56Tf(x+K< z@WD44w>>l1Uw)JES^b(-&wO%NSw3?9@Y23#=bLTJNDux>4=g>f^uW>sOAjnPu=K#v z151y}(Ib2G5Vus1nDTqaHMY26FJ4l)?iXwZe$=S?eOIsl{I?oa+ix_&+FEZ~qw4fl z9+RQd8&#i~<8ga^R-@{kuXsG~{5+J8_c%YcOylad&v^WYt=zb}%KP3g_ioj=y50KD zUH5HV9d^0*-NmOgu5P`G^IvXgT>b9vgBH4f@#Ufq8&%a8htF(ORZPB}+Q|A28_MZZ z+0)lBJ~9U2%i1)yu>sd@)Y!%hyzd^3Z7jjB^=WKl48H5S#^u=SHSz1Zr^mf!^@xev z9s7S<*LTO67OSDnzO7rklk=zJzNu?Ad4`pLddfF-H|*;?eyeZlCXbkIZF_*L9Omn{2%0bzj%r-Q~@){OqQ0l=jcR`FGPMJ?NJn zSbB`39$0!{>4BvOmL6DoVChjgdSs8DG(MC|8|AZFG_Ddi%Ee16KmTuytHd9hHZvMm zRsR+rG_EQRH_d5WReUH{+^|sOAjnPDo2m((F02lEIqLFz|sRt4=g>z#27dH@azl-NesF8jt!QXddDG@YX-n{r)27ColY=EI;v;A4>a^ zR$5TjGwgr`W&O)uwZPgXKFR~=5mTP(6jT1U)moSHpqTR4mv39HPsB?qZ+lI~_^F=llBP{lnT-*PY_)lUKHDSAF*iUz6;$TD$5#?R*__#U14|DqJ+Sn^(gRBmEIqLFs9f`} z^bogHkC^gaZ?!JhB;qBNr}xDkty`CClGVU88!TdIQB^+w^Gc!qn9r}TwyY|j-*|LG`5y z-LkBw`O7WK`p13L(%L0Ha|blFH3oXbX$(`%OR~T6x6N#AgUu!DH?uVZd|%^csOAjnPu=K#v14|DqJu26lPA`pD zfu#qQ9+hiNC_R)*4=g>f^uW>sOAjnP#7%jCaxvwpPBG;#)sHLJkYdUY7*k)a33r}W zU#@>ft(e=o2%E|KpkhgFX@4$2bLaKdSK~+r3aQCSbB`39$0!{>A{zsUcSG4HWX8y>J%@@ z{=9u3ET1J$S?f^uW>sOAjnPu=J>0c|&@LTdGG)`Cr

t8fW4=g>f^uW@ia^(%_p4BvOmL6DoVCf+ay7ws; zQ=aM+Q$FDC+v~LNDyIC#0i)`)?f^uW>s|3B=#dHk1C{{JtGks@2lGDg`-M)qO6yx!S&8vDK_WNiqU zu@tSe*h(s?_)vohqons$REUg9$*!^#B1uJ-^ts+tb^Exl}1g_|T)dQ=CF)8YiiEn@1m^A)!ZSjRmo-X_S>bF&+%YMH) z{Pxjhzh8ZD=IFBDug=(bOxf>O_daq=+3#0r%V(Jb28=2D{c4ZL^755unKS=ArtJ5t z#C?{byw5V~p}*>Z)dQ;sRu8NmSUs?MVD-T2G48XBdKkB&9+~)*-A0CS)!Zgx$c-O#N}dnc&Bq`m3tmAHhc%w>h4+P3$A!3^0ZmyGoBk0ctC?U%3JIkxyMOw zl>a<;bcpXhB#%EG`JqqWD1SaS^1_z0%eO9yyy-Qw%bi-s&mK8?cDXb+@*7{xE-&a8 z+iJeeo8=)_Mh)K`_GbCc3!e@3w`}`nxmkyCf!Dq6&GN2yR{x@pjF0+Z^#`u#ht&_O zA67rCepvmm`eF6M>W9@2s~=WBtbWE^?}*F9R}7w!_A_%&oKfDnW&CdZp$%q~7k?hV z58wPh)63mEM*gnP^z!@<;&O8pR%c-rM zR!#{T7$3F4YJ=4Vs|{8gtTtF}u-ag?!D@rm2CEHL8{=8jCKDetVMg*rt}TAfzSGmb z<&JP#@*V8yzn@h0cj3+V znpF08;r%b2RQ7k_b4E-m`@8VMg_FwuF1+1tlgs`ttTx6$ZLr#4wZUqG)ds5#RvWA~ zSZ%P{V70+&V?5sIM&U8^^meNMWDcX{lbaBZhu+k$Niwk_DUVB3Oi3$`uTwqV;T_KUdf67O-- zh3P&e*A`#Zqg{F)|MRQu()0L>OWURA@yqL6lI~^1eIBR0&*RkN^Y}I`+of?k@%f9> zc>Y**aT@3EpS&oI|IjTiO7}AL&@c7C>Vef`+~;xi5LXYZ9#}oFdSLay>S5geyz_T1*!b*A77B_>D8ufs{fRkZ9}_^ zgPLJA!)k`r467MdGpuG<&9ItbHN$F#)eNf{Rx_+-#?7@)TsF@58`q0QZF{HtpiKE@ zhuod^Cvt7^A;_dxnAI`lY=@pTGA@dyH@P>X-H&y}!CA?N9c7 zxQ5?2`<_&0pDpf5pWXT0yHlN~4ZS(B4!t;!S8}m>UOG74i(fx~aJol7b?o49@207B;*;1lzBW#4jT$KJ_{T^{b8JUagU-pRWToA*hct~#Sn z@_OIlebT-~ZS?)egL{~D3}`t+g^$;bV+8jY-oi zfz<=6$GCeQ^$=GNtR7fBuzFzi!0KV#PP_WS^joA%yr@&It^CIq4^6*aet+lCl+U*5 z3qwDrA)l-kAF*h7`e9i@f&tbdzkGeT$lDRi%+{Q?JJI0aBbRe>~`U`X&>^#``4uX z$*#vsja(?xhm~p)W(=xJ?6UfJJBPD zT^D{oB7V%2Tu+{N2Oqufwc++-;(w% zYGbVGJ=rP!mhsF_ozi`6>_MH={cirPozs2rsOrw?{>V6Z-#oeQE$M!G{~vBi_u0SY zdibr1wut*33+4IFhcPVbk%>QhNV~LGk!y<=*GPF~+q73%^+ww?4t*!LP2+R^D{a%b z9lxM$8qXn{Uzo;u>3J8X@ozu=!sN@?<`*TuetPhtv~Q=ZBFr*=>ICnFy2p7K(j zURD!7uT_s!{=DuzQayd9^hotD`?*KTOHmKwrXE;5uzFzi!0Lh31FHvCPvD9kSUs?M z7@so_=#=(&a&g=!ujbmy-}_SMv?sj1W9PIdoV#=9w3nDOzf;;{Jo!JJ(%$2!D>|h; z2^!q1wA!Xq+QWQbFE3x&6K?;zPHE3W+&v-X-4m(@{px|$1FHvC53C+oJ+OLU^}y;e z?w(LRj9XEUOnh9o-f2%L*A`!1uW#BDez#NK@LLt-8&&m9zhO;3tZ({lYyQD~({Emv z@7*{37B*$8zUeoz`&aZyzn#sQ+9&;{HtwE2>9@84r}Rm`!L6VF-?6{V&79Ud{ANer z)ds5#RvWA~SZ%P{V70+&gVhGB4OSbhHdt+pkJkj^GV!8jnfUcTZCbV2&+%OqnfPam zH>(=Ae0;e6%f!ofH?A7eabk$e#q#j$QC~KyYWzgxgBvuiYPdWiC zWZceKr%~1Km&f1MH*VUfs(qu#%@1r;^<8W zexX@r{5N~9Vb$brABQp<4ro|)^`(*ja#h2sQ?`ga?%0M^pZ5DGlzDKMhE>f!`Y`a< z8#k=FYwgI?Id`r2JN3dZHm!Q^)A$?oln?WB*Po5QL7z2e)2bgj#owTb|L5@d8#LuN z-{Re%Sv}}f53C+oJ+OLU^}yd z+0UCSasQJzFQ3iaVu`;YW}CNM681vG_iDYw-yE~;Z(QPUk=boe=jG$OtJyQlmiXIc zHg>;n{7o}!+x;8&LRtIS-?-2G1>0`kuhcGVyRhxTwhP-XY`gI4+NEC&mVKM_$hF0r zmA>=&B5QNYckVy4uU`1heQCDgnk(F|=Ko8+!hLM^P1_ajZ?iw#w!(dHHu=F7?uWDe zp339#d(mvW(JS0PXO}&;!hLmi%zzc{x3i+839A!UC#+6b zov=D#b;7ID$v8iD`m%DJS>ZaFxVHEQyDlr=|3bKyW>Z!!El;|4BG-p(%A}>`R}Y;O z_{z>p%k^K2eDi)w%ZqoI9OAR{^C9aWAGyuQZ_4{06ZsG4eN%q0apa|2ep7yUbo}i2 z_m-3w?htv8;Y-S`+Q+u$wqH{2**|L7@Q5Yleh-9uQ}%X?CFP&*4EL;T)#gje-*pK0 zvar7X&^p|Ye!=#Iv9d3LD}90O3v6Ft`vTh+*uKE_1-37+eSz%@Y+qpe04tMUD$SE+l5!xF51kSqP$Gpd_v+far5qA^X>xItaIr6XL|mr7=H|iX=E3IX!RF?{=H|iX=E3IX!RF?{=H|iX=E3IX!G+ws z%=|`l7WvC#XZT%uR<+iQ@LWups%(0AE`~S0VS0Ejh95h4dU!6j9-fQgq2Epm&&BX* zA59C-#c0rs5* z^nHH@8H0`g9G~x4(vNP#w*{w zg!0ZY-)};5k<~_AZLr#4wZUqG)ds5#RvWA~yxK>V(w^s}oiytWH>+usTD$q7zmptWLP7vyhvY z$&B-YnG^l~JbPfmL~|*#SD%>}o}nm1ypnqv%2(cf2=(;OfA6Nul5HlX=cZFmos^!N zx(t|=e~U(8A7vvO^5^Q$Riel=`Hfrbv5EUGHtf6DufIV9P_G|&zvjt$!7BKGqq;R%CsHbvH*DqLY^hIs3+F-T8YJ=4Vs|{8g ztTyBBPm0XeClRtD@@8L($%z@C)>dsYVQSsAcrWx$@50ee;k z>{%Ib;jE0b?$G8Mggs*f_KXqOGe%&~7=b-wB*ZIcjKH2T0(-^?>=`4lXNzW z2$~CLwj?IrYJ&#hEFJg{Yd7$Wo$TNF*)o;)RYTl83FY0BP-p-AzRzb5-K&9T`()p@ zZs3_eS%bed@GPM0j(Zw-Mo@O)xCWjblzAQwnv1M9;%bA{X52lA+K8(SRvWA~SZ%P{ z;MHlPzn<+wdAYW@XA@Dzvx#8OCW1Yi2=;6u*t3aX&nALBn+W!7BIE8!3TG3AdfbzE z))V^G2CEHL8>}{1ZLr#4wZUqG)n?p1$?CMx7tgBVvvO_m!Z~1B;T*86a1K~jI0q~% zoCB5>&H>8`=YVB}bHK8~Ibd1g9I(uDz|iK|WoRz4+K8(SRvWA~SZ%P{V70+&gVhGB z4PKo#H2>E1!E@WFN2a{zyb+g)Tjtm0J*SQ`o>K>VP95wyb+G5u!JbnGdrlqfId!n- z)WM!p2N%w%%RCPdZADfaakar}gVhGB4OSbhHdt-2+F-T8MQxr*NL)sLQKwAYGQTeG z8H|+i3`W>97>&EfE1U@#>U59i8H|+o3`W>97-7#~gbQadW}ah-wj!&IxY}T~8F!DT zHsbWxJ)YW#s|{8gtTuRc+R*QroRpVqi+iRhWjs?faLpN~nP-X;_e@ck_2M{trYLdG z6ooxg)VO;*%KIIZ>kiFDRvU4(1+F>oG-)HQHtTVm)ka)xu-c5f$17^{OkK*z^u;r5 zVb8FIJ;T>0MOXV}7?VG9?|u+2OZ7;QyX8*#P4YBTPBLv6&> z2CEHL8>}{1ZSd-}q2Ke3DKFO+_k3o`cs?`i`OL8AGsB+G40}E^?D@>F=QG2e&urZN z2Ic(@#51nZTx7KoR~xK0SZ%P{V70+&gVhGB&A9uG)oG(Ip4ZK1<=Wz&Jx&?V9)~@9 z9QN#S*t5q&yyjf=%(KUdd-gc&+2gQhkHell4j0ZI&pg*1{Y6$MadpD#gw+YFGsJ7o zNKZP6s}oiytWH>+@alBZ7q1nRmx&j0aT60aFBdj17d9`~xYrZ&a*3Ol3!9e}{1ZLr#4wZUqG)ds5# zR-19JC#%y&Uwj{d&&svMeV>9dzE1)BJ_YRi6tM48z`job`#uHi`xLP6Q^3AY0T4u3_J~hJEK6_ML0E@XmGSd-3$E z$m%Dqepvmm`eF6M>W9@2s~=WBtbSPiu=-*3!$tkRzfWAIkHx;o#4YpxD_?VdLgsk| zl=r*>xNv?#=6MCy>HggF3W$4N0ql7Nu;&%Ph4TtB&wM~zkqc)jByE&Y8>}{1Z7}_H zf37y-YJ=4Vs|{YAHuU3T<^Kp0*A{0ERQ~HB%#F%_1cW(L`R{-*mn!E#hB;RGuYoZ4 z9B1Za(tF#LU)G?E8$c?=!-_&j|ZIBkcQ(aN&K%?6jKq zNq@oWM87&=b;9a|)d{N;Rwt}ZSe>vsVRgbqoxambT&6Gon||V!`E_~U;iZi4@WQ^s zYux$fJG|EE{PZ1O;=aQR`wlPcJG^k=9p23MpwU)jwGmevtTy9*AEGwm^w&A8HsWf7 z)ds5#UY$1d`%X9I<=W!DlTI1mNe^7}j(p}j>BM~}9cCRl&c2gQ+;`Gp-$^&__aTLM z($jiGvuhJp8?3g#HSfzOZN$|Es|{8gtTtF}#{E8|sI743WG2%W&!2=ne-ifmN#j1h zc>W}D&!2=ne-ifmN!arzVb7n03+GQ}p5cl9BCCzK+F-RA_xVL_#MK6?4OSbhHdt-& z>a?NX^GGQ#*B19YRmymtD(rcxu;;15o~H_Xo+|8ls<7v&!k(vU+~=3Vd8(lvpIa@`p&)4O%a&2+X2d0eY1H+yV40}E>?D@d3 z=L5r@4-9)gaNwHriZjm#CSEunIP;8UG#6QI#MK6?4OSbhHdt-2+F-Q>t~t9nX(PTm zZRq!!KzW(C@9PnliTi#Zak;kgzN<(X-&KTtR}uDIMc8*0Vc%7ReOD3oT}9Y;6=C01 zgnd^LF1)Ll`5q|xi>yxK>V(w^s}oiytWH>+usUIN!s>+839n8keewNP%FDIIeLt5n zzMl*GelG0$xv=l&!oHsi`+hF$`?;|1=Nk9^Sa?4-)MI{y??IzqZLr#4wZUqG)ds5# zRvWA~SZ&6=KNhw5{xxM}`cl*>6SvH-%lp1LWqjWp_I-2M_swD7H-~-S9QJ*4*!Rr? z*S!Cp`Mx>v!u#fFJ)+IE39AiO8>}{1ZLr#4wZUqG)fTwsUHGJpcu`y7{H07rf8m^{ ztZ+_LRyZdrE1VOR70!vu3g<*+g>#~^!Z}e{;hdV(w^uTCfWJ-;i|Q*$2LZ^k`~jL&)&8SGhPuxF9Mo<#+usUIN!s>+839A!UC#+6* zbvo&b=hsnQt}X6ae3bDlKG?JPV9(-%J&OLjjCSe>vsVRgdlgw+YF6ILgzPFS7r>U7cgZqP6L0^1kZzQFbcwlA=Kf$a-yUts$J+ZWir z!1e{UFR*=qi+#}};xc{o3}|tmGc>Xq0Ko=8JWIN|F1QlvFT&kt&7et zuk8Ny{?A=CB0Kft$ZZxqlr?)X@`wk9W$)h|`M?K^;#J7F_oDiq{b(cn_p6BaCrv5#KpB>83 z?%3lZqi06_$ms0y-dUjx`cE7mnSM3@cjWIzk4o_q_WO4#zd_G2sh$p9pH1~2y?K_} z?YZlOr0277&n2CgKlXgmKXK*rsb9qHFXbHv>T!Ii-*KZ|#}hq{GddlA^y^E}FL~5q zi}o+FJ`&eQSRY}1g!K{DM_3kNJQF^f>nSzLBIo@o?bkhW-mlX9V&3=Kc6S5-F*HeJ^4ILI`es0Qhz=VQ@@DYU&=cU)Z_S2zvD)`jwgB?XLLIL z=+~E`UvkmMioc;etdFoh!ukm7Bdm|GKEnD4>!WeT!SeVB>m#g>us*{223ril={)2*>AEBCyrsPBj(S{o)bF~ZUDq9YTzBYn z-J!p*?lRXM*BRrvzo~rgd#Wd&52^lqo}_m3`IGc;om3~+N%eD`v|q&SFXbHv>T!Ii z-*KZ|#}hq{GddlA^y^E}FS+Pr#otgK)<;+$VSR-45!OdoA7Ooj_0hQNP9KTuBdm|G zKEnD4>m#g>Fnz>FSRY}1g!K{DM_3`UvYItdFoh!ukm3 z{VKW7%;P2ZGkN)v`<%R${*wEmyxo%frCd+ReN?Wqcid>#@kEc~j84ZN{rXb$OD_6Y@i&x*^%2%bSRY}1 zg!K{DM_3m#g>Fnz>FSRY}1g!K{DM_3m#g>us*{22WbFW|hM@Z16C^@ryXIBz#R zr@*U1f%ykm|FxN@ur*ZtUJnIgo9@ZU9{j58fc3F2YdRTWbI$3vc-mmZ+ z2h%V7g1OGH?%>?tR6h4T)sxSMRDV8CQoH&5NqX{m6`t>?hwG&JxlYgPIXzlhsk$~z9!!#)!Y)XzQ>rd{@# zFnZW$s*`;tjDGf+aM3Th=wrp-P#$J{s0Y?ZSRY}1g!K{DM_3j}>ta9)3S9)a_A!*dFp>j}>m#g>us#}h-BI3kr;n7;M_3m#g>us*{22>0Qysioc;etdFoh!ukm7Bdm|GKEnD4>!We^nUr^* zsgIP=M_3A2Q z`R6Gp>gs_PKs`VD#Ky9sa{TLud1*;f(zZ{apvXAIi|L z12zw5@@MqdIOAY>#>aXXH|u9SZI^LY596;+d{MuC@%!v=u|85pA7Ooj^%2%bSRY}1 zg!K{DM_3|mzY}g!K{DM_3hhqk=pJ5*%wJqpM$?lIzPJM%cTFEzF($(5wBVh*A(S9ZaF#Vp`KL- zy%d=GH(39bz_i=1!>fVOGxwtS-_UJxofF@R{~?I}^`D&{%5a_hV(l4$>2HeX<6wEl z$9fny>t{S|mvL4PtdF65#Yb2lVSR-4F~loA!ulBE6(3=Jg!K{D zM_3O-`ly}_w!w_Gv)12}K z*UbyO?TK^Bjc3jc{Q0eO%7-5v`Ngqw%1?eC-Y+g~xnxfHxW^;!)nab>hXIj~Z96x` zAG&{TD&J}5+*Hq@YtBpccWE&%wY%czc}dUxZRaJOV>--B`d__%Ug{U|>grE|PReh5 z|NOwz)4BbEz|=pm<)?vZ_l`FrqvxE{KMQemewRf?|Eb?creBY*|9L1we~mK^mS=pd zhjFuh#?y8gXZ0}t>ckiI>lZ%$7V9Hr^byuaSRY}1g!K{DM_3U;8+7 z_kLl{5Wn=udjeB_({^_Urk;oU-4&Snd%byQVA}1!TV(W1dGwADM`z0;BBOs={mAs| z`W1ac8TxCSaj-n&V?B(U^)sHf%Q&kCzto9e>c=npMSR~a`-gTZf5%Uesb|&ndqbT1 zH}5+jFzq(j^S;37ne%L9bY8pFzz|3OTc<{*UprqOnf@AQ94ycHSP$c7{fwvWGS2E@ z{MCss>SwLdFMRwh)<=D3d|-Wq^%2%bSRY}1g!K{DM_32+9nv`RBeR=S zP3?DYh+n=q|Lk6o=daha>ZKpT_+%Auuz_UHP}2d{WZ=wSf25*9>&f38Bg0~oYlkls}o<; zuU|Z;{}$^bW%Lo&M_37cG;d4$Z;|Hn z0Y_|+=J_3`ZIR~xqnB@y*2Q;Swn*zG8O5wY+Z2q<`e~Tc&;ycivLo`Aj{|bLw~g z)2{0RJ+2pYx{lEA`l4U1JNj#!aj-n&V?B(U^)sHf%Q<@mJ@(+!yuh7e4+LQ=aQ5 zW%Lo&M_3rNku>m#g>us*{2 z2vR%emJ&eCP@kRZtHTs2*zs35f?~D(u zk1*{rp0GZ``UvYItdFoh!ukm7Bdm|GKEnD4>m#g>us*{2Xq<7dJmUjX590>wBdm|G zKEnD4>m#g>us*{22i=+A^VIIHzuPJ4*=wVnlFmCD@09e{+j6JWFXG-WDDQoQdc40-zxN&5^?rmN?^EdX z{)K+;YxK+e9sM=VI9Q(Xu^z_F`Wa8#Wt`Q+_^T6N)URLo_*<-xl+j06A7Ooj^%2%b zSRY}1g!K{DM_3gTz@ei8S6L3!^Z)Z_hy`n~Va zuJE&U!z~%@93{_#=-K8kM%Ha*3Wp_F5|2o#$TQIqJI6t$KPUoq>Mho z`UvYItdFoh!ukm7Bdm|GKEnD4>m#g>us*{22m#g>us*{22E;pdR*hF!i(FgK3w2AdDXNhcG(XH^S&=KMB(>_L(sKHO@F# zp7F6B#?AT}Pupdj)x-F!6JOM?Uwkk9Tda?i(MMPxVSR-45!OdoA7Ooj^%2%bSRY}1 zg!K{DM_3{6b1l#F zul4X;Z2deh+b+-1>fw1@orUkgN`>#iO2nPFly^Q;kMo@Ro&U7!xS6rVi7)EcFMRwh)m#g>us*{2 z2?dLR#Xb|J zzs4B{%QHUK!?;;L<7vB$vw9eRbr!w{3x3%z;+6eL@R$7?8mNbT9Zdb~_h8y(9|)s| z{UMA__Kh(5*-ygsi+v_ce~mK^mS=pdhjFuh#?y8gXZ0}t>ckiI`yD1e{ub+_zE}3) z$w%V)2m%&?N$NLNQd*7j5??>qIK7~&2U+DL~M!&q@(O=_?gXI|?>tWoipYgO^##ud#zdG?n z{rZKEzs34U8GVHH5!OdoA7Ooj^%2%bSRY}1g!K{DM_3m#g>us*{22R9_YwB1-e1_q zdf#Dx>-~s*ulFhT!`{ExCwpIG|LpyaeYJ7++m>e^ZawVJt)G3n?XsU&56=baEPM|Z zo(sI+5%+#UdG90Cm%&(u$o`gNYOuATp^ch?2i0oM!H2iFnT4c8af6W1Nr8RJ}kEYEexdbnO$Ki4ta z<@%-`u6yb%d=D0`lde1B&RfbmpQ*=rPW{e*+I3x^$Mu3v*Ae<%U-Zj$M}Lho4wh$p ztcP*4e#X;w8E5q{{_5m9seb*!$KPVgyYBRn^7;ttBdm|GKEnD4>m#g>us*{22VO#Hv^r^mCEe6N`?@x5l)_nKkfYleNV+4%qA z_tVq45c&Jg>AZ;iJ?M0fME-tsI$t7xZ#tbjk@qW|N0Ij{ol}wbE1h4F_bZ)i;rS1h zex-9TDDU|g)brnSJmR@kzj2Pof6qJ0*9ha_uLiQ_1qQC4e;C*&JEBn&J8G@yTW;l%z4(A=R&Z)JTHRv%#LWSTCMa!TR$0!1^kjYmv@XqrB%}P><(zP`~GO(5~lopvUt%(CPUb z==WTX{5t>tvYbn zbK=@vGuztgA3ZWPY`RyR`)2kLUbk87Z`&vOWIwGH`N~1P zvpMtPc)mXS_UyjrA|HNf&urack>9(tTlQ_&$d`O^OV;Sh$S1FPQ!$UF79CflWT zx&ptmXa+ks1Ro^o9ny?<{%vvjZ@a)L_ zo?kC}dvS*l?|Jry*-ckQu6xU-*$p3F9pdxXYm{w!WaJCxH_Gb&>#7uAwozot5BmGx zQauB|Y#*5VTU{2Jb~~)RGQ`o-@4?8&yg$GCtn(r_TQakH`aY4Xu6V9`#}<)uPfK#{ zX~{CVrzJm|ds?#2+|!b6<(`(*kb7EETkdH|&AF!~`;z-uvXAgCSKJgdQ|8e1ZVt?6 z9~c&yI%hQM6ymhC@|4JEXwx?`+K$g6qxp&tBGZ@AOCr<9o+~0B*W%0+A3yr|R6bvu zsUGIr+u0gnO))2D_KVD1{prfc%;A3=9hte^cIU{<`KLCF%v$KMY*o% z+~vYeO0S+6x#K~bl{UXF^29NXO0N#A;cq9@lo|0+WIp@t+H0pef7&iGZOuO*G8&ei z9vN*nT^Sk8-Ou@b_$+;C*gi6S+~@C+>HF{-BQqw(87s>(hStN_HaH@dXUxz1Q)Ik2 zbp6P9^y261gm&?6@#M&O`uX6*rP0U6^321Rc3D4^&#x_|S;t4tuPvpouZf&rTS|N1 z8#%wWl%|Z1oL^f?@63ptUt3CJKaHGUTS~8eA349al!mUeL8w2!wv^sqKXQI;DgCuU zeLJM<_)C##>)DZ!(eUUUk}=>d`He>E&%*WV#p^J0pmEE{%#FQ{kIbC;$JLRU zOZD%H%pBYL@yN`*m6IbgCpUgGGIMqQN0FJsO%_IGZukEpGIRbfpGIaa?DRoo*2u`$ zBC~c5sQxkN=RSUXpUB+bzdSiI`-kT?i_Cst!t@_PdG-$*cZtmYVV%8e;y--)eJDfu zV+Tj3o?}jmO#Rz5j7+=ZK3EaQFxT_y6OqyR?2I_Jx!0xpM@7!PE}b$ca_)8M)_Wr7 zUZ;5Obt<2Go$ATGE{$9n%jaH~8tfH)%)Ks^u1Q{(_Ro^nrO$t#Jk5?-d&_WLVh$Yk z!4`p;8-IHyGIM6h-I19~?_M35Ikw}ek(ql>91xi~*>tza%+;TFh|CeuEoAofBUG9kG8RwZDA~XKgCq~AX{dS9tUl-Ji%$hytlWl??)@h6WDPAgF zyJLvw^~1Lh+PL=}x@TnWiTi9BnS14NKW`WNmES{;m=l@%?~m1y zx&IzMpoX{ZP*diz){(jYZoNxn>TJA0WZK$g$+k&DleZ(It^ef6Xzo2LjxBvzH7PQE ze1B|Y`hL~u$c%|`#>(=Hq4hAfzgrl~Gv;G|7yZJEY1>D}qvMW+<&`GsNp9*swvZEosFCur6-$3rp_^kN2aZzZ6kC4ef*|M`CQw+cSlC^0k>`% z>Y*=_?utwwXAX``-**`nnK60xfyj*2O#>n`hX1@hGGp8C`pAs=nDZm!#Y2Zh#-mM| zN5;F?ejgc6pZH{x*spwDKlFU!Qv0i78P<5`Gq?Y;M`Y%_an^$6StHiN+SzRT#`>P!zF}n6 z+Kt~e3USupJ?}X|>+MRxEWc18y5*eM-4ww+icRVRF{w}yBGXBAMp1n@>P4%MY;Xf}OH==dqW^XST_tk*N9Uq!M?!1p8zjEo<2z>)yKTmY^7sAw{OUg+89Dbid;GIFp85RDUa9+h zD3j0IY{RW1)Avudi_Dl9XRIvG7+McwJH9&B$(WzoB{E*LI5;vM?X)ubi+49Z8JRuU zRc$Jq&%=}2%?Wy#hX?n3J23O`z)K=C51XDGnR$50F_D>vC$^5vJp9kuk(q~Ab&SkB z96UHO^YDzRk(q}#uklW3i+MO~|H#b4ojXNl9$xfPWbPw3Z}4s?4-cOMdfr+;GW9?DTJ({259uEnuU}jkudB>~X9q`SZq)y4Wado0^&&Hu=DrfI z+sv`+?~2Ua>)AFkbMo?oBQsZb*flb9`1t0LncK#h^Ok2VSWiAy`wcqeb;qi7+f|Wy zuK9XoGL`5b#@+kTE)Hs#xU0y78BdoD6_W6zr-GiUbP zCo*%X`X|hDu2g@&8zVEvc0DvQbH3H)ky#5Z_w5zR za}D{^7LmDztiMiVt|2F_ygiiR8d9}JjB^cnW`oFFL(XaznQKV*qa$+-IrQ(5xrSWw zL}acZy%t608q#Rj-l2Z3A%DF#GS`huCe(26o9;_x{^zC0e0E;_fgw(vmmU|HwtDx9 zjD{yCMMhiuuOp**;HHDZXX#6;T_V%Rv8BlLeOOgw#$@5%kr}J0O(QdgFRv9D-$xDX z6zXI?Jalwq=E-+!L}vbcdG*bq4D;&lr8fm;zD?;8nR)oxPLY|PPkeS`D8syM`g~;O z^WUF}%se;F{I@*o!g^RQU6*$W_3+Fxc(7h6)0gIT z`hHEQ3MP^KlGgg*o46TQ;-TL3LPR4xfKO*DB?fXT>quZ9nIf-|3MnuNb znWsm_>xVi$9P}^;hMyOixpC_;k(o2E9vqpu^z>nonPWSj9GST{^UBD~$(46UX0BFG zjLaOK`(0$_cAdQ*3GFiHdtDcq^)h9AWY){P-;D@m;3e}P51jX<^wS>y3Y_<`H1g)i zdEZO_d?|81CZ)I585PRpV^u1ZBj;mS+WFGR`Ph~Y?-e;8^HSfTk#jFfZ61lt@0IfV z)vs5dKP<+N?e%eW&%Ti-wOv;I*Q+Amys%Do>yeTFGIrf;m(3&Je)$I3Lvy3Hb{}t? zUGYHV6Mt-&9ejG^ZHG3>R&5mdzLy$hyzj>tSp!8yG*! zn6J|&GG4sXG%_B&{a#!Pc(?N%k@0k!10(0Tjv2X&{>KOTjTH_#jk0m`8;P6W2>r1~_ zU;Ymr|3gIH9iH<4MC9Ya{BIF?dNBWIME)Mk{~Y=MclD^Z#)$*A4zx4$kLcijy~JdGZOZ$NWaho8JhV z-w3n5)X6$hzxj=nA#Q&u?>Ly>X#I|x`HjTQZ-mWngwd}rtS|B#EAf!uSScU!8)5Ss zVe=bd^BZCF8)5Pl{h!cWf5>knZhj+7-0KPDz0R25NE!1RVe=bd^BZCF8)2>wbr}dK;3ezt6qA+^MBZbjPekqK8|HqbnEO~mwVe<4~_S@t-!ug&yy>^Fm?sMPZ&($jO9xrm%jVHOQqT&NB!(mN3sIlR$? zVCD}wcrf#a+&q~1L(U$|{2`YQX0DRs2lK3LoM&*$bFHu*t|8=JQl2<@k1*xQpR^wG zCt>O*e-fr$1adEBavfp5b07y2 z=DP@TBVoRyAZId^&%e7MmlEbX4RS1DelI5XQYI(UGURH)eD6UHCrq8>cEYqp&L@lp zazR7+d|i-_2eW?3#|!a%j*<5W^Ndek92}ng^L#m&?*z!BgZZw2{5qKL5XifO`EG%H zJecns$kT)QE`t0$nC~da>x233f_y)i?=;8*g!!(6{6LubPaYmg4Prhf7#VcIp09?PTCdeBdPCgtfD zd7Ci(C7%;!9LV#886WaLVb(RdmomAIFux1jdr4$|FW7C5$oaLswD!_Pp$xxAto>Nz z{2oy{<=n{p9&yyhHStz2e3{DM-7zxt+_hU|>TkOwYM|XU#w9%=9}hjO3-a-T&V0R) z>j>w42|03b-p7zT2j_hcIdyP8CLz}j&c`a`;KBJAraJSn4LN(n^Dz&(d~ohX$nk@@ z@00rn=ia6A;r^B9TM|bn`He7ZoV-Vv^-De^%=#ry5@!99KMAvb$*Y7}zvNrO;rq-y z4-;nnlAj5)e#zT}S-<3S!mMBNJYm)^`JXWBmwZc@dog*BF!yNkAz|*_OUe@`*Ab>XIgr*v zZX`_o6Zha66r`pNBtX_uT&m^ns19?V)G zk1oXXHA}7|%$g-f4ra}gI|s97$*F@`v*g;rtXXpKVAia4vS!KIBhH#7mk(ymlH&)n zW{tCEEzg=I-;y%uB-at93^|Z~mfT2~I?0)YY0EeoERQzpK{Gj-l&3G`YQpr998Q?N zliLY1Cggm=j3N1!FzaRgcjI`nj-Fp0nf3Kn!|g&D*6AtxMrNJ<>72-{(>=P?#P@x? zrhJ20k*Vj7ZzEIx!<*H#d)n@iSqtR0p@(Nla^7H`G0BC4dG;hn4(6GZ+&P$MRdVWJ zo?*$ggL$?k2M^|%m)ty~G13gxU9!CmG7;`(g4YVfNDGRl@A0$+wir!?X-0GXitn0xI8-?<$>#O&R%(}k*{F?YpJtI^8q*0NnXZFm<)c@r- zk!g3x22lfg$iYJoV?_>L(3y`RIgK#>k_!jpFFA5B{*pTf<1aaNF#eKj2jed}crgBw zn+M}BIeRevlFJ9EqzK0YDu4$j9dleY<*R|%V=2%EbIo6`uJ>j;|z z37Z=Un==WUO9`7}37dNfo0AEfs|lOK37gvqoAU{q3koy;$-9G@d*t28)(AOom3YX7tCSBpaxinA+&P%FKu#UZ8X?yXX6=xJ2eYQg z&4XEMM zesV7Px}4LOi-K8HhYB%H5> zkTVJAYoSCgC7iE?kYj0_+)K-olL=D~xtcKblfwzqF1ejBYk}N0n7K#J8_b*}7Y=5w zk|PH*hsm9TncL*l!OVGb?O@gdIe0K@gxoxswL{Jx%$g#X4`!{A;|H?_$^CSvmPzaI<+3OkylB1;^Z{Klqc8GddPu4z2XZ)J#)sTanDt9urA!_p%(DskjWEwFR@y2U~}+bbMs(x_F!}QU~~LnbN^s-0%3CnVRHy!a|>bC6nU61Yl^%_ zm^DQ{B+Qy3PZDNLkv|EurpT*=SySX&!mKIsFk#jd`I#_lio8vjHAOxr%$g$46J|}3 z{|U3E$P0zhMjj@d&&iM{3FmV%O}T;eO=8CPz( z?;M{r95&N`LoSbNwp){o#gsiM!reuS$RK z`e(f={k>sIy(;~^<!~&CrvC0ecil7&TRpdK8lQF#uA9b{h+x$3ICd}V#jzGB_v3vvCTyguIa)K6($Tt4@w^1bWEbunwRmE}4u;<{Mll$GTJ zuZwG;&XASmncu|u|M=%C%g+pp{Oq59E??9w@{3)6PVv9J{&OmSRpV8uo(E1{mFoZ9 z9jj8i%d%BT&t)^eP3vOBDJ#;t7+iNnS{IAQf0x$9;%mQ4>tfR0-=%eN=BjVgx}Z+S zt@V@Nrgc&G{%_N|*sK4yXFV{?7 z5Z5EhyGE!-ZS}^knY=!Aa9+N04LtCMHPhUfcs6P> z&M7~9{(k~*H2a+LvOQi6d_<#j%S#$f4cz>1=a%ckhHf>Y=r_5}d z+Wqs+7bZRE_j*G8u6Nq?I)EOp59su|fqut|etDgtzm6^A;FvQ$deP&i3sYOGdbCS( z@6WHcOTNFjv|XAHm)E%@=_GDFl(&BBvE6N2wo7_WeE#C3^T(=-lm73YyeRc+=oS~H z{(gM%(6lbTzjJ81cWnB?&~#7vbmh==uUWePuyhaVd&{tNZ(8=suyp@AeBpVXw_2tA4gHj() z{L`S+_Z=4vOk*-}^uRP$)ae+GzGz??+bd4U%U7;-1CJhvvE0 zg8NVHp6(GN9`2s*9ZxT-iJ#Z1M=F0__a3R9K2v(6`j`FOBei?x0iDtq-uqJLr1|!a zozpna-MMob|2gwJC10NWpH9iIqps+be56kOZM99OQ1hdpB-_KbblGxlN6 z*oQr1ANGuW*faKxSN>}tl&|~;L8zzl-vpul%6}Gwb}Rp75cE|3;~?m){P#i7U-?gj z(67pWC4~MO_l$isc*Z{L8T+tj?8Bb14|~QwTsUJtYgGAqMFRU@B(VQQ0{dSiu>VB@`(Grm|3w1(UnH>qMFRU@ zB*yj2{~{sof04lc7YXctk-+{J3G9E7!2TBr?0=EK{uc@Cf04lc7YWR`IUoEl65{?B z3G9E7z=i)J`NjXy<74H&w}QWw|FjCe|9|YgSJ)Lr8gMJ9C<3A&K^?=0n6rY)Zub_< z8M9(WF$YF5XE33H0YwDFI0`C)8TmG%m?H?7NrHeP1_VaTf3K=u_3d*pb8gRhp8sMV z)|B;Czg=l}SXEto>nikz;u~0@pA_H53jL?}W>y$q#kaIVe=EMR75ZWE?XA#1O=o&ZjFa(Y{C=}3oNxWNx5D@;zG)T4SMjZ@Fusa!V1@Bjd>bo_ zui~3oVSE+e(hBhx-`EQ0ReXCZoUiGOFY`0LEQj%B`HU}*%lI-L#+Px@F2%REs($B= z^YYtvaLqRgt2N&!tom&`^7w5#*l*jxe%lWA+jg+uwuAk)9qhO5V83k#`)xbeZ`;9s z+Ya{IcCg>JgZ;Lh>5eb*J0JROJM#E#JJ@gA!G7Bg_S<%_-?oGOwjJ!Z?O?xc2m5V1 z*l*jxe%lWA+jg+uwu5WFZ5P_B!E!^xH9zV0Px9MuDaZay`Sx>;YyT%6#|3dZUWngu z#CbWsIA7DL2lG=umP5T+KK1Ewsb}M%{*9CNGJd}S%K4IR|0KWtmU8URly5)hxb}bI zaa<6m#5DfbnN7vtym%l2ZP^n95=tq0~+ z>xcQ)dSf28KAE4bXXb6|pZVN&VV<|WnEy@ZcftJpURVylBbLwai^t`6$9VWXGERQK zjNfl1hyIzTd%oni9w^89p?vF&<657@V?7h6^-uh^3+H8falWQg59X(SEQflteCpHV zQqRUi{TnCkV*H==omp<#ry9oBjU#53FZtqyz{6IWRi1s^(}6obIIH}}j`8`->;L+y zJmvPsLi&{RXO{=v`f%X;hR!MX-S>gOZRUMl{&PfcWI@Wm>4fi6Ig7trn96VX{rBm(H;nrs#k0wgKc+Y<&;OX>|8eS%>AXmP zYV!%@^IY#m&Rwy#B*O=y!Ro_O*e@5JH&te;CR2o zd39bh-tTa}rc)2*r+zGldb51$)8kUl#zXxZC+%YV#0md)O^o52A6r+( zE*%%rC$7+@vhE6zyRF-%^6NISeZR;Zyq~VE3wdrhwoPT!?_&dBb##&S;Bx^3m72P1E|f7{CCN5x}(cuL#K_S?l6 zp1-7RWur}B4#zt9#$&y#R+ZOom=n@h8`P?D z!C8?zo!_c*`PNst+xb##uj6K{k?N52_xFzNOa3+2`Xa<|{WEP+JX3GW{lnsKpT53rDzn{% zZPT%yIKFL)VOf_ve-Yd44cexdPx`w}I+t5MZrL zZ}n)u@;|;A9QcrF{mPv;iQH?={^k4o-5b*XKBj+p$A3iL`Jw*h-#!@>^DpRMer9~+ zP4*a2{_>CbOmEmh0~6o0(ZKRA3*wkMXUW~=2kPSUz`#p>-TYNDfm3j071Jbc7=MG3QjNW=^ zs?T1J4^Hv-`+0CWueWy^lFs+g%ZH?TxNyvnR6qCrFeKI6k^dN)>a+K*LsLC((rsv} z{|8Rb(~EZLd)Cm@ULSQIn%eQ11Ba&ez4gh*Qk*?+d8~ZQ7O~wo&EHv%_%pWk;XNNK zU;f7Zp{_{Zzh7*3@((^fwmanv>=N7kiq9V_&*>c7{j1f6m-jy)qS^)OzpeIJ);wEc;@KxZGXnL9>3k_@uK z%J28m$aLKH7r&6|ZNZ}FQq2FUJfF_xp_kX2!JY=;?5?}Db#i?!| z+w0;~=LfuXQEH3*cfKgK(c%X$Ol|k&iWjCfef^AHDgCU;7o_}W?0!Kir}^vWr}B3{ z{QPv>PTyRc>h16D*QA)6Jbg_%mlyxICY|G$-L6gNKDW=csZRE*yEfGoWm<b;R)dQ9mrZL>ah#HFo08u)r5xkA zW%Y&?$7y-Xh84%@;RiIVI8HzA*|6d`ePUq4isSU@aSbcZ$^ZCng^F|Xkv$tFe*c(8 z73bvfT^d!KlRs|XsN$SFam7Xz=j3bWtXOeQo;ZHRigWV6ht%`W7uV-`^B41Q^M5r@=XLvC&C~gwI<|SLhqJ$Gp6ch*Ra>MsZE;u2 z#DlMFS#ciz=A@Pt=i!e!x2!l1AG~hMiu3Sg%UV>NhcEo7Ma6meyvOU)2VK`9#tcT7t4Mw!;*tDRJF~-^j>M%&`IgN(!v8LrT0pe z~(DabVCy)5KyvqTR*E#9u^22Q-FJAlS@}tkkza97G zqVj@`B5(iDqVldicn`kc zrOVRzZNB6`=^Qu7eo6O1C-?p(-3R^f`Y-7|XtjpR(tXelJ1tB1K|l9cmhOYrxp`T- z4|?t4W$8Ys^h};!+y`y={IYZ(boP_W(tXeYgO;WHpk0H&Q_vlt% zrFfcDzDjZ4b<|fW{w+`XDxDYU=N~&a9GCpVKA#tua(1tL6PWU^@BM9Hj(gj^3j!0* z{L8-!Oq?S(SQwc2C*Bm9^V;Ew$egd~)Pwn{AIqWMET8)HxYV=pQ2)kByBI(1HF>+c zLky%pH)23w^53+@oq;K5_M5i{ru+x{+!mPQ4m!JkVB)FV+%GV3UOMO2z{G##m618G zpSwlod`+hw%uoGT4)tdF)ThU#o{fk4H%{8c_-QZCi}Xcx14BIIUuWldk4!lehQ)hl z%3pqVyuaqS&3=vd-Ne)5%XmLdoSXNK_vyrc;5U&uuV+_@_wt;t>C}VysUORs-YlQ` z^tjZs@lgN9NxKj~4seaT8(4R@#u-kYF!}XYVf|HDe-%Ei@K<5|Rak!&)?bD7S7H6t zkY4z!u>LBnzY6QG!g{u_E-S3d3hT1Mx~#A+E3C^3>$1YStgtRCtjh}PvYO6srTO`- zgmr^qy=7Q$8P;2d^_ES?_b@;H53IKg>n+22%dp-uthWs7EyG@O!d`R2UUR};bHZM8 z!d`R2UUR};bHZM8!d`R2UUR};bHZM8!d@H0UVp+~f5KjW!d`#EUVp+~f5KjW!d`#E zUVp+~f5KjWn$Gp7`MLgty`G1?*MPm(fW6m%z1J|EYhCkmuK|0n0ei0jd#?d|uK|0n z0ei0j>#xH4tFZoR;KE;p^;cp2Rak!&)?bD7S7H5C(;W-?tEB7J!gC9k71m{iby;Cu zR#=zSbjO7*E9ttdur4dC%L?nV!n&-mE-S1L4C^Yxy2`MwGOVi%>ng*#%CN37tg8&` zD#NW2lm+x?6V!%XFIUZc3_|Fg!JOs4(ziX*k?Pi&vsy+?Z7_Ufqk|E z`wR;9IS=e}9@ytRu+Mp5pYy;z=Yf6B1N)o@_Bjvia~{~|Jf=Hlea=I=&&^<;>A^nJ zgMFq4`%KSt$E?rvNcWi@>@z*sXL_*D^kARq!9LT2eI5(@JQntOEbQ}G*ypjZ&tqYq z$HG33g?%0i`#cu*c`WSnSlDO9u+L^;pUuKPn}vNg3;S#q_Sr1#vsu_@v#`%*VV}*y zKASb&Huc#o=|10vefAFf>>c*mJM6P}(`{3qy_4>p7*!Ni^0AZgMBXs`(6z8y;$Jly%_9!G1&KFuSa%xMorZO%VclsM7je(=pNH!=-D%Qwr(xY` zSa%xMorZO%Vclt1cN*56hIOZ5-Dy~N8rGeLb*D|o6*NDtAWS*9(=g@ZPQx4*R~9B7 z+-aCNai?M8$B~9PFWhOE^EF*}nsnW1Sa%wxK0U7PH0iq2unV2V7YjIr#nr$?li1B4eL(By3?@kG^{%f>rTVE)3ENe>9&{dH0iq2 zum+my_y3?@kG^{%f>rTVE)3EL|%=p3;gmtH3+7|~8 zrrmM#VEO~j9!x*M<%8)zIDRnw3il7Dzu^SJ^g~=hnEq+H?lkGT)3EL|tUC?sPQ$v> zuuj#ter0Y(@ zy3;WA>2YrTVCvd+W0)1>Q8!@AS3?zHKSFWqUF!kxU)}1C@cN*56hIOY+cYNtildd}rQ@;INcbatFX;^m})}4lRr(w?5@ufRW zy6!ZrI}Phj!@AS3?li1B4eL(By3?@kG^{%f>rTVE)3EL|tUC=epW9x#)1>Q8!@AS3 z?li1B4eL(By3?@kG^{%f>rR_)d+AP-t~(9uPQ$v>urTVE)3EL|tUC?sPQ$v>urTVE)3EL|tUGNw?y>oCl40FxSa%xMorZO%Vclt1cN*56hIOZ5-Dy~N8rGeL zb*Ew7X;^m})}4lRjA4CgSl<}dH-`0%VSQs*-x$_6hV_kMePdYP7}hs79pBje_{Oll zF|6Ya>mI|p$FS}(ta}XW9>coFuyX1b zmkE>$gmzVtcMKi zA;bF8uud|plML%5!#c^ZPBN^M4C^GrI?1q3GOUvf>m!rhb>9Afptd|b!rNesZuwFXsdT`kF;IQk#Vb_Dht_O!*4-UH? z9Ckf8?0WFP#d>hq_297U!C}{`!>$d7T^kO&HXL?sIPBVR*tOxXYr|pJhQqE6hg};E zyEfc(p8>iyoOIXM!|nqByAJ^DJ^--$0Ko180J{$W>^=an`vAc10|2`Z0PH>hu=@bO z?gIe37YFQK9I$(F!0yEXyB7!SUL3G{alr1y0lOCm>>ePn`*OhU%K^JD2kgEau={eD z?sHN1S77&Df!%incHb4)eOF-jU4iviVf|HDe-+kWh4oiq{Z&|h71m#c^;cp2 zRak!&)?bBnYhhhhSeF&nWrcNFVO>^Omlf7!g>_kBT~=6^71m`n-RGsctfcD$!@A0_ zt}?8v4C^YJ?(|R)~dtt%ug=M<)uzO*V?%rZB z`<1cp8SK7iu=}3D?t5ms^NjnRkxn^yp0N9#!R~toyYCt7zGtxep20e(us$uUj|$H` zY*N^>1%71JNntM+c+K}GhCN>3U;0lBd%wU_j+z+ugn?UaJ~8YS121SaG3+4&@BaOV zVQ(4u{TUyIJ!jxKxtq#fH1LqGKMZ@+z+;zv81}A#byHz|U|3HT)>DP`RAD_;SWgw! zQ-$?ZVLeq?4;j`shV_jD7rrs9Zw%`j!}`XszA>zC4C@=i`o^%nF|2P4>l?%R#<0FI ztm6vnxWYQFfeXhK)^UY(TwxtoSjQFCafNkUVI5ak#}(Fbg>_tE9amV#71q~<^<80o zS6JT_)^~;VU15D!Sl<=acZKy`VSQIv-xbz(h4o!weOFlD7}j%!^_*cnXIRe})^mpS zoMAm@SkD>ObB6U%VLeq?e-+kih4o!wJy=*j7S@}E^=V-}TUh@V*2{(UbzwbTSicw6 z`-Sy^VLf43f7o<9RrBMo!g{T+zALN;3+u)*n9xv;)2tj7!M_riL= zus$%XCk*SOnvSPxe*9HfuNBsJh4o-z{a9FU7S^YQ^=x7NTUaj_*4KsgcwzlsSnn6s z2Zr^8Vf|s#^;Gp&N!M$I^<7~-SXe(6)|-X(X<B{Cf4J5-V4W^lrwi8Ug7q-rxlPg@o|)bw>3WZ_ z-XpB{Xgb$><}daG4CNH-dNRF7^5{LndXKQ)Bdqrb>pjAHkFee&toI1(J;HjAu-+rA z_Xz7f!g`Oe-XpB{2fU|k?s7YNn`f^~slT_9K&2-XD(T)##>(*+`37YNq>f%Si2{U2EW z2iE_A^?zXfA6Wkf*8hR^e_;I|(;cV!Kcwsbz&by$&JV2fW4hy1=ZAEiA6VxH*7<>T zeqfy+Smy`U--h+iVLf?RPaf8jhxO!PJ$YD99@dkG_2gkad00;#){}?z>$cJa*PUf+c9`ILv}~8NCb&*5J7M?) z*RN#@7EEwmTeji0ueshW^SL6i`K%B2Ss(1PKGYT4 zSs(1PKGw|sP2m7oK_E{h7vp(2oeX!5^V4wBDKI?;h)(88n5B6Cf z?6W@DXMM2GRAHar!al!+eSQo3{1*24E$s7K*yp#f&u?M9Us!J$)~SYds$rdKSf?7+ zsfKl`VV!DNryAC&hIOi8ooZO88rGwR^{8PzYFLjN)}w~?s9`;7SdSXkqlWdUVLfWo z9kY7Wr0Y?`y3?@kG^{&qx^uGbH0iq2u6xeq?u1O7 zPl0`(0{cD%_I(QM`xMysDX{NTVBe>h?)8B0Q%LuH3het7*!L;0?^9skr@+2XfqkC> z`#uHseG2UR6xjDEu1O7Pl0_u1^d1X_I(-b`!d+~Ww7tdVBeR)zAuA)UlzE2 z|K!Z~Wu*JQ4A!%S^=x51TUgH)##_Vhg7s`+JzH4M7S^+c^=x51TUgH)*0Y86Y+*fH zSkD&LvxW6+VLe;Z@yg6!?8zC*DfTE14 zY+*fHSkD&LvxTWokE>@(x}GhpXAA4u!g{u_o-M3r3+vg!dbY5hEv#n?)FD3wy>V9>9&`iE$Mo;u%0cfXAA4u!g{u_o-M3r3v<4< zqn<74dbY5hEv#n?>)FD3wy>TptY-`B*}{6Zu%0bUe<=3G4E?0oGc)v`VlU0muZlf3 zLx007<8SqBVLe+|&lc9Rh4pMRT^=x51TUgH)*0Y86 zY+*fHSkD&LvxW6+VLe+|&lc9Rh4pMDiL5 zXAA4u!g{u_o-M3r3+vg!dbY5hEv#n?>)FD3wy>TptY-`B*}{6Zu%4~y#h$Stf3cTr zD5uzCHk9x9(zE4n^=x51TUgH)*0Y86Y+*fHSkD&LvxW6+VLe+|&lc9Rh4pMrcYNvD zlCEb9>)FD3wy>TptY-`B*}{6Zu%0cfXAA4u!g{u_o-M3r3+vg!dbY5hEv#n?>)FD3 zwy>TptY-`B*}{6ZF!Q)FD3wy>TptY-`B*}{6ZrrTb6wxsLX z!g{u_o-M3r3+vg!dbY5hEzJ2kPwLr{u4fDD*}{6Zu%0cfXAA4u!o#LbcQ20Yxv!>| z&)WB{FektN)AaHhXN3Jmvhy3yC_j34*l#48x7m#Ht)JWx^0Yf_MtR`2k-zOTqx{wr zVIPw0jWILITkjKj?L{-nA2yB5JAzA>h5bpg1AEL&>5tquGv&W#^2}7uo(*TE@~_)` zRyyvo{b!|k?&~ot#rZ<7Stj=!Pgzx|KMl=Jt*d&0R;{+hRiy+<;R z+kA(x_ee%OGhT{JoEQBg>_Zab|MaNHoYxlTMCN==ryk5t{a6n5X8F{o$EBW)hx#{8 z+Qs;3uVN3M&|cp!h}Wp(AJ{lD9w`|GH{U*Gz5`OZ5=2HvDHx4ieT@a?wj6`lWZr`T-!`54n%9;Jqf>i!%XMLBBJMf$DQat^4Uzp;YeZ|5Q z|L3}{J7f3ue+hWwn@cPmT^%=xDDydKO?{a6n5X8F{o$EBW)hx#{8+Qs-+>b^Lg z*E**yE=&1HxM*?t@R!Dh7{2VkxIAxeY{!E}FD`$uQRG`cUtIq5+A$%|A&r-m zSNwUG+tL*O4u3CA=SBKuXN?PSlK-RqUk*$;yRIMGk@An88JXiA zbloc<5Am$GO4uhYBhDAjj!gV*M?~hl&KVb(^EI7%FhBKUIn=KQikA zJ~=-!-oEMh{N~5=w;cR`%V%AH$7Q`hu~&S?I)ay1k9ElUf}Xp^I&>`nF}rR8cC7^L zS_#;-60mC}VAo2(u9bjYD*?M!0(Pwg>{6JYmGfZaa< zcK-y}{S#pKPk`M&0e1fc*!>e=_fLS`KLK|C1lau(VE0de-9G_#{{-0m6JYmGfZaa< zcK-y}{U~7f$AH}*BXIpU`!e^(Al>~jVE4y>-5+=0DF--SauKQzE64-Smuuth%o3P#{thWj4ZNhq+u-+!DcM9w4!aBOJ zjxMaD3+w2@I=b+b!qJ6wbYUG`SVtGu(S>z%VI5sqM;F%7g>`gc9bH&Q7uL~*b#!4J zU06pK*3pG^bYb@igx%W^cF#cAJp*C)420b?5O&W%*gXSb_Y8#HGZ1#qK-fJ4O?UpO z`Tlk0o`K|X&p_Bc17Y_JgxxdHbbnLGuOsB1f#h+|K-fJ4VfPG#-7^q&&p_CH7va69 zkM%p4*~m5O{61#(#bI@RH#7TkNS)u)%x;>Wf9pJcyEz-sq3ZWHv-|s0Q~LfBt118f zt;eNuE*7Jw;{9!$RSkE8U^N02PVLg9X&mY$FH{CYX z^Cw-;AJ+4S_55Kye^}4oblX(VpL9KcSkE8U^N02PVLg9X&mVTJ1nk-k*tHw5Yd2um zZosbHfL*%*yLJP1?FQ`H4cN6CuxmG9)}$2QS;$`xoK*P{O3G9KS%hL6&i+fgzsOwVK_(l>5dJ-54py|7MiNUz_&F*&`Y>-54py|7L%tkVnY^ujv5upTe0#|!K6!g{>0 z9xtrN3+wU1dc3e6uj%w#^A~%orhZGhV+wYDfbGw){Ta4D!}e#`{tVlnVf!;|e}?VP zu>BdfKf|^C+4+ie=PS5oonuzB&M~W5=a|*3bIfYiIc7EM9J88rj#xII4p|D;ktQQLFg~EEFuzoMB-wW&a!uq|ielM)w3+wm7`n|Az zFRb4ixPGs{-54py{6lyI=!TOJr8?5 z4|_cidp!?(Jr8?54|_cidp!?(Jr8>y0ec?=drt>@PX~KX7r1^cUb?3v-FrINdpg*A zI@o(U*n2wIdpg*AI@o(U*n2wIdpg*AI@tR-*!wux`#9M9IN19**!wux`#9M9IN19* z*!wux`#9M9IN19**!wtGzZcd$hV`gnyVZClxuN&6uhV{B(y>3{q8`kTF^}1obZdk7y*6W7#x?#O;Sg#w_>xOl?VO?%m zmmAjQhIP4NU2a&H8`kB9b-7J<;$X9qh9^*k^aJ&+cHK-N8P)gMD5H`@9bJc^&NYI@srRu+QsYpVz@YuY-MF z2m8DZ_IVxb^Ey}`7}iyWb*0weA8xVf>A~%XZ+!mr;P%5kitii3 zy5I1IFJBzKX$Ajy^u^&@SMWabE(+hkg10?2|JGrC-v|FT?ZWWQEO?s(FAU$+f^Qtx zEAhCkdZj$q|2zM_Vez-;w!a{i`S#Q2r(@lD!1*Z#J#flw`@}UV{zDdBlg?}U_SdHK z{k!M2sUF%rc5SMk*;B7g_15&)Yg2tb)1r5(=gt1vJJtUh`L_7}zE6RDp91?n1@?Uk?E4hh_bIUNabVv)!M;0#YxbndYWAecYWAec zYWAecYWAecYWAecYWAecYWAecYWAecYWAecYWAecYWAecYWAecYWAecYWAc`@6L$d zcW1Eg&S2l2!M;0#eRl@??hN+b8SJ|=*mq~J@6Jpw_8Cj>&Pdn0hV`yty=z$S8rHjp z^{!#PYgq3Z*1LxFu3^1vSnnFvyN30yVZCcu?;6&-hV`yty=&8p{X9edVt?c0U6Y6M zi~T&4cTGC+6#E+|@0xVtFZS(B-ZklZ*Rb9-talCTUBi0Uu--MScMa=Z!+O`S-ZiXu z4eMRQde^YtHLQ0H>s`Zo*Rb9-talCTUBi0Uu--MScMa=Z!+O`S-ZiXuZMyBHcTKw9 zHLQ0H>s`Zo*Rb9-talCTUBi0Uu--MScMa=Z!+O`S-ZiXu4eMRQde^YtHLQ0H>s`Zo z*D(F0*xxvL*QC?0iv5j~cTKw9HLQ0H>s`Zo*Rb9-talCTUBi0Uu--MScWrvHpJ(!} zNvE7*f8*p`lg@FA{f(1%O*(NF`x__knsmKuSnnFvyN30yVZCcu?;6&-hV`yty=z$S z8rHjp^{!#PYgq3Z*1LxFu3^1v7_YV1-#B^Kr0ZS7de^YtHH=St=DJ~T`Q%-bu6GUV zUBi0Uu->)ljxW7y()F%ky=$1`7W=&?@0xVIYgq3Z*1Lu|U*}1^Ytr?uVZCcu?;6&- zhV`yty=z$S+H|~Y^B4OYC-0hc$}jdA4##zT>0OgY?;0llV!zzvU6ZbN4eMRQde<=Z zX8C&8r0ZS7de^YtHLQ1Sy5mdlnsmKuSnnF|=yN2;j@vdRLYgq3Z*1LxFu3^1vSnnFvyN30yVZCcu z?;6&-hV`yty=z$S+H|~S^W!tade^YtHLQ0H>s`Zo*D&$pSHpVOu--MScMa=Z!+O^+ z^@(>4>s`Zo*Rb9-taoiX-m>}enPI(anDX(TVZCcu?;6&-hV`yty=z$S8rHjp^{!#P zYgq3Z*1LxFu3^1vSnt|&yk+y_GsAks`Zo*Rb9-talCTUBi0Uu-eLx-ZiXu z4eMRQde^YtHLQ0X@)zDUtaoiX-m>}enPI(aSnoRIFT875?;6&-hV`yPdf{Eedes`Zo z*Rb9-talCTUBi0Uu--N78hqF_@34Caz^;FXUH=Zd{vCGxJM8***!AzQ>)&D5zXz`0 zFFLJ%C*Ae$u=^Xp?r8wKrvdDq2C#b?!0u@PyQcx{o(8ac8o=&p0K2Dw={QT~FTP!y z_B0^feGFjtF@W920Cpb(*nJFO_c4Io#{hO81K52GVD~YA-NyiS9|KsQ8P*>T`Bxnp zzD*D762rR0f$P7umt11fb%|kJVpx|L)+L5@iA}c-b%{yW4~O-`Vf}DeKOEK%Hy!WG z{KfZwlOImHemJZj4(o@*`r)vCIIJHI>x9EP;jm6PtP>9Fgu^=FuueFv6AtTy!#d%x zPB^R+4!hTl{N%3j{?~nbNOwOO*!^T+_mhF$PX=~B8QA?~VE2=O-A@K~Um)0hfnfIq zg54Jgc3&XVZ9De`BHev~VD|-r-4_UUUm)0hfnfIqg54Jgb}t~_0{ zol;n*6xJyXTsWn$PARNY3hN2Oy1}q+FsvI4>juNR!LV*HtQ!pL2E)3+ux_yF&L_IT zr0WL5`oOS0Fsu)3y8Tcem~?$$SRWYH2Zr^5VSQj&9~jnUh4n~bU0nG3JDOCsUOVgu zp56I)lgbVIhW)^^E8c2Sd2wji4?OEVze#1c){!SQZd!R{Y}f-l>%C>uO6k_fPaa&) zCtO&cXXHIi)89V(V!mg1QRdL8P1CU+|GsI8L1&oQ^n_tOVOUQX))R*Hgke2lSWg(% z6NdGKVLf5fZC^cM()EO4-C$TZ7}gCo-S*WDCS5le)(wVrgJIoZST`8f4TjwZ5_S(p z*gY*__hW?Jk1=rlx5d+bjHJ6CBkX>Ru=_E>?#BqbAEW8kTg|t{)4rPIabHc?eKleC z)r8$w({$^w=6m94UrqA3uO{riny~w7!tSdHyRRnfzMAk|U;a^cER1UQXW6mPd#^vs z_S^n9{#kY`Z1(=2Wyiv8E&nPz7UmpN&wD@oSIYDC{J+xQ{GVO7 zzbt2^yFZIO{r&w*1J}DQrg#5&Ib2;)OzunsD(Gw!KAKI|f_ZLKN^7(sXUcD^x>kE5S_S2c##``%JDhJRdsQ`Hz=UE%twF)VIyZPggwZFgza7$=Ds%lhY7qrbT_Q|E_rdW`O$o%mNwKW|9C?BknbJRg00OSW{S80X$+ z_08Js5&6rrZpccPM?Ukr-q~-%BOlT5s%*m#B5&6J!tA|yk&k)i?5xYu$d8UVIoo1c z#WQTnjIqz@TA=Sv&4gICA_m~SqoHM2@Uw!!a$alZ8O7*iJdxiAA z$FEks>b%H}d#_Qw;;Rcn`rK98RNL(v`INbBs-7?DOIDBPPW~a6{VSC-cwx`Ll)vlQ zkvVR!KhF#4#B=ww8<| z2|bq79ejS|s~0q=_SrXbr!gy6w^}puE$6ISePrfSq0BSpw5XnYf8@h{Z&lsBTjX{R zw5k5RdgOcGY?FTrY-Gqk>YUcq*;hv%GOT6w=baa^Wa{~a6C=|f9=YbxkU#Iw*-a-z&ii@RdB4bW0irk+iwp3P4^TMqSn*T|Tk zdj9R}$kg*j?H>!rqMkQCJ2Le=^~K1Homndm4|(84bK`lD=a21UJ@B_9u8vHZkG~n2 zV}05v)-5q)<;cXg#aWSwdGA{zb1t_%5Se=TVy8{QTuuFaw0HZ!^v|QWi%h?Lv~^_0 z#qIyuFyx`1H=h!j{=f6c$c&5aZ>Ue-@`U>QNA4V%az1Spnety*+AbZp*%y(CXW(m* ziL>97^+O)o>+cDXX|HKxBGX>yKOdQMG@WxdKXqa`)YXa$Vt(py%!>aE29b%)wjk!y z_lfD8%PogS<{XzE5t(y0ojNi9sxPlxT|9Hs5Ko>zab8Zf@3fenmtQ?~a^(ED)z4my zoX1l=@rlTJoYj%HMb6`|-g92${Jg5I_m7;PZ*|xF8_N9F=XFx;^mmL6UU`$q`ENn> zkL4rhzXjD9vtm8uzXjEM$4Ab83#uzW7&-qfsQ%~r$oX$Uwas~v^WTDMgX1FSzXjE; zx<<}_3#vcw9XbCks9v>K@5pp}HMDD|o#J>pXYTtrPNFSCnHN zQoeP|ajkRWu`O0x^}9OTXop|_th4QoS>ws9&-dNKT=C2Eqq3vsL_W0iY_`c8kyq{e zLN;wc^QykTMt%A-U%U|hmi)&) z6q$0aIVUpZkKH9Q$Gvim$i&ll@$=ztiSy(yA`}09??vXkI=mSZ`yq~1w=KUwdllQ9>XWrkc#-I1YbY7%;zT~$aD98GteCv(lTA##YJrk$(PyDtE z{m}NJf0|CeH9!5?a_HxlPyhG0j0@voycj3r$oLswwioH1FZpdR%CWsD-}d6Twiof( zUc_m85r0j4Wwsan({%c+`RUJ=LqE5C`oG6zTo@1I#W)#9#?Scjyh!(a$!|SSj`c(N z)*HvQK8eSACQj?0_-z;Zq4OdA({V??bv)9a9jEkj$1nZgam~1Jyfa>$2N++@4~#G8 zL(-iO$?tqfInIZa?|jH{oezn}`H(oB4~f5KKCC()(mze7-8kuXDwr@n{8pd?4Va(4pjAe2SbKUJRKi4pmdqw6NrtYxFT*H*M zjm$O7DNQ1C-EzX$@tP1mV1>0qY+S>1p0!qBu3!T*K_tJ~G!ZueFQJHOzXOMCKZ1>+K>_hod`3&aab8W42u< z#Fk&TXWQ%@Ilr#X=A0ZkzuwM%?Grh_ZqF`zEOLI`o^|~oa(>;O9kHZ7{n)i*yO4jo z&XFnSnNuQD{yW!2=D1fp5SeTB^;*Sx;~Kto`?khb9kyy@uK5@K+$N-RFYxi?$lOyL zJ}NTz6j$|)%ss`W-RsjYDAng5+A1>T{Nv}=p-jqeG&wT&GKanpnRvduKQeJn9@R4B z=UKtQ4@Bk}Lg#^zdA2b3j>tT7=r$lS&msm6j?6QPGaie~vx}=O<0nPtSx3+B zBJ&KS!76Knv?`XUwcSwYwj;@yfiZR7suTnnfr?w6C!he zv1E2+?k^tuD>C;NwhQ+cBiqL|;{IaN){(it=(K%g?k`N|{=)q9z0Q4#*z&%&^MKXE zxiEew4v6WD-^KSuX8a!aU}VOx>5O0VGkz_T@%!%CF+bzC&B2iwzsqeKnelr~v&f9! z$LGhoWz0VEN<9yl)hxuu_`RVTneltZy^$He?JkMT_`UP!$c*1>%8?nr4{jWp@q25l z$c*2YR*ua0y|O`M#_!6@MP~e-vO;9WZ?9D&Q-@2}iOl%@tJ!KH&h;zHXMHz_eERE+ zvw@|^v$kuVU2|0A>rQQ%-Ec|dOLl9WO&uKh)fd`iH@sZWqi5IWIk{16BmVa3O(Ij~ z3wuZASP%4wObjEhip&@}Wl@T=?wAHmjI%mv;VOaizpcJDC30S7_45}Z=f|o}85lW_ zvwD56$a$RADP8M%#1{2={c1k>&;K|lGX39l#)bJAFP6hNy6vHupYhe@<;aY?qh~~BJbvC_ zrEpxv>8On(GnSt}u%6%CD%L0Ceaaz`nFoHlFf#K)$9p0(Z@l$;t{r^_NUt{=KGGUM8G#lT)**ctWU=EkFP~$ zTz@;Xoa($lRvm^7j|5+in5oP|dVPuXqw{v7-Sllf#<6^`I@!T0No$G!N=g#lr zA^jtV-{m7B^LskJb!2{*U!M3|$j|R`i|ZouyWFT_efn?ne+_xaf8fx_lyku0ktu)u zR*^aG*y+nce&Ts=bY$XuY0}Rjo$-6$sK|`pBZow0{PwvkGUL~D#;^Gqzm~)J9r0(( z&-iWLVR0y*@ta*3nen?zH8SJ(+m)8Y*z)na^zeFa+9cK?`qrX8aEPE;8e{)BMPc-_52+rXLQv zxQH|Fhd18ygLPPaZct385C8sTWcv2RXCu?+O=m2apD|*YjGf{8#{7(_-C9OwthJt! z>ag1C)>Mbp(|3)`_&x6DSpRUR?dFHr7~@-gJufihxA&mPlzHvJkvZ03t4Ah=A3mQO z@)O(NPevx@Ik!aST!vm8nR9%*XJpRZbjGjwsW;1E{I1sTyHGyYw9Ac+ocG(T$D+u2 zf6ngQc45fFwef&UB6BUh>+6xZmfo+$_aP7IN1hm&{3|>enQ~TG9GUXB-9EM#$Gzvw z$ozI(z3LaC9QdIRWX9v-W$|1Xr}H1L=QkF-A7UfVOG6{`w@nX@ zOqoqqiOjKPzVlwlPYjpd8JXDn_J~Z(=j?-#fkO2k~$7K6%6zZw2PJ@3g<)3``$x@OEVS_S73A z)90t`8ksS&@zOU!e#Xe!k3}ZE`O%Tde{!?Pl+*pq*Hif&ZivirCmtA?F*56)k%{xe z&M$}jjPYmIkIdLVyJ=+Rgh4AtX09-uImGAlBNLl# zLCn`}8QX<(d9QP1&hh@eBXjPiQzz!9?~VK>#&++s-RpMTcbxTBeW&p&f$6uats9yC z{Pl*B>F1`?|IN?1uuR6wxVl(A`Y{--JH;(BI&%D0wl(i$T`_D7#hU^siu`c`8oq1y9x+YuKjlU!Eg&o`0?ekvb z-;ZxpcU6-Z^Fx0v9y`2iki> zLprTdcgQo5uULDtx&{p|w&QZUj%k0}^uFP5|9bbR(pAgf9Qf0#KQ6WJ z6?y!s|HxWzaZ5-aegEEBUHe-Dw{3e~cGc1S0w254joFGX_YZvbzwgYh*!%XtAC9^= zo4fFiz~fgPnq59@KuTY|>)k2;3<*p;U#&JYFmX

mQ&tGT$yqv1#HjVC{^s&VG$RW<(n zys9jDz#oOmb3AUH%n)Ajr{K3lS@ncM!s=}FH4)h z8~NB%zA7EwJRa-!kzbdF99bOqx35dh9*o>#pV_4szm5FejQ5B`SnTszt>NGwn(qFedU~WYFX8FI%#C<@FmooJ9?X1* zrw211;_1Q6hj@B0^C6xd%zTKa2Qwey>A}p0czQ6$!qbEKy}-4DxrV{DgZYiXwS$Qh z*AAu}(<$Hl9M^J)2bYih#EIhv6F=@B%z5Di!kjOzAgqT8-!f;>&ad=}F+V=GPp5g^ zBVV%qTb)Mj5&7A38_Q-o~ zyK?EP<03nzh#zK5!Hy}Iam|>59aFGl3U*9|{Kc4p9aFGl3U*Avjw#qV2kzNwTxrRd z56Ad_c(>I5k;rds_DSiaQzF0luNkEi*NJ>ppE;%HK8o>QxzpT|=R!K;momxExP~c* z@eWVV%V!?&xXceQ@i1?|4fY*UVm^VV9e-2FI&sb<-T4Z39)q3VVCOy9`4D!Vgq=S_ z{$gH*oo`|1Vc7W@=K2#q6Xv=UKNHq_g!Lg|JxTN9I>KDv;yS`ySK~UuTo2KB(<2u4zSL1VeIkLBQJ!d%B%CfBYWD<7M|w| z4Q4r9o57UNH5<%vxt4>8hig38Yd_d)LfCsl*n7i}Ufh?#^k?qZVEQxnaWMUv`#YHa z%zYnBf98G=rayC^2-Bare}w7J+*iVkBknh0??YklPht8z_l7WWa(`zY?$==N<6z3< z{to6?+~2{(V18n=9Af7FkvyCW_mwc`$o(eFxpN;1QzzV?!qg%6`>^-jF!KiY0u_W`6pc?LvR!IW76=Z#=(+>2EyOh3RiR?}h1aJO_qpQ{JJ#)FJOaLV6x2?=Q^H zdkvU!c;5k2KJP(bj?4QIn0R<^0u!fY5}w z@=gjS&yF)9^S8%*6PYsK$lraChhv#e4CW^`%OU3NUX1xUm#c?F<{VGIJTmA0&5@C* z!xq~`rVe>8#BGFwf*A|E=Ykmvy#In33%nOIo%dzt=RF!sIlNzk zDSzP+^~dFX9O=Zvdu^Dy;(c^T&+CwP$}sWst{LXMcn1x0zPy`;sR!O!!_*J&vSI4Y zGO17AeUnZ-^G+P5{&`mp(=MjdUgoDwd9O_#;=~z%885tFh8ah^cZL~XypM(%cf6;D z8IQcbh8d^4*M=Ftyzhn?*SrUZ8SlIwhnWX>Zw@m*@ID=8-rzkuOnu@o!1;69;19t0 z^V{GR!1;6C;2VVeg@*v+FyJS^I1G3TGCqTO@EqX$S#j_mV9LacfH@Yv1WXKg6d`{e z8*UOz9pWa1^t^6yfnd%BM+oK|afe{e9j6GUPH>H2>Iw%5rVeqFVCoiU38v0*nPA!i z#|fs5aGzk>4krqxO>w1Q+8s9uCT9F1n7)B81k-2mh+z5>ei2L`Go8L?e)^>4&{y%7 z$WI@}Yl7+9_)ai=9uEp;EZ|4Mv^DM-Og*3aT&!E_zt;zmX_w;`M5et?UZqXQPg_5| zMP%Cgtpw~E6WFy0uxl2~&sql9H4dm|xaCFu;GDyGIl)DT^YVkE4(G=W?mC>u6P$J! zhacA+#_h*}hjso<$C)=jE+IQB5*T@_D%Woc2DKx{UMc~_mgzoy#J(laQKZAx8L}6{y7%uo-g^W2goPU@&asFZA$N7iphpf>k(yOM^Z_Q7CwjBDo<H|q{LY7z!zO#Mf8uA22Is}K6Kii_uIpGc8`AUZJ=VR#Tx+o&7Umj^ zb+RzmW~`ruxn^TsEzGqX>uq7K@hp>TKi21x&NU(Hc44j+SpmgeXBleM?x zAx_rM!sKB+tbfZoS(q|eKMQj#(}}_S#AZ3f%=%pNb1tmgg*ivo^TM1v>wIDAg!R8L zb;x>Zn0raqHN)KNvECUD&sFku&@lIstdEAdmt@^E%)KP*sZD2{wfR|p4O0&5vSG?+ zy*A8oS;q}?&B@vpnYAr2*PN^+fw|^njS0*(Cu>h&t~ptg0&~sDS{0aUPS&u%TywIv z1?HNQH7_vNoUDa`x#nbz49qnrYiD4tIayN!bIr+G8#u4Su(m~Jtq`1_S6FWX=jR*N zp}=`Pg!L(KUY}vz3Y^zx{;i7mw|RYrbuOl}{>A*Pi-9SJ^)fK!vyKMlxU8>%sW;Xf z!CX(Wh6v_*lC?!J*ORO{g1Me#EfUQ2Bx{slt|u*r>q*u$kD^>;QU@GtU-YDd#JEB0nYEO!kUGU zKX-vOWbS{?T8@ zdgi=7SSj6uS6gnH?!l{%>=l{%d7*n`>h11JBU7J`-x8U6zG_fp>i?ztBhxNh@Y`VSsEOuxc!hv{#o(+|y0|Fj(XE&e?D z>CbreF#R0g9;W}};lqpz{Ct?U#*LR*UjS3jIO;II zxbZU1ym@fxVcHtU9;Qs(dzfS4Y23?F!j$G3Yc~=o%S+6ZHhZh9vF8TCQiI%nEd$6mV@UEQ$GGP z%yCU89`h5YOW=6vyWVd?>o7p8vjdturXw^qhah8Zt7t}x>W z_Z4P*;lzgg`MATCg&DIrv@l~9w^qivH4iQ>%$UW|g((wv7v@+vy)ZH0`oh#3&NEE> zILt8Th1(2szBtb?^?(ZvQ$IM;F!g3R)F)0g>C`i>HB9~EV8gVp>9m*mX;VB*^1yhQ z{w;1KOquwTFvr5Hgoy#)5+*i0OqiJQGhxmJZxiMm@i}469nTZi!-VxzVO>X92NKqe zgmoriT}oKT64t$hbuwXHO<0E$*6oCKK4D!@SVt7r9ffIM{8*TC#CL@`cRW~_I>C>H zsjH)MZx*Hw@o8b|)^ezG{9Dp#3%p#I_QltQXk2CBC1?O>weWKtz&ai(JoX45U%;OCEO_83*8TO%q^Efm1r-Ji1 zQ+gg}%1=D(C1rm0@3I{BfPyKXy`f-^%brm%@nrd4QZR9{#}rKb>^%i@UhGK)bH40V z1-ow;>>gaOdvn3=*#*0o7wjHiuzP>O?g<9FR~YObVz7IQ!R|Q*yB8Vk9%Zn5m%;97 z2ICygd|>-Z%Rbe>Zw}wSa_;Dt0+(OezA}FC3xRK+w|(WH?#~4tu+|QhHmf}o_~~vt zR5ortI`FbbcBrgz-cx}$`elbopKN5{>VX|9uU!-OHC=5)hsw>JBllRoV@m(MTgQ}t z(~%uhIX!>rn9A?JrfHfr;~xcisz3{3l=keqhdP=T zL%mr(_33e`XXBy%jgxjU{&C0VW&Sxf9QWnVcBq`NS8Ny3d#@b#q91tl4wd~@jC<6> zUoIEhm;7(N9M8A;mK`b`caP_LcJmIEe|`2wD6`Yz9V$B=5xGVCjww&~OFO2&op*f4 zl;`;_9n;^Qvb1B00XEK?mvu}rz{WxWU1iP=2FX*%(f zpS?Qm&#?U&wm-x6XW0G>+n-_kGi-l`?a#3N8MZ&e_Gj4s4BMY!`!j5RhV9R={Ta4D zn@)c)Km7!@Kg0HC*!~RLpJDqmY=4IB&#?U&wm-x6XW0G>+n-_kGi-l`?a#3N7PjBY z^jq`LmtgxaY#)a0!?1lAwhzPhVc0$l+lOKMuJp!NJd$$zxzu!8j+Ti_dLk!hr=I&j;A=11r#kVnWF=DzH^W2%C|ii zxMP#9)u%Q+=OyZ@;GN+jhE8x1L*OEYz(ov!ix>hIF$6AR2wcPvxQHQeaqfYOwhLUe zZ;2R+x(ZAi<#iaisN0yHw^3f_foY?>Edm#9l+yFIOZoFQ4P3N!Opkpa#8C8&6i?n~ z0vCNLaM8yC7yU4l^Yqm_S9{!44ZPZ3ovI%{GbV7CmpWDV9{yb5m8W#7u5rWYz#|59 zs&+c_$-qDTv2*pd^M?m+*K+6T%(_Pce?4u->iQ==82GR59jhZR8y0wzMjfkbJ@8K8 zYY*P8dgw);1YXpAtLnT)a{}MH&X(2X_L~>@rGcAQS8M%k;2xiETAg(0cY(`4Z(RL# z@xs8Zer#VIzu^18H_T{PZMW?Yf%{MVXSMwsF@2qn)~kLpBIX~pXr1aV^B06X*B|$L z-S9`>2%P_0m;e93YrZ<6uDtQmz)OC6rLNmevCKx@bAE1qefq3fDgVWtzX(h@+ccRP z)9-$#?$dKV44nU4x8~jP-1GmQj+_5oU4Fcfr`xPqb@}lkKR3TFKVIaUen{zgTq%Ek z9(DQoWc0nf{_66244l_rU0#oY^ZKjH>oIU%e|3312F~lRF0aSHdHvPp^%yv>zq-60 z1LyTum)B$9y#DI)dJLSmTV39Mf%EpP%iA?@-jC|?{uDUxM|F9B3Y_<&y1YLH&ihea z-k$>J{irVQPl5A(RG0Usz-ftgdy&zzc%pODU+nvdJS%&GZ!3(TCF&#i%(Q}b~fIiFMWaT}O9 z)pX`m^E0Pf4s)vIGpBl7V$SE6P!4lyKCcC4PR-}Fz|5)nycU=_HJ{f4GpFYBT43hX zd|nI8oSM&TftgeDc`Yz=YCf+8W=_rLQ+a1OkD*gd44rCX=u{I!r=ibS4hi$vOO-r`Xk!PG*`snT0M$0Zat~C16*hYW1KeY7dZLy73d~vVR zJ8hbVbIC3%l{WlGY_CIK+p2Wl!?BHa`SzcsxuYY`*sWD*)7@j9XEtqI+VAN2w@bhH zz0GescDf_etrhnsHI885gCRaZ#!n7bV99^Q+^L`PFgC{8}?V zlxpUOQqBBOs+k{3HSLHJM~{$+HroI_qIFn z$I|)jUJY~Ii+_GoI`gzR@11w&?9zr~BJaBIw9;iQWBz}3{iM{c=j$Q=qW342mW_KW zaQAudmG~d?A!+tNG2!YJRh_n%}If<~J+zH;Xp(x01H?HJca7r@L7%n>ki26G3@T*90JGxr!ja~^Xa z>CAcg{2Q1#FQ0z{Gw0>=Z(!!UeEtp0oR`nPftmC2`8P0gUOxW@X3op!-@weZ`TQHM zV+#(~w?zzNYhnmo#1OcMA#f2x;39^=MGS$97y=hD1TM}!aM6x|i}tOnsjI+69R@Dy zHgHkrfs3{XT(nW(qU{0~Z5p^}>%c`H2r(3WBgPi{OyHs~1uptn;G*vZF8XRHvlt_R znRmG^;k=l4xh{d3ceyTsnRmG^fth!?E`gbMxh{d3ceyTsnRmG^fs3&jxEQm6i@72& z^DftC2ttnckz7&wsu#)&%kJR@qGqHyNmBLFxp*wpMg^wWt`euFizhj#_3zdIDNwyr*9kM^vz?OzJ-j_H=TUaFyV~{{qutfE&lv5lwtdEEceU*^M!TzRpE259ZTpPT z?rPg-jCNPsTr$3ajnlWcar*W)PT$_f>D${leR~_HZ*SxD?QNXCy^Yhix3QKT-~83A z?XPhf%NVCIf^ix<7^g9XaT;qFr!j~z=6f)wfM=M-EXHXpW1Pk~#%b(hoW?}PX{=PF z7h@>nG`2EMV=?121~g7%K;tw9G)`kc<1_{|PGdmhGzK(IV?g6H1~g7%PvbNuHBMt; z<1`jFPGe!?G!`~aV`1Yo7B)^}VdFFwHcn$<<1_|0#@JumTx+lJH~x+1pT_LQI+uX4 ze8I&Szu;o*Z=B`?jMH3!ahgLg*0}`CEf~WO?BEM?7q}j5a~FDFaGJZQN!NVP9{B@n z-+{RiW9_prCu5BE)%97Jld*KPuddI+oQ$Pg`&!dyVNS-<(Z0Gq3v)7-u6-ruf{e8f z#T=2b_T8A9GDiFA`fkikSvuNR*LP!X%F@xky1qNQz8iB>W`p*XeRrE#-{u!@ST+UE zq0OvI^AnrAk~ubeP0utv@weG(`X|{S-Rymy$vS^rTGjd2Z=UM8WwQ4RM!$sT2Ig}E zqhGT3P?^sS>FAg6+`#CU@Z7+BZeU+e$VgwA-_$=J+T&W*0kE%=iX%+MPJAR zzBTYJfcY+f@vVV(0nB#+jBgFR3t+wrV0>%fT>$$svJLU+sBcX73>&sHV74>Hshu%S z?F^Xh44CZQe&X8ys09ye=ze8X8tX`j_+aSA2wu` z3*Y=?e)IdWfFFa9VgF~3N0?9gMIJZ~0&^S$<~Rtpe%wb!`pS&a z{PUrGy4J>YV12gLV@&djepmH))0d0BkOz)!!5rIyIkp9JYzyYt7R<3Nm}6V8FC&=m z5z|whv~{W)po}aFm}LR8EMS%e%(8%47BI^KW?8^23z%gAvn*hi10s@Hu*PKLP%`YbKl;<=rkEe^7p(oD&540ICkEDj(B{Oz zoD&0UKWKAeVC@HOP7KUBF|d9cU_HyqOGf(2%-8wnLwj7S-x!#~wYsF=NH!kEvn8+S zcU8|l`f|}1@}S>oHqQy>JSSMc(`=p-%y~|*ey7m{m}LR8EMS(! zGs>l7Nvv1en9JKR9rpSTVI9-vG|0GC$GLynItBCN{ernZ0_OS%nCl~8u8)AZJ_6?Y z2$<_5U~MC@W@_anBYkDoZv6A1J+9?i57@6gkyrG)s@I`>x#$ad;F=ehYhGZkd4aj+ z1?HL;m}_2Ou6cod8M$ug(^1Em?in^|9oFh6*A|h^wM8)37QtLw1aoZ>%(X=@*A~HC zTLg1$5zMtkF!prlcR&fuwM8)37QtLwH2Y$`+w6V0SQeC#WdXA+V3q~UvVd6@Fv|jF zS->m{m}LR8EMS%e%(8%47BI_V_NgqMQAYjt$C|j6QNJIJVZ(H=U#BMH+O%$N>#(bO z&6@e~e!=t$=2|(JYvo|Bm4mrf4(3`pm}})=zc+x4^p#o1_s@s+?%D^ysVo)lIajRc zcUA96@a3W}Rx{`!n6uNqZ*VhWku# zE%%v#xzEJznf950xz7a5eI{V;GXZm-37Gp#z}#m7<~|cJ_nCmX&jieUCSdL}0jIVi z1G6kBBg+D2S->odJ%|5gduCV`H_VfsFL@&0y*2 zTf(@m=R6_W?)3>y7`o=a+-`>XQo7^~k zs~e|pc;obKZ_GW1@WnlcVD32tbI&1|dk(?ea|q_1LvR|K*!_LESQeC#WdXA+V3q~U zvVd6@Fv|jFS->m{m}LR8EMS%e%(8%47BI^KW?4L=jA`sCzPzwuIyjAm#WU>FxY*Lu zxY#(2i;dH`*f@=gjnlZ;IE{;q)415!=Yj0~g6S7bzhL?W(=V8Q!SoBJUvQeEuso2F zp5`blJH zW9-XCU&sS}f$0lOUtszI(-)Y&!1M+7WlZyIR^OP8dc}0lxHiqvnSGkOGfs1Q#%Zq4 zIL!eXr@2AnG-qg><`Rw59HViXdo)gSlE!JS(m2gw8mGBU<22`KoaTOweYsc`l#yit zvn*hi1e}A<1`O%%)I&hc)wu!1=BB>e!=t$re84q zg6S8W)y+yd8vwOsb?p2}s6boxSiS~Ifyr!^zv zv}RI7@(1z!aV9)bMV4gp+^mP6R%=1TJo<9Qf{1KSvkBrm#BQVb&fqDK2%=1TJo<9Qf z{1I5&haBJQU|$yIALU~H!OXv<|1UT{#rz{bWRykQb~_{H%Lp5$gE1F~Z*I@9PwV)W zp4Rb=(>lI!TE{m|>-ffL9p5;u;~S@Sd}E&nviA$7UoicG=@(4DVEP5qFPMJ8nCr#& zI?78%x_%q{w`cnJth_xq?ai?Iqu)q5zQu8W@``@bUKg`Tdrpkgo)hD==fpVeIWbOq zPK?u@6XUe!#MqaMzK{p{0@D|mzQFVarY|skf$0nE%c$SCIlj?-I-Ud5J;R3QOu@E? zO3#^sdCs&tUC)`)UiWMn6|Gz z?Zq;CEmMwfcclBWF#jkQ^ABeJtJD84pOa<&ksmV3qV?3y0)v?j8>WNxU8z2sOon~h z2WaEpv=7iY?E^GU`v8s8K0xEN570R612j(i0F8Yf$lfoQe!=t$re84qg6S7bzhL?W zYg>ptx0VMo(sj<^zdgI{pAYSEZQ9#u^+)Gkuus+QPhQb)+AC`|Y0s*0+Ouk$_N*GG zJ*&oP&#H0Svud37tQz}r(HHVSUtszI(-)Y&!1M*CFED+9eHpcng%-qrc@9iReIw&q zoa@(q+U%((fOP5!fT8)I{k_>xPXOuE696L}dIGf9?+Ih-30Qj469B`n?s>BLSma0h zdt>Sez=nDP#)XzewLQv+vM~Q(<{!-bTl)V3Jp}z;i~8Ned1hmjOTX``+1oH3`PVsf z=wR5jWL%5$D;Q(I2Ip7stq;ce6@2T1aef8g`e2-2!M8pb=U4Ep561ZweCva8eg)t9 zV4nxF_Y0<9F#Uq*7fiok`UTT3n0~>jj3wlOjC36z{I?n%{`t_}UE2bj%3}8?ujn^D zTeC@JG)`qSPGvMsWi(D@G)`qSPGvOq<)Sa-fxf`>1*R`BeSzr0nmu)6ke=RIOHc2zG2TIpF<_J4{Txi)7;tJUEIqX$#;I+ow#OKQ_rVy$ z?o()<7^ipNIJIfUwaW7Ui0%#ZkLOQDc~je7tBkN=I{55=Olh(6F|*>u8&=8(JAYU) z@xhtK&o4bHTXfD0^1=rhTdUjc(f>-bRTDI_m zDzj<$>u=f7UrsQ7x^YA4*lMitmisr7j@OPc?$!S9a^}3z#_yi7mGt~_l<_uw_mbUO z4mIBK&DPTX!vV(Uw?0|g{`*Gb&laB|yFOQGoDV%ss%G~#etD11a^H{}j4#@$n_Sto zyK$Erd&$@_XBcnyUO(yjU_0Z@KEFveU#+ci<<~b$cRAAdl<)h?&D{?(&dwPkjauzn z*z7h+S~c6&xW}R6rDON{#3CXbc>)p%t43DW$BzZf^{QYF(yzoqAS zDrNUMQ{>||cNv!*G+o|ldV}%LL#NAQ&-5@Jws5*!+3Z~7=XabTdr#CJ2_LT9#RWs!E zb_ZmzZ#rq3JbM2i<3VptmKP_MjF0R*S+;NWu<=tL+%A{D`K0k$oo<&27rkJ7#f=kX z&H6tZzxmZz`S73(1^29+Izo0@u!Hf7&kvW83wAO-;G1DG;pJV7-(7#0?DF*P#!a6e zD5q8&Y`p)+ePqFtCm0|0$TjkP$8(K4TyT}l`{*CWUpBZxx}M$DxZ%vpr0j!>j8FLG zEIIA7>x{2yeVpv|QD5WzMjasU&mCl3FK;PJX5M1_?VA;H>TQFK*ZjVj)EjuK@!D%| zFMD(yX*~bb_2i@R2q%c?|Nak?5HKPjjMk7GF#YbhH<-AyGe&1#~bh4zq9PzaG-I& z=6z-2MHdKc$;RL9**dmebENS-M_d-S zXjEx@%(jDLyLl%YU)^J3-2L0_jn8X5D}MRte^{QkdiS3A#GMBj-~Nw#H=Yq6KWu<;x6gNvCtqJY z^MlU(I=^$L;kwkO)oM7A^9{zSGv+Ac-5OWIyVwpZGYMYdzwzD2fg+U`ZRd)gjGwujnIMz)jM zenz&R+O9^ntJ>a1wzt|2N4CS-K1a6C+HOa-+uEK-w&&W;N4E3Y{zta|+Al=*3)){q z_7~cZMD`=vzeM&g+V4d6JK7&b_D9-JMfOuY4jmuae^u@_DzabG{w}h=(|$0rAJqOa zvVYWmGqT^*{xq^b)qXazpVj_1vj5e7IkI2Y{yMV1)_y#)AJ_gpvVYfpKeFG~?}5ng z0sT&h{7%sChsf^-{jP}ouF&s|$nOpP4$1i)qTeSuzfbhLCFggGe$V9mp3(1|oZmV6 z{gdIskDC?I_bE3g*L-W0mAh}Pa`&xO&Tp-$ z;|?k3J;Cmt!QC@3Z?IwBz|0$%Wdyr223N+wX9b&@XH{0tXN7b=bFh2n!9DZ9-wrnX z?ZEu)z%_NCtlZUs;OanNU4lL95}0)f%sL5nbuzd*8CbW?Ce>{)>o%D02-v+Nf$s?V zSiWnp;kyRry9VYv3wG~paPMs3yAK<_`(VENV74K4pPDu#xHcrPErJc(A~4$`Fxxb+ zYtw>j(*oN@*syH`vuy;kjRm_lHn=u6u&ss-+iGx4TU}OO)8?0zyEZ?#Hb2z#9cAV0 zJ8&QN9booBVD>@yjo1f)U0+ttz6|!RFDrL_VmbRnT+2QY?E2Pn_N};&>s!lRA0607 z<67582mHIq@w3G8pZa%jy~XoOEx(>=>DpdQ)^9m{1C&~vd1b!kv$Ktl9`i%~;62lg zkLj~_-0KSa{wxiD`kZ)DpPMaR|Bm`^WBvcAcE);L)a&t0UefzTy{|F88IdQKo`aLU zak@`Ldb+=H@@t&(W1RA7obqq1*P~oa&yWw?6ZwKaF!Bq3V3Y&?z$hR5fl+Sw1LJwX z9~jRG{=miaE1TldGiPs{?juM~_cu;{jZ=P%Q$CIH{P?@*_0_+Z|9#ze9e&>m{=WRi z!|(3C`OEpuk9+W&AIz~ss&6)S0CVgB<`@L*#vs9sK?27zu;Ew+%&`pEjfu+Lm?*e0 zQQ+7L_8eP*Ikp0Gj0SdNwBW{Qfnz<`aI6RBSP#rGBiM}@gBvpjjy+++u_u^gPcX-@ zU^j*hZVVeZ7KRPS!eEYt!5mYA-IzLXOpV`*V{_PWY!2qw9LzC3m}7ig>&Ezja|N*B zTmhJK1z_#hY|a7f<{W~Xa|oQffDPv^!1|46a~EJY2U70lK!TeC32rV0{V(TI&@Xc? zrQFTQlygo7<>H(S*v;+Wd%)&)kO$7~fH_A5<{S~Ob#p|)%{Afs#O9h{@8+7y-8@y` zJQePPKWK|)Y;-Hy3~P(PY>U8bi@U8bi@FNH)$**zBk1^VE_=COrLH>=Yb%S(j;1q0HHhPMIMz_Uvzv$RmM&A5mYPpZJnGrUn?IY_*#u`3oJ~-h`M3|B3t4@M z`kJ5oirUZTJ@r2G>5DeFmNsD8fTy*8qqKJ$n=cCEzkIVar-6MBgzH)^EWQ1B!M%U^ zq;%>zGb|5BJpFa4(Wf@26qatgywv|dn>z|^E7r)j?KabF{CA6EalXX)66Z_k3uSb^ z#Q75Xf{pJJH9bQf@LQ;T1@or&sbHS<{uL~X`mJCYH9r+ByXLck&&09!g*?y~@sQ5UWYR`=f``+KYSn*t2m}p zF(26FzDX5p&7WZD*Pnh<#nDIHW<0cWhl-oF9&fzPBU@CQ+p3sX-0Xw-E$+U%sFS{~ zIu6bzxN8INi8@1HVCDhr@)nq9q`R`9KJ&c@mo5CF*|OqY0M7%%p7q=_o`btq+_hl4 z7B>0}OYV6Zr{`J1^Ta(hZzViWu;#gh=Ly!bl<+*kTE&lBnTOiFm3V0~5( zr00ou-`+>0lf7Rs{etNiOut~~SLhe%^b2-=>nyK-*Bl35pM8CE>4E7ei+_JP20JF>J!LbZq`ZOw1UPamA=3^no=ri>Vr%{!^! z{hu3=&{#W=^#F z;Om=9_w_LNvC=2EyqoP&&)VTI_RP1kj%yb@^yoLT{ob;*nD9i8*Rn=86uj}TFK3mj z7kpN|m$LutV(oVDz8njEq3q6=IA7v?iSs4SmpEVI%l^w6M`b(DEc%-59z7!a;gX`? z|E2L^S=_1U>(4pnkgV~u1#i@?Rkr5QMPI+cGcB@brx)zUn2xJ`A^-FRcD}^<66Z^t zFLA!4u6M!Lv7N3Mkd43G>Yi+0H6Z(`N5Re}IGf;Xf`9iN*Lv3`9y=tMC$hz?+OMm~+M)Jz#1^=-5#_!Ez_4c0f z=_iHFi5Ko6TMsUH+dX!dIqMhfeK{7+N8z1vzQp+w=S!R~alXX)5?}T~tNoH)dxU+H zgp>dNOSVtL+pMo_*=u=r_&WtRY_=@BV?^;i)3@EyY-uy=Yr<|H|ClW=73}BM$jCE& zft@d*FQn5K*!dFYOPnvM>s|15?4$$h$t$N9ZNk9g>&b!+1v{JIY=W~1{@r(6>s|Zg z>vd)IIYnD>`Wp4+usaKO?_+Q_!Px}=eB3;wxOvE0{U+@(Z{zH1&0Dgcg-xej&XF{D3nK$x+6*UksEq&6gmhx`X8;zfQP2}cndK;Hb7kPA@UiMpDvqMX{K1jZqdx>4Ub-UKG>D@)19ecmx{EG7{^o!q}e!=t$ zreCo0TW5J2Uv!Wxf2Qaw9ft>JULapCEA|oj`sUID)A2j{x$(}I^pHJ2yx7XS&6?fi z;gLnz@4u>>4Edqph96%n3zioA$jKMUiMJR0%;#OD$B)Ie-j`#cFO<>w66Z^tFLA!a z`4Z<#eA#>Mda%5HZP8!{Gw!2j`!5unc*%;J5RGWZPO`curAu1Nq@e{n zo8WAMvk9&p@LcO%n|5a#`S6~it+?R9HnR8Rg5CQVoK0{xSoi!xd(xbJo$EF1XVHEh ze(WImWb-|(PCAx%x(|?Zv)z#{2lTvI=KZ{@@!+%j$);TjKJ%D9a^BnH%Oyfi)(-U^g22B7Q4T^H}-02w#7bXv-87O$owYFR^;Gp0ae<@Y`1vLP)j-Lbf9#a%1z zTABC2RWfWzN4wUs^nT}ZId$>Lmj3gNm&xKQZSP_j@JM%A`<`Ph{n<&E%E&v8Hr{Q= zOQk`-!;N1%`BHhHV{7A{`*fG}4n5HL;<-KK`_3(m-+Q5_GEJ2-6A9R+{@B^eRJu-rPo>${CLDrd2HRHt}b6X zL}Wd?PxxzV-B0*L!A*PJDvg`i8h7Y?-(cyod%>SBzD1sTyRh-T91GVUk!R;ioG)>{ z#Q75EOPsG-W&ic~YvtI%r`zwfXp`$?{CAy~ju3yuaiXp0hY#;(UqoCC-;Ds_`Yxm$>>L9E-1GC%xTMPM>Ra zPuBXZr@UTOu(JuyCODhm+5ykC-nA)HuaGZ~DB6nW@4Z4EY*Da#AA_?A&ZhcV;rY0A zXL0M!wfapyPdr;^Uu&J3{VZ($w)i$V`RLcNe;_!P{XQ8d<2t{FbUF3qF*5OqSB>}i z=P2n=S)^YwZ-gu!V%JLN=ZDFw|9;bKCaybF8lUr?@q^diDiuF{Wc>54gXOHAUl{+e z{Vnq0ec!Ce!Px|NZE*Jt&R1}G2+SMWNtfr~$`a;mdW)R9%eU|wZuoqV9QMw4#=n#X z$@l@bpCmLHI7rT@SYqjp#a%1zT5;FPk0%e4OPg(Bb>6W|96Ll>FWSt~zt?f(*PCr> zyvY-{NWE7#GVb@tASvHdl=PX8V#ci;7! z<#X=!gXG9LMV=jdzvBFg^DEA;IKSfjit{VZZ=K~m>yY6xp~aTSr#KFkUrvzaquxNC z#n(5N?(1Q#y%0m{-!5++_p+7usi9Re;T@}!;ngKUHv4RWrT0HL$jcq={-OT$ljO(k z|HIM`pF2@bYf-TGyDJaRg@cVvFS)@^x}5L_kTY^7M|YN*zX}Bukf6OzL4&GiSwm% zP}RP~`4Z<#T>ba&h4?xaD+kFo{jKiFhy4c0j%O6?Y=W~1&L+5az;ms4ZM7|Kk-OKh zcUCUg<`&uY-J;!a?_+Q_!P#IR;2%1pL3^}~b?wh#KMR{|t*Nr-Y0E0m=8*BsfBpJ) z>8I)7Ngo7hddg~6=jVJfQ7R^`Y22#81ZmZ=fpPaPfSyDk_b_rH3JamS&fW#HcZjNhy`S{fXD zo$-tXqvX~p7aBKSGD_B2e(H+s{fhG|&aXJX;{1y9E6%StzjcYbLeD4{^k2ntR zZa7UU?^|y5%GWoS9+-|g>Gy#BHh-op+F}8&4WFDlQ@ZBw8z1%647qF37shQ*m?8J< z@}2SAFkL3Dztni-yVGR%qs*_*gJ+>H5YqT{bvlru|0E zp1xh4+2ao5e;qqn9=z!;<97E=mf=UtKW>dJ!M`xu-}a5mVF{fExV(H?DMUHcN*&%&nuu2W>~HJazBt7QBZ`!&8@ zWaoWy@T1Lw9QD|)#%Fe$C>@t?Z~WxDw@F3)&5e)gH(tKV8W=y$Xmn>}i*taa1DCH!`6TaJ}!cl5S&$KJ0vzvBFg^DEA;IKSfj3jJz+>MZXD zPfnA?Cx3}@iQ{n5ep98*5iP8q`1nejHAC9oTULRxeDvK6S+@Fy#y4I&Q*I918=v;!OnGurh4G17&XPAi zY;WxM43k%Q&f97QZt}jy~vf!pDq%={QU_>=%u<&xc8yc5_$c;B11sHn@8R=PS58=$@7$Z+P!q zo`Wk(So^VIa@MQ&!f&Ym$uN0pgE`iBl-3$9j~_GJ(l^>^xSTr3&YlOy;;t25i|6C6 zm9I9wU0$vnVE1t>ZU3U<$^rc?edMAE((a3bdw(!q_reaeJoMG?_7g`BHk&KA86)+d z9%h_Xj*<&E8e=vW>)xwL$4|8M-PRZ(SDrc5_=UZO%QYJmd3Nmmit{Vs|SsrThBk(t}H{wden){u89_#j8iXXShz+ zsIQ&-o0a|ZODD+sBbFQY-+qETK7Fb2Nq5~QS2SE=eB>s#N#*kIjlD0&!t({lv-2g+ zmpEVIe2McV&R4Cnclt!XEyvh13A@}qMRwY;;9gy)%C>71b>_*9r^&vpZnk`0H*uP@ z{i?6=q&26@>3iL1?9WP&S9s3ie2McV&X+h};(UqoC9eM0dKY{hyJYv_GO@zyp6t2H zaQWiQf}KrpHo@5h*A95D^{##MuVM23a(icG**}L#?;VPE!@ZBe*#u`3{PW?t5;wB**bF%AW;v!)ORJNPrS0AQIw8~W_)Bt9~rWA zZ{vF}x>4qBxrg!W?ox+-V^_d=oV$k0#3~@#`c%XJFaj1+Q&D^(T{FuyycOM{E ze0_lNWu^YI*_2ks-j`$Hxhmw1zQFVarZ2GbCC-;PU$x5KR<$^e>{$}C+P_rPjUMid7#aET&)oSE=S!R~alXX) z66Z@;|M8BH;mg;t(;D}ceYUi^C$H%qljn9X*x3Zy;6AhgyLKQruJx|HbygqgHLqwZ zhIZ;BXFgM~dmn?d3C;%R#Q%_n5AD%5)^+}l{VZ%wysne9A9=aeJu;rpv8$aX`?u_2 z^}NqU9c9m(FEPIDu?{k5XjkLrTXc{MyPsz~W2+AG?V)EGfB0+%8PlY*@r7G=lpFRw z)p+pwr^&nP8AszhjtOvmr#&v-t6a2FY~yqA@Iw+3fOzoQC%toIr6%Es4Q z*~d>fL$>L4t=Y8gbcS^M>T2T#Pj!)XFTcvz`*JMKmpEVId>KRN8fV=e#w zY^-DNOPnupzQp+w`a)Ug3+#MJUGD}Sz_?$Bu)*`s2p z{VtAW`Mj;9>X=)RE}P%Gr3^m&7UO0oZ7E0XJJ5Lc)Gc-IVt?bSCT=Cm8r@{PYqpL2 z+O)6nJ{OnE0q5Lk++f$na^b7Jjc1(EMD?j|SdoLX3A`51pZ5eiUx9f*I`am0c@C~D z;r!7}bdALPhP6-INiJzx@FCmoET4VR%j)fxAMdPt8fr71gS%GTwZdy*({hcY<<0?> zC|7VSKkaaYG+N8b9zK5kP}$~@;@y93r-Nnx{>8ihQ?pjG`>xm7wMYFulLkGnwfy{h z@qRM+9|gB~VJ}&8?ZW2j*LIWBj=tXPU;lekxovcjXEO5R{EG7{^lLUXeuaLKPQPI1 zSDfEE%X{GQZDotoir<}#-{sCzwv~VEI1G6fU*BAMaOuIHZQt+St!3kDM%gpz^wc); z^QR-N?CpndD^r^n{9yfZS<-War4MXcE~Pt$8}IVfw$kL^<~Mj>j>Y*B`a(XPFLA!a z`4Z<#oG+EquR^PWBOP=FI#w=jJ~T#Z+7Vk`mJ81 z|Mb;~^763-drbhx)xMBt`U2Az*!j|PqlGV|J73~_NnP)PuVX#xHI?HgSbdgeOLmqW zCKpT_{O+^?(+2F?f#A5-yLL+7CUSeXqOG{NM-#d4@`By_7@SRTHqcG_LzxdBP)iXRAFh0l%sApL}=rQq_3ldGE~5+72CS{Ms4!W*dwc zZG6xU^Rm6?TOAhpTg;ZOWp!A({rqs&YjE+teE8^7Smk!Nlng>nVQ@?B|d*=|AcUQgWguTtKuc&~5!=`V80YeUV~ z_y7JiYkI#ulki&eCE4tctp5s~w*D$R|BNC(|M~nU*{ppFmaE^(#-3jAwx_?I?fgz{ zMt+=Maejqg8lBkzA+sp zOb2^Sk3AdA%D#AMiao16?zuC2wDS~u&aW=KJG<-o$(H^f*W8nBzV&2FKc)Me?A_CD zH-7*AIoX55s*JraGRoq734I~m`4ajlO+JI>T_U}F!_w?`Dq+4Ff)<3go zE1I11Que9p4|*Hihc;l^fc^8KZVawZdv#-^s&-~$lid|+*wcn16 z`=9FV;0bk#k4jZO}y|&~Ys$k8^c-=OVYjy4nTowkQL+ES$J?~=2Pb&R^iYtd$=YgK=v=33Erzl8n> z_i>E=sFeDnply38^+!S5{8H+Vg7yWa)E@=yBT7YoR92;ZM=AA3LHm?a>W|RZlv00$ zx|gT^$g}s0evp3A57MtVzf$A3Qk-9Le#QB%v%K0amDo-?)^&u+ob9TwZ!X=}!&*AJ z`d;T~L-1_%eb3RhfVCaS(dK})eaO)kfwkSp(MEx_J;~8_fxR!sqVG<%p0M+UwuQdX z=Fk_~BKkrbMPF#U=u3RrwOuWt4M!fdy)B__2WvZAVwfF1Y$8+Fs>s)3hDS+15E5v}v?K zTSuGV+5ykC-ZgD+bGFIa4(HWvb*#vhj#<096#o`Wk(&@o7kvAOyUI_}OfW(Vtd zJjYlbtYe29WBe5uV;NqHF*~otSf1C4jy-eChu~Vrm=DR*d`Qr_g}j&#DXY>shrE~% zDXY@Ch`g8&DXY>sioBQ)DXY@Ci#*MTU```X^C3a!I`U#Zq^wHEK6#oC368yA%)=zV zl~UukQfmBGN{wIry=weo9)^CU#;?xv)KOj?7v~(OI}SR=j2zdyx`(kR(=iXgdRR+8 zT*sA>V^|$;MvQIooOK);Ip)>zX~b9<={jzW7$c*9)bVV@*cs{Gmt)bfTeYsc^M$c3 zePPT?UlSu-L<235UY1G&1H~BpA zY@K~AO?&pUu+cS+=+-;PSa*nNy#wnGF|BuC-63MV1NqVQj+oXvuRNEY#aw?6Wq1I-7`2}!Q~;iykU)oc@C~DLFdCG)`rw? z&~=}PH6yUD2Su(W>AZC08k1wprSn>>8Sz@ICGlFUiA1*^N5*j|;ly z71Meg*1}?1j|;j+7SnoM(6zIe*5k0I7Snnh*4koPkHg%1OzUx;yC zYrSi_-W0herRz|UYgO)j49+Gvo9btU=i_2?h|X>PZafq|PqdBBzE&&`_Or0jJtxua zw;^NSOT>N~_|<(c5&Lbxy6+{X{WjS564QPg?0bo6zYX@iMC`YLz3zL7X}=Bjy+rJ{ zLAvg3h}dtl0taUk+_k~oGtd{_9hZmT@)lg4gDXqW{TPvZlXTxv!!E3Q+iPvH;6R*XdoQVBkxQ}D(2a9PxSkS#yG3^Hny5}mU{b1OO71Mq& z?9qy8KUmPcTQThi3%aK(ru|^p>lM>}Fzo$^X+M}}?^m2(ael@573Wu+UvYlL`K`0O zx-TelpAs3rm+otd+}Gsl9`@ca9s8hI4{ODX(S0?Mdw6ueO~l?FJZIg96S3z9tow5! z_X6p@orpa`@T>cIBK8igkcZ&>itb&hj&tOEVQ&w8Vb2eJVJ{GUVULjc(mY`Akof}p zvg^L4$URiL-zjo$mF|Oz+;gS-qayZVp)9&@DsqpO?x%{_yM_Gg`frN0ROVvt)cAs5 z=L>tQ=nH$U=nH$X=nH$a=u7Ae_i^>#zZc@_o9KR_$UQ~6k0^4lk+Z>`BHCcD5p9BN z2Rzq$*L1&A zzc=<>N9^~;^VEIU5&ONty6;+J(%GI~?7NO>zc=<>$F$!Y`>tc!?~Q%e5&OMyt?sRj zX}@_a3=tUiZUC?4?J#?#qqb zWA7MyiFqyd%=238rRTNS6CT}p1TxMe#B?4Z=-&Q_^9abB?)i^6j{w%Q05P3M2zo{! zrt=6mI}p=(1e_^|={y3?8pL!S0eg>QI*;Jl`^7m3^NZ(CzhLKAoL_N%#rYNIx6bnF zzI6R&+uwd`$3gdaNA9b4bq{;LEgjFnrPqp+rTe-g_mJy;@5sI7x(_^Z&$;dokKBu{ z`^F>psOx_6h`sB$zxPGPbLipX%{gD#TTWltb538_i%wtIqfTE!U%00)yY8!x+{3T? z?IZX0>puL*J^#8tKjJKaUK@1Ze#998up_{olS5y*sD*Q>Su*}x>#)DVzJfgH~Bo#Hah!SvD?_s!se@uZ;$T0AsOfX zVmfb#bAK_NH^jNWi1UWXkDmLB>AWG%{l#?N5a<3P&Ktr;&;7-8-Vo>hVmfaqdbTU3 z^M;;-vkC6n;O-gd3(wr;A-KE+m*?Qhf-`85XEXKOW#pMnJ&zf2mQ(YLGoF!WJRRdK z8?VKgO|u20VaYfT8`F8%pl3@X&ch=Adge5y^RPIJ8q;}LoKcPGJS@(x z#&jMQXIf)A4~w&|al_&~EY7~gbRO2T_ltA5<`=(<^DEA;IKSfjit{VZZ=L1UbCHqf zG#v*$%NcpD)73qkb7XpO={SF9u{cpz^;}`(8Ad&C7;&}{&rr`HMxJ@p^NA5>A(5`< z79-C{>UqYeBlf!ec@~=ec{Y0ec>!Bec_BMec|jX zec>GC@4gGJzTr$|fT43 z38f9riqZz>fB#UNR@$S!)fKa{N9t!`qZ${{>0OYaI}wxK1#~B3(z}4}L`-@Y(4B}$ z?*h6LG3i}EcOoXe3+PV7q;~<`i3q(5{MM>15R=}8=iqFhmBDMFp}~7XTZ6uW%R_K^ z3og&Wl_jViLZmi`>V8COhNvD$q?U;45=3f@IEI!2uZ3m^uZ5NfuNBq4h|puvGC~J~ z3_X^Z^jM&65|bVaG*4pEV}TY*OnNNPNQp_01==Yw>9IglB_=%2JG?K)qS_JF@t2)1Xls}+)LZ8Z zS{(ERjSl*Pb_aclFT3iBL}-{G&#E^PscoVH|c<_Ud43x&R*kwRb4PN6U8c>M0W;Od*GUPq*+hw6AlYJE5x zXnL3p%I<7}YX>~nde>BMBvO+^bx0z$O5FPhO%mEbtAsW}O%4 z8f($%t&yR77L(o@bkAbaTZ8UdOnPh3J&Q?i4Z3GB>8(NcEGE4*=$^%-w+7v_nDo{} zwXI^(Tk{;8O>ox+chBH_1(%1wyx});c@C~DLG`#IwdquME>g2j_2?qC>{J&kQsd4s zw7hsNH0yXRwCs4TsPX(dJ%en$mg6-CdQ-(2ra&t^Z=pJ7n2?! zwEJSx1B9kuOnQJpwfc}XsYS~5V+PS(1oj0aK_mB0kRy=6cRg2VcQ@yoFZ8z0ni`0BmeYQv~IMr>7)QD3( zw@B?c@5`~Mc3FIJVkyJ(alWAKMqki;qc3Q|(HAu0=nL9$^rhO3#dAQ}Ro5<3Lr?YY zBDM8Y2QN}{PxbL4wfIywFLq5DeX6GysokggKXLlBrz-INl96Zn0y|&O)}t?I?$H;t z_~;87ee?zGKKg==-0!{%uD*%t#YJk$sg7Kv)||6}rW|dcHAkD^+5ykC-Zj;`i`2wZ z9lS`bJoi3A6OT5~%A*Zp;M%joGtro~vCR&5;@uP%bG%l+NqcKQYwT;qC}%$l8`b!Y zPVbit-QAeY&=rG3il5^EoCxYG^^nq(=>n=$Q1Vp&cEQ z9yK(jW74CB)^tpI)X<)dNsrpI_X{0t`W5F_oL}f*)2}$c;{1y93k_tJ5xU1@QC;Fl zon*&BwUi@um0jI~&M?!1ONah#+-boM7KdGReIqr5Rqr=aTUd2~BQ=LrA2?ErSapLV zHHuYFI6}Kv-yNR^&q7~#znm{<3)2@ghv^Gi#PkJ?V)}x1F@5>x5L8z=Qo~vGmLs*D zRfjoJ^I7$oBekGaw>eTHTJ@YGwWC#kGETVYg$(a68F_Zk85+*?1#M^gg61=QK?|C` zpb<@9(2k}r=otU*yWr{@G>s!QjaA1uQtQ~+K+~8u&^o3~aP5HSTJM_bEk|lHs}6Id zR&&k!SXSk1pw&zp=x^Jz!t>GC;_>n~pS1o_wLRnZtsXY^{U+`4Y@K~@_O<$SjWH2j zya_VmKExDn0&yQ=iZ_9{4>84?K-`Cz;!Pm#Lrn1|5ceUbcoT^G5L3Jf#C?b<-URgj zV}l~zgy-OFLd~_hH?roQ!TAa<4~T`qyaku%;L3s+1d*{hH10-Z%npsm5gE%v;{rs+ z_;8F^2D}zAJ9sT(dGK1%*b~vkLm?v`N=)%k5L+ascqoWD5>q^sps`3|iid(2B{9WA z2^za3rg$ibX%bUB6vR4-DIN-9AH)<7#k2Q|I4txl&aXJX;{1y9E6y+Cu+VRv<<+UHaaVR2VUTA!Z$XFN} zw<0n|hQ_mqjGf_qITrfDyXJf$wgr75<^_Er76yGGMh1N$b_RWkFT2L|h>Rhk@jfDB zi)b8>$e1G}q+nUIlZ=L<1J=nJt$=nFAN=nJt( z=nFAQ=nJt+=nHW)e)nB)^-VNhMr2G4jiV76Ys1+frUq>gYlAkywF91Oy=xlpBQhq4 z#sP_p72@7U!~~%YVujEK@n7s&;rSf!&9FG(pLR7@BJNmB@y-x;ET(v8h&!fx6nmRrjXM?*?+p3TxMLCV&cGUXEF#_+ zSmTaG#5)6P+_9MAor%VliYeZi=iqFDyEeFc2Ini(VL1W>?6ps%v@?wg|7c_QWO!4@F#?*@`9v@=u#T1V(XdJGX z;_-QQek;ZK73Wu+U&H~VUvYlL`4#84&hlzpw#Ybfj)TTii;OGh>zhjtHR)wl8qX`f zKX;Hm&$4ojYZehh4bN8Nokhl0(>Q36G1oLcTHGhaV$-;3kulmdo?2w=Ht)-^)cC4I z3^n>fY&H5q%r*K#EH?T=j5hj0>^AxmUv`Zv7a7A&^o1CC^o7`Y^o2NXzxyt@ z`X(B$Ei$H?#&L^`_2z64(~UNW^+ucE+5ykC-ZhOk7a5aI;4oJ|ZR^Z4j%D zHo-q1jd>Kip4}Do2eFXiypR52?EB3c`?7LpADn%yK3!w%=7_h8`57|qukm*C6mJ)C zZ}Svy7jbX%6mJ)CZ}Svy7jbX%6mJ)CZ}Svy7jbW6inoinw=u=r6^(5gQ@mZzh{p3DGG+1N5#yd0~v}f-Z?EDJ-BAtH0&acof(&-mWzhIUTe#uDJ zxWJKdiX8`yv70llv9E6~Jun^j)OfP_#*HSSo|kJ}-JCIeHQsKH*uJpQIJ`My{%U;Q zoUwp4Zg0*Q!5YsuXY63_%dt3Lh~Z0Li0x~>P%h^Sv4G8&J%{8A?0os>5HzlFL=0u* zS>qi?##Yui$dNIZH9m4gEN0kf+~mj@%^FWRGIq1Ze~k48-fG{UWcYQ@88MX27t)Ndf@ zYZ~u3GA6RdL5_@-OdH&XHelL-{qyUo&rb zAb)Oadsg9AJ^vURje(z$j_KL(SB<(p64NNADN%KaEhh-`o?tFxb!gW z_Pz60-kbsZ@(rG8kv}_qhCP#wy0yyJJi6d>jyWW6{OojlCciX3ERQ=)H=FGqJtF_% zl4-`jtZ`Jn^USHn-WM5VbiRbXkWOD<=S%1d>GTDrFR(BBS@mAZ|Fg>^%frUMzMNOC z9xTsK^mr|AbVIQ8p+~=w@Ap>0W6yjm@3^+TgW;1~-p%)@S7kODe>}hA9lN&NakVe_ zr7y7aCG>@K`T{#&LSIN{{m1V@M!K(K3$GrMciCd3{iYL-9g^o;6-*mkOB*n4!2aDQ zXI`0a`Rr`tqsRP^KX{MT$_Ktg9VQph+_|xaa zllt6jHu`tee;e!nN3}E7>!Mzdx!IE5FY0}b)lYYrvM0&cvaq?@N@?)Ix zX`J$JtkERe>*ULJFx$~Uc7ak?9%Qt@%xsy ztym-5wwrNSy6y6c{s$I(#M56_H2T!~j?nv;PbyA5r|2)PYq_xE?Z=D$V*HnHR?KNo z@U-@CRP5bm8txgIJh-6ZRfU&S$_XKMhODv=2p@cjjUGr9A-Zal8u*uwZ=t_YiNBHlb|wCH`kR*co9b_!y_ zF-5%=rKVZI^%l=BwfuUfr7KsE*R0o~f;O(-UnSod{(FXf9P;~Te(ToNKk_>k`Qdjg zn0-BXW%_aVtsC4o=PLQuUDe-IuUy(MU-IoVt26IiHaFkzF#BFD_x-*bUk8q_@vPkV zI&gfA^pzRQ`*{O5mi$xal;T-@uUzE)38_~op4+Gp1pbKVRMNI`yYba{}B9o@ye|K`u!5CdXI!#9}jMQJh=7o;MT{3TOSW@eLT4J z@#^(u)Pem!?h_Y0d4koArq2(Ir&b)S-&bYjTwjKb+m{vGzO3N(Wd*k{E4Y1G!R^cP z`@U-JH}m_E{>;6Ib?skr`wTb1kC^jf1OZ#Mj#$VC?rlyK_c?=Zugacg_g$g?Y{>xN}Cqoip<1s%o8| z^5<**%(HcMoyT$K<`BP|=jIUCyZW5b%A6Z=XX_9je3hQ9bLXl8&sE_!a_6doJ69Fl zxhllD=DDii&Q(>POF})_xXrA1%KK}Uz+aD@8UHq8nXx}-^SnrR z=XrxW&+E@G*E*-{&$0fQXV~jH_v+54BTg~Tr`I~$zB1=?{dx9xR`D5jcYZmz^UJ}V zUk>j4a&YID5zm+BmxDXMTz&o*bz}EAQ{u;M?#jUpyHv$#qu(;_;m-3q-HhOLGlJ92 z2u?R6INgju-3-(p>T-a+9tbrekp5?C#nh!Q;dEdSkCi$wwKQZ_MhC;|#;j_sm{qMw zQn}lx*s7Uo+i5+?G*(8VR{I)z-3+Hs6`VfR|B)7!*WL2EOn;^(TU|O%PHzoyC#kpQ zHL1MrS)F=QPLnOHYE8CPt^L*I#$Ivkm@}+yT(ncScxBh_#$KPw=|BeRK;qqZI*@-@ zbJFWuI?cmBRr|Cqy+o<Bj!J%IG?J9n@8=ed=^CgVVhXPWLi6-OJ!~FN4#)3{Lm5 zS~n7H$c}Hej_p4jV0B}gzI(;pS`Ib#I*?9p8F7oKxBP#k?d)}=z0UBTsWD!cF0s=O zuTy(`W%QG4>2I%Mjqz2jW!>=C-}0mN+#TjjR`2^-zVL%8t0!J>*~K;ZAB&;j;y8E> z|35XBM_u~=HE}xXj`6WFaSB{4kFcs^d93P~5zj9@DqnQY467R-?EGPA;)64deOv<< zKj?ofR*{d3q|co3v;NeWS#`zPVLUAKt&E2S_VI&OCLWN!3)S(nH15nQjhUsfODske z^2vBfV8%-VGhPyy@shxdmjq_KB(RSkq;;bLbpv}0w9aIxGhiP-h;jOGt&7ta7^e^E zE>2%?ar%Ob(-*XDw77(@*EYF2CZ@LG7N-*Fe`ajTy5iX}?j-WVxRYSU<^yYASse?q zuDE;Jw+iEiXnc)T8kUhvD7V|2J0j*l}7IPWD5##@Y8UGjT;{R&Atv?oPSifC`->&*iEBvPQ@o-(-dFUtq zkHomwF{41!8~OL~)>Q{vpudfD)yEd-a)VVjTd3EqdfGxAZ`Iir=zGIP^|uAO-(c0{ z7U+S4bxbPI2?wk8vQUS-uK4Ua78dB1!(PY8LOpXIcYbB!$m`f&r~|Kh=>qL{+*5Vb z1={am)mN9K{T@_zU6S@Y^w=e7zeA^8p#2Ve)o+)i{SIAsf%ZGnRdZXC26#}dY=JH} z_CcwJwm`2NtlHW_9dFg#7U+B9TAk|<=zfEB4n(L2u5%-dQ(vxQVZm4!eT|Nh1!H8e zk2|j#tpYt*+()%r1v;@{)pQl;$AVSsRj4bg8n8mWS=ELW>d@+3kjBW~-}0<;P(tlu zowE|^39H_(P-j?mfQ9)feO-&p5Vg}TQ&*D4*m*SGIg zom&&mt?8VbaL!FN7^V3Se=!@K%N6Qg>Kw074^!uUg*ur!CoI&@)VX4zuBOf*3-va2 zZdsBZY0x=sp+>9DfeUq0Ro7HDOnR!ScPi9bRUK5J{;KMu3UygkH&v+Ds(Pvd9alUz z)matjyW&~toVifa6M-ico)5*H#3&tav86<|5Q<)wLLbjw{l2jYg>N zs%tm$PSYDWS1+8a*ExLQ9KLGJ$=(w>n2oLt3HAMS%}A*Gr)x<ok`V!6zWf^KBQ2W zQgtJRdX=gtDb%slH8`QZrLN@(^)prLPm&%WGyo;(1Y+$^sJE$Wf=TnkqDfB-jX_i74RFY;X^g<W-0VY1)8OJhN=}QNxKqjuc{IDeG5EuU6U2+OzK*#P=8X_aD}>*y0$COtAxF- z`3iL`buCy1@7mS0$aL*bxb~-Og2FXH)zlK|mFZfuP{&NyprvclH`BFgq3)TkSqt^h zbS+z`lcsCjLj5#d`f@A5W;ur@DCpy*^y4Yx+VRKiwN3)Cp8gGfBE<&^nW(hlafbLR~@KV<6NU zRP8dM4x#RakfenO?J`OFX3#W~qFM4Nq0XM}2@&e=>0S|` zE}!lp5$g5n-V%Yf9_C|pFM)6`f$lL7?lDm9AfYakYA6Zynp9g!sN>VpY&$#jp9P_IlipoDs8s@)_>-wB#dl60T2H%SWpw924+mV~-$ zs?j8c-dZK}og`_#L8D2Mj#JRRPm=VVuop|HN2j`Nk~HX`=O#&m4mxj=H0YrJCP{-1 zx^R*-=%5!TNrMhLa*{OYpf4v$gARMZBx#XhZf7jEJE884?!go4;ppBxNqRv+_XG+xlyncFP}fLxhlF}Zsz)TyK|*;|r%0%er20hy z-6W)|u8~krN%f9|I!mg9B-CHhJ%<8aCfMuVMWODKYSc*5v4M7tBz+s~brkAE=^jX- zew1p_2z8}&ucjnzD`?S3(yM_+jU*i#?ClilZmB+%B&{vzR!P#@f}WKmtu5$WNz&Sa z{*@%Ht)RMClC-vTHkaQ2KP#;P6rV4eFbkC|#Pf7Q( z3U!urkE>9BN%y`Ab(wUpqhPNi+7{gdDcl38S`Y%A4Wz3khERV)wK9ad9IBxq)ay`f z4WW*QYHkSiJyeTBsQaONeI@ClKp#e+6@%YS_aqDTTU1{~pzDHk)m;(jy?|AZMW_R# zIxPZy7^JIyi%>U4bzKB{GDugw7opCK?qQZff2K01riW19MzuI3>2*M(Lz0e1P)!@5 z9**v*mO>||GN|T;P(MfaeoNBuf#!xJT@Gk*NYd+omWvenLK>H0$5xUwg@WqyNYWGv zs@o$;QwVxK0!<<0Uv+*2nnGaJ{}E^kfmIhspeY2_J?D}%g`h1XNn0kU28&SdMYUOk zIxwo)BGiXbEf=9~jB30H^<;FjYF0c`Z_fF%8gpl22YnixpeGY$fs z3b5)(2=pt!sxKkXwE(N`gh1~Cta=ne9Sqf}5a?qdUG*yjx*1^AwGirQ=$QzC&IZ!; zY=uC_1FV_@l5`1zY7t1%E6{zv>k4!~V54U=1bQG~)fN!wgn;!di6pI(pxOeG^ap~T z^^l}X0L_XFIx4VNy^$`X=-3_VkmQ6EFk+GNnpKtA;hPDVWq zJ)4t3X9I18p2ZNH#Q^IW4dEFLJ=>e%+%(eljB|$b)VPnHea?8!TF*phIDd_FJu98z zTsBzGP-i@^t!Jw zob5t=&@*2d&wRlj&OVPkc!2DBVYlq4C9{pIe)%$6*lC7wyH>kNhablq@7uq#?A&mm zalhs|$92&~#=q*E&y>$w8lTm8sw`T*mT|NF?w0(F@j32)-Vyi8#Lh!X-~$esBRzZW zl!5ncdWW<+`&r|;O@mA>-%61F!3g~>+OWOx(EG2Jm&8`G>uG{zix~rFUoz48=3nl$; z0e-Ym=PMhj#$~TF|5T?aeK~Ix^P>7&?JL)=X8vHK&o9yY4dw>D3TKX(vzYm}x-B!? zUp|NV&7=o1uPf>EQu{hPRGg8SysiuL*!ve{-t=n~=0R0o%lvus7p!x+J#S|IO6Obo$KfP11OKqn6tdsClmdT^yK^l;B#l# zxnG%RPnA0*&m7g0iSnp^X5TNg%N*&$?E3{hna`bJpJ~({0JCyn%+8y@IS0%GQyba7 zxA5<Fb9dW2hJ0@S zMw;=z(Yq1DBbiunH~03C|9rZ*d+4^1{crScLUPDzUyAX+#k)Iayui90A2r4;dSemu z178nw-A;vl>Dc%#xAma~T%PdBoz9uCUrSH5a{Uv+ewDngk-PSVu>NZnR&&MLhwOig zcPpM=%zrEUZD1?4-^Tdg+}(s$OIgPM7Volhh3tQ$cUM34GMD?`?p=Z0A^YF-U0kOn zTrPVyP^awK0INMk|F%2p>{9wO`Aq`|gdp@7^S=%XVFR zKgsgy{(7VKgBkxDy-RBp%BcNgM%`;~{BQK``rR|R9<|TS_}}6)EAI&PTvXzU%u0=( zVwvYoUY41%J=F8~fwS(0wPF3+8=r71_lNcLE`QYB(=X)1A0KqDH3(Vlmoxsi_{=-z zg!YmBd$6!3i&+L&J+SdO@pZRywko|A>nNNQn`kwzyKXYF5kk9P_OEaS5*s zM;d0%7#wo^C-pKfzcQ2=yS;X1&vxP8Ug~?{Wlt%_PWF_7WzRGC-*pG^xjT7%F1ztL z_iJDByRFsz#TUKfSly3&-krs2zxsLigRA}RM%`0<-hJq5AO0o3hy7CDe=U2|;SaJ$ z9jwk!{M+tYmAgk#zd8?c$?x!0=Tk0vm#ex5_Po1U)%ln6?m<@PWsJIyHRrBpw&%IK zr!V<^({i2&?cRS0?)jB7FQ{M6ynxl2tbf~`l5)o)>R0E>F8N)h>b%=U@2ph!U7mLb zr8-Y{-hHp?{GCzvPU<^tjk?eDlHaR)sqZtDGjtd`IYS3lXFQFZ@kF^gs+ayw#&dT;Ui5B0b>8;8yY|%i-1F|WROfk(x?fM<-D%XljhFoX&`W)9qnydb z*vXk(u$&nOt25*OpY8~gJF`%yI{$9e`S(k5_nbP9f6+V0)cO7M?i5q!{m;9K-wDN1;*o(_Qj=5>@_$OL9M*obkul$r*pJ%0cmOy9-I~215NRpT;G>V@u`txaeI= z>Yk?a?oLwqL(aRWOywIf>b@j>7n@P{a9#5I;MDzJm*gHU$r*yNlbj)7mDA?mcIS)S zfr9!~ex6HymypUAbkRFyRDPlJ?ub$Oh|ar@N#!px>RuRq=af1+e#!q2mi+%< z$$tozeEwj`mk5@8iD1dE2$nqmV3qIDNFGR(%iSL=a|!M-xzzVZNRCA4uW}?_l3e8~ zcel<Nhf+e3hSn|h$RbJUkeqY0- z&XX@WSJ5w(bJeK4!A9i`HY#thk-Wk9Ta`E1sJy{O@&-dj^zI6$o=Oqg-+_gC!?3SaLW=EV-bK%J~fDoX^qUN{(pM zDLJCimgKBPA32vb^tMjtt6HOeKIHCS?7gH`Tp^igtRW4t7XHtZ}p zx?z9G(T#DD9Nic%$SoVs5)m{{CL_ zl>JMHnXzChdan*A06%>lYMl!gG~0(;SMs{ zM~6GeWFH;wAd`J`STo4JKCC5VUmw;Ovab(o64?icwTkQ~#F|9*4Pvb#`v$SLk$r|( z^T<9!qxL;w4JP{`u?Ca?=LtKjeV(}cN%nc-PAJ*uiMyg?pC|5+l6{_7m&!g*tVwvUAdg+NR}ifB zvf@5L*~^N124ycR?jMxBthkp@_Ojx>LfOlTdklFmE9z8xS@A9)`*LyDr|iqcU7xZq z7k7QizFZ^wa#4@$%LU86T(IoR1*?6zcn6Vv!gx24eZofV6UIA^>?_8dgR(yvcWcT% zWZbza`;d*=w~Tiv*|%)eK5D$v@&0P)qxL`J9!%L6je9V8zcggjK5E>9$@{BOuJ&Ey z9!%bkjdIzi4OaWQjqDpox!O05I~HZ%IPPAQedD;3QTC1Fu1486jyoJ>-#FfJc<(Xl zl)cAbwKpF3_R8LP+~+HM<8jZg?2X6$zp^(T_X5k_c-$8(d*gABFz<~={c4{-zAeZ; zf841p`}}dIw(RrAo!YX`A9rfYK7ZV)E&Kd&r?%|#$DP`;&mZ43!b-T~iC&+grulpa%GJ3KeD9KTB1X=kKt`QI!Cl634h44{%Q+O>eJtlt za3`{yL&0}5IfsI8CVZ9wb;?-=usUmFiiVG!OA%)qs~bgb*>8Ec;#G`QRlqy%~{TW;hVFZ&ob)VmXY&Zu!%b7Wz_jEv*_Hp zFr&_k8Fh{f-_PaTnUQmCs8gM5GwNKMQRmu>I@e~@xi)-g=9TXZMUcyJytdJ)_R<;dciKr0|bCGkA_$@}xMH+Q362IxlIZC6>W8ya*Id^H)xl5zYY2r5{Ij3pVxl#Ov z#pg-UUv=ISzhTKaP@~R=8g*{esPm*ooijD+{HamrQt^A7oMSa|P8RK|bFxOAlQrs` ztWoD=@%x>elg00Pa!wY%>F`-g)G22z!RjoqQD=dTIty&nSzx2i0vmM}*r>C>M$Q7G zes!)Hzop8#W~0tE8+ESPsB_ImoohDgT(eQJ@y00xqIvrkaPF=jhN4FqfR-y4OY1Y zjLI!wRBi#Iatj!hTfnH?0!HN)Fp^sU^{YGy*qb4F5{$}|U?fihRih zmB-0Q9w(GbUMaBO%W6)1bvy4*_Iq5-q{AVrJXA*Iv%;QO&Rd1QRe7t7%5#N1x8}Yw zcXFL7?-up|b3QKot>nuBOCBw-c3a3kFSKcYU^17hyl~iy zZq#0MqxPa3wHMu}z34{mMK@|Mx>0-4jqF92Jay1b^3<`OC$2Zu7Ki)Z%YJvg|Lzd7 z-+S-Z%AuWA9y}v?@bI@PZyxsWn>C|Dd6mZxX9`T6AUt#7b2yt9JA~&cO0O@!z-Cv281>&SgWcTx-Hzp z@6Sh=!PUbvDJpNFk-UY_S>-J>DsQ3jxt-04QQ?^ppYz$+<>8qTp9|X5I1tt;x$jVq zlG}yUcr*<6)d@4!IHNY?9a+^-deCfD@W?A9I3N%q|VBb zIx9!&tQ@JcawKQvB#$oY_h=ZpXC4D}<}r{nkN*5-Fn>*W zzVBRKWxo!5YgfFS$Mokk139PZ&u<2De$$`p4CGv=KkpgHc~5^1G>~(kDmSlDxp_^( zYa?B!8lUr7RN;+<7Er=#zxw=S;h9|FuzVybdFH76V)byYAe?XY^)UYr^`K5Z^Xv6t zj`X=$J!n_tnN|H#uIss2zy4)Ce(d@F>*#J}zOOvGb2&OM{NFpTaXuL~Id{JM|Gzu0 zw>2x5`Q>kGEcDs7t90h9&g+@`rkBX9nzE6($$UsOXhm@3TKwD ze1!Q_P%yJu+spjC@b`MZmp}8<^@W(rf0r+F&L3r%UwOv!!kRhdPq%86Bj024t<0$B z$79K1xvzi04Lz9AZmB)}nW4|=jG@feue>>PcG(5YZ%&BM?4O>=TqGgL+_7psbMuTK zv-K-)F<-eY$h>CiO6Fy=gUsNb<;=(aiqD)e@)hRF#o{x+c8i%0>~54<2r7VL#Xr41a;&fH7_uKQP7< z;|hi!!JokJBlr^-eguC4vmbeX0>h8sPhj{F{0R&{fw{1<)Uk;iMQyqkV41xwic`&7 z!*Or&Lq+;-WjNLyH`k`&FNJI#BC2v-D0BI`1bV+j__u#o?MN@r2E{c{eDU*w)Vv@yFG$S`LY#$f_<2EUUXYp>q~-<5yzp^= zBo6rbNHQP&JSCZ@K0c6&52WG)srW!DK9GtJq~Zgq_&^dLd|V=lOFmwa#H&V!Hc{gz z!ZX~KKGs~!FmQl|vqn=qtJ+q8@W*K>AdEYVejP_$_^ADzZPc^d$g|t~vXM1|_i-a@3Ge&H&jGfTpA*K<4Q4-A zjGr^iehwKwmze$B^7}4`+0QxS=N_}4i^k7MW5?0PJI}LHt#m0giNF znMeobNC)Of2j)lz=12$TNC)Of2j-~n%s%eI4$P6Qm?Il9N45>+Lz^>4W5FDa5py(l zguX;$${dX~bL0cek#8_ZKEoXO5_9BZ%#rUgM?T3M`6_cXcbKC&!tCQN<_NQoyO<-) zKJH?UF#EWRIl}DYF6IcckGq&7%s%d7jxa|tfjOF+%+Z`>j$#F~kGqH!%s%cSRxtax zi&(+z<1S(avyZ!o70f>FB33Z_xQkf99K|T+D0VSNF^xHjb<9x=WR7AZa}+a~qgcuu z#aQMj_A*B?nK_Ep%ux(yj$%7=6!V#*X908cj9`wQ9n8@)#lV-MXB>0%EMtZ(VN=M! zmar)pwuDW=uqA8?hAm-JFl-5%f?-S86dXOfnWJYYbM$Owj-Khv@G1Bf{uVw3-vYBw zdEWv@&va(^6nqQi@G1Bf7(NBx0!M2J=4g$<9IZW=qcsV0v{qq`)-cS`+J-q=^Dswi zA?9d}#2l@in4>inbF|iCj@Dqz(b|kTTC*`nYdPjYM=!HB=GL-dZo9KAa*NADD2dHAlu9KC}uNAD)g z(K`z>z9sl~nUKSG9OmfVhdFvDVvgRGn4@}n*cNF@!tx< z^6(o1bM$S2Ir`?n9DR#m#KN8j#p%Kbddk@xeH8TI&i8-#)u@#K>c*IsP z-s2Hl!FZ2HYz5;z9A)Q6z#Qqo9O=Lu z^__XZjCGll@9z@3x#-#^;Csh)iOp!bntA{1F0p-+Rx&rRU1GzJz0TbDNS9dSg|9Jp zs@*l#`nhGy&yDFCYj9>M^M@aFjlJ~2%glW%b&DM+6!MyJ-D0nOx`fN~?K)TfeC_Tz z@}ErXo>Ncp54-2oUq643oOT<;dgSOct$&XkJ^vopBS-&3lY8X!3+4aZzn>sbBS7X6U)4^A=|4Ke^aHn9;AS+e1cwr5tt;dDutl zf!(Bj*i+htokbtmU-ZPdi2nWR_&Ohbi`%_xdDqy)9pSj3{G~bTxSVQrjSZO{jw$%B zC)VW1f8RFj?^|)*Vx2$V$mK=%ca1$cAmn}j=o;&KAe32m@|;ZGcHLw0w~yBAo+H!k z+U_}jd)51X93vgTqGz3ty65Ns7Tr*%=#RFFCNF1wQ0FceGTJKKH0&dE78&R%<28%y~#h=0A&tUOqu=q1r z{246%EamVAk%ymv#h=0A&tUOqu=q1r{246%3>JR|i$8AY~43_x|7JmkdKmRvA|KAs%<#~#6)coIA^fu4g|KwPt$LoKZn;2i2 z%b2H{iA88jv($rf`CG8WB`ptq^xw*J9OW0|i^WEX zrKtZx{-4$cA}{UAx&pdM{J$7qEVjcAvgXk&^@vSm{Ugr>l#4v{5k@)25p|;cVtlb@ zlRV2%k7lU{+d9G=Bw5$JCKTj{l|I>38_2X}4jHDiv%ijvi+EV19kFe;8HJ<1R zUYA`wvwZ%9*x$3xWPy8JnGiF}&oWo?<)gR!&D^_KLhRdn<2FF%>k0|6I!8ioS3e;( zVn8k~Z;+G_Tk%=QdHW~CTGqOZ%S)yu#C{tU^6M`p#J*o1^2sd;u}?p~Y=hUwXcifi z%in^fPO!8E79GH%8(4G(OJBg!N3ibu8yj24hPK|${hj|z>)4`tAuk!xIyS6h$Y)cCOFbM7JuTWEbxlMtz*xB z{WEjr1Fd5x-af*dy{mO>z*9$=uie@@HnHO|<}s^U$3~qD`KkG>V=c%3!sXQ`wvO%D z7xG_swT?9{`zx0pZPhw9yKcze);w3fuHZTO#NWKnMD+~#Dj}!-t^Y{KX}93ogdBbB zvVM7XmM`qOj+x#Dx(e9bwzh{O%wNpZd zo^uL@4E-B?c8F!ruYH*zqrXxPJBU2&BlW;;Qa|h|?ZVEY59}{`VqBm<#!kiyEaL^1 z@dC?ufn~hFGG1UAFR+XkSjG!1;{}%S0?T-TWxT*LUSJt7u#6X2#tSUt1(xxWa_O&( z7s_S4z%pK7885Jm7g)v%EaL^1@dC?ufn~hFGG1UAFR+XkSjG!1;|2a#<8|R&lX3j- zy!+3ecX-|f4cf$JuE@3FzGsVP{+1^xmiuVjhEivXWu94?82ct8Zo}L;MKjM%ON<>` z6t`i^r~VshpTyV)Q{y(orCyo2BS?&u86LNx!;s4|3zbcbwdfJI;ktjEaD%T%j2&$k zx8c;RA6@G2tz%7E#BF%A`)>Eqq1Le(LEMIJ_kZka?P(p`RX=V+<+u#@__o%uw`+O% zS}(bVpR|tkzCLb4*NTt3S3hbUySru_KSMQ(&h2lw-1O;?7`tv<+=iC@3z&VkCB{}h z9Je9wz+$FN*Th)A)VK{-pDtwv_D_rzcqDE^i^Jv37Y`)H?t3b3L%#x5O_@g$W366@ z+mPO%rg{2>#8}0ZzTH+gni(!J_T<}f8~&?T zNK!2Rk5E4EjY+Yryt%lZxK>HAS|xLF{SWm_id|Jb7q`1%L{e;b{amb1?bM`Li>A3k zJ)cO5{oFDa>%aEtq}ZaQTpQ4@2G1nL>bK3cVfnXzl9bo{`e$kr$rsDmM^ewqo!d$3 zzwfCJNZPH|d=rU2lPhGB=-IUQdJ_E~EwhfKUnrOULSF2Edc;1cU+ji<#h%bd?96&b z_J{s5E{Gv|EwuKUHnEq#%fss^DThy1Ti!bMVDH@Qlfw@r#!6NVWkeqKSv5K-);cv0 z+pXRMNwK#k=3#qo9hwxoY+N3;^J{&RVqNaf!}bquON#w6I1i7@A0{bQu4f(|uW?oV zShUZ>V53(+@YS06Jw*-=VtwT)J=?SS)H55 zeRu7|Slv~*dEBKO_S_oD!_HC<>@W3WT%=u$m*|6W6g@G%qCdu6`h{}oFXY7zs7LIB z`o(T&SL_LW#Llc|WPgmijLZL4f7bCw`=n;XC9wnI(trIk_lEyu|NP(d9MR8ru*6Tq zVR?pvrChH8!2c@tURdYuC5f?j?%k0E`Ko)9Vt@Y;z8elH)HYUn%on`2*DUX7s7Dy{ zWzdK=vEFa)%7XpBAJ!(;@Qqzrm@f|xY!lnIcvlvl<9)lgiH(1HR~DY*$CBE_R!-cN zh3EM4hHYZ`2JXtjbG%;pHnBSrcV*!@9)Ee8*!?wjW#Kvg$PY=edoJIVh3EL0kNmUa zo1I*qvN9=FHESo!zw=a5?7I0oxt{kPN{X2WcXIvh?@EeI>AsWO&DS9*_I0zJtk3+W zNwK1}c7}S^^J{>zJ6Zp$Z%B%Dy=G??`ZcRYQmjtVomq&7QjR$Ja3qiTDfJ+(O8tnp z(k|wU=!5tydLnL%{)p$&FO*AvAuo17Jz^i!FLpz_Vo&HJc4j>z`$K;j7xe2ua+}yA zW%qJ_`?qfs>sxv++u?MpHnB5B_OgBU1Z`r=a_wci4ZXfi?5m&lusv&D+a}gv+a9*_ zinB?v@oV<5{ns2wiY%rwov61b<@}FiT#gc1=@=fnginY2T ztmoElNwERn?dJMFXr2^Xxpg?8HSZc;z&Dec0}q7UpZdSYBee~g#(3+2*Z$cr6N zkJtzGi`~$!*c1AQouQ}LALAwCqQ~pMb1j^+|2NGwiH(SvKm6P#cI$z?99M-=u4AmQ zF4upnV>S52tfW}YyY_Gl7sfl_^1(^5gC}=q;T`bxTl~A>mfczI(*l`q`gfn!>ASPW z-;_7A^iPSgQ(bpwO`4D^v*726vAFo%S^Eo}a0NCb#@;BuJIj9XgS+GP#MqR4yR(W; z`^tT|C^2^Tsjsp|JoAz3^0Z$||MXSXnsV#ikw+6_x9s~WYpQ$EZJ(ML`{y*UUPrJV2?~2l2JhL>5jP`RpN5uc}9Fci}=ZMS~JV#_6;W;An3(pamcX*D-e8h7^ z<|&>dGJjDn^BVFp-%*dm0n{(?0qsiMfIbpWpr^zc=r8dH{rcY+m*A7KegNzDK3Pj# z=%4b90_A#rqQ7;^H*nM`-^Ri6%^WP>(!uhL9W3A8!SYQWEZ^$E@(mySuijfxuKOkH z9F)uVYOs9A2Fv$tuzdFh%lB}wd?yFX_j9m(R|m`Y_KVr=KW$#??>zqr-<@DX@g>9= zVQpKKi=Dv|Z!Z>?Q2wvJU!h#q-eB=1u=p5Qd=D%>2^L=kiw}dvx547`V3`YGnImB7 zBUtxK{0imbZ(#95u=pof{1zH5Ji~oaVUV!DhG5EjV|9{};`+w^9fBjt6^A}?$ z&tkCn{PcEpD9`u&3oz)bMD%8>G&G#b53?GcHBhS?_y7KvOCtL7CpWA z7<23Fn$$1&jk$A=s+4~i_Hrk?x2sj4Kd(Q*9N(uj9qn`SLMGKNsdh=VOR8N`?UHJj zRJ)|wMV}nn;C?-Ii2DZieR606?EA!h1N%O4-@v|44sC#apB&l%`#y2sz`jooeY=2l zyRfCS3tLLNu%)yMTS~jIrL+rMO1rS7v`fKN8(rDdmE7)_BX7HcdEQ_iecL8?M}yax zn^xWI>es=UtYlZT-)48P$P(uDmv459j^j*LvYX}4dOmOx`?{0en5W)$w>8GT?qoM` z&Ib3>$MY^^-7cwiNwrI=T~h6mYL`^Iq}nClCfeq9y)Mv++3N^hnZ54L*TwAnguXHR zzB=DFv$uisIx&0OIIk}@3Zh-W|n zF6N!Ii}@(+VxCI7G-}~oyYl!itk0CV1$N>7aOkuUBoeuTOD#!F+3M zudF|rXWsF)?OgHl26_yqk_rgIzm_fx2${AF83*Fm-`yE%QlGGW!psU z@-tJOFNhgkmns@2A;JjN6e7tqhj4Io;%Vm zo=4Iyo>S5;o?p@~o@>%Bo_EqNuPLH-3BC`%hYpw%@KG@43VaugIRu{uV{XCM!I*QH z17OTW%ndN+DCP_pa~E^?0@m%4YL`^Iq}nCbE~$1&wM(j9irTeGALdA&IjV;_s-HP( zmpRghInt9kvfG8M+ZBBvBYHBccBNljuG$qlaJgz1>lyfoL%$;bVUEU^IU0B7$RC&^ zKVgpihdJ^qW;`45j70s4b-Us}kP*LPR_%%(a=B_({FcjAyBrI#CP2HwIR!LhoD5h=qRanWOgw=IA|w8L`m&E;C{h*664cvC#Yag$&=6b~zS$ zAA$_W!l+%2g;Bd43;i5m8PzVw!l+%2!BM*$3;o>YcBAJtbMzc%j-Kz#(Q}_US`RQs z>jdU#{lFZpXD(#juB;OvBkKod)vl~JxLma>>k}?l?IH$a{f2Vq%dxIw_IhHy$L#CD zI*{4-3+qE>-!9gT%-#-IPcnP^V4cYvtv@eh-L9&I+;0IKQl+`YUXIY%^a=6nWObNGh(6mxnkX}tivG>zrr(~S+y(cc`jG& z%KD$nRl8W@V6B64=jS_OBD0^5SQ|0>_<%JNv!B0MOELR+f;AR1Vj){|;XRHS zu`r4cPO)wm^Ih7N_bL3Xyk{}1cICZ{%T>FGKhiG8B(w*8pbP#D3?1<|VCarMfYB$k z0Y+cZXE1C4TYzC3=n96-?IO-gyI3DeyLc{0yLetmyBw3? zAJ73Y31bOHOoDHL5tA_XV8kT&BG^AS@%@1rz5^dZIbsrg8Vnzo=e}ayF4l+AF2~@g zU5>#~yLc{3yI3DeyBvd~b~y$|?P8tgFt?!t<~rsc7%>2`0F2mxxe7+iKVwJUbua@8*VIdzfyd)xzr zekm6J=W@(@tPjxcjYX_mIkOa(E9Pf!^gg25DH+YwddV7B_4g87&#CHfx@n(=e0=S4 z_hp5!{%2BNai#VlpFpy!IC8NYce*_DzMapz-#Uih^v17y&i%Oc1}?v|=CiKp_4PxU zCiC3L*2EmU>=_q#xCQe!&NbzAJgYt8r`q^Bs#8 zxXTs~V^;P#&sM50r20atFQocHsxPGaLaHyM`a=88^@UVlNcDwOUr6l29Hzja+gKsvtSMuJ>T(+Tes|J=~ zE>~&2`?Bm`KCeQuyFP1;YqB|m`P))&x!%+6V$RiawL56$t%pp+jlq$O&%==Ox6DzU z%u!nbWFj4yBi)#lO{6aJ+G2f_{-PU~ z`#H@%iasjlcbb3o9QSjY=O^S9pSNzo^F-E8O6ELyKc^k$1M2Z}+F?F`{hW4~4`4s1 z9p(er&uO09U_YlF<^$NzX@~g$_H)`{K7jq4c9;)fKc^k$1K7`Lhxq{ZbJ}4(fc>0y zm=9n-ryb@4*w1N)`2be-(M+l@r20atFQocHsxPGaLaHyM`a-HNr20atFQocHsxPGa zLaHwkpSfRA>;+3q=5oCrh+-O-E0*}re;dXB3uPn*vP=|PSSE@&%uy_2j$#yZ6uX$C zn8qB%I_4+_GDop7lnLWMa}-ONqZrE^#a`wpCNoE|npxRLo=qs1ILWN~B5{?=RbM0y zbGhn^#BDBDeUUiN+!LOd^~6N@sNBxXZEp+d_3pa>*FE$c+TwOA^CXD?BgN%c+N3A zVvg;ROa}Cf{+2nalR0Y3LMGCIIns?;*+le5xz-=?T=Ykb75x#Ft-(uJ;Srm+SHV0=qM#zkWQJy{}=Ma@dbwj?BNZkJ2B0Av%!KpOpUaFVP=< zC;G!5bN*K8kMS4%;n$)+{9W|tv5WM_{1E+_BmFrxV@-*1M4XP8V>8y-C|BRaARj1s zVaVh6N62eNog$-|V>8yQs2{P}#}{VAW~^CJj@azu5i?>l)~qN;Y{r@ujM$7dYsBk? zu^ty0tkdOhv3{32v96c4u-+FP@E#z#DVv;UA3R$k8IH}--*Rk@>g3oQwZ*YH(t%@h zq#MWPNN2F<4;j%Pe=GWU2`$TgMEOU^{qxs0?(H!S;#WLSn zCYtXT$~Y|#e?yEzyOHnZ$Roy~Jn~iM$cLFD-)4?{o;jKe%+VZSj^++?G^d!OxyBsL zLFQ;~GAo;$XCI}%%pJ(foMKk`%N*o#r9Yl698dALN`IN-EU)yJn84*qe~BSnuJlK2 zW}RS9#qtb=yo;Wv{I}8bh|3kr^O|L%=kF3I zj}yuj^I8n!3f=sC=QY^{GUv%h?`~Xw^iIbdz3VYY?|{tFyCHM*&d40SOEO3An9R|; zCv)^p${f9`GDq*Q%+b3obM(&39K8!OEBl;hE7ccyKZU%!w=%1~$a^lAtG>v4F_){p z$a^%GtG>v4Hv4J(ow%O|U#SxjcH#a=BuPo>L-^=eWqrekysUUnnEb zHI|Q_9V`<)Q<$S?4RiDiVve3o%+WK8IeL}};~6b7cy=>K&vfSKSYKeguFZ}nU((XY~^yLzdVb%JX&LjjOZ`Vbg2_-6=tQstPQwa=}-B3ozCd8 zbRd`iG3*BW#)tixH{H_J_UdsL^Vk+?_H?&C%u3!Vd8g!^l6MCd{cd0Qt`-076ASaW zY7@eE^?Qjz?(BkiE-%usgnOz*J!U2El)O{&PRYA(OEhyIY|PDnoBO^5w{Y8U0qlIX zT|4*pBVRKYS#rDExatFDCGV8HQ}Ry9yZL|hcPXu_^WPr&V4y1;_iH@rZNQ8PGPQ`(!&*<`7CqsTf4ZY zM!w0cvti%Ri3DedpS+Q#ka%;m)%f6lHf&hMwBl84WWJm!MPV@`=Y<{HV| z^mCA8&ic7YGMD|FC7I(&9&=XYF_%RiF+t=JD@bCCk0B&6$Hx|uSma|)ATdhGBj$)a zVv)!rriuLd^=~RquWW2Um}~3XUr&wW!uYngT_dX5)o}TQ%bHSp-zLltoxPRv=;=Zcgdulx|Mx=9F$u>E@JfPU+@;9N&(9_!7TMW(S|Qs6+YZ24Jf=P%`$R*OF<* zAKdrAHE2R_w`2QQ#lf4DL^t;!zNb^k+ePc@&^K=dbaT;$6kn$SmET3oRp$rv@d?A+ z?e1n&Z+H{txp5t+WQQuur-md`mshW69{ze0x~)qSN-A&}HOjo1UbOg~G&|@}C7?SF zU>vi9{kd+T%kB?ley-Ar9@`d{H~*qJeb_lHFLtN{{nq+suIKiS$y8=Mo^jd1;XECv z>dc1BJ0ELL>Hgaa+B!BhnFf`w%Y1sdUn`8Q&Ael5GW}c$zu{&FnUy-w=y$3x*BjM_ zetv=N84P{2J$*F<{*xWwc11f%d#N$=fU+HETTgB)Udd!AnG7Y9q5AGr->vGqReg7= z?^gBQseU=7r&WEo%05on$0|EGWe2D1V3i&8xH~oOPK~=$LbRE6d^cL#weE{W?inpKww}*V~ zi4K&n=*?W7XIXp7PmP$1HRwQxuW!gccK5(!YI$Wn<`IwkeFOXJu*}>&-XC^1q{#&f zQ;%Zp>8FZ~nXl^Cfd*}Ez}$63B0c;9v2Qe++k_tK1bc{6jb$;tF`gSyOnz3+{jRh#+j`u21~dH82) zu;gGn`n_jk=A*Z@r!iYOUInvTbf6je8gls;?{=V3>u&bGmmK68lT2oAUFM)mD@xgF zV7FjEdW^ms!Sg!UeOYT-)|O*qu=s%lI`&{FqvWlUvFdNFlDA4vtL$Kv&Q|GcmCjb_ zY?aPd+14t1T4hhG>}i!ft+J<8_Oxp3oEmGV#@Z<#b86h3@dp2 zDc^I-&zB^<7Loi@=8@lR= z0P`YfShy{{S3hJ`ZdJKee`{5pR_SAvK33^tl|EMW%c*`jWfP}t;*?FCvY}J9)i!sp zH0?l(i#J4E3O;B3)m_Sl#G4U_x-w`x$i-fe?CaT z?`$ipIB5G&DizCqGw}C*zo_JGy}m=~@;+Mv%&7xEjiAP#Ze|{Q$7s4`^gGOl);~;x zKg?v_aC8FY|16EU=?{}=bIT`~_a{9>)t7Dzu&(GhdIU{Bg|W*HcI_KQ>8syi&Nq4- zJ$^ikWhQ(-k$Qi&j>{|Ood>R#R^*nRl2h!+`r8v)$9n@c$M$cAX!n}D& z8nrLElx14COrxWJ&0}uzaVib;_sBqp$FEGKzlzUbd0TEGnW>YRuRf4U-;Q0uJlEH= zs_as5eB+5})bmQ5k;#s)_GTKrvu-i7lF3jq8A>KY_1&qyTh(`~`tDTUt?Ii|{c=iA ztNL!0eVnq7Rd#U74o=y@Dm&N2@m8!k5 ziv3|u+Cy}7{Kf!ll{s0dG`s)G0Be}+H^$M@%~@RjcH;^3VFSm!Ye5?Q@cAO<)32n_ z!dG8rUf{=KT*6|mlLn+w;kTb<&SlbQ&h&XKv*qF2d^-f^nd$a z|Cg9sw@#()Z?9tC_@==_v~$fyU(ed$)i+aV@iOSPAn4t191Xf+1DD4i9Z&Vs9dpX! zG}>~@Qsy={!%%6RhN`)Id&HU`EY4qkjFZ;GqgH1k0UGXb?EIH`@ zXc{%^v5d=?dfjHmEoRPKnnqvT@B+*1=#)m6ADGWP`piU{^5i<$EvTP&98K=Hfy;X@ zokW#8@foh5Sjr^YP-ZR5D0!=7tomE40%J-b|bEo`J&jt62 zAK&_g7YA6w-0l70srz0Iu!i~Dk8hphuX#UdNc+2`(wl=E0RQh@!=Gxkz*UU7UcKI@2&$3|t@-%wA2BTQGC#6oJD|W95u!i}pMH-b{z8pFPJ%3K64`VAZFM^rH(&&bUZ!oKJtIDnV zTdV4{N*}BAu}UAS^s%a6PW8(vn>b|?r)=Vs4V|*BwmEZl$;F6E!9s8U{x7}2{GPY% z@@X%^=7D01@rvZFlD8x4rP25nuVX9%#a4ZHqVy9Z=$lU(^Y_@Sl(E!wLS5c#bhJYn zHNLts?=KpEYzh_JIFPw^wRBn+zlb@h<8<0I@K@%?w@sy9CrVhXVH%W8qcdY~WFB1k zLHays&iq)up)~uBj?C)287bD^(45lEDczjX%_-fS(#)=&t^}djp!_e9BYPsOJYo zS^nCWr&3(oQp{~SPoZm8ROG+iKRK0}yi=RG?!D9Ljv1eGJ=L2}r^SW-0LLHm<$sO* zkvXx@bh^Fl-^@xTL&;<)nGDr;r}}G^9jxlRQ+>Cp?@sm0DLt*~yH)ma%05=v!6`d9 zWe2P5pvT>*ad&Fmof>zi#@(rLclPe-wD!cO8Cb)-TYoyee)(qhlY0(MA+u#b2G%ei z^`1^YHT@(5YnbC}r&7r+6S=(ebJM6v&sialOQ*$6uC$PUEPguGd;bKNC*___i9O@k z#|H14Mt7Vk#7q;X(a+cB>?^d#mlDA66s=u{L-YPw^z&;CwupqPKO>p;_F!! zG^pj{Td~v3Gk#5{JErFHb7WcY$H(dP)vc>Cu!ec?K|fD#{Tez1vxiQnyO(amya+}; zFrA*i=L=?4ZdJKee`{5pR_SAvK33^tl|EMW%c*`jWfP}t;*?FCvY}J9)i!r?&!*G* zRdE(;m>TQT>C;k|GvDYxe6^mM8*w90Y?ZuK^7d~(UU$8^8)FeDw(7SzI@GuqZGK`S z<}96^bvKQA_A};6|G1Y%HUFOZs_nxlsn2odF3VDA>Crd``MpmKBXf6t=DPa_&_n%- zFt5+ki>@emHFK|jcA%6ui!zri+=5T5Aw(-LRXV3&mf$hn{%s0Q2|$`^+8Hjxay-({TFuAE%km zQV+^1d9}kFtiQe=rHm`e{O8JHROj8_c>Pf2?t3Wpo&C@`IDP$4iogA5<`>h3)4Yl& zS!Pmp3Z<94jQiLkF@;`#<_wpA_tw2sCQl)UHOwCs@1cL5#Bci9!K?Fz(kEjIFgLq( z7+tqHKg;wzFo@dEDa`!v&;gY6Xc6WyH{C@Y`eWR)gWFd3puNRId*ukUD*HHPAFJ%(lpUP1gH?9WFmsKaL+L{*;ILMy^zktI;oAJn z>wgu8^mCjb_ zY?aPd+14t1T4hhG>}i!ft+J<8_Oxp3oEmGV#@Z<#b86h3@iMx}EVa9G3STQ;1&ef=u$Ck?6Kh7>wg@Cx?f zZ!?F{;T!WitYO~SG?X$s6kx_UPV-}pHO$|irO@DhmopcC&-=#Pm}_f;1AB*2+q3z6 zJw5s@$q_tNzxiI<3;jDt)Zd$0~i;Kcjv*)i0-P;*?FCvWZhRbjr5c=I-x?LuuBI z0*Fh&>J~$2#d8IjOD-HjlR6iK%>%_&$y+6F*Bu{Dee+(0u?Q4fwSS3TD_Dhke_I#x zk;dFqje4&&%txx%puKf49Q%hoSRCqC`V zJmTKMRNeMw{$=51ROY3w%%80~5?q!V?mbicudv_jU+u+mN;m&3$kELy-JH_RDczjX z%_-fS(#^wWf!|cNisa8#Sy>M_RPtITinPb(*(5f%*QSHK@#;?U*Olu0gj}x`TQ6 zmV#6~e{bd$zZ9bx<@+*M^<#AXuw?i@4H{5`_U&oQ`sewyI^EJMfw^;+8Wh`fJIg$B zO?CR=!!BIj?O1hs^T|88{DYZg>C(zFTD< zr|jeR-safBDLXi22dnI$$K9!McWT_78h5A0-KlYRs~)RD2j}(VHOv(gs?smigZ<%= z2WwFKSCctD7g$k+)(q{*Yna<_uR&j&y`9U=f$9|Z$(_uTJC~*XOZqbBdcFeP_C_CO zn_8Z(FB|&U?v`b!>enIPU9L2B_2Z5;PnxMf8DI3_wMvVpE7HQcAr~)Eo(jkMa{1sX zRjE(i9_%wOd0#!;Ioa#EHYo636`I@@x-AGscB?@Tj)*w@Oc|>|mA7R_Sb&&Q|H{pKCcfTV-3T>}i!ft+J<8 z_O!~LR@u|4v2$vyof>PWe9WnFcghc)@;#?~&ne$?%HN#wL#KStDL;405A|GdX9t$2 z<5m0e8s@F36(}vE53gbVK30ih&BFNk;J~UB^y|SsJo@2^R5sR!*DbGCsz3$zhdj-X z_2Fl_@w(-qja6yE$K9Flm|2x7mB(CL8%$VHk-AmFd|4Lc>so>0J`TBhgYtBy0p`fE z;HD|n==&z!cnvepRHklmtV8hiEmi3B?>#Xuf*Zc9Om7VA#jMJ$D!1xyt*X;1eXP>Q zDt)Zd$Etog)i0-P;*?FCvWZhRbjr5c=5FSY@-(JOUtYI-Z^}`}F(F^Myd0hG!Eqx{ zY?ZuK^7g9-E7Revy?70y*s49=lzi2*K~LiI)HJvJoM6qF;h3BB)=y6avks4A{wvob zLH$LOm`4pu4IY~@nfb0peS(`3r!nu?YJw9br!pVDwnC7%M;h~Q_x}-J;kU8OrLI^X zf91O)nAIM2Qmpr@JEfabx;dqrQ@S~&n^U?urJGZ_Ii;IZy1Asyg@QW2PV{c9$`6I#HW^A9J)Y~RF9@-&L<#xi8_Xl4Nn(D_it&)#u$+xHA7l<`33Q4IV9(#{5dHGC`BIsmxz?tsU(6aWeBY36BIt z#!Q0$)7E=u2JiNJi1qJ~_wk_B%M+OAR!R?=PfBH(ML$dohUS{Wbmr!n_?H8FT?JH|9S_@Pg?pigUzb#^enWv}2=QYh1Q@~uJV*;845Y%vPHJw1ha z$DW&ldkTm3&wSvzVBt5Z{I_-I4i83e3hNx5+$;Fi*W>Gq-)rs;lHx;NJgIBYzg5Ue zCPT?&D47h^cc=PpRo|`ZyHkC)s_#zq%PBpr>bq6;amqec*}*A0IAsT`?4ZZpsd0B| z+?^VCr^el>ad%rcr34dKz^_`+Du636HI=_7)6FHYq(OuK{A zf_2ZPa(T7wlY`GbPGerSvqLbd=rrbEU+5AXZZVDPDfnYTaByQ-XV##eLHjnL%=0g| z2ue+x%JQ|>cMnGRam06+ovZr>@wbLN@|#XUT9c6L&L0&FY!doOv2Kq9alOa-Cmd&EVyP0uTSoMCOxRo7CxLDl)H6Yu=EZ1c5*Q2&xeC;<3brF zZZwEvNAs=2YwM!6E-#!#A0a{8&Hb#~R;Z-Y7CA zSX^c*^SfV<3X&Ry{+51YzhI7U3u~20^?L;Sy|03c_v##s^S%cjKJ?+B)#Fom4Kr-T z;NY7=tV3|H#PFc<2Rtu=g@=X&b$$q0m0MMA)!$lGr&an`rH@tmSf!6u{c@^bPT9mM zn>b|?r)=nyZMDr^v6fwex4lj99p;LG9fP(vggm$Aoxz|6976)dR>@l>Z%ZA%Czz3o z$0AT{{hA@?+}!YoJbW0xHq=pJw1{4y*b_`?`mF>m;+nJ|95 z?KCu8hxA^RVrQ)k<=fvl)Gqukl)3VzNp{JRu-zk5C)@Gghijo{tEJnq6T)@NgJT}I zi}Ho*sGZMsw;jWEOVGN~P+RpN*BL*3!a!TLa=30eIC_K~{8Cu1WHOXYhLXupeRrzw zR`uPgzB|=-tNQL#zns$3s=ixgAE)eNl^vY2gHv{}$_{$mof>zi#@(rLcWT_78h4k{ zzMCcgT*eyai8UQvIc`C1A z@*W>-OBV>&Ek)nC&z5^IEH5ynqs@C`xbA(RR}H(bJ=Wf9gU8?RV*C3w57scNU%biw zcophj8+=+Y-frI>^3i=mY`Tx_C=Zs5vC9gEY>P~?`~L{*$vtGUef5`c&C`F#Fk9BI zy|IR=y>pOlS|VJl)SG>;J#-3wl^ir!H`4z0SSa(+sL}QxHN*1D9+_xu>2Q6r>atdL z;Zk1v1s@KmZLj_*oa28@Yim3G7RsmJkz}jw4rP?QRWerntyS_?>1mZ6tkT&kovqT@ zDxIy;*(%#wWlyW@X_Y;#vZqz{w91}Vjh$0t?bKL1;V(bkpTnlu(#CZ=PB*% zevjRnH(a-L*+1OAn>Cf!Fy;MNxA$X>HB9k$ZnHs!Y0UHLcC>%iL_Pjo(!{}bLy>T; z(x%98JJ+vCux@$&&iichNg;2}-^Tv2e=4tG9{IDcZ5h5J1SM|hVfXlWi0?2bX7sWf zB39*Am0R_X%bCampr6*~BRuI%QjJb4QPlw13UucdH<_ zdX#NQAx~}mfbG_uV@sgeDtW8q?Y0$tZ1se24Wrol-)?ep3sgDrlTGs9ma*PwQa;X| z?1|qOk}0in0e7@>FXm-quXZUL`5P>4?pMmq-_w`NuXwVuYw=bn<6Cm?PV2!-} zz0-!d`CZ=5E%EKWA@#ZbYL~e<{C%hHJ6E|XH;2F1RQa&bqY3g2xyJ3F@VB1p zo+#}m`|t4RxlycT+LSvB|mA^Z;L&zMiI;-)ElYSSufTzK3HDG^&i1)#VeT%C6l3KGF0E4>bq5ax2o?>_1&tzJJm0z z^t7t)R@uiX`&eZMr|jUA9jvm09(Sk4-KlYRYTTU~cc;ePmHfWE8*{1;uVMNomvbN9 z7y3!jyRUX1t_gn+x^H!PH?}}uUc*dVdX3xJI{Xc2(gP)YE{u?8{aMvzc|XK&Lw6Ub z;^x%t#eDMPDsJknp--;bQO&I$)0O@0%SP4RkA1ta%$SZ{VS@@LiE>s2~2e^#-ITU-kMnHs!bw6e2R zdo$;mU)k+^h2vH5&9_zD{_6OKpBijiTGbUhfjOQWj674#%_+#geFvXxD(yNSV7moN zelO-yD{$Nk7C(HQ`}N(BOa55K?b{a0D0!=7tomE4RW(l)pLUhfevP zQ-1E0AL_Z_=I*WHvTOC^HOyD#s<=O|>&0uBUrtqY8;*x@_3CluTrfEF|9ZVDyDz@s z-z=zQ|0-_92R(TWbFUxkQ+}+mhDqO6*8TlN$S>Yh&UG6b`e(oTmEH6!d-J+wVyudr zeWEAxV`r+kd;Sl5?;W01(e?Y&6f87-R8XWUieMK=_71lSVgn^8c2E?%lz;^(3M7;S zDe8lwh#-muMFo{WW<^1;bwUgDy9bH*)w0wG8 zXWf%2cfrw8ZIt@&BE!z)cP77U)474%(oy|-kzwa!XoYwCtfN)OKqibz z;%_g#^Gc~v?;wop_%{FEn^&BqH`;xZ^xUQ~Z}HmlIZ|$O70t8%z#KVo`0t2$i<{ru zLuw5APPt|68)aRGWy*&wxmxaS_NKDA4=Ofn?}id1n;6-|$RSdPy5EzlxjN#lFn zmA$0VX^4Sr5w|bxD&60yiLnqbyS$4W>&t-{ZH*CgRf8WEIH^F*)SOG zxF|Ye`wg;sW)h1#|MMJqrEU^?nOc)0UC*hgc|N*5N1EnWR-W55N9Nt7v1jq(g*h^@ zq`W@2;QAaH^1yD54Zb9|mwZ|KC*RhKq9!Z5%csY0Rvx#whvc7;#0GzPT#j_?hyJrD zv);H~vTfOZ%I6Nrkrf^FS(zqJk;zkJ@)Q}}#pvryJvgJg7~P%GU5s90nRS)-&0|sjBT>SLK-Q|e~5bxR|-qPS& z8ToomwK0D0(L^L)5GM_yW2NqPC`969QU%34m> zl{xamCl!=)TIERZ)>SmmbMNHHrPInQx9E~1HI`RaTcz6aUUGe#{gkt(=E!~1_f`J* zyzX+yqgAz^WG?C|S?{Ai7e*60^pIocLbi#~P5$1w?{7}hFZucg89673(cOMjj{H_o zMf2BKmLrFswvY0+ALU5tujQ4S+>#^J-`K4&z-`aTk>!ohKXaoy_Q{d;D|L>FK9pW^ z^N9U4J^P^?>G#vV%4hm=Ha@VA?|a!%eP90OE)|pqw7x}dxV1X!Ejq3EI+-~@$8~hp zf?MU$NA>=?Xw-SP${A~`X&#f`nLN(?)|vdy$mvWyI3uSs@;f85Gcr3Pvom$;Ono|2 zpU%{$Gxh0AeL7R0&a|DFwieUYV)~evb{EqR#q>QfeNRl^6Vvy^^fxj6P)t7;(+}-f zkdObJBTxRmui7x*w#|_`$5v4r=E@qq81)uW`LZ5T;TXi0SBS32?kT%o)3Xvb z-I;V}e(Ow`&dB48JkH4Dj6BZhB}OkXbt0xt#MFtHIuuj4w$A0_2mSm|sj}KFcfFe< z<38F)d39lqY)_$1nnZ@3$?r^lxBKaya#TBwwT=usf0j9YM`h-}y36e&^g9~y8^i9B zCaup_8)MwyAu>Jx6y+C&4wYtg8Y?$XjgZts|5EPLuRwawUXC+{ap$Fe|2Sj3a(fvn ztM6*7+;qV`()YyzJ+D3di$2mPRa?(-n>#aO!}k76F|vt~O^j?}WD_Hs7}>cjuneum~!{o_Mb(MeHXQ*sB z>@+CtDwn?7II$l-$(4g9AFuNNc+Ozi@IZ1-eCOrEWWv)8G|vT3 zkB~=Cs;PPIxof!GJLzyuKjn}DNws(#=lkM@E?-7Zepz)t@`eIwQD>3zoI47n)3VPs z&(@pr<={`AR(@l~2r1onoN~=6!)12Cy_)})=0oM2$r;M)8W%{`@xLm6=F8c&>2q-A zp?wSF)x~R-qpk(gqua;ICQp&cQ)KcK8QsO`>n_<-56S?;Oyzjt1i!%Cy$$|d7izkKnmu6s^_T(_&K5PYhNorc42|E$^1aM zg6~V!ey^l`Y=7_b%-`PF%UKw;-KRhnWR!ETVczdBOp3m2py{POhD+{ml2n+^G58zWlRvj*9m4 zvb8;6wWgnPS%H*)Xrc1bV+!Q1C+GS8mL1g_mM_cdOjEwMaD;qve+@5No#>QfhRF@Z z4Kc2xU8#JzrPcw;O%KkOojVWIJSM+0d7SyJGx?p7(;3;Ek=dF0aYklmWOhboXX@6O z`gEo~ovBY}>eHF}bf!L?X*)4(EvBu-^f58*E~X!f>3d@Oo|wKTroV~lhhqAkn0_v% zAKI}XKl=7feY~&;@h~s@{%~{a&-85dB{vtyQL8rje$pa->AifJ+PsqX|E|7oO!{)A zo~M5P7XRDziYu)XzaeqpTCwbUC!G_`)5z|t7li~dFoj`3gpl^ zOO#K!s6bX7zd-rL2KiF4^MMZgFb%FLkOAL)2N|N}&3u1u^b6+9=+?6eWW~50$|l{J zbZ36+OqtHeQGGG+B%oMmlw#&Z3{6kMJrA! zkSDvprTozu1@i6kcQ9{6hMmdpOnz74Qvch#f6%klhMm7tE`5*p#B=-_?YmYH?2x>x z@06`Ou2Rl;`(9ak)DY!2h76I{i|$iiet4eLIqnhVmzw3tYXe?XzGuZC>2kYM?wH?K zzP|zYs%6I~KYEKCKK@*>cd^Ud~0)bw&N;w%dAuo#Dvjaf6o+k{NfY?$NHcLuC1_BcY=+995Z- zC%em@j9|l<{H|Wr{<3af&j@4c{j=_oTYny)ysF<|8J0C%xn9>?`C!BY%H==2Q|3o+ zDfg;4P^MmrJHcAS18*K8Pn>vP1l!|?tplatiT*18uNM!Nb$P>-$M2Ub`yM$~^Q>y0 zCy!k{LDPSHC0DL&G)~hW+CNw7EqYaX$JImRj!O$Q&%Zy;m6qjaDA%o?C!bxacQM7~ zmkyTE)#hmaFM1D>#@n6p`L_?0kA8ez^VdJ)F3GR>mh$f}=1HY@le_ZX@#WOK=q03Q zw!S7$8cljZdBYpI@_iS5R;I~QWbzc5JVi!#F}gdWyED3r(cKx{#poqQPG@v?rhdfK zk2CckrXIx9gERGD+g(h%i)nW;?JlO>#k9M$_x-AK-KTMXRD8FOfo-*LiuQ-RenVvO zgZD-74V^YKPwswcD(+#6f2@@&M-LyX=?muO%JKgmr`&bt5P7T7YswSK=ShRvFDbwO zQm%YaG(*eWe$o)B`hB7DXc;WkE}f%!7MJA8teltiF1sdYto>?Va-Ef%y|qZ_$NiLu7XQF`B-$ zAWzyin52Aq|2(5Tl&$n1>F&dBUc-8xgB&eW$f z_32D~I#Zv{)Tc9TC#J2%^eZv#E~eeZ^g}Uy≀P-S@=wJu&@FOg|LU_r&ybG5yev z1sVNJt_)f~L+`kI?w4HIRr-?Nad*P-Jh}MgX}+Jdh)?lz(W;~LzO{I8lqX;9o{qcJ z;+wwq^X=r9l{fpg{;K{Yz1Obp(|NM(!zYx>`~G}RKE_&Mbl%x{lKaqfKNhA%8^6u< zF+DFUzw&Udzp8zv^5j8z@?n?9^^Ut459G-m-#!N!q8Zckyq_2MG5WLBQ}g7cR(f}+ zO?M{Uncq57rZe(5BabukI3tfUdWq3XOr40S6ESrnrVho_t*vv}`E0JtS*3SxM(?)G zm1{nHMen$qaci#JbEMuY7#VgZzccyWnn&}b{`q?MU}V_&yZwD1su;t@Sbck2>Am&< zDFEj*p{jM#HVe1tVJv3 zLqCe7{5}aEQ0aI%qbSL9$?W>l^`I7-$9#JwHf+DcB1SebvWbyRjBH|L6C;}#*~G{u zMm90B$uoDJCUvL9UQX|e+1*YaUw8!A8IDXIci`eSvMo#Xjcz!=e-F%`!-NfEII7vN zgWNH)xqfTFAVZ%*|GJN8|HM7PnI05{J=#2t>ye?%Igovl)*Ez zlsgSQT^9QL&+*$^8fMGPFOH32!`z5y#!WTPmciL_ z@v&D?UHLp|xhc65{^L{I$z>l!nx{{>_HyXydJlHo^Zaw;-=qHOZFRIi|ww5L7CQp&cQ)KcK8QsO`>r6d3qq`X0ozY#4j$-6= zrXHNBA2IddOg)IH2Ql^FOg-3k7t`)y+FeY$i)nW;?JmFU+d;~W(mTE5GhXN*7glVp z{o#t^{r4shZW3#JOT7*<<%$+DY?z99*^=9>siuGB+kIK)3CcqkpDVk{Who!Gw4EH> zH41#bEUFx9nU{Tjw$ynx>3g5fZY$$ACHbcfXeX&jQLOjFJl|f9cr{abbMN!ziqm7| z3t#RaQ-3^7`^i~#vt{X9$NDl0qaRM{AU~c8*?dfIzigRYqp7C9^Fp?aEjeC!YK`{t z(kb{JM`3i%5$DNoYamZyR9fY1`Qb~*Qy5L@(MCQxH~BU}9oJ4)_d#FHjb>lkUKakM z^G|f#>h{ukaHggYo^`%Vs*Qf08@=26JemAD#(Q=&?dG$k&wTXN?C8w?+0uXb$*8wz zaF1;1_R?{hKDSx6JQkm-T&Z2Q^mzUh&13RAlgF9gI+NcSIh~Qs8JV4_A7^BCMrLPZ zcBXEfsZVF>)0z5oraqmiPiN}WnYQ!shv~MKhI`stuHVzg#I(DZeki8ziRpV{`koxO zG~M4kr~9Fpz9*)ii|L1UEXWsfzWj7Z9Ah8mjn~`Bc{x#xb4l$#yg+6S%J6-rMST23 zKTjU7_uj|PKh$2%d`IuJj|;AECxtIYG3=RzzOB3Yw#GipRZBX^u7cB)PcG~rBi1J0 zyqG+%y%bH#^y6h()Zn3Z^7$x?ooP{@(dYZ`h~QfW)1s+oX3K^zPl>S)Gq1{pGUz0g zA=>fDg|c)9zIjn0YLs`O+}K~g;bPOBNq6SA&XnnlJkH4Dj6BZBrKFn>;ohL<86Yg34eEGVMe%~Q7>`Z=V^1Ce=7s}Yp zEzuT{VQ0SY7H|4-r>k~EHpXLI{;8dAN29BhU;AmhJGkIx<*5s{x@+TJ$|o)P)-8Vf zPURz;e(mD&_bA`~i}qit?@pPtas8IGo3zut|F`};P{YiRPjKAU#9f%C7`F;zEvhkLWjjmj_7 z+3u>XyiIxVM_b&#`u0&C`RE+ir;2t zd1&87QGSQzuG0kxAD!uA!s{k^7FS;64z8B)zMB@f-q#M)-?|sxcH5c^(BJOrQsjQw z&{z5A(@WeD$0zB%QY+oABel%T>kj$GJuw~qXHn*iZ@zNXFGmmxn0j!g9&EddX?HR0E~eeZw7ZygmpN~h zxSl_uU$u!loUp+SS=vwgL&4&$u3p1lYKOG1RqC!-+Fxy$H%I;8`d!;w)2|%)z1w&H zJCs}g@|kPg^B(1!K3d_5k4re}{gwOTs(ZA|)0ZuFRWcIJeBcxJv>*GhksAKI+>JQ> z9<^1fuKwE1TkG%T_vfrf-T$SVbYqf!>ggNYpoRUkZ>;-qtNVFzPhVzXRQ|G3_pc(z zHZf{4_Xoc(&|A~L|L}YFNb&8;pLJd7R@TOI3!`q2E^~8z{{$DFy2uSVDB-IQUFfd4 zd7!4}j#=S4o{T=38(m!OYuBM7`cihZy5}nQ?n3m>+^F!luiR7DBzYEJ^0`~sJIV9& z_C;>}Q3)@;ceAVh^IdA6EcodM*ZNhR$D#?N%iOA)b$*K~#GBmMEqyhQ$?r@aXMXEU zerM!#rXHM;(;4}lk=YrUosrp@x^<>LovBY}>eHF}bf!L?sZVFxPE1>iX=^ckOia6r z>4#$ao|wKTrtgXAZ({nPn7${bpNr{-b}UHS%&*+qtM5@8=FIUcT=$diQ5)vmZ&$nT z&OkqD5qI3O-c{exPy6t?>0i6@n+K}h(*CXGuJu{>D6jHuJ=3=}Y?!mZ+TeEG*-!cC z&Kulj!B{Jd<{ZAto&D87U(U4X)8;GO?o5n}Y0*)ieCdAgmhhPsH@UjC?p7P7$;36T zSxuE8s$HeT6}KLMaS^SrzRo>5F=3PLOu93_b*4;bO@Q(im6*$=ki(WuiSOM{$ayx`sj0awjW>MmtXn9J<&tw4a?5tcP78<+jOm)RXRXz z7{kun3=zMF>%V&&@jJQxd$Ci^UDrnKzrg!0 zJ8rq@yQuPP*cI7v`$M-!57q3heEX$4qY+!WC`Y?@MpcgNsBFG*85_2;iIGi=Y+_^+ zBbyl6#K`9NEz+`ykxh(jVq}v|x9x~(PfF~HI%ho}ebcy)mwAyh9GN_><9FXht7fV0 z(TDy!Gq;rVgO1K{wCj*Bqs_P8qx(E2zq{@C=cBCNiTyJn^-A=8yE}FK{@PNaE+g(% zE=;`_^_V?C`QXvpqjBwTRj%{v57CwWeqoIFjU(no^Xm22chImLeH%8-IC-1U{r6jucSG4=0 zXv7KYq5~gHe%q?&rl`-t#O7JLadTAtiM#Z<d*DLnI=z>$x~$V6dB#c z=<7^9IHS85-JQ{0jE-XDbfzAhsUI=*;7mP;sRuFj;7mQ(b{Es`V%l9yyZd{Y((Nv$ z-KFc<%cJra>iiRz?)W@fr}jgO_{AUQMLo0n>-<09^RJ@kyv>Pyo`wzIiHgq}py{9W zSP=c(9&>w>c*{K-qsoUS?~Ae8u0SM=fvcuj$QKejYXQ^CWEeHC^XLRS!Y=h0$+A zzlsX4glrR|c;wqrn}+D;h0!S=e-N!dIk9;*9k?!<^mvlq{;-YF#*317)BZ~~N0+{O zm*&5q_4j^GyF+w`%jJ};6y}D#kw6cNLTeNZ6{OCe&iz5ABZI(unx39pNb(TcObV%}; z{LbWY=C{t|cScTU>cJVAosroYnVpf@8JV4_TW9Linfi35KAovgXX?|L`gEr4#I&`T zwieUJ#I(DZeki8ziRpV{`kt7+C#JuN>4#$axtM-v$AWw_wlpf9++S^^OJ=Q$7F|0) zZKO_fS4Bs?p4dq9JA4s6)hn^{A1qrFb^Jx&#c_vgOQP-d5}wj}Y1G`eHEg6Sb}ozV z^L-fn$}68o{XCCH+dQAHhJ)1rZ2mqtYcFb1bZmkeAIZRm85+DM%$ zu8NNPI?|FRYL5uBG!*WZ0Sf&g6F&U;lOV z`%bl8Bg4+yGexw2I%lsg`qtlR?#E-?@RZ`BORh|8m2SgF79CwbPt!{Zt|+>F=P>2- zUfsXwzTWxD19J;o);)Hl^4QU}Ge0;eNq=j6-^_EK8LH`T?Vg!=-Is~Yv#Z|MnQPkM zy_Ovto60h5Ey^ZFHZih^kxh(jVq_B|n;6-|$Rdup~^S!Y+f`sYlQNa)AKTO*5)bSb?o_>XWTbj`RC_57rnJ) zn7$)UZFo=7lbuoji=r-%j4OI$XQIpK3T=y?alO*f#uNFi=w4(Y-{;lospWS(s#QucD$ai{Ay0U z%zes|a+Vz5HnVQgaLxbLg+nsC9h%5f)Va}|Df=hooOH|9mM0#moY|(+XDu#1HQ`%+ zX_GPcCw*?F$x~$V6q!6lMt3p#I#UnM=q^TgXLJ{%ml!#n(cPK)5mP_T)PtCM5K|A% z)PrqzG3_p<-Nm%Kn06P_?sCX8E$6KKy+HSQDjzUr&ak2a?GIDCURm_`reSJhG&-#9 zoI`wl!iIUff9s;_7Z2C;KKC{(`eDfkiqJVnbY$%&#?IoGI|^^Qf-x5JBPPC=JLovBY}>eHF}bf!L?sZVFxPE1>iX=^ckOia6r>4#$ao|wKTrtgXAZ({nPn7${b zpNr{-b}UHeT9;?E*j%7C%!;PfG9L5&0luoUX4INp_Z0M{7V&9c=Fd6wt)$OCKYCot zNli!U-p=Dgj?Ji8CE*p({5kb}Tf=Ty{QSf@pG{79^M(iJY=0%`hv&LpEoYp7@iHyC zsO{ky2USmavs|C?=310LEoxKw<2h$$6sQf;VfTR9hxq(nhUn7w51+H7n$D%sstIMY zpYr`2dp;)JnRI7<>r9!>$m5JW&dB5UrPA^^qn8-H#MFtHIuTPRV(L&#-P$^rx!W$y z*zW5edpkE?et*W4SqV3&otF_U)H;t0JCom;{O;M#&(3b$MB5@V?7r{%lVo;19OE%Q z($;RE6bNt&V1!J`RwWv#Kpxu4%;pJZ~a1f@Y>(x;yxcLUsmfkxxdpq z<*Q%+RjTf<--?aTT=lbDvkTui&W`(z{ZWP&JgGcs?RFVf4&PbMj%RHDLGGF~UipjR z@5#vXI$3tevufY@()Pr2l$)=9L!PUAn(~n?L|(b+2<5sB=g3z_?!q~R__)_+Nvruq z%4=%BCfAJUrd+=5t5TZvsGhwFtY@!6o=o#wuk5^vw_P5gJvlErK&nlCOC!DPO=(zRr=%oo)x_6xvTyT=6H>=@f#{IRG ze;qzqejj+Ja;M1?rNY#n%H6Uj$gx{)RQ_SwBU10-tCi20Jzgq)a*6Wld&kR)W$l$u zukeVJ+tfz+n^uoXpL1j7OPV|;spC#nzIXQHQubccB+s%ZWZT7wUJd$8m4Uz1)AUDj zo|D?&9HG3uaJrB8OXU3dn3*!-lfyLq+^1*B(K`~p>ESnI^GAr010Tc6>`ZHGe_*?(gPF)k-fZNBhl{ zBXegcUv!a^PW@*o<1hY=cEtZ99~i&G@4+Y!<%01XJP(ZLLk=+Hf_z}e3%SA21NwlW zAM^yHtP(*N=SYWn1nGW`beLbjevWjQD+5PlKSxHG zkC5)?$O!Wk*w2v><}a|HBQr6tf&CnriMbN&=g3UVgJ3^LW?+5{Jco>VlzA|}^0%0G zStjOVJ`3|SWx)JR*)ZQz7rY0kBi;|x9q$d+3En5HE4*h|hj{<6Zt-4Xo#TDQw!nLg zZG`t5+YawNwyAIHm~HL*K+Hbi`$o*Z;ropLwsq2Hd|!&$mwX?K*~fg}i`n;lpN!cj z{rHMGzWlh0Iqp7g+|z$QH|fIzmfsLpsh0HZg5{m#dABBg{+I3-$KO1ZjD==jo|opw zZ#^TO=Y?Barhj{Ry%W=AHvZt4^s|~wX%HWL%2V2=tv|05zkb=X%8;$_^JKo-QhHeY z+n8jI0+(E#^bJ36#GE($d=hg$@$*c~dB)E_G3OsYFU6df{CpL2zVh=}%z4buZ!zaL zKkvny_xyYqb3XKcW6qQQ|8;&upY*@e`4Q~P)A6{3eeSg$B z5$yY^&WT{(e|1g-`+lu+BG~tLofE-+9O#?~_Txk6M6e$>Iwyktc+xo$?8lkTiC{ne zbWQ~OajA16*pFA86TyBQ>zoMo<6GxMupjq2CxZQapmQSF&l54`M6jPfbWQ~O`A_FW z!x7leH!Iq<ru%oCujQE-)vOF(-n< z*ijB+N;!-*I-cV-YLrAU85Y{LCWFXq#WK^%Hdt69Nuxt;oYYk-igZLU8x-2p~~Uin&e5| z#meCwtsLIn%Hf@^9NzWH!3Izcwt;f68I*%9p&V=sXHfoN}=7l!NW3?CnF?gk;!? z%mW)zIoOuU!RAyBwy1KjQI&)3svK-x@?{K{c1pd8i+%3=0`AWVa$(U|4zZahcaw@%za1?dke~8&p|ot zMJR_o3gxhOp^P=OZx7|L*P$HtK$1Mk-iUJ8Gf@tEDav7wMLF!fD2F{6<*-+yjP(lE zEs!7U7|fMmtZy(^g0b$wTnWZ{2y-PE>m#!arsQXW(x73W{uO1b~;v*P{tPdKmLh4Ij(Ej2y=`Rw@g zpH5I7pW7imY@f!;4=y-A{`a%BlxMDL8-MoEfy(}jVazjz{*Hop?kfw_F4}#;1@Z4A zS1DJ#{hWBxl5NUkS6vlXt&`*#we-e#zkcs&`lB`Oh)=FGU-|Nh{o@b&%vC<5$Kbf{ zQANuAAJ2;qtNxtw9VNN(&MglqUp#7XJZi*n~ zXIvf6A2U~Z_k-8RcRjXPxuO5Q_Fb(vDDSt_$J%$@u6+5locP)A%L(N9dR)&q>-qzf zPhNXt-2b{7%5y4R9q(K9AmyvS>=5V7tf^e9dYkx}7n3~xp3<22l-h6jUj0Us_yK?Z z6XoA9?&SFCinWx@_jCWYZ~NNs^sT+&)u`Oc%T%_Uh3`j`YbWbL^NqZ}^ZR}2Z}D7r zjm)|5_kY_x{Ps>=-zSBA()U$iUp4pH z#^yfT*xYBk*YDc3_vZOAE*#^2>#CgHouoIQ`t+4I<(J&(=V^Vpm{kImWh*ql9&&DrzVoIQ`t*>igq9`Vv{ zO3B$V=FBmZDoNu(XDIJDteWhen7qf$`LfuYFN@9jve=w2i_Q76*qkqm&H1v}oG**b z`LfuYFSF;}5EI2XsMyD%JI1d27(b`u}(51AQ1ADdY8*uz6h*2!SF?3%?XAt0&7k%d=Xf4f`iSh9BgUjU}Gx> z+gmx<!EdYnx8S!`zg+O!s=qGyZPkw#{I=@f z3w~Sm`vt$P`U8XCR{ey*Z>#>p;I~!3V({ClzcKi2)ejl`w(6e@ep~ftV$F$q3u`px zuy#`pYdYny)>95^K;^JDR1RxK<*=4i4r@$h_$BafJU6UKmBU&!$+O3AtNvj;5BbBI zS2?VOmBSiYIjo(P!<=i1eFJ6Vw^jdk@Y|~2JNRwYA0GU+>L(9=TlJp@zpeV! zgWp#D?ZI!We)!>VkGJtgI^*Q6Zw zpp?Vjlyca!QVx4r%EoVt`I3HH%$E`7Ce%aN6H^X*Wy)a>O*!nXDf{`7ep}3!^xNv( zi8&NyhP^xfmVR5EgE4O+PuK%g4ts;jVb4%G>@g~by+`G+C#f9vDwV??rgGTZR1SNd z%3&{5IqZ=thrLtfu&1gV_F9$09;|ZMn^g{bw#s2IS2^tQDu=ya<*+BLZ2Y#mmxH+y z^%M5Mm5tw4jNev_-&Ty@R*c_PjNev_-&Ty@R*c_PjNev_-&SP{ep@kqTjk)l)jg`< zx7EEX%#Y9|?D;DPUx0G(5hxqKt?rp&e#CEsuR%HZAe4h|LOJ*>l#SmO@htS)O7MMX zp5PNvHhx>gv(RsgcozC?G0)R)i}{~^TM51-EeHFlm>(gt@!N{=+lukqit*cu@!M*d z!EYgt#&4?}{I;4W_-*yK!EdW&2EQ$0Sm?J!3=93Xh+(1M7BMXJ+aiXA zep|$_&~GcoZwp(3ep}cW^xMMrpx+iY3H`RPRp_^c4MV>zY#aJ*Ve`;$E5>gN8;O2f z*iQ7@!lt6%R*c_PjNg_Vp}m4{RN44#VMEey3mcMtTiAj0+rmDi-xf9`{kCMaCyn2h zzg3$vl&Ng|wy+`LJ68KG$fj)kw$xE&Hhx>yiKZLBE$dLzjo+4auIa{a%QlKpKgMs% zHq~_Fw`CvDbmO;WpV4&Vw`CvGbmO;WpVag)rj)~2Q#O8E_H9i!ep`+OO%G!vod1jx|lkvoI$jkMY}b%xb#v+j5L+y7Aj`uF&)_hbSArE$19fH-1~h+#$9^)5F}A zl#|S9%EoUC+YqrUnjYpx4uLw)ib#0$CsvK-oy^mY%uz5VIQikfI2sR zTdsZdx5jVFwUVYAzb)5Rnr{5IT#ISC@!N9krs>9S%e9`S8^0~rhMI2twwO0`euVtS zZwp&dZ7-yUwW|I$tYMXn-xju_+IGkv*20=6tdW(&+F3cQsg;f27Pcb&wkVH&Tg=1s z+iL7H=0`ls_-!FC{kGf_&^*R(i?*WQ7Hz2ZG|Dl4TkbjNZ;juUdlZ^({I=ZF&~)Rs zEi>#*DTh5P<*=8f9QL@>ZV7u|v~92_rX2Rll*1mHa@bo_4ts9OVJ}WO z?9nM3|H$9=T|fJsLE{Gz;|CGr2l?B+-DAHcWc(mv{2*fdAb;Ea{PueR#t$OK435(J=KhF5fk5nvBUTlj48&qh>33z6W<~xzC}!Yiv5fk5n zZ-OwsMNE7P<|4+oV2)yZiv5fk4cCcZ^Xe2bX)7BTTH`2HH> zTg1e-U~Xr83+8;rw}^>v5fk4cCcZ^Xe2bX)7BTTHV&YrG#J7lvZxIvUf^Xe2zC}!Y zi~p{8I=)3re2bX)7PQKM@FYk9-@3#&)jI#*rCeZ zT6T?2Ja2^ZXYXZ2Kh_$qyy?*TQRU8g%G>VPnOT3^0Oi{I&dIFuc5mgJTSjFzsjYD= z;+gR+V&YrCjBgPW-y($7(3Y>IBz0L(f$Ddzl`0GY;vj=_bAf zb;$S@)Ggy%#KgBqt9s?+r!JT4Z}S=*DBoXpweqw92T9J{qpPE?qYIKYtvI={v>I@_reA;dQBv*eQ@@v`HCqg;+8}e%$Yse4(u%5j^p8uKs3bS{CdgE`g@2h7& zAcNWKz`pN)>)f2l51%&9|A>)IIXqW6=niI`D2KXI4t1hz^0Q8m&bm@I`MDRWzcu^Y zkc<1j))-`x*4`>`xDhAw75R_ho#Bi-cxpW46mx~MN1zx8zjomH36_mq8|XrDtK zlOJ`${Q4LF_Idu`oAz>{jHcNBY>&dBvs6 zd+7JoEAJRo+;#o}T?nWPN8JZI$`_oJqtx$^O>mH74ujO8Y41&lsGQ z_efGFkG<0+>%2Gj)Aa1Ar)Is`^8nTThNx23x#JRD=6pFNZq=l!%D?UVFC)XwrNAMJa)Y8+C$a&;Z;t7|fUmILlh`gumjH)U7TR+{I?U;Ov7 z3fd|UUcQekzT#ZX-@5A!N1OE6(sbd!G<+nQOm_<6rESO_f)5DkrbIgJ{X2Be@V2)WZ$1Ip*7R)gl zSjTM0qhl8Af2(5_%rOi0&(bjq=9mS0*>uc;Hw-G&F$?y(XkP_moT9IS*;m2rt6=t3 zF#9T)eHF~U3T9sgv#)~LS3|n?)sSEND%h8!eHHA>*S-q&&(*#P_VQ?71$#NQuY%E6 zG5>%u1~LDDIsXLK`3KDT2h8~g%=rh*`3KDT2h8~g%=rh*`3KDTC$P>xA&<^KV9q~a z&OczzKVZ&3V9q~aFSE`+V6V#`<{#+J`Sw55$^UilCOdZ-*7q{%@SiruVTV93KX3nk zY!aknelzcGn@8t%yze--gE_Z@Iky8jx8r@mxgF`8+mX(>9n85Mc{sO+^u2D6{kcv; z{ruzJWvE-eufcd<8{Pl#9{=+^iTwY!%$atcG`8G7&Mrki$GiT|_Bqno)@*nCz5ruv z;(cn;|8X`0bf+x@rY!`fEd-`51g0&7`k^g^blO5-+CpI3LdZ{BD5UQdyS@IWbBl|% z%}(7nW>l-%N4#EK_n0}#`+ieYe9A=$@5n4Ho_2e}r?h>gc+kj%Z>#@Oam9xdetXlj z;^hw|y!^eVi}wq8K3qDbctf8gz2(W1iko#z__CiT6n}Me!VS)Tq`39gM22C_9xmQ7 zJK>Lu#}yaeop9X>IJZKj%+Y8Kg z1haj?YDyrzXG$rf!Pni?4MxvTd=R&EY`VC&thBn{8?-xUrrX=&X=FX zHucZVVq1H8ve*Z_oLTG}Uj8ih8Lw9s`;yl;i+#-3Ll*mK{k#x$jmVaT{t$OBgZUs=U7IaaEzm_IQCJ8oD)#D zoGVz*taJ8l<_~S8<$zf}n9l`M9x&wuQ+_b@0#jcw>jBLA0kht~tWPlOnasY;cHwW) zUSPH(nC%N@yMx&u!0abr_8&0&6`1`E%zg-F{{*w&f-zSVRCFp28FMx2-=r%e-QPDI zBRzlEvNTT`{3KXRx-!yHPPN9brOP+0>ET($NN4%rP`><`!?R+flkr@#N!Q*|)*$^I(nzFvkd(V+YJJ1?E@-a}0w2 zX>%#Y0`$VTHk^KcVQk`E7UlsvPX91Ana8)0+8$v(QJVzp+emE{ux}%^VZgqP)V2Zp zHd31h%)STqZKO65*te0|PGH|gYEyxI8>y`Y_HCp#7}(FNYMX)o549z9E`t1QqriV? z3)Vl{>;Jt6_u6~VzVH6hDKSg7em9ZFMOuSs}jr_xmC(FxDLsx(zpnDF!0m!`IVned^#N>lT9B>YtW(p1C! zKGbqHj4Mr@b8N!byj+@k`mBU2EhtU3ygK3D%SuxtuTS`gHKnO`*Ct&3`_j~-of5v{ zm(tY6RKhn^TA!-iAmOhLT%S5%SMuC$2d__EusGp&4qKnP`pJY-ZP%xU{QADilV5v7 zng<-bA+=(5lK$rY8&Wm~TAp_8)~DsHaL$Ib zUe~wVkkGf2dS(W4fOlvj4_(|EX4eW4d3>t+_GX-)bDR zG2IV$`#kKQL)UCb9ePw!|6L|*Oyv!DSL=V~eH&A4&QJL80UJ}>8wI{)V`}bx3Aeg* zW2*PAcQpSYZT4`+Nqh2S)ZO#jC#&u$bI0xt>1RE?bwld3!lcZDHf~6b{V8F{Huj99 ztxsOHAyskI9-i_=!jBzVmg?UeMaaX>-a_H@8UmCn-xEx^Kdpipx?BmL@v(_vu}pOnBz(vebk=3D25Y zmU`sugkPUlmfBh`;X%iH*-m&{>wN0?vecs;-c9Q-8-^x)#iUKC__Bn*d3aN5pA!?FGI~=gvueUybNzF-y`kl_=({O3dUeA0 zepHrvrs*CY{FT!@5BdJ^+SY{EO!s}@5YhC-lgd(US||MGgJr3E`zE|^L0M|ms|l|j zQkME)N5VtzDNFT>i}kk$4lGL@oR=`tUtEwd@^`86y5>PS=UkL9%71Q5!g%i5`3Xaw zQCkv*oP7@7qt~NHB{D(- zUczXXN4}k-<)FPPc2Tn^E{il7cgwd~V zsgyAK+fzRmYB}hKSO1hS`scIdk~|n|V+s?-7;O6aYl)7&KX0o#OBwzA!FCCw|6eyI zVT_B%mL`nx(z#AjKE{!B3(xZ7YteHFW8A&DF=33yrAH;t#W=kq=!NlndR~%_aedI# zgfZR^bO~b~82@&{m>+JPpD^Z=(@I}S^!4-1n7IjK{u%Y}gfTCD&@ExiSNoijFy^ru zG>3H9rx+buH58kvZVZ0w_?f0tc zj`t?{aQ{AK9=vDyTfBc+Cf?Vl#xLn_@g85WU&465zxMfynvVDWyU!#Hdtkxc3Byk4 z(IH{j52rLs7`9@c2TSM5{A80uOwmEQFZoDo(ucx%hM8u-SvLAgkeKIvwzY?ur0~3)6TyzNr(M* z=;(xD*Io5a!m#%y>_`}PV1AvX9bq5V$xIk_7ogUa+63FYId81MF?q5A1N(8|-t|C+v3CGwgZRKkR(A3+#Wk z7uE%AN30jvzF0@F-Lbx4f55tf{RHa~_8+WM*srjDVSmHAhW!xh9rn-G154B6>z21m z(qrV1B_-+pJbi6Rx}Q(qQIhWe1yxGZ<6`C!dw9$VrRh9l&hXC)2W&i&eHVwg=`$x4-G0!k9RQVfu`q{r00#?R7rY18FFe#dY*aUn3DATQ}2k9 z^t|+BwUYFFHKsyIdLFy@$93uX?W%9rrRTl=U#?5fhljtrE(cY^@+s@m^K<*B)}`m|L!Moip3iH(xGp`B2*dj3D>Yz+8%ykee$kEo|Y36#&278N*HCXteNm_N3Ki1qifb& zmwtEOS7}}Pou2*E+Vs1A@#eK@8=(K1wQ1Yng)i5pZHC#Ou1(t#t3FzrwlNNUcWv7C z`2CHwX`5uioV96NWuMt=(>Ba!o@v`ukhN)>r{}!2XFC94)3(!R%l&hM zO?ChJwJF+K=RV;3Pp})ov?ovY{eiaGx|zP+gUz;M?z*%sx6g;`(l*|_&(@`FzmgT} z(l%l1)$7u>qFb{rZ9^iRwk7h@=0rKPMNvL&R6LiqE99X~3pr`)LND6J(3dtd>VdX2 z>W4Nq>W#KH>XSA(>Y27W>Yp||+J&|~+KVy&_KtJJH1O10< z5cDgqP0-)CW6E!@$B)wLW_9f{x)bQ+*^xEoX zKVG=zy0Sw_dM(!d{F3w9yOijFLTTx@INmwccY#mZaB!Q>vDv*M=i@txK;N z=a;QZuO&bJVqJQTi8+L8Qp_z}t76XK8WwXA*S46WxaP&&#kDZzG_H{`*KzHPIgo2= z%#B=YW6tCn9CInx=9pu-X2;yiwLIozuJJKfbM22goO=S8+qqYOIiGt7co%SQ0q-*I zjo>}PJrle;xEBHD9tHAn?*i{2?rGrN#Jvu@vsfnHW!!JUJC6G;c=vI?1@A=ex8Pk# z#ygaG@NVUA@y=zLy;p2ZkL6#NY)mySm#i7TbQ@E@Gkd3KhzewiWvUfJ5y8fK3eKz*kkcux!xNeONsn@n7_AP9xuRc!rxeM2)(^qaO zP3K?nh~NJV<#ar+G+q94l}gjk-T7fjTApv8DoM+^aAZkZ{!4O8(t07i+`h^B6#1Lo zldQ*4&PgkiH9pF};)rBF0ngoie6kk-dEPxR*;j#_n`a~p`THD_>~TS__AL{JzD!3w zFhA;t<)GeJKI)UtMLkm<)Ia4!yFmWK^V<}24;gIx8`H7R%ygRv%sxp*pJX2NNih2) zn0*q=J_%-@1hY>nhdv2rp9Hf{g4rjPL!Sh*PlEqXA5)ay>H_{x^M+05+=cvPwCUcQ z$E<8%J`2n_6U;di%sCUxITOq|6Kv;9&f7>QL$AM@!;zo$0A_x$o%8wLK{^@b@6C4* zo<&{2d={ARJ22mOV7~9beBXijz60}p2c|AyYa1{fIx^kn0n>f}(|!QcegM;c0MmW| z(|!QcegM;c0MmW|R|)n5nDzsh_5+yq1DN&$nDztspJWSB7poWeKiPgZo%Sd4lhM|D z(-yU|f%z;j?OrhLUNG%mFzsG2?Ow38due+koeaJH$___<)&rRN!Pai)+5zcgl)pFE z5qK7L0rOd4u35lbvw*o~0dvg)=9&e}H4B)!fbIH@>ClnsHV>Fu?A#*tO3DX1A@5*1al1t<{A*pH6Zw(w4S9dRxdEx?!Q{U+jR6R z_&boFjJDpJ`w3PyFrNkH-UXO@7hvvPfVp=8=H3O^?pVD3ACx$gv~E?~Pa$8_k(bejjv zy*n`X?!er;Qx1D~VD8<4xpxQV-W`~GcVO<_fw^}_#@-$CVDAphy*n`X?!b5!{bw{x#--%r+hNBz$DZPez`-x!-GL1M^v6?k$74w+!aq zGMIbIVD2r0?cOqMc=+{@PKI88wbzaOtOqdjgYDip_vevLM)`YluO82$E?_01HQx1t<;D`5Io z!1S$v>01HQw*tmq1bi!C>_5PlN``NRdFXqkF3^kegDJoA|7N}+=m`0(F5v&<|FY@y z!682xI_^z>oRtmCXMySa1Jm~hrtc3--yfL1Kd|-v(f^2aGW7Z@UnKIg9>B~Gw!TaH zPmxYW`Fqosif2(5FrNjc-xf^2Etq~=F#Wb*`fb7V+k&YJ*!sAc4jq|p^ML6G2h$G@ zrXL(kKRB3va4`MgVEVzq^n-)x2M5y+4yGR*Og}i7esD1T;9&Z}!T%(mK6SBrf&Wts zgH2}~1@e>8)_XIi!pa8bv%rks05g6A%=is3<2S&J-vHbA4aSfloeaJHDxL)SSr1_5 z2iy1)#=sz*jPmzpJPe*iUBG-6n6Wot#@>J#djn?d4VbYvV8-5nsSDV~CNUj4GTr6@ zGk%H8cP`_Xkk0reFyoiNj9&sXehJL@CFKym1ZMmanDI+s#xE&{_$4som%#t0$6rx? zs|)x)#hBT2#%fe!12eu3%=kL6jjv;jAJWOt>#ySd zke~GcW`3}Z4`hrY(#a?vanXA#UJ=itE?_UZ)CFwg zNSO{DnQrrd5j%}oQ!ryq!HhKpGu9N$SW_@#O~HueMyx5Av8G_gnt~Z?3TCV+n6ai{ z#+rf|YYJwpDfpihH%nctUf}-}Cv4LhtBm|)wDsPMTeh-+`7AJFq`{1l1~Wz)%ou4f zW2C`0Mw)TjNGC(DzlzyLe%1q+`N1~E8}aklJ4HGffcY#iyrb3xIiE0L=3O zV4fFXI?f9)Kh6t)d0qg_^8#Qz7v}}QJTCy|c>yqVVXPYUf{xS$OkKd#1x#JQ)CEjk zz|;jyU6}s=_t^*PV)X)}?HJF-JdnYrqhBE=4f)B)vp3J4SlPgQ7MSN;z&z&y<~bKI z&$)nk&IN4GxnL|Kjt=Q$==E3UZjhh#0A_x$J*UI7LP#g0{JnW@2+yJ}U_J}XGfH5d zQ3CUf5}0R{z&xV_<{2e0bphM+Tug_KOt*Q!c+cX@7no=9w=r&wPP-<_pX- zUtpg30`trlm}kDgJo5$SnJ+NUe1Uo93(PZL;D6HjHR@vZ0>hSLY$Wrb9c?=7OvE=L zKN)%U=J`P@8<@`m^QII{ngn?!8~UQ<~dU^&zXXG&J;{t!1f$2)1f2NZ5}Ys z>VkPzS2>*31@o*fm}hmtJgci5&gz1BRu{~(x?rBw1@o*f7<&$kE#z5Uq=OM3%RG#m zr7qBm@`EYA^8aRMjiDptx4M9_SMy(;r?%akQU2aMn~!Hv7cid% z<~;yl-U9&UJpf?d0|4ed0ASt&0H!WrduIaEp(E369x(4!0P|i2Fz;0W^Iioo?^OU} zKOgrhfO)S182kUYR{_j>6~Me#0nB?9z`R!h%zG8UyjKCtdlkU{q&p(0i`5GZ-_3t@ zCx%UjUy0*|jJDpJcXU|Uz%}8gQ518>qV8$1L8D9iud=Z%OMPSAkff-+fXR&-R%LlW3Fv|zCd@#!gvwSei z$Fo>(NGBtmZ3kw3f?1zn)+dEFaH8 zJO<7LA)SnL#;$`IR}W@fJ(zLzV8+#h8CMTxTs@d^^>`M`2eW)I%LlW3Fv|zCd@#!g zvwS>@@$E<_Bc1W*V8*?J8TSrm+&h?Y?_kEggBkY@X52fT#qz-{AI$Q>EFaAB!7Lxl z^1&=0&q6=P`8%YOk&bbP{R%MSpTUfO1~dK{%=l+8 zEFaAB!7Lxl^1&=0&te=h(#c3?oG_U2$zaAOgBhO;W_&W3@yTGuCxaQEjAyZYFv|zC zd@#!gvwSei2eW)I%g3`A6N_{*(isa%d2mk%m~pCL#;JlCrwV4ADwuJqV8*H9SuCIO zpnNdP2eW)I%LlW3Fv|zCd_0S>e@G`IoiT4<#^Zq*j|XNv9+>fXV8-Kt8IK2MJRY9K z^1&=0%<{o3AI$Q>EFaAB!7LxoVq6^3$w+718kq5NV8+XV87~KByd0SEa$v^Gff+A{ zXR&-R%LlW3Fv|zCd@#!gvwSei$FuMr!JP(3CnFv2GTfyAW;_*`@l;^OQ-K*z1!g=I znDJC#yr*!N0-nY4!7Lxl^1&=0%<{o3AI$Q>EFaHeTocmCNN3y;nDI_v#yf!-?*wMN z6PWQ%V8%Ov8SjK=v3xMg2eW)I%LlW3Fv|zCd@#$$v#@T$JsU_TBb~7&V8*?G8TSHa z+zXg-FJQ*KfEo7!X50&&#qz-{AI$Q>EFaAB!7Lxl^1&=0&tm)u(#c3?d zfEkwpW?TxGaVcQNrGOcif@iUOFv|zCd@#!gvwSei2eW)I%g3{@uZ8=0kWNNAV*|j9 zTL3d|0nE4sFyj`$j9UORZUM}=1w4!8gIPY9<%3y1nB{|6KA7c$Sw5b{_yMGokxu_U zm~jPQ#ub1WR{&;Q0hnEFaAB!7LxoqMsM( zWTev%3#R`UO#d&K{$DWtzhL@*!Sw%v>Ho#ESU#BLgIPY9<%3y1nB{|6KA7d>S@by~ zos4w)+9(h1$^g?32&NwpOg|u)en2q&fMEIo@hp~4c~Cx><%3y1nB{|6KA7c$Sw5ac ze;m@uNT8AtJPlso*d@#!gvwSei2eW)I%LlW3Fw4iY z=o>;h8R_(ifa$LR(_aIozXnWy4VeBKF#R=P`fKnkmJeq6V3rSN`Cyh0X8B;24`%sz z7X2njCnKGH4KV#FVER+Q^rwL7PXW`P0;WF&On(ZV#qz-{AI$Q>EFaAB!7Lxl^1&=0 z&*I)b(#a}Y*yjgxza7l|b};wb!Q5{LbH5$T{dO?-+f}wuKA7c$Sw5KMgIPY9<%3y1 znC0VH-1kO08R^`Y26I0g%>8gM_rt;54+nEU9L)W2F!#gpES3*u`Cyh0X8B;24`%sb zmJeq6coz3ykxoWB_a4FA7X@=)6wG~5F!x2l+!qCNUlh!JQ9O&~gIPY9<%3y1nB{|6 zKA7c$Sw5b{J1D^1k3t@%gKfIqALIQY_^oB;`Exq&6+t@hx?vvp{=mFf1k8Iyz`R!k z%zH(^yjMgy+$#d+y&_=VD+1=dBFf=j5isu+0bAXv7wUoXlW{K!7H?-NVCn*OW0;Vot>H?-NVCn*b1IWX4uuZr23FC$E zTg%Mz=k%XK91+qPM+9aZ5twmAV8#)F8Ak+W91)mtL}11dff+{xW*iZiaYSIo5rG*; z1ZEr&*wzDeM4eC5RKj4sjP?#*Kg(Hv(qdh;oP<0W)p{%(xLS z<3_-Y8v!$J1kAV*GU7&<2XPnBoqB;OKbZ0>2l>I2A58hdlwUc>52pNJ$`7XeV9F1s z{9wvYhWyL}`JoHuDBNcY#yreDE2bmAO~>5MJeVK&Tg%LYGHp7~2_l{61i?Hf2ow=-&$s#Kc}M~;>i-AG+Wjgu8RWc+YaLjOoa4)A8=c9T7;!{EvGu@LS8w^XGJ)1425_0fBiA2+VUp zV4ed4^BfSE=YYUG2L$FhATZAXfq4!H%yU3so&y5&91s}qV%#|ow)H?Ap*wW}Qx`CG z0aF(+bpcZsFm(Y_7cg}JQx`CG0aF(+bpcZsFm(Y_7wE+}e=zsikca7Dn-0c#7UsdZ z50*n_oj4ZMp*wW}Qx`CG0aF(+bpcZsFm(Y_7p6lO=7%m|>H?-NVCn*%^fggBoFw)H?AQ76;|OkKd#1x#JQ)CEjkz|;jyUBJ`@OkKd#1x#JQ z)CEjkz|;jyU7#2C3ivLjUl@6q4z}smPmOgwZ2-&6gYs=U??pj6??q7#_o9G#uM3#> zx`27Fi*mTv1H?-NVCn*OW0;Vot>H?-NVCn*< zF3^j2_kkIAggi_K+jKC_`Y{jAHnJQt^ZYrT_cS7%_cVfePa~N3G=h0gBbfIzf_YCP znD;a?9rrXcKkjJ+^PWa9?`Z_{o<=b5X$140MzF01Fm#0O)CEjkz|;jyUBJ`@OkKd# z1x#I-4qccZx`3$*n7V+e3z)iqsSB98KrimkgSkHs=KegG`}5%c!QOj-c~zVZ`z9)} z_pT9J)L5}ZWp_C?EKy>Mu_l(-5;ZZFgv1gB)L0?Lf(21f0UL^ivb%y}0qn-8V2Qgd zyKG_CZmjV?_ss7;jC}IOyl>*)@BQL+?d5$9&zWb={LYy(^OPCw^RV`LSo=Jj+vl~- zQqFpoa}r_JhO)Lw%C%L(+A3jfm9Vx-SX(8mtrFH&32Uo_wN=8}Dq(Gvu(nEATP3Wm z63%VN`fDiHUjyr}f%VtG`fFhQHE`~)$$d}eh9F~Z2yFfctS=1K7Y6GKgY|{M`ods+ zVQ}sX)6PaYYfo)BtosIpa}p`n1_f(_iu^URq2)F}{h_o|e<-X!6xJUK>kozXhr+o( zH23YAyN8Uqd$7J{SYI=&uNl_Y4C`x#^)o z?ZdG4VOaYxtbG{PJ`8IghP4mF+J|B7!?5;YSo<)neHhN|_QoDiZtMYU>;Y`-0c`96 zZ0rG?#~$Qy6y{$eWBxU4TnB9aIBZ-8Y+MIyTnB7i2W(sioX2&zMy5PpXSrsi+%+TY znh|!*2)ky4T{FV28DZCquxm!k|JCc?d@XOB54w!=fsONljq`zx^MQ@?f%7<@JZ8x~ zG>~x*4cHhe*cd9<7%JEpD%cn**cd9<7%DiAq0+8Jd2Sog&O^C&9#}gMtepqe&I4=b zfwl9%+Ie8@Jg{~iSUV4_od?#=18e7jwe!H*dEngsW=tLB#?-;a)WOEo!N%0V#?--i zOkExy=srluxDOI+ydrG8B5b@OY`h|DydrG8B5b@OoX0C_bEZ7EXKIh7Tzjnib+sqw z_HbiXX|pk_uraH!F{`jKtFSSva2~Uo$KSe79Ww4y2OAFz8xIT{4-6X*3>yy&8xIT{ z4-Dt=!1{(L&;1MfN+{P?0_!V*^_9T-N??5@u)Y#lUkR+Q1lCsq>nnlvmB9K+V0|U9 zz7kkp37q?|j1Q;W_;A?xaM<{8*!XbR_;5In56@%W-D?yX_Zo$by@!pxhmF05jlGAB zy@!pxhmF05^VoasLX>MWfwh^y+Du?=CXv5pHlN&P)xUC1BJDK)0yh5wHva-P{{lAu z0?zX<@>~-4f=0%@pkZ@cU~^kwb6a3@TVQirU~^kwb6em%w?+Fc<+%+IyMewQ?U~4E z&xEyS!rC)o?U}IlOjvs+tUVLfo(XHugtceF+B0G8nXvXuSbHX%+nLS%q}<$3*xXOp z+)votPuSc~IM4kwrRTvym!SJ+%v z*j!iGTvs^Hb#!t>ngv}#{%_D}*BZkc*hRq{}%_D}*BZe9OIWrM9))eNu zrk#ZEo%R#sFp+_Y!-SFfI>nLZaj@o+(@t~AVROl0bIDXHN`y z?E6l+?>n5o?>Q?^oyx<`yS$dOJgl?pwZzWBD9`6$InQs-=69cKW%T}|IRo;_z|Je+ zd|shFgz}uVjZm&_1kP|<*8G7Sbr1O%9Q`3ZvpbkzgT(P-`#OfgYdo~p7J)Q1l`E?qKiQjr4%D>XPp*XbH?x4i&dMSkNnifO~qm}UW~lnreO~A%^8uWo!n9!zt78&Kb$nX*la@L zTbFDr`t?lw{66i)wl7SNGLz2kC>9x<>iOYibBgc%G1Y&-S)E0<>CZ%&yKB0N)h|x% z89uG6xbX4EVtH5hH;TsEha&siu}9GScu0_6uy;C7?TD#e#pF%ziF)JnqiO zLw?&?^jrDX$h%)Or|5CmEs=ZtrlV*+Xn5ptz1xemy5AUigU?!v9+QVg=39AJpTswW z^QkRgdbQ?KesF73SM%y=(?SFjjhWM;md2-eoi;-bbSXqpM+gY!mcG@*OIVnN!Ya{>{=3bEeSin zg`Ka$&R1dA)Ua!6*fllmni_UZ4ZEg>T~ouZsbOsnur>$Scr93)1FX#f*5&|fbAYuu zz}g&OZ4R(D2Uwc}tjz(|<^XGRfVDZm+D~BZDzIw}SQ`$k4F}eS18c*9wc)_paA0jX zuxlUKwG8Z92G*7ZYs-SQWx?9AU~O5jwk%j%7OX7`*477W>w~rR!P@#@ZGEt|K3H2H ztgR2$)@S*@>ug-=*PaQxZi2O)!rD$@ZKtrdQ&`(6tnC!mb_%=Bf?a39uCrim$gnnK zSQ|2|4H?#k3~NJ%wIRdWkYR1?@B%N-DqanF1hD6U!kz~j`D=8ZDecjB0J|=R^;5w5 zDPa8+uzm_yKLxCx0@hCfyJm-7cf+pJVf{6*{u)?+4XnQg)?WkbuYvW~!1`-oeORzQ zELa~_9woZ;&B3m7Vf}!xen411Agmt{)(;5l2ZZ$l!mhhv z*U_-+Xjp$JtUnai9}4Rah4qKR`a@y;p|Ji?Sbs6BzZlkE4C^n3^%ukXi(&o6u>NA0 z`SwZsq;o&@7gMgk7}j45>o11&7sL9CVg1FhzHeBcIIIl>*8dLce~0zI!}{N0{qL~; zcUb>BtW5^i#sX_&fsI3ejYEKqLx7D#fQ>_djYEKqLx7D#fQ`+7jm?n1?q|T!PGe4B zZDO$TEwJ$|u<=U@pZ8Ab+GYu zu<>=U@pZ8Ab+GYuuNLg@ z))opI&j}mP2^-G|8_x+F&j}mP2^-G|Ynz3&wZht3VdGk1<62?kT4Cc_VdGk1<62?k zT4Cc_VdH*bp6CBt&&r|w#x}#+$zkKDVdJP_^={$`#iwz^APzfI^P6c z<_^I61z__OVDl7U^Auq76kzidVDl7U^AuqH6tI2=Sib{oz6NZ*25i0tY`z9;z6NZ* z25i0tY`z9;J_~F<3v50MY(5KYJ_~F<3v50MY(5LjeDbR}p8{Rx?7;eHVDp1u^MhdX zgJAQ6VDp1u^MhdXgJAtQuzs8!m*2m(^`@@k&)vuOf{(hft9WDDxX9NH=_jpc9g=j$5F-{`GBHkQBLp654~zv%*7H4C&N&x03vBFgZbpWgSW$UOgBk9#IE@5Q+fJr|kxW#^9)^B#R~ z%Rk3*-me3Ho|yOUg?0WC%XuG%T>C;~-qUNId@(Zb@4+33d9T-8^rcwN``-MW#Eb*= z?$~hN0I|1Yfn7uNp^>;HxI|HArzVg0|b{@*B5@&Ce(pO)jVR~~;otiL|WRQ&a@{(4w{ zJ*>YT)?W{EU-;``{q?Z^dRTuwtiK-CUk~fAhxOM-nTo$2_V*&@Bxip+%KhzNe>+&; zJ?w7>``f|(cCf!4>~9DA+rj>Ju)iJbZwLF^!Txrzzg?86{C2Rvo#p&?%JbX7{&rEO z^4r1wcCf!4>~9DA+rj>Ju)iJbZwLF^!Txrzza8vv2m9ManaXbm`+Hsd)KWFhEn(-D zuyae;xh3p7EAt(JeaDq&On@B|V8;a5F$8vOfgN*T$0*n_3U-Ww9n)aPI@mD~cFcqw zGhxR}*fAD%?1deZVaIUTF&uUbhaK}_zXh=02-t55>^BAWn*#d{g8eqZezRb|aj@Sw z*l!%{Hxc$*3HuF&{pP}cb78-^u-|CdZ#V2W9d-@?I|qQB1HjH1VCNFBa}3xy3GAE% zc1{A19Nkb{fAXaGj5(j7{MDON98o?-Id&0~13NCkj!RMIKi`ztKaNZEiQ^LNxCA>c z!H!F?;}Yz+1UoLlj!RMI3%)7&?+810^>@GMiV5*|=Q&|rOu1_u*fkF98V7bw1iMy( zT|>dHxnS2^uxl>ZH5%;N4R%cjy9R_^1H!HWVb_eXYf0EOChVFNc1;SqCWT$Y!me#$ z*SxT6WY{$_>>3$%O%1!&hFychuGwMN?67Ng*fl=v+8@>?0Bb{lwIRUT5MXT%u(k+T z8wIRQ1Jp{jkkx`d2=e0Eycg#v-;IXeY6xDAh{?VTsiftBq zFkL&fp*Viy#AiL!Q1sY8@xc0q;++18_YUvTqW4wgv-P0kFzZKk!Rmt51;1X=1*;2I z7d)>n-(SkVy68W zZ9^BVE?8Z#y5L;bWuG+^Q#Vh#a(=#hW3lPpsr-zhvDmVI;%SF87S~Tny!2^}#l&yd zM!k1m7-D7nCtg3Smw)q4;%=iFiIy%#ut=4r##zn}Yj4*J8~=hNpL`J8>Hyf*f8knvjj@URyr#Xga3!-r$jvrXIH z9gvtdUsNRKUVhd(G4=!Zc*}sq-22_jC8ke$U!CTw^wmKtC!Y6x^xfp%(Mvnk3#%7a zFRWfzy|8-WT(9>?dCtCT+`EiS{yZbkv!@KtJZw4g`TOfUigM>s@IO26%H;=#KHR3) z-LZdi?)gMxG2{GHep^#xQQMGs{|_3A(Yq&G^w>pa7F*OOK5>Pa#c#K}C)Tsc>NAUe zwTYivV`j0z_V>o}-m3;1(Zh*H1>4c@cD^s(Z_dil4_*sfC#){mHo&$Gw#~5j0-qA} zz8LK4@SRJ~EOy*0aobWei_r%p{!ZXE4o|lCoV}Jl_gXl=cEL3pi#5+08}C;}*Mi$O z77txKHtOB%h+t1UFY(xO8jIqD#LwRl#)_K6kJL97(>}gG%D?bpV{yT)iI44UELPh+ zaocB&#j7(?o4b|_{eNU?bI$6eo$7_v3#%7aFRWfzy>PDAd!#()w zLmG?gmi_$mM*mn2`y9ggysmG*#$uzT?uvbKz}bz()a?^56#8(8_iRJ4#lwj|nil2>U5TA1qbp~1QLZj{xr#1WU9h@fb-}r= z{Q1v0f5sLF@5^0Bq-SsWz%Ak3;eM5Ym4R~^-+lDvoWE=5hIe*}iZAS{z&rO&^(#Z2 z%D~D{XWl=qDJXYM0XwhYTIFHoVdddm{*_gl!hWiw;`^TS`I|HqgL@=j+cVW6PijQs z19ojHPFe4^B)?}<@w1VMtNR4o_$J9u_v_t)U+J#IxAbZ%`fqkelwWl7rs9!X5`VOM zQ*qvMcgB9sSsB{twXk)<>VjXXv;nqlux*CD7x?m^_tX`V-gQ=MD)wGI@tDvLo34|1 z$CaCkrM{c|k2!lSeeSjJ=dS(M%;M$OD%VyRy$gP4X7S)EqvQSF(|cxd#tw-uIA&(C z(*B9-&ky{=#AlD3S@iFfxZ9MOMZ@xm2h9rKtd~+dkNj+A(Ro4Q87nmvA8wTN=B!@Y zsa{yUuzF$j!s><93+H-w{DS*MX4!Wei?!}fZIdbQy;xK6PQTATZ}gAlu+Jf!uV+vE zR#P$l=ObeuZvKs?;#XHDKL691#kG$nzVVZp#dCj4eBs|`7FT?CRFwbjf=$J-2PIb5 zyzNmJt#ABWbzN$YZKJ($mV%X5c zJCAQHj=w+gm7{~->V?GG2hf$Xx+qr{tS(qxu)1J%!MU#d`Oi6j#y$zp-T{?oZ_V)T z+!Nj%?pGOD890~m-A8ZE`MWkYytB_NpPudMfj0_FJ<7n!z{*f(-apz>DA$$(``zSP z6d@+S1KMzq?W_LC)P*Z7$y3EX5lf7xq6Nbx-2+*Jv(I*!Gq<9u8QkxmcvO z!izT-2W(r3Rrq*TvDY1m$IqTstiDo;ZFu6DS;c0jB);mtATu#N=Q%4wJG~a3R;d#n zP|+2+(gxVJ!L}LpUf{)p-peK>y{q0ct61!j#2el{t2l3J;_XJyDi(SwwKHe0rO&+< z&ad6*hNj}lZ>DQy^sX|tsd(k5ss6stHWe4#n|MTLQ_=W#;y0F8zr4 z+r$sCIWav{SvXdSUg#>V?${s~67o zdXJRnyu@Wq#pMr-h|jr<%&XsOE#?|2$q&zJD!QGM_-7}FXXB*AO-DBsw;!MQ=!2Sy+FvEUB+O67_e-o@6kR#1 zi*j|r>Vnk;s|!{aoa@S;|D5w@?3M8Byy# zt{>i6WR445TNyW$p-yFBWsuMNM;kKb+K^$tn_R0rtURndoXbx*aCY(O;1o}l^VL6^ zU7Wv0ip4rK?47di(8QbXG`kqHYI^>Evc>FT>q`>vv&QUV_S=asTyS==*Pdy-9X7kA z*yZxXyH0Bx9(>+XmRS!L}LpUf?T6wG_`*^d3H< zrTB4YYQsi1w-oJNiQgO6Qk?l_YG=+~OP_l!oL_tKec?=pNvW@7^fo-yT

_y}y&6 zZ!R{vHSxo3&BgUgB)x|&*ivkBWa2s9TZ)dG6F*#py^>x`yk5v*zwn*Jz0YYWF8w6& zfuYUql{V+BUfQW%SiP`%Vf99tie6Z~aIV*Tq&(*>?rbi0Jt2)Vnk;s|!{aoa^%5;`lS@4)_0SYkc3~lOAY|?>p_uSsBW`7GAJYC#){mHbj|9 z+hE%adoS>F^{sJigoo6IHdMyUyPfM%QMG zw#M%fd_vfxjPDVA^%|}5dj$V{)7JPsf`7A9Yy2L;y$)@S-y`@teOu%A2tMb^*7!Yw zFTcMvevfER&g!LHy|8*=^}_0f)eEZ^&h>hal;`~8&<~80v`t3l$}w$mT!nq!kg*)j z%X7c&3v=4aF=YFOwsLIw^!c`O%(;DP;L2F^^2D}sjOsS7tsJ}5HE(;=MY+0Qb;0U_ z)di~y&UJb3+}B#&TFWu~JKt(?1 zt~cSePVR{7P57mKJK}m1-e!xAxZZ@jEz=R#oA8Qnw8!-(y!kWjalHwz7WS}Wy-9m= zR)%t~g{>1-7i=3~+XmZa*n5Eo-rXM8=J3$b?d6*N&O6%6wS3)e?QxAyJ9GA0%DooO zul;nd_R=0Aqif_Y?a>|rAF*S5w1>bu?9?9ZA@I(-w?}(O-{z20M#&+fhbfcCgfr)@Ga zbx(D~bv^9!hK%KKUY^IRR4+HDT*Lmf+njQ3+w@^ax#m5rGd#DIweYEp9pxIi_Qj5J z?X0eO+oLYZ)di~yRu`-;SY2?g%X{a(7CWT9v>_ZBSlhy!1KUfR!?gWEK2F6JQMG4# zX`{FyJTuxZjQ>Gb&g!CEU9h@fb;0U_)dlCe^5;M2{24nuJbSFEx%Se)thKpcWng9C zT*h~wYje)uwFkmGi%kHTj=F>z-;hvq*-$DH=tQKPUgTDhVKAaQ%9q?k)0|$QxyxX`r(cb|-ICxI+#iPU$ncrT3iD zm$cQ+bE1!lcINE0lzT0lU)! z&t=6yA@`)>i#ex%XX&HaXm;OpUjm4TIka~a=#uFW}r*G7eR7M~O{PXxwSMLo*E%D~DX zpZAY3qLdpW3j5vUTIFHoVdddm{^1?E%6OZcAL-r|<87$_>c5BFs1R=hFZ0*V7;gi= zGqE$q+rZxp`=%0a1Hbi$&KPe4A9-?TjJJVbJFGLt+rZQJ>5TCM=#24T@F9DI{t5A5@U=UK{YyhU82sUmoiQE^ z?!QZCj0c0)3~eSJjP~TLUdq)As~1);tX^2XuzKNKulGoK&Z9#<9dSyuO-AOv1G-{d z6YTSbjOB1%p6A^>c|}(l!*klet}?dgmGipFn4e#s(N)F*-FH$~86&jgQC(&1kh+1G8Sjm*oYh6Sx?pv|>Vnk;t1HT6y7K2g=lmJ#5uQC_inw;Cz{DDHzskVMz`2a? zKG)`)zian~cb1qaWF8AltQ7Sq11ke7gM8jU#>P`_Y&`6DlWUcSm4}swbNOu!?<(VU zbAG4jD&uDNT&pX_>!Rz^1-oLrEF0u@5GbC^a=6gFnvWlIZS)ZgUFeC zH;!Gsv{}8ddSUg#>V?${=X$+I%5&c7*IkA2%rY`C`3}kxD^B|@hpET%JSVa5&0S@V zL(kz|W$wfGukR{zB4%INRpv^Zd`TEfD>)QL^y?~fE7Ub_d(=g_x?pv|>Vnk;s|%i2 zm;FGwIS$C1`#?SBL{PuE66iIDg7%nOVZJB2a?bl%UA7Hfu)1J%!Rmr@UGqNw`FoK+ zZ{*9w`onW*9*xhT&!;&xl;<+W>QkO`{;rWPWBumQAfLa>=G0JbK2F|0=EhQwxv{X{ zP1>nEtURndoXaz3cysF1*tVRRx9oLxDrequ;&&1=Z~5&5Q=&ZcmiNA&n0d?Sryh&t z%v(n6nV5OY0#hE1<;+{&-YGHPrqPohiSJI%%Fs@)g{>1-7i=3~+XmZa*n5HbhVB#g zj)0jrHjhipT=chhCFZ-f*vLm>n{)PB`rK>b{95Kti(EK4UMr)EIq)&3PmX$-8y|O0 zV&=@P*Cu8z-FsSM=GZ@3?BOWS-1~+fCuUB*#KgqR)%VyWwV7}C=$liUb5<|yR4=Sv zSiP`%VfDi5g>${$Bjq_W$9wRabT2Y8%#kjB_w&yi{bM=oa|kmZVE+f0IoPLvn--b* z(qWG!W*)Wb6^WT&-E~xA=3N(Uo0$37Uzbg+u6f&|F3Qyfs|!|Fl&R=~)dlCeym#8q zy!7hpD}55?##>#Ln0f4*0}?a8op4-Y=DqLjl$iPO87n8|{dK>KoYh4e)CDs)Mi;Cu zSY5EX;9OV!{O6oMW6byZ-jbd@=7Bqo`1~`;y(f5vzuRfGL~aE`{@yhv5gFS=ZV-8Qf&lwxzw+={claawjx7E3yf8OXH z%VD2G7<&}^@W9yRemNvD_PTMuN{k)vk{uFb-}}*0iLv`#{_3;wTI_)j-kDfk^R`D_ zl&cF?7pyK=U9h^~T$lGw`>~5YeSGQ@?4?boCB}~W*r|!Juby{YV(hN<`y|F5JE%uu z){pKxl(V{MgSudK!Rmt51*;3rb>+{0&iONjz45uqvxgn>v{zF*mEqo%fpZz(ee~v> zziZe_4}3d4+t^V*2~0i8z{p9%-R?Xyq+IhNzMopEqt{I*NHnfC9(Z~MXJ ziSffOd-p%b z=UhexAMqx)eg1i)e=LW64q^PE?1u*97e4y_#Q2M6T#*<*^3^9M#=m@1kr==8&Pyi7 zAN}UbFT{G(HE(;=MY+0Qb;0U_)di~y&UJb3v>(6x)Du#l;ICi%{KWY2`&^Y6|Na@* zCC2aniz^co5Ae%#6XU;d|F@jgMH|!ws|!{atS(qxaIPzV{&UWsG5p6eOn7xgDnf46KnYh7WZE3$j;szJ`Sz_V_e?2EX|HKWx{kz1(4Q{`DV&Vp8)TZ&4 zxWSpHBqnZfm0pR74V${!Ut&M!tPJh+TG%>ab-}g)wr#L&hP@Y<7`6i{dWqY7VwKbe z;yG(pPE1_cZ7ZgB=Ipifx!1z^wZtwC*fsT)j9y|;8=p+?FR`hg{5Uc3v=@Gu^b*VZ z=FN$TajiKrF|n`9^hiuh?DfkfCRX;EMH3S{*Q?UzoYhM^)eEZ^RxhmHC{xi3s~67o zdXJRnOpIm2wQ1~?xmr-sm68VV^@d-*b$(#NXaBJw7wUD}L*W#KbXP{M*FD zH~w`0#Kb)w^4-M5Ltg#iOYvHD&D$PzQLZjnU9h@fb;0U_b6wthyq6Gz+Iwp16XHeh zc_T4#q+2eX+D3fomSI0nPCfDg!Hn zeBM9qcSpJV-NAl0xmI~td02TkmnUb$_dRFwR(Rj3pS%^`cbL2t-glV172bE4ycOQ} zC=>Elc;8|2R(RiG@>Y1?VR93A-)T?I%24jLFgZAmA?l*sHbj|9+hE%adoM6K6pW29 zc|(qwL^B@jZgcnc{l{lS{?-2qwph z?-5My72hM6oGiXaFu7WMk6>~)_#V-ooYhOYdSUg#>V?${s~1);oa^--DbJZ4AI3@A zCL=?R4C5;7^M;J&a9&P62xA51*rl#{+oLYZ z)di~yRu`-;SY2?g%X_E&#6iDtURndoXeB5?0Pe2@}^mDQa^dqtT$ourde;o zy&3Y3iZ<_TcOx`r>O_ab-}g)wr#L&hP@Y< z9A4JuFnQ~)*~w>jEl*x8Ykb<7v)5AYwQzndx!c-9WOR{(k39rFF641z4}rvY;CBNKD9!@3^!c|*o>I4>t3nYAkA+;@dKY8)m5XhI;wm=@eHV5+SwMCG3uZ?1Z z@XTntAb-$3-g8zLZBQ4iE?8Z#x?pv|xvu>A&pCg_$Tw$A&9&sAv)1N*m4TIka~a=# zuFW}r*T|R0CV&ii^wxu{*Ij4 zw+DX*^|Nme{tlRZd+>L_?AwFC17_bI{2eg+_TcY;*|!IO2h6@b_&Z?sX2IVV?${s~1);tX??R>pfDQGkYB2C!%dKGVBqAUkUbkL&kDAFK0g-d?l2#FOWWz zox|Ql`c~LSNS_P)3+ant-ywZ8>_?>UMqTr^M_rVw3sx7bE?8Z#y5L-w_fGrSmq{NM z`!(s?Vjm}cUhMCrFN}Sk^pUY2l)f|eukdV(oYh4e)CH>xRu`-;SY2?gD}VlT&Yv;% zJHn^Kwd{k0uZR0p237{nWqkL!Hs}0ZW4|VRQpm866TT|yQ3h59RtEXJf85uda`$zI z{cdut^04x-@^CKCo{h%ae2&9@mBianKl?@!Zv(S$B=I&d`$iIP1G8@=@is8~MiOrW zvu`BvHZc1}5^n>uHz4sgv?pg}DEC^}I$?FewgI+nux*Cf1Jl?c_An$iiE{Ss{B0#> ziTyl{Wny1JVw`Aa&R!eurE)EtU(4Q=#)HY|Vh>W{!C>|#B_0gkKkTPUJQ&Pgro@B6 z>~Tsw7|he%wDO)gTd^bNIV$r$yvRWs~1);tX^2XuzF$j!nt1Wk@B3` zW0N=~+9o5z9+kv3!9H)uSPtjq?8oRi6zofB3=jKN8r#D@md5o zJEX38+oLYZ)di~yRu`-;SY2?g%X{a(*ca3oD)tLCwu(JVjk#ifQDd>#chndy_9HcR zi~Z9)(Vnk;s|!|Fl*x4E&wtMOGsb?K#1wHY`*0F##QiD*D+A{;zWZF8 zbN;TeUnntA$gqznu~O8d46F>S4DxyZc%B92o@WvDX5VP#sYiKOdD!nPobLttuipQh z`rQjU>I(a8|NpU1xcleZ2IF|$1Ke_B>D@Ej@_)1kzWZh)?|$8|`*p+a*A2U0H|&1h zu={nx?$-_H`*ph)H|6eu54#6G>>l{Ad*H+Ffe+8S2fp!d|L9B;uASdm7>+;4IR3zn zKd|Eu?Dzva{=oV8<5)*|KCb$%QT|nabHC_4jcxb`-(qCG%y{BA2zkGKu-`t|Zy)Tp z5BA#!`|X4M_QCnL&+(RW$6MI(7IwUa9dBXB+bENbxB2)pzjJo-@yB^S^*GOmo#(^O z^I_-ta6Zp>O+k6SesNAq`B%BN{i69WZE)QR=j&GI_LP5_dAn;p4DwI6b=_Cr|vA*}rn)_w?UKZJApVQx>G-#KErJx#wA_2{>P^;^OEtzi9DaPGI# zM@D(>kJCp(`B&+y{UZMkZO{)3=YCjyRg`}jKa{>p!>F1(+e&^QZekyOs8v_g*0}LAj3>yOs=P|&>ol0NP;w4xH!jnBzeCm&so+=LLClZD4b4U~_F?b8TRAZD4b4U~_HYJlDqj z4$95%fX(lK&F_HC?|{wkfb;y0Jl|n{=fLLq4(1h7k9mc#d4=#llf#I7o-b(*9pztT zF6|fP-_Zv1WZ^td)?7l$%_W5AmnUd$DKh4?!sfKX=Cs1*w8G}J!sfKX=Cs0jPOEv8 zl$%Ehn@0(oM+uup37ba==XsQQUg7-C9nSL#&EKaU^Y>x%_hIw*Ve|LldGq%@pE2K; zz+83Yzv?|J=FM}D_Y!j6wZG9e_oINx*;hvUA?4cfVDs_a!vT5sj)2`e0(S2R*u5iQ z_l|(wI|6p^2sqz6!u<*;cfSJoU$Hj=^~~>_Yo4Wh*Blr7#C>v*cb^>CeR5#;$${M` z2hR7&;hFcmGu}1MfJ26NlXKZ%-Vx7h`*-gR^+o&1#5ROHeb2dLY?*h@C}bD|J)3WS z``$2Sa&92!7l?1l?XRaZq2_nCEZ?RefW+>Z|C8|QgL?ng(t`_aMqesp|8J=ckE zH)mZT!?&LEr{J%055_Orw~aQqzapIPuSm|L=YKJ$@(i;1?Jvh1jPuc`$Gs3?_d{n}8IsOM zao<M^!?1e}!|pj8`JdeDn6)Hl0CBDR+`{g23%k!P z>^`@!``p6$KDVrS2lgBu>zv=&+2mI2R5=^M{ne?*{ncUjSBKqS9d>_pINx8LHNNL` zU|ZlU17xs8aGnVKRh}vEMf;G`2G0wC^Ya48Vevc{Y(AbTGr#@Pu@Q0J4fVLUKkVNA zuzUN%?(Gk|w?FLO{;+%d!};F+*rwdW-~HsH{J&uDdg__qS?$>3HaH}md*V4J$a{_n z>^UYdw!SZWW(xAyD(ypToA&uvd3Mhio%cc8u)+RUXZj$64cTXVe&>>4bM{^E3>~iZ z3?0}rbYRcWfjvVf%6y5ld$4u;4tj1&tS97;{7=t_p`JZfYblOjHa+v$W?KiQX9L^5 zV-7Zd_xJX^Fs}8yFxd0LV9yJK^Yg;+K{z(z`*2LgSK=7{Ri2UeMdxbKX3xKa^YibB zN#^W4%JE70t(@QaU-+>6wvwmt?>r+f`pzofbk9elot}>ddp;WM`DidcyZ`DeHe~)j zqp8@hDUJE~dM-L4edF*II*0LGPUJn86ZTwA7+>UtQ;5&YMuUjJ%d*GVL^RJQj{A<|rui<~@tZn3p z&2Y^~EQf2%uky_IFFGfhwt1dAoS)}TjG6l_6Eovletzd!6Jz7r-?P`L)3euM&t8W; zdmZ-db=b4lVb5NN^Rw59?a}7odEdx*-Z$)d->~O>!=CpI=jVOr=U+eYPD62VWiMP} zQT84%CdS}tw;^^;yA7<}2L5OEnMB@w7h!Esur?@I8x*V!3f2Y%YlDKdLBZOfU~Nz^ zwy*zcA4_HOeJ}HUDd*h-R{44NtF+wxEwv?5?*6ne_xSFBv_C5Mcu|pUv9rDMQQFs6n;YfYfnn{yvHZWepB~q0 z2Zpt2!`ifAZQ8IlZCIN&tW6u%rVVS;hP7$K+Sp-j?67sNyHE5Z86V0~n;J~CJz8LW>C z)<*{GBZKvk!TQKxeRi;Wj=}CZ2J7R4-9rr4CkX2kg!Li9`QBpsG%45D3A^7Q>^_9B z`x8d_%D#oL`x(OSa|pZtA*|07*2fC#!-e(X!uoJweYmhbTv#72tPdB)&bIZqwBMsX zLCW=0!}_UV{nW62YFIxtte+azPYvs*hV{9_`rKiC?yx?0Sf4wr&mGq14(oG=^|`~w z0Ko381iQBqY|H@cUP-Vq2Cy*(urUd6zK4=A5|kS|0lTjn?0##o`>?_PlRe^$*`OX{ zLSSP;U}HjHV?tnKLSSP;U}HjH>}*4>P5X)%V?eoaFR*bh@PBt77_N0+6xbLZ*ccwz z7#`Rd9@rQj*chHD^AGkHLdKXP*ga%m_nCo>L4w^A1~z61Hf9Mn#tF{%iZSMja$~Vz z_m6_zR|=@-4V&W+8&eG%Qw0>z0}mSm4;upy8v_p; z0}mSm4;upyV`qC|owT2fG1ZhC=MNj_4;$wX8|M!j=MNj_4;$wX8|M$3vjCg30GqP_ zo3jw*EBW}aISa5k3$Qs0usI8`ITWzD&#<}AusIj7xy-OR8n8JUusI!Yp5tte3FYRV z!0vkhyB`AVJ_)e^=;zIV`X_FR(c^usJobIW@33HLy7~usJobIW;hL zw$uBjeaOwxpxnG6*t{Xwydl`UA=tbj*u0@AQ^^~G%^QNvfr8C}g3W<~&4Gf=fr8C} zg3W<~&4Gf=fr8D+g3a-S&GCfuyis#DDL4NbHisHEM-0w$In7z4++4QEmHcklyl>ci zaM(O?*!*$WymHulbJ(0X*c>|896i_^J=h#Q*c?6B96i_^J=h#Q7(3f_m3(t^zM@Q9 zLwQz?xr&sVs|cH`2%D=2o2v+$s~F{L8{%I5uz8oTd6%$xm#}%4uz8oTd6%$xm#}%4 zuz8m-xuV*>V9#eES5#Y>d85d~+T6@DwH|G5$Pl+?xo6NIuT9VVS!B3J&qCrJIfIFE z?vXQ?VD6DKm|*UaGnioRku#WJ?vXQ?VD6DKm|${CIqL^DFBmp280L53Odpuvi?e>B z{M3ec1`y2e>v=u=?wlD!xp||qHaG3SlxqiuwFAT2fnn{yuy$ZrJ20#r7}lm8IlOBR zT|73nN1Ha~+O%P9+ORflSerJiO&ivx4QpeEwXwsD37(;*O`dYb7SB4=hEKURd{~=5 z%oycaZ~7o8*Eaz(X3jYO?s$)knY9gx88bQS5E;hIE$S09W^&dc<&2q}bqF(NZm|8m zk@ay<&iK#Sg0MapSf2~5&jr@!5@o_(0ey$x6|d!cG34pQd`G_jZsOcluMMAT^((>p zm0SBtJD53!XO%K1;jCfGnX3@D2I~`q^$EiI5Mky#o~f!&lX88X zFmtfMJ#LM4G6(zph{VjnPFe4^SWez3@odO52jfg(m^m0{3d797I8zwbX9_c)B%Te{ zhYRb&h4taW`fy==xG?k2E54iRVP1OdL5cPKA)`+a)=v%Vr-t=Y!}_UV{nW62YMA-< z_y}Q}X zu};=>qwYz}n(l;cZ;9os=@to30`ddGn(lyYQ(v(M;9hqmW)HyCS4wR&1_OCxHeh2y zU}HjHV?tnKLSSP;U}HjHV?tnK31DLkVB=n3<6dCa*TlWRth?WRe^_MJy9N0~^Bw8^Z$|!vh<`0~^B=WhyZ|Fna=D_)hA7@=q`QB(X6? z$QV-uV*?o$;^<&(CTCU{TMBV&lpC`IV@ql8O6A5lQI1XKyo$UrSCkuz1!E&Re~r{{ z*of90niw0=m{o6zy08&#eMw?$M6=&cjE!ioJ(FH+M7vy`*qAQr$KFLe8*GdjY>XLf zj2Uc<8ElLhjD76MS8t5(? z{JzFCQjTrbXT}&v%8h}9jhTe8@jh00#*E>N<(1e@7@PAhJ=5=w&3U6+6Jv9}eu?zE zV{_i-$iJ8n+QUivG&n3z57eHV-orG8^dVPjTdV^(2fR$*gSVPjTdV^(2fR$*+g z#IwQ1K*Gl5!p7yo#^u7s<-*40!p7yo#^u7s<-*1o!^RlH#u&rK7{kUGN3O&e!<=Q~ zn9LbBj>+VoZgxrurq)M<=5Yz#bX3_NTMJZua+ zYz#bX3_NTMJd96=csAIWYS=h`*f@XKIDgnUf7m#G*f@XKIDgnUf7qM_*qjB}oCVmN zg(zRiS%C4SI>*D8>KqSWs&hPisgK-}=6mK)aIHBMFh1XBmQV9lb1o>yckG2{U~|M^Vp=$t95!bSHkS=1#>TZjF*cLVOLhQaY>E>S6Js;8 zCNVKK(>}gG)=7-b1-B+P_l-KuiG$6dgU!){&C!F+(Syy=gU!){&C!F+(SwOOA)XC3 z=WDx*hSxm4c0;lJfcjqWM%yrQ?s^08Mn6h}{gEb{dA8jD?qK9OWv8jD-Ho{4<+ zUuG8Xk9?-yZR*Nel4dTl&62J zhkmpEjY5B_mwvWA^uO)ocd`AuZP8qOyxAjBZ%f!ydaDl}j=avU&BYb9iR=0_7mxH! zeEvSo#l>4B{@K3G#p7+0qx>OzhxOO+#3%02Tpak5#1nUFE{<6v@p;=d7yC7)=V6ge znu~kyOnhBf$Ib4ac-WH7#R@-7{D)6w6|410{BZlMV$hC>pPoLesNX5^I#Xs9*X*5m z(fel=Z+B16*s>vB{pwv4uQ+m6aqTII``i@Pzrz#1GHh0{_Fob|J$zQNQnxAbUcNnI zR`IiK65o3JtYZJ85*PQ*D!zAd;?*9TRg8Z*@#!;W729n%HC}sY=d5DnsfmC1w^_x< zmn9zf&E{g`QHh5y)m$8Rf8y?|Hy2w^NPO7_&BaOgChoUYbJ6GK#Qlrr;?PSHZ@hbR zar%jgfBr~wG2o2U{+-TjDOOr9m0x*wSZ7U7ZG#uQBr!6Bc1V2xuLFOOu3h`YmSXF% ziJuG4n{}?YZ%eWB9;tlb4lTvI>sENPmSWPPiN~zoQk?wBqw(G^Tx2fa@m_N&b4OEH zt5&XEF`Qpxom2N}Dc*Vf@p$dnJ}t#hK1uwoAG8#wgnhypLniDU&X_nn@tFNXKFg(v zA3n6Dm@qc+ZAXW;%}Bh`NiD_0?Q!tlC=g8Oyg8uZ~OQ4=vVOEc?5}gFl;HJh4OK z-NQQWl4TP2XqsINZA-u7*gproPbJ>tq1nY%b%_~6#@(Oztn25NFMG*c`K!*DThH%L zoLm3qhtJi!@cy&Q_UyUm?6RHT+^w~|ucP;DE$_E;-`27p4nL%|?4Ms8-CFkB_>;m} zW0n4V;f&U@pMP{gYuW#kuV^iQm*ehgEq|}SPHQcH$Mt5lmcQ?qH(JZzeT|P=%jaRC z1>4H!WW~kW%I9aPrQ6EqYSOZ8<@2`8a&6^v`1c^=^Lg&f*7E)O$+h8Jw#s`qCaf8K zo>x1gt$fZ``*~aW{P#Mbt$asT+<7i<*JG~Cc5BYPcKDKW>wNF;t);G8-fk`5)8*P) z%lDVI`Cf1FdTaT!cH+tH<+#`9y!LWDyyNQja-6*2_V#l8{Pw-=<+yt5`1W$V{h+SB z9EUsV+spC!^ib}&J!V{cIiBAia(Er*AGo!>9RJVWG_glbOD3*9 zq@x(HMB?8Z+fh95jl}PTHR&sz>6`e2GdqeapG&;@c^$?3mG&=vNk{Shb5r^3KXw!= z9+3F%t2>GXIvsZ{4~-1j-uz1iQn!Y^u9AO*0W9Dj^fhB#J_(koWr~ETt4UJ+9-2n zcpmP1JMqkLUhTCj*2VJYhK93EcS`)wpW2Jx_f6dG!uI0zdlNVIYcHm~m-yVX+Kb;+ zr#b2pXSSE~I?C^SJe4E=lVu)=^;6Go`z5CSQ3DgBx9Q=;wC9pH6VuL9mY;iH*Q}S? z%>6FAd}8{c^MeVoe)?yfmlD%&9itP|pAYp*Oh50jZ({m?&+du&U9RpNAM4@wS}6EK z`EK$%uD@zxe&1#9PV-fM_t*L*=6UFGP-32w%eGF;^V4UQ#5`9&Unnup+f5&ijrH>! z9`-?Ep3jjBBpKedfnyW%4sQI?ed!*<^Zd?|_ebVA|I?m{dH#PoFfs4Nb$?0B`|{&8 zQvJL~bw^cnh4<^(QHd7`@7+UfiFqIYvR=~5dwN>szIcDPACSs9JP z-23zJ#Ege;ot~I+@|PPYX8i1W?d~YgxO&c?5;NXza#~`>;ZJ^&nDKeiK8YE(-|mx` z@qGM#i5cf#J~A=m|C7H<%y;3=YZCKayXm6TX1*!Q%uMBcN6ySc*P7~5Ip4djW>z?S2ao$CG2h4g7ri&$JKs&2@2N6;XT6s1 zuXXah-l}?Zyq53ycYnwa_CweKZn z9(chT>33v)xJJ*!%p3o>M`GraC+(A%d8XyeKb2=*YCX(Xt)F?UdYRwa9_GEalX5KtQY)!Sx5N0v%c_o zVBO(!!g|E#hjoh273&wDH`X;ihpcyeK3R+TezA`89btXs^US)*=bZJF&p+!d-wW1X z^1!ezQ-<}L*RqbYPS$toV%_I^%6icEm$vy{vwrk_haCr4hdOSsK6N}{-Rd~Qde-rW zb*|$Q>tDw!*2Ruvtd||%SVueVvA%XZWZmsJ$$H%JlXbe|D(iR0Th{fC!>sompRoft zZet&CJjZU}IFCKS@gF;h-!g0te&eu3_`SeJ;dcbvh2Ix!8h&@Mb@)BP2I6-L+lb#U zY$kr!u%-CD!^Yxw5ZjC2M{F{FH?h_DJ;jFOcNW`@-`^9y9c&bp@Ab0F&MLp-7cVrc z{J!t=K~wqNe{N1VhpsXoIDKYQIZwDf#O^wO829I@Ji5InP2^J zc2nWJYxm2-vs9Tw!p<$X2+xM|v{_@qGf<{@pxQ|)6T|9Zu?V#De8M{a*KoGbm|eUaOK(OOjhDDj%%Jo@|Iyf>EfjeGg& z#G^vYfaR~f*;2~CdUdczRqEOI`z>YtqZVo@^}hdPbJ?EGo5CI-m3BT6Vm565kNP*4 z_eJ>v-6qC1Aiv33lOj`3kJlcIO#KJ1p85p6f8X@sSWbH$TjG((v~$kgiD~~SD?S>_ zxvxIkCgy%EryrE3f2@aovwr$hz4Wu~q5o|szl-hn_ZqU;Pik`Zx1-$O4)(W${q10X zJJ{b2_P2}jmER8bw}budV1GN<-wyV-i}ID<4)(W${q10XJJ{dOa_(Ju`ULj3gZ=Gb ze>>RU4)(W;@|E8X_P2xm?O=a9*xwHJw~O+X-wyV-gZ=Gbe>>RU>*QYT6BY>nedB-u z_0v|_r|zWX2Hd#&v~%h|J8ohf<*#>~R$mPMRz2Lj(vkI#FR)4EGe+%NfAHaZMqco^ z_3M8(<>-2@9o+jH^}jj2Z!CZ9uDk0#`E|d@Pwlf+-O@)5h`jDAAFfY1@}aysldq;8 zbcK3qvifV#8|2ptdTVG8*M|1g&`vnCvnFeQO?F>3i|jR^KxWRz57Zpg=RA0=w$1Bn zh8KS*(DnLq_t*S+r3)i(KYdiqWm7JSeCG7QH6wao68Zdr{cHLRxHR%@8~(7S|LFr` zJ>TxNdd&~k9Tdw)z4kzL>u(1|T{jQ$7{Q=N{1&?y>&ZtM7@wY1=Nl*S~dWy7$+o4vmaV;F?profqYQw)^!pZ6nT) ze8K^PYX)v{LFBe?Us_XhUFwr-o;$0ien#q(JE{+u>S;6m6WUzQy};pK@_Vlt za_gG$8NTADz3WG9a#`dZAE>HtocuJ;%vwJhx^ex`^%jiJ)!uzqu0Lbx)#J0*F!9s6 z^MAQndXZ2KP z^;c(lYqIv#&`#PG+L^aMKF{^1EnmZX%5M$xTl37rzO%6JEbKcA`_96?v#{?h>^lql z&ceR4mGbz`R^;P53;WK(q5k;J!oIVx?=0*)3y1dS_ZZ(<%6(^H-`RL=<(-9nXJOx2 z*moB8orQg8Vc%KUcecXuovp~kcNPxU#&;I>orQz0_|C$&ct^X4)+qD z)yUyJ1xzyXW7FOg{g%{;!)e z@Q%^6;&|JJR4?N!@M ziQK&5$Xfo8p^Sfnk>whgI;ab#?(poa1EVvP_q067S1BLriA+7A{>aoH{vx9@{99yn z1|5;n8FW-r4?2U6$d&uDyk{m~mDN*~)nAqAt;*U{m9?`fYk&1g%PqKW<-V%3`>oFU zfqH6@L1)%)=#Ay*Vm18euU8(%6nQKN+qRayO2nck|bJ=Iw| ztF!jU->!0BlzYF(*H-SUI_sb6tl!WZWzfkzSMIAS>;J0kcj=k`Ufkm!pXxp#yc6qj zk1+bVM;QIwBaD9T5k^1yVDxj3F#5Si82#KMjDGqNuKacrEJug(=zysQ9WeFt2UEts z!N{TmrVez#v>zRC<+rn(-%k11SCx8VAHv*IrkCH&_Qc-;8TtktFnt!@yPHxyYsTNy z@~j{D?W!oJFVO+hm;Aw$@ozA)=zyss`(1kGzt=8nZCK6y@!RdS%-Yo#ZdW}XKKf7J ziRJAB+a}!j$+sg9`sT5GzRu}#)a*(YH*F+9= z)P=fwA`|MaOlug{rtg{@ozA)Tmw^wI;a~Rl=EL!-ZPW0 z%Ic}g>aWW5R%h+0&e~a>wLkoh1BRoAe$DO|dHaESA_tw-S-({Wz13Vx8UL2*8C4b9 z8JRjl`y*5L{C>OU>(`9Gm%dST;_0u(@`YdOSM~Bo>6y4- z^5m+s#xEa#`yf-j_HWkbSzB-A`p>H1jSj!BXXiriMjkb6i>f=C8X{B2I-QS2-nnB$ z6@SQ6#=pVHat%x!)CE&Fzcq}`P(H!(AYZF|s3$V@9N9W7@{Qe|sCxO(iIFe8@$Rbn zfiFfre)m6B-SU20lARoiXd+3~*mZ2W2M?%S^(d4C4=j74h8%{WP&XbWxoqfZE z6^8seJ~NLFA2ng|MFz(59>>fGGJRtCsI$A*Uh(PQx8vFu>OP*Z^!LWc=W2s@KMC?n zMVTJQ99(4Kwm&Ic`}>|elP}brQ9I*?eI_9D+|!*CmRaIQ zQD)ZSH-&3&ACJuMkLg!?NW)!G=FBB0P1wAc)RSlU^(X7Ywa-pK=DDYTQ9I_ySy5)S z9(^b5cH06Ikmg^Y%Y`?`z?BAZ4TF#eOQ(KjymHm!EzI>K?X3s!X_RM^44xi2K|Fh-_>m$}-U$-?^KKIM!g#VeV zSLV`R=eat+9qTf_iL6az)+}&k%@vuo3~QXqIxen#VAdu4!K{b4Ul>`gfmz>B7fjvg zgV7nv|Fd3BYp#E4y`0TG!n`ZZZNA-k<-cXV#9Si$uGOLbFh407y>Z@XIdd51kXd<@ zsazZ9pov$E^FQQib2jIRGO2vUI5*AY>+*V(nO{GIHk9%i)BZRQOnT?e3A6GjQ_)qM z-VN@3#k$YSlylT5Q)y3pwkvH$zU(*ZQ6{@zbd`O0_PArBJhCfP{WS7UgSyv#`09a? z?_KBm+G%g@8u{#T&9xhTxOwEdQOnnbzsRAiF8mudg6be!7p{pM>Zl8KMGkexH5W2L zC*{1i)s&+HMjjp3gASPb`GYA#2aGJ&z|=uqFmJ2s=6rb6Z>(7q7(cxQ%`T1#)M-3Yj=IuvB<~drYbJxf_cdTC*{vwC6_{>mGkgW^X zRKcN+x=>f-PVl~o9Wc*iR$i6K zhqYl@Pt<`t_mt_4Iw%jaQ3p)lWbLmWab545D5o#8`$gVD5nGW?%*(LR_yp-$M}4(9&Q2h*>#4W>WP2h&gJgXus1&wunQ zI$+At0V9tNn0n9wQ$K$&W&9hAEZ4x)p$_Us2j%>imB-(XGTNBc6Ms9(xu;AoeIDxx zvh<_vjK3Z7q3-zG!SrQzzp>vbr!TYqiN6!&{BHcg=tT#NEZ4xa6CE&h=XR>he)S)_ zV(1@ieqT4c;(y++^gL(p@7MbM%6~7I@soEiXWmE38E1G;D`V_`zHy;X94F}$`i4G& z9VcP>lCjKk#yI5}`(Wx}OoSaLVaG|>aT0c%gsD59pJelv|I8=D{O#*FpA5fcoF}uM z;(cSDSy^|)Ij8HaRDNYuCKJEWmWO96+LN&pBjZ}>UuBc$nWN5m*Ls=#`G4d)$lCw8 z_0hl19{$B^w||EXpWl?e;&+hw9seCZh|?E7tA5FE{;_zh@A191U+7nn`)+$&%WTp^!WpeCI0%$$j^=(Sd96`FCwq<=Yhpz2b>VO-$H|m@vT3P zd|$6Y#eNU{Eb@2H98{dyn(E(b;-F&TqmS!F8{V8Yu()Tt(;|<4dSJ1}A5Mup`PEQ9 z^H-4{dS_r!bI?hV-&<}_ao;v`hmkwi4Q<%%;K)l{banCg zN{2Go-w>ey*b+t$jHCj@P=Y` z+xMb8d}r&1|Hri-9dd2a?Tss9`CgY_Thu-Ahse9Wac!~0o4<*?>WSACmybLm@<$5~ zDULYd2a${MLyD!J>lOKTXI)<`u-}%ENAEqf7`ofWHU37l6aLjh*A^=-b5-PJ-@CS0 zX5ot>AMyR`id%nmR^%t@t}Fhy;Ljt!y!()1?2!jX-g(ZDVy6|pA9?9v*B7T=R79S1 z{eqry|d#4Td34H5;)5`w5XVP5Gul?5eN8`QF=QS5SR^DUZy{DA- zUiXcuWuIJs-PE$LPFiJJ*@r(nZCcs4b$3jQeNG!}GyMK7kCyi`^4Q19dpu?JDdoMt zGI2`TC+&MqE&J+#iBroyym`54W#8_)>$I}ZxnJMq`Q1DHz}OPnQ=@#i_nLXjE6-jm zul&9>-V5?sAJ$}jSd;Z(P1c7sSs&J9eOQzAVNKSDHTI!xvkl%C?a%tNChO0dtUqhA z{;bLRvnK1$nyf!-vi_{eo~8NTd-m+rWbbbcoC3 z5|FY|6a^Jf5Jd#UhN!5>Z$2~6=kDll`7Ynxb=UpA{O|pm*STlToS8XuW}bWJvF4!Q z9E5*t8*H1c`6#UUD6IJ?tobOc`6#UUD6IJ?tof+hi}eeAakI9=4}o|txZY7du=Z(R z1=c<-L*_aNd9G7vueBx$YfTi^nkcL_QCMrDu+~Ijt%-tbBJ{(~zh$$vJ_>7n6xRAE zto2b?>!YyNM`5jxg6rek@8@+N>$y$GH1M@4t2Ni%d@VEQcdK>W13TYuB?q%y$qUNg z>{-az`pLi5`S3^uQTT(dTE2eaR59R9!>qU3 z*ol6-shq+3m6|sxFspR5rM5 zyRyxtPn69reWiTp(ub;zE`6(P(Depv)AfQ`uPzVN3ue7w)(d96VAcy}y!+D=sqL zshfSk9a#H-Y}tFf^KpfP?#7??%Q}n4JDJB0xij|fm!yWe0#5X-ahk){=65b`7_=GX;ZNmvR?Qlh0Y>>6+0lmX8`y*_S`w^#Nbc zid?mP{X^T<_3NEly}obH!513(c0N$2v2TA=a1*~>5p$aO?L|5L0D1ZcdgwRkr$13I z{S15Pf7r=>f&F%Wfv;ul_4^LYz5}!G!0bCP`wq;$1GDeI>^m^~4$Qt|Ir@(B=sPg` z4$Qs-v+uy{J23kW%)SG&@4)OkF#8V7z5}!G!0bCP`wq;$1GDeI>^qjD?^m^~4$Qs-v+uy{J22YyXW#vI^_|Ov$SEFLP;=;eC7qkTdL6x3D*1GILQe zXTrXq3^2;u51pqO@}KqnKr{3_7+NqBGSHu6K{d^&cR^-|X4rEyUmMM^^H82HnqmL@ zeYPA; z%WY3Tp}ASadfEKRmYUBg`LU` zmOG2Ak@-F~ZESLFwS4?3)ArQ!t7ZPB#y^+4B+BZKXX1QD)N7L{w@pmboZTu>Hrt+} zd0vM^`FM-Xnk#otl)rR&O>^nNiE{Onjha7yB~jj4XT9cx1&OlQkhPkJY)X`0{k&Rp z)BTC^%4e%IzkNDU9(=&?g&z{-^Q%_s@_FS~%Bgh>ztL)?9DbYOzExKF+$n68oE4C{ zI((HZJ>JOFow-WRy>9r)&8y^v%|?ImPglu9E!JrL(@Ud|Cr9SiG%^D!-8VH1~WsRo=P6@P@Lf^0k8bb$Mu^RC%Ma;m2~O%9sX*ANe#zE|-P}x7+G- z^qS3bLC98Z|MJAmvd{(7zl)Y{mV2g}wnr)cv0k9B*KU?2I+?!ybkk(Qsw5T#@~x1KzkOSstqRxaJcRlI79a z%{6CNOO~t7N+^|)MU9-%~L$vVrjCRG4?6Lc{a*CKlIc*ZstZge7WI1 zIg(`013h$kRIeoY$f)j`Q@1C{wi~)?zVdC7eDp$R&9hIf_VtXOvck7#ogF#Pd znfnVR$|66v*1TzGqI~Y&cAA@ioG4Gd+d=auPp_08l`uNvFRzr&NmEzemsiPUH;fI= z{j25v2xI4SV^_8w_=cM_&n~%4_TRK!b9nqRS*pi;%?Xb# zlOdayY2H$Knf&77O3iJGFOxYYtk-;W<8oQbnW#DT{^fGidBfhC1Udg?ye=;omLO}@ zouavOfdn};-*nBn4la}B#?8`v=lW%G!Ra}g#~)wq>s(QFgKzU!7uL(OEw*Wyh11r{ zgm7a+!*c88u^!8H`PcK;$!n7qXwH#)oosVtrsn2-*2+E485`#8TO-HaZ*02}x<(G$ zW^86mz!=~f1ZM04Gj@R)yTFWHV8$*mV;7jQ3(VLBX6ynpc7YkYz>HmB##J!mJeYAF z%s3BboCh<`gBj<+jPqc|c`)NVm~kG=I1lC;1m+q9<~jxD`UvLw2rwY{vnX!%mjlGGN9EFk=Onu>#Ck0cNZKGgg2ZE5M8u;Qv&N zV!gHvU^@;|2L55WEdyq(1~XQJ8LPpJ)nLYIFk>~?UN2Y|>ZN`#^@FJ&O#NW$2U9FT${jLo4{O~!1fwPJ88BraZ^vqTeP=o3Sq^!dnFFAlIRKbB0GK%dm^lELIRKbB0GK%d z_&=35?|1JgDzZ3ELbFl__dws8*yn{Bpb zY^DtK{H>f>ms{t4%pntW-5 z;dS3;`ZDdtxl&9qbv-rMm7T(j{-j>6tdeYWE^g(@azzX;Yv9VxGmM^sm0dY2%y3u< zSEkf3T(_JjAG&VN5MF8G$$L+SYTItF=gIQtTWRii+?5pum~(@#Zuey8;^quwL`6>~ zj}Ox_4eNVyUYI#^INivTIqos%A@`Kc^v^DK49%2Zy=~4D?tVQ}UJf(-O95B@9Bwoe!R~Eh6MRU~hZNAPk)i%qjSB?GgF`MP45M%$v?VIJ{ zD($uW%DcD7mm|Y9zcXx$40_zOrTEz`a^&8?8Az9{ve`aU@1zr3Wsf?>wwlg1IcA69 z=|hs_@n+@>p+%=8x$(8N`g~wzk0dE3Bx{aIOOmZBnzM-2u}QMv#D%*2FV7~)XCGUl zxkY4>yzxwe<|^Hi13It(+#y)t;+4NBVZzviuCq`ySpd2j(#KewLLgFXjoH)pSag({~t~ zb7f`7sn>IApNF5ykQ2_|sd>*k8FI;`+?uOCpCK>JE~2^J{0v#OL}ATkHfG4jF5j*B z%)tz~=0*X{^WMvl#ec}B`O95t^2mKbngN;+ku>%aHZU7SsIxfvvvIOT$y-l2T@lhp01KoYf-^v>1>o?@?#? z;Id(C%DiI@znnW&F8sKSmihRj6q$LS;W1e$a*;6Ov&yOz*`TpGCoDTP zMK&&G&hDy?OOeM*n|U`_#R}Hj`KvTJEQgUPr{d2v_1gq&h*5o4wV2Ua{p~cl{+!{y zJJRIW>89Qdo6=;@vc|UJ3)5uRSi@^ZrpdV%4Y%u_Ci~rG+V%D4Y4YtortNLNOp`U9 zHun7Lyfkp`4I6l73+9%rj~&6F8#=^UNH~GjlM{%)vZk2lMP5%=3RR&;P+Z{|EE@ zAI$TAFwg(NJpTvt{2$Eoe=yJg!Tdb}%-v+G?Yh8r4on%em*ut$n0Ydoc{13}vH2|YP##QqFy-xM z!OYLWx01u#GTbBJSu*PSdwT@CE->Z6_MU?K4wTz$*JU$hV8hMUbmkS%X)~WiIiCeH zANZ|2a}ty@Cjm1j0W&87GbaHvCjm1j0W&87|EF>x)@$1UwsS(tz|SnVWx&iE!OR=M z%p1YX8^O#Q!OR=M%p1YX8^O#Q!GDC@l{VP+fNz##v)q;e+j%}^;AfWGGGOinz}yRf zxfcL)F97CV0L;Ar*xsA4F4Rl?VCn}`KbZQ#)DNb9F!kGYfw>O?a~}leJ_yWx5ZK;Z zQ780M514wu)B~m-F!k6v!Q8KbZ)HzM8CxD~?>#AldRcDEfVn>fbAJlv{uIppDVY0H zF!!fm?oYu51N&3(e`;UMdTkrP_THZ|@DIyv88FWWz&sxS^Lzlz^8ql=2f#cZ0Ndvk ztPAy0KbZQ#)DNb9F!h6}A58srU0|M#fO$3o=Gh3CXCu1YI&Yy)=%*eq^?<1dOg*|h zpa(kbeGT_zDCfQm%zYV{`!X>1Wnk{hz}%OCxi15AUk3go>t901I705H!1z&r=gGJoS; zHME6xf>|$^^@3S1nDv5LFPQa$S+AC{&L4R00eft=&t6!LXITz;n|VHia-PqCc|HT? z`3#unGhm+2fO$Rx=J^cRJ|kkiu!r@6SudFNf>|$^^@3S1nDv5LFW9cvKBKVNmiZMo z+asSEXwI3-KDtMCIAC~Wi#>99WpgHcPH}}-4DW5cM`nLw&Z|FE&khbY{KL1q{d4Kr zckhw)-#6#REh_Jk=f)adKYf=klQZ`&**s8hOo?6cn?$3(R;69?X39o)n)B-1>dgP@KEoM(GiA9jb5`7}bEaH;)o}ZuY+vV{>$2s* zW~SbU=Vi-6Zy4K3Ow5*TMw@f*sIl4d{!`}JA;YreTaOqH?vX8Hx|_Oow$7Gi&KP@s z6xs5#sfIUxoGtrSGw1My&t=ON2Mw3{G+Uk+yi~V0OYx-5$u$BpHdAKl ztS0&%h8dkQ1$bGH9TNO}&&M>sD6=)=J_j&lR@B)or%t-Ac}?Tpazkbg2j$N@yX6BZ zIW-p#*)4x~?RE!xQs2z>8TzU7p^7_Yh4#C({?i}tl;y|Tx~7Hh1^+k&g27P`%gk#9g!s` zJb6T{8|H}CA7sf_UOy)KEOEp$%7&;9Pl=Vi9Z^8#7>~a2iOAbVT^VvZTRz|XOYv^y zU?B?Zmd!%H)3(76xWfm&f`4qjnXks}>7(V*7Tirif8tp%+Iz593(fGuzV59w!#@>& zZmSu7t5v9@X81GWnXa1Q=dC${X3^tGi?w0y?E8;nlT=( zm22T_e^!VWRL-;gKx^l~Oh@GCk}X5O4s-VRazya{EO~!s7w5;xLKLf+CBIPbNTd!5 z7Qei(OSV4#w6kbaQ*p-+JLLzv`#K_DQ}I*Jo$|Y85sui}L`*reL-xBCp>4xBgikm= zf9oIkmUoXR8FzowJT3oHpNHH&@645BU+(9eJ`(KS({!$kTpQthRlcd);H^0_v1p|F zM!SiB2Na%tX-=Yk7UkaDRoefX<~McaovUQM?;@NRS32(E7goxU2bFDyA9mN>u~P1; z+7GtrXEDxE@A+yg<;%Nv2-I79&q}#@gey>Q@tUh-(}YYx{egMsa;~8qjPkBa>$sox z{_CAxWOZ+e%llHm)*UIXbw`S8-I3y2cci%19VxDLM~Z9Rk>Xl+r1J8{q4*_rs{EqU0H^Dg2I8RwQ{{r}fzGnU^~I#|%Ab!7c48tP6t#y;l^Z`A z;?yWyPsH|{DrZi5#^D_@wTDgZexMG3P`u>@%w@ngdA1qrNcg_U8 zA1f*q7_IN0*`~^ICk)E#{Qvs>J8FI-qwkOj$p1=)cgxT=+GCab_s>8l%Ap5#f@vq1 zc7kE&KN|;T-!osX-`Gpf>tmVoWwF$5njd;}f&Ahp9ar7T+ZM>grR{Y2l-vtt&fPi= zyH7M)D4WjE@mbGh#BIz|%xm)RdA}U$;=Oi^Gl4sf{FtW3u=|a-(!Y<+yOgN!sYCfo zl@s;-bznJsg}&Dg-0j42ecv58zWZ{04<2~NZOirjcv}8Ig1$Eo{8(y&ZZG=6=G*oq z`2KN!NbvnuvE_2#pZU_4`+gqYY=!Utl(Q@ReqpTscf@DZ`@o?6dR)Pt@UCxahMg;q zyssJdH;(^AGuk!k;jc8Kz4=%DtQmg5x=;U*rSjWDZ~ugEPPIR;zV?M?`1zr3XEnqB zw>N%QGy3J?fd_~FHBDVaQ;HM|75IqZ1dFMVv`oi z!%HWLd%`~oo-}-+Z2i_0k@9REmo`^>S6ic$}KTIakmfKXz{=E9zxf;^U$^KJp7m68~I7ahA#7M z%zc~7)!6OF(!X5E_G9c(bBoHT zFR(_CyYEz-bEho(QG~O+VN>_*6+30KkNP=4Z=RN$s5-dxbmVOt$`|SQb03E`+6?;{)6g!)I<%KD5Po26gnt+_ z;Wx%o_>(aferD{2|1r+lFW@&SHgU%&+olKK5PdrayH}OXO&`4~uI~}<2dXWPCteam zMmg>w)y9pZ&x);c9k-s$mf1hPFP?B5_ci$Bv7_SEnZnK8DNF8~^oD4>BiQZx<}R6W z@^$gaXHDIba+iz=%M$$>HFXCk?v!8LxkD^ceetI1i^+GmSUdEd8gqvX+rYo)eh~WM zf9}7qM%c`KJ!Htg=N@0#ZJXcN5AF3 z_|fHH#9rnA_8QG{BP~<@_N}7g@cNpMr?3Cj8jAH4^A0%x z)@3l(<+E>;)7+}Y9C7tn1Rn59*4HCZk8+BeZ)KjW4pO@w9ku9`Bc0d9;~_JwB5Iq zciH(~jp6lO*o-l}<9RDT=}GxbTq?Pi<>OY z%rkndzH@TIh8dYve;K1W@v}*pXNMUcR&7FNrH@AI@|UK+oLQ!&VU!o$`hqVXexG6J zDKvMKE{FcQrGCx0SC;jHSudFNf>|$^^|BoGQXch!Sugn7-Rs;!eO}Qv{F1!ZUB1!q z+No>Y2HzUqnYzk7(`bT`c`(sE^sM2`k_m3xjfRJeT@;_EdBejm#JjC37~a$+);(F$@Um;;-NYP*f876q+w4Q5=et3}-8Gv7Tyl_` zd-Si_ZVQ-g0kbV&wnfVX+5%=GEnv0<%(j5p7A+HK3)mk2H)|JVAkX=TyJx?<$vC78@DjJIlz&@$iFotgg1qdqqw zE19O0QO`Ezvr1=E>Qr?Fvo2*rFl`{)wt;CIn6`mw8<@6%XVAcg@U0~J)W?f*`1y*&rtV@-gd*f(QxMmJ>1(rH{9pFKCXy)TFa#7i*k#9_iMK6 z0<$hK>jJYbFzW)dE->o?tGWd1Qssg+D0xBKlpaBwm43mtsCot4sO%AJyYh*kPsny% z0ULB(VAcg@U0~J)W?f*`1y=p*kAKch#3HgS6JURAC>cMtkZl?8&H94l7Bcn9M!To( z@1tY;kr`3$9R&g+u9}h5$xHPw=VZ_q<4;of6tx1P>;r5Sc?Y@^a6*mk8~&?l;1L0>6* z1bwLN6!fjKU(n~OU4ng~+AG*c$`68lr~D(>r>d_7`8mB!L%7n zo58dhOq;>98BCkOv>8mB!JH$Q%e2{MTPDE%T(ieE*_HwSW{mlL$9}YBz$(WJ<~~mC zvx2$5Q~R}G?)%h!Etva3wO|$^^|BoG zQXch!Sua@Sz=Aoy+6xHo1yo)wxJOX=w&31D<>7*R3YDJ=?ln~2F1QC#`MluXMCJK{ zdlr@d3+`pqzCdt~qxK7edmpur5Zn`~{e|FON$sHo_fRUY7R+X7}=G^@7wdtTK>?u8-GJu>ug?+pFiQ=?w) zwP6qU;INZ>bJ)*4JKDv)Jle}WKKhh6Jzz-$Yc zZ2_|_V73L!wt(3dFxvuVTfl4!m~8>GEnv1q%LLj2ru~R5_FN#_GGLB3$lEc2Y|DT- zmm!a5{k{&cEdxF}{E&OF*mmi;Nf%SctuaoeqwC#DH@3+x`$s#6$F6c8$(tg--t~g> zb9jRL$$csEtE^E@*62m&;Aoj=~L?tvNUT--g)omx9hR+u`{Dg50`cf{~C*|5fQ zPVnKmZcBBSOSg;9Ik!Ey$Q`Theo5N>ywfpHf_vzWbU9_qD5rh(Rqn(0rpqInUT}UI zz20s7K)O7)eY8{M{ny;+D(Ny;))=RMnH2YYiFDca^|8(`6*Am=ucgV7J6?2F9Nyu+ zdsy97rT!1-#p~H_#RX~deEK-&tJ%uuozrB7`aht?V-C1&3#ZA1F5{hh6W?$*XK$Cg zrm2|xgZeL|!P{l}rt!|k4u{;X&9=+T^k4Tc`x^b8>&ihlZs>MBU*d+o;Xd<*;bK4U zcaPkgrpphmdfhEF!0?KRS?*#jEjVc&R$ey6yc`UGK5mUUjdIGkkZ>scy-dhTlFp-F^LZik2Ba zYPMTzk>N|b=ev*eHhkBDCGMIB4S#cdg_~H^aB|1B?tN+uqg}(UB)N;!7zQVg-|AK^ zV9INqNOSvFG5o}F&t2BW@E2{f-G#A+H`Und9@}SlW6J~Xs3OL;@Hua|{regY`uU*S zDbujscYpf!_w(()V_rPn$BgHl&#ZM@_b}Y&@=CXUsNuECmb=p$8g7=j)V-&;;h4J@ zyB}OK|>UD-1)=xPgYD zKf^JMddCzq414lkF+PW#eNGsL{ZGDO7-O=*Uc=v~yylm;58mp_7o3#p>lr>F-PhkL z$o1=;RA+~8&u1AseLDwk+~wP!b$yrLE|jyqkf$G@hyH}S8I zb_vEY72gEon~HmaaZklV!FZ_Rq+py>@l!B?fjJImM3C3YH#|746^cNZH zvdwCZ7Sj`2_^&CENDlgd2|WBlyTYZ&7y&NFij<1OU{ z!x)EcS{TOoyjIRI#_dOU7{++s^NU%t5*}aem;bmf!I!_c?;>AMv4pw4{);co{A;~6 zrup{N-u|j@=hg<3efvMz8t=CYl0Qa2-_ZqhGGpO%L)@9!wwO;#ns&(AAU#;(cyHL*dLY{tr9{LCR={M9%f5IO68FteDu%G>M zEAM{T?~44Z-sfpJYEdxWqi9hvUUcjp@fsN4CNv(kC=>jsD*so#<8&+UZ`kjg;2kj7 zfcIg@c%P6mV7~j&a7kN-?}QXD)5l?5bs~m4e9y{#?^%cMUk$4_(&2kquS7rR@O`bI zXP|2j+kLf%zYQEXRNRQ6B&C2ZkQ}#~+yg@dxIA{DJu& ze_;N{ADI8~2j+kLf%zYQVE)G+nE&wy=70Qw`5%8^{>LAf|M3UrfBb>@AAc;TANU`C zDCd9tf%zYQVE)G+nE&wy=70QwVL!$XzSZLR0dxF-Iex$#KVXg@FvkxV;|F6H%rOk+ z7zT3;vmA2=%((;R+yQg$fH`--oI7C59s7I0W7Cb!Q;!XIo_N{t9UX`3c@6n3jfd<1 zPzEDE$N%|~)!f$%8T4u@7|2vHTLFW7UMZbRr{|)^g|4-zbwF`E> z*JrAPooFxrQy#po;{olTKldsAS>pf6eG1mNzcm-s*zmufg^V>eT#gOM;M)_7pFi6F zp{sH0{&@!efA#N z%~y*|liRKg)I6xkH2L+;0h(|0nkJu>{v@1T(%BDY7qzvp*$DnD^2-@9MG z^8?N-)YE5_2XZsLPLUx4#u@d?m(BZuIJ@rjv047EhH;kOpn+kWu}|7#-d)7mdw3heD6eqJ*a`WO{S8CUuG_;&B5zKxB zvme3iM=<*l%zk7!`jPVJM=<*l%zgy3AHnQLF#8eAegvy_3C=rJF4(_HUa;Sl9>MXT z^b3v?Rj=UqQT7OqE1cbNyx~lb;}Brvyu*RRHjU#}WJzCAd*qn$X@qy0GRW4ln!_ClV1fFAk> z`sp{+OMk*1`Wbf8|FEC^V)qx>?#Dp?YI!jG5zKxBvme3iM=<*l%zgy3AHnQLmUG^* zA5qSJ1hXH(>_;&B5zKxBvme3iM=<*l%zgy3AHnQLF#8eAegv~0!R$vc`;q0GckD-$ zvme3iM=<*l%zgy3AHnQLF!osk-t4N^3!FJvtjhy3x*Tlp{lQ!}$#|y-Y^}eVsR#Qz zoN4fU1M=MK*&I0c@b`n<8wTzuut4kMp$0Tcv7lHn5!2<(nkU=i^GN z_l*-Ymp)U%dH&E8&8=n@bxK_usJT{JA*XhkCYryFEarV z!_JPaQZ>W=7G=^kqg^Z?HKMXFf4u7hzMd7iYWezywyo>eJGFX!-=2dnH1zF!piX1o z{;1$4e!C*(H1XSua{2-C^bhpVZ_rPFqF(wL_R#;Zll=nw?elH>yzW-c#`%pWa?3x; z{RzygVVivy5bw^i&l3MrcX{3H4D)7vf!`f)p7W2Ko!V!%VC4Tezx`MJmSOA1?;5c4 ze>xLZ^7;%GHh^i*|MoW#TMvF8LB0R%`L_LA$v^X(3%~XLcia=m@7ys5?cZ_iw%qJ@ zAIQLOIG?}S8Mu8;j=DIH{s?!z!5(~*jX=C!{5`9 z^YC|ejGk&$~K-@|X&VB~@LjT?;o5WjtckvHNuaWL{p{8kP|o{8Vk z!N@=H+d3HeD%t`@zKS-o9BrpOd;*3Z_zDdD@F5uW!na`9gLe$TuoLeXfMGx0F#w}o zc*g*Ye2?YG11XREkb00eQa}3+&$92p>^m^~4$Qt|Iok_)`T=_AALyswP%r%nd+2A_ zN&mxs_KV$Lie1h-CFAlv1of=T_Y;&(m+vj8x?H}`plopYo`bT@<@*oHW|!|ps5ZJB zhpLVG{2zHN$~kT!&+!aB9Oux_@sD~rFJKSf4}qP0KLqw$?}z+feNWQwFZLbA4Eqku zz5}!G!0bCP`wq;$1GDeI>^m^~j^&(p>^qdR@4)OkF#8V7z5}!G!0bCP+QoUN=A-UY zl&g8F`x>m~uO0(nHLvy90IT_~#|&7-0X>$$DxT;u2FCde?Z^3y6;Je7r99^y^l;um zKj$6l<-CJEoOiI3^A7e~^G^32^xJ#A@ySO-{c+~(@t&6si$dR;GsXq;4vN`B41aX} zfN-yM)3K=LfxV*AEW?9~>=s{y7@qju4zV<6pnOh-DEz_A_oT34@SF^nGU{2^f40bO zmpWBlF6&Y@xU@mp=F&E0vrC&*TU@q9wekNuH%7gXITC5kmhtSFB*W0T>`TL_D}VI^ zY_A*M!?0?v`*oaQ*t}qMpj@@3SGwWf?1lB-Hqc%{8TiV7R{4-R;ak=PpVJ2P1#Lqg z(Ps1=+hXt8)i*)@Jre(o_k^hLn|^h_4ZmSj-x&VO@6v&<`2CdnKI^~kej9r|{WJeD z`IUxIr;F(3bv`Olx{i^{Lzc>4qncqGmR`ZSmFz+Y;^Ns>A?4Y^S&A|@2dgxz8Wy^s{!-A z8Zhsx0rS2ZFz>4Y^S&CeeTUNTabFhiZbDu5y-fDKPxhTxyoU|)yoU|Ud)UCdhYieo z*ucDp4UF+=-Eo&m#@$D}2M>25@qRqqmBf4VaK97p)8oB%(1~&TkKVb*d)uJLzDMg{ zbw}LI?&GrW`{KP@uz~ljfqCB=nD?!LdEXjX-D&nW?{>r98NXliw`MZW3Q*3o0xyf@^6|B}Hea|Xbtw;KvRW0)extkRGXxIb$ zasLmPXAznMcb0=Qn0$eMc-KpR`<8)J4?ap{uX^_DOla#qVFsPtNUB@ouy!P ze~Z4e6s+!V(RY@D)%`8{&QkFI_MT6kKj2v~&L6-$e*mjIMBn8L{%7vg#d#z0Rp?>9 z3TD0vX1)q$z6xf(3TD0vX1)q$z6xf(%5uJM!+aIx%vZt8SHa9z!OT~|%vZt8SHWl( z-kSpB91?jf80VA7Z^1aXMBWR=c_#8MhjUcgk8@Py;gCT& z-?xGM@AaM=>cV*o_7`CMj)VOL7{Bjee*wntKG0I=IyYDc{})zaQ7hh7qEvp zJed0+F!OmZ^La4yc`);NF!OmZ^La4yc`);NF!OmZ^La4yc`);NF!yT#)_0$Rxkm$Y zj|S!*4a_|nn0vGU|HJo-GS`J3=BQxa84G5P3TBQ9W{wJGjtXXu3TBQ9W{wKB?*!&O zv?%9(Cm{1LxwDsh9O&d82h2SVn0p*B_c&ngalqW;fVsy3bB_b&9tX@lPJs0u2h2SV zn0p*B_c&ngalqW;1o)r1yIbEy3_aY}fd85MsO@(S@ePapZHxWx9~m-We(%F?j;M$K zRY4j1og({vCwy1Scb~v~?+E{81IGW(KqnYFS&naQ@ZK!SZN@va_J5zKzMsmj558_#gh?H~dc}{`=DYpUQvme>4AA|78h3+y6&q@!$L}zqjAdD<12) zO(uO-RVa3CzBXkw%LVyn?}(zm`0gl}{jSE6wkPntp0K{x6V~^7!unoMSl{aj>w7(6 zeXl31@AZWBy`KJFJMg`p|Lrzxu)fz5*7thC`d&|1-|GqMdp%)&uP3bU^@R1kp0K{x z(_=pHjikUgk~Y&e>w8IIeJ?4j?b|DWv#TY`*z+Cn z{hBB~C|O>t7N+^|)MUA|PFu|_mL|&?WA(S9qT$M9xgz^XUA}QqvOHAram^TCb%PwAYbU-36klCfFVD8vrg`DC^)exRz2=7H*2`l(mTUfc{yKSW(gMvna<7wZ zj?C2Dyw6&>=ea4G=j>Y}$K9{L8x=P~*T`YpChGF>$5+czj^U#lm-`%h|8hC%yeaqA zB*^(E&9eo=5@fBqMrY>&336z@=~_>&gUe*OakDhvxqg{kaC(mB@c3o2RFCnT&6^Nte$qxlH!ov|aOKb(i@*89il%@2i!& zSI7?rJ)!+}f1yNKEYdybzn9WwJh1_!?NXDj~EW_ku77o zPtr0wTW8BMXUv%SQDn={rW$S^l|!5-rIPO%>Kma|FGE}IXKwxxfXk5g;$I{Wgp!mI~*`}j#TBt zE1UA(7t-X1RZYzK`tvmT_8!A+zf6-go^GYv)%mM5IV^{nJLQ!8w4Nqj#i+Y#s}>8@ zGS%Nslk3kJ?zGJte>9XEf!^1bF%SkCEb$O-B>9S>N3C-s#X2@P6i)*gkE<@HYTTFA+=QHG` z*+n$Bo1Y=8mME;b%*G7)*yX!5pE;Nz*W4(edER>&viJ}AG>4zckQ2_|sd>*k8FI;` z+?sP`Wyq=5b87ymZ@SFW-mDR_Qo78&d7U2r)m7hR&DM7ai1P7ia(nK@y8LM6G+C~; z8QVG1x6790XXx^M53Bo)bC}rvSyrmNn8(bof}K+3^c`kyhJT*o&)>u$ulYQz%xkjF zD@JC?fn@pQcr$0OJfAG*H8C+{Mx$g|X@b%Jz-`I0Q)x3FqfaEs7e|}<7?YMHTU9i3 zaCK~wEI4tYw(T#^Cdp?XGqI~hWRkq`jEQwsx+Td4lT4g!(J4u8d~L0kU)du`iV4Y@ zrw>Vz$D0}doT;{1R=sN0i};w$a#M&IGZ(jSmWQk8|8f;8@7^L`jttkneP`Gf8T7b` z)y2DRraW3=4nl5n;f&laMbc`{=B}YY^KjUR80HoZ6kB{ z>zVR$nBiXvxbo+CGp}>Cbmgm4js8pHUAaBf%>lwJFRQ+{3TWHb(3K`xh+l0)1Wri-F{6L$K z$fAbp7Hbo7`>yG_yvNU>Ay-~CeDLGYkgOLBH+|!;>S=H)VKes@KC>9D1T_9@jv8`#~A-Z&$_bnw4KoZ#7@Jg_i)Sk zx*YcWm}wYxcE5XpE{FYtn;AyCmbW*I_Ocv)pgjCTJ@6a#!=J1dex^O}KkY=n1nd{~ zc(eHy#;UMngf)hRHMWI4{%yX6xg#tYVa+LF%{5`q$KUeb8LRr)fQ+!lu;#%0(l&7X z+jHR-=8kTAV18+v19M8ZB{0{7HGhRQuQdnel$K%4vEY zHO`i~$@p~bHT}0Tf!zM4Ifgw)ZZf}IYp!YA0(${_O}FQ-Yv*8`;{~te_U6Whgyd=3 z*a6SU7ZNh&&;y!-zLFt}mR8ez{%slZz{0AUo2SZj8IoLTHA}?og>2&$f1-)C`?M=ye&gFSCi}#ygdNr19IqZ8GHQ zdkuB@n$&MpDoO8SkX}9=6&1++1$g5ZDX+G9YhQv%W{76$7l6#=x z&G-Mc{KLF|m4D@mpZ=@y)T~o@2#B z$BL7V6+ay-t~yq{b*wn-Sn=7h;?ia>wYwp`I{HAf(j@4EizG+;wW3LrgZyG19+`x{RH;sE%{Ip}#&Em|jVv!XC zZyGcI9M3u~{nw0VYdx~pM7_pw9k*p}GJZUJjk9HLGCp+<&-MMcGJ)Lwra6W^M{Y8| zJZr9L+X8z5dri0JuV?3Aoa5aeOL7~wdMQ}`RK*F&y~Uk=y+$VZ_R_mtw{tNUT)x!1 zZlCW*Xx`oGJ2$bwTFrBwF6iZ(a9DG}4Hdl&>6bM>*Us_Ib=_?h;=|FjeRLi_FhdirD2cQdzFb@F$6P50xR z+|_=?#|m$A7agr3P(GtzwtHZ4yyj=lz2}aYm#O)!Pri3MojR|1|6O-`ujb9;K)y+x zN?!1!5}KzcIo`%^@7Mg)zK&kLD^)e4?O(R8u6f_#SigMr$yvU9+tLZXo=Md={8fMY zHjnide%|$H&w*Om9_{=g>2;6x_dmH;_bF^c`Rt$vGQp7VcDaZPhMv^3!!KIs8C*_=kGnH|mE!Sugxd zd*FZCiGHE|c0Zn5y2b6^p{78eE>qudEiOA*^Fzztb^p@d)%@6=@7!k(f2KKOc0up0 z1$i9E-+i>A7gnRB=E?&dZ`G>unisC_=)JVDnr5`?k$g2Y-+wyRFF*OyEMGq2i3DFy z;iwJ1{%*IWc&vBnUtEv&w1~_0Xy>+kdp+7er-_+^unpz!RIHH+hJ3Csi@IRw>CttB zX6Wy-c8zA#8++Gb&9G-`y~~`=jCM5~nO`&7%X0XE^6(G!z;DzK zf3jZqnfAc{v=jY8`#IOfeLr5XAHnQjF#8?M@c`yH0dxF-Ij+DQZ(xo?FvlmD;}*>E z4CXiobNqujFTk8HV9p~j=NHQ{?N{9P1Jxh{jbUW2)ggV8Rm?_jR`VCDn5Jdh`VnLmJ;SAdysfSHGYnV*2|eq_uc|F%!&~2}ZjRGr^3RV8%=^V+iX3PXLW`Y?r!Hk(KN6eu- zViA}z6U>+iX3PXLW`Y?r!Hk(;vbY9W5zjrx#q2`Y__VPWBJ!r9`u;^O0@ylyAwh?2Keb+*fBPxP24>L}j(ezaG;^a638;&V^Mcyn_t z5}zsg$VD;U>ARMQc*Xan#CV0eEEQ7m6TSL-e;K}1wE3p06Zd9}S3buwaj92T=X`X8 zS1b2SU0%6KgjcxiEOA4XPtM!l`+mn#@uc$M_UlT|u_dCX;+<{#dy8INB04BNyT6R_ zj#pVC2B`A-E&F>bD=rZoRe7P{{@&^-i$!O}#}CJN%kwQ3FDjWEdtpv|N)0BMZ))?=x@=JuHWVZYi<9&C0q3ES# zny-xUa?f8Z+N$!W&ct|q9$P4StMV27W4!&B7l=jb+4siAc)O=962p|tw1gOMbnOMA zuaX(_fU@DM`C_G#sSp+8)hoD2yrg8p#>9B-Hq00OluTab&x`TO236i9JjRoi=Zgqc zzVKAESN{8XVx4;S*`hIC@XQ5brIHzbBih?oX`YBwGV^1jy(@+0iS4KNRhqUp8NCR^>I9MSD5a`}=ryRmEtpVEwsbt$Ox@vC&>tcb?d; zWRA6u_C9%Po=8(%r+&28tm7PQPkS%QyF6%)SfS(#UXSu-emz^;A6_Zi8*_H9NLBJr zWk-3RO_{CR-s#CGFVFVbV!o2Ux+ltOUS_UHQZnDoi1Olh&Jn8>-)Ir#l{`L6`!nNM zr1wn8*M&2iS!1no2kb}j$;wtcZFt&NF_gDM5MR8_G}TQWUl-W z;f)_SQ-mv>mw$@zifo-F9#Q4{+z9Wf(X&J?#m8Gkc=sf$ajTx)_I0S&sM@PKRxIBV z>UG~aS;vZ$N}=BAqh{~({FXM}M=Rs?{OUcetyeo@lAd3WywuL?Gi;)sUq8Ik-rIFF zPS3B0XM}lMCdKLbH8i1vcVT{#cd!#KxZ*w)4sjjn(CQ2DSI5W=_!Db#s_kdZ^)qs~x-#XBqBOucP-t zc_ZIqRY$Mnqj7rv&RVW=e)VoU=Jn_Ag?ewt#Ov}3A#J>Y4^P(fI&o=7uk~#c^}K$t zZbxs-hB!U1=P3T>i&#Cc_k9rV)qFNi&+DYz9law*WA(gVm>KTvSsSbS?rdndH=<^o zp4USft7mIY)bqOOXW`!V@01T!A9b%3?k$Xr)$=-YcL(qNUt;yV-n28^tMg%;p4XF3 zcJNBIjn(tI{R`pVf%G^%uOFD!!4nU~>T#H}UI*{=r?GloZ~nG}xANsUJ+EKA8s_b- z8>`3mlEg5t*!fsJuQzY%;GGx}r|0#C^{TvntezLWVmf$j`o!sZy`+1XcS6MKc~rV^ zn78dlte)37KMM0Mb&k{X`qb|BUaqHO_1qlva(iz^?KnNJt1S-mR(Frn^LqUA?Y-$^ zj7-N4VP2oeI6be^Yqs|uO)%wyzisDTd@fGU>jDScdlM(e>3RK^xb|N4)p2@WcUaKQ z>-&STXX?Oq-p1o`dR|{_*Ur16Mx3_4L$mf?uYGZPUhmA`&da6hLQLCyzO6U3^+Y|d zEAD9LJzi>}p4SVb>rK5{lAFQ{`@JXt@p;UiF#i5745u(FHY3+de1{` zy_m)m^}Jqwqm6fc(nLM4FMQR;J1}CBp4U%jwe{qW6ZO14H=(U}Oit4CdgDuNyeFJV zdTe|ZTy8KaiQ3vZX)@v}zC5J?9phi$W_B%3{`P^L69#0aAKsF zubi>r$Egusjh74`p4iVDz1#37qxyRJ&KSO#4^M22@ls?lXNJlRYP=BR)hJ)wsc@TG z>(%=B^UuYd`HEw_Xz%o2N;qFAuGb*in-W*jsgP5}_E}Nh&RV6M28t`3iu6{wrF8jg zg(JQ2+Cf^rxXLAZPYBX_-U#pKb?}0;{uYD#dRfPUbiH-I?c+@zTiSV2jp1@X_VH$1 z407_RxKTPW%Bygrl#`~)2j`CVqLK`U{Uyrl-@lZTFSDvs^6@AyZ+t1Ic%Q1y$llT3 ziZCPd{E8^=lKR@Glq$db`zWv7<&s+FzNgigIbKxP)mP;t@du0Qy7qkE$Ln0Fw9`S2 zw=F~adSewoqqzIwfp*c51kBh<|>))wIjUEjY~UGO2%s&;q`wj$T_TJMtAAw-FY;~ zNmeqS4T$i{R4(nrD49{S`+0Bf4RT&r<@?q}c+VCt?F>-mAMT0p>aPuQPOE3@fMe6OCJa4y0-)g{QOr(_o29_5YgALKl%WQydC z^6IEQy`f|p+@tb=WHcVMdI`h*pNaP3GD~Xx(W%ki$KRIJI;Vda?fsBl zQrl2jjpsUQuEEZE)ndFKx|G!R2i+Fq?Yvq-x4pNTcX4w{>bfFY#dvuumDFv2A|~2P zj4Y|`={7LNyKuRL_FE1aDxJY4 zwEv&Z*WU}DT3nBxGy7t^9*v9ZvG=K(wa0Up(0w?8dUOT9?hv^g*U6BcYF1mI)-$~SJ7KP z=r$c&G8R?vMla8yV@{Wr6}-=<-VlgU>81W3WA7al#qz!X17^iU5X49_=XBMb#he92 zQB0U4V$Ng?WMmO`7ceXsh^DK=-F*z#oUS=5Sw+mE0wVb9KC{=KRp0Vc@BdD9o$2Z6 zK7Ho3J>Ab*!}dy*z;o1zy4JW*QAy=-&8=~u<9C7QG&|=1&%APh=eprB*65J>P2f3j zMJ*dVYV=j$x$*aR#Gl?HL4G#qtE@q7?t8%+5AGU}J-wYZ`c>$Y-7nD!mm7$7ld)E) zZmdV;9h+J~X;Mw^CZXCAORFo%e%-_hHC|PaJ!-TST0JTwd*uNuEPwiy?Ddw`IP|@g z>A_NKWR`yscrGohw!#3bZ^Vj0_pQ-l_E&-D(grWBfaq@m&!u@**4S%b zCh%N(VxKh{b^j*tT)IhZ1$l6pz;mfXl@%8DD;Ib!)$_N;y!yRmv&WJ;ksYBz;kI@t`&}1R|q_p8jZ3>*iR&srpPfV{MIYj(U_!@4m9a_EbH}rM{D_@$;-6<&DnK&luN%&x5oAeeafY~ zE?T2Wj6UVke$4-6vL5BqNgmeNa#^2psVv?a19J5!m-@397*(xLxpaI38w_DKkB!vF zEDlHMQ!X7-VhyXs29!%PrrKcZYy--r)5@)pu|=P9={X}CG>kT&T$*WagHEaXluL^R z8w6f9pj_&iWCQzb1InfIXWKwk-+*#yeT5B5Y-&(09iwLp^F}o&m&R^s0XH&A> zy;UgP^ohO^-~AtL491&)F!JwK5d^^^lvop~1*`wNv=F%~s(}hChzwgbJrv z`H{Q+Xx%4NXryFo%Q5~aydEN4VLl7og0Xl>xKM+Yn-2&^?WCPT4`y4p3r0h|aADAd zZ9-GSV3Z{96qYi3f-BdE$C;1QZWu!d0&@;SIAlgaqN=2cd$D`TwX6!bamT;T7|5 zmKTIx=R<`z%zif~2)k;83FZ^G3032Q;4(i{IKcc@oC(60Euq2(=JRE65VCHB3LTlx zO3NVJ*%K=K#q5FggRsmXR5-@`E4+j7;!B9|h4~M23Bm|I+JAwoLyFC7?!dOJdda^_QbIuJ)YgbMb|CtzP7HX4Qs3&hv0A;L-KpZp~d zEjot?-?{fqhA{u-l0ejFaht;YHy#c|!K+~MacATH@KK1+ zkNF%h3xx7ch|q!Ai@ydS(S%^01_?-(-;lv%IcJc z3X7Oer{)1rPG}@~%vG+%a(2@Bs{^Sq)9ic)qR&H+>fNhn*LLsXk&;8LhK2-S5 zV%6Is0I}>FH;=}>!5xzV`xX0`-=lt!Bv;PfK zp|-uAG^zP^;ccc0M+zCwSZo*G+*aYFMU^m+*|(plux3;xm4CRSLdDt&f%})JRR~Wg z6L>vKB30P*=BvQ#Z{VWB*Rfv&e&65o+n;ja1QQj8j}Y6uf4vF^wi;0TEiSTp67|Ur zt`mn#*?MH3`6~{?xBR3W6*eUf9bBu(t}{0d8z)qfJw3}-%%=y7!;Z6m3YVBqvu7;E8Zp*lKC>UI zuzHuCvgVpKkQ7z=N@<(q}fMvDd%dSnUQo$2H zg+9z@-+dJ#qN;=s%x6HE3V-#i61Fj)R2E|=hyE1$F`pVG}?JN1ua*EnddRZ<%|-#HZm?|=Pnakx0PlG?9&s>0=!6$0=75O!_mmGAWIO&_Y@SWzzUv3vSX1*;Y1 z0w3SL9pmusQiZ_#u=FaM%T3A!9s?uTz3O_G2|Rvg+Qz|uRE5C%f5|x&X74Q%c>FAC z%lhY1xxmLRpXG#^oy!Csdxx&8uq^VMz~i%*aU6PFEfaVQd`wWG%eZd>kKu+HY+R0h z6?puAuOElv@nr&!pOD>bzC8ab@c2KWABP*az6m_``i84uw&ttA=Z>8Dc-;CT@Hth< z#`?;$uL6(Z^Xu5P`@XRM6Jq`2rNUnJdyvn~UF=zUF8V6)_&>T(h3db)2z;Jevz)g4 z!xw?iouO%LOzV9S_*}bpK!wEEQp)pFW~$JYXItkv+KFJ29m6NAkU z^F`-Jk(5t<=d^{Jx8v~Xom3tgxE0|M5oG^~-?IMRibkQ4RKH!yb_5&|nefe_t;qYn zOSq$8?}FXiQQk&IcJ&88yt-{pxp8ulA6(7N>0K}<*AK_9n9)1p_xFX=O^$t+45{4n zNeGHg8ULT}k%;OL3^;8<^;hnfW45{>+4qV<;8NE_%G>kaLyq1J8MKsyX7kQ#} zSuEMT^F6SaeQ)LaTTDVcQ0l27yX{I3{97JJ_MgV9TQ^^v3sMlHUR>n^!yQUu)Qhp+ z=y55U7b%B}V-@&I{x8_Yk9wd*X?x7ki0O>&ZNEwpc}sYP87{LEYntQHM_Q zh1=UG;?juOp6r`@JaMUUXHQ&g8&6#N>WT-NoR23iHFx#JhS~~Z+J8Iw;?xoav8ZDk zU(~CT6QkBK^u;xmg1A(E#s@VwDu_#GH}u7*sdD1dOL0E1Ypote*-0Pspg>% zMnuYqF?uZV!G?uO;?gGFebD!qlDKr^eQ#WgR}z;NP4Phi`yR@9t~rOYhY5Mwn>~aq0Jk z-ng_}NnF~Zt2dmlDTzz-^}KQBN(^ynexetAi(`mO+m?A@b@ymuzxVgNkkB)hxU_z% z7l!POB`%Gc?1cqaV~I;UM0nvr%^2cR$9Z0OzafU0v(IcVq#iAytk zd!fl2(Pz5E3r#=oCN6zt;f1=(_7ImYxa^6_<9mopP4YZ3EjO09)JE-zMzeQQ+vetb z;@brsrh10^wsVoF8yno zC)$_nAujzccp`7@UgFZ7p`Lg!TSZ)2IGo+OFVID!5a^>OHxtHtSj_D zFa0>;(!%>52u+J4F1>Ke1LqsX6PI3{>x)^@a{6t>=lis&O)0nVJiu+92Y7zqHlMTa zd^|B?un{q8$O%uR*%}k0Zmj8r!3HM8s7Ka$!T+`iF>23hFIb10N;#wI@At-ue$Awu zQ4i1Zfy4P`R9@TE7Y+KEk^lLvzVHZU>)VV=hkx}&k27Xezu@Wz?R_)4@9%l?Pq|dF z*#kY78Bv@6KIsAZdSkL%8nba1jxPt>_4o7*Cd8V;lt^VEbGH6hRwtNl!fQGIrJ;hCW+F{s&`hq8R zl$sEu23+&PNjFm|XVkLuUKn%6RLU7|`72KpbTTDIt^VkRgtXB7R{ubQO#F-WAv(KQqHJ1e7vx@ z(p1VBb-BVD_lGr;az>q);)RmV&7_=Bx3c`))>XXr{=eQhuNCW`&vLI(U^6La)Vr2G zIQVxnYJ+KSAM~!lz74VZ^Ll$jc2e|tJ;?{R?=++Ke`C3N&~vf8+Ya`A`P_`2UD)G; z1w+lKe-2#phIwZ*YD4u~ADm`3XVk|vePQEnM*VNB&)zi?%&7f6oBHDN2s7&c>wo#c zb&VN4`_wMJD0eZVv0Eke#qbm}8sD2qKF~jIMtyj9fiJQH%_s&UHu)mrjv2+zhXNl= zy>3SRZ|>_0>25QMpPG$*k<8`@XVjEEzPO!gMzQzhgfE_bHlz4lK91!FQ*(-eT@QR= ze94Src-#kHl-4(=`0vHu(NjB`Q~ca7^+oz^Gm8K5LB5zPF{juY+|&;fo|w_x8QsMX z2QAELPEEP&i#pTIDTbGg_rsJIW;E~iE%U=^OLLl=-HUzMzAtl%e-oCY(qEa;Jnd80 z51&?;)7*(2?T3;r<}}w{EcJt@r#a0>{X{<)wKb>t{=YET|B|2ggeAb|;$vdbzg8u{ zugeo+-97CS@UZ1m;;YMH5qNfM4cQCsN1(^YRpfKIGy*!H{zxek6jrMf$G0!5RY~48G(LJW)qK1u#143 z-U8w=`P>L->n|Z5d#8v%S&l35SpL}v+%#T6JobBg{?z6wqX^u}n@H`s@JNQu^QMs9 zB}0a^<}=7{dRT@BZ)TI-TqDC+^#ZaJ3S{W8bg5`tM&R5dH?m_VN1)5HRb=nqAAv#t zOeDr@#GXAZbOQ0=#Eud8Ts}*v$9|94cZk3f^ErYMvoGh!@bTd+!HY52?Jg16)_St2e~}Y0=h#6J zu#Ipe=6o_e0^@f~A?94zI|9uHO(o`B*`38k>?Gm`lL-;{xP2-yr*Z_VC%~DQvo-6h z*y+=VId2+AAXwu>%xO|L0@rU(A)X2B7Xiqp6LStXi9oXV41qJ}nJO8A-b^Lttn3ki z0dX^kIcL0+!LY-0V#^7yWN1Bh2C-#-!w58fJ4;AszgZqNj(~&XJRy_+eld@LzH|X` zpjY1r6dNxf_UkG{K+$R;v7Z$immhN$5&QLfE5mfJ1;l&4_7Tu@SWLX9X8!3Lmk6Bq zd`e{q*|(5*ulckH?C7|Jc<&n<_oQ}9iT5I=M!?y78S&oC+7YOFxR`kFMbilQd{{!f zx6&s9drVx3_qK0{K*RORiT7@`jzFCn%cy_!!r6G$Tu!{#H6{Wz6w8VC>V`x>zR!(# zFaKx+{7<+M?`5%e9%;FpcyE!K)h}H^ymy#Ai=mYpjn^60=JsdYi1+5LX7l3f3gW#I z&j|DkTS>gv=w>SZO%?NiZ*VH&j)?hT>55cf$P=3HzvqhdfCS_xKBKuX`bz?Ketk~% zN7qEy8|0Eb{BT<+SCw2{_p7DXm+E2#GN5`;68zZ|qM*YOCk8&RMHT5(Zy? zPV1jFwkF}IkVEUDd%h*%U)LO3FI6p1#+Aup`GcHf)c!8|*LO(4z`BQ+MVF3T6*ZOM-cF zu5gUa{ji?Nm>DAagndau-RxZ9I4e*2nuJR=a)lWz&dd5F<8r#_Z#gy<5`(97FMY36 zY1l$dHO6w;p9w%UR&!@CzQvD$T`@Nsi8q1om3Fv9_jMibS z+azLI<7c!!v#ot1YM*>YYdcwqY}^|?qgXxoS0dDtp3&OQ=raj;H~$%}w`5IBMA|M^ z4|}e%nTfdE`#G&0DN7UJuJ>Hv>oc3TC!%-V=d`}GZC4`R9(qn|Q^Oi1;^CO*w6@b! zl?b_%*^E7Qc1(nC_;XqpvQQ_&Vbyb5*Lr?65wGj!(Aro2yhN;QoI~qN&Yu$DbLly) zk7;Wrq0g)wT3fsCors-da%gSJygCefTC#5vCd|p9wZU@J zB$Rf`rFFRzPAtaUa%mlJ@%kk8jV71Y`XaNEATP}kmb08w&?^}Sev0<1Rms@*TC6|B zEg6v;#X4UGCBuBN*aok|$*?;ow$tW(GSFXa|CHind}Oi2*A=^NNXD#v;=R7*C8M%M z4n4b-JQ=Q`VtWFrk}^EEM6m%ah_HE!j7XLHF_FwFq0@I^n|L>obf(>uQv3pgT zjC6_k?DHH`aNbWGJ3ZqRG%?Smev5HSLAs+j?tW1zknRv;W5C1|)H^Tse`b6N6fed2 z*>p7p292Ln?2TNRf=iL&*oA6Ra4=Pjy_X>=SjYOAuPZ*j$J)F?j9W={3haW#c+R|# zf}15`{G``P#kUt?%=>mv#qu(7Ufj!1L0pO$d%atwV&YzLj?At~foicBw;{b!vFNTC z=Pk#lV*GY-F8pvwMQ!J&G}pShM_9=QHY4Q{(m^?Lgg;Bln$Zt z0d=F`l-}$A~G3u}edBMo-B^%R1tE-JjkI2cKu)a~mbq-{Iol zIJa0$_K6pN16nn;p|)No`p#F9?dTcJzHge4Pv33Puv=(M?O7ceja%EA(0xaKQ= z6Jp4O)k<90YC;Stf3HB7^`^v-eb*__rmh(=q*7mj%)gowL(beIN0ZVP#E?}Z9Jd%9J=&$C!98k@cI&M`Pl>hxe4|_Su+t zuif8D%rY}3-rLLk6ZSME-t&%7;%+k&;yt#8hn(D$kP}T@A(BOk$tf#@t*l2CAz+CO794ZhDuD#Ga=r4SE#__2`0pQ zuLmn3v@#;z%YLgs)2^n(dzsf27`ok*))+1KD^R1cDXlRstWcmd-iSER_JIN(UyXBRA8QyF>#&KDh1wLYDQ~}c8&`4A8kf!jOjKCbT%}j zHO3mur(PcuT4PMGSKx4(39T_Yn6djVG^aI2*AhAAjxZ;-eAz_-r@^M=6I3b3CB5dv znS1i&=zpj=ab_%whkpB;6KCFkC&%cG&1j8r_f0uU+OW7~@ASn-_;uN7>hi8)t0%5e=Xi8*(=%TYMFIWcFixpEA) zv>@hOGf9rEwylXdcej(naC2*7&ccy${QJ#<#%P3{9P!nyi8+__l4C_c8)8oPMsjSI zw;|?y-$D+fxVFTc;bw9;uz2R*zMY%OalN}GG3Rc5Ig$^xqL?}UB?`L+wkGD3Jd1*{ zTN`4|^jlE~tlO5DbD4D(J3B9>xzNox3ze@2Q63m;n1ygFF(3Y(qrUgiVB`8Za24_D^CA*}R1}iR1BHQbe8V@cwkiGY$8Z~Q;Bim?^8h7NQ$X3)*W0C)G zvfJ#<#)-lqWXHG9#!)#zC=nV2(RlN#UGOeE$s7^+5>9`?kX+Nx{>_Zv&)u7|VX95IUg>rTwZhH)dP zp74?^TwFDb>i^-Dg>LnR(tV4Mstj3x-&cufe8)@Jq%p^XnVDGXXp3cOFh3s1U0W*jX&t<6* zBAZHl`01t^QTYBk^IIST(XL zCJ-OKdZ)(3fs=_3gM8HRpE8m7@Mn=4u|p;iA8uHuhPl@S`tEG)tHx6)i($rZmF!ub zPMb*FxMCW!AKKIR>pt_8*0z)5>HD?0nHnzV#!?#!Ez}shX$-aBFi4FW_s5Y>NKG|% z*B?vmKg;6zROMJI@AN4fHqK+{*(;eHS8p`+Pp?TV=BJIJHZ-}MjVpSisSn>?$i}#n zBdP!O?9_M`KAPIU_(V4BW{;x&f7L;at=C7^i7WK@AcI+^U&-pRgFwqX97K|-&c=L;Ar${te6#TE{1BR_tv+X=X6j&?J2Nw~(CNh>nrr#WEHn-uMDy{b z1Iw!}gK571FAVm-Ce&q&3Yv!b24ITeAu^T?;8CKac9=F_!DYNldyMIP;4w?3GH zqgDB|r+t$o1<$V*&|dd@*OTGnQb>E?m(EB=qZ5U+H-7HRB-FT2NPFgAtxZC!D6!na zAPJqVM1NC7B8IFJ>-p9r5o}`f+P%lEZW7hl5i?sv@@S1;zt|NzV5=><}B8; zxi|rl;>Rvzt{cQ}v$gEzUfXa4blB=oBDg7(126(-@exo9_j zk%W6oifGUL($plh%`2q+@Zr|U(3*)pwOJo7`&dYO=C8I*hSLYp$B3=TJaWmWd)f78 z)z6&%BzgMGUP`NPFgOJ11h((R|u7KXy$b z1|KM-J@b{r60zWYKJA%bu`?0d9v9M{`6z87&Mz*cJ@dk*M0{LOKzrsZt|X#*KoRYk z|ME2vchrTnXI>tWh}AI#v}b-oF>AxZBHAZ#yCh4=)$dp857{ZEabvBHGhlRh@`)V+(1|e8|EioX9Vt{q0>_ zBq4T1A?=x;$krcLCKl43`Ce<1F!od-?PFh%l!THgMYK=;g=I1l7m0S%>}1?<6zg|h zkc{I7FR0Gu+mfOGS!_dIEL)H2T14%%{U;fd&x!5#c#w>m72>n6oXOTPo{9IGm7k2Y zhs0-BZBE9>8)ADV>7`)YHnHC%aq}aFe6UmsmUu^#bX$lsz=jCS>HjGVy`5bZV zM%_%tQ-AT|cm+ySp?6v*+bgoVRa~iX|5LG#BczwTMfP#kpqTAVbYf<0-eySIVI6?LfJ-dzK8B zzdKOA{XIWhHFju6l6;k9IlbaN3#voj;I)8QC%XCC>Sei@DWN2Hwg3h74Y?R@iW&)i<*E-8! zY41qq(5H8lpvTN@jpGxP@XU&kY{h5>L9QxHFHm1#{ zQmk$oCqr;+Cpw3&|AbvDb*6LEpT379_~kS@hrYHKd&bsN=^T2?E8)1!zSr=x*!$my zBh+jrokK5aFT+Y}XF7-8)VlU!|~B73DbO!uUD;cU=E}}EwZr{SOyl^R<0e{TK zbc&uUyr8D3YddgtjWeJ@Dugl7XZcFJ5xJ^6Ox1HQ*T-MBC%(K;v&Va8U zD?@zmWpoDItv`#&9xG^GuUyKmwOUSRz$a{xp_7ptodG}X&+fZyC7l5uZl{HT(uL+r zpSF-!}U_8G~ zLO!$q%Eq=q1F1dEqq6bX^)I^D%eZV@Tp|z?Dh=6hpDR*g!s%<+@A`d%hzX@P)F^v8 zgqYB=wFdh(4JRf{n6JT=#iNJ`!=p8b+&h-a*PqtlOnnFPulZ1ee|9@kJ#TU}sB1Tc z>VNb=1B2XYbl=~{>rZ2vbuAmyH}th-@Hnzk2h1c+d&Amark+8Zw#_RWiYWuAJbHOHW<^P;JgHQJChuktzd2TG@YrxVy{Fc8 z(qj1F>GW=z-c5@=L#9#8pQx$D#P-hgzPsK_i{(S6()@Z@TZ^}>-}srwe)$@FD49m@ ztXaLa2pl|x^3shWR=?gfdavDK*M<&qqWAALR%g4ZlZoGoi#4d(X{vbUk=<8eH;MQy zhP7?|Do5hCm9I6(l}@2|XfkW(&_RyG0H4^k`yHL={d>t)i?%~15w>j zID+cG;;w;PjnTqd<|ALHLEErl)P{jl4Z>1}QTxvcfG>YFK_4O#L6*P6PRn z;nea z6ra1o*;-%TAc}!84r*-5lTZwIYpurV6oKM@4qx}1Hi+UUtEU=TR|&=c-q~stKeVIR zJ8GiFrym1p?s&gsYZUnsno|Lt)o?74QVcsh&c?d|18Lq3K9Y?Y{UtOvM>JK#%3DhD zUr&<_qZb2cp6>dVjUmmYGf_QJ(X(cRe8W8U#Y*)fdzX9=H@kS-CM%N?W zyE;vY@jvPl?>(KPM6seC@!sqKO0?QnkGLYEu@avw8W8WDV&7$Ye{Mj$H+_i`n_e{_ z-n+uSmDt>^N4z)biUPh%8W8VwnWThYaRcJLXP4NwkDv7@uI_bHLR;E^c#nTiaUD=! zNItc#*!P;ehNL^x!e5T&XT|bU?0d(V{f$X?sAZuX0hbz) z?$DO=ax@#)Sm1hM8usn)zIkJ6k93F}W4<;awk&Qh$H{*iQ~OUJl4H-a#-uwmqP`s4 zBAd{&H(~a&jYht8r7(9h$_xxwOzWCFXRv69u;cM%16OM^SKWWJ1ho*H4bX zwMN987qg<^V{A;!c}x|BDL;&9UfZNZq5Bb7D>}mndxA z)0~*|e_^WsW$s6|3HhZz*6MNaFI}?8?BHK|W$DY~erXU53W@urO_Y8+?w4lK%UW^2 zG%=pC^E>}(Wz^8Berag@?!V769usuB5X!mnsISwD=&&;$xerAhiRa1j(0e87OW2)^ zhpJlCop`{?-|F-z)`rEys)?vm@qTtZ9_aKd7PpB+~+puZe@XQq;lt z({p7Ui^CJ0w#L;Lapa;Sx_haqX>1kZN z8wagUm*crI4tI3A9Kki>ex2VR+ba$hI!%CY6XI}GrvtETNgUqlbOULVZgm_2`-^%7|9pueC78BmbK|e**i;%H+ zexlR0X!M=UFP+xJ-;Lt2NvBN_Y!;8$SW&-X_^^0f(dlFOvig_nbTbA_jmKA=7RSl0 z@mQ(T->ApzsUD(UN5SNHjIJYUdQA6*Fy+r!f*aG#)uR9g_R(8MQjCkB5unQKr)>xyZ@`bUG*PSbQGP>4XHc zXFsjeIoZ@X9)`z7jgekc;*p`#NU36do1xQDY0KvOcb!(rl0osftJ7MsuOE-SuA)wh z7wfAlI-Qdrz2Y%er_)lz`t!I>BPE>8>s>mHmuny5uv(}6@`UyOG@aJUsXFoKr_+ZC zV>xi4PD5q|^IxFTX_;Hb^!asqGA1lmEp!?$$(Q2LR;LNGJB#Hdoo-C>G4}rgI$fHQ z)BeA-XImce|D{Q5#`Gor)2dx+$IjYY2NFBAIv0RXNdd%8%CUjiz9WFxY0>RKn5mi0 zp+3{waSFn{k%7cc@i&9erF{^w)APYhSHUTm*r~a1FdTca{~%zRLciz#KfNOacE0{U zjmLeN0l%~#&rA>er3q0!+Escx;)kTm}8kNz_PiP;j42gA%bgqSVBKNzi61rxLVhz^G8Y!ETq^hLp# z`6Gy!%{?F(`*#Epv$-w{#!6dJ53smXFnW&=7?ZownO!qPrE>3wn;sMA^i|U%x3yJ2u9CDZNr~Og0P%v zQSN4W(!V^2^?wjC+wlWIh;=L*dFf!k+D(qc_3lhAmyS~#weAoO4O6SMg_1;VhmsC9YeB&*Xy)QYU?8i)bCM4imKbpnxG;!n(0 zYgHh=&j}!AlaCL?))@iBZ2j|D%nuW_H>aKnfT~UaF0*Kirw+}#v=l;ZOmuCe)&2(A02JAIS0KQfP5VKwR;E&gDnD!|f$B*xQe`zqT zXJ=LZ(`F2=^8KaR_&Z0fn5_7vW0T3w_Wq}D^C!LE7&P z`0L+n-}*}j`%gJ)Qj@K}^scv0 z-u_DmduNxezx1w6Hf_g$I@sBJw*1n}Jm%z1HfeDuiZ=f?{d-?E-{6btTv0=E`ZFKQ z*J(?(ec+8+I?c(}&%E%gmFQFQnVn6G7BwncwDH8(FFNhYg&x?^N3=U$a>rVo)}=7o z9Sv5BnnDpJTd-HBjj24o1simlnSUD7Ywo@{t<#XKUB?#=I&Dc!XCFA}G$$=4dt;bR zi&7Qng)ptCQF-nbJ0Ggkt_<()iA_39%UOvYxT({+G#$v!R_in{lU}>C?@gjM=Fd!b zWau@;SRY@bMLmdJ4(-rx_oQvRsUxAQ={P7Co=V-L996!ivImbv4ePA~EJ0uQ9< zv=&R4{}r89;XHE>e6|s_7GDqYfRj$=u)D+qc{-g&6&oWnoqpqxO&&O=(@X5_?}6t! zjmK%9*?l#l4rGYj12c76i_?#K;F3-gGBDi(AL@uYjeQ?^pbtBj%GU{_hk3%B=}Gc+ zLeK9W2wo!UJ$~%riE)1BQoc^uYPTl>UCpI@op1q*^A$R+NX+rXt;3>E&Ioo+`7Arr z$JPMburr~u2V(hwa!-t8+LgTiRZ36nVfW(egbTj1v!6E2sSSr`dcoqSsFS(jA5ZLM zTBh8mRVOc0j23k=KfY(`9_-v4FSnY@&fe-YHsj8D;f_v+v+j5=Txad!ZP48GfvT0c*7L@QOQOza=cDW#=sQt+Gh&!Ge&mZ9p(QGBv`-RsM9-Ue zqp-cG)oGyd#xkAOXcJ=}%+u+VhL7>aV4coqQJFWI>U2tn`gr4Cokr-IzCK9OX`G%7 z^g)(R2es)tZ_L+ejY?1WV4Jh3mD)?s7nKb}oz;4_KA5f3DRuhf1FcSHRpsJ?HSBr0 zF5d!kcJ5NA(RxzwWqLTGcI)(8KDc^O)Jp9?%@;#;`mRx1eBr6nfbCk#7X~_=)j^wm zaX_aB>ulu~Lh*NR^wRymfOa-Jhg-dim@~4bI|_9FNAO7L zjy(B3V$O-Zd{Df17cu9{f4uRmco#8ew7)k#IqxFo3|`|6-%gRloNs1&QxwdJq9^TPM!NMg=8pS|HVERvYB>j7`r`$iIT#)o;qcuXWQ=Q?)oe(k_0Vos^2 zH{#+Wi8&wId*PHKl9;oLz{;OT5_9r%*#>V#o%~imJmFdxMa;RM%|Xe$C}Pg&NLHR8 zYVS7>_r!r%IWean8?T`$QN)}TGuYYlx^h})8#}=ZqrbB@u=qJ|<%t1nMV^%4r zrbog5cc6ZuC(C=R9_I5d%L6l<#QzT1&$KlXhKv6@;B(9qhCk)RoOc2}V0cCJnd`|k z8RjWyo$&2+4>TSj{%1kzIuE4wi6-W})7lfKx{CihU|#Bh7ct`h4(zJQa`Gtge-PX| zd7!Xk3^C_`Tz4$JBK~i}&dVN%GmNHn!W8yiXf{dw&jpJTcYN&;OUyaWi)kr*i6-V; zJktZa++v71mw36udAayM4hu8fp&hWBn6op>|A$Iqh&i_`aK}2Pg~I=L;MzEM90}S@ z%&7`>$4|#S#GK<;JLNB9i8;@|b!YnXyNNkZ*t#R-r1+l{b5^+{Zs}fP&dCqmA$h-> zm^01H9T!LLCFZ=4?v69%dx$wrlHJkJcP}yLJQwy(3}pYK!N%f$VXFUS?l(d<9_AKH zxK>Q3jBNaz_(sCDBR(9;#JPFq-Z17!)MqgG*xK?55 z=xB_Y?GDgDn5*PPTqL=4b3D-;XG>AoXPPl~YC3e0O14X$^ z!u1kAe2T%&B~cQtmpEje5*_2mNNTY1!z+~-CQOoWy~K~fN(3x+lyJSoMXV2pcu$dV zy~J&PN^DJ-A>n$7KI~b>1y7c6y~NH*N-W&rBH?<82V&Uwh5Pd*Trcqi`<`;X+F8Q2 z?>4Y+DAU%?lkhVmRcDouJ1mlLy~N@SB`%+Km2ka8hxtl8(ae=_U791S*tZgW=ELla zJSD1cx=FZRVzny+lX7 zXr%AnBH?<857{@Jmh;v~xL)G+6G{x8xE$63erCjp z-D`w?u!QR+o@g3_>Zd^xu9w)hdkikW2$pcYMEAilXyqLy;d+UI*Q0SdF;v3!67Rl= z#>D4g60Vo{ba@OKp9z(4y+j}17Yuii;xWD*jChv8uou9q0PF9zCL zJ0)B%u{F$U|N?38f5#0vWuWE(_C_?eM9Phwy(AY8)r62GpB!M&mg zikWshSlbrul5oAmw#Q=-K0Z>y^%7rPh(XZFND0?V%xroJLGf8M7iOdZSBUBb?unJ)}ST-$uo2vQH#x zG4@sw+3)KEpG|YgcAE=K@_$73%>)3$Zj-Hf1_Z9YLiTOFQ>fMbEZKj`fv0+^v2M?6 z3D;L_nW)CH@vkLZckzye21_emNx0TcaIglgkGzm@oyHHP8VG9&BwRBm*-4946LKV6 zGbbiR3(qN!seIKJE!^YplD|<;uzejjsGh}hfa=JLRKKG)kmG%t?ki#6g(rS|E#bO| ze($rfRrX%ObrBE9fZCrlRKEQQ;Oe8L^1n*iKKWB`BwRnuvxk~}&w3-_nrs``v-Iy$ zBH=o0?I);ls7Hx}>$bgLp~joiHxjPxwj)@LzI93@T=Pwu%Fa6^ypeFdxUz0)e7yah z;;MC$8Yz!oOSoR#SXR%I2k#|Z!)@;cH7@ObE#YU1TeAHCM@`>IxE|f>aQ3Y{`Mrdn zDYnvMdn!H@OSop8)JB7~LrWxF@6PhL8tXT|mvFtfX00@c_bZn0GsVI!cJ8L{dkNQ? zyTbM!e5z3_;aYhU*}jF|-Cj$$p5DjC8ob`}PQuTYj#{gM;ggpVerBX@j0Sd3UP<`5 z+6~=V{208GaJ{?gFb&#wdnw_1eJ33>*uLehgr6yPNM?IT*1eE$9Tiiy4`G>->pQIPvW!nJ5#tk&ZF&gXRPu2?O+ zlb%!khO4v~6LYsg-tV<|*7ycbAkz}xD3)c*}$Y0;+m z8MS{$r549Z?^6FC_`&*Q=~H@kTSH*ivO6?(NBaOhFW#o{9bpSJ8}W$x@Lne%dEiZo z0o5eH*7aYCpW*$1ZTlZk|378+C&dklpIKvpO<(WP*j0`IF1)!$v3K7M81&&P#pgfE zfyv&tDF!yU0205;6vJJ%0Tt6PQT*5T0G6fSr1-hGgw_AgMT&oiAYeh!4T`|gr@Av}Vu4if99XJ4V|9qO}rpZwtc;sb@f13bcOzdfz zr*>ID*^G-ccP3o{Ua$X$=31{?z+R6tG#|Gd0b)C7X}T7BcMa2UpFh1vy8CPJcbgCmuRouS^{~G?QTv~+1{z-NKyB!fs==s? z5DjnJU&ZXauwA*D`_H?l#7kE_4R6oELu}7XP<^^rz!oKLH+!MxjB3(c3B9K`)SOWt zu>BReT~4Ywqh1MCp!|qj%^5X)t^zL%-PD{>XN+U}Sn70Ab4E2`c2TW=vpJ)NPElaJ z+2(A{sK1ZJpT=v3trBaVRIB;3`=%>kS5Qdy!f6T&dwZU2rzQ%dsrQq;ELRTCj-F(P zuzfW?n(k!xXZFtq=d*b|%kRk9Z}~A~TcjxA-29W8GpdX+XXTE!YR;K@teq_$SY>lY z)$5^P|KH@A%^7vOp#q;9>t}OD{k%?ztd}p>{W9XUB==kzqOZ|v#6(p#YvylYR;netpBse z%E>2*?fL1fbyIT|wVSAbdEZ%T&Z7QZ6(}sQS92D9VXnZx+HGpiqO;jPAHM?|sBJ4o zDByN`pqjI23tI)kI(Jrc79C$lfxCwms5y()Ww|0+ualayXyqUUzF9R_a~2(JrGV|A zx@uxkc7}SX{U9}G(FbMhyz|d4YR;l>nSa9H@3T3JRyga7Hv010llJ~*_=hg*tPmuZ?ZXy%Ev2^ za&Ub%XVGkS-?tSPvw6&1WBZrhEIXdfS#QC#VZ4y>}|>R|DKLZGun||wk{pL?}&DXKuC$`^_l{Yp_0vSlS@dh~ zEF4O0rsXW!xJ4G`^l7H$EZVa{7J5`Q({dK=Ym|j$Bh9s(Mei49!qCrL%UQJeZ6;!G zG}m$#Et-*qwu{ZQeC{uNkclIb=3368abvQe9c->8?e24#==`a~ zjh3^hS7s&>54O^B7G2pP6XQm<)^Zk|tzysU*jme3^hV=M{B^Chmb2*6TA3Ktq^*{- zsQwBzzREUQ&Y~ZmW#HNAHd@Z2r*CGUcXeAWXVJTpGQnU;%USg7KN;xAY|f%JSsO}E zx7BhMZIzUPM~b#u&Z1qTGZ1r~#WTA$L65cPs->2*X!x281UOh~Ig5Unoq-EmthAg( z+ZAPC^DrwdXVJ7N8EkK)rIxd3yGt3Eo@S-xEb22L0~20|*ABADz|xv*j<9Rbg=E0d z(^|_}w1Zv-J3nYeZJ1x24sSPWYX6!Q8TfKX^sy*RhdR)T+OKuU!1}f}bnU|n>4-RL zMbDm^nvNkStf_w-n`EG6oDH?%QE)mo=39wF}wvp=WoWz}i!4MPv82M>^6TTGROMk)`8VFI(!v1}5n!D6*m$*io8>$C=g? zKTfOD(Q=3__5b2;X;^aGisI)7t8>jrTN=B^kC=bD6~&%^MjCc)w5IqR+c+KW{cI@) zdhScZp2b!a!&3J&n44Hr{MY=D2C1bj#ZO1SG*tGoqWFLOZyNg6u%+0Ww=fO!%PeW` z{IE+yf{fL};$JU34f%&{D26jTr(w}jOPY7awbHQhttHLPC9BeKaJ>!1e{th9G&Z%Q zd1^c{4eH)DG0wznp}?zR2_Wc<1^_{L|i&=KKG`TK`LaUgs2p-Y<7c z`1cEYwnkC3a-W2Mzi^VqpuhP+3I89)Gwx~}_@GC7m9yDz*iZi-V`m*zMfbjam9iVV zMNvsRj)fhR-A&tp1qdc_P`Ye=R1B1JR3y$^*xiJJVt|5z`q*9Xz3-WaF8EAM;T3t3B-UlD5#9mz^&H?{Cc&ZY6c-gE3R<9^giS>aV zCculyuT^5tulh7sI_~kFkI$GS;ZW2kF2CU=&407L@Of^op!M)gzVZ3}40MQd|Hl9O zXPy6cU0*WNvH3;@*Lm^bbljzRoM;EXrRn%|sDR@YR_R!sQOvO}7tkO4hT}a;fr`&R za-3{L^QM?@9JdIOP%_{b$6cyP2w5n%=P-J|;n$%ox2?9E4#`vHcsF@6ES&pWCHDN9 zb|noKncq}GYwk|-wOLO;s>GgOuf_vuLGL*Z?*&Yo@>V7G{EDMF;Hs+cRASGsWST>5 z`S^y*G&KX(6uwr8J-q?0yuga2!=b2?tEyUzb*doc}N;(w@w&ecL+ z2lr<`RASGsD5~db&2N?1^J`xV9THFcR*C%++t}zZtKf%9tYf@5Q-@X?f2+j)iM3Yg zFeC1VN__ufO825xjqfUwH&&TPyw@Q3}8cE-A z?5^@dCH8fSnxez=H{VoZ&#(M^`c}pDmrCsUHT9DYGy8s5i9Nr*(>EH6&VN&hJ-@8W z(swlPeyYTtUxVrUriX#wRASGs9?c}Qn)_2FzMpN?Uc$o;-&A7HuX!0dd?@&;658T~ zDH5hx|4@lNzczbF7*q5`CHDO4@|wO$S@u;W_WYXQC1KQx?<%q9*U3r}CjI=P5_^8V zjFnL3=r@(v^J~#=3Hp;itHhpPulq|FdhfHU1C`m6LHFqW7nRuaYif=J)2NRsvFF#i zY4q-*!)KM)^XoXh2MGA_StY)INm@zoA69-+4X5Mh6X~~)Kd8i>UtyOe`2Kva5_^7i zr8)l6==UnI=T`>JyDJs`%W+ehBGm5olF#2hndbGa{^fJty#}})ddYQIf0E|8Q;NBs z|9k{qM-+4Yk39vRk1gVBf4mx)_qK%p>ty+KO#J+eubrkrFr{~fqCQ_6q{G3nh}&(g zVLDvfJmIz-qyv1@i@5$rd!~~=Ljkw{O_Ox2y7P$dov4px|3bcYQ`>ZOX_3$OF6IHf zPe^~l?Y3`XIvS08#P@wspL9ey=W%XC{{Z&KJ?8d5vLv1M__)vcGiYo&YTe7>+`CdS z9W}l`3OyCLoVmf z#I5N_t&qhzU%V_Gh3jr}zliOTj>f7S&b^3#(s9~2gZoIw0qL|~l26{FMf^-Tun zd80|`v_I)>?hA9*(DU=$b?$3do6$E8L&x#6;(#~JHB!d%v-Hy5Xq;a*mY=bIKA$J; zj725CU0gn_axA*qZsWMsh8VQp62tM6>M`gN9m;W24V`~M0LPIo(Wr816~`0E%PY@i zHphP(7c6hZVr+7pO6+C-VN@*o^oUl8z3dMbknh&UFqPQLz6)tpzpkrQV*TVu^B7EO zyj~^tvcLTz8tomuRL`k=hm$lH?lW5@_Oc&%BpUi3r>n&J$)z+0H{3T}CHAscZ;wXY z{YfgZ=XGCwnit;+Qi<=E>vg7YRiZbk#P`d02GVyW8v|70`{gGdF(|AP&Sjj(#^5r& z!x!H#*Iq;(T!m`Ry>+`|Xbr|DmH2-7_t#h)th$r`>v`2UIBeUZ`c41!h~}HkYfM!Q zr~VkPj>h%T&Z=n?OEaT!)W%IUhW__tWHdf%Jydh(_zs%4Zml_6HI9x~SQrgU%vVjI z_~?FmU$JVj%9qO2q3=YF6wOrCrW~`P>#fw#O(nix_6dl__9x3#Q>pwOnny3X>7@#x z@@2`t>(LPpRWB-2Gn(e0=mud}_DVs+gZuR_C&QwPC zihSg1`Kp9YU9oBmrj1^!5_)vCW-)l$cD;(%I-12G%so&gzF+>KruOU{suJHX7oU&8 zmoX74v1k3x_!#8OisExxldkmYUNqOCZrNBoGKyA-ed;6c#o&IqaMeCKzmZ`qZU@Bi zwOk=@H>+{6DzP_x#wYSy8y}$(>kUo#n^i(1?n*jl$ek_RPuuy%;{D9cDlc(e z*0DH}9HrVo3%vEuPbgJw-)3>RFM!dUiDl*D6l>{5OXQ$v- zPGd>1Q*vSoqDMED1XKOVMUGw4VcOfahd936mY(PJB6TAE8!wH$F5#+mv`(D=L0UQ< zzZuv=#P6oics*%Y53x62nZ-1grAF#R96v1zmv60473Un;EecNdi&I5?7CnxH)5o5v z;FI8{oR`U7(_RPto_W*|$&f)rBnG=oblgi7_qJi`dL9c>J z)ZtxD6r7V6aNQ0VAIEOzw%iW2${xr4HSM^4>SP{6<1!Z9Zo^g`$MSFOB*BE8ULD6U zV{=I`VU6iY=yKd#5=^MhO2VXUb4f6v?T{0=yOhe5qyC$60+*uAB*BDkCdo+Z+>VbQ z2}s6;DQ&oX-KWV2XxN(1^RyHBt$DTN^N(MVf*C>0_<#SrUw^x&KkSa9dC<+{ zsM*Szjd z=#_Z_bsJl9oOu2Ord>0a1QV`)PxHG$W|CmS3ehx|JSdl$A)SC-v6&>8@Y&iEXg1rN z%jlUL$I0#H{9nrl9EW32JN_?CY6`;DO(nsE1Gc1~Plx7`V8TwPQ*fEyX$U6NQU1R; z*Fq9ZXhQA$>p}}jFyW8D6qq@gNP-E~qv$=r5EDr-VV^a0UrscW1QTBLOhK+$D@ib+ z^`aDv_iio;CQP25LhnpkNrDNFw@X3ApZzBmNjA%>Vaa13{gyH%rsFl`65=_|rRx(@%wvhxA z?ktmn{FGLbU;`_`%3ruPZKu5Bg3gmqugy9;_BC7944B^g;8DbJ})K~^$$ ze`+lWChW5<8Pgk@NrDMOW+&6SwRVzV!mxehW6-dTB$%*_OETh`noEKSe{@d9g0W^2 zGvTIWoY>Pw5=57*sjmqpJn-uT zt~WQA1QVLj`+-xA799IIoWO&l7JUA3<7i%A!-~(T>3RawyIFA^>eo7f>XfUZo`s*2 zFm#R;*WdaM<+-sXU%UM<>W^2<`M>VoO~UWxR($Q9El!~1UvsXHE;$J=y{)+2YQ-fX zuC^t&ZRoos#5A$s`mbGd`R*-7Zz&VsMqXIv77jkc2S9i21N z!h+i^qH7XncDCaCzN%>w1|(W=Zm7MJaKDiSw|}oM$C2{DlJjTJljE2*+=6qj!8Gc> z|&P?rP4tmoW7>y3V!WK4L-d6RMb*bKZWAI!^E2%{b3z(z}T6 zL(I4@M07oln^VlVuNlVDIR3FNj|F-cqTyJks!lxHl!wA$s6CZ7MBE=QtDqfm|uKSyGiUNXlA`;fQiockQ#*&c;u4nH_fsTqxC(<<}- z{%w4*?H7d+$p&eH2|KEyP%dR?nqb1R!=hjtw;@e1;iP#{i0vAmCYUgZzHe>x_`cF<34V)u5CzqRk~G0@mqfa9*0=w^N4Em^b@Hn&7vc^qp@|wY)UJZ|j1h@Z8~gn&7wTZ=$fR z_-UHpx7#jJvw@ahwJKWT(X)bj9r)w1Y)OASvx$s zna1l3+ecxVV_KRkm5Cotd!I!mq#dL(Zo6oIw6&Mg1n-5lB#+ZDEtlyZO6Ai}rD^H- z$U0HDGjBg1AJK{GQ)^4we)?_vBI1O4+O%XUbJ{ryH4G1=iSLnjmLdPuyeO{EGCJo- zU0|AEMQ8H(-F70F>t8&9>b7}j+6gMZ`fVgS_gc%>-l|>{9uJ$JCb+TA;3!0V4M{sp zWzJIGuGr+CCKxi{c_gxiP3QJ3Q!5HS_lBnlhCJMzzPmr{lO`C_wM&bONI%$F-_jQdTKVE}0!H~aNN8!5rsZ_y` z{|h7iFMZ$t>Jdl@Gg)()`sfJq;%2ZG)1Yc1Y-&zp?c=Cz1U8)n>#!diN8tR8Gpx@x ztr&szAI`DPd$v{xX5?JwxcBExXwmcT^NhA3Xt3)v*Qf2_5O{e>96wcsBIQI1$5k^zao^(v$1SN2 zQxlRnUS=2$e=qs?$Zg@YCzo9Q`loOlD5K*tA-zLjy7r1rXt*9#LXfS0Q76_JJ}VB# z)-GptLc{HPD;$UBp3(^o_d%ryl&^JCCp6sYW+AB9`m#=sjz6Cff{soXbVC0fus8(g zaxUtGwtHn$23BkNG zr*%Txm7GGLyLd(?bh_xm5X_uw2_j%KS4rq3zn%4aJ;iCv`&G{kfa&>9|um zq3w1eud2dcCw1a|@@tz=RKI#kC$!!D<3llMYPwEnyYK(CLJ>`|fNg0+y!hgtmL{ zaVXq}OFE(L2G0$pZ;;b;Lff5N7)o>1be+(4I~dX499N(d+HQ91FqmA_>4di1J1G?L zMX5TW?P_vE;o_636WZ>tVPSAs2A$A$%gqhLjO{v|&~_L93Pq}!T;@65_Z{<~6WZ>D zO|(~w7j1Du@%N*&N6Af{PH4M*hR{AWw^DRM+igeZ@wk}6b+e*MbC$!y}U&3%| zqNEeru2DGciIbh86WZ?X_hHB~N!JN&_kQhg6!@p>gtmL9XE+x2BFl6t?|Ps159*$( z6WZ>r-(h&RF;yqD-Faif(Qe~O9c#P3;mD=7658&!mf^VgHI?tt(WT+2Z*@v1wB7OK zb^m+oDV@-EJ@<#B+suxunY@3(F}$~=6WXrvjc^zYhE8a^g$3a#mjj*9cK4ZU(DcN5er~iYNJN*cb^JUD zK9h*iOV;so=FewKWxqtUS~Y{qS1nA$;TcXGXR0)4bI6tBYHKxkI%GD-o~asGx1G;% z+5-(H_gKtv_P-j~dMx8O_oW8?_j+;MAV-6`cYQhjSEIr0kE=O8xJ-ko&(?DMw`ZWQ zc_P%36Kky2YZH;)#g()^U8szm^&F3FePJ`HzHT=JW$|b_pV-{<; z|C%MDj?WC%aBsgz#G8w2`FM+V8tn2|Cu_bn6OnshCTl$(`X{3I^;xVRRq2q3vg@2! zGx|0p5#<^>v&NLTC=qijJF^aTWl18;CcCgcrQV*1kg+_000`0nn^+ScssMAUxb&f1(M#W`(USQndEl!zPqJXqH=uBJiYM-SHiJbxv^ zG{u$mwfzPfIH~5aKKPG?2EjY$u(o)$h6Ysw+*q6YQA>kUmFBXx*wch^V~RWLdd|%? z$aplDbxHRj8a$skPu4C6X|Te0HtU14x@%BBd_L=&-KJ>})M5c^qa}172Ys2%+TzRp z8eE&dfVI(eP8u|MG>3J`C3YHgaa_o{YQaJcrhi<>+Uq~7G{{Mw$NJ{nDU|c|7PGe7 z)lY-*w->Xv+bBo_iv#mn8_k%dLHpl}S=;rA)L`kh1+1$!ryTq8YzhC?n9BPe_vG_G z-b?k_xQO-Hbqh40Rk~b~9TbFVD?<7#)30%x&wl313*}-L8|7}M#IJRL4AK$l_ z`gP25zV?_8Xd zUfllG(=~7nT+Y`%XRZdFhI{k9D_O5W&xt;Ke@p1M)i$l&H>w%8f@$3 z%lWg9>QF1xi`&1}R1FL(`f~mZO4eXWm^a_MFJm=m`PP?nFWQ6db+8}jXSc%|{0Lpe zIgl|>1CKmE&f#1t|H^YU=l`aC8m!vn%lUJa`na3zYR>=L+chv6=*PKt(^`X)wAI{q zTKCc5$@n$gr&tKRL}gY$JxZDr9DB@JS7m^9Y zY$M#JJ>j){aSzqdzw?FTYyPqLJv)Q{w&z-NA7neuL(2o`HS@r;OLLt9B*oR0A)P>k;K|U6Y^=q~Tp$0S0KBhj%Kz2yX#gHG-}2*9x+^(Dcm zPV^0aSQleSFlunSK=c_~LlTTyZGIqno~$AXMlE+f5Y7P=CBdkvWyz!9VtGk0>Yw-G zZ})5Fi~vN=lGjI791(yaA&t3iBgp4reQG_9%dZT;sWS3f&C5pvkhP{7AOBr85LOc_ zalF?#5LI>>aoj5*5Ran`I9^afo&abm2}V7%o6a-QL=ud8yipJ?pEQyLqq>lP!s0w5 zNib@KH-QLyVju}dopU1qTfeoG1f%Xw55U8_%_YI8X7{O05}HebQ8!V$UES485{x?M zIF&!rR1%C@F+2c)4O>WpQK!>+@&cMjf>AFg24LIj#*$#vSLy(?{n|_tjC$i*0H%30 zmIR|lQM`9G%kqsols5Z#~ z@HMS32}U)cGMAhiNrF-JvI1ybQ+4b zM|RWNl3>(+F9YC8>u&|4`tKkgh6rOxFlzV#x-Uy>OM+3S*AB$%Ry8HTsM_*@v>$YJ zNib@yqyU_sREx_uG?GkCkdEWRT7M9>lg_C@>L|ksCiW9l`X4Df>A%Z2I9-6Dw1H-n%;ppo>W;9 zj9Shs5ZCM~NrF+s>I7m{+bWV^)PZJ!Fzr%V5{$Yuo;)$?R+0px>K!ESj>HO*VAOUt zfjB(065k_DdLVX%S(b$8@~)h`1kUXU{u!y6mO^? z2}b?=J&?Sf%1eS#HGzSM(v;_%xeynK57y-+!Kf|CucN!lND_?dd@T?I&l^gDQ4{2uxplm7fDwenz0a-Bo@*{P~PZ9vF*@jk3A?;L|a<6)(s4y2oJ3GdcdP zjmG`^N*VKLq^*}@n?q4>DU_dev*?}4xF4B(o)f1c(ePFV$7YjguPfKv9Ba!(!spUW zj=Q8rVDPu=9RKZEdZl43a$00ED_YR{;Zd72nIWf=*7^H(CbQ)Q(oEehXEJl%7#@u# zewoao5AR1I@nZ%vstvt+dE738kDsqj@0VKL=JNGZBk}6RO+L?yIpl}7{sy1_r9~v| z*LjWqx5L<2#J$O27M(}mTa7B0#VoqJQY89yzQ)HBE=FMOk!yT>%ZykooRrC9R_8XP zksZzCaWJ__EOG~A^4K@GTr9r0W%5`#;T5f8|C-6;>Dx=RH`Crs9%sjEV^Gm5i^u57 zU1P~7Ig9fu;}Cs|hfE%$`_+rZob_2eZu)JCfgQDpSbw;7Net{qXE6h4a$`{TViu3H z?xSe^^Q%negmzs?XLQSA#`u*=`!3~Y@fe*#ZQJ={CNoB@%`vF;Ig7{lZ*@t_rh1C? zhdXKCrQLI~m|;#&h(UyLHgm!n(oA=M$YjpxLYi#Mv@B+%`IJjtn`AR%+)pPjk(Ze= zBh`<=q88cACyu*lP5Yxv<|~yit=F~5Vg?(X6ODfwXEWz$NteH!mdTt}u0O4Xu9?M* zS2-mbQMI#~k+ig?x5e&EX1ph~zPgT4HuKd7%G(L+Gno(X(>i3mOv+VSA6S#L^^*^? znA2S8z3cownar7WZ$zQpnoMTY)!k@4_Sr0EyhHSE)3#0~GitZ`w6=Lq7W3gaM4?h~ z2LJX~6ulp7CZB&l<>8X?S}^Zp#YOU%2?_iiDT?|9@U z=iY%OkvO~KCg*2DWF$6P-R2y4ME;o-zTV&*cCwE|3)OzPN-QVCe)_$&@*;PuSk^D-sBwK(uwxbTX>!Oom1sV zg!aA8ee+z~NOT)^lk>k!>qwMTxX%6bd!0z!czlEVPTvm^h%&sveQom72wIbTo%>_M zw-JbTy2kzee_^oy<@s#)I2_SskFkF7v*ugf zUyCDpeyjz%#cMIg-_s=^2?YfGtQ{Dbq!*%|ue-uZK z`ElH%-BI)(@5Aw=UPn=2v4Z33y^o^&k0l&eHb06DcNTEm-{>fg-I~L3(k;4{A8s7) zq522XJYDEPBRgu*x!p{T%iN^-wZk-y^Qg{?hD~GrcgaYar+1#g`ftE1EsX{9SzrG0 zLyM?Z3pw6?TZ zv}j?rmjBDAzZQkTYxuv4W@@l((R9|ojA@R1EPMuQYU)G{;#N#&9c|JjnoBmC!MfY7 zGaAglF_X2qo1baE>^YM)yUFxUX>Us>*89HD9Ib)vOxD+2t7_qFK8y9fOR+SM%b&>_ zTxSz4S{2V?t*~BQE$l*_Sx@vhr$MWxPORBYvD2dR5@*&N_w}S}uj$HqrFAaNmoGT6 z-gj`i76)xySg-8$ispAzUTDq6i?x_u+m*G>+^JgJi+5u^)VP)w?vGqpbF_%kqUgKl9mG#OSd$e%c@6LMb+0I(jnd-(`r{^(h+h7mYY8S?8k*`08 zHQdHyv{?7AJ8Pyo%CUXZ=djMZB2kN(m*%n->^)11i;@THtq!?bY;>5*y70#ZTAbW8 zo3+};ls~t6&Sh=)OoSG5>&;{RH{pyHTchW*zP#@~^(p(s9NXq=F|VU1pZ{=`qwsC$ z$>%h#CgP=BhoS;4zBX9K^$e_f6!RM`=lb`1ti_XZEBM-r&T3)X-;@7qbLFFu8m-`K zZ+~8ke=L`BeZndn#i~Xtx!o2}{dLb*a@!`J)56klIoH2;nWJb}-<#Wi^$jhmU-9O9 z_l)X)_3d)L_Ag(x7-{Uo_pZ??EuQDC;C9>fPKy)OR`GpbcaokndscC7_$O=Osqy0W zze07Ee)@9$s1vkE>fy(^cUr53eXKX%JBK@3OkM8BxmWg(7Ascy@O{62MN8i!`*Ggx zqZ}C2cs1v9>}DK~K%S^ekp`CUjj%6r9g`L*;uyz|*T9G4v#hTN2YIR2R!3h!C+@hUY#F+6=A zA3x+Bg3c)iIj-?x6J~ePaQwG%VS`gRrcO!J39Z>XKMaMH4(o*0ym=zM!>^T~6I%0# z%utkgCFq3KtnWa2!Qdl0p*26d6@q9Ntxjmo^(Tj*`q?C%(3-n72*DGBRMwiG-PweL z+9cMRKfK=rv+-%HHNW?ueOT=F>%{s)^W;!mm=>=S>kmuTliqYFK_}K9&eRWs%e{SE z<_1Dx(d3{`tUqjjB^2Ka4(Y@?jrP^T(7^MMPOLw?a6TN*tP=RY8qoXvF7q@xpQ&_+5P$vYRJ|wYzU1$)35$%t$etoiA2to%OXZ^ZKy%5ZCILi9<=&rQaNs)&2 z>mi;YIC)g76Z-Z0#vy3>KAH9F64JJ+4LQO3^?1_qj*UH{6Z&=QV|097qE6`74;(`9 z);mcj^y`Lkq_uTBtP}e6qdC-W-H+>pejQAE%A7V$&!ozuaNZG}(5agZ3Pr-n!#bfyPgog>*KZE$#QMXT6~j=l4bKC?P3_-&xq%1=~YB~%?BRT z3GH|l?Gf*=_K;3!$J<|qVeN%@ozRXu)C@=Qp#3_b9Z$9h$I;kBI-wn(ITeOqzYghy zb{tUL%`Mn?<_TLk9LOV7#2uIqT1f9^1qeuhlG5(-VXvY?V zNu$v_q7&Nj9@lVuPCcR%+Oh6fIO1?bC$!^o-O2A_QZA3z{i?@ec8wfn9>ZU>_SNU^ z|HnlxPY+;j@E$(Cbn!0C%s=&i@>2Y%T^Jv6hR=V;<{<7H?c;b1?NRmc=N?I{_frS$ zLi1UtIj-F&5H_{+`JCt41Y-HGa$KJmp8`-VvJC(B&u2@*g<$fz%HaOK=HDRXzb)bT zZ_k`Febm?;_*P!)(rhD4M(1$6#b6`gbBEVJE;CibAnY~AGkhcPYw#_uk9K?nM)=+0 z`t&Oo0n=Z%xISePBT(zjZDzCHuObk+B9obIS+_`BdXU8|XA}~N55{+x@rJ*S#Egb_ znf-Q+i^8a9cbN$X(<1o3OLF+QUUyobb2^91`yQq>)i-kZJhPg|p!+r|QN?)DfAIG4lYRCYoP_RP)Y zv8gT1pi!MBg|Yau z{Vs>c@ga`UxZ3a@bI8?Bw8ndSE;Gy}%7^M-bC>}JTSp_P#yw`3-gM3*-*cEBoU7A* z&E@Vf{|x>@^X0y|%tf8)`|+X=Im{vLZqvG;oLpw7V2S4A)pMDzE_J1~NiTAkVTx!? z(M2hjS!+cD+Na=Q4)f28@F?uqnkxxk#OJH&J7UUD;afQVaTJ;*=P*b87!!pi4!M%> zMLaZw*4udJNWvF!^I2NwLpdzg7B=b@g)`0NGEHeMQ#HRFNq7<-rnND@Ugz*{8`PjO z_2u(7m>-4P-6#jBOwasC?C{OuI?TQwNqdss<@)a#MgLn(E;HnOB>LFoaQ&m`zozEj z<=^HXh(yt^yL|20@s#H#ce#Bo>QNn5-sL*v(7gNHyt~|nAxmjpP~;tMf8&x!B=x<^ z^&dd*>$*0-%kBS^_GLbycbBhyV!ueVxpjx{UB+PAv*2?!-`|!yBhlXX4!7YyH6u~Z zEPZ8MiCX;ix*^&qx|CPc0?ke@!nyL)$o0n+5 zzcD+k!Mju5)8TFCixo=FqQ;Ejw7$*iQe@k!H`w1lD{#1gDekprkulOJvJwAT2Odz5w8%Top8uadjoZb=SzN-06G+NpRh}#r_!WT}KjJS8<;| z{G5y>!F98!OvcgrlHj_IE68kRl(8hZZf=S{X2sT%1lP6q^G8dQ+LBn8=#WJD(5jXs z)+HvU`{U7)I+EZ$!w9Mmnfi!zi50GpXZ0`AO{h!>dA3K!4J5&q zru5tWXUa>0Ew_{Rc%{qw+~2E`&iKvRND^#W=_-|3Y$yq~Ecb5!evZ|b1Y7sac;Q~wVo~%31 zjCX;xUU$}=lc%`i?5EDGJFBhTXq`+))}2Q-bVuC0_N+U9sq2AfRjpZf&Tl#!8%J8P z?)>fCY_#rZ#kzBybI#b@t2b-DmwP&6!oXgv`JSvd2V37;vgR8|^_0q5vgUiI*&Nj0 zWzL%Kzz}C>^Lnx7`}T%25}&JB^W9$71$`&>WX<qGpmEhstoaW6*A;y) zb!5#q%g_yBb2_l*+pnc7%x&qukhZv?wHwM>b!5$V)^s-<-`;^W-s>b-+R~miU!z}ccr@CYHD8O`Zuq#}n#*_@yQ6*E_N@8p zjdn-wDQnhzr~0{LgTEDPz7wL|@OzyVYrb~5Zg44Y#dW(x`I%37A~fHQh8{Tm)KU_f z@6^Wb$cnaP%{QmE2i(tFvE~~-)&tHPtXT8CxXAa*U0 zHQ)XBJy4;I6>Gjz>d!_@b4%8IGrD+SXI~4xN7+qg;~v#VXuczd%%=5kmaO^O&Yum_ z3YM(-ZrU;%|Gcnd%~x~L1K)DZC87EDr~GVLV#%8C&FZsJBgLF^=1Z^HFg#$+nr~R_ zY>bUHXU+Gs=y%cPtoiy*8x1MFnEU%RqPdOTwd)W6dR6m~9RZPabEBO)@NvS#Yq&=ILapRksCG0g$Dx99Wm zl`AN||A@;MjB|iP#fN;JDPtW_&@qqCZ|CWNW;5^c|Ni-W``a@xztJcxHIeH)tkp<( z_9)@{&#)PR*Hw!-ezU|88T+4ceCn(N467A!yt%ytRt$N{@zvAzh@D)(@c~bJJRAL( z<0|&{n5}xq@y+4(Fl&&<@#XpUF#n#*al!LZxVWd7wcTSFgwqdta`|}J z8+&wWk;})8az^2EtrFIN>N<@=le5LFE8SQ=3JGJ2SxdTaGYVVU7PI!$>-|V%&M0Pm zYTliZczO0Y>sDXZk3`;^=d5`h>puzy=ag_>)!sc4tJKd~^U60Gg@05ftV5lcHxf%7 zp0i$drO`sHp4M&ir0XRNz*N*MvYC(l^3dp}_$;zEj9^J;y6 z1deWa#+qIE79%mxzL@p0@d+c)q1Q9k`;Lzvfg^*Tu_l<9Gy?rjJ!jqRz{nAJva^VF z!)w1BadAfxYmT#4kHE#n&sno8HXT9dEMm=Zp8W`1YWbY?zFk!Q+LuDsD}NqzM9r6l ztZ80*>4^9h&saB$klu#k1ni&Gpi-lC8-Q=4>0q&0oUnq#kEM|6Dtlr_^4VUEzA zDPq0S)7=p^0Z&MU7YF=S7jPXuQU6*r?lHGvk(C4X|9HghU#6)8&eSU4`pEIK1mIw_)CJx~{bkIR|!BcED%jhnzpH z?%LyI%g5aQlLk3pXqAVYKbx=EZpES#X)`{KY zemXhHp4Q0S=e{%Kf<2tJ-s8U3B*PxV8{gypcw?{w8jQ~6{=Vtk@>14vc(=Ti!3rKO zFJ-eoIqmH31qdG}b5y-EOG@Lv@!OcIOVHHMnxE|(;ue&~iIL9(Au#7#)v=13(vJ~2)_QB&+n4&T^j#w9O*}UHyn8UmY7o%nK3c<=23VIMy_22x0W)yPM_wB3BjHDc#lecXtkm{#}3{7Fu!3>j{kPQ zbVe&Nskap~s$mV<4<*Bj8FfH)Z+xxXo*8xcZ*NR1?7)oLEXM~yqdGIAUWr--lR@2> zQ4e+W#rgdzW>mekzBu!;7c=T%zZF>)+3 zM6&^w%&50%zZLCnb7oZM+beO2+D)uWtkuj5J>o5yQ9IL~Df?4p-dI=53m*fmm{BW@ z@k0D%D`wPp`)JP*`kqv*OFaEzCH7XdU`9>r=moz4GXH$b_JXaOH8bj=cGOm{t(Z}( zdeL4pffmfD-Hp9b=b|+;s(O?+jIG-hyLZ+LdGWJc|4>x~`TESXX3 zUH8WHW*wMOf71R7E|1$Yqt>H6M~bS+9N4zJ57x$aU`GAd#s~Adb!0}(-r|GJ#vPea z-D=a`2gcUSsK-b9(DO&;&ovs_AHlN|GwP0tw70^%PRyv$5kBOZCUdM=p$}R&>&%S$ zyY4EC%k0dIdYATSI9%MB8TEaoRrp41EY>9sq`e_JPmuZfE$vnD(y=Qus=@75NLt%f z5{w$>O?#0v>coutW)B%LH|WNUntyW@*1hP)jGAcbi{KvJnNf`jSK)xJGc#)0I=+|~ z(}fvzQd3{t*x7>_b+V@~ZdXzB)@x&d(R#-Fh*j_T1u&__5uYQPmN?xOKf3GwS0rzPM;F&ua|t`O-HXJ(y8b%lV;U z+n&s*cPsnhz}242sD*cfO6RtgKZ8o=y!vC*rE}qPpMy|OVa4u7YCKmMaLaqCMI^DC}xdF9;pF$V}^bG7tu{W!9}k`;=`~ z82I+P05nn9_|NC$-=3wuE7i#RCbQz=U^O!8%M9tDR@0hHnJs;nsqsN!&IKdXC{$Q9 zw7wdz6-HIx3WA@)u4R`8q5T1wX|rntp>;KxbqjX{Vx7XkwM+srPhsQOcR?^zSk$D4 z8s-X%-nkHj-u?wr2+f05Bm|-Pq$g4|#b+z3;jH&WN~E0ZyD12ft)Ft4>ZCC>EO{bn z#2kcvJ3iuxG?CVmn_dsX&WlgE{BH!5@^Ex!Kq(JzsH#RSWgPt6NR5-q*cw(wjZ|ek z{cWJeYGwRwLORrcWAy1NYM3cwcUcQHjM~ZL{*<9=3{b||y4BT4SH}Ip4r)wS#$wkR zYHU@QA>LArh6-0m84ra$-s`F1uCUXh26Rq^yQWM~+0L7QD?8rPDMquUR`0o!C!(fD@*3aj6rHtGm*Kg&4VCZ zRk+cUbU=gMGP8M8d-mBZGhRUpHN6LrInX|z`e1T_G@G6|XZ8hQjPp~Dz19XHN#W|g zbAqr@Vd-)cgHUFW%-;EvgW#m_d5w-iF#alY`;QJms7(AXd?vre2VufynVIJ`2||Fv z{EZ`nP_s-CGiS95L1?y1o-b4~48k*IPLV?UCzd@cbGs@p5Hpo|hy9&ESSoWCn^8f~ zYbG;)_PIdhDRY*esvz=Xm*)$&>05wC*X8++;U2L^q&z3GsuYAD%Dkfnt?}NZ%$pX{ zcMY$VIoFA|w7y!Iv&@=7-vuahuCTj-a98F#T?Yr^n=)U!-7OFglzE)nu0Tvv=1psA z(AsZhuIEhew3{pQ!6oZyeYi5`szCa0qB1x9I|6$jzT`3vFGgU0@0a}BKg++bZ41BEd0hV1 zo8g$XjfOEX4+!F?WY_MzG;hY+#3g;yl)%JAJoB+2n_;O@F3% zP~cx!}qZTtYzya+2L%Rr}DbTG&}S=S;*RV|1S18PPr{Sc?Ms%ClmSST;9pc z0b3sx^LYws9vbqbgwNlg>Ih^dzTp3@>XhX=Y#iIN6u+(2g4ut`MA-L z5$I|2ijQx)>4;OsFIkgXAL)p=6Rn*?0>=9R-x7bQS?qpc+NN-cEIJA zC9KnxadAW&n-{VcM)M<^t}j^2>pIK<@l#4z2b|Esk@lf`!8%$>EeG^0DPbK@``ZDQ zS4&ufi^{jh<+u{o5SzWU$HLRatTRS$bAadI64vq}R@>vpzs0OYZi}$Ti+aVZWA>lt zfP^w7tOI6`vd7)XV%9O+^>u*mL@{fKiKg~A*tM87P%|5Q@6yhT1s9&Pj=A`-9llh3&N^)0D0}px=Zsj(G%~;riBw+b z$O|=guzpa)I&#twdwj$*)>0q$x5Ga-idYM7wb%|#DiyJg{LsXn_8EM}I&7ke9gL^R zWu$WU*i+^iYq-%ycC?1Skbir=mmNZ^3;Fyv&f1}3k0REBk7n9pjb0(wVNP{BgxWvl z`nQO;gLh^jmno5KabNwE>pvsd4v#$K<2L(k5n1yoUwi8pwwUSigxe=^vK>A~(0C!P zalI|BH+;fv`0KhY`mZS9_CGn8%CvgQ^{=+f7CW~WaQmO>WQS!Zp76E5^`QRStbp%b zxl~&$3draC8(-TFv6%(jhV3TU;$`!E&Vil@wlI%+%=r^c*S>yw0k{A9QMR~4?>jpPEKxoZ3C& z9B%Gzi>1vUa336ajp9pr+y}eR`KKR$$oX&RX$zNs^0?2|pmsjg`yuz82j6UIj`o22 z+ARY+JbRqS{n57AmVE#2vyN;zYXsWFyyST7?msplG~YpBkUtu;!;6yPtB!wPmfi zp5?Z?pejr`t`+NyEU6vGMkkywYliGIHsIGRj0x?)$9GhA!lFf;Sv$`6azdG2G{+(B zIOC27Iz2GqCu~^KMG_u3q3fJzeCfm*be926P^Wfet=Trw341qp zWUcxBL?=9}*O9g6XKS30Q=-DW!YyLLI83X>cVy(Gqu@edlI2^gS@Smnmz_SBH2Y%iNT; z=HA&Jv_Da6)|xL!fu-!^e<84xsYVhT|HoQ?a@WXMR}32Qk^4o^HJ{S>Z#*_S*$2~l zzvt(M|6$kC_z-A6)(7u-?V@$OYiZo=*^1KVN%vnXN}n_9=^fO6&!0b^MQ?g9fO@3t zbNHf_XKDPmXVldOo*2?jehyS0wxBeQZQ)7Z^0eXl4CuF@G)`R;T*{xr%!5n0bc;c7 zDX;$7R{f?1!Bt^D(;S+!C`@QMgywe&E3QjWBSK-waeBe1qp)SxuwYm!%;~&3nEXX$ z7IoPdj6n*cE=Uc=;1ro%8_~vNB?{A)-5-os3hVyuo=!Il!YzgUenbSpS7E}FAA;bm zu;R_(Y6L3`IXXs-r3zav%2uO{!klsX!3a=TbhJq@ZYYeptWz+|6n4E!@uw3q(++MG z41a}nHEzLhQ8;r=^I-Z;U*=5rszFdGocZ)~U@4bg>J^O5%6MdJ8;m8&824gXFr1Zf z?V(RF7AfOk^w?n3P{ztd8-j6P8AA_E4n_xM{M}$h_fZ+|j01!5L>Yg}bPmROWlY== z6pTK~*c~yI>Y$A8MLmPDOBq9FQ<)J81B{~cS5o+4be~|1RL0*U0l_$?@WZLTbX*y` z^VSFBtim2|$I$&%_#}eL?D>xYyn``BVVK3kgHcuCpC7%0aX{gR7fXZTuJDgD)y+v^ zk1O+o5vH)yV>;ei;j3PBU#2PyGn%ezgu-CG+Xcg3;kN`!s;9y~Wkv@hO5wMrZGtgF zVW(|Ff}v8_FQQg3hAMnmt6ng=D-0&iQ$}IPr(e{_ttj(nRMlW4Dg4%~Sun0mmHD#? z<<&8T{Q{~7V~WDAeeTh_tUQ@-2fm~|_*acN3Ik^*t8rzo%+E#SpU_?5&-D9h zq$vCxdP|K<-DP&QxkT@&6!y*!Q)8dP=k>K}xG4<0V>{))!tn8KYCz%t@;lWSqVRKY zfEw`%|2N)5?~xStPFSeMEoJWD)KiV&%KYMvs~S}lhCg6K|EtVF#?gDKKxO_CG)j#V z3jfEnQKPXke_7L8jc8@=kW25xS}Sv(llOygOqm}|tx4^p%t2P=2GN>%c@A}t-kIqC zH~;z`givMv@&-ZpN11=cKMBGVW$u%+D~R^AlIL#E7Y5;kGN+3@8idBm9Lmfs2ocI0 z(6k4=Gg0P%{o`moxibISH!O%Y_mby~^L^>J%G}M3j_*+BdIPQKy^t~=yi+EqlsO$~ z-{=3{50u&ESNh&y{%60^_X+R%`k~Q@PRyJ)pZnr1z2_I}3F}$HT)F z%$&I{KCp^x%gpKF?2Yri+AwpT9`A*7p{C57Cp9Z^#>bSI^UrbTZ)4N&V}7Nq=rPW( zlp!x&^DSk|+zYEpnRC$|+CyAn(JOPkOBpr6%&U}LjW?}?nZlN@NjFjVFlFY9tW5h* z=bB35TbMq*QlDQeD z*MvECl#Lgb4{6ODySXcECimEcIo5fd7pi}jS>;s*=`w3uGsgyATM3P+DRbid3%|OUGRMB9`<1;;_NQ$a?uCYqrp&Ri8gJ~n zE_2uJ7vAW-!IU{RzrHtucAGNCdi3|fwskVgxh?d;;-PJrV}DKdhE1L+bL=eIKYGS% znFD9;@NGygIaHE`9pS2a;J^Nqh^lm$VZ55Hm@93o~)D zFIv~MV73ek_r>FnG8<32>Wc;!WR}i8?+f4kmdulvy8FT{!-5&|djmhLUM(~Ey&8U) zI?9?Ea@Sm6^oy`$hHTZ5^55Bt8S=s~Kb#+D%?!D)mml7=>A(y*gmUj-b8BYEC0~5; z@x3)Or0G)HOMR3)zbH4$4-u6+F+<*>|Jsw;o*B|Ukoww~j?9o#yZK=k%~QmB#iF5p z2=?#93|VQNAG%lX!VLMpFw+0hm*a;R;Xl8`X8VjveH5=>H!Ag4-0s+?)GzUEn?9vJ zip#I|F7;Qu@MCbPU*hzogG+rBNB0_B>aX}``D2BB@GUZxeRy1}+n`yI>`$mapdS*` zWZ%MX%ll(O1Nr#%_yHJPLG~@2dwC!>FOz)>-`yER-(8;K^IV)i80X)f<@j%PHXP6w zS0|ljFUN%gZE&sPN%nH|x9^9P^6Bj5_4XLGX0E!d{NOPxV27_Zjw4^zrM1xkJ*~M=`1DU=(b-%07zO9|ytB z_Y(UkE?hDgJG)(CAH_-WeXu0w6#FQ8wdsq@<|o-lu}ZJLn4NWseH1Tw_r<8Dr`Sia z_2Irae+ulQIHr7G>{%(XkD}MFzBu$goqZG&I@w^z35k6akJHIYIQS@tJ1G|4^kG>7%`_VcRu#aNs(0(X; zK*v6c$2@GXYF#S(D83oq4<*aNK8hPd`eEl>u#aL`c0Y98uhR*Snx#K%5b!C5eH8Bw z?1#M>DeR+YRJT98V!=L&$7b}$kFv6l;sQF)=nJw}p)|2S9^L@^DE8gnALARQvybAf zm;G^>u2*=}6u0P)w;xj2M{(<%{%Bz>dn9_b8~~4x>FlG}+H(MAp9A|SHaO8AGuO&x zemf0-G~qj+%d0F*H~#XgF^z79auHYeFfvH9QuxU?XReH0gN8UTxmI`&aCF&T&% zdrq^DV#3OS$bWcBC$!)@Sp(2HO~*cpS7r=^)0#8vqc~vuKx8dG%RY*$KMjO&(HZtp zTs?Ilj!XvoC~ny`5Hs!5*++4DtwGoxa-Mw@Gv*9JPLK2Kqd4!$K=c|TdtK%ZAB5ql z7uZMf-rPZ$yW%4IC`KL~1c#d!*hjIBW)PlKxy(L_MKcHC`Oeciv0ib|twE?(aG8A+ zr|cYr?@wj#&FSX{!Suvg_EB6~WiVFGJI_9ftE>lO>6i=bqj=_#L8)J2z)piwAH~p0 z2BrRrU8WmgtKt**@~1v-D*l0QQ}vPfP4*QW6QvKa;f(MbY!#-Driu^Y{3H5kTUque z-0?~u2iD8Jg~7H4xY|zkGn{kD0NoUy!^Kk#5v}+i-mPSWAjKE)&*$6Uo`L&3^|4*? zT5PYUkLsUf55|Yb_0U`KW}K+j!^=IgXX7Y;J*;+@y&OFc=wVcM+2gVBtseTena^uf z;->0jh~f!ZhU)+MperBWu-O1viic#JlOfy{Z^>R84e&|vOWac30P%`n;;`vPn4|bB zey?nVMn1B?V$5U%ELD8f&NeoHx8l|2?P!2Xia*=qP6o(V{M@37^zlgXeCw}gfPysH z3(hK89}g8DInNvVNK<^f8hs2SMIxL6;PwkK>9@-PD!(uu#0< z-ki|K-8ZtA-H-+P=&ktREt*MnP<-Ul_Uq$d1=$C0i>*H1_LM#7R&AwoHj_Q{s!Y&F z$^_YGudgZ9bAaq+XB4E5J;P)#K9gbk7@_$1ov*8p`ic);_F8?IOqG577FN{9dc{NU zh_61)5o8a*qy6=_X=)rNL>;ZV6{`Zk2dl;rU>Lc=)C$A?w{ag>~0NG1$Pq;p6Dqe^yo%G>; zOZHLJr}M1YAo~yw*rtzRzhoap@xLbPWe>w@2kBnal|2|uSL@T>J+e<@!f!pKte3qI z%U;pPGzZzsapgXJoM$Tf2`#`?#X@J&>kL6xhedsG5 zl93Y(=s6~PV5SW+Kn2AoGk=RdTpr3^loqiDn4x%S8mbKtuJ~})qUXl;&$5qY#WVw? z6v#fD{d4q@Ut9LT40&Kc+P&=I+2)P`;uN1xk46UAHCgu3oYvM5zmLmapl3}DVXpXy z4z)4B0e{(tGjfC>jwn8&A6yNPnJjyF_V+SGO~r$Bg|8u|D&C~4s6M+DFVH6$hWODy z_Ah;%XNW$E$LYW#I*+^TBPx|KD)l>!uVsi{iU(<>#fG@4c$R+LV_52IdZCXI9xA@6 z%^os|Nn5X14L46^nd{daX6gag9?g)L1SZ)cE`(ZDLcXL zZqdWsb|(l*hjb$#NT_^g?%fZU*Y&&nUGM+yYp&Vd+1;7h=gxi4IbyE|CPdZPWW_todR3oJ=)iSde? zX1K!4pKUN+aW9Q6w_ec>;}u^_b%To|bTM8ro8HSSS3`_fEV}OoYgTu{c*Vo#++g&j zZWymSBcPikUXom92ARO!QKuW%o2HnChHaON8}I|T(N~jkx$s}gB-?)+(Ppl8`vlE z4BOVp!1%MkIb73DM&}KIe>lqA8nQ($;@|V+zvj{v6-p?p{ebhyN^d2!5E+c~ukn!U zE3g^uvpD$nNnkc6sB_>hvK);x6>vyoJa%tm3tC$R_G7e~92`;vTTw297a}WiNv1WJ zToB6lBw9h8$d)`bMhOa$m$>TxXFF5RgOkW}i)^a|7m@k)CW?m_A`7nNYaUvO9JwA5N~qp1aNFz;^AI6& zGtuqa0q+rV{^V|l7l4jRt|4&iFJWKn*wvH??(rMaM51|=eg^Ux0)xF&KeJ!@q!T;yq`iXZSQgo&mj=k7hsXkzOtS__fWR+ZqH7HYZwZXk z#P8NHO5}*nH?@XuBJXs?O>58+8Ke`etYMkREPYvR1)W8%>4lS4uuSBp{x2Hrf0>^< zb{z!&$4k`zZ%`vgamblLjeJGpe)Jzf2By{vTh_Zla`-m$<1^(#TOv zAE435SNywv`&SxpVXVLm-26uZUwR8H!4ww>ETS5o@oLUJQwLX(Jvhfx9Y)0nOhQ!~ zb?6^2unG_4tHE56VOU(C1|LPXp=mpHxaTD>53f#ChoK@1G4HiHxSigJ=l|DzCC#P( zup)Qy?h_5rRTp@S3(PbiK;$&Oz9E5Vk>9wMwz;jfz;zs>ErD+$@6oeD9l}Hor1FP4 z*p~==$Y%NyxFT{R?|Djqh&)NxyAtRlawcy~lR$ToZJ3cNX=EGrpl$mqrEky#g$qYkGeV6b` z9mb2?ymEU9v}!MK=L#37!%>l&cddQ{eI?XwrKW*?0F` z)S*yh_qm^;?^i?M{&}fOVDBM;n|Ibp9V|Kv+`o5K>hN4-?!6qY4rL-Uu=R0u_^+eD z5Y&$2;1jM&rq7|7zzp0y zRvi*MEx|ZLt!wHqdfZ}+MO>Do4yOG@_Mo>qq;y||@rp;Eszdzzg&6DDDpei6irm6& zv(@3T$wI7i=NrA32}>}}@Y70l*l)f7%WG+So*tZ!=XWnxhc4R|VI1SYqw1h$KM&iG z)|B=Ek=f|_OC20fEW|pNx74Atv%qXz(ozC8Q46qq;v01sFkRq1ez%msl%@g`@>g#O zjQu$e+mQEL9fpSr+{owv33M7KFegVVB~T$U9<4h{AWmdX9&nYwIHkaWT&|FSpUA5; zJ}-fR7X+qd{zeJ(+bM7(FRhipEs=Y)LD{pCl z-YbFm`KoCXI4-hDo26&~FY-d2EStb4kuO?2tqF7!8Khdro4_)WaXR|q@J7Dkt(@VF z+{M##Ml|vmZPOhgulK4RKjH@R5C8sN{OgA{yI4EP0Y-^T z#hKL(a9rdr4)k>Z%dMA@yO=yv}Q=j0XS zE|xDH46}M&LhfSD!@)3iroi`mXg&lCoGv4G@rBc1us(ksxr^J5(EGi74Y`XG-G)GJ zj|<3M+<$)vJfCn0xr>2M2ZNFAHRLYth!_G@SI#4M@k3MUn+v&$+(p0qA+Xm;U=;>Y zf76Y}7m>SI9yA2P)?GpF;;IeyF#C(ZJbWH+51~6QB6rdE;}Ce<;Yt+a^SHjZhkj24 zM&f8)duaapGIAG(9kqwmb1oxyv1_J1xJ|o^+{MMy9AN8(i^yHEAa~JT!x6Nv+(hnT_h!SPZqQBSF7Bf~n(bM4kh=)fU%BS#E#xlFupbV=r*9#5 zvG}$lv^Bbm+(lUtJ^ze*$X#4c`+UC-k;q+)_P1{2D|!yKZsaZ|R9H3g82{E${lB$q zWG9AZb#G)U{!3q#t}%xHV>7mk&~9Wlz8q)V$XXmQOS_T5*mSvDBVW-?$E}gOc$=>O z{2!0;@42O>hf^av(TnbX|39YUzvi6yZQ~l*jGN+}8kvp7dgB^di{~adH8L2zrVVQ3 zE3Uk4*T`Ko^0jN^G5-CmqRXryzn8GT#_XpI9$Xge?;7;KMr0Cp)3$}?BCGIe2L#4kR$RW8!CBtEOI9Of|RgVJWuOaXldu^i6T;#Ah()v0g+pTGY9VCc6x8tkr8u@Q`wCo^JWW+Vt*ugoG9hdc1 z2_SOkJUiGytjKxGYHtS{MDE<`U&=-n+@B&PycL;sL)IxFMdaGe1toN|5ZG~Ahm|l; zWZ&7DE5Tjl=DCF{VcQ;oJJ(~b5_Cmw-oEAZnTX7~3xkwU(nDbGIep>5PUP}U>Z=4( zk$pEPg9lBK-S>4l4-Z7{-*1T$R*Kxbd2}tvNaX(YPvk*eWbTciYanMuX5ctI9@0gw z;OY%L3>DdZw%R;A7ukc-YaGpGCU6UHx$*E?kpkoZsE0_Jm`wdz^$h^SS>OS z-`I0-O5`FAc*em&kv({>KL@EIJMm(y0+xx~#pqoe91yvMZ++my z)dK}cL}ufF>2xhilh+)a?TQ42p74OkMtE#OYe*Aml-&eu1iP+cIEVXIqVX-mv2&SVFw*M zj2k(-i7osmaxb0E*n+0Wob-7v2N0Q=J{#olZN9+OY&yUe)I@e=nS&hqi0n%oS>$8Y-vj_5yqJjDrn) z5ZR$EbZua|$Q_+b$9r>;+iBLshUVTCxT6z3+CZSl{OtUKu0M#((#;Vv*dek^?r3gZ>6O5DJHa&wGV45MrN_m4Kk zc*VcJJOBDN{dwov$Z2#f@}%p}0>80ooM$7~@zGY#M&9F%rk;%)$PMlujeJPU74D7P zNPW7-K2_u^9+$hpkuehMn18TQwVk}~>zMhc!wjIVRc3a9?*r?#(2fB(;m?5g*L`3wtnLQy2&~iuQ+v-C!O~M#-pdo0|usd!+6E~MQ*TL zw+Y58zNUVS6x*g4ugG_E2es8rFkVrk9bJ3x*$m?qz3tuM$Im7huNbk?9X5RwIDQ(- z++o7&<`}Pdb&ng^oowjS;<@L_X|S2R?5K-4mUNw~R(2WU-ejq!@3*1E&Ii7hc+vCl3K z@Lw%(4o?JnK=7Eh7_T_@f;(7Rw!(PD@H-yRVWYrETogmw(4jTPD_RwtS+9t@!Gca{;xD-J2~fW@{37_V4I>qJd3 z!gxj7ZJtmb(h=ho+w}4T)s;>duLxBhAeq_$;}u_1`|1KCj8|;8g7(ky&ba3#Q^%9C zIJ#iGVnGFcw!s}SUQu(7Cqx={#dyV3+P2uMoiSeVe4+=ef-V@Zc#`%*M?KnSs9ybF zG}8Yvmg@&*lN9Z8j`>nG%d<#>a}oDAVk5uqOBRVw&*xU^ZRT&a8VFP4cA~w~a3E|M zwg>Bcmk)#)%?{zQVe@T(zdHo&_IG9QBy%vSYE$ZS(ae*XbZ>k`Waocf_FXFb1bjl+p*SgRkoO8 zdHn{*SVPlevpAO5Z?QS`F=e`QEU#aZ3vJuSQ5?(bSHEW{6iM*Xw%jT4h|3ISWZ3X5mpdYu!Cbc^=8sO z&{}gN$8zco&Y)}EFE(&2r{1*v)i&xAqwSx0gw{R?{UbwL}xZm5vv7CAhHrB9v)BL$hIhIq;#@!lD z{n~(aQm0x&;nT$&%c&Qz$r?IXEZ|s9y&(zK5bZpVV>$JdH>^QTwVGq>n&2dB*i*g& z+ZOo38UmyJImTDqZ9u>2TYNd@3wERag+i^R9LuTqf%^W2N_;q$Q!nbbHTW7&=U7g? z$k8%ry zHW@s>Gz;HR;2;_3n|N@Huh@*9=g&!3j^)(z3XwrN!l7fi!ds$8zdrJdnYn z=94+*3(lA+gQmYnaV)1^@kbfFJ?4ddW<`<=u77jqSWdlhr82lRVI0SD>K&kdnGHKf zb1bLc#{+R>mi#`B_c1lp@8NYH=YbUJ2itM-K90>5(Q)L)+DBY69WS<{zmTH6FS+K1 zoB5MXzmkt0AGn{?9#Zp_v^y2cv3SKxT@y%vXCkL(M036`Pb9mY(>MjSN7W^fsf#kP z{3+#;=v~Xf`dg=_kq&ivcpgV{x*vLU0iOSkB$FJBD8TFfJ-_{H4qWl_GdXVl1lwHZ z8B5;JdxQ4lesN@ueGJ-jMtmX3TN2P-dh9D%uAh$fguV$RJSH3MqWnbC^H2fWjvtdr z+4vH)zsAsg&&|H0-MlcJ+}|V2!^7Irz2M&k+iV;4S$&Vq3@=^SI%oamZFx>aOgozim&+SpUiQOfvC%0bc8pRu&1}Rf^a8tP@98^&(t*+GotUIMS-(5jT$7 zW>@2g^vEM_Ep6NKmvLlz;1ljXwcjs}BM+`U<5*5Hr>0-X#D?dbl(ww{-AU4F;ww%? z%YST-CCmPMjD7WbpD#rH*-Org)>(EYmb_W=l&hfa{OR_EOyBUDV|n`4=u1<=W8lU0uEsIroWUdHM#>f5C4rV>kH(Gv&{v-BS z`h`1A%lm7`lhSqx9P=-)Kk&$DGK<-5*a$jkk0;{j2yJG^^pO&wR|4Oa}By(2O&M=QB(+W~J8MU>%6Udh< zsT^b1M5HE?;|nv<4!D{`yjEu8`Q`aZq<>*1o)g9;lld`O*oHe>lF7Xhx!BIvJyS^W z;v8&$s!s~3PRhf3Z|XvG8WiW^wIq8|NMgTSy!Xf_w7=!&VS5tPQpxqCTzqa=t0Nw#(aEt7Kc+v zTUil4H>Wpgr0Ms3eD9Nbr<1n&Mc6kw?Mx;5tBUdYyWUPG26Vi${`0m|2FW;Agnh4d zn>6xTQiAVpSnmu{l30L!PcJBqOj%We@BQ5I3^KQQA@`|P1dE@ zfAm8sZ*o8(_W6g+Gs*m4MK~_FmKo&Xic;)*$r_o&)vOT5h<;E8>369V`)yFjH=-6_ ziv2u>j`ud7OK~iG{zW-14~uZD1@4o>pYW^qnFhO)A%_!H8}2i0wqTzvlvRz7WSZ@7 z-Q|>K1LmF8a6Sp$FNd2aS1VYZf9bJyyKUgyhj|Ki{=;8oaOprj+Nxw5@P58X!Ez<{ zr)yRni+-UkA$g>2fRJnWs4nG*IO-rfH}hNpc}4Tsvh(~s|63mWLL6@P!E@H%NFg`7 z21l_v|N1U`p*cfZnTJNPHrt29lAyLdvHdM5gKGG_V9X`$)a(ms`?eRhXKx1?xbJ9% z^^J%%2wT0G80@3#N zwuMahBWM>S(tm$*K)ZKuIn76$g7$6~syVA`(B2s(gM@kwY{S3aSF1O2@R@u40n?mY zKFh)KjFF0I&h0nl@I7m?ifPU$8edU7FHFTWr&Xm5%w2y)#Wd%ni8ge@!YdWioc58>DX6JGU)g0hl=Ug3)V8|J5YlAZmR#tAvj^w1EyoY>e@n!yO$m? z9V<CiQwM5T)9*x58r zMxV4)F&%q#r7bw?by6`M`{R=wPCXv2Vmfvnz29r2rm2{YZJ=vY3w`>jn2tUCOb&{P zQ&ddHrp~Yhomf{D)2p*RY#~2;mWt`sxnJcp55gwZT{>QT=gZ-A^l4QjwTII<7K2qc zRZLrUmB^ue+*K9RlV9jKP1d}tVtTSHpZ+%~AFG(2jM*rMivuE6Oy366vAOd5Qx(&Y zoA%kjn0_BsOhfukmV>REPi#$Td+Z(0gIpY~T|a3t-U zifPELR5yNe$Wbv3xn`FP7TT4nn1&3bec;x!A{En+mxkKFuJ8gC(~#eK%P3c*RK+yp zQcW9}@}*40-dE>h8O@bhsbU(EKTGxJkvbLAkgD}ExKaCC#WbW%k6*-H(G};D-HUz^ zt1;bhp4n{vn|z8h#@IZvx{la>?uM*vLTbp9lJ3aRjw!Aty1~ZC);_3TMJ8P^#yu|= z9V*E~2V-P$pIlQ;{3mrsM)!5fbNyA;70btQrKClhE?9r>hhlP=bj0(71Q(G=%?^0} z(W?u|JS}~^?%(s?zvf0OWjz^lM~F|Zwx}iUf27!c%?>}wqgy6uN7eoyzA=J5B)x)2 zCkpnr*zY86v`~NDw^B0eau2M(qg@FxSueytw+<*GYva3Mxj|(CiG_}6Ke(4qLIxS4 zeQ0JqdFR;;S=_lf^`zB2V`OokEhr$`2XwK#OGZBFd|D67mma7mk*3{|*}L#=9hp_! zoiM%EF{qCG(d~}x-!!8-;^N;OS-~$p)RLXMjFBg7F0Un{es)LB@ZF3W@>{0|GKvS* z){)-I9>@f4_M(P-voJ!L!`G7M8@sQp zCQq`Bk4ChyWo>_wj@_lm zSU#^?Mdp+mBO}@~q?&lrSZ=2G)Q}=XX;DQg21}6KjqA~KZ zN6ITm?9obJfk-a4k7tXOG`jPC8tDoMxBJ&|#}Y*9J+ ze6%||Cq3H(zjbr1fLEbLoP8 zKmtXiS9u5Q!xH@>a{NOF?Eia~+wWsuWlYCJpk zhs7syd*WL>PsdZy*J1ovjAsxEZam*LI%^;ar$JKC$sNI(O zlsfFM=1QsE`9VBs5?IMGF5+kE8?>BU##vK)bw(V?SW$@Oj`w4Ud1^M+-}~${QCv#H z^So~MneCLGq(Y+#ZmT5uh=@gmipspqV@a(=Rw!8+Z9HW+|4oEB5M0^(d3EV zXU>hbVI+qw7Blk?f}9Lr6%cR>s(N=)F+((<8GV#ow( z4ChGirTTR=+444#WBEqkFOMOW-#>FRXn84(6A!tR%rPEg@;jRE-6w^MqQ_?5k0B#h zf8`F)I?cUf$WzaB&Y#xtmVG82zNT{@X`RvOF{E0Nz+Izt8V<#fciq2njHkD~9I1mSaJihI15_G^gt{*da0OOO6xSA8%M_26mt!W0iF@LKiUDFtxUCM2xT!@H6U&*We zm1s-+<4MTADm?#LO`0#X{wJO@e{DR;si?s=L=H+IYbO1~c7E_lAVD|lu>GC7CX%e2 z8oYPe>3EX=s}ir(H6?*0t*FO)pWP~fRHXmF_DCr^xxD``d~WqklE`|CI()V_s9$&K zs%mWi#Suy5!<^sv{JVZnA_jx&@!c(VN+hQS{=|F#`aFp!D}Lj<`}iP{WGDW_=cZ?$ zOg{Sl!T0W(o=gJU{=&X-_z3+c{au64Upgp-obA+r{l_~dg(wdH!oK&kO)@#PycXZx znTILl(3A%3d%5e9$=%FaeD8bgQc0802JE+5FH*^<%wO1_gZxv-jU9E^e~bpDk??yB z*ysB_NF$T;e&M)yl$t_Dzo^5$H=WLJOKvpa7@6pnO5S|0!+vW6F3m5Y zU5{g7>y>me@cb_vYoj~J;l*-KoHKXKmcxeoo;a5}_MkB*BfW6$(yp?BqCh{6<+hu4 z)&`t!E$0}EhNpg(K}$DrEVtdIoih0C6~wXJb`77bp~7Vs$8y_^ue5?QgZFbRx80Hk zOX%I~FvoJ+O_*j0yCRQpEVtd?^Z&oT5xr~Vkm5TV+jE=lL1_DWE!xML$f4(g?P%*! zKfCO}F0}WIm%+gBgJ|D(vId*cN73%tlll?XpG3Q0fh8Q%Ji)P?dLBBK@Iey6G5(=C zy_Y=(dpO3T*-!Tn%{myyF&51unGEvAhH;EVGh(t0%#R7eI=>=iu<1z%$5=E8`(+R+ z4aUA_M*nMEo^0b7i>CCp9EP8rhSxgRT@LBJy*ZYr&sAv&%n=&>w+U(4-QG;i!-ZXK;N zWP>Gm8ijK#e_vvZC2V#)!Z8-jog6C|x+|Px`TJfswFc$agB;7>x3ks~u16o{SpGgY zy6>R%;v?8sn{o77b%!{Xzi()OHEgyy%(47^-8NW*{*3)xI6e04Ju7(D@gT?Y_chI@ zdluFn;8^~?O%>Kqeq#^E^7pN$F>Gm?2RIfVSZ_@I0&VwmEPvn8e%8<`cOS>{_vIY3 zhL5vpeQF!uAx*Y$ET>-PT^rbQ zdMlpuNs0}u+qoIrka*h$;v^e5mPapDX#?50n>ZF9m_(ny+tBrRFY2W>aG`J|$8zVH zPPc*d`VAb*oo6vf4(pVwITjzdV4@uEKU$9CG@^@~#@R09SbU)AF&l^svdK+Cc*)u&LB4|vA;ga_8NdB!{XO-W>DoCbr5a2i!X&Z%}(l9{H2d89Ai`dgPMNYC>+x zzje`&v`-}C`!EI5OH=m6lXn9SL^1ncdg<%IL{e(FFN$ffWi&?2)NZtb+4p}Z5b1+` znEUvkYM_+#5Ca=+aj{JqY1LF2c9n`X;XS3 z6MLe(lq6FY7Sn`kxn<<%fxgJlesQ6kG+SuL+Sbz7(D&l#^49`=k`;$!7 zqjl){cSX~G?YcgA-AlH0h44J(x$JG+$Tyx~~Hjl3%nXk+-o?)&@4Qczz4B5X6Gk=n}nf)+! z!iM`v<~W%nPq-glD;PAQFJby^0R6|;I@=FpPSO|FkQ3p3k@1_5UrnB+_CpqNqEj_- zzHW}Z;)yk?JBdWE!g%Rg#9){gKIRzOa&< z(d&mi=lNr*$m|y8$U{C5SV{C&_D7!ct@t0Lu#-8ml&2L|km+;!BMW-hnhMf~_A#d4 zj?i=Fn42S$c~DU~StIX{OzA(t<>dD*bL3HnEUhH&eaw;Pd~QxTvD5C4Jn9<_7369c zbBr%4DE&@!ztKE3^uBH%{Z7)yn&Tc2sa^$XR%V7w=_}P`B*&*8?h`4#T}Jl2Hp4w8 z&rXz+>bGVXU$<^`8Tmx>W3t@Mea*|sZQ3_jY~BZrGIHmoIhH^CR7!Nanc?|=j`&Vi zn$tc&>kKw1C0(1CV;fpjl#olFeX;%L63WP;{JvP{%;^%MNAvM9{dpsxjC7;#mmOO- zu!MZ+YKHe7*|CH)%VRTNQ=U)LO#8bZy-g}=7MZ~zaH@>^y+l$DqVZHGEj;<&snx?(+8SaZLByv?R z>;v;Z782u@rr3YtcNUY}GrjQn7kL(v)9rc*{ilC1Y3SGs-<>)AA3rpWGHmH}8@d#d zE_bBZKi!rUk>}MW*au1-X|B0aDfZzb{}qt_BYI;0U)8yY#M5;@rvI;0RH^y;yadJLUT67nf z_FoIgvztAz{}(*ZBd_RsDf`cQ6kI?|>x^;i)TdV;Epkf;GjGHYy|C*;_ z8q&LpuEXzruVNZ<)>#Wdt`8c!SJc~r$Tq<4w}_({*P&Z^f6NDRKFVj8l2F#Y!3xT<3RUo|cY zplO>_Ohfjjx}srC+bDJ|Wq&z1w`>;0G~~l}9PC!R{eWr6Kc*awi7kG>G-U2(4vHdv zJYX7fuoZ1{vojBe{ zBdQh9@k}!n(~vcXIGUGXkcw%@ASDNPTez#3hIFY{zJq#JGXsPCIqOhfKSR=`&8P!-dV zU8)qY*6EmvX~;c06!5mwV-?eo<#r0tij7t=4LLqc0Z)E>!E=6}rGRjqG;D)Si7lMd z$WSp28QxL>FCspun1&qLN&y|hOYmN1Q{QWTW{HYv$ZlD-u&dP<71NOWljy$bw?9-& zLmHj8g|o%=Dz-*Z(cc!1_NiAf4Y_i+EqqGKR51-XmFl9Jc?Bw_A-mYxg4wkuxW}ZJ z`tppoXy6``_tv(ctS(bA4H>9LW1dO#D7GHbCsqz4==qt3ETKL=n`dgc$7G?a97g?W zfqP8;7mf74jOEjM9U#6_GSB>^bGI782D2od`B=}4G=z086M5!i9ZmOS_3b$yZ9Nrb z-+iBtb)4wlqLk=`cpH+QZ>FW3kTc7eheJbQ~W0cm2b^?cvs!xmdsH zRtLDUA^`2t84i&Dbr#xYt%kzZw$sp#Qy&T!Z6~3v_Syl~t?)#9%v1-k%X2|{U^55s z;>V%=uQul!+QW#uvw7yL4G*&iQsKulU#)+NJ>>tG$unQAs~X)G7U#_~U+tS3d$7DX ziD$mr@R#<`E6j^$zS?=S?cw=RH=g-wuXVKtsjCame6_36hR}V-b9v^g&G52^?D}~; z^VNoG*u#K!&OGz0Zk=uq8zP-~=2x{{Pq}|@$MP&bFs-dU-5))VXMWX@6Yas?Z4S@; zs*`)!!`hVDJoBsGr_a1kc_7dHs&D8sALkdyGry|y1$#(sGnZ$6)$UvDVQ8BGp7~X~ zQGVb-e}A6&RZr3VT%^q$p84sz9;f@Zbo_bdS3Ppi9#-i4@yxHPrQty1zI=J+S9Nad zKyx_-@XW7zw6_ENF7fA?Uo|(?9!9qJ;hA4`qKN}=%2_<~tC~AFz_TPjp7~WTme|9A z*0Xr#SAAP&54>b1&*B50**U;ly%{`<53HW+0C^XDc;;{Ix{h8eXco`>t*z*FzZ}()5Jv{2} z!870P{gn=|r_zgOzTIPf4&de7li1=oswi#xvjUO;-o#K|Jss z75rxpL95+(=G*NZNc(nSEK-|i4P7WN%;=9zCd@47u~QFG>*Z?{d5Ccuy+ z9PdfvG~vWmVLo~MvMqePEX*^{t+l{yLo(0e1Cy(@phaj3&*B49U$+C3>8U)65A-^( z4OO+NJc|#E4Q&q(-O_j#ADFgW2i^sy@hm>D)pT9B!wcngL-kvv8gd zMf%XoS~!1`a|UozU%2ky^V`4Xz$LphVP=n1oKN;G)B?q%G_(~y?Lh9Fj`kK`Z5Y}h z*gF@rhoL?hSiW?v4s=~7*b{?wAz_qYFWI9<_ZJBD8^ZJ7xaXN0WIL%eQcX78KM6??rdG?O<_nD$ip1xRY9N@KP$zV)+I=!qvsgaqn07GFJB??teB}Y!;835+GymYE zecDhRoW`?QzJTrR;KklFp2hMRp4JAnPH8-g<=ghW9khI&#xvjU!xU|JCQsv8ET2xB z_Au;O8qZ?+GzMvdu3SuCIJ8f{Q<={)l-)&;kR z!^_fm7Ry%`r44N+rSmM7ukdAiNZpvmf1~9S8)%(Bv@g+PKPlS7!jN>H#rR2;I)>R1SKg8+4();PWEv+-Kw=Q@t6x!f4R~I(M2<`vE=WcS_dYd87v#r<=M&27!sSCk8!WZ;K-Nxph9Q&mpzmbi`Hxzy3%@rD z?bjTo2OmmO@%dkk(uF5;gnM_{s0S-v3GZ&mCq2k&A-vy?wtA4?Pk4sUzw3e1e4!7N z4AO_9vqJxASf&RHS_;oU#zY_XD~0~U-_e6x>1p`x8Ybz3bqk^I{kozL?=6M?xy(!- zuCEjNz_MrhpxPt!;Z!{X(7c_3{eQHdK7`SGXZ;69bs8 zC5)Y4D-D3_DU7Li+6J&~r_hJfHygm!wZgc2lVAX;+k~;{J;DIeM+*I4{gwf&8Yqm@ z+iMJ9vzjn=oU#p|W`;1<0`v@_SW_5}*9RKH>a-*r@1xexe}|JjaPEEjf&-^+Jy3(K zU%=^pmD7K5;S(;z$0dNKg*f9baXce)?*t_7aoW$qy8q#T0whl5He zm0IvDo>1%BAea(97;W!`Y2@X(nRw14U(<=??F?*>VqOLrJ7)$S`}g-EI6)nr`Kqv7 z>Q+Ym*ay-6*LTEYaS7?v{1Bdh?JqUBw6wE-7Fn!kL?^Q_#B~&*ZTWeO{M!Z^)GhD`pxNo-`p=9&~8ClPZ2xx(Jq(S!qy}m zv^RB@!~A4zw2xNMwebVOwYGyb+-Wb^%YIwI{+@#UulJQf|G)Z_cSVh=a)An(3RIkjk=|sH4Jmo zMUCp^LidV>cSnu-J(lh#UDFLUYJ8LxtmvVO8uef+x_8(}2Q{iQ-7j-DP8&6Z;A!^j96AC!k&ImQC(Ft4Vcen#; zRO>)ncvEGF8a39{7Ge$?phh*fR?q-ZL)55&zi9aj1JtPgwQ@*%ZGajznyy_}F40Gg z`s9f%ROrz6LcfW}9?BtZkO6AcNi_D)?6JO}QE7~y>vBERs5OqZ;Qd|?HEL}$Td=Uv zL;bm_8Qrg%u7?`+BaQ3peMT2G>U8@5sJxIsVCPyr)Tm`!Z9u1&9%@u`4;#?< zrGpxEkDVNjN9v$PJxF~MW@B}*Z4>Ao)s07VQKLq`mx1#-9iC~_Th!0e=6ie8sHRWp z9@Uw;s8Ro0Cj)aEUDT*6>}9aEpAKr&V5trK_Gph9buEoKG&5?C8dba28aDmWL5-So z&l>bv>7Yg}+DG@u6lmi++DQASbA=9S)NjGo^uJOEHR>bE)XHh8gBo?e+!}`0=%7Xo zmr!Qc6>Ze0m73PDMWTxuRr>+;F&)>&KJ%2G=V^pCYE=D!)^PN!Hfq$D8rJakhBj){ zutSApr?D`1HLNZq^#y})9%#=Ol8}~49KWAq@`=2qJ!;gAU1^@=`3|U2ckRd_iB7{% zqkcEYCZ)TFqeeaOIg<>x8HE~k@sn?)a=;kWsFP_v+jEPYvHX&22Dwn^hV}Q=q?5cY zUU(jlv~)6d;3PbM&!!pVed1KS?%(s|zvj{x(tI+)&<@*trf)7uPzm$-A&+d*J9`M0 zZ@-*LdT$$w_7v-H;-hs!~bpVsEVDb*X^-vKxY0)Obb#S@PQsHL9*A%{>@74a=>H)5rz8=~!+W zRzP-68I0eoy{Ga?-~7R-QNw9InXKnSP@_h8<`XSld(^02G%j7aZwP8s_5bL*cw>(m zbzMp>ah+z5-)LoEJ~7xi2>aC;tvoVufCFk&_wRYcCT9?8RGo9Vr28=k)TsJRa!Ji7 z2h^y;)boh(<-w>?;}UX+$9 zkWIkE0X0ThLl${FbvSAyty$S*6>&g~YJV|{c&d*;jT)w&MU<^Zphi7)D2v803`Lz2 z(J$AZcHmu+EHk8DyBJGq&GqRt7P@GaAb)XpC8R3m3fi4s?&k(dRDs ze72X;y;p0;VjI9EgQ!)y;xiokB%N$O;)c(^>Onej3LJ;+mkgx2G~?ay`5)SmPEJm6 z#(S6RW{~y|-SORhrsa=Udf@xrWt~oj+q>d349iU?MY}w)4}6}HPM&#tVgISnPA4S_ zH+=s0zoe7(tG%%Q9Iv4JTx9O}?($!!ldb{dvF|M(ole@1nt=VY{BatQTXy$8qsy|#_?Ddkxnd&r{Q@2Uo_bNGC${9nu62E3e;?! zf11EZ{|cPL^ZZPpa(Ow_mUcJ*W;wJ$B55a;gW0pdPy< zbpz`sA*jcSEL@?Btm)Mo3J3zNOz!l)3` zgs(ikU{P5xYC=6nFStK71T|q%6EE1N2tiHg`N9Gz^!5T{qhS2L+uG6RUlNR((6ZhG3etj66J}7x!lLQHs0jxj@r08p zL8u8YyLiIhmqFMMS1s{?Au++I2|4=iHcSmhO?bbBCrrE-gqpB?fCp^*9E_UKx5OP3 ziNUA|cb|3#$)aG?gzcAkz_Rl}s0qW&JRtr;5Ng6xzV1*@`vY6I++*ktT_S=}6Sl~r z42l~;sJr&|a0eaD5Y&XZ8E$Z{PY7y4pPg>-CM6g(p(kZZZ-@>;P3YC!9nKU4q24Q; z;s&o5hoB~W-qHU6VB@83ig{q zQ4+H>YC^MKE>M*dhMKTzrZZT*2t!SHvA~(~sdl0!ER(u` zYgVEr6re)pg!Tn+q<_UNjf5Vf)a?UNo-D0-lVZCH>Xg@*I$ zXnX%>0tYrq(AMQmVc;;Ko&TBx-(50+@=-rfLmJqbz?Pya)RwwsQiwYD6E$b+M^YHJ zxE8gj<8>({46jFxs`*3;CLMpHc5PlI1^w(lSgsst0{zFRDcO2#hbR-MFj7~tbz1ci zrZ6gAUCGvOCzqH)pS2PtTh~>jn!wmam8kum%`$;a&ni&+?NIiDr(Y#Xww|fXHig(R z8cMdFX?4v6bo*7}H)2qr2^_Ag#P81La1*Gr`GMb>@oP+A)UhAx^to;5`xC#*?&qW+U;7ik>2OvGLwu_6o2Z>euY2?- ze$$IWr0^}J3cshdAEj`uT@C7i-aDi)Yin!34cLBrTN7|`S5vZe;|&2)$b$yF_t9=9 z@NkEklC3!};!U7WlA4mOOD7zZLXel5lCAy5g_uBWxtfx#T}RNd{L(>P$=1Dl-I7B1 z9yKLfH|DRHz{H;FO1AF3k@lIV@70uS&3WPn6L{^Ru4HTGU!Ryj$^~^LuB*4DZMIWa zvbF0FT~p|IS6#{0-rsAQ!nYO@C0n;2-=Ef5s;*?~mNYjbq-Clr*}AMf+dhk*w=uAp4;Xo_|J&0*<|EgSOgS z1z5Iit7Pk_mf>SyN()`ImDTi3>E#Q3-yTGb>NeO1q;LQ=YU=q} zuvB>fHR|8*;$QFUTW$bowmE^%IWs%};%*#8d#!N*^@)U|eSVEU1kOH;_N5zs@G{~c z+AkjaLXqwPwDWHJz>k!DXkV82z=aWl9WM!hjDVAntJRCLZ`C@-)GBE-* zYQj5znD;dtHR`W4Klsul95w3s96z|>d;~S>^b7tl+anxxpk1UNOgV4_HL7)}AN=Zb z1U2f`5I^u*b{IA4;R*f_J?V&`QTzGBuB^kTKY!6&_N%-Pqeku9*AMb8A3}|~U(Fw` z&J*g?N&Mhg!y(kDJz{(z=JX-dsDqyRfwptGmV;T=?B@*528k$H_#VeUOb2zRjbwqti2DSMjesj1LyA?5Pa)T zeBn{6gQ!u}xB3Fma^_pt-s}VM@dr?&Zk^@>E*1w+qn;k&3;Smtz;_fr+z0sZ1E^6y zcK3maD-NJWP0{uNO`5!d`PTE}X2C%D0o14?-}rz-^nTQ+@mFU-wb238s4KSlz__se z*k@d)()0N5M~!;4l@IJN-j5p9AY&Hw5${Kh%EtS6Pi>rA*gU{&HV?4*f!R!>{yj$- z9-09iGlco-#f6y=|5C7f-I@hj+XZ{mbsu;j6>P%@UwCuU0MFlhu^(9e(MQ{BfIoOD z1^Y>~KUmJx!}1&#Iu|Vw<~qBZ0q|~#4wgF=2f&no_GtfWE}gn-21I@_K&|MuY9{n} zY=9cl+j|zw3Nk=#nXmAHB5MQGobD}rq1SVLC5r)Q_RJT8W%^1M0}$uy2O2x|u-v8G z4;IDfV*NGK{6Q|!#q&(LeVvxF;P86?#}FVxS-7-qu$#_Ri@lI*-lQ zS2Fg_?=U~;Hc21r7i$DS&UQdoAQ*`%NK{t=bI!!)v^git0T7Ai zoU?bj&zbX`d+S>D)~$N??pO7<%G%$y^Yrxebocc0oHO0KOepubFv}YjT{oe;WpTm; zSmA9-=RSCQLx*)Hl($&joB-d4nNrR$aJ@Hdi!h;_$MmT;blPb`d6A2YH#pmvQtmNO z#|KJBnNaRDz{>|}&o`mGD>~L29NL&t-m<2*5A1g|p}ecX6>n&0WJ)QE1swTGhyuR*Y=D(LrDDP^d z?+XX68{6XZ?rx$FRO~aMoXw_#FASJwVvEn^KTYrj11A$(eEz;X$royau`Sl#sW!w9 z+BcA}cA6hFJ!VAwtIYIc&sL0x=bSZuET1$Y8492IvHmGWBwDdtt}a?3=R($tXlZY4W^PqsCpwa=J35&o`aNPAa@jt#%MmHxy>OKRqje&&|!E2Er=|7U4aSJ9Gkp1XcQb368})Iy0GAjG;cP0cPoEXiGcT@$Gq2tTL zJ?QD{4cNQN5>8rc0Jr_h1-u8{ytx6myebp$9(0vPhG11g8nZpc00Li^33w0sQ5{40 zvsfB)Ho_E6W*5_3J^wI;%FiCqTo>4TQ|Ip$3;15W8GHZgA)k_7u2fZY=E(AU(74RM7sqgE;sqj((??J~5sSEz~O9Z?} z6L+>QBsDD)@ZIc9A$4KwxDo;HK_C597e0?E6Yw7Nkg+^VqvpY&_nBHqh5&`%)_4J!t#AdT^?0xq$a*G92|_xmT%xcMw`V z)q`oGcaa9&{sCf8KFPxq$beFJ#q&pP$PFya(Oz zp&qn(TPol^h-w?_LC}_R0q=2iXjBhsHYyYF9`w}WdNBB8xq$bezjf4ylO4(hyhk%& z1*>)MS0>;+=w+kz;rp9%0q;St+@=rboXdq@Y)scP_2BmMG6C;F*W92FyQ)+Ocn>Av zS3PjvSSH|m_zPy}L$Awa0^WnZzegX|7M2Nk5BgaX1K8qIF5o@rmj;IL#$CexF@`Xm ztrz*Htuq9%q?~xp%{PRSbCL{6RgK`;&oYwpqK6Uuij?HPGuH?Ta;3GqFE#|%Bhp+= z6O5pdx3u;Kq9M%LCdrd`)d*@>OM3hJnGsy_m2~UV(Fit8lH`BU&lsZam685E*n3U= zt4e!!#+QvBAg$eeu`%@BR7QKZYJ(A&wvhA|qcH{(e`()moHd4fv65}n(J_XR7fVV1 zM(s?X=aW*hAD>Pppsgp_UV1NMn6*aQyXNCe05+A9?YYl3hW8VseSeo|0!bqzyIr^1 z1STvhA$u+;GzRaNC1gJ_-%MaTl#tCYeQg5MDvHT3qI6AQ?%oozy-w{-p?W|G`G}#t z33LmT>~_}QCh#!7nC!gGc@y}xqFC~U{-z)blCLd%-v`cp9YXQe#KHl@ZbK-RZae3| z>SGV0*i|>&0bVA#2zZBO${PoGwa7!jJ1j4{IKt1g5dz*}Dd_76gV?ipyuIMpUhsB_k1JrYxB;Xwub^QO`8L?!xBbXi=O7gsX z=Lo`Ncfww_ec6475ri{`_Jx*H#}J;;p)YtZ@FpC0(-E>q`V&rMy)aI`ov;C++)&kmqdBR~jc zV|w&=VDFwy67ass>zNMl=2xJA_f3wDcZ9Fm{sP`N*~Ro}^u<-prst0q>ib zEp!B}O%utkF7I>ztLXs(-Z$x!>-^Wn~xU`F#1MD|E4pV=vk{-FOth6h3)LKdBYu{iSAe- zi;el@z2EKcV6}cJHm&9Zgd_k)NzCmJvRaGynL$f2>020?0DxT zr@ABfP4*D*&dax+jAyV5*~XeY2e?wlMZkO0Ov`e4pVW;Js-*=BK?)hYEOaIzO*KY#KC@{Q6>-0x{~`NXf6S-V>`Nk0Sez zROL|{Z~YQ0jvgU;K>8CgYCsC%-{n_+i=T-%e3FTO{WFyyBMu0synQN~?@Si(ZgSMp zO6)s65H5^o{U##o6VHK91?ao20mwgV{dK=^kt z>TQ}m{Q0RJ@gG{NH_X@~5MK7p4%#|*AQ|=r_JS~TJHo?vvv-pMde9i*d4;&d-kRjO zRr8@(u*8Pu+NRRguTl3z!@%J*KHc)3*rT%)e+G}fCl-8>;?nU;_rz%hQq0sWVs$|u z_owmS<`;-o-5m*gWfY37uJt0^sBMv0amkKw8he-ES2s!KUYkqApZeBBAG@|poIKl- z@bC82YjS~D<-st@A&rI(we&Xhw|yHp?sY7e0ta-(0N*mV5>$|3vN z-xmk^_M;p!erS={YK{ZZ3lbiP$pyV={1~kgvE>GP;xi_h)x|w;OZ*%3EfoyO{7fsn+B+M zwb=V*tY()Lon>L(Wn!t7HQD@$PG#cG5*s=nwdRzH1>dd7ziK&`iko+`@_EeOjIGMW zhNc3YaYd}YacY1K#m4jJ8Bbq<&cU?U64ABThR*BQc_re#I9tm1X1yvEJDAy0zUOz4 z)k!WDDBl~ivsf%mw4;1)_tH|a=0aOKa}V?_7JE#wrJP}NgHo~cQ(HQ(C*OY{Uaw+D z`NqQX2cmn1J>`2IP9?q_u0>*GVo%EVPR}h8^LzHDJgNt?pO;m7QNDL7?Y`KzT5rnt zzTLbpHrUyR^060l9*9%c_o95ykJX_yJ=2?Vv++$Ih{d+ODc@W5tx!yl=_BC1>GgK^ z#g=Ux1ud52)d(pPAFt{|dEgK4La}jMM*;6dAIvNiW5vEgH8y5Wry}vsUJjHWMl>!I zGb;6^F)b?Yi`zdr2zYP0eo=uqq)?*Qu`3k6j_*(Wvqsz(PtWKp;N9oReg)#3^!_Bn z+nWXAp!x$y{=)kAMQy8oG)CxJAdZh>?`ts`GK&hur&anBy9ZWjh+cjUj)^jM?z_`48u^Wrq_ zrUJ3X+rgy&=8f~kpLWhr$Xzw1^W&G`2$o7&l^Tp5Zu4JF(?gir1Eknr$ z=KQ=T`r5mZ4UgZ;=CX4q`+wV~K&-#Yne4~u`#mwRr#spIC-VaF{yZ15y%p@U9=$xs zciu7neOh^vPkn1yAci`-kqr;i%NG-S4I{ssbv0kSqcfa*vsw$LD;8Vu`_5}7fA5~d z$xj>nSs=b?<3YZ&%%XtRqv z>SaPXXSS07PkNY8&N*kJ0J&R?Dd!aC2vE4yi1G@9uQt$alo92e=Z6bmESOQwY0^;u z!OWC$P7^Z$G{+1m=RC091}5(@pq%rWu>g~zO(^F)^@!1n^~tV!zO;eTO~#aS?mcJ& zHdXW~M>=J01J(5PDd$|u?oFTmXh=Edwq7>SXq+D9T^rcFZ_CYklylAruz?os3@PVa zQG?wd-&~h+ws)2`@b@?-1GBe`^VTr!nJ(pcbB9`ky>ng4IpMlBXuYjRIp?>2)=+y* z9m*S5v3J^?JL*!-dHHW^$nIN@a?ZBZt-(-B8WS|Z8e&rQDChie%nE#G>(FPXJF$1* zJJq3_GySC%JfBsUa?W!H*d63ox|DN%WPP7YLTi&eKUhuU(g`}0b54402`|lRll+gS zS;4X?x|DOi+h_@HpiOIcv}LtzkJqN0b0h0_mYiINa?Y)+2J#7;I+Sy6t;6~^wb3Sh zK0UzdP&wD8ob&S}OGtdILpf*bQ>+fv`&yK9YR~Nf$IsUyzuwWL2OQF^O*!WTR#W$h zpAO}mXEyf$ZA%@>IS&@G8pZ2sk!_4$Z2@-QwJGO3F}er1>g!O>c{85Xq)o0xap2%B z3&?m{n{v(~R`d4oquP{nW>mHS3$|X&IscQK>Ob*)^*fFKws*_bIoQ7;?^5Th@7cTb zmAVWTrq)_2TxajA&->^pw9@~--%0;(-|1H0VOQt#|Kx87>bpY!?fXIM`%r4z{wL2b z^}Vov+kIj6@8180-@4V$2z)Gz!Tm=e`N(m0SK5o+l}6uD_e=V3_efIrgi_ZH`zLD; zs%!QCx9jt(`w^&XZv2yVa?~|@|82F?)wR+74fW8}b>zl0|0I5#)J()P7dWBSHJ-#n`9oJwzmT8Wxhqd-m4c21`AJQALYaY>HJ(gF)`oQs#M>JTE#d)*? z?9)D`!FnuXhOyrmtDe+gJ(er1UvomIvl^_&;(Dqt%o=(@gY{V4Z2Q5uyO(J$b&unJ zvQK)G`$J);RSgl}&uP2Q8DyFxZXH-SJ=3#CC#Po5BN{^ z^z7$v%ldU*BpE8#vW1GzmqdIg{7aMobCz8Z@m=xQw>I$nS)PdRkhkf>>QAy7(D-io zpJCSUv+Z>e-}8C0+Y0V|U^TB9*1K#8gTrnRy+cJ0NH~9k#@G33!Fre6AU+{_tY_ca z8^nJ=2XiQIc7x{a8XG^M#JV z0{P?kZNAXCsulTT)+j$X`O%#GF`B)f^Uc2-`J+n%_Acw>F657&O#Lr#NUFdR`r42_q$P#-J0yZ zzHx0WM11~eGu0b*CR@^6E5FWFWYE-@4_JJEU_^n&4wP8VA5z+b^I zrlKpYx5?cQh;lWj^^L2x&#@T~>3xqT7l)QLtgdUDElfPf=hxKA-H?szx+C?p8?lJfnIv zOwlePJKy{v3hEZJdyg#se7_k5ZBk3fFLrN^g2n^N$X`17M8SLZJOJZT3)3j*YVnZ9 z&pH|j)dJa_WERJ2kBWq~L63?5wYL%Qhxrqlckki|5RW_|dCrKDu-)!C?aSD9QE+wN zGqT(7@lg<3_LS`T==&%Le!yx?G8@Pn7!5Hy9+UmMB}c>Tevim6rr(N&N=GZmU)E^F zK!kBQ(cN0az!i^D8b7Cd477_ZCO&r<{+L-r{QI?xf$%4VH1E13US@_r4T_g>%xf6Mz)Aq<68@_yCVb%vYrJ~};fR`%C>gcEeUexG!>m93rYw)m&B zqT4MsB9-&HL3sq+|GO#q=7(DmFlrROT;b&7wa7Q8w2c4{*E-~z0dK>hutPnHMa%QTVW@)<`KITIa2OG6M!s3+VmKtT{w(+| z#F&C`FdNc@eAD=SxYBd{q`@jBAA37@6(kNkN4a0<(^XKb;3VaKAwIE?w(c0^ew7}@ zg4IST_tOrFgGrT+Q10jaCJt;fj!^CwG-EaVk#mf4zkp+_A#2SE%KaK^$18c};NsPg zRQV9qHC^t#8b*)Wr@?nWf=l9{qV^sQzWcFuL>%NB?ABoHb-ob`PZ#Xg;JY7MPO;$I zZ?6X5{djbB6(so{&|vH}8@USfPG)Fuy_WS?L0PpN4aVNH_g8}1A(7?^zqnU9D?{7w zgJ}5-?Yv|k9Ffmf^DFycoqXoD*4Yn}+DT_|y3KxAuv|K$1+V>3r;c=Xm-+99XY!eT z(QiN8kk9&H_x(`yo0J2DblVSwa&F*WWk00IIYZ2eeM&Cz)9iq9R-W`c0IlUSR4@Dh z?3K^fiQ5jaeqPdEV!NCJP)k0ePwqGXPV(8kJMsW5?=GF`HAfr(U-_&z zZ+HM&$T>j5wf*p}l9U@PTCg8#$T`EP2K$vc*Yrdv zmh;ckdWqm6=cQ&j3GhPBSDytXz+yR%ecmAf-pcvyg&*-s-a9Td9)9+_O8!-8UpyGF zI_&s9q}_{nNSJqn;_w{H1i(I{80TxON`Uu9w<&H9e3by>8nE7?Ra)DodnU480Cy

RPYIn^2Vnw$tJJ+@Ju z;f!sG(6IP4)ft}fJ`sA|E1^2Wo-Rp{HRCJQ8NL~x1bTT@$xqkhCn>d#=Y}RLeas)m zCxd@GXB%8Es}=+!O~={bceL7HlR@|W6zU=Vu73*rH9mxTh>zNy0;85Kr5@rrMr$C( zJ<-#?!-C2A^Kvxx=5T4B3|@_vQE!fG&yt|a&;`_+qbsxX2KIqA7?&LP zCV|$6vDBO6+?FJzKZq{m0Pp{Pq)RT$kozV#+?EUeazEwk^))c@i_~X1DoO)??2-B} zzj~(uf%TllTxf@z2veM-e$8ukiV*BB^>Lo^UWEDSQh#UtE&xe#-)G-306*n^(9R11 zisU}gxiJ8|uk`h?M}YT!Dj0eMwB+7K*`1GorQGvqQRO2LEcZfkKE+-|lzSxgnh&sO zp42-jpasA)xu=rZDG?6Ky_Uv#iLguV!LnDW z?_(9s*2{m#@G=K@x9}4EzLC*C8+eb@5eC`dD)$gvmX`(V<=%qd7iPg~x#!^W=2`HE zj?|0r@sUjE^jhjs_|zp64thzw3j<3sK;J>?X_y(50XyYhhn+ti1`oLhqOjyJyq0?- z_B1#Q&ex@$iD^3y0q?Q6!{{*Zz6k>s9)`JJrM>{&UmS)3a=(CjV>7@)?jsO=GXuQj z{sM#gXTqJ?Qs04J*_m)o?nf}OMHXbpeG2wQWWgD^e}PGP7DUK>4a&P`LyX+-VA#BD z7$^5Z$l8|;y#Gbglf%G&e|yQ+&VPS%4o*>Ovi1F#43<`g0{Y|DsmXA9v7vzenD{aY z+Rro+@HZ3l8A;H%rc@6txia(j9%cgdSN%H?^xicP&>w#|CPMvIjRo|_p=OET;@VWe z_;c=Ef>JlndP0Ko?pFH71n4}3MyJ zUM$w-*P-Y2cTOfje3p)Yd4m4HWJtExq387`smYKwScjh1UwWIYyfcuU7pK%oz7rV- zi;ud{de?f!!R0g$TJL$QIQV&B1g*DSmpHJ7A8Flr1eJki-l<8iL~DQCb2NJnm4WY zRNYuuaeWNEpI~4V3!W)nwBAvjW5H`0t7psBdwFaubeZc)>pdC~3;SC;(|S8)$13mT z{=H(WQeQgo!B*I8EY)R=7Pf(rT(9-=#%-`muH#xwZ#(pq>$_H6ydCxmQr*|TKW>LB zay{78z#VX2t`mE^Xa`jPD%FG49ho|_AOyGV7$><;I`F1h|#=K5UdBG)Ag zpOXt;r%Cn7s`So<_HrFF@kb6sSxEKG0(R$sr(E}}=Fl9NCD%h+^)wsKOp)rOeGkco zj&l990Xo^h>#bRK&H?@|;={BYI3vGnm#mWu^W}H&hEK}{ANk!p+snD|Nq%R~`40_j zkl*FoI$i_k<#+s6rDz~te)n(YQ4JiE-wD*Zqk$9hyMoV(G*FYhQ-pcZ-P;=A?-tHE zq5=L+Y0o}6pw-Zkboi!MF7W5hIfs~R@^j~wqcET!Zf-5#;fb8@MXGGm*Z(}Dy)+0 zb@;`n!W_AdN9|Fm@IkKcG2b**se_aem6hNf*x&HZ6&6M-Fw26ng$&^hQZ0mBwFv8DWRaVESc7O zX6-`gd^UyFyRtL{w)B_o?Ee}V0s|}mP3s+)9}Ec<>uJ5UVuRuM<5XI&{+wWl?37OH zO`RMJylz1CZS&#V&Qy}26z0Re$n~_|y_FWg%6aQ(y%|9ZU}*RnT5s=P3t-RDWLodw zj9|#?m_+M+85sh%?kCWCQ|2s$GdJUDy>|^l;n}cwT5pHUQ0V$&HO+-G@Vm(`LW99k zzIz*eFc=QYcXDTIg+NdFuI`>0A+TJ&!`tO&2sD@P_Ez4w5Dv$@(5KAp_S{!=4DV1;OEi~e%*YA|f=Xljdh)>d^2hB@IT zL?5|r0pwjUrtwDB?6=nMM#N|Pllkn9l@am(l{FtS?F^-P*&da67?3%DL!o4I6xq_aRnE}KHFv=Fn1(y$5SHhtprAn4D(T95%_Z+K!DsA;)lsHO-;59NQ;VYXNuVm_Kbr3*{{M z{*~4Ckz;SK%?-Xx1F2{$j?5;hJ8ydffil1I$^((la2KHfh*kwOe-!=Xx>$L3M>!ZZsIfqz{ zi;eN*r_HwdL7TM+lNQ@?cq z@Sx6m^3x_60iZWx1NkZL5kFtly%p5&N~!O}sr$32ZB^~#>bi*Pm=k)dOys{^sNaA1 zsOmkfe&0#`KB4+O%-_A|_Pghsy*Aq`zagvNVNkzMqJ9tOckc!L?)ioKnVtF>rTQ7M z`q}#Lp7pDLZ&yEG_}%Z5>SsXeXJ@~AmZ$#RO#M6I?|yUm-S6<~-+R@+ldHcMtA7Xh z-S>#!{hp@&-A4U;*Y9#>b)KfqOV7RgfB(L${$8g3KD$f&3oHgLmU>)z4S?dV8p5^A z2f>@sZwW87a)Pva2K4^?17}xQJ-aR8p`(X^=XUA-R7{W2aJQBd(T(?e!|n!Ngi{g& z;dSVE!jlh9hn7F2JE48@<|*{?Bf^yN+meaAi>FQ_jPf`vSVI`) ze74~LVU&M{-!a0tuA*_L3FCS>9reJ+qkcFa)EnoI`sDMXp1C}ze=g@|wl7?M^?q@T zHMMXI?j2&jcZm7kA?ACBnC~58zITZE-XZ3DhnVjjV!n5X`Q9Psdxx0s9b&$Bi22?j z=6i>j?;T>kcbtxE=i^Z)i22?j=6i>j?;T>kcZm7kA?ACBnC~58zITZE-XZ3DhnVjj zV!n5X`Q9Psdxx0s9b)x<{qFmn-SVZ-NpA&xA4#!X44VUD39G-SsK1wGA6Tr^l(XBp zRH-%hyPQOQ_NmW${LaPmdG+_8-+eC|)o+i8aifFIQo+93L2+$#2LZ8G{bS-6muSMx zOz()7(nZ222YnQebbUfNal9_X->PAY<8^nnfU+qjgy*{0!rPb4B>EapaR1VVFz!*` zVeJV&s#vbjyVhdQv*hs)N2V!!nlIX=@V9N80eoH`)}oWk^J3Qt;Bx-a7l#(A~bvo;)q^6biaK^Wz%@TvkxNBR5t z)*_7SvOHazur6CKr=uSDc+?N)gL>oqQJ;KX)H9a{_0Q$Rec|$}_lsk@Z>?Cc13fh`G%p=DvWK`v_w0 zJBYbYAy)5K?UDP)?=YU+s&`mSFl(zp9H)Ci9Qi_DL_EFXu9#Umlkm0jPoiz+R>J4% z)P*0s|@(rA!j||`W==z*KirZ48TO3{`!{FLDCM3n#>N`p{i?op*TC$V zQhyWko*FpY*^9<|T5909+z;hxBMnTF`=o@t$%WgerT!`F+4BM|xvz@8PcB?fl=`hC z)nLyxmP>tD8n4fRgJn{Gmh@IRuvhNeVz46{hRXe1bn|v8Jrg^2KdAJ#N^#Eu-uLS7 zR$G<+tr_84p=4Vj$=Uz?R#++b6MP-84F=171|6Pkg9y3*;QgTOuuJYs=>BdyG?)7o z_MX23X3KpHt$*!+zkfX-o>xP6!dAKO;hHZD%l!~r1?+-7a-YO=E8>)%us`(U;A-(u z`t0euu`qX>JK^@3v2fUI1mSwSW8wC*(S*%3u`nQ4>KC@PG!|O3zNHvjwlM0&A0$F>n_$Ax?3r(^YjF=L^EUEZLco^n~!iZ6XY~T2A<-Ho#k> z2ZV#h0=O){OE_;U0Q9*=SW^fPG4(v*Yn6^bwNA$ge>7SP?-kqsRx@xdF8n(24uR;B|SgwHUABqTTA6^M7>YgJU9u)!aOj^p z+RhQse^n!*I}eY5WjWHm*PI^#$0|woaQQEWfJbSD-nDvBt8?mB!cJn8^kB`SOPS-dYy1PuLKzAca89YDhUvBE|0K9PCWGc zdYSOn_WPl6<}$)X5n0-6SfapE*wW#w}QRzH_n^z z4V(S!H*G({b(idi^8SH@XXWgN&TXa;&b_}MMq1AxeCy?Y7!)vv@V)2k{lF~?2-m;6 zA589q5`MXVKV18;i15xi`(gB>C4>(Siied)f%b7+n^jOh{W#$^dse}M1tQ^cn^?%s z%qFaRJr)WAG6^?l@1u_1ok4g`_0>U(KFjN#ienTn#%aX=seP2kyV2x2(GF zt-8P1@A@jL`=k9E`i`l43H_6O8~>9Yn*U_4^Qj3|$~ow9%?di*OQkcYbDS2Zz)SekYc+40pD0N#)_{lv>$nU^f9J2Va&24bF9EaX09_HjZ%2^6qfS zIfiglpgD*)mJvSI&H_#^4<=muqy_kI3?%%y1Cz~rIN=_{dcci6g9(4@QZDi{t8npk zk)LsM&s-N%J4olqD~}uErODFya;)P`F{rn6?gaI}B^E4`&ZAiyZi{n_rE_X{ySw7L zYts4k?D0LZMT&H;^}SLcz8WT-cek(I7d@&==U|Petk>A;Hzbc^oldC_IYZBU@28xtJ>Cyc&fF~xhbU+9+>3Tf z+&)xc4_^~AWMXog>BP zx3~L3(2!%q=j@bzaQe+j!rS`SP|mE_+SQaZZtE;9*dU)HU8-t<-bd+tDLPyg?BsK2 zM08bnzF9htT*IrvB7f+Y7oWIlzwL&6IPtNxHsr{w|$hr{oNC-`c{fFVcBEZ;UO}l+W=g zdj)vtE1mDX%WR+|PdfMSR<;2*IUlI6YYi!Kp3qds3hFMG@`tOHETK=KgstB&pOy2C znWg6N=XQy{`d)YVD(5GqMRVb1*LGwNZ;an|CEVc1$P?k1;1~T{{d~&a)!yWEBQe8VH0Rj1GelrFMkBEDKWRJ-Klz ztoCeAbkh?v75oS5dBMkTXyXGNW?Ivjo_Bn}c#;L-J3D=0UYR6A_f$W~c_GR6b}#EC zktWGJ;f6m*Wlube|A@J##2r-~Nd3v6D_vz3xN8Yr8nXy#D2cFCHHPDI-e>@0c|N z9=R10t}|o^1lkl4&Ko#{J?AYXe16IhX#edVVf(ZQMV{Utf?-GT8=|kB!g^%LSj#P_qIvBy`pNQ!CATI*RdXH z;2`$`Tj8Dtt>qqJHO8jFY`J&XNY6B=*-h#xrX{37k=$!+x^5bLl6#Of%1Z@Txi{I* zSBsRMHE}=LUL2MBHGJEcsPwFH@m}yheI@2DfG+-0?}h`17C@rh)1je3FzCv?9)=_Y zLo2xl#F6eH;4k-vsCW|sW96O^MdubmrHxWA373pe)*oEzG0}f`7+A}_C*Ir-gST=| zib1}MSUqiN49bJ=t>J!+UlFGC2I}%I6mF(Ty_@-&QQ?_vd~5^gei0bKcG(W?kH_Z}i23si#K<3?Yar&&I}oEh_&fzMe?EekKQ}?lpQj+^ z&sh-j=P!u)a~Z_^c@1Lz90xIfzJr)Q_d(2`2O;Lq9T4;94v6`?0f_m#0f_m#0f_m# z0f_m#0f_m#0f_m#0f=#3|L469NpJsO-|J|j*`@T11sUjBe%m5xsOIx{x&-zmG$Ku}a^N=DM*;{q~mURw;Ge53gIL)O**DTBX#1 zKNi1AsSiIVdzDf*zWt|F!0XA^9}=t7x<9igPN^OJzGSshQ#$le(*`cx~$Ji#ae{ zuK#TQS1#xpNOhr0f!$l_F4c>^+DZd6E=%u0=`Yj3t!q+!>D(I{xFpw|Hq;j(S*}Oz zX)i)OxlZ-F5hDEfEY+_b?kz&2PEuX#FO1$TK&p4`U?&2v8E!Bj8+dK-YH$#E&G7vd zN8r$i3pVJFpRXT*wO6hap0Vc$+Z& z_TvwPvuXe=N&ZT>*(wp9I{YMTQCEaj(<+hu3}AOH!@5=`e4vU3vPMhz*!*1B^hz4z zX1fL~O*hkLz0y*kc33*$IGq&eF=##Emdlf&%erL3WqQeAkrYd~@%|)eF*Sm4f^QPk zIk%ATaP}On&^M6q#U^abU!H{X*mIWeE42xq3rU14n)%kKlj+3?;Qc|!LA(67HLK81!3qCOq3M14b1{ShpYpVt-0_<=9M^ zzEZ+-O4%L8s7^F~!ssj*^+Doke?1Gd@3telp^yzb?Aj21v?d!&&Hp5P^hq{!J==`% z#x^-{y;5Vs9+yS9*g1*hyq|jnieEcgqx??G4uJLar8MT@Wp<~2(_+G3v<|}FLt%ui z+a82I!$Jsq*&c+_4)X}>*&T$M-)9omX@3xw-=0diPmP0c=xPw*jH~Pp{`ZN5H?w>9 zk^Vk}UAi3r^S0v&SIXNDx=v#VzaF(8jGv4oT-+=kQZMZyncuEj4K){RBfNyY>u7#* zGvUfEad0nt6X75GVj*~fM6aVC3j>dACHk)5RbZaIlW@KFDldS3>*RS%i0= ziDCCgt`lDTG73uGJSF_>V+7Pqs6_I(&5nR3d#V!dP&0z{d8t7-abGz5u2h?_?v!wN z=%hzDuzxr#wKXDqN?^4n2G=J%c~Cff8ZPb2=h@*9Vc&x2y{p7StDjd1cd(9!39qjc zKD{^|%5rZKZj~PotvzoOo@AE*2aen!e0Wa+{Cawqu<@UX5O?by;iN5zP%)R)m1cW= zyA8X~enY}zn15xIOE}vi8UA3u_u-hJ++=9gM#5FBQozwm;UbXxHP9Fjj6K17j&T&VS^MOxGAiG2u~a{268-AyfiPiR5#i2n2f~A_ zV#0k)2SKCDrG#z94+4j4<%Ij?4TAZ(4+%FNJs5&Q9~0hEdkEY#eM-2;%^~nERLbjY z4?97vz0Zl>aQjej|N8}D%iYdk;_#BNONt-#b^bs&>Qab;T?!+WF}+7efuH=@R(GR7 zN9NhFe>B{Z=UTcu8scRcJgdflu`Juo0Wr`~mf2@f478Tl;=45l`pRpZniB*4vZb{* zWS7;S$~vjMJqBLLy2@D`qv&wTr!Ymg0}q8MIuGy+Q}*KACH8$*-lKbG7Aku;eRGJi zrxzv#D|@}W-2%l1EFaBNY~y16S#g|yt&mEIps~FYL%wg;3~&hyAf5C*xRW@Pw}Z0Wla@dyZg4g;)7RTnZx7OlKr>;WC1y> zo<92Q>#CN}OZMd^^;ivU*~d?qSwn*C`*%%kV455g*4GlC$ulWdG<+<8(NQUeB<{Bb zQI0MB#@N9UjTCdHzqW%raxC&3Yp=wp=d(SO*!AZf z&V}4p_kCZ!I+Id@So+RZ|WiM}v=8vRYYwGwL;-7L3wz&3n@%RlX zHw$}pRcy3Z%GvS^u8OXoq+IT1NS+vSRm$<+cg+)d?$@g*PvmF%sDwKrKkGX;f5`d* zNM}uAvq$3KGtJ0mzKwe<7Iu?zhQNDI#6`AJF7YJnnP_`Q$}xh6z7XrlxktO6uf(5n zPO_ul8?o-H&cw%m)H`wVF9}D?`5-zMO1M?bC-H@x^Z3Ml5oZ=kv3+dFH<9N^dEG6Q z+$qT3O3A4@wz5`ot>qQgN)Dz!%SOq~j$X4-a<ZIoOt;)%`w@KBmO6Si2iN8c+|D-)qN}e8$Bb`{V9Ie=jiwoA1L|| zD_|TJ8v8+9ZXDrz_7lOrd^O>qKK>9KkU)5Svj7l!ClRiHCjeTGmij%N^$LU+d)E@Z zYq=i}zgWUoB77kDq=d`odxLhd zgwOgRm!Oyyth~B1NGe|c4NjedJHid~lzY%_-*9@vY`a-y0|7OtW z?kB>NH#LL6f)9jeHf;`DzP=+o{djX&X#bXQMoTAna6O7}g7#2oRy~sNO?_wB786eR zn}rMfF>N{FQK#`d9YsgspS3hV3zD_Ie*Vnd=N3-Cq;k!oHbAJ zS;JcM6<KYg7+5+l2A+|w@u;Hu@^=A*xkB0Ii282K6$HJMJ z^=#9%pZ>N6(Ob`WrB7V9KUM?pAE&ORqplrv`rB$~XxmG`TGLiF6TmH_D`9m_n{iGD zmELwYuVn%6d8e+0qOOOdt|znkekQzaoJ>4hpE&?0eRB!#D>@9pHFpZQmfzKLyYVX# zc1;Vi#yS`mf><3kubMW9)pg0#b=aErONO0E->h*h51%B#*2|L#tLuXewKxK;>;@6f zxr0P_X_`QF7u7YU)V0Obb-Fq&*T8|s(Nr6}WB_{w^*~$VpH>qT4a4CtggZ6TfPG(#cUQ)C$ndy z!}yY8gw?hC)b$(H^$!brq{I4lAfm3GXzhT5-!~F2S-u7Ss(w(!wfwFY@oT%O5be^2 z=6cq0mV(tab=5V5-7n6B#$la_|ME3c6|Amp>y{M)W9;4$&+t8d3Rc%gRoBH;*O;BP zWFo{|entF!OM(@Q&qVS(-_lxsSJ(Y>^MT4!J9_n%fqN@2LAP+)lnHavzz^YEp9FQP=G+-TFl2wd~Zr z54vr*C2}A6w!cv1zGJ@aw#fbEcfE3c*ZWf4vrOIN#^23WiCxZu0=sk&xJZhI@`O!=#HuyWR@YfY%@ji~E&lTs*o= z!~PPT(KPJe2(z&o_8A((cxV_eYnitO|BHXvoJh~bdD)yep8gHT;~YpwJ~#)CNB;O1 zG1Bng5aU?<430-0$P4Mn8|OegMSls+A=9l@<84%YY*hShRP)-XhiYG}=k>K9I*yB7)Q#{Biyt}T z`nMxoZS=g{viwGb=k?9Z4NtF4{Qq!!n#=yuUND-5{TpF6R>MAHjXGpJG>n&(%v*#1 z#XoFLr03umHYbkHMLLehIS?ZsoCC)ofBcJdq~X6I9mnEl5F-!dg=3I6&Vd;JsOVOz z@zyFn)++wis(Ecx^4O^4v{A`#Bh5nVLONeBj^}znK3qRGD!tjTdAUAO9^!>#nVf`? zhiYG}&?fFR-9)@_9}%PN;Qk^;o5FoZjJAgMfEaBMZ2~dcCfW~Tv{|$X#AwTCZ-}|= zBj*0a={N@;k8>bKJ~#(rh|vboP7tGQqD>%1n?;*IjJAyShM3zpV(wp@j&tzw zI0s_ngL5E8{`eO$((vC9<5-*nG4jAU5TpD!2V!|$oKF5FkEb~hqwFgFGzZcdjrOdtY`4`f;?Mr+t$iFyUr3dma&PSy;@-L(#4d;;fNdAQwd8qb<{0rj=t_$}OG50T| zp-thwBSw2ho5L|^=V%j1N83ajMU1wOHi2Wfe<2-hAODMgxPRdoq~jb&$MHA^(vc6& zfpp}Le-R@M{|zyY#m~@OvVS3+`xj#FUo!oF{rQFQ5Z8Z&Kst`cIS?ZsoCC)ofBcJdq~X6I9mnEl5F-yh2al6D9{;H5 z|LgM*raRgTTo+>QcWTVmOLV@EIEL>dV!n@v`931%`-qtDBVxXfh`BBi^L^xWoP&?Y zIS})GM9lXQG2chTd>;|>eMHRn5i#FKnf|~2yeo4!Dx5EJftb#5!i8cG&b)PjtfbXK z#bQxd-=5vSdK)hc>826vqg|n$O`_23OOEhO#|_FRCJ8I66`0s zvpz;C!jSSzp~%t$Za+*BHaE-^zE|^vt)12gQ&Tg9w_%=exZ@h(N~H{;))!A${vkye z?0s0!{%aVFU!5ZCNj@aZSTzh$Z|^&g7Y&4=Pn*l^IeJ%p`R&u{qlfc zwrhlt#0)`qfhVlBTO+*wcv!H0?+FFf*9cZ44hth4he5#R6d^X|kYK%H7-(sw2&HQd z3I~o4gR9+=h0|Hu3EDc(lQYMUQPRAD8gOxK}oHd@JLaW<6~`+FYzA z;dYI`*~G+EqVbJVf7v`;yGy_^4)*JXi4H3T&>f3mOV_hgBfncrkB-jr;M(BFe_%>1GvO zgX59T#*4@YG2aw2AOiYoai(@UHGM^Uu|M^k2LIyc zkcR(;7{}sg5F-!dg_!e3jB_$N#Wtj~@is`u@r(~) z80TcX1l&`clg&YN_WzqybZgak8x9D1J3Kf>^b4LoqQ$KvM9&WN7bEA2gqP$7iQxq~()hMh#Krnqgk!c( z66}uQL9`i(Q0~k5SwX!pQ%R@NLSxIS;l-l5eYdPaG;{!vc8FDO4-7usYqwl0CKOTc|( zbb;xC=xn^e)mrPDvUL$g`I#LO#&vNz+ec+Q+h2tbvqObH zvqNQGW+wudhuM$7<($@biXuO=LuFme4wdyHo$CR|bNwJ6t~cb*^@;OxJ)=CRf7}a{ zlkW@4kGjMCLS3Rx5u=V#*Ek;MMBO1B=S1Bh9p^;dAsy#L-66&~QFk<+&5620jB}#y z5TlLY+?;lo(Ogk-THQh<{ zjeaK?pQVI_W5&h+{&_J6Y^^<0Z{3&mSedA})lG@i-Bg^|J}5t17h!o_gsZ>1u8h|fZz+8048N=J&&kMF z<~?w#xr^FY~XS-J0v>Fk7o&A7pJ3r^6_Z5 zoDbSF=Z|*I=SBPH@}OUEIniIZ{IY-1TIa?NBJ?|z;(%So-q0}n}hU#KF#JJI{Gx5gXrkfY!0HMPqR4)qffIr2%}H4IS8Xq zGn*icF_`I8p|e<~jAu4M82K=pAdLLko+F%EMwPVU&}_T*4?n zi@AhxT`IbjYP_|IkF|=wwQ62#l|0reIjvRlv)?L}b=j!aYopSGwMswMD!o~&^l7cq zv$ab9)~bE6!q|lIg!vcdy#nqL`m`!P!MvBopig6L!tvdjh!5D!U`D5%rjPqhlL5%WXtU-*i2V)RolpkXg zVq6!eV+`ZtF}86&81p!PjD>t&jFDU(jGbIgjHz6HjJ14S7=!tGkuTu78x1?+eP0u?g3OK8-O8G5R#dGQ{Z97@H8IPh)ICj6RJq5i$BS#wNt* z(-@l&qfcXOLX19*F&8n$VDxQHN1sQG<1rQ>Mm`uL5F>w#9f)yWj46mw9*i}JQBI6O zh*5rwO^9(_oQ^S!kH^@?`C!cB{4o~tc`-(Ec`$ZzIWeYk`7ze=bzuzV>qR=(1CHnV zK|Wk>$e-&I=jD1vdAR;jPQEWFKiax#U4(JHXzNHvJ)o^4M*X0zBSyWUts_Q#qOBuF zJ)^B7M*X9$BbN7zFzy%H3a6tDA;$4&TZoYl+8ko!kG6;y=S3SujPjuEB1SpUrV*q3 zXzPe&J0y(j<>OHgoDb@U^GCh$c~PHS9@I0J6ZOyKm-mbK|6lCAXH->PjdSoHJeiGa36|p={0Dz#;~IwLI0xfef*R*wTuV^n9E@uTYIzPu zjcX?Iyj(8oGt^jLv_l%(L7vBQY+t;WG|v6P9({dbkIeJ9Rv^z~eY78W9<`xgq;buW z>*HD^w}Wex+&->d@_TVjlkLH^PPP-*K-qqIZNzusnkn}e%Vj@cec3Z`dy^H^hsyAzu3W`gkd@ z4#rEYb{#`+cCt8w48@nZipAvH^hsy zAzq{n@gi-A7imMh^!4@eBKzfdVf%)7QGX5bVpwj77imMhNE_ls+7K^&eSN%08{$QA z`EQBW|K<=QqyNX|5Sr(4tYPdh=l|2j9j@2dFL}L2ZQw>KH*h0q12>X3a3g60HTC0+(_EMjie3SNZP=Sqz&9i z+Q5yZ4ctiDz>TC0+^Daw=SI>phoJoiZv0)2+=Ar>ZX|8sM$!guByHeEeSJMQk~VN7 zX|(^pAzuGuV5C`bFBXUn6bUuaP$F*GL=oYorbPHPVLt z8fn9RjkLVK#&;R^Yro5JAByFM{TgY*evPzYzed`yUn6bUuaP$F*GL=oYorbHKWW2$ zjkICEM%s{*qz(Hu(uVySX~TX^UthmpBW;)`NgMWSzsqqyj{P$1*GL=oYorbPHPVLt zn!dh%zed`yUn7n7|2M?ze`h}WdGi02GoL@>g<76Z@LUM>f5NyEa~AbQK3~Ot;n|Fs zv#1R%%vq%6b7O2D*Bs%y-{oR1 z_+4MjS){QYF?W#0_Qjk+8s97C8hw3XkC=lTB8~QoIg2#*OD@N=D7ikep4<+e zUCHg^nU?%sJnNF}!80(~PCOfv?Z>k;F&ERjkoDyLV!7-GtS|cq+mZc-?aThe_sV`o zdu0Ekonnol_R;?ThInD@^k-cE`<8)zz}&!`L5(?sxr7>X33CiJ<{0K4YB?uSV@_hO z%H^2DsIflgHfn4Ka~{6|Vf#21upHluV+1wkB#s@_n3FiBus-JGpYi%n9d~%9hI5zb zGkrHijc1~GriL2N4)IJ4HJ*v$nHp+56U8$%)OaR}=P9W1Occ-5P~({>o~fahzlWm6 zGYmXKl*{pKQLc|?ps2AOJc~q)?c*6GYJ4xAU7|*N@Jtgm+KFeNsL_5r14WJf`lDR& zM}7MKXlRGNOQOaz*FWA%-!ZWq&uIU!ll@^oeGk>QV+Mcp7yj@AeOHy+`NMDY9aett zAAV+k_@CifC)U9;?Ei*%{qGySkr95!z_EsN5#}W349-#b-2=xOYRpN@G1T~-1al8H zepkWsLDcyD0drL@#~enD_5W{uqyIBr|Ec3n%>Oh7@!Kr!A#ps4HA0DdMbx+_#=RnH zv8E_-uZUW#HA>toq84kA68EmC#o9#oVNi=TONq>l8W|k-z^IYUac?Y_jPxF?qTi{-dyMjNoc>>q4L_8Yb@`xDmcLfej7EiKkm0t<32TgkG_0-Nv86RMqmHZR-Lj} z**;WfiGQ}T?>l|_VMGMlstDjWfJs3hdz2*t!{MSm-1-p+aPw#9>ddZU`%BIx= zNbkuxq`VXAr>~#Pm33SBkRE;dpfbtdn{*rNOl6<)dc8kvpK|auy}mYixAO8tU#c^& zAVb-*Vk6SEyKPr?@6m*`w&7Ogw}C)9G<37_bmd^uIR`f?+qs63HeI|y`DuD<(v2R| zeS6aXf5#5vh+_xii19^@@x{2~_`xez268Frg#a;$EHV>wm978tueAKbE8Yf81O6 zT`u+|*e|Lt_9egD5&M$g?Tfwm@Arx`fZz6rGl1WAiaq^r`^8@WcfZ751k0(vST6ek z>&yPZc4WU{`?5dry|SOt9@+nBryLiw|Gyz#7(1Lx4LM2LkdqSTkRc}}tYgSYDmUaL zl^b%Bv>_+;_4PUVzuyr3U;GWxpYi%n9d}~gQR3WUU7bd zaqlX>7x%POU%$`#Z71%Hu^jEkv4&cX9cqjz?xnFEjJ4bj=78Kj=7#)U%o*7p%q7`Q z%rVS8Y*Wrj)R>cUf3aNl1J;-QgYC$E!}eu=;(KL3qdl_!(M}vwvi*O?>pykep&xN9 z8_xGgqhHaFSdM;0KcYszq90MCU(t`K(XZ%7)aY0ABWm<3<^gK-E9M7k^d;tvT#k7! z*T=j^jqPCGqsI0zFHz%rF<()mJvg_bMmsU@QKS8s_o%U7ayjOaTp#mGZU^&DZXfee zelO;!Y!BwIY$xWmY(I_zxnDRA<6qb`v=>R{f6z!{>1mnenxv_|D&Cl-`E$l z|Gyz#7&{z;a_n#p!I)y~upDEJu|thHfU!f3xq-36`j|5qJ1oas!q}n4oW$6nmU9v{ z<|M{WF2~r(^)Ys+u^o&ZYHS~4hZ^6Du|tjaVC+z%oftdRXg|gdwLI2PV@&1x7;Cv5 z%mKN5%nkXym@~3Hm`k#qm}9d2a!z9Vn3HmUv0U~8)|dT*?Z|$^_GN$Kdu2bPJ?MY* zE!v4=3N_mQXT1JX$DQa`wqZU&wj(Y2o-KSrTKFVe_=>dfRkrXUY2m|c;ak$ex7oty zq=nCs?ez7^E#*_9wnq_A}Ze`ycI; zcje|@X2|7|kFEHCPFa%oOFNa_tq|_N?WmMfxw@+6 z10}yY@2+H#ZKt}k7kKN7MbeT^cB;dt0{KeaS1Dj`HC0JT7=Lxwg2#TXsw!Qn=8=)r zIli}g%^1>XGwRqX@5#&>biZRYRjiSUf0$oPwmozR=KZ!lkh~vMRUOV$ z@+tvesZA*-jNd<=DP6KHR{ltA#(jmJW8Pl5IH?(*JieIp$(q6ZUHg4x=aASIJjL>= z)M$Jbv^mfC-CuX9JpBUjvOgYD{e-eA-nUL3>4^HkhX(2GuRgyef8F`I)F_~us{I4T zEv0Kx{->&{@wXV?*W;?>IjpKG{vzX5?&e7!T2@unQUdRt^nmR2+^FOeFXu^R)#j?( z49GUL8EsQl)=8GrW-D9G4dxvy9HIAK9Hio}hMyx{?kD5Rn(4^Sas7h1=EEh@PG=d{ ze#)ZuYj+Ca{NV*@jz?9MHjnYgfmf+Kv(Z2r z+m!W{86!wz``9mRKRo@QG*@Y3C`y4w!dVged-pBh0>AKxj zJazL4s(;B+$)hsQk+%BEc+AgzDDZRe=O=)@)c<$PB z)W==l7#}z_M>^#9Na?!~sK1!cXb;+k{X%_V!7;LP;u0lq`}Cw#vT?Gq(MjN4&YdPb zyCv|#up1KgOZAHJn^q^JU8j30=Xfjmt@me0ml63qI%%);xT>wneS0j=ZJsG5x!9;G zUTMZ3l{-rMK{XX``~D*7Vv#3d+DFviizzCe1^1}@j){`L8}UV2Q>T*ZzHJz-6HTf3Z>_A1sW_q}C&xZ(W-#@yDUJ-N0z%x`iUqnzFa_cf})iC*vO;O zSci(LnQxW6!j3ECw;W-E$^2td-{7*U@=KMxV%%xTy=58IyLQ0GsxMHUqzRvxE<7!r zj4@RiM*)|f#V%-;h;G^FkG$AjT}}BVx?Px*a85Vx{8Yhb~EOd0my) zL_0ku9hdCpR#6R!QSu3;how&oY*le1RlKBQ4(a7PfFDS^Lb_D+ec`>!()A^kRkelQ zzwRXYq4G806ILCO_AIZY+M-hN)+aAX|E#X4Iw;z2()5zlXT6OI#CXr0!lfGL%vD*H zgZPRSTzVR5rW#Wwh}SuMMQT*`wbJ4oF=2V-%wa)0BKi z!WrqyMKhIUW8gD((wxmekuH1P(kh^U>D#7U$%0Y!nekm?T8uKDqnXpsjvza9QvNBg` z-ivkc;3diO;!9kCVzt-_TpLMzINbR(4RGC*ktJkkbl;e-a*QfGMyN!9qH$T!p z2bW5{m#au?s~Z3H-kWZ|^sWj#kav&qA}y)B`S~Fpr0+a%;aCUPbgaW-8**fu8Ry)& zN96__*`{`Nd+yP}i6h&j$5r9I{&nQYHrD6M^X1o_IkHVy2XpSW-iIUG>|9qWm5yk_ zk!@zR{3+F5(u^b9)UIs855`9l+t_S3yGaNaxO;%eguASyW_LQWU@lG3^IL?Qc8&>7J!<{&?O>DU; ze91sZ(l(1L@QG7h$ev%F&A7d>Ka~$oE0q>5aN@`|HNREi3nw?AHq+nR^U_E!j%+h~ z%ulIJaYK%5QJ{w8k!_Al{wcLC*N7wAlpj(mg&kFpZDrUmNt^7?k!>`+N+llF zjM@zOY0PI&cjU+kUAkED(Ly8J*rrj$hKQ zwH_SVW=lmQzUZhIN4Dv${we(o@TX@d3!j{oyg0JWjfkHT+J-ixZF}xIa%2Ga@N#@! zj5EFWW0Nwx#CK%qZLaO)oGkd67p@%HrcIFv|2)8v<68gBvjRUnUayM} zS<$mtj?dP-f4=QP^$SZ)dGdz(q*aTId4q9|HCwrd$Ys~X!xpHKi*}B4D7ylqE6sQ2Ej%;&jg$cKfX+U`r;cm=ZB)D;8o4jczTx#dbk!@DbDV4GZ zyK-ck-fd0!&PUEP9w&yG^X?PeNvDYMwJ^0l`S9N(#(d&(Cys36d&+`OF>~g~GZ(Ix z;VZqt}n z#KVJhT(A+hEq3R~Hp(O;Zr9kA{E)xIly@HI%#m#xJ{NO-FL#b?^L()pZ{_LEk!|)I zFyii=oH(-0hqSVMX{r-PwsB1?%X>wOc~7uSw2u*AHq@IV+hkh&l$=Byk!@TCR^VgX zHQ>lL-fqS`{H7B}wy^>Wo^nd8DS~Y>%8Kh zd8$;_QbT%;=Kx8&D}wZyI{41TBuO+tO_A{mF-8IBE{aX%| zYF|?m+w|~El$O4aCAO(!=_8$wNhG$}VCO2m-rkMa=6Ysb>EM@v#5SWY+emx5PN4S& zO@E+6jckM3?`#U`Lwg*gT^@Z&S17G2E!sAm^fxE3^`48e*H=YO&IZlWJlchbn23uAhe3CT^=%8Z=Ks{IIj@aH(=d4cT*OK)kfq zGn(eZ+5=`ubCR{hEho3kkV?8nkT&WxUOHlYETV~R>Nw1j z;$xDi&D-uPq^`fBiET6~0a9Q_G_lQy4vnSt@1u!r&Q1%EoXp!1+w}Exmu@ZXK(+L!`nlen9z;d-2T3<&$u^gFeh2zVc2-fOtrLQ!oFIL?9=Hsa zhIEZ2wy8D0xny@;Z*%t&rPMx5Lu}J;_+ZI;hnm*?rH#8tXCw`=&9>7K(rOk#YyIiK zaZ>(X4e4FaN6@p#0Qjs@Jd3RI=usCbN)=0WN{W3Yt zT~!83Ek3rTwaK~5BFXlnhV;mlqa|IIn)I-q}mC8lWMbv0E<2ct9lSD+@xU86rl=Hoifr zl8tFBX|KtC6i4hk#<6p?2x6PWS7W5DJJrNCu5KyPtVa>VHXqYkNawG_65BY9@sY;= ziYK1gTjU|-uZ<%8{)9?0a~JIhJ_*`1Ryrh}MXsyRZlbhtznXMji|$hDE;ZF@ct2TM z^iE&Cd0acmzF8ENAL|?>?NG*3f7>TDl(viiFNTcwDIi#CH71_wtjPD2247MW+q_(r zD3w_gMSk0SUM1BLu|u{owoQ;my$~@KY%||eBVBA7NqO>oVyN`AL_=&-HA^jZT^L7f zV|~a=nmt-WY%|zFD>>w;X%6Yf+e^pA_`A8iNlLgys{unQ54ycJ?l3R3= zc8u4MKKeOIS~w$$^ltY+DKjC8*rvv}KxtYB4f)~rz-Y<#u$tIr=l%}Tg&&c`He=QV zOBXLk65Dhe79w5ZYGRvXdwWRnlA74YyMGU<*(NdX3AP!(M#YHk*N5o}X1I#Q~!B#!F1W_d~7 zLN&xT1Jede#!EEBHWpikOX|}J#5N}-H)(Ypv0ezaxw#=un*CNyF`BcWoy6TDh-WUe zX(OGgry)IiN}M!A#24Ad+A2ZXdqqtQGc+Yp+I%CD*ycf}5UFEK>%2|dyito z?pR`*l9W4&@NQaSn-|9BtfZfwZ6ekym{Ujsu}y9b4Rb8$Ol-r{-PpB7y@_qcf11Q9 z<_@FxmI+)<8vTR1_JNLMXSX$p?DUNuq?-;O$(HQvPrApLbT(_Lme}Tbe-oB;JDS)g zOb%aWyVT9+w{EY%SN|p zPw%=HlBuYk8cl3-u9^p%-YlBfMtQ#hJ8v3IY?IQNV;(~ckY@5&QFot~Z1@Gn>~KB39$H$1d2fgzJNuP?qDWt*_j#8S zj%-0}EVUnS`ktbRU@bhiNk3kf_5PucW4StRta9gAVw-8r?kO%*iKcabeBL)j(~>A+ zo1#mV*vj_twASbEzMwcA6GuAazzqdHiwuCzE_RJ3J4Y=4su=n`hRU0rXv|O}+sGQ( z1~s;iY=iBG8O0Kx40m{_aN5>|)+XJ>6^eZ~<4BKMc17X7LrXe+rZL-BQA_n(O6A!o zXT9z^ye6}m)|TeOljlw<4)4~pP0p)E%+*v&Y;*0fHM{SqC3|{D)?^mnqlj(p=Gc%u zxW1!3XdCtmbzGR1?EGqH!Os4QBAzMjTY*g#;|R}i#!RcidM$`1wn@+QWV+f~;+b__ z%dw>vdOht~H8$jGS6b7HPA^rA?XPDQt5eq%$0ulsTfF`;WnD+^4&yiRRe zFwOQ9TGP|)yRiJySgJoYP01ECi6ORmRPlvkv26^ojqj~uMK3Xa@!ZDdcm;N?rIz%l z8FiS8Pc*H?>pqnzvc#N;oYUua0ObJo9pmU{CzwH;+YDHLNiqAOme^*;`k#tT4YkBJ ziE*{qqa;1sXiXHXIcP>J6c+o(;NI!bXRGqJY$muE6CKBtA9ALhi&7i?}ZHmS6|x?tawTsJ-fer z5L?t&OKj7Aff);Vq|cMDWnI}^5j$j?=e8EC^s9)eU>lo-w(MCeE#=9Jm33GXkpp;c zbGupnA>VH@fd18i8@Eq(d=bQhL$OiOGNKGB&?HPQRZ@18Y#vPes8V>i!)-CCk0 zwh8R%$d*jj65AX|bYLZWqKR$5{GB3yYc#Pt)Gf{Pq2-#hb!xLLC-e3Rs}Hc zIbx0y=Qbfh=M_!bXo+n)W!7Q!>qQf{u)5zA)~$v8f@jvRsl&F3v4gt3WhGYlD3d$RUH^T<(P+vFS5?*I(A5>KhHT}TEK=r*PqXvj=#tDpVQCDzeeg=PcLwkCYZkhC!b-St81r4S@98B0Dgx8$|laG)Hi6>_=?lRP`ylI-(J= z&4tQ^>|l})vCWij#cYD)Lu|9W@(b2;LL*|Erxt~5T$&HDjmEc_b=lX1_~AsK0#;(J z|28+q@;U1}FqqgT&h{<~4Gto1X;Jkq8+}PZy09Rh?XBQT_Gm4hvy^MzRKB*FDI9}f zVw(Y#?lR?I{n^6mk^*L4sQ)IFUi^bSz3oM8Q>D%iw(f!cn^flcA1twf53!9`B{P_D z(vNIgrLY9Qx8B4yWe1o-rEN{fZ{?R(1gFDIXfEoWTEKFI#&erHT?$yA!+xX>cw54X z0=*B9-n`4k-SQ%~@p|`}Z4dJ%`^#DwL&hWhcPO`trEH704?X+F!35SHjY7dJ)_7i2A~YywZP@D!Nk2jud*+vrk)^!sVCxZ&Hpq zrDPk?|o!z z_co^XBa-hktJq3m70?Nw@v{)iwuCz?r7~#c8>b=h=odb z`z@RMh|!wWEG(ZLE%l;vn{u~*vR>1Ch;4@FykOBC^xw#)t$526ZG4Dr-fb@?dvJY6 zd(bxQ7wWPDe96u+?}}Kzfj-1D{^iZEwF~pG4fTUx7Z~*t<_Y#5O$oIs3fA zoAk_**KDF!Yg)T2-@3<|Hf>6L68rNWQTk&nGiX<_ z39achw%UMuFMXX;TaBS@g#cokCoLYbsN6=xHvi6h$g+F*5YLotTFicWc#}TZ=sn9# z^ry8rCGQcNXQBTlb)xexiX-+N=I%{-@;2~2D|^?Q z*yj3%SFCTcH?d9H7-P7Z;6rS4Z9p-*w9l93kblF9n3EV^I5wBv|H%CN>3wKc=Pf(9 z%b(b$Ppe04!*f64nXj83vvXq1BHNr6WA3iZRTEm z#@G-);+dd1PuSL2AJWRH#cZ7TN72YRPoqCGqbFX(Hi@S`vE!3`$Pc;KUa;Xle#ACA z9iFlX(LR2YdcX4{tM|)`*v8%YBRi>RL~L`lep0v-WY}-Z%k|x7l_Aht2Jf5>b;dlB30UjLD$PAf-i zLE+WLu%>A_Vu@kaP2k&W{au>g*6zUF>r)+GTI;Vh`cL+#6QaK}v*bxFn47D=t25Eb z{jWCDQ;ev6JC!e_b=Th$j_l|IucQLHGyKId0B&x|C7l--1Xb$XCcW3DHT-F(nfQ*0 z%n(p76r5~olWw*<2yCrvN!QBqbJ`*>@yl zn>Jq(AtClA-T9m}xDRQx6ZNmYx9GlThrre_WXc`VUa#UI@vFZ4K;zD^xXd%UOT2!e zFVsE%itZBsyWI!!MitUs;uj(QFlf&sx=VcFf*2XSxzN@RhBh!EZmFN|3$W=c-5G8<)CWql9+Pb!2K#~W z@?0w49~uOuHm1ZjdxQO8Yr6{M+uc1Cuy^wRZZ5w?^N^>e{no>MVepUJbeDK-NmGbueuwT7&)?n@*5A5AcZrK_MR})NbeH&TRgqV7bIHzD zBZA;r=Ua4lPF)emHk?1vw%I@5(p}amy?o%!if3d)=3rlVxS@b_yhi{m%6Ln5R_gBq zHdgth!;PCj;D`6r{y%Mfpl8E-beGu1sWB85-=Xq2C(Jp@oxLHDXYqzHPK!cJ`q>V*x|V!HckQpOkN6z7qya|W!hGRC zlLER+?B6c{9u3N)yTlL0pN;WeolEzJANvMDpx0f}XOB05w27h}!8V(_`GESyce*E> zzuE^<#=azd;i?bx?)RMPjA-Kv7Av1nc^Mx+h&yY2<5$TVTFND<3r@O@LMPvB+ z`Z3)lKGnq!cJ6*gcZM_i`$FU7Lelj#{!k<8F6raz#d{asrMtw9yEOsTuR`)ed?))(`h zV4JRInn3Z#Ji1HV;WWVGj^cM2;@rk|pbz{QeUI)ETNMYuZs`Tx6ZWm_3lk>Yqx-|N zp9VnK$%mv1=J>b?_TPvp#wPWlU52p4tNf$Mah7RK%=%F!7m(jaAo*fRU{u4;YF6j$j_jV^ew@-J#I>;thG%tvekWD3p)I&t*CV#6m=z5x;>`5Flj@^|f=WAdc$av2N;|Oo zG+&2ziQ5kA2+fxa(cxX^qvJL8AmnQ2_H$RmM zz2jSuu6(vXv~zuQ5X;$_k+8(fg4o72O$%czZHaAW9@BzR>_;8mB|dvq3&WJ(baou(6JeBnx(@F-f8U-A zNgdYc@Gf!b-uB>OGmPxKsOkxegB@rtI`$zNYBhHt9w_%Q8g{XC9iHJ_T9XW6HGC-6 zw;II3y{Bh&_)Y3kdMvDV-A?u&THFp!yv?He9oGqlT(pw((*#&msfhv->MrlbuH^(q^LX(Kg?8boY3T z7WxI;C;c-w8kSx6r1^01!dUR}+NZ<2#Q#RLg($l(I=oA~o@=4&xcg*}`dT!6b^D;h zyTm5>`u^hjj`pB!Xg}&NJ|@(!GQ+g+?8qk_euuI;rG=&SUXUIK(U59=l=^jIMI8Lv zU#i2q#M$$-FmeAA(p83tvC}Jt)^6SKWU#L1M643)83P`-%tpHwwGiY-R z@aO;P@cf~nc@kW6+d}2z>LtK*X_OA{oMd?PfJ&#T65H%8)@^w`u7b z4W|~}rm=RdX$-7-|3Zh~q|$w(q3Y)?I=oAq_q82-cKoQLyTsSE(BP3N%^}YHv=G1e ziVnx-PBFe5+dm{9zT6)Tg>`L+ZNe95!PmSzF-(~uS}1H?mh>EvxB2tUNxv1bt{iz) zhj)oj-;aTCYa?Qt)TvsyKcp-%%p*~M!MP7QJge!EtA%m*&XbPp5DT{JF6!_uaXtT7 z_<8p;`Ju}pEo2s!A-1V2+JD*Pst(U>jz5e6Gt28byi2@ViUIAlO2jtZ_Gm#jw-T|9 z|4uE8xN%O0Y_n}>EZ8{i)!|*@1w-3{`<(j3HoBr17?XBehj)oTLJYJ!Yen3WJx&WB z=ib)gS&fH6%n#CA(#PIwp~|x@I=qvU{G%NV3$8i2v5L5JU@>fO|W zaa1*8o3|ge(7VG`9e$HaFNpbzA3{R4O_4ELx9{wk(mgXH!L?I=(vLs4 zf$WvDN!v=15MO>d>F*EP{`KB1`@hnAr!|=X73)+ddq6c92HtTd{rp=RU>#i3vCh7P zdJKOjwbHsjtUTz>@OM%}pQJ*`Q-6l{ZR%RIgUM6E82(O*Z;yf(Hxe2CPU_kzHQYEj zogv$}_l|(z9t#+`C z+om3A3t@^3(pybZ;78dbq(A)V4pWm782(P`yQK!MzKLM?JE`6CBS3kgD?_%aP*V-Z z&va(UHat)b`>#eY{GAkA8Uf$cT^X{?o4RUPZ5GOqA9mY{eCU}>_PBOcgVzl|hV$X1 z2kjs#x)DQeS$C){%pMd-`jl8}!c&vUp7El7hn=&je3>p1+^hIA{GC+O9qph+19xh( z-|ep8J!CRNwkhbQf!qU=7_v=ZkOoe)oy?GJ)+TGfCvFZywmF;-1w*GVCfg!=$HL?A zbcSs6wSw%dx*-+< zmW*M@Hth$f;dG4|RDO7F1bkgQnd;Z*tAY9h=8%4o8U^Q{2GF~*vf?4cW&%UD8FNw% zQGLcUWSfxfYWN;GmLc1Oj!{EU%P9=m#%qxV3QW`K*?qSnVUTJHL$*0QUqiN`&1jqS ztQA8BXtgvF(i*j+_m1+^z^q06Nozi~fn}XrlbwNMBEfs|2-3PHYKXN7r}n>wMnP)t zAq?4ORs}Vb{v1Q)--oH;*R>W5e<$S-8wH8;V;ORY(`F64N$J6mZMdl#vU>zETe zL_@DH%}Ccx(bBV6j?ZrV5kq!<%GSUzziCuwTKNdl*ru$JZBS$T*e`59e{oBOtWx|W z5=J#>$Z$>X*fANh9YaW0ek)jdTszW}oHSsY+?nbh3su9JN&`q={L}_+mjL-N{ZtHe zQA}mXHlr_Upl(tsL$*27Kn+RH`cognMEw^@-59csa}_n&gZYg1pl#SM)M0lzkexM_ zs^NuYSB7kJ(?Jars`ny&S+w)0Xad82?S7_)=*lS!*=A*e8g7p4L%Qf~8+c~p$?%(t z{oKwlVshI(GQQ+2eCYA4b8Ug+5u3^YF zspHy1>V7rD-%0f|iiD%nGz@W*%x?0jJd?LVQO+3}9*+~Nr zQae)l=-FzRoimckdAJ(VJZ4dUdpC*%Y0n7KPZertw|*AYNlS`^zG;aJe_^DxKQ749Xi3j!-xm$BU8x_9qX&1_oxJhzmu9!M!eT;1Vgsz>92-Ww!;~+ zO@x~ouD^?9_&X_eY6Q%zAI0!@QU}^cfVsJt_XOLt>7fSaB~ux)O{d2in0P9X;knHq zT{QGa9L$hy)|FAiKP;9Zx8(2BKt$MJhHPUc$~Ud-PCDLF4H<7{P@R-35zy#f3x>aw znxl<^u-xVheP zJ)6kzF7eVcYHnL%^0pBRdp7oe?zrq%OwVCwTh}yR< z@PW_$Oh_+k(*VZbwIn_5kpqMrtU~&nhXXWTQ*`~okXQpL&4mzWC-L z-rMz>7ish@>aj(2$#%8}8j8C-yWE*vTCs=vO7?5p_RPq4dE@jA` ztRg2kZ*2@XAEv(ZhvTn}0NLi!Q9oE6Y)txaU_kUn{S{=J zI@}*lCYVv1H+KYshgC&DwmG}s9yV>T0c4x;S@z)j!v>ITDj%?i*T<>?vQ4X02Pmjt zi)=eLzzKHMt_sLDUP=e}`OA^o44dT!RnHp(a>DD{9`N9tF(BJ4uHym8b!(A6(%T7s zd@v%v-AwQXugcbdY@_~e4}lvhQ@QtbdkDH-mFi#Y;Q+JhRwO+|*tz_H5xuMX7GF4_ ztN_S19j@BLv}e|UY!i6b9$1JqAlsyV5OE(@5s+;>#j_ngRH0{o`8mMY5fuU1##xl3 zZD=#v#%G%VGQfp84Pdaidx7>39OME8Pc2EWz3TvTSDKKW`%3D=G%G982Yei$v!@BQ zuQPXtkyhma*=F4k2UzH7P30Fp+rvp`6F|1vU&9?<`*m6>4k_?g(E_mZLneo9zIz)5`*~&Gq4qaH_T~AlvkL zXb*W4Edbdjv5FI1Utmt-vDpS^m||^3dW4SyY{<4GAI^N~0IM&W0%m8_2 z(03P@B*rZ26ftH;w-ojWz4@Ip1ivp2$TmM4J3wNqGJtH;t<(wTT{Ht^o5iDCVDM}U z(#{o}pyo*{(lbPVpNzEvWSay#2k>ZWL4HVT;RJhZ%mLYEytfN%{Zt;1Z9GK#8GFhD zvW<7R1H|_?1!S9;?r!jAxG5mp{A%Y0wO?5QvQ43}11xP?36O1i9JGfG;l_Y$Gr3kn zcyX>AAltalbbty@W`Jz7I^Gr5=9B|un+LNT!1j??Uxe1&a)cZ8Y^lz5;ZJK<6F|0! zs^$)fXN>{brmv$1RG4W8$Tsn>9UyeJST6+Is7^V-=&$A!qeab~;p(%pfNb-iwIeK_ zUxswUV`A)!v59QcNsLX!P;)@Gu{rJx6?EkR*`{Tf1Ke0^OXZ;-#hkO=6p(E$+PZ<) z7;`|j`5`$&+;j_|-+)&X>u{k7AluYQs}Ig^%LB5_geHIUL+n~lVu@jvb}*rpf^^x& z7BF~RDCxUfUb24bP@0FoYhN+D#tPD_qAcK7rYGrLZ>#;aj{o^=@h%m$GgNbj6__bW zKMFX{O3wt5?zSO|{hQW`^y;x0jA>#?&)b>t*Lx?tjiq-zma4+A4-uqqx?8|(|JI}r z29z?agN%W7OszGm$8N1tklZ7%oS!Iq^Y5Zi2=nZaIobtAS}++jOAtrRn%Uu!$Ziqz9(%VB@2DlkPuu3p3AF65GVDJ;wSvD2Z*x%{k33)D9%JS#^@L z2?tfgHfEI$v5EFdVw)OkPqPhHfy6d;UpVu3R}w$G`+SM@>!%`noLvtylWIZ4Hf_$` zXE|d6iCfBM-D72EDM>q|UT1gvs>q&E^$)Wv{aR7^x&ayN?$QRof2%5SZ^;YsMws? z=Jk-h?9PN{#5S((`&fF%Fk+hs+udx&`c`CTW?}|&NC=~`T&enQvJKe=ZJTDLq_y?t zxpT~ZgWmq>s^iT4N)Xwgo1Mk3i8`1MNh8j&v*SZZs~7EOw<;^C{ZB_Pu%f-e#5PkN z9bn1*n^C!E$UbIPMM-S4rT7Bd(?v<^els}9x{nSdwwab8vGl=8TI+W%zQztT*6XFm zFVnNg0QhV{d%c}@b5F8K?ORa&&SASqBiqOt82~l5k8FeO@3U4CpM>r{&lc`)PHWTa z;$k*4T1nd4=PE0|O|KVKJ#Vhq}lYNq{s?mb;!vn9ZYQVxl$I(Ep0(;qrSY8#dK&zJfjLG% z6)_cT6H%gL2Sx@{p6FU+vUN8CiEZ*u>e%2L;lwth!*;SD`#@rw5*=qdf9mIuD7T|* z>4XrPPbx0l&xVS7naGMI7qi%-W=dikr$sp|V3?8^rsY2;n41{0$TJcoewjYwMt?b)9B-DylWuo3!6AguilJww}boGhk_7dn>UvG zS;x03@V>krfLxJ%m!B-vz?_P?WQ}#OzW$NZIY9Yu;Xu(#4ve7 zjF)5CpTR7*Gk*vlVmBS&sp84q%S2t7fwx+7Ot9z!pXS%m-j3P%=VQ!Pqtc4;sl)W2f>o&WqrRP0q6ok1=<2f1m!-|GW z>o$E23oNWBU~W^CFri@gvec+PjP^KKLP7D$1IH$A18QYZsWIkgreIO z73MZ)p6Dy`zxZJOu%cX?qCb0I3+<48%Sv(Gs1N2gO~3C~h*s>oXSQym2-vMyrSwA{ z`EG?m#pJ=~8E>o`<`EY@mYVSXPP3e zrNkBomMGv_$N}Km)fK(b&#=Q@is@JVvAl6m%{*YpZJKKsa+^ksK|ka+cbNWK_CA=O zWDko{9Ns?=pG}9l7Ablp`XYbMOj5i&r$TI2kz%x~FXk$jZY)*wU}F$+oB4Ka6^UJZkY}`*XMgNcAFOZGfHC=# z>I7oBzw7-x)97LNeAg~6U(jW%H|93ih4G4eN#2;-gd7>GxW>jWtlR9^qOWj!;Ef!* zF2g>%sy9B1vm1LWMsDy&E;7273vqSe4{-o%xzA5YN;6U!Ux+e(Yv#K2NpZXZ7ep}Dzc2dF}KN@_tbva zBX8^{2P1L_bDPDJ z{p~-pz76esLRm?1;+P6^n~ebuiZN{L!@AAb+7s=QR6dy7czQUm?{ zQoN;?BAV3~a+|#azuRwPZ3`UwafN+ltw5A%IOB3&|7kv$+guaoD^hfPF}G{v-KJCjN%pVjX>yXcQG(-0DX;L#nIp8DF6AwS z1BgJ>Qa*G2{I#E+(em7*{$45n>3iyGL0Gty7iHWbKj{pq&=Yf&(bwk*M!lrf;(a1xGOcxdml=6pB z7LfwTz%w0WUM(4cxy{Is2%&GYAk1w}?v4`H*7L&L=F*C}!mhp^nA_-Fi51E|cE;Rh zW36N%*v18On|ZZ&2$@&hF}JC^ZnqG}z9)cpQY}B666WOuU~cm%?5?oq#sIW?XqXlS zhCBiIH2Yo$xQosaVN8K9asvB~ekJXLyl2`AK}B3Jw`pIpOjx1shPh2Q(4!Y+E~HZqsGba^Z=A8|F4s^_K`aWt}m%dAFU(oc6%{p-;0|fed#>f0SOSf_^y_ z-VfJwnJetO(hKvMYX{~EWp{N$);qFL$Yb*0=cyj4f-Z5z@^-#?Lhn;vnA^~fIiWR!{>5935S>=6#{tBr* zO&-q|8s|7+ZsT%!gOKCog8nDZ-yvK+<%;rs914Uo{iQXWz|&iVT}OLLZQ?gih<(7W zWw}l5hMR<^7o9M-IWc>q(7eD2bDOnovV_#>(z?z0d0T~PzS5f2zU_I!o~hEhP2#kz z=o{oV;9E#Dcgz9apI9vPAL4>Ov>m!kI344JJkoiU;8)ch{d}SwCs-v&YoSXHtP>Q^ zrFEfxa~BB<=Q4TrPU>aO8lh6I6Z-5_DNDHZ)g5!21tS*;8$Y;U9ukz3An2ZV!rUgw zZiSG^z8!&Qy;+NBp;g_k$XoMc@LDK`Yh4Xp(a-523Bne(W&-7w^S2{IZo?UJ8(`26 zxee$aALWkuNsBg%g|6v=_-tyUJx54aOKTUA&!dGIyOXOq-6bpy~CR5yj(Dd zW@~zkBO_M{Rd#yf{V-e<=!{%RcRR)r>JD)fDzNYH*gL7uvC)E4whQJq#}_6F3+Fpw zZZoK4m0(s~TDSS@XpWH8$`$h&RhvAa&SocMgIODd!)=%z_RMt&j22pM^~Acn?_VHH zNp?lvYPM8xTkV1}2R0-M*V3hRt@QyZ!m8y?Se`$0y>Rll3)VNbV3%N$=!Cra`Z}Te zbLrY=SoipY(m7XUFhc-E3yB(ggK?rBDgWSg1Bt@`OvzW4Vn>U6T*e3AY)UUBd zNX>J?+-8(2Lzq6%1#=sN!8?WOADu9_Df1ysnDm!3-b1>ml7&`me8JdEJ+w}^ve*gR zaP50f`lAbO-|xEVR)<)<~BFVuM>8kcg5W1e#{c#&=FV6Z7kL;5k9fl!Me@X zm<_^p!5MR#(EHnj?8I)E+t@x`D4b$_338hS4c7?ideWLq{{;!yo{-Ok)LbLb8|?YQ zxWR>V;q)XI%xyA8>=Y_~cE{YtaO@&s@C^^lZ7N&F3ZWO>Ft?f3NEA$c+4F+sHkEdz z3a>Jx`(bd;6ruVCC(LKY)W{T+DraPJAXUiQ?2Nh1H1iZ8>!ma1Fwy$SLJ_MkypuAq zSSQTQal!JLzPp4539gviRIy$vm^^jH+{V^2Ss3}=33Hn@<}CND#)MF^4w$oS1CWS zF85T(x+=ZTS}{iVC!KFYtWp2C&4zR@wM6bT(umGWGDL2rYf0xn)u?O;Vu&FYApTDdyyf3GcaY%>cAGLYMVOtX(l%xxadwWMe6w!qxR zV7M98PpOBwP2oF3YO8C7xlM+J5iR=51aq7G&nC3lvZ|Qd+!=07H)mAC+$OwPLwX{| z1aq4e&s)>AE6g#sNgdmfTJ5wzyEja|kReY1UjD!ceKS=xrnuruJtf)>G;@?njEc(?6TgFZh2>n z{+v8)O5+NuV)>NA^=QA&HkjLNtZqch9c_tqEPKF=o;)CZZxd}$n|htAin-0L^|k2U zLsc=i+4`*(jlNbDbDPztY-qZ-A^P@WP-FUXe^tzFs@J!n(aTIw=e`xK>Cxp@crSYX z-jIf;Sz$hKlyOc^L*x$ujj6-q+UV!7rG_*iuo~tz7PV{8jP$BlZoAH!uGlAiV{^22 zZR&7CVjuQ<97%2KN-2miTNni8P{LHkhK%a|fHyX^SNPv#VOt z#e*!-&*H^Kw9=+($l-OY=&PyKQGbNei1w+#u5i&n8LV zpQu7j=#^Asl<#L_MmxGiq(+ZwVH@sAG^81utKzy%mQEe|xr;I8HbryH=*K8S ztfP5dOIr7}5#}}~Pgp-^{=oAc`~ik~0T+gupr1kBrZmXb81tF=>&<9L2P0%mEJ`K;Tisjaxb?IL%P4M|{l-P=P*kXaXjpaEbnmxt>bDOVE zjA#{0W6Wpf<(W~BMuy0fZ(GuDg=Y9HzL;-JAFZ#7Y|yn1#u4fcaqOZ~6LXuMd>5vswaoxtMy*16rtBU!|nw|CNi6PaHPrkLHR_&M`mfNUu z*|@k<3+w)Z#pQE|Ir4*k#0(olUM(@f+{W>V35^+A4co0_i4~nc-UM@-ttwM$Gl0dEX3J4?+9IPW<~C8a>e9(N#+ch|KVwE;95TUsNDBi~n!B+Y z@+fO7nzz~z+c4~r1wC2E9CMqiQN}b^X@>dC3SATWn2lM;ZI-ezd#Jj^fyYf~#hukK zxA~%HMavqPU~c2K-ISi(Zi@NL+#nO`@y!T1^{N?tIJO${%kx(B)|_gX+r-9MQSA=W zcSq}^&8U5lDdsl5DJJx0PBqMJJStkz2gj;mZZrO9bsDh89CMqrcE;3hn>pq-S?!If z)?jw;V!6$e&sJ0`t19L;I}~+jueCKXw^_2$kgl{b#N6iH6H7WF-3;@V%O{NK9a}@p zXNp*RZr@{sT&s~e?ZVmrZn5k2=keBwJd1(F=OOQC8o4B8=J6hbB&G7tcUD7Otx-w zqr`-=4F;Ioq@1Zv%dvYAl%HN(mp&U}j=4?I0AqUp7CVH4t=m-k#QL6=G3GW$E}GGV z(-xT9^f+il53v|QZu3gV>ZkmnWutPKSKOYYq;u^a;P=3%hq}-$Zu^kCAL~J*Kkviu ziic(Ppc6+uKz8$Up>9>m;r;niwDPCtxcu6AVcStpu7MjJa%>f{QJOP7v2YQxg^wFO zK4v!Zm;t@$6aQJr-P-l}$!@CWSF{@w5=_r8D?+v}?oG{N&mvz^`BIR9+y-PesITHa zsaY8Tbg}Lc+$Xiv$%~pc--Y|64%)fXDZ|#{KB+sGohdn$g!`mcv){oyR5=RwN%d^j zgNBCA!hKREM}26v#|+#jwW;#}+AnQ9?vr|QdldD&-W%->3!Q-sxeai5+nMOwHLpJO z?4C);uEoRX4WAI?sprG!SF04X+Y3X)Oq)f7v1kU z7xzh-TYA#Z1#@wq)QP?9Z0vq>ai7$XN}lx7;RxI(wLjR4PP#c0eQRp&Pxsl*#(h$$ zg}o>Zo`E{8U-qZ2iR*A*!@IZ6bmg*jxVNarJ7@a6XeM%eC4V|?{}%MqI?$CC?OlNT zq{d}=P`@YaY-rZzgNOB?&mHEX{H=zbbn5O1WSt4j=ZiULYxP(+y0QCw+$U8fsVgnJ zb3X2qs;uft>&{t#`=rPz4?6y;v`;E&x+iVYX*OQ#klc%U-IDf6jhp0&zCmsSzIpds zCGFE$;Y_{NDQI`xK4-c|vsdd|pc{3pybArSlj=+>){917ROC(v^jw4bGj}`F$;)GK zpOkZbce*WO0hU+U?LkwgtigR!I!q^J`|ltR(MorwtuDsnKB?kXu5?EEjks^uBoFTUX2K|uRfd0;%SL0r%PMe%* z>%6_V&t>zw?)25B4ai*;F0@ZV3Ud2H&NO#%0?IF$<3c-iT7*1tv>O$lZpOV8*(EM? zvHu+0C#7BNNoTHFiu^jGtS_VZ(?a*9BcMOfha`Uo1X|**o zaIes$^Fh>WVJ7aA8WH16_iAV2KB*lGoM~j!rMNdL_mT@;TP+sZ=#?8C=AI_)>sjVZ zXPC`Fp5DAW#u0NH7RNe)S-4MXwU-MmQ<#eTqy}WO`^J-4+$W{G#ElN^7=`T)5CHb-vKUkN6}`i``Xto^wf!TCrpD5qDXk~&w9ARvC}VV@Cmo@ijQgat zi=AneZws*93g>uG-6P9zpVT52yFG?1rYyIqJ<65dDIbgdB)-Ir`d*L2eNqc%xY8*L zBXOV9gUdbW=#nM4Ps;ng3$31%g!hodGORtVqmjGaVLlWr!Zs{w??#u_OUHdu6Baqs z6{gE^KUBzicJF0l7IK?#*0wW-B_o%A;7r@NN8>)J*C*X+Twx;alj`f?LVKM{!TnG% zg{&^OmLNwzaiN(F79tmic+kCb7UDjsr|mpwe!^00hb*-V9abp?_emW(?@aqSMdLoH zsb}2jg|*SRPs(bAJMA2~0{2OMV)yxL16JTZsm}AAX`fYKu7B8?`*wm1D@I4aG!NegF&=QXiL2JuCF-Yr)RW0_XsO)iFt^t z&H$>Hu^;!3udX)eC!H_1uFQq+YNlTeq|+7@<^%6r=|dg9%*JzU{Mb3}>#|NDH#-$T zt1WtuJl-|l&*ant6^-9l&Z;3be_oZVWwkm*qQX>QvjZNNz=i9uf&dk1JADGPm{_@XYV{<^3$K5!1Ha!oerSEC7JCYxB1q-FP*UU zpgq*_;-=wLJ8c`DZ*yadFYWX?8_&0CJKmQ%x88>5+w5HHOT+!n;rTX|k^||7bx-kp zn<}G&Xv~9Cc)rbK(?Hs4u@1J|jliL_=jPaa$P>H@eCfQ@*nIewSY*6!%2PZa=1g!9 z9dao%585z!LjWzTl!oWq=r-`7`j-o_osW6?Q?HzJC||TTkTx^kjy#U(`8>B?Tk!wO zl-_h`zcqNiP0B7Gde~qUo^N9u<3ooJOvm$WTpfMr!TCGze4FaUzO<+ADQwTZ@7V8e z4BUZdZlt`Bd;_1sx6!8$l&C$-@^i3xL&xg5? z?1v1w4QI%0fI&aLlVbW!CJOoRUa8CxAL?Isa6asliVyaq3pUilvr6bA6?IZCu!r*A z69-Y>R^9PTn=VUKG@^GD@?w2&`bqsh57xd6p8C_&Yq@y7O~=lD^g<6`Jm1Eh$p=)7 z!aCm7VZVzqx*wizbCC5<@CW*H67vTb>IGbFq!RsHzMlDD7=UNmL@!m*`F^3u#sw;R zGITwjZ!`C$54AY&hG*LJWaH}$or0`&K}F4qGwtC!lh%ud&<#s=E( zyT*W>bDvfaha9^Ae7l5o|4w?-m<ys2-+xp=-!n3*^A9JU+Jx7nlbPb24?z%y+o>!xsBx>Kl*OP$2_QegNOcfxktGI;C->))NPR!p3P!bf%V~Sj#wVHT1D+n zEyMB?SG{S4TZi#Xn>Y0WXy(xby3P9 zRG_i|-bo28cKw%*!t-rfZBx+^GZx}lyTJNtM#>mG-{#^@6>XTgAJ4aGkm*m;hV;Sn zZSJ!;>TI#YGi@g1s_3Sv3CI`O_^MrDHn!o6w<@};RrvyVC*{U|SI79Oc>&}zb*g*Q zLxbxgFJWW$qi!?gV@FhU&gP|fzK!u#Z))_lO96au(>Rs=KFMxtJjbTaD-|7Aqc3vQ zG8G+rCIxw&jt^T~NW$}NY#w>jyraI@4ii}4Zh5Cc0qm0sy{e+)4=u&>ZH902rek); z8u?h7a~{c!s?Z?A7xxtv3}cV zV?KOK>|^OmZOmiy;alQ;qAwlddmYcWxn$Ibz8dU~=iA(3{kCzCBgUu<`#qVK4=3Q6 zHr)@hG4jwIc@~q|6s|0Qb(<&_-xa2<@En`QYIg1Wcs$>xT#7f{wdN3(FaPRKA8jdD z0N)aKiuR@*cC;#hb(;lLMQfbygXi0HVC`IG!(aKZPil5E9~zpr6wkNmxW$`ZtCfS# z)_McjxW1SpK)#XZprW;w$6&dwZy>Euz8muWl|er}qvg5By7^u4+BR81^yt+XWP@&j zKgpN&Oox1c=K!CJW*|=;G>u-Yo`BqU(PTPu?gr#9UBl_@H(QY}d>cZa`$+yDb?N(4 zT}t!6wA|x&?1B&YOk_TQJTUhY82ntf+=+&iw{RR|7`b}H!A{6JHFShcehOq&%Sd5M zTw~;y6$%A%$sGAqze}QWS8!=g(;huRF0-iy4IXEp1eqq0dbGB8 zUF5KP*MyEUTO)^uW(vL7-V=}s5IPGspSmC)J2ADO@fnHBdc-P{zB^)hkJcUz{dcrN ze)@K`!33)|A=!20v<}={{)Klm1=g*5%~GBZ%yStVV_{P zu~X2W;kt_)n$(xRe@jdl_mB9_|NO;S=v%|LMuPqeY2U%*j_v;u-|4vp^g-XklPgfg z1nC=cofxBk#Cvwf=h8b_k@(YD5B1Q`6Xp8-Bi6~4M_S_8+}M5=)gPvZ{IycVKVqI+ z+VkS4XG-CA0p{R7a|hB-n{)7tSq~jQy8O&`JY)9Y8+RHSl!s@`nqBEcTW>6s&X~PT z=-K$|cz*u193}NQ`4G>~-+ib(O)vO}bMOyrt>gK1Jql-)d`<60d-O1;aIY}8RI#=6 z+Q>2MyU{DQ4Uz5ta;6t;rQho@pzW!HcT)Bv-T3hM)vk5{D2&)1`{KH%I}huW@gL1916mQ`PcuanzRI7cPg?VDhg)S1FJt5$|( zX})g{^sUM!ZK~87fIj3sC`&V14?%XTQXzWyfw1@WAcyqEs5T# zdj%L5m)C?U`^RJ>`-V*TN1O#cd~FR}ud7^jw$g9t8swLIB7Vw|qm-d~Z{JX^8`DU`TeGT$`5T*HF+MZCz z8^KSWHv;p#5g7J&$oG1bmS_IX-cs-Zbi!WL-?3ZT-V^y=mD2Xnly<%c;hZOUwCx=bRAm0d&H-BEMs|w0*?#eaEHkcP{O$HkeO=4}3la%;!_UaPEqH zZdKa+>vzt410O&qoDugsc1t@G=6BAnDec@{nA?I6Uo>-DU_Q46hBNf!=joL;7yg~| zd%*|L3FrO(j@{DE_miJnSlU^I^7D=5=ON2~TcNb)Dae4I@S6)D1I(Yf!0^odo!?^k z9X)d2N;|9hcg~b9?f0-Cp8=nFJ_F428DRKr3;FL{l$QVe&hKi051s)|-O_$TP5zr}rTrdU zX}?nsc|Q2S^L${)^X0!wEC2o3(&h!f^LzK;1L)UnpW*O3c1!y`T>00O^EnqVpK}4LAJ4Lv&%a8WqqRCZ0QIQ1*Acch9*u19)kH|#I0^Za znU3&x?W%5v!t1zj&f8m+}`J5LR z>cZ#0z%^PnA6SnK76)`MN}DYZuIU91VPr z?^y;}m7`xm-r$`2-M%uk-0@yGcYgJ~ShzG(dPj4@?1nIW%PuT`II&PT=66BjZ|TD1 z*k{Q1LPrVpmwrXo-D)P-jnl@twq2(Q1z-c_;LN5y*Z^iW6<`CH*>nIKz|5ut*Z^iW z9Ud|pz|5ut*Z^iW9l!=Kv*`dffSFAt*Z^iWm0$yy*;IlJU}n<+YydNx4qyYA*>nIK z$luZ(zy>h0=>Rr>nN0_<0nBVFzy>h1CD;Ilwgel%(3W5W7}^qS07F}{dLctwf(i{A8_7ddB7cUA|`^-bm^0cDUCXGQ}!oDYG zf5@zivVTKnvXoup06Lit%5)(!-4tvQL!D%H(FT+=S+oHRZ6os^+YZX1EoJoudEO47 zN6Gbo4Pa(4LmPviz|b~e8yMOQYy(4Ef<0hn6Uy;BA1DVKTpnxygC4K}4Eo^@7|P(^fI${) z0D}(D1q`~u1~8AKrX1s_k;ga!gYPo^XamYw8QK7bHjw#=HlQ5ZOja)_=k*17WN1rS z`+$BW*AF&;p$u#QgRHFmF^*6Uy8p!M-xV+UIaL42nNh!UKGlD6_U7-L3;Lg&TQ2`i zmeS5tm;a8;-~G*(-}z0M|K#`byJ^Hm!J{N8xzqf9qytwWX^5ym&l#_b5LHQ{3BLF$${Zfa4>R!lg@(LV|%^8H;tKJGltre1t^BlI1DhE>Z9yHjCI5Gn<48y|#8oKC;hM_+H5m+3`VRA!NB!-(DtKG^MlD4q@AF2`d96 zf4WbkLgiFjl&_a!MQyHHBYW5xQp2MXznENs-kl}2ZO}F?n*FI2%6uFDRhSSW#i(J$ zE;M<3c`Uz@*^YLvEwz98;YL4wLtC6GeNS6_!j(Qfl#g*V&Fe^q1|35ls;#6)pWZ^g z5Kn&E%TwC-wDSE&e|N9Y@9ahTPxe{M&yXo?54il?o4P95uGrZMZ zE#xfwJmK=K_Y}&F#@bQ)(0j=B??uw=YR8ZR7iCfS0~siTe**?txCR(>fG%Lr4S51E z*kt7nyqw7^xjfT@40@P;WYEw4kijPVH)OEMY#@V8W`lqpu*qy7L;fQxcaX`0uUrq* zf$LYw>@r_}_ycW$GN41|KVdfNY3fB}^(C@)06i3Bz^1I-uVLx=c;{1l+PLNu*xr`2HDptk1(({HKjOf5lE5`*1%QF>O1ts_zux zS)g=}TE6(5P{TM4%l#F0v~!h($a>p{Quc?;$|(CcWF|}5HFytXIw;eH%yi>C5yn2V zN&RMr;{9_{_I7&Q`~|YJ)ka#jcQXny)5LV@E%rxV`7nl-448}jtl3z)JS7>~{9p$f z5U~#V`^)ll+0L!V79%o+{jYW)SKYd@puL&IC8O#%G-;NN<>%rLJM`?o3VHeCq!3HqgPh{o)`t|LR=eLpcmI3Mw z^Abt?ksV}C`vCQw7Rh8n(Kd3Nm8&Ktl4ipc@IZ$;{#$ zGMJV3woEDY+InTTkto*@YW;(|*{^~QWlSrdu z+lc#1e|7W3MB=%B8)@7*Ks_iqku1#FfqcjB{i{s>ZRVicM0)ZBNER#D)scr3FPy1N~(ve)P5d`Wd3l0Xg^Y^ZN@Dl zJwpn}`SITBb~BSm^XPnX(ZWaFFC>{vJ(fpqo%c~2v`Hb4n&y$-8NTY_7gNaO{9H0% zlAk)zBbAH|$t4E@{ne}DQ;9ql@;HW{-9`eLpU>z2+y~_GEuWi>ePBu71me*?n=E}X zQoX6((x3WN74Q6NvoUnSn=@9S6)(cdPw~ct##oPGg+W;}N-+d;{6J(L-`= z>1*VAkMEQF`DF>n1jpPXJ<`h(xb|J&d*tA{vc#Y9;8FL;)2(I62*yRz?vXdClFY3B z_r$BY(zV9%_rx!8l1}>kzUY)B**ehdq4;99Gu^ zgS_OFo_Nb*74q1S%3`^zE07O=swT#ESdLuZ*F>B&JPCQ+ATu$2{8Hr2Cg$S4nTvmv zXJy^OF7)Wbi-DZ!$8}imG~d!cirQD$PYWe2pROeo)wD>`VaMqK?b{r$3!E8KMnRS zLd4F2q@4O8-@5OSA9_3@_x;d6N}>K?w{Sx~<^CLavy*Z^-5hd$ z_#d@s+mCup`nL5)eW9GU1IY9C0X@9kKtFF!u*=&S{Ne2ne)710|9|2YuKu^i3u4E| z9mEuvk2PRE)`0m~1Lk85n2$AJKGuNwSOex`4VaHLUJiYj%R}D==3@<*k2PRE)`0m~ z1Lk85n2$AJKGuNwSOex`4VcFcn2$AJKGuNwSOex`4VaHLU_RD(IgB+f4`U6Ok2PRE z)`0m~1Lk85n2$AJKGuMtUVol(|E_1;pRxAu8f%+0`Ty~f3rd6gQvTns_Ce(%P5xi; z$S$RQ3n~9^I&i(R@?$CgKhQ5#S<_O=|MlxGR(8?k|AD%5l_xa$f13=p9Wc#5BfK0@_(@VU6cQVKN*_*AN=$#FXjK> zzooyF|3kfax&7gLKjdR-z4@VMS7$B4^$$OwN4Q|ERFkQ}#XkVb@mm`iDPt z_1^yQGjs3zAN~&-_3=l&#(w?yqrOni+X3Wx`+y$aZlIsHC)nlf4F2%;2S0gS!2dt- z3RnMI;{~zf;|^j9%*PrqA8WvTtO4_}2F%AAFdu8ce5?WUu?Eb?8ZU>j#^qtG0rRm2 z%*PrqA8WvTtO4_}2F%AAFdu8ce5?WUu?Eaz2h7JBFdu8ce5?WUu?Eb?8ZaMgyd1_F zmxr+i%*PrqA8WvTtO4_}2F%AAFdu8cP_IAFxPR9(?$22Jca1fFv!29QZ>)OmjIPAH zs}J(K;;!VnZy@sXZk}YDVG#1;h#sU&U@)?JmKTYtI25^7D_=6J!U$y5#3WfbzFj)TZ(gVD%y#}6mpH0855j3&ArCHe9@!$`%7lAfDmCXu$4B>m0urjd&p zy8(8y$Vwy0pUXQU$ZbE#&ylBQlOf$C|7T2%B%{rxdY#%8NygptK)cIW`I9To$f-=; zv_>antDO<#&_#lr!}NEqr$E-upGI74+9IDGJBieK)f(AgR~Y$_*a~@R)@b5iN8+>z z!^sg%d1j|Ur0}IAZ{9YD(0Y;{rzwFXuCAoNgtgo23zFTj5njZ`O7ds?>>lL7Wy#NO zo}Q%tUCICYC0)s%c#T#6TjK?>J5qN(j?w3OVL<2=OmF8hQDlp+v8{RDSX3Kr-l%bgk#t zzGP-N8m$tIqJSot8Ic_NKF z&;$3$>0HKWhiiy2y$-^GL+(M#$T1MUx}f zrMSGSxQI+Jm)g8*>o~IYmDC?zMa7f5nm)7UT|6=C5Qx`8c`vg;$RPhsCDk4DIA>4z zq2KP#G-R+F)Hebd{Mi{5i41-QT#7;l|0}!AL56zq@*AE(Kjc?W@cE(VoqadL^>4k^ z<%iwEjpT&}_M^T~&f5XxdHaAK-fp0uw* z#x*dEYZ&jqFy7%l01Wp5xIX~H{Q>Ti!2Es!4EGbbPx5lOPjY#DIb^v+aKA?xU8|dfl33hoqgFn3e!A~9+@LwLU+}v_l$4BS$$P*1~ z&AdzQ?UKs-^>lK`H0X~q-@7?ET-I={Hy4zLo`hrh=#-jd=(o|xGrpRT0m;LVPqnN> z`rQvkR!`9)O>_q!w|04^yfk7Da{TRBvanzavbA|8F$qXQZWNeHwy35c*LFBc{Cajm z?%(gqPyX|I{poK~KmRB8x7p>EVC){TcL*~yTyf4Evi4RqmOo|X8#H|MR6LohkvYhC zfreL=B#|KvlTm&J<6sT%WilPRufX!%jERPen9d-L%ss}vHLS<%-t6avb2{5Ck>bdX zp2%A_M2c_Qx*_jx9Vylt)&=>v*KG0f`}WAaD@BMddP?M%=VypFceF#^{&I>q$+Qh} zl?CBqMrUb0_^dEg{OByr8QG~#;$vHhZ=?+syFHdTKW3mfE6NV99k#8n82Mb9KXz&o zAbJ@(V7ZpHk2v@H5Z?}EJiZ8!1Sovz5&&U6(=ewXIOrx$b; zKO6gE`6BCXV$4@*9-X<&Qw&Xz=GP6c_YnK$N%MXCTVCP_S7|=pCB|2L*HD_LpFb2R zPH>mz@7>1)iTcZ=`TqTZgTzld(tJN<+Hf%`O)B3rX0+%PtXUuE7$zPWDCx;RK2fZk zCF$Q)JXP%BJ_vm~pEOf+>)jtYzh{J)@u@em>GauRO&34p18$MxpV*C6|F>cXZ3}ZB z7#Fu}Jdua5j}+%?yCH9D5-A?8)de}X(`<2VW_#q!=d;9`Sq{ii6K04N{o5h03z;G+ z4%;D@zdb=ruOQ7y4NAs}LUU+6_4;?ZrA z&eN6s#W|)*)ahpGEe6->fNXcLr&wmQ7w#%}a?JH61Eu6-nH1NQl_>nKZYJm>(*3(ad=}hlGo!qa~fePp621 z`jV}ucV>vwzV}CezFS0yx5i1n4I4OHyg$be%X2$QV}Zv@J}&;-W6&$MEBa8}qPf^> zw={R|+_kxAwLb{U6^&Yo2R)_vxa%G}(a?AtmdC$PhzHJ2M&7%)qv&Nb3)yvyo7i;S zY~=erdWoO>q`7MBvp_MrsWexe_Gyq9TwCI)jmL>D9YN}q{( zRus+=UB661o|v&f+-ntz{P22=SeHm`zOT<>acYLNCa~BbUW|?RMw#08826XfZ9ZIz z7x(p+)<&j3j1w)-N^3IjtQLzWD>Os-UUOo^>YnwH^X(Rh$_urS-#X0^=bW=dUVmYh z_++#h^4dz1#3TEqwS~NIqeP3F8a^2;R#8hb&yEC$HN2{$yi@z0;?RiN$nPe)ipkct z$j(9sv1Zxk$b&m6M0!UWBU?MziNQ0a^(EuKTHrmC_me;4nysh(!^icX@x|uC|Dy3F zj~6h^N5OuykwNPAqs3mge!dTIPIv{U-w^(%T;e?z!AYQDa?2f$qUA(y7 z&L4Ty_IR=9YiUk*Y-yb6-(Vz`H(s|$e2@@^{Qh0EsQW>h$8}7dFLsHYh2?d#qC}U6 zvyn|Y%@U_hlIGp|x)a4FZKQeko_eFiOJ)++Z4fN_)RAN^1O|xL{iSQG==K!HC(T4X zabsLXJP;-yX|58YE*s%>R%i?$&Ufg>%G9+S1&47b`E)a1B;o z!+I;J{d}hS{*+8IwdF2S;qq!4uD?#sqHnupSbj5NAIpsgBU9I_;gYZST`(o?t>Bu){o)b^r$wXEiE)Wab z?M7CoEf)hmUPLZF5Gs04c!;cYun}iAC`RtLbv<3Y?=7-p1wUI^xl$%iWO|59Katrb zGJlB7Pa^Z5$m&I8^(C@)AhPx$vUVe~b{1QR{D+PsMfTo`G`Q?`3BsuREa@>wu#J0*4!NqcqR)R$s`*;$7-j1w6{xka`1 z>PW`vP0u=XH*T+vXS~k&tiv|L_UeTinTKmOi{-6K2wZE$xGQ70_H6cMv8Z|pS;4Ly zx_-0Rkd?1z*RI~US=43R-8qPi-0H6mQ=Ato#`Y(zBj?%Y{miKiT-D=oY%0 zf_(j`r=oIsxCrv^R-O>M3>riN?~E3+t6dSx++C=IYah&gB|6UAL*d$c*Pn?Bok=2G z>woH`xadhfUOV0;NgTB)S_#*FFM2JuN-v~v?W)!_0^~Kl;0=IdhiL9N;jo>$U?dkU_ zTbW%Vt1pqYGm*tqZkNdFOJwa#Wbq}kJ|nL$k+n0C#h1wXlDr=hSvwP1e2J`I5m{d) zvX~NCUm~)8OJse9$oeXg^+R&kX%9Ji(@P!0_N~9(rzV3wc&SHRSVH=D70Hy&Ds|Y1 z1mgKvAXfyHdd-7G(sF$PdD+)nz1uN~EM1gOp4InJrw(R&#@FYOn^k<(lYCN0%*R}E ztD2v>qi!mx$<9vhVdJmP8<$GH`sWfIwnuwoaw<7?TTKoXd#Ur5Eg|=3izK~?O6^{} zlyq-RNrz~ay0J2mSbr=apDTH*@3Q+|?B#rtn(eLb6PiTSXYxpgVLs|w9?7Kpy>|ap{M0*}rI1r)c9HTQ{nT^cCKJy=J4pq1fAzp6 z$s{{z2MJs3ueL2tBFon1kWc&k)kfAyWayP`5=o)$(7=X zBV*^`^VEB{#FF=!X~-mUF#(zEVUmno{yUR_@-9q9E?-)?Tt6^edzRUH=$DIo-i^{y z#b$GMlEGbOsEfCyimzEa!(Mp3^i)xyOYw5tSmJVy|z_7*+Ywy6Y z_6}?Ez_2C{YxTgeRu60Vz_5l7>-@lcogWz1`C;uH7}nllO&%E5eAFYhPvz9;X)^8O>gwzPLH@>u`M;Loq`W#s+jR|a|LKl1lS zz`T$B${-JYPu`d0eGGDGxE6A0$hU!cz6}idHss{Mkdyz)pdZTR`8hDZ_E!e^Uvqf5 z55F?VbKii$H@Tm`GMAChBji5UbSe}diUp~wI;dS{nUj-S+hl~3EPY(QuG0%-(G6o+Y ze=cDR@{m{O|5DCn{LrIXwJf6K#5%i;ewALPDq{on&Hhq(YR2fOk!SmbB6$j@Wp zeHi-f!x(+XN^E`_ky}jV{k*ECpD%m(h!#ajefxW%j;LxN_2Hb!WyQ`LBz~Lqm5$Jo z`fbmPZ|VL<5*LKLr0UDMsQ>xX3Syaw`i}mOR?}ftpJ~~)%n?bB&?^m+OScQxNLPkd0^zDuH=<0J{I!Gw|72j z;*=uh>*tYHCBEvck11mPCAp-NmcP3Cs8n&r2=*I0nf~fJaj9Zyx!ib%90KbDZ7kE} z>pY^YzM{M@@v-ph{an`fN>_8vZhhR`eI$Dodoz(v$f)r z)J=FktW$?{vG}PT$|O%Hp&pgW;=L*IkL0LR+UeBM)S%@wmQFkfOesr*;UH? zk@HW!$?OuDU8T%7BJ-KZ>LS;vg!*#3OFv3}&X0JcJh@lm~xNux2{t`Z1P&yu|cLIjXzvLd}N^KIO%Cu z8f{lmEHc(}{16gI$9YuzDMqrolp2?J$MhY;kNZ-HX}+lMSh<}$vf~nc$C@{l$Q`@s zJJ$W&3|TH;d{iIp!nL!R9=mn{D07u@pq4-KxNJSgI>~{wpo_j(Xshp7k{w9wTu*SLr)m@79sFIsXQE?($C5YRY@$5jIZL@%~4u-&EhR-POi4 zs_+Ar7ank>>90Oxd8?Jp>2~oemaps5jh>zU70YjIZ9_j*(Go#_yP#h5z=UsDUVW1z zjk-`4%b^`A9h1tNSh>=yYURZI(Rz*@2Ig;Ev^xlF0?`W-!T-{kyTe*Vur zL@Dd%zoc0@rH#8_H<06GA6b?>u!>XPa;q(9he$jnrm8vRMtA1tp3X&m%MNDO_{SJS^c_N zE|J@9xK@&hG0GL?KBTsin3N4Nq$T4EW~35R6N`y7+Dc_MqK@+HS(8J*MEAK`gh;M z#&0M`-bc+-C(OV5)A!7O_Z#CV<};kxSaD+JPv--GmpikMXpc@q zz9{67qL{$s@eg zCH_g`z7qo3bx5V&R(_ed+Eye6-BjwSi3#H9WHo8>%}ZTTZ>i`Px|^(jz}AGTFA*Pi zmGa@yP2LM*dLQ&JM#hdVIIl`srJAc|Vu;|54%P9IG(j?(03E z&H9&fG}=5v-8<|BEv{M4aW3OoY42#sPHo3wj8FS~qoZ839Un9Kn%}g3s-wK_^0{Pt z%^F3ymapm9+tU2;UdNBrm)V6i7Q4_gVsCwk4IH#Z`J7b#{k;6UdU<{2Z6$9L`S%0C zw+7(3m&e(+1VtLI!M@3_VlxTLT|I03fA;Nx+?EhB7WJQgY%K0>F#>r&zlvf;+F<02 z=Ve6InSsdX3ZGJCYA^}i6s3M(`k99J8i^cLw~APrpYm@f-{I|X`Y(#8?vw*xj01I zu{rDi(_3qi`VX}o*D~%<_OtRshjNbd7-t!kC|3?E=UASxPQo+gBG$KIybphUUn##2 ztnc$3n?ATzkAP-_n*>y4$;_c zb@HV$SL4sVozIljJ4wD(82DHjsHw{|79)AR{%&35ag>kKzdQEj_YL{D`@3W0e93X_ zV}maW%9|SY`1t>@_ZCoA9nIc1o)97g3jq=cF2VimCb&Z&KoZ;~xP;*D?t{Aw9^B6E zg9ZyuaF{^`m;na2Ac434wY#`A`QG_n@;x_so_BrsuElzOw^H3z)w{b|_C7r^Rl3)E zNZzYfY?adTW_{dgHD?XUZy9c3d4VZA!In+X`h`2$a+>8~?y;5INk5+9vYR}fncH<| zTAhuC=UC2KVS)QukXQehjtks=w*GELXVgxY>KSJ^*%ptVFAH;%Sp6%8yIB496JEIT zjxWCZi|_S9pX7VJz&0@u>+FB-Wb^L6<9of( zK76ki825U~JDK^eX1<3RI(!c^vAu^G%=a*Z`5tC4-@^>%dzis|4>OqWVP-ksO$~j% zvzqT=h7RAu4CZ^7!F&%h@&8Zm(3W}rUzzXZ-0@fQaCGxsbh&!{?gQ$hh<<@n>z=!t zEKhHI)r~H9N&UEo)==5i=blH&GqSAIDY47buV?CyE=Nh7{nuTp|0km#U4D}~lka)@ zpY-rYn;WIhht~hs-Tl$#RjE_S`oAml!f11{)Y)O%Ga}}~X!E($*=qHb@jtq`KuKSVcwy|zBLSQ=A3wtR7v>qIw)N}V#c{Zoy0 zqs*JKtkfxQ^*h9ke$JIT&%fMD?emq-7 z!vc5R@F;&L;(pkDH@VRdc@(DOG%rp3^^lvoZB5q)xf*&)*QruTCm1_1u=f55eS6$6 zU47)(K#cf1bU$CP?wxE@;HLpg^w9)bKNvAQFebq`{pqJi^ulUG1LvnU*B5^X(G?dD z4kU@pqAPzFuG91#6d0cIxLafYEnVaJz(CKBs=ISb-`2+u4Gi3!*LGv>b2s%@$p!@? zXAN;0j|$WA?+ps%I2%_r`Sr9;US&w&O#4#mVDr5?Q=wsjnQ{85o@v+VXOl(*rk|g# zT34Q-+tnQ%2Da z*tgybQ^iYda}aO*+t*drre5ra2HaA=)c4vX#(w4nCJR0&rNiXOkz7E7GZXDFA z#U$c#J+|nB<5v=QOg~@uNVAK0Y}=u_{M-}7We!)@*Mlz;FRGkGw|#ztct^7Z?!k_? zi8u88&Y$wuE#f3g>N?+cyGC3f_hY9+iF3pydN?X^*I$Wew(O<~ci2cAV(#{yF?Tlc z%EPNwhu#B;dmY`aHsr2I>|1?G^~sZf_;kuJwQR~bit**Ho2ts3u3He}AN_BuL?=qn z-%P1rCQ{`Y`Hj1{*{HyKzFYdcnPoM&?Tl0UtLYvOoN`LV8{p~e&VNfC&VSFvS>>Px zS9HnZC5gx1j?fjq4EP|Q9DYNeNwUpJV|Y^8Yr1UGZFIId(41S!Gfa8rxgfcxbIqK8 zCjQhb`=rD*HMWRXXWFnEYIz~gR=FDyYHn`Nhh}xIsIKesQ~k3dlc;i*eXnAuk|}@N z0)LL)`B2?#p4|^_-7%qB_FY@zHB%C)ZdoT0yOolvuoXWOFX)+E&Hi~e@xYH#sh^jh zA@2MzwMvmDoOoQK^yU*{ptkYKbEqoDU(j#V1$ob6J8r!2%h`hDX(pO%I=S+jCZraH-qU;SL%iFqP7#g%nS317k9`AGix(862dTP}BH zt-s3Ve54b$Cw$A6wXXRcU-%JI9sx*{+%h-5U1)o#^1m5JmSRz zhWT@>7*71zyn+5@IcgHWyJ3L8#iLBb@iGnePp=S8eeY$X5&q_vR{G%EcPsY!UtEqP zZgw%$|IxJfsQugLeB}T3P%`3bbz{3P<9g4oV~P*l74^M7)9>@-ZtW*ulFrz%>D{Nd zyyw1ZQXcoG`d)vyQ=^2NPSO(45T}h3 zOFN~)DaJs#SbEPF2Z$pR#L`8^d+qR9#h5yEuLx?N-(o*Be|zX_KiX&PgFEi3Wuu7a zt-Im2xxI||`yFBK^5kA_`EuO_H)Uh5k6jBo;qKoUK{}teKIq2H?>*~+&3|zt`+GSg zNxrRayTV?7xW9IjyRGsGA8b7zA79_@>9xj`Iyf{MKK4E>m-?mAWV)b-Hs^2M=li922QI^+ka`cEwp3hU`RMa24UM?Dadax>D zd2O*ts$-ft)Sd%=n5&9k%bg!FmS{9z{pLGT2)y^$eDz88zJz*S1rp^NO z{@#@2PjzR3ikHYC?)ArfRV_tR;*XlnS38~!Bu>|Fo{D&HB5|A+bJeNOy}p$4#%R^Y zvToT$ZGL=`>fc*#ii*?TYtJ@6?NVFYdAxS~dbMiuc&cZ?m?dicwN}Kt-&?FQ^eaic zuxzlJAC#Q<-F=JHrc+0$&abC0QjM3^A>O!kk-G10rx>5TUZjfV?Y|i@ZV3uj342!A z0)E|ovAQ065pkJuOVsWu&-{@8ut%%3mbb@0tTGfmMsqbUuFM*V%e_ zI%kIj>w8wG@%6Pj@MH*mvM5a;@Jq%PRc>+?%K z9--eY`H18nUK*xHm-qVo=FvlSs^4U`(9uiy0Yu>XU>deVlgq(5lYKz%EvmseAF z8=xaf?;`ogANuQjEjJQR3hk$zgPw2UE&J)LcD(FP-$>uJu`EB+T^C+<)Q7hH%-k*W z<&ML|U2f0Ra*g^~$NO&BS~C}S4U4iSd7Cv%%8c8b*rsf{*4N)^t()%mQtl(8-#Wof zwez*#2VRrlmXd4r)2|}+;n;%$g~wOlFr-GLj>tMFFkn~p4L?7B;O5vnHPGCwm!35( zrMEVk6zEyvq>5c*h>o3pT;SIGJIp1h3w6xkQGt|?mZ(adT|GH`c%W*Wu`2tT!@BRH zp@GPKO;m;gAv*8ZVRseNdp~)3T0ipRh6y-4#Di z4LqtIrvAx&gjy1*AAB$I3mcEx?<(~ALj{IXtpk|jEYFXU_+IciIFg9Z+ zHS3oh`flRkfxX*@s`Wvev{QOSAShXoO7LL0PC0*Mph$uFYU0B=dR6?+-*h30(B~Ro+|!^=Y#=8I}7Nm33}o-Lvn6z_+IltHBRT>yFtc1@hiHsdkRdt0Rg9 z1>&4NtA;-PKsV?-C6J--CH3go2RduLDS@w#UQ(&ttU4k%D9|e6ypnsye{yg5^!fw$ z^T|^KiC2Z`xRoEeYd4v17*d7l^RK-AhCM=o&Xx48h>3w&t$)*pUk=mxPK*s?_ifW_ z%P!I}2aF25b9Avj77@^4vxWzT9x}g4fA6?{UTkQfN%QaZ#w8c^8najJcJ32h`AoQ8 zw`Ndad!>!;jC{BBhDw71Lz)$IWj~kwf6>l#x>l;mflC=f^n3T(>!1DO0~xa)(69Gb z(iitn3{-7$LU(^P%-jGlHW0h=c0IS~RDJ%z=s?i?^}6uWMSAG>qXMfdEYUs7tNUe6Nn(Wmur>^}f2{k)wKu*u>4D*#-q>Rxa&c-V&*6m_9tQ^=5yADUb?5F) zeebhUF8J`H8&Ue$(N7<^%MN;b(l%M|yD^V?EPa!E#-bTL9qb?HC-usLWuA0%<#Rsx zdTJoy(Y5;8=p}yey)xsY%xiMKdu;WCM+9qGR_e&PvUiTdKGa$C{!A^)N*y`x6i9xQ z^pnTyuVq=OBj>Cwxjp|EAMCDWS*auEyN6c)c=1MBmX$hku1s&+Bx|RBT9%bMa-RKS z(<5rb6=oh!kmDh7i84cUj7E2ewCrfgJICPK6V-M~TZ~bV5-oM6+ z_oIu$v}_0I=YQ9F>B7v%WH;>g0iAe;$DM}Hh_c?3>%i#Nhq9iUzkW+~PAzj--`wYM zrU<{5a#@dDA9k?gqSd;cQOZgkxwf2T^_L~sqGegBBiE(*tUt|*t9Q_1jh}Syt-E_5Y?g&*<5$y?IEW7YL;o54M11*?+PDpCDG zT^1{8OV;_X?5E^2D&w@G=annbVzvKu3F1>#g4O=7lM`P*x=2a?rQN@}2RxSf2|X9B zCaKa>W>Jh=8qJNe|CRgVg;sw|^`wfVO1rYKowxszVM{bo@Y zC3R#ya$h{x>VJ8Cw320|j@(o4oj8HoaIJ|^mX$hkKQ398{a5z;=ge6F`c>9y3smzF zDaoJqc@`-BvyV8&dsenCl4g<-+f+`XB4|>*#f9%Os)AU$%nsDza6%J zzWO|6KdL`Q&IL-^l0N^{^No#pym@@+iVt-L%Q)MS=RETKC)=eH!L6 zlTc5;d8&$9mX$j4+$PP4r+&oV?}(#iS*at>e0o~_y{W5cSyt-E^P-L$R+9f?a@5nZ ztkjWbO|ngXsO|OPtZA$1RR?oW9`?`wR<~N2g}6qun%Y-CEpa1VTX!6sf;e-Tx_ard zM8rRTRZj=riAP*BQGKmT-64MpSFW!k6M1W}wy)}G>8JEZK9_&;{H^hYaLOS^?vC(( zw8d+~#)bDsIkS~#xepe3>oJ@yPi=aip6T5*k^btD-Wn!o?-75I&%;RGB=vTGk+vs^ zcjsL04?g${@tF^2_`79UPuyVaIRCcq7ZN{uJ>0)E?I_}L{Ra7;E~-O3DbGOvf|pr{ z2TvUAmp)71{u9o>%Lc-3qF?w8E>miH=CjNcx+$I~0x?<;+~l{}ayhU)j96&b(82(j+g9{q{}5-37~Y z5kJX($E{WEOX4gM=68A3G83O_^VFS@Ee-MQ$}ioa=aLa0JpbD59pioC<@sakGM!=& z?|l$cxB4pFhy1y}KrDSY&jI3d&tmE!dA&Rz!@T2={>b)`??L1k-?Si->gmCeCG-B6P+y>(Rlh(pfsv&X0%ww7BN<^867@440LzgvE> zBg;x1`OY*4*SU0vBg;x1`Oa>`_&t6+-_et9`D9tCBj5KOS>xpyyf^GV@d1@B7H5I) z>$A6ri>~ndt`)mN+^N$cUx#&G9v-|a#3yaZI{%e-kptW0BU_oqU)z$b^FZSAr&e#7 zdf&_Ktur*<@@%}H#c#L#@5` zJnxk7$+A*MzRM2Jk(|b6jT^-sSyt-E_u#?V3y^+-x!s%{x$_gpo739)u$nh!QzUQd z91hP(@9Rtp0JhLq|)rPN|u#6^1GLz*|JeS!8bFFTW26%yg8#fd_M{C)A01F)TH03 z&YoS;DOta)=dXTy(=W4Ucf_V1O8Ow{k>B7cR|@hJbipGB+E)2 z`Aw1ROC=tBNwF6hkWlr}ZHVhFPNcdYoJjnvc2X6$*w4f{hb32^yKf3e( zFV8)2eX%^tlIKPLuCq0H zMkLQ?{_eA>{$;)W&fu0Gx-qUDqC8eHdja=An8&kTgt(FAJstn2zq)eYA@@6S4gas~ zYyQc7hdfV^X9e;cK&ms_ziYiJ_fT?wB=#OkR=XjxXS z4P;qarz{)Yc!V7F^Ed@#oJKd6A%_l+aV{&zwJZxcbTHm!+30ct58N@ZBmCNOn;P?S3=<(-`J9?SiC*DCz3>eD2%l)Rfr-fJZ9JdyWc z$lpQB`$ObCpD9XjQ&mn>3!F1|!vB-^!^^v{8t{;3Z-4k^w%PtrE zYwi1LXYV{3ytvObRVZ5@;tmnVl|Ros;#ukZs_5jc#0hTBP>Y(JBL1LACsidPoVeiwcD3+F3qQ5+UyHc3h*yht(4u{`XgB>o z?Mcu5?`ThX53MSGZoR@isKYleQi)4#P`C%R->1Q9MBfbx_n^Kq-%W|TRrQ2UL3D?0 zvVl8v=DtmdQ)fG)CpZ6uIC1X?eaRi^;GWxFukP!m?d$l#@qT!upYGq`f+sJ&t8X~D zHTcw}FnzOOFXD7DE2s z&A$b^i~2nxZl5T2dLeg&z7q8)QNI#)mGDOiKb7!biMW)ASBZ8|qJ5NTH`(S|w7C{- zu0QBDnc9EZ$(?$8naT8AP6X}L@$LrE^HS+|>W3dTC!OyXoz)X}H6xvO>z~yfiZmmg zbQjO)UhR{U&e_B_^~fU0NhkB(8+!TGPe|wIuWsnNt4BF_)?tet>QVznIp_lkzk8^Q z9p#f zK_?v@PCB_NX3!CF!%1h&&Gh>CxCf*&^XX!@R`Ca-o4av>Rr1c_sYBxZLXH{rYNgLo{u)?h_X@c6&F6g)m_>0 zUhW@CjiGza?-$stHV&#q_jOme2|+ zs>fy*_o#=byQ*Gn%B&%Oefx~^7wbS=x$a)|ZG)-A3m>dfcQdXh-q>)W+8F#R@!n@m z)#?1_i68b%r9P^84LtwAk=f3-J0djdH}l0pA$OqtuBnEZ_Bid${VJ_)g{uJv zb~=sCZy2Wy30EWAZ*$;V&M(4M>vkuJGeurg`M&L((yHY5@0; zM4J1V!4)=LR?mxEC!Q4}Ox@XZoVZZVt5Kdyit(?U7Te5k+!kGl5_@#*vu4Llr>mYC zNc+K6_4LjO;^cg^z77HLcRAoZjBy|dJh?peIeJwNikAX$&>+tKx5c^8drtLX0HmhC3nQ;tEY zBk%f_cX~(HhSCS=n;bhgH+p{uIcDFmC}UsRl6QT}`??n#_wrTZ&0$)~%cb`6)x70l zTI%$&a{Mi0sndL*my0r)yU=r6Zk#qu?>3B_FvRfAgpE9! zFLxcu5FW+n$K}1;Rb~2B{aGt7ryaU?O{Wh1jmBpDuGjSGzTw3C%3Re|;=LeV{NhTK zc9ZQd+fBAlbhe~#GxzRv8ku~XZ)CVWpWe&E5AKHRI|IDD{a%d-eRiXl&y$S5s$Y)t z^0s^Xnl3fP%jdu32-o==#a2g5{%=z0s-Bb}j{3sP3xnRd`j_vGm$ss-Q}&Hnd%T>3 zJL+)<6!!tyH)Q{j&o^U@{Z2`f|Ieh2(6<`zcfK=RA#a2p)M>xd((sy+5mDOVZQ4!# z9yz)@*+3!%fF4AqvZZbiY*w}>J&vMuRLmxK4s0TK{s2~5p zkm0|9p^GwL)Bzh{)D0V8b7rwX$bCYeY}k6p1{g63yJQ1$w1Mzb3IFMg!K)_)92IOc<`~yP<8(uxrsSFr(i09&y&uiO%JwqsY9E(e2|;E>DhseP00N$ zhYc|FVFQeMU;~W$@ed3c{u>y&C<8_vumMKhumQ%|jgb3_tEev>#>wxRBoWJid1|FY6G z|A>vuHUEv+=(?s1v8lr~by40hb-&4z#-@f1^eM<;0}OrG0HYq*0Hc2V14D-Y28J%m zfKdnP0;6u&0Nc1&?i2cC!`4GKz=%oMB^!{V4TPU$19G$(Y0d3>j>A^$bN@5Tg#*fZVG)6}2O5a{j`&M-G7u`2e{HY|2oM0waIm9~gNH{|yXX zlmVj-)CK0c!8SMgSdQ@zhCciPqaNf7FzQDR0mCM82pBezL%^_!9D=iV*hCJ29P^rx zBR8@>_IeY@c7sP9GEVUaLzQ8sZzQ8sZzQ8sZzQ8sZ zzQ8t^eF4K4*kC#0WqsHHqaN4*qkjAYLx%qbhAwP?Q3q^*Q8#RWZCot>zkZG@{A8hW zmUa&`&NM}xGk0`0Gy$(=5}eD0O}o zbE&%Uevd%o2F8}KTYCEhI>2;R??O%E1!#eULT(hqOwIY2di8;nmYRz_Y4e3cTwdF zY3dwL+B48D*+o@4sF@Qnuty+o{EO<3ubVqD9&``feG#gL9&6@2EZ-+kqS8gRvSc$y zwd@_(_|-)iYyH7Z$a;{uNJhx&9>HL3vzA|3f zKC(^fob0c@P1!y0Yp+cz)%AhuVDIjMCGTxi!(R_lQ)YJ$lqhH8T01;IPjg=daxZR$Ck__O+C0tIht+2V^QmeJy9cs9 zJ)|<9$*;~&>K-UP{g5i~ppe?#uzTRf)q|?@jsDIUqkpS&sG9M?4QHs~Z_=Jsv;Rn} z1{jVge?nCq*u`lP)IIRg>QMEhU0bL6yzYTYXF}Efri<(QS@1uT8byt;3od&ntu!N~D<#(zn0MqRX=_sBUFYPepbzJaSj zXGv$l$v%NWb+;*nCuO}lVW#Z2Cbxb4M@s`!=G#EI5iRPW?(PW*X|i>hq%M#LWt_D zL)Dd^>JWeTLx@_uqBil-Sr^pMF5R5rYx)G{nfjgW?VOU6`vfi=xcFB2N9MFTy_z`4 zGaVCNRPOpF&bgYs0t-xji*>JwQ#D4fz^hajRhFM?lTI#UH%G}j#4##|sOc~2632WT zqC$5yAl^1Q^e^YkxAEb}$}OpWH+G2Hl&`h(-u>=@8p%VVI!-2*wx zghZQ9WM7qKWsZ`$Na{z|x8+!n^+cQNME?A%xm4z1X;+Tl=*Fznk@ZB$`6B;IeK{A% z`9h8_nKz;vgR<;a^FC{?>DwPwi`vh38#%_*^LH+)orWI{>>F5gp6(+c%Ix zhpJk?b#c~o=o`q_DC+$6wsY41ZeBoJp-s?MX&-s9&xm(kjVS5GzI)nPHRkFn(uub^ zM2$-`nfUwAP&I4XL-Mmptg~wByAR3F-2F{{Ui5(cJeB#3dbd_6>8N(+)Up#Ho=)Uh zm99q!>6DmwR*ikKk978LKCdGC>?56L`Om8q+4qsopbO_z?pCWv=U~zhwJYW-(#byI zf~w{JnRK!gx}ef*4kDe3B}3J#`az`g`_>Q@KWz}{^f2>?9OE)4Y)trrGb>HsK#9i} z)RQJ{oipkB2J+ksiFTb3-JBxlAm4xv&h{hS1D~%9QL^v7O`AtIcSqMhWn9v(^hf3; znbTx`mUBdAo3~qayP&}6C*b_G>QgS&Eib6fk&TG^&%dCKPi#gUcJhLfZ7b`^8}8-* zQ9oW#1=G|c{Uz-#{N*`9=6pGq$#EpxIl4Y9bH&B!jhs4%`UZBHd1`pO2F|aceFK;) z%O8qitMDo^7HlshSL8$up z_7Bb!Bky-8RQ12y!kJ{aSKxL7oFdx9^r`7n0@PT<)pm zUOQpRI!=jttpZQ-gs2+jO#U&yF^tjbf_j|Ty=WvpG&Q#;)DdT^G%XOSg#?OVu zf9a2`KRSI`r}V8z+a&t=mbP?mmvwbMJ@K=d#J?5)T%UWmfzHH#JDoyL_~%+qimyi2Z+bd{#a+&evUX#o{x0uba#lK`99FaE5)KZ^XyBYk8J*sIQ6yn^yDWg ziI+?@JUh!9c~F^xZ}jU9Dn*QXZr-cv$xZz;v(+Vr-A_ZB5&tltrt6I5kH8mtWzEuN}OU%a%wR>XKlrVWX0+j?^Ij7*yo;~AM}L2RGV8@YLQZ}iPGCAQDn zlY4!De6W4vjX$Q(5Zk^)Z2K6o?T1v)n!bf~vtgPzVOgI(xpp&gi7h@|ZpnJ$cYpKg zBtupcFP-SqzE&%U@4YOn$97smoGx);ebHS=eDy*>ou<(|;#Z9e=#@QY6K9TBK&P0y zpSb@wd35zIr-<)2&Y`cz3nQNPS#}+x;&tLJle6iB$!-ugJDWuxt$vI6s|T6%vxnaM z=A?Hs=xsM|lYB^MI-M@}9pW)ZzR($Vd-BhYrPimGdityGf2NCsd+%Ka*L&eE3EoZm z=6_xD{}X?@W2gI7rpLsOo^N++5A*7b*Vyp-@c)uuy7WfBYw>f$s3%u~6P`S1zk9mv zVPf;Y?x#Us?B>6}v1`h?#vbX^zI4eo_B>u6?iza@54-b5Zv1+qZ{l!GJoK)}w4ZC* zk=V4KYub_6w4ZC*k=V4KYub_6w4ZC*k=V4KYub_6w4ZC*k=V4KYub_6w4ZC*k=Q&p z*E~OB^E_SiT!~FTa!r3CHvPyo{fXH0BiHmNV$+XY)1QbokyFk1AvtoY z8Mnm9sb;(pBd40&N{pOp#;wODr=rGUL!_MHF=E~Io0GfV&qhl*NBl*O*b%yFr@L2B|#obia+5gG=6pQNNIO$V)&#U^b98UWM-ZLt4;|u57YL7!pCUvru z@^sc_iSJab<&}MW?uGAqgjZ+E&EdXE5uUA)olp6GEAM?nQDewHU%o%Q{^qZ=)%WzS z*RPg-u-SM2gOuch>7NewPvloIE*vo~95F5&F)kc2E*vo~95F5&F)kb)7s#(X9+6*p zoFc!9{NRZE;E4R-i2UG){NRZE;E4R-i2UGien5WZyoCJ9c@_W5`L@uQ$45bBwE->nb4KQrNHWXCNMU@7%Lbvq;JL$#u6A~3u6q7F^91S##qFd1Y?Y1 ztb#FiF^0hy(-_-ejCG88FmeEL0T{UfIRcEFf!qN`E;>Czr@ISCjSy6*P8rG>sZUQzO_F1g%8Bm z2V(03vGsx2`ao=bAhtdbTOWvR?8Npt65HqNinb!QZAfg}me{sAv3(ZA_8Ae|XGd(G zDY1Rl#I_HR54LZ3zIlCy*!Cr2+sBA)-y^ntmFl!(gcx}j>k`C;yo+@S7E z)+J!%U93yM$h%mVfRT5xE&(I&VqF5ZW0Tm9Sz?>@(K7&5;F4kvYG_F7^yyJBJe6xs}+?>BPvp*gHWVc^7*pF!C<; zPGIC+?47{KyVyH{k$16o0weEY?*vBP#oh^Q*Am2bT|{ixOT>2VL2TC~#CEMhY}YWv zc5Op!*F3~_EktbBNW^ySL~Peo#CEMkY}a7Kc5Oy%*KEXgEk_LhO%5WqYffV1UF_!( zJMyl{eZEcR z#CGjXY}ekzcI{1U*WSc-?M-ag-o$q8O>APvn*R-({7Y>2GQ@U|Ky3F8#CA_XZ1)<( zb`L^~^B$ZjpbhPwh1l+8i0vMS*zSFZ?VgC(?v*^bw}&FOdn;nQ7bCWNKw`TGB({4% zV!H<yB8+5dtqX`7bdoQVPd-% zCboNFV!Ib6wtH}5?EOv7rF@0|#s81?w|jPCbC!U;yvN=i-(zp@Pi)Twi0xScu{}c| zHfISqTOfuV=)o4wE>Ip!XBVbkusyr@FS+r9_2D1b%pEuzAvSXs&SZ#@U&Wk-GZ~U2 zzlu2vXEG$G{Q6&W7S3cyj{GX-ES$-Z+{~3Y3nDgiD9(t8&D@Q%DPrVTF?Zu^isZfa#oVpM+>Ns-(m{UZxx4K02lSmM+M(?7PVRS^k2``%-^d*!xBP&OK{=eIQv*vkow#+Q;f-x_l-N4*#V9ZN24h?g=L5_I|?FPoYgmwdSyMbjt zVTSx|o~djf)<;?H17O)Fng49}@9v*6F17_9u-3p>0P|P?W37R)0Oqj(###eo0nB3o zjI{>F0$9e#IYi3Q-&iggI-F;~oM(t_o*}k*2F!T|%y|aPc?QgR2F!Veq#)LC&9d) zB=*k0HJI0vU|vsxc|8f{^(2_rlO(t6NieS`!B`t(Jq(tyu>XjQ{RgxEVD=x({)5?n zV(UMc{RgxEVD=x({)5?nl1H;1X8)nX%yD7O&&+FnxfhUo5N7EA)B6$jlkLI>-Uoqs z9|Y!o5SaHtVBQCTc^?GkeGpjg`ZTn`A$^2)#fA@Y<#>KYa z1Mh9Yytf7O-WJSzTQKi!!MwKx^WGLLV+8X!V!7>;B$te`e1-t#GXyZ7A%OV|0nBFz zU_L_t^BDq|&k(?Th5+U>1Tdc=fcXpo%x4H-K0^TW83Nek2b@Rqn0gZz$ATC+7BI&G z=2*ZS3z%a8b1Yzv19FrRaR%{qi{11lQP%8p|FQQJ?2ohy=Jz9Dem?@{_ak6_KLY0WBVc|%0_OK4V3Q;9&XnS1hWu^b z-N^P~eU#;QJz)9niTTfV|L*rtGA_0SANZXYnBRGU`JES--+6)gofnwjd4c(z7g)x~ z?+v9KeT?Ojp<~~}Qvc+4i;(lXMKHfx1oOK^Fuz*_^SebbzgqxvMKWSEYk#~Grx?xpkr+BG2g~==%qVN$o6~#Pzx$mv`y=gw*)Evh zm4o?RIhfy-gZW)KnBSFy`CU0!ejC6H`P;n5m+iy)qU;v1jm0P0+4pC=fA=>DGA_0S zA8dP)Km7dzskUa;+BR6ol_pQJXCI{cjp%JO$6VE)d8 z>a^dPfcZNUFn?zP=I>0v{GADyzcT^zcP3!|&IHWgnSl8_6EJ^g0_N{bz&2MnV2%Yb zax7qu1i{19kD&rBerLK#P$r3 z*q#j%+cQIAdzMIS&lrjA*(0$%lO(ohmBjW8lh~eZ65BIRVte*WEaT!>5F^I|=2*ZS z3z%a8b1Yzv1V20ehAHh2jlG}GBtn=o#9^6(^-*RD;1)I2N?QY{DhMa9dZr>SE{q~&^v3+Mm zY~L9X+jmC9_MH*2eP={$-x(3JE!bsSV73KjTVS>YW?Nvk1!h}dwgu*RnXz_f<~{}; z$hl2ehkt(reg6Fsn16pna{K!uF#rAt%)dVZ^Y4$q{QDzf`}-p>|NaQfzdr)=?~lOz z`y(*_{s?UHgNyY#SjNKsBQEwI%>I-7Kj8OM>_7ZrMl2?`({IFNjL=~@7-xZ4b4!N4 zeUDFa`yQXzzQ-rF@9~N4dwgR19-r90$0xS$@rk7m%+fBH?Sk1ZnC*huE|~3t*)Evv zf^pW1^*Z8ZhTNc3`<= z=F#G>T{%`)BEc*|Cm=TNVr}SH3Fw3FC za2S{wc10=TJ0TN3en5A7X+Xb^- zFxv&QT`=1Pvt2OT1)E%mZ*Iv4X2{K%!~gNO+p>LFA7$;goz#EK*$ci?rTUrwY}bA( zOFH(ORbuN^HMbCAQzJ65DT9iDg`D3qG(dFxvvNEil^xvn?>&0<$f! zjM2=oxC`R{(GDy}e`7{j{I1{3)1=S$2|&*G34n3ugPHG1hwl@BobM9=Lyr3dSl_HC zi1|JNlH2w~2a%+fBH?Sk1ZnC*huE|~3t*)Evvf^Cd`_`nRg z*&qBL@92>2!}_9ZVX%#b>SzA5UE8*#V`C(?F%sJtiEWI;Hb!C_Be9K&0<$eJ+XAyKFxvvl7;PW(OF7z^<&vRe#~|tRy)ls6F-vkgmWeS2vB!Xp9s4er z?~MW5TtRZ1Lx^o|d83a#2G@f<2G!%;c|vT*KC#Vd#8G1TzvSK<_8;xfjCgHsj}jwv zSPpL1a#7)|RhH}bPN!3svtIGd*}9DQ(6dTTWb>uOBc4ul=9OPe++p=}r*K3tarI{N zoW27*j-PCa^HXwBOIXm0Z>7J&m|uwUnyK zrm4gsjXzgiZciajGbE47QDg#frn9A0wJRfuTa~Vt$IO0ximHpsAVs}D4HGlO0 z;$yiQntNmW6SvFKQFU+gBXOfa{nYenjfvBR4pnWoRwe%Q#xRv4#@ECH?+sT!s*1$5 zAB|AMe=JArG#{^$7tQbKOntcYg&*}KDZ5huH(ih!9yzlY?)%EON;&&P> zP_x?|Chj(9j*9#KbKiR^5-HRpqpybtPOF}Wk0Fd zm)jA4`$tn%FQN}|uhP|3p0FXr1*Q~Jm)4Iaj_(#xPnV4$esI>O>dqQV9QRQ{6@Sz? z;&}@+bm7cC9p8v;f=VF7U#8r#tP_>@SB+fsgp~{+c6!FkP zL)4sh?TBC1nyMDvC_>ycL$Hc``3`Zx0;`nUc&3Z`f2god&1pE^4=z?}t?JSxiv!M| zZG|e@>;UolZ1dE@w4W=;F9(fRKPIY1JYi!`bu4y2;@Y27R!eJ5Bt9@Nxw_JOK5?-n z+nmg?Ruan?=j7e%Uy^Jc$$#Cp%+1{3XX51LyR`l~?quRM6@JpGk`E-V z^2JzPbyH2^o}K6DoDb3y|Bzw1zP;-V`TTjv8og&_3E~AUO2Aw>#1%>p)$!hMLp*sz~oy*MBJbw+$F-7ydX68H1^PQOoHP3@)e$+fant4<6 zylLiB&GV_5XEo2WX8zSY|C)JO^So^4Yt8euna4HH<7R%>JinWHU-P_g)&rW?17@9| zd7WU^51Q8xW?i9qU18Q6n%5g<9pdsj#H>$TUZ0qCi_7a4vz~EzJ!956F0XUU`p4z< zk69PFye=~9B|op1%sOfducO+Hxv+V9_2n9KpW#Bxyw<|sZsD~SnAcjtGk!_SYb`L> z2_3G}{4IDe)rr4p!oJyh$TwR*`3B|~!5ky%;TXZ(R?y+Lf)CtQU~Y5hbDJBU&utEW z_}QTzes<93X9qd=0WkLgl;u7E=Dq~G+?SxweF@Bc5<1)`QI`88nEN*Lxo?BHZ-aS^ zfO(9dERPW|k2Tohu?Bq}YmoDpg`CGM%JP^+JMh?t4v&2>k9}%en?q11=Mcy_hoDZ* zMUZnYLOq;|P?mEVO9?M5Kr3QTz@}!II;O(ZT^2^^WU}6BR1urjIbx<_?uFGt50m}(U9BviLG5?>kqN@li2!CY~y0N13yqF{DM6&{DnO* z;($GCSHT__al;-M?E!mWv=i)sZTl@0a!2SB+jfPw4aB6U=*0Fz;c(yoW_SyoWXQ%;&u@ba*ce=Djd{;5{|u zyr)Jzyr%~9-W>Y8H-|p&&B46K2lF1E>alx##KmU?(BZQJFrO8G&Adiu4q!fWKs|is z0Oqp`=gTf^$oY&2b@CYzboh)2_3&8}^!cm_%x6ttKBs~{pHqSHf5?4(&lW+>pj-sz zTmwz-1JaxQ|La}k(x5g54$_JrIK`ox@zAm>~J=3E5kTmws9#d zr@6!G)7$|@?u0$Csh{Q!Fmf&Ifz5x{um`qt0r`oX4SSHI{Y)FD2V1!-^oeaf8gg4d zv9(KV{UJs!hdt;UJMf>F@4A7U@4)ex?z$m=jGXSe5pwdumLRbJKkHaqqyt`D?X*8{*~L`<%-d)EYd=^*+^5Jz|M}e>5BTG{zi#uTW&0<$eJ+XAyKFxvvlInl@+ z_y9kRz7M{k-Ap|`_zbzJ--lQrH+Fp-qw&Xw*r8+m^r1~8OIy|lvIS;aV73KjTVS>Y zW?SIQTTl9~Il*L$nabWj;@gvbAwA!(p8Vn~o_{{^$|M_nRT_BbfsHoI^}VxsHp%>oc;iGNVmc2h3$nJEY}0A!l2V zvkzeQ4a`16e}Ihza@ps9x_GnT3)8nDH@pc9{pk8Umqq(Dyr% z_3dT-w>Sq=PbD5#YOSM_P9e_x(=sP>E$>|Ya+&!~#GN3LPrEzK@t^hB2_ElcO5y1+ z!#CE!v*xmpbDfa0Ey&piF#84__8H8vK&N-6@lJs+CR3kr>yLHjD~}fijdnJDKbiX2 zR|iKrKXvlt%xDuX3+A$5E(?xWTfymZav{~j4EcC}c_-a=ug?!?U(s2+VlL_Q+*8Fl zzGOCW5v%?J%M8X{W%sdDISjI-hWo_n$}dB(IJ+ z17mvfrtyzDw;FkEE^RTxXSM}qTVS>YW?Nvk1!h}dwgr~4{}HE>lXaPw8`JHo;5_c& z&HI03DCg)b-rU!`N+~D90dL+<+_9(=x3V`^e*9};=fDzg4wZXMW@!t|w!mzQMXOl?pnvE&hn;{$Zpnmo;j&&P9U9y*Izh;8;>LT z4}ZLNc8>F&QR%6%)Ngl2kY zW?Nvk1!h}dwgqNeU>W=97=JjuE6gN6Yo`3e$(Phy9~SBN(kXwz;&I4gp@^~{i} z&zxrk=TIy;u03&H`sYwtdA7zZZGqVqm~DaC7MN{;*%p{>fukD>vX6aVJiaN_$J+IK2~^CrUaqJg=Y3UfrN^v;dRPa{I$+s8d=82F z`5Y1~=S|i}e`9^*2i6C(KJsUSFI%Z=1KQGaVMd*&pEXyhPqdYX(|5KkM> zK&{Q>eJhfneI2DrG$*-J>U%XRp2yQZtFFH6;&Jz6Rg@az={G80Q4K5GlJsjGDXTV3 zZXJawUaJG3duHz z#>L(fN)1mlfaI~4D7EXoe#E^p7ExpF^(4Mm=_}Rgc30wqiHoT@89Ni#Z(l;)U*CZ^ zb=A`9lU1J2%+fBH?Sk1ZnC*huE|~3t*)Evvf;mRCEi>d9+Lcf*fA!`{X6S5P)>_?u z;eAIW`y0!l!*Z}Z8*kX5v&wy?J;j?Q?vHB6WH0uOJvyrKk3CL$t-U(=%;TLk+o|ss zc>L>)HmdUzudKAi44>H+m~DaC7MN|3zO@BrTVS>Yma%uqUQ(Uv?akM(r<7D9i+l53 zoh2nzzW2R(aC5zqYW!~_sc)QjOQ=z!M^U_we=V+buF=HuodUD81!h}dwgqNeV73Kj zTVS>Y=Khao!3??VW8XI{t#-|AOJmvJp|qMi!DH4zS=Irw4w&n-ObHOMKKUoK{b6GIg31(Z+XCEME-ymn7A?H{i zUpuXvDpj{2_0QMl`@kfh79!r-zpLtTvJkby?MGeIPvZ+mVYCUC1#?+2mj!Ry(nC#r zT8GLqLq6a_S5@~;O_Dz!^pm>N{afOZJAYK~uK5N&%s()ZCpxTAqA6 zQL~fUQl~U=mwZ2}kIED$o%ZWHt49rskUaEo7xlp&&u3<77tD6SY!}RS!E6`IcEM~H z%yz*XBifl6^6$&_QVko_qvy*^F%}r3Cg;vWa@pSwSUH{%%TcF%CwMJrg8C&vZi@Hi zv++uOl!w|OUTO0^;hsDs&(?38%8)rP$s2AMs~Y9R`|j9j!|#ky`_6m%(iSs(W?Nvk z1!h}dwgqNeV73KjTVNUcs~Wx4H)HFQZ;{FRsF@EN5PvhMkNG=Ljo|0}MN|5ywjVVi zj;zv0t)AVKboQ_At&S&dPAuQ0GD}-vwgqNeV73KjTcl%cf!P)~y0IYp*!SnVsQT** z(=&Z1qKi5;-(%Lnb7UPb>wq~A;2AN)t{iKNg1f2P6}((=Xk9n8wXnymgR-mxW*x9> zAAavlaYgfOFzX|KvOfHj@2Pp7h0cd}W~rK$PtkiOX4GHc`V2Lr;R*WYx$d!PYR;bD zi1P)es9FO(d529w>dyF6ByV_VqWbOXS>ibfCa4U}Ly5Qc9;bZ2hY>%|K2|mDa+COR z`Z4OthWk+%ezFdj%YwO1FxvvN52mf=vu}{I&tQ%Py!MkZs>PSyd$s;IMyqlc9#ZUo z_(!XmBOeoI9yMAu_C1Zl^h|A8FqZ{$S@4sZ6IG{zsi>bbLq2EvcvU*`Q<6V2`^bBr zeu6QQHrbvr|BJo%fcB!g{=Q9&v4P##8`uzg0r}0=YbUXwVl0S?U`w%KiyEUS0{+1U zNEJb@NU?#6f_F~T7>!1ay~IRgFEK_;qOt38~&SN1)cDTx(+3(TV-}^>2+vH~-_qdmZn;(CFs;%%MuJ{j~F%aqcb~IL7+#yH?DBryn0<+s|D)+TUMttS!~(6ukOMV{PS!I|twT?ihRi zu=RrT7!q;r3zjcfzF_%+vNd zu-1W`@vG|;UTF1;ZT9#68U6o!?Tc-b=c;u>Hf$>!P&ROWd=zg(pNhAE^ZTak`E4nC z`jI_zSoW-+#iG+~i$gzdU?Zl_&)&JphIu=D<%?6T>%j}f_-}e`iZ!Mz65P~rvNiSX z7<_X7Nw!Ddm4f$qd!h|Jv~zI(Ur(^-mfIru?5DCE-U+i!mJZF&*`-$>7wzl4@89k| zIV9S}xnEd*VflsS7nWaGeqs5AmYZRNZ}}wVRX*R; z&N)&$oX3EDKK~kfYxO4^oV(YKxyFtyUx<0T=Ym;w!&`3#_u7A!-MI0;!e;K&nKosa z52JnTb2DtSJwJ)|+?SYrkuO-jVEKaO3zjcfzF_%+^L@Xf(^ab^rZUcK_zr zalV@G+;^JYe!&gVzRxYw?6N&>41V_QX*Od2xxv5sc$)2Y&b;6}c21o8g5?XAFIc`{ z`GVyOmM^%iYayRwcYZL=j-P%=oa?hb8fPExQ?YC~U$TK^1LxPi7{B?o_VZ%AJ^oO& zRt(&3yxn(3#j>Fv*}$@a^W&p9L;6>oA)MbgWzX6ud*-3+z0YRZW7A=it8KCGZClbV zrq6EcU1he>)+PMg?o(~gyEh3wV&D|(`^mb&_da)pH9D*sy!Wt4wxH-3{NQPq+f8?T z+QPO?H&3(<*Z(DW&W;mpSclt#JFGX+KA1b{3(PoW18ZAYeKJn@qFrNvH8xmd#$NkE z``PPHv{i1H*aBa-$wZra@aW({TTisdzkgxyM~#U#_onl|!0d~*g|#iLZQ(mwrrS|( zz1f5Q#k8+AbDCZM(?3VMO>ef_ubsN0mu9w>%4*gz?ZO*ufw&(>r2lv`;qRqJOyf1L>7nWaGeqs5AdykkW`FvA5HfrbG<*~0lx0q#z{AfSs zYNzcw&a%-R_A0R-^lM)yx9u6c%5F35gOzuR`Mmt~Gwh=U+eLfVkEYwue>I{#_a$bW z@&(HmEMKsE!SV&m7c5_}jsxSIamh?yTi=ayJ#f!i*6ZelV?BTQU$gAv?=08A=KNn> zWB)aE-QYuCy2kFkvJrg18rRy>FZB-2V}`}KFIc`{`GVyOmM>VoVEKaEx)wCwusPZ$ z+Gc$Q$F+QAG0|RF^27smM& zW3$qclWgfT{uS-{d{a9%YKQZf{|kmswq7TEC((Ykf201@+|Og*|9aA7TV~8B!Nb>` zZ1>FkF!;b5uCUWrd_Q=PA6#LBKY2Ge_a$b`@&(HmEMKsE!SV&m7c5_JzVH2B^WT;e zE{yZL@$9Ru%LdhXA9U<=TjzTtqW#_#X4p1O{}tmrd&&&!wP0wpU%ALkJ8aAIqdm`+ z5a+&N`GVyOmM>VoVEKaO3vTOL$miIJn_Xs88kJVV78_q?Zyr&xY`9Kk1Iq^1I>0#< z<2S$7{&DAMd*PFtW6pg1>(O@J`qjE28@81VEE_mKKFTYh|F*OvWY5|td-{<*W7d6^ zXZ#UA{4d+P-*z!4#q{56_AonrP9woZZ`TtT);)NS#t<9%;a0&nAAi2hTVwO!Iqwd( zGdgY@e8j_pZNkeN1mFGnU^}<$96b8`^KImuwStd6c!(YS+-hIo7-ww*Yg<@-`uLmW zi*}6x*4SW;8P>kQO+OoAzn->Q?C-8u53$+LtQ!2u^FyrXQWYPw>QEcH(<;#}<~V3u zSlhzd7CwI3So`J5OUJfi+K;~BGF#!=j?q4O>L`2pr4GSkM_g(h@2Pl+GcUG-dRI2% z&%Dsq8Mai|{AA*A`$gYn68rwds~6Z_zg;fcSNh2?d+3H0gBR{P)NWs*8nZa}3(GGo zzp(tm@(ar^EWfb)!rDiUt(f*p$B(nm-(Nb;uNa%7IuEyF#%>?&`FvA5^Hc5E=ebV5 zIdFt6Shgp}q0`zUN7yqL?ixJuiV^nS`#T4peAWoN^O&82PugsRo&L@a!Kbziw^gog zier`g5;JD`g5?XAFIc`{`GVyOmM=Kp_g=2WvBzo4#29w(Ji)fVyy89HnqVIsS)JeY zu9;|!r>gnWwBO}s|6YpmH!t!0<<|R=YHpme+kbMz#JMk6zF_%+A;IdM-H(;^QyICRKFp1 z#QhcPdSqMKz_Ni)sgD)?D4z~iJ{_FjH)YTIDSP^nJuG`{4mi7?^&b0+IHzLz+;^cv zZTsy`iDNQk`M$Qrf1Mb7#oc}EqEW{NZ@YRQJMQG41kYNtkNtDEBZFUhppQ-1@bKW{ z*6M5LZgoiTCCeOY^Ugge`0P>r?9#6Le}NgBY+!8*t52>S`J!E8fHgL3G-lehFYqz9 z_p{qS{&DQ@N{1hA1NN02{Vv z#dn`Kz#d!SoM@jkd4R1w=vTqL`VFvw3w{~g@xK1HE0!SV&m7c5_}e8KVsYyNXhiD}R0*o$}cxA*^Co$E*E^tW^W zRW{lGPB&uuOY zo-=(7k6j!deCCuj?cb=1 z#O$wZU~LPlPguTSjRDr!V2v5pzQ8{lzoCC4IXCuqu|vDqiCrt+Wu1-ejW-7|KbzNh zbt8`jtgcNl$3)x0+7{Nf@OIzZ%dQ_WIQkdU{=xdY+sccc7wxY;wVSPdSJnR$U3RwZ zhgaAB2i==&vrWzpn>|-6tmA3bI`GQd-RzQ|R@~#EEp3s-Dw|(Ev8f%pSGDa^t97+2 z##eocbHA|s!txt7wO?3%VflsS7nWaG`^d2s)4t=6d)exTR_9%e&GiSbV?W(sbj*Q# zzNsA>wZnOCd$*g{vK7u67w4$oeQVoCuaAvm)%&t_Z2Gnp-`=51{y{222Y5AI`IA2=j< z`8|8vMiVMN_4)m5{0$X%KWTsetzPj53l6YH_pLbB1Q6%GVEKaO3zjcfzF_%+F_P*k@gGNRB3)?+XJomGaUtq>28`d#x3#(6TRw&fSA6hYJMoE8;rHEFJ}bK3T8-z4ZQn2Eyj+c; z-&zZbpAEP)Z2tC#*NSVmsoL$Ae<>y&R<*Bl*i*$u&sOc?+%GJ@u>8XE3(GGozp(tm z@(XJpIsRhW$Ie^Qemu6C8)DAaLZ0XQ@B635dC%vY+UZB_aIWdGMaOH4Hy^p0 z16j zU;WnFwu8?@pSQUU+sX!(4Xkw_XSU6+wJR@vq*&&NYOUDt=tqjzU4JmQVO!b2vVrsC zBi$Ibm2M22-#2B?yG_|M-(*jpvS~dbQ)+JZP@f6cOVo;C$aV*x>wPp#!Ql|Gc(KsgRi86^EnXaRPQ|ieTiL*}f%D@d?JWA2b{3r9 zH)YTIDSOrs*~7AD{q#9sa=p_orcb}#ORjg=ue*}#9ro+4;d(MnOHtf5$rCoi}E?=<5fQ`lmYs|3r1$&qf~MMZ2#jC2JR)`w}x|`GVyOmM>VoVEKaO3zjc9-*;bE zTUf&xo3FPmTHAdcZeh)5Y`#9Xa4*2d*XcSNe5BPJ`}h_5&$P>)`6heLORnwgHc^`c8-M0XJa4*9vzUJTc{B063Hx(j;&~JH z=f1@AChX6BCC{6%Klhb9Z^HiESMt0G`*UB(^Cs-ieI?JEu>bxqdEU&K{gn-@ZDI8Z z%NMLMFn*1Vc8wX&#Vuu1q|`(vLrHCOzBwb7y|H1RBqjX$?0o{?$y=h>uZ z=iHZ=eUUF%zF_%+VoV9kI0ifPw;gZ+8A)HAg| zN0)lmmJQp=29^!1bs%T@%&#?n-Y@k|z~2LudRHJDwv`Pm8#q5c(x|6@Y1G5{eN*-v zTiJ8`We>|98-M4YvhN+i^y%L_65l&u|L&0Z-U0h}hs5`eu<72E_}&5gcZbCH4%ojt zB))gRJs#RJ@x24~?+%IY9k9P!PJHjknf;XwtZiZS3CkDk-&|r0u*L>!%&_(a_IKb( z--i6VPvV;q?fyL|>06S&mrnY|Bxao27S^_~wuSxMN6Nm(1=H@|uoBmsJCeSw_;-+`Z!Z3QBe>X|`M&sX8lD^&KzQl|{zF_%+n0C!K*uU2#ebe#pI7#1nWW%PK8wz7d`1M67Pr)qOV|83Mmkv+#&_8fnI7aH|b=u`Ju=A_4*B;swb z7t_DT+a%&`V2^uA#M{6g_mYUWfj#ae5pM%~+)E$ z$2KJ5ZE|L8vVpZNV^g2B%NOk$1MM0c?HV)f+85YkFcPszu*V%G#VmO|QX-a#ZI8LV zUn0gSXU3^*VQmX*Ti9c7QWg&uOuNTWCE~&G>#X{KE1J%P%ayu>8XE3%9ku9v74p zrzB>~9?z2$*ObpUwPT}p_Qm5#qV^E)qdcxA5yOLx$J-=gd$931oJ7nI?H-?#hy|kE z<93o_ggl-n5j#YC?n}(R$QLYMuzbPt1At!!Y~MEn24x>P!z9NV^P z80kKXjmJEvEZ#eqF?+msBHkPJxa&l`H|%lOiFj|=Rqwy^r-n8+8bF~AxdtTDsd7uaKf6S491>2dE# zG4mb|pA<{)ak)t`_F~4VZDDN-Yg^c3zZ3Zg-am2R!L)k}e^%-Sk&i&TIQI+7FD$>X{KE1J z%P%ayu>8W>N5(Iv-Q&{z_u=+&e#MN<NWSUS35Rphfk?%z%f@nt~)7)+~d6y zvE|r!9C%X9xyOemV$o^$xbdVIb&n@c#IAF!a$jP`AYZV2!SV&m7c5_}e8KVs=lkw) z^@$jMj+MvTCt~{29^!1b%66CrvLm}^LYEDn0$}J zPm0x-4cp2FmJOUAAJt-`f7N1x^ZTakIkvKAoU(^ykIjM=u1ZJ3zjcfzF_%+rBca^?c8y+)~d2P2`+1PR|cb%0>0O z(WD$z&nHdFUG@Bzs6EO(MV$MBrN!}E@0Q4Na$U_t~-&?yMPznaZ*C> z0(RYrgx&@0x)TY#3)r;<5_%UoGd9`4+Scb)v-+f6zF>_3*4SXz%7`(;+85aM5R$Y( zT=yeMGsN{klC(rzmmo=FM9es~Ev#)}Z40~hMM94SUt-!_!z7`{Lc435B=lHd*E~t+ zv9OP>g_6)?fn6gdp~nKdc1l8z1$)<2N$9b_uCPbaMv@kX>t-Z0I_SssG?KJCa$jP`AYZV2!SV&m7c5_}e8KVs=lkxu zA_)x>#^ZV;32hUOiR+LgG*4)EeUcrjwDSF*YQZw`j8FV$_ADVtaTt~`pmC2*BeRFByk;* zB&`zJu&r!h*}(bnQSII6zm0m?vgg>!o__LLy}HkGPj~&Xgx(r9V)}QzwS?Xp?7C+O zy*1c%&k}lTuB^wwb4Jxl1V!LECj&|8CD_bj2e2D|QALT?RrZL5UdTF#6?Hn6sZ z)hE}Be9^8k(5|u3t}(;f7v`bsaV50rXm{PYgk~M=dUOdbJJ@xx5*l|oGfr&_Yg<^` z!mhoRGCjax+Fe60p$Et~U0W}q2T1=ny*4GG2S~eX@g?*CX?KmjgdQO5+I8XE3(GGozp(tm@(ar^+}8fOE?kmMotUw?o?DWx zT|VE`j*Z%3*At7{^z5VSswFhsoSR*5EurlOyAE5D=9}xYC27IAZd*blj(%LvElE2r z_a$au+UA>eqq<$P3Zl?uDhGi`-NS1 zH=*|nyY6m6?-zD$)r8(}&Wuequ(pNOCoEsE#sF(k zLr&6Cc3svajb$<8)V8p;g|#j0+P?`sYOZTB?XKaR(4%HNuI-%AqsGQHpA&l2w7V8` zLXR4Djp&3PH9Td>Q3*Y2*fpgSdepFMO(*oIVb`He=uzjK`-SBfmS0$YVflsS7nWaG zeqrt7m-p9oiIa4a#f;7Mgp+iYHTUR8?bxUtc0JqF<;nGpx$3&U2@PS+qwD=9w1r{U z0ZwQR!>$jU&?1IiH#nhDOh2wCoTOcx`w}w-`GVyOmM>VoVEKaO3zjc9-*?wlPG~qY z9@kq=(sp(o<|NH$*Jn=Bf_B~Jghn*>uIHSj9qsy)Y4Y(8`TQA7t?l647c5_}e8KVs z%NHzPuzbOq|BOLQyXG70dc{ea#;#+Wq;)JCwv`Pm8&K;&&h(jIYp%DPq{-|$%t>0! zvSC}~$X!^(J7i`;e$N0ejttM7;^v>pmpvO~79FAyIDvc5VOE z(d$j*%y?wOIJGV9>XUZ)f;9%WY1Y_i*O+P7zR>RV2okk9=+oKLc7;4Nz_Auy{1W`9tt*I>m*SRg?6ufkf?`}bM60$42e2*HcLE_C3b;*K4@X`BhR43$JaFsBPhX zsdVoVEKaOD{N|CuzbP!zI$Dd zL=6#+mDl@7)D~f!UI!#mbA)!U50a=wLc7-uNz^Ez-Rp@YYM0RN`sZom-*0C8MiS?~ zVEKaO3zjcfzF_%+TF`vM#_MGy)zt7h8cDS_WW$(c1Iq^1I>0`P=`+99yxvDr zO%SgGl2j{1Hf$>!ST=Bed|X35O@4IaSaV!kK8<~{OK^VQls(5*_KZ{Zury4vm=iNjZ3}B#Slhy0`z&Sk_=0Ko8g_|#eE9O(c8Pj?u-Cjx)Z>G_7G9zrAM7>q z67~3Cubr2u#|L{&y+l1e*z55n>hZx|hbvK!FX!AZEWfb)!tx8tZ`jm+VflsS7jA2R zy)Ii)oj5UL^LlDYb>%eo=tu3?s2%otUg?Fo7sXoPbVoVEKaO3zjcf zzF^INj+>Zv%{SQVwI$Vb^Ez%xwccdIwz7d`18W_~nLhJt&Fjr2)ui(}bm_NstvcDT zt!!Y~!1?j<8b;~ZqmGR=$7>sd)7~{Ia^Y17ke?|_j$&eds|X(7xuchCG~b;uX|fkZx^2S+Q%jJc44o3TT*Wq_PV!;db_aKy-n2Hg}t_E zqTX)Kj7>I-N88e_K53UP+BF7PV}mtjSo;EdJ=Ub!#9ntesb;a)BTm#Z#>VTSCe=6= zGfr&_Yg<^`!d`nfQ4gANifQ*6%87c=w0mvkL_KKOYc411LF3nJF(>Ll!(O8~Q4bm$ zuic!e2Ti-zbWYTRhP~Evq8>EtwO`Y9UJp9w+%GJ@u>8XE3(GGozp(tm@(XJpzr4R* z7dWX-v6!)WJ>ODwjq~}YcKT5}?Db^J6;`Hh``}JqSGS~wFYR7$x1_c&eR>_4=%MlB*5S8L8eBfQ>9}a$r`L$GU%e)anM<-^oZ1#vpV-J3tTAAtvB4TM ztbM_L`v*sqr=B!6_V?;B7nSo492@hqJnWLP*((0k1|!REuJew)m}8=CVQmX*TX>lR z|4^=ZU3D#sX}@f-`^(XOtmw1XhcS z{E^H#oe0AH{Ko-HWL<1C|jPXxR^e&++fwpMx6VF}_sdtfHVs`=CPepse1GsC9yZ+9=>J8?$vr{CMN z+~}I=VUzn3GiLdM`DHOBV4 zQ=TYSK6h%gkJ{_$vfH1k_K8RQsqDL0bF{y9@pI+oi#Lb8*B>vhdv2bsv^)?wwB_lS2VeI4qtk&y zs9`<0#s8c9?_mG;2iN_itpDKJZ*V=H;Ch_F z_4tG9{Zf0uIOvmc;SXlK_=DLG_NVr1_=DMR{J|U#{J|V2{K56{o0hc~nSF5GkI~NY z({Zc)MteP;;Ch_F96z0xdcUGwJZt$!TF)I^9}|P?V-?Ik;hT1yJGegP(XMkxyUtzJ zPj&9H_7c{)gX?}0T=ySb`wgzg6I_ooSm%yyb?)GL-(?@?j`sRkMSFb=gX?1(taFFG z&K<0CSM?Kfe_GaFWcI;2ceL028?18&>)gRQcd*VKoS(0UFI}QI>EvrTkDYoozE`X> z5MH?X!*xDs4BzpZSSNS?{X317U+3Q8@9;l;t#QcF)&1h^?VfM^`JU<^8s{8dSFV62Vdv?W3+_ie+m?p04g*%Np zyienTwI+q%a}K+pvDfa^Z}|SVT-jK3e)W6c`W0?z?A@U{ea!P2 zGh_2@=d&&Bea@#(*!Qu8eZ=0!(83sCA6pA!!^X$l!kB6IeQ9A|VBg0U_7V1dZ(-lD z_hZt+F`?a$)onUfer#JfwzT^(Z{e83elA*cF8my|aE`p6Wwo za;|CjIZ#$}z;zw{e;fYz+8Dzki}z^hTEMPv@b>(c?cRxP;YP*&+_89%hHP}-$6oh+ z`qOvt@ydp+a)I`?t?_QSrt zf9tmQZ>q;m8dkplPu79Ko&Iv_+_Kvbua0?@-}m)=&Hn27n&YPDYufdE4eR+D8$Dmc zdVa?ye{YaKSALuCl-ha@)%zmGtoKE*o~hxl^SqqDZ)xv$O6~pbV*VjZrW3u-;?CdXLQ<(0goH@3FDbdvZ8`KcBz9{WibdwDrDM z-(?u5zRSRRcMX4?_tN=yjrRU_)85|*&f0aqwB^e~V{YvK>5=KsH_i^u-(%~0F~>*W zi+v9KfBH6^e+SpMQRdaR86(lwcU8qdu)m6bfb;LgU+4R89zW3DF%s?lEq?n~homR( z-9PR%UH@=lI;634%#-|kvEs5gkBZBJ6_*7oE(=y%7ROd`S+L^1;5^tXM4g>%>{*aeD0?i`d>VZ_g~4m|ogxxtJTLpFbrn(%~b2Mvhv~?HX&H z$93m%zu#uee_L_FisxrOD4rkA z?XyF{d#ybFS$RerE9Dt6my~BjyYh@+X%?gVMwa17dC*-(_GrD%z#xy5$eal?`@Y~cr zZA&jvx~9w%>6*gQeuTe{u4AqX+TPly?X9u7!85z2-Y<>tx#4w_hi;iR-ELIOlUxT< zddt{IZyA=}GRIAN%d|^xnRe+d(=I({+H)Q0Txa;()EI9|mstAYj8ppIKK?IgkAEHg zUY>WyZ<6l}eWHB+#pd8#Z&`H>IM=Fcz%f)^1KL&BfOge2 zpj~whVAV~)Ca>3!>-m41wLIF=|5u$3#;iIWuxc4F{;yM~K(#HfZ|_OTIm6oG8t=uaD^HI(qdI-`qdI-`qdI-Gt4<&7s?!InP9N-RW7H)CeNAqy ziRo*2)TyNX+pJC5Ry{k_on${|M*H7osI*;)&-t-5=DZ*8qp+1|A&{hl7R zAQ`9X5^`Qtmk?H6LiS5_329edLRfVPvGLy?*0*V*?llGXns_e$?DK+q5S-WPQ$1Yo z2VL=Rr1oxJ=huG|Mm=c8_HEXHZmVvr>N_(Y|4sXqwV}UGeOv#n-dYd3y=y?b7JbxQ zX3VPp3#i@#3{|l@BFYM1U*6Wq?V?OwASF3)z`g--uu2%h~4Gm^S)w(7I{v#_CCj*UMfoAk_8Yo7l7S>DiE zhuf+n@6Y~*4m|z1Ub>b=nQ>ci8pY z4efW>-ys;<@AT=K+lB@>?fx#p(B+2x9fe7++uvOnI^MMVI}JnMn{EAFhoSpTyT1c5 z^uTHNcO!P}?ey=O%v}bWo`wAx*?30gzT?`Y_FpIeFl=0-)zE`wTi0$ibYfxGbT#y2 zVb^*!bY)@JfHm}HVb_K=bZ8lazYFpj+1p3Ezk@Qgi)r_FRwg}R*ZVbehG};lV3Yo^ z>jN9Q#NH=*#U{OC*Aq5$jIno}VME^-cKu;P_ZaqfT!tPp?7Ffhy=B*iHS}X?cgZFUVZ4oO2e)JYv{zn{_f7ukA?kRqDk-Cb)gN7Yua5e z+R(U$T}Rr`xQ1O{+R(U$U3c2hxQ1Pi+R(UW-(9EL(72}E-$@!8*RX2~8(PP(zuPqQ zhhcx`Y0@S3ccF$}G5z>EQj?CczdJSbjcNCHswUlIf7fb#PwwFD@ovp{x5nJ?cWzd_ zbMt4|-ji+H_r4o8u0?6my>yLAlOCpPSDJJ(UDMLg&tz<_b!pPobPY_C-lo4>HuOlb z@psxLjaGjLZqiM4T~k}G)>C!8Q!6zSS6v^~&}H@g>g2kqCcReIQ#I+hy3VRe z-__rln{;3O-MdLw)-^BA*TQPK5Y4>j~hF&Y}{w>DP zai!hA(HQ!!wEMRkd$#Mj-X8Djjd%61zr#1Z!*{JY+iG&3c!%$rdxpLr{kRsNq5DTa zuF+@G19a^^LnqK}nqAY+&=17Mwf+oULE8OWm7%*xyMH4yv?yu!Z)zreNY`&P=|;M) zqe)NF^&SnKN$gz*($JrzAJ>O8bSYuijWqNsVb_y1bS$y=Z*V4kOaGQ<($93QKSK`? zd)ELobOK@j_Gi-D^lySD9ZuKuGwE~sw@X7KG`6*ghVCEi-xdu$K-j-^n)FLu=hM(E zrQP*E4b4*6bwLfyQrPuE4b4*6bwmx#QrPuH4b4*6bw>@&QrN$l8k(iBe`7VYD`Efk z>KbA12KzTzLub;DLnr@MYtoTN=vA_kOdUuA-9_%`JhW;Mx z`gn#eAKSWao=LCIzv&w~ezbdRfT0tJy=$5ox@WL!of&#)u*VV@x`MFB7#MnkuxpnY zI)t#tLKs?zuxpnY`ev}lDj2$Fu*XgqI*rcFu4iayGcpF(IW)8xVb?!2v>9R7MKrV- z+1B+E4Q)o)brcP4Mr>SP(a>h3-D5BeZARK%6VK4-!nRN49mydp2L(kCbgI)8-9-h+T+eR#b5laAjjDZnjz&*&dgG{43RT zmq{ON%95i@x?!&CWzrLKy)S#)b;ju5b-+yeW3CTo=#tUD#|WA9$~@M{q=)9(O@_V` zHm>Pp=sv+7n`F{Y^Oz-*u9|B!ne^5?w#v|a!`?NT3>_!fW1kFtC)i`LOnP*#+h%Cc z(e8R~h6bIFxs&U>85(r7yZ)P@K?l1ooS{JnyI!23K?l2zoS{JndrX(1K?i#bn4v{R zpB@`#(g*XHF+(?uc8?`9^u)0D7&Aj>4EESFLw^kRm^4F|4E9(xL$8ea;IT5z zlB&vkzBvX&`rYLb&U)?C2U;p z$k17$-F1)*{UzEx=Fre(qTOQ`4c#Z$HEIkU8`!mL41F8eV;v2hDA;2lP5M!;MPukn z(Wl318roK{Yta~bHL%B08ag(x$99@@w_Kmf(AuKib*l`mE!g#}46QBq)$BS~hSnDC zu771{Z7~Md#WJ+EVAsnsw6?JE7*RuOi+0yIGBlUy$F+$}I!LaMWauMd?^;HNZW1=G zab)Nz!5+(M=qzF5F|H>4C69eI=`wk&qY>-Kobeb)t70Jicgr=WTBWlwxRYyQnDjSX zE5p#`pikG(FzI!;wuVW^!!5~?*rXNXG07(V7S~rX>AJY? zilO(yzPJvINe9MtS`2*{+FifJq#NV9E{2{A?XLG?(wXrXW|RJm$3mO*ZCs1P(Cc74 zuF+xWc)%VzZPLT>m})~Ohdy0%!=#_%vEPP<5B9FPVd!$e9-D3Gb-*4gZqgTW9Uend zh<4ZKF*Jp|&rYt}V`vJ|?s`6krV#8pKZd3d?D{{3rV#A9K!&Ce>@nwtrV#8g>V~!q z?6K>H-V6PEOuL~2L%YYi8~QM?$G{u9G1z!)yh%^SW9CgdGagHC=+CfLcJv-=s6(ngE9W0R6jGfJv9YH3SU30@__$z|b*ZJgzxl=o`@PxdVp& z1MQx(U}$2%p5tKBsc;<$lYWKkOPF*mTzA5xcj0;zh7JbXx=w{jAH(%44BZTTxvqtw zr-6;M|7u;*5obUa*hz|bY2-L(h|y#m;CF$~=g`tckMlOBj`3z&35JeS1KD#6~h z1q}TG*mFG$T>{v1PYQHYVAmTd&`zOG*C8p;PNCiPNeZ-6VAm}v&`!a|^-K!1Q)qXc zlLGA&*!52g?G$W0hsDrNq1|&{3N$oe&xI+ZYvDOEh4d~wccwrG0~^n&DbUA&J=dl{ zH-kPs2d6+!gLco&DbU$q4tOqxk&6L)j)o~m!*hEJ@}`+fp5t7QPfb6b`&^J`O+TI! zU66lGyXQ(5eJ!=Bq!NZ-J7z6x{?=*M%Y3-l1M@!YfmO$OL=s0;F}Vb2{a$iId?m#vUq zgzG94XhhJD>n#*$M8K}YP@oY3yFNpKMg;7-4Fwtz^y7LC1sV~s>pT=_M8KXCSD+Dr zz31i^Xa&&jxpf8k`>^NS6|H&w>;14G-{0+yt%;yLX#y<$y^g{r_b5n{CSBBU|7d zcDcz;JFQCrZ`1WUYdY$I;JIC=+O$q<8tpHR@!v(u^$s3&>o4umg$D&6ywYAatIz1* z2d1v<-vXM0cbIucvEg^G4}NR&Ws5&exG8wbR`<5d{K3t^_ut|A68&xn-sZ5S)4;LQ zg8#L}uBq1|V}ozp{nWJj%7cUVUgwgu&%A?ze|gH3wAnw`4gSe`*QUS!_Kz{7a9}W4_Z7@08bfsm{gaZ=YOV^w;Vf<>yX(&NJJ^oZy_o%87>S zT;ph0PBiVxiH4OE4J#)aR!%gmoM@PQc6?{;MP?tYoM_sW6AddT8dgp;tej|AIni*v zk5;#b{y=RX`U9}{6Z!+N_a8azu=`E;gMB;+f3R}cVdb#H96w(>*Uj3?%s#m8Cyr;` ze{k(LxE@cia@gs|_lxmIyJ7&)f|zqmQ_F;NW+wR5q1{{h?=UO)f>SqY+4Aj**ZRxK zEjtdnCfYkpTexMT1r;AZ_vzdA-R9b8KkBDf-?q`-6)T>BJ{8XZk2_$$mLCsq4*NHk zIksh)iB|^ixaF{xhaR3BeBHcBEeCYJBKSK?-rBP9pDzzSd&pxgJKsGq*uUww-235# zV8vI^|IA*Cm&cq_wfndDa-p*;Ry+na{>{C7V!x_g@f)-&ej{v}RxHQ$u53OYvtoJX zz7;F}1RKSr!2T`1-2alPF`jo%JH4E8!<67tpFh4l_`_;n_S^P|^4>EiMSIVO_Ag7T z_G`w6yOl@vtoCc=)w`EJm|FQ#d<*?69tKvt4Xk(@Sn)Qn;%#8X+rWyqffa89D`o>$ z%m%EOBKVuCS+5%I^r`r$;5t4E9zJb$`ABnhtmZvCr|dPVIzCSfxVc<*%=kElJFP#j z+-m;VU|TAcA1*p3c;H9BDFJa^sjpNu{Y*> zcEy9iiU)%gKL)F=J*;>(SaEK!e~V9@pRC3?Wu@<@PTemHUsrta-E`s;)i~dM<+HNu zt<@Nw*!KN$&dZmEO~17kls_9#@!$UNT6yg@6)Rqj{uN&bD}E1F{2r|MJy`L3u;TY% z#qYt2--8tc1}g>(R*WM2P1WXBt!nyIyd|u7OSnC1zAOHd{#Dl-R$Xsc@uINmbi;}- zg%w{4D;^bA{cc$Cv9RK1VgDANR$lbHIPb4MwOd;Iu0g?1blEv=Km45F54ty{%{DnZ zc+b^})bX@m1;6rkw{*!*EAH{omT8g2DjUV$(tmr`g;z`|z7$gmE9M#grfLwYCNF&| zej8T&HryVytrbsB|EgaMt9~)8`17#IY8ESAop!~m!-{W*Ri_wMygjTqd|0*1VbwH; zRqGs94Rlzw(P7n0hgC}*Ry;r4-u15)qaNd_W7J{gP{7|*tyR??rBCI9z{&@K+oOiB z@>A$vby{K7X@&FJud2IByYgRP<-fqnmw{D}6;}QZth^prHJV}7ZiZFU8CI=lST&$w z)rN*uGa6QY5ZvB%ewFirFXg<%7_vH^-&9RW)mWr|<(I+AFN52oR;lvc=wJ0HVb!CA zl^+MIz9g)CI#~I1u=4L<)t!Wu4+twy5LPW(ST$;4{}%s^)YVmfB7G|V5%zEEQ9Bh@ z{v)jXM_Bofu<{>aCL&N%!{)d*9~Ec#UbJFNV7xIJpm zDIcHyRbLENeKA=1`>^VT!OHiCmG2Kr9{^SzF<5#9uyhPy)fR+Ra}ZW7LRd8lVbv~# zRnrhwtwUIP2ylDXr&EqUzLet+OM?RbrfMOnHV}PEPXm^o2HYMswxsVt|Ei+|tBw*Z zJrG!RkznbEz|s$ar8ferUJ@+*6Ii+^uxhBms;vgA<{GS8Y_Mvy!K&Q`tEL+)eHB=G zEU@%mVClWU(tClW_X11r1(x0mEWH<4njx?>Lttszz~5BO7u7(aPwDf((&vHOqn42L zg6LoMVqpIk-&#{f`a-m;{tGNUB3ODvu=I;y)rEnjrvyu930AErST&?z)s}))a|%{1 zDp)nDVAZaIrPl3zZNQ8PvQWAv}O7_jPM zz|t#&Rp$bhz8NfiGgx|PuHovh|A(c22usf&mR=$(y+m00im-J4Vd*`>(t(6k`y*`Hp^l04C+T1Mmaz0K zVd-1K(zk@AZwX7^5|+LtER9518i}wpJmGIjt6bXM^eH`3SbC&zduZTGAC>;4a}G=A z9G0FcEZuTg`m3s!LW3LVd)0L(hY{C8w^V~7?y4@EZtyO8pyCTkYQ;c!_q*8rGX4f z0~wYEGAs>bSQ^N%G?`&(GQ-kjhNa0f;754%w?gdud3#_;o zSaC0~;$C3I;lPT+ffa`XD{co?{12=+A6Ridu;PMX#Rb8NQ-T%01S`G>R@@P+cqCYH zO0eRWV8u1Tig$t)2L&r`3RYYethg*#aapk9vS7t!!HUa*6_*7owg*;h53JZTSg~iY zV$Wd3p23PegB5!QEA|Xl>=~>$I#_XZu;S=o#nHivqk|Pk2P=*aRvaCyI67EyeX!#C zV8!*piUWidPY5e+5LVnEtT;nhafYzs9%02p!iraf6~_oGz7ba3BdmBxSaFiD;wNFn zRlfchY&@(u ze^_z;u;Tn-#reaE^M@7Z4=c_eR-8YqIDc4q2e9%EVC5aa%2R-q?*J>W0ajiEtUL%< zc@VJjGGOIvz{;n9m1hAf{{mKC2CRGySa}?<@;hMVeZa~Sft7~>D-Q)$9tx~H6j*sE zu<}q~<)MU4oy!0#mjPC;4Xj)nSh+T^a&2Jc+Q7=Sft70mE7t~A-Vm(3Ay|1su=0jr zQZLsp%VCA*J%4>s_*9I%E4OVUx ztlTJAxqGm3_h9Aj!OGo(mAeNkcMn$X9<1CwSb2!B@(^L=A;QW-gq4Q~D-RJ?9wMwf zL|A!G<$->H$h5egOh` zyOC!NE6*BMUN)@!ZdiHTu=2QJ<$c4-`-YW=9$e?A!^$6rl~)cc-yBvRI;{M3Sb6KP z^4VeKxx>nfhn05^EAJjw-aV|mdsun*u=4I<<=w;njW}|*VdZYa(iVWFEdWbf0G74@ zENuZ;+5)h&1z>3lz|u*8rIP?lCjs`@jL=DdrIP?lCjpjD0xX>bSUL%?bQ@slHo($t zfTi;QOD_VJE(9!H2v|B2uyiC~=~}?jyMU!f0ZXR>mVN~+T?<%x7qE0NVCiGP(#?RS zvjI!T1D1{lEFBM6Iv%ieJYeZ~z|!%6J?12|AYf@hz|ty#rBwn;s|1!-2`sG=SXw2p zv`XMpcB`~XVCk;F(p`b2y8=sh1(xm#EZr4Yx+}1BS77O`z|w(%r2`Z8wGIp{-56N< zGq7}KVCl@j(xri=O9M+M2bO*gEPWeTx;L=&aA4`=z|zlwrKRP+f~5-tOBV>1E)eW7Y@sa!OIrq(_7N=YBUsu;u(Xe0X&=GTK7yrv1WWq} zmW~rF9Vb{iPOx;GVCgu)(s6>N;{;2`36_o%EL|yBx>B&mxZ1gY>m9Mm(xIaLm|D*Y zmTna+-6~i*SFp$2+R3Z!AN@#oi+1U8!P3iurK1H)UkjG*7A!q3SUO#>^t)i`dchvg zY#($vBgWuy$e}YvyL852>5ReB8G|QH9$;$^s^YYJ^&4OV7yL5%@wjMP@)u_YOREZd zX;s0}QiG+X21`o~mX;bUEj3tLYOu7_U}>qr(uE6~^>?={7TvN~bjxDVEsI6BEEe6e zSai!`(e2Q^syKG()Zxox<88mmRjj+m%-j0YD)tzAfA3JS$KLyI<#XfsNC%H?rGp1c zHxKq0e!JxtmA!QQXqUbp>^TM2ymysP;W-6%$&W6M{<|NzhV8k{g~4;Cui<&z!-LP9 zvZj5!@&&=06l>dOU55s5eL^SO;pp>&r4va1o*!X9-Jr@zk!~UF(k+CgTL|~QY#p1v zZI#<{dxuW;{%KXt$c0@yS<7`*&WPt(*oLoEeM0ZK~ zgHvo&=g3GWlXlPLDU{12T}|4hs|ibo6ZV{-;&s>4houV&OD{C|uGz&xw^ey+o}*M` zIZ8#Aqf}%$N=25VRAf0yMV6yfC`U;;rTCH#Dl8pTSURY%bWmaGpu*BYg{6ZEd(KX1 zX~Le%6Izaz&OaS7fH5N+V^}E1P&&i3OMe*loX5sfqo>7O@|?#;mh;%iavmF5&SN9Xd2D1kkBuznv7wwt z&);lJyk$o8?|GL!ly~X*m_3w_>3NzBUZ>}KHk9w_d7usDfl8Z~ zeUUaV-1FL#$^$lhEOJrBcPurj=y~lwOXcK>tM-$M%s#koZ>yis&LLmb`w9MU`k~Lr z`StMx*W+ocAN=ud6!gQU98JYx2N3KFaTgmER3NzT=wdPyf25CHU!8)2IXI2lu~V zrL^9OcLZ;D+zP4x_a6uzIeFQ%-kpC6-g3*O(^{S14*sywG3~hLcjNePdEb)h;rUAi zul4E@Y3#pO3!XXNd2*N5_A$G4Z?!+<{9S_S=goKasoK5&NnH;K#_uZ69Tm)YKDzC= z;Em>Nokp)QDfq^7dZeQ+NWshWY@{b|njgH=ZH@H9nR9~|d%TfW7&<3-*62oR{Or2m zcRuNnE;(staOdTFr02_N!LK~qJ+0k;YVcp8>A2a^;YnT3)V|_ zy!rRwp?~R|I&blI@Wl_Wlh(VZYG32gwbE0wD*M_0SR-xs`kP@hjdVy;d+C)p19s% zt~0K;V88y<&UGn!u2=QLb*%omzU7zeUgKdsU|pb3)``b`y?|LiSVzP^IdA9S?>x9g z%hmVp9enJ#-YtJSyW$HsJgH^l=X*u_YJV8k^3S*S3O-=TF)gdk-ZS`#}dc7e#hm6xnrAWY%!N8LhFEEkA<#BzfKEXr@lTE+4@jq>qC*P4@I^<6xsSvWa~qbtq+CP2Va*8txLXM z6K&^^NU$#n1VV{E#Y`LVR@o@LoR%d&fxW%n%0?pc=Ivn;!3neJIW zcTD$aKZmA!rJq~VJ=EuvW%q8&?%kH%yDhtSTXyfZ?A~qJz1wu}_PK2O&ERv~^jpH` zzWFr}$I7n>^J^p6uNCuaCfKhb^J^*CuPxUkEQ0--Gr#tN{aQ4?CWHMNHNRGa{n|CZ zhJ*c@Hovyxx07G%=GT0%uL0(3L9nk4=4(W-uNmfRN3gFY=4(o2zvG&w-*3M5w6d>- z#`?>3=WCv^{=&ZI8S5|XYo4+G!oKDi>o4qUp0WPIzUCS0FYIfcvHrro<{9fRT>EOk zzSbJ+Z^pO5^%%mY9z$?FhTwV(!Sxt|>oEk^V+gLt5M1wju&=uuhv52H1=q(gxIVU( zeRa%(>vIuYpQGUV+!gFgeNKbxa~)jIf#7;>1lMyWxSmVF^&AVX=U#9w83SeeVda z?mEig}OmO|%Cb<616I}lm3a)=61=qiwg6rQ@!S!#g;QBXMaQ)jXxcq8} zu7BgTGHVd~SpOCcu77g|`?||-&R}16`OO*Z>n^`JgMHoQH)pV~yZq)1_H~!voWZ{C z@|!cb{*4`6|JD`r8#uWB?HyeI_71Lpdk5FQy@TuD-of>6@8J5kcX0jNJDB^A_8n&Z zu2HM`dK)*eija{pM`_#XW`)b89catHjnj+XMBHV z4~}R23#xUye#ZY#`wK6$+WR|!VEXZQ1yy_X4k5UHw-8*va|o{AMFjIM!TnWSy}PKm zdZ!Uwzv~F*w>j%9$DH5ntg|rB5UjH>&kC%wFwY9vJ&SiT(ay6%cF*FSOtkZ?klnL* zCll>FE9joZvk~ho{qu~%It%mc!a57{%)~ki^URdpyLmSi?e)8dpGZngZ@ch}nP*I}!@ zU!TGB{q^i{vl0UFMI2D@aJb8(sar8HwO

X4=v&YcsyP17MwC%kig@K#G6(zNa5YlByOpl{O;ub375(4f9e+k84B_{vTDHeGf9 z^x!3)KDgv&!seNgK-e}2|Mt>Zucl!IFLi}q(;o*#a(zu?L;n0`Lo;`U(r-~9YLgYmoekh_8z z&sOW*9n3iIIq;rf#()0uzYAu+e%-rb_E+s32ibFc)DOo^{c}9!m*cGQaQrn+&WpxB zU~?bCh`Hgn*rZR>Cl}w+%Eykb&LcKgjhz?mM_kvZY0#6^xtqJt!A;BVb6vDA`*NSA zr^||8_+6i-rMIta=6&!Vn??8P+q&(DE&I0G9Q=d6t=lgCd*8=;Jh1$3{$SrGjR)2^ z>GO>}t7DF@10TC1#zUVYkFFSBeO{?-7_)5H7j4U!Wy8K`TkWG?SC+Gm1MS*hI6n@u z;abSsWly_o*f!_paxD!Ew+&ewlSW(yr?i*7XbPx`uVV!&(Pmtq-u)4Or_5 ztaS#~`U7iSg0)`3TE}3mZ?M)qSnDC2@2{>$*>j!3x_)6@*RZa4SnB|+^#Rtp0c$;h zwa&m=e_*Xku+}SB>lm!{4c58`=j)-)-TzJNKl`Zt(*AN^({bRw2LI1IygQD=|KIbF zbD=d8{_?uYJ%x7ecidCN+*4%FeF4_}0@i&2*8Kw3eFxV42-bZE*8K?9eND{$4%U55 ztg-37NxSZ+u<@(JzA4AUhwqG?K`jHK+al*2Pb>C;4 zIm;I|Ie+;W>YV1=e%0~JeZl|T?+V6)U(E;kRX_TD!anl50{fivZNF+hXutG3MDv7p z*~9rf%vrv$$(cE?G3T6b`&IKf_XTU7!?K6&b>K~ux@p@3Dqe2AZml*0 z&gj;k*toaOUKEs;Nu;w$Y`3!45!mR+L;fsXP&^C&#>k*toaOUKEs;Nu;w$Y`3!45!_|w_@guY?w>1<}j=|3~LUFswNYYYxMj!?5PCSbjB! zY1bTvHHTr%VOVn*)*Oa4hhbg6u;w$Y`TRfY^Z$A4v+k#y$DIFXE&5$tzyCY0Mfv&q z@2*YGudZdT)10*}?Ygev{JNI?m;1@rkhZw3wMAf>r!sdc=By^AE&)7 zZfkAST1x+4=Kt=uf$Zg1zik*BzhN}auj01Wc8-I7^W>~Pbxid8NB0HVWshGm?VLyY zq`fU}>)xb$8U5s}erVUWu7Q+Nj?@qB+E%RJb+TtXVvUpE zcp4{6T>tu8%`M4I5RbidvtRS~`de*X=1iN~bIxpvoNJqsesabp_a)A3!jJ#Ww(2wb zsrzs3v)(rB#hFdMt@n$F@anBz9G4i&mY?=6&K)%-_=@`;E)Ji6 zaqw0zu4JoSFgSSb4m;Z^H~u8p|7-qtu>ZTcU9fLwzI{ob-k*8D!S09JhMlu^##z?( z!T*c8^A5MFy7o2*8WA)a5V4>lf`Ujr2a&y|im@m5Sd!RV)N4mgG*`rKqQq6`u*PDnuBMZ{d_#n_vd%+KljbdTy3wD%^q{UV~l*B zg7JKQbH1)Q-;X)pr#auhnP=pBoQLakA29dD^%lw+*MoUJt_SnnTo2~+;Ce8h z6W4?J{OC7V8!v0~&G|fSjOX*4^L5Sne$4qk&H4V#_4may>bh;uZu@chqm{=tZtZiL zd4rw*(71QE6U~}me7*F6=08ndzu0%?HfH_*LjT#U|DN|^)^UZ7FFB{qSLnQEUB~aP zHr{~qd~-fe!FWEuIbYYD@5h|))12?$oS!SkeIJ~Y`{H^q_sjKQo`dV<>$Y({nCIqt zFrNq4gZZ4e9?a*be5`eA<7I8WIiIJEaX!EJ-12ojp6|z;@6*iZ7w@J1zBK=)KdrDv z;_u;`r)D+&cGs%rS5DonIO3-7nf2cldky}MdD_$`ihlh*E||~%=Rd>wzc+In$1~3P zI4{g~^ql_RT^{$}WS-wvJC8Y^-<+>&);#W~o%#7b&H4V#Jfp4`{^x-12oju6f)~ zVm{a5bAh=IpBG$zUp(W069*^$9_swzCUYAPel*bI7nKJVBaT?ZJmAEei}%-G(R|yt zFBR7>`)$Fo{D1y4%zw{3nBzDe=6swN=9;>Xfwgh}edhUXjOX*1^ZCvBy5@X8?aa^j zY0md=&d(L&+(*oB)Ah_cPn)i1*7@6Xy|`{0|2f}JJM&$%$be3_HS z{k(a8Q9F;B>%`}luj}!AKZ*HVhtCD(I(&}swQFsfK79K={!SV-E{F8pC~erc`uG2> zJ6hAP*Z8gHoH3#`9dpc;=DB}sNk2LEa`S1ETGCbBE;V=Eq$PbZ`XckC3&*5ud;i+J z(YIsL4hNlOUS+qI^u%HNnYa5@OS)sfpO}C3MoW5e=8w$F{jfFl=)IHqgeO|lyHEYl z+;fHT>G+x7H-9~Jv-Itw!kpJ%`-8;Yrf~u)^zWzb0csZZIybc=EoCm&d<7HvMDZF6QA|j!mesx9o3rp zKR(!e$-1rS+P%MLp8I@Dnl<%F?z3#ydz?J>H1n&kwxmm@&*E9iwU%j3^JgqG9zJ51 z)^yazYneyf-M46+t&B9@+M=`g=2nT{>cNa>CUybH?O%vYns<} zC-bqNw4_1r?`q!W`j)iQBYT>k-?SxNy2e4~gVt|J{r5T2yvcW3(*E7fH@`ikCEd5h zh2}$#Xh|oWaEZCsjF!~nkju@-Z_=86Gwn+AFMqOeI0*~JE0{lIQt^=)%uQl%KC(HU0N4@A!U39@~o=Iv-BL#xn8bnY znwR_Q=(O{^_sr|;GCDo>L;d#Db^p2H=ycDlPtE&2H!58;xjVmA8Z+jNN)K$XjCsR# zN2l`D@0d6J@6l=N<9e81nln0m-oBjqEB)_x{oPio<{w_9+cxgs%;k;xZrSIK$Y(C4Gm*>C$i<;=53rvtC{`OEp^MyE}-UDk7c_RXlY>x;gha>|TRY37V> z9)I-pQR(9Ix|$z8SkE~7L!PC)|Ax`&%D3m4cj_`GO&#;DdE4X0q(7|V&!=4L<1y*- z7yY@F7i~H&J-6+@Jm->q8);#;k({$p<1(0c`gqw$=R7jRzXxvaqq1_72bwp`&(54+ z?x)6$IF|Fru}#Yj~P^=|<-7P8goHSv0}iXXoMR_PZPxH~v0( zcv|6@Ej@nkv%}NFgSIx`GI~V%(dCLIbpPuwJtqC^S38-n-*Q~)wbMS$TyDK+WLjZ?%YW}TJe{=97M?#=_c?c4 z-)H&mPlu}((i6P%{*|((DdnXr<*T$dc$-_?{my6O&^_Zdd=%CjT)DI|Gq)` z^{>xlPI=Dsq3Mw=s&$yH#|}+5{L1GkN4+v6o%I)=zZ~(~A?ZI|Dt_?jA!+GW-$S|m z{zKBwwm-$^+2h9PL5G=F>6(DeTDey;Md7lx+K+x)!c>uG~@+HL+E%1a;IK;JX| ze9FHzhNZ)AskqCTBhv=6tNGLZIWpb;kk^qKH7CN8yrY@R<&GJY zp8n=K#>*#vx^6o9oNLXa|Do&N=kt_rZn|Y;#eX_*Q2J!LKZkPuKL@3;Csw@s zA%oN4Ln?m%nxX0J&Hb5_XX@{5-7bIRoQ)bU9_O8|`;(#Ry`g{byKY-$gEVQEY36u# z<^=P+HEzVQoIj3jx>kql-ad3d+IGczd_NyQvsU_ag}cq=R%@l(UYch9^!YW@>CaYt z=0R(wtLInTZDId3s;K5Kw|oDz+UV*$8!gp8wd?-5?gNjkp634Re)B5#ub#eXf52Qk zv3lC(t_RI4E?7PN^0w*bH#S`(jlZZgZ++xisqX=QHa~pzz_it$pK9jvwmF zTlOT|NEy z0^eu3k=B3qJjd^-ob~hmsn7d<#&X3M`lk){tN75Z*GzkT~EkLpg8h0jc|2&-?ysym*{t zrtSY(@xN|aIUTfWHUGs0ebOWW-(r# z@f~x^=YAQ@*`<@6>;S&tLXfyLVdY5MQ_4U-$Dr=lOohZ#L?k4(#Up zEa#opJMGltIiKgZ{Z~$xPV;k>XHQx=^&4C9v@cdp|9;n>L;1l;ebZ6TRs6?=ebXi% zSA6b&R!ciIp7nXI7`IC5HSi<2QR6b0cRHc9Un;MD-|u?th*i`072h+*voj}{=dE!g zj^+GuY}2(mT({Te-%StwXs++)i*J`tufI9l{Mh8>(@Q5-yxn(~PZw@e@h_+LN{?<) z@rI*&rB4p6c)yc+rjrL$@1Gpwn{U7v5`+ZsQ zUI+C^Kj~6^CaqWYNEiO6;`he(O54o*-1BFi`Q3Ezrd?S7Y}B|M`|@(BeU16dDL?(X zM;bQp-{w1}_DFy4_py1uLwlqL*6=yY7Tv>9#fKhWOZRZte!hqDuG4y?&HgdZ;~T%+ zBX$4mJ@ZS~_DoyO^)r^!m+6((n^f`Br}aw3Rux~c^z!NMEh|3%?B&zQlPkXGrz@o) zCsgOTev4k|!l%3W{%c$Y^G?s-Yx%U^)TO*0IRDrc(vin>HOKQZCz$80aU+i9^NC~O zIDZqDk6+h4t$M__JY!?RvE9<7hZdQa`*Nvt&xDG*oV!$-`RziFKiO}obpE>)?{aI` zbnaIb51-d1t#@%g_M|T9gWbOI{FioKRGhJPS3mE2X;vKp#Dq1e{`OEueFD!nrPQ?%ZdttHXy}pO?lSzw;hrjaQRry8Zn_}X56))4L zYwEd=pR4RYscY){or(v4-8H@Zj-S0eYSL0^^RFwuY2i|-=T_C6TdrFst^8Sa9{tTG zy(iy)jmu!(sorzaJM+8N`%ik8=6H7I1oON#Zp5*?$2b;_^EYuh`kPORxlb(T`WrLf1c%ez2_7cw5-6Kvgi4;i$kvSdCGUUn_b+ndd1sp zHoJK77GJlVxXQT=ziz_GkS<1uazh9iSbH!(V z^g*%L4=P@J{)fea{VVP>_oHImB^6Ko%jd-&qpS1l->5?0%f9~_m%+SKeXke#j`q9O z_kE%7ZgV_4bAoxs8aLut-ftWW$N8JM-0SUG#ojae_5|C)TR?M<>2ee9@=k3*UaOn2_iE`X4ik$>&w$W3PRtczOMmea^uf zKBIam6>mQ0>0;i0D&FV$r;Ec*>+3l$fBJNB_;;%Jd-Z0|7CSAqy2tgKsL*eeW-kBx z{29d|Z}wxnyz8)MiuP$fw*2wJr;APcRs5LFKlmb_zifHq>0+n;6@P#EXNqs{_C1uV zzV=LU`7#y%X8Md`pIiNzl(UNGi=Phjvy^kz(DU}Lc+FK`EdJK7;u)*FRNOSa;zPT= zTpV~p#r+R_qd0!w>RS3uTIhF}@4v=nFz-~q;|l#I^SjpXyF$O!%<=5Z3Fdig+=yd& zzi})a=WpWjtNsra@7>kk_w$d<+KOu~_TFOSdnc5|eXSK=bJz4@@K@F6|K#5vECxJR z@xty87VT{nUwHWaMS8K~<@f$$v1sM$*ym^6UF>>#b^bZK-CZ2_TE(CJXIe4&2W$Ge zcRxF=m@>2CJ6@euT)f9x9>4b3KNLTkSbbKCfeOVx9YDcymnQ!`loyV=yEtI! zwV6|H{MNMM-a~z!^4uBIik;u``O8n{O)GwMWW{FBUK(Rs7hbve z{8@Dmia`s-UB3Ssm%+SK#chRRFu!ZXbA@6vb389|f_cUoH{w{{ZyXE9`J1>L{_b@} zW8Xo(pBbB6t304}%}<{(wRrl8>NCIT$tlH~XHo%YVGAxZ`Klb$@mIWyR0tRs8uOmlazb zJJ|QoW6LXwSEqVKTA3Bh2Ir> z46As(r>-fwZC&x$2d5MhCsq8)`BRHOKU49|GjA-`-?+LTtvMB1XYu{lxD4iSJ@_yr3IL_b1<-bonv-s&V)!*S+-Onf%o?Cs+-&e9qv4>=rXhV-`e>fO)ieVqT+#TO)h?Zbj6n}eM<4w0TuUt^yFgK^DDmNpT`t! zzp2i1)eT1%gI}xov+Is3uAER^cbk77S$yoM-^x8U-8r9 zjxJidRQ%-$#})%m@V%A2&Y4*B-?-xApE#vBb#FgQdBG*879Up6SROQeaT)%e>} zPAlGdvf||rI=xtPKy~bwJE}XwbpA3t-YG# zd6^T;d#`aLj^+Kvv2dKfiOb?UKP>(_ulj7~U%qYe%m1kyz5V}dn_{;?6<;%K>tfsI z{Mk09{AJ7H>I*AgFnWt(`o0zarR#)Z$LjNM^t^AA;*-6r@e!xD6lwkHJj)IpQyg|g z#oI4Ex|lVi;(6@gyiKw6(CR$< z{9>nKz&F*sX-}!pK8o+Z#$_^E-{FzN+}%&HvSC+q(MSi1skqNA$hbxIAsQcN+cv)q~WDZBsv zoyIH6ReaPNvm5uH?Q@oYKYecFy0t6*&D8fAZBP1s%3GiOsB!C$D;_xF)5ck?72mLJ z_hRg`)!$Or9?KNRy<733C%;pyvraYVh<$n#Q%xHfWbd_TB0a&FAH zHgayvxHfWb%(ymkZp^qga&FAHHgayvxHfWb%(ymkZp^qga&FAHHgayvxHfWb%(ymk zZp^qga&FAHHu4pkxx}@RbHjLvYa{2zjB6w3#*Awt=f;d{Bj?79Ya{2zjB6w3#*Awt z=f;d{GrL>GxHfWbJdSH4=f;d{Bj?79Ya{2zjB6w3#*9-VPXcb#xD4i<;@ZfW@Vmyf zkxOBYXJ<|@&s*b09LxFR*rscBxGt`ZoEzT{u8o`!C8#AtroEtN)jhq`Zu8o`< zGp>!C8#AtroEtN)jhq`Zu8o`!C8#AtroEtN)jhq`Zu8o`!C8#Atr zoEtN)jhq|v0=YJFZp^qga&FAHHgayvxHfWb%(ymkZp^qga&FAHHgayvxHfWb%(ymk zZp`{l#;t)HHRik8m~n07+?a7~m~n07+?a7~m~n07+?a7~!C8#AtroEtN) zjhq`Zu8o`!C8#AtroEtN)jhq`Zu8o`!C8#AtroEtN)jhq`Zu8o`u1&;r@$AeA=6P#O z?B-*6k8vy<=WpT?*GA3__twC*k#l3lwUKjU##CwTU&Hcy{Il^Sm`?t;Wal9^+Uz&fml(u8o`< z?yZ4qBj?79Ya{2zjB6w3#*Awt=f;d{Bj?79Ya{2zjB6w3#=JnTjhq`Zu8o`!C z8#AtroEvi=xi)fc%(ymkZp>P5Y^$wv2A8-ta&DMY;@Zf$G2`0ExiRC~$hk4&+Q_*v z+=Ya{2zaBmG<8#y;-TpKwz zW?UONH|DG5+Q_*v8OJt+uZbT;kfuxnWL;Ya{2zjB6w3#*Awt=f;d{Bj?79Ya{2zjB6w3#*Awt z=f;d{Bj?79Ya{2zjB6w3#*Awt=f;d{Bj?79Ya{2ztUZ*r+P+dSdn;z%DXvZI#o*e+ z9!)$ubAox^8nYMUV|kBpEF9-=;u6SC$MPQI zSUAq##3incoEz?~fomh@#*Awt=f;d{Bj?79Ya{2zjB6w3#*Awt=f;d{Bj?79Ya{2z zjB6w3#*Awt=f;d{Bj?79Ya{2zjB6w3#w>rJz2+?hm$)`^ZkSWz+Q_*vb(^Ya{1|`6aH6oEtN)jhq`Zu8o`!C8#AtroEtN) zjhq`Zu8o`!C8?Ia8+Q_*v?|v zoO8ypa2(rotq#}4wUKk<`hoEtN)jhq`Zu8o`!C8#AtroEtN)jhq`Zu8o`!C8#AtroEtN) zjhq`Zu8o`!C8#AtroEtMS5HShQQsWZWM$Qf6C9aK}8#AtroEtN)jhq`Zu8o`< zGp>!C8#AtroEtN)jhq`Zu8o`!C8#AtroEtN)jhq`Zu8o`!C8#6H|aToVr zV{#un&O0S;BL;(s=ZMYVc-}hmyfMx><5)P3ZMs&6>*CtTx$*tr+Q_*v!C8#AtroEtN)jhq`Zu8o`!C8#Atr zoEtN)jhq`Zu8o`!C8#AtroEtN)jhq`ZYfh}QaQ`(X*U96&Q`Tu%bAegEVJ!xZ z=dCl(8{?caj)mjcrfYS$F0PH78{ZGEjhq`Zu8o`!C8#AtroEtN)jhq`Zu8o`< zGp>!C8#AtroEtN)jhq`Zu8o`!C8#AtroEtN)jhq`ZYn-e(@+>tjac$(>Fka%? z$hk4&+Q_*v~1Z_g`c396ioEWnGpvR+#l#)?VRw-a7NVG0r*TSU8Stx>kql z;@Zf$@%`Z1$hk4^Cf7#JjTzTQ&W#z@M$U~H*GA5b8P`V6jTzTQ&W#z@M$U~H*GA5b z8P`V6jTzTQ&W#z@M$U~H*GA5bnLQ2m7(P0mKo=r zvhT_sD$IT?d#i9fZ=JcH80VaEEF8x+U8}=&ac$(>_m~n07 z+?a7~m~n07+?a7~m~n07+?a7~m~n07+?a7~xQ-33 zjhq`Zu8o`<>cddqrd`g>co^44&W#z@M$U~H*GA5b8P`V6jX8fl%}jlp_7zXwmvQRb zw9C0M z+?a7~nDaYo@a#2?ch{)BYjb{&;~9@*CtTx$%5l8#y;-TpKwzW?UONH)dQLIX7lp8#y;-TpKwzW?UONH)dQLIX7lp8#y;- zTpKwzW?UONH)dQLIX7lp8#y=T{N32hc5UR`FmBgI&W#z@M$U~H*GA5b8P`V6jTzTw z!Pys?ac$(>m~n07+?a7~m~n07+?a7~8#AtroSTAsz_pQcW5%_Sb7RJ}k#l3lwUKjU#l8ZQAABFiw4&b~!g@TpKwzW?UONH)dQLIX7lp8#y;-TpKwzW?UONH)dQLIX66u zT^l(!W?UONH)dQLIX7lp8#y;-TpKwz=KLFsbH?vdpFhTVr}_6-0q5Uo=KR~Q19Lwy z&N<^)IF4<)R)_22+Q_-_{ovZjxiRC~$hk4&+Q_*vr0y&W(@7wUKjU z#kql;@Zf$@qAnxIX7lp8#y;-TpKwzW?UONH)dQL zIX7lp8#y;-TpKwzW?UONH)dQLIX7lp8#y;-TpKwzW?UONH)dQLIXC9KU)jvmw`rGi z!#MSA+U4Asac$(>m~n07+?a7~m~n07+?a7~ zm~n07+?a7~m~n07+?a7~m~n07+?a7~m~n07+?a7~ z!<|UH)9g!_vqxc$=VeYX&s*bgEqwksmd~notvXZRrd`er_eOo2b~!g@TpKwzW?UON zH)dQLIX7lp8#y;-TpKwzW?UONH)dQLIXAu^TpKwzW?UONH)dQLIX7lp8#y;-TpKwz z=IjeKGxcrSm~n07+?a7~+DULC3j+$x_xj%~VDhwI|n$hq-+TpKwzW?UONH)dQLIX7lp8#y;-TpKwzW?UONH)dQL zIX7lp8#y;-TpKwzW?UONH`N@uHgayvxHfWb%(ymkZp_&aY-Z})w8^<)occCxa&FAH zHgayvxHfWb%(ymkZp^qga&FAHHgayvxHfWb%(ymkZp^qga&FAHHgayvxHfWb%(ymk zZp^qga&FAofrP0!gBRLioOhaiNWbgsNt)x?nG?+O);L^BpFfUmx>kql;@Zf$@qAnx zIX7lp8#y;-TpKwzW?UONH)dQLIX7lp8#y;-TpKwzW?UONH)dQLIX7lp8#y;-TpKwz zW?UONH)dQLIXC9)12;4EZQA7AFiw4&HaRzDTpKwzW?UONH)dQLIX7lp8#y;-TpKwz zW?UONH)dQLIX7lp8#y;-TpKwzW?UONH)dQLIX7lp8#y=T>^#HNoWTR{FwQ&8{!C8#AtroEtN)jhq`Z zu8o`!C8#AtroEtN)jhq`Zu8o`!C8#AtroEtN)jhq{E_Wzri`ZjHHZWyP& zO`Dt>Gp>!C8#AtroEtN)jhq`Zu8o`!C8#AtroEtN)jhq`Zu8o`!C8#Atr zoEtN)jhq`Zu8o`m~n07+?a7~m~n07+?a7~m~n07+?a7~!C8#AtroEtN)jhq`Z zu8o`!C8#AtroEtN)jhq`Zu8o`!C8#AtroEtN)jhq{E&S`?FIYXXThjHF% z&TsO&&UsJfcy{Il^Sm{V+$f(vj%~VDhwI|n$hq-+TpKwzW?UONH)dQLIX7lp8#y;- zTpKwzW?UONH)dQLIX7lp8#y;-TpKwzW?UONH)dQLIX7lp8#y;-TpKwz=A7Tx%+$AO zlXJs(iEAV0#*Awt=f;d{Bj?79Ya{2zjB6w3#*Awt=f;d{Bj?79Ya{2zjB6w3#*Awt z=f;d{Bj?79Ya{2zjB6w3#+-8)VQS8h*V$p5cbfAV{jPJKqdA_PIl(+{jUyM*=Z|BX zuGQhXxHfWbJRjFa&W#z@X175V!C8#AtroEtN) zjhq`Zu8o`!C8#AtroEtN)jhq{E&gX4r>f5x*xnZ38Hf?fl%(ynHZ)3)_k#l3l zwUKjU#sE=y$AEWHICe8pFfUmx>kql;@Zf$@qAnxIX7lp8#y;- zTpKwzW?UONH)dQLIX7lp8#y;-TpKwzW?UONH)dQL)weO@+Q_*vs-gc9M8_2 zV4k2#HuRK&ac$@+1>@S#Qwqklp{Ep# zYeP>d7}tiLQZTL!J*8k=8+uB?xHj~Zf^lu=DFx%&&{GP|^+1}L`Zn$2#HuRK&ac$@+1>@S#QwqklQGFXTt_?k<7{|4trxc89Lr*Cf z*M^=_Fs=vc};`7I`P1ovhU0fS_ zN-+o5hMrO|t_?kDNb4Lzk`TpM~y z!MHZ`l!9?>=qUx`+R#%9#@S#Qwqklp{EqAcZBZ( z^EVv4c${~t_k}m(cdfqxY8;v4*_ji}IcprXjC}q$w&_|Ou8V6!Pbuc$+R#%9#@S#Qwqklp{Ep#Ya{2zjB7(rDaLVa=qUx`+R#%9#@S#Qwqklp{Ep#YeP>d7}tiLQZTNKoEtN)4Lzk8$F-rS6s+%Ld>6P;Tq3L8#y2#HuRK&ac$@+ z1>@S#Qwqklp{Ep#YeP>d7}tiLQZTL!J*8m%2BYpGOwF0##pAqF{T`!Mq2INB<59!V z9M8_2V9r_Ns8#6m$FWV<>Tq3L8#yDNb z4Lzk`TpM~y!MHYZZp^qg^ps*8*M^=_Fs=2#HgayvihZc_+04|pDd;Js z`P8>5=qUx`+R#%9#DNb4Lzk`TpM~y!HT&GIX7^l#*4>!r;5L*P3m{8n2wsI=6H7I1arR)_22+R#&qIk-0Tl!9?>=qUx`+R#%9#d z7}tiLQZTL!J*8k=8+uB?xHj~Zf^lu=DFx%&&{GP=wUKjU#=qUx`+R#%9# z=qUx`+Q_*v_mOKuPbtQ6ZRjZlYdw=X-px#Xn}VKFnnQh?f}T<^t_?k=v&PbnDJhMrO|t_?k1do>I)gwV|gJ zjB7(rDHzv=o>DNb4Lzk`TpM~y!MHYZZp^qga&FAHHuRKY4z3M7rC?kedP>2#HuRK& zac$@+1>@S#Qwr8z26g+Jnff*bJ*6~<`Zk4}8#AtroEtN)jhq`Zt_?keEvAL=~^AGi)%wqDdynX&{GP=wV|gJjB7(r zDHzv=o>DNb4Lzk`TpM~y!MHZ`l!9?>2#HuRK&ac$@+ z1#9n;J{`?WeVc-wQkp}3n?lZw8P|rMQjFu;&{GP=wV|gJjB7(rDHzv=o>DNb4Lzk` zTpM~y!MHZ`l!9?>=qUx`+R#%9#DNb4Lzk`xe6(}3U#Kw zO+im7&7r2#HuRK&ac$@+1>@S#Qwqklp{Ep#YeP>d z7}tiLQZTL!J*8k=8+uB?xHj~Zg5^li7YU~3Oz`4y-l=>EdI|Ym%fX<>kU5^6Il-K> z#?ed2=Z|BXuGQhXxHj~ZVh*kiJ*8k=8+uB?xHj~Zf^lu=DFx%&&{GP=wV|gJ{DE8> zIX7lp8#y=lCkDNb4Lzk`J~KYACZ@hkqNkL`sc)0$ zDFx%&&{GP=wV|gJjB6w3#*Ax2PbtQ6ZRjZl2#HuRK&ac$@+1>@S#Qwqklp{Ep# zYeP>d7}tiLQZTL!J*8k=8+uB?d`I$~*u>PgN%WM`IQ4B3J*8k=8+uB?xHj~Zf^lu= zDFx%&&{GP=wV|gJjB7(rDHzv=o>DNb4Lzk`TpM~y!MHZ`l!9?>=qUx`+R#%9=HDp3 zm&MeX30^$TJLP+w?`W9sd%pMKc=kGT&KT#MaV#9iHeIX3b#ZOzDa9OI8+uB?xHj~Z zf^lu++?a7~=qbfGt_?kK&w z!Ti4CcOJ~|L4FI?ne)du=Zs_FIJW6p9j=ROLr*E@;M&kr3dXgerxc89Lr*Cf*M^=_ zFs=2#HgayvxHj~ZVjS0oo>DNb4Lzk`TpM~y!MHZ`l!9?>=qUvg0}=l; zG4*W{J*6~GeVas2DHzv=o>DNb4Lzk`TpM~y!MHZ`l!70WYeP>d7}tiLQZTL!J*8k= z8+uB?xHj~Zf^lu=DFx%&&{GP=wV|gJObklgC8o|y@ZxdaDRCPy7)(4zTnERq*O_z1 zIOmLG;W)PGS{<&7YeP>d=HS}UQwqklp{Ep#YeP>d7}tiLQZTL!J*8k=8#y;-TpM~y zF^+3PPbnDJhMrO|t_?k2#HuRK&ac$(>m~n0BDaAOh z4Lzk`TpM~y!K^v4&LXDHOz`4y-YM%ethvCf->{AY$FtX&bH+I5jAP+Aw&_|Ou8V6! zPbuc$+R#%9# z=qUx`+R#%9#Cg8zD=U16pU*_PbnDJhMrO|t_?k< zU|bt|O2N1`^pt{eZRFgTac$(>m~n0BDa9OI8+uB?xHj~Zf^lu=DFx%&&{GO#jhS^- zF?D8w7mxE!S(jyv6=uDbbz3-|z0RC7#yMvk3&*id*XnRxTpM~yF$dR%o>DNb4Lzk` zTpM~y!MHZ`l!9?>=qUx`+R#%9#@S#Qwqkl zp{Ep#YeP>d7}tiLQZTL!J*8k=8+uB?xHj~Zf^lu=DFx%&&{GP=wV|gJ%pNBDmrZQf zM$Qf6c5Ub>1>@S#Qwqklp{Ep#YeP>d7}rM5jTzU5o>GkC+Q_*vUdP>2# zHuRK&ac$@+1>@S#Qwqklk#l2a51D;aje9>iv%MRbcgnsid#Et`vFyvj@$7Zx{4vfs z<5)P3g>e?xr-#|kXKx;6pP&7H7%u=P0LI0j=MapGLC+x=7lWQdFfIl?hhSU`dJe(3 z81x*1aWUvQ1mj}Ra|p)8pyv>bi$TvJ7#D+{LohA|J%?ai40;a1xES;tg7b5k^Zl2M z=jSr#=k*+11A6K(2iJg}IxwyQJ#}DQ1A6MfxCZppfpHD!sRQF0&{GG-HK3;sjB7wo z9T?Yuo;onD0X=nKTmyRQz_xoU!0e^dGX`caot`l;d+GFyf!Ryfp1PU6bk(mgvzJcK80N5-PR|&ay>xoU!0e^d zGX`caot`l;d+GFy@%-xh&78ll%=tUYoWHxw>=n}!g=5((rY8!_UNJpUVD^gXi2}1% zOivV;y<&Qz!0Z*%69s0kn4Tywd&Trbf!QmjCko77F+EXW_KN9=0<%|4PZXHFV(l55 z^S|BZ{O_+h|C?*h{}!9s3#I1==V33Do*yuKq4fNK*$buT2h3h5JwIUfLh1PdvlmLw z5174BdVav{h0^l_W-pYUA255N^!$L?3#I1=%w8xxKVbGk>G=WY-=gOHd(xbLLz?q% zOEY_Y^t9ku_WI~)0khXfPYam6K6+Zf?Df&p0%os|o)$2Bee|?|+3TaH1~ z+Lt-6Uzziol{v3vnc0h==04|PFM^u;FnbZy+=tnVpyoczUIaDwVfG@Zxev1!p*;yR zdlA&!XPmtVYVO1AMNo4eW-o%8`!IVE)ZB;Ji=gH{%w7aF_u;&j+YaaTSaV*3HRrWi zGi&YClxIF`?bMWqS!<`JJj_}qMaQy$KH6Xv|XV9t9A=Dbf~W-XbT=^V>iGBwj- z){?224zrd_&2*TxWNN0vtR+)39cC?=n&~iW$<$1TSxcs7I?P%!HPd0%lC`E>&Cyyi zHPabqEt#6>Fl))wOo#LSnmO;6ne!f*Iq$ofSu3R`ILES9sx?zHYo*i#XPmWCYJ$V8 zl~NNNX04Q(;4o{Y)C7lFE2Snl%vvcm!C}@)sR<6VR!U89n6*-Bg2SwpQWG3zt(2PJ zaNavM=lx%E-t#r*ePlChfm#zZvld9rYtHlkbAS2lGx$EU!(h%{gt;^JPtSgi?>{>^ z=Ir^HJ7a(F?3?-ivtwq?-kP~H_P@^lr0+jFljiJUnmc2E=j;Rf{<8yY&R(%u`5m3E ze{uHPegD~MH)l`Y+!_1xD%LNlxyko-&e4cxbWdBxJ7fP@tq-v#;%CV@M`ry^vbJLG zjQv%$-WmN#m)KXdGxiV7`JsL%ZnE(I0S$ef>IP|31Ym?s><1QEc*m?OWFw`_n1L zjQ(y*?90{}`>$zDU~w-q#s2PD#=Fy+fP0p~ow2`|)^OStGkcvuYc=l4#j|J)$33~= z&e%UoYi{m2#rK(i-XFUQ1dFbx$SkUu&f9sRYXp z>2&>%w5Gkdmyp)3-7|=1(VDh<2Em=NzmN7H7Wc~0UW0q$@GRPca8Ddq`}>`)e~tFU z-SdU}*WQqOzQEcua?cmIGxlfE9^c|#C&VShCp?Sx_}tS3?u`9Mv?uGH9o)b6Ufr_; z&b=7?jGeK+2C;JNkLPD;)ShuX+!^~v5G#jMk^lDmT={R(+!^~LXn&a=SOxDTe^;3E zcZj(&*8kW3a(g&$`McfElE3rKow2^X_Lu2V==;zA7Mt_G(dN!rzg_#w^xX9Q=ig4| z{F}<$8S9g4f0@3qzW@AN*PMR?n>%CuZS6196WRBlV-s_ZSG7TTKFqPC zImejh&R9QL`^!;(c!_m`J7axdVr9Gs-k0{5+wdFUyoO`$jP-A|zZ~^rmst0eSecv? zp0~5qch&xK8(tCjoYz9ld5zTE8S9s7e>v)ZF0pQBXRObu{pF}{xx~7Zow5F;_Lrl6 z;}YvGcE zk9WrUZ^X(t**r^j8_d~xFn7lKX0`fYORVeF8S8h|>R&CfZdGTjPgSe$w8Xkhow5E> zt$xuG>kf6s`a;>U^!G#5oA7hDiEjnZUim3U(-`CTuRUC%YnxuV|7tLFt%Yab_@XQ$S_ zYVMnMHbrq;e{?whH#ubTU2YVE7$zL{G4s=05b*1l@)o2j+0 zn)_yI?W^X#nOgg*xo@V{zH089b${jHF)ijU`oF4?}o|m{)6(n;mGfXBflFazk5aHcf;g&AFKRsnEdX? zmER3Vem5NX-Eic0!;#+&M}9Y)pRt4^zZ;JHZaDJ0;mGfXBflGt{BAh%yWz<1h9kcl zj{I&o^1I>4?}j748;<;LIP$yU$nS3qR zem5NX-Eic0!;#+&M}9XP`Q32jcf*n24M%=A9QoazpYyxn$nS3qRem5NX-Eic0!;#+& zM}9XP`Q32jcf*n24M%=A9QoaF3qRem5NX-Eic0!;#+& zM}9XP`Q32jcf*n24M%=A9QoaF3qRem5NX-Eic0!;#+& zM}9XP`Q32jcf*n24M%=A9QoaF3qRem5NX-Eic0!;#+& zM}9XP`Q32jcf*n24M%=A9QoaF3qRem5NX-Eic0!;#+& zM}9XP`Q32jcf*n24M%=A9QoaF3qRem5NX-Eic0!;#+& zM}9XP`Q32jcf*n24M%=A9QoaF3qRem5NX-Eic0!;#+& zM}9XP`Q302<#&Im{BAh%yWz<1h9kclj{I&o^1I>4?}j748;<;LIP$yU$nS4?}j748;<;L zIP$yU$nS4?}j748;<;L zIP$yU$nSDk^ zRrAqItw+^-G*jzQH6P8?dQ{CvGqoO7^U+MLN7Z~Z=e1&U3qRem5NX-7vKb zRlvr_Qp->^4b9XtR82!OwG36$&`d2u)ig9y%TP59&D1hfO+z!a3{}(6OfAFiUsp^m zL)A3&IJFE_)6h&UL)A1iQ_D~_4b6FN-yHef+;il2!;#+&M}9X@!oVPc{3@)ap~sJ~OrYRI|@a ztv=Q4GgGTiHT%qYFUB1C-Q08Jcf*n24M%=AOf5Rqr1P=VqT6jy#nhrxO*)TLi%vD^ z%+#V&O*%8R=v0%=Of5Rqq%%{CPBrPw)S^>OIy1HCRFls9o@&vlCY_mDbgD^brWT!Q z(wXz#nK|;ix#!65h9kclj{I(zT5GDg=3}X~rkZPJYOSf}nweT_s<~#S)|zUrnW?p= znrmiit*PdknObYAxn`!;nrg0@skNq>Yi4S#spguQT5GDgW~SDfYOa~{UZ*+oyM519 ze<+VfemCQh-wm^tpqSZnSW8gMY-TM%F|(Pq1jWo|))Evmn^{Xx%xq>YK{2zLSXnW% znY9GP%x2aS6f>JyOHj;gW-UQ6vzfI7#mwfsH*JpmZtgkqyWz<1h9kclrWTrFW*ShbL4mDXCY?xxSrAZ-Hbnqp=%wa^qZo2iASnAuD%G{wwjYN07+Hd6~tF|(OkXo{K5+5Ip_ zemD0V`Q32jcf*n24O0tEF|&`Q7MfyaGqunZGn=V}rkL4GEi}c~U(LDP}fP3r#VznObOyna$KfQ_O6p7MfyaGqunZGn=V}rkL4GtgM*X zOf59U%w}q#DP}fP3r#VznObOyna$a)GDm(l_Z<1%aO8Kxk>3qd3r#VzkEIrxVrDb7 z&=fP9sfDJP*-R}o#mr`Ep($oIQwvQovzc0GikZ#SLQ~9arWTrFW;3Ktg{GL< zOf59U%;xOEnIpfOdyf2WIP$yU$nS=!g{GL<$5IPTF|(OkXo{K5)Iw9tY^D~PVrDb7 z&=fP9sfDJP*}Oot&=fP9sfDJP*-R}o#mr`Ep($oIQwvQovzc0GikZ#XT{K62H}@R* z-Eic0!;#+&QwvQovyY_~nqp=%wa^qZo3BZ+=jCbM}9X< zEi}c<9;X(XVrDb7&=fP9sfDJP*-R}o#mr`Ep($oIQwvQovzc0GikZ#SLQ~9arWTrF zW;3Ktg{GLnqp=%wa^qZo2iASnAuD%G{wwjYN07+Hd6~t zF|#?l+|`_%-_1QMmTbpahZSSCO);~_sfDJP*-R}o#mr`Ep($oIQwvQo zvzc0GikZ#C%8HrI)Iw9t?AV!FXo{K5)Iw9tY^D~PVrDb7&=fP9sfDJP+2_gby*cu` zx#!65h9kclj{I(zT4;)yeNJkjDP}fP3r#VznObOyna$KfQ_O6p7MfyaGqunZGn=V} zrkL4GEi}cnqp=%wa^qZo2iASnAuD%G{wwjYN07+Hd6~tF|(OkXo{K5 z)Iw9tY^D~PVrDb7&=fOQ^Q+tzbL4k(&pEfn3rgKSH}=X3r;9R?KWB zR#wbxCRSF=Y$jG#%xorBR?KWBR#wbxCRSF=Y$jG#%xorBR?KWBR#wbxCRSF=Y|gnz z=E(2nJ|n*yj{I&o^1IE7l@&AlSYl9Vr9k5W@2T<%w}R`#mr`6 zWyQ>9Vr9k5W@2T<%w}R`#mr`6WyQ>9Vr9k5=A1ibj{I)!Ir6*V$nS9Vr9k5W@2T<%w}R`#mr`6WyQ>9Vr9k5W@2T<%w}R`#mwGo zBUV<-Y$jG#%xorBR?KWBR#wbxCRSF=Y|go~=E(2no+G~-j{I&o^1ESTWqRJj#LD!% zhl!Qxc@GmSD`qwmE7S9yabjh9-owPo^t^|Ol@&9aiIwSj&p5F%J?~*+WqRJj#LD!% zhl!Qxc@O8@XLICtGamWfaL$SLoXGEHoLHHj?l7@3J>6kqWqP{9#L9}9&BV&|bZ4Ac znV#-2v9e-jGqJK_X74o8`)3Y2VR;Fh;Osq`La+p||p5<`<+cQUgH{+4t4M%=A9QoZau`)fmVPa)^a>K;R z^yG$#mFdY16D!k`8zxq!CpS#2toq?*Vr6=AGfu2bPi~l4nV#G*u`)fmVPa)^a>K;R z^yK#ZsuqMf^1B(2{BAgZhj>opcQa0`OwVbUSec&FFtIW{r(t4cdQQW{%JiIuiIwR& z4HGLXW;PQm({q|}Vr9k5W@2S}PBTudOwVbUSec&FFtM^?W^?{-H%ERqb0WVRj{I&o z^1ESTWqK;Z#LDzkhKZHwsSFb<(^DBHR{p(uD#OIe^i+n4mFcMr6D!kG875Yyr!q{e zOiyK)Sec&6FtIW{m0@CKdMd;D-(qv*cQYRO-Eic0!;#+&6D!j*7$#PxXE02xOwVAL zSec%|FtIW{gJEK2dIrP9%Jd9|iIo*In~9a_8O%7bGChM~Vr6;;!^Fypna#w?^bBS^ z|8_D*emCQh-wj88HyruhFtIW{abaR*dg8*w%JjsAiIo*In~9a_iOV>#GCgr&Vr6>b z!o4^&yE7KDfCRU~=E=;UUPh6N-nVz_C{;g|{{BFi0zZ=fKfjuYkyBQ}| zrspe6tW3{Wm{^&fuQ0JPJzrsBWqQ8C#LD!1g^88v`3e&&)AJQ3R;K4GOsq`LSD09t zp06;mGCf~mVr6>1!Z|iEM}9Zsk>3qRem5NX-7v8-JxyU^WqO*z#LDzEg^88vX$li7 z)6*0tR;H&ZOsq^#Q1hfRE7Q{y&aq^IBflGt z{BAh%yWz<1hKZHw*$ERX)3XyMR;FhsOsq`LPMBDko}DnUGCezCVr9k5W@2S}b}~+^ zOwUf3Sec%kFtIW{J7HpFdUnFZ%Jl4nb8RiIwTO2oo#Qa}g$1rspC|tW3{Em{^&fi!iaWVrFw*TQf&~H*@mZn#c2+ zn>q5knG^ZlFtIW{1z}=kdJ4kC%JdY3iIwRo2oo#QQxGOrR?KWBR#wbxCRSF=Y$jHw zry%o*mFX!66D!kG5GGcpry!iyLd}ui&3Il5^?2lWGamWfFtM`smpzAAnVxx!6D!j* z4<=ToXC6$fOwT-+Sec%AFtIW{^I&3Sdgj5z%8HrI#LD!{W1Lu-o_R2_GClKPVr6>f z!Flc49Qoah=e28(=QV9}g(tWqQKF#LD!9gNc>t2?yuB26N9Vr6=sF;1*Z&oh`AaD4WaO8Kx#L76?FtIXDHcYInnAuFMjFZhcu`*6JOstHP4HGNl zWW&VDikZ#C$~f7K6D#9n!^Fxs*)Xv(PBu)ejFSy#x52ExN#}Pn9{JsH3qx7scb*Q87n;H*<)U6*GIBSQ#gqabjhhY?xRXCmSYK z#>s|>m2t9RVr86cm{?gcvzb^KC!29%Wt?o7SQ#f9CRWDDhKZGNvf=CwnIpfO@$3$H zJUd0^$nRzju`*6JOstHP4HGNlWW&VDIN30sMOiIs7(VPa*RY?xRX zCmSYK#>s|>m2t9RVr86cm{=Jn8zxr9$%cuQak61zWyQ>9Vr86c#)*}2vf=FJnIpfO z@$BY#T)(LboNUImzg*yC!^Fxs*)Xv(PBu)ejFSx$E8}Ft#L76?FtM^?W;3y}VrDb3 zGEO#gh?Q}&VPa*RY?xRXCmSYK#>s|>m2tA+>{6N|znk&M?}j748;<;Lm{=Jn8zxr9 z$%cuQak61zWt?o7SQ#f9CRWDDhKZGNvSDInoNSm_87CViR>sMOiIs7(VPa*RY?xRX zCmYW0t2y$!8ISyKIP$yU$nS=Um2t9RVr86cm{=Jn8zxp(%xorB#>r-!SQ#f9CRWDD zhKZGNvSDInoNSm_87CViR>sMOiIs7(VPa*RY&g5h)g0AA!^vhm^1I>4?}j748zxr9 z$%cuQak61zWt?o7SQ#f9CRWDDhKZGNvSDInoNSm_87CViR>sMOiIs7(VPa*RY?xRX zCmSYK#>s}WTW;2xK;k(W&u+OnJLl%e?`96MGEO#3tc;Tl6D#9n!^Fxs*)Xv(PBu)e zjFSx$E8}Ft#L76?FtIXDHcYIHlMNFqYk%2Htc;V*II%KLHk@+-%#q*Cc+Lgzc+L?p zM}9YRh?Q}&VPa*RY?xSCF|(Oi87G@@Vr86cm{=Jn8zxr9$%cuQak61zWt?o7SQ#f9 zCRWDDhKZGNvSDInoNUiudO+g)0*?G{IOlG7Jm++nBfpzDk>3pyE8}Ft#L76?FtIXD zHcYIHlMNFq<7C6c$~f6Du`*6JOstHP4HGNlWW&VDIN302UN#82WL+72ZxE3akAm)4-Q9v za5(yd!^Fxs*>Lm+hoe6@9R0!J=noDPE8}Ft(H|TpR>sMObMB!z^1B(=-caKAE}U}` z&5_^Dc=W%9iIs7(;pl%26D#9n!_og5j{eth^uLCq|1})_ui@x_4M+cLIQn11(f=AI z$9ces)$h6wH<{ab@T2Ot)4W z-Je%`~4b>j2k zI`O&X>lPfF?gyF4>GojGh2^JZZ<_Y0LA!Z{G0K;pu<( z-O_x{Q^V6zD{gIGdgzFB+{xRR2YfR+?emMB%=LdOgSqF<`0r!yhH z@wBgorAuEs(!9c+!&2j>ipM>>L7Mq?#b@rnL7I1XHNU0H2I=W>M|=Lj6NaWQPdL`x zf8(L4*Eti-r)n+X_$N*=f2j5H3obd;yy>|^(m~TFo8NhINP2t9Y34Nt3{A@)bh`P2 zziybm>~W5{{u?Zq`|pguyW%$(_kY!a>!)G6U+!nze4X`D>$R7euQ+{hI`y!MKU**; zJ%4n?cb+>aEy{B?8#pLk`b9N9{`_^*3tv~~nY+chY0iQxe4cqD2c}&=y4t*l);uP@ z@H=xit$D2X)HUXblLn@-4^A=v`I&*~mGh^X*WY-(bo0y`&Gp~*!Q6jm{5>DP?YaL; z(}48qn)mn_4_JEbbm6GG&G#Ou z0sYhQ{i^faxMKe_VA(%Z=X`ASH1&!5&9k&N)BE-Z%(p(idOGFi2hAsawtCur%5?MQ z8?TWbn^c;w{MlM*-0pui*JH+D?!Pm}i89iv9#b63^X}BYZ)$m?;&1O>IemZmYX0TRtejSTt>S%d?UQ~py*lSlhxJag z3fJ~8zv$gN%~|6GpXYB{Lt1my7tJ?~@116>@{;+$6MCmZyS;2ae&4>S|AB9q>uV9g z+)rm*e~7gR?*HIjzngA8Y_6a2f|eE1dA;YD54mpn)bsq=<{MUDKE1nL#V_8Xp6{Dg z{6wQynz&EJtDM_2UE8ZVcH%lc(|T`IeC5O*>BLpu_j%6Rxkox|e#Luft?SH>KJfU0 z{d=Uf=YMD(cS(=bXRdn|lzV6`ZR%e>_juGWxooMlL-&e*u+CEHzS#>sXU}`PricGs@xxzrNuNxr=1e@V zOZuYmjpy{-XHl_CpRUw?Ecz46&eeE=ub9Tn{(pWp?{@d4>UyOZuIX~mDf&VW44|{JO_Ulx?e^-V=3Wa<# zWlKcJyzkH2=8cpLC7Gwl6qWEru|&ySC z>~~1dN0vX94K#;H-9z{LLs?1V7~cH150)>U(({6UeW1+zMbESEyQkc8@nVj7$w~K= z$%UV7F5BEwZaAgqFU`KEoU_p4E?@VAd&+xG?|F@59w=Ylb4iyE=j6k*J3r3DXHK5} z|M$OcD}VXr^L>rKS@YKNjz2ule8qadD36`i^9ozsQtsNa=OqvRd0AxTo*a}NK<^>!5sGNRM&wsxEhH};4dOq@JHuxefWm*wSV@kmCxnOe>iUi>t_nz8+iW-)9(D}@5Jk&|3_|oUAgib&QCGk{r$Dv zT$lHKm~rK}{CxYK7yjO4IpN#%MbQk)%?WOpD647w!ij8esfV- z?cF^e{=AFIjj!!_fh{g92W`;vm%nsDIbh?Sum9xv<@m#Te&mPemF+*#Ykp?k^UCsn z?fH>O{cbq0Z+D|(KU5z5UC*oO9FNx>yqf!P`j#Iq4_)|D^U#|P)BpL=kB&F({=fUQ zvdpiY>ty`xtxqjyO!n7%=~?eA+iukJyS{ZwdHJnt_&)sOX{VHR^gck{g*Kd1uGM-l z_>DWfqwKJM&)-|&#Il=y-%|e2;%_Pcc~`IVSUswI@8+IQx$?;J%UON9GynFc^1*9+ zKI}7ZD&HBc<+^L$b5wcSY3rJYYaYVr&yVXIvgU#Q|JUlTD%<|6zsAokxP7_gN9*`{ z|JrR=>gGKku*U0=Ey_lk%Ruvo&)KZpzh}=o zUbR6vVdY-uwAt&Ik00Fgic73lcKu<`2d(?^a>*8bA5Ok{-Ezq{d%jn5@M|r#p*4qV zX~MKMKdzt2S{nMl&*v8}muYPkJo9ghmC>2&n@_)M(Q@5m>zNO{V3Bg;={;}yif5Ha zH|hB`KVP`K@!v0Z%#A-@pj`Chp5K4=)5~|Yz7EZu@A>2C`h)uTkKFa(=$cD={>1wC zk9K-m-_}=Fxp(x6xAuJA&woE!>EWJ#_KLel=We!%b%txS!sySB>$0*&i~g@S>*J%F z*4WtB__8m2Y_#aT{dimOj~^L5Uu(&TdH+@CjgGsme?~8v{lU>0r}q5B>F17?*`nt= zKl$#_1zP(@{JqPbK6>HP`|`y$+<$cRjy*r;S9^@Uds@#MF0||D?Av>O+jcvRcA4F` z^~I;{Fk1Awo)>y>tI?ASO;~fd_Ag9Z^W%EIto@_^OPsLp#HwrdW9+vxcA0pa)|*j& z&vDyMtUbHuA8xqG#M~eB_hf~+t4$nwWX~7xz0|}9R_*z=PyAr!eK+;@bIwMm%_+|Og_GU zfB%PTO2hPXeq2YY*RRjOrT-hf^cCaFzT1!g?_Rb2_H7BjdRn^leT4<&)!|?K0EjLGPK)MaB33F#Vq& z*C*@q%V+h{e|cZ_z~CRR^ZW5jKG)xq1uy^o_|`>xKJw0c#@C$QzqkDQo%fADxpL3% z{lo*~`h))c{E8p^X?(@*JyN)BdyI>5D8}-+F(~|N6l*>nf}C zF-PpPNWJLTp4a{KqV=+0wYu9ZS|}&yV{lvbTc%%loQ$V6eQeiU$VE`>J?gu)ME|2L{Xg zs(4_qyswG}2Fv@Zcwn%+uZjl-%loQ$V6eQeiU$VE`>J?gu)ME|2L{Xgs(4_qyswG} z1`qe_gejjN_vvKM4*i$+Rq?=Jd0!O|43_s*@xWktUlk7wmiJZhz+ib_6%P!S_f_%0 zV0m8^4-A&~Rq?=Jd0!O|43_s*@xWktUlk7wmiJZhz+ib_6%Py^?ga}|K0ogN%3d(~ zFYl}3fx+^=Djpat@2ld0!ScQ;9vCd|tKxyd^1dn_7%cCr;(@{PzA7FVEbprxAP)?d z_f_%0V0m8^4-A&~Rq?=Jd0!O|43_s*@xb8W9>Xx@^W(lk&EHl$F#0d=tKxyd^1dn_ z7%cCr;(@{PzA7FVEbpu0fx+^=Djpat@2ld0!ScQ;9vCd|tKxyd^1dn_7%cCr;(@{P zzA7FVEbpu0fx+^=Djpa-+`Ag4e16=on!T&^U*1>61B2y#RXi|Q-dDu~gXMiyJTO?^ zSH%N^<$YB=Fj(GK#RG%oeN{X#Sl(B~1B2y#RXi|Q-dDu~gXMiyJTO?^SH%N^<$YB= zFnG8pI!yWexDPseqUpc9uZjl-%loQ$V6eQeiU$VE`>J?gu)ME|2L{Xgs(4_qyswG} z2Fv@Zcwn%+uMQ6kmiN`+fx+^=Iy^8~-dBeQ2Fv^E@W5bsUmYG8Jlty^rhI<$ZN{V6eQe4i5~L_toKn!ScR3 zJTO?^SBD1%%lqo^z+ib_9Ud4g@2kTDgXMj7cwq4G42Lk~^W(VhQo|d0!nK7%cCr!vllmeRX(Xu)MDh4-A&~)!~7`^1eDe zFj(GKhX)1^&zuQUK0lr_lQU=Nzr3#w4-A&~)!~7`^1eDeFj(GKhX)4B`|9w(V0m91 z9vCd|tHT3><$ZN{V6eQe4i5~L_toKn!ScR3dthRDUmYG8hQo|d0!nK7%cCr!vllmeRX(Xu)MDh4-6ijkrk$VemoZ| zXJpZTd0!nK7%cCr!vllmeRX(Xu)MDh4-A&~)!~7`^1eDeFj(GKhX)4B`|9w(V0m91 z9vCd|tHT3><$ZN{V6eQe4iC)y&2>9GFj(GKhX)1^&t3~tK0ltfru_?@=5T#o^1eDe zFs?=3m&V~@W_e#79vJ2FzB)WGSl(BM2L{Xg>hQo|d0!nK7%cCr!vllmeRX(Xu)MDh z4-A&~)!~7`^1eDeFj(GKhX)4B`|9w(;Nh8mVan&nbNq6qAN`m2)!~7`^1eDeFj(GK zhX)4B`|9w(V0m919vCd|tHT3><$ZN{V6eQe4i5~L_toKn!ScR3JTO?^SBD1%%lqo^ zz+ib_9Ud4g@2kTDgNJ8DhAE#P&xg!ek@R2QSGR;bFj(GKhX)4B`|9w(V0m919vCd| ztHT3><$ZN{V6eQe4i5~L_toKn!ScR3JTO?^SBD1%%lqo^z+ib_9Ud4g@2kTDgXMj7 zcwq4G4AL;=^W(XrIfIn`%lqo^z+ib_9Uhpk>-G&hJTO?^SBD1%%lqo^z+ib_9Ud4g z@2kTDgXMj7cwjDHV1o`143_uR;eo;OzB)WGSl(BM2j-X!Htg`gV0m919vIx-Grb2b zOu6=d&3EV7w$CqLm-c^kcwk(Mysr)q43_uR;eo;OzB)WGSl(BM2L{Xg>hQo|d0!nK z7%cCr!vllmeRX(Xu)MDh4-A&~)!~7`^1eDeFj(GKhX)4B`|2*02L`wA48H$i%C-Ni z!vo`c>HKm|a{K<~>yr1?;el~2^1eDeF!Qh0?eM^0d0!nK7%cCr!vllmeRX(Xu)MDh z4-A&~)!~7`^1eDeFj(GKhX)4B`|9w(V0m919vCd|tHT3><$ZN{U~v1+?E4(1e11HC zyZwIgb;<$ZN{V6eQe4i5~L_toKn!RfVz!?A9cRyd8 z>)w99`?} z<$ZN{V6eQe4i5~L_toKn!ScR3JTO?^SBD1%%lqo^z~DA#;`hQo|d0!nK7%cCr!vllmeRX(XaGNvq{SQ+ z<$ZN{V6eQe4i5~L_toKn!ScR3JTO?^SBD1%%lqo^z+ib_9Ud4g@2kTDgXMj7cwn%+ zuMQ6kmiN`+fx+^=Iy^AA&6#`8ewgz4F~3RkFMM6{zB)WGu0`HghX)4B`|9w(V0m91 z9vCd|tHT3><$ZN{V6eQe4i5~L_toKn!ScR3JTO?^SBD1%%lqo^z+ib_9Ud4g@2kTD zgXMj7cwlhzjC}vYl+TZObDDqG(SLbg9Ud4g@2kTDgXMj7cwn%+uMQ6kmiN`+fx+^= zIy^8~-dBeQ2Fv^E@W5bsUlk7wmiJZhz+ib_6%P!S_f_%09KX%KDjpat@2kTDgPUjS z`yZx!e$2J?gu)ME|2L{Xgs(4_qyswG}2Fv@Zcwn%+uZjl-%loQ$U~pSA;QJq@e16RH)z)wL zy5xOTJTR_B-dDu~gXMiyJTO?^SH%N^<$YB=Fj(GK#RG%oeN{X#Sl(B~1B2y#RXi|Q z-dDu~gXMiyJTO?^SH%N^<$YB=Fj(GK#RG%eni=2!Fy-3+Rq??1{yD$ok8A6f`fK0# zx{3$JwaELbcwn%+uZjl-%loQ$V6eQeiU$VE`>J?gu)ME|2L{Xgs(4_qyswG}2Fv@Z zcwn%+uZjl-%loQ$V6eQeiU$VE`>J?ga9cCx`y8fxe#}eQ*6;bcJ?gu)MFT{aJ?gu)ME|2L{Xgs(4_q zyswG}2Fv@h2L{XgvIhps`?3cH%loni2Fv@h2L{XgvIhpYJtMyVVan&nyw7d_j_;4W zFMD8Ii@Yy;V6eO|dtk7%HC!~^46v zd0&%wV6eQeNjxxE-q$1^7%cDWT0AgV-q*EwV6eQenRsBZysrs7Fj(H#1RfYH?`r}N z43_sbfd>Z5`FI(p0BRnv^f6gy?>h<~^;epYAd0!(uFj(H#2oDUF z_chY~FSER_5gr)j^1eoRV6eQe5gr&U?`wny2Fv>z;eo;OzDC;rWtR6f!ULmR-q#2Z z43_sb!UKcleT}sL%Pj9}ga<}B>jm(=xX)qAwg0Q&fl;pf6os6QFlTL&(-BsFib76D zn6ox@=B8QsDGE6qDOY}qLQY3m`6&uH9bx6C7?INvR(^^RIUQl;rx=mb5mtVR5jh=U z<);{t(-BsFiV-;-VSQ$i3*aeC|K)v+@W5bsUn4v)Sl-tN4-A&~HNpdf<$aCtz+ib_ zBRnuz-q#2Z43_sb!UKcleHA<~Sl(B`1B2y#6+AFl-dDi`gXMh{JTO?^SHS~=+n#av zKTNs2uYw20H7f5(!2^Ri!*y5X3Wb&Tq>w8VR^F3Bu25KcPm0cRHFJim&T=&??@1w7 zC^5==QpgnwEAL4mS17E!Cxu+0FlV@uD->4VlR~agm@{0-6$Pp6QB7FIr; zLJnG3`E&|7Xkq2kDdeDql~1RTgBDgkok9*;Sow4cIcQ%H@3(JTR_{ zGpF&uVC88lW@dX|wV)6>=L>t~^bJ+{Uo-G!=3i!^+cC$ZZTOPg5bcG0d6M zT(J7*?L9LT+PNd728jjbY_!D&#hX+nFs-VfxS6hj?HxXCLB$!JK`F2L^NY zAs!ga*@t*wFlQg)fx(=8hzAC9_8}e^%-M%{U@&JN;(@{Pz6u@~%-M%{U@&JN;(@`O zeTWAJw=;9x|1jm+|5fn7xJKpwD&)+DIm=vUnwvSxTxXh_Im?`!*~D;`xz02v&_kv4Re;c&NMf3mbuO}H*=ObIkSo3EOT;Z!<=PK&TN>o%*mMzw=;{L!t|fB z5AncY&OXEggE{*U4-Dq)Lp(5;vk&pWV9q|o1A{sH5DyII>_a>-n6nS@z+lck!~=sl z`w$Nd=Ilc}FqpFs@xWltKEwlq+nG`Bf0%OZ|0;N3Tq9@X>#Te;XXKNMopR2|Cl@=+ z8TsU5hdCpkT_a>-Sl(B`1A{sH5DyII>_a>-n6nS@z+lck!~=sl`w$Nd zmiJZgz+lck!~=sl`w$Nd=Ilc}FqpFs@xWktUj+{gX1@r&7uOP|T>HNY9vJ21UQiAO zGr1R(gTYMh1?6BclY2oq7|i5eP!0w&xfhg!!A$N2_a>-n6nS@z+lck!~=sl`w$Nd=Ilc}FqpFs@xWltKEwlqIr|U~4Cd@ZJTSPO8R-6p zDcAn5S$JUFe{y;#w}+XW9?I=uCZ~sTdzi`Tq1+y3a(bNk_nyh=q1+xWC#Q#Udzi`T zq1+yBmz*BT?O`UThjM$E$?2io9%gcSD7S~1oF2;UVQyzOK85K&XCLB$!JK`F2L^NY zAs!ga*@t*wu)ME=2L^NYAs!ga*@t*wFlQg)fx(=8hzAC9_8}e^%-M%{U@&JN;(@`O zeW?9kX3jpu1Eaj1ndy5Hrd<2KX5oQx|H&1joH1r{#VBWtnOrf-8Dl0_jB>`9$rYoV zF=lebC})hBTrtWSVkg+6{DOnW^%`i^ z;`<+_|D1h@2L^NYAs!ga*@t*wFlQg)fx(=8hzAC9_8}e^%-M%{U@&JN;(@`OeTWAJ zbM_$~7|hv+cwjJRAL4<*oPCG~26Ofy9vIAiS$r?Q&ori7`@d%4fl*ElBIP17lY>aP zh|J_5QZ6DhIf#^t$V?6*aPh|J_5QZ6DhIf#^t$V?6* z zDJQoT9vJ21w!#C0$!(<^S7vfsDaTb`SGlc}^{t(4=+Ol~XXxH7jhtDnO3pR*6O|I63N*@t*wl*{{? zg$D+6_8}e^%-M%{U@&JN;(@`OeTWAJ%ln#z2L^NYAs!ga*@t*wFlQg)fx(=8hzAC9 z_8}e^%-M%{U~oG#-2D$zuKi!L@W8m|_a>-n6nS@z+lck z!~=sl`w$Nd=Ilc}FqpFs@xWktU$gMQV9q|o1A{sH5DyII>_a>-n6nS@z+lat%)9DdmFv+=jz{HsG?U{|xgO1{FSP!wH=ebVx#jG53e$hiKEwlqIr|U~ z4Cd@Z?f)`!_8}e^<(z$}{a+C~3FqpFs@xWls9nQk{;y#Bd*Z!|rcwm&1J5)JD&EyVM4pB3?LzP3+Ozu$S z5H*uKR5?V=ZEi1zWy9g6QoKQ)hQrvIFMhzAC9_8}e^%-M%{U@&JN;(@`OeTWAJbM_$~7|hv+ zcwjJRAL4<*oPCG~26Ofy9vIBohj?HxXCLB$!JK`F2L^NYAs!g4`SMx#Ui3dqx%Pj} z!ULn6oV3bKYbGbHa?_g0NvqtnW^&RhH?5hRw8~9uCMT_O)0)XitK76^a?&a{t(ly( z%1vt~C#`bRn#oD4+_YwL(keHt`9$TURc>0d_Uz2U_oAO+`p?;icwjJRAL4<*oPCG~ z26Ofy9vIBohj?HxXCLB$!JK`F2L^NYAs!ga*@t*wFlQg)fx(=8hzAC9_8}e^%-M%{ zU@&JN;(@{1Gc^m}i~ffx*Z!|rcwm&1>sUFD&Ez^(&SNvVj+OJ+Os-?)JT{Z-SUHc) zsUFD&Ez^(&f{w-C)crZ9#6vLI#$kOGr5kH^Vm$TW92+Hlj~SHkIk*m zPhtAc*@sKW1A{sH5DyII>_a>-n6nS@z+lck!~=sl`w$Nd=Ilc}Fj(H#EIcrnvk&pW zV0mA&@W5csKEwlqIr|U~4Cd@ZJTREE5And@HfBa#dzf;0U$gMQC?|(D9vDmxZROH7 zlS5m%w9VwuRxWKbIkc5a+e{8^<)Ub9bO`p?;icwjJRAL4=ex^(s-9vIBohj?HxXCLB$!JK`F2L^NY zAs!ga*@t*wF4x(IcwjJRAL4<*oPCG~26Ofy9++cv_8}e^%-M%{U@&>jj#}!}^5JvW z>0Z0^Mx!g9e~Nj{oxd{r>aNF{m5Z!AxzK^;Z_HV}?0e&OX8zB=smtGqgQ-V-7(H}h z+96-tpnN=tH#eP1dDAzycFnCn=GISh>%X~OSIWogN8-oopIJIp?U|)t)t;IE^KbgV z--&DetZL8wL{IIRbzSw-7i@hQF|B+wh&MN#LV43Sw|32~KW5s={ihx7BXx(*D}2MB z)|h&BaJwf3ZuiRE?xDHeTXVbT<~%#<(kAz`*Xf_#pnMFscyrUKlsA2IYuDWRW6rZ9 zKF?`N*3{&?b}zu(vV&TEz%eg3)on18g^ zt46z?vZwi@kH2H|<#HTv{u zYxC2;@R!kQAD(6Y{jm#{*X^>AdCku}r)+oZ+UD0B@PcyAvsN>g3tv=Tw!{kN^>%(~ zx%@-VGe2_ddgY!A7cpP)%!%^0L;gMDTAux{&CBPnmxnFhZs%>wIj_6Py!3xwReo5; z=BuB+OZoiimzw|n+SiqZwmaLr^<%r26<>Og`P|>^Rc>2wee)4Z?pv1L{%Pig&f2dW zwB7j==&w9`|MIeje>`)**TOAk5^i$ACCi@9B+xm~-t-IGdN z?OvJNJv6s_Yi{@4+@6KGJtK2_cINg>&Fxv6+ZZsnv0-jw#@xn|xs5S%8++z9CR0AC zF`4*DjY+d~#u}4m>5nxg&1!e7F=eH-X;%No8k1&S*H~lHtm_?XOqz8c zs>Y;Q_or%1nswi*#-v&IvuaG5b)T!oq*?dBYD}8-T&l)oo>$eFH0wE5jY+efZ`GJI z>$z8rNwda7)tEGEoK%fTv&K)=m^5o#RgFor##_~x^mx;ltQwOZhmAcxTa3qTt2=6A z5>0b!%iQ{4ZhbSiKAYRMm^CK3MsvG%bGs*{jY;m6x!pr^ySL_c&&};wnAY5VNRd#}H@wD)9xZ-M{! zv+w`^&ptly_I>8s-92Y6KU(Y0dz+VA{ru5h-+hhw^1bdF?Xc!n=9TVTqRhB-Ei?b; z-_+&r#KF{~K8zl^Fzx7j#*9Jvco1)HI_9QdiD~VcTYt>0pXSzobKWzltMak>k@&It zXO_-b?U|)t)t;IE^Ka_%cj8(sB-SqFDdEHUozRTr%?En5=&^^g_PVP^>bHe$~IVk`C^!I|sjGyUe z&%b-(mfc@uKIX;yjo$y*a^^*Ey>!&wy}0?|i*Fhox8Rc=Km4D6GY0rOaWM6$52J@J zOgnkqwerb9{1|RJ=B96M?V4MED)FtK=GK2RV^Zy{M$U&PI-$T4|L2;-`v_YxBgV( zTR+XM|K>b9VpPtUOgv-KOn>P&G2BbqgY|#Lq&Z`Wa_$H1!Q4yQgEJ-v!#4xBi%0Kh3TG=5}2v_iuCRw%@!imyUm%H+|2m z!1-+s=eIeW_enVKlW^WA2j#x@{5GdNzs=$NHivaxzD~IHr@*bBW?h%(RVW`muQ2nC zxn4N;0nYt_bKl_HPdN7(&i#kma~#9%Ihykv2j!ku%yS>;6u9Y|Gkz#<{c(Bgr#a)0 znBg_%K2V!-_G|IJ(%-~Vo#b#2YO3Y>WrIP)rS=2hU#tH7C8fitfHXI=%)yb7Fo6*%)MaOPFu z%&WkeSAjFH0%u+Y&b$hoc@;SGDsbji;LNMQnOA``uL5UY1WrIP)rS=2hU#tHAAE z`8_A|DwJnl1WrIP)rS=2hU~`y|X~ z51)hijA);go=buAnF8mt2F_;?+&<&1lg}*5|M$DfSNy#tpOx*t`98w=Y=zrr-2dzE zD%aoj+Vc2Cv;7(jGuQX@FK$;ZSZK2`e94bqRjxU+=dJJBsod6W;qt^V9#Re`9^QYm zwaQNyzT5g?G`~DvwcJsEYn`LFc}dytk)C(_;Tq-StM77oV$exBoOt;8>-~Q8#9=S; zdt(^=FU|Sx=*AzdTHym$x?!~a<}=KnUHNCD&#t(N`7dv{b@baey~zCP8-6u9_vJmO zF8V2l6AwoRjz0XyXYDk4;;WmwKVkZ?%e706?z^P8t;^rI;^;N2_Pp?{HAjoTu;;%$ zw()4&GkX5uj$4oB9^B7qr!M*_hZ7G+2aZ0hx?|cMGW}8C#`F`G<~VIhbDTa%bDX|O zbDTb>ZfncsaN^t&xxnq zl*5UKqXTb#z_aSZi@m&{|GSG9sb6_~UGrCOTeQCDD?PvI8PBdi+pOnhmtDLbckw!o zNnLbO4ksRt4jg^>PaB>wesqCdt#khQXN@1&yXUi?_nz@eXZHNq``Y|f!IPq|F;ON78|NPWi+w|Z6SDE4%$k5Ys)&Yu6LCCpz9sw{^)u~xo^7O zQSPVi)hPElb zlznf1uKDQ8_9?SZUc{VuUN0$!6AwoRzVnH_%BBadtZ0ukF5T*=nJ_t#{tEYk9*SJx3G$#8WrraN^OP<*z^7$(*)mH#%sh98NqO9eCxY52sx?I@2|uea;4Dts_tM zI0+LoFGlBEZ&|;*d+W0tA0~dAx$Bj!uKbMqf6UX?E4#eq67%_=e|dS}IUhG4dgIH> zM?ZC*dCf!CE6eQmKJ&bErni-N%A*5EA5OdQ4qsTmEc@8!`aZmN{j&B4t~4L_%=OEs zW?W$&_Brv?O*x!+`23~=|K?4blxO|?>(<%!lN*)gM^~GVSaiek#1>yNN0a-Lcw#8QE%p-dqY9@Zz7MyrEI`Ha?Zc}bt<)_wM`Hb0R(Kr3by!3Cj zE|1*$19LR#PvWVYayapDbl@Y8nO#=6_crV7{JYuZj&pute%Z>~ltW(lbMv_`+ol|G z;m^#`r>)dQC*^SB;po88hi_SStFqQMcUki{4{lZd`mSG_=YDnTvi$g$=IGN_;;EZ* zIPq|F;E7LfURHYF1J=3aA=I!_dD;H zRStUVpR9Sr{hO9emj9#q`r9@ucO3VSIr>~n>JIw}CmxOt9DR6?7jIlH`R~51UC-IL zeCr=QzyI-#%K^tc?6!vAHxf_Xl*5UKqXW0!&VF5NxzxI4#?tqi-+#^eW%R%U=AmZd zxvrGMiHD;Dx8K^x|U#^W9jVPfXR==}4= zOP2HMla3D)zw}EME04b6+5Ua>i?=UU7TsVG^9kELyL^Ayh0VV{dGYeDl@~C7V3p^V zJNAB>d0slx+e$p;(Sf56r(O8XTQ63=cg=IG|BJO2E4w|qxOtHoi?j#nRocD1AH*fUo=a#n|zMMIl=qH}KDTfmeM+ZJ*wPniQ-&(oA%l&fca@qbp z&wkI+<;n$m9%?3j*cP04I6CnAKetTT^f@oK{_{VxOgZ*~8RnTME>reha}{$m=|keF zn{qhuaCG2gG@0w{-c+;V&`oxc@TcU0e6-expxYsf$j^ z;l#tyfuj$9?#D}%2j9Pz^$&gaQe~6(t!X}R>*tk2PkX63`m~jJ>ZTk{JRBW(_}la1 zJ)To;xU^rx{JxJox7>Zv%d8(w^b=3rl*5UKqXX}`>4N2v@2_K>wLZ8|S!B<3&38Sv zaCy<(o`=7A6Hncg!-u8~tv*`Gq(J5#3ZQZcxeWS~+ z?m3$1C!V?~hZ7G+2X1r4)^GE`<~BcUZu7?GHlJ)xTeKS;G*b>I9*zzieK_sH(V4D! z=#1+}?>VS{ZH9@N7o&6YRgumbS<)iCfIorI}n?E%=ZQm`-!#*UQx+#Yf z4@U<+cjo6t8yw#6MTf!-ZTk{JRBYP9}gcs`qtsJ$iJ}4*hH7 ztiK;W`t$NT_;oSVO#HAdIPq|F;BVcr+vq2cZ)TmX_uqH4$rt+9+M@q;@MwdNY~}K3 z(x1drH|22R;po84`?JpHzPZcjSI_U;dgea6jy^r7=V+pzciUV%8~b~^=F+!MJae~A zT|O_J>1`#R^60?Phtn>6-5N(t{Qb6VtiQnH$4tC$y`J|y{v8u5f2bd~!#*dTx+#Yf z4@U>S@4hW3j`(9g&QCaMhlw5j`;~6%qnqtD@ww&t*FrS8KZ&Pq%HhPr(Sgr;#%N-R zi9M|O)7v(hc;;>iH~jH@Ap~ep&1jOU$fum_{aCIJMo*p?q&UG z(x1drH|22R;po6a-|a=~eRJj=&*=ABuJgpbGjF_LKkIL~=0Xz>JhSKM(^l%DlX5um zaCG44xA@6im*OX*ulQ@zuHvsvf8s^9Yjj<7Qr`3(4@U=%KCF8(ndhZ@GMRg*dor1O zt81C+TjHskayapDbYMN}NyZ!f)H9vT7|=7F%-Dz~F^Q*c%HhPr(SbE4C-ZvIn4HWQ z)|i~k*dA&oe%KbAcsM$+UQ?5Kz3VkKnb)9RQ$}#N?|anMcdBu|gXuffIN!~pNlfCY zn{qhuaCBgOCmiSds=gDB^Bq#(3CHb`EIZ8@Lr>We&Ve^Si6#V%A*78H^n%= zgY=tXoZle&O)<`IlW3x!_+j7R#KX~n_4{a?-*NhVG|ulS{XQD!cb0x1jr02}`m~k0 z=%gG@JRBW3`mlZjj`RCezX8Yj&8XjiqZ`d)vuc@owu;cvZ z)o<8wehWvFn8Z^z<#6KR=)n37KF<7reuIzmn_a)b$N4Qk)J*)aEjaOTbYRUPj5EKX zIfQZM95jb8&Rj$^=}+RRn{qhuaCBhJfs8YsqdAaq=1epPGR|B|G|^8ybyE%}9*z#I zIiE4}NYvHb&Ny>Hnj;!#j!1JmpLhvv2}(cIQ6n&+i6y{*Jk9vwLPaN316 zhdIvts^&1qne)^f<~Vbq!#*dTx+#Yf4@U>q9PBvr!h5H((g zJPWVML_hJ=O*x!+I6AOAlp5bh9!ibpA`hj;i-{)siKlML;l#tyf#nC)_*U|RYWySl zK{dXT{Gb}YDf+aPy6B`FPCOhPIQpz@WCeN$JJBvPTC7!w|hZ7G+2bPyt z@e`>l&#uPflV?}s{Y8_Q#8WrraN^dMQm@xJ9{*LdRcvTM9@dD%4{dfK9HbkIz>+imf1bl~X2X%~*pbWQpGb+8`5 zOiap$jE>e7RMt5RnHa5As99g3wF)(B8?;uTX3c}vD%7ln&{~C>H4@Pr>J0Va#KX~n zqYtNDSZg*|SMU3;H5)Z+JhWz`X6?tY&xxmQ%HhPr(Sfz*g!TE>Z|m*NZ5_Tjnp{`n zshe^*@o;ott(mE;=b^6F%+##0(VCf>wKvfuCh^owIh=SnI$G?{I1#W^G~gX)E#6O*x!+I6AP_I#$+OQdeslYt}$&O=Hd4$Y>IicLNQu{CRGwI;S^ZEZBsPds%~4ksRt4y-l6m376`)mq=0wZU5J zTeD_ZYkh0h5^Jq*%^KshMcwG2nQ}PsaCG44!)X_e&U8(!i>`z9(q>{(K4f&X?z*xL ze8|LTEqBfObFJmBS^KTE+%;>$wU)bPt+>{5*Q_Cr=1^y-4<{au4jg?r?K)<(Ma_D9 zt!b}W1FtphHEZLCebyRy$5S`uaN^{fJ}*CCt;w%h!>={@HEa8$$#o^3x+#Yf z4@U=Xd%>*V_J5h%zA$q%(N8>eQw}E{jt;Cn5jFcYv?row4~6zb)azJ(f*X0{Vdv_QnSxR`%`N6 zzeJz5QWu?+!-0bpI=|ES?Xr%yy39j>zB{(dF{J*uQO-=+~v_kKk?K}Ih=SnI`Co- zzN)@%x$Asx!0T_`sorwX_sy@m{k3(0!+vTWY9@Zz7MyrEI`9jQ*rs0o-xpcu#G|&W z%RYF8xw~Ndy2PBT&C#SkiKlML;l#tyfw#PM>-x%@&b7{?ubEvB`s{h;<$pQ5F1gA1 z=4hgycK7Pgz&F}ic=JmXXmbLy#pWdQgbLV#E zI~LojK6jbp%xQ~uql0G3;l#tyfuj$nT{t?^H4mM!c|Gy@Yrlk;FfsGufsW7TY??mX zr1fo*x~*^K);DwOo4NJPb?2osy{*Jk9vwLPaN332Gjdz)8JXKNG7tNlcc1%Yzt02938m5M_H%6N15AulsTI8A@S5rIh=SnI&gcx9aFcx-}cGsSJS&lGd}Ofg5Fwh~X>l*5UKqXW0kMC-KAM05L0 zG)EKt#8WrraN^k_+&Z+`eN!MUy@xp1Q-f5>I(_;P#usI_SE0iHD;Dx8Ekd|7n-<=uFpazq1@4CT3oYPWv6__%QM9x1syrejA$GZ$oqY zZD?-44bAh?nci07DUS{ueK_sH?Kg7YhyFLUx&1~q5Br>W>ZTk{JluY3``X)YeCxE| z_~!N--yBWuPvVDtgA)%&2X1p0)@gGT<~B!Rjwbqvr*6vO#KX~n+Z>CprOmOJ+Z>B| zsG0a-TX5px=)i4`$U1F~$lT_L%+aJjiKlML;l#tyf!lnSb=rKFxy^T(+kBTf`m~k0 z=%gG@JRBW3`f!`;vu2yqGq*WCbM$E|@zhN@oOn1oaGR5~j`piEhiPtel6`qUuV_v@ zb%$*w-sMdPZu6_I+vZozZGP3<=2xGh&$XoPu%B?^;po88hueIzHQRYF=5`K@Ir_Af zcW>ZTk{y!CtUvck;+wNCRu&CLTfN0WP!c<8G(md>Q;;EZ*IPq|F z;I_8YI&E#IxvlLqN0a-LcHJf zHT>r2`?^{@byE%}9*z#&_9j@T?LjcNJqYHukHDOG>ZTk{JRBXk?V;#jcm19VbK65< z9%?3@Ye_krc)0DwaDUn!5bLx(Am+9Q#2iiflX!Ge4ksRt4&3&zSf}k_F}FP|=4hgy zctt?woy={olX+e` z)7wfs<+IPV>-<}5wsULE?L1p^^xamAcinq^F0P+l;wg_#i{U)mXmW0C+T#4%UVqRBwdMF> z-zT4Q**xr9;;EZ*IPq|FV2xGwYgob=#E6n=Lpt;lrW{T@935ES893j=I{MDQnHy$(XW%Rjb2RBs z;;EZ*IPq|FV14J|d=l&EI}c}unA;g3=4hgycGH zI~!-An1`B)AGQT29*z#I@0^^=Z5@5*9343Nuzn+Ou8uYJ8-cTK%=(SM88~Krx91FVbKM`p#4rlm0MU!huJava{C7$x=!1}$$c}LdK?={XHGVAvm z=MkCpdyR97%+aT<)E)K{PCOhPIQp=DlX8xeHT9d6vz5&HP0E=|=IGN_;;EZ*IPq|F zVExwS94hPRH#KKNnf05RGo#GWL_hJ=O*x!+I6AQA1UN^_uRF~NaJH3Ma{`=sWgcoK ze%KbAcsM$+<}^45%sQIW;A}3l<}^67%N$MmlX&W;98NqO9awWRoO@;+&B<`Km|1f& zoH=HWCi;n|Zpz`r!_k2?2gP}7*3n!OXQr7o*Th+BX3aHm#+q4kO`N@EPFu7a9W+x8 zCmxOt9DO+L!qJ(osd+ihk@I*66EiPHM{|8sd04{4YtE2!|J;Ag8FCh1e~tYaeP+!u zj*{CY@o1(T)*K^e`nf;Rpq{6G01tkd!}m|GqPbIb2wjy`Rr zE;=cP6AwoRjy^1pgY!bIDUX9QJk9brINQ@4ecDPqbyE%}9*zzykA`zlts{?yGf2(y zXgHhH98L5SPu-NmiHD;D%WvWwSL?`c;yhKe{3gy>HOp_}{8e-GX)ATnNjaQ&I683j zVR>qtPiswiYMdEsmZw&(`w;P0s8!%hTj6U-M8i@x!*@#KX~n<;ilsv32Cha^|pEo-Ah( zo1;m85>MTf!-?5a&CiZ(0+=ndfdxYeF~+-8}4b;;EZ*IPq|FV6AoG{CVqWO$%qjo3*Bev*OKK z12dJ2E%DS%Ih=SnI9=qH}K zDTfmeM+erLPx7bud1=ijIZe!3^GU7~^H4MK!?xhW!_k4YmX-W3*3p_(aTZIhyDvp1LWA6AwoR)*55->{v%@iOH2? z)>>k6==5#%xpmB1OH9rkbK0Wa=%AT$IPtL7Bp2$+iL z=Edk}T{n4=93LiLYsksR<7q49aN^qSiOX{MN zayapDbl~X2+9N|gJ8No>3_0e^+9N~mIdk-BEAiA#Ih=SnIY|f!So@nC zZ*DrU_Cr}8)}E}Q{i@d2o~)w%s%GuUD%!7Vjy`QAp1LWA6AwoR)?Txs{i@c{p0c9- zs%GseE84GWjwbqvr*6vO#KX~nwI{A|gox7Kg(x8~>*pStLz98Nsk-v51{ zqfa@x=@-3qM)~l$>vW$z|L)0Kc7Kuim>2Iie*a_3nHRnF(s6h9;^v1hzG-~if=`Z! z*Z;@*w^@I$iZiQTReiJcs&praS3C977kp<1+{!267C(lYj=AZZTf64gpGth|r@8gt z+^#F-6SUXjN3;jiU)qDY4%&mcKH7u1ZrX#nAG8N^pJ)%}{%KuEu8VSCZ;Kxdbj(fP z+}bs_{uJW5f7FN3qdoW=%B8v5`WuX4u5q>XziL+bIOUD4*<#GC?o|2Zd+lHLedgNT zJ!dXITINuTx#^gjekG>0Yi|89w|<&i|IJ*l+DrLZ{Yd;+{WD8vtoF>(uWHZC|M@rV z@^|7|Kdag^qo?-Fw4-N#88NMVG>A7h9dpw!#I$zJtv_bk$^EAt?j!MB7vl`hcz`ob z;EW$Q;|k7rgWGs^e=C;j zkD1q*+B5U|<8|8fdH)&1{GZn;%-@NFsYiVnJ+$+IK<>%GPeZ4JyG|(|OeKYNF zoy4^M6u9-%Ogr31%GJ)NzVV#pXYpG6_YZFy{p5?wnQuLL*K)+CmNM&aWv|tqX};4)|3<(4-Ap~TXGTx$x&O5DzHdEt8S$;$*W2RD zK*vlwxo@pqmn)9`%p#t4xGym6a35iw*ZOyT#C=%rU%QM>`M`PR3%~!<(SBcluX+8u zmMt$l^HlR!H{Ytf?MsK4_5Y%OoAvjiIJ4>%)%UeXuSnOdcKm)wyRF>U)#A-frx4Th z&8=N?>yNqh)7<)R=6TT`IAG}nEOO~F!xX6 zaMeNico1)HI+gOKZ*J|HTYt>0pXSzo^Ij{=DR(S?-)O=6-ZO&lUvfqn^61S!aXB&Y zXTJUJsd)IB10QtVzkL3EPvPl0(M(&>i6%O5bi(Ms>09`J>QBmZUBmccAC|pl=ZR01~bI6BicbG^g(VISW9=(^)* z4tc{l8&9S#9DQPPy>R*&rk_KdF#Uw16HTrcj!qaIIDHGF14n1N=CIG~%{n7n3*8S?b^ zhr|!BJxqT_Z+`XE{TcEGbFP`0dl;rIVxk!y>dcFYPkA_+luzgBF|dcFYPkA_+luzgBF|RhTrtYBJpKB@SGcNJOL^Ge8(NB5$$=FB?Jk%fP{6G5N zbcW?mxt2lQp{Coq^WtN<4@3SRuZ6y~_@~66pYma!iQnho+k8I}d%xK+2OW5PJ^3|nbKOUFJGTDr#N!U}>wwcM!dI%~aC>yu~CDc5&%C+=GE z^t!;D6UsZkHg{sFjn1rx9CUQK`b%>sj(GH}df_97m!C-UquZZdkNWEV<+neYJMph~ zzNa4Xz1NkQzn(ks^L5YRUisc~uegu7hx|MDnf}pF^|#VL`lCu`RR4XD^9Hoesk``2X{ZU-njnh^+5G==00=kg1ekqmsdak{=yUL zhoANCdYSsU{*!O5>+Y%ksr)0S9$tU{p7+!zf2?cVYXAE8_0Fjy_45Viyv}1F<6#Ls zKc3^8PTZruljkS?{Gviw0*yEXTJs7v< zHfDzRxiF5~>#i`4+v~0{jv3Dy*M)J+c-FWsjAO>L#&uyFGoCfB3*(satZ`i!$Bbu< z>%ur@JZoGR#xdhr2 zbzvOC8rOw!3~O8$#<4ytR@JyJjAP0*t_$NB*0?T=V_4(bW30VTK4rZ9Pxq7ZCpSC8 z_myiH@}l*FzCL2Yj1yugBy|2?N3ve}vC1o5+X zIiX(tkF(14;{De@x<0t`*=3IS&g&1aSDo>mvZCr9a_;_hPd$$nHa(+Ee9iAO?iY`rhO>^t&VRQ^`I zFP^0S!3XPo@ssKwJfZi+mCrree4E}E?^pjQ|BT)jcUS-5zaDZ_{ki%F@2L013)DY& z9lbBURQ-eZ()%L)gVkT27v-A~4~#<7`kt#NE-Tx%Sg z8P^)eX2!L~v6*qLact&&M&sDbxYjr}Gp;p`&5Ub}6EowQXOMdZxAzVD>2mHR?u{$>X@aFL@ld_a%?x_P*qC+}@Wwj@$c^$8mdK@;GkqOCHDVeaYjvy)R84 zZ&UYe+Wjo_pJ&c{`Ad&Jy1eMv)yf|?z3*E1$z@+s&K(~(319TY>iXNK%||Y>R=M&& zx0ugcZ{2dqv;JfL>T5PE53Rn$nD~3P9+h>DSl;~STem3J{%MB!%eQYw8|KeGZ>Op9 zPwueWRQv%u?lYzHrr*6`O8*l#A2!u)_t&GQ`t$o0-Zs_GtJgkms{gNl?(s#RhnLWw zmw)Ma%4foq>$)aj;&okSbaY*2^mSck+SPT9h^IfgE;Ieqb(!hEuFKr6%gpsAp8F6T z?oaf&Z)unNnf`E}(@*Yy`p=>o>DTT)rSshL_ny+f<=FkF+THs{Zbm&z7x45SN zE=m87S^03v{k$mGbxlxCyspcPj;_m$zOKtmySgqj{n2%q>8JW{rvJJwbGt4x*PD3m zLv*-5(dWLUUG8W4!+lOax&P@u&xPm3Yb~!YIIk}_uP->SFF3C+IIk}_uP->SFF3C+ zIIk}_uP->SFF3C+IIk}_uP->SFF3C+nAefk9QnHP`bs(DHt~#SIIk}_uP->SFF3C+ zIIk}_uP->SFF3C+IIk}_uP->SFF3C+IIk}_uP->SFPP``zweDlPdz(cgL!svo*kTL z2j|(rd3JD~9h_$e=h?w|c5t2@oM#8;*}-{sFwbuIyuuovHJ@u5w>6(@8qYPKYZ{+5 zpKH3tn$I;|W6kH9uCeBGP1jiSxu$EB&eZ4HRJpEkDqhz(rK4+{($_UkwX18K>W{8* zs-L>Xss8I4^*gNpTvMBr`+bt~!RG}!eosSZ@cBZ!E~nkW=Mnw%XBPd;=NkQ28~I$D zD(89=&wYpv_b2+?x3tUsOnvGy1d>+wHm($ODuF?O&=i2|p z-g}2vS#)jRiiKVjk&cuQLV}V;NwUMDh!994m`D?Y6p`MGRO!7pK>_I37`UAK&}<-tWUd{Ej)+UhAAWXXYyV%C-IN-to>Kk8xlg zj1Ti;+*lXmNj(^6>csd{KYa20Dv5oP>kG{F1?Kt!bA5rizQ9~xV6HDP*B6-U3+(M7 zy1u|%Utq2;FxMBD>kG{F1?Kt!bA5r$`tl#Ib$+s)$2G+BxW@H`805$N2XlRap$F>) z%=HE4`U2a2X$;pF+PS{KTwh?WFEG~^nClD7^#!);%kLNGB)!A_N$*~{&KYgDb4J5 zw#RE_d%RXgT^x@PZ;#i?_IRxf{Wz{6#`a6u9}L4A zaZQJePWeAl?tHmR#-S}kmCu#$kukGdDdmW^y)w4{+;|ge9Ujvg97XnGqLBwN-e;BZ zSudwDa(cCtQOnby-=#u>r%f5!Jk9$3EHrz4(RTC&=XGAK`RL>S>?daZ;@FKj_D|nW zT)*78it~2NAMTm(mwP7W68B6n`v~Tq3Fe*&=AH?*duB=G_iF0(2;045!DjDVFo1g| zVz_65xo3j8XX3NmGttgH6YbFN^wEdwEcoKJ`*8gQ_TqiGE(3dce4clkt#>|L$AP`N zK3v~{Jv~0?1baGtxE=(1{nGn0V6P_Hbss=Gk8y~{`5yD&x(1B=&YXds7_>tV&iBC3 z317g_@6}ND)}6oIJNEhGy@j;($@-Z9s&(>oUX^?S!|+@C3l zy56zd-(R$I91zd(K^~49@^d^hc%|J-Bv5J9OgO4GjIxG0xwPdzFmGI4}>!hxsvXtc&ra9*i?}V*GLKhFb6i>kI1+ zV~ArM)?Hw9oR7!2o)fD3c#I3E>GSazSA0lCACGY}yNCIBj63Ul-p6BH=R0M6IL0A= z@r*J)9^;103j4vb?QV|a|iXL*c6P8{RBnE9y1V;nT_7zb@U#z8ZWap()y8a|6Y zqQB_7U3bd=v!DEP_Y>DIcdlYD#a!i{3Fe*&=AH@Wo(blj3Fe*&=AH@0-iZJ4k9#JV zdnTBBCYXCBn0qFednTBBCgwT!OteEkzQ5#mnqWS+gYW5_c0OD6U%oHKcgOa*H9Q0H z-~Qe4-}U96@|@3KjVGQt`0xI%*8T1nOi%v_&mH}pHm5zq(X5Pd#{6~L{|V1{IBO~c zY}Z=GKjnEvJ3s%6HfK$tUDrFt_3zsM3C~1%`gBjj7=!J6&cJhi|J~28V&BDm!vDnY zm(eerqq^teF5~+Yp8NgJIr%^HocvGo^FQvnj{m^#zw|jA-2a4kSYPO)%UpN=bHCSI z3wzh9|G4|TTz7VU>bkS{u{UF1wfC`=?R{)zdmmfb_Dk8`$5yuYv6bz8Y-R5{Gz0f8 zkl)_NR<`%CmF<0OWqTi6+1|%iw)e4>?R{+S8yU{?od1aDlX2dH?;`R1Ce9DY|Ac3f zoo7lhZmJD>{|V2RI%DN?#_%8UjIJ}saPHy%ei`>y`MoplH-f!u=M3C$1bf%ccs@kg zyLQgN{YJEV*UlNZ-w5`uoilL15$s(%XW)J#*t>T2@&qbl9kCtvjT!&*SLS&e#M}Gc zn%~~{R<`%OmF<0RWqaRS_1pX2`kb3rGXwXBkrVB>KMc0_y_M~KZ)JPmTiM?Cj-ejh z9|l7w?rDIb->ac)`=yNjG9KfA`^<>P_~8CC7~_Wf!(faj?pK2`&eVzVr+)9AMh4Cg z5#!a=`@>*+-+MFI-uG6<{d4+d?|W;z*Dt+4jCgzBdkfg>m);)++xy1M9u$% zzd>{K=yf!X{TNI9{eZU~{=5I)Q~iaWf5P7_;%{}~-Jky!`0xHE7ke_|vBv*z_)g(J z>0Y$s9i9_VAODk|d4PAAtM;4${D16s<$rh2&1v^J_u`cKt^l<2odaO^eFC;!-!s5> zFCfPIo)Ygm_OF5`V2jCUFD?qGhG@%|0QyNt0yJIBr87{+@se&+izpx=Fu%Aeowf$`xO zI(hz!2EKFS&+i^#JoO`w8}sLPp)j7~gLpUQ&+leoJjWmLh*_HVNJi!UK~lEWx>#_& zK0#8j=7-9=ItR(Ba%+{xy&fd-rPnB5NC=Xn6+cjJ9T_AoTd!6=`D~E9uzi(s@n6eG z#Ttggj+T*_Ush^+!PRAC;@5_+k18X1uN&U^Mj0tq!Nf0l$%|ROD)!v>4>Me*PP9`e zm^#7K38qdkb%LoAOr2or1XCxNI>D~am63rGwdthxD@R(Od_CXrq#l7%t%cz>Qv>Cx z`zJJJ|C&I#+1~Ko{eklK)^D^u?M$Fl{poAvlpBH4A&cPw4+7<!uZ>wt`};c~sI-3^ zo{cN*AD`}RO6$0xuFI^8cGd;6E|_(}tP5scFzbTdy1y0*lHKhN=s35p6eOK@>{q^$ z6eMMS-KV^zd64YQW;n4+kmSy?SKBLl>!SHDyA6Bm<^2=8)ECT2GV`M@^Mjcm%=}>H z2fO)ibS))qmwv3ZX1`KOW>np-ytzs#>3rAl)v~4JsV_d!_D>3ylD(gNs=P2)DS2_n z4&@73O3BvGb}BFOxY(Ip%9nGNlIUxuFXIZ7lHY&YqwRHqO38?`roZcarDWt5GY-{K zOG%YpW~>rAmy(rFAJD$LOwH&EHG`=cOwC|w22(Sbn!(fzre-iTgQ*!z&ES7Wvpe6W z_Y08UN*>dGova%mx!QiNJSk^@6uxsnoYlNQ#^Rr-n7VLi3UCS=J z^XIigWn}sbhqUhc5oM%G&CiruC6* zrQBvtpv>+wOgU&opmZ!WSb1@~K>4=DK;?A_fpV;1U*+&}f%04S-pYlu2FlKEJ(W9O zC@uG2GhF4<(h_sHm$na`TUsu!>!V!t?b0&#;Q-}VT9%e|y9O!GNGL5~1&8@C-(04C zv{OHr`oYu>rhYK>gQ*`({b1?`Q$Lvc!PF0?ez2=QJ*J3!S7(sUp8`QeUvoJ+^gw41dnA=g{Kk{5qp{J?Gbd?$mSse&x9Roc0&_U1ol?Ge4O5 z!ORb4ez2Rr_oP6-&d=9-Y;~6TI?%7P|8IeQotN{K@#~yizKmbz))&k8b-K*_sLT9d z<_9xBnEAnO{uYe_{JxLx7~rp4d1QcJ&w@n(ex3Jr2l(~ZyA*U}uN{l2@*{HV+P zVCDxiKbZN!ZvJcEmXVvEj@CK0&pUtK@QC5^IfA4`F|&>a6$z4VCC&P(TP8?~JY&{f zbh#iYaL=sGav|Qi&FP^!KV4>i)Mb7!^Mjcm%=}vy{}jG*a6eJm#I-^ctaj zc3MgKVES<7%4JH*>AHp|Y$)MxFIcyPKmPjn#r=8i4=?V|f2Cq^tqaZ61EwA@^?<1d zOg&)g0aFi{dcf2JrXDc$fL%TAzUs2OFSR^TL>gooZ^mJM5qb2vvFZzBkdras%1#XT zI<&ich|6va*9hX>wd}GR!{a96-FfS>8^dER;@#tj%Wh2d*s|h1N2=Gn`3jYl-Anr_ z|9B@z?rj^S{J~d2^6jr9l^bmil90WVl{e1~k~LT6D32T+B(G;(rQFQBE;zAytMZ0U zK~i(vVdZby2FdiSXOu6u3zElH-H5?Da+!M2PCa1i0aFi{dcf2JrXDc$fT;)U>bd)2 zS!w=wvie?mOIf+&OHqDnZ&`V!;mgX6PL`F)wbPVq-6|{d@4uovDtE9%wQi^!Up`p6 z4{W6TPQ73+Ph;ga-Gim@48tqm36?VB4JT|3mh_T_E1wRQ%&F$H?H&e;Ja2OTRxm`) zeQ0WB4-1jXw^KFe?dl=2;9h;5w=T0U=p*|AW?#VU3z&TYvoB!w1yZIjv3zfAQW}cra94bvZ&egi1 znL?#b@hQq1zArC9!K0Mpcb1p5FU>kS{eF3wv)-()_WjH2xgUR9W`;?tyGL}Lx=hXRj+(*L45nr@qYXKkFht^&mf( z`N7N&cJsIWE>y}d%Fubf^F*i=o3}-|@X=7|yI`~OoZX?){=-em@2wA&UB@;m51bn+ zKjbvLZ+NK8ZN5Rfy4g&x)gvo4r*!K@2rT`=o{-MS4f zhRC+f%T&X6yF#QuFT=g(g~<0U43{4eA}ilEoaxmNnRm$W6<>%nKV{m^Mb=`UH zuG4_eLgei*bDyyD+z^@hj=2|Czg377t77iaJuDI8&BH@lm!Cx~eiqEng85mn`&oDY zblIH`k6!lXWxxc+LTVZ+gp1HrhKYw8A1Pfy3oVAVAch* zE|_(}tP5sc@Sp3Z9W{Fz+P6lUJq_`*G7KY6uQ$y1ZpeQ()a-Sr`$t~$JstFH&1Sy8 zgU&0t*6ZAZ{vQgO{lsPT5p}5tb*U3|!K@2rT`=o{Sr_cq#WmolL-SPw?rV*@U>Nti zPLx}q?YIxt>3zevKlY0()b>-}eY3NVEmFoc>C7J&sUDY^A9a}@%=}>H2Qxp|&5wHv z$d7r5`&z7v`(4z7`(V_G`(xCP`)2GHu7A;A5OH_u_JKtT~q`^<8o4eajpdT&8C9g_^vn$b?pU}^?aGnkse)C{I(Fg1gz8BEP!Y6ep?*wuVzd#EHXeMHCYP47CW>zOB& z<9-U2n|X67KYSP}+jBjuoG)vbJTtABa`l{HQn+myF!O_% zAI$tXFOLkGjkcW_~d9gP9-v@8oyK zA=BtkIn@86YB=uQGyL_$LDj|>%v;8Q-59P@w7cW%vKzxSj(B$-y6nbq-Xh)|6PMkX z?T5mp%lnmdkGi)!T$0~0yk%6ljEOeKg|*@d#{En@4Oo(w;n04eEvq5jJs1#x$*TdDSj$g`Nf~ZWX7jKx~I8JZSaWN zz|;n&HZZk;sSQkRU}^(X8<^U_uC@{9!lh)Mc4m!S4wnZ_nk(n{EnHeY*I4=4>=Dv( zN`2)!B_rhAt$5`JRU+hehg!;wnnuXL7iuV%9vC4{rc_mKK0iV>Uaz8@dryR%&Lzqv zE=S1NH6~_S_DET<-+Z=vaHNFRsI4(4YDUUacN28Yx=hXJODn4xOwC|w22(Sbn!(fz zre-iTgQ*!z&0uNfid|E3+`O7z>WcZI}{->ry$*c8V(DqrC zqGU*4vqlmNMalMNX6=-^S6PPKGko$yWhwAdnD)zM)`cF{1+y-gb-}C)W?eArg5A3A z7`p7%{d!fDblF`}wH@0ZCHwOi(|$1qdl6&6ZVdZ^c6YtI?8b0^K)gH8U3O#WJL26n z;<6jluTzAy9@|Fs=k?ZX-Hol4Gm;~uz@}Ep$7@H(w)a{nPkkvuZghKHIcJ>+`7|M2 zIiP-oRIJogd1kW+IV(++vvrS<-rXB1Ump`8{l9OZJbOumd^i0S<%Zrquy{tAa_x%| z^2N1O<>A>P<%xGwb(~$MW_U-exc|5&R0Q-xRwetfxU4~muS_Y4=#@3o&=q3usT8Y`O?uT-x1qfe%$tWth? zzfaOn7%sBhCktX$YkQ+nKDp4<@P*bs`S5MS(`)%;eT&sPZZ1=9BMVAEZ3$icey%8GiopSgAZ?u(n4QjFmO7 z4N)!<94p7G3{~!1F;=RE4pYujB~}W)FkBgZj13>5eRr94p@((BtP5scFzbR@7tFd~ zx9((b?|PlFfS!zt}iR)^w<+F%^1w$AZ^VlzUE!lIv6IE4N-6 zCEsT@^S^gSl+<2r)w;Mq%(`IK1^+vB-SPbRMvP?L z)?c+PtR5pPM)y=+xinhdpWZ<^F(g{n2bevCpT!=<&w}|`Fh2`+Kg;=y_U#9vC2Iw< zcJefjlHG}mbqrhOt1LAR%~j5FxuP69Hbc4Zj}_$h#PO=fW#&ZRnG?*MVCDq>RZi$} z_a&EE3o-Ny?CxnUyD?m|h+V8s2_#lw)b5-<7{|$x%^ZDe7LMG3rzs5+>#fGbW@ZZcxdL*tX)yk_JNsWUw;`ThcBABH}`6k zY}st)WYZ_3WkGv0Z(Ej%mLvBK->4of-CCHr9nvCNj=pa=Vpy~!e)x@!r_0ogzEHFF z*J=h+Gq{V@45nr~JbIU2Sb$p%}7$uQi=O~Zw8YQVM z<|{^Lx?t7?|2uVEFDeB@%k^^ResaYo(K5T#PWA3`*J!zTVXN}mHqo+T z_6FsHRih z{+YRVaUVdu>xIj1Ouxrpkv>yrX@7SXdPP3nFjF~OxmTpv$L}bAUg;J2aP17`Phww@ z=$X@%S9`pp-!$b}UQC~sQI73Km^#7K38qdkb%LoAOr2m?=dB_2CDSx> zEQo7SUtSJ2e6(79$$r)B&tr!QzT0l^Ng{})Q^5qKbZQ#)DNb9F!h6}A58sV>IYLlnEJug52k*wtH0LyRM}qF z>|K2`rOBM>hWC|BlW(^eZdD^qW^6D#qIsHJA7!}BpftHr(Qw^4X|imq*$;bfN|Veb z4c9x8CWqg6Pv@Jw;Mq%(`IK1-o^RcTJJ8;bzVk>6ao2HO;!nJ;rOV zW!6j8xhZlc%&en=-aHxp!0?6RDY9^ZS!;)XNs;y?r>TCInICnTAI$t<<_9xB*v;?G z8JFGsJKLv7p_*pRHg1(71sjdmxyKmnMT`NvF`S3Gzm0lXzUph{cG&b(S@FG@!|p!d zGCvE=lk8`~?q}&E^1I{XvK!;h0hitV=YyMRa{KvrbjQ2je5Y;1EwA@^?<1dOg&)g z0aFjy)pKo6ZMk9f&%ab#TFo{6dM#U=>}zDWR@peYcE$94Y|S|ND9v!Urg4&ajv1fS zu5q$_pLv$aW#&g+<_9xBnEAoX4|ek}_*8J8LH%8@KyaTy`Thvcqicp6b`soY(DszZ zg8K~0ZR&VlS225jHqT%0K7+RR^L+R2Gbm&Hz55L6i_5GFJ**36T`=o{Sr^Q@VAch@ zb=MrNE{8sAts45St1fve8!kVkx=j7)4Q-#?wYn7j&2Xps)ul^46Ei-ty0rV<@T&aP z{)opt zj+Gg)#Os?ZaUu>kNk`WGal^5 z(^Is&bJAruhHDe??w?=cw=hlapEO=HTb3r{_L+Mf z8@=nD3hRttjpwJy(D}y4p3~Fh=4|6{(_v}y-b(XKuglbozECrmn!(fzre-iTgQ*!z z&0uNr_v-HQqUA)Q8IL zmZwUUsI|%i=B7%^8f%n)nvg1an|`2NtY4~pIc~M`(3YvP>clGLjdfDxZcW2Yo==tJ zW9IoQmsuBjSQpH?VAch*E|_(}tP6JQo|hDPu*@7^_7qK#kVb~P-mNF|DjUA`Wj$$F z%W&m&_2m1ZhSMh3lkPWdd-r;BedIzN|H=+CKk70+nEAoX4`zPwzmwnfw}m9j=uzhR zy-q8WC1uAF)w4cdJ?YuK`ezVr9e>zo44cxAr z9^hS9#_!g;j7NUPgBcHY<2eV=?vA0$ZVczV#@js~W9aUsZVdNZ#Jl^0%Wllo+Trr% zkUc)c->n)holEXe4vGkuH|}p!KK)#{3=G?%ygGBZ)I7C8Ir&PMY%087dD?+6dH>;B zy|?{0d&o-C^TY^PX`b zQf0Eahj468h~yn(?k%{?{HV+PVCDxiKbZN!ZvGorLZ$yAvxm&^p5+^K!EnBEVKU&p z;kof)a_O?+4(-AuWR2mBQDL$y+3=x7VY2POBGrHU<1l%zwBf18!=&!(X8&}Vb)koK z!K@2rT`=o{Sr^Q@V7Kmw`ytZ2vY99EW-cdpYMS{|u|PTbq^g-?C!a4TlS-Jmcdb@A zd2rV7s+Q$sU|(}jxW=$@vij;Q-S=E(e$-`tF!O_%AI$tUfJeRw)vH9U1h6B+3Hlb`t{jJmu(-lopl|Z+RnOYXI(Jsf>{^r*3H+r znhZ?4q#CkRuO`QDUQx~-SWWh1yRLjNb2WKw;!ny?UaTs?{eD*Nzo)8n+iUp2qN>ua zv*Co{RVCyt6CeI&RatfMn(B0!b)koK!K@2rT`=o{Sr^Q@;J>KrgI~5?*~Tl|Jjyn| zvaPFZ^(b4N%2vM*bzQc7)OOZ&bZR^6qMdcYtP5scuv^z1Lzmro5_eDJmydqbF+UMr zRc0@^oT2m9tQTd*p#3jmRHwVX++j)OI(9a~m=4n*9q_o$kKsjEo5J zMMTQQpUgY!9xoj!4ZfYG?fnWz%Au^Yl;6wm#Wb3uJfL8tB(IsTmF#7^#U%>1O*zHS=A1cU@+7tD>qVly0(z%v7$H?+~ z1z8e3S=-xWttc-QG3V8Hi&m5`e=uCJVnyjP)tq~es#j6YmNMt$2^}lSnsJ7AjjJdL zN6q(iF0(H5ur8Q&!K@2rT`=o{Sr_cqwa*@_e*4_DvV9&~**>SOY@gp&w$F7d+vmNN z?Q`JD_8DM3KXjROp@((BtP5scFzbR@7tFd~w{A*Gv;>vxsTvZSd(ZQ<=&ro0W3)6I z)K$54&uGa!yt8uFx1!~{{vDO4d+oh@v{x?KDOx(dWxlic+RKw|y7?~SiTcrU|Eo8& zUoNvQ^sp|Nb-}C)W?eArf>{^r)(v^4lGOOloVVYLs3c!JYtGw;y_y^>^q z%J7mYmE@bxP5j!mm85Jt!>tZilFsMM+$;EFCCOabaQOX7lC|?x?U&1}3q7n0W?eAr zf>{^Lx?t7?yLH_$blIIJSrw;Mq%(`IK1-o@W4z3`-omr`W zC%8Iq1-X)H{zi3#cm8uI>qKooaywEI+YeO!{#v9=|K(NXJ69v+otDwcPu=u5G{2sA zxy<~i%lu&G2QxpI`N3{}J0?ENE304G_Dk9JSJ{q(vK=2~J8sH$JeBP@`%u?q){^Lx?t7?vo4r*!ERkURx#+8?XR*O2W2}x%68n8?RYBNan}0)E;B#sGQa9EK59Jk zqn-J|ZhqI(zhKQXz?(BOgX%`(vzGPV1vQ|LjB!|F+_mhoJOBH5e=pOq-ep}Q5q*7f zV&ab($io;gW58|<_Xo7Q`{7@(=HwbgygP?o{)-s(!ksfN(--7)=a|dx{%rN@oV5MY zxyl%)kJ|3WJiMMHmnQbuikRJ*lO;TFcjZz6$ujChSLNgy$&&ta7v-KUlI4lUhCdvZ zECY)f&c8HSy7~-%v_DyLuQR;la=cbOW{P7Ppc08;~)8o<;5 zrUo!IfL#stxi#&JeU4PwK3}SApF35y&!Z~a=Tw#L^Q+4CxmIQSysNT(4p!MdAFFJi zn^m^Ys_B@xOr6kAonYz&Qzw`@!PE(+PB3+XsS`|{VCn?BI&U`gzDG_nf2-9tB}w9= zhN%8C$w~5Ck-^HZrY6b4OoNoSzvji?9H_jtW0G{ZI6(Q-kR%yWtiSfxW#&g+<_9xB znEAoX4|en0X9cyEea=(aKL4p~p9@vC&x{^Lx?s2N2i`h8v1E*D*yDZ2`gDlldux*9*5J|FUhyDlhKnV~$xE3swEbLMoGiGtS-FPC z{m*Ptu9+AoF-JBk?`{w$<@aw;?%z62S{?sL`H_Bc((||V+Ao)>8D3B`n3}=V45nr< zHG`=cOwC|w22(Sbn!(fzb~T?ankEZQ?o$1I%6fkvadx-z*z#!-aC49HC69+^-e=l_ zy=UMH?pL1kT$-FHen7cx?ldX%>_O$`cT;7-O~VDxrb_1z4r#mW^qx_vbJ%=#L8|1) zFr062s*KF^nYNEjPn8pe4gVgSDv6mt)A4kfn$Z_(22(Sbnzh|(22(Sbn!(fzre-iT zgXdVyU}^@tninpwD;EmR)4n9_sw;UWuSp@((BtP5scFzbR@7tFd~w{D>hiP9*~yQ-n`m_#|(YnF1M zm5Gv^!|-RHCCctYGqpYSR-)wo*znS4lVrvj!@DYb&xwW2QvEJ7Kk70+nEAoX4`zO_ zo8R@+WjFt8PbW&bv+t>f4yzJmU8I>0S6@t!8;{P__C;UEOXnJ9F7dP2Gx=FCKMUq( z!Tc<=(HFFn(ayf3-DR#vw7dJ8%We$!L&Upt*kw1yoii@GYk#!&EM>0H?K%#fHhO!= zi)P~ zm2RXwb5WvED{E?=DjVv{3_?8o<;5rUo!I zfT;mY4PaNphMbAAa>$#iC+F=1`7T#m)Mb7!^Mjcm%=}4fT1u4XRf3iGPVOJi~UWuSp@((BtP5scFzbR@7tFd~x9+(!8-*TgBGjH)5? z;%X~r4Xh!7%U@D{>)9GI_{@vSW3tzf&u>>(9`ZyD`Q=ts<>8OlkhIHHv|lc>F7&W2 zn03Ld3uav~>w;Mq?AEPOx2}9T-Q1%n{d`^daJRX4Q9Vap`EpKA)i&-@9l27ZmvZLa zb);dm;ScB4ky>|5%=CeEWPYl7uZ7FZkGjkcW_~d9gP9-f=6A=$W!Lwb$Gv%SuC$I} z_XpJ_d#!NQ%oyy+i~+kbod0Nd*SO1W41Gbo+h3R67|vD1yZfrkZVdMp#245RFC)g3 z*S!t_7nYp6 z<5RYO-=}Q5nlxLjs!g#N}lzHcm%gm3u%nxRMF!O_%AMEDG zT*dpQu&(i39N$BQ=jHf*Dm+KW_g3NgI=;^e&)xAoS9lJP@4v!xdVDVyo}t3~vQXD$ z){^Lx?t7?vo4r*!ERl5tXy{IZK(!zk(ypouX{7UzF{2jk3MoQMT7X z%J%w5*TAG(?(-VcK)&&{4JGYa=tE>DEDrjENiB9Qf}QaSx)ropnNDUSu*;yQ!Y>; zSvG&zM)_>vWI0ym%~w;Mq%(`H= zu02;*4feW2*X(7tFd~)&;XJn03Ld z3wG@_GyM!{G1?JM;K1en<)L`4A+QElxyD(QT@$Q z5~W+sA*$bH=0{!T2QxpI`N7N&cJsSlyX=mSy$(_h_WDS*F$Qa&F<>`_dl%YE467qA zUj0V*x+j0CD?_UlHhvvRkj1%bD!XgbW#)l?<^eMgxT=$f`zPwUbJ%4!hU1BNcb>TH z#<*U%?CvKy5|X6#y90IH5^pC;T#vVvBj+Z{@(%`Se;JRuj0ZCw%y{%MzEuI)G3>nN znbWR-oY{Lpx#fTY(*E}!m2=K6AnBPeD=*zsK(?Q|qI~;q0V&w;nsR!@g7VA0>&nmd zDkv2{{z*A>TS0j<^=IX7PZp8~!+%zttP4G?3uav~>w;Mq%(`IK1+y-gb-}EQ{tn$# zKw3RHRP`L4T0jo%H}Cyh+{f$72J`-q6>SU1 zHc#@`z2ZG5Ks_^F^1i3GI&(;pU;o>_B!9oqUf{@7)r0tsYo;k9:Pm688W4fD(` z>R!8O7@G9>;9zB;Be*fctwfC4G?~l(qGTxu3bmw?~{^3pH{dEu3 zjrZ$$OXB@HuUGQk4Px~-uMqF=7uq)rHP_>aPhVi38$q5MN6fV_@_+S|Vbnd_Zn)}) zo~M5_&u>6ypCN{!zhG^{=-18&!{{&DF%FE!_%IK~jrlR2tc!7`9*jSA!WZhNU-0qo zm_8zgK7#2Zm_CB(BbYvd=_8mvg6SieK7#2Zm_CB(BbYvd=_8mvg6SieKC&I-z<7)g zm_CB(BbYvd=_8mvg6SieK7#2Zm_CB(BbYvd=_8mvg6SjJ^)Y9j2zkW&hcz-NXM|jB zb#W8;*C!$*_vse;Ea?2-!zH5bV&zL0!)4l2Un$o)7A~X8JhBDxZ)AAyQaGDO`SK!5IqgwSygu7ZAJI-9!SoSKAHnnyOdrAY z5lkP!^bt%S!SoSKAHnnyOdr9nkB#=1lt&+VSI?Ku>?tX)7oDX%WP3?jRLz__4OmxF zdUrMFSD_0^N{LP89PF71C8cHo!~1%bl>Jl9Ioso}d7rIdcub9wviq(%ud7_9q}=?$ z@P%yuYH$Bj34i?J<0brgnrtiK&tGj>34h(2@09TCxi;4OtkpSjSP8%W{6k9k`-S$o z=S&|F-(=f++DGIWF=n|GJCZ{IB+m*@gV^cZL-5=ULvqkU#%~hK2lftHl-a z>+!{UpSA1mOoc*z{jDMj`TK=-&RfKDJ|hq3Ir4MyAF6oj!u;BbYvd=_8mvg6SieK7#2Zm_CB( zBbYvd=_8mvg6Sjp&prk|`JL|DXdhncTV=%WuXR!xd1m)Mp^W@5ef*6w>b5Cn7LNi~8Xg`-S#h z7fl}#|Mt#PssVXcPCBiO{7)vFQAXXf*9=2XlTK%~9XbadF%139vY*p-^egf?!{{&D zF%FE!_%IK~jrlR2tc!7`9*jSA!WZhtT0_6!9U1k*<_ zeFW1-Fnt8mM=*T^(?>9U1k*<_eFW1-wqqO^kMRN1M=*T^(?>9U1k*<_eFW1-Fnt8m zM=*T^(?>9U1k*<_eFVEcW-lD1k*<_eFW1-Fnt8mM=*T^ z(?>9U1k*<_eFW1-Fnt8mM=*T^(?>9UWIK;{^bzg!5lkP!^bt%S!SoSKAHnnyOdrAY z5lkP!^bt%S!SoSKAHlAVxJK|F7rg5T9xrfS%Hs&mS9yHFc`T1RIKSob2#PT_o* z$1j{G^SFldXCCixUd?u#Z!;d};mm{cbLPi+JL}?no_cUyK%KZQpnhBzuwQ8B@dEKY zjvx<@FUZg14(jrF1U)=XK_`!2(9h!<`o-fN`pb5V1LHA1%!6@bevBvUVw|Z5<4>Kq zE}(w;1t0&85sz^|41EOCM=*T^(?>9U1k*<_eFW1-Fnt8mM=*T^(?>9U1k*<_eFW1- zFnwe@k9YJD?eq~$AHnnyOdrAY5lkP!^bt%S!SoSKAHnnyOdrAY5lkP!u8-I={qxh? zS2=I7PC1{kemT#vt~vj)-nlNY4{*I;f8aX8zQOf{{eK~C#j!)!N9U1k*<_ zeFW1-Fnt8mM=*T^(?>9U1k*<_ePlb=9eqSQeFW1-Fnt8mM=*T^(?>9U1k*<_eFW1- zFnt8mM=*T^(?>9U1b=;}k?al~q}M5Aw0Eu3Kwg{PPxs6L-rq)jcBrFrsh8_ZwN{Ol zYrarVzWTYU^3!Qa@>Wm@<%wS>NaK^g>vM5&+r97R1};;+^Gv+FalV{#{gZX&xB7h+ zqLyvX0NZ$Fn@8E^--;MpSJ~=OwmOxqer4OQt@vKRW%d#6>?4?c1hbD|_7TiJg4stf z`v_(qo%ReTUYUJFJNpP`AHnP+n0*AZkKhAG!X@wE4E6Ebli`v+exve+`{B}N^E%~M z!@ci}O0H3UzE6Y{JhxK$#<2*wpLeSyel}* z(h72I`$CNwUZ$eIz4W|_{`iP|mHc@^`&IJizx8D$f88C=Rrc#?lUmuYvu2OVe*LL$ zSN8V{?Ynzy*Sd($sJl}cc>=%Rqm2AH0}d#oZt%@R%FwgC@)2d|Jayr7W$6Ft>KDrB zS9Hyz%IGiKF%FE!_%IK~jrlR2tc!7`9*jSA!WZhNUzpD>(>t`&J21Ti(>pM|1JgS& zy#v!bFueoQJ21Ti(>pM|1JgS&y#v!bFueoQJGP_mjK`RO=^dEff$1HX-ht^InBIZu z9hlyM=^dEff$1HX-ht^InBIZu9hiP$-F05@ibOv3kJ2(<+xY<`tQE{ zs=r@o|MBt7stxhqeX~^=d1`g}L>c*CSZmfJ>ed}-)+6*B+`Ug@pz~o@vo@jstG5nn zJNni5sA2S%?HC8fV|pM|1JgS&y#v!bFueoQJ21Ti(>pM|1JgS&y<r2^s=WqA+6Mww7pD5copls)cvYj)^b}lK~ zIi_sqp0b^j%66_Q+c~Uk=eDw)^U8KDDBCrnY}bymT~o@|yRD9o%Jk0hUEAp$+UXsb z-ht^InBIZu9hlyM=^dEff$1HX-ht^InBIZu9hlyM=^fkQ9pm90nBIZu9hlyM=^dEf zf$1HX-ht^InBIZu9hlyM=^dEff$1HX-ht^I*4o2nF>>L>81*!F`xuEYS3~*o*chqw zWgX=SJ7Oe9<`m`h96tGGSOevNRzAsFs;P2`!#>IP!RyK|REw3jvb9n^v?W%`6=+I>hr=9vo zJYCJ-FSPf6H9|EYe)5MQ%E%89I{(pM|1JgS&y#v!b zFueoQJ21Ti(>pM|1JgS&y#v!bFueoQJ21Ti(>u1K?~KQofax8W-ht^InBIZu9hlyM z=^dEff$1HX-ht^InBIZu9hlyM=^dDUIqNPKY-5z|XO(SEWm`+xYEZV?l&xlE+ZScq zM`hc0WjiLycC3``7%JPbRkmZUY}b*pU0=%9JAb>k9{us&exhvWfU=z%%685u+qtA{ z=a{mcd&+iBD%-iLZ0E4Do!iQG&MVusplsKOvRymMc1pM|1JgS&y#v!bFueoQJ21Ti(>u1qJI2F1FueoQJ21Ti(>pM| z1JgS&y#v!bFueoQJ21Ti(>pM|1JgS&y#v!bthE`v8p`l4m$rhRnAAuz=ew-@<+8@| zb7j;1`{pJx_4^;Reb(kzrC{0f%B|)#m7hwSQeNHmHF@UtSBCSXdw(N;M0xR;bcsE? zS2^pq=~ANYcIDCc)8*Wf4a#yYU9O%m=YG>xrAwyji?qE-^>k@gbhh%!<*&)LCDW8o zU2iJ=3Y+KTn>^K2sx36nt`9EwsP9jwfIV(2^j3ub@8>@S%81+%|k z_7}|lD%<{o*@S%81+%|k_7}|lYK-kKnEeH_zhL(F&;Di!_esH)JGUan zWsV8r4}1|J$8x@_<8~>ag6w*BiE{B(6(vs-bFN;zWo2nSXS22sl4x16%6RJLWFFLF z9x(GL+dN?A0W;5^_3-bf5aY62%l*5sKQsOg3!mlRRe=L8hWP)c%w_j)zFc-=$jHiC_zvyWi*5zIb<*+($@2xcF_>?4?c1hbD|_7TiJg4stf`v_(q z!R#ZLeT1j(T>9Vj_lBs;Ire|cy!uc2&f@R(VIFtjDUUl~9(TYz?tppR0rR+{{0}?M z{@uRK{U4gS|11B^afEw2V*bDWoh;sYj`yqJv-n*GzIO$`*TDC&;CCGOo)-MR1K;0* z-+kbFUGO^;eBTRxCxY*R!F%BOewdGM#7Nd{{k7J@>M^onbWi1#OQYre=^d04L!xDU zKnvvx2cqQUKy$BP^1aIPOxt8_4=oZUeLEX&;ER&Ydkw$XI7-%ZFz*Sh&?`!szGm(@ z^qdqW*QeCi&$eC~CEsUGRqmY;CAC+lDG$#UDNnp>+WU2ikk(_{XnWqK5mI-fx#y6P z93cfZnfnsQYe&eo_l(Y|FGa|WZsy)a&N>nDX+pYwHlTilRIJogd1kW+IV(++vvrS< z-rXB1Ump`8{l7PToV_GMzMKAvwl~}pA&X}iZM82($QRd)w!S}BklPc@-$hRM-rK*v z#cGY;ejr-1R#>5&r@8l=GKq_oTji@PH4e>H&T_e;96L5c8NMvJZO&CL#CpGh^2btb z|EWT(1V6r9`9e^vWWQ&)aDK1-l*#|(qp`AS@k))U_@mGJofLB}`tp9Cq}%h-BFlZU zAjW8GG|DFzx*ERF+9w~rZ5SHfe$pJr=Xx66ygnip^YCnBth{h)xboz{Sn2kiIqnzD z8|(eHj(NvIwtGHV6KFWgX`kHfJ4EBpeC(4P_sls%m)SlUx4`hKK0dkH$MCoYKB+s% zaIT6z>A%5nU_S5nVhWi&pZ*#nMHd_1b}~keG%~eL?(}|_B-H4E{=;X#(7JDR@ky>(|qz;J;PC(d@>-D;e+4!RH_yNROxxFOi;`A{&ACe8dT(wYGv8@uUK1tx z&l{ax)_T7^bnB?bH{BE^2OgT7vvx&E+XtrB*I!1-;fqGY+^bQtWwX)Q^hxjcs@fa< zElWkqk^6>kRF9T!EsUO!7SVF_eZ!RkqUCzI{aUMHlW3V;YNzt$uF-Pwg89y9Z5!`= zc=iTuKUg(da`s-M+~7`>)SR}MeEmXcWq`qXDX8et7 zQD0sTHhi>NeaU{+%z-h*>dWPC4R^hlBF!Ec9{Ej*42n1LJ2s_Ap1p>%yq6*)+L`$r zG$ci;RxtDYM8^~vR%E2sU7emHdkdSjkpGnw*&i}m+tcc&$QLh;Q68C^B0n}At32n` z6v@(MobsemFUwbb&1b`=d%p$$y@|2!Z`T<6?sR4QI|a)2_Y0Km?;0rE-#bvYzk{G` ze;+~F{%(S@{XGR``#THD_V*W*?e8)u+xN69+jp}o+jq7r+xN*U+jsjb+jsse+us6E zw!aaeY=1jI+5V=0vi+?A<-@hMnzGq)<(BJ<_;UiWF=#UgK-^N|0txoB0+uGC|rF zF!ONNlmy9@-OSIHGZQ4+O*4ld@wmrvGq-1Y?|L1y)y(;3-g{|$Yv0qHsouMPm+v#{ z_u8J?a>K6E`Il--tGQ;)zLqUc_BAqGt8AQHyJFV$*qU+jQJUdyP2(i<9JBW8WUVTR zKbv)pcY+;%-Rv7Pymz|=wln)iXYbu^`#PAqNp-#VwzV*y{my&OVf~j(&ShOhn&dWh zL&k{2S#6t_h#aVH^3UBP(siNXXD^EEIsLD?-Z_Kzae;aNn_=@_IA#0ZHf8%hH)Z>t zH)Z?&H)Z=?IA#03IA!~8G-dnFG-dlPHD&vbHD&uQGG+U|K4tqJKjq0?t4q<}-cYvh z{ZqE@15~!}2~@W44^-a&dA$6x!pyfF^%LaSyEC-CZ=D3mH)^`_$e08QOLpRbxG8F>wV z+ayiS^fYtkM)x#H+i2!e#;7!Dc*4xF6*JT1!FhAcs<$vr?w>TrvS!QDWZXV;jN7<0 zO)9KAtQs26Pm`hZ4=MMYo+dYEA5ql)5jCD<0XE- z;U*dJvMJrHg{j{A96mc_c@`}vjad;66))=8DSHCHLSzeRZO|Ht2#)axw! zdx&87w+{LHiD>8V8-n@!r(pj6DVV>13g+*hg8BQWVE+Co*!}%e_cs&W-#6s%(juO} zOAF@j(t`QBv|#=&EttPc3+C_Ag893&VE!&Gn7>O4=I_#i`Mb1W{w^)p{asrAJ|o)Q z-?ij#s-m60sS5sI?7exsk5$|EADJ3ZTx6byZEsihHf8U1a!8lhV%vL*t5nj!RT+v@ zlq8CzC{!Y28c<1*?C*E)CR0i&Lq!=fB}0R$kbdiPto7NJo=eaDdp*y6zwW!o{_Fi( zueH~?&f^@vpK~3bx{W$bt{XsD64}w{L z5X}06VAdZ5v;H7BtUnmmqzmixu~wk|udfvdX01RlYXySCT7jpl@yEJ>=+8QO!T-jB zF_l>t678%D2@dN*{zqyju^totm$jn6tiJ|k{WUP_uYp;A4b1v$VAfv)v;G>G_1D0x zzXoRgHE>vejrFR~9@eX3eJixH<`kH9^uVm62WA~TFze`nSw|1dI(lH%(F2Ed^un4} zVco7?{|B|Y@u=W<~l%bt<%D}8s24X1z9WSg$SgqNJZE`q0l4Og~RB{XD_+^90k+6CC<^(gzalr}Mg`eE1N-&8PtQ^BEcYUo`_Z%p)|KQNg7z+n0VgXs?prav&4{=i`R1B2-g z45mLYnEt?E`U8VQe_(obqMcry;Lxj+KA&h0{V?gri+1|)g6YQ#rXMeue!O7%@q+2c z3#K10n0~xq`tgG4#|x$(FF5q${oi?YqCb5>!J&63{aVpZzg95)TEX;d1&4mE^fp90 z{S3kMGX&Gm5KKQqF#Qa{^fLt0&k#&MLoode!Spi()6Wo0KSMD648im>1k=wDOg}>~ z{S3kMGh{n`9sj5MQqmI-`$Zo-Fn#dA^uYtu2M|Cpa4ebun<^iKoRKMhR(G%)?s!1PZ8(?1PN|1>cD)4=pk z1JgeZO#d`6{nNnoPXp6G4NU(uF#XfO^iKo-RekX2!KHDqdD&!G|Hl4l^lrlO zfb}Jj@=o*rY)*9(dP#-q0bMP zK0jdk{DA561E$Xpm_9#X`uu?D^8=>O512kb;4?ly?t2#U<>{+~e0loqAYYz7Jjj=) zKM(Td>Dz;RdHVSvU;e+!=Z796IF9rc0n=9mOkWW&eMP|Z6#>&%1WaEMFnvY9^c4Zq zR|HI75ios4!1NUX(^mvcUlA~UMZokG0n=B6?euw|uL#=dD*~pk2$;SiVET%H=_>-J zuLzjFB4GN8faxm&rmqN?z9L}yih$`W0;aDB_>8ZJTc=7t3dDqd6kz&Mfaym8rXK~E zeiUH(QGn@30j3`Xn0^#s`cZ)CM**fE1(<#mVER#j!`y1-!lRwJ@L=Y`gP98tW-dIK zx$t1-!h@L$4`wbrn7Qy^=E8%S3lC;4JeaxgVCKSunF|kQE~kuWeXgal z&%sn?4mFMobEv`0p=LYt$9?W+{y5Ax_qn3lj_oo(-RG8SyU#gQ_PMCaK1WsA=dLRI zoK|I@>#FQ?V3mDttg_FURYv^(B>z1Z`^DT_uJQ=H7ytdkbdnE!+PpdDCGIpwCg#`1sr~o!zeGZhe&y7;{IaA6$mrB{^SSkD5D`lUPrR;OHlzk4Dvd`^O_Bmh5%-O_oVa_I) zIh$-}zN*hP%O8jNtv)wR+kMWOvd?8x_Bn3KKKD)8=fo-dTsdW*L#OO>>y&-YowCox zQ}#J}%0BN>+2`~rhq+_S_0x0G<>xjBGuIEyTt6^#{lLui12fkT%v?V(bN#@~^#e24 z56oOYFmwID%=H5^*AL8GKQMFsz|8ey`(GtblXWn$U#u$%W?fM*>xzO|R}{>;qF~k) z1&4J-{dzV%H?S?%*<^i8^k;2fFl+mQd;j06FYIe2W6ZF2C+j1lo%NBytd9(4ePnQ0 zADQ()(H_=6Wo=)yv$ijowSB>??F$ZT`<||LD(kVLKkI~oS;rR4I<{ceu?4e^EjX-W z8`c;NYpSxgFZ#2#FPOD`!L02I_G|z2__DSy+QZtu|B*VaVJ-6F2Rq0&C3@+Y6W4c; zqaAuHr@Uor{WR;Nywt7{eSL-FPIq*W8-I1o8sC@$Yn_8xHynJ1x^gZ{^y@f7e#_-@BFlcW`C@eO%dpH&^!G)0O>qc4hzlU77XnalFDh@3sGa zg}k}!Ztc_R{3~Srw0o4t>~1G}Dh*UFx~!dCo#yz>neC*_5!dJcZ;kj0eKVx%1<&c2 z&Fp#g?ZC;(6<*Dd%<~<8`e}wNTQy1BJ0Hl9lJ7X4UACi4+~Rm?GrMLo#r40wREE^w zIz{{UeXWBmXgp1M?>}tKtOC=OU;MJY^t;UQ;NI^{;<+ds!`xpQ+tmw)_7*C*7_o-R#CW>;81P=a+^0zsr72m!Frst9;Fu z>GIKV$BW)hm(>?JUNAXbb`5_=`&1g1F6V!or#!WHx+EXURbF*Xx>PRgxJqWaTwXA) z?cb)S%d7)A%9mLlvSqPy>x^_UtKU{$c2&AGSh+}f$Svv8bKP6Yzc%kI8AU%;-dwqh z%-XnA`M!Exq{!A~%8xhbBDH>AuDsjw$f6&*_QWnSvHVKqX;r((hH4)v_bS;%DwO?L z`KF_tW!BG*%Wv&0{a#)#ncsWd%+y{Jn4%qis z_Twn~@s<5PM(FSNUD?l5+0S3u@0YUQUu7Q$Wgj19A2($mXJsFMWq(|h@!n!aPs4qhYPu4z{ji@j4_ByVxGfB#CbNK=#mnTW#m&R$IwbPQM^kXic zW!Kmwc{lk{ZQnUONj@~AmFM4|Bn>*b9HqN0AMES$kDAy%M@Nj&KFh}>NsIAgl}G0! z%iQ|!MwsW`whiUhhn6cJZE0)9)%ZX;p^>d6cRWvdbJd12G$p1yuV_PQy=jqh=AIN; zTydfD)3$!xj1zAt-!VHywmm&xdGo_5a^VlJEB|mqic~n?wZGaTMQZJHT(feDJURMJ z?UQjLSsHJ2W0u{PEVEa>t?ie8oGf2o7FT}aNFy0@+j!lV?hiMT?tgc&y=q1ysrQnL zfA^e5viWy+T)z3Vk&HEt)3-K~Bi-DwYqr0U^u68Xaa?n_k-XFYDIN2HUmHo$+ugAk zyRD(rZ0x>|+@IZ0iu~g8gPvNKB3In#*6{zdCs~HP=+^d6JTFCt?QmSCeu_MB-0}4G zDYE-}$9;RJNYZ@A@kdi+PNw5kFQ!P|M=$Ce4!)BjQ))YY zeADxd@KZY&ob?V$XR zA5&!F`w6+2=ew&KO8*&`C?A{KP%@u&9DB5(JeKD8>)RU2b0eE-pGF;QoF8tY{7}P& zvOcx3@`Du{O8eIuD!*T>p{&@Oti0rCiX1qrf%3MWQe@1L`pVbrPmyYy5|uY@XeQ+@ zPf`BpnN)deY+dCOkEKfG!S$3MyFXRlZ+_ZUx_xE8o?rR*ghY8Iqm&+ta%B_cyu5RjpDmUsw+t?*yyL7y`S$Sx`aEj# zdp)@_zE%0@vlHd-#a1itDxN6M9L!VRSUFM3o;6STM8ibcI(@qG{Pu~`|I!J{m)w>p zcQ=1jdEujpQhoC<<+N85rA*FX4^Kyv;6eo(A|?DJzL?YmeC9&+32X|L;L?UOZz zN8U}AjM--?-?|}L?%YyDIsJ!Z`MGons z{>cTCrCl|5TsBoqmTPZ!$7|?@Y7)D4adTXoYYtbFF-zZ8UR1KWEIiNg!?mhQnZ}E> z{q@GxrQ1K=QvO(~%eSo-DnHh`y4>1yf$~R|i`98kd1TA#vbWqD%G;V$my65JSFT&9 zx=gF}x^nJ?)n!V%dCJMZR+H}@cezD1zo{mJ4!o-E|JqSWZalD3`MUCz%+Y4P=N#r%h*FI25hA(rxaAqZ0;oFNZtt2`Ba_!6Z+xlpixpCfpzoK0B+J`z$ z-=`|d>V}SMpH)#>?tNd|KPy;K%#jb2mz-NsZaua{dF4eFrS8v5mB-YpDD~GZQ-02_ zt9fnea^;(^t|*VCuTXArxBcJG9Ao^QcXHe@#vJ%B7ej38 zXtIkf=J0!I7jw)l_gr@@Fy}ob+%Y;}_xHeiF1C|fRg%i>U2JEKsU$BBnyYgg^jRgz zymGeko99%PNxR&$=9gGyd32S_jh#Nx@(#!C?yf8w>d(^t2Rc`lJ7zc@*{rf0689Y3 zRHd?PJ==}5;?k=5r*WDk!o0ceb4?FJhcB1tAV5N?UaYiJ$>k;F3f7V@V=(Dhuy9V*Uzn65^JI3sG z%rUlg(Fu3GV-6o&;I8p``x9kmDL2miqDj(cm^;spzFALhDwL_)Z5FF1N1|-ydsozx zzg>N$a@URZWPIB$%54tRljo2BQ~A-7iIRHD)ynM~B+6YwyDC4Mm1xJgM)|h85~boq z$FDwX_jj!04!L%}YB+ATIZ=vscK_S^M54&w-I%|WPm*unblW;FB}tkc?5txRY?UOl zj&)N0zITG0{n}3k&!AS#>*2YkT&9ApaW;Ff@~$HZax8C{^6R!f%h!iTDR<3Dkfask zm2;*i$oxIilt+!Wwam_WP5FlV5@bV8uJWQg5~TH*Pn5svl_1ZYvqjlIPnG?1R@px* zmHjhR**{yA{WDkDKZ})bZIUc=E`39Jdup;g`OZS+yILemtEP*UbL{sobzeC3$Y;Bg)+x+2{Vpqm(zLSCT$&JgPjgLv2YZKSE=*XlWfOx^A5E z3wd>9z};h%-|O7X7lSbT6tU1?s^9i!ZT)XhKcgT~d#KOa6@XxSgrx?k4GKh{Hj zsgr*Wd|#$+{<$%}LEZdwX7>5D^T)ZlYpwk8$KGBmzfZGKwetUW){C|B$2_*IR{plK zcGt?E!-$J&$=T^+^qAhYtfpMJ$;Dy#tu>|1Zny7Oon2FY9q9Ib>(e#l^=I69g7s;e zuW~3j2Cs9^@eciJ z%B!V5()OS3tSP-_zoR_$pEYG-OXvBJ)1s#IJL-6EJsYdf-MhhiBxi+SpjqMNay`o)0O?hOid&Vt@YRagX zd#+vDxu&!j=$>mYUtU+9oa>%n&4wgMy`Bqno@MMkwtQ>%yj$8YL0+rxo>^mVOpx}q z=WCxG9TH?sQ}L+*K3exBX#myY*8 zT31T%cf90Zb)`y^lk?%T`*4MX{AYTfOYC*$pUZnXCgeY_V>cz_KgTorC*(iho7sKg zbN~8Pb>*3hSLys0K2ld&wEk4NXGUFl>;-pB=T@yN%UZc({lIT^^3Q=+8`qK4#T&K% z`CaPBm(M#McXu7R^k&DmJyl08Jnr6SR@(d3&wU&pU0FvS%ysWSUAEMbmOr@nqU@jQ zNZ(?P@4Bsa{`jk3t(D*YabB(b{&m;Z${**deYNt(fBT%;`P+RWp?3a!%BI)WdBQg` z^dqI09op$-2Y%_ka#DWLBkD)`O0RMcH~S^qn7+lk>{Ut(|{V{&yay*cLr7 z!GBesPkK&bA6X|0%sN?M*2x01P8OJTvcRm91!kQrFzaLm?f>buz_2a)`hw{>38v>H zn4XhhdQO7rISHocr1F0=uVZ>nVs7-A1k-0y`7}Pm{B4dt{A~{AZ*wqzn}hk=9L(S5 zVE*0*^LIL!zth3|oet*jbTEIXgZVoh%-`u?{!Rz;cRH9l514usn0geLdK8#?6qtGx zn0geLdK8#?6qtGxn0geLdK8#?6qtGxm>LwA8Wfls6qp(mm>LwA8Wfls6qp(mm>LwA z8Wfls6qp(mm>LwA8Wfls6qp(mm>LwA8Wfls6qp(m`#^&NQ-cCig91~70#kzmQ-cCi zg91~70#kzmQ-cCig939M1(@q7z+6WG<~j;6*HM7Ejsnbe6kx8S0CUX-m}@G)TvGw& znhG%2RDijr0?aiPV6LeEb4>;KhjZIY$&R<@g6|k${j3)BQGRPndzp~pnCpVjhii?% zTx$g8S|c#m8iBdi2+XxcV6HC$bA1t*>x;l#Uj*j*A~4q%fw{g2%=JZJt}g;}eG!=J zi@;o81m^l8FxMA>xxNU@^+jN=F9LIY5t!?Xz+7Jh=K3Nq*B61gz6i|qMPRNk0&{&4 znCpwQk6&K|=K3Nq*B61gz6i|qMPRNk0&{&4nCpwcTwes{`XaFR#L)AEYgW2~W1vBRz%$#>HbKb$sc?UD+9n73}Fmv9)%y|bh z=N-(PcQA9_!OVFFGv^)5oOdvD-oeay2Q%j#%$#>HbKcpGoOkwraLFcR=DeewIqzWR zyn~tZ4rb0fm^trY=DdTM^A2XtJD54|VCKAonez^2&O4Yn?_lPQoIO{o`KaL|j zThNZ<3(poXjypVCz&Ib^*#gFS0?!sO&YzV}J)?~C>cu9GalS1(`n0y=Jp6g5W1OFC z$9c>CIG;HV&U22BoOEs%x$2zH)J+Nb^K50m$#VWH)+Xfd7uu(P>-G`-ug#mH^P#5% z=1)%vFg+!}^ppV8Qvys+2{1h+z}R1SO@I*xcu;^5A9z!M5jS{NfDuo4S%48|cwB%H zf6f!fh4Y8U4m?}Xhn_89dbWV!B{Fr;2JHink;~utN*UfGw^eZrPm&)df2r;8D*4Db zhKI@bXE}zq$wm9V&_3`yVLQA~*dHD#9A|Ey3i;zdadn0K?OvK*A%8wm^9r)E%|;z_ zOOpyRvgX&yJsVZX-!HWD`a*wRUl`}rahtV2#xK&r-4C(dt@|9)vjuUWXA78~Ens@K zfa%!+re_P7o-JT{wt(r`0;XpRn4T?QdbWV+iNtoEpXkr)i=Ig6Lr)|yJ(0ke53dW% zlh+I8&+7>L#p?_E%XY+p{ShCIgShefLOgkWAq&jt3! z^Md2xIl}SreBpNS+~Iui{NgBJ^jG+^aIn=4@^%#Fg^Xi^z;MM(+>~n{W!{gd}Y5~gFb#f%6^{8e*VgSzm)y{D*HGn`}ipPxGDR1>UMpcm3{n` z{c+Lx(=!uuqh}_Vo|#~JW`gON38rTzn4XzndS-&@nF*$6CYYX?V0vbP>6rs>?1vC!StjB(~}lVPg*cNX~FcQ1=EujOix-cJ!!%8qy^KH7EDiCFg@V992lhvNI1b{*@exmM7jfo%5P!}S$A$B!S2p&AUe;i*=j%Sw z%Np(UvIf)38cZ*1Fukn7^s)xi%Nk5CYcRd6!Su2Q)5{u6FKaNptiklM2K(17S3mo=DP)?j*BgXv`rrk6FCUe;iGS%c|i4W^ehm|oUkdRc?%Weuj6HJD!3 zV0u}D>17S3mo=DP)?j*BgXv`rrk6FCUe;iGS%c|i4bC{2A?bHNsOLcA=@~Nj^DdmZXFHgl?O=MggX!50rY8fK zJ`Z5}Gl1#O0H!|!nEni4`ZIvXyV^{-VEQwF>CXVBKLgm;gwp=LR+KXGNl`Zwedrki zre_G4o*`g*hJfiA0!AJvYHNb&83Lwf2$()0VETlB=@SB`PY9SkA>f<)iL6d~L&q;< z>vK)HX}4yNO9|D+u z2w?glfa!+-rXK>Beh6UtA%N+J0Hz-Tn0^Rg`XPYnhXAG@0+@aXVEQ3|>4yNO9|D*j z2w-|3fa!st?cM_cOb-MwJrKb3KmgMN0Zb1B@HFp%0Hy~5m>vjV)@=d%x{7)&_X5AJr>$ZTmWOkHaD!F_3 zb)7rP3k8R1oZr3P)^z)MsB-S@9i{Jg4=A&43;uVot?AZiw|mcL-4?X7ZVQ-oTfnT_ z0%qM7FzdE}S+@nux-DSVZ2_}x3z&6Vz^vN>X5AJr>$ZSdw*|~PN?_Je0<(@1n01uE ztfK^G9VIa9D1li=3H*htlcn#6tf_={)>HzsrV`lKGt%F!tf_={)>HzsrV^Mnl>*KI zv!)W5HI=~re`8=jrZQ_Pp`A6Az^thR_Oa5ntbV_g{r)QZI4Jx0DEqi6`*%@W29h_=wNjGS&efp-#tocT{%8*oP z*Qbqg?K!qq^5$&iSAMcJwLiE{nRVjuzpN7nW}P@N>%@UsCl1UyabVVo1G7#Xn04a7 z4Ubh*Tq z^OH-Y-?#4fZ~0x9NYQ4FtNFTz7?X7m!K`}-X5B+D>mGtx_YlmwhhWw{1heiTm~{`q zta}J%-9s?z9)el-5X`!VVAeeZv+g07bq~R;dkALTLon+ef?4+v%({nQ);$EX?je|U z55cT^2xi?wFl!xxS?dt|tFLtkX01aoYaN1F>k!OZhhXnx69=bze<3jag~0R|0@Ggz zOn)IT{e{5v7Xs5?2uyz=F#UzV^cMotUnpR`_tIYo?erG{(_aWoe<3jZg_1_TSSx7P z`!M~5&`y6LF#UzV^cMotUkFTpAu#=g!1Naa(_aWoe<3jag~0R|0@Ggz?BlQZAAekw z=`Vyn^cMotUkFTpAu#=gz}^=~$DzLv+UYL@roT|ouIB^&g@SRko&G{-r@s)G{z72- z3xVlr1E&9s_VNBRVEWI1=|2Oe{|uP^Ghq79fayO2rvD6>{xe|u&w%Mu1g7^9nBGTV zdLM!5eFUcW5t!abVEP?_>30OC-w~L8M_~FLf$4Vyrr!~men(*X9f9e01g75+n0`lK z`W=DkcLb*25tx2QVEP?_>30OC-w~L8M_~FLf$4Vyrr!~men(*X9f9e01g6Ikm>x%9 zdK`i2aRjEv5ttrFV0s*ZS%(_TI@Dm+p$4-KHJEj%!K_0KW*urU>rjJPhZ@W})L_=3 z2D1(|n02VZtV0cE9cnP^P=i^A8q7M>VAi1qvkorjJPhZ@W} z)L_=32D1(|n02VZtV0cE9cnP^P=i^A8q7M>VAi1qvkoL9(!J+HiULI){v-c02llRC(`KfARkXIZ{`om+o0$@;_&%XRBdI^UTtb3a_G z{r4?zD?jD9bs*30ZYw>fJHGzhbosEW<2LouW#69l+W+y^>GD<=#{;^hOVMfTw7uOq zEhXc}FO~6}T6g2;$`h@wSf}?I<$hLg{IIXvZpSM`n&0gH_ZzEEcDme+Ij6tKwI$tl zlO7XE_jAj6S>&TuZv5%XMecmTaoO)gmTx|}-R2EluBg{(b-P|uRrXq|ve#ghy*8`t zHCtt`zeOTKctI|on|Jw1L$Fk*y-yDznDqDuN zcl|%GbGTrI<6={?<&oYa^?wr{%9fT*+&Q!1_G}qZX_U6l>z*wuD!N?bi~gA{E0acR zdzVhx^7%g=Qy$ehTXuDOTzTB1SIQTIUH_D4I?F5DUAx!Ww2#-{l)d()>@_iEuazl# z4Nci=Ysy}8Q}$Y%ve)R8y>_SUH9cjo^(lL8P}ysS%6F_vm2O{ts=OdCReFB1TDi`` zRB5~RGv%W5Q{|#Wd(=#m)yEzG)GAE|-0aq~CEc7RYi2lZG$Kth-gJCPtu)zRf2Gc+ z>9uJxwdNA#@9#{L?{?%Wzj0fdyfSr>^2aUHr1+ru%2yppmDbbdDtCM$RUS!wQMtgA z)=zJOyH6G#nktR&bobA(ccx0`o85hNPp?!dc%xgh)XsYMUDVUvd*ik}{Wf<`PO<$n zZgKbO`yNP@0$pFw@i#6pQaah4htNqLEaJ|Y>CKzVt^3`1xV3R}xpqIrmN#P1^oc9kKsr-`Typ2XycXivsoIly>j{Cj+BWZKHI~I359m(}s zj#C#$@<2hyAAc3eSr5BonsOwP$zQvB`=|?=ODF4PfoELl+RY`snmacd+I@ebygO$G z*q9tC;LauJSN!hw&QC_p$s3Z3|9zpAkyl3Fqx|aZG@0>CU*(LXG+9{dX5}UyrOL*k zS1FIT-id$fm8qOuDOCpdb9_~lDmg10|Kplencp|d{qI0~EnJ_ie9yR4**~F^@-4Gd zWqZ-i%7fzex|r8RdE~i`rSNmE{r)=|$t{oHrtPJz2j&%TyIiVxW+N%LxTm(SYuiZj zrnq@Nb$KKCX~2!zUc6l+dA~z<pfjw@bd+c&xKixg-si(h(G`!wAZSr6XVl&@SFN%swoE6t5$mT`0I`e-CO?sUB4 zmPp=w&@tv^?qI7}HDWAlBEp)vA%D>TOW*FU6vpfRp%@vt&9#+J!WlZVDw z{^F6^P7hCXJi+wv1k=M4Ob<^m{X)U?^90k+6HGr(F#SBi^z#JM z&l5~PPcZ#F!Cr&X{i2^I+Ue&Brnf4X9#fTdccC|0Sl%FESMg! zV0yrU=>ZF-2P~K#uweSWg6aDTrtd45zOP{VzJlrd3a0NXn7*%I`o4nc`wFJ-E115o zVES`{>CXwKKPQ;}oM8HMg6Yo*rspS^UY%fib%N>D38q&km|mS=dUb;7)d{9oCwNmu z=hX?OS1OpEu3&n)g6ZiBrl%{Io~~eex`OHH3f|~FUBUEp1=G_NOix!ZJzc@{bOqDL z6-*yjFnwIX^l=5##}!N;S1^5C!Srzj)5jG|A6GDaT*35l1=GhBOdnS;eO$rx>m$QQ z2u$xjFunW0^zH-GyAMq7J}|xe!1V3|)4LB$Z%HuyD#7%t1k2nCC&movThhX{~g6VSzrq3amK8IlXMuO>k38wEQ zn7)@_`d)(RdkLoRC78aKVESHy>3a#L?C)bqS`|C7529V0vAG>2(RF*Cm+VePH_Uf$6^orvDz8{(E5h?}3qP0RKHO z{rAB1-viTs4^00(F#Y$y^xp&1yAn(58uSjr?_lgA5D-ukvNHD!3 z!Ssp*(<>58uShVxBEj^E1k)=LOs_~Vy&}QQyjLWcUXfsWMS|%S38q&hm|l@!dPRci z6$z$SB$!^2V0uM@=@kjaeE5z>uSm4hD-ukvNHD!3!Ssp*(<>58uShVxBEj^E1k)=L zOs_~Vy&}Q%iUiXu5=^g1Fufwd^oj)2D-ukvNHD!3!Ssp*(<>58uShVxBEj^E1k)=L zOs~jAtINdKb?79yql@H$C%5h-yZ%;Gxk|H6lJ<<_H*0s22TK;y_EjZ1$?|(0pE!^$ z|61>OpVgnMRXa!fbX{noh=t{JFI-<>TGG&!tsWF*>daKhqS$|{Z8>&XUBKGoGo{hcRX}y zwp1+a`0;N~w!eMiWdGXbJLQjaPD-cz@n5p%B)5A*mrnWfS#V>g{CT##tyBK|KeES; z`-S$6b&u)X(7)k1$CWY8jISMI{Mh8*v>n@>-|~bq<}-AeW6ZN$z2CJR^B>g1G4|_| zL5{J%Y)2f}AMxQhh#SX8Jh@%One##XIZqrH&i}7|yl{SUAOFaV1KJrMFyjVhJi&}J znDGbmxPW=Qz&ws%9$zqzJDBGKnCA(Y=MR|Y6`1E6nCBsw=O^27-LXHeJ2204FwcK5 zuM04*7cj3QFt0B#uRAcWM=-BbFt1-QuWK-`cQEe*VBR0V;eCV04)+u8FPL!vGd^I( z4a|6g8D}u#59VF#w>47|pDdPF^k1c; zpTEkKfsYl-D|NJdv~E?VeDYASyvz1fje6u}%D?P$_QvyTN7ZL%%7i|}@*ZhYFM8?8 zOj+EmSl-o_*N)*6! zrc^HK#)O50PFQKU-8!w_H=NHy z)#8TpY;pbDhVvg?agpJEp`H7S{)_|0VSF$?!{YYOL~|J_G3<)$u$^DxfU`|YvFD4d7!cYl*9+5aee8c^O=OOMVJU`LS^A`PiK4To7=NO;oKeo&30`uYZf_d^f!u)xC;eI=!N=Io@ zuaN$Z2=Aq+cS7-i$@Dg+sIC zs=0;p-nsGPSd)9Qr1J}wU)dh(a&wm4^lah0xebrRDrICz_UOWSSEm$=KYvM|2R|1rxwop z;m6YP#m{HT(5i*=?lShb#vps&E@bZ;cE7lfVI0DJ#C6K+_pfx^|El*}9LKkhbd(!= zeWUMnWE|_?>t@N2y_@v+U|YK;Dt6BnudD#Ea~;u=3HEN6&Gd6lo^|IaXo%9GfR$)+?X#+m(>Lehx?b2hOa57Bb1ts;gw!l)T+p>ou9PLEHf_@Wd(X;}VzEs+&d)nDrQW1X zI{v^Zyf9Cjj&T_kW&T>9@&T^i3&T{^E&T_xd&izGy#sT9nJ{X^I z!*&@@%!hHtJQ;t?pT`CJRU$V_?rE`8_jhbgmUJ*XH4e4j%#!a@c4~ZzzLX_T*Vw6X zd*V!(D4twmMK%d+pgQ4KPgiVf3jWY)AG?wNyypm z<~bx&*3Q|k^Iv>-ru3V!U5{6)_0woGb-Nxfwj&O;e1F7;;~;JvAMxaN5ogW^@#j2o zTsVImFYXuGxxeVoIA9#c2jeqt*e>IV`7q8pPal6AFCLfhc%8Y{+%@|@>00Bx5%=3B zUv!kmzu1*SrecxTA|(Y|9murn9$47p!s$pbg+ z%*8vyBY9bJWy_tpcxUKp@6~fE?aakH!^Vf~d&rR;xp-%|<=QN%wPZ&w-Wd`aX35+! zJ5Je0%#(8q=N#@=c%I`q!t)=`ku&$D?YaNm?n~kM7QVawcRTmOch~<8@6vy~7WkeY z#xRU+IDas88(ce~{=@e)^x^v(nD-fMH`MUM?;8J^dOo(xcSZ2OyLX)~CTQpHBQSqA zfkTb!zv^2Iwo5G$Of3#fjSfuh4opoCOsx-04G>Ii5KPSwOf3;ijS)=k5ll@IOsx`3 z4HHal6HLt$Of3}rSJZxSjqscYhvz)ovF~h0A6`dbp0{9rp91r{6`0?%!2Hey=Jzi! zzl(wSy$sCj4$S$0!})~Y0r`CpefZrF%FhjT$}H_4&1OwC0}i%FEVOjjFVMO1bu)n$gO36O|wCS0{R?;AG|d<|Rh= z4Vt0+T#E+Lb))7e|5CGAROiF@{>Wk6Ob|B{#LWb8GeO);5H}OV%>;2XLEOwoC*x*< zxS1esCWxB};%0)lnILW^h?_y&9&vFq>rckb1aUJ#+)NNR6U5CRZr8fFneN9L*kqPX z8aHrD$L5iVHKI`;Y|!?n%an_{O+PQ@e}2vd(RELLsJuL}cvS7{rOIR5 zpBs(u`+@Q|EsI9uE4;6Kdt%|}t|RUky_a=%G--%yFY|VR=(fqO|Nh!1%&|_(wg1`E z4w`7*=gQ}``O&=n^%u(XFWzq+ZuhnF6|&ECyl<;=<%#>u)6eZxF4^J-^Lg$b<YBaWg^OOb|B{#LWb8GeO+U3n$}dg1DI=ZU%8nba69he{{k; z`cN&6TcML|Qr_Qb2KT6{&0K1}Yf)VJ zs?zV7_o|+!oc>A7biV5xh|m1{S(aY-Bq>!dGf4j_(o0TTHPj_glp?Kert*;`$Up*xy@6} zro$=9_l}ujdOY3oj~vF$1aUJ#+)NNR6U5B~aWg^OOb|B{#LXN(88;Ke%>;2XLEOx( zC*x*4J;{xft8X#pxm%Kzho?0)53a1IJfdMkbLR+mj6NP&-`xJLJ9f)<)iOoX zt81St=T$Mqx4Ywe$<^h|@m=n?e{gmwlh?s<*J_1LSARbA`})(gbF*Ckgysv=y6$p3 ztnc$_E%sH@F?%-~pVn$h4dnwDjZFLOb$9K&@!kDteHzr&_AwXUl~%fRqVkPZ`ln5K z_3z3@9vqNXIk$mw_bNlvzAD;SdDW_+X=8RYRlfecyVI65aB*1G@7lDXJzHt}kWmHG z-u%AfAK5fH88;Ke%>;2XLEKCbHxtCo1aUJ#+)NNR6U5D2b24tG|H-(SdMD#%hM$a^ z3F2lBo{XD$^JLu2*pqQHLEKCbHxtCo1aULnPsYuBdNOXt#w{m^8`;d*+$HD3p_geq zC)6F9ll65o<;R|RFz4}gO_b|49FSA6hC5!r59*gw<85~z82;=%IoqcvXrK5E!*gDK zxwi5rmyXUk|1)+^Ygqy>!iyOxp z-{9tU=vdR(;p^OaIKO;aY}$(#>pahWvw7^P>)n0q#=&i3xs}|x_iJL8*qED)_OaJy zEVxd|Vcbj*HxtCo1aUJ#+|00(aWg^OOb|B{#LXN(88;Ke%~UuUH`D24+|0cv<7R@m znILW^h?^O3GHxb_n+f7(g1DI=ZsvxQaWg^OjD0S|g69I+%>89*Y-$yEPdjVubFqcS z9iu^OCdKx5a>uUCeG_7vu6D;dZ_Sgj@r^3!v6$BPiP-4G^2*~bej@hw;$@X5E`1`l z`dDe@ul7F~E8f&S2cLUte5`ZKJs-bGoEU3-r+aSRQ{aWz{Je9u|E`U5V$Dmq=j@cH z=EWx5;-0@NH!g@>*wgX+uNKGFp6&W9n35Np+S>hZ`rki@wXg1;%g!WA`jxao6Xu4+pq8zt?_4Y-}m_ERKD$JvM4tWu1?G_lWU5#J-b| z!?>9sZU%At!Ntu4aWg^OOb|B{#LWb8GeO);5H}OV%>;2XLEKCbHxtCo1aUJ#+)Ue( zaWg^OOb|B{#LWb8GeO);&dInL``#N5-h0XB#)C!U3#z;Ku@mLajt|K^TjSiUU4eM- zt!F7eIr5j-(l>t5ckDr155&HjcR>02AwR}mx@*7kyVdr`PQ3n|@)Q5q7aKTfyYd6I z_r(fq*`mB)-oDsNBfn9e+4slT_*dNTf+mN5jcv~QSljQ(I1!ss%l(cxSf@aIbjKyy zK5+Wk@pJEYzdOFXxJdl&AKmYfDjSN$56yM$J!YI2pEAky|M80w@qcY|%#ZJEg~E730NsuGjVl?x`Ms{xbI)%Ko;B``=bEu>Z{! z#?1tAGeO);5H}OV%>;2Xh}-WjZYGGELEH+uxS1es263C<;${%HEiP{6ZX36mE^Y>K zd(6en1aUK8oQ#_Z;%0)lnILW^h?@!GW`ekxAZ{jzo3X#^~Uq|&(C>S`HL-O;@37FrrddKnfM3q-mffQm5D#S=?>){Hj*HIJ5$kLu`j zl1qN55Pzp-OKpGm=Snu$!|5v1F0C5hw7apkzqhS=eBkp=lgU|ID_(4%*a_{H%nYdHO9Xm(1x%iT_&Y4>8&_@TR<7Idh1^Z3{f&2@aM9mT05 zSxt!?#?1tAGeO);5H}OV%^+?~UEE9%HxtCo1aUJ#+zjIOjEkE=+zPt5nXWc&kGi-S z#O+-dH-orkxVV`hZYGGE3F2mgxS1esCWxB};%0)lnILZFo%$K^4P&ici!q-8mgoIYC>8v; z<&u+LQyyNlMtpnUqsm*m)Qo?&u6i2!9IH}0-r;^xp53!<{Qf(;C=aWX7;n|!U&`y} z{5@W^!T{yNZ#RhFHs~JZXG%AY|M;cj!@HZt_un-{+xr)Y?4pX%%DdNJ8h>Tj3}qjy zKXMp16U5B~aWg^O4C1!X#myW)88_3{#%+L$n?c+zb8$0>+uJT~25~#);${%HFI?OV z;`V}zn?c;pad9(<+h!LxgSdU_;${%H_AYJ)aU1O7W`ejG#I1^pn>lncZYGGE3F2lD zw=@?wgSgFgaWnqfG&o-Vngv6*j9a}|+pTUHw|cL#)h**z?^U+CW!&n$%2v0GTfJA= z>Xvb<_bOZ6GH&%=Wvg4pt=_9_b<4QbdzG!;8@GC|vehl)R_|4|x@Fwzy~YtM@8f-7;?VUS+FW#;x9~Y<0`H)q9n#ZfWyd$GSehR*qY}SJ~>8ajW+#Tir5l z^xG<5urgwz_59>b=TV?~Pl%SJ~>8ajW+#TfH}K^xGV^;4~wz_4^>b=TVw~Sf6SJ~>8F{}3~Tir5d z^b=TV@6EA#ud>xGbFAL0Y<0^VtM@8f-7?4Oy~xGjn#XVt=?;_-m7eNOJnt3Wvg2ntM@8f-O^aSSJ~>8 z#_GMwR_`@d?^U+CrLlUivi}zIM-Jl#y_a!=-pjZ_?`7Pe_cCtKdl@(Ay^I_5Ud9c2 zFXINimvMvM%eX=BW!#|mGH%d&88_&?j2rY`#tnKe;|9H#af9B=xIyn_+@SX|ZqR!f zH|V{L8}wer4SFxW18Up?hHh!B-mC3aw=`DoRkpgNv3jqv)h&(HdzGzjX{_F>Y;{Xx z^Xydpy~xGjn#XVt!`_cCtKdyUn5wNDT?=)H^^^j^jddN1P!y_a!= z-pjZ_?`7Pe_cCtKdl@(Ay^I_5Ud9c2FXINimvMvM%eX=BW!#|mGH%d&88_&?j2rY` z#tnKe;|9H#af9BAbq*T0fT3GPR`1nzt6N4^?^U+CWn}eUWvg2ntM}?Vw$&|-)q9n# zZfUIEt88^kWA$ETt6LhY_bOZ6(pbG$+3J?Y>b=TVw=`DoRkpgNv3jqv)q9QAdzGzj z8Ckto+3J>&)q9n#-WyrHSJ~>8k=1*Zt!^1vy;s@lmXXzam91_WS-n@;>Xwn!dzGzj z8Ckto+3J>&)q9n#ZW&pE2)q9l@ zH>>v|ZqR!ptM?*4(0e1R_bMZ9R_|3t+^pW4gFc9x)q9l@H>>w52XTYm8(F~d{?`Qm zd&>Ru#?eip<5zv8V-{W0Fp8EsP49Hirtp3n{I3cA_mua6jL(Zk9cH@st3EHC9X(v# z{RTPRyH@!A5d5zR{`Zvk+x30Nn-vq>@6(%`j51aF{X^d?PWRg(d>;<}*98B2%I~$+ zWiL*xR5DY?w7i&ny5GXVZ#@(IFPQ&(ivD1?8{?eqd}7>}(`h@QUJ?AS3I6vKJ=_bXr%>TkjSn&5x29vI)IdCtUn&e-!I&U5K>+Iy%c+jEBhYl8nh z<$H%cZ{s}Y?fD$%wP4S4e1l8FbrG-$zmEj}i)(@Zd&>7a-yZYV7q+GB$59Tyjrwir zbsGFHt}p)YDc__0e(5-Vf0cb4@|oZIecaH_m?#JTd&>F>e_Z02zdv5e{x~X!YghcS zMmvwGa`3;WtQYdl&{)!P5en%kxthtsXO{g0f_Uc1n7&a9cQqj3n< ze#e5f-?(S~Z?9jx3;FwV>`cx}0gY#nyAca>UV?j0EV$?Jce>s;!u!dYoVCdslOXph z7Urx4_vhH@?zjHltM5W*ev|(BZ&Dva6Fke5!{1ZEZ=Bc}P3g}yC4Y@;4E?pQjC&@v zP5&+wA?9Z^;Xl`e{d=Is%0HWw!{5unZ`jzGZ#sYeO~=2tYYhFnlX9pJ1i#s1XTHh) z`8QerJ4<8e-|dzCJ3nKazrNzknhN(_`*dq6{O@9ooByq?9O^&e`lw)SPb^s56ARY% z#DcXwv0!aaELhtU3)c3;g0(%dU~NzAf8v@buVZKoy*8p8Xk5&#(C1XJHZK;e&5H$V z^J2l;yjZX{FBYuLi~UvCG}>o6H9EY{|66^}>thO@jibhC&<2s2e~b=Ah(6rxW>(2`^uqS9cajSpFfk+ zXX6>{X=*%!cYgh5?e(ZL`8Y0*>9qMc!8<>`8}gl> z-?ednIORKg@XmiGpU&kWo{~=&yz~FNbqLVy!!-$K@?l*b@oDp6gLnQ@)?I|_G=g`2 ztZ(Ey|CxMt=L2v`KD)oh@l3}$F8tnC#ydaPr3CN%Sf9*y{xg0Q&d1{vKZ@X;A8S0Y z{wj{xhU;*GcYfp-(1+)YpN#Y2ImJ&Vc<0BO9IThqcn0tMr>qMK-v7_|K{+3-Q~aQU zH91_PsPPQeT%EEG>WrV8uE{yApPM}=xyB6d^H`6n@wC@C{TNSK_Z6(kIpfFZd@N7# zW3=~7uF1jsJk}3uJnb_Gc}B|q`?5Z#f;Bm3{8XI}?J0h$_L&~>neM;WYuti0gm|B) zr}P;=WalFde+>Fa<9$Bg4>?$qgZKG=yJj+2lXE8D!R3jZHs8U=(BK`($5z>|6H^Y> z(2`^vay`gQwZj>egMLzky{+I&O*42p1m`e&1}UuUcApY_VY znw&HF!YE{Xb;AKluL2f&L%aa+sGfAgOl^h%dMRqR~=Yhn!fXc zws&t@UJiY@U-{tCa#H^Oeaf?!my>tD-J@K5YB}j%^n2wV50sNWzwT0=*1Mc+S+PU8 zea~|8!H8|mQ747l1#`P#ZWqk$g1KEVw+rTW!Q3vG+XZvG*hlc1HIM0hUg=d%#^*h% z{L+1PzZN~ByymHLvTEfB<%buSlb%H$);aTkF(&^P%>M=Rf5H4;Y_~{8vWywZa^Z%zbp9M4a|qknAMG3m%<;k8E|~KHbDrS!RgR&w{-tucXH(>w z^Brf*PLZoCeWC6B7T9qrtXFQFlOmIguT$=C`IF;oloJ-FNc$f?SH5>niZtE(na-bc z!~DZ`_D4I%0dssXw+rTcz?>(T^9OUkz}#Oj;{XohGc&io?3=Vv=SjwKzx$^osq~B6 z-+jL&$+!b94sA--m)wmmKBa2cmkD!R4C5{8%c8C>wv(=@FHh`py!YPvGO&X?F54#8 zm*u0}wm81dGiYajv~wIV#|Lw}V9p23d4j`hEo5#N`&jGKBzZ7ptsbv_)01SX{@}T70T}qI#0OE>>xL_`euGY-fM8a~v?o2Z#5lka=BTKJ)e`%FI&kTAN=qN%{FpRwKWItts_AAL9u znB#-P`y?6deAZw-WVDC(D>B>vc>lrw^4dY4ka@164;g*NwQMe*Z2esKk&O0x`$y8| zc6YAc@pL5DXE{z?9LWO(9e?~)BxgPB&h3;Vkxc&Do%5qEXfB;fI4)hgxujQf*G0p| z&E<*m?mjS}d2=~ZV6ASK+rr$!cJ@a*#{qMEFt-cle88M1IGq2+B}PgoyLSdMejUffHb-)F@I%^X z%RBbx@Uh{_{ijAUW|rgE?u%saeU8Um70DID9G7Ss$&f{k>y(M4a0NHc`-hEGe#vp( zMkA}cKAeBNFlX#z*v|fF=Qv=F59W5koDZ1u1atmi?iZN*3uYX^j1QP`12dlBj!&e@ zBdITHOhPX3WUBO^FjdkAqmj*mHn?d*?sjsxcSU~U)8`G7f3aHA1vlJTayE<(Oz zRjPFR(%l;u2neD}NKes`Snj>BKSQKNR%GppvB zYtehJIoB#*?Hn$bFK$+@&?sDH6yL5~(Jx$XmNn0Q951eS#s|B0`oqpRV8#bCFPM73 z)CuNV3jJi-dCkI3=KO?@%Uq)nhYTNg%_PIlxd(qT^L`e)KazUDu%BBIDgBFHH2j^n z<_tZrJp5Xu%xZjA`L*YwWX;M`%Axt9 zZFg12`1^H@kb9?Zs{Q1I2$^&EmU83O5%NN*UzIN$_3nc|82jw|5whm;P3;%sLxXFl zKkSSHW_&R7f~g1W>f9PoUVcBbGy--q#`xl$Q28YAl?d>I>mD}`SH5r~R3_hlOZniv zP)TUpPkHDw<>f%8vC7MHm6vO&vot2-Aiis-KkSSHW_&R7f^8i(L66I}7izclQMUC_ zw)IiA^-;FkFUd8UnVORh!kU%(WUZ=?`}8^oN~sz;FB-BvZcj-;DTV*tZ=BmQJ5l z+zkF>aj+zPVtC{5U>O;1_@`FEGJQw|^$Cd&mg0lTD-R3~mSbU|${!U7mbhiX%3o&; zmfhC_mA5|%lDp~3DWAU`B%>dcRc?4QNQ#^aP(9QDZLXdEurm&r@xjasrXDbLf~g|Oo~RKjFFuObzLQatq3437Sk5-O4z#!$EKeG}tDN=sU}^qpL*+bKLZtbG6y*oS zLgd`tIOQjmL*!n&XypctL!{s9)s;*13y~L+t0=!aJ4DvqtgM`4SBRX>F3Lr(hRCQD z#%EHNP?@vWe70*qs03E8r8=n%V{z^Dhn;c2j1OjBF!g|`6HNVJjtk83f>{SJ>jVDm zT9_OjnooP}^6{_3q;1#CYA^kR_w1c6t8()zVbW$}Hszwfg~{1zIh3YCUQ~XV zE?mxhnoIe6&;H50+{*L3=g%)@zoK)A@u9)B(;s%m0W&_BdBM~JrcUt56O|-y%^=O| z^1jJovgYGbYJWO1ObYcXtvs@Kn0y^wM){ccf1)9m%=}MH4wJX)ysq|X6~km;FLR9~ zNYo|Z#j00wTF!O?`2TYw{_6U4rZ; zzMaMXK?AM}`h%$rOn)%rfO$*D3+Qwg= zU3Od7VKVI1qDo89iXIW*-1$q(&V{{{FFo*=KeqH&{^Gd5{Pf!}(^CoaI&FGhFF(fMiHDpKbFrK;$(O^Y?sZ`_9^F^Z!SL<6eueZ6KVZ0W-1c&kcFfGr)1Q@-nX7y0ykZ>Wa_#hoeXWfHW_&R7g1c4@lxh{$ zYc7{Jc;Cm3o0KCG^XKaZfpWKE2Ic!r0wv@1$Le3AX`qZLc1=0CVW13}^rQ0J#6T&% zXSeEP9OQEC^oN~sz>E)OUa+gpW!3>Y-!C61i>j_v4Hv=!W$f0~|57X0PJhJb977zJ zxrV^UWw)m;yVpAzG2J?lVdu4p_+;1@AAMb(CS=t0nGAbSe4uoTOurf2zDA&&diOcy zXDS8CjCL<5N0$hcGw~Uf_ht)}toJf0hu$eCB~!B~Cmt>*0q>c6^rIE!B)OQmN0<7z zoFsf?_(I73inBxL-ykOP=%=&;^WC@a;ae-PNmmh2kl!S%p)c(HrJ$~miFDS>{3Y0s! zvMWD*8YtVc=TXj`DM((PR9LxMwje3cx|BW}GY)dOcKXB4IAF#HGcVY#8(LeJ?X|3S zyRItRbyeA}tIBp=RkrJ@_K0zi%eB)VcE$lSKA3sIt~Qrh2h6?nBLd|>pUbM@sJB-C zc4EJ3pbz4>cGusXOJv04nuE`}?Do`U_j)HIj#~#Z?7Y?xpA387e4&!GVz&Ojm<;>D zUghOr&ry-!*WW2G-Bt`&4u7M(%IZyL-O1+;Z zDfccA>itb@n)0Wwcs>ngs(xz57+pL4VP_mLBDgO zxleoL$)3GOx3il@OBE$UrAeBL@uA1H(;s%m0W&_BdBM~Jc6HkSTWKyb#%2E>r+V!F zmzC}RmzC}RmzC}RmzC}RmzC}RmzC}Rmo*pTLyv2xKkSSHW_&R7f~f~go!}j#D@god zQ%{$x|59EC)*7pND%~hA9izu7XM9**7KD#iZk4Hm)GRnb`B9+?a_kqw6)IGaP7^1p zeR!P;a<;gMAK$)$tQc+j#rV+R+UXBFH^x`qg0R7qn4%d4^!AacZq{(zPI2UtqQJquem=^eyYAn??=>( zUbuGp!_GKh#s@Pmn0mm}38sE9#|7qi!K?$A^#QYPV7H!Q9)!r~R^zqrWb~-Xpb%;D z+Ekqb^*#%c((^x2ZnDAqTkD@@t^WDD5cxR5aLm~ddC=Ib)s=3BNW1pt+Hd$Q~fRveOyM~tz_yyJwsV}P{Z`4Lf*3SRTa~_ zldqMPaYao}Z$y`sCua>WYhG6R^_r&o83(ysJN;p295Ca9nHPLyW*Nyfa*XP9`O?Q_ zWLu#5J<=}&%E+FG5$dy|cNr;{GE%vl$M@QeQZDcLJQ_S&dDrMNQhEHxs*`b$%eB)V zcE$lSKA3sIt~Qrh2V4vJe<>sR&YOE&j$LKs`T67irB<%p_2)H(Tx7&_*9w>2HPB^u zye_+Qz-4zHy3A_d6M)nObymnoT9DK#_s%bHDX~0(XDcCev|vxm-K_VP_mL zZqr`$S6n&i*3U-{ifsWRt|;e2OPrQ;U|)GpgoB`Nk>^VvD6l68~e+yhc& zSbC#vRFhOWQQ$irJGDW-Yo|Z#Gi@9&|wo3>PwL$S$+6Y&!aRvG<;+yo&p62C+UXBF zE<_w=7;(g_`U1`Wx|b`x$fH&HEuvI#!?cFWOu? z{gIb(z>E*(8~}G%=gsFgHfYQdKc!0cz-`K$&(KDHuxqD3?2H3;*FZAtyq1xd47vE9_ZGeeRD=jy6l+%HLnpXjWd zR6R+W{Mt#md$S~YzMu1A+oE=-fA zd&g+rQ+vI2K6I?|>sQib$8N({o_$m54IHQTxcqNQ!=~evSC)BGI@O<`JguS^zxhPv zJAX6RUI&rFj=n+><> zpC-2}n9mM?TGiHnoPnGP!7^LS#>L&^s|pAqH1S5EOhdphc{a@qEA5*l(u z`P{%bS(p8&@`)L761UfIqfK$LzR5AQPy8uPzB^!e*3&o{_M^MdXDUE{lKpHI|o zpEH&1bEdL=&Q!L~nacJ#Q`tUeD%PY=)!8UGK~>bI-;> zF4sVKA3sI)B~nYF!h5uE-=Rn zW*xw+57_Os%e-E24K|Y`88O^kcO8}{N%A)fbnL5h*O5N0=Ia>gkC?8V{;)F+n7sox z@$;Ss;&y7Bl+&qFyx%tE=hmmn@wOY3Isc)Dp9Q;i`oqpRU^hN{0lUjw!=Z-^AI^W+ z$*}X=U%`y4R)99y;AGxvb|rc-9GOr+vh!H`@E-YpZApQ^PaMO-cz>E zd&>5CPuV{2Dck2gW&6CR^`{=_ckT3topHd74`yC4^?<1pO#NVv3(WC?SqJdUw~{4e zr_rj@<+}q@B>kkpYL97_B6R}{AFi4rS+1LRKSvf$k*hx$?)*oxG<{-t*pJE5KhF4n zvp!jJ?lzq9(_|UiW{Af0ADApv$`4gO(LPxQ7aXR%yh*a`E-+mAl{b@RZ2>Ysh3mb92<#`SjQ7}?Xn zaCGSyxpB>meN>GYS(9eCOXC>HF!QL^mT{2RwbLJV#sM=vn0djdPgJm3Z(W}AwaB2y zA8Bpp%n`ZpPJiXcLp}c+hU<3_sWfGP+LIfKtay8%a;sRc*OkqhpV{kg6>pybjJ>zl z_k6DpQT>b$4X&O3urm&r@xjasrXDbLg6IEIRaQ=Jqj_Ckak!cs_^zeed#$P_IV%}1 zH=&wLy!D>i$9JwKg?=~OA*Gshs$+aU4y`6_9vWWuN;P?O?S1v{_oS*+F5X(l#rV+R z+UXBFa=;mO^3uwQ3vhQ&+kytCD3$Aoyvp5=4p=2PP(^BuF-K{}7S9i6H6spCEUn`da983(ys zJN;p295Ca9nHTJ8bD4EOZR4B7%f`=v3*_Zz!LFVDurm&r@xku8N2VRuJM_5MyStu{;mrom2z-R+CZye{D5GUqVjkl`~pqLxf6nMZ#&OLpuL%5`eVkvk9dy;pg+mfVT@ zN;$GaEg3g+fO5bGwWMC1=ar9q=yBLUKYZ5OH-N3bvW=rW*u>X&X03(@=ydJ$hn;c2 zj1NZMR+~co9DBIquT1^0+xTin-?=Y=%jg~VF2MSUeFiWVte@O}0P83BCBXX0{R*&t zavuY%pWNR7>nHX-fCk0~yLS4+&NyJk2Qx32dcf2Pw(&PXv&(jjYPWfnZC+)YSJ~!O zwt1CpUS*qi6Y?^?qet!Zhn;c2j1OjBF!g|4ow*xUm40bgw1#AiG5Gx|vh1?immq#f z6)E$f*>m8@yeiVBquGm~&#o%cWw+rME?1F&-iG&Qs48!dHU3#jR+U|u&7KAst5ubw zcdltJ#)lr)PJh@L2h8|j<^@v^m^#5WzSh%aJ4UtJyvjDOvdyb(^D5iC$~LdE&8vN3 zd`FMk=?^>OfEgdmykP19Qzw{X0iOu2A~WWgcivj|7IO_`{Hu? zSut`xTRW|f%a5d%Jp4Xc?Xw%yk_^f5%A>sXdEDb#%9p3qlI_3NP(HGumh7+ohVr{V z*OIhn4A1?umb_lZ_$)0FBT?(kd*2fzMmBv?Tm1)kzxnxMMUwJ5?>T(I&uPlThs4O2 zcivL&FeyfcZf&mhp*GaSwbLJV#sM=vn0dj}1Ex+e^@BMsFvkmK9l)#)_;~jOdFl72 zo6#eeKj@SoZR3*Eo@r=;kIYhC4&AG!Jn;GIa{q1>9V6pIgKMWh?2MzDZG15Ef~f~go#4s+Vr6z}cg^c^ z_1d-N>&ac!UgEXd^5xEM%GI*gmSZ!G|L7~Ra;@M8YR|AUR_ccv{_^u!iGI*s^)n7~ zxpw-)&NyJk2Qx2t-P&sM=d)Qfm&@5lRg>~BV;lX-aDY0Wbn(W{Pmb>Qnp5Rr1*ck`R_+aJ* zQxBLr!Dr**W$>Q1n%CvE*%D;w!1vXj?Owe6oV~U3lwaGVFGYkzjjoQnvRdWqWT@w)ZAwdv8*< z_aIZXNV2&5e zI)L5!*xE+HPDTyw^%4cP>%6jE=aua`uWaul%66Ssw(GpIUFS6y<0G$Yr$6kB17>_M z^Ma`dOr7AS$qCY>hWR_2%d5S=w>0-Ne{(yuFkUKlHC*CAylk6fc*(Evl4+>nCb<%% zPmJN}p$T&1r-7=UagfWk(;s%m0W&_BdBJuq()ze;uVuB{bza%7^U8LeSGMcCvR&tu z?K-b)*Ll^?_|V|m=?^>OfEgdmykP19Qz!Urfh0Ln>V3`Y^4bN7Qnge+wGZ5vC;>P6 zDj&F>D4WU|o|Pp@rWEL-_QIu-WWu^$%6%&*$@ZK*mGjm~lGg%zD8Jh{NxJ%VSN^kk zl5~IEMS1mmNpgBuC*>aRCdrCP9h6(vPm&WKv{OD1lO&sZo4(6Q$*J)6;}|2@=!I{5?E$R)Q@4qW{0t)3wtd`WXkz`HA>0bIpg3 z%kCU=nQJfN6dfEZZ(RRT*XI{*)s{h33+NoEaxh-zXRo0;>5urXo&K=9akyr}PDU*C;F}S7_O)~FR{Mx3bSGwc@6kr$6kB17>_M^Mdhz;l{(3YA%<5xggRr{VKIz+%A%R$Ct{z z=82>>G2CXj$lhZs)!wY5$iXs(pYy(}`t;ouYCq)t&8^6QFO(~Je~UZw@p9#1-rwj> ze7sES!(7ng+UXBFZt*XIg`?qDa+wUoq?e`SQ_InCt`#puS z{hmVEeovunzo*bKGQMgv-?ONl{;)F+nDN2P3#J}0b%N){#Y)xUA8THhm+Xy^cS44% zed5&^DZRpQ(+sgvtKJB;M-+*bTg68zw+{805gNk2|d{7L>SP?`a_#hoopHd74`yC4{_f;`->30i#x>%7U!ZpTJ)JWCUg~|Xr;NXs zdf)dcV0phjK7z9-zTbm##arFo&K;h4w&)5%nPO-Fm;06 zx#2SFhP9}8y;ym?ZH#I=Qzuq3-TnAqYU|qRkNB(=*nTggpS9o1DBJI4lzCksFFy-* z?evG8almeT)(!T5W~^_}13Q^(4*Xr_TCM)h8t%?jm)&)kjF|5ALWZ4d4&swxACfs# zo}ZqoI?1s2?hqm^N43&kI)%W&? zoIfQ^?X@n4$oDslPHMwgTs!??XB;r&gP9jhJz(ktQ$LvF0&~1z)&b1=fG2zVwXSYv z?lmrBZ`B3&7U)}!p633lvX&GicVS92Z1{?%OHuzxkz zJ?vl2^$`14d%ttgT#S#ruATm{GY**X!ORP$9x!!+%kK-5ll{ybc6q$Fr{&A7lXNVB z1;eCQN5l0Z!(_v5!*4VUlNIgE-;K+E;O!CmcCz|+9~UM!C!{F1To@)7GMK+1_t@m^ z)xSJV$Hn;2;M(aAJL9NM8z0QPVCn%=r~2D*ffLGv%WA)7ns@2KaQSR}1&8 zK9XVQH3EM!?O0D}=i0KMW+@rFcv%$eWcXL=<1eLKtcn8X_V(w@SK~|N9Uc8;S=p7! zqu=qDxDqRrFUI@J;R;_Uw+!`{<}H^ipUmSguWwtXT;#V>QlYxxpu?pk;{H;#=UeV+ z_`&ea;iV+kO~c#YDj#pT8Czf${G`HIW#ufA5Eo4vTa z@y$2N7c&-@&EIWTp67AlGdq;8W-Bh?H+CwI&Rbj_-rA)c>t9@kp53jyDzdl?+qg%$ zYHD$*{J~!BFSS9xYo|Z#j00wTF!O?`2TYw{>IZXNV2&5eI)GUpaNj2-<(55j$K|D= zB_(YANgYepw370}Y{TQam6WQ@47ZwCQeJ#~LVfnGC@FW^8h*65qE-!3WbGMe8RGCnl8cKXB4IAF#HGcTBWz^=}&txBkV*vYu2W`E}A8}GrTeyRud z{agHeI!hh#^Xad5!_POab(u=|#yiHpgs%>HVoGRzkc;ubuATm{GY**X!ORP$9x!!+ zaXs=pJC}dU@9#VRu5CqsJ+}_yx|ZngJI`+8yZ*j&?h-or`_8|s{lY9Hg z@5PR29ZuHvlkBZcO~z&OlL8OEReR~}#iiF#^Ii`>i(Iaq{;)F+nDN11W-268FU`}K zF8{u}{n)I5_Q@3c*Zk@ti5%ySF!J_d0pD7&pa+m3>=;k|vThjEb0wbLJV#sM=v zn0dj)e=Z_D?waQ`m;0S4A{!g6SN(^7D{SJ>jQSLO_$j( z%e}g#_->C}<~oD;cS4KE%X1fM{TmD@A}5|*qVeg2 zIIf-ku)Axu%e-C?|E{P1?pNmde_FMIQYg;MpE;uo%Df(nHE)kY1tqEOLe0z1BED;< zKkSSHW_+-_CcEse|72)$*DEsZ|Gds1zI$!D?9MSV;!KGzAwl^D>-XRDlDJfmLjn?mjzVe=9n|VFmX!AS2dK~dHYL413HvFpiZ3Zg z^7T>|$f_OvRWo&B?5>^uurm&r@xjasrXDbLf~gWn$rGVfTOW4P}Zd2AT>{jA%@sU7$IagE0-=^y%#Ldr6F3j5=Zc@N?~H@IuATm{GY**X!ORPO zu6aTErt1jpsmo0w3d+y1{neh=zo1;JHbA*o{(|yboq@{tUn(ej+7D9R@?t?*H-514 z={yC!>vxE9aIu0ieeY1^#v$Ib#QtH*r(z09+m*w0ZZH@0xOV!(&NyJk2Qx32dcf2P zrhahQGT#3IPaDlH-}tGN-1*wnVUPEBp|$A@m&@ue%?b}!&HW4dOP69sf9+EKQt)Ln zuJE${lJ}3nIu^!3F4s2jl$EbKc^!YiE~|Yz;F?A{5kH)X2fZfFYJx-IZIT_jopZyJsdiI$Eno>6=G*l1aP$Z&?{(Ng2J^lHyLAX@Hr zGrV+mv|L_d`1c*r-d;NCx9E5srXJX-2TVO+>H$*^n0mm}1EwA@^?+SHUp*Twq*g)c=3qx zfWFakB)j32&7x)gn}^jtt7f#+-fr?{DH$#A)cam*&b-H)iYlAft6%V%HF9=Y5seX3m9e_rj8r|Zh$HHLFfIPOZ-$C?o#s=YLa1-b$4XL(lu`?yDU-52YH0{to#JV_XHEH;nPpjyljE^t1I3ua6(bAhP=Ol@Fl26HT6juFhUgINi-qDUZNq@{qFy{c6a|6sd1Lj-;bB=*I_rRQ!V9r%A=P;Oa8_YQm z=CuIkH3H_f1LidaX1{O^&Y2l4VGpkByn6lfXqk2ThVq7m(ehy1P33IfeW%5QTgtn3 zMoYhxUzJ;&jFxV{8;-f_-HZF&R{Pp)wdChBhR>C*C6x=^QTwf$wPbvd;m6+l)U=oC z_m}^KskMA@K3G}H7e9};uLbiSJnrplVf7ThP|K%t`L$X;{oyxj`NjqN_u0)D;otMM zYpMrvvNgD>jQDq_UQtHgC-=>I2tBWNFbtiOvKfZ{@`o<@#&u?sVT_k{)Peq}596S2 zjE{OUFX~J^s6Tb0FVxR|p^q-p2X=lI%$Q*20#gH++Q8Hd=2*b!9mWXe*uks`n6(14 zhG5nf%$kGQ3ov^GX76anoTNYIB$#sm%((&PoB?w#fjP&(oO@u-NigRsm~$A+xeex= z2lHA0^BMv3+5z*L0<&MZ?)ba`cArschd=G`;j;nQeQu#0{;r+Rb+GeU7oVja?Akwy zOq3Ou%-?XbN}|O6Y5t}(rKYz(Y9Yhdy#0O$#+tuD&3!jfT8|hTg*eqeNR+O>j8QH% z#@qY1iQx&05+(an^Z(GTI}>HeSBCeWPn0*88vZd|lF$BJp(LMwr;16wIH`%=dkQxG zJ@0)4=3Uk$$*1R;kCJ>kM-5H#>3?N}_x^$%7wmZtPE?)nZ@*%aGUA*XI9VC-A5@>B zjJ!848-|`u?LJXEbk;p&82VRdo2qtz zvyZf+4)jNT!0aQKeFU?QVD=HrK7!dtF#8B*AHnP+n0*AZk6`u@%sztIN3h$+ZeImS z`PIB%3rq(_TrRM{&vt`_J^PS<^SHMzv9Fm3HHUm zayi(SclJZXF?xP`KE$W9f3^^x{%kozB(CDH&oLHj4+C5OaIlS|Y~w52yb?4?c1hbD|_7TiJg4stf`v_(q!R#ZLeFU?Qjy=rr*F9v|N7&g%F#8B* zAHnP+n0*AZk6`u@%sztIM=<*cW*@=qBba>zyM27Oe4G?+H)1p9*v*RG9?NMXl|Pg? z`KjV4@sBl%_vIbaHr}V_e2;ja&h{V0`}98? z5bqlo>}v-NS3U4=GG~}F;@mzsR2lJ)zi1eF&$bz&cIbKO(qLui>^aad^yjN(7~|R= zVi@D49d)2T>ccpw8{?y%%!@ix59&{y=nM6;U+ClCG5ZJ~_7TiJg4stf`v_(q!R#ZL zeFU?QVD=HrK7!dtF#8B*AHnP+n0*AZk6`wZcGQ9Xs1KNZ1hbD|_7TiJg4stf`v_(q z!R#ZLeFU?QVD=HrK7!dtF#8C0`}oShqVi0-=~1}u#ttqj?-ZJ*d}CBmnOD_3JKg!D zsPyP;p0BDdDk??Sn`f{_TZ&4JyoTo=Eh>8_nrF7Qx4h4mH+(U3G1>XZJlElG`*(gZ zJhJ*<_UGO%=JVh4K`~#Pm&X+I#SffQ%$K+Cs$xDp1GjmfwK~u2D(2JQU~e%U7sl%{ zePHKj!HfxJE-*EKsSQlcV2%aMF@iaEFlz#4t-!1yn6(A7=3w>$%pQT+JKATRGyBxR zztI+RRu|$79XUgv#}NN)&6&!`yXlf)=&9IhmfE4S;a%in&ExcUU#7z^82p4A;tDbZ=Uwl2ZoIDhrWEky z{r24gK0Sxqd!Mz}UAgWBeEJvmDB!#9T&54^DnAQmOfYkSsR2xFU}^?)EMSfi%&~)6 z6EJH9W(~otEtoY2vln3Y2+ZEm&Up)e&S%8oJV$)af8^zL0X@84pp(}T^z-_{xOm-R zytJbZ^hbRd2X$k7)RTEpXX-)ysS|yne)bFV(`EX=&d-7w6Uu3uev1>;)LTbFaISFZ`_6AnZem|D+86z0oI?5obn^6UvBRbL)@F z$lI#0Vd%Lv?FY3(=e`KT(0?_ZVT|jQ8^_fLhPFZ@5+eoDuVI7`Q!R!006;?F1}@7WuMp{G%YvucOVeg_Rhf72}I)Q)k5 zzG@ibr5$ykKkCCcs2k&>p3I9nQxED-o#+eovtO92F4G5geiqD_VCDi-1DM*t)C}fW zz#Jo(V+XS)VAcxE8iH9{Fl!EGFTm^(c=r*1-~F!Iaev?aV#XWCxKTClC-~G;I`e5GjvtY&qGZ&Z|z|;n&W-!MB<`}^o zJD4>AvsPf%5X{>cgAU%;RD5yavB1@U>`L0;aEpojM<=;Zwi`gvc& zxOl(Acxgu+=#Tm^4(i7Es3-HH&eVhYQz!aD{p=U!r_1z#ou36WCYZUv)BvV7Fg1fY z7BI&M=Geik37EA4vxZ>S7R;K1*$Xgw$NL@rkHGsKokLPyg#q&J%;5nZ<@%&Hy z_hkSb%u7V zKlI1C#5h>57$55x^J0CY9;|!RiS>~Bu}<>3bD2JvtNbjOF~Q6QrUo#zfvFkHv4A;7 zFvkvNO~9-bm^B2mwqVvA%wB-mBQSeMJLfI@IiC@S^BnOx|B;v11@!QGflgjW(9i1& z!_-9Mp~RQBUSYov8=)r%v>R`q?kcPnYQfJ3k9%OfYkSsR2xFU}^?) zEMSfi%&~)66EJH9W(~otEtoY2vln3Wj${1cK?B(t*nczZWc1OpKHGPWttW3!?ycO{ zJ1hCS1MQWI*G-YCEgCA#uC%DBJj(;bZeETRqBFr?S=Wj#1YfjtgVwxWF72 znBxL-Twsn1%yEG^E-=UC*f%-;${ZK$92c150&`qojtlILYu~|O$u(e;j_aqB!P4a8 zb;@fW2TQ9BtCZgg4v}=lRw%#LGeq*8Gw+4nJ`y62b1hc;&B##cd0>I^AIn1}rpSEd zsR8A^-{YD0g>x<}FE_TCcYcSIs^GJi_`HJ8KO}cWU!1_+6@BsV9;@if`^~GBe0o}? zR`Thr(XEnCf9gk-eB*+BXE(FA1N=ADHt)|OPRR?qR43wR^V_G4ya9I(C_~TUN(Ysp z^VG#d%Fw^&`uEBhS9p!X$`~*0r~~~`AI3r57$5ayUeuX-P=D$~U#Oq`!W{lPW*_0h zK7!dtF#8B*AHnP+n0*AZk6`u@%sztIM=<*cW*@=qBba>zvyWi*5zIc)jyljE^#QYw zVD=HrK7!dtF#8B*AHnP+n0*AZk6`u@%sztIM=<*cW*@9ob_dT!_U=c)`0rb zYS}Dhd0Jn_&Y!8gx>p0qo@lu29}Rr=eO(*+{C~LI&===uQX^mdDT^BU^0vI&$fqYq z>9>43ug1LP)BmXMTfT9@e(AXlssa8#|F~HhaiTk!{Z$bE^_Av&MBdu{%=HL8`*-e9 zf9QPL*<72@fBeJ!zHv1?Y#8IE9d)2T>ccpw8{?y%%!@ix59&{y=nM6;U+ClCG5ZJ~ z_7TiJg4stf`v_(q!R#ZLeFU?QVD=HrK7!dtF#8B*AHnP+n0*AZk6`wZcGQ9Xs1KNZ z1hbD|_7TiJg4stf`v}Ik&_^))2xcF_>?4?c1hbD|_7TiJg8xk)H{(8N?aJ0)*~U?} z@s({}WvfTo>QuJ+mF>8c?Rb@K9h7Z-lx^LVZ9SE3ot5o%q-?J*W!o>G-CIw5{@!|` zZ2PWk=Yz7HC(3sIDBF3ZZ0DP@orlVHek$8}t8C}9vYqG3cK$2d>q6OHFUs~hQnuIH zX7uszn0<8muKw&J?Cc|$eFU?QVD=HrK7!dtF#8B*AHnP+n0*AZk6`u@%sztIM=<+H zJNig}^byQHg4stf`v_(q!R#ZLeFU?QVD=HrK7!dtF#8B*AHnP+n0*AheSF$9LN2}$ zp*_vfHbUacR#(0{DncqAi&Y-;O@w64kgVJ!Yoz=*xSq0Ki%7{;ys>i8ZzCo57w;&) zUNuTS%-llxz{V&ko42KM_3+9PyvOkRb(MYgdfvXB^lv^-d~x2%Ud0!`WXmePyuW=> z#iwWbFI9XxyL;zGQUB1Fs`|zSd!M&LR0I6Se_2KuaklpNQ%3yT=?g0(@7fl5m7!<# zkGYhgGpTP*W$2&LF}pIxHDy~iWsH}0)Peq}596S2jE{OUFX~J^s6Tb0FVxR|p^tyZ z>?3^GM=<*cW*@=qBba>zvyWi*5zIb<*+($@2xcF_>?4?c1hbD|_7TiJg4svfQ3v{? zK4A6{%sztIM=<*cW*@=qBba>zvyWi*5zIb<*+($@2xcF_>?8Q!^f3zeJ8M_A{>nCv zvW>57^D0|C%2ubc)vs*FrEJHmZ0n$G>!WPzrfln}Z0oFSuOnr9eJR_1`Rv~H==1m1 z6J^_XWjh~~?L1Mo^GDgvD`h+1lAU)~kFc|kVD=HrK7!dtF#8B*AHnP+n0*AZk6`u@%sztIM=<*cW*@=q zBkkxT{n1A-`v_(q!R#ZLeFU?QVD=HrK7!dtF#8B*AHnP+n0*AZk6`u@?DlcW2lZu0 zC-Yv_^Wz#whTP_Tt7D5A%CD7-{o#g2GV#JMn{jPU+whj;D}7$M#pjLXR?$<+%Ui!K zFW)W~*ZhWdK)$!6WxK)Z(>Z%1xixWs z^1u1J-)7W-V+V8WV2&Nkv4c5wFvkw&*p=2G1u$A&=V~HX7MZ^jzSjP2 zX>-{89_hzORdqKGGA#yJc9?*9Ph{tsa8{{ZIx4`A;90OtM=VDA3_=Kc?0cmD^zvk5!j zJq(VNqzvrg%y+?T^U+){r3wPy}ZRf5jXPc2%nq)Bd z+~$4rO52B*)IPIKUOBV-qB8IG$mQPam$c3+-?Tx{Ix^X|M0}Ta$v8y|GLi- zA%nvu;Y;(I-VZxPN_2a}9VSJ}+jR_wt&fzx=?(AyF;dbEGQaN)dJrkoelqvdVL78D z#qL9%t3;Idz2Py<8yp%XWAYtU?&6(K@!**w%GhK7+q33-I`Bs?7|pXhpZ9MX&1b#O zzJ6+m`j0OeC0%|t`U~ZXlJLU%A;Nb)&I=aNXhz#dG_cuBT`1s zF}$p2q+IW5cyzr;somdj_6m{GXRYCqxg+KI{3g!VzePx)`G&WgjF5v3Os)n`QSZS7;P2Gm39lzS=ol zE?+d?>8xz!J+IC%&q({LgiE#_=KJD$55lCzO!FP_sx4vC;#>2KRC2X<=EV{7U229E zp3d{8N1axN$-=wlyVS<(!(`u6)5mE$!ld;R)88MCg~_*%-m@FLb%Ln zYvxSz;^A`evEkd*!lg?yGq1`t3zx&68LnI`LRycxtly_^^}e_L{mjyhnCHuLm6vO& zvy_KEQ(g{a8moNpUZ^Cr?WcU!I>V^Kj)C?|2;eipvp*+1HCR)xWmB zS8I6#?Dn(jV`D1YT*_91vel++H7nb(=)R!EA|m9s;A_fH(jw%?IyaR4x<<&o)8>r( zlM^Cj&f!~XZ@fA}UMTge@`a<`eEY%JXWx&IHJ6S5@m!IzzOjje^FI0)y{P^ny&~nr z*h|Viy|Z%K*SV^Uvs9iRdR`f4tjubBR{1sW%$GGQPbuR}mO~RxD&wq{%6WfK#u+XX zlaDClY?q*h-tV=&TH*TrEOx)kn_#y-%J#F$Hm0)8rEE1QTW!i#vtctvWjl6dJ4R(Y zc4b>DWm`jKTU%vYb7k8LW!ocV+dJiIQKcnlMGx(7+dk!doIAhwTkD0r)PCuKzx=VK zzw#H}?{j|oZJ2U{4gOMQ_ju(Ev;1YnwVBGpMtHvo&$LXrskd+ci4B{T*LLui8l%5e z{;{>cOwM#h`Dz<~d3M=ty;GNhW%ws{&L@|ubHd%iMq?n{#^OHdi9bT3t7-m6wd=KPVOydfb_#!bo*i8=Fi zgFv}kF@y5`CV`Ui`ePkqiKc-vrr0&*K%p9>0< zm77dG-!C61i>j_v`-QMT8M}40@~HxW(y09`<-qiT5?f?~^4bgK#6MuTa@_WEl6K7W z@$_fqWaetq-;OI&rB~%us=v#MR9O=CrE;6asZu#?rE=d{snWcP}OVxf}lI6)Fb6?n1$lIH)f#J@N>d5Dn z4Bt3bN9so#uC%I-To`0HZG0W+ddJ$k){&dT%spk@w~5ku!$OVUOp;{8aKjyzCQ0%) z=J!IYbJvkRt>&vw@Zv<7zQ_3V8=5GSGA>g4oc9uCY*)jhViKiQHgiuYP%crv*=IOs zzC7q0ly~o_s*DXww@~cc88qQ9W zL9sVQ!0<|Tulo7{+_Zun^M`HO{r|prc}0PQ!3lD{FLXIa}|~C`F+avTt8)d-kGkHhVh>t`(}@qlZPfKueu#4n*$8*JrpPRmyB0CdgMJb=>62PuKDOApDWN` zK5wA!d=9~U;PVOQ37=aqfA~CuGdKC1gE`6PqTu(d$g<1kdFe!O6`3)|JQv0MA##6> zd0vViQbo#qXr8s6%&Q`8I+|y&KD(+&m)(Y6xLid7dK=#FeZTznSmU3iWL4Rf**u$N ztX5Ty-Z9U6xf@oMerZ>9jDsU;$+VJr^!_rqPAxfd=b=7-inoW`ov5#rBRkZRaWe-f z2YgUV>eYE(`N)SJhYj?@z0%q@fUUo>jiYSi8#Z}2!r$uA`dgjKR==_xm$DtNvaN%% zt&g&;o3gF5vaP?et+TSNzwt5sQnr0mw*6JMeOI>gLD|j|WjlYA-Sax#Gd+1eGU~u{ zlfgVs8O(E*!90H%%=1IR?zy5DxBt(bp{#lB*{0%`C!T+6eTH((#i@`k0 z7|b({!94pIZ0|doi)SUn&a;)l?m4RNS*tvE7(P6Y7|e5u!92eh%yW&w|DCgO;m@;! z!8}tK%(I5UpZ=ROi(%)vPGFt|2Id)IV4fWY=9yw(o;3#M8DwCdO$O#UR$%w6EB8D# zp0frYp1%g>xolvb*9PV}ZeX782LAuzEHK33Sz}M*EePhBgJ7OT2<91uV4htF zcF!#1IbyK$d@(T39Ru?`GVp(OwhnyUvv_#^5$rq{3C#17z&u9@%=4AN|L%+!*m(vJ zm}dild1erpX9W*L}gnSrr?KF@T+p7~^+vj!iYzXs;HY+#<(2FAH6INuG7vlw`O9M2EZ&))oh ze)bUjc_tT_XLW&jh8LJ;dx8I}v%}!yo>S(YG31_W#`De?^Z(8HYxpdG+XLqBdBFeo zcUg^fp78fPs0n}11Lp5}!2CTAn7`)%^Y=Vp{+N0IGDc=2lMygVE#TF?EXHS@6)j z`@7n`kJw-Ai3CR9u~!lp^8tG(fiX|8w-Olh2YW7oF|V)}6BzRido+PD53zR>81s{M z%v<_nJ~IyHIpbsgGcT?S>cRCwow$y;uMzj8LN3_3Z!P?}FD2q|-&(}yzO~59{Vkz~ z`_@7y_s@iW?pup-ao<{umv+>F{-_V*pl*zhdNMESOg*^1s1w&0_5Y{t|Hi%h&@b-k z2j*UXVD143=H7r{?imQ?UV>okQ^);nxc4CJ+>;Q@y$ZqH!w}594Z+;=5X`+0!Q3Me z%)JxA+*1*Ze)0N(o%0j^oVSR>`Hc9S=g7pUKh~G>jnCG9bsI& zzA#?eQ3v{?K8%C9F+S?ayr?tvp#Ic}zED5zU+fq5o8ow}-xTYB{iawS>^H@_VZSNX z6Z=iE&e(5?^~Ziw>t6ysyRDdxp~Q`Cd~rl`~1Pndf_ zqhGLdyzplo5Qp_aeAW$lSx@L;ouQNUhko`2<6^%sUfNLy`lCLKgSs(3>dCyQGxebU z)QP@OKlhf$xVWD@nET0txt~0k`^kg3pFEiR$%DC{Jed2*gSnqPnET0txt~0k`^kg3 zpFEiR$%DC{Jed2*gSnqPnET1o&VBX&Pd^uc=W$?MJa+@kb2q>|cLU6GH^4l11I%+b zz&v*Y%yT!uJa+@kb2q>|cLU6GH^4l11I%+bz&v*Y%yT!uJa+@kb2l9Of5iDIJgW%f z;`u~io=*hk`9xrzPXy-qL|~pz1m^ifV4hC|=J`Zmo=*hk`9xrzPXy-qL|~pz1m^if zV4hC|=J`Zmo=-$O&uRKU{hTTH%rc&3_P^LW5AdvtZr=k^r769OKnNrtX_NqY7laZ5 zNeBT#??rm=1VZm!1O${`q=@vIcO$(DNReIy1f)rmj(7fRX64)GayVBWK0Ka#HqWE{ z9OqqoX6-ezXV0Gb59%mqoPp)+Gq9YA29~qZz;cEfSk6`h%b9CnIg1S}XS9Lk>^88R z=?0dw-oSDO99YhV1OIP3AJBfbqn!B&Kgd~-U^ycaEN4f8m=s+ z3-i&WhI$>>^IiGK^Qh)(H}X->YuAEa3mh?!io zj&41fJ74vn7mYN#ws}ygAA527(AggJ+nT=2Wd?fC*jKU4wOV-4nw^7~?dPrA&t%V1 zAP3zH)_YrGvgM#Zstw`$_$XZt+S^g@XK{a=gEoAj>wY0q4s|WP@5V1r4w|`7@5gEA zpM#nn7|FjqADV;OuhM&V61T`f+q;kEbbLo{l|{!)i_g)cqb08Jom%1w->)UE@LgNtO3sLf|M4BXr=N~Dd>@xQ_--!0#rJfviSO)kEqs5M zGNgL=Nqm`yWzI(*gpT8KcHfnkK0dGOHMn(N3b~={Ui*W*^t6}RqckNCeLq$E3hxCM zs%W0D{?qvMtW`dZ&wuAi?sz*dhUbpAf3sNb`0HXH$Iur8<4{NJeYnze5Ht2f1l`t* zy%Hs+4d!(0p;*~y2s8Fp9Cr<6#-58ZK3X3Ddoi+pHk{M3UqjZ9ffqkq%;{Iv-m4>j ze#?BfXb^cNUaHdz1X0T8nzLtC>F1YmdeVeJv~kgL=3>`MtF@ZnG1u5vni?B@gB(js z)BI8^IKA$u(sZ?}=Buqr)9Qhmr>gxaYnyA{y1yi)D5~v$)GUy8MJ(dqw#-<9${n1| zocy<9bnMtP=9p_m>EXoj%>6p~Q>(FUnA11(rz#s-F>i_Vrz{&=G9RzxPwuaqGk;mp zpYC;Q%AC5gKWz(d%$%>fKNTz9ka>C&f4W5VnLq6APrbX>Wxg}UpZZ_XI!NCv_NQ}G zYjJv=-Tt&_S~PQ|>;Cl9?V8NPKMbHGGc|wlyaZ)v8_DTDIRYuBv*y~R18LJ9&E@L_ z(#j6iI8V`DYR^}rDCVA%0_o1=>ddXa4Wui{w9VdI)V{41`npB;2hy1Vx@^|HQk25o zpYtyWE=9{m_herFZAqFlwF7g6cS%~CPx~a%>`=O#x&!woou-7+2&)D2sNtcs`hElE z4Qd_o;&ai=gX@LT_bVfrCsQbG`Kk)@^4y^mv@wKv!Jq2PV($vf&CXS#=!E5&k8P?% z2g+%_KCKe%_+952tJb?tdQpk<%&S|8l0}6xKch9R2oPh5_oe{(T+e;G_EL;RR499P%<#e;cBl5+IuK^f*TDa+B3hr!H!GL@sj z7t1rJ$X|}~FRjRYCa@gM4Xwo7wOTp)ePt+fnRex<&Y8;0Ge?%AW$r4>Yt=gK7Ws5v zedOD4D&AeQ$H8#gIz{uc-@_@z2+fVtM^OJz&E*0j==NFN=QoLppl%g3uU}l1%6bl9 z`>DdKQmdJoBOXRjXpe!M9xywCmVQ5odC2~%m94^llXzS~feU zmpL3xi_%nJHt`dO_%U&{1#IGt*~B5UiBDz|x6CG64Y!6d&Vnw+8{!OY-zPc%y-PJ2o`xAROe~J+il>V9SLvBus zpw_2#zp;3J1ogeB`;Fh1L{QaNy6>8{G=f4rbpJMeVFZn=sQbNaGb5;Bb=@B}8WTa^ z1nGYA=bjOi?nx8A?)uabw0uZw=F|_v>0Fw&%+pSU)3fk)%)aZ?*^VXJGw)P;5We4| zxq7E?YWh_3rLb@swpVkxDphFP)b5=B<-#hI`;X4dcRviHv{gGYcj~702d&Zh*If*w z$-bIB3Rj`kyLxb*;8a!U#4O$Kjk{5qZszF4>B)9graC1xubx|(LLTcpQwLP0c{Meg zHpux++hjIvmf5srX4A%*P1|QSeFC%TE0|5+!fg5+X4AJYn?8rx^ij;F?_xH68nfx^ zm`xwZZ2CrK(`PdGOI(ZkemNru@&En(XnI(9CUccb(bRUY=4ywd>BrCY_p%+?YSFg! z(>c$Fg=$eQ>nr9X#cR>(RnwS%2&zRTr|W$pD->_PDvA7fsXFYaY=on(mC!+-8v4UsgPy)l}S<@tuoY3#>w zT-~Wkrx%Z5-mUf?rt{YPe5E?ieeh^b&+}DP3g0k_`QDJK^z7hB=2zXT(x&|*nAf*c z=^OMo_I@3;hq0<2>y~U%l_&B=(iT*b6g=F>`~O>Rk9l zgE)O_BW36Q0Oq)kRjI@ESmyJp3`271vC}J6{u>i@f3hoCB>AP+{Zih1ku>UbSI!?< zE|MDm-i5hm^GHfkPxIv}-gk{w#6Hv+6Ct^?SO%)4rbQjvY@nftd2rIyFnF(>F3Ne+02DL2&2QKd8$VkU3ol<(^G`1{je7_$FvKh zUM4+ThX|_s(M-@MIWuE~mMKdcObCYX;}f zwmgC&Q)xbQD1vq!oX+VrA4E`EOY^sxs?xNJns=5^`+t3PezSj>^P7Fm%x1qcv)KpD zZ1zVpn|;&FWk=c4PN5cdEu(yCNu=h33w_DGe<9m>X!+9D9-6;A z?n_mgF5vXWL;b07Vg2kLf7y@n2IyyczbHRS`eZiesXfP^3NF&m^v0X~>B67-nSSn& zKaDS?IrNf0J#MI`i-1>F4{(e%@51x_-X*Q2eli ze!dq~d7cf^&-dNqyvg;2evTiT|9z`@$+APhxbNbGXC8^1vuFS1^mZW6EJ2R)~Q&WBT5GbgEDl3x7$IrE&Gfpm04R^}871F2K*e9Rxl1S$=mB05ipK$^d@6mzcr zfmFGD2(!l$r8#pUih0>RH5atK0rNtoUGx3C%*;Q%3Z$;X#mW(M=unN^;; zvzTME22kY6dCcX0ElNWwP2{?ixLuSwhv@i8{odNHciQ}evd#b`k; z&CmUd(@&Xn+zzWzoB|7I{-AqtO8K$o#gmKEsUtf7s#V3QU^~q%e=JU&f6>>PJWpAT52zv`q0gMCZ`u=O0a_Ym7f<~nys~xR)%>| zm$H*Ny?7fh>Jc=GdF?1K`t-se=90_3DC4FW=3R%qplQQw^lg}p{t2_uMPW92Da=Mk zh1uwzsaEX}|n&`T%q5(>~PoVp7f%de?{Ur%%KD zO7+!S(_~`Kn8KGbOv%L@oZ6SNxAkN`bGig&sp!l1ZtFom>N2M|^Yf*C6#13r&7=Hi zOi9gW+xXGU;l((Qf4F)k4lT+&#LtgT1O_k<%2H}$ zKg?|UXJ*rHGn?lE^Zu!Uv~Ij7^U3d&mfEg7%*XZx(!R{Om|u+vq?|DYnaA`Cq-`PI z%qNtV+VE@I=QX1OsX?{RIDJO(KpGOG?@L6sK-$_w->q9$_ZD1ZS+lPKlt$FWoADZ24J*TH@=R+T#UdNnN=^%~krn$D#>2+^f!s+LB zdQ+BOntRXnrYp@g7m4+zXc?!s*x*HLgTG_GKFf>#OuK?P^B6B`_+0bQeqNOM)%Tn}qnj6P z|7exw&R#Ukdv!d|IlVJJPqRn6nDN`R$@ehB=AIAtGUHmFe`rP-I&a^{=_vEAcKexo z-1DX!PfjrBJLF9ReUCABp6yN3zdFKPy`?whavfrR^{KZi&q3zfFTH8fgP)m0(iWn) zGbfqTc@(0_OHMIwaTTKVbx$)-uUCjBT+@83Pa*0ReumR8&nQH@M{1rMSBP#;*L>%e z5B-u<^LZ6NiEioN9xCEX{TFDy9N|lTMKxDy>r0ux(bp|K#Fq+P(dEhVl`qvxr8z>4 zY3t{jM#}`ML3#|2}u)9Ao_gUgg#cmy8&1cbygl4a3 zMS?{u5-eJgV9|;Mi&i99G=9ON@e3A>U*UvS1PH7L=+%j}>1U)7-B z(p+IK(OYpJ&7SpYP`xx)IlXq78Z=|4<}L+mkmt-_IXzkC8nkZAHRe$%YEXlT*O^7* z7uOPvU$AKWf<@yOEE>OH(f9?6#xL_fOqc#Y(c}+8IYr|aEN51N<;+U3oLLE$Gb_Pz zW+hn8tOU!Mm0&ru(w6>S&fU$AKWf<@yO zEE>OH(f9?6#xGbje!=pd4wiQxu)Gt2Xo-uJ;W4*-_=0kF&)fMq@b zEb|OtdG`m)oB&wnIl(eF1(rE0u*_wFWsVChb6;SYD+9|sDp=+@!7~2|mU&UI%$I^? z9u+L}t6-UT1}5LSiVz$<@*I#zH5Nxdk0v)gMi1H?;~LOZo=v2dkR>-vw-Cr99X`2f#q8m z=P}>N!1C=3EZ@|?@~sUl-{8RVZ4NBo?7;FZ4=msK!1C=6EZ+pd@(m6w-_gMGeGM$% z-N5oa4lLj4!1DbLEZ@|?@~sUl-{8RVZ4NAJy}+^t3@mHIz_MlxENjWYvc?Q7YtO*4 zCJiiW*ub)u3@q!xz_LyZEbGU>vaSp)>&?Kj4h<~p#K5wC3@q!)z_Q*9EbFzvvW^QZ z>$||R?h7pI!N9Uk3@q!%z_P9kEbGm{vJMR_>(jupZVfE!*}$^S4J>QMz_OMMENjfb zvSt!2YZSqGQqM|6D(^uIgeR0 z36}MZU|IJFmi3TeStkjW^^;&(R|%H&mS9mbJ%VS(6NwwaQ>w!wivtuk2FFoR`n zGg#IMOKtu!rc6ZW%1=nZdHo87%9c!LrUDEbITlvM&HE`vt(Vj{q$D3&67P04(eF!LptoEbIKi zvi=_|`vSnSUjTf`>>~in{sOSjBGt zAF%A%0n5G{uQJwagEn*)|TJ7C$%1D1U^VA+oYmVG*4*}nspeLZ04Ok%GMSo9UaqOS-R zeMPX*k>mVEUyj-6&M_N3I%cC&$87ZLn2oL-v(dX_Had9BMjwyaIWJY8>ni$+w)+() z_Y3E1%l*Rn;BvokJ~&wP6~Usf2o`-su;?p-MPCst`ifxDR|Jc`B3Sel!J@AS7JWsq z=qrLnUlA<&ieS-Kl=S}}&Xq=8L|+js`ifwq7svO==*Te}eK}^MJI8GF=$MU89kbD| zV>Y^W%tr5y+34Ug8+|-xqnpQU^z@ja*Qa#$n2r7(GxYkDE+4be>x)kxm~&Np{?V1b zV>Y^f%tjB8+2{l^i@qX!BKnG8(N_c;9YW48`ie*weMPY7D}qH|5iI(OV9{3u!~arF z(N{#e=qrLvdXOzYv*;@#UGx>fqOS-ReMPY7D}qH|5p3$kHbq|%>7uU)7JWsq=qrLn zUlA<&ieS-K1dF~RSo9So9r}ur|J<}MPCtlL|+js`ifxDR|Jc`BG|+s+Yx<5 zq>H{HSo9UaqOS-ReMPY7D}qgXVVk0_h;-3c1dF~RSo9UaqOS-ReMPY7D}qH|5iI(O zV9{3ui@qXQ^cBIPuLu@>MX=~Af<<2uEc%LI(N_eEz9Lxk6(t?|ijsdzl^x8mlmE(Y zX4p@iZ$C4x>vjJiGs?5H#9?NX^ZZr)4I1TNck3rkN4-i`ILeIrN;>=?`Qab21HXxV z_*1S6KTCPwe<>&KiMQB+gXD*Q#18x>_Tf*tF8nOzf&ZnP zxGz$E(N{#hpo26#?^!Mb^pW<3oMDD;(l@sN-5Do29lA`= zNrO%3HT{-AGv2>4-~O4?q3Q!{GzXj zG9X>*i~QmT*b)E0zW5E-6@Q{U;%Ago{Eza>eL=nCexbgS4nIhK_($x(Z(<+*lNSakouq6Y{Toj|bY2ZBXc5G;CwV9_B2i#{P(bPK_v zX9yOZL$K%{f<+e*EP9Dx(NP48zM`ZZFL93RO8lcd(k@U=X)h?hv?J6@+8638>F|T(hkwKl{3iC{ zPq{AqEaid!rJT4gQhw1_M7>1E4=nnAVA1^piyk0YbOOOB5A^83qALg%y+N?(5Q0%( z=-Porw-79PhG5Y-1dIM5SacD=qL&C39YwI{D@wY=C-O_&!j8l<>`R>Ex)T2=kF*Pv zQ`!s4FYO5RlJ=?`Qab21HXxV_*1S6KTCPwe<>&KiWZ4c8TaqCDbflvDhV^2>cez2ttOzLE|MX=~Af<<2uEc%L)4t+(*-+2B=X4tuRcmy--|NOCLT=!DD;hc{0 zq`NkZ8RhIdL^H~twUTDkYlpvP)K}8s2gwirh#mM%?8BdOUHDnb1OH1oabKkT&{s^L z{-7?RuLu@>MX=~Af<<2uEc%LI(N_eEz9Lxk6~Usf2o`-su;?p-MPCst`ifxDR|Jc` zB3Sel!J@AS7JWrqdY~y|YU_Q(tD|2WI0RX5%+z z<4?Y>@iVjWKeM?nTz=74MA<}N5iI(OV9{3ui@qXQ^cBIPuLu@>MX=~Af<<2uEc%LI z(N_eEz9Lxk6~Usf2o`-su;?p-MPCst`ihbceMQONai#8)Vdwl1{mg~^$K|GR9$feK zbD>tvJ+W#m!1I`@(Hz(Je%}=ox}V=MXIVhhWh~1dCoGSacM@qOS-R-9@nI zF@i;>5iI(RV9|91i{2wxbRfZ^4+$3CNJ;-Gjjki|_bq&r>j*ok>;A?J`wynyV8(S{ zKGJKIQJ&8_X+}Axq}Gh`7d@iaHltn_w`fLvB^`c{{P2(1f#1YF{3+LkpQSwTzmyaA zMasXwU3Kb4&$ygr+Ek}Ap3j*@w-EIeJwveQ9D+sv5G=ZgV9`qii;f~#^cBIPy9gFN zMzH8Kf>De0+eJ>_~K|GMr^m|>^V+{etY|Jmg~m~q__ zF3l)U>kW@M9pyYyQ!~onDXV7GD|-^nsIR2M50W4L5j*gk*oQymy704<2mY6G;=V}v zKCgkiIMr$1Q6<-8w|n=&l; zmKopWarPYY$k}#aIr9!IXW@b6j6ATMod=dP^}zUEiF5J5a<&~<&b$N5S$JSMBM&TR z=Yi!+J#g|dtf;i4=iUdN}kq7_ON~Yc1);d*!=DrJ(r7X z6*|5vz6>}!55JW&^}ur09(cpH>{RZ%y_{#4s_%$$`%z`7#Ye#sJtHL4XMh87<>Sub6 z`j2b{cuyIATcW={OO&~90m42tu$(;#mNQAga#kr=&M*bT4$dJ3%Nd~H9iMwruA<*@ z`khgpl>Uy6ldLN|Y2r!EzDGT&)FaKg|L~+@<#hftnF`QnTQ#=|C_pV*tzbJ>!wb;S zV&5~5Yg&N9JXSLA>|B7pE3}F^qpC~R3agpr98#1=&iw?-d7xl9CloB_hl1r?QLvmh z3YK$7!E!z+Sk5g4%Xy|?Ip-8C=bwV*TvV`}F$$KmN5OI?DOk=b1F<8z)2Fv-# zU^!bEEaw`7)ozNV!kf>(k)tu+5Ilo)31$|WTe06p_v{;$v6Kk=8aYi|`Siv}> z99pbkoKX%fRxr*ehZZXsXOu&W6^t{=p~VWG+n@{`z8}ln@=h6gGOrJF$u4E-hDSGM z(W66t(WwKAejQkJ?ZBdU2NoSXu;}T5Mb{228gyXMrUQ#+9ayyNz@l*n7VSH*XySoI zD-SICbzsr81B>1rSo9ddqD==D%{s7X*?~pl4%}7id9trW6A$U4l?N7$N3durf<_XrjpNU-Qb zfO8@#_ZR+41IU~ zHgm>$Wobb44d&#*W$F0+o6ITmm!;hw-eEqFtSmK}c$Ycp^)lqu?|0_@yUS3wJ(^!G zEJN)&YYrb?hP?ae{KHCBq8a%!@jQ&-%_!TjYL)2N{imD2q~1602mQcYx|7n;oi&)* zOKIxXu9k%PSf5JNW=lXmZdPQ+{SsFJ@C;X5$BD z;~!?@H)i8!X5)WmbFZ1rJz_TZj@jH(W^=EZO$;!b*kCp>!@TcE7(H6{MG)$^=3W@Z zc}-@HO%qOMj%cpq8BT+~)^k21ONG<%;d;&|rgAuC9Hr-cwpS0QV>9(Uj~Pp_9rN60 zHsb+iGfrSO;|FFlu3$Ff4Q4YAVK(CvX7lV|HqR7h^Q>Vu&oySWBlWyvHqRzz^UPv4 z&oXB7jAJ&>K4$YwWQISLZaFjTA8+~-bLA9eDB^eh{XNrlqTLrX&)!Ycb%Ewhi;4CJ zYxW*P6uRkW{_T=3MD^2ZKBu1V)hnLh^r}@<`I{eS?yTDH-VVo@r>XXvznxxZa$C)- z+%tA+D*fuEdv%^}4MQo}EdATD6+&rUw6+;iFqCfJ)ZFO9P}*BpUw7V(O4M?;=8#_D z)Fj<}zE%^Z&s=(y{w_RSY1S zYMVvBtB&m)PCum5-1O;@mJy@Evp7A)GZV9|^P ziV9A6DY2#+T^XwR_K9j#Cq#4CXVqwK3C+86Mv-@2&1*AOqyB9cv7JuK zBPnY8V&>))Nux*Uxs(k`54P(j%^zj0N_m#*Iil=Es?zrTdX8mmsM3~9t$DuEcb(XM z3ELSkqAE>EuGw#CRhqe1+qv99eLs49fb)#}G@Md>s@v@BS79_Xjpi@acdJ7ObsMk0 zC5$#U)_nS#FbdnJ`-ESHgwcjHnhSLdqX2*1Z&Ys>Mi+u~-*Pxg>2Ma+{oBJZrAPg# zo`1NZcxei~7H);gGwsojT%KI&w;$fta}n#5UZvM9ZNK5LX!?5je$LZ#YBb&dMwh?d zyl5IaPv_sDbdQU!(RP|FiKcOT_54P)1<~~4jK0>g>CyD^vM$4xQPEWAv@YAd?$H#z zL6`Y#{b;(_Q`e<%nP}RQUYB86?r2&xTyyb1Yf_KHnj7a+dcR?MZlwB!nv{3IRxW4a zjWy}#_M4c^epqI+kCoZ%Z)G<7UYX5)SZ1?Nmf7r|Wj6b2nZGw0!iZbZ76ywZFj%yL z!J;7y7Hwg$Xbyu#ix@1r!C=u728+%xSTupbq7@7l4Pmfo3xh>-7%W=EV9^r>i{39- zbb!I44-6LFV6f;3gGFZ;Ec(M>(Ip0pUNKm7gTbOF3>KYXPS<+iabVH-1&j7CSTupb zq7@7l4Pmfo3xh>-7%W=EV9_WBi*_+sG>yTc8w?gbVX){7gGC1zEc(D;(G3QRo-kN+ zhQa0;$MqFmVx)^^9r%29AFAJRHjlSO;|}SfeFqjzJg{ixfki_PEE;!U(Y^zVCLUPy z48fvn2Nu0Mu;}1{MIR3=x_MyHNCb=aAXqdB!J<_N77atNXd8k>^AIdrh+xr31dDbe zSTq&EqO}MX4MwnNGlE645iGihV9_B2i#{P(bPK_vX9yOZL$K%{f<+e*EP9Dx(NP48 zz9Lw37r~;(2o{}2aCesv1sB`M?_vw8`cT2Wdzho@`OwfQrCpbx&g$9$@70h*fPBJ=uA1*pQfADNq|`Q+1^;+RK{R_9Hp z_>Otg>;km%<}BvAn+lNko-dfcS7%b6{bMBawZ{eMxqA?E#%${R=x<|~pRF!P%@Rj) z-~KSzo8~{S&YaTMn@T*a$^0a%H~q4@7IV8-UPOiKFqgRCMagQ`We$&1x^{W$F)#m0 z>Bx=O+@`x1WuK<`t7=~KxU}Z5B3{&efd1{Mv|be0O4|&1P>|-m(ATParXYP$DVlBe z*;9}*)TyDbySbpU6U8hVhPaQSZ3q_4L$J}7i35v9B3QH&!J?@M7Oh3FXfT3B3lS_D ziD1!A1dHw^Sac4-qJIb$T|}_xC4xmq5iI(OV9{L!iG%dlRbqN*?Ot5HUf<-eE zELxgi(bxow_9j>~Il-dU2^I}cuxM$5MY|F#nwDVEx&(^`CRnsF!J?T77A;M%Xl#N- zdlM|0oM6%F1dE0zShPLCAKwq4uY59Z20y-~xJ60kE4Kq^>Z1nChaUz|MEe2EBb1)- z!4wmjSEMgWH*4zWj-~cWJh`}>(_>Yh=>@86f=$CbKVz;{3h5?4v$4Z$>@%C|GMn-+ zn{qO{@|2>s6RvX~^>g~tw6UR{@0$0h6s^0i=e4dJFGcB3>UpY$YfDj5Pd$HiW^yT- ze^jUE>t2c;UeNhpMwg;f)wG>FrApBsetNE~uR05?V>Lau<{wjO z;6m=x`o;!Q!n*ps&$nwJMYPiIaa-C3QfM1JM^Ra6u4Znj=Pqul^h8bd+V$}&f6eB4 zej~|%Knm!p=RFcmRGO}n^?XQerQKa&mVS>rP^KiM?!A()yQ)n|TK3I)=HI%Or0ZAX zn2XgfN#Eq%!CX9FNxD-=e{1e^P-%Cc)bBq2!%9-b>QkJ@yLm}EI!E)p;F8p>x#kvm zOVZ&NdQPcfQl)v`-po7Q3Z%_uUg+eBK>G2zeg~YfGmzT8)bBnGHwM!FSNdJ4%POTw z{y@J&C0nWda9O`woGMKThU)SMZY)i)iM0JrQ%X~# zYX7>{z@($tCuer3w&^pB*?p!I9j-f+dD|bQDCeRf%=t5__|K*}O|jC{fBj%iA6L6H zRT-rDyS}CAR$t9sz9~)P=4-xam8MkBH7CDNnx4gIJ0CtTO)K;3YvoKIr1ai3e~~|k zx}DSIxuoj;+4N)lu;?m- zMbj88TE}3~Kn9C8GFUW|!J?%M7L8@FXfK0BCmAeS$6(Pw28%W_STvKtqNNNLjb*Ut zA%jIH87%tAV8j))j+u=HGFY^c!J?TA7A89($~rvUBZp^%y#a%qqDUydNHS0 zdDX`6{WUwMyL^2n=an+qXt~qnDL|?mmFX_tM zVs~!0=h2wg_&r_AWxG~9tMa&{JgS^7DW@twN%>X1Nb05POHyCu2a5N@j?N_hQGO$v z599fLTr2Oo_S7q-o9~64%RlN(R)GebK5}L(Et%XT4)Fz<9~A5RQcUfepN5G)JxUZE%jA?u*46_KbH7M`OOl)DSukx zPvvJz{H*+MiT~AovE;repICCg)P1yU_cWgWA!Un?x9R=6($J5;;TX#u(2KnG^qZsbH{MFI)Rn$UXU;RP?lae`h(^q@#XhAAXDc#)`DGc}_iX{@fTne+ z-Iqz2E1YXjfgy2xUt)Unp|VG-GmktROHpUDbDywhdp}y6B$*54ZPln7`Hh{%{PcP= znpXG*bGy@F)M0p5LLNK+)5@uQZ~6I-osV+bxqglq>)2smuKTL-oviXXS1|v)x&i#e zzUr5~ytR33K4$!l|7J7l|C@XX@H_k->97a8CXf1Sz-#=zulqQx7Y(A`e2?s0_{%or zPI!>h-L0Z&(}k3Ta_*~Hn!H*RW=@nLCnfW!%v}7>`>tIznlSgvzrdBIn(oiX4DoOU z%+>w*$bQ{6kNz{3^Ndej*xj(2PXBY;V)yiwojKjke`gs+&TQ;{wY@i&!OrQXY;%v? z*N)TIFHL5h&RmDNn4g#RNhx9;cR9qW{re}(zg=r&Jt+Ew{kC>OXX|PIZ!|$@ z?m5NX%-xNBVvp6g&2MjOJ*Ks#*%5mkqEMcXWKt-PYFC^b;M!5l?3XEh+o@J^Jsu?y1qetTkcX-MAxm4)<$k zS>1MWdT`mgR^Wd9-0A62&hlUBVIlw1HlEgtC1sh9ZcJt+Pg{pMVE$hBq^fP1o8;{8 ze)+N|^YF7f<2oGd{~EuKYyEJ1gDYlB2fmh_FVsv-?ef**^p(K{XvN(!%xAKP(D&DK zGiQ9zh~}n#!gU{*ybE1FxRAN?;TRf~@>Aw-9>-F6lEJ0nhwobSr3MjYUEn)G9jUkf zI_9$H>rwIC9}v>3oGnY|e09v&`M;|?tp;SVhJF*y^|kZ$=hxgfis^T{&Yh;YuQcn% zdHNJf;eP&oKjsW&QUv**(c`Q37s6Z*f9k{Oc0b$sU2INI8$*rn`LRFkob1ESRHo-L zPG4QR5uKayjQOBv2>p60H^JvW^eRZ>E)a8Ml4KMctDg~hM*rXnNZ6j!?fgD$=D5|! zb@iZb``1#{4N5mpxBd0Uug7Js)t}37Db+Z4u?O9mJ?@-y*IM0@x!a-iR-MGvn1_xC zuu=^y%DkXNq;>Ij2Aw}!OY1<(i(K~u6S`ZgS4?2``>em!#QlKZ2krddRUW&a{|ejV z=dZ9mHlF{~mCh%b$$rRF{Bt_J>kRWlot$TEy-kfglW8dYsw7DTY zX!*j8YuR~Zw~n+V{aQ}{a!?<-dOM1_`P^7)b+Rtk_xhUtG-moij=il`Px|rq0qp-w zx7*N=_WPOVj;c*d$0X+%KCIR$C-N-t8o!Tg)w41N`5e=2(9U~36S=$J>c?dmp8E^; zZ~nSH`jx!oj`_6(r{|iV!HQ}h$-HBEfc2!FZjZm7t7>&Jp6_0xcpW( zE8xjw<`oB2-}y8N^X9X$*8O@(*;fnG^tB3>spN*A?fl5z-Wk};T7LW{bJaZI zRt--*uW09gm;C~M9j$Vm_4C)xd(-!|5}pd-GB>&!YwaF%gUeiWNIz>p-=_p7n@&=j-}m+yK$SfbHV}rsd?jb+}EwI(u2y( z9nCRzsNm;x>6L!&lp9`+=4VW=>-c9;T9Q2AwffrY{yuEl?c3SjMlPl8YxVN1#N{t> zCDy7t=nl7$A!GVk2kNKhwlF1YH|t=iZXoqG^KdVdOtjq=O z#9I9eT3g^}`?Kj?erxYP{|Y~dsZYx@B;xyPXOB}Is6*KeZj|l%ralz1CW1NcP%Qma zFekUu`VafjXFdtJE{ltHr)wF$V6Jz#1@)MGNpq1%I{QqIrH@|^pwyr0XL_Mc8E8ra z{j6V_hVYRy#%sj4edCR9)KIZ4w>RVG9CS;z| zwxi_^Udypm$iJ_Zx?zRa_+4z)KksYBBm;`by1vt?)fSAxAQ({-dl6D zdsK7}=C~g&$MtQk=UeJts}*#0z8)LgYh2$ImO#I=w{Gutjhfq@^Do_*n6_Q4%RG8p ze#%rjn7MYj@>Hauo@+B>Th*LUQP9cg>OYUWJa>(jumbz2C| zR*qV_J=i}NrsbvIua##m(&UvZqjy8*Cij-RKHAlZdEpcvS3xg5W_!~&<^L(=tml*4 z?Qu%irBCs1+?{*r@n`4G*WC%T>TztA-kGep?0T&GAaPMk{lk7xX_oqb%qp*?e#5?1 zHY{a}S=qMKHJCBKe!I}r_&NFf3qM|n`}lX3!6R``t815GZd}*SKV55W70Pg!(-YUO zWl@I@E#&FBovabl3NoKrm)A;kNPmMHe(D1&s$)G)FL?9^cfb4XUgLMMY5$I6=Rz}M ztS>U>=W;F|-o+YmWghdHq)n}?E%h3hX(OvxSIcMT@-$pr#7bULzbgggPHRmnquZN_=gqQoaGiYKi}Q@^ zzsoiGnVx(9w0d&7_+4#IpTDCZwVO%I_I|+5@8eqb*x2!`jTQ3Qe)e;OPhIQWulk$9 zrsw6Y6a({e+0O6twxSONG24Cn@3Ld}?dmc6-O<15_u@ILcDcW~tNmt=!?(?k7<-%V zWp@An6@C$v*h5`|(5C(hE1Q<;|2e;%({yiWWoY=)1v@p1b+W>ftYq%htFN_hCovDb z9cyhHxsCh(Sv~q$>-VSSdv_vVH)}*9{SLUYM04xchu1j0eeMWr{^87g?~-))vo?+{ z&Ybd(kFA7}daUv!`5AY?=6bABD{zdvOffxH`MmG1aZ4KM*j`klM$qL&I<^Nsspm?W zRF75c{6D4qW^R-HU}rP`$?0ZZlznLCOPS3)D!{aAlL_4G?_&D>s_^QT=`(2D++^l#q~+ka;n>@jKQ zS&6o~oE4|>7JOx$DnO&!mSJu`w<7iHug7LzYgCyT^ z4A}WyY}#WZ)w)Q!8>HWPhYu-3W#jbRyZt`CZGL-fr*PGvKk}yKI!-OsoMLY1{=r_C zx6N<&?O$PgU-wtotOw(`va?y&%IRjkE3;V#%WT%iGMja?%w|0;w@0(~mD#LqdyU`I zwXjZAt`*O!JXqJt>1Mqvvsni#^}_mCX0vXV*{r8!Hfvv*mEW+w?lpcN*HUZ2@Eo+z zrtECisdBnmzshXZwKALauFPf~EVEf3%WT%ox?$g}r)4(lY`IT1>u8`hml+2Yx(Q{{BCewFKG*0pkd&3acid}7wYGMn|W;!mubWj5<+naw&|X0!g5 z*{pqKhF!U*cK#=n&0~xY);x1L{|cM6vg}W@hL+i^m1VZa$=l{PYh}eI*3ineu(p=j z-p{;ketTOsYiJ4g#H_7lw)c~7n_qnsC$;W~%V}q|7KqfkBTiTAj!3OL;%ljON2Jyr zF{^b)q}ClVt93`D)*Ugcbw@6>?uc2fJ94RYN6hM*c#v9m^cug%YgzD>xh}IQ53?yJ zvnfBbsTZ@UFSGFjvnjJ1_Kn|OSwd#GO z_n2Hg(b?L0YY~@iu2)m5&V{?oX+I0Mre@aPQd>0gx7I8y#`RL)q%8Fv@HKwl_BSWE zh&NlsEB?aiJTDb z=XbHG#x`#CzC*abcAj5ule=zr{T*TH2MMj*IU8`E4|jfQy=YaDdG&Ocb>OPkYy4M! z+dWw^dX+$bm$dVorWxtp6+LH_Gs7jAE*4}0huZy+n3@gje^cVYjTgh@a=C;|i zNjvM(q#ex9F4nR_rlsJzdtWPUZP`_b`QvgqtaZC8Gmkuf+kI(eQ|7f9X1Zq_?#k>D zn9|*CmRj$k{v?@@IVjgr-FE&7Ww7^|A9=^pu1E9P4~BWnV}BmKZT??p>~q)4rst9D z+%>~s_qm>W9xuK1OI+smx^J=j$IfrcZ;x#|7pU)c|GA(&!RK=iB(_GJt;_uIcz&ym zxBiCps9|}_Hz*&cFPu@|`to8z=Gj*|Sf`WdZy8fJ_py>Lig3Zs&L3l~^jmVVPjWu* zXJx3DfMcU{cz3H>&q>S~6SlN^9lXd~Z9t^eYh(rszwOqjs8wM}0P~yL+CRC>>fX83 zePsXG`C9G%uENjsxMKILZ9$*^toywg)qBNt9sXbUdw=D(Z}L^9`PbYQGC!!PQ<FRd%~6D^H#6b>s|8Of15ofF-4}X z$M%cY$V?{*=dx8KYzM_>KgYRki`=skd~UJDq1o=D>sz?p! z)i*(s?~JCst9dK@;kM8GE;ip3w`$LqrS_4r|J6P+OYI|LR{O}@Y9AT1+DGPA`^cEp zKC(EqkBnLEBMVad$X?@jv1yOhGl}b36AC9~`*-UFTW!D2&m3^m!z%btuQ`cpk;JMU zTbI-4_-uD?TB7^>z7yNKfBm4hPCxo}T=t;X%lUU+%N{4+^z)%-9ktI--3%k|PFcB} z_LzU${D>3vJ(0if{}ui#-vsS>-V{G?N*}bmDf!>M&3&ewZw7Xy>g)7+?|m8i(P*D+ zoM+XOSc?9-8-GKrsPq#C*4A^;`!;u?l3w4r&=P7SZA1YLo-;2h972nK%1ucB;Z#9d zJCc}#PbH%U&-FK;7R7hCnsn3OhV1-zmcgte;xgOWtY_nNv(Am#tbgO@ky#fPhdP?| za&E9$N5^c|ym9=fZzWiF_Zq*CYds3y<<6Q+w>3MTc+tlFk+*Jl!=4O{o6}XdyKWl} z28~eb{80YnzYlXIeW1VRMr=Oe+S)>o$F4?vL?ydc=RAEwd@1>g63m}A3a2f{^)ur3 zp=Q)}ynYt%dES+7Cz-*1u=C$p1{MGR>ArZiKA+V3d_sNI`g~IB^O@E9e3x3E&#czx zyVUx8X0<*)NUhIjR_pWQ)cSm8wLagi*5@+wCc^BxaRYu&G9Iep0&6|Bg;d6+j>X=o+9 ztJi5{ncB(v>Y?s4Ti)qw#r|BB{kcWG^R=v)ocq|17R6ZWQtS15nLp@aMcrQLhEGN| zZfwO3_=EYEvX!jDeLmrOO|Ii*rO86f*M}stGWpbDw)@b||5M6oFSDKPKEHP(pY`Nm zIrj6P`^s9sRnYr$dmpG{B^sHO(~nheXC*$igZ;ecMlWlBg^tXTYTVI8oy`v4e(w=$ z)kwOC`}0BbdRbTYcV#~>yV%y6_;eR@^&)kw+{5(v+}@x6)5>G-bJRWyOYO5@Kd5~c zmfB~*Y=7RpZGQVRrNV&E-Q^nTwt2En$G8tB=(af{`V+UmBM?f6(%x#zlVdLKRS z${q81+k783?S0*^uDEzfpeHYpV5Q{ zKe@+zY4}YGVz9|3tc;>(By7sZ$rZTN5=;cpb-@?f{QtGJn z%=TyT+va~$pZ}(GyJn7^&76jXc4y`~nALw`4usjvjWC-z6J|3Gw|%=?>Uv(gj`W6pl-j{9*N zJ)d9U#9VhFwJ!+QE%+**d$oG5fbI7p|H6sty+nT#|EHBRft7=vw5&`hvz=d*c;ZTT zP0uf-_g?90R7B5})p=6Iwefr(&i`%8azRbk>T%kw!zbeUP0@3_S0@j0Zy2G+b#{Ii zn=?1|h)Xb1U(3$R7BzKuUD%t;^U2|@?r={%w?BDW602h4x}08vJgx5z>oG&YUgfP1 zKhbl8_V}^$yVx}C;R8>ib-nB6J^lUH z?w_~KZ;!D_#}c^9Kkmn|w4!Y}_s}YRneDOtw)wSB@bA~>e2u^O8V)=Dabm!U0Vf8W z7;s|1i2)}DoEUIoz=;7T2AmjhV!(+3CkC7taALrT0Vf8W7;s|1i2)}DoEUIoz=;7T z2AmjhV!(+3CkC7taALrT0Vf8W7;s|1i2)}DoEUIoz=;7T2AmjhV!(+3CkC7taALrT z0Vf8W7;s|1i2)}DoEUIoz=;7T2AmjhV!(+3CkC7taALrT0Vf9j|BZotdygu;BCSvL zzV*AHchkS$_pFcfzBSd?tUjyG{?+$Q)ypj!?@ABNE!yuYt}W4oS9)lcXvM3)EzyuS zdTFf3qkdxr5C%*Kv|JjOn=xh}K%Unmc=DJQcjKeN&n zi@#say=y@5=l{@qx8U!LPu1?!_1=Gcs&*HzclUSnC#u~oGWB}TXG5fpzhA1|#q;0M zw>bCiUC;G!?j72Q`txto|8&}2f&~ArXS&m8YJE`^pZ~V;nA2xEedhmbEbX*Ar`@R- z!8-)MTm4sh*Ut0KdES{=5lwY|_cZS~%trT{*?C9!_vp+!?apa;PP8w{VF~DPqcUcSP zyx%$RcPf@J{^D42zTY`({G9hYXHLu+XFB6dXPoJbGo5j!-XG!2Xa0Tro1FD3&UzK| zPU5T+`y2NaI_=JBcTT%=)``h?Tg(YbJiP1vQ0M!d^Zm}eOW>J~{o_2}X!d?GJ9E*_ zT(s$LoVjQ@&7}r$)k6HbvCHkGXCVYfE`kDinzb+lV$d(>|P9v^qvlD-=Bd%$?E^M$J z9Bv#Bq$sV}q2hWav_`ZAmP zGXG!q5%rb)s4ug!^B>{_*FYJJkC{z}im&6!>3G zJZNA1yZpeh^&k2ZTYrc)%`s^D4QBKi=o9fvv}yJKnALy&Kc8#(jp{czKl(6RfB0{E zuHhQ`&;MV~HL2CVo@)cFeS53(Gp+RPURHRjj{FR4IJlja@$PnJ-!nC=(}8ISzui34 z#|my0$lUQ|LTmA;`po4&+3j9`vMqCkxMA)GPkS&|y_d{=YjZ!Uls$bu^uyUEMK18X zFo8L3;*bUEoF?WMt&1-hmM6J-<_@reg7Pd-|1hhx1?vAXtGx5oZIZ%ChS>V^EwxF*VqbX*g4F!l04 z-N3je>I}v;;R`UX2_J!RO?__$SX=fLOl?btA0+>Lo1OVK`|u~{L7J^R@V}IEfvx;1 zZ+yL&-)B4w{4jqU>`!ac)|DsAh&aSsnnzn*DJJiXL%gl|C>7P%lfaF5^PXCab{5I% zM!enfsY6?a%;Vp#pVQb?@KZG(Cvl&*#6Mq+Ko205MdyP44f84AFl<{sk zw*TRZZ(UjMEoS?FWN1Y_CoE_CUv=m}rvt~a{dKkea0R#8$o9)l%uS0&on`xTUb!f6 zaaK3#p6Qd~uJtExvi+SDMinpjW&4@3OmRJU`Ul&ubh#$o+WeC3_lc`V(|=ya_CLLL z%5|ac9k#zYSsJ>%Ewu&z{CuwfDZ6Z6UB}hxtIQVsQ)X!ZDZ6Z6UB`8HYc31^x$GN6 zXS3wB;Ga(#1(UMN_SJP<%B}_ftLwOwUAC{TL&`5~U->CW*=76cI;8x<_LZMp$}Zbi z*CAz>?W^mM@(bHnesU?luzlqxm+}kSSAKG-`^xs!eGXE7Vf)HYE_GkozPisYb|mlb)Q`-=GeZ9!60>C*}l5ZE){=lU&UjP zy02_s-Dj7&uWVo4XP1ggwy)weNW~@FS8?i6amn^ooVrvW%J$KkR9v!s6{jxMpR#?V ztGHzQDo$N0F4?|{QT@^AGa-j+_w04+v3MjJ z7XOy5{km=K*Rr)=^$d>hf84hAtDeX4{g2z$el1)3RnO`8{>N?Wf7Ek2zW=do{ik|n z$M-*$t^ZWd@A&@5vh_b`SKNMapKbl8W$QmJTi@=s^`DllpLg5(Ps`SSTDJb*vi1L# zt^cD=J^Hx zvwgHP^lPw>c7}c#!*db#(a!K(gnhI#JlA0#?F`RF*hf3V za~&>#wD-+|H1fQ`cI6XrT@YBpUaQ?Z0mn8ewO}+FfK%V;y&B@ zPmKSi|0G-gkMY0spJeO*G5(kS6XSpBKgrhrHvm))D4X5qRwEH2fhH~n(z@A<%jRUYOZyxEgf^Sl3(VK z**`Y>nB(O*>2`lxPS>P^A?UYRCi2Rc)D3-gto(KIqLrG-3u zMiiry{rs691?Qx}2`V#JS^a<5dlR^;r|o|{jY5V7MHAKYq>=_w=zKOwNRd!UB}JK< zR2rzKOJ?bsT~cXwsZ5#b?462I88T%|hK!kAH1S{W_h)~OmB(>UKRx|j-`(q#-uAQh zT5GTU-fQjs`RwzY52IueX9HMqluwQ#tF>- zM=nzDYqol??d8~`WSvozzh+_;d%@%(#QC4yX4g&cLtH$6jqNq|6k^+KPuKR|BZ!}? zd5|k}cTM7I`N!d3VzFyfyHWB+=`l)wr0hn@pGb5XI0>Elowa%w%%4LBbBy;!KzRSG z#x64Pn#IpVKl{jdVV79O8;L)}GTuo1B$n~Qe_|Og#zidS#lOUevua0t5_zZeIHezP zrVQe&{Gspg5%Z(QxYc`b{B%e0s`L8NDcCC3&e%ieU6ulex19Whoq6?BDRB7Fre)om zT{fh^;l+y^yILph7Jf7!;}@$Ojmz4q!uZIjA1Bk=i+@n^ZWA1@X`&%{?Aus_@$ zMbPuer^Q|K@(m+!yH&5DuJZVy5p>S~_W^ED!)vMYomD9}!YrcBqYgX34!wT@bzXaT zXZKdamel#|k5lY59j>F!IxnqrzI%Pt!?DgmRbAd;-%`&%)>O8a7h6vK zr+RDa$W;<<{b=1H28ExEmkI$yglUKiCPiwG&ItM@7*1j8%{A0nc}s!a=lR_Y;&5*HgWacQC3RLFo3;zPRy7#= zH_x|n6K^hIF!p~p_}(rVy&rY{`1+ga?<-U^i0zU zj+Hr}9+?xn`HU0Ux8+mMSm6zI3Xg1`(LE`1Q;XNFa43#p!)vW@n*IpK)50P46;4^< zH|+}F)534s627N}L)0Ujvch%h7w)Hp>(nXSx036r6KhnsPMyMiD|w$f(JpzPI)R1j z)G6GzQUj*JPE52zpQD=R!nJy)ICGbOcw`qAEGQS4{qYBN$&8>kcQ zlP+ySoeN96mTEEaFzS4~)H$gy?6K6j^3AVP_pExDIyb)aPAYv#FX}wt`kkXa_bWv| z4?n6-^j@!vsdMM+D@GTNZ9tu?CY=%~&ZNqhIf^=K*6$xFo<#S()0H}(EOk|+_?c2X zi3aY|pZZVu;HF6NGg91$)LKX>enyHLky;m#;%B6|5vg?%DSk#no~y|Cocs8Ol;TXJ z)<~rI8J%4BpNw0L&j&?njYO$Iuaf^4?elP?_!+4+VkQ-oWehjDk0P}eOeMQ7V_5I? zoecayK7n89A&nTrNrzQ1u!sB!`>=tv0GnUF8!?9S>g{Ks7dZrWpbL2ex>f#+pbNPO zx>f#+RQ`;h3wa5;RsNJcN+xF-mFH!@lF6Ay<@reEd86{DQF-2|Ja1IpiBz69ss=@> z1{sy-jjBgR)g#th#1m^&)g!k1y&3i!#Sl-dQB{v9gLq<%LdNgY;Aa{-kxS6-_iXSp z?Q13cOhYGf31s~K4SuGf6S)Mr!`Ds3lRA+vkvn|dL_Dppn~0}{PUJ%54qrDBPYa#M ze-cmXM9xD!fS*`@$Z^n#oQE0!omg|o_0Wm6g&YT+$a%=`)G7I1>L&F_-Heda;WO5d z)J^JZXIAQa6p%O$R@vZX#Dur_{}q)J+FJrEVI@57a4jGm^SVol-Xu z7s_LONPeJxshg41P3o7ri5Rgj){5i=+LF479LT;>H<6dv7i&mz0_{rOL_TC+shh}4 z?2GjzIe|V%-87O9*;nc&@)G-Eonilk_+Xt$uAo0sH;v>*>XEvMyhJ@%f7n-HPO<(Z zH&Tz(%?Nue%rDj=_AW6GHy}5%uhh*5`z^!}>r!$cWu$IK*n2UCvKPZ%5dL6|V(*1{ z!5YQB5O%Rfu`h%ztWoT}U<+#$dqn8R8pR$FIXf>fmbyuuQa7#C zP3n}oX{Bybr_@a=b(1=!Zep)Ro!Dzh-K0*bo7i7bC-zrTH>p$Vrd9k*E1p=Xo769L z(<**i#SN?00`_$YKe4BxUF@mUy1>4Ueq!A#ZdkQ0u&-lZY8b;rwreR;laUo}@HR7b6QK!^5tJZ>(+D1K6>m2+5m*AJw zHpWnDor67a3HD(FT!KxhZL}q|&OtA@1Ut|L{y?|NpBB2nALv&36Xy=9%qdtXX1QBKmGZLI1qx$@4fLC3)VddSq3ecd8!Y?3UCcr}8|` zaY;SGIgUE9MpX^M87-+b?!vQPkCvA>*NmL=<TcKlDA5aRr;;6Yn4A~*A=CAnXblS)fm&t2djM>dEE0U_}L)u zrRceN)usbO-)SW((&y!;u87v0a2sXbt^8_qMd@qv5*cYv1EXE!EimLoKQVj}{gi=z z)ozu%ReG$<%`~qc?TKB;C;n*vw~|+5vC6KEc2U|I1|hK zBL2iOznB+dnP1EovCJ=gAeJ#&{EdC?VkOSRGS`Sdv2aZ0C?gL(Br=ie3;wVj{84tn zH@1Us%FjsopHkyW>G3Kbq@6xE%!{|>lr0Aids|M~a^SqT<**jKEr&JYZ8?eUG(Q$u zXI+vpI&j|m;IP)Tywa1*1@tF#0lUduz@KC;;Ab)y@IRRgj4PQ7_>jaOcENwd5dLf> z?|JBiw+RoO@L71(zYgT#uje7#Jr605aY6=mwY=w^6V8K&;4rc1qP%dtwqKj{4f7G( z>H^;~I(>fN7=3==*nNIrOniP|tbBf83?;VI1D^Y}@5dhd@Z7u!)09k->o~tkC-^`; z;Dho3{9!xzqkIOR*^V|f#+345D|r>qNX0qwc>wW8J8}r(pX3?DA9}2h|5oxU=1KlR z{CVEd&yfSh=?;JR3_gYdhdAt54)7U69Q0q`c?c&%JA)G95V-N@IIwiaF4K}228>9I zF(D2i4%>qR&z-q4_0Hp?-9PWE9|2!o^AcxT%_1J(Z=k!P-w(v6eBHzCxvGYNOqcv) z-6db9h##3>&#j-`nYh^%WnAskE{NN|Uu3^IZ8&k)CwkdqJB}uvKKAVN>orCZPdMPi z)Tv8`5VzWSTy#LeImESgc_&(#K8bitp9W2{HU;ICOz|SEEjDF}341LfG3_Gv~ z4Eyi{7=Aq>{sF^Z_zjG4U_8JWAI1rcabx_zhzH^Vj5r})z=$8>2z>Kd-KQk^YM=d@ z@Q%tk-7YbW_lWPMOq$Toe08nm-Ge>GbTR$!-q}I^f&NFC$q&>e{$|)-=ERvDiEG^X zKvb^nKzxo-^57VA?k5fNl6yYgyVk)y8Me1wSP}PUrbA}$y1(GFnZ);gvmEzri2GiA z1McAvUsbts@)=1}{Q=04KxH|&OcLDbV?W&O;3 zq^~||ow<)Rr$X21iJwo+J}+}0Y2^`vr62x`F_#X$ICCEf?a4hK$S3!IpeMN(1pUc< zA=pjsBf+2Kei8gk?j6DZJWVHYXc+i!o_F9L7Ze|Vvr_T(n&ne@iP_NPk@iJ)iox5eBe*L07d z=k8-`xElG_QBS2;+qf&!^Qq_T*X!B4o|s5Im7nkBZtc_}fbhJp+5Ra9?l!hI*cQys|Ad>=Wv__Qa0vv^)Dz&nG|KVh=du-_&#O z#8++2s;j8yyM0Tz{W_O07}uT;)o~v^v}c5vj6Z27+iO)NgK9L!;sY4y=d41IL=@AVMrk**~_jBz#-9tT} zxwiJ<(?6!34c%|F^EQ_=h|i1tAF?-eZ%RGY^4Hqijz5@sp1<;z^uVDfP|rtmez9+r z6~81tOJCi~j_ALcdP>wh*}k`aU+T&4GRB@Zu@&_kc=$c`o+c^knfl~`>6?G)PCctW zdCY#Z_zCJc?O*q%Z*E-5V7~s@^t<%Qm)549@~tY_mS?u7o>c`$*s@O@MLpxH9JFA` z(dSdothJ}vrjezdPrm;5g7f<9Og%@`{Lg~Q{pwQBfPs6bhjr{oJu^17Os{(FNa`8z z((IPUema19zPPb-x zR6J_avl!(^d~|p;=YqD>zv1ZfqDOD8PWe^mofGw4eGv6*K4(_y^L2e__xfF~h}z$O zAN4%lB`>P{-7)MtxXM4HZyWr;dAWO^e$k*k4q)HLdn`(|UwIb$R_-w^I-^o$>fdYZ zjnRq{)2ZjHYoq9;n?vWYTW0pSkD#RqVxM7NKf{as!fcB&8kQ}okng*&9Bmdeap4|I{IYM z&eXYIg+n&*ooAJ^1(09{W?zbA8L0j}Lx|dhjp&z`BE9QT`WPQ~0-_d<*IsK4f15 zKfrnT)&2X5)PsNF2Y3s=5Etk{oZtu66#Uxh(|Xi{f4`ErKo8;sKd|=U7vcgvh!f@s zdN6N@1@s^`@B=vkeqo-V2lIxwKo8=Cd4e9y8@NJ$ggb}@`XV-%Gw8$|f;Z3u9$}uK z2lEErKo58Xen1|40gs^*yvCeCC*}}5h92-5yn!C@2%Lrs$N^#VEsTI>*=NMK4GmHR430|esX!rml<*rpRHiLvZsm;{WzcUW2auo zcK9j#D?TrUpR&JVJA9M<6*26}{tAAkp$C4V&cd$jwcuwOdf=z{mWCeqCjO+M$NOWU z2mVO>sR!{Fe=PLCABn$B;x93`Nz5g-Hi@moka`e9;TZLRV-h#&LEMB_)B|1#m#7C^ z63$Q$I3qlv9`Hog4)tK|2p^~ie311*Jy_U@Z#I z9mWNoOMmLY`jh_DgEc4p9ma)qCjF@g>q*8#Jy=81pL(!vWIWV^btB`U9;_7^5A|S8 z$ats+>pa{HhkC$w;Wzd8yzLNYa9p@cJ>as$mwLcinQ!U=PbI$81D?u!QxAA5 z^G!YArp!0>fR8fY)B`?ZPmlO~uvdkAnQ!U=AF;p3yuY&GmVE5*;m_h;tMjqHM|>(h zSF$el_lWZ&GwRk={-m+jN1WGvC|B!$^(U?TNh^QS${(xZlUDv%6(1{WK8cT2@v$mC zR?Syh#mB1ovTDApnlG#7%PRh))qGjSAFKFd6@RSak5hcMia$>A*(yF;#b>AZ?9}?Q ziqB51FRRvvqQPL}V_Na}__2f&7_ZErZVmBz;B1 zB|5b&{0^(c2ko2o8NaJ48O!gCaSCjD`Khq!^-P6LuYW3Rdb?Bo@6CcgQz7g9oCY1< z|7oy^-_3}#BWy~0Bx7eg;wa;yyx1^_9?@?khSZNZ%D8A3ag>6`Z1kC8mY7<)_}zH9P(3zMCizb@$iCXS^`}Ew!$!jd&m~PafF3HsXYMJ-zaYT8JO!E}6$uhVS9v z?}o*1+vA7sN4)6PnYQ*#2NG|Z)YZ-!crfv@cWwIow+UiV$;9|u-G)P0W3BR zYygW*0~^3%)4&F>*rW|$u^GVzu-J@X16XWEumLPKQ?LOnHW$DKu-LS)0W3BxYygW* z3md><)4~QYVhJ0-h$U-A9 zukC7ow4d64JuW?79S0pB9XB0M9cLYXJuiB`z!i)gHue1KdDncFFl=HjfngJK3=Er?dtlfECxBto&z*x!KVJ?u{d_st z^z-Fl)6bWKO+Q}_HvN1#*!1(|VAIc+gH1nQ~yaZTk75O+R0>>F0|!{e01; zpD)_<^F^C}zG&0W7skcd$=ES2#ts-Z{d{3uj2+rx)6W;i#n_=8HvN2IT;K%e3*$=W z3*$=W3*$=W3*$=W3*$=W3*$=W3*$=W3*$=W3**{qzVzH_?B|#Ae%`6a^MU$3PiWWk zhyHk8(NE7e`tNzjaq02uICwrYK00om|BR=OvtKWazh6h37d>Bk9`*d{dDncp0lT!Vqe&f<%YPo^1hnZ`Sv?)v}BaKYE#AOpZ-|dwtBk2wRxxE z^p(9Drj`{O>F&AssOfdObc^nn=PG%PPMZF5$Hme6mAbgf6FN<=bxc`v{Esc&qnCG{ zUTxli1~z_NbMkbtX<*~2H;$PuHVtgtvg+XJV$;CJgB`0)7n=q)-mXw=y4W#%mqA))t!>myvPR5t{}!WL$N`W&|5Dt~z2ff(;p0 zp4g0FL&lXSHq)>nHe_725lh&RaZN=m^?YfpWprPyQ`^!$ zXy3HYdMtX3dh9wTI#xP{I<`9IdM@-F>ABN$s^?mBKyyQLMsrDXOmk0j67fyAinu2n z#(X5)#ylmQ$NVL00rQ%y5zKe8cEE#VP3iga>mBvvZ@X9YwTbo9*Cy6gUz=EOeQjbL z_O*%i+1Do4ZC{&M&wXv;9?91x?17USy+ii)dhRs#c^mtJWbc8!bh7ur9y{54@J!)r zCHCaW-UEB}Wbc7J{8r=A;V*z|Q4v5fQ@)N50(S-qC^8rN%I=LDTAbPmzEMduuyi*%0Cxl89Xo$GWC z)VWdTOpUdS?yGfbTiOThoAz0cMUPRBUB^VnO2<&gR>xe=g`OilcYoJ-8Q$?+x^xLGLB>9z*Xv^c)R7{($LtrhHS!GI;_2PsAY) z&+KHrrptT<9O4i-uwyt7@?@wHfdfUv0e^<#^V>x?7snaL^+<1wDoog$c<}4XBJ)fh z@%tCt7|lJb5%HZ*Hj64&Sy96=P1!zm{@1B5w!}KCK5+b2&xhq%A7$iOpOt5Q z#PY1q%CkOVdDds;Ss%_{c-H6SSs$@H>vQs~k651dCFeCfgLN(6i*=Sd{djxvfI8IE z?X27F=_gkvzVeZ0?8mE06Zg3N8~feFkEo~PwY$2b2R})?seaY1bk48cknQ&@Y2?aI zIvnpl+{|f*xR*Om;&arSK0nw^*z2eW?Jb5KSwwBT#31MGS|k>wUxOhmbtbv*Tgc{R_2;m=Gw|!6U$tuWv+>3t}!pf zu)__Hd{$NsF!^Ra%GD{ivD}UEf5PuFhy$_x;&4x&FYW#}^x|E`k1n2K^Pj$m_`^HvSa)B1hY|OV@C*UA zr9Dd8MLtU8MNgFIDGHtTlMkXQsrdI#Yy8;HcSc`q9_--T6|Yx|?%NoDXJ`J58|6Er z<2XsXP1;4?Ci0@kDxDduWpv-)=*-yCKERK}u7J7;*1l4YfN=*;{$V_E2M>4e(2jrc|G@GG-=$5Ae&~-z=)>JUV7W7i zy>ub0WprQZlF_McX&Ss2lUnxJD{%Blt?*VrD`r&L}wPubjcUSy9)_RN@YZ=`aaS^|%Cl@R_BNfjK7X4A; zgXoVE-^AyX@;`&MjP46xge!924}X5e5>J!FT;gexxsZ68WR4`BCYd{lr%C2i;%Sn( z&gQ?C(S5Z}ZA<&0ecP5;CS#2MjmP^d=Ks52|36+kvR?4L=4{8k&}6NNT;}_XagQ`v zoANL3sY4I$oytG#EB!LRgP!+P{d&d6H}2=Nw|6ixA&pK1UJz+(j%uLQW(0xsKTTpU8+<;q|CxbYHDg z+tNO0-?Yy@PiFGiZ^mdvcahWrd`2LdYs~@84Kcml_>9j7U@V@)$=ree$=o6KjKAkF zvFC6yFYt%h`$_EmCzkl-C3B~-meGCv7};0b(mr^bl=171KI^f-CO#ja#+b}qW{rD2 z4l-UpvA0X?{UO$Kq30;9ySUCutTJmkth;!xsA~i`8P?s_H8-rgcNFQR@ z6kWvLCUM6-Cd^RnDJ35%J(1EMDZ8R06ihRp1pLMw;AT{S8n{z%$=Mi@OvudJ=r^U{1PKJEk9T>v$5y9goh{UP&BQy>7fk-1IRCS~?Yik7 z5f{(zVS9~znbA zH}4~28E+)xC6@6yebYSv?{>h1SS*1o0hYabz2H3xncX zrf-)8k+!S*HpzRBGCk)GjI1~!jY2EeXVNWs;}}v z%WTzGjYZqCy040fRX$tYSH(7KU&Vo}eHAyXwyXPUTUuVr=yt3bS(ATw7vj&!{FyyZ zF+PhCj^f{K#T=9GyN&qI#G_bZ3;%8_c8E3Bq#AEd_`wU`w3V*uOM8v0t|mU^vD?#Q zj(m>znDZ*xHuciP4_?^S-q&#^@eO^hxA=>`Xv5EdA&Wl1&;eb*&^`OBucrdTrnIM$ zc9D+~dC@}*J))l&`sFV%Y|77wVN+}n!=~6EhE1_ST(Gw34Aq`e@{!ULDgBYM8!3Mx z$?^cOziWqk8>sXighCaJF{DmI0;b*{*Wgo%N0bOW^Zm~BF81|(-O4>!9 z81k5-M33k4?t4Pw|78^i@`ACkGwv`Y*#@)FyO9*KEIzfpF< z%fug}{4~mcQ?JA~`F>nzw|-oZCx%TGALw^}TpSxPZT=c(_(>VqRPz!g^NaaP<`+1b zU*Okf?CokdIMJ-@bW?i7x^l$nqdMDz>NI!tD>XDT#vfvfFW+DxW6!_ewl7(i?ISwO zwToLn%k}|{KCrhmD#!NM4%lcbl^e(Q-FudHGupjoq33}ks=9^8?8Wv*r&n;RpT2_a z{ku1Iwfoea2L1ais_gPVn3sn9QRWE9M`(wR( zpY8Bp{4|hnsqsD9QA3QVP$IYntK;HVep*@MGQS$;lN&JnP$4JeWQS%NzosV0j zc!F`UUE&rgE~ONIu&0$jf2JOXzB@LCzs6hcVsUSPyQ}yN1^kdZ@;Dz5%l~FR4~P5U z_zM}i^NW9pA&Wj}hYsihhHg14CZBoY_a-FmxQ7qyZ5m+c!M%N8=*PWcVA%9~7yPfo zT`~aJOzzvpHpj3XpTkh?_$*N(&+`QO${&1|DA6zH%#2;Mu^l#*pGIuZXXutY;PRPA z{27DxWW1UCT;8UG1oWu5Wj@0Mn;0`>R2_8q?}2r(Zdm8%b(8N=WxM}=Qp)@9Eu|j+eWuj!zvq;8{r8{JAOF3m^wWQj zD*gB0qslR=c6^^Ka}#VTJ$01+JY^T(S1X@8zQD*l~H{JvxFDz{Ol%?FoQ{0#hqta^{&@H31jmR)Zl1Doo-gY-L^GO!6>Ap_sl zdkP0%p$EQW%#cA0)O!twF+&D101F|5{|DCV1a0`4=!uk`%zGcvlS=f6Ka}zQ@VyUW zDgH!|iDS8*GJaf?!8;Qf7iBOmiI0ITA0Nu#9gD<=GKi1-j50pX20kN}@-xaHmSTf4 ze!eJ!Sc(nGAeQ1QW&FHT#?L!t5KD<2Wjuc9O8p_m@1FS`xN|%_nHBRI0O!CZw~ybuc*%g;S63hXK<{E zFn4@D^FQ?b1hW=DCjtsMjzWk-h{OLS4zzxGsO$6T4LmE%F@4>dDQ^)kf3l-{^o+d> z*l^2=7VgP*Eq3X z<9ycTa{{rJ*X>$f>rwfEdjAitk-sfx)SQ~dHHJj}CJyJ^=GC2+%4=AV;B7=N!lz2p!h`xE9C$stDeC&ZFNjO`#cbyl&U>T2J5) zBJlU(jG9y9IbhJ{IY8_=5TV_3hFHt%b}g^%Vqd2cjCz+~)U`tLTF;{&7P!W}*SAC*UHegP(%}`E-)58>>`E-2OuTIHS#FQ( zza>6@=i}Wy1vMPx@4C9atMX+;JZf!e*ZH>7iH|(a+D-TND};-}*3=_wxDtmSPg^U0 z{>DE3ud|5L^(Wh<`SI^*Z?mPmZGZYGw$JJNL(9|OkM{si&N?YNZq7)y_pFhQ&R!S$ zT%}8CGwZW>EE*Sutt0mN&MsmFc(mnBh2jUOjEpWRWT8!_D7N0%Jz2o-cd}&;SwzLoU{8KUS8-4IT6Z^3^ z$oMf5`>_*yKMP?$mhEcG&#!?$o&&_58^oS7#GXsUo@2zGd&Hh6g>X^W@@tK@{2C$ zjpQF<8M~4ELo9wql79+e8OwIJC39^g|In6jAd>t;EZm4B{}2mjBFR6*!leb0e~5)+ zR`L(AaL-EqAr_uE$v=f~QP`5T7D@hbm}^;sM)D7_tW6{NhgjCEk^Dm}YuQNtv5=QF zZY2K@Oa3vEf4KH#of^qMoG*=w(3bXrInet?AH2`Rek=z5`!N#xu@ieg3t>N&?P|-< zwSzyN1H_&i#GW(6o=e1@W5k|&#GWUGa8cOuYmK)28YGtdgSAQQ*DSGL%Z#DqAFOd= zzxIj!I^~{3<07(^+5h-lN4ry=yTtuGvjzR>eb0q%UHACT;g`Fd;#z&YC&zMQ{l@Nn zdl>OC*OYQo&+AJ3q@@xG|R+S1X^PscvDdi}oWy!?19MWNHz zdISDz{EzqY-1(bZvAxTuZC$0ks}X-(ysz7T%G(j-Z}?`oYqg|5@zI|bxM%lxo^#jl zo=e;{y;^eadbGaKHLvk>A-uixd!HFYjlEs^=Kaxrvfg?B>6;%Hu^%sWdOwMaLZ{~p zW2>>BceZ;z5PO~wd;So6UJ-k~5qr)Q!rM!~U$cy-#(u5Qu3wMDew`Bg^-Jv6HL+js zoG-sliHky~&u@wUnf-~_HIjd5SNt)Oe~86TBl#!s-$?!;mT?)$Kg2TLNb(P{_#8?8 zDTKF|e&NjT?p0*ojpQHN6+RfrKg7b5Nb(P{@F$Y|LoB>XN&X=gzFEmX#KIFR`G>eD zbjq5|?0+jh_-i_oR&X=rNBl)Kg z-d_5>&y0`8-Y$Lf{%Aj2D*x%59~ZG7FLio9iHky~=MQ76v7dLgdp;0*o)CNf5PMz` zd%h8S&J@DiOTS;gjHkwa-O;XJkHmhR5=;KU`X%=3n%J**&X-@O#6_VqTYTOt)y16D zqb&V-dqXdC#)|dyL32Rk{~}Lbd3j>5li2q);G|yT8fTNwmfvQWMyV}}<9s4GonVp2 zevGy>&L%HDU>}wEmcin)llZV*d~*_?WQ^Ev6vF>S-eT+$pUhsx>tws{>wJ7N`#SF% z+q21Q&in>v_N6{P)Z^no?BkQPBZdh^Y>D-rT;s3r`YihN+TN5|)^``vpj&6+Y-f`{ zkk35dlfD@&I$feu`r5>n`0%^W9<#~oXG$6`oLAsp{=5~>k{%~#+uwb*mQCLKV=#9b zd!O0veIxc`EQJ3+KJ)y+$2QT4m=pWh68kwSg#8>9lGkTmjb*$>;=`DD%vgCD@?Ya@ z^4a{+`=agjT&O5?X50Vhx!7LMg^EI_o+FL*UTAwg7b-%XoI2zOjrCq=dp#E_3Y~h-qp@Gt9M|@GE>uK1f45%9STfIr{IhX#>Ce0uD+--5 zr#tLjmGCoDfBpLo&hMXj*CuP~ck8LFcZk`DfmX6@^Ye zr^e?W%rCL$74i0ZFIE&f{hCUipJ2@rORm7WrvKaPy;xD`Y+HA*nOrx1&-HHe-lo_) zpOZ6(4`^?yEUZHRKk3%g)SKFz`1ps*n*&##OkCp1HPKTy^dYYQ`HfNaUh%UOzt3m8 z#y&qYKGo-rGWYf?OIvH^4Uy+Fw-Fz9=sBiG$q$J){_7-@US5fMrVTm7yl_i1;;{u4 z&AC@~ARbZgz3A4@;_tuyPsf|1E(gXw>_}UBj2i2h=ve6(>e%X->$%W#q|c;n%QQA8 zuZ^F-JyLd0(`(8pjL9#vUynZjCjMP*FFbNxRO$GO+1}{-^{L*+k0#!KYV-8IHa?%` zecHiJlXq!YgBoiY-B;_>wzLo0H|?{=OGh^{ho5yg?aq2>ce8BBsl=`3z7kbkb1w0D z<*tn0-D?>XC5tJ$3aFMOD_CjL6-zbE4qz^lN z5t&!6iQi++PIoqUz7RjtSXk@=b6fcp7BN4m`Ec{_?IVeg-=)C((2&2wwb;CN1!hC9 z+qrLick^)5s7(B>K|jaP*zZ3bbWXUVnwc}UE%EGON0?@(9YkEY^J&Hwlp{`Ed7fFh zY!&UEe#tOXbK_;ibyklyx6WI{dT~zQ0(0)1>*&K#2aGVo4!j_O{vByck5OYC6CEoZ zLmgWkb3GS&j=X-x!RsgX`WX|ipE2?J856Ic*y}flmDgVgYZ={F>(sWi585~Fv&MeD z=)a#w`tRqL{`+~S&z=v&o+tF#^M}~;ir90Y5Z;kK_W#eZC_0`HI-*D`KCo zh<&~y_W7X@_W6YEKF<*Q{6p;X60y%$#6FJ^`}{`i^B%F!hr~P5R<`l#nCMvP80y&S znCrRFbL8tI$LQ-Lv9FKBzCIHB`bg~SBeAcK`nL_Z#%b z??Z_F{)E`?TZsLBhS=|O=(FGd5c_=*vERe|;j{gs_CaFnWPeD1B%V(8hr|+3C;LN= zMdImXe@HCxbh1ArmUvp(9}-JEt?UnpC5D-2zZ(0!G{-A(aI!z7Es2lZAGnQJ;^t(3 zNG$PmvOlCwiL;aaA+f~Y$^MX7=EchXkXT}6Wq(M#BW>w1YOG_TW2IxLW2{re%LfEbBKV`$J+`zme<@3t=sz z`)Zxqmi9sWrhV2}@}ZOcA?-?@bh1Armi%dDe@HBO)yn>mSn_RJ_J_ohhf}gYB$oUf z$^MX7@^&QqLt=j(EQEKY53)CKvOhGaU$P%?vOgr2{eYAGVT5+s4>;K$63c$T$^MYF zTlND^_J^$LvLA4=KjgZQ`kQ%=qp^QJK>bq3o$L=|yTgufvOgr2y64WSmoa_(jgX}k)><{U~j0g zM`B+eiG6(}_Vtn2*GFPsAIWWB9}8hEqx))|+Lrb~`=))?*zY&!kKcz7`~3;A-?tF^ z{S2|+=g?=r{~`AKB4WRX;qx?&ccc%R8~^2w0e#kMe;fK*tlw;R47?r(8I8TIKkVyc z#lC-V4=dJ18QPv&k|w!RV{ zjF)}=-HZhP*E=n_^u?UTfBw&Xe$XW&55FHHiA3N)SPOvzfdhd9fdhd9fdhd9fdhd9 zfdhd9fdhd9fdhd9fdg4Nz~_=aJ^?cjf8XD07tb^P8^##NBE%uYA#fmYAaEdXAaEdX zAaEdXAaEdXAaEdXAaEdXAaLOKIG{gM{|CS0DD!&>wpHH$P8B|n%=SBuL}%vrMQ^LT z{+%${e#eoQ;l0ppmG{2!uA=`vPQ-pJ#NKD(ZI$=G{~^)&Uw^08w#w_@St0Ss^>=D9 zR=LRQ`^*~qyUNL3+|2K4^Y@btxTtZqyVG8V@zL1Jvt8ed)_0yY)-t-UzoSb%8tdP~ zrtdb3Oy-{VLtfaN@5i;( zcetxKKu;2%t-gC*#dE9gQdjZc>buds9annx(rF3)yUtzd*~jJ;_1w*GH|77Axzq2B zc3*k1iG67NK;qWb=i1c|cPEzI;zm_%O+0^G9VdT@rOnCDh(*>(ALbR&;Y1g4 z^1aZ=Pq^m~8$f7>4PeO2Klob=dSC+>`n`=}Xv5FYE`OZwQw%y18?o+R-;b*HNXbV^ zk5T&Z-OY(z0~;_TvPSu7l>g@LmhERk2C-D*g?thR=)qs=QE`J^wxbO;AR~W__(=>M z;y-b$drTrz?97_?&p<5EA;~kq-~Z!Ywl}RdAg_$QhuDn#Jg?ZEw-TRO^T7Onym>kC zvNqlG`eN=>J8B6CpF!u_@MT&9r|M%tm*Jaq~ed-$9CwJ z;UEVYj7$CyH*Hc*II?ZHTeZ#1t*^ZJVEUo)UlX^k-bns^hgf)KM^#-yJb&CYi@&go zHv9}2vT>j8k~6-x(1mvB9#?L~bnmC++XqugyU0htkQY6~&{O8_NyOFim)W-W&L@7Z z<{aB=?90Tq*+1>N=^qgn&+lO`nEX9){%3pJl6AHaUo-Izd|sNltZ9>RbyRyw$wx|0 zr1VG1ZlwH?Jeu({+Eng{*q`=aMpwQ40mrrWmJLzm-S#0~c-$|*j03R95JN`#T8!OF zUlqeh#Wqqg7dx4`klK-%Bgx5`x%*u{fEeuzce{4CP8bl+2Y&8AG> zE(;=USNCm__a0?>&K(?O>)Y_M&6K(Hx>>1geU(gF+g0r;Wy>lYDH+|@s`jn=Dj&4W zR(;i2v@NUqs+d^iv(l6y05mS<+Y4%2Nz`xFh2+UzYvFC_kLhbK9y;{dYU!2hB&PVoGnWN|O%(^|aA=1f6*t&rJ8WXi zkdZ$)a}mR)=3)Hft>(|fZTRo@ZjbX2_D-Uk{^X7`<3&IA_2bJ08;r)wZzGOlu>9Fm za86?1+;OqQ7XIBf4F$(f7o{wzaz*nkZ5__Gi7$2OYrSsi{B>&cwC=%+th zWzIv8@y{D64`2M5i{~MwCpmNRJf!T(STp|626W;)gct$iJS5K>XT<(w&RlF)aeyA2 zvoNmY%*FGTif3}>qO3o2(NBNof=!&~ov)10mu10#396C z`*9$tzb{W$d$1xoBa9yP0G@ftpB;Bbc;w-?^`04fOV)kt+4Npc@A35BPn^x{6ZBqD zKhN*Ixakgmo*zFyjOR|{<Ar2u9e@71VJ|S%fz1@$s z`Pp9^-;*AC1~I9N^%?UAyjN3aZ4? zaFl8Aa$Vx%D|a<_?opcfi8B36qYIwm^P0AkN0_{dy$j(Yw8dvh-Unjuo55JT&%}N# z#D0v#e(c2F&qCObYrERIWY%f!iIVZ}qi%BDd2aqg@$aL4;EZ8z)F+qIR#`jR&3I}# z-bWRyBER!{T17gucgq!I3mYH^%f9o5gZ=&;bD{l&++x(a1WIp9^JTe*jZ^c5<=%drF`PVoq?>$F2jcYd0yk~nJjSzhnbB^T+roIx?K9M!z4AuJ zP-DH;irNRgMmja>9odN^9LE0W&Lg9aM-C^}c}C-0`s%e=rfq?__;SA2E#@&}qIv#1 znDNQhSLYw^Gv~sOg*e;#%B8QKi(Ihg@YD~^cXj_2|IYajw+wf+e&|O&%(@$?Z<+5wYZaC-sO} zYJrn_#Q7BtJE=#7a1q+#8u305d*2+^viF(TkA>Kek=T!&*!x)s`*CeoTbeVH>x|@E z+Le53B;OKCzBQ6>i6!3}$+yIkZ;j+z`Xl+)NWLYOd}}1%a!pCTHIi?+)+EOo$+r<= zqVbOOLDsU7`b+<%{u-&j^jYe!k@`z4_18%KrTe~r{%VyVAI z>aW4Lr2ZPIzr<31jnrRaslP_*FR@-D8vhl1(|JSkxlL-2pBu^Nf5^8#qf^gUE?DOrA477$$Cfx-F3qK{&UI3w zoz!=Z-DAc?=Z)XNx~?Ao{xdrNm1wzBkIdX%O)^xx-Zc^D~LZe_GRQ z`sCO`cw6-x+vHrg?(Wr`-*X;6#dY~~59<7E&S9?a5sisUFWJ}4`1}OotH*z3mzrM0 zd!I1XUVqO;#7l?e*(ayOK5HK|E(%+D70xghUsTc{Zg;=Z%0zp{IpL9!d1me@aZWgE zc?omj@ITH8+p6cwUfqm6GS1KcyuZKss_qkv;hr~-G%FrHnRwlj0(12GhUCVG8lz2> z7k(sX_PuYYnX!31`7nE0A5*Ep8shygI@!!WxB|zbaZ%XPYwFgcJ4MHz7Viya&uEl- zba4TFc&*DX>AQ=KCZ7E2&31N`_&ZW3-v5Cu(=Pt*)CM=~?Jn5uB+8W9rMcT}V^iV{ zXLfXD-rbA1*^0jIqEp`B7%zYDVpo3U)x>ws9PKvGS;d%W{8#X8#h^XiIcLP*i@N;A zM(*U34(C{EUC`D|exe%jg`Il3anpa`Scv%>uW)#;zRW zCwq@}Gt(Q$hx2M*?E0p!x8SW_7aH$KAK-^PcXIK+{~hc6v)ikOngbdi%)WE?KEafK zt17YPt;V_Z)$4KK#?GeQ!1(*ECM`MD+;zt8jK5wZ8t2kib1WCE=i>3_o4PKC#NTUt z;$JKi>Ud#DyFLo!+zK$Hw+}8Nd=+r#P1xw6bQZJ;A*rbj~eX&V> zk-B4(x})>9#@nuEoZO3xc_lR>N@|4Ejwq=eQd6R&rbw+ZNv)9@WRe;rwaFy4NyclE znx(Pa``PZcE}zrhtUf>fKI{`_j@ zqMxoEZQeTgP3EZiw-lIzTAk0_b>iX?=9O7J$>(WNKU2GVyeFU6t*hxfG2W9mo^+I% zI6OWxZkSu!%zvdd$E9&m+to3Yy6=*@FZ%(P><46@;F5iU_5iXsaLL|4_6#oBGss@TC3^|UnJ(F5Xj~Mw;=G@G{@3%E3)XzT z^t~g^PaO{+H_mvoso8u$yrwiyG|r{3p08Z6j-k{Pm(&!gH7=<&nhzT1(pS%y)I^um zM5&c7sg*jHYMe`7KVOWY&)dX4pA-8$Pwe#}vtBuP=pgQP}eH=rC@d2Z()sAoh8K*mJ26-c~(+P7Un(HO?6NwNLDG0`slU70kmv zhgkIWxrNyCkiKbL6t;96FmhfXmh*y<^8&{x=LI9@1!CDd896U7CK~@0e3QMLk@Eumm-B*= z^8&G)7mS=2h~>Os`k-T;3)a5L{@KX>nK6<5vyuHXvFx9X?4KD2**_cEKNIV@*7(op)N#uNBktSs zUS8*0pYshg_*y`$*Qv(2^ws&t*DS`+*D_+A6Ex1HulRuHOZ3w}cOv%Bqlo=;Dq_F) zE`+yL4`P(W**{aFPXDZl*gu0J_Rpq>{WB|K|167G<`>VnlC_h;MPWowf4L3p^DnB zj-i|voSYXJPdP6*IWI6r$$7!ad4ai0&I?Y?3tYc)UT|_=AeQrjlk)<{BIgAs=LKTf z?>RXy6v9PqSI5&oC!`Pl`601?u1G9v2hSS|;ce9;>k-fTsK-A8WPJRyL1O>Rkn!}- z5*cUzj4=Yo{If@5$su?qY0$25QP|Qt{WBSk#XqYl6dxV8T>5JN{WB$w%Rg%(*11LF zT>2tLNuJ3CYaZr;^?H=^j+65aVy9J-pyChFexrL5r+%CnRd{s}@ybs1qfh$BznkN~?D^^2U%^k!4e{S5 z{>!**GAn#kFiy=c>`zvZEaQ-9I%cTGoCr@wZp6j~eXSo4B#v z$8>(M9dX4fhnbac#P6Y2k37YskKU8*n$H^V0K3>fF#h6?OZ*W(UE-(s?-KuITs9e( zjMpaPl{nZW4icZ1NqofrD2bcKdajGYuI5iJSo@O;*7GuY?tt{e<6}MuP9<26_cu7h zrEGmQ2XevsS+UPc?;^&pPv&y zk++F`J}35hp4jJqVqX`CeZ3$S|FQN9VZC08!Y<}1;ZiPG`;!aS^Wt+L$LRB0q4EAE z4yX}{Jo0CPkynW|2Xeu+&K}}E?tcg8F&8{=*HhfskM^XkefsxwollD2gYSRq1@43% z%l=SLE`7C(#ZKoC8six=k4QJ3ALDJ6$LAH3dB??gL(FGuowK#1;N1mj3PgNpIN9^}Q2k$;F057uXzKZ(8n#QNMC<}T(yn7d-+hF?eIn_pkVVco^?3F|K8%#brf z&h&eSkTc^wOxUZ$`&fs)8TNh2K2ZKQ>@y_@A!ml18FFU)JBGsfEA&WwMrbafh^GoV)$|KH`uwL(U92GvrKPD|p@v_f_KGcOPoK9}{Bv->}b&_f+AIpTr^L%#brf&I~zIo;iej(Q#b}ciMlgkGwPH z&l=o6$TR$Kr(NO`a%RYxA!in2P6(ezXcF$$hI?XM3*pW~xbqO+-~Dyo-^o_Z{~6;F zlzd(^{{PS(;t)6xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4x zI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4x zI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4x zI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4x zI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4x zI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4x zI1o7SH{^hc$Atfm37EkMafmq);t=8xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4x zI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4x zI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4x zI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4x zI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4x zI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4xI1o4x zI1o4xI1o4xI1o4xIPiDjzy-7Vxjj1A2;<2Gk1Bnvt5#xv1Np8MI=N$e?MD3L&%NB! zkFEbhJ-PJNG8zxOw!Ry>KBBER?k?;4z0;Zam=??J%0?FupZWeU`$Dhb#QhiEn;uo8 zfVlqL$*B#^V*K5(!O@IavCRAXEsGAC689}TYiHAAL>J0`{6IbP@oYo9?!-2x^tyPw zCoJx6E?WKz$EdNE(S5Z}ZA<&0ebYYcvFI`CvFn&9%h=RDKnw3q1f@W(DPH!Yh& zTw~%0)A8`$g|L>^v9jpxUlDYK|v>cOQkzU8gT zsc&D3aj)-7rM`VT#@j0Yuc7C-)g?dR*mJ?>Ej`TLynkbk>&ZTCT?bc<_^RTkyBD7; zL!3=dE`7C(#^uUZb&Vf8f%<>C>}%Wbm$QhsJTT4fdd@|}>+09DmtS%z@jc^ioZt1A zI3{N_-Y?2~BW_>Ob8@t%`e4f3aq0S~*Y3TE8@JfUJYK0i@lS`eFzugdLR_m)M^pQ? zy<%Lwuc>{=+l*B$jg^eW$$qU&(; zdhg-H`<*z-G;Un65Y{rfZ#MaC?Vp@>nz`~HfiU-!(FpI8xb$=)zR(rRy<$Xc$iDyh2?%uJy&Wpb-q#WKdA)= z#CT!r^{ETn#&~p(4^nH+_wCy#Kk4-|+^l*fs6Q86y>|n*Tm6XgGe)M|cXbXVzGZHE z*XO({f2b#yzFJ1(pKjX4oqc3nF^giGzCRpa`#`o)LRkClqoTBW;h zPc>*4SR2igA0j5o>$H)_n+bJ2{SL@Wav=7=h?Xw<>9-|(+j*0e1R(_w55GEveT&9gM)%b+x!`A(o@t)F_b1xY_}=jY%omqG!uHaQN1E$@ z?DB{HXc^si$v3;Zx6VA3b2N0sfiB%JMVx;^8#m$8cz=?O&$;wH{frZ%OWjE7T=V1c z(UhNJ-1p{VqH&EcVf#-FkBU-#W4x{Mv(|QSYj>(hJ-OfxUsrW!m5%GqWxX4@4@Mr& zzFR6E<@#4V;1BiW(pSr9+UP+GTCyT6Xlfy%wCmC0=Xq zJXkf_we%?ZGqU-_XwdMu#!VRZS#-=TagDqE#42XM;<(10etvV)@%E;af7+dFNq|d-FL#AP4>*MdT@^J*r&RCV86D+|J>NZ{rjhQKbDQpx%Az$*$vUTUks(r zQoCOto!|0e;uAi)CTf0djMt^Fie7jv#@i}iVp3~2>g(FnnG5cH)voTCDV->Pee?a? zn13HjJmsW=-9e8Y`iFXQ>8oWl-q8DbJL1^5#yxiW7~AdTVYJm{?fmqt&*NI3y7q=t zg|p&ychRKtqklFYL77TlEslCz9@n@|PnI?tX2&(|=uLIa2Mv#+%p-5NHoa%WacDfT zn`!g*PHgXcPk%GytoRJlzW+$`YQIy-6OFZu?yGfbTiOThoAz0cMUPRBUB^WGqw%s4 zqfPq*-sM`WCOPTM5BF(_wbuXp(dLk~kEef&wT$kYO+H)uog)UCQMb)ytTb*kf23JI z=R~$YetUsgw4o1u%ce)m=)ObOuePOYp36CU=BeG>gjY@@E_G#n*Z1pqKbDQpx%4g8 z?UAVA?E|QD_oE+*#&3#os@?<9;vNIpK7RK((TasJ-d6dtb(_1cZ^wB)7kug1?`@yY zd(!S>yYJ~XOgx47m<#K;>zlVG&ZZ}qzFJ1(x3}y*98Y{ zjMv(&O)E$DHHm9nw{jDrWvk*EH)zl&(N6oE&Ax}7UD;F}cp~xh6Av{5`yNc(xys3= z{=*fB`|Q`p?B9MZxv{GLP*bCOdn6eb*HhG(S5Z{F1Y!mi_NnqUBg&u zT(`t%Q|Ymvxz>LAs=&P4XdY{BHl12V_x;DK57`cDE?Lz*^JKgq z%f`c8`X1BgjcCO)eaVLfJyu6wns|-Z>GW#!y zlM8M={6%}ss@PVkQa{^4$HcY%>?tT63-4dgv%~`<%VG*7_Vg+{}G-WFf3&bl+_9+1hV0 zmzXDdwq^`9KIF*)bLZxkjA83XMw^b$JxAZN>CrN}?+Mecx5etld%S6RFWcLi$DG_U zZWs5jqvPiQ*?5>s-}Cp`65Vli%5^GFG|;)*lqTQ)tp^wlyNrzRX~$E=Ib zuq&>+alx$r#B1%EhssCAyTvtb$ov0_KCCx{KJ0t`N6~E);u=?F#NH-d^(3};da0S2 zap)n$Zx85T#!rsVwrwY$W4`MAK6!H9YeP)OYi}ifOU@wXf%pva^dgeAB|UkKg#U1|4v+A`;8o7y3aj_c+2G%nKL#{Erhj< z?wd_MTl?9kj5cqq{*>!W3eKO)(d++f0IY2fZ=F<1NiF=rOpT~Q-^$+ZB23>b5Idj*da%OJ*cu#x# z%e$HPmc@8m<%f0J*)6?4es7fvp6SNgPolW)JbL;(dtBeR*00I?(0!#wh0{4BTe%6?|cgmi>`*U#UMFmIjQow(c`1*Xnj@fl>{ zt)tDBomZ1H8fzKdSL@Wav=7=h?Xw<>9-|(+j*0e1Ycn$i6`klUXgJjA>(zT(vabNa^eTz48D(QmZ*;F0$k!(*-+X2$>HvO+#+omxis z?R?vh=}t9cK0I~HRrcby%4<1L( zwA-zQsnz><;sN!mn>#AR&vUj_e(tMZ*h3!aMLoITYbzaLzkeXEJC_|c-cDE=Kl2%U ziLo`5mun5W-jEu;Hplh4+E?vettdCEatUmCZ%;1bi| z%_C{I&Ao%n{ol?i$fuA;9z{+BMjl131kR=>m%ds? zW7Hhf73fDTLR|qyjY3@kM(sjf0Y*(jT>(a|LtOzz4Mbf5Mr}l00Y=S4T>(ZdMO^_# zjYVAnMx93u{w>xry06x$ZD}90Z`x-)7ClBib{&&!zF|LteF=QVegyjxVC->F4}Oca zjP9FFK3h9#5$X!`YmB;t`h<4WCDbS2YUMc#`?oL1jf3=dIR28dF=7ApGMzYFwQqPKR_Pm2Alzaac;ob063eTT>5Gm zjd8}pISTr5_QE*|7-uq^qkwT%!#N5VXE>arfN{3NISLqOKAfX~aTdfm3K(ZZoTGqo zcEmXf7-veHqkwU)#hLTBSj*_XTBo+9ebByXpY>Su81>k7OtSfg^Eb}n@EPZCoWp@} zrpNi`w^+;QzS-onwd3rCa}@MzjB^;yV`#@Y4CgW6YB*(9meCl`6!F{;`tht0&kcd`3=+=`f$?k-&kcd`%o5KHf$=O8&kcd` zj1$idf${7U&kcd`Occ)zf$^*q&kcd`3>D7}f${l@3&aX=)T$Hv$f+{BcB_>fWmn0i06-J#&btJ ze+15^N6YBGcvgz%r09$1qj=T{jOU|x1`3>whq?5{^AbEap&ogTg6Ao~c)o(?EWmi~ zg6Ao~+bWNDICyu0zPVt$zry<=$m6{b-thqAy%6600B6&aOJ6OcG2Wr!JsI@l-5TDL z0ppz;-jf02T^!z%0plGV-jf02-5uVO0ppz>-jf02T_4_)0plGY-jf02-5}nR0ppz^ z-jf02y(Qi${uXN)-B;_>wzLo0H|?_?iyosMyN*dV-|&7F?^)q9-ml_4D=^;K;{Dcd zv6j(&v&m;`$GbJWCxd>C@tzIu+t7~pY5KORcuxR5cyECB2f%orfcFZ(c+Y_M2f*7Zk2?#vD}cVaVBFWheF(_o9t7?* z0OKA6?m7Tx)00bIEu%5+jNo1f^y4lG?u7v3jtTCC0ORfn?u7v3P73aY0OPI-?u7v3 z4h!yu0OM{8?u7v3&I|5^0OKwU?u7v3jtuUF0OOtx?$G=eYZ={F>(sWi585~FvmT2c zqaM4CNjBebp9uGg;4|(M;a(9i?kM3t$8WKg(S5VYXKTk@65I=cevNUj1ounOj(a7z zUjm#>kCxGWaTf;nV9*!$UvQTN824Xr#|1bW4|C~@_u+Ui4n25Jj`!un^8Os}(Sh+^ z9q-G5w^bf@^l�eRILMpNPAFkjK40+~H$ix%Y>=eZ*OG=F(ToXpB3OxCaUSxI2k^ zkifW8iMy4+xNC`fkifWuiF=U1xSNT4kifXJiF=U1xXX!qkifX(iF=U1xciBFkifVT zihGd2xR;7Mqrb&kM)%b^wJq&~_D%b&$D+rm$F5_N%{Sbi#XVa1jQg{=M+>}G?&RYB z;%~8*(S5VYXKTmZN!){kevNUD689<5j(e22PYIk&kCxGWarYDVKG7HVJ#lvv823GK zrxQ3EpL6Mp`(L;R20geJhWlZ_xG#o#W5B#eCilsJw^bf@(s92WeRILMkB|HAkjFiD z+*t?4J$Kw?2hOG^m%ds?V|*q6_x_Y%!*&e|4jqqbf9q)a!&iy&?U zIwM{LaU;NpL4m*iq*!T`w~W559I*oM`-gnRh#Nrs0Ll?JfcOF6GC4}4yohx`oCA0f z-+)*JV8k~dh5@+D4y*9O-x+?-kOMzx_(KE3KN^10!0?-fKQwS#=@Em4cqi~y!H7RY ztQY7J*M%4@V8nGHb_=*nP8D9InFw199Ae=hAF*+Wa|1@q9OB%75le?SH(UsjITIK;U@zGB45AzlvU zh?7IS9B`Q&rBPnQ_93nhyol#RY#uP;`4F=QTxN$=coE-&I3LJC+z;Y^fDsRbxFBG} z2_gOmxUKYvIYxXhc&lKjp*)I^w#45u1*ugcWAR0q{fb=J0M8@27)CuO=J9{}d^pMx7moOF;4(Q%qr8Y^M;tqN5xbq{or`Z_Rq#=7cMSVXU-+#J*zl`tp1ljd z(Dk-`AY1tK;`@7m_!58nDtRugcWAR0rs` z^26s}F1k@?ZHu;1+pc|5rkjrub@nkL_AzR}N~64G^kwB!FS=wn`_w*^uXx#OXAVoh zvI)yyUhn1X{_}Qi&_QJ?jqHU33?C;4|QKL0jgrBPm$sdcFis+;PpZP7Mr+qF;1bn`U{b@nw0 zvCjn!SZS2EjJ~Yg=M>6U>~j;#eQs*dL1ik9^7S58&G@rM z?9X6?;}X>>wjY37qlv;3a`>A_B|Bk`yPtVm+zs7eGf(Kd#IH$ zF20B2^W}ReV&6j%`yMKS-uF<%zK1GsvA1o+#XhTnS7mBls)OpLI%`|BjoNnY6WD6h)Yx>N_%O?B3` zXdAWd+9zeY`I$3y_A_Tbs+=mkN~74n zk!9#-|3*ga-^hsl8(AOF_%|~4iGL#__HSgw{*5ex-oKF%`!_OT|3*ga-xC|K(kQRW z)Vfp$)lGHQwrCr*?b;`0y7@O&>Wthf_Kmf`#W&VQEHo4GmeH4#`!_PmSM1-~Snl82 z8g&qvN~65~O_1a6-}M5<(ZBZ*m)Ua_UjIfwJMnJ^#Qsfz*uNbRx0T-g1gK{f?0ylX zcYg+A_j71fP8D9IQS3e;8T!_JLWtcbgmawxgm8{?pAhzm`-Bj?Pe_Cu_X#0(pAcgA z2_bf$5MuYAX~0UOyed=cQXNz`)mhu3ZPd1FpOoq5K1I~oeTs{ z_lu*RRj~U3W@w}P?~&L2`dXD!g;!}5yALGmbstD#_krXb=RT0^2ls&_b{|M$_koPi z-+ds7-3OA`eISY52a?$RMH{fvD6h)Yx>N_%O?B3`XdAWd+9zeYxeqOMb{|?|_g!qj zN~64G^kwDl14;Rc-ItQ(?n~LAgUVDI<#nG=+JO6Q61zWV!1$Kga}{3q0i(?zw~G0O z6}a#jBX-{~;uL%ZBxo!I@@Ta{CVS7{Wx&p+#OpMTDA?(@$%&VByb z5AO3%>^}b-U-$VZcAtM@_xUGwpMPTa`6u@Hhz6`Q%BwQ9F4aMGQ=PRf+D2`=_DPv; z9y3CnJ!XX1ef1l#(kO2keObBt{8PSSj~!sS#||{;pfZ(4c|FE~_TX^}#2&v8V4r37 zT!q(to@qbs3r*}k(!}lyP25&`k9(q?Rj|i-WoVbjXAyhcR;zNV@G6aBk8xvN9^=M2 z&STuzc8_r*_82!}k8$JpdW;*f$G8!Dj2p4XxDk7d8?na&HejVuUX`hJsSc`}>a1oI+_2an4m z_IN$wGJCGV>oGpm&0~Lvkz2)Lf`~o#hq$fu9_JhI996*{*UWZ#JTkGzDHE5;slux? zian;AbDYO?bB^73_IDNbmVK zh&?Yyt8%LFDve^#VZu4ibC~3K);xy^vF9)$_8cbc6VG8n>^V$|ek<~^5PJ?2V$Weh z>^V$`J>N?MRvP71nVv6&ysCrhraEg|w2j(!?UORyJO>Wz^&B|Fo_nMLD~<7=;MeI4d zh&^W)vFGd}_MBbBp0kVCb9NDXezOLwG|H%Imqg8tBW)J!co`6?^V4mV556R%I%U@_LRk+JomAqfL7Lu~zM{3a{rZ zqHdnch}d%+5qmBp;^Umg51ylv*mG18dyYzC&rwP2IVy=gMeIhlz)Co{3rx$5 zH`Q6&qHWZ+YoCp5wuo9C(}_8hjvo~xF)t@NIkp3h4a?78>ZUeBLD9&?cA z)n|Ll5i2V)%V!wlc z*zap-z)GXMDpTuH9aJ~fS=*v*)V6D%l+JN7iz~|2IQ{Z~6%nqyYdJcB#=DFF4J!dt zck{7N%5?KP3aPW-QAq4}!!=-~QQk88vU0y;j`9`zU3Dz?yXqQrP?<`jynd%1+wS+` z5&M04#AS9^h1c)cqHcco7O~&SMeKKP5x14z@9yODQU&{6qHLGn2TJVsgc6s@slux? ziv3Piw$blYCH6a2iTzGhV!u-=j@>zyF%p z@5OFaP8D9InFtqmh_j7;hd8m{Ax`Xfh!guA;>3Q3II-U$PV9Gx6Z;+F#D0f3vELz1 z?DwrVV5L!Bm8o^94yv2#tZmUYYTNzp^#*-ZPrrknG=2v?vETj8@lvcb%BwV0u-_rh zx)l3ebD7xhRwiyMJ#wp9 zd@uE^f{|OrVw*{i+$t86OpM$r7OUKn28S6^rX8Ms5|0 z>n28S6^rX8Ms5|0>n28S6^rX8Ms5|0>n28S6^rX8Ms5|0>n28S6^rX8Ms5|0fp5S{ zqr56p>rx$5H`Q6&qHWZ+YoC7`as}4z?(_+$t9DO59d@Mct62UKV&qn_yd=cPtzvmhh?iM<#x9n}B$el>-01T}Z*uY^ z$K=N(-|CI2UehP0wkuW|78%y!yxa{An($D zDyIss(kQk$#qtklY@^L7AI*sz$92(MmYV%-_IW))| z`cLh!3a>p=E$NxEXRReYYxWGbq-W5cwU+d3ww2!2>cR3*@SRfy+uk8q-V@rtt^b4N zSRuB3L9iSv#AR}-@G6aB+d~D*CqntQhsrF^2(j&YqMwug$AW2L|g>=rGLN%4MGEHuii zGPN$%L3LA|wJq94ZM*h~?S=oTZng)HmM4We+a5ex{uE-{%SX#&(twpldCTa_%54u7 zEw2juO|k98qUA|py|x#NmOrII2bHNb%4>VZV0ls~-}ZgMa;y;BelS>$72+~Gtio&g z`C8H%($!kp>TA(9(%aclusjshvkJCzvtW5oNN?v|!E&q++c{XU z94oELslux?itWrWSUwTTw==`c@{ADMnPF!6M~Lmrux5Eli0#a<#qyO9+nHf*c}$4y z%rLk7Cd77T7%lG!v7H%4%ZEa2XNJ-8q!f7RZKCB*A-40?Xn9O%CyMP{u}-7BDpTuH z9aJ~fS=*v*)V6D%s6LAA%sE<~6zXhe&e8Ix5Zjq^v^*y19J`K{MtRHV%gXJ{Fj`&} z)}`3a9;4++VY!_>M$4blsy<4iymm$!EKdr@#m+f{vjHCASFrxdusjsxt%B`4QLwxxq_^)o!E&q++jpN} zIaXSgQ-xP)6x%nl%<_p)zI`LhEYAqBeIv^({|K>tBkN;%Nr>$mS#J4Ci0vC$Zh1_I z?HgHc`AvxJ8(FlxC&c!RELuJkV*5rGEl)~Oe&Mds@~6-??0aIgJSGj;zAe^iCgK&D zT9@jex~b0E7Hy-pUHha=H~YpKEl&z{Ms5|$v68;AM!P>CeYdS+rBPn{7FMUJg6$hw zw7e>;SFwF-i@>ap-7ZEJ)3F*zBAy|$T zV)JtdmSd$=IaPR-MzQ&XWR_2a^35m2?gBf2*nC22mVboUd_r0*FA1^vgyfd5gxGvS za?4{vY(62;@|zHwPe`=9C&cCx5-lGJvH65V%acNEJ|WTar_eUceTmOq8MmB~~Zap-2bfvj6VjXiUa%Z1 z#OBv$_dON&I+e+(!mBij%?C2Gd?KvNd>}K+GeT@WkbNxw2(kG<=9ZU)*nA*!%U42d zK9ITPF(Eb|$Y}XZh|LEwTHX_4^MQ<(4~5u#Afx3;p>3ECWVHM##O5y=Esse9RvP71 znOc|Xpt`Bf+7@l2wq5(AOgHnPjg}{c&zkwrM$4bVXU%*UqvbKl@Z2d@8s$}*D%gA= zqvcg$Unw?U%4m5~_^g>PWwiV$oO8=$Dvk1*&u3wio9}n9JQU=ug3a$ev%DvyH-Gia za;y-WAA7JIE3L|@!mBij&F4R}d?J)@KL0h#GeT@W|1Fk(gxGxkbIVIYY(D?FDQLHq| zt1`7N)j@SrowY66Ms2(HiRz=+Vn(9nN#V0*F(c9Pr|?-bU;Su#Od7D#C~p~kS-JWA zN6V|iep76*1JUxNun#SEAX@$u>Q*L4X_VJu95Tz3!tt^=h0JoS5L^60upBGIW%gW! z*Ll7>x1$nDri}T7X?+NKGJ}a{v zE5sJJ6)eX}t8%LFDve@`amy^92<2OhTOZ3aLToW^x#b@rwivhE@{$l+j9YH`N{B7S zEm|HEVvBK$mfwW<#X%cI%X>m>F>cZFq0mk&#w}W&6k>~Ui5i7KgxF%b zqvbInwwUf{`Avu|raM~R6Jm?$j+PH4hkaU1ceFey#1_*XEq@B_$Kv0kY%!*&e|4jqqbf9MDONuh09PJn3nQ;03MK(st24OnTEw~W55++w<; ze?M zi)oFPGlg<2)-_s=6=I8ljh17D*kWCyDyIss(kQkZCVecQ2<2N2lic!*5L*tD-13hQTMm=l@{$l+4wGp4N{B6o zNyJ|~Qz*mlfI$l$V90o(X;4*uz!fQDkqUBgA>}09mM$556Y&jpIr=Z7s6z@b}yhrh_1TK?Pg;!}5W6r_60{NJWFs}e(j>5bGjJXT*3NYq0 z%qzf{>oBhXV-Cc;0*tv4^9nHLOw235m`gFQ0Ar5DyaJ4Q9&_-dSZS13WolijgX*R_ zYg@F9+IH=eGTpEq!MX%GV?Ba(2{6_;m=7k!N~64G^kwCki!iT1zGBQvn4eINc?t6q zaG4yXQC`fYm`A~j`4e*?Fy>Fpk-%kkScMnQ6P_!`!E=V^4H(a#t`eH1YEcGyP&W6y_u6fpLJ*hc|lkBEH~F!qkvM*(9`iG36>_O;k^PKuRAc~z#? zr8=l?sa1*oOmSPmlf2q*!T`w~W559D6V9qaa@~_F>qM zp&a`#?8ku1^ zp;%u6x0N1eS~yDrZxxL5Je-$-9_M5@^8&^>8P39h%j8tyRT{-OQ^dI;BhQK)E#JM3b&OUK&2#hmPoErk;tQ6;lz&Jz2xgjvl zadE~vDOMWgRhe3s>Y%!*&e|4jqqbf9q)a!QH{;wHI^(<<=gz=5!^U~vq*!T`w~W55 z9A}L@H$(-3aqfuoM-=1S5$BJXb5ii)d=zJ$z&Ibp87Od>9aiDRc?r%< zD96rGQm$H@ui%^oG2H*-%h|=1>^e_z7>HU--Ymv2N>Ul@a+eLVx>{uGWxP|d|ShJGRRkq?`-(qhH`vov-~LyI;c#gQC@r-#CJi+ z!S_IX+XKe;Kz#E9F0;cby!bwV?*x#8?*{mO0F3Vm_^tqq?+o~U0Nhr3_$S z0t{aj_=Nz&hXsBi!0>H>UkEUKUf>r33||=dg#g1x27V#H@Y8`0&7@dqlvibHU8;lX zraEg|w2j(!?UORy;7n!$%4J9Ft-BE(? z>iAxc^0v~$M-RSn;H`q;p9o(-(8KQ!K78agzdyNK?Vrl5!mBij;Uft@NYn-2N%%nm z!>1CymB8?|gdZd@d@$h$2@Ky%_(1~0XA^#q!0_dSA0#k*JmCik4Bt=qK?1`k6n>Dv z@Jofy=%iR_lvibHU8;lXraEg|w2j(!?UORy;6DpLTIdY_S@_WcziK|Y@L!x1D~1TXwO;kyY8e^2;y0+-oy6<+v% z!4C{_;1>q}FktwL!EX$heq`oP2HaM9_@u+99K2O9{PE%M4tn^x!)F~Be(vyP2QHIS zg;!}5BPIZT|B#PZ0r>p`BZdHe|Gr{5gM7rsA{D>14b+z;@p4{V~035V8q@b z&J7qbd5CiZMywv<+<+0ohd4K2#P%W14Hz+hh;su*+#zBDC&fymyed=cQXNz`)mhu3 zZPd0SE->{;nQn-WM4TjaMtmgVB!LlgiTJchvC=4S8GTtfV&f3!2KkB+Cx>`Blp{_K z@p8ara+F4S5!;8jKJX%*53zZ`i04Dh9&ni*R^df_58`|v2XQ}${{cok5aNP>5hsNB zAKxO*9f+MaQ7%}3A z>jp;bIO4j25mS!1ZeYZkBd!}5G3bcv21aZ;;<|wmvyQlKV8pT`t{WIJ?uhFKMw~rj z;3vgOqr56p>rx$5H`Q6&qHWZ+YoCxe}MM*KQr)Pc+FunI5YSrOL? zIf!$$94o|#e?=TD$`Kcf_*me!(j)%_@@0Ux3PyerAU6kanVc%T zN~0J#PLRh0@{#)lc}#$j69supfRQT&c}#$jLj`$EfRS5egA2x74&>#0zMP)eaD$OD1=4!~`t_je0*tAhQ#N_u}E68n3yRXJ67l}548DU|PX3bD^Av{j!| zh<#3BpZJ_oL;v`k!spB96k?xK0%&|rA@(_i*yrB{tTf82GPN$%L3LA|wJq94ZM*hK znQp!&q0YW0A@;eT0V|F2meH4$`v?v>AWai2WHXaPe#sx0T-4)zq^J_I(8Def>}D`+`>GRN++`#lDB4eBVRy`SLv! zvG1XXeGhd9#>Mwge7<}SMeKVhV&6jr(EA>W*!NHcF7~#KxY%bk@TyF$OLb7)RA+6A zwo%)zed2rJ2HkuQ&T`*_6Z_t$0V|F2meH4$`yPt&75iR{<-Qkd&_QJ?jq>`QF=D)Y z-$(5GLEA(Ai1hw_huFXS zv?`|xuhJ;?Z)7?8*}sty`!_OT|3)?*H2#f@ed6E9i2WNGv40~Ap!aWN#Qu$p*uRkx z`}f2KtTf82GPN$%L3LA|wJq94ZM*hKnQs1#l{zE03huE$d;Qy1BNm#8c#H46jr1ku z{*8?Eiv3#~%l%tht1^{FdHtIp$KAi{MYPMm_Ys%ba}{3yMnF69ZwJKwO@Y|I9T2yb z-u(oqXBF&z5u|s224eSfXjM)XUZqj&J|Q{!)_p>V-6w=|ocn}uj&q+7_KEw15W7!E zfE@P;A$Fe-V)qFlcApSp_n&FNN~63gQ|nS4R5#UG+oEmMwrii1>E=E~)Y*NCh~1Z? z0V|F2meH4$yH5z^D|X)!mb-6BgAOWFX_VJ}U}yvG#}YB7?%zUOX3tf4{hK&##=n&l z`!{rA|5i@iR(kh^qn=f;`vK-?qxJuT4MKIY`{vRyk+!d&bO?ypYle(bHvslux?irwd*b-B+! z=Q#KI=N#ug|Lh0%`6qUte~z#F{1dy+Ke7A#6T8npvHScJdwfI#RvP71nOc|Xpt`Bf z+7@l2wq5(AOgE1iq0SyNLhQc!4OnTEw~W55+psu4ANPeOb{}bC_k|{IE4{}(QO_#ahY7LgFd_DQFAZ2}lvibXz7+DR4yv2#tZmUYYTLC>%5?J_IIP!m;1GN6 zkp`?Z%3DTXR_-}WC||MXLSeb*LTS)JWh#yGdd?O;cb<2Jw&(d+h|BD`3h%fghXZx< z+z!N^^MTlNI~4l2k=}DRQO_#ab5*guo^Oi0o`M&Nu4pIp2zQ6?xG{W6wZkgBp0kL$c`hSj5x14za}`q0D%f)~a^CU$isbdYi>=D3!mBij zJx67RXU%g|5_^tHV$V^@e()TX#Ga#)*mG18dyYzC&rwP2IVy=gMrx$5H`Q6&qHWZ+YoC6&$rpC9aiD>9DUTybN3N@PCsJL-ACM3de75KJ*!~PMa=ekK4G@k z^9;8trwXsqDE6Gpe7-yeIhlz) ze{};^8s$})T9@jex~b0E7Hy-pUHha=H_z!!ojs>FvFB25z)GXMW%Om`o|BpK6?<-H zmV0jJ1|3wU(kQRzpr#FY9%Y%!*&e|4jqqbf9q)a!z!-6{d9TvoXcR&MH z8s#mcFDv&u2q<5%-(|pZ-UgJp86@G6aBzjKH6`kgy$uiv>t z?04=E`<*+)e&-Ic-?>BVckU4Tojb&S=MJ&oxkK#t6E$F^QC^j)b*T=jo9e7>(Kc$^ zwNJ`)^E;cUv)|c7?04lfV5L#sGWxP|zjKH375m*iEcd&68gx*ZN~64f#}Mto?+GII z`-5ncWp-GF*Y6ymZhjXDvENZb?01n6x0T-S9pn3<3if-}*haq}jo9x^V|&ZwRN++` z#eT;e>+(D1*j~T4j@a**BlbJyi2aT^V!vaK*zcGl_B-Z?{f;?ezhjQr@8fI0N~63g zQ|nS4R5#UG+oElpsO`nQd+d`k-TaP1>g;zE68qh74OnTEw~W55-0zs9e8qlO9n1Z$ zx&|ForqU>{->Jv8`@ML?eqSDOnH^T)^*gqxo8P@f?00ez``uf_ZKe17I{Ca*!G4!0 z+vWFx68k-&#AR}-@G6aBzf+ZM^gC6F{Z3V4zf+ai?^GrBJ5`DOPE}&RQg;!}N!o?lpY@^>HPV9Gx6Z;+F#D0f3vELz1?01M0 z`yJxMeup@*-yu%ycZd`Fed`TaX_QxGYF(;>>ZUqtTeOYZcE5YQK_AuA@1Q4*-$768 zcYkxd6f2GLDoqvacZjnt#eNq#%l$6$R`pRD<@Gz$$?Nx?vn_rfdaHI=h1c&;rhLC! znb_}KCic6PiQ7t#+$t8|OFgS#AMs5|0>t-8~ zTgBqKiIH2y;<|~ETgBqKiIH2y;<|~ETgBqKiIH2y;<|~ETgBqKiIH2y;<|~ETgBqK ziIH2y;<|~ETg77F8?e$SugcWAR0q{fb=J0M8@27)CuO=Jw~FNjpw7sxVtD~LM#!yV z@z@PmX_U8&zN{R%RV=QX^(sbg6^jpNIdZF5d^mBL9HmiS3r+?i(Gtb zEHEy={trd2F#A<}_J$&t(H$ptj>G3G^2FjN{tsUNJu&#ek8;R^Twv6*%+e=b2IS@J zAEzgFIc$r|C-!=YjUDSH;6;{VXo ze@_fPtB-m@p4CT;dd~0Dk2zAjJO{7S6T6&3wB&Ru!)-(Ut#*xF-eD2ycpS$M!^Ot;oHlMp<-fTX1&FAiyeC{54a01pX z0neYWXNY~BLu|kL+16u+4!?FZ>YCi^u^VrAvFk6n?%L_@Wtb-r>%p}C#5yspOMU&w z{`_~=&&w=5V|~1uWB2pyeVSueUx!CLoBz%}sQKLe{Cn8uJCinvGY!5!?I+GU(%kef z&m5ZX%%A_fsQJ!pzBB#ork$;EaF)gA(a*Suo6lYIx%0II?V;*fUvs|u`Q|&U=ZZhY z9K zZJ=obO&e(1z~r!j$ZjqAwuzhl(6oW34g4?LK#=!g6Bp0IWbcO)&pItz_Pe31=cEbk zvrpb0PJF{T^S8|Lco7G*)C?Qt3y(dR{q`01=&h$pxF!e$!3X8z)CyML*-;Mw=)bga7t&^FuJ7)8c!P;v2ek%f2|dh~K&W z-OI9Fw<_*`pJ~FU*}kK9i0GFIo#qeEzqT&%hh0_aAnb zEhgPe=RE0bZOKzxOt(C>QQNM#t#aIMssEY7Cgg7{`g`K9w&@VJU3*L7i~qDp{Npu! ziOckFs~n@pyE@gINxebp4N`A?y#5{DVvO)_^ORUo6pyO zgAKIJH^t&Ous-2CRsAQ`uhQ(I?&qxj&l*djF(w*&qA@902Z?`OJqFzAQ%p4GSkAL9 zpV;dqc72FlPh!`f*kSz&H$vC@c%L4Ad-|0A{<{@th#$#zdS5#cH^;6XgVP*4vkiZaXm8Eu zuE@#IeC~>OnwbaQ;SukU<~y@F-!$iTzAFTi9{KHlEqRgk? zxGrB|#^Sp`ZR1PxBQGlaF_cE@T64+g@=slE2Gtoaw`nPL$ zY`yJe`l}q%Crdh8y;-W)^vRMwN~699)~+nI%i5cz_A1T!E6kaHz0z>DrCqyKEU#E$ zYgV46a@9w%j-9oo-bNdXdfThewDtK`nTnzNLl16Z-?!?yg}KM~y;9omqpfT&zW>-h zpBO*!|3a64eRldw*LCC~=Ua|B{5dRE!S^5iR-HcKlfHQ)Uu?x)0;Ftq$L#U0tv4cG z_|MD6BiCAv`0~{^i1%JJ7x7=t-6?MWyZ88g;ruWpp8v-SiSK%7SnP1l!o-t9rrRfV zSZT~Y*{G)uBtC27<+Hvo9YTEUec#renzhJxt@KkZb$RyZulFU*kSQ+CzHdK-xc3w1 zWL>8$d@q&8^v_bC>^A%3*}d=lp7hf`dPnwkx5D>QX`Xobnry~%3;)JWa}LTze^BVA z`Y63(8@u|MnDt>ueQ13fQr}viht%gb79ov=jZsKrWMdc7*g@uO6OQFrYq`>^9F?#2 zsy^11mejY_=XvUL8;d-Rh4p#ecTwrBPx90!)>nDzE9-~4?J2gg$kTXPpXaI1Z7lLM z7D}V_+L-2POl_?5G}f^1;!l-xxF$`rubMW{w1K7#{BPJm^>Kdhp|e}QTysQ3zx4fP z&HU2^4GqE=?sX#Zg(HW@B^H^97;8NHcE)w=K`)GmCybwlcfftL*N8an z*kg%D+;V7qrhRB@ z^ZK{Hkt;nie((2-zU{Dhzm}G(3#>F+uJp(MevR(QR=0X)hYWaw>kkTp=6i|w?YDLf zE4{Z+K>2y|t`&xSzdZ57?Uo6T4%(P_y5(mJw~yP2_|+NS%WnIrSkq0o_Nr`?I}T#` zNz3h!^*GSinCHJzTlA|UM(5^EC-u2wngYK%{<@ZZ?$9}`Q6YtovN}T1aDTvQGW2-pD+PAVTuRgnX zylRT|h!=YQ;JEd%-}Bzu7hW9^7wI)~jy8UO$nf~`-4_s_xxnaNxn=j*bGpJ#r+#O;IOw(ASbppm&*i5-Tll`V#J4!3Sq5BW+vYM;Z4FJ-Ct*0zP)mn&}+l7 z#B-dzZ`fqFwTZ8v;gE3uJNLJsjWgVjv09~W8)_%EPvrB2=K$YrK@XoP_}u|xk7z%P zpT2wb{IA#(;=3@)u}5_OBK$YvJ2C+LYm&d7$u_-;cgzMC+;_Q@PF zoikp>a?pyNb$`P`_CMM?Y*csl$&yD53+=-g;@KA-9JU`<*u&CYb_mng7KqS!fvMIF zyKPbQ|0X*w8AffiIm;iOa)!`ppWMI|~E?B&Hrcc=ZkZiGqigDk%)7YBe7NN<7 zHy4>v>WZR66y2ie9HlMP3p)GQv0XlP#6EVU!#C2jr}wdAxsP3vg|Q>{u_N}eBewVN zWvBzS!d`?PW5;s)RoxHKpf;wqmuwPu6iIn5^ts5H$mXS9v?=K`(X)d-f&%EXA|?+1<2+{X`~nw0 z3oQKrIjMgjAAix_<~UkEz!qe@tdEO#%P%pGRu}IXK%F;CzZS>ny9Evjhn##T@dEAk z3Rj&m1IO#jPc{o3H|s^*nr>Xo&>_fVF9eBuMOoqdfk*FKN*+4qLx{d4z+eOq4ZRM6Zs`0JKM z*D84LxOeq@m30mv@1cW_%FkN6IMbbbi_!V`e#JZOn6)0w?|OMV(tNY|H+lSNL*n&o zbHpRs7w^L%amje=)eEwGx;NL3CvNs7+q>WO+sC=ix}5m5xAu+4{Rs?cO~zU*h`0H~iJ_7tOoBID+Mm5AM)%&q4+M z{>?wt)@XMK%U|AZo$TpLh7g~*^!eH8n-}L>BhGs=n{B_XSw7Vw?L*wOAMv<1<_?c+ z(TDiW9hMB;K3|Nu$B+<)y)`rOly__r`iIxquHTK>B}{m44DrY*28Vvjtw8+jlZS-; zzPOp|)4%`y(D3}0zpdMnVtdb%-sdc0pRHM!<2eJ7l^z!dq3Zx-JU6o1+OkNFlo_M;vLE%sV|`g_GUoufv~9tR$?5z8+d z+ABVGT5sZS&)zV$JTwRKip%X1x1I7$_Sefd4ULa)dj|0WN_%O?B3`SljLU0^(;T|Mvxpo2l=WFqUatF(0J0h^bNcOT-+F^$v8y z+90h(d`@RM=K5rRm{ZamjQ4vHKf`v_*CI}zL8i+IBA?jnCAQx|A7a;&*!3s2xS4LK z4{}gH^ZI24j>2uf|ySi<#-0M z4&Oh#w#e~Z+l>8q*Kp})FA}eJ;6~y0(`KiAZhQZ-VY^idUyfyOoh7__aDSGseZe!? z&^-qdpS#nM*|vKfKs?~HYil1(SL_=Nw$m}FXAG1X-{#H54i7L#tK zb4)syeX~#+&sil-d0BDRzexMl;ulkOV|nKjSC0=bSLE-?Mz0a4cz02j-@b3( zc;IKn89}da`^FR2FYq3H*Nhi^vM_0`-fGRb_0t9ZdYv`nOz#&sPPJy-FDvLTAK5o< z_@{;yZ_h!i#m|rKN}1QrylVVj9zSP+d*0kV-gP~>iWvQ z!Cc|rV>TGNL_A^MLZ3%Z=@E~etHyda>GIpS*kvmdKlGcP@#wc!B);qRrQ>|7tU!GE zlgq|Fy^H5=sx5lQJFe@+aHcn}K-K`!)|RY&bpf z84C>v{qLEMc)v9UgfS-+c(dAoaO;@`K4SU-;k!2r{Q0=e!{&nv-lcxKdDwKtLgu5R zHVcdPEb7|vxJ|>4H_Swt^Dns-X0zFIdNG}ZjX ztM0O9xZuHsiLW|v)iD3)!v2q_^$8&~l4}X=YfH_?2M`hBKyHhxmgF<_iz4u^#baBj*VVy|_N{g>TOl zR_?d~@m_zOGhFa=fe#uwXPCRwhAdzA4|9fdr!R1aIpzv;Us2GEZZ~(B?uUM)xn%u$ z!ah?Mc+-#P4R=0N)b+^o^M}1RUY9f-e$y!|bjjMp%Wk@Gc;KEw&wdwKuDR*gVEN5Q zcMogdSlDD(r$-pGWnpipPQ7$k?Zcw&-M?Bk^q94jq<9@OIKMiOtI2BtV8iCYv)7gwsa}&AlT52CPjywHL0@Qlnz-nZWp#jj1Z zMc8oLX<7c_-**gKJzT_u+V{I4-|y^hUqE8){(U<9C-xEXn z=4js&L;4npGkWp44IlP6!2Esry|PZDyxJ#}^@u+k1Iv48&bw~Htwlx zzLy6Q|9-}!vsY$0fOw7_AFC}ou80X)?6cu5A0A$e-QC~poL_L%L8NKFY%!*&f1nT`!PTBOnl}u@tF_eGatlfK8VkJ5TE%VKJ!6* z=7adm*RlD`*J;dWzRqht^L3f#GheUEeCF#qn9qD&H}jdV>#S`lvp4ILDB~Mtd~+G! zT*kLW#ohjLbzU3ax=b72dR;cYbscPc>$=(a)^*ml=y&SB z{P<~p>)AWd##$D?D8Ik!5aKm|m^JUWWf3=V&2C@y+4A+mR&W2)hS}QJ988++7i`IP zeyjNAZnj$2U*&7L(yJVmul1@vs;7RJAO7mpaljeHGji^+i^sV?%Bb7!)2tIO9#OoScV9#t`wfp5t~5Kb#%QQ~EmwM#qw=+0)kpPIKLjfeqJI$m zgXkYb{~-DY(ZBw@sC?7EUT*r==}rH-9Miup-}JB7Yx>vqQ9W&Z>pmDZE}7U*Ciatw z{frm;$;Ezhv7h?8PUY)6(Cnv9Z}wA{WA;;*Z}wBK*X*aRkLvmVan2HoIUWC2JHJc0 z5j2KH{j@daMPp$+-hno3mDOWsJXVF}h#f%;3A8D4iKR6cb2l;eN6VF7<*0nESM^an zRex>QBy}NPhPrvYOlk{!P>J1dpV;GNi2e7(9xuaZ6Y}88i}qsdZ0=^fuGXvNO0RNM zzSgVySOs-GRe$v*rWzIPprFOS)$FE8-|VZV4gA9fEH_In<+mBM*&5lxs~p1j!xgVw zm@Twyu~yk;)|a!3uGp33Pc1inIO&%6`vD53nzE8+Ey_)Ztr5e|N$#{3;+e((R+^t5+lJvP(w z()5u$HnoyGHuZ9)zkP}mJD)RZ$3^h|I_#B?Ytx^5*UERVd}#Q3%+TzCz1QpW!pR4Q zX~*7{{o#y@`uu(5-eJpAKF{u7{iQw&&$>hCJ#MzJqP&!wyE5RSfn-uTX1bJhOx=k>xK_w|Vvzqf8}{UJTVG^-4V z2OoK8t;5)9!|C_!70+AX{MzH^-Ig6Q^MP^ahpw%?GS6Pw`;Q;j`Nm`RTNF01>2*hR z?tRPC#1CFKsB`ai=dk-z4h!2Zxk=|84_ujeqtQJ(-@W11#5>M0ZRfwex<7G;K6fnI zvG+*gy*{ZeI^wsZi1D=BdMTA(n#zs-(nN1^E=zJu{$)wN)q7d0*Yvq8>0^3cmh?3J zFH8Dg*lj=<-t#!Nx5I!e+-w;QtF55CF% zY}tOL@ZD5hGuZ7dYt0o_xNGVR{ki8tA7!sB_!Q}vxN=FeJQv+p!t! z_M08|46`3_R0ey#?!1p{=k5D+AB^2^j^8fKaO}YuY<|P1Hw-U)I55Llyz%1lVgHUB zu&()QbA%mM>&ChsefPcW_DiS8pxZ|4U!85Z;$5ukw7h3{^oWy5|Mh+|htMe#gdX9Pzg)(;UVm)*FyZcztZUiXUd#ra)Sq=t_q$87-8Y?& zbv-eg`M|&RAnDgRX^QamE0>af<=G$0p8We^q`%?rv$Eya%SeCZfDOWsjQYP@2(ZP9WqluA5NIQ7V_~^2lU%%%jJe#iVk`i~!dC!6NMM@Zju-<>5xuy>B;|>A#v+Ff~&0f6fMb`C9|0}auueq9at#jY7tlL6|v93qn_$WK= zo7qX9y>n-F|I?q6zWsS;WxH&alm6kwcF0!!{RyPM4mu+nH=;wpv#|4vduH>l^EBxf8vonusR8Gc z{?g6&uHAV4Gt_O+UQcDS&A2Od8~f-Z*$uC4OWnF(cvp7GJ^iWM8K2#ljs9|V>h}F? z7iEuZW%;+P-=6vC@NAEpXJB3H9KC)v`=KwfuC-p9Gs}0mlyzO*dwABROE1ztaCE=y ztQBS@{VR7aoISeO+obO>_M_Tr5052%&wCcBZFTlL)NR!nj>sN(dnk1q^ur<9himLb z-L_kA@9diGwx@1uow!Z*_j5O*Zjb%6dUojvE3mH5=j@c-{qP*DYr8$Zt^Mwy_gU9X z<8Q5f{pr=LtHYpn*@zYUkbc6UkJkp@KR4-Tn)|Za;9;MT{+#&+*X|y89qH#?aCDzx z-+xNoK3Q~JZSX$BsN3jk#@2?OI+VKIyWd5%v)9^@gX@<{P*DDWw)93j0Z(v<`5C7rQf*yFU?+be1d%rB`fhT

t_ghPPzuCJt%DXqpyEn?aH_E#=%DXq0cW*B5-aNf~ZC;2n zFXS>WbC%7gQRdSq^Jy;g zX`bd&n?qaD9BT7^O!L0Y^-<>fD06+3xjxEVA7!q$yqfj7K2LMKtwW-$L!zuha#@Gu zX&qu~kCwFdu=P@u^-@ghC0ip!StCVRBSl#wMOh=|vPR0&8p+mgQPyu!)^EA2-}1D6 zvvpcaTBp6Vz_57UO%HJoGI+J2aoe5m;ojtv?{(y<*45C#s2 z9O*w?@ALfVXJ#h-v4`A{-?_q5T#F8U{EL{(W30pqU_P4?9rm^(W30pa@nKhvPa8xk2c!}YmUty?1X$evEz%=cKgG*U)uTP zVR7X5Cw0BziFb+LU+~DTwapggof9`qw_Dez=Iuv3&+4moooU*AiD$d$k&oAB7Uvsd^4sqK`Xy3m9KNj(Oo8-5-k7xVe#G0_jb8pmpv9FzV@$kbshJ})WpwBxU1{UEwd(?>-rt4&{Ez)w zOW*cG;{L0RsZBWb-2BZ;wu{@YbX@JtN59J7y{d1V_4VJ?7M^R7_}Tegp|l%redI<6{?|miK=6;6Af`HZ;yO$5Q!~Tg=>N zj}?Z+g+IQwrOS6Gtvq155mDpQWpCIbd&U-x`__1HjT6`Sag8h2cyokqpr>wm??H9L!lCq6l4So)F=C};2&i-Z%p&yu14Wgiz0{eHu6Zr>F% z$a(mz9mAP_T?hM}{LdE*3i}S(4Evz`t4$6F-8bGEd!_uyI~NL%EZ&Q9WRDhqTC!g_ z>Wf_{NA`5N?E7-r59S-Lxkxt8HAhkBSLVGcyXlr0GUz@8ZBdeZwcKU(C9OyuNv8fBiV>JV&3M!t@W{Mx8epwR`x@y^%W4aL$}zvM$;8#Z6!C6*len8tdA3#=c>#{lBEnH*LRBc>96hU>%!}nSDSQ{pD0x z-{#wY-XW~`(4CYcd%8IN$R)$r0bf&&>;ZGx8|Jcq%*W0jnw&^>;Imee#J|yOZJ2D^esDunf9MCz&7qbcgb+jg7adHozH*9@?l2H zjR>9J9$pIzt5(kIj^4pRYD8<;Wf|u6WvK*;Y$0MLDu(%w;c`%N{eo zrS}!JTi2L}Iu97xD?9(hOQ`c>3mlcb@zICW`Nlaf$u9X~7S<*E$9T|dk7jeNyAtaf zyz^_>j$f`zoyTqQQ8wzr&8hRiDZa|yJ9-=H{M47Dvh8hOjke3)Fm}82`mFPQt5S~a zC3D$h=Cb$9CmcMmcFrzcsPiHxe^onU_i@yDwIRK-Av?4SdU{dWmt<~M)JPMv8Gb^dyrC9)n{ElfGGXN(Ko z_PeapXZwN4HVu{r9|o z%#pKAL!CFj;)^lceOA@+;-+#))sJtlN+5uMYX6gsE9Ds)bJSoHIF>E{;d=N9Sb7U}1-KSe+1 z($Bf{b1wayr+zlu$i+6&-V?Twi*2O6Dr_U|VPP9-Zwq^F5qoYCd(Oq4bFt^NZ-qVQ zV$ZqQb1wFrCwsPMFqdaA?Md+r=JE`tJuIHVw711GnD)GQZ?wpJBbWC^F7J(8-WzE@ zi}yw@?~PpE8@aqU^7P)YcU>;;y0lltyDpb^UE15?U6=N}c-N)9Fy7BC@_x?c{hZ7D zIhXfy+UMf^9OeBS<^3Gx{T$Q#+2)j7=9ILD#hemlPDy)S%qeLvj5#IkkueYEG7si5 z59Trt<}wea{V(RhDDz;Hc`(X67}Gpxb9a=vJMC>TcSo7K(_R>JciJOk?oNAWtT%F5 zZ{)Jx$Ys3|WxbL1#aM4xy5RbHBg%Rs%6cQF^@gpHqO6h9o)>GRC~Ks&N5&c{?VYif z%hOs;_SdvCDw<+84evaU<}WvuI>tm~qz>!PgdVp`YPS~SX9H0_147LBqNO?&6u z*2#HVC)>I-?XR&eP5bWL*3Y@DpQEgwqpY9PJ{s%iDC_4a>*pxz=a|;d&;4|39`o6` zK7VWH4)KXwx8(Y~%luvA4JVD{I{&;kf1A(vr&YQ4k$rUBWr|JX%m-Y-HUEplZp+u% z=@EQ$jIsyMclvXO_}E5s7Hj^0?9=mIPUsrP?7jl!%U(Wze^?f;`Jg}c-TWSm^G(~| zh2m!uH~XP!13#|~6wj9XQ}H=-Kdbc2{fxN^@lCm&Z<)RvlfxgZxFe(R!JFK^c6c}0 zy$Z}z?>=}L+UUM{#O|}l{&ZhHV)yY&{S4niV)qFocKwNqJ2D#Ih0U=me2UuYC;6Wm zyTV_x{@lTLv|-%MgzEO7cB1y9cBS^Fc8E5b-CPEn^z!uF)$_W$oCq52L$8TgN~63+P?xE7sSc`}w~_j5TmDHKC)+bG-Xd#9Mc=Vq&<8T??@d|J7roJ! z=08;*7xo!wroQ_A%e>D2+OeDZ>b1H|?ytr>z$~-h0fQDiz>rbYVX-%WN;$S;}idpNX7IWWw616N-Ha<2`tDx^D-0G>1h0PuHF|u=)`q=$bd$2yhp9VWY z;p_{4MjhIRuGs=pJw!Zx?fgv3AD;3AmXF%#nTcpl*#0}V<$}e(DW%`K(_-w0#TNRh zly~YY`&rwzvAdVw%d{@#-DJnBNweD)<1?*Sd6(|;8fms4HzX_LUGj+UNi%HJpK4{i zLerx4N_kD{$^~aaqrAD4PsA%aD9uE?(iW{NS6=CpTy)NrSNgV;S8Sk^S8OBKdX-n} zQhKG)a@e9h1AIR>@vosDinBwE)#P5QR z3tPiFLE2kCAN4&~dM+p0`^eq|zbB2o$0r&W9j{5o(dNARo{QM`L(~m&WN(6cS&lj} zSAf_4V9!MiJ=G3V8_`}V$DS+Ea~>$faL<+GPqZhp-?JQb>K;n>R(9^&wUEO-R}PFi zp%bvz8G#{3`VD(7mZPm`GidA&_FTlMQ^tk;l-gF1PBfOGD8s)$M|rXh#?VrqVhpR4 z|HB?k8S;Ajs$jOm>D!2lcDuhmd8^}gsV@9%D~{-OjIXq}61Md|*7m{A8;P+W@;w*# z8NTPT-|@VWG_vRNGc%sc1=({2>~H*BE@0nd=Z&MiK9pl$#B$%ukly!Pl;e9J%J)4H z&+2^7MSXk^MLm6QRo@RmzMnTnVCW+BY0m{YIBz5k_Cr!H>i{qMK=e#?K!2P!jsZ=o z13yvjdoHw#btE~c0~q@)-*cf|(1$W)&qW!KrLuwjypiS2vHSIn9iG=T|21*(PH*-@ zvmbsw8%T5U1gtGNpJF{IYp~qsOH?`08c)}L_B--oJs@kaiO%!w?s7X9#h+j9JpaZU zUYzWEgq`kQhCW$X&*_>|`T>2D`e&lGtE`!M2FC6w)|RCAwIy*OyBM$H%&-wZ^k8!w z(TA{2UBg>ZL^*8P`n100hpnR=w*SkHBWf+i52%TYUTF41vmgFjZD6XeMuaWDIcYpb z_<`kzhaFCulV=4xo;4(FHu!wv_`99L?wh|){Pf4`hrjMV58wSKecm$+`Kh>b_vG#! z!*(Zb!t&?edM0~+tAWIyUV2Qn!}I$SAN$agwa+d+lvwN4a-~-}DqrhWeN<1?U)zOo zwE4)+vWoX>nj5jUNOPmFEvP5v!nCHq&onn0dwp&MUs{_$URtvhYm4H2ig$V{$Gbk! zo1FT&6y}B`-+snaFV-)p&;HWCAn9rH>T4NmSG08n&y&2IbBNW0wGXk&fvn_5NbL0z z+pnMxvFl0f`V$v(QnB9k_9lAt1F^|L{}6k>5qp0U+wTMFv%fs+N_wK7P#?-MUbe2_ zcs0ka=qtAk_FHr8igQ`FL)cTh=5yD4?)=?Dd+>K4=db^@cc#s)Eosi31lQ-{x!)L- z9kp69M~{2?pgLerWmS!_p5gL;T#9n}nH%b|ijtq2Gtcj+?-~ zUGuF2!Ww1)qv`>p!`Fxc=p1_-=oAyWPTG^Swa4 z$Tu5>TVI_mg61!4^$MHcS@_&syu_^GzQy~qeDJ2vW*e_o++*>>vqxrcY*XB0vEixL z)s~sIxDUW^OTtEzCmQ3;6R*jPNv72mQ(dM*OgfluG3jPH$E35hC8oAm8)IstwLPY` zTc5<#C)QUn^_BHuOnqp58&ls}pXaI1Z7lLM7P>BKj!|I`|JTOo{ek1N?Wf(F_IdB^ zQ-uNR{f>C|zKeyw&aevcF88h#+RwQVarge)hgom>iZ*|E&%vR?Tce44JvS^Yy!JxG z?Yg*4~)fYyA*YKUn|7)IZj5G4-4EXH5NR{Tx$2 zTmR>&|C?h`*uZ~&EShIXcrMd()x=GEXxc#22AVd|w1K7#{HJW7UAv3NZV<1SW3GrX zsDg1WZs*jbuY&bVyCRP1>>c&|D{Q~-Bl`SHY;6qE-hY7)V>{hGo0uKZ?31QFG;N@1 z15F!f+Cb9=et8=xU#Bg%&+@U~Da&x3GRK+o#}`MgOFYB+Kjb|R-j;Zhv%&f~q0%U? z%GCAY8T0gx8-CJ@GVfbsuGsyU4TyKm-_IWlI}zWr^QHMp=MN?xxZ`j08&)fF1?aj_ zWoo(7s~nZD^{PJlO~-sE^5kn_z7u)!!7$&6n0zzLcOoXA4fCCd$(O@?Ct~vPFyD!o zd_T;0A|{^@U88EfTCVgeN9Ak1s*mca`fIy%4Q&0ErGB=4%ToVazh!A$tlvT!FYC9E z#!=VCDpSjqUgfBKtylHYvuMR;ds(tiv%Qe))@&~%dsZD3D~<9dnTRdG-)2m~uP>%R z$1Y*SiD>*t5sT8BaU~jWqH!o1pMqEv$ny9XV#tuV9kVh!RsHC`_iQ;7>t|#T& zN%1ccydM8T?C~$eo^ycM>m)wy+ef-uyHYvgl@fi*$q-Pd#PuLY1ac`bo=EhG64w(o zE@|a$=0Yw7lT*)+l;V|AKUkgh{)y6WQTh}5KnC@Z{!jUlQY?|l>K!mYO1maYyprYd zL9Qa|q~ka_t?R@04s?bL(Lb~wJ!Kj@l>Z{{5Ik$iUVe$(RyKBZTk$qVJQF_FvFO)- z;)LOJT}|K-dn=S;nBu}QRxx+Xbp8jjF!PX~u zXPTT}F3+Lu3$WHhoyc>De1OEzOKcczWcj~qlaixyqPAeRYmiS2`Cdnx^BijYpw~w|Cs!LM$t&`UwDEr-KaA&2p*_H+ z+*W?pe3eCR4p_-A65q1E)`!Ry#xcSgP{zg9fX%tUO!ePdKmT8t3!3AIH_oqb z91)*x&m-UMlWYBKF|uhM$9$3Yef1c4e>d>`fOp2f`97f>#HY)9X0q&CEjIl>v2U%f zpNrfA#rqR+>oSgLFUJ&fHTKN3&cZ&4v4_TAl=~i<7_>6KPqglmeGtmiI8L;$H*oqW2rd7&P|hU*^W_I%by3WgM};BQNF=ku%Y}BlUtd=`)eNiT>f*nKw`4IMI4W z`T;T`6h@uWZ>X2$s1t1ljs0mQH|AlGWos4YG9~usj`-(nm#m+EiFUE=HeTH(w;kGe zrG4u!W{1ctmDZWSVw02Q-O|hzR)5y`T-b9q(KD{kzP=M=T(GtzZ*kU#r|utX%_c^F z;7_wpn*H#z*#Mt6@6RS?M-=a%W}h_sp=kq68)(|V|7jbD#rWXgpKVTT%4DZD`?IjE z|LJ~ct_h20q1g}3ewZ9K(41?Ub4}9*CYudF@c;Du-L$RAW?N0WV%IjGuc8~8{m|@( zrVTW0plJjDX&aav`?RJ^j_UvEv*6|!HOHuF15F!f+Cb9=nl|uXZUYyeSqmMe>Jib* zQ8R53#%(k$@$0oc!+N!QbCmD@hl9e#EALF)^CG)*X18s4&y3=>%2B^k^8=pj_qHX! zQuyeiKC}zI;>p+9eVEyH_%{lJ82-)4H{ImaeWu|* zo#eyUGu7*Up410^o=H#mc_#g>p8DOTUT(gh^?TlkT~0u`%P01FiS1YQm?hVf<*q-m z#*Hg(j^odB4_LZ`c5;tnbG&|C!|vaAWci>A28M9&)7;Z_+2??8%?3vj z|B`jJ+wPFq^{=b4-fL#vCl0vpI^s_Kw~ZG(_XF{WGuMnCk6M^I&wun{@y`1u^#Aw)ZCPdDrgw$lo4B9EKj(veKSKzrEJ)zS>OxkG(5_*Qx5>HwtA)QA(kB z?~N!a8st4&NhnG()YpUt8kM2ROsNb_AEiP0c<&7*rMbLkHxr*G4PT`>4Kxxd%6~oU z?0q~}-CQ5{e(8VS-|uxF`(0{wL0kO*Xppo=GW@5?&j78K@zV8Vx7*f)w%UMwFhYZS{-=!wL0*oGucXQ|Gqm5 zQSFNLJgg<6B3S2hYlHZ2p*`kU8$==23-KE;XmJfNcz_o$)~o0oo_K8%h?s~GllHpRJ}@tP}W*)NcRYa<&+&kDSI^8F=#uFIvj9PZBpDHONl zN7x2m)T>bZyEgD&oJX4Y3-&||A|`;HEfvGg6jz1%jsJzepr3DRK-AWfK2z-B+PC-J zU$D=F*P^}>D8Z2x5<4VzNMay~fg}e0>M;<_hp`?^^JL6Dbj-zE6?1M^3rq9uO`c!* zXGRbcoX3^qd>GG<(44A7@)!TCfz%86TB+nO8?NOizSB8>p=4`0LO4qxt@ZYbJ>w<2I<{#b48pXmQb)2bAE*3W*&OJ0vlX#6S`Q zf9)9X?~HTrel5{=#%=H(!%}%?oO}1Hyo)Y+2XaZg<4@lG>faw)YVY_%RI%?oMmfFv z5AQTopW=Ok@*Y0L?wy8;@!mgr_n(x-@BS_+>wvW~U<){s9FEEhlWc&CG zpid-oeVmis{Cv{KCwRzL<5MwYl3(;WerdmcEEEqWIO@?8J0y14{1}MZUo#6^x^|~+ zUD~j=Z`W@qcKwE8^ck*QqfJ}+4Q=0|kCAH>yM9CaCiF?OcQ2a{8hl-UVo~n;8SDBD z^f}7M^-Id%^;Z^Ut{;O;Kdvbc@M7M;G_Gl170J-N)%UBaJMs79n(M39=li6mA^rWh z2H7b0^)+M%L-z6Gn(`O9@>{%apcu4de?P9N{*VEBv1I{c@?D9njnEobp}Mn8;1B3V zW0|j`MLFVye1|$}IqXEf^JAH%u?%(hW10Gz`1r9*V}oOc^eGf$sUGAz(8n=M zzSBCOE{GTM9b!`b0-5AHKbEQf-e25r$@2+#Zd}JVx1ONbtta?#Z?m2!q36a6tuxR% z3EDrtTkQF2_Z~^*>DGS~i%hKlC>C+Zc@-n)#aan;aCxxeKYJ#D-b;w}pHg|AM4tbl z_g`0zG0Mr0C9>W{&jpp*dY5~ztNOylr{XQS-bK%rAU?ex3q601SV3$cb`UGTh#gup zv4|Cv%g54sV|>OB^mlDg>0F=B8+Go4AEbUqI9kgrhv(bM6N9{hI-|96eN4s}@ zh|d4rc&FF9K1a)4pQ-e&kJ@7Me_Bt5F22u%j(*%ky?mdEdTsLjpYk~LYv`{_Z2k}4 z_=+v_7?bZ%N2PIfRP5@g*wxYd&cd(Yg)zkS^P018T_|@$9kZav7)8DVAB`vQapMkR zL&pZtqYS@AddG7W^@SVn)JO8W($GB}lp`j!96A!805TkZKUeWF>Ge?=pm8zj^*5Be zsSMD-mShJ*_R+Wp4Priu`=~95K0>Fto1d#F5Aut~1!$rsiGMeLz8djL_#}2nVt`{n z+L`tVDC53``jA3>5%nRP-2cnkSte@xCBOdTk;sMz(5abLuJl=Q#8&zIlh zKEF_3M}0o>xP81l>hlZrrPSwZ{|YcMxVRw z|6reN<@i19rBTP^zHsy$KIJ%@d0#jhC*AWH7CuCdMb9m4v3z`k=P`U9S7pI30@ zA!r=EV#i1A>-Z~nauv%Z&_}V;Q?b)uG0shZJn)B~AP*RNd7sIDv4>yFQ4h!i4eAGZ z!1BA1KZ;=w$U`~o1bM))pPZqf&ziXM0HuyzvEu_?p1)!zSF!vAeH1%A6+8VEN6#ok z{$dQii65h9KDGuwM*dpwv*`bkUlW|zA&G&_ivhR3Y+=XJ=>KI+S=O-QaiPTef2<>y zWG2x(Z~S=8IPqgNA8_*@oddXekzzN0QS9bX8hg%PiecB%@*~$&(?Pk1KwOk%*tK=c>+2l5Tr#pOYY<-bY3CPql|wdfu&`u`;F-n_gUZ7lluHi-Wv zII&3*16wWzl5uToT!&=;Cv%dcEbOthtRYK&9p9HK4d3}^?@D?-;s3*X+!EhynR_?> zxk=+b<4zDs;p+_k%;&y2@YUEkRBd!|XdL!Ty}Eq1><=`*8e=*6af zzK3Ta6uY&0#rWN|bH7HX0=HJ{NLQ~NczmA&rI4~PEIn< zOy-%%JoCU(dNwbaXJWjTPcqLGBP8vv^xK_ApZ*g)`y2f~!HFG`7)WAZn0@uIA$GUf z-|Kr+?|o#beYAWlJsWAqgRivJuRSS*jV}E7LVLo2S;ea=pJKNkxUJ^tt;~`3oiI=F zoVqDnZ9sId=Y!GP*zzx*s^!aHe>5CXr;p-OQpbi@e08PbV@|1*9r;f5{@>r0Z5Py9 zI9SWOOq~$i`g(uG_ci}4c(i`>-eksqah*f2v(zQ@b&)!TzK&A&w6D9^B=9y7TLs=$ zVngF?D7H1;wqkSRZ7#kr-WTE{<9#H)Gv0UNQ{#Oqb~E1BjK#KpS)KozXG-W?5`MR( z{hO|V{B7$M_0RaXIAfKk9%elHZ(=9878Xcs7{x(ihr|v^3?wm-#6S`QNem=0kiJ_h701nha# zT#cW@cV}q$94>xtpP%P<&!Q`hd%jDtJ9|f;8Q{H*kmK*qx^ln2EIuQVpA+L}-JM($ z#l-qEJ@~8--m@w1)Wn&GN{@YP*w2P*`7A;CFP_cQa^WAJiHT?J@qf^}-xc#dINl!z zIr4r@e>PNn79yXy;rLkabo>=Nxr*hd_*p@xrlD#+&gQCJ@(L7^m&p-eJ-`N?-{NB{qfCn?7Gw5S6u0oj`qoH zbptz;n{klsaN5C&|1)VPyXUx0iXZL&R#@@U-ioWV8yS9f@nwqNUHCw@bH$+^r#%*$ zz|+XJfxlLG8qZT?881t8FkT1I&3N5JXXAC2x)@&rU%$tKe%3Txz2g^ zjZ0rtJmKsb_Qdk56_0$stUbE?PI5kVGkf_x{|OgN*<0}gzfB2u=(3;Uy`JwFR(S3p z#X0B9$chZbkSQ`0L#D`344EQBF=UDi#gHj7R4!zS48@QsG899m$k4h#rpUm%15hs` zGD24`BQg|2rpQnXnIc0mWQq*y>J^9##gHj76ho%SPz;%{9q1twwgZMt*bW#nVLM>R zgzbPK6Sf0}OxO+>GGRMl$b{{HA(Q=86lQwn!~9t;>%)4o{#-AvFWZ6b!**kPvYpxf z>=*VI`;q<2e&=}LIN|u=xZ-%@IOO<548i8GC1ML0wnWSU!pOWTC= zm$nt>FKt84U)r{uzYJ{Y{AFNE=Pv_WI)541()r84md;82Uv_E%-1^t1rr?7gFus`bR~~4t zTH8bInfpt_Lh(E$C*t|w)hTn{h0T=b{Xt_hs@a*!v)-jm%@4EBQ$FJ^Xlklg*+=<= zbq_F)O&hGZ)7S>)uvxv*SN7aKxB9I^?ckfw3%*}bDYtWzD{R|J^Mh^Dm2%Bt=i7I? zR5IyS<#UJa(bfLaqp_LwkF}{TgPPkVyLT`@kNhNc+kv~=ez%-uIxl!8)o;Y-;g5R_ zFh@1MBlYlI{|vK-4l##5en#r`U%tXi?fBEw3(GLR`Utkf$5nIgkVy)uv~GOW}q1DPVjO1(0W z3EN4%GLQ+|Nxh~*CTu75st1{{ozyD@nXsMID+QUbozyD@nXsMID+QUbozyD@nXsMI zD;F}^UyPZCuVtPri*;b#SZA&a*OBYaHep+_4cWGAbM^)Mh<(RCWnXg)aBOhQa4d0* zaqMwSB5r)FBA$E#0>&8daOMQuQjGJyeh5h|F3%`VJ{Dr?lH!j1ES;)Y( zuq9*wW9|SMz?f6GaUU}Myb&@n7r{7)xWXJoF>DDLD2FY%4X)|cBdGCVrQFevUtxDX zIPqv@(?;CClRtIO9wV%zO+IaC7!GV>JGZ&9AnQ&ZW>PVA7xK*VfK>u%hOixE48(%hxu0-B{NBl)tR|Sy}f}EbD$&*8Oy?PuBgcto!L2psf2@ zS@%QkV`SaW%DSIoS@-j~o38oG`lRxa^+_x1lZs`1(#raz@|5*SE9;YUz(>|6t*lQf ze_5ZjvOcLiWqq;`&lv+=)ADKg)$EvEw?Xb^>b?AHSflYSio+@k!^*eRQ`~dgJHo-| zYp!R0o_KuNb@YK+KJo2uaW79XazkE&#d-mFQjV$lAFt)Q98>c@<|F>qYsJ55@vma> zZy^3vEdC9|zlz1bf%sRk_%{&$YQ4n2KHr3Yv6ihgl(*^{fXiDA<*m8~0KK6<@>cu? zjND!9rdaG|#BRpfEfBjY7P|#vH^pMNK=uaK6pP((uTU}ac;w08gY^Kn<^a1D zTElm14!XAQ)*N8BU`x&Scnz&IG3WcGi8)s)P0YDoX=2V*OB3@NZ)xJC^KVP9JUV)Q zqxI^egCA-S)Mq*BzjH^h_q+WRAAQ1qf^p@eXFnEvw}TnAZ8t5?ezLE*WKy7b$7RQu z_p0rwxbuphrpISr>$4?wcDU3mzHpr4yJhXDVcjZ(eYwwTnH>(P zW}cjNrhRhOrn9-S?SA58M}=_|z5l#HW7FTz_znpwZ<+u5a;Fg`xJT3hOc-&3Q0;$%|LoOJ4jX^TnbL;g2WxwLhM`JagFc zOt?$?v+XYJmt@Yq@6+(Bp(om}hAzr-dFb6@V>GOrtY=uN_*VceyMd;d)O)es%xhFYf7r~!>w&e?Uw6Ha)$znSp%kEt0WCWIedI>>x< z>Dts)w>1cNd3dPV<>7UyD|Tz0oqftsGy9ZvsrSCQG2Nv1K+~l6npCBlM+E)K^f&#= z{FwUYz1xHEx^qo<-B+o`PrMdVs3G=l0g?@bsvL!PBGetyi(feHJXWzU`@-~XhJIH-a-edGo5{W`VFch3bMjlaTt zH2&w*HH*&-KA$+$d_HkqYOfh*r@uaPi23@=-%?XLEXmINZGf5i+sahW?6`1A{yAnz z{^zMOc^`zg&Fg4xoA+vJVZCVXvtrvvQZjF_@_)0i-uRUKZiOx=lXrSbuCsD|&@)>( zCH$=LO;71?c0G|}MP7EV8B3;!d@Fi{*DU^Ys_11!zi^lDT4h9ED|*ZK+Kkl0N`2%z zBO~>*QcwBL%SgSg)L*_IWyBt#*u{36@wP&{?hkdiyu?)A$%tOm0T-Fe15SJzo+0s_)Ov<1s|eMk>7Kr z|IJW2;>6Pqr@o`W>2Ksc*LisbCscw=jvtOI=<4H* z<1ngQ6rZTGk6YNn$1`l?<6L+MpPYPo*Y!SBj`xIn`jGg*Zt_+Bu&0lI@bLP;{yzTU z7a#w4Us=Aq2XqW%GL~!IC-I~2Psq*^Q-3W#dT${V%F;%-XmG8r;Mh`bL=g&G(zKc?0R_$m$f8;FrewMm+yU&An zS6*!1UHN_L(=YA|>OOj@sr%@v)DttV4MwaUXhy7FlX`Pi)1b@?Lrj?$eoK8fZeIE< znIoLFY+b6x#S2?p^3YIo$wTW>&wbN6`*EEi=HoiQr5@?~Q?_24fu>%YHL0gwXce|> zcbRF~?x)m{zE_14+x9gR+b&P-c2a&gr^9(>PKTwbYudaVKKsEL=GhNEOs(#^I<)JK zH+J1CsrKnz?1(Zg%!o2`QvK|H_VJmu&EqrgO6~AjTRX1H%3xfV0jUAAyW1KQ?+I#5 z+$S}D$tCvM-x>th{x-edp!%8>h&MyO@46QP}};^W?}0`ADO!3yMeZ6`jN0_ zx>+Xwfw#!a$Dc`3vdwp5ojxXO$zHeu$F5AH# zI=h#AzsP)>eJ5Ocd4Id~@*gv2e06KsaP}bEaQ52FM{Dba^%oDd^%t+pyxO;X_W8Yr z+UNILms$JSwDeIq1MN{cYce04(Jpv%N^>`|XBzc0X3&xy?Vu$$ zWVU_kMAON95_U2@GyfL&FXSKR)&C*9V#bKR%ir@Z-T# zfBt!hY2SWoLHqXg#v+y&Q@>GYJeAn<{S5k5-~XV$_5IQ&wU=>~kIgITe(&LjPA!o4 z0cgKBXiWWJ(3olU_8T$CmN5lE8IzZ)zIR{Seb$Pg`>cMcCb>Oq#dIxGF+C|&YrA7? zuajDsUMI~-o!E0fJEmh-Gp6HPsRi3svUM&#&(yhiX{y}43&Xqiz1-Zj@9Nap?gPUH zdkr-W_F9)Zwa)Y`;WW_%bZtO9MNTYBh{le`PKl<5FbHJHj&w(zCnTD@ro-B)XVBJ_}t_xyU&SWo@cZEmi z|3$eH+6d+%s4vD`%te6ZBjbL&9|U8zmZObGn^BB0Md%b`tjAmg7osf)U&R=wqj!_X zUlrPcZ(m8f+cNK5NZMU|hP?Jsu1{8+ z^qJB4m9#rux4__}b6J37yi4XPvbJw&Z9m4@;g{Nv>yFmB&Ghfiu~U~XR($N`vPX4% zb?sYDpL>u!qvgSh4|;qj`_Yx16t}(Wt+4+Ey%pba=E(5$3oldLZTSP)Z+D2!HW!@s zSZD%IBi9E0TH$FtPmyK3EYZPu9Yi4pMtoXw%$GxV^FB!Q;}VY1KxGr{3PuY@4aCxNeyv&5zsd zqc}CLm056buHqp7C{y;UdWxUCq_w$xd0oX#e`#&TwvX`nt&cX7zu#NSXP$DjIrYs5 z|J3eiQ)O9%?RH0-0YOB6&(*EX@$W|X)~Am$jps%DZ@j;iX}V)1_kcb}niZp>v+*C; z@d)!%tw_&>ivm-=U|*GW;KeP>Wo>2usC+tqdzcxrI;!IrT@EoF?>kV-2S3o%9C@-l z*Das-DjsO;4~Hl&ds$;Mx_5KM^S9a0?Dk*_#rHI7XsVqOD8BBE2Bz!vM)A9^);Hby zwN(6Ih5Dvx-6IsYylEfv;dK!nd-^`+iAN&*=-K<2>t;oGKxQA);))3GzH5Cmde;aa z@MwMW_~?k|-9sCg!S6(}R-M1EnIZRMp!0G48=A2-BYj@Jsgb$1Mq0~H%-!EK$Q-VC z{x%1gQA-X}{OprW%pNTdReaCu2g!5bQM=pjq-N%+2b*fS#D?{;(X>I@_8Ahz!-KV2 z*;Ag3?ElsDwzk<%wUvJ9!yW8_J$F;w@4gf4q>px1JZaI1_NZreRQyZ#F80lfD=WTC z_8fg7`;DM~=NG%$_l~cq_?Er8*-p>zpm@Mh-E6_w2zN<$vya~z;Sm+P*)^X-G+B&+9jo$YTAMf>abJmf_CMnP5O|LZ{~*x$xfQ@rfn z^_wBip3)wZ|n&`$B!ckN;4A9bwa z23PNH_gdUu@!g--u!mQT&JDQmon7r+Z$|iv{=3@U>Kv~$$K0^1y`y4;%kNUd?lvQ$ z$P1ku5kminp7~HL*v26V<)`s)KB!oujxyJ_|qN({SEk zGkJKq0C@Pmmzg%*u2y{dQ5Tp)YQOM1%rty0^PJkUwk_MdoyuU`vTYcynSP;`e}Bi) z@T<{hDxTMC2ix$}=ze!GX#&qj=wmFhjF&4sjpr${0xzpLG-8VQedq~}V>`l9ra`-#@ybCmmu*58XnjzQ1<*>4(Mb`RPW)9|%y6UK9gG`7uqG*|mfd%cRC z*T1vkBWJx4?(soy#phNY6@IwWWr}y{`AW8)oPiEm4VDj1e=|Jt-E*tY3huh<3N0_Q z-?PDPA6=k$x0A}5X-iN39cCK7mU*%))`4|now+VW#g9B^9?~=OAw4s1>6v*;&&*qT zX5P{>^Ol~OxAe@srDx`2EYHlxH1f=Re62h)AM=!F=3`m%%zUhaJTo8bCeO^rI&)o$ ziZ`)|A^#fkZ$SPH$iHdwZJ~=8e`dgCkJ!$`YAs8*PVk7CrA4x?(el~&dHxdvHIk+JBjbeW`0`Fnry)AAJipHmV?pm>X?pm=3i}%j(o*K7TMQNgUzxd}UbT6yc zi_4jw`7nQ$%lfdMtUuRl16lDt1(BtDl3_LZ;Q3)+N9>nTjK6rE7zFNj#cschwoSKR zMlt*)W4GF$<#IXGGau&9a^3UHDwp+S{rNd?p%EL$^Uwstd5KMIWQHU*wxk{8Y?iD) z-=b4!4>WGZ*^5Xd7qU1_2Q_XY4Fuy z_QzivYx#qt+S@Nz?XLKc>$=->zFw()OZ!hQwqfU)ir?68pnYt9YsI%dG1Ol9S~`t- z74_WvUrkTx8>Nqo#sxW-W)7WWlP%&Lo4B0mA8L45?swVh^}uV`hu>u@-tp{H&mBI* z{8Z3CoOjW&bKbl0ayjqkiSUM7CeQi#>Wj?DH?0Wgwt9cg-aGd&&1O}z`@K{-TX9)O zbN%>z?LTMkmpyrWU``$p*b%EbWS_ihUvurq&bI%I%d`DIt!!4F+slr+{-4=~ue=?M z`)7Y!yWRBcBM06T^l3N9PQQ0fcFgxX1sm8uK3`~Se?EWMU4zYT4W7*&{^{KG@FRwp z#MB<}Qg(RX?b70leD8~beOIRI{r2Kh!}l3tx?g-jaOd$y%{j8_ z6{f3vM^CCh{Kn#FUbw(Ma>&8}&_Xj3Em@28J7=fBv({A=kk+4lV! znF=ktnJY&Q$(EnKy_xXhh33v$ld`Yg`9yHdj+dLW=0A}AaQ6#?p{twbe${kuod0M( znba_M@!dG)i_)?q^A91yVh!-E(fd#Z>hRR7BReEuZO~BFMX!= z%yw^X*KC&;B5ogRQ^OwmY`GBjykM_y!w+k}q4W*!ofW=5@XjpkfBmoh?B`Eh8zOF3 z_q@PXzwD|I@%-SO-(~N-EJl@WrQ#53!e4Jx*oq zDd#@)IC3AA_3~Fs!zZVf4WV1d_A|rd4|`T+jSmm7FORrU>3^L(feN4>>ka`jOp^v;C^dd5vPXuTOt9`_kOu zs@t(&wXypQtYTrqMHSOFoKw!iZr456*xoey7uD_8!F$+!^WRrl|2cncxZ;b4RMv?z zUJPHmb)3q|UVn4=`j;J5);SBR*bdkHs`THz{6$#drG-j=z$K4{+phYT(tmTysBqQF zim#6gaU2#h|YiN0kws6+s3&NW1-c!PDeaQPNtIfx|hT+*$Ro2XAgTvh1rb<6=REKclp*t)6htKRCzTDt*r7u7I z+w74GrYrpc&)3bKa@!ZG+YyyUg!4Y{ue$a5bzu0-Q5ULiXB>M`c>fvQRkt?dP78m& zqoeBf%DPtJ)Uk)EtQEV~37=cAi^@9V{9m&Fn7>SAJu>I<>`y<;R9WTwHYoYXu zhP;~XJ9jswud-Vv+jr3SN`LzveY4N?eo*Oa*3O?ZXzdTG+xPWmW&2({NOjAQ>NrLUyK{&w_Yc^vlTX^UVX5bydr**&Tb=R9Ro%T|e8r(h8OJ z;r!KeMz?=RW!>;Yn7ZMIi2lO0x2G;#8_~b8vR~?jl@a}-)d!^(t&ZqV891QcDFat} z-O{96nsiH(ZfVjjO}eE?w>0V2!s{k>3&?J1vRj($mL|Kk@OBfQ2ISL#d>W8X1M+D= zJ`KpHY4T~>`&8mBpm+-?-U5oZG{sxm$D6c;fZ9SpZ6Tnx5KvnPs4WE476NJufo}`a zP6KME0kzYB+G#-TH0|4|^dW}&5IGPq?n4aqAp!Lv0repP^&tWEAu^wc`Vi^g0_xua z>fZwD-va92(!PI_zSmISYpCxv)b|?ddkyuy0rkBB^}T`bdu3cOG%f@*E(A0#1T-$B z{kS0Gm+|A5j9G@pEJI_Kp)t$Qm=(~N70{R!_%TbyQ$ypaq46}J@ig$`sf?j%KZeS< zZ~V9~W4)oV-q2WYXskCh)*Bk@D=8@AH9;wL*j6twzfN1eajeL-Lr)bFA6qi(Ee8a#Wj(tmU8ieS`RJ1YIP z10M>WIrI&ki}ru@$Mj)ys_Gna;?*bSKKx|^jkLLy;rc-?l$0zgN4-io3mVP=3en zK2%)3XYKrUw^u?gVAl@ZHvjd*a}`&cyfAZrea#WQSpZz zUa#!d1g(^(e7Vr4JiYKqc|O8F*Yg*-xn8d5lk4>nJ#)RDqJOT}pYpYA>oWb!rAHQI z7u|eE_}P>*%<0Xq%YOFqs_?7(TAQ6e`A2r|8g=dRNqOeHSNF-T-T6q{^grcI&o#f! zdH1c8?4y}Q!E3KSIcKK|=h|299v?JYaOIq8%lq3ZyEG2&J!!`|=N~%A?)}{Z>D)Ef zKh;h4!1Mle$_=xWGiG_;H}41Med4@-{Gh+s9{is9jw7b+6}|r7wwjXt=bQIBc~H3O#LH~`6HZ006pnmmFS~Hx zrpkwMG`nuU4)&@a&sIK^(}k4xg_IA5#~)oc-2MKmROb(C-WNXdSfvm;S6jL!T)4VJ zh`JwoZB6^j>_IAv@;lqRMQi(gtADAiexG!;WoFM(op)(*rmeW(3Dx>4A?1J}<%!|)m#c@Xa5{dnDM^KqI}R!IJu6ka%p9Y*qD3Ae)fvmH8IBy_q^p0 zTUpLVgwCH2PTRc>t*<(-zH(_e;o)zT59NAx_|#o&&)GGU59Nj-<%}WalHpEW-pii- zVucX#Jm{|8;fNh?Qk|aNs9RJ5JA3=txvF#B8&_p-Id7Kgd}P0-VZRm2r-j{z*HT%OSK5(n$Aw>( zZ>O@}`}(%<<84n-ohQ67B|PblUaIrzZKj1cSLvfV|8!czu+b@dD<8@k?Osp(BdoK$ zgYuyqGo;)zq?|My^VYIClV5G5I)7W|%4|W~$5iK=t2~yyv|c&YdD(=Ivh#0BsVvGj z?V3(IhE*$dQd!mV_6%=+`z+P@syeyh4ZmHYIv>?%-|)n_SE$ZiUpgmyeWyI-L%F0a z-}ax`x7*6Pt+WfuJwwV#L&{adgLk>V;GyFitInTKKJ=bG-#(!__pWozJtM1CP@O+} zG5?-3mPfM6-;uq?<)L=MEsO41RK1JJI`it!?|Cz~x9Ysh3oGuqbnpPx`SLs0+*9_< z!CvPy>Fje%=$s~T)V8|t5p z@1JE%32035IV{E$Lt~21c`>H=To_}D&yg_>1~d)^G!6zd4hA$1`urE;prLWl&^Tyl z95j9$l(E~;*zI#$jNOLDZl4Qd?Djb_#%`ZGW4;m4d?TRwMnLloL-P%v7h}F*Xue@+ zzF}y-Vf=hU=17L-NIvJq9Ldle$>+$JBl+AJbGg9JO=G_Nx>uQPsLCv#Clb5WlQV=iiFF6wjVQ0B>jpC`+_)aTcjm-@Url=*W&^Jhcz zXG8O6pGRZeI-_UyR#*D>2r3F z0gUJ1@C8O0WB|)Y-X#*-KYpe!;=SHqXVkf`z}FLP9_{ARLIdCMLBqntGpoJ^(oR1KbZFALLUHwUic^mA9=@= zVtMycc+B*t6fdlEf7tV?MT)~_H_E%BK36R7e+ti^{G;N$rMrgPrhZj?-CYy$&N=PN zmVm8Xe5AU*-{4@ho6`ba+->lv)6e0Zc!hi?OUuawqH-ggz$sIR$^BSqO=Y!Z^rAzw?jE%I85fg-P^*a%rJU(2$Xo@uxou_$do`{x924R%;R z_rtssKEqs>=87TObmYs;o2#Sm_AwF7r%QgWF7LZ5_&d(kqy0$hedpU8<_T0^_)*&; z@(l5#Z|`30gAe5uqX!~vK!=T zIb_OjiiHe0mtx2yzo?yj-N3J8anuh*e%n+W*BABBy14ok2OHGP(QhJ-{LcFxijUX( zTEu&~_*)!ooz9@$BrNlN%F-q~$J`QF@niDIb^nD1Vm|=~|u3xl|vQL#duFw~F&2@OSHt78tq^ zz0bM82kVVWgM5hOstjBU8<3t}2K2{zV*zNq4E#m8%ehc5mErk71~Bq1mvfz;sHEFaPR`DCDuyRd9;~*1aGU1Yv*rx-IPI~} z1fFICywPjLhlSP=u`U<+wW#u8_UVtB%Ds1dii4Gp>MR#P*2Zw5^*^F7qI{Tn`lE;C zc?W!ogV&$CBo~0EuWwP-rVyUUF+@E?o2!Rwq=T2Oz&pLf49BX{jnpC zu~ol|-m%BHIM>4F^Lktx+ka!&@z**!9TYp=bRE^n{T(jOwPHiq#M^MA*u|&POFScn zJw|LRb}|1)7;*0D|M1#k`qX%xrS3-jrF9pZ81a{4v6T^jsVuRB5r6#-7w1~U6VPvT*V z#siq?J5Dk{cs|}gkB{f({d4+mySbFg( z?M}~5aB&;Jo-UphyEs?dy7*V@+J$1dq!|6lIJu7<`AcjWW61O6eroDV;0p{no&GaX=3#Mp2<+$;J3fjXf8m`Y zXHBVG#ZDi^PEW;7f5rRNwRt{YlJZdW@bsa`Q;c(7M4n>dZ$+MB{Kfwv7r#ezsweEC zx`7|~f(CMqe6=R#w5Tu217OJUc5r;O-0?S{adH(qeH23u>;f96zv7PLeoT3PCBEBg zeJ5_k=kJ$G{#|nr9^)7%e%z|YyU1Oom?KN9l*-yvlHWyVjbcp{Ye~-0IyM7u?wV@i z$LQ=*zZNZj<1=-{yvEJ7a3(9(>ec=(kMq6|vShs5+&Ci~IM6cNKIRNF3zhWm>vC~Jf(^Ik2UooVJJYU{e^zihJML)&D=KztX zSoj|x@)YAQ{tq4SJLsIA2Z%h?6Z}M;V#pc01HOXl*!vrS4omv??b)!-w1^~^fRpB zExjzrQCT>bS?s7ZZhcH?{M-qA@H^?2?rE&FA8u?9q2pVS}rSa>Hkmc?vh;1|uVP~cB>yV&vc2*kEAO2FB z$et}tRIkW>;N$$RG|ulzL1Fiyx(d{m>3Y4s7T?362br*kLQS1KOhdM05S< zKM79kurPlw#!m%Fhqdgqd-7e26$()h91$;I48%U!({JNv7i zuoL8g9`=i#sf}>ryRFlAAIz<7y1&v^eO-0p4yIPRo8tGIEe)FFpQ*T0g>3NRR~P;c z7w1|Hl}(s`iLB7e5*wuV1>|#l= z$VH6(4j1QIv565q^xEQJ@r4n8sV~GwM*O8da#(%mXw)x%fdBMbrvr5I{r{ifXpAY2 z9TS?wR$D;~XskOu6Rd_v^60HM9-w)WcfblRuhBNWHRT;i4pMj?vbFfp&HXgq7`wTm zmKT+e6o&>e?Q`McU^h2bxr{}(jpif8p>cD2-2G`8CwL3dV~4qMXgGL8`xS9}#PY&_O<1Yz_6iZ6kjrzKhz$=B$7J z?|c^pg^!!)e@Wi||Huy7FT46CSPk*_T|bcbD_VTrdlePCcVa5Wdm!CADCPh9PE0Mw zdn4VuBW?6P$wxx)0j+y?q;>Da#Jevo-d8E_#LV^b+`BTh+`T(e>G3{D&&RzxQu(`g zM_R~q?~YV`qW4WUQ4*ddN`Sgb!o@gFn8&S|-0md>Z9J1~7O;GUS;7;SCumheRsR zC;EKo>i858{{oU*K>8Gro&}_T!AHMdS0&+M`X z_Rkmnl?J?v@*VXv{(aEsdkc*5zvD3i*JwHVZ{J^||ArmWci}7L@t8XvCrELW1svMk9~^W*rymgzza0sE!Byii}Bd4Eo*sk zF`nl|-->5a@w_cCo?*rFt-umz`us64o-xK3IC>@-&%;K~7Dw0Uv*Y@FFv`JuT;&D% zz|c`-q)apqylRo+u-T2_lKjsVm&rRl zJb&_!iu0E48g85VRq=IqO~gHP?aO4pR*K5gL>~~JfcOU_Hz0jvJc;!T)>J+`(x=0> z!8MCN)p~t2{^y`ZrQH=j-F6*t7WD!a8pWWIYeSTWaxLuZ>W;kxit!vW?2B?K3&E!Bl(g?ug9BqW_f zzLsoT5wcvqmSr(L({MRrQOB|fB=|3HhxKzmniH1DTpfLPWRB9CtK;l| zzvEn8Y>7EC#$oq~=Chb5P<`P?oh!MVOR-#loJ+CGxfHuH#nO)>=hAyZF6UAV-W&K) z#=IyWqTB>L49dZWaudkaa>&J40UG&O%1z?uh9x%x;jeiVbS!?6HYB@_V!&e^c>#UyFDz7k`U`tcrf$nfQ42bF@F3{<6Llol}E(6V1UeCi`(2 zb4$gTf6*Kab4x7;EzQ9&x72bsw^WS%aa4}ErIusPMtlm*@kp*AeG1JLNq-}I<8bbV zd`fRUKUy=4e8(7jh}5KB|4-Yij;F5f306ZSdCArr572zQ|By5Ixgl}}KWB6~gT^~@5}zyJug_70 zQJkaTI-hfZpU*{P&0Ee_j^s&sync+l#M29(c)eNp$2p3~iRZSM&qAJj{kb3UeAera zJ~}#QIeKOb@`zrs;{#rswO>!3Z7St+LU6AHpTu{tf{P9Hql+2E@)Kf7v5PUqF7_1v zuYBkBTd59=i`t{-_E;%BhfN@RMPq`>#~|%8cW~i{6U-`{)NdWiQG`esA)8`Ji{-{z`LrwTZ!^L(fv& z(BL~c;*;`ZuqL-Yyab6?K`f$wU2%Fg*J-A>H}@xZOiGIL|-i)YNt)x zE(Cp-R|eZAlgBHr_)C8~qu(cr``>o9J+js=>eI(}?TGt?it!i!$F=w!bilX{*8_te z_yR)?D_MC=#VVv6eyB@bF zTzd3nioYFsRe0g^LlhsJotK@}FS2>HT+s3ClNI-G zT;BZi@|KD}onPPF)~l}KvY)l)dl_;5gPg_ZKQ1>>dic)gKgfN2{(~}#+l}6%>DBA7 zJf9a~KI-!y%u|U^oc~~6OLEQO3*MKULv3CNOG&IJ)zMPjE!o79twOS4NVd(A&C}$I zfP55??+p3WkgpBJfT7qh6f@>;pg-#HyEzK^)KZ@iQeVM+NS6ARfcl((`l5jPC_L+- ze#f&8)TbHh>kRdQhWbWBeWszl)KDMA{qR<)|CLjszM_@=N0#Rpgj*0znsBk`WqzRj z8^+AaRaYxMclj9>^AE%W#zvYW*-fR#To!!5gT`4487PNL9Tnih(F2Jx2;W z?2y`|)MK5*NHDlS^f$NHcmA|7e29E9t-2Ya2yjw%*{~YId zo>ufJ4hEg>M}y2 zV~-T}N}v zza74y%QPx4k@o)111;kHs>QLh=pEO0S?EMra}V~=7Pi_$VCDV8xRD`S;n8M{Im!xYPy7RuPB zSjIZ+(N-*Dpp~&uv5bvY`m5Of#lh6puqR#lNR^Ak_zgC3v@xb}$521{KZ%D+Z&`Cs zamEF%uk2qAQ7_qVjeX6EWxqA{JL^0_&TPOwX!X17x5oZx#j@WT`=%AkerxQfRvXHG zYdupRJh9Ij{|CnJpaaHrxE>h%z!w;DAP*Swp$9PZf_}hGUkkjUFQll5@?m-{uJL2& zpJCyve1ryla*PpYxDIiL_ya~fA})aur-)Zz#4q9)7;&xfEfDdJxJNPC0onsF+6USR zFxm~;4=~yj+Le||J41T|M*BlM1V+0=`vgXNMY{!#+Hq8O&KKIZub1cM{r}Z_Di2>U z$>#!ydDR(lR}y_4+rOAt>n_zVG@i<}e^~D4rLY%csgFeo>W5qi81-WvHphme&)wF~ zPqvs1xsD~Rf3-zl$~!3W*}SvO*W0}4oTxC(`Y}|5t503M{}7YE(6_4}<+>tqamEg& z0WbM(!umi=4}JZ$e}Xq{&PjDF)OQtCE;>NA*MFlJ>pq~Dbs&rL!hms>70wF-##vUY zv9>KVn2I_zub zzf(u?#FcFdop||PC)RpB*QC!aS%!m22T-X{s zp%3fH`g6U6RO^M9Ld@Y>#1vu?*qz&{7%_#|MLA*$F%68ELca`*m_i!>Mogh?03)X8 zd?Dzl<&eweOwW9nKg(r(_*^5_pX()Ky~;(Ofj$Mgq0d0S42(VleGoAE4D?OF=rhn~ z0i(~L`;{2$)#m6kqJCN0vh;-;%rW#@$mMdTXFklI<+47kC+pAk+F&lHdSXl6s7nXSu8o*`$#EWJ8W6oXe{EW6Y;m;#kGGtV)A1 zpJEATtZ6yMe2OKU%c|vW%vX%|OEDZuh{WYg&wQ9a%Vm8i=5a2o^2D5l>m{-*ViN6$ z`U*>Z1#%zX7a=Fo7(h-$eFbt8Ek_PTeFbtZm5ZE<`Y6bZ<#IXGGau&9a#<*w zIny&A8f#jxT-Jy6Wc|5b@GJZ)A4_AsrLi8*MJSELl%=uW(pYb4thY4QTN>*NJ$J!! zY3@;op7}6;mdpCEo~%FD%gyIPvNTAI5S zI**R!N*}HBH{^v(&wQ9a%Vm97Pu8F7MY#!Vi@qaA+BbZpSlT^&=W`$URNJZa6Y#ZS z=|2iR8zZ(g;3NGFVn(s_Ls)}SEI+~5%3u1eLgh@)e9#Yqr;D*zF6+a3vi@8znybUM z%16co_(-vg3GkiDk}&~3RV-tIrMWuJ*wk{w0L|4yjJwbiF;hg2V7Z*>nGf@4xvUTC z$@+7>IIa>5&)_pmeBeI`jx4dY*dZr}-?hP*->Ko=Iih~%_iHc>mot4)@6q7*WyrOr zR=S(==l5kW4VN=LzYF6Ju=Ydlofq2g^7}7}^Ii<6gMnWeyLxH4(@n9{O)=AOIn#>{ z_SSQ&dp+$D!;kiQ0_)i2XrvF!$zggfckf|QdWV&d^O4sle(#LbC4Q%j=w`+KzAj;t z{4*6Zjp!VgGd;I|+&A*~^kzrzx6*pK`G@kveJ}qEi2RM8E0n6mV;Am=%k@f+`{KAi zh`L94NVHZ2IldhC);ztCVXZ~!A;&)>gTG#``(0^poxk@8eqMj67v66r&)voEw^I8% zdc}^91&!mc*vVBaKS3YGPEW;7f5q+{NxmHQ_4KfVV&Mb(D0X&J?Ch!7{jM0-!H&=k z{9s35_)F|4&(uXY`m5MP_j%*`1}J6wxcVBDvpw0)@>6Vo_6z%K13$+8g}#sn{_;V6 z6}$R+xpDls`f9nWuj=gTtC;J{c3}Ik-PoRNXQz*aVop!Ru&eji+)+#9zGl?-vwxi( zlwK~6r zzs=uc!*dCUTh!IrTe0(lV)-fVKe%6U{!|*a2lr2GzyEkW!UPusrUUDHA1%6$yS>l2QT z>go6^c5)TV<*K1{zS6Z)(H_!3Oam(?{ zanAAY^ii9*I8^N7Q1K-{?;rc3IN1A5c*`g9;h*C_wog&*qG!#$(eJ5kU4N(;?G^Qp zWNnFcsYri6UZXA^i_P8IRlKICJ`$V5W~zhO965nv`HQvN-|5CWb6s9&ItBf((sQ4{ zHh~=9hZGP0zAr%yy_^j(w>!oh8%`e+UAw-GbBuB9aZGZoatuSCD2I)7^O$M)TIR{J zSO?)0_dl#N*TvP}*G2xj(bzR){}{8cIR=Clyw#_oKjyQ(UB|HmnM=;SQ{uZc=D+Lb zpBwnM#Mca#oLj(kR6DRu*j8*qwyl^bwt4aJF#GPw7wJ6^j|}SI)k*QKgWn6UY1>Qj)qSrI zulj6&;_u#Dm2FrzdJpmE-=xy-&L67f*DY!v+^{Hmzxa#SKN1{vTJ-McqUypld@b{2 zS*!!=#yWFdxQ<+Rwh7xx^psEW`zY5QweGH+Dt2v1v1`|AbJyM#v%gBZACUWGxbI<5 zJJ%;GmiCJAMX~&Z*i-CcQn8Cw#qM{-F17>k6#e7%B*=;K>$qI&yE$#a>1iR$>91J& zQ8_On@)u*K;cMmcxP5WE^u9CEy`;E~Y6rFn+lp<-wsrcbJ=quRqYe78 zjpjryCY7g)NyVZMY^GTBEHW3^U~KZfE8$$=Pshhn(m||Kiftd#qEB(=FzefAEW%Y)ELe2!{a#j)l!$ZZSs78bzt3iUa{d^E3ymz-DqwHqCad4 zqT3&?*S*m6bOqtertm<(buH}=2VwsOjJ8_9l7pB>C7~It?*->7=M+&(8n<& zJma`>85fe_C&XPSvQSOt_#&`Y2-Qsq!3E0;q_Vo{6>}^N3KU&Ls-DPa=XB#N)ar#O2 znb#})AA4T{@8$6Qf6-=_3ayqXQYmFg-DgCLrLtwMRH8k!iMCrP%U49Q%bx5>zP_pZ zj4fmfktBRYmJr!}Q~u|ine+6{?Q?ss+voo7^`HBCao;_6o|!Xe-gD;6@|+R;;w1y@ z`;WaW^51vOg|@+t!v&AoKhMs1^bZE z^Te`H29ynD#=2k~vF@l7)RmW0^pg&cOXl^=0UeK!8^{^t5^@Z=N9A(g5gELV73^)S z;MvP6H{kLpEw67ReHr_BCiyW9zB{{XHO!O8?gBEPY$!9<1?z})N1dqbEPpz@@qXd! zVmTLI7s0^~(LJCvVH@{fU_OSkRJp}h& zaZeWaYH<%2_jYm57x#j3j~MrkaZefdnsE<0ll+-!Q!O-8DUrJAx^n&1UnJ1IPz&|BG#7sg8-vXp81IABlC`q%A_dZ30{R zJO3p80{t2EbI||6{)_#Z+aauth(4Kbs@sHn^p^zVd>_{VaD4#R4RAdH*BNmA0oNsP zy#m)UaD4;UJ-lovvtUev?_!=<7RrFKq0CqptRvPPb%MG=9j3$MOt0sMs15(?c%*%H zv+u1;Tk$!MM}}n7H37lc$1}-~Y0wT#Td@xF+@u}weOb!=J98qI-TktR8qea`9sCogROYX^b$m zry!Wd4nunif@w@Kw5K3zI5gH6+EWlrW00Xe1=&aNSoRlu8W{`xyMle5hDG*e3HCAw z&Llsk!FMrFEDL2o*-&Pz3)T_qjygeIk(}&%h<=KIwT}F*);;X$kOE2n$-WioKiSVB z{U`fer2j-$Ugrh$nfduRQ~$UsG~V;i`gt_jE<|mPT|&S}@tzh|Wk0Cfl1!XQTy_P0pt?(t^oW$8<(oFxl{! z&PWR;;Sz2j#x(dY=80vY3@97QjCH{}V%2JVBhY7sR*|1MZoOaB=@)^>n(nME%Ik) zJ^V`^qeV`?wjh|=I^yzJSM;;dx?mc7Hz%hY?I$F8^0=>gW??-%&AJMv+4z|2eKW(A z^}d;4@0$tszL{X}n+f*5nPBgm3HH93VDFm=_P$xfWqIFBu=mXbv;H==-hyfHUCa~9 zLK#ptlo{)Sb;P=(PEc1=1?Gm-s|eU~-RURcRdLr|R`k1C*Zep8xs+1sC=>fi61 z$aBAMBG}s@!QO@l$8hbA`8Io5tUBB*dvMggESu$q_Oc27dwV)FQ8tku>w;*Gncw^eUL%q;I3D3RMfq$to1^ryf<{W_KRek z%D%7iOp#&%qWqcknUixTttTa%*`z*;YsW|?|ARhBCcN>n)z`&vMxGmj!+J}y=f!*$ zosf#sV(E`QyRyL+EHVFQWBW%qrsG(TJ^=a#=rf=%fj$QM9_W*xuYx`d`Zm-k z36~IK8hjV?#IjHZlnrIZx?ml#?x+*g756)4ko(y*rupCh*|*Z_&#=sj(Z2l+Tfugi z`?K8J%Ke!!`Zn}WZby0U*AE5zbw$B`y-~1VhZNgI>%)A0UNEg2^Z9vQ>rT$n`!v#b zHp3dG$lzr*To+vP#I;adBgJx29xt=3$)o&OFRU->0ri7=L)nUev0iDg)SdlY<^=1( z+e5*#pIDZBr-{A_`Y`kgb3@V>cU&W`N^G|c>nj|_m~U!7H~Zdqz3G+NpDdsU)Q|q1 zb(I#ER3B_Q=@s$|+!&W;Tx0pyj}hzpudlD=8e%^4o0sHyJkf6f8BjJ#k=PvXhe&$z zd5V1Qbp3kW`f^#9`aJvoNkQL)CDHaQhztAM#`0QU7aG?%UXAo48t*t>jbIuFIbMxm z8Xq}cjr0W?H#uI7U>Z+3UX5THXE|PtU>bipUX5THmpNXIU>dJEUX5TH$2ne&U>e^! zUX5U?Nn%5|zU%MvUjH1^V?LNamW%SBoG3rm3+sz|K>eWJHk5h2oN1ny#h3u-&tM(# zImQsc*a8@H0Amr9lDG|t4Z-mj$7LL^aU93-9mjq22hdMI{{j69^f%BCAw9Ef+D8&O z@j0f)d@z437v(`YQGTo!)))1F`a!*+Y(>D9((=z=>zL`e=mf`Q^jj7VX~E;5q$wf4 zg?xSaf%YokduPpWNf*a;({mQpnX5_xzboeF*_b=De6>*#*G1WHIgorc`AIl~z5)6z z(^gEx{39OA`Atf{(S1_y$4VMpKk7b z$1fb$aJ<8D5XVOxH%TP3-ky-0k2^W>Ii|;aFn=r;F~yU zA9~aK#f&z@>vdAx`Af|k=8)Yt#pEZQb$^UZw`Ec+2+6Qpk(GTlf-o@vb z9`nKcv0Rh~CFfIi|;aFn?Z)Vmr<+qCDJoO(*?^a!OnK^n!gpQZCLJQ9me8QE?{! zWOmoXN;Fo0u0L!jf64hLvzJ9!UtVvQc1QhCdnp%4%yd}mh2t-d%bs7_zJ}YCGUxLQ zS&pSV&UBhKF|~hE!toYF2doF~Bkp(MSl2*sT*mPl$8j9raok6L0R05?AJDHre*^sx z^iN1?w$;YfVVu3-hEb~XzkY*ME{)j@ySj*E}|Y#KO43+w)>{B@9)AB@6QYN+!5^U zhK?f}?6=mu;nfG2W1Gv)Y@{xtAGAwePI-=Y4DB1r!#1<#4ar_=B0ts(>x+6o{dn1= z+?1HdYfWDyToz*_V!T1pPf}lejxiN6)*{AW#Mq3b0(DO~6XF%B~|AfOV7wN7*K4;Y!gZXE9{bYT8 zvF>SbCjI2(bSC?qUO%LNj<2HaQk=b{r0ux;k{eHZV0{Z~FGG4&e^@Z~5$rqIr?9Uv zmo`)EKG4;AyMgVF{Q~<7_9HK+^sj>B<0GV(WE>aUg7w1sq8>K173q9tF30_>Z+G+q z(LY4L5&cQ@GtvJLM(xIi z@~`I=@!YcAXTGuhW;@Q9+Lr4o^<{g;c8#B-edE9TbQ=3z(%?9flau;8BjfYu`L$r| zN7%ox-~H8|Tz~&tv|gX|Q?1wE9yci~;Q9LTh4!sV**CfWT-)+(!(Z!ho6=9x7HEsm zMxpIOn})UyZ6Ml4w3%p2(Z-_fMVpMWrNl|!q4Y(9ZTDi#*5lm=ETU<)S<&C(4iY!up~fP(P@*jmV7h7mA5{$+y77 zz2qBV;$HIYFmW&WrkJ>wd}~bHOTIxS?j_$Q6ZevDmWg}Gx6H)77t8?|qw```Pzpj^Ugd_2czyI1SDP{*G_6qTf3-mkz!S z>%jeF_IZ>W-oK4Fz4vbgd+tlSc>h-0D2b0suW-MX=j<1=-^uxS|5k9*Nitv7=R9B5 z^n5-H+n$p`0jl zM$G!L^xg*Z0$;8?_kS1c%N6_V%N5LhX!f#SmD@ZYDRz5#ok+PJ8<10Q(e*RVp0O&2 z_9LYa7I)qxGN5dmz*v_wSn@}nAaAFwkUL%_jkjHzextlCuI9|;|H{;l(#57r=Z8>v{-=Qa!e{RHtanc2<+6;u{DQswg6U5z zzhE!FVBao+i~jvD#wA|wpRioq4_O}12cLgQenY*!zF7A(nEa^Zu2S-&k~>Vvk4o+~ zB|j>;^OXFkd^UxnRzBZECClUQfzeZn((zB1M{hjTD zVDzcb*YY+=(x7kVeNOSy$ZjP06cyvxieoO0#W+Ue*o|X4j`ipRpl^Ua1Nsu^W0ZBD zglrw}tr#}uw0_I+P6gAtF2_3+OzXWI?^Napv<}SiP6gBYFvmO9@2Qj6r#_9ewSQNz z&r`VJ%M$Em5WEpShz$4~(_=oEKbDK~c$xLP^+bNG7uFZ`fcinb73Pz$Ufs`zevA6C zo=c)n&oRNCdxAYDMGu~f^G@7?&(;3pnlSrW>~C>u?`KIL!8x6uLlx*dnfk?F&S56&C-@xa1(*+sk@QV0 z7v(`YQGTo!*N5BB{oXYGi)@=*=l8y->MB{c^fpGGdtX#^i|d~(*NT4AbzaHqqGGqv zclG&LmK=Ru^nvM5#_J+y>FKNJ3`J7ksX$1Is87C<@qL<%hCQte@gU^&oMpb zgZX=&OIaun%8Bx0y>fCc#`-dcB_Gre%dI*oD#o%<2Fho%>9E5+i>VHYZl&*dT?zKO zGMol&g4dNir$4bgis_$;eN3KXddvs&$8vq!i42@yhq~{eoWgof2qs-6dnlya#0LJQ?UMFN^PJ`s;oJ@>isoX; zc_f;PCFhiAE|#2MqPbXdt_k(V?M_+vpEP*GJuqzJzk!(>!VjMBu>a12@O+2oJ&bw2 z!}A`-Jm2AY4`YrI$MYV>93zg;k$Ie}nAZ?A4X-WeyS(P0dGcC>mc?rnDucHRl4og_ z4dpBPul+dxOygon%X4MFcjVkgCV5y^)lV8s zXXYtC*N5oN%>-k=;5b*@|2RL6f5rWhF~`N?{>qr+WpO`d%yG21e>3LzTC@funB#8I z+KjXj$K#?k8^Ii>i`H@kbNnt^;}Ohpy=d)6Fvt6%H6g($TV@;0bsDH`msP*e%Y(8B zrnxZ1{Y&O@Sss(d8Cnb1cmW%&Z%NB@bGxk{WDfYTQ#jz;OECXU^^*ouJbdP-<+O;s z4H2Dt|3>oneZ-eF&Q4qLZ`F@w+adXYuk7=Y{Jp;=*xL}n^bXq=!RTM2-&vaFLD~KW zHdKH9FUOBNg8g_T*pE|!{rDx=k86T?ZJgJeIUhd`Y8oCN1^aPRupdta`*BvVAL9g5 zUHG?P@6QSLex6|dyHBUFljOPg7X|m3Q;~dTXAg@xzHok$C(5=7Z0Vg1&g=N}MS0F? zC4F%?ycumpB2Vy1+02t- zAF(f#W}l=K%Eo=ru+fH^+2ujmii%5m?r>I(yY^*nWLnQGZSt_J zIxeKaRTf>I?0F-mb}{t6@T4&REhpzfom*|x4*PsKuVRhArBoiN7uGQo<~~j5BYYfl z`j+pBuG3j3n0~9z+8VyQfS-T*%D!gGg@+3sc0fgQ{5hu!uJ+yY(V3SF6#VGKzERHc z7YVNN!-U+&hPpMYgY#d`AM}E|A7a%dm&PmGjgT~_bXpX5Z`@Dt(iS_|rXO?`{No~vRX(%??hrYHNAh)L(1 zhv>hsJ&4k_clm!I59;b~VAiqdnZ_MHM=iLtoo6e}vY~z01h(8Ke44+D`8|2JH2Vp~ zSu4Zy48@!eCc5(dLUmrG=cU;3<>!Vmm+t3`g8f`lWb<=O!G7*3*w0A?`?;!M zKZg}uR%Amt3&Doe#Q&+UQYhxOy|Uj6^*O!6_X?)`lYGkhzH_ncXV>>Om%Xy2U}=j? zV>Id3o!6Iv-`}e3W219~IO2 zD8Y0-DyH*Mg6VuzKAn#eOy{F=>3o!6Iv*9$`6$73J}RQ~QG)4wl%excg6Vve;X5R` zTsj|R_-;wYbUw=Pos*2|e3aq4C>hiFD8qMDGG{ zXCRR?h{+CfOaSQvrQzIQCjJz29gq1abu4UeXj6M7nPe;EIhV<0>)7|Va3)`!IayNQ zP#|aUTaVHp8|$|yHVW&4xFk5Xsc(WZaj7)RmPzJJ&r9K6%trfZDU_4#2g|BstKhN*)&21$z6lOC!)ZM-T3z^2RqyEKt z@_%{8-_x(`sc9Q3Qe@(E@M{qV|LpjsnQn)Y4y0NThuS>yYMNX9YFPQ7W zb<3K6Qc~v`a2&_|-@^D@QnImr%Zh)psn`OZKgt>YEx087lfNrlCYdumFV0#$?niH~ z@q*;Es^{R7v=P3sK79LSj6;QEcgt7T@}8i)TeweBGX4_DPd`qcG#KlGcyn>AFgtlx zjjz;C+vs;Xo}bK79Y+M0X4x{yoawpum!w`r{XQMXrp;w1J@-YP(kvUwxe;tUXZZKu z!o{)GvzNWH+4ogFf21y@SvHh24KB<+gf%E;G5?IS?)RoK+62U#%RUq~#{FGCsuam4 zdPaLvSbcMHlGu71Jp=FaDR!U5aT&j%C=IeXUX~4iV^gsZy}eQn@NdB-;cxt1*)qwT z>3LaMTPQ1X`aZ6lG0K@t&kOIfC37wp?FpW3E)BAkC3|vKjhjpH{N?Y-mdS2pdS0A4 z0^JS0pZYeN%Ll-ISDIx*IT06S?p|15$@aOjo7=VLwqtv@+4cxL$0X0PEUfv=?78@d|LhfN>s5gKVk`_nZG;_?!sqf_QV;nZm|O8efw$Z;G>BuD2o5 zcZ!2c;X1IT#@2czxU9&Trtf2#!uncC?JHq_!Ec{SgKVz<7vA?V4b}y5w)-QGjeqyt zS1FQ>``ZS4(}mf+a3;htPyHg#L$O_%FwVsg69;1Uf%v^_ox9jnd{=Lmlmq-*aA}q; zlgyc(7iW&JqTj>3&aXPzEO$teoJRFrJlS5zs%$9dUoh)~>!5pfe+!qk?Uf9GE%T_z`J_qkVx!>8pixbb=;C>tK!;vhT zEe@N;p~Zbfzh9{PYP?4#`((7=V|kyDb-};+-;C)e*}wF1%5yKj;M-eu@qgUv6q2CD;lJf+9|K9LZJbw`Er<~>0eR{FCexF{j zKW`zpF#Ab4$&SCiU5$hb!ZQwZoJRd;GHrZZuUWLzFXgen7OR_cI(YY0gyPoaw zj?Sx;@OZbqw3i$E*5lBQa!%!M`z9i@*w31GL zr-B}W9s&mf2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI z2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI z2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI2LcBI z2LcBI2LcBI2LcBI2mTfZ4CpOjQAUWR>^Kqh5cCi@5I7Jx5I7Jx5I7Jx5I7Jx5I7Jx z5I7Jx5I7Jx5I7Jx5I7Jx5I7Jx5I7Jx5I7Jx5I7Jx5I7Jx5I7Jx5I7Jx5I7Jx5I7Jx z5I7JxP>=)eNlwlal` z>(k}%d;C5>N*`%@N@g@4%HL@I^xJ5;^mjw)Bu{$JsGO9a zQTeGHQ*ZiP)45##JYwwA3-;KW9C0d5l?qq{n>}yWdHgnE&nH73}lme7TOH z?MM%$q3u3;sgCKf@F;0(#5>)zjj5e`syzSjpp{Y6`+5mJu~L5Y;#Y$T;7sYcy_J(` zFy$XZ{s|@-VwHi)vML+NY(f46XG)LUPJ=6U7-MhjS5-KVc-^c#+j@MvT&|PH`HX!U z;XL9@>9Jp=!M?th%R=mRBF}x@1$%uKz?sr>zTCIn?@eRR2hE?kA=q<9u;+$g&#?kH zQ+m>gAt@w%8caGj)LyFp1e5*^wU@M!$I^B_y|yo>7n~`*mw{zsJITKb#hk7v`V8sQ zb1&#B=qhj^a3F9Xa3F9Xa3F9Xa3F9Xa3F9Xa3F9Xa3F9Xa3F9XaG<0(@YbPco4!AN zA?wG8`wSUoj;L~zJU=&ojA`{kMTZyXnMog2mNn@{kB&4iJ$PKqvexW>u4z2xX~AuK zbum-E-AdNK7t}q%y!%l-!9Sc;*F0Xetzdd3*{ejH?Q%c4>J-y%#3F1uYsV>Q0C1NaV)y}QV!;dtQvK~0HmTCRsF@o1@`+f9kowEd&d+yHY z&FzN@uKafO=&aqw2p;*_wexQMIZyCwFXqONPaY-skzXH=|FyN-FD=Qku#QE=y!Who zytwz9lXLj}y8njzjkt$QWhHydxaW*}(YV*a<-ndW?{!Q2ayj#x-%Wea$zHc`*ryka zdpKCfvM4{+B@O1j!hB-=AZGqDkNG+CmwC*X`O7?J%=~2@GiLrWj~O$6na7NozszIC z%wOg)<4m$;yIi(~+|OAC#B2}PF7R`*ZHD_lW7G-aOzEj!mR^&05o1|wci9ed{%m*I z{xW8}doI~u#%y=l{xW8}%l4Ns+g+87?JnD2e$IB6?Jwh!EDP&cRE+04@Z1MgA+fQU z`(O^9E8+7pQul1x5IR?~H|rMbSQh1Hd-(kqAJADN{@FAxZ_mgbdAH*v;uT|hMjfBJ zNOXS1kIzNNKQ&PB`EOP<%X3Z_ynn|ArcPZW_{N{xn^)i8T`-Qnqo)owb9y}>c4NVr zqfNg>`wM2-URiLGp5;k!w#%hD=0klGjN>xlRyszbP7r5GPxaz6N~-?^W4Tnv7<3zh zZY}86f^IG7)~atqy0xHNtGX@8vbetAf6+zTF%_nEzmM5Dc`qw-m59R`tr}lw)>L91TSr|gKhdjXThg*S`>G0+)wbTOD>I9 zwi_Y%;QW{K2fZ*>aFrh>77{N zkh$&23&+?QGs=q%+4g_KY|}fh7d-6dbL@jdmka*SF2~y=YFCrK{A0O;Ed3{#o>}^v zU`iX)JAx^XnDP=#dB;?SU@9}0$`(wrL?n}7k})D#1(T@BdY{+M^hCO_Kp zT!k_D(U#{bjB&gsKRV{Q3O^@5I_9|w;{%&+pU8~$;H>sGMWt>BU@i#S$K>zf8sTkoUk zeSZ|0eLofK`>$Z%uLb-5F4)@v_uSbB(V@2+g1tSFw)S>Lc<${_#QOJkNwBw9hM#*o zCfM5q!SpA#6@vdsb-{Y2!G3HKJtOvGqCBTL3Xh2nFV5pJQS?u96dn^r=QKy*F;Os% z*M3YCJ<}Y8$HW5qM>(@yuJ;)%m8rgjU@x;^?@LI1Q74EqrKfBS_!|kva=lL_Wzigk zeL2B2M`2%1FwIfemlI5L6!zr=`?VLr-j@?ha}@UF1eau4nd+P7x%dA?W}^A5p&J|fu9Qw00@i(o&mkv8@79l?GcB-qc7gxh}J6j42L{2WBEZ(GC9 z=_hI5vR)UgR~qc+!lGNmehx0rnb*v3RuuD^`OTPl&HQG}yk>qg#_^iwC_D!joineQ z-<&3sY}qc?uUAN25aT%R*Dea^1oe|CJ=M!l_2gZ|Se9SIku+?N*)FqA*dEi`kzlsR zY?t{t+hexNjCuaVHjA-eI}*(HnC&t@FUhj7jzz_Oy-{TL>yU!|`lMjLZYkKWXA1V~ zoPz!Or(nM>D%h`=3ij)$g8llcV88Av*ssS5hy6OOV84DVn0+N(3&r}D^}2Aq$X_I1 zkbgFf{o1?e4Y6PIm*+G`;WdB3G)Lhzf59|I;WdB3G)Lhzf5A9j`!#>jIn7ac%|Frq z#`YbuT`teb*pFxJAjWar@0Dm8-g7B{Go>e;CwoJPu`Hhd@mz&v@OxE){a%$|zgH#L z?^OvV-SSxx(V^d~Qr+@imEe*ri|bgF{X0&tdzTmkAk+B=f4)NM?$2EaCe>FmmLKbq2GbbC=M$vvhj;9IvVW@!1SX zgE~Q+DLvK8P}cmPo;eYWW%0T)&q+9qKkFjcpLLNw?$5di_GeuLlh4LyU1W{LpLK~i zAAiDMOfF#gP#v_&Qxg7qqk@)K1Odzc1O zU*YqOq7%f#Up{jv&w1Yu=G1)VP@eO?AIz!w%%MET@t61gc<#X*=6ye%Q)iMb+vSoi z zH?R38nEYSEzCJ(a^F%zyV9e)CCx|np$2}dySeCD&^nI^e!Ctq9_2YFb*y~oX*R5c$ zTfttpf=jY2;!?7ol?HR&c#gsUFNw3al)~M*rUE z^NU|--0G1(oAX%~JLl(fbARsb@N3sD$$e|hf%1H(Q))$D*(QRIJ-=@B=V=~KY!F@Y z?E&)qlN*~xBgZ&=^uKyU-F9mz&(CRfSu|l~eZhUE-X6X6+g^gNT6$;n{{9Y6ta)$r z$QgUe^TSWOKRS8B9)fG!F)w=b;u?ZiZ~a#E#;a8X|1$2g=wE%e6P$Cx7tytcZ!37a znk%EVRksnm^~c{t@2;pM`0Ur$MK|7*Be?B?iss4w-^E?(&9j21&fVSIdh&yU+t=R5Y{%Zd7!!P zge?TWHSj=l?y*1Rv&?(UInbDIR|sz1y1BXZhf4+T^=ospWXPm>oMzSg&CMBC{N9T3 zCC@iE+kIF)mvR3Y&CPkM4;FmS<;~45TXYtD>0!;xrA=QId}__6CVskF#OZHr)Yw#Q z+*a^_hZ~s=jXDT^rd}h{vi?beZ@#UenN{-)!MRuNYfjkhQo+YQQP(_q`7MI`)vjZf zwwWn-=%KYueEt)H2OL++{Bh&I1)q9WO*8)KIfB1`zN$H>?Hhu(x^R1Q!pENou69{@ z^V{H`1V3_2In%w)uY#9svz6)b!ta8oy|jf{+3OF%+pJz4J^DZe!*#jm(2t|em+m0= z<590h_CM7GA9caY(R1^55j=jt{OH4Zy9&Oo%X85-b9NKl;J8PkwyWw0zV^Z!quu-O zE%?~gUjvt>%b@7&a{CKj{$Lahy{oa{sY=ncyE!e=PU+#~hxq{Lb8JpF7;V&vm(%?b=+@Ab#Q5srPaH_`h0%f6N^@ z*!9`N{&!yV&VmN={IMq*$lAPCr=36F)pEzxz~I z_n8eF#;-0qK+@kZd2-zFmwg0xd+){gi?*)qK0W2v_{b*Z!jbbF6$Op2x~_;(x6Cr+yJ@zo7mSYk#4B6l*`C{uOKgqJ9@^zoY&bYk#DE zYPFwI|FznGsb5>|*VNyw_II)aR_y@U2dnmh?1ojlLH5L|Js~?|)y|Opv1)(FE?Kop zWUs8+E3#u&?HJiNtM-lTo>jX?_Ry+5Bs*!`!}vcp#GFxh9T z_L=OqRl800+^Rh%J8#v_ll`}9|7l#XIxf(7VRgKqam4C4LgS0o@rA}6tK$xhM^?up z8mFv|Q#5{A9lvN?vpTMkO|UxN(Ku*z9HjBl>i9_Grqywi##5`~DUGvM$5|SGV;z5K zT#j{Irtvz~@tVf*SjTZ1-(wx$Y21%>+$Vn^R)2u}gjoFq@*iULAIPtW)vq9bBUXQd z{E%4v5b{rA^-sueiPdj8c4C8A{TcFeV)b*#|B2QAA-^bJ{UY+0^3`7=KWd)(Q57on zo7;{0J@MFwn|0h?yP zrWvq}25h4N+i1YX8nCejY^(uWZNOF=u+;`^z5$zWz~&nmI}D5+2F4BpV~~L{$iNt6 zU@S8*mKhk!42+2e#zX^SqJgp1z}RYFY&9@O8yKSvjM1jTBkkEwW1qyp_-qeAWg#y*W`cO=0HhbfBJ~{@EYPz(!ZaK2ft8Dp1<_(FXO`=+D0(_w)F3a^QXUC zN++1!v-G}T%Fj~1?C0=1_JwDwiA?@E`*p^rXMaZX5$y99?8~JxI3JNmu$NP?mtXK} z*IqE4%j5K1K9|Rs<>K;uK9Q6AAj9?G^7uK|kIQ51>iwi()(4lz&sk4gp3CPTv*mr| z?uX}6U!OjLd<6Ua1^aT1%jZd!N3fSuu$Nyj&#|>k#NgL)`{ru^_n9n)~;r^m?8RoyvWw>AHT!#Cd&WX4m>70oB zm(Gc}|LWX|`=idSxS#6WitT{T(YRmh9F6`B<&OOD-g;q|Ra4?&%zs?V-+L+1~10nC+*|h1ss^T$t^)&Z*fB z>ztbHv(Bm6{_EVF?YYj)+0N_SoW~KJKX`-r@98h_6z*4*LVTw!?mcuI;cNqH9F#SLhlM`y0AO#Quz~HL-u9 zYfbF8=vou|Ho8v5K98RbAr?IQdrOAFY#p4%i~U_s8y=JH$V)xwhpQf4b)t zTl_k=?mCBCRKIiH=pP+UnP#r$L+KMtW#wwQlxHi=lgetTWu-~8WZ76V_1$M=Ut>_k zp=R2bF3!eXpPym=m|ISG{q3wn%tIXx6x_V|w&sW>E{;c^lOKyNn&4x_T)j5;<%;eb z=bN@&nBQtk zR>!#`?3$g&%l^)lhxNA)PJ2V}g-@JfzaF@)w8bOSbM5&*?Jv0IoZap09o=0P_jF$q z-&el7Jpb_BnQ>*~+UT6TBjan1870q=tB5fTzKeNcSttX_hB9Makn;oYd+xARzK;-o zS~2qcFF5H_nchW?Ato6N=+l5c4d~N=J`LzI0)0lH&j|FH^hfM>*)A9Bm=bT4+w|^6 zpJQL1JMq)}PW@fK{(a4_`3q`0-20#k@yu7o2(OBozQ%b&?9;x`@?@WA|E>jbns-}F8e=9NwSCO~2jbP=<(Z#5KPl(O`sa@_msC1T zbla{n#YO4#u;AC5_As|M_*L*OS08Q0zgt^mJ7jJnGq6G{!M)Dk-n8v`vfz>B7Dc-n z7w_WVPfv)d)OPVM5NEqwtYaFC97}`iF1|l{d#U>#bLQ#~b1RN@TpIh>s{C_WJKSsG zL-D%$F3mT0Zf!?=;O-83sn@}F$UV(OSJ!@Xy8W|r1;Lrh%|=6eC%QfP=AlKza!2@ zS(*9*a;)n0dC}J^9QRImU}$vbeXf6{NrQbKG4{0{cb*+RdWGwczut9P^gwfGH`1g* z{gBPfRhvn+G*@jY`V~b@KjFL6Y{PHd_r-{x?ti#_c95Is zFPhfAZvl*H@LkLk%R(7YHk29bV&48D8r%A8DR=n=pGRlj>~K!a715mU9lkmKG@9Jr z#mYdO=H1TMoom)TIwxlPiMZEkBh6J?pCZpIJep_9E$kp?pK6>x)|~nIC(@@DPQSn$ zSp5p=Q++4&H9H=-Sn%q;oz0P-?I1G0_wHflwk;13JZ@MmGxbgvv+zcWX0wjkAZZpZQQ!u9dTs@jKt-o_v(!)w{2KoIi1d=UDq0@xd>- zG|z2Y$v*YLX`-t=ccyhkTJPX?$y9DO%0iu-cJvtY+AMd!R^29f=Ey(pmUiEz@i4Ra zrJJR#?OR>VWtVOta?UvVF!S1tuC2?Tyo0H@z{QDba>l=-s}FXz6md4nLjEI0j(zgz zs;K5D7cX?1mS06ztmq~3r%98^4q#uq^Q7g`>36yQ_~2{HqWs@_Oa5unpni6|{PC!H z9XFRb|;$IYUq-y&{iZ$0{8kq2?pW2)Ly9ywl~f3fZIc*`f8{Oe{-jhnsc zV(-k$**5NVm-BnO#4okF^c!b0zdp8AH2Q8g&)W6uN1`h}c5+_Q@VDr)m2O_v`{+7m z_hv^+{)jORzKeNcSttX_hB9Maejm7xIidTJQf{jydz=3*b9m1q_crTJZzIpAKT_8` zxVRur^X}(QpJ*m^scgBQB7U=VAM@$WABg?@Q%rk>( z*Oor@_>UvaAEzH9eX8j_=b0L{W($6C-!sh-{niPd@M}ABYqdQ^=6z-~FkikE6~Ngp z7web?BgfLGOc>$TUbfqETQlc3xAszd#iP-eH#=TkHG55N{T-eCtog;8`TIZU z@G0}|jcfOEv0Ua3t6S4US7VZWcBDvJcAHV-}qubw_;YDbK{)9`5c+9bfM3_@?We|9tYgi}T;O$l1xy z`p?f@_=e-^c19jKYDchaI@bo*9yMrncilLr#=+C>rN+{-%i+BZJ7pCzwVnb`}m)Ycj}udhavR){UPUZT1{rSMZSG zd1lKR6U3HwYd_rFJ?%Pa-{)tZX;%O155bKVw=&1Q-%#{`I2&bU>I=xR{9}$cli#T- z^89;DC-dM5u79OTlgSQXUu$we2lGk)8j}CcCmdsr{GgWLG-*&j|K6pgX`S!Jpgt$I zFc06>MDoFLv#9Bhxbyb-=gBTUKjMRj){KW%ay)$Tmh!FMUh8b;l<)SBZs_J>f<1iI zebF@II63m;@1rX}ck{>EIW^6?{9{G7kEXORpPcICe5mJ1=Jvij$@80SAM@j-?+YIg zV;X!H^Te`H29ynD#=0DF$pF)C*2_}v;|C8g2kiEWli{oW=AJRH3jY1p{^suGuNA;) z-aTjEU!s>T>|xn{BJR_(wt4l-qviSWcegYr)Nd?!?v5v$8eeZO_|Pr;nYVU&C+2t0 z`{e?&(|Z#IkDWZ$#8a1uEj?{oo_Tpfcj;f-RUc^<-hPJ2`QzT_nv*}ATL5RfT&!an zj2ugYYu6fPUT<-W)NAY$UCs9YadX@I_c+WP@w}Vco>q4UbJ$8Zx4mTLlhMLsoh@BB zd%LL1b&kXBsyvauww&W|rgF1U7V2cLy&9N7M;mGDdDkCrUKv5}YOt_IxjCC2SueH zS8Dwnv!1UQKG;mD{-EH4e;j4*8+ef56+h>h1D9PR-%B>?HO6f5O=Xc8akk6FI;O$M zu{8L=wbqa}Vd4RXsY19-5tWfjN87zoe}biyLHCfxnuUCr(-I|(Ph zn|ZMLU*~3muiEkilk;{J!C(G(j_J15Cn8&&HN#Aen_bNF7Eg{bFZ`#HJb&)XJd;;{ zsq}rsmc<51s0#pem`*>7$1-rzF@ue*B>Q@wM0 z!PlM_nGdS%FSzL`rks@NiSJ@)Y4xn<;0S4}WxX+qWKRWxADj zccLwARoU$L=81;Wf4^d0bo2LaJt|YV*(eKjvaPpEIY zJ=0j;sOjILsyh7aWzvawrZ@P8Sr}n95IzH#tg!kU(NHg{E zeT0*@?cT*K?p984s}Y0DmTj%@IroW+%-i#O3f}3GJoCq^qeafa&x|#z|6Cw-?{WSJ z^FxPAgb#=@4Ze$cVp%8y%7!vyT?VflX1=U2Rmy#Pui>WSbyEc2cgAqjt@d?-S6(~Z z>^5U^0i5RD|88|ue1BzUClT*)W0m~D-mYG8%DUVK%Z-&jGHT5=QQL=x3vT_$vM9>w zBY4e{%BI2DCpvsfQB%-k8RC`pHyoHp)Vsyt3-+R&Rag#@4r<85gac?`^61COWlFFKN?V zSL|cD{(gku8tpoo(|+Ae@MCRged+u+r0%En8)a&3*}4GEMp>Eq0`hI-^Fz&y-nWT7 z2R$~-)W7lu!D-T9-$#snZP6>k&G5R{NS^!LeSw*K*cF1)q(NPsuzZvmy8K{y_r=bm z%?@!x!8mRfHGQ8>Rn2J+9xuE?{3yi%Skv}kd4BTLPNsiTwj~wA-ol9tcv$Mm4KkH_?p8BWAb7b2y&3)z96~JlU zU0&Vofe&X=tz;R`m0Yz zADrQ08sF1lOY?b`uJZg@imCAP<81{0?|{~3*>Cj)?{)R*=IL)M6u{Xo7web?BgfL< zQ|>&@eEY1M+tyq%z%*lsgdiOB% z`~4CzSMP0N%pbW84C74YW}__BNxd$|#mCNa?fZF!nXNwh-nIKmGcsDz>OyI|ZNC08 z`r~(JOW(U-Z!@#8Yim=lgL&eD8j@zg_UOnm|QcI&=f%=ewjiELZU z?P}USw1wa_X)@UX>}x|GIMd9%&+WIKvtJLh+tI&D-P5E&{d|2@e>0)}>+ly&`h`0ey8M#?=B*!JjF@}JJ#(Si{-?o$-#9eS z+;sIF!rSNf$TL^0m?6I9YZqQFYDr}is= zF%7HkXYBJ?RKD>!f}2OxO!YsH6I^~ub92iD2Nl5CE*I;V1|!GP z;C5r{n`3WrbK8q1b}~=4b#vRTYZ3pie?@q;;I&cavZoIfJo%YC^Jk;x!pSBtTwtoT zy*y&RRqW8y+`apcf-{wyjj~WD2VJrx{&J0*Urc@Mlz9Ac&XzW5(YMur-(9=E@V_BZ z$C=KS-Zo`LbjjOiOPiijp{_ZpXIsHHZFQ{q{>PdHa5l<9{v$@d?U8@5x%#MPBG1_W z9%??X(o}GoG@0xG_O;rVwKTW3asBa+TXN0GTQrpX)1*ONjlQmfY4wGhyH%~#$y~MA zaS6xGqNd-Y@mZ$f+wMCf#Lu5U#H=3RzDp`MVzjAq!+yfOPw6|(>c7M-nUj009&IYU zQCoQXUeBTC=IF~;3ZC_8NAv4mZVvLFuMad8cRNJte*5WF%;-~3D1b2y zzKeNcSttX_hB9MaI{#-|Gw9+|q};Y$wlhEO>hOxS+nKcwpDfRt-MPKFs&zq}=G_4^ z+uMds_KEa zE=Pr*G%*SlAia^HR7Q2SgHH%9MVxrY5?NC$cT@awDMbwk{q!i$~niNC&Mh&+Gu z`1*0{Yeoxhaby3vQ~z}Rt3}m4q9c~N=RKC*5&hY0sH8!h?Q*e>X)tmu4ZgensOZqf z&L10e@>kKzA30lk+r4|6qbj++(C(NHX6yEDZhQDG{md=rxw-APyNxop4sI{}ocn2> z>3ZY$^8IY4aZHO4N7+5+)R8ta9rv)+Zf-C5>vkWY_{+U@x@n-F>AYSFWeh^&oFb%Vz(wd;k=Iqp+|5rBV;X!H^Te`H29ynD z#=1;?{IlFTy`5h-Z{Et>>c>0WGljjG@6 z>VD3;716Ax9Iwu5Ue~m4>E^b-)j!t!>jgKro%Bv$Q{{bko_6t^k!H6Aoupkdm79&S zP$v&=+t=P@mWT|WYdf4Q#DN4Wz=JDesB_I-9FKSXFI)(-FI;Gz-x|6IBpg-J?Y#)e@`&=I|KdQKz}#T z-wpJ41N}XM{vJVp&xQV;5B)vCWD}A!WGj+)$%Z6(l5I)KBAb)Qu-8s)6WPc{B{E}O zh!6Q{8_8zotIZ@^nyYM3#Ccb5QPJE8lR*(&8sWyacOQg1iY)+&$his8iTSPX>sEs1q zWz=?+WLc;Ovf);3IN5fqww-LgRhv&^fz`2q#)w$Q2pT(L9XrU*&(kplaW=|A{v#$^ zmvD@1TC6sWY+b(Ex-@CX#wL9qG4?gG$@yxN$yVp9txl5$_0#yJd*?Rv{ygE9igDa5 zYI^ed4a_$aO!Gbi^GyTuO#}1I2f(8791 zf@uxG!g`2>^$-i|Ar{s{EUbrESP!wV9%5lVB!=~n1ZTV4O!dw5JQLqCJ*W9ptaDYG z!^S#?rMYbjo!io!H_|yT&4nYK3)39g=p32m&PM0XC0Q2gfz}YLt|8Fcg4MMJT63_v z=0Ix^R@WkEjl$|01+87gx^_YSQmktlh_g`^@*gqHyAzJloI2JyHO;kSoolB_L+b!Z z-$#snjn)KWT@#>nfLPZG(xgHCkk1*b&q=;$tiC9Y(M3&9Yt9DtI}%L$4hHr+4D5GA zu-_5Een&3scjUuwQb#I9FjI8b%(O#0(y(C(fwz|iJIL*7XCt_hgF2S^iWnn+g!hW2E{WuHz zaTfODEbPZw*pIWYA7^1dF2UI@H&cBxJpoVSVL zyiE+}Z7iI(v2fld!E`1kNkeCKl6UD0Pm(8{?Mcd_Ge3z8bQUO)jm`)qGGkrn42IRS zNpxn(>X{`v%VhN|6P=5&dd3NHns@1JjD_=H38pht7S4lNI1gswJeY;^U>44USvU`7 z;XIgy^I#UvgC#iIKQFMyJhw4 z7VQ^XJ=29a8)YH?5!1P&gkyB3$m*FQI%{P0tWlaYbjB&^`-rix(U~Z#XQJq=l-09R zY0{v6XwTj1o;&TuTiuJtF}kSf>C9~e=e-k5=dL3-@0|s_^;k>tn z^WGNDds{f~onSf>o}{6(;>o*ohCIoW&Xy--(V6o^20DwL$VO+>6Pd9tbRO91*?2lL zZ}rSPou#*WmY&Y#T0LWrIL*6sHrvAY2nnV${1(1Pu<$*Ch3^q8e2-w^djt#LBUtzz z!NT_l7QRPFaJI|MRNqX`Gx06cb2`s#^{hCZA-8&loX(b8JzGv^&SO1uzS4}0^(;D_ zQJ<%0)amScq-WPlvMkgCo#D57hM&&%TRq!PXa238`KNCItbPkX-w0U!Mu5H@u=?!) zomaH_O#$L;l!g39Oy}Mcj?tNRt7qEjth?2-?rGA{8T+K~BgVeA#oVq|&*alteXD2n z)1*QD(3wxGXFlmHsMWKe8;sGQ+cfFvo39AIH%u^n_m>Ob8|K6JhB16^7{m957QQ#M z@V%jh?+q<{Z)o9r!vxbeiAfszRxx>Z%`HunJn7rUq%8X8F_D43g-m3lZzL0$u`cvI zn$>SJ>6=Zf-)z#ioL0Z(r0>G4e&dNa&Aaq%U<}{GCYZh+r*24F&7QTnI@I7pTvt4ec`eu5biEo*n)Aw{%zg47f7_EN8NZ&SE{kD<5d9?b? zV|(*WtlvV?HHp9SHIlL@=0+j|#o|b0qZl2D z%vcwShhQ}}2*nJs8Z(4qiCB##LU9SK#u!1I=3RhaPV{}mLj#y)Nlw?_`2Z~`5YYY>LZDKXH3B^3I8uNr=p;(QDLNQXT z#z>*qDOO{r(D&L_W2zv|Mp?*z#1!iz;TXmAuo}~YVtrVR^^qnG#UV-hK4R=^6qCei zOcIJiVl`Gtnlz{%`sUs0H}CWA=v=9%_LOj3(XS>`?_09A=6W=mEKj{LivDzqxo7EU@6x+>eY&VMeW;Ny; z#e%aM3yxyMS&b1#@!VpK9aoZNp&lrPUaT?nD7Id#vGpkCp4FIp6pPPlEIx|SXEjD2 z#qP5jyN}`pS&iw3I2&al{}EH%xrAdBQ_gBkIf^xBHP&33G!)}5>HCPWuTe}qt1KNit zTZl((As)4bc+?i+Q71UtgEDCcb5QPVsE5#tNnw!d7DlQ*2?Yv4tt-u+^Bu z6pPquEMkgLY&AwP#V)oQySOCFLY+_y=Uk29OtGC~jqOY^pJR>rOtGM?#)768(N<$b zQ|xG~v7;$orPY|yh_g`^@*gq9I!-u7F^#RpG^SX`R%0EfNkcJ~lfI7_`x?b$wi=U} zVl`Wh)tn{`>W5-}T8;Thu|TcH0;QOr$rxSK^c3^o!hI77rh6YO+&5w2z6lHWO<1^Z z!oqzM7Vev{aNmT5`z9>hH<4hvlOjn&cU2_s(j68_o^-cGQWo8Lk;p)IVI;EA9T|zt zSQomF!0O!`bZ3XvJ3Htu536^1(7gaw@AyER=3TlQ!oYnf38p(lBDfDFg8NW%;Xagn zxDO?U`%vgU)8sxB3-_T|xDUm`eJBaecDb4Ao9THbzGZq&_bFJttAg&ZuzH6D-ECp@ zZVS5e!s?wDbQgxzyD;dE46Ao!(A^nU@6IU6vQQ6nhe)J%h|t|4xq7z<-8mBLog;J? zNvwB~&>baK?x)Uu)LwBVm@6sJ=NuG4KT2j`0T6<9$ z=q|QIHoBuNks0ek_hDJR8;^C0 z)jQN)e2&gb_`B8U&NZuduF+j=R_|h?JKC(?(MET-S-rchB+EiQ&>eP0@35o0?IOL~ zj_$n6)jRL#F1&ob3yn-6J-RWlaPB*&i z&FWomY0}Ugb4lMvjD3ynq_cV_9oXX0C? z=X9TJtatU&9lloY@TI$bt={cRcm7(v^Ox=dwt5#Z-4Sf{j$pbw*y`QEC0Q2gf$mT? zdWSOIt!(se<*nM!i1f~7x{Eni?_#Dqn)CIJX1cpM*1MbOzDTQgIwQ_TS;&9HbnkG& zF}hPY);opiuHjhk8cvgj?l?~RK4R=^bSHAGcOuhW$+6y*oF)zGhwj|8dgmtH#cA~} zP8_3)n!d%PF?QlnE=~yI)!*gWpF2M(aYg#)kFu9kIxOPYU+pRnwsSf?Eco@NJ?!lb zeigjS)koX$@76Y)=8(CK?7#}G1ot|Bd)v0>$%03gTNLkV+&uK(Pfv)e)E*(v5n~#B z7xTojPzIC@WyZQpd9qKuf7gqo+}RKHkCzz{KE-EXYmZ;!8+|I>mz!Pnl}A@09;WC5J*a9-3% zb1UW9y;nXivFtLHn~kziC)a*+y7{wn1(EHgUI&{Y_cRmy&7E7D5g(i?xYxpmqILBL z3m*H}s@!v0ySARW`osK+V;!dZ%Hy|}x-^KhQ5NzaG4k!#yH1NAXzsYztuKe0T5y_|x*{DPOB{^)cr zkMrU3xje=!7njGFevIbB_2BaOA=i(~V@!WH^h+@7gUjRRtS2syG3)Pw8(QAa$Ul!5 z`}Bf+KAe~4FW8qWnEu4_2=;Oc_VQ~QO6J-tw4LKXS!_Gzf%|c78F0`;;6UI&;6UI& z;6UI&;6UI&;6UI&;6UI&;6UI&;6UI&;6UI&;6UI&;6UI&;6UI&;6UI&;6UI&;6UI& z;6UI&;6UI&;6UI&;6UI&;6UI&;6UI&;6UI&;6UI&;6UI&;6UI&;6UI&;6UI&;J`nZ z1FtMtw2yxK{Ak^VQMWGc+vjU$J`inj`C!X!zkK9x(QEH?7u>D-9_GpC+6$iF+n73A zG!T44>(kAWz7+)z`gWjM@%6Lvz4Nb2FEYn$*x-#+j0?m4FX_)i31bL(;Ds+X%7PJhBh%}lFF2Ma#C<<4f|?k5WV{r>l( z9#6U05$*54Ji6`Q7s&IQwq2OpYNm@JaAu{e^A9@9#g2G?%+UCl8SeY~?S{M-Png|b z($~IaJ3DKYi?MLXipI9f>ciyuK{Y$rqb9ic6${SlWluZgYmx2Q9fsLP&l_{t@Dwq2baq>eMDjkI^Ydwk6DpH%ByyWQ6F1mE)L8TR1a%3FS3@$DcRH`y`=NNwVXiGIe%mO1zP)Rs1DkH2v>jq>(~|g}ee9T- zBuDnYXP^DVvJ#Cy(ChgF>-&0fTmoskY{VbnGTe`gK@f1zL*PK*K;S^&K;S^&K;S^& zK;S^&K;S^&K;S^&K;S^&K;S^&K;S^&K;S^&K;S^&K;S^&K;S^&K;S^&K;S^&K;S^& zK;S^&K;S^&K;S^&K;S^&K;S^&K;S^&K;S^&K;S^&K;S^&K;S^&K;S^x2pk9;2pk9; z2pk9;2pk9;2pk9;2pk9;2pk9;2pk9;2pk9;C|M5tbK~KH9(jMk|AhKFMf_v+Ap1zZ zjsc4z!k$^#FLM#bUFMUzt0c7{DNKlXJ_*`{xj)Oo>Tf*)6*+f^P&8$ z=1;$^mP>!PTps7|<422}zFh=!dr=H;X|K?BPFH2I?LK;`j_I-RC~51RZraAw&OKG| zhX<{Un%>t-@QIc3qZhv#Q~;-WmpMfIkayEyDl68qNQPKtAla6T2KThu=N@z0vlrZhJ^spAQ>q+jX2K z`1LAh+YcvvDLALvakksVyGY&N|D(Cxe*1$2FFJ1*d(mFU2`=C5%lM!=XA6F0&uQ_R zQ9}h&nK75mWg*5i_%7y&WuXix8_JAz!8&5ySqJoQ!}4s|XY#zaes=d;oICl*c<#}o zB$ z=bR(v9LC6BwQ9Gw&hhrWaL1W{<~u#lGiTmYtX;L%yWUk{_wL=|eo5R%(ZB!LUy1uJ zaX+T)Kd~Qi|0eG1*f`4kl26!CE!8Z5S+ zP_cFL<<+mUsX?-et)DYKtdWmDa#ykSHZ7%&+_n8p7q;Gh+;VqWPQ-LOrCp-!nTowc z?KMh2675H$^iOF28f9EU$7N?0<`1F%$cmqY`Y9{^6Y9Ur?!T}-HOrY8BfU1C5U(u6 zD+}?05HASvf)FnV@q!R92=PL#@X6`-N7l7r>oaZF#>?!r@v?rj@v{E4@v?EX@iKq3 z@iITP@iPB0Ui)QdmTBV^c@X&#c@y~*c^3H>^CISp<+1K|*Q)OA@+}kdE9PC)gQycx zKZ-x7D^YKv4*#2cVZ7A-2M^Td2S2p`AH30VfAC5D`N1>w^9TQ8Uf5pg-|~gJRqRpE zN?%%Dw`(f`J&bh&?PyPD%%h$($ z#2!pPzZI4LDf63tZQ^SgovwbY>Hpx|{n_)mejm=)H9Zf1G7pF7exrb2^`_-lU)uRc zFxyjs-&DKokM+~__y-R}wW;*l2EIFLu)Xva&(dohzihAZzHc1)W?x+@?S3iKpkp{W zx+zh5VBJ`g{d5qSLu+mjq5&O()MO?nwpbq97wIUIN+91AI=Z%y&#Ru{A*K?(LkzqgKKYLsnlf=egKGT>~ zEH;K|Od1v&!!#zD#l|p=NoKJzOk)BT8^bgvV6ibwV*(Z%!!#yfvHd&#v&Su6*agPz zs)hdKr1ymjS%na1bqRt+7q+55r(EJ-^po0%8^2Y?{rm6uFBq55aWNL^3!y$Crans4SH#qJiN=7K#^gd{Lri0p zY0QWz2QuXXG35p*M~EqBKx6m`voZh7aj8aRt^TQYWNlqgO@X#vsMbJRM^uBLtuLxg z(AFK*ENJVIY8kY3N;MAJ`W5kCFfN-nP-C~N`jX(xj)6+WKO1hPLk5oT05pHfLz-l+791Iuh|;FfOZKVDlC8MLUl%AGPxv z^Ibddv6!^;A&XTzPcja)^C#m*JFha%wDYZqS*(BNxNOeQt}krP(5^dd&d{z$Y|hZG zQ*6%Au3v1<(5`E2&d{!RY|hZGgKW-VwZwQ6@n0}5TbD6ktR`4(Fdta0u$p0*)ex&C zhFNW~8e^E%9IHKsSuL`fWSG?`t5t?s?Xp_>cg*IhzhGR^A6#=4KhYn>f5b{$g!!q& zi&)_SvBD2x#s8nM67QcmF4GAxKNbBTR&<3}(Hmk#hlmw@B35*ZSkW{3tmy40tY{ML z|BP{!TE_mBdPl6x1L%)3KOk1-4b+%2pGb@oWu8H-%s+&+EAzuo_%9fj&BGXrGCw0$ z=555ve2!R|=MgLOKVoHFK&-46h?V*LC(OqDGsk6fA=L_wtDG+oE9VZx%6SB_a!$eA zDd!i&%DD#5ILdhk&p2!@WHrWeC*r?g+#mZlWuJh4D*FeFMcG#%R`wf+m3;_eWq*QL z*|#88_7y*2R@1D;SiFDIxNQHX^@r{25G(sV#L7Mpv9doztn3>REBi^r)K9k0M4y!$ z{e+dhBHAnaNyNW!T*jNkcvJS_s2^p2j=ECz?dY4bpGU0h^U)t=|BqNX7a&&l?LT29 zUw_)Tw659t2**{|BhP&hzZNjPpF5|JgYjb4S+&cD_bT*9&&;##k6(>T){>tDow!MJR{ zLD;yg)>+LnO!q~=<^qQ4ehJtd!7$xN0h>D*ru!>ka|*+B-vzAZ8D?`2n+q6ba}t{) z{vETq@Glrw^anMj_=)}~{v%f60_LX@FJgrU#0o!%75{(2O1yvCxQfnk+}vPAON7Ps zN3f$NOEv5OzmHe;%{a~aP=4QF-S{DLJ~w{f!1U#Q*=tN7julp?Ft`oo_k!*ntp-U^ z&9L3zeruTTXN{OW+e6(#JaKLiRB_*eyvZi9u zLK%3wxhrCEzNKwI|Ay_<7U(sYJ8=zNQb-Nk5;kET6^v`QVuQI;u0^c$3ICo)#RqIx zd_$~@hkuIyl+PdcH*$kTZvP0TH4UsD7|*n(fz>v{w59=Tn?hRCz-k+t2loY5+YHm1 z23Fe))0zfW+YHlxetfTj*0juOn>Es!mRW5xOlw-hYMWtN(-Ny~hG|VpthO1ZH7&8) zW|-DAVYSV$E`I)ru~6Oqx9h&H_J6569rplpW24NIgz>4&pIEcXyoy+vZxJi=Fls}Y zpHUCWyp33y&oM{JJdaqJ{}C(e0%B#oK&-4Ih?VsPu`*X9*2T#`I2OYASK`VI{vUbJ z#gEv|=4Lj}vT@m*&E{E#|D~qr9M9%i*3RaBHit4y=NUr#LQLmyLg#bTgMx7mQEVjP zTEuMK(5?~6ScKUqJ|I?nL#&IFe~SNNjJd&#S2m9`PW}jHIbrK7>xZqkTCDJi?SD58 zMSlJ%{);-#4W=>vxL@~2Fsn;#&9b`G*0QLXzZ-`lKmRcQf13A{SpK_qU^!rQM{WMk z_*d5i93h#LD>>v2rd(OsQt)WyH!k8nJS|MojOev2!wSsY*BglQ zYQOwuEU|0Q7_WVOIi7fpF+^-tS4|#&O~rcmxThvT4sY=Dm%Q4W?u;Vm{6i$>XASRg zBK$ShfVLK>=0RH{ zd9|mt3EJAEH4ECBrL_#&TBbD%+8WQRJ)K)XJGam|2efkzor^#_7tuKfv~yHm?JG^W zDyQ;F?MnDhQ}y#v zgH_vYwy8bq$w#c>VBhCv84(4$!tE1f=`*!bhU%yqqHf#K_d~2n-Cr{blBHOz{Sobg zK=qYB1AowV2x!h-!uDsU-C^G?{u!}|{|>$-%o+g?3h;MR6+NPsM%|5suixI-rZ{PA$<{g@~yd&$La)$tlqnf`Im*|&vVQIjezZ@;R+eNzXUK>@z9 zYfv;~1^Z<`KwJ|iQT*0c|lwNA=t>3db4|C=AwKQcSR>&QG+|MqJ5 zQg*-XphgAZ!XkGVU1wH?N&Ux79?(3E`Cw}O#Xn0k;$Q+is`x5>+q?*fPnaaHO&Xql ze2^zhoR|;Jl{U|?Dn1mNJUAzxp8GVt*tIwqn9ov<9eX0}!O8@f_Vu(TtKWdMH7|YW z=Yy~0O*>0wOpNIQ?LL^o_$e(i)KP&j+2(*e&i+h#U7Vpoe7kJti#`i7+XF68R zc-A-^ju%XlFYFwfew-wLN9C8A3*i&eR)1H+n@gv6_w8RLb;L0**jMYTJoG??jGWRP zpw692FfyfM#)OET(9x{~82r{Cqk9d1n0xP}yvqDu`ZM29uuWScyC0pMesWbjWIi*J zw})q>)v7Q;wzxs(vY=rZV|tx%8TwQW4n^&WIu~^)*23?vhJxYK zQ*xiH_tRY$c!BM;ukt&OiWy&fH-Il|9ihOO$c*iuZpm94`a*G&IsdYj9WOKxcFcb! zkFQiLqgnBE`QykCkQ-0Vc>DIK>{U1bW;UCZF}UqTIez32h>x9}5x%n%7<*KJqAS{D zoZjFKGyA=la}Jit7&|=xHbiB~5q&SGH%Oi@cWW31h5aXFthTNRJL6Qa*kn{j|30Om zyrvuY)=JE1+`KZ_X1N0S{+rHr@mjIZy!xXnuH0}Uawu{ua_)U}D0t61EqmuYNS|jF z0){TjY;BN zmpaIcBlx>5MJ(DJD;@}!svg4FvmMf8tK}iUI1%yqLG2)|vjw(`_77`Um*ftX`RA2W;_k@K7x{A;7odz{CuaNAT~b>@xZ!S6JI0+rMbyVdv(;7)#W_ zD5$hF7_sdEHMkV6gXiD)_wg{Rcz&71s4)+tYvTg6nOVypg07rIJY}Eu4(|{Ml(OkjZM7~x7-mAgT0DipWmOvgKy6QIPST?FsRaa9^#|p{b6d$6NsbE zB*64(2he}FxH!lv?||1vJ&6L(CP9dI(tTX}P^l@4>&}t{Sm1UZ_uKdOg~OA+)3G1_ zl9fSv>54wA4nH7=`2`~0om2~MS9d|&ZE96$J+(Pv(O$F>uNCb@KSdryKSlqU&+Yyf zpG9te6`x}6bmdyqn3#7_hq=+7s5eoEqV`0ci#il*;Vb3JajJ6@mf!P-6To=IVbp_# z?QocIXE$nK@T-*wNIk`;skei<;(A3 zs-1nH?Vz{+W4m~**k@k-(G^#2I1xD%xfMD8LivCEsrfF(f5ZIrxyOJlSYOj;sbPJv z|4&$#{kf065P$kQaw1~SD+gs_9thP-mYiR9&^x)&J8vkoaG}kNXGTzcb#G{Wc9G3E zTT>WY+6@-2%drl*RSz~+cB0QWJ6f9=^@Yy+3qw}>epZ+0^YaaN`$&;p-=(Ur*M|r8 zjfsntm_Fpd3ppr!09iYFcY2pEJLJY&hm+Jtm(yysog=GvhLO+tE2SE2kmNPvVhM{; z#D53hLLY*>s@E`b*gi77;II-fa$rxWy4>GJ#G;KspE|HJ54?r^HA(xNBK!(Z0>(5-_4mPgwhCpp8unV|W?c9X5Jf+Pnoz0GGB z%9vJAys|CK4P0$CXw(%sXpbL>GhUM(X;~T;-s?tA`DxNWt*Zma8#DoRzBbm4PE~=K zN7_Lhht1Y26HCF&cikbTRaKk*vt1y+Wi6O9?3GoA$Nk~=y1&cOapSD)cXtHKjTIrX zON7D(ICQ}M6F(s|6WjIVsPm-FcoYR&p zr**l*f%I52B7NbF8qj~Yifj&El)kf{3EWP0BTtL$P7m_EA-_21OA1|HpME4f9>~2? z@`=zdR+ja{A+%os4(}qG-p^^+Tf>cAj#H>Y(L&3-S~_OmL04?UayZ#FOWI{#_U)prQ8co ztJo$6wt4lI9vj|IEne9VHacCG8X0D$89WGsS=DFDgO--CZtq+NW~4TOv3=WH-}o2< zRSUbyv5k$bTba6m-RfFUE%3e7C+Ci^*uxBx#>ZH#TNVzd%@QS#O7+vix4A>7Vg<>m z21V0@do_c@ud9)nrG}@k7*!Km+N;O}&xPqlvqE6;;8dySqdsYScEm#eVNIktGj^ul zzY+;9RYyu~3Yw((CJu#(3(rV4#aE|Up7w<2i*uyxo8Qs`JX(V92s@G$IUxPJnGck> z@K&z9ak5qO`_5o(P!~eX3Ryoj3jo*oN9El!&sdE*>IY%HuE-@8Y_}5aMH}&2(O&dZ z$;l&NyHLB`hNT4r`G2)b6@Oh1zwnU+>D0Gcg5 zDtk^mW3_8~2wdNiCWpHevMw1N1`&_u$`ghax7OT=ft<_^()+-(sb9wgL&)Kk($ddE z)7n)Y0?mHEB<(7@HErVUA+R+4yzGz-R-SZyZ@M(G>HPwGmXaIsP&vmyPRV#_)utK! zKGAQBG>bnhv(nWrUMu#QSATTHl^ae(4n=N7&d)@X7xMc@;aH1080Xura zl4r#cues&fs}^tI*sS_T)feTRQI84)NL#B%qrHg#4!#AIDXE%qnfv_eTW>hwZ-hLE zShVp;TOn83&Odi<{lp(8#vDU_L|iQ<4w`gukQi5@y?^OGP`xAXzr;!UEYNuVeb}}4 z213UckFlS3st9m2n1Z;$#nj9a%KMrgJ2sX5*7JSfvnGKM(cvK4eDmlFmtFY1j&?8r z{8vB6cDqd>(CtwwV#C5}Xzk9Q^Di?w8q6jR!gj|bWB9FAcg%~e?OXY@EC0;BY3l|s zaE~Llw|LYXzT5D7K@TgPmpA3`?~$3WSt`$K8j3ann_cDFFZnyB9v{ih-2Z^{xwcjW zj0>M4F&=7^ZUJ%c_;Uh7-}i?4QAT*}e#5%3?Jj>#AU8I@Dt0k0(N8gUUHs&ghhLR< zi=0TI0hS;Bg6FS@uK_SC{1A@oc{&=3?dgxcZ4D2B{hiaX{j_^D zJUQ-%IG|EXFw*e*cq=#1d+#Ip{oACk7v$|Txb|$jrpRU=LU642`(2>n^O}fHsZCSz38XNgXpK|e{Oshx&2jqin-I3Yf)oj z-bEeeRePe|L>-Dc7j-Ds!b*o4aKMx2*Qu}y)}(PgtgSW}&NR7?dK)=89==AGKrF6h zT~;~5u6_+r5AA5K>(6e5xo&tj0a}#=)bOV!2{3!$E5vi7-Qdwo6SSXGsR=C2s)M+h zMKzdNl7H?{@tYbhH#I|@-18d>a+k9>?($yY;NUb9agc2=c-~w6Kemh4ihbtQA6;?f zh7*xPkz0}T8Y5~z+bW#@dbcXVq|RB|(QCsIznmTie$A>PhJXYJvbcx!n{-JHB`%l3d|fw>fX4Uv8nnvwvmDjE zKY6{Ubh54g7}e`2HJMy4GriK84bp2ef^0sMlTpbaTly3}h)y+XIL1S$rW|r2V$tSv+f^zP zb2VA8<3jpE`n<`xo%X1C5%&n{2{rnaz}$)UUQOfSWG&wRgAMWU-N^{Ydb3mwE7yA> z|3ikw!_1S$63dtQ<3p0|{Qy$*q2)58(BV?xhbZ!H)5HwN7iyr7PvW>?F=~+3j>c<` zCdEV0hh@J zab(1-(P_8)pOFtO9!eH`_eg=hlP{ygK4SvUHgG)Iquux*J>EM zdKLQiG@=vi*;)a8+x<8J8c)bX-;BIsq0#f^=-Zs-H{^~7e2HK2vMF-5O17OIOZtX; zq^ZZZ&n)&uP0qFONZ(%Wh^qVk1k#}Pv-D7><8sNp{^YLhZz+k#3&MzI?xf~ztEKtE zp2ax4(){F?YIh zEow~6yQst5XiwCes6$bEqRvGfinY-6)?#_z_)t=|NmQ!C%j2@ke1FpF@%WVWFRbBe zSZmZQVHdJi1*V>2rQ<$~wzAGQCSj`ZSr9I_RQ5G`V;TuRRb}9Zuya z`>R1MU|$kH$0hV~2A_F#(H|!r?c%j!pLz91S6sQ_MC4H9R^)tZ(h_;Z&`>hLJ}gxp zGFYygK<`&1S4=BjZnW$_Kaz}Sd@ohRy6k%yVQ{5&h-1(s^q`)-A*Q13Ds-L}L+ z{u524l_0XH#^s#HSn>yakVg4>V~k?^jW{C+e$yM7V%oVRVF6@0=3f{rb<4$Y7OLI-V@Y>j! z6^QwaPKYDBIg^Epcx|37eMj#9YB07tneEJM{gU@n!pA|DqT{f=<=s@3Fa7=r+q31y z=2yio#wGeG#;%K>yz=m?@_r}oxg33r*PZ;dG*s=)?@_c$^##*LH!;_fN4%HIt>&66 z@xl{cH_E~G%*t+X!^9MMzFJHzZFs@o+xDBoA(i?#uj@54w@ZgU4@Vob{pPz*(R~Zc z%XM!l@o1BOQ5gui-WBoT3_rN~<_h}I zuGSa%T-pBEZsyt_Oau8EG4)ATI60vVwr}Y4EOYmL-hb;O0n+y>{Qm8Wn4?m-RRG#F zuJKKpIEHI4-<9Gnv*^B>`MLB`LHWoD?t{zV7|rl;yuH}>YpRoDxu32^J*1RSe$Q~t z>%9_r7Kqnw8tn{khH~9{T=ItMC*PsZ^}bhwNgbM@P0P=iT zAMsh__E+&K=1y0xMU9Dh7j>9d?TLC5btvjw)S*}lWyfApS)bNJrIj)nQ=~C)scPNJ|!Q0j-@@%b?k`>(0VYR(}rY~g&sy+&&}37 z(yZvs$Lif?zl+ave(m=oA5~MT@b)z(wcy}VesA-U@glkL8GgUI-l}WzYn31R(CpJb z*=8Hpp00NBTCvZ(`lBnZ+;AdtC~_-uUTemARna9p_WZqCNoLLX=LM(j?WCg1_&hIS zUG|!;tL0u2UxP$U_Y9!jKiquN4cZnhjU0X`-45Dqvp{^X7XhoX{Jya~+7`Chw!-#7 zt8UB7jrhIRqM_;1v><-}R=V7dEX%BdHc^{~k<;cf)_ZX2NHW)WJmQZov82hIR*30d zh3upIC^pZC`0wDGPw5Ea)^sZRc`T?koPKAGafw*8seir$d3@IlZCbfIK;&og6RuXK zynMSppG!siwS8K{Nn;zduSioS6#OKvfXY4^$rv>(te555*e98A<9_1QC;Pd*}el?;3EX?3Fm{2fF{=S^g|JI=f zuwzX>wDD+GnHLI&ezJOCWoX)#=O=ho^>IvH)^7NhZUVk zLizHDTYUE-7oz!oDcU-ic)j4~S)w-4JU!2Ae0K6d$=ZSU)7oI9H0dT^L!FMklY%bu zH8(dlzbbYyF40dhc3u4Bm4{!I_leg=X)NP7pDqQ6d~g(>D{79igGQZOVlL)h$j}_C z#%(+=l>>`Q{Bx5vvH9WEMGv%DTHb;rBaVJe12}esvrsP>5kWa?9@W`?8|-o*r6&MI>_&_ zpZNru5x4kUmt3+U$PKwZ>(nrWS`ydflGXd9%7?g4y4I>hW-jFW_SF_Hw(|NiT+h+_ z=1VVXbDJl!dmKqNG?y8^GAf#U ztTq@i{mh7HKhF~J-@!MBvGL?=2mZ{@+?x00#x=Q~MJ(EcH;g94(;s8M+HAhuu_f2D zh%G-(lzv;yITY<@KfNapbm9GfDSA`(Tf^6a8@+bO1upRO@4AU~p<4!Xl@aM^FuU0%KC zc^r24z2>bQuc@z2KBT7aTa2Z^fk1M3D}O%*iEl^7*RjBU{1cjxef{~ppt~nS$Xb_F zw7)FHkP#1hBkp`Hf$ZqL7k%5&Oiga|TZBHZs0xx@JohK0dlNErD(|O@s|ES!$Jfwm ztvZlBODo}6xv}|Gv5Rqueu}Z{;wP^>{Hna$*4!kW&f)8F=th5OR2`mQi?P$?-I-hu z*&9|$Zzk|{_Q|?l@^4*YklT4X?r9bc<$164WB}P#_&Mgz=z@y0*joc_IzR73-kb8z zdSVQMNYBCB(dPWBP?A3%|82*DpIVYb+xVW@_&^Pka8`xaUU}S&3@*>lN6!QOqygUC zw`W9Pw@hS@v=b_A{*bEtf6XyhgHL4U-#w=l3Uz&VQlW*_`{fzuh`jt1?O*3HG9m zc&%tJ`YH18M|>8!{Z)L5xzm+vQDb7>MIGiwd!pV%9g5l$buQ{qtcCB6UC6ZVI-i~fXl**iUZEA24h&t!`Dae)9?`#f#^$b$0w(|lj*@;XG5JcZYzL(ZAq%a!|Y zbu&v!jw88E@Jx_W{P-GFzD@v{(ex< zcCXZq#QbbU#Pr!+qJ6Gd#D53h%&q#8`-=*rpQL78jr)GiiHJp;%=lR1)SF-P=)+8XlHRevV&(5x;d31pHKe681Omq6)F2>c;;$2iuYdB8(6fL!G&TH*c z18=g!`Xi22!7G>qFX7J_dSn)m)@Sn^?RKxKYIB5NJ0o9V&EV@Cw`u?m zEZ>=tN{9K`Wd3X;Y5!WThgVRC9JOhJHe;)FmkN#K8YupDfpqvgzh}~Zq?-85Rb$@A ze~BjJw|gM}Q!>=V*|In0cXZoO5f0lv;wHZG*qelIlF;n(R?7 zm<+Ga_Z3HM)g-}dIr`c4Q34s5UxPjbYGO$En9efOn~QB2>05|@-~V#0;ly#nZuDVy zQ9sgS)OEy-rpJ(gZ(R`=Pf8%Z7cOC+1v;q7mx}YS&z6s_OLlMgni96Fsnm8Q_sxH0 z0rJw;17m64@uM`p8oy^K+KV>gwW7V~r^tior|5rfd=|O=ReXxM)0JycV`AP#9p+Vg zqTWOuiaHl{DAvO0;26@OUJuM~okC&6=K$BkeZQV$ux|;>T}?l8(&2u4#Nt}kdu0Uq zz0f4QHhEbAGS{Bx`j~|Y2|nhA_I+$BlJ<6;5P#1eLSByH&l1G652yDW_%pia=;tSO z+w#vHCY}Bw9edz~_AUpzknPj>{`vVAXHw+}KgTuA*OD0CutOVN?c%j!pLz91S6sQ_ zMC4H9R^&X(Glq;$?};4dw@4s`*6`o8-%vE3JaMXo?IPA?-{zw$`Q4y0aw6ga8zhN+ zuleX_`vu;kXGp7q!^zxw$+q`wwn)2Eg2+TiPuuR~gtTpfKe>`Q$@=YO3-C$jWuJ?wMQXEoVx*A3S=sYp-K`$Gv}bI9gvHl){vR)`ZT7AL>A=!JOk-ruFF zd;24%-=UV+_q&R6Tjb=3)I(pH%W%AW1A-$YyYIwq)0N z5b1V(iq#I|Dr8lEUTXuVn~~{dJK|W)PB;_)N_7!OTNNZ9SGW`T*?o&8b?!-q0fR}G z(wnSQJN8IbYYrnuUgd4}M4FJ7Q{2d;8%C9vHEvFfUR5QG{|TL{k){uuAwFgsOnTi} zEwlCwhkVJB#r!?1NuhBhC))wrKhWowo!+j*dH&=cFVeO9S8U%ptqXC#YKs1tCAg4Y z&b1I`Kw(+|T)`9qn==i?FHq+DzMj9HHbg~-9ZeMz+QdW%Ob z1Bt)oLA2RoR*uy5?n0i-oo2SnusWGBkYL^qJqjXaS8PJgUFq{IYipdry!1RBL-v*F zgzX7s2N9DAj}V{r@g&Qq=EIz3Oo}I^*O$Qd6ZCnRiBqibeKObHMv)tfhhuvuBX81E z^HE~D>OR+yT>k1#ns@tRk^aS>km~$d$1yj`62H%Gq^NpO<#DU467x|0c~ca9t~|Zz zLiDG_ykPRE`%3I{evAI(!uZdKYZ|+e!S-Bx8~P=X;YrzOe`BwjeCSpmanr|Ya_i|O ze3satSq#~AsyANycv2|II<^?GX}k{!ANmIInu{&S`4aq0ZAjmBoOZe!8M9=f`L}F0 zGVUWkU*EFoNMhp5kVDa4v=Ofr?L|LD-$b89esbfp$nCGnaeK!{ zldwqsxx@Z-oybUkem`??S`3*LM&*qacO!H z{Yko2gtY3_2bea#_)M10^oT&bzMqY>aYr2Dkmp-e`*IQxCpF)iseR9$i2n}0RVY$l zdRCG9JY};ZaqHHAu((7l+6>rjNOB&!V_e_pJ5dt*nV`Lhhtp@oMvkthV*QBrpN=~c zUnkywXjx~Hev{ubufDPkX%NAmh3?XM09n}QCFb$FrDw z%;ozcve%AWEZ-8x^6uM{bd2MB)TII5#Iw%_%)5E*3MBkmC$yQrG9Q`K)f4f(m}62s z`aN?NuT8aJY5nmi#A;tPQJ0^B^U3~6-o*dOd+f*IY!K;ZwHfi_Gu=pyCVWqr8=GGh zyBL?~rx?2~e)7u0ugZJBjGln)hdWy_<@f$CAV|?a;SB_sP!`x_3)SIY7QG24!MIDN@5T36KS-hki=5*>& z4{|h->tWpONOC4yjT%_iPfe=6O+-zKYuU9Ay~*=%BfNHRp;+R2ljl0TZ34+MevbB) zo+XeDJ9i^io$@DjJ|4q97te7g^GHFww$+@Dq|x1qh!5S5CJnoJp-wDn#E_3&`=WhR zEj2k+C|$#Jbx9LXzHcx5Kemh4ihbtQA6;?fh7*xPkz0}TCQe<*)vlcX^2M8z3f9$- zhfh`8kmV-UKVe<=JNLwri+h}r6A{yQ`xEVZ{u`M3k)WRZ{_3Q@!^!zGyO3w^_aS6l z&lJR0s?fdbyn2Wy4xqnRa(60ne(h2<(qLFK^yhnB6RBe7c*On8%E+U9IDYkEw0tl& z65C6gFO#$FLlD#76p-2P9kASq`0wD`(=n0qrXhUI-F_*EEHv1Rv5Q!=8FV+Fbp8X6 z*Xd;pS-Hs-?L}?Uq@*qP_3^ATkp+q5Xb?VA6I0zh@pNl(x%eT#BWB*v>ZT8qRnThmWsI1SoNwH+tC>7dYQb&-$y1yYVzk38RtGy2K_3jCz z<@U$e&zo`yHYI!Bk>%e`m#^jwUzISdiFCShYIt3srOSevj0Q}94pW+ zQL@MgM|`%Xr&R1c-%~ZJeqGgQEZ?KXthLWvM89Xwd^;cQB=0%JeI8wZ0Lj?pz%m z^ty+9eqSF<8XsSQxYPYuvU!^$=KV}BKhnMVHEiEBC4ns5bOkjqfqqu}BKaD=tJa}I zrqr_3aLm`@-^-C}a%aSicjYHeoA}-!I&iF1(v{b8Bj0Y)Hu_FpmdB0VOOZ3?{9fhz zbJfX)RT8$B82L_G_{_$4X8{;ujBg)_t=Bd)4E)r$qjv^pxs=16-(SxO2pWOH?a{H_J6mzF5*P_P6 zyo)-_jrK&ni8>UuC+b|(p;!xP>vN=n$M|{beLhq2tvc63c3?YFv6Thpde*WLr2Eo! zm^*PTD>R@4IpW_FZ4T31M`iO|H|!fmo^P3l_Ctn+kezD&E~B8rwaAmzE@xb-eqnVgOsV6^j#oX&YIJ!D%eb=?^jev6fIOtS$P`(yKN!4{D0I{I}+Cx>(hp@ZZ6=mx<=EZGU_8&25aD44WLMaUJ&1 zM#Q4cy&Xw%0rPMOKHtsy5q&30C)57&1NC@25zqB$K>S!jsoG>_q$0qtvACsRT_@ z{`WS?ZPf(E%-0w+4X_>XG>#PWsUp|3t7CWGV+7Uq2HE)TdAr%&%fQEyyhcvjUYD~h z`99E~Vl-)AJ5a8_e!AUi*LadP%|xDf)Y8tQx0)oMo2j{Rthen;r!aDT^nAIfqsHz- zU_TOe!vJ8wH@mRN0J7|HmONnKBfB-v9%jCOpoSeuBW+{b6_Io3d*0_QeP{DLtemvV ziM~tMrkGv&cz>x-{b<-yqk&zi#U16|7h~YU=1`lMeT(GXTSCEYx`B0#ob&P}`kiyO z#*Lb43?c2hBYuC!ob(*q9@Lli+wF=8kkV|T;Y?}+yMt$UOGZ_PL$?Xhc1sftrO}t; z!TouGT-k`Ri}8v)L5Ip9|Z9Bdxi z&Dj`5Ha`fFZ+DwzcM9xDkkkU4Hk`EUzbKTX^j$1JO4@4|G~J&Rs(eB|Wc1W-q(v?I z+evEJw=vK*yGw8B0e#j(l{Q=~)m#+{M<%=5Etrv_k{hTYAp4SSmQhnu;aF`j%z9{7 zL5e1&cMg^Ne41((?(9GYmTv|*ThG`H2o59XE6$TI&fIP1eJp?kcpa9v8#GZWj%DMe$!<(Ar}dgX;Oq3?ru>Sb&l-L9jw>}m|v zlC9nM8xy6%>my)EcpJM?IrN@=r(ozfdx+h{s;5;;*CfE)md|V_j2O`5GktgJq>XcI zYkE7%&W~c@UG>E_3$5Krt#1XvB>tOSEd5A^E$J zqJCwdajP$OqP=J%UMt#*eu_MZev1C*#%Gb+U&W`GJ6*XJH74d=)M0M4C+bbqp{PAk z=b{e9T6mdqUUhbH0_-F&Yzv<1ByBtt120(yr}@kI{$9>qIxsZ(#8Rf^m}Hv%fN+L%eBD!X0~00 zm8lYBhQP&!-gad_x=4`=V!@%2xn2HFTU3+id-j(Vx@~JX){V3sYXVh9e75s0`dxb5 z(hIHxF11@cx)KR>?*K2~?6K=U)0o(|?hc9jHtTE`uNC{ut3SHp$_*zXha$Hk=ND#O zQawycfX~xj+Rh{sTuRg5UD#%sW*geRh00}{8ca51{tMP+|L%1`GSa~vigj9UCt~`0 zxU%;5aOv;l%G%$_rN5smYkxnN{!Xr}{axL>+SC0B(e6*)*RD%;?BZviZ}HY7HeaI6S-2y%0FleHvRsMf`X0&8I(or*y~Z=<{ur1-TsD4r3Rw zXmd8n4{XU*j8{#+uiWoDKR=3iWTRM33jLiA7O!X@Vr4-BCi4C(POD5#PT}WSI8}^P z5AB8aK09TpbJ8%xuMOz?RL6ct-wODLgTb~LIBv}R_fqy!ex_b_w*>Jp<>!<&jp=i7 zM!e7Yd(KOCSNXmrwrfl2SVw;ECI6`mscl1k|7}uE3%Gd04##>^zy>S^aXlP2=hTmg!PT!R2Pk-N(X{=7-8);35590e34CF2MxlN|Y8EO7HeowlIMMc zTWg3ivqAgVlMb*Yi6Gv!vlp}*SPZfICsS~X;-62AD(D5S_xa~pnqYG%d7YmrPEO7T z4+bdbJDa+&_8^~IN}iaT3GcXX*;_tH4ZCrz9=3a?x#i05&y1*WQR+OI>$C9S<&yu4 zU>tXCkTG2H;Ct-uRa!vZ2lm*muIvHH+Y2BzXfPD6IiEwlMUo1Te3E~L)yw&vd@6^J zbz_1N1U>DI_6b*NKt)g?zEnYi`VsuID#vYoq0m}>);65#ELGmmYsBx-HK|%1ejX_{ zPNO>dko)YH^-XoR5XYkZzt{-ZiuR(PA`gGWXOY`q#iy7%UAY!DHbls~sKdN!Pt=>J zLs93V4#iqnIJ^dIu#hmnonDrQ3r2h`ODMBhesw+w+XMF()eN}GH7TxT4cl2j`cOV6 z-&>+l#Vfg!i77vK&?=6zy*{cah(va*YL*4wg%uZK1D5-igdVpiT1M<12=#A0#y(Rf1b}977GmlH zXnpuM{QtXetqKeP_sCcB?9g!YE%^qL${U}d&mtCWiq)(NZg-l)!F)TdauPd{w3!v4 z{@2IJBHmGBv()5t5cD{;FGaL}{Bi(^d(Hb_;O9en?0h3z&oW(d?@cdKx>zw7<<&QN zGBhTuNPQSlZbC{s^M0_=#}EdTd12v|*aB*M+e7WSEvzm~?m*r*uLRA^4N?}j??Yz1 zEdqWaPRWH%_z*MlTJAG`6!yJueqtVijDA$UD@rV9;ccRmffw z7~IDVN`+pva@|!O*6fv_$oBPCy*?8dO5epZ>3k2X58wL2ey2ikT4ii$RyJDN(TMD;S&yDJ(pSK#zu@?j926#H?fOx ziGGT)>*6P`Jp8J>U;H*ndNw`+W@(nByvsQ#IhY25;fqr#V-sA-tmMiNG`eWYfaNo# zl5N6aW|8G7>!wI#*!${G?S@y%+!-~=uJS6FoVY5*>cTzwWAnjq_RUSJf$`mB^~4zX zHZ|Jn@Q?-a1{3yMO6#mLB8$PuHN7CR?_De3Z{@&qcV~FB;gVI?ClN9UiGs$~iB{Ds zT+?JvNPuIb3tBbUyhDGQTdyMeRsHLI&8)j`#hz=z04MGN_Xw{eE9Rh&pvYMYI=f#A`)+(NB?w zKjO2QL04sB=+=Vl8Z*zC2_Tv>*Ir?jebRLZOu06qz4QyfG0Yi^%UfDLP2SWep>DBm=WhVy5C zv#Q#1ne1g50uN$#Se-X1K(5Dmz~HY`C#EMMCPl<-@5uidNwg?mK0VfRqSt_419}bUHK5mk zUITg!=ry3%fL;T74d^wX*MMFFdJX6`px1z219}bUHK5mkUITg!=ry3%fL;T74d^v6 z5}&J6c+g`cLeGg_4|)ygHK5mkUITg!=ry3%fL;T74d^wX*MMFFdJX6`px1z219}bU zHK5mkUITg!=ry3%fL;T74d^xSpQi!KeLiyN=4kvb^1?5%@)64@#5D~k%cTcIAin;3 zt~@U?3~^rV$L*>Gr3<^@wVRjJhw1|xBc}fa`u`ErzXP>HoL76+xAt1rx3*9AU+q}z z?^+-7YENUAw6Rl8BrPYDD@n^0T0Q88=Kf4CmEexmIG=Dt#hW#zL(0i8!zJGx7GmR`Cuu9by8K^O}JA3*R81fM~Oh4G+`Q5XJCh@JjM^ba0#gQ3wbKbht9VZUf_opca! z{@Q`i`+N~#?fpIbz};f}9lGPAB&Z(F-=DhK*#gpBywRqO!AH5xcK%M^gwz$XyB~iK z^gN>)v_I`ym%Kt~mjruB=tmOzC&IWy@P`O~62brffR^9JMUzr(Diu#V{b zz-kTkK<5WmgNW(;z-kloPUiZ0JN47)A<2tjU&!yc0s1KkC@I6GMy6;)A>Oo zV3lAa3D-(OpKLC|YuQ{R_`v2at#52j)B4QnT^oxS?|(v!V!XM*Am~BFtiB{=eqeQn zn9dKZ9*HtPusTId=LbUT7cre52(4?xbbes1D8#XTq{;+vW>nEGvwEq7;8`qGkUCH^yWr5}6$iRkVT1F$pwhm>;=$hRS z-^hPS8qt&2?f*bQ9L3 zf^iN~Y%ovCwTP8I3F}803$fw@V#PPaiqD9ZSP&~QB35EYtZ;%@;R>V|Y#L z^hfkl^k0lij927AK+&I=RYX3j^{foxdo*{l^Jo-NWJgxkvbF1Cc=C)>dCjNps;;)>K z^kZRK^QwjaMEg9?7kSjykNV2xdh}=eljr_(>33e^)Z72p{Yl1!J}+DmdLHyV=ry3% zfL;T74d^wX*MMFFdJX6`px1z219}bUHK5mkUITg!=r!=q(m=j^PufJ17i0Ld3wgy$ z3aQDq1pcgpg7H}gr5}90;i$n766nL9`+2*$D|vK*KM(ZQuo0pE;yrBIM(E!VQ(K8% zgP8e6`$Ejdp<`&VMvJM9thHg|Xs>1CX!~U2XvY#`{3rS^#*!N>ey>l&7qSYGoboEU&u-KG@mvhRUd zmp^~TSmJjVMJ#^5QT*Pc7`upd+0$5Tl^oEt={xNkvxX|pHm4|y=S-L?KfH&a;a$SE7{6X(AajU-xR1=0T;TksH#0q;Q@sX+k9$MQNY`^;L=z{%d{q z+Nb4vJ9X~w+fn*IUN3pK?|$}PYwfk?;TAx6zO#mynpw{ToX$lHGED0yj|MN@m}Lrm z|LYPC*YaylM_yW&+;Z15*9N`o_lI8VPA*{@esm7_t9|uN?+==Rn^fpvR=i&cJmuxS z=9>$)L*M)ZhM9$TO$X1MoMB46SqsePT%Mi3KAY_z;UTlc2TM9&N#AlD$rmj0fJIKQ z=&0H7xBn7dv|fM6;#aV_X7NMxS>m6tv-mAo{2A$spM%B!!Q!ibC__5(lDZ7NH0$>Q zq>ks%UE3j9eDWV2XBzey&C>26T-rmhw3A?IKf%(jf~CC$OWT-3eyvM7^3uBGmT64R z<8a6?<8v^jlV~$#Jdbc0=Yw@$Eb{_{%X|TLNXJ-R>v%BAFLtx+hpDiPCt+L7GX6xk zj7wp28Lxt69E-k5##jLje6lUi8S$-V zneQN6=0RYYAAx1w1eW;}Sms$^nG=Dv{F>8|m)0e>EOTneEOTw}KeV8si)8 zhnSPela9Rjof+<@IbY54b`rw*jT-L1IgZv{bF%oPi{*Zcztv1*e9L1R4yQ3b-6^bq z^l6N5c?`tiG{(0)He#kRe#m1cW*Xy%JeFdnF@6gk_b_YuHK!vltxIm1#`u=U$1F3A z@hy+7nQ4q~dCbjBV|>eFab_Chhdf4SrZIlVV|Qj6Z{mGPt-I!A@nw8yMX$s@5$S4q{LSIK*TG|bX5Itgu|6~Jjqq5XnfFY1tk2AQ zDLmF^Cfi#c>oaTlHK!x5WO}6%PHW?q*7>13t@B%2=ZC(u&Tna*A581~me%>fw9ap7 zogZxit@B%2=ZEgJ&Tna*A581~oF42z>-?71`N6c#Z)u$$OzZrX*7?D-&L7e`KbY3} zLt5tt(>i~g*7?D-&L5+7ez0D1&^jLMx@f&pVOlTZHy>eh&D7^u9+$HpQeR|w4!}%( zl;t@9Gxc2|&jFaJPYZbtz)XEzoaX?{)Cb0R4#1pDo^<3zWB=cMYf`^QNn`)SJC#~@ z&B@}EE{T0)%{0add0fu=(%8rH9Dtd|M3(0O%rsWAJO^N=F_h&w05grPEYAU$Y0PDL z4#1pDmvrQ%b;&K$m^$QfGs{e4ZOd~2W*UQAo&zw`*xd3QfSJbZmgfM>G?uqK2VkZ# zzU4UpGvB8gdC%h7OcEY2OMI}T1D5m+$B}%&A`e*P1dEQEEr0tj(M9X^hb%q@n`;(7 zM4u)82|J75g2kVazW6y<{2wg7`iC;4BQL4T&`Yz_eS}LL2W#CmCyP)1!)w=;eMYmi zdkB~I5G?H^SlUmpw5wogZ^6UpSu(_5k9eK&v9`b9Jxd6gt%n#POYfcuQmQ+~QkzhB?vhIX%S&stC zIu%&fuV80c*8ep!bH%lbT6 z*6qQvo)4CFesFflCcOUd!+Br8$LIY5uEesd0ftAD*IDl*|!4Aeim5vxxljj1?D+1&jC0csrxxN9eGh*=KW2` zpjr0*5H5RsV6D66Wbvh51fmzW17KeB;Bh&J%YG=@L)j;V?y`RhmVH&oAp5OgUW4H| z0H>qn*PM>L$Yy;06S`>Ty23iMJft6=;RN&khF|mH{SChs#QPh5jfnR*{Mr%kZ}>GO z(vQ!SBCm9(ukEH;mt#8YneO!W8w;s%5seS|cN)QecwL#t)?9XSwgfC^PQY>&1uSP& zz;bp4%h(h_;LRNj{s6 z`7iI2`?Xx&C--Z-yie}eetDnVuL<)$xnC<5`y7z;^?XOO)HReBwHbW(1pHT>{Y!WH z(k?+}&7>pG84)h+7+Bgju(W$%X%E5DPJ*TV1WUULPIvm!kDyJ^EPWYdkTC;T#u8u| zV}NDs0l$?o30TG|7`I42h;d80)0eRpWYbJK^4Jx!$rutWV@t%BF(+8YqF@=Lf@SOq zmT@Nd0HmK76H0kOe$p{<-iGA)%g@-PJALwp-#u3&_6)h5C;$1&&%mTReQ5*X8=83x z!fh7oC2MhDS)&8X+8tQd^uVbMKJu&mdC)15xa{=4TQq`k7NSGvy?q$7RZ?`x)U zPGVnM_E1po{;Iv~bf?dAac&2>Tr`u8iFHxgQ$yMPReQ|`D1G?62ac3r5f6X!H?!ItZ_#7~+3 zC3hvDZ@P3@*X`R{Y}<6-VUac*x}?In@C~DU159IDem4&+@9BZ%ojtI;zXz6g`M~mC zA6VY;1Izng&%;(mXy%vroW`7VHC_l7N4)}R9RLn$M0D(gSFZIi{% zbIOy#J#nco_%?dC^Y49wl**mYOoyd?50H$Oj@Hh(%@gKEH{>cBDHjzx(^YlEvq{aeR-0ztt?iQv>1r{w}|<#c?QZ z;#~sGe-a<-;u0S$X@ccju*i^ulf|dA_Iz(WVA(W_9S|<|0gD~Lsl<`{M?U?;-7a~1 z(5L@@evee{%Xobgcm3GjtTXFH|NfufJx+GtQ{GTQ`v1#2>T(|e>1dX>Sr9I7uz*RP z-~GK6$>OtbvW?gdn#Cpv7h8eFo;f&Ke0}FjbFz0M#UDbJM{~0HWD~wG40$w*%@HnT z0oM0%G$)HMHuvc#?w*L9efs?SGQeVIpI73I9Vw$6ark#QtayFx4Ayr|MuvH~SRLs8 zW3gf8;}^2QFaFfW%)ej<_{0V6%=pKuAe{x@9A|=8T-jyzEoMGn)D_|Fi>?aFtsDT( z8Zs*Qvj1rCg#{jtJ$|Blv#4{6`SBYII39P=gmCBEZZGxw;j6=}HSVq28!j$xM_qO< zzJ25A`nL7a&B0sicd(-uySHi=R=m)jU+F)Pt8z837hW2NIGfL&7re2{ zz1hB}RbF$;&K?LKl~L0)?A!|c?Bdf*@i*P?aOqI8mub3qFJwD&(GWAJ(No}hwKL3X z>y8I=*)?id9A)?4?8~%AV_ffHSe||=CmqLgZ1z09AD`)v-p-8mgCUBhW;N+ z|7+xZ&ph;9K;I*r(hDeEaOU`DD1Y}380X`|IUgUN(y=}r&c~he8D0QSmXqY{NR2sHKP4w*KdoyK0ez4OzE(Fz+yKr z<;(U2%g@359ovy*Bl)>ph@I^?EMjMc$PSSmA|Hr+Ao7982O=Mcd?50H$Oj@Hhr~V z?!TopL!Tz)75cnLhS1AEvV~qYk~#D;lP;mxg>($Pj--3&btjvI-X>(L(A$b^7MD) z?~=R1Ze434e$kz;hQDqu3+`5IXLwte0^mw>4zpEb>mfs{PpjEqUY!MQH~(1M@tljn zTF2^po7hRuw{F2Y-nFEmt#x{lfO+E4b?jODCV;DtsAO**_X2oU#UggzMO(qsTW$)k zuW+d0_{9d!4PReT1#Bk_3G;+?!Fx7ri{E%#Bk*O5UTJRfyWbnVp>F=*l!7jNLH&&2 zmZ$3=&e3l@7j!h0!Iu{PCitRqQSh~uieX@|kmK7*y*_BQAC94zfTSlWNE z^b26=FTm1|fTe!{OTPn_{s=7nl=m_2zrf^shWt=7-i_q`zEQ(lYI3ia?)~2tuXmw* z4#fU1Ycs*D>-H4hA(4IIkV9p^7%cn9mcwO#87%wGVEWOY?$?jJr#b!3-UGK^&+@uI zQQ5H_4z{wRKEhHT;m4L%jV-MjTUs@?v{HZL{H?0XJ{_*tK0dbtJ{_=X6Rc`OtZG}V zYICe=qpWJ9tZJjIj8T!kYU`|O1FdQ^t!gu^YBQ~BW36g?t!k64YQwE+!>ww=t!neF z>Ib^P;V~c1`S|#p zk57m5@#*uwK4159Cl7z;<>d6d{G89KJ4SMTR>I@V5wCCRDel5cH3ka9~0xbOkSo#aF^e- z{CFpL(B)ZnYoL^bWRg{PEYq<*^H@Y+SiXMhww!=^|Q;T zd;@(8>>g&XZTtxMr%4%hw~9R00MQ|F~+(6VWnwJzG{f2F$c>s$k0W!^p4 zppHnK96q1Qx7x=viwu^_U1S4`%wW+4EINWk_mIC8n}EeuU|rWVr#oM*V=maRE)xF_ zS=ZlBdS}>mFB}X1neg5?TXXY?;3cib*~!ID1LrpW+|Pdw+YfPP<~84bL{&SeXFJGt z?}g3n#>?x2$J9B;4sLlE_^mfDwPjEH5c%%z^VK@0!rI4D;dgfTwne|)3B9iUYJ~ly>#gAYcV^itO|L+Iw=*Nd zo>aI_z&3wj^+5Z>sAb@u=bmjJ>2ZYN@CE&kwH0dw;AHuxBQI@}3WH0=pM1~xz}u%^ z6Lucz?$rGF_O`J8f(ucmN1RG)>a$yd-#+sUJ7Y_E@Z;46*h|a51>L2-=iqeYm8>pk ze;ZL@h+X)|T*!0n6+`Td4_uu}B~G$-K-aY;bBEa1`nviU6c}pnxpxloN+piAm9&}o zR@zdq9#`Zx{$Em3?WqyNfjE*H(7WJjZRDoo4g)cl_F@(`;t7oSe$Hy9?zv z^S5?~UYh633xmfeyRq?=LoW`V8Sn1&9roF6vBP`0IyLpar{b5CbX;T5mEkS-xqEF# ztbIAWz3M=uS-VR?`|P%E;G@RZviFU0b*<~eE$xIeY9U;6y7SdKro!6CQsGrc9Aj@R ze=794f61A4{_e8iR%I`@o1R($zxw34adyw$&A@e5WZ4aSYr-chR~}{GdGWe{{r37w z7upWx{{v2zZ#weQHhE>sv|!P-!y*6h2N%W;-{tzyDsL1HCp|kJ;Wu@dAGTdF82sTw zhuUr5xciAO-gAE^n;_2zUDd~)io`q z2ME8qc`D*SL+=`8znuP5QFOD2xD%Qh8IvQoKzLPDftJ>Vo#MsdM&(PxW%X*PzS3aQY@!cT$OytR2vG?cA<;?AKSh zG*=yy*A6S>IF&fsRzLPU+P+iXwLiNS*R-80w}K6IznR7qZkt41|c%Q|kgF@}bgKz9seaUOTy1Hgx zJtmx$?Ty}dC zaDz_^n^Vp`AAIkY*}^F+rRduNA(D-A<@&FRQ1SzXXR zR{e(K!qVqC-}|P`@!`~ZIsGtM99{P{>$>(>x5nYFqAtzWW_@-kBsV%jOvd9)gJ|_KMGWTl;Cvdn@rzi z;mQ0hSvdJ~;M)pnLt?%Sp|&ON+ZJkbLf__4TV#D(L~WGyZ4|X#*0)^;GB0fhYQv3h z!>MgIzHO&A-}pA4`U2zo0_r0I-$zj25%|7?+W8i~Ptlx?ytMyornWBOW7MVvzD=XH zF7Rz#DsiYCPSkzPx~@^19QZbw+Tp;r)v3hM_SyLI%gx{1>-u8i#h!J)ncMg@=C^9T znP8gtSvB9ZYQ7n&`DUo*n{hSYjH&r%pyr!_nr{YbzL{W}lP2QOTs84+=fbTLY0}&_ zkr&N*6Ee_TI3XL&krOg&U1&aH{M?-8?8eX8X)Yi5xjfAa0zb#soXWQ}H#BNJB*CyeQ3-X_%SDqMFT$;)qQks(Qm%#72&|Xa7_hM*|ChqrWXzwQUdp8F%FKq|f!!mvki}tpR-`k=+FXQ*TXfMq8 zy)fD%Gk%YZ_RfsoJEQeFby;Y=}gXVahA1Bd`o9|5^2)eoGaoGJi`JPUlGsoz26#C7t0h{tOSD z?J@pr51sij{>%@Z1q%FGAUY!y_%lLub|~i04jst6v>oUSmGNh&=xmkoXRGMUmGNh; z=q#4;XR+vvmhoq_=6J`9FC^{=;{8_0~;%NKOp1bjT?z9(g{9e57qjMXd&Y%YV{JCa2HyhCT zXRJ}vdEJ1{KZEJKuA%eKU^=gB==?L7&g&XF{|u({x`xg_!{_O|uA%eKU^=gB==?L7 z&gdFCw~uq7nsprgtxi+trDf2vX_>VybcWf`y#SnTrZdmRpLu5XXQ3qy&h!5c|KYb{ zL&N*0nnebLi)>(#87#VhMMtpc9&nms6R_9{EH=bGpyqVvt98r;TV`c3aRx@@4B3X7wf+C9yne_3Q7^QQ(VZIO@6^y;8{_ZV^hH^AOoFg=kXGl&bsq>2~20;dAx*rO=shIycBR=(l_N`9Y=qw)6{us8MJI#X040# zp~zRpoM0J?f~8-}!Kr*JV;jRdYL+oD!ewj>mN7F}#?oLJV}oVv?c%sGIatQ(kW>2Z z9GvcawT`K<_OVo0#sknx#$aF>o1s0CFVoz+852St87qQQiIc1y&~;75v`ACNy5Lme zXj@5}iEpJX1xuR=&TV{IGqLPrnq}P#;dBHDR!<6@z8%Chl{m@T0bSQ*O%-X%S}Qn}INDY+XUDfPmxs^j zelxf6WzPU>@iOlQ~mydv_YGwpm{5lm;@`Me^S&cO3|MKGO>=ktnSIUAOP zbsYVzPE+TlWze!|nYAu*h7I}3nNP5s1qI8wvK*Ysw{o@+_R%b7P!TR?Q<1)$Sp~~k zRCRW{m-EZbLKG~e_%lP`9V5)a~U&hyWzAuBk zmmG}fL{;c_XJR<dB?*2m_c@qFEZv}v9 z9>nhn|3I9TqCJ9c-;!E(pkvAcT?PL^*v^3pbu zJNWPcxtou2mpl6?Yq`r0IpvN&SnmFVX}rX50_5Oy5xb6s)JLBldK)k zbxrQnBTcz$4^AbHww2u3#J6&n6Ri8_+{ULhXMQgT>1d{X2YxRI;qqP(Sl$Z)%X>j! zc`pbo?*)P7y&$l>7X+rYWqvOx2kSWcTb-uPOUs~T(=uyaXg%E0`FZ3kZ!Ur5EhaFn zOY<8|IXIPXX>Wqxv$EWNYNkCbe$NWw@-`Iek-QlNmbawPuF4xzs9*B-6zZ3}Nd=a- zsvsw=!}EJqIXK<^PwL(og!AOg$VL|}Qd2rO?If#r=Ou)KW)PL^*v z^3pbuH=t0~@-`G$-i$)I%Ueq-PI`T?Z7qq|0n@EsH-bw4Y@pttW6QakQ=E%@BMmZ;60)znRD&vySBY?WuM#Zp zRf6TcO0c|F36}RNT^#pbC0O38gg?;P27a$H2k#e0eXG;dd1)E6Y+7cm3!TT{w>^=s zy!i>1w?M&kE`r|(&B3XBOJ`&FJypx?r)D}s#qX&iT;3)H%bTTOdCN59Z{>|su)KW= zmN!xTc`$xY6>`!!5PnZJ2d6ta&Me=YsLFI!9T!1P^6--9W=kkSQr?D*IW%Fl-fKAiLM@i`x#4(H?3 z=YM^^@^hra-+4JXJug4!Q!D%JTCAajhs+WmEa_Mdm-NAsFPMJB@_`@Ucz!yd~?d#hhdzwW9)cy(ydd$YKK+V*=7}FGpx!?`v7;GL zv>ABmx&|h`;T&+W6H1r~Pxc2tTH)=W`RAj+Z^pBNW6HbVOFF8`oS5RciW91DLzSjg zd08ccRkB$nvsJpV9lVao`2Pppjj}^3Y$q&kAF^+}^6gkVBI^b4ol^(dq2&u$4jGnlTNk4QLPdFY31s6{-?dbMLyXbwy!W0y#A;;VO!(o3B%{sr}X@MtHvx9 z9;o<%N+(e18YL2x|2y2b8*HoJW3E&10csz(u7Rn2;5rDV z_JQjr%9`2-uCrijA1u{nFtrbs>NuF%hmh(%nA(Ss+5|AQ4{^mY6(>;N1}aT%i|{SC zMM?&4yS!}Nrg@pUzJs}~Q~Lh@prh6|6}H+win)FT(mrs#15^9J_0dTC!1WYN?SrBE z3#RtLP`w6I`@r=bOzlHJ?EskC2TIS4DK4zokn4*N=k~H$;0iK zmy_E!FTd9DU!~U%1)5s^yZptwXKXvI5%{>#yW^)+tP8H4Jt`c!yfXNQ0t>=sPZR~e z`rKC`|K)F8*a9%eWj>3}&;WjEt&2fbJxPJ{j~2%IgNvMmEuF0dKLDfr~8({U|zfQYrDLrNok?& z^6RdgCXc85+9-$nHB*jHKjgo8I32&n%IQlUc{ohgM>(36Zy=}7!=>%VY;K*EBeN_j zexTCfHEZO{I;nhFCod1LS%;hsrNL{~V7A$`7H2%p;cQFJgNehH9XK8S%X)G8V9GPG zR?cDkGmb-l4CleXX>eN1F6{|EPM+S?=Fpn5)068w*F%oCz=jfFPOq=(a*pXw-$ZFYyXzgs6}akDeYRE2ZvMs9A1-| z!;y!?=R6=ArNenJbNc+38DaD@W{%5wFmoC%j|rC3<~%r@b5!9oRQwq%tE7{y($7}; zW-EEJm7Lj1{_Kr=CY5mM%;9jaFUR+G;B>Mf57|=Ljq^n~!hW-JwzB^Wk{@w6?PO)A z+8OTqP^R2|t3HDJK7@1ot@;SG*X#q_eycuWzdnxb=-X@6M{s=KM{qj6k3c`i@wtCc zeFV!x@z6(b-v{P2R3CxKE_&_P zCn`G_-G?f>aoHEN(hANjBsgu}y@!Y6kaqF2$g%@7C792LcJ=`>7GdN$ZUg6~r?*P~O zrfgWC#vbsb2dBiz4rt37HN2&U3XiGyfl4P(=?5y`K*>XGYC_Inck$*ESbr0!VWy3((Hc&RFd=h0reMh2e*{m|>k`l@g)M;{;kfJ-LNesdp{ zFULiE&Qr;`-`wie>o?JupZ{RaMdO&noC_>@S`O!Ql-)RAgma#(GsmGnJm&&)o~m46 zGq0PAx?fou7smhnE5f~RaQ(|I|K<-Q40I9wQeo&J@pH*e?-j3i;dv6iO`Y@jy!hYT zvSq7t`6_)=VjA!B*xtx`BbetyGUviPL*`ucGpsivj+%4Hni1IDJ`fw9G7vitp!K zoDQ!yA`Z`oRKCcAzhxUJIei{1Kd(1ta~z)s|I6Vr=VHB(hfjy|VCMOj%(+-EmIrC5 zITzC4v~=3cvfhaBsO%2Dvg7*d+qH;Y`ySaLvcq5J1HS)V%VSIQr#yaFV=x|DBAoKv zZ;YqLV3vM{I6NLuV=x|DCdQDN zADPZ`A$l@8TPXJ?yO;37rz@kXlhy8cin5?+fFQC+qKyV zo_N>#@P``@LpoDe&kh&gUk!ZkPnU(;FFF={UA3+8Ra4v<8P1PAjQ{0%pv*6EhDGLW z*bkKXrRDja%=7TC%>O9e1&KX9{!ZqLNRQLi`J~Dmk8H$q-?YoN{KYbfGd-FQqztLr z#g~`%AI&`;Y}ikIIsGAXJd(lJ_djJGqxroeUN`Xb zD4tXK`ITO0=e;36ALF^1-%}yI5_>AVZs7M+c-_G7snGnE_rsva-<2=v%6k=%fpzt= zv94Zb(uMcE5Qla3I`Y3>clkNu@OR!;oSwHK=R^A;q;sA;e{;TuWymbpAe_?NtqoNl zJ||pWbST0Xp7m?^&WrB6`}E$`?M>gDj_|^(Pqn2_ap%-`oYKv%?_UVvCBN%$@A%;@ ztOuhlzxRF4pY6|aIDfAz=kI0VaL$9{aD4iQ|N6aJFsCnhVExD2 zfaA(HNzcdfI})4+r^&LY_R~w>x68D$PUg5ksba@J4AKMSu?UjWQWKHA|Hr+Ao7982mXCNkS9;I z>`e38QERZavhR?wrvJ~~F~4b1Yq%*?|6%a)KlU{lGyel#v9*J_Zdpaljb6!UViw)( z_8Tfqs$??G?SSyFC+!LDyv(fuy*yxXa82_;2!FowfZ&LxW58>+y%6iQJrlh7>FTj| ztK54z|1^0n?>ow7#;<|ysqilsjIh-!-HG_63SDNqcKHDO)tTqm?}{Dz$~U)lV!_pGTJ-qF$^1%-TEUF_-TF%Hva^GuN4hn{W9VL5{Vlzr@4Q-N&DH0f z1-||L6U>x)jllz2o^BQ&do;Lo;r6Ea$yLDVO#hhGRh~HX%X7_(GY&QPkJvK%nR=I* zo=?6XEUGg7$CcoBhF=ndX)ww#3?x?=`E={4DcbyVkM)y~sSTn(^kL=gNf4FBKeZg305-sl++|l2K;dlxq+_6~6G?k!EMln-G7+?Ec2q zd>efD8Qsjlu7xbiP;pgD)2w1G@Rv8%Glw*80e zbfmd)M_0SIP%)%`&5;A_#L{n}d^=SeZP%8{0588L)4tSxJ$$eDf-JlC-B#fL<=df4 zv+R~`P0;UbUozglzot;YR-LhTjQu>b2RM~Dt~^p7n-s5hQvAiZYkwZ7-Z^Y}%UHu{ z{CN11@TH2bpIZ0Hp0GqG*MGfTzp_2+z4nMx?xP0wXn6;&-R*5`qw|kM_=8P)*k5kV z2d-3pu$}qybCCbzj1hLh33q`1u6zf#9%Uy@ycRP28E>0a@z_fnkF?#+xH%|McwyZe zrf1maJJbvo+Zuvgb-gxl~@RN9-akkomQ$r5_YRQ%M=i~1I zzc=<``^0yjfw$gsuI*HptiW9=NWwxuta{@D+oPHQ!ea zz=tn2=E4W+fUnwfwwXS#6u9x-7n%MOH=~RW?>NL9ciS`ICuR;emlmG}{wK@!=-^T2 z=FYCaONA?q9cx~=wF~sRrNwyjR`Ign`-*3o1-qYyKVQ2g%N)CU72a9Y{O8}M-cE^s z822xHC1MyOvSH*Kkq<;Z5c$C0>jN~FJ9UiNH>yAS$KKf)W?|Ku;B!C8G#m0QMPFHi z=K6E)T#LR^b1L7y@=lg{G+r9%?099oX`NjV=@*~0wLU1Z^&h0(Q)Oy2>0aD>5 zj}JGEk8op~^Ip2hlvuq9dF5$)rupdpau^qF?01sMzPlm#(qE4=8pEBQ5C@HO#hwnEhhgmtFtY2Wl6ie;wiJ9E`PDzJNAok^70NdE~_@e{yg)p za9V8o%o83RZ>N4$H0=4w9W&S8nq|McYe>9z|4Z-O{!y0Qysl7u%JHAw^?yz0o!%ED z(s{1asyd%6$+91ucXDh*sTp;DJbk?VxkQR>)JdU@V6_A^|o)c+YR1UuBCl=Yc0d!x9zKLw_f7T@Lj!YZ#aLSJ41H# zi(zQ*xB_wJPaYCZeb=o|=3BWXetbu_KAGKOLmvWCN}Q`aBkvvE`I0}ljrp@mCyY#m^kOs*|VM=Y5IS7L(q8cOEU*9 z%Q9zQ*D#h!9H{hVhS|8fs%vu;A9;GFx#5{@Xb(>evdo4))4&_w&N7{5RLH@};=eL# zl&Mz6wTG$jV^5ATpB&@b+hIF0%v+=YfO#kpi@Z49*nHOujvU@oE zG|2nP#RxCb^3vdw3*BDBqPcIz`pk9Z{?*s_wD@#~TmSjH@vkFTqMIETM-p`CQcHrV-|+Jo(^nQr}R$ev+#Ta8B${!ftM+H*$PpsH)%Qem;P zb^r2z|9JiOk&Tm=)RTU#%Bwr#C)aiT+8rGygonTD`n5;9tPbaW==!y`UmRk;Xm|nA zZ*}a^_KlXVUn{dKumi`te(ixzI@+rzxPC3&=}+6##V*c14Dy^fsk^=8sr=wW8(e0y z9)CY%3pCz7$}amN6WncXrY-*Lo2b9#Kg_ays}=|URq1SAlx15U+5+`@Vf*oRz%8ZW zOM{n=wm)qj3Qi@?pkAZwcWd1qTq?XG-<9^Y5AR3%@9e$UKKtHA@W%F?Z0~nU8@9v7 zBF${Cj~ak07N}t#zx6cmw5dhy+Ggj0SM~oOd^hi9;2me&5dO4mB>0LSw#93m=IUV3 zy;r>FL#}TAUHP&;x#4D4 zu(+vo(YerlUjN#r+?-RvW!j!%s^zN#-g|8av$cICaJtifxNBFFvAY=Z%KLeLv$oD^ zly8B2!%h1luD!Z$>uA%W{9uI7T9#>U>i9bR@V2+I%+xEZfd8s=KJS}pe%!DLX;vsS z#w_c81@b+<@?dl37p^Uh#k-kVj}(N=%jYyPJA1fx_=k!W&5f6LMEH+4YzxkM?LzPs zEw2n>54bVa_9u=FM)q<0q|Zll;b}^hTQt$#uG-_%Xho>JQZH? z*%-TdL@(HO`|R;H`>P`02D7v5&o`Y7`+rUQ6y*yPjI%77Q~CD6QJJ>VE1%%oyrst4 z>#KGTIh_~Q4Yp%`mcV5&E;UAXY7Cy4+Lh#(( zlfsiHjs&0I{EPUjm%2XX#XWuEC8oJK)Zdja>+olNqK?yOVxQP3k@=UKy9V9Q9t*t& z#N)vWFT1^lW?$|NW*6v%@Rxd*Gku4j3EuEnBU8QCiQt-D+M9bnaC@2qf9+|u=HCa~ z_O39<>?^kfJa!cAFT@@M|6TbGy>ygmdb=AZ|2aqNQQ|Ac{mcK2Z1UII#9Q`{$FY(p z>e}(smd881?b@7WAB+sU4j+y1VRu%xLnpNdPwCg(t{ULlvE0V*)w#F5@62CNPe*<= z+@7E1e(zAdyE5&#mG7f1O(jmnof$T>NtJ+Q*L>uOnReKv+tIdvSv|{sS!O1<8jUT_ zsu0V;$>J}%ag?2T-PK4x6+UgkAp2~wMTmcM{hoH^rabWLJw;Ek6Wh2k&*GmN*uCGK zjPNxxs@V$F+Jd__-W^se)f*ho_d@u}{6XMj`}7NUPIdFO2Ep6$;oejxJ_-+(-+ z@a91#*6(>YzCHKOHL*F_xYNa~+?~aov88>znRNfp_0B$ejDK`@MFn<2}vr4X)3v(f3qimb%|-cSEP6%!{wO zb?ol67Py7h1X<=^MlTA!9WV&oZSkeSyWPitcdh(9*0sNDThg6A%aNP0$|IjIjX$;C z$u{Whap7IZx^{2g&2%UEWj9X`O-tJ@tOZ?i8(+6+!Ry2A+?EfZ92eY~X^VZAv)xM; z=ga(KZ2vpld_nVvTQltK&8r5ib&-}?w%MAg@X7eTEZh2ulNWQi=4A1oxnz|6;%+y0 z{xeqZ0;Keo1INF6Ya{#Q+>h|PoX#rS#2)$To#0bmZ(^tHECp8S?)Tn+yupIJb0=m3uVEzH+>V9wne}L3msx#p7 zZgpN&JLAfy!5bRUI?%l%!PPHsV7EWt2%O9&$-?z}L~BK5OSPW^UK+MlU@d&v?i~ubmp(%SpRpzwfB^=9H-Id z2gBXj)xm9R4h}QdyWjEh^!zg6!b%Mhe$hMk#J?%r1k81SzvI6tuu*aT4mKpG&-Z^~ z)`QzZ_r~M?Job%DyX=FP;~d(m$0*zM3)e>+-?6`)v|Wh7D)d zLte964YkiTegfR(iw;_eSB#Wt|L1w4NUyRKU%nlgV=+ZIY~9uD!KTc(NT2`LC;XeK_DS zx1N0MPcMf@mviSB2barh?=9IAabDd}*;YHtjn8|3)YRTkuL;6$UC_ZcDpm=6M3r8) z(w%!@+go26Xp26-3_OI|{Fm-^<^JLO~8bDdwkc=nU= zO{JY*xp!AwTL0Nx++J1cT-e{dRNq!9*&Mv+KkaSCp_Rd9p6Y8?&D-vLzV|Tu$eQWk zAMVJoj~rGT?EHk^kKsRDmmTxF0{-0#dT)Z?9zc9~M+528dlreeWB45n{(qOwZ*R@; zcl)7HhZX8(W zhMg9snJYbO%Eb<4O zzUT!OeZg!8{<-_}8;ji#N9+j}JL4O%KUm7era04Z?s#79Ci6%dw;71NVD9`VfMHhkAZ*sXrvu5Wg?hm{#j(MFg?pIfB$@>d3@O{ zd)NDOz~j1S+Psf`3C?@Ncw6k_;`sK4xf%BALu-I%9-3iiHf{{oHeubjitcQa)nXGJ zhwE;-%jlx(UZ2l)=6w4Jk18_Wt~tL_z@gVXm1&#Y^;V4et|zkWy!X!ni=24JisOHH zekH9V!a4q`_s@cTIGt1OdJ9b7QoG^&P&4@|^=qyjOLyCKAoJ3;(wy${)qR2HqSq7* ztG(vNFi-w)ZMfw`H->pASRQ^h%#C5D9F@loe%Os+`tPn}*X?m*m}PaE+A15}80L%? z9c;eYZVYqYnw~axk6Vk_F=e1#eEm!Chp*43ed>nSf_ttRZ~JyU1T5`Rj<$>ao!d(G zH|hJp^uLL>y`-;1IQL!LR&splTfyAdaa+mZVrQ_nzviOvjJNG79D+E5yN|L1zHxKy zW1kvmw^e%y;ZJ_s(=Knk4}4{}4tC2mm5|riHcf4pWlg|&kE(39Z)^{K>+C%ChHKq9 zt38h_4`aRDxsDx8uM79pcl)!Q<`fK<(wRt>g=KYr{=a6}PV5jd4Ds7Ig8W3;gny|2 zKP5gOem3OIF_80;&w2-%8+H-5^T%xWi z+OQkA?=^+YgX>-W`7yRE(CJ(;%B{=iKY3BG;4xR&DgplL=5x$NLpDK%^FF%B41d#&DNi7ov)8+Ja1G^Eu3*>PpulQxG>nz7RYQG)pC3EcWI?Rtv>+9x46Fc4-yKuha7I|97 z+R1&_x4wC;#THtpWWA=Xdt*`e&mBK_-1kdXUg-Fq<+sE?dC#SP*{Wr6FVCive@-yV zc3OVd-<0~LQt;%{7hRuVFs&4POR5_~|9>h7E73Fnny+#EaPbPU4p%w8XmVz3Ru#v)51SpE^ny#XVck`+$`?Dn=;tqDZyo12 zf2AEUtryt@vXvm4kgdSqlC8$BZe!~ec7FWU`rdY5Pv^&v-!#;|Hr4rY`yLr~SMlTE z)7(#GmmF4?Z7SiYKN24->3}7Dq1z_!Co zwQe(@%d_M9nkj?62j{uJy(u`}&HK+hwZ5r$V{^#XqiJ!|?FP3_@Z7VjgW}8Gdc*BK zuL|y(>&8u2*H{z_|Koh__D1)_uRF{6;wiz<@cfl-zv9^;uZ1VxaXHegd_@sE>eutY zTesG=XH5>kx-2vw#JU(RU(pdPx`V|gV6hcgYzP+Hx^QQ6u#^Q@$_OlF2bMAgOIgDw z#RtIR8(^`sU&}H6_eyHNJ(zT1+q*x1J}%JymJ5b$wSE48jc;duX?Cn>c&79DU#b)} zH{9gv!lm<91Rct_I+FRosG#npuI_wuV|MI^TCPqJ$30V=(8r-~L;o$MX?>cMm-Tu5 zfnNV8+4_Cm)7EM2=2BhX7-a9yd>(Do$7RRbr(V7QT>t7U+wht3m`}g(ZKf^r?jp>~ zf9gHj<~@8g{JHg>%k9FUujF8Dhrci{qxqXUUx0$v-5k<@7Q(rAzl9RytGfI$iM3w+D|lV`)k&|RQ>oXO!oAps4pA34WhRJ z+_|At;-uQndK)IIo7%P{gY`0yY}U(`N*u8v{7~9J$F6MzOPdLnwiGOFtY>a}eH?C+ z!O~WPr44uN+IFzm|M%EZU*O|&`|S8{lC8)Eeaxj(enPqTY&y(5{@M)ix$82_>7|YY zzqK>Vd^7PXtXmfuInJ!z<<_eEj2dhnq2KGl<=^VO9%jrr`7Cqh<1J0K)7_brPw0KC zj&i4D#mqgy^4`4=r{TaSgVGf-pyyE-XYG&dlu8X;%+@i+w-3$GwbZ- zBwa$U3+Who9ZC1l>rOVY-X>%#>up6gwBCkfTkCC0Hn-m9R2J5k1(lKYWkh9Xec6$H ztS?ht7c?J?GHdz&i@7~SJ)-bGWvzQEtkb0VnxT0j>IKdF49ye4G#@lHPXu#2S7PO0 zKVRc;)DejfmUO_9K79Un7<#3iZ{L*jWuJ9>0eSM!T)@&i5%SXL-Ry1%{vUu6T!MHG#|veSoT5D5iGic#U@~}6`1CUY(ucv)`dHpgQYCM zQbu4YJFt`~SjrkcDLw!e-vEo96Xze?UPhig+HVggU0nU=|Ni;DgZ8&vFl?*slZ;6Q zGp$8&{LbC{^D@lrJT*}7Hffko9EfO3yOfVj=0>$7q5Vv zFSZ_SM?5+PT()GEExGV1%-5!!o@KA?c0cBEzkD{@?tX4?$TIXjVxS#d_!V&0vE6LT zo823YZDyWg2TeZ4a-1d9hxV6o#nRDv?c*QxKzPOV&xb7+4+6iJ_nh#ME60Khv}+X~ zL+}3aw|P(bGPbctCb;lTHwM*)ySq&n&3iw%_PEOse#G>{%z!VufTz6Bz`REb z9n6wxmB5|v>}z^gbZcm(4;^M|y^sx=%e2lg`AfS!eA3sDzR;1&_odIOCVr=~XWsKu zd)J=OYlV_mKH_Cwu>1di}9su?yW;t82ws;dze^Mf|+8 zcZSnT^Z^%|R?Swf)fRl&XMug@?z-SD%g(o_HZBbAbKUXBU?p2kb57{b3-{RVcCvyRsu}_%V#CPa#jK? zXC=V$bFiG12ss^nCWY&&AKUylXO4dcdn?pOTh&Kf)kj;^M_biLTh&Kf)klY_j}BEI z9anvHO!d)$>Z1eIM+d5pHmZ*{s*g6Rk2b20HmZ;2KFjyfM)lD~_0dN4(MI*rM)lD~ z_0dN4(Shot1Jy^zR39BzeRQb$=uq|1R`tg@qM)Q<*U!m z=rc9?tc^Z{qtE7u9~$;6eU?X`@p*Rs`fTn?IF9t!K0cpU1=Eib=O3ltN4Sg!z%ot% z^LOg(505JneOAAh8sYb}rF*==`nW&2ujBs9sIT;vh-?`7((n1e?}f3YqVULHA|Hr+ zAo77!e4zf#&trVFaK#`Sah^Pp9S$0Qz?@aeD`HoFBRl-V?GTMmU9S|`A+p2&&px2{ zqz=SdZnUPCC(r+~hp5-yHAm&x6YH)A%i3&IUI$ls>AI#lD#wGX98+0~*guZj7m_fv zF{v}h{9nG0zD?cM|9o4iyO5z~e`k~KkOux<L&`^8TD&ZXIK_M+Hsxlek|_I&y->VC3$IqAM_eDbI6?9anD z^$I^(?#{AheSb!H$nE2xONDo1;TOi;aq0Y6{qU1DjxT%j$gpzY?yf%fd6{t6jgDJP zDjp8NI|X_2jC!tMcqP4s$^LQWO?kukp-#@moqmmfRL1eod4GwY_>q(0y*<6c_ug?_ zWJvE&-3Q-~)&1^J-TSucKDbr)#I3qNZqH$rL_S?tt&2Z#Ad#t-2@9`C>hXWl(p4T}wMyzsb^;rSIEU-V#w@Z}fWdBdHj937T#>$uaVdf`nkk3*Wro_})qVk5^_ zU2=N($?aniK4-((`^giHd3qZ5t%GH*5sg<5-ZMN=*+pgde>pQ5t+V}g>ulWCyFdT@ zIYuOBR7Q~xL_QGtK;#3F4@5o?`9S0Ykq<;Z5cxpl1CbB>YkdIg^isYN!w}KEi^v}$ zABcP)@`1<)A|Hr+Ao7982O=LhKt6!;F_Kp*oQpY2`pQt9ku&NXooVpf`8uP{&hhV9 z@n`dl{#J+2Xyo2~>3npCnOeM33${r~I(PX%^{O~iw{}~G8NYB0c+lyiP3!JABF%Tk zjNFgA&nkxS`=*XJ&CV_5&-~F20hsx%O8+|w_)epL&yvIaJD2iSCa1-} z2ba?abNZ48?o7x#nHA zO^R!koL0$ir?of(?{V_nN9oJ)y&X6m{)=>!-8f%_a~S8rap;dFIl-I;$q#mEPXLoG z6K{d@2P#ffc4QB+t6|&x)64FkGiPRN@gL`75l41N-3RjI`S{hUw$EGc_YG+7TsR)S z^7R#Hw>C8WCTuvPANcSoMQxRs`@M-ejt-ZuA+9b`Q3&KSd$lVH+?%iYV&WeO(QxU9iCjt(bX z67hAr!~L1>W4SN%eXsP9NR!)m-&b@0>HBahChkiShxHM^j}Pa3 ze0)mhFMG3_$06)LoR90r-S~**<8YDJGP53jjKKOyU&cRTc@RhB1dIG&Hx_a2mgwu_ zvmL;cPGYPfc0;(>6D;|F#r}{}$_32j<;Ec_+J0>%jrEG-ZGF)<;23OImYZ4hHO!(f zSo8(cj}rFR<)X{$zsfODzHC=jj;yawKj9~$FTzD%u;>dpMPIPiSKC3`N83%?Q`?#J zO4wiIv}^}mUi5o=`AvBr&i)A&JAlPLVC^SjPlSu!V6lJ5c}cktyE?#O5j!hHb~u>r z;Kuu;fnhCly-vnX+tllU)G41n|Ciq=7_b056JHdisl_|?Kzrv)bL{us7qRe7?z&w3xs z|MLI4bRM6<@tFBL{+^lB<8+xhN0&FkYxr=AU(?5@d}{i1DE*o~efqbS&zF8)%gaOG z)$(#udbPa#lus?rkMosq`aS8;i{sO}CiLQTz>+>#@}=+DK9C12a)K!zmLEK3e8Cbf zzl6R%KHCAz^0M5Vrq~V4`f+|D58D~c_V9ADoj5;^qswvIX^qTrqj$$R?39XiP3`Pa z0rSx1l_}l=aI+_hnpdCu3e5lV|8pGvxr^5n-|_bx&gpTw%xpau7vXUqPWgmBKBW`- zbSVAMr%(S{pD+E~dU@zO>*b{Mte2niu|7Wuk8|D+>#@})eW7s~?{Il+_< z%MV^#t>ojJAIBGcef)s)lXTcVV6hvR_2c|F4*lG){>*F-&X1Yx#Q8C=c)iOE){Dx{ zR=l&*jJB1I;BvHw6=*Y~_9wT4f9-$b40=x!9E(+-aeei|>;snmok9N(rk_uzcwqW& zI(-kO^rlm~V9tf|^WimoIOpTzb3Q&D&c~WL;9C|^Y_Osy1muyux_7qyRF-EN;=Wb>-Jyw3!J~tTlXWnf1wD8 zen7Wu(6*W`ZCho^CG zWWT=8O5Nl((@LEUn58a*rH+H8?o&PI_9D?{q7CEkIb7NhFx!j5e7J8jIlgZ*IUV0- zavSN}Osm>VmWSg(25yt2&1Cs~n@K-Uw3$Af+Z@&l`7uj6A+u^TeZELTQTlk@Ry zrd4gG*Vo7QZ6^Ic?1OOCW^%s1&GdGLJYs*aYBTNh*FLM)b!CtG?DtP^e=IQ5s+qg* zJ;AKp@O5ziGyP1rUAMN_TD4y=^zJd>*6-aPe6nje_?*Ho1ubR{1Xnw;TF~XE`uMh3 zczwMGN=`8+BQ&T`F@66ZS1Ki`C=r#k z@0%9Q+;g;86A_h!Y-!KFYbQb~DTO4FR_)u&J;zd(B1`ryLfOhr_TM?j_w#%7-+A1} znLBr8?)!b8^M1cyucazNx@T-|pulqJAfY)~=Pf)cDBsslXi3&SU6%yc)^rH0$hu=# zw?Jskv$e%#DdB|UscbDXK~bo3c(Q=*4{1>qMy$W=NYB&v^8z<5P(H{4(rYL$Jp&To zhC<=uBSLQp8EB>G3sH2DF!Z1S1ffnaJiby`-s=iShv>klhc&`0L+8W4pZdWfag|VV zcmzC>Ujq^vN`x(V6U>|K4)k~B3a{lw!dHJAb$8S;l?fDa2*JR?H?f* zbM737kniAr%qa&e$??m(lR)pbMX>QD`R)hUz*n=JxwidwFt@=9o?dWpF>B`xl^cPRS`e%**91o=G=h}Cav*s1h>P114u85D!kTI8K*4Q02>S&>*}-;T zz2Wc~KNQXkY6fTD*}>hRGoiWoK1kJV0-4kH1Jn0@ zU{Z28tm_;IM=5lGAs_6ZeA6`Ol>Y{NvS|W(hm(PvauD#Ldk#;6D^C3a2IHGR*UnvF zxXxPOK#u>q-49-9>IIEGcF-|N2&YdU3~x_s0f47Y!}EO*WdNW0)E)10pCq&0i;Uj z?d^83dCM3W7HI-Y?VG?YpONrkKWk`f)C6{KnhCt3GJ!GqKHm=E!5zopa73FOG{r-q z^&$s&eOMFlx#tQ-pF9js?hJ?BarR(9(NXX!Asp)VI|il|Xu)CU?4a&MDLCbZ3k-bK z2%18AfvVyZsM*>G?mQj|#y>a-ZpVegrmZ``lskGbsLT%P2Xuij_35yuv=ONOQ2^HO zi$GdTIP}nN0*24L;GCdFP`auTTsZ3s<((UWw8~ttP09p%WZA*HLtU{)f-cJyW!vO% z|K?6WW2)EimFVyBa{?O6qBwngc#$(SBJmY+Mhfq|;R{ca_{#c$5Lg=q{YiW!?wpS- z+Bd?jB)-&x=JD@RNS+|^W!%}$%?*r%he&+QzOWPM$E<^nB)+VUHh?m(aA;5Bt8Y%b zC%;RO?mvL#5RptCI8?61VjLfB6iK2k0nGy|1{@S6$4Rn$k{9GFnwOv;r1?bq)4PVJ zg(_@)^F~Vj${aPeephkAF>2m0wtwp-JHd~)N-QtE2~q%3GzLig_K!UaGLCvf8rNk# zacKYKI2PA&3WgYj>$A8{__haZzoH9iTsJp{0}WjxNaOlJ-5XB4rVP-y_FOUz_&+s) zt|YFj9^K=T@0SA_*NNvuoX7i0K;wG)A7wCciv^@{J+CJZnC8ugG_J=iNdogXEP}Zt zuJ`ZT%B?W01@R=Vr(G)JW?!>{G_Gg%ivt!WOW-IH*Q2VPxWz7YfX4N=?1iA_)H1k^ z#Pzt#{kdnV^(?Mudp{R``fUwqT!#)<0cS#jU>Aw&LuIcVH#F9>xL%#`PTc;%8q&D7 zdjEhMRTB(HlDM9eI7j^BXg!PTB=tSq+1wELj>PrMvMzDFX+4YUD=t-h!bvMgqi3wx;}WBUGU%TfTSNdmy7GndoHFEf9 zaVMbX>6~0*;x)gbAlP!4U%lEI3nIz0d;1gqZEz%} z*J-rbSa`M0tcvbAyVg*+XKGW!IaEv%nw2`b;%#?&PT`EPJ z$=cjTQYc|}PZUYk+tfM)8H?%r((j>F$Q96Q+qc68-Ws@mEWPGYeJRJm%nVa{Ng5L*R5j0QV#N_xm3L!t&MFGWCqGrp*f24BCQEkn;moW$y8% zDBMZjw=Tt7{Jf(cjUl-uUQdpf|9#*uo~IZ zKc*h|D?Sj9ChyhpFa##s?c#Tl_Znw*P5gJd4c5!FgRi%@2=@wX@XiuD_{7pvXmqU} z4cHzIbEe%8+DFu*B=U@#&t-7yCRyVd$PQ{ho56jSszZ}V?kZRL&PhdD;*u+NaJZEW zmoqUG&+uym1$r@D>+c$rOP;4kinei%mqW1Yjz(ZGFpE<^Q;n3!bNRBfDNye+!zPdH zV1=O+i0l`PGw(HmLEX)qQ9%WoMcCl^eP1A#V2n?8+rd}1xSXn~5Fl&jam-uVA$K6x=`JJQ(gL z3DqiG@u}_S!O`RQfPsbr_H40-cV_j2C)~avce2i(AqTw`U!bex{1>Msfm2Jv&=_*g z^srPgbn+5(gIq)7AZ7U4>pB`suJed|7WlMnI=V!zfB$zixcZ|QA@bSJ+1kS2dTKb4 zyw~}}!{Fgl7bGN~eP@ItVKyb)8h#$!xRnEzDUU;^$@lh7LlZ{4$Vb}byRB7ng)2k* z<7al~!OR;cz_iz6kOBGrcSh;Jg=VQ}Df#VuH&2GooWG;TYUjb(_yVvlRSl_=-|pS9 zX>j4XHz=HZZwk`IphtcXawNa|LTy7>y?s4;{m>3>u$c{89Im3=$|f)+q6{=We98aV z9S-gKo5HPvDQF$J_tXw~L)G)AQA0BM{(UOI+k$I+61n%@H~GSv5f#Xt{O*p5RlrrL zj<+NC?Nn{@|6}P0WI*oc&GY@Che8^38RUl<`-a-SRa1VK@MIiy2k zq3OLf{B7yUYm!)7B{vwyzMIW*X3Y2tsMA-K<K_^HqYM8wh9~+>IXpVaD zDhdz2;3SA7$J2ba;sLjmz$lWVWHr~}=J~sUC&^K}=LX{$=dOT@#;FCjNOQTJ!psh~`_DIg;Y+;`=Pm&%UN8wy>;b zd0sVDUHoPFZkFexGslQ$TaIUWKC!_-+$Ddyf#&(J-A3XQ8Le!E}*&e*F%U~Cl7>KB)=Ku z)FOMOW--mBGfity%YF}@=2FF57TC)35>IpKG~Ezv?ia(;T)MBN5}n_Bn5Vh4cX|-E zNRdV~mxc-ha97h5M04qilS|R+`cy=7=`25GY_Zo7CzAKNnWT(U+O7kdOMP;OV@WSD zptZCLdM*84YMIwN=-}okNmADY>7I z+fBjc6MDf+a{u(`6{2SgQ~}MU5)tlr%8OTEBDu%nQi~CvCkJRQjY%=Yft9O(DaoZ# z{pR4&qRSwQ+>`AW%23GZXB^F?YsQ)4kX5drpqu>fnD2udKJnlixu4IZR3Mvz7LMl9 z^Q-4!H~CY*jpR}X{VH_8r;?+&)LqpA%g<2-i%Gm!xB27RTgjl6#MG!$HAta$WE!ZHV?fiuaa z?e64Rx_7rD&80Vrg7NFe&D=PWOD|pz!TrsZI4P1#GkZgD$sHR(8Od*hE?VLC3>Ti} z(oI9mabVJLmP=P`G{L7Tr=nJJ{@ChrbVuO^Pjjhl%PADn{|!%bX-BdF{_C}g<pc$li~xkX(A%@dO&! zrHe56-n7y*aMsHLG@5+3=e2$D{&`iXgXB^-uN-vMK)`b8{RA~E{~DnsYvL1` z7I+Ma1@okbD0Zg;rn$7tPSNbdq+G_RTb3Q>Z_KsElyCcTY2SRCc=sl%ycEcCZ=(GU zR4H1=)~|Igpp_F;*=viBe=*~=9oRW{jyhUmRMppqSQ$3)=1qwbddFz#rcAp zezL+RWL=Q9T5wWPMc7W(ZBEL9HK5lsS<(P1d~t%VjoHGOr_%8A7+;tYTqrE9JPRr- zLt%wRh0wty5Zra$2$#&M7RF3U;B*&7!DkaIg~@TJd55c!&?}}`sF4+ouJh~R8+26Y z-CKrYO;^B$=9$6^V~t^(rXid?t_B%fC4iQMZD4h67#^P~Li-i`VEOzS^r>YF3fN%+ zr`X$I^}i};;<-`~Qy+#u$VtMgRsG-^&IUiu>j93b17W;@4Yt=G1=YQ5;ogpF1kb3z zj4c9qN>q*7>hFNaGehA46&pNVa|5`hlnka;gkh5@((vk?iSWz1Y81K(gTdcM!jDom zICEJjaOq70-%f?$KWl%0({j_G?%Zm$@#8BH)a3z}gKD(k?QtMutOM(Nt#QHwPq0rW z8@wzE!-_*DfdMADz^X6|2VT4YtaIiW*Whd@2qjqmvKOI&9H+W|)7)ti%)fRJGSJZ=d$HMTvx)#n=I~*2vRU!3E zC+=>!9SnbCjb+`FIQ>B)@P_QUXtkA-{t^zCe5gWtKIeshmqfs=e@Kqot}iZAu!n0t zkhuM%%_Yp_fg(A-j_W0%;tw8pkoBnJGx+Ul5pbYRHIgmb$!m_YgJD0d@#$<0q5Lca z&d}>0QNt}#jWm}2=5y`G!aO+}Tt4c!SUd!Qx#atKZlTDp z-ok^V{4o4-f*bnT83c3oSECEp?9sb{R`AMxV|>y4SaUeo$OgM`Stu!HF|-*_gJP48@=nj{!Rz8MJTl@q(u($n z-^bLT89JC(P^kms$vu;0f1RIqtp;2v3&Y7nzVK^FeM!4240i1APr<2%xTWttaHjc;sImd*lKb)ZZSA85>Rwcan z)eFAv7>Ly_ofZ1NS`KfmxQm`Yz9Muvy9TPQ+mG<9TSBq?R`?YSM}vpm6^6Wuf;Cce zMOox{_qMI@1C|Hz?N@{s7OjIZTN6Qi^I2i@;b54Qco}F`R0$0wd|{5d4BUB?vEu*d zw*}*+g$7641@zi}e3FO3k6#0N&Gq+R2-a)%7f&U}xwTS4OPS}Q31l54GgO%Jix)YQ zb$XSiuuU^f zg)@x4AP?7)oF0REW|w8-&&kq^O_d&+p1r49D7{Qy>E$>HjOHh5s821F8LabS8i za#7cX0uOT>>|KqjbR^-$8~t$o3u}Dirv+TLVholeap(MWAZ!};4uM8%oKmp~9Fy6L z%*Z|Pd#5ej>^cfZ7giyKuvqY8S0d6OIlr6(_8(LQn1ufiqGbAfuDk_|WHF zfU}H2sX1YIM7=9az9Wm>G^$Y55Orv%b^+z4TH`B0$>4j=2IO=o4DWHD0>>*!;w4`z z(Was_FeE1&`5p+vp~v0fcjvF@Tw5h7PZ|yH=9MFjcxxP;eh7?xFc%F>CD(Rj4vg7< z4}~18L~q>n;Q*V1$Y+Z+E+3x*2CK~=y0$QE={y%Iooz;G+bWSv{V`yp?22CR3BzYk z_`#P4M5u9fB^vH-0%z34p?RCE@kEtEu!=K7e|M1>uUHIEafgu8yh>!h%>wT5@&O)NI2E$4qr}=r~I&kBX7>~#8#fmeMBfLy0FUf^5~&N&VO3FIE$$$7xjsWz*s9}v=uVcwStu8iXPXOWOUS14#Y{J%_r+_ z&oH9vpEp%X7rE83)9X2N_%FBN%U1S`==;0~-*5vo zdIquMPZ|<|%;JBnyY&aDp@ffMuiaI@uyn%W5_V4Uu&X64&uiKGv%gNMiq^mPs_mWt z!p~Z;{UdbKfz2v?wl+AVCFavxDk* ztGc&{J~aou*a>)t<4*j5-yb#7NN*OZJ0s0 z6a^1MIfqIam+rgu9yL9i4nGqv9hK9F_WP(aF8w}V7x`~3Vq7}+a6c^bb_&!XTw0eU zi~r`h!T`dhJbH+1Wri>=?Y9h~rJ;F@OQlv$L;72D7?+CQs^RWo98uA6w2eg<}bq4w)x~56b-pluOUOX^PKLG|+4+<5DxXy)@>Gjq+ zR5i7Vqg<*vI2_Mej5*4s<3k$Iu!MAua_Mzv5gMu(&rvSz$P}aMeH=%*^zU#UZT_pq zQ7&C$9gJ4#o3Z~^G~VN%uV*tPDiwCvMXRui@}9;gGqDx297{Q{%X%xGSE7nG5=K3+ zb}bJ3mW)yeqwWGhxV!iU5)wvzRp5j5$I4i&afxG9x+&x5r>kl>;A+db`qO4p@z$3u4U`pS4jYKmzE5C`8k3+UR#Ho5EV_4s ziug=$17p-YBrR_F`IH@(N$e7-x%L-R{#)t1l$C_fwsGMNBNNS=1 z+haZNX~UUKreeyd38fMBS3S%b8_Q>ftfI9^AN z_rI4VTuO2ZWz-B$JA6fbE>9V?Ledsje!Rs~M!kC}6nl2dqvhn;m$D)R?@2X7LF8Gv zkkrs@lr#}#RK2d{SmYFe29W1$03!93NGW|(8B9?`0?Z!ofqnh6DBvIMTAiW52{dM?|Ysys`_Uy95Lc1I!hQ;u~Zum z*^Y!*X@N-Rj^~XU?EPuxa zQ%21mw+ER|jYgDF11_oIdAZ{-Wz@WiN63vEf+?exM8u&8r$j^AP7KBlQ9kfxPWC@~-I@e+kg0jo-EW)TgV^tAfatcvKUDde>eVw!% z+Y&~7bVKwA2mJUA9>aw z%BUHE>ZlYi*Cl`H_h&?TEOM78{x(brQy%Mk zJx_Lg76n;d5m82U`Y4Y#KX{EOqi$;%EOt1wm(@#A`fzb_)OZ1{m!1pM6s!5wJ5m;% zGjg=})g!%ny55_tAwK%}Sp!|qd^b$Iws*FOt__zD66;B3iYSZTlamr(Y_Aki7S&!f z4f9pKfYvP!&(1}qyCyI`T>L5=x2VnL!X;{usci&an0ijUzPB26O7f`pTE0->VHiI0 zlH|?nmwDsg)#zTYEq>+QB3AfhgZ&_n?CaFUWe>tI?;u7m2aVwy$a=XL;3M;uFlEkb zs%rT6jVp*UXWXU?w8>)`qRbhgKME`NM}XEs;X)nUF+C5^T4;Im9K25Y4xs$0{%tO9 zFKYsnIiE)x;a%A~0cFmQ_X<$)En~)Nx~WzNxZ%klP!n*n9cvLI{Rb5aM;T4>@SLNy&^q4` zoV(o;Q0CmHZ;NkyXya%tw2btRE{HF1v=&+K!goGwaXUYnsSI=K4!&%rv_64H6XEJ^U)}8qdQQqSeM&UiV z2vOe48aM@uumq;OH*!}Y@=74jJHmUv#S^e!xeTVfm-XialIv%ODDQnK%0t5q0iwJY zUws4}HJFYl@4Znzj6#3UL6rAC>HQV#i+(GjEEoSv8lGR)izwrD)C%Ad33HY=oSdY^ z1CO+`J&Pi{M2nY6GM*_nIV0MbuPmmuzOgMCqH>W2=^6>QNrV*5=Mb_g;jX|p|N_EiYF1j86dRm{6Dxc7bl zd*8l!;NvHGyyfw0cFmk`O!T3)=K#Nj4`ck-X3g)K7KjLxN+R>T-3f}5vJVe(BqGAnK`E1D78)xoqt=zxKY@XiaPC< zV#B%0Q`kkjM*+FjN`Tk@Qm54H*Ns)_AY14_HJSX_kE+7 zF&i4O8&tV2W6XACNjRwAX~vlCxN$M(^0A&Vo0Db{u<2aLn9VCS2~6s5#F%Z$%_dHB zZXIK`Gm{&DL7N|AHp3C^obC?tJS5DP<#-7sZ=K7SO>X>g;8LQ)m~9Iu3yzGhV9e&c zp%XljoyC|<35tNpHVwvX+uT(^dh;p9Y=fFU1H+f@jM*&BM+07?gfUxWm;|henZlT@ zJLwvDvTYb+wh2q@L8E3qW456dicsb;nIj?h{0GAqV8O}3jM;|PIfFYb#~8CUJyV4z z4m&bt8~fND>>Z!OnC-*CB|szc0Asd!R^edDgfzx%=ua=mdoInG?bE8-(w#?iSe>oz ztUi|F(^!xAcw-P&j=2UXv-RaDkKuE%?tuY}sZM`igdc>yXM3zJ4aL9L-)67<_9nly zplmfe=ckF4r8zucYv&QArJ0-Nvi0Lf>UiavGi?6}8*LmBTg2A>d)C0a+8Kzxuf`g4 z7<0rMQTFS$ZzvsN+-XL6@AU2gMwM}4=S9iWVQ@#`6}I0pN*6AO&SvWum#n~!AzRqzExh=f zoAt_u)$!Kxj~r)PXs}wM_Dv7rf*vvlL>O{g&M?$uxRv#tALt!Kt26Q{~eX;YI$mPNlR?oaMUQ&E(L%o19wUlca$Q`)MX=uYvE&InBw7pF`?knDC=jV5#(RUyuJGV*80&pcS$c=xEn&-Q zjE{MJ@!;Wz@!tH7K`8oiDC>QzR#+ohhY;5LUO7V#dCjzDHO8r{bog(&JmbBO-3xhW zD`qvu{B>JV+?xQ_`*!Y~kL1^zvl^p3sef2~YhX3TM&lG@K6WYVeV+?BhB8JiV!iLS zibN!{)`<1Kk8Zle&r7LgHAb7uoxDSEHLEdRGr53lTIaGFqt5Z;NN>6h>wSNIA%Wz- z{_A}g<=;jA2j;LEqx;KOWS-H3)fmI-F)Ec9#d_cB-kM0qu!PkZJ2+G1d$oYo7{~3E z#w#yPWWDcz*>}-{hM}zYz5B~J6k>3K)fl@sDqyE^POSGmL|YZxEfBEY_gRm3sCUmm z*83i{U^e@lG@IjjOzVAz^wRA=nt^iQsZhM< zCac{IJ7X^Vo;awUGN(nEnefB&5=UB#Gcz|5T5H(~Xf4iKS6kTc!wvyG-t4C;T)eS{ z^^W}`WrW!32|Mni{6>&*OF~HZPnpsrs6U`2r1d?mqJx6+jiZFLb{A&kCqOIogtTVZ zH-@UtKldgzSx1l z)~lH!+WQW?8U`CxdpO$rPD?{zmb0{w))jqAL*awfYJm2>*9{vBb59Hcln?jz^5Aok z97lWKyZ4drs>>VD-uI1(R&dib4$$8BDl(sfV>piXzNa2o4rRWs2dwuUAqJ77S8}xX zJ#p4Dc#ibxY47_@k{Mi@8xANRhJLFD)1MY`wD&D;Uq~8HMS%9c7jzoJfZclm<->qQ zb)bD|6GwaBTTl7HnMoo*d*6$bYQXwyk2%`=)-an3r%!7EwD-NoSqHkNw61v8a3&nM^EIHo?|m7g;M(aJ(7NK5>{Fl!ssdV9l+T?8z5ad&w655%wHTZ} zqYY?X(Xnk3jNUB;X+C;( z_P*U8q=QjMf&i^6&g<2OK1!yL_P!6#{tB+k%R*XLn2yw~j;tT33`WQHPp__K^0zkH|a&Uk#NYtt*ay9S;h>?*O!}n14nAj+x{HY43X( zZUwFhYLNE6<%dUuFHw5{tt&oL8~_V{PJp!cZ8&8exOO82P)6Nr+YioKGZoU_x8s(2 z@X1IM(z@b=>O~;yNhY9mMN7Ho;Aq7xNPFLvcE`Y6WnD#MO>Z4sjLna@1d7vI=6gVq(H;X^}XQJI11F}e?eTqd^R(mwDAlW@FA4V%-@iY0=f6r zV>&ZGA+(cwIwca*nfdfYDcDTV6w%c4_w3Xu$+O4W?;2Wo{&B2-0O*C(Dxu93?gyG7VHv?5TRcxklnB@_8LM zziU7p`t0~_Z%@(8IofQ$XG)q#_sMW}9`2G@RFt5=&VMnWLp0g@51Z9LIDH%Pt&d^) zBPCMni+-nz>CF6-jFEicfLf+MsyhP24|{5v{>b=ut@v$%71JM`cD}%8`3E!oQM~Ia z;li$3ra#Kn{w)5vH-zbr-1SFti=#rA{^-%nrg_EnnckE{jj(V31!rau}9!;r<8y-a@;I^Y2s{6T@~kGOgtbpK~M(;p>0 zIgj#3sA4)Zf6-C{qfARoXXe*iO-Ex6WHJ4b?%iRSld!{dW`6Y+7xdxpVWvO2GN=OO zZy1T`%)I?&Ih^<#VmdRwEzt})*yb_)(ez!1P?(A~rZe-^>iu!nepgIq<}XeggP!)! zXZoYW%wDwb&16hx<^@lNp^%&craxNlwH=*%uZQW({EXU%Xvl33OlRh!yZ`VFE~QL= zl+wHa%^z&c^hbO|D_R*k8`GJ2gLj?$^r>Y`e>AuoqXmuLn9j@xCbsfRG%J|?Xzx4= z6cucS>CC*oWiHxVKOfVX`IGU7_&C#QraubI{Ka4UW5M)Ci$12JMPB}x&dgV|$MP4J z)-e51#;Q1UyK*t6GxH5@laPFI0H!nZ*NXH}j!Ph>GxNg=()mGSt(g93WA1C=%RwY( zlll3dvPU_WA}dU1=G*Vs4#G^V6=U1|s`F-Q$fq766rZe+;bFOpyq$}9W{85`l z;QBiwOlRhQ)VTrsO#ztB%va>}0|)g>+06WeB?;i`6+KL6=2Klmz|`!en9j_5%^w65 zUl*~Nd1$^3NX0BB&*vt2(hb0GSC zjLpnvnpJ`^4kIz0nK#~90mkL~VmdQ_uW=k$@IHsl%tt|ze|CDanfY+!3JgmQvzhs$ zb{BzWg9@fI^RB}mgUX#AY-Zk@^974z(%H;BEO-d2mnyKCd0XLIz@M1LX6C=0UJ5GG zQ`yY?P|F|SbJS!uGaqzzAbjKx+06WmmCDdynIoH--@frZP%)QgGxL8VKZ;C0)iP~( zos1&B_2(|rjCa3v!#B&-+5hgZMz2IS^3I8jT$W0=@OTIp=*@H_S+np7ex0Z8S!kd-An`CH@6=q zx^;`@PDFL<_r3k_NP#4#TJ=A>!?DTcdc?Hq;hXSVdrw5Q>fz;NPH43?Pqpf)%8~f- zpRXL%s-G!ci%U1{1yrj(@NxhybbAD-Ry`rk7oVFf&9v(F6AvR9#Ys#vp1a-!hd4+x z&G;SPI%IpHTv&OI=)!X9(2ar0;-QVx?tNb{+ByYrY=ob|V(4mj& zOou*cvp$}BE1vmFz|U@YZ@@c1b?7;zGjVvreL!{S1KUf{Ak|+S)uD$>G{IkzW-)(> z*WR=7%dV?{>d^h1%Td#UcIGcJcB>CgdddT;Lq8Qn`l)NqaMWKSOV$EMM+|5F5<^!l z#OA*<0o9=gT&h9ua^gAaFHyMN3a>cKb5w^udf{UHtRMkU9eP1;E$VQ0=cvB~__Gw} z>IVU;L*M-|5WnIz0M(l-_y*$~rFR_Fl^1wgV>!iiLkqr3wulTE*sImwMv>9rRfpL zl;7a~y2?`TH^yu&?su}(ZQF9TmLeJm{%{N1e^`DD{5djW$~N?=Gb0x0qd0djI1*c6>-`W$A{?0=AC)JQ&M9yUSkN zH|MOqu^4OFceC@~9qogmwj9evfw5}1)cG{qA1|SW%ch=S>%N?sxBNRdr_~ZtCTza< z)=}cQfsitx_*)JTd|L&n)?1^s1H`Rd2C3FNJzNnce({7<>piK}7%oc#kZQg2_PW5& z%6gD$y_YT`|Fh%=K&qp3$O(p*7F`BZ>-}r{I@15z38>cFDP=3%ARY*)*4y@d6nv_% z$bo9T^)_vVzdkA;s`c*sds*b_2unO6W5OA;OrdMk6vl*W4ZQ?YvbBX&&zN&IT@VpF zTu60}5%EZ{v2l=)>L23{bqG%1`6Zyb$k=2FVSW950o6;YbSnz)-lz~zCVaedq%b=$ zfgMlYp(E@!)sF3V4lop^PpNaH=PB1T79MZ2wWa6xKV&HEY!fq`{>JCk;O&WnJk?Qt zc3lo*dL|&MNnd!ehI=!;3Q)~snSUVoOV@#F9(y!Gpl|m%p6bVSO6!4JuA7i*9?f`bcp=b*qxx|Ji%>W` zQG%!X@$F~ofK#Lz(>yAzu!51sXE~}LFPRz&qhFLdQ2lsMZ!I|KH-%{)S7?R8#6Ss- z>c{iH*N}T~6Vp7tnrQ(aT~`8BKQ8JGhFwQbb5uXR(yIz&i%Oa1@u9ydoH%+spqj_^ ze}dp4xqg7^$3^88V2|Ymrg^-J1EExw7NGj^D>uu){={~sd2Gud+9vr3K=tDRYnH(d z_XU9J$9uwy!K-fr0M$G`?$Ln(%}Ic29vuRfK)7xzp!)Go&kBI$@1cNd9wn3)!B;Q| zQ2jVRDjzs~)&iFK;qdxAO?dt8abV(P4^Qoy2M3QT0aRDM>t+tvSz!-e7KB5MHZ^E? zObmujw1?_GK5+ReF`#<$_a2AA{k1M&MqxP2xIG&h*0zA`tneF`xPKFcveFq7(=Rs7~ z9+0CD0jRz*w$KGGy44?kBd=ZHy%QXJzX4FKWsqw>INkd@pxhXEXdIM0r3`nHYnZw+ z8fcy02B?PJ??Df^;w%j*Lmrzs7Cx{Y4yo?)T=sfkshbF>hJE`(bC|tJ6H*Pko<=yh zJSz!M4f_=5hrm!r0a6XS`9>Z1)WsN54SR&YFIY}yovDU>41W=%%~F9>!~Sl!2J~pL zfKKF)JegQ}| z?0?=_0Q2L=0M%Vqv}J>~g3*v_*xUW2;JE`XkZRa-PU!-Zv=e~pE-M%Q1gn2df>gu) z(s%^$ol^j)?$XS62Uveq4^j>Locea4t?mJ-hW+t$36SMh3aIXK%fUrJ3K~PIyVMQ3 z4#aJqkZRc9zIw%7iYxpmwxA>TP&H+Pv4x}HgS;nic%=!%vQsG;_T_i82hD+dn($# zuZ1yT;b)Pk*RY5AhTYds5#^gmGtZv|2V6x~af)mmr{35w=ZY%x|H%mVc98g@#{7T! zK9BZo)Wf=hU5sP3Vtw%ISXt&LrmzX(v$u?xpP0oWZT#){MCK=UW!-P&FmD0#6AQI1 zM{7r|V18n^PdTBVGdDx(CpOLdi8%g#6r_G)TVL$wid~~1^%ENzCCyD(SkD+Tr|1>; zRUFJ1Qs-tKs(fzBe1`(-W@5|g`+)LZoKzz=uWQwW7cwf8`3_~@ zt`zvK2!+&7%p(Wz%|3O2`iYg!`^h&iw`9IU8+22|wu?d`^%Dz-*u-mE)iU29YrW;X z>!%P%{lqNK9ppcjRWskAk>efEtWjpncj%C>3_AKg2vR?>y>fT?i>RFW4h1N$K!1=S z^BpR1H%0U31w!g4ruq0YukL?}`3}`7cp~H30g(EM9Z``(fk%s(?@+l+8k#&rhxrc4 zmL{Rcf<=(}iAjs}P=nnG<~y|0zZAU-9>sizMt#Xav6>5*@6cp-8#FYZ)EP;9jVHbN z%iDY*^%KkfG#)*y%x1nr{_rC5+pNNThqABSMxO#^G2fxPzq`n^^2|@{xy5oM8I;0&hnm25@ z!XcMA<|lS>mI^-j!k+nwP5Kd!wp@u}zC$ot8cPg$2Pkuzza5D`$6GN!v4bXwsPxc= zf4)PL_M)@xq0Dz^j;bQ|`F;mb=FEIzghj5p%y(#0ge5K%YA`=BiL(dLRK3~EcPMs) z8jkFL8c^ok{nQRyi&UAPSoq&VD0cTG<~wvX#u;}ll3~6>iyutFvnzf9>L=FuM-!J% zKEZs4`o`}Em+##BDoaQiFZkIxQ>n)T8Na!K^99Ry4x)8G*mqCg*E*kyDeldk%j$ci zrU(1@4*kDQko*Vy|8?Izre@K_14nwZ*Ah<*!GE3@(c>?G|GYAYrW^j}p+USUgbDxi zrdZgiB)oI6g84#ZoF6HibNZiOMEx2aVM5S99|?0sL*WYbfBq5~yN!fC%D?R?M@cjo z2)`Qr^P_llV2lvi{qw1?PEi+j2mSM}kiM!YTxI>w*W!Suq|p1+KfjBNpU(uPZ~ysV z^!;4KD+6BspI3(e&AD*>5*fy#ZN9;93x5Sr7OmA>2mku)29!nb`D}%ouP6b^qK}9k zv)&vED2u-K+zP!k|9N_x4Ot7Fl~NF8(KV7m5R|kb%A##Mec-VWS>`*Guj~ptqIH?? zklB0_*rfrO?~vb#rNFu&mDT-Z=P5(8WJl&Z^r^WL_-7sFsaJ-WXpL9Y{PW6)x@kc) z)c?FP3Izc$zHJJkUKvt3wV+q-ZgqUSPh z{P+mM$VmekH(Kw02tc9&^BwXsdJmx8zq;S&UmL*85&!CbTU=s*ebzQs_v;uc0YBgB zMU)#=tP;VO?HgF#&t;k%9O~bRC^uf2rU~a9w7`@b)8-|C(f7ky-Ea5;U1;&#i1`i$ z&Q1kwpO><_AK#<|b%(Se%8fSl7O-4Ollcy*S7idX7!OwWE8DIHtKK3+xlvKZ7H)W~ z#(amYM;!(+A1AQ7pSOx5#A(XRcSxT6U$-_Eu)3cW@gV&2x&Tpb{JPNv`esNm-=PcR zP7uFGT~_xCe>(=cOQj*ojdrBxl6w9pqTG1!#Yr$Nd<3ie9sS@2f2sB$%8d$(i$FlN z0;~IhWCN(=w+T^h{2S>BSKqphC^tqnp90h5-td$g?`|-Gi49W`<;IF`FZk5y9HQKK ztEwD4QMtiWZj{ybh0P195aq_O>kDDO-2I61VWb=Jx@p{oCRFn9jgVpuV!+T*q)7wHY_+Ks z;6iQ-N11K^ia@wBNDokE>%Le9cGW-QD6_3dHH6y5s{my-Y_JUaYAywo*~I&bL3fTE zW40M1b>ZK^$$&E32GV0$7#jm9v)LOIg73bnjM?_x^oMfSlL2M6p>g@({EyL$*><;T zLOIe)qs;bd%{(|t<`kgJrj&dXsJ^jh%(n8_aCl{w7*J*lT;KykdU!yY?Kj8<^Br9n zvptlU1FuzI29()WtZ;{`pS%K;*`yt&K!2xRK$$IduQEJv{W_q`MtmC4f8MhVGI{7f zZ${$TDEiN{@qyhTq=8m5b}}9`45^uKW$ZM3NUX5m%P7W9*B9A?cP*P4I|cL*t?sjb z>~yfJ7t|kL$k?f6m=;_fJ(;mnGhr5Sv^`^|zPXWjR0{s{s3hK%Q1buSdhfWL-}nC? zNogorM5RS(4^h{3ou^I8OeloXE|Ha4BwNFXqGUyBNm|$SJWrdHy|S~iM@BZk=W%$y zKHvWM{r9|Gw`;v#@$BI|?)S&>zwXNUC*0&;-u~-&bSTTMcAWgL`!Ojm&HcguIw9Ru zKX~~4uPd_e41dXj|8+=awc8>2z2aZDq{qHfl3UgPIwy@kB$9VS5;3#s478&Q)J-w7 zwF=Q>zr+qnIHT)dUB)JE_Q$TszT;a{^^@Q5jIND)6EQi_7BgGp(s|@+?Rv~?%M+fE zGg)G$7c*PQ#F^yc`q! zHr*w|$i+1~F|#S{FD3iOb;ZnfaDgth{nH0CTlIPgSv@xgGuw;|4SG$LU}n4c%8p!c z+lQHL_4jQ=t*;qowppIv$^5!unA!du??}=c@-ee1eOpMT)c3^9HmTwTaVQ>vna$#m z5@|SGh?&iE&@J&EIul~IshIXEgnN5Con#?J^0yEpOrmZp) zLubrvCmMW+!Yu?d+x#LsV(S`)nXRAsIqAf)RhZe-!xN<^wOlZ>y_;qvop`tkGn-BK zcI3^?aLjD(+biY0j#pu3yDr!Zy)HXrW_x-$NY+ifzd#3Ut0SAF#colU*=*+M2z_2w zVrJVrw^pc|?u1>DMJMwWi^bC?1d*PVbI{KXylEf}oI44x`^kZc&dSO>&yATIv-aia8TiKchp@ZLH z%xpWCEMk&xL73UfPo=PS{ikCG?2V&qn9fs6?0^-!Ze;&;Fp3>Gvi~}8ZeKGgRO^Zk zFHKz6G0)G@A3SB+TGz5Dc6}LUxs5x|7ly^7^Gn4J9P(cWPRo2H_T-TNdUC}69P(d( zj@Wxc{_DLF`*6sAeK?Y<2McpoqWeru`k1i)`m4qMXZBy;b<2B^*muqT>$?_vu-Sh- z*kW%s`>!`UYQK9?fA;S?7X`mA96tBo`@63-D9UO0_x;7bYxZB?wb+Br{_DXOdnpy+ z)&F`a#U4m5nU#z^kl@8cI}~C+q}Xriq4&Rj%kg86SAG9qhvc@!Z>lr?*DV<-jFR{N zU*}|U>L&TJ|8-Fg_mj&{jn%|Ctew$gxmDP|?n*1yHVSK(f1Q?LcG?Qw?_byDO`EQY zBbEO;FlP@lSA=~h*qL^Jo|U3T@~<RBMnY$zxooK zar*}EWD85?;EY?V=^l%@9fC9NgF%{n$tYi(ai2Nfi$C7^ue(xj^&qbK+8k%x4t{=o zVmB3>agWIj=SB^e8O*rJfq6VVH-*8BJF(wVK1!y`V8*SryoxpcxTAn`!aw&S`Bv-o z0?dx@giVnC7CSBBoN$$Td)ZL2(-OMTZhR2g3nL!^=DY#odA_3d5}p$ph;xCTaTD;I zuziE*$)qRYIpI!I2W~S-%s=Aq$HiJ@tiD~P0Oy3elx%s4vnPW&@3ME{JpH>WgE_CJ zpXie0To&M*P`W;hYu&MCFz4MAQzCx%7Xq9UUN^Pk)yozznDgHMI)g9#6V71H>!)16 zKB#D5-uoMG&YP__F_`nZ)CTfbdsi};^L9weW2cf0Fz*csn8qKeY+*3x&Ayt;o;8|b z-U~K1=35>gU@+%Bd&Zx))hlH%=e4<+!p1@0^^)jch}~QonQUm{NX&Z+G&}M+&@oF0vH-hCYh@edJ7IOkpdWi3k@xq!hr zVRLmW{!!x_gLA@Dvpo3OLT#M?+GQj#Jznbn)aIpN8={w%I_ zHqMs|29>Zcxm|I-JZNZp?(~xKHR5+rkGEkVVpk_*&XuG*@K2@IBQmM zST3CZU5>NnyBf>clRiN>Yu0ZbB{Yj2t#D2_Y}7U(NbGKfS@Wfr16e1rD;4_LtY=+S z3>Eub;heDR=~~5Bi3`q}*Y&qxqs5+8=w}O`?W3TVt8mu5!L=>xA$GJvKbzi(Btci~ zbcKGlcK+>zO=9mW^s}8&zAWuD$^~c5aF6wLjI@TCk+^q&_qrZ}dk4gQ1Pb&2?IU=c zu!Nf|=}BPbJJ~;$r={;BF!MceZaVL$(L`Y8o37@?+g|R9{p6B!_Iy{f$G?7ZgARO8 z!#M0GSDJK$MB5C!%Jq6{1 zwG=h~+h5T0LR-a@z5n(atk!uepXK&%-@%y|HS*=L|MnpK3D_;y{@;EC@60fH+KhjD z6W+IZEG!#;7&GV8-U)1SX%J>kgSk~KLGnuqnbWEwk{>v=Lk8!Bh8`o?-iJ1LPI%$R zVm9qVPt2UFQ&d^9W+7%yUGc2UHPHh5$wQnwvM&7(VdiuVGhtau2QhO_EXreVpBQ20 zOxc#r;%fsia~7Q|V`~=sV?TLHqX%17l!N``YZNEgrwDz_oXI7eT``%6{p8DPhO%=N zJ27)^%elfbANycGx&M)IY{%5?m^ts*-etFsXkzB^K~ zHnBs4+G6Ikxzw7c#|_4Q^63xa*u9r)F>}^@YR^a3Q|u={YrKM)uV0CoQ!-D9hxYx1 zdj}SD>B8SPxnMuJ^34tGmSrqv&cn)@e6r#m?j2B!?#>mf?J#qe9!+B($An1{p4-q(wUt3VdivvpvT{KI)!@&;?rHZh`?-mZst_JNF{^7Y`V*bqpZLpQwEu{ z>uvG=q4`b*=Y-yS0{L>MRRm_!zM&P&vm{Oiv*}O4q1^Oje*&}VTDNe%_EuK{v*|sx z&U{XBj0|SeoeKZYJ4P-LTw^#Vgun0qf8H^$ga18e({h_4xP~k$o*6RH^}w06$Pfx5 zXNcW0c`r`dDjwl^BQHxT%Ts*(3o~Wl4FB&rEnl1N6VHSSztERV*m+y#V&;!#mE{dDnJ;}g3o^sKT&kJkE!8`sM(4Y6q@5#YCZg z$DA6(!8@L3(}w2+Oy=Mn$33rRn}^Qi;2mo{SjW~*nvdRb%kSe-ald+jgOLJ0cV*3Q zVZ=+Z4@3MuAJ=tNl$z+EBmCg1j^fV!xpMH1U&~Y#$~_LEQ|$efxc{^Q#d-p3;c$#S)Uv@IKq-idBOshDs+U;6ua^?;hq4FaGx)t6E?<*fg>F8 zD2$I7FqwfP{B3y%_d1=xz!5&FW6yoQPh;Q+-)vjOj{PVSpfAz#;51%4c0U70xVV!w zzasW`fg@bkvx42(RVP4SqM73qe$A@qqsaD=N4j^>v?y<*@9udM6JRlJTdaD?BSE?}Lum@sgJ8*03`VbV_q zj_~8nLwMsIWe&YGi?`@-!(;UfdTB;J+|SOR@?hW&r?%e1+&>Ow;0`zUkZ{WwJq~?| z<`dO;){FNHdTG=jh|a>*aSZwrw|sQv51)49(3kjThCM%NX~Cf{@oAS-67SwgVL9^`GU!VjF~2+47W-$RmqyL*6&rd|gM*K(zJDF#@hcegC7M`v z;SJsTa&VK&c68*w#q(QmlVj_yvY*9z9NgrC=J9OAgpCaP5=Sqe!*r)@V&Ew!yll-a z%sn}H$`|db+1G7G96V*!q)_(NavK9rIeG0TX5C{X2T!?u!(%q_+E@;rvRhaVvt3}p z!Bg(EaU?t4xQl_Od}mvKmfofkB6cMfM0eC#+lBL;38*;SFp15bJPm(Fa4t>{-4MDs

+`z5OPjw*-Y|9V&U=x2HO=GmdA zocPC9!n3T=JMLq!QWEHDhTidqE+vvMUjux6)c89Rjf<-2AcwYTB~5wu4trp-mug9) zFQ3DHnB`}?N)z|(l7lmHJHCI3v^B+DI#|tH{9_X?fr1QTJO|_u2)!XgVmK zD7N2@M^8DtW24M?%rf+pcYRnQ?ul7|p0YyuIMHYqjh?d8kyg~(c?x>UjoBtNR%IA^ z%H6t3=#Opo=qZO6jiFUlozPPraVm(eiG0bRGv`+NY`W~{K?a>U>Kcp1IsH%uojGJ1 z7d*9QqNjY`wzEJ~1@x46$3)YE-(L&RMN_y|LA1t81n8oj=1(l@+3G0o#H!+pVA#4-OwqXtG`v|a%v_z#k_EzY@ePRI>p-# zSSu!XW#|-NAh%>=+s;I%*!Q?ZqBMk|Q`|aGgN*+bg--F=fo;jeiLU4rU(|goo%2LM zr?}m3Z*trq0-fUH!+Vnt%n6<16D~HgUZN`vPI2$MQKW}744q>6w5hU(X$l6;$RhVu z;*K8C`4ycJn}xx|YPdZ*#d$sV%G}0RqfUr<9?tDXWfi@#i$=coJ24S^b-)=B@&ZYGYzB7G5`VBn0bYK|s`hFh_V#(R_leY(vY{pHa2ab!nIDg$Tah3FlA?r(%H^P-Xt z)bfTn_Ys|ulB@&aLdxYxeFMNWYq9 zi~IJ5m2IqA_!+B8>-%1n8o1 zUnjB&Mq32vqFEZ#n+}*zCV(>%J!(VIwv?Pg$Z1DK#{cQ#Vd(Q#=+Ecr7d9}+W-W8t zy!lJ{lhO|O`15Itc$fTfczx8|jazORAwXu_>XTcfBbUQ0nBQHywMa{48NPpKnq4%& z!5Ob7id|>Jw$}p2jRfA)=*-+A72S*Y+McP> z{0Dk^*lDvme|OQg-L3I)MW>XaqFrftogLsthdFBF`?vf(65Sz=E?KmMz<<~H;$`$q zpE?;_uPYMw6Bnh);ImXeJJO7}8tCxkA$f$eUsPd@GgV1Y!v-CL&*`$eXa>8HnzMDIdf!AEs z=)%`sYR$lF_EE25hja=A=&=b|V8B%dxud^aaM751Xu6=kd@1EO6CNp{zifYK7W?S9 z8U5v;LR)Te-V*&~$M33qO4t7$!D37auE8U5uxPA;6BFh+m5RirzA9%q35^1`8= z_@0jUu&+i%vX|~#oOhkYA3jloQCJd)`guvfFtCvS?Mg9rsKQ z#g4?NPluR8qB;7@=S+&(k61nQm%A8p#x@yb(TN9U@|~wMWYFFHTI@tpYciBUclU`OZam!Q zvOD<87VTLfu(`87OCgI+wvFLq9_kCw-QC;Qjqh*?6CjJKTQas)HeU*z zIc1w?a?N+!1nBNwEoO(GU(X28-Q9j-Z*KBQE-Um#5x=W?sS7BH7Vm&?SfNN#gQ~i0UigdfzeF^x>e%9|K zr@dN92Z+}%f1Q))#%Q6BeC=+wq>XAfeEfv|R7psqCA!JkHD5jAMHd>LzbWmidzUs2 z`24T!*H^Ezwa4c?yJ{|f^voLl<>pBVawj7*DP+->_sp0;E82K+BX)P!*Zb4uRc$Hw z%bmInq3zVnDEQ0A4DD&@76}D^`FVXOx@G$q3jXqWrx#?1_6!RCa-Yt7iTb8k^p{mS z_a?I%7E|aLfAg@5Oht%Ce|gG~TH$2gGW3_TpU1HMm*UW0z8oq3+^)PBQL5YID{B6D-E#G>LfWLfUHK9I+9Vz(BZuOepb-Us zS*tLZxXj&7z+cwMctMU9kD=f%?}*PO>o%BE@Rw`UClTGTI|*dbt{ZQY9*2D?_{(Q> zN0VM{a|mQn&kpCwzy*F3{AKgVWRhcIO~GH@*4>?Ke4LB^^5MgIqUt}rz%Zn1c$RD2w^p|fxZcQ|IiL-d|`;W2sB>Q%$4E<%<5o^-7RTTQmAwO@) z9)BrEe|f8hD%s>8jsEf}r7T%ZoErsy`R>czviWnW(O*6ryH2*oEC&7Mfw%5SKL(1s zxy1MPQ(Y}Hx+q6~SBS> zZFYu7!99ll^6r4Yf`Ql@4*v4Aub&0!8CUd|wf)X2R3aJr%U)CZvAKsM&|m&}&W2^0 zJEOmBnr>F6)#m9Jv`yZ1tWxyON0K|@xB{_87Ingk_zLuw zm*4&)*m)g6e|e=iyGy-Vg8p*T&1|MuWP$#2%X{qBZRO0=)ELhxZB@S6#?+0+T({6L zD!($W4!mQrJMsTLr{!x~{@Yw+9R-nx#62(OQ;yjN2A~H`jmqru>xRz%kB9uf=d^sS zPINqt8?zG6ACjzGXxD6a0bG^mCcUJ6M>tl4s}kt5h>o1;%V4&fwrm#F6n{^{&aV|= zf%JRsI|e(yxYcN?@kkeEyQwSPX}@8PINOzL8`GWxJ<(rw&-_C+whqAA?(yA>=&TTT zXo!5^%WezFU}+rs%PCn6vXe8Gp}#zS(tAbQTk+^GxBSkXFTJUjJ?)A6$ex9M7sg$5 z#64vNi9Mu~e`=yf{OOK~wEg8UoL_gHqA$&h&&Hi!5um z*2pW8?qW|IxGJ7S2PO0MbZ~C&@M?+V^#&vKmlwraN{-yMK!5qn=&c?#2G-~=FSOWI zm1qBNx8u@>dO|DhfBO^FcQWCNcO?4D&*Mjs<43onzdY18h&-%LMSpo$MAvRI$&=u#}k%^+Lxq;nNd>R{t{<5!?x$N)ZO5_-AK2%8J0;AAh4qfCc zYrI#19OHoJzh(2rI-1lzhC_SAkOCYj@>D%Nj-{lZPT&#WJwqCu^Uw(If2r+vVg8ni+ z^Go(*-amiY$uo(p?bHMP<$F(q$>~nP=r7N;S0j2>1vu9ZnY@B*`WA@(vVMaevD}-7 zbM01Vc972POwnKdUMKRCKmPg4bDM2R?1#NL*Y5r3Fgb4275(MP8^vU;?j-b=BmMi5 zqGLHY*WSt*F?l%w=h{|o_lT=}G|sOLkG~=#j(X#qddcTAr2e)J`paufKag2PO6V_V z>}pL5e426RmznP>vcoeTXUzd;*OA}V^Kiag{Ifm1zW)jC{8HB3On&{Hjx*&28#~e< zr^~qWD^A;n9$ROIGv(2b)5(w<6L6+HrPPrc&g_OWWsRgvvT?x(oGI^{+?n3`A;+Cx zr>!M4{)!gPl+$|eCX>zj;!L?sjJRX5)dAf3715?2b@pkGGv%N``^Z&mJDe#$&m2S} zkG8>?a)H?a()*Vw&XiA_HK+NKG~D_1Lu&+G;r0r5emxjbK&Jdw!0(@N~47kP%_qb0NyDgpH6;oS^o%JsL7k|u*4xIghy*)&=- zWfOy$^086DG;n_~gPHOak5C%sG?>9mxwzbkmNuOJw?DB}XT=@=_f_B~JCAhX8!R*h zaEI^Z#&ZSn#CxoI^tI}(5A_uAoL9%a5WFbA3&-=`dFmYeWydiQJoDWJ z2LAH0Hw$=Lz%mB@a+>y1en;FN2fMamfAPDzA;Lm&cDy(slGj%&1lW09HDwD+{V|Dw zzg)U<9b4};mw~_R@aSo(%K!82kqeh6kMh2Z0V2`%HdoLclb{YepMcF=_ z>t-1-U?cVJh42+)yczh*7Zwz;3;kO$@Ruj5S@N4}*E86o{c&+HKNSA+x*_N)7WT;uLahW_%ZgY4CYZVde8@mq{}^X^;*d$c>`P3F#Cc?|sJ&%V1^nL}R& z{&KK~0e}30Gw_$YDf#hdVz(^#%ev87?2+SO2LAGq$K&{4y$cNd<>p#1zFPA=1Alpm zd@Nd<`SlI48zl6mI9u#PyR~j+K8ss(@Rz-QK44LH8XRWF{f39J3Exr~_{&A_ zCNU$$RtEmEui^}=*V5xKFHR2c#M?)?bC?m|F(1I@&&y`uFGq{r=1PaVad1ggSE%vx zVwWk*h+i1>W=SLVpub!a+LMj>xgY&yMYqk&cA+^3m!$0HXLdwyIENW=*yN{d*6WcR zX2jn5>MUk)0s71K9cHl=f2=snh%N44WmfBaILwH**MAqx`xc|W+<3Z}?TVYkVMaVu zp2e;`58yB(p6}9!`7E;IFe4_fV~V~MU4^Vg?Yu0g%8*p_cIQrspivhu;JI1LTvU5$ z8U1qoIG&;PmoK2&rxNfv=R3I2l0 z&FGA*$#JIok5KIqlw?A_A%1SloSC`i2y45zEBed77Us*N_vxU&d_zrOo_C|s z895Xi%lr<;p})NI^HrgB+A{Q)O%^N5&Yz1%e|f@Xdvc=Z67-iZ#Oxx^?B<}q{MO(p zY3dwI!5MKltWCWQd?+|0nxAZ_G(|?iUpCVmM2D=hpx`fi|C&e#auo{xa?77rPUmjY zLfy3z$g8!17PQ(wl|YVNyL7QUudgxs%Udi><)epLqQCr0e?#>VZEN(G<4g{_s}x#G z!CyAr_uQk0R!=E-H&rG+l7`l%QpkkIjkZaA&Kcn29h9a*kriYx?ty*W zHj}uxj3(ejcWKh5ZQETVz&cKvx`{|tf^iS*;-T&7qR2)9ZcAkJFgo|b4+3t>r*X;T z?aP@2SVxaL18ICfTMACJQIBCviuKV-G_LZp%sy4Z2X9P;gu7 z&N&kKt3BvM_n)?lywmPZ!EMP~piHkE9YDct3A45&pC9i>C%Q23H_7NZl!DtLF?d8e zMvtQ4ws4=Tq&xAU;I`CkTTR+tu%O_!1Qywl&7W;4xGgH=vrNn0k%HTj({rgTa%(wy z%1&9HvZcE#&`lowJyn+b$%%s7axU(SRMEZ)edGbFtED$@JEM;rXlqK2E)PQ=Sz}{= z>4(rN^pU-NTah1i;pijZIS*qmMjp?Gjngib(X4uiv|%7$?qP zfHSPf-Ykp||2>XAa?fU|=7&i1k*6wk5k?)UL?8L0Z&h`JeiZu1OPYoYj=w6ebd zB%ECDh(7Y7uPcPI&5`IM2fJ<)vYsFP=OZ7pW*R2;=p*Olo)Cmr5$Gci{Z%a3t}R2i zg?4Ps{`?9@AGvGAIiaAb6y28jk$!B*tzPIOH+%JC`^SW$k8G#%LpZ2YjBZQToR#e0 zp&sZXmtL645;g^+k9=}Odv@=90lF>XpKP{reGmn=UVE80%3c1RMt`}h_6a$E z`Vzh7mcL(oSJ?0*%W>FgGdgoAA3t4H0=|>FE#%rhr~>nxOWJz2{uKiX3=$PZn>1AQ**0YkIS}=LZ>E-jbkUP zwx477Ceqk}XEf?mAbJvDv*gumK(Us4(c1E}5g?uB^h?<3*;YPU` z_nU8nZp)JFO>ErA8ORyBq;%q~TVKTfnO%mCoMs!L+tNR02aA0&967^{vkiH{w4(&_ zTb{og&l;(ZZVTVFi#`1VR&GN8Da!GSv||!-SQl{7gwEa)!RqLwV|y z-voT*O=I%eI}=^x3?qGe@)t(&$Qk~Q^5&lPZwTZ)FONd@t4SF-!-?)=c!$ut1bpPO zSH;X#_D5fxB(gAV0*cnAEnM9r52HgRFRe{xm+T|7P;u^ECN5vw}Su8!3a_*yoQEUod%( z405B=$zY!McoG4(rT6tvo^0wydW#t{MBI`6ZrnpDWXL!}7p~vCQVJPTd1E+#si8%{ zZSmk$tf1QnDR71^Ppa6D5e{bF{S&`+1jvxKRbt1RS&|GgWN(is9zXPv)L6`r zJ4B8waiNL;oMD~FR(P*x0%phwV#oPbH^n0&s>w(<6EAp%MWyWc=s| z@jU&v06y}1nFAl7W{4d)E&u+WpLv9p&ghCh^1Jjmg$Yl+(P8nQc`whnk-#~gc*ght zp40NR;x!RxugDpSXMIFG4@Aze_nJ3_$8O>K@P(O1`JI-o`R_dN|DMzGwaH3-xxs5E ze4n4bN<8=5Z=9KiE_)`oesUjYsUtsj7I(Ug;J_I+2ftySZG$*)hFxFeFsHAv$Qh2E zX(}#yT!Nfokm*KA>3ea1h&aQI7kZMmOO_yK*ssT4GAJ_^IYV>btHjVh967_5-=}`( zE{Vcj4LL(5I+7M{#>g3ZDs#Do*tr1n*4ne1p$^Z@1#W8Ri+t zSd#vJ*;yPL66y8`4412&|y9pi#H zaE1|9E7^Yg5abNMr`WMpkDWMhhWfhg7_}-z&Tv=2d!c7#8FGf-sEn1LjzG@P=Vznv z^Rg=k&Txv^RiQ-W`GGSm>0rPPicBZWcB2k72*RysWq&nt zhWQS&gad6A$Qj1?s0mNT#UN*x(8p8KV9*CS!x0(I!YF+KIYX6miIUhwF~}Ld&gdmm zNMevPjLcae%Z+eD&T#p&NeXR|vx3u%(_V-#|RhvEhhrN{{63^#RkBE{>RkTdM*FO&6YP#|ZRov=`L z=C~X=!;BHDNM|05oZ)b%aB?ER4mrcM+cIT)eXEf(Y?HQ~Ot~G1oS|*mUJ~&?&hW*$ zB$6WOg`8mrv1=%0s6fF>TKyqx173%bJBTVyy%wPe;sQuvQ_x(J3=^DLxxchk0zFyKcAG>0I^)0dMVCl34xchkP zjm}bf{Q%CCTi!Q}O3O*dzQ)KIhPF1LmTAL~GhCVAPP_OzB4_xjeiY5}(L>Jgpl2Y> z=_u}+5xb^KPtT&!vkDpP<{Ncq5$&*YIPQ;rkQ`5E?wKIKZoUB@meCI#j>up)-=+A4 zba$&61USQ!(_&~Rv!et!!&Q^SbHB;W1UN(W!gkdB#9-tM-5&aqYSk>{3~TC#(a?5n zC~$^t7Vi?hkdZjswY`3Ugc}(kXV^II2^kZlg`DAn5?%UslLR@#{oY+^e;1J<5NErO z$yf47Uj;eC)yH~L+1p+mc9$exYD;%5|Ajm6EQdsqv+cJcXV{c!M`yRUM9%QY-T5T% zaw>9$fnrzH%Adx_88-LRq{X!_apzrOSQ4QhRwHM4tXf8A26jTuuu;re5gl&g&O0r` zb!5WuMC1&k_70$3ZmA<@n3<7G=CxVMV79w@%uqT_bgY0g^#9S7<_XDtqxof)$+{-*?P8Bh%E5*IcTkFMtqh8DtVCP+jfqiIvm7xH$-N;|n zWcTNE+{+w3Cx*5Yd0^Oir#4tYlpoH+z07VbhK^y03fOtKV_6@nx6(%noMFB?BZi$- z1n8!&ii)8fo(-45&bvXE-DvFO1l-Gfdjlg~FXSkoo7(pJOuDb)fDAap4Hp^NzU+z| zx~bJZMbjBGUdmwSoq50BR59$)AVqaJH*?X$)14Xe7WHc0XK9?&|5_Y`4pYJo47j24}mfM{-G`ZXcZOj#|`( zI+vfpz0B$X8w)i?U4gSW{%}Se>p9v0v)u0iTD*hNILu}(b6TRrh7apU@bQowBi@|v ziPxEfl=%IdzmXMuz2Q%xw{bJR=bfn~g~10N;q`mT&B9QXcX<8A`!m~Lp@N^4@T7sI z-qXVC!c#AaW|pL<@R$K-cxdlvUQTp5aE8-D+<0cP3kS|n z`?xvZSuuzMXV~&*F+9IierZr!%&0mEb`##JzMQ?hD|;q~BqP%%~N%1NogoH4gmY z;y4+9KA{r_{&1>Pga6Ta&453=7`uzj`#1_SYD$kCtayp&Ly7$1&z??PrMWu?{;*yDc+qt?zdS0sOp#*DhO(1!aqEyRr4^8VoaFk4b^%n%vHH~!NkkM#fTG1;QpMslgb zMhg6)psnH2eAOO#!ho1L)twjGBTqQK)<`~NYcG5}>|nfH@!kyC!hyO)@_DZe@bUEL zH|4HgYWV!rbwA{%mw(2LYOqy9k-q;DX4DMr?@5hYV@?QGlPA++}#tfOs(ENSG ze_|~1hif7TQN%4q{;>0LZ&~7wc;pY$A08IAd|HP5;l6z#%+_}y@`ndSU+=#2c~Y4hp)(9%z2Ex0f~)#T;0 z$rSj*5zRUz|927chuW6@{A=X)g>L_5@q0)Lo2KawmEmjnQR z_*f~EG>QA)fj_jnvX*ol5{&%e>>uuAkC77v{_wqGEa{UIj{ISTzbdIzccs7|4mj~y zHn(FL@`qW}nLP80ME)>M|E}z~*slWop`N@W$vYQ?{NW&%LfMv%ZWQ>#sXGtIcGOiN ze;8=DTXv>qCh~`Uj(3vTis#(GA0E84QKsrHNB;0z4V5jO5`+99d{NdI$o!!9 z!-j*o!q8hYkv~+5Jt0vSa}w}}4g7`R{9D}JB4*UOmrsT7Lwh5C=sqJyF)@=Nf7t(w zo0wf9kw3JKv}E1uoRL4gp4(PX>%ove4D2rM3(g8h{!qKWyO1+iK>qMe+CpZtIu!ZC z_xmO?qj3(%AI8p26SOACkw5%3E}M;*7>N9#Rohjp;%YDC54Zd{BwTtS{y!8mUaDy^ zd*Cq@`NOAaXN2MIVkeB455FAZEb!ta-PhX4AEsA`89#MD@`rB?bhzqR8S;k# zVz+cj*FDG|UQg`86HWUfe;Bm#GaG$X75T&BoT)6dC=>a^3ssiftCt<}hiOBUc!^Of zK{MgCCjpgO<3{VitH@lA=$ z?%rDD5BHQxc>F_MhN3Tw=ttOuV2Gv_e(eR0`iBG z;|B9X%T86!M3M!bb9sX&(vfPigbHJNM~Ogc)_tunaaR zFc34U_r|fjs`v?k{VA2|S#0U537AozY3^g8HT^K7I(QvmT8*xlQ47nc@LzQcG1oQiI95n|YuG_{eLqCESINT(d2rqGIW1q?^55*@*(MRsKaoEiI`F%# zPW_ypM6^RCz8wVcIrZyX{_bxAK+>uL+vt~^XYiVR?&uW-8zr1QGeIZeo!>svp4-@INo8ibM8XeV>Ztt9fykfwC z_EP`Qv&b>p{rDm=>-1U`{E4l|{~r`=fzB><1+1u(+RI_)v?*tiMES# zNB;1}gjK{~S_1NiC)B&pkyftA9|q>EBU^(OAb+?xw>|wd{u%b_I9pm$Wp!)h4?Xv9 zBA?#{A%8eWts|9py^6g$P1k$Tlhhpf!^eT?B3fO6 z2YciX2VWaVTYXnT{%~MyE~!j0NB+>w#++W;v5aGYokv}|g zvnM4v^RZXwh|Op!&3S;mIv+n266?)>u}5)Uy$}6sf0@Dl6t$K9^dTu_us@}B!W8;K zzK6m7lwz3;?K*fc_9#xzcBHpA3)rLBWq~toHP=yq{VBIURg&!Y||A+SGX{p2t@EZmAfr_Hgv65_4XD1%NLwMZ+f)@2@n{VA3=LTL8sp#=7)tlCvX zJi7joLHD(uS}+~-Due)k_+fGZ+44sXXU*4co72xL(+G6hSRR;0Z+LAYz#rc1b%4Yk zFvD4Mbf_`ac0GtairX~hTf+{Nd+Rk#)RzkpO>K zd1W*mCBILAKQwROnXXJ@1bP$?4tyxz`rsnYkyjNf@$7b=an8HwxP+^Iwd3$_^ZWMO zCFXTX$RF-)=OYPN(E<6x4LcusZ0xCr{Naix?(VWf1`3!j@9;iaeff(XUh9n_@+38F zyzZ!!EU&O`htD6?wo3k>TNCn!E$@?;la7$2xUR?_{`hf(^x7GN{Nak-L&t4an}4TUzydgrN|!+)Y!^C)z3x#@a(R~%xqaO2mWxpx*k8QGnxZ`=;&(A z4{7w{z#pDGu!!kou4TXN|4a5AAxjWiN`ukw1K9K1nd$6^ZIKo@(Tj(e{<060fMM;}KNs@5j50BsN%OVEv zM*gtcTI>{BW5R(yw4&<#lQ!kRA0FRe!`406hy0BE6PJksz~ z@U1LC{?Og`1WTGRfdhZoX>&GPo)W-;Kb%Q7Fvra49Ols@)y&w4_jcmUu@5zP?;xD* z=ZyTJ!I*T>?RP=`Fy~@BY0c3pqMh{A!tZekAgT)2^(S#jh(z{_xhYeA#*Ni~(lHZ{7?b z{a4r`e`wHOn;csgj{M=@9&Tj#^HAgu`vo@24qY!n{;(!%5lK+}#~*IKIhmAR2}b^K zXG&|LEp~##?6_C_X40HB4f(?)`F^51XA1I%LvL>(R5xWbUN6hmrrFWgks(Z-VOR^scQe?o?^I=tBmpKo>Hio5@< ze;nfu*&C1KwLOt z`^Sy~E7)E)Q|5T-D6)ducfQF+#XC}91&!~e5xZy8D6oQRzY}B`f6I{--12lesTEy0 zUR{ZT#$vtl%9r z3$mvy3|YYtonYzs4OPers`Y3~4txklREIQUvHtBC9vVxKN+QO`yN@N9Z=cY)eSVSQ!n7Ma= zFynRwvVw!N-v~U+5m~_$=b6Ih>_}t<>s7Z1^Rtg4D=3-PlXbaehpb@s*b3p`#|UHv zwH6f$$yQ~^3VuKQRhaWP99cor?`MQA^Gk7mO4GrK%*DSKg~5%SzgKBd^#?KbW0+m4>`xbNElTplT@cim~5kvZ>7*kykVl-m~}3 zZIM^Z9j?y(lL_*QS&a$oTSgM{iZAxI;`3a-V;A?slO6fHB6s8!TTe@3C!Cfeujr@R znR|;4CUkN4FI~%C4qAx3;?irXeE-Pj*u}l{t2s~jV2!+@?c+42*Chmb#p;>bysz7J z?Bf2r*P5G-5xHbBL*C?D+3@z0kyi{fap2C&jgeRMnV-Ri=8nM(**M35SKa5>#ocM8 zJ5TfOguLR8$QL>UKO(RBGRzDmc0 z1FtyYz*Jsx{~H5d(dO4IUKdorfLDyZy_i4i=f;3n)O{Jxug+Yqfc+_*9hUN@&iVxQ zr!<+x@vlaU3G7cvJSfgwmz|J7hU_xbfp_!jjQj8ER|GM~(VH>vId;?L8`euO@9mvc z&T@CA$spGqeeKAbcDE?bi$aU=toO$8!88XOqg>E5y zb@)Wwi#H)NjE9}HCa@<(zqpFISFMr4o|IU77oKo9yBc!c^3CDA{n$7itgVlEdxWw-|r7ZsYRbi;e7A~;2=GK=YSf?g8Dy zP_FV~R%G`&P1y2TC;$-zgHuQNr23+FVo#uSX-ZXaVo!IGjcRH_Iu#N$j z`0YXfpDgYU0WNVG&t+c^m^0uK)w&z;Cm#}C6HoiIb*7&3{!IZ@1jOVo}Ouy4?%$6gal=!95pK&+erooi2KCOn?GH8iA zUp%K12QIPp*9x|-?Mlp+xksAVD)9^ixWs*KF5J@4P`n?VA}7=qvjv`OFcJEG zSYftwF*D(jkL)>ci66h;Ve2hAV76@e_jKz{E52;eJj{EF6Jv{RMrPQ-S={Tm!+G-^ zTVv;T%jdLwt!CkfBG1aLkn8?C1H^gs|DJ>XNXzU0ofG17Rt_IkH0W76zSga5rN?hc@@DtGFOHia zAK3Cc`-?N^pmz(Alk^xem8T5-!C>zEBYYVD>1e`X?tCT2Ry)C$1)!MVzf4J&s z0h_zX7`eoLx+7&B?$5-T?@7PDlF|!qIP=Y@-YZou6L98xuX_)^bIx`KT%uKy3Fj9} zvH$S&vC&-p_e%yd-?$fE{CnmP1~XszQv>evqL#tT_uB3Ktm3IVa*1pE_vaS}YI2zQ zx_fEyQ+uCa|KSAXJ#3lrP~;Lb=1chPMqLgwU;lvK+}FDshna8kNoDTT_#OKX_oZhr z{Wa5&OC0t8F?HT?HGh8`m)W32Q$t0mG_=sYpL56x(LiLDl=iSCG7>T~vnt7`v@}%r ze$KJ?%2s3(Ut9L*ch39j_vpX#=y7jK^|`P6c|G6HcheS9P#gtZVwqP@YUXc4dFQ*m z_$wJZyaRBF_pLV)lX>%jOU(B-qpDvWDervE+3)yT?>>}wzSTV+k;wC!z$F@ASV7Lt zSP5KWhQ|`pr(i8`iJG@m=>qn8#yj839nKMzAOqkMhqRkR!m87NODw$Bn&$5I1TOKf z$`_J!ZX|GtfdPf2s+}2diOO^m@$9|}xWt1^-sEXwCUA+5=yl?#F%G!IU*((0-PKmW zCCaXNkmMcvfJ+Q>I!=a|PXsRUUT6`CyfuaL&bQ`39GUU57jTJ=YpsaW&phaSPi{9L z1$_#k^G)ixhHNkjfzJ2i?!IJ$NpIj1567#K`8`XZ^X-`!PmUDNfX=u5NH3!QJRCaT zxW9kJ?e;E|cfNM`fq2=X0y^JYja0O;uY}Hb->+6=oLw|@zA9f*#lFl_$DK3f)3U|c z|5ZWf>vN@C)aV}roo{qmiWpxR1D)^71MS4_`EJnpcI%KO|JgSdI^P?Ayu@RR*yPLHbc_?2()PA|V}S^r?-ljGvgfJZmv`TJqiiy42LFKsx4rBU0DBEA8(XM+^2BBkpo}VxK?@lE1YjN&8kM(Bzttgm4K7W!%}gjP=yrKQ18L z*_gaDQC63%@X`c*&Xc9a=|dkK?0-XcWvv?Y%O`hzlkKJ7Bm>xU`_-$-L$j|-I2-w- z#6TW6?;v!|VWYdt)5_xEkCJQ-~-f9Pdb&E1T$i#Br2 zJ{`f$7{6sLF)W)7o$oH`L$P*eIdr~C%uhM5ektLdFR85{27|7E|8PZ}Ke0Gz51p_6 z>SS_moegxpucs6cXQQdm`Iht&NyOWU(E0Y8yPIs-*aJFWzpOf9e`^eMzN4k3r2LjC zbiM*nA;p7Bp!2OA_L_WQbK2ZFGbKQmR9z~B&iD4#@5J$n7j(Xdo}D8*f(@YaZJTRP z?hed_&Ud!DDh+=)5ISFB{sZz(stuj*psDWUpz8tXd@Gpu{kRr}&R6^5U}F3&8#>=r zW_om#sylSP7yo=9or6@N^EEg-kqmpi3p(Fvt1M{h2nXnV|Hzc+o=Zy5`TiOo%D(q> z=zLQbTGNP4*3kK8?~5ajCR?EMojK5fzTag5o$r6~sT^|CS@7gp! zni>0??MEslpW}Cv?a>pU^KD<|Pd~4}g*caZ#Mz2w_T7%Sb4H)-39o(S0iAFA_mio~ zwsJIsafy0DFWPGABE-4G9m@`q-^p&!`G$53qKzx|BNxUcHeJpmqn}wr=eyueFb#;> zijFWYF>AOZeWmV&xO3*|wql~ZP!l>|o1`$>bw~t?VO-+dP-nVsqaotXnYMbRT=}Ny}ssS$XahEEhv9Ma; zTwR@`x8SAuWS&wbEc|JMvlHq0WL8r zmU+6K7zx}t6EwaLjj+s+a4ylOSS05rTLPE3f^q2TVK?Ms8JGC#sT)0g(pBXC!$HXrF^f~L+2WrPs?|so?U&bXq*h;+OO^Bu)cjiEJdtHgusHLGc*D{b;TCUXDb z>9vGZ`t_7^F43t=6qRe465jdNOPy)3O=s{QYTGlmU0;-Q|Doah2pX8upYYCi^Crez z*>+a=53^;&?MWi|4~LJaCar#_ga6R%y93ReH-vEiAp4geIRgv0~SkjXCKbxy)C_5ACaSPqx-(qKJ^SS?Wy~FLsT0%b5=w*&%%1*!sveyXI{2I~n^&+k~ zUEG0_;I)IDh2}GRE@^)54fW6Y;Sue4zNNj^X6NAtE8+VpePxjsqNKv-vZ=$}0AZF6 z>xgF8VJG8UAR+=JDn$K623~@Dr z85W!MQIdqyT_ArhO3#t_Pf~$%;EOAg?$M2qU8h)mmh^DA2Iph5m8ByK4*(zN+@K-d zdmKDbA8!lbo}uGnBO_B%lt;SqhWqWE42+CvUVcO z?<|kW$KyP3C+&(1Xb zQj;rv7a^m@PoIPjHC2%#j7vO|*B#G1lR^0GjH*fzGOp+h8P#fGiabZg<}z4DJ-w%= zaCCzk%+3U7P7+qXjDgu1Q&pL8$RP%1XM%>E7k)Xp!tBfiNs;vFWf3x}(H3jeaYrP~ z&a4eIL3z1OFgxR#-bGkHK!l9?-N74CSvbtj+?_KUH7%L}voo9Z#-WmL_Aom$=R}I| zOe%wnnwgs;Y&u;98FlCD47BiR5X{bm4_t{3ce8YUY^dsGWx&WYpX~a{&x4RrH&+Zq zj$`&gMxEQIGxmKhg^ap$>l?J=m>Oi%Yma?UJLgQusBbC_amNd8kWs5Yn&JCljxakD zYNUjdE+|1pMLH4aUaxJCQE#@Li}d}{AfujM;efY2Fo)ThI%PH7LFXNCi5AC}pg7j$ za4+Jhhpu?c(XKE%bMTD>-)Fl;xue@wwF}PHy+gR8`_bw(sM~_2kWtZ=ji_PcJjkf4 zOorl*H`~JOOpt*Q{*%wHl`Ny$vH9$47b78~ruO&3PKiGVcXa3X_r_t~Y`%kWiF8vp zeEWML;aFnu~s{v4f1-#wj1YQtts7wdLRY(gIuD^IzU$IZ)c11AA2`;E!Y^S-^aQvu7sZ zhPXvy8uJbAbxFcEi*^W7<{M15Pr$3zj6-}TMd}cTd*>G;K9k~69*9-nC^Bklj2B}D z3^1Qbkv6#C>1|yxpGo7kx|9_YEq~DitJjS{!P;Dm?G0=``(ZYS*HeE<=!`WlG*Y4;B5S{E>Tjp zLXnLxdxqkMyGzM5mPO~*F-M)`ipaf)&j(My-DaIeiyW{Jo9ciJhc#YJH+mdd1j*gT_e#S_V|YN zYtaXmhxt5CmGeU(c2_yDj%U6*;J&d#2xlFS3eMQWxHI9bquPQ9tTCrQ;ofgeohaP! z*M#tSoQtbm@lxAkB4-^t1jb-VeWl3fan?U`!?9~zMb0|Zv zaWTuiF8gHY;;BTDvyK-MVzEyBb@>YBT6{3R56;-1De1{_MfPS9ed^d*%H=7C(!z2DM5G5F8(4MGreEsE<1+V54J~B zr$*rOIO}(^uer8H;I75$Z3OB5ULfVJ#elGXYFuD9M{DQa_{K-GNk<_ zMc}T*r?-RgthlYr-&0CfN_%0e8H*ITcY8IueJo4huEk|)LD+iDe#GZ-q&iiobV;?q zU5mA2%Tf6Kw?Yd0w>IdOGFM9*$gznw!t$qwhXZcE#{%p{o@L8C+j8QqXk$JL^YXtGG=*jUFYJ4F&)38eoiXOKFnb)Ap&0gl zp%;7ZYBg2t@pvHSvoHn^&!L*>2AF5gA(?TgjJ@wLVhpF(`tQi=niuA?Fy*eLsPi3D z@Ej_Q2}O6=dlsHKcMo`tj6V8cJ`0n0d?M2RZx?WeTejDsk$1*mJ_}j9p_ zVW$S89^bQpGrVIVBH{f+%x7V8mnEZn>lL0uwejxgwA%sT3^V)-nBQzF=Cd#>_Sz$* z!MVU0cJR|hHJ2F&!+y_a9#uhkLrQ=%Y=6TaiR?Wl&zzbg{R-`L;eI2(e~1}p*nI!+ z|Cy@g^|s|>b|{Z2R14S%S+2M*GwwU7@vMmd-K&Itx#j!xmgkm_dHhRO;CDwEo?Era zOcs^Z1NvE)?lz=dls)vb&YNbEu*35qTLwFKlV9x{F5?avL2fB`I;{dO!H`qda-A&> z)tt54z1muydU=5R0(RE2u$0#yQj>6&um56G`DBAo31|5xh3Lq;J<61Dmd|RUvbmVv1bn9 zPMeO064*ea)WoI9hX{0P%gz zqjQ4j;Q1dB=OMdZ8%ay_^`ZNAIN?SITRKDcZF}8_e(ygVy6=(94IY*=8M^O=*2l=8ye2J}1c;lUM=m$}Nsh&PLXUjYJDQ}PVTIzB z7(BVdJCak~4tnI{{;ITK7KR@Aa#IqyKQ;w=8_`{$V^FMeX z&L8gmK7n4p%sh;&%RZ!CMxF=Gwe)L&|qLpV}BkCvPx^ozDL0RpjdHDN?>)?-uh5 zj2hlU!go5OI}voQ=NW#-@SV=G z)iY?JCnkKS^TXU;^tjS&2rzn?!lH`)r>DRlYEY z@@_XEZUA*nx1zk;ZKFMbrZ%;syxVPz4W((<>Iv_5TV6|Rl{Do2Tz#Ow?!h|l>>YD} zlicQYv+DIVJ>VhzPyDSO7uf~)#^SYsvMFyn0{7TSCqt$arvzv9sI#&*InSWiF8usj zmgI2^y6+!t+sYp#ZG%oc;_)HUeZCQJi6@=~(Ci+Sgma0nH^)m2zgI!0e0G_+aNR2k zI^~C*yVH}y(gkD9l@VfcRTNE)Q{n((gKLcW`coR8c^OfUrwD#{+6xDDRqw zE^kE(+=fuzHOt~Yki>uyly}VshUk)3^|{bBw{}@Zs_QH%@0xQ5DwD@o4@1{H^+!Fq zImn0duGx0jXYs}ABIuguZ5csMowNmZaf+6lR9B6sylZaflt<=;PNKYPK2dU1?5oN0 z8v9#L?9!REnx^0wFRa~8US60=dDpya&`$C3)pF>X?c?W(-9{dTt~u>`kvO=aH*kz( zSO`h)9|B$Tq-&TYN6dh(`CQdEx$&4P=$fbLzLonhwt#od>TmSPc@z#^bG_yw`CH}( z<{V>>Ry)Ll`y!!hE_kFT1`ddVu6e|*_tO6cIz!jYvJ+~~PPf!-&^JGO;0c`tyTi}Z zdqeKpR5$2Q;MHN!H7~sDmgm}DgWrq8n~^L}ecmR1j}EivlK(%qMILL^+b7)Xp}6nI z&SLXsiZlVDkmmMEdOP{LaRKrPrrqskSTwp?Z@9ePQTbzA;S-MZVL=A5jmd<@kNh{k*d=jyK}RFgd!^BEkAn?^Vu z56654Cz&~zUUhfIdD z-#J$4xv-k$Og@LAvpEgm5iPP!9;)B3QS!<>hC+GWUTN{PUohpvXb@TqSei0^m)voQ=CtujY^ zzw@wp#c187C&B}k!JJ)s;-cL%A%C81I|E;}@<4pQv%YU3S~ByOV9oNIRqqgNAqzr$ z4rT1Sd~~awD&)^w(=2eUavJ1MmBK(=H+3W8^C?fF51{@l6&ccOr!lt6ROHY0zb4~1 zdRd6it;`;|53R0LGkw1TRV9v~dqes-@_-l5v6c9_q?c$wSd4dYEQpN0AB7megKFlx2;rc&cFd}+e(XdGUlx0Nwy+e z&ehD2B*rT;=a-Fvl9g{1Sv2$bU-x|xij3N!)6IVA|FY|xd-3x7->M*U)^uGbUU?b` zvoKwadZ3^MGm~TedkF=9oM0Aa>g1i${Nq)SW53Q(6MVW?L5>}J_Oehqjm_mU zW)j!mk)2M6f?1eV@fO0XzELm>b1i1M(7us5GgyvY>f8fowT;@)GoQ zL<;1|np7q1koXPQ#bNfw_`x(sn1xYsT7y*j&4mnE=%$7TGe#v9Tk}!nCQ_i)tSAfedN+$P@qd`$4!zQR&7={FF8j*w_5j z9JiaZ4LpkbGR_o?-m1y(_3`_AnDL6u_xJvvky`#Ow|va$X(tPc-PPf_uF8!CEBr^Z z{muX1nF75tn@8ij?clv<%k#gzD)1QBckc=o{Wl7p%Y2EFW?y2{*fu!x`yb!~nYRZw z`xTknP}b}=?Cw2Hc6Xr;u!U1Pw3019spx`_9=KkW{>2pf-?LRa+~p%sF3mU3Qk z>m@G|e>wqp#UoRCvW_JQc*V74UxfL(i-A|HYgmt3oty)_;@*@xD<#kcn|_&2G~&X5S5%47Cb3>@Pjy>o8k+DyObjoBE;wcrX7k(;z$sKN^WW70e)cAid7mKSZp$m>5oGwm}VLRT~z3X)eyTrA5F~BQET=*a# z{>BZu;A1(n#k5;8=z`;y8jF3|ept>c`oslR=P(w8^NN;7UPx;jS;x&hikscP$=6hg z&;^$)N|1-S66k_EGghIMjIk-~KKzXfMMCyDSLlN8`IJ>X4kFM6KYH_A*nTn^y5J23 z1}J-a6m-F#o@t|v)109To_XSvRDMB(F4*dVo8a1Bgf7@nGZd{z2!k&8!5lACe$4^8 z;EfYz3;4YZx?s1XD^Li#M)7^kI}Ov(b?so_6|K51Lnlmap$j&CRUtUvsDv)qF!QD` z_j(0%!DBzj&{xSM;1xap>_&zGJ%CqicmJc%Ze^>cL z)EvBA!RC!kfLBZm*Foi77)QYzKAi?wpqKCSp$ne9vmIMac&p+;_e^@QR|w2&DWV3%X$Q z<%T$yF^zmj-lxiOsDJiu=z@(VOhsc~?0_yfS`vf4n{9zE_|t+p=&C^)bivGXMVozz z+FP{fHpX;u_K*1$<;{M@E0Y81)G=QX-#xctS}Z-UUyk_hxfM$m(7uhqi0_^Y|FD>T zZ&fPr-E$S|84Fx9PUO4iQtu{E^MeXMVd<$j`ejZ5;k@E)&uO%}%X`9kMfE%0)Y)H$ za$Zq?Q9pWQyd&kjV(}jns<*|Ha$d3J^?`XEWzAkkQ?}Pn^PfjC{*J!<%@u`f@%CH` zd7H8GV1M7^{WkLXue&O^#JTqJ^fn4-W8xiqdAI!vm*emaw(^)A3diH4%I@;m0EPRp zL#?5F>TZP-($P{~et*a%@IXHC`6K&$>w}E*ioJK=l?CooxFx65deYx*S_7}>&v@Hc ziKBp5+@IH;9y>Xha$eE9ZY=qrvWM_}&1>2Hp*2U&z>d6o)4S1?M#Zor&%MT%j+*uY zcI27d7)!$g?jXJ+?`?o3U8lPPcI0h*%l1ybtVDcAp3!t$TAaTWcI34#KR^zs_W@pU zr%E6_zBCtcUeWbaE?H$`3%sKJ{b|(T?+(Ow9m2=xw8!f4H67NrCsak)PT1!2gxNcjR5Z#&%HqEfM&Ryz*AnB>QWw zzajR4ko$ak#)8H6IuEp}p-#OF6GtFjFMp@~^YU^Y<-;rlBun+aFGZZhYOMZP1?c?a8BnY35Rds{E& z4g2t4uE=-fJ=bz$`;m@{oLBsIg^;}eYGl066%IzxvTQ@bc}3F)&h+jmg-5Z|Izoa! zWXZXs##=3t>O56=6nCo;67SFfJc<{(hSN581Hq%Xs>qRU>@$RLUJ(tFGndp{@F+S= zole)gZX%plTzjY&ZGU1u;k=^3uWE8uo$b?Pdzq)D2T_uoO*pUEcV-o7{pbjI6!~28 zg!m(b^NL4qTT#mdmUTI=SkCsr7dC)L@h2TeKlQ93oLAgE$eccj$%lQ-uh{?fma$5N zdlYy79!)d9JtUl03^Xetv)ii^&MV6Pc+&?F?+E7=HGXuZFFcRKzGh}?B5BJk3Ga@7 zdJm=3EZR}dD_VT(LYHXWCY)D1#at0byq#cQb1LgoBJZhD&MS`EzMs6fE)d=wFRK)& zdWbgVykb7;L=RkjMR<1{RFFYdG>s;_JD%a}&ohx1#Gm*igL_JK-6+S*Q*fb>E$zXkq7ekWov!b;k`o z?15JdY-5YB##jNb=*)J`Oda%vaM$;#>C4cSiK&oLgI=@wSa$>975#f@;TbpTVW!6a zG23^lx&kt4-)3oI2@~Yow%@! zI%2;SJ|t`gkD}AneaPkY0LZ9XTMr_ay)KYZ!~RUcovRALqlnb)aN?L)@F*VE%|}n$ zSwTkC3z&u-lXrthF>pc%PJXo-Jc`~Ed*e>JZs1YuGPDE@Z%~Dddi+x=s0%`)mnuUPzc)pIH573Z&V!w%EE1kNkg7!&mI+IBh5sNa1F zn*JzW#yyG^ucPtbr!~Uft&9`9?}Bg5t`#`1*yP4sajV>5kF(=}DBSo~9dTZ9W$NAToDx~@O5W6=UO)Yv?qCcK8f$wo{`S-q<@rpkGJc`V(C~fvD zCYuG})+wJ6=M{H67>TEA>SN9;CR#F9;Di(AyrNedV|-a}IOe=!Ow?aAKz$14ykgVs zYNXs>;V109BNW|Y-a^hR?x`sesy{CVUh(s1FLA=IB;Xa*79(vH+Ph(AHE71Rc-Z8$&{2v$f&XxwR5fDMzLdhkWOpa zxC&d~70W^cWy^FFZpo(>6ENO#3UOYsqE7*;)iHvMx_*2$IX!g}u!XaKb|!_t3xO@n zDYnFu`fh`ay5>_i#>f>yMitih;k2Vq5oZg%Lr38uJ3k@L7Pek$h|h021sSz`&R{IA z=zuv}D28;#n&Lgks27GEMC;$UKt^p-&>#2lR>zzzoX{}`MO^C-8CAPjf`2^ef;n55 zct8znWV}V3Ei_c!gL2l5gN!=1Yj3eMZrvsUS$t#+sh7fwlH&9BRY3O8D?sx{9KE)7cYUCnv`V*_=5@q3ItQ|DDH8MK+CGO!Ay;1&^u(R z>4Q027@j#5RTS-nnVOYD9->cfV=#AphkVFDmNR-_?)v^Rbr||)lnpaAR#_B%y*3eZ z*LR=qE0D%5g-6k_OhA)2?FSaIQL6~O6%-ytm)zc{ruGob)YN!ppr{Gcz@xZx+jwL> z)&V?<;WPD-*~3DZsX4xU0n%B;_C&I;;li{YD4Ka7c}5*ESPiY+uJ9=C)ESS~XM_XC zSbF=Hu!Z$5Q(1PsF1n#}%pu8{#uN3=gh$LX$(hEulrustb2)O?_pc)j!XW0N&Us^s} zvB$ZuTR*{Iwg`M<%KF*z%ZFltZyfMkTTF581AJrcuC~II9*RBAbAMpbhIu$S-{|a> zC0(~evB&w0=U&m9IXpSvxORAfSf$B&1NQr=`RRmA^|E4*v&JPYQhPQE_{J$=$|OgX z?RsWxZP}A_xenu8Ip28N*NHqI&zu`9qfQNLC8n^q5qzfR+*LoKoEZ*$V}Y_enP$`* z_{RBaVWQy-#@w^_StDy#lZ-(jz&G|=9!c1{KG@@&{$QQBv5yS+MxoRu;G`c?qnXn(a)Y{%S~Jfr>!UQc?my`(&&9@ZiS&nBuC@GSa|T||7Y zq~$fa<+=ppZDr*IXva<`UW9iea-HVv?rZ?96g4JVjd%JnWO zoQJ{#Q@Q;Sg$pr#imrU@5rreM<@dFg?HN@5=TR)FHlcmbds5Cf7OC{3O4l7J=Nqer zc+u}-GW)2rcpPY4~Xv;wBNIbG^`s8?Bc@^Px_|! zFWA|4u8%KqV}3>6HOI7SN55|vNIB~`hj~J_Y$mW@FE-SKhV?lF`}JD&%^}x#XHufwPY5Z-&wpSB4_KUr+6G zCFx@GT*|v7sWY>)aWqXFlnu$elSBvQnZ|cLbjM`HU^acLx(-9aF<-e3B{Q ztm7rEVzOZ43(=N+4Pkez=-M4~31=N6UWPI!`vAgONBPGB;=8s<t((qG_aMtmitpyF*xQTGqaW1o8th>31aMsaw)&aJ^!h&$`;?>K>wBPYVgtLxy zOD5B}quGSBj`rL4k+$#b3GbR8Bu}6^k|Tt(j&Ijxky)zlgm=vgPUun7|3t!BN3VOM z=`-7FgtLyxjXTKXL~p`({2fu#q7sAagtLx2d-+heJ@tgMj{eiP5$l@)gtLx=hI-MU zqi+az=F}h9L}tASCcJC@bx?)cj(JWv>$v*nK)=_1%5)H`u zMmX!}F%;7yD^)3H9m@k!Nb!^$r%`qW&3fOgZb=O&&)s=umEfp*%XB~TFhmxv$X{2cd z>j$lR&_Bx7l(UZSI~mXvOBc#nN2k5obl%*4l(UWrm(P<9%yG(DN9H=i&3;AZUBsFH zyo=1oDB1GQ$N2q(5qq5<4t(RlqR;4A7j}P&xoi4`A4Dn-;(>1@R=rTx@I>Gncjl%^ zLf4o1@KU@TOs zlDsxmcp7iDSugRiQTQ8^#~{hVe_qFNeahYYd{y`!4{qpJ^(ar_f$XsBarHw>g&%TW zr_r)eOBLS8JJu#-MB*Xnn%mF2Ll$iJgRc3*oMTdb=2Sewb~+EspCt6%t?({N`lkuq zd?OWI^NoDrH*+)cz0al02NI{J@Geexs)JUxRd^RS8B9Z4Ekmda+xtv%640SttD$Rt zl5dJ{CfWlt`Qy(Xvdh>Ey5=AESCZ$gETL;o*62WPjW2+%x$#XjiLth(oSBqw_$>y1 zErhQ5;>&u`I-&%+<`8ce@*u$uy5{QT)kNYK0A2HysX0WYbTZ}4#m z*KBlY0IBhv0nB7mPL_OCQWY?hbGIClmFPP|*S!3DS5nY99GJ;k=^k0Kyb8MJOB-K_ zN{JD`OwRmlDn9HO1#G01QE~NY90gtT?+?R;%@$5{AM-AD&+3U%*VsYV{AE=Lx|e4S z9AonO|Aek~#n3hXT-X-XY%GAT8Q)otJV$f~cJbKPbku+KRNxhHH#4+<_Ce^H+nTfc z=)aA@yI8s_A4PYc1iYg0etXnTD+jvf`5saf>6Hat^9I$EXkNH3@QRu*uAq#$W1wq3 zp!^8=8u$ROICYgj(s;8Sy5^frwdhehb>J1vJU=4c{v&`_#8;=G9km zA88aUH-h__n0Xgbvv-mCuW+-EvE{Xexf5}-JCQjRakEpAc^7fBcTrE`SD<>q1HR72 z5taqVo{xj`l0<1i(wtFnX0Ao_f7jxdkEq$f$oz`ZX1^lyF5>dikV;k6gb-HZOY3J0Gsk(|4&a2PJ~N|fyOP`C}5 zXGh|?RU6!fCWmSyk*gFg#4+}blIkRdBXLMq6=_MN!krjauOnTNrf@2@{F$!S%p~Xj zc^5}E>>*k6W&y95kl&m9VE#tVE9TuY7TbzRz$<>ZaYlGwz8HALs?1pQ?DBlz75}Ux zNOOh44@q{n!e{Vg%z4Gq4koz9YZ&Id;+5Nda9}4V=IuQ$tsOiH8!?AD=M~Sedz;gr zd_sR&hCH90i=6i8Lxx;bJPwaiK7lx|XmUl3Q08Og8M4jk5)x)J5qQP-*%o+=^Jd79 zv+9j8an6Gbxg~cW>ND37GUTeLEM$3K0vYnlY(0GX9)%1!W!?_dF54F}WPPkAp6qlJ zab9t^kq>qaWPexeHS5{2t*C3eNiZ*C)-(bic=!$tVXtd$Pt%aPPAJUF?6|3nT}Qk` zoL78jIS>!?Y==3o=vKNKO&+iS=4IaGw8EPle<02)HpL*E@KgeGL@qu0l+WU%SW|m>zf49J2-dSVLEB<;s0mUEP3iC22+MGw# zUpr&YD;6;~vU-LK=DcG6`Ge8K2fJZjro6foX>BzG@1o0TEqtz^ALhK`m;vs{)Flh% zWt6=bKeG;D&MQ`y*rVk^`+!%RtG@?*VspqmLxxBHLSrh2V$LfDE!RaV5`{Z)mG%ns z>#4%KsPFg|%~A5goL8)TqJla;Q+OA*Ce@>`eY;J;m z{^xRvMr;`e-o>X%XN7HZjsUMXX@(U#aoY}aUh&+)B2>iKN1h>9`jQ240(R$BBaLLkDOP0U+5vEGIu4^NLQj)8)^Yx07ec3*Irp zI_Aveykfta+wxGM3V6lmZPUfb9?b8`GGt=)1i;*E3P#n;R` z%6Y|~yR_IWOC<1$ZjDRCX|0X|uXrMRmAHvHKRK^xp|(?OeXSgLMcI{Jq(hS(@QTk2 z+mh}d!+}>k+W(T+#C)ebL#hs*OxovX3e^67r;MY*#64-^IIEu#Z#(9==GZa#LlN;@a>EMe6h5GJoY(*E`*h$ z_~}I=&yYPX_QZh}!GycJrJ;eiOuC8O@IQl|<%VFhJpsg-Wk^YGDLOmngur)C-|aaa zhYnwW`0nX_b8n*`4>ce|ULN!ceI2L_8PcP4E(#yG1~TONU0+eV-mQUGys>o=+ONL~ zGGx@GWTcb13^L>y#_C=#eFt+lcPe!8OQ{=V$mBdz{5#klc*Ti~+wH6o1H7XBM|FH% z_b$xcod0Ekk+%)-ieB?KBhh&pWXN7$ZLp(<1@MYJJEf!h8Dk+s?vB^P9|9=M-F(jO zgL|Io0=(iN_8K7xkU)mqTVaCl|J+Zw<572ofURvh0k1g2AP05sY!4YS2oJ<3_1Xci zI6QnLuAcLXaCi5jCSQDU-d%7uHVx>G`#7y7+}&N4ZHF7WSrKb?Uf#Vo-d}k`{L#So zI~+x4E(VHxAM}7jmFUD^Q;FMr%YVf%uC_PD%6S?%K6O8 zVq0e%=`|4cJ{Po)#KS%w7q79Im&n^y=yOb=gztS`m|lf;s~nPYclX`^C*0X{qrmq* zXAX$MhLXK5JPV&MU525Qd9)_d=Xkd}(fnS9(d2&rbG#s6Vps-U#p_ zHuH+$S8VzB+w%O6SA@rm3G*)e_7l8_ICQIeK}^r#d`~o8a`2B3U*ilc;`8&p(JJjk z;1ye*TRukGwPV4^{X^in&)rO=Wd+XFe0Saxi5oUA9w{38GuC!=5?-&jQRH2)^U(+H z^Bj!9!MOOBpQQegF7S%Mi_;}hxgEh>^K9Ko$&*!op#Rml`bx5;wieEvI=7R?=^cS{ zMzWT4(~uQ#-eGJg9Uo`|?wX}>#?sxt?pE_IxaHSec>a&z^~xE1kE7ooLf3c41Ftyd z<7ed3CJ1=NBp)Mu>CkZC6}#8EUG;8M=M^riM$K8dfXQcyWhY1lD`xCJi>^l-0I#^`tQGo7^Pmgv8sLg#o(G`|?wq2EhxiQyUh&V~hv@WI zP2d%mXL_J3YxY4GoHsxlU)du7uV{P902gjo_!S@Gujop02jCThB$H5=!MmUfzOyO} zMTpy=3x1&86I<+NyYW~j6<^p6$9w#QF1W|S*=S;;!mrr-o;`k%YXQ7sagZyXJlzO* z#lCSGcvj|9=z^zZtU#}_S3(yYt+WQY87~7~arWW?c)Up`;1zXk_3@tr7h$KKhx0}h zls6xE#akVQ;z#!FfLAo_%lrr3e!@<@c{fdQ@6>A@VTsR1q=UPr|}qEPJ7I*IU|dW&qsa7yF?aI-g`!7Y_ z1?!)S#6RblgS$r6`zQ*?x*+l{7%!+~vxt=FQR}YsVUzMdI?}BX( zBvD_sHo?-LsPYdwEM!Lg!76nTjObc+g!qV#o80W z)G7WI;k;s4fiJa|X;aQC8X8Dwx1IKs^NJ1IO=6ayyB-<&&9*Oi-A|nAN@=^_g)h4iY>1X;rSok=Z&(3J=7+b{s^i6 zIm6y(y|%XULytRv=WyD$?(+KUp|F#B&e^W=iMg3F?ykvNq#>Vt;~eay_Ec&m|JLvh zK2E%9We;kU<=mZUqFXF8_1Ba0$4~5%EbHiEF6TbR_FsC*2JEqh$NcwmclCoqc5==u z&e*-HA01{d=ew|n$41i(%{L<7skdmgoJ6Aa6?w`7za0c?jw_bFt(oDkLHTPCmlR>syz+LmqU>dz?lR-EG zS>jYhOpX?UyQY!3aQhY(5Y9k)F6l|{rfnpAPhVLbV>}X|QD1~S^F zJ^dB+lW+#|Z_sWsu6_dSlAb%#fqvRyK{*3izL@!UH--?-K)PydB(MDv*gbdV{ad<* z#5pb_oN4TT{5whP*`9KDjoYLvglg$g?yj-kQb~d`O(^ew&)9q<8Xn%1bBSi2Pl##Q zXv$f{@nw5S@8jJmXAuV*o+4u}PN1AW{2HE0;=fr_?n|_Lg~{W0Ilv#5*OU<@*57dc zFj&`xtQl|!_(L&lKbgT^TRDH|H#3Ad4riH@xof%_8j;<-3V}aNc1a=M3`2oGoHoFf z{3g9A=MSZyG|1aC#lRmfyc$K0O2dFZ>{!%>tm?sjuIzgcdGAF=>qh{8c%V;P5%XIbKQvCu5i^;GmUp|VOXcE^N0q=IQiD5UdD|G^5A}`q ziFe0V1An;hJ=>3Pim|Qi_qP9_U-G%1+<-q^K4_}AJdH7+?DwZM=C$lzNG$M&_vh@B zdcAZ5{xDC+R=hY)1pYAM^)2a*fox|j`x_a3`;A=dsR;bx-+TRJ>4ORIhtKqEq#q3l z@Q0ITZ4$y?xdMN9RCg}kc6lw~*V6K}4*1yg6B82QF&R_bsHdYQe9qY7PQ7k*e8lf_(xEDU5Bqp3!RPnH=EMA> zZgiwOy1Kx>m0IXZ2Nb3W{Cke%>P}z*#^>- zT@K*%Rw5?SdAeI6A7{GsZ)<`-aOG(1n!p$3Xq!-UlhjUv$Rq1cMpJ zgA!fui*VLRy&;)<{k??qhtYehB_j?iNqOdM`Sa?Kh z(bVH(F4DSgiK^K-zD@}nKKI0&X*6GV3wZ=}!JKJ4FkloiUYCh@j>f{?P(W_FP^XzESM)eVOtCy+>j}R zGEaEcephU`txVu^H)9Y%=ey;(^WD&@1_TXTk_@|{9oYM|Rfa~0GmT4!Ib&bk1#zZv ze~yT%Z2n65Zs=RfBC!9<0f;k=Z?4GD1Dp8*-vNChx*E;3*eUQG&`M|QagUJEC_UDh z`oFfo3tnWQDeU(%%hm)>pIwPKXV~-cDE!&uBjWQf*Y6F(7w)yfoGo+_ba9t{HHfo? z)(dh_-BpY@Pk6f?VWZ8OnDd0a0z2XLOBxX831=_JVtL*Rah~wdyT16emOkb@;m=Yh z?BZjJIZxP%-G?6``HMJDxJSMn**^?HoG0wjdNbO2CLZw&`7N03T$^NdJ=pyM&J&JH)x^Dv z5av9gQ`~Z-yqvLBEJM~3H9XYW19P4*cE>`Lm$e@83|Y?Ds(`#S#53fm{UNAp;&#L{ zeARpAH15Y@vR-10x z?h8Djjk+w!jm%yzZHe?k1Q1NP%6_vD13ehLh`H zPRGrEiKNU#;UQdp#zM06r8PLZ7yd|fzhN8&PLVF|l_{%@%WJjVk;PLvl?_|q|wSvdQ4eKBuH28spXUIBT9eLp8 zGT0g2bnhzCTs{tSo={)C2O8TgA9%t+9mdiwwf7Kr6>jR8OS=8+1w3Kv8yRf>M|W^^ zFDgz!hs+d??&D6y$YcE!%z45)L$lDc?LnCHgq24pp|?Bj!O<-lxda^+LxCsUAhShx z+3qBs_gs}aqMkR4fhSB@9Ejo`gaJ=@^5S3Np;syJgh^ig(flJ3z!T1W)F?>Lx?s)| z3c8mB*QG}lGcN<1gvuq+z!Mf_rU_;%*}OQLc}d=JL?}X4z!TD8M3}rV26)2c_B(_S zT8((#>u#MO=-I~tPq=?>g>+J=VlVTIJ|lz^9og<<#&mtXK2X+P77IL~QmY5@(ZPLy zCv2OnCv>Y7fhP|QbF2~Wc*3Y(;Y9t79qeUx z)>X;g9(Bq??H~@Pzsrcf~o4 z6~Gfd?Q($>%?SXW(0Ta*61~O(c*32+XYuakGH`S^rrjg=ipBy@n4r>uTn;}1JYnVT z2C}2j7kEPDz9Q-6VGKOs?~C1tPKN^E36GbwrZ1F+0Z({x=XDbAr3*Y^dUreWKrIh= z!q%Hq=)8bIz!P?}=tssqJ^(!70zs1=S%`rrJY4aDj4M{hJagLV`jBU>vw$ab{Aon( z&0T>fJiGM=nH1L^c*6FbCXynb-QY{K?_@y_9&iAj(7!N*WX((mU*g4gJ*nqcYv2jz zXSSo~^?t!#=DfxQMC!5;@tGGrQy03W(HM9_^V&}Ibkj@N%Y5weQet#-4e*3T(f#Q9 zy?VeC+RRTOTRm3-Pk0~|(doKcz!N^3uS5H7xB+{a)BHA&X_FQLPgrN`Nwr6}0iMux zt`WsD5%x0AU$&X3{*SFQkE-d5+juEMiUy5RX&y9Fs(bFZnJTK99&2}O`9S%I<75&|$p7;Y#=#amcXu0?RPq^cP8LdnzfL><%)o<)or}^^v zEaU$wk*TRM;{pG#rfR=Gx4*}J`)zwG1RNk8ez{vwgNiRd8^oWz+oYe4I|EPH{_pPg z*X{4w9j;N-Sw0fJ_Kk_1+|$pwcHZwaywavG)y(r0dG=rr#?&Q_Spnw^`q$rkp_kTj zeoxKYJkJJ4JLn+(G<|FBcRgEqB71#ilBMk8Lkl_2OH6D|mfc!wBL}-Vi5=>`%Z_b&E90;4*Xb&Mwd|~n-yb(cSMHshC*$8|#6uJLn)9=u z`?ztrmAuopZjjU1{(U`*Xp@e+=1lp|e5pgTU~n%Dc)|yj4Pw;HRNx7>TCw~pNh0us zBMuNUWhv7sY_?mI_m_Apgiy{CN_C8BF7~B7FEMD9C!IRPnR1@+p{+mf0jHcNJQ_KJ zX6^k*I8S&mZ8p_1C?T9D{2stE7(>Ss&J)g(R1;?#Kgh1>ilb;kcn88e_~xi25_iRP za{D>s)`COHxauszdzqijc}T7lt5VA#5A1lum|nMWq^5P}QQ`_e;&Xfl;l0eo+cfEs zKu^khnSX9oqPH@=sUEv0@Q#kuL8As3#a=HrluQ|4<=qy2^uo`<7bSxW9XHbNfG$_N{(EuBwzuis;@ z2pVGTLwK*>z3gIQHvF&18O0g?VKg>7jBrNLZ&V?9*V>hEMltY$IVJr!65i`~xMCV@ z3EV_DqiA4$ka)M6LND`{cw^R2P(V1Nc(zLj9ap%Aa7OX!;Qhqj$^m+r?;8cv8&#!* zGm1am_7FuA59nofouW^>waN%*6fb6tqfdWbC7e-AUYSjf&GREX4@YCYCT(S%$ed9e z*z8ZuJsuIxC|-NMjcmOYNMOFK;YUT+Cc+uTo!vH*8Goh|&L}SUtwQIs-W<*--rY5r z-Y@S!Iioo2LIxRHJ)dw!@nXIr{ovmMz06aU2GHs;DwH#dVaCP^d%$F89YTTF;T0^*yK`yPo~>82Ql4 zkaC9b_7o5DjOG*04X$jnCk@T}fE6sdu#4oez8gO0eeqm}yxe;j_`usERuZX}73H(t zVP~6&`SFpI^MQUYUC9TQU%_X)_dOqxp|$>$^MM{$ev4P;7Xu&Y@pv-1Hr$SKKJdvY zLXzGDQqBi9C|(uw!w4LNge10VS7a)W%8e+}?~r^daLKkMBW_`u1h zJCohlBY_WGF=`zzCm%LMNZTzz6P4zb+a+j-s3olzTV`<_~Is4-9#^UMxGn zav0g?R%v35Y{`rm-~+W|9|`IKF~A3EZqJhLTxEJwbuXS$B+i?>>I6M6n& zf`Y#AAgH;<{!bd#uvmmUH%%nG+s(D_PuP{xh$Cw$cEfj23g51KSy=sEmnwgMiNL3UC&*i%z=kQ0$3(1hZ7vQ>N4Uxp_zlUqj zj4cws8Oo5C_@!o~(BDNr=wPp&vxrv>`}MAjxgJuawG^f*4e>qm!A75{q0%`v)!9T$>_{Y zYv2RxoE1<+?tgsXsq*ew9p3yM&-h6 z_wBDMD5psa_`qnZr|55>Kk$L~b*G}*bz5MzJHzuOdepTm@PX%FHKWBjBY+RwsuYbj zJlX)W-7~=oc-qV%zz5FP(!jz13Gjg~JM{1+*1y1enRDi}BA3w$zy}u8tK%P~w_&z> zO4$JKv#*6tJ(b`*q~<;d_`unt_o6|k`T-v}U`%hk_0?|3q6r!@97kGzgYLYzpu?!@ zw?6QJ9+M8vC_Ahwi+wL51i}PgURp2U?aOZ`(GJ&vqw;_QCpAV+YtiwW<}Q@>q~-c^YrpY7_{JK>uB29QN#sWBD*^~)i=J8%8L z3N#tzi+r}LEY8I5I>bX3&3cwm7M%a8~BPn8(gT zvS4mIWUp`02#sU>d<+{Bx$UgAr>*&Qio~`sTebu`k+psP7V6k3!#$U}_ob!FJw=`e z*j_IUlr5whXO_VCzkEHFey=+TXLL=69cW>CKlp#8=ettfXRD?BYcKV)D$?8L2j6pU zOdssgbsXWZyRDgrZwlK9KWA&dw`{6N!J5lD!|T`nCSiOk7_LY5?~CX6=mtN}lcmaq zD|2rE-^xpWUY&Csx{qIu>L9-+djQ?X#nWHP7GM4) z;aV>K8ZNr4Z{EzzLU^aFqo9Miy4;r1tW@9wJEtX}9S0ME5B#YvqQMW?OqyxJrB_VRrqqML2i}%l zMOrQ6Fy{juC+#OrUXH*ACjRiJ)0RI*JkQWuHwUfCGKEZC>xC=OgCqatW`~YZL2VcR z%hq;N|0zALRRVnAg}IZ^oV#|Ar+toIkXC*w13u95qAl_>cEp?yEXXTHF_poX^MTKm zOIbMGao_{L{mnzS@zo~BX*d|>N`EOFmg7vKZG|B`!M(2W5;&^XIiT(YMM_`rOp zZ=$cGGw^{0&EMsnK1Bl`n5&;6Zr@r7d|=PmWHEkOH1L6)<93M2eigt6ezCVFT4@fz z2kQGNkp5RAfe*}FaYZy%DuYbyoPrQycHb6ynLnDD5}jp?HDMZT!0|@${+|-a(~j;v zh}gaj2R<-|eV=Wl2)tzz4pWvyV&|HwE}Wt8>oe*t@;J2j;OeUlr?~zz6;|K20{T zOgGL4Zq*!0&MnFTKJZE4C30eC58wk+M&BYHH~{#-KXeRPrL+_Hzym#=5xuz4zz5#$ zJ((zlZUsK@Y_}(*GENQn!1Gi8kX<%Ife*C$7f-Gitb;tm>-#=G;m{BGz%Ldo zn<6n0_&|>#D%2sq5ph0H{ircr(Ci3&;F*B+hBMH;9wPf+S8jrFSGj})>rse5BR_g<|)%1 z4Ry?zz6Eb45N2${zN>_aLgKGny+>UaXzs99-Fta9BocC z#9TwVI`5F2xU3{_4H>rF44a8QnDc?Z=M2DkavRL~z`KJd;m1CmG3Nuv&5yxr9-l^> z51c$I36EJ5fjA%7jb*O>e78cH!!oq*Ri|QWzYC%l%h3M%ZV?XbI-K-p9+URZor5zq zh4***LWcJEWqokEL<{>By$B&DI z4DBT<$I$VFThemI{;7RFiXyIeLYxn@h@Fo6Ue83F4}6$+0I4lBN1P8lb=4Bj{_$-cc?~>t%60KXBf=RTu)!xCk|#Flb$)%D7dS;$UC6>1=pakie@?Q zfF5kq7bo^8k@Gx5?H#jlTB9B0a*v!9g{_Kyh^{pyOJ)oDt3 z2Xwq%H2%Keg4m0BOnM)!K}Ipl1fFNO`*k$lEhdOO&oJ7o2Du#gEAS5Jj>}!})c6xp z-T{5lF9yp;EE8U{T<#4$tI*!3i=?~*+U|oREHKP&d1M{AkU~9MC zi1UGOEA;UzM;YRLpj}NKs#P3_I3L)OnT>3mMzPK)+6>&Z= zEpj6|7ZHIt9~eHoGj8kf4jJ5b$J=*%b>x?;`;9%NeU zbF~@fd|)>mi#iYAfVhSXDKNs04$heKfn6r)VwV(m%=y4S;uX|1sR!m7GEVt>(O2hj z#atgUuP!Q^X^6RYYQKKlU$?)Pttn(YSplwq~Q zc=M|fR_IoZI3HNwXE%zB9Sw8UXFYWAgcY}8uA1*;gb%;0h5qG{Wh~=*^Ec>UwoV+2 zr!_GCjm=fhN-eOR*&gU$j*H%hPWTT3J}~n~5PrJgB;ozbr~2FBfT^n>D`tq~Aj;Kr z13u8XBm|GTTtayN^3$#}aQMAk!uyw_^qg=@;&{l4`KVls>Q5Q~AK3j5>lUj~1wJt3 zNCaLpK7sK5<;iy$b6eI6vSRX%mZMc4e~Nsr+Ui9-g@MF4eI!9ugK@Etx<8f&Zk1;d|)Emk51h*7Jc5h(%ktn zwC>{yv7XIFms`Z+xw6rs@{{AlGASM(I^-ws%B~|+`s1-n^Mw+2zh4RY9t5-9>%$lex^=pg&vtL!3CA08D&l-#rT$E;8@Ca0KCt{}AAIpk65{>Kr)Jim zeT9WmKHIHNt3t*mm!y2Q+ke#*934=BI3Kunsuhm=w;l1>uKVZ;wA<~ql+SiI9h-!M zUz|gn5A0_Xh$pVU$+A%^$grtq*r)Fy$chOn9D}nqG$PIi-cu_@t%e#f+kI6t3a@|h z39@3||0+a3RgGb`>+$UfTD!~&X1kp?79g2jf0*qSx$Q@LgD}i?pI1p}s3P+=v%eWv z{_aT6hP6VM@mI@#vdv50L&vejz}{44(@@I!z&eqw#ZHqc=L1*0I!7+uh^Cwm9G0Mc0 zCJRBja^7wCTP0l<<7*1MpVLw|S+2D$@P22Vj?|W4bb!~t?alC<-s%YK-;hHey_8qk z!|STYCP*e7w}SioUE40XRAU79ggc*~!+TJm#72l)SXd1pqKdOA_g2bP2^ zB@4_l3GcSEoYn`AX|V#9@3Kxhy0B>l;dzEzezg+E#*UP;d=2KWNZyg|l=sk0YS5tz z^Svl%`F#7R(=QE}a+Xhj%?);Tu1h(~ml&x?<5&1n&hpLhl#xlRjVPb(4z`bD^WZIn z_t5nfzmb9_KgwCYY1={xU9yAl9=bcT8;P#!Sjt&GE6D+(QDROx%a>5^N4&iA3C}ZJ z-0vdklQxNRmT&F)_2iJUE#PVJ{+_?k*!`C5H+ ziR5MsuzbVDmx;S=+$o>!s@*s%dIVJi%a_vmt!UUG4p_b+R)wO+*BW5?j?LdMZhsv| zd7fdcxu&>aXn)G{40XNY#o|SBVEil=43tkl8&7$jVco=yLelL1l=m-}E$|c#BSc{T zOh1Xj;;MMc`DILdrA zaLDIPXps9%;0d$KbEH0JYk?=+uwgGUO#hE3{N|93w$88vo^aKX8`8KPRlpNgcQ}ax zB7%V@JfXcCJ@K^!o-p*+TWL*k1@MGd9$ZIp-vfas93H2LQd#CU=Lu`(K0ylyjRT%A zyTn1|Ky*0fohc&vqZY`-!IOjRc<1WaA}dRG|+%;p`+!^q}b|@PwbjlyOe( zP~Zu#Xt|*4Uk?$U6=T$26|Z|b2zbJkwog%rize`dCWnV2y_tJ~C(K=>k2N-W08bd) z@&(z|bpf6*tY9qKeJKxk!pBXx7_MC|_P~D@-i5Diuis9zO~(&oKEe0**Pnzfc60_^SJ2lK z$1ghy_dj{u6VI7<60X&vr#qC5$^_oeXr3cox;v2YS@X1Y^Ju;4f9HzrpBK){0w}iD zfM*BV5l)XgKY??_o^LzS%7Lx$wUK8&IXrZD3O{GJ*@qoWz0KkJ-o!f&%Ck1YwR4&U z4Ox;0_ZL0WrRhhm!u3M&aqT!KBj5>dU-%=AdD|CwLN>D?%nJkWWz$(rp;T!Z=vcF@ z9fh|mOF&OXe|{%9ZC5X8VEg~SRLpt8eg6tkQ^RcF36m~MQ2EZqz!SDgE(!Q)8t{bi zJ$HyJShqFj37emd!Hf65LOjnf<#+)aH`5()o^a%V58~V@vB3U?jGiP`jdTb0&ug9_ zj#w@SjXEr-H};rUf_VRO=pB8WdE)}&?4L|w7``@B33K-E?$$xrBTyA{_OCin14o~4 zK%D(^Z_GnI&-o+H{uwh}x02;1bN27;hfcUv`U7$HuS;$=S`s@20sFVo8BeJ(#hm>+ z^3E1dDYU_y{o6jY4bAV?33K-E@~Dl-cKdw9*}q34*CPKlOAyc8j(%l`Z=ZC-oc)ul zyg&(i)iG!PqBK^cYRy%MYt#kF+Ssf?f;szVc1sNpC?AMrmFKUPnj7@Z<(XXeXhrf3su2HwpH|WKf zF_>%A_{4ii;njG|HR{BH+tIs|R+wwl*eOGh@v6OuYt*$Wp2#w?0CA1_^m{q_{%H#4 z8r431A!-|AkGV#DII<6#q;>>xjY=B!py1Hym}^vrT^rETxif(|vkShoNaG3dcv}JZA@P`I|ozUhFeKF?`pO1SfRmraa{!ppV3As&) z2L3Sjy9y$2Vt_w<_F;!K{-+z}{9!=cVQKD`8sHBz_GL=X8pwb@)XZBbt$fJ*b4;Ti zot-6YeBciJVXqWAi>3GH;#;EEFMkcIlmg$q~Me0@7Rs=Mvea<%d)%zl7 z)D*?%@;<9X(5UU#`=Tp<#PoNpJ13woU6cR0_V}niz#snJyNA>~NC5uuMTeKi1LH0^3}0r5OTEsurt zc~IERZ2L2c*Md~-sM9&ynfWdR$gl0CgC2Ih!O|+u3JT3{2rGRj&iTiZZ(`g z3>;%GuP>;pvj0`qKya!{H0v z$c+OB5!a|!PIsf{dhBZ-#P9^el%i+fUaYnI8hi{J~`8?8*iH(B@5V`m)vq_`{-_>BO~RC*&FKY_p>N>h{1Nt{$gMhX?$HuH@w- z7m$ow8zIlIjm`DueKP_6aM&+3TG84BUCEgSOURM5b&zM6*w2GXS*{}I4-4L{AcNb| zfj@klEu{}HX#sy|s;5Jr{J4X7p5aQn^`tR375Kx;cZX8*)ylvhzRT`Kmw8jfHR_A4 zn@IE6dB7h=6^x`^KDQyRQPJaVoPnh@8h{RW%U%^3#~*Qncm=8?8X zV}U>1<2Z>H_*_Oj&#?1r8#+CG19UMDzq*&S)C~dta9QbO+INi%@m}V*hys$D=>_~@ zOase|ksU=m&roB71AUPb2OZ7bSa04axhe36`D4Rq?&nOz^9*G}Tqwhd5%;{P?JglR zBs#z!ZrKq*)0-C}o@Z$0SVmqR?E?Ja_05sgq#+RTJj0>7{phXTYKZfP2J0)y=}S+f zJac<%aSWxAdWiQmTPnFzyFQgt-q+kVt(yD`IVWNO_)NV+-rbdvH|B zHR_#1adgh}LMhKP+^Ej}K3Hub<(`-6adI+FeU6lC)S=5+?z+}Nf%i4f@aj)HF4C5B z&&z3lk-U$UN_n2)ICjrdVUV2X8Q%RNlF3_Dq+Fv8^NgnnliWn!*Q}Q2&erp6k!Nn7 z-%QA*+sXp>y!<;6ORLs2h`g`)D*OB3Vc(}B&)il|CuF)TTgEfDwKv4jCj}`7N7~!PG?Gvq^W~e+@!u4?XsPZxxeGe@s23}L<;D!pbyRR z(7H6xW4$y7k*^~bgC5&%ag5wG`A?5!uKY!YG=+d3^WS4aCut1>J+^tTD-9dnAM{xJ zpQmxnH<^p`RnVV(zo^o@hfSaf9SZwP9Q6%AH-_6E^vcUO7PuB&sIjf)Xs6zwGY#*4 zsg3jePjeO>m?F#c{7;Kc_sx~f3;R!_{+V-LHnp`4&P$X2Jz;fZFG1g~{!)Y_PeL%) zgzxRTB4g!apb3pfIMLQKW}pde*xwmb-gN*?XzGzkq6RMoO{o8B1zI)44s%Vo)p9KQ zXzhf#CX8FU1|_?PfhL^#GZxLi83CG5I@SQKXmG_`6AoSSK$_aK5;URa4>MH!A{sQ| z6^4cPigUwU6V@AuQbpHl(1ewiKc!)eujZQYXA4Vfjb~@}OcP4~X-oHBa|cb>Yt>R| z+d`IW%rxP!yF;Y)2jrj$yEa-1E_32R6UJ2>m7ivO8P|kAMs$@9T*=sPrU|!XHpr`3 z)+pD6%QaStd5uhaFip5(RlfM_uN!E>o1Ioj(gF!+LW|k1@=9LGZgvV8f1wX(LUOiPJTayQG+`7yK(tDxfhKe*sUpYO z*);c|e0;o<3^TC;P1w4qNwl@908RMvoDzAFUj~}+?7{~mvd4JPgs+~I6RRi_(1c+s zTEy#i324F-!{3p#)&8If^=f_*je{dV6Uq)Wp zCgLz76ExwE{VT|^p6Q?oW3uJ4j6Pc65gw#>j%2Jb0FUtP(_Lv7oj~}TG-N z-~lOEt}VY+S_%G(9qzs5y9zQPN7`zIjeJ0q6m(Qus)O7SQ7^8eR_i#)2Tanf<{se< z>JIX0CO2!jrs_M_TAq+GQpR8RFE^GC>%9fM#uJo#$hH27&~-8+L0RtJ^(Azj%)0YR zHomtKoDH_$H`>0c(wHYr;7Qr96hyb_b^`5sZg&)&xAY3)S={?(ETGdCW+0x$ZMQ0g z{;gI;Jd1nQ+cbLrTd<60aff$Jp%b6$6YjsBb#fl9T)dS)7WbP7sx+^jaP8Xt`vkh} zRaeTj>-Zl7sm4z$%C&1S>o`7^Jb-fT`pbC`wL7Z{n$XBKo9z2J1vFuhw+78>K$L63 zM*T4Ie&cpHw~U;rO%-?DfsAYPz>pT#QpmUtY#2e~Z~TOe>lVydXqWepas4*LjK+>V zjQF|ba{Y<)eeyNLGp^_VvZkJKn;_$Q-S0ibZun5pgpaob)BaHu@r>)o%MXwonFKW9 zrVAmomib71I*6ZJ4m-m#;-|fa z9+o4lUoLTpIpUhI=T$cvGwFhqXI$Sbsv_MMU4tGLOU8`Pf7Su5qQS6WJP~!+|NYD&n@G1 zL?VgxhaQ%x7vkxPu+cKE3EiHEq{ACSDfgsUWyjOPo4O*;xDNcuI%3pAM6L;+F>G|+ z%E1EnCO`0rqrvm;i9F-_FY}TgMh`_ex4c2f@X`BgxhLhkK`ebfK%H<+c$+csn$7WY zer`E*XEc?sb%h=l{`a=6zB%-;^k9G9X@>QI9+sWu5!C$W0>U+6{0ep!9x?%XSl;H! z$$GX|@^j0waba|Px3z?8!fCNG@=|p@^sr1hHiI4>m_xWG96PcP&8}Tec*b>~$<@SZ z)fwnvQ7V{B&+d{Dt_lB*w4z`7?SdYb@2Qm}_3aap_pnSEIElVHbBSx4byQmmb#YK)EKot9677zz%S3`KNL)9r>UO<(jbgo)%5p`Ve|ptgH5s z!#xJWx#g5QUi8*C9m+M~?k8PowqY~$uxv*8q|IP7oLfFv#uI*wOhj$;eTGbIVKN zStRp7BAiMqPEz%=3CMUTjU zhnnDn4zSwj5Nf*-bX|0B7i7b-ez=x9FftK6ACm~$ti4V%DWs?*Fcx0FFgy=kkD3eD zna|lQ)z$*OHhte?hoKuo;d?GyU*b^sYZY9#bie4(?MEV9yU5Z}(r8<_fBW6(=`lZa1OC_f(K%@3? zWIlm!F;cEk$1duJt9QSXa*evhAqGFP?TL6-V8+5Iys+Z{#AoYC*)CW++6nQlzXa&sHPHGKe{dD8ud%^arEfVCnj%^HfYrC)s`4Pvj>f8oNtWBhWEvMwq6?e8u>ML1C83L?;5m5X$5Fh$%*CY?VL5B zQNxHjmZV|KXX`6oT}K@c>Vif+**_UoGY>MKt@m#0%zV>6n9tTPvJP>LvBNQ+tv|A^ zLjNL-F`um~X3j)UgdLz!2RKYbPY>mQM)kh;1dXTLZV4K-Tha)$<5oUs z)K|q<(I3N!n9tU;KAl3jSwWc3)~^?=McY|696z@VP$@!nI#V&9t)J0zVVvC|(5P>o z?Lk{Dr-Me7$D1Rs+M}RRA3pDil#Ud^xuwQ@6*R{47--b_TNTjY`ZCa{MqeESziQ`x zJYz?@%pD(%zjmCTTk`!uyMEabzCYy1i)xQ=vj-iUpEBE1Z_Ix=Ga3t@d39TC5A*9A zgGWh1hgicr`r)U|l2Ozc=Ft|niKO(Z7QEhf^J|If0411B7txNw(AH<5Q5X4W3%4R_ zL8Hd4HW56vvOuHSrA-Ny3`%wbT`kWm6-r;E0RwQ= zz!F7mO9loY{qi<+V&gnu0F<5TQF&_wFaS5_t77NP6MzAT8)=KZ-(X+>j-`6z`IeTz z0Ms9uh>y5-0S4d!j>NqW-XgryP+{SG{Q5%{;S9izz9~36oB7e0Mop_3B<}he2eb9~ z5={Fl9x%{aeL>%{p?_tq{D(eH83Pc(w-pg(n}~VO~G%!hT_gUp&m~9dd)Dx0K>xUVlh$wbX0^(_u{a>N$RuVx~>_yuRPm z_flHl59alrS2_qPtYeSQ>pL#)iHyQyU|#>@Sdn1VD#Ef*$8j;Gh z7dvaxoH|hY=e-=}^$S;wX_bC8%xWT@!iWSG}Sb=id; z23ogs(;wd#d%_HT@>&7EGS!B;xu?4}j%7KAJbP!)oFQ0!eJ7ZeKc8ZVI|QBv&3XIu zMs#4v0+^Ktw++V*&i|nMZ?eWV`u3T0GnsZHCE}H8x z0W_z^_X$|kt|Pqr&)>lsqhH&g`>%=hF!)%H0L@tu8^kgz&Jy1J_vp`ll+cJlb57Vl z1#7xj65jo{{c#^$kdy|R^NZP0wC1i2XwF)eGnyB+os4IiQ-M0+j>|@a=2U!9gv>e{ zf#xK#Fs!h9HR0WVaWSPRqq8PxPV|Q5xjM!Zp1t$psw*C-XiWGyWXi+i?Ai56Ym8YA!lET!Dk+-5;^r7934#KWJ58)mb{w!&m^cVcdea^`xj%&Js5Beh0 zS!18+gAZC75FpW?U0TDt6Q!OtgX59sAnKIz?K* z{Yp!g$Q*)=;QO32I3kN3-vhqCPwGusKaWn}zi$5?AFNivC$2Wa&+KS#hZ#l)KInrA z-SNzi*LE=x3`7Uz5^_d%BrPa@Wu8N`fn z(Jjfw)RA?pav$`PT?z93udBcZ{oD`zPjrDdgkMp2q zhElO}75JbpCVmyHvZBEU-O>8I^yjoF@Ih0*mCU=h6nxO1Qf+b3CkyaFk6HYQNE|v+ z?t^wMd_?AicB5;G-0|nrGs$>1FX_B04jMBb!rBkLJUY~yu-$g8y}_d$0%HJIcd z%_Tz_cP(*Ye>1xqQtpHHo2yCJg?dr$gPwoElQewHC)@{p=uB5?KNVB%gI;pTk&ODi z4}8#fx8@S-#@>|spu4;MB>t(xDEC3X|E5PyB(jV%)|W9nd^J(KYDu{d+HK%_;&Nal z!)6~evH%Gw-ZEy61_@?_)?t@;uPl0T;ECwI+TaW3)u-TS!A9RcNNz$}Bka8ci zUC>SOv~n5vpkIc#k`p5xDEC26TvtX06$DZ4gU)?kEp|Cr4nF8>`}VP1;VG2+pqn-G z#eq5%Y%UmwKiPF4@1HwS?t?CKSxF+7%m5$s=9(a}VQdxQKIk!ed&IUQE|hn*j2sb7 z&gISoAM}y8R$^T5YVbi{qa(VyMPEZ1vE#r8-Q95%5_e{U4_cx85gK>TAAHcaD<-0}Kij|ut)u)9 zt^3jqe9(8cv?9w7!@vjqTM~;-n{NOgv}w{u^yx=O@IjB(SHh#%9G&~1!#x%vx0e~< zgT8xF1qc4a;DhdPR~Kusxf<_DdF5z?lXf|S4|>gZ1-#$;C*dBJ5AR3dx??@zOrW}x zI z-uT`2t>otZ)8JvrU8#bdFExUPrSIiVf?L2^@UZlluOaxa@&XUbQX^fV$N6ILs(j7W z6SlpKt8rmJv+*NsA!*IqT7GT)r<)L1Istss84gNH> z{&VT+(`fn7T(m@WDELi;tf6?`%Ri7uJ?g6l{+@Xo{3Zz{dU)GhO1R(T@Nd><=ROcT z%M-nOG4BWKrDlE;oxnY4NN-Qbqi*ba0R5ZV2RzHemCf;$E?Xgwdg^T-{FU|V*l3eG*ecbYh49YyXv)WNenaIp>cXq^jr)R{j=;qI$m65eUj-LDvJZ&d)#@`nup zc*}=dWIpqoT)J6`T9RLi+;5`w)gC`O=mmMy5i^7FxYH%1k@-zdHy=l9!w!kuZ<1~4 zjK^$Kggol&r$g{qnoD{zzsbksN)%t3A#%ToIlg;eZ2ZDruJxJuICjp$MRP47 zzxrlL4Jv&9PBxL>(>n@hyZ;ug2b@JmifYjBshtE5_WFSWSM0WAsPxQ7mUqE2qQ@(H zi+4w!MZ^2Y;5xlt^4Wf8(Sf3Bbncb0G>H8?Z@RhQIbrqEpKsjpxtc1}<{m8N-WIK1 zF?dVy7opkrELs*U+(sp~~4_q>Go*x^5+Q^E7Hxhw)-(ep$%ndjw{ycF4XYLs%%ON?7FN~u)@&&xq| zOYC|t6LHT=m%gF6_Qz7hJue$WSr&Tm7Q}tixza=E(=uc5ytq9x#%7ZWAQL;Q*A(p7 z`5@xH>2I(1qd?Y0#62&!_l(C&mS2KQ?AS?TaP*Cbi2J66C3@HrpMXs4Yen;^!M+W^ z1a99ub^;A`9Kt0U;MgeE;aPV`+t#Cg`qQRWtg_FdObyKG}ncxtHO(>&Gn)@AH1b z|2Jl)C0=NoiMUQY_%RxvTK->NV*9!TbpL&=;!A7r zP4A9q6USe32H$l1dAj3Xb9qq!1`T;B$3~ufR$jY+X-)%{!?R~oo*VZyr-!o{R$#Rk z_f79gHw|CF+jN4gGVi}Wm-hdrqsQ9QfoZ;=A=4M7P~|t>NCwk# zZlBWVO#izcyjSI27CVHwAptN8dS-2M6|nZ#rnuaWeBxPw-9qil@kv zae?5Q4m{vP9^zc^O*hwEAmakG!8d&+^d|XU7XZHLmfrp>n|UYrroE3pB{K~D!8h$Z zC5ZgB*ap7oefSZ1Y~Brg(;>mXNXeg};F}Kb8AoOYtcP9|-TNQOYVVHFtMWETnYQfo z2H&(x&O&nAA_IKWcN)6Vm_G=7(;BmvkbCD=BChwwcq>q&No|Ptsx&3)(R4jG@J*Xc zSVK;HNkm-lb=uQ~`j#{z=;q5bqOn(;z&G7z=Q`r25f8rUM+?o_EZGix({{3r#PY&S z@J$z|YS8mZw-E1DF?{GqjgyVRHyycsCu#mS3cSw>H}z=CVK#qf-F#a9{pgYY`rw;B zF)EidCVPW#IzQW!4mhR>zUk+;@=17g|NlJKLB@2|;{%BIs`NUFRpKdsR+`4Wk28+7Rzm34C#woKVmP-}L7vBdNPe6XM-`>2ZZb=T~R& zO)p`YB@ftp>c~SiS*_IIpWzn zwa3cHF!%FPp1sqW5llaru=B<^*1N~fRCb&!mhxVe$77u6qk9^N_o`%QOsD?d>k;o& zsc)+!I-M3vc{iWIY!{m2aY`D>{$98p7D^3MQdnosIb_#XMV7P9SKh0lJ}-=Fj1NJ) zSLN!-Y9d{)C*|FIej@XPtnrp|-}H7mi$?7=LA+NbrMQN?d^^^BC@!-Dc zL4PCZ1uX?s&9ZmS->f0?Uc`Cu?47NxQS^4j2`TSYdBi%(JOW3^c{ksU2d;FDpO46W z)3Z%t=&h}a(mU+geX6mVtYvwTyjNvwt_wYQ^PI@L`A!dyp?zm}^2}tK)8D+B1Zj;D z|E*-tZl@SJFGx|8u)mdjjH7Aid#A-tOmn`sh+@^HN`(8StLHhu! z>1Ai|P5%zRU0d~32Yl08Ev@BFpVGiLU3=FM>9-_uyf6#O9Jr(7<%T`0D8IdII-5f9-k3tLrr#f%~98Z5}N7wOn1`+H!NBjgk<%j&N=M zMJD-a`w=|Uvpt?kj&8aP8g-?ug79$oKG3d8clM*Q27APP)4dGGYX!2XT+{gM^+qExZzO&FQo;4>@idgt*69C0_^UA2^G+ z$N7wE4qCf#IN}~>mEGHs(u6?7Jk!wRu3H`;)0f>a_c*J4 z?1PJXn_=#8J{LU`sibZ~Tyq|3v%stR*kbN+-u5IAUAEbdxaPe51a`_dXY_m!g#F-H2<>7ZHch3RPpwHK%iTbv!{yz}yo(r@u2Ale!Oa%~`I{8GAh* zh;5kWRB|*!`ML)Y*PKnN>rg_j1?HO5Sonat3?GTP=5(`rgqk~y!CZ6B3h#(Yf{GB= zoWUbPkC43B_E|Lzm|ZXda-Z`y-FRAKQhhPA?1ct=3fTh>Xc2k=tXx&%)Qmi zG78Xcohi78X->(wE$F)cG|YY0LE2lSQpS35&3XS}gLKSKXUu)p(NmYAcPJEm)_J8d z(woUu;Iq!ragwI*tOm{bBQQW(bJi7n)&^huqf3`q=QY!uar#=wIW-b|*6ML1giViY zKy$vjSuX22t}pnkJucjlZn+l)KIvQ%Q*y}b^G<+{<{4=jS{t@oZHZ!f=!JDB4jVd&vs`C ztK9aG!uJVyzw!aW#N!D$ydfM<+*TpvG^x_)5fkuUx6?xFVQboD(m;Im&sE_dV`=0? zR@ivb9ie}C5H$y6@ucw8@-eBr z8IJcKI4)Fd%qPz~&&53!?H3A^1hQz?V(hUsOVDQTcQSjw?(F?`VDGD>rB1q*y|2TQ zS#I`kGm7tR5X`;>3gMb{7qOvPV!{I|aXSP{5|!cM8)2 z{qfRc+BoXu2EowU4|mcqz~?S(5W-_-;AzJ`qFHNq3v*iL;L0ZjXmjvUp+lc!Y@p+W z?nagi;VDrqQ^<=Mp-@ezz;%d(zeKoG5%gV|&w@ z*rAkvZjUbMNIOgpqWtsxE$#+EG?MbqxsK%q(y3xT<)8oB-m0WwO$z1f;;`iUWHz8h)aUP}WgUys{+*x{_fnDTXM zHhmC2wAzaD^}8}`5N1AT%0HjI#@S&(6;uAXJ-$l=NA(Gy{PSFL?hQKdF_iMp`OApI z$TV#Z<)8n3zXzfHUW+MT7ul1QrIXlMH(xJ@_A8P-4^k*!N7L`EA*Kr#P`SGz?xAaNq$>&4}F9F|I|2wyLGqo&}P4GNU6m#eG2@pW@c%GZmL0`t?1@u7UZ z?7gADI1SbX!`931%eCm*$T-T^%MSZ>D5moQSTBR>Jki>U#jsvF?OlL{Pw9lOmw1;{ z?33Rt^7Yc;Y8uY;Rgv=ba>HjaX62xWub0)5c&4vdHy>Lsj(dZ#XSfoqmp!+-)LAbc2$aa#G%QsUQQE5d~4riSTAp5%<#JFKCoVn6e8>` zw}bT(u^*e}^RGc#Cn#k8n zkDiP1kLV$Uua^wd`M7%AX2RFY#_(V0$Bz(rzI?nYN9wO*;rXIADH#b}6XE$XXW2LD za{W|zzC2J|Dc|=z4W2Lhi>%1@rOEJosqDRv z>r2+)LN_aVV7~5B%!bjb)h3v)$K@?SthZem^L1+dEQ1UvBgsAlG@#@_X3&`aJxXbm-p{c)m0jq@wDV3*q?^9w(v! z=VRgdGCJWGI{YmJo-gB;f0L%M-^o(8UfkJxFK6$aua_n4Jzin&kw0t3Els1YYV$ z_o8*PtohXIi6_Wy!D?X;gg|MzZzJ_o9Z9^I}a^D(poXQ7j)fItliob*0RU zI42(VqTa(>$=HiiVK4ftWlX0J^o6}>r-DGo?{R>=D9&sYcmBJLPx?*5 zj)cHoq!?L290TKFFZxzLfm}t4U@sbUEm+jqlm>f|ZtZ8O%#zIk*8oLEaiJq$Kw{*_q{jed(q__cK#CFm-4-6%VaP7hyBgQ_oC+e zz3|jQ!ztg3dWN*38CRxKz877+ScKB#vtciqmEnlOoReWMGVStPX8w_JZEP<(_tAlz z^hbK`MohvSGpE6auHIHC7f#6P#?r$^&q z^L1b^vLIf#M8OI6B5{N%{$4r+_M)FL9qoVep<`8xj5L1N=+uBUo5+p??uni zD(R?@G}wyt#^Q|^GSfcNL%+6S=l%f^Ywek@Ci}N z4afZR88j-7To0cMdl6Md#64v(>_xsG<3y!Y*5krH=e`4Tq^s=HU@yA9a5@^eCkghV zf@K7mt%`-cXpu|_KZyv2z388_8J^kV1AEbi014KZ&hosN23Xh2AD?K`hP|jdY&zbU z{sr-M8n-(h>$H?3t|hLr_dANcU%p04pKcKUhrRcJimGYWg;7uuF)JuZm=Q52z<^A* z2u4s;Kt)7Q5lKpv3}enYiwP&7f&p`4y2P9V=A3iRS^w_dw0GX`u5-_O*8hFqJ!jov zEwyZVcc`v8Xgvko7BiAN|n@BV}s#-_I)1?6q`B8ES|dZfax zrm2YO!E!`4beeHX!LYi_9wk&CY@=g(8+kPyW-aVNSS&OtlRi&GpJQgRQ2fRaP;L4` z82*euk*mxZbW266oHY+n|#g9dT@Nt|N` zeV%pW__OC~8(3b;nd6UVCm(3yY{l_sqFo4l-};R(te*dlK6~Z4ldxFmTv9r`!hH#g zh3e%hq4Ba#I)?d!3$vkT&QS&13&xqG!O8A1h^{1&u{~wr zd0$u@S(~qK5}nHsIv0jNA$0Cb7WE)Zw`mt*q4D)Cg!zcKe+aa!{f)4DhZ;sbAhoG2 z$Dbyrn#1~cZXAF5wlxP|n|>UBwzN7%%Jz@u`19&~GT9iG%JHZ5>AgCW+u0m{+_#K! zOZuSX_*3odLB+Jg*&Kh8FTGYgXidMFM16#;x7GdFujKgignr*I!ZU;8&*OoG)Egb_EV_07{ z1gE$CP8j~AbnK2hIM@NhpCbv)@MC9pVEFUO*bHBo(jOT9B;44KF674m!ylg~;poeN zG>$*9xr-EYJd_-NTEAaYqYyLXk7YuNT`C@`T8yy*vO_6V)j2GJ|0^YtV7H%!ghvY=La7U^Os7^d*Bui zY&ia`FlvQ;F16$MGqw%4e(pjkdGsB_)K7C}jYPA*rgHzS zy(SY4sFcd>6Ken+3K+@pr{#ois7k94jz0y*>fm;LdUE`!|D!cdeBOrRPnOyn-~MIA z@n^ku2=0*h7BPR>{FaXSWFBIE6q22RZ_iU8=3i$QDea^ z!Ryo~9lI~9Z8jQO(F40I7P=k~1~c6s6Lw$b`nnh7t+3!&wC9W~SUb6JELt+4J{Yz4 z;#gGpyc%d}9KvED%TeYqh3?l3i)z1b0``j)9E&Dh>;lIdI&dtC{TU1%#lHxw#Brq(ZaV8RRCXL6Ch{u9kZ9|Xe#sb5l zDRugy`pR^UMUQ(U#h7(UjzufIjLC(PERIF(zvqzR7l|B;_S-xmRqVnz7QM}@4R_SO z9E%FaHH4_O9XS>)8srAwXq?Hgi0+kG?3Hv6#bOVodn*=uE8TOk*mLP#jKy9|_h>Bk zXu5Y}v3Juw9g97k?)6yg^)v>+A_kzb0T!_VjTx|r8E7nlMJz%0N-XwDx`$%1htj7I_oo=*3AEcSXD17HyY(AWTr*nq|iSi}r8 zmcSyGh^IOUqkA{IFQa=m7JGMf?^K-DBo#4SqH!G(aUG5Kkcjta9Ee05NaI6=h!1Jp zs1tD`jVFnSCuy8X-+d^>nKb?c5r5LS6hvG~<5dvxDve`7#IZEK1rguUxEDm+OXE5a zaUG5KK*W1A4g?Vg()bWWd`RO)5OE`oCqcxMG|nU<&ZO}t5%DLDOLZbHrSYml#H%!p zMIw%+@huYZEscAThTvpK7o8c0TIf;ll&)lA^U@<4dC7RO!k<)N|;Q+GsT`p!=B!#BhlOC}FhaOa;3~8(32b zF*fUT>>h1(d3yi4wKdNdRZt~^3(eIqT$=7M8aC6M2E(O+i?U$e1v8#6YC-*edynbv z>>kbgRR#=CcH#L|)GiJJmlq<2Oa0dlf}DafnBAiV7Si{z9F${*OV7L-LG>RPGhDJy zw}3U~zL??CK~e@pu7>8UAeH8<7%t^mr-5ISXu|H%lyM_LWd(%Yqpe5}g1oiH9G7ly z@qljKoj5LqCOAONC0#f!wetQ=oG%A+T&g@^H_2K!isO>yz!_w*V=~7jnu{YM7w2)I zJrOyps_)m4da>~wmln@{OYoW@9GBADTf@w3Z;ngI+a1OaXvT5L)oB1&m{;VuWJ2FF zQ`_e#VfSby)~RqKC4;bgv~4u!pHjn?=Zn74{b&)*#W7r>IRqkd2sF1)BytNh=b#Wd z2bzmOA{Rk(6iDPKXzl`u+y%{PV3E_HxehFH9W)0*<2@+{LUSWnZ?gES41ITj*vEHsaSMIIx8&a1xT9m24P=DV=SchNi; z7I`q5AHyO)M)PJ^K{tlx-xwCr{2LPa zH_AaE!9m!W4RHVPl0L6b@y8;?oH$R);`ozkw2*jQr{Acc_%lTHh(u+EVTL~@@KV(ZGyEz1(Hra!*2D~dHXaFvIx~MGmLnSaHUer;ZiV5`Glys>q8tRn zpPab^z$eNSvmDW9cMqsc`7DM%vwq4!qx8ZoE;=&)7YV8|7&H9Y8C*boo5XYcIl01> zRK1tM@n_8NqeUt7J!}krmQ0zYNC}{M9Ev}qiy9%ptpwBWu1ugD6T_c~m0@7k^bunC zQ`I*SWY<Y|5k2XFq z6zqq8BJ3V*$TvS2n^=|O59Q9lu9Q2Y91{qRseJcAVC7$y<4;-ozL-l1gs^+Gh#hJ0 zGB%Xwh{ohA;ia9sj@_eOS)T=+&R5|1>awSkV9B6`h~dxM)NuHrxrG@1)c!RPo@JY0 zmLsa`)DtRF?u_9Nc^M*j8OqlX!Pih8hX@{r@;gO>-=Vw@ z61)%PgOK2ZC{Kh0Pel16Ecl~WBki%^l_=kY1>Z#Z6fF1@%Clg>vrzs83;u=jGDz?; zl&?X8uc15+50`dbdDjE3u9PBxm_%{UCQ}l!TC}y7z-|#a>Q70#FRV6f;*<1G8UXN z<(jeJnkfg31qV&JX)L&D%2{K2`-y*-1IqEiQ}f+Hxk@8<#v(ab}8qJ1m{b+ zU?jL;$`ND15mW9M3+|Y5%2;s9lxxOd1M?N;fbb z64r?GlD+EsV~6%tIWMW3J{+&@d5^GM+zM?X9yWV9VY#?!m9lW***ZKIxACD8x2oFK zo%8#YuS;lz{qg{d6cy4*lcTBAjiQi?MN9^9e=EfvEqShkBaspkZX5ywV9C@x_+8rfM zZ$87FHR)3&+3u-y|#-S8^f%@7Z9^c}X9$PT1r@ z1I|k}Y}*81!1R;XG#6LUvKmg$@Z-GXd^(pV2@4R@tu>vy=1d))i-RMb@PVogICo}S z#|gK-=fQFQU{zC`d2|5B`2zJ(G<$S3$N5!uQAq2Q#&KS@I#iKAlRnE&aXyNk3EMg$ zo8$bGcH>CS9Opw1Zb9QqVmZza>G%sxkq_oLzjJ*(T&-d^ zj`MX7x5DO*?KsYt+usSNS~TFCV652~((-%?$9d!4$BCD1H0SZp`d5IVia^fe_c}zs z57y0t^Z5OTbb&J49XOA#T^<6VCSMWD#g(Yy;N{?rh~a#@${7&XuPf&QZZFP;pw}e| zcK>_#y%GW^(SV5NIZsph^q#WrEFZXJVkU%FbmCmV$<~QbJaH9bI6pdQ82DCwj#w^E z7vT*R0<1ZY|3*ol%dMf{Jbu~9mEg;qew@cI`gxADjEUqt{*mTdn!`-sIDfKcH0f6_ zjpKa(cS?Bv)v1W(;%ars0`FtBcrLE(z-0Px0{kCU*2SDqa=ZPV>PRNc%jEXF zZtFan=NZlI{F29ca?UD}b746H%;1xEf6kGqpfQ|Ui8yzLFLZ$zI|s0%epJ?O5REa) za;|N4K{T{qbc8U!OCFyLZF8p*=8t(@vp|&uj)L6jS1 zdEH@kI}%w~2DhbllXs9-wy~V!KJRS=ZYjZ>- zPpLhFu;;@|8$dy?PMqT|V_E?|!~}AV`<444^0sLV=eRu|g^(;=8n>lA#f@~jol0&? z<9d8i9IBknZK+ec>By&NGPk9wPj?~z^`p2gooN3EB~m|SF$2Xq`rbkb>nH|-z(9(P zAh3~QCJ4-IyDJj}mQsubfw2^OL0~V%WDuB4u^I$cQw#@z;S}3JU^~Tp5SUN*0uXxv z#X1mJM==lt22yMUfsGV1L0~4uQV>{5F%|^IQtSnRy%du{U^2yO5Lity90Z0_YzKku z6!Sq~KHUpI>;?0vPFhp!Wwu1I7Xl{VzmV`R z>UT)^9rZ^n{E_-87Jf?o7YqNTevO4+Q-8<8-zg4YfddpDu)qh38(825^$RTgg8B;< z{zCnTJ}W8t5%n)D{EPY>7Jf(l5et8$eu{;kQvb!mf2m(1;n&pPX&zqkcZvf@-~h!3 zg}?`j8#;j-*XUdn)KA&IM*S2EKefI%1Fffi%3=nJ!+2mR4(H`&;%2G!d5%{$KM`+k zvjVYPN*(7goOk#!V)rr`KYj2?MP0tfC6#M|H|X5>9{2oB75uW7Ki}gzCtpJwQb+JT zuB~<>@>nYEami+55Zhnaz0CER(TL$NyO+6`T8zejj^TTpY_~BsPYB|B-0+Hy_|ZyF zzQ<`7dg1o>{_`$JTK_+l>GPI|zOS2~&H0=1pZ9y~Kdbp4$@IH9q;)|sZ~t$~ zh}OsKERX&-cm5-}&!jkrv)IJX8U0Ne)B60Z5Uu}rWY)f@|9528rWntEDwpa+%$Mov zKa-h$gg*aMxpYl=n}1Vg>&x3OUDN-gTxyfN{l6(Qo8)bl+UNgKX73JARGwMD-W@Q= zCKE24ZAF;8Wp*5R*>2+U<*mU$i`XBdENd^=JCpJ>^oRY+{?BCk1Euwh*mdlBR><08 z?K0W4(oFU(O;L_SIjv9MB`npa)v#!XwvR>o^j|FcrN76t9&d+Uhs8K)dsvL0oufN{ zbO!B@&x@5KCYRRda%nrPEjBOKK9@`T%nOg60D|ID?c?}#Jf zUA`x7J|#JY!?=(8n;szUYh$?Fc+JSIFX8;(l0mQje=0M3f9JA*zEkdB?_c$rF3A6P`j?MgulirsPR#KS zmX>0bnByPpEyYGL$3IxDKW6>8q*<|k{$T!}y@1yLvq$LbN?(Vi*vR|R*SY>$lwuUzS>>BAu(y2i<=)qtE1{*NgfWZa~Hej#; zgAEvLz+eLg8!*^_!3GRAV6Xv$4H#^|U;_plFxY^>1`IY}uz`Pq4REfav>k)Y6(R9J z2Avr6V6Xv$4H#^|U;_plFxY^>1`IY}umOV&7;L~`0|px~*nq(X3^rh}0fP+~Y`|ax z|7;uBJn4?&MN~FF>o=|K6ts13vLs)*fVLis;BrF6DtO#$e=ZlV_^n9&NWV`;&w-vl zV1`X=_viAc)Dm>iFOti5_Dn34iUd_RtUCl17S z;^_C|Kzu)repe2}H!eFj@r9lAeVweG-gN?@{*nq@-uHC~T#tFf+oa#Q!{R%_^xJk= zeA|wG^A3w|-qCNdVex&vdpkSeVP%^0v4zg0?*MUF%+H6SCE<8m%UfJ-InEDbr)s(54_?37(`bBjh4gK{kyTQ0W_l*C({EEYKHT;sZ-<^G#q8WEYv*UD zs!+vNTHjAQ&0wRAw5AcQY+%=s9(?ZW=QoAkrV1{n7k2>D&&{|z%eWm_K5xb4@g15# zw~mO*;q==LpYpqNd8JP;ymP!IW_@L@a>fOLZMZyXSS?&@c5g0sJaP|hP8-hU(I36> zf;{QlrW+1EMU{6-XWZ-(YvU6qeR-Xqg{|=j`hH2)COx-`*%?kv`rd%!T{J5M@)M`a@9xWXm6rC7R_$_gP*^jlQG&fu|eQr*(;H%Yps zI>$oibSRplgK18d04Sp>w(xAl8De5r{RSYX@TO z=vol57Ick3tPx!c5Nko#2*et(^Tc9ZsLf+x^VAox@CE84SojF_9V~o@`VLVb0g!&E$-=RJQ!l$T@fbbFOJ0N_A`UnUgp}qscci7o$ z;V%@6u)w0f^X*IhZI{zu>I)c>X@#V!!oMKKKorcvwy zfn5~SKwug>r!H`eo(V6ud`&YaS-s7RberDsTy zI73R$mLhSsl@THzBS`F;=bc4l3i3ukB9#kp{H_B}hRP|Mn6dnD_F zNvxdp!DLpS{=@#Tv*xUQF0=Ma`{3_!VZUQ_=ns@$!^g?mVue!M5(aPEdLvJ-{Li~v z*ckQN`Sb1;HYdG)G3$f1N$dW3-vHB%-uUsb1FhGvI_!+S-hBU@k7xDiFWDd7j-K9F zzr384u|8NG`h!caVe|TPUSDc^46oC=Rb{Hn|6Mk$qZcp*{tsA3K2Ew`j{j==q<-hf zbn@@CPwICK=)AbCGGEcN=YJZWP``63o!7q&PpIEfT}s%ZFB{hJ503qp_l1AwIu_Mz zgZIChUDW)MGd{Z06`x*GTol*V1y9U&#qptEiu^-e@UcFwIJC00ZsceeJm!rHzPGQF zZdRcSmeYDp0hzjyGFLqCSW7%S>ZtBnVq0u~rWxKl%YyjR_tKVWTOY6cI)%Ke+76E| zQx|K}kCI1qo$*K4H^^d-49woz;14ScQ104Z@M*^v^vWR!-8YVc$-N7a_T&{s(6&?v zY!Zkrq*YPG^~;9t*KaDO7gkdg_Q{6K>$eoM?b_fWFJ~9EzwV6v4!Ghmt&58uH*vwK z(_C@Ul+Q&={9SOGS;GqlCbxmuz;+J<@;$!;` z>qZZ2i=DqV!?kbMB9m*j!(sF4H=B|6`whjfNvW_fFbIttF$`T?8UaUbx1$ZsJm~xT zl(_A=zD0jWF7;`S9R^w2;|+Q+=)qtE1{*NgfWZa~Hej#;gAEvLz+eLg8!*^_!3GRA zV6Xv$4H#^|U;_plFxY^>2L5~7!2jaT{?)u^>sB-C3tjxXczMyE^sn^22`01t^*B)W z?1A7n{_+ff{<8t}GG3?j*#q%?fWJIr@DFno&s6;7Sq0h-uraW9X!~4d&mHJJQ}O59 z2&_*!PF|<<*#j<@K6}9B26^Wgw=2pSw=3#1ZkNlfPrdg4@+=4Y9sR?f@z8(vgYm?y zoVC5ey{CAlf^oZi?yQ`RiPb6X6Em6hsi!yAFE3|vWpieA=ns2Vgv+c?+7_3kJ|)bc zy3~87V&=d6d6*-U9yXAM_V0KehV^8?#!`I?oA__66A34MeB}DR_AhyU$;U_iZ+|}I zAJ;+8AO9sd`44jxIAg#`x)A?WoTR$U6IjAzy|rU|!5@s($6kF**2ikvJ+IF&Tp!!@ zG2eib2HgHfyb$&$p2afYDxdo@CFgvim63 zGuvbJ?%n=r&%^)2J*l{NW3iUFcVm0L*!S5zDVJG{pcg0nm!5}b^U=38y_n=*5>Nia z91ZcLbVh@(<9{`tG~9Rp)pqsm*dTMq{)=z_YjtA4NruyU_ilf|WPPlri}DA<^|4*= z-VGaY@}Cz^8gSBplL8I@wHWw!^lZRM15O$Nvy{@@9gl(8{e;A+7qxU+DtKxEL%**q)`twbD{TN9< zcB1WYy|VaAKi2x6a$ju7AO7>=y?@LfRvIdC*83(kA^lbH+)nygts|N$pQ*_6xA_YZ*DuMhA%%;51cF!{zXF5g*@2KM>G70iwwEm4B1 z=R+NnUkuBJp}LtI$2R;L4P_hL;_^dnIGmE#0#;|~(cbXh#FfkJU-o}i&VJA8F_~S* zu4gi9kG0EW)(`8C$*g}i4koj4vGFmPjhBs^$!s2MK1^owWAkJ(n>U+3lbJr4UYN}E z#Pr2vp+5t5F>SD){|UHlh%*gw=KqSF^kXU!53%^j@VwBUXQDVBvY6ZuXZ}yXw|^E6 zOE_uZ!3{k4f4BSbe~e@GxH-e~LjNOTuzwat{dZ``5KkK7NkcrzVrIj0mH#irhyPXV zHQ=NHCk;6H@5ae(Rh7`fVv@XiyG@En&otQGVY$Y4a3ty2%okeKv($bMwSbW6&4|f8 z3(aTmOtAiT60IqJOMYch6s-8*h|$iS4o)vRfqpwN`$og&NPFv&sM)0Z#0(fIKcs26 z3lWt@3GLfPs&~2$(6KrUAy}Qh`?J9Nw7W*#sshQKtAyI~2g>WM8mZ{!lnvL{^wu<* z_EFdR_&`Y5Tt$2FnF+kkH;2|&%4#+D1K|C&rKs`Jck-G|k|64PRg6s{<<{%{U_u>R zJn+M3t4R($AiU2_#QOSrB^>q}twHGM9IftmJeNC^%KCGuy7mXJe|+s=X!UF#YJ7W` z%1Aa6=FYN&=NHVhrhR(BD@zP7bF8$x0~^DhfL&zw+w~f^i=)8*$3-%)>T%8Cxe<_` zfuY@UEA7Ikjo{SXBJwzOvnJ;4NEnhc7y>7nX)j*;L3DRslF?J|XnJlQ3K6zScs{?e zW>mv`-Qt~D;9@jbGcv)Hl%E(4%5Kj!-`5=_3v0Y0c02EA+G&Qu@vf)Q!SXld8+t}T z%8P99THvhtxpc42_Lvf^j#$atEOk;C&-Fq(ww;r=Q)Ga}l$Pk^-GlOzjWZ!y>4Bcy zIV0~oECW{NJwPu4kI7G09uC#U+Td$l%gXOA>H$p#UqUUDF3C|w1lWey;lBBIY)oa{ z;ppSR@WRPVt339d^m{QFhRMvdA-lhmcfL0GZaEYAv7#QZU`-O7on55aws#R3H`z*2 z=h-#cfOAT?-f$HPN`EJ>+b0pa*gQf%Zyb>~FARgbwYwpu?!0_|wG6ntDgzcxpR9?V z;7(xJ8AZmI336Nd&5F*e3lxVo4wa|WRlDc^s_X5v;mfDs^mQa{z0~O7xXkAzL0Jmuk z$>{1eG;ZT)e$T%rOnYysy?MV5l-awz$mjkv)$P|x&~EPsQ~K4=&W)@DH(zhmtz9@v zonB1|N&c-Bt7d(Z-6&Rq$$2vYTcW0Y!xS)E_)GD7_Hy|q<7^1_eoWpZUDIqH76yyDhmd8fyJ~)1N`r;= zO1PRoTb}=Etzts!p-_CWoOVU=YtrgL4KSTvLHl-HA6T5&PdBA+BegC4{z;D0N3^kc zhx``_g(|QCg-v)ZZ*V3KUcPp~{V#T`_p5Uk7~Q=KY%sObZhYl6d zsvh~KSv%<(x%fg3`-aufR#kbyo=(+Cy*r=P9+6qF>f=JB9PmzF=5P|sC^(5abh;(~ zxh4w2n?G`I=cbj}KT<-%ya;&u;*(~?*Nde2;y7r%{Jh5g!$$H_(-u0Ps;jjKY7OsS z$RP1*b#1rg&XBXu2!@-!)3|yC!yS3(-orDURQ<;pnh^D0jmnxwm2@yq;DCCU~1@UuygzW!PQ!m}jeHtsX0((r{zAJnNID!S*2N z>M@JNP9LYyJf}R}?+d!MafRw-%d=r^)>JY!B|~$5Niys{vJNdTd?SB7J|6Nzb`tv^ z1)4b~vCw~?8Mp?N(KeL#ht(&y7MX-jRkeMign74JNX}+3db~P(E-J76II=ICulBU4#?Y;*w1-Max$}-h zT0GQL4IV8fCW_cvR669MjFT9k%p>%|q`Mb*{Zp^@XlQn-mvaqE}`0pnXa>zpVqD z3b)b**K7_Z-`t>QUn}j$>&?MU`_{du{RUaaeToV9GSR58XL4DMRG4)x3YIs2r5X3) z1bK4eoNo5)4eAbSvZ0N4Q!pK1p}pB(0Zn@55!)*{nmoG%C{bU~O|mOgpIAY;QS*G1 zyz-6wMoK*8Ao|15r`5HWmeB86RStozUn^>DJ-?IfuZ{8NpUdSxhXg_Lqld(+;Z@BJ zT^OvhDFXx6ywgmp5)9ktj3yDcf;DR8udB85u!m^ZmqlCF?@&#ApoGH~6`(*hL$x+35Pn3| zg^T8^Rc>#6p#P)BFnq-}Rht|HkM_Gko4CWO5{njpk-r~r47;+osrGI`5H_hUNksiD%d59nmRn zbmQeqcG|(Y?eSc`mcJHRt(A0QSA7mj_$+bpEkY)^7rvD0k6mpCz9**gwTPkq=opj0 zuWdY8gStfy=klsH_mN}s;e^e7=GZi7@hg?f)%v8u+4d1!&hSrzuOnUfe1}m#eb^&` z>#h9WRLJ?zkLzvFHzf?o%;4qM8m7Y6OVap19@wwDc3G0!rSI464UFe?HXKU@--c58 zx6U6G5lMviC0{)fKH8UXeaiB(p?10l@Av8siVquy@H*4BrGcH9WHXf-jYPg@SMl;Z z*F;#*XDydQ4#h*gDZ9CRe<_V8{e7i6ThbxGc5??d-%3;`6B2s!^0Vr6DAF6-3opsG z=O**d8r_pA(D^p&isTD-jq~OzO8U0pV>tgL1A0w!<8^HO zTEH7)b1qx;=?8bMow@w%NgL1~kG`A~*oW6S*RLkjsnCwg$3M1$m&p!Xp1-yW7dB==T`U8Kv-RA5WV^avw@Qcr9ucxq7J$ zFYnvj874F};<8;%Ff5xC&E;9DqvU8nBi`4}w9LQQKzX`nv%VVN-Bx6`SMtp_&+d}W z*p!zC?;QYVGQaRKlvrm2_x)czIpfOK2w%iBMEur~a@a*nsNbX+71G{wBHO}mtk5pb24?>#;OLa$cj z<#(G+Cc73slMav zx1@GoX$-QRt{~fSnAg8czd<^o-f1pR>lX#ftR>sdIobl+R36ORi9Pm<#MhD9U->8; z)~tEJ>(8L~gTJ~;*qa-qB`;n{7+z=S8ZvRveqLwbr5N};zbTjJ^~;1dKc%&s*4olN zy}G2gDPMx2eWc{?$;VHTJ8{ii;PggPQn}XR}V6AM}XfFBAZ&w-2x*^#^&r!8ud=p#VesPT+pj_UW%ZrH&w)K|Q z7Z0lmx2s4t(71O+=yTydAAgfh!@;#o1Ruk(MM_xKP_jMZyP5c_rG5GAmx@q7N7D0z zSXU^SCHd5%@Nq=DP10eb;&6z*?gyUN@2L)MuL>>4hCrPbZ&Yp9d?kJJB4OFn@2cJH z&yn#L;=#DMtUBY{n!m_CizA`lmG7#fndeBI`5~~$^Nq@U#8;x<=F~7Ncrtyu{D-p- zPI2rD_p?)FUd}b}#v$o&ediciL{I>#KWP9gJ-9%9V!kQd9Cx0i=6zJB$ReS>q5>&1 zZ-V+waTe&eb9ql7SYBSFovJO5x9s(X71e&!cQCfbXY0Dc!mYacwdl7gSe=@sbvi%m z1e?|vIhK5K#1FsJgDii$`a5rQ#V>AkgjbW>${q(a#750V!``T+vW30oqhU3(pzzyN zRbYS>>GiD)s3ShA$IKW6BQ7VB%XcrRPpeYFbBGK1Iu@&4e`i2BlLKU*YP0$|#Rv1( zpGn%2>e?CKL%5t;D(las>z&mkP%%dBb1MPv54ug__P$Ub9~chCMcJUN*h1Aa?1ZjS zayHcJWg~mj;*R2C!&n$}y{%fN+Ch%RBtgO2TI$fYOURtz*^ppSPuA$_1I2HXIOv$% zTHUJJ7Bca10_03uDZ96JHL6`X6<)7?qe88+$j@%s$@XX<&YePG8;`kmPtkJW1@cZa75R?sQ`soJ)Y4~&lAOFmtBt9Eu9 z1?hfm$)&Bk)GcmiK>Iq!$)wZ|>P>B;LHoNIDPH5D{?sKC_H9pqTGv;~&X=gr=`9KH z;r2?|&<85Cx@$Y)+HJSmyd(oI?g)Za(`U)th8p91ZChyl=7idRU~4e0|C>0!{HS($ z9}L}I>?YO5y;TpNGzwy^>q57c&(tlO^n|@(-Y_+1u&l{wYrOk;6WH_as(Rr@1thd< z0Ux?wQV&$SL9-LC@S)#n^&N!^?CMh+LTq2EE#LaW$(^T2qc0!SeMd%t`OMld^ver% z++knHrDJm`9b3$_bl7C3lx-T&7uj`If@gYJ)yJ7RI;SiBVR^GfYP-CO(9AdkHe{s8 ziXFS7xxYQ2x2sP5+SCblbWVZzrt@S^W=ud6oBP0~`1R`j(N-{ESsO_AKBfK?LJ*PU824mu&c32Db@`O!fZm%$~eVC}; zv+^;ykmdxlCf`!mU+Dp+HYreIZ=@c%efTm)s52Qq5Yb-K2=aK>P=5GP#qFI>R^%v}Lp4M(3U~D>EDPd}$VJvUZnMx>gDKJ&lEFj?QX(?H2O3 zy)Rv_Jav|@1q`A09ameQwhy^8!96^O=KmT39qpIO+E09gtmwCT&v_klXlg!H@oc{m!duK;-Tq8V-N}XN zaJbHXRhF_3iM@cp>0`0FueLGtx%7~<{b9QCIwGZ=D zw+G8f#zzl0=%rI@YdOKbae?5oWuCgGQ3ZHSzd>DT_;iOk9_{TB<>j=Y&=snoM2dc>~3B=N$-m|Uw zx>~1Lplhue1!k2ysH^$yCX@HL!Hr`_)cfkS0NWG=+zI1u#g?$$yb4%by;b{v^@sTnBcO)IYT3kD7to&Lz2Nx%HR^#+ zETAsMigh2#+g~UX1#k{IicWWV;4y7&H2cw&+Q z5iav(S7IiiW-AgP$as~k#&9+A8ncj8F?pzdcR2|rK28Srqh-|fye50%Rk{)koI$o)DL^S3Q2GBY6GFfT}M|)q|5=h{=a+xctCOy~t#@?mE>& z*7-{6C)Z8)F08EthmDogr>bpG=*x#_oogkP)Q6Wg+w1>18#+8TQ(w8gQ>Wi%&ifIh z{Ymrsa|Wd0VdG5z4jq#}H4VaT&3qwzi@n@st_3a|lm+)3NN%&!HOTc?42%0+UUvUe zBN$${JdgK0s}BVIcHYXXLA|M7@(FYNuxb5I46mFB6>qhbO*@#2!m9;?t^WgATHP}E+bShI zcA0GdOdG5?i?d-}Kof^<)~^-w4i19V_>t^;P8r-hLkUZ3tL-QE9jB;UK>;;#2g^^X zn_}aEnb2&{bcYbnrf9nTVd7o%R_<3N25%|6NurlLklXAJ#|h32VXMh}`PUyEahHHh zNNzX7A!tiewDS{!If-kQeaLPMl^Px=&1SupcXy7)4;xM+!*^Gz|8Pt)K3N`-D_0}%SEg!p`9QiQ_y7VhvW!|9- zl0Isu ziwLs%L@fAbugvxL+Dg2fyFl}&NPfAz3{R~X1+$aq$$Dj;K`*I4j>$h|``Z72Tc%}G zc%3*yes_`r&mGntj=4q4*G_AR*|jZ7udQ%80)|x1kuCdp0c~j754@LpuUg%~9GKiq zPxdL5S^J8DQ?{!E4!FfF_Xew=rt;=Zt?_-=DDt7VdHq9e((synt>I1evGN+7+Tz9Y zrm^jSzy`6-63zW5vo9QQxc%)Y0Q*L>F*vi` z^>kBtm`Hi9m2>XcugJ<*{Q8gys=Wtt_e9x}MTaTJ-MxpsCbEfwjpr7fZ#Oy~CRd?j z8%^ao^V6ViM2W+c_ruWmVM=&CYpZ>QgqaGj^-8dN*gjYLvzKlbjDRs+dgnS!yh?QM zGNGVhibH|M7A?Aw4dr()%pL!HpYB_kXi~LO<@yI2r{Vig+CqcCICP#W$6_`e;v;xwSfD(Cdrpax#1T1Bcb*BRGC{>fadL9^>q<=5=pF_~ryCNnki z8ArS0#-T%DXxIHR)7r1m`}(6`?ac&P|C@V}Tl;hf4BYRK)pG#quS*0kv)#FmW-KQk z%6EaA4acqc;VuKsXUgR#@5?nQTtL1(@&wQQHCMQwtPjt+B|}id>N4XU)6p8|cv$Pc zHuuKN0fKGsoKRiVjeG%SeHVJIcz2d>n_KIgW--%HrI;S@X%f71Rd{ zcIUp1twhlCFo<&BB74&EA^M#W10TkWmlf1Fh~`kAeYD3{<~v|LI@Fv#{}5s)JKbqM z8nS9MEU`bBJKbjvak`NK-!?6Au#aks#vhM^N1yx3bXPW@XIm(zvSyV1sbyUh%CqrM zBWitaPW83ql64~BvfFd5M&^?JG{;nZ?iKqv$y&vgj)_!1t}?qBtC07c(QxGSf!umq z=a7~(9{8a-mV1BM6cRN%1m?J3khv#)MJcsH;ltyzvX=`!qc;`ep>wr0x$nlUC+e^P zU~j2hb?vArT$s`biVx3`2cE;&-a8!{`A12&hBf&5b%7h{NWS8>1HKyJ4nq%y%18HZhCkkR z;b$Jx`zLZ2cB%QZJ z?-r%O@>(Sh9=nF2z!k}`vQ=f7bMREOi1Lf`s~^i9q?}5kG+p8HsG=1zY!7!932}<7-`+)a8irQBFpl+Fpa+3k(cqio}-uFG2`_z06 z*)}T`vcXgxZ#No6^+^EJjpfwA^|dIkb`+eMP)5C?^BEM~Arv+~`J&oh;qzbQ3H75O zY(^P%RM|6VR_6q;SzAv1EK-Z~+jKqbfmr_PSx5$U(f#JRri#C_aL7q152o86j2jP0 z=DM0~HXVhUNIc8IGdV=-?8nO=6jTHKb}o#Qa@T7fW#F#m*6}t+*(>p$N&Y-nwtI~d z>(^;={$3Fq!<|P;eDSp-AJ6F(nfOTWEMDH^ixN*)OLwU*!-<4z%Ysrto^Vn1>{t?#5J`475+zdqq6>7erTlJpx^G3 zWWh5jFRke|i^vBkcsoyeG{rvgwYeOA%@=>TFY#z?Jf5PtHiLNixSeHj;OAOgzSXKX zo^^02m%A^1i7vi6$@6=@OQUdsNdPb3_PsKGJ*tp%KqucQvG3~_eC`V$DDfk|MZEs> zok_UzM}JCai%l&Lp^;LqHFdFu++HZ7o`&wsEnc+^oB9Wa-2-4*Yf;TtN+CcQn?=zSsL z^U9r=fmb;JAE#5+NbJ(cgI}vPYKUK7k@Ti^wMP&9VtDzE^9M;MTZt2C;%5$4^HO~Yd)oKIyJ)VQjUn;6A0F~l8mH3iC2ATh+3=f90cb?ahP+Ph?~b^$v!tK- z6)cIq4ODm~aj6#h@%U(TYhHi*g0|SoP3ku$nr={?C0jc7%9Hq2moT<+b`H^DNe`L( zmn%jz*YG*E$Vk93!&A7tBq|jjYHr8dtlF(RUK}WKf)VT6;Dt+i@$#=tEpfB4k}v$O zcvB&JDB1bUfXU>2d8xeq!JmpPrRUQ-(evq{3%vNX=%*YXcbCR6^1}*+(IIK=eyi)^ zc=lHCOB|V%hIjJ~Fb4+aA zbAvvj^@kN)wm;VdAEVEOvhpqR3g`}v2bdgt$`TD6QSijDbw$i&M+}6e5;aYP(o^Fo=u;s6#(s&Z1as4|x_+DS|T8USld`Q?hT@Hrf zr03FFf4mxue)N=Vspi#1y4EzG%<5EmU5Q*M#fQhcmMgyaNn@U@>xA@W{kb?&o||2J zX6C03nTw@%mf4%5HYZN;eyc`C;WaO$XFLw%r{j_P?0NlQ_pZ49vzlB^dD|QB&h5$T zS3j1H>s^s-VB-F6IN;-B{!GZAUrOw7&6L;Q5jX(*bh*aoE1Ne0cUJA^a)qNYxZ}r9 zJSIHmkd6E8m+BWs48Y4Wq_t?QzNMJj>k_YjB|8G&{$z^T_$PK9fYTaCd%?nbdB{3Z zvggWsHlfZBrFif9(lsb!vNYfAJyI1`Tc!DK{%lG-UP|pp2JBUI2$9Mo0&9>7$ePDd zRevh6#cW$HfBB)rA*I-|r;I7_?hwYulQKIEuMd&-g~t}Jk<&QIXDfc{i{{5kV>2D8 zLFeX6V|d#!T9NW=9lzE$Js$f_lH!4=qvufPJjrJdzPXBC(tIeJ z z?2E@y9*2!>j+Fy0)5@8z#bNVIeCdF+?}Yo!Ml)|(@j6~tyz#}cQvDfu4tRbGIWKp| zo&Pdl{jqubeC7Sl%n8AVz?RpqyQ(|xx!Hxwi342m+XvEfEWQs9qx{d6c)49*Km0Vw zoy+|_n_;+C9kX%18QK@mQr6=0dVWEPPkUV9?Ki9xfrn9kjn!E+suIqBA=y~K*Te4n zze_mKXQK;Rzd?$BW=7X1F9PaIW80XC>(g90ySB@(3>;=rkGIouZZ|ykr?f|GP+8#S zKGJ>1-d#!fe7+Pjbp0^}Ezw)YW9IAl*n;T&9a>Y!+thT8!_#|q=WQN$vcuk~5{|i_ z8IJZ3m25aA_o1R;8|i*c6ZanVsH)@bG<=ec&7E2!Hnv%HGVzU>>AcNXZBy}fi>+L4 za3K~~%KpXW64_uJ=NZiVdR}aV=hcvW`E-;OI@c(Om%sKg!4qdn>NqY*`M6e z>jn-Xz{|b_@@tbl%HwH?<+;4~Y9Q`oUd*qpVm%U9x-E_2uwNJ4 z*F%b7yxx66mAeh*_3wZGiM|9|b2%y58@qpzp2IoVAPTRlC5`h{&GOjjsuT|#(^SO4 zIm3ASc}vpp&BG(O+&Cx=?-?TL&GF1T)I345jeT>cA?1xHd>w!F%f=I8B)#QVw7?VB zF5}leyqk!xwUNrf&jNR{Zpg=DUc&=Bua@)~J;EIs&FP|JHt>Fn68D+hoMT8gio)T*{2(I}- zdd8-!+i*Oz&Hz3JXOD_FfO1T%-;5dcQ5UaF-eyyqR9tqTv@gHE6NbCbk@WmweiuCT zrZuk)H(B3JFggy=bst`S8i8YuAW{72VP8tg)gqI z{=6g(>9eab9vOWGW-^l*5 zvL$Ys)gN1qD3T3vF~iU1b-?lA)8&ubHpioj4CCF_&waB?i7ktJ z!hniZR~7fEgKs{HgKXP%s|I!0fUF*m25rfDRetC!w1?uun2Sr*lSjQrO;7fLKJC}3 zdTgzMncTNj)}PDunvu}JBVOI%zNgKR>0wB3p$Li;#H6GqImi3Kon9- zA&Zu$ua2j-=E7O@n=`AK36ss zSD$qrHMB93zo-|9Gc9Y8PKvnIroLJD(R~lR_S+1(c_SxWsZDzv96n7RwWlR6nPZG+ zY;%#n%L&3Y*VZK2hhtaQ@yo(98U@3QHdmL0zB0ltNgeT-BQxZ;&NRf6Edy}Kz-6-G zw=3g;qdLI<$K07mQ`Lo!KQe?SqEy1YhfEoxgu5S9lqOUvAv2jW&)h;(N|RI~u3MUv zN~v(qZl32!6VhCoHE7cB+`ZrTyS!_CzyJTNWv$P8*0Z1c?D6dV?0xpR+ig?nu)qwe z-;Tw;cYG_gRjuIBb8fG>*}ih|Co{0n4Z=HW3rbCG-=b9ql5lujUFD|ht5K`Z0&LKr zT{_(8CmJ~~8MEW7s%DQbL_hZ2MzQ8H%!Af&xY2YQ)q)Ho`!F0dE0b_yTy15I>l(B` zG!*oj0+}CYr@|*wZ9LIURaDQdD;+~;;G#QEw$4-=3{lDsxIWCh@@c&(OkW&?zjePT z9dPCiy4hk5=kDh*MT&NyS!0abjn7v4Uqx_tssUb<-&!eu#tC8_b#YvplE_c&3YRSb zf0r9jx!=JUbc6kHS%0-Hi#Pv4rZRwUKN(nQpI}UUOW}Om!}%8TqYS^?R`b_d?vyDgU3+H`s@7SwJ{)n{H9>k&h-XpsCB1nC-2h|4G}j^^Kru+D=}9dp4|F<%&xl zt*KZ)Uzc!k58n6>@9bgU+G7{GeDDyzaZ?;Py!D3SYj%v}pd8o_dyl5Ai>7*~0;;HIb7i-Q0*w~Ipnm2!w`@mcpUZY|p^?vu7@dgUY!^8 zo*0IIIBS-NuY8DNZ_UK6(>=H5pBMmhSEb-biA$<3#pR%&%p9b*CXwG+m;!saSUDTC zfWN;e6;8?vS-bufBJ~d`@V@#ldtiE&XxSBC@X+`!xEfW*o64;_j$};4_OZ1UJ}>zH zsmEIVZ|K$|K9kSw%lmjP6RdW$3ePQO;6iS}_A|X3fFOlbUkB(aMk>riRZi z5r~G#c*2Vb^RUKM=kjGiitx97nB?O6%1ZkiLU10Tg)=pWif%o1gWkvLCCw5;k@#me zY?j@}md@WU`f@TBl(l=|(6CHVR+TS2*?EwyJGxC&`Dzh#S9x-0gz~nUXRCsvD38_o zSSkALoC5D0f+TCJpH!-C;nsK0RPpl=5H0fYgsQ%6Y~bQzkzGtEy#B3;COdTSl614+ z^dymBwZXFP@(&{gU}8Ml{`ss++9$X%-~7NpY;<|NNX}v=92ngX7e%>?5|_`06ayEu z=8-<%*(d|1cRHa}8a%$lHv^{RY2o+lhKK@--5}@d1iW|0k&1$44EQO_!jKG0Mlsh1 zv{QQFdmb60modJOb?UL8vZjK^OU#CE2EFjANtvSKWxlX_a0%Nwc)RH9@kH2j#1pG+ z&e`hVuL`lVj-hq$uJPZAW5Ct+4r-~FVa~AOFk^ot7FjRZI;r&>dUIW$oz-uNXi!Ba z%x}IV`E_-yXnjLAoWFgX9hWW=d5?^SB<}stHC{O)+nh{z-+Dx%wZTZ_^*tL7jy977 zKRsA^=(G@qmh{6D`pytJO_~k0nqJua#IJIF@4gUbZHgZFEA#7SaB273NwmV*%4dz- zTx-Wtc95$`bWkS+c2wr0S-*w+2Y-^`;6m=q-i-;Ocm6YB#<*h1WrH9Qf0huEixxVR z|BJ$0^_#}WBb@g5YUmPNQ|(J=IQ zY&_u~$F`$g3+xETE;ffb(14^qSSH7Sfx>SxC){?|58Uq2xoC=(C0OjI^M99q`cUei zg{ArjFS!Bxr#IokdGr6nJ@b)VAlO(*^@qfAXK6Omx^R-rfN|-GMCZ%nji_NkCSga3 z37WFyJS)w+!Lmr$Wl7`qyo_jgYkZE#o$f}0eF9yRE_9s)an`iliYoLW*mNkCroAv? z8Wc3p*j@5922>wW|LZc1!0HL*lSxJ}sV_}?|EfOZiWd+c^hfxBv?si-V?){C3j*q|*G)0Km_s`D&hdwq$zFWoye)9eh{dA>lh%i`8bXxDHfcrzL zv&qyN_PG2d_R(u!kkPs?kp9-;qHNGhpHA$o@EQW0oz8?4I`sdO*2G?x$j62HaCH5zThH&s!MKUJL_ahx1v=G? z$@(;vTc2iqqWN-JA%j-Wnn3)loU8}(W;EU#ToDO_OmvAI@B5kHQaKV!%Rg(LGaOP@ zBy5m54=gL_{)l*@F1(toOYEH5;tI34*tb;woSqx33^gV`pqNbfmUf%wcWX9GF78cq zS~txH{&f28ObZk8pL(3oG==B{$PR}`9q);qK9PaYcjj_pCnrh>$|+sM&z3t2;Oi5* zm!06~4m#griM;+=DttxLh@JPnhJvd;trxozMaW;-pU7Lpvp})pEwLXV9|ZeaD+s%d z=3<6v9>k7TNjij9)3toXi`fwD=|tpNAsNsSLC3lg{b#|m7?z|(RngGxPkm^(mkOV1 zY29rc7Z0W@*OU6Ho6WTogJzN!?+w|IwMIzf?u&(R6y&kA3|EwRL+}?JVl(eyCN%y$ zOt@jvBDmE;``6;!42WDNOYGFQ3L){i63JJ6?HrJa{X+D=fAoiYmuR0YX$%GJ`ZGi> z(u;y}4_j9HTN`g=z_y30iTp!t5;WSk5xyB13Y*=u2pjgwf_)YXiN3l^8WhLRBRtP2 z9W1|dF%j-BxikYl=HDPJzhNPKWyTSm&*w5AWsM=>?@KZvci|x7r`uEyP+zV_c-LzW zIOQErbOtn}g3O&Kgrk>)!1qjdqGM8|4$tO2Ao)#Nkqy~KGDNPd=nIxPv^+-^XM@6* z@1#6mjmU-zezZJGa=l^45jxJS_OOQG0~|@(ht5Xev)c?y{r5Jshy5p)ASut=mI9i) zDhYp3O#laF1!D8XBQ91PwV24?Tu%XB1g+n^iSeLd(nRFt8Zp2RG-joCVz~CNy_oJX z;_Rm?hn77`!2PV8{7 zf3uMKqjVi5T#yhyJx@hL^b5Mrl6@u}E|qo?KTjD4{Kw9GH)_Yuf0IClJ3AsR6W70o znohLPXYQFs9k!>=UIEpSY$}%|JWnS2_A?7utzUHBb*`vha(x?p)|>U+h2{<%Lv&=i zMnk~;Q>1NF-^zwDJ5CUPQh!B3fJ+-;8bbJeo{!#(p7xU!U_ z?LQz96f9_5dZ7&GJGT!i&5P+&V|X&#k8s?jKgi*l3SnV_7mSk~O1N7v4RkB1&Ze`! zk;VOfM80$QY!E2WGFLubims$GM7~CLBFz3q$Lb-Ud$AA3(=zcIv_(>DpFwoI_fJ4c zMO44!;{@ox-<|kbUYQQLcC@Un=6sawmP;l2s)w`KO24J#S>XO%2r5Q2Za?CV5Q-LT zCGz8)LdXxN&*iuqDKO<7eMhgbE)HVsyo)4nO#9Rka3sQ+1;HY0ai%D3`2 zqqr=ZcHz}fn9Hr}q-AAxt6qSwh>P6Ci&hdqr zX6b}q51xmXY@l=6W2@Joo@sBF(=kxSUmfBbLP)#4w@C;|Jvg=puk2yp&w|bm|7M** z!!&4n2(8OROAY8eD(k^W7&46hF1oy)eSK>f@u#G13Y4cGA$bY;8v`4QXq&X)^+VZ{ zel$tzvASIdO10yK$0sYD(pFENvN2EfybxRiPo=4}6Keq%y=GGvR_T7v( z=nWSum+B8J`h@yyr2V(bbv8I{-b!pP4^M!SrF7lVM{^Lcb1X?66`mCSrwxRfq!Bx& z-y=}XxXFaooV1}WVn4Cd;28@=o9js0+}>RL5YaJq=+$(HudyXMF;_C+2De_4`g6lH z068wD^>ScTet^=75NW$-i$n*8ZF8PMnjFXOF={S_rPkbj5Hs{>5a;Jm{L zlGZ{s8k*{66P-Psec_$n6v8>@hr=R6+Gh{#)ra``bj|xF&m3B3#F4bF7r8l@SfA)0 zwHOcnHB|qysy-xbRwnW>4s#$S-;wA~Sd;-T=eZNs+@21zxEPbv=Vw)(5Lb@~-#u## za*Jb$&V#$Duzew&4@~98%wCu06P+ulH~d7D9~jBO!trB?{+pHz*kz?h>eus<5S~Aw zecz&b3M#dv<#wkk0qma7Aa?8nHDF&GmG93_0I!KG@%<<(b}^1rhV;IMZ5n z7*$QBPv?gPOBsvmT5G~9Vl z%UNH34wP>UCN^(py+FsW(>h8#nF_Y^EaBe$Mt-lYw(xqlBg`Ipg&(!n5X>%32XD<5 ze&fr*FkNFl_-l3WpT)@ihjR~4ho--e_~G(HK=YI%h^?>iPbC@t$L7{FC-S>;+YE4Y zXC&bjm1o&*?s*{1qjt>uV;Lc|ozE<@f~C*qlRWAxrbFqHa#CL}xVcGBJBz-@lC*=` zYS^NjFv32|9q+_emrH`xpJ~2|Ra9V^ zGxb@m;3xWZp6YZ@J||c{p0)v#KYgGjl*+3!pGo{uLx`OnKc1jZ&%6nrX65kR8MI86 zs&=w-a_N{RKOlr{&ZGL~=boSvt$D;ZIqo?bFYiOrE^L*>`se8Q=5kXTkG$JVbjIj~ z1JkFSu;gc5fiYl-Hpf6AfywWN38Ymzqfxe#{P(U@DquI+5ts{X_`7j9koc_Qtzt11#8&E_t# zzcnu$`grRT{w&Uf(GzK#DKC7;4s4+Ff!>pRVNQu0u@n2p8!&g~URwU8L%I3n_A4Z9 za9jlR%bY=Y)BbdB-Eoz$?5qe->fzgkf7-ScV_<)!hCUw^KdnYiIkazPfJ$ZN5&fyx6v0d2N_ZUBh2c8iN!@i>`@`oebiSd#@ip@7?MQXpjo`y?ny+pZ z1AIP-mZ9g<0j${|+V-BVu102BJfd&)*#+t)y@|~QZCT))UqpCkdlLN22qSIVd7}{4 za{tnDOVtY#FkGx$%J*!G1-~?D|8;Uy0QP={GbUJ{S5Be)lI0bT$nnI%ZBY z!HwJJmf9)aIEfuIAenHa+bXs@jOP7mh${Np#yxAfzk-iK-l zusN`V*cWr}qV~%iM&wrfsgRMCOys@NxU&;8=oroy?nkGOP#BGe~<7wY1{`m$$5N!|po?k(An9ldwf9ioD zkLn~?zeRc6nH8zc+9?+h`-DDclg=MR6S%sR%Cpx@g0g|%v*XDGfkikiLyg^TFo8S&l>7NF-%aHNy1XtCE(Xdm^PM-M z$y3t7^pPTC*zJWBWV7L=gEFJ~w_DJY*Njhxz-C3JdDR@Wy*v?I7RoUrf0v-1Hq~|S zBmP{aZKyd6PcbwHW$PAk?m;{J=f*`6`e-;FDNc?1g*k z_>I(p=ffU|Z#;6tDfgZu=X3Jg?6|uZ9Ci+cEt#F-nN0Sy~_UhW66*~ z+D)O#J=1CY6j_Pj-qU!9`C=>n&Wc$1$yv~*UCA$P zR7c4deV|imqxjPr8NB$S5Z-nj;>D%u3!HzdLjIheV)bdBI5AWUT3>z?N9}RLe$`W< z^UxvjrOQLHh@1Bp45;J99$^IabB4gShDK&m+H@FwW)Ns!>=JKQ@xWQz-l5f9y|)cL z5r}PNonYbBtxSxmAq@7I0D&D_n6uOLAabb_IQwm7LP`u^lyyHyY(By8xxHic;FHL| ze;aeDC^4)Ch%x9Tut|Zu6-ND?wYcAXtEC+IJ!|hSyvW6 zxO);gK5S)dB~frM_JM|X#=yGQG9~K~>|5FwZox@L z=l5(F9_a|{r&loOfgzMtj)Zv83$gV)XZ&#U45+%bhIw^S1GKC>Vd1A$j0R5)wsL3g z({2_p1xu8{)J*{5XCel?N5PkQ8sPb{i81Y%0dq10aJfmuSn7>}p1!^0MZoCZi^PKd z*I1v!SrGqcQ`O-^eb^y*5j-y%$M_c1p(wRTc-zd~p?&-!dpXk|N-ric?9gxM`QTt^ zYt9!ROMAtJ-U@?#zCKK*#eEdi!NtuL3z$y@N)S^N1hK=Gi6<4kVf$pKgU`zMRTC%7 zWVJKXAj#KAFvNbJwWf%mA3IVh2fo_XMxF_YH|JG z{@Chu7Pxk=t@2$Z%jOIh!sBD(`25!0f=AskaA2B%3CTKwy4uG>y7Nh~`At21>XR)j zbKlOi$XLSO?_5lOP$B=oxn9T#7D4?02PS`1J^HjT6N<(h;rm}UM*sRF&F{Y~^{trO z7guOe6kS-G+|-tl1y&xV{7GX6pfK*d+KBtgOkqVXa#x!Qe+!D4K5K`;ymIbr%IL2= z<6ZuO>8^=zWuz`M#b7h4DSUvQZR@k`?2<5C_+~ED-PtPE`l5(6<%OVUD z(!=a@F7^%XuHxtS_p*xwSzxkI#Q*tK1IczS1n&ZxyTytvsyNXx6ArkZu9{t9#@cO-=GN-tnfEy?%E&T_xrV6o_1; zCN}O~%xctSz=cIOtLk3bu^YHP`}OOlD&D?6tSMgzPb}=KqJ4HscuoN@-Zz1fpVW!Y zaBH*3J-NJ<5g#37O0&Rgby-z;vkGf+fIAmry`P_>p@)9-pAXKDav0wU8OpZ@!Q-a|;&Ik**fleK;Pc;&;s$S7T(8oFPMKb2$~zZ;`Z^(eo+rbX z;YSNbaqVFa-=;FSWLx9Kcig_dp9ZtYstA=82w|7IBH!33RdAK7-*2bnMg7mjH~B0P z!W->=RcX1|k{7Q7;qs?wCb!Q!6!?wD-Gz6UIpXL724TtIEu$^ge7u6qTqT4qeTAyt zO7RlE6Pd7W?LPkOJU+56jR9ZV+2ZW{W9(!10C;Ac!0hVRi41xtL6MvyqY+%pYClZ` z$rlAie(VPJcwstp98h8c!IPacDjPIrsxZcOUnCE?I7Qnt73RojIf*A1JC=Q}!h93` zY^t}&hNrVs7>~i7605v)@ZG1xjJf8?e$p-@v5ui%gt*CICz+2`Uyj4wHgvAI*Aro0 z0-blUHu;h{8~w=qZQ1kR=+hDl!Yz^Gpr@TKnUiSjahuZDucGjR$n|K&jm6Af!zBD+ zn=Z<^;;p;%b|#kUNaul4o&Bp~5tFr;uXr~VuO1F$&M7)7#HW3NiO#B3+&yFi=-PSH z!72DbB%NovsCTfs7wKH|X#dM7ESb(l4|wRqfHDs{jJ+(3efS1#ss?e z-a|dPXI|7D+=;&0YjtoxPU9!LVm=|@_Ccj~^o(TiykG(0Ou;BzX-L;fwjoQ|J?V7K zm}t3;b^Pl zaWWOdl`bOhkSxH5nyJ2dkc8z6Xk85EccT++G{%xJC<7}ORQ}~mF>=2@hxjm+JM({AdmQ1$n-v>zB_lGmvUpFJKi;!roFe_0-p4{Kzu&BC=%<3)46?JfGS$Bo9+i~HMoKHhST5m zn57K7Wa`iKUmMZpxpZxE!y^epFgk)!dD^zws{*{Cjm8c7M=0QOu8&J?+8L%wI&)14M~`#B zZ*-|#cz35@*$^5B`1aKWzvK4vr1~cv%N;&iP=B;thM?7EbPwgo0av`to5pJL_=EA1 znKUo0!CtJ+I~tF2HTK2dMRa`^XEzfU^+*fF(};cNB2AoKP1m`0uE)^7Y~O>W@_+3= z=Ipz?7)jCwk8s96YW9&nK8$;Zem~oX$OlHw#k#e$Uw99Z$DR_p=X*`KlO4yMvytX& zj;EI->;{cp=b%vR-Wf~eO5bXb>TtRiK6_?8TUbW*=dTZtEcr_NLX#+){nwv1&Yzxa z<`PcqoF3oI9_P_EDR*HdyOKMvCjDL1o6o+SLf5vxFNY%~JGvfx>srtHPN(bB3hNHZ z+i{0UzP^3n?&@!$vB9|LS-7Hg0kM-dr;By^Coip&yaWw(o<#mRL>114({;Te(}v2N zt%*G2tPND0v?09M#TtJtr(?+Yd6szcChBM2lI85Lf8u`kwohyLB%Vt2<*yILMmMOR z^&{*4(+132XuL7=rZ>L1e-_a9Oxiq*R9+yk|+St1{Sf%~6 z+(L(66U>RB<7bs}2eMV8J}6JyC&+w4$GZLRKcWEvfy7R=>Ie4jDeA)jIYl%;Kd(iRLe9lAE>_*#0S!f>Xl}z_3cFVkE zx9LzH>O6J{EIlbN>Ayi@H-yH2_SNcOg%7mu+6Hj*!^gDGZVOky26;5z__X^gyV!}Q zougbP*m{%h$sUV2$#y1E{b}4C{}&6W4C71*Rv9^u(0Na12kQvX-3 zS;zMErsIk7mR>lV+nNq&uYwcr1-2CS(}mq47>c=Rgg2_vArZZtaRn zXz?)GcLtXoK()_*k-EFt=7%5t)0VDPD%oFfpH9*~=f3Up`yY8usjZ!1ChZG@SB9|4 z&a^x~ZhDCNdC_r3cAYEMai-(2TAe$-8bsTqjs7rrwV1X^!<&cLv^lgrtlV^yeYt`9 z7COBztHrJ9r1^3xsAJc0=USv}ZrIEY|4iF}`s=r>6L)q>D&M+QC^)r=*4?DE7ih^t z+V*bmU~tfM+O7=qJJ`$7w48nYb6Fvx{cH6_8!SJ8+PN>YMbKXD1imlt@sBMsz(@R? zzBym844xS#%#pZit=^UlwQq$ywclelj|Y~apIIXM31H#)SjMe9N#J?<~x zIk}bn_Fz89FZjZ5((jE`qh^3>@Jqg%@?fkxm7Xa@*CO!)j~Wu2EgiyrTcn%r9c*8c zfJ;}XW<-e1C`C^1haS3_ETte3iY%z=j3;?HzEH-h>!G7FcpQ-zpU=R5tQrWHrpDlFK@$l-waUQrZRnYYMuRkbv{Q$a^TWrkIN%R0 zEA9+e6LXce$$foSqb28QTWWo}7nS`pKD?|{L=(PJeV${n!@tbuxMyBAUZ&5W_w%Qr zDDIq`)c=#a*9+Eg`=C<(^K1r=drS90P6b5ZRlDduT0;^KpVV<6I_D}(@sj(OkyQVC zc?9k=Vj_{Z&tEeEa=nFrB;QP^T>sJ#fBNjg_CI!f2WsC!)Ff zddj!tu1Nm%EsXQcIjMs9zi~nWuJav8?C30k;0Iz7d`$M64;?wPt?%D_F-cIVJBaPKcayyYNmhXNT_$-g|V2Ls1F?XT#wp7@YE zHVLQOon@tE)!rux|123qDc%_LJ#kV_agFT*Hv&r1f9pqbvUw-X*NV|vBnyUeS8Q9O_9Y{@1G(0G8hqsPsdx3 zd^MV6;;pj7h)!G9R9wx)prm{}yMrzFrt;5WYXz%J*iS%=!$DpSL* zy=p<^SNP+wUHt&U!?`>DSFUv>Eb`LD2Nh_(c1|s3Pu`;C(_5yDwc=t-((*Z7KN8El z(jfdGZwCHlLG3>;+rw`EXFd>?SI4>xqx=3BXN2QPDs-=3>roi4J4o%HIKP@5lS0ek ztYe;}ZNe#1cQJRe@iz^+Hn*8@jkVeHhvZj%fgf)BNXs*!;~G17J)Ns8dNC9W|2d23 z+(_;8~imLXGhR+GKdXDrV3+-|8BC@_`4Tv4?)8K>x9tx-YIiM zJoTTw_}IMBcrSNmMVj|fryQ}Nz7FBErIYXn?wvQOeB6$MtlvL-Om+$!|Xv_8+z@=>-o(-zIaa1AkeDY!54Gi zi|A={)Mq<9yPX8cSo+{Agmi#ru{4218Za< zR>5LcrN*)he7JfEN>Ehi_uiR;J>G>w$)a(3B~iE81>3Vgqrg|saHTT4be0f=Q-)re?UL?MG z_FZGX;PO@%?!KH~iyQa}-1~SQdLH8| z+3b-+vHk=boe%tJ*!H6pKA4-w6Ac=Rn@i?{ru{IzJsW%Dh<9^gP=LB#!3Ramn$PFX zLl4!{9xsRc98HE|^|^Yz%9pW0F5LSGLuTt4DwaylW+uYk$20YEuWw{6;)HO-WT>7s zuR!uUz>j@Y)w`n5&Hn4#5Y9K%_Un=l=Vw*I?ri*X!&oFgu9|1~AOpWm z)Pa}vag3_VB&=Y;N*rXSRbF|PjX#ChfuVl`b0*CkA92=Yeg61YM%>H9U*DKPq0biP zcZVH5yL2KvU*EzQKj7nl$9k;SnFW<^c4p$oA@>DY%|m!cS7qbVUVpj!!um30&wO#M zX&GC*_;f|t=&S) z#rI_rLk|1GL?8nD&D9OiuhkY@&t)#ScW@0^w4?_ z^IYBr%PDj3E?$_gcicFdeWei%T7l#B%JfgL-|K{+uc51#2NNZ#8z)NCHz-vesuSXB zYdMLY=lKdQ7LMI-K1E7}_xZb>L-1RD6Ueq-$LIziJYDv%Ku`UxZUMLM@KNISBIldv zwXc55_G|;D(d${2&95rLxY%{Sld4E9H=I`+oP`VI^gqCNa&`v4ttkPg?-alV{%I!Zvk4xWw+Jo{oUG?~ z;t;FQY6pjoH!^KM%<#HBu~2Yuir&@See9$S>1bWD3O{*lD!%c=8LB0>nRS2larEI5 zbfU?LU$`?7TN^2YSugJH`i1jwM~DfO-dx8lH9+_?cL&PSANtIzA#?GXNl~yh-AQjS z_x;JNm9Nmah^PD!YQb1vEgxyikKo&>rr_nVT>la_FnKZN*zB(s^i>aMtZm%zh|~nZ ztI?};byfDbDI1HDoU3_{?sMMLsfj7-B3Q^vt*lOv4G zHVYgXTZ3MFPUSnQ#Nnb;Yt-+Ah-cEBfnQs_LHVCv@H@8$;r4w_F!B0zCMDDW`^p1k z&pXeoh%v^GydI+Pedqc09$~oD$P*>@zs7sEG96Ej9S7PaN0=#D7T7m;3|yU2%goOm zjn_YjbqHG%qSL{xGNx^z%#S;Nm4!9(c4OHg!Ys$tkF(!attYhx$AZ)au3!S^%n^}B? zyJOxf3f^yV(tCOKG#jO<$9n!`J_*J#?>o5p9`_D~^U!tt?{+cx-LDc97U<01 zTb_u|PZy%usss6fZ&L8UyJH~HW9X9nN|pYUIP8Wyx~*KfDWpCWSOjn4mFH*UyGkx-W=t3FsBs4V7Ey#IyP5FIxbM8} zLaWhc^HKaqXOpmesSEm`{DZfJ$-rl4J`nUfvyr!AMK(6+h{N~R?PV^f>|oFRnu3eg zmNBRI4a3)l_QI|&BAE}{d@+8Xf%^I@i%WUj{)mbII{l7_ohwG+drw2bZJVE1POpXS zX{W(!JTAnq8SNB({5-%D-&@?yI6YFur7FRgWzH}P)vwr|I_K5A@v=U5nRkN~a82$a z?3;0jS$ygc8+~v-w)`$)HZAOpUtCkg`9({ZqzF&ktu&HVp0|hJSeA*elo$cySu6f~ z8nCix9#m}DCAPb!fFm0Mz~Zp6xIXU_oAlcm9$&~2C$#HhuX;0ZImC)bjj$&?{vYm{ zmyoV$FmZdJ_@ja*u2^dejmxKshlN_=f|1_r+0a&gkxn|kzV;@&YSm<>d+tK)H+Y7C zr`Ia7s1f2jS(BUI%G}je`Nges#kbhfa5rYea875Sp}t?gH#JSj_0!{$y+3M`PK=^~}x>P3#r*K`=6StN1~I z2OjXGKbVM0#nBP7@RL|IxNxgnT=>%i8*P~gu8K#+V~+Fj#RUN{VQh)m>+WZ^Ji*2He9OPTpK)3AAxCSIMnl(|UtUkaLoWPeGt|PFUKR_m&&@NaaJ#qoh;|hAiBrLInG9yb zelPrH*$$M}Z7a5Z6^9o^JVSjRWQeb8h2S@leX(V5Cex>%7yc7j&gQ#nG2xpN@N1=8 z0z1v%DqV3lR$6R~d0&bc{1xHRR$6$|#scQ>EjQfJBkejJG286NV_J5`W8DWlcs*{n z_`)2Q|CKLt@)w-_G5^?CSC+@e4#YFoN4)X*wG95ew2-;=ZUQ##6~!`3Kk(V%X*j+i z4jUNOFm7vhvZpufZK~F^O)%aBA{CQ zJH`!b4y|>t{B0*v!)-)YF8Y7e!Z5N(7BWS(LMq%%3H>G=1soRooc z(vF}9r`^O`{>I>x;3;tGT)j9iX*m8d-4cW`b>ik7wpeyUFoXnIiA|TiV85+>!R|7h z$E;WvjPG)>@6?qunWDf@JYT_7km7etwB(Es*W4*bJieKD#g#L!0 z5V%h~e}ohEdhY+W8+1G+9YprN`Z6+j!m_ z_8mGX&Kz!so80FJ5|mzwg0~BCtjq{jIJb(g@gozryg!3Jp7s{Ano)R9eImL&Q$eh` zAr%i&Kg2d#S}=9n7UAI4Yguu=DkE8xgip)HvjYWR`4L>7eH)C}#i6J8cFQyH%7-UW zi~k(4V^b7XwJDV>>BZ-NohZa^T1jk^X&3))Q7UfM2^B0G@LiO-Nr+SH?xQF3V#Rw8 zh2gJ$H__UVaB))bLL5Btl*5rN?xKKq+;?)sbJ&qTAM%5p)A2%d3UytXBYv_Y3J1nE zqI{DX;)UFN;M}|m?0z+8X7PeZJSpHDdnLh|~E>FYA_o%0I>kF7q6w6_XzSI`@F`9L3L=H?(gcI!!GG-8gp<$M%A zaQQ52Ji@Jt_a+jb-FS{Y^~bFWa3t1!SH|YH4XvW9=R)>?c#kF*^EiW=XR`RpTrNS(uqpK7aO;;D@*jN){Kq+ z5C32KopLsq`-e`s!_3rhE5bRL5ZX5B8n^V8SuWFR-oS^$FiPx}JR&U{3h@ z8Y;Hy%ki$iM>HYwZbZ+%bd0RY8PjH=BUQphbiSw;IFK>~z98%|>u&)KbE? zXBq-)xQ_6lGJR;-T|xM2G9QkMjM>DQy6TW|LFIwlxBOGeK4Y{7D?V%!YE$ZkRN#x&d7ow-yhJ+2r=A%Q~ zjR==-%0v!7ObC}L2BK*Ov~AqYpNMWMSrED3enZq%VM+Md8WmL4ZAEz7?`A0lT=W`lEeo(p9{3T6=?Ud(*JZbXZ zP5EcHwWM`0<=I=-NsgLP`$NxNku-Nve=bjzV^1VeKdUpjQx1!%|5u9~S&tl3@>{P$ zr?XzcqX;u?KJ4w=#)NNWE@G#5(K69$U&1c#qrKRjDUp{5kO7>%% zF5wMTJJ{y~M-bNhRmaxY4JCZ(#Buf)kM^TB>nrTW^8<!wZ;uIQ-R_4UpQe4*RZ|UrS$%=XC4PhPrrr|5--Cu>f&PBNV@GP^RX;_9wV(0u z?Il|XyQDI>p{kg0_yB!8NmNL=^pNcclw&*`rQ)< zw~aBw*Ilg%mwT9F)u)<-jXql7hfd$g_>kpeh21@y2*+iN#%iid2rr*%jZHw7u-aW~ zJj#2mgS7qle6z-(^-lIuUdfH$@Gy^#t6kQ3F4mMt<;kb5ai7H%gylL$;|0PagrirF z#-9qW5nerVG>%mNM0k3(6&^8Kot372Yi^0-kR@T=Tyxz1dm3TO6{h%0Km_5gi6%JO zK9BJHTtn^~M=JIus`Y2m9s8VSoD z9)^qgCkR_=4aJk4&lB!*bubp+zD2n3vKm%zY9oBwy+2NN?jQ^smGJq%Z-kYrSHJ+eE*j4T=8+(jC*H#~U%AQggMC9M~Zn4WR zs1xpMbCq40J(%!IiwkVQHBG_~)laf3Q?v+A?O)FxP}e1VP<|I19K{emUAKj`%o<79 zO}mIY-)=-WIy;-)Sx29nIf5yZEG)Ms@6PSVU(4<*9uw-sm)5?qk^n+^moT;KNXnYw;=WhuNa1I zn^Law9EmiO%!z!AmKECMOY>5aZghLlk1#pYS)0$H*X8h48ffFHq83+D?>xKA{86GDLpY`8OJ^@q@Inp?m&|Bdy;pkp!(5-NlaOQn=xYPd(;qMQIfC5LGFLE<3loDu}`gGO?9w9 zD)&gV{?B}==iKRUaX(^nBa(;GO-I4y91H6=e4{0*xfC5 z{by#uxx@V)|95-uJ@@n651xnP?+ovHYi7-wHEY%^18}o1#p`JElH1bJ21?rqy1hYq zvR663#;Zq3pMF!?>hP>LY906P()bGc7J-c-QRMCy9HqkzZkTUSN8?31J!#9mP3CcD zW9au5x2s1rA8+pbIko`*Nd8y2cMyH>u{8ykoHZ7o=Xs;Z>k~@D+Sm+>Lo0mHd4(P< z|2*5mr&~`9H~T0xaZ9tXUD>w)|43f6^(*kZ8hxPX&UY626TcCW?{4l6z7=0tVB6w& z`avhCZurEaM-^j~cDIGcv+i0HSyj0J|49BM_0S&be%hO@iMx0^-*y%_4d_sYZ#u61E=*%)K9KouNhLGmTMs+ z+WHkZ`{-$sViue+bHWf1x&I(S`qb&0VZCew1g>38`dn|FvB)twg&0L2-qGhJjb|7xt$ymNM&xND;_xaMEiH0xqNeX-`VH|7MoX)X zJ|o-EH4Q6o87;L>jZumGBYDx*ufUaC_Qu|epJgn`(Ls@e2Kb@=m^T^e#b1zF)dH~8 zhYuMIoUf9wpkZiS>|2JdkD5^BOo}sct(mnoaX4z(0}~ZT%v=ls*Rm`W&Pt^{0>v^HA6Z{-idr z5Pnm$^Q`KWI2br|xHK;0ws}y62>9^$h}3e8w}p3!Vc?ik5^6l2W|4cT3%KsA3l|J_ zTGY2|1U>!QK|<^mi@~QW!Lwrn;a=-^7FSo@la4hDfxX9cEu*(jlkT>Ng}K8FEmycd zQ!^W^f1x%t%!Z3j2}^2|FdI5Wids^egxRpE_S}NnL}sJbms1whCNdjS$E>rUHj&xz z+dbZb+C*l<@>N|6Y7?1_$E7mNsZC@y*mG2B6PXPf*Ai+InGG6O2DORI28}C&+C*l9 z#+5;BBC|o`%Ahup*`RS{P@9C=pm8mwHVLyq<625>YM2eyPqADw8#Jz^ESJm%jcX~( zC9^@}%3!%*X z{I%{S@x^Wd{ zZJteLm=w5AS?fsG0r7TGu`^@S}teIerY*h zU%|?$JYPGZ*xbgM>7n{LGyU|Juc=@*>EAdrf9NrsnN6yTbDmAkIc+nng>sD`PXs+g z&`$)rRL39wpx`G8{-bw7krjDyvGV+QnS6d8m>$l|rjR#Oa_7opWicyywh<*4bd531 z4a z$IImN<7ImC<7KgNX0ZzK7HC&OysRGS@w|<2-HchhLOH8PF2nL8=1tJg>M`Fg3jP$R z7qPzf#qG9cw&-tx`eim)xsuC2^26$pm$O{5UnaxKggmo)D*1C7|FO9mIzLqF&z`FZ2xyq8jI921 zb2ST8rD!gdd;R}J-LW~Kycls;LTx^`X5<%*U8}6(+$|#zi>!Xnd0FXxXt1CLpEIdy z-3kZamN;*mX^&6#bm!cpesSzGZaC)(FZPm~Ga@)AUL8R0)A#q7t(vO`X`T*<<($#( zo_gK45YB#@6zSe_f6hg%uS;_db>Mv5vOK>&v18fwhWM-6{3RG#1X=uq+hjLCHd49{zoKNO^x)HhLO|t*WOq`Vr5%=79B|rK;q8 zD)@JC^J#N6y9dQ$-wi9(q1)a!B6P2;vvvkKrp?Z)FT9M#it?e2(?gD;Ue_n%ANbdS0q-=cW*QE^BeS`{saR={bsO`(_k zfjE4$LQ5-iD4Ls1PF}8yDJivJWUU#b`x+MvykHCSbovmzCJpdyls#Y<2clo95$>N^ z8}^LWAyXTB;1Nd$2t2n-lls5|ou)Xz`0|r9mpiIZ^V9))d`Ojl-(HXxK6C(|kZp3$ z%_@|s%X5i-Z2I7XW|B{PX}L!*-fZeeygJU1RyPko z*Q-lN)9OU(c&!V1MxG=in%$LJc5jR(W*^D;qQxMprVU>IK;IkcV+UiUM zRk%{`BB|4?HlB&B1^utiAP>`B5H8t+uTKpk2R8bl&p(Pqn{uTkYTrNW4;<~GNB3$h zmYt-+0SfC;wrMeem(MDmq#Eiqm2*hT$trjC0?yk)CaFwR3Ll|7C69MgzLUo}lrtJB zGIv8J$$RtoHswvN6rIyrPL>^-E4DI=C&}&dd?=osBv0?7_+v-es-MEuDevg7unA?> z_w+0N&amjTnbvGf*vajUA$vB(o*#wiJThd@tk`oU*XR!QyE50&kUbk=&q$)` zWf_N;-_f|3Jb!*i<6?UF^E(Tw3cZbW&c%v3i;R0gVLWE$J}P? z9RAe)gxUB{_b1z4IoYs2>(A`}Z!a5V^Plejk6*K+_v?jqN6)Q)>Dv9jRd?Mc4KiT$ z_jc>;ghDRNLtz{E_qG8xhGaRluh@XCbAu&0AqH%0%f_r@LSqfsxSEYwONYkM^HAwS z#%~TcVB>H$W*ysar~w3OWr z&Sz#LGbv4gQkd1fQ<<|VRQo1&wlM*A5UOq>~GV}N+&W|cFg9d zPKith)3va-cOuixY|yw8x0?C$^?NifR?f%&G%hC3$Nw}griYLJX!Bdpm8O#+%Ow7u0)ozK_=!aSpURw$!yTL5?DF2LF1ah~AzKmS;Zxr*X0T^YK58i`5Gs|FinqYIdKm-z%)UziQplTBdE3{a5)Z z${@zqmhZOkdUmZ$ecWzCGk%n0l;Jn44Inw%1JEl+B#^2mJad9VY{(s$+Dp_nU{IHIiWIcQ!UjaDdYe$?jINyv9) zEzqZ|6w-8{vPS5Q>pe|&-r6DGtAo^5d25P(do(~Y96Oxr9P@Us^m$iz&RyM#!}S}= z+N8wU_V9F$vSumWwiWEnP}VXnFWV2?%PDJ|_ACtqix6e)(@~l~vF-}{$zQ*pEUcsd znmXd=uM`~5@4H#Qkw1^eIDa0GG5z85cntFA@fhdN<1x;k$77s7kH?tZ`*v*l8-1qE ze*SZ7J1^9m%I~|GRW_%XH&@8tM`pgVa{9yOKRL6xNfsL`q-88OoT)6IcV*>N2cLIk z%;qY3>(0%Oi_g2}m$Ugy#!R06!+!s5?@d4L(1_ZM=Q&%o+LHWoHn*HF&*qjnQ$2i+m)T`D1-tC;T!zUCe)2hFCeL)QI2C2X zIIm6S$IIk7=h;Li!St})F=jCd`DAm;yqx}t%`J0gHd&6Cypl7ezSz0O%JS>4kd?d? z=Hb6R4~6%_betPc&-=gJoWPTZ3p6)NEu8Q`6$kAIL42g{EZ_q>cs&`q9Q= zFucJfNzdt$e)m#?A-H%s$kZ)o(6Cu2h~88m>aMSE@Vbi|95U+w6)Sfzs8_K9=mq(M zPN2WR=?~YXre#CnQ|VBHn$1$AGqJJIF*ep9BI}xZOI#d$jf*pATQOb}U=#t7B_j+X zO-2ygPQ&1H=V1o5W*;VFc6J2=O;>{oen!~&x(7tu@-UcozYcazFoU9#%?uWFYlHn; zJ(Fg2c&6|AyC0UEHD9{EXuke7x?iKmiqg`|?9%#g;$zU)T1PW>$M^A1Zp2}+qwUC* z9qkhCABe=R`*)IU^3H@Wz9aF#Y+XDxLpSmLXZl_2mo_;4sZHVn_a+$GuLUOeZjl&y z(i|u0_r+$qeG|iaeJ17X197}T1G&IZ%BmxW4|hJa(mAqHt1&q{lrhrzsOVFp_a<0MvpNvb#lYE#W@ zSRIKqpf)wk#?3jQ2Gk~DHby=1H=s5NvvIOP2LoyonT;gp`Ucb{G8_Io%NkId$ZUMy zaaNz&L}nwiYMef`iOdFVGkVk}G8;6m3DhPs8#Jy2Y7?0a8dn0fiOdF#E0NknW`o9+ zNNpmsLE}oKHj&w&aV1ilgxR2RB~qJ&*`RSHvRpD7G_FLJOJ;+{mB@0*Y|yw8SuU9k z8doCAC9^@}N@TfYHfUUlESJm%jVpoWlG&hfC9qtI^(FF*sA%jS9i7<1&Q2<0FdC;7 zAD!rRAyfMLq#wFG@0ZwVY_7C9qcx^1Z=L9nQw_eIaKIsF91<7aP{Aq>BTNRP#1Ut^ z!huysNz2Vg6H4413RM$BN#!}A2?62Z@K@|N3Vr^sxljDdU9*0+?TP1dVL$xW?T5ua zQ|wE{K342|#Xec=tHnNC?AvL(;@9pjF5Q-i*L3k(FOC7kv4J>d5XTbY7(*O;h+`6Q ztRjwK#IcPy<`Kt2;uuLBJBec|ajYed!NjqdIA#;aa^e_I9Q%o5LUF7pjv>YKuJ9i4 zzx^JN)$m_8M*999e~*v7>-Gc2$w5`Q%=Q^xIL76L#NPXx($){Z#xCUC!7m8CTb1Ly zw@VCq@3<#38R=>qKDzEj7$3hKiPGe3&ihhF;=n4p$jX=;4d-DoO;ER53(l>| zSzyU4eK_l!_)Jch4dnc~!dkN4HJY>Yaz{enrQ_UVYY{u4ToU9ZL60Qp2f;1~{(#^o z2>yc*7YOl!kOvU*147=!+=}@uATR0>^^0~ze?&h;|HZh(c*Q)3`4RJ$pHDB#_trvr zf&2@4h@ihfJqrF5sCU8t0_{YIw?MlR@+syGeMa|Hv-UG|MjQ^UrSLk+b%pXGpp?&| z<+HmhJchDVqZdE6-K;nWI_t|hm9n2uzUQe@9!|^4=_~Snltq6;7XANGxfr`PGGY#Y zR$ipJ^7-w@ZpeFEZS;%sf?e@EMWOtU^PTAz%0+n)%C(Xg`~)rh zDbQC4`4R0F@JG}y$_w=ZLjHfKUz8Wx!%xfq$Olp9k8FuD7dtzs7QKxFFUMgj>E=bv z2)$?syI4l565N;UUOWm0^iGgI)X5~bs`Y_M=XXh=Sr^II;>}^`oVU`J--=+-n%0n= zYz#4VO;ER8QJD125;n}JiRscdDLlO%Txn>BElV|#(w{YiOY|N5sTnCMLf^q}H&)h! zUyFtZ-*lt}<(d=KvmiLoa+LIT6wX>|DRNb05)nSJu)vE{Lr>w9~^=XpvZdcH2Z;SW4 z^pHX;G=wXr_83voMtZ)r5rlTAjkRv&s+;cefWt)`(8PALdcKzmvZEZZPs(8Rg!!rh zK8yaZI^9WT?aZl86ZuDM^u__7q-?aAM^vB7@Suq5mH-^Mm?t zLyvRUhPClol+i}#zaqo@{>l3K*?50e|4+4tpFKzZiFkj?A69q&sLhBnKVNr$z55+; zTqlm@#4+A2VH_xq4_SVcI@T`krnj9*^Rmh_a&7o{(-APc)h@o~K;-%3{ovT-=e&GZ zPk%7#eS`Cv7em15j94zpi{oK&3@na~FAL*maa?_h`j*ma7h#bzPR-*yyS#ia z^-ZVu4bJDNZ?#^YrubKS(k8-QLawh+^mm;5+ANm|XM@Jj}*}7QQ%Sm&7im9e; zdK~_U>2(;`eZEr*U9PsY!Rf%;A}9#%nj^xc5a?J!2@jkQwZ~xW>Iu=itw~Z(XDVia0!flQ`bIvJg@u)D^HIl~idaSgk zLo|$TnJ$;B=pZe%jRV!=X|lz^C2Aoj1$6!&C`Td2za;0ke|8T3EFTNDWalnyI#>a< z;k-3YaABycwaDMTcLkrydO!}iAV1RI<*OUqUZxA? z;V%h!+X7~7)d%(FjbudW&hWdHKGb{PlkD8s1GZl)2FJXvYVz%}c(q}{E{H7nCJ8=E zLM-`fx?n<6^US~5dbwh|Rd?>Q`x7Inem`&Sb6o0V>05eZ?lTEKCh1hE&wYM8@v9`- z{Yl1a-yPw%VtFAIkAl*7_zl3d*w@JO$qY1G)1th*cmt^vKJ zQ)Ms8jNK=7kTy6h)G%I~>@M9L@Kqyi4}i%%&Ppx%p5o;l@0m!mUs@AZeoeDWa_{KH z_0(^3Qk@djoR=?no+0(`K82SLi0h&roZOw4&+-nF7FccJk}+Rgq>V z9wl1>z2N%ElagxMV_shNK}YqNikEnKv87X`;lvP`%&Bh`q(sX~bgU5%N6tE}V(l|O zpN#YK$v8isjPvX3?^)4ftF@l|x?p-(T})m`=w4qsI;<`(Es;3?j7;~gYiyaG1Lc>? zlNU-VMGwhYYFbOhd@FA*r`Aicw`0uO&$@QuW%J`LJAAcme!M$dt+maMw~fhK+x&Qk zclTZ?o(uoK^D(atOTxJT!npv#xd6hs07AQxg!U#0?NAchC$KiwzDp8o0}|uBcEUNY zElI46<+TA`p4awxd0w00<#}yY&DzG9gU#%%HdO_7Y+ifgGI?#A%jC5mE|b?*xlG=< zpkjLR+8dY2Yv+>CKDiHh=LOdpo~r}ddYdINC)#j+JGoBg*)SgWsh`1#B8$(WwkJfBR4p6>uN2K5fQ|{5*VWwzEOL|CSAE5y5{V_)i4?3-r&TZ$ILEyAj5wS$_sU8$Nvn zJ#XjoHF^vrhA*3%ECw=$W}@4_6!@)}fr6_pR9@^eTse`a*GQYcJ z^XVJI3&=ZmQS>-cJ-LTYahbVWhu};{1Fok^&mOog)RMFBdrz$4qR8uz5E$J};mbQh zfX=OP89L7f>0yfe+;^TZv#z2isz(o~dQ{P0W9twI$@AI%nFE|gCEg8{Lg6!B;XY*5 z34jd0a$IMJ4;|s$R9nto3mU^=KP3+VS3{uZR3$%4K81johyM%A+A$lS&~}9X1iR-Q z3-s8ZVm2O5r}u_0`y^*gr1xv}>HXUDeziy{yT2i~V6?``Pl9`!7km=N%yE^bGm#6%%Cs%w~FOP5D#KYwKn~v`UTiZ_$5#o%T>*kO!WG5ZXf$bTKc#(=Q7o+{m~Cc(fSn2MR`$=sQ-AqP_DSw* zFIz>!own(+(QyZ9C_T13J@zF%wtelc(3PGS%k4@+t#3o10X;9Ohndd&<*aeCfQj;U>!T7pG`?diY+g2M;Q{;?(=Pm%?2`z8yiR5sAVyn&eTr%gDEv~s_tOX{JTizA3d`|PZwx5Yn$%XbgDU>hFRbd+_Yyby7rJpam zEmvwcqcXoP4Dvy#**xXCu+n^-H0N?XeqA_fq{qL(#jYteZmr7BzrNhre}20*yih+5 zx5sYQ9GO|sT^p{pm+WNn$@+1i73;+TlOLLV&7+zYO#R4W^2`@)*pd3d5TS#UZUFaNUWIE ziL+-^Bt~55!ue5$NbLT$JLl)MB5|_kIKsx{_5op7zsUs+tA=k=6mXM?(gn~yAo&V>sXOG?wnAhH!owGDRx;ZZPNK70*d-1G;hU z>17DVmNenq&EE#BirR8sSEUK;t7FJHHKZFXiMz=CZ(CmvJpS?t%;mz|@_^u^%eqqlU$4gLeQz_0Z?7Kjx z&zHIXJ$ePe_9E$=w`T`K!Z9<>Pd-IMv37cV4f*eH;=tv_X`T}@KNe~)y3KPEOZN*Z zdrPU8)fETh@#_lLGaU?#XDTvF=y$vRuZ>j-<1HMY7q)@IHc;3G3fn+o8z^i8E$JAw z`P)>PjZuF~Xh6K}-7xX@I&j)QgFnMFP#&oQ^jq3bP$GQ%5tUHCW10Cy*pkv)(l!NG4x3XWl zhRNG(b_VDDrPYj2h1BQo*Mz-Kl@~c|-?8#eSDa^Igt3FZxc&a-CfV|S5KcWi-t9{6 z75cry0Bm0|OLgYXHPR)+ADx$JRA!dfiO&Lm4BbCgwSUbGQWyNO#NG(i#vU+#;)Y4Z;VyX1X^L0F+$Ll1Eb z|JM3B33}#;x5||T&pt6Yy>qHOs*kZ0H8TXy?V2y2Xf#FY`F1d7q|TKMjL%7n0=r>z zdAhvZ*%02ZZi4!i7syk(+rV(J#qs(ij6pUw$@ zxbYiFd(UjSwrUhK-`*9=)-l3EM|9MS-*&+#?Tk=QH(kB_kPq%UXoQ2v1$Ef1P8i;> zB+flrLHhi%J$8#Pg>z*|+WWaJ+7>B|!E*zoqog&Sx>O3Ab($pAO>2(*CYHuCy%tEl zMmNTh8_J+llT8xnd*JSzviPygKFRWu3m!UXj5h8UrJ_9?v0_;hw2pizMY>v})z0#` zx6@~7hi`Q}VNel|f7F9=rsc7DmMLC|Dg*U48sYmhl`(!&1vu3}AHS`tf@K#~hTRL^ zl0`ME;r($np>*rp#B|sd;-qN}$BO5YU2Bk7FKz?kJ!7fjH^}8$7v$is{@C%E3C6sh zE?2+Z0n3zk!8#XEZhyrUBV5|x*AZ#*wxwq1dX(-(a}?!(&L4>Gn~`X_ELpBUA&VSb z6oLIi*UMwe`VprdvDhz2miLTQ?hUumXI0jgrtTTFPLri~u8`Ea-k6Z^ima;L440q0 zO?>D5PP*+3zzH$&ZuvZe}%X-3Ba^(VLQ)fTp{Zr0O#-fkZnh84WPD$P+RVOyP?qlLp)~l z-R+5EE{WgrJ9+xd6K{Vv#gw#)=sB|_`ec{FOsmRxutRzDKVgnZo66&xj>RyrjXl2d zHo@xi-jKQb>S1YmZ`b$4O)}=WJ2qZa7Qc{_B(t-GlY-0O`MW#G*)h%V``pqPRcZwZ zKGF);JD0*yzEjDNoox}?mBe>NqDV#BuGW1sLe1&+Wb(95cw@E^j`OZXoLBhZmZJ1L zJ@Hv{d{-Bo`Q8v`p4p-46xS6EE*j!yyBN(_<8F9mr6HC`ekMOZ{*H|4-vQ_6E+-2T zieUVBGxXe36^$nr!TO%wXtiVk>4P`PG0$9b?@?2XtX&*+vR{zeOI&dJ>Ng~NR|`Bm zU;RkFNOL;PIzHHog^i9R|vNbwuR z@yi;(Qp*mJG&(QA`aL^3FR^oTEn+gO1#YfY6&pTww_$ynUxzxjUUa^K^;c}ZVkDif zVEvdIov&Ctt-a)%n<}g59EkS|W2s0FH>~%vF5WDa!TZCufqQK3ED51|-o@kbG39JE z=I7YARnW_-m~C!MQ8lx*y_-2&ZcNZHhBY-Yzg;EJdatu>I+}CF|a$HDtArx#okpFA2g-`1vuZ2n5d{WCQsr8AnoE;U#6s}ORGBo{qt5s3 z;f19h`Fx+UsQ;U<7X(rL^)ywXMow=qqWZt%cj?=;k&sID!|N>RO^qn1MfLBj)IwT( zJQgNU{V}O~_?iTkXKkP9U)?i7`q*G{=0~$I(1yh}pbcB;jOXpd#XAhNVQqAZGE^sT z=Ttvx!{V{p@N&%ruD@%!Fw}-Gs2uotJ-VA3v|(+05M@f*)aUI`=ad_2!&^%!bF+>o z4N)7Wwzz(6+mDMwH!gpBks)Zq&EhJ$v-ZjCgdb}x?TJa1&-9N1n;Xj|-Kwc_MVrxJ z-bfepj8o+mcD|6^+X-~1)A22Rcj3&|PTba^PR0dzN6_DNj(F2p+D~=9=^F+6o+&!h ztww{op)MFwo%QT};YJT9s7!UX8s88)H>iiqAKcIYqPv@-+4@v@z;JKKZh4O!981Tm zmj}X|F~MX2NtI1g!=Y%Ia)0K-fHpkqOlR)T_l;#h8y4H7HXQ5I zf%_wGE05Z6#lZGhp5E7Vd`-W-PPqc*<*zE>;gTj(-s)3z86p~uGT@Wt-soX~|H+wM?9^pccyq%H3^#(27y{XY9tx#70%xOVOZ$&B{H zqx=Tr`#L?OUO}ny3yVms*{=K_ei{Y-jYU0<^@_uJs%Pqs?s#g!1*r0>f>DM&$GupV6u5O=|%l%v2-LQ zWFM$uT?Z=EPL+Mfs-Rcv)=;@is$8X7b@DT@)YgMGS^(3roWb>cgre zA8?~SRHQz%pgwrCY7M5;hso8eL-*eO;VShZe%ouQ^5a05PJQ^+c!hKAS;m zpVVQxq3D^CBKP)Akz8E-F}P8(eEsANsc%9TYzIklU7J!c&D9AHoSY=DTG0@aw&-HL zl9Ob;TRkDJ@fy-vnj|lE4}@fuEwLR++jCSjB#l3kqiL2bThV(FPg^6&zj~@%K0W3S zA4(qb&pB>H_n)Oc4AA?e)-4%|y^~X9QaMF3Zt9QY8Yasp({D%<)4Sj*DM{X0x)iuI zal)#1D5ACQA z^M)BouGEKp(_{ENUS50C>i)5(Z7M%^uG|g5{yUG6*Ez|u%iN*p`^*r#Y9`6XpSz;- zTYEfTd!n2jFX6z_t?>EkM7hV>8aULoAEua3l)t`zM_ODNg0{e?6mFu{91~C(}8f_imbPdG%Gfk(Wn4SD`HWlY8wL36YcKQPYNE zjUq;%pTnJf5 z-nELvd(@v%!Cgt*tXQlRpCV_@IID4@{!~m!mD?_G*L*pb%=56aLMUp(`F)GF=QY*I z+cwn?+VF+MO8j~{Gr1jV!}FdVDc{{8IYNqTxnU%%o?Qgumra(9a(aQ= zA`2j4ljOduo5T7;jp1N-%KdHOSwc_fRC=;Jx}_dO-5L&G+9k=V+}%?8*a)a-m?FE6 z94MWpYYt}jqyEq}2>E`7uCMsV`g7fl6|+PiP8wxP;natzD@KCT+9L3X`Y>ZdFBrDc z0`5{Dj%755$p;$40qVn<0k-ftrY9s*AF6iMgBF*D!&GnDSD5dSX2(RpR_a5*{((~P zyjZwOeMszaMlJSB+A#I`r^aJcCvTs$-$QNq)frQ+ziT;f(1u?=QvAtkxj-)QDhg-L zOO;2+F4Dd9Abe(TQvl`)l8D_d_F}!-3!BsPm<-? z?_){W+ZfzU+w;by-!=I@4`{W3zEh#($B(k;!{+!b;+vTw=g>LtG3JlR;4w+^z*_@w z;)Kfhf%?$uR9oDT)(9i053ivveqYoDcTgX)bxPsRMMLlg_2HrIY2tn}46UEiYf8sB zqIna823=F-EyZ<+Hf>3i`Pp{0wvjT<_oL%{ZTM&P_Z~Zz*Vo1PFw}nZGucukLT(``Fzv1hTY4YJ3TS(|FB?B~8BGteIq=6$^vz1X$8jApEEm~ zf&N7mETsN4JL~{HeLI3P^=GTf1P)*HgGSV!OXkm{i6(U1M*VrAw^r)r83p60Kc(w5 zlO|DrlBhq=mL66cj7uQxKAezUpN7KOPff`v`W$wYMI9)4*swNxc949$)S3^KpOe~8 z?C|~j3Xngy&z?!;&;O62&j|A8|0~jG2NO4(B=hZkamtIOQs(Nnf=7T{)b@?P!X3+L`^KlRbmT*Z<$f;xpHB?_SY1tgJU-|1IRgwKs)rps)=Twt>PnP}m0kDsA9r$Myjm&+~gO_3Xi* z4Y!}7tRZn9=8D=d9Y_4s-lr=sjF)bEPRcw@_g~b8**N8A_Rgg`3Ds{+^`kcYXVm-H zsbkpsB^aQqS*CmUk>)DhlTly#uJK9mCo}p4!rG}(q=dYZoQdcQJuG*S#XWu}!>wCF z`FhXDmCHqNiK!i=ZYzbRZB6j8y*>;jHSv2~O>DH6NY}0FqE`hwEaTrz+BLob>YlER z@A^Gf_l)V-O4QE3LCvuV#CEeDNp*;VMfZ)#e4hl(;3Ki{VAeE^u zKIGp7FY2}6-1)mXe%jTCbJE7oWMS?o&Zmp4C61M%Iq#d|$o2>0d^_RvN}*g5@sVAlbd6jm35ocMm*u)U}!c5XFEV&&ydcEZMkzp5Ee z8R3i4#{+DSOc=kQH=f9<%jSb%ymt@G-MX0b-NoK$dg(6b{dd){Ev z2X=n`Oky&hO#9>3NR87DrkWCbKa)0`K4OBupkcJP4C(stA**xneM?Q+9Bfu+}56cj>KMCTC0l zb|}4;%LF&*jg9?_A=9(TxF=q4)E>Lfm8&`GG;PdfKDDfdc3JLR=CfBtv|ZDi%PbB3L{58l=Q26H za>@0T-dx6G%p+3i&~IGEtM(dl{N)fXbNzcJxs=qG%lOP#MD|^yYrLq>C9~>~9=n6N z%&sUq((l#~F7xhI;PW0-@ePsCN+R9fbA+Li+)s{eaL8L1>2{ zv_lZuGYIV&g!T-=c>%(C0m69!!ubWl`31uH1;Tj>!g&h9c`Ejw;<^7n_S$9bhweLF zU|b>Y<*Q9!EsjHkV^KKvhkcH4tay$1SB@>v?}`1P*iVZ6r`WHG{jJy!i~Y0MZ;So8 z*w2gozj$4sdnWU1$A~f)GKKO2*B3z#5%d?hP6_@LxULEQ7q|`z@fNsl3i&B;ofYd* zWZ|0f%U+Auei?2pl-N47 z(~rX8Na?YhOHK)c&3XH)Xz2bbck}jFsZIA+@z2|*awoS%Dzg8gd6w*zZKU}sl_bLl?7U#14b{YUod$h|X3S&I;O=wYv(UUC|VOAUdR zTkX^?b<@bv4fSEq(fC8zEML;M7Lb^is^iRk~!`^J)0fE&KQRTma+ zJj~xg>-OnY=K7Cg**^Q&;==G%HtFT~`)-MeWo^HXYscSN(@*PTliea9#^CwYSsH8Wd+H{$BXNEY zjcWIY_LB4>4tuX%k@=gHt%{raaYU|rg zD%Cv_%fFIU&3F4q@!^s9)k>q%>Dft|Np&vju2GGA-CpWQ_g5NYr%|=H>Lk6b6p6)B zWL4uHJ)~-lA~ATktV(~~Rl46Z5*NOeRr8X3r1ScwS#yf_vuFOED{q?RU8lwx#!2br$$A~5LLJ5ak#3Kq&m9RT@~@Zpo}R0BWB-? zYV1D$k8hLxBc^jCYF1CGQ!BS>!*2URpwYcdk3C*#(hvD$NswvZ6*Aoo+3_eFnPPvK4^1n;j< zxXQW^t!#k}81eXcIjeZ!{Z_1jzNzF}MP_I|%a_kM>`O26HBN*MN< zt@P(lABE$MyglJB(LLc`=j{orceKMU-cI+OMYaqp19C%Sdb$A*~IyE3?KStuZ!9=wotQE(1S&1rvCcDj4!ib~mXmF6*6ZsAhR(_tSqtlfnqPT6`msiJ#~Zw$_V znx&bZbC;L@OrM#&B{09A0Uhkh`(kW#-TKg7fMZT+e_me&8@+A?Fjrf}ogpInK-a#z3>( z_xSf=8r+YAv-iCS)06%*5~8MNb2gqm5+>Ks<>Lb9=DzSG-G=kK@l8Nu)q?ZfN){mB z>BITV#m|y^l|arbtFD#CgYrGSqH7(gO=V1RxyO2Ip_~ZvM9@P7{V3Q)!5cEl6jojC7*Z;UOh2XPMbyh|>*1aYRD zT@b&zO8y;cIFWnz;&}P>`VZtp&sfg=e}ASf;uFTXg2i}gXv1Ng#~U4yLR|U0rB3*D zJ*c?Ulb6qVVoBd&vFAK4S%S9POL4yD+y&kgy~1Nj9~1y{_0u^A>(nWr<`a~>SRKWiFSvFB`) z8Aby4RptCfcN=N6#*p*D?GFk4<$DU#GNgawOl6TC!2;t#i-A1{;7&jZuLnc8GAaHcj{Z1itDF6IwsCd+KF za;AgXV4R;z#`^0HE@S_)-~ZOS(_h!J)}LK>Ic+okSL%-SuWZbs{9DL{c_?fH|K2w6 zx4EKTRh99^xl{GX=Co0KY~WdKL;iD5W)@@2l(9rkiWRb7R+v}Dnaz2#V^}%U!E`ZZ zx}EE#EMv^ZlC)f6#LB5W=RBMITxWWye$Grk{pHMT=G_;t!;v1t%b888i?d===`*Y| zPiG3{k|3Y|olvF+1pOe`W%{^IW>fGJ1pi@ysvVu{V?Xh%JU?D0&pFQ~G6|+f$Q!fE z%b86UGn1h|ke3S`W|QTJ6)HBB`l7ky`vtOc+k9@KVBxEA20Kl`^@wR@fK)5LcFXVxjfS$#7p)4EncCV)nmRqt4Gev zcQK!WT@d^!P%mPA9Za~FN#*DduSbay%cYP9ricCJ*CS_^OCg`E9(g&F74pyOk(aZ2 zbj#L(?+xj`iuiXE2lZ^f!jE;)cU%zR{VDF6Oi{G)Gzi{k#EDZ~$3m-1<^3>jg zG4w=np0~^Ox?_@!6=z+wXMr3Z%gb#v&8=ZvB`$MzL_1v3wKnI8-__Xjpb6(Xzjwf- zsuej;snZ_4d`&r9H}}RmhZLDvmpWkWH|MzzF9HT*=}X@^x0u=+N4!)OR&>G|V1_oxzvbB3CH=WemEiqW2+c&K0P-E_be$Xv3aHKLt|jl&QhFT^oxPs^nFEEe$tA*L*FTa^L&eN z7~Xjn=RW@Q`O+wbPxKEiaITedvjTSPEhkTS{;W9XXVtoc{e%nr*p@8@7mz=7Vm>cF zF);{2D?R5tBg7Bt*z&cJ>JqEG==u5c&q{t~o>0_pTjP|(`kWU|C1LW#N1WfRECOO* znRWgBROE!z+V0+g!5(x?c&G ziKgGYTX=OBXYVHtFyc3*oIG@ZSV`eIR3^2Q!oiOnz)-g<*YnZI8cs)MaQ-r>3e2l{ zo^y}3h6Q3j@+F5{EHV<0EPSjgd+jOd_0kW&wp6K#V;b*6stoOtm77_Id>I>s@0To8 zk6DpH^lt>>jc-fU=Cx0ewv&fopjR7pQrJi?AFfv~Yn_EZd2u=%i(XApzleIG8G0)Q zx78i0PUvOCua)YBG1$4~6+V~JJTVqunr!6Poz;G$&@{9R@4wUZebC-t;@qibZJcc4 z$GNxLOH$e|ob!<9VeDGTxg>pFRJWX>|H$GPbiLc3>rB`bfjZxmImyejI%0zfmAHKF z+;+ICoIA8?hN9gH9V2MlF@>=Z%J97h^RG zy%$T{Dh0tY+liW9zt5LUzKsG?>*kuZZ&ypl8U{j-VeK@I(W@k%ut3=2-Bok>#R}ZN)3e!f(-a|`H}Q68_T;-%!?ogmGu2wu9BD22W2PR^M} zqQm`_vZd2;>8|e(tkhmsYr43R&DW!_@v9VBUb$UzbQy^@BUh`_>a@?;(2)6a%&SuN@>xsN&7aae zimpnUiM>loJ`T~?bJclGts%HNQKt9o0qhr)~SU(0QcB6URnh=&|39&B{Jn zHcZNV;fJG~kC4w0DcxN=3=hAUN6yAIkusfVyS-I|7`0Ny-qX8V;g2{dWE5}n1HEf! z{VTjSTp8ERoVP*x5tmzIMrgl*&zxm9O7d^ENZXPw5jcyO&3=ig0iaP7`EoPEAq5~8Uk6wA&E{OHWF0h78?0sLiDq-qx>TLc>Tf&_<0V=I6M^wc+@lXzu6LI{m@Ei-yZs7TGDeht%aVOZw8jdYeC&8Mwj^rqo!& zW#(7OkvwKr=Q0rk>p=4f9k@*2Zv&ufpP5|dSTk8NA8yEHZihL->!NO4X6)cWp!+G7 z%OrSeq$yrcdESlAnr7Z&bQb+a%|Xk=Uc$ zG1YLxF4B%26>)l&wYu?YZ|J$Gq_p!(Y4rg*PH45Il(hLyX?4T?F>qVwt@^;+vT7Hd zSlB=QgnEHzIrWRgSQwVOLS5sQiMs!XSm^3{j|{qJr!KW-An)7q`$1*Q{qG%nFP_{D zq^y#`z*&L`|)^CB}yq}Rj-jXa_8nxuS+AIn?8rgF; z9UWajX5`IsIDS<}@a$YhHTB?CGW&x+RCsX6!*+5UseeBVN)+wtQFmFA97*>&)Vtih z;S$?$bhu=yZnrR8ve2oFf!96NC2zHblx8KR@?5c`JmiHm3z?1oHdk3TgR)y z=hcuWQjT^Ws7l}1P7b3yyP;auyv=AiobpX;BNY@$kjGMfXf)Sj{qSH-r`7&Y?EMv~ z%$*ogzVtI`+V4GJ`u}6^EugGAns(vA1}C^XjNnd?IlFLocXtLG7<6V1P6+NA++9Mj zIlFNQ7Bo1)o!}Deudd#`-+C`O`3`H{;r{v7nYEI6=&9XR-CbSnRWml2x#N5fJvO9+ zo{2}BePd2C67J~=jf<8wA2>R|vf#r;(@j0h<|#YCvBNGS^PeZpo35hZYLEo(78+_k zi`4-Zu`OnRI6Q{2oyH+#13$ z-}QuKxt|ao`BNJ>a{fHwhj%-|;Dmb#zu6f4Uo=O}ipIX|2A@uGBB1q&Pn5ntdIWHqHY|NTqfhYZ;r36Tov^;qm;y!5cir(0 zaicQv3r-Rf%=mc6BE_B@MU!+XZ8mO)KA=0_Dw4a%Ue~;{5m0AThav|C#1?VBZw#qF z&M!JG@eZ@LvpW>u*|cck@eZ@ultJ+0#cM@I^>&Ijk1M;@m&@!0?}f9eNna5 zo*+-KnXHv-NQw61d9fR2(tD?~Vf%@snd|ta-gAoZhU|6xQq4U{xN?poO-sz@LG;9g8MRb46Pe2G7?e zBmI))m35(hd$G43ygK030j~~tb-=3wULEl2fL8~+I^fj-uMT*1z^emZ9q{UaR|mX0 z;MD=I4*VN+;AF9O(COt}+V|zSV@Mw;lWZoXcXx$D(7xCTpL4>vt4Un4ta;WAgoCSU zni8k$(jD@K?;u>hZBv-?I0o$>AI??=&R+E={Jc#z*qFS$-dFyw`>FcQWmNOMKDGf= zSP>tj%p6-XQ+ns;Eg^B@w^UwUCmg$@$87)WKC!;L$$33V8U$rC6@Xt^;lx5zfzASmijC8SYoNaQjaBe zCtFnWm9|j!b14JI(jG{=Ak)#df$aYh^E%St8ql=Z-#(Z2x9Hhr+UMC#8qsOxR*SjYDHiq-XGMcPzO;)#p z)vaK4D_GqMJ-5NS6|8QBuG??POP2TP-KM%7J;K=T=p)I;XT{Vok@UDf=|hYzA!6&4 zC4^`0Z!I1)c}BQ!nyTX0-{qY(AD?@l^NN<|OAx+TJdr4HsUG15HBOr?^QybWPlgRQ zA5`c^=|x?KT;29X5Ki`dgkybgrRVELb~1cwDcw%-=U$`5Fs0jl^2LT)?Uiod{524! z^e;u<#<*1;W_8R;80~}nO<0!we@j_-xjex*2AOP}wK0x;CL8-qHugE#*k`b@&tPMp zJuc(e2W;#EJ@&biEvotA+(58-l#Tg#js4Qpa}0O&z@c0D^|oJ8xsGoKBB;asf7E?YA;sxzCn0f%37jKh7{D7(I0@2J^^I?W17If z5k^`Qzaflyn3xw~%-cjBgpsEMc@sui43vp5%4ndhgfUxty~E4+Z!ZfkmnRtekdX6i zq?PM;8>3zewx$+rO>MF@waM1hCRx5%>^!SOKOAGle{@9rFLVGOOUXWmWL4xfC3APs`*j|v7jq*o(EZAO< z(0f7Ok{2)I*J2#Q1&-xZ7986Jj`4(X%ojNJ6UMoKz&U{_D--7k0_O^Zaqb{+4nejB z=M)0x7IZfk=Nba%9Mrxz2N5_IA&heqfpZj)+2EW-;M|2U&SeD7X$a#S$Hch~VVwJz zI0qt(b0QPxMuc(xh;yaEgfT0-egExc!8xN{E>AGd*@c{c%lhOP=g~s08Du)nqlH|n zNR0DnA=fGr<2+i(wTi?zj}~&RA~7GYaUN~TwTeu~d9*3lDiX{0^Sb^yj%vPE8A;zb z#&wB3j$1fL%E{}5V|VoO8##YfzyE_dFRP5E{Hs;Bgsr-zZ>_o|Y}GAct8NKfbxYW) zTf*Ox7wQ=Ka+GE91Y=wK>H4wyBgt&_Q^HpNC2aL;!d8DLY}o;ouIvNVp=CD+TlR$7 z+OjjG=a&63q|BCGB5c_!km;5kBW&3O!uTg?D+vE@Dhn@{C)gUBsGd2t#zacTHHsV) z6+Y*bVk*jgWvZd>an1IyuKtw9J|Z3{9Tf9&@Cx0i*N%M)y^g{f{iw$|X3F7;aK zx2!0s*HXVFmU=DqTVko#QokkU<29~Pp#I+6Am_l^ildo1m;Oqcdp+GUC5`bpX>iLJdO z!qOf~yDZbcB`;pauf^7WBgt&-LlU<3Ckb2omV~YSOv2VaCt+*9|Ibd;WxRjUxB_3F8_??)ekOHHzHxC(OrdYtNtR9M>pv&)=?pebyl5)Htg7$~Bps z$IIH`n2+PuS&62RXD(l0cl216zda}7yyW^%u2rNA)>#!{>#T~fbyh{#I;$d#bt~_R zP#s!lRl08FSry@L$xD{^YtHW^J+?KSU0U}dNM?8UAFTToRCep$1!1f@d#tzaX;8X# z_DVR}={WLCR;Sy3*{pjMIv;`kpRjf2OV~O~C2alOqW^cx&&%Qo#xY3VPoT1MEcfT+ z+Cb{Cb!ULE+@E7(pS&|b>DHYA!hBq|?hH`6b!ULEJK3U|uiWdE^L1G+j`?_v{ZHP_ zAR1mL9J`~(asg&7|I>F)2y#hsoZ^_GDc|A%0r#n=SbI%}Ohf!@q{FhC#_hIB+E#yaS;m(Hea{U|SM^&-y zp(hyoioD-Qb;2>~ue@_e>GIrQdQI(4 zwy5Tdwou+*rM|{7AD3}nZ{J7db;7YbdMuY5*FcsRe{9Toq1}~tWl08kUd{G`Qh%4{)od?F%0~Ii^J=;Fkc{McwcZQ*mb`cwzZP5b0g~UEClL0u4}Pn82;a}- zW&AhF@5x>?r@^^1;C$4D<(7N?Hpclc$hp2um-mU}8be}vpGdATB$oGyiFU|BY~#*qL27WXidoxX?j z1JCYqd$N|1dHu`fmt&St<@nDU4gdYO=|lJB4O;uTu)ND6w!iA`c-2ASqm#}%PQIr& zA0lys^u~RWpJ=M~%w~LUWZ{uHjbV@TQTp{61&o2=3RfP}%4nWCH>I}^8fA=l5J0%& zw4aQVZ?h5}dvSqrA(z4<(=9R9HpxQir5Y_a>W|1wIPLsMW8KiSgrCJdX&gV2jPUEh zw~R5J5)k&Oeb<;&Dn8)^=^hv#lgk(>MMT_dkBqao;}C9l?2|ELrVrurhhxK*E`Q2+ zC!*iD@8GYomkEzto*4dIc7gCYR}v__^Bm#Uza@p3zn&&MWqulna0KFxn5TxDV|xcaIC;Vwz?L62<32sb=X z0E!QcL-yeN z^fU70h2(k56Yjbu4^+!jjqoo2JWw*AF5y{obHk=|O$a-F420ULhZC;4IU8*GVK(8; z88X7favKQuE|vkzo|_4Gt(hJ^%=m?H!#3$)$d2uVpYBZ#Mamy19HW0isD14^;S{4{ z!P{Oh39qdZ6Iy0`L->5W7|?3pJHqo0MuP`!KM;=h?3uA{r7y^`EG~AOaHC)FnINs?P=+ zh5U06E}LYK@%gaAy^8lSI&`MEGNNkJZbrM9xrpY*D#Pf#FfZZc>Ay2hg%lvX`KZhB zeP|)VFB-3Ryj!pEiW>_YDefp-xZ`BUs8ofChGQ9%MwUO* zTo|g&Na~XGMRym1xqqx8oyj&Q58O{xo$5Tx@T@Sc&wRo@$C5(p)29iC|Mt;nn<5&> zZx~ zwIAW;zaKE~mRD_ev%wp)Z2p*(p093V(QD*IlEHB}vshPW8R38_xkZjCN^grbE+kG= z-$!LhaKEsq{^1byqgdY;5Xo03Go{Q6TLg+YuZI&}w=k_}T|AO-iw=vTzQp?sG&BMns2>I>1b|GfIDXJ~*ym{rC*H*O=FJr~QdxOS3P-R3MsWH;Hbi1QI zxU@c?p18E0p#HeD{-9o&TCY&wOs#LIho;s;)K63EC+e-K^%nKn)cTBiZfZS8{WrD# zW4|zUzrg-t>i&ZL$khD^`~ zwtHv~g|>%iCxy0?Xg`IvpJ-QwwyS7wg|@e7hlRGoXrG0)&uF)Ww%cgWg|_Et=Y_WO zX#a(_|2QrPJucvQA@q2GmZ~FjntDEi^Bhypb8!A+>iG}Oi(GnMg!3hro-g4%DpJp*eB*T9*&O@5?E8pI zYRu+Zz~)-O=32n!TEOxImZ!uzPf4$3llf@bWd2$gw1J-uHbO4wR0Mh|rx&%y@fawx2odl+nz;qIrZUfV8V7d*gj{xf-)g^KCr$I%!UB7A;4@1Fk1x776G$Gz-$^Yn+D9L0ke(3 zY$Gt+2+YO;v$4QzEHGOQ%vJ-l)xc~%Fq;p|<^vl$fQ=o%#tvX(5U?=_*cb$CECV){ z0UOJJjfud4}Z(HKXtqK?T3YAsegsuDuTYRN`!#NhoL)em&uq8j?qm%l|*nc|Rp<@k7xukqnK6ac)Sq{lh zrpxk4eiEy4tGJc2KD3;&o+Lk&PZ5Z|H0E-Nt#moBqgaxXAIpcZl|NyNFQ|OB*l{8) zIVoM%pUhX%$Tha2{cp_Xb+UaOx_#LkPwJJP^GiL^bAG8mdd@HPQ?DJQzUj4t)I+^? zkb17yAX0Dj8bs=|UW3T~qSrD~|Mgl%_6xn1k^N4uiDW<0Ya-dd^qNTaU%j@H{ZX&2 zWIxqwD`^Mx8cp_Vy+)J$U9ZukJ<)4DX&>}jPudN=){}NguNkGC(Q8I&fApGB+Bd!S zl=e!mJ*6GfYfot>^%_>%J-vpN_E4{3rM=Z_VQD}0T3Fguy%v^sTd%359oB1VX`l6) zTH1fTHkbBXug#^M*K2b*j_5VM92fK&Uyc`gjW5R|y;mT|7rj>?#~r;_AjdVm=OD)^ zz2_juFTLj=$49+)A;&wtcOl0?y>}tUS-l4$$4$KlBF9s`2O`I7y_X`#U%i(i$7Q{j zBFBBbCnLvky(c5bcfBVg=MQ>sN6rWI-j19n=)D~|57B!>a$ceLh~#`j?-9xQjNWUK z^Ao+-Ba%KZ%zh(*|McSj?RDapFPf{vHTC9><5%w|m26`9 ze2-oH&CYC}6ix9o3nIf_DC{B4PMr_Z+ZcH{G+)d!Nau;XN@`x7(44;<0n^UzqH~RI zv3tY3d&(WPZT*-R}P$}F_ZSQeqnf@KuCj97M|%Z_piT_+r4xxN{% z>O1?1_eqD)`Oc3ex`LZAEXw3Ee z|G;*ia`!FQF^*9NVD$;CK7rLIu=)g6p9ZT>gVm?O>eKFzyx&DNUtUHJ@!#q;e*3rS zyf5z@dDB&+i|W_!-oJ4j&Y*CIBEIH^U&BeSzLq|1j}WmVRQX%rcuTG}qS~cDN#~QK zswQ^-n3nRNyeGdXleakGJU0@Hu8Haro-pB}d1-J*!V7nfGoO44CA>fGD_5}`O3uf% z{2eb3E89D1PBo*;Ipz0;V@|`r<#}>mTm~*1mzkHP+4P>qkhA?sw(1MJ884#`ApG;{ zF2?zM3QyV6(a6>8OYF(F#m9xi$Vv%KIqq`&>`y1Ws<(yik9Bbkf?;t=P~BEYf__nI ztRZ}?Kr8qu=NrN)$5)0SXETs&-|x%=!M@5zQ`?>ip?vH5ls+)#X(JUVe;2>(7-1yK zp!{8M9Mybz89l*V$2`H=&Mh}iT~zNeH$1!Ih#jGHDPsK-SNqZmw>`1i{1l*Q9xaF~ z`dw;B^>eUoQ4zAZ5aCIW8jH{Md-PT8LT(w|ao?R#O9vErKYA%Oke(EXj`sNm(UFK``8KGkVFysdPv z_R8MIf~Bf|c|ybcKF7STwOY{5ST|br$2SWb87m7byWt59uOGCT4sA2hmO8X8<@1WK zr62KUBa!=&dSA@(jxMFdnu~$dj?bQF6%Bf+_ke|};Q7dlW|UrT?lyDI!R~}p9jwwiGG6PcVk|~PG4Y7!@uQua$Z~pE*qDb zmjzDUH6lv4BfdBK-Z5ItQrIWmZDadWg=d*JjfoYNuMCbo`L^EV?(k{dc2n9cq0XP%zDC>QkLYbb{{+o+JFMQ#~kqD-p^3 z``HpOH+nw8gZre1X$zFk#z$#h8uj9+H~1V!HD6vvPcYXpPw)@ja*C8bwqk6v?)>}Tm%#T91JgNkNP{5WFkrAAa&S&|kJ`*6QQwu?KyQNfGX zNu$c)aCB30(t&LGoly3}B5L=PdHcY*gR`iu#mQzcYIrn~b4BG6aCC-h>sa*@LF~iI zPgMRUzZm0-DqG5NRPf^Z&oS4r>+7Bv=>{o(q47%IH%8xXOY(a{N_9KhQfw(;|X_5 z6#*yaydzt>|AZ5|WynB%YU7K6@S$-P>Qe<4_kgtNe zYCeB@W_)-uUFi}ZH@}wt@}-!f%IPLlc8-fR*k#5q)s51J#B68IoUG>0^*;@D9Uq|V zh0zZS{frj&FjVQ0am4bzDC0AlSRRJf%;+=!D{J zH$UaW$IY*$FSFn$ z^VLM3vP?eV%VB>sIQ;RuXxY)(5*wzSbaCmb5l zlKNMIGy~zpPfbY97umZ*{VO}az){VYm(dfR(v** z0cG~8wQZwpiJ-&-wYDAhV2g30s@FyW<-bym*~t&6*Rs zRR(J7$f>p9*Wl!YQw$7-yXp2(Ti@*z1|M(bBz$SI6H-?TrnY`_JQP0pPM~_&Jf|h( zsr2p(92LCW^#!hPF?_ngyNSC=o`$Eo!T`rX!k*CZzRxl5Yb&dCfg$zP`D1Y0&XDz) z@-68J4X>-a4O>9-eIH4-Mv0ok$Mi~<__+DC^i%zoxN_uCdd2a98cQ4^w@RN|u8)y+ zuC*te;E>UGSyzyK{LfBtAYh@|U#d|#2L#7ebNG+P%R}KI%FlK_qdC0%)raV(eCQ6< zM{gzh>rWd9&3~x<1?DvTTb?K9#bx+~$;M^oWeKhk22dvt@hy-i3_8@#Pq!na>Jq2T2S^jsYTR zVenhhj3iH+o?&pbP)@?0(73Y$ysxd=HwemgElznZEHDWAgqJ7m2@S8Gk#j@gua*<( z+wg0B;8cxig!#Dnwe*Wdr88E?R(i#8%2huZEheaWX`!L_joPQxo^Z=GsUTCy8l;nd zZYT5yeFQ8X0NC7D9HRBlQOxbi}+ZBMQZg66SQOtgzZN#MKR>VTww zdOOmX^;GRgx#JrZym*~FXgS<)RqaRZSaIT?#xzj=Qj*pVfabePQ@UT<8gM%_72%dK zyTa*cN2u)YcMpQ8ON$fExz`C#L-JESa2yr9-1P;nV}T`{a5%<%(!F6JPFON{NP3PG@jkuw`Rq&{Q~cY>qY5W;-i{95`W zEq57d4W(BcSNJ0)%>7O6i*EJvhw6LOo^W=*vM_CJo|i@%HFDHKX_hk80iDYoQ8kP^W?m^3|uxYGcQZ8 z2Yuk4?=<3jDr+cIpFD-|(k7wMJi}zd4<>~|>J<~ez@B{jM~q75@+8Vma-4ZaGFLCl zu8wZ-$+0SC1oe?Y?zF6_*~DNNyjH~#I3E%Q_1@*6GPa)Jgr2@V zNv}$op|Ev;TH8*KXbGb>sI~2=rw+KVNZl`8bRa1#F>#E?A9sACf)}roU!Ob-I(bWt zttWR4Ha_mRY$-f48fI)uZJO$~A2fSchH%;n)uGXw)P&cU!~Lb6$Eoa%IuC;M(Mx}U zqk@;azQFZu;NIS_qQhL0r^xy~5b)!4!k*CZzRxl5Yo~t=h0tshC{MpdePL&b(S$vr z;dNE}#vtf@qbPlQpk5dxGIJB=o-f(QxT*AvUhQplPX$bfE;Dl{Ga?;##eYr5`UN|qwdHTB$=(u

zyiWX^)-fl_z(C`CP=9K>cn|Lx zAKocj`g`B(upzH%Yw)iIoBO6En!`gn!~Dx9sq7p_1uu7ff$Q6xz^3rDMof||+RkQB zeswg$p3u0n1H7;GUfBY6E>-8P?Q^t()Ro^***&4*_49CS7Z?$6jJ|z8sVk)Ic8D+^ zH@}uXYxh#{>p6ALljE|_8^Mvg>R#xL>s{gGivxz#y_&oFL&BH62p=!zgqh>#liu#l z?1a&`SJ2$@X#f6jU~pfO%?!phNV>y>htz2VBhdGe%;(y2fUR3|e1SO)|CZ;;d2t!I zY+Pnumb$^kA#_N7;#=o=aj5VzAK}~mO2Ebr3Mcqj0=Ax4=Q|vG@@?Jb8N}O%l_^h- z8)SNImL1fJ(%a`-ZFVo$i}2_T-5ZqCgIZ=#vlFq z5N_gk%ZQb?J>kMe3P|(0CgE693d8KaMZUmM&6k(a6U=qY6I>x80IJSbYuf=MYrvNB zYHb@gJ?j6|UrDbH9~}gvb`&E#ahDT5=P67&nSWnjNKyU=L+V@XYOP^WrWb_W@r?>z zyiSS?J8#~5uhtjS);BPR)Ks=KfALO1UEis8-}hIDQGJ85rE{m;Hin&QM{U}`HyhM# zU7qmF7**lvi*#S$sNlu*pJT3XnO#L;e5FDpPsAU^;7+mvggv2gX9sv+%P^`W%qge( zP}s2?pi)ud*&pg8KCbWghKRh73>1K6! zlU1!jwmmEeu~UCfW&f#hG6-u}`wPrz__sVy&Wp>yW#cmQveeraAG!@~Kzz$LO#m-a zDSZ250{FP5KBX60kPya}{t|ogZPyJIMeh8WDIbm-4a+6oCom}e(W7{xm2X4BeMcQL zANK1)IQ(~~Ipumk!hfWUbj5zC=BV2nj&(e5uliT|X`PH5H3tw)$dEn8f#bo1k6wxe zslRXX1&(UIyo{b;u4A6yaw{JhBD$K7O-8%@`j|yJAPFkJIDDLj9L~S(r&LwkZK4nXj zMQdSJy06;w=$=1HhJI3QU3pViqe*6!9;f&X2VS6};T_1+H%^ z`^AAjW;7ysA`-=iHBVKa@`T2n9pHU!bEQO3{-io@J$*VcluKQgczHs@>&Kj!4K_Sc z^ZDhY{UBDwvXl=WH@}vCc4R;J5N8PK7030jL_n`K>RtICJ)96JM$z1|U(W#$yI}{? z&l$emK=j;A_|vc^kf}v1l4pFIGO%fyKjECE{h-xwCFhcBF<@EOrj$OekZELE*X;|; zY52E1PtJ?Wz-8ky^RlFQyT*9_yeILk*f8RKCRoT+HOR__yII1sHs8S8$R#a=-QnNe5>>g@u`#AL=nA58w>F3UyPG~mc zDZQU{$2Tf?@jCInR7qsno{`!Js%I7{W>qBou);MnL#qyiN7ig_E_N!Lx%1RqQ;)=ca? zX6+FrE-yklWuv1*^^FhX1g+$ zQ?@jD*jh(O@-J~z^W|mq1alqp1TPNk7c}OrD%af`y^S=BRN32qx@~OQs`RQ&;cQU4 zq*~j)4X6rZ_Nle)xHFv~*#&i<_T2V?kos^9Y8Q8Wqk-o<+*ofJVPv2cEb}IUO(xxbu?DB zQ}q@R*vnXXROu2QH@}u1>l|2rw=woRVEr9fe+Smzf%SJ_{oP>w-C+IQ!TP(4^>-Vi zO|WUuR@mR74YBh?+hX%Vn`6t6HF0@cHndT;%)Bh94=!yR(Pp}|%|u)3(zX=a#iea5 z$DVwPeN(XU$i`^H1sjh98;=AVj|3Z!1RIY88;?vj9+_-BGTC@!T(9TEdF@@u(;KlWyW3+X)j-gF6wM|1?=hC*$6B@L! zcHifi_cgT1E^U+1R=c#V_JoGlPu_z|cILL`^N34o%*V~IrN=oxu=S>maoq=Oy$Ni+ z32eP-u=S?F)|&=fZ~~ z$hOS9EVv#q_1YZQ?519`<67R-Yk6E3n0k%Ru_xc++EB3l5F6tjf?)e0g6)S0wjUzc zeu!ZEA%g9P2(}+0*nWt~_CstO)qLHR*Il|heRG$N>nT&ORdEe#>NPB`ZHw!*Ev|VD zz2?QWu%Xw&xJCxOM#i->=(Y2=p}~CsyYF+%`x@>En0ikD z_W?}3SKtW^uOFOqntINOb5T>zMfn*0we+~>4D7ta#(3@k?7Rcmd56KyI}CQ-;b7+- zE_U8wvhxm;op%U!-eF@r6R~OVti=8n&rs|<@odHBg=a3d40sk}%Z6t(w#>XNxF0U` z*$|!?34LaSXGubzCE>ob&}U2>d-5%wi3oNcXJb6W66`!qu=6;<&f^3-j}z=XPO$Sh z!Or6ZJC76WJkG{Z&DULd-KD$JH+Si{pD*-T37(;t`V0lnR!n`if@dx}^_dHv#Tfc5 z2G3{=eMW<4H=xgMz9lbS4|s+p^cfbOZ3%t0g=bzupLyX~n9yfoct$4l85y3P34L~k z`*o&1Q{y-)cyayb7|(rd9m6vnq0e;itVigx9#3fSjLGi%9P_@0XHr6+N#R+Q&}UVi z(D3@fJx^2bdE#EEsrN$p82z>Mc;^AweH$C&y%&Ssw=vj#8-v}q31atcOm^SKWcO`M zcHc&@`!<5zx3Mwa$+2nhu8#dJ-r=$H#JfEi+5uLyANh#yhA0}eK5i9g9&yYOtAZ4g53ub>^_)a z_rV0a4<^`sFdIiTUw7qom+nsA+@<4v5~1(v;2j>J@9^N=9#h}#!8<>uzVm~3fg<%? zAiN`F=sQAqcgWCphrT5*UJrPOO6WUOc(+REyH$ASO6WURco$3PyI6QfOXxdVcy~+a zyIXi(EcBf&j-!GX*ME-j-jS_ic&A9{J4JZcNa(vpp3vYOC%f-+%=;SNi4yuw6yB8* z`mU5GG`xQB%w6a+cRY(1`YfK0(O*lCcWw=K-`mD`@7iGZy&denw~O8PHrah|lil|g z?7p{P_q_$X?=9GUZyV#CaGM72ire4f9dbKQyjyPb!aL`-40spamJRQy+cNXA;C*1B z@5bYud7F)H+T{_-p7W%F@-XRzI4msW}7y52F-Z?k*o%07U z(A0O)@s4_=zN3zJ*A0Dl{af}Oaa8c)`p+@md$)BA@3aejrycLQ3w_t!6B@i@Z})wUd0&gRvzgF$ z^6{>|(0BDcq2cv|cRq!_^NDvsg}w{=Ut=_@TTkfm&6mO68`>D({W;isLl=8*XtMW) zCVOuv*n304-Wv+`-cYdjhJw8}v@yO(v}y3IqW$gr*#+!8@ol5c3*S82GT>WCTQ+p#c%*3#B7d{Zg(n@W6ZDfC-QPiXLsr``8C z=6wy{gbMv86yJ&p{Z`Zy8eTv6=1Ax_NB9;==(k9GjQ(1B^f};S{w{2cekV-k@4{sM zE==a{LNI?9g891;%-@Az{w@UbcOjU+3mc(C3EGJ~z-8htR$_&_{=H zUnoNRLO~xXLi4CmJg!c8}2@U!o zvHL#9ysx285}|#PpdS*UeU*4Z!|Mm%ybJy29pAzW{T7~&(O*lC{YnHY#Q{{W`B!5-0VEjx0}rieZJW; zpf5OEHuMo^%goDy{F)H+ZF=3lLi=h%A8tbX za6{j2Li=_@pKn6@d_!MwLi>V4A8|tah(mvFruH58EqU>JKp%Rh_MwNq^-S$s4}IZ^u;8!FD5=le=R-wTs4`$UmK&} zUBUeQ3g+)uFn_;-`TG^j->+c)eg*UQE117u!TkN&7<~fUH0UeX{uX@*+j*jIVVf8F z9JXaZU&OX-=%d({nU@9q!3ymgdDeYg4_ZEx(U-E&zLe1~tI$4{Iriw=1wR?gAGM9q zhqJ-_QAaX=)F$&sZ8CqLym+0U4`+w=;f%hW zP3_wmeLkDo=QH|(7TOmy`iK_VM>P757TR|-`l}S$r!>b=!HerZ$LQuVYVW(8sdf_c`W$4Sg~T?UNaOH4E*l*%KOGKj`yQXrG_x3sh)dpy>0{9;3gO z9)11`7H`7F823T2coTxfn-DDCgkbR|1dBHzSiA|r;!Ow^Z$hwm6E?<}6gCaUs<6Ms z7#4P(7~8_;g)uK|888-xEgQzjuw~|D!FU8h$L7G89YV+Kz*rta$MV3q07A$3;MkLI zF*XFScqlf;7$OFXhhngJC=M16#l_;Gm@FO&#xu3!p$HZaMX-1%g2h9zaa8klS6+AN z?)1%FI>u8FI#vb7un;407<0tbF-I^KiK%0eV2l!>W0YX*5}{+4pucpXW14Ur6}-6qbBu8} zY#qax8bZg^z*rkX$J+3O24j5KeV=3A*DxlC&@n+UR*2BCLOh}2^@Bd=h4wj*zUYPa zMbF3RucgPBQ-Z}ivoXdU6D;1DVDZibi+3hiyfeY#oe382Ot5%og2g)%EZ&)oF(#T# zgR#==Z!w0NohQatvw7{uy%#M5#$vN&!x(M0%)BfZ4@>CSa2PXA=$LUBOHSxmau}CN z=ooVxd-5&DCIc3a&&C+T4p=-sgT>=BSUf(1#p8=)@%T&@kI!WB_)Hd$Pq27=HjZk( z?#k;f-JQO(?@L&*)iCCo&@tCA7Mswq*f2($&@tLDcAL<# z+rA|)UJn?<4s;AVjBRJ=*mfB6&Y@%8VJtkCj)jLY@=P5g4`b&E9Xk)>^#~nPkK?G| z#r21!J(9IyN!JEH-t_VvJ>M z>R84Y7uD1;jyd+^Ta1khEFQFtF@`d*c+kM&K?92iZLoOI28##nVDX?`EFQGU;z64% z9<+_4ny4Do~)^3^c`(n&rp=17HEMTEy0b`6{p<@JN z>|mi|2Y*XmydE%yGUyn}7+V>1Y~>ggR~S0xGR9(d=vd4cquHfnG-K>$Q^#(`c#%TK zbmllJcyayb7~>AxI)*WYO&wDhV-1@+*03iu7~|OP`yBJWhB1*%9TOR2C7U`{vL`gW zelX^y&@neL7N^j$IQba;we-cug^Q7ul%EiepZ)0+uj*|fzam{+gT$~nB@F5Nt3r}q zVtb7>gpUr}zcY^r_6;K3wr4_7zIA=V17n^xQ-NBC{<33) znJhy;O6Qo<@NapZoEMjY%f@BqWtp<2qnWGO0OI@e>MrK_daTEHxfhFM0E*I zm~hd!G`J(-g*(S#JkwCZ`{TZH6w47o_;D?N*UQ6B!jtAyGrOD{_yvw?zPyZ{V6J1H z;0{H6%?-bXQ@MOEY%*6|Q?cQu>`x%lpHg}?;d3z&@*+RcY`oG`1Z0UpxZB*`qDJGN zNIxBMoFe;!jpWPD9p9+n#p`6!qsH*Lo-fIEux(KYSzL(lqXluH-=&6x+n!i$d=mPj#9PZ!5du2@S6wjQMWrnC}=1-qf++`567R^aTryTk7L8 znA+>iZw1U|>B9(@%dpPK(&CLn#9G6{$rz=Moe+&FKVf?#5I>Pv!!0$vg@alk92fRAq)d8;#cy++51702Q>VQ`VygK030j~~tb-=3wULEl2fL8~+I^fj- zuMT*1z^emZ9q{UaR|mX0;MD=I4tRCIs{>vg@alk92fRAq)d8;#cy++51702Q>VQ`V zygK030j~~tb-=3wULEl2fL90p_v*l}hfn+Ix6kXcJ5e7| zVf<{usTYTf6UXBb{_(t1RLGc!%D7_QK(X*_EmO*0H+^@JAZ{e#+3T8!qN!sEnI8L2 zDY2(|AmJ`UvxuPi6$p>L_?MYFm#XvR9afv$OQ^Pp{Wy=gx1wsJf&~)VZO1Wh({J&f zJtBMq$`SSN*?-=A*vg@alk92fRAq)d8;# zcy++51702Q>VQ`VygK030j~~tb-=3wULEl2fL8~+I^fj-uMT*1z^emZ9q{UaR|mX0 z;MD=I4tRCIs{>vg@alk92fRAq)d8;#cy++51702Q>cGEK2Y8%lPq5X_`kgHP^Pk_f zW1jLYGSPnpmfy%&*z)&3Vo9gpo_m6=GU_}5zxhY3@|6Gocebxres9}(b-=3wULEl2 zfL8~+I^fj-uMT*1z^emZ9q{UaR|mX0;MD=I4tRCIs{>vg@an*~)dBB*x~gw)J^b&e z2Opn0aa_iM``zT3(tqKr2Qxye6O|}E@yvLT!O@WLl_C#}0!!Nx<}^H=(_3d(MDGcf zXI9m!Ek=L0w*Oi3FKqdrC2XCsQJ&%H%88xhvJ=MN0{=}IKezqiazDA;f9}DNx0mU& zK+9h+eT(!4^3(Z%CAW{{qw|-)HD6vX`JMdUk{@Kg5=%bSs%1ldgzYl&GrFkuw~O_< zRP(dSE2K15c?sh`WqAo(B_I@JTOA6{>~ zK6yQ3Mt1%4cH!;yQ&4sESFFx-C4b3JN`UkxYe!ojFn?Q5kgu&jR=Me0{7$fTlzxzP zJ5sr2{=B@r9(eumdgJwppWF4!>)$FD@%TU5OO}h$t#WBOWVr}iWnk#j#B2@s490A5A?z;uvS@u@A>Mp~pl{!_zrE zw=JIF*wwWb2> zvJj?L~F|H<;QH>mRVabX!PFZD-MQ8cP2Uz1QYgIw9M{`tjC@s)&DOJy5^0VN&^1%Y*&*1vXUbm7x=ksko&hq&=pSR=Z_I#et^R0Ca^%WI&M(GP*FYt8) z=3}of__~9yNBFqL*DrisBj->Uf99L4<5b)kWzVeglD)U;fv{CSgsplbY}F@WtDXs4 z^-trnTtCVB!aVS2u)x?s)L!1U^U-x^?`c>%L+MyqQkMu@I!4&iJ;ML5+RmB>k_^^d zj<7YCBW%t0zQCS*OR8e+EqH>hxv`evZ`TXfe3)oB_T*cx+n(URSqtd7rCdAET-2f= zd-XS%`U_t>SeU-GWDv4$Ji%6ZiJs5@`MSWW2cqHFlW(myqHjIHnE(H{UO>L~`hsIm zzQsBLl!N5)1pm!ifa=*=3sBoxG}JDCgQ*?=vv%0Bk5_{$p3994vn~_-p67{}}_V{007&KQjNn!?KJz-4pEdB4!aG|I6L~z2kAYf`kK> z^)pJP%}Mx0%q>Q*ed!4w{NQ$V19X@({MEOY)Q7O1UIID<4zIT|~%o zNPaS1mQV7NSe1JVVObxNpG=qaB>Aa)iip#hk_51HDz8OvvU~_z`4hJI3YE_mDGy;w zPQtSOBtJ=m^|w^f7NIuQ*ebjJ_Fvt0zH1L=$8v!zn^ktgQPp<2T?eJE=r;X-(ROzG z@^+W~N$UgG6Rtm&ev&S6eY5nF$|B3g`kk$}T%Wm~bN%Q2!jk8Uw%~1q{cag+J84fe zz0^s)Y`YSd~^wv*$R=SCaN z#`dN3k$Ywv1AY4tPM_q4v16m6e~~#Av|d<)(v1SeAm^_I2nVNZ05h8>AiU^sIMlB1 zOY@fnZzEuE@K&1dyqpsPb%Gbue5dBB`tT}RLXf&s;b>l17pElQJY%Cn#iGp!H_E!q z`0N)#cWPpT4ks<2aJ@Ls2J;sr;%Smc*^}hjZoFFET^Pf!XYVp5CM1m6RJ40`Jp0E_0kAY@Y2h6F zOZJ5ED#N(&jAGr!Y1z}<9std%wJ`sfeKOmL&rZ0|Fk{ILX{RmNb-X{kkJZbV-T2<( zn%P^!l1(p+2O%AoB&Mn($w{HZ3?st~y(=`SaY9UnS_?{}w{Gzc7G zjM&x>W@a3_#F7~jwOBq@;|7Q=`QhglFPE&&Qo$ITV-UP;{AfwHLYs}l$9q8A9v7CB zIT8mlv~2{*vh7{+DtaF9-4Fx`&#YMz=VEn;mp?T`jvc?Gk7E#&99zy9yTi4(-A500%J`Ui)Z!4uzR>)Q(F(Gz_{H$T`+%V-2?Yiw7(wbu9FN6I*hL(VBo$`q?ee3#fNYe-WE6+BkM$GUlk=zN(C$4q* zzUY(vNcwPyY@WslJ8)*n%DY`)^2j4b-aS7o{e50FIB_lw6g;?Usq2_O3@BIz-n?A6 zG{crR#^m^|VC4FxOU?7Ejk^B5VEe0&OD!7(^CMS})p+NP1!FCH1*h*9T9&2%c;n}r zq44|VxXb>kecA9$*%9gw*t|4a)^t!{NmY2XY~IqgM}xrUR&F?dXyww>^_#$jRk7e| z#Nws#Cq+Qd;PZ~kS*9*YcrpS?Z`|j~Hmh;=7#n-S!S?ISz?mET8q})|sahlx2eRb! z58fFFSx1%<=hg)KuZr=P(YRwvv1;rX|LDc$8ZUqCEkyho{%z~#GK#kg6UWj|@vq-9 z9F{joO18os&b&GtD&CAsG@YM^LrAx1g!2}OfJG0Ukq)@S?!Mhst%}j?;Z5OAXqIA#L+Wbd>ml&=*g`|%=g=4ib&U-Y`=|aMWldb zaIbwm!VOEDHL97N2pdgf!LAWazQEI}{A~1@-GkCE9NuR9YIY~Q_rMDyZdDV_&pPr;N)Xohf}!={81*H3JB@XtC50EvKr_pkf2ydHODtk2`#Q z(*P)bv^CMB$T1MY`ZXr}`|N>mBV+A<#O}Uzq`2j%)hUAH;rM;nTvx|ZO159#=5iH1 zpzw}TR~$VCEBe9f#~W)eh0?dv$NgcfPuziU-dt&*N2cn8eLuH>AGbat*?#HK5B{t@ zjPS`vPI#aH0NJS1(FTCy=Wd3qw}Zvo!ThIp37`E~9x_(S3Nn4%ADN+B){2A&fB0bh zHn9caziy?1kR&y}z|UJ;F}9!WK$p8!DqtRClrRh1J(M{6&Vw9 z-)SPG%&!-$Fn-*s#_{z{;u(pThg16My{C3A{iN!1TCUzOKH&nDryHF8OmCR~X%5je z@81U=Jeon+NF548&rkVB?C#qRbq)s2dZc9F_{gR|idf zrs#j2T)}vqP4)f$Gq)Nm->JS|ZHq6Y-q@JRnC4_d$h$Ev;Whhv!q^vUNzU4xBcRr? zn^d2Hj&SJuF@+)P>Q&!v(5`|Yysvd#=-(+Z$n@Lu3c%YY#R%W%lms?!tV8%fg&eRv zeyJ~Tv^LS9Oik6VcZI}+cS)NPP37`-}RIl}vE+%U#2QuAK%^B|*= zUw=w3GPAs6^JZ0VIerqZQGcku6HvY@96xiI@^ptArwxW8clQ%b!-v6;>h*5InYVR= zQPIqQ#BRSmHrQ1zLdlbv;U|qF%=CZtBbirzZfY)%rN)BkD@M7J^i=e1M_qP2AFAYE z<``$hPon1k4|?4(=FM(L-){I+1?v2jj_?l^I)PC}*+#$D1EE5WDkO8-F-`~{-G^-c zpxb@G88FR|^?5l*OL%(qFT#0Zl!kh_13{)2EtU;Z7AsG9UyI_fX+r)l@UWCAV0=2& zuh+&+1?@H|o8TN*6cP?7MD*WxYY0$19^npSf}zTxy~OLv^?@*EM^(aO`}Kz>Q~R2d zZ8c%Hvr;=tJddH$T03{evn?wkIos5ugfv3ggt&vt zL+0yh?8v;b4cz|xnDS4Trw=4PK8x_B<`MApuRElN$^1j$W|n29@12j4i0!8xYw+?CRnVRStg)S@jm8}x&1}y$T|VD+x*}f(cLLJE*Kh6d+a$! zyBQJU?%Fj0@5W9s=4T5Py)Rq}Xn8s}%)JyOQi>M=KP9RIsp=&a;|rb&Xxp+oyxF|N z+}k8x;PP4#kYM@)SCP-r0xM*W09T_oj=jf^1jHWS3rde)Y4lqi8qmK|Q%ILKCY%X7 z?LYNH8K`;P57K{*>A$LIeVDo-A^4X0Z8^u+UloN#i3-8K6$3MiMa7_Ey#mneZA-sH z&+5RX_(|a2!|DFra|OffY5R?p!z%?Odoci-)@p8Cp0qNc>;oqxeSa$G#iF|br*ZAL zaLWlZZ=QI89oy7`Zkv;fgMPk&ea>fxO_$4xAAWoju&~hY#>2{;#Pgdk0+NJQG51lpSrv|dN=x{3?CNl^N}7Mf?!L|4bg}vSyb$`9Vs8Zw};v9{vf<# zb1f)TIyuNbSa(+|*qZefrE@HL(fkJ#O}YkZHHX{L4&{Tgo#;P}bJ#3F5lx}s$5!htag#udI< z8;OePqX#yfb==%ivWsZmB1zztDSgbK8U4kxemMhwYct-}wY5|1Z*K%v*!a|Ox_E?` zw6}7gt7BZa@wuV+>wUSvLw$ve98QJaB6ZQ7@J`4veJ(`!R6pH#^;WO1Lj2zfCZUa8(HQ* z3>du!_ZFHIa9kOhKQMmoaCmSimHFgSaA5on^?@A2H1YocJ45?GhllY4YogETM|Zn0o0p+#O}VuzG7lO z5$CtAUCuG~6@h(5BptCYVB^qqqFs}!BIS|c0ezReHn%ruCB~LdA8;{Xsd=hah{%w1 zj(?_?naoj_!bHJxkNpxQ`zt8)x>LN*aXNeA43CVU0A(xg`uf4dEoDj0-%{3qO;=J8 zZuMPvm|i8)tnny)w)FkOVadYp%zK0L`DH2Rgcz@9J7&MA=-&hPOY`G?X|)^C1IAS7 z2roxmGMe@p?}xSu&`wc5n^a(M{7PX zN6c$0(sxW45S%x;_-=PCaWvf!KeW?;_L}l^htaMB+IONsdk<*43FG(xI5zwvcK0og zjRMC-`j%rH8wHM$l-_PhZZXkU>D#c5iNuP?dX)Zo?{Tww!7hXgIs2I(JE=8Gy0V>I z3iH4 zy&XjJy}`I&T4_u75v!UE^SB647?7289DM4vKw zMCp^2Ry6LIS)?CcQ5?Q9U`4fKug!?6t;F>9V^+kQy3FjKG(?DLWB)()-aOo<`j6kH zSyG{B5W+coR}!I!vp$+gsVF2>eJrtE8bW(U=Ljvt)=7AXP+snbH+vC zrzLaZi)Rli8@^;>=v{qT`3DPTm)6$x(kssSu;{b?cNGqOXLR`ev#X--=J&|xTqNi` zBwBOG>Hi1oTqNk6B-(A;DVZy}j11=vEQx-oHZJr2*zuuyhy9{cKl`(=?W@J%fI-d5 zTV1}oJQmEF1dtIpLmuuf<i>=kOqvn0E@S^yyxnr!^QB&u=bL;2vpHqk0 zjoZ(d_wKiQS-ZE7vk8qS&D*8LA-3wH)^@^u*OcizEYkUyzjl?e&f6lLzxg^kpNn*E z=B)F-Nauc4a%GRzxv%LQ*dLqAI`=i51N-uo9~^5-n$83N)lZxgw>jui=M&cVkJkL2aOX)MMUO2>J{#Y9zEN1aee&Il?{7Fh z44kotufKZgxncEnulRfI^Bcy6b|Z?M@7MLxZiAESrH{NmE^H`m7xCWIwTGbV4#{y~ z4(r-O&@~8O=agAv!n<2v?EGPy;_%bH_xSp+|2!eAYp|97{IQKkg-pZSoPYUwP*^^3 zt@B|zcRc#P$#vIG9hOHk*PrFvc~pxvdb0ex-;?9F2cDT54;`Ew_eSft zvbyW~`TAq(Hn%IUNj@`&?RT{O+O?@K*L9aj*I%k+U8jk3y~fwk^_xi7Vw`ooC(^Z^ zD!H=9>ROlSnwMqYSf9ydUF$Mk^Rl@g&d$8|$SJn`+Zwj})o)~$-qFdfyC-V}&;FH} zd}(95?BXu==FGa;ZVlJRV^*JLYkD`$j_Y%GT-4|y8-DNs*$sbf6IFX}f}J*?cJ}Gc z^P~Q!USOH!&t>*`s#ciSs+Vos{Jz2;CWY|eSNmCc-)%Ere|vh^@AF^czTY&-6c&#T zr?$N&es+G1%yqh6TL1Ft<-M=j{SB;Hal$Y?lx!9iFR9yJ+q(u(!r*^bD&kf zrh0bH+>`9RakXvg+SUcS&Kl`@tG{-Yv98NTx<2dc=z49WYp>3_z8mQ}ZuMgKfI$ob9R4+?**PCj#HEIae;rEd)6Re_!7+yf`d8 zW~%c8?@kN{fB1s0-~QZD;mpHt@t;4k#^7-6%)}$S(B+u0Y-A(fh8lmah+3{ouDgD{ z$E3(UNw)u`wl5sEN}ug)L+6*K#3g$t%iEo`EJMuak#Iu+n{6ZyQRrz z=7=c+ZECZ>{rAeNMDi=XPGu|)6UoQ;I`T7-T#K`OP9&F8C0F)Xxh#{@^2g?~T$agc z`L-R^cevGC^kRI?-WCa_pWU$Q)j!9#t(I}8nd$2;^2!*j@xBlyLUrp+kRAO z$;o}z#PcsZ-Tqhafs$5dv@L(aimlO&4d;&R)Fyhk+ITy)=P7eL)qg!2JL?=fvDr^$ zpVe;^ww-m1?S9$fvgy}$4L>g5$Br)>Tz18hq2Z(_KZ_@iC5!KRY5!)2 zK0Pk<8+=%NX6HI3*L^%ZtnKoA+~BUuOWS>RN@zZ(hQ+;`meszieW>59r4_H3UDl|^ zQ_;q+M%X7ER+Wu;GaL0T9&dNHUs|?o)T8CKb}6<;FS>s2hrQ;olkX7x)RfBYuv^HvPY|S;*Gqg5pZfw~ucNfswsJXG1|J=8f)<(^Z?J)n+Qd%1|H*ve~FDa$9 zQF9ajyyCq3Xl>LD#EajYQJTxNHfjjU=kN2$Tv{77H|5=bDJZ42QF9X)EgxP=Yoq2S z9(7J}DXoo~8(a0pDW$YFYHsYc(@INdZ3b2wZS`C4ouRc+b7RLmR+^!;QFCK+f8H}g zYoq4I>J7ZLkk&@cjSXH~r;yf0&5bQO{qX`?8#OoaZ}sOF(AucEiI3{FTOm!2nhAgH zDq~t3^%lMkt&Lg=XF46V8dY*-kEOLyr{eowF4NkmS@GqxHfnC1X>HWpIMdpwx$)mi zYoq4InbtHWpIMdpw zxpAhoQFG%=Yoq4InbtNw! zoPB1CT-jsw9x>i8{GG~WyHWpIMdpwxpAhoQFG%=Yoq2SSx47P)!g{+qP0d)naldT z3VdF%oYqFojWex{nj2?Y8#Oon^J#6=+&I(PsJU^bwNZ29Olza&#+lYe&5bjyjhY*0 zS{pSt&ZpAaZ2hPIE?OHkH_o&+YHplqZE`-Vx5%_M6`$?2HWi=wv^F_^BeuwuJ(kvn zzmH$-Hiy5Jo0!%{&CTL&AH7*XYoq3-{N8g~7Sh_Nxrwh_dtxE2jhdUdpxqILv^HvP zY}?ECD5SMfb7Q|udb5DmM$L`A6E!KIwNZ0p?cTYnfYwIMjg8oIn=Gx3nj5?6+f^A_ z8#OofbBD4Ft&N%+yQ$X!8Cn}PH&%bciG{Q_YHs3Q>t~nJ+HidGZRynigK2FzKKbOd zQKhstYHs4Km%Ug*Yoq4IUcTb90$Lk2H}*o4tuwSXYHsZA2PS7|ZPeV@4cotxp|w$S zV{LZbI!kM#=Ek1e?#&FXjhY*KsB?<~S{pStw))4L3TSQA+}K0YHWtv@sJV$J?Q&=# zt&N(S_~=Kv7t-3Oxhd~?*>i=oHaW*;TVz_Bieouin~GyRTAQ3>!Yy)TkEONAIUe4` zv^EvT!?ZSPZv1$d)<(^Ze-6;vsJZd|mexkijWex{nj7EeX>HWpIMdpwxpAhoQFG%= zYoq4InbtHWpIMdpwxpAhoQFG%=Yoq4InbtHWpIMdpwxpAhoQFG%=Yoq4Ip9fkSH8;+*HfnDC{X%P_=EmPgv^F`{Ube`z zHWk-uXl*L4;n3RTT=Ur?SN2$4?=r4;ec5OGNfrFUXDuhu+Hk$=$d4yArL|FW6Y(6< z+NinlZKkzRbL0OPS{pSt{(q#kQFG%=Yoq4IpA%XeH8;+*HfnC1X>HWpIMdpwxpAho zQFG%=Yoq4InbtHWpIMdpwxpAho zQFG%=Yoq4Inbt)~4dxEUit&HCtWRjdQN?Zjmc{EUgXKw|Px-nbwBu+bpNGQFG%=Yoq4I znbt%}WdX>HWpSiHVz8Lf?) z8#{Pzt5RAUH8-|#|3B`dwNZ0pyO+*rMr)(y#(FQkuqmyLnj3#^X>HWpILj#n`~usV z%d|H51(ws=sJU^bwNZ29Olza&#@g0@qzSE!nj5=$eNi)78#OmN552k>t&N%++jrTp zQd%1|H#TJa0cEr{YHsY~X>XO%+NimS|K6c*DXoo~oA`kLOfI3dQFBvX{B-$!v^HvP z{CT6bQFG%=Ym?(vw#c+L6)r}e#VQ;Ptxb;8*&HWpIMdpwx#`IBKx?Ds#-BG@8#Oo1v^F^|b&E`E zQ{i4|Z7Q5Btxb-@-6B`^SX!GLf4zxmZSdD@Gp&u98)sS@H8;+*HfnC1X>HWp_}_h6 z8#OmEkEOLybK}nst&N%+XIdLIH_o&+YHplqZPeU2)7q%HalTEhjhY*0S{pSt&a^i4 z1N^RBrnR9TU^%Ugnj2?Y8#Oo1v^HvPoM~;;+&I(P)V?Cw23i|6H@=+KM$L^gt&N%+ zXIdLIH~#;nwNZ29`#-IXnj3##(AucE@#l)xM$L^gtxZllu|=k}sc0=|Z7LcJTAQ3^ zV~bqbV`**ZRo33TRkaFU*uQo)S{r(mZbx5PMr)(yCfwRFQ$}l}<|g{J$CahDHfnC7 z^LD?kgw{sQO;P=!f80lFqvoc(=iv5DX>HWp`13<+qvpn$)<(^ZGp&u98>@a}rzW&E zYHn=mjQUM!ZPeV@FZ*v*LTjVu#u_g_vXs_F&5iwaMWYh7o$coJ&1JTo|HH4hLw6@5VJ(l+h?-QQ4T;{z}(WlYcsJRKOLu;ev z#@DB{QFG%=Yoq4Inbt&n$i~t<5b($$OU8M$L^cr?pXY<4kL#=Ej-UM$L^g zt&N%+XIdLIH_o&+YHs}hMQfwx#+lYe&5gguX>HWp_;W&Qqvpn$)<(@uVB7ed&S@jJ z$b7C>w3K|_S2ULVeaLAtx5$+}mcNbsjSLGKWOJFnjr@&VzVCsBv^HvP!t6(H%+T7X zxe47a|1Lvoqvj@h^0D2sv^HvPqDv2Io~5->b5r!%)HYdK8#Ooad)b|{v^HvPY^U*0 zW@v5H+}OmsZ^_WwsJXG1Uh9&fwNZ0pL%+VKkk&@cjUBUfrWvh`nj1Uqn7JjiHfnBc zZE3f;9Gh^A(x>Z5Gb(sjF~=qxqww6)+Nim)HWp*zEF+g|s$mZtTk%b279xYHsX?D{s!w+NimScf5PIEUk^2oAMS7 zTV`o()Z9cvh8>)xwNY~u4XV{JOKYR%CY*QuuNhh!H8)|$jhAFNF3V}5x5ymFaXiQW zh2y)5rkdlyoCbS~T-jqe7Unqk{b~*NuHf1WuHTzuVeiiuK3Ym^qvj^Oe|3)nS{pSt zVe}!dmC)L#xrtu<`PUL!8#Oo4pLZ-Np|w$S6Af*No*dEtioT0T*b7Objv!amJM$L_#^y`8WS{pSt z_D}n#OKEM?+}H*0Z78L+QFCK6zwb~+Yoq2S-tW@cWwbVGZsPx)wM`kVjhdSdzrK22 zDXoo~o9LO|ZNoIMdpwx$*xOt&N%+XIdLIH^%R!wNZ29Olza&#+lYe&5bjyjhY*0S{pSt&Rl!o zx&uEam$~*(@qHg!8#On+4y}!v8)sS@H8;+*HfnC1X>HWpIMdpwxpAhoQFG(lPiv#* z#+lYe&5eJy)7q%HiP#=m8#OlprnOOX<4kL#=Ej-pE;-+I+9GqErsBI%T)(OK&J@>s za=v4=MXv0zT&C)wMg{Jp^mZ7y#a}!>! z_gRM4M$Juh$HSJPwNY~uecoechSo;SO+5DJMTN9BYHs5FR^4AfYoq4IhSt8Xkk&@c zjrTURHfnB+-iFpj&5hC9(AucEF?t(X8#OmZZ^N}lt~1tCV^hH$#9V9Snj^gpt&N%+ zqqm{8QFCMTHncWsZj9cB)<(^Z(c944sJZdphSo;Sjm=zfZ6U3Vnwxm5;kOsi+NilH z->J?!g|s$mZlY#K_R7%OsJV$o?sR{K)<(@u*!$Y|Gqg5pZo<HWp zIMdpwxpAhoQFG&rTgdr7?HWpIMdpwxp{_drnOOX6T!4LYHplqZPeTZmebm(xpAhoQFG&rSHZ8aPGyXT z!N;%;ex~9((fFL4?@(`%D|;+1E9d*;n;4f>@%?dH8#On+owPP;Zk%at)Z94J+Nim4 zrnOOX26${P(+*7kS_*h6t&O^ks<^Vp(yGv` z@Yr0YRiRm7IjxPF8)sS@H8;+*HfnC1X>HWpIMdpwxpAhoQFG(Z39XHqn`il%v^HvP z{Q0D{QFG%=Yoq4IScld|&5bjyjhY*0S{pSt&gnL9#_9I^a#|ZTH_o&+YHplqZPeU2 z)7q%Hai+CVbK^{Fqvpo9jn+oZjbC@AwNZ29|1WQCW>pJpGp&u98)sS@H8;+*HfnC1 zX>HWpIH#{&5s$5m)7RS9Nnc0jbU*R!sf;UoZ2BJYZOG;H{o>1MZPeU2)7q%Hai+CV zbK^{Fqvpn$)<(^ZGp&u98-IRiZPeWOHq+Xux$)JPwNZ29Olzb2 z+c?wOsJU@YKchC|^z+J>)7q%Hai+CVbK^{FqvpohTbr*Fk3egq=Ej%P+NilHXM1RE z)ZF;?)7q%H@&6aCjhdUlINogtHGjKSOJy<|gbiX<>%eM$JvM`}*oxS{pSt(O0)G&(PYaxhY@&$VGE$ZPeVv z-@ZGigw{sQjji0dRw=EGnj1TQo35p_HfnC{+|?6GX>HWp*uiICRGJ>2Sn;_-{tr%% zPwe$YSC`V-sJXGBU2iC*wNZ0pGv`k!rL|FWWAk@8wUpLI&5d33NT!t5M$Jv!Ci`6p zt&N(S#jhSe@IG1_H8;_ljje#zM$JtW9;}|FwNY~u_P_R%46Tito6w^4h77HZnwzkE zM)M4HWpgcthUSePE0`RiC2r^j->PI{c?oE`^O$(21eJs$RbFPGEf zVP8&bqvpn$)<(^ZGp&u98)sS@H8;+*HfnC1X>HWp__op7sJU^bwNZ29pHZ|nYHniQ zFSIslZk%at)Z7@$X>HWpIMdpwxp7Xga1e8iX2+Nim4rnOOX<4kL#=Ej-UM$L^g zt&N%+-v(M6H8=jAqP0r{`|IJUuUSPR{|W&t0v)Z94J+Nim4rnOOX<4kL# z=Ej-UM$L^gt&N%+XIdLIH@=;;HfnDC`J}Z`a})Et(b}lFai+CVb7L&0wNZ29Olza& z#yP#_uoNoIMdpw zxd|+%wNZ29Olza&#+lYe&5bjyjhY*0S{pSt&gr!m|CyC>dacISNw32=r`LR{HWpIMdpwxpAhoQFG%=Yoq4InbtHWp#E&dvwjx+NimSKDc8*mexkiO_+S<@GPy3nwxOMkn^*& zHfnCdV|#SY(%PuG2{Z59F-vQs<|drE*VGKHjhdUVdWW9PXl>NogpWp!Elk~t?*o-_ z>SBDI)U!CJPNzz)?6IlC^2g?K>a%<~t&N%+XIdLIH_o&+YHplqZPeU2)7q%Hai+CV zbK^{Fqvpn$)<(^Z@2j*nYHs{9pVmgrjlcJ4ZPeVvyr*bw)Z7?MYoq4IIdzDeaq1I& zIjxPF8)sS@H8;+*HfnDC=hND#xpAhoQFG(x)U-BgZhSjwZPeTZwt?10&5bjyjhY*0 zS{pSt&a^gaZk%at)Z94J+Nim4PF-r1oVr(EC-th%sl%<3D|>9}ul=#Poce2DPHUs) z#+lYe&5bjyjhY*0S{pSt&a^gaZk%at)Z94J+Nim4rnOOXp37-J;Oo%ZsJU^bwNZ29>(kn(xpAhoQFD{9S{pSt zz8})ssJV&wU9>i8ZhZS`ZPeU2)7q%Hai+CVbK^{Fqvpn$)<(^ZGp&u98|Sp0sFKsx z!q-VV3g@)hsFEvtY}%-V^!_%qE6!=J5)SQJkNevMH8)}H4%NB8O{C@~H16m3w~5r; zg!KM4MQUzBdVia8H8&x>zm2K63F-Z9OwCP5?{8yjZbEv08&h)=rT4cnH8(}+{cTLm zO`P7}#?;)z>HTd?&5fn^x1kq`>m~QM*~DotWa<5FOwEm@_qQ=MH*tD@8&h)=r}wup zH8#?;(|^!_%c<|d@~w=p$0A-%s%tmY=9_qSQB<|d@~w~5r;g!KM4 zk(!%ub8El9O;B?a>e?OL--bTQU%SdUZL55pw3~8H8?7q2vd5-Pnm;y|(>~3Y)7q%H zai+CVbK^{Fqvpn$)<(^ZGp&u98)sS@H8;+*HfnC1X>HWpIMdpwx$*ZDt&N%+XIdLI zH~!wIwNZ29??+l2H8;*_AGjIQ+UPUOm($v)xpAhoQFG%=Yoq4InbtAh7PFqS} zC+#Gi(HWpIMdpwxpAhoQFG%zpVmgrO~iYg)<(^ZGp&u98{als8#Oo1 zv^HvPlI3b`)Z94J+Nim4rnOOX<4kL#=Ej-UM$L_L`rU^rIsLALuakZc!a4oUMU`CH zW7F@L_+xW9{l1AWr?pXY<4kL#=Ej-UM$L^gt&N%+XIdLIH_o&+YHplqZPeU2)7q%H zai+CVbK^{Fqvpn+b6OiUH_o&+YHs`(o7P6nP0VXVYoqH9zCYx0`h6c?ht@{TjWex{ znj2rA)<(^Z|9n~-H8;+*HfnC1X>HWp__op7sJU^bwNZ29Olza&#+lYe&5bjyjhY*0 zS{pSt&a^gaZk*HaI#tQ(ccXlr^m|Xv>36KEHWpIH%ujtdi63Li#%C z_Z*$m?^IUFl|457KB+%8m(%Z)`tv|*qvpn$)<(^ZuTN{E=Ej-UM$L^gt&N%+XIdLI zH_o&+YHplqZPeU2)7q%Hai+CVbK^{FqvpncFRhK58)sS@H8<{a)9>^8{*cS*_j!Ha zptVtR<4kL#=Em2jwNZ29Ka8Wt@KZ+1E+G*X*2rhq_9x?6K+h$NjOnoPK}Y zw~f|D&5bjyjhY)@pVmgrjWex{nj2?Y8#Oo1v^HvPoM~;;+&I(PsJU^bwNZ29Olza& z#+lYe&5i$FS{pSt&a^gaZv3@Nzq9YlbD7pg&5ggWX>HWpIMdpwx$*UBZPeU2)7q%H z@!v~pqvpn$)<(^ZGp&u98)sS@H8;+*HfnC1X>HWpIMdpwxpAhoQFG%=Yoq4Ie{Xv4 z0$*Mkr}sMWb<+D7IH&hasFEvtYHHxsK2mQdcO$YHd-5IO7WRVYoq4I znbwAxQY@#nVWt#JYr{+_nAV1wQZTIzGo@f!8)izuv^LC?f@y7-DFxHoFjESqwPB_d zOl!kTDLB1H$7Y<~ufz8ZS{r6cu|BO0Go@f!8)izuv^LC?f@y7-DFxHosJU^bwNZ29 zOl!kTDb}I2VWt#JYr{+_nAV1wQZTIzGo@f!8#Oo4C9``rqqR{p;pAg*So%FsX z&gnf;s^rQZo8BMBwHWpIMdoNQ;KzHZI~$qYn!=0&t{z7pU0Qe+Avd! z^=WOGDFxHosJZcFJ(1=HFvQwpZFVWt$U*N%G=B|oPU)@#kZjC>uvj@;wOS^Ek1M5>Z2d#v6s+z-mP zA(zwpK^0xm^rRA68)izqSoB;etqn7!9{HkU8LbU7rEa}$av7}+Go@DkZ(13x4KtD4Kt-+S{pSt&a^hnlwvup4Kt-+S{pSt{(S1#jC&9I z`jxSc<+xX&ucPBM?qTSx<3R3tSS45XSRDg%zenGOT-Nb$P;*nxcGB7~QwpZFVWt#J zYr{+_nAV1wQZTIzGo@f!8)izuv^LC?f@y7-DFxHoFjESqwPB_dOl!kTDVWxVnNl#V z4Kt-+or7?{O<$hN>HRi+9a_q;R_DCj-?d}2ZLcn<;C;mD{as_WnbwAxQZTIzGo@f!8)izuv^LC?f@y7- zDFxHoFjESqwPB_dOl!kTDVWxVnNl#V4Kt-+S{r6c!L&Bal!9q(m?;J8ngjRO-Hg-w z>-ut98)izeKCKNirC?ecW=g@dHq4ZQX>FJ(1=HFvQwpZFVWt#JYr{+_nAV1wQZTIz zGo@f!8#Oo1v^LC?VmYl1Go|44-opOa%2?NGxEHanqw6r-qu4pUr*V~B*<*E$i~BkI zHsrFdcX2=Gm~ErAVWt#JYr{+_nAV1wQZTIzGo@f!8)izuv^LC?f@y7-DFxHoFjESq zwNZ29Olza&#+lYe&5bjy4Kt-!pVo$%Qn0Qunwp!I(rWEVb+AvcJrnOtqn7!U|JhyO2M=?%#?y@ZI~$q z)7mgo3Z}JTrW8zT!%Qid)`poVU`Z%+T5}Q|i%QKF!eDFjK0|*Y&fsHq4Y-IJQ-m)<(@u zs5Pfmmez)uQg^+zTb9;F%}wat@`DVm4Kt;tZMY;uYoq4I=Sk7pFjI=>O%9QH89q-c zm(zI}z7DMoGo|`#o)oPOGo_d(MQg)MsU<~SGqg6$lv=m=kqoU3Go?nX{3}Ci!%V6D zzHOVOwPB{zx64k<(%LXn>ey)aEUgVQrS6zlElX>|OsUHch%>Y{YHk)^xMXmK)`po< z7yb9OLRuSUO4*HHmdd3vE5x_6GM0N~wurAIugc63=X5Sfm0a0l)0r&3@8z=mHS<|~ zIjs#drFfocZI~$q)7mgo3Z}JTrW8zT!%Qid)`poI(rWEVb+AvcJrnO}bojyeiv3^}XQU?x$OT-jskYv@%Tob%{T72M+2+iRusn5^Z!_m|SzFjMN` zYj()c+Ave<=trw%XlxhqYZcmu+Xem!8>tUM{N_Vjfngw)5Miv^LC?db|03rL;E8l=`aWecazBW~S6{ zf1OZDYoq(ygd;muE2Xv3{cS?QW1UNBZI~%Fzu%-XS{r6c754kRjMj#kQis2HMH#IP zGo>2tyHgph4Kt-aoY=IK)<*ZYi7&dmeIcz4Go{WOu%?jKhM7|1zkcmLUN>Gp_JPWn z*O}Lwb$I=GEn)T-_LZu*vd8jX;XT7+b6I^F^Vf{!v^LC?f@y7-DFxHoFjESqwNZ29 zOl!kTDVEdPFjESqwPB_dOl!kTDVWxVnNl#V4Kt-+S{pSt&a^hnlwvup4Kt-+HG#~( z+l=|F;xmhNXl-sOO5U@yHq4Y_Ijs#drC?ecW=g@dHq4ZQX>FJ(1=HFvQwpZFVWt#J zYr{+_nAV1wQZTIzGo@f!8)izuv^LC?g4ISc`_F%7Wz6R~pYN>C=RKd@Fn=HT+fWr( z_E`Ql@^>-4zs)9AkIKA7OYd(Jm?@Rs-zG3qD!so=V5U@hf1AKesr3Ffftgb2{cQp> zrPBM`1ZGO5_qPemluGY!6ERaNy}wPwOsVw#HXYU6g!KM4F*Bvo``g6KluGY!!@SEt zZ^Lm4oZjDtd6)j2(AqFlD!so=%uFeI8(JGRHzB>hO~g#8^!_#xGo|QlXl&x*S$7(RggB%N1#g#plV_}Yod2BALKWDzGFQ>I(rWEVY+AvcJrnOfY0uWod1gDfLsex>;HqW=eHwzam3x!%V3z z!>-TJ+Nik+uN_h|Lu;evCS3g2X(hBa%#@nCYR59JJ#gLO{O(1ixy-c(u0gDNEGnb5 zVWw2eD4Kt-+S{pSt z&a^hnlwvupjhY*0S{r6cv7FY1nNl#<8oAE+Z`Swwm|yS9X>FJ(#X7V$YHplqZI~&= za#|Z^O2M=?%#?y@ZI~$q)7mgo3Z}JTrW8zT!%Qid)`po#|&*WgV{9a_tq?cPazdcB|sb9?P|Du50tyT-NtVBd&3?oYsb!QZTIz zGo@f!8)izuv^LC?f@y7-DFxHoFjESqwPB_dOl!kTDVWxVnNl#V4Kt-+S{r6c!L&Ba zl!9q()Z94Z7Vruz&t=>Kj)CR0Hq4ZQX>FJ(1=HFvQwpZFVWt#JYr{+_nAS$kjc+Hd zjhY*0S{r6cu@0?`nwuD=wPB_dOl!kTDVWxVnNl#V4Kt-+yb6A$D#pX$V^{}2gKL5D zIk=pvxU$FMvhY|uHkbAN@d&5Ia#|ZTH_o&+%#>m|tqn7!U|JhyO2M=?%#?y@ZI~$q z)7mgo3Z}JTrW8zT!%Qid)`pog-v{#hKz<*{?*sXLAiodf_ksLAklzRL`#^pl$nOLBeIUON5hP(IL#rc-D=Z0?kEc5yAlV2zfN3A)?=egTHmxN~)P4W5c|2#V= z+6CG?os-9bl}wUo$uMMQS{Z<?aZH} zku?T8FB{n?ywK$s=a%b+gc^UY@a?ouE(u@nG0Az=#^PXYUpS0yF4_B%(D|h)F?{r} zL80AQ>zv1~I6Q1~V8&Sf-O>hOw?W6+e}~<$@6=|0MTw4e z^)t2#N1WK-moNXeMtJX$Q=G56CmWXDk*t5&#a+VWOB?(0OIDv2x;0$yzqhE-MPYoO zyPd1OHz92JYnzB|=zr=3;pxuvo#(ac74~_mR$%#qU+ouum=v7%|NNKe>u*nY?%Vd7 zsIYjn^In%vFS>3>@*K|UxuksH=M%$KU*4S^deYL4xBgrl*5CKRqzZoOpYJ9uUtJiV zaQ*nO^5*lJjXZCk_^Y+aYxm8dnjP=?JNY?-n)QtyYBbh={ujHy81))A-1+@8YK2bc z^m6WVOux{5uWg(|uM5MNw;u5Auknw5|J93pzdB;$xR4#x#{a*wyPgw9_kF{8&Y}~; zu(`V%|Ho5Ax+l|M!G&*c0`fXRbdhbn39&xBrxyWO(42xiMUKUB3{m-^$=CuPF*+>Na=&wQJKbY`>$OZ>@Dqh@Wk=8Bd>A z7>1m5gfAa;#DU@Ii#s|uxS~rqby%{`Pdsi=IR5qIy*8%K$gtxLrT%*#J#|8Ob4?xR zFItZZJKuM!Z|7xa4hS`-Rtvs8ecFd`Q%mQMYHb$=?9tcxrzLZuI%izu+^71oqTx%D z&x*^=`LMk9?1a~Sc2zv|o#cJ7w*8)QVZ-D(%;m*D-XAZWaH0R4a|f2hS9BTaT)o47 z@%v+w_rd{#niaKuHF+(1t{o8l{llfc&b|F!i-taZj`Ox#A08$*&pQA9-oS9p4jcUc za^r!Qgo`>QpQX$6Su|rv;j{d|{+c@`e6a8$|G)n^b!d3!*3X^Wy?tDG_uIXUbyj`U zI_%Qo5a$OD=@o96Uu!d7`P(7k-kn?f@>$yzg)`?Suid=GJ;UY0l70U8gU<;YUr63- zf1fobv?;#Cf7gtgibKOA&+`3Yn;V9QyXL&$+q}L{k8s&3bpzY5A?z3KtKG@@xH{iN z->o^*`H+i-McWQao`=)E>DaO4ujKjZJng7>Qc<$cKYiL`affxu--S27ydYlrR)(jW3X|va!Q&^zKP^w*7cczUsXTfz`T0NowQY3MYsu?)%mepE z(-$YN*VA)ag{J-5`Oj%z{p2v@w_TmXhzmm5@<;vu_5E(eVN~~r{j+G_ttNzN^&9x} z@MQnA!nx$0U7`kKlINlNy4%Y4Jt}#A4q7lHKEGPJ z&rkUzp4NGouiw1ieenl#lIJRyPiym6yu9{lzRnvP*TuIKC7&msZv9|f*e!Wq{L;Ec zTzf(CyO#gax@ggo3D!oHDGk;o0;a%$&@*R!)qu0=)B8w-NWz}yBW{Jo;REm z9@_48U!Kc*bv`+)p0%s5vt5%uVe5lyI4|mOPUv@Qvd?$Cc})21`ceMab5Ac0Z=Z3k z|K4}oPYg#d_{H~!FE^eN%7@kPZT{$nHsO^~ZJno_yluGTn&dNQhuyA=cIbbxFaLE# z-=YEcCeOne2NuR%Zcjcd9^B!nc=xZ9*C?7)-Huq^-`8i`*>3(Xxy-ine_;7L*X?X` z@9OFN>G0+8;j7MazPr)s@tnoUd#$W*tMaMOC%^Z{SL#PKnHtCY7R{vd)wWI zggb_`_Q(D?c|e%hGx;oCdf_Eu;1QQc{H~9GDGp7V&i8$9;)HRbQ~%)4kF6UXPKuv% z{_czZVbJjE#`^3#>^FCHo?NSf3;SKMGy4wv(4LonQ#k9W!J*DWKgB<;YLV^LXJlCX z*WCD&p}S|h|1myH{;NU!pBtxTmi$&68n2kuan+3?=pI)}G^>LwS z(ca<7s7Kj}yEO}qFFPvyCz@Qk|Fo~7o;`>7|E2u0dzbex>#v*H z*hUOa_TdeOZiuJ7GSHWw`oQh+Z7Y+%HA8!C8`pj(dCq&kGOnoh70EWtfBg4oe$C{) zvvs$^aQi(+_+!5x*CV`LP&a&k+~BgaUb!F)`TF5#P`jyRPmG@!b~x$tqN2TbE&G1q z#PHuAUN3*8e#=a^%SMIM7Tz3x{?LxubGi=;efobAFI#oLs@>} zL&L+G>Yk z-R8c{^?TL{ckX zZETE=1$}!~7T66NlIMZHUHlDWc`oy}i@#wk@6xlC*}chU_$M`M+bjP|w&AuLUy4T@ zkQ{UN>pmc^`)l%EsPor5i;w&r3Z}-PgOtFpTkc7oF8VidCZw(2aX$9 zCzm;P;247CYdVh#x9oST^U4k5!wN(d{-Q%mvxv|?X{ER z&qt39JNCPEUUr*z5S#j+y}8V> z8^>_VUTRRbr**R4W3%C@SwrSEUfINIOgcIoWDDkfvvF12`2I7(Wm_$sx9c0X#(N() zDm?bgqw{|G^V{-I222b;u9`IOt9?tOx`iV{(T~@cHTt7^ICw_?(00EmrC(Z`@MG8H zv-Feg28J8I_{aahH@tdrIK1IZ=PAb*hxRpZ_I>h@brZt3zg3Ib&dWX=9cC`L%9&$l zj+k7>Oa3`?a`sMXhy{Pb8b5` z{CMHF&L{u5cbNarvHtu-M|==n-8uQ}?Y!TyQNg<8GiSooQRRD0OZK;knH%GA-z3N3 z|NZ>W_|yGP^T(dtJZmj4<%arvjwu{$Pz z_kTR1S!mw(D1Ypsbx#W8j<4f9<*pH->A6q)|9$48<3sbJX3m9g6o+olHuC3f`P<{d z;BM_=wvBT~&Kv*DoI7$3$?}e$O$e85+}inu{}qS%A3W&muWLFkEW56=|NQ&^7!k(Y z@}%<~3r-EkE!xhvr^SLAVb8ad|Kqe@AC4Y+=>lJV;_F`(^*B5EoH_UJ-Q#Rg^4UAM zv&FxSKF`+~bJni*;_1oX(BJ#Evu|`P$o4E;aFTs_R&8g_-8pY(c`kGA&N)2G|ESZ? zmWm>BlE)BLsI+6mW9*v?$$+6mWCSboUM#o>wd2RNTUX<~S$(`UZ^!=GFnCOvws z|NKXH9U5+$kz6M^ztQob#Q}Tzwq5h&&(U@p&v5>4kISPc&QFfLe{1=2$G7#`^Ye=y zKQDf_dh*#j=a=u|rR~r3$`G5jaHVsHk=?E1oxAz^Ki__!^=O)WHajD0AMvrY9n$2wE-2B_Vp?q=jT3_?zg<;*@ z^ZfVjS~ej(+IL6i5?#A`;DvYme69c5v0+KKV|{rpx7tt~=FM&C`}wDfi$htz_Wqn- z&}dxfusYf2Pk($wxMSl}{@BsO`i0xR-P*UI$v;t;J9>ZTE5nP?V1$lKWqB@-y6t@98ZOJ1#Ut#a|0LVF!|na;zLnK|{mFfbY|^pGu|boi zd)r?H$NBQnM|>T>RG1uV?Qrfbi|3`+J!ZXeSQH*l&H*o&|3UOe^W?L1ms$m3;QS-~ zvE7SL2;)vn_J>bLo*k+;ddIinu!k-U&mVqr82idsYe^2{hPB&lY(u0q% z^4F8kitB0)vV9i)?%Qy3;e{4|_@MI%-G|tq+rQe3`%fQjYu}&h%OC&hV%v92vd!Do z8)kp@_|%uTntPm8Z?d=lu4-R5x52L^?}d*Z*w*&w)z_C_F#N;vn(1|q!xy|*RO{{J zGjr*XN20A4B%h`A2i6U}dnTVnO|I+|hCiG2$DTUuwD7>zfBNrQyX>N{Rl7T!+n+f; z3_ke)=X(7|gtuONW;6cr&T(Pt!ySEjrw=X-UmkUu^KTE12(=GL{=U@Ore8Q`TJl~i z+5hnH_dgl`y)z~>47GOb>O7#^z-Z5JlFyc{`ZRp@ObRj1>b>9x~dOD~W19(0MXUu{;kFnUn(S@g;7t-@WOC&#+i%{w{VQEgXW=dqoK zhnE|^?7w%>W0!<)dnVhj{U_w?Kbu(lPpH^`#%?z%T>1QM{@7<03<(WtCx2f~zvqPT zYvbg-w*RtLA!?QU-dhIj6o%L9?Z3B2ukE6H|C8+JlZQW9e)sxh|2b*+eev4clh2&r zs@Jj;AL!-lKe9sy>-<^^=Prlzw*#jqe?vDGjI=&YN_`vZoHgEVSiirs-m{kT{@uiS z|60ZSx8{`-t--yY_oYUte12|XeSU_D&(EX!4iEJfz3A)z^?TpY_pW50 zZ~RcFP-9l|UOR4=eFF}Ref#7-Yohs=CHu47SJ4xeY_r@~{BX5on>*EiJsvwN`ONvO zek0p<)-nFr>DP8O92h_6iX}r02L?~LWQ^g!;7<=Iw&zOc`tzy3S(fwnYZL45m))QK z{VH2iY%5PL@xNtW4gbBh?`m)LyR~#~RO6|5 z<5$Vw;xTV#Q@WPut{jooue`vUU_QB58 zk3J>5K5a+m#~(i{v^_KV`=w)skaPU7iFN!CDvlrIz5))6|GV5*z=6SXUjYXO%Y6kL z7%cY{;lN&nr z&hgtO*72KF9KXqZ84ir~<-QCD2FraJ4h)w2G8`Bz_hmRRSneyvfx&WLF%Art`+5ck z2Fra#I51f5E5d=na$f-l2FrZ~92hM36>wm%j+q0;&)1hWXi&j-jhfRy$IpS|=dC~J zGFR>^;J{da=^dQ{4h)w23OF!W?kmE9!E#>_4h)w2ig94SJ@#D_xvv-pw(+#ug>qkp z1M6P*`K;WR;lRGV?Z&L!m*K!B@40_g?#pmskHn)ha$kl6yCt)#K<>+MVE8YczZmB) zAIpDL@B{K+I)5?FU+`aYUxowgx<{r&?#pmsZ6>#9Cii7Huy4CI$;f>f4(#?Lf6T~z z84m2k;e)brUxou4_}PnDxvv-pwx-toS-G!r9N6|vAJ|v!E5d>C|CRfSaA2_9SHOY6 za$f-l2FrZ~9N3+wO`fN7#*lOVxQTWC7%I*m<-P(AjK|7-1soVG_Z4tpu-sRK1B2zh zA{-bj_Z8#7V7adt2L{W184e7V`!XCDEcazNFj(%(aA2_9m*K!*xi7G8`D|%Y7LR43_&c92hM3WjHWc?#pmsu-up7z+kzr7zYN+eZ@F1SnjI` z2L{W1MK~~6?knKHV7ae=1B2zh0uBt;HItBY{bUpC`bpsW3G2vx1soVG_Z4tpu-sRK z1B2zhA{-bj_Z8v5V7adt2L{W184e7V`?4$Lz+kyA!-2taUxovN<-QCD2FraJ4h)w2 zG8`DJYgU$X{c02I`ju5&zmoeh92o1%eHji6misas7%cZ?I51f5%Wz<@+?V0NV7adt z2L{W1#W*ln?yCb143_(faA2_9SA+wD<-P(A43_%}I51e(3`5TK!%eK~hoR#7q1;!% zfw8{aSHOY6a$gY+43_(faA2_9R}l^jmivlvV6fbm;lN*xPw zT|W;M*U#m?0uGFIQu-sQU4h)w2G8`Bz_hmRR zSnkVkV6fbm;lN^lRs^Gii zzx3X<3V$v4WjHV%EB9qMFj(%(aA2_9m*K#iuP8Pg7%cZ?I51f5%Wz<@+?V0NV7adt z2L{W1mE*u*xvwG|7%cY{;lN$5Y;=?6BkK0Bj|en9Rk!h!i?+mDKHV6fa* z5e^KN`zptQ!E#?Q4h)w2G8`Bz_hmRRSnkVkV6fbm;lNN*gPQS5<^|#9^`VF}+!-28B+?V0NV7V{Dfx&WLh697;z6=Kj%Y7LR43_&c z92hM3WjHWc?kmQD!E#?Q4h)w2>WBk_<-Q^u7%cY{;lN-WJ4AS|^SbOYse&ifd})%7 z9U>gq+4btqllzKrV1JxwWpZB;4y<=s{W7_)#W=8|k9@d5?kmQDyoSq<-TGZSnb`<%gTMlIIxC~zn78wD#wA_f>=ggXO-;abU3ASBwLL<-TGZ z7%cZ?I51f5%Wz<@+?V0NV7V{Dfx&WLh697;z6=Kj%Y7LR43_&c92l%~7t87QHnGlK ztfJqO`!XCD>&tx^4h)w2G8`Bz_hmRRSnkVkV6fbm;lN)hQc`c=6v!-27m+?V0NV7V{Dfx&WLh697;z6=Kj%Y7LR43_&c92hM3WjHWc z?#pmsu-sRS1B2zhVjLJO_f?JqgXO-8aA2^mos{SF!<$&wPKqk}VY#m&92o1%eU;L}?&AN6Q5a- z^Ku**%jLde92hM37308Qxvv-p2FraJ4h)w2G8`Bz_hmRRSnkVkV6fbm;lNGOzz8YU{?>nwW-{f;lS8Vxi7QtS|Rfjst_`zG560EcX@Tz+kyA!-2taUxovN z<-QCD2FraJ4h)w2G8`Bz_hmRRSnkVkV6fbm;lN&tx=;lNGhM%IK6)2%jLcd2gdqx zUxovN<-QCD2FraJ4h)w2G8`Bz_hmRRSnkVkV6fbm;lN&tybI51f5s~iUg%YDT-Fj(#@#(}|dUxovN z<-QCD2FrcvZ&~tLD)(hLFqX@G84e7V`!XCDEcazNFj(%(aA0tH{ctl*uOIqyxi7QdA{-bj_Z8v5V7aey92hM37308Q zxi7xz6=Kj%Y7LR43_&c92hM3WjHWc?#pmsu-up7z~I!MMmG;>u!#%q z`M#Rm7ydMwH0so>+?V0NcJ5n;?|&H%?2gxO&&Yil4(x(9d-DA+!-4&F&trW5%Wz_d|1um{`yFS@llw9p*xKRK=gED=IIz(#_P$r{E5?DbJ#t?~I51f5D{==Wy!DS2 z5e|&Sa$f-l2B-ddGfw@rFPHlYI55_i`-*U2u-sRK1B2zhA{-bj_f@X%e>uy2#W=91 zpXqa-+?V0N`uE~VB0>iq9pA% z?D9Q3%&g$YFFIys+Hd&!a$f-l#$)Ba0uBt8`-*U2u-sRK1B2zhI^w`!xvv-p2FraJ z4h)w2G8`Bz_hmRRSnkVkV6fbm;lNwm1+AnR!X}{#l<-P(AjP>Qd0uBt8`-*U2u-sRK1B2zhif~}C+*gbPgXO*q z2L{W184e7V`!XCDEcazNFj(%(aA2_9m*K!*xi7k`fw~G>hi(Ab(SmDallbLJ>0jtFxD(%=45v zQ)I|2GWFiqwb$ysbY6eQL(jwWo<5&GzV7aQ@3q&y_x|m@uC?y%p@G5Qv@Z`03~bt$ zhXw{V?aM<01Dp2cp@D%-`|{Ahz@~kr(7?c^eHB6j1Dp1hKm!At_LV>b1Dp2cpn-u+ z`*P60z@~jUXkg$lXSE22`Kz>>_T`{~!QZqm2Mr8t+Lx`F%5uZBuLK$x?52Gs(7?c^ zeWlRAz@~kr(7?c^eR*hLVAH-lG%&DfUmhA5*t9PX4Ge7Bmxl%hHtowp0|STo!?Y`h z`NQ-v?aM<0gTHBC9vT?fv@Z`03~bt${T5~8B&L0NXkf6L_LV{d1Dp1hLIVSv_O%om z7}&J01R5CFw66pj7}&Hg2Mr8t+Lwa{1~%=>K?4Ja`P;NBhxyy|G40Di1B1V5Uk(}= z*t9PP4Ge7BmxBfdHtj2c1_n0ms}LF(*tD+{8W`BLuM`>>*t9PX4Ge7Bmxl%hHtowp z0|T4(<)MLrP5biDz`$YtJnhODJA?)XAJe`(G%&DfUmhA5*t9PX4Ge7Bmxl%hHtowp z0|T4(l|lmpoA#AL0|T4(m9zCj zzd*ZkSie9Y)4m)uF!-DH<)DFqP5W}tz`&+`IcQ*D)4mdDU|`d}@}Yr&P5Vlrfq_l? zN}+*)P5biDz`&+`d1zo@)4n`3FtBM~9vT?fv@Z`03>?;v(5@WTkI=`oFAoh2{-%9- zXkcK|zC1KAuxVc&8W`BLFAoh2Y}!`}4Ge7BS0OYouxVcjG%&DfUkNlYuxVco8W`BL zF9!__Y}%KD1_n0m%RvJJhxI!}IIQ2H-Lx+U4GjLKeK}}gVAH-FG%&DfUyd4>p=nLjwbw_T{00fld4J(7?c^eR*hLVAH-lG%&Df zUsy9$gv0tN+D-fN@0tb%f78A^G%&DfUmhA5*t9PX4Ge7Bmxl%hHtj2g1_n0mt2Hz* zuxVcjG%&DfUkNlYuxVco8W`BLF9!__Y}%KD1_n0m%RvJJhxKbkIILfz-Lx+U4GjLK zeK}}gVAH-FG%&DfUk(}=*t9PP4Ge7BR{{+TY}(gSXkcK|zEWslVAH-lH84ZdzC1KA zm`(fg(7?c^eR*hLVAH-lG%#>jKUjpr`a#-F`|{Ah;BVTOhXw{V?aM<01Dp2cp@D%- z`|{Ahz@~kr(7?c^edVBmfld2Lpn-u+`*P60z@~jUXkcK|z8o|#uxVco8W`BLF9!__ z4DA{k*v1^zZ}R#z?aM&}gO6!n4jLHPv@Zt@3~bt$g9ZjR?aM&}1Dp1hKm!At_LYMM z1~%<0g$4#T?JI=_1~%=>Ljwbw_GM#kyOB-%^3cFwH|@(q0|R6305q@zAH26gMadS`%0jJozrJYUDLiCG_dBA&ZukJmxBiO?d1>W znfB$Nf!%%o0d-9Ka?rrgX4AeLG%zscZb0|im@#()8W`-ReK}}gVAH-FG%&DfUk)1B zH~9s%P5W}tz$Tp3HqW##2Mz3@vv#X%+E)S%?9~+y)iv!afd)2V_^I_w`znM6*74jG z4NUt=p@D62&C&*@eR*hLr*1W}foWeJ8rZr4&(t^V%R>X}(D}oBDuH5YSd zpnIV`%3=LD+lktT(7@n>+K14Av7>BY9B%a15dEphtR;l zrhO&Qz`&?|2n`I3+K14Av7>BY9B%a17q$UG_Z|1 z)UQZjN9{vsU|`d}95gU6Y9B%a1EcmKG%zq~A3_5IqxK;*FfeK#LIVS%_8~MdFlrw{ z0|TS>Av7>BY9B%a1EcmKG%zq~A3_5IhngWpIMffJ9kmakfx#cO521m9QTq@Y7#Ot= zp@D%>`w$u!7_|?ffq_x`5E>X5wGW|zfld2z(7?c`eFzNpqxK;*F!-4E<)MLrQTq@Y7#Ot=p@D%>`w$u!7_|?ffq_x`5E>X5wGW|zfl>Pq z8WPq8W`w$u!*tD-4G%zq~A3_5IqxK;*FfeK#LIVS% z_8~MdaHyG9ghTx_+EM!u8W{Xh`w$u!7_|?ffq_x`5E>X5wGW|zfl>Pq8W`w$u!*t9PP4GfIhhtR;lsC@_x3><3K6=BmaP`{4$D{{RYG%)z1 z_8~MdFlrw{0|TS>Av7>BY9B%a1EcmKG%zq~A3_5IqxK;*FfeK#LIVS%_8~MdFlrw{ z0|TS>Av7>BY9B%a1BaS{ML5(Cq#d;np@G34wGW|zfl>Pq8W`w$u!7_|?ffq_x`5E>ZRv@Zt@42;@`(7?c`eFzN`w$u! z7_|?ffq_x`5E>X5wGW|zfld2z(7?c`eFzNX5wGW|zfl>Pq8WX5wGW|zfl>Pq8W`w$u!*t9PP4GfIhhtR;l zrhPeRU|`ffga!sS?aM&}1EcmKG%zsME<^X)n6Y*l8W`-TeFzN`w$u!7;E>Tfo;rKyAKTvcGNzE z1_nm$Lug=N)INj;21e~eXkcK}K7`w$u!7_|?ffq_x`5E>X5 zwGW|zfl>Pq8WZRv@Zt@42;@`(7?c`eFzNX5wGW|zfl>Pq8W`w$u!7_|?ffq_l?N}z#(QTq@Y7#Ot=p@D%>I|sVg#%yCJ z_K?4J$_8~MdFlrw{0|TS>Av7>B zY9B%a1KZeP0^Mt4M(smrV6db1Av7>BY9B%a1EcmKG%zq~A3_5IqxK;*FfeK#LIVS% z_8~Md+9wt`XkcK}K7b1EcmKG%zq~A3_5IoA%|Pfq_x`5E>ZRv@Zt@3~bt$g9Zjh?L%l_VAMW@1_n0m z%RvJJqxK;*FtBM~2{bUUXLU}UR(DCAv7>BY9B%a1EcmKG%zq~A3_5IqxK;*FfeK#LIVS%_8~MdFlrw{ z0|TRW9W=0w8MW)6fx(X2htR;lsC@_x3~bt$g9Zj>?L*VRz^Hu)4GfIhhtR;lsC@_x z42;@`(7?c`eFzNAv7>BY9B%a1EcmKG%zq~A3_5IqxK;*FfeK#LIVS%_8~MdFlrw{0|T4( z<)DFqQTq@Y7#Ot=p@D%z`-^aBKkcY}2n`JWsC@_x42;@`(7?c`eFzNiQ8O{+K14<+Kekb2el8OfsMF*#T?W=ga&qhgEBXw_8~N| zyY6mL7qt(efqnb%m32}35E|I&Kb%q*wGW|z?J@8EJk&mf23E8E0d-LO5E|I9e~qb$ z+K14G_bty-@P8S521mfou+*y(7?b=n@pW!cS5%R#b=u&-FBWp zZoA9v$(_@Nka!*y_-7Dg@3Ro;NVXVaUAR+J~`}{Z2yGzkg*^13;eMk^cQ&2 z#DzD;^Hp;0{<-IF?j_~t%(%NjGU)UP?vR~!%CCP)#$UWTGr!W+^=WTg?}PlZxq9Rl zuU5!&fP{nqGgrj*iqMzuOC%CY0>Bc@(V3@Nh-cP zf?PO!*QD)vN0ApatdksjVIy+)IpX`j#B}JPA38b3qR0h#bxx zIh<2+IM?Km1LTk!e@^0%Lws`BZ<57fd&t-i`UUpTezKjf zcyIA?Tt4`x=I`aWyd0O8SG1am74Ddtx4MKx z<2*+HLa^jvj8A*mZwjB#9&%_WIkcZ_*V=~jrCf3zc|ZBboX3)Pgn#Zkg1+nNJD|QB z+AHCPcSe1e)OSpM_tbY%eOJXh?4rBguy^JS@34Hg)puTf7uI)VeRmG+@rV=JNe=BN zKmJ%J8w1$zZjLdB=#Mc6vTeTM9pB<(%z<|MFUB0m;a!=GcV&4u$CyKWH{W>7A-lf!<=p*>{V&xWxP+s}qE6TQ}y)knA0n7S`*gSIUkBioPh0K`R`F&

~aO%$u89S1Jr3*_QrmozLr^Z-|=}R&&HK%soEUqOn z?bMsQ?#D%a{;4(uHLcR$s7ufaM!3pJ9y!))--p9oC${@-1cNjk>zIt$&!hy4TzonL4~RGa53w zl7XcQOCF|<>Ip~0Sc|bQ8JHT2Uu_ZBl9+bttB(7&nfpV1)e-$8r*_2jB^g+{F!fch zxqNY7tJHzrVXes2hpmigxQ3BW*Ryo-N4l_dQ~zOVNA_BIG5498l5>8KKBxOvW27(1 z!;*(34^y{#!uQcnYE0jIY4l%AzmkEeo&D)Ean7lK9af3D)Wz;_LuARP_ETM0y0COp z8FbYb?bHz8_<}fIYKX7gCi0C|m%P>Dk*Ohm=f`m^QA51_OOdG|zW3nB)DR#2Ok`?^ z&neoeA>QZZ*iH@cb3chp4e?u>NBh)U|FzVR@l!IebYamqmKL*cSfJ7BY*f;k*Pa>^}%s1iP4n|EL}L2p>Ft;u`$+S`jQMxP2n#F z#sh+=D_vN+aOyL)lHYqY`biDt6K{*0?qA8%m*io|!;**FztF96)$P&G(aYXiIbyl! zzZf4R1CML_NadhI&r{bmy%xr!s9=lpl1&50(BiBG0||x5}n1qYq;Ilng9gSTqm?o$-vTu zQ<;r>HqQsw#aN5!OEU1GJFJwy^;}#_V%nenX4!nX4oi3(&pmmmyyc3KQ#)e%l?*Ih z_`Dx4seHLsbKiF-%Jfx_aL7@#trx zU)Romc_4DSe>Fz>k~}PVSn}T9s8OT!9=s>-aK|}e_HuLDT=Z4s#vRYBojUVgZ$GR3 zleHiG?LOyy51LZD@gom7x7l-%((3IVcJ6uR3Z;z??&*B*5^I;bJm1H8=8GGaW*pGZ z`K|4JT^=tlAwgcV0vafB5|SaF0E zM_6%$6-Tu*50YnoV8szu9AU)~Rvcl)5mp>w#j$AjI2Q6AM_6%$6-QWcgcV0vafB5| zSaDQ4ag;o9gcV0vafB5|SaF0EM_6%m{_U=8-wzMZ*mrH7?~y&(Ci2|}JeW<|`%rKH z{<%l8$?F{CTr;Xy*7m)9WBVz6vt#bu!+GZ}k7sQ!+Sz%hHTq}QK2z)b#0pPjV=vv> z`Pb8*$hKUpb+!Hed)KSVf7E^rXY8!^;7ZQloBhSETE>}v*WIppY&Uz8pSQfY zh%^2VeW$VWY#Y}~TSV^J?v85vZvDDeyVilepXim%D%io1;~ z*LpDfd3BxKd3~<+WB%k?S2nI(>&?cMYaQCSa_u|XwQiBudd80SosBEkzN265JN(hU z!%yuy{7?2>u6<{5thQTxtMaxEt9EQXRPEb3srGB@r|OTb!>XUQ4y*p#I;@V1c8wQ# z%>#BcKiJp2(XZwce>Bhdsrko$#U+iGIE`ZwUzdj!M_6%$6-RF`;s`5_u;K_SjP%cVCz{=!x19O}}+sW%Uh9M}0lhx!dTD zr3c=g=sf7>he}7a%bod`|3;VpA2}F3^kM8_7p5QjOWNxa`3hXvaW3pT7yUXH{x}zY zIv4&sU)grAb*(?O*O?!Zub6+%W~XBPIh*~8_2buRpIrXS5e{U|Q$Q@EHzXT^^8 zV$NfG5j)xyyJ#oIE@`iWi&$6S!j7|IM|;t)w-^367k)Y`cE~Gsa4~ktd+ca0=E~cP zIdoR+kSXRow#QgFD|XRNj2&FG*TRZjVyEQoMeJb34p!`7#ST{N;51&5J7!U4mWJk5jocWjkMwkB|IT$_kVeHKtw6U}KmeF6*UP(J?z5tLw`xT&qE=f(_YwdF6=uO{W=%^I2V387ydina`tBHS$}G;m>-hQ ztv_e8lUskzWyN|b!&k{S%g?;CuU+2Of zXZm4Y(4`;6C5@Mud-G!Kes5dMiE}Ym&cz%$7jx^Z*kOl0(T5c~Sg}jmD~Ws#D|T>U z-`k6RoeO`Q3qPF;|D6>(>=a{{yvL6AVy?Wsm_uj9uJFfW2P<~4Vi)bi*d^_yL_ULA zBlry~cCcax7yh`6Vn@4T2dD9Z`7NWp_|0+FZzk>f&4l%v3F|i#)^Db_7k}?y{bs`Y z%}m-ocExY3vwkz(PVt)w>o+sniNBe!elubHX2SZ-EZY6=T_NwknQ-wNmBYnvm$QB| zY1eNi%->0V%V7Ox!urij+C6rKyt95Y-A?hF3F|jA+VQ`?nt%Ls)^8>|n*t+l$!2iXE)jCGCDMq}b7}*ujN;|NEiX(O&rD?S-GtiXAfiFP%s6 zpRvn4rvL7-<8M##cks{a6T2SJ-?-$uB8T-i4%Xi|`2Y6x3GeCX_s{n`xzEFY!uuWK zWzWIF;{A@VpW^)vY|qpDeT29F`Ch<(m;N{23o!qBF984fJb4+9#lPqCkXK50(w7dzw_1e680XjdX7Tp5Rlh71ekWc*G69NwXvi3+Su27ZTi)FZT!)D zZT!@GZTwH(YybcCJjtKu5aK%gk2r^*XC170U2nj;-hg$z0qc4L*7XLg>kV)J^SR>x z_;W?xsVQEt;sq;Su;K+PUa;cj?M1v`T_3`_K1|yEy`ioTY1j23tm{Kq*N3pK4`E#& z!n!_$b$wX0`}JWV@7IU0+4&EB?-}1O7w_o(UFx4_3?A~e^zVAcfU_lv7p!=}wlC~l z!Jp@OiZdSntLJ$}EVX)m!1IglX#bY)-0+nAuqKgj8+CWyZ@DJkzUwzb^JPD*asDzq zmtVQ;BF^1TdLmzb^~jqn-#hO-FUp*=$b)&`JaYNeyYt-+i+s}Q-SVAYZS1<+ZF6(p zzE$MiZ@wTbqSH_>l51f{F-uDmZ4(A`5w|nk)=ii^-Isf&FDraJo z$s}XCnRLx&CY#n*roPOFOg`8cvt*1}GR76wVVhg;7q+?eeqozi?-#bY^?qTE3zmK6Q}$umhh-m@eOUHk z*@tBxwpdi>UrfLMomj|zY6n(KVZ{_yOyT*~hOd*NeSv;jU)6OeE^PjH)?~F`t!->- zZNpmIu+}!Ly#{Nq!P;xE_8P3c25Yau+G}t+E-|rFU$FXu)fcS3VD$y7FIauSr;dFz z@AJ+#zE9t6{9ry|uWy|}Rt7)AC)iB^pJWfAqRG`*Q1ObA?6!ntiq6 z&u;(ii6>@F9*w;BCI@C6$5%NQn@lbl)6J!8HgnmuzH;?tcB;B!;_}bhN#{zO+JWT{ zEPr761J5@uA7jzJKtHXo>Kuv-oBy5ptoEz8U{i5{6&F}>fwfLxtpV89n6ClY)|jsW zIQ3avtkvpzlO5V+2bP_5Z5RFe+AjL_wO#bkiPZqdnd zZ@rPv=r_9ze;H=wXO3*-?X$0F9QwTfhqu4V{V$651JQww+CnB=e_@}xBs~BjC`r#-#ODh z;L-1^@@HJ}gEMyS-up*q?9XZPlQaE}?Hd_?cH8i0Z^zFLog?G_UN1yuTx(2OzYFuZCPyVxvceU>%6RWZtK6S^>6#4 ztbJkorL6s8`>3paWc#bE{bl>EtbJ#Dv#k9HYoFTwEo=YUzAkHD+kP)=zuWIXS-%7J z`%u>JgZ*xl^}Au~D${eu#fCV%XAAd{cA-!u7dzXO@ZMZ3m}yygKrnjh?I-so5Ji9ecW{M7v8zv43g z+Gd>>`=z?hkzvi#{%3sSZ{~kWeA9T-T0&xqfffl{p!5dv-jphTm4pTKVq@DRr%#ViHx1L z1Aq5+?DshP4`=%Q>yq=F@n=rA$oRS3*OBr6vK1To-*?7!@|uw+J^W0yeaw=Bs`8iZ zKBQ{r{mq9}?e8_HQtfx!5UT#XSRRqf&pj-kiu}Ll(vj71(XR0#uX(_Z<_G(lH~Q6l z;*aJTKQ;gOuehY~67SujrmWb(iXE)j!HONM*ujb&tk}Vd9jw@?ov}-vIe`^BSh0f@ zJ6N%U6+2k5gB3eiv4a&mSh0f@J6N%U6+2k5gB3eiu~R#-lRUA56+2k5gB3eiv4a&m zSh0iCc+G#G67N}R%Kta-mFoMdDc9da)s*Y+t!m2k_gppQ`g<{38`XQXnsWWUTTQwC zp01``f3Ii1)ychBJ;(O+e(nD~5BB?6y_Zb6Q-is(xy|%DW^-PaW`W?f5^>@tr)$bVo=ywc1 z^*e_D$?sUE-!a=G)ppxERe9S}RXeuVs`hOUR{OQRS@p;Ec-2qa<5mA{k5|V|n(XR_tKK4p!`7#ST{NV8u@D`W;j3 zXjklD#ST{NV8sqr>|n(XPUBVoe5s~f|D2?zT>t!}rdhHgUFR(Ei?#c4L2UTgc>+G2L9c_0NIb&*C|-`&m2( zc0Y^f!0u=99N7IVo&&p|#dBcyvv>|1S-)NN&w>57w0I8ezoo@l)nrdf&w*>oKMa06Uv591 z&DNBA4%sL_c4MBk)|4+9zHV>cD;4dT+D$%_eEsvl^mo|%EuQ;%zs2*w^lw@EJO4lb zwYvrvZ)5dY&A-R} zzWpBhJw9v9{*L>-By4}*{T>sxzx#gg3ETC6-;=_2o#6MXuw6g+JuGa$8-8yK|9PMI zuf0#Kzu)Q9;NGYH?{6pmzAx~-TfNM}|1RsyK=B^m-}|TUMBpzjADMl;$yffoWw*aS zn{~haYiGSH;r(xYU!BSedp}q&^Dn&)slL}Xf2wBy7WR%?GK@=S4`3Ttu5sCTbB$Lr z%+G)2?2V1F>Q6nV*JhoPYcr2s^&Nfvd;Eo8ztz9@Pi>~xfxb?v=K<>F{T{h`t!Ve% zLHFAA*QlMi-~X4NRjBXFulI^`5&tvS!}Jy3^ESK=uW#?f^M~r#=Wmy8{XIe_?q&WZ zXGQ95{_E~L(sPXe?72$zuik;yojNAltX+*iFTL`ak=a(=BTI%oUVnersl2fB1NAch zwfnVt`P6>ANBCF2ueVqiX8?Tui}(2dz57$$Z}R)_UpXf%dHz<~J?#JI{b~K0iD#U2 zHe+FDocMiHOm&Wt-#3eCu9#Y^bH!S}Z~v#?!1Om$XBUyz*+p1q7hyX~Rz2UfpmTl5 z{4?kA3Y&h`4*s7$7sr~{8G!%O-#*Rr!uF2#CO+$oF|0Gju+A96I%5p$j4`Y;#;~1J z^|RUVg3cAw{?D8TE^PW)U-;kQT<*fwYPz;{UyskauZMMC59_`j)^kEw&k12YCxrE! z5Y}@-SkDR7{^v7Zo6mp#8SkI(7HuurI{c4#x2V5U{9P0CH_N#CjfR-^Gd^w{mU-fh zTHB+g(fw*dyOtAc?|b(3(%mO45>DRWz1j~R8DH9G-6mo7SJP`xed^WHUq5dW{&@GB z+Pa}*OIh8bq4i5OrM*vlv9wj!rs3wE%ak5kZA9s+*3H6W6W1)=yYkRd_kPVn`#rWU z9r*pzrL8A53tvC7bLk$-soHdAvtYG8N>{Jbv$WETX5q%Jhm?9<@JMO@kDG-n7d@i1 z-^hnbPk+!XG{5}l(uk!VOu3TCR1)1vVzctMkGll= zSGtaF8p8G~mc}#+l@Ate8cv+sv^4O_7b?y6STsDh*)O&4uQ{eNu}hQi;P10)@9Z$H zvd*YQ!mvZ8*0y}(waNj%*Mx7be5dw{yR#A-LjLQz1F{E(e>QCHbrbT>M?IBovDN9r zrav$tAJylnto`@P4Qp zwd>7zGoL;5>1@&!XVvx_`9}WKiqB?`?S6OdQfI%O-~HHgS-U--tu6iVT0ZN@LD|J^ zU#?xX`?$Pqiy_&KHPdVRH65Feet&3o(bqrL{&Cbx`GjGW?6|>=OLOmfA%F6L;o0Op zo0MK2H8Ovrb?3rqL@7yKvILyzyz{ zvx6^wdD!Cz4$Aw?eJwk2-kNp0{Wi#+pS+fx`_7Sd%f0n{zV;KZW)F3~v2KI$gY%tU z8J8Wo)x&k$d^RLM{+J z9r#k#{PNj#%ikaJuWtKCw&|E(>V~{MB46Re(b@O^Xk1yfi8u!hM-hS&LHKjM|#yIaZzqi@$p~!qMp0p23EKY`wO?%9scDY=P!F5T9+*zx#PEu>;7`jKyTmUz0HOt+$NE!O>}D$o3%+_wTTb4 ziEp)u&$Y=|*zXx}Tw>C?rOA)JCU!~tutdHtu~V1W zuS@!^OZ=%MepV9yiCy8(x|Jr^k8rkeRoX3^JKMM_e@q^Wx}S6!I!jI)iaZktb^cD8X1>w0fw#+9_UN#tu2JGF`Z+N9sw#Gg{)XDRW& zLA)3vf1`+9%FF}piX*Hz!ipoTIKqk}tT@7oBdj>Wieu64aV+FLjxh5^9AV~@IKs>` zafF$F;s_I$#D9+??KVb_Bdj<|o_T{6M_6%$6-QWcgcV0vafB7eqTS7KNXJnf_d{?$@uXc48T|FZ^X7RhSKVE%z z*!z8FWG%*b&sJ$Zb!hqF8QF}<-LpoYAJ%5cGiGEfwZ1EBHG0w7O`FZgn!IpVHl^1g zwd1e&B-`fRyR)gAcB{ST_37Ci58soW7zWmUUHLfMKkJc=oHw<$#UUSMe>?F0tXtN! zbp58&vh`1YD4TG|+NDkYHYNLGqn=rl38m62*T0)xe8FScQQIF?`myhXZ2ullWlPSw zu(ZypQ|Ju2<$4~aRC>xRWZhv#>hdFt6;npu^pS12= zx@5wTZ0@vIvYpPlwzTQQXR|SDzLE7_`>fIhEe2#K?LHxU;;h3;FE7_WTjkPsvNs>z zuC#fR$FdLKeK-4jla)&SUh19oyyd-Yt-ZgfJ*-8qY^#ayXNzszr*@Iqk7nH;o03i2 zZOhvJ*FKt^`@@v%`jeMyGw|U@v)YfQWLtC`GVH`nduDAeo05HV%TaX)Z`dnqH1hrI z)9L-|e(usc%Z9#}b$M=j-BEk?&DK19a(3TSEh+;JeLU+maZ>hl+g6p?kMz%`F7{4# zbToj09#Na@f!KX9J?@s_2$*+z&{E@S4(`^*cHDDqUB)?c1xIo4;{g>55A)o1ZI*OeN8+BsMEaUzNm% zO5$53@wt+WrE>P--lzBbmoqQTR_HasdC5C2&fZ?ZuNz7|ZvAW4@}T#;eTR$A%Z8Re zaDMspGqZ1AnC5)*ZKq^wzwwcCqm_=&jyZU`^Hp0Mk$tk`C(hJ*y!p1s6Mx*Z+J5k| zyHw@J^e9#B+%jU@s{NLOwy5@7cYo`uKfB$tQPt0F!Uk3UKV4%3`t*KjZ+pY5&d6W6 z+*oJqw0Y-6XYAiUYqT@{o^X&(zKg_@UBrftljaR~zBzBb~c9kS{l_YkRBzBb~c9kS{l_YkRBzBb~ zc9kS{l_YkRBzBb~c9kS{l_YkRBzBb~cHUl$-Q|lpaXZCax&2}ez29PP-JfF4-OnNx z?tc*@A6F4OAFtYz*!ld(P7*txPxYI`&gWl#Cb3KR8e`0p^_gqm*_`CscQ#kK_MOdP zu6<{7n`__Moafqi7K>c_&SI1&`!3hMvzS)fZH!fUTLV=)HpZ%bTQk*uZH!faY>id@ zv@urww>4QE7wuZN$ZI`gN9!E>TL1K`eStsPFZii_g#X%KwkC7!JI1Sa=0WnzkL)mS zvd?^~U*=i2z?NazV2 zq=k~R*P(Yp5l|p>r8kupI(I&^_xEIY@8y55_b=Sw`}29uSij%x3 z{+O@8WyoC_a#x1jl_7U!$eoP=yDO=3SBBh`A$L|2c5;VYxkF#M!;W%?edP|n${q12 zcf_gO5x;WBm{jguuKh0L&h6BF<@PoHL+(5t&6kink6-gE$hez%cl9t@?|k(#bB{z#bz`Hep>{aMetRG7>W>E5n?W^U1|%g zHlm}p^IP=^Hq}@7QXdk7`j*(#=S9c`XT9#{5#7%tzV3NM_Z?dI9ooO-4sFIQho^V; zzny)ed~liJ>F%{3aK5%ZEFJpJW6qcL9hOesd)o*vvfIMIREG6({HWo9CXT{QwAOE6tWYzG+#-6O}~&$vs1`d z(7~p3@Fksc!>vvx7JptJnCH&?TS6`m>~~qn*?YrtneOLG)+f|T;d#(h@m$Grn(I80 zYjF|Y8Hn!~_`Zxj&ws=7#DBMEquvkJ#(%5l+V~Ew^XS(qhq#wQI&xVUHjygOI-?O@3op|6fsmC54 zxXuah{-IcPg&wR6{w$66ePEN9lAC^(zS+sLWA?M`o8K(I7Ee|@7H3wR7JpX!;eD9m z>)vk(+4tXc{>kKH^W@!ncwhZv=VS7n zE6(UV=PXBOd$-B?@$Vg#cRFGj=ktdR&$ski-P!g68%tdsuJ;=Di(KzD>?66}YYN+I za=q6S^Za6u{LGoldf)E8->>s?!{>GW{^bMnyj%8he(C02^I2Cc?>zjsJLO-`v$AvZ zifwbxyH|CdFm#LDXKa7xWf$Be-*G|1d7rWC=Y4Lj__>wW%4>X3>74#)k8eef2YdMDx=Gj4%pRsy_HWcCyn33`Spp% zmka-XFXxkgbaXl9{r#MK9Wkt&F!lgvd&W`f8HYXBDD~{ao@*qK{c&1aF^Yl86Pv0Er@ff$n;hD%c z{(Q&!q)?w&Ulr;r>%&5QXnk9#Z>L*jbfG@CTolShs5hu{{wU}Ga`Y}lAd z8Z$PQlE#vav7|9(V=rm!*_ccklQve9#;T3sq%mw`J85j&m`@t>HW!lSg3XbnIbw4s zY3|sZN}5wP2b1Ptr~?a|gGqDH=4R5|{6DD)sSmX#*jkaaR@fSnw1(K)V)qKw+G1-? z(wbvyQPNsuYgE!2WouW`+GT56(wY`(Hum&R&1UcZHS2c;Su>mUyMje{rc>A*Z0C7a zc&5|+JZ>s_9v7Yk6yaGw5uODU;aNZto&^-)SwIn<1r*^~KoOn=*dEq-7Epv|0Y!Kg zP=sdzMR*oagl7SaA3d8W!m|Lzo1SGb4ztw`zD|Z`0j{rm+VCvE?dx7QJPYu6bPpV! z1$g|rHxADNyuFf#X93NyfV~&WvB_uP%D<9hAgelQEgd$H79dQwP+b?MdqMtMdqezMdtYb_UxpVV)*01=tUsz1S(j8pvRRG~Vy=_a?eGC_}Bt-pQuL4JXSoKf57mamq@pW}?te*o%eeQEQcdBvk4jk`% zzOs+Ux*~AY$Cvi~uiWv5c)qr_k7t3vUwelf&jNvqP@fl}ZZASTUxYfp2=#vv&ILs{ zFBIV%QH1kFiDL z4#vOg*vQ{_O&e?Sz>ERay^Iaj!;Bf#$&4k{&x|qE)r>vW+l)!o;fz()=U=&74)uHy z>iiYz)>gswj=+x@3<7hxA{yqJQMlG&(Se2!S7dc7tY;9 zIFA?MoL+?UdlAm{ML6#l;U1s}_XE7M!8@wOzw_VCg})R0xBQz&y-!6RdB-{Y-L(Im zK60KLguk=)ztcy~JJkGrJ?!tE+u!NKymQUpYJllSf2oH%My!PxHo`UTQ2obYgk^JAInV4*y4E%meq8AC8)) zxpC2>n19&a<$4SBZQeU#+T!$kZ!g#Sec$GaLuM^b8Gmy*?f3dMub6Xz;@VekDwi7G zuldrW%M_pYxVD`3-hRzjKP-x0K6+Vs?@RrfpRW0nVx!-UEyH{7k&6#lUDoJEMU z2yqr6&LYHFggA>3XA$BoLYzg2^Z)4Cba;OK|8)wf~+{ zd@t+U{I{OM{q1-D-L_e5zIScBOfjL~O~v(x^lct@_z#Ou$KPCxJ#m_5*H%jxkN)1l7c{u}r7YR>lMYp%cFhdrB5 zAN#87|MZ7Fn{zJoit9IRjk`aP zSnJhZ&6}^EEj{z;HN_7G+kfj~o!Jtxt^0D%=9#C?nuu+oK0TZ3pD{}!wu4u;_W`e- zIT722lfFocKQdDywkyhyQ}f50xc+0)eU!F&Xk*tOGVsInyJI(U{artMKb^YShOWQD z>K~?Se*X)P?dTQWO>g#HKM~K!7e7cdt?>(wbK3PjNSj`|kH_|h;qRx$yL)?V<9_yD zdUVoW?(3oQAE~jyf4Z;VulDzJ$KwOs*P6GzlP=kBPxrNbub0zd7mRfMeSZ7bw9e%t zTz|Iz_)FUM-VH1Bii;;oPK*uMDS*|gRQ=Xh+_ z?)7Xs;lZ;#whzl^(*9eX?Xhh={^@kw>1VmGV^*D%7CCy1`}+K;CsVJHqutk1M?aB< zpLM4D+Vzh6(%I$$d-LA6q#LHc-D7*{Z#SpqM&0JIy|d%ZY1xl&_1I23xSg(>?N;}- z{Bk)xaM#W5>$aX{TIJNX`x^D^g!JVvvillv*ClEAz(-yGh4U^>SI_cC*WcyTi_$~4 zJ?#2(kGe1|Kky;fzx>LvY1kqYJ+`}d8UZkz)7t--%TYWkaY3-Z@B)c>kUqOJp7vLpK;irblx7Xy8iyt9g%*1+e;qX-=5erH6EYr zu{|+(&-D30lRdWG{=P^0?Nc9mY{##@M|xqN4?VU;m)kwP|L*(lYrczjOF!S(#-GiF zwb$4+U32F@+}E%E^3(LUjsNbx*8A%U>DFVvaQ#)UTt1!h$Y-v9)~Fw+vx`q%zdU@o zH0yOAyZ)X7mrVno{?KFVJMRqX+1G8JTTZulX?pv2NP0J!v+Eo`ecFA`-c9D|fCZ*c zFMQss$vj>Ckm=Gdf7YwXJYD^m|40WM*|SM(|G0eG)aU9RP3Gxjdhn3z ziywT_$Mx4;eSC4@?0sB+#QfJ4bFJCi^{<}h+M?G1_TRCwdHvxRR~4^**rUnZyyuEk zto3m}k8R?BRLpyKKacI%w~ONP{rh=rYwlDOJ^S|a*bYCeQQW*|-^$l&{fmbVo5p>e zI`eA9=NI;IU!VVNm7@G}Z}&x=`r^x#zWrU{xY<6d^!XdZ0~VXc_2GTC>C@5w<72%P zTNz?2Lu_S;tqif1A+|EaR)*M0#b*6hhJGtUzm=ii%Fu76`pt5hLr!zZX%0EfA*VUy zG>4q#kkhQ3+IY)hyyY<7au{zpjJK@uW^*BjxsbzL$YCzzFc)%|3pvb%9OgpST(EhX z!#vGlp5`!5bC{=D^VHUm9M+H=){q?5kQ~;K9M+H=){q?5kgPSt*0&tiw;a~D9M-oS z*0-$n&DP!=*4`Y}-W=B69M;|(*4`Y}-W=B6thLwng&g*U9QK7A_Jthwg{*zS_OGn{ z%l51s_N*NCtQ_{N9QLdn_N*NCtgJoD_R}2p(;W8G9QMX58D#A=VM+QaIlcBq%ys+X)rYKI!B z9crX@sFB*CMrwx|DXT`Z`mG)6w|1!C+M#}HtA4XOEvrtudt$%#)4T3iurK`K%zo|b zX56u0U)Xt_e(jfr>`<^T{OPH_?G>Kd-fPQyR_ohd`On*Vt++_nH0}9z+tzEvGY;+3 zo-pk;UMr5iym$MVax1SDCm-FnJ>P5#y8iv=Ow<1P7xTORZTI$RZ`E^t*Wd8t-tAs9 z%;);~kY4Ss^}gpdWH@`4;p{n8oRPzsh4(=8Hzwct_gKPt?OXk~YQvfLYyTbH@OR(e z$-lv$b;<Yvqd5_G=!q;xfe*f4!;vdEXw* z#pZgcm|^pW%k@|9*}QwLSBm3~npnQPx&61|mU_+YJU)Bx<`zf2?smdCt{k^opXO&L zzUg)@zNSy})c<^oxm<4Bcbet_U%bT}FArR8n&!>hz0KS&dvD&ex$;}HB;pBYwDN`h zdo|x(Zni``;Y?SCb6*+GgJpi?-L&2@>nCDfeW4H1tH0PV5%cm(OiruLv2mj94~_mP z&A9GQ+*df?l}p|INm^*SP2Ja(mw%e>yK7Tw=5pgrK1<)%bmgG&9`iGQ zdLTXb-guAsl7%Ox8CJ7@^VIrzzq4{WdZk<3PB`n8cdTXq-q`cEx}9(~EW??x3}?ym z^m)dmXD>0kHa51tH1xq9`Aa@V_vq`C29KO{^-8KIk6o0yGzr;yFBK; z&Ya`2blQTCd(4XtzAU|e(c>QT?zdf*W}j^T&aB1!$_r^wACJ;yRUGrESJ1s#k9+rU%IbR>#vk9TB`@=uk!2(E2TlF^x#}pj{kfm`}gkb zzQ+1__9y=%opXQBChJBxGnPGOm_Chs%l^A4wr+$oW*N?&WjK?TZ~gk}VzHm}Y|_uS zE_iJ*-%-7qtQ$|Cab5AN(Y>3j8!ufnzUbPmkNXPe&GI*m8;X9%Oyj;9FWyizd-e60 z|Gv$Q#U0!A^_Y8)xv|*oxV|3qJ!AV98{apL+X-jM^3b)5Vu|o3*YV}|eFtB=Rbd#Cdap2lN_pWLXg`-1CpsQ>oy-`X9$^$+rg{^94`@}er43`eD;5<}$>rGbS;YA!eOPiCJe=V%8a!el9~lm!Y4_(9dP)XPr;!=Q8wj z8Tz>l{amV_ZEWN)Hgxu6Y~(ODbXH|-=nTu)(Ak#poWpp|VLazBo^u$_I=3>Oa~RJ# zjOQH2v;A9V)p)i!n8O^@nUp!0!yMEZmN}@iEpt$3Ue=8q){Pw2jU3jE9M%n;XIVFL zST}N5H*#1vvepe->vCA@bXH}p%VDk4*_O3VXI|DiorPJSb6B5qSf6uPpL1BBb2+ZBNNzPth5cJtc=dMQ2|26rF|HQ*=gVAIxDN%wZqQVIRz4AJqAm zeK3c8Fo%6GhkY<>AGEzYhrL^8TlVf8_HLbp*}HW{X7AS7nR+9KdLxH=BZqn;hk8Tj zV(N_?>Wv)gjU4KYta`(0q#SA_oq4H|a;TAXMy5v6*_m1{tCkDrYwEfj>be~2x*X~{ zotLTWa;WQasOxg5>$2)Pt3}(P7S&mpTC^Q%QJtNsliRA3tuEF1nz~fyZtCZDsGr-R zer|{QS?6f#=XR){+o67Lhx)m#`uWA1?aVuAE3eNd{;5xUw=vszeSXy0)3i@`W?Qe% zmwc*M`?bH!;`MwuN0&YC?b|*oZ|}AGYjgK$KfTUuZYP|<%M+KIrak0$v%Af3PA?ys zJWYFz?dEX%;VfSsdP?8+*}doF++997;n?=4+mGgNdebj|aeVuYBPxDk<`L~tf2(-2 z(IeY~FCODMfBNFY_TuNC<$UG}C$(RH{A}mdmpQrptN!OYFZa^P?N{$OuhQT8ly=u% z7dYQ}=qc@2<{j6OAO66F9sO7Kzt|Z&JAZPCGxlHF<+4iO{9b(W<<7*j$q83D6K8YX zE1ik|uj4DGU5`$xcbPYvtXnRMXLj{UjU8q)Fmn+*nc;u(D6ptjkL9`*B+7N`23_>~vh^<ycFS^L}v48h&RUYwsLC-3W#54b} ziivZrmntUyg%`Zke@nYQSfS#B&pNInU-6LRJNmn>e?rI3O+7|*?4NS}h>qWx79H7% zXN6%SJ8{l_%g9druRc1m(=Oy{FZ${S?5KaRuYSX?`jdFn&%~+zCw}FnJ6~0k=qSDG@{?6;k{)|IBrwXQT}u2u4Cu2uTgT&wI< zbFH#p&9%yJHP@q=ART34EqyRI~4u63m; zbFC{)nQL8X%3SM8Q|4MFujX2%U(L13PBqsm`_){l{8n?Vil>@uRh-patKzTbTGg&< zZLIj;b^X_VO&%-mN>la-YkOz!=t@)el&&;oujxut_MombWpC@U(3Pl3 zWPeJ{(3Pgt5?zU!L~;JfY7)gir6w^uom!>RulDZBPPKP;r71N}<+s|qt9YutyDLqp zovQe&y}N3c@--!Q|9*9s+SolNsaLBpqq#6Oj!CVV-FqCh%GABbP43&Pv=}q*t*kv` z59d42A3veruJ5;yukqLATQ{uoqVwdwLt3Y=a*y-NOJ3aKgAOvjgVE(TFgCCSWBd8d zXFLzar^)+EZu$-Bn;mEDn0;sL+s7H7_MJ06&4)8S&4>ScK=?Et&UL#a?;rFV!A>LC zZv?-M5Kkk-*$D9$vkiS@;ksQ#Xm1hv0Xr>p@EQ6Izb?loZLaJLX@vf7guL{R`Pz4p z1h!WPAss z%Wq(8U<=0fVRQWGJQ$xQ?=QLOH>7WNoUvo}ow08pXMEasMP=ulmichTr}=Qkr}=Ou zcR}7i=r@9$MzG%qej6d4BE(sQ_>21v`oqF?yO68B=(p;26`_BM&~Ny49emQ}x?PRX z|BaBB{xM&)anyqgPEZ?R{L@Al|FjXtKW&8Zk3Sgyv=PQXZG`bp8{s;43&C~nCPEi>&4nAP)^MR4^9gHqMU~J$6CVqUtb-N@dchdL1s_l3m!n7&)C3lL)bAb+hgAbT- zvDZnTUr^auz;h~j=m&DwKu%xc1Ew$ez{vOxMi(D2Ht+${moZ=KEwrTnJqm5yY?dDs z$F5e~1n+tBVlIDU6Z2zXR}e7t^T#`a^+nb3&G|ex%aX8M8Aa`eSE;!!3T_eJ}@%AgVE(TFgCCSV;dhZ z{|oZ|LBA2~G=lv`@LPm0`RoNek6YaG{Df@Q9d>T@KYV)U&1N~jb>bZ#Hpq1`^TRFs zIGe0x-#MFZX}@tc8>QLmkG|RVzJzVOAfF&PK4A3m0b>UrF!uSt$oLLMm*2qHzz2+N ze8BWYkoOPzjbNt{>^FknMu?{faTXzdbKY}o70(ZltG(zqkekmU^iL7`4Zp5~%;G63 zJLfm}4UCPD7n=uz&Rguu8+;r@p5}?3jeQS&#^uvIF}N}5lWI&HbNlU$fj7T>L-|f84n-?|sppT62V08Hnj16qT z*nV*0d<(<)H2DO{O}{05v*V1NpS^az^Lc$AXiVDaX6F&-UERnd|LnZah9@^J{P1<> z!?ycbbuCR-mXo4_<3u?HNNjW$Dut-WA6vpbez$#-!_Po--bSHg}!ZtK5vCwv_g(r zA$JpEPL2P!V_=T6KIqRlx$A-@Ck%UQqVpw3o;zWVvwrJi=B^7anK1pdBVGRE0Z*CE zCN96^$OT)ce*VR3{Ps`frxRvg`6eG%OT7P?>CfakKOV3{Yy5~G-h|E(1A4ahxaLgP z8Mwy&_S+-+GbaC39@cv5+^z}e{PCf;C(JU#Hm>v1^keO}m*0fW5d#Ldc6{L~*ExK~ zTP7^G`Yrt#!_QC5_S;7$p!3Iv_G?}9vzJ`wdp|yS!UmW1n1D`mp4;uW%eBxse8x3e zSIyd^g|G3GFT3fl2hZ0+Xa1e8wcqaPI^X;8x`eg^n~E6 z|9Tr;?mDyY*+1&^4>9*Y>U+1k&OQAH*>5|(`iHhh9s6x3=0@nlM)1`LZEu8J^baxH zZ##Y12zl%u+HSw?yH(_S;TQ8)3}!54o`4cE&~{u!hJ(07Cm@^B^d4jVE%vpvr4osUk z`@oz__`t~c4n~*Xz}UbRjP368viHybuk&)KJ*@7kYMc4rKJ6Q+m#8HyuZ7vS`lQ47 z^}11VY8b{+kh@O(TdP3_onP^sUjLy_%%SFSok~8Z+4_op8SO~t>-xcB=;#L~ey;;7 zzf)?$Aa@*oOJ*Y zE`*NxM9#b|kmCbJA0M)V4;cG=U}X4!(d9QVHn0U_8y|4pF3B4~zY**-f_?YFZ%yVt zVEQ1$={}ItXCE%P+E|#r4DChV+ipIwyuEobk~zszfFzx zB>OD2CFiNHJ4diD);bN-iRUT(mfFVeles5GM`xvf)tx*sV6$2iI_DSLqyII}4nq7^ z!*uNb3-81K*JrnH;trpjhQ89-v-M3pgD^jh$7VQx!m3M;%J2@yT{_|Qg+@BRwdFk% z)>-rf=K;U}c)~nuALl&#zy(`Fjy}eDvxytGj_Pr=^O7eFY~6X|aOXcQJEpbt4a1x# zJu#tmQ?H7jd*`Xv<`)b_-U@zOQ6BVL!A>jKZw0@t5Kk+_*$VNuV!LK~eZ%shm45HB zo%GfQ;e5{*>z3PmdZzQitE^cbwaysl$8YLiF1hbn&O6_?*g z#W~KmEx$nd!Q&MlvCiz}RV$q9@)JJqSFXNg#VhRpaZBoXRgIhamN0E zpP%H6-vOUjV}N+BS+-*0y!g};U5EJJUZrB%waeTU(_YEx2kFy4vO~YgKK&`b^t0lj z{}m^BQT!oat;ivFt&qD`$XzSst`&0E3b|{A+_ggPS|N9>kh@mMT`T0S6>`@Kxod^o zwLVi}9)4F+P<$#;0<}_*Cu~pUNHMQ@LY&DtC-e<&N>G+%Z0tJI1GS$2?W;7@x`= z^IExMd@6UW1IiuaQ@Lw}+%Z0tJC|$Th1|Iv&AX60_p5mqa_4bs-i6$GyEN}Y?z|tQ zA9CmYCi@|G-p`6Bx~x^bxG{t^0oQO8N5*f9ZVL zxbNl34{Yl^dEaLK;;Ge~ryIIs?zzL9&L8*vbv|$WBo(fKdGYg}E1zEISI#GHeoT4DEk`;JIsL}gMSmVDZir2%kdFPf&~MFVl1=lK z)WKhwLUM@=a!42 z&IS2Wz0?RfYJ?m$LXH|CM~#r9M#xbkiCY*u`Tm#3tzu~#r(8Vd~>osPY%pYyZ(oRxMSc`oy%@!n-;rdPH&g*npLZo8Ayu(dyR ze(mC;(m|X3C?OyC=6>lvn>#ws^6L%Kh?xgDzcbDE)6RRJ=zQGAj}^1uINJH8Ww$Ga zU2wkhT?-vD_RSB+N?uBC`la;EPL>_BpJm_tX8E;vvf{Bgv*NV)v*NdQWwp!No7Gkbe>$j|av;NHLPwVHbezyKE>;7+rT(m+iS|Jy$kc(ExMJwc@6>`xExoCx4 zv_dXgAs4NXi&n@*E99aTa?uL8XnnY3Cl|<-3-px>>?jx5S1$0YTo8|PL7d73@hca! zOSz!E$_4$PT+lzt1^uR6(4Wc${j6Nj|H?&UrJ;|MpDbLRB^Oz5M0xrTF3gP8Rku2( zT;Y_9oL?C+r0n^~#m>|I_>l61M=o)mYx#Z3yGLH?yzc=!l`HnW%=weeH!1t9RPo2B z+&tm&Gb#>e$#3%v+r1`Nd-PPdCWktwVfP6Q-9OlULPPfwcAwDDeTCg8G<1()_X!Q% zZ`gf8f8Bf7eL{cThuD2Wf8CSV*z2$R6C0ELH70GW78F8qp~h%Mj&(@ns1rEevB!JwhUsX(zo|M{fW-G+^guE+Y0Ag?qPJ!ZH04gE1Yv% z;hftF=Un<+=Uj53b1q{*_ehLk)jT{~Q7yzX7u85Si&5>wGaA)YJiAe?#WNk%U_9$l zZPp4k+gIjA9NTf+hI*+L>Zn$zuUet*YK3}?xv!e)E9b{hN3}wI)e3c2_ZhRQss3M` zG2^;TUQ|bsFV$DAP&16we*&-i7_|GpldCgoelz%OhIpDG&Sr?e`E>t7 zJzw-?XfOKe2kbP7$9!Vn*?i*H85!T9gRaHtj17z58QU>mm+w@~O>%enWd2R%uHx`B zcTDR(cZ&078$6Nzu>LX5m+v%xbE&z0?R@o5Hg57k9~s}l=<*vF8`y%ez1K-s`kIMP zlV{0I-x+IOEfNIOEfP>wJlgdi^i4y;xu0@63+x3*^h?rte(u3vJ}s zG5gN-zTjN%3(obv;9Tzu&h@_FOz!Iaj&`w+OP_t*+3aXPrCsgdSNkvVXkVsX+OLVf zUGI0a3px36dFTi1H0yR@-`U!QUuS&MW^{;$zJTeQkQerGmy@r0kMrC`uGiI)wY*+$ zOV->-D*0eXiH-l6AXY&r9}@dYv!XTk7?{WY4MhJG0~a0&Awr@d2Y>?=Nl# zAIR%{!MWZSoYCbs=+ygyGx6gCIqPS=-_b7iap|*mUlV_` z-tTA^a@I_jhkn3L6FGf}5178>Bfp`a*~eXujgS|upPsvVT`gHx>-Dx|y{*^bl6AOV zpG(%~dfhIO)$4hQZoSTz*r?b465I8DXLfvF@U|m2eP{H|PMi4aeZjfj7o6*T!MWZS zoa=qTx!xC?nRn(xa`tiQvyVID(|kCaeeJWfs~zHLhd8xg)2?>C-_b7Qo-gE~AF$J` z+l75+?9(>n_znHcKJIdS(nsi+ZPh29uX_EgxZ3YZ*7AD2Em?2tb+}~huh-|2^|@ZR zOV;grJulfq>UF+kZ>iV+l0B#1@63+x3%*Vw#|P^J`t|iv#(v5!liecYMY@qs>V3Vxd*o@R(s`!(%q*83gpLhfrO^3V_1X=0zg z#0N}Y@{!-r&+Owa#|F00!FJ5odsm&;9C6?eJ$F6VILGI+w*4ky(`>ZOmb2MzKep-eiy=3k$TN%_AJWGM zj2(Qy*yjTy<2x8#e8AYi7L09t!0ZdOk+#FM5mp;vwGmbuVYLxf8)3B(RvTe&%c|E< zk9FGEkz0Jy#|Nx7!fGR|Ho|HntTw`GBh2{3cP&rERO=^vz-Fh357_KC@d2Bx8RBW; z1G(8~;sd77-hFfs^%(6!?&A}=={uv34|L2Y_MNfM2RSmntL!Y)Ei=d8)3B(RvTe-@d2xi zFm0Uc@Nq6@Oz!&G`Obeoa?gCpsL{@A^?Na2@tcv(a~-~Ddz+qzJJ0{yt=jf+Hd))g zb2i)n#y%ey8Q;O^@*5Z%*n+W* z514k*Mslh)!fGR|Ho|HntTw`GBdj*UY9oyQalg9W=bhRpIX0}<+)$r)^rgvtt|2#l zXY+}jCi>t( ztNpI9d9D4fu=%e2u3+t{*N4JvXum61t86`4xU$pP?_7=#CdxiOU}St(+3Bp4w9EGb0^Au^clWkm36JNSUH&j&`vcQCs6fU$uO7~A-OmB(7HJ>B~!*zr7~ zLz{wM&m(fv^*qALBdk2a%A@3=A3Tr9v4anozT^WV<2#tX#0QLxkQeQDo;&6|Ib{uC zEr3}Y>iJvP{MCL}uwF8^(Xsii{jM-w_Al0l!fddwIkQ%=7a+Iw1i8;O^Cu^l`nX(_YV`d8zCQ1BzpZ-!zt6Al2mGGDzBlmu|N1_`p9|FY3xcSYoqJcFBXh6r%-#04 z`Mfpet7e~f;f}id*@4Y9?)9g(X9qD~^%=o)SJ$6qI2V-E+jYHKQis=dY)S20*S94# zJGHFst)=PeTu_E{K}pTNN%vhJ{iAaM{ibsP{i$;S{j75V{jYNYdHKp+bhxALes*AE zk9+;8?b$&+zkFW{=R3bYp%xAEi}Rr77w1IHFFzO8^NVw(=2!Q*d&>R8zwF#yKkM;) z)$^ZyE1KIKvY|_kBp`9%ib$4~g#!h4+ZM-|w<|gZHoM`8CzN z-&M~qujlLeRfhRha>rKRgO%Lx)%Rm1_kQ)gS;<`;cVspedp4d!aj(ezTWPj+ z-)MF^_l+*E@9|t8AF_iF82fx+WcYy5t?wH>PJAFIetf{;z7e_Z8`0N&BX)G(h<)8R z;#c#FcIm#6ICbAh{JL+XUAk{{dFTh-H@cnBZ@O=EzoDOX-{^6MynN-}7RM!wDG@~lnx<*vIPpPh9cxwT8{2JOsx&v zhUd9z7k5T5_a59O!Q6*%28P2p^!t-~9QwUVJr4c8r5=aeN9nmd_fg;K`%BydgmyXW zo~>?|-?P>2@_PVS_W-c&*9cS1y}={8CZ;Dg{$+FH8G1F(`N19Oyqk`2 zo_O8(^vYaEJ8!qo`RVfoM>>CY-?3@Q4Ni5w^o^a7-51c7FKbn~Q7T zIoG-OZ=P@Lu;Tg7Lw@vw^1<0E{^<*UF5ekZ>1=t;5A$+Yo#i@@Z~dQni{s94zGL3e z`MxzrIluDUDS7RmRD9g+Bl1aSRy^q4qw_vXo#Z;ZjvkWF_^{%G?mR5d{prare{0eK zdHv<8m=C&czr4V4r@6dw_}=;8p1*hA`>d<-z!i^m-nY-K`Lt~ZJC{$~pBK6B*UtCd z^>99IwcVVp-*T^4*LR-l`g`;6UvK0*(=>PIwALohBeuRX&$`y;&TCwKM?Pl9EuG(; z@6NpYLEAY0?)P`)u7TS-x97MwpR@f=&a)4BAiwzTPn|6w+m$d%Xb2wXG(l%o%w!EYpznIhE)5ofqEidV;`KNQa-Sp6 z+47Rs`FLw*%SGDy)?YYVF4Eb5-^Uv^#XUj!8sNB`ra*>W5zq7OD zA~l}c!P#<=Ca=Do^9q-pn%CLlFy|W=JSo3J^sdI+`lk)bvp!$(K>*P^F>Ft)MG^VPca<&A%A%=`MsE`R2oj~hqt`(5xczRj1;oBU+nV$%(J`n=fl;)RO4zNps5r+%qd(33 z2RLJA^8VEti~U))t=38WzIW>}wVj#MhTERtOq@UZWTZ3k&woZ$SNvgvK8p@oq^c!M zUP^BIrSz>`S$52RmVNV^<=5iLipS#2iqqPa6~DDBhjwMP7k%{ucGN%ESHIy`{YgCP zXW~@<6TkAJdhe$f&)U>p32U!}wO7L0D`D-Gu=Yw=dnK&B64t&9tG0wyTf(X>Vbzwf zYD-wPC9K*KR&5EZwuDt%!m2G{)t0boOIWoftlAP*Z3(NkgjHL@sx4h!*OstqOIWof ztlAP*Z3(NkgjHL@sx4vFmau9|ShXdr+7ec639Gh*Ra?TUEn(G`uxd+KwI!_D5>{;q ztG0wyTf(X>VbzwfYD-wPC9K*KR&5EZwuDt%!m2G{)t0boOPANRC9K*KR&5EZwuDt% z!m9UR)qAk&Jy`V~ta=Yty$7q_gH`Xrs`p^kdy-Q>NT2!vR=o$S-h)-|!K(LQ)qAk& zJy`V~ta=Yty$7q_gH`Xrs`p^kd$8&~SoI#PdQWod2kBEkz^eCP)qAk&Jy`V~ta=Yt zy$7q_tL0u-)cRg;z^eCP)qAk&Jy`V~ta=Yty$7q_lU(^yy@y=&9;|u~#xM0Ata=Yt zy$7q_gJ~D_9;|u~R=o$S-h)-|!K(LQ)qAk&Jy`V~ta?v!OENX9;|u~ zR=o$S-h)-|!K(LQ)qAk&Jy`V~ta=Yty$7q_gH`Xrs`n(PUXng_6s&p=R=o$S-h)-| z!K(LQ)qAk&y;|<|Uajx-9;|u~R=o$S-h)-|!K(LQ)qAk&J;|x}q))vEtKNfE@4>3~ zVAXrD>OENX9;|u~R=o$S-h)-|!K(LQ)qAk&Jy`V~ta=Yty(c;KlJu#gVAXrD>OENX z9!xycX|U=&SoI!!!FpA_SIfQLtM$F!gH`Xrs`p^kd$8&~SoI#PdJk5;Cpq<=^r`n? z)qAk&Jy`V~ta=Yty$7q_gSDS>|D*j5)_w;~N^XEs)SNHQcTN7*?epjByb@HX$G5#ZW z-?LTsLbjgxb5;7s))RlO3fp?(&sFPn!=J0d-{w7Ayt5UvAL+bFJm2*Ft$g8EzF^%I z!@4Vmbyp1Qt{B!`vCF^aJp|p!qoX@>Sa;^I?#yA`nZvp>hjnKT>&_h3ojI&Kb69ug zuU-Q0}<#eijZ!P9Rank=& z!!uADWB#rb@rdc?80R+tY^@$oOG^o!MKF;{G@0{^zzj4N=`EbUk`Eah=C3z9_i(n@O z`ziQMA)XZCOdN|YKe8F?y zxW#I;F*5qd(Z>#q9qhx{$1jXu;(>{WIAQvR_+k2tcER+q{f)|4xNdJDIX<|kv!NiCUnAq_F)286p#}#t=AjIk85IKEj{kUjl z$H%AIi@q~`8TtqN8GZVa4~z^Sl^q|S&e#ZfDer#f`b3-f-|yzV&iRY6hnF+Ie3|nv z9{i}>;mEU{?|x?Gd}7z}&S~P_**?xD%l4hK>1O+l&m*&u&6cy-&Xt!QJY{Bvm*KPE1h}`s@(WkFu$Lu@TZFH{N=!{SMjdR^b=emu~b-N^I zOiG_I>5NbF;f&AVH-~s~h||Yj-L6dT>UJSld(n5sC$ZM;!oD*;X&Z8UhJI#Dx*VS& zFFx1MuX5a-yYEu&y7#s3*1k6M*86?UWUfuV{2u2cA3veo=%|~W@40%qeBS9-IS;*c z5V+S8F z_W8ib_zp&w-@w?w7L09t!0c;5UIhIV?4)2n1-~i8lR}&+#NXN1=*!Sv^b;|dPwY6G zPwYFJPy9L~<2&@xWg2)x)srVOaGrOsz`I4XYl8sc)&dVQN*{4YLO0LvnmbA0IGw@BynH zhE)&4=;8xbJq%+TA29O^-?iLhs`cFmOzil8%|7P~XOsE)1-ZrJ=NFi>LWtkaFGI&w zcKp1i_M-2Me&`?UC-kw;2S$dE%8sAcoUsw|Lf^TZzJwpkf9>QBCNBKJ^a(a$`U+n# z?ZY2zGS3}MpW_dvU(J@Ya)(^GgOTGy`uKpcgAW+{d|+gJ2cwG*7#rAvl{;9utK}Y3 zt?xcy`Zd`1+#xra=MJV1LY$sEQ>ecn7Wk@T(2k2^?Kst4I9`(M{96p$ImsTkldmd~3GT8AvBFAU&>v=?uZiv(Kh#cGG5yod|ujdgtF^2x}JR+w}v<=25 zZLaK8d4%yv-@)`*cfNcaerNI(*UYe%cJFaEo~On=?!JR=&a9v8tNl(cosay--7f4n<1_RdeqD}F+FaRLJ%#>HAuqm{pi{5&31$su?}6DDSXW`zVAflheS{B; zjPGD{`3I2AKE6?c>aQ;`}WGa^4f?Zy8|T6X$Ok zVBQm_?_k~&$A{$jkUlpkT9gHr&fw6%tShit& zn%w6Ea?^K4-|QrGuw(X}v2Pz|eA;);__W_RY=>^tL=wjswSZHDnlU%>cO-{F&a_x&iG{BVW)1Fd^npOpV#Q)Gx%jaaUFC+oGHZb`Qo?u4DCf<{eYcZw+s8u z)-L=yc?#wUG;9G@{?FmqG6gVCWMVSbBExNf6!-9~3(AU1UBHfpW#wjgKS zB6pRY?lqHssK=!G^PgTbxo@ibwEKM$>j>_e_|PYH{qJ1gart`A{U7&D=x}DzI>}jz z`!&hA6NAy`J`To?*>}dieVpq%E@$rCxVuBYzT3o*gOh!2?9gZ&)*dR>GLeGuaGItqE!X9N7aMqh^Z zqOX3yPL`d}Z}@dNGJGhW(Erp|F2{Dv*MHsP*!!%#-Sx?Lpgv(OCfCfnYK`uG?#8}D zpXgo-*0US9-q(Ci(PxZxen^}gm@?`zI_c7wk5HMo17 z?5x96^*Y)8-bnSH#&_ktk(jRsCr)H;`(4n+SKsG+*_tDZ4}Np2^WJmMkgnMI8s`Tm zZj$c*%URB+jT@Ty@LObj2cyexU~FIuu59;S1jeVy{Y;14^t1HMjx%=5zBBgiYA^b!ZWnf(@frFJ zzb?loZLaKWl0*OJs_%yO$7jqJJlzvx8+99<(c!nqi5HtN?Z6j|FJgdcH?hIQM$9n% zL|fph|9US1)35lD93Rrh2VA$&8T)*Y*KKr07az#6fe*NDqqFtJxFBatO5eu-`otdW z`}aV}slwr!Ql^ z{%an|yYdL5k8c<|*oW)(YRq^%$m{mHyl$^EHn4>bvGCqqWv6=%*8S%50ZKA|)A*^khv-zRjg-zRjg-zRj&r}=PZ9P*wdzco4Ue@frqw?vN5 zVBg=*M2;-P#d+R=2WR^@n=IRR&Ze8~H_m1wn=M~A%(mZ&vR0T+1gf%8%jY(Kz64sc6 zi60-Z){t86Ye=onoOK;y#|LuSgb$duhIm*LTu$HM10DK|XE!i?8QP0}Mvgu{VEQuj z8-87mjPEKt)fxh0Bjlxw`TFnDM%EnV5vGqBTlHGxd4!cmSb2n%N0>e)kFfFx)5rLL zl}E|Rf%NeKD~~Yt`M}B}j4nQ4z_1OMSt}S-v zTV&FljpotUe80WarQ;i$oLccQZ!BLtFnx0Q#xo2l-ucz)&NnZ2aWUsLYdPPt`aQ)5 z*RJRMw>4fY_SkM?=l|II{bJoiH+LR9TaPsMy{((d zgC_0cjQy96*xwnycMdwhnRwo~^&n^BoN@8rITQbgvk!H)ye;zO_Yaf2CAsOB(lf^vNTvJi^K&tUSWXBdk2a z$|KC3#<_DW>oy;I>$Ap1cU8RDoWCo!e{4CIuQcloMP7DA=dm-JkJhTr6Aqa^eY9=U z`L-+OPj~-$9p|m)`e7Q~?*Mvs22B*)L_^ z{AT&Jc(UTLc4ftB@n^+v?eck7w=1i?=&K*FqyE9Z`VGJ8PvTKO6Q}y$+SO8Cy64wH zp40Ez{Cf3-Y1^7#u;v%6`2}l!!J1#N<`=B_1#5o6nqQJLKBdpNg*Crm%`aH<3)cLC zHNRlZFL=5q7Fm?}Rm**T)%rfaV9hUB^9$Def;GQj%`aH<3)cLSocSev<`=B_1#5o6 znqRQy7p(aOYkt964g8kHwi4r^TNY|KdB{ z--)$OBG)B3);j52ualCq&Pbp22gVNT60CI+#xLs_OgyY_ zu+~Xf>m;movX=WgS?l{c32U8%l}A|XB&>B3);bAmopi3(Ny%9!rO!GEYn_C(PQv(A ze`=jXu5}XDItf$%|9QLDJa_Zz@{sc+FC{nq zEPb<+WykDi**Cvgel4D?c&uGnaa#OY@msrmU#r`d)n4?~57<%vU|;=)U-c*PsGo^b z{cr6mm6tfzy60Clf4>X!YlpcfXU#8I^9$Def;GQj%`aH<3)cLCHNRlZFUc97(r4Vl znqRQy7p(aOYkt9+U$EvEtoc>TeSX#YKEGhiFIe*n*8GAszhKQTSn~_k{F0pcC4J@> ztoa3Ne!-ewu;v%6`2}l!!CDU^Gq069Sh<6hJ6O4cl{;9ugOxj2xr3EE$+fniuQf-x zLr1xTmAlH$f9JJv%3ij>T>GS>-+n52ejndIJ-h5A=NEte+w{g;6~A)cq3Oj%pKym9Cr%rlHap~v zj{NfN-tOpMwb0+4v2$(vU1#j?^1Tn7@w@G!lbwmDeBdKz;=H!^C(ch;{I}j-G3}bG z_opr&u-%>=`ObIk($U}U_#HZSzWC$T9s4ui+|}{B?*5y0;@S4gjg#Um25*!U|A{>| z>a+{F+KayW0Xym+?5p4KtNtV&^)qp*|A}9DiTM)We(jQN+Kvva+`-BntlYuM9jx5J z${noS!OETFv|al239Q_~${noS!O9)1+`-BntlYuM9jx5J${noS!O9)1+`-BntlYuM zo#f(y?1@>1*;~AH0>uA5ih2oBx&?k5xQm zr+3pT`)}ns%iZ*TdVTG!ofp6T!}QVy+c+P;_eZI5(6-J)&i^>&JGXNlwc96Y^`&-j ze&xJRyq;u^BOf#E&K>>v_xq_ccFrkxamN1pukY%N-@m`JTcvODjJ^G5&cu1nF1tGu z|6(^+OuM?CtN8X+UhT-+`@PiBFCTfaV`ruVpYPb8d!J`Jey_Rx=}tVY<0d7=dF2C7 zb>iRd_@_GULaz3ruYSOe`Um^!H~gwUiAViRoa%q#S6*Vi#N<@DgOxj2xr3EESh<6h zJJ+vs2P=25awj>tlRkX{D|fJR2P=23U*`^1?qKB(R_0?qKB( zR_KvD|X7*a=+{(V~cTas%G4iXgJ;R0vu|8#7{_-hOAX3de@*UVawvum^I$4jalQ++L*)m%o?}oYdm8|;~e`M|M=CsARf&Z z;=Hz=N5rrBMY}ZbET(qJo-@?irtlYuM9jx5J${noS!OETF zns>?_a^((I?qKB(R_0?qKB(R_Rp;0qnpOYU-kMbx*`AwKFWFw4RY%#L zo>gDjo}N{A*`DtAd(@f8RcE5F`VBj(GqJBa6Thl6iAQxNajMQF{!nLT)tOeqbmUgs zbo8wT>)5ecsAJ!1q>f*!ojUPY{oIMuYOqfHR)clgg0?%s|tV-B(~o z_bS-ey$XJHuR=V!SMfEozE>gsaIcbeufm!mxv!bEK5LZhuy)BlYnuGB)+rv=K*h`UE~f{?qKB(R_0 z?j+Z}igJfsxr3EESh<6hJ6O4cl{+}*YvfwJ(s}Rg?C<@4xPFh+f6VUAi#_;$@x)wv zIj?Zmi^ZeGe$G3Mx~Ev;FTZwP?ZAtRD_;Js^T@S^6pJrWy;r=~iYpZBji}!xes6qZ zmuUvN4(~el8CLO9?~QLsZu+J4%}yyhX1|nu^IOWV#ZxLCi?dXm7JpX!)~>8}!Nb3J zE%Cnb&X4^j_y5^#&R;(A^E~jgo1G{AXve(v*=^_9*V{BNv}wh2|8mW|;Y^jz=-w;k z-#mSb>kQa=$=vUf+nwLJZ~lDHZg)F>|MWTX&2QZAyk^fC^ADDI#Chj6`{jQB_>=QR zhxN`MFZhh}ArJP<`Ix^r7mF{JXB>Bp^SKLMT;4YQCC>J2ZtS6tj+4BQ-1L+5tzAj& zBByGv*-x@>ev|xKJW26boJnz7{7La!yOP>v?M-U0^+QrWSpOvTkM&zpzgd4K^{4f7 zQa|gx(C+u=zZ>t*Yb>#DXe_}ROR&Zgtg!@ZEWsK}u*MRsu>@-@!5T}j#uBWt1Z&Jk zW?U&|STVzj8CJ~ygT363TPxmVA{^TzL+Z+_O)s;aK)?$zCE zZ8n%=26N0{jv34`gE?j}#|-9}!5lM~V+Qm50QgbH9jM$htemVbx|AG8J^*%`LLfiTN4(9ti znD6gkzQ2R{{to8*JDBh9V0#~@`#YHL?@mtlcc)MHcQD`I!F+!Q^Zgyn_jfSg-@$x; z2lE(b7WGZs`=G;pfbXH$YhPbFu9u$}MbA1PsqL9=sndxkmg;0m)?P}yH}^!-yG!^? zw#tY#=FF9u>D+kSp2H?@o2!ZM|LKC+lvIK^<+|kf!JqCXo>(et{QEEJC*;Q}zmd>y z)2BT#>^xn!J2C9PnzJu4{HDAUo^>OhJ@ELSYI z`abJhJ3ia7_Idim$Ur2urYx8X9+rPL^vON9$=YReE=Rew;|93qc-vU7Af%- zjh-Vul`nJLYyKf|oxUf`UGa~J8%)??W^C_8+^gtp|wdu1>>&s_fHU^(#u(A0Zn~gcjG26C8 zxh>r`rbM}ow(U`FyUmHuIkCC&IafA^KIhQp*5};XT3k}+e!SO4AK<+<^%M8(70i2W zFz>a&yw?WvUK`ANZ7}b(!MxXIdHVCa|IYKfaIcLVroZRVh~@#_Ya=JT*9P-m8~nfb zovFT8sO#`wZJX<&>mysHMr_~Q2uF~0cyD2y+D z4-@kA_rd;K?}O1^8+o>8bUxS1p3(VSFMCEu@8Uwoo*~dXx?p>TK=1B??HK~S(+jp| z2=uNm*q#;mTrYcukpAAR%?b7z+|RKG;r?&OMIz63yd?5($5Em#_B|r{YzT5|-!G!i zAb{7T<2`#;|GLQd>FPoJR! z+j*WoLkG6=Iemr>Z0C9U3?0k)eIe-o*`LEoe|8o=gZsNYJCpTd#`AIePSHPncPM>t z7_P7WxAunoehBLI&%6&d{_6$)>?`}L+*97s({5fy{7{G2^whgo6HmIViQb!GJ@Hke zYUze*Gx6#3Wp&lBw-GPfky}q3v6Faji=Dw|!*>(+`Jh|y(yTqiXFfj|n|v_jJHBcd z$zLR7{oK>u@Hcmn&b>+Vz1I$GCm!-S>FJk2HK+m40|Gv2B+sc0m){cB$gu%pkVyQok0NLTuZmS{)isY}=*! zK0JolwoBdKY9z63msjJ%;l#FG-s{f{Bev~|l<-5g?TRhP80y$|1(C@kNXND-csV+n z*tSde=sAwqwo6a%Gl|%?OAjhOo!GWZPcI%2+ji-zUYkv9+off_Djr(kKhb@NI=8Wn zmV8a>Y?3G4+(yTy#E3Io@xHG5>NMinm7mk&222dEZCqPF-()Ot-O^=r!#yL3$M(8X zZz?mKc-Orvg9$GUCBFaRSAvQChY*)*`eN+%r6KR$a6Gd5Sg6zBOmFY=%SVvTz%t)? zrIJSz=NnN_HC-`|xa50LwIy{jaf?p%)Q`~_#IdulsP$iI;w-nfR3p?}V%tWwX#XN& z+b(s}8!L!yyVMuczb3ZrQe{5c80t5!t=^iumDsjRwW_j{*tSb0|FoOfw#zG(_6@OZ zmv?)oy~MU%kx30gw(W{tRW8)A?FyWbXjr7_5(}}BQsiS9i zpG@4ei_$aZjwhb})D60M-!a5}AIhNnl^R7naZXyWtF6!`F}$|u;`E>bl1h+ZI_-`XdSU_mu^0A6|rrXZnS7Av2E9H>V>iP-WONexp&x?L579rt=%47fVDww`XE6FR`Z*Z= z9Q_}R{*Q41K4-@T#tRtZ1>*>eafI;&#`waxBYivWFdo4ej~J(5j8lwXFvc&&H5lU> z;~k9gj(Gr#c>wbR81n<>4KU^n%qL*XCzxlzm}fBmfHD7IUIJrY!h8kBe1&-oY}-Zi z8yNE&<~=axJMrn~$(_$1KR%;A8=vbx^GrVf*KL{f@LOm5%iHGn(^8W3ge}Iee@#LE)7)8T zKBsosxjnsKUHbj%_j3Z@m(%aXc71Y*-;3qiX^l6}$G^k7ZpRU?{OH-l!wwzrZY&cg z?s90WxA0&d$FZ zAvmA5p7ft<+ARnUt|i`jPdunLU=4AeX5R)a4z48bdv}t4cGoiEJrCs6Bl<2TK5{g_ z9$R_=v2CM1KWh%LZI^z&VVu~uOW#@|Ahzw&g)7e_w(Sb89XE~Gwks(3@f2d)u3*Z+ zNyN5Y!Kdpd65DnK1s@C9wkvk)>ml2AMZUc$)VJ;OcD*>6^liJmBK}lj+b-|(kERpb zc6m?xX~ec&>Yb{Z*tSbm>N1Piwo9R1*oUHB^wiQwht8%gKTlw+}*HiZ1u ziFRo_hKKy#z=@H4M?(DzGoxN~N@(ZTNO!OOnb7{qiQ1dA!RD4 z?1OM0`b(j!)EzG^A^A;yJ~gr8LgKs1g?-YsF};7M#$GR=o*`nE#xAlN(SXOgl8seDtr{wE3}sMYXwt-wntYJuUNb_*xn&L z^RfG4mAh7Wu43Ek9iA1Q|Je3=&n^tFwe9s5)(OvoY1?gvh%3D3noXm#wc{BZc_n*Jr?a(2_x1LkF*E3FZSS3dw|CJ@ zI$L|@zHPsmPyQ$KfSi|dEYp1M=aoM^i_iVkzUB6;FFf~Cd!DgpfZ@5Hs&sY{pZlp& z_b=shKPBhPKWna&Ha{t`lH$B+=U(rXeXA(Ws^7=F@7`NOaW<^~nOEe%*A!>59gV!Z z9$H6n<{wbd(|y)coQL1h5qXdJpUmyj&f&M#bA4kYv#sO$25--{@z@;N`UaDF+Bj_v zZGD4xpIgoK4Ss!c71uYA_r(9n{Y&1j>zq#Gyalh_Ig|4i{5;n7HyfMHTcD%1AKKV# z-hu&Zr*Pha8@o;Byv1aH{-3M?5Zm!ln-$KSVH1q?0Qw{t_e#{==_usc=|qqpr$cKA zC;!d0vTw_n|I9JyV)#v*vaiY*{>@%`&%NYKw=NHnK?4PnP$r%2u@%8*S8KXJItO-WvUZduX$`q|qV13Yc(rVSaVdiL) zqFaLg$=J*RNX}6xzL7 ziyZ3bn`N}^qI~K?-7`iT-xTuFw2aY?kA*CBl#nZ-Z@+(YzW;vV*+xB>3@GDD!<_EQ%t9u(t;B9j5N!glZ;pM ziy+gIul=jGPcS`>y&jYrvev(_e!O|@`7*)$vg`a`i;Op4&N>)7+isoz-Q01ebeU&k zd%s-g&mA_-G&-IuEkoyZen~UVoatFH^4Oj0{G0QRH<{mGAL%u7t^b%FZ>Bz3+`DQ2 z*Zz^T31(A^7rjw)*7)P{PBJ5^_4clOX|>;b#AH*Y`Xo=CSm__CJJr0Cy4cJA*>XQM z`wY`D(_U{>@=|}^wlwqBv6J5UdW-yZF>Rilo>86cHQyim-Zj;~y6AHq4viw|jS$xvuuaNS{xp z_%DoDWu`A%Ug?8gQ~cFmtui0Y%Nu)R(-c4BGpo!)?<|gutUc8qc6Oy{eBt__>Y1tj z6VI+RuWYOv$k{8WhKG@#uYp35n zcxTpX;-tc3f)A&yBz||!vS97w%Zb-k*dMG3mJr`L<8-k6$A!e7Je-MQV83}Em_zbU z-_4{KeHkY%yY`phTux1#ZN!1#nt5r&MUJitR@!wYuC4Lpq+nK#>BIxpd=g|@HkG(r z&l>2)|(r(4Ly-#C(1eMrcibG;lXRx;FI{&6lZ<+f?0zinJIZ$_`sX6)9! z-uZ?zNq%Kf?d|>M!)_WL!i1ZkFNR>QBO)=S^wt z^_&>iBJYOVy~d5h8g+PVa>UlrASd?wGu4(si-xOj@_r1rCkZM$@poQBx8OP^n#Mr_-q8y%cZY}*wSeR?Xf zZC7yW(aFTNT|s=^L}J^npxl88#I{|ruAhgDb_sbz=zGGBC+vH|uP5SBB2FdZ$NcQ# zDMD=TQ5v;_oEdola~;84M=;kB%yk5F9l=~jFxL^xbp&%Aot*0E^r?E0&ttNol6)+>dmXTh^FHD<+w7 z`C9Aea&9z3dXF|2?s`@?eq)>2(S3+fAKar)jo)SNoYdb;8CFmy|GLL~+MuuLG4gb9 zXz*UsZ*L!S&EX)}_S`-bpWfS4iGLOpynesAePAzBen^$ztq=E`2AB0R=T~fwZ5zJd zWMB1}$(L|+|or+CNoH>Q^Vg_(0ex|#htlF2{Wo~(PfLZr& zVRc*c?dE*3!6s>)Qp?(JHt)PX!qlr+Pn{gT&eZy1oVnuA8|ubptIUy2Q_S>PZB@@T zOUwsX$4sL)JE?n5*?W;c+YD{=u{v?om^aEUH2X?)Qtz&tVb1PaX6}5kjVif*l38;7 z8Z)%;i|Y04GRm#yZ8 z8i&0{vkx(4)^9Ueix2ZM9~opm8?oK&s(Obvy3HW-%8Bi!eUn^~DFX)?Z_jp9`t2F9 z#w7=v$ot#Pk6r2o58XP%WSFzf9N0TLINf=u@zb`N&Xe~B^{Njy*FU?(^c|O7kAGyO z8M1zpnUH$3KJwLQvoq^PQ}({C-GX+~aHY8I?&t2=Blrq;a+&53-Sbkj4lO>;HR99`L&#t8Q%o(IscM&yW7 zf7^6VC*3DHlQ>9jtGh3nO#JegS9Q*fCN>{LjPWAmp3wJ%9VP55;a7=xl!#M__!IM+ZI`-y!4mSj>w`{e z-vg_NC+upg9_YM|xO9^@)$BT(iC=G0Uwz$SJMqLlqdUDa zU+yD*c-KeX4_)?$ylzHBa7^d~;@Uvi)WVk*F=!E+7BOqlmc(3#+8ybXOXuF*6?460 z)$v?WJ?sIJtI99<`lSaxfsPto+hzt zC*HWbwLW@FTjC+Ao$mHiE8=Wx+UXYWz5jdGLPv{hwXms$FD+uwA~r2z)}k%?rOU`C z`MvIi_e`E4>xi%T^c}My53L*27oWUo3e?$3@=9;LYSN-Rh!;Qmg86a&F5-{7H8q9p zzmtxfWVre%)8L`K#H~s{ZuV8)M{M_h=HqT5uRmEmA%7_6-3k3AU#NtgF0;!g>=&3? zI^j3yS0WKl)jq`%ah8i0O~ilT+M@7Dej!iou!0!+Epsg;hMma9g~YJm@6bGA_7KG`qw%<&-q94G3+ z@ymJ%)}nS=)J}`qX;C{ZYNti*w5XjHwbP<@TGUR9+G$ZcEo!Gl?X;+!7PZr&c3RYq zh}z|9N9|>~s2$~p?TFe@KH0CR9p#_n z6t$CM4Q=#A|MYp>*_`-1?rg4n9(Oi}K94(_Tc5|B&AHFx&ep=`ac67fi*e`kxU)4) z$ZZ=F`nC@w?ASIY?Atz*@N3(ch{yJ^M4YybiTG`wOtcGf?zhnA{tP?Z&taeYKm78z zKs-EN5GRi##Lwf)_DP?|9ooxsiyQ|KuE^e{ycoKRM^ z;}o@%V~zGRJnpcc;c z{*C3>*RekKGi(R@8Mcr84Ex2tk>kOBhU3J3hU3RxRJ2R+xPw0TXV~F>4*T5y;g`n+ z;^FavIC&f)ejZ;~ck;MHds&V=us-s`c91u=k9@LUSx?0d))YZtY2@|!Wy*JB6?PxE`c0}!HFUo#J z?PxE`af;fZPjc;OkIMHuQ9C+2aJeG;-2X-GC>|a!qIMKNk1tU>YA?%0?I=HNN7Rn; z$$mxcDE~a}MD5TnuAR2$`EhZ!&#e2k$Q-}^$=tN=-}b~wlV$pg#5J4kG`-slBo3C& zHc2nfBfjpfFU_4FhkJ>ak2f`We?CR>cZ+8?_x+kVj(vXB1->qIc~)k{Y;}CrvDf;1 zt+na1P3y~NUp5AxW3aLL9Gi_f$}!956oQq|QQ}%9Y%1YPi5QfKO^KM5Z5Ou%%x#1Y zw;k7VPGFOB1z(&)#K5^lY@Bn%%(cM2Fa3E$`tyj3J&#B~LrXtH`%}))u6U?}Ir{26 z+$Z$P5*^Hc4Bc2Cc63>-vO?_8K)S6j|cLwA; z26SJBKA!)kKZmvb{D1fy_TTvo-M%*x=XY=3-hIyWxaAwnY3k;=$IOAv;hfWb(RMST zO?ZafpzS=T&i<)J87NmjKGDfvQ1%Mqyg5GdXJ1)} zczuD6euGvehzGat;Lpxfnb_V7?3k*ZV0W*<{la(m8r(;Gcdt?QUgNuajmr086MuW( zl9b!0Uw+-+*&#o1!Lcp<{0}7&@0-=o??3Ji;tp>&@L$hYo;W)0F+by?io~&Yb^N5E z5#o~9*YxKP@rYj-TFrl9R>(Wc-{q&C2zC0LQT~9M;XUi_d=>r8t3#U?cHQAGD_xeZ zop^5vze&5$@37{#_+PCrP4Y#wg{OrR%*HHXS#6H(h{H(-2*HHWn#Xi?i{A|TO*HHY-#Xi?i{4B;k z*HHY7#y-bU?m3PU&vewlZB>FZhr3ZcmOW;TlcmLwK#6AoN<0ft;#q(a&jOTq7NEql041IUDDf-+&s+J~ffCOGlz0}P#IpeOAAUBW z#IpeOH-46Ze(2kE1kID;SpeztIjwjWK=%1uS3C=#c=#MxJPV-s`P^7M3!wJ0Ts#Y) z{IDJIEP(RKe#Nr@%0I^`o&_jzCaG{%$>--df97*_oNe-Xd;0l*_`Lgn>-=A=-?UiQ zX|dkZVjZZ(`cR8?qZaE)E!LS@tUu-cOT#apONce07HdVESMVBAi?yN_Yeg;AidwAY zv{>V5vG&tqO{m3MQHwRC7Hdl_)|^_bMRESX=N?+D{j^vUYOz+-VhyRq+ER-(r#v&c z=y`}(<7u(>(_&4i#adB|HKexd99~;$vF5~kIJ}m_yDPlL!#gd!_QSg_ye7muFuYd8 zyD_|m#5*&*w#2(MyynC^HoO*<@BC=7Rs{1}QHytV{_^*8#2ODd;k6%f#cM+3kk^XH zEw3Swb6#7b7QE(^XHyqFcM@wn^Z{P`p>Ob-5PgQ%is(zchD0CZwI%uTn)nh^63uN5&b@fs5I6|XHZkMWul^Bb>4<@p{yZ^GvWTC5fE zc@thk{^m0&VsEa+p54BGnApo}vB%e9@2|y~fEH&3TAU%^`QUJOwg5SwIY6J!B4CHl zC}5w@F5s8XG!PG;bs$bY1JUAaM4o+J^z$`h&7A%oRQL|tCH)?hSTm=;KjZ2p*36gO z`!izAoc`X0tJkIc-i0{tlIt0H_Vt_fj9gy{mik~`|HyMux$adLTldQKvtX%@^PI$) zs=Rj#mS;Y{xsS_rg1yAtbpCD!>$ ztpAnR7bvk`P+}jU#Qs9^U%uCneMazKzE+oe4Z%vR=apFJE3y7pVqc)degW_E^F9LS zz`Vb}`~SS}K>z1;tmMCZO)J;rg3$+f-HX1#>tXa6UMHh3@%kBkjMvrZd%WI8pX7Bo z`YNx_e{;4h*7HiN^OactE3q$7V!xooJ_7wSafU3;uCYgE`JcA$_$&5Mat|o%Dl#_H=mW!h5~nJfji&V(9aJ8Fv2L&th!+{4NCcw)~9dPusu$6=xB) zpYU@rdDbE4J@mIf<$0OhCkm$bO!zqh`?w z@3uL?=N0~$&v(nSvNppq#c%j^UGUWO)%w&+nd2*ZYz^jiS*6QXOp4D;+ZPmXw?a=p zniMbD;m6?1fP9@@0B2FdZR3c6#;#49|CF1<2o=uDA*Z;3`NIt8)B-$nNul|$X&lmsp z(MA6~CHY>~zw_UE66d#n`*+)N*zsPwMhP8DNmJ9`OOAis;x>I|+AKA+dzN_Zhl}gA zZ!c6+VoC89cNf!hmMv9vzRMiX;@zq@&0V2x9G5vhy7zaa|J~wD@mv=UlK#slGsd@d zK0x|U-j*?*_l9ptKWgWwB{g!J(eDja%e~C;r*h{uHCB&Nr<+|co!jiyBc`racOA$S zpEW&~*?wlSD%>Vh{Jtu=3}U-yf5v#V(p3hrRo{Bv z+_L6MgV@IDUre-gP10X?`Dyd$sv4xArdO@%q+h1;Ni+HL7b&)n z%KT&wCs#9wr`w(r=E~F;DbB1_PnZWrzd*4~=y2S4KRr*e4Qu?fS-bT)^0i9;XuNx$ zC10OcI%ejtZ$`fEoO{%adbuh2s+(!Q`Cv#l(tqLYy{5|8uB4yqvTw{|OFkj}{Udjq zC%^AP`d{6*(`&lZPqkw=2C1&>(4SJf0;wE^?o;QrskSMzV0Yx%<_e^$k*JA+EnNjCtp2w#LR^k4f$%e zaFprLaxLla9yHQS%JDVnKh0i@hxVfX{D$*Z2eyC|*WCg{xsL_|^!B=)u zY!BV?rP-Z-H^tU)}Nx-HnnML&b@PrVrz7)iFtd=Ns6sYPcc(TqlNbC*zFzz0N%KREW8|yq-ZExR=kugrar_2H`C-O5V*7DyR+BU-LmcC@*~S#JZ{-E@ zwer2`y6~?_q<>H4X?l3>B+~DC?NojBota60QkE$?)0>&%7}qDyPt*raW{6{KE*|IW zyM9Tb*j6<2b^b*u6x)s?N{@Xtg<`w2fzlb1Qz*6;A9#9J)8x=srHEejK^F4W>#9on z-0&pwb?%1>T5rruzU*ftZ`!jz)CcD}8|s7Kyg3W$V=eo_qe%(Z@!q{d@;ZIVt(^^ zezSA0FXmof%)P#tdwntY`eN?&#oX(Qx!32p*WMR=abNJoeZd#^1z+43e7-N(`WllSFYc$lxS#rbKehKzpYNgezVGvW z-`?weaj*Bqz1|o1dSBe@eQ~e%#l7C=d%azU_+lO6i*<-E)*(KxL+ska=e37jFGaDDH_ZAD6JLyjm;e0t{v% zzxpqkqnWZ7B7O5-rfBV|1!xT^_MTeoJuitpve>iWJrMqk$>07x7O`LZxBgqTV$XZg ze@9n*?puq`gKP0QaVrmndA)do3Gxdvp=|6SF4;czUZ!R^~W7o==~37il-Jk zNOsoe&K$4P@etV&`#3$UQd0bE_rqjoh4S@V;r+NqjB%$09AVGg`l z-5};Wik>nR^VBeC`>KAY%@z0DPrk(dP8VDBtGVIw2guj>v1iQEg%4oOtZURfYYN_1 z3u|dzckEfSzE3TzvGw)Ue=^NiK1+7Q-c8qUcHGol_dMAVdp#}ofLiPm^^;?En#>bF zrkIy5*=@FF_=I8}H|!g8XR)pn^BceHH6NbqO1{LtPtQEL-%RqlldsZCzcq{E-6`hx zo;YCI=I=o<51V?xtaz{o#aw2_R`bH1FUgMB)9FP6x0@l+0c1z)0kzm0YO#OR{Yoq_ zOK+J#F}J*Ykx5=Xkz$@VezEbYOs1I6ZCPUGJTQfPiT$7++i#i4v3)A}%Kyl6GrsjS zih28nFS%ZZ_Ewdp$k>F8l9|?V3Y&#NJSgJ);(T zN!=&kFtcNnwQKvvBcq0!m%dy@F<+iC(yXt&hGH(6X_U$K@z>-_>=Sj%_eYx>pIS%0 z`sNv9dSAbuV!o-(7;}8YdW!k!xnoRj`wzPy=5Kd@VXj)co$QD`pnkqWKT~h^PO>BR zj9Tm^wb*0o#*6^$ktT zW2aA$9kG|xVvniC-czR?EotH{PEpJ+^(kcrZTf{`zV-4uOpk+SDCT;3%9w|noFiXi zU#V{$Qr0}x_X7FqQLUUAaaRWHzx04uIn(;H4A__HY3It>fA7wo*VsJg-h7!ExGZBF z^M=?n>I~VlnQq@_ieugodrU3%o?7fl_4lt&(l_6qF^)XXxqgZ+)G<>W^TxI>rs~)F zWsYOs*f(ODuH7h!e2M+0e#4ugQ#xfKU*4V>I+`h&Vm|ihOg;bcWQsZSmos&vkCQ3p z#X}>y#?mZgN9-ka^ShNUdOVrzh`py4dr~d-s`~Cm&4yPimYHHUZ+$j=*>g!0GvtNZ zWTBW}&DC!B=KGS#7ufAXHT2iNZO`a!exSeVN80Dw&&9VJ-lKX}iWz+9gRC605;5~0 z6EQ0hGw(?eGw)RqGw)%MXC?BiM4pw%vl4mc{VDRSM4pw%vl4k$oM+oNe9<>}?}@(Q zi@w2oRrC$s!=i8S-WL7Y7ya26{n;1&*%$qp_pRv9zUa@s=+D0B&-ULs3;VMjgT5Gp zyeGvN^u-wDJuJo`?`<&#dC!Y^!x!_0FXjzj%p1O#H+VmbdBYd;hA-v~U(6dm&l`5G z^Tk}pdsWPJzL@KHZ;QE(_q>?vcrT3k*%$M(FXm@o%+J1 zeb5*8L7(q~_TKG_dpGZGaqsrUy_@&KxOej&8TW49J7c}!i}i*t)*HT9Z}?)p!TVyY zH+-?)@Wpz=7wZk5*Bf??D?|HFC^2Hj7_sCcy@!lD0IiJ^ZVtrC z{TvnR=crgeN5%S?_t98CN5%R%D%Q_Yv3`#7`gzYRyXW2dFs;v5Y)FbW`tng)pLZOP zCHl$s$7p?i>y}K>gWu$!^}N_e>x@g1qa96MTB{$tCMmkDN-nY^_TajEsVvd9@8>3) zVxO+poXQeSeLN4@7khc#{IlfffXsQZ@7AZ1GuiJdDP(ZQdG{3=h!+f=7E5V(Jb*lP z?;XL63VVo8CASUwR9H;B|JIQKexL&x{sx9Ft^vaaY=L1LKEUv4nL|r1XUN057P7hAWOSNla3KE~0ur2mW-#o;< z>(&j%{hXEfr6TrwJ*xi{K)*%Jw_3Rtq)@Ov_6R8Q^+Gi-xGE`Vc!#eJrR!*aVil%)y}mG za&9m51J^Dk@}orF;FomZ6K!_w@K15F_yyz>%#{acHjdH`}hGvhQEQK3m;(EfDbU@ zhYzr87t2vQ)~8%KJCs8(+9dp%44q1d3a*V=dH+TGYa(=);8 zzB!4j-Y_bdw=4s3nY8S>+7;cj~aZ3 zH*W84V%WIx$Rgq@hevq$fj(sT8yLE{1`Hdp1%_?J28K^7kFnh92dr=H5W`O6gM*0& zB`^23Hkd`+b2< z)HjwM znT10}#j<7XM)K0lwpg8-Bp>zR^+B(5=PTjb4f;&%s`6>nuZkW&YxS=rozl(f1=G6T zmIj?x%`yf}Cif+smZ`7WYg$*YIL{PwkDlvr;5jf zuSnJV#*$9%rV*(V5iv(P7MMdiizBV=wFzGl(RQh0uT8}4i5z;umnYipiCRQN%=X$u z4n0xFh-kaLHc<;t^nr-Tp}jUyQ&04nh^U3VHqkdcQAewv=t~jN2RzYdezS%bYy0#) zm)##>A9ktjx#ZeUtO?WC>TWH4DX-O0JM7DFPsHAY8G9D6+j9|PFM~af+sDz~2aJ6Q ze!$odp}k<};up$otX0hf;tPig}l9y}=eJ$;T*TT+!tre|b zTH}Q_GbZ#Qch@5R-{^>#Sx!2vkM_72w7AylB>V=@aq&>!7W#?2NgdH%_)6sP!kccb~2I= zFl^ZPNesIedVj4Jg(8pvUTeIS0+4s!e_5j*U|CfX$Y zBIl%Ib*XmHM{eK)`pB96Jv6iv){f;O4^%tozz%$Xtxu{Q`^DcNM?CNWh7I@tBbV}= z3g=glzZ)Yk&0TornMN-tDhA!$)02u82|J zzv3B${r9|eT9?Uc$h^+@J`8>S!MK`M{0-uk?H8-rYibeW`$MjrS4^^kzSALg*AhFM z#2=-;<&7S?llb_(LnE=4yP0FmRwrN`d#$$dkdC#fZ9K%*m$vZ`!?%q`vUc%6huB?9 z>}(P{U&J;Z#K4T$SO+l^f4#TAzP(s^1^bRkj&X8(vFR*VLI*5$z{=%;Sma!ZoGX!Y z*yWrv({GV;zLw-7=j@B*BInArm*gVnO5_|iIp>InbB=2`=gb;0Ivrw>bGAuxk#mlL z~E8IXSV_=bS6Y(AUD3{wM0oxguZU+Ka`hUERr-@XN809U(`b zN%RND3T+W`X2@BeSoATe!@hp6gKM?xhf)XEvRvvgYZnjeus-BcN48z+urIPB$C_Z| z8DpGmN`?=fTSQ;NT!el|`qGYMaqUI>q0>?LEtvkF{R%sn5C4_LC49dz3{_%fFI6}v#%)r z&@Zuz$9L^QoW!$4tv%g#c$iC?S6l#YZv6yUijfWzz^rg z*;mkaeu-T?#PEZ>KnH%PF6X)xN4uUJbf16pY`5a|vu9UjdQ>AGcet}^|8A7{$w5n1 z-T}A!$F2So{WAKmyj6hY_>KRE9Dj!%?BF_F4~9M11;Y>g3Aq;f#LkXBaHd;vXWu}_ z`8ANccu4NzB)N;9U{NnG>b8#B$j~Mn~ z7joOKaD3T3IJpw~%H;=kh@E{OI?gZU(8WUxKgc7lb@3CUU6`kEEzgHwH_wn9;~4W4 z$=!Siw&R-SL$I62C{CUaA*XR{=R+{hhe95Joj$eQ*&%lJiFrOmy<9w$XPysXhv!4E zYZvLb`NTku`3&flXA}Up}jZK{vZ7w?D{9M>$k+{7wGrUas8aw^?zbFE);Zle1Um< zfq8rhIqt2jPweavJNpJY&M&cxhnU9~bX@!-=kev_G`_&D-?AMVU(P;_FEEcUFpn=V z#wD%?^Y{Yu_!4p@^ogAvVjf@6;qevPq4Dm6U7W-`z92`t%H^y;@^#;z^$I>vmiXqp z@2iKezKytC&KYX%xNC`rUiF=dy_by`zw!UDgTF%$jO%bc81`Tn3_tKEA03{^19CT$1e&-T#qCuxl@|%L6g| zAdk>-c_ViDRFJzo6LY;FhacDl!;if$7ZLIR?DRF**&%lJiJe~)+6n6gc5#y2#ZS!j zf{tr1$z2}U4%G`fE^j2~dO_~;Ofk6p6LYCm+M!Rrd0rUL}?CuLB=ld7Q-Te#f?k^Mr-@hPt_alNp>%N`a<%79iV6GRK>qT-`FEG~& z%=H3uy}(>AFxN}S1EH_MTraS*Pjapojma|fw^8n?g@SSL5hSOVy+kDTraSThic*a71xFKU(i9jurC6;{R^?%*AUab z!S1i1=6Zp-USO^lnCk`RdI>qrhg>hnxn5wd z7nth>=6Zp-USO^lnCs=_R4=EGeJIVbTrbGEUSO^l*v6xw2X^@<=6XTS^#XIfgg)ig z*&*h7L5J%V+6n6g=6Zo;y$1d;lKMR4&7U5w9=ZQ{%HhFP1Js4t`-wNa`l%ZDLs5#e z*yH%&2mV~UAg6nZ(#}{;Yd_kYb7nsKv zba;G0&f^Qr<4edXw@#mO%i{}nczl6*e1Tm&q|f6Eavon`j4%Agf9MzJH}LD~8$j;r zPHlAkf!OsEV%L9&(J#=CVF&#h{T_DkANPCLKS{^+TVmIriCsS@=J5raJicHLesDb) zeqa~OeuSKI==6zse8DDxD7s^aC*03(WNbbG^V^FEG~&?BdtpFz)pEkn4q zFEG~&{73b2xul$OUhy0Mxqkb%@1JN3j|11P|A_enHRXE^*xiF@tns}Da=zDq`CbF& zdkvWHHDJEifcahnM(%JAaPt3{wVZ1gt(?yavqAYry=x1`Izq z{}*yk=yQJP`5NTTKFRrcO=yRn_xWIcUIXUmHTMk&|E-!r9m@FNIu}lPt5=mGUg^E1 zF3c%PT&Tko^-#Y8#1&ibS9#}VCB|?3Kd!~!p$EowxE>69unUGC)Jw<%p|8Qt4zaUO z?EIS04#h+4;v{zQ6Qf?%AIk$92kUDaAF+*BTYtpXzPA2|@f-i|;xW*3aT@E781}3` ziXVPZFX%WqwHJOk5AehJarPDTonIg9;vt3~&OiJhkI-@LqMCwv+@+7TY&7mJ)v<Dn=sko>{k;*?3-4=j?Ih!UA%6b{?B1)P_l5ZVAL#S@KhSaS=a5Z) z{|9n@{|C(P|A6`ZA0gL5pP1kONq@iY58kh{??$3_*x%8+n(6NwYvh5ScZ2zPH<+Jy zgLz*74xe}b``$OEdbx4;dq)4~{T-P1cVOP%k=*U?!0x>Q1?Kk_!2I3<*tXY)T`+v2 z-w1j7dy@acdy?og$REx$!F=Whc4v|#cW0Hv?hKQd&)lHTXKr9Va|8348yJ4zPsr2X z8xP-C=R9lV5&7ZgbYOl?2j+U=H~tIHqyN3n3fV7ybDsfop8<290dt=LbDsfop8<29 z0dt=LhwW=uM9Ba4&vtp8i9G_C_XuF#kArzX4(9zh*zK3;y-nVaL(cngFz?5~@Pqsb zdHVaV;d{3K)cdZ;8}f%dc6fI^@pnn({8Mj-pEJk)x!UGqBp-bGj^FGD<=znN_QJfE zOyA4foVY#sC9#+PXX*=`R(XE)mQ=rk`T*Cos_g^C{8QfB_mrZ3vgh7+)Tm-sV*80Z z5AmVXzxkW$tY4ILzDt^>rhi+IbZ`!Va~9|fK0R5DzM%l=40`#1%6H&0(sAc4q%&ao zKK1USSxE=&zGQs@qx1@VJ8rF0%0c*@n{i`7V&84xOS0_YZvLbc9D+D z59zr4kdDg_>9{-__;PtR@a6Js!gf);NXONSbX>hi$JL#5T-`~>)tz)){~;aMe@Msm zAJReoY#vDmjPoqS1Gaf&JAthS+oAI`=vX^}tp~@WZCyDYI%k89jYr$Ml8)^c+UAjT z+<6zbOWQn>j?Is@c_bZoK1Mn=KicMzbntiRA%}ck2VeL*^jy6R{6UAuK6K#6=8<#| zugxRrxbr%$yFuKrgLd0Ia{r-oKiEOL(f+Vr~MdE9q!Mt zL;cysqhN>64`B!S<8gufiSb3}ilSW#zFdCD4xcwd$K{7~T%LXS;&VvoxIFt|yQp5I zMk;_Rlkjdwg3q^}(m75r0;oTEM7tnQdvrF%0R3lk%_D}L%|jOu!~Rt#7ZJnng_BE&5l^nq zmk}e*VM~`2BmO2GRuH3I{TGCc_Ocv#V149=?I3S#ANgdz$TP=-{BxYB3&$US!rD9+ zkl$IG%cVBFH>?ZfZL`iId7paaQt!_aPw=)3VSS;$cvjfnt4fwnt#D7+-j}W_pZfad zg{1HOTrRcJVGvxnuKo6@3JIO*cUMSU+w??*L=0e#^W)PMQaJ`N#|E1m zKYSgV8}=*MoKbQr#RFeQCx(oeSqE{l9PvZnuH_8(XE66?F!yIL_h&HoXE66?F!yIL z_h&HoXE66?F!yIL_h&HoXE66?F!yIL_h&HoXE66?F!yJcqd%}d`U#l(Gno4`nENxB z`!ksPGno4`nENxB`!ksPGno4`nENxB`!ksPGno4`nENxB`z@IJEi?KI>!2@zxetT6 z4}-Z6gSiibxetT64}-Z6gSiibxeqh5U+%+@a~}qC9|m(D26G<?_CIj&j%_jcqQaxuQx z+`@Aad`V_Ikn^=*o|mLP;*r<#eH`+O@x|swo=ai>_xz962CUD1d2NH(u!i9{|A;R( zw<8a{=8?=cIVZgS;rjyQtPj7;kjs0}#rR_PCcc-!j%2n2IbRFr`~W#)Aq>mwd!juUGREx&p?S^Y*9D0d*!Lbdq1n2 zy1UIJ;_^Y=)K`yCBA$<$J&}m> zLW?I7@gHdaM50}gZ`qqhexcuKkS2zmU+$Pi4Ev?q&mo528#>G*Mm%M2UO(Sbmog0!I`yw^khu1;rM7l19x(eYy`n)P9x%rVo2@s5eF?sD)*eUkz~&|$ zGJIWCIn+VStb?}jwTPK@&=y=f?#=9p{tV{+4Cej}=Kc)k{tV{+4Cej}=Kc)k{tV{+ z4Cej}=Kc)k{tV{+4Cej}=Kc)k{tV{+4CemKa`Xq*M?V2`e+F}Z26KM~bAJYNe+F}Z z26KM~bAJYNe+F}Z26KM~bAJYNe+F}Z26KM~b6*8>eOZov1?GOvjDF7g=-XiK+hFe7 zVD8&s?%QDQ+hFe7VD8&s?%T}h+hFe7%;?)-?%QDQ+hFe7VD8&s?%QDQ&tUG)>GSj7 zZ+_+j%&6FxtuFl4qsBva|`sD zf3NdL^Nh3)W*sokMbaji@8hs9eMvdbjjYdewbc2ed6M=2(K=a=y>9KHtlv&L7=pS)bQ@c%j+5{gM{YWAn z)`5MNOPkExUeKJ^oEtH^`#K{<0%TXxlX zINtM};>5L|svCcNRAu5%Dn1q8eA$Dcj34{(Y2sI=yb-_oTvOsI ztKUz^pRV6Jp+B-uyM&!;?K&pxx4Nuz!taEiCq_K?e9)H|aULExnHcfE`Rp8Gv}{- z+JU)tV6GjQYX|1qfw^{It{s?b2j<#=xprV#FUje(yMgBCOSyJD=cA51mxB4e0RE%- z9CDs-!CZIDGhBBtk6D_F(&yVtX1?Xxp)P#?WyXCL%zXpQ{ek7Y1~`?R$^QGEwGH0& z!S_Lf7Yv?8-vHDBvJf4Wt6Yp3ghAw=7VFNzEh#x+{u3aog?O303hZ?L5elOZ#t#-=rnJh*D@_P#mL`thwJ{V@6r3S zzVEN`!NCE(!){RWa&K#cS;SojP4Y~)jl?fh@97Ocd5HLf#~XY7Z#qrfDsO&Ie9v7( zeixpQ$Ao?$>;%GoAp8a*9(>0!`Lf@282lCA-}mQz=ioo?19|$Nh@hV=9CB-{{r4+~ zM}7EJEKmQpsn0ANGAfoWYd4aYZnnkh)Fk<+53dh;ojYF%*KW{fVpo+9kCJ)n3~wfs&))IU#~h6%aQ$2(%F}7 zsJ(V<8gyDUYZKJpJ&|-;TroRVs`Bgz`tYt5#$LN72A!{0y&Oz#ypMDWlzumM@0biR z=tT3)v)7gipwr@t)L>%H3;}#iJ2fV4@4JNp=v>=iioLce=@ck^DkgL)-E**As8gf6 zy|y*!OgmLPCVWMz-Zz$XayN}gors7z(y_oC(pem7ZLdxEiioyL9eZseW>4hM6TUpr zc2CqIB4W1JCUWSBIz~j>?X`(oc%lzPL=Nq>iJE$%&qPEm?6rx$;fXq0{X}1ih(6$n zKJ%M3yja_(@44*02Kz9v2fQTqTypIv)`YaabZf=*wYps=V;y~|t<_OG?8R{3$KHe) zdls>pT;eFf`dZvuuL z>_fn?kG%;PK9N%}d}40`hEMcEFnr233OV*%tWSF!XNUGaVE7b%FS-4)SbNy-Tn@kI z*M7IJC)Ou_+Ik7=Lz`pzZfL>q%iq78_^xEsR>(=mT}x}wkn_@ahlk${-P`K?@pneU zme5ap$28>OwXl;|gTWVn$1ySch1_xQd!0Y}eq^aHV!(G{vwdqP;WrTRP~UbjLqCx> zsUzBpcoI3}?@Wj8f8uwhyLM46?(TlQ_sjOjiKpH;z*~B(8u5oS_j~sH(TVk_+{*qC z|MTCOo_RR(k6gkB7`cQGu=Q#Gwx8Jggnb1$?BfRv8U6-_F0KK?hNw&8JMPggTT@l^ z*6y^Qy2gA+T)bhq;7HP2#G?jJ4#w?mM2voPl5+-3^{zTK74>-2R^{Cj~_5(_!}6y@BxMm*aE{ge1OqLA@_v7C+v_9 z=%Y=-FZqDn>XHvIawFm=ACM!LqP@`PJiv}(JMaNUF7X3~3_e0T8OaA2Hf;PPhizFe zFxrRzpo8Ct3-N)G6W9cE?Z9Xs{DF~I#0Ew_;17&E!5w@vkl}A&=;9hMa>+hmTb@&i^Q)LR*9ydWS0K*8 z0&za3aTW&qR#%JjG%e2AH2#kNaONk@<)BY_z?q*o$J63`Fa2E6<_)<_A76j3@g?g8 z#{7vfAQ|Hka?CRrr*4i-zsK2}U=G7PiJbf&_TD>QtK#bW7F48)fPjf5_68bzIoCet zLNs;_8XI75QGmkZ5*uO!D~G|vl3b>8a-8hReX#N*OdjSRSa}jw zo`jVrVe0G>th(F?5I4G+10+mDy|(wH{Ufjzp`{P-zj_O_G#?S(Wa`okKg;rS@B zuTSa;Ij5{Yu{g*0U#wYHTRj)W=N8<^nX4Mle+RgaMyRz!E4Z9h?^HEkE*Lfe~4Y#VT zzSC=e;{z_Ptu~q1-T0FkwbcuE>1n)uO+&f9a%O zr2n&zv+9K3)>&I~kFBllQFy;lzFf^VR{rdVS@q;DH6`!6OIF&S{o;nkT_35f4jaFo z@vz~w)eQ%)Z+!d(wbdavZD72^gLS3Nwau$lUHgmA>Pnm0lj_QAue+#PYJjD4+$Ghj zG{DkEozhQRou1y)+NI9npYCByTbq2eyD^$&gHDyBAN$^ICzRtE)_8_Bo?(q=SmPPi zc!o8eVU1^4;~Ca?hBcmHjb~Wn8P<4)HJ)LOXISGI)_8_Bo>k6xkUirB)_8_Bo?(q= zSmPPic!o8eVU1^4;~Ca?hBcmHjb~Wn8P<4)HJ)LOXISGF*0>cjW@N)yf*JFSLs(-N z))5++o|I)zd776}8!_#s^SF3P<%`Rc%B!@Svg|2O^J;1%rd_mY9U@**`Qq}t<^|eK zS@x8t^FnGPrd`cJ*o&7`zPNcx^BVP}EPKk+c`daO)2`-I?8Qqe|DWbu)uXkX>?wyA zougBG+C`hzc;b(myu-Wkl}``fxL9_#_lyUvx>3=-!w1F>UDv62?ROs;AMxe}#SdT1 zG0r|;uXy6akBwLSbe&@TO+PWdVES6chEIC=fS1-Nri^s^RbKg3(RKERW;1H;szq!! zr`=edQy%Se>|;GS^~Cyf>W}T_v>Wy0=!rUWbVmI-`lDYtekB^RL|c|<&Jtg;#K$c0 zJxgMeC9%qq7-mUqv&2W0 zm#;dsveXe<8Q*cnO_fDn+uo0ED+ih$7W`1jB?mXv9PP(IV=fD~(-}1P-E6pc4 zFMrXP%JvUCZ-2-Am9{%MzkJ`=%6;efwTE0>RARe1?Z)z)@@Su9AM44fC)S@+e{46W z-KZx=Pt=*CGwRRLAN|VlE76cA+VVtmp7@d{KIVzWkLOR%f8Y3w@LlCOSHEq%<=Dsay>^{yd}+J!`KI0eZoGM)C-O!wzHHp=k*D*M z-h1AdfAin8#ow`mxsK~$>Z4wmc4!Z#eRRO+LLZFYsNZ~w`t9#gzg-vgTYXW#wG;JQ z`%%B?iuz4&)Ng)7{pMfPZ+=Jp7LTak;uQ5;{G$Fm(QonI`S=yNck(9n$LEnN@bv9g zvwLdp7Z23WYqhfRN_Hr{;f z?E1Oyw=!-y<@@^my0s{&4&D`DbIA8}IVL8u=NwI3F@$B*;zT|VD% zmg&q#e7$o1*FlkQ+MuC)$E{2IV=mYsS3O^U)-6~4w|6=)SG#LZJ1W&&lf=I!>6c34 zVc> z*+lz1vCk8G<7jU-L0g4uX$wDLG~g$UHvEL~G1{B9Xm6UMz4;RDbL{ztYbm2H7+cza zse`s*>W=mn+h}hwkM`CV(cadm_{p{Sgr6|6N%-N!rarQb?Pz0TK4ID0J(6fMKci;z z6Q&OnA1yAS+{Rv_S@!rMdwet<*auxj>{I#(rmu~YJ}n|M9$@vmuB{~38uOfnPM&FE z4!4}gGaKbRSMkgS^IXL<8_aVR&ulQyRXnr7JXi6|2J>9SGaJlv70+xi&s8BN#`qZe z(HP%DOpLidLTrt>KmMKT|70zp^+x6Ay2d-^yzMQ9=-=+@-x#lc<^A<*4&2H3+2h94 z|LK%nj2GNGvi|mscQc-I!tnZEjNaY2cZ+N5KcBOQ@fI)kukSo#PvddxpH%;0Kc8Q2 zx_)o&9V=%HGS290#%aQuJM4Z;uB}PxtV!CcNi@_X+G-NbHHj}ZiH|jj@Bde=6_aOG zJug@O9s2;uy-BXN{v}r@_i`n<$1BObUrBO8CCL?)B!^Uz+)_z$P9@1jl_X#NU$xHs z|7$OcoXdU6TuRP`nU~19F!LLG6L84E8G9CR*n`Q~%YefkOvWAu9QI%`_CDaS2a~ZU z0*5`AjJ*;#?7?L0p}=7eCSz{}4&yrGxf%{RI3s7l;W;nkxzzaeUuHa)!r?hJ~CxiBNo z!XZayIq}O^iY2o8^*L7#*8s~!dNn9EQK*<9QHyOlU5I7lH7`Z#wvT1Fk_g#OPI0Eo+iwg zXRj0HUSJOt<{n{h6z1Mx&lKjKifd-O*W#Ml?m==ZHr$(W%}lOkpV`XeKC^M$XEu)e z%*Jt_**NYq8^?WS|n0rdYJmC7p5KBgJ~ZfFuKqOqZfay zJoty7a9H0m*BFQOEpw1@Sl==?8He>PbCz*f-!hjOhxILUoN-v+GWQwNKgpWk`j58g z&$#CQr{@~R0XA_j-8k;08^^tL|YtP{}cALjM*0o`(4KD7lnN=WA>54{+KcQOJU#4n0=?PpJvQ{ zRM=-TW}hnTzZtWC753$f+1CpDb;j&>g?&6@_QAsbo-zAlk4QpB}=b0>FJsV=f+E~}JW>%f7rH#q) zi3Zl*R?eJ|XlAW$<;)?8kM)V~^+`XnXKVJ%rQ|#GGe?mJVdgIKBW!!EAvx? zIgmVS?0dG(Va^PDyvEF>s>k+zWBts%YL_`#dYG%pv((8PPM(FC+mrFh?<`i%8i72E zP5hn3IR4IJ9Dipqj=!@Q$KP3utHwf&xl9-e2DJYc`)QO@&kk~i%4 zJj!`qPV$WXo<}*)*GXRD8Qk&}zx5=!H{alK&trS8_f@{k_nzyHyZDp5!{L$dpIw&! zVdl)zzW;WU%X+%Bcs1YPTHnK&ef;0@@Q<|>%JT5HvfXfvmp?u}4|N%bHuK}|pKTo4 z%tPB{dC*kaCv!(ZZpBB|@8njPbv?NiX1z~tg?SDjx57LhkXvD%8_2CN&lAbq$G)PK z^Zb#_l|?d#7RlUNBy(<&%*91AM;FQ5T_kgQk<9f)vIZ!UwLy`r8H!}hQzUDlB3WY; z$=ahx)+9x;RwP6S$ggNH z4*3;r#v#9=**N4^d@&CB6(5a5e#LiVd>4oON}uMm8}b>kG7fo;7#fHCN^FfoUL@vT z9)1%`o+;=fE4Myscm|gPCkYCot%6M^ZPmZ6y|qz@+r*k?c`IK-{HxpF#B`KGb8t)m9uA%JY#atS~>SD z`+!`_o&ot3<{nSp$Iv?=mJ^cqH}npP<&flk4|0yxL(WN_sSENc^|Qwre}lH)bCTbE z`2EIg!djBwZ;ZnllizQQ!`hSIZ;Zp5l;3ZR!&;T!Z;bgj|4m!`9XpuoxE`iH>V;{C z_F&piei!5S8!JaI-%DUqshOMS?|ZwIniJuQmoLQjomjN5B=)QWi%|Y=d7mNf-`ZX` zW0ZEehq#wu?yaB8@6O}`X^#7x?9FTcGbbm7HJ;g!lgL5X$2FcYIf)!Zd0gWelat6n zl*cumF*zyjo$?!m_EGKkh(v?-Ifwh)H}FGmg(<#_?IqI6jLR$7eC)_$+1|pT&$>FT{P+ zCH`(0_c?RcQ{*!A#Aj9G_^fIipH+?Hv#N1?RyB^#s>bnI)tL1ZIg$EVZ^k@n>(H2g z$d^1*o6Udv@7*!y+nPGgHT>4}lfRo6=eRuCN6nLcRD0%#b20CfY5&unb>duX&pL4~ z=AAO_qw-Ff_E&kQO#809Q>Oh`-YLuCT%5C)5Z5X>&t7p2L*CUsYRet0%6Vtp2#BvUa7J zXWY2fA+=h-^0{c@hI4Jm)U(3pUdq2iqC^~KgQ=oyHDfuqvePA+-i9v zKDXL4dVFrRXZQHrYR~lXxz(Qa<8!O+0mSE4+Z%|_t+r&NGDE053VW*?v5t)BQ?Z_oPidEcJ(<9>oY>&N|soI2uuf<5cU z{RDf~S2yh~}nQBgn7`f*<_=UG4Q*X2Cx%bsU_)x)#C>gQQs?eeTo{*vanx5=7T zd!DRmwHKO`pU6|#lefrUF!_wU29xLFzNM`*$%B-W7vsLAtxMy6=@Q?oNwjItlWVmX zYU|{rE$yA!x;oLuI$WBy2a7M-o3(X&(s$acwC9v0R@ytwnXi)A+I)tO%x_6wXz!Fh zYAA2mJGJ*?RS)y3`iS{f?J^H1V@7+Y_Fir>#B7f-YGf3 z@+svZS7@)59Af#Da`p_8oMZWva@MfQb*ycZ+@(EI_Aj+}O0Fx*lf6@NV_8qKcS

i^bzOL&J(@SG##DqhA_yo{@O8CUT#uHt1}#ml&gmvI#@<0@XpRlJO= zco|pmGOprfT*b?{ikEQ}FXJj+##OwGt9Th#@iMOBWn9I}xQdr?6))o|UdC0tjH^V( z`)u^#GpCHJ#F%`}lyQ~V2HIs@CAOJ%8CQwNNV|-y#6F>2##Le;(k|mFvCsJ&E8{Bh z9MLZ0D)F4sF5@aO2WXdZm6$WM%eYF+G1_HZ#fNv*XpiG6@Q>pv$jLaag7|S<1vweV zRnVR|u7aG5<0@!>99Kb3#&H!KZyZ-aPR4N+^iLdDK~BbT74&BuS3yq3aTWA`99Kb3 z#&H##uQ;xPoQ&ftIKOdR1vweVRge#HTm?B9$5oI&aa;vC8OK$SZ*g1&c^Jo4B4b=7 z`ry4aZcCPNmAJ1Qd}LfDwvBcfSBb|$yNs*EW2arlRbpS!F5@b(Z)ultm3S@^v`5BO z;<=+;##Q3Erd`HWVs6kb<0>(iXqRyn+z;cpinsUUI`O?#@0tG{@38W2zDeI<4>)i} z97~Ds>?!(uQ;j*iIP}XK5r0#UIq10?vg;-3-p6P20hAYvo|m5&=H@l%aC6};wX*pJ zYewbLk(XtC}BP-CX&$w@2kq`#y{L%d&?GSB08>x3BM*R-Km3Cs7}@ ztAB+{E2ih3GSTBHR(bp}j+E_MOX78B*G>|zDZ6%Z@mf~_18F)p6HU_BYXp5 zx0kj}I~Po3obBGeG~KCcHg93_+i#@nzs}~WopC}%KWkto`slW5SAUJ8@$>rMom|j2 zn`ct-@?(-lgU2yu=?hQFm719yW5pvMF0A-uc8qmJ%&EIt=iT9S8*hMgFQdb zulRlzf7}OsT3;3Vv-^JcEPd?r%-*Gc+rn!WWvu>cSAUITKDoH9`Q*o#=CdU3%VI8# zZBT!;tG~vv<4s~e*zx9K|Jd;sZs@nmk4a;HT3@BHpLJWcTmNtH|5Y4`Z|B#=^KR!i ziTPmXH;H*-=QoM@W4W<3=9O-%cJ(M+1#+^ zdvdH2#zuMJbEn zlh@~G^C$1D@b6^q9of8A^;f(4Yn=IyjBs~&NaQ}!qINe{%11& z%XbWN+plwar@=;bQjzm{#Nb9{eW7xOatrnaZJJuBWr-l5D$_rOt? zk=0-A>aTIGTiDQbd_3_u-sy#jdp&JPzHazY?x3r7AlJXDr^`Eh9pkJ2uk7NlaTbkx zB5D2cK*p*3`VaQ4uAbyQAF1q`Zrzc*|I`NVqTBW-tH0XSU*j~sv%DL6cJ}<=aP8)< zMvoI1XOz|09vtcnytn?ttG~u6TXBTj@9b<|^uA37y48<9&3>47Zg;ov z@KTKVX?}b6>CIKi>aTY7*ErW7G{8;y@c9J&-*na}x2D5+U+wCzagOM4tb1ns){Ob#lgGQ>A8bJ$UblyPYs4>%*`sT3_wJWpk=0-A z>aTHbe|%nY;KFQf`4*GENE)v1&G?@mS>27^@<{TF%UZg-_RrQ3t@yTs+v$iZwClEN zSAUJOxx|0_`trW-McMuKUslI!^2sMK=Gnh|m$v;byZ3fk`C-~9=}Wu%t6lvy&KrB) zn9lBS8n>-=_{-^=1=;$ADi@aa^;&eJ{h~{%`3e_j$Ef~lSAUHY-nAJgykC>Udp9|} zzmwHp?dq>_x;7Y)Tzqi$dp)g5o#dp&*>CibZ{L?2`c3v5{m{yr^H+y&W2wK|)nDVB z*1MhS++ZiRZ3oxf{rFf5^40^YxmRw_`lQ=?UnPfh%kp8?cef|6o}4|C40`kEWccLl z{X*lYUHvtV#@GGMJ@jCA%cr}s4aMPptJ=8s_3P8WI6UKx0(Z>pGQ1D$P;P>|{K{s$ zUdEIe?)rT;n_R2xN$$i4vUMo4J00y_{Gt-$w{PFt%{yaHvc^%n`fD7G|EvA}Fu~1z zbLSNIjfT|<-29#A^S-p(x&pWGfFb;SJm~5IcjG&~+2%3guXgpaTY7*EqX;y_XyG^?n}hFWck*H|UvqXvQ}0I)9{_^X)XU`m0_2 zHBPNM`?zjzXKSgtwzY4Izqx}$U+r*CU)R@vkbt*4ZMge)k88=L=TC40F3Th9wrW>@ zjid2@exRl+^Wvf0*ZXhPaSIl-C2#$91Gh!L{mIjpHFnE>ZcSEywX46zS^Moy?w;k@ z8lp?;?dodYcL?Kbn_t)6d2aT+I<-YZS8rcOyZWnL{WZ?os_&&Mhh^_O-Tm!pozt>= z&SBS%NUyj&dq3*kBF$zi;jtZ~$?{u)Q)>wcGgS=xQJE_?PU4nJSwaSg#*UBJAU4u@zr1L>aTH1f6>>yvCAsPKk3|4 z+^Ac!dU4lXGTO~Q>`dDI_Y+*+*1M3^U+wCzaoVpQ;l9~nI=Agr?KF4CsaY+8JMCMe zM}&IIhfN*i_L!X2>{5TVtG~u^vj@AueX@1;gWniw^*}C6&{u~wvbDMs_9kCFw!mGz z<7ECeslVFQU*lZ&!kfvx|IWsiA9%c?n^-d&Tdr}~UheKoTQRSC+;*7TfBr7y3%m7n ztr})E2XtGttG~w4_}l$5J9%gG;f#6Pum#CMZ)W%HHOv2bUzFj@W8 zuKpTl;ffi_&ErRK+d)0%Bo&5d_n-EUElhf~$@aDXj)lo)9}c09`m0_2HO}sP?B|y+ z+nd`y`b?hx<-P2;tj5G`ebd{Hp}q4LpQbIpIFYRWYFB@a^V7Q{{5$((<3Gc!ZrQ%! z+dcKZ9_o88zL)2{_Su8{vN?~E)nD!EuW`QL@&xbB&E5^qJo{unb96So^pJf|VEgm4 znkt<(AM1CxDqDB2{%Ti$jWg!5-TVa?W#ghxPig6wkIUW%*B*43Keb7AAFF-talYSo z*}Jg%t6lvy&Zq_-re_b%?sX%ZZti=$klm9XZ@j&IH~DDx`K;l)`rNqew^jYsuKpS) zXo8Fr^geRX0m(rhBnRD)9CS&t#!`HTz}HfqAEuaaX*SJts_i^@-%xmj?2b=;ltW%>5oP=3v+U&g>cNmnE&--Zl54Jx~1A zuKpUQ)TQIxnnfLX?VOPt?ncd?MQ-zHf9Fok>R-+AC%B27HfMbGSG)RaoR2%$y7IBxk zG#|eU4;a^Y^P+6L)M|z8)-|gYrvA^1UHvsqt1t6i;gUUg>}#)Y?;fpLmHgRT-Q8IO z*R!wg95v9Do0`=YQ-8IqzsBi0>G9mkG|QPW0}7H`R)=TBryfi0K6nuKb@+_3?wY(T z_YT>)zWeaAHni)uYFGaYC62~7e;?zRzmM_FKaKk}|1`G8_Ei|$soSbu{WXrpw?6T) zudGje>_h7lAN$t&(8oSkf3>T>#<6qiSGSrIrT9&EC+nd8TD7Y`fD7^Ngs37 za?-~fww&}aw=IW#%z5=!yZUP!yQX}+*6f<{@fx&i%ExQdu0bEKS@l=D`fD7!C-``; zuzP}!_Yk`$_;_!zdx($s9Q9Yb`fD7!*A>Qlpxx`zcyF|OT^jG1cCYjCUTXI`AMdet z&-C%$t8vt>{u)Q)>wfK?pUVCJciDbZQu%%PT@G_pcs+*sC*&|Mg&gLqki$F{a+oJW z);MZce~qK@b-(tT?&5E~{ia*(tn3-Ue$!oiHn3-aBtA2!zuMJb_DtpCGnhS7x%g~m&tNV-v#Gz@)nDV-Gog#m ziuO$C;xnW@6T0|pY0r=@K69$S+SOm<*fVVspLOk-*2QOFd!}{q+1Q?eU3_L%f3>T> z#<6GeG(M}_GkF@H;q93`jnDS>44=kle)U(o`fD6}r%2aTI^ z9o)xvb9)E(@txh?!F_y}w|90Q-|^L7?dq>_Yz)E2u>~7LFs&yWbFeW4AIBnW%)!So z3iVgJ`fD5;1MzWe#Ku7Edl1=}iH(8yIF@2#CO(d_sK46PU*p)=P8!F2Y;4EJu^=1U z@o|jE#&&!hJF>AIAIFqzjL65aCXJ(Z_18EWU-xTcT&awA{Vv-WnwRmk-{mkDk-r^b zo*_BRKO~2FiR3U}ksRhjk~NOn)nDUieBG~&VJ2~G)5b89IOb_%m`NN9wK30J93xeK zwX46zu`yT|$7XE|*2OVf8-q>aSgwuPCUJ~c{nf7i8ppam{WXqh5I$-Xra}0qS(palqn2Tsg^wDC`m0_2HI8X0K58qb zq4=n|n1O`go`KTY69^|90WO|T~dXs5MKI%}qt=iRJ z<7j--ynNKcO!M+lBQwp*NA1isG9NWH^;f(4YaG+;eAMzxv-45oGtJIN?awqmA2mVs zSG)Ra9Mc?q)FMrD^iiWU&Cy5g(lkmRHBI$byZUP!(@cHTQcW}UQDZgD)JN^rG*%xq zS@l=D`fD81e0|h{P4o3pBR0*~NA1`&V$-%VOTHFVR&ebm-9j@s2<<7j-{uW9;T^!?vun={~L{=o0D%~eR_90r@KkjA+U zHdi5ya~^E2f{$|{Y_5Wjb0loegO773G>+QUU*l+e-LK8rSQ_VY*qn{RILE{0Y@~7S zht2UwMb zIQPcp*d%dIj{2)z{WXrw`AOnjAe-}(#5qDX=f}mlLpDdq#W_XluXgpfk+T0YL*vN>8l&grr_T0YM8 zvN>Ho&H+<@wX46zu{mZw&ONg^W%ZboHMEZYFB@aV{&5I z4u4ONv0t0RnZ`Mv>aTY7*Elw()Nhz;I{YXf=b+l0Qomtt>cWOT&RPAHzu14}FL7*6 ztdDbLZBDF@b7*Z&tdDbRZ4RxEb8gjN?dq>_Y_6}5bAWBGua9$sZLY76bB1lMua9$y zZLY76bBt}yu#a<(HICZVU*l+e-LK7g_A>wZciHAtdzoMTyKHm0eVpTMbGdz-`)zZ% zeVh|+bGdz-D{gbSeVjvXbHaU`Tdr}`uKpTFkL?m%-g{`4T;+hNfSG)Ra99z@j<5~|}(~-tC zAhxC>jcY?zu0J)6Yev*x?dq>_Y<-H4>sD-iis=j4dKO!s;^R6OTc6_N`WIW<;^Vp) z-B#`DuW>ZKt-jgtDSUHvsqug$voHmgc|+@EjiGsHK#$*15t`;GN8DhwoV-nzhVGyhu7 zd+B&kf%jvwZz}1wYFB@aqw%j_Q^A+twlnv8)e(9AgQMG$Ut6@VAJnD^xzQ(w`+F4jgdG*p8u9`q@QF}z;#PD5s^;f(4Yn;Io>-%z7wPBoBDpc}= zzBrnE&4Mq}vA6doFFZ6&-@kbXS^d?n{u-yryX}0%iP?PACX3qmqkGk7oZF|j@DB}d zPQGt?17C0M{$%x6yZURK!nyWs&ohsq{=0C^B)@R4CCs0rz8mBB?mLuuwf4Os{<6A- zT>#tGLrw++`gIb7r9a8DqszuMJb z;C;Yy9v_Jg5lf&;j zIsCpeet0$@>$YlFe~qK@!!r!yhi4dac!nW|XCAWpt6lvyPIw06w&59!9G=0*;hBxB z{%Ti$jT4?xxovnx%{Y73C5LBPvihq%Jku756P~eY56{@-@Qh6k&*WtFSG)Raobc|z z^BCS8$l=|AF~hqwU9F4F04e!WoLwH9fhj(Ohc&8?-zuMJb=u6_CT20OPCwuk7Nlal#k{_!gyDT{tx3_3QrojOmfXm>$~@#sJCcuXgpl&Q^a5G z>aTIa7&W&IW7Om@MokW5+GO=tyZURKFviYp!x%d`jIoo$m^@ki)vo>;Cuk7dHfRv! zph1v>Wvc({WXrp*Zl^)i7|`ALC>Op zaX4sayblEJjMq!h&d5PKBM0q_@q-3O);MZce~qK@f3@FCTTF1@2pS^qOF={A?_R7zWS?O{WVU| zpcyA<&{@n(%O(fSnymh651Mt6I6*^a-v$kx{U0=RwmE3-Wc63O`fHppAHbu3!h8U7 zm=BP`9_9m(!(0NgZmV|n*EkwK%z5Cx!khuXgpX5@+9del4LsoyatG~txbB(xdm}^81bB)MhZW3Aj)vo>;C(M=N zwqdSR#@U=Ja+q61R)4jJxm88tgt=a{hq+$lFxQJ5=7y2gU+wCzal$-0Zd)7<^YrLn z91e2=dHsetf!sFC2_%O(f#fhJkR0X~k~NOn)nDUieBE!D8_D*Bxsl{BH_!raaT_pvayllRXsx0CnPFc*~Z)nD!EuW`cMRK^c;Q^{d&Dmlz$C9A*M)nDU; zxwYIj%&jGdxwYgl7niL5YFB@a6Xph|=$|k*m>lK?lfztM_LcgpUHvsqnCHx#3GaTY7*EpdzBexB89m$~{V`k6lI+8>EMzU_J_E6WcXq>FBBkf@hKRL|dCxu^;f(4 zYn-qKgz>`~5OP=pLJn(2$m*|l_18FI4GXsoYgou(4GTG}c_FL6+SOm9M(FK!&)bDSTjY|IBHjajid3y8Y{*LYre?Uvo&Jmu;z;# z)`%7HSG)RaoUmq%xfIr{k;9rba#-WW`0B5A_18FI%^iQU!kRn2bA>f`yeEe>dfb=# zt6lvyPFOR@IAP5o^}DcUFdP5O)+DkG>L1n~(ysm*C#-qov4=H}PqJ>ScJpAmK^HYl0%(avihrC{WVUg zXB%Up{w+DwvyCxP|CX%&q5f?V|4{#yb~|3I!zJ7CVtp>zju-28$#%S0&r7zx!a85F zZmV|n*EkyA&MDR!^IY3G#TsO?ol~q$W_-&5tXU?jzuMJb8pN7$wn6>XuKpUw?g?0{ z&SSTG0@ko|Uv^Kx+IF(tL$KzZto~|Oe~n}JG_18}e7mP%4L;fKX;_<24r}nq>aTY7 z*En{sMhyXOYxio@79iWb8Z`&9_*pFia;OzRwtGHm7mziM+ST9g`KW0?e~qvEwcjk% zPoPh6*nSgHpMn0xVf)QRZ3_C^Z!T(9knJ}YwJgZ?8;u$lWc63O`fD6}WbAlowrYIKm*U+wCzaqO7~wLzFm_RNEtA!K{zK`jxoJtLvU2;-~2+SOm< z*fSeyn=p<&v!Uh**`C=@3x#aYc&L#=R)4jtzs9j=PSj>$+w7SWHCxE`%!yhq7x*^*; z0&3up?VSR(afUHvtVz2l%J54W{<9MtL|+dB?w_>k?LD6w_2Wc63O`fD6}UqgK% zo>O~YL){_9vG+C9BO=@T8tN30?OhM`i^#gI+SOmKf3>T>#<4L0)Ue{V zHYVU~oh;eL1W@yeY-0$hg+*3>wX46zu`vzQ;7ZYc8`D5-F7}m;X`p5of3s{11hu>v zU;Wjt{u;-|WKctl@oh{7wZ+IbCWD$|WE;alEi$tDt6lvyj*T^;HX8H9#+pzwjcj90 zsHH}>u_n}5BimRLYOj%P%nCKxxL=KQ zqUIs(HfD=jh-4eHMU6zVjq##(B3b>_uKpUw#+<#aOXapU=8Rg7WE*ovjYqPLQKR-F zS^d?n{u;-|%u#ca+uE2pYEhDH%p5f;$u`E0+LdJWSG)RaobXKtZX3SWKn~w=AcyZe zki&N$$hxiC)nDUieA75ktCMj|<3J5hvS}Qs?MXIG1T{a&>aTY7*Epuppw=k2HH`)} zNXe$rpf)MlG#%6|C9A*M)nDV7-h{fTyp~OGLOoTo=}oA!N;bU-^;a3+v?|nPCF{0o zSAUJ8@l8`hZP*0&Pt(*;GnQ_OjAZ}WcICT%BY#lcP`VEQA?TqA8IBuzWS?O{WXqh z<*51W(f_8EqZTyTv~tvlPGL8#9JQm#rj?_nG}$zF)S717G>+QUU*l+e-EXLI%{CN= zLk(^E7l&;w1ZsNI-{wM~);HPaLZAjX+2%r^HaOYlLZD_i+2&NBmN;4Cs9pUvj>gyh z+ME#7HfKzm6M~xOWSbL$TIgh(LxLLVWc63O`fD7U(}LRX+}7r_Se=k=WSi51TJdC? z1A`j!Wc63O`fD7UlY`pz+}7sgpr$?9=H#H(J=x~)pawo!{nf7i8Yg_0huenl?~ucH zdC1{=J!JJ)yZUP!n;(Tb|J>H*N1^^d+2%*#y8z@+&!22_tMDBGvTm#P@O^O?$hxiC z)nDUie4BHKZ)Z5{*XA7Jn;K-BbBJ$kust?M5#Qh-tH0XSU*p)ENqqZ*F>THyz6nCM zIg|KS2-)UXI$IA*R)4jtzs9jSpZInOx3xK+_@)Wj=6vE?CuEx=if^Eh)nD!EuW@Y7 zD!#qKV-MeCVH}&Yif^@$!#7#Tzw*z%?NZb~`&J9>Hs==Kj$wS8bBk}vkZsN_zBNO( zIlA};4O#uwuKpUw<`UzZI4RDr%_YXSa>zE97~jxgUfEn?d|QXVgEp5K-`wH8Y)&%1 z#Y5IOYFB@aqw#gW;Tu3~Lvc8KV~GC6VVf(CZytFZZ}_$m+2)+%8%boFD~@j`k!`Lx zzNy6cHs{>gdRVf?QM>wU9F4F0wK?;N8{TX8GK8Q`?57M_{JRB*2v)7b7Wgn zgKyH2)nD!EuW@XR559%RZEcMYzL7_^H9q)u9@*9e;hTD7^;f(4YaCmz8s402YZ#raSIvCHU+wCz zacr%nv-PUX6I*NPY`rS;$JSapTd&HzvbC1Z)~k|jt);W|s$^TU>1@3!_p5Q#uKpTF z{t3s({?RyUSAUJ8@pZr9 z9I-v&9FfC0$~ZfxWc3fZQN&;4gdC$!$T4!rF>=UBvihrC{WVUwM!0RbM#$kBA%|;< zto~|Oe~lBaac&!~adNoE$>E+rR)4jtzs3poC~h0>QRHxsB8Ph#S^d?n{u(FTZ<#aU ze#=}6_gm&zxZje)y_);dZPl*+8b{+Jr?Wq&Ggb+g^g~Gwl;l834wU3TNe-0cz~46q zPIskB9d%>>JLct;D)sw3{KI4Ggky1kl5dE8VsZYgYv!rA@g zZ`%+0Z189JzkIJQ&hNrTK7aH#>ksAOAHV10fp#MKeEqN~7cpv(0;RFWiOq3do&qmJpG*={X08+la$)Bg`alEmOk%C)33|6@E>gZUfQ!s4fmD#fA%q{73TKtG3_nZ%$928BxV;Y4$$*KAAqa zb~9Jc?5^}r>66u8OIq80ZyZPx-)f&Ew(Yu+ zjeX%ZzvP*W19M_Y+vU;@Ll1Qg64i_<3wmiv&JaLxCNyrmtd7L1hk=K^T3Gx|vZF!s^pOM#= z#}4_7ytX`c$YjZg>e73w!kjKbp%j*PrjC{7dPLRjQXUppZd5nCvyw2G@Hs+!$Cgc8GoV=$` z$P@Q|NhIQMQFUVe$FtoXZ=#3byTLyC0bj%{6shZC?*;_EX_Ua7y2Qwen>(;Adi#K56I&r^aJuZ3H^XP&V_zJ z9_K+Ezk7Iwu`!xCzc^t009P$|LM0=6PXeZi>JVrawUgUAO z?h@p2xbB$8;ksiUhwF}c9IiX&ak%c7$Kkr;ZyL@o&NK2j+?SZg;l9K?4)-PIakwur zkHdY5c^vLb3Gz7HmlEW0xGyEhW1L5vPvmj9FXfQO;l32_&oQTQul|o5-Y<&%{!-%q zpWp9F`lqCSGzXeCnQD3w{+#Y!e6~pf>bCO)*LIiN$#+g0hHH=4--^4syCqZe$P;U{ zb@&T^*zj*)`{Tkkr4R$LV9a7?ec!Z6g}P!-#XpreUgCS%ug5+R(|oe&>fO|FuGkat zPb3cdEyhQGlEbl*(Ff8_oR`>sH)-O+8?j%Uuaa~3&pmhX9A^K`&Swdi^g~Gw{53gH za&P?S-WyBK-9Pu-W%sY_d8mX-`k^ET{^}e!-Jwq(f9!?2jnB;9ttL!qknFJAX|$Ji zHziH#W^2oO-Trm5%a(`JUOu;r>vUpc^2uHEZESBF@|2^xxH7js#dp10!v?wwdW|Pv z+i;BQR_kW2P1$|d0x;L6fX#>RBk-|p$=KFndbABOZC_;U%i2Ij8?0?)w9VQ~Mw{(e z$T*g$A=kU9(pQe z_kA8}YW;{md>7`iW1r|dSi?RY82gld!+vSUK5@+Ou|IehCZnBlUeb8J@Q$y%sgH5L zu~+K*{w6*~birSJU6;f}4`hEz`u6|te)zxl{F2|eQXEH>dvD2aoLwCF%_{kg<5>MB z`5o7H@Zxa%tzUj<)di7f7_UAqdq#czpgoe?ju@FeOPp~@a_Y4HT2Zb9glSFOZ~{-^zpm)baM+ICbwHN$Q_-Z)n4uJ?g+Q*jZJC) zar+6b);=@&?ArCv0{6m256lbqQ#YwL+J`@$2v+j4T{cZircA~$nf63@?>t8bZ+xnM` z{?wEUmgqk+xnM`{?wEUmgqk+xoWw&LfV=`Zwl-xBjI+ z`rG=KjQ+O%C8NKsf7u4~xAiX>{cZhAMt@uXlF{GRzhv~c^)DIyZT(9|e_Q{O(cjj; zwk|4bTXDGjVH>V5?|CoCw#D@iLVsKTlF{F|{$WRdmNSoZ(RRi^f#`5u-y+*T>oIZ zA9!5oIZA6U_y>>g$J1CQ$;cDo;VT>oIZA9!5oIZANa=~>lAgp zU;VDhyQeo-{EhEuWW0CEyXPO$D_=YAvzz3-Y?J7fk~2<^QS3Ng_Q|GxCmr~FoAUCm zx=F?mD!=e(d=JIgLW=W+ead-6zQptRmy97)e&NviavnFy7{YIyFB})oT^J9*vBj|w zGR6;N4B-#W6WHi{;kXzReJRhwzZ#>^u?uTTY|pQrku={lC*^#>pXUzGnR31`HiG{z zRdU@Ge=KOD^H_4-h5XUH(tOiA{NH-r;Tnp+!6lqMiKx1muqXFpX_gV zPWU@8uFlw=Ql-9bG{HYJB>TQXji-kB-j6TfSl2nNdiZ9IejyJoeUSftOdadjQl;Ko zRoCDC{Q=}!FKp&7y`dX;dhk`_$y?ul_|hM(rZu*GHB2)quH3Z^53nUHjak*J|4&N{nxeAx0hym!ijIsP9HBfoc7%t zf0|aP(}z5HaW&s-c&1bRGT!AClM));~$?A8r3N`4#HNKD6WA zr28%RavA@^)yJ`)J5Jx-cX-&5r`h*y_qFfb;ygZeOHco8rFHD{cSoFRW1_c^&+0P4 zA3QzNrqEuyw{Orc*6cCEj-gbkzbd}we5DU+y7BiO>Jb0QLv!w-6ZRnIZtLQ{A5orM zX3#*_=D}<}^^4zg_y)7`IKSVLYy`?+kLi z)@IsWzxiEVrDMynAC7y#xiwerPVVyPZmwOw?3)v=>iT5m+H9_$@;|Z7ns2jPp6q^k z^mX>hYrk}IW6#KR=Bw7UcH6z2&Fg$&S}k|O-iNYJ{^Yj*&+A(AC-1pD|H`}BHw)(; z=lpxyW#5Jw^G;`=}!_^@63fuf=wneVQYp{6ye}6BEvz_KfakxRJNxt>! zkC?Y3?-=R#doKGP;j`bI=ziZ&~)u zr?>MaxjwtE<+-R}-0JeL7g5LnJ z-TM>#27vYV>(1WmFkhSYO%WfzIdQ-EEsE{IZ&Yk2e!F7(@tYQp3%_;oc$KyNeB++uD1OX5HIbWOkNvF!I{P_M+_Q?C*8>aK#WzSOnZ@A5H2 z2Ky6_TgGdx%Z#zU*ByPxM_*ImkH4cAuT8!GDF0RQ^&BZ{{O3Mu?knxug6(g6<)Qwo zt!t5sm=v*Xb>C+A&}y?eg)-FL|@Ha8DG zCq7Zj?Yvp`>}{WJbiI2tq`lc!UETX1mL+d~>tL6^*Fy>X8{IzEy;9*svYTDt_Uh7| zzngX}&YoxDwYh=+4(+KlVWg{@e=+YNmmhhO>vGe3!N^ow&XjxQj$Jpb9kZntLN=WAbMO8Qif zQM6b2KsKrctJ~lch_d*ZC^RsCrv7m=Pv5+hxC1kZBy31{U;tv ztG=UspLvscT>ZbDI=HC1JH9PN4-e<+G{`=hzA-7n(E`4`=cD?kz{Fd}z zJ+tfRjmnMF>K(J|OY_|3irr-Q5N`Wd#n)q3*7%K%?&`Pwpd9ym_slMS+GW|hb8&po zzp>55Va>_nu%55t@W&ITF5Pc!c70uc;y&r5H^zIkYmb`q)32&$&#OQF{9QUQe4Bat z+?xKq)!B2!fi-h}$oYHF|HaF?`0c{8`X@aG`abKjb&Z#=9qr$}XcBYs`Sp|h10OD8 zPL?{t=4|eC1#_~_%VYf8Q-(1QKYMbJuXOAqr@+n(fnVgq5 zf?RRO%E`%HCzAEpl{fW%k+a#F#8Rc~9m3&R2YF)e5H^P~8`rXT2p7k@>>a|zaWH#_ zaB+Oh-XR>G!?3OLUmV{de%LQLw1*tp$s7yqCx_!AYkR=Un~&oh^U&r$9e?`z0)O#A z16!k=b03^wzelyX-)a4a`)V_Y%wqJ1eh_Uvq4_`(DH z-p5QsaL`(?t!WDmS_{}T2M4VMY+8ha)&e$-!a-{Rn|9%#wSZ02NT9WVP3uT(Jhuqz z{bUpF*GYTGp`GN=esVZ2ayVX|-_Q@_&`z?pA3W;vB{o*I;dmJ*^aJ^?+OIzE*>4WU z%@{w7r;)=r8##=>k;AwgIlPk=;lD7x$90ZA3FBtuFrG#Z<80(G{zeYt24ro|^5$1! zJdk$$X8slN=TBUhJbFP-k9J;o@hwTuUfDC=3FkIWsl>x- z^vdj?&$~J8dS2#lWACZys`OFb6!A^B@}^sHU#44m)2+y+TY1y1$fjF))2(>Tnr`Jy zw<4Qv45{r+_Jw*Jz&$B^%x^;|k?+5qx%$?55emouGf%184HOYN9FztyieKi95W#-+DD zJ-PMG%;&2i&n2_2%(gvd*tYJ0d$O3@*4o=W^;ovA-x^!{C$|6UxBIw5+h={-_xKU+ z=ml4>pC5W)qU(M@S@L$z6}UZ1)!_YSi?QR}2{&{~k#nuy8R9xMDdH>eCxh-GKwDKEI{2}q}vit4A?QTsf9G=~W7hcjhnR~SLK$C^RJa| zPyXF?&Ym%4W+0%9T_WJ}r z7d|q~)%qx#w>I;d@$Q&K`LuueX@NU^%JO{pSU)(s_cAAy|88x|tsm|hd~qe)`C#Wh z?v4SUkbkV&&P_RQC+0wnul96DtZGHxVd*xm+bf;POFwurseDy7K0os55y^Fzj-kE( z@QZVk!}$E-PaZFvT$qi|zj6Gz>7EZ{iS z6k+YdzjK=#G;HsOK9uPiKQ`;*fBGcr&kxhn{C-zo&%RwSaDv}%Nkj6W9}E1rN7^h! z&TMnSL|^Nv>|Oh%nIrs)9cCo3|G4HPe_4%pim>+8rr2-i0i*p-XH4dP58Q8{A2H`? z^0PgT^|$uf+M#Vr+dJQI=S;UMdu?ss?%soFKkk>!e9iN_k%tannjTShD0##^z0&g@ z981<~L3vZ}_qX~}_xtmer}=G9yMf1Bb@^a_@xlkm#qrT&DGqCH7l-w{7l-v8d*ESx z+~+et;jvV^WVmZR^BQuueI~lQX6{IS=-UF9|I9_q$$E>&yXGBQr8w8yUO&va`)(tD z@Iw!G|G%>O9Iv@U+)hg~&G(EQ8@gqkoQHqs!^^n=i@Iif;qv6`JqDA@9x*UEr^Q&Z z^-s?3)kXO4+-ChPN|#LV)hpIvza6#3a6k0N+2p;e_wkiGeM;_m;*q}BbJZOBWbu%u z{@F|RA$R{|d;iItj^wsSuS~ml??--Or%Tg^n~x+l4WjG^^$hUvVUPze8I3!S^>Kulurt zpKw$aa^>lL{YU3~z#Ln$aJWDA^{dH!Kb+t{f4C+Y$7o|B8|KHheqt)e;WzbuHCHEh zysxnQ+U$4jlAv{5K5~@RN&A^#@-#k9=a=UOw-`wd8SU9_l}9P|LyRiCT^P4gC`GgwMeeP+%-KRJ2mDDqvUUr%m4 zDI3E%f9CeC;ak}~{Fuv{xm!-l@^Hyn9bBW;Rp_s*=l7p-EahuFLb^r#krU=zn|-~^;_im z*L8I3Ki}TN{$lxkT+{EHlGj~Z)vasWo;SW3;eaRG~r@jE0Z9x;)u zd8qt%ZnNgY{Qdj7@h^SIK5RL9xZB2EOU`?If*XAEZseuw3*6wrB*x^p^ZYm{oeev-Sa|2wpAikO-|#bLdci^JOg z#o=}P?C1O5w>R_r%mK&vLGNu#exP80pSS8c_QP2#NBe%?6_88SD)5I*%W8_RELY&` zEWCsL`QSC9{kPwok>FZ8aEAf@lm}iQ_gc}(FJ7{pgZ-q*`}z+?G$9Xvr>ZZ%L-yM` z=%H2V4B?86yd*HJ3G0L(+985<~%ex{mS&Gidmam7H*SPx+Hs+9#!Y3 z{IB26?(;jnb9nOhr{j2BYjXD`&%c_ztM*x4+MT)n1lpJXP}hC*!2#qWk8SI^9-NKO z58SQ0>-bYC+Bd)P6gO!5MeN(lPZ;mMu5|#p{1*l8%jJtWE>xq^*U2iw3^>kNY#`R@K}3c^Bms;Z42Y_dgo%4rtwy z=jD;hhq=ycvv=MTkL}_1emHwxs&(f@ef$bocy$4(Ix%CU>R}{BjEUx9$nW z*;f0cIQ(1rp!c66KFjxCrI{A|*oFK1DR*SLNpXDa9**z7@xAicM<%#4KHrUfwR6+q z?)6o($Q35_aZfz;F}X{{_HO(K*;wC}!<)Gwm$u}2zog?1uG+k#$UA@ZZZdMhN#s4o z&PY0*pUvO9?X-%?!eRgU8RqZMo?3^rOi%b|JllWAwzsCOg2r^_R1KGwI zoQ*S(ZJfc`I0MwkQ60e?<+t)J*V545TGYu7?* z_f@vj?yITYSIKr?EwuY8+3u@3yRVY%zM9y5m2CIb#O|wPyRSOCuafP)>g>Ksw(H2* zeYFU0>iyb1$J>3CeQWnsZ}(NQ-B-QcSIKr?^>$xn+w8vT?Y>I3`>MD5Dp}j9{8z=- zy#09KK))=^A*p=I7~gZ3(J6AE;gJRYz9!jv=PRC{U*N+|MJ6?V}xi~(*l_#42TORg)Qm5`oJTJqKspy8C z(uw@kbB)|~59i2#)L+kOaTwPo&Pn#?_gU{h#bG^P#bjsqJ+^7ht^?hi?Vn+vpHXFu ztGXatXR%N10(WKCdCZyTcPMbPx-KY0`|n&c+8tUWd!B!0TiOl2Wj$`J_fX^LH{ILi ztB3NmvVypgtr#%R8IJ!`{vWT4l0Pr0g1*Q*EK+t%`6K$GgHMRu{E?p1DjW!u)5q!e zl^P#xF2`0)f!J!ywd9?P1%a;|$|du3tN}ba%X{)s+IGNin_K?MdUu94uy4icz31&a zNn)>^)&1fVk;2M3SNBVf&{>vedcB8@-Ez|^FiiK$D4%SiNr3Jbj(NM@g@4|^bH7Sy zO)`7xY-eX#Q{wA51Ml6mIu6uv{#koIjyUH1lB`9fj5>WC`EbA0Ai3FZ9LD2?N8RMC zCHkKGXYDy}?qHtt?qEJAxP$3gaNPO5yjOx{?kTg;#=eO=OV8Q*+2Xdax-wAPcD8I61#V_&Nu&;7ybNt>ho&)LqGC}WAB2JF~ zj&0cxblJAE>%Cj4)*0pFg?dld?RrUB&9kgjbN<%c_2tHVS%H7(+DR^dao1Mm2}|^s z$uBMe9^@4+dym!MtzZ3flq_9n2A-{RPB?zo_40ms(k4XoyQs zf%keA^d0r1z*X0*H4*J~Sl&vg4(gx+7z*>STRioUb@~Q0o{)Q|1ua z3)MmSx&aTYHMV{Z%j4wuKjokIDaYLZwV=M@_SKb$KV{DV(W>AzV0UbI&bxzoUb%xg zC+^_4%d&y!Ie+}#Lmob&LK9bG~1{a0t3Whc(1*M7;9uQ{%Nr^_ex=tKW5Rr_ z#4Eya?Ydd>tzb*YekO#qI!`hCLUlDC$Nbh*t84Sv=`X$0BraH=Hs1X z(?;05i+VYS9CICJN3~7X%PLx9OxEwH)v05kP5vIZSspu8?@%>k*d1z>X`@SC7ZPq z0gK}S4;s@)9E#S@8E+Q|6UnpHz?^^Ta+GLz=oX$c(*5*z&!7L@+j2A8K(TwLJ`a#} zWmmE1^^dqm9Q~?^NZl))R5^TqYI(7?S#jVWUVDl@&-L1AYR$)1^>6eui`fg7TMOg& zgH5ZM!kRWD>8eabI6F_oc9Jc=fHu@`Ec~9IX7;pHk$L~z~-DeusH`Vlnw7| zj^A~?bhbg#*(dNx=UXJ5Z$Vq=e2b*>Ex>fXMbh~eU^?F->3qv36*HZ0k#xQVZK3lm zlFqjP)A<%j=Uag3OpB!REodXh@4DW)eWqKd$LamW$d5BvmcQP2TzF7=^J6;4ui|eW zub@4?zuu?xuCmC!bwKZ5?oYpE@2cGyHg)G_mZfVn0N%Z=wDhn30WgoB<9A&z=a6Hb zCqDfK$j+WK&|m3GMaVlTGXuYV6(v6iT!*tsX|{*U=9Tp~D>h9HmiBOcw!Fo%06DUl ze%AIbe7=&-SB)X{XU=7`x|_nDfa;u$*Ur()=N*V~$TM3=w1Jl8rl zQro8-cFoGtT>II*#Y6O6ptU&48A0z%;aZOW%6iw-X(Z+!*K=}{;I3lw)1S~st)34Q zea?;t?$Rq#SYKR(zEo~PlsH?tAM~XW{-L5$dHwu_W8Rj3$G`D|J~q4o8$N*z&%lO% zVAC(aroVtqKLQ(`-@xy>Uc(i*HGG0w!!x)w{M#z8OuqmdJ`ppIljHxCf8M9RgAxC@ z%2DEWqB)4)V4fR)X!Evl&GWxVqQiFnTY8T(G3iG8!ce{UamR+w5AI;Yp-`Ov3H*nB z!TaTH`Nr=Hrj77v+79fFO?ab9V&X6Q+*DxN+@fEh8n|}$#aGs^iS#qpzT4MWk(c_Q z{K(R(){I(u{apUlCEvMM^;#%JuN3z3xq6K>dEaz{B^GOqfL*CaM|EK($bA#a1oG%47=T3pmc~oF?P8HakUj;VjT7k`ZS73Tp zsLsK@f&a>S&AC&=V9uign{%qb=KL!9$ee2hrn5lmyz3j7x9eT_=lxr5Xo#qLVmM-$ zd@WQQ_i7L9jtw6drC05>UwHJ8D&O*a{j2?PTRmU#xrJkQuH`(qgLw|SgWopZdH$HQ ztmsE`#ueBd8;=Cu*1a=&J$Ys3LMy>deP*)g>ATkBKKjh$vJ=@v<)7-pXRVACM4Q9< zj7Ry#{vt9-8kFxk*J z#=bh2i+IdAB4BgA2-uuE0ygK7fXz82VVA!p2a732)Z@48-db_j8r^F_es z+!3%jj|6PaDFK`FMZi2xj{j5sd7pC3{U7=Mj&*IVJ_9+#W1;o>wbtJvvwK^2PwU)x znt$h}1EgE29Q${!+D6+3t6BEI1Fff){5V>8}P6upIFOE4g$WE@~U5j4-f$x&^GVXhe2B~&)e*v(S;e0FkA*?s;t;H4c~$wy_92vtt`BWX|f z2L7Llf#!Kh^E~3AdETaZ9+>8No9207n&)kr=YeUS-$?U3FpYhS=J_`;Z{xq?KmY!& z;_Rp&!J$=jpr~JCGH~`q5n}SKyY+5G((>lSXbpkN06Dra=0r=m!miI-AfLwCLdVLl>&AAu$>I?1RKmElO_VL|) zfeR-pV>iDY27F>t$<3ZG|9EZxF8pWpnP*K4)6X3yet6wVl|w&wxY<9GsNk)iI|Roo zEe0gh&mHV64Mo|AOo+L9<^WM?@O9+yQu?Mr6W@8j4^M@Q&ZWJ9)fo@hH@6iYH0>&N%|Eq=~t5UE3}vM&+&iC zKkf0=`+8E19rGR^uz9}^*u3`#Y~BY1Htz`noA(ES&3lEwH1^~6H5~ty^_utl5RZB9 z57@j92yEUHL?4;=2Z7DIY;R!RmVd`T&(;4;=M~?^8_!$PdZ77m`|79q97y=AW433GK&g1{-8+qpP2mqb{nz61%;R#v*GJWt6&7RxPG2!V zj=gma`JZdx0Qv2E`aH}BGD7B?m;~hqPDIHEPt)Vx@!c0gWbt^7(02Fwo_+8g)*6Qd}v)_qTv6+1k;xYRpV6$(M%Es)cfXzM&*zCW6X--i4 zvN!NwS+Cg#AqKNQ0yg_5V6&eBHv24Kvo?MM^LG6^{@>Q`oFB7SLcf?j6#Bv)8$NfH zJlR{0s=L8beRq9Z8`-*E0-w(FiO@4vRH`0y$|4hB~?MF$!(=An=1a0di zqi5ei?zQ=`zr1s0A@KRt;W9}=A7IT-Dtu?=-?>)#QFW@ncg-{Z4I0&-F8)=2y84B} z5U&1G{pspQ^!APNp2Z8GB&k2kkfhfla+GUQ|55 zCQe`zKk!`N`uSZvn!Iw^t9%2dcBwoBHu(um^{TuDHvbN+u2cES`i1rTZ{MwTeQU^7 zKeM+KHhzGOf1%1vy}%|OVEU(jIbNK8{Ll2G>Ie1bj60qG&ba&I`;;^8oN;IFUzpFG z`<*j?{+-q>y0@JBool`4-0z(G-Cwa^aK;_>J8J)ky_GZWoN?!jJFSnI^#k_)qz|b7 z0z2!>-!v9y{``B*pH6@Mz50u5m>fI(`1k5Zr@#JQ{l&)`$4)=~z53DVufJD+@v+9S z(~p0jetZ-;-7mPFeiw=3G2aDSA4Cs^&Tw|bUTch(evi2K?&RWrjut4NIHa)HT-Xn| zR#0tGJV8$268k!e)6aj#b6%fc`ibp@mjdq(2^Uc#3IMC;+II?v(DP>c?Lu9SX930@ z*!Tf9{)MtP^#YrCfK8mhCVpVkt~c=irZy@*=?po}QSj#}eE-Y$#eBbPbR_UY^v0cA z;O804IRV)4b0$WAK)HI(uj*5MM1OJ5-<4ja>QjaE-?;NF{5d{d7k3_pKSx&Q0rJJ9 zL!Ov&a+_}oQ zb981N7UsSXcka%)-|2V%o%@}$R&mxUdfsr>nQ>>))qLs9nR+jS^{2B((CbfUf9HdI zaOTYaJ98$z(`wWA;?VC+wm0@&_*`pc#m|?iR|=rLQOIews}vn<2@HiSCCg0MGv=r5L=b z8L(V;z}nF(2)J$T5Nmty!N6P}`@h^?-uAa){*KZY2TRIsAC#4f^MaEyO0OY}fKM#A zVwX4+0Ni=`9J|&A{oAA5=ezL3eZCF5^eq*$dl+`e6I?>NmHzMVm(y?g`Idj8ztQ0i z=9+Vvp``y_rYttwCTP3{h z|NGnc$2p<%#j$aCaB{%O0VfBX9B^{L$pI$^oE&g+z{vq82b>&ma=^&}CkLDyaB{%O z0VfBX9B^{L$pI$^oE&g+z{vq82b>&ma=^&}CkLDyaB{%O0VfBX9B^{L$pI$^oE&g+ zz{vq82b>&ma=^&}CkLDyaB{%O0VfBX9B^{L$pI$^oE&g+z{vq82b>&ma=^&}CkLDy zaB{%O0VfBX9B^{L$pI$^oE&g+z{vq82b>&ma=^&}CkOtb9KiQFO&ma=^&}CkLDyaB{%O0VfBX9B^{L$pI$^oE&g+z{vq82b>&ma=^&} zCkLDyaB{%O0VfBX9B^{L$pI$^oE&g+z{vq82b>&ma=^&}CkLDyaB{%O0VfBX9B^{L z$pI$^oE&g+z{vq82b>&ma=^&}CkLDyaB{%O0VfBX9B^{L$pI$^oE&g+z{vq82b>&m za=^&}CkLDyaB{%O0VfBX9B^{rug`&a@$Q`o7aj?`ZB_S+uwbzw*F50TIRiwZcGrPJ zb2k*n`eeelBvYj-El$7u0Jz=oOd_5~L*O4rUbhZp2mr28f1Y)9KrryacHUO2li|Rl z+LSFHFP`paRVUSravlRO=l0wW_s{F)@$fi#{JdSfy;QHI;!r%4njK^Lrt1%U%jXws z(d`bvzUgy`O3!Nm=PFWJ4$ zxCF-Lnu&cywHzyfPp)mJ+9Q=sgl9FeX}k|G{a4Wc2c~}#WCu*wS#&)x`LoC`@UBr; z^0~&Ts>fBX>T%htdR%@~Jud(1zpi@Czr&}x&K0Nf=Zas|Q?f*=yeekZAFej?zA^2^ zI5O=8HtiMaO4D9o(_UcuC)HkH(_UcHUSO)z$5o$cughMw7nuC0_5z#s0-N>%oAv^m z_99NxUSQSUd@)CeU-V-f51b$4M=Bf6C+C^|DUN^MFTB6z`qp2n>QjD9dw~rP!1Paw zA7H~9u;CNfv>Vv)Z!4dsUw~cwnR3-Gw3qY1`Qf~AKI!^6o=v-i^2z(0g_wE1@%xd3_5AR^od?RVymT*?YE7W>cyxkLxphhoOXXLw z*}de~Z8NDn5sRL;mgy%aw^V-ZTvJ(k z)?Qg;;JE0^LyPC3_NsDMdzHPby~>ZPy~@9zn&Oh%L-e0O8i?6Sfzjdv6F}#0yzw>^-@*l?=)f>kr#S_Of#Tmyx?-zCd_^19t-Wq%4v+;vGH~x|Tre2H-6OXH1ad}1U zip#fcucPGUi$yD5ZSmu`?qJS?yI75Bl@rR|!43~j4mdgRE^@%RpC-5eF85PsEu_~@ zbW2ogTCA!5j(z9Ont|K6yJm2WWwU08(=BP8OdbPWZ*q^k7 zyqM;^Uz_j-VnK+9OjbD7FX(v(5peBi`{DChe#b`l6kqh)VlO*Bz^_}qfui)PPwfR> zW&KLm3>PQAFJvzYKkb{Lag_LE&E(iwcPn7uI>{qmfm5D~l*S~ge4DO_N1qML{ySp( zZ9nVI7~e_zj`-aQZpysuWchywD;`vR`p>}*5C0c(;2)o7slBzjFRH%(ee68vHRD3+ z|Hg}F@0n%=Eg69S&vC}o>8(c}MxeY>fqb#4_eKE^e_GZ4rdk+q^&#PQY?i^m?+;3D zd&g*dpQE*Xlf2OOt>*+=J!7=ZnwSGt`hG#MFZFXu(P?cnU@Kb*5p<>;@aKKHi*BEO zk3Jkczo#hPZ5!~FFX3gxuqJPi=OSR|Pv(}>6oPR{t0JnQHg?hb@n@fhd0+y2<*eTyNmCHT#CSV&#ZKf&88;%y}3ZTr9Atx$#f zv8z_-+~D}ju8r+1(}zgacW1-5+UpPX)c9Efd9h6!;BO12l~=|!1wJ_Ou3dLTC*Wm; zzp!)7?+2V?_)oE^!y|!1M~(3NX0Wa+$ADf|OrlVfPwR5f%2`wA;rHK`7Ht~pGX-bv z`3ftxFl;`V-b8#iAsz6qxB81D6BZ)(1M~i&7ch2aY^bLWJfj2fTS=0b%VEz#H4v712?iz%$}^5;+Flho6{q zJ;lnjJAt!(7AltJ42Z)q27keLJI#1IL%dxwylrH>9U|W97~Z~OycK7>btB%^8{RT7 z-aaGVybNzAh_|-C!`oQmZJXik1@V@i@s{z5=B)tnw$$)8oOp|8c*{b(l{CDiWxPc( z-Zl|$l?-nih_@KVTTaH?YQtNRc)RSH=Xyxh7aRv&O)Qs9YK8LX4uxga>VCl6lGl{S ze)R_KbgZFF9p(XCY@(lRo?7QdPVd}udd?aspWEu9eSUry;P1{%w9~B`2%I$Qt=Mf1 zbRO>7Im+)|Kb?m&N}RD0Oz#Gp^|x;j z)>iR1dKoT~ew7_~+ps9{)HBjgmFJi|Se*EN0CFSM{oW#MuRa5^C|g&tJK#LZf4JLG zYzg@pI7_VoqDt2sO61B}9X_KHMT&;GUa4n0@f2=saNr;CcHHpR znRrWOcq>l4H8Z?<6K~TDZ;ObxpA2u?iMOu$ap)1P-#SCv13m27J=2k@C zaeSaiZCS99?$f|;I?1XB?%0akomu-Spz|b?6U4B1^gwa&&Zoc!K8h5TU!6s6 zRHw5=mC8@Sy?Fb~NU`qZ3FJ?7;Rx|+LuO00anA)Sn?<}egx)Fz~8NC0Wc&o;Eo4|Oh&Ugzmyj>;U78~9U5pQ9Jw`k(6oZ)Q`@ix-% zHk){>VR(Bz_&44vGTw?2Z?g<j*h(Yf}5% z$qGKL9@9LuaC?S_-ulnW%kOU$ljE~)$UCJ@W_f*h1Gyq3e!h>U47YcD z93of0&XBLrh_-g%t5Es;MX1j=9x<_b-;a{7YF5m>BT)nE;x>J+f7$(^RVLy?0hUtgq1p9Of{wl1Q@?hD9`qMrRlhY$65iRwI9G&~uC^0XI*h$egM0`G0v zQxx629oY76CBo+>fuEWC>x%2QvjNlC6l|QvVa3}f;;pseZ7%V4!SHtCtI58(3~!ql zZ{3KuVTQLJ#9IpDEk5z~A@P=wc&kag)h6Du6K@TPx8uay$Hdz-;_WK&ww!nyO}uR< z-qsLrg$-}%UWWRdB;I_8w+gi?=3Ys>T{65qCf>>!-gXgh{?TW!PJKH{w)<1LKwcFpic_X5f83vqbaxhOeoNj&7zif~Xc7gIn*in?9+#M{-RG$MJvp8JV`!Fx?rv8+lT}NTAsJVHtY*wbft^Aa^8zh@_ z-v``jzrTF1QEK$#7YWkK@im$N_i2z!K1~_6}74t0gjBxA%0p@8@S`h?NjA1?F#{DEEvrcKt@O8V1a z*pIt(&}v>t??)#7nm~NsO7C~l24@mp-ujGlbRREKy-qFIizT-#{~Dcvk2jiUH8JO% zALr?0-CUvfIJCF&bM3S8Gu(uD`|NjkyGp#>H@vka-m)3qjuUU43~z;rw>^fpOT^nn z#@i{wTPETyo8fIN@fK)!8%?}T`W@ct5pS0bZ{3MEf5TgU;_aZ}?O4a(cuPXOB{RH@ zA>La23*KUgx2lG>s>EAU!`lhQ+cU-+?dv7m*T>-{CoQ>YVL_pCEM!o2nRb31v2tpH z#V?;cwOc>yAX0P~9-Z9!$g2_>u~@KlW?iD@s0@uqSV5(rVVFs$nvH zL9EZ`FvmG{jo~@wS6_%VT&OWq7MiycIXRT_fHG8{RSyZ}ALonTfY$#M@Eg zZDXE8UiBDnGYxP152l}A%J8<3ch&c%pllb}X=}UaP7@~BL(UJBuXARPt~u7rUUx2B zZYohc`g!JwvEO%yl1NLcnc!lIumc-7~b|0ZygP9k1CItWyU7*ieu7yZPI&DPI|8& z>Ak?D_gbX)0+Zfrk=_eTdap%#FEHu7n@R5lCcW1ty%(7DUYqn@VA6Xf>Ak?D_e#=x zfl2R`r1#?fOM0&)y%(7DUP*c{aK)=plJs6^Zlw20(tB|)CcRgZ-YeBSLwc_yy%(7D zUP*c{FzLNE>Ak?D_u8cQ0+ZfrlimwVdaoqC7nt;3NqR3Z>AjNlUSM-ycmtE(8^>E| z##;pOMtZMMvDIO`6=A$BKJpuHjTmoV5pNj`ZzYJg0K=Ov@kV+te3ITPgMNoM(tBl3 z##^VgnzvfSTae-HI`LN6@b)3`=4E(GM!b#x9o_;NZ!d^9(tE)}8sd%gUSMD1?F+`+ zeZ!kshahH-N$<5t??pN3y%y=c8b3=QNbdzEy;qRl3ru>iMS3qV>Ae=|y}+dR`jOrX zOnPrD>AkvqKrfs0USQIDZPI&zN$-`U_X3mND@pGKCcRgZ-V026uOz+KTJd$Z1*G>% z(tCaDlwGu#^j=ANuiZS^sc6!BCF#BPx<}KOklrgv@0ATI{JMnnUP*edTrlq764HAm z>AmuJnL0~I@0FzY%AM;MEg`*ElHM!3W;?uu^j=ANuRU<)nP}2`CF#9(x=NYnm~}7m zTw&6Cfl2R;0CelHLm&(tG20 zBfZxqy%*)A_e#=xfjMua_e#=xQBHcVB)!)vVt6CH*S8e$MtZL#z1OZuypi53N$<5+ z5^tpUO455}ed3MuUhuYSX)dj;ve;#`JW`AF{- zr1y$y!;9r3y;qRlD;|cY&PRH$MS8E8`rXpJr1x5+_lg9m^XDbK*N^mGQM^YzAJThc zN$(XSnyg<;daq4-ugEl}@DkE{ZPI&1;wR~1Nbi-T_X;_uNDS${lJs6NAlx-KETSCZaqeIJx&3F*C(^xoKS_DxwrdaoqC*M9U%;uz9pUP*ed-LhP%XwrKn>AiN&l*5;h-YZG(wHIdaiXpvMlHMD8>gDkzW?%1D zerC5Ag-P%AD@U00UhvkM@%FXhjr3mOMZA&TD@gAZ=ZQDcdj;veqB`+Ldaoe8SNu%8 zk=|>O-YaGiZ>0BHr1y&C#2e|o;H@h0MtU!J>rT9p-fNTIE7CFE5)yBu_e#=x#dpLT z>AjNlUNMh&R%E zCF#9(RpO2GUP*edoyqVp6{Pp#UPgMaAiWou z^j<-FFEHu7g7jWs(t8Ezy||Y2UO{>*y%(7DUP*c{Vj#U&lHO~5d9d;V(t9Q8y?!h59$rLx zuOz*9^V3JUqDk+Sr1!@5IyN$z^j=ANul-5i;*IoPV8t8hy}+dR3etPg z7SekK>Ak?D_X^T`fl2SRNbdzEz1JeW7ntiB)u0gDBei#wfY*~NbmJqK)jLOD@pI&{IlVW^xoK>hBwlC?a78W(tG_@8s13n zwMr9jr1whFd#wwaH>H#7wrkBCm~=})dM_~Py@K>!VA6X9>AhGxk=`pv?}es8daoe8 z7g`7Dy@K>!*puEXNbdzEy;qRli#C$pD@gAJCcRgX-V026uSI$Ak?D_xh3E z3ru>iO?odd>Ag1Ty}+dRO456QN$-`U_X3mND@pG~45ar;(tCkP@0FzY0+Ze=N$&+F zy;qXn3ru>iB)u1YNbi-T_X3+|F>heS8|l5cR`Eu9FRAiyVUSQIDEz)~|N$-v0jr3kWAHy5zy*BB+upzzI zCcPJ!^j=ANFEHu7lJs6+#T)6ph=KH8NqR4^;*IoPV8t8hy}+dRO456Q6>p^X!jIyO z^j=`~?2q(bw3lPjEd}Yl;Dq#EL3*#P*1Dwk3etOlN$(Y;_X3mND@gAJCcRgX-V026 zuOPh_{z>l@r1x6N59z&v^j=`ndj;veh==rEL3%GR>AiyVUSQIDEz)~|N$<5t?*%5k z*CxFenDkzo^j=`ndnM_;8rLl$N$&+Fy;qXn3ru>iB)u1y^j=ANFEHu7lJs6+(t9Q8 zy}+dRO456Q&9i1;(tB;vet{Klr1ye1(t8Ezz2HIdMtUzW>AiyVUSQIDY3|azk=`pv z??t)djr86)-bnAY6mO*W3etOlN$(Y;_o80Xdj;vez??VIdo9v?QBHcVMS3qV>Ag1T zy}+dR+NAdalin*y?*%5kSCZZf{Lj3R-ivb5dnM_;z@+y|(tCkP@0FzY0+Ze=N$&-w zwXQnnfHrbWdaoe87v-e)3etO}YA@-%g7jWs(t8Ezy}+dR3etOlN$(Y;_u^X8dj;ve zz@+yI(tFVtr1uKad%-8^y@K>!OZg|gSCHN-6ehh_klqVSdaoe87nt;3i}YS#(t9n^ zdx1&s-AsBfFzLNE>Ak?D_u8cQ0+Ze=N$=G*!I>oKy}+dRO456QN$<5u?*%5k*CxFe znDkzo^j=_dmIj#gUUkL>nDkyjdhZ*&k=`pv@0F@ur1uKadx1&s6{Pn9lin*x@5QyG z_X^T`<9H*z7rc?)D@gAJZ>0AM(tE)h>AiyVUc|t8BfVFU-ivb5do9v?fl2SRNbdzE zy*G|G(tB;vdr?k$uT6R{@Y{GJy;qXn3mejVZPI&zN$-v0jr86)-pn~Jsd(U+bW1^c zFUm>p6{Pn9liq8Q-V026uSI$!a7cQuAiWou^j<-FFEHu7g7jXYVkW&;klqVSdap%#FEHu7ex&yT zlinLkdM_~Py*BB+z@+!ur1t`o-fNTI3ru>iO?odd>AilW_X3mNYmwdyOxlq;H~0ot zypi53RcxF$(t9n^dr?k$Zyax=_X^T`QBHcVAiWou^j<-FFEHu7g7jW+MS8Cwy%$*V zMtW}?Z>0BvAI=-;y@K>!l#|{oNbeOYHqv_q>Ak?D_gbX)0+Zew#~bOralDb<8^;^z zy>Yye-fNTIi)%^mjpL2<-Zeg7L_gbV|$|+~(DZN*a-Yff`3R8NoAiY;UC|pG8y@K>! z`Toqqc}VXSr1#qIf6^uo>Ahn4h%aNW?))_u>AiyV-q^2ptx|fgNO;xui)x=v>AgaX z*=%*(2EA91-YfizzEXOxAiY<-`n0Fgdo9v?#gQ>FO7FEu?-kF^Zc=)$MS8C&(j!*s zy?&(kis1ueqYs1~^Ci7k{9Nku=!;D|Sfuxg11Wkcz1JeWS9q)_yZFO)H!ae8Mf;|K zO7B&?foIZt<1puq^j`30^j`30^j`3GjCdox7raFfZ>0Bvx2eP%>AiyVUKv8Xk=`pv z@0E{AkWj@kV;DAidWvLA;UPD@gB+eQtOoy*GBX;f?fOziz}E>AiyVUaK+j zMtZLxy;syE-bn8ir1y$nh&R%EEz*0%Vd9PS-ZWc z!0ud|V0<1j0V~+K~A$`x~*qv)r%<}e|eL&Bj<%%`;?fN_pZ+2m_iFMih6aJUiQarXRHj3GH z#Y}CnU2UN_ZC4vPcIR5+R=T()&ZUcU>I>=W3*uS2`iNt9uBCjCuH2xUk*=JfT#~L_ zqCAnV9OKxXYbm#-E4L}H;=?-oU1=KfKno z7dD0yV8fME^%@@D!0udY`U}^ZJ_R;?4Q%@H4eZXfCf{(a$w^?7tH34?-@xu%YsL$% zrSYZ4lnbk|25iRQ?_o9WT=u_vtr_pIF>?a2nJa)PPBn+Tf!(>*%w4$F%xS=8t^+2X z)g1T+cIR3%-{M*`Cj*PlLJl;I62_tfRh7G4mdgBkI80Kj?RNIi5DlPAI)!)g=9gp8MhcdA;*T zx0L-q)9=}Gd^3Ff=JHSUdv1$5m9-;(2m?Qbb1t_ZX6*<3;@78k(9;gUQS6z_;25$*ewAIC=cMUA(=V2hIX5wDuREV=o z3L##0)8BV^z1W9-+pikR`L(>9+jBqMKcAyG=HtTma9Xh`TT`J%V4)$|#QZ$^TL9dK zmvehQ7UK60lzVgQZ_qC|I8ZiCroa6yJ4DF5b<-m!`TWeU<>lO-`{DliJn0TrbBk)9 z{`=RM=cGHB{L6eX>F75T)t|cWkH>wVUwflQWjlFSJwF_rxXw<}t`GXR^|<(QdzrSt zqk83&k3Z7i>FC_9y3Cp)56UO@X)izQ_bYOy=9Rv(ShW?v9wozN-3!Hld0o7m+jBqM zKd+a^!{g-fZ~CaAD0JNeoN}z%t~sE^QTK2e_H#k>`~HpnWQ_@*19z&{QTkka0z71R zEqV8SFZkK#RY)%GY5|AeODap%YYE)*;0}ANm;R1G$`8BSC7Xnz{Bp#Q*ybbky|vKp z(|+AQ(cfg5xqPhEt+)R6%G&s6ttDN$!G7$_^rGNTje-5AloDU|*Wb$FG4pb6&;4-! zyj~s;kCVsG+r`_$WAiEH4wOh~XuDfIfvXK%RZ z`9&_2Z+=a`xplh&)??WdMu;4jJ#E#0_KjfCAY?Xhyc+@Hhw@i|xqn{H?YSTBpV!Od z;c@aD<~T*pb|P#1_t1BRvh@+??|y^$PtrHs<|J+aoO6GaSnwz}zL#`AZKTLj`33Hk z3Fi$I$C~Ni*BQ6GtLU8kC$wex!p7qDz4TJG_jro3qU0|nfuGSg4WCtO0KA~Xb!%J> zeNXAucD9w|ZZOJohGn!m)r|n=vGHGcRPX-a(HvM1=bb6#cuhx;xK5fM}Bg4-|3^breNY0i0jxqn{H z?YSTBpV!Od;c@b@=?>=k=?>;O<_=adj15fqxyl)ZUGx0O=*4#LN&S%zb1&VtKYr8+ zcuT1)vd+o+z~yU}kv+dF1^nzmLmA%4131If0C{8dRq(%QRj_PvR)3Q&;99u6w=*Zo zxqn{H?YSTBpV!Od;c*)OLbZxx&bg@<`C#e=HuVCVdf~^^3vB8IHuVB)|5LF3=jGg< z`{Dk1y*wTs=kN(v?7heI_~rQPJRb9Ed#j)uNlpB744L`t!A7H}|u;B;T@B?i40p|XBIk)G2 zxPM+RkB7%;_yLC;^EMjZ5Rc&v{bG0nHoT#a3~%To?uVCid+vw(=k@Z~eg`9lah2(N zmx<;e27?iUvFA1@=k|QAn3!~2#fp7E$x95Gt?YSR5|G0xWZ+`+y zmY;u!`5a<^&)W1d z-TubFJT_j=?YSTBpV!Od;c@c#dAoRfIS-tl7k9eIDV`V5*Bo2*Nw{ZGssAWvqTj=H#i zUe4{gAMT&m%j4m3@?7P(Szw5KIcx-Cs9HWq4v0Poe7JoJxvXFT9lY7Dn?%ob1HS2KkJ+mCq})F*=l0wW_s{F)@$fi#A7$Rr zQ+~E;E8_okR)3kg|6*Vs1Gnep+@Aa4{o)Sh+`5DLSa1iw-!xKGynX}s9gb<;9ZmNG z^hNnCg{+Ak^mClXO}?Oq^}C4XF_(a6Rc#`FPQ{G1z~T0CCl z5B%NaLspA~dfqF%BE<6Us^`5{Q$O=7ZRWi)V-Lr+U8d)~2A<>W1MT&^=W**tJHyxd zTfGlccu222jo`D!iZXIt%TmCpPc@NNiFCj`W?s(ixgYMI*URJKaq{?iyLfv!51b#) z8|Rbvdxm4XV_dnHDt>F}RWh+qd=4*ON#4m`0J!W)Z~04sn!u$uKC>@|={)>!+L!jo z4mv-7$WX-2+F0i;_ruG%J@>=?^LjU*@|UCiQlnmudCpV_2$7vXAA#KH{y0*`AG-nL zE4X-+y!*o<FQH=Fz3M?OwUyXJy%8i9Mc>qX}t$-BfSU63^`{3 z%Z;7oiwie^&-_$RjvS`1Jyo)}Ot!u}{Jb2Mntm_SA9(%zBle()dhK__8fu^XUatwq z-B=zQFOyz3=1;rauU;07<0l_#E&Ea1JnVJEnm)$uE*z%3`ncAzkIIu_8#pC4V z+@Aa4{&~GT9v&x;pSO#*m-E2+;k-4Nx05t@twEb-?o#z9=X}oj&Z1TW&22#I0iwx@ z8Q^)_mI%?VN)q5SN1{a0c%B#+2}6g7HjA6u%1?z0y+qSe`ZwcWb!{zXj86pr^Ji5O z$)eu}u2eCXNOZae@RCl?Em==L`&*S}nU$)JekQnTQW0xuU9B7N*mya&=YF_-vB|X2Bihp|kBI!91#wIG_VN=S1L#p8H68P6SNPgCspC0_OgCIk)G2xPM+RkB7&}{c~Km&vfhb zIQ`sz?-!W{?S&k9sR0_NZm{C9qvypFV;3I4nIG<_7r`d*8!ed^RZR^n~uP<7c93H#@F{* z?w^-)d+vw(=k@YZ$?Rh!3=YDu@yMuYoxPv)A z?qEKLv{)7(M;5z^+}JcVSlYwq0;ky?E}K`@=lWj1ijp4$uEX=?^ra%?os^l;r#}4# z$j+WKfO+n5|Gb>rb3fcaub0QeSr&L}?)q|LzO2AMbnPUUztG=RPgtVAOnz|*a%qrPxa>W)1n}ygqh#qqGoV9q z|Gb>rb3fcaub0QeJ-HwGvoSPE6izw<`O~j$sQ7VJH}u`S zF+Ih#!`pzTv}z@qR7oP0A08Vo=l0wW_s{F)@$fi#{JdSfy_^Tm&wc;GcC}V|j^dbe zd*P+G7@eXf+Oj$IbE{H72jH(Bd}+0BsMlRvj~216)Y5*cuBlw%g*h+5{qS;b&;4-! zyk5>B$GIB@%Ba|*;Cysgh}`zeaNsMKB4td3jXnzSkCL~tPeI?^-!oVaXx7hC{nDs^ z54rKZJ-}DLY$0FVPKF%F@ybsgo?Hkx#>-2d8l#^hcpQ3a2PEu>@`*FPv~wF>_k+GA z?0Mcg_a?PSwfWOu^?jem#>=@q_rv}3dU-rNP98sR7jG};f%EftU6lNJNfmIy@t6@C z?H{|7jzfQ=v%DuCrELd%z$zu>|3!za4q-4%eg)G!~OGm`B>wa`#MwpRFX#5$5BJY=;N`$b`Hk;+ z^w+4ngXEL6qtTB%pSe9R=l0wWAG7XYK5w{#d0)GOyY9&(>tE3OeU5oufoXG#euZ?- z&%XG|`ZZB|@Z5L%8Y}WrAK)WPt6DQ^>3webSC@R}Ue$e(qE`xgxyhx;`=;CD%o;Ch z_Z8cBM*yznb@6g;&;4-!yj~s;kCVsG>*9F-*8{}vF4HWPKlQFeh+&Bn07veM63 zL=FtAKSUfl-W)lwa(*wdEX)S(;n`Z8PnsBQ;eL2Ix95Jie_rpivgKvKhT=lS!|{Xn zr`lDo=yBR(+ZB7nPR(KPh0HQVM%|BHMwF9R2b4fO9Zxou8#ko^u9`7W_Std_F>jq4 zA|L-e4ES8qD4A!~YP2z)SCp(h@e4my??>lCWY?!rmcm=20_EpdjsOo2^p`y@rABN# z9$wDvxgYMI*URJKaq{?iyLfv!50vv3&D)5L<78Q@$mn9yismwh^TvFIQnJs zwNP=~t35Ec;pN=^ZD+afE^Q_zCeptjf5$sWM5jLlpTj%`i_9zZ^X{^_qr|M1pJVJF z%@`%-w_JfaVa=ToQOh&RR(u{h7bpss(`%c?4V#I9%j`5Q1W8n{B<@@G5U+T zz~>6xwWiF~_wG?c=UaA_V3cRwlf??kt=AYlHeSx{xgYMI*URJKaq{?iyLfv!51bz! z8^_+m-;4F7-(6Rn^vamZN;WY9IGx{YE8(MH;C6#=S&tic1|Bykn`oD>9&lP&LEOkz z44C`j<=me8;r@BOlzVEu3ZERC^$GgXtTWNSW}S%~FzZZUv(AJcv(5xI>r7y?&IIQE zc{#V|ez<>LFOP@EY1VS6i(}qKv;KsQS$_hX^(U}de*&BJCouQJ%eg)G!~OGmw|~@B z7Au_=J~`&&@#B0I>?E7@8p(g#S9Xd8eWl8uddpwfiSO$<>hWoBxh22eVngXB|d zH2QZ<=kBuP_V0mtY`mP?b3fcaub0Qepftz-a}5B^&WUL z>pk#k)_cHay@z_udJovF_khiM517Zp%eg)G!~OGmc|1H$9zSmvZ!hPeMyFu0Lh9$p z95)p=?X8P+PL>!t%YKGkvdX>G#9Bd;pp zImP`b@nFZ-cxLKZIYKO)j(v>x`gu9G z=YF_ z&7abxw{SnaoZE9h+&`~(M&|CaQ%b$&A5ZUacer~uZw6APD zZ6#vhHoTnM^V~adq>xCn(+^`L*gvi4+ovgTqS}|OJbAkS^Krqi<>lO-`{Dl8SXSdt z|NU#s=M#4@=ieR7bJZQ(WkX5nU8gMC@H<$lc4e7TUk;j(1vqh;&NAm^{a#!5biuOr z@&(AHG%{T7i_Hy8oX|I3KFg=BHRb3>V-IZn02}{223{}9xjpy8{i}L29P5s6ZSi<` zoIHNsF4OO*mt)nxuJ3@E`4eq4^Cz&GKY`8s2|s531UB<0u$e!BmH!mj>%PU#c?yw8`hFL`WfZAS@W%6OY4VY!hEd6EA+F! zHkUV4d~BZmB~O>tUgM?LFsrl8vJ>ahYnwR_FWJ!*^qOaQo{aL~ZoL-b{&_jK=YF_< zUN4V_$7%cvHFh}WW7E_N8&fZ^sTbJP3vB8IHuVCVdV#rrUe4{gAMT&m%j4m3^0p-F zchu_CF%b3csJ6*^Sw-(v`P|Fxc{#V|e)yO*Hd1kDY=DhVU~bRLxjpxz#*Xr*|Nb@R zIr%3r>fn9xHvBYRn7q`uHs&0T$zITWjy7g5l3vIHO@IR$pS9vQ?FKxo$tTvbl7oOR zrM&7_;loJapD#3z-LgbKhn@dkJG=MOP?U%INPAC2FW@wF6Uq4#TLX6s$S=QKRT=oz z{c7@;@p*vD*D3yp8MhcdA&Ry9w(2V z^hQDFSP&=2v}TBV9!mPWpmQvUjr4gz=U9MApBHqF1(@`CLFZV2NuL*Vjs@)^eO}Nx z7GTon1)XC758OX5=l0wW_s{F)@$fjge~w8LmUNBWGk((P?J#{x{cy-nv> zfJwLaqjN04q}y9`js=+e;pN<(`{Dk1y?iWioPU2;ady;?;LR#JP}Hw6894i*2r>Cq za^RpxQDWry1vsy}KSQ|qYEnsCM zP3M%*E;?Ui(>WzzI(KB#IVE5^k5rM)DFO3qc{#V|ezTRp~4TuF?B~r$hV6d8fWW?s0ow&h5D$-oNf(KE~a_rtRR9W79_TySX<3n|l-N z&AkcO+?#;Sy$RUdn}E%|3E145fX%%L*xZ|d&AkcO+?#-TY`mP?b3fcaub0Qe4bbrp!E#dySdrksD^72R8FO{Fr$j*v#|5W}XM;{&_jK=YF_< zUN4V_$7#kI>f)HU(ais_G4nsLng4;!{10sAe_-y1mvejWhx_OCnz;xZa?Eqv%=1F^ zk(uX_+h(2zHuF5NndkAW$ISEaZ{~Sm?w^-)d+vw(=k@YcE7)-l^NM<8(T-f3iP3V-0~zZREg9+v~YKB~T~upkR?`icQ^ z?5%5PORj+f{B1%4ZnjSg)-4{b-@pz3a#o@w^z2(9c8-Z6f zZ6iaIBowN=d8#V%{xA7}d7QkQ+jBqMKd+a^!{g-f^LFv}avnH8oHw2`=3a)jn|m3? zEFWv!o|kib?uU;ZjyXRaKj~&qY_Ink6Yi|H8{E*(KYgX5JJ1Co^nwzD)8Wg{{H zSI-}}#Z5BTA!aM8K6H!!b@mvejWhx_OC@_2ZhJbvms^}Iu>d4OZ1 zEu(yKsu=M=!^IR&tJP62G5QvjRi6u{g+FX#5$5BJaO*qHD3-PFj%;$;7MAVD%BCd`->Frs4q{xxea7`%E9=RN1#@A|$2zkaHwx~He7yQZgS*3`4Vn-pt! zaCY#{q1-d$Vl_L}55_M0!V$69Q;!Dv$3OLsZMo^^Kz}3FDpqJyiQu?X@>Pg!zbF>y zUE5}i4Su3qLce22+P4+24)m0ESEbFUl~@CW+ZMKW4V4eq6Rtme+;Drs?F_d+d|u)6 z4fjL1e|~v7mX>i$;=UQy@sr>@WUko!?D%-WoTY<)yU<-1ANKS7K(AV`e?0Y~M2!69 z{W`?^94Zi#^3M#d9)Iz!#BXrDj^&OYTb$r{Y2M}C&AoaJ49e^+bob_+HLnl!iOn-? zuC^!fp6dDopEkVtqr|;C(S|L-?_XhixO}*taQ)%qhT9WvXSn_0^9rA@w4uS?+k@Y; zL{EN;!ZrA}=KWr`_UicB)NO%phxPC^HLdeg&t>^O@oaKsr7@cebsQb|#LT?AHs7~+ zNT9Fpof7}7Rrf&eclCMk?JE-R&$|w779ZTRY+x_<#AWekr$*<-_%a>kl6{ z+@5ed!{@SpX}9A@eZwX<@~V+@9!9sYih;G8nLCR zwF5o8Z`d9#AFd}{f4B|jqKC)pT=ej~aV~nbrKi$%?7BQSudp88_uC7`#}5vz8q7I` z_m7D8-IL%eo>9Mdyv7B;1@@~=i}{P@w*rG4D4$*t>0W| zL*g5`*FI{vx#ir%yq9@P+f6_Jl$dkg`l58&rpLzz*HdvaT{9)=d!PLqu90{ z6$8D|qnE@^jZFN;kzvSHu_n*&5Bl)?A8&{?>^U*eXa7DimiPB3g7xGz?I*=nOiFxL zbN4%=V_DUR&2rpsM~B4ve7`f$2d?fG%XMkuTI;?w7CSNL{Ge@@>?#>+Kd@z>huapm zhs%fS3D+M!Zn!<+c81#@KCkfkhWjDhKYhzwAOB`Xf`cfmhk4{qeOqetdz%u!x%Yc- z{^mUy6TiiuU+MVfY^4*w(NBA(K)la&9fI@yWlWuTvl-O`z3*+E<2|yc2Ks}o2F8C~ z^={B_kN5qN=g7ppHf#@<57!f}KYZM9d&2E}xM4Q#pNaaz=fXM0lIP2DW6Ab#+*q=m z95C* zI)T4k6;J;CJN}MaJo$I)`1@}0EoO#Y^z==fkv{-&Vl{H?Il9KvCHxO}*taQ)%qhTF5F<{X(r zg8IexlkFGZPaao%KiMAf{bW1E_mk}x-%p-bxSp^*Ts~Y+xc=~QnPbw#@8#UXy0ka> z9U5~+Oy(>p!(0-RxlDBCn3&9QqBHlzWbPB4IVmP{qUg+3F_|kxXAVn~IaGA1Klyhm z!}f6ba6RGr!^aJ`C)`e{f7E@?((j35CC?@O9AjclKW?C>A2-m`j~nRe#|`xKBkN9^y3D4xc;y`Ts~Y+xc=~Q!|e&TlR05C>#?}BA*`>S@MGGp+Y7 zGCgjtlvbd9;-1)N!KnH_rt`g&TX@0dqkR(gFPE>_+-+u}e7K&lJzPFqPq_Z@ahWSN zv;GPCEv$#z%>6yi`X^{7_x(8QpFn3l5NG`p=&TdstbYO@WBm|k{S)Y{E8?twg5L{R zZ^T*u1ZyGIA#v6}!C0_9iL?F*bk;5W{mqO)dsxrJS^oq&>zp|2pFj_{Eo={$57!f} zKYZM9d&2Duw?BMd;qwjmL%4s!*JfA`k5}s5ucy^KmH6hW`-~^kzNs`k=)-WCusvKp zJVs$XJkNBV**Ly?WBH)3CN?S+za>MW-@;|W_HcR1{OPgT>1<9-?F z+;3ytF9V(XaE$w9pojMj+r#C<^@Qt}>nAxUpPT-VzrhRF7xtxd(f{gM503OWe`g`^ z?d#WFAFp?4R^ZPsp1dNy;`jFg{pmY9#Vfs(^{#>E%X@B4wCe%}xD^!t9Gr{DJjJ^j8P=;3<8_Hg-dJ>mMp$4$Scl6A_O zA<)BZPQUL5_VoLHpr_yW13mq|AL!}#{XjpjljWURVl5c9hs%fS3D+M!?ti+SN7feM znf_mIXU9jT|LJp9c)Y^>A0C(Rc!kF?Jig(2!uD|aa6RGr!^h40Q^8n=8`}qC6xPG@ z!}v=F#BLk+NpS7ocXDK`-1d6{{k<|1WBt$nKA0=AEtnMh;mV%D{qg=@V`2p#zH+np zc7a=m#75no;DkJU&n2;(>3`e$nxYM2S)QyM95;NdusvKpTu-?E@NvWK3AZ!c{_wmJ z*7qGK7XN5>Vr?*_Pg?xRa*20?>nC-Kt49*=F)ki@b-Z8q1kb=F_m7G9S=T=}$1V>~ zieI*_PjK$xdcyW_`EWhq`oqT!k40Dyk9+B^tzu6sC=v8w8CyM8`KQDhI9w)d50|IR z>1+HCy4*K|I>UYv_Mfm{h5aq;hYz;QaDMVS3SYnB>pFbBhv$Lt{185uusvKpTu-?E z@Npk(nHp}7Jg)`k7;b;~yu#-j?g#Pdb1! z&uYeVm8g~IpE<4L-()Tx=;1QWL-ufaxHjYRyI}H|(|go;TJ-L(jgK$rRU)`vJ|1~p zyk&<3C&2#H0r9tQ`ZTbsyq)5`rsfNdb>x?t@od==Z8$tUUwlldPJ!L``gC)xVgmww zP02?#|2!`7&W&SkmSfAY!g|!6MF0G6=m&hEUh>+(7t+KhWW4Z&H1P@1@r5+;3DNO| znD~U~_(Dv4LUeo~CO#oLz7P|i5FKBLiBE{m`NqT#{-}q2WS8+ftr?vGj7hb9*dJ_7|hn zC-sWXJFzm!<6+;Nv{Qa_vOLA&$$F?io~$1kPac>2IOT#m*^l?biFQ(7JlTHn>vBsE z1u>!N_Q3bj%LjUTJyMrSuRqY!j~nRe?Fsbsb_RNS`vd*qh8^VnUeYe-n=CK=5a`n0 z^y8`Yehch!esVl%L;86Ky7Y$}Pwdi9ay-$c|3dH8PwU|_;eEq(hL06)1C^d`oAhO} z&C-|2bK&po(3hvrQN}K4XSh$ON5(F&hx;(xx9R!GbCj`5o}-Li@*Mf?Ai-TA$B}l( znM=E*eWIt=6B9kX{yd?I>9q~xJ-E8aGl{}h1(ErTe!_~%;dTJ;T%t&d$>=i z=X76%`!L+M;XV(K1;;r(M&cvUb$9l)oIZAO8TItB3-t7{3-t7{3-t7{3-su^`}baV z;rr~l=zq0t`ETr}*W2MW-e2j_JfH$UPoHN3J$?QO^z?Zt(9`FuKu@2;1O0!){WluN zzu!2@d@TQ>`)^|X8C`dYdrh>CI=!|({Vc#`B5UAaz74No!fTuK^=eQieH|OD=hLsR zK#%6hzu!FhXV06_IQ|{S@$@tG>1Wda(DUZvq<^HZ(_(U;{ZBn_O5KTnlY_ZO^zbuj z_*pgl3>$v7O~3aA?PT}U&%)t0htGv;B7BagpS8pH4(j>0y*CIwQ_I)|b7^>v4bQ#d zIXOI6r?)5Qqx5zLI`v8W1D&<>>EB7y&o^0qv-Bf%$Uo_yKo74O!fW{S{Gd#F|0nMS z@~$9xFW@~-f;$v{IjyIUUGf}Hzat9Q89r9H4dJ$>k6qA)@VSKlW_0-6!+kcc@0&hn#$<=+x{I#6 z@SGFf@5%(%Mfe&CUpwJzD!T3xzthoI(r3XO#C&r4x65dqd3tV<-`9fviPo8?f4ljY ze#cM0*&(9)o%BU?-6ftqqvyNR-zvznd2lboJ>=Ou(9@rb13kRhohns$Ej z{nhCh#&mm{v?slMpr_Xp=;`&xq)hs813kSxfu7#ZKu>Rfpr@Z>T=xCH>Ad6`+_U>| zSvfD(P5;sNV-qK=T_VSmW2L_j4D|H-NT8GTZ<{}#SpU}l$oGf+w^jci{{HaH-xW%} z+l;e}vb}S|1wTy+o^h(aSubsB zd|aT%Rp)QxHmvu3;(hYD z=;8OVH9i=Xw)Wb@d*(7@_oux&_Nt(*?;Ok;>$j(PAqwQiv4;2dZ zy1Dzu-X5CZ&>OV%y4W4pJrrC=$3{+wt@}AgpwEGCd(?zagTIe+rydtO-l9!#9j!S& zESBM|je&m4?>%CderjTJe&20x8k<|HTtfe@bZq3D=7Bzbq>2q2k@#)s-Iksobvq>S{93fgEu=_hHs4O%bfAZ?dE&dqsdK;|K(2BVPyl(UzyN&#hjq|Y)2y(WDp zV<=;rKN$1Opp0`NMj#6)UQjsjjKWw7(HAls@}&)n#_ zv5Nnn@zSK{XXhN`T5u%shlKx&#~PCKfaaKrWH^qrCo`?j$`QoVGLdB5#rI_N<+w7Y zazybyX-x(!($CT!Pm&&%mWUrFj+mX}NE>X>j>K{0y359~r5)#X-JN|!C(i5KuIm(z zBJIo;v{SBqPm)<7ThQ9foV6oKZJE&w=b1U^kHq|tiFRgUJM1&!IbzYsuzoH+oSWJb zW0{Hm5}%Pi%}9Tx(4NG&%J|9rB_k^5Dn00tiC&O7PG&S|LtoEi3+KYB~JZ>+a2jwJ0#){q5V{N_vzNk94PK9Tu6*&E4gO6GF8(#~8>xoN|n z^~{+*k$yP4XH?J=;uYctNne#&PyUIYB~gppC{(Azw%Gn_l#%$**tdkJTHED=4wsM_UAg! z%Nd&8j zmX%r)*L(*0Pi9&f4TvKU#Za4(gZMJo`({ zQm148M4fU~O3ku3S!r|PPL?~^ z&W%MeH%m)WNwVgVcIF|;nn(I4FG$_8d*yExvK9n8*lF766Bz#MG<^?Z`N z;?As#_&SnxtBhD-q^xCSMJsDtS>wt|SJu3;_LUW|Jpah* zxBw`tV_7B3T3Oc4XP$IqJuNHiKR#c``de1we|)}>mAb6l6HhwQ|FXW9)qNIxRF0lE zIBs%%@~^IMllKBSVq!geX7)>5TS@;(u1^xH3u*a3p7*5plk19PJ&E;6VtzXNE|6Hk zo|*sueBMj031!8VTp5bz$TNlXbMmSQKkbIEnm^vHk}JdH+T*Y1xA4rCn3rVElXb?Q z&u`(GP0A#m0TVM-V$KS$ZNfhJ@0iDA20JsGotejE20JsG{o{E|u7@+T*}2YR$r1VE z`wbbLGjBG+GuWB;8_5v~zvcMv{9oplv!C)3Pn6;z@_d(AktUw<#1o`#$>+PU|DW-E z8Li}f|7^cK+hfCb{4;+0=kw=3KX?7P|AhS{tS7IFfBjkM&+jAWR=@P&|JnPifBt>W z|JnPc#G9q$y(autCou!$;Chz3&R@4D`JDLQz3-Cw`OKTHGw+v@_r5dlyZ)*@$+up~ zc}eCC@d%kS&c4U}xu2X{nSXpg{p**5}gJ z@H2QG)(MFxw9L%YvX)Lfv&kHtcoQdgap?!SS0v`^#QQ_{qR-HvSS9zY0)o4-rK<>!d*p{b=>|l1b|5;y33ECjf_~L#4p6ep~ zE>Zd`Id`3lU&&i@8R5hmbQu@%_p`@B-u24UuGF0z{lrY2@C|uGob(wP1@RT>A9-() z^e!0%@i%!xE}ob4Nf`xMN8}F1AeH>Y>RXN_cZol~S5LlCmob-Pi9aOXuK(xXtIIjb z$QMP5ABZ=IUxd?-~VV0 zCQk^7xkc^@a&5}ol0whP2qvxp`HeyRNW3wznvtW*J1Ox2IjX!%k@+WaZ;-iMW^{Sa zbuNCMxQ8dN4!QrzDo*N1=+c8{zvKF=XFXZ>{_(x5^h{#DOums$taxRlGT{%&cM<>Ed7XVmXV&mCN`E}N#Bq~r_;Wk1c=Fl54JDr-!o7N? zKmYu=GHYaGH02)k&-?$MKl7ejJ>r9j_k3sGpeFhux!ySY{f5j5e|*a!b4Bv^)9_o4 zKfd3PnIZXRLuP|BGluk)cxLkVT=_-h>{%l5K12Fe=F~(Bp|8H@@t~_&AB|Uo&DZb=8d!8zRH{-Z$cBl$;mGla)$r)z3V^!o0^=Lv|oM&Ow3oZ zK05n1H93}Clkx^w&P(R2bDN_Q_wmG>^uOtzD`)-B{FW`=B7U0qMLY2;w%q^Zy`8+j zll!8qvc%I9zi6NNEj#fZF!_siVQLBg4l6#A`~_C}_}qVAOV%Sb{42lrCFg3nj$|Dp zUzH@@fc<-(%fdd8&}C-(WZnGFe)BNi6;~zH1UKH5P&3fSyNPZB`Xpot zHQ7x9W4fejtf!MZ!%cU^cyr!FH^!Dmis>nCGG!VC+YP}+da9d(r2%?FT_0?qr@5(E zO0i!_u&HjMOQ~kMDOf@`154@>x|A-7R*w?(b$?xyclG^sF*QJ6p$8!QVd<~?a`fqL zAhu$vFP46~50<{JE_>C}rKzKox>64$w-32}_2uODan1FWST4uXN0*UOsyFt_U2k%V zsovNx*S%Z|-5hMLd%LofDy4d1@2z{fmbwMlg1nwsdg&fmdb%F2m2RnfVCkusb8aQo z3b)*qRLjtpyJc<~a-~~=u!t5>skN!8u8(XDlNYQD@Bpj<&+To*$wcH`J%F=>gL z=c?(ddY-GUtARCib+D$c0oKwr!P>eOSVz|e>*_k-YGi(DDFBv5R>4+PFQU%HE+3Zs zI-f3w?C09*HeefCkXN6FEiWmbUP#GBE)SNxI*%@oT!3Yv>+jm>wz@xi^>eA%^XOE4 zK5{;}3tVpWRGnK_Kn`&2bvv*frE_7)t#j!MkXN}5x;@yQyqs8a>72SEvb6eD{h~^% z-;kx%@5s_zFu#LZD{_t2U~$f+H06rx9PE`7tb`owI_eH!2kOm^C5O(gDb3_FHV1=x<3~^*3w@cGVZ_ukANh@M3+D{>omYyMSLKKet_UXYecJG22;R2!4({ zZZFiGz+=c0wv+A%9!H+A9clL$_JkE2*_AX@}(WQZzD zeJS=%t{eKLu7=B~Q*;gVZmzn^q%-R3SZcUxF0;<0t6{0`s-jl|v*^saip#3AfLU}^ zSJ`FLS#@PBRa_d2N-zuLl-zt@#_=ec{``N;c_=Q&Nj3ZB`1war~ewp+O7U`y8mY~@;l ztz9c{rJd{MxK(zg6`bQ9bgS(uEBK&$z^$+kxw+t6x6&?0UjaVs9&*dT<#w5U#69eO zv4v>IQhSek#4W|L%>JOXI;DOjY4ttF5!C7jmBAHKzu2G1(ds+Z#zEMqGGxTPzojXFlRxxrL zyRTI(*92_hnu1L!@fDV@!P>5t`%=|$wZYo%EA<8Xmtb92$DIJbP$yJ9SJxc}PpIRn zzN_bsfydP`)xgzvpM%HL=c=J=;EZ}h9Z^QTi8Sghq)~4pjd}-Z)VoNd-a{I76lo}} zSsQrgTtRxmgN2YcYv(LjP&qdPyjf2NXXu&QI^$;Qn~}G$WkBP!yNTTC`bO|3eXG_^ zxm)!u$Z1$^)PuNP{%!}6qufXM@euGcB0JUo8kuR6qgYk#Ma05BRj-hr8Bxr z;9%qwN>0_EU>)l|A%BP)qBFT1;8n=Ul`k-yIK!HPQo%-57pUSHaC=%qZ5myxa7MYPc zGx?1E8a+aPr;EB`?mK-F`He2*3WJ5&=X-LBx$jBE-PgLHD+CrIZv!>2aU0xg_Er0p zF5n8fugLvc|DcPz67C1~EAC!qs{~lWm2_WH<}3ZB&gBZY>>M$p&+f0)*XUPt8P5L| zU6MX{MZb*vLg#k5z+CKeLZ`ai?gW-E^sBn8+i73bJM9bL3w9Uy3bq{7lila=*Xe8Z z9qt}xsMqu^yBpkXUj$!e>$uM2Qr&TCJE3z@GKbIUN9ybJ>-shQqJ5oo&>o}Aah(f$ zPM^zPuSe?KU@o8AkJ8ucLjDFl3LJ&?2>TthM@R>3LF|QmK|fmGpbLNneE~m4kJfMK zBl>`SgS6k~$5O!O_ha=K{U$m4?VF^1HXoM!Ui%cE(`izEXVp{qpH)vIt$GG&)w4*e zHX*Hg4r$e9q*ZaGRa=mjeGE?|V|6}XK#kL5bpbVAj{_&@@!&)~0i2{Kg86)2$`oYF zaOC{Xkn*`a*z$Vo^SQjvdV_R6k2|KF&+GD_Tcq>H^yfO2l6m}N_73{ld*?sbp7fdC zU}w2I+y?BA*$n)qq- zM)QPQ4{mTzfUnsNZW?%_nPy(Mui0tlhl+^us{DLKtdHE-HC>{RoXeG`1!zGe5B+uZGLFSyU_HMh81(QkFPx&7vLcQ?2X zxd;1Rv&YPIx47TjC;DUkoBJJk!0b17y91=V+-`FBnBC@PH`5(72h3e=7y53q%RKFF zcB{=nEUV3W`?y_g?&LgIvwf#~f!tl@1@nx1+I{Oj)*tC_Il{+!Czcn?PV=mL#;q}{ z&Es~u+2o#e)6H{k6Zn*S4!p@c3O?$d1fO&p!Hw=IH-+<>YNnXIc8{H6_Si$+GXu4RQxZ+-V*&>+D+ln0XZWojd71)ZdXl&=1%& zw_816x8Pw9*sb{51NM2f72Kwt2e+$j;10DN+^KeeFQ}d1F7*PqTkTS7se7$`(yj%+ zci*`W^!KFq^@H{SYt=fl);wuvm~G~HGsA30&Y(Rzz#VMOFw@zZ%y~^Qlg*oYpPg*> z*}dRfTt$=3+xjiNl~T`}AKdruef5OQ)pP9}><`(w z;8WN)+NbP#^SF7~K7?fe^=vf*%qH_J_#AS8*^C@u;>ZDJ3vvJ@wwOsAcQW{nep^p6 z@9KBJ_w>7Z2emzAci1P)dQ+5ZB-L-X8_W}CJC+@G8~S$eNwdLRK~2ws8_kp8Q^+gK z)5t5#Gsr8*d&W$p&Pm{p?v$HoesVv8r#Op==BR#8FEhWmpWSlvv-=5Lh8##;+w4I0 ze$osyTWlPCtK9-VZ?}Tm?DKXhdo43d&9Ckkx56x^))l0QW(k(1;5Y79x6-WOs4Gbm z%qrvrvl#ml@N4&tyBXUAvj}}L_?7$GIrWHr*g7@OJ_0^WPs-cCqJAN{i_AjvrTfaw zG&i%?0`rCY(k;NU(A;8XV!0JL!OS^t5xx6Note{+YO zW&4|c$extxWqO)t?9=v6N{u&-%`7|HHa7i{J+Y zwl(Q~@P5XxqrDqjM^bCsfn(nd-pzIaQ{UI~`N0Avzp3f#`}X8^uzO;umbr;?k;oYHg69I!Co@O6E2{>!0)k-~;A;h7uyb|z3FN@nhxM4$gWr}wms}soOuuS>S-@S?_p>9^1ia4NxH?~3RVJdLEeU} z1Xl7D!R#iRxeYD5x!q?oS;5RQ;EbGgF<$PK2JYNnh?9T)9BX9P1_$=mTQf4!QEy2ttlj&!Nn5)36IK~*S z%tdE?0$W2XB|CL=flIm%mO zKtqWMVue zpXf)MY5qo^!AvE2a9W^y%FUwBXM)9$*ZWD7dwmrMBTD0hRojy*=3p_CbB@26i&`uoX!z+a7J zsJ)g_H<(7YAtQ7jx%c}a*sr!j4RzY({#tVH#eSc^3fmC7!Y{`%82u`{(yu^YNg8EV z`IUZ@`O180Mwl;1Uz)GM;ow)u40e>c-gvu;G9EpHO|cp5_2xuS`Ws3OH_op1tGu&o z{AzHO_ckM?t~bXibHaRUzM+h@kNP#yMpEDR_8<~b?AUM!oVLzv~W9ASw4L50~k-5UAk%rrPl&o*+ znW0Ecod#UyAN4Ux4Yx7U2wRujdge1~_}sk2{=>jS$RZ|YM%W^xYiu2?Lroo0U2~ZH zVdhiHe`YeMM)Z6JRnyk68B`71$ja|!_xil*PCpyG%ijs!?e7Bb@ppsw`g?pWTa(g7 zIl?uzDCt^Tn;PqwPpI=#Q`^=ex0oqvuC>KT*V$SebC{_`s%?I!hem=U&2^@@DQ2#- z#YrP=P4hCPYLaT15@w_wYfF$n($+AqkW<6FimZWF)BMKX*O`)(8f#0E#@OoQ)-cu0 zYsgaMjIpIiqir=T)lD_?I`S0zTnqk&{1JJr`3ZTgS*=&;*}gRUjkZ-OSx&y>5y{LJ}%3|@o$nZ2(yD=4#4KdRSI<}u`KzZ}a7{R{aYn_oyDncMVZ z*q32nu773wL-Q*+ADP?rZP=G$U#5S+`hod@oDae9B9J!(qZ_sqNCQS+WDW8XFJ zfTfXZRdrk6KBlVK>R@%dRz0e!+G_SuERU&ms=lpf*QvG0$5lOB7hH#2qpH}dU{%Vk zS9NV2yIwtxT&*hGDqt1z%Gxsa9W%n;U`N>zezd*84hKj0;q>%qdyOAuuLnmUXRA84 zHdq^?-P6tyZZ@wz3`O%b3z;7<&!(SNm)H^>(N)Ys#3R*oXN$*&~BmsVdq^ zb|vLksRq8BDQg-~W~jeQ-AV2Wb%CvDS5Ri9YDjJa-_W0D%9*>>UF0q&cLi9%USJzx zZ|EEO^5#5qkGh-OW$Jue!7d|rxk|&{$fx=9O?eXo(|pWVFz1`LV9dAm7nlm>UUd(9 zEoHA|stuO5zKySFE-3+hAFG^)+%|cW=5QcJOl9-7t87~Ox7}N8jkk-{A~oJFQH#Oz zkS|m6759#7>09`B+}p?rc9B}BCfM=F!{ol~-X*_Fm7y^KPNx(}J6?nkDm2aqZ1L1c=WgG^C#ktymSWQuwi znW7#+=23H~HIJIB=YS9Cx!}Y4A@C9XFgQ;?0?ya-zy*3fm>0Ph`5^cptyxPe?ga1D zv-Kg);w3l9E>QE;Bs&q=gqAn;dnmtGPqvfnd^MRgPwmFCM>i(7iQk33TfYGA(&Oya z`20@v7xWHrr+(6}rRI(PNiR5C&(a(GI*zvi`;&ebHQ;`>o(M|Ge+*hfw=&w&MO3pT%ajuOc(s*ZiyC>;5$`lj=>GOzLt<%l9q2 z!QFnB@8d7`nbaQF*the0xWXFyy>5?d2e$K_{XVzX30~+sft~$@e!tu2I{D`6UH^`6 z1~ymC)O-G2-$FH4?||?4w|!GA%~VtMvVYIFR4vro;M@K!-vmoj)kMAI52GLUFZ;%7 zuipdi@h^cdVQr;as<(VA(wja;ZetZw`}|&CM!o6Z09zr`u*6iF+VA)I%<58q33v%- zl3DfPTym*h{so^)9rOpl7yUu-kbe<;!5;#1li!Ga(^MmM!0-1B!A7bf`yKENz=rBJ z)xo#-x2lf51K7ders`vFpl(r}d`Eu^_FL8Ms=e>xZ>MZ~KT{oW``t`(Z&5SVe){JQ z^1Fat{6*kJ{$hW#I_M6#n<+U{%~E%$i~TH8S6`2s>#M7=b@f-1difcYyjj)7UQbO& zp8@W62i;Ig_3}eWJ$)T=>#AX@r|;p1siDZ5)GoK%-9*Xh>Pl5sl~IF`f@Rbjeh}%1 zAIz5E5&ya$NSQ0uKvfP|o7(EAE7W;xT|pYCu2O^5>wdWE;V%P+A#YSKxLxi>j&hT# zMfuulfGW=(14vh>{_1?T`jZBz5o)-)%#R>-_tVs7_kx?ozBj6Vssg3@k@~BtD(*JB zspL*meX;igFF>Z+Asjo^wpK&HHmWt)R<%)6)D{&YNy&_?V~EPM;}sO^`6UP z54rbTUYo~GR$JW`H<|KN)a8`v16D$|XTMZCNj>kjx=ECotd3FsJ$KCIvw3X?@>A_Z zwaq>6CQ@dS`W*W)_qoe&^VyE71G%4}f9^hW1#EtsMP0*rW>ME7v#9HkS=jFGv#615 zWl`57v#3$XEb0bi7Bw1~MU6pbQQiEdlbjG3U=h|a;Q$o9O^=34%Hc%Lv=ysP!}O{sEd&~R99pUbqO*DbzA}#vqjmr zxGe^ju*JbtTf$~l+ub&oRqb%w!JTdgIF_@|s>UI+s`1FIY63E=nuyG*j=PB&})r#8e>V0<<{R8(t_@Vm%{K$O>e(XL1KXD&} zpSn-LLbf2~3)@0q5nC86YKwqJsW-DtWqy3!r`oGj9$OMGdcZERF)-%R+N|mwzGoOkyVjdxHhuzomv&PvT(J? zcb%2l%FOj6UvXAqJ0n;bSrM7SERlh)>@Gmd09Hg+Kzin)3ITfMn7bUmW|YU~nA0r3 zo1Mp&Wj-|gdS8w$!(6GA0?Q#~Y-FTLGg2~YZGsVM9gIq1)LI2&BO@hWRLQ8d492Mi zBUBts#;JHPQgXMHZ^UGb94aTVnBUBho#;I^HQgZi`ZwO>;5~G$Dj8K7K z)EWgN)i4;L{K42HMy)|GHhF_ls~?O_o?z7K1!I#Mj9T4bRB{KSRwo!68L7lvBcmuI zR4W*p#HiH_MkRYNYBhqfk&%*b5@pn?2P0H17@NeXRSiZZb1-UEg0Yd2l9h>!TIFDD zDg|RBBPHv08MTVRI9dR~s+Z$$5-qW4kJ`@`t{ zq5QTKz3+|Q&&yX0(ffJ%{~3i>U?Z^NCP<82d)G21{@D>O~C0NNQL}?gFCJ9wPTi@{6fSSQZk!HW$m~ zlbVI+?bR{;hl(n&j6{ZpCeOa*2 zMeI>Z<@c-k4n04S_N!HHKZK~E+@821kmwTP^@kF3lG_g>8YZ_NPOMIDKZ5v;-2NJ( zH*))H>BlbA(g(Z9!%iPgV}h-Hb~zlkWg{$>E!37P8iklTUnD~N^bhjTZB5EI&z2Ke1fbPInggEd!%|388v7y^Qi4UJe z6zlWgHX_FFAnJ81C^6)>6Fa*_-9{Yk7WA#~N!^B4MBhq$ZBeiYEK;`+TU$&&M>~t5 z7lkKkCNaasu@r+fY7;C7ue#Ezk$KfMA~Na~Vjcw3OpIuW(&WADVnoKiOw2=!*oo5W zHCKYYit7^kS$Grij3&g& zO1wo=A}X2^B`eVtP0gpS88N1x5=GI>e8RVw&B5kGj(*H{iGnSN5dDZR6$M)o!TBNI zE(*3HM)L!{W)y7As2n7Mz6f7DwqcCk=Uc}%rm#AQ<*2&~|2*mj6McA;FChn;_xLI@ zH&FwMuhL$mwFliH^cP`3Imnk|8Hwn42X2pdh@i-Xp3!T*k2(Z1&jE5@a2kCV_yS)N zYrgc|1McPvaLxDO&2%<+IhupbbaR~*W|OA68SENONjZEAEX`pSgWtqA(M@#@P?$6t z>n3n!G$!Tp`#DM>7}grYoDn0X_!>s5>O^p9Rf9OI>d0!Oz3{v2r(`Ykn#8f}<%{#G zL&Ag0ln|X!p=gl@sY&Fk=+s$EkbGDPa z&FnBQ!J4xJ%Xat(wvxNk9D+4xC-xoi6l}q=8Cg&*GB3iKvxwZCCcnOu*r)vXb78&M zybgoTVk4YNiz%}Rri0CtFF=|6dWm@hCZi?fE`|r;IqU`X0-~x4l3PG8HSfWPw3ISS zU@F)|?lSYPdJlXL>oeF2s^#V#Sdo@vUuN>?LU5$z1@nLls3otSuNJ7hu*DUEd2K#g zK0S|Ene4Xwhr*mV^ zMGSCpQv%G2%#2nN%!2$=<(j#h~a+J@lGm%${nBL6DugLuprm%;J?(mdxIwN_d ziO$W0{F>aaUJ>+4};aHMaX#2~CR7m-$(5}qh0UBcf@d|C;A4{=c? z{Jq3QmGJiw7gfUFPh3<9{{V4OMDG$8Rl?69E~Lxj`YV_H5q7d%_9s}$OAiCjEbD4h>9+On7;iXHZOl~6R&a)o{ zaTAZ39v+SpBQY9+YhfH2K>&Moe`H?! zJ0Gy-rA!{8qx$(LOkdIllh6L9epmU(&1?JkzJ7yg=RZ|PRXcwa53%YLj00Bv2+M#~ zKfxMcl~Lb--@xu<)wggtS#=WrCab=KkIAa<;bXGu2N(?s5JR)U6d+Eh4_qZ1U=1mt zo`i{{fZ7NXNdff~Oe6)=(_GI5)H7Vs?Ky5cqGdjTA*(mBL1 z?*KQTA-1v<(W-5+U+CMzc4$Eh-%#9^C0;*n%Mq_1x91VR9=GLvCcW8af|GBv%?u~s zW}5{zzRj?pWYTS@r>);&OA`IR#g-!ae~T?m^#2xHhUot-)E0;1BP(2e&)ID7^F3#? z>m1-_Y$<$z{JYBlL(i|^@5l@;1?k!T1-+^CifW|az~A)m;O|lfe`Fi~DfELZ^;T6^m+Z7P<@57tZ4SvuCuz_9% z$}twe71{&6hwcgXgw^w?ZRuP2qwL+%e@IQu!RGA$5&DPVQ^@xy)yls|YUn@4@)0~! z4SfUuE;$YTHY^{*Kh*#>mv_i%;GL?i>u9Iy=(?a~D?gEx1=My*ZiBB%IAGppkNSQG zmhJW}ThCYbZ;?~a@5HhL4liMLd6S&#{tdQj__40OZlK4w2D%~GP&Wb_!5upWZo>w8 zoT~?y?>Negbw}U{o~Z>zvl zJ08n8Sb;8v&-GsRxL8jice0y6?s%fDE9)xy9`d__U15QpO70Xl5&HyUnJd9sdN+Q|1A{@6D**fq5b+L6}?hy`}x_*YM zq$k-Ku&!0ooozK3dW6xYn!niAh9Br+%3ox=GETL9S9s)Vfwi$-Xsg20bD`~wobDzO zvpe0*Kwd%_;j4KS*~wOcho%!{tN4z#GE6ibu~qgp$h`#aj8~91x#?~)IGK3gny^B? z0=`0C2P?ca9c)MBjqWBl#okDo3QNXeO4TCOwC%01__U{NMPD0xEjSTgLbfC40vL=g zfG1@!+)%S&znV=iZJ^H%frluyfm9n7h7Dj__PEZsC5`mAxEtM6dkbkAG0+3?=em@s zW7|+_q;EsI-q*uY*WL=d-866-k=D1tgC}?+(b#jHa9Pc9!dx}S2{+Xo7-Da?x5JWm z6L=Fb+z(M^E-bOap7o%cMf)CvV|JFk3(G^W;|aIc12D}lh7a&|HyxZ#%=i67)-8tj z?-t74>4a@dI0I*ZGhoJ=jYT*CXF1V@J?lP7F9GjIHdmwk4a6be06WaRMC&cF5)F4P zvB;yawoupmQN$m&vDbsGIop<4S`e$%8m*OTWn05udoO#nMwf`YmbR6>8@9+LFrkcs zLsVkJM!9@MeoOS*5aQMIsjK}^aHt;!4ui!apBfH(MLsnGPKtc$8Y04*Qcr8uRJE`z zZ4*$UPMX^maOd7l%@327+8QuvG_W<*26#1UqD%Z+Js3D7_N@Wf03MuL7`cs!^LhenUA5jmVe6|j zSkmefo0S%@_%5|+s)=n1Hl=g}C0uF^h#QO9dX%qAlvxw<8mh+drpd3Mjlm|i5fN|A z=;t=1LB0wl>k$#!hUoXM$U%NyzzKXYv7&?g#iYT$GG(d|M>?2j_=|`n9qd=Qr7#Jv zAZ~K0?Lw^l5Z{ITt9&K(xLt26QNFTT4)6Ff+nJuvM?7j5QN#E+IIHw|kA_*!GgEZ8f%a#&Z}a^$bF4cudPEx6V;gVD7D(Qb{LL?|{Q{b);R) z`HqBNWifoRja)@F7W)|ZbXLLGE=)ViZ8o>Ut^`-wtgZ}otcJ5|l^YALhME0ZO00m> z=Q?C|N@jDVDYY7Y7EkYIP{Z7CaI_od^3vZD8`_pw>%64)V0&Vx^O8D(9myX-+2O7m zHD7AG!4tdM3183(TZ&p&+iS=j;ksk*X1m)*iKG>_q7|?jt>D=8>8l3dqxLa-8M)m- z;rJX*UJh^svImyS;1b&a>*p|=17_V}HYcpH!|ZUj>alNq*OS~Hwx@jpmfE3qn9T*| zf=#v;mY%kkT@TMFoKrS8m>YK38thdMTw@<4@^_7`0hhGI0Do*gF>O_E%J;JHRM}Mb zDchfzkHEa@Bl9t`wkySX)h4Y0OR`m)eQUW7DV0}!Mu|`1>-iAs@a<&OZ+G>o}Ot9(NP`I=Emb zppEx?^)>EVw^wIS*MQej%g1`K8w6kKC&;nBH(YjOVN>gEC;GK;zD{IcSkmBKyWEZ; z^|AZdcP}ifAL~Idp9;JDXx|4uyU~>DWA~H04_?%d^p)_P3V%FIXuhwVMCxY`kh>oi z)DQJQ_W|h&HyNh1es(gczdcCq0hmlb&{x1adW9R{rufOeznwxFV5j;iu&7NXU14wc zQ@!97FoC_uUI$?*eV@MuaGSr~545+DuC%wpW+!+h3}OA@`5fSG@q_GOdkY+RgJ8(J z#SgYaR6dvAT?J=?V18G?U9IxM-Fr3mAuu^yr3$#gq=H~U`gf>Gg}ZmC%H#5aL-5<7 zl)qZ_qyGM`pL>sX3{rhuUpI)o`?z708LEb zV0)F_=-z?xbfbG0F4B$E)6WfrWum7Wp>Bp%ZUiNVtEb%CaHBp&$&Ky`xF&kKYt#(b z^sb@I2qN-dgsm)#JqY(%7Ic_P>>(J+GQnzc$Yiw#;LpuUZWegeUNVPGM)F@W+3bFE z06ak60Qe|+y1r^U40?U3`5N^!M|=ui-M3(7y$SxjzAD8YHZPkL>Nsq&+kIv~xS#zc zKKwQxw`Q`BoPKBuVH;dIWUUWSt_ zk9q~xu{`QkIL7j**WhHzqh5!TDUUh=ds80u2CPnb)SK`*`FE#qta+z;D2J>#WBz&EH6_wGQ1_ z3qA?s@kCg147!3Rj^p{g)c&^L!*Sk57mk%<=D2wiZkA(4nAq~b-_lm?G4D|3ZTME+ z^vBH`q!Z?dKViNA-$4FGShQT7tE+u!7rFmt%gT1qgn%#Uq*EV9&lkXI0C+*pLMCU`UjJ$exuJ*)q4K~JU>tP z4d4b?pHkJ6@H(ZcAK>kxm5KlBe#GfJPJS4 zdiL4vTkzK)_JF%#*lB^b58UfBsRghf35UW0pIbdg$=qra`z*q?(Dze!_-WuY{OvZl z0Ppd)seAk#;2l_R$AYHrf*tS<^xNSW7p9*{T3CN3p-Cu5(aC+kBn z0FBo#z!NoI3xCgeO6~Gfuus-g^oua}Oa-Utsrn#XKI34Kii11-W^g=mEUe~nFz&bb z%PBKeU#<_p{WC^yfhTDU%;#IY@I)*EAB3wiGunebmwMK30-uLPDwo;@(^M|C9e%1@ zYKMOo+{F2h)?49N8Vy7HRv6u%$9e-S?$5*beuIWnNY8@hV<-GtcY-e!& zB<|2Vk-PN0eik^(zo574yXcqg`VKV<+`-mveV@M)5qDH{vpG(c7bbnaV<|7|L8vxEj zuF?;|ld_6^SHgZZQ%zBu*?T4&YXkHZFswa-e2$zcFl9|q{~vqr9p_bX@Bg1+m%0nv z=yic*m)?8tU5bDp2uN?zt%!=CV(%4u@1oJDiHUlXXcA)*lbA$Pj4>LoDK{~_`+GiT z^7$?(C?vV}dw-8_{+QR)Gv}PC?|ILA-m?=8Y&Q~q17>BImVals3%o1r0(WsQ#P!j^0qcfM@F%*cO=w7asWFlV9X?RsMOU{;6S zJarBl$DRsjWuL^HjfR>n*^KS&%(|j>v-SL3BhGWDlVcvLM@w&bET=VRW+< zWRIYgtswgtn%D}mN72DnkljETsqth_&Eo7DG~5+u*P>mn7%g*qz&(6(ake_F0oQO> zM{%~6`#FlUb==8OoE^t46UEtj?v5zVHgHo!aki0L9g3-$lI&`<>lLGs=hSRg{x;0) z{HxH(SDammj=tjT3N-Q+XP2XmPpvKU@{i6h%8uslr=n~=H%1j@3-YIdm&e#?{CQD! z9`}(HW#@ATNl|tI8ZC>m3&Ta=Md++7$}UDbT~UTEI`C37;uU3=p`lL=Kxd#aq#%0? z_c_^a+>fDct`OI`xId0=xk6m0<9-~ia)sFwXp$?;o}>;6seyCQGjc|@1Kfe`B{jvI zf##UG+}+cFZ&t6&wrn=;t=aLok4Gm{1I&rwiRff%fH@gF8Qnt-Fx$ZTq;0@6b9ib_ z{!!pj+zK?Axoj?Lo7d2Gc12c(-^#Hv44g3{Bij&)|`g9llq^Yzl^#2`|Pp5 zgQ*AB0J{cSSq6Xu*lC6fjSmhg{(QIz{lI?sYr;|J3--m2URPYT z;3D*4mgyaJtjJTSll8)1CzFFv7pw#Jz*f&rU9dZL(za8Obwwt;0Mnh)?ux5ESO~gu zZ2;B>UCS1MYHV@^TnrY0uAWP>D(n)Bx93*kE5&$+ZY8cVxCoVK5t@XnAsm@WtfnU7 zYLv;JX$&?3<=!*_8-waXY6{n995@btGdL4t!Lj(8!-W|Gj=`@Mq|xAL{7Dy*dUm`E zc?4V(we7S-GHMvwby{OafFlTPLr81noQB~lhYvC=<1RQ{+y#f-4r~h!#zy)E7xFmh z*g+l#Uj^>=e21yk`cn>;$1nAnak$#@HR+szdYs0`=f@M%jxS3(fz;-tUcC14`}|6E zI;kJ3J?OnqBjVqvC8#Cet$ruU~nrliHrtBczTa z_2{VcNSSvvKdDnlJxJ=>Q7@9^t?nl|L~7y52i5+jULNnOR=0-wp$5^i)UIT`sS|1t zC80K-&R}QatXuU%4W#APq1|)=)%Bz9p?=^1Y}>*BTAv!+)DEPMpsu7-i(kLkChPuP zH_^VD(bP25{qJqn7N>S8wWk%*ntOn@V>LDv zz4^EoV5*?@Y`4eYtAge`2KPctCulxfxH{N6(LcNM#Nzl3#}cZRx<%Ma2%8T|KQ1M- zE2#duWl=}bGJIWe+q0HoGU$J)%jG<=z!eR7uW(Jkib)!CCBB8Mt$L8_s`y{42|bo| z*-Gp+ge?Xa^YmImmx8S5SRvX5*71e_F2z>g-cmFRE+OyZcw!0K1dqeL9C&!RiGud3IA$v1NLUZR)MQ{dJCaz!A;m(V_Vu9Th3NO*AcP>dn>LQjKiBre>~xg%+cF%pN2Vsxx^Vj&2uL(Tl6NsGhz$bLFmcMBd24ZN!Ur?Nj$xi&~4xj z>|L?N@8S*lxScz95wi^%;!IMWh1m|pa8|_A$SKhW=U|`CjHdp+-Iz0&(as^nd2I*O z(r!Y|!<-48$9E|6K55?8^w-4esXY%LzRnycAmv$F;%p$^8mUE%0)DSCaNT@I2md73L!FN^JG% zUIbo5uGjFEOF(<>wfHXuug1QP(96JUu=fylDR?Qls%5thcm?+L_^$x>VBbLME5Ylq zZzTV#!7H)V$a^JHI5!e38!^{{*OK?` zybtQ1_tXLRV5_ls5AwdZlKxK2jo=;FcVXWM-bk)@^RAmg$EbSE3*_u{%EyN{ULvio^cJ@CHhz8&BFxNb*=^<%P*AH=u_kj11le)O?${r!+-t1%e?#mwK9ngp5T@SnuTfN)&A+LKcxjshPdy(mV z4EM(|4`$wNCO$|`PwJ+)ra32S1Jd3~zY?biQ~7*C)6w=xJh~#XJcJE zus=iCCy@_zbp9;wK_4Xkr@+r(e~wh2LLTx{@x6dXc+ zUm)~Z@OkVn67~%E40*gj*t6iX_(C1tjynME>8v|0U3Q<{QMkfb`yr z4HhlIWg{s8+8!d?MiA=fuB-$lww9f3c>RSdp?{U&K&1z+V2Z(+U)?;E-@*Sw@NMj$5cWFwI=L!2COZHBl=qZ?Z(#q7)Ng|C zVE-J~TcDCh%BsDIMB2}B{{ot6Bsh{>e~JG;!T-X3m$0|Nw|V+kg#HBlCHAi)_3>+b zKf(P|e80x^Q>5(PA=lsV#5+iv{Ra1MF+WF=?C0e7JA6M!wrn(S`#m|o3y#A61986u ze~0}?!rn!y?3d*IC>o{gzTge~z@$p9%dn?muDw85i6eQvU}0Blcghe*^xOoc@aI zw@9@77596*@%P{u>@56_T(j^u!b5nE@DP5_(;@tkr)z{ikavxcVdsTEL!IS?Kk=r# zPy;(3X|%s&H8Fn$m6xf>t*U>?Y9R;tx2$#;%NuHkF}$e`{tSu0TG(}wXnYTRk9X7~ zECVz0E5H_|3JZdiV*zqRjlde%g~~ zLoucvl1a76qlEa{p_H(CNR$?YCRrIi-SzM_BE>`cEGM8|280d+gV3K%R@(ET8B>L-xjRG?o4Pqup@RCa&Mk- z2QhXRLfaG48M`ZK+k$O*Lsv`(_C3q@l_%nqQ2%HysHX1o9=}4#B^kR+=KV@ z!gK;V@mz0WI)WX^yAQVLYNZcvYYr;k(U-Jc!LH=(-Ok;()43bD_Q&)D`{5hF8+(9i zh#p92Z{&yiV-F&%2iSu=1{2mBNub`mV+f{2HU!fW98B0yQuGA}VGqOA4;+d;99MsE z81@MA9{{R%dL*F(!$@NKhf%y`5I6#RG+_h5f#fWPGn43qGU07sC=Wc;JSiP%$uE5s?hp%pk9 zdkQh5!&K6Z1t(!2fomK%6?+=?I8ffh^q|)3>Et{K_tb0x@@~@zpMjZ(9GdcWN8+0Z zP9#@vau!{y&f-0-L8bp@lXem~i8su_90AV8J_`E?P^rziylXnBChfW8JQG={Y2-bR z_-V+T%_U?${v*M8*b8vY0$ndJAnZuov+x~5+L_3r&EyRW$^R(unCMn&X%YT;;6m)h zylXC~R_kL4n+KCldI`&fh^FgKCmcrwl2QP9#D9@H*+JZ~*EhqIc;1cW=xE6xT zu~*_+1g^kdMgEIHwPvphYRz61)SA7T_(gE#7LoTF;unL9$!QI-t3Y*XuO)6N+`84+ z>w?^Xb@-OzUWRWSu4VA=*6`GEnB|~6(c^e_4X8fu_1G)m?#;<&}qf|Z{8H%pJ$dA+ zy%jhNe=#^5+w*jl&_TlpslrzYZ8!|Sr}?U&!-nGSh_4EIaVY-sxT06jc1I||A%xV2 za+SwZ&g#BxTail1pB9K$--3L+Iv9Cyf$$n&4^~U^^lD@3u&$Onr(|~z)@pqTm9r;@ zFOTqiOfS}meF&|IPq$pYnwUO3EgzsR?+ReRUki6#^2o=ojqxdYK0fPO?eNl@XAPb* zf1fqyEWXA3eOK*$@~?H+`5*509Bz7h)MDC^ZN59@)(zf?|Kg5i29IPet|heox$sWr z;aW-`mbO>u z%Mv&vb0QCCA?en@(^&|r-+wLn%FkI!IypIVR+eKQM~UZwE3nt|Oyc3JgJZIaunm~w z;Fx$Tg!~%$D09eBPR@F84fZBRhdFRcR+C~g`L2eWVjI}PlX-Ac))FfBW-UCF4TQO-C?^qfI{BXjoxO zc92UgxGHjq&cvJn2jw(!*h#qjl~b{I@ys@GTjaj%AicXj>>!cP>EL$a4$MWkT zn=+I5TQN6*H!(}zikS)bWKZPh+<<)>u3O-y+<@y2Mvl7Rjo5dRUQW)D*z$93hhK6d zad(mLjqp>vSLtq^xdpsAa#oy$@4?&&r$lbhy_mbZqH=^i0pcK67u9=wzLiTN1j;mEyt z1bl#)M~P=Aj3@60?r+na98h*iYkn3Uux8G!*tk_$E*C zjHi(0+kBj7o+bB>!yl1XBVVQvdY`~tQdo6muAb6z6-i{K>em!R(_!5MjxRA0k<1%Am_c~E0jMes#Ze1r5a!8$dq!%z7-slJ1G1wP8l_~hYy2i}QXqwkSR19&IjBIf&~{}%W%DPAMT z#KZX>T$5Mu$*Ga2GKCbcL+ek0J0gF`bA;akUm=B@njgYJkze#9@-Bj3@_oYI#Jm9y z<$Hv_MK1Diet`XB@GW>Huak-sUf6F#l}!b|&oiDulauoU(s@!(9?lOVPety~Pspnn zd<*-hq?VKOM&zcvMW{TQ#JBkwJQ8^|{{?+G3Vf4v|Aqf;@NIm*Amz_Nc|~$+egVFN z{Vwk)1%HD5E1r>`^IzD%!u3lyDL*6T*F5<%@F$U{@^f6jCC#tE(b)2Eegpmj`*%F^ z3wS5L#PtXAMY@J(O5vl(ANnIko{HxV|3ohGbKWJzpLt&H&9CwQg*<-?{+4uqfd(EO zIW=-`enX1C@%-;V`8e;9dqdE@viHcP3}QnrQ5JqriV*%lXbAF(LXb1$X~X~rMV?Sz z7(?!Pq|XSEKa(H+O8)tz;V2_+c`9;=Y6Z>tGgkK_ms5Vc?!+DRmI`CoS>eRrl z3(8-S>r#(A^Kj?!Oac5E`8o206VlAFPcn$3~t? zU2OR_@>JwMmxMvA1xk3A{G58ka0)kaSqiYrBG;%4u1({tA-R`E-VGcj@{*HNNQy?7 zCRrn%k)Koaciv7zxF^NLHQ||JI4g3AnquU#aGw`kl~UrG^Q1hShWJ_#*AOg?9G50p zb9gE|pUJOj0oMc$P$pld5nPi-#L2N~1Ou`38|2`8l;wmh7+a8sJ$>%g0u!8d73DmgXn;hS_Iyb4nR$D|eU9WfmuN2U^# z_tP1F6m8Ls{ku_vOE3`U!P~mPJLyb(PfRyB zBAp29g-gDT{GHxGzB*hJa+G`19qfuN$EGLP9a~OKFZn2>>qmTdusd<`WfBjkFYZ40 z1_XIc19)q*Y+y_w7e>BKm&jS^fjyXzL2yupW&OZ@q>_g-5F8kWXG1W25%25;KSf@T zJRCVI{jrA!c}l~{ORWR_2_3;x{lVe9ZzTB+00(1_#5EjF$zWWgi5&sDgFc45_Io=iNPsc=%p6FQwI<=eQ& zJ%juw;g(}G12Zkmgcmazlw&j#GaYV7GZK~=D-b+4JI zzD+;AX*ns6h5xabv~q8jz!OXn4bw^_t9tMM-e7n4Fh%OY?E_8MHP;BoZJmV@qT z%Bxw4dpY(xTykla@}&HiHSk$h;$Kh7wcuKOa#-ZO$gkPRmz8H5LpdCRjl8u@Ccj1A z%R21Mgvf7Mg}nt-zD|zO)}Z{uR`Ohrdp&8l^27i_)?pt{nk}IGp%XwQ12Q6gOd?#FLwlTHHvAlX=HRq!~BkI)z*|BO5t@)Z2o)oTrl47Gx>65VxJ@ zj|Y#(znwfzKqm9VfaW6H+rt?=eroE~g;B zc?#)v@%*Xasrb(#$M)G-SuI zrphCgt7qkOmFlXC+b3)BTzX%Ae4~ABa^U2z{ zl}0v?^qxAn{<-h^N6JBdlqFM(FRAzUZ}H3O;jha#%FVKD?;m^4Qk3(R z%2bY;Wn``8%ER)k6W=6n$+v1J9$Jd=TTNxnrmwKn)7M*<`Tv98*Oi&J1#Pu?_wagRdPF{G32ocGy=iJcMNfEpeXdyic13Sx$Ua*}I6@7r(X za?3{?N-G+LKaZ8nC|ZSF=-R{#r6r6cG#|QPBrQa)wY_r~EpP;(@~(!1a=D@7_-`mo z?7vLuvL9KhGNC-32eD@WLZ zvI~Uu#|+?$gXL@M2xBtDhx9E)4I&bDA%e72Z2pf#v; zXSy|V9ObA)=%`qO%6N{a#FYhA?$bI_O4a&+u8s9o5o=IM&01_VmU` zT4@!jEvYPM*)|b+sRkW$x{hz6(I#Mh4a%DZOFZ)Za zI4W3Qou~(UoHCwC`qTPy6j27$8#t8?Rl3vu?G2C0eR@ZzcZXUZ%6d9NIkI-8Hrx?W zBYCPX@5ptxL%C1yr&L?H^_Ap4dr%MFlWR>SiBF|GmH$jPh;pgF zUNaX{0Y4x57qoVcrsmp!ZSc>JbvmDrqv7FOn+q`W;pE%SVQl9Amhu^weM(h$WkmE9py9rB4 zvz%O%7Ci>vinvd(f)IBa7UN$@-pYwC!Cr+?degCO4S6mDt$k%bmEl~5y_P2{;|@R- zSV`)2JhK8^j(;64rA1fbTF*1?Agsi{fgC%+*SF1VjJ=stfy8gbzXn`II%P&Xf@?{; z39|ui|5{v|$xF%6paQg4d;0G+^1 zgq=i)lAPYp?0$nX{z{*o!gE`}t@yXawt6b<&^?Bl#GHz8r{P3m+zsdqcEUc5=hIGu z`wHIS?0$o?o!;tv1|iCD+P2S(?fOjeJQcV57s`aX->{u{cOABaok_hD(*>TrdkklR zofS+Za@>t^r=bfelp^g4?!iOid3se&I zd|c&FU4%UtcO5*9a6LJ72i-roA@=?oc=Khr>tQQPdL5j9cPiY0 z*aO%9T6{`|y6bQ~IoujYh+BD9nNj6Vl^?x{eE_9Zl^nepKL3rRRdVze`2X%d+(C*x zaQAN{^iEPJE$UwEU8Lv%r~hU`?X7moQklgRV+yvME7E-(Ga7)~2xEoHt zI}P{qq;jHnk=ui$zXx>OdJtEV9K8?j{@tW{2y;JpAHKb$e*nA}`(e^5Eo!<)NO3QC zFL56uMNe=q_Q!Dbg5UoT@yd@Xw^^U(+;w;ue!i(6$Mq2S5GkG@h0>yXiF=Z`UU2ds z!T$;3loov)`;+AG80hS$#oa=ihw- zB}Cm4n(-{z^WgYG>j0qWktS4r*e!q>pB zk@`EhUj@I3?LNRa;qkwO?H0a7e3z${3H=`Y{_hd*PJ_D(B|PIEgVLL?VY|nmtmf<3?f|?FracDdcV$BR!PWQ1 z@E;TVCRl>~V_c>1{(nHcI}LBa?a%ErD7Wbz!#m{tL-_hX!u1nUzX`sH@28~hA9?>} zU@4(LgTg3KPSJp;Qaq5wz~_;aJrZ93s8y8GSa)d;2wiI3Ew5J0id+ayFA|? z{=YIT?g=ym%dp*J_$l~PQv3$@uR&!{e?u<+#cseaaQ%+d?ku>+;C{nz;r72vp1+Uu z(jTCw8p7>wNSrdGjo|YuN%}|fdKYw$;ZNWn;qxnl>aK(P4UI_q7fjl9_%l5J-$Q+& z?~Itg5z`oKg#8{*DlMw!L*+yN%JTnDagV{>1$P>h-fT?D8sRVGp4)HuE4k$bDZRWP zJ(wSq`^hI|jkq%aWfgZxai^gP>C;YwyAH~5N^jO>k6{SN zp>_5FTs71qWu3U+;7)_P3+^?9N~(umZaas3d0xY-L5efR)(pK#a7B8y&+gz=#0fLX(Z>Y4;vxkz;N*LK(sFL0P7>4>5rp zN3a7hI_@=$Vt2rOh>4&Qs*}mpeTXsmrvy19Q-Yk6DM8N4lpx=QaAF9-p2~ZaF`dIZ zlr2qr6_c_fh)uf`N`A_@QLCpr5l7&2uVNZI1M+*6Fm*p-8on9iF_|5P>0t_PB~oYL znu>ceKKC$YfTYTBBiS=Es8eWWP-1Cjn1)=@Oul4lC@+^MC|&Dnuy&;HYU5VIO-ia( zq)=+%QUa|3{`^Q67?wGn>Lr+QkoF@7Z;J+0aV|2W1CJY~C3PK06#`LtRT#$jd1~JFU3+vA+trC>~(I3|UW@vdE{V@HZ6FTAQ!LZ=@-uH3Hi)xhZIU$pdK& z4#W1$Ya?(dwkKR0fP z@?5$^l-K4dTsbwJapyQaop9&4LGpca93y!{Io^`|qw?~qSZ}tC3ZAy!Y$5H*&w8_k zC>h(9TC#1l<-OLMt)iSSvEFPIZTPmXxVy!Avpuxp`>i)yhiJXoRz&N~HYD0(Y+GXD zIa*`3yrz_)_2wRB6Ux?llS|o{GPmB`(Q8CqSa0sKRo9!mr$MpaJcU{dW9I2Gl%A@Z%QYo)hU1O67 z`FDMNu)c;i^5?t0whUE7q4aRb5{bVx3uE&MnrI^;KiP`f?VLH#>>>#GRvz zcw0r<-E#NIy))a7yMOM_*{di@V_#9e-d<(zaXc-e|G5t}2vY(M#y1dG8da;uQ}>b*zqlVR_lA_6a#VE}$^P93 z(-`cF?G8f|&|NJ@Rd=l1`Epck8pqRSj4fulQ$~57bfpjbmvbu>*Q>;L4KdiZ_R9<%?*YMZqk+c)hoXJa7AV?BZHJ=0*48N6n{9`pz1-F)+WT#dqN9SXQFOGhHM)1?_)`(b z4R``@MAFD^-bM$B)#|`^oz1SxUV_y{=L+rz%V~D+4bPTb#i;fW$6DWX$!~eB-3G8=3$fru{E6dZ^>ApX|?!Uxj&{5vU^rnC?L*fUrIXo-$;QZeq;S}LBw8bhlbLio`5 zUQb_1lUOF`9Of%}#WL~q)hJq|CFc0h614U_eI;#USxSFd$9=%zvD}6e?wX_szZ99R zp)WWo*4iY(k?td;4Q;Ujp;BkIp8lXEZV#*vb|J(TCLL*AOaSepQjxYo$Gmo!w$zHf z*}8F8RhqIrrX6J_6=kiBqaMc6Gn}!;QZv$;8KyloB(-Wib*4_FJ3V)m>aG*zE?rxL zaBHsu+uG^~O8e%~Qz}4vN{XQMG{ z04){B3ZcDvp8E~C_QGxEszWo6WWZE$$}zv0A= zh+nDJC0l~>2*YV5>R$3I8&UWE-%!jj{?K0If4T~?oesgco~((>y<*#=iA- zV|g|uya^?dPpI-Hox#q;)rc)uiewNiuS;y3)@PsvtIw(iwllEuDax=YmCz5AYIlSh zK>M?Pou6A!dl|8y)uq&(FA6aBc4_lMj5>y#aq45_HpqYY@5#q6$$gby;}aSNSD=TS5Gi!c0C%puD6a{ipwXd8BbKjfP6e)r>Xk_-Nac3ieCwk$z_lVr@qm z#+0^0PZXxOT)Om(p~jg@N|&BV&mV67|J%|_r6HqEpF!UNrZMRHxQuq+0&L8mm*IE5 zE5ofOu3GfnhPd*vYcfVO!j*^ZilhjaD_q+{F_`#X8MdXGMnJh=&S&*$N3M2ViP#rv z<5ObMd8q+$MdS%pP;U9>>d=);YHiBtIWna-XZy63I>M#an|hFInAC%8z2>cqW0F2p zF3**ZvW&Ijv$i7FKY2V;2%4j9r9N06zhB~?iLR%V=(Ek$!sU9YHnwdh_o1de%+(z4?BYbVX!xC^#tHU>10{)>r)sjr_ zDvEDu5Z~xi>Fe|3Q~sfE^eM~BH~MU~1Ze>wQW(C+S~-;ewUjIgSC;9CwC+@TF^~Lm z<&z{<<(8UjQ7ol@)pshNYG1ZR*am9yjx-Kf7l&W|spPGN>hgE|O(k#XRF}V;V$0t* z<$>0EY3ws4vA2}qmO_+^RE#O%-|cNhm|}9Y7dF5Yk$+QM(y6vV`)6V7pHj5GLAthH z?4$K!AC&^O*GLCT8A}z*y_8~>UoE99B`p;#?@S8Y7Aj>e@LNhL03upyDF#xoxLaEl3(pw!Bs>j&>4FiF8S52EnIbU z0bOsn8tDqU4sn&z4Rn3t>ZLm<4K)&%{Ay=cS2%L5UF*31kz3{*o7P1`{@uU+JNj2(r1+?L^WS~&|6gOKBYQ{Y zfX)#e{~gmi$I-kq^F(LjD)8xc?wE_af_+xyTj$|cHrCPJ+kVsm(;dIJ{Zt^m+8w_) z{8TVHs||HPoC^lTxnMw?1=Kjt*SICS&Qn2mpIb6}$dl`j z84fxFZDVE{h1{kbxKlA|oaj&Nc0$zYEtl>TQj7+-VV_3qcBDX0A>?Gtm?&u~%9A^t z*wc{E?T<@c)7(^r8HbE+e?rwjIu2^!goyI$T3{xC^5@i{}CQf&Iv%8AcA998dS- zxV0Ebx!$0BPi5+qvHJ|}=Wu^6dlp|Gr1YKzpC{xwiWEm*jtgNb%Z;E zF)n~op=aP%3iNIyFVz-$Hx%Bdcvll-9UlYLc-aK=IQTd+i%l?3f=?oi*aY)QP_30s zFrUhHkmnglmfnLbrjn@lAi9#r1JD zCXWZfOOc&z9OZZ$BT0J&?kkYGZH&1JRD)<^%wBLWGMDd_bDEKIU-T=ws zb3tX28(_`{)h^orb0JutcvqYapsLj?+X!DWJ62g^fzAS!E z#=k31>=$NW#`v;{kSjpTcoU^q09u;<7y7YqZ;F4~j-FT_zyIDYmP0%GX?;SE2e-!Z zX-AK)k6+FA?Wl=!KqbK2@qdmHWpV5%Bh3l)JI9)JarCh#o(=#=4~4o+hn zE{o%=V@dlsmb54J8MxKI-yU-&=sgYXF}pz98fQECm-gg$I_MZPlYC~xF{gbTf7-{f zs68Xsv7}JLeS2!QjC7@ORw#|LL}{E+O5+?;`uAC&Y=+dm(~ZJ(`-{kk%a0F`lMsEngcCF8#KqKLelFN&BKV3_33R-!!rTJh!bn_&xeZibauwzdP<_c&n7f$o zTal;pbrp0#6W$~>&;*n=P_CpK=pLCfdlghiIc_<+J)i@I65{S$6;#Dw(7ikNW6Md= z7N2hS;M!v33p-QEBbHO_%+?muA9Sa$EoLBNf!vYAiwxNEG4ik{(yH3W89Zs}Zx`ou zPjb0lw>H)N-k~vgqrX<&gc70`=a&kL(23NxjdWsA8Np$(&3KdNNKy=> z6%8frD9mtLRVSVqL-@$p+EUxI9V%-$h7?0+kt29wEQY&GNzc8e)QtQf_eyNRYIa0p z1~`VW@uVA0D<8o#6G%ORzR-GcXG~COIQC4y+zR9E*4Z6oQh4d4dh1}ho zis7btLdSxW2%Cy)5;&Q#BY0{uI1zgqPa#)I>gHf`THSO~H3KJO&me9hIFZydNjZ&q z#gX<%Offhe-;u;k1}Ed2MT#jP5~<8O-FRjW=}JK7jya?%250cZ9L$m6EPP0!^4w9F zS#ixYo7u?OY#yc|*pRk7kF=%WEbOC6e-tWO%Um^!xCMmH0_El|z|;lj;q!#y zY;ZQuEF}GWX0xM+TSSU_pxpFD#2p1LAZ#(IypO_@hu%P;?!s<_9ZS#Z#{4Vya|xzC zxCq}8(s>H;XnadawGdp$lgk*_Jbzdpdl~*?z+*_a3{#(3y*p`_W0rz){#KB>2Iz>m zf>Z(YtfHqAmw`*MR}z;G%GF+p=?ShNY$dK9U=N;9li`Z2yj-rmyFob~vAg8zC&=wE zI0neWP844r;c{}z%M)KW#e^7o;IPE)_c>`u(;qn9f$}?orvjryCt6LCJ(7{5GpL5aS@BEt^_Q1B~NKsic^BMhm{-0K9yIVk99omB@SdWRLqpe7)s~2IOQ>_Q4w&|JJMWpd0 ztUIutTwOqGuqE1B3ur~QxMPX+Y^+iPu2}nm>cPylR{8nfs!|x+k}FwHxw@XU70M%C z7W=m?v;nQCKcU{IA`L31X%6y?ahSD{re6ac@7Sr9%|=l0p1j?_7&{CcMhf+Du7i$uWZf7?O;5>kBQ<01 za8UV-O}Nzi>8&nm)gs(hV z1Z=f_mV?e(r{i|DqonNVjQ5kk?S!3*Fh(@1j$rXA?|Wd|XybJWo14KeB!os8|8 zrvvCZ=*&2)@5JpY=uBq!os0rgLFf6MxTb(Rh~J58N38Y6v8}krWZlU{ZA`gXhR!vm z{FO7g^Hfd-$sO2YzRCYRkUWyoOs@Tl8U39<>&9BHOK6igN0ic2tyAZeW^qJtrR9M@`sj$=xx*N)?tS{%CJR=0yxq2KFhe{}w>OOaSveW|roFlmz0rE~#DLVdrv*Gu&@A><*GbajBV+m7C!5iGtm{#P zc~hCa#vbLl59{52h2F8)3+zR$Vh?EzTKo0~(Kc_d5N+GGd(qbG`HA+imD^4|S&?Qa zcLm$Wc_;%j<|t<+QGTg&j3_1TJmm~E9p5Z!Gk}4#voX#@QazqBl0K4B=0pyurH?u@ zqc~q5g^?O^4pRrY^o_jYd8F<%u#UQFw%3CamrjO&;)UBFz$fx}Bev;P1iQ zP%F+Uu0Nz$j%5Z|3ObKSow#n1>hb=pW!NidtI{}fpjP5q7UzSdjP%YYt4QT7TCOrz z;a|=i;EHE8##zIeWDRB|qrMuMojZDg@?_WI>J7S@T1QG}3D-&MFsm8;onxE>oGI3l zM(qh}8S7nLZNNA?IB#sk92dv`KA@aj$9+Rwvu!55IvM0?Io59g0s}L+Ctv7gy&KxI_x<9xT`$YWeYB&Mg8yD+?a{W%ibv)y@JZ(qw;~A%2Tc1MO z{-Cpk+7?b=yP<8*>C#=d14f_mI z4Fa7Z)U$9ZBe9&s9hlP?wVf5t#HVhCGjZ=E^KF(d@r>v?0{>x zlQimFI1_XZIEQhg6f7lvH?}BOOs&sDKs7|4i&1B^tMT(le-7w=_IbE=!#Pxs^aYr6 z!E;HY{slu^)yo(4W-eFo>UBOJF6D*b#TfNDTtFIc1v5lmz$J`F@>b=zUW&O0R4a7i zbzVlQ;keZbeHpG1@IB=dT+RsA1Z+%NH9%hqUXHC!Xm9MgjFjqbxD=EhaTViQQ?Mzi zuEwZo`YLSoJgDvAO43||83n2{`dY@mW?(Z?U58QM^tIS~NFg`s8f-N`Tmz~F;(F4n zZ(9D=4fw8wyCkpVM&d_<^0d4&OkEE0r*6Vr50^<2;l`;SBp zrurf#!TD7G!^dzB;r-M4y~5brCfJ<#9cLuJy1mChEniu8mh`lKcLV*1e%rCpuPTQRmud8qA4o{Bo3l0 z7UythcqtXRV^T3v!_Md9K)Gf;K~DrG?xE)*m2;L3lJ4nA$w~zzKBGJ}Icaj(a(8E{ zA4wUY380##q^LX_=xWh(M@k1(5GTDQ&&~CwT(b_K=N_cYJU=MaCQq#rw2sm_L8&+S zZqj-+amkTOH-yTG3*>7a^1aNn3RD+W;>}4VRFPh8ofLpMBrcxZJm+jrD@t8B6X&!@ zIm^lwls0f4&FPFv{KMRxwU&gXVCh*}mXzGc#D$bzOkB#O1In4n+Hy8bTup1$T2ET0 zoY$N!L}x3+RIx;)LdJC)PQ03v;{v1mk z8NJh0Eo?c?uV+|u9AVpEj#KQJS4Rq4lOtQ=D(CK-mD_Av%5kA>Keht7)3%%(*V=Qq zlPGm_^88X8uq}4(WT#JfBE)+3yE?|vvLj#A61St7wb+{P?nrD?uvu(bwmj>+g8EfX zEhCk6T|w>UgH^Fqs$xmV5p5dly@K+pqO_DrZ$#^{{yShQsPEdi$_Q^5Yv0|RD*U#s zq$SK<9&Z$ON2Y|juSfbqOl52d9jIk@aim}>sr5?ywuDM@_B;JbcMa7u=@+_6QVXUx znJ5$Mm!y41Q<=t;O5!QuYKj`~OPhFB%2}F9UX~m!Qz?0Aeo4#b{%<^Ze(5`X+kw7x z|L?T_$=8x+=DU^eO#C$8Y7WXv=aWj=OH&$dy7aGU4>eGRN@5paYQz!^l(;LrQm`zR ztFps2VyWv=hBcLO4N6xzW6M~%R!dgtc%@r?SN-@lrDTXzsovz0uz8JA9Mp{?j+O8u#zs|E>>~ zVXD~=mZI&^Qgl?ZECXNYJ5%{sPL`bI=h$P3TCRSFDTm zJ;{kEC6U^=-;(6km7exX?5VkuNqyHoeCTb~67uwbZ>SzY3gVdJ+Z|=BRma*7|MxU9 zrO_|2?Tqr?1M5jHz8)Glw#QSw@cd_NwZVJ-TH9Lg z3-`@AeP?d$+&@oqtp4|d<+*Qe=Cl9Tda7&R@7zDn!!6Gb|4wtu)s$yN4pc{}cJ?jL z53i$r^GqeMZ_fLcYRWm4Kq}RP{rkT%&s@EyJX7tbFWk2+`M>s>>K653^`6V~U~S2K zZ1dGEYTq{h;dPYy(FfbozIlGIjt(VHOCZ-b59QwvTf%#VHXztNmiHY!OJuEot9)ybBAAO*``vJ>i+2RJkWO@tlq8h>e{a^Pbux{+W+W!Pv4oV z{eR7O?pyD<8n=CZSb5sgJ+o?i&y}Y=;Gb!qhf|&h>qq~p^0Wt4_on^(Q7!tE^p5=~ zNkil)Ut6gwIZN(?X^gE-dEhjOfnNQb>sI~w~mjFl=ezTIL8jh0BK`qDo0sqQR%5P`bw2MF5BvJXD|zVm~59_-&gx{mfQ&kxpns-qA7d#+Sd?WdA_f4v|2cjj{2w?*xr zXYM=q%`^A4mg=E=XRfAl^`1CSw)yNJt^LF5=)i40_njZ!=08}TAJ&#~^`2`*AMBNf z|DDQNaDN|0t&k1jlQzPr52h|*^({*rb7>QE zFOP3+8^5L<-=oZc=Ps0wP}-z~x4Q4qB7UblFmK}a3*9LT{9gfo)+&CXeBc^9txlZQ z@eAb%=aFk&Lfgb|lee7D+iZ2{_$AI$&G1u+ugSO6j$h(==eF@{-EXSRH`OLi{WI1@UX-*tym&#WdjC4_qViiLI}H*UP`EUaS$dAXz(yQZN7RFaIy=UzI>m8;x?w3bclWz)JIP5Yzn zW|=bWG33_Nhnpt%E^|BByZ(_h8-lXr>$%-iR2p?7Ase{cQ#qJTL8+HbxV>Fed6&&W zxt7g@Z{l{(5xBMlC0b4l%C?`#9ixM|U3652#5dtvxJ^{amE#E6%FUn3!k)lgp98aX zVG>dX>xlK&4@%8?2kC(9w4h||X~gu)wsVVTUr>qLQ-ks>rv~M5y-l9n6coWw=?voXjPo0O0a}R_c z%^kGLq0SASjhM@=vYfRcWPVr>ltW!cJ}bGgR{7VX!d&blgQppeBz6IJ)hbInhj^r2 zF-K&}NxzJHWG5q^v4gMSE~ubXi+7iH%8ucQX`u49D@e1P8)TI?U&sx%(?NA1%p(6I z1GnKKyE-c<;kq;^SH6^#E4cl1N9d9*;*Q%Hpz^s(h+P_%gjq;UEe?yq%#6Eq2|bp3 zZ*?oHdu&h-!%m*=0xFZcGbmFtoBU^m#Yn@>j(4VZ<8IbnK~yH_EL@e`2C$geDZ#TB zQ^6_d>R*B+>=EEpbpCs~Vj6fvP;zz}_pP24I-vW18E$1}r-v1o8Q^m4bBL?pj@RAT zE7ATxGkBh2Mp%V@|H2B_Q2+I794Qp|a!aX)z z8eg^es6j}`h6VL!3=2yB z4kL%*Auqcv+zQ?vZUb*6U4C{)xIN?(lE{atQExDso;}33{2)pfw-1+Q?L)hu)Unu( zn`!oj*SYIyFKJ)rmL+ea`YHbJfO~^?K)uRMR6oJ@DmOO0!p&9Q2=xlLI(?hls=O)c z+uZc@E$+X18{fB(C%zTPbhdOO~d^%lNwU|!~Ktv9(R>g$+qM49FC za7|Vo+J>(Y{&nP!ui@sMYcZ|E%~|Wv3cMEkCGLBAle@LvOjvX-GmxG8JJeLPAO zw+fz&ZxNI_7F&eo;j5(g?k;bkQdYTnxE|9id=?EUe?nu5_cc8Seh&1erq6IY)bGJR zVyj=}k7!8ozNV)!&t>XY`8|@**JsVbv$%ejsb%H&S<|qGkWZ8HX|$-khy4t3zW|@b zR(85+_zJgV{hZsxe$LlCPuwrTXRtrT4N~uc@A2f9xo7HU;Lk|+c~ZO!K95}zZXuVF za2@%)$jwy0<)*XWlI{z{zYD(0Jy{>;mZ-mhe462cibOFf=3B!tJw;p50#-$LqJF=gS2tOmD9Jwfc_$OzZKbsOM)F zWVY`i_Fha;c$jdduj_Fi)qPn}CFM?%3(G4%FhIy@uiYP=l!+NQ=+GH)=H^BbFGDvS%*0a z`f)lG&c;ZS92eF>{~U*z3$1Y+w9*R9Jg83ToDHPe7^GR|LAiLh>3V3Asi3--){|xf z6yy|KCqmmyfu5WU-FX5u-ejo9N%)VCwBPZO_S=g4cy7IyirW$?x-Gc3hGmiFSr(}h zDJk?F5xXT)a+|@;VN+O2s)f+JW1)3ViWILD@JUcXO9@{RDYPY#f;yJ41yI4mBV9QH zTnuHzY1BydEygt;YD+p|CUf_CPJA<|%;hM5(P#GVo7_Zg&_8D=x*ZiXhBg?$Y9 z9SvRMj6Iz++-k(ky9Fv~Huf~Aptayy;u19^rN_B$%(2kJ(&wi{n*0!< zq?M%cI1h_i0_7={bQIxppuRk9Gd0d@Q+eAK=+H&bVhb=!p|?kosnTZ&A&U;?;XT{ai@JJC1hmzv% zR?Pw*}D?z2EF99!s zisTd$u@z92*FbG|!1n&LbF=o)lUGC0R$#Y-p1dm3wO2z0oy#061#~VHaXYB!a?F*H zKE5i_+*g8ELP1M0T>{N&H;>dNr+%P6rQP>HyGyA`)87C^*B|<$Wu#`M=5K`FlXB@BX_LOhU&tDwC3J3| zNa^$;{`^P{T?+PrD(VJRav9hayL+Txx@Oiak(qouSGbLNzzQ+z!^qE`ln)BhvD>Ls4`g_4UwEU7%#8`|l*? z4k(az#N7~Sts6n<66vvp}WWKH>h1z}EG7GnbO1y`Z&WNp`pwRzA3N-+A#4T0Hd8s&? zwuG{}o0UunRBs92aThd|vu_J%syjhv<)%NW%nDzZLmYKh7S3s_|r&l+UYBNK(O4O5epLdh6&bkt%y7Qe3YP z`zn;I^q9A}{st=em!x=@93FuR{$-?&rSwWdDfGrSNcRWuW$bT4`AIK(FX~?6A7;Jw z7F4ZVv$t4@{3mhWgRcHhXkjVRuk+j=Sl7G>9s46vy~zsY9a4NBI{ckT$2<;}K+n8E zil2i&!hQ{k{U_j0NasDczXzpSe@Kd-fp1{{fHbc`E!Bg@d!5jqfe>p{rEd* z;1_xBcifZD)CcLaYazt#X)_A zwV~_2NL(%O1?;B@`84#d6y_J8Z)=6mN1F5Vgw+hs5UcjXI?#d7LpkSz(x}fu_0<70 zD8OfleFjSZd1%7{GeYHlDpjN0pzT>%7P+MP z7^TZ=#@LTe`+VZ}{ z+-a`=yE?`8)h3osxOv_!cQ>N^t8^O9lX0Gva}3X&o%7a2PtsN2jp!_s(=4V|hTPqV za-%$#=ebF>IP}8g&hh2$MpUjco$r$}^9dcITb4z*bM*-F*!pj(|*-Z@(vbiSKKh$}+%Zp_AC7o3GX8!EOt*d5;-LhFI@ z>gP}cJ;B+8&A|^3oVWsT4)#&Rs$5ge}aZuH~nffdjD@(N+h7?yW2)v>~_%dodyEC6fM<>)j9>jD0L? zlEI++FH5i+fzobE2ssvXM`kH@V{jPuQd~{ofO~dX-ni~z*vnXr4g+14E+?)TxD0za zA!^Q2>P2pOGtd>{3XD36Jg@9JP#wObh*`-BZ4@|?uvNsh1Xp6OB3!LS$_lM!g*F;o zg>N-3brs1)UlXbCHN>iE!gI-MGEXDBCTzu;bsVm>(C6jg8tir0<={B%b&N^lK+htp zk)j-&fPEaUwxHTc*2i_gde#E%aZe;veHCq4TdyZ%1EvC;h!0La_6B$alR$SvHV`+3 zcHM(ktvslD`!ZT=FR&+V$UA0xW4hCBGD7>t(7w2O(k?PW`^SFNKlYmbr0q_KE4BU@ zb@};>di~Tz?VUn{@VlO~x2najBdGSjL4>N&Pn~^9uip^T52T*mA5q_AC8(Ckp``Hc zx4!stTKtmEzKqr~fVad1fr%qt3ozgpQ;9y*alnwwm@l3p|E2<1oXhD|PlIEq)Uik31os@%%*U zyCtX$*F>Ig4UXX%_3gExPR8<_H%O?FPmO+)c~<>>uC&y$-2$A5J%zY2;23;UNIRZU zPyMEjhujfOYi4WZmCJ9Rc^%=ywc%q2@mI-7F+^1JF@xA%1oFCCzvh?w~Rd1zvo=GuNJ@Mah6=p zlXV$OmSQg_*F~UO09Vk<)Z*u!dD3m;_@mC6yf`9xI#CU3>QPe@juO~P?%BKT^X+LV z&W3GpWnekB=h-}o;Ar2PxEi1{U`}FC8chy>cW*m`c-GcY+%v4r<80-4r=~2&vE~@% z89kGrRHHJ4&R=T3@>V{_Or_G4G;}2QJb5EpkoP1tAw>b`yr2dyZ&UI{zb1rw`%zAB z!2rI`8N^wC0AK1XV>$Nc@12z_qkg>EnagphFJ({@cP&PVUZ8WFCFp%(wIe!**1@Gd zt2($XebL$0S`?j&txM6_ybxE{*c!UT)*w3j+mb{n1Y4o#NL3O?p^`Xu*)BWA*6fXM zrHoFVmiPYhbc?wot-VEb^!6rm?=M%or@c;eZ1?u^v0xKyZ!7oC@}}6$ag7GkUFOa{ zjsofa?WC<%T^P<;jw$LFb&hjn89_}u>p8xpyUe}6+!?biw&<+tNGCeaI^K!S(cTr{ zE#~T5wGE|JjB5a0(&M%ZS3B0GXXRZDl$Re!m*f9L*gr?hTSiJRcspg%53F9WL(vc1 zjB-x8CDJ|TqBWN^11DV+>QJfH47@Kbzb_S^G+jvF?@Pr?(36Ak$1*AV1JUyPQt|c#X?dl~?H$h4@4xNb9wld0*=DJDd8bKVh-g1d+C-9m;Qgt1 z`>-6)gWqORdwcqZ&}YuBO@&HWpMaMm;I@>F?4B_Pp`bK&l6IsM!CKu9>7gq=K4} z=1TRGbgrl+q$1Xp=S$=ir`3_YQ2iZAYm4=k^thyYb9}9gwNVASwn`dbQhhqgR?(}i zv7|31>4tH{wRWv%->R-5_1(3@ULQ4=T&=_2PG(Gku$MRbHq z+W1<=5iV)zOIrI{Fuo-nemSjv_OhhqZv<_{x>u)5P9vc6jXDAy+gu%pj%R8S974-b zJB%}w=-5^k$2MoBoK`~h6AqxJ?QO*vwHP`VC0&LMa3xKL{bK)8mr&AqXwP%bRZF6C zP64i7pc-(T0iA`MdDO3H4^zXUb7*&J$2ljbk5OHWt|FzrospdDyHff!ap%Xm$Q5g6 z>dCpt@mO>&a+VjRqooH#Y2;3{`!dk~?i9uOQ}QrX6YDL`<9Ze+V#C<)giW5XO}v-(}-eOb)byo1b8oO;!RajUiuTK z%+ky0C{8n2AV;}UY1T^diEHIE2TGH|EPH1?^E3Va`Mf{P!RN-@I}-ou!{<@IQtq6b zzMM`P%fQoW-c9O^Yyb4mJW=V?vpNKlmJZL&deT`91L`*L)Ua<$ z=jlD)s%8PtlsZeK^Djl@l=4)+!GZG3<>o1Lb3c?kz3JH#Pu@G3ZqoFGk>_VD2X(j< z(H{NU5{!CU{Z8+X^d1wxvkapSSijTzI?Lz>esv>^RI7AiV~n(`)S?<)Jw4zpxH2-|A`Z zI`NC`#Xfm(xmnwx?IO`&epPDIeuw`=A3IYwxL{WF=x-0*;;J3 zrI^%OYSTt+J^Qwq{|$Yl7JvFt?Kam={*~?RP~Lke{pE1m?SDr*JltZp}gsE5){4yC>Ao990>uKHEE5&Cf3hI6tbhbM*|r5t6Px77vW znC0B-sOC(TG$~27I-j}Lmnw6fvt%4|9dQlyYjUHa-}cYXhSo>Yks?nj{&)28ecQ&qZs+?nex`Xa&Ee9B(wFJH%)ag6P}e0HK~a~O3~J&<^bnQTa&b;nhR`AQV>#ysWqk6mHzi|Xx)z*_YOt_eAs+_ zpmEQcI!A3fQ%iFuYV)J%Oj~s|wRvcC=Hbu`IcmXs(xo`1Eu|Uk^VO6?HO-L5y&UCG z7VE+CcZKv(W0dVrdc$&6bH={3-@a{fU-yC9p5b1cBtAKsSrT-Vky?@nswQn0c-0{

-DmB)--CDQ>)rkLu;3FTy9hQxKyl`d^k0&1=`BZshyiC8BYBir^86iscp5ZIo_>ov!!0$sE4&JYNQ2e04eI#nR;~Q+!}QP zc6zN|9jQl0&g-e0{nR@4N&VN_wdc4!rRCb$o^^bQ9%1fi?7qhC`s#XnZS?~3uDaV{;?Ms7cm$7x-b9*hRc z>BQj}pqx(ZjZK&w%kda!a1YMMgQf03@j0F}4w_xfk+i)VP)zEZHUUa+50MKPFG%c7 zCQX7@*juKMCc{s}-c-^Qc#NZD8fhxrMZ8TXO@o(+x1C7Nk=Qq8kamKa+e2oOWDy{>!O6bbz9l*5G zv@qmo<*ktAwyM6Hz6opC&uYkGusV|>r$d&}$mLkXT7O}60QBL2mE zw8Hkl|E8F?MZ~|-Piy!W^U(@B8vo_7P{;r=G8`cx<3(<1Q5MIe(@ghB>_4N?_$OfN zm_eEZoRn+;ld%}gAWa2M#eOh@G#xk{8$mO+mI=TKoHr*MPxEVY;?A2p8$KF17CVkJ z-{bKH(4#>AfjzJVbj8!4mQ)R_M%S+;^#Jz3hEPlD3G9h&pqA7d3uAZ`=y9-&|LbF* zcY$67D}gI0>%uc@lLtVj*XH&s$s<5JPkU?|&3tDc;7mMPR$^Z|Fxi?8OctaAu^{bB z$-Y?24kYad+z+eSfuyy-wOH5=aXm%8vui zA=f%I3^)v%(6LyH<^bn#O)Jn);7}|yCne9Qld#&qlVkm`eu_25DQ)k^ z1NEXh84J4pOaG3o_7_-rf5CnK&V9cI{uO7q6K93~Z*CWX;_DHgiIWM}1xypgu@ldi3J%r_G5XV}OPURa;N%rU8 zWT$a_Ds!cCsoyuTn#~1jNBbsotMh?7Q|AZy*F(Tpu}VFdH*oeK)}jVr6S*_3#{#vk zKbq{Tk8*wtbEU6l4+6E2J&AB)}Zv-@+cb@%65?e6EBA7HlfG5+;9R`vBj z=Kvn({4i#e|G*vh<$uJocOO>6KLY=ZeeW#3>P+Ux4krIL-}_sv@V|wKUrNbYKrPZ* z<}+Z1weJ#2E@e(u8@2wGf59I87i^Cg^Pct0?XKh6#T>26wOs!>bDs5LW?P*R`xZwR zF|(~T`(EDeEca8~qviTu<|n_!J=(ADO|!oj0zb@5;uFj#ei(QG`4ilA0dwKnx$nuf zSKpIsx4wt}-OK!{bFZHOew;Z*=T;wK4&`xd<=;#*43BblWtxS&l6yYE?BgdmbB_6Z z;Caj^eml)Sew*_TF=wwG{O(+P_}#ho@Vj}}J+&K$}^JoRy)Gj9)(9?7oanO8EW z_7GP;#qm{mPkx(cI?r`~c5Uv=UHICD-|cnGf`5h?`>V-63%oAZi&tM>XR$s{+2`;< zxSITSp7;cF9S@T0S$j87|J&P1`r0}#cSD+syn*@1%kXG$p7eUs)xgU*yPl)Z18?B$ z3;g2=W>ufSX6)SR6B&Mk{2Na~uHQ)Mi)q&NrR-L|{v5n8&f(e@)7--snHRX5WBoXs zdwntc8nrw({~GDm+}X{$nBD&l=gx87h0n@&ICrM=E}$MFU!g<~7kx{eg}oD>mnS)Q zPWDc`V4mdsE6kYQiC@f9aUS;!%k;j`O7c(n z*<97L=Qi@QncKb%*-=^A6*Fo!O0#+tT#q#Mbgqr$yZGMfnQ=Stc04s}k?Otx`~vLy zgFNAEWUlY#Lz1V@qwLt_SLYa2ZE<>GO=Mn4`XmbG;3&LXuTC?7{!4k&D$U^&z+l=)CqP(%ov6dUo~Z zKK)T%%=;$4jJ|wTKdfeYWE`I9U7*+3_w$96Xzg9ZU58PAc=9>>e!hV6@SS@mKa}#r zk{8T?*sMOn8&~LyHju1 z@2+pQ4!@L3fS2$eecPVT=W@?HtZv$8w9VDyTX!jU=;ii&esFdcX9trGL4tmcyJvDA zYhk#zPj)PKJeMC!`OX|4!`U42o$+ZqHc8)a2kPNA8=tbXc*-o!X5*cA97kGohU3}u z0ldyeCawN-&dxy3&_b+#+8O94&76-Rxem3NBllG~1E|m1I7-H*^mJc#-p2wa9u)47GU zcpn~!J#;s0pL+mz$1_eZKRx7xdjIX6?%tcL8?HUnmu`Q&>eljv)f}x&s|gPT9>_oR zpA))jv7w>zy3EW(AS0j#Xn(Dw-t5($P#pWU+GsDvwxgwrR0nLwnHpssx}??@_1Ze9 zfL0mx%RY=-tu<{x8FyND)Y{zPNvn@KMSn)7)*v;$0gNc^L+T>~8Dp+F z>`u~tRn3{Y0{o`8MJokt!nMs1j^sw+bg`y(&8J6w^#ADs%`j& za(%6N&(uP_c!zD|)n2^SHuBxQc}LMwwS2v8RJ50EWPA0Y4z`i)RiD~M%bqqp+eV9@ zwm#cNOQ5Y|tM#W&+68SJZH8URZ51twwvnwih&pOV?LlgIt-WeEY6PP_$jf!vR=gFh z)`4es*h1TBX>oOCM=-LjZ71forvDT@rxTd!L`#+HyEScRtJ&{t!77d&SGJw4R}_yX}hwny}jFRW4!Iiwk!7^dwokUicw#*UAextU0dm7 zP)Nt1ZC6WsZC^TBj6SJlv|Z52ppdqsbW)p^UoD-KHnz~ot)Wq6T$RV##_hEsoz#b6 z;}PdbXra##$BU-BTYgD7I8ex-G4a_6mwEm6C23w7NXjY%S@e)Ux1f z1+|o_2b~PQR&K9?TH0!5Y8iBL%X}@UWpFpCX2I9CS9=An3eFN7ZDXF&T6+bqidNgP ze66)_DBfO-uMOKvNm@?UJGGkJO)rJb@wGB-w2cZ1>5S9X@U`G*ayR*!?NzkY-v?iF z9;t=9ZJkUKW37-(TI8bE+HTYS(?VOel{W5(u~wELLox|TGC11yrHw(C0%K*mR8XX% zpBKEW++GERj8?O+?^xPc<^@3&mGX-b*S4{?wQ`8`u#hC3L$+<+>an)9{d{8@wIN@# z1-GC4-`ZH)_!~AyCo|fvkpJak-lG;!;kc0h%XG5bc5RXW+tPN9uR;sZgP=uIQ+j-B zxp}Upk|Dco6c1r%C zajUyErao5a-8-6I{VmYU^0?bp9@m=uUufT2OG57sJ4vB^Yb}Ykb0oG__VFr` z+*cj9JxM#;rNWXtv1-gTq>l@ITCRLt8DP}G85GZtBXPmcI z=Z#s*Xtj-f0~|#~UH+E(UTb!$c^3mF*H?(Jicktyz}dnvu1odCAts zk#*UUZ$oS2sF(v%bKenjKxLi1OdkrJT`IA$&b~SNP@dZ=Y_`sD74_0`TiE@i5=Fh7 z{V(i(&TtjB2xtEtJ6e#mNE9|(eQXM!4Q)pSeb95G=zH3Z96RbTT5gNJ=iG5oug%#a z%Jq7q_SzA?DBF|nmB&=MUT-vayyHA=%C+0nf>a(;1>GxrqFS#@+ilJ}f-)3+&)Lk5tZaq8aQnn(~^{@Yv+*sfVWV3XN{)O7l_pqq@WA;iMz*q}21$HDROhp48h?|H@%RN7S41 zFw)`Bjz(yP9+7%Sx=-z3N`~O)sITNe&IaN4cmkf1?;=i`K9DDIwvum~i*Myhpli!r zK|78oyZ+NPp?W9x=iJzcjXcBMa|Yr$spqI(m&XC$&KI1*^NuHCLOEx1rJB?Y-{^BG(Hpu7C>N3@M_dmjKfR@Mpi+G&jxJ77>n={-&le}Z=Zlk< zv%3vkz*W7O^&0*t{<;U@uljvFZVv$-LOq_(*HNG6bA3&p&-FKbKG)~eSjg+}`#p&J zUdZ(TeIeJQ^o3ln(id_)O`ps4OMNcaFZH=xpH^cCPs4*+ZO6!YAHt`;Q}U?ZpZ~m= z>w)@Wt`{nC-0&+ka_MUBj(##cv8QVe-JP4m+&1w z2Y3$nd5NdJh~Kl`)6e93P(PEq9@JRA)%Z<+9RKOB@`PLR%abqlmpT3_UiEt2e~IHS z<3)cfM_2KsAHvI8pJlzWFHIiT`fOj3{IEZnytJ=Oe%qJx%$upv*YUP@F8XGkVBAV$ zG~S-;XMB6EuQBl;@c_O(*CY9MzW*g+=;=Z9yGd_fBiAGO zj$9w*J9ygdc%{qDznja)znja!jUZi%H@RNOpW?eu171abHQ#eHs~hCpH&OQP?3!H8 zZq)j#S)*_hC0``HhZPud|7*E=4XYf!NXd=K*ZDJ)U(3pb8}WO-lkYKF?iW}YacAz1 z_D`oZ8b-jb=eRyI%Hq?k)wqF`6L+#g<7v+C;>=jRt}VDLch$jNxhoIu%JqDIDy`#q zDy_eGDy_kIihq4Bt$w&U`(%Dqer5g@RzKX#N(Wa#T%Lb2zaqb!@=xZjez=*{7N6x= zcjvBAxI1^z8}MfS|8D+!KI^A$B7YC*-K-dLjl@%2W1j`qXxzlQted#@ zB&FA~=IAN%_koKqvbyR?^7paQ|Qyo4J1PL{{*fO8yFKkM0BB$GWgr(rTnNJnvlA2)@F4ul+b)!|Jw&IeRs& zR@#?q=cVXMw5$^{YZ*(osaaE)d+l{{UA>fBt?e%cI8Qr{WA`C&<=#uI(0hru{DkyV z*7~`Y&zRvy=Raa?Uqm1OL1t{e!&!ZIOj?6?WIA^3;87eMo4=g>i2u1#@ZW$xApZs5 z@lfun$p={t_ZZ()%lX5slQoX`bl^1BuhvphM|o{pMf)hLXTQlcSGGRPn$(B5HiavX zvO@KnTt`hKE>@yPkD^lezCP;A5Ok=6{c}=G6G*Gf6Yj%GqzQ z!t@teJl0UjqklGt@EAB>ff%E?#XK1 zy?`sp_WUR*f1P-Sv!}S%vFL;iZ(Vd@VAYF~eQUYn<^VlrLok zZ)c*{8D)G4Ylb^>zLS9e#m8}9YyMa2o*j^+LdFU||FVBwtjsXJf_G{M+WZ`M`8h^(FoHu> zdbaT)I*@#J{NET3ZFx@N3$dl|c`NVPns46Ne`9O$WAr8?@eD^#F*?&S;4pF{HZ27X zB{!#P5|vPmNGVEa^eZJZp;57v)r3aNQhE~_D?({cX!M9)q=@=86RFV1U&@6ukY0^8 zp`^GI@~rVElxU|T;Tn@d8Fw0TaS=~!D!M`uL(F&<#$0e^VnmFIh+&hE2aT8ETE&S- ztVYu?&dCINqMD2AEyvRnjTY8{6w$(jYH6;@6h_RjD)hOC9A*z5ML$;iQ;!x#-De@N5W$@|qxMs}y%g_z%XSec%uP4qsH2WGQx57(~%ZI|54+Gvy z$=BemL$fTC!wyB(vPa%S`MqiFdxj)BfOF-R`^Nq-GXHxQRN={3%^o>aN*RUS@y4Tib-^iKk z^3OnaG^TB=p*Cv#jmV2<@L$*NpMe~CF3)f^|GB_Zxc7ae_afzAhko!m?!GQ*0XHI- ztb;!r;r)J~a?^9@8+X9HT-*OVN4Eo?Bj1e@d7IG+p5-3bsJepsSu}yW62ChNUG;hH zU(P-9KxLL^xaz9d0bosTcofjs0eg@#bdm3K|5K#ffVc4#%lOxFpc2F~(lKyfqUmPD z!_9KEv;pXqt^gj89fW*!2=dk;+$*=v(aBsX{50^pa6zKuW=5-j2)XSb?lCgPdUW6Z z=uJzwo@YkOSdWCD6!QZ5S$}ln{^+txxmL-HijikZki_KW>+S=(d(D%iM}Y3Wvp3h4 zA>lkp$z!B%0+px6LZ4nhl31EoGGle@hlFdK4kO$e2jNNXTgAUuB8{sJe2errlA+N( zR&&SRzO++&h%qpM<~9<(Xr6{@83jN9};~$VVrdIGXY?*@Aq2E?wwLsWA!1 zXETwMW+So9K&sk_G#d+p_LFHTLdrDCX6Mr=afPdKo2HQ_0=2ie?saOC&ZZ!DDgVvj zo@r1?tqwCttb|SS;zVS~*-1K^iaenlHlBq1#a-?nqFupVM6|Gsqih(`7qMiM-_y#6Rj&T$!#wqvUkryl=jqJGIVf)jSla)lPXK<9c5t*uF@G$53)8_DQXt z3^7WM=J=Sbf^^z|Y^vN@;b=(yHp*SOu4VLX$ug?!Iv5F73H2ySTmi4GRH=3lQms<# zk(3;jwdZUgdZ#*}tG-VIYOQ$%z3taP^}Sb;2KWm1{4PbEc?G+VwwcqDCFb=j!cnkUP-ZPehE|${5k0rtWjF0 z&P*%e&*Jz@bO806pOId{zNXE|Jyp)a%62+O#&P)>@Ml~-hc7uDcskdNE&dAj$x}Fw zcp}CXc@ztPntx0D2xCiJgN4Q@6Q4~skZXX~a2~NjjJ<9Ib}b7J@`T5emi-N&76JEK zxE{OKr@7zQ37^Kw^m$6Z!1?EaSCQY3<>Nu@Q&(~R65sSH@Wk;Dfxy7$gq@jRAin|NSTIqFS0SBAtiE`YM{0y6~%5OW#4My7M1_Mwa=PqK+?eb| z&uh=3^cHNDmtmXIQgR1(KbP!O&tv=gSh9R+AJwk)EVi|eQ~H%;GyMuS&re{}!!7vx+m`n{8lzBfnj;@EwS zI%6035m3FhGe^G%{ty4`m2COFlJ#2a=*g6v#95bQdFhg(u5?LOg)UfP{*CgN`Df2$ z`R~u|*q^=yj$nlH(vnJW5YuMl8lN?`6uEc!_()AV8 zst2W40FBC`^!-UBYOPV-sQ34P-%T>McD`z?d`247hFF~V8xUp43VBCUU&((YLA zZUP$nr8`Go2ln8sq2T~1=vt`r66o4el93gbCKyp1wA3#n9Rk!+FKt_wXxe(9^ldkK z)DgfV828dNOAe*4?M8CGWjD%KkOv(Ls&zCp>u6}+?xbUZ?)dD?&)ev)yK}q;`SHNr z$)zgC1C3L$C+QtP_grRgB6{jc1^O?uAD=DHuC~8d$JGt8pi&4!1L%6Ye??sd_H}}ou1F7Z>`~YKk^HJYsmNK=t7`- zH1AKk2zU|w!=0WlpnvSo@ig*Ff%}tBM^?{)N^R3g?SPk3rrvfbe0n-1MI6rQoEs~$ z15j;iMjACU==q&FHcsbEj=BJyJ5oFBjKrcgH!JnAS*b70O1(!7vMbVzy;IH7coVZZ zo|F2$k-&|^?RYa9cW9zLkzM2#p`jLWn?r|HtDQ^g4>Xdq(IJf&ss5p+tNyD7GoLgV zXe7x691Q`g=Pe*L0@cQpR0bo{s3$EX4NLM(6Vi{m{36nDpmDpEl12g-az&YGB+wY3 zqsd1lO?@=bn5v6OV}V8tUrZX0ysSjjcJKTnSYQ;%+@S~@OSTgRcbLmRl z-N2(hQxiDvk}&IBrt@6lxpTsNCtAVTNZXj_X>>DhtMt`mXICLhT8 z$-slS@-Ffdq0G`V>GQjiGB*6aV{;}kCHWso+%@r30;z^NyDUM#?jiBb7zCsaOFI5sh#x9Ib&y(rE068T^|M- z*=jZC7XbI+%7x?~hH^^JoPoX&x++y$3GKQV=#1w|&MyV7;>u;@7ekrde@R{8GU&GL zvR7)ay;2MA#kF>n>`h)pj)qL$9=I3z9vpQ5+C%n8J!cQjJ9E4zSGtgQgtJKD+_$a^ zd`AkmBK6D_sjsf!yay$_bESs78ZIVxHi}UVJWe~=@-!lrr!lge^Eyg)<4Pa$-i&iK z6eA!RYf1{YG>yKcX@oB2d_bZG^^Db}jLIeCgAz>`$jFz%X+hL_C^gV_7*t{qbYfS^ z7n2W7RH6y$AcZTmLAAbJI3EFA%oQn`G|yfyB~jOtzAa>=i~(wGTgdr1;3BS!Cr670 zjt4sCq%A_J+8x2X?V}IzuJ+Zn)3S@8T z&eL2M6n^4HIMP$xl?L+CF7zttkleM)>(2~7?s&56omzip`Ds!zpXsW%mS=Y6+%xa& zl)kMK$DR3lzpx|8TErXm>uyiqiyDa;scaR=Xh70qW9AzZNUE&AWXuv6dBS)~9a25S zY{YtY#kX?}5$RcMTYu{+J~G}drL0b+*0No~mN6AxY9p1!PfxW<6=QiN&&G&iVRrLIvW1nbCM-OyGpJT?A2IZdb3cz9wVtF*V zBGHkv;WIZke%ms}H@@c|rJp$J-pcV+v}v?vnKqWGqIA;U9X+^(Dn@ITshRy`N6_1U z)PAx(=&%%6-W60OD6qUiUT2)Yjp=Zio)nZs8Y)F@jSjcoPd4SD@~?uE#;7m%5c|xA zJakjO+?Kw#`DX@IR%VD@2-+$$Y)Vh$LYt#1!6oGbT^JQ&O$^AjjfUr!%e$qPjwX4x zTw6{p<&O-?QEmTSwY<=yfUWQ}M*68?c?RP1P&FjV6VxQa| zvP4)>LZWC*-`QUMq^$3Ro!k+py;ZGKEVXDuo9j#7?S0yZTeHXhwe{jRLr0DnZbR^l=^sW=4H-8hbr@(vi)RR`d(Z5KwIwF z+J5ram>1h#{iJM<-4^>v+w5$u$((JMV_WMdtraDylnQu&^{{Ku*Hm4W2#m@HD^poHYWvWt^ zHp{(bW7}y#qsn}z>`}1kGs{ogeBXO3`^jHh-`QHfovr0N<@w^a>N`c7ZX4g(e47?D zD*8!qpDpXf<$hA8PCh^8pxeSz+R~TW!gt2vgEt)SI@ennb7&;cSVa2Wjm9T$ELVpC zoACu4%aNXVdOME;4gwlwXdFjFfP?V@9LG^39(m({<2Y~PxDgM(@f`I98dXRyYP}8n z1ILs10oLQ2IG!W>!9@7}MDkvg)Pa@pNpI0tTRWLMM78I7CEcfrV=^FCtRO*U@30QqSZ)mXYVqo(aDr03}!pb0^ z_!yh;F_xnWIMC~$9eGaDK2b$(4aCk^uw@PO5O!U0BP9)dVJD88ICl5Go*WP5xG8<< zIPf*LgvGI(2QK?iu8*`WR0r$>*2X3LwO~%qN|v| z8N;iFrv;Ycn*%@b&4Hiz=D?3FTHvRiCj@5fYkKSle(EUKdt5BFh9A9d3;dMvVEb9u zmRgouv)qnRqZmhyr~+?MyE66yZ&B00Rn#=F6g3SjMNI=sQPaRud~IOKbrIvz7}1&> zt?j6(d#$e4+S*4?5kq1oMxxlV$JqmiQf80yTp!+`21S3^6c6Jz=+|N*+BfhJwT?PQ z?V?^$Bk7KQzv3w{6L^c>6*Vo7wWx34XT$o2MZ;RRUf<{!Ewv8ZMtuXfQQyF=wHF_b zQ&(P4STnvyo`sUHEqYJmn(Cu zjV*6{>z_#~?==)Lc&Eur)c(6Ci1Eh4D!$Z_N`gPz#%tR}1iifDX zJYGzQkHAc8c!-`5Jtz2uJX-qWcr1TgTj)m7PhtebXb4QaF~*8OL%G&s zOzlx0|8X3ttvNfrqw&zzT8AzZT1;q&Zw?O|*F7}l(3y8U9@<*#&|*ST56xw3@DS8X zN-WQ8u^~jiXt5-O^`NjDXfX&p#HbId8aN3G5c*)y!{{xAZfKtgO`tV8S;(QTg;$$V zQ&eMAuhvT8N@^u><#xwVp{>Zy7IgZZqyGrmOOa8qoWQ?hzI9erRDPK zT3|i>+_e!sIqRMJd@Z&CYaj-yk|i(V#2J%1qs-Ca-f~h1F%Y|_J8nGJ66i?sTnk~? zVXBca)QNqPE6KNn0kxMguj?Ki>L>Ko%I>KnZ%>Kj;!Zw~y#HwS*=n}gbD6E@np zeeBKP$8|bI|0(04s9Dr9yyC25xpq;ns8RGDM^AybsGVb|z+T`jY8tqTng*7lrh%oX zX<#X88d!?24J^5;NPAR_6FEbSmijb?Tz&4?3Y&)g#eNgxP<%NS1H)R4H?&7>h=*v& zsCTq;^zjzVl<^R?jygu|qFzxW=}L+|Mjn_6yh&q5(-O96d8|c!13w$qSGrJ}XhZAu z4SLg3>%eW)H*mXUd(_tAp%~frh%MtGY8tiMuwI+CV{i>y(-ChwZd|XT1sxedwF93) z#{-|ChX;L+z89Epi#_Vi;6b@ps@BpY%Kc$$@E`^@<|SexuwqXy<6+D8DEXOGd}Di5 zaJ#@^U@tHhxZ1vWkRwTt9U0pX4;$KB9NA)~?e?g^Olx=u38VNk9bu#b9K0yz~37lS|pRU*IkLm)&JUZwha&4YL9y3@fbSM=JamIoSdQ0 z1|w0uL8&t&^wy|~eMV`e`ZfJojoMfUI~or`hu^r?o7!Qv6%U)r7}h;3355+|N8_Qb zwQh?&>W%OaG|XO6*bt&ev`92zJqSIyjE5NYp&v%y2nrCiHRwQCTMAkedVsyAH99$$ zD^j|P2Ll(e z6WAttTem0o=2eWYkq7 zK)#q8JMl&S75kelWtT4FroBY@i$rtRE5`kf~S_51| zX)&Kan*SQpbveC2{cAjFGEkqg@kElF2sFmrc&-m4o}W)Kvg>l75nGMAe+N4n7!&@C z6m{{86mQW;hDWn|fjb_3jdV+XR*E`%7Lgi{CT`);T>mPiPvpjOJ(ish9_PMW(>^`7 z5|RFK_I5ieMLz6I{uOpnc!E6_j644oQbvr#5Ad(|litn_3Xk&7vy*OnHW>b3_GRwM zfEik-I|AI1zlV5>?E!2d=h^HS@#TCdaTL37{?F_SF_irtj0Ac!J4p;Bj-s6C zJkq(uaWtx<(H!5+eh)Y2O~g^`%C-C1`RX3_DY%dP6t13{-Np_Bcd&QBqwEcF8%ORX za1Uj-ar9_@Jl|?0-S?9}$nFOB=O+_2@?DwxbTtv9u`ADY55wcwx9CBxp2XL_hxn7H zq$rf{A%6$gP6wVq{s>R~CUO4n=M9gLZe!IVz_fz`L6vfi`(x(%{@^sGJ z3!;e#kX?D-KXKFuypjAPlzbSdmB{@c8i^R$jdS-(yDaUU@p0hCIlel(mYCgFv)|ga zz)Q(L4ZJ#wo!Q*6gZF9%+c zUBhk^pJrEyPg8y!yG&dI{7l+$;u=aWC4Cln9r-2XpUp4hUzZb+(&)RFrM>+wOYy2N zOYy4RweLzIjbFmGi}}ZA*;mc|CN569O?;MeqmW-rei3D#&p(&q`hJd*&$6%EMU;Fr z?P>ARv@hM~xoVtoV`W~L_QSZ4>o?@rr%0ODQ~vqv0(Q;-Z|oBCh5QEacOlWqyOH0( z(e*?m*TV1x(hclqashX`k4Xd3#;Ym)Fng3V5UsnK^Yhv5q=9JN)trAQ?TGR)@z1}( zekSfM;_hbe$RDEQVdAELo!s3{PGmQ<6S?{TB@Yn={UIWncjp;50dGoirf(*~v@xf@ z1gz%D5T0#JOLq+!lDTupkj#BVhGgz@=Dunt15Y78jiVFNo?s{E_Yhy)o$TC`?rxwl zuOA?P4|{r?mfy+QUBnN+n<(L@bAAH5e!PeLboTpr5Ac2Dw{!p9L?ypF#UB4UXUB8p zgxuZrZqJTmkCGGE1LXwv4*4b}x3MqWt>kZ~?EUPu;*KMaQsVw`Un4)3vJbHLiu;fp zOFEOC=f0NW&fh|Q3}t7sFWoJ~p?{os=C@==vx~=>>;>X}Cr77!P`*XEap%86{x-@! z$X<6}NipcZO#TuP@qY&VIr&TM4EA&2FUembg8nbFO?TLGm#*dPl;KVxv2)i?x%X#S zOx!`Q2hq`=0Dg&F+3ri&M2=z)lfk_CgFtt~8%&D~A!_|gX~(sn5?g;2dvmz=#@;-6 zHTm-VWv>31Xy@*!whv{?*`Z?};15$I^?wEakljMoq&+_NBX_rt<@pbYbp8^t>tpw~ zm&uK4|8lmBYirp%WPkE%_D|>n>_$E+?WYwxes!d@bJ|5?9B=}AUyS7HDBxJ~k?e*s zmfb7Haa6;MclJ^n$F<4q*f9|}k+XK}Ur@z99aA`8%A41+cioG8O*7{s z*gIn?dFxydx)d$^U~G@Gr2R!V5g7Ba2mUw45O~Y*}Lv9To{^mK^aP!d)@sd>k0f5y9)Hm|7-+( zj@_H%kL)hcl=e_*;vYM)Psbm*)|mEGY0R6*>nL$Yk3X+<#az|5U+24?PxH!wSl z9f^8TqyJ>i;~8>iKAr)(b0RxtQS$+rJNgXB7O^kR0G=?A`4RVC?45RI=$-aa?9I*q z|DEPdeupi6UOqo3VmAAou+J9zob=~81CWIOoBaT4NxujFp1ly9TlsG+oU_@NrC&CO zeOZX4&2BWrEN2HA_T%E8b=>!Vz*_P;j{4+SVcZuabN`vX*$^;5v~BM0n+*mR`Zv@A z-8rNW`}_3+_G6!uKJ0liAg|{hJ$?GH>qb3kAaEc%eAH)y*#9F-Qk?Othi5rS9b9>= zLQ)eqsU9KgS?18arF9c5Kq@j0&$57M}jb z;?~PwIn7Aj`m-pl8NpjGLS;51d%NDzh~7s0o=nd+(sz#}L)HMDk9HR^_Y*TxxciLt z0vb`-UB`?uZe(#|jQ7rr8f*me-eAgj^X_9d3uqK__ct?2`E0SsF&NB@D{pLbz0%bm z+$YW0=SDfFtvMQi{$NabqoNx>-dO2IO&^5LU?g>;s1HUXFv7ag)s4HZ71`ME4M2Sx z-M_67*Z?#Jyb+nTySo>S`@b3A-F@MP0gcS;jta}cLN!ntyo{r6N#c&U(mjx^dvHxD zycBBaElU3CA)Wcg#T<7e@02tg zb)ZF@8|7JTX(7-k&+1$1Rccxb=qd9#a$leM^q_ehRlwjp`qW&G>~A{*)y&iwBL+(7EJzeX=nAD%g(x}y3^LhGQ z*uQIdckGm>hi&YyXD{!`m&UGnj-1$o&wk&Fn#B%!jxKwDZ|bf8nB#2{_;4S+*g4M~ z^xQwsxcK^n75nFnrCrspJAmQ#q>cB_Q)6=mcQoxOeQ-{96j&6WK}BN3%}%4NW$%U< zadou4V{I;}*mcl7po-lH`_XS4XYNn9fMfj-7XV{N!`RO-b~=oG4r2$z*#9tptxt^r z|FKJA?2$N}^WACBoIG|=EOu3N#A$Qh9jJ!d%+U&3%Y7H!>0vioY6<7X?u?E^N91lm z^;vgtbmY3LV-sl^Utn|;agxy*dQSEtjiANsZBnTbw5mO+hV$ms(!&|O_8w{5u+%4p z(%NcvQo*6Lu>Hm!&_t^?@;$bCBQ0t#v!xqoS9_%`J%kpuFL&a65U?}3tvrwxweL%< z2d4HN0CbeFI~KX~@%>WE3LQz-LMRWZa8#da)`yxo9<|$e>N7aiaY(Akpj5}fuh+3Nb+kSMUazBdv5wZx zS`>Bc@LC=F@}*Ujw@dZ1hV`kYeO{}bwTjvar9w=2Z7)N?emC zCWeukUu)H&shx*XK8(6r_r`>SMvj|kJ=?Y+VWNTZM%vI89ztrM^}2F2DB)lb$AhV@ z?L3e)h+5jh14sj@Unh>D_Wct+`hf{&PC6t^*uvtY12q-{eSo&D_^3-bsN+~X6m43e z2G-YlWvNEJfwr%8=>@c&vHGnk)v<|kYZvvhof}Bj$aWq=vPRZ-Fv)sZ(?KNbWnUgh zD%YzEb+WcmyMC|LtJ7=s>PS60QoDL;WlLJSsFAg6&vAQ7qh7VCjG!p6=elIC8`)xv6D)kMwYUI+}R$ebSkx7 z25q)Cu1IAoQuzw*k!nkGcjwqWH{?Xp@f<6mG)!A!1*n~IkHoX~q_iqo5!(UfXnT_O zNV|Wu2P)-iGjwl|(d2ule&r5O?KvJpzIWn`D}nAYBE4Bjt;Z${V+X92Qe1a{>IfW1 zzAACq)s%KlHqK5!<>A$&RoFxw(fg3P0+o>W0p}BetGTid=V3YRie+>X=WDpH8_;p2 zwX`d668RchauSwTC1>rh)yWFG2FvUej`rugJ5YP9yFpcBLw1C&<*YkUxq2LY14tzxpEN4?l~hDIEbTOK&6s{$$JBpM-C>r zJEENN5YBo7XObTRZ=Q)o+?}4*aaIddR$s@+m<^mo*?O+^0j?uoPx(6R*-8J06c;#M{=%(d?82f?K2Qdv3>$?qs0Bn)B@b?XCSs?SF#*U8UkEI z>Cw=VML=}{_h=l14SF$0$B>3#BUVp1mJ)XYIwqB)`ImRe@}0TUonVxw)hcGw zmb18bUZU{x_~$T=cj9hmftqQv+1xvyv@uLZQmeD0MWwCuUHkbfOZm@Wpu2M| z<-YmA`J64|?ghXF{C^q$+XbqZlkdj$fk3(YZX68&?#lmmBP|6k<7@@@Ngml?@j6p^(y9K_T+dk z&Q|f?y`V`-N2~dN9Z)Li?yP;FPtLUL%RSEJ>`CbwXhBb)d}>?%d9vzg9fl{!86Gb}&PLM-Oa{l99tOo(*ck8&X8h8--damsc+@Jp(3T^EIlrtX6^=?3S zaXpl42S7QLlnLcb|KZkLC2(&{z`f&c)8F(nU)W+Su*7Lu^({qntthIxF$T6LR z>j-SeT}N%D6@ z?+)(ehVB_){03>bdk56e8gf;4`f&$=p`5vwfO?CxqL$Q~-XUdHl9J-adRD1rJ!t?? z3h7={gMiYydcLU4(GocMiZfjePOKmAsw{_lmZ0Z4HfbxC& zLHH62)o^i--9RCZ!a-K_{{^$ayRMAJo<$E zPAW4O+z;Wnfi#EqXh=}5DvcA$XQgyPxv-M4P=0NXG0v_!f$=-#4@P9w}FjrT^>iV!;_N~vRS#K3m!jksl5KJ0|HTzPLqt&H_x zSewVJ)C062ZMZk0cFJ0Ct(~&GE24WOYTJyx5zDfCixjU+uZ=XMc>C^__eNBjZ;|E8 zQoJKaF7HZQN0d^$lt-CWekq(hYZmQao1nBUW(9h2G=ugITdF#Wyl_V1 ziPLFad6B$xI_)X{(JJc*b9Yj8s429STqta?YGG4oCAH?5-_X`t%y7tq996cYe0e;$ zm*;44RZmu%mcJ`~w`OzI+S-mZiuTjmTFlkRo#fhuRZ5%saIRZRZR)i^aiBfD4^V84 zN|+m&a5)lu_U9Smdn9RK>H&S>AR{>*3>-w;hh0*6p~bQ_Dq&+-!iGLUw)2S8^7bTm zn;bze5Hs3`MsVJoFw{(${AC2CYP;H(MsTh*ZA8M7{aKA)T-k>^0qwQ&6??Y0Y6jZR zt4Q*t4&?3Ac|;&r7Ap8q@Fd5Gdlm-QitGL_c-7|aDf6(P0j3w(%tTSe@J*n>@$XNM4wjvvp+lbUDarBkh=E*rE2#Ihl*jkAd;J^buVN|2qjj*iY}=@`huCAIui9H$MrHJ!ICtfB(U*%z z;r4^*gE88pZw3{Ju@cll+}qyKqwNjupqT;1gEes^c%~ky4%r155uWUI)x5{2+Ur_q zOTElw8Y+LI&mne2kJ;dm zSG4py$EI!&-VV;UDg$f(FZ>+B!$DsMJsgy%m4{mQb0|C?u@-NK7C#3y z(-v=sE%`Yp1%|gn+0Q{qHl#=;+ZI0ub)(otKK7GW{`b3;{neV(8~oOoJ?YP}8iciX zk9j>ilnwiX9s878!3^X^9NUf*IgX=2EkUhdB+&8V&eQgGzoJ`uYBx%>P|z)rgE#;ELcW{Hq^l9;ty-+V)s(K_t=)mjHihSs^3MwH>jm70d=Kv26Wen&NBaVIPkm}%pz}+v zxHuT-+>t9KT!XPM`GMqGggbJy7O2%&j1@6#T9C~ytA+VU{0?cKqXHuvt>-^_-B*f|iDU(gD2KAH`04zSbTp{ixzO zK3{6mj#~MAsdLzAL$A)kfcHzgV-GcT<4%-xNcT&pTJ~#FtCbE3+mpNZQ)sdwKYK;| zY$(@>S8=VRE54=WYDmg>Aq}h3gg$8vt&8ocHsiP1&T3%R#rAhJ`X=kEL@utZuQFas z8;Kh+6FBjiK~u$zm-{$f5)G0!n5SQXtnNS%z@LujezSnOmc&=^ew_09|uR>>!ozcX-b+#pJ6WhZU z3K`r{R@ej_Wo;Q>T^L<`sJ)}CwejWm$mwkDkn8az**RiA_BY;lvjO= za*TasEwuOm_)H^IOizhMcuOOt2PJBEP@--6MT~}%c_mZK=QvbooK(>Nc` z`oIrT|1-(Qz)dGpIu#B#nbm=3QgSM39PljiDQTVF6wb$Td@A`Aj;5yddsEW-y(wuG z;FPo)a0)Bp-p3v9C!fN4!uJDDA)f+A*UM=M64D+(eV3LXY3&7c&7;2IOMvqH@DET9 z(cfD?sl`YmyQ6Kapl<3OE07p2!i!`VR+e1^JcoQ2uABou*Jor_TJtw6t?HY_D!q45 zaw7Sxw03V6cbvlUDSXwUv<`3)<<9o(!ZT-+jzu;(nQIGJNq92wWX{#{jzx+&ma_Sz z1xZ#o7P-e#b-H7Lo;NfUW3heeeexbhVeqKve~!qYanich=y92!OT)ry8vH4&sllH% zv~(7HNg5=j@=bE7f-m`Ad5(Ot=#d-pNiCRRS5zzV9X{vH@pJWw;BPTfgTFZrrQ`B9 zvCxTQ`B;ow>6xRqHC&Z>NFjsxwPHX?#5elo>Mn)NHu$aYl+!A86gD*Zt?!l7`aK)s zWW)V1{Fj=e?dX4$JEDCz&tt`P@dW=XHTFwwBW=?`qr^bmxhXA=ciC5@Uw(b?YTIyo z*#9=>)n)siHT0{Co@%cN$tL<#!4X3i3f>$tk~}$NCi%4Q2)mhzjJHeTj(amdzD0^KgIY9yM2tm zu;)AO9D~Z9y%Kf`TBN0{8(;10jn)r+x|BY&#%oopNj0?}>vIz{P3jiZQ7R|hkRxhI zlDaypCuLWzRr=~hZgku}NOHY6(r%@Hz5ezCl9bn=~r7;6J=V=n)#n}xS=5@FKALh=>rdzZptglI!zkC2 zLN`@6tfo(Ei&a}xvym$p-N+R+S{Sq-sqd&`+REBL)jj3G@?R-sSfZ50VxCujOlujO zJ7#!;qubN8c=?^tTU>SJDkVqy8@(moAV*X(us18|O0kp{ln$h!zCrEYF(M68CqeN}BAM@liClsA<$JM;5SCBF9j{Ey?$cNhP1)Ok;|RYQZg zv}S6JflIL^&H{^K)7pr?w$77BouZZ-&sPV33j2CS-3lAKQmeY3ezVo&Jvef2I_Y!F z;YzKQENro2=2Gm26~Zsv*I1(vBPB z!9J-3Qczy|tnZTk`USqr`D?$xcR805oYUDTle|<88|~;dd>m$zmddH+~s`XQvVa>)->Iw=u*H}_`>~(=J`n7V*&TvUGn=2Pxt=R*p6--N=y-*xFBk#95uPyg?zRMMy zezSOwZ*>%l`|#GVe=FH)bL+!D>fz2KI2xX5`x%}!k`L#+5s6_qCC+_0^QH9QJd-m? z&VV^{(FBx-JGV59w}~VBp_D>uE$!G`neQ*G*V5M(f2Xi<%V$IDEF`?(m5xMZu8{D> zsNOiz)UqFr?dSXTHVBKp>sj?mD0-o>%j|`*Hn2Cx_DkEq-npfb;2YcCBO4n2+V77s z;Vfh)>K78FJyffKl8|@*mi~FBL9o=tp4K&3W?S6?Fg{<8H+)@_TrkhJb9iY zxti;J({XQdXKalbsAQ^?8Z)_lxX(W8icVWmZWZG*W=Xs9WgX}z9r&VR#?*NaIh6fH z*~>mGg;zi5!53&T){?A6U#o-P-Oym$+Y9ZNN`YSWn$Hh8+p9r$?=My^lAHe@JQ!e>`l@at<}<#g2M&3m!`zdsjf%1r;7n` zYtI)SuFlpfE};^3)Ai2U$Q_-o?>63u+{{(ddLYQ#Ts^Hm=g4$bwe$S8xT~!P zQ%~Dn`ebRG4Iz&;L*6AO^%U^m%6EDS_*BQaz5u?>9;N?`Um@?5Bl&e=*trtFT0HBG zVQs{-?PM**v#qPdBc5$jd60OvmBp64!FCsm;@O@ccI`p-CHs(ha1QS-mxpD;vFO-Q zUXPip822%A6?4QbvV~O2R*=Hmg0_NEn=NQ7ICmsXvlWy!Z9!Wh=7{ZO_ITSuJb516 zMZGKR6=C-+Jno9KxPtpQ!-lAj+f4SV~(hQh_~3Y%AN_bHt4MAKP<+w%LqKlTVm@Bs3zX{>eS*uLdh>q2r2I=(um5$Dd0jzpg%4ebMT#7U>^J<`|q zyt@uq$GK9BGL0in$wnM1*HqG2bETi7O4^u{dIEcLO|Id&_^C-}mU>Ohc$e4^FFsqj z)29|1kC^doVne+6joPIAI=?b_iZsws);HD0T3I(oR=-qNYc35GTLWIhkr)zR1JXCP z(1*}~q!Z;n6OxWnnjApBP*@2=%9pEz_0C>yUw8C`1;_C!mI`hxmgE9qm6Rihjo<~o zQ<^0<`~qp2*bp<)IPu_UlJ>cVC z*$?FceyP3DUTO{OhxSQpW^c5YT4Q^oJyT4GXZxfW63_P1&{D*s*wm|7j$kW`XU{fl zUrVFJ*2&T=XvBSRb@K}Tv3t61bf0#d+aAt+Rsn4f=S15BZ4YNhI{#Xp0yR zs}ryjrHiR^XJBW}cL5h&fL%CW1dh4_yK=q|+;szXOS7D|#RAg8Y<_Bs`CxegGnsPa zc_imIm7V93<}uT$B)v0fF0-P_&&KB3nfXz*xY?vR%%&^+T<>+I}0!-A&%LPTFj8~ciQ=S z_puM3TIFUvsP!1ud)U>F`p)WQ8~)Y$R2zp(Sy<0n{oM3R4lnD7gXhY+v9yPMKm4xs zn$>q!pW5(cc3s_QTEtb4O4_4nUA>s~tsO<{gnzSh-ma<~0aX9jN3ihDEgwUstcTz*#)`UnGkrWF)kV}gy-D@P4j)1N2P1-=ex~{#>y^A= z9J}!9UQB63vukK@mca3%CvGQ_tFb3>)REknV-q>*K<)~-2^_U2H|E%Qj*R+k)Uk0K zwIdg5F{uC@=UPm1p!7h$-VB%nwT~G2B?D^pFfNSaUt7j*z=-ZOoRMywmy?W|V6B#s zjIpPmrfV8q$7o!yC8sR%En?%qY=p#(kiZPbY+Dj>yleWO&se&@3P<#>)Absi(oIsP3tu5Wbwdp$;2jJ6n& zdWm+Y6}>Y?TX|f@x`!BT<#AaaXE7p+(P=GWocWEtX>CWIRc7?+MSEozRw7>nA^T>t3!bmVCrb9F(iGANI>;q*4Wz8#rHXNqWO z!)dcvU*P)W@@R|o1;to&oW}Tykyjpz_BOrr_1KRQS&Xd~zyDZe5F>Ihy<|}8m$6=5 zFY{PC(6YLqh$$&Wmg7sejkz_Dp4?FBSe(*)8=pmCTckc_>w8qYc7EZLVsH!CIZ#ijo6_Yhpm*rK<9v!XIccO?kMz_zUnMQQeWat#+tl*4j@w#l<2Tok zdhiBoqqb1P^Q=d2a;ldxRCR^YQ@g?Aaf&zAfD*gFd_yRPeOpDosmSR;)zq7joV zi_wxS$re~(ltE^YnVqCzsDn*|O&Vy@Ff+9QCk`h~8pbxsA99#EX`1wZ-?OxJ&b>1u zkIate(X-c~ea~FobN1TbUhu66<*)7xlK4$M78|&B5G7BdxpwH!-V~(kh5qbKL#kc+ zvo{^t$=`N{7CS9QI*X5{Ek*k7k1pSRnG?iU!K)B#6~6lsOPM1l9aH{ht||O2j3e;9 zHewbW+6G}51@$#0vU)E29&?Aqrvxo4qNB?I+KCpMBhYzezDm|HE(}@ zv6)Ec`Mkym+mp6T=ULYt&ZeWwu`8e4RCLZ%wraPjXcdo-=V&Ur#baw<$mX;Ixve}a z!&6}A?d9(^rTp!tl)vMY@;6obzAxe#bRd1x7nN_i47QG~MdhfH<8~bTjwb)t)>v^= z`qy^PYQ6QmDUKUw95YBZa5RtY(DJ=BhGQDXRXm5Rs=l|g zcq+cj&Ofv0F_#fBpYK1GH)=joy(qE~?Whr5^DN^{@l9(f-?Wxe%eItSRzLXiauli4 zMDg(i)vAuEH5{w8eJ905Bg-eNmR!wS=~?|!5mDgy2#aH9XJqe)5NGq9eZJyCbGn=l z#f38%BhG%}Lg!n5DRH43m(JE=!{d0WB1G9`j^#OTDW9@WMMUUx_i2d*eG_~tB1GQ} zXF0KUk$5Pl{HevNXN4}BDf-Dzi@1e1ZB67_rh#N zc`p_r7jYack)nRB1CDJ`zt#a+#beCNc;OiK-IiV5as1A*^c?TGU9psBO4%g#Qyg zwqw|zh!jhVVb2^OhW~4S8=pnwtwn~GPuN%^9K?zReHw zZu$Y8?c7ELu)l5mvU&-#x7WLg7=2ItJ~=B|JSl&3M0{xj7H5y=TzEUR{!ZnXdJg5U zJGK0Er3e7K~UsYTs}@sl`XTaAdSQKUvwpZ=mgHGc!`GWqseZv*6_9<5c znVU&lhwEf57|vJOD&`E9*Xgnogk3ExY1snj+CE$9WI4#3_+mD#cIMuw1+(SB8O+&8 zJ?J{a%>1xmXuI?+2n$BAGSzJt&Qj*=h-1`uX45;HIWwsT)q>jmj$|ylE(i->-KsaA z_er~gRy}#owAP7T=kkVVMbNI`{G?S*%iZkqotn*=IXoFrX?M@7@kzPj_xYL2tNqQV z*4^`pCl%Ewe0IHiUiBvxRWKa+J~izl&RRV`FISMwPp$js_3hyu19nA3G6?fysk&F z|3vnmK&ICt*?$uIPbBy25$yj1`%fY(?BVP$PfsH|YXx#Sm3gf7wTxOsPe)oOY$az_ zP?zT^WVkJ*cF{AC)*f4xto5~u^DC(-vot-EsxoVlM^k4;X?3#I>B;2Ct)}NHD&rhY z?XoSjXBF1TQ9g_MWoyzSor-c@C9!9z>4Y zFKG`({)+9d$@O{=@4_puje8+a<|{I_Z#XW zJ&fPsXY_a&^5<-SSJu?|9esXFO{Jf4_4j41o!@i*chuxrpMFnGp7rSu)Y(~|{z#>r z_32Mk$68Olp|kiOtx2C`dp1?LK3OQwrYh30RP6Z)m9Wm@nw7cEp=y^klRnOo@?0tg zwUiaJ#0zJ!e->4_KFz!Osj~9ddDI58w$Mj8Ql6hKNT1>Ar>SuCQ@-J6+5Zd`(=MRq z(?_U~c0u|aZ+Qzfj#{|(;o=NxX?>UqS!W>kQTOV@^xc;}&lqW?0+NX2^Xz?&DrzTD zd+S4d;-vK5VmCFtzFX{}w%2!y6Zk)Tmr74Rp;nUET`Xt_z>G$i(P3q zayR|HNS`khAE1)gsp$jsIwgs8zF54UbEl^F)ApwC(f?Lze(g-V(kQNdiSa#>?Je}$ zn{J_Wsm9X2inI=v7~;!R!5Yi{*O32>);y7lR3iQp z6MXDxKDyVvBamiLo}NxjN3w4Q!s+ZSDo&$v*ilH=9JjDNipp=dpq;FEwYsdIwVE1R z+u5JTIXR%WBdzDPv8*ZPifcz&%%{Y{?`6AzifKEOtFPmcJNf^tr#9LTkQ>-8p^upQ zTWp7=Z&TZB7&XMcU5ua&Pe;@5hv?4rY)7Ua7vDyDZ7H?RzJ;#)7M~oIeneHaQCuBK zJ*^*7r)@N6Mx|xcI{PNN@SF4-!<~MJ{9##J%T?a;;u~CFPFqG5t#xIEEmwRis7Uq= zr{}x!S4JRZv^1C@Xs`3*lD2|sUNgBmgEoMwUCiN0uNif2I5!|orwycn7qfcmWN#31 zI@=b`jHh;0CugS72B%HT^et&KpIue7a@0Z{H!Ur#N!v?n(mLFlwEDItExN7gM6k#l z`m|DmOgqe6fQgTIV6< zpr1lztn-oQ73Y_=vfvd-L()0)nueUlx0T<1NViK~7w_Ae$odqUceoK3y1xn#`V2o|`J?AN)plaSh|=ax3=xuuPIZfT>Q zi;em;&dcs^4)_^Jx%}tS_JJKLOUg{n%>t>(r#O|Y-0P9o^LM7wWN37)D>I|k3H<_7 z={JKqkFwFfitlwPQr`Mk(X9S>345>R+g?JYNSWzh!P(2pnvz#g^Ko{1HPs%MPzmm} z?7xN@lycR-jO$lWr&4};t5se}-Nwb#(R&>|UrSxbqo}6$dd|GAcnLkOM!uBoi`lyd zc@3GxFXr6U)PGz=&AvC#|MgUWT*TfRizBJw_ad%eOYP2U`TzYZRXwkzBH@wA8j(j( zrSHv1D-|xJw%=PoNDGl#VBW&sn~S%y{}%A~^Qf}fM*9~e6+V&HWo)DU8`27nZM1hH z-$}*CHrl(9@1{;<8|`M~&D>)O+ZQ0O<9D3G-V2d0=W_ z#ZYSGoy~hWG+l?L9nDi0Ctpt+i@c7b8`x_@YT-0jdn~`4=<8bADC8)5UBiqp0y%=? z8|jyjH?VyG+r%>&&NVZ(6Hjb7$5w((JmKLS{~bq(CqJBHE6*n0l;IqIAN2AF^q+a_ z)}?#|^M!fq-=lpWt!9l|D^)(6s*#W8%B{5Tp#`mcYwgO1F)u%wvp+@tgt`1NY=1`k zDO%I&wpO-$C`iD}`rp!i1|qnLquzXv0K%=Xvdt(%ZH(c@R3uE!!D z%keMS{}u1I%m}aG&EJpQ&+)5h7bE3OcsZlv5~Snd)f_(_`6{+AW4v67yp(IN;oReq zkLP}`q5YEgdpN(vOKF!OFQeaUx$;ZoFF`a<xVpk_9@M3%X2TlX*xzLJ4fL0I5evnV2>73n>RP;}Pq?ET>P?{Y@Z_mE2)2 z@(*lRf=vH_{1e*^$d$I%PPvB z=jcVCk|kVSN~4N7_gRb7>;46L{VQnHTE@dzE&LPm*=&cEb&iLXb&iMePCbV+!`T{3 za6VGrt}pWW)yOZf)oXViQdY0`vc`B4QvQzjvL<;lQvQzjmi!&>WzF+c_MgQ6?Pm6^ z?<;S`m$=s|-huo#H1{y}-iCZT+Ikp!Z$ZA5`Dhq>v-#XA zW`a4~`4;wPBb||NDQDzc${G2Vaz?&|S$rnv^^m;3oU^T6JgxXZIn#WAb5lX&&MY6~ z+!V0;2ib3Bwekt%``8)PSWk#iIW$WNR7>#-(XFtR7Ly-^V{#FHk2%7muuKhRizsfP+f_}b{ ztpLsrKpUx~`rL5Cvdznp!GCvv1q2BhaI$TZe8zZi~6@BenAn)Jl z%)7U8?q$q-x1!Bnf;^L}`i3^X<3F_xcR5!8bV;6Mhf9{5|l_3ur$;x-JwkevjFtAAdvJ zpr|gDQVuCm-8o3t9tG_@q^pvGb^+2AM?t%Y8QjX^u8)-3BRUzmA47hObGteI1ac4C z>74IGYG2sJ*-s*Ovz@`2>7ay9qLo~EeG={S5zfv;8+-&E^kMdn=h~-`pW^Lu&87bO zFxTcFXETSoaurMe5cwmX*~NT2*F6P$uLniG4kROHe*^7$r0bG5&_wrQ|2NXEMPAF< zHC*|ypkSoDOW0Q0Z(1d{^gu~E4b`ZQai{3_Vr)h%)GRK_C8R-&Fn2K*Aokwac%}1yqn`A z%5}z(Nd5V)JQg9fYPc3T3aM4Y)roOCvZ$FMtq;Kb0cTTVep=C+;(AvBX5P61u)8R2Uy#-XZS{ICwP@(iG*ZzRs^jhR=dF!-<8B6nF-c(~?9b>MT za|EqtbKIZy`pgBb9X}Xuwd^}zi0X_abT$jia4O-nJwu?%M5m~H%A?($9 z=)(6P#;S8c>the=w|OXG85aZfuI6=}3p#A^5wV=(ll3`81f+I+E&E12`b5Lp9~Cts zA~`B-)T51aRHL4rdL-lF*Sr?__nr%S3eTn=e=+gaOe&w8kxTl-#0{>x`|*tmt{J(c z7uPr@V`mCv!8P%fdDMC{#6lDK>+1IDT+tgmoqgja{B`^-{B_o$?PhR(CT&oO#FWk> z;i1y+Y)y(;Y<-i4@OI5XIwtjGi8>=P)lsKSEaJ?gHfKb>Mr}@?Z?H=bWriK6@8~gL86}UnTyuMJA?Se1F7}CPuwB=*4|Zi2gjYG$ouPgjlbnR zJ=^%Vyk7A_n2#K|(a(67!SwIVch2K|RXN_(MOGYhysNLQIOcdaV#11Jj(7E*703Ke zRvoj}*fRd!QueGdW<2{6_9BYiN@GiSKE}5=(nYT7>!{q*T518Glp0!{KD>NpRu@~y zz8Zf7`|53H2y2b$ou6MmKW7o60FD2f$62e3%|#j&Xq7Sb`VO{M8S_1hxoJClFNb|ov0>C@NJWW_PHv2&u)E{=C+Nk_eYXy?uFDNZf* zzfoTs8Fd>uYmG7I0A~klj2T0Cbcr{dHLNnGN7H%4Dr2Gx=LoBe=>c^vIO@Rr=zAG& zs=t}ckIrcE9{bkIJ{0fxVz!O}M}og`j0DGtqs4Kf26aq0HXKWiD92Wey?LCO&$C}n zA7dE(eI134((p4odSe`G0k6ik(XugWD;*Ge!AKPKg=;w9npwO@p=m;|4B~ufipPj`HD@CI|9fSQi za`YsmqwJ3C-~IZzu9-tu$FJ<~eP7bgYUX%@yVK7j%8?+72rZp;W@yXq^=fbQVeZo# z{d}mu6Hyilhx7-&?WQOyKD5bI=NX(-yZ$ksF^pQ8;lON3ZxMvYU%FuvpP9z={4-# z75cfZlk2)VbaGuwhfWUt9J<=rACZ*$Idpa84271yEA?~W#K;#?Gl!P$PCr+gIk4tE zrJv1qo6UM&9l47)*6QdxIWjj+#$U7K%#oXkRI~2p-JXY~z}adKZ@CrG&8pM4FaukH zbIl2i2P>j4;H-Xx>8#5ZvZp7Z6Y2l`L}ucJtl99>Bb}R0LYG-7{X~xRBuqsf$@XOS zrXbaIr!fQhI*oH@l+W^v5)o+mpTL=AY|rEgk4O6Uomswd`U2Y7U(R+P z*Tx}Na;$e?JeC_Pq@TsvHsn6GXO+nRY>vlb%~{3q*(HKF8?3XM{j<1YWpwMLuPN<4 zXLEEe$D@&JO52YsIBnEpu>NQv)gC??xt8sDU@0r48+Bo|bnQc~?9OLwTOIv8u3W%1 zD;lro_yXF<(yBiKX$*+f(zPU+({>TZ!;nVtT?EdvF8YO>vvRuLY@<;wrbjFCBDNQU z36DV@!_j`O4MlF^SPxnYHkbXJ$<@;J$XGw!YU##3U5bv|g1m&IOWC^wJC2c4`q73U zk7cXBY%tPU#cJtVdZJpotH>)rRRfUDLe@+lgxt#3YUu-zTiNDn>CQ!0akfA5O18Ov zx;d^^OYeu=&Niy0U(KkoPI_V%yM}8CX~yU^9M48x&ADqhzM7HKH?r>d$m(uPtzi79 z*Y`2{s`0g|X?*1|730g%R3BgZ=*BjTuRNw=d^x7hW&EsRoW#hAF%{#hr;$}3Q;wz! z%8};yI+}gQQ6589$C5$J-_4SaWB;eYg;+K96^mEYdbxzF43PO zt3UhI$Z8x@F`CTJ%42E=y&YMOKIg7rIt=bEvmvdFBu|&I?y|+H0rcw_buIok&f3^( zk)OYyk>;+zOZQ4XUwh&GEPDs{dRY$JPjA*R>)gvwEi?wHeH3ZzeOh zNI+a`O{}?m_6T~K^*f)dM{>@nXJ`3EoHw>k{)R=gdCa@MX%TTN-|vy^TeZi$z%fYK z6qeA>GmF^D6=CkHx&B&G7BhFs8SHx7iU~_OZyfMa#=0EB#&a)3np3!nYlDz0*sh|F z^%YjLjm-AQidjS7#hh8p`L)b;qSrO-uPf)-b$ntF`&N+FBR;4crRx}zYw07~##-bu zu5RSoK;(M1`qbAWk72us5k3kjH^(OWd1eFK&79XpvWYWW=sOVUh!(pa!|XJYYsYcT zeQO(R<;p;$Bhmc40m!Xv^(!2Uw7SBMa*eTr&m7DCNItoPb`0ZS1bdE(V?k}(_^dvf z?MO%8Zmt}Q9Km)sd)vWeqP#t{0Z7^0_Rw~L&qmNgkI;6cYnv0;+XW`Gu9o=C{Rte2 z({>>zusx|98&>if#{Mq0@`$R*%v|;T*4Co0*_>X-mV9je_-talX}{1S>lkuW1#_-r zsBt_Q2PMjLJhd?f)acbn@{A*_lfUJ7awNs5n$COP!U&0x6l2SAmq(JhD0w^$rC*FH z$J5w@<7sF)l44ZFc#4rEE^{P}MLMeH^X@yUVmuA4jVJAL^-(2%L47=pIXIrGkz~HX z5sVAxq8LMYJRQlourcP5WClX>cpBX_o?Q1jp0s0i9Z!SH@#HL*N0KY6Jf6aKGMKT{ zIG!9yYZ(!1YU62CZ9I)SIGzTTBPm8zj3+T^9!cx@yLmimQzi1I%Xo^M)jXa?HjO9a zdYZ@6$b;iagzI=3iL8$&S6{OGIFe#i#dsRfFrKW*Rv%At0_9N^<7p@N&!cJt?{^+g zTHNw@8c>d{7*8>h`j?|hw${e+WHz?rDIFY7TIGx^@P1mt2O_m|n+N52Z7TKiTJs7< zguG?i`oce=<{aTy0c5W>ut^$qLb~Z83*_>y`l6lT^dFx#h z9z`3D{&sdX3uhkEOz6ezIg4l$wxZlo$fazTaaP$u59br-619<5{G~{O}BE-I{L3JN5E1vxhTQ; zVJ*_EeKTXMIcn^+*-z`rx4soABFua*E9i9$S2rLx(9^kNJ#r&=v(k+-$6B^qcsGtI z-~F}daxsk7`pw8q9LX!QiT8X9J+wGg6c^q5w-8+%`@3a|oB4hm%tR8AzEd{&E zvEsgUqE4U2Cm;vMp|L=G}>TR<@$)vVD=b?+{@7!?CoU*VeFsl2v_y4`p@FZ$>sX{3|0xo zfmj{#OjZkLasC|I=}6b{=W=aexz^r?H2&{g+8|car*m{ZvqKy59FERs?;Oznx%3zF zpNDj{ei41nN1jjri#azCX=L4g&bxBnN3Z?t?E|rk48-jhB3*M|LK_HL7s*{lzYCFL z>3tdPJdpV%^cSDIT6Q&kB|R@gUPjNWIOke-HrK`IvymeCtLY;~zmQK{&EAEeZPD8` zH1YSP^b(O@N-Ty<6xY&>&A5j1*RfU3Mnhc3-fX1$;yT*3=mYhJ6+|8DB8(|CGZwX^ zsF#$Xmz+yya6Aq0i~)s(zczcZj;pW)6!f)FWzm{>W z)l2H0&`aXAte09!y)?83y)^WIUK-k@mqH_jcIv8^)IwP=%`A14+R53w(oWX9QzI$W zMWWx`=$g<)Mw*<&wKn7lY)|1moP|_7ReGrny&`VfOVbuv>8NJC)P}AJy)=k^p_j5Q z66c0SQb(z8LN6J278*(Iq!mNll=V{Rs6nN63X9=+XphiNSuYKwcj%=H`1~03O=zTZ zIm&uTjdT%rKEKpUV-D&i5lCGx?dSNSQWuRuR@y0RqyaUJB%aM0=@R~K)=O$6ZEu&A zdTI0lU33+_XQOLGK3OAay~}zjbdgqstdZ10>ZSgrCQ|G4=h}7X2(^$owdx{ulv?jP znrmU7lzH-Id}}W-mtPx!I7>cH<3+=oppQ(eflSX~O%PLQanJ(MJx+67W7P`duqvCv za7LTD%j}MR<@l6!Cvj&zxe<@6S9W}$j${-6W;R*$|`h`@f?qc0*f z)?+D}c5tb07nS?V_^iI7rAVy{S`%bpa#iFSNF2D9?Ya`ZtfNoXwCdiKXi^!1LdOOc zRIAF;scm5+pHknhqvuANI(B0z<<;3lzpq>=?(}`zLK6XMnb^XfIB*mF zL&u8t#)7}LmIzKCkL4R{ccA)L7SS_AwL&|uh&eVb+zEX2qy;}yi6Z!O3mmixx9?`6+5 zzoW@@knB~l4iYEGWb1eld&msOWlm3pH>GbZTCEnCd&NvdBH)O;T`)V=JQlL*P z)yX>*YYC6}22AvSGT05|hk9YL8pYxq-+S5$bmBZmy3Uhpw2c&b^pETHJi!T}^3M zTZ9}-kFde5pvNHI^rdXWX5dH>lPssF{#4gWE9fI8aYQ&<$x7pRaqPKDvhKI<`C58u z1rW8!)#Mm43eJ(TjCWiO?C4mB)TW?4&XIC7JvY+RwbFX}M6FNba@%}FM{hE(W4{93h0|T5{GO+8sEE}b3>4h1!H<0DPmDM zGpva2*mKOtf4H5VMm$>|bv)M`BU_MSo!wj;iaegJ{9sxRw7h8n*oqv__C(IOcG*o& z*Zt$m(Xkadz8oEnJ>UI3$P?*vGJ7ZTuD8>}70^zk_B^vdMH(U~@y5x>lQ}w_>wA#x zY^@F)7{kn^J@h)0ai`C+ogN~MJ}V@(p8q8j&qUc)AK_1L>d#h<~rysr0c8w zTpNbe+qj>m&*Kt~E~V$i$cyRYdS@6?ugB$_cfI4v>T|cjeD?NbYQOIeWtNS_3ml35n zcQ^Vx96=eAWDke_4?P^>6K7x%iq}LqVjKM>!BZ}(@y;3Ngx4e^oa`ylk0NKIJ*`Sr z*>uG)zDdC+Xe62##-}c-5&v}1MwGvfQv0qx5%G(>_F>;O8dnRh{*g}3!n}rt)UF`H znNj|)#V+b(quJESW+`{lQ_U=+oO)R;EQXoQ(HuS{;?Rd;Wg>O5Rf|L~>RK)Ma?p)L zs=r+g&PJ#Dd+GnMTDRC{0ekXMyMh$Sj6&DSIN%D=eL42zDHeAupr?GK^U=10*fUOH zK3Z19vY5W3kgQmsMf4q;F4<(g7ItEG?T4#tFPTN2M~=9>E(*>2&=SmY+QB9%7e7PhVyHz7B1 zw3Rn(2yzIYaZRX2OKX@I#%R^8oY9IKF|Eh3FX}m-t5&d9zgxk26FSjoS6Q63y6#|4 zq%sb&j~b9jdOsW5B09mmul>BNNs2*(K9SmJJ7Z# z(NpxI^-6?PVHo!V!|di$6^3!&yt`95E0WRHv6r`c8q#&cURnoIG;@3Lj7UZtBXSYL zh-bw7uBtMg5y=Fq$r#2pL4{;G83B&PjAukLfoi%#GNP33@r+EU^BHCGpo;th)reul zGa1_ik_lAPh-bPYnTW#fif2SV*_$W^3WOt`5!L7e$#_O26R4&U&vZpH>e%k^jL0XW z8Zl5tH5t!{Z354TWCGPR;+d{UMtriFane1W5&t*_95rH_jA|TnfocND1gdGoGl5|O z)dZ3erF4g9L_8VKh<`Gw2_)l~%Xmg46R0MTOrRPqB;6w!QA#tO8P6yPJR=5bL^T=D zv^3$Fz1$~IO~x~IB;(9?C_K{+QW5=RRI`u%jd(^R6R4&U&-8?3#4uu%VMtL;Ml#NX zFn*NSCQwbrGh&;-Ga{KlHH~=YQqE^QBeoHj$eqv?&xm#!QH|(FBvYZ9p76}n5`FZ9 zY68!QY%;15&xmb04&s@>Hli9CA+9OWi&?9IWUgTw*hX)a{ww`h;lEN7d8T`RmeCdk z+R)yOK4izfzw98sh2G0a>@oy9N%Kil&^(XO5;BpRpFr z7FsmciE2?JGejyI*;|LMTu-08LR6=1;%Ercm0-4_I4>BJu?{(g?Uqu1ibjmiaOLQF zP#m#|JA^GIuMI^iVNp?|Y8{CcqS{QHp-tLVVOUgl@xt9Geo%|p4vFI1pX6Tzgl>5w}i4Vf|Av&5x(<&JL7ppCq zD;fS5-)?;_buWxQ7w7!&zvzouz;Q%IWdDoSz~D;P{sk|^_c+Xuih391%d!lP?D89|k|9XVO7qhY)6_sCD6cG4Xq`sP~+Azf3 z+B$-V(m7vLoc%AZ9oEt6R>2j#r`azY)j7n~#vg@uI6N=D)or}3MnGi$OL&CEu9aWd znLqr(t^&5u!YZhbI9mlHQ&}ru-7h?t9@+mgjuGa&Ef$dBcst|J_cweoqIRnt`96#P zeZ!l*!$UahTR5bA&$S%JJ8u<~oxDH#h_y`XHP$0+)>rnwOy@1vQ#_6LdN=2d7H{Vb zu6!;ha6ExCMpR_~%L$wb@34qEJTJRI*CKlHgNRxro;||a5X1kHJuhPI(`XZsdWX+o z77#^*M_B7gcx18{Mvt)mmx?!)NS9VXT0HG z$}ylu!c~@yh+wlig=isrZNveW!s(CMoiM^wGlb!sR{45UYqdO zj72v$duoQF6YHKDQHmNjR&81~#2VRaQ}@(}Qck4pM2a-Br>2Fs-!+{Uj_}urIl^m` zJvD6{XHSio~KM&#f~Y4+Dto*I2OB9`#iIHIz@Ml_;*V=S_6-w1!rAo^+Fkbxll zH6n-XsWFne*~Nv&R;X0H#+<^j-qVe2!GA-+$Vc##K76U z5&jxSl=h9V0U8tHOq8u0S`1I(JJkI(?Tm)-*EnXfeWUKL5#dz+8m$-MuW4Z`CNbYk zuT8dZh*e~ptNbL5R8|gsFX5>PuZ^sU*;6C(2~Ul-4!tqquaSB3I<93;jlLVbF>I}BM&zzKOpAwhkBHgL z=c{$u-4PdOjBaCGoRPYX5pmA^5f|4O5m%4bts-@Mj*E+kxQLE3b~mrcv?}O{HUhVb zh|4Rop5o$+h|B9T5kX^ITtvi0)NaJi**}NI_<+Jp4gy1sL5GYn1XS~%NaU3D3OGY&cK0BRGvnN26IGwxe!tTw0?egkJ- z@tgZ1JJ&m|bizwz=FwbQCt9bCy?LObHl*HR^`EgfM*cOfdd%ZlNKaQf@(jd!#~2$k z-^Q}FVzJg&tz>4t$>yc4N+0h6kePT-L?^D(&MQ_^*O||w#xqmLe79xvtX4YKQxwGw zLB^`5ovj=O=Cx_z711p~`-xpwa_p*Q3};1hN1+KPa%B}QJipqhCUTr(*p_mCt3GRg z6>n&JHCkBf{TiOiB%~`;tyoh^B&YA!Dnt5(J3w>dQrAa%gw2!-Th<1i>=Y2*6s~Bw ziX1uZv7$fiu4|Da*=}Mlyujw_L@u1Ty5!dw39jD)4>+5=?d349IcMP~{1bZU9 zV@m87E29DI>kW1t1UEl@TodVCj+%S=g3Z{mdXup_<|!EcWzJ4mWzCusLFyM)>I>LK z(-J$CH`IJMtNTsk?C$cdbq%$>=kVuA=MqUicq-FEMHu#pL|Z)KitY^@+wL$#Jq}%^-~MiD*tdhZ*r`k!av+n zTR9mi=16KUM^5wl$+iBmw66Z)yoxfOLT`qvsK)hEteGM{v>xfE2iP%Gt)H}BXiw<6 ziW7^hs#*%_}GKfErg$S`M@;j61k~(kheJPeaPJRDBhd{ljes*H44X z^;3>_Ydg4plIt}`y2Z*#YlrKnwx;!y2<2>AnAgVs(3dudFtz@LA8}r zj&vK#%1Fylj(3aoleV#oX73G>Kub(cY|D}xZuIncw=m&BwucBN(MReO0d}efQ z{WJ#D;MybmhX?YRSW)Fw)D`s4@or`Y#VRUd+^*xAtEli2U(HcoMGdH}pR`=wKxsE=dM97YrJ;Zf;gli5lg8X>lCyxB#ut!Ax zaM&ZXI(3&tT;&gEtAzFDGCCI@H0BRydxRN!#y&)DUiK5a&WW7iMnAEZGI4gZpLk7) z7sC4xd3t6JXFu`LT+MlUT{DNZ59Z9_$RZ9uu@*qtJG=Uct1RNWpSY*|VY7uBJ;Y`b zXWy`^i=00knZtT3jt50H=MRSsBJ%ViXYY>W4~r_Y=h$3gk;P!77$Q8!jrqf74rf1c zm78~O${%*U+UO_lDStTf^u!*G`NQT6XK%5&#FsGp-#7AyBWJjtMXZIQk5@#SM8(t7 z$1BpuD{@D8MZyme86`bug@naHON28^LAuLN5nE{OFhV2l;A$$zZ$v~# z+^xz_sp8ws2hnC>ZixAM*=AVJ*Rv*d}c7dc-~B+@~Ty8S|i-eINvLdNQ@_6xZNv|s203HybJU-`A-uZSSqFSHhB|F28~*@{v3|4yh` zE_@fV4QK(B6(H;v;)3k|m1Usv|F(2%zleOjcKT)iulC-`|J!oFav^(p z_n?(}e%m7zzEq@|M*7zk1%!q*YdoGw2hZ-^P4BZ5}zYUHg34EX>*)%)Yja z^S~H&`-QwEVZRW4TtLg7-^P5sh;l!_v{}d(kfYqga-pp_V%qfr4?1AQxD=~LWxtR! zAm{6it=TWMpNAK?^8Cu+*)?BJ%g5EFZmH}S0}t9S!vCwyBik>s~eI$E+ zb3Md*)}9uQoV7Q)!G1Bi$$nAK*VBs8hg0q@oD$4u5%=53Cpfy)mKC4iUBQ25^o*;s zI-lS@!+)l>J&v(pUUTLX{M+F_tJ^Qc8WCR+s3Y^D)z9A<@ta0&nnBVI8VKgWh~hM| zGioVR{Db;4gMTohINLcge$yzaVIU=AZc z4<~-}_C;=L+uughKN;K`!Mb7OW^ixx#cv)?{H7jn{r<*pR*1fi-$nFtaR%Q;#Ba{# zOr!rXm^LDEQ)tDUPhmc;sd`QI)2m0&Fp`?d*V0sHfHXPDvGn`92Da^d(Q`U zTk#>mG1h2b=`OFO5zm-kGJ$vFwlh&gEOLeggINC(qlisp1+zw;G4*mW`#*2zm(Y7_ z9-_6n z+qv|XQ)4FExuqpWEF%+=2t+*7i5ywlI>kw5%E~Ap-U%;|yc=Sh;0%!6QT~ltNEtj9 zaUb>dk?gCh<=0rqR-cgA#w=Ocz+?_H)+^YPWfU`?M9vPiv{72J1(=Vb24Bur1~9es z5-Fq!q__MUvX7~;#Wul7E&`E7teKNswhlG6Ij`~rM7&kRUdjEX zmX4K#Jj+`-Q^i{u>5WJyvN%P3~#l<`wW zS4BRGEMvQ|M9B-QCC6-6nK|S$&lxHc>0#E1xqxayb6$xzRt(&3L>)t$k?1&nS+nn zjFV=bc=?#CjFaGr?>YYSp2|Bh<0P_Aa^6XmaS}NwcW>TFWSm6yNj>jGD^)%F@n96XH|MWL zylB0mgE=b|uTWLjK?_r^I%6#e?F7L#UR8If$BSCsA@d5=>pF-UazzJuh2+5!LAd(A zYjA`J!d$KH>pBF2ICOP~L*s};S9IvZ5muVHcjJh@Jd(NC@cQyd`sz9!PF=^|#9`Fy z&^7uk^f%<%kG=6;^oB>v^@e<&hho#}8i!Hm(aIH1?#wt0BQSE^lX}IIV9@F*4ns^I z(HQb*^~GUSJX(Em7-E)tnnx@A84-a|XVa?UsQjc#6NrzNK`WxEBZ4~Ew0e%i(6iV*k5+RuM$QA5Q!DD8 z96Ao8Ck8FOkBxcY#_(TEtMb6JKSNHfuKtX!aTs+5t%$%df1$fL40985Hn`kdRUCC@ z)4G=Yh2}i)VAHDeXw@0CWYo$G;bvRp2H#(0W{HRCDWz7gTG+PTHNx4jSC!)>i467c}a) z8I5rY*d?Matm76H-0lr{rYn*W;fP`SctQJkLAyqj_VI%1mF(jMjXG|DWbPbZ(4P20 z`}`{R9lwf5G1qITdsl*iV`_0JwUGNbvPJ>!Tz zUeKtk(0g9cY!#kB&PJUV)clWN2bH_4j~CQTyWa4En!i`ojl64lL1p}Ewg>m|g5Hz7 zps|Vyc2M)r4u=<1rto(3eD{o?9aw88(xU|_Z>?O$a*`) z9~C2)(|b`FCqEx4+lIONQCZh~|0VQ`3X$gc2RFG{%<`Y-TxRqCjTc=)yl2-+P1bNS zC(fMZQS>t-ZVA#_lk2%Q5NTYf@u2IFQKLzw`Hi%k#k`T;YrzL2%j~#~?28-*Hd$mx zma8%2N~n-COL|B<3kyNl(Bp_$J$SavnPA9`&J>df|J#ptWbRdJ{_~<+SytQ zlB!~z^|+0Ce1=s>y64Z(Gc=wipG6*F!?~|`VFIJ6ALA%0yC;}JJ7}%QiCnEJpIHlS zICqK4XI4Qochpg5#D@D(|IGh)Cw+4*G(8+vuLgwUIv~yd7qtI;zYdt@CFLW)x)>ja>Q63aXB?_4FQFjwjjutp%S) zm0HAn(`Nn*^G|dAv+!`N=MK5jsi4v~K7vw$^)d{j;d@9)1oziKk-m*n_kVrOaMddAHtsRsXD&{m4UgG|9Vby+FsB z)r-x~RtGpL>il<;7y;e!-}Ns?LcQ`?RoPt+q8<*b7guo`jr{%AhRw6hZ2HgVJ+N+T z#e8Rt)~@x>WX`Z!S|f9Y87Gd80mwT4UCcR0FtVI&tXLc)Lf_aDT37zNfxPuq6}08N zH_gob=6O3t1|sYH89mi^*EePj*JiZ7uADPgbGOW&5u6#;dd7M^?2&1AW{yX!$omphT>&lW94R&ec(|IQV0#eX;S075^V zI|u(=bA5NMrDxLW{C6$HZCLrNk^fH4jm)2+eOBhX7Gy+kMBK)N2L22yvj+d2^VzW8)mKM`e#;d&HNeGbkF?#&Z3$B?lSr`#%)C9 zvtZG%a@y7Os4BZ#7rv1{!zT1D{yXt;F#6}{4eO-k=#8lCo})LK z>$^Ae-)X5B#4oLtqJ`EEY0ionBO(P6MP>!H=1Gpa2qw^A1(h44J7&`6yG7ngzFU0O zH_E@_oxRU^{{Och&jepaJNL+VMkFIMX9jB2{_ zfr)2kalJw^B9rd$j3_9h8u8Fvuu;Y{nGa0n! zIhNL+pT+nYkF@suY{p?Q`N|P)oV1KGa`Vn(Op0U@Qe2cP&C6sXda>TT_($yCAL&{; zY6{2+6VcbQ%7|5>()=RcY3m3WmF-&Ds_~<_wwTW@ED?(p4MjM<`BwQll73bbu+qG! zsqVjA#<6^qf#R+48VKJyUR7Pg<($v;=B@PASVusFBTMff2${=LDj)16X3oWpHz23ZxU-C~j)|+oD zk-SJ>#3F7P%#+Xc=G(w5jnxF&IL>)tqNZF;Kr|zox0-+z;zTF6U2k5LyNfqV-0w;- zD$tAgqu#vCU(OdNfaB{G1jIJxMu=^!+-eN!DZGc)n>V-2Y681TJR`!7dh_j^t@|%? zy?JZQn^`WB5xqn<`5Ek0mFAtXa(?+~^t3{eu@+W;&H3eL(kH6UpTqg)dh=0fejh!o zG+))27s;GY3yzJ`K`Y{uD!<%VQ>)HLX8A?nkEkPHwN|Uni)5-g0^*bXG?9ok=5y`& zi@9gcEZ@)lj6B^BLJ^-_4vG=sT*6VVHy{2>ImE8ws+EXj=C&S@ct$jGHFv+X#4{Hn zJIF@QndL^O=FIYI`1G~tfJw-xIzNeP*P$8aAftl79IlvUE*8=^T93D=^JLV|*Xy=U zF4tmO3j3iCL@&l^j^Zs=|2VIY=FLiAo6KuyrC7PLh9lKv(`lZG`i0sDo$H4qU5(8_ zH)&(g2BHbFH4S?{E^)Mi#lsr1`2p1yTkwJwIeVj0JE z&8A<(DuyfRS=Vg(MYLpOoi?%5Z&qy8XVP*|r|DU7u3v?&a+SS~7M0r7Z>zbtt1v62 z)hnb-XwYm{N~>$O2{p|oX3RQmBlpRX8OEA#p>@@4R!Zxt+1eX4n-+-nQkw-^M&!C` z&2SZ_FT{!`>M*rdJH4$pxEU!^xwebr&?r0TAG5q#Mk~U2uI-^6hbEHiQ1%O}sO{m* ziClGcrA|DFYgRl_i>b9_CqKE=R5CT5LQ{homuVE{ZuHS!u7~b&T{akfV|2!8wB6+@ z%t~omDU6=qjU31J4E9bgHI)^qwfL&3tdX{t?O9ygi`3E*TI($KtVq3&97|LI*b12aVA&{6UI4QcNKOHax7bGsSQA0QR*%$u3gUFr3aWWuB7*V z_O+5-NmF-SPXDXWM`{=K*fm_)j~v6+`e{~2lacgV`UDsGezeej`d&w$Ygl8cnXYI5 zI^-4f3NCV2VOO*M3KsIIY;WLrDs|JYuA*}2`YBy2r-)xJ z1cRK5tk+Ko9z(Iv#bAmyq?K31FjW;5a{$9~992~0?W*dhM8;pRFk4II3a$-6UJ0VP z0+iBRKSlf^a=8d;wH47zuytL@{*@eE3m&QR{;uX~uKa4geN)8leh}Ak-FfXLQ)t$mk61VPj;pm=e~^;a;Z9mrcV4T5t1Z`VjdkbS(1F4H zHH$v8X=9P~y7Stu=JK7#v-;AmFpm~>8m6=F3ea`iSY*`3w(|8tdWslay}3#oiwqC* zP|oT%v(9VOo!8Q%-#J&Dw+8)KR$toB^rTgF=ZA8XE6y+CQ?B7;G#)~~>}MXsZ<)Cc z^|~$RSS!*HdNkIZ*J8Jl7EH%Sv2Rp}oL|~!2XnlN*4w)CQET2+ey%hT=)IFCE#{|NT*y8mM`Z+BxnM|eJNE2^V=|3^=e9KG>> z==qRKyg91lzU%+!8qd+^|IkXJWuz~j!&zwtIwIrozIYDf1~VS-i{}{6C~>50K?VcI zy)B+2^NQ=?hexrmJ0qSW@VI`F3$Y{0z|l3TBlB<=+Yvk*y@}@# zn;Vxg9GUUBQ5{haMQ=)G;4tnZP`P-#is}eFZX}2H#7jWm5zi6z42|Sy#N$;|#|>bp z3XkhQxdDvaaS(||RL3;VHRAE+c#b>EKGB=|^u=@Jc#gSf`W&TtNAOJM6|;t$YtXwl zo}&-XxN_LZ>g@g-pK1*ts|qFFXrs4XRqLTJGQ(I@@w;p7KsAAIa(wDcuDZg`*${JC z=^LM_7dO{;>nT3f^;~n6x9+1<7tph@zMGM$N3kM~`pmZ{K6N4M^yRG0bCl`|{zmul zsmtlPik^B#`|!+mtPDNd7w?OBrZ-4N%yVChPwk3l?nr!U9m!M}=K2z`^gc56Mo>;w z)6Gbbuqi$OoTQa;8rOTOhf+V^82^#*^ca_ad+O4w{hIZj9u<8l&3dn@OFxsVS?^h$ zrOE{xeo*h#Bl3-aTfk?Abvidm;Mj_33+Ugd_pC@Cd0|=;tGe`EE7BVs zVwJS6b?L32657vN_GYszM6WHSzt%%7i$>>bJFM5Wto$lbi@wgMsOQXDY0Y)%jSi_- zv^<()^H|o>KS$?BT}vy{S9L9`y7W=kvR;v11iBgPU~^r1qeG6RZ9+zL{wB6LI)5{t z%5^OxF2AR`^!1ALdP~e=u|nE*?vVAKmFx35&ghW5nv011h|V`Ap3F7JCDkEJSHb`w^O-Wb9Kw!`&H@{>2J%UGLCo;tJvr0{H}hLvxzl{>hxBIs_N3; z*ZnH>y7b{!se4o^U&`TDr0+`GJUcZXIl)882uJ@~iMxE3dTlVj8zP7oq&&4;bq$(MKch zFxJ$HY|Z(AJ)@6|I0Azl4(}SL6fU z9^4_yI2H`hh(5Z*9U_j%3N#;3i$mlC2I6Qhqfeur_I(R?j02fu-j2QanuE-Xtp2s;f~vjJMR8?j=KkU1mXzvasP?u=m~e+z5E=J&nh#A zwc&>|yWe~AS?lo}@^jo7`K))`|KV!(wz68g&t?1s& z(jkHuWyr~~mc3?vj%H>KnQo53x**el@qWfLSrxv{LoN!imiwVtI=b?61o!w*J}J-M z22e&Ykju|uCHRV&!t=q9Kk~_OUEf#kL2Ju87s>v?8!-{a=!&6%vZUUEH?HF8_cWR0xWus8I?x6v3;VbpXh&H5(IY#E2XPquu- z9m4(*_i46*^c-(0&xHBNMr%8(PGWBiaw1!^Unhb_jOvydz%22>9LpAFl{VwIjScUI zUBU?N>9hhVqsVm5>0K7p=tpixif!Z!kU1doZpAs;Il}TWvb21dfgADL?esF1w7v8$ zTdS?kxF_R=%m8{>jKnrtdn7V=_l#9Fa$EiY+4f`<7>QTcIDDhE=OE?RTg34KY#G79 zH;}E?4s9Msa0eOpj>I#fXC@f;^Yw}hi*98bV|Vm!xkdTaAALs#|y z^`(`nR`5IOZ`S{^k~RU^!Leu~a&srM?<~2JU$_G)i^(eFB&3`stJqr&=9t7YTEpHX zFojq`%{vC^HIcmBd{gOtG|l}X90ebenp#FN?IL<#RwIY7-N@cLaEEMRnITE!AU-(; zc?{<>i&#b}8$lZz`P3HL1}q(7k7Id{w_xiCMzKxYK_AR!kcb((nITEU61EWSA{9Q- z?;_KHl}tKI--}2?A4^1N8*l39k;!x$Qk=7kCM(}K-of2`%4ltKE@ev^hwo(5sj)%twcIbGEh_vWk z6sh*VL-T>j1U8@VJ&X5xA@8{F`aI-3-t?aNz|2Cgvx3!`C>;@f@fNo<|T0@bdgPELHC&_#uhmedI zX6eqR)p>)|UX#&P&AdUf2TcYin1!WuwhzXjBRJNxv4CxzH)s*}n8$o>q{bp<$~te* zaAs_MCYd*AQaSIN7p@<1I5K#HoWX-j!x_J-C$G<>;td+kez0rE!eKnck<7cx>66(t z^qH(KXY|ap5gZ$<=+np>6l<$s*N7FCewDn!T0{TL8?+A8umP+P^LQ&Wajqs^4|a{HB=0M@w^Q(>mJ8;CvSsNeyN?@bt+P3j-Bi|pHJsVt{`j32YXP| zJuzZYd&Dl}u5y0{Z(TEQkgOYG*IfN1a|jJ#{WObDpTavitBkjhjXZdRqSi^QwnQL% zX|A>!*ID{KqVCCFwr7A^Dh7^y^gWYL$iorqtTVW`JREXw1nY(j9LCC@j69iM=YX-= zkio;zxXv=(;&fJB`an)cj%8ahaL9>xF4(e>H)t&Vq`%e+CeSwm$W4r4{HF4q)Sb2qbDD-NN&+8SM3 zZDsbL(Ztq|W+iqVTbViLux;cJx`I3R`7!Q0evI3fmwLGI6ZcO)hAe8kS(`NHrQTWg zgWIxXbmb52-l|cppPF%mcd(ACo=PKOrqM>D@w?+w9)Yf(4jO2T*sQZ+I7>vVrm+;V zcNy>AbNoct$cft*w^@&$xU=FmtBB3RkDus$zhQalV&FH+pce-$HUyWW>#?7ki{BReUpLo%Y5L$ z1YXY^J>2>xnJIJ>Rs}s5dMDgBio*QSLotE(RNtg8enOu_@P`_U8UBgB_=(=uH#xLF zqn1(;*ZL;% zF-0Dg8C1)$Xe_}Bx3u)?^`^c_*UBcYlU%b}6RTd|MCOb}JZ@!_oI$mgPv!b1RyL{f zsH*xVkw;apY+_8zW^9Aa^-W~gI+oT`9#yV#lD&65)iB@u={B(NlFQ!@RB&wWr<-@obtKg-q>@F^?cvXFqIzOGY zPI||O5&U$rV%!!VMr4jwRZcQ9U6n=JdnSyWN7a4i=mW3{PGzLZv{h&Sj2H`RokW$B ziubc_nTWb15p`j;!R;+Z?Q zUfZGZjQ;A3YV=+&=13NFtF|ox_jF&c?asn8^-67h@t{4ieBBr0LI1YvwdES2);+m5 z)NAVr)kJ<)y=q&wFIIRa^0RthudOFk(^HhjX6A{;yzo9e(=#7NAD+1<_`T}97me{5 zQ6E+=j7C1u#PN8VwU@P-v=a@{4|FJAoj@B73bZn92W=QqHeaJ?t)Z6qWK|{BHQ;#e zqXld{*echD)jt#UVcY3#^^{yCb~?QW;E~aPGo3z0fkZtuE3VC?>8p|BHP?sLe`D6G z-r>L-v&wy~D0AuAz5T@6vGeIS5NY&CBV(^#Bcnp9`mjcfhJVx*Vyp+XpXB@#BRNNv z_7jmt)KklNLvAkP=m#Nx@`3+V>8Wlje5&t*vpk+)tOom zttVB_KXLBZLhG7;GUPxkh*hIPe^&Mrt50PsNs4Y!=|*|P+Aylb8mk$(C|&bUj2_LICoR17k$Dnzqg){#&pNS!(`rinYTtE zM{yLMOqsVv^VW+wGXu?x@=UP&H~KTJH6H#<>zIUBQ~s?nyzjwbUFV^R2x+5)o8v*{ z(lQ>}I%>^X;S1>Bm=8XXeiaYRSl;@mGw3K|3GD@nBwxwb|-c z6vxQ8gI1Kt2X_=z_LFhE`!OQIeqxp7Tp8BbHSH(kkiO@Q@u0>S<)~1{Rh17u{vh6P z6onPVxaaY_`}KTqt1R!}zFQ7jPK>3Khh{u7>chI~wB}G{MG5^gjO5M5MLXqDt)9-0?IlBF3McO{?rD;mO=b|6ut)k3LbE zDDuIrjTZG`t<81;S95*X3%N3pXrtiwHv%u$hYkCQadj8dy4p{ylNNlUR$QyH3T8CKd)tgdziZ4xq~LW55g-K%%@c=_k?Gn>Sg59R;cFg!ZXf&B73W8I9emlTeNR}*HF&R zpve~+tf7wOSv0+(VxigSuYRBd$MqcAh!Vq$LPnKXv5*no`f!Z?&h=qMM7c7oRqiA5 zJI8r1;Hvpu`eejHMtjdIQHoxj$m24qdofpYmDnYGMh?)bexkU=imz(6WwgNaRkXJ@ zl^pFIaoz*zSH*ej)u~re99UwIi0~E*iBrq^fhDSsXzxJrYxq=-^BzP$ ztt2ZzB2iJ}Xs#Z^XfzvT1$WK$VZ}l@!h0iqMEJ&ei-oq(x>ixt^3k=5;$V8`IPY;h za}kRb?5EOqJ9lfY4?CE%J9sAsBefak`mnh&tll3HOYiE#PUGFmao$yxSjS1!hixxM ziWyu{A9fFj#VTOp{2bfu8Apa$<<^I_GHg_dt*R?d0K-Itw=>vYTA-TUAd$$VjcD&v zxpS@$+e*KP`OZ1CBAJNrHrm@7u&wmS^@c=fW!Mh(jrq=T-oxn^ z`Lvgp7$#@ZUcymhocD108QVPx8C7B@F}AN}Jj;(hyoU(y5nOAo4?6-B6ZK(7lyTk( zybXqJDLB@46YheZ*^=Dp6rB^kw(WE^JWEXt%%mk9*eYs+I-&cp~yM(xqIuq zMn<1iUybLnKH5<{FKtuWqXr+eL>a>~8Z4y^Y9(lLF;eT)O8Tf3wfC;#sui$h2r{c) z8&ueAjWCrnXfaakXg0o5>ywsSt7fm_4(q^ltHETlY>DK=b%W@q#daBT8CN%Q&Dv>d zQ1RX<_iC(1Ki*+26VCElFNSa~TP%E5jXWE{59&DRF76}l&{OnB@ND>5(WABy@76Q! z=uLi$QFSvIgY|k0_g-G|p7=ozhZ(ecUh-fh4|Z}#yyS<= zNbXx1o@duw;*mr1l5737QvC*G-6~w?CGT2a%J=rptM}TQO0TZ`Dtqvd1D4>^nVq6i zy=x{}LbE;Cb?TY4$|~HOO0TYBbEVgP+%2k11ta-+*o2$;L0x%YK+E>v3+QncYo7DD zPqqphTW5{eSUH`=enir_Iu9GLSuTT03}W8uSb9|U;HuuMHC``gO?DAd%;K8KDpQ#s zpt;^_ScS*X?`r;1Rq6E#jyX z5@_ZAgj0@3@9t*Q9gjSg^`P;_BapjF|CVtL+LZL3X-znRwi{^;*b`_Xl*7d-J@bhg zm65>u6TvOk-E$ov@@WU9_vfgczdjyaDSoi#vUV0NNk($0Ib@U?h*Udvpn1k1MgOi3 z+K>a-PGUwFjC5w0#Jn>U>FhTNv^WAO;*|Gm6w+t|bFSq8llN;9J@o&0=Tu(x+m7Lz z+23zFns4SE{I;X`d*0J;JCg6^xAj|&;M@7V{jS5gum1zT@i4xT-^B0NdH}Npc56Lw z&TGRC^z}2t58T6hjW}>`|HjAzf78D`>cDsLJB>c@9sREU5B%<<+4}z}%I_4vsTHl` zH}npLTt3Ii<#RNiV+7}Y zj(Q~YP56xDpK;{*_WEYuo_EGO=QqT=b@vw4M`G9iQM@zt|8@R9`p!hvb>E!(!#i_t z)|q$gJ?ZJ)sJ}n)p2QRH={@PHTk3C1-+OXr&8;z49_|d=tWR$5{1UTYOUx<0 zEtAXn$mq^->^sX%F6XDorM|TWq#hLY?c{RKnp`3iZ5tCf<2-hM&@GMgkw~ZKnJ8wf zn2)-S#O`#pGkbkL^3Cbp98{mV4*mWF4)M<2p_Dp4IrN)T$0YIo_zv{^wy0qm-!6Zj z{Eqo6-5=hc!=Ib{-EIrj-#K{xj?GOX_D0;&JS%0~+jT7Tgm{~0rTZ)H?Y*9P zi~c>GkNbD+-}UeMUHr@5$>wL`o7BHgb$&Y@`&rmIXO+GuV*s|%jG8g4Yb(vzK$+3y zZrzFnRp#GgX=Xf3V{Z$7%&ABt5H_>F1@H8f(noD{!ZD1|O-L;-8h!c_W*B%Xalyh!E>7i?9ZyhU^cI?*1q^_k|K~ta78k#H`dVW^ZjJwnuWAvpN zB*t)93q>EkndEx%_4CWfvz(^?e*{O%XvRsIGrW{0!@umknelXj9+{;h-_w<5$Pya?d^>_n($J~oIC)Zk-!##cK zk$-0nof&x3`KvO?&tTih-h%R}&*!Nch3ivaP(I^@Nb4;4)Rji$`lOX|7Wt%=i}+1^ z#>%7k#eC{Yt1S4umB!`zyp_gj_@tG~cp^S;rO|6XZ>70)K5ym9gU{P%yt;hetIH>? zv^K&h+FG8jj4M9%wdM0($8$9{!{@z@=W6W5Fxm#>aE^T58+f7{cr#mQ`h8nD@=06K z$@&OBdzn>?#Rz_t$g%TTY$>0DatotlAnmyF$sAWcA*Ej7{bqWC;VBa6?m9a(&q?a1OYY)2NK zW;?QYH=p`=@gC&6i<`^;-_7j5r+6>>Hy7_izPI=X`i(+9ne9K)o?P6*`S%r1;@qg> zDdpKGax|)VD*I0<-p|!ril^}xMj}UY_UXl^IC?tmX~hS)`u^e>#V3pZME)mNoqi8O1-b|4ih6uzdpZpNfCx?xT@UWc#wzTD&y9B)ydF%ac#wY z#Va`T^7JB(T8kH@4-_9nw(?h>!}(XFf91*ti+`nksCXeqA1YpuURcTx6(27CCA}ai zKU{pIcz*hqr2I(nuHxC{8}w}c{^;Vl$*28X?)IGYEUt_xURpd0`4YBcisy0lxoK?i zVvfhs#+2{F^U{krGq(8G;zh_8vK?EzfbH1g$!Q3m`A6iF(^HWDn9eQ!g=_k^l`o*r zdByXJ=OdrbmGfxl;^USf`uyU#Tsfb19^UG+Idehr9L`-pGamRX&g|vP1^C$av3~|z zN5~n-!NpV3Qer}4<* z8*CrR-V=&P6<_D*QM5-Ek1oE((W7aPDjviBqmlp3_V0`TV*B^B#}to9&rfeI9!`4; z@)2wwmL8tof_zKy*5aY*VM+Pc;%&u4(nFK-ZN=M*2d9Umw-;BXXQeCCRq3DDUO{^{ z@=CT>bLJ}K;NqFcXL58o*ZvuK1>0*le|5Ty<9|S2&h}c)T$8RtUYjoF|JPPr&;E7k z2ITc=UGe(j4UGOb6mLYnv3L`@;Z4PtkzX#pg8WMHRpdI(jUxu2t<-j&wgZ+2#8MW0-$eW7CA|G2k4*9s^@yN#)4=ohdO&(0`wvVHLOv+{ zU0OwthoJ!?&Tyc31H_w!4us2fvo>M((4Adt`c4+E_d) zJsSDw^nkRI&%Yeq`tsrx$X67vEcNUo@R7cjPwpvR!}bKE5&5rXdm_^Ktyi(Vh~LVL z%13gqV~WS8C!}MFC!{ALpO~J6d{TO3QiHz|J^m^_vx2=>A&q#wgx__4+R6X)G3j`= z%EzR?PdnHu|32N6wzE~}kGsH>E6J`M{r=5Z{mv=dh>UezOv1uFa zacL`UQ?Zq!$ED*q+Qb}l5#QN)^OCf=*qpW?x1?i{$I^qWXZkoBZAYq^m(k45T!u8R zWIPd{7b3S5dlH}K4x5?Dc9M^`w9Ls{THHv)g>xH~YSJEh$ZS5oxHJvqFYZdaIdg2W ztCXju)6=oV>6~4{XC7G2jt?mIrqeikYTAoDj;->PbZTlZBTm|hI=PBj^C}`q+RJ#= zc4AhqW&c|KiiqIS^s4mW;vvN=(?f_Pc_l{=DPEoau6Qu=!Nsf6Ytn;?zbjtDnOCRR zrUw=eDqhRqe<1QfoPAw#zJ48NUYlOe{_D~kkgrc~M7|-NnFetGHznuyH*w~TX&-0K zOm9xt6Gijp^h&ljCu3`F=G^|`J;_Xj_oSQIo<+}n>D}p4atz*`E+abT-RV6Xy(^iI z@Gh=gUc58CD_w!Sg8$FIr+4yy{xW~-P3hm#zq9`iw(UiGIx(G;#?wwlwzHj(PT<@G zT6-GD*;A0?*-lJnaAhKGLTcmODacdOamCxyJGjqSj;NSO+giLWy`3{-(%7`M_zHjV z%V~5P!~Q7RHsolwpW^&i(x;L*=hMhfrO9bj+E#pq{ZFUQCb7_G+5b%X9Q&V5leoUE z=wPed2L76zI?^oA&s)-4(}d!!>21ij@pnaXXQlqMvyo?~bCBnxbCKt!^N{DI^V6&} zo6pWNK6}vx~LtuSsju z1#H)G@AHutaJ-JcaX~toGwafN|0J^#zkr{D8G z{T%WSZ2!plKcwGr_6x}0v;7li{+Rv;`KR<-&VCX3JGQ?_;>lld{(sVMIQu2!Z`uBu zz5hi1hV3uu^NaK=uMtPVv9&%_;t`n9l#@|2Xs4;?Eqz2+7_ z;`|TOkCF)ae~Kww8^9GRm(i$6#?icDL>h_wF@1iNhNlti4`ZtoW4Cht$Eh_9W80d3 zoPLs8I8y#3{WJ|_tNdyDSsKDt`Lp!%G?=aO=jnTCVsQ&kpnHi zLH$0EK8PI5c3{5`rVk-Mls=3c#L*mnjsGbI^c&dk!)XBRBdLGC0sTIbCKZ28|A+iP zZaawuN#kEPWjL@$?_a|45%e_Al@73BF%ZtVnZH!FODN zoSWt$=cW1S=fzU~_Rots{PkZHOVZNx3(ow!_+_y;ElI!R%rA;xvH#2B*Tqq3ar!m; zzbbyi{;!dX(ot!0@xSRW$iJk&B8T?-U*uo;+cWu_^V3Xv{g(aT7QaLOuJ}Fj_r)KO ze<=QlT$Fx;oSzoZb3s~&T$qkP9+8ej9+?)U9~XmpIzKMHm%f^QRD3o47xKq!e^~ri z`fucq*#4mS@ANg~*V5OKKji59#Se8_QzssacdgVk4k;?n_7G)eK$=lzMF1MuHb&kI_{^%&sep6kGoAPzEymi z{cjiFL4K$BF7ms@t;k!s&KW*Ajeh@+p8qd>6Zy^bEkBjM{r}l}?>N1V^3eYrX^XaL zwbE*(m9(pOwd%e1W_1}i+^M2-;Idjf?&YYQNo<4Jc-_F02SF*p&{w}MKz6Jaz zjw+PY341vDI-F(<{J(?JZvd4G)ZUb(pxC6bNDZT@{Y~Kek&s4H`XKNF$X=r4Zq@O`g z)Q|ox=}rGe{m-Fe>PP=h`Zp-rA5eNPPgicz*748WYdr8@$Zw$Lz3};wlzu{;diYO( zZPeWaR7%t)aw9Tg8|7Ppw;<8CQMw&?8zcD>{v+N@K$1|hznn970Ncnfr*s)|#+^vB zN*i|~Vff7!<&T}nG_H)fI7z%l!tO-YXruO`B-6^#??N7GqxKr$)yOw(l)AwD9|D~j zU8H{i{sS1^m2kd`w&=-dOEIfTM9!2hB<80W1@)reLbg>7e_N8n)r)=${q1eY<8Mte zx!T-sqrd$&`rR++J-Nk~(S?6O`U5n&C#nArYJLIl_%fyci*+PEOsG$(OsbRp{iO1%4JSdll*P*-C1RS^pF|`%2PhnDsqe$ybx$ zZfft>XIjfX5Bxm3@M_ZUpjW74uOK}E{1pFOLFtpgPht&NLHbm-2CX>H*N}z)<#w)D z`5o%jpx2OoFI$fG{uuBv?zfz@0!?I1HZ)&LssYLamthxpBwI#$6!<9rSVmf&sLyO9 zJoTCjlU}2=cXxIH+ReSd3(3!?bRX~n@^#$1HeW}o1J=Rw)B)rFC;D&w+19{pL|K7p|f%JU{;%XyAP6=b<00N9#R=^jAQ&#Pj)1rJ4cUX+(;8%DT zkz5~qI;D;9#ieKr8^{+@=c);90}GSQU>o<_kuBr=(tJDRZJE-{#B3Nf%X0Q}${T=u zcRXLfzg*$2AQ`t%cP9PP zf^2>|HQ(g=Zy+x>Q+pPD){Hd0IXerU-vY-!2W??|E>$ThTt0mgfQePVM>BoR{R}x!M1hy9bl9@!U+Qcn-SPR<8Id^4lCF{H+`> zN7mn(tw<6-yEdQ!@#Qu29loH$+x28)(G+^JPBafz1EP!cWa=eaKK~l11ad0x(*`_^ zd?ix#WORhd+)-_$4X7q`GPzI<>10wn`hvQ|Nt8wdPbNQ+QU~xP^3|MOg?8J)^G=|y z1D*B+%IdZ~Nw@7uI&BY@x}Wkc&ye1M70Epvw9(DMj`vgScJD+F_-XzWXJ%vH`xlO% zMSJ*{q~rADg0=>W+8XpCZE9>#+eoLjJoP&&ZUjXJTcX#($KvXJi+mBTNHMqxK@o7h>UZ zmyC-kUxbAII~-j?x)^)d7sxM7$Cn|se*w$b7pT1)E#ULO&vSf5(h07hMr)Y5z?Gyc z@=4hn>5WO5y0aE<<-R7Mnlthv{qsCB?U9swv1}ZPB~+QPG0B8lWB(32?2ozTT}fwo z0jRB3UFO}u7xMQ2-wpf``HR5!0M(ja0=@|R0r?^H#CmM0+9VpVM7$69KI{<<*d5*v zd_UHQ1}qLA05)dd2L6D5HcHu8NxTh6!r!C(J#@SVbh#ho85Whpfk*HTS+cu4 z#Ip{`A0%x6K1BY2_8Oqpo(HJgfQ?F<&;1;2%C%T+25!!`V8^--I1H=D2Z0~N_M!d% z187h8QlBS#64ra{Ojz%+QRSIdt31<=m1l3jo|DraM1<^4>{xlGEi2EoV&$1usXWt) zm1kPaKFt_inO{XN)KYRamXJ>YKgIDil&{80r*-67(lyuuKS}92Y$Kn5hSk#8l2E9SIQyQ9S{j0;C@)6)i(CqbJd>FfoR@)lvxVHgs z%ZFyQnKp{rWTU7}){)v|HK|QDm|AQz*K<~@Ol`7B)?%x?fwDH;+Dt2NZKmC~78~#_ zz&h?%%TsD-pZ(&>O?ULRO~bMp>W1;mI-o7myYH2@!>eD-|Mly1Pv5AXR_m>+Pj685 z)4kSq9=zxN?a#gWQulR?R-*0dqc&z^6-jy9xEJmJ9Z1!#fY7_W3hCKzu&qIJb5{+$ z*~>}o$iCyKT}DY?ww`VM=HW44iwvuOTmPr~c8=$q9`^CboBF!-aqHPOzTyz-*8|-# zKnrxd1Iy*-1QIoYW=qFrmTlts3lt8 zxc+jz<&&t}4Ag?EpIqO$p7Tbe7JcMeO7)aC!BdPa=p`9#pe?k4Yy9q@e(7QGZ+++5 z74@JuFz2;oLPE*w;jgoRvp6?|T7Bet$Mvqe&PKbOku+0*S^|x17HXYyFIl5eYEoHS zoTCyW<(N2njzmWqHFsFm7NJ&UJc6U=sJUB;BkI_UX1p9jN2NWDnydQN%GF}VrIAu+ zQCn9NF#s6p zbv%00NI4oxYjVapX*?#UQOnXuIWmr_qv8%>j-~X_cnGB+M@p)ueC0?W0q*7N z*X$iT_m>b8+<9Ul18mHjm_dTYQxjmEJ~y1sxs-P zBjgSUj-n&v>PYFQqvo1ODW{{>kVa*08Z~7jDWv07&j?8s9Vd7BH44dbGAbzO;Y^Ml zDJi3L&ykXDN);Wc94NJHBOj5D#6{P8dX?166_x&5+#L#(u8P?;Kq;yiUkjAJN>l5A z(qrdFJy0pmnKKM%?4UEM0cZrKGtDUTSf|=WFHE4Xni+3<&aa=eQ0k_p2`K&SrsQ6! z6Q~>FdyU&nLq z6P)R!C$6N%9dJ)Tw;j*9@B-^+bVoV&oO>tr&*b`UJCdB;iA6@Nb^qLx(00djh5He8 zBw4%@+l^N|NBy(N?;b0`cP86x2YT*!&S{(NNb>zDKy5_tqW*a_m=EWtq8S)tqO~@@ zL8AsYfh)Aub|gLLG@v%8GssU*`p+53|1lc>tTXU`0Y8Z+WHc7e>A?2nrx~66wiEF4 zc5%ft&a`7u8;#{t{bT~Z;4aS1p=Nfni?%1tVFI42F3!!Reh#+Lsr*Y1?*#l+U7VYj zJ3r@fb}pLM6wZE*`p@EN`7N%Q&slvw7twMxvG(lqoc&z>b_zIX+KS$drB18lBF-+vrlcOLJ?TBz>a;#C=IkPT znCi6JoLK2^1Cx_0Mf9}V=3syQt)NqmvZC+w9!$Sn(3%aos=Ec z(LhIKYNMlwK-dD@LTj}hjKTuejrVLK`5yqg$wy{d7})WhvvZQ2a1OS@v!EJha6C6t zkDi*s&`2j@pB;&%Rx9wxOwDy7Q8E*=tCM$>_$X@Y(NnFx0?k%_%$~$pBDJ41kVay6 z^g6B2BZ+RQaQ1TE@DG7kaQ)?^Kgb)CO{S55HK1`;xb8B}|6x9paaaP>E;^G|E(Xpb zUyx}TT!2mR&w+o=7%kwvps(Dgk=U6E+UlFR#~%WTk>!(kkh_ zw$z2mjyVHc?Xr9Z_SxmYnH*L42VNSkzX|JYh4LaIxc($xl5=>mnfA;#B=2;x#^ybY!_7do@}8vi_av>q zCs_u1lHH&u*$sNI8|=(SB>UlrWItrRJN83%5x{=PnrW=3BQou&BQovHd_$KuFX8Fx z9@L;#?G_?wWA)IA}N+~R_#TL%Ti*59>8jSXx0YQ(zrcEVN6OklS#>DqL#5U zZ>1&1^=sSw4zLwZODi5uV{9e?Ct+FnZl(qDyU7arU9R~K7X5E?)nO?X=rAlV_oN7% zyRmOg!d9fkzZI{}X#S(s=AL8=J2F}STk!&oPQD)E}QBthx~W0 zI6qfXIzPXF{O8mS&(6!w&yB6s=h>2cp)JWf+LHX~Ey@VNb|^H%X+w%RPSw56>sL|L;-ryU7pKj6|jM`$cMgFZqX>k+778 zm5e7NdG%&z=hI2&0FB8uhEf^ln+fUzZ%SVArsPX+N^yxz$+x9vyeWCcoA6L8{XR{4 z3NNBk?)AXy@P;ZOzn%2OUCVXgDZ{yQU=z4`X&6}>pA}n=^c1z zujQI+NbB$_D;3{B+L1LTKXqgBQ#U66bz|~qHzxmiWAdvvCVzWl^2s;S(x&8@{Sr_g z>pOYMGx&k8;m$XLJF9@JxciNnUJ(7ZU&cGDul8B4SPxv!f3BkZEbwabo48WXwvkTH zQTHr<&8zVJ>+k)2pdQ|vIeQbnPa^{KfIgSJq0a-KCz9Z?6iuK<^IgcG`q>*u%A>!{ zQA6_eH>4=dhU8^#NM7cKZP3H~OL4A_T>WWYX5Bm-7gA`XV7sDoiC(qLGM zF34!nEg8`)v@0XsoGDSer>)Yf616+f8N*pix(#?6p7+}1g|AH>`P$@vuT6gT+T>fW zO@7td%I?{WxN=0p< zBWov(0jd{_BXz=W)i2set|V3$P~TOTYNJLSS1q8OYt;hW-%?Fp9ao!^dcHfPyXx81 z?v2#OmylX`A2nXrS`$%2$<>7r+SJc#ui6fVlGGgB4O4wrT}pkpmjC#zN&M@;VI0*^ z3hQl!7ONGu@kZ^bm1=>?rz1$VT)ncDq!y?a;yy#Zg%Z8(ljga{XA{sFul}J%<6F32 zkGuAWiR!ktUtCk-u1{}LPpi5pEC1C2?P(>dTA-R=4|xsm<2RRVy>F`iC(Rm?D9{i} zV%ubnwc_MJX_Z=_wiPMVc2WlSkv453xjWr-N?VXGrUSJBY@y@|p_!C6A#=?HYDL&Y z$rVDgDQ!TyoDI~{uz}J>Xvybp~0<}!6r{tGc=2KdmX}4I5gtP!SpV~E)T^ppG zV>QX$`xa4Jg?zIJs9nVU){VS&k97CvTmpA=r%tUaOBtotf_oF`ksRC z>GK}?TH9J*3>-qAYAq4#hHzysS)%IJDTd@`v>>@GMHF5E@5C5 z_nas0ALU#saM) zgm2O{X^8vxIs)RC*i}$MX`tgJ7bHIf4cYUhA?Io#-<9r(!|q5D z{MTK)q#*H{3hOb6+2xyF116yOYX$<4NwG zSIBrHDT|M-q~aTt(!hfAHgl#U;aMv<*TFsf%B50LGe>1^tF#xglM<8il$fN|Ty9pD z{lq8tI|?c%KG!D9bf=q;qk0q8DU~Z7?k~D`5cgg$+*95wV_@hS;@n6uOAcGmH*s$` zX>_7>Bf*8Le&G&)?z<$v7VGp;4CkmX))km0{fu2H+~v}}I>qGJK|Ex?I*ygomEy%o z>7F=NlQ2*jPpTL)pK|>{-0Pp`{yOR!BNEQYIa?F;QHqu>wI_-vr*%ZdI~B z6B9KJ36scR+NQ1|PAmIWsF5NXmlc{!rQ#c?gX*Cxc64>u)?%kucWo_pfOXf_VrN)) zZFP58Z5!Ha-8EL5hjA)Z@1kDE*soRp>Y=>xDBvh+x6?oEz;=%PGUjOD=%k6NVQ(d= zkE&sBA*qR~VQ(g>kE-8nBB_b0-)tnQkE-A3Y@XfC| z%YB0mj!0NIf-_?h&bERV^5tfZ#{x%?t7o+Gj(sIRdAahR{#?1b+_#f46PGfQks;bK z3Ti0L6@OXl#reVtQ}E!hwrJldsG+tOr9iD1J^bS!9sI9F2g}@7?z*e|7goQJ0)rnH zb{6?|OTt$5i9+KIt)sBKRBe2rZ#3|qz(98x4!Wmykuz(164ogNs@2Ge-8ERQEUi^8 z3|boWS3K9|B9)a>tC{RS`R}03<@J*P!pbbxh2$3+Z*a=sz{U5Iv>N+m%dtQuyosb( zl~ZWHfqOl0p$@RgZ(~Xo{aQ=#P3_dZBz4-rJ@w$i_9yR`<3-Gynr(3N;ndZT+`Y$G zXZfd6fH+=Dl6T5+57NE=T68a@x3Hn?S<7vQqbm6o6i+N|A<2d1&MlPm4zzMjXe099 zO2Uj5xUAm;5UZ*l4z&(BYhh=R&-!)xDxWQEeB$Sxc&?Z%_EmYVw!nk9_g@Y7Vs};} z=9GS`Uwja+^sK2DC<{vomARD4lzWxwnUE%#EbDG5iWfF~WuuKMh! za-SBU+Qd}SIOJHhglU{>0!}5L4wV}L^qUhiNPhjdjbr^tu_Be7xvOaR9N-*kS5wxPZrqjLdL#VnY1exCSWo^!dR%Q}K5#Pm z29AdS9fJ+jE<|rx%9R^w+hX8ijyCcxMuQ*1H5*Ao(Q_u!?oB+~nA(-(n|bO=^dkLc zTS!JyY^HuIeQB(;(bPtq%tO~wW;&F#j(D9zfrpX&isc)~jg8z6R5Lq*{u&KjOWhG1 zuO*&x0i~lz#$p~zjOEcpNghjFN)e#O zw;e_K%oO9MxA7dx>wssIpUb(kfyTd`2j(^c{Z8=tq+@~SrLwDEFW~4nq6IGiUPSz) z-^Ohxzlir+16;$=rM%sVtdl>HH@%E>GO?Skw7r}(k0{TRC|yZu8*m$McNOVK;F0vf z)x2R3@HFyk=>KbhJ>=K%&ZhxSqvm@0`6%E~w0H;4n+v>z+*pn+z`5i*C>c{>q@uAB z=K*gfzXj+%0JoC6rje(D~kC$0rvOCLM}JQQe5*(3DIwZtD>N9oPLM~P#&o}PJ(bPf?7 zH_#K0lPbi4+(79qy!ov_cSU%D{8r!%x&?R( z5i{;Ka2xP8&b*x-+X=jd{O#1=0=$DWZzsKt*ql2kJw@6HbYF$1>Ddc`JISA>bTRNL zj^07vod|pr`7;TJo}tI?CH}>)j=qyVyMkz!2k8%EVb%igCx4Efc^G&#nDQLy8e&|o zqc5IkW*h-Lf}?j4iQyg^(wcWcE8Yz>+UGs=l`$HJKuO*MHCzDH3h^FlJ-dMOFVbrj z;3lZbifLb(O;`njkiyXZ~?M=YPIeIVeb_wuy-tWD<<;6hvyL&IS zw-br-4&qSW$NRn`MWx&WyoaOr^UiC4YdCs;+C9WLm1ij5lj2sM;rs{ak$J#(l7BEo zr+kp(2Pi*C49*8RGcQHte1KS-4^j7Fde7LL2kA9;2U!bTOWjAnr>lX_(T5+Q^c?VE z>OM-(y&3o@c=b_Aj{=RI{3yq70G`hIk8*rEkwDjjZ670@19YE~kEQ6BkI{$MQ=U)V z$2d2i$f4ihO+QXL5%`-NeVn)YP2h>-pP)7G1b&G86SV(Bz;}{YDxo!KEv|)oDZ_VS6VDHBAF@F3|Bwg{^8euf?j%u20fXWH za{hCY6!2R4e>?Oncz(hErFQ#||I7J93JA_0Qox@0|HX;_2j>qdAozck^M@=DoIj+1 zD*wM29(Hkw|I7J93Mlx$vd&$kU8R86m;cN8Lkb9?g&;Ku^M++$+_`jS#q=5aw|K0IDbe1gW>=3_JZe! zED%yaNCZ_Wpvw7`0)q2j4Cj~sU;Lk(Kcs-)fV=O?|J^sN;Q7J-Ln1g3{9m45@PB22 z{`tQ=zu^DM0tM#}DZsebg7b$gAmxHz{|`y}zuc*?0tEkmA?f*j^?x;gtphK>>HE|F%Thqu7EtE@>iLBgpsfFE5hyhO zzWl$+=L`KmECQkbD+?TW{lBdFhb!R|1a}@Ei8pCKzXaI`D+ol{+D`we^!8l z`v30s|H1SB{cHc<-SQtEf&Fd&FIxc)g#JGm{=a9=A6|g}zWl#G`+w;F>imWNzkluj zW&Yov{XaDS@B;L;|M%7Z``Z6Q^S>S5UfBQ3{69EZeP}u*2|Cc%c?p}b<^ZT;` zyc+)xp0BoFNC8zZz^|JBSG@p*{vSNQECp08{|EX1Yw`adX#TIKtML3U!0+{H{{I8b z|AX`QwfvX;|4We9tN#Bbl=s#DU*`Ye`Hv`of&2gWYz5dC{;%ghq5yXF|A*&4q5!H^ zfPv}%;rWj!fbjo^{$JJn!xnH3e*gXB{}29O_57G%v|MzGA zADI7tZ}$J-`DH2KK=c2y|9|lOU(bI;0ldEc|Iq*S1@v$KFZ};{0S4p$*XLjO|BVIM zlmGwK_`g1XBcb&F8wId;{XaN=ISQc6`NJ1r6hMERzp(%J=l>5rADlmI0cHJPzrcav z|5YzQ;qwnZUycQ+dj2CKpy2;y&OZ?SKRo}{Sb$yie?9*Z1yHHD=Eog9TrpOB`_l+E zqu3*cxaOe$AB;7QcGvj7z5D-v-S~gl`TO$%g#SMx|3V6Ihpqk1|Bd{MD8M5A&&a=s z0(`ajKO_G_3V5~nzcT+f@-L)-UE}}C{9n(1NC8FUUqk_(!4o42Fk=47QGmO~|7rOz z_p3q<7K{_y|r+43KLfj#m6;QV3#FUSAAHvfNr z{J-q~5B^{E{J#r}w2^;>{eO4E|HJZM=Kp(-|0_rSg)9*9e_`h@>;Gl{ zfAD`J|3V7bHU95I)RvTpwADlnp|MqVG5C8w3IlmDBFZ`$dKX`sb0fZD_ zEI<+SSB?Vg8~+#lz8e2$oW84r|2xM24L<&V|MLF>9sggp{P(p244(go=3iX}P(=R! zYW4qt@c)7M|NH9y<@o)vuJQl<`TxuOe<1OH!SnZ*|Gz)}-`D@I&%f~h z@16e-ME?(+Kdb<|bN*NzP`vwt&Iu{}K6DT?M!&{eSQLzd!x|SH=I! z>;FRA-}5TK1LOZM+yDDp|M#on{{vtDSGNC0{9kny;Qn6!*B}2MjQ+oO{vSO5!0G>G zpMTl%UzG(8y#4>R>Hop`<@T-xGzu{If9U^JYkv_1*x&lUgZBUb_tyWH{r}+wI1urF zeb@i%`43w_to+{>`+vm$8xgQ4|Nk*W&L7Vjde{HE6M#Pd?6zu_M5N;s5=`|Gl2;{|2M~S0n!m`+wi~ z|FZpG&ws24h?W1v`af6x$11?ry8gc}|KGpy|Dpef6j0XxBO;DF$|A*y2tN=;@h5bMHzg~b>o1yJn#(>MMvcK)eG0T!HpAp8GB;Lwy|L-sRzdQfj&+aYr{&VM_ zi2Ms%fL4HA_x~A;{_o2FSM&exU;ba!{EPj6%KU%u{{QOEKd~3kp5p)1KZ~7zs!;&d z{eP&Hmrt`oGx!uRs1j`2GLN@qYu+ z|NE~08(94R-uVBocKv_Z{@+*sukHfa|N6hzC;oq5{r~%y|M$25Us?a}kN*d^@4Nm# z_65`nuqXas_WYOE|CMb4q5lsg{;#k8U-tZ$?f=ys0e98^`)dCCy8mA_@-OxR+?V}- zLgz2@f1@i4DWEU^51aq)wt!vZ|I7RT9gP2ft@{7o{r|si{J+fk%TWMj{r^|H|L>kx z{_XqzKYNe=uX_GtFW`Z#|LeQ|Z`uC;+Vuab=KpH@{|qMnzpVccX8+&*^#8%c|Aps2 z*8GJm@Y>@4Ut9cNf9wCMoc|HLA_Lw3x9|Qx{q6rd82x`B@qcCh-=F>8J*4-v|8MO4 z8@m9<{=fbC|NF-Oh2|e#fWhqlQ|A9=o?ngpFXI2o`~Q^f|KaIxoK>;hbk0^D`y-#thEhm26H|LYt7zpwFsyGQ;XT>m%N{eSna|L?2) z|MiLg@9PC9^Zx^3|9?H>|HJYh{{O!F|Cjy$RViR#{J*dNfA9MLK3g58VD=*8ltR|Ni#>E%X0~`73_~VE0u3 zd)oh}8U?Vw*Z&Qk|HmqTa{Pa+_B$l){J;Ay00Yzi_bder%>Lh3{|}wNzbF8$1O4m& z`^x`!=lmfN?0fuw@c)SXtM2(*L;;rL{|@f|`|I)jpITbV%zXB9r z{y8w~|NC42xA*n`)tJBXSAb&8UpWfk)$ITMt^W(l|L$J_+Ee`h-u?gO`2Pdp{~wJ0 z|N8j<_5AP4_kRY?|I6S1>AU{FKmEVI{r`98{KfviW&3}X^B3`def|ICmH%N2i2Z+F z+xq{3`2Y9s`v0)`$0~rZ1%%JP90jOEP~HEh`sJVS2$bXh`qTe||CfCM)xCfQ$N$UU z{|TLc_pbmI`hR)-e?$RS@d&;P#b|N4IaryT!x(EfkW{(m69 z|5uLx-~0Ffg8!GJ03-fy;PL;V`Nt}Ni2pCI{~JjB-|OZ7ug3oy`R{lCj@e86f5-xQ z0S3qa%l7|$_5X+czZwOwKlcBR`2X_$KN0`0Tu{XS`{lpb3#kA7fA((wFUS9t*Z-CE z|GxhJkOBtt{hu=bk1zj)=3o5^(7vz#A2|OH&cCnme|`1;!TA4Q+xP$a+W$i$DD(fm z@&CK;0?_~W|AO;J%wO>T*b%7A|NHL$6E^>d{M-Bb|FZpmch0}>@&A4O|MBI&hyv*A z|KGC|u&e)nU-^Gi+9PlXu!(QtHu6Q>8g_>Dn}L3l*DsGZu}e@R=W01>1p2k#I`Vps zg+tS^`wF_Np!*8B?!a#i4x#+b>|5Elf#1%)k$oNb9pE>}zefI@>@TywK`-h~z&;Ee? z@3TM2{+#oFLi*$Ed({1X_Hy0{LY5ct2yKf>{k@F{%+_;G4J2K*#>M%|CH|C#+ZN1q^l9QZ%U z{|C@-J${%gev6||u-le9IlV|-2Fy5qF@3@E-Dw2et1Bm}`Tf+^ zr?~Dq{B8GBeu!%x1o|D;H}l2J$BFBHoa2W%dYrGgy_wRzTwBjqHXo%tjH7z?P`!uz zHqtQQu=EvHzx(WNHp5apdjnq?c@tONPP&cNX?Jtf$e9Mdyz(Y$@1X8Yth2g{lJVb- z?A^YT@|BdD*n7vX<6K2*1U6E81*wVeS6>0V9N0`uzTeZmnsgO0QF4iE$b~mhdmZI# z@Yi0>m9EpfhA(4ZM)_Q%fy;oGaeOXG+k@YJ_e;YqX+Of@L`l16@Oh+jSyQNXbUsPT zy(_t%MpA<`#7L>i#AqUp24{j ziBvv=Zw{SCeiG?K;Hl((XX&K0&asUhdQPD{lA|_Of*eEXP||jwUYl){M*+8!`?cs% zeEZBVJ->l;Xj=dIM)rw(Bgcnvh*OAr&H<0_q>~-mD+a2j!w(jTP4xsa?>i~|y zrZ7K!nR{;fCiq;A$M7BQxqKUZ0rm5N%gD8NFXJnr%Q#-h(K7Y{UqZ?6c8_IWwb?+e zZhkx5Z>jgDuafps-$}WX+8)w4_8IO0PUh?2vw*WWH=eq2>1*dR`KI_xYNv2ClkeqD zr{s6n$MbdZX_Wo``uOxccE6F{MR_1JxlHr>Qv0Cu!3*k{jnaGR|G;T}+`kFhk<*^w zCi0P5k{m?dQt%M(KP)|=fn1LB>O4g*B|nOL`0uz&!LxjZJKx%lChk~n$3X5MZ7#n> z+$Gv>8wb~Zx$Dr>I@=h$H+sdk##{L;d&_s**Zzt7$9?+VKl-KU_2@gFHSqqAJI7Os zJ}I}+dlt_P3Bo>$=Q=J*3ig2Z33nqFL!|ga`Jej~$H*2fjCOg?qTiygqK9I1eOlaq zAmiKL{l(D0q2gI$ZB4?WeYt_l&2+o#R~!T2z&69dF;GD${O;)_1@+ z#*%M>N{EptcTfx**NcML@sMUCR{< zvr1)JdfqfzGnF3j8PiGAcx&%FgCqy_UNcEEcrV9(R=UG1N;7$*I*#Y0r_7-&AD61l z1-vAuNd1bMo+(ikkm*m^}Z4{rnoo8%I zJz@`3DA`l?%tT7|pgrcj?bFSvf9+d)+J3jU9RbI~Q3x6`j@;2YB#ob==14lOj;15* zcst5tNNeatN52DXP%>Ua9@}gY-!~UJuerQ z5~s!C7E0p1ST626AH;s=gfqlh&`8Po;~a4gIiniMomWBez z5;izvYpHhzJD;7u&g$tvDV<~N{CCz%38V{BgN!s4ZN*;kTd`x%UF?sONvELo*mK8m zW(@kyXlk`Lk41YrjqWF=^USh{&O5hC!s|d=X5-!GdOb=@GP{e z6RA51-L0MfAItwb(d62bR%hQIPF*KZ96paT7Xe3+pO;4CP|l1)Q*z{uCcg+x?xM7p zjGEpXIeTc*nhpmZiKgUU`bVM_j^tYR;vbJTIFjQ_(nuag-FUPqaq41fE&=nzwawH` zKx4fM4fZn5Tm^KrFC$%yetH=-my@ml6E}1HcHjn}nCvS1EkLpTTK;ue!jNmhUFVJ% z+=XV_$~iH+8@;!c<24+K{cC{Y&(&zhH=-3^58MHMi@k>=d=}T&p&buT8uN`@aUG=_ z!B_d;O0HVNToRKjq=^XwuLE9}R;;%G#r_KV{GI6Tet+$D=Ak^Y2drHUUK;5puHFpZ zi`6R5-1Bs_Nx%uAMq`+@g!#Z1o3foeE|dMPaiF5>Qu+;L}`FLzHZb3rlBH*4l;$wg-h>6EfxEvc&B2{m zW}f2uC$XqJ#cY|C=8Us1=U%hZ+vWT*W^2JK}Lit1)L@7q; zML8u#aWyq^J!z`AAny~m){^9X-ISE4y1^tRDsY!ihOVeNm<1?F_SbS;j`8Or8MQP7NByQvQ{%tSxt(nl%fO{G}ZOa1w{?|ssuF* zJX7{kcB%&|Zz)UF0hO*6Q`TxBeO&_7rXhWmqH6I_Mq9>s4*@FAO-WcXg&OT3%414z zbwDMyg&fxamD!Z`>Ve93@`f6q@>ob#wsam(Q(AKl4COtPwL)H$#|+^u8>sbN8-Pmj zA!Rya#aE?LCC?0)fhjZTnI>Qp=bXvCK;;m7v>DjUIp_E!`dc||I%x)&v?5{F3QE(c zSDqeDN!lWoNoA%|r~KVYX(Dw>K+>2tj;8=ekavT5tAVRIH!{sur8=ej$>2j*qHkSX z(+y6Hq(&RrRxnWxK7rH)-bh!K`L=?U(!lYg3E-C2vCu|B5>O5p5B@1dC<|@|Th%x^ zN#nrL4(iosHiEkws8zeMEN!k-w$mczl|xg@?4gj@wo)o2xh<3m32$?H-;n$^@pgqo z=sc0$D=j*Igi4XlE1~*N%r{#*F3m%s(&*aMDradYeWK*LCbhDVYL#e}V3b;vcUPuf z(B3zi@v@IrP}k0A+MCNc8pVj)g>cKf@iSxM*Y@11W zMw%tl(`=Z|Q4P4I1~V7UU+d(8eG2V6tGjJ|3I+Iv!|WsJhwG(J+prPPHKxb&Ae=;%$L|JqUy+MkDT zCPui69vwlAlx#8Me#kGepqrjl=aH%{N_ZETGLc?YBN8_!(yR8oUknW{E}yjjd#I6H zi{H|}`QZO%jwg}Jcjczi!ue^&$SK5KV+N#%j+DBolt%if#<~@_mFpa*;B9m0)5+A@ z%aa)=IiK`$He=ze9+GDq?7Vusj1`Yh&sB{fl8&0-H@zO2_Kn9 z>NQ^DU4;I#QfW>&+?*(blxiezAn$4-HPb_4we(7jX*lIZ&Nk7n!#QrC+{jpTB^;ap zbgZPjRYXXv|ojaFOl-S?WfgJ+6swlPM%iB36|(kwO3UhqMh zr6xKlVMqlij)*@KfzmGN)Wn2u-HA>KrCHJ`p)^Z6C6s0-v&dt2&_w$wk4#01{VcNg1R7)eKA5@Xg4bQ~Sy z3b30q8TTCx6bCY{>i|w7Z%A+5kout^^;iRUYo>Lhxp&T0qroOyD?W;SVtrw+wKr?h;Q=mA@oqpT>DG=QI`7Cc`XmzN}U`^ye{UxJuYsE=~6gHXECGY zxX6WwXTZ3j5)KN<5d{erR zl8Ild622Bx(|NusVQxV?o%6~i$|uTu1s#ElE#u4|UFP zEw+94yt>Z5&~{~a z? zl;gTNnn3EMxAe;>{pib?z>&Jj1n7ctP6w%z@s{t`Cu}Jq5!FGQ6&>`9vdzeJuaT6j zG3sU{rB0}bazZoz9tKnbX(ma1)D@dKSI>NKb|{68OcYD6hTb2wuN;_j-F9FG%&?qn z<6k*2PcosDXDdmWP^oeYNtsX@vzeq!SW9VBqD>ot%7o(WhJ?=>C~ss;hH-pIqH*hK zTLUA}!1207CD&1-OelV?C9Q*hN@3TKlnJG`t4Yd)Qr%S~>4vm-C2197E0(Pw1>Fdr zqtamLBOw#2rz|B&H^i4EBq@ecz+#egL!Q5gq%utO1Bq~lm?~J^GQmB@{4&S zWkR{fT#_=OGQ=E`(x6m&Hc6SVo6@YrO=bd}>1qKpfa=vfcrSZYJM49zv>yRvg3SB4fFvYb-3b`fRE&}h{uD)h3nC*(TmOxUv)(tFBr zG5eJv!{)V!zOCxLQX4sf5`CflN)tk^3>i~xq>$;PFkxR?$~cBrEFBO}!UngDu`cxF zwct!4T`mV7LUWcXNMXX3w*s8eN)-War_?&*9CKzl`7 z+&Sj_a`rjXoL|m9`=$=4{YDF=P%7X|b7ndFq=hll8ktkhyS0ff_>PUVSPJ1Bb7nd3 ze2W&^Cxvj1IkTL1wz-wJlae^c+R~f0(ht%UdqZ9v_O`H4I`5W{VvaepoOjMKXO^?i zvFl)DrG$=e2jeYGl;aq|C}mXV9}C_{GsT`x@J?Fl9CKzl@AMQ*06V3<&N1hg^G*w8 zcfxX^wA%SrVJ0}^oNqnM7H6FEZ4&dw8RvZKWv)2moNvwoXIyvDTZv04s}ZRD z71k$Zu<;2ymGY#3+M~p%MtU(~TlC^63CiimlJx6WIA=dM0;SrH#cFz|hkOjC+P9h7UOY8m~n-%Xoj#u#a< z)P|Wcj`M)pLo>#D0nn(O;p8pMgDjPXfNQNheFVQDv?Jrl*ckh*j$X1?3YkQ@HaStf zkh$f?_Lc7(lDcwwBmF#?T6wdP5EV)j=$oNwOlyG3)>>g4QQ^pO;16m1&;RDK!DSa&ii<0u*RF$yS`an>6LBBvO`zqKE=l8@nvR^I6lcK$0su+vk(y ziqe94B)OtAVlGLpDD9X-k}FD0W|QQK(wbQ$EhXZDK0_@f(kAgrOG)6J-mYnkLKCow z+Nt0|BT!j)3gguPY~WbCw>UD4<6cIy9$3%uB+BB4l(YvZrbuBcjB^c8&1oVyHxxLO z=aMk?fBJ)Xyh%(`zwP^{`9Fx`9%Tn61*W zE_y`jqQ|cn=xhzjCM_G!*yNni7r2x@nnTTO(l|y@>|ah=Mt_Na(!Ftvv{Jwd(sKGv z*+qWe2{wrFD@iNpNAXm8s6C^GTIt~!`l5#84vxmqr_(7pGgbkmQlqKspeN-O^`y1H zI*!`u=czzxXFF*$Jzvk+QPj6HBJvz(?OHHFs%ixNWT5eb1$S!Tnl|e763DyMVAg{n zTd5t9aKD+_4PZqRc`G%}L3yJR#0H?8a5y#2;+9l)9t=-2BY3W}OetnxIj=l7`0uWq zS1b$u8$37ouhOk;m;cIZm1%?jipBPYbiUxc&GesGU+~|8^A2ZBoFxVSEjaH8MzufA z>nxPY%YU7n()V^Su*`X5HV6N8e#?KyfUnMeF?lRFDpe4NJHbxrgm^m+EG;;?wURn{F0=dD!qq}T8k#!l+T*PE|bzbn0`bH-ZouW%3!6 z8p(xnQKJK90cUYs`1gz*2#aq-m$h&tCdpm(mdpc&w^8oeLTx=zoN`u-pseJqrF$V5 zEgz6mEC+UzM^vO*-7@Bt@d#TeEd|O|lv2BaM)|1`t^^vnvW??SK%+^vGdhcaj*?MT zOMt7$59PmGiP`d>Z=htH);9io7&BoNP!FzaW7Yy!@t?zK-vXfRJe=c2M1)DzjvyTh zl#(4mKh_WWP5N~V zcQ_Jw1o<)49zh)2k=*H6(ow|09h;zcJdV;~M8zG>y^iPjaN^;Prq55HpXUG_g%cC) zJCSi3M!B9lp2*#f1s+3w5~bsSCz7Ac9gYVcM}7+TIRWSwMU3b>0qE$T%6(@8Par=H zJZJ!lAE$ALlYkB6r*nssfyVBgLFstl@!aD~(y7GloyvXAO89jarI|$JNkd(U)eJn1 z|D8=b9oWRtIh0OLF@2{4Pv&0dl1>4hlgi%ryma65D4m*O`OX50+vg{|KA)$}AiA%G zJ6-_RwE)Gw3phT9h`)2Vm*0>(hqyoQbrHvBrdYspiP3ZA*ClDzT#{yu>%pcG_b0W# zH1UE<`R|34T?=*@rHhE@J1<4|8F6?8M;8OV%N3N)Clb*4dS#lAS5iBL_&;T~tC*`J zfo5f-Zx`_Bb*S}p$F1&(&UrV}@n7k{w=XHrrTt{gV(R@mM*OOc! zr|fqSHzg`{Q=&{aaju6rKBdQ-p*S7D z(cJ6ibg!E!T}?dT2KdS?aJmgZW1Vl|3D*F9#;v4lfj;Rr?sgOKCZ2K|$JY@#cr(}D zPPzrCEO2|GeYbPGp7I#Z-@!d^0p7x$?tp6@0`$IjCYpI?x~~z1H&SyObvwDk?ZDf) z!%nWh1E^H86Z$(2Xyngb>Hl|e?pDfoLU)Zd6uL(7Zm!%3RO-1Ksy+dz%yl=lcTmc} zeB<)NLM}IT<%V=Y8aNavU69_@0HqF6zFJ@%`G_>Upu6L!PGuTf>v3{gq1j8SxyS=TocCE|&*#jq99!zR?ebH#z4>PqKZg zU%7nGft0J!4!ictK>uss)zcpP*R~BK*HStp^@P#$w#-Q=Z%Z@}bW^r#LHLUY#{@3yJeeHY4$G8qHwLZ^#*&gp6F)*+8zXBfu1LE1$R)|0L zRJ6!?{XybiBXz@g4@X6sFQ>P4Qtvu&#I{Mp_3w)@fhT(Y?HRGfI@cN4N4`x1&#{-B zHO`%(9A%WE1U1NPXu0o74T8xS!8& z1UB#<_M;=@=y^}aswg>n_N~x5dnNiv%<_LeL94tih~D)1=!v`BqnMX*g;&Okj<|#O zl}>r*;(7LdK`#OW+EbsjLQm|Uj3+BcwnB02#SW78o~A^BMsp-5aLtH#FgEp~u};mD zn>f?SxfY<7BV(hqK zyH3PaBrVicI2SgQ@mUWot_RlhzaHLT7*PAzB(SIrD2JWI)uVt~PI~DP{UZ7|d$~?O ziFTRE^pg?TV%cQ=Sp%FzF6Y*EGlYCHCGJv@Mh@qF#V>nF3y&BSI2ALwjw9!+v&w$3 zWsZfdbz~ePan^b6JP|{+HN|+fa98b4#@P5C`gV;Z8~Mv|FrLhHJ!8}RjZOVDma~q4 zcXkBSKdOCiuWM%#V<(W>>5J%f$Dx~Z`g2|PJTbl3ME*ODvg>~whp|BIM)qMR(DBiN zp&dhOWDg~K-JUVRXdG}j`6NpAx_#q{?C#W`oy z*?O-KOT;fJL(pI8pww9W3vMGVl|O5tw2k6(&~Py>aIsSHK0eVmi92~m?<;k;zXKno z8op25$2-fTymO_ZKQAn!+G~|re7jLxA^rx{c5XO})Gx(u-$1EIYO6FfoMU;waGvY2 zy*ZpGdMw=<4)nO-)iI{Q^Xw^m#&eEqMw^09`wr4D>wTk~yTptV1A+&|yU3kwff!&f zN?U`E#$A1aZ|qee{Wzw2E4^Pc$#=15clCM7EyI!=98oSQuN0e)udWoRB5`8tj}fa}RO zrrNa}k50BOWA=UiCelW~~^ol9vH@I3PKsaH?c)}}T)5>0d|#}{DlSemrlk!X@j zlAfyF>MZI;qD?MN+N$2KGdXSpo<)8!HjYKWMO<+PwIhIMl3zl-`=Mx+JDu8A;2GqX zCfnSl)L(+WemeET$(6Wr-Xv^T^3fq^=cjQ_%yE`!;c`Z)g`7&g)`1o@{8NDL&@Lx% zzn00Q%YkaXlS%5&S^y`LE=_ia7C6C`Xt!$8M*t^tG@a6sz$xT2C>;g#3p6uGM+4nM zMXT45X!FHdFZqc+K5g{c+2(PliCIskwN7ig)Kts8`nB{>z94s#ZWtF^&ylNLjVYJ* z>K`};7!l^(95vHkXSqAsHz(UmGggx0DZ67#GwDR0A%03rq(Evt(!JnXQbYUFS)g2Q zPlmn`^UnVinpe!Pp&UE=f?~$3EaqIbzQ1b*a((%~<#PGI{guntm&@hrqu%$h52B~l zNZeV=x0UiZGIG|S9ZFY$ablNpv-~x5Bzr|FE^W0}#YFE?Nk@g(W-@muyg5_o?ZV45 zmFH_&lIrON5`(1Mj%;`x^%uE{Opd2@Yk0Do=}nSLYCRLGgJ`1@s^Jt~Dt%L0P4!l( z_iH;9s`nS(E`3}R6LruQ8rJ4+sDN*_JiXcS)Emna=DH56hkEg7Id7>a#{O7A8U_@X zT?^<6z~!7-L9MF;Cvjw?fDuaC7uIlRM=>4=~C{VuX4p}wqo%I{Q_t4HEz#-JRpH>Y!YvmmOCh7fY|Ev!( zR_@F78P3%LKS2H&b`JYM+FR^1?6~EAUG6DX%iditvESB*fgi%Y^Jy$cer@^FScg8% zu{%$F8tah9?l|>nb_;unt3L|-2$rQ!a|d^s`ZT+Ty+rNDx${fFmpJ|e<&U#dSVqa+ zr)selxpUZE>^xx9@RwOznm(kDReoiYBC0>~*@k*{-0ZuLAjGSc|7{350g-U zrs^YXAsIKI&(XQ;43?8Sk7onr-Yq138uH=E{Cgu%@7rY3W}u$G$s|3AddY{wRi*-` z@}E}9dON02a;@SBc)A`bJ&tY63Vm13jnHJ(ZS_g&#T><4*Js%Q)Nen9(p#9T&CJi< zwCY!1OC4z$P)bzCN?%t4zlEbZYSl0vr}PBUL=P*X$5Fb6**cCj$&YjHt*mT*oR!Rv zQF>e21@7&@x3Rj}{okGfz8&cPZ%?P4;htul@gtNUq4pirJPmXYxo3dxKj&_9?*zIp zo!=0D7U({8?l|`x>Dlag%I<6D&T>!kRO!%@z;{veJhb*njvLr7?@4Iw3zV8@?L9!L zO%tVif%kHC6X^xu3tXrE;_C3b!Nn%hb-?Qw;U>}s;08vei8KW`g??;GG))<+hhFa? zSAshZC^vTJyh;3?;Ea3xJqacH5R~MDr1vqyr5c|i-2uEKyA$aCb+%f`RL&Ffvz$js zRf?sBCv?ToFtx!bRfmmGUZ(z`<~1f=KPFv2hX2@Bt+aXqrNp-0o-ndUSxX)DJ)6DM8Q)+0lQO8 z8+nBqadskSLpCyAb|mFWsu@Wx@2LZhB3G)a1u9?5b(E#F!-V&8GWBZoa%OQ|?4Qh$ z*sn%Eh5D&!Ht5fH)=s5nI>|LETG{2xu3b^Sk{@>fW9_l=12Z`u4K!xJ2#yY*v%XTX zr|n(&=UD!2KPtJ3Z!Pqfa;mnI;q;dh!+1*esJ>hK)fkMNd@-f|*WM30W3rY801L~1IWRqC|2dN{U6(MN$5j_fyM#CoV#7PS}Ex$RwP zf|jny)N7xzf0byopeRjfM{y2J=4dMQQYia(8sk0;sFYzuh4PL*hH2DBPq))k#$&kl zTiO`08p=LOJ=39+V(lzSW1yB^H=90me?QO7;kxNiP9tjOlB8MUzfm}|fW~Ic=d61G z<>Y$&bGU#JoJM8N0XoNv)lja*H>zbWP@24u>s@=Vt+7&3Lyh^@z+KcGLn1D$JE1++ z@s^=c>ao$@|Ues08I+dY9M=k90))#VXS!Rves43T%uP^>*UHKa0 zy^NIhxveCvAhtvsi8gB6r8Pl2qyN?V&_c_lFWS=eE=Rv^V%) z?_)ps--1s0U+I?j5U~mv_bB_HA-nvyd`N3tbJ2Q-#79a-$M<;e~2IIYTnhcm5O`4dY0BZuUG%_8n0I`bA-HJ%_08jyO-bF zvTYIbc7LyOo1>?qCiIZ7q!ivG?T)s^*2^z!i|w;@w#D|@y6_HF-_Dko-_G}nH?-w@ zYIC%++_r)A^XSwzJpoNn58I|U()bhGruWh)6!BTlrrsP!q>bb%YkOFaiWWrsyp?1O zioG|SB)0n&EhMqs7U><*a%O$B*_BN4NOdx4SNJK6ceFjW(5M*OV+(DY?XiWn&Gy(r z+h%)gp>4B0w$QfuEbSS#NPm$2Q`=@MY@u!S8jl0B8q)ov2O87;t3BZJq8H-bqZi`c zqZi`cqZi`cqZg|0u1!G;a54A9v+$cW(-S#o)!ghAXSB53UJ?JL@%D=NAD(4L%+}c> zj+oXbR%GXqF%~E@@Ol!W> zUM%yi#SQ{lX`28ff=;P8ql zbx5O>ODYw|NlC^w`wa0)OfIaMO8sJ<8juO2F*W$J>mlZ)C(NThr|kRBOHY}Xo}z`qovM6Fv0s%>QNDMlAID1l zd>&6yGjLtM)_t{;`Dh_if!h4l@a89dV}8;*)Bw~<{T`8V{c4tT8OL^@+TL95*8%jt zBgos(G-h&#R?5cv&!X(k;q!Tyx#?}@QgXkz`9L)bH5fh9b13N%n3MI8CZT7HC9kAo zb?!N6Y#yr*&Owv&SbvZ43lW{H|EE%Mzw*iSk=NzvobhB6D7#m=`gYDgjq_KpHY%Y4 z)R(G9)o~k@dQ=&vma;u+WQ?5KkvHzQ1?cD$t3r%pQD1a+j^dip97z*KacnQCr*#0e zEI2E2?&oY7#d~?|yE+$*jaO!9ps$q^Vh)N=K@GHXjZAGENjqJSB8J)Ok=)t#8qaT= zeV#3MEs-s7M#St@E^++Ci-ox>~828*>ygvh|gUv{PytluB+? zeQUXfbX-0lC634d@kshD<(76RABufabmebH*peK=z84Q%aTF0$t{;jPt@!1WV$Fx^ zKWeb74aFL%hoP3-7zm-FQrsZUWawq-HL~i*JBf2oZev(Pz$jyr=<;vCc$7tR4U1kBb_xe^dfm(olw;4d~9`?g@ zp!TA$k;K{(ZL@MD?I@#}zslU&SB%V@Oxd~aS~)FA+GfTw3$?szzln&M_)dYgU+qU> z0hVTjeOTJz&UCRyoqlbt*IKqWaEBh?T8=kRS_9Pjy)jXija)Y#yYwOCn@H|2?26~j z{L6htwGwUS*a&%N_ZHgJ33P|Xtw62VuAFw)1|#Gno?d&BQT6V?xP^bYI(sY7-SiG6 zZO6hc-F^efsQPWx9>#TJfZNI4QPoKL?HnJGXuH1JH&AvzRioVx$FeUyIFkQ#01qQS zlG?+t{(H`^Shydn9KmRJ{kc=AJDUHr1CJy(s$Ji%yR{yhIEL}^`di(>^;rIE-2Bm8 ze>}Cu&AS`z36%9;Xv;c*Kw;7U`@rhFD2q%+CS;hHmnXHa_%cs?7ylJwXp2JEBwmIdE^(8+!;6a$UTqai@3%;a$Q|;G1s*KjjQ*oWEbFb@(Ws* za^9GDeVLb%E&^Vd{84f#cfxJK|Kzt?jgG$zFOWBVK?jDP7C4k?jjPcU|&cy36fVl&|94^<38g zyoUUGj<3P9b{+YSbnXV|&mz2gi>SMSv^zPvC)M7| zHFx7xG5Y;pl3o`5!S~{QTY;ZO&UPRF9146BxqIun!|uK0?zMX#o}QH)JwUoY?O~e( z@8e$&aeN=}K8_#e8uzn(fVziCerZT=@gs1U447pV;Da1JnxvpdIi5(_U2*;X&_lon zx#Ce$1@Dyd(wn)1-z$2Qqc`IXTm|eR_uEB}GCsChT}V4w=oWHpIgGqio1S)ECFamd z_I|xr7XMP(Ury5NF2`F&$^BdPwY#IMtG(RKHFkQH$GK`u{ugV)|C>NBw3FX!LFI~Aho7^}A_q{bPq1X@C zU2vyE5!@%&-Erl0?w32A(o~W@f@$Q1@4#Jl_0q`c^cwV1>HtnApG0X4u$NqpHzx78 zv5bkHiX*&bW#-MzQ}wf|!jVq}VEhHUIn z$j2FZ{6FsG)iu;r+v(Z3x2>x7llE?BRR6tYKUHn5VGUN#4Jlb&Se~M+tc6Rt*S81> zH~b#Hm!oT|yk1%$W;nh+S?$}g@t)3^h&6S*TGBg+CDEV0vHfX}N6(8p#TbM>;nSl3 zqxa)K)`~^`SM1W#p)7B^)aV`U>Zr#!+FtMEe`7xMH(vhNtK+(2?0i#ehtf(uKKD1!Z>Wh0yp9b#9^bPx>O1E=qTV(#zPrL#nhGnj~daS{F)j zrD8%UvC_Rz3N6(WO1a%fq*&YR9zO0iVw{N-Gxi^GMYIv2?oi^+K<-iE?m(`bRwj2I zyR*i6dRvO*ifjAQ(UxY!${9z&kr(FzL*+}M&p88PzW6`KuNcu{?5ztN5Faw|(ktVt zp~%`HoxA7sR>sf$39*eWt7X*X-NAt?r>&>_Ma4Z=V?nrZjJl9{7D* zT}d2!^tkTWSuMUCsC`>!GCO0xBWFMnjW8{ZihMM7GA?#Hnv!tBnUtqKiQT0mzRune z^Oax5f{$W&vD37(!`(GH!B+9S*lBtV^{%Zi_Lv?I4!RGd`-H{LQi1>OeIEOqySub= z!QJUbGE0jcQDb*$cSUnwqUx@x?k?>PM((mU0?ZIE#E;lr+Fejwz3tAwQUWzbsi*y| zL>{{XyR+J+G!E|M>8Plk&j&-@b;%t!H>dey)UEq7xr5slW{lc}b4jU3oy1u*7mOFX z-TiGVb4d-y88wFx8G$F%Vy(-~FQzdN>aEOk8Rn&UTx z9#_UwzH^@oWjy6O_w28sqpgDckc8rA6BljPy8N$a-CA1nt@QAM_wjWUkaOO z^nko+F1=t6$f1PlfyPA4rZ<}@tAPpCB-QqWwppD|=o=~HO#}K31iz7>e5b6Zo~m3o z6|G!NSEyF+_Z9rwf_vqwkqaFcXR^>y^P3HR!NG4e_{}cA?BF*X{7%;fpkH{1uj^>- zjJ@h(rz>~B(x##1b3OPZ&MM2V1CLyJFFjfdM){QqzdYf0DE#__Ul;NF6n-xtzOyBz z^XnCADN;b8dP_k)<%f=4P*KNB3t7lrMoR>}_N<-~aZJiAPU(-3kIS7yiU|3zQVE_~ zsd(>#0?WOXc>G6r*Ojq6>sZ?w>ATckoY1@CNVSlMHO-NfS82i3;;E%mOYKOYYZUcn zyQ(g{x>AHD(s-bpwTWa5nBHFFINFc~0?A?AFrN0eForjxRo(yubN_t&4{YN3$HY=g2>$ddMm{ao-d{Sx+I#JpyIn`={H6!qaS<^l`gN(KfmxMq6rO8?DktZSRZu zQZ;Smj-!4hJw;O3;rz5dONF)cI*#^y$ivF~j%19e?G!_7gKZ7z+jY@J%!PAX+!FU< z#|y_+dukIl*N;Goj3(H^#1pPQ1hSgGYad{W|%xT57>Y?GGjzju%O=$}He4T)Eo z-_|NiI&Oi_%Io5#5~X){9HRa9MvPYIOT}A>yN-pju=nvAvE2KKIuc_U_D*2?q0vA{irw5{eGN_VoKnM7$Tn7>+M{nk5Id}b5xvh93lcn zoEb^kv5;!&;jq`Fnyx6(njbsvx=Pk)HCN3R>-op>4_9Bhhnv{u9&XNbSNex$Y|Np) zBj3>|ME3|Y9#K27yYSklMf{;y*~M|hABOKTW|HHrWNObzbRtu_N$bTv2xx+aoSPyzmLW zix?wzNG+s4KF|KQ_0H=iptgXK92;>HK4Sgaj*z}w@yCcCse{;|zt@p-$7Dxq6tIQ7 zgOZwuW8j#%idOuI{nX@fu9R&dcNJ~KfI0$3;&!Ex35!NIcrzSI8@m7v=bSvwHM7Z= z%w0xN7RQXFZO?kBi6~EZ0+V}BBDsoII^N5Z^eFW3F1?i0&s;S&hv9 zCBQvArcg5OTo2$BlG>ZS>GyT~I_6}Krc#=WEMQMhBdOa>tYQZCyOG%23sTf`OKduzTu-|-;LO&1A>{@6ksNK!kIj$HkI5(HJ$WVH!tqhSqw+Tb zkK|}E*DeCiCSRP-$Y%m)=CgpasO#l_mHc?_a4hiH{J4BFb(MSyc_p7pUdd0&PsmTq zr*TxtPo{iQKAodVehN=`Bk*Ycc?zYYfyZYCBHnsj{Gv<<-qI7ThjkqxKjh=n!FZR zo7VyBsN2C+m*+#NZ^=*PnWyBfv||ZyBKZ)`wB(oO%Q$l>=~Uoyjz(~P32;fiIlqLO zOY=5Ln}8$8M^f4dY$N~o?BBAVXQMdYkdLBnWBz}#f2Zcw{HFZo{8rK}`7g5nLrptZ z9Fn(l)rR~w&fW^Vk$g0@>w)d$S^j^s|HyK3;eTYm0RDpi?#xf)J$CXoHvn(oe>*we z0lY209e8_w2k?&kPT-By{VW^8d;N@m4gu!*&$E~F6}-pG`AYJa^Ht<8=c~zIruGux z8jfDh*OI@SuOok%Hmw7mo1X(bkNjoYxE^>uM=$3WkiVQ?Nd9tu5&6sc#pEw@uZ#1$ z^3!SWU8J4)53`?TEx?w1c>bg8hncWD?*b0byYt8MGr0C~(p~vKWIxKf^2exo9C#-A zn}Lr3&mw;%|HtefvRCpBTJcIghWwR$Ecq*WC;2P+IPzCG_cCxiN3Y})$Y0?}6M+A~ zoqwGDBmaLiKb!kKN_untPuY*Dd4xAS8+bOgKgs@ynuoc|IlyzM{pai_)ci~K&%keI z-^sq4eVg?6*|$jF1AZ_2KJeQd{WSX*uKC~OujGG|{cZMl+24@91^gD*JdwXOe=>g} ze;fG|`P<2#$e$vAB7d6viToYpPvp;#KaszM{GGrj^1tTa-_QOc`}6FT?1lWf{Q3L^ z(!27nQuj*swd||F7pZ%9{vzo;z~?yn3hjRwcyE3W@ILadF@%`~TbMF93 zZqePfq=JM<7@*i9k}3uwqLhUqp@`kxprV4J2qHG32%>_D-Q8k${XgFs-)CP~7M9ST z`hTB&=A5}RbML-$CeN8O=iJP%x*B*bc{iI=czPy!g?FCeomYXcMy~;1=II$?A4Crm zJ_LRk{Q!K1r(1aIX0wQ=AEE`sZ!rtZ6z~Fm>lE`yw21Ua2;WC{ld{0v&2K!_JWAU4 z(W8X#qWPrUZ5H$NU9_0+ZFCnY^UY&CeH%SS_$Hc1%3Wp&v9F^gq^$NfE>2ciefLi3P$knb%7-UGfL{D4{D@8T`+ckvcb_5puS?}6xE^6xYEQu0CI zgFMYA=K=2W@h#wk+%bmC@6rT}jX#sH@10qFH7p za3=3Xti`iTIZA4GaGSZ6_-u2VxguJ~dsh(T-|-=yuHo&KrYyPTxG!}L@iNivW;Sp( zsn?OV(v&7ed!IYZ?PiHtY#uYWaT9V@G>!a~W;QpLW<`&av(((q4W?PqGRiD5%LtE~ z>6BW@lomzz02h;LsM({yM=51UeZ8|?s>Q=2V;PtyaI z6ST))ZnP6!Zh}AR<>okUU*5?1>5be6l~>ank)A9!@~_wyd@Q*-fxQW=Q`Q@R^b|9W z*h9O1xFspWLo6;yWw( z8)p}DZhI2twJ)v6ojl!*(_KD!4!wkL=$_tXkxqA480}lNm({LS{A?a)o#&IQJA3DI z+B=al(pFeubXs~DyHjzA(oX6zbuo3SCZkjF;xB|1U0oF|{dZ#bDS z7O4A!rvOi8H>|zq?wmtU0#4$)(tv0Rl>AC3%%}LhZ39k>bq0I}@0=A$QlZ;t+7)Y8 z+YqRmV|7Tc4QvROWU(P<&N`pg*|g4}b+&yP;SAuZJniZwW4rR-nxI26hF`H8VRxiZ z?W3+}7s%3pG!TM^-qFaOB%A8&rB%I=qqRpbWmoVZ-rWs28ay1`g%LnmERg=fXrxg( z;qKriS30rZ4(Zf(JZ(ehfL??wD(L3!XtXT`p;saOiqTOwN^XM;PPbO2SJN9Uj6swb zO5PygVc_nRk@in-uA@_STy`c@gdnltzy{s!Eqf_MEpTRT6*Mz1*MD z(jt+^<=|IY`XdLz7e(xXrF*6mHuZ36s*0=DZd>}l(g)MtJEcV`d4+U^rLC(mE?!yZ z${Ok7%fy|D&kj0-8tvlirCBK6A;nipiXc8A@CW)|flEkP026;FUBt+LQ+%Fy*Ayox z?L=wTNyZ~?HrUq_uPiGw`fUX_sKkToUe)UNs8mPIiq`W0;(Ih_%VL=9*=QUoM>cH4 zW$L#|>rv7f{Z`3jBtsHi#CeLJlr$hn0;Fvm^d7}qiY~H^B^iLIBiVpBO3_8~yCC7y zeagAT4nqQ;uQr6Vtmd99K13ZfCJ`9+dZ`3NakF?Ca*@Ho{7O^sH0s?!>|<~Y>| z)!L-dDo?*!BR6)OZtl4^wF_F?8oD8Sq0}yD?Q^g8MLN^ateaXr(|1JL3uzus?Sdo^ zEqo(<_4z8|YyXY8cWrH2)c&?O>*>1MbZv8QYDbjX-~R9RMgQ(`nm+gbm2JA_+`G1M zy5=4!)uz$_OPx#=-Xo=t)1r8m^l_>)j5X~ytiDImDAn#LeeMmjZt>Ss&AO?bQfiMB zc$RZ&Nxl&dsF<2XuP5Pi}vJe<3qKZPq)Ug=G?m`ADY_ziW?0(UbU}! zVF4c+cE5oe)h<|f?X>&V8Y^o3iKUHpN3~#a~^X5Ozle9B693O|@h3*U;jO&El=0e^onfE_uSb+VQWP zV^cfZjgbo#ZpWhJLYrqVv_5%4m}!G_DC}$t%Z0?7rp9B~<%Uryu5@$Ag*LPuHFIpN zJYik?pS7)(MalOHw`0)p2$H>`=u3YFC zq_s!;n|#LrWk2#D!f`-ZuRMq_4k&Avk`4>X3g*EC-90-PcnEj`P!{bDAxr`uOxhvD zWXOTrgqNBYv z(b4_{bF@Ff9PLj#M`M}r0Zt)Cd#LluG5)-AA^0KAUdBWVfeSg~9ZOgQT*Ue9Si+;6 z(T)Y~0bC4R%-QT7geAZwoT%e0+$482HuMl zY4Ytwd~fiUKxuaGO^_vIX@%=1u5R7zO?)44d7!lJ_90{ewVTy_Tv;{Phj<@wE^r@k z9#|GK`w-jL?``(=yPAFdu12R|@;I?CJDk2=O3>HuVfuOrUSBU0=<6ltIvuOZ>6fH- z`w{8@b&j;3KVRCpY?PB>ITdHgs#A@oF(n=&y#w9yGIB3 z^C8_T*6r~FI4jx_xC7@xI!ijxpCujW&yo%#T{plFooCiLN=lhvqjsogj^giHy%sWRiyF37V2z(^Z4>6w{Ns3NC7Xcq; zt{Fk>VW9LvM)16t*=7WBos&KSl2ER1YUrGtJ?o4Dg7ssNr)-8ataj_-1G%Jg^l*4!`4;%(A z3zla%=>iXBp2-511rOyp4|o_)x!^q3HE97K%1l!cD4ozld9Dl`N=`L!MOH>>?;gTa zRiLy#58=5c@K8So9YV^%%rUir@>ipK`O+3Wn3RK z5O4#aZg>pwXXZnAmPfsV$jJvcX50-Sb|CYOtOw{k|3GG#mOxp*X#sA@_&t!=0n9ON zfGxnS!EG4(2N2tz*=8%CZo2Hxb333sJ#PcnOtZhAb#%6^nMSjYZfOkWS!d;%gX9%p zJD|?b2NCN6?9N;>i0AIiJcEeK7D88`?vxB9wgdCdK;rTW&;zL3Cj*#ob^^*W#Q>gV zH(~&=Ke!ig0JuN%O>dwqMf4|iH&&nir1WErlD|W(Rq}ecH&7NLWW_-q0s4^=EIeqA zmyHK`K$HdSy_mPc{l+FxKIN}l-n#2TdFdWBAxPI&Tyz6MRiHTM2ELUW_?4!CUuopM zMy;i_v@yW~wT^17kZyBh;tnW(L)ufyiim89ROVYH{JJ8qo#8~QK0Ub+sp2Z?)5{z2 ztW~i-y}S|6vI86Lao4A3%f_o#(T4QZOBMyn)IcbDTCLQ$hbq1*O=U}ByauJQ!z)98!1)pUzQ_pnpnO#hm`A2__g2c*8H@9Uf5Z^Adzza|NSzA2ww`tQ04tlI*b zD|A~}H_LUuMe_6DrABqpiJodC&34ThDO+ipIb`!knhVkn2zG%i|3RmfI{gs!L|Oe$ zQ7zCi=sg6TXz4vmYOy|kTNE$Q#t0f1Yo7at^ZS%GM$zZ@;dg1)6_vwpR9eu<5VfTd ztsGHU8rv!(I;%BAPf<*I_@bWf;)`OUp6&=0w7w{)->5zi=q5TAP)zbHQE+q9tvLLx zBx41q=Ec)rDT;2Z_s{g6DVm6GYPrzci`zd_-z?5J(s_z;4Zzo{OQ>Ma`Ko4cR<74u1ICMmF0tJzo*arKih ztAu%2`URVB9^O!WxOK_PiZ`Ex)w6IvNuNp5N4;7$wR#qe{nUI?)EcU1~pRE6z z8{1E`3Kr}f!uqFCysm!oZ1JtVb%OP^2H zoTE0jpRBq6T-&-6R-A(U$>#1Sf5pD;@9rn5HVtDxy`QA_kPVwpitc+weKYis^jT$7 z`ib^$;zYvTQOzgn9ibnj`pN%lJ}GM5(X5=}0<=d{9SZJ4if>41?rLvda6(gDJ?!G{ z|AS_t{zr(VbSpNzpRB)4H~gFFJ!I``*@ny~>HQ?tLsI-~s-L9qW7nKdHkRKhYJZZ> z@1!`yf7?EG)7mubHq%=+oySjKcft;~sQDzlpRE0xYwIU#?mbfcPI3ClKW#oqmnVdN zt64=eq4+?_95kO4-0LW6-O-#Rd*N%|2T0ea*_eIoU$I7{z8U(--^cH)tuGa|Kl!Ws zNlN0hru?Kh^GR{~NxFXI-ywHeeLm56SASenzPDlflhwbO{CDb?cYYNT_)I-$c3r-?J%NDgi2{YBY z!L{rgpHKLvAlw?ca4?TvR_vwdr5CKM6gg_-onP*PXS^6>G}Sic=;vpZwd`o%Hja zba`z0{v@3*4tfQt)4&3~Vo^KYPEApAwxatrU98q>uXa-Ddh;B7GOJ>FZ8$`$=*7K&s5T&I(iW$=}&e(&hHW z*~g~zl-71nVMF+x;>;&&+672ocS2mhMz_DzQ&P7}iqlWlKcD;+eXlrc%0IQA{GIbj zQR_}>#gRRizn?E&`(9$h``-HJs14~S>)PvX?)fC#cq)8vX4#YcY;(loW4mOyJI2e52% z%YUL~IoVyv=0>z`FUr%XyeDctl$C}G+@RLpLpB@aB~hbWRvgN4ds_YB@A640Idkw# z*$A0{;f}9PoKl`C8<8SkLAtrz5Zr>ChCq1=Y~gPyxA1q$TX0jnDP>xaTOX)f%`J%K z``gX3U{Q^`&H3DNt_iF`o8=R$4Xni-Y1z4`L#WM7>E^`h0qfEd&57x5v%D(l#&ji8 zD)akVA|2O=ZOQ%T=A>F;;a+h|TBbRvhLqq(s3k4XoK#uD*Xdewux9pL>eP~Q;!axv zWm#iOa&-e*eilm;4>zFYld?I_@<`d7wyFRQ-a>T)x)m*^=i0UNskLgX`}X;sPWhfr z`JPVso=(-skxwSkr6_t>{)_Z*V{o8~Ar?FsHRo41=U0n|YVObIMJZ8F^$@-Cc~%WX zseGQR{z<=luxMG8-=9TpMRMgaFrS!cmR}^DRAbRXv{8*k3q8w^r@V*<+LQ&W59ITw zK2o^uqKbNl=v0^vp^oZ%&Ht>sTDbY2{UyD=q3?wHh8`5^8)y}37ibcGd7w%7<$)%Z z_zi&?sh$<65o%N%n#dkaiYDqADVnHlqCe@-g#Xf%9-#Jb1Z?c7(#ZFYhSXCv4)qN* z2`wIK9q5x@>(FOHtwYZVwGQJc)H+Zm)H+Zm)H+Zm)Gkma{Qf|h@cY+I8QJ2|C@QMA zgx*mww$kaKzMHCRdL7ei7wT0M#X?OB_n%PfK$%eMK$%eMK$%eMK$%eMK$%eMK$%cG zSshXhWFJBEgJucM7lC5(*e42Tq-exw^r+WpcG4Kr?4&-WF{d$Dk0)8uDCiIAbV%>x zh3OFL8)_Ho6?&08UTAa`^rcYK!juWM4wMPC4wMPC4wOl+b)ZkEZ#o5vu5}ng1$7Tp z4Ydwb4RjMFibsd$tIcZa5rydx>Kkeo>J_LVdl{NtM4dpTP}9Pc3AGNCDXPVbU+X~C zQ0qX|P~SjLS^vSRGR{occ>)I)wU$I)-`$YJ}ZSphKu>pn$9v7PT|j_;C^DfKczX(_};G5cZj2 z&$&7sLN5rE5KU5}TjM&N4yjtJzOsa?9iQm2{@vlm(;Qr0`XzkSstli>&r9T8ZgxYKf zUFx+t=ulAiAa4&+=Klp9ic5hY-&r3Wf~-{g-&B9lnigcsMV-|I`EpTo2y21PwKXy{ zMuI#!tPZL166Ore9_wB=S05L}t$V(g`llpa>8D%aTuWy(>AfO-HV)FajiW}WW7utk zdIdU!-V*i(ff`|l5c*G$tcKB)E>{fH3%dx}uh)4^Lo6oO^VXB=@w78C&0d__iu3P9 zon&oUvVfjQ_hf%robXP_Lw3YEv-rRrk#^N0UejA`7LT+&lA!H5uhqOG*n`tst-gY? z_$;f)g55Z&l{7}MD;A-}`wPl8w5TU2YtgcSEGWOr@?#_@>(a7$EGT=^lIaV|%W^hB zXS6xsEMo0}I>Qwm+5_8jQd^#|HLwD>9I>r{<-ui%we@ngt(c8u3tQ5bww#W%;lx(* zmo}_qtvM0Yde)k?O?I?3zqg`K%ICNIl(b|8mp5%`1hk;nmLy(+puLRxu=;Z|_BPH# zovP_PP*A&mX|V~450DJqQ> z=kE_x3cr6tDN~pxq3(euq1J&W(j!RGq%a-S3mW@g(8TwGrqsTG4(feDDqYR@zI@;B z^8ak{P~Xs7((4;~PN;9_KcT$>WkP)eO~P*uGzq^s&?NlkO{aaZ-<@}Y90DdsCA%EsCA%BsCA%B zsCA%BsCA%B_~n5z;g<)>NOMHvK-wf473v2X8I{0-8ao<88c!Nkfrc7m8fnsQ(U_A= zMI$26A=RpZ5~50ae@<`NP`faXXclSoCw)Rq1AWpd6KWkO6KWkO6KWkO6KWkO6KWkO z6KWkOld5%?0}AS1xYmJsq3)`!Y8_@8%{YOc(t*%Cq&aGJI)u80)($iX{i1*}p{)ZQ zLajp`L+wJn!VDXFPM}p`%7j`6%7j`6%7j`6$`rrWfqJPHU$dI7;8Duvz>s1#vV4xx@3y&A=#S8Ig}{aO3IFp9Mc4x@O@+J$z^k!oEnj zpow-anl%Ge!rUNw1UjUz>0u|G>ItF7Yp2FvO^5Vf_1DuRP@;e`DGG#<9qPI+Y6QBa zkBH6HAJTj2|AG!-*ArHcP`~2RB+Lw(iw^&c{t#*tYPMn22t8!e=ZAkY9nxzb)@1dr zjhiR`*W)6Lh>hzHfev9k3~S?>@{`m&EGiY=KcwUy>I*6UU28~c*4mU`74|9Nf3E)* zu5CsN8sO{Sw@8*Ci9-6mKCDn{&c>1u=`NahY;oE_c2bhQQ_u@GHyt*V0-L|ql7AU5 zJCH5@H7St3pZsUgVf}lv)%PK5wsPQAB-@g04()LyAJJX7e-|CXPP6#jTRI)oizJbh z*SC$Q!}{h2{m0a9eM8r>Fn1MybOdS?hkFaVFWtJ499B0YHUdQ6rt~e6K^cg8g zoQt0E3hFK?b6GEaF7r3jp}2KV$-X4@+E_Xi=10`->GJl!mk!0Pdywq}DNkWKq|d`a z&XRr}v9|tD(C$Iro|3c|oI4bzLzop)>#N2{kQo(!o?P3w2oxyp>YtK#t$CUgWTETp z6`JWa16BM})|{eD!MRLP)CgR$!(AI9S3TJng$AlItJ-Us8OIm=s%(EVKjxhhm)Jsnxq*f%*a7* zFWVK`X^5tq62IE$7S;lzGvjNBUv2I&3yh1dFjt#6x|{R`=3dfVbS=5pnEQBg(RG9b zn2>rMX)ans$-B*!<_g}LX6`3#8sR$g0P$&NI(V9Sm@`JB64iBnDj@@ z#l%c>F=;k>%;?PfG13>C8I--z+y$Ir#!<>dZp)KcJ5^EmKv zv&*T&+CYbZcnLs$nyhi>q;4<@s zxtTiLWIm$I>*i?Qh@v^>PBYicAF|Q zn0nDCqLt-n;;Og|rvRdmi`_Ptt*C5FKiU zn#0VYgkk1ja|p2}k@i=*+o=;(-H;kW&Y@Zgk$M^B8gSdr`J7dJm<^+tchtygl)4 zn2U8*xW75T9BB3@3^99)0jLrUwOcf)8`O4UI_q6{Va@tgNE z{iy%pM*hQfw_3Ntb=UnX)0R*_8pyYYn1N=H84MiEQ-7X^0f+IXZo=0`m!g%w2VWmN zfZYCO0A+`muKbs+qutD|{KxHxca3&8yAkg~e7k6Svpew}%=W-;q;z2(?S^JaSwatB z542A-vv!NnPBA+e^j6G{z@BC&;10ai)pRr6&32|Ma5wyd?}``jo$(>QJMrCsyMQ~J zZA}-`nXnyjJ4)_BncbsKJaso6O()=9_z~YT>cCTXvyJHh+y_tLd*e}jXL9x->=m^$ z?a6CL=x+8Utq&f>_wl~P_wl~Pcjl>$X=}DJZ3tTfx2AL(O7{S^1NY-=@e z1m~Mxrl-j#wHL4j_yE!mj1EAfXUC{HdF;0ctg__yH2Zsr!T!*Ad;GrdK)L;i?SOyx za>SaM=B5^Y+{^LY)HEYLkocgeiD^o_vZ-RKnlaI+XmnJ~R3={0R08LkJYu;7#Vea? z=GbUVG&VYxa5V7f=$PoZXe93)M;HSfLu$6kp>!6Z8Za9?j-2D83OrRaCr0C<6QXja z0`YRDJh*&xXmkjYjsf8E(ZSJBFZCD*97tMu@($+Qs0qKbW>nMEFg2q_rXjGgX#}ic z8Uq`eCT0S^GBPe?s;q>SmN_++UD*8IQmUpg+N>ZwxDM_enrbfe~BciE< z5x^0=^DX7S0e%Ml1o$oRQ}A`XdoA!Xa0%Y7Yfk0esnIl2u8W*0L5d^PF;k+$$(cep zHM*YMX~0Xt*Atr_eGq*ZeFXd{`Z#)@@Con(@MF=V(c)+c@Udu7^ayw!TZhH$*o^k5hhWv=F=uxCp#3dKg@RHa-k^STqbcj9(|7XDFv- zHPxa~Ekip;wM{Kx9aGy}%=c$RPx6%~q6edg_{vknp9DVW;|qCufcR6z2F7Jo&(+kzMI%e-~w1xpr(f7c}`~hUU zWUBFOfPav$GxW33gE>1o2Y60&F7RAxSvC5R_o_xefvZyUpMXE`epM*(GyF>qWpW9( z0%u0I0B3=7d7g!I^3~`y;A_$Az}I=B3PCdOTcVqRx!}C$&S(yBE;x_WxxhKmJS4kM zM=O9YM=t?i0axbv72r#JwKAa!{8Jt!D-!Mk-WAOU&WEOzqGx!!QuHji5>$Q`csIBb zsk%#3k*CJYqUC_nK5WLCRTfy*?>D4t*p$$WeTVc5n-EF^OOslk(iMQxXsl1^^6X!v z+rl4ur9c!*XXQCIwP61 ztyrnHBCQrdr)0HxlC2osr;#m1Nw3pA!pd5aZkhzX%kY0KwUzCkJVGz(Dt%bBaxZEr zeOR?!PiiK8SheI%)JFQSl7sI^J*p6|O4#1_P{E)B8?<7j1*~pm8 z2udGTE3TmQVe5ber4OsUnxJ-*b%}L`I(3QH2Mekd)Dr}?FH}zulxA!rLKaYcq%pAy zz((LE#L5F3gPRg72W$dvMofLODOj5M(mGZT%_kqMrh??X*VZw3|AgBlX*0h{pDh*;$5Qx96G zZwAdm3h{f5G^VJ8}MG@+a;#=R3g>! zl=xP1espQxZJ5#{5=Lx&x_OKpE*i zi>{g%+R_^BNY#ANhE@{gN)xuEh1)<^%_h=xmacReLTNuANgG<@u`EF|lk}v6d_rxY zHd+6eT3dP5BsCIctux)%d-@pM*zd1vjHmyelwC#DqNq9HztXSNqeAccXZEYcjNDp` zu{z*p#586bgPRho0n`X?!pN-#)ZD3)+8T^Q&4rrx>H_QVMgw|gJ)mwf$evjQlx;KF zITJUpc|$!{n!%cdv1J;_S8L0!I5#v|7x#~3?{8-iM zs9WEf%fk5W#ORl{UoJS0{w~^U6w97mD^hb9lbQufl9J8X)A(&ms%Fe>fZH(EG*&fR z%Tk?b zhV@vxbk}1C0(>%0by&gFF5>QLd%k*2dwgLX3oBT6+NCS2n4nrpmiPok;Vxi7(R^D^ zXW8Sc!rG;^baktIok{6L$b*)_5})WON^3pV4smVv__UU-Zk10fnkZGl(?S#xy(FV3 z2Sv56iSFyN#~0QzQCbp?()0thkNSor*}ChYeUxr%>YTKhZ~tb#wWY&Z()U|O-%`(M z;`@vGt)rhd@%>1>aozU#G*4=0q8U@Wl#)QrZxLT90o2|l*eTVFtiJv4F0b8LSXq){ z)i-@U-?X@93E4u_tdW{2)Hag-1q+H{-bl4&Xvu_@)TnO?)GVcuE*RQB^b6f7QNIyX zuTifOR6k1fEbW#was?$5OWB9ieWO%A)jcHb%mmeoQ+6iR%hme@)!#K|2x>OaXc3gv zO6_Q6!BUnigMG^|uC$lecj zk>8EESrR$T4%*oU>z$IzX{PAz=l9giQrpiiVaCziv!kEW1vMLKW*5}_q2_S_KU+z+ z=E4lCR#F?u9;$BG>2{skD6~~q+Cj6lZsn=H#EFxA=nXRn7id19k+eeY7H| zy~1j-BkiG8L^lTO&@#Fy*vq$@R^eWZD79NH-(I!+Tve0SiRlU257#6(U@g*W5Gw(! z39e48B(Mg!8nIHq>foxxwg6TGS0T0~uqwDRvC_aQ;7Y{G04swl5-SU=1kNK?4p;t5ds2S-lSyfHhnF8|xVO8Cn0; z4p?oW6(y#&;(b)_64YBZ8A^gnWa{`2?W>t~%=FcN%e8t;oeNJXPX2#>c zYdmU)n!aC6{)79~OdbCld`G4oGwt}#mvvKV zJ2HEK%pTz1wFk)XR{xE)Bh!wVcKo;O0scSq)y$s!zcC&&?U-rDf6Kg@>8qK(n(3<< zIl$ke+nJGd{Fh`M{~z|`nL7SA*2hdcX4)~c&&lj_GW(p(bx$X=m-{d6C zCl@3GlEKOT!2Oef$>`)LN{uFrNKWD13BXC<1Cl|MI)E@BxjvbZ+yuNSxgj|znL>$^ z2osV^k_-9jC4}>nBlyM$;27``$yo5Ilo}750-g#UpA1iqCTDnZ40t%PBa-uY`~0L= z(mUA|xNEX=avJ4M1WpAXPRZfGW5K&orWbG*@adE|0eBjC7`cZ7j{{%I*Un20OOEI1 zFv76p49blIo(?_}JTB><97wJDCquyfi490DcoQ zg zCHp2rdD@rIH@S+^X92GSUkyGhxrH~TC!LcHNynroHSPu69o#e713Z)b>A>m9w4^;H zIsrQ++We>R$xf8)3EUIBQ?eKMR#LA6&I0d9%1*$&!MBli9q_v3+GGb(b_DJN z-X6FEun%}P`PTxkO|D692Vaxi3kB{1-j&P)-p$jJWLfeA@QGw;avy2)l6L%__P}ky z?UF9w`^lLHoR`c^nkJ2s#>oRb%}ur@w;gah@YYFJ@Pp*c1*OJx z=KvoBwzSRWSBxwk2%2ONC+X8!l7xKm&;GE=+uj$AFLXtDht+ zNnTD~OI`=Qp1hJgMcQLYeZJEG*bH1hX%1da>SEwi;1%G-NxdYWoO($Ma6Mx6lc!02 z6u1IhH)%;uT|&L2a*~%+Or9a{5#ZC{I^@;`wgT5qT7zp7>LkxnViE8e@JjHaB!{;v z0xKq!fR&Qmc6&Pu9--y!t{;M?E|q+|hWfZrwcdEh(X@}yJ%)&!SG;v`AR5ibv{ z1%8im&jH^BzYl&cF_cPxN#cMmvB{VG&QF1#CZ7O5=jki(CrOl)q->Ow0!PG5@-?X+ z1HS@)1O7PqBi@4iKjJNuEr6vc_Z!AGjQb7aslO-RQsN`vH{jpn(#e*;Qm{^#+J;LnMz zic2_0dI`eM$!GCTJTC7fk16kDW7+p9=SmRDI$8E9>s}@IwfNQeeekRC2VhzIDeFoR%D7iZc{P3|{t&E{ zw~X6@P};pr$}929@kij7fG-0-2FuH99#&%VuoENOK&2hlXWW)fwt=>EPsdNi%i|~F zr#)OAuOPl6elo7e8x^oVBdas=xgr0s6-ikZKSSAN@w4D%#GZ&NlUg48HI=}!xl}%S zoZMycOGsZDFNt3OKL%U^d=Xro z5@oQbQw=Q3KV`7c)5u%QYeek9_`dl5_@4Md5ATm3ApSsnZ`>GLOR|b7n@qB_CySYl zi7%k!J@JD0A@G8DA-E~2b+EM51T5R3b)vgTUl89NKMcM*UIdoEV)=1t2A)sK-SPbR z5pce@FC@#NwWGV@M@hSjFh8CbFXm|;;jXv^c4%s1nJFJE`Q>lKk}a%`gsris)RB}Kq@e*c>^go#y7-sz_Qlb21`q_VS7C(H^kS+cY>$K zbHURI*T=H%+8R4dvV__V+zN~HvMYNURfU5MN8q1%wOZJxT3>Rr@`_=aYUxe13c#_&nhGz-i#UDA66;_IrZ&26xB4dw*=v zpBkSQPl*Te)Gs=j_^I*9gsH%(@hS0OtgQFLDttez*$>9v`arD34<%z_MQ77aR6{v86vTKAW_Ogh{dN-0zFE z`+c#rKOsJcoC$=9@k#NyJe@?C5Fbo_A8ft%!S?%f9+Z0%gFYkUJ_K86OKC86O88P3kZ#+>Zi}0S}9gB7J0h zRD3-6sCXQBEUAZK-F^)CNK%f9kBm(zj@{N9T?kx7xd6fGBcnv$(Ja;vF*F5I#Ey&%TomZZ_gZ*Nj zdzc+pp1YlWW1icW9p$d^9`T;>u7uryd+~G;zx5n!yUQN?MTB#)`+gBAz2m*f?;Y<0 z?oDjh_!3gj#L|MSGC`32SDS`-SzsOWZZy zHog&00MoqH{%KLJlShVJw>NW0u9H2zTz4FOI@ifkV6JP)+@9;spqJ!2S(46mS5d=U zcPxEA*U5Tzt~;Inlk2Xe*14`5b7`*Ihgm7t9m2TIbv0Psa%ufM*NOkXUEGP#8Q7Jl z8T^WA*zBK%7lYtU;3n{OQAct+#U0~r;Er*3@Xe%Ni(UAez_J>DZPX#|K~9HwdvFJ0 z9pjm#UgNFLUmI-`??BErgbuMR(O-id`fKo>&_3Rgoc4rm;&#N_19t-7O5Ro8TK&~n z^uLNc`)9k1ox%K0Pq~*G*arL-L{5bw0 z7USpPabTsmYFsU@M5qj`&eJlyMLdCjhQ;7z_>EW!T*^~Lax29Z;~LQI4`aZUQW&<_)>TTFA}+=IUYMcj=r})+V8CVm3$n1 zZGYnFYx^_!OZ3-~MhEBI?tKfrs*SKu#6`O1E2e*>@L zTOZ*ocF^j`EiC0E(+Nu!S5H^+PS1N*MEM&2mivLEvF zmi-7E8*6@w-n1X{^rrm;{3fxttf8dEV@6DFLijOy!+uKs8-zFQ@A$v?1(r~LE*zzP zj9w@A4g0$N3>@*U!B>VngGA45+5~{$luaD zVP7Ht3Br?h8UOheUR9sai^VW=h!=dcYnOjM}-Ckm^x6^HJymWQN2Uu6UZ|#bItFGo!a;Do$ z?KFEGa5{Jw%JeoDQ~nZrvAqGjGaj?L;lrvMp06&m*V=3BWt6@acq#ZIe#4Ex8!3Ac z;bOZRU+;o{Wy-?T&aF>w(X)9=v%q=~vkuc_-oq>PicGMD{YEB*PdgiQ0`pdDd0im4mOkRg}gDDa56BPUvmIo*~1*bJA2|g zZEyUo4a85}-sV($wmr+9%2&Cf~ zDsP-+&mf!*oC@xTC%Zo8OyXx)d4B7I|F=H8DgSl-&1s~cX-C|wye!4t@xXa@0r2isG5BgdUY$^^Ve9uGcx+d<%q@wzzG`^yxZiU-Br$QxjHBlNcy zkt@HOr-LsgFUQHJ=BZ|P^84G}Z9lsous`@h%3Opm%@g^L2lF3?+6zdz5bvI6fcK!( zes&Mr*X|444}3o97noi6J-w~GZ05N0@c4KJ9wX1dU+A8c+ShipyV#w9*=`qmGafT9 zGo5(a*>)oIvNw@(Gd?q~0Cy&>m+egGX>Xxij=P1t%kYYM1tn&9U#8oV-_veucd|PI zdxCEyeFnZp<;C;{!i}a2IXl`eb_csXa7S4ZN49d+^pd3pk6Xrj%%Bn^LyDT|oLhczC@H+>Eq#wwc}9 zZUt-yzMJ#~rV;si>h0|`a}9NR())m|XdBsvwjy6{WS`=D+3qQF?l+Z4ZD1>r)6hOa$tUqyDzC6T z_(FGk9bRLvHrElRo63}GU@H^q+dRHg(Ju2|VV6<<3H*sZ#W$;vU*A@-^=w^WeemOy zS!U#=cDm`xH+$Hnq&$u{R{4~zN~yZGs;y&d1M7nGsaYGlgxsa(4SbX?H*XTM-J3iu zHwpha*Czb;JR1WMkn@xa%(Xf8b^L^`Fs~EdFmLf*wkttuwk<(^j(v^X*YRxn4EQm= zzXb1{Z&9YC&9W72Ny=pbOMt&5{VRNgz72kr@~@e%O>C|Gn$j`wEAThQT4TQ<$J&Sa z+GF?#eVcc_@E&Vl;jLHkR{AWs6kn}iOA*T3Z;i1L@Ehq`EMJiNYSwj{l*{TSc2@0*|bPd@>F0RIB~8SlF9^BX=gAA>&xe`03#HxGkwDIrH^_p^hvmD@!@j_;t zHy#P6>MvwlXu9o372_3@IxS6C6cqVz5Gm`GsP!GE zJXiG_@E2-P7A`|PMmey!w#Z0sDw*iXUMf1CC-HdV=fsyu8ax7Th(Gas0wp9Fo#JJq zlA?;&i#BF1_RHSXCwue)O#3MX9NQx z@r?2dD-Wph-+44=27~Q4S!tGhGlMb)804JUrEK3vV#a5eJPyS33-hfXv0=Nv;`dRwyQ;2Z6`0jwc*IC0;|H~)^<(cWotY6`>o~Qc?=oTHkPzvODjZ2JHY;xtBl>o!K7Ms#u|f6O}& z_K14GRf(tC9xR?#+^x7*`6tn7m3%Ra&lS%rKgK;s+tZ))wfE+JhUfXecD&LHCoP0{xaq>7_$88JOS;uvO8?EDZ zmDg*xoBUn7+O8QepSsm?;)m<-+#J}Px>kjT)m&AlbGxd@%v%BFMX0Ki53Z`ND{}Ix zt{XD;s>sZH0Qcn7uBwx->Z-0azeN5Ib+RkZko7nTZWM_t6oxX-FihMy7Gclhf+-=akb)K#h>cbSEs!4)F`f1{I2+3 zd2q~+hQfu3A3F@JQ}P^t&aTt)Y=7pivvYBFfnyuy`Mbm6^A05@&n*=>Gnc=Y3WUm$ zI7e}W;snJ@9%;&xsx$Kn{#;$&W5k~x<@wV?j84?6adKWBEKYW$=RyxQ@*IO7Qg;x~ zbzL2#19b`bO?TdFx|28cy6ynD=eqFLLx4lzUhBF&saqAN^Y|*XOI26J$&XDHC(kxj zoNT~Xaq@ms#mVzf6(^riRa`CTAip(L+-SZr3f{FYvE$+I#(QpVyh+f4h`gVhDo(l< z(us(@-i3V9h$|EacAV$@PJ|y5|9Fxqhu(xVBjn|!9PcHO_)T$^;w8nCPBdkme7#6- zLb?&sq7Xkj32yZma2Y2*IAzeQC>4n#p6t2YV@zqZD7J{sgg-jhSaeJNNW=}DYku>( zCem_|zRB<4dhTf6spsmtF~BkKzV+N#xa4~7WVqpa?i9G&dTt8bWj%K)oM>gfyJb|_ zdH+7>WZ>(^m4-5v(HkiREXBzkWjMj34Ef?8#c7@KCpUIBe5ClvU(vXcwu|+;Eiqax z;z`ek`#c>izV!n03;HqAc0uU{=+Isf&wC*p?P=hj(RPt8%P-)I`E^s_iBBW%Vt(am z<|p)Eq{&i}-|-{*E|uLSl(`t5wjMF@JlB{X&~d5kq(}65A`WPpk=B#6iazriP^-`< z63-~k<|@x2T?d~d9&@_+gi_Kr`qFC^eT7z$cvW$q;x5I*-e5i^U)n}rdrhKm&>Irx zEACcYtu&0JQS>obT(fxME6DqhwC|F+?BVY)uO+XdlcoLqTvMO6x)gXR9CUqm8E@2g zH^EQWcQ?cD)`z#A37lzW0WarUl{lrX>?*l;(Vwd1-s2p$5@)p^06#!GsgnB+y`)O+ zd(K`fIcYUXZ%tZYuYje=_C_MEQ+&hhKlzC{M%?H;^Ah>e6nn#KfxU?qm^fMSsk12| z4tKtJk$h=~y_LKTd>frFam07S``!wEfi!7>y@Q6AIB0Rqw~}`czkQZ@o*Zd@y~{6q z4qVCIOZq)<$n}Y>)@%_BhZ zGvYcQGt%073jMpMyf)qvp2V?=9~I9ies-ymj@}CN?^bwiyvKMF7c5R!yzQf;N)K-_ zSUk1(;|IxmgtTXp2JQi#8z3jRA9z3c4P1Sm8n`Fmz8knF;iMbDoi7J2hnKDB9!eG_ z72QJ4)+@S)IVG>?7NNOU(LICiUPbpTr|K0sJ+I^{I%)oizk1FrKxgvaM10nZM%tv( zq`b%LRL%##Cl4k48UW4@( zG*!hfe+qy6E?C_3XJ#6y(ovO$>oj7wCgQv`hSG^UDRPpkwJYWBgxz_8j zHgs?E+z@HRTfn#A_#3(gJT-J*!236JUm_dGbJy~&v=J(Drhc{8Nw@~h);xC`nyqP=1S7?oOs?J%|+-uUy_Im{>7Y+HuXj5FJIs_t1lw`SGeMz z;E%-}i?9E|%K?5h=aF|Q8pfA;J>&Cv`rUK=k|=zSWI+;xbIHF9{o>2Kmht6i6Gv83 z2gxM9Gv|;a{o*Uo6gH$pNH`iI>5!b`TXVM8JU*K|X=a=awB#D(Fb#>F=`}ON<8Nsv zquqT;7L*$$xS5v zkZh)c9Z$ZryifJI+f&ibmUKt58%c4b(=EO2@!%X}K9c@Oo^t|erzee&-6Xb=ml-v3 zIY^8exrU@Qa*__^qQR2qa?wsXAwf$4J#I7^&_Bs_(gM$;RIWW99Tzkn&|k?#`qc;- zR3%_Vdn|h3xlS^W>UJc$?xPdQNorYX#Y^Y?NUtF;4fxtfxFn~kN`7r5CN+SPoJg~M zjMr?J#`*}Jf>caWw5mwaBqftJyL8%*_8RNbf3J_UO;R?=+Ya|S@6u*JHjz9}ayrT4 z8t@A%S!uB6x?x_={V;Uab6rEy$pbdDL($I3b&?LXu!GUbKOm6=skLp4tgtb#F_KH- zJmt7U&?wJwhoak)gWgWAlYYCj+z&*DeJf;lZM`g0GCawe+IUH&WR^i9)e;$}Yfl!I)zF|yoFz>aorw9j*#q@7)DZ#4gR zOC&q(VWkznI~wl0qu(ysv*gQ?GVkQ2%{!4Jz4txPdzTLUUP(_R)sj$qSv6^Uc^!DP z+<8y(<1T!4dqQ_F^X>_3>?Hs0#Cy_;&v83=eRD2f2X8_^cpg$)FyIbkWOD|q}^pdXk;nZPQ zfA*mBg#rBkU9B|dvt3(CbxU-5AQ^mLe?A~ddmHrTv)w>S4zRjY(9Yj4=m_k{(;(6Z zBCVIyej9)Hpf!3+*{&6OOFB_$!fD9!o#5%@O=ozM$en0)Q$YIu(*D<}-0_^kjRRNmw+PC5?X)spYi%;+CvkQ+ zjuN^4cEQP{Otz)biO+JFAD@}Xp+i!tJy>#z?kI&^Kbqc4gO`XnMPo|Vk zUeB}AtIu-3#nQe%$Dg_C^z~FLeg2Y(H2kHrFAe@*dxmxwyC?o zpS9|wRHv;vCq2z3+%hQPZx9HU;Qe2CJIgh57jpL8j8@WFvh?#RxS!F}(@E=@{?v7< zb^h+b#gw|p{)C=<1$R2%KEqmn8$p`(KgH8I^S+c5?`BTt-xu?wQ}F3lTKb=PE&U&W zKkziopPEbezJmLdyr1IhI6K#Q_@$gudd2;II4PWKB|#WN^#Bj?+f+bitX+(giwgKxP_a1-e>?1$*h zS8zHdzuKRYUv9r4|BLuae`@}vzpL;{`~jNwcTrxN3OAvv@Uqv+f0@(@Zl2d(m`Ca@ z_Ek#0g3kVXX!5^G_#mF^wI5zWN56ub&lm1Ok72IYYq-VEw69U}Rew7`cLd($X^z); zxZ5_TJ?^Ibd^8m1P*NHYv+Rp}r7fC{FM(e`qp__+|AKP&02kQj(V=haUgxgCYq2yL zZnbX_f1NuDZ-S-yAngWeGQ3UN>+x-*%(idDy3Zh;{I+fh-?_(1i{xG_?foTQdmk-* z((d&-DfijONNww+?Y|Vg{%6tof1JP*?=C@;MOrJ5f(7qGe?&J39``p0bdTT}JyCKg zIxLTpyBMv_wr-KvXpwHq1NKpLI@`KslzANOo94tGLA$=K)6Iotu{2K}w9EZ{gyr05 zcsgF_HB=Uo{;*x)?>0Q-^;MqqHyos;-_}XH=SlQ?n!6|LJT&#&I_dUHe_wk1(hQPD zk@SCFq0GxxcLC<3`@fJI0lFQqD1MRrr_c?`cg@|alzGK#AxYopMbdTG;30q4K=%oB zm*9DFmfN}fr#9%V&I8|xK5HBI8ee$TYbr@Y=y}S#PReU`4jTAvoNhNPh^0OBw7sAB zJ=}G;4=mj$=@m(X=mCHKK|1_x(3-s-_$gnIR@Uq2Wqn5cQ!CAX>G;nf{}ZpTC4H_p z(ap+tpIO}$xPhAiv$-#zy90N`AA4P|XZSDA+I#)Y3h9VRZ%kTZx`}X`zlosR2D)kR zq1POnhCXf^cO9C$ZQLrp{5g7R`NXb87r%}BfcK^2^&wa{9cG}X-v<3(Y45jjzfo2? zbNNnMaleD5=P$kfYbo)EZQ=6KfXjEkqg5xZxnBuiS=|xPO@XWZodDep_=Ozl=l$a0 zSLoB}#=(XD#)0k~T*=e9{J+*{2A>ChpWpP3oyqUfO^jQ>=aApp{p5B0qPPYB)c_;3 z^UopuJ<7k2p4tcCS-f#m{3AMo(%SnPeZ6-{f6w0RZ*=H3#6@WFw{|Ca-Tv0-C$@0X zSZv{>vuMy-ERUvQ3#S_a(*4&R0O>hOGg3N@xnV@a?1Hb!Q zdl`2+bbCYhGU~-GT?`sXx0ypTezWlwt#NRL(#(S+?P4cA$n};6kNPkOVB=;GP_4gW%<9>$jX4LRnvRm_ot=$h1`lH>u6*+AQ()4W*H$*eNA35zv+1lR@7yvwsH`;hjU}*|BLIb)bCHhjf zm8;HwsEBrRE7#HuqU1n-*FZN8hVrx{IW1jluU*`eGCQIF-U@AK>BF~j(gCjMb*rU& z-O@?NdPlIdm8H`xeP!Kl7z8{7EFF94(Mz9Rn%dIjmR5F4uhlG_d}-$Q@tXMiQm%*B z4i)4TYCPxpy@9i{%&3me3ZWj(!y&|OZT<}cVKkGRz{)w zEInxHNLS*%%2-mW5UBx8HeuHiG_!xs@F^MID#OEO`0k9XAS08>$dNMgx{Qo5Bg@UmpEEM^ z%-KZdJSB5(l{st6oM~pxVKZmPnX}`}*>UFVICFNKIXljr9cRvtGiS${v*XO!apvqe zb9S6LJIi@XUCbdt_IFoW z`&%o5vH>Ouf}m`MNuneu>tdQg1Z9Ct_f`aDy(}9n*bXm7Io^{|4o~g5=_0R3vX-?C zcV9YSwJeXP4%~*3HM5F5b>xC9hf@ZjWuY zIy?!=qFWtrbFMCUC+vvT^>8Qb)z#-ouqU?cM*6!sBWWXxO+!nYj3OjJj7b4Uk~W%H z37~9MjV6==jv{Rgu`PhI88wDb8aSG?vBb&%WmRh|p&W1wX-5+)50pKyqX}8Sv7{YC zEE|{&MUNrm0*@w5-ga{3p9G2?OQ;BxwK4fD5tPlb;|NuNvMnY*H-fS%c08fFEDJ)d zafF&c+5VEJ9Hq$q*$IR?z&g<81VTOFIMPleRv%cOUVNhO$@0xp4;z^3&*Obh9`F0G zeEc-TGN$_QNxl!C}#rL zPV#+nlJAX^DAfl0m+Fm^eLtM+`{88Y11D2XZo;qU@Q+@9g z-|J5C{cQ?Q+hH+N{cVcxX;XY3laHb9*veENJJt8AQ|VPZV3+Y!57ncl`W`jaTRl9D zr=HkrR4+P>urpBJv`z;L?t-<$)4lz})4lye`IXrXn~t(Ec!swzc!swkcqUJKV&!p9 ztmK_Z*c-SvRtnDo3(8jES%iIovd$>aJ%Y01c(%9lcs7_!*K-#q-HI2zU@_7w|k3 zC>xmoanim@r z8qrg`>3x8S)oV{c2~mOQud^I{uPTGP*@Z_}30hTf*xaVtWY8#Nb(S+TtDeVP^9GbSql zEBIM4%lAahhaDKR*}!airDjF-M9qht{JhwSct?7n=Ecs0PV`01i`x=9(<3!6b|Gv_ zkJP-l9ia>TQuAV0!glmd&5Kx7NP z@+Hlavg#T8|B&$CG-qneB>%_Wd%$T`Ywg?V^xk_PKtOtvqEs6y*s!3--g`quMN#a% z7ev4UD)x>I#aSx=$5QXi|^`0_EW7ImneR%2UD>Q;TMdYRhL zfO=Zhf1Ru+sta|f*X@R>4|eCNE3O7$H|#FB8iHN1(Yi>@sCR3aQDP%#Q~hu!Op}aG z8)cN+1S(da+yT=J?8uX}ST=*|)ibxpv;f!QNxVV}T8VmT@enPtUbrQw9y`~dDQ=@R z^;6(IdQ(5W`5Lvc-qcSozD8}V7d4}M3Dw4WQZu@FP;IOSbrW$XOgCyKWvCki%i-!u z{glIPq3&!H?;+If zjx{iCvo_X_I+1ozaUgB8)>Q-+L4#^v!VRH8aUDY4W~kOB)UAbTT|(VUSRXSKtcTqI z*ATEic0*ifDCKEL)|SM342BZb((*PY-a~gMs*SBjJ?Rd{raTV>n_#Pr4WOQyWjFvz zY{8STKa{9;CDg5tYFEN_pi8wYVP7cm0{X`NK5N~SgIi)ti}5H>H$$Grc()m-`yNll-V_|cIC(1L;|Nf9NJ<0p#-Qr=6vopHLFpMj z8G8dzb$W7E%O_{`F3s1&7`auO6SMlAnAP}6S>2sPjjqRdubMq68{bc)w)(>vs5Vc` zYV*X5ADEEU&V;PKCS)}z9o+rlFw}NV$Xe40)LC!bs=E{5NBY8@hyyu3Yc0<1%U*m-W`;XdP|f-b8~(XViCeMt9Ny-U^;iG<#G=vqxn#D;?m? z;TJ{kXrabFGNW{9qizC!sTMOfYb#^3Rw7;14dF-C=8ni(+Ywnilb+>zaI0#mhi5JI z@T`qW3v+F_TebDWvQ~ar*0QC2y9V5__})Xa-r~@#hd7kyDsa#0V-CrBmqW51MLNVQ z!EKALJ~->84$k_ggR?&ApsZIrDC^G-%6c+sCy($OmcH=7tp7VOE))c zUr`*Dz2kk2NE&NY)+&3AHI|giW%ZzONwuO-l~?&JzD6HMX)3R9 z(aQgHKJ!vi38<`!?Y#U{jw)T1tIAg;82|sc%a5b7wErwum9L|Om6~W)Uzw*SYWKJc zzrXx6^E@sujwnItiFQ=?7StR(|Bir<-Yywu=}^&(-YH9*^2CjNjee;DzZk&4bHyzE ziuiD=cJ}L)@Tr)6rApD_tDHGdIVtI0l{Cwe=d#4fTb=Tmw=8{M-jgY(dHLj&lDDwD zRjFpx#zZZ7n=Hi1>q~W48ZG^2=){oA)lHvEmu*>S@9)Q16*?(NZzbKUlIGIi{`cEd zS<)#BU6m!yzk>!=S3g!rC+~st{%G0uRa!eOP?W}!f9>lEq08$JOOLZEv{91AO1f7i z&9czR>WWh~T3Yeg^nZcgRu@gK3T>36v6AjpNpp44Qd!a|&|5xYmfrTu5@+S_>AMKT;PXBk&=kjQ8b@6_yi-ybAH>!0k zyK1NPyOQg4ij(`4EltJ#*EPVh&{b*QzAW!omUIezqbP7i>vb!Nquqz%_45Cjb=`kw z|G7MVvMgm=mN=_ICt4>i&|69Os-#(#JeMU-S?F_RXm9!Rj{jYKPg=<{L}WRY~{%OEgxN_Wqw5 z33g>i6s^izoQe{HN>9&ImOM`fY0zaQs6 zMPo~UW9jt2hQ|Jzq81-+4AH3`{uvP8$(NL z*9GcY-E)Cep_7v1W=Z#|q*)faDodQQ(UnHtT>4P)|6h=oTOM5%XnuKdmM+@@)h*4x ztuFd38=WW*rL7OkKVK8hUAb&$+0xXT|2Nl%b!u5>m?Z_?Hj^D~3*9H&k``{8tuyO1 zpW&2(Buw+O&h4@@2<`A~m7QMjoKI-S>4YMrY%72|GgOqF0x06SZFUl%C_4#I#5o6@ ztw@XZ*$Eu=Q?4*>=OX<9TPH$JrPMFl> zOo&c%>(rLcsp%}RPF>gL9EeVPcchec0$e8xbPA<5r$clqybez~Yp9dhYf&HNK%E-b znQWcM?u*@?T1#LeEI)Bxj}V<{)9ED1Mz`Zz`|+%k+Wn|!ox_rxbUVsewXRd!I=kJU z7&@&zAZtNIl%LK+=^S?h>RcyK)Iy3VW1XDRneK+vy~mbJ+%4 zC#`fsPN#Krs%<#+sWUrGF-@rXmiXv2w@x+=##iUQ2SXP+=iMB)&dlj-m(G3<NtnK-AeUmBuj4P~IEDR}9X+WH|mh9jViQgZKuWvK)-Pepd49<3F4nVgYpnH>I`EOQ0M;IX4KM_&?3rI=gOL4 zH>JEqUF|S!sfYgAclFCqryE6u?LeIfTnk%mW1XxNbkb3@xE3X)v-vGCEugH*_*BAl z0Cmc+6_nEl>_d!-JnQUUC2Y}RCu%~cAq}QgMrWNsovpR_tNwH*(qei+VLE546Sq1c zs8hF&Pz$Z}$S6Zv1w@NoprP&=C8_0z3cG;aGMdwg$%yHerR_lV$~xPj@kV=BdXk^k zN-VzWdlW8-jyzO-l0u4ol#arbN+E?jHNBh1UQs%Fb4B^dPxj=$o9C*KmppHJzbxsL z<-784%Ev6Fu97NzbHSba=H;b+S!1noq;nvJlTC`Nc;Z+7C)3PJy-;U)F7!34lFwC3 z(?kEQD1(;&EKQYLE82i4B|p=p^G^9Wu8PpNPFCo=NTh|UovC-OOeO*5s)= zrW(D7`V;jRwds4*^QaGNob@=mVOFC~eM~)Cwt55gV@<#&Jgcv3%zsPXZUolmza_s` z3#`n4OWJECF!0}!GF0nOix52)XhUTqsdCYKPAO_p&6}&_wL7lxy!>+d6;0%>JT#{b zx$_hirl&%CDoNKR(^;CP@>qE)rMvU|aK&)?Yp9(+8EuzD^8>qMmOMKm&&j5t=x;Z(06EN zCQd_NshZUJWPQC_ZB?EeM)h2>{8b-o%B?Krrc%o3UFBCy=WFO~`Sez@?XM}fvbWPh zA1q2M@Yv$3#c9{exbeE6IP;vB7QbCTdv6Ge-_B6(Ea~#cpG!N3us4#EPEWu!Mp0p#axDC(wY)CVp4zzI1JRC;5DVqHxjC9CI zhlIz77b?tXG>6qpNV6V|otj%p|5p2drku}XT=uR~)~J`yhZIw3DmCe>$={Mj8l@(U zUiw|7u3RZ^;vn*wTmE(8sPk{s7wS9n639zNI%`xqDxFmnuM)L&C zHZ|u|U21Nrd8X=LbRcTTHJ(V%Nj{&<=Z$@MF3cG7`Jr@qNl%yPRrDz86n7$>HPX{1 zN|i3JeCDUQpm><#nP17-p7eBy+C+EK)1~>Fba_czmu7CFIMI|SE1$6q#g)(7^4VNI z&&y|gIpyTkBAs39Gr!sZN@$(whxm82uVq`7zEdr(WXsA+w`BXuzggc|XkYo4=j}^t z0@eRnSH-IbYF{dmye!JrzSOdE+W7aiFHvlV60NNC_NDf+;#Q`WhvHV2x7@#OUxk*X zH^tI*2weq1`Cqz6yyFD2Vop=D{cMJ=t+ zzSO%Hx3U$tFVR-teqvZt>6FIB#Fl`Xt?W8{*q8YncUI zMD0jrt*lR1-AE&m+HhM;JLpC8DfNR|+tZk$b-K1tQY-pu(NimWXSEKk))i%az1DrS za-tQv##w)Fv)*5Qy;fS*&&I*^v)0!cdURP|Y00(LXFN}i5^KP->Qy?Z>f=_w=|Rnl zwDKceKhgoDRfl}NAyDe|@YPz7T3}r;*Lx(bM;htt;#)53UCYsG#kJSLr#42Ks?^h# z&-&Q%xWwP9C#Xf(dSGqr3WRD7Pz(QxP)09M6jBkF<_R_NuYr+HD^W`&OvS9{9tesO zDrb~anb1mE-!TAGKP+8W8ei2{t0(CX=IcW0xBH+cr!T)FU39%MefT};?dpZ;O}?eK zt0$%x`Ig?U9+;kd;c#5tDWl49KWNYhLZiy(mfRTAKQ5*BT>zW$Im9VOm3dDwUR)R#2$;loptlP_9a?Ii>~ls`0fMra3gK zexWHwGjWZ_O)yQNM~%~sF-@RF@fwXVjiE*H7Y#9upuB{uLDnnP2Q_aKKT$8Ey~2!D zvyZwMtpkXL>tHl*)oi3TrjBXeJa1unYf~%J>YjL~m1$>cVR>s?x}E8F#Ct5;+B)H1 zXlEMVmTh4Tp@xRU_^Wmn{@Kp7!dI4dwrmRd23tK&epWE=FJOpGpz?`zrui;=hnw)#YJl^8Zq(~n~xJ7I#sLIs1Rte z;z2YXM5s=EfqMJ|4XTe2C68daO$HOzM@?V^#jI z%g=vvS*hlfKh@fQTRrCcadjAR`#>=oed}U0o6_i84QMy}2+0ytZ-L0bYju`1~)#xidksaX{@|nI`hxA8wVieNsxJ%Z83c6d> zvZR4hx?9!yx@GN7S}LW%ReW6!P&-a)r#&;OkhV){x|C*1X~C54R?&;}Vro9DQLz@L zH#L*5x~!?M{~h&}@5`vBMHiC8QBAAI&9%izmzVTovNF#jaBqTcN`q@7aAW9O zbAu{SSWi&=NEN87Hz+P&ynA0zyt}m6if_+(dU5$8 z*`sufZ-}19w)h>6IRYJ&TDy^U@eR=Y*cRVy=<$YunuTsd$olAcY)hE*jSfTGV_TlL z!!U0PVY~TC0(gS znXc5LOrL5|rcbrVNCRq7rYp55)0JA3=}IliG^sWuRcVMVB93&zs%Msd)P|W3)rOf4 zRrQYQrE|#=Nt`sM_mqT#=C)0+wUgH>>!n+Q;_B5)t4CJf+!RWZ)@kWg--rLU=zZN6 z+z%h=gDuK5zKX{X|DhFyn%MO+n$S2>6St^DHB|!?WhkH3K~Y1)tnM2^!&NgHu8K?A zSF2`vTB}08RWnMKOFCPtLd8`xdX{TL(x?hnrG_`aty!dKpm$d0y|cRLoz+qAtTuZS zX9Gf2r@gZpcNyiojPhO9=3Lg=T-MGUbv>F^sycUBJ-e)KT~?otHZz8@QA_EOwUi#T zkO8>WQhH>R*(0OO9{k#%tV~;iDsO4ul&(MZ5!$s)p!9Jz%W9@sHo~bETG2+U@pdoj zOq`kel}Z@R0adrEt2We;`k2a?O4On1DqrEKLasga=Lu_!uWG*uw&8mn=m;}edpG2_ zU)DPqXuKEne<-ngfxUQ^w*OwVo+H3RNTU(hh_HikA3_@&i~m8m56)U#FHk+qf%qJh zwY8p5dSjl|zIsCMjd_;F{+`fLW1gj@zbACnm}hC`?+I-+=2_bKdqQE2dEN`$o3_yy zSG%mew9DE{J2c!LkIxR+?J~-5mr;JZtnIYR+D^Ny?X=6u z*pss8j@#1vbO+VfsE6v7^+w&YUaV`@V|C4Xx-MC-*5#kQVdsoH=t!Av2|Y@)a8>fU z2kAA=T68Yupt@6?B*LHVtT zslm5MszI}u2UpPIZjF zMd{SQs1}q?O^j+m>8LIO=(8HhYeA`LzNxxUITUI{G6nU>nd(BNQXivQ5ZyJvXg(n- zY)C#Tfx1b%5pInMswGilqbvvFp>l3YEkpT`#EV*sa-+Ufe3bH`@6UCjCT!(?dGG42 zLJDdZCEv|waQS|`T0`F6)OL%hT%}|v8!NB&kcier&ywK~tryz5a;QEar@dkd7j0`5L2C)3^@22ua;Q~>n&hSeuF_~yzfw$@ zYHKT|$V5Iu(Cc0h9N$waKme*h-jsU`6c8xax!A^hA;M z$YZ{0q%|y2TrSa)%YrHAg*@jc6%q1CGw$R(=k zWxpI14{nvqgYdu16fa@xyBjb&+XMd{=;ESfG*uTm=>aSClpRg04%4c<#ZJ|_Gm0w+zy3==; z#v7=Fin-Q&)GN@~ifEv$w7Q~nO43rEAI-1}{B!YGTpItZ?<(e^)$=H|0#B&aYGX9A zh-y}ie=cy&>VFD7Pf7lHMSW~p+Cs^GxFk(3?Z13}yJUM=mRHZqa7D9^!n|X7rB|4D zh=a~KYK^3SJ^NU;^a{MR`tj0u>3nw5h@M(=NX=oi!lts9#I5a+J(L$e@p zN6Lj}h8kh=T{`7eGXc#5G=mZ^Cr(V1A^OmMp2jVWUYZSyrd0ak;xxz5I4HhOGmxC0 zTpjblm1!4wix52*+C^bR$Y;?jqP>!QUCDm0q+8si%2p*=5u*~$dC|IA35z=|kI7}) zRkk@do9}(*GVS7V3*4{DQ{}9@sr0nsp|Ta1EKap5D4tns6DncNmP%{me>F!gNu_Gt zg_f=n?LWa|lpJ$aQ>%L&V`X`md`vG#nW|;xt3NBIlfsy|^!Qk^|5=$jQaKcQKBUVq@~YBRkJ16SW26F7G|9e3ehZ7t4w8` zd#WCbXQ0J%&%&&;LN>l>#;LhzVZ|w5Ytqg_VeVO&byi`nsaa<;dd_?X+Kg{h`LDh; z#*(9aS=y%BL1Fc5*)>M-pK2F5-D(w8oTplYR#7!?)l5Y*pTatDK1WmC6|V;W^*XSq ztgy;cxRXuPCfceDirNw`ji4HRly1)PR;A`O5~+sNgJ|ts^sA9dxz#*FsI`%Neq7RD zdDnMque4&ulN9(9aU;ousS!(kjQSzXpS4a@7(K;@EX|*2JXL?D zeC4C3@-HqWUse7)>!m7>!m6qI2XRcRx?Y-7uga&u~soMPVMKx?a(^nV&OO2^Qamp;bchJK8nWS=*94SXt%*TBpp{ z!?YVzlKT?PXjeu&Sjlxo^mf^z zx$5hbg8mBq-qLid8q0Yu&C8aak*VL;JWacRdB0aYI}>MD-0z9Q(`>DHc2+zuD{V$5 z4pOtV!n{nq-?Fo_oYT|Tr<^NXBZa=Eu-B>j`n&6s`Pi4QQmRer`*QBIZ2N1a(US7E zqBR-yDB5!=>_@DQF*N7>3Ok-Fx6WC1TGhUTzEC?R|GF-x6*-N_>Z8?nD(1@2t>PEP z<&y4_bh|qEHt1tm=BT`mSPb?XUUvm7)2v>}4!VOQoeRx+pHC()o~* ze8Td|r!*QXZI5_aI{eo-d5@+VEXgaDq|cS<(+WGGI>8`$h{As8%Jylw{DXS7zupfm zIVUa5Mhp9)E22-e#lqfPVOMTd`M{N}-;(l0%kqJx(a*~E$tBY-3w^H6^i>vGh0*M| zw0W^O|HAB8+(tP}RZz3!<;{y%OwYw*bV(X6N!z8B?O)ZM@>o1mD3+XAUfW!m^jBBk z@>g~DchWD+VRH!xIEdj!tOv}4!b(qU|!DuUcPa4^`(EcR#TEcEX!}@^s^$V z#j@6{&VotiMSJa%_tAQz&WmYAQ488u|6f?IR$Z_BEJk&t-7Kw4mXzDf*VzAR7Nfph zyJ$~-D?k*IQc>!SZEubB7Fd0(B=c`->cF2z91H zJKkDr(E6z)y(HNs`E2bgNTy42+uBhOuaNUOlIoVcmpF-H`L3ML(SDg$Jv2+zo`P0G zw1c4aH|^Yu!zsvjX;nphPcGlJA|9Y5o#g#+Vb!8|PFj*qmR(OMZ7!xdENwmNulo7r zrN6p(4CQG>bNu`igrq*ik*LSj*XHsbrS-8Td5nCHCZGJQ!OE=v7iLoG#Z{xZrVXuJ z<|CBOS4d`{cpXV+ytJ08y2@)%dyfSP1dTcc$pp>z@;b`TjjIJ}UsoqV^7gCNsN5FD z3+-_fpP6b)sL9TMN=Jg?7PR17eB1M$bR;Mb(q$$cXC7Z^43v%p=@FF1z{p8QX*lbY zebL%kxvq^n*N#x0lit#|EnR^XzzRHf)`IoiB@T~?T3*z zOKG+3kLkx5UFo(Rfa%XkUFo)!e)#%eJ$!YZe4ts6)~(a!I&D6PRxi!#4SAM!i$-80 zo~7+Vx-X>pVknX>O~7W@Lvan^+_5wW4mY|bU^r$N=Z>4>TAy>(%{hH64QCs08n^}L zmRsVIMzfZj=9PvsX&q}tovf*^HT9)_YfbxF)4ta9him%7HRIPBeq#;4v4%ff!ym5U z=hw`?{@wGhI?R@(0axoU(vd68xYCd--MP}3D?OajtgCxIG%uEZT}k5UJim1CO8;)+ zS-N?pkymR1($=dp6gpEOUB1%bD^0%A@hh!P((o(YztZ?C&A-wKEKR`D2rON}(hw|7 z!7Z~nvh)c{SE6(ZOT%zA=8e)dEX~8ZZB9Cf+hp_QHrX6GzgccYdd^GUBarJk*V=$q z0hZQtp5J7U-*K=i_Xy-#jJt{K-$iAx<9{pF2C_+{f8Y3J z74S`2a3BAUzOi3m*1U&P(Zr2JuqjsKiSNi+L&C zrK(#Wq-|RFKeXj5O74MbFV(^|YR5@?G5S*NuBzA8_v-v|VFzE@V2XF}OYS|D+> zrLt8yt8BF^s&ZDTYPVG7EDlwCs!F|3wkqemY*o(9DNWsWQT?CXYN3Q%{9A5&x)Ht{(NO_ecFBJU#67MGq5awx8pbw>iXWY##FZ>W2t@*gxi_ zAL}u~o0tc^XzxKnAM%eAQpr5vRbmg||Db;Yze?tQuadkU{|Ee&_*F8qy!P>C;eWrs z&r1&NK73~RdvV|AwNrbq?`S(&bcAC%*|qJHymb#D_xcXDBYvInS=)BDPm$tUwgWz0 zaCf%t?OM3I;_hO*+Nb?fz8!w-j^XZVyW3~{)4n_IZng*R?zS!11ANv$FaMvTf}1{yAUO-0klIt6{gcH~8nl=ZR6p+~x1|lBK@Ox5B@*-OAqR zZ}3~;Ze_Q|y_FqpXZjocXxv-dZE%mamCYUgc3;`t>F)rmU@tH?`; zJ@9Aj?@TY-8|-cSfPHLVu&-SQT*vkU``P|re>(siUy zFt`N!2Q%3A1b@W--t;8@-cXnIYP3$h<&TbdCx!uC<3hv@|b))R&b|<&9+XURi zjlvyStCgCuVnic5^$rjqOHuNB0lx9o$BCD7Yi` zVE2*v*bFA-?rw-%Y(6qW+-GJn_z}Ki+)z8rj&VC+Z|{cL;ounTp~M;DhPtQBXJ)8- z(mZ8`fkWLe_k?-UZ0ELj!|isM_3dzchPmPHar1;(9~|yB0M`c}Gmo3k%@Etmeom== zXTC5S+9CD}d_Ff{nhorR_Dg)eFkj*R5?tSIV80^m^}%i3cJ6ENEAzG4#%=4q0lzli zn9*(<_bvF1`POXhMmz1}-cKKPzj*+Bz&r>(XdVI|G7p=Uc57m{09)D?b}P5FYXr8i zjqH|gE7uroWE@D#B{^It6Pib5nu=G?tH<+ zrn`IC%m!x@qX$0ST_0j>0L)(I~?Cn}$ z+Phz%-%6$(Pwk!d$lJL~8SJdR47}7_X8y#!#9WHkB^YNfH-F%FIp#8Rv2oVhi_In2 zSD4=kxdL;!xyX1M>_vooJIVY;$Rx}a=0X$fFW^Pk7nolOxd1cCwB?uExwcOG@jGsR5uQ_NIzrJv-5Q_VDRnz`CsLFgoZg`aG$!hNHeY$p3F{ng;r<{I!C zbFI0`Uu&)duQSuZ$vj<7%q#rmex|w6Oz~Iw>ELuT!(4{X<^D2%lbLBMyZ)}Bt?X*r zT3|z4(^hhoT`jPdt!=0J8RmL3)lb2`l=zqVOa0B}CR5Q>ams^7vXcUzsTQaZZ#9}ISH(6tJssliRNTe z$yTp-mOKP4q>fO*Ve2D>pP0IZQ_X3nTR6>} z4tC|KZK&$1xVHRayHGA&=dbnUh?!D(+~rb*G~Hk4E8s4lblYfC_gkFKbNA3KoNl^f z&H&FaXPTl=%~f?pq}Dd{2xpqJOpkDuIUDTGQ=3rN)pKn^Jy#8^M!a9+3_sofN@~Bw zUG44W4zr8h)e7%0cbeVs+12i5&o{T5o$W66PVi217kHPs+w5d7@aOxT?9Nv1yD8;= z*q!Y8en-rC;6JcihuW@=YaQyix?o*?bqBknJL`a=K{N@-Gew6;d7xq5Z5{WK>W`2KgW~( z_2BjXmw2)56?%q?iF1)XfLQ1FOYpha?$6UXeo1KVTDT>lg=-16bgjTvt~J=&wE^3> z`tBU!Ut-U(y+g0?Q)uRzyPtS#N%%Q5bqb6wAfh zF2&ZNRYOLhnrs zv1Ry^IDdri@&7K?NQ4*{J^nx7^L_jwp6XBWXYYz z4c_|1>o%cJ{KwcI66YiTq1UZJ)lzjrE0SW1P%%2}g+{f+dit;ey4dD5cjfs+X19DEN(&x{{U`^J%aN7F^=Hrhgc)ljLpKv zJTHkGf)l`M)YS3*1fI^MoX@gn+Pa}{IDxH`E zbbjRw`xZWL+PA^Cz|Z|>zFw-!uhhfr<=?^QZTmLA_>O?)A+^H?P<1ts26S~UK8*Z?AvX1 zDCTzJ-)0-9z5PDEaoWf43pU~DCVR7O67C?*?e-2^HCBsv*lMwQe2+BWwRhrkhrP?* zM4U#caoX3D&H9LMPZ0ZNtzYJVcB};KSJO+m~%8^CEHQ+mi@A(LQJ&vW>z# zd|tE@@j1yp08RuOg@)k)!W)I(37u!}$8RDy(VlF3vfuQUpT*P3b{6Io`<4IQ{sDf8 z{ig3p=!BrXvk8>*iQ!K|{;>BE_Z09Hd#b$`TX?EH-hM!yI+_pc``BOmKUqBb+JA*T zHy!Se@Xx2YNqB@G>tDcUZh9dd<`4JJrRURFaI8Pl&%@`1G%p?M5A)Ba=hBhjk^U(E z6h8CPQ|S@r&(ewu5;%?e7opv%!bcY-(;l-23_c{X^*he<1iU_9DBOn2)4Jgg=6rot_|t zC&7dK!T!;nVj6*s(j)1y^iVp`KaMRt$Ul)D$90fDl6;;Jjtsi3_bBkl@Tpxy z%17fqD$GgsNofw|(bR)oz&HIk{ErR~;y))HgL_;!hBrExW5Hv>v08?xXNA_9x+Mmfb! z;T!+8KPY_8uO7rNjtvWfcfZ*M#PzN@DSjTCllEuvQ(`U*i^5$0jbDWO({M0v9Rz-B zKer#?zbG7n`(W@J`>nl=(s(f4mYQPU4&DZ~#y*tLL&BlqYx|A81E1T|9jO)e4*s?D zdfE}(!SCo_O|PYY_*c@a;H&tK@vo;B(-^-4_D=rg^a}V2VcQe(V%i=v4)-|v%sWZ# zj&x^giM<_u70u56rSx*znYVWGx>4s1@D2aEe?Pq7=Yn(n2VtO}pI%A>iMg}i)^EpK z>-sCx{Io9q1O0lq*99l1E7Kr`K|HBWtbuMOBHHB0Y>dHx0e9yxhG^!J~~FJgb<_w)UIb4tFq zZ=PDD-n`d54Zx?rAK;r&AH95U-y#hm{lUH=J_Ep}v03ctd*R;`(-Le+DfIMrrn^!j zLL2%3dV`Y!(7bYJS?yJAmEL;Wy6EltI4 z?$?SPVsm0P^PT;DX;$h?-22jNr0{CEg}B4~EtuiHg>N6%iY)~bplD|0(_v?eVV7DZG3;zcGuZM~5YkMeoXgDmK?7p&J+mrE`=uUEng~P*1 zZX)(6_@C@fabMc6Y!~w~Z+0=S_?LYb^QwOZe9gZKcEvu?9UhJdC-U~;;Z)+E;!bs6 z*e~s=?mPR1y(z8lH}E&5o3T&B=Tvu^``&(MPjf%m@9hM4qB|l?z}y<%p^_ZcH=N zhJHMLH;3_ET$+jPNf0?}R(U&!lxHsqPKlMVvb^Kid}xeK#EAj&(D@8R7bHN7&o# zjJrOJ!`u*V5Bs=%-R*?$KMj!Lb3 zYkxdc`#?ILH11DF<8u_)KDP8nrs<)lIdo4wNTVmFN9vZk zWA8|;nPErFb)i=lwre=j9p!fAtzAM_VzrGAgoE6{?tySW_6~&Z8g>X{-I1Vq+8;(={oSb zbaR{;H}o6%nQGPWtQV&zt z*TN6oefZS#Yo!jPxn+2eRJX)z7kZLfk64pfoILcSh}8g7-`DUp@oAsdB7SwADwuYu zJ??AZt7qD4Y@JvoR`b>IzZUm3_FCIG)`@LXJK|LJ)$p&1DQ~XB|5|&UZ4?{Fx$f%p zyqoK8O;@KXUVDR8d^z?At9b3TR`FG_%hUe84duf{;bQP&o+|MC9r#`N9xTt(Y>t1jZDeY(R zy)!=Rp2L3D-5KwS^W5p_j5Lp!FSzOC{5m_`Hi!-5blWgCisi^#`A{xg5H18S3Acqw(KY%~r_l&zM-W{KD&tkvmPD`h!7fE@Zdx9JtWpBpkMR&71HJz58c6Y~n z;?wRKY|iTW$c}1dU&YUYqDO!u{3hTgep7H$zZtlh9|?}6#%9G))Y+`q!2jrGkk9FM zcKp#TakJwr>|03xX7`l4C*B*Ma!+HYa0Pi!m~x>~_$(|2KgX^_u0IDChr03MI6E$J z4`Y6Ex4Ki(sp(eIxy3z6O83SmG55uXi1m|u2=lYMjX1Z0C#O@=6U4eNK7si(a`M{; z^B{45b`N5Hah3Uny0J2*9#}8dk1Zto{fLFKi#v${lk5T|AP2oob4XL{fK+iJrn=rK|8_HuBly%em5ZNpxKo}11|ce`^j_qfMn zpnM;XPhjs!s11+B$5Bmly?e|)Zf|gN>|@|#_IfwNUGE;ZGcZrs8{MOJ4mgLfJ;I*6 zHJ$c%l%4L5vPXk6c$(=Rv5$g}67M=U-5qVO!;G^xxhL%-;3I^cm(ET1xYONJ_DOp> z{x`X6i961ofzRpg4EMBs%GL;%+bh5;>?E){PbTah_6P=J!%f^+Q)c0}qKd&Lo{SL_Y;j(xyBu`k#+t^=+U`+@ypf3Sb-1YS!{ zMx2i-&NiZm$+A94?a z54+j!68tBnOVR`GL3eq&BFzS8yN}{X(%dYKOjF%7cTu`9%>rk+``u;f^7K)>4D)fk zn71xT7pIHT{qADS1MbpvS^79$iuojt;@y#HRGQ+Zy2s!-UkqEMOVcND3(WiRx%e3L zurZ;d(#Gj3H^prPZk#p*H%ddm4bxC?2sqhYuVSnsl_zX?M(j<4K8B>amP3odq>PO_NX}7UIku7*bam|W5-}WV~>uL?3Lh^b}~4b7{f_z zSlT|0A#{7pvvwSDj*jDEP0Dk-xP5#UeAYf^kHKeL+%`T(9c&xVap!{D@pNpgMd=?) z=rM7dc&KFwoPxx!%63eI67^Edo<>qI5->_e)osr ze|X$9JQJP`n_`{=p9{}}&xg6--0%YULYN263v<9ZQ23xQn0E(Ze)HeD*W+vPTlYqM zJ$~c9b+3W1#aH9k?i(k3HNFzRBlKJMoqI375!d7G-~49bX?}Av%%LIG>n5xcTm#_-_2ded*?cbK?tff70A9-WV@)m%EpUKi_@szHl$Z&oT4j z4TN0oZopgtUg0LWYl(Sdygp8H!_)PIPjUmpy5UzpDm=+AkHU-$2gGlE9k5Q=KVC!p zYr#w1Wo~l3$X)Da@b>UD1G7H3e%c^i87Ie!-IbV2+||UqCSDz{jB;P%E_E-vtoDnxjo0FeWVe{|=_JQQ*fcT2r zGHsP!A+?v?Vp4iBF2>A{Q+aC&xE0hh6?1{RE>0(f>o9}U7U6Ny*aEY8m=?Dr)-=r2 zco1nG7+-bUr7hE|r2L9oM5^=SBFsy1lkgbtZGzb%Op2r8=5Z2c3vdh4n1q=Yw@=&g z=4)13-P4%#I{3PK!|j%KPr^6cn{L;% zTN1wM-g3L7U6b%F_qH2le)Yfjk=zLWi{BjgC~g2BNKI|V^UvT&>@D!woZFWBhXG*= zGaw8Mn{tQv&wfjMw&339@BMdv7xSIpncKblhb_T=p?}y3pKtw6=39SI+{x_B)2_ta zg`1;yG6%(fU=9Wkj)%nU%@6*2zdfP5ax-|puobvY=ofY*?jdmpZk!e#5)X}|xvBhT zKN|CsAH#jrhsH6OedBiKNB@K0j&!!?9`T?260cjufAZU!CH_b7N5XW&_!8ec?V0vU zy)k=(d#8QCebT<*zG=U-KlXm<0C4}biFwz(=Qc6#x%a{M-3QaB%9AMv(F*<{^}grVY)G=^x-f(oWz` zX=iZfvI=Jf} z!p7kr@$7g`{0HV-@Z5MFcwRgo97V{n#5snW%{L4ig$wXIKOTqsSnfC9AZ!>e#OH!| z5qKfE5BA02Md04pyP19CPT&~qOYpfE+zb0)ZZh8~UW)q?a8K;Zz)QhBun*!k_MPH^ z+`zt5Jb=5`g*(NaS{?*SIftuM2mLyTyIXzDBrP+&%7Xb|<~P z%|6(Bnakqk;NE5ra1Z?+x3OOyhwvTa(ReZ591kAPP3%K36Tk`F5cG6TPuN<58^8)Ei= z7EeU-=K?U=U(H_ZnjVB%8~oAU6Mn-i0Nci1sS`8kJ!v%~aP`8~mf3Xk=9?n_*A%%x zNr`QSds8F@CC@a{N_uG|{+l6(CmkW1*iErV*;YsujUsfU9bu(MWCY<&%;vTRaz>jI zItn>F=^ELX@Wy5f{5Q87S!p8Kh>%8ROMJFKvQ2tQHYB8>*$SU6?FLr5Og12-0dj8A zZn8dp_04c3=%n{#ICxs9VNPeC^mObqFk2y+H{8}Wr{X@1eb}v#0zH%Pt?ViIoXURg znPF>tGVW8@3qA|?*_hFGB0eXFbMPB&&&3vwMqc#1aBkSfo)pf@P*R+A%rMfgV}|le zCx(;4wxDD=Cxq>g+?)_j#I9|I*rDK1VxJJUM=tV&Faf(3GL1vPA%q2id{kVBTL6BvbiQSQ7f%7V#&rd2A8; zTXy6#l&s~C#90#RuuDI{{($>ORtY4JS(lZQ0iYx?zsKhX))4N(t{3Y@WHWJp&+5nB z*!6i{*Vbq5JkWlN&v&eb+=JbKdGxyW8{FTrf_X1?L!Q@Ty`lm3*Z6$His)_FjabK6 z&$c#=GF*?`w>FJg)o5+l7XX{GKhWAVV?Uv_sm0F2`P9NhRuOOG{hwJQyb-(+_n)jS z&je@k{0Htok>k*M^Y55H0w)4_pEH6;0B}YSi2={vZW|M@+n9OTjQ<629vq`)%` z0=$q_iDy_*xe&Y<`x(}ME(R~feukCZOTo*rpCR_;@SKx*doJb$xX{VCo@cH)8NT!? zT+gvud=;E(4RbztKF<%cI(loE%{)b@)%1t5HR*@&f0()SY}U{p$=1;yW$pa;@F;#a zgTII0!h_kW_JhQKh&jm&o*&58#pfX1@@tsG9Q?O11!hWq!wRkT+_c2$z zM(YU7&Z@<0FjeEV%;u`b>zLmOtFkip809zxF6$ZW$FZk?Q&^VD?{QCI3-4im|1=z{@NQNk=D;-z?_$-Yh?;DJ^ahJJvB)Ika*9kjq;`r- z`B;uM;5p$=rnr(eUhPMWftP9 z96!eY6S$4(*q_2_REi(r{unM~2KGbDq;G{kl;q7K!YjoO@&5=;Me6{IT}7mk7871E zE^s&Cw*d1Y{B3#i`kAYMe9~vcssKm-8DI6ayOCI5V-~>Ye~!;LZYF-;V7_Kv@C82K z;`0r&j4yG2hgVWZLy!I%$`$r>DmA2OCNFbl({;HT_LeTaJjQvIK>BR>?G ztpx!&_V5Y#31J_YFIgx4zV+KFz&HTxg^bsWaL8+!7cm`>r+<$nI+&NRJD9y~e^!+w(bYeb5E~F*X2#nA8U0~#Xk2JM2=9l5We4i8-nxTBl zyGARoI#KZ}_$w=#m6KN7D}j}n^}S3ARgj4~%2vS~Z7bqm3CTUJ%~wTw>S$X5PG>AQ zmauB6Dn8XP>NXi={OrOaYf#_Timr{A5m zP)U@1ZvMdir!NX`Fn2EsZ!%vm3U4t}FA8rnM=uKRFgq^_^O(JTgtXY_NMU}?nTxjJ zbyfq~h9c~C;WhUv*cQ88c-3_@zmulc!gfQ}R+7^lO&3xqLZSnF;@{%0*gXjC8ER7l<&q@SJDTp{bxtjH$G=DTJ^mJVK%%X>sg30I>-b7m zy`%Xf{*Hem{2QmP_;(9`^1P${6KUif?1%m%|AqMw^QBqK4r4aa0bI*=u)~>UG~}&D zsl8px4mIsDLrh1zK68(bgm$nE2yK}9hS$vNrY|XX4V~-;%y2ppr=xAhIj|w79cD0d z*w=`$Hldw3Th^1AQCq?XgM*QT?MLW3VS)e9e~ApM&bEvTM~7YQILvPLDDdcTOxVr- z?vDxMut(r?6m!>I?5=i5(D|n!q|gsJDXsqw)VbSv-mqHfMd! zA)SA}=}dj!&sz_0Hs)d8y2@5JQ`mi}ZW^SitT0zMlQCD>5Byi=Ib?PhV9(;M`@uGx zF_=c&25B0me!4P?eFrIZLRP*L(y}ANFVUru{MIOTbLyvh>1y_L>ZeJ>ywcuB3bV}d zR&t!jv&&O2U4j23doTX?nG=wysGCl})Jg2Vm@Di(_}^dzxP`#$zD$c1&a$6~sH$6&YMSDGVPbuv;Tge)87=~-y#*IQ;@K{ zo$^~7c^;kEL$(LkYyK6pUXX0hD`q@zcDLh^^X+Ee&CU|O>)*phvWPQ&FY7Jj%wF^B zh1W6bhBl;Gl-i_Ik;QD2PD2XwCB;OZ?{!w5-|z!jL3{((z;HZr#NDkV{RV`$i1U(f zP5d@#zJC*+`I!FUZT#QzZ~OV?C36_k%H8cdoLhVWx!ZTKZ^Hj=Uo*VpU*J^Ze4cw) z$!YemhY_;{U)U`^~B{fnGiypfnQk&Et5$x3>&ht+<;JaYq~HzGrM2tIXK zKc8o=_w&q)V4ckUA~7Zt-owuDbwiyn1OMxhEpNfEO!xJW9iEQ=4Byl0tWi%pnV8MV zML%M#i*NY6-T+evG#sN{G;&E^z;GH11J!oG!bTPK4j`-z+*yTu46`jh-N;d@fvhLaWF$G-fcG~hI&zIO~i zBJaN={@WlK^dqi;oKc$Q2Vx{&IgRs4>*1OPPNjAS5IPW<$7`?$;n&L!!t}ON%t@Sw zm}0KO?(eT8ygz1u9}|{vdSDDG?+^y_MsGU=QyUzNJ=L7$FW{8i6zqO}h_7v@aT@4+ zPRvckz71*B#ql=GqIi2+gv9Ob$gD1kS97ZFe1A3OJby>}8X3yYC*U_b0@>`Q4rQZ`RwKg?UR z?X`A3(y7-HGCy6%)0N;-~hz_%pZ=dj^s#SEU)4 zDd`jYdHgJXVn2)DfZq^%5z@;)$3>W*kZoPZ*Rg#ub&<9HiL(}q?Gj3SF|mG%AKNeD z=iukO`4R4qk=z~=whx~XcMS3kGwhV~l-(YAqNfPiK744uMB?>BduRF*{33pY6!Kk^ z$kTQ^ZE%Jl=@U0{1tdeX|T3NBTHM49oC(~&f!^hX?H?4{~qG)fp2|qckDemQ&FGY z)}6zi;W^^&9Nx3{BK`UvG2gd)`8^5U3)6tT@IBeHf1bE|a(3Z9CJ-lu2 zN3!*8;=g0};oL+6umR^&Z%#Mancz&`oW~oxg?%{z(a>Jut}&eZbXS}6{3NH7XOq}% zJkMW_{}t>?Udy@9E1gb^UCI9AxxN>r(VNo*4LKd$%QUi$!N!~j?q&8RwaeU9oDgNt z(Om8(JDu^G?9TQVf>-i%Q@WWG6gQERo7pA5&|l=Qau;!C^D5$A=r85n%h++8%-PfZ zIG54O%uKg%Dr4sV$KF|hT~(}of7Z;J+0;XKcXxMpmr6>5beG*=fFKBB6E-3$Vt|E; zgqVP0g582i>i7Ha{XG}x>-mnygYSF3_u|^u{3qA!wPsD+GwTjr70$IwkXAjHuj)(O zQhPI!sY@w&y&dnyQSv-EKyPyA;cj$%%Or1!y$QLxd#Pb{xQ_4=zEj?aTUM$DU12Gy##67NyrY= zHSMWu89cbl;Hzy9U+np|J$2vUh9e75*IY}uP%F z@c3$YFtr55sV)LND&EHym4I zxzBO9>~Upx72Had;e5Wz4mZQhsxTb4k}s5VxPF8gZdSs(e1+`=_j6@;rL6+5Xivgd z!lOQ(I9*bT@pWwDv@Gm)Md3FOD%)J(Hk@H3K<30dMa z`)JgNnj6EdU5y$iQBzu+fm}+E_edm(<42TD+1?QWZE9dE~Viun@E7vR`tMUP2LuD36`?XFY&BCccH8!ZYeLvP&L;B01t-2|J( zU^T&}8Ei6g727UG;bs$}=go8AW^_d)NRhO8Nu)&+QK`6OyauK>3&!x@t#KYsz%?$w zjkv}o;CWo*#7(-!WsEa`nc|F~W%lUF|Mo(^LvMIhPs1$*m%?k+!=7bEnI3i&ZQg@2 zJ<$ho6I@oOQ}(8?!@cM_#yeaGzIpB-)FJlBygz4r^enm@JfUYz2JR|>)OsQ0;W9*} z<5FPZxOCjzjy7kR?$qA{ofJ31m30Pn-x$_$S8H5txVV;u+T`32y4f*&sqIGj?iMLr zYr)L;1N|-li6lsbOmfO8KVM7(IIJ%1YSn&KSPu;YJ*JP zWUigUSLtt%x~OaGP(xkZ^`Q&(bVbv|nPx0stG`7uV-jU1n|ih`d}Z};Jws=5yP%&! z{1zGcc5CfKN>1Xt_I~6)GDU6qo}4La$M@t+{8z@vMcd4F*05z zhR${ZS54$Q_fM+uHG@OyFz#K-0+%z;(2lqnD9Y%1r&4qRdfy zzE@|CUZPEGw4E=;9BSj+Xc6+|y+Z@)=^dmmV=DEG=NtC-$YUkovbHvXi|jN~rovHu z1euRujv^xx%(3Vw_)ByQ{5ARoH1=08vc?AZt|Oa;d&rEQ1xYMri6l7`MK-$DMA1Uz z*CRp;&FS2AM|(Q1gPqR5=-atuSx)1A#5p9*9cNIg1K0uGBIl7i9j*jPx`-#Gz3pS# z*|uPN+s>YAeu{pK&L#IeW8Kx}D)1_#?k%&rbA3%8)7F}30TT24J$@Q@l?AO3FQCUL zE!yI?f?JV5I){4Bg=6C9=%*;Nn`f>znW@dfi93%_CO01q1gCRv;*n~MCXur#c@Eqb z2cw^(jO1o=vk9MVW}8FE!DJvMqd0nz&(GklL2tn(=!*Vj-YEBBCwzKN&Z zQ-q&!PlHdn7u>JhX~LZmnxIGH4F2o%Fq8LiIGTx@1-J08Tt9=9nP#SyuA^CYrWHz` z&n zW;)U|_q&JPIpp8(`fw+3@!5ynde?`Xhuu_4PP2XOdiRLyYy045J`sFas&88et|ma70QGHj18^H$ z%`nwYu{8sA*jh-ROaZ6Z$?%djvrWOK@GcJIiVbcc?r~QeDVE8$Hg1y5!o9~XJI|6W zI)+}BEUrIS^@BsKIXYs7ht{?gykM;f4GV2-Yr<`98+&GGWm|&7@rQ=K^u3{^4-0j| zBxHB$ATcuuF0IW z1Iyv3xnn$0nmdYSnF?Vn@>LbWIHaj6g!1?|`X|vTb|YLgPr4QUQ73%T-2kuBX7{|i z39gmR?tao&AUpFYp_~14?pb%Uf8IR@-h^Kf36C-MKK~f{$L^!d8aNN1r8RG%?6YpQ ze;gfUtI53&zQS94_UK-JrX2{s<3RhkyO-S6@EB%CFUxJ@XOHgjgY22`MV?8C<>cgu zvU2BXNO>GV1I{wiazx8;IitJ%U^~d(P5FELh|m>2x)HR`Aow4L*uii_4km9b=_BA( z>t?!|v7x)^X2yVHgLsm1MxzOjfvc^D>29)7e^w{HrJPYIBu)n+Pc;a?lpBm+$_>FU z<%Z&ya>MXT(YuF%74Y-9!*J^4qlRp*y1fGZDAnzirnjkPr7@)%Db>-QG?!3So7Cfi z2BqGn2Cf&fIET5iH2*gMEQMdiUSQ^+Z)px1m};U;sh6pV>uKi0Rh2WEkINNRwilWU zOl3+|L5osN+tcK6hs~Oo0+$WG$7->h?XGz&e_&H)Zxu;PfCwF&NsKC8dL?6>7@NzxrhuNX_N&f`? zQ+}u&0zQfV0(EZj<+z)^t{ivN&n<)lZokPzO`}3C+{jSgUJ7qjdFrWPpGGQW2zZyj z(?3nf zuJ8xVAu|^gALAANkhv0<+s*OP*EWarx$sF|$@{y?=R$VtDnhwjUvlTbV|f)4UL*Vg zw2h7M!|~^lmeb9{<#5Az@&oYZ9e^iq7%j0M?z<8GJ2Mo%!E60c_y!k&*OGT8so$G3 z{Yd=F;eX5FF2`keLnt%U4~DC7F}TiS*AxMZ*`i=^TMR5=i-RR?39ytc36{2{z%sTpcs{;o20q_hL@hm##JmvyMfjSl zfK>u=CP=6iwilDv9ZAoN@b{4WqQ8V#cO*u;BPGFyPs&_MtQ)eW-H@$#lQMg}CAAPz zN)A6V1$m2+nFQZ!WG2Jw8o}W@87yQAk~B`oktB_bCFc$5c@zHl_TddU z4PM0K%Q-se*hlUQMf_=BjS&NAL36V zeU$&0*kj;h$hv)kdj$L#e=51t{1kAipX?vRpNyO0C;5knO~Os~6a6}36LFLL1Y`i$ zf$NBm_v?v`$4&6#sBt~Gp7>bmegu4k_*nlbu`%FSI6f~z_Pql#tei@jlFS$#OhM%H zI+#Mp@^>(WT_LcDD-0H3PU&DS=K0|eg;%(PxfJf<4(2krjXRhb@E>;pJHS;v)6ejo z!7iq=nT0G$C$O{WWM=zW-k8zw=NdBxzFlK>AnjqyS;%o1Gu@vJe#)I0^BH$%%v;Fh zbwrZwZ18M98=OsDkgi;}!$)QoUygIYN3fK$_tyMw=KTE-TbTHg0YvK znC!v_Mw&F?1~j00MwGO*%AUJpB;+D4YnHOuof}_Te%Ty=x$)EOR^}lE={xeJuU57# zrMp&^FJ<9dmM&fLA5>!wYSKTe-t7F3?nwX2=|J*MbvIeLFFk?oGL8Gq!awQmvm~D< zvngqc!;M?gl)#rZ{-XR}DdMucP#CV+Lh#ZSAiW4!gczF#O6cDs&`{FhiY5OyW$PiI z$xB&T_tgK(nt-0L0DcDI((jwV&yjq(9Lbi*L2hpDORb%qx(a{}pD)XlOWmpN8(G}s zv&hmxs`X|4Sk{7KM1E^W$WNLVV5zaI!_w zhETyI?{gurAkW$gU$zSifi3ZifQ7;4rUlr7SW&`7z-IWxz@oHbGeX7r%G``LZAz#F zUy7U3MokEnY zt&knePP`&*kPXa699|`2m2k32sgs_{xJrCy*V#`MTxGsy>ZGG8E@hK4lc`3EY*K0; zULAMbGG&5zP2Oe#Oz{1!7Vj^Bfp~5Dn+HAdI=qV*jEUE!hd9s?uSZ|8pe3G*KBJx; z5!blLo$S%FJRwcYIdD07OVW6)ex!G+RB>oKo-OsRRkPlEHlE57lFd(9qLmd^&OHdp zO0?|G%9bf73WQ?bt~5KVH^<3d&3cC)^Zp8hMe$?aTv1RXLb{(FPgQ~#YcD>lF{!E1 zVR%oa2$#Xv81Ot#Sz@vgS{9TZu822L9xRi5VoPfU?u2s+{0cnb$?dD^pXoieC86}b zn(C$Muj;EUc(Ue%iY5D}dTeu^swwe5>Z|IX={>d)q5r(TdSWkC|Ez(_0ICP8$Ns@iS0TXK)%18R?I*BCr3`_*4Hh z_-V;{ve17GVf7pJCzBlGnxjMH3% zHD0qNM{2g@NX?cUquG+9EF0IUe%)(?lYVo}RGPJO5YEnAAzk+x_0qtelTbumS_?JP zMbxOcX1a)a71#9<*G9ClYKv$yt#)chpKRB34e@IC)O*l7(VH>UQ2^BZZg7P_&FKbL z1k~6t$x&f==Hi6)ua-~=P_wq)d2!yKW^IQn4Qi&=I#`l-teHB-l>^1w9OEj0j+~et zlIkT|n=24YpA$4=*yNkHT&wj|^M=FOWXV)LnuYY{eX_pJ-c1wuLM6w6b`W z5mY}^UpUeB30l^Pqgfq43#i_x-f^Ps6WJE7Nz2Oaa5hkFow6`g2R}O_M(?mr^4-Y7 z(22H%axtgtUFutQ%AU}P7B$js3pHYOOIaBDBU?3%dDpTn+yrdGTPVmJ)fANV;eTeE zp#|@=DD$A!<<|H`35lj@O{h4iciRTP1gLl07QZB@H{1^YMB758p%(O>JK&4XIX>dm zI}~%&T7>q|XvxYyXC2ayachV+_~bZF;F1cXA2}#^Aj$>v!?NkdBJ@2{WLZ5t5Y!*&oC~0Yx2{WX~~wFk7f^ znB+WRlKsIXdxA;M6DHXQQnOSZVV4?pzUQ#0{jkG4@Hi7m?!!Jn(+B{0OuTWz!wWg+4*-Xjz zt(iZNt~Zk@`DR1~s^92sWKKR!W@6f3>G^b@8h7e{8h4qK_ns$tr+K(z-KEw#&4t`CNLB6vfN>2Ff;LTgtgY_&6np6(?C%W8u3}dti&sFzsL6j+LI!M zKx*aW*r?2NYCoVcQw68}fW}f)oc046W7Tll4`}RF$H_*$#$*kgs4I=tnmEx|8pE~d zLj}P6q>8erMXQ`@tAEs1>8+$yO|5pSt^RSpI@MNxehi*!t5a?Dcg*dl`qim^b*f+e z&(c??#^9+jcxnuu8iW78><3THSEuHyQ}flS`Rdes^}p||@Aq@NPR8}6UEcuog$hPhQ=OZKc6!;X^yh+MxL#2WAo{8h-_Ul}bx`fejAds+){*C4+rD`LASwFX&`pSkuY9Fo?g zt_64DFGSvK1Gs@}UMFoWC<|q;;~qpFuUGtuyLBO&nu>;?Bm`_P#+7d=~NN78_PHg0w#et~`9J}iOhTbb|!-Olp+G7q^l(eb5ggU6Plep#)u$#18QumV!&s`EUrg z43tj#L%jb7!3U9LJA_*Yu0xjX5N7hQ2*#c`~hHp@B;jS-~hA%T|nqebWU9mp)r8(VrUGY zhI+UF*2g~<>08^eNMG8HMfz5FEYg?6W4!s7kouBF`D3_Oz?`(qF+ztx*;G4*`x5*T z$-84Xr00?|L|y6*d`;Ci+B$qmP4KO?4&hq3j9_hieV@$;>f3G4XdKqRYY@WbJZYKu z(xq>M(pw?!34JB3h7*TPbz)WV#dDLDyOb82W05rM97FHsI4p-Z!0vf{uqS?lXe?4d8QN=IKO(#o5T_!UiE zw8qv$7O*4XqqMi=0;MVLXjF;sm`BkZ)eaQL=TY=QbpShXWeK#uc8W@(@wFq^F)D#B zfjVdvK%)SDk*FKB7Qxkxic_vLC|$F~Dc1?jJJJ+e3Rf~JjfU9vV0+@lD1lB}N};uu z8l=CWE53ALbdAbTvUF4yECWijY*|{bZBz~{i*~AmgwVImm+sS%6l#JTs(ARufYKx^ zzCCFXZUu@Dbu1~;Ioupy8il2^w>A7Lqi}7}OWd5ik;K}9ZF%PLq)2zMIQ%An<3aJH zjv)VNG?B109*Z+|693->Y(jjJk?iAP?yWqMm*vs0br@GM8qRe`qhUx}AB~10g?$vc z;L1@IWN#}I%78Yn%1GxXNC~*ANV8TVwO~{m?G2d-X9N#ZPbOR?Bwzz&Jgyqjr`6Cr z72|4vo>*o|WEj>lUIS8jI^>yUtq520O|XYo;ghDQzIQIpHeDM z^ofzi5@|!s8{NV^9*J%Rr6EHaxo^dtkCuyDNWTp!)pN~lxLc7+%pd)Vu8W&VUyd~D zIc7QTHuEv*zkt$M@-Z45^F=F=Og$StHD^;o+A)qG)%Y>j-$3k0v=aH$*=PruO^H>6 zSDKH=J%+X?$?3et-F}A#sl(B0=yQ6F6zO#mN(N^q*B_2{lKVOuL1uFG?YLFuW%7Om zU%}r+88l;oyU@rplM;6%bzQ$iiJy!#QvHZs^T)`4oI4U8i5|n=`J?z7NO|0BK+D52 za2c^3T=O&d68?Hh9l>U|bi}PEv>V+{p7y~uEpQV^+&;N_-jae59xf_5`PxA39XuINcn&gAA(!) z_kkavX<#8Gwh-QjwkGNFypNLaqx)$AInn_oTu3?TeR|GpCVwxu*Suh!C%hTmPxld0 z$xYxUYI_%7_$=k0q1Eo<3GN}T8s6av?<7^NaR;dPG@tm>)bu=exEc38&wVc?-%e_o zdJBA;|5#0nsePUXpQhdRkoFdD<~~Aia?kg1$Jda)0QV&CK+kfB`rhYFO9#~(xHsu{ z8tsxre-e}qzJ-LIp!ck$)Nb4x^oGq`d5|aEOuv1AoL#uxwBtg`UyIv7pMQYVoxH~f zz=!aEru;!r8dxM_zX6oqz1PXzNk82}-cPji7T)3_(ih_%qjxM$;$!smAIbfRIcPF7 z)s*CHHHG_KMffUwX`*?Qk+hX^Kk$~f(nFV!vK03SZ*m_!=zIFoHgFpyj*xbk(fcB4 z-{HPzep|)3)-1OQDZLj-JwTs-k$yat^l7*iWEy2fmov9a zC$yX~Hl6Sc+^vk~8A-gA`6*BI0soyRQg56^&Mn|A%ulm%H-WS8B_)3obK(b-%N?ml zYTdhnnd>HIBT3cY#7y}SeKi-kxtUo%W5ZNXjW3PvGROIC@uP&`85le#)^dQQNmv`Piw`W0BQ|Bo&TN-PQ=elZk9-E@LX2n zxvVeJIUt(iy6WHY5<;PU@FGinCZT=`IPu9P-`!)PTq7d(gOIvhzC z(BVk>Y7R%zPIEZAk=g8Uw2nSn`6k3JHKGx`V=t|+c99axTVxqBx;8P};@WVU!@$8alfKSPH)t*gDbd*b@H``7Oax_=ljjOMzwZr3Ir*RFYjoC-xg9lh}z}KvDLCJ-{OD1&iX)yhgk` zdza3XD#7lfGuRbhytEy`j_e@HB)P!FSKEQzQCCV}sRCd7*zTaD__1g~s<>|3vwM-2 zT1j*$+>X{OkAEZ*kMCYRtZG7_K2W6n_YNyvAT-V#7&o01m?+%zm#4 z*bIL#p&{%5hm$*ql)>O3{E@`#gCp=q5vm7{#6OeVLF_8)@tBSl=al0dNR&1-?Rh>P>}Xe6nX zLYyUuUs|#&b->z`kVJ>1L9$Rrys$^v+4kk6;#}}Nupj=pJV8J9yL~tb_^b2sOCr?4n;oRZ^!WZIB;{@m!rDo&K=4|6aQZB|9p2oS&nB?w$7G-90 zE^;v`m*9GF7SoHIONsU3oaq>+Ok;_U;e@6qq07k8S;J+7KaKQ-=u^&#vVmE-|BoZ_ z?tV;MS_;Lx`w=N0b7J%<@9D!x-0dHd{t+iq;^6&&ln;|y5RY<#B|hGLkvMqwk^2EB zBcF4XG#nn~bS@96dpV=ZW8Me%axN*J-lg2(OiqhtaC&w<^1S+(wE_; zaUv;R-|I+U!kN)BQf|Oa<#aP2HNMBGSU&R}rSh8_$(hOt+EmW;7E}JZwC$&h&1j)THPIa<_oeq4WTGIuAR>JxSBk zF-}pBkt%&pi$G~%T}SBJXfx%d?{Yu>{mF9obNci$VVz0cM%@#^iJaZ7A^m>N)YftB z!?*>U^}a&teVnSj52z*bVqXX^Xv!v+Ld9Zpv(;2A!-+Gt!-; z-^D5R2Fh$qo@`44;GNOiBlc5;~XPlRR_RY5kL==(|!%N+T5#N+u^grc>V&!>L@8Ow*O=<#RG?B^X1R zy>#N5k+GGNlytf79E8!Q#=In{YROnjx?3le*tbp2RyqyD%5CzTS?7b2^3%WR+)y$K z5&x$1L`V@r9!!0&NPWT3S2BGwlfEzzy^mID84>;YAPVN&pwVTfGC3mFz)A@Zy zTn6r2=l7X#YDe{#%(zTExq3|&oMd|Rz9jRMlI@i2i)5hGVv<@;Nv-J3>OD$MNpCmR zvpgxfE4|r}e7ky&lHu3e)q7M+>+S0QB^j@`t7n(AR!Z(Ufv-NOo+DY)n2=;r_0OJ= zBqAl1s`@0uBw0y)PfLv^eWg`f=xeT4>h$lq`VZY%dRnTV>U*umkL0XVJwiQS|DkVl zdLIs_aj7wP;<(dDJwATbj*|SAM7Xpas7<6NLGoK_6KPRUOQ}sX{-o_dZ6d7;YALme zv@xiq)F#r>pqA2`(OqB#8B9rs7fZIcWT2&EK>sEAPs!@&za$ZgCYI!XiIxdC{g-Hu z1Wx~@zLWu{|0X3^oS;UIo?g;n8ae72lJ?ce z(R`!%LNkTtp%kqcxI(>Hlp)sF32ENZe5Da4odBAN^i&a;6+boSWgwPXCDa?$H&r6l z57Yanu2-4Acbxtm_3KHFztfX{|G%yOudf~I+sEhXliRodt~E}*;-AlrDy2TESyR18 zeOEJ#T23?S@B3c*+?bx8>U+BWIG=+jtScpHs+CgpXeH6L(tROGR;>k+`qe1XdYv67 zIc=@BYG2JPqA^76WCTU!q$Fo^k)D&0DViiVPV$iYvYZDe-7VtT$%~T~6^$6_;m|y0 zlkxwYbv89yXq`>9%ile|PWGJq`+lpH_0RRC)GT)5I(uSRT82cMYBqK_^+wIc(m|vd zUeeOiR;1pLi@3BHsjuWDF6~A+K+(X`dW3x@oaT0|yqR#C+qLp$#!2#7`*6uIYc&_W zsufo2wpLq7#Ofcl+M?ww`M+9iLvqE{+FF?Z(Tc0JwGgNkS1W8mP%G|lS6Hn(t0E6MzYI3 z+2*2o)Cbh&0jEBoHW$sKccFD(G>_he+B_pp??UUor1RAWwC<7l-7PpkBgQQO`sV}RJP~_Q4gXcL{EsS z5Pcy!L)3=o4$&W?LPU>bI>3baQm~a9-Y_+(!>9?Z=76uSiR-6RdFpk4|2fis!ugNd^Iw@8PwbPaa|z9m z>Z@wARQR|3{KOuve@oHx|7^|D8j-$oX|>Y&rIkyomDVqYNho{E0qEp?K1^3MnUy|qAZ z=l7>-sgr`^`{=*E&;5O$Or7-VL{6u3n&WhOp|cI0W$0W~CuiC}swbyLuPCrTvmZ=f z-_?JA8$RCCQzz3pVbeWmF4A5=bfD-lX-g6vD4IXuL9D1TY2H^)b2w43>SO8p8AXM9obFt`E8ukJ zqAR2;N_Q^0A_Go$uBXn3)1B+7GvP#^=&7asN6(|D&VmyKt2IXSh@MM3n}4srsjdF& z`K@YB?{6n-F8woe*Po#wwPvTU*C&2m`7_r_%T{V%F8W@5CZ+vP^Px`tMA`pO(er<` zowc5-AL+b2_3h?gr4{w;zdhAYpM_NK@6Q3!$C0i||5EeU_8tGZXT0i5>aUvr^kpKY zOHQ+*zAb2O)SN7;Qs2&wf0xj8ily2}GvtGQNit?63LwSsHq(`v5$rq*<= z=32+~%}Hyz_M2MS^D{oQj%&7)wo2WR#*6Mjl&!{#cF`I|+W%^Itx=@?uXf$q6>I;i z-MDteDeZaEb*6vU9cr(xf7cyq53hgM9cpi{U9j#@dwx+Ax6y$V3cc?Q0X_eI- z>g=E}?IGP~|K5C<-t&*oiofswe>6_D7x>q|QL5+YTsAc`>I;{~uvX#JscNc+{Ifmv zZ|OtzqTkN6sk+qPQuJZ!JW?lOI2y}-dHUY0eUr}l(&vqTfBpS?_mb)TN9(W73`G}d{ryk) z#(g3k^6#{#dPDl&M5i|YtRMc-H&*que>A_P`ebTGJ8@3?qdmCFruRwp#`K=4-l+bW z>Y0B}pFG+7-2XaP{P*_O zRL4SXr*9`yf^WOZ``%G~ei5mHH`VmFY{1Xw83h{~{{%U*SjkpY5OOX@7aBhw5kJ<8e#{Fymiy;fX3+DU1rld?#V;wns8Di9xHiazzp**i6dr)KmM z`@ATQ-|om#R~_Gr{g%e~Yw!B^d+PN0Su=C`EUmMelfe&`;sO&_n4VdE|L>+5PR{w^ z$=e70-Ou~aze}ciVrn0s>Y?gqDUMh51+|#?WYtUcp42ZzU!?EhQ+|r-NO8_+-=kSg zyOr2zk7S(yCPBOK7(s`y%GIe^O^GuyCYX6zy7&_T~{=fTsQ;LICeMbF5 zJNVR@QHtYL=jq3Jur@+|Fh@S;&)7)SF6{hb3y)R@^=0mw1?hG`dRwlQNLRC_;>uj zw%(<_Y#ir%7qyz|jsH5&_KAJ+#5ph()=ZO{75^$d{737~Ups$3S?l26yMF!Mb7T5B zlIYU^t>^iFbjFoBWleoG(G2@XW&Y?q_OJHa^s#V!FP2U}r04`u36iW4it_(Y=8OBQ zWAMMy)hB1ZO7Fv}?cb3b`giKlTRhG~o;uI@@7XV$oHqP3{a~`bs2< zQQyP$^+*(>=tq5362&O`G2KFv=tq5p62&O`QD3K0a&D=wR+>jeKk93iC`Qqb`pPAW zQS_sz2%Qy+eoXQ8p19Vehg0W%sWFw>Kc^*unGm^yP6zk)_=%HETtVa3O+ZzXy{QP28@q9<2dh?bKytYqOt z>FN8JQbZ}}OPMUtDg8J%sq7xC>%L{_;*Y_scJheBanJ(J@0RyR8m-a{@*^S?p%AC)RU&ZL!}`xuXb)vJ49ea zydAA!K})b2^eL!EH^DVU&w_e%V_XxoFi1|Q5w0=18r13ylkMG*P$M)rWG7xf z+3NL^tzMs$2Ive>d&|;YeKZKDy=B$39`fjF^*Xq^$favM*2dLAf;}%GSxU+a<|SSu zIf`pAp7Rry6{YHgYakmh3rf}4y%q!ukXn`RtcAcr#H+AQ6$T3vuS~cK()H40PzhHV zsr{maD#G=&F#^R!|`W5SNqN`z%E z%oD1d9FNlXApM3KgH@AbPw z7EbnqH3n$39d0SfmTvkmCO(3Befafrpz1~gUxZxm{BwmTi}{A(`Y2h zvTh6JA&taVxR%UJ8iTSeDVvi;NNq#7HFKCoUt3%o=CV!HZ z$6y&ynnt8|bMayZHkZog8IGQE0;zY}7 zu8_S}Q8=>YD%+)+)ih&d0yW!d#>fbYw$_Z10ThLz86yFTa?y+tK+U6?H+*ugkex_T z$R&uyIDP5VEFpWtCBYJ;TEaTfInmN*DN;4FmjTO=*CDyCcOXS{m)3h}Arjps{X^|= zqPr>(YLlcA+7K4SCF-Fy^Lr(*Vv_EvOsFOEdu33Xe_9f1#r!9oKP_-AnHQzir#Vj4 zS9L;7ncu5})su8r4MI(r{>= z1e#Hlqx2m}>w##=<6QcZ!7UoWx;gi&owxSiqOYZeUi)&<-O`7z{krbIA(Wx^ z?Tw-T8WPF{iW003O_&SUkhfBwkj?^hPNx%s?9h%nJCJTqof(LpuR}=Z3OZeo{f9JY zP@O@@{)5gQM9=C5SO*}NSsCu2OI8f)EvS?sIorB88fzD%eDkG~028=-2cR%&MPQ9;F2xhOYgrClSuiJl_T*`m=%=!*$)ZU_IhA1@*148wsnV>*I`tC$ zREl+2`##Z6C0UJ2K%IzwD#2>3Gj>r<#aWGYk|tWJ7^|_U6VXpPV@sX9=>$%?9Hrw( zTBbxfNxo4uiYOn;=mU7lgN2dTj{*6zYnV=b%rU5RBcxp z%z>}AE0t`|(#f_fnQYHe$+jzzY|oO(wkw`&&l237+D$E349tSB_Ebx%4b`4Sxl6U7 z+OtTq?WC7W=bDlh6>X|ERI92zMVF?xq%=dQRm8oJ-jZrh(Rq44q0V4at*U3voqS&9 z>B$#4Y1CijCZJJ&k(-FMgvD+Wb`lo5$yjVy>}0KCv6D@S#pEt>*E(t1zt%0nzs||B z#C7B@c1s9f=N6Jb)-1puYnGC-#9a?Ab=SBBq%0$Ry_-*LteJ;D*4#kKGIt|*gS*~MRVTkeM2VfaJr&F&WP7V<{evR&a;y2|9QaD(hLY9B=IU|WftmF`SZ2HA>)R=J9#t#lQLt#Vatg(R+W zw-dhI-QlX*JKUXM75r-UPInhr6~DT@%iRrD!>?hh+q=QL-Q}*Ptzm_iyE$$k|8l17 z?5=QEx=uXVSkuXMPKK`}){(TarVF{9U01LRILFNe=Mw8c{#er-xD;wx8<{mc%b%`?$VfUsuwWw*B1zSK5}sFK*9peZW5Cm8FI< z;F)faD^IBb-~cz!m9yooaG*OAJkyo6#ki_CSPQ=>Sj-jyi`v3q5wJG?PiPNs;|ke2 z#0udG+dc7i_o90%e$nj!ces1NJ;Zj$+uU|=yW11L9lsUdo1zY)I~Z*|+;oAECE*W%~h zW^gmtyi2Lh_T9LX?Fe?ZoooT>F9_Dde>I+Mo^!9p&$;Kp=eg!RuIOlAA^p`jKV=Ho z{I)*+%cQ&#=Odio=Ccj(^Vx>@`D`Qnm&koN-T}T8zX0UI_WihnZ4Y*|9qeAx z+S~F@wlB)L@=kaVP5fnDIVb!X{rVN$VeA-GpiFsJ(aCaFMN%rbGOn!qDJp|&QptS~?~B{n4{&X57557|@T-tp*;RGU{t{IsrHZTO ztaY{;DOKG&u7z!B-*zo+EASos>MpVtw3K+uwX)6aTkdWAcPaUfd)KwLE$n-)jcpCK zCUuW%ZkyRXlx=Run0Cx9V@w;@){QZ3nQO+FGW6atrkE=Z7I!7U60Rgz(v<>Bxzb>1 zp7TxD%r>=eQeQLsKJ~xnYH%mjT~Swz5_?H`-|clD#vjCcdCInSuWM`D*f+SYDcICD zu|+65#_XfaUbox5;hNapxW$M#_iob+?n0U!xkXru&seu!eh$w0!ns%6#NvThrA7e~oIoZ)2_kKX#uu zZ)>^QU~N|ijEM#7Z5{Vb{B8UR_=)?}eI0)j3qN(Axv%1{W8r7+bJs9Y$Q5>t5=D5T zMu~0Xyh7$jmc|9&KOf8QP0(P)f07GU9hgJ2i9{n5;YU`T?1D$Q3JnPB5=>u zC_}kKL)XaFp`O}_y!JI(Ag_Iuwy2s&*kG$tvRa}ZS2u8VaSg$Sl&(u!16L)H!6s~# zL`ItdOi=oZ_)G5U3prPr^eTx=HlwYa_&ok1{=$LoOZQp)c`W?WedX?qzjgcFUGV|; z5_o5<@P2o|-9h@D@g4Cu?pt?v{E~YaybJ%+__O#c@GJMVyC;6xy#n5i|4IC5{5ALu zSAIh18+UK~ihC8j2Y+?^s>^Fv$M@n_N@TW~Y$fiia^k*tb)47Uhs$FtCbHPfU}o~x z#P`K{>>6BdTOpBVvw&I1yFXqN=eFfZsgRiDa@rhrqMPJ|Ic#=2nUqOxvdd+2+6iu= z%WkK*+%^}Oi@YiBey$zwCXhZJm(7lI*=$yDJpNR2r?{zZZG3+`4V>zxxd-C4@mQC} z|BZF!6Xn3HHqDN8812U3&meueo8caeABbBdnv;8$ zE0rjnILnnylmbWN&m?z-o9P~kAB*HB&wtE;H=}IO_Bu2VX_#<42L~(E={%}`3Q4Ab`zb>Bb&UWkKhw&eY*TrXpXS;LU zqwyoL@Emupdn|r57M|T4;qmx< z!sojSTwd2H(J_(Nbxw3j=c1(0gjG^S%FeYq>ACL37T#3$!e3Z=V^0}Oe zT#4MSU7{`6KG6=$gFiZKj5oxiDL*FUr%XPV-{nY9*5!6>!M2Gui2|hLcLiMb1UasC zq7~RC(HhK!|C7y5iJxq?M0Uct6WJ0uTu#>tY?Wx4_?eWS?9Vn&A~)f@i9BGwMBYT} z(1sRiiz^7W#%~u2CJKOU@!N-Xp#WGQkw0;e@;}=Sp?%1o=n(P|??4FOY>Z_Q@euyc zxPw@SJBZVz{cJ4jzi%BpY|A>-~M?N_@Z zoI%UoHt%vnhrYHKO&+}dzI{)kA{?nY2@BsQ~T zXHAx~&NsuOOR#@8oZJ!Ecap`uG31|ThLJAYU9z2bvx%K|H}k)%%-Be_`NmTATr3U7 zq}~Y1_MmgI8%p_MScW=>79NLnsB^H<=iH6h>vK+4`_=~Mt_Nku?}4y3ECprR@4@gu zSOUr}<3r)Wa2+VCjkCi;;Ro|%{6zeNc`AMqd^&y#d?tPx+!Q|pJ{xZWpNpRbpO2r5 zzc-uX=fUTRe`j8ZH^<+R@;&w#x5O{R2T1u2tBhL+EjF{l?68=BxemLMXNOr~5h;tY zKzU9$J6uc3BJ*PS61#^x!i(W^vpvYJ-*!@73@?Qpq-+ba@wbii?crt8KF7}GIb6BW zoEy#wTZ3%>ZKce%@Cx~#V>|QQu+VG?vIe+?+^ykNay~aNkg_Gb5cXp|@P)7?-fuRC zt?`z4GvOD)^I==OHGZCy&EdJQJ>C{S7iOF7;5JfyG$afLhlU~GurL%H9)^JpJNJn({W ze)z(?%H5tx`9WA$ljX-bl)T)|v2(*k;Zl2Mb?^vAy~48Xq?ybTmbUKy?cFXo!_?HSm5JD=;$i0a0fu@qS+t{V$wJF<3MCl<<@WIb~0#`WSX z*zBwqr(w&pUYr%%lJ(+jSnjM9XTaKHt++OReNyVh_2cZ={%io&k88#W>_XOzYvJdO zcZD3_?yxK5CAUGGH_m~@&>FF)Eox9U5SBH`>hX=?hEP4OfuE1^dE>fCTWR%@Hqq)~ zlWz)k0;l5FPg*ytkKMk>*kGJWYJ;Rjvj*f$it@*Agxw)OHROw{#ns~*LN(m7P>Yha zu^cF?WDU7uB6c08V!g3I{APF~6o}srZ-Q@djuw3Ri|P_Udp|IFFX=Bl~$^ zqom!jM$|C@3!YP{r6AW9h~Elthk|i+Qffqnh!u>h5w0HX32%i$@g7{^xGE{tqI2ze zwr})K*b@rJ@8F8Wr;*k-dN;fiip1~YipIT3IW2lG6pf3;?}c~q-w*GFV(~dv*7VM? z=i>Lo?-e~`t_=$VR*A#4;Nq|dye=#TmxSxUrC|wpeOL-E3)hFIO;y_EX;Up;MtB*i zo3Q!2Fl;gl!ZqN+upm4|8QJx%5?76%CI6c6oOw2h*M#}uNz!H4w{l!1e%?H1=7;Ca zyl^!*KgLzR4&vkO4zmq^11Yjh zT`n#k%YO8DD;v<`?W3e@z%FmuxLo{*DHE3k%f^qIm&lu7UozYA*PGIDnRq?9k6?fG zB{RW3Y)ZwYgPk4wZqkY7ChmX!VB$50|J8UIL5iTE2*z70Q-RxuZ{^RnJqY)}W@TI7#&-p~VuAE$>R4xf#ywOG>u# z?R;C`C2B!ROMfu@93C8!KQwuon@Pn z+r+QqKEDagNNMVu`5AVmy)v3;C)um8PB+P3L0C5HUZrKOCO#Rw3V&`SJLPjpzanWr zZ?c_}w9Gpv+KFY}Ipog8F5gZ<3&@{rFN)VUrcD4t%BXgs#s-Q9M$*N;p+Li`1O2c(yL$>SJobvkYCr=@k_v^#OnA;q*um9 z?hO3viP!eB6j{etB&8Bob7$iBjc4Kai)Ul?vLE5Tai4f5d41x(_p986LK>SsBf>K}Mz77pZ9~d``&&LAjY4PcC zX|OaFV;jY?1=@)8hH>xsw75*v8&@{^GCaxEU*f(BjVaS8ZXC--XfH~Y1|* zd&Z@}Qc=mMlfN)(9Cz{^{Y8Wu$4v-d6kQm7#2Jn7+0RMa285_di zQ~o>K+xPOV-EQ~Aq8I&kFDt`4 z{ENhP;EG1ud>5W)8)dfp(|m8=CO!?EOn|!;teVp5W7(NKO{72zK@WYVX zKSS;&@O1n;Q{lyf6W(& zUibN_<#j^&qhsMH>Bn%NnVtT1ztetUM`1_%3;QMhF1wSIU&68QnfV3xsoCXs`dxMe z`6JD*LAKq04Zq;;_Pa>`nAj&6;`%jwY<64H>~4Ffzsv8oIR80yk1%)mJBi=!?*Mn3 zUCiwJXyXsU8}@F0yMM#p!Z8vN9IFwH&6eO zxd*)4-h)W@$AqJVN!(*?B1#P7S%zav{8RgxE#UL}eW3s@YvL_?zhC3u;y(A-&Sr=o z>O1okoy@vuk9iY(lmEEOzHj!LyX*(%eegr`0eCn5z0`b3;8rKEs-Tr#25C$EQ!pC`zX2E-e)r;JmHLq42e7JJLYY3hke()1Kx=*9?D03 zd-Jeg53cu*fRFff;G_Owf2A$rGbgU(+WYL4Hd7)a;mnCliQDa4-1qJFZS$77-QIzJ zyOrf(V>X3nf-%pAP2h9kS@4;V=FwK>GlOY93&^*m(8ZMXLwpxnl6Ewo*iY?H+I*O~ zihsP)US*5=BK|5{%op{m?Cti!Xq9~+S_?jiUE^g@RbRy~i>mpmV0B*&tl_JJHGK`R zmahq3kAFi{#a9NG;b-EXGy5B(%DxhK1OC;vgf9*jKYkdQX&*=gQ;N;Rnc(2(#uNmN~QP}{!XkFukd$8 z*f=JAr5{0=mC*=49DgLSl~Et_j(ykmfxq@0JIaqFWx2nNe_zg3EBsl06e+invfPg* zwleBwZj37VZbmk=yBS%}?q*~MyPJ`X>uyH&sJofvSdi{UYjicYa_w#YR(~r`RnnL8 z3%~_-p*_=lU_S&uc%Z z$M}bMk-gd9WN!vZc zZ?e~e%luOCdhiB&qg?_n_2Sh{_?MzZcCnRJ@x^vW^i%v}yn__k8vl`dkVWvt;9`57 zeUaQ9*ztZPy3THoevW^Nw?_x#pTVEv7qMi1kkD38Hq8&k2jjp$B>XO}xX$jvEwMYX z#4TK6m)hOY^>&$k4cv_#@14<7`#Ry*2rsqQTiN7ZW@T|(xXj*QWmj8x19$&cw8UQr z?!kXMy3Q{K-@<<Sj8qr^88mPPen;$!ji zpsb?*8vhbM2g;_o@xR7B&2;|jS;Eg@X`JEeH-XP$J=~j3(bM2FSO)jz>1djt?t7YE zW*WGV=eX9thdud){{3iyzXn|B7l7~K?~ShU^TGG=r}}BWm)RHXjpqB_W-8&{W+th< z%`86?ob6|UXZzVcM|`!P<8y*J;+*k3f3?pQ&-e4dd8B5K=lHokdz=G5TRhia0cOX~ zO_^MA?sy;d=Z-&!_C;CaEB;SOXB}Ww^|j&M7Z^giVSs@F=@0?w5CcS%QlvYFl#~uZ zKnV#&Iuz+1x>H(z1|i)@cYV*A?~ncNeb(OR+&kCdc+XzXyT*_9$z2Niv_#UlwC;jF zuamja{u`gnC8xh{GBxo7X&%leAGZ?EW!I?9dk!+n%X zO8Lf184fjcC!+c_w#EA~`L;WLWAKFLuy1u3# zqmS%WKhO{GSN$ORYxD#Bb$ZdSe1CKR{S{`f`pf7QbTIv8KZO1U^ZorL#+T8d^f!t1 zNBjGJ{vwe}Xd;)`UF7wL`dhv)pYJW^`ZB&re}UPHXv8IQ{}HRB&imjZ?mUqTK6A(v z*6Yl)oBFo@kJ&6CbGWIqgd6%gdQ;!f|FZtP&l<9X>pCm#vAyGOvoc$FY@gU{AuIh^ z*8JQzsw=ZlAXFRu34`r(kYJ-kPH|h=OCcP2etT&-s^k#Ic z-lF-t0U>30L&bANsoWB;bA=c7rOg#$==lo+;f)}?Wy+8V6$IZPVzGy2QtC-%1&@-S%-<}hh^;P3K@ z)Kd@80WPAxa{b*`^aE)FTtAK?sxN&+^>KaC-mVYY%k@UTq$NUo(f4%xt*6k_eM#TL z^>j(YegDAMQ{7z;#@$?ZG^J|nnz)pziED~BbNZH#jnIh0L@z?w-HT`@Bc1uO9k)zP@_oAEJ-_BlL-Xj6U^G(1PJlpCl9v1?UTf zBq4Dq#8Hw^m_9L@I3x;1Xc4q9{UP((zw(ES3a|ZP^pH7hbTHwtF~Oqz;-N0+@SAz* zU-;k5EB_KbM1O?%VROXr&nX-+A^33AL_$D|aQ&mED6esp_z`o^JonH1LG!{tM}MO~ z#_UmZ%oGbn!!c7l6blE;Gyl{dVC^&XDL=~rQy8yL{^xUrc5XuR+@K0nXudJF_m#I?M4gY@reqBY2yCjcQ;5Kl&DaIabdhZ z1sKoaw`aDSNsCo8 zIEq#CT^#fCY4e=;g`&a`*O}N5+I;tuo533K4n>8$s$!^sRtgo-%ApckB~(VELX|L- zvxc~#t`q%q&Wly6_~}-fRi^7CuFn;?wx?%hlc0xOG&X1fCtA3!5 zRny!L=u|fiUCmjm%xY6UlnYbbR3ekz6ttq+X?B^4Y8O}g-c2S_LG3U*O$Fi=;e|8v z8d+$=(cx|cI>L=aN4l@kuiYq@M~!l$(b4W3^cyz@9plELW8FA(ock92)_sS5=f-<1)C~Hkr*vY9DMsH<*p46p_;S z+ul|(-e@+N2zMK)M>fa}=B_r-4dN4+$frHgO+qKR@6kMJf}7}uk((T@hNBopLW zS4KjS@Yjv#mC8ya3w&KyMnZ@vh`z2W8?;19#?g$kLrc8DxV{sXp#ginqCz^95=tCC%B9LW^y>Wo91wGzs%v}9+|_vV{5XDSr!#a?<00M zlJX#LI_+$2eE1<$3*Jh8nA}WmXC+s6@C48S&Li1@Q zM4nb<_}R4jke{v+YbwGqf55)Buzy-rW-J7=?1>5!sFkpbT2&!Z8B$sHN2^-d`>e{i z3e;l>W~&jY3K?0PG0Y~4;grFBP^$tS91BMRs?q*^0Dx zZ6)@uMTHx!%&xVl(CU@ldp5VN!rpamJH^Qp|70gm|C1TZU2cjyWv0^N&G+ta^AGwD zbJLiKH`8bvOkO8<(!5Uo&ym;3|6TI(>E_^H<=?EHYCe0Kv(E4&n-5m`FP>lXp>MMKxGo53 ze4H~1+Ec8N=hkXu4^HU{WCq6Y3dPalu9!Qa3&A0u(1rOuIKg>^>`B&~;tBc$&y8bQ zRgC|;6e9=!2Qkkbbu8mSJW7hA4ZEt=%HiitmiFkJ-vCF^&1QxP&!}`9||Uj+WAvu-n;^ zZ*MrB{Kxtqos*_|uv-f;^|Grp_Ju4FSe z-!$dhrR*#=b@PmT$CO>bwyvoawxNj?Zb8`ox7}PL-#zEDOV`c`rC$myMHZ+TE5#v@ z4^E=FeUqGXbH>eJ_sf%g5^le|>!P}{SKoyl@TKVQ<_}bM!n^QYZ5b-xzPj)|Yy~Rc zsk-p(Y85Kq8Cux<ojC8rgDg4Ku6Rk(+DUJ8=_~LuD7Tp)JeL*^uM1uB9zN z7QH3swy2rRw8;jFRAqyS%o&+%GSQ}(EJU(K z=5Wo~IwLbvOh(#NlbLuHm`mB&N=Yv&`(!C2vX_>E_#3d8vdfh!(uHr9sh~G!FrHz$ zxD1e%Q%wfiG}D8B2kmSRT6=iWIKE4!hX0In={Pq9oaGNto9W>&r@>*${!yG%27PDpvyQ|_nTEG?Nvq#*K=&xFco}`7$E@1EVXO0#T zm)&F`m488HFSv(m5AWLD4RqDvPP@Bhx+hPA%ZUG?--`@%1DtTM1Kk?p%gBm+$#diT zkpVn^3Qs%0ttPTYe*jhc6*H2oWExlMXQl=$@H5stHAR@s6?tx|!TCNn@528+ zXZ9I6ILQ@A4seAo%$g#R7p6Q6?+a5E!uJL1pOZCPuGf;ayGg%}eyx6Kgz|sM$`|Cn zZkToYl@b2?74etQpOv7!UlVy{*6ZucuGf+$+k&oVw?Z;to3&((HZ$JBUWVi}HWAs( z?uO(9HWJyS<5eZD5)ThsDH5-Q5?#+&xEN(m!^p(buTw%3uOq%5E=KmGH!^?PtX1XU zk=HW2PHkcr`d_G=jr7+z`qx}d*oVHVuF=1Rk6|tOC)uSwuddQdHtHNIJJ}Z#_RBAl z3p;Nvkqf(kN(SI^LJr|FIRxITVuro-Jh1BHO>87ji*$*!onMf-Z8HZmWKboI) zlT5Kl@yH~0#fwG8;&CW|7K#)^3$UWADIO^i>1uFgpp!TngNLFJT8I^JBzQd_OK^a6 zGvfE?#u;TJo7G!<8oO0V92vVAZ-#w(8=u84BD>+EO5wQJNo1Gm&NWI$cF>EKj+8=6 zF(>4DyzWHn4D%jG-!b91D@XCVL&EWP&f1}xhprs859ipgYM(IIj&XaQOU^-9_kd~H zu6h_@w0bbw294FjY*lTTZ3~xqj!`SLb?6D%vPHFI+zNv89HTv|Cy_7VWcH|=;T!UC zH^XRi3sPh>Jmi1SAfwF<;x}P6#*jg~&CDoso$(FGjKX|I*FzUoIC6*R*X9o7(kOF{ z$aOfUJ1~`dx%M77u3m6DSBYPPgSt!n9&Mx%Dr%&8KpTPHr@sONH3H_VH$2fk&e{uG z)tk`~^e8M=ANZrgjE|_xuP%8io#o z=DYwKIt0B)znrrUspYCK+|x32xmp1ub`U*8zk-=VYANw$&`~RhFH!wWUnupyW+_b7 zK{zwvrVc`__api%M+eXYaA~WFELLk&f78#bVZ2(Mhff${&eH~)A;j0H!RQb*NPT7c zn?Z~RLt1~u=o~!5U~`T($h7vtUA6JgV6fWw*7U8sf1-h=KT zC-QmNO*TZx-rc%k*hL;h_}*Pw_}-oT0mrkUFFZnD7<0+Riw=eAH4!0v4SD%**vF_3 z*IXX0zz$Kf&=jpeUyew5c8i4YtwgLTJ3;k{+K4c`l5-!;Zj!LTvZvI9-J<%eaAe^} zvA-m|u49alAj@NqSR&~P<_kP|h7@CY@7kO(z{@B%f1Wd0lY*N_FDC1n0TgEUDV z5w;{5Dw%v`gv(Y2vRY{)yC2$&fY;VW(bwkPmI*?YB#kso$o3nf%`jzXW7KQy_~~A2 z;j&-DXe;wtdq{!TI=}*0W6T(3X=BwZBCqu;9f2u$r4zvvOov`LqozYL{EHr=|B2(% z=yZA>{moc(EKK)H*1y6tDP+M*Ep)&P)}2x_SbG}3g|G%QIXb0g!3oq1vpD{T@l1Mh zN$}w3^tb9e)R}SWg>DFI@InjO@j^F(?0CU7U*gpi;$SxC)ePtLIsKhFPaChEv*rb^ zPN6@Z>n6}2(YQTolaHv)CzBnY$0z6~9A{&kJzUV^;rS&?HC{c_^`L&9>H07!&p7uv zITmq-WTj;b7xfP~6fWuscormkH9WSka@I4w+`f-LX9Zqr(f4rgEF-cUKlKMV za8}w{_*hojkMVn~#D`rSt&T5crTqw}%2L)W!#n*U{u|ufct=*@;jR~!5Lt?kx(1G% z)%d*YhVixz?`AxsI_TN6l8hGP~IBCR5ze z?;=y&3GL)}!+h-~vXiWFXS6fXy~H~D9b}N>&^V%txWcbEkmss72{j0^go#`?bJ)k) zj($5?<}PR#R_})l>*yz0$zx5jnaHe6vJ*MFq{YE;Nl(Mmaf!U%H1&kf?WwKD`fRA-8 zh`&dAQJAOZszqVGnujh>^U;NB0VJa=II0s!szZ{3i zM0BG15oL|Id8k{k7}w4(c0IGpp*+9GU9v8Shh-g+_4s#wrq00<*8XhQCiq;|GP@2( z&qBK(!QZpcuHmzsqSi3G7IyctzND9h1$KUd?`MHsO=L}Ys6U1{e8^ApNUtKYI;;v; z$eR8V=G%Gp7rZ|6?Mfo6aMWDUD{&spvvcjw_>Jb-cp@u8e7H&uc43%n=h%hJ&$Szf z#D|UO2KG?r*x7a#9wz$02%Sa0li7`sJ=e&`&Iz-q8!?An)>(E3k)3#)W>PU?F3zTz zb~}+B@Icqe%FbhEhTX<^I}VII3HSQ|4)_5T z2ZR;AufHcg8FqgGtK5A#dt5Fk?dF3YE4sWb#7tW+JvFWM($CPw9mVPU$nz zXCaaq66_Wk=K8$mUGy&X7rH?+c7&|DrL*`3#O~yH z!r$^4kz9;pd_#_I>zwqW{}IjUZ|nbbJlE_7=hTpB4*vyim`1o}a=_}v6W>7V?W27o zB8{1ehO%mmZe*r6DuhBdB0_rA!$~A`UoRNGUho;e+b`iE{=iKx+7rs*gx$>C3A>5e z6U_dOOZ^Yq!~c)g-5$(ukdCVN%pN6Dp|OZWY9{W zCFw_!eJhEUq94h+QsEd^JC4tJJ=Eu4T(2+M7lIk@5?A<|Ry3@^Pyc~mLwnyJW#utk z)9WA>*V^}?rPtau^hbys#bqsQ-6+m0imOL5itDHd@}6HutL_godjy}hP$&41&@A_)KC~J!8-iV!b~r=>cMf+BjIt&Xm@>#TTW3WYe;f%|ft+6FNkrD22Il5q-c48Fzr$gSL>~VB^tv z=JpdmU<>Mv)Ho?fybw;Fjf_g5#nDZ6qkT(nrs~OCj7#7e+RUh=-eNb~jz-wojz*~2 zPNpMlZ6_lnZl?swwyNH0x7ezzEU7!NrlaWqJA2%BfQ>!jJDX1CFnZXZ^i^0{6+U|# z^-|*SlAQE$v{Syl5o)$Q>pPhCCQkhUC9=}*w*z2BRxuXJuRr<~Dy-i?V*Bkt+CE!Z zZ@1gfZMKT;$83KnkR|kkShdd%qV2VV{a)&A3?{bMR$_f+y%^eLkL`j><&^J2JMG)? zy6vH7_t@R`SHGD4C;zM8ZD;tO5_GrSWoP;sUUV1LS!&|rIPGiF&Y))?Q`&Ncb_tx^ zPCLu*u-nm{c849LN8mRatOsdPaSP4%v;1~Dn^p-Az=$vivVXAtE)1c48wL;=hzCHN zLqnPQHhe{703=@}82mYYHvKRy&Y@wf8W;LA`<4F4)HIj;N9H2*%SVhZ`ZlJsic@WP zS8dI3&KMhp)5e6kevYpQM_3WAe}o>c$Al4Da{MD06$Vh(z&U000zaRA6p_)e zO=syx`E&GNqoe#$?%NY_dmcqc68RcZ>OB2Ou6^G3N$_X(VYY7=L1d(t+BYM7E7Osx zPOW&|)}}XZzhihukKrX9&in}9fx1tvOfUR@$8pUcXKonr;r@3bz3|unj@C9qVWw)E zkIgVtXr`8?180rl=o{Fq+KhH_U*Cl5as;39CuW+T>OV1KA^kovwdvcdmZpViPtB;7 zRQ#FZC;Ly0P=B9N7ig+~ACF-+|FII^-N))}91OKpH5?4JVG671Iz~vkI!4&KI-EV( zr{dLq3&Py*3bj;eym_@$8C@EE2k%_11b;>?wUE!WmipN*M1S!=qr!vN;#EFYwP44~ z>T+D^w@{vT5G_X^W5necW5iRK+r*gP(Vo;C$ZezsL2iz}4DD14(;RlcJ^d&>fSQ89Zbp?Mg90(PBdHP&jGsfgHhw;|tGU6l5Wscwu%wuw!9%%Q_ z4V5|uj`(=|N`vsc<}`c4Zge-!-kjzTZr+?+IhTnw zc}%wuOY4XB!^s+J`s0ZGmb1RY(=<2?3gggk@iYwygF{|?rNdA>vuG@R4zoAxLB-*l zgICFEKH_t$r9M*QU^qWgKR~E{q=XUuNKJ>J_tY607CfHOA?UC$6dl5AM4SC#Ux+r9 zd_^D4)pD3ktBpa$hZbSm8pB z7g$-eERMNsyl!?=Qwi-@QwarG6EgBUbb=p`3j0};s#O!waeQiRR5R1mw7~F2P0(4nayBY42^*f(l)#mc)fDq(pwm88@98?~6TFO!@n+Uhb#Q9dQFV14^gUfy zC+12M&@; zsCuR@9 z+VS4L*NIebUZt&0W|Eq=MB3?dE~Cj{&hcI{nl{AS>egE7zO-iCMz>okt$qiO=8uDYwmL?s86#O-G`sQm2Ro`yX2-7x{rR3dxIJ_dzjse z!+*bPsdp3E;|_AvQXh0JbaS+&ZlQl8)?DwRmX>I9=$O9v5ED~ZDYG4gc@EyxQ6@X`Q&b*H{q?5sJ^_bBvgy&OTCC)t{F@< zq@Rl-BFtn*-9bks`1zt#XWfZ$obHTv(Q$gC69*?XTXau!7yTyJLw83v(rEkrr+wi>MrOO`Ua}LdPbdyt*(pSMvGG0If_y{s2UNac2YGWN^NjE(dVuK zD?h^x@Z8OHNBKGC(tdEixMLjs;*Qh*!f3AhnX%MOIzj(}GoHJJjDL2Y;}3X&T5tU4 z3YZ4<-k~o5%EwTR?GHDW%8R0ZxZmA4Dl&@x&e`8EJBE6NZ}|VY(dajJv`vA#?OS_- ztAA@3x&`Psjz$q5P3^+uK862|T8|6dceMGg6Ez@3=R@0l&Fm;D945oj*4cKl^IT`z zB6N}a)r}FX@!?eeN#YaxZpq{1ucc=${wbf(bpuL0~|ySwn7 z0SfePf+ocwbdOO|I8J6EMWgWS+$RdhI72pbQoo|#;tZq)mmyuB~|O(T68_tqmrt4w;o;XHn?=uuSliSsZ=_iaXir+Tqj!R z(7kOhOBH+O(yBB%wa%&g*xoiL@f0PQoAm_x<*B}^h)ZtrB^qo+$Mh) z;s3emOpu?#QD=p~&VXiy^~}aNtI9#29nB5_nuFI$kDj(?Yz}qC{)_%=&!T7TIrN-8 zkEZ7g%li}_x{>+<_Pr6u$oX^}>_f$S}Pd!6xa8#AqYUWKU z(LPge(w?g-<^%O1`XO`qnR%}A(_W~`M*OIinXO_9F!MqcFj8%$0HegZ60?;}B_m$S zg3Kq<1x-W;RI061Bwi`OJ6I9M_9g7>TeO$xOMWYhp~Y26j*{r2jEkw%E{T3_)1aww z)x6DITE^nADao2tPP`PUTx$9vtS_okx))S|6hF@kn~wEqsnk*s$~HYp0Ke>g(1UV(HBy$=?f{PU!$6eV1<;?8plrxchV-Oow6A@ zD}yVRO*xZOiSs6>68}$5C5|AfY2zKD z9yG5?t!)dEgdZE_~sJx8juaD+S80S$!uNNRzRh2Vk;q$A}mr_McVbp4)OR1u!2;*X= zC|cN9B8Jbj3TKps*e`3|fr>6}ilN0=QJI-{AobrdWuT~w6Xh?l~ozEj42Io zU4prH)LW(mJbEQn8ZB)~!Dqk4Tm|^`Qn28q%-fLMZxJo0N}9Kzy(_4<(UL^VGb(A4 zaZk9(9qlF+ACswD+y})C@Cq+YLG==+O+gjSXCm&I>150IlmFXKKJYlMKR57AeRTBy0g=d7(EtDd literal 0 HcmV?d00001 From 56fd7d944c9f002ffa5ce5ee937882e0ec9ac2c2 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Thu, 28 Aug 2025 19:32:10 -0400 Subject: [PATCH 044/180] Co-authored-by: Noah Proctor Co-authored-by: charlottemartin1 Co-authored-by: Sriaditya Vaddadi Co-authored-by: akg-022 --- src/main/java/frc/robot/Constants.java | 7 + .../frc/robot/commands/CompositeCommands.java | 310 +++++++++++++ .../v3_Epsilon/V3_EpsilonRobotContainer.java | 439 ++++++++++++++++++ .../v3_Epsilon/V3_RobotContainer.java | 432 +++++++++++++++++ .../superstructure/Superstructure.dot | 4 + 5 files changed, 1192 insertions(+) create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/V3_RobotContainer.java diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 9ade0782..a214e721 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -14,6 +14,7 @@ public static Mode getMode() { case V0_GOMPEIVISION_TEST: case V1_STACKUP: case V2_REDUNDANCY: + case V3_EPSILON: return RobotBase.isReal() ? Mode.REAL : Mode.REPLAY; case V0_FUNKY_SIM: @@ -21,6 +22,7 @@ public static Mode getMode() { case V0_GOMPEIVISION_TEST_SIM: case V1_STACKUP_SIM: case V2_REDUNDANCY_SIM: + case V3_EPSILON_SIM: return Mode.SIM; default: @@ -45,6 +47,11 @@ public static enum RobotType { V1_STACKUP_SIM, V2_REDUNDANCY, V2_REDUNDANCY_SIM, +<<<<<<< HEAD +======= + V3_EPSILON_SIM, + V3_EPSILON, +>>>>>>> 4b7ea16 (Co-authored-by: Noah Proctor ) } public static void main(String... args) { diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 84677853..5b34dc56 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -648,4 +648,314 @@ public static final Command homingSequences( intake.homingSequence(), Commands.runOnce(() -> elevator.setPosition())); } + + public static final class V3_EpsilonCompositeCommands { + + /** + * Creates a command to intake coral from the station. + * + * @param superstructure The superstructure subsystem. + * @param intake The intake subsystem. + * @return A command to intake coral. + */ + public static final Command intakeCoralDriverSequence( + V2_RedundancySuperstructure superstructure, V2_RedundancyIntake intake) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoalUntil( + V2_RedundancySuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); + } + + /** + * Creates a command to intake coral from the station using the operator sequence. + * + * @param superstructure The superstructure subsystem. + * @param intake The intake subsystem. + * @return A command to intake coral using the operator sequence. + */ + public static final Command intakeCoralOperatorSequence( + V2_RedundancySuperstructure superstructure, V2_RedundancyIntake intake) { + return Commands.sequence( + superstructure.runGoalUntil( + V2_RedundancySuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); + } + + /** + * Creates a command to score coral at L1. + * + * @param drive The drive subsystem. + * @param superstructure The superstructure subsystem. + * @return A command to score coral at L1. + */ + public static final Command scoreL1Coral( + Drive drive, V2_RedundancySuperstructure superstructure) { + return Commands.sequence( + superstructure.runGoal(V2_RedundancySuperstructureStates.L1), + Commands.parallel( + superstructure.runReefScoreGoal(() -> ReefState.L1), + Commands.sequence( + Commands.waitSeconds(0.05), + Commands.either( + DriveCommands.inchMovement(drive, -1, 0.1), + DriveCommands.inchMovement(drive, 1, 0.1), + () -> RobotState.getOIData().currentReefPost() == ReefPose.LEFT)))); + } + + /** + * Creates a command sequence to score coral at L1, waiting for auto-alignment. + * + * @param drive The drive subsystem. + * @param superstructure The superstructure subsystem. + * @return A command sequence to score coral at L1. + */ + public static final Command autoScoreL1CoralSequence( + Drive drive, + ElevatorFSM elevator, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + return Commands.sequence( + DriveCommands.autoAlignReefCoral(drive, cameras), scoreL1Coral(drive, superstructure)); + } + + /** + * Creates a command sequence to score coral, waiting for auto-alignment. + * + * @param elevator The elevator subsystem. + * @param superstructure The superstructure subsystem. + * @param autoAligned A supplier that returns true when the robot is aligned. + * @return A command sequence to score coral. + */ + public static final Command scoreCoralSequence( + ElevatorFSM elevator, + V2_RedundancySuperstructure superstructure, + BooleanSupplier autoAligned) { + return Commands.sequence( + Commands.either( + superstructure.runGoal(V2_RedundancySuperstructureStates.L3), + superstructure.runReefGoal(() -> RobotState.getOIData().currentReefHeight()), + () -> + RobotState.getOIData().currentReefHeight().equals(ReefState.L4) + && !superstructure + .getCurrentState() + .equals(V2_RedundancySuperstructureStates.L4)), + Commands.waitUntil(() -> autoAligned.getAsBoolean()), + superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight()), + superstructure + .runGoal(V2_RedundancySuperstructureStates.STOW_DOWN) + .onlyIf( + () -> + elevator.getPosition().equals(ElevatorPositions.L3) + || elevator.getPosition().equals(ElevatorPositions.L2))); + } + + /** + * Creates a command sequence to automatically score coral. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param superstructure The superstructure subsystem. + * @param cameras The vision cameras. + * @return A command sequence to auto-score coral. + */ + public static final Command autoScoreCoralSequence( + Drive drive, + ElevatorFSM elevator, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + return Commands.either( + Commands.sequence( + autoScoreL1CoralSequence(drive, elevator, superstructure, cameras), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)), + Commands.sequence( + Commands.either( + superstructure.runGoal(V2_RedundancySuperstructureStates.L2), + Commands.none(), + () -> + RobotState.getOIData().currentReefHeight().equals(ReefState.L1) + || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) + || RobotState.getOIData() + .currentReefHeight() + .equals(ReefState.CORAL_INTAKE)), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + scoreCoralSequence( + elevator, + superstructure, + () -> RobotState.getReefAlignData().atCoralSetpoint())), + superstructure + .l4PlusSequence() + .onlyIf(() -> RobotState.getOIData().currentReefHeight() == ReefState.L4)), + () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); + } + + /** + * Creates a command to intake algae from the reef. This uses the closest reef tag to + * automatically pick the reef height and reef face. + * + * @param drive The drive subsystem. + * @param superstructure The superstructure subsystem. + * @param cameras The vision cameras. + * @return A command to remove algae. + */ + public static final Command intakeAlgaeFromReefSequence( + Drive drive, + V2_RedundancySuperstructure superstructure, + Supplier level, + Camera... cameras) { + return Commands.sequence( + DriveCommands.autoAlignReefAlgae(drive, cameras), + superstructure.runGoalUntil( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V2_RedundancySuperstructureStates.INTAKE_REEF_L3; + case ALGAE_INTAKE_BOTTOM: + return V2_RedundancySuperstructureStates.INTAKE_REEF_L2; + default: + return V2_RedundancySuperstructureStates.STOW_DOWN; + } + }, + () -> RobotState.isHasAlgae()), + Commands.parallel( + Commands.sequence( + Commands.waitSeconds(0.25), + Commands.either( + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_UP), + superstructure.runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V2_RedundancySuperstructureStates.REEF_ACQUISITION_L3; + default: + return V2_RedundancySuperstructureStates.REEF_ACQUISITION_L2; + } + }), + () -> RobotState.isHasAlgae())), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) + .withTimeout(0.5))); + } + + /** + * Creates a command to drop algae from the reef. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param intake The intake subsystem. + * @param superstructure The superstructure subsystem. + * @param level A supplier that provides the current reef level. + * @param cameras The vision cameras. + * @return A command to drop algae from the reef. + */ + public static final Command dropAlgae( + Drive drive, + ElevatorFSM elevator, + V2_RedundancyManipulator manipulator, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Supplier level, + Camera... cameras) { + return Commands.sequence( + DriveCommands.autoAlignReefAlgae(drive, cameras), + Commands.sequence( + superstructure + .runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V2_RedundancySuperstructureStates.INTAKE_REEF_L3; + case ALGAE_INTAKE_BOTTOM: + return V2_RedundancySuperstructureStates.INTAKE_REEF_L2; + default: + return V2_RedundancySuperstructureStates.STOW_DOWN; + } + }) + .until(() -> RobotState.isHasAlgae()), + Commands.waitSeconds(2.0), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) + .withTimeout(0.5)), + superstructure.runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V2_RedundancySuperstructureStates.DROP_REEF_L3; + case ALGAE_INTAKE_BOTTOM: + return V2_RedundancySuperstructureStates.DROP_REEF_L2; + default: + return V2_RedundancySuperstructureStates.STOW_DOWN; + } + }), + Commands.waitSeconds(1.0), + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); + } + + /** + * Creates a command sequence for the floor intake of algae. + * + * @param superstructure The superstructure subsystem. + * @return A command sequence for the floor intake. + */ + public static final Command floorIntakeSequence(V2_RedundancySuperstructure superstructure) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoalUntil( + V2_RedundancySuperstructureStates.INTAKE_FLOOR, () -> RobotState.isHasAlgae())); + } + + /** + * Creates a command that posts the floor intake sequence, which can either go up or down based + * on whether the robot has algae. + * + * @param superstructure The superstructure subsystem. + * @return A command that posts the floor intake sequence. + */ + public static final Command postFloorIntakeSequence( + V2_RedundancySuperstructure superstructure) { + return Commands.either( + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_UP), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN), + RobotState::isHasAlgae); + } + + /** + * Creates a command to set the dynamic reef height in the robot state. This sets the height and + * then moves the superstructure to that position. + * + * @param height The reef height to set. + * @param superstructure The superstructure subsystem. + * @return A command to set the dynamic reef height. + */ + public static final Command setDynamicReefHeight( + ReefState height, V2_RedundancySuperstructure superstructure) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setReefHeight(height)), superstructure.setPosition()); + } + + /** + * Creates a command to climb the robot. + * + * @param superstructure The superstructure subsystem. + * @param climber The climber subsystem. + * @param drive The drive subsystem. + * @return A command to climb. + */ + public static final Command climb( + V2_RedundancySuperstructure superstructure, Climber climber, Drive drive) { + return Commands.sequence( + superstructure.runGoal(V2_RedundancySuperstructureStates.CLIMB), + Commands.parallel( + climber.releaseClimber(), + Commands.waitSeconds( + ClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), + Commands.waitUntil(climber::climberReady), + Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); + } + + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java new file mode 100644 index 00000000..0e836a3d --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -0,0 +1,439 @@ +package frc.robot.subsystems.v3_Epsilon; + +import edu.wpi.first.networktables.NetworkTablesJNI; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; +import edu.wpi.first.wpilibj2.command.button.CommandXboxController; +import edu.wpi.first.wpilibj2.command.button.Trigger; +import frc.robot.Constants; +import frc.robot.Constants.Mode; +import frc.robot.FieldConstants.Reef.ReefPose; +import frc.robot.FieldConstants.Reef.ReefState; +import frc.robot.RobotContainer; +import frc.robot.RobotState; +import frc.robot.commands.AutonomousCommands; +import frc.robot.commands.CompositeCommands.SharedCommands; +import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; +import frc.robot.commands.DriveCommands; +import frc.robot.subsystems.shared.climber.Climber; +import frc.robot.subsystems.shared.climber.ClimberIO; +import frc.robot.subsystems.shared.climber.ClimberIOSim; +import frc.robot.subsystems.shared.climber.ClimberIOTalonFX; +import frc.robot.subsystems.shared.drive.Drive; +import frc.robot.subsystems.shared.drive.DriveConstants; +import frc.robot.subsystems.shared.drive.GyroIO; +import frc.robot.subsystems.shared.drive.GyroIOPigeon2; +import frc.robot.subsystems.shared.drive.ModuleIO; +import frc.robot.subsystems.shared.drive.ModuleIOSim; +import frc.robot.subsystems.shared.drive.ModuleIOTalonFX; +import frc.robot.subsystems.shared.elevator.Elevator; +import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; +import frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions; +import frc.robot.subsystems.shared.elevator.ElevatorIO; +import frc.robot.subsystems.shared.elevator.ElevatorIOSim; +import frc.robot.subsystems.shared.elevator.ElevatorIOTalonFX; +import frc.robot.subsystems.shared.funnel.Funnel; +import frc.robot.subsystems.shared.funnel.Funnel.FunnelFSM; +import frc.robot.subsystems.shared.funnel.FunnelIO; +import frc.robot.subsystems.shared.funnel.FunnelIOSim; +import frc.robot.subsystems.shared.funnel.FunnelIOTalonFX; +import frc.robot.subsystems.shared.visionlimelight.CameraConstants.RobotCameras; +import frc.robot.subsystems.shared.visionlimelight.Vision; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonIntakeIOTalonFX; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_Superstructure.java; + +import frc.robot.util.LTNUpdater; +import frc.robot.util.LoggedChoreo.ChoreoChooser; +import org.littletonrobotics.junction.Logger; + +public class V3_EpsilonRobotContainer implements RobotContainer { + // Subsystems + private Climber climber; + private Drive drive; + private ElevatorFSM elevator; + private FunnelFSM funnel; + private Vision vision; + private V3_EpsilonIntake intake; +// private V3_EpsilonLEDs leds; + private V3_EpsilonManipulator manipulator; + private V3_Superstructure superstructure; + + // Controller + private final CommandXboxController driver = new CommandXboxController(0); + private final CommandXboxController operator = new CommandXboxController(1); + + // Auto chooser + private final ChoreoChooser autoChooser = new ChoreoChooser(); + + public V3_EpsilonRobotContainer() { + + if (Constants.getMode() != Mode.REPLAY) { + switch (Constants.ROBOT) { + case V3_EPSILON: + climber = new Climber(new ClimberIOTalonFX()); + drive = + new Drive( + // new GyroIOPigeon2(), + // new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), + // new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), + // new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), + // new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); + // elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); + // leds = new V3_EpsilonLEDs(); + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); + superstructure = new V3_EpsilonSuperstructure(elevator, funnel, intake, manipulator); + // vision = new Vision(RobotCameras.V3_Epsilon_CAMS); + break; + case V3_EPSILON_SIM: + // climber = new Climber(new ClimberIOSim()); + drive = + new Drive( + new GyroIO() {}, + new ModuleIOSim(DriveConstants.FRONT_LEFT), + new ModuleIOSim(DriveConstants.FRONT_RIGHT), + new ModuleIOSim(DriveConstants.BACK_LEFT), + new ModuleIOSim(DriveConstants.BACK_RIGHT)); + elevator = new Elevator(new ElevatorIOSim()).getFSM(); + funnel = new Funnel(new FunnelIOSim()).getFSM(); + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); + vision = new Vision(); + break; + default: + break; + } + } + + if (climber == null) { + climber = new Climber(new ClimberIO() {}); + } + if (drive == null) { + drive = + new Drive( + new GyroIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}); + } + if (elevator == null) { + elevator = new Elevator(new ElevatorIO() {}).getFSM(); + } + if (funnel == null) { + funnel = new Funnel(new FunnelIO() {}).getFSM(); + } + if (intake == null) { + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); + } + if (leds == null) { + leds = new V3_EpsilonLEDs(); + } + if (manipulator == null) { + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); + } + if (vision == null) { + vision = new Vision(); + } + superstructure = new V3_EpsilonSuperstructure(elevator, funnel, intake, manipulator); + + configureButtonBindings(); + configureAutos(); + } + + private void configureButtonBindings() { + // Generic triggers + Trigger elevatorStow = + new Trigger( + () -> + elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) + || elevator.getPosition().equals(ElevatorPositions.STOW)); + Trigger elevatorNotStow = + new Trigger( + () -> + !elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) + && !elevator.getPosition().equals(ElevatorPositions.STOW)); + // Trigger halfScoreTrigger = + // new Trigger(() -> operator.getLeftY() < -DriveConstants.OPERATOR_DEADBAND); + // Trigger unHalfScoreTrigger = + // new Trigger(() -> operator.getLeftY() > DriveConstants.OPERATOR_DEADBAND); + + Trigger operatorFunnelOverride = + new Trigger(() -> Math.hypot(operator.getRightX(), operator.getRightY()) > 0.5); + + // Default drive command + drive.setDefaultCommand( + DriveCommands.joystickDrive( + drive, + () -> -driver.getLeftY(), + () -> -driver.getLeftX(), + () -> -driver.getRightX(), + () -> false, + operator.back(), + driver.povRight())); + + // Driver face buttons + driver.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); + driver.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); + driver.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); + driver.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); + + driver + .y() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); + driver + .x() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); + driver + .b() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); + driver + .a() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); + + // Driver triggers + driver + .leftTrigger(0.5) + .whileTrue(V3_EpsilonCompositeCommands.intakeCoralDriverSequence(superstructure, intake)) + .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); + driver + .rightTrigger(0.5) + .whileTrue( + V3_EpsilonCompositeCommands.autoScoreCoralSequence( + drive, elevator, superstructure, RobotCameras.V3_Epsilon_CAMS)); + + // Driver bumpers + driver + .leftBumper() + .whileTrue(V3_EpsilonCompositeCommands.floorIntakeSequence(superstructure)) + .onFalse( + Commands.deadline( + V3_EpsilonCompositeCommands.postFloorIntakeSequence(superstructure), + Commands.runOnce(() -> intake.setRollerGoal(IntakeRollerState.OUTTAKE))) + .andThen(Commands.runOnce(() -> intake.setRollerGoal(IntakeRollerState.STOP)))); + driver.rightBumper().onTrue(Commands.runOnce(() -> RobotState.toggleReefPost())); + + // Driver POV + driver.povUp().onTrue(superstructure.setPosition()); + driver.povDown().onTrue(SharedCommands.resetHeading(drive)); + driver.povLeft().onTrue(DriveCommands.inchMovement(drive, -0.5, .07)); + + driver + .leftStick() + .onTrue( + V3_EpsilonCompositeCommands.scoreCoralSequence( + elevator, superstructure, () -> RobotState.getReefAlignData().atCoralSetpoint())); + + driver + .back() + .whileTrue( + V3_EpsilonCompositeCommands.intakeAlgaeFromReefSequence( + drive, + superstructure, + () -> RobotState.getReefAlignData().algaeIntakeHeight(), + RobotCameras.V3_Epsilon_CAMS)); + + driver + .start() + .whileTrue( + V3_EpsilonCompositeCommands.dropAlgae( + drive, + elevator, + manipulator, + intake, + superstructure, + () -> RobotState.getReefAlignData().algaeIntakeHeight(), + RobotCameras.V3_Epsilon_CAMS)); + + // Operator face buttons + operator.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); + operator.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); + operator.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); + operator.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); + + operator + .y() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); + operator + .x() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); + operator + .b() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); + operator + .a() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); + + // Operator triggers + operator + .leftTrigger(0.5) + .whileTrue( + V3_EpsilonCompositeCommands.intakeCoralOperatorSequence(superstructure, intake)) + .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); + operator + .rightTrigger(0.5) + .whileTrue( + superstructure.override( + () -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_CORAL), 0.4)); + + // Operator bumpers + operator.leftBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))); + operator.rightBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))); + + operator.povUp().onTrue(V3_EpsilonCompositeCommands.climb(superstructure, climber, drive)); + operator.povDown().whileTrue(climber.winchClimberManual()); + operator + .povLeft() + .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR)) + .onFalse( + superstructure + .runActionWithTimeout(V3_EpsilonSuperstructureStates.SCORE_PROCESSOR, 1) + .finallyDo(() -> RobotState.setHasAlgae(false))); + + operator + .povRight() + .whileTrue( + superstructure + .override(() -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_ALGAE)) + .finallyDo(() -> RobotState.setHasAlgae(false))); + operator.start().whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)); + + operator + .back() + .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)) + .onFalse( + superstructure + .runActionWithTimeout(V3_EpsilonSuperstructureStates.SCORE_BARGE, 0.1) + .finallyDo(() -> RobotState.setHasAlgae(false))); + + // Misc + operatorFunnelOverride + .whileTrue( + Commands.either( + superstructure.runGoal(V3_EpsilonSuperstructureStates.FUNNEL_CLOSE_WITH_STOW_UP), + superstructure.runGoal( + V3_EpsilonSuperstructureStates.FUNNEL_CLOSE_WITH_STOW_DOWN), + () -> RobotState.isHasAlgae())) + .onFalse(superstructure.runPreviousState()); + } + + private void configureAutos() { + AutonomousCommands.loadAutoTrajectories(drive); + + autoChooser.addCmd( + "Drive FF Characterization", () -> DriveCommands.feedforwardCharacterization(drive)); + autoChooser.addCmd( + "Wheel Radius Characterization", () -> DriveCommands.wheelRadiusCharacterization(drive)); + autoChooser.addCmd("Elevator Characterization", () -> elevator.sysIdRoutine(superstructure)); + autoChooser.addCmd("Funnel Characterization", () -> funnel.sysIdRoutine(superstructure)); + autoChooser.addCmd("Intake Characterization", () -> intake.sysIdRoutine(superstructure)); + autoChooser.addCmd( + "Manipulator Characterization", + () -> + Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.L3), + manipulator.sysIdRoutine(superstructure))); + autoChooser.addRoutine( + "4 Piece Left", + () -> + AutonomousCommands.autoALeft( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + autoChooser.addRoutine( + "4 Piece Right", + () -> + AutonomousCommands.autoARight( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + + autoChooser.addRoutine( + "4 Piece Left Nashoba", + () -> + AutonomousCommands.autoALeftNashoba( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + + autoChooser.addRoutine( + "4 Piece Left D.A.V.E.", + () -> + AutonomousCommands.autoALeftDAVE( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + + autoChooser.addRoutine( + "3 Piece Left", + () -> + AutonomousCommands.autoCLeft( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + autoChooser.addRoutine( + "3 Piece Left Push", + () -> + AutonomousCommands.autoCLeftPush( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + autoChooser.addRoutine( + "3 Piece Right", + () -> + AutonomousCommands.autoCRight( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + autoChooser.addRoutine( + "3 Piece Right Push", + () -> + AutonomousCommands.autoCRightPush( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + autoChooser.addRoutine( + "2 Piece Left", + () -> + AutonomousCommands.autoBLeft( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + autoChooser.addRoutine( + "2 Piece Right", + () -> + AutonomousCommands.autoBRight( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + autoChooser.addRoutine( + "1 Piece Center", + () -> + AutonomousCommands.autoDCenter(drive, superstructure, RobotCameras.V3_Epsilon_CAMS)); + SmartDashboard.putData("Autonomous Modes", autoChooser); + } + + @Override + public void robotPeriodic() { + RobotState.periodic( + drive.getRawGyroRotation(), + NetworkTablesJNI.now(), + drive.getYawVelocity(), + drive.getFieldRelativeVelocity(), + drive.getModulePositions(), + intake.getExtension(), + manipulator.getArmAngle(), + elevator.getPositionMeters(), + vision.getCameras()); + + LTNUpdater.updateDrive(drive); + LTNUpdater.updateElevator(elevator); + LTNUpdater.updateFunnel(funnel); + LTNUpdater.updateAlgaeArm(manipulator); + LTNUpdater.updateIntake(intake); + + Logger.recordOutput( + "Component Poses", + V3_EpsilonMechanism3d.getPoses( + elevator.getPositionMeters(), + funnel.getAngle(), + manipulator.getArmAngle(), + intake.getExtension())); + } + + @Override + public Command getAutonomousCommand() { + return autoChooser.selectedCommand(); + } +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_RobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_RobotContainer.java new file mode 100644 index 00000000..7bcc06d5 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_RobotContainer.java @@ -0,0 +1,432 @@ +package frc.robot.subsystems.v3_Epsilon; + +import edu.wpi.first.networktables.NetworkTablesJNI; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; +import edu.wpi.first.wpilibj2.command.button.CommandXboxController; +import edu.wpi.first.wpilibj2.command.button.Trigger; +import frc.robot.Constants; +import frc.robot.Constants.Mode; +import frc.robot.FieldConstants.Reef.ReefPose; +import frc.robot.FieldConstants.Reef.ReefState; +import frc.robot.RobotContainer; +import frc.robot.RobotState; +import frc.robot.commands.AutonomousCommands; +import frc.robot.commands.CompositeCommands.SharedCommands; +import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; +import frc.robot.commands.DriveCommands; +import frc.robot.subsystems.shared.climber.Climber; +import frc.robot.subsystems.shared.climber.ClimberIO; +import frc.robot.subsystems.shared.climber.ClimberIOTalonFX; +import frc.robot.subsystems.shared.drive.Drive; +import frc.robot.subsystems.shared.drive.DriveConstants; +import frc.robot.subsystems.shared.drive.GyroIO; +import frc.robot.subsystems.shared.drive.GyroIOPigeon2; +import frc.robot.subsystems.shared.drive.ModuleIO; +import frc.robot.subsystems.shared.drive.ModuleIOSim; +import frc.robot.subsystems.shared.drive.ModuleIOTalonFX; +import frc.robot.subsystems.shared.elevator.Elevator; +import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; +import frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions; +import frc.robot.subsystems.shared.elevator.ElevatorIO; +import frc.robot.subsystems.shared.elevator.ElevatorIOSim; +import frc.robot.subsystems.shared.elevator.ElevatorIOTalonFX; +import frc.robot.subsystems.shared.funnel.Funnel; +import frc.robot.subsystems.shared.funnel.Funnel.FunnelFSM; +import frc.robot.subsystems.shared.funnel.FunnelIO; +import frc.robot.subsystems.shared.funnel.FunnelIOSim; +import frc.robot.subsystems.shared.visionlimelight.CameraConstants.RobotCameras; +import frc.robot.subsystems.shared.visionlimelight.Vision; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonIntakeIOTalonFX; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; +import frc.robot.util.LTNUpdater; +import frc.robot.util.LoggedChoreo.ChoreoChooser; +import org.littletonrobotics.junction.Logger; + +public class V3_EpsilonRobotContainer implements RobotContainer { + // Subsystems + private Climber climber; + private Drive drive; + private ElevatorFSM elevator; + private FunnelFSM funnel; + private Vision vision; + private V3_EpsilonIntake intake; + // private V3_EpsilonLEDs leds; + private V3_EpsilonManipulator manipulator; + private V3_Superstructure superstructure; + + // Controller + private final CommandXboxController driver = new CommandXboxController(0); + private final CommandXboxController operator = new CommandXboxController(1); + + // Auto chooser + private final ChoreoChooser autoChooser = new ChoreoChooser(); + + public V3_EpsilonRobotContainer() { + + if (Constants.getMode() != Mode.REPLAY) { + switch (Constants.ROBOT) { + case V3_EPSILON: + climber = new Climber(new ClimberIOTalonFX()); + drive = + new Drive( + new GyroIOPigeon2(), + new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), + new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), + new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), + new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); + elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); + // leds = new V3_EpsilonLEDs(); + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); + superstructure = new V3_EpsilonSuperstructure(elevator, funnel, intake, manipulator); + // vision = new Vision(RobotCameras.V3_Epsilon_CAMS); + break; + case V3_EPSILON_SIM: + // climber = new Climber(new ClimberIOSim()); + drive = + new Drive( + new GyroIO() {}, + new ModuleIOSim(DriveConstants.FRONT_LEFT), + new ModuleIOSim(DriveConstants.FRONT_RIGHT), + new ModuleIOSim(DriveConstants.BACK_LEFT), + new ModuleIOSim(DriveConstants.BACK_RIGHT)); + elevator = new Elevator(new ElevatorIOSim()).getFSM(); + funnel = new Funnel(new FunnelIOSim()).getFSM(); + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); + vision = new Vision(); + break; + default: + break; + } + } + + if (climber == null) { + climber = new Climber(new ClimberIO() {}); + } + if (drive == null) { + drive = + new Drive( + new GyroIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}); + } + if (elevator == null) { + elevator = new Elevator(new ElevatorIO() {}).getFSM(); + } + if (funnel == null) { + funnel = new Funnel(new FunnelIO() {}).getFSM(); + } + if (intake == null) { + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); + } + if (leds == null) { + leds = new V3_EpsilonLEDs(); + } + if (manipulator == null) { + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); + } + if (vision == null) { + vision = new Vision(); + } + superstructure = new V3_EpsilonSuperstructure(elevator, funnel, intake, manipulator); + + configureButtonBindings(); + configureAutos(); + } + + private void configureButtonBindings() { + // Generic triggers + Trigger elevatorStow = + new Trigger( + () -> + elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) + || elevator.getPosition().equals(ElevatorPositions.STOW)); + Trigger elevatorNotStow = + new Trigger( + () -> + !elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) + && !elevator.getPosition().equals(ElevatorPositions.STOW)); + // Trigger halfScoreTrigger = + // new Trigger(() -> operator.getLeftY() < -DriveConstants.OPERATOR_DEADBAND); + // Trigger unHalfScoreTrigger = + // new Trigger(() -> operator.getLeftY() > DriveConstants.OPERATOR_DEADBAND); + + Trigger operatorFunnelOverride = + new Trigger(() -> Math.hypot(operator.getRightX(), operator.getRightY()) > 0.5); + + // Default drive command + drive.setDefaultCommand( + DriveCommands.joystickDrive( + drive, + () -> -driver.getLeftY(), + () -> -driver.getLeftX(), + () -> -driver.getRightX(), + () -> false, + operator.back(), + driver.povRight())); + + // Driver face buttons + driver.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); + driver.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); + driver.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); + driver.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); + + driver + .y() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); + driver + .x() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); + driver + .b() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); + driver + .a() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); + + // Driver triggers + driver + .leftTrigger(0.5) + .whileTrue(V3_EpsilonCompositeCommands.intakeCoralDriverSequence(superstructure, intake)) + .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); + driver + .rightTrigger(0.5) + .whileTrue( + V3_EpsilonCompositeCommands.autoScoreCoralSequence( + drive, elevator, superstructure, RobotCameras.V3_Epsilon_CAMS)); + + // Driver bumpers + driver + .leftBumper() + .whileTrue(V3_EpsilonCompositeCommands.floorIntakeSequence(superstructure)) + .onFalse( + Commands.deadline( + V3_EpsilonCompositeCommands.postFloorIntakeSequence(superstructure), + Commands.runOnce(() -> intake.setRollerGoal(IntakeRollerState.OUTTAKE))) + .andThen(Commands.runOnce(() -> intake.setRollerGoal(IntakeRollerState.STOP)))); + driver.rightBumper().onTrue(Commands.runOnce(() -> RobotState.toggleReefPost())); + + // Driver POV + driver.povUp().onTrue(superstructure.setPosition()); + driver.povDown().onTrue(SharedCommands.resetHeading(drive)); + driver.povLeft().onTrue(DriveCommands.inchMovement(drive, -0.5, .07)); + + driver + .leftStick() + .onTrue( + V3_EpsilonCompositeCommands.scoreCoralSequence( + elevator, superstructure, () -> RobotState.getReefAlignData().atCoralSetpoint())); + + driver + .back() + .whileTrue( + V3_EpsilonCompositeCommands.intakeAlgaeFromReefSequence( + drive, + superstructure, + () -> RobotState.getReefAlignData().algaeIntakeHeight(), + RobotCameras.V3_Epsilon_CAMS)); + + driver + .start() + .whileTrue( + V3_EpsilonCompositeCommands.dropAlgae( + drive, + elevator, + manipulator, + intake, + superstructure, + () -> RobotState.getReefAlignData().algaeIntakeHeight(), + RobotCameras.V3_Epsilon_CAMS)); + + // Operator face buttons + operator.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); + operator.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); + operator.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); + operator.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); + + operator + .y() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); + operator + .x() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); + operator + .b() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); + operator + .a() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); + + // Operator triggers + operator + .leftTrigger(0.5) + .whileTrue(V3_EpsilonCompositeCommands.intakeCoralOperatorSequence(superstructure, intake)) + .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); + operator + .rightTrigger(0.5) + .whileTrue( + superstructure.override( + () -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_CORAL), 0.4)); + + // Operator bumpers + operator.leftBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))); + operator.rightBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))); + + operator.povUp().onTrue(V3_EpsilonCompositeCommands.climb(superstructure, climber, drive)); + operator.povDown().whileTrue(climber.winchClimberManual()); + operator + .povLeft() + .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR)) + .onFalse( + superstructure + .runActionWithTimeout(V3_EpsilonSuperstructureStates.SCORE_PROCESSOR, 1) + .finallyDo(() -> RobotState.setHasAlgae(false))); + + operator + .povRight() + .whileTrue( + superstructure + .override(() -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_ALGAE)) + .finallyDo(() -> RobotState.setHasAlgae(false))); + operator.start().whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)); + + operator + .back() + .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)) + .onFalse( + superstructure + .runActionWithTimeout(V3_EpsilonSuperstructureStates.SCORE_BARGE, 0.1) + .finallyDo(() -> RobotState.setHasAlgae(false))); + + // Misc + operatorFunnelOverride + .whileTrue( + Commands.either( + superstructure.runGoal(V3_EpsilonSuperstructureStates.FUNNEL_CLOSE_WITH_STOW_UP), + superstructure.runGoal(V3_EpsilonSuperstructureStates.FUNNEL_CLOSE_WITH_STOW_DOWN), + () -> RobotState.isHasAlgae())) + .onFalse(superstructure.runPreviousState()); + } + + private void configureAutos() { + AutonomousCommands.loadAutoTrajectories(drive); + + autoChooser.addCmd( + "Drive FF Characterization", () -> DriveCommands.feedforwardCharacterization(drive)); + autoChooser.addCmd( + "Wheel Radius Characterization", () -> DriveCommands.wheelRadiusCharacterization(drive)); + autoChooser.addCmd("Elevator Characterization", () -> elevator.sysIdRoutine(superstructure)); + autoChooser.addCmd("Funnel Characterization", () -> funnel.sysIdRoutine(superstructure)); + autoChooser.addCmd("Intake Characterization", () -> intake.sysIdRoutine(superstructure)); + autoChooser.addCmd( + "Manipulator Characterization", + () -> + Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.L3), + manipulator.sysIdRoutine(superstructure))); + autoChooser.addRoutine( + "4 Piece Left", + () -> + AutonomousCommands.autoALeft( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + autoChooser.addRoutine( + "4 Piece Right", + () -> + AutonomousCommands.autoARight( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + + autoChooser.addRoutine( + "4 Piece Left Nashoba", + () -> + AutonomousCommands.autoALeftNashoba( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + + autoChooser.addRoutine( + "4 Piece Left D.A.V.E.", + () -> + AutonomousCommands.autoALeftDAVE( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + + autoChooser.addRoutine( + "3 Piece Left", + () -> + AutonomousCommands.autoCLeft( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + autoChooser.addRoutine( + "3 Piece Left Push", + () -> + AutonomousCommands.autoCLeftPush( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + autoChooser.addRoutine( + "3 Piece Right", + () -> + AutonomousCommands.autoCRight( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + autoChooser.addRoutine( + "3 Piece Right Push", + () -> + AutonomousCommands.autoCRightPush( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + autoChooser.addRoutine( + "2 Piece Left", + () -> + AutonomousCommands.autoBLeft( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + autoChooser.addRoutine( + "2 Piece Right", + () -> + AutonomousCommands.autoBRight( + drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + autoChooser.addRoutine( + "1 Piece Center", + () -> AutonomousCommands.autoDCenter(drive, superstructure, RobotCameras.V3_Epsilon_CAMS)); + SmartDashboard.putData("Autonomous Modes", autoChooser); + } + + @Override + public void robotPeriodic() { + RobotState.periodic( + drive.getRawGyroRotation(), + NetworkTablesJNI.now(), + drive.getYawVelocity(), + drive.getFieldRelativeVelocity(), + drive.getModulePositions(), + intake.getExtension(), + manipulator.getArmAngle(), + elevator.getPositionMeters(), + vision.getCameras()); + + LTNUpdater.updateDrive(drive); + LTNUpdater.updateElevator(elevator); + LTNUpdater.updateFunnel(funnel); + LTNUpdater.updateAlgaeArm(manipulator); + LTNUpdater.updateIntake(intake); + + Logger.recordOutput( + "Component Poses", + V3_EpsilonMechanism3d.getPoses( + elevator.getPositionMeters(), + funnel.getAngle(), + manipulator.getArmAngle(), + intake.getExtension())); + } + + @Override + public Command getAutonomousCommand() { + return autoChooser.selectedCommand(); + } +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index 4ca17570..7dbd2f01 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -59,6 +59,10 @@ digraph Superstructure { handoff -> L2_transition [color = green] handoff -> L3_transition [color = green] handoff -> L4_transition [color = green] + + L2_transition -> handoff [color = green] + L3_transition -> handoff [color = green] + L4_transition -> hadnoff [color = green] handoff -> L2_prep [color = green] handoff -> L3_prep [color = green] From 02b0b4923c9ea2bef62c4770dd69c06acb840a6c Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Thu, 28 Aug 2025 19:39:52 -0400 Subject: [PATCH 045/180] worked on robot container for V3 --- .../frc/robot/commands/CompositeCommands.java | 86 ++++++++++--------- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 25 +++--- 2 files changed, 59 insertions(+), 52 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 5b34dc56..26776ae2 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -22,6 +22,10 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_Superstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureStates; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; import frc.robot.util.AllianceFlipUtil; import java.util.function.BooleanSupplier; import java.util.function.Supplier; @@ -659,12 +663,12 @@ public static final class V3_EpsilonCompositeCommands { * @return A command to intake coral. */ public static final Command intakeCoralDriverSequence( - V2_RedundancySuperstructure superstructure, V2_RedundancyIntake intake) { + V3_EpsilonSuperstructure superstructure, V3_EpsilonIntake intake) { return Commands.sequence( Commands.runOnce(() -> RobotState.setHasAlgae(false)), superstructure.runGoalUntil( - V2_RedundancySuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); + V3_EpsilonSuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); } /** @@ -675,11 +679,11 @@ public static final Command intakeCoralDriverSequence( * @return A command to intake coral using the operator sequence. */ public static final Command intakeCoralOperatorSequence( - V2_RedundancySuperstructure superstructure, V2_RedundancyIntake intake) { + V3_EpsilonSuperstructure superstructure, V3_EpsilonIntake intake) { return Commands.sequence( superstructure.runGoalUntil( - V2_RedundancySuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); + V3_EpsilonSuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); } /** @@ -690,9 +694,9 @@ public static final Command intakeCoralOperatorSequence( * @return A command to score coral at L1. */ public static final Command scoreL1Coral( - Drive drive, V2_RedundancySuperstructure superstructure) { + Drive drive, V3_EpsilonSuperstructure superstructure) { return Commands.sequence( - superstructure.runGoal(V2_RedundancySuperstructureStates.L1), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L1), Commands.parallel( superstructure.runReefScoreGoal(() -> ReefState.L1), Commands.sequence( @@ -713,7 +717,7 @@ public static final Command scoreL1Coral( public static final Command autoScoreL1CoralSequence( Drive drive, ElevatorFSM elevator, - V2_RedundancySuperstructure superstructure, + V3_EpsilonSuperstructure superstructure, Camera... cameras) { return Commands.sequence( DriveCommands.autoAlignReefCoral(drive, cameras), scoreL1Coral(drive, superstructure)); @@ -729,21 +733,21 @@ public static final Command autoScoreL1CoralSequence( */ public static final Command scoreCoralSequence( ElevatorFSM elevator, - V2_RedundancySuperstructure superstructure, + V3_EpsilonSuperstructure superstructure, BooleanSupplier autoAligned) { return Commands.sequence( Commands.either( - superstructure.runGoal(V2_RedundancySuperstructureStates.L3), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L3), superstructure.runReefGoal(() -> RobotState.getOIData().currentReefHeight()), () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L4) && !superstructure .getCurrentState() - .equals(V2_RedundancySuperstructureStates.L4)), + .equals(V3_EpsilonSuperstructureStates.L4)), Commands.waitUntil(() -> autoAligned.getAsBoolean()), superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight()), superstructure - .runGoal(V2_RedundancySuperstructureStates.STOW_DOWN) + .runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN) .onlyIf( () -> elevator.getPosition().equals(ElevatorPositions.L3) @@ -762,16 +766,16 @@ public static final Command scoreCoralSequence( public static final Command autoScoreCoralSequence( Drive drive, ElevatorFSM elevator, - V2_RedundancySuperstructure superstructure, + V3_EpsilonSuperstructure superstructure, Camera... cameras) { return Commands.either( Commands.sequence( autoScoreL1CoralSequence(drive, elevator, superstructure, cameras), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)), Commands.sequence( Commands.either( - superstructure.runGoal(V2_RedundancySuperstructureStates.L2), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L2), Commands.none(), () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1) @@ -802,7 +806,7 @@ public static final Command autoScoreCoralSequence( */ public static final Command intakeAlgaeFromReefSequence( Drive drive, - V2_RedundancySuperstructure superstructure, + V3_EpsilonSuperstructure superstructure, Supplier level, Camera... cameras) { return Commands.sequence( @@ -811,11 +815,11 @@ public static final Command intakeAlgaeFromReefSequence( () -> { switch (level.get()) { case ALGAE_INTAKE_TOP: - return V2_RedundancySuperstructureStates.INTAKE_REEF_L3; + return V3_EpsilonSuperstructureStates.INTAKE_REEF_L3; case ALGAE_INTAKE_BOTTOM: - return V2_RedundancySuperstructureStates.INTAKE_REEF_L2; + return V3_EpsilonSuperstructureStates.INTAKE_REEF_L2; default: - return V2_RedundancySuperstructureStates.STOW_DOWN; + return V3_EpsilonSuperstructureStates.STOW_DOWN; } }, () -> RobotState.isHasAlgae()), @@ -823,14 +827,14 @@ public static final Command intakeAlgaeFromReefSequence( Commands.sequence( Commands.waitSeconds(0.25), Commands.either( - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_UP), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), superstructure.runGoal( () -> { switch (level.get()) { case ALGAE_INTAKE_TOP: - return V2_RedundancySuperstructureStates.REEF_ACQUISITION_L3; + return V3_EpsilonSuperstructureStates.REEF_ACQUISITION_L3; default: - return V2_RedundancySuperstructureStates.REEF_ACQUISITION_L2; + return V3_EpsilonSuperstructureStates.REEF_ACQUISITION_L2; } }), () -> RobotState.isHasAlgae())), @@ -854,9 +858,9 @@ public static final Command intakeAlgaeFromReefSequence( public static final Command dropAlgae( Drive drive, ElevatorFSM elevator, - V2_RedundancyManipulator manipulator, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, + V3_EpsilonManipulator manipulator, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, Supplier level, Camera... cameras) { return Commands.sequence( @@ -867,11 +871,11 @@ public static final Command dropAlgae( () -> { switch (level.get()) { case ALGAE_INTAKE_TOP: - return V2_RedundancySuperstructureStates.INTAKE_REEF_L3; + return V3_EpsilonSuperstructureStates.INTAKE_REEF_L3; case ALGAE_INTAKE_BOTTOM: - return V2_RedundancySuperstructureStates.INTAKE_REEF_L2; + return V3_EpsilonSuperstructureStates.INTAKE_REEF_L2; default: - return V2_RedundancySuperstructureStates.STOW_DOWN; + return V3_EpsilonSuperstructureStates.STOW_DOWN; } }) .until(() -> RobotState.isHasAlgae()), @@ -883,16 +887,16 @@ public static final Command dropAlgae( () -> { switch (level.get()) { case ALGAE_INTAKE_TOP: - return V2_RedundancySuperstructureStates.DROP_REEF_L3; + return V3_EpsilonSuperstructureStates.DROP_REEF_L3; case ALGAE_INTAKE_BOTTOM: - return V2_RedundancySuperstructureStates.DROP_REEF_L2; + return V3_EpsilonSuperstructureStates.DROP_REEF_L2; default: - return V2_RedundancySuperstructureStates.STOW_DOWN; + return V3_EpsilonSuperstructureStates.STOW_DOWN; } }), Commands.waitSeconds(1.0), Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); } /** @@ -901,11 +905,11 @@ public static final Command dropAlgae( * @param superstructure The superstructure subsystem. * @return A command sequence for the floor intake. */ - public static final Command floorIntakeSequence(V2_RedundancySuperstructure superstructure) { + public static final Command floorIntakeSequence(V3_EpsilonSuperstructure superstructure) { return Commands.sequence( Commands.runOnce(() -> RobotState.setHasAlgae(false)), superstructure.runGoalUntil( - V2_RedundancySuperstructureStates.INTAKE_FLOOR, () -> RobotState.isHasAlgae())); + V3_EpsilonSuperstructureStates.INTAKE_FLOOR, () -> RobotState.isHasAlgae())); } /** @@ -916,10 +920,10 @@ public static final Command floorIntakeSequence(V2_RedundancySuperstructure supe * @return A command that posts the floor intake sequence. */ public static final Command postFloorIntakeSequence( - V2_RedundancySuperstructure superstructure) { + V3_EpsilonSuperstructure superstructure) { return Commands.either( - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_UP), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), RobotState::isHasAlgae); } @@ -932,7 +936,7 @@ public static final Command postFloorIntakeSequence( * @return A command to set the dynamic reef height. */ public static final Command setDynamicReefHeight( - ReefState height, V2_RedundancySuperstructure superstructure) { + ReefState height, V3_EpsilonSuperstructure superstructure) { return Commands.sequence( Commands.runOnce(() -> RobotState.setReefHeight(height)), superstructure.setPosition()); } @@ -946,9 +950,9 @@ public static final Command setDynamicReefHeight( * @return A command to climb. */ public static final Command climb( - V2_RedundancySuperstructure superstructure, Climber climber, Drive drive) { + V3_EpsilonSuperstructure superstructure, Climber climber, Drive drive) { return Commands.sequence( - superstructure.runGoal(V2_RedundancySuperstructureStates.CLIMB), + superstructure.runGoal(V3_EpsilonSuperstructureStates.CLIMB), Commands.parallel( climber.releaseClimber(), Commands.waitSeconds( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 0e836a3d..644eab5c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -38,12 +38,15 @@ import frc.robot.subsystems.shared.funnel.FunnelIO; import frc.robot.subsystems.shared.funnel.FunnelIOSim; import frc.robot.subsystems.shared.funnel.FunnelIOTalonFX; -import frc.robot.subsystems.shared.visionlimelight.CameraConstants.RobotCameras; -import frc.robot.subsystems.shared.visionlimelight.Vision; +// import frc.robot.subsystems.shared.vision.CameraConstants.RobotCameras; +import frc.robot.subsystems.shared.vision.Vision; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonIntakeIOTalonFX; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_Superstructure.java; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIOTalonFX; +// import frc.robot.subsystems.v3_Epsilon.superstructure.V3_Superstructure.java; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_Superstructure; + + import frc.robot.util.LTNUpdater; import frc.robot.util.LoggedChoreo.ChoreoChooser; @@ -76,16 +79,16 @@ public V3_EpsilonRobotContainer() { climber = new Climber(new ClimberIOTalonFX()); drive = new Drive( - // new GyroIOPigeon2(), - // new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), - // new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), - // new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), - // new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); - // elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); + new GyroIOPigeon2(), + new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), + new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), + new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), + new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); + elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); // leds = new V3_EpsilonLEDs(); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); - superstructure = new V3_EpsilonSuperstructure(elevator, funnel, intake, manipulator); + superstructure = new V3_Superstructure(elevator, funnel, intake, manipulator); // vision = new Vision(RobotCameras.V3_Epsilon_CAMS); break; case V3_EPSILON_SIM: From 519d383425b5aa4297e140923799d6b22a7475dc Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Fri, 29 Aug 2025 13:59:36 -0400 Subject: [PATCH 046/180] format --- advantagescopeassets/Robot_Epsilon/config.json | 8 +++----- .../subsystems/v3_Epsilon/V3_EpsilonMechanism3d.java | 4 +--- 2 files changed, 4 insertions(+), 8 deletions(-) diff --git a/advantagescopeassets/Robot_Epsilon/config.json b/advantagescopeassets/Robot_Epsilon/config.json index d22a5fdf..7ef79ac3 100644 --- a/advantagescopeassets/Robot_Epsilon/config.json +++ b/advantagescopeassets/Robot_Epsilon/config.json @@ -17,10 +17,9 @@ 0, 0 ], - "cameras": [ - ], + "cameras": [], "components": [ - { + { "zeroedRotations": [ { "axis": "x", @@ -85,8 +84,7 @@ "zeroedPosition": [ 0.15381615, 0, --0.270855 - + -0.270855 ] } ] diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonMechanism3d.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonMechanism3d.java index 916d314d..adde42b5 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonMechanism3d.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonMechanism3d.java @@ -59,9 +59,7 @@ public static final Pose3d[] getPoses( new Pose3d(0.1875, 0, 0.1363, new Rotation3d(0.0, intakeAngle.getRadians(), 0.0)), ELEVATOR_STAGE_1_POSE, ELEVATOR_CARRIAGE_POSE, - new Pose3d(-0.15381615, - 0, -0.270855, new Rotation3d()) + new Pose3d(-0.15381615, 0, 0.270855, new Rotation3d()) .transformBy( new Transform3d( 0, From d55cb7420bbe4281af1e0964d262aa15651d18fe Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Fri, 29 Aug 2025 19:04:13 -0400 Subject: [PATCH 047/180] Fixed errors on superstructure for V3 + renamed superstructure files Co-authored-by: ThatGuyRuchir --- .../frc/robot/commands/CompositeCommands.java | 4 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 82 ++-- .../v3_Epsilon/V3_RobotContainer.java | 432 ------------------ ...ure.java => V3_EpsilonSuperstructure.java} | 64 +-- ...a => V3_EpsilonSuperstructureActions.java} | 6 +- .../V3_EpsilonSuperstructureEdges.java | 246 ++++++++++ ...ava => V3_EpsilonSuperstructurePoses.java} | 4 +- ...va => V3_EpsilonSuperstructureStates.java} | 20 +- .../V3_SuperstructureEdges.java | 246 ---------- 9 files changed, 340 insertions(+), 764 deletions(-) delete mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/V3_RobotContainer.java rename src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/{V3_Superstructure.java => V3_EpsilonSuperstructure.java} (81%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/{V3_SuperstructureActions.java => V3_EpsilonSuperstructureActions.java} (90%) create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java rename src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/{V3_SuperstructurePoses.java => V3_EpsilonSuperstructurePoses.java} (96%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/{V3_SuperstructureStates.java => V3_EpsilonSuperstructureStates.java} (92%) delete mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 26776ae2..34245d10 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -22,8 +22,8 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_Superstructure; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureStates; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; import frc.robot.util.AllianceFlipUtil; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 644eab5c..e6fcf8d0 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -42,9 +42,14 @@ import frc.robot.subsystems.shared.vision.Vision; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorIO; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorIOSim; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIOTalonFX; -// import frc.robot.subsystems.v3_Epsilon.superstructure.V3_Superstructure.java; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_Superstructure; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIO; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIOSim; +// import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure.java; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; @@ -62,12 +67,15 @@ public class V3_EpsilonRobotContainer implements RobotContainer { private V3_EpsilonIntake intake; // private V3_EpsilonLEDs leds; private V3_EpsilonManipulator manipulator; - private V3_Superstructure superstructure; + private V3_EpsilonSuperstructure superstructure; + private V3_EpsilonManipulatorIO manipulatorIO; // Controller private final CommandXboxController driver = new CommandXboxController(0); private final CommandXboxController operator = new CommandXboxController(1); + manipulatorIO = new V3_EpsilonManipulatorIO(); + // Auto chooser private final ChoreoChooser autoChooser = new ChoreoChooser(); @@ -87,8 +95,8 @@ public V3_EpsilonRobotContainer() { elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); // leds = new V3_EpsilonLEDs(); - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); - superstructure = new V3_Superstructure(elevator, funnel, intake, manipulator); + manipulator = new V3_EpsilonManipulator(manipulatorIO); + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); // Doesn't include states // vision = new Vision(RobotCameras.V3_Epsilon_CAMS); break; case V3_EPSILON_SIM: @@ -104,7 +112,7 @@ public V3_EpsilonRobotContainer() { funnel = new Funnel(new FunnelIOSim()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); - vision = new Vision(); + // vision = new Vision(); break; default: break; @@ -132,15 +140,15 @@ public V3_EpsilonRobotContainer() { if (intake == null) { intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); } - if (leds == null) { - leds = new V3_EpsilonLEDs(); + // if (leds == null) { + // leds = new V3_EpsilonLEDs(); } if (manipulator == null) { manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); } - if (vision == null) { - vision = new Vision(); - } + // if (vision == null) { + // vision = new Vision(); + // } superstructure = new V3_EpsilonSuperstructure(elevator, funnel, intake, manipulator); configureButtonBindings(); @@ -206,11 +214,11 @@ private void configureButtonBindings() { .leftTrigger(0.5) .whileTrue(V3_EpsilonCompositeCommands.intakeCoralDriverSequence(superstructure, intake)) .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); - driver - .rightTrigger(0.5) - .whileTrue( - V3_EpsilonCompositeCommands.autoScoreCoralSequence( - drive, elevator, superstructure, RobotCameras.V3_Epsilon_CAMS)); + // driver + // .rightTrigger(0.5) + // .whileTrue( + // V3_EpsilonCompositeCommands.autoScoreCoralSequence( + // drive, elevator, superstructure, RobotCameras.V3_Epsilon_CAMS)); // Driver bumpers driver @@ -234,26 +242,26 @@ private void configureButtonBindings() { V3_EpsilonCompositeCommands.scoreCoralSequence( elevator, superstructure, () -> RobotState.getReefAlignData().atCoralSetpoint())); - driver - .back() - .whileTrue( - V3_EpsilonCompositeCommands.intakeAlgaeFromReefSequence( - drive, - superstructure, - () -> RobotState.getReefAlignData().algaeIntakeHeight(), - RobotCameras.V3_Epsilon_CAMS)); - - driver - .start() - .whileTrue( - V3_EpsilonCompositeCommands.dropAlgae( - drive, - elevator, - manipulator, - intake, - superstructure, - () -> RobotState.getReefAlignData().algaeIntakeHeight(), - RobotCameras.V3_Epsilon_CAMS)); + // driver + // .back() + // .whileTrue( + // V3_EpsilonCompositeCommands.intakeAlgaeFromReefSequence( + // drive, + // superstructure, + // () -> RobotState.getReefAlignData().algaeIntakeHeight(), + // RobotCameras.V3_Epsilon_CAMS)); + + // driver + // .start() + // .whileTrue( + // V3_EpsilonCompositeCommands.dropAlgae( + // drive, + // elevator, + // manipulator, + // intake, + // superstructure, + // () -> RobotState.getReefAlignData().algaeIntakeHeight(), + // RobotCameras.V3_Epsilon_CAMS)); // Operator face buttons operator.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); @@ -418,7 +426,7 @@ public void robotPeriodic() { intake.getExtension(), manipulator.getArmAngle(), elevator.getPositionMeters(), - vision.getCameras()); + // vision.getCameras()); LTNUpdater.updateDrive(drive); LTNUpdater.updateElevator(elevator); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_RobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_RobotContainer.java deleted file mode 100644 index 7bcc06d5..00000000 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_RobotContainer.java +++ /dev/null @@ -1,432 +0,0 @@ -package frc.robot.subsystems.v3_Epsilon; - -import edu.wpi.first.networktables.NetworkTablesJNI; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; -import edu.wpi.first.wpilibj2.command.button.CommandXboxController; -import edu.wpi.first.wpilibj2.command.button.Trigger; -import frc.robot.Constants; -import frc.robot.Constants.Mode; -import frc.robot.FieldConstants.Reef.ReefPose; -import frc.robot.FieldConstants.Reef.ReefState; -import frc.robot.RobotContainer; -import frc.robot.RobotState; -import frc.robot.commands.AutonomousCommands; -import frc.robot.commands.CompositeCommands.SharedCommands; -import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; -import frc.robot.commands.DriveCommands; -import frc.robot.subsystems.shared.climber.Climber; -import frc.robot.subsystems.shared.climber.ClimberIO; -import frc.robot.subsystems.shared.climber.ClimberIOTalonFX; -import frc.robot.subsystems.shared.drive.Drive; -import frc.robot.subsystems.shared.drive.DriveConstants; -import frc.robot.subsystems.shared.drive.GyroIO; -import frc.robot.subsystems.shared.drive.GyroIOPigeon2; -import frc.robot.subsystems.shared.drive.ModuleIO; -import frc.robot.subsystems.shared.drive.ModuleIOSim; -import frc.robot.subsystems.shared.drive.ModuleIOTalonFX; -import frc.robot.subsystems.shared.elevator.Elevator; -import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; -import frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions; -import frc.robot.subsystems.shared.elevator.ElevatorIO; -import frc.robot.subsystems.shared.elevator.ElevatorIOSim; -import frc.robot.subsystems.shared.elevator.ElevatorIOTalonFX; -import frc.robot.subsystems.shared.funnel.Funnel; -import frc.robot.subsystems.shared.funnel.Funnel.FunnelFSM; -import frc.robot.subsystems.shared.funnel.FunnelIO; -import frc.robot.subsystems.shared.funnel.FunnelIOSim; -import frc.robot.subsystems.shared.visionlimelight.CameraConstants.RobotCameras; -import frc.robot.subsystems.shared.visionlimelight.Vision; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonIntakeIOTalonFX; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; -import frc.robot.util.LTNUpdater; -import frc.robot.util.LoggedChoreo.ChoreoChooser; -import org.littletonrobotics.junction.Logger; - -public class V3_EpsilonRobotContainer implements RobotContainer { - // Subsystems - private Climber climber; - private Drive drive; - private ElevatorFSM elevator; - private FunnelFSM funnel; - private Vision vision; - private V3_EpsilonIntake intake; - // private V3_EpsilonLEDs leds; - private V3_EpsilonManipulator manipulator; - private V3_Superstructure superstructure; - - // Controller - private final CommandXboxController driver = new CommandXboxController(0); - private final CommandXboxController operator = new CommandXboxController(1); - - // Auto chooser - private final ChoreoChooser autoChooser = new ChoreoChooser(); - - public V3_EpsilonRobotContainer() { - - if (Constants.getMode() != Mode.REPLAY) { - switch (Constants.ROBOT) { - case V3_EPSILON: - climber = new Climber(new ClimberIOTalonFX()); - drive = - new Drive( - new GyroIOPigeon2(), - new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), - new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), - new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), - new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); - elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); - // leds = new V3_EpsilonLEDs(); - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); - superstructure = new V3_EpsilonSuperstructure(elevator, funnel, intake, manipulator); - // vision = new Vision(RobotCameras.V3_Epsilon_CAMS); - break; - case V3_EPSILON_SIM: - // climber = new Climber(new ClimberIOSim()); - drive = - new Drive( - new GyroIO() {}, - new ModuleIOSim(DriveConstants.FRONT_LEFT), - new ModuleIOSim(DriveConstants.FRONT_RIGHT), - new ModuleIOSim(DriveConstants.BACK_LEFT), - new ModuleIOSim(DriveConstants.BACK_RIGHT)); - elevator = new Elevator(new ElevatorIOSim()).getFSM(); - funnel = new Funnel(new FunnelIOSim()).getFSM(); - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); - vision = new Vision(); - break; - default: - break; - } - } - - if (climber == null) { - climber = new Climber(new ClimberIO() {}); - } - if (drive == null) { - drive = - new Drive( - new GyroIO() {}, - new ModuleIO() {}, - new ModuleIO() {}, - new ModuleIO() {}, - new ModuleIO() {}); - } - if (elevator == null) { - elevator = new Elevator(new ElevatorIO() {}).getFSM(); - } - if (funnel == null) { - funnel = new Funnel(new FunnelIO() {}).getFSM(); - } - if (intake == null) { - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); - } - if (leds == null) { - leds = new V3_EpsilonLEDs(); - } - if (manipulator == null) { - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); - } - if (vision == null) { - vision = new Vision(); - } - superstructure = new V3_EpsilonSuperstructure(elevator, funnel, intake, manipulator); - - configureButtonBindings(); - configureAutos(); - } - - private void configureButtonBindings() { - // Generic triggers - Trigger elevatorStow = - new Trigger( - () -> - elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) - || elevator.getPosition().equals(ElevatorPositions.STOW)); - Trigger elevatorNotStow = - new Trigger( - () -> - !elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) - && !elevator.getPosition().equals(ElevatorPositions.STOW)); - // Trigger halfScoreTrigger = - // new Trigger(() -> operator.getLeftY() < -DriveConstants.OPERATOR_DEADBAND); - // Trigger unHalfScoreTrigger = - // new Trigger(() -> operator.getLeftY() > DriveConstants.OPERATOR_DEADBAND); - - Trigger operatorFunnelOverride = - new Trigger(() -> Math.hypot(operator.getRightX(), operator.getRightY()) > 0.5); - - // Default drive command - drive.setDefaultCommand( - DriveCommands.joystickDrive( - drive, - () -> -driver.getLeftY(), - () -> -driver.getLeftX(), - () -> -driver.getRightX(), - () -> false, - operator.back(), - driver.povRight())); - - // Driver face buttons - driver.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); - driver.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); - driver.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); - driver.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); - - driver - .y() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); - driver - .x() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); - driver - .b() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); - driver - .a() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); - - // Driver triggers - driver - .leftTrigger(0.5) - .whileTrue(V3_EpsilonCompositeCommands.intakeCoralDriverSequence(superstructure, intake)) - .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); - driver - .rightTrigger(0.5) - .whileTrue( - V3_EpsilonCompositeCommands.autoScoreCoralSequence( - drive, elevator, superstructure, RobotCameras.V3_Epsilon_CAMS)); - - // Driver bumpers - driver - .leftBumper() - .whileTrue(V3_EpsilonCompositeCommands.floorIntakeSequence(superstructure)) - .onFalse( - Commands.deadline( - V3_EpsilonCompositeCommands.postFloorIntakeSequence(superstructure), - Commands.runOnce(() -> intake.setRollerGoal(IntakeRollerState.OUTTAKE))) - .andThen(Commands.runOnce(() -> intake.setRollerGoal(IntakeRollerState.STOP)))); - driver.rightBumper().onTrue(Commands.runOnce(() -> RobotState.toggleReefPost())); - - // Driver POV - driver.povUp().onTrue(superstructure.setPosition()); - driver.povDown().onTrue(SharedCommands.resetHeading(drive)); - driver.povLeft().onTrue(DriveCommands.inchMovement(drive, -0.5, .07)); - - driver - .leftStick() - .onTrue( - V3_EpsilonCompositeCommands.scoreCoralSequence( - elevator, superstructure, () -> RobotState.getReefAlignData().atCoralSetpoint())); - - driver - .back() - .whileTrue( - V3_EpsilonCompositeCommands.intakeAlgaeFromReefSequence( - drive, - superstructure, - () -> RobotState.getReefAlignData().algaeIntakeHeight(), - RobotCameras.V3_Epsilon_CAMS)); - - driver - .start() - .whileTrue( - V3_EpsilonCompositeCommands.dropAlgae( - drive, - elevator, - manipulator, - intake, - superstructure, - () -> RobotState.getReefAlignData().algaeIntakeHeight(), - RobotCameras.V3_Epsilon_CAMS)); - - // Operator face buttons - operator.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); - operator.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); - operator.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); - operator.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); - - operator - .y() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); - operator - .x() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); - operator - .b() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); - operator - .a() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); - - // Operator triggers - operator - .leftTrigger(0.5) - .whileTrue(V3_EpsilonCompositeCommands.intakeCoralOperatorSequence(superstructure, intake)) - .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); - operator - .rightTrigger(0.5) - .whileTrue( - superstructure.override( - () -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_CORAL), 0.4)); - - // Operator bumpers - operator.leftBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))); - operator.rightBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))); - - operator.povUp().onTrue(V3_EpsilonCompositeCommands.climb(superstructure, climber, drive)); - operator.povDown().whileTrue(climber.winchClimberManual()); - operator - .povLeft() - .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR)) - .onFalse( - superstructure - .runActionWithTimeout(V3_EpsilonSuperstructureStates.SCORE_PROCESSOR, 1) - .finallyDo(() -> RobotState.setHasAlgae(false))); - - operator - .povRight() - .whileTrue( - superstructure - .override(() -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_ALGAE)) - .finallyDo(() -> RobotState.setHasAlgae(false))); - operator.start().whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)); - - operator - .back() - .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)) - .onFalse( - superstructure - .runActionWithTimeout(V3_EpsilonSuperstructureStates.SCORE_BARGE, 0.1) - .finallyDo(() -> RobotState.setHasAlgae(false))); - - // Misc - operatorFunnelOverride - .whileTrue( - Commands.either( - superstructure.runGoal(V3_EpsilonSuperstructureStates.FUNNEL_CLOSE_WITH_STOW_UP), - superstructure.runGoal(V3_EpsilonSuperstructureStates.FUNNEL_CLOSE_WITH_STOW_DOWN), - () -> RobotState.isHasAlgae())) - .onFalse(superstructure.runPreviousState()); - } - - private void configureAutos() { - AutonomousCommands.loadAutoTrajectories(drive); - - autoChooser.addCmd( - "Drive FF Characterization", () -> DriveCommands.feedforwardCharacterization(drive)); - autoChooser.addCmd( - "Wheel Radius Characterization", () -> DriveCommands.wheelRadiusCharacterization(drive)); - autoChooser.addCmd("Elevator Characterization", () -> elevator.sysIdRoutine(superstructure)); - autoChooser.addCmd("Funnel Characterization", () -> funnel.sysIdRoutine(superstructure)); - autoChooser.addCmd("Intake Characterization", () -> intake.sysIdRoutine(superstructure)); - autoChooser.addCmd( - "Manipulator Characterization", - () -> - Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.L3), - manipulator.sysIdRoutine(superstructure))); - autoChooser.addRoutine( - "4 Piece Left", - () -> - AutonomousCommands.autoALeft( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "4 Piece Right", - () -> - AutonomousCommands.autoARight( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - - autoChooser.addRoutine( - "4 Piece Left Nashoba", - () -> - AutonomousCommands.autoALeftNashoba( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - - autoChooser.addRoutine( - "4 Piece Left D.A.V.E.", - () -> - AutonomousCommands.autoALeftDAVE( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - - autoChooser.addRoutine( - "3 Piece Left", - () -> - AutonomousCommands.autoCLeft( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "3 Piece Left Push", - () -> - AutonomousCommands.autoCLeftPush( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "3 Piece Right", - () -> - AutonomousCommands.autoCRight( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "3 Piece Right Push", - () -> - AutonomousCommands.autoCRightPush( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "2 Piece Left", - () -> - AutonomousCommands.autoBLeft( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "2 Piece Right", - () -> - AutonomousCommands.autoBRight( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "1 Piece Center", - () -> AutonomousCommands.autoDCenter(drive, superstructure, RobotCameras.V3_Epsilon_CAMS)); - SmartDashboard.putData("Autonomous Modes", autoChooser); - } - - @Override - public void robotPeriodic() { - RobotState.periodic( - drive.getRawGyroRotation(), - NetworkTablesJNI.now(), - drive.getYawVelocity(), - drive.getFieldRelativeVelocity(), - drive.getModulePositions(), - intake.getExtension(), - manipulator.getArmAngle(), - elevator.getPositionMeters(), - vision.getCameras()); - - LTNUpdater.updateDrive(drive); - LTNUpdater.updateElevator(elevator); - LTNUpdater.updateFunnel(funnel); - LTNUpdater.updateAlgaeArm(manipulator); - LTNUpdater.updateIntake(intake); - - Logger.recordOutput( - "Component Poses", - V3_EpsilonMechanism3d.getPoses( - elevator.getPositionMeters(), - funnel.getAngle(), - manipulator.getArmAngle(), - intake.getExtension())); - } - - @Override - public Command getAutonomousCommand() { - return autoChooser.selectedCommand(); - } -} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java similarity index 81% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 60764026..7d2e27b9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -8,8 +8,8 @@ import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureEdges.AlgaeEdge; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureEdges.EdgeCommand; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.AlgaeEdge; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.EdgeCommand; import frc.robot.util.NTPrefixes; import java.util.HashMap; import java.util.LinkedList; @@ -25,12 +25,12 @@ import org.littletonrobotics.junction.Logger; /** - * The V3_Superstructure class manages the coordinated movement and state transitions of the robot's + * The V3_EpsilonSuperstructure class manages the coordinated movement and state transitions of the robot's * major subsystems including elevator, funnel, manipulator, and intake. */ -public class V3_Superstructure extends SubsystemBase { +public class V3_EpsilonSuperstructure extends SubsystemBase { - private final Graph graph; + private final Graph graph; private final ElevatorFSM elevator; private final V3_EpsilonIntake intake; private final V3_EpsilonManipulator manipulator; @@ -39,53 +39,53 @@ public class V3_Superstructure extends SubsystemBase { * The previous, current, and next states of the superstructure. These are used to track the state * transitions and manage the command scheduling. */ - @Getter private V3_SuperstructureStates previousState; + @Getter private V3_EpsilonSuperstructureStates previousState; /** * The current state of the superstructure, which is updated periodically based on the command * scheduling and state transitions. */ - @Getter private V3_SuperstructureStates currentState; + @Getter private V3_EpsilonSuperstructureStates currentState; /** * The next state that the superstructure is transitioning to. This is determined by the command * scheduling and the current target state. */ - @Getter private V3_SuperstructureStates nextState; + @Getter private V3_EpsilonSuperstructureStates nextState; /** * The target state that the superstructure is trying to achieve. This is set by the robot and * determines the next action to be taken. */ - @Getter private V3_SuperstructureStates targetState; + @Getter private V3_EpsilonSuperstructureStates targetState; /** The command that is currently being executed to transition between states. */ private EdgeCommand edgeCommand; /** - * Constructs a V3_Superstructure. + * Constructs a V3_EpsilonSuperstructure. * * @param elevator The elevator subsystem. * @param funnel The funnel subsystem. * @param intake The intake subsystem. * @param manipulator The manipulator subsystem. */ - public V3_Superstructure( + public V3_EpsilonSuperstructure( ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { this.elevator = elevator; this.intake = intake; this.manipulator = manipulator; previousState = null; - currentState = V3_SuperstructureStates.START; + currentState = V3_EpsilonSuperstructureStates.START; nextState = null; - targetState = V3_SuperstructureStates.START; + targetState = V3_EpsilonSuperstructureStates.START; // Initialize the graph graph = new DefaultDirectedGraph<>(EdgeCommand.class); - for (V3_SuperstructureStates vertex : V3_SuperstructureStates.values()) { + for (V3_EpsilonSuperstructureStates vertex : V3_EpsilonSuperstructureStates.values()) { graph.addVertex(vertex); } } @@ -147,7 +147,7 @@ public void periodic() { * * @param goal New target state to achieve */ - private void setGoal(V3_SuperstructureStates goal) { + private void setGoal(V3_EpsilonSuperstructureStates goal) { // Don't do anything if goal is the same if (this.targetState == goal) return; else { @@ -197,20 +197,20 @@ && isEdgeAllowed(edgeToCurrentState, goal)) { * @param goal Target state * @return Optional containing the next state in the path, empty if no path exists */ - private Optional bfs( - V3_SuperstructureStates start, V3_SuperstructureStates goal) { - Map parents = new HashMap<>(); - Queue queue = new LinkedList<>(); + private Optional bfs( + V3_EpsilonSuperstructureStates start, V3_EpsilonSuperstructureStates goal) { + Map parents = new HashMap<>(); + Queue queue = new LinkedList<>(); queue.add(start); parents.put(start, null); while (!queue.isEmpty()) { - V3_SuperstructureStates current = queue.poll(); + V3_EpsilonSuperstructureStates current = queue.poll(); if (current == goal) break; for (EdgeCommand edge : graph.outgoingEdgesOf(current).stream() .filter(edge -> isEdgeAllowed(edge, goal)) .toList()) { - V3_SuperstructureStates neighbor = graph.getEdgeTarget(edge); + V3_EpsilonSuperstructureStates neighbor = graph.getEdgeTarget(edge); if (!parents.containsKey(neighbor)) { parents.put(neighbor, current); queue.add(neighbor); @@ -220,9 +220,9 @@ private Optional bfs( if (!parents.containsKey(goal)) return Optional.empty(); - V3_SuperstructureStates nextState = goal; + V3_EpsilonSuperstructureStates nextState = goal; while (!nextState.equals(start)) { - V3_SuperstructureStates parent = parents.get(nextState); + V3_EpsilonSuperstructureStates parent = parents.get(nextState); if (parent == null) return Optional.empty(); else if (parent.equals(start)) return Optional.of(nextState); nextState = parent; @@ -237,16 +237,16 @@ private Optional bfs( * @param goal The target state * @return true if the transition is allowed */ - private boolean isEdgeAllowed(EdgeCommand edge, V3_SuperstructureStates goal) { // Change later + private boolean isEdgeAllowed(EdgeCommand edge, V3_EpsilonSuperstructureStates goal) { // Change later return edge.getAlgaeEdgeType() == AlgaeEdge.NONE || RobotState.isHasAlgae() == (edge.getAlgaeEdgeType() == AlgaeEdge.ALGAE); } /** Resets the superstructure to initial auto state. */ public void setAutoStart() { - currentState = V3_SuperstructureStates.START; + currentState = V3_EpsilonSuperstructureStates.START; nextState = null; - targetState = V3_SuperstructureStates.STOW_DOWN; + targetState = V3_EpsilonSuperstructureStates.STOW_DOWN; if (edgeCommand != null) { edgeCommand.getCommand().cancel(); } @@ -259,7 +259,7 @@ public void setAutoStart() { * @param goal The desired superstructure state * @return Command to run the goal */ - public Command runGoal(V3_SuperstructureStates goal) { + public Command runGoal(V3_EpsilonSuperstructureStates goal) { return runOnce(() -> setGoal(goal)); } @@ -269,7 +269,7 @@ public Command runGoal(V3_SuperstructureStates goal) { * @param goal Supplier providing the desired superstructure state * @return Command to run the goal */ - public Command runGoal(Supplier goal) { + public Command runGoal(Supplier goal) { return runOnce(() -> setGoal(goal.get())); } @@ -291,7 +291,7 @@ public boolean atGoal() { * @return Command that runs the override and resumes the old goal */ public Command override(Runnable action) { - return Commands.sequence(runGoal(V3_SuperstructureStates.OVERRIDE), Commands.run(action)) + return Commands.sequence(runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), Commands.run(action)) .finallyDo(() -> setGoal(currentState)); } @@ -313,11 +313,11 @@ public Command override(Runnable action, double timeSeconds) { * @param condition The condition to wait for after running the goal * @return Combined command for running and waiting */ - public Command runGoalUntil(V3_SuperstructureStates goal, BooleanSupplier condition) { + public Command runGoalUntil(V3_EpsilonSuperstructureStates goal, BooleanSupplier condition) { return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); } - public Command runGoalUntil(Supplier goal, BooleanSupplier condition) { + public Command runGoalUntil(Supplier goal, BooleanSupplier condition) { return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); } @@ -339,7 +339,7 @@ public Command runPreviousState() { * @return Full command sequence */ public Command runActionWithTimeout( - V3_SuperstructureStates pose, V3_SuperstructureStates action, double timeout) { + V3_EpsilonSuperstructureStates pose, V3_EpsilonSuperstructureStates action, double timeout) { return Commands.sequence( runGoal(action), // Run the action Commands.waitUntil(() -> atGoal()), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureActions.java similarity index 90% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureActions.java index f5fb9370..80ebf662 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureActions.java @@ -6,7 +6,7 @@ import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; import lombok.Getter; -public class V3_SuperstructureActions { +public class V3_EpsilonSuperstructureActions { @Getter private final V3_EpsilonManipulatorConstants.ManipulatorRollerStates manipulatorRollerState; @@ -14,13 +14,13 @@ public class V3_SuperstructureActions { @Getter private final V3_EpsilonIntakeConstants.IntakeRollerStates intakeRollerStates; /** - * Creates a new instance of V3_SuperstructureActions with the specified key and subsystem + * Creates a new instance of V3_EpsilonSuperstructureActions with the specified key and subsystem * actions. * * @param key * @param subsystemActions */ - public V3_SuperstructureActions(String key, SubsystemActions subsystemActions) { + public V3_EpsilonSuperstructureActions(String key, SubsystemActions subsystemActions) { this.manipulatorRollerState = V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP; this.intakeRollerStates = V3_EpsilonIntakeConstants.IntakeRollerStates.STOP; } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java new file mode 100644 index 00000000..799b9261 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -0,0 +1,246 @@ +package frc.robot.subsystems.v3_Epsilon.superstructure; + +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; +import frc.robot.subsystems.shared.elevator.Elevator; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; +import java.util.ArrayList; +import java.util.List; +import lombok.Builder; +import lombok.Getter; +import org.jgrapht.graph.DefaultEdge; + +public class V3_EpsilonSuperstructureEdges { + + public static final ArrayList AlgaeEdges = new ArrayList<>(); + public static final ArrayList CoralEdges = new ArrayList<>(); + public static final ArrayList UnconstrainedEdges = new ArrayList<>(); + public static final ArrayList NoneEdges = new ArrayList<>(); + + public record Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to, String action) { + public Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { + this(from, to, ""); + } + + public String toString() { + return from + " -> " + to + (action.isEmpty() ? "" : " : " + action); + } + } + + public enum AlgaeEdge { + NONE, + NO_ALGAE, + ALGAE + } + + public enum CoralEdge { + NONE, + NO_CORAL, + CORAL + } + + @Builder(toBuilder = true) + @Getter + public static class EdgeCommand extends DefaultEdge { + private final Command command; + @Builder.Default private final AlgaeEdge algaeEdgeType = AlgaeEdge.NONE; + @Builder.Default private final CoralEdge coralEdgeType = CoralEdge.NONE; + } + + private static Command getEdgeCommand( + V3_EpsilonSuperstructureStates from, + V3_EpsilonSuperstructureStates to, + Elevator.ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + + // TODO: Implement the actual command logic + + return Commands.none(); + } + + public static void createEdges() { + List coralPrepLevels = + List.of( + V3_EpsilonSuperstructureStates.L1_PREP, + V3_EpsilonSuperstructureStates.L2_PREP, + V3_EpsilonSuperstructureStates.L3_PREP, + V3_EpsilonSuperstructureStates.L4_PREP); + + List coralTransitionLevels = + List.of( + V3_EpsilonSuperstructureStates.L2_TRANSITION, + V3_EpsilonSuperstructureStates.L3_TRANSITION, + V3_EpsilonSuperstructureStates.L4_TRANSITION); + + // Coral Edges + + // Level to level edges + for (V3_EpsilonSuperstructureStates from : coralPrepLevels) { + for (V3_EpsilonSuperstructureStates to : coralPrepLevels) { + if (from != to) { + CoralEdges.add(new Edge(from, to, "Coral Level Transition")); + } + } + } + + // Handoff -> transition + for (V3_EpsilonSuperstructureStates to : coralTransitionLevels) { + CoralEdges.add(new Edge(V3_EpsilonSuperstructureStates.HANDOFF, to, "Coral Transition")); + } + + // Handoff -> L1_PREP + CoralEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L1_PREP, + V3_EpsilonSuperstructureStates.HANDOFF, + "Coral Handoff L1 Prep")); + + // Transition -> handoff + for (V3_EpsilonSuperstructureStates from : coralTransitionLevels) { + CoralEdges.add(new Edge(from, V3_EpsilonSuperstructureStates.HANDOFF, "Coral Handoff")); + } + + // Coral Prep to Transition + for (V3_EpsilonSuperstructureStates from : coralPrepLevels) { + for (V3_EpsilonSuperstructureStates to : coralTransitionLevels) { + CoralEdges.add(new Edge(from, to, "Coral Transition")); + } + } + + // Coral Transition to Prep + CoralEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_TRANSITION, + V3_EpsilonSuperstructureStates.L2_PREP, + "Coral Transition L2")); + CoralEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_TRANSITION, + V3_EpsilonSuperstructureStates.L3_PREP, + "Coral Transition L3")); + CoralEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L4_TRANSITION, + V3_EpsilonSuperstructureStates.L4_PREP, + "Coral Transition L4")); + + // Prep to score states + CoralEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L1_PREP, V3_EpsilonSuperstructureStates.L1_SCORE, "Coral Score L1")); + CoralEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_PREP, V3_EpsilonSuperstructureStates.L2_SCORE, "Coral Score L2")); + CoralEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_PREP, V3_EpsilonSuperstructureStates.L3_SCORE, "Coral Score L3")); + CoralEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L4_PREP, V3_EpsilonSuperstructureStates.L4_SCORE, "Coral Score L4")); + + // L1_SCORE -> GROUND_INTAKE + CoralEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L1_PREP, + V3_EpsilonSuperstructureStates.GROUND_INTAKE, + "Coral Transition L1")); + + // Algae Edges + + // STOW_DOWN --> L2_ALGAE_PREP + AlgaeEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L2_ALGAE_PREP, + "Algae Prep L2 from STOW DOWN")); + + // Prep --> intake states + AlgaeEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_ALGAE_PREP, + V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE, + "Algae Intake L2")); + AlgaeEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_ALGAE_PREP, + V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE, + "Algae Intake L3")); + + // Prep <-> Prep States + AlgaeEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_ALGAE_PREP, + V3_EpsilonSuperstructureStates.L3_ALGAE_PREP, + "Algae Prep L2 to L3")); + AlgaeEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_ALGAE_PREP, + V3_EpsilonSuperstructureStates.L2_ALGAE_PREP, + "Algae Prep L3 to L2")); + + // BARGE_PREP Edges + AlgaeEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_ALGAE_PREP, + V3_EpsilonSuperstructureStates.BARGE_PREP, + "Algae Prep Barge to L2")); + AlgaeEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_ALGAE_PREP, + V3_EpsilonSuperstructureStates.BARGE_PREP, + "Algae Prep Barge to L3")); + AlgaeEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.STOW_UP, + V3_EpsilonSuperstructureStates.BARGE_PREP, + "Algae Prep L2 to Barge")); + AlgaeEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.BARGE_PREP, + V3_EpsilonSuperstructureStates.BARGE_SCORE, + "Algae Prep L2 to Barge")); + + // PROCESSOR Edges + AlgaeEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.PROCESSOR_PREP, + V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, + "Algae Processor L2")); + AlgaeEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_ALGAE_PREP, + V3_EpsilonSuperstructureStates.PROCESSOR_PREP, + "Algae Processor L2 Prep")); + AlgaeEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_ALGAE_PREP, + V3_EpsilonSuperstructureStates.PROCESSOR_PREP, + "Algae Processor L3 Prep")); + + // Unconstrained Edges + + // BARGE_SCORE -> STOW_DOWN + UnconstrainedEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.BARGE_SCORE, + V3_EpsilonSuperstructureStates.STOW_DOWN, + "BARGE_SCORE to Stow Down")); + UnconstrainedEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.BARGE_SCORE, + V3_EpsilonSuperstructureStates.STOW_UP, + "BARGE_SCORE to Stow Up")); + UnconstrainedEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, + V3_EpsilonSuperstructureStates.STOW_DOWN, + "Algae Processor Barge Prep")); + UnconstrainedEdges.add( + new Edge( + V3_EpsilonSuperstructureStates.STOW_UP, + V3_EpsilonSuperstructureStates.STOW_DOWN, + "Algae Processor Barge Prep")); + } +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePoses.java similarity index 96% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePoses.java index 014135c9..c077de17 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePoses.java @@ -10,14 +10,14 @@ import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; import lombok.Getter; -public class V3_SuperstructurePoses { +public class V3_EpsilonSuperstructurePoses { private String key; @Getter private final ReefState elevatorHeight; @Getter private final V3_EpsilonManipulatorConstants.PivotState pivotState; @Getter private final V3_EpsilonIntakeConstants.IntakeState intakeState; - public V3_SuperstructurePoses(String key, SubsystemPoses poses) { + public V3_EpsilonSuperstructurePoses(String key, SubsystemPoses poses) { this.key = key; this.elevatorHeight = poses.elevatorHeight(); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java similarity index 92% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 0205fe6a..d099d013 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -4,14 +4,14 @@ import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureActions.SubsystemActions; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructurePoses.SubsystemPoses; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureActions.SubsystemActions; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructurePoses.SubsystemPoses; // Ensure this is the // correct package // path -public enum V3_SuperstructureStates { +public enum V3_EpsilonSuperstructureStates { START("START", new SubsystemPoses(), SubsystemActions.empty()), STOW_DOWN("STOW_DOWN", new SubsystemPoses(), SubsystemActions.empty()), STOW_UP( @@ -246,26 +246,26 @@ public enum V3_SuperstructureStates { private final SubsystemActions subsystemActions; /** - * Constructor for V3_SuperstructureStates. + * Constructor for V3_EpsilonSuperstructureStates. * * @param name The name of the state. * @param pose The subsystem poses for this state. * @param action The subsystem actions for this state. */ - V3_SuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { + V3_EpsilonSuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { this.name = name; this.subsystemPoses = pose; this.subsystemActions = action; } /** - * Constructor for V3_SuperstructureStates with empty actions. + * Constructor for V3_EpsilonSuperstructureStates with empty actions. * * @param name The name of the state. * @param pose The subsystem poses for this state. */ - public V3_SuperstructurePoses getPose() { - return new V3_SuperstructurePoses(name, subsystemPoses); + public V3_EpsilonSuperstructurePoses getPose() { + return new V3_EpsilonSuperstructurePoses(name, subsystemPoses); } /** @@ -273,8 +273,8 @@ public V3_SuperstructurePoses getPose() { * * @return The actions for this state. */ - public V3_SuperstructureActions getAction() { - return new V3_SuperstructureActions(name, subsystemActions); + public V3_EpsilonSuperstructureActions getAction() { + return new V3_EpsilonSuperstructureActions(name, subsystemActions); } /** diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java deleted file mode 100644 index fa0c4415..00000000 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java +++ /dev/null @@ -1,246 +0,0 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure; - -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; -import frc.robot.subsystems.shared.elevator.Elevator; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; -import java.util.ArrayList; -import java.util.List; -import lombok.Builder; -import lombok.Getter; -import org.jgrapht.graph.DefaultEdge; - -public class V3_SuperstructureEdges { - - public static final ArrayList AlgaeEdges = new ArrayList<>(); - public static final ArrayList CoralEdges = new ArrayList<>(); - public static final ArrayList UnconstrainedEdges = new ArrayList<>(); - public static final ArrayList NoneEdges = new ArrayList<>(); - - public record Edge(V3_SuperstructureStates from, V3_SuperstructureStates to, String action) { - public Edge(V3_SuperstructureStates from, V3_SuperstructureStates to) { - this(from, to, ""); - } - - public String toString() { - return from + " -> " + to + (action.isEmpty() ? "" : " : " + action); - } - } - - public enum AlgaeEdge { - NONE, - NO_ALGAE, - ALGAE - } - - public enum CoralEdge { - NONE, - NO_CORAL, - CORAL - } - - @Builder(toBuilder = true) - @Getter - public static class EdgeCommand extends DefaultEdge { - private final Command command; - @Builder.Default private final AlgaeEdge algaeEdgeType = AlgaeEdge.NONE; - @Builder.Default private final CoralEdge coralEdgeType = CoralEdge.NONE; - } - - private static Command getEdgeCommand( - V3_SuperstructureStates from, - V3_SuperstructureStates to, - Elevator.ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - - // TODO: Implement the actual command logic - - return Commands.none(); - } - - public static void createEdges() { - List coralPrepLevels = - List.of( - V3_SuperstructureStates.L1_PREP, - V3_SuperstructureStates.L2_PREP, - V3_SuperstructureStates.L3_PREP, - V3_SuperstructureStates.L4_PREP); - - List coralTransitionLevels = - List.of( - V3_SuperstructureStates.L2_TRANSITION, - V3_SuperstructureStates.L3_TRANSITION, - V3_SuperstructureStates.L4_TRANSITION); - - // Coral Edges - - // Level to level edges - for (V3_SuperstructureStates from : coralPrepLevels) { - for (V3_SuperstructureStates to : coralPrepLevels) { - if (from != to) { - CoralEdges.add(new Edge(from, to, "Coral Level Transition")); - } - } - } - - // Handoff -> transition - for (V3_SuperstructureStates to : coralTransitionLevels) { - CoralEdges.add(new Edge(V3_SuperstructureStates.HANDOFF, to, "Coral Transition")); - } - - // Handoff -> L1_PREP - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L1_PREP, - V3_SuperstructureStates.HANDOFF, - "Coral Handoff L1 Prep")); - - // Transition -> handoff - for (V3_SuperstructureStates from : coralTransitionLevels) { - CoralEdges.add(new Edge(from, V3_SuperstructureStates.HANDOFF, "Coral Handoff")); - } - - // Coral Prep to Transition - for (V3_SuperstructureStates from : coralPrepLevels) { - for (V3_SuperstructureStates to : coralTransitionLevels) { - CoralEdges.add(new Edge(from, to, "Coral Transition")); - } - } - - // Coral Transition to Prep - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L2_TRANSITION, - V3_SuperstructureStates.L2_PREP, - "Coral Transition L2")); - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L3_TRANSITION, - V3_SuperstructureStates.L3_PREP, - "Coral Transition L3")); - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L4_TRANSITION, - V3_SuperstructureStates.L4_PREP, - "Coral Transition L3")); - - // Prep to score states - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.L1_SCORE, "Coral Score L1")); - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L2_PREP, V3_SuperstructureStates.L2_SCORE, "Coral Score L2")); - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L3_PREP, V3_SuperstructureStates.L3_SCORE, "Coral Score L3")); - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L4_PREP, V3_SuperstructureStates.L4_SCORE, "Coral Score L4")); - - // L1_SCORE -> GROUND_INTAKE - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L1_PREP, - V3_SuperstructureStates.GROUND_INTAKE, - "Coral Transition L1")); - - // Algae Edges - - // STOW_DOWN --> L2_ALGAE_PREP - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.STOW_DOWN, - V3_SuperstructureStates.L2_ALGAE_PREP, - "Algae Prep L2 from STOW DOWN")); - - // Prep --> intake states - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.L2_ALGAE_PREP, - V3_SuperstructureStates.L2_ALGAE_INTAKE, - "Algae Intake L2")); - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.L3_ALGAE_PREP, - V3_SuperstructureStates.L3_ALGAE_INTAKE, - "Algae Intake L3")); - - // Prep <-> Prep States - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.L2_ALGAE_PREP, - V3_SuperstructureStates.L3_ALGAE_PREP, - "Algae Prep L2 to L3")); - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.L3_ALGAE_PREP, - V3_SuperstructureStates.L2_ALGAE_PREP, - "Algae Prep L3 to L2")); - - // BARGE_PREP Edges - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.L2_ALGAE_PREP, - V3_SuperstructureStates.BARGE_PREP, - "Algae Prep Barge to L2")); - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.L3_ALGAE_PREP, - V3_SuperstructureStates.BARGE_PREP, - "Algae Prep Barge to L3")); - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.STOW_UP, - V3_SuperstructureStates.BARGE_PREP, - "Algae Prep L2 to Barge")); - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.BARGE_PREP, - V3_SuperstructureStates.BARGE_SCORE, - "Algae Prep L2 to Barge")); - - // PROCESSOR Edges - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.PROCESSOR_PREP, - V3_SuperstructureStates.PROCESSOR_SCORE, - "Algae Processor L2")); - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.L2_ALGAE_PREP, - V3_SuperstructureStates.PROCESSOR_PREP, - "Algae Processor L2 Prep")); - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.L3_ALGAE_PREP, - V3_SuperstructureStates.PROCESSOR_PREP, - "Algae Processor L3 Prep")); - - // Unconstrained Edges - - // BARGE_SCORE -> STOW_DOWN - UnconstrainedEdges.add( - new Edge( - V3_SuperstructureStates.BARGE_SCORE, - V3_SuperstructureStates.STOW_DOWN, - "BARGE_SCORE to Stow Down")); - UnconstrainedEdges.add( - new Edge( - V3_SuperstructureStates.BARGE_SCORE, - V3_SuperstructureStates.STOW_UP, - "BARGE_SCORE to Stow Up")); - UnconstrainedEdges.add( - new Edge( - V3_SuperstructureStates.PROCESSOR_SCORE, - V3_SuperstructureStates.STOW_DOWN, - "Algae Processor Barge Prep")); - UnconstrainedEdges.add( - new Edge( - V3_SuperstructureStates.STOW_UP, - V3_SuperstructureStates.STOW_DOWN, - "Algae Processor Barge Prep")); - } -} From 05436f75875f551f2f4e67bdd9239d53d4f3ecf3 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Fri, 29 Aug 2025 20:03:52 -0400 Subject: [PATCH 048/180] Fixed some more errors with V3 Robot Container Co-authored-by: ThatGuyRuchir --- src/main/java/frc/robot/FieldConstants.java | 4 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 254 +++++++++--------- .../intake/V3_EpsilonIntakeConstants.java | 3 +- .../manipulator/V3_EpsilonManipulator.java | 2 + .../V3_EpsilonSuperstructure.java | 36 +++ .../V3_EpsilonSuperstructureStates.java | 4 +- 6 files changed, 174 insertions(+), 129 deletions(-) diff --git a/src/main/java/frc/robot/FieldConstants.java b/src/main/java/frc/robot/FieldConstants.java index c85ad048..6558ceb7 100644 --- a/src/main/java/frc/robot/FieldConstants.java +++ b/src/main/java/frc/robot/FieldConstants.java @@ -69,7 +69,9 @@ public static enum ReefState { L3, L4, L4_PLUS, - ALGAE_SCORE + ALGAE_SCORE, + STOW_UP, + STOW_DOWN } public static record FaceSetpoints(Pose2d right, Pose2d left, Pose2d algae, Pose2d center) { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index e6fcf8d0..4a0e7361 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -47,9 +47,11 @@ import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIOTalonFX; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIO; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIOSim; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants.IntakeRollerStates; // import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure.java; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerStates; @@ -67,15 +69,12 @@ public class V3_EpsilonRobotContainer implements RobotContainer { private V3_EpsilonIntake intake; // private V3_EpsilonLEDs leds; private V3_EpsilonManipulator manipulator; - private V3_EpsilonSuperstructure superstructure; - private V3_EpsilonManipulatorIO manipulatorIO; + private V3_EpsilonSuperstructure superstructure;; // Controller private final CommandXboxController driver = new CommandXboxController(0); private final CommandXboxController operator = new CommandXboxController(1); - manipulatorIO = new V3_EpsilonManipulatorIO(); - // Auto chooser private final ChoreoChooser autoChooser = new ChoreoChooser(); @@ -95,7 +94,7 @@ public V3_EpsilonRobotContainer() { elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); // leds = new V3_EpsilonLEDs(); - manipulator = new V3_EpsilonManipulator(manipulatorIO); + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); // Doesn't include states // vision = new Vision(RobotCameras.V3_Epsilon_CAMS); break; @@ -109,19 +108,19 @@ public V3_EpsilonRobotContainer() { new ModuleIOSim(DriveConstants.BACK_LEFT), new ModuleIOSim(DriveConstants.BACK_RIGHT)); elevator = new Elevator(new ElevatorIOSim()).getFSM(); - funnel = new Funnel(new FunnelIOSim()).getFSM(); + // funnel = new Funnel(new FunnelIOSim()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); // vision = new Vision(); break; default: break; - } } - if (climber == null) { - climber = new Climber(new ClimberIO() {}); - } + // if (climber == null) { + // climber = new Climber(new ClimberIO() {}); + // } + if (drive == null) { drive = new Drive( @@ -142,14 +141,14 @@ public V3_EpsilonRobotContainer() { } // if (leds == null) { // leds = new V3_EpsilonLEDs(); - } + // } if (manipulator == null) { manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); } // if (vision == null) { // vision = new Vision(); // } - superstructure = new V3_EpsilonSuperstructure(elevator, funnel, intake, manipulator); + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); configureButtonBindings(); configureAutos(); @@ -184,7 +183,7 @@ private void configureButtonBindings() { () -> -driver.getRightX(), () -> false, operator.back(), - driver.povRight())); + driver.povRight().onTrue(Commands.runOnce(() -> {})))); // Driver face buttons driver.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); @@ -227,8 +226,8 @@ private void configureButtonBindings() { .onFalse( Commands.deadline( V3_EpsilonCompositeCommands.postFloorIntakeSequence(superstructure), - Commands.runOnce(() -> intake.setRollerGoal(IntakeRollerState.OUTTAKE))) - .andThen(Commands.runOnce(() -> intake.setRollerGoal(IntakeRollerState.STOP)))); + Commands.runOnce(() -> intake.setRollerGoal(IntakeRollerStates.OUTTAKE))) + .andThen(Commands.runOnce(() -> intake.setRollerGoal(IntakeRollerStates.STOP)))); driver.rightBumper().onTrue(Commands.runOnce(() -> RobotState.toggleReefPost())); // Driver POV @@ -296,7 +295,7 @@ private void configureButtonBindings() { .rightTrigger(0.5) .whileTrue( superstructure.override( - () -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_CORAL), 0.4)); + () -> manipulator.setRollerGoal(ManipulatorRollerStates.SCORE_CORAL), 0.4)); // Operator bumpers operator.leftBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))); @@ -306,145 +305,150 @@ private void configureButtonBindings() { operator.povDown().whileTrue(climber.winchClimberManual()); operator .povLeft() - .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR)) + .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR_PREP)) .onFalse( superstructure - .runActionWithTimeout(V3_EpsilonSuperstructureStates.SCORE_PROCESSOR, 1) + .runActionWithTimeout(V3_EpsilonSuperstructureStates.PROCESSOR_PREP, + V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, 1) .finallyDo(() -> RobotState.setHasAlgae(false))); operator .povRight() .whileTrue( superstructure - .override(() -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_ALGAE)) + .override(() -> manipulator.setRollerGoal(ManipulatorRollerStates.SCORE_ALGAE)) .finallyDo(() -> RobotState.setHasAlgae(false))); - operator.start().whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)); + operator.start().whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE_PREP)); operator .back() - .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)) + .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE_PREP)) .onFalse( superstructure - .runActionWithTimeout(V3_EpsilonSuperstructureStates.SCORE_BARGE, 0.1) + .runActionWithTimeout(V3_EpsilonSuperstructureStates.BARGE_PREP, + V3_EpsilonSuperstructureStates.BARGE_SCORE, 0.1) .finallyDo(() -> RobotState.setHasAlgae(false))); // Misc operatorFunnelOverride .whileTrue( Commands.either( - superstructure.runGoal(V3_EpsilonSuperstructureStates.FUNNEL_CLOSE_WITH_STOW_UP), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), superstructure.runGoal( - V3_EpsilonSuperstructureStates.FUNNEL_CLOSE_WITH_STOW_DOWN), + V3_EpsilonSuperstructureStates.STOW_DOWN), () -> RobotState.isHasAlgae())) .onFalse(superstructure.runPreviousState()); } private void configureAutos() { - AutonomousCommands.loadAutoTrajectories(drive); - - autoChooser.addCmd( - "Drive FF Characterization", () -> DriveCommands.feedforwardCharacterization(drive)); - autoChooser.addCmd( - "Wheel Radius Characterization", () -> DriveCommands.wheelRadiusCharacterization(drive)); - autoChooser.addCmd("Elevator Characterization", () -> elevator.sysIdRoutine(superstructure)); - autoChooser.addCmd("Funnel Characterization", () -> funnel.sysIdRoutine(superstructure)); - autoChooser.addCmd("Intake Characterization", () -> intake.sysIdRoutine(superstructure)); - autoChooser.addCmd( - "Manipulator Characterization", - () -> - Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.L3), - manipulator.sysIdRoutine(superstructure))); - autoChooser.addRoutine( - "4 Piece Left", - () -> - AutonomousCommands.autoALeft( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "4 Piece Right", - () -> - AutonomousCommands.autoARight( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - - autoChooser.addRoutine( - "4 Piece Left Nashoba", - () -> - AutonomousCommands.autoALeftNashoba( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - - autoChooser.addRoutine( - "4 Piece Left D.A.V.E.", - () -> - AutonomousCommands.autoALeftDAVE( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - - autoChooser.addRoutine( - "3 Piece Left", - () -> - AutonomousCommands.autoCLeft( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "3 Piece Left Push", - () -> - AutonomousCommands.autoCLeftPush( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "3 Piece Right", - () -> - AutonomousCommands.autoCRight( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "3 Piece Right Push", - () -> - AutonomousCommands.autoCRightPush( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "2 Piece Left", - () -> - AutonomousCommands.autoBLeft( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "2 Piece Right", - () -> - AutonomousCommands.autoBRight( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "1 Piece Center", - () -> - AutonomousCommands.autoDCenter(drive, superstructure, RobotCameras.V3_Epsilon_CAMS)); - SmartDashboard.putData("Autonomous Modes", autoChooser); - } + // AutonomousCommands.loadAutoTrajectories(drive); + + // autoChooser.addCmd( + // "Drive FF Characterization", () -> DriveCommands.feedforwardCharacterization(drive)); + // autoChooser.addCmd( + // "Wheel Radius Characterization", () -> DriveCommands.wheelRadiusCharacterization(drive)); + // autoChooser.addCmd("Elevator Characterization", () -> elevator.sysIdRoutine(superstructure)); + // // autoChooser.addCmd("Funnel Characterization", () -> funnel.sysIdRoutine(superstructure)); + // autoChooser.addCmd("Intake Characterization", () -> intake.sysIdRoutine(superstructure)); +// autoChooser.addCmd( +// "Manipulator Characterization", +// () -> +// Commands.sequence( +// superstructure.runGoal(V3_EpsilonSuperstructureStates.L3), +// manipulator.sysIdRoutine(superstructure))); +// autoChooser.addRoutine( +// "4 Piece Left", +// () -> +// AutonomousCommands.autoALeft( +// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); +// autoChooser.addRoutine( +// "4 Piece Right", +// () -> +// AutonomousCommands.autoARight( +// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + +// autoChooser.addRoutine( +// "4 Piece Left Nashoba", +// () -> +// AutonomousCommands.autoALeftNashoba( +// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + +// autoChooser.addRoutine( +// "4 Piece Left D.A.V.E.", +// () -> +// AutonomousCommands.autoALeftDAVE( +// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); + +// autoChooser.addRoutine( +// "3 Piece Left", +// () -> +// AutonomousCommands.autoCLeft( +// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); +// autoChooser.addRoutine( +// "3 Piece Left Push", +// () -> +// AutonomousCommands.autoCLeftPush( +// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); +// autoChooser.addRoutine( +// "3 Piece Right", +// () -> +// AutonomousCommands.autoCRight( +// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); +// autoChooser.addRoutine( +// "3 Piece Right Push", +// () -> +// AutonomousCommands.autoCRightPush( +// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); +// autoChooser.addRoutine( +// "2 Piece Left", +// () -> +// AutonomousCommands.autoBLeft( +// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); +// autoChooser.addRoutine( +// "2 Piece Right", +// () -> +// AutonomousCommands.autoBRight( +// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); +// autoChooser.addRoutine( +// "1 Piece Center", +// () -> +// AutonomousCommands.autoDCenter(drive, superstructure, RobotCameras.V3_Epsilon_CAMS)); +// SmartDashboard.putData("Autonomous Modes", autoChooser); +// } + +// @Override +// public void robotPeriodic() { +// RobotState.periodic( +// drive.getRawGyroRotation(), +// NetworkTablesJNI.now(), +// drive.getYawVelocity(), +// drive.getFieldRelativeVelocity(), +// drive.getModulePositions(), +// manipulator.getArmAngle(), +// elevator.getPositionMeters()); + +// LTNUpdater.updateDrive(drive); +// LTNUpdater.updateElevator(elevator); +// LTNUpdater.updateFunnel(funnel); +// LTNUpdater.updateAlgaeArm(manipulator); +// LTNUpdater.updateIntake(intake); + +// Logger.recordOutput( +// "Component Poses", +// V3_EpsilonMechanism3d.getPoses( +// elevator.getPositionMeters(), +// funnel.getAngle(), +// manipulator.getArmAngle(), +// intake.getExtension())); +// } - @Override - public void robotPeriodic() { - RobotState.periodic( - drive.getRawGyroRotation(), - NetworkTablesJNI.now(), - drive.getYawVelocity(), - drive.getFieldRelativeVelocity(), - drive.getModulePositions(), - intake.getExtension(), - manipulator.getArmAngle(), - elevator.getPositionMeters(), - // vision.getCameras()); - - LTNUpdater.updateDrive(drive); - LTNUpdater.updateElevator(elevator); - LTNUpdater.updateFunnel(funnel); - LTNUpdater.updateAlgaeArm(manipulator); - LTNUpdater.updateIntake(intake); - - Logger.recordOutput( - "Component Poses", - V3_EpsilonMechanism3d.getPoses( - elevator.getPositionMeters(), - funnel.getAngle(), - manipulator.getArmAngle(), - intake.getExtension())); - } @Override public Command getAutonomousCommand() { return autoChooser.selectedCommand(); } + + } +} + } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java index a9cea76e..84668924 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java @@ -75,7 +75,8 @@ public static enum IntakeRollerStates { STOP(0.0), CORAL_INTAKE(6.0), ALGAE_INTAKE(12.0), - SCORE_CORAL(6.0); + SCORE_CORAL(6.0), + OUTTAKE(10.0); private final double voltage; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java index 277f9afe..66ba61d2 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java @@ -174,4 +174,6 @@ public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerStates io.setRollerVoltage(rollerGoal.getVoltage()); } } + + public void getArmAngle() {} } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 7d2e27b9..b37190db 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -251,6 +251,38 @@ public void setAutoStart() { edgeCommand.getCommand().cancel(); } } + + private V3_EpsilonSuperstructureStates getElevatorPosition() { + switch (RobotState.getOIData().currentReefHeight()) { + case STOW_DOWN, CORAL_INTAKE -> { + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + case L1 -> { + return V3_EpsilonSuperstructureStates.L1_PREP; + } + case L2 -> { + return V3_EpsilonSuperstructureStates.L2_PREP; + } + case L3 -> { + return V3_EpsilonSuperstructureStates.L3_PREP; + } + case L4 -> { + return V3_EpsilonSuperstructureStates.L4_PREP; + } + case ALGAE_INTAKE_BOTTOM -> { + return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; + } + case ALGAE_INTAKE_TOP -> { + return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; + } + case ALGAE_SCORE -> { + return V3_EpsilonSuperstructureStates.BARGE_PREP; + } + default -> { + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + } + } // --- Control Commands --- /** @@ -356,4 +388,8 @@ public Command runActionWithTimeout( public boolean elevatorAtGoal() { return elevator.atGoal(); } + + public Command setPosition() { + return runGoal(getElevatorPosition()).withTimeout(0.02); + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index d099d013..0cc131b8 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -193,8 +193,8 @@ public enum V3_EpsilonSuperstructureStates { V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), - INTERMIDIATE_WAIT_FOR_ELEVATOR( - "INTERMIDIATE_WAIT_FOR_ELEVATOR", + INTERMEDIATE_WAIT_FOR_ELEVATOR( + "INTERMEDIATE_WAIT_FOR_ELEVATOR", new SubsystemPoses( ReefState.STOW, V3_EpsilonManipulatorConstants.PivotState.STOW_UP, From f3837f260e233e6d0f4fdac2996a5d48c3dd1833 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sat, 30 Aug 2025 18:57:51 -0400 Subject: [PATCH 049/180] Co-authored-by: ThatGuyRuchir --- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 259 +++++++++--------- 1 file changed, 129 insertions(+), 130 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 4a0e7361..1687d244 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -52,6 +52,7 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerStates; +import frc.robot.subsystems.shared.vision.VisionConstants.RobotCameras; @@ -69,7 +70,7 @@ public class V3_EpsilonRobotContainer implements RobotContainer { private V3_EpsilonIntake intake; // private V3_EpsilonLEDs leds; private V3_EpsilonManipulator manipulator; - private V3_EpsilonSuperstructure superstructure;; + private V3_EpsilonSuperstructure superstructure; // Controller private final CommandXboxController driver = new CommandXboxController(0); @@ -113,22 +114,24 @@ public V3_EpsilonRobotContainer() { manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); // vision = new Vision(); break; - default: - break; + default: + break; } - - // if (climber == null) { - // climber = new Climber(new ClimberIO() {}); - // } - + if (drive == null) { drive = new Drive( - new GyroIO() {}, - new ModuleIO() {}, - new ModuleIO() {}, - new ModuleIO() {}, - new ModuleIO() {}); + new GyroIO() { + // Provide concrete implementation for GyroIO methods here + }, + new ModuleIO() { + }, + new ModuleIO() { + }, + new ModuleIO() { + }, + new ModuleIO() { + }); } if (elevator == null) { elevator = new Elevator(new ElevatorIO() {}).getFSM(); @@ -151,10 +154,10 @@ public V3_EpsilonRobotContainer() { superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); configureButtonBindings(); - configureAutos(); + } } - private void configureButtonBindings() { + public void configureButtonBindings() { // Generic triggers Trigger elevatorStow = new Trigger( @@ -171,8 +174,8 @@ private void configureButtonBindings() { // Trigger unHalfScoreTrigger = // new Trigger(() -> operator.getLeftY() > DriveConstants.OPERATOR_DEADBAND); - Trigger operatorFunnelOverride = - new Trigger(() -> Math.hypot(operator.getRightX(), operator.getRightY()) > 0.5); + // Trigger operatorFunnelOverride = + // new Trigger(() -> Math.hypot(operator.getRightX(), operator.getRightY()) > 0.5); // Default drive command drive.setDefaultCommand( @@ -213,11 +216,11 @@ private void configureButtonBindings() { .leftTrigger(0.5) .whileTrue(V3_EpsilonCompositeCommands.intakeCoralDriverSequence(superstructure, intake)) .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); - // driver - // .rightTrigger(0.5) - // .whileTrue( - // V3_EpsilonCompositeCommands.autoScoreCoralSequence( - // drive, elevator, superstructure, RobotCameras.V3_Epsilon_CAMS)); + driver + .rightTrigger(0.5) + .whileTrue( + V3_EpsilonCompositeCommands.autoScoreCoralSequence( + drive, elevator, superstructure, RobotCameras.V3_EPSILON_CAMS)); // Driver bumpers driver @@ -241,26 +244,26 @@ private void configureButtonBindings() { V3_EpsilonCompositeCommands.scoreCoralSequence( elevator, superstructure, () -> RobotState.getReefAlignData().atCoralSetpoint())); - // driver - // .back() - // .whileTrue( - // V3_EpsilonCompositeCommands.intakeAlgaeFromReefSequence( - // drive, - // superstructure, - // () -> RobotState.getReefAlignData().algaeIntakeHeight(), - // RobotCameras.V3_Epsilon_CAMS)); - - // driver - // .start() - // .whileTrue( - // V3_EpsilonCompositeCommands.dropAlgae( - // drive, - // elevator, - // manipulator, - // intake, - // superstructure, - // () -> RobotState.getReefAlignData().algaeIntakeHeight(), - // RobotCameras.V3_Epsilon_CAMS)); + driver + .back() + .whileTrue( + V3_EpsilonCompositeCommands.intakeAlgaeFromReefSequence( + drive, + superstructure, + () -> RobotState.getReefAlignData().algaeIntakeHeight(), + RobotCameras.V3_EPSILON_CAMS)); + + driver + .start() + .whileTrue( + V3_EpsilonCompositeCommands.dropAlgae( + drive, + elevator, + manipulator, + intake, + superstructure, + () -> RobotState.getReefAlignData().algaeIntakeHeight(), + RobotCameras.V3_EPSILON_CAMS)); // Remove the extra dot here // Operator face buttons operator.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); @@ -330,91 +333,91 @@ private void configureButtonBindings() { .finallyDo(() -> RobotState.setHasAlgae(false))); // Misc - operatorFunnelOverride - .whileTrue( - Commands.either( - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), - superstructure.runGoal( - V3_EpsilonSuperstructureStates.STOW_DOWN), - () -> RobotState.isHasAlgae())) - .onFalse(superstructure.runPreviousState()); - } + // operatorFunnelOverride + // .whileTrue( + // Commands.either( + // superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), + // superstructure.runGoal( + // V3_EpsilonSuperstructureStates.STOW_DOWN), + // () -> RobotState.isHasAlgae())) + // .onFalse(superstructure.runPreviousState()); +} private void configureAutos() { - // AutonomousCommands.loadAutoTrajectories(drive); - - // autoChooser.addCmd( - // "Drive FF Characterization", () -> DriveCommands.feedforwardCharacterization(drive)); - // autoChooser.addCmd( - // "Wheel Radius Characterization", () -> DriveCommands.wheelRadiusCharacterization(drive)); - // autoChooser.addCmd("Elevator Characterization", () -> elevator.sysIdRoutine(superstructure)); - // // autoChooser.addCmd("Funnel Characterization", () -> funnel.sysIdRoutine(superstructure)); - // autoChooser.addCmd("Intake Characterization", () -> intake.sysIdRoutine(superstructure)); -// autoChooser.addCmd( -// "Manipulator Characterization", -// () -> -// Commands.sequence( -// superstructure.runGoal(V3_EpsilonSuperstructureStates.L3), -// manipulator.sysIdRoutine(superstructure))); -// autoChooser.addRoutine( -// "4 Piece Left", -// () -> -// AutonomousCommands.autoALeft( -// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); -// autoChooser.addRoutine( -// "4 Piece Right", -// () -> -// AutonomousCommands.autoARight( -// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - -// autoChooser.addRoutine( -// "4 Piece Left Nashoba", -// () -> -// AutonomousCommands.autoALeftNashoba( -// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - -// autoChooser.addRoutine( -// "4 Piece Left D.A.V.E.", -// () -> -// AutonomousCommands.autoALeftDAVE( -// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - -// autoChooser.addRoutine( -// "3 Piece Left", -// () -> -// AutonomousCommands.autoCLeft( -// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); -// autoChooser.addRoutine( -// "3 Piece Left Push", -// () -> -// AutonomousCommands.autoCLeftPush( -// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); -// autoChooser.addRoutine( -// "3 Piece Right", -// () -> -// AutonomousCommands.autoCRight( -// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); -// autoChooser.addRoutine( -// "3 Piece Right Push", -// () -> -// AutonomousCommands.autoCRightPush( -// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); -// autoChooser.addRoutine( -// "2 Piece Left", -// () -> -// AutonomousCommands.autoBLeft( -// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); -// autoChooser.addRoutine( -// "2 Piece Right", -// () -> -// AutonomousCommands.autoBRight( -// drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); -// autoChooser.addRoutine( -// "1 Piece Center", -// () -> -// AutonomousCommands.autoDCenter(drive, superstructure, RobotCameras.V3_Epsilon_CAMS)); -// SmartDashboard.putData("Autonomous Modes", autoChooser); -// } + AutonomousCommands.loadAutoTrajectories(drive); + + autoChooser.addCmd( + "Drive FF Characterization", () -> DriveCommands.feedforwardCharacterization(drive)); + autoChooser.addCmd( + "Wheel Radius Characterization", () -> DriveCommands.wheelRadiusCharacterization(drive)); + autoChooser.addCmd("Elevator Characterization", () -> elevator.sysIdRoutine(superstructure)); + // autoChooser.addCmd("Funnel Characterization", () -> funnel.sysIdRoutine(superstructure)); + autoChooser.addCmd("Intake Characterization", () -> intake.sysIdRoutine(superstructure)); + autoChooser.addCmd( + "Manipulator Characterization", + () -> + Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.L3_PREP), + manipulator.sysIdRoutine(superstructure))); + autoChooser.addRoutine( + "4 Piece Left", + () -> + AutonomousCommands.autoALeft( + drive, intake, superstructure, RobotCameras.V3_EPSILON_CAMS)); + autoChooser.addRoutine( + "4 Piece Right", + () -> + AutonomousCommands.autoARight( + drive, intake, superstructure, RobotCameras.V3_EPSILON_CAMS)); + + autoChooser.addRoutine( + "4 Piece Left Nashoba", + () -> + AutonomousCommands.autoALeftNashoba( + drive, intake, superstructure, RobotCameras.V3_EPSILON_CAMS)); + + autoChooser.addRoutine( + "4 Piece Left D.A.V.E.", + () -> + AutonomousCommands.autoALeftDAVE( + drive, intake, superstructure, RobotCameras.V3_EPSILON_CAMS)); + + autoChooser.addRoutine( + "3 Piece Left", + () -> + AutonomousCommands.autoCLeft( + drive, intake, superstructure, RobotCameras.V3_EPSILON_CAMS)); + autoChooser.addRoutine( + "3 Piece Left Push", + () -> + AutonomousCommands.autoCLeftPush( + drive, intake, superstructure, RobotCameras.V3_EPSILON_CAMS)); + autoChooser.addRoutine( + "3 Piece Right", + () -> + AutonomousCommands.autoCRight( + drive, intake, superstructure, RobotCameras.V3_EPSILON_CAMS)); + autoChooser.addRoutine( + "3 Piece Right Push", + () -> + AutonomousCommands.autoCRightPush( + drive, intake, superstructure, RobotCameras.V3_EPSILON_CAMS)); + autoChooser.addRoutine( + "2 Piece Left", + () -> + AutonomousCommands.autoBLeft( + drive, intake, superstructure, RobotCameras.V3_EPSILON_CAMS)); + autoChooser.addRoutine( + "2 Piece Right", + () -> + AutonomousCommands.autoBRight( + drive, intake, superstructure, RobotCameras.V3_EPSILON_CAMS)); + autoChooser.addRoutine( + "1 Piece Center", + () -> + AutonomousCommands.autoDCenter(drive, superstructure, RobotCameras.V3_EPSILON_CAMS)); + SmartDashboard.putData("Autonomous Modes", autoChooser); + } // @Override // public void robotPeriodic() { @@ -440,15 +443,11 @@ private void configureAutos() { // funnel.getAngle(), // manipulator.getArmAngle(), // intake.getExtension())); -// } + } @Override public Command getAutonomousCommand() { return autoChooser.selectedCommand(); } - - } -} - } From a4a88dd9df9992eef2df0b3af9a88700aad1966e Mon Sep 17 00:00:00 2001 From: LordVanra Date: Sat, 30 Aug 2025 19:37:25 -0400 Subject: [PATCH 050/180] Fixed all errors in V3_EpsilonRobotContainer Added Autonomous Commands for V3 Co-authored-by: ThatGuyRuchir --- src/main/java/frc/robot/Constants.java | 3 - .../robot/commands/AutonomousCommands.java | 705 ++++++++++++++++++ .../subsystems/shared/elevator/Elevator.java | 9 + .../v3_Epsilon/V3_EpsilonRobotContainer.java | 12 +- .../v3_Epsilon/intake/V3_EpsilonIntake.java | 4 +- .../manipulator/V3_EpsilonManipulator.java | 3 +- 6 files changed, 724 insertions(+), 12 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index a214e721..7a11b629 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -47,11 +47,8 @@ public static enum RobotType { V1_STACKUP_SIM, V2_REDUNDANCY, V2_REDUNDANCY_SIM, -<<<<<<< HEAD -======= V3_EPSILON_SIM, V3_EPSILON, ->>>>>>> 4b7ea16 (Co-authored-by: Noah Proctor ) } public static void main(String... args) { diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index 53b17b96..0c267ced 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -11,14 +11,18 @@ import frc.robot.RobotState; import frc.robot.commands.CompositeCommands.V1_StackUpCompositeCommands; import frc.robot.commands.CompositeCommands.V2_RedundancyCompositeCommands; +import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorCSB; import frc.robot.subsystems.shared.funnel.Funnel.FunnelCSB; import frc.robot.subsystems.shared.vision.Camera; import frc.robot.subsystems.v1_StackUp.manipulator.V1_StackUpManipulator; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; import frc.robot.util.AllianceFlipUtil; import frc.robot.util.LoggedChoreo.LoggedAutoRoutine; import frc.robot.util.LoggedChoreo.LoggedAutoTrajectory; @@ -398,6 +402,15 @@ public static final Command autoDCenter( V1_StackUpCompositeCommands.twerk(drive, elevator, manipulator, cameras)); } + // V2 + // V2 + // V2 + // V2 + // V2 + // V2 + // V2 + // V2 + // V2 // V2 public static final LoggedAutoRoutine autoALeft( @@ -1077,4 +1090,696 @@ public static final LoggedAutoRoutine autoDCenter( V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); return routine; } + + // V3 + // V3 + // V3 + // V3 + // V3 + // V3 + // V3 + // V3 + // V3 + // V3 + // V3 + + //TODO: Make sure superstructure states are correct + + public static final LoggedAutoRoutine autoALeft( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeft"); + + LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_LEFT_PATH4") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path2.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path3.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path4.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoALeftNashoba( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftNashoba"); + + LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_LEFT_PATH_ALT3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_LEFT_PATH_ALT4") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path2.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path3.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path4.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoALeftDAVE( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftD.A.V.E."); + + LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_LEFT_PATH4_ALT_ALT") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path2.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path3.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path4.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoARight( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoARight"); + + LoggedAutoTrajectory path1 = routine.trajectory("A_RIGHT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_RIGHT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_RIGHT_PATH4") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.25), + Commands.deadline( + path2.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.25), + Commands.deadline( + path3.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.25), + Commands.deadline( + path4.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoBLeft( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBLeft"); + LoggedAutoTrajectory path1 = + routine + .trajectory("B_LEFT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("B_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path2.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); + + return routine; + } + + public static final LoggedAutoRoutine autoCLeft( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_LEFT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path2.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path3.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoCLeftPush( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_LEFT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), + () -> drive.stop()) + .withTimeout(0.5), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path2.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path3.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoCRight( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_RIGHT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_RIGHT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path2.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path3.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); + return routine; + } + + public static final LoggedAutoRoutine autoCRightPush( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_RIGHT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_RIGHT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, 1.0, 0.0)), + () -> drive.stop()) + .withTimeout(0.5), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path2.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path3.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); + return routine; + } + + public static final LoggedAutoRoutine autoBRight( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBRight"); + LoggedAutoTrajectory path1 = + routine + .trajectory("B_RIGHT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("B_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path2.cmd(), + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); + + return routine; + } + + public static final LoggedAutoRoutine autoDCenter( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoDCenter"); + LoggedAutoTrajectory path1 = + routine + .trajectory("D_CENTER_PATH") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); + return routine; + } } diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java index baf774fb..113a5116 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java @@ -17,6 +17,8 @@ import frc.robot.subsystems.shared.elevator.ElevatorIO.ElevatorIOInputs; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructure; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.util.ExternalLoggedTracer; import frc.robot.util.InternalLoggedTracer; import java.util.function.BooleanSupplier; @@ -323,6 +325,13 @@ public Command sysIdRoutine(V2_RedundancySuperstructure superstructure) { Elevator.this.sysIdRoutine(superstructure)); } + public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { + + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), + Elevator.this.sysIdRoutine(superstructure)); + } + public double getPositionMeters() { return Elevator.this.getPositionMeters(inputs); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 1687d244..8df1048c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -1,6 +1,6 @@ package frc.robot.subsystems.v3_Epsilon; -import edu.wpi.first.networktables.NetworkTablesJNI; +// import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; @@ -17,8 +17,8 @@ import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; import frc.robot.commands.DriveCommands; import frc.robot.subsystems.shared.climber.Climber; -import frc.robot.subsystems.shared.climber.ClimberIO; -import frc.robot.subsystems.shared.climber.ClimberIOSim; +// import frc.robot.subsystems.shared.climber.ClimberIO; +// import frc.robot.subsystems.shared.climber.ClimberIOSim; import frc.robot.subsystems.shared.climber.ClimberIOTalonFX; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.drive.DriveConstants; @@ -36,8 +36,8 @@ import frc.robot.subsystems.shared.funnel.Funnel; import frc.robot.subsystems.shared.funnel.Funnel.FunnelFSM; import frc.robot.subsystems.shared.funnel.FunnelIO; -import frc.robot.subsystems.shared.funnel.FunnelIOSim; -import frc.robot.subsystems.shared.funnel.FunnelIOTalonFX; +// import frc.robot.subsystems.shared.funnel.FunnelIOSim; +// import frc.robot.subsystems.shared.funnel.FunnelIOTalonFX; // import frc.robot.subsystems.shared.vision.CameraConstants.RobotCameras; import frc.robot.subsystems.shared.vision.Vision; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; @@ -48,7 +48,6 @@ import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIO; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIOSim; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants.IntakeRollerStates; -// import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure.java; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerStates; @@ -443,7 +442,6 @@ private void configureAutos() { // funnel.getAngle(), // manipulator.getArmAngle(), // intake.getExtension())); - } @Override diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java index 4696f390..1b20a254 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java @@ -10,6 +10,8 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants.IntakeState; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; + import java.util.Set; import lombok.Getter; import org.littletonrobotics.junction.AutoLogOutput; @@ -85,7 +87,7 @@ public Command waitUntilPivotAtGoal() { return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::atGoal)); } - public Command sysIdRoutine() { + public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { return Commands.sequence( Commands.runOnce(() -> isClosedLoop = false), Commands.runOnce(() -> characterizationRoutine.quasistatic(Direction.kForward)), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java index 66ba61d2..cc82cf2a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java @@ -10,6 +10,7 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants.PivotState; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import java.util.Set; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; @@ -75,7 +76,7 @@ public Command runPivot(double volts) { () -> io.setPivotVoltage(0)); } - public Command sysIdRoutine() { + public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { return Commands.sequence( Commands.runOnce(() -> isClosedLoop = false), algaeCharacterizationRoutine.quasistatic(Direction.kForward), From b7d82a831b41c89c995d3ebe22986e0b20b9c624 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Sat, 30 Aug 2025 19:53:37 -0400 Subject: [PATCH 051/180] initial --- src/main/java/frc/robot/Constants.java | 5 +- src/main/java/frc/robot/FieldConstants.java | 2 + src/main/java/frc/robot/Robot.java | 2 + src/main/java/frc/robot/RobotState.java | 3 + .../frc/robot/commands/CompositeCommands.java | 314 +--------- .../shared/elevator/ElevatorConstants.java | 4 + .../v3_Epsilon/V3_EpsilonRobotContainer.java | 390 ++---------- .../v3_Epsilon/V3_RobotContainer.java | 432 -------------- .../v3_Epsilon/intake/V3_EpsilonIntake.java | 126 ---- .../V3_EpsilonSuperstructure.java | 559 ++++++++++++++++++ .../V3_EpsilonSuperstructureAction.java | 74 +++ .../V3_EpsilonSuperstructureEdges.java | 363 ++++++++++++ .../V3_EpsilonSuperstructurePose.java | 116 ++++ .../V3_EpsilonSuperstructureStates.java | 210 +++++++ .../superstructure/V3_Superstructure.java | 359 ----------- .../V3_SuperstructureActions.java | 72 --- .../V3_SuperstructureEdges.java | 246 -------- .../V3_SuperstructurePoses.java | 110 ---- .../V3_SuperstructureStates.java | 288 --------- .../intake/V3_EpsilonIntake.java | 104 ++++ .../intake/V3_EpsilonIntakeConstants.java | 8 +- .../intake/V3_EpsilonIntakeIO.java | 8 +- .../intake/V3_EpsilonIntakeIOSim.java | 4 +- .../intake/V3_EpsilonIntakeIOTalonFX.java | 4 +- .../manipulator/V3_EpsilonManipulator.java | 96 +-- .../V3_EpsilonManipulatorConstants.java | 15 +- .../manipulator/V3_EpsilonManipulatorIO.java | 9 +- .../V3_EpsilonManipulatorIOSim.java | 6 +- .../V3_EpsilonManipulatorIOTalonFX.java | 113 ++-- 29 files changed, 1610 insertions(+), 2432 deletions(-) delete mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/V3_RobotContainer.java delete mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureAction.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java delete mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java delete mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java delete mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java delete mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java delete mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/intake/V3_EpsilonIntakeConstants.java (93%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/intake/V3_EpsilonIntakeIO.java (89%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/intake/V3_EpsilonIntakeIOSim.java (97%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/intake/V3_EpsilonIntakeIOTalonFX.java (98%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/manipulator/V3_EpsilonManipulator.java (65%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/manipulator/V3_EpsilonManipulatorConstants.java (93%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/manipulator/V3_EpsilonManipulatorIO.java (88%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/manipulator/V3_EpsilonManipulatorIOSim.java (97%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/manipulator/V3_EpsilonManipulatorIOTalonFX.java (56%) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index a214e721..77e7e874 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -5,7 +5,7 @@ public final class Constants { public static final boolean TUNING_MODE = false; public static final double LOOP_PERIOD_SECONDS = 0.02; - public static final RobotType ROBOT = RobotType.V2_REDUNDANCY; + public static final RobotType ROBOT = RobotType.V3_EPSILON_SIM; public static Mode getMode() { switch (ROBOT) { @@ -47,11 +47,8 @@ public static enum RobotType { V1_STACKUP_SIM, V2_REDUNDANCY, V2_REDUNDANCY_SIM, -<<<<<<< HEAD -======= V3_EPSILON_SIM, V3_EPSILON, ->>>>>>> 4b7ea16 (Co-authored-by: Noah Proctor ) } public static void main(String... args) { diff --git a/src/main/java/frc/robot/FieldConstants.java b/src/main/java/frc/robot/FieldConstants.java index c85ad048..f9297346 100644 --- a/src/main/java/frc/robot/FieldConstants.java +++ b/src/main/java/frc/robot/FieldConstants.java @@ -57,9 +57,11 @@ public static enum ReefPose { public static enum ReefState { STOW, + HIGH_STOW, CORAL_INTAKE, ALGAE_FLOOR_INTAKE, ALGAE_MID, + HANDOFF, ASS_TOP, ASS_BOT, ALGAE_INTAKE_TOP, diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index aa8761af..222c6408 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -20,6 +20,7 @@ import frc.robot.subsystems.v0_Whiplash.V0_WhiplashRobotContainer; import frc.robot.subsystems.v1_StackUp.V1_StackUpRobotContainer; import frc.robot.subsystems.v2_Redundancy.V2_RedundancyRobotContainer; +import frc.robot.subsystems.v3_Epsilon.V3_EpsilonRobotContainer; import frc.robot.util.Alert; import frc.robot.util.Alert.AlertType; import frc.robot.util.CanivoreReader; @@ -155,6 +156,7 @@ public void robotInit() { V0_GOMPEIVISION_TEST_SIM -> new v0_GompeivisionTestRobotContainer(); case V1_STACKUP, V1_STACKUP_SIM -> new V1_StackUpRobotContainer(); case V2_REDUNDANCY, V2_REDUNDANCY_SIM -> new V2_RedundancyRobotContainer(); + case V3_EPSILON, V3_EPSILON_SIM -> new V3_EpsilonRobotContainer(); default -> new RobotContainer() {}; }; diff --git a/src/main/java/frc/robot/RobotState.java b/src/main/java/frc/robot/RobotState.java index ad7ca746..2cc9567f 100644 --- a/src/main/java/frc/robot/RobotState.java +++ b/src/main/java/frc/robot/RobotState.java @@ -67,6 +67,9 @@ public class RobotState { case V2_REDUNDANCY: case V2_REDUNDANCY_SIM: break; + case V3_EPSILON: + case V3_EPSILON_SIM: + break; } OIData = new OperatorInputData(ReefPose.LEFT, ReefState.STOW); diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 26776ae2..1faf5f98 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -22,10 +22,6 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_Superstructure; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureStates; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; import frc.robot.util.AllianceFlipUtil; import java.util.function.BooleanSupplier; import java.util.function.Supplier; @@ -653,313 +649,5 @@ public static final Command homingSequences( Commands.runOnce(() -> elevator.setPosition())); } - public static final class V3_EpsilonCompositeCommands { - - /** - * Creates a command to intake coral from the station. - * - * @param superstructure The superstructure subsystem. - * @param intake The intake subsystem. - * @return A command to intake coral. - */ - public static final Command intakeCoralDriverSequence( - V3_EpsilonSuperstructure superstructure, V3_EpsilonIntake intake) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); - } - - /** - * Creates a command to intake coral from the station using the operator sequence. - * - * @param superstructure The superstructure subsystem. - * @param intake The intake subsystem. - * @return A command to intake coral using the operator sequence. - */ - public static final Command intakeCoralOperatorSequence( - V3_EpsilonSuperstructure superstructure, V3_EpsilonIntake intake) { - return Commands.sequence( - superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); - } - - /** - * Creates a command to score coral at L1. - * - * @param drive The drive subsystem. - * @param superstructure The superstructure subsystem. - * @return A command to score coral at L1. - */ - public static final Command scoreL1Coral( - Drive drive, V3_EpsilonSuperstructure superstructure) { - return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.L1), - Commands.parallel( - superstructure.runReefScoreGoal(() -> ReefState.L1), - Commands.sequence( - Commands.waitSeconds(0.05), - Commands.either( - DriveCommands.inchMovement(drive, -1, 0.1), - DriveCommands.inchMovement(drive, 1, 0.1), - () -> RobotState.getOIData().currentReefPost() == ReefPose.LEFT)))); - } - - /** - * Creates a command sequence to score coral at L1, waiting for auto-alignment. - * - * @param drive The drive subsystem. - * @param superstructure The superstructure subsystem. - * @return A command sequence to score coral at L1. - */ - public static final Command autoScoreL1CoralSequence( - Drive drive, - ElevatorFSM elevator, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefCoral(drive, cameras), scoreL1Coral(drive, superstructure)); - } - - /** - * Creates a command sequence to score coral, waiting for auto-alignment. - * - * @param elevator The elevator subsystem. - * @param superstructure The superstructure subsystem. - * @param autoAligned A supplier that returns true when the robot is aligned. - * @return A command sequence to score coral. - */ - public static final Command scoreCoralSequence( - ElevatorFSM elevator, - V3_EpsilonSuperstructure superstructure, - BooleanSupplier autoAligned) { - return Commands.sequence( - Commands.either( - superstructure.runGoal(V3_EpsilonSuperstructureStates.L3), - superstructure.runReefGoal(() -> RobotState.getOIData().currentReefHeight()), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L4) - && !superstructure - .getCurrentState() - .equals(V3_EpsilonSuperstructureStates.L4)), - Commands.waitUntil(() -> autoAligned.getAsBoolean()), - superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight()), - superstructure - .runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN) - .onlyIf( - () -> - elevator.getPosition().equals(ElevatorPositions.L3) - || elevator.getPosition().equals(ElevatorPositions.L2))); - } - - /** - * Creates a command sequence to automatically score coral. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param superstructure The superstructure subsystem. - * @param cameras The vision cameras. - * @return A command sequence to auto-score coral. - */ - public static final Command autoScoreCoralSequence( - Drive drive, - ElevatorFSM elevator, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - return Commands.either( - Commands.sequence( - autoScoreL1CoralSequence(drive, elevator, superstructure, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)), - Commands.sequence( - Commands.either( - superstructure.runGoal(V3_EpsilonSuperstructureStates.L2), - Commands.none(), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L1) - || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) - || RobotState.getOIData() - .currentReefHeight() - .equals(ReefState.CORAL_INTAKE)), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - scoreCoralSequence( - elevator, - superstructure, - () -> RobotState.getReefAlignData().atCoralSetpoint())), - superstructure - .l4PlusSequence() - .onlyIf(() -> RobotState.getOIData().currentReefHeight() == ReefState.L4)), - () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); - } - - /** - * Creates a command to intake algae from the reef. This uses the closest reef tag to - * automatically pick the reef height and reef face. - * - * @param drive The drive subsystem. - * @param superstructure The superstructure subsystem. - * @param cameras The vision cameras. - * @return A command to remove algae. - */ - public static final Command intakeAlgaeFromReefSequence( - Drive drive, - V3_EpsilonSuperstructure superstructure, - Supplier level, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefAlgae(drive, cameras), - superstructure.runGoalUntil( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.INTAKE_REEF_L3; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.INTAKE_REEF_L2; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }, - () -> RobotState.isHasAlgae()), - Commands.parallel( - Commands.sequence( - Commands.waitSeconds(0.25), - Commands.either( - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), - superstructure.runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.REEF_ACQUISITION_L3; - default: - return V3_EpsilonSuperstructureStates.REEF_ACQUISITION_L2; - } - }), - () -> RobotState.isHasAlgae())), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) - .withTimeout(0.5))); - } - - /** - * Creates a command to drop algae from the reef. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. - * @param superstructure The superstructure subsystem. - * @param level A supplier that provides the current reef level. - * @param cameras The vision cameras. - * @return A command to drop algae from the reef. - */ - public static final Command dropAlgae( - Drive drive, - ElevatorFSM elevator, - V3_EpsilonManipulator manipulator, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Supplier level, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefAlgae(drive, cameras), - Commands.sequence( - superstructure - .runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.INTAKE_REEF_L3; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.INTAKE_REEF_L2; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }) - .until(() -> RobotState.isHasAlgae()), - Commands.waitSeconds(2.0), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) - .withTimeout(0.5)), - superstructure.runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.DROP_REEF_L3; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.DROP_REEF_L2; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }), - Commands.waitSeconds(1.0), - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); - } - - /** - * Creates a command sequence for the floor intake of algae. - * - * @param superstructure The superstructure subsystem. - * @return A command sequence for the floor intake. - */ - public static final Command floorIntakeSequence(V3_EpsilonSuperstructure superstructure) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.INTAKE_FLOOR, () -> RobotState.isHasAlgae())); - } - - /** - * Creates a command that posts the floor intake sequence, which can either go up or down based - * on whether the robot has algae. - * - * @param superstructure The superstructure subsystem. - * @return A command that posts the floor intake sequence. - */ - public static final Command postFloorIntakeSequence( - V3_EpsilonSuperstructure superstructure) { - return Commands.either( - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), - RobotState::isHasAlgae); - } - - /** - * Creates a command to set the dynamic reef height in the robot state. This sets the height and - * then moves the superstructure to that position. - * - * @param height The reef height to set. - * @param superstructure The superstructure subsystem. - * @return A command to set the dynamic reef height. - */ - public static final Command setDynamicReefHeight( - ReefState height, V3_EpsilonSuperstructure superstructure) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setReefHeight(height)), superstructure.setPosition()); - } - - /** - * Creates a command to climb the robot. - * - * @param superstructure The superstructure subsystem. - * @param climber The climber subsystem. - * @param drive The drive subsystem. - * @return A command to climb. - */ - public static final Command climb( - V3_EpsilonSuperstructure superstructure, Climber climber, Drive drive) { - return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.CLIMB), - Commands.parallel( - climber.releaseClimber(), - Commands.waitSeconds( - ClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), - Commands.waitUntil(climber::climberReady), - Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); - } - - } + public static final class V3_EpsilonCompositeCommands {} } diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index d968385b..75c0ab18 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -28,9 +28,11 @@ public class ElevatorConstants { REEF_STATE_ELEVATOR_POSITION_MAP = Map.ofEntries( Map.entry(ReefState.STOW, ElevatorPositions.STOW), + Map.entry(ReefState.HIGH_STOW, ElevatorPositions.HIGH_STOW), Map.entry(ReefState.CORAL_INTAKE, ElevatorPositions.CORAL_INTAKE), Map.entry(ReefState.ALGAE_FLOOR_INTAKE, ElevatorPositions.ALGAE_INTAKE), Map.entry(ReefState.ALGAE_MID, ElevatorPositions.ALGAE_MID), + Map.entry(ReefState.HANDOFF, ElevatorPositions.HANDOFF), Map.entry(ReefState.ALGAE_INTAKE_TOP, ElevatorPositions.ALGAE_INTAKE_TOP), Map.entry(ReefState.ALGAE_INTAKE_BOTTOM, ElevatorPositions.ALGAE_INTAKE_BOT), Map.entry(ReefState.L1, ElevatorPositions.L1), @@ -216,9 +218,11 @@ public static record ElevatorParameters( @RequiredArgsConstructor public static enum ElevatorPositions { STOW(0.0), + HIGH_STOW(0.5), CORAL_INTAKE(0.0), ALGAE_INTAKE(0.2161583093038944 + Units.inchesToMeters(1)), ALGAE_MID(0.7073684509805078), + HANDOFF(0.7073684509805078), ALGAE_INTAKE_TOP(1.17 - Units.inchesToMeters(8)), ALGAE_INTAKE_BOT(0.79 - Units.inchesToMeters(8)), ASS_TOP(1.2), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 644eab5c..5793cbd8 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -1,25 +1,11 @@ package frc.robot.subsystems.v3_Epsilon; import edu.wpi.first.networktables.NetworkTablesJNI; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; -import edu.wpi.first.wpilibj2.command.button.CommandXboxController; -import edu.wpi.first.wpilibj2.command.button.Trigger; import frc.robot.Constants; import frc.robot.Constants.Mode; -import frc.robot.FieldConstants.Reef.ReefPose; -import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotContainer; import frc.robot.RobotState; -import frc.robot.commands.AutonomousCommands; -import frc.robot.commands.CompositeCommands.SharedCommands; -import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; -import frc.robot.commands.DriveCommands; -import frc.robot.subsystems.shared.climber.Climber; -import frc.robot.subsystems.shared.climber.ClimberIO; -import frc.robot.subsystems.shared.climber.ClimberIOSim; -import frc.robot.subsystems.shared.climber.ClimberIOTalonFX; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.drive.DriveConstants; import frc.robot.subsystems.shared.drive.GyroIO; @@ -29,54 +15,39 @@ import frc.robot.subsystems.shared.drive.ModuleIOTalonFX; import frc.robot.subsystems.shared.elevator.Elevator; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; -import frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions; import frc.robot.subsystems.shared.elevator.ElevatorIO; import frc.robot.subsystems.shared.elevator.ElevatorIOSim; import frc.robot.subsystems.shared.elevator.ElevatorIOTalonFX; -import frc.robot.subsystems.shared.funnel.Funnel; -import frc.robot.subsystems.shared.funnel.Funnel.FunnelFSM; -import frc.robot.subsystems.shared.funnel.FunnelIO; -import frc.robot.subsystems.shared.funnel.FunnelIOSim; -import frc.robot.subsystems.shared.funnel.FunnelIOTalonFX; -// import frc.robot.subsystems.shared.vision.CameraConstants.RobotCameras; -import frc.robot.subsystems.shared.vision.Vision; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIOTalonFX; -// import frc.robot.subsystems.v3_Epsilon.superstructure.V3_Superstructure.java; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_Superstructure; - - - +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIO; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOSim; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOTalonFX; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIO; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOSim; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOTalonFX; import frc.robot.util.LTNUpdater; -import frc.robot.util.LoggedChoreo.ChoreoChooser; import org.littletonrobotics.junction.Logger; public class V3_EpsilonRobotContainer implements RobotContainer { // Subsystems - private Climber climber; private Drive drive; private ElevatorFSM elevator; - private FunnelFSM funnel; - private Vision vision; private V3_EpsilonIntake intake; -// private V3_EpsilonLEDs leds; private V3_EpsilonManipulator manipulator; - private V3_Superstructure superstructure; + private V3_EpsilonSuperstructure superstructure; // Controller - private final CommandXboxController driver = new CommandXboxController(0); - private final CommandXboxController operator = new CommandXboxController(1); // Auto chooser - private final ChoreoChooser autoChooser = new ChoreoChooser(); public V3_EpsilonRobotContainer() { if (Constants.getMode() != Mode.REPLAY) { switch (Constants.ROBOT) { case V3_EPSILON: - climber = new Climber(new ClimberIOTalonFX()); drive = new Drive( new GyroIOPigeon2(), @@ -86,13 +57,10 @@ public V3_EpsilonRobotContainer() { new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); - // leds = new V3_EpsilonLEDs(); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); - superstructure = new V3_Superstructure(elevator, funnel, intake, manipulator); - // vision = new Vision(RobotCameras.V3_Epsilon_CAMS); + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); break; case V3_EPSILON_SIM: - // climber = new Climber(new ClimberIOSim()); drive = new Drive( new GyroIO() {}, @@ -101,311 +69,41 @@ public V3_EpsilonRobotContainer() { new ModuleIOSim(DriveConstants.BACK_LEFT), new ModuleIOSim(DriveConstants.BACK_RIGHT)); elevator = new Elevator(new ElevatorIOSim()).getFSM(); - funnel = new Funnel(new FunnelIOSim()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); - vision = new Vision(); + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); break; default: break; } - } - if (climber == null) { - climber = new Climber(new ClimberIO() {}); - } - if (drive == null) { - drive = - new Drive( - new GyroIO() {}, - new ModuleIO() {}, - new ModuleIO() {}, - new ModuleIO() {}, - new ModuleIO() {}); - } - if (elevator == null) { - elevator = new Elevator(new ElevatorIO() {}).getFSM(); - } - if (funnel == null) { - funnel = new Funnel(new FunnelIO() {}).getFSM(); - } - if (intake == null) { - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); - } - if (leds == null) { - leds = new V3_EpsilonLEDs(); - } - if (manipulator == null) { - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); - } - if (vision == null) { - vision = new Vision(); + if (drive == null) { + drive = + new Drive( + new GyroIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}); + } + if (elevator == null) { + elevator = new Elevator(new ElevatorIO() {}).getFSM(); + } + if (intake == null) { + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); + } + if (manipulator == null) { + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); + } + if (superstructure == null) { + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + } } - superstructure = new V3_EpsilonSuperstructure(elevator, funnel, intake, manipulator); - - configureButtonBindings(); - configureAutos(); } - private void configureButtonBindings() { - // Generic triggers - Trigger elevatorStow = - new Trigger( - () -> - elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) - || elevator.getPosition().equals(ElevatorPositions.STOW)); - Trigger elevatorNotStow = - new Trigger( - () -> - !elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) - && !elevator.getPosition().equals(ElevatorPositions.STOW)); - // Trigger halfScoreTrigger = - // new Trigger(() -> operator.getLeftY() < -DriveConstants.OPERATOR_DEADBAND); - // Trigger unHalfScoreTrigger = - // new Trigger(() -> operator.getLeftY() > DriveConstants.OPERATOR_DEADBAND); - - Trigger operatorFunnelOverride = - new Trigger(() -> Math.hypot(operator.getRightX(), operator.getRightY()) > 0.5); - - // Default drive command - drive.setDefaultCommand( - DriveCommands.joystickDrive( - drive, - () -> -driver.getLeftY(), - () -> -driver.getLeftX(), - () -> -driver.getRightX(), - () -> false, - operator.back(), - driver.povRight())); - - // Driver face buttons - driver.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); - driver.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); - driver.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); - driver.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); - - driver - .y() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); - driver - .x() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); - driver - .b() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); - driver - .a() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); + private void configureButtonBindings() {} - // Driver triggers - driver - .leftTrigger(0.5) - .whileTrue(V3_EpsilonCompositeCommands.intakeCoralDriverSequence(superstructure, intake)) - .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); - driver - .rightTrigger(0.5) - .whileTrue( - V3_EpsilonCompositeCommands.autoScoreCoralSequence( - drive, elevator, superstructure, RobotCameras.V3_Epsilon_CAMS)); - - // Driver bumpers - driver - .leftBumper() - .whileTrue(V3_EpsilonCompositeCommands.floorIntakeSequence(superstructure)) - .onFalse( - Commands.deadline( - V3_EpsilonCompositeCommands.postFloorIntakeSequence(superstructure), - Commands.runOnce(() -> intake.setRollerGoal(IntakeRollerState.OUTTAKE))) - .andThen(Commands.runOnce(() -> intake.setRollerGoal(IntakeRollerState.STOP)))); - driver.rightBumper().onTrue(Commands.runOnce(() -> RobotState.toggleReefPost())); - - // Driver POV - driver.povUp().onTrue(superstructure.setPosition()); - driver.povDown().onTrue(SharedCommands.resetHeading(drive)); - driver.povLeft().onTrue(DriveCommands.inchMovement(drive, -0.5, .07)); - - driver - .leftStick() - .onTrue( - V3_EpsilonCompositeCommands.scoreCoralSequence( - elevator, superstructure, () -> RobotState.getReefAlignData().atCoralSetpoint())); - - driver - .back() - .whileTrue( - V3_EpsilonCompositeCommands.intakeAlgaeFromReefSequence( - drive, - superstructure, - () -> RobotState.getReefAlignData().algaeIntakeHeight(), - RobotCameras.V3_Epsilon_CAMS)); - - driver - .start() - .whileTrue( - V3_EpsilonCompositeCommands.dropAlgae( - drive, - elevator, - manipulator, - intake, - superstructure, - () -> RobotState.getReefAlignData().algaeIntakeHeight(), - RobotCameras.V3_Epsilon_CAMS)); - - // Operator face buttons - operator.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); - operator.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); - operator.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); - operator.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); - - operator - .y() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); - operator - .x() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); - operator - .b() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); - operator - .a() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); - - // Operator triggers - operator - .leftTrigger(0.5) - .whileTrue( - V3_EpsilonCompositeCommands.intakeCoralOperatorSequence(superstructure, intake)) - .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); - operator - .rightTrigger(0.5) - .whileTrue( - superstructure.override( - () -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_CORAL), 0.4)); - - // Operator bumpers - operator.leftBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))); - operator.rightBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))); - - operator.povUp().onTrue(V3_EpsilonCompositeCommands.climb(superstructure, climber, drive)); - operator.povDown().whileTrue(climber.winchClimberManual()); - operator - .povLeft() - .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR)) - .onFalse( - superstructure - .runActionWithTimeout(V3_EpsilonSuperstructureStates.SCORE_PROCESSOR, 1) - .finallyDo(() -> RobotState.setHasAlgae(false))); - - operator - .povRight() - .whileTrue( - superstructure - .override(() -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_ALGAE)) - .finallyDo(() -> RobotState.setHasAlgae(false))); - operator.start().whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)); - - operator - .back() - .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)) - .onFalse( - superstructure - .runActionWithTimeout(V3_EpsilonSuperstructureStates.SCORE_BARGE, 0.1) - .finallyDo(() -> RobotState.setHasAlgae(false))); - - // Misc - operatorFunnelOverride - .whileTrue( - Commands.either( - superstructure.runGoal(V3_EpsilonSuperstructureStates.FUNNEL_CLOSE_WITH_STOW_UP), - superstructure.runGoal( - V3_EpsilonSuperstructureStates.FUNNEL_CLOSE_WITH_STOW_DOWN), - () -> RobotState.isHasAlgae())) - .onFalse(superstructure.runPreviousState()); - } - - private void configureAutos() { - AutonomousCommands.loadAutoTrajectories(drive); - - autoChooser.addCmd( - "Drive FF Characterization", () -> DriveCommands.feedforwardCharacterization(drive)); - autoChooser.addCmd( - "Wheel Radius Characterization", () -> DriveCommands.wheelRadiusCharacterization(drive)); - autoChooser.addCmd("Elevator Characterization", () -> elevator.sysIdRoutine(superstructure)); - autoChooser.addCmd("Funnel Characterization", () -> funnel.sysIdRoutine(superstructure)); - autoChooser.addCmd("Intake Characterization", () -> intake.sysIdRoutine(superstructure)); - autoChooser.addCmd( - "Manipulator Characterization", - () -> - Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.L3), - manipulator.sysIdRoutine(superstructure))); - autoChooser.addRoutine( - "4 Piece Left", - () -> - AutonomousCommands.autoALeft( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "4 Piece Right", - () -> - AutonomousCommands.autoARight( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - - autoChooser.addRoutine( - "4 Piece Left Nashoba", - () -> - AutonomousCommands.autoALeftNashoba( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - - autoChooser.addRoutine( - "4 Piece Left D.A.V.E.", - () -> - AutonomousCommands.autoALeftDAVE( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - - autoChooser.addRoutine( - "3 Piece Left", - () -> - AutonomousCommands.autoCLeft( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "3 Piece Left Push", - () -> - AutonomousCommands.autoCLeftPush( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "3 Piece Right", - () -> - AutonomousCommands.autoCRight( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "3 Piece Right Push", - () -> - AutonomousCommands.autoCRightPush( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "2 Piece Left", - () -> - AutonomousCommands.autoBLeft( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "2 Piece Right", - () -> - AutonomousCommands.autoBRight( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "1 Piece Center", - () -> - AutonomousCommands.autoDCenter(drive, superstructure, RobotCameras.V3_Epsilon_CAMS)); - SmartDashboard.putData("Autonomous Modes", autoChooser); - } + private void configureAutos() {} @Override public void robotPeriodic() { @@ -413,30 +111,20 @@ public void robotPeriodic() { drive.getRawGyroRotation(), NetworkTablesJNI.now(), drive.getYawVelocity(), - drive.getFieldRelativeVelocity(), drive.getModulePositions(), - intake.getExtension(), - manipulator.getArmAngle(), - elevator.getPositionMeters(), - vision.getCameras()); + null); LTNUpdater.updateDrive(drive); LTNUpdater.updateElevator(elevator); - LTNUpdater.updateFunnel(funnel); - LTNUpdater.updateAlgaeArm(manipulator); - LTNUpdater.updateIntake(intake); Logger.recordOutput( "Component Poses", V3_EpsilonMechanism3d.getPoses( - elevator.getPositionMeters(), - funnel.getAngle(), - manipulator.getArmAngle(), - intake.getExtension())); + elevator.getPositionMeters(), manipulator.getArmAngle(), intake.getPivotAngle())); } @Override public Command getAutonomousCommand() { - return autoChooser.selectedCommand(); + return superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_RobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_RobotContainer.java deleted file mode 100644 index 7bcc06d5..00000000 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_RobotContainer.java +++ /dev/null @@ -1,432 +0,0 @@ -package frc.robot.subsystems.v3_Epsilon; - -import edu.wpi.first.networktables.NetworkTablesJNI; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; -import edu.wpi.first.wpilibj2.command.button.CommandXboxController; -import edu.wpi.first.wpilibj2.command.button.Trigger; -import frc.robot.Constants; -import frc.robot.Constants.Mode; -import frc.robot.FieldConstants.Reef.ReefPose; -import frc.robot.FieldConstants.Reef.ReefState; -import frc.robot.RobotContainer; -import frc.robot.RobotState; -import frc.robot.commands.AutonomousCommands; -import frc.robot.commands.CompositeCommands.SharedCommands; -import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; -import frc.robot.commands.DriveCommands; -import frc.robot.subsystems.shared.climber.Climber; -import frc.robot.subsystems.shared.climber.ClimberIO; -import frc.robot.subsystems.shared.climber.ClimberIOTalonFX; -import frc.robot.subsystems.shared.drive.Drive; -import frc.robot.subsystems.shared.drive.DriveConstants; -import frc.robot.subsystems.shared.drive.GyroIO; -import frc.robot.subsystems.shared.drive.GyroIOPigeon2; -import frc.robot.subsystems.shared.drive.ModuleIO; -import frc.robot.subsystems.shared.drive.ModuleIOSim; -import frc.robot.subsystems.shared.drive.ModuleIOTalonFX; -import frc.robot.subsystems.shared.elevator.Elevator; -import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; -import frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions; -import frc.robot.subsystems.shared.elevator.ElevatorIO; -import frc.robot.subsystems.shared.elevator.ElevatorIOSim; -import frc.robot.subsystems.shared.elevator.ElevatorIOTalonFX; -import frc.robot.subsystems.shared.funnel.Funnel; -import frc.robot.subsystems.shared.funnel.Funnel.FunnelFSM; -import frc.robot.subsystems.shared.funnel.FunnelIO; -import frc.robot.subsystems.shared.funnel.FunnelIOSim; -import frc.robot.subsystems.shared.visionlimelight.CameraConstants.RobotCameras; -import frc.robot.subsystems.shared.visionlimelight.Vision; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonIntakeIOTalonFX; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; -import frc.robot.util.LTNUpdater; -import frc.robot.util.LoggedChoreo.ChoreoChooser; -import org.littletonrobotics.junction.Logger; - -public class V3_EpsilonRobotContainer implements RobotContainer { - // Subsystems - private Climber climber; - private Drive drive; - private ElevatorFSM elevator; - private FunnelFSM funnel; - private Vision vision; - private V3_EpsilonIntake intake; - // private V3_EpsilonLEDs leds; - private V3_EpsilonManipulator manipulator; - private V3_Superstructure superstructure; - - // Controller - private final CommandXboxController driver = new CommandXboxController(0); - private final CommandXboxController operator = new CommandXboxController(1); - - // Auto chooser - private final ChoreoChooser autoChooser = new ChoreoChooser(); - - public V3_EpsilonRobotContainer() { - - if (Constants.getMode() != Mode.REPLAY) { - switch (Constants.ROBOT) { - case V3_EPSILON: - climber = new Climber(new ClimberIOTalonFX()); - drive = - new Drive( - new GyroIOPigeon2(), - new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), - new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), - new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), - new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); - elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); - // leds = new V3_EpsilonLEDs(); - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); - superstructure = new V3_EpsilonSuperstructure(elevator, funnel, intake, manipulator); - // vision = new Vision(RobotCameras.V3_Epsilon_CAMS); - break; - case V3_EPSILON_SIM: - // climber = new Climber(new ClimberIOSim()); - drive = - new Drive( - new GyroIO() {}, - new ModuleIOSim(DriveConstants.FRONT_LEFT), - new ModuleIOSim(DriveConstants.FRONT_RIGHT), - new ModuleIOSim(DriveConstants.BACK_LEFT), - new ModuleIOSim(DriveConstants.BACK_RIGHT)); - elevator = new Elevator(new ElevatorIOSim()).getFSM(); - funnel = new Funnel(new FunnelIOSim()).getFSM(); - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); - vision = new Vision(); - break; - default: - break; - } - } - - if (climber == null) { - climber = new Climber(new ClimberIO() {}); - } - if (drive == null) { - drive = - new Drive( - new GyroIO() {}, - new ModuleIO() {}, - new ModuleIO() {}, - new ModuleIO() {}, - new ModuleIO() {}); - } - if (elevator == null) { - elevator = new Elevator(new ElevatorIO() {}).getFSM(); - } - if (funnel == null) { - funnel = new Funnel(new FunnelIO() {}).getFSM(); - } - if (intake == null) { - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); - } - if (leds == null) { - leds = new V3_EpsilonLEDs(); - } - if (manipulator == null) { - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); - } - if (vision == null) { - vision = new Vision(); - } - superstructure = new V3_EpsilonSuperstructure(elevator, funnel, intake, manipulator); - - configureButtonBindings(); - configureAutos(); - } - - private void configureButtonBindings() { - // Generic triggers - Trigger elevatorStow = - new Trigger( - () -> - elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) - || elevator.getPosition().equals(ElevatorPositions.STOW)); - Trigger elevatorNotStow = - new Trigger( - () -> - !elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) - && !elevator.getPosition().equals(ElevatorPositions.STOW)); - // Trigger halfScoreTrigger = - // new Trigger(() -> operator.getLeftY() < -DriveConstants.OPERATOR_DEADBAND); - // Trigger unHalfScoreTrigger = - // new Trigger(() -> operator.getLeftY() > DriveConstants.OPERATOR_DEADBAND); - - Trigger operatorFunnelOverride = - new Trigger(() -> Math.hypot(operator.getRightX(), operator.getRightY()) > 0.5); - - // Default drive command - drive.setDefaultCommand( - DriveCommands.joystickDrive( - drive, - () -> -driver.getLeftY(), - () -> -driver.getLeftX(), - () -> -driver.getRightX(), - () -> false, - operator.back(), - driver.povRight())); - - // Driver face buttons - driver.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); - driver.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); - driver.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); - driver.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); - - driver - .y() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); - driver - .x() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); - driver - .b() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); - driver - .a() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); - - // Driver triggers - driver - .leftTrigger(0.5) - .whileTrue(V3_EpsilonCompositeCommands.intakeCoralDriverSequence(superstructure, intake)) - .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); - driver - .rightTrigger(0.5) - .whileTrue( - V3_EpsilonCompositeCommands.autoScoreCoralSequence( - drive, elevator, superstructure, RobotCameras.V3_Epsilon_CAMS)); - - // Driver bumpers - driver - .leftBumper() - .whileTrue(V3_EpsilonCompositeCommands.floorIntakeSequence(superstructure)) - .onFalse( - Commands.deadline( - V3_EpsilonCompositeCommands.postFloorIntakeSequence(superstructure), - Commands.runOnce(() -> intake.setRollerGoal(IntakeRollerState.OUTTAKE))) - .andThen(Commands.runOnce(() -> intake.setRollerGoal(IntakeRollerState.STOP)))); - driver.rightBumper().onTrue(Commands.runOnce(() -> RobotState.toggleReefPost())); - - // Driver POV - driver.povUp().onTrue(superstructure.setPosition()); - driver.povDown().onTrue(SharedCommands.resetHeading(drive)); - driver.povLeft().onTrue(DriveCommands.inchMovement(drive, -0.5, .07)); - - driver - .leftStick() - .onTrue( - V3_EpsilonCompositeCommands.scoreCoralSequence( - elevator, superstructure, () -> RobotState.getReefAlignData().atCoralSetpoint())); - - driver - .back() - .whileTrue( - V3_EpsilonCompositeCommands.intakeAlgaeFromReefSequence( - drive, - superstructure, - () -> RobotState.getReefAlignData().algaeIntakeHeight(), - RobotCameras.V3_Epsilon_CAMS)); - - driver - .start() - .whileTrue( - V3_EpsilonCompositeCommands.dropAlgae( - drive, - elevator, - manipulator, - intake, - superstructure, - () -> RobotState.getReefAlignData().algaeIntakeHeight(), - RobotCameras.V3_Epsilon_CAMS)); - - // Operator face buttons - operator.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); - operator.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); - operator.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); - operator.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); - - operator - .y() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); - operator - .x() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); - operator - .b() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); - operator - .a() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); - - // Operator triggers - operator - .leftTrigger(0.5) - .whileTrue(V3_EpsilonCompositeCommands.intakeCoralOperatorSequence(superstructure, intake)) - .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); - operator - .rightTrigger(0.5) - .whileTrue( - superstructure.override( - () -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_CORAL), 0.4)); - - // Operator bumpers - operator.leftBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))); - operator.rightBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))); - - operator.povUp().onTrue(V3_EpsilonCompositeCommands.climb(superstructure, climber, drive)); - operator.povDown().whileTrue(climber.winchClimberManual()); - operator - .povLeft() - .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR)) - .onFalse( - superstructure - .runActionWithTimeout(V3_EpsilonSuperstructureStates.SCORE_PROCESSOR, 1) - .finallyDo(() -> RobotState.setHasAlgae(false))); - - operator - .povRight() - .whileTrue( - superstructure - .override(() -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_ALGAE)) - .finallyDo(() -> RobotState.setHasAlgae(false))); - operator.start().whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)); - - operator - .back() - .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)) - .onFalse( - superstructure - .runActionWithTimeout(V3_EpsilonSuperstructureStates.SCORE_BARGE, 0.1) - .finallyDo(() -> RobotState.setHasAlgae(false))); - - // Misc - operatorFunnelOverride - .whileTrue( - Commands.either( - superstructure.runGoal(V3_EpsilonSuperstructureStates.FUNNEL_CLOSE_WITH_STOW_UP), - superstructure.runGoal(V3_EpsilonSuperstructureStates.FUNNEL_CLOSE_WITH_STOW_DOWN), - () -> RobotState.isHasAlgae())) - .onFalse(superstructure.runPreviousState()); - } - - private void configureAutos() { - AutonomousCommands.loadAutoTrajectories(drive); - - autoChooser.addCmd( - "Drive FF Characterization", () -> DriveCommands.feedforwardCharacterization(drive)); - autoChooser.addCmd( - "Wheel Radius Characterization", () -> DriveCommands.wheelRadiusCharacterization(drive)); - autoChooser.addCmd("Elevator Characterization", () -> elevator.sysIdRoutine(superstructure)); - autoChooser.addCmd("Funnel Characterization", () -> funnel.sysIdRoutine(superstructure)); - autoChooser.addCmd("Intake Characterization", () -> intake.sysIdRoutine(superstructure)); - autoChooser.addCmd( - "Manipulator Characterization", - () -> - Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.L3), - manipulator.sysIdRoutine(superstructure))); - autoChooser.addRoutine( - "4 Piece Left", - () -> - AutonomousCommands.autoALeft( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "4 Piece Right", - () -> - AutonomousCommands.autoARight( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - - autoChooser.addRoutine( - "4 Piece Left Nashoba", - () -> - AutonomousCommands.autoALeftNashoba( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - - autoChooser.addRoutine( - "4 Piece Left D.A.V.E.", - () -> - AutonomousCommands.autoALeftDAVE( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - - autoChooser.addRoutine( - "3 Piece Left", - () -> - AutonomousCommands.autoCLeft( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "3 Piece Left Push", - () -> - AutonomousCommands.autoCLeftPush( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "3 Piece Right", - () -> - AutonomousCommands.autoCRight( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "3 Piece Right Push", - () -> - AutonomousCommands.autoCRightPush( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "2 Piece Left", - () -> - AutonomousCommands.autoBLeft( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "2 Piece Right", - () -> - AutonomousCommands.autoBRight( - drive, intake, superstructure, RobotCameras.V3_Epsilon_CAMS)); - autoChooser.addRoutine( - "1 Piece Center", - () -> AutonomousCommands.autoDCenter(drive, superstructure, RobotCameras.V3_Epsilon_CAMS)); - SmartDashboard.putData("Autonomous Modes", autoChooser); - } - - @Override - public void robotPeriodic() { - RobotState.periodic( - drive.getRawGyroRotation(), - NetworkTablesJNI.now(), - drive.getYawVelocity(), - drive.getFieldRelativeVelocity(), - drive.getModulePositions(), - intake.getExtension(), - manipulator.getArmAngle(), - elevator.getPositionMeters(), - vision.getCameras()); - - LTNUpdater.updateDrive(drive); - LTNUpdater.updateElevator(elevator); - LTNUpdater.updateFunnel(funnel); - LTNUpdater.updateAlgaeArm(manipulator); - LTNUpdater.updateIntake(intake); - - Logger.recordOutput( - "Component Poses", - V3_EpsilonMechanism3d.getPoses( - elevator.getPositionMeters(), - funnel.getAngle(), - manipulator.getArmAngle(), - intake.getExtension())); - } - - @Override - public Command getAutonomousCommand() { - return autoChooser.selectedCommand(); - } -} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java deleted file mode 100644 index 4696f390..00000000 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java +++ /dev/null @@ -1,126 +0,0 @@ -package frc.robot.subsystems.v3_Epsilon.intake; - -import static edu.wpi.first.units.Units.*; - -import edu.wpi.first.math.MathUtil; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; -import edu.wpi.first.wpilibj2.command.SubsystemBase; -import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; -import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants.IntakeState; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; -import java.util.Set; -import lombok.Getter; -import org.littletonrobotics.junction.AutoLogOutput; -import org.littletonrobotics.junction.Logger; - -public class V3_EpsilonIntake extends SubsystemBase { - private final V3_EpsilonIntakeIO io; - private final IntakeIOInputsAutoLogged inputs; - private final SysIdRoutine characterizationRoutine; - - @Getter - @AutoLogOutput(key = "Intake/Goal") - private IntakeState goal; - - private boolean isClosedLoop; - - public V3_EpsilonIntake(V3_EpsilonIntakeIO io) { - this.io = io; - inputs = new IntakeIOInputsAutoLogged(); - - characterizationRoutine = - new SysIdRoutine( - new SysIdRoutine.Config( - Volts.of(0.2).per(Second), - Volts.of(3.5), - Seconds.of(8), - (state) -> Logger.recordOutput("Intake/SysID State", state.toString())), - new SysIdRoutine.Mechanism((volts) -> io.setPivotVoltage(volts.in(Volts)), null, this)); - - isClosedLoop = true; - } - - @Override - public void periodic() { - io.updateInputs(inputs); - Logger.processInputs("Intake", inputs); - - if (isClosedLoop) { - io.setPivotGoal(goal.getAngle()); - } - } - - @AutoLogOutput(key = "Intake/Has Coral") - public boolean hasCoral() { - return false; // Udpate later - } - - @AutoLogOutput(key = "Intake/At Goal") - public boolean atGoal() { - return Math.abs(inputs.pivotPosition.getRadians() - goal.getAngle().getRadians()) - < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); - } - - public void waitUntilIntakeAtGoal() { - Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::atGoal)); - } - - public void setGoal(IntakeState goal) { - isClosedLoop = true; - this.goal = goal; - } - - public void setRollerVoltage(double volts) { - io.setRollerVoltage(volts); - } - - public void setPivotVoltage(double volts) { - isClosedLoop = false; - io.setPivotVoltage(volts); - } - - public Command waitUntilPivotAtGoal() { - return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::atGoal)); - } - - public Command sysIdRoutine() { - return Commands.sequence( - Commands.runOnce(() -> isClosedLoop = false), - Commands.runOnce(() -> characterizationRoutine.quasistatic(Direction.kForward)), - Commands.waitSeconds(0.25), - Commands.runOnce(() -> characterizationRoutine.quasistatic(Direction.kReverse)), - Commands.waitSeconds(0.25), - Commands.runOnce(() -> characterizationRoutine.dynamic(Direction.kForward)), - Commands.waitSeconds(0.25), - Commands.runOnce(() -> characterizationRoutine.dynamic(Direction.kReverse))); - } - - private double holdVoltage() { - double y; - double x = Math.abs(inputs.rollerTorqueCurrentAmps); - if (x <= 20) { - y = -0.0003 * Math.pow(x, 3) + 0.0124286 * Math.pow(x, 2) - 0.241071 * x + 4.00643; - } else { - y = 0.0005 * Math.pow(x, 2) - 0.1015 * x + 3.7425; - } - return MathUtil.clamp( - 1.25 * y, - 0.10, - V3_EpsilonManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().getAsDouble() / 1.5); - } - - public void setRollerGoal(V3_EpsilonIntakeConstants.IntakeRollerStates rollerGoal) { - if (hasCoral() - && Set.of( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.CORAL_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP) - .contains(rollerGoal)) { - - io.setRollerVoltage(holdVoltage()); - } else { - io.setRollerVoltage(rollerGoal.getVoltage()); - } - } -} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java new file mode 100644 index 00000000..9929b71f --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -0,0 +1,559 @@ +package frc.robot.subsystems.v3_Epsilon.superstructure; + +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.FieldConstants.Reef.ReefState; +import frc.robot.RobotState; +import frc.robot.RobotState.RobotMode; +import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.EdgeCommand; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.util.NTPrefixes; +import java.util.HashMap; +import java.util.LinkedList; +import java.util.Map; +import java.util.Optional; +import java.util.Queue; +import java.util.Set; +import java.util.function.BooleanSupplier; +import java.util.function.DoubleSupplier; +import java.util.function.Supplier; +import java.util.stream.Collectors; +import lombok.Getter; +import org.jgrapht.Graph; +import org.jgrapht.graph.DefaultDirectedGraph; +import org.littletonrobotics.junction.AutoLogOutput; +import org.littletonrobotics.junction.Logger; + +/** + * The V3_EpsilonSuperstructure class manages the coordinated movement and state transitions of the + * robot's major subsystems including elevator, manipulator, and intake. + */ +public class V3_EpsilonSuperstructure extends SubsystemBase { + private final Graph graph; + private final ElevatorFSM elevator; + private final V3_EpsilonIntake intake; + private final V3_EpsilonManipulator manipulator; + + /** + * The previous, current, and next states of the superstructure. These are used to track the state + * transitions and manage the command scheduling. + */ + @Getter private V3_EpsilonSuperstructureStates previousState; + + /** + * The current state of the superstructure, which is updated periodically based on the command + * scheduling and state transitions. + */ + @Getter private V3_EpsilonSuperstructureStates currentState; + + /** + * The next state that the superstructure is transitioning to. This is determined by the command + * scheduling and the current target state. + */ + @Getter private V3_EpsilonSuperstructureStates nextState; + + /** + * The target state that the superstructure is trying to achieve. This is set by the robot and + * determines the next action to be taken. + */ + @Getter private V3_EpsilonSuperstructureStates targetState; + + /** The command that is currently being executed to transition between states. */ + private EdgeCommand edgeCommand; + + /** + * Constructs a V2_RedundancySuperstructure. + * + * @param elevator The elevator subsystem. + * @param intake The intake subsystem. + * @param manipulator The manipulator subsystem. + */ + public V3_EpsilonSuperstructure( + ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { + this.elevator = elevator; + this.intake = intake; + this.manipulator = manipulator; + + previousState = null; + currentState = V3_EpsilonSuperstructureStates.START; + nextState = null; + + targetState = V3_EpsilonSuperstructureStates.START; + + // Initialize the graph + graph = new DefaultDirectedGraph<>(EdgeCommand.class); + + for (V3_EpsilonSuperstructureStates vertex : V3_EpsilonSuperstructureStates.values()) { + graph.addVertex(vertex); + } + + // Add edges between states + V3_EpsilonSuperstructureEdges.addEdges(graph, elevator, intake, manipulator); + } + + /** + * Periodic method that handles state transitions and subsystem updates. Updates robot state + * variables and manages command scheduling based on current state. + */ + @Override + public void periodic() { + if (RobotMode.disabled()) { + nextState = null; + } else if (edgeCommand == null || !edgeCommand.getCommand().isScheduled()) { + // Update edge to new state + if (nextState != null) { + previousState = currentState; + currentState = nextState; + nextState = null; + } + + // Schedule next command in sequence + if (currentState != targetState) { + bfs(currentState, targetState) + .ifPresent( + next -> { + this.nextState = next; + edgeCommand = graph.getEdge(currentState, next); + edgeCommand.getCommand().schedule(); + }); + } + } + + // Log the current state of the superstructure and edge command + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "Goal", targetState == null ? "NULL" : targetState.toString()); + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "Previous State", + previousState == null ? "NULL" : previousState.toString()); + Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Current State", currentState.toString()); + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "Next State", + nextState == null ? "NULL" : nextState.toString()); + if (edgeCommand != null) { + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "EdgeCommand", + graph.getEdgeSource(edgeCommand) + " --> " + graph.getEdgeTarget(edgeCommand)); + } else { + Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "EdgeCommand", "NO EDGES SCHEDULED"); + } + + elevator.periodic(); + intake.periodic(); + manipulator.periodic(); + } + + /** + * Updates the target state and handles command rescheduling for optimal path. + * + * @param goal New target state to achieve + */ + private void setGoal(V3_EpsilonSuperstructureStates goal) { + // Don't do anything if goal is the same + if (this.targetState == goal) return; + else { + this.targetState = goal; + } + + if (nextState == null) return; + + var edgeToCurrentState = graph.getEdge(nextState, currentState); + // Figure out if we should schedule a different command to get to goal faster + if (edgeCommand.getCommand().isScheduled() + && edgeToCurrentState != null + && isEdgeAllowed(edgeToCurrentState, goal)) { + // Figure out where we would have gone from the previous state + bfs(currentState, goal) + .ifPresent( + newNext -> { + if (newNext == nextState) { + // We are already on track + return; + } + + if (newNext != currentState && graph.getEdge(nextState, newNext) != null) { + // We can skip directly to the newNext edge + edgeCommand.getCommand().cancel(); + edgeCommand = graph.getEdge(currentState, newNext); + edgeCommand.getCommand().schedule(); + nextState = newNext; + } else { + // Follow the reverse edge from next back to the current edge + edgeCommand.getCommand().cancel(); + edgeCommand = graph.getEdge(nextState, currentState); + edgeCommand.getCommand().schedule(); + var temp = currentState; + previousState = currentState; + currentState = nextState; + nextState = temp; + } + }); + } + } + + /** + * Performs breadth-first search to find the next state in the path to the goal. + * + * @param start Starting state + * @param goal Target state + * @return Optional containing the next state in the path, empty if no path exists + */ + private Optional bfs( + V3_EpsilonSuperstructureStates start, V3_EpsilonSuperstructureStates goal) { + Map parents = new HashMap<>(); + Queue queue = new LinkedList<>(); + queue.add(start); + parents.put(start, null); + while (!queue.isEmpty()) { + V3_EpsilonSuperstructureStates current = queue.poll(); + if (current == goal) break; + for (EdgeCommand edge : + graph.outgoingEdgesOf(current).stream() + .filter(edge -> isEdgeAllowed(edge, goal)) + .toList()) { + V3_EpsilonSuperstructureStates neighbor = graph.getEdgeTarget(edge); + if (!parents.containsKey(neighbor)) { + parents.put(neighbor, current); + queue.add(neighbor); + } + } + } + + if (!parents.containsKey(goal)) return Optional.empty(); + + V3_EpsilonSuperstructureStates nextState = goal; + while (!nextState.equals(start)) { + V3_EpsilonSuperstructureStates parent = parents.get(nextState); + if (parent == null) return Optional.empty(); + else if (parent.equals(start)) return Optional.of(nextState); + nextState = parent; + } + return Optional.of(nextState); + } + + /** + * Checks if a state transition is allowed based on algae presence. + * + * @param edge The transition edge to check + * @param goal The target state + * @return true if the transition is allowed + */ + private boolean isEdgeAllowed(EdgeCommand edge, V3_EpsilonSuperstructureStates goal) { + return true; + } + + /** Resets the superstructure to initial auto state. */ + public void setAutoStart() { + currentState = V3_EpsilonSuperstructureStates.START; + nextState = null; + targetState = V3_EpsilonSuperstructureStates.STOW_DOWN; + if (edgeCommand != null) { + edgeCommand.getCommand().cancel(); + } + } + + /** + * Maps current OI reef height to corresponding elevator position state. + * + * @return Appropriate superstructure state for current reef height + */ + private V3_EpsilonSuperstructureStates getElevatorPosition() { + switch (RobotState.getOIData().currentReefHeight()) { + case STOW, CORAL_INTAKE -> { + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + case L1 -> { + return V3_EpsilonSuperstructureStates.L1_PREP; + } + case L2 -> { + return V3_EpsilonSuperstructureStates.L2_PREP; + } + case L3 -> { + return V3_EpsilonSuperstructureStates.L3_PREP; + } + case L4 -> { + return V3_EpsilonSuperstructureStates.L4_PREP; + } + case ALGAE_INTAKE_BOTTOM -> { + return V3_EpsilonSuperstructureStates.L2_ALGAE_PREP; + } + case ALGAE_INTAKE_TOP -> { + return V3_EpsilonSuperstructureStates.L3_ALGAE_PREP; + } + case ALGAE_SCORE -> { + return V3_EpsilonSuperstructureStates.BARGE_PREP; + } + default -> { + return V3_EpsilonSuperstructureStates.START; + } + } + } + + // --- Control Commands --- + + /** + * Returns a command that sets the superstructure to the given goal state. + * + * @param goal The desired superstructure state + * @return Command to run the goal + */ + public Command runGoal(V3_EpsilonSuperstructureStates goal) { + return runOnce(() -> setGoal(goal)); + } + + /** + * Returns a command that sets the superstructure to the goal provided by a supplier. + * + * @param goal Supplier providing the desired superstructure state + * @return Command to run the goal + */ + public Command runGoal(Supplier goal) { + return runOnce(() -> setGoal(goal.get())); + } + + /** + * Checks whether the superstructure has reached its target state. + * + * @return true if current state matches the target state + */ + @AutoLogOutput(key = NTPrefixes.SUPERSTRUCTURE + "At Goal") + public boolean atGoal() { + return currentState == targetState; + } + + /** + * Runs a temporary override action, returning to a previous goal after. + * + * @param action The override action to perform + * @param oldGoal The goal to return to after override + * @return Command that runs the override and resumes the old goal + */ + public Command override(Runnable action) { + return Commands.sequence(runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), Commands.run(action)) + .finallyDo(() -> setGoal(currentState)); + } + + /** + * Runs a temporary override action, returning to a previous goal after. + * + * @param action The override action to perform + * @param oldGoal The goal to return to after override + * @return Command that runs the override and resumes the old goal + */ + public Command override(Runnable action, double timeSeconds) { + return override(action).withTimeout(timeSeconds); + } + + /** + * Runs the goal state and waits until a given condition becomes true. + * + * @param goal The desired superstructure state + * @param condition The condition to wait for after running the goal + * @return Combined command for running and waiting + */ + public Command runGoalUntil(V3_EpsilonSuperstructureStates goal, BooleanSupplier condition) { + return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); + } + + public Command runGoalUntil( + Supplier goal, BooleanSupplier condition) { + return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); + } + + /** + * Returns a short command to run the previous state, useful for temporary state restoration. + * + * @return Command to go back to the previous state + */ + public Command runPreviousState() { + return runGoal(() -> previousState); + } + + /** + * Converts a ReefState (field-level enum) into a corresponding elevator goal and runs it. + * + * @param goal Supplier of ReefState + * @return Command to move to the elevator position for the reef level + */ + public Command runReefGoal(Supplier goal) { + return runGoal( + () -> { + // Translate ReefState to superstructure state + switch (goal.get()) { + case L1: + return V3_EpsilonSuperstructureStates.L1_PREP; + case L2: + return V3_EpsilonSuperstructureStates.L2_PREP; + case L3: + return V3_EpsilonSuperstructureStates.L3_PREP; + case L4: + return V3_EpsilonSuperstructureStates.L4_PREP; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }); + } + + /** + * Moves to a scoring position, executes the score action for a fixed time, then returns to pose. + * + * @param goal Supplier of the ReefState (target height/level) + * @return Command to run the score cycle (pose → action → timeout → pose) + */ + public Command runReefScoreGoal(Supplier goal) { + // Run appropriate action sequence depending on reef level + return runActionWithTimeout( + () -> + switch (goal.get()) { + case L1 -> V3_EpsilonSuperstructureStates.L1_PREP; + case L2 -> V3_EpsilonSuperstructureStates.L2_PREP; + case L3 -> V3_EpsilonSuperstructureStates.L3_PREP; + case L4 -> V3_EpsilonSuperstructureStates.L4_PREP; + default -> V3_EpsilonSuperstructureStates.STOW_DOWN; + }, + () -> + switch (goal.get()) { + case L1 -> 0.8; + case L2 -> 0.15; + case L3 -> 0.15; + case L4 -> 0.4; + default -> 0; + }); + } + + /** + * Runs an action by going to a pose, performing the action, waiting, and returning. + * + * @param pose The pose to return to after action + * @param action The action to perform + * @param timeout How long to wait during the action phase (in seconds) + * @return Full command sequence + */ + public Command runActionWithTimeout( + Supplier pose, + Supplier action, + DoubleSupplier timeout) { + return Commands.sequence( + runGoal(action), // Run the action + Commands.waitUntil(() -> atGoal()), + Commands.defer(() -> Commands.waitSeconds(timeout.getAsDouble()), Set.of())) + .finallyDo(() -> setGoal(pose.get())); // Return to original pose + } + + /** + * Runs an action by going to a pose, performing the action, waiting, and returning. + * + * @param pose The pose to return to after action + * @param action The action to perform + * @param timeout How long to wait during the action phase (in seconds) + * @return Full command sequence + */ + public Command runActionWithTimeout( + V3_EpsilonSuperstructureStates pose, V3_EpsilonSuperstructureStates action, double timeout) { + return Commands.sequence( + runGoal(action), // Run the action + Commands.waitUntil(() -> atGoal()), + Commands.waitSeconds(timeout), + runGoal(pose)) + .finallyDo(() -> setGoal(pose)); // Return to original pose + } + + /** + * Smart overload that runs an action using a cached pose–action mapping, determining the pose + * from the action. + * + * @param action The scoring or action state + * @param timeout Timeout for the action duration + * @return Command sequence to perform and recover from the action + */ + public Command runActionWithTimeout( + Supplier action, DoubleSupplier timeout) { + // Maps each action state to its corresponding pose state + Map actionPoseMap = + new HashMap<>() { + { + put(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.L1_PREP); + put(V3_EpsilonSuperstructureStates.L2_SCORE, V3_EpsilonSuperstructureStates.L2_PREP); + put(V3_EpsilonSuperstructureStates.L3_SCORE, V3_EpsilonSuperstructureStates.L3_PREP); + put(V3_EpsilonSuperstructureStates.L4_SCORE, V3_EpsilonSuperstructureStates.L4_PREP); + put( + V3_EpsilonSuperstructureStates.BARGE_SCORE, + V3_EpsilonSuperstructureStates.BARGE_PREP); + put( + V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, + V3_EpsilonSuperstructureStates.PROCESSOR_PREP); + } + }; + + // Reverse the map so we can look up the pose from action if needed + Map poseActionMap = + actionPoseMap.entrySet().stream() + .collect(Collectors.toMap(Map.Entry::getValue, Map.Entry::getKey)); + + // Try to look up pose from action (either direction works) + if (actionPoseMap.containsKey(action.get())) { + return runActionWithTimeout(() -> actionPoseMap.get(action.get()), action, timeout); + } else if (actionPoseMap.containsValue(action.get())) { + return runActionWithTimeout(action, () -> poseActionMap.get(action.get()), timeout); + } else return Commands.none(); // If action is not recognized, do nothing + } + + /** + * Smart overload that runs an action using a cached pose–action mapping, determining the pose + * from the action. + * + * @param action The scoring or action state + * @param timeout Timeout for the action duration + * @return Command sequence to perform and recover from the action + */ + public Command runActionWithTimeout(V3_EpsilonSuperstructureStates action, double timeout) { + // Maps each action state to its corresponding pose state + Map actionPoseMap = + new HashMap<>() { + { + put(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.L1_PREP); + put(V3_EpsilonSuperstructureStates.L2_SCORE, V3_EpsilonSuperstructureStates.L2_PREP); + put(V3_EpsilonSuperstructureStates.L3_SCORE, V3_EpsilonSuperstructureStates.L3_PREP); + put(V3_EpsilonSuperstructureStates.L4_SCORE, V3_EpsilonSuperstructureStates.L4_PREP); + put( + V3_EpsilonSuperstructureStates.BARGE_SCORE, + V3_EpsilonSuperstructureStates.BARGE_PREP); + put( + V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, + V3_EpsilonSuperstructureStates.PROCESSOR_PREP); + } + }; + + // Reverse the map so we can look up the pose from action if needed + Map poseActionMap = + actionPoseMap.entrySet().stream() + .collect(Collectors.toMap(Map.Entry::getValue, Map.Entry::getKey)); + + // Try to look up pose from action (either direction works) + if (actionPoseMap.containsKey(action)) { + return runActionWithTimeout(actionPoseMap.get(action), action, timeout); + } else if (actionPoseMap.containsValue(action)) { + return runActionWithTimeout(action, poseActionMap.get(action), timeout); + } else return Commands.none(); // If action is not recognized, do nothing + } + + /** + * Updates the superstructure to match the current OI-defined reef height. + * + * @return Command to move to elevator position state + */ + public Command setPosition() { + return runGoal(() -> getElevatorPosition()).withTimeout(0.02); + } + + /** + * Checks if the elevator is at its goal position. + * + * @return True if the elevator is at its goal, false otherwise. + */ + public boolean elevatorAtGoal() { + return elevator.atGoal(); + } +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureAction.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureAction.java new file mode 100644 index 00000000..4f6606c8 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureAction.java @@ -0,0 +1,74 @@ +package frc.robot.subsystems.v3_Epsilon.superstructure; + +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakeRollerState; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; +import lombok.Getter; + +/** + * Coordinates and executes roller actions across multiple subsystems. This class manages the states + * of manipulator, funnel, and intake rollers and provides methods to control them in a coordinated + * manner. + */ +public class V3_EpsilonSuperstructureAction { + @Getter private final IntakeRollerState intakeRollerState; + @Getter private final ManipulatorRollerState manipulatorRollerState; + + /** + * Creates a new SuperstructureAction with specified roller states. + * + * @param key Identifier for the action set + * @param rollerStates Combined states for all subsystem rollers + */ + public V3_EpsilonSuperstructureAction(String key, SubsystemActions rollerStates) { + this.intakeRollerState = rollerStates.intakeRollerState(); + this.manipulatorRollerState = rollerStates.manipulatorRollerState(); + } + + /** + * Sets the manipulator roller to its configured state. + * + * @param manipulator The manipulator subsystem to control + */ + public void runManipulator(V3_EpsilonManipulator manipulator) { + manipulator.setRollerGoal(manipulatorRollerState); + } + + /** + * Sets the intake roller to its configured state. + * + * @param intake The intake subsystem to control + */ + public void runIntake(V3_EpsilonIntake intake) { + intake.setRollerGoal(intakeRollerState); + } + + /** + * Executes all roller actions simultaneously across all subsystems. + * + * @param funnel The funnel subsystem + * @param intake The intake subsystem + * @param manipulator The manipulator subsystem + */ + public void get(V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { + runIntake(intake); + runManipulator(manipulator); + } + + /** + * Record that holds the states for all roller subsystems. Provides a way to group and manage + * multiple roller states as a single unit. + */ + public record SubsystemActions( + ManipulatorRollerState manipulatorRollerState, IntakeRollerState intakeRollerState) { + /** + * Creates a SubsystemActions instance with all rollers in STOP state. + * + * @return A new SubsystemActions with all states set to STOP + */ + public static SubsystemActions empty() { + return new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.STOP); + } + } +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java new file mode 100644 index 00000000..fc56834d --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -0,0 +1,363 @@ +package frc.robot.subsystems.v3_Epsilon.superstructure; + +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import java.util.ArrayList; +import java.util.List; +import lombok.Builder; +import lombok.Getter; +import org.jgrapht.Graph; +import org.jgrapht.graph.DefaultEdge; + +public class V3_EpsilonSuperstructureEdges { + public static final ArrayList NONE_EDGES = new ArrayList<>(); + public static final ArrayList CORAL_EDGES = new ArrayList<>(); + public static final ArrayList ALGAE_EDGES = new ArrayList<>(); + + public record Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { + public Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { + this.from = from; + this.to = to; + } + + @Override + public String toString() { + return from + " -> " + to; + } + } + + public enum GamePieceEdge { + NONE, + CORAL, + ALGAE + } + + @Builder(toBuilder = true) + @Getter + public static class EdgeCommand extends DefaultEdge { + private final Command command; + @Builder.Default private final GamePieceEdge gamePieceEdge = GamePieceEdge.NONE; + } + + /** + * Gets the command to execute for a given edge in the superstructure state graph. This command + * typically involves coordinating the elevator, funnel, intake, and manipulator subsystems to + * move from one state to another. + * + * @param from The starting state of the superstructure. + * @param to The target state of the superstructure. + * @param elevator The elevator subsystem. + * @param intake The intake subsystem. + * @param manipulator The manipulator subsystem. + * @return A {@link Command} that, when executed, transitions the superstructure from the 'from' + * state to the 'to' state. + */ + private static Command getEdgeCommand( + V3_EpsilonSuperstructureStates from, + V3_EpsilonSuperstructureStates to, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + V3_EpsilonSuperstructurePose pose = to.getPose(); + // Default case: Execute all subsystem poses in parallel + return pose.asCommand(elevator, intake, manipulator); + } + + private static void createEdges() { + NONE_EDGES.add( + new Edge(V3_EpsilonSuperstructureStates.START, V3_EpsilonSuperstructureStates.STOW_DOWN)); + NONE_EDGES.add( + new Edge(V3_EpsilonSuperstructureStates.STOW_DOWN, V3_EpsilonSuperstructureStates.STOW_UP)); + NONE_EDGES.add( + new Edge(V3_EpsilonSuperstructureStates.HANDOFF, V3_EpsilonSuperstructureStates.STOW_UP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.STOW_UP, V3_EpsilonSuperstructureStates.L2_TRANSITION)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.STOW_UP, V3_EpsilonSuperstructureStates.L3_TRANSITION)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.STOW_UP, V3_EpsilonSuperstructureStates.L4_TRANSITION)); + + NONE_EDGES.add( + new Edge(V3_EpsilonSuperstructureStates.HANDOFF, V3_EpsilonSuperstructureStates.L1_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.HANDOFF, V3_EpsilonSuperstructureStates.L2_TRANSITION)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.HANDOFF, V3_EpsilonSuperstructureStates.L3_TRANSITION)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.HANDOFF, V3_EpsilonSuperstructureStates.L4_TRANSITION)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_TRANSITION, V3_EpsilonSuperstructureStates.HANDOFF)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_TRANSITION, V3_EpsilonSuperstructureStates.HANDOFF)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L4_TRANSITION, V3_EpsilonSuperstructureStates.HANDOFF)); + NONE_EDGES.add( + new Edge(V3_EpsilonSuperstructureStates.HANDOFF, V3_EpsilonSuperstructureStates.L2_PREP)); + NONE_EDGES.add( + new Edge(V3_EpsilonSuperstructureStates.HANDOFF, V3_EpsilonSuperstructureStates.L3_PREP)); + NONE_EDGES.add( + new Edge(V3_EpsilonSuperstructureStates.HANDOFF, V3_EpsilonSuperstructureStates.L4_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR, + V3_EpsilonSuperstructureStates.HANDOFF)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.GROUND_INTAKE, V3_EpsilonSuperstructureStates.L1_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.GROUND_INTAKE)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L1_PREP, V3_EpsilonSuperstructureStates.GROUND_INTAKE)); + NONE_EDGES.add( + new Edge(V3_EpsilonSuperstructureStates.L1_PREP, V3_EpsilonSuperstructureStates.L1_SCORE)); + NONE_EDGES.add( + new Edge(V3_EpsilonSuperstructureStates.L2_PREP, V3_EpsilonSuperstructureStates.L2_SCORE)); + NONE_EDGES.add( + new Edge(V3_EpsilonSuperstructureStates.L3_PREP, V3_EpsilonSuperstructureStates.L3_SCORE)); + NONE_EDGES.add( + new Edge(V3_EpsilonSuperstructureStates.L4_PREP, V3_EpsilonSuperstructureStates.L4_SCORE)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_PREP, + V3_EpsilonSuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_PREP, + V3_EpsilonSuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.GROUND_INTAKE)); + NONE_EDGES.add( + new Edge(V3_EpsilonSuperstructureStates.L1_PREP, V3_EpsilonSuperstructureStates.HANDOFF)); + NONE_EDGES.add( + new Edge(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.HANDOFF)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_SCORE, + V3_EpsilonSuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_SCORE, + V3_EpsilonSuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L4_SCORE, + V3_EpsilonSuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_PREP, V3_EpsilonSuperstructureStates.L3_TRANSITION)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_PREP, V3_EpsilonSuperstructureStates.L4_TRANSITION)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_PREP, V3_EpsilonSuperstructureStates.L2_TRANSITION)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_PREP, V3_EpsilonSuperstructureStates.L4_TRANSITION)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L4_PREP, V3_EpsilonSuperstructureStates.L3_TRANSITION)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L4_PREP, V3_EpsilonSuperstructureStates.L2_TRANSITION)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_TRANSITION, V3_EpsilonSuperstructureStates.L2_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_TRANSITION, V3_EpsilonSuperstructureStates.L3_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L4_TRANSITION, V3_EpsilonSuperstructureStates.L4_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_PREP, V3_EpsilonSuperstructureStates.L2_TRANSITION)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_PREP, V3_EpsilonSuperstructureStates.L3_TRANSITION)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L4_PREP, V3_EpsilonSuperstructureStates.L4_TRANSITION)); + + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.STOW_UP, V3_EpsilonSuperstructureStates.L2_ALGAE_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.STOW_UP, V3_EpsilonSuperstructureStates.L3_ALGAE_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.STOW_UP, V3_EpsilonSuperstructureStates.BARGE_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.STOW_UP, V3_EpsilonSuperstructureStates.PROCESSOR_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L2_ALGAE_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L3_ALGAE_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_ALGAE_PREP, + V3_EpsilonSuperstructureStates.BARGE_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_ALGAE_PREP, + V3_EpsilonSuperstructureStates.BARGE_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_ALGAE_PREP, + V3_EpsilonSuperstructureStates.PROCESSOR_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_ALGAE_PREP, + V3_EpsilonSuperstructureStates.PROCESSOR_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_ALGAE_PREP, V3_EpsilonSuperstructureStates.STOW_UP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_ALGAE_PREP, V3_EpsilonSuperstructureStates.STOW_UP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_ALGAE_PREP, + V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE, + V3_EpsilonSuperstructureStates.L2_ALGAE_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE, + V3_EpsilonSuperstructureStates.L3_ALGAE_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_ALGAE_PREP, + V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE, + V3_EpsilonSuperstructureStates.STOW_UP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE, + V3_EpsilonSuperstructureStates.STOW_UP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.BARGE_PREP, V3_EpsilonSuperstructureStates.BARGE_SCORE)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.PROCESSOR_PREP, + V3_EpsilonSuperstructureStates.PROCESSOR_SCORE)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, + V3_EpsilonSuperstructureStates.STOW_UP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, + V3_EpsilonSuperstructureStates.STOW_DOWN)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, + V3_EpsilonSuperstructureStates.HANDOFF)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.STOW_UP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.STOW_DOWN)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.HANDOFF)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L2_ALGAE_PREP, + V3_EpsilonSuperstructureStates.L3_ALGAE_PREP)); + NONE_EDGES.add( + new Edge( + V3_EpsilonSuperstructureStates.L3_ALGAE_PREP, + V3_EpsilonSuperstructureStates.L2_ALGAE_PREP)); + } + + /** + * Adds edges to the superstructure state graph based on the provided list of edges and algae + * condition. + * + * @param graph The graph to which edges are added. + * @param edges A list of {@link Edge} objects representing the transitions between states. + * @param type The {@link GamePieceEdge} type associated with these edges. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param funnel The funnel subsystem. + * @param intake The intake subsystem. + */ + private static void addEdges( + Graph graph, + List edges, + GamePieceEdge type, + ElevatorFSM elevator, + V3_EpsilonManipulator manipulator, + V3_EpsilonIntake intake) { + // Iterate through each edge in the provided list + for (Edge edge : edges) { + // Add the edge to the graph with its associated command and algae type + graph.addEdge( + edge.from(), + edge.to(), + EdgeCommand.builder() + .command(getEdgeCommand(edge.from(), edge.to(), elevator, intake, manipulator)) + .gamePieceEdge(type) + .build()); + } + } + + /** + * Adds all predefined edges to the superstructure state graph, categorized by algae condition. + * + * @param graph The graph to which edges are added. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param funnel The funnel subsystem. + * @param intake The intake subsystem. + */ + public static void addEdges( + Graph graph, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + // Create all edge lists (NoneEdges, NoAlgaeEdges, AlgaeEdges) + createEdges(); + + // Add edges to the graph for each algae condition + addEdges(graph, NONE_EDGES, GamePieceEdge.NONE, elevator, manipulator, intake); + addEdges(graph, CORAL_EDGES, GamePieceEdge.CORAL, elevator, manipulator, intake); + addEdges(graph, ALGAE_EDGES, GamePieceEdge.ALGAE, elevator, manipulator, intake); + } +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java new file mode 100644 index 00000000..8db1fc6a --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java @@ -0,0 +1,116 @@ +package frc.robot.subsystems.v3_Epsilon.superstructure; + +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; +import frc.robot.FieldConstants.Reef.ReefState; +import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakePivotState; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; +import lombok.Getter; + +/** + * Represents a specific pose (configuration) of the superstructure, defining the states of the + * elevator, manipulator arm, intake, and funnel. This class allows for coordinated control of these + * subsystems to achieve a desired configuration. + */ +public class V3_EpsilonSuperstructurePose { + private final String key; + + @Getter private final ReefState elevatorHeight; + @Getter private final ManipulatorArmState armState; + @Getter private final IntakePivotState intakeState; + + /** + * Constructs a new V3_EpsilonSuperstructurePose with the given subsystem poses. + * + * @param key A unique identifier for this pose. + * @param poses The combined poses for all relevant subsystems. + */ + public V3_EpsilonSuperstructurePose(String key, SubsystemPoses poses) { + this.key = key; + + this.elevatorHeight = poses.elevatorHeight(); + this.armState = poses.manipulatorArmState(); + this.intakeState = poses.intakePivotState(); + } + + /** + * Creates a command to set the elevator to the specified height for this pose. + * + * @param elevator The elevator subsystem to control. + * @return A Command that sets the elevator height and waits until it reaches the goal. + */ + public Command setElevatorHeight(ElevatorFSM elevator) { + return Commands.parallel( + Commands.runOnce(() -> elevator.setPosition(() -> elevatorHeight)), + elevator.waitUntilAtGoal()); + } + + /** + * Creates a command to set the intake to the specified extension state for this pose. + * + * @param intake The intake subsystem to control. + * @return A Command that sets the intake extension state and waits until it reaches the goal. + */ + public Command setIntakeState(V3_EpsilonIntake intake) { + return Commands.parallel( + Commands.runOnce(() -> intake.setPivotGoal(intakeState)), intake.waitUntilPivotAtGoal()); + } + + /** + * Creates a command to set the manipulator arm to the specified state for this pose. + * + * @param manipulator The manipulator subsystem to control. + * @return A Command that sets the arm state and waits until it reaches the goal. + */ + public Command setManipulatorState(V3_EpsilonManipulator manipulator) { + return Commands.parallel( + Commands.runOnce(() -> manipulator.setArmGoal(armState)), manipulator.waitUntilArmAtGoal()); + } + + /** + * Creates a command that sets all subsystems (elevator, manipulator, intake, and funnel) to the + * states defined by this pose. + * + * @param elevator The elevator subsystem. + * @param funnel The funnel subsystem. + * @param intake The intake subsystem. + * @param manipulator The manipulator subsystem. + * @return A Command that sets all subsystems to their respective states in parallel. + */ + public Command asCommand( + ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { + return Commands.parallel( + Commands.runOnce(() -> elevator.setPosition(() -> elevatorHeight)), + Commands.runOnce(() -> manipulator.setArmGoal(armState)), + Commands.runOnce(() -> intake.setPivotGoal(intakeState))); + } + + /** + * Returns a string representation of this pose (the key). + * + * @return The key of this pose. + */ + public String toString() { + return key; + } + + /** + * A record that groups the states of the elevator, manipulator arm, intake, and funnel + * subsystems. This is used to define a complete pose for the superstructure. + */ + public record SubsystemPoses( + ReefState elevatorHeight, + ManipulatorArmState manipulatorArmState, + IntakePivotState intakePivotState) { + + /** + * Creates a SubsystemPoses instance with default states (STOW for elevator, arm, and intake). + */ + public SubsystemPoses() { + this(ReefState.STOW, ManipulatorArmState.STOW_DOWN, IntakePivotState.STOW); + } + } +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java new file mode 100644 index 00000000..3ac0d9c9 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -0,0 +1,210 @@ +package frc.robot.subsystems.v3_Epsilon.superstructure; + +// Adjust the package path as needed +import frc.robot.FieldConstants.Reef.ReefState; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureAction.SubsystemActions; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructurePose.SubsystemPoses; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakePivotState; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakeRollerState; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; + +// correct package +// path + +public enum V3_EpsilonSuperstructureStates { + START("START", new SubsystemPoses(), SubsystemActions.empty()), + STOW_DOWN("STOW_DOWN", new SubsystemPoses(), SubsystemActions.empty()), + STOW_UP( + "STOW_UP", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.STOW_UP, IntakePivotState.STOW), + SubsystemActions.empty()), + + HANDOFF( + "HANDOFF", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + + GROUND_INTAKE( + "GROUND_INTAKE", + new SubsystemPoses( + ReefState.STOW, ManipulatorArmState.FLOOR_INTAKE, IntakePivotState.INTAKE_CORAL), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.CORAL_INTAKE)), + + // Coral Prep States + L1_PREP( + "L1", + new SubsystemPoses(ReefState.L1, ManipulatorArmState.PRE_SCORE, IntakePivotState.L1), + SubsystemActions.empty()), + + L2_PREP( + "L2", + new SubsystemPoses(ReefState.L2, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), + SubsystemActions.empty()), + + L3_PREP( + "L3", + new SubsystemPoses(ReefState.L3, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), + SubsystemActions.empty()), + + L4_PREP( + "L4", + new SubsystemPoses(ReefState.L4, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), + SubsystemActions.empty()), + + // Coral Score States + L1_SCORE( + "L1_SCORE", + new SubsystemPoses(ReefState.L1, ManipulatorArmState.PRE_SCORE, IntakePivotState.L1), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.SCORE_CORAL)), + + L2_SCORE( + "L2_SCORE", + new SubsystemPoses(ReefState.L2, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), + + L3_SCORE( + "L3_SCORE", + new SubsystemPoses(ReefState.L3, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), + + L4_SCORE( + "L4_SCORE", + new SubsystemPoses( + ReefState.L4, + ManipulatorArmState + .PRE_SCORE, // Determine whether PRE_SCORE is accurate for all scoring states + IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), + + // Algae Prep States + L2_ALGAE_PREP( + "L2_ALGAE_PREP", + new SubsystemPoses(ReefState.L2, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), + SubsystemActions.empty()), + + L3_ALGAE_PREP( + "L3_ALGAE_PREP", + new SubsystemPoses(ReefState.L3, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), + SubsystemActions.empty()), + + // Algae Scoring States + L2_ALGAE_INTAKE( + "L2_ALGAE_INTAKE", + new SubsystemPoses(ReefState.L2, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + + L3_ALGAE_INTAKE( + "L3_ALGAE_INTAKE", + new SubsystemPoses(ReefState.L3, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + + // Miscelaneous States (Barge + Processor Prep and Score States) + BARGE_PREP( + "BARGE_PREP", + new SubsystemPoses( + ReefState.ALGAE_SCORE, + ManipulatorArmState + .REEF_INTAKE, // Assuming REEF_INTAKE and BARGE_PREP have same rotation values + IntakePivotState.STOW), + SubsystemActions.empty()), + + PROCESSOR_PREP( + "PROCESSOR_PREP", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + SubsystemActions.empty()), + + BARGE_SCORE( + "BARGE_SCORE", + new SubsystemPoses( + ReefState.ALGAE_SCORE, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions( + ManipulatorRollerState + .SCORE_ALGAE, // Assuming you score in the barge by stowing intake and moving + // manipulator to desired position + IntakeRollerState.STOP)), + + PROCESSOR_SCORE( + "PROCESSOR_SCORE", + new SubsystemPoses( + ReefState.ALGAE_SCORE, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + + INTERMIDIATE_WAIT_FOR_ELEVATOR( + "INTERMIDIATE_WAIT_FOR_ELEVATOR", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.STOW_UP, IntakePivotState.STOW), + SubsystemActions.empty()), + + // Transition States + L2_TRANSITION( + "L2_TRANSITION", + new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), + SubsystemActions.empty()), + + L3_TRANSITION( + "L3_TRANSITION", + new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), + SubsystemActions.empty()), + + L4_TRANSITION( + "L4_TRANSITION", + new SubsystemPoses(ReefState.L4, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), + SubsystemActions.empty()), + + CLIMB( + "CLIMB", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.STOW_UP, IntakePivotState.STOW), + SubsystemActions.empty()), + + OVERRIDE("OVERRIDE", new SubsystemPoses(), SubsystemActions.empty()); + + // Readable name for state + private final String name; + + // Target positions for all subsystems in this state + private final SubsystemPoses subsystemPoses; + + // Actions to perform for all subsystems in this state + private final SubsystemActions subsystemActions; + + /** + * Constructor for V3_SuperstructureStates. + * + * @param name The name of the state. + * @param pose The subsystem poses for this state. + * @param action The subsystem actions for this state. + */ + V3_EpsilonSuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { + this.name = name; + this.subsystemPoses = pose; + this.subsystemActions = action; + } + + /** + * Constructor for V3_SuperstructureStates with empty actions. + * + * @param name The name of the state. + * @param pose The subsystem poses for this state. + */ + public V3_EpsilonSuperstructurePose getPose() { + return new V3_EpsilonSuperstructurePose(name, subsystemPoses); + } + + /** + * Returns the actions associated with this superstructure state. + * + * @return The actions for this state. + */ + public V3_EpsilonSuperstructureAction getAction() { + return new V3_EpsilonSuperstructureAction(name, subsystemActions); + } + + /** + * Returns the name of the superstructure state. + * + * @return The name of the state. + */ + public String getName() { + return name; + } +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java deleted file mode 100644 index 60764026..00000000 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_Superstructure.java +++ /dev/null @@ -1,359 +0,0 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure; - -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; -import edu.wpi.first.wpilibj2.command.SubsystemBase; -import frc.robot.RobotState; -import frc.robot.RobotState.RobotMode; -import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureEdges.AlgaeEdge; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureEdges.EdgeCommand; -import frc.robot.util.NTPrefixes; -import java.util.HashMap; -import java.util.LinkedList; -import java.util.Map; -import java.util.Optional; -import java.util.Queue; -import java.util.function.BooleanSupplier; -import java.util.function.Supplier; -import lombok.Getter; -import org.jgrapht.Graph; -import org.jgrapht.graph.DefaultDirectedGraph; -import org.littletonrobotics.junction.AutoLogOutput; -import org.littletonrobotics.junction.Logger; - -/** - * The V3_Superstructure class manages the coordinated movement and state transitions of the robot's - * major subsystems including elevator, funnel, manipulator, and intake. - */ -public class V3_Superstructure extends SubsystemBase { - - private final Graph graph; - private final ElevatorFSM elevator; - private final V3_EpsilonIntake intake; - private final V3_EpsilonManipulator manipulator; - - /** - * The previous, current, and next states of the superstructure. These are used to track the state - * transitions and manage the command scheduling. - */ - @Getter private V3_SuperstructureStates previousState; - - /** - * The current state of the superstructure, which is updated periodically based on the command - * scheduling and state transitions. - */ - @Getter private V3_SuperstructureStates currentState; - - /** - * The next state that the superstructure is transitioning to. This is determined by the command - * scheduling and the current target state. - */ - @Getter private V3_SuperstructureStates nextState; - - /** - * The target state that the superstructure is trying to achieve. This is set by the robot and - * determines the next action to be taken. - */ - @Getter private V3_SuperstructureStates targetState; - - /** The command that is currently being executed to transition between states. */ - private EdgeCommand edgeCommand; - - /** - * Constructs a V3_Superstructure. - * - * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. - * @param intake The intake subsystem. - * @param manipulator The manipulator subsystem. - */ - public V3_Superstructure( - ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { - this.elevator = elevator; - this.intake = intake; - this.manipulator = manipulator; - - previousState = null; - currentState = V3_SuperstructureStates.START; - nextState = null; - - targetState = V3_SuperstructureStates.START; - - // Initialize the graph - graph = new DefaultDirectedGraph<>(EdgeCommand.class); - - for (V3_SuperstructureStates vertex : V3_SuperstructureStates.values()) { - graph.addVertex(vertex); - } - } - - /** - * Periodic method that handles state transitions and subsystem updates. Updates robot state - * variables and manages command scheduling based on current state. - */ - @Override - public void periodic() { - - if (RobotMode.disabled()) { - nextState = null; - } else if (edgeCommand == null || !edgeCommand.getCommand().isScheduled()) { - // Update edge to new state - if (nextState != null) { - previousState = currentState; - currentState = nextState; - nextState = null; - } - - // Schedule next command in sequence - if (currentState != targetState) { - bfs(currentState, targetState) - .ifPresent( - next -> { - this.nextState = next; - edgeCommand = graph.getEdge(currentState, next); - edgeCommand.getCommand().schedule(); - }); - } - } - - // Log the current state of the superstructure and edge command - Logger.recordOutput( - NTPrefixes.SUPERSTRUCTURE + "Goal", targetState == null ? "NULL" : targetState.toString()); - Logger.recordOutput( - NTPrefixes.SUPERSTRUCTURE + "Previous State", - previousState == null ? "NULL" : previousState.toString()); - Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Current State", currentState.toString()); - Logger.recordOutput( - NTPrefixes.SUPERSTRUCTURE + "Next State", - nextState == null ? "NULL" : nextState.toString()); - if (edgeCommand != null) { - Logger.recordOutput( - NTPrefixes.SUPERSTRUCTURE + "EdgeCommand", - graph.getEdgeSource(edgeCommand) + " --> " + graph.getEdgeTarget(edgeCommand)); - } else { - Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "EdgeCommand", "NO EDGES SCHEDULED"); - } - - elevator.periodic(); - intake.periodic(); - manipulator.periodic(); - } - - /** - * Updates the target state and handles command rescheduling for optimal path. - * - * @param goal New target state to achieve - */ - private void setGoal(V3_SuperstructureStates goal) { - // Don't do anything if goal is the same - if (this.targetState == goal) return; - else { - this.targetState = goal; - } - - if (nextState == null) return; - - var edgeToCurrentState = graph.getEdge(nextState, currentState); - // Figure out if we should schedule a different command to get to goal faster - if (edgeCommand.getCommand().isScheduled() - && edgeToCurrentState != null - && isEdgeAllowed(edgeToCurrentState, goal)) { - // Figure out where we would have gone from the previous state - bfs(currentState, goal) - .ifPresent( - newNext -> { - if (newNext == nextState) { - // We are already on track - return; - } - - if (newNext != currentState && graph.getEdge(nextState, newNext) != null) { - // We can skip directly to the newNext edge - edgeCommand.getCommand().cancel(); - edgeCommand = graph.getEdge(currentState, newNext); - edgeCommand.getCommand().schedule(); - nextState = newNext; - } else { - // Follow the reverse edge from next back to the current edge - edgeCommand.getCommand().cancel(); - edgeCommand = graph.getEdge(nextState, currentState); - edgeCommand.getCommand().schedule(); - var temp = currentState; - previousState = currentState; - currentState = nextState; - nextState = temp; - } - }); - } - } - - /** - * Performs breadth-first search to find the next state in the path to the goal. - * - * @param start Starting state - * @param goal Target state - * @return Optional containing the next state in the path, empty if no path exists - */ - private Optional bfs( - V3_SuperstructureStates start, V3_SuperstructureStates goal) { - Map parents = new HashMap<>(); - Queue queue = new LinkedList<>(); - queue.add(start); - parents.put(start, null); - while (!queue.isEmpty()) { - V3_SuperstructureStates current = queue.poll(); - if (current == goal) break; - for (EdgeCommand edge : - graph.outgoingEdgesOf(current).stream() - .filter(edge -> isEdgeAllowed(edge, goal)) - .toList()) { - V3_SuperstructureStates neighbor = graph.getEdgeTarget(edge); - if (!parents.containsKey(neighbor)) { - parents.put(neighbor, current); - queue.add(neighbor); - } - } - } - - if (!parents.containsKey(goal)) return Optional.empty(); - - V3_SuperstructureStates nextState = goal; - while (!nextState.equals(start)) { - V3_SuperstructureStates parent = parents.get(nextState); - if (parent == null) return Optional.empty(); - else if (parent.equals(start)) return Optional.of(nextState); - nextState = parent; - } - return Optional.of(nextState); - } - - /** - * Checks if a state transition is allowed based on algae presence. - * - * @param edge The transition edge to check - * @param goal The target state - * @return true if the transition is allowed - */ - private boolean isEdgeAllowed(EdgeCommand edge, V3_SuperstructureStates goal) { // Change later - return edge.getAlgaeEdgeType() == AlgaeEdge.NONE - || RobotState.isHasAlgae() == (edge.getAlgaeEdgeType() == AlgaeEdge.ALGAE); - } - - /** Resets the superstructure to initial auto state. */ - public void setAutoStart() { - currentState = V3_SuperstructureStates.START; - nextState = null; - targetState = V3_SuperstructureStates.STOW_DOWN; - if (edgeCommand != null) { - edgeCommand.getCommand().cancel(); - } - } - // --- Control Commands --- - - /** - * Returns a command that sets the superstructure to the given goal state. - * - * @param goal The desired superstructure state - * @return Command to run the goal - */ - public Command runGoal(V3_SuperstructureStates goal) { - return runOnce(() -> setGoal(goal)); - } - - /** - * Returns a command that sets the superstructure to the goal provided by a supplier. - * - * @param goal Supplier providing the desired superstructure state - * @return Command to run the goal - */ - public Command runGoal(Supplier goal) { - return runOnce(() -> setGoal(goal.get())); - } - - /** - * Checks whether the superstructure has reached its target state. - * - * @return true if current state matches the target state - */ - @AutoLogOutput(key = NTPrefixes.SUPERSTRUCTURE + "At Goal") - public boolean atGoal() { - return currentState == targetState; - } - - /** - * Runs a temporary override action, returning to a previous goal after. - * - * @param action The override action to perform - * @param oldGoal The goal to return to after override - * @return Command that runs the override and resumes the old goal - */ - public Command override(Runnable action) { - return Commands.sequence(runGoal(V3_SuperstructureStates.OVERRIDE), Commands.run(action)) - .finallyDo(() -> setGoal(currentState)); - } - - /** - * Runs a temporary override action, returning to a previous goal after. - * - * @param action The override action to perform - * @param oldGoal The goal to return to after override - * @return Command that runs the override and resumes the old goal - */ - public Command override(Runnable action, double timeSeconds) { - return override(action).withTimeout(timeSeconds); - } - - /** - * Runs the goal state and waits until a given condition becomes true. - * - * @param goal The desired superstructure state - * @param condition The condition to wait for after running the goal - * @return Combined command for running and waiting - */ - public Command runGoalUntil(V3_SuperstructureStates goal, BooleanSupplier condition) { - return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); - } - - public Command runGoalUntil(Supplier goal, BooleanSupplier condition) { - return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); - } - - /** - * Returns a short command to run the previous state, useful for temporary state restoration. - * - * @return Command to go back to the previous state - */ - public Command runPreviousState() { - return runGoal(() -> previousState); - } - - /** - * Runs an action by going to a pose, performing the action, waiting, and returning. - * - * @param pose The pose to return to after action - * @param action The action to perform - * @param timeout How long to wait during the action phase (in seconds) - * @return Full command sequence - */ - public Command runActionWithTimeout( - V3_SuperstructureStates pose, V3_SuperstructureStates action, double timeout) { - return Commands.sequence( - runGoal(action), // Run the action - Commands.waitUntil(() -> atGoal()), - Commands.waitSeconds(timeout), - runGoal(pose)) - .finallyDo(() -> setGoal(pose)); // Return to original pose - } - - /** - * Checks if the elevator is at its goal position. - * - * @return True if the elevator is at its goal, false otherwise. - */ - public boolean elevatorAtGoal() { - return elevator.atGoal(); - } -} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java deleted file mode 100644 index f5fb9370..00000000 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureActions.java +++ /dev/null @@ -1,72 +0,0 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure; - -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; -import lombok.Getter; - -public class V3_SuperstructureActions { - - @Getter - private final V3_EpsilonManipulatorConstants.ManipulatorRollerStates manipulatorRollerState; - - @Getter private final V3_EpsilonIntakeConstants.IntakeRollerStates intakeRollerStates; - - /** - * Creates a new instance of V3_SuperstructureActions with the specified key and subsystem - * actions. - * - * @param key - * @param subsystemActions - */ - public V3_SuperstructureActions(String key, SubsystemActions subsystemActions) { - this.manipulatorRollerState = V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP; - this.intakeRollerStates = V3_EpsilonIntakeConstants.IntakeRollerStates.STOP; - } - - /** - * Runs the manipulator with the specified roller state. - * - * @param manipulator - */ - public void runManipulator(V3_EpsilonManipulator manipulator) { - manipulator.setRollerGoal(manipulatorRollerState); - } - - /** - * Runs the intake with the specified roller state. - * - * @param intake - */ - public void runIntake(V3_EpsilonIntake intake) { - intake.setRollerGoal(intakeRollerStates); - } - - /** - * Runs both the intake and manipulator simultaneously with their respective roller states. - * - * @param intake - * @param manipulator - */ - public void get(V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { - // Run all actions simultaneously - runIntake(intake); - runManipulator(manipulator); - } - - /** - * Represents the actions for the subsystems in the superstructure. This record holds the states - * for the manipulator roller and intake roller. - */ - public record SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates manipulatorRollerState, - V3_EpsilonIntakeConstants.IntakeRollerStates intakeRollerStates) { - - public static SubsystemActions empty() { - return new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP, - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP); - } - } -} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java deleted file mode 100644 index fa0c4415..00000000 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureEdges.java +++ /dev/null @@ -1,246 +0,0 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure; - -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; -import frc.robot.subsystems.shared.elevator.Elevator; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; -import java.util.ArrayList; -import java.util.List; -import lombok.Builder; -import lombok.Getter; -import org.jgrapht.graph.DefaultEdge; - -public class V3_SuperstructureEdges { - - public static final ArrayList AlgaeEdges = new ArrayList<>(); - public static final ArrayList CoralEdges = new ArrayList<>(); - public static final ArrayList UnconstrainedEdges = new ArrayList<>(); - public static final ArrayList NoneEdges = new ArrayList<>(); - - public record Edge(V3_SuperstructureStates from, V3_SuperstructureStates to, String action) { - public Edge(V3_SuperstructureStates from, V3_SuperstructureStates to) { - this(from, to, ""); - } - - public String toString() { - return from + " -> " + to + (action.isEmpty() ? "" : " : " + action); - } - } - - public enum AlgaeEdge { - NONE, - NO_ALGAE, - ALGAE - } - - public enum CoralEdge { - NONE, - NO_CORAL, - CORAL - } - - @Builder(toBuilder = true) - @Getter - public static class EdgeCommand extends DefaultEdge { - private final Command command; - @Builder.Default private final AlgaeEdge algaeEdgeType = AlgaeEdge.NONE; - @Builder.Default private final CoralEdge coralEdgeType = CoralEdge.NONE; - } - - private static Command getEdgeCommand( - V3_SuperstructureStates from, - V3_SuperstructureStates to, - Elevator.ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - - // TODO: Implement the actual command logic - - return Commands.none(); - } - - public static void createEdges() { - List coralPrepLevels = - List.of( - V3_SuperstructureStates.L1_PREP, - V3_SuperstructureStates.L2_PREP, - V3_SuperstructureStates.L3_PREP, - V3_SuperstructureStates.L4_PREP); - - List coralTransitionLevels = - List.of( - V3_SuperstructureStates.L2_TRANSITION, - V3_SuperstructureStates.L3_TRANSITION, - V3_SuperstructureStates.L4_TRANSITION); - - // Coral Edges - - // Level to level edges - for (V3_SuperstructureStates from : coralPrepLevels) { - for (V3_SuperstructureStates to : coralPrepLevels) { - if (from != to) { - CoralEdges.add(new Edge(from, to, "Coral Level Transition")); - } - } - } - - // Handoff -> transition - for (V3_SuperstructureStates to : coralTransitionLevels) { - CoralEdges.add(new Edge(V3_SuperstructureStates.HANDOFF, to, "Coral Transition")); - } - - // Handoff -> L1_PREP - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L1_PREP, - V3_SuperstructureStates.HANDOFF, - "Coral Handoff L1 Prep")); - - // Transition -> handoff - for (V3_SuperstructureStates from : coralTransitionLevels) { - CoralEdges.add(new Edge(from, V3_SuperstructureStates.HANDOFF, "Coral Handoff")); - } - - // Coral Prep to Transition - for (V3_SuperstructureStates from : coralPrepLevels) { - for (V3_SuperstructureStates to : coralTransitionLevels) { - CoralEdges.add(new Edge(from, to, "Coral Transition")); - } - } - - // Coral Transition to Prep - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L2_TRANSITION, - V3_SuperstructureStates.L2_PREP, - "Coral Transition L2")); - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L3_TRANSITION, - V3_SuperstructureStates.L3_PREP, - "Coral Transition L3")); - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L4_TRANSITION, - V3_SuperstructureStates.L4_PREP, - "Coral Transition L3")); - - // Prep to score states - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L1_PREP, V3_SuperstructureStates.L1_SCORE, "Coral Score L1")); - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L2_PREP, V3_SuperstructureStates.L2_SCORE, "Coral Score L2")); - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L3_PREP, V3_SuperstructureStates.L3_SCORE, "Coral Score L3")); - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L4_PREP, V3_SuperstructureStates.L4_SCORE, "Coral Score L4")); - - // L1_SCORE -> GROUND_INTAKE - CoralEdges.add( - new Edge( - V3_SuperstructureStates.L1_PREP, - V3_SuperstructureStates.GROUND_INTAKE, - "Coral Transition L1")); - - // Algae Edges - - // STOW_DOWN --> L2_ALGAE_PREP - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.STOW_DOWN, - V3_SuperstructureStates.L2_ALGAE_PREP, - "Algae Prep L2 from STOW DOWN")); - - // Prep --> intake states - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.L2_ALGAE_PREP, - V3_SuperstructureStates.L2_ALGAE_INTAKE, - "Algae Intake L2")); - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.L3_ALGAE_PREP, - V3_SuperstructureStates.L3_ALGAE_INTAKE, - "Algae Intake L3")); - - // Prep <-> Prep States - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.L2_ALGAE_PREP, - V3_SuperstructureStates.L3_ALGAE_PREP, - "Algae Prep L2 to L3")); - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.L3_ALGAE_PREP, - V3_SuperstructureStates.L2_ALGAE_PREP, - "Algae Prep L3 to L2")); - - // BARGE_PREP Edges - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.L2_ALGAE_PREP, - V3_SuperstructureStates.BARGE_PREP, - "Algae Prep Barge to L2")); - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.L3_ALGAE_PREP, - V3_SuperstructureStates.BARGE_PREP, - "Algae Prep Barge to L3")); - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.STOW_UP, - V3_SuperstructureStates.BARGE_PREP, - "Algae Prep L2 to Barge")); - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.BARGE_PREP, - V3_SuperstructureStates.BARGE_SCORE, - "Algae Prep L2 to Barge")); - - // PROCESSOR Edges - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.PROCESSOR_PREP, - V3_SuperstructureStates.PROCESSOR_SCORE, - "Algae Processor L2")); - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.L2_ALGAE_PREP, - V3_SuperstructureStates.PROCESSOR_PREP, - "Algae Processor L2 Prep")); - AlgaeEdges.add( - new Edge( - V3_SuperstructureStates.L3_ALGAE_PREP, - V3_SuperstructureStates.PROCESSOR_PREP, - "Algae Processor L3 Prep")); - - // Unconstrained Edges - - // BARGE_SCORE -> STOW_DOWN - UnconstrainedEdges.add( - new Edge( - V3_SuperstructureStates.BARGE_SCORE, - V3_SuperstructureStates.STOW_DOWN, - "BARGE_SCORE to Stow Down")); - UnconstrainedEdges.add( - new Edge( - V3_SuperstructureStates.BARGE_SCORE, - V3_SuperstructureStates.STOW_UP, - "BARGE_SCORE to Stow Up")); - UnconstrainedEdges.add( - new Edge( - V3_SuperstructureStates.PROCESSOR_SCORE, - V3_SuperstructureStates.STOW_DOWN, - "Algae Processor Barge Prep")); - UnconstrainedEdges.add( - new Edge( - V3_SuperstructureStates.STOW_UP, - V3_SuperstructureStates.STOW_DOWN, - "Algae Processor Barge Prep")); - } -} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java deleted file mode 100644 index 014135c9..00000000 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructurePoses.java +++ /dev/null @@ -1,110 +0,0 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure; - -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; -import frc.robot.FieldConstants.Reef.ReefState; -import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; -import lombok.Getter; - -public class V3_SuperstructurePoses { - private String key; - - @Getter private final ReefState elevatorHeight; - @Getter private final V3_EpsilonManipulatorConstants.PivotState pivotState; - @Getter private final V3_EpsilonIntakeConstants.IntakeState intakeState; - - public V3_SuperstructurePoses(String key, SubsystemPoses poses) { - this.key = key; - - this.elevatorHeight = poses.elevatorHeight(); - this.pivotState = poses.manipulatorArmState(); - this.intakeState = poses.intakeState(); - } - - /** - * Creates a command to set the elevator to the specified height for this pose. - * - * @param elevator - * @return - */ - public Command setElevatorHeight(ElevatorFSM elevator) { - return Commands.parallel( - Commands.runOnce(() -> elevator.setPosition(() -> elevatorHeight)), - elevator.waitUntilAtGoal()); - } - - /** - * Creates a command to set the intake to the specified state for this pose. - * - * @param intake - * @return - */ - public Command setIntakeState(V3_EpsilonIntake intake) { - return Commands.parallel( - Commands.runOnce(() -> intake.setGoal(intakeState)), intake.waitUntilPivotAtGoal()); - } - - /** - * Creates a command to set the manipulator arm to the specified state for this pose. This command - * will also wait until the manipulator arm reaches its goal position. - * - * @param manipulator - * @return - */ - public Command setManipulatorState(V3_EpsilonManipulator manipulator) { - return Commands.parallel( - Commands.runOnce(() -> manipulator.setManipulatorState(pivotState)), - manipulator.waitUntilPivotAtGoal()); - } - - /** - * Creates a command that sets the elevator, manipulator, and intake to their respective states - * defined in this pose. This command runs all three subsystem commands in parallel. - * - * @param elevator - * @param manipulator - * @param intake - * @return - */ - public Command asCommand( - ElevatorFSM elevator, V3_EpsilonManipulator manipulator, V3_EpsilonIntake intake) { - return Commands.parallel( - setElevatorHeight(elevator), setManipulatorState(manipulator), setIntakeState(intake)); - } - - /** - * Returns a string representation of this pose, which is simply the key. This is useful for - * debugging and logging purposes. - * - * @return A string representation of the pose. - */ - public String toString() { - return key; - } - - /** - * A record that holds the states of the subsystems (elevator, manipulator arm, and intake) for a - * specific superstructure pose. This record is used to encapsulate the states of the subsystems - * in a single object, making it easier to manage and pass around. - */ - public record SubsystemPoses( - ReefState elevatorHeight, - V3_EpsilonManipulatorConstants.PivotState manipulatorArmState, - V3_EpsilonIntakeConstants.IntakeState intakeState) { - - /** - * Creates a SubsystemPoses instance with default states (STOW for elevator, arm, and intake; - * OPENED for funnel). - */ - public SubsystemPoses() { - this( - ReefState.STOW, - V3_EpsilonManipulatorConstants.PivotState.STOW_DOWN, - V3_EpsilonIntakeConstants.IntakeState.STOW); - } - } -} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java deleted file mode 100644 index 0205fe6a..00000000 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_SuperstructureStates.java +++ /dev/null @@ -1,288 +0,0 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure; - -// Adjust the package path as needed -import frc.robot.FieldConstants.Reef.ReefState; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructureActions.SubsystemActions; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_SuperstructurePoses.SubsystemPoses; -// Ensure this is the - -// correct package -// path - -public enum V3_SuperstructureStates { - START("START", new SubsystemPoses(), SubsystemActions.empty()), - STOW_DOWN("STOW_DOWN", new SubsystemPoses(), SubsystemActions.empty()), - STOW_UP( - "STOW_UP", - new SubsystemPoses( - ReefState.STOW, - V3_EpsilonManipulatorConstants.PivotState.STOW_UP, - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), - - HANDOFF( - "HANDOFF", - new SubsystemPoses( - ReefState.STOW, - V3_EpsilonManipulatorConstants.PivotState.HANDOFF, - V3_EpsilonIntakeConstants.IntakeState.HANDOFF), - SubsystemActions.empty()), - - GROUND_INTAKE( - "GROUND_INTAKE", - new SubsystemPoses( - ReefState.STOW, - V3_EpsilonManipulatorConstants.PivotState.FLOOR_INTAKE, - V3_EpsilonIntakeConstants.IntakeState.INTAKE_CORAL), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP, - V3_EpsilonIntakeConstants.IntakeRollerStates.CORAL_INTAKE)), - - // Coral Prep States - L1_PREP( - "L1", - new SubsystemPoses( - ReefState.L1, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.L1), - SubsystemActions.empty()), - - L2_PREP( - "L2", - new SubsystemPoses( - ReefState.L2, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), - - L3_PREP( - "L3", - new SubsystemPoses( - ReefState.L3, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), - - L4_PREP( - "L4", - new SubsystemPoses( - ReefState.L4, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), - - // Coral Score States - L1_SCORE( - "L1_SCORE", - new SubsystemPoses( - ReefState.L1, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.L1), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP, - V3_EpsilonIntakeConstants.IntakeRollerStates.SCORE_CORAL)), - - L2_SCORE( - "L2_SCORE", - new SubsystemPoses( - ReefState.L2, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), - - L3_SCORE( - "L3_SCORE", - new SubsystemPoses( - ReefState.L3, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), - - L4_SCORE( - "L4_SCORE", - new SubsystemPoses( - ReefState.L4, - V3_EpsilonManipulatorConstants.PivotState - .PRE_SCORE, // Determine whether PRE_SCORE is accurate for all scoring states - V3_EpsilonIntakeConstants.IntakeState.STOW), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_CORAL, - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), - - // Algae Prep States - L2_ALGAE_PREP( - "L2_ALGAE_PREP", - new SubsystemPoses( - ReefState.L2, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), - - L3_ALGAE_PREP( - "L3_ALGAE_PREP", - new SubsystemPoses( - ReefState.L3, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), - - // Algae Scoring States - L2_ALGAE_INTAKE( - "L2_ALGAE_INTAKE", - new SubsystemPoses( - ReefState.L2, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), - - L3_ALGAE_INTAKE( - "L3_ALGAE_INTAKE", - new SubsystemPoses( - ReefState.L3, - V3_EpsilonManipulatorConstants.PivotState.PRE_SCORE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), - - // Miscelaneous States (Barge + Processor Prep and Score States) - BARGE_PREP( - "BARGE_PREP", - new SubsystemPoses( - ReefState.ALGAE_SCORE, - V3_EpsilonManipulatorConstants.PivotState - .REEF_INTAKE, // Assuming REEF_INTAKE and BARGE_PREP have same rotation values - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), - - PROCESSOR_PREP( - "PROCESSOR_PREP", - new SubsystemPoses( - ReefState.STOW, - V3_EpsilonManipulatorConstants.PivotState.PROCESSOR, - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), - - BARGE_SCORE( - "BARGE_SCORE", - new SubsystemPoses( - ReefState.ALGAE_SCORE, - V3_EpsilonManipulatorConstants.PivotState.REEF_INTAKE, - V3_EpsilonIntakeConstants.IntakeState.STOW), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates - .SCORE_ALGAE, // Assuming you score in the barge by stowing intake and moving - // manipulator to desired position - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), - - PROCESSOR_SCORE( - "PROCESSOR_SCORE", - new SubsystemPoses( - ReefState.ALGAE_SCORE, - V3_EpsilonManipulatorConstants.PivotState.PROCESSOR, - V3_EpsilonIntakeConstants.IntakeState.STOW), - new SubsystemActions( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.SCORE_ALGAE, - V3_EpsilonIntakeConstants.IntakeRollerStates.STOP)), - - INTERMIDIATE_WAIT_FOR_ELEVATOR( - "INTERMIDIATE_WAIT_FOR_ELEVATOR", - new SubsystemPoses( - ReefState.STOW, - V3_EpsilonManipulatorConstants.PivotState.STOW_UP, - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), - - // Transition States - L2_TRANSITION( - "L2_TRANSITION", - new SubsystemPoses( - ReefState.L2, - V3_EpsilonManipulatorConstants.PivotState.TRANSITION, - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), - - L3_TRANSITION( - "L3_TRANSITION", - new SubsystemPoses( - ReefState.L3, - V3_EpsilonManipulatorConstants.PivotState.TRANSITION, - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), - - L4_TRANSITION( - "L4_TRANSITION", - new SubsystemPoses( - ReefState.L4, - V3_EpsilonManipulatorConstants.PivotState.TRANSITION, - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), - - CLIMB( - "CLIMB", - new SubsystemPoses( - ReefState.STOW, - V3_EpsilonManipulatorConstants.PivotState.STOW_UP, - V3_EpsilonIntakeConstants.IntakeState.STOW), - SubsystemActions.empty()), - - OVERRIDE("OVERRIDE", new SubsystemPoses(), SubsystemActions.empty()); - - // Readable name for state - private final String name; - - // Target positions for all subsystems in this state - private final SubsystemPoses subsystemPoses; - - // Actions to perform for all subsystems in this state - private final SubsystemActions subsystemActions; - - /** - * Constructor for V3_SuperstructureStates. - * - * @param name The name of the state. - * @param pose The subsystem poses for this state. - * @param action The subsystem actions for this state. - */ - V3_SuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { - this.name = name; - this.subsystemPoses = pose; - this.subsystemActions = action; - } - - /** - * Constructor for V3_SuperstructureStates with empty actions. - * - * @param name The name of the state. - * @param pose The subsystem poses for this state. - */ - public V3_SuperstructurePoses getPose() { - return new V3_SuperstructurePoses(name, subsystemPoses); - } - - /** - * Returns the actions associated with this superstructure state. - * - * @return The actions for this state. - */ - public V3_SuperstructureActions getAction() { - return new V3_SuperstructureActions(name, subsystemActions); - } - - /** - * Returns the name of the superstructure state. - * - * @return The name of the state. - */ - public String getName() { - return name; - } -} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java new file mode 100644 index 00000000..328db042 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -0,0 +1,104 @@ +package frc.robot.subsystems.v3_Epsilon.superstructure.intake; + +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakePivotState; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakeRollerState; +import lombok.Getter; +import org.littletonrobotics.junction.AutoLogOutput; +import org.littletonrobotics.junction.Logger; + +public class V3_EpsilonIntake { + private final V3_EpsilonIntakeIO io; + private final V3_EpsilonIntakeIOInputsAutoLogged inputs; + // private final SysIdRoutine characterizationRoutine; + + @Getter + @AutoLogOutput(key = "Intake/Pivot Goal") + private IntakePivotState pivotGoal; + + @Getter + @AutoLogOutput(key = "Intake/Roller Goal") + private IntakeRollerState rollerGoal; + + private boolean isClosedLoop; + + public V3_EpsilonIntake(V3_EpsilonIntakeIO io) { + this.io = io; + inputs = new V3_EpsilonIntakeIOInputsAutoLogged(); + + // characterizationRoutine = + // new SysIdRoutine( + // new SysIdRoutine.Config( + // Volts.of(0.2).per(Second), + // Volts.of(3.5), + // Seconds.of(8), + // (state) -> Logger.recordOutput("Intake/SysID State", state.toString())), + // new SysIdRoutine.Mechanism((volts) -> io.setPivotVoltage(volts.in(Volts)), null, + // this)); + + pivotGoal = IntakePivotState.STOW; + rollerGoal = IntakeRollerState.STOP; + + isClosedLoop = true; + } + + public void periodic() { + io.updateInputs(inputs); + Logger.processInputs("Intake", inputs); + + if (isClosedLoop) { + io.setPivotGoal(pivotGoal.getAngle()); + } + } + + @AutoLogOutput(key = "Intake/Has Coral") + public boolean hasCoral() { + return false; // Udpate later + } + + @AutoLogOutput(key = "Intake/At Goal") + public boolean atGoal() { + return Math.abs(inputs.pivotPosition.getRadians() - pivotGoal.getAngle().getRadians()) + < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); + } + + public void setPivotGoal(IntakePivotState goal) { + isClosedLoop = true; + this.pivotGoal = goal; + } + + public void setRollerVoltage(double volts) { + io.setRollerVoltage(volts); + } + + public void setPivotVoltage(double volts) { + isClosedLoop = false; + io.setPivotVoltage(volts); + } + + public Command waitUntilPivotAtGoal() { + return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::atGoal)); + } + + public Command sysIdRoutine() { + return Commands.sequence(); + // Commands.runOnce(() -> isClosedLoop = false), + // Commands.runOnce(() -> characterizationRoutine.quasistatic(Direction.kForward)), + // Commands.waitSeconds(0.25), + // Commands.runOnce(() -> characterizationRoutine.quasistatic(Direction.kReverse)), + // Commands.waitSeconds(0.25), + // Commands.runOnce(() -> characterizationRoutine.dynamic(Direction.kForward)), + // Commands.waitSeconds(0.25), + // Commands.runOnce(() -> characterizationRoutine.dynamic(Direction.kReverse))); + } + + public void setRollerGoal(IntakeRollerState rollerGoal) { + this.rollerGoal = rollerGoal; + } + + public Rotation2d getPivotAngle() { + return inputs.pivotPosition; + } +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java similarity index 93% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index a9cea76e..d776e16a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.intake; +package frc.robot.subsystems.v3_Epsilon.superstructure.intake; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.system.plant.DCMotor; @@ -35,7 +35,7 @@ public class V3_EpsilonIntakeConstants { } @RequiredArgsConstructor - public enum IntakeState { + public enum IntakePivotState { STOW(new Rotation2d()), INTAKE_CORAL(new Rotation2d()), HANDOFF(new Rotation2d(Units.degreesToRadians(90))), @@ -71,7 +71,7 @@ public static record IntakeParems( Rotation2d MAX_ANGLE) {} // Will add more states later - public static enum IntakeRollerStates { + public static enum IntakeRollerState { STOP(0.0), CORAL_INTAKE(6.0), ALGAE_INTAKE(12.0), @@ -79,7 +79,7 @@ public static enum IntakeRollerStates { private final double voltage; - IntakeRollerStates(double voltage) { + IntakeRollerState(double voltage) { this.voltage = voltage; } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java similarity index 89% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java index 595fd338..9b37862b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java @@ -1,11 +1,11 @@ -package frc.robot.subsystems.v3_Epsilon.intake; +package frc.robot.subsystems.v3_Epsilon.superstructure.intake; import edu.wpi.first.math.geometry.Rotation2d; import org.littletonrobotics.junction.AutoLog; public interface V3_EpsilonIntakeIO { @AutoLog - public static class IntakeIOInputs { + public static class V3_EpsilonIntakeIOInputs { public Rotation2d pivotPosition = new Rotation2d(); public double pivotVelocityRadiansPerSecond = 0.0; public double pivotAppliedVolts = 0.0; @@ -30,7 +30,7 @@ public static class IntakeIOInputs { * * @param inputs The inputs to update. */ - public default void updateInputs(IntakeIOInputs inputs) {} + public default void updateInputs(V3_EpsilonIntakeIOInputs inputs) {} /** * Sets the voltage for the intake. @@ -51,7 +51,7 @@ public default void setRollerVoltage(double volts) {} * * @param meters The position goal to set in meters. */ - public default void setPivotGoal(Rotation2d rotatoion) {} + public default void setPivotGoal(Rotation2d rotation) {} /** * Sets the gains for the intake diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java similarity index 97% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOSim.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java index dd44389b..a1a99415 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.intake; +package frc.robot.subsystems.v3_Epsilon.superstructure.intake; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.ArmFeedforward; @@ -66,7 +66,7 @@ public V3_EpsilonIntakeIOSim() { } @Override - public void updateInputs(IntakeIOInputs inputs) { + public void updateInputs(V3_EpsilonIntakeIOInputs inputs) { if (isClosedLoop) { pivotAppliedVoltage = armFeedbackController.calculate(pivotMotorSim.getAngleRads()) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java similarity index 98% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java index 9e29b2e2..b9b0ef50 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.intake; +package frc.robot.subsystems.v3_Epsilon.superstructure.intake; import static edu.wpi.first.units.Units.RadiansPerSecond; import static edu.wpi.first.units.Units.RadiansPerSecondPerSecond; @@ -153,7 +153,7 @@ public V3_EpsilonIntakeIOTalonFX() { } @Override - public void updateInputs(IntakeIOInputs inputs) { + public void updateInputs(V3_EpsilonIntakeIOInputs inputs) { inputs.pivotPosition = new Rotation2d(pivotPositionRotations.getValue()); inputs.pivotVelocityRadiansPerSecond = pivotVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java similarity index 65% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 277f9afe..361a49ee 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -1,26 +1,22 @@ -package frc.robot.subsystems.v3_Epsilon.manipulator; - -import static edu.wpi.first.units.Units.*; +package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; -import edu.wpi.first.wpilibj2.command.SubsystemBase; -import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; -import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants.PivotState; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import java.util.Set; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; -public class V3_EpsilonManipulator extends SubsystemBase { +public class V3_EpsilonManipulator { private final V3_EpsilonManipulatorIO io; private final ManipulatorIOInputsAutoLogged inputs; - private final SysIdRoutine algaeCharacterizationRoutine; + // private final SysIdRoutine algaeCharacterizationRoutine; - private PivotState state; + private ManipulatorArmState state; private boolean isClosedLoop; public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { @@ -28,25 +24,25 @@ public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { inputs = new ManipulatorIOInputsAutoLogged(); isClosedLoop = true; - algaeCharacterizationRoutine = - new SysIdRoutine( - new SysIdRoutine.Config( - Volts.of(0.2).per(Second), - Volts.of(3.5), - Seconds.of(5), - (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), - new SysIdRoutine.Mechanism((volts) -> io.setPivotVoltage(volts.in(Volts)), null, this)); - state = PivotState.STOW_DOWN; - } - - @Override + // algaeCharacterizationRoutine = + // new SysIdRoutine( + // new SysIdRoutine.Config( + // Volts.of(0.2).per(Second), + // Volts.of(3.5), + // Seconds.of(5), + // (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), + // new SysIdRoutine.Mechanism((volts) -> io.setArmVoltage(volts.in(Volts)), null, + // this)); + state = ManipulatorArmState.STOW_DOWN; + } + public void periodic() { io.updateInputs(inputs); Logger.processInputs("Manipulator", inputs); if (isClosedLoop) { setSlot(); - io.setPivotGoal(state.getAngle()); + io.setArmGoal(state.getAngle()); } if (hasAlgae()) { @@ -66,29 +62,29 @@ public boolean hasAlgae() { && inputs.canRangeDistanceMeters > 0; } - public Command runPivot(double volts) { - return this.runEnd( + public Command runArm(double volts) { + return Commands.runEnd( () -> { isClosedLoop = false; - io.setPivotVoltage(volts); + io.setArmVoltage(volts); }, - () -> io.setPivotVoltage(0)); + () -> io.setArmVoltage(0)); } public Command sysIdRoutine() { - return Commands.sequence( - Commands.runOnce(() -> isClosedLoop = false), - algaeCharacterizationRoutine.quasistatic(Direction.kForward), - Commands.waitSeconds(.25), - algaeCharacterizationRoutine.quasistatic(Direction.kReverse), - Commands.waitSeconds(.25), - algaeCharacterizationRoutine.dynamic(Direction.kForward), - Commands.waitSeconds(.25), - algaeCharacterizationRoutine.dynamic(Direction.kReverse)); - } - - public Command setPivotGoal(PivotState goal) { - return this.runOnce( + return Commands.sequence(); + // Commands.runOnce(() -> isClosedLoop = false), + // algaeCharacterizationRoutine.quasistatic(Direction.kForward), + // Commands.waitSeconds(.25), + // algaeCharacterizationRoutine.quasistatic(Direction.kReverse), + // Commands.waitSeconds(.25), + // algaeCharacterizationRoutine.dynamic(Direction.kForward), + // Commands.waitSeconds(.25), + // algaeCharacterizationRoutine.dynamic(Direction.kReverse)); + } + + public Command setArmGoal(ManipulatorArmState goal) { + return Commands.runOnce( () -> { isClosedLoop = true; state = goal; @@ -124,13 +120,13 @@ public void updateArmConstraints(double maxAcceleration, double maxVelocity) { } @AutoLogOutput(key = "Manipulator/Arm At Goal") - public boolean pivotAtGoal() { + public boolean armAtGoal() { return inputs.armPosition.getRadians() - state.getAngle().getRadians() <= V2_RedundancyManipulatorConstants.CONSTRAINTS.GOAL_TOLERANCE_RADIANS().get(); } - public Command waitUntilPivotAtGoal() { - return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::pivotAtGoal)); + public Command waitUntilArmAtGoal() { + return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::armAtGoal)); } private double holdVoltage() { @@ -157,16 +153,16 @@ public void setSlot() { } } - public void setManipulatorState(V3_EpsilonManipulatorConstants.PivotState state) { + public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmState state) { io.setManipulatorState(state); } - public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerStates rollerGoal) { + public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState rollerGoal) { if (hasAlgae() && Set.of( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.ALGAE_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.CORAL_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP) + V3_EpsilonManipulatorConstants.ManipulatorRollerState.ALGAE_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerState.CORAL_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerState.STOP) .contains(rollerGoal)) { io.setRollerVoltage(holdVoltage()); @@ -174,4 +170,8 @@ public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerStates io.setRollerVoltage(rollerGoal.getVoltage()); } } + + public Rotation2d getArmAngle() { + return inputs.armPosition; + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java similarity index 93% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index ac60ffd0..9a915084 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.manipulator; +package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; import com.ctre.phoenix6.configs.SlotConfigs; import com.ctre.phoenix6.signals.GravityTypeValue; @@ -22,8 +22,8 @@ public class V3_EpsilonManipulatorConstants { public static final ManipulatorCurrentLimits CURRENT_LIMITS; - public static final int PIVOT_CAN_ID = 42; - public static final Rotation2d PIVOT_TOGGLE_ARM_ROTATION; + public static final int ARM_CAN_ID = 42; + public static final Rotation2d TOGGLE_ARM_ROTATION; public static final int CAN_RANGE_ID = 41; @@ -85,7 +85,7 @@ public class V3_EpsilonManipulatorConstants { CURRENT_LIMITS = new ManipulatorCurrentLimits(40, 40, 40, 40); - PIVOT_TOGGLE_ARM_ROTATION = new Rotation2d(); + TOGGLE_ARM_ROTATION = new Rotation2d(); } public static record Gains( @@ -137,9 +137,10 @@ public static record ArmParameters( double LENGTH_METERS) {} @RequiredArgsConstructor - public static enum PivotState { + public static enum ManipulatorArmState { STOW_UP(Rotation2d.fromDegrees(75)), PRE_SCORE(Rotation2d.fromDegrees(50.0)), + SCORE(Rotation2d.fromDegrees(35.0)), // Placeholder value. Make sure to test PROCESSOR(Rotation2d.fromDegrees(-61.279296875 + 20)), REEF_INTAKE(Rotation2d.fromDegrees(-61.279296875 + 15)), INTAKE_OUT_LINE(Rotation2d.fromDegrees(-61)), @@ -157,7 +158,7 @@ public Rotation2d getAngle() { } // Will add more states later - public static enum ManipulatorRollerStates { + public static enum ManipulatorRollerState { STOP(0.0), CORAL_INTAKE(6.0), ALGAE_INTAKE(12.0), @@ -169,7 +170,7 @@ public static enum ManipulatorRollerStates { private final double voltage; - ManipulatorRollerStates(double voltage) { + ManipulatorRollerState(double voltage) { this.voltage = voltage; } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java similarity index 88% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java index 2627908e..2967a0df 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.manipulator; +package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; import edu.wpi.first.math.geometry.Rotation2d; import org.littletonrobotics.junction.AutoLog; @@ -40,13 +40,14 @@ public default void updateInputs(ManipulatorIOInputs inputs) {} * * @param volts The voltage to set. */ - public default void setPivotVoltage(double volts) {} + public default void setArmVoltage(double volts) {} public default void setRollerVoltage(double volts) {} - public default void setPivotGoal(Rotation2d rotation) {} + public default void setArmGoal(Rotation2d rotation) {} - public default void setManipulatorState(V3_EpsilonManipulatorConstants.PivotState state) {} + public default void setManipulatorState( + V3_EpsilonManipulatorConstants.ManipulatorArmState state) {} /** * Sets the gains for the arm. diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java similarity index 97% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java index d353faf7..8098343e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.manipulator; +package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.ArmFeedforward; @@ -134,7 +134,7 @@ public void updateInputs(ManipulatorIOInputs inputs) { inputs.rollerSupplyCurrentAmps = rollerMotorSim.getCurrentDrawAmps(); } - public void setPivotVoltage(double volts) { + public void setArmVoltage(double volts) { isClosedLoop = false; armAppliedVolts = volts; } @@ -143,7 +143,7 @@ public void setRollerVoltage(double volts) { rollerAppliedVolts = volts; } - public void setPivotGoal(Rotation2d rotation) { + public void setArmGoal(Rotation2d rotation) { isClosedLoop = true; armFeedbackController.setGoal(rotation.getRadians()); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java similarity index 56% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java index bd6fa35e..25b3db39 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.manipulator; +package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; import static edu.wpi.first.units.Units.RadiansPerSecond; import static frc.robot.util.PhoenixUtil.*; @@ -20,24 +20,23 @@ import edu.wpi.first.units.measure.Current; import edu.wpi.first.units.measure.Temperature; import edu.wpi.first.units.measure.Voltage; -// import frc.robot.subsystems.v1_StackUp.manipulator.V3_EpsilonManipulatorConstants; public class V3_EpsilonManipulatorIOTalonFX implements V3_EpsilonManipulatorIO { - private final TalonFX pivotTalonFX; - private final StatusSignal pivotPositionRotations; - private final StatusSignal pivotVelocityRotationsPerSecond; - private final StatusSignal pivotAppliedVoltage; - private final StatusSignal pivotSupplyCurrentAmps; - private final StatusSignal pivotTorqueCurrentAmps; - private final StatusSignal pivotTemperatureCelsius; - private final StatusSignal pivotPositionSetpointRotations; - private final StatusSignal pivotPositionErrorRotations; + private final TalonFX armTalonFX; + private final StatusSignal armPositionRotations; + private final StatusSignal armVelocityRotationsPerSecond; + private final StatusSignal armAppliedVoltage; + private final StatusSignal armSupplyCurrentAmps; + private final StatusSignal armTorqueCurrentAmps; + private final StatusSignal armTemperatureCelsius; + private final StatusSignal armPositionSetpointRotations; + private final StatusSignal armPositionErrorRotations; - private final VoltageOut pivotVoltageRequest; - private final MotionMagicVoltage pivotMotionMagicRequest; + private final VoltageOut armVoltageRequest; + private final MotionMagicVoltage armMotionMagicRequest; - private final TalonFXConfiguration pivotConfig; + private final TalonFXConfiguration armConfig; private final TalonFX rollerTalonFX; private final StatusSignal rollerPositionRotations; @@ -51,36 +50,36 @@ public class V3_EpsilonManipulatorIOTalonFX implements V3_EpsilonManipulatorIO { private final TalonFXConfiguration rollerConfig; public V3_EpsilonManipulatorIOTalonFX() { - pivotTalonFX = new TalonFX(V3_EpsilonManipulatorConstants.PIVOT_CAN_ID); + armTalonFX = new TalonFX(V3_EpsilonManipulatorConstants.ARM_CAN_ID); rollerTalonFX = new TalonFX(V3_EpsilonManipulatorConstants.ROLLER_CAN_ID); - pivotConfig = new TalonFXConfiguration(); + armConfig = new TalonFXConfiguration(); - pivotConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; - pivotConfig.CurrentLimits.SupplyCurrentLimit = + armConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; + armConfig.CurrentLimits.SupplyCurrentLimit = V3_EpsilonManipulatorConstants.CURRENT_LIMITS.MANIPULATOR_SUPPLY_CURRENT_LIMIT(); - pivotConfig.CurrentLimits.SupplyCurrentLimitEnable = true; - pivotConfig.Feedback.SensorToMechanismRatio = + armConfig.CurrentLimits.SupplyCurrentLimitEnable = true; + armConfig.Feedback.SensorToMechanismRatio = V3_EpsilonManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO(); - pivotConfig.Slot0 = + armConfig.Slot0 = Slot0Configs.from(V3_EpsilonManipulatorConstants.EMPTY_GAINS.toTalonFXSlotConfigs()); - pivotConfig.Slot1 = + armConfig.Slot1 = Slot1Configs.from(V3_EpsilonManipulatorConstants.CORAL_GAINS.toTalonFXSlotConfigs()); - pivotConfig.Slot2 = + armConfig.Slot2 = Slot2Configs.from(V3_EpsilonManipulatorConstants.ALGAE_GAINS.toTalonFXSlotConfigs()); - pivotConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; + armConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; - tryUntilOk(5, () -> pivotTalonFX.getConfigurator().apply(pivotConfig, 0.25)); + tryUntilOk(5, () -> armTalonFX.getConfigurator().apply(armConfig, 0.25)); - pivotPositionRotations = pivotTalonFX.getPosition(); - pivotVelocityRotationsPerSecond = pivotTalonFX.getVelocity(); - pivotAppliedVoltage = pivotTalonFX.getMotorVoltage(); - pivotSupplyCurrentAmps = pivotTalonFX.getSupplyCurrent(); - pivotTorqueCurrentAmps = pivotTalonFX.getTorqueCurrent(); - pivotTemperatureCelsius = pivotTalonFX.getDeviceTemp(); + armPositionRotations = armTalonFX.getPosition(); + armVelocityRotationsPerSecond = armTalonFX.getVelocity(); + armAppliedVoltage = armTalonFX.getMotorVoltage(); + armSupplyCurrentAmps = armTalonFX.getSupplyCurrent(); + armTorqueCurrentAmps = armTalonFX.getTorqueCurrent(); + armTemperatureCelsius = armTalonFX.getDeviceTemp(); - pivotPositionSetpointRotations = pivotTalonFX.getClosedLoopReference(); - pivotPositionErrorRotations = pivotTalonFX.getClosedLoopError(); + armPositionSetpointRotations = armTalonFX.getClosedLoopReference(); + armPositionErrorRotations = armTalonFX.getClosedLoopError(); rollerConfig = new TalonFXConfiguration(); rollerConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; @@ -98,17 +97,17 @@ public V3_EpsilonManipulatorIOTalonFX() { rollerTemperatureCelsius = rollerTalonFX.getDeviceTemp(); rollerVoltageRequest = new VoltageOut(0); - pivotVoltageRequest = new VoltageOut(0); - pivotMotionMagicRequest = new MotionMagicVoltage(0); + armVoltageRequest = new VoltageOut(0); + armMotionMagicRequest = new MotionMagicVoltage(0); registerSignals( false, - pivotPositionRotations, - pivotVelocityRotationsPerSecond, - pivotAppliedVoltage, - pivotSupplyCurrentAmps, - pivotTorqueCurrentAmps, - pivotTemperatureCelsius, + armPositionRotations, + armVelocityRotationsPerSecond, + armAppliedVoltage, + armSupplyCurrentAmps, + armTorqueCurrentAmps, + armTemperatureCelsius, rollerPositionRotations, rollerVelocityRotationsPerSecond, rollerAppliedVoltage, @@ -116,20 +115,20 @@ public V3_EpsilonManipulatorIOTalonFX() { rollerTorqueCurrentAmps, rollerTemperatureCelsius); - pivotTalonFX.optimizeBusUtilization(); + armTalonFX.optimizeBusUtilization(); rollerTalonFX.optimizeBusUtilization(); } @Override public void updateInputs(ManipulatorIOInputs inputs) { - inputs.armPosition = new Rotation2d(pivotPositionRotations.getValue()); + inputs.armPosition = new Rotation2d(armPositionRotations.getValue()); inputs.armVelocityRadiansPerSecond = - pivotVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); - inputs.armAppliedVolts = pivotAppliedVoltage.getValueAsDouble(); - inputs.armSupplyCurrentAmps = pivotSupplyCurrentAmps.getValueAsDouble(); - inputs.armTorqueCurrentAmps = pivotTorqueCurrentAmps.getValueAsDouble(); - inputs.armTemperatureCelsius = pivotTemperatureCelsius.getValueAsDouble(); + armVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); + inputs.armAppliedVolts = armAppliedVoltage.getValueAsDouble(); + inputs.armSupplyCurrentAmps = armSupplyCurrentAmps.getValueAsDouble(); + inputs.armTorqueCurrentAmps = armTorqueCurrentAmps.getValueAsDouble(); + inputs.armTemperatureCelsius = armTemperatureCelsius.getValueAsDouble(); inputs.rollerPosition = new Rotation2d(rollerPositionRotations.getValue()); inputs.rollerVelocityRadiansPerSecond = @@ -139,16 +138,16 @@ public void updateInputs(ManipulatorIOInputs inputs) { inputs.rollerTorqueCurrentAmps = rollerTorqueCurrentAmps.getValueAsDouble(); inputs.rollerTemperatureCelsius = rollerTemperatureCelsius.getValueAsDouble(); - inputs.armPositionGoal = new Rotation2d(pivotMotionMagicRequest.getPositionMeasure()); + inputs.armPositionGoal = new Rotation2d(armMotionMagicRequest.getPositionMeasure()); inputs.armPositionSetpoint = - Rotation2d.fromRotations(pivotPositionSetpointRotations.getValueAsDouble()); + Rotation2d.fromRotations(armPositionSetpointRotations.getValueAsDouble()); inputs.armPositionError = - Rotation2d.fromRotations(pivotPositionErrorRotations.getValueAsDouble()); + Rotation2d.fromRotations(armPositionErrorRotations.getValueAsDouble()); } @Override - public void setPivotVoltage(double volts) { - pivotTalonFX.setControl(pivotVoltageRequest.withOutput(volts).withEnableFOC(true)); + public void setArmVoltage(double volts) { + armTalonFX.setControl(armVoltageRequest.withOutput(volts).withEnableFOC(true)); } @Override @@ -157,15 +156,15 @@ public void setRollerVoltage(double volts) { } @Override - public void setPivotGoal(Rotation2d rotation) { - pivotTalonFX.setControl( - pivotMotionMagicRequest.withPosition(rotation.getRotations()).withEnableFOC(true)); + public void setArmGoal(Rotation2d rotation) { + armTalonFX.setControl( + armMotionMagicRequest.withPosition(rotation.getRotations()).withEnableFOC(true)); } @Override public void setSlot(int slot) { if (slot >= 0 && slot <= 2) { - pivotTalonFX.setControl(pivotMotionMagicRequest.withSlot(slot)); + armTalonFX.setControl(armMotionMagicRequest.withSlot(slot)); } else { throw new IllegalArgumentException("Invalid slot: " + slot); } From dd0f296f7c2696e42dd2ea0141292dacaee4dcf9 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Sat, 30 Aug 2025 21:22:11 -0400 Subject: [PATCH 052/180] Fixed auto implementations for V3 Robot Container. Still some more errors --- src/main/java/frc/robot/Constants.java | 2 +- .../robot/commands/AutonomousCommands.java | 2739 +++++++++-------- .../frc/robot/commands/CompositeCommands.java | 6 +- .../subsystems/shared/elevator/Elevator.java | 2 + .../v3_Epsilon/V3_EpsilonRobotContainer.java | 14 +- .../manipulator/V3_EpsilonManipulator.java | 2 + 6 files changed, 1387 insertions(+), 1378 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 7a11b629..d181f165 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -47,8 +47,8 @@ public static enum RobotType { V1_STACKUP_SIM, V2_REDUNDANCY, V2_REDUNDANCY_SIM, - V3_EPSILON_SIM, V3_EPSILON, + V3_EPSILON_SIM } public static void main(String... args) { diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index 0c267ced..d470fd79 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -23,11 +23,16 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.util.AllianceFlipUtil; import frc.robot.util.LoggedChoreo.LoggedAutoRoutine; import frc.robot.util.LoggedChoreo.LoggedAutoTrajectory; import java.util.Optional; +import javax.management.openmbean.CompositeType; + public class AutonomousCommands { private static Optional> A_LEFT_PATH1; private static Optional> A_RIGHT_PATH1; @@ -402,1384 +407,1386 @@ public static final Command autoDCenter( V1_StackUpCompositeCommands.twerk(drive, elevator, manipulator, cameras)); } - // V2 - // V2 - // V2 - // V2 - // V2 - // V2 - // V2 - // V2 - // V2 - // V2 - - public static final LoggedAutoRoutine autoALeft( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeft"); - - LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_LEFT_PATH4") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path3.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path4.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoALeftNashoba( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftNashoba"); - - LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_LEFT_PATH_ALT3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_LEFT_PATH_ALT4") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path3.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path4.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoALeftDAVE( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftD.A.V.E."); - - LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_LEFT_PATH4_ALT_ALT") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path3.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path4.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoARight( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoARight"); - - LoggedAutoTrajectory path1 = routine.trajectory("A_RIGHT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_RIGHT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_RIGHT_PATH4") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.25), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.25), - Commands.deadline( - path3.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.25), - Commands.deadline( - path4.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoBLeft( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBLeft"); - LoggedAutoTrajectory path1 = - routine - .trajectory("B_LEFT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("B_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN))); - - return routine; - } - - public static final LoggedAutoRoutine autoCLeft( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_LEFT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path3.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoCLeftPush( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_LEFT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), - () -> drive.stop()) - .withTimeout(0.5), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path3.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoCRight( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_RIGHT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_RIGHT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path3.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); - return routine; - } - - public static final LoggedAutoRoutine autoCRightPush( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_RIGHT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_RIGHT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, 1.0, 0.0)), - () -> drive.stop()) - .withTimeout(0.5), - path1.cmd(), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path3.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); - return routine; - } - - public static final LoggedAutoRoutine autoBRight( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBRight"); - LoggedAutoTrajectory path1 = - routine - .trajectory("B_RIGHT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("B_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN))); - - return routine; - } - - public static final LoggedAutoRoutine autoDCenter( - Drive drive, V2_RedundancySuperstructure superstructure, Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoDCenter"); - LoggedAutoTrajectory path1 = - routine - .trajectory("D_CENTER_PATH") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); - return routine; - } - - // V3 - // V3 - // V3 - // V3 - // V3 - // V3 - // V3 - // V3 - // V3 - // V3 - // V3 - //TODO: Make sure superstructure states are correct + // V2 + + public static final LoggedAutoRoutine autoALeft( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeft"); + + LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_LEFT_PATH4") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path3.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path4.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoALeftNashoba( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftNashoba"); + + LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_LEFT_PATH_ALT3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_LEFT_PATH_ALT4") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path3.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path4.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoALeftDAVE( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftD.A.V.E."); + + LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_LEFT_PATH4_ALT_ALT") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path3.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path4.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoARight( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoARight"); + + LoggedAutoTrajectory path1 = routine.trajectory("A_RIGHT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_RIGHT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_RIGHT_PATH4") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.25), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.25), + Commands.deadline( + path3.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.25), + Commands.deadline( + path4.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoBLeft( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBLeft"); + LoggedAutoTrajectory path1 = + routine + .trajectory("B_LEFT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("B_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN))); + + return routine; + } + + public static final LoggedAutoRoutine autoCLeft( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_LEFT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path3.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoCLeftPush( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_LEFT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), + () -> drive.stop()) + .withTimeout(0.5), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path3.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoCRight( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_RIGHT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_RIGHT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path3.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); + return routine; + } + + public static final LoggedAutoRoutine autoCRightPush( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_RIGHT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_RIGHT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, 1.0, 0.0)), + () -> drive.stop()) + .withTimeout(0.5), + path1.cmd(), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path3.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); + return routine; + } + + public static final LoggedAutoRoutine autoBRight( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBRight"); + LoggedAutoTrajectory path1 = + routine + .trajectory("B_RIGHT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("B_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN))); + + return routine; + } + + public static final LoggedAutoRoutine autoDCenter( + Drive drive, V2_RedundancySuperstructure superstructure, Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoDCenter"); + LoggedAutoTrajectory path1 = + routine + .trajectory("D_CENTER_PATH") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); + return routine; + } + + // V3 public static final LoggedAutoRoutine autoALeft( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeft"); - - LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_LEFT_PATH4") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path2.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path3.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path4.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoALeftNashoba( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftNashoba"); - - LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_LEFT_PATH_ALT3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_LEFT_PATH_ALT4") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path2.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path3.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path4.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoALeftDAVE( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftD.A.V.E."); - - LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_LEFT_PATH4_ALT_ALT") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path2.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path3.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path4.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoARight( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoARight"); - - LoggedAutoTrajectory path1 = routine.trajectory("A_RIGHT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_RIGHT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_RIGHT_PATH4") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.25), - Commands.deadline( - path2.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.25), - Commands.deadline( - path3.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.25), - Commands.deadline( - path4.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoBLeft( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBLeft"); - LoggedAutoTrajectory path1 = - routine - .trajectory("B_LEFT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("B_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path2.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); - - return routine; - } + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeft"); + + LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_LEFT_PATH4") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path3.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path4.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5))); + + return routine; +} - public static final LoggedAutoRoutine autoCLeft( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { +public static final LoggedAutoRoutine autoALeftNashoba( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftNashoba"); + + LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_LEFT_PATH_ALT3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_LEFT_PATH_ALT4") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path3.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path4.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5))); + + return routine; +} - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_LEFT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path2.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path3.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); - - return routine; - } +public static final LoggedAutoRoutine autoALeftDAVE( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftD.A.V.E."); + + LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_LEFT_PATH4_ALT_ALT") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path3.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path4.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5))); + + return routine; +} - public static final LoggedAutoRoutine autoCLeftPush( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { +public static final LoggedAutoRoutine autoARight( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoARight"); + + LoggedAutoTrajectory path1 = routine.trajectory("A_RIGHT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_RIGHT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_RIGHT_PATH4") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.25), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.25), + Commands.deadline( + path3.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.25), + Commands.deadline( + path4.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); + + return routine; +} - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_LEFT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), - () -> drive.stop()) - .withTimeout(0.5), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path2.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path3.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); - - return routine; - } +public static final LoggedAutoRoutine autoBLeft( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBLeft"); + LoggedAutoTrajectory path1 = + routine + .trajectory("B_LEFT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("B_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); + + return routine; +} - public static final LoggedAutoRoutine autoCRight( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { +public static final LoggedAutoRoutine autoCLeft( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_LEFT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path3.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); + + return routine; +} - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_RIGHT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_RIGHT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path2.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path3.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); - return routine; - } +public static final LoggedAutoRoutine autoCLeftPush( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_LEFT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), + () -> drive.stop()) + .withTimeout(0.5), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path3.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); + + return routine; +} - public static final LoggedAutoRoutine autoCRightPush( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { +public static final LoggedAutoRoutine autoCRight( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_RIGHT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_RIGHT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path3.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); + return routine; +} - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_RIGHT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_RIGHT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, 1.0, 0.0)), - () -> drive.stop()) - .withTimeout(0.5), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path2.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path3.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); - return routine; - } +public static final LoggedAutoRoutine autoCRightPush( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_RIGHT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_RIGHT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, 1.0, 0.0)), + () -> drive.stop()) + .withTimeout(0.5), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path3.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); + return routine; +} - public static final LoggedAutoRoutine autoBRight( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { +public static final LoggedAutoRoutine autoBRight( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBRight"); + LoggedAutoTrajectory path1 = + routine + .trajectory("B_RIGHT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("B_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); + + return routine; +} - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBRight"); - LoggedAutoTrajectory path1 = - routine - .trajectory("B_RIGHT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("B_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path2.cmd(), - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); - - return routine; - } +public static final LoggedAutoRoutine autoDCenter( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoDCenter"); + LoggedAutoTrajectory path1 = + routine + .trajectory("D_CENTER_PATH") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); + return routine; +} - public static final LoggedAutoRoutine autoDCenter( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoDCenter"); - LoggedAutoTrajectory path1 = - routine - .trajectory("D_CENTER_PATH") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); - return routine; - } } diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 34245d10..7fc6f845 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -667,7 +667,7 @@ public static final Command intakeCoralDriverSequence( return Commands.sequence( Commands.runOnce(() -> RobotState.setHasAlgae(false)), superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), + V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoral()), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); } @@ -682,7 +682,7 @@ public static final Command intakeCoralOperatorSequence( V3_EpsilonSuperstructure superstructure, V3_EpsilonIntake intake) { return Commands.sequence( superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), + V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoral()), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); } @@ -696,7 +696,7 @@ public static final Command intakeCoralOperatorSequence( public static final Command scoreL1Coral( Drive drive, V3_EpsilonSuperstructure superstructure) { return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.L1), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L1_PREP), Commands.parallel( superstructure.runReefScoreGoal(() -> ReefState.L1), Commands.sequence( diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java index 113a5116..766875b5 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java @@ -16,6 +16,8 @@ import frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions; import frc.robot.subsystems.shared.elevator.ElevatorIO.ElevatorIOInputs; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 8df1048c..1f2fe127 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -64,7 +64,6 @@ public class V3_EpsilonRobotContainer implements RobotContainer { private Climber climber; private Drive drive; private ElevatorFSM elevator; - private FunnelFSM funnel; private Vision vision; private V3_EpsilonIntake intake; // private V3_EpsilonLEDs leds; @@ -115,7 +114,6 @@ public V3_EpsilonRobotContainer() { break; default: break; - } if (drive == null) { drive = @@ -131,13 +129,10 @@ public V3_EpsilonRobotContainer() { }, new ModuleIO() { }); - } if (elevator == null) { elevator = new Elevator(new ElevatorIO() {}).getFSM(); } - if (funnel == null) { - funnel = new Funnel(new FunnelIO() {}).getFSM(); - } + if (intake == null) { intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); } @@ -154,6 +149,8 @@ public V3_EpsilonRobotContainer() { configureButtonBindings(); } +} + } } public void configureButtonBindings() { @@ -340,7 +337,8 @@ public void configureButtonBindings() { // V3_EpsilonSuperstructureStates.STOW_DOWN), // () -> RobotState.isHasAlgae())) // .onFalse(superstructure.runPreviousState()); -} + } + private void configureAutos() { AutonomousCommands.loadAutoTrajectories(drive); @@ -442,10 +440,10 @@ private void configureAutos() { // funnel.getAngle(), // manipulator.getArmAngle(), // intake.getExtension())); +// } @Override public Command getAutonomousCommand() { return autoChooser.selectedCommand(); } -} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java index cc82cf2a..be462602 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java @@ -11,6 +11,7 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants.PivotState; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; + import java.util.Set; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; @@ -76,6 +77,7 @@ public Command runPivot(double volts) { () -> io.setPivotVoltage(0)); } + public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { return Commands.sequence( Commands.runOnce(() -> isClosedLoop = false), From 9491a3e0e31fcad27c3a36190abe3ac94f47c639 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Sat, 30 Aug 2025 21:28:19 -0400 Subject: [PATCH 053/180] need to fix state machine --- .../shared/elevator/ElevatorConstants.java | 2 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 4 +- .../superstructure/Superstructure.dot | 3 +- .../V3_EpsilonSuperstructure.java | 4 +- .../V3_EpsilonSuperstructureEdges.java | 238 ------------------ .../V3_EpsilonSuperstructurePose.java | 5 +- .../V3_EpsilonSuperstructureStates.java | 4 +- .../intake/V3_EpsilonIntake.java | 23 -- .../intake/V3_EpsilonIntakeConstants.java | 2 +- .../intake/V3_EpsilonIntakeIOSim.java | 2 +- .../manipulator/V3_EpsilonManipulator.java | 26 +- .../V3_EpsilonManipulatorConstants.java | 18 +- .../V3_EpsilonManipulatorIOSim.java | 9 +- 13 files changed, 28 insertions(+), 312 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index 75c0ab18..44cb9ef9 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -222,7 +222,7 @@ public static enum ElevatorPositions { CORAL_INTAKE(0.0), ALGAE_INTAKE(0.2161583093038944 + Units.inchesToMeters(1)), ALGAE_MID(0.7073684509805078), - HANDOFF(0.7073684509805078), + HANDOFF(1), ALGAE_INTAKE_TOP(1.17 - Units.inchesToMeters(8)), ALGAE_INTAKE_BOT(0.79 - Units.inchesToMeters(8)), ASS_TOP(1.2), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 5793cbd8..0cd2c900 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -120,11 +120,11 @@ public void robotPeriodic() { Logger.recordOutput( "Component Poses", V3_EpsilonMechanism3d.getPoses( - elevator.getPositionMeters(), manipulator.getArmAngle(), intake.getPivotAngle())); + elevator.getPositionMeters(), intake.getPivotAngle(), manipulator.getArmAngle())); } @Override public Command getAutonomousCommand() { - return superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE); + return superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE_SCORE); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index 7dbd2f01..18ef63af 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -47,6 +47,7 @@ digraph Superstructure { intermediate_wait_for_elevator [color = green] # Basic Handoff Edges + start -> stow_down [color = red] stow_down -> stow_up [color = green] handoff -> stow_up [color = green] @@ -62,7 +63,7 @@ digraph Superstructure { L2_transition -> handoff [color = green] L3_transition -> handoff [color = green] - L4_transition -> hadnoff [color = green] + L4_transition -> handoff [color = green] handoff -> L2_prep [color = green] handoff -> L3_prep [color = green] diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 9929b71f..48ffb89d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -8,6 +8,7 @@ import frc.robot.RobotState.RobotMode; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.EdgeCommand; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.GamePieceEdge; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.util.NTPrefixes; @@ -241,7 +242,8 @@ private Optional bfs( * @return true if the transition is allowed */ private boolean isEdgeAllowed(EdgeCommand edge, V3_EpsilonSuperstructureStates goal) { - return true; + return edge.getGamePieceEdge() == GamePieceEdge.NONE + || RobotState.isHasAlgae() == (edge.getGamePieceEdge() == GamePieceEdge.ALGAE); } /** Resets the superstructure to initial auto state. */ diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index fc56834d..fb6c3c20 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -66,244 +66,6 @@ private static Command getEdgeCommand( } private static void createEdges() { - NONE_EDGES.add( - new Edge(V3_EpsilonSuperstructureStates.START, V3_EpsilonSuperstructureStates.STOW_DOWN)); - NONE_EDGES.add( - new Edge(V3_EpsilonSuperstructureStates.STOW_DOWN, V3_EpsilonSuperstructureStates.STOW_UP)); - NONE_EDGES.add( - new Edge(V3_EpsilonSuperstructureStates.HANDOFF, V3_EpsilonSuperstructureStates.STOW_UP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.STOW_UP, V3_EpsilonSuperstructureStates.L2_TRANSITION)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.STOW_UP, V3_EpsilonSuperstructureStates.L3_TRANSITION)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.STOW_UP, V3_EpsilonSuperstructureStates.L4_TRANSITION)); - - NONE_EDGES.add( - new Edge(V3_EpsilonSuperstructureStates.HANDOFF, V3_EpsilonSuperstructureStates.L1_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.HANDOFF, V3_EpsilonSuperstructureStates.L2_TRANSITION)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.HANDOFF, V3_EpsilonSuperstructureStates.L3_TRANSITION)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.HANDOFF, V3_EpsilonSuperstructureStates.L4_TRANSITION)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L2_TRANSITION, V3_EpsilonSuperstructureStates.HANDOFF)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L3_TRANSITION, V3_EpsilonSuperstructureStates.HANDOFF)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L4_TRANSITION, V3_EpsilonSuperstructureStates.HANDOFF)); - NONE_EDGES.add( - new Edge(V3_EpsilonSuperstructureStates.HANDOFF, V3_EpsilonSuperstructureStates.L2_PREP)); - NONE_EDGES.add( - new Edge(V3_EpsilonSuperstructureStates.HANDOFF, V3_EpsilonSuperstructureStates.L3_PREP)); - NONE_EDGES.add( - new Edge(V3_EpsilonSuperstructureStates.HANDOFF, V3_EpsilonSuperstructureStates.L4_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR, - V3_EpsilonSuperstructureStates.HANDOFF)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.GROUND_INTAKE, V3_EpsilonSuperstructureStates.L1_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.GROUND_INTAKE)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L1_PREP, V3_EpsilonSuperstructureStates.GROUND_INTAKE)); - NONE_EDGES.add( - new Edge(V3_EpsilonSuperstructureStates.L1_PREP, V3_EpsilonSuperstructureStates.L1_SCORE)); - NONE_EDGES.add( - new Edge(V3_EpsilonSuperstructureStates.L2_PREP, V3_EpsilonSuperstructureStates.L2_SCORE)); - NONE_EDGES.add( - new Edge(V3_EpsilonSuperstructureStates.L3_PREP, V3_EpsilonSuperstructureStates.L3_SCORE)); - NONE_EDGES.add( - new Edge(V3_EpsilonSuperstructureStates.L4_PREP, V3_EpsilonSuperstructureStates.L4_SCORE)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L2_PREP, - V3_EpsilonSuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L3_PREP, - V3_EpsilonSuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L4_PREP, - V3_EpsilonSuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.GROUND_INTAKE)); - NONE_EDGES.add( - new Edge(V3_EpsilonSuperstructureStates.L1_PREP, V3_EpsilonSuperstructureStates.HANDOFF)); - NONE_EDGES.add( - new Edge(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.HANDOFF)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L2_SCORE, - V3_EpsilonSuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L3_SCORE, - V3_EpsilonSuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L4_SCORE, - V3_EpsilonSuperstructureStates.INTERMIDIATE_WAIT_FOR_ELEVATOR)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L2_PREP, V3_EpsilonSuperstructureStates.L3_TRANSITION)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L2_PREP, V3_EpsilonSuperstructureStates.L4_TRANSITION)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L3_PREP, V3_EpsilonSuperstructureStates.L2_TRANSITION)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L3_PREP, V3_EpsilonSuperstructureStates.L4_TRANSITION)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L4_PREP, V3_EpsilonSuperstructureStates.L3_TRANSITION)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L4_PREP, V3_EpsilonSuperstructureStates.L2_TRANSITION)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L2_TRANSITION, V3_EpsilonSuperstructureStates.L2_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L3_TRANSITION, V3_EpsilonSuperstructureStates.L3_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L4_TRANSITION, V3_EpsilonSuperstructureStates.L4_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L2_PREP, V3_EpsilonSuperstructureStates.L2_TRANSITION)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L3_PREP, V3_EpsilonSuperstructureStates.L3_TRANSITION)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L4_PREP, V3_EpsilonSuperstructureStates.L4_TRANSITION)); - - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.STOW_UP, V3_EpsilonSuperstructureStates.L2_ALGAE_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.STOW_UP, V3_EpsilonSuperstructureStates.L3_ALGAE_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.STOW_UP, V3_EpsilonSuperstructureStates.BARGE_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.STOW_UP, V3_EpsilonSuperstructureStates.PROCESSOR_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L2_ALGAE_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L3_ALGAE_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L2_ALGAE_PREP, - V3_EpsilonSuperstructureStates.BARGE_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L3_ALGAE_PREP, - V3_EpsilonSuperstructureStates.BARGE_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L2_ALGAE_PREP, - V3_EpsilonSuperstructureStates.PROCESSOR_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L3_ALGAE_PREP, - V3_EpsilonSuperstructureStates.PROCESSOR_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L2_ALGAE_PREP, V3_EpsilonSuperstructureStates.STOW_UP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L3_ALGAE_PREP, V3_EpsilonSuperstructureStates.STOW_UP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L2_ALGAE_PREP, - V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE, - V3_EpsilonSuperstructureStates.L2_ALGAE_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE, - V3_EpsilonSuperstructureStates.L3_ALGAE_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L3_ALGAE_PREP, - V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE, - V3_EpsilonSuperstructureStates.STOW_UP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE, - V3_EpsilonSuperstructureStates.STOW_UP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.BARGE_PREP, V3_EpsilonSuperstructureStates.BARGE_SCORE)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.PROCESSOR_PREP, - V3_EpsilonSuperstructureStates.PROCESSOR_SCORE)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, - V3_EpsilonSuperstructureStates.STOW_UP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, - V3_EpsilonSuperstructureStates.STOW_DOWN)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, - V3_EpsilonSuperstructureStates.HANDOFF)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.STOW_UP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.STOW_DOWN)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.HANDOFF)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L2_ALGAE_PREP, - V3_EpsilonSuperstructureStates.L3_ALGAE_PREP)); - NONE_EDGES.add( - new Edge( - V3_EpsilonSuperstructureStates.L3_ALGAE_PREP, - V3_EpsilonSuperstructureStates.L2_ALGAE_PREP)); } /** diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java index 8db1fc6a..8a81cc56 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java @@ -66,8 +66,7 @@ public Command setIntakeState(V3_EpsilonIntake intake) { * @return A Command that sets the arm state and waits until it reaches the goal. */ public Command setManipulatorState(V3_EpsilonManipulator manipulator) { - return Commands.parallel( - Commands.runOnce(() -> manipulator.setArmGoal(armState)), manipulator.waitUntilArmAtGoal()); + return Commands.parallel(manipulator.setArmGoal(armState), manipulator.waitUntilArmAtGoal()); } /** @@ -84,7 +83,7 @@ public Command asCommand( ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { return Commands.parallel( Commands.runOnce(() -> elevator.setPosition(() -> elevatorHeight)), - Commands.runOnce(() -> manipulator.setArmGoal(armState)), + manipulator.setArmGoal(armState), Commands.runOnce(() -> intake.setPivotGoal(intakeState))); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 3ac0d9c9..b1ff2c3d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -22,7 +22,7 @@ public enum V3_EpsilonSuperstructureStates { HANDOFF( "HANDOFF", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), SubsystemActions.empty()), GROUND_INTAKE( @@ -132,7 +132,7 @@ public enum V3_EpsilonSuperstructureStates { INTERMIDIATE_WAIT_FOR_ELEVATOR( "INTERMIDIATE_WAIT_FOR_ELEVATOR", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.STOW_UP, IntakePivotState.STOW), + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.STOW_UP, IntakePivotState.STOW), SubsystemActions.empty()), // Transition States diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index 328db042..56d21a29 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -12,7 +12,6 @@ public class V3_EpsilonIntake { private final V3_EpsilonIntakeIO io; private final V3_EpsilonIntakeIOInputsAutoLogged inputs; - // private final SysIdRoutine characterizationRoutine; @Getter @AutoLogOutput(key = "Intake/Pivot Goal") @@ -28,16 +27,6 @@ public V3_EpsilonIntake(V3_EpsilonIntakeIO io) { this.io = io; inputs = new V3_EpsilonIntakeIOInputsAutoLogged(); - // characterizationRoutine = - // new SysIdRoutine( - // new SysIdRoutine.Config( - // Volts.of(0.2).per(Second), - // Volts.of(3.5), - // Seconds.of(8), - // (state) -> Logger.recordOutput("Intake/SysID State", state.toString())), - // new SysIdRoutine.Mechanism((volts) -> io.setPivotVoltage(volts.in(Volts)), null, - // this)); - pivotGoal = IntakePivotState.STOW; rollerGoal = IntakeRollerState.STOP; @@ -82,18 +71,6 @@ public Command waitUntilPivotAtGoal() { return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::atGoal)); } - public Command sysIdRoutine() { - return Commands.sequence(); - // Commands.runOnce(() -> isClosedLoop = false), - // Commands.runOnce(() -> characterizationRoutine.quasistatic(Direction.kForward)), - // Commands.waitSeconds(0.25), - // Commands.runOnce(() -> characterizationRoutine.quasistatic(Direction.kReverse)), - // Commands.waitSeconds(0.25), - // Commands.runOnce(() -> characterizationRoutine.dynamic(Direction.kForward)), - // Commands.waitSeconds(0.25), - // Commands.runOnce(() -> characterizationRoutine.dynamic(Direction.kReverse))); - } - public void setRollerGoal(IntakeRollerState rollerGoal) { this.rollerGoal = rollerGoal; } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index d776e16a..055c9849 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -23,7 +23,7 @@ public class V3_EpsilonIntakeConstants { 3.0, DCMotor.getKrakenX60Foc(1), 0.0042, - Rotation2d.fromDegrees(-90.0), + Rotation2d.fromDegrees(0.0), Rotation2d.fromDegrees(90.0)); public static final IntakeParems ROLLER_PARAMS = new IntakeParems( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java index a1a99415..87cd56c2 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java @@ -31,7 +31,7 @@ public V3_EpsilonIntakeIOSim() { V3_EpsilonIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO()), V3_EpsilonIntakeConstants.PIVOT_PARAMS.MOTOR(), V3_EpsilonIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO(), - 0.1, + 1, V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getRadians(), V3_EpsilonIntakeConstants.PIVOT_PARAMS.MAX_ANGLE().getRadians(), true, diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 361a49ee..e5784d81 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -14,8 +14,6 @@ public class V3_EpsilonManipulator { private final V3_EpsilonManipulatorIO io; private final ManipulatorIOInputsAutoLogged inputs; - // private final SysIdRoutine algaeCharacterizationRoutine; - private ManipulatorArmState state; private boolean isClosedLoop; @@ -24,16 +22,7 @@ public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { inputs = new ManipulatorIOInputsAutoLogged(); isClosedLoop = true; - // algaeCharacterizationRoutine = - // new SysIdRoutine( - // new SysIdRoutine.Config( - // Volts.of(0.2).per(Second), - // Volts.of(3.5), - // Seconds.of(5), - // (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), - // new SysIdRoutine.Mechanism((volts) -> io.setArmVoltage(volts.in(Volts)), null, - // this)); - state = ManipulatorArmState.STOW_DOWN; + state = ManipulatorArmState.STOW_UP; } public void periodic() { @@ -41,7 +30,6 @@ public void periodic() { Logger.processInputs("Manipulator", inputs); if (isClosedLoop) { - setSlot(); io.setArmGoal(state.getAngle()); } @@ -71,18 +59,6 @@ public Command runArm(double volts) { () -> io.setArmVoltage(0)); } - public Command sysIdRoutine() { - return Commands.sequence(); - // Commands.runOnce(() -> isClosedLoop = false), - // algaeCharacterizationRoutine.quasistatic(Direction.kForward), - // Commands.waitSeconds(.25), - // algaeCharacterizationRoutine.quasistatic(Direction.kReverse), - // Commands.waitSeconds(.25), - // algaeCharacterizationRoutine.dynamic(Direction.kForward), - // Commands.waitSeconds(.25), - // algaeCharacterizationRoutine.dynamic(Direction.kReverse)); - } - public Command setArmGoal(ManipulatorArmState goal) { return Commands.runOnce( () -> { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 9a915084..234a8616 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -41,10 +41,10 @@ public class V3_EpsilonManipulatorConstants { 0.5); EMPTY_GAINS = new Gains( - new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 0), + new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 50), new LoggedTunableNumber("Manipulator/Arm/Empty/kD", 0), - new LoggedTunableNumber("Manipulator/Arm/Empty/kS", 0), - new LoggedTunableNumber("Manipulator/Arm/Empty/kG", 0), + new LoggedTunableNumber("Manipulator/Arm/Empty/kS", 0.24274), + new LoggedTunableNumber("Manipulator/Arm/Empty/kG", 0.66177), new LoggedTunableNumber("Manipulator/Arm/Empty/kV", 0), new LoggedTunableNumber("Manipulator/Arm/Empty/kA", 0)); CORAL_GAINS = @@ -65,8 +65,8 @@ public class V3_EpsilonManipulatorConstants { new LoggedTunableNumber("Manipulator/ArmWithAlgae/kA", 0.0)); CONSTRAINTS = new Constraints( - new LoggedTunableNumber("Manipulator/Arm/MaxAcceleration", 2.0), - new LoggedTunableNumber("Manipulator/Arm/CruisingVelocity", 5.0), + new LoggedTunableNumber("Manipulator/Arm/MaxAcceleration", 20.0), + new LoggedTunableNumber("Manipulator/Arm/CruisingVelocity", 50.0), new LoggedTunableNumber("Manipulator/Arm/GoalTolerance", Units.degreesToRadians(1.5))); ROLLER_CAN_ID = 30; @@ -138,7 +138,7 @@ public static record ArmParameters( @RequiredArgsConstructor public static enum ManipulatorArmState { - STOW_UP(Rotation2d.fromDegrees(75)), + STOW_UP(Rotation2d.fromDegrees(0.0)), PRE_SCORE(Rotation2d.fromDegrees(50.0)), SCORE(Rotation2d.fromDegrees(35.0)), // Placeholder value. Make sure to test PROCESSOR(Rotation2d.fromDegrees(-61.279296875 + 20)), @@ -146,9 +146,9 @@ public static enum ManipulatorArmState { INTAKE_OUT_LINE(Rotation2d.fromDegrees(-61)), FLOOR_INTAKE(Rotation2d.fromDegrees(-68.5 - 5)), STOW_LINE(Rotation2d.fromDegrees(-75)), - TRANSITION(Rotation2d.fromDegrees(-32)), // Placeholder value. Make sure to test - STOW_DOWN(Rotation2d.fromDegrees(-77)), - HANDOFF(new Rotation2d()); + TRANSITION(Rotation2d.fromDegrees(15.0)), // Placeholder value. Make sure to test + STOW_DOWN(Rotation2d.fromDegrees(0)), + HANDOFF(Rotation2d.kPi); private final Rotation2d angle; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java index 8098343e..42f88bb6 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java @@ -37,10 +37,10 @@ public V3_EpsilonManipulatorIOSim() { V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MOTOR_CONFIG(), V3_EpsilonManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO(), V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS(), - V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MIN_ANGLE().getRadians(), - V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MAX_ANGLE().getRadians(), + Double.NEGATIVE_INFINITY, + Double.POSITIVE_INFINITY, true, - V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MIN_ANGLE().getRadians()); + 0.0); rollerMotorSim = new DCMotorSim( LinearSystemId.createDCMotorSystem(DCMotor.getKrakenX60Foc(1), 0.004, 3.0), @@ -92,8 +92,7 @@ public V3_EpsilonManipulatorIOSim() { V3_EpsilonManipulatorConstants.EMPTY_GAINS.kV().get(), V3_EpsilonManipulatorConstants.EMPTY_GAINS.kA().get()); armFeedbackController.enableContinuousInput( - V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MIN_ANGLE().getRadians(), - V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MAX_ANGLE().getRadians()); + -Math.PI, Math.PI); // Wrap around at -180 and 180 degrees armAppliedVolts = 0.0; rollerAppliedVolts = 0.0; From aeb62b6eacb152a53d2ef7a4875a530f90257aaa Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 30 Aug 2025 23:32:11 -0400 Subject: [PATCH 054/180] refactor V3 subsystems for consistency and format --- .../robot/commands/AutonomousCommands.java | 2761 +++++++++-------- .../frc/robot/commands/CompositeCommands.java | 11 +- .../subsystems/shared/elevator/Elevator.java | 2 - .../v3_Epsilon/V3_EpsilonRobotContainer.java | 225 +- .../v3_Epsilon/intake/V3_EpsilonIntake.java | 75 +- .../manipulator/V3_EpsilonManipulator.java | 71 +- .../V3_EpsilonSuperstructure.java | 10 +- .../V3_EpsilonSuperstructureEdges.java | 19 +- .../V3_EpsilonSuperstructurePoses.java | 2 +- 9 files changed, 1586 insertions(+), 1590 deletions(-) diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index d470fd79..f84d3fd7 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -11,28 +11,22 @@ import frc.robot.RobotState; import frc.robot.commands.CompositeCommands.V1_StackUpCompositeCommands; import frc.robot.commands.CompositeCommands.V2_RedundancyCompositeCommands; -import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorCSB; import frc.robot.subsystems.shared.funnel.Funnel.FunnelCSB; import frc.robot.subsystems.shared.vision.Camera; import frc.robot.subsystems.v1_StackUp.manipulator.V1_StackUpManipulator; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructure; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.util.AllianceFlipUtil; import frc.robot.util.LoggedChoreo.LoggedAutoRoutine; import frc.robot.util.LoggedChoreo.LoggedAutoTrajectory; import java.util.Optional; -import javax.management.openmbean.CompositeType; - public class AutonomousCommands { private static Optional> A_LEFT_PATH1; private static Optional> A_RIGHT_PATH1; @@ -407,1386 +401,1405 @@ public static final Command autoDCenter( V1_StackUpCompositeCommands.twerk(drive, elevator, manipulator, cameras)); } + // V2 + + public static final LoggedAutoRoutine autoALeft( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeft"); + + LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_LEFT_PATH4") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path3.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path4.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoALeftNashoba( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftNashoba"); + + LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_LEFT_PATH_ALT3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_LEFT_PATH_ALT4") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path3.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path4.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoALeftDAVE( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftD.A.V.E."); + + LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_LEFT_PATH4_ALT_ALT") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path3.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.25), + Commands.deadline( + path4.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.STOW_DOWN, + V2_RedundancySuperstructureStates.SCORE_L4, + 0.5))); + + return routine; + } - // V2 - - public static final LoggedAutoRoutine autoALeft( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeft"); - - LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_LEFT_PATH4") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path3.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path4.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoALeftNashoba( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftNashoba"); - - LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_LEFT_PATH_ALT3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_LEFT_PATH_ALT4") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path3.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path4.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoALeftDAVE( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftD.A.V.E."); - - LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_LEFT_PATH4_ALT_ALT") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path3.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.25), - Commands.deadline( - path4.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.STOW_DOWN, - V2_RedundancySuperstructureStates.SCORE_L4, - 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoARight( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoARight"); - - LoggedAutoTrajectory path1 = routine.trajectory("A_RIGHT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_RIGHT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_RIGHT_PATH4") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.25), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.25), - Commands.deadline( - path3.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.25), - Commands.deadline( - path4.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoBLeft( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBLeft"); - LoggedAutoTrajectory path1 = - routine - .trajectory("B_LEFT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("B_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN))); - - return routine; - } - - public static final LoggedAutoRoutine autoCLeft( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_LEFT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path3.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoCLeftPush( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_LEFT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), - () -> drive.stop()) - .withTimeout(0.5), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path3.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoCRight( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_RIGHT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_RIGHT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path3.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); - return routine; - } - - public static final LoggedAutoRoutine autoCRightPush( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_RIGHT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_RIGHT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, 1.0, 0.0)), - () -> drive.stop()) - .withTimeout(0.5), - path1.cmd(), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path3.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); - return routine; - } - - public static final LoggedAutoRoutine autoBRight( - Drive drive, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBRight"); - LoggedAutoTrajectory path1 = - routine - .trajectory("B_RIGHT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("B_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - Commands.deadline( - path2.cmd(), - V2_RedundancyCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN))); - - return routine; - } - - public static final LoggedAutoRoutine autoDCenter( - Drive drive, V2_RedundancySuperstructure superstructure, Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoDCenter"); - LoggedAutoTrajectory path1 = - routine - .trajectory("D_CENTER_PATH") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), - superstructure.runActionWithTimeout( - V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); - return routine; - } - - // V3 + public static final LoggedAutoRoutine autoARight( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoARight"); + + LoggedAutoTrajectory path1 = routine.trajectory("A_RIGHT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_RIGHT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_RIGHT_PATH4") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.25), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.25), + Commands.deadline( + path3.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.25), + Commands.deadline( + path4.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoBLeft( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBLeft"); + LoggedAutoTrajectory path1 = + routine + .trajectory("B_LEFT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("B_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN))); + + return routine; + } + + public static final LoggedAutoRoutine autoCLeft( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_LEFT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path3.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoCLeftPush( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_LEFT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), + () -> drive.stop()) + .withTimeout(0.5), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path3.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoCRight( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_RIGHT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_RIGHT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path3.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); + return routine; + } + + public static final LoggedAutoRoutine autoCRightPush( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_RIGHT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_RIGHT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, 1.0, 0.0)), + () -> drive.stop()) + .withTimeout(0.5), + path1.cmd(), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path3.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); + return routine; + } + + public static final LoggedAutoRoutine autoBRight( + Drive drive, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBRight"); + LoggedAutoTrajectory path1 = + routine + .trajectory("B_RIGHT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("B_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + Commands.deadline( + path2.cmd(), + V2_RedundancyCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN))); + + return routine; + } + + public static final LoggedAutoRoutine autoDCenter( + Drive drive, V2_RedundancySuperstructure superstructure, Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoDCenter"); + LoggedAutoTrajectory path1 = + routine + .trajectory("D_CENTER_PATH") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V2_RedundancySuperstructureStates.L4)), + superstructure.runActionWithTimeout( + V2_RedundancySuperstructureStates.SCORE_L4, 0.5))); + return routine; + } + + // V3 public static final LoggedAutoRoutine autoALeft( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeft"); - - LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_LEFT_PATH4") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path3.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path4.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5))); - - return routine; -} + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeft"); + + LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_LEFT_PATH4") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path3.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path4.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5))); + + return routine; + } -public static final LoggedAutoRoutine autoALeftNashoba( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftNashoba"); - - LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_LEFT_PATH_ALT3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_LEFT_PATH_ALT4") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path3.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path4.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5))); - - return routine; -} + public static final LoggedAutoRoutine autoALeftNashoba( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftNashoba"); + + LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_LEFT_PATH_ALT3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_LEFT_PATH_ALT4") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path3.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path4.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5))); + + return routine; + } -public static final LoggedAutoRoutine autoALeftDAVE( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftD.A.V.E."); - - LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_LEFT_PATH4_ALT_ALT") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path3.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path4.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5))); - - return routine; -} + public static final LoggedAutoRoutine autoALeftDAVE( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftD.A.V.E."); + + LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_LEFT_PATH4_ALT_ALT") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path3.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path4.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5))); + + return routine; + } -public static final LoggedAutoRoutine autoARight( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoARight"); - - LoggedAutoTrajectory path1 = routine.trajectory("A_RIGHT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_RIGHT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_RIGHT_PATH4") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.25), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.25), - Commands.deadline( - path3.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.25), - Commands.deadline( - path4.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); - - return routine; -} + public static final LoggedAutoRoutine autoARight( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { -public static final LoggedAutoRoutine autoBLeft( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBLeft"); - LoggedAutoTrajectory path1 = - routine - .trajectory("B_LEFT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("B_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); - - return routine; -} + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoARight"); + + LoggedAutoTrajectory path1 = routine.trajectory("A_RIGHT_PATH1"); + LoggedAutoTrajectory path2 = + routine + .trajectory("A_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("A_RIGHT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path4 = + routine + .trajectory("A_RIGHT_PATH4") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path3.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.25), + Commands.deadline( + path4.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5))); + + return routine; + } -public static final LoggedAutoRoutine autoCLeft( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_LEFT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path3.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); - - return routine; -} + public static final LoggedAutoRoutine autoBLeft( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { -public static final LoggedAutoRoutine autoCLeftPush( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_LEFT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), - () -> drive.stop()) - .withTimeout(0.5), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path3.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); - - return routine; -} + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBLeft"); + LoggedAutoTrajectory path1 = + routine + .trajectory("B_LEFT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("B_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); + + return routine; + } -public static final LoggedAutoRoutine autoCRight( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_RIGHT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_RIGHT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path3.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); - return routine; -} + public static final LoggedAutoRoutine autoCLeft( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { -public static final LoggedAutoRoutine autoCRightPush( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_RIGHT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_RIGHT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, 1.0, 0.0)), - () -> drive.stop()) - .withTimeout(0.5), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path3.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); - return routine; -} + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_LEFT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5), + Commands.deadline( + path3.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5))); + + return routine; + } -public static final LoggedAutoRoutine autoBRight( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBRight"); - LoggedAutoTrajectory path1 = - routine - .trajectory("B_RIGHT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("B_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); - - return routine; -} + public static final LoggedAutoRoutine autoCLeftPush( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { -public static final LoggedAutoRoutine autoDCenter( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoDCenter"); - LoggedAutoTrajectory path1 = - routine - .trajectory("D_CENTER_PATH") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, 0.5))); - return routine; -} + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_LEFT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_LEFT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_LEFT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), + () -> drive.stop()) + .withTimeout(0.5), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5), + Commands.deadline( + path3.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5))); + + return routine; + } + + public static final LoggedAutoRoutine autoCRight( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_RIGHT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_RIGHT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5), + Commands.deadline( + path3.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5))); + return routine; + } + + public static final LoggedAutoRoutine autoCRightPush( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); + LoggedAutoTrajectory path1 = + routine + .trajectory("C_RIGHT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("C_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path3 = + routine + .trajectory("C_RIGHT_PATH3") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, 1.0, 0.0)), + () -> drive.stop()) + .withTimeout(0.5), + path1.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5), + Commands.deadline( + path3.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> superstructure.atGoal())), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5))); + return routine; + } + + public static final LoggedAutoRoutine autoBRight( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBRight"); + LoggedAutoTrajectory path1 = + routine + .trajectory("B_RIGHT_PATH1") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + LoggedAutoTrajectory path2 = + routine + .trajectory("B_RIGHT_PATH2") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5), + Commands.deadline( + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); + + return routine; + } + + public static final LoggedAutoRoutine autoDCenter( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoDCenter"); + LoggedAutoTrajectory path1 = + routine + .trajectory("D_CENTER_PATH") + .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), + superstructure.runActionWithTimeout( + V3_EpsilonSuperstructureStates.STOW_DOWN, + V3_EpsilonSuperstructureStates.L4_SCORE, + 0.5))); + return routine; + } } diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 7fc6f845..5228d7ff 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -22,10 +22,10 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.util.AllianceFlipUtil; import java.util.function.BooleanSupplier; import java.util.function.Supplier; @@ -693,8 +693,7 @@ public static final Command intakeCoralOperatorSequence( * @param superstructure The superstructure subsystem. * @return A command to score coral at L1. */ - public static final Command scoreL1Coral( - Drive drive, V3_EpsilonSuperstructure superstructure) { + public static final Command scoreL1Coral(Drive drive, V3_EpsilonSuperstructure superstructure) { return Commands.sequence( superstructure.runGoal(V3_EpsilonSuperstructureStates.L1_PREP), Commands.parallel( @@ -919,8 +918,7 @@ public static final Command floorIntakeSequence(V3_EpsilonSuperstructure superst * @param superstructure The superstructure subsystem. * @return A command that posts the floor intake sequence. */ - public static final Command postFloorIntakeSequence( - V3_EpsilonSuperstructure superstructure) { + public static final Command postFloorIntakeSequence(V3_EpsilonSuperstructure superstructure) { return Commands.either( superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), @@ -960,6 +958,5 @@ public static final Command climb( Commands.waitUntil(climber::climberReady), Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); } - } } diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java index 766875b5..113a5116 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java @@ -16,8 +16,6 @@ import frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions; import frc.robot.subsystems.shared.elevator.ElevatorIO.ElevatorIOInputs; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructure; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 1f2fe127..c8c1ca98 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -33,31 +33,23 @@ import frc.robot.subsystems.shared.elevator.ElevatorIO; import frc.robot.subsystems.shared.elevator.ElevatorIOSim; import frc.robot.subsystems.shared.elevator.ElevatorIOTalonFX; -import frc.robot.subsystems.shared.funnel.Funnel; -import frc.robot.subsystems.shared.funnel.Funnel.FunnelFSM; -import frc.robot.subsystems.shared.funnel.FunnelIO; // import frc.robot.subsystems.shared.funnel.FunnelIOSim; // import frc.robot.subsystems.shared.funnel.FunnelIOTalonFX; // import frc.robot.subsystems.shared.vision.CameraConstants.RobotCameras; import frc.robot.subsystems.shared.vision.Vision; +import frc.robot.subsystems.shared.vision.VisionConstants.RobotCameras; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants.IntakeRollerStates; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIO; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIOSim; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIOTalonFX; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerStates; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorIO; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorIOSim; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIOTalonFX; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIO; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIOSim; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants.IntakeRollerStates; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerStates; -import frc.robot.subsystems.shared.vision.VisionConstants.RobotCameras; - - - -import frc.robot.util.LTNUpdater; import frc.robot.util.LoggedChoreo.ChoreoChooser; -import org.littletonrobotics.junction.Logger; public class V3_EpsilonRobotContainer implements RobotContainer { // Subsystems @@ -66,7 +58,7 @@ public class V3_EpsilonRobotContainer implements RobotContainer { private ElevatorFSM elevator; private Vision vision; private V3_EpsilonIntake intake; -// private V3_EpsilonLEDs leds; + // private V3_EpsilonLEDs leds; private V3_EpsilonManipulator manipulator; private V3_EpsilonSuperstructure superstructure; @@ -92,13 +84,15 @@ public V3_EpsilonRobotContainer() { new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); - // leds = new V3_EpsilonLEDs(); + // leds = new V3_EpsilonLEDs(); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); - superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); // Doesn't include states - // vision = new Vision(RobotCameras.V3_Epsilon_CAMS); + superstructure = + new V3_EpsilonSuperstructure(elevator, intake, manipulator); // Doesn't include + // states + // vision = new Vision(RobotCameras.V3_Epsilon_CAMS); break; case V3_EPSILON_SIM: - // climber = new Climber(new ClimberIOSim()); + // climber = new Climber(new ClimberIOSim()); drive = new Drive( new GyroIO() {}, @@ -107,49 +101,45 @@ public V3_EpsilonRobotContainer() { new ModuleIOSim(DriveConstants.BACK_LEFT), new ModuleIOSim(DriveConstants.BACK_RIGHT)); elevator = new Elevator(new ElevatorIOSim()).getFSM(); - // funnel = new Funnel(new FunnelIOSim()).getFSM(); + // funnel = new Funnel(new FunnelIOSim()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); - // vision = new Vision(); + // vision = new Vision(); break; - default: - break; - - if (drive == null) { - drive = - new Drive( - new GyroIO() { - // Provide concrete implementation for GyroIO methods here - }, - new ModuleIO() { - }, - new ModuleIO() { - }, - new ModuleIO() { - }, - new ModuleIO() { - }); - if (elevator == null) { - elevator = new Elevator(new ElevatorIO() {}).getFSM(); - } - - if (intake == null) { - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); - } - // if (leds == null) { - // leds = new V3_EpsilonLEDs(); - // } - if (manipulator == null) { - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); - } - // if (vision == null) { - // vision = new Vision(); - // } - superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); - - configureButtonBindings(); - } -} + default: + break; + } + if (drive == null) { + drive = + new Drive( + new GyroIO() { + // Provide concrete implementation for GyroIO methods here + }, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}); + } + if (elevator == null) { + elevator = new Elevator(new ElevatorIO() {}).getFSM(); + } + + if (intake == null) { + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); + } + // if (leds == null) { + // leds = new V3_EpsilonLEDs(); + // } + if (manipulator == null) { + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); + } + // if (vision == null) { + // vision = new Vision(); + // } + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + + configureButtonBindings(); + configureAutos(); } } @@ -166,12 +156,13 @@ public void configureButtonBindings() { !elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) && !elevator.getPosition().equals(ElevatorPositions.STOW)); // Trigger halfScoreTrigger = - // new Trigger(() -> operator.getLeftY() < -DriveConstants.OPERATOR_DEADBAND); + // new Trigger(() -> operator.getLeftY() < -DriveConstants.OPERATOR_DEADBAND); // Trigger unHalfScoreTrigger = - // new Trigger(() -> operator.getLeftY() > DriveConstants.OPERATOR_DEADBAND); + // new Trigger(() -> operator.getLeftY() > DriveConstants.OPERATOR_DEADBAND); // Trigger operatorFunnelOverride = - // new Trigger(() -> Math.hypot(operator.getRightX(), operator.getRightY()) > 0.5); + // new Trigger(() -> Math.hypot(operator.getRightX(), operator.getRightY()) > + // 0.5); // Default drive command drive.setDefaultCommand( @@ -250,16 +241,16 @@ public void configureButtonBindings() { RobotCameras.V3_EPSILON_CAMS)); driver - .start() - .whileTrue( - V3_EpsilonCompositeCommands.dropAlgae( - drive, - elevator, - manipulator, - intake, - superstructure, - () -> RobotState.getReefAlignData().algaeIntakeHeight(), - RobotCameras.V3_EPSILON_CAMS)); // Remove the extra dot here + .start() + .whileTrue( + V3_EpsilonCompositeCommands.dropAlgae( + drive, + elevator, + manipulator, + intake, + superstructure, + () -> RobotState.getReefAlignData().algaeIntakeHeight(), + RobotCameras.V3_EPSILON_CAMS)); // Remove the extra dot here // Operator face buttons operator.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); @@ -287,8 +278,7 @@ public void configureButtonBindings() { // Operator triggers operator .leftTrigger(0.5) - .whileTrue( - V3_EpsilonCompositeCommands.intakeCoralOperatorSequence(superstructure, intake)) + .whileTrue(V3_EpsilonCompositeCommands.intakeCoralOperatorSequence(superstructure, intake)) .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); operator .rightTrigger(0.5) @@ -307,8 +297,10 @@ public void configureButtonBindings() { .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR_PREP)) .onFalse( superstructure - .runActionWithTimeout(V3_EpsilonSuperstructureStates.PROCESSOR_PREP, - V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, 1) + .runActionWithTimeout( + V3_EpsilonSuperstructureStates.PROCESSOR_PREP, + V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, + 1) .finallyDo(() -> RobotState.setHasAlgae(false))); operator @@ -324,21 +316,22 @@ public void configureButtonBindings() { .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE_PREP)) .onFalse( superstructure - .runActionWithTimeout(V3_EpsilonSuperstructureStates.BARGE_PREP, - V3_EpsilonSuperstructureStates.BARGE_SCORE, 0.1) + .runActionWithTimeout( + V3_EpsilonSuperstructureStates.BARGE_PREP, + V3_EpsilonSuperstructureStates.BARGE_SCORE, + 0.1) .finallyDo(() -> RobotState.setHasAlgae(false))); // Misc // operatorFunnelOverride - // .whileTrue( - // Commands.either( - // superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), - // superstructure.runGoal( - // V3_EpsilonSuperstructureStates.STOW_DOWN), - // () -> RobotState.isHasAlgae())) - // .onFalse(superstructure.runPreviousState()); - } - + // .whileTrue( + // Commands.either( + // superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), + // superstructure.runGoal( + // V3_EpsilonSuperstructureStates.STOW_DOWN), + // () -> RobotState.isHasAlgae())) + // .onFalse(superstructure.runPreviousState()); + } private void configureAutos() { AutonomousCommands.loadAutoTrajectories(drive); @@ -348,7 +341,8 @@ private void configureAutos() { autoChooser.addCmd( "Wheel Radius Characterization", () -> DriveCommands.wheelRadiusCharacterization(drive)); autoChooser.addCmd("Elevator Characterization", () -> elevator.sysIdRoutine(superstructure)); - // autoChooser.addCmd("Funnel Characterization", () -> funnel.sysIdRoutine(superstructure)); + // autoChooser.addCmd("Funnel Characterization", () -> + // funnel.sysIdRoutine(superstructure)); autoChooser.addCmd("Intake Characterization", () -> intake.sysIdRoutine(superstructure)); autoChooser.addCmd( "Manipulator Characterization", @@ -411,39 +405,38 @@ private void configureAutos() { drive, intake, superstructure, RobotCameras.V3_EPSILON_CAMS)); autoChooser.addRoutine( "1 Piece Center", - () -> - AutonomousCommands.autoDCenter(drive, superstructure, RobotCameras.V3_EPSILON_CAMS)); + () -> AutonomousCommands.autoDCenter(drive, superstructure, RobotCameras.V3_EPSILON_CAMS)); SmartDashboard.putData("Autonomous Modes", autoChooser); } -// @Override -// public void robotPeriodic() { -// RobotState.periodic( -// drive.getRawGyroRotation(), -// NetworkTablesJNI.now(), -// drive.getYawVelocity(), -// drive.getFieldRelativeVelocity(), -// drive.getModulePositions(), -// manipulator.getArmAngle(), -// elevator.getPositionMeters()); - -// LTNUpdater.updateDrive(drive); -// LTNUpdater.updateElevator(elevator); -// LTNUpdater.updateFunnel(funnel); -// LTNUpdater.updateAlgaeArm(manipulator); -// LTNUpdater.updateIntake(intake); - -// Logger.recordOutput( -// "Component Poses", -// V3_EpsilonMechanism3d.getPoses( -// elevator.getPositionMeters(), -// funnel.getAngle(), -// manipulator.getArmAngle(), -// intake.getExtension())); -// } - + // @Override + // public void robotPeriodic() { + // RobotState.periodic( + // drive.getRawGyroRotation(), + // NetworkTablesJNI.now(), + // drive.getYawVelocity(), + // drive.getFieldRelativeVelocity(), + // drive.getModulePositions(), + // manipulator.getArmAngle(), + // elevator.getPositionMeters()); + + // LTNUpdater.updateDrive(drive); + // LTNUpdater.updateElevator(elevator); + // LTNUpdater.updateFunnel(funnel); + // LTNUpdater.updateAlgaeArm(manipulator); + // LTNUpdater.updateIntake(intake); + + // Logger.recordOutput( + // "Component Poses", + // V3_EpsilonMechanism3d.getPoses( + // elevator.getPositionMeters(), + // funnel.getAngle(), + // manipulator.getArmAngle(), + // intake.getExtension())); + // } @Override public Command getAutonomousCommand() { return autoChooser.selectedCommand(); } +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java index 1b20a254..01c29259 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java @@ -2,29 +2,27 @@ import static edu.wpi.first.units.Units.*; -import edu.wpi.first.math.MathUtil; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; -import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; +import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants.IntakeRollerStates; import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants.IntakeState; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; - -import java.util.Set; import lombok.Getter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; -public class V3_EpsilonIntake extends SubsystemBase { +public class V3_EpsilonIntake { private final V3_EpsilonIntakeIO io; private final IntakeIOInputsAutoLogged inputs; - private final SysIdRoutine characterizationRoutine; @Getter - @AutoLogOutput(key = "Intake/Goal") - private IntakeState goal; + @AutoLogOutput(key = "Intake/Pivot Goal") + private IntakeState pivotGoal; + @Getter + @AutoLogOutput(key = "Intake/Roller Goal") + private IntakeRollerStates rollerGoal = IntakeRollerStates.STOP; private boolean isClosedLoop; @@ -32,26 +30,19 @@ public V3_EpsilonIntake(V3_EpsilonIntakeIO io) { this.io = io; inputs = new IntakeIOInputsAutoLogged(); - characterizationRoutine = - new SysIdRoutine( - new SysIdRoutine.Config( - Volts.of(0.2).per(Second), - Volts.of(3.5), - Seconds.of(8), - (state) -> Logger.recordOutput("Intake/SysID State", state.toString())), - new SysIdRoutine.Mechanism((volts) -> io.setPivotVoltage(volts.in(Volts)), null, this)); - isClosedLoop = true; + pivotGoal = IntakeState.STOW; + rollerGoal = IntakeRollerStates.STOP; } - @Override public void periodic() { io.updateInputs(inputs); Logger.processInputs("Intake", inputs); if (isClosedLoop) { - io.setPivotGoal(goal.getAngle()); + io.setPivotGoal(pivotGoal.getAngle()); } + io.setRollerVoltage(rollerGoal.getVoltage()); } @AutoLogOutput(key = "Intake/Has Coral") @@ -61,21 +52,17 @@ public boolean hasCoral() { @AutoLogOutput(key = "Intake/At Goal") public boolean atGoal() { - return Math.abs(inputs.pivotPosition.getRadians() - goal.getAngle().getRadians()) - < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); + return Math.abs(inputs.pivotPosition.getRadians() + - pivotGoal.getAngle().getRadians()) < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); } public void waitUntilIntakeAtGoal() { Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::atGoal)); } - public void setGoal(IntakeState goal) { + public void setPivotGoal(IntakeState goal) { isClosedLoop = true; - this.goal = goal; - } - - public void setRollerVoltage(double volts) { - io.setRollerVoltage(volts); + this.pivotGoal = goal; } public void setPivotVoltage(double volts) { @@ -88,6 +75,13 @@ public Command waitUntilPivotAtGoal() { } public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { + SysIdRoutine characterizationRoutine = new SysIdRoutine( + new SysIdRoutine.Config( + Volts.of(0.2).per(Second), + Volts.of(3.5), + Seconds.of(8), + (state) -> Logger.recordOutput("Intake/SysID State", state.toString())), + new SysIdRoutine.Mechanism((volts) -> io.setPivotVoltage(volts.in(Volts)), null, superstructure)); return Commands.sequence( Commands.runOnce(() -> isClosedLoop = false), Commands.runOnce(() -> characterizationRoutine.quasistatic(Direction.kForward)), @@ -99,30 +93,7 @@ public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { Commands.runOnce(() -> characterizationRoutine.dynamic(Direction.kReverse))); } - private double holdVoltage() { - double y; - double x = Math.abs(inputs.rollerTorqueCurrentAmps); - if (x <= 20) { - y = -0.0003 * Math.pow(x, 3) + 0.0124286 * Math.pow(x, 2) - 0.241071 * x + 4.00643; - } else { - y = 0.0005 * Math.pow(x, 2) - 0.1015 * x + 3.7425; - } - return MathUtil.clamp( - 1.25 * y, - 0.10, - V3_EpsilonManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().getAsDouble() / 1.5); - } - public void setRollerGoal(V3_EpsilonIntakeConstants.IntakeRollerStates rollerGoal) { - if (hasCoral() - && Set.of( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.CORAL_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP) - .contains(rollerGoal)) { - - io.setRollerVoltage(holdVoltage()); - } else { - io.setRollerVoltage(rollerGoal.getVoltage()); - } + this.rollerGoal = rollerGoal; } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java index be462602..3dddbc53 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java @@ -3,26 +3,31 @@ import static edu.wpi.first.units.Units.*; import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; -import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants; +import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerStates; import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants.PivotState; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; +import lombok.Getter; import java.util.Set; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; -public class V3_EpsilonManipulator extends SubsystemBase { +public class V3_EpsilonManipulator { private final V3_EpsilonManipulatorIO io; private final ManipulatorIOInputsAutoLogged inputs; - private final SysIdRoutine algaeCharacterizationRoutine; - - private PivotState state; + @Getter + @AutoLogOutput(key = "Manipulator/Pivot State") + private PivotState pivotGoal; + @Getter + @AutoLogOutput(key = "Manipulator/Roller State") + private ManipulatorRollerStates rollerGoal; private boolean isClosedLoop; public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { @@ -30,30 +35,28 @@ public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { inputs = new ManipulatorIOInputsAutoLogged(); isClosedLoop = true; - algaeCharacterizationRoutine = - new SysIdRoutine( - new SysIdRoutine.Config( - Volts.of(0.2).per(Second), - Volts.of(3.5), - Seconds.of(5), - (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), - new SysIdRoutine.Mechanism((volts) -> io.setPivotVoltage(volts.in(Volts)), null, this)); - state = PivotState.STOW_DOWN; - } - - @Override + pivotGoal = PivotState.STOW_DOWN; + rollerGoal = ManipulatorRollerStates.STOP; + } + public void periodic() { io.updateInputs(inputs); Logger.processInputs("Manipulator", inputs); if (isClosedLoop) { setSlot(); - io.setPivotGoal(state.getAngle()); + io.setPivotGoal(pivotGoal.getAngle()); } - if (hasAlgae()) { + if (hasAlgae() && Set.of( + ManipulatorRollerStates.CORAL_INTAKE, + ManipulatorRollerStates.STOP) + .contains(rollerGoal)) { io.setRollerVoltage(holdVoltage()); + } else { + io.setRollerVoltage(rollerGoal.getVoltage()); } + } @AutoLogOutput(key = "Manipulator/Has Coral") @@ -69,7 +72,7 @@ public boolean hasAlgae() { } public Command runPivot(double volts) { - return this.runEnd( + return Commands.runEnd( () -> { isClosedLoop = false; io.setPivotVoltage(volts); @@ -78,7 +81,14 @@ public Command runPivot(double volts) { } public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { - public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { + SysIdRoutine algaeCharacterizationRoutine = new SysIdRoutine( + new SysIdRoutine.Config( + Volts.of(0.2).per(Second), + Volts.of(3.5), + Seconds.of(5), + (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), + new SysIdRoutine.Mechanism((volts) -> io.setPivotVoltage(volts.in(Volts)), null, superstructure)); + return Commands.sequence( Commands.runOnce(() -> isClosedLoop = false), algaeCharacterizationRoutine.quasistatic(Direction.kForward), @@ -91,10 +101,10 @@ public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { } public Command setPivotGoal(PivotState goal) { - return this.runOnce( + return Commands.runOnce( () -> { isClosedLoop = true; - state = goal; + pivotGoal = goal; }); } @@ -128,8 +138,9 @@ public void updateArmConstraints(double maxAcceleration, double maxVelocity) { @AutoLogOutput(key = "Manipulator/Arm At Goal") public boolean pivotAtGoal() { - return inputs.armPosition.getRadians() - state.getAngle().getRadians() - <= V2_RedundancyManipulatorConstants.CONSTRAINTS.GOAL_TOLERANCE_RADIANS().get(); + return inputs.armPosition.getRadians() + - pivotGoal.getAngle().getRadians() <= V2_RedundancyManipulatorConstants.CONSTRAINTS.GOAL_TOLERANCE_RADIANS() + .get(); } public Command waitUntilPivotAtGoal() { @@ -167,9 +178,9 @@ public void setManipulatorState(V3_EpsilonManipulatorConstants.PivotState state) public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerStates rollerGoal) { if (hasAlgae() && Set.of( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.ALGAE_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.CORAL_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP) + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.ALGAE_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.CORAL_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP) .contains(rollerGoal)) { io.setRollerVoltage(holdVoltage()); @@ -178,5 +189,7 @@ public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerStates } } - public void getArmAngle() {} + public Rotation2d getArmAngle() { + return inputs.armPosition; + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index b37190db..213c097d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -25,8 +25,8 @@ import org.littletonrobotics.junction.Logger; /** - * The V3_EpsilonSuperstructure class manages the coordinated movement and state transitions of the robot's - * major subsystems including elevator, funnel, manipulator, and intake. + * The V3_EpsilonSuperstructure class manages the coordinated movement and state transitions of the + * robot's major subsystems including elevator, funnel, manipulator, and intake. */ public class V3_EpsilonSuperstructure extends SubsystemBase { @@ -237,7 +237,8 @@ private Optional bfs( * @param goal The target state * @return true if the transition is allowed */ - private boolean isEdgeAllowed(EdgeCommand edge, V3_EpsilonSuperstructureStates goal) { // Change later + private boolean isEdgeAllowed( + EdgeCommand edge, V3_EpsilonSuperstructureStates goal) { // Change later return edge.getAlgaeEdgeType() == AlgaeEdge.NONE || RobotState.isHasAlgae() == (edge.getAlgaeEdgeType() == AlgaeEdge.ALGAE); } @@ -349,7 +350,8 @@ public Command runGoalUntil(V3_EpsilonSuperstructureStates goal, BooleanSupplier return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); } - public Command runGoalUntil(Supplier goal, BooleanSupplier condition) { + public Command runGoalUntil( + Supplier goal, BooleanSupplier condition) { return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index 799b9261..0a150106 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -18,7 +18,8 @@ public class V3_EpsilonSuperstructureEdges { public static final ArrayList UnconstrainedEdges = new ArrayList<>(); public static final ArrayList NoneEdges = new ArrayList<>(); - public record Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to, String action) { + public record Edge( + V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to, String action) { public Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { this(from, to, ""); } @@ -129,16 +130,24 @@ public static void createEdges() { // Prep to score states CoralEdges.add( new Edge( - V3_EpsilonSuperstructureStates.L1_PREP, V3_EpsilonSuperstructureStates.L1_SCORE, "Coral Score L1")); + V3_EpsilonSuperstructureStates.L1_PREP, + V3_EpsilonSuperstructureStates.L1_SCORE, + "Coral Score L1")); CoralEdges.add( new Edge( - V3_EpsilonSuperstructureStates.L2_PREP, V3_EpsilonSuperstructureStates.L2_SCORE, "Coral Score L2")); + V3_EpsilonSuperstructureStates.L2_PREP, + V3_EpsilonSuperstructureStates.L2_SCORE, + "Coral Score L2")); CoralEdges.add( new Edge( - V3_EpsilonSuperstructureStates.L3_PREP, V3_EpsilonSuperstructureStates.L3_SCORE, "Coral Score L3")); + V3_EpsilonSuperstructureStates.L3_PREP, + V3_EpsilonSuperstructureStates.L3_SCORE, + "Coral Score L3")); CoralEdges.add( new Edge( - V3_EpsilonSuperstructureStates.L4_PREP, V3_EpsilonSuperstructureStates.L4_SCORE, "Coral Score L4")); + V3_EpsilonSuperstructureStates.L4_PREP, + V3_EpsilonSuperstructureStates.L4_SCORE, + "Coral Score L4")); // L1_SCORE -> GROUND_INTAKE CoralEdges.add( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePoses.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePoses.java index c077de17..0da77bce 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePoses.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePoses.java @@ -45,7 +45,7 @@ public Command setElevatorHeight(ElevatorFSM elevator) { */ public Command setIntakeState(V3_EpsilonIntake intake) { return Commands.parallel( - Commands.runOnce(() -> intake.setGoal(intakeState)), intake.waitUntilPivotAtGoal()); + Commands.runOnce(() -> intake.setPivotGoal(intakeState)), intake.waitUntilPivotAtGoal()); } /** From 7e10c80d8aa102efb7ef6183c010db98ebd15058 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 30 Aug 2025 23:41:05 -0400 Subject: [PATCH 055/180] move intake and manipulator into the superstructure subsystem --- .../frc/robot/commands/AutonomousCommands.java | 2 +- .../frc/robot/commands/CompositeCommands.java | 4 ++-- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 18 +++++++++--------- .../V3_EpsilonSuperstructure.java | 4 ++-- .../V3_EpsilonSuperstructureActions.java | 8 ++++---- .../V3_EpsilonSuperstructureEdges.java | 5 +++-- .../V3_EpsilonSuperstructurePoses.java | 8 ++++---- .../V3_EpsilonSuperstructureStates.java | 4 ++-- .../intake/V3_EpsilonIntake.java | 7 ++++--- .../intake/V3_EpsilonIntakeConstants.java | 2 +- .../intake/V3_EpsilonIntakeIO.java | 2 +- .../intake/V3_EpsilonIntakeIOSim.java | 2 +- .../intake/V3_EpsilonIntakeIOTalonFX.java | 2 +- .../manipulator/V3_EpsilonManipulator.java | 7 ++++--- .../V3_EpsilonManipulatorConstants.java | 2 +- .../manipulator/V3_EpsilonManipulatorIO.java | 2 +- .../V3_EpsilonManipulatorIOSim.java | 2 +- .../V3_EpsilonManipulatorIOTalonFX.java | 2 +- 18 files changed, 43 insertions(+), 40 deletions(-) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/intake/V3_EpsilonIntake.java (90%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/intake/V3_EpsilonIntakeConstants.java (97%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/intake/V3_EpsilonIntakeIO.java (97%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/intake/V3_EpsilonIntakeIOSim.java (98%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/intake/V3_EpsilonIntakeIOTalonFX.java (99%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/manipulator/V3_EpsilonManipulator.java (93%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/manipulator/V3_EpsilonManipulatorConstants.java (98%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/manipulator/V3_EpsilonManipulatorIO.java (97%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/manipulator/V3_EpsilonManipulatorIOSim.java (99%) rename src/main/java/frc/robot/subsystems/v3_Epsilon/{ => superstructure}/manipulator/V3_EpsilonManipulatorIOTalonFX.java (99%) diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index f84d3fd7..1afb6fba 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -19,9 +19,9 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructure; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.util.AllianceFlipUtil; import frc.robot.util.LoggedChoreo.LoggedAutoRoutine; import frc.robot.util.LoggedChoreo.LoggedAutoTrajectory; diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 5228d7ff..dd5c1cca 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -22,10 +22,10 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.util.AllianceFlipUtil; import java.util.function.BooleanSupplier; import java.util.function.Supplier; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index c8c1ca98..557f204d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -38,17 +38,17 @@ // import frc.robot.subsystems.shared.vision.CameraConstants.RobotCameras; import frc.robot.subsystems.shared.vision.Vision; import frc.robot.subsystems.shared.vision.VisionConstants.RobotCameras; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants.IntakeRollerStates; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIO; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIOSim; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeIOTalonFX; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerStates; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorIO; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorIOSim; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIO; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOSim; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOTalonFX; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakeRollerStates; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIO; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOSim; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerStates; import frc.robot.util.LoggedChoreo.ChoreoChooser; public class V3_EpsilonRobotContainer implements RobotContainer { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 213c097d..375d3e85 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -6,10 +6,10 @@ import frc.robot.RobotState; import frc.robot.RobotState.RobotMode; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.AlgaeEdge; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.EdgeCommand; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.util.NTPrefixes; import java.util.HashMap; import java.util.LinkedList; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureActions.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureActions.java index 80ebf662..c7d72e7f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureActions.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureActions.java @@ -1,9 +1,9 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; import lombok.Getter; public class V3_EpsilonSuperstructureActions { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index 0a150106..4c573a98 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -3,8 +3,9 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.subsystems.shared.elevator.Elevator; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; + import java.util.ArrayList; import java.util.List; import lombok.Builder; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePoses.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePoses.java index 0da77bce..bd8276f3 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePoses.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePoses.java @@ -4,10 +4,10 @@ import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; import lombok.Getter; public class V3_EpsilonSuperstructurePoses { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 0cc131b8..1d5be0e1 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -2,11 +2,11 @@ // Adjust the package path as needed import frc.robot.FieldConstants.Reef.ReefState; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureActions.SubsystemActions; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructurePoses.SubsystemPoses; // Ensure this is the +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; // correct package // path diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java similarity index 90% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index 01c29259..f4df5916 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.intake; +package frc.robot.subsystems.v3_Epsilon.superstructure.intake; import static edu.wpi.first.units.Units.*; @@ -6,9 +6,10 @@ import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants.IntakeRollerStates; -import frc.robot.subsystems.v3_Epsilon.intake.V3_EpsilonIntakeConstants.IntakeState; +import frc.robot.subsystems.v3_Epsilon.intake.IntakeIOInputsAutoLogged; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakeRollerStates; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakeState; import lombok.Getter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java similarity index 97% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index 84668924..e1373bb2 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.intake; +package frc.robot.subsystems.v3_Epsilon.superstructure.intake; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.system.plant.DCMotor; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java similarity index 97% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java index 595fd338..7c2f8b47 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.intake; +package frc.robot.subsystems.v3_Epsilon.superstructure.intake; import edu.wpi.first.math.geometry.Rotation2d; import org.littletonrobotics.junction.AutoLog; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java similarity index 98% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOSim.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java index dd44389b..82475f9e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.intake; +package frc.robot.subsystems.v3_Epsilon.superstructure.intake; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.ArmFeedforward; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java similarity index 99% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java index 9e29b2e2..6b4c1d37 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/intake/V3_EpsilonIntakeIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.intake; +package frc.robot.subsystems.v3_Epsilon.superstructure.intake; import static edu.wpi.first.units.Units.RadiansPerSecond; import static edu.wpi.first.units.Units.RadiansPerSecondPerSecond; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java similarity index 93% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 3dddbc53..e3500119 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.manipulator; +package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; import static edu.wpi.first.units.Units.*; @@ -9,9 +9,10 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerStates; -import frc.robot.subsystems.v3_Epsilon.manipulator.V3_EpsilonManipulatorConstants.PivotState; +import frc.robot.subsystems.v3_Epsilon.manipulator.ManipulatorIOInputsAutoLogged; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerStates; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.PivotState; import lombok.Getter; import java.util.Set; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java similarity index 98% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index ac60ffd0..cba16dd4 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.manipulator; +package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; import com.ctre.phoenix6.configs.SlotConfigs; import com.ctre.phoenix6.signals.GravityTypeValue; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java similarity index 97% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java index 2627908e..97b07bb1 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.manipulator; +package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; import edu.wpi.first.math.geometry.Rotation2d; import org.littletonrobotics.junction.AutoLog; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java similarity index 99% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java index d353faf7..0ce5ed3f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.manipulator; +package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.ArmFeedforward; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java similarity index 99% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java rename to src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java index bd6fa35e..8df9e09a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/manipulator/V3_EpsilonManipulatorIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.manipulator; +package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; import static edu.wpi.first.units.Units.RadiansPerSecond; import static frc.robot.util.PhoenixUtil.*; From dea7a126cd3c8ed4b4b11b618c43734017541038 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sun, 31 Aug 2025 00:07:02 -0400 Subject: [PATCH 056/180] Add methods for managing reef goals and scoring in V3_EpsilonSuperstructure --- .../frc/robot/commands/CompositeCommands.java | 89 ++----------------- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 20 +---- .../V3_EpsilonSuperstructure.java | 74 +++++++++++++++ .../V3_EpsilonSuperstructureEdges.java | 1 - .../intake/V3_EpsilonIntake.java | 22 ++--- .../manipulator/V3_EpsilonManipulator.java | 41 +++++---- 6 files changed, 118 insertions(+), 129 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index dd5c1cca..679a0c9f 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -25,7 +25,6 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.util.AllianceFlipUtil; import java.util.function.BooleanSupplier; import java.util.function.Supplier; @@ -736,13 +735,13 @@ public static final Command scoreCoralSequence( BooleanSupplier autoAligned) { return Commands.sequence( Commands.either( - superstructure.runGoal(V3_EpsilonSuperstructureStates.L3), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L3_TRANSITION), superstructure.runReefGoal(() -> RobotState.getOIData().currentReefHeight()), () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L4) && !superstructure .getCurrentState() - .equals(V3_EpsilonSuperstructureStates.L4)), + .equals(V3_EpsilonSuperstructureStates.L4_TRANSITION)), Commands.waitUntil(() -> autoAligned.getAsBoolean()), superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight()), superstructure @@ -774,7 +773,7 @@ public static final Command autoScoreCoralSequence( superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)), Commands.sequence( Commands.either( - superstructure.runGoal(V3_EpsilonSuperstructureStates.L2), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_TRANSITION), Commands.none(), () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1) @@ -787,10 +786,7 @@ public static final Command autoScoreCoralSequence( scoreCoralSequence( elevator, superstructure, - () -> RobotState.getReefAlignData().atCoralSetpoint())), - superstructure - .l4PlusSequence() - .onlyIf(() -> RobotState.getOIData().currentReefHeight() == ReefState.L4)), + () -> RobotState.getReefAlignData().atCoralSetpoint()))), () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); } @@ -814,9 +810,9 @@ public static final Command intakeAlgaeFromReefSequence( () -> { switch (level.get()) { case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.INTAKE_REEF_L3; + return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.INTAKE_REEF_L2; + return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; default: return V3_EpsilonSuperstructureStates.STOW_DOWN; } @@ -831,9 +827,9 @@ public static final Command intakeAlgaeFromReefSequence( () -> { switch (level.get()) { case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.REEF_ACQUISITION_L3; + return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; default: - return V3_EpsilonSuperstructureStates.REEF_ACQUISITION_L2; + return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; } }), () -> RobotState.isHasAlgae())), @@ -842,75 +838,6 @@ public static final Command intakeAlgaeFromReefSequence( .withTimeout(0.5))); } - /** - * Creates a command to drop algae from the reef. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. - * @param superstructure The superstructure subsystem. - * @param level A supplier that provides the current reef level. - * @param cameras The vision cameras. - * @return A command to drop algae from the reef. - */ - public static final Command dropAlgae( - Drive drive, - ElevatorFSM elevator, - V3_EpsilonManipulator manipulator, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Supplier level, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefAlgae(drive, cameras), - Commands.sequence( - superstructure - .runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.INTAKE_REEF_L3; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.INTAKE_REEF_L2; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }) - .until(() -> RobotState.isHasAlgae()), - Commands.waitSeconds(2.0), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) - .withTimeout(0.5)), - superstructure.runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.DROP_REEF_L3; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.DROP_REEF_L2; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }), - Commands.waitSeconds(1.0), - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); - } - - /** - * Creates a command sequence for the floor intake of algae. - * - * @param superstructure The superstructure subsystem. - * @return A command sequence for the floor intake. - */ - public static final Command floorIntakeSequence(V3_EpsilonSuperstructure superstructure) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.INTAKE_FLOOR, () -> RobotState.isHasAlgae())); - } - /** * Creates a command that posts the floor intake sequence, which can either go up or down based * on whether the robot has algae. diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 557f204d..537a5fca 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -44,11 +44,10 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIO; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOSim; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOTalonFX; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakeRollerStates; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerStates; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIO; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOSim; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerStates; import frc.robot.util.LoggedChoreo.ChoreoChooser; public class V3_EpsilonRobotContainer implements RobotContainer { @@ -212,12 +211,7 @@ public void configureButtonBindings() { // Driver bumpers driver .leftBumper() - .whileTrue(V3_EpsilonCompositeCommands.floorIntakeSequence(superstructure)) - .onFalse( - Commands.deadline( - V3_EpsilonCompositeCommands.postFloorIntakeSequence(superstructure), - Commands.runOnce(() -> intake.setRollerGoal(IntakeRollerStates.OUTTAKE))) - .andThen(Commands.runOnce(() -> intake.setRollerGoal(IntakeRollerStates.STOP)))); + .whileTrue(Commands.none()); // TODO: Algae ground intake (V3 intake is different) driver.rightBumper().onTrue(Commands.runOnce(() -> RobotState.toggleReefPost())); // Driver POV @@ -243,14 +237,8 @@ public void configureButtonBindings() { driver .start() .whileTrue( - V3_EpsilonCompositeCommands.dropAlgae( - drive, - elevator, - manipulator, - intake, - superstructure, - () -> RobotState.getReefAlignData().algaeIntakeHeight(), - RobotCameras.V3_EPSILON_CAMS)); // Remove the extra dot here + Commands + .none()); // TODO: add drop algae (V3 drop is going to be significatly different) // Operator face buttons operator.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 375d3e85..6b2b4261 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -3,6 +3,7 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotState; import frc.robot.RobotState.RobotMode; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; @@ -16,7 +17,9 @@ import java.util.Map; import java.util.Optional; import java.util.Queue; +import java.util.Set; import java.util.function.BooleanSupplier; +import java.util.function.DoubleSupplier; import java.util.function.Supplier; import lombok.Getter; import org.jgrapht.Graph; @@ -355,6 +358,66 @@ public Command runGoalUntil( return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); } + /** + * Converts a ReefState (field-level enum) into a corresponding elevator goal and runs it. + * + * @param goal Supplier of ReefState + * @return Command to move to the elevator position for the reef level + */ + public Command runReefGoal(Supplier goal) { + return runGoal( + () -> { + // Translate ReefState to superstructure state + switch (goal.get()) { + case L1: + return V3_EpsilonSuperstructureStates.L1_PREP; + case L2: + return V3_EpsilonSuperstructureStates.L2_PREP; + case L3: + return V3_EpsilonSuperstructureStates.L3_PREP; + case L4: + return V3_EpsilonSuperstructureStates.L4_PREP; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }); + } + + /** + * Moves to a scoring position, executes the score action for a fixed time, then returns to pose. + * + * @param goal Supplier of the ReefState (target height/level) + * @return Command to run the score cycle (pose → action → timeout → pose) + */ + public Command runReefScoreGoal(Supplier goal) { + // Run appropriate action sequence depending on reef level + return runActionWithTimeout( + () -> + switch (goal.get()) { + case L1 -> V3_EpsilonSuperstructureStates.L1_PREP; + case L2 -> V3_EpsilonSuperstructureStates.L2_PREP; + case L3 -> V3_EpsilonSuperstructureStates.L3_PREP; + case L4 -> V3_EpsilonSuperstructureStates.L4_PREP; + default -> V3_EpsilonSuperstructureStates.STOW_DOWN; + }, + () -> + switch (goal.get()) { + case L1 -> V3_EpsilonSuperstructureStates.L1_PREP; + case L2 -> V3_EpsilonSuperstructureStates.L2_PREP; + case L3 -> V3_EpsilonSuperstructureStates.L3_PREP; + case L4 -> V3_EpsilonSuperstructureStates.L4_PREP; + default -> V3_EpsilonSuperstructureStates.STOW_DOWN; + }, + () -> + switch (goal.get()) { + case L1 -> 0.8; + case L2 -> 0.15; + case L3 -> 0.15; + case L4 -> 0.4; + default -> 0; + }); + } + /** * Returns a short command to run the previous state, useful for temporary state restoration. * @@ -382,6 +445,17 @@ public Command runActionWithTimeout( .finallyDo(() -> setGoal(pose)); // Return to original pose } + public Command runActionWithTimeout( + Supplier pose, + Supplier action, + DoubleSupplier timeout) { + return Commands.sequence( + runGoal(action), // Run the action + Commands.waitUntil(() -> atGoal()), + Commands.defer(() -> Commands.waitSeconds(timeout.getAsDouble()), Set.of())) + .finallyDo(() -> setGoal(pose.get())); // Return to original pose + } + /** * Checks if the elevator is at its goal position. * diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index 4c573a98..14abf24b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -5,7 +5,6 @@ import frc.robot.subsystems.shared.elevator.Elevator; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; - import java.util.ArrayList; import java.util.List; import lombok.Builder; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index f4df5916..04850a3b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -6,7 +6,6 @@ import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; -import frc.robot.subsystems.v3_Epsilon.intake.IntakeIOInputsAutoLogged; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakeRollerStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakeState; @@ -21,6 +20,7 @@ public class V3_EpsilonIntake { @Getter @AutoLogOutput(key = "Intake/Pivot Goal") private IntakeState pivotGoal; + @Getter @AutoLogOutput(key = "Intake/Roller Goal") private IntakeRollerStates rollerGoal = IntakeRollerStates.STOP; @@ -53,8 +53,8 @@ public boolean hasCoral() { @AutoLogOutput(key = "Intake/At Goal") public boolean atGoal() { - return Math.abs(inputs.pivotPosition.getRadians() - - pivotGoal.getAngle().getRadians()) < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); + return Math.abs(inputs.pivotPosition.getRadians() - pivotGoal.getAngle().getRadians()) + < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); } public void waitUntilIntakeAtGoal() { @@ -76,13 +76,15 @@ public Command waitUntilPivotAtGoal() { } public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { - SysIdRoutine characterizationRoutine = new SysIdRoutine( - new SysIdRoutine.Config( - Volts.of(0.2).per(Second), - Volts.of(3.5), - Seconds.of(8), - (state) -> Logger.recordOutput("Intake/SysID State", state.toString())), - new SysIdRoutine.Mechanism((volts) -> io.setPivotVoltage(volts.in(Volts)), null, superstructure)); + SysIdRoutine characterizationRoutine = + new SysIdRoutine( + new SysIdRoutine.Config( + Volts.of(0.2).per(Second), + Volts.of(3.5), + Seconds.of(8), + (state) -> Logger.recordOutput("Intake/SysID State", state.toString())), + new SysIdRoutine.Mechanism( + (volts) -> io.setPivotVoltage(volts.in(Volts)), null, superstructure)); return Commands.sequence( Commands.runOnce(() -> isClosedLoop = false), Commands.runOnce(() -> characterizationRoutine.quasistatic(Direction.kForward)), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index e3500119..fb24dc0c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -9,13 +9,11 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants; -import frc.robot.subsystems.v3_Epsilon.manipulator.ManipulatorIOInputsAutoLogged; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerStates; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.PivotState; -import lombok.Getter; - import java.util.Set; +import lombok.Getter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; @@ -26,9 +24,11 @@ public class V3_EpsilonManipulator { @Getter @AutoLogOutput(key = "Manipulator/Pivot State") private PivotState pivotGoal; + @Getter @AutoLogOutput(key = "Manipulator/Roller State") private ManipulatorRollerStates rollerGoal; + private boolean isClosedLoop; public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { @@ -49,15 +49,13 @@ public void periodic() { io.setPivotGoal(pivotGoal.getAngle()); } - if (hasAlgae() && Set.of( - ManipulatorRollerStates.CORAL_INTAKE, - ManipulatorRollerStates.STOP) - .contains(rollerGoal)) { + if (hasAlgae() + && Set.of(ManipulatorRollerStates.CORAL_INTAKE, ManipulatorRollerStates.STOP) + .contains(rollerGoal)) { io.setRollerVoltage(holdVoltage()); } else { io.setRollerVoltage(rollerGoal.getVoltage()); } - } @AutoLogOutput(key = "Manipulator/Has Coral") @@ -82,13 +80,15 @@ public Command runPivot(double volts) { } public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { - SysIdRoutine algaeCharacterizationRoutine = new SysIdRoutine( - new SysIdRoutine.Config( - Volts.of(0.2).per(Second), - Volts.of(3.5), - Seconds.of(5), - (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), - new SysIdRoutine.Mechanism((volts) -> io.setPivotVoltage(volts.in(Volts)), null, superstructure)); + SysIdRoutine algaeCharacterizationRoutine = + new SysIdRoutine( + new SysIdRoutine.Config( + Volts.of(0.2).per(Second), + Volts.of(3.5), + Seconds.of(5), + (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), + new SysIdRoutine.Mechanism( + (volts) -> io.setPivotVoltage(volts.in(Volts)), null, superstructure)); return Commands.sequence( Commands.runOnce(() -> isClosedLoop = false), @@ -139,9 +139,8 @@ public void updateArmConstraints(double maxAcceleration, double maxVelocity) { @AutoLogOutput(key = "Manipulator/Arm At Goal") public boolean pivotAtGoal() { - return inputs.armPosition.getRadians() - - pivotGoal.getAngle().getRadians() <= V2_RedundancyManipulatorConstants.CONSTRAINTS.GOAL_TOLERANCE_RADIANS() - .get(); + return inputs.armPosition.getRadians() - pivotGoal.getAngle().getRadians() + <= V2_RedundancyManipulatorConstants.CONSTRAINTS.GOAL_TOLERANCE_RADIANS().get(); } public Command waitUntilPivotAtGoal() { @@ -179,9 +178,9 @@ public void setManipulatorState(V3_EpsilonManipulatorConstants.PivotState state) public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerStates rollerGoal) { if (hasAlgae() && Set.of( - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.ALGAE_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.CORAL_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP) + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.ALGAE_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.CORAL_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerStates.STOP) .contains(rollerGoal)) { io.setRollerVoltage(holdVoltage()); From 718d18cbbb9ae038cb067dca03dde7d61918721e Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Sun, 31 Aug 2025 00:34:14 -0400 Subject: [PATCH 057/180] .dot in progress --- .../superstructure/Superstructure.dot | 691 ++++++++++++++---- 1 file changed, 560 insertions(+), 131 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index 18ef63af..110a70a1 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -2,149 +2,578 @@ digraph Superstructure { /* * Graphviz DOT file for the superstructure state machine. * States are represented as nodes, and transitions are represented as edges. - */ + */ // Node definitions - start [color = red] + START + STOW_DOWN + GROUND_ACQUISITION + GROUND_INTAKE + L1 + L2 + L3 + L4 + L1_SCORE + L2_SCORE + L3_SCORE + L4_SCORE + HANDOFF + INTERMEDIATE_WAIT_FOR_ELEVATOR + INTERMEDIATE_WAIT_FOR_ARM + STOW_UP + L2_ALGAE + L2_ALGAE_INTAKE + L3_ALGAE + L3_ALGAE_INTAKE + PROCESSOR + PROCESSOR_SCORE + BARGE + BARGE_SCORE - stow_down [color = green] + // Edge definitions (All-to-all pairing) + START -> STOW_DOWN - ground_intake [color = green] + STOW_DOWN -> GROUND_ACQUISITION + STOW_DOWN -> L1 + STOW_DOWN -> L2 + STOW_DOWN -> L3 + STOW_DOWN -> L4 + STOW_DOWN -> HANDOFF [label = "coordinated motion"] + STOW_DOWN -> INTERMEDIATE_WAIT_FOR_ELEVATOR + STOW_DOWN -> INTERMEDIATE_WAIT_FOR_ARM + STOW_DOWN -> STOW_UP + STOW_DOWN -> L2_ALGAE + STOW_DOWN -> L3_ALGAE + STOW_DOWN -> PROCESSOR + STOW_DOWN -> BARGE - L1_score [color = green] - L2_score [color = green] - L3_score [color = green] - L4_score [color = green] - - stow_up [color = cyan] - - L2_algae_prep [color = blue] - L3_algae_prep [color = blue] - - L2_algae_intake [color = blue] - L3_algae_intake [color = blue] + // left off here - barge_prep [color = blue] - barge_score [color = blue] - - processor_prep [color = blue] - processor_score [color = blue] + GROUND_ACQUISITION -> START + GROUND_ACQUISITION -> STOW_DOWN + GROUND_ACQUISITION -> GROUND_INTAKE + GROUND_ACQUISITION -> L1 + GROUND_ACQUISITION -> L2 + GROUND_ACQUISITION -> L3 + GROUND_ACQUISITION -> L4 + GROUND_ACQUISITION -> L1_SCORE + GROUND_ACQUISITION -> L2_SCORE + GROUND_ACQUISITION -> L3_SCORE + GROUND_ACQUISITION -> L4_SCORE + GROUND_ACQUISITION -> HANDOFF + GROUND_ACQUISITION -> INTERMEDIATE_WAIT_FOR_ELEVATOR + GROUND_ACQUISITION -> INTERMEDIATE_WAIT_FOR_ARM + GROUND_ACQUISITION -> STOW_UP + GROUND_ACQUISITION -> L2_ALGAE + GROUND_ACQUISITION -> L2_ALGAE_INTAKE + GROUND_ACQUISITION -> L3_ALGAE + GROUND_ACQUISITION -> L3_ALGAE_INTAKE + GROUND_ACQUISITION -> PROCESSOR + GROUND_ACQUISITION -> PROCESSOR_SCORE + GROUND_ACQUISITION -> BARGE + GROUND_ACQUISITION -> BARGE_SCORE - # Prep states - L1_prep [color = green] - L2_prep [color = green] - L3_prep [color = green] - L4_prep [color = green] + GROUND_INTAKE -> START + GROUND_INTAKE -> STOW_DOWN + GROUND_INTAKE -> GROUND_ACQUISITION + GROUND_INTAKE -> L1 + GROUND_INTAKE -> L2 + GROUND_INTAKE -> L3 + GROUND_INTAKE -> L4 + GROUND_INTAKE -> L1_SCORE + GROUND_INTAKE -> L2_SCORE + GROUND_INTAKE -> L3_SCORE + GROUND_INTAKE -> L4_SCORE + GROUND_INTAKE -> HANDOFF + GROUND_INTAKE -> INTERMEDIATE_WAIT_FOR_ELEVATOR + GROUND_INTAKE -> INTERMEDIATE_WAIT_FOR_ARM + GROUND_INTAKE -> STOW_UP + GROUND_INTAKE -> L2_ALGAE + GROUND_INTAKE -> L2_ALGAE_INTAKE + GROUND_INTAKE -> L3_ALGAE + GROUND_INTAKE -> L3_ALGAE_INTAKE + GROUND_INTAKE -> PROCESSOR + GROUND_INTAKE -> PROCESSOR_SCORE + GROUND_INTAKE -> BARGE + GROUND_INTAKE -> BARGE_SCORE - # Transition States - L2_transition [color = green] - L3_transition [color = green] - L4_transition [color = green] + L1 -> START + L1 -> STOW_DOWN + L1 -> GROUND_ACQUISITION + L1 -> GROUND_INTAKE + L1 -> L2 + L1 -> L3 + L1 -> L4 + L1 -> L1_SCORE + L1 -> L2_SCORE + L1 -> L3_SCORE + L1 -> L4_SCORE + L1 -> HANDOFF + L1 -> INTERMEDIATE_WAIT_FOR_ELEVATOR + L1 -> INTERMEDIATE_WAIT_FOR_ARM + L1 -> STOW_UP + L1 -> L2_ALGAE + L1 -> L2_ALGAE_INTAKE + L1 -> L3_ALGAE + L1 -> L3_ALGAE_INTAKE + L1 -> PROCESSOR + L1 -> PROCESSOR_SCORE + L1 -> BARGE + L1 -> BARGE_SCORE - climb [color = red] - - # Transition states are inherently wait_for_elevator states but for different levels - intermediate_wait_for_elevator [color = green] - - # Basic Handoff Edges - start -> stow_down [color = red] - stow_down -> stow_up [color = green] - handoff -> stow_up [color = green] - - stow_up -> L2_transition [color = green] - stow_up -> L3_transition [color = green] - stow_up -> L4_transition [color = green] - - # Coral Edges - handoff -> L1_prep [color = green] - handoff -> L2_transition [color = green] - handoff -> L3_transition [color = green] - handoff -> L4_transition [color = green] - - L2_transition -> handoff [color = green] - L3_transition -> handoff [color = green] - L4_transition -> handoff [color = green] - - handoff -> L2_prep [color = green] - handoff -> L3_prep [color = green] - handoff -> L4_prep [color = green] + L2 -> START + L2 -> STOW_DOWN + L2 -> GROUND_ACQUISITION + L2 -> GROUND_INTAKE + L2 -> L1 + L2 -> L3 + L2 -> L4 + L2 -> L1_SCORE + L2 -> L2_SCORE + L2 -> L3_SCORE + L2 -> L4_SCORE + L2 -> HANDOFF + L2 -> INTERMEDIATE_WAIT_FOR_ELEVATOR + L2 -> INTERMEDIATE_WAIT_FOR_ARM + L2 -> STOW_UP + L2 -> L2_ALGAE + L2 -> L2_ALGAE_INTAKE + L2 -> L3_ALGAE + L2 -> L3_ALGAE_INTAKE + L2 -> PROCESSOR + L2 -> PROCESSOR_SCORE + L2 -> BARGE + L2 -> BARGE_SCORE - stow_down -> intermediate_wait_for_elevator [color = green] - intermediate_wait_for_elevator -> handoff [color = green] - ground_intake -> L1_prep [color = green] - stow_down -> ground_intake [color = green] + L3 -> START + L3 -> STOW_DOWN + L3 -> GROUND_ACQUISITION + L3 -> GROUND_INTAKE + L3 -> L1 + L3 -> L2 + L3 -> L4 + L3 -> L1_SCORE + L3 -> L2_SCORE + L3 -> L3_SCORE + L3 -> L4_SCORE + L3 -> HANDOFF + L3 -> INTERMEDIATE_WAIT_FOR_ELEVATOR + L3 -> INTERMEDIATE_WAIT_FOR_ARM + L3 -> STOW_UP + L3 -> L2_ALGAE + L3 -> L2_ALGAE_INTAKE + L3 -> L3_ALGAE + L3 -> L3_ALGAE_INTAKE + L3 -> PROCESSOR + L3 -> PROCESSOR_SCORE + L3 -> BARGE + L3 -> BARGE_SCORE - L1_prep -> ground_intake [color = green] + L4 -> START + L4 -> STOW_DOWN + L4 -> GROUND_ACQUISITION + L4 -> GROUND_INTAKE + L4 -> L1 + L4 -> L2 + L4 -> L3 + L4 -> L1_SCORE + L4 -> L2_SCORE + L4 -> L3_SCORE + L4 -> L4_SCORE + L4 -> HANDOFF + L4 -> INTERMEDIATE_WAIT_FOR_ELEVATOR + L4 -> INTERMEDIATE_WAIT_FOR_ARM + L4 -> STOW_UP + L4 -> L2_ALGAE + L4 -> L2_ALGAE_INTAKE + L4 -> L3_ALGAE + L4 -> L3_ALGAE_INTAKE + L4 -> PROCESSOR + L4 -> PROCESSOR_SCORE + L4 -> BARGE + L4 -> BARGE_SCORE - L1_prep -> L1_score [color = green] - L2_prep -> L2_score [color = green] - L3_prep -> L3_score [color = green] - L4_prep -> L4_score [color = green] + L1_SCORE -> START + L1_SCORE -> STOW_DOWN + L1_SCORE -> GROUND_ACQUISITION + L1_SCORE -> GROUND_INTAKE + L1_SCORE -> L1 + L1_SCORE -> L2 + L1_SCORE -> L3 + L1_SCORE -> L4 + L1_SCORE -> L2_SCORE + L1_SCORE -> L3_SCORE + L1_SCORE -> L4_SCORE + L1_SCORE -> HANDOFF + L1_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR + L1_SCORE -> INTERMEDIATE_WAIT_FOR_ARM + L1_SCORE -> STOW_UP + L1_SCORE -> L2_ALGAE + L1_SCORE -> L2_ALGAE_INTAKE + L1_SCORE -> L3_ALGAE + L1_SCORE -> L3_ALGAE_INTAKE + L1_SCORE -> PROCESSOR + L1_SCORE -> PROCESSOR_SCORE + L1_SCORE -> BARGE + L1_SCORE -> BARGE_SCORE - L2_prep -> intermediate_wait_for_elevator [color = green] - L3_prep -> intermediate_wait_for_elevator [color = green] - L4_prep -> intermediate_wait_for_elevator [color = green] - - L1_score -> ground_intake [color = green] - L1_prep -> handoff [color = green] - L1_score -> handoff [color = green] - - L2_score -> intermediate_wait_for_elevator [color = green] - L3_score -> intermediate_wait_for_elevator [color = green] - L4_score -> intermediate_wait_for_elevator [color = green] - - L2_prep -> L3_transition [color = green] - L2_prep -> L4_transition [color = green] - L3_prep -> L2_transition [color = green] - L3_prep -> L4_transition [color = green] - L4_prep -> L3_transition [color = green] - L4_prep -> L2_transition [color = green] - - L2_transition -> L2_prep [color = green] - L3_transition -> L3_prep [color = green] - L4_transition -> L4_prep [color = green] - - L2_prep -> L2_transition [color = green] - L3_prep -> L3_transition [color = green] - L4_prep -> L4_transition [color = green] - - # Algae Edges - stow_up -> L2_algae_prep [color = blue] - stow_up -> L3_algae_prep [color = blue] - stow_up -> barge_prep [color = blue] - stow_up -> processor_prep [color = blue] - - stow_down -> L2_algae_prep [color = blue] - stow_down -> L3_algae_prep [color = blue] - - L2_algae_prep -> barge_prep [color = blue] - L3_algae_prep -> barge_prep [color = blue] - - L2_algae_prep -> processor_prep [color = blue] - L3_algae_prep -> processor_prep [color = blue] - - L2_algae_prep -> stow_up [color = blue] - L3_algae_prep -> stow_up [color = blue] - - L2_algae_prep -> L2_algae_intake [color = blue] - L2_algae_intake -> L2_algae_prep [color = blue] - L3_algae_intake -> L3_algae_prep [color = blue] - L3_algae_prep -> L3_algae_intake [color = blue] - - L2_algae_intake -> stow_up [color = blue] - L3_algae_intake -> stow_up [color = blue] - - barge_prep -> barge_score [color = blue] - processor_prep -> processor_score [color = blue] - - processor_score -> stow_up [color = blue] - processor_score -> stow_down [color = blue] - processor_score -> handoff [color = blue] - - barge_score -> stow_up [color = blue] - barge_score -> stow_down [color = blue] - barge_score -> handoff [color = blue] + L2_SCORE -> START + L2_SCORE -> STOW_DOWN + L2_SCORE -> GROUND_ACQUISITION + L2_SCORE -> GROUND_INTAKE + L2_SCORE -> L1 + L2_SCORE -> L2 + L2_SCORE -> L3 + L2_SCORE -> L4 + L2_SCORE -> L1_SCORE + L2_SCORE -> L3_SCORE + L2_SCORE -> L4_SCORE + L2_SCORE -> HANDOFF + L2_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR + L2_SCORE -> INTERMEDIATE_WAIT_FOR_ARM + L2_SCORE -> STOW_UP + L2_SCORE -> L2_ALGAE + L2_SCORE -> L2_ALGAE_INTAKE + L2_SCORE -> L3_ALGAE + L2_SCORE -> L3_ALGAE_INTAKE + L2_SCORE -> PROCESSOR + L2_SCORE -> PROCESSOR_SCORE + L2_SCORE -> BARGE + L2_SCORE -> BARGE_SCORE + + L3_SCORE -> START + L3_SCORE -> STOW_DOWN + L3_SCORE -> GROUND_ACQUISITION + L3_SCORE -> GROUND_INTAKE + L3_SCORE -> L1 + L3_SCORE -> L2 + L3_SCORE -> L3 + L3_SCORE -> L4 + L3_SCORE -> L1_SCORE + L3_SCORE -> L2_SCORE + L3_SCORE -> L4_SCORE + L3_SCORE -> HANDOFF + L3_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR + L3_SCORE -> INTERMEDIATE_WAIT_FOR_ARM + L3_SCORE -> STOW_UP + L3_SCORE -> L2_ALGAE + L3_SCORE -> L2_ALGAE_INTAKE + L3_SCORE -> L3_ALGAE + L3_SCORE -> L3_ALGAE_INTAKE + L3_SCORE -> PROCESSOR + L3_SCORE -> PROCESSOR_SCORE + L3_SCORE -> BARGE + L3_SCORE -> BARGE_SCORE + + L4_SCORE -> START + L4_SCORE -> STOW_DOWN + L4_SCORE -> GROUND_ACQUISITION + L4_SCORE -> GROUND_INTAKE + L4_SCORE -> L1 + L4_SCORE -> L2 + L4_SCORE -> L3 + L4_SCORE -> L4 + L4_SCORE -> L1_SCORE + L4_SCORE -> L2_SCORE + L4_SCORE -> L3_SCORE + L4_SCORE -> HANDOFF + L4_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR + L4_SCORE -> INTERMEDIATE_WAIT_FOR_ARM + L4_SCORE -> STOW_UP + L4_SCORE -> L2_ALGAE + L4_SCORE -> L2_ALGAE_INTAKE + L4_SCORE -> L3_ALGAE + L4_SCORE -> L3_ALGAE_INTAKE + L4_SCORE -> PROCESSOR + L4_SCORE -> PROCESSOR_SCORE + L4_SCORE -> BARGE + L4_SCORE -> BARGE_SCORE + + HANDOFF -> START + HANDOFF -> STOW_DOWN + HANDOFF -> GROUND_ACQUISITION + HANDOFF -> GROUND_INTAKE + HANDOFF -> L1 + HANDOFF -> L2 + HANDOFF -> L3 + HANDOFF -> L4 + HANDOFF -> L1_SCORE + HANDOFF -> L2_SCORE + HANDOFF -> L3_SCORE + HANDOFF -> L4_SCORE + HANDOFF -> INTERMEDIATE_WAIT_FOR_ELEVATOR + HANDOFF -> INTERMEDIATE_WAIT_FOR_ARM + HANDOFF -> STOW_UP + HANDOFF -> L2_ALGAE + HANDOFF -> L2_ALGAE_INTAKE + HANDOFF -> L3_ALGAE + HANDOFF -> L3_ALGAE_INTAKE + HANDOFF -> PROCESSOR + HANDOFF -> PROCESSOR_SCORE + HANDOFF -> BARGE + HANDOFF -> BARGE_SCORE + + INTERMEDIATE_WAIT_FOR_ELEVATOR -> START + INTERMEDIATE_WAIT_FOR_ELEVATOR -> STOW_DOWN + INTERMEDIATE_WAIT_FOR_ELEVATOR -> GROUND_ACQUISITION + INTERMEDIATE_WAIT_FOR_ELEVATOR -> GROUND_INTAKE + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L1 + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L2 + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L3 + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L4 + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L1_SCORE + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L2_SCORE + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L3_SCORE + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L4_SCORE + INTERMEDIATE_WAIT_FOR_ELEVATOR -> HANDOFF + INTERMEDIATE_WAIT_FOR_ELEVATOR -> INTERMEDIATE_WAIT_FOR_ARM + INTERMEDIATE_WAIT_FOR_ELEVATOR -> STOW_UP + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L2_ALGAE + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L2_ALGAE_INTAKE + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L3_ALGAE + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L3_ALGAE_INTAKE + INTERMEDIATE_WAIT_FOR_ELEVATOR -> PROCESSOR + INTERMEDIATE_WAIT_FOR_ELEVATOR -> PROCESSOR_SCORE + INTERMEDIATE_WAIT_FOR_ELEVATOR -> BARGE + INTERMEDIATE_WAIT_FOR_ELEVATOR -> BARGE_SCORE + + INTERMEDIATE_WAIT_FOR_ARM -> START + INTERMEDIATE_WAIT_FOR_ARM -> STOW_DOWN + INTERMEDIATE_WAIT_FOR_ARM -> GROUND_ACQUISITION + INTERMEDIATE_WAIT_FOR_ARM -> GROUND_INTAKE + INTERMEDIATE_WAIT_FOR_ARM -> L1 + INTERMEDIATE_WAIT_FOR_ARM -> L2 + INTERMEDIATE_WAIT_FOR_ARM -> L3 + INTERMEDIATE_WAIT_FOR_ARM -> L4 + INTERMEDIATE_WAIT_FOR_ARM -> L1_SCORE + INTERMEDIATE_WAIT_FOR_ARM -> L2_SCORE + INTERMEDIATE_WAIT_FOR_ARM -> L3_SCORE + INTERMEDIATE_WAIT_FOR_ARM -> L4_SCORE + INTERMEDIATE_WAIT_FOR_ARM -> HANDOFF + INTERMEDIATE_WAIT_FOR_ARM -> INTERMEDIATE_WAIT_FOR_ELEVATOR + INTERMEDIATE_WAIT_FOR_ARM -> STOW_UP + INTERMEDIATE_WAIT_FOR_ARM -> L2_ALGAE + INTERMEDIATE_WAIT_FOR_ARM -> L2_ALGAE_INTAKE + INTERMEDIATE_WAIT_FOR_ARM -> L3_ALGAE + INTERMEDIATE_WAIT_FOR_ARM -> L3_ALGAE_INTAKE + INTERMEDIATE_WAIT_FOR_ARM -> PROCESSOR + INTERMEDIATE_WAIT_FOR_ARM -> PROCESSOR_SCORE + INTERMEDIATE_WAIT_FOR_ARM -> BARGE + INTERMEDIATE_WAIT_FOR_ARM -> BARGE_SCORE + + STOW_UP -> START + STOW_UP -> STOW_DOWN + STOW_UP -> GROUND_ACQUISITION + STOW_UP -> GROUND_INTAKE + STOW_UP -> L1 + STOW_UP -> L2 + STOW_UP -> L3 + STOW_UP -> L4 + STOW_UP -> L1_SCORE + STOW_UP -> L2_SCORE + STOW_UP -> L3_SCORE + STOW_UP -> L4_SCORE + STOW_UP -> HANDOFF + STOW_UP -> INTERMEDIATE_WAIT_FOR_ELEVATOR + STOW_UP -> INTERMEDIATE_WAIT_FOR_ARM + STOW_UP -> L2_ALGAE + STOW_UP -> L2_ALGAE_INTAKE + STOW_UP -> L3_ALGAE + STOW_UP -> L3_ALGAE_INTAKE + STOW_UP -> PROCESSOR + STOW_UP -> PROCESSOR_SCORE + STOW_UP -> BARGE + STOW_UP -> BARGE_SCORE + + L2_ALGAE -> START + L2_ALGAE -> STOW_DOWN + L2_ALGAE -> GROUND_ACQUISITION + L2_ALGAE -> GROUND_INTAKE + L2_ALGAE -> L1 + L2_ALGAE -> L2 + L2_ALGAE -> L3 + L2_ALGAE -> L4 + L2_ALGAE -> L1_SCORE + L2_ALGAE -> L2_SCORE + L2_ALGAE -> L3_SCORE + L2_ALGAE -> L4_SCORE + L2_ALGAE -> HANDOFF + L2_ALGAE -> INTERMEDIATE_WAIT_FOR_ELEVATOR + L2_ALGAE -> INTERMEDIATE_WAIT_FOR_ARM + L2_ALGAE -> STOW_UP + L2_ALGAE -> L2_ALGAE_INTAKE + L2_ALGAE -> L3_ALGAE + L2_ALGAE -> L3_ALGAE_INTAKE + L2_ALGAE -> PROCESSOR + L2_ALGAE -> PROCESSOR_SCORE + L2_ALGAE -> BARGE + L2_ALGAE -> BARGE_SCORE + + L2_ALGAE_INTAKE -> START + L2_ALGAE_INTAKE -> STOW_DOWN + L2_ALGAE_INTAKE -> GROUND_ACQUISITION + L2_ALGAE_INTAKE -> GROUND_INTAKE + L2_ALGAE_INTAKE -> L1 + L2_ALGAE_INTAKE -> L2 + L2_ALGAE_INTAKE -> L3 + L2_ALGAE_INTAKE -> L4 + L2_ALGAE_INTAKE -> L1_SCORE + L2_ALGAE_INTAKE -> L2_SCORE + L2_ALGAE_INTAKE -> L3_SCORE + L2_ALGAE_INTAKE -> L4_SCORE + L2_ALGAE_INTAKE -> HANDOFF + L2_ALGAE_INTAKE -> INTERMEDIATE_WAIT_FOR_ELEVATOR + L2_ALGAE_INTAKE -> INTERMEDIATE_WAIT_FOR_ARM + L2_ALGAE_INTAKE -> STOW_UP + L2_ALGAE_INTAKE -> L2_ALGAE + L2_ALGAE_INTAKE -> L3_ALGAE + L2_ALGAE_INTAKE -> L3_ALGAE_INTAKE + L2_ALGAE_INTAKE -> PROCESSOR + L2_ALGAE_INTAKE -> PROCESSOR_SCORE + L2_ALGAE_INTAKE -> BARGE + L2_ALGAE_INTAKE -> BARGE_SCORE + + L3_ALGAE -> START + L3_ALGAE -> STOW_DOWN + L3_ALGAE -> GROUND_ACQUISITION + L3_ALGAE -> GROUND_INTAKE + L3_ALGAE -> L1 + L3_ALGAE -> L2 + L3_ALGAE -> L3 + L3_ALGAE -> L4 + L3_ALGAE -> L1_SCORE + L3_ALGAE -> L2_SCORE + L3_ALGAE -> L3_SCORE + L3_ALGAE -> L4_SCORE + L3_ALGAE -> HANDOFF + L3_ALGAE -> INTERMEDIATE_WAIT_FOR_ELEVATOR + L3_ALGAE -> INTERMEDIATE_WAIT_FOR_ARM + L3_ALGAE -> STOW_UP + L3_ALGAE -> L2_ALGAE + L3_ALGAE -> L2_ALGAE_INTAKE + L3_ALGAE -> L3_ALGAE_INTAKE + L3_ALGAE -> PROCESSOR + L3_ALGAE -> PROCESSOR_SCORE + L3_ALGAE -> BARGE + L3_ALGAE -> BARGE_SCORE + + L3_ALGAE_INTAKE -> START + L3_ALGAE_INTAKE -> STOW_DOWN + L3_ALGAE_INTAKE -> GROUND_ACQUISITION + L3_ALGAE_INTAKE -> GROUND_INTAKE + L3_ALGAE_INTAKE -> L1 + L3_ALGAE_INTAKE -> L2 + L3_ALGAE_INTAKE -> L3 + L3_ALGAE_INTAKE -> L4 + L3_ALGAE_INTAKE -> L1_SCORE + L3_ALGAE_INTAKE -> L2_SCORE + L3_ALGAE_INTAKE -> L3_SCORE + L3_ALGAE_INTAKE -> L4_SCORE + L3_ALGAE_INTAKE -> HANDOFF + L3_ALGAE_INTAKE -> INTERMEDIATE_WAIT_FOR_ELEVATOR + L3_ALGAE_INTAKE -> INTERMEDIATE_WAIT_FOR_ARM + L3_ALGAE_INTAKE -> STOW_UP + L3_ALGAE_INTAKE -> L2_ALGAE + L3_ALGAE_INTAKE -> L2_ALGAE_INTAKE + L3_ALGAE_INTAKE -> L3_ALGAE + L3_ALGAE_INTAKE -> PROCESSOR + L3_ALGAE_INTAKE -> PROCESSOR_SCORE + L3_ALGAE_INTAKE -> BARGE + L3_ALGAE_INTAKE -> BARGE_SCORE + + PROCESSOR -> START + PROCESSOR -> STOW_DOWN + PROCESSOR -> GROUND_ACQUISITION + PROCESSOR -> GROUND_INTAKE + PROCESSOR -> L1 + PROCESSOR -> L2 + PROCESSOR -> L3 + PROCESSOR -> L4 + PROCESSOR -> L1_SCORE + PROCESSOR -> L2_SCORE + PROCESSOR -> L3_SCORE + PROCESSOR -> L4_SCORE + PROCESSOR -> HANDOFF + PROCESSOR -> INTERMEDIATE_WAIT_FOR_ELEVATOR + PROCESSOR -> INTERMEDIATE_WAIT_FOR_ARM + PROCESSOR -> STOW_UP + PROCESSOR -> L2_ALGAE + PROCESSOR -> L2_ALGAE_INTAKE + PROCESSOR -> L3_ALGAE + PROCESSOR -> L3_ALGAE_INTAKE + PROCESSOR -> PROCESSOR_SCORE + PROCESSOR -> BARGE + PROCESSOR -> BARGE_SCORE + + PROCESSOR_SCORE -> START + PROCESSOR_SCORE -> STOW_DOWN + PROCESSOR_SCORE -> GROUND_ACQUISITION + PROCESSOR_SCORE -> GROUND_INTAKE + PROCESSOR_SCORE -> L1 + PROCESSOR_SCORE -> L2 + PROCESSOR_SCORE -> L3 + PROCESSOR_SCORE -> L4 + PROCESSOR_SCORE -> L1_SCORE + PROCESSOR_SCORE -> L2_SCORE + PROCESSOR_SCORE -> L3_SCORE + PROCESSOR_SCORE -> L4_SCORE + PROCESSOR_SCORE -> HANDOFF + PROCESSOR_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR + PROCESSOR_SCORE -> INTERMEDIATE_WAIT_FOR_ARM + PROCESSOR_SCORE -> STOW_UP + PROCESSOR_SCORE -> L2_ALGAE + PROCESSOR_SCORE -> L2_ALGAE_INTAKE + PROCESSOR_SCORE -> L3_ALGAE + PROCESSOR_SCORE -> L3_ALGAE_INTAKE + PROCESSOR_SCORE -> PROCESSOR + PROCESSOR_SCORE -> BARGE + PROCESSOR_SCORE -> BARGE_SCORE + + BARGE -> START + BARGE -> STOW_DOWN + BARGE -> GROUND_ACQUISITION + BARGE -> GROUND_INTAKE + BARGE -> L1 + BARGE -> L2 + BARGE -> L3 + BARGE -> L4 + BARGE -> L1_SCORE + BARGE -> L2_SCORE + BARGE -> L3_SCORE + BARGE -> L4_SCORE + BARGE -> HANDOFF + BARGE -> INTERMEDIATE_WAIT_FOR_ELEVATOR + BARGE -> INTERMEDIATE_WAIT_FOR_ARM + BARGE -> STOW_UP + BARGE -> L2_ALGAE + BARGE -> L2_ALGAE_INTAKE + BARGE -> L3_ALGAE + BARGE -> L3_ALGAE_INTAKE + BARGE -> PROCESSOR + BARGE -> PROCESSOR_SCORE + BARGE -> BARGE_SCORE - L2_algae_prep -> L3_algae_prep [color = blue] - L3_algae_prep -> L2_algae_prep [color = blue] + BARGE_SCORE -> START + BARGE_SCORE -> STOW_DOWN + BARGE_SCORE -> GROUND_ACQUISITION + BARGE_SCORE -> GROUND_INTAKE + BARGE_SCORE -> L1 + BARGE_SCORE -> L2 + BARGE_SCORE -> L3 + BARGE_SCORE -> L4 + BARGE_SCORE -> L1_SCORE + BARGE_SCORE -> L2_SCORE + BARGE_SCORE -> L3_SCORE + BARGE_SCORE -> L4_SCORE + BARGE_SCORE -> HANDOFF + BARGE_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR + BARGE_SCORE -> INTERMEDIATE_WAIT_FOR_ARM + BARGE_SCORE -> STOW_UP + BARGE_SCORE -> L2_ALGAE + BARGE_SCORE -> L2_ALGAE_INTAKE + BARGE_SCORE -> L3_ALGAE + BARGE_SCORE -> L3_ALGAE_INTAKE + BARGE_SCORE -> PROCESSOR + BARGE_SCORE -> PROCESSOR_SCORE + BARGE_SCORE -> BARGE } \ No newline at end of file From 1c4f37500fc1b94e3ac270e429876e3a7fad7962 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Sun, 31 Aug 2025 12:54:26 -0400 Subject: [PATCH 058/180] finish dot file --- .../superstructure/Superstructure.dot | 308 ++---------------- 1 file changed, 21 insertions(+), 287 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index 110a70a1..5683555d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -33,8 +33,8 @@ digraph Superstructure { // Edge definitions (All-to-all pairing) START -> STOW_DOWN - STOW_DOWN -> GROUND_ACQUISITION - STOW_DOWN -> L1 + STOW_DOWN -> GROUND_ACQUISITION [label = "coordinated motion"] + STOW_DOWN -> L1 [label = "coordinated motion"] STOW_DOWN -> L2 STOW_DOWN -> L3 STOW_DOWN -> L4 @@ -47,533 +47,267 @@ digraph Superstructure { STOW_DOWN -> PROCESSOR STOW_DOWN -> BARGE - // left off here - - GROUND_ACQUISITION -> START GROUND_ACQUISITION -> STOW_DOWN GROUND_ACQUISITION -> GROUND_INTAKE GROUND_ACQUISITION -> L1 GROUND_ACQUISITION -> L2 GROUND_ACQUISITION -> L3 GROUND_ACQUISITION -> L4 - GROUND_ACQUISITION -> L1_SCORE - GROUND_ACQUISITION -> L2_SCORE - GROUND_ACQUISITION -> L3_SCORE - GROUND_ACQUISITION -> L4_SCORE GROUND_ACQUISITION -> HANDOFF GROUND_ACQUISITION -> INTERMEDIATE_WAIT_FOR_ELEVATOR GROUND_ACQUISITION -> INTERMEDIATE_WAIT_FOR_ARM GROUND_ACQUISITION -> STOW_UP GROUND_ACQUISITION -> L2_ALGAE - GROUND_ACQUISITION -> L2_ALGAE_INTAKE GROUND_ACQUISITION -> L3_ALGAE - GROUND_ACQUISITION -> L3_ALGAE_INTAKE GROUND_ACQUISITION -> PROCESSOR - GROUND_ACQUISITION -> PROCESSOR_SCORE GROUND_ACQUISITION -> BARGE - GROUND_ACQUISITION -> BARGE_SCORE - GROUND_INTAKE -> START GROUND_INTAKE -> STOW_DOWN GROUND_INTAKE -> GROUND_ACQUISITION GROUND_INTAKE -> L1 GROUND_INTAKE -> L2 GROUND_INTAKE -> L3 GROUND_INTAKE -> L4 - GROUND_INTAKE -> L1_SCORE - GROUND_INTAKE -> L2_SCORE - GROUND_INTAKE -> L3_SCORE - GROUND_INTAKE -> L4_SCORE GROUND_INTAKE -> HANDOFF GROUND_INTAKE -> INTERMEDIATE_WAIT_FOR_ELEVATOR GROUND_INTAKE -> INTERMEDIATE_WAIT_FOR_ARM GROUND_INTAKE -> STOW_UP GROUND_INTAKE -> L2_ALGAE - GROUND_INTAKE -> L2_ALGAE_INTAKE GROUND_INTAKE -> L3_ALGAE - GROUND_INTAKE -> L3_ALGAE_INTAKE GROUND_INTAKE -> PROCESSOR - GROUND_INTAKE -> PROCESSOR_SCORE GROUND_INTAKE -> BARGE - GROUND_INTAKE -> BARGE_SCORE - L1 -> START L1 -> STOW_DOWN L1 -> GROUND_ACQUISITION - L1 -> GROUND_INTAKE L1 -> L2 L1 -> L3 L1 -> L4 L1 -> L1_SCORE - L1 -> L2_SCORE - L1 -> L3_SCORE - L1 -> L4_SCORE L1 -> HANDOFF L1 -> INTERMEDIATE_WAIT_FOR_ELEVATOR L1 -> INTERMEDIATE_WAIT_FOR_ARM L1 -> STOW_UP L1 -> L2_ALGAE - L1 -> L2_ALGAE_INTAKE L1 -> L3_ALGAE - L1 -> L3_ALGAE_INTAKE L1 -> PROCESSOR - L1 -> PROCESSOR_SCORE L1 -> BARGE - L1 -> BARGE_SCORE - L2 -> START L2 -> STOW_DOWN L2 -> GROUND_ACQUISITION - L2 -> GROUND_INTAKE L2 -> L1 L2 -> L3 L2 -> L4 - L2 -> L1_SCORE L2 -> L2_SCORE - L2 -> L3_SCORE - L2 -> L4_SCORE L2 -> HANDOFF L2 -> INTERMEDIATE_WAIT_FOR_ELEVATOR L2 -> INTERMEDIATE_WAIT_FOR_ARM L2 -> STOW_UP L2 -> L2_ALGAE - L2 -> L2_ALGAE_INTAKE L2 -> L3_ALGAE - L2 -> L3_ALGAE_INTAKE L2 -> PROCESSOR - L2 -> PROCESSOR_SCORE L2 -> BARGE - L2 -> BARGE_SCORE - L3 -> START L3 -> STOW_DOWN L3 -> GROUND_ACQUISITION - L3 -> GROUND_INTAKE L3 -> L1 L3 -> L2 L3 -> L4 - L3 -> L1_SCORE - L3 -> L2_SCORE L3 -> L3_SCORE - L3 -> L4_SCORE L3 -> HANDOFF L3 -> INTERMEDIATE_WAIT_FOR_ELEVATOR L3 -> INTERMEDIATE_WAIT_FOR_ARM L3 -> STOW_UP L3 -> L2_ALGAE - L3 -> L2_ALGAE_INTAKE L3 -> L3_ALGAE - L3 -> L3_ALGAE_INTAKE L3 -> PROCESSOR - L3 -> PROCESSOR_SCORE L3 -> BARGE - L3 -> BARGE_SCORE L4 -> START L4 -> STOW_DOWN L4 -> GROUND_ACQUISITION - L4 -> GROUND_INTAKE L4 -> L1 L4 -> L2 L4 -> L3 - L4 -> L1_SCORE - L4 -> L2_SCORE - L4 -> L3_SCORE L4 -> L4_SCORE L4 -> HANDOFF L4 -> INTERMEDIATE_WAIT_FOR_ELEVATOR L4 -> INTERMEDIATE_WAIT_FOR_ARM L4 -> STOW_UP L4 -> L2_ALGAE - L4 -> L2_ALGAE_INTAKE L4 -> L3_ALGAE - L4 -> L3_ALGAE_INTAKE L4 -> PROCESSOR - L4 -> PROCESSOR_SCORE L4 -> BARGE - L4 -> BARGE_SCORE - L1_SCORE -> START - L1_SCORE -> STOW_DOWN L1_SCORE -> GROUND_ACQUISITION - L1_SCORE -> GROUND_INTAKE - L1_SCORE -> L1 - L1_SCORE -> L2 - L1_SCORE -> L3 - L1_SCORE -> L4 - L1_SCORE -> L2_SCORE - L1_SCORE -> L3_SCORE - L1_SCORE -> L4_SCORE - L1_SCORE -> HANDOFF - L1_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR - L1_SCORE -> INTERMEDIATE_WAIT_FOR_ARM - L1_SCORE -> STOW_UP - L1_SCORE -> L2_ALGAE - L1_SCORE -> L2_ALGAE_INTAKE - L1_SCORE -> L3_ALGAE - L1_SCORE -> L3_ALGAE_INTAKE - L1_SCORE -> PROCESSOR - L1_SCORE -> PROCESSOR_SCORE - L1_SCORE -> BARGE - L1_SCORE -> BARGE_SCORE - L2_SCORE -> START L2_SCORE -> STOW_DOWN L2_SCORE -> GROUND_ACQUISITION - L2_SCORE -> GROUND_INTAKE L2_SCORE -> L1 L2_SCORE -> L2 L2_SCORE -> L3 L2_SCORE -> L4 - L2_SCORE -> L1_SCORE - L2_SCORE -> L3_SCORE - L2_SCORE -> L4_SCORE L2_SCORE -> HANDOFF L2_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR L2_SCORE -> INTERMEDIATE_WAIT_FOR_ARM L2_SCORE -> STOW_UP L2_SCORE -> L2_ALGAE - L2_SCORE -> L2_ALGAE_INTAKE L2_SCORE -> L3_ALGAE - L2_SCORE -> L3_ALGAE_INTAKE L2_SCORE -> PROCESSOR - L2_SCORE -> PROCESSOR_SCORE L2_SCORE -> BARGE - L2_SCORE -> BARGE_SCORE - L3_SCORE -> START L3_SCORE -> STOW_DOWN L3_SCORE -> GROUND_ACQUISITION - L3_SCORE -> GROUND_INTAKE L3_SCORE -> L1 L3_SCORE -> L2 L3_SCORE -> L3 L3_SCORE -> L4 - L3_SCORE -> L1_SCORE - L3_SCORE -> L2_SCORE - L3_SCORE -> L4_SCORE L3_SCORE -> HANDOFF L3_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR L3_SCORE -> INTERMEDIATE_WAIT_FOR_ARM L3_SCORE -> STOW_UP L3_SCORE -> L2_ALGAE - L3_SCORE -> L2_ALGAE_INTAKE L3_SCORE -> L3_ALGAE - L3_SCORE -> L3_ALGAE_INTAKE L3_SCORE -> PROCESSOR - L3_SCORE -> PROCESSOR_SCORE L3_SCORE -> BARGE - L3_SCORE -> BARGE_SCORE - L4_SCORE -> START L4_SCORE -> STOW_DOWN L4_SCORE -> GROUND_ACQUISITION - L4_SCORE -> GROUND_INTAKE L4_SCORE -> L1 L4_SCORE -> L2 L4_SCORE -> L3 L4_SCORE -> L4 - L4_SCORE -> L1_SCORE - L4_SCORE -> L2_SCORE - L4_SCORE -> L3_SCORE L4_SCORE -> HANDOFF L4_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR L4_SCORE -> INTERMEDIATE_WAIT_FOR_ARM L4_SCORE -> STOW_UP L4_SCORE -> L2_ALGAE - L4_SCORE -> L2_ALGAE_INTAKE L4_SCORE -> L3_ALGAE - L4_SCORE -> L3_ALGAE_INTAKE L4_SCORE -> PROCESSOR - L4_SCORE -> PROCESSOR_SCORE L4_SCORE -> BARGE - L4_SCORE -> BARGE_SCORE - HANDOFF -> START - HANDOFF -> STOW_DOWN + HANDOFF -> STOW_DOWN [label = "coordinated motion"] HANDOFF -> GROUND_ACQUISITION - HANDOFF -> GROUND_INTAKE HANDOFF -> L1 HANDOFF -> L2 HANDOFF -> L3 HANDOFF -> L4 - HANDOFF -> L1_SCORE - HANDOFF -> L2_SCORE - HANDOFF -> L3_SCORE - HANDOFF -> L4_SCORE HANDOFF -> INTERMEDIATE_WAIT_FOR_ELEVATOR HANDOFF -> INTERMEDIATE_WAIT_FOR_ARM HANDOFF -> STOW_UP HANDOFF -> L2_ALGAE - HANDOFF -> L2_ALGAE_INTAKE HANDOFF -> L3_ALGAE - HANDOFF -> L3_ALGAE_INTAKE HANDOFF -> PROCESSOR - HANDOFF -> PROCESSOR_SCORE HANDOFF -> BARGE - HANDOFF -> BARGE_SCORE - INTERMEDIATE_WAIT_FOR_ELEVATOR -> START INTERMEDIATE_WAIT_FOR_ELEVATOR -> STOW_DOWN INTERMEDIATE_WAIT_FOR_ELEVATOR -> GROUND_ACQUISITION - INTERMEDIATE_WAIT_FOR_ELEVATOR -> GROUND_INTAKE INTERMEDIATE_WAIT_FOR_ELEVATOR -> L1 INTERMEDIATE_WAIT_FOR_ELEVATOR -> L2 INTERMEDIATE_WAIT_FOR_ELEVATOR -> L3 INTERMEDIATE_WAIT_FOR_ELEVATOR -> L4 - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L1_SCORE - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L2_SCORE - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L3_SCORE - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L4_SCORE INTERMEDIATE_WAIT_FOR_ELEVATOR -> HANDOFF INTERMEDIATE_WAIT_FOR_ELEVATOR -> INTERMEDIATE_WAIT_FOR_ARM INTERMEDIATE_WAIT_FOR_ELEVATOR -> STOW_UP INTERMEDIATE_WAIT_FOR_ELEVATOR -> L2_ALGAE - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L2_ALGAE_INTAKE INTERMEDIATE_WAIT_FOR_ELEVATOR -> L3_ALGAE - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L3_ALGAE_INTAKE INTERMEDIATE_WAIT_FOR_ELEVATOR -> PROCESSOR - INTERMEDIATE_WAIT_FOR_ELEVATOR -> PROCESSOR_SCORE INTERMEDIATE_WAIT_FOR_ELEVATOR -> BARGE - INTERMEDIATE_WAIT_FOR_ELEVATOR -> BARGE_SCORE - INTERMEDIATE_WAIT_FOR_ARM -> START INTERMEDIATE_WAIT_FOR_ARM -> STOW_DOWN INTERMEDIATE_WAIT_FOR_ARM -> GROUND_ACQUISITION - INTERMEDIATE_WAIT_FOR_ARM -> GROUND_INTAKE INTERMEDIATE_WAIT_FOR_ARM -> L1 INTERMEDIATE_WAIT_FOR_ARM -> L2 INTERMEDIATE_WAIT_FOR_ARM -> L3 INTERMEDIATE_WAIT_FOR_ARM -> L4 - INTERMEDIATE_WAIT_FOR_ARM -> L1_SCORE - INTERMEDIATE_WAIT_FOR_ARM -> L2_SCORE - INTERMEDIATE_WAIT_FOR_ARM -> L3_SCORE - INTERMEDIATE_WAIT_FOR_ARM -> L4_SCORE INTERMEDIATE_WAIT_FOR_ARM -> HANDOFF INTERMEDIATE_WAIT_FOR_ARM -> INTERMEDIATE_WAIT_FOR_ELEVATOR INTERMEDIATE_WAIT_FOR_ARM -> STOW_UP INTERMEDIATE_WAIT_FOR_ARM -> L2_ALGAE - INTERMEDIATE_WAIT_FOR_ARM -> L2_ALGAE_INTAKE INTERMEDIATE_WAIT_FOR_ARM -> L3_ALGAE - INTERMEDIATE_WAIT_FOR_ARM -> L3_ALGAE_INTAKE INTERMEDIATE_WAIT_FOR_ARM -> PROCESSOR - INTERMEDIATE_WAIT_FOR_ARM -> PROCESSOR_SCORE INTERMEDIATE_WAIT_FOR_ARM -> BARGE - INTERMEDIATE_WAIT_FOR_ARM -> BARGE_SCORE - STOW_UP -> START STOW_UP -> STOW_DOWN - STOW_UP -> GROUND_ACQUISITION - STOW_UP -> GROUND_INTAKE - STOW_UP -> L1 + STOW_UP -> GROUND_ACQUISITION [label = "coordinated motion"] + STOW_UP -> L1 [label = "coordinated motion"] STOW_UP -> L2 STOW_UP -> L3 STOW_UP -> L4 - STOW_UP -> L1_SCORE - STOW_UP -> L2_SCORE - STOW_UP -> L3_SCORE - STOW_UP -> L4_SCORE - STOW_UP -> HANDOFF + STOW_UP -> HANDOFF [label = "coordinated motion"] STOW_UP -> INTERMEDIATE_WAIT_FOR_ELEVATOR STOW_UP -> INTERMEDIATE_WAIT_FOR_ARM STOW_UP -> L2_ALGAE - STOW_UP -> L2_ALGAE_INTAKE STOW_UP -> L3_ALGAE - STOW_UP -> L3_ALGAE_INTAKE STOW_UP -> PROCESSOR - STOW_UP -> PROCESSOR_SCORE STOW_UP -> BARGE - STOW_UP -> BARGE_SCORE - L2_ALGAE -> START - L2_ALGAE -> STOW_DOWN - L2_ALGAE -> GROUND_ACQUISITION - L2_ALGAE -> GROUND_INTAKE - L2_ALGAE -> L1 - L2_ALGAE -> L2 + L2_ALGAE -> STOW_DOWN [label = "no algae"] + L2_ALGAE -> GROUND_ACQUISITION [label = "no algae"] + L2_ALGAE -> L1 [label = "no algae"] + L2_ALGAE -> L2 L2_ALGAE -> L3 L2_ALGAE -> L4 - L2_ALGAE -> L1_SCORE - L2_ALGAE -> L2_SCORE - L2_ALGAE -> L3_SCORE - L2_ALGAE -> L4_SCORE - L2_ALGAE -> HANDOFF + L2_ALGAE -> HANDOFF [label = "no algae"] L2_ALGAE -> INTERMEDIATE_WAIT_FOR_ELEVATOR L2_ALGAE -> INTERMEDIATE_WAIT_FOR_ARM L2_ALGAE -> STOW_UP L2_ALGAE -> L2_ALGAE_INTAKE - L2_ALGAE -> L3_ALGAE - L2_ALGAE -> L3_ALGAE_INTAKE + L2_ALGAE -> L3_ALGAE [label = "no algae"] L2_ALGAE -> PROCESSOR - L2_ALGAE -> PROCESSOR_SCORE L2_ALGAE -> BARGE - L2_ALGAE -> BARGE_SCORE - L2_ALGAE_INTAKE -> START - L2_ALGAE_INTAKE -> STOW_DOWN - L2_ALGAE_INTAKE -> GROUND_ACQUISITION - L2_ALGAE_INTAKE -> GROUND_INTAKE - L2_ALGAE_INTAKE -> L1 - L2_ALGAE_INTAKE -> L2 - L2_ALGAE_INTAKE -> L3 - L2_ALGAE_INTAKE -> L4 - L2_ALGAE_INTAKE -> L1_SCORE - L2_ALGAE_INTAKE -> L2_SCORE - L2_ALGAE_INTAKE -> L3_SCORE - L2_ALGAE_INTAKE -> L4_SCORE - L2_ALGAE_INTAKE -> HANDOFF - L2_ALGAE_INTAKE -> INTERMEDIATE_WAIT_FOR_ELEVATOR - L2_ALGAE_INTAKE -> INTERMEDIATE_WAIT_FOR_ARM L2_ALGAE_INTAKE -> STOW_UP L2_ALGAE_INTAKE -> L2_ALGAE - L2_ALGAE_INTAKE -> L3_ALGAE - L2_ALGAE_INTAKE -> L3_ALGAE_INTAKE - L2_ALGAE_INTAKE -> PROCESSOR - L2_ALGAE_INTAKE -> PROCESSOR_SCORE - L2_ALGAE_INTAKE -> BARGE - L2_ALGAE_INTAKE -> BARGE_SCORE - L3_ALGAE -> START - L3_ALGAE -> STOW_DOWN - L3_ALGAE -> GROUND_ACQUISITION - L3_ALGAE -> GROUND_INTAKE - L3_ALGAE -> L1 + L3_ALGAE -> STOW_DOWN [label = "no algae"] + L3_ALGAE -> GROUND_ACQUISITION [label = "no algae"] + L3_ALGAE -> L1 [label = "no algae"] L3_ALGAE -> L2 L3_ALGAE -> L3 L3_ALGAE -> L4 - L3_ALGAE -> L1_SCORE - L3_ALGAE -> L2_SCORE - L3_ALGAE -> L3_SCORE - L3_ALGAE -> L4_SCORE - L3_ALGAE -> HANDOFF + L3_ALGAE -> HANDOFF [label = "no algae"] L3_ALGAE -> INTERMEDIATE_WAIT_FOR_ELEVATOR L3_ALGAE -> INTERMEDIATE_WAIT_FOR_ARM L3_ALGAE -> STOW_UP - L3_ALGAE -> L2_ALGAE - L3_ALGAE -> L2_ALGAE_INTAKE + L3_ALGAE -> L2_ALGAE [label = "no algae"] L3_ALGAE -> L3_ALGAE_INTAKE L3_ALGAE -> PROCESSOR - L3_ALGAE -> PROCESSOR_SCORE L3_ALGAE -> BARGE - L3_ALGAE -> BARGE_SCORE - L3_ALGAE_INTAKE -> START - L3_ALGAE_INTAKE -> STOW_DOWN - L3_ALGAE_INTAKE -> GROUND_ACQUISITION - L3_ALGAE_INTAKE -> GROUND_INTAKE - L3_ALGAE_INTAKE -> L1 - L3_ALGAE_INTAKE -> L2 - L3_ALGAE_INTAKE -> L3 - L3_ALGAE_INTAKE -> L4 - L3_ALGAE_INTAKE -> L1_SCORE - L3_ALGAE_INTAKE -> L2_SCORE - L3_ALGAE_INTAKE -> L3_SCORE - L3_ALGAE_INTAKE -> L4_SCORE - L3_ALGAE_INTAKE -> HANDOFF - L3_ALGAE_INTAKE -> INTERMEDIATE_WAIT_FOR_ELEVATOR - L3_ALGAE_INTAKE -> INTERMEDIATE_WAIT_FOR_ARM L3_ALGAE_INTAKE -> STOW_UP - L3_ALGAE_INTAKE -> L2_ALGAE - L3_ALGAE_INTAKE -> L2_ALGAE_INTAKE L3_ALGAE_INTAKE -> L3_ALGAE - L3_ALGAE_INTAKE -> PROCESSOR - L3_ALGAE_INTAKE -> PROCESSOR_SCORE - L3_ALGAE_INTAKE -> BARGE - L3_ALGAE_INTAKE -> BARGE_SCORE - PROCESSOR -> START - PROCESSOR -> STOW_DOWN - PROCESSOR -> GROUND_ACQUISITION - PROCESSOR -> GROUND_INTAKE - PROCESSOR -> L1 + PROCESSOR -> STOW_DOWN [label = "no algae"] + PROCESSOR -> GROUND_ACQUISITION [label = "no algae"] + PROCESSOR -> L1 [label = "no algae"] PROCESSOR -> L2 PROCESSOR -> L3 PROCESSOR -> L4 - PROCESSOR -> L1_SCORE - PROCESSOR -> L2_SCORE - PROCESSOR -> L3_SCORE - PROCESSOR -> L4_SCORE - PROCESSOR -> HANDOFF + PROCESSOR -> HANDOFF [label = "no algae"] PROCESSOR -> INTERMEDIATE_WAIT_FOR_ELEVATOR PROCESSOR -> INTERMEDIATE_WAIT_FOR_ARM PROCESSOR -> STOW_UP PROCESSOR -> L2_ALGAE - PROCESSOR -> L2_ALGAE_INTAKE PROCESSOR -> L3_ALGAE - PROCESSOR -> L3_ALGAE_INTAKE PROCESSOR -> PROCESSOR_SCORE PROCESSOR -> BARGE - PROCESSOR -> BARGE_SCORE - PROCESSOR_SCORE -> START - PROCESSOR_SCORE -> STOW_DOWN - PROCESSOR_SCORE -> GROUND_ACQUISITION - PROCESSOR_SCORE -> GROUND_INTAKE - PROCESSOR_SCORE -> L1 - PROCESSOR_SCORE -> L2 - PROCESSOR_SCORE -> L3 - PROCESSOR_SCORE -> L4 - PROCESSOR_SCORE -> L1_SCORE - PROCESSOR_SCORE -> L2_SCORE - PROCESSOR_SCORE -> L3_SCORE - PROCESSOR_SCORE -> L4_SCORE - PROCESSOR_SCORE -> HANDOFF - PROCESSOR_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR - PROCESSOR_SCORE -> INTERMEDIATE_WAIT_FOR_ARM - PROCESSOR_SCORE -> STOW_UP - PROCESSOR_SCORE -> L2_ALGAE - PROCESSOR_SCORE -> L2_ALGAE_INTAKE - PROCESSOR_SCORE -> L3_ALGAE - PROCESSOR_SCORE -> L3_ALGAE_INTAKE PROCESSOR_SCORE -> PROCESSOR - PROCESSOR_SCORE -> BARGE - PROCESSOR_SCORE -> BARGE_SCORE - BARGE -> START BARGE -> STOW_DOWN BARGE -> GROUND_ACQUISITION - BARGE -> GROUND_INTAKE BARGE -> L1 BARGE -> L2 BARGE -> L3 BARGE -> L4 - BARGE -> L1_SCORE - BARGE -> L2_SCORE - BARGE -> L3_SCORE - BARGE -> L4_SCORE BARGE -> HANDOFF BARGE -> INTERMEDIATE_WAIT_FOR_ELEVATOR BARGE -> INTERMEDIATE_WAIT_FOR_ARM BARGE -> STOW_UP BARGE -> L2_ALGAE - BARGE -> L2_ALGAE_INTAKE BARGE -> L3_ALGAE - BARGE -> L3_ALGAE_INTAKE BARGE -> PROCESSOR - BARGE -> PROCESSOR_SCORE BARGE -> BARGE_SCORE - BARGE_SCORE -> START - BARGE_SCORE -> STOW_DOWN - BARGE_SCORE -> GROUND_ACQUISITION - BARGE_SCORE -> GROUND_INTAKE - BARGE_SCORE -> L1 - BARGE_SCORE -> L2 - BARGE_SCORE -> L3 - BARGE_SCORE -> L4 - BARGE_SCORE -> L1_SCORE - BARGE_SCORE -> L2_SCORE - BARGE_SCORE -> L3_SCORE - BARGE_SCORE -> L4_SCORE - BARGE_SCORE -> HANDOFF - BARGE_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR - BARGE_SCORE -> INTERMEDIATE_WAIT_FOR_ARM - BARGE_SCORE -> STOW_UP - BARGE_SCORE -> L2_ALGAE - BARGE_SCORE -> L2_ALGAE_INTAKE - BARGE_SCORE -> L3_ALGAE - BARGE_SCORE -> L3_ALGAE_INTAKE - BARGE_SCORE -> PROCESSOR - BARGE_SCORE -> PROCESSOR_SCORE BARGE_SCORE -> BARGE } \ No newline at end of file From 8d505a13ed475c611c46e69321608406234a5068 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Sun, 31 Aug 2025 23:33:20 -0400 Subject: [PATCH 059/180] finish dot file --- Superstructure.py | 2 +- build.gradle | 2 +- src/main/deploy/Superstructure.dot | 221 +++++++ .../subsystems/shared/elevator/Elevator.java | 15 + .../v3_Epsilon/V3_EpsilonRobotContainer.java | 14 +- .../superstructure/Superstructure.dot | 544 +++++++++--------- .../V3_EpsilonSuperstructure.java | 65 ++- .../V3_EpsilonSuperstructureEdges.java | 176 +++++- .../V3_EpsilonSuperstructurePose.java | 19 +- .../V3_EpsilonSuperstructureStates.java | 163 +++--- .../intake/V3_EpsilonIntake.java | 9 +- .../manipulator/V3_EpsilonManipulator.java | 13 +- .../V3_EpsilonManipulatorConstants.java | 8 +- 13 files changed, 792 insertions(+), 459 deletions(-) create mode 100644 src/main/deploy/Superstructure.dot diff --git a/Superstructure.py b/Superstructure.py index 68d83cce..99038af3 100644 --- a/Superstructure.py +++ b/Superstructure.py @@ -2,7 +2,7 @@ from networkx.drawing.nx_pydot import read_dot # Load the graph from the DOT file -G = read_dot("Superstructure.dot") +G = read_dot("/home/elliotscher/Documents/FRC/FRC_190/2k25-Robot-Code/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot") # Specify your start and end nodes start = input("Enter the start node: ") diff --git a/build.gradle b/build.gradle index eab042ee..17f28036 100755 --- a/build.gradle +++ b/build.gradle @@ -222,7 +222,7 @@ dependencies { implementation wpi.java.deps.wpilib() implementation wpi.java.vendor.java() implementation 'org.jgrapht:jgrapht-core:1.5.1' - + implementation 'org.jgrapht:jgrapht-io:1.5.1' roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio) roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio) diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/Superstructure.dot new file mode 100644 index 00000000..940605a4 --- /dev/null +++ b/src/main/deploy/Superstructure.dot @@ -0,0 +1,221 @@ +digraph Superstructure { + START -> STOW_DOWN [type=UNCONSTRAINED] + + STOW_DOWN -> GROUND_ACQUISITION [type=UNCONSTRAINED, requires=ELEVATOR] + STOW_DOWN -> L1 [type=UNCONSTRAINED] + STOW_DOWN -> L2 [type=UNCONSTRAINED] + STOW_DOWN -> L3 [type=UNCONSTRAINED] + STOW_DOWN -> L4 [type=UNCONSTRAINED] + STOW_DOWN -> HANDOFF [type=UNCONSTRAINED, requires=ELEVATOR] + STOW_DOWN -> STOW_UP [type=UNCONSTRAINED] + STOW_DOWN -> L2_ALGAE [type=UNCONSTRAINED] + STOW_DOWN -> L3_ALGAE [type=UNCONSTRAINED] + STOW_DOWN -> PROCESSOR [type=UNCONSTRAINED] + STOW_DOWN -> BARGE [type=UNCONSTRAINED] + + GROUND_ACQUISITION -> STOW_DOWN [type=UNCONSTRAINED] + GROUND_ACQUISITION -> GROUND_INTAKE [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L1 [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L2 [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L3 [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L4 [type=UNCONSTRAINED] + GROUND_ACQUISITION -> HANDOFF [type=UNCONSTRAINED] + GROUND_ACQUISITION -> STOW_UP [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L2_ALGAE [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L3_ALGAE [type=UNCONSTRAINED] + GROUND_ACQUISITION -> PROCESSOR [type=UNCONSTRAINED] + GROUND_ACQUISITION -> BARGE [type=UNCONSTRAINED] + + GROUND_INTAKE -> STOW_DOWN [type=UNCONSTRAINED] + GROUND_INTAKE -> GROUND_ACQUISITION [type=UNCONSTRAINED] + GROUND_INTAKE -> L1 [type=UNCONSTRAINED] + GROUND_INTAKE -> L2 [type=UNCONSTRAINED] + GROUND_INTAKE -> L3 [type=UNCONSTRAINED] + GROUND_INTAKE -> L4 [type=UNCONSTRAINED] + GROUND_INTAKE -> HANDOFF [type=UNCONSTRAINED] + GROUND_INTAKE -> STOW_UP [type=UNCONSTRAINED] + GROUND_INTAKE -> L2_ALGAE [type=UNCONSTRAINED] + GROUND_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] + GROUND_INTAKE -> PROCESSOR [type=UNCONSTRAINED] + GROUND_INTAKE -> BARGE [type=UNCONSTRAINED] + + L1 -> STOW_DOWN [type=UNCONSTRAINED] + L1 -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L1 -> L2 [type=UNCONSTRAINED] + L1 -> L3 [type=UNCONSTRAINED] + L1 -> L4 [type=UNCONSTRAINED] + L1 -> L1_SCORE [type=UNCONSTRAINED] + L1 -> HANDOFF [type=UNCONSTRAINED] + L1 -> STOW_UP [type=UNCONSTRAINED] + L1 -> L2_ALGAE [type=UNCONSTRAINED] + L1 -> L3_ALGAE [type=UNCONSTRAINED] + L1 -> PROCESSOR [type=UNCONSTRAINED] + L1 -> BARGE [type=UNCONSTRAINED] + + L2 -> STOW_DOWN [type=UNCONSTRAINED] + L2 -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L2 -> L1 [type=UNCONSTRAINED] + L2 -> L3 [type=UNCONSTRAINED] + L2 -> L4 [type=UNCONSTRAINED] + L2 -> L2_SCORE [type=UNCONSTRAINED] + L2 -> HANDOFF [type=UNCONSTRAINED] + L2 -> STOW_UP [type=UNCONSTRAINED] + L2 -> L2_ALGAE [type=UNCONSTRAINED] + L2 -> L3_ALGAE [type=UNCONSTRAINED] + L2 -> PROCESSOR [type=UNCONSTRAINED] + L2 -> BARGE [type=UNCONSTRAINED] + + L3 -> STOW_DOWN [type=UNCONSTRAINED] + L3 -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L3 -> L1 [type=UNCONSTRAINED] + L3 -> L2 [type=UNCONSTRAINED] + L3 -> L4 [type=UNCONSTRAINED] + L3 -> L3_SCORE [type=UNCONSTRAINED] + L3 -> HANDOFF [type=UNCONSTRAINED] + L3 -> STOW_UP [type=UNCONSTRAINED] + L3 -> L2_ALGAE [type=UNCONSTRAINED] + L3 -> L3_ALGAE [type=UNCONSTRAINED] + L3 -> PROCESSOR [type=UNCONSTRAINED] + L3 -> BARGE [type=UNCONSTRAINED] + + L4 -> START [type=UNCONSTRAINED] + L4 -> STOW_DOWN [type=UNCONSTRAINED] + L4 -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L4 -> L1 [type=UNCONSTRAINED] + L4 -> L2 [type=UNCONSTRAINED] + L4 -> L3 [type=UNCONSTRAINED] + L4 -> L4_SCORE [type=UNCONSTRAINED] + L4 -> HANDOFF [type=UNCONSTRAINED] + L4 -> STOW_UP [type=UNCONSTRAINED] + L4 -> L2_ALGAE [type=UNCONSTRAINED] + L4 -> L3_ALGAE [type=UNCONSTRAINED] + L4 -> PROCESSOR [type=UNCONSTRAINED] + L4 -> BARGE [type=UNCONSTRAINED] + + L1_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] + + L2_SCORE -> STOW_DOWN [type=UNCONSTRAINED] + L2_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L2_SCORE -> L1 [type=UNCONSTRAINED] + L2_SCORE -> L2 [type=UNCONSTRAINED] + L2_SCORE -> L3 [type=UNCONSTRAINED] + L2_SCORE -> L4 [type=UNCONSTRAINED] + L2_SCORE -> HANDOFF [type=UNCONSTRAINED] + L2_SCORE -> STOW_UP [type=UNCONSTRAINED] + L2_SCORE -> L2_ALGAE [type=UNCONSTRAINED] + L2_SCORE -> L3_ALGAE [type=UNCONSTRAINED] + L2_SCORE -> PROCESSOR [type=UNCONSTRAINED] + L2_SCORE -> BARGE [type=UNCONSTRAINED] + + L3_SCORE -> STOW_DOWN [type=UNCONSTRAINED] + L3_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L3_SCORE -> L1 [type=UNCONSTRAINED] + L3_SCORE -> L2 [type=UNCONSTRAINED] + L3_SCORE -> L3 [type=UNCONSTRAINED] + L3_SCORE -> L4 [type=UNCONSTRAINED] + L3_SCORE -> HANDOFF [type=UNCONSTRAINED] + L3_SCORE -> STOW_UP [type=UNCONSTRAINED] + L3_SCORE -> L2_ALGAE [type=UNCONSTRAINED] + L3_SCORE -> L3_ALGAE [type=UNCONSTRAINED] + L3_SCORE -> PROCESSOR [type=UNCONSTRAINED] + L3_SCORE -> BARGE [type=UNCONSTRAINED] + + L4_SCORE -> STOW_DOWN [type=UNCONSTRAINED] + L4_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L4_SCORE -> L1 [type=UNCONSTRAINED] + L4_SCORE -> L2 [type=UNCONSTRAINED] + L4_SCORE -> L3 [type=UNCONSTRAINED] + L4_SCORE -> L4 [type=UNCONSTRAINED] + L4_SCORE -> HANDOFF [type=UNCONSTRAINED] + L4_SCORE -> STOW_UP [type=UNCONSTRAINED] + L4_SCORE -> L2_ALGAE [type=UNCONSTRAINED] + L4_SCORE -> L3_ALGAE [type=UNCONSTRAINED] + L4_SCORE -> PROCESSOR [type=UNCONSTRAINED] + L4_SCORE -> BARGE [type=UNCONSTRAINED] + + HANDOFF -> STOW_DOWN [type=UNCONSTRAINED, requires=ARM] + HANDOFF -> GROUND_ACQUISITION [type=UNCONSTRAINED] + HANDOFF -> L1 [type=UNCONSTRAINED] + HANDOFF -> L2 [type=UNCONSTRAINED, requires=ARM] + HANDOFF -> L3 [type=UNCONSTRAINED] + HANDOFF -> L4 [type=UNCONSTRAINED] + HANDOFF -> STOW_UP [type=UNCONSTRAINED] + HANDOFF -> L2_ALGAE [type=UNCONSTRAINED] + HANDOFF -> L3_ALGAE [type=UNCONSTRAINED] + HANDOFF -> PROCESSOR [type=UNCONSTRAINED] + HANDOFF -> BARGE [type=UNCONSTRAINED] + + STOW_UP -> STOW_DOWN [type=UNCONSTRAINED] + STOW_UP -> GROUND_ACQUISITION [type=UNCONSTRAINED] + STOW_UP -> L1 [type=UNCONSTRAINED] + STOW_UP -> L2 [type=UNCONSTRAINED] + STOW_UP -> L3 [type=UNCONSTRAINED] + STOW_UP -> L4 [type=UNCONSTRAINED] + STOW_UP -> HANDOFF [type=UNCONSTRAINED] + STOW_UP -> L2_ALGAE [type=UNCONSTRAINED] + STOW_UP -> L3_ALGAE [type=UNCONSTRAINED] + STOW_UP -> PROCESSOR [type=UNCONSTRAINED] + STOW_UP -> BARGE [type=UNCONSTRAINED] + + L2_ALGAE -> STOW_DOWN [type = NO_ALGAE] + L2_ALGAE -> GROUND_ACQUISITION [type = NO_ALGAE] + L2_ALGAE -> L1 [type = NO_ALGAE] + L2_ALGAE -> L2 [type=UNCONSTRAINED] + L2_ALGAE -> L3 [type=UNCONSTRAINED] + L2_ALGAE -> L4 [type=UNCONSTRAINED] + L2_ALGAE -> HANDOFF [type = NO_ALGAE] + L2_ALGAE -> STOW_UP [type=UNCONSTRAINED] + L2_ALGAE -> L2_ALGAE_INTAKE [type=UNCONSTRAINED] + L2_ALGAE -> L3_ALGAE [type = NO_ALGAE] + L2_ALGAE -> PROCESSOR [type=UNCONSTRAINED] + L2_ALGAE -> BARGE [type=UNCONSTRAINED] + + L2_ALGAE_INTAKE -> STOW_UP [type=UNCONSTRAINED] + L2_ALGAE_INTAKE -> L2_ALGAE [type=UNCONSTRAINED] + + L3_ALGAE -> STOW_DOWN [type = NO_ALGAE] + L3_ALGAE -> GROUND_ACQUISITION [type = NO_ALGAE] + L3_ALGAE -> L1 [type = NO_ALGAE] + L3_ALGAE -> L2 [type=UNCONSTRAINED] + L3_ALGAE -> L3 [type=UNCONSTRAINED] + L3_ALGAE -> L4 [type=UNCONSTRAINED] + L3_ALGAE -> HANDOFF [type = NO_ALGAE] + L3_ALGAE -> STOW_UP [type=UNCONSTRAINED] + L3_ALGAE -> L2_ALGAE [type = NO_ALGAE] + L3_ALGAE -> L3_ALGAE_INTAKE [type=UNCONSTRAINED] + L3_ALGAE -> PROCESSOR [type=UNCONSTRAINED] + L3_ALGAE -> BARGE [type=UNCONSTRAINED] + + L3_ALGAE_INTAKE -> STOW_UP [type=UNCONSTRAINED] + L3_ALGAE_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] + + PROCESSOR -> STOW_DOWN [type = NO_ALGAE] + PROCESSOR -> GROUND_ACQUISITION [type = NO_ALGAE] + PROCESSOR -> L1 [type = NO_ALGAE] + PROCESSOR -> L2 [type=UNCONSTRAINED] + PROCESSOR -> L3 [type=UNCONSTRAINED] + PROCESSOR -> L4 [type=UNCONSTRAINED] + PROCESSOR -> HANDOFF [type = NO_ALGAE] + PROCESSOR -> STOW_UP [type=UNCONSTRAINED] + PROCESSOR -> L2_ALGAE [type=UNCONSTRAINED] + PROCESSOR -> L3_ALGAE [type=UNCONSTRAINED] + PROCESSOR -> PROCESSOR_SCORE [type=UNCONSTRAINED] + PROCESSOR -> BARGE [type=UNCONSTRAINED] + + PROCESSOR_SCORE -> PROCESSOR [type=UNCONSTRAINED] + + BARGE -> STOW_DOWN [type=UNCONSTRAINED] + BARGE -> GROUND_ACQUISITION [type=UNCONSTRAINED] + BARGE -> L1 [type=UNCONSTRAINED] + BARGE -> L2 [type=UNCONSTRAINED] + BARGE -> L3 [type=UNCONSTRAINED] + BARGE -> L4 [type=UNCONSTRAINED] + BARGE -> HANDOFF [type=UNCONSTRAINED] + BARGE -> STOW_UP [type=UNCONSTRAINED] + BARGE -> L2_ALGAE [type=UNCONSTRAINED] + BARGE -> L3_ALGAE [type=UNCONSTRAINED] + BARGE -> PROCESSOR [type=UNCONSTRAINED] + BARGE -> BARGE_SCORE [type=UNCONSTRAINED] + + BARGE_SCORE -> BARGE [type=UNCONSTRAINED] +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java index baf774fb..2d93a886 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java @@ -134,6 +134,17 @@ private boolean atGoal() { <= ElevatorConstants.CONSTRAINTS.goalToleranceMeters().get(); } + /** + * Checks if the elevator is at the goal position. + * + * @return True if the elevator is at the goal position, false otherwise. + */ + @AutoLogOutput(key = "Elevator/At Goal") + private boolean atGoal(ElevatorPositions position) { + return Math.abs(position.getPosition() - inputs.positionMeters) + <= ElevatorConstants.CONSTRAINTS.goalToleranceMeters().get(); + } + /** * Waits until the elevator is at the goal position. * @@ -343,6 +354,10 @@ public boolean atGoal() { return Elevator.this.atGoal(); } + public boolean atGoal(ReefState position) { + return Elevator.this.atGoal(Elevator.this.getPosition(position)); + } + public Command waitUntilAtGoal() { return Elevator.this.waitUntilAtGoal(); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 0cd2c900..67485c67 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -2,6 +2,7 @@ import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.Constants; import frc.robot.Constants.Mode; import frc.robot.RobotContainer; @@ -125,6 +126,17 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { - return superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE_SCORE); + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF), + Commands.waitSeconds(3), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), + Commands.waitSeconds(3), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + Commands.waitSeconds(3), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L2), + Commands.waitSeconds(3), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L3_SCORE), + Commands.waitSeconds(3), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L1)); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index 5683555d..8b68b87c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -1,313 +1,281 @@ digraph Superstructure { - /* - * Graphviz DOT file for the superstructure state machine. - * States are represented as nodes, and transitions are represented as edges. - */ + START -> STOW_DOWN [type=UNCONSTRAINED] - // Node definitions - START - STOW_DOWN - GROUND_ACQUISITION - GROUND_INTAKE - L1 - L2 - L3 - L4 - L1_SCORE - L2_SCORE - L3_SCORE - L4_SCORE - HANDOFF - INTERMEDIATE_WAIT_FOR_ELEVATOR - INTERMEDIATE_WAIT_FOR_ARM - STOW_UP - L2_ALGAE - L2_ALGAE_INTAKE - L3_ALGAE - L3_ALGAE_INTAKE - PROCESSOR - PROCESSOR_SCORE - BARGE - BARGE_SCORE + STOW_DOWN -> GROUND_ACQUISITION [type=UNCONSTRAINED] + STOW_DOWN -> L1 [type=UNCONSTRAINED] + STOW_DOWN -> L2 [type=UNCONSTRAINED] + STOW_DOWN -> L3 [type=UNCONSTRAINED] + STOW_DOWN -> L4 [type=UNCONSTRAINED] + // STOW_DOWN -> HANDOFF [type=UNCONSTRAINED] + STOW_DOWN -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + STOW_DOWN -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + STOW_DOWN -> STOW_UP [type=UNCONSTRAINED] + STOW_DOWN -> L2_ALGAE [type=UNCONSTRAINED] + STOW_DOWN -> L3_ALGAE [type=UNCONSTRAINED] + STOW_DOWN -> PROCESSOR [type=UNCONSTRAINED] + STOW_DOWN -> BARGE [type=UNCONSTRAINED] - // Edge definitions (All-to-all pairing) - START -> STOW_DOWN + GROUND_ACQUISITION -> STOW_DOWN [type=UNCONSTRAINED] + GROUND_ACQUISITION -> GROUND_INTAKE [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L1 [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L2 [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L3 [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L4 [type=UNCONSTRAINED] + GROUND_ACQUISITION -> HANDOFF [type=UNCONSTRAINED] + GROUND_ACQUISITION -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + GROUND_ACQUISITION -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + GROUND_ACQUISITION -> STOW_UP [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L2_ALGAE [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L3_ALGAE [type=UNCONSTRAINED] + GROUND_ACQUISITION -> PROCESSOR [type=UNCONSTRAINED] + GROUND_ACQUISITION -> BARGE [type=UNCONSTRAINED] - STOW_DOWN -> GROUND_ACQUISITION [label = "coordinated motion"] - STOW_DOWN -> L1 [label = "coordinated motion"] - STOW_DOWN -> L2 - STOW_DOWN -> L3 - STOW_DOWN -> L4 - STOW_DOWN -> HANDOFF [label = "coordinated motion"] - STOW_DOWN -> INTERMEDIATE_WAIT_FOR_ELEVATOR - STOW_DOWN -> INTERMEDIATE_WAIT_FOR_ARM - STOW_DOWN -> STOW_UP - STOW_DOWN -> L2_ALGAE - STOW_DOWN -> L3_ALGAE - STOW_DOWN -> PROCESSOR - STOW_DOWN -> BARGE + GROUND_INTAKE -> STOW_DOWN [type=UNCONSTRAINED] + GROUND_INTAKE -> GROUND_ACQUISITION [type=UNCONSTRAINED] + GROUND_INTAKE -> L1 [type=UNCONSTRAINED] + GROUND_INTAKE -> L2 [type=UNCONSTRAINED] + GROUND_INTAKE -> L3 [type=UNCONSTRAINED] + GROUND_INTAKE -> L4 [type=UNCONSTRAINED] + GROUND_INTAKE -> HANDOFF [type=UNCONSTRAINED] + GROUND_INTAKE -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + GROUND_INTAKE -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + GROUND_INTAKE -> STOW_UP [type=UNCONSTRAINED] + GROUND_INTAKE -> L2_ALGAE [type=UNCONSTRAINED] + GROUND_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] + GROUND_INTAKE -> PROCESSOR [type=UNCONSTRAINED] + GROUND_INTAKE -> BARGE [type=UNCONSTRAINED] - GROUND_ACQUISITION -> STOW_DOWN - GROUND_ACQUISITION -> GROUND_INTAKE - GROUND_ACQUISITION -> L1 - GROUND_ACQUISITION -> L2 - GROUND_ACQUISITION -> L3 - GROUND_ACQUISITION -> L4 - GROUND_ACQUISITION -> HANDOFF - GROUND_ACQUISITION -> INTERMEDIATE_WAIT_FOR_ELEVATOR - GROUND_ACQUISITION -> INTERMEDIATE_WAIT_FOR_ARM - GROUND_ACQUISITION -> STOW_UP - GROUND_ACQUISITION -> L2_ALGAE - GROUND_ACQUISITION -> L3_ALGAE - GROUND_ACQUISITION -> PROCESSOR - GROUND_ACQUISITION -> BARGE + L1 -> STOW_DOWN [type=UNCONSTRAINED] + L1 -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L1 -> L2 [type=UNCONSTRAINED] + L1 -> L3 [type=UNCONSTRAINED] + L1 -> L4 [type=UNCONSTRAINED] + L1 -> L1_SCORE [type=UNCONSTRAINED] + L1 -> HANDOFF [type=UNCONSTRAINED] + L1 -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + L1 -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + L1 -> STOW_UP [type=UNCONSTRAINED] + L1 -> L2_ALGAE [type=UNCONSTRAINED] + L1 -> L3_ALGAE [type=UNCONSTRAINED] + L1 -> PROCESSOR [type=UNCONSTRAINED] + L1 -> BARGE [type=UNCONSTRAINED] - GROUND_INTAKE -> STOW_DOWN - GROUND_INTAKE -> GROUND_ACQUISITION - GROUND_INTAKE -> L1 - GROUND_INTAKE -> L2 - GROUND_INTAKE -> L3 - GROUND_INTAKE -> L4 - GROUND_INTAKE -> HANDOFF - GROUND_INTAKE -> INTERMEDIATE_WAIT_FOR_ELEVATOR - GROUND_INTAKE -> INTERMEDIATE_WAIT_FOR_ARM - GROUND_INTAKE -> STOW_UP - GROUND_INTAKE -> L2_ALGAE - GROUND_INTAKE -> L3_ALGAE - GROUND_INTAKE -> PROCESSOR - GROUND_INTAKE -> BARGE + L2 -> STOW_DOWN [type=UNCONSTRAINED] + L2 -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L2 -> L1 [type=UNCONSTRAINED] + L2 -> L3 [type=UNCONSTRAINED] + L2 -> L4 [type=UNCONSTRAINED] + L2 -> L2_SCORE [type=UNCONSTRAINED] + L2 -> HANDOFF [type=UNCONSTRAINED] + L2 -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + L2 -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + L2 -> STOW_UP [type=UNCONSTRAINED] + L2 -> L2_ALGAE [type=UNCONSTRAINED] + L2 -> L3_ALGAE [type=UNCONSTRAINED] + L2 -> PROCESSOR [type=UNCONSTRAINED] + L2 -> BARGE [type=UNCONSTRAINED] - L1 -> STOW_DOWN - L1 -> GROUND_ACQUISITION - L1 -> L2 - L1 -> L3 - L1 -> L4 - L1 -> L1_SCORE - L1 -> HANDOFF - L1 -> INTERMEDIATE_WAIT_FOR_ELEVATOR - L1 -> INTERMEDIATE_WAIT_FOR_ARM - L1 -> STOW_UP - L1 -> L2_ALGAE - L1 -> L3_ALGAE - L1 -> PROCESSOR - L1 -> BARGE + L3 -> STOW_DOWN [type=UNCONSTRAINED] + L3 -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L3 -> L1 [type=UNCONSTRAINED] + L3 -> L2 [type=UNCONSTRAINED] + L3 -> L4 [type=UNCONSTRAINED] + L3 -> L3_SCORE [type=UNCONSTRAINED] + L3 -> HANDOFF [type=UNCONSTRAINED] + L3 -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + L3 -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + L3 -> STOW_UP [type=UNCONSTRAINED] + L3 -> L2_ALGAE [type=UNCONSTRAINED] + L3 -> L3_ALGAE [type=UNCONSTRAINED] + L3 -> PROCESSOR [type=UNCONSTRAINED] + L3 -> BARGE [type=UNCONSTRAINED] - L2 -> STOW_DOWN - L2 -> GROUND_ACQUISITION - L2 -> L1 - L2 -> L3 - L2 -> L4 - L2 -> L2_SCORE - L2 -> HANDOFF - L2 -> INTERMEDIATE_WAIT_FOR_ELEVATOR - L2 -> INTERMEDIATE_WAIT_FOR_ARM - L2 -> STOW_UP - L2 -> L2_ALGAE - L2 -> L3_ALGAE - L2 -> PROCESSOR - L2 -> BARGE + L4 -> START [type=UNCONSTRAINED] + L4 -> STOW_DOWN [type=UNCONSTRAINED] + L4 -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L4 -> L1 [type=UNCONSTRAINED] + L4 -> L2 [type=UNCONSTRAINED] + L4 -> L3 [type=UNCONSTRAINED] + L4 -> L4_SCORE [type=UNCONSTRAINED] + L4 -> HANDOFF [type=UNCONSTRAINED] + L4 -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + L4 -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + L4 -> STOW_UP [type=UNCONSTRAINED] + L4 -> L2_ALGAE [type=UNCONSTRAINED] + L4 -> L3_ALGAE [type=UNCONSTRAINED] + L4 -> PROCESSOR [type=UNCONSTRAINED] + L4 -> BARGE [type=UNCONSTRAINED] - L3 -> STOW_DOWN - L3 -> GROUND_ACQUISITION - L3 -> L1 - L3 -> L2 - L3 -> L4 - L3 -> L3_SCORE - L3 -> HANDOFF - L3 -> INTERMEDIATE_WAIT_FOR_ELEVATOR - L3 -> INTERMEDIATE_WAIT_FOR_ARM - L3 -> STOW_UP - L3 -> L2_ALGAE - L3 -> L3_ALGAE - L3 -> PROCESSOR - L3 -> BARGE + L1_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] - L4 -> START - L4 -> STOW_DOWN - L4 -> GROUND_ACQUISITION - L4 -> L1 - L4 -> L2 - L4 -> L3 - L4 -> L4_SCORE - L4 -> HANDOFF - L4 -> INTERMEDIATE_WAIT_FOR_ELEVATOR - L4 -> INTERMEDIATE_WAIT_FOR_ARM - L4 -> STOW_UP - L4 -> L2_ALGAE - L4 -> L3_ALGAE - L4 -> PROCESSOR - L4 -> BARGE + L2_SCORE -> STOW_DOWN [type=UNCONSTRAINED] + L2_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L2_SCORE -> L1 [type=UNCONSTRAINED] + L2_SCORE -> L2 [type=UNCONSTRAINED] + L2_SCORE -> L3 [type=UNCONSTRAINED] + L2_SCORE -> L4 [type=UNCONSTRAINED] + L2_SCORE -> HANDOFF [type=UNCONSTRAINED] + L2_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + L2_SCORE -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + L2_SCORE -> STOW_UP [type=UNCONSTRAINED] + L2_SCORE -> L2_ALGAE [type=UNCONSTRAINED] + L2_SCORE -> L3_ALGAE [type=UNCONSTRAINED] + L2_SCORE -> PROCESSOR [type=UNCONSTRAINED] + L2_SCORE -> BARGE [type=UNCONSTRAINED] - L1_SCORE -> GROUND_ACQUISITION + L3_SCORE -> STOW_DOWN [type=UNCONSTRAINED] + L3_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L3_SCORE -> L1 [type=UNCONSTRAINED] + L3_SCORE -> L2 [type=UNCONSTRAINED] + L3_SCORE -> L3 [type=UNCONSTRAINED] + L3_SCORE -> L4 [type=UNCONSTRAINED] + L3_SCORE -> HANDOFF [type=UNCONSTRAINED] + L3_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + L3_SCORE -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + L3_SCORE -> STOW_UP [type=UNCONSTRAINED] + L3_SCORE -> L2_ALGAE [type=UNCONSTRAINED] + L3_SCORE -> L3_ALGAE [type=UNCONSTRAINED] + L3_SCORE -> PROCESSOR [type=UNCONSTRAINED] + L3_SCORE -> BARGE [type=UNCONSTRAINED] - L2_SCORE -> STOW_DOWN - L2_SCORE -> GROUND_ACQUISITION - L2_SCORE -> L1 - L2_SCORE -> L2 - L2_SCORE -> L3 - L2_SCORE -> L4 - L2_SCORE -> HANDOFF - L2_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR - L2_SCORE -> INTERMEDIATE_WAIT_FOR_ARM - L2_SCORE -> STOW_UP - L2_SCORE -> L2_ALGAE - L2_SCORE -> L3_ALGAE - L2_SCORE -> PROCESSOR - L2_SCORE -> BARGE + L4_SCORE -> STOW_DOWN [type=UNCONSTRAINED] + L4_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L4_SCORE -> L1 [type=UNCONSTRAINED] + L4_SCORE -> L2 [type=UNCONSTRAINED] + L4_SCORE -> L3 [type=UNCONSTRAINED] + L4_SCORE -> L4 [type=UNCONSTRAINED] + L4_SCORE -> HANDOFF [type=UNCONSTRAINED] + L4_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + L4_SCORE -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + L4_SCORE -> STOW_UP [type=UNCONSTRAINED] + L4_SCORE -> L2_ALGAE [type=UNCONSTRAINED] + L4_SCORE -> L3_ALGAE [type=UNCONSTRAINED] + L4_SCORE -> PROCESSOR [type=UNCONSTRAINED] + L4_SCORE -> BARGE [type=UNCONSTRAINED] - L3_SCORE -> STOW_DOWN - L3_SCORE -> GROUND_ACQUISITION - L3_SCORE -> L1 - L3_SCORE -> L2 - L3_SCORE -> L3 - L3_SCORE -> L4 - L3_SCORE -> HANDOFF - L3_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR - L3_SCORE -> INTERMEDIATE_WAIT_FOR_ARM - L3_SCORE -> STOW_UP - L3_SCORE -> L2_ALGAE - L3_SCORE -> L3_ALGAE - L3_SCORE -> PROCESSOR - L3_SCORE -> BARGE + // HANDOFF -> STOW_DOWN [type=UNCONSTRAINED] + HANDOFF -> GROUND_ACQUISITION [type=UNCONSTRAINED] + HANDOFF -> L1 [type=UNCONSTRAINED] + HANDOFF -> L2 [type=UNCONSTRAINED] + HANDOFF -> L3 [type=UNCONSTRAINED] + HANDOFF -> L4 [type=UNCONSTRAINED] + HANDOFF -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + HANDOFF -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + HANDOFF -> STOW_UP [type=UNCONSTRAINED] + HANDOFF -> L2_ALGAE [type=UNCONSTRAINED] + HANDOFF -> L3_ALGAE [type=UNCONSTRAINED] + HANDOFF -> PROCESSOR [type=UNCONSTRAINED] + HANDOFF -> BARGE [type=UNCONSTRAINED] - L4_SCORE -> STOW_DOWN - L4_SCORE -> GROUND_ACQUISITION - L4_SCORE -> L1 - L4_SCORE -> L2 - L4_SCORE -> L3 - L4_SCORE -> L4 - L4_SCORE -> HANDOFF - L4_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR - L4_SCORE -> INTERMEDIATE_WAIT_FOR_ARM - L4_SCORE -> STOW_UP - L4_SCORE -> L2_ALGAE - L4_SCORE -> L3_ALGAE - L4_SCORE -> PROCESSOR - L4_SCORE -> BARGE + INTERMEDIATE_WAIT_FOR_ELEVATOR -> STOW_DOWN [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ELEVATOR -> GROUND_ACQUISITION [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L1 [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L2 [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L3 [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L4 [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ELEVATOR -> HANDOFF [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ELEVATOR -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ELEVATOR -> STOW_UP [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L2_ALGAE [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ELEVATOR -> L3_ALGAE [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ELEVATOR -> PROCESSOR [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ELEVATOR -> BARGE [type=UNCONSTRAINED] - HANDOFF -> STOW_DOWN [label = "coordinated motion"] - HANDOFF -> GROUND_ACQUISITION - HANDOFF -> L1 - HANDOFF -> L2 - HANDOFF -> L3 - HANDOFF -> L4 - HANDOFF -> INTERMEDIATE_WAIT_FOR_ELEVATOR - HANDOFF -> INTERMEDIATE_WAIT_FOR_ARM - HANDOFF -> STOW_UP - HANDOFF -> L2_ALGAE - HANDOFF -> L3_ALGAE - HANDOFF -> PROCESSOR - HANDOFF -> BARGE + INTERMEDIATE_WAIT_FOR_ARM -> STOW_DOWN [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ARM -> GROUND_ACQUISITION [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ARM -> L1 [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ARM -> L2 [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ARM -> L3 [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ARM -> L4 [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ARM -> HANDOFF [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ARM -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ARM -> STOW_UP [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ARM -> L2_ALGAE [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ARM -> L3_ALGAE [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ARM -> PROCESSOR [type=UNCONSTRAINED] + INTERMEDIATE_WAIT_FOR_ARM -> BARGE [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ELEVATOR -> STOW_DOWN - INTERMEDIATE_WAIT_FOR_ELEVATOR -> GROUND_ACQUISITION - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L1 - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L2 - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L3 - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L4 - INTERMEDIATE_WAIT_FOR_ELEVATOR -> HANDOFF - INTERMEDIATE_WAIT_FOR_ELEVATOR -> INTERMEDIATE_WAIT_FOR_ARM - INTERMEDIATE_WAIT_FOR_ELEVATOR -> STOW_UP - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L2_ALGAE - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L3_ALGAE - INTERMEDIATE_WAIT_FOR_ELEVATOR -> PROCESSOR - INTERMEDIATE_WAIT_FOR_ELEVATOR -> BARGE + STOW_UP -> STOW_DOWN [type=UNCONSTRAINED] + STOW_UP -> GROUND_ACQUISITION [type=UNCONSTRAINED] + STOW_UP -> L1 [type=UNCONSTRAINED] + STOW_UP -> L2 [type=UNCONSTRAINED] + STOW_UP -> L3 [type=UNCONSTRAINED] + STOW_UP -> L4 [type=UNCONSTRAINED] + STOW_UP -> HANDOFF [type=UNCONSTRAINED] + STOW_UP -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + STOW_UP -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + STOW_UP -> L2_ALGAE [type=UNCONSTRAINED] + STOW_UP -> L3_ALGAE [type=UNCONSTRAINED] + STOW_UP -> PROCESSOR [type=UNCONSTRAINED] + STOW_UP -> BARGE [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ARM -> STOW_DOWN - INTERMEDIATE_WAIT_FOR_ARM -> GROUND_ACQUISITION - INTERMEDIATE_WAIT_FOR_ARM -> L1 - INTERMEDIATE_WAIT_FOR_ARM -> L2 - INTERMEDIATE_WAIT_FOR_ARM -> L3 - INTERMEDIATE_WAIT_FOR_ARM -> L4 - INTERMEDIATE_WAIT_FOR_ARM -> HANDOFF - INTERMEDIATE_WAIT_FOR_ARM -> INTERMEDIATE_WAIT_FOR_ELEVATOR - INTERMEDIATE_WAIT_FOR_ARM -> STOW_UP - INTERMEDIATE_WAIT_FOR_ARM -> L2_ALGAE - INTERMEDIATE_WAIT_FOR_ARM -> L3_ALGAE - INTERMEDIATE_WAIT_FOR_ARM -> PROCESSOR - INTERMEDIATE_WAIT_FOR_ARM -> BARGE + L2_ALGAE -> STOW_DOWN [type = NO_ALGAE] + L2_ALGAE -> GROUND_ACQUISITION [type = NO_ALGAE] + L2_ALGAE -> L1 [type = NO_ALGAE] + L2_ALGAE -> L2 [type=UNCONSTRAINED] + L2_ALGAE -> L3 [type=UNCONSTRAINED] + L2_ALGAE -> L4 [type=UNCONSTRAINED] + L2_ALGAE -> HANDOFF [type = NO_ALGAE] + L2_ALGAE -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + L2_ALGAE -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + L2_ALGAE -> STOW_UP [type=UNCONSTRAINED] + L2_ALGAE -> L2_ALGAE_INTAKE [type=UNCONSTRAINED] + L2_ALGAE -> L3_ALGAE [type = NO_ALGAE] + L2_ALGAE -> PROCESSOR [type=UNCONSTRAINED] + L2_ALGAE -> BARGE [type=UNCONSTRAINED] - STOW_UP -> STOW_DOWN - STOW_UP -> GROUND_ACQUISITION [label = "coordinated motion"] - STOW_UP -> L1 [label = "coordinated motion"] - STOW_UP -> L2 - STOW_UP -> L3 - STOW_UP -> L4 - STOW_UP -> HANDOFF [label = "coordinated motion"] - STOW_UP -> INTERMEDIATE_WAIT_FOR_ELEVATOR - STOW_UP -> INTERMEDIATE_WAIT_FOR_ARM - STOW_UP -> L2_ALGAE - STOW_UP -> L3_ALGAE - STOW_UP -> PROCESSOR - STOW_UP -> BARGE + L2_ALGAE_INTAKE -> STOW_UP [type=UNCONSTRAINED] + L2_ALGAE_INTAKE -> L2_ALGAE [type=UNCONSTRAINED] - L2_ALGAE -> STOW_DOWN [label = "no algae"] - L2_ALGAE -> GROUND_ACQUISITION [label = "no algae"] - L2_ALGAE -> L1 [label = "no algae"] - L2_ALGAE -> L2 - L2_ALGAE -> L3 - L2_ALGAE -> L4 - L2_ALGAE -> HANDOFF [label = "no algae"] - L2_ALGAE -> INTERMEDIATE_WAIT_FOR_ELEVATOR - L2_ALGAE -> INTERMEDIATE_WAIT_FOR_ARM - L2_ALGAE -> STOW_UP - L2_ALGAE -> L2_ALGAE_INTAKE - L2_ALGAE -> L3_ALGAE [label = "no algae"] - L2_ALGAE -> PROCESSOR - L2_ALGAE -> BARGE + L3_ALGAE -> STOW_DOWN [type = NO_ALGAE] + L3_ALGAE -> GROUND_ACQUISITION [type = NO_ALGAE] + L3_ALGAE -> L1 [type = NO_ALGAE] + L3_ALGAE -> L2 [type=UNCONSTRAINED] + L3_ALGAE -> L3 [type=UNCONSTRAINED] + L3_ALGAE -> L4 [type=UNCONSTRAINED] + L3_ALGAE -> HANDOFF [type = NO_ALGAE] + L3_ALGAE -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + L3_ALGAE -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + L3_ALGAE -> STOW_UP [type=UNCONSTRAINED] + L3_ALGAE -> L2_ALGAE [type = NO_ALGAE] + L3_ALGAE -> L3_ALGAE_INTAKE [type=UNCONSTRAINED] + L3_ALGAE -> PROCESSOR [type=UNCONSTRAINED] + L3_ALGAE -> BARGE [type=UNCONSTRAINED] - L2_ALGAE_INTAKE -> STOW_UP - L2_ALGAE_INTAKE -> L2_ALGAE + L3_ALGAE_INTAKE -> STOW_UP [type=UNCONSTRAINED] + L3_ALGAE_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] - L3_ALGAE -> STOW_DOWN [label = "no algae"] - L3_ALGAE -> GROUND_ACQUISITION [label = "no algae"] - L3_ALGAE -> L1 [label = "no algae"] - L3_ALGAE -> L2 - L3_ALGAE -> L3 - L3_ALGAE -> L4 - L3_ALGAE -> HANDOFF [label = "no algae"] - L3_ALGAE -> INTERMEDIATE_WAIT_FOR_ELEVATOR - L3_ALGAE -> INTERMEDIATE_WAIT_FOR_ARM - L3_ALGAE -> STOW_UP - L3_ALGAE -> L2_ALGAE [label = "no algae"] - L3_ALGAE -> L3_ALGAE_INTAKE - L3_ALGAE -> PROCESSOR - L3_ALGAE -> BARGE + PROCESSOR -> STOW_DOWN [type = NO_ALGAE] + PROCESSOR -> GROUND_ACQUISITION [type = NO_ALGAE] + PROCESSOR -> L1 [type = NO_ALGAE] + PROCESSOR -> L2 [type=UNCONSTRAINED] + PROCESSOR -> L3 [type=UNCONSTRAINED] + PROCESSOR -> L4 [type=UNCONSTRAINED] + PROCESSOR -> HANDOFF [type = NO_ALGAE] + PROCESSOR -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + PROCESSOR -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + PROCESSOR -> STOW_UP [type=UNCONSTRAINED] + PROCESSOR -> L2_ALGAE [type=UNCONSTRAINED] + PROCESSOR -> L3_ALGAE [type=UNCONSTRAINED] + PROCESSOR -> PROCESSOR_SCORE [type=UNCONSTRAINED] + PROCESSOR -> BARGE [type=UNCONSTRAINED] - L3_ALGAE_INTAKE -> STOW_UP - L3_ALGAE_INTAKE -> L3_ALGAE + PROCESSOR_SCORE -> PROCESSOR [type=UNCONSTRAINED] - PROCESSOR -> STOW_DOWN [label = "no algae"] - PROCESSOR -> GROUND_ACQUISITION [label = "no algae"] - PROCESSOR -> L1 [label = "no algae"] - PROCESSOR -> L2 - PROCESSOR -> L3 - PROCESSOR -> L4 - PROCESSOR -> HANDOFF [label = "no algae"] - PROCESSOR -> INTERMEDIATE_WAIT_FOR_ELEVATOR - PROCESSOR -> INTERMEDIATE_WAIT_FOR_ARM - PROCESSOR -> STOW_UP - PROCESSOR -> L2_ALGAE - PROCESSOR -> L3_ALGAE - PROCESSOR -> PROCESSOR_SCORE - PROCESSOR -> BARGE - - PROCESSOR_SCORE -> PROCESSOR - - BARGE -> STOW_DOWN - BARGE -> GROUND_ACQUISITION - BARGE -> L1 - BARGE -> L2 - BARGE -> L3 - BARGE -> L4 - BARGE -> HANDOFF - BARGE -> INTERMEDIATE_WAIT_FOR_ELEVATOR - BARGE -> INTERMEDIATE_WAIT_FOR_ARM - BARGE -> STOW_UP - BARGE -> L2_ALGAE - BARGE -> L3_ALGAE - BARGE -> PROCESSOR - BARGE -> BARGE_SCORE + BARGE -> STOW_DOWN [type=UNCONSTRAINED] + BARGE -> GROUND_ACQUISITION [type=UNCONSTRAINED] + BARGE -> L1 [type=UNCONSTRAINED] + BARGE -> L2 [type=UNCONSTRAINED] + BARGE -> L3 [type=UNCONSTRAINED] + BARGE -> L4 [type=UNCONSTRAINED] + BARGE -> HANDOFF [type=UNCONSTRAINED] + BARGE -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] + BARGE -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + BARGE -> STOW_UP [type=UNCONSTRAINED] + BARGE -> L2_ALGAE [type=UNCONSTRAINED] + BARGE -> L3_ALGAE [type=UNCONSTRAINED] + BARGE -> PROCESSOR [type=UNCONSTRAINED] + BARGE -> BARGE_SCORE [type=UNCONSTRAINED] - BARGE_SCORE -> BARGE + BARGE_SCORE -> BARGE [type=UNCONSTRAINED] } \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 48ffb89d..947f3a74 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -242,7 +242,7 @@ private Optional bfs( * @return true if the transition is allowed */ private boolean isEdgeAllowed(EdgeCommand edge, V3_EpsilonSuperstructureStates goal) { - return edge.getGamePieceEdge() == GamePieceEdge.NONE + return edge.getGamePieceEdge() == GamePieceEdge.UNCONSTRAINED || RobotState.isHasAlgae() == (edge.getGamePieceEdge() == GamePieceEdge.ALGAE); } @@ -267,25 +267,25 @@ private V3_EpsilonSuperstructureStates getElevatorPosition() { return V3_EpsilonSuperstructureStates.STOW_DOWN; } case L1 -> { - return V3_EpsilonSuperstructureStates.L1_PREP; + return V3_EpsilonSuperstructureStates.L1; } case L2 -> { - return V3_EpsilonSuperstructureStates.L2_PREP; + return V3_EpsilonSuperstructureStates.L2; } case L3 -> { - return V3_EpsilonSuperstructureStates.L3_PREP; + return V3_EpsilonSuperstructureStates.L3; } case L4 -> { - return V3_EpsilonSuperstructureStates.L4_PREP; + return V3_EpsilonSuperstructureStates.L4; } case ALGAE_INTAKE_BOTTOM -> { - return V3_EpsilonSuperstructureStates.L2_ALGAE_PREP; + return V3_EpsilonSuperstructureStates.L2_ALGAE; } case ALGAE_INTAKE_TOP -> { - return V3_EpsilonSuperstructureStates.L3_ALGAE_PREP; + return V3_EpsilonSuperstructureStates.L3_ALGAE; } case ALGAE_SCORE -> { - return V3_EpsilonSuperstructureStates.BARGE_PREP; + return V3_EpsilonSuperstructureStates.BARGE; } default -> { return V3_EpsilonSuperstructureStates.START; @@ -322,7 +322,10 @@ public Command runGoal(Supplier goal) { */ @AutoLogOutput(key = NTPrefixes.SUPERSTRUCTURE + "At Goal") public boolean atGoal() { - return currentState == targetState; + return currentState == targetState + && elevator.atGoal(targetState.getPose().getElevatorHeight()) + && intake.pivotAtGoal(targetState.getPose().getIntakeState()) + && manipulator.armAtGoal(targetState.getPose().getArmState()); } /** @@ -385,13 +388,13 @@ public Command runReefGoal(Supplier goal) { // Translate ReefState to superstructure state switch (goal.get()) { case L1: - return V3_EpsilonSuperstructureStates.L1_PREP; + return V3_EpsilonSuperstructureStates.L1; case L2: - return V3_EpsilonSuperstructureStates.L2_PREP; + return V3_EpsilonSuperstructureStates.L2; case L3: - return V3_EpsilonSuperstructureStates.L3_PREP; + return V3_EpsilonSuperstructureStates.L3; case L4: - return V3_EpsilonSuperstructureStates.L4_PREP; + return V3_EpsilonSuperstructureStates.L4; default: return V3_EpsilonSuperstructureStates.STOW_DOWN; } @@ -409,10 +412,10 @@ public Command runReefScoreGoal(Supplier goal) { return runActionWithTimeout( () -> switch (goal.get()) { - case L1 -> V3_EpsilonSuperstructureStates.L1_PREP; - case L2 -> V3_EpsilonSuperstructureStates.L2_PREP; - case L3 -> V3_EpsilonSuperstructureStates.L3_PREP; - case L4 -> V3_EpsilonSuperstructureStates.L4_PREP; + case L1 -> V3_EpsilonSuperstructureStates.L1; + case L2 -> V3_EpsilonSuperstructureStates.L2; + case L3 -> V3_EpsilonSuperstructureStates.L3; + case L4 -> V3_EpsilonSuperstructureStates.L4; default -> V3_EpsilonSuperstructureStates.STOW_DOWN; }, () -> @@ -476,16 +479,14 @@ public Command runActionWithTimeout( Map actionPoseMap = new HashMap<>() { { - put(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.L1_PREP); - put(V3_EpsilonSuperstructureStates.L2_SCORE, V3_EpsilonSuperstructureStates.L2_PREP); - put(V3_EpsilonSuperstructureStates.L3_SCORE, V3_EpsilonSuperstructureStates.L3_PREP); - put(V3_EpsilonSuperstructureStates.L4_SCORE, V3_EpsilonSuperstructureStates.L4_PREP); - put( - V3_EpsilonSuperstructureStates.BARGE_SCORE, - V3_EpsilonSuperstructureStates.BARGE_PREP); + put(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.L1); + put(V3_EpsilonSuperstructureStates.L2_SCORE, V3_EpsilonSuperstructureStates.L2); + put(V3_EpsilonSuperstructureStates.L3_SCORE, V3_EpsilonSuperstructureStates.L3); + put(V3_EpsilonSuperstructureStates.L4_SCORE, V3_EpsilonSuperstructureStates.L4); + put(V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.BARGE); put( V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, - V3_EpsilonSuperstructureStates.PROCESSOR_PREP); + V3_EpsilonSuperstructureStates.PROCESSOR); } }; @@ -515,16 +516,14 @@ public Command runActionWithTimeout(V3_EpsilonSuperstructureStates action, doubl Map actionPoseMap = new HashMap<>() { { - put(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.L1_PREP); - put(V3_EpsilonSuperstructureStates.L2_SCORE, V3_EpsilonSuperstructureStates.L2_PREP); - put(V3_EpsilonSuperstructureStates.L3_SCORE, V3_EpsilonSuperstructureStates.L3_PREP); - put(V3_EpsilonSuperstructureStates.L4_SCORE, V3_EpsilonSuperstructureStates.L4_PREP); - put( - V3_EpsilonSuperstructureStates.BARGE_SCORE, - V3_EpsilonSuperstructureStates.BARGE_PREP); + put(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.L1); + put(V3_EpsilonSuperstructureStates.L2_SCORE, V3_EpsilonSuperstructureStates.L2); + put(V3_EpsilonSuperstructureStates.L3_SCORE, V3_EpsilonSuperstructureStates.L3); + put(V3_EpsilonSuperstructureStates.L4_SCORE, V3_EpsilonSuperstructureStates.L4); + put(V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.BARGE); put( V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, - V3_EpsilonSuperstructureStates.PROCESSOR_PREP); + V3_EpsilonSuperstructureStates.PROCESSOR); } }; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index fb6c3c20..8a4db0e9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -1,19 +1,28 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; +import edu.wpi.first.wpilibj.Filesystem; import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; +import java.io.FileReader; +import java.io.Reader; import java.util.ArrayList; +import java.util.HashMap; import java.util.List; +import java.util.Map; import lombok.Builder; import lombok.Getter; +import lombok.Setter; import org.jgrapht.Graph; import org.jgrapht.graph.DefaultEdge; +import org.jgrapht.nio.Attribute; +import org.jgrapht.nio.dot.DOTImporter; public class V3_EpsilonSuperstructureEdges { - public static final ArrayList NONE_EDGES = new ArrayList<>(); - public static final ArrayList CORAL_EDGES = new ArrayList<>(); + public static final ArrayList UNCONSTRAINED = new ArrayList<>(); public static final ArrayList ALGAE_EDGES = new ArrayList<>(); public record Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { @@ -29,16 +38,117 @@ public String toString() { } public enum GamePieceEdge { - NONE, - CORAL, + UNCONSTRAINED, ALGAE } + public static void loadEdgesFromDot( + String path, + Graph graph, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + + DOTImporter importer = new DOTImporter<>(); + + // Create edges with placeholder commands (null) + importer.setEdgeWithAttributesFactory( + attributes -> { + V3_EpsilonSuperstructureEdges.GamePieceEdge type = + V3_EpsilonSuperstructureEdges.GamePieceEdge.UNCONSTRAINED; + + if (attributes.containsKey("type")) { + String value = attributes.get("type").getValue(); + try { + type = V3_EpsilonSuperstructureEdges.GamePieceEdge.valueOf(value.toUpperCase()); + } catch (IllegalArgumentException e) { + System.err.println("Unknown edge type: " + value + ", defaulting to UNCONSTRAINED"); + } + } + + return V3_EpsilonSuperstructureEdges.EdgeCommand.builder() + .gamePieceEdge(type) + .command(null) // placeholder + .build(); + }); + + // Map DOT node id -> enum + importer.setVertexFactory(id -> V3_EpsilonSuperstructureStates.valueOf(id)); + + // Capture edge attributes + Map> edgeAttrs = new HashMap<>(); + importer.addEdgeWithAttributesConsumer((e, attrs) -> edgeAttrs.put(e, new HashMap<>(attrs))); + + // Import the DOT file + try (Reader r = new FileReader(path)) { + importer.importGraph(graph, r); + } catch (Exception ex) { + throw new RuntimeException("Failed to parse DOT: " + path, ex); + } + + // Clear old edge lists + UNCONSTRAINED.clear(); + ALGAE_EDGES.clear(); + + // Iterate over edges to assign commands and categorize + for (EdgeCommand e : graph.edgeSet()) { + V3_EpsilonSuperstructureStates from = graph.getEdgeSource(e); + V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(e); + + Map attrs = edgeAttrs.get(e); + V3_EpsilonSuperstructureEdges.GamePieceEdge type = + V3_EpsilonSuperstructureEdges.GamePieceEdge.UNCONSTRAINED; + + // START --- ADDED CODE + // Check for the 'requires' attribute to determine if motion should be sequential + boolean requiresElevator = false; + boolean requiresArm = false; + if (attrs != null && attrs.containsKey("requires")) { + String value = attrs.get("requires").getValue(); + if ("elevator".equalsIgnoreCase(value)) { + requiresElevator = true; + } else if ("arm".equalsIgnoreCase(value)) { + requiresArm = true; + } + } + e.setRequiresElevator(requiresElevator); + e.setRequiresArm(requiresArm); + // END --- ADDED CODE + + if (attrs != null && attrs.get("type") != null) { + try { + type = + V3_EpsilonSuperstructureEdges.GamePieceEdge.valueOf( + attrs.get("type").getValue().toUpperCase()); + } catch (IllegalArgumentException ex) { + System.err.println("Unknown edge type: " + attrs.get("type").getValue()); + } + } + + // Assign the actual command, passing the new flags + e.setCommand( + V3_EpsilonSuperstructureEdges.getEdgeCommand( + from, to, elevator, intake, manipulator, requiresElevator, requiresArm)); + + // Add to proper list + Edge edge = new Edge(from, to); + if (type == V3_EpsilonSuperstructureEdges.GamePieceEdge.ALGAE) { + ALGAE_EDGES.add(edge); + } else { + UNCONSTRAINED.add(edge); + } + } + } + @Builder(toBuilder = true) @Getter public static class EdgeCommand extends DefaultEdge { - private final Command command; - @Builder.Default private final GamePieceEdge gamePieceEdge = GamePieceEdge.NONE; + @Setter private Command command; + @Builder.Default private GamePieceEdge gamePieceEdge = GamePieceEdge.UNCONSTRAINED; + // START --- ADDED CODE + @Setter @Builder.Default private boolean requiresElevator = false; + @Setter @Builder.Default private boolean requiresArm = false; + // END --- ADDED CODE } /** @@ -51,6 +161,10 @@ public static class EdgeCommand extends DefaultEdge { * @param elevator The elevator subsystem. * @param intake The intake subsystem. * @param manipulator The manipulator subsystem. + * @param requiresElevator Flag indicating the elevator must finish its move before other + * mechanisms start. + * @param requiresArm Flag indicating the arm/intake must finish its move before the elevator + * starts. * @return A {@link Command} that, when executed, transitions the superstructure from the 'from' * state to the 'to' state. */ @@ -59,13 +173,31 @@ private static Command getEdgeCommand( V3_EpsilonSuperstructureStates to, ElevatorFSM elevator, V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { + V3_EpsilonManipulator manipulator, + boolean requiresElevator, + boolean requiresArm) { V3_EpsilonSuperstructurePose pose = to.getPose(); - // Default case: Execute all subsystem poses in parallel - return pose.asCommand(elevator, intake, manipulator); - } - private static void createEdges() { + if (requiresElevator && requiresArm) { + throw new IllegalArgumentException( + "Edge cannot require both elevator and arm to finish first"); + } else if (requiresElevator) { + // Elevator must finish before other mechanisms move + return Commands.sequence( + pose.setElevatorHeight(elevator), + Commands.waitUntil(elevator::atGoal), + pose.asCommand(elevator, intake, manipulator)); + } else if (requiresArm) { + // Arm/intake must clear before elevator moves + return Commands.sequence( + pose.setManipulatorState(manipulator), + Commands.waitUntil( + () -> + manipulator.getArmAngle().getDegrees() + < ManipulatorArmState.SAFE_ANGLE.getAngle().getDegrees()), + pose.asCommand(elevator, intake, manipulator)); + } + return pose.asCommand(elevator, intake, manipulator); } /** @@ -77,7 +209,6 @@ private static void createEdges() { * @param type The {@link GamePieceEdge} type associated with these edges. * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. - * @param funnel The funnel subsystem. * @param intake The intake subsystem. */ private static void addEdges( @@ -94,7 +225,10 @@ private static void addEdges( edge.from(), edge.to(), EdgeCommand.builder() - .command(getEdgeCommand(edge.from(), edge.to(), elevator, intake, manipulator)) + // Updated to call new signature with default 'false' values for requirements + .command( + getEdgeCommand( + edge.from(), edge.to(), elevator, intake, manipulator, false, false)) .gamePieceEdge(type) .build()); } @@ -106,7 +240,6 @@ private static void addEdges( * @param graph The graph to which edges are added. * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. - * @param funnel The funnel subsystem. * @param intake The intake subsystem. */ public static void addEdges( @@ -114,12 +247,17 @@ public static void addEdges( ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { - // Create all edge lists (NoneEdges, NoAlgaeEdges, AlgaeEdges) - createEdges(); + // This method populates the graph by parsing the DOT file. + loadEdgesFromDot( + Filesystem.getDeployDirectory().toPath().resolve("Superstructure.dot").toString(), + graph, + elevator, + intake, + manipulator); - // Add edges to the graph for each algae condition - addEdges(graph, NONE_EDGES, GamePieceEdge.NONE, elevator, manipulator, intake); - addEdges(graph, CORAL_EDGES, GamePieceEdge.CORAL, elevator, manipulator, intake); + // NOTE: The two lines below are likely redundant. The loadEdgesFromDot method already + // adds all edges to the graph. You may want to remove these calls. + addEdges(graph, UNCONSTRAINED, GamePieceEdge.UNCONSTRAINED, elevator, manipulator, intake); addEdges(graph, ALGAE_EDGES, GamePieceEdge.ALGAE, elevator, manipulator, intake); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java index 8a81cc56..b9175e8a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java @@ -43,9 +43,7 @@ public V3_EpsilonSuperstructurePose(String key, SubsystemPoses poses) { * @return A Command that sets the elevator height and waits until it reaches the goal. */ public Command setElevatorHeight(ElevatorFSM elevator) { - return Commands.parallel( - Commands.runOnce(() -> elevator.setPosition(() -> elevatorHeight)), - elevator.waitUntilAtGoal()); + return Commands.parallel(Commands.runOnce(() -> elevator.setPosition(() -> elevatorHeight))); } /** @@ -55,8 +53,7 @@ public Command setElevatorHeight(ElevatorFSM elevator) { * @return A Command that sets the intake extension state and waits until it reaches the goal. */ public Command setIntakeState(V3_EpsilonIntake intake) { - return Commands.parallel( - Commands.runOnce(() -> intake.setPivotGoal(intakeState)), intake.waitUntilPivotAtGoal()); + return Commands.parallel(Commands.runOnce(() -> intake.setPivotGoal(intakeState))); } /** @@ -66,7 +63,7 @@ public Command setIntakeState(V3_EpsilonIntake intake) { * @return A Command that sets the arm state and waits until it reaches the goal. */ public Command setManipulatorState(V3_EpsilonManipulator manipulator) { - return Commands.parallel(manipulator.setArmGoal(armState), manipulator.waitUntilArmAtGoal()); + return Commands.parallel(manipulator.setArmGoal(armState)); } /** @@ -87,6 +84,14 @@ public Command asCommand( Commands.runOnce(() -> intake.setPivotGoal(intakeState))); } + public Command wait( + ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { + return Commands.parallel( + elevator.waitUntilAtGoal(), + manipulator.waitUntilArmAtGoal(), + intake.waitUntilPivotAtGoal()); + } + /** * Returns a string representation of this pose (the key). * @@ -109,7 +114,7 @@ public record SubsystemPoses( * Creates a SubsystemPoses instance with default states (STOW for elevator, arm, and intake). */ public SubsystemPoses() { - this(ReefState.STOW, ManipulatorArmState.STOW_DOWN, IntakePivotState.STOW); + this(ReefState.STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW); } } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index b1ff2c3d..85b7c0ef 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -1,6 +1,5 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; -// Adjust the package path as needed import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureAction.SubsystemActions; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructurePose.SubsystemPoses; @@ -17,146 +16,112 @@ public enum V3_EpsilonSuperstructureStates { STOW_DOWN("STOW_DOWN", new SubsystemPoses(), SubsystemActions.empty()), STOW_UP( "STOW_UP", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.STOW_UP, IntakePivotState.STOW), + new SubsystemPoses( + ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), SubsystemActions.empty()), + OVERRIDE("OVERRIDE", new SubsystemPoses(), SubsystemActions.empty()), - HANDOFF( - "HANDOFF", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), + GROUND_ACQUISITION( + "GROUND_ACQUISITION", + new SubsystemPoses( + ReefState.STOW, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), SubsystemActions.empty()), - GROUND_INTAKE( "GROUND_INTAKE", new SubsystemPoses( - ReefState.STOW, ManipulatorArmState.FLOOR_INTAKE, IntakePivotState.INTAKE_CORAL), + ReefState.STOW, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.CORAL_INTAKE)), - // Coral Prep States - L1_PREP( + L1( "L1", - new SubsystemPoses(ReefState.L1, ManipulatorArmState.PRE_SCORE, IntakePivotState.L1), - SubsystemActions.empty()), - - L2_PREP( - "L2", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), SubsystemActions.empty()), - - L3_PREP( - "L3", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), - SubsystemActions.empty()), - - L4_PREP( - "L4", - new SubsystemPoses(ReefState.L4, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), - SubsystemActions.empty()), - - // Coral Score States L1_SCORE( "L1_SCORE", - new SubsystemPoses(ReefState.L1, ManipulatorArmState.PRE_SCORE, IntakePivotState.L1), + new SubsystemPoses(ReefState.L1, ManipulatorArmState.HANDOFF, IntakePivotState.L1), new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.SCORE_CORAL)), + L2( + "L2", + new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), + SubsystemActions.empty()), L2_SCORE( "L2_SCORE", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), + new SubsystemPoses(ReefState.L2, ManipulatorArmState.SCORE, IntakePivotState.STOW), new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), + L3( + "L3", + new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), + SubsystemActions.empty()), L3_SCORE( "L3_SCORE", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), + new SubsystemPoses(ReefState.L3, ManipulatorArmState.SCORE, IntakePivotState.STOW), new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), + L4( + "L4", + new SubsystemPoses(ReefState.L4, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), + SubsystemActions.empty()), L4_SCORE( "L4_SCORE", - new SubsystemPoses( - ReefState.L4, - ManipulatorArmState - .PRE_SCORE, // Determine whether PRE_SCORE is accurate for all scoring states - IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), + new SubsystemPoses(ReefState.L4, ManipulatorArmState.SCORE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.L4_SCORE, IntakeRollerState.STOP)), - // Algae Prep States - L2_ALGAE_PREP( - "L2_ALGAE_PREP", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), + HANDOFF( + "HANDOFF", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.STOW), SubsystemActions.empty()), - - L3_ALGAE_PREP( - "L3_ALGAE_PREP", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), + INTERMEDIATE_WAIT_FOR_ELEVATOR( + "INTERMEDIATE_WAIT_FOR_ELEVATOR", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), + SubsystemActions.empty()), + INTERMEDIATE_WAIT_FOR_ARM( + "INTERMEDIATE_WAIT_FOR_ARM", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.SAFE_ANGLE, IntakePivotState.STOW), SubsystemActions.empty()), - // Algae Scoring States + L2_ALGAE( + "L2_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + SubsystemActions.empty()), L2_ALGAE_INTAKE( "L2_ALGAE_INTAKE", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + new SubsystemPoses( + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), + L3_ALGAE( + "L3_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + SubsystemActions.empty()), L3_ALGAE_INTAKE( "L3_ALGAE_INTAKE", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.PRE_SCORE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), - - // Miscelaneous States (Barge + Processor Prep and Score States) - BARGE_PREP( - "BARGE_PREP", new SubsystemPoses( - ReefState.ALGAE_SCORE, - ManipulatorArmState - .REEF_INTAKE, // Assuming REEF_INTAKE and BARGE_PREP have same rotation values - IntakePivotState.STOW), - SubsystemActions.empty()), + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), - PROCESSOR_PREP( - "PROCESSOR_PREP", + PROCESSOR( + "PROCESSOR", new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), SubsystemActions.empty()), - - BARGE_SCORE( - "BARGE_SCORE", - new SubsystemPoses( - ReefState.ALGAE_SCORE, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions( - ManipulatorRollerState - .SCORE_ALGAE, // Assuming you score in the barge by stowing intake and moving - // manipulator to desired position - IntakeRollerState.STOP)), - PROCESSOR_SCORE( "PROCESSOR_SCORE", - new SubsystemPoses( - ReefState.ALGAE_SCORE, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), - INTERMIDIATE_WAIT_FOR_ELEVATOR( - "INTERMIDIATE_WAIT_FOR_ELEVATOR", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.STOW_UP, IntakePivotState.STOW), - SubsystemActions.empty()), - - // Transition States - L2_TRANSITION( - "L2_TRANSITION", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), - SubsystemActions.empty()), - - L3_TRANSITION( - "L3_TRANSITION", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), - SubsystemActions.empty()), - - L4_TRANSITION( - "L4_TRANSITION", - new SubsystemPoses(ReefState.L4, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), - SubsystemActions.empty()), - - CLIMB( - "CLIMB", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.STOW_UP, IntakePivotState.STOW), + BARGE( + "BARGE", + new SubsystemPoses( + ReefState.ALGAE_SCORE, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), SubsystemActions.empty()), - - OVERRIDE("OVERRIDE", new SubsystemPoses(), SubsystemActions.empty()); + BARGE_SCORE( + "BARGE_SCORE", + new SubsystemPoses(ReefState.ALGAE_SCORE, ManipulatorArmState.SCORE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + ; // Readable name for state private final String name; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index 56d21a29..fd6bcd98 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -48,11 +48,16 @@ public boolean hasCoral() { } @AutoLogOutput(key = "Intake/At Goal") - public boolean atGoal() { + public boolean pivotAtGoal() { return Math.abs(inputs.pivotPosition.getRadians() - pivotGoal.getAngle().getRadians()) < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); } + public boolean pivotAtGoal(IntakePivotState goal) { + return Math.abs(inputs.pivotPosition.getRadians() - goal.getAngle().getRadians()) + < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); + } + public void setPivotGoal(IntakePivotState goal) { isClosedLoop = true; this.pivotGoal = goal; @@ -68,7 +73,7 @@ public void setPivotVoltage(double volts) { } public Command waitUntilPivotAtGoal() { - return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::atGoal)); + return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::pivotAtGoal)); } public void setRollerGoal(IntakeRollerState rollerGoal) { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index e5784d81..5c3f243c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -14,7 +14,7 @@ public class V3_EpsilonManipulator { private final V3_EpsilonManipulatorIO io; private final ManipulatorIOInputsAutoLogged inputs; - private ManipulatorArmState state; + private ManipulatorArmState armState; private boolean isClosedLoop; public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { @@ -22,7 +22,7 @@ public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { inputs = new ManipulatorIOInputsAutoLogged(); isClosedLoop = true; - state = ManipulatorArmState.STOW_UP; + armState = ManipulatorArmState.VERTICAL_UP; } public void periodic() { @@ -30,7 +30,7 @@ public void periodic() { Logger.processInputs("Manipulator", inputs); if (isClosedLoop) { - io.setArmGoal(state.getAngle()); + io.setArmGoal(armState.getAngle()); } if (hasAlgae()) { @@ -63,7 +63,7 @@ public Command setArmGoal(ManipulatorArmState goal) { return Commands.runOnce( () -> { isClosedLoop = true; - state = goal; + armState = goal; }); } @@ -97,6 +97,11 @@ public void updateArmConstraints(double maxAcceleration, double maxVelocity) { @AutoLogOutput(key = "Manipulator/Arm At Goal") public boolean armAtGoal() { + return inputs.armPosition.getRadians() - armState.getAngle().getRadians() + <= V2_RedundancyManipulatorConstants.CONSTRAINTS.GOAL_TOLERANCE_RADIANS().get(); + } + + public boolean armAtGoal(ManipulatorArmState state) { return inputs.armPosition.getRadians() - state.getAngle().getRadians() <= V2_RedundancyManipulatorConstants.CONSTRAINTS.GOAL_TOLERANCE_RADIANS().get(); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 234a8616..9382ee89 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -138,17 +138,17 @@ public static record ArmParameters( @RequiredArgsConstructor public static enum ManipulatorArmState { - STOW_UP(Rotation2d.fromDegrees(0.0)), PRE_SCORE(Rotation2d.fromDegrees(50.0)), - SCORE(Rotation2d.fromDegrees(35.0)), // Placeholder value. Make sure to test + SCORE(Rotation2d.fromDegrees(55.0)), // Placeholder value. Make sure to test PROCESSOR(Rotation2d.fromDegrees(-61.279296875 + 20)), REEF_INTAKE(Rotation2d.fromDegrees(-61.279296875 + 15)), INTAKE_OUT_LINE(Rotation2d.fromDegrees(-61)), FLOOR_INTAKE(Rotation2d.fromDegrees(-68.5 - 5)), STOW_LINE(Rotation2d.fromDegrees(-75)), TRANSITION(Rotation2d.fromDegrees(15.0)), // Placeholder value. Make sure to test - STOW_DOWN(Rotation2d.fromDegrees(0)), - HANDOFF(Rotation2d.kPi); + VERTICAL_UP(Rotation2d.fromDegrees(0)), + HANDOFF(Rotation2d.kPi), + SAFE_ANGLE(Rotation2d.fromDegrees(150)); private final Rotation2d angle; From b361b7dc67e8ea8b11a8aa915307ad676e6bcf0a Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Mon, 1 Sep 2025 01:25:54 -0400 Subject: [PATCH 060/180] ughh --- src/main/deploy/Superstructure.dot | 58 +++++------ .../superstructure/Superstructure.dot | 68 +------------ .../V3_EpsilonSuperstructure.java | 2 +- .../V3_EpsilonSuperstructureEdges.java | 99 ++++++++++++++----- 4 files changed, 103 insertions(+), 124 deletions(-) diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/Superstructure.dot index 940605a4..de5ea24c 100644 --- a/src/main/deploy/Superstructure.dot +++ b/src/main/deploy/Superstructure.dot @@ -26,27 +26,15 @@ digraph Superstructure { GROUND_ACQUISITION -> PROCESSOR [type=UNCONSTRAINED] GROUND_ACQUISITION -> BARGE [type=UNCONSTRAINED] - GROUND_INTAKE -> STOW_DOWN [type=UNCONSTRAINED] GROUND_INTAKE -> GROUND_ACQUISITION [type=UNCONSTRAINED] - GROUND_INTAKE -> L1 [type=UNCONSTRAINED] - GROUND_INTAKE -> L2 [type=UNCONSTRAINED] - GROUND_INTAKE -> L3 [type=UNCONSTRAINED] - GROUND_INTAKE -> L4 [type=UNCONSTRAINED] - GROUND_INTAKE -> HANDOFF [type=UNCONSTRAINED] - GROUND_INTAKE -> STOW_UP [type=UNCONSTRAINED] - GROUND_INTAKE -> L2_ALGAE [type=UNCONSTRAINED] - GROUND_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] - GROUND_INTAKE -> PROCESSOR [type=UNCONSTRAINED] - GROUND_INTAKE -> BARGE [type=UNCONSTRAINED] - - L1 -> STOW_DOWN [type=UNCONSTRAINED] + L1 -> GROUND_ACQUISITION [type=UNCONSTRAINED] - L1 -> L2 [type=UNCONSTRAINED] + L1 -> L2 [type=UNCONSTRAINED, requires=ARM] L1 -> L3 [type=UNCONSTRAINED] L1 -> L4 [type=UNCONSTRAINED] L1 -> L1_SCORE [type=UNCONSTRAINED] L1 -> HANDOFF [type=UNCONSTRAINED] - L1 -> STOW_UP [type=UNCONSTRAINED] + L1 -> STOW_UP [type=UNCONSTRAINED, requires=ARM] L1 -> L2_ALGAE [type=UNCONSTRAINED] L1 -> L3_ALGAE [type=UNCONSTRAINED] L1 -> PROCESSOR [type=UNCONSTRAINED] @@ -139,49 +127,49 @@ digraph Superstructure { HANDOFF -> L2 [type=UNCONSTRAINED, requires=ARM] HANDOFF -> L3 [type=UNCONSTRAINED] HANDOFF -> L4 [type=UNCONSTRAINED] - HANDOFF -> STOW_UP [type=UNCONSTRAINED] + HANDOFF -> STOW_UP [type=UNCONSTRAINED, requires=ARM] HANDOFF -> L2_ALGAE [type=UNCONSTRAINED] HANDOFF -> L3_ALGAE [type=UNCONSTRAINED] - HANDOFF -> PROCESSOR [type=UNCONSTRAINED] + HANDOFF -> PROCESSOR [type=UNCONSTRAINED, requires=ARM] HANDOFF -> BARGE [type=UNCONSTRAINED] - STOW_UP -> STOW_DOWN [type=UNCONSTRAINED] - STOW_UP -> GROUND_ACQUISITION [type=UNCONSTRAINED] - STOW_UP -> L1 [type=UNCONSTRAINED] + STOW_UP -> STOW_DOWN [type=UNCONSTRAINED, requires=ELEVATOR] + STOW_UP -> GROUND_ACQUISITION [type=UNCONSTRAINED, requires=ELEVATOR] + STOW_UP -> L1 [type=UNCONSTRAINED, requires=ELEVATOR] STOW_UP -> L2 [type=UNCONSTRAINED] STOW_UP -> L3 [type=UNCONSTRAINED] STOW_UP -> L4 [type=UNCONSTRAINED] - STOW_UP -> HANDOFF [type=UNCONSTRAINED] + STOW_UP -> HANDOFF [type=UNCONSTRAINED, requires=ELEVATOR] STOW_UP -> L2_ALGAE [type=UNCONSTRAINED] STOW_UP -> L3_ALGAE [type=UNCONSTRAINED] STOW_UP -> PROCESSOR [type=UNCONSTRAINED] STOW_UP -> BARGE [type=UNCONSTRAINED] - L2_ALGAE -> STOW_DOWN [type = NO_ALGAE] - L2_ALGAE -> GROUND_ACQUISITION [type = NO_ALGAE] - L2_ALGAE -> L1 [type = NO_ALGAE] + L2_ALGAE -> STOW_DOWN [type=NO_ALGAE] + L2_ALGAE -> GROUND_ACQUISITION [type=NO_ALGAE] + L2_ALGAE -> L1 [type=NO_ALGAE] L2_ALGAE -> L2 [type=UNCONSTRAINED] L2_ALGAE -> L3 [type=UNCONSTRAINED] L2_ALGAE -> L4 [type=UNCONSTRAINED] - L2_ALGAE -> HANDOFF [type = NO_ALGAE] + L2_ALGAE -> HANDOFF [type=NO_ALGAE] L2_ALGAE -> STOW_UP [type=UNCONSTRAINED] L2_ALGAE -> L2_ALGAE_INTAKE [type=UNCONSTRAINED] - L2_ALGAE -> L3_ALGAE [type = NO_ALGAE] + L2_ALGAE -> L3_ALGAE [type=NO_ALGAE] L2_ALGAE -> PROCESSOR [type=UNCONSTRAINED] L2_ALGAE -> BARGE [type=UNCONSTRAINED] L2_ALGAE_INTAKE -> STOW_UP [type=UNCONSTRAINED] L2_ALGAE_INTAKE -> L2_ALGAE [type=UNCONSTRAINED] - L3_ALGAE -> STOW_DOWN [type = NO_ALGAE] - L3_ALGAE -> GROUND_ACQUISITION [type = NO_ALGAE] - L3_ALGAE -> L1 [type = NO_ALGAE] + L3_ALGAE -> STOW_DOWN [type=NO_ALGAE] + L3_ALGAE -> GROUND_ACQUISITION [type=NO_ALGAE] + L3_ALGAE -> L1 [type=NO_ALGAE] L3_ALGAE -> L2 [type=UNCONSTRAINED] L3_ALGAE -> L3 [type=UNCONSTRAINED] L3_ALGAE -> L4 [type=UNCONSTRAINED] - L3_ALGAE -> HANDOFF [type = NO_ALGAE] + L3_ALGAE -> HANDOFF [type=NO_ALGAE] L3_ALGAE -> STOW_UP [type=UNCONSTRAINED] - L3_ALGAE -> L2_ALGAE [type = NO_ALGAE] + L3_ALGAE -> L2_ALGAE [type=NO_ALGAE] L3_ALGAE -> L3_ALGAE_INTAKE [type=UNCONSTRAINED] L3_ALGAE -> PROCESSOR [type=UNCONSTRAINED] L3_ALGAE -> BARGE [type=UNCONSTRAINED] @@ -189,13 +177,13 @@ digraph Superstructure { L3_ALGAE_INTAKE -> STOW_UP [type=UNCONSTRAINED] L3_ALGAE_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] - PROCESSOR -> STOW_DOWN [type = NO_ALGAE] - PROCESSOR -> GROUND_ACQUISITION [type = NO_ALGAE] - PROCESSOR -> L1 [type = NO_ALGAE] + PROCESSOR -> STOW_DOWN [type=NO_ALGAE] + PROCESSOR -> GROUND_ACQUISITION [type=NO_ALGAE] + PROCESSOR -> L1 [type=NO_ALGAE] PROCESSOR -> L2 [type=UNCONSTRAINED] PROCESSOR -> L3 [type=UNCONSTRAINED] PROCESSOR -> L4 [type=UNCONSTRAINED] - PROCESSOR -> HANDOFF [type = NO_ALGAE] + PROCESSOR -> HANDOFF [type=NO_ALGAE] PROCESSOR -> STOW_UP [type=UNCONSTRAINED] PROCESSOR -> L2_ALGAE [type=UNCONSTRAINED] PROCESSOR -> L3_ALGAE [type=UNCONSTRAINED] diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index 8b68b87c..940605a4 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -1,14 +1,12 @@ digraph Superstructure { START -> STOW_DOWN [type=UNCONSTRAINED] - STOW_DOWN -> GROUND_ACQUISITION [type=UNCONSTRAINED] + STOW_DOWN -> GROUND_ACQUISITION [type=UNCONSTRAINED, requires=ELEVATOR] STOW_DOWN -> L1 [type=UNCONSTRAINED] STOW_DOWN -> L2 [type=UNCONSTRAINED] STOW_DOWN -> L3 [type=UNCONSTRAINED] STOW_DOWN -> L4 [type=UNCONSTRAINED] - // STOW_DOWN -> HANDOFF [type=UNCONSTRAINED] - STOW_DOWN -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - STOW_DOWN -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] + STOW_DOWN -> HANDOFF [type=UNCONSTRAINED, requires=ELEVATOR] STOW_DOWN -> STOW_UP [type=UNCONSTRAINED] STOW_DOWN -> L2_ALGAE [type=UNCONSTRAINED] STOW_DOWN -> L3_ALGAE [type=UNCONSTRAINED] @@ -22,8 +20,6 @@ digraph Superstructure { GROUND_ACQUISITION -> L3 [type=UNCONSTRAINED] GROUND_ACQUISITION -> L4 [type=UNCONSTRAINED] GROUND_ACQUISITION -> HANDOFF [type=UNCONSTRAINED] - GROUND_ACQUISITION -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - GROUND_ACQUISITION -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] GROUND_ACQUISITION -> STOW_UP [type=UNCONSTRAINED] GROUND_ACQUISITION -> L2_ALGAE [type=UNCONSTRAINED] GROUND_ACQUISITION -> L3_ALGAE [type=UNCONSTRAINED] @@ -37,8 +33,6 @@ digraph Superstructure { GROUND_INTAKE -> L3 [type=UNCONSTRAINED] GROUND_INTAKE -> L4 [type=UNCONSTRAINED] GROUND_INTAKE -> HANDOFF [type=UNCONSTRAINED] - GROUND_INTAKE -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - GROUND_INTAKE -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] GROUND_INTAKE -> STOW_UP [type=UNCONSTRAINED] GROUND_INTAKE -> L2_ALGAE [type=UNCONSTRAINED] GROUND_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] @@ -52,8 +46,6 @@ digraph Superstructure { L1 -> L4 [type=UNCONSTRAINED] L1 -> L1_SCORE [type=UNCONSTRAINED] L1 -> HANDOFF [type=UNCONSTRAINED] - L1 -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - L1 -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] L1 -> STOW_UP [type=UNCONSTRAINED] L1 -> L2_ALGAE [type=UNCONSTRAINED] L1 -> L3_ALGAE [type=UNCONSTRAINED] @@ -67,8 +59,6 @@ digraph Superstructure { L2 -> L4 [type=UNCONSTRAINED] L2 -> L2_SCORE [type=UNCONSTRAINED] L2 -> HANDOFF [type=UNCONSTRAINED] - L2 -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - L2 -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] L2 -> STOW_UP [type=UNCONSTRAINED] L2 -> L2_ALGAE [type=UNCONSTRAINED] L2 -> L3_ALGAE [type=UNCONSTRAINED] @@ -82,8 +72,6 @@ digraph Superstructure { L3 -> L4 [type=UNCONSTRAINED] L3 -> L3_SCORE [type=UNCONSTRAINED] L3 -> HANDOFF [type=UNCONSTRAINED] - L3 -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - L3 -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] L3 -> STOW_UP [type=UNCONSTRAINED] L3 -> L2_ALGAE [type=UNCONSTRAINED] L3 -> L3_ALGAE [type=UNCONSTRAINED] @@ -98,8 +86,6 @@ digraph Superstructure { L4 -> L3 [type=UNCONSTRAINED] L4 -> L4_SCORE [type=UNCONSTRAINED] L4 -> HANDOFF [type=UNCONSTRAINED] - L4 -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - L4 -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] L4 -> STOW_UP [type=UNCONSTRAINED] L4 -> L2_ALGAE [type=UNCONSTRAINED] L4 -> L3_ALGAE [type=UNCONSTRAINED] @@ -115,8 +101,6 @@ digraph Superstructure { L2_SCORE -> L3 [type=UNCONSTRAINED] L2_SCORE -> L4 [type=UNCONSTRAINED] L2_SCORE -> HANDOFF [type=UNCONSTRAINED] - L2_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - L2_SCORE -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] L2_SCORE -> STOW_UP [type=UNCONSTRAINED] L2_SCORE -> L2_ALGAE [type=UNCONSTRAINED] L2_SCORE -> L3_ALGAE [type=UNCONSTRAINED] @@ -130,8 +114,6 @@ digraph Superstructure { L3_SCORE -> L3 [type=UNCONSTRAINED] L3_SCORE -> L4 [type=UNCONSTRAINED] L3_SCORE -> HANDOFF [type=UNCONSTRAINED] - L3_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - L3_SCORE -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] L3_SCORE -> STOW_UP [type=UNCONSTRAINED] L3_SCORE -> L2_ALGAE [type=UNCONSTRAINED] L3_SCORE -> L3_ALGAE [type=UNCONSTRAINED] @@ -145,56 +127,24 @@ digraph Superstructure { L4_SCORE -> L3 [type=UNCONSTRAINED] L4_SCORE -> L4 [type=UNCONSTRAINED] L4_SCORE -> HANDOFF [type=UNCONSTRAINED] - L4_SCORE -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - L4_SCORE -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] L4_SCORE -> STOW_UP [type=UNCONSTRAINED] L4_SCORE -> L2_ALGAE [type=UNCONSTRAINED] L4_SCORE -> L3_ALGAE [type=UNCONSTRAINED] L4_SCORE -> PROCESSOR [type=UNCONSTRAINED] L4_SCORE -> BARGE [type=UNCONSTRAINED] - // HANDOFF -> STOW_DOWN [type=UNCONSTRAINED] + HANDOFF -> STOW_DOWN [type=UNCONSTRAINED, requires=ARM] HANDOFF -> GROUND_ACQUISITION [type=UNCONSTRAINED] HANDOFF -> L1 [type=UNCONSTRAINED] - HANDOFF -> L2 [type=UNCONSTRAINED] + HANDOFF -> L2 [type=UNCONSTRAINED, requires=ARM] HANDOFF -> L3 [type=UNCONSTRAINED] HANDOFF -> L4 [type=UNCONSTRAINED] - HANDOFF -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - HANDOFF -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] HANDOFF -> STOW_UP [type=UNCONSTRAINED] HANDOFF -> L2_ALGAE [type=UNCONSTRAINED] HANDOFF -> L3_ALGAE [type=UNCONSTRAINED] HANDOFF -> PROCESSOR [type=UNCONSTRAINED] HANDOFF -> BARGE [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ELEVATOR -> STOW_DOWN [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ELEVATOR -> GROUND_ACQUISITION [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L1 [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L2 [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L3 [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L4 [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ELEVATOR -> HANDOFF [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ELEVATOR -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ELEVATOR -> STOW_UP [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L2_ALGAE [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ELEVATOR -> L3_ALGAE [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ELEVATOR -> PROCESSOR [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ELEVATOR -> BARGE [type=UNCONSTRAINED] - - INTERMEDIATE_WAIT_FOR_ARM -> STOW_DOWN [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ARM -> GROUND_ACQUISITION [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ARM -> L1 [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ARM -> L2 [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ARM -> L3 [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ARM -> L4 [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ARM -> HANDOFF [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ARM -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ARM -> STOW_UP [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ARM -> L2_ALGAE [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ARM -> L3_ALGAE [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ARM -> PROCESSOR [type=UNCONSTRAINED] - INTERMEDIATE_WAIT_FOR_ARM -> BARGE [type=UNCONSTRAINED] - STOW_UP -> STOW_DOWN [type=UNCONSTRAINED] STOW_UP -> GROUND_ACQUISITION [type=UNCONSTRAINED] STOW_UP -> L1 [type=UNCONSTRAINED] @@ -202,8 +152,6 @@ digraph Superstructure { STOW_UP -> L3 [type=UNCONSTRAINED] STOW_UP -> L4 [type=UNCONSTRAINED] STOW_UP -> HANDOFF [type=UNCONSTRAINED] - STOW_UP -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - STOW_UP -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] STOW_UP -> L2_ALGAE [type=UNCONSTRAINED] STOW_UP -> L3_ALGAE [type=UNCONSTRAINED] STOW_UP -> PROCESSOR [type=UNCONSTRAINED] @@ -216,8 +164,6 @@ digraph Superstructure { L2_ALGAE -> L3 [type=UNCONSTRAINED] L2_ALGAE -> L4 [type=UNCONSTRAINED] L2_ALGAE -> HANDOFF [type = NO_ALGAE] - L2_ALGAE -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - L2_ALGAE -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] L2_ALGAE -> STOW_UP [type=UNCONSTRAINED] L2_ALGAE -> L2_ALGAE_INTAKE [type=UNCONSTRAINED] L2_ALGAE -> L3_ALGAE [type = NO_ALGAE] @@ -234,8 +180,6 @@ digraph Superstructure { L3_ALGAE -> L3 [type=UNCONSTRAINED] L3_ALGAE -> L4 [type=UNCONSTRAINED] L3_ALGAE -> HANDOFF [type = NO_ALGAE] - L3_ALGAE -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - L3_ALGAE -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] L3_ALGAE -> STOW_UP [type=UNCONSTRAINED] L3_ALGAE -> L2_ALGAE [type = NO_ALGAE] L3_ALGAE -> L3_ALGAE_INTAKE [type=UNCONSTRAINED] @@ -252,8 +196,6 @@ digraph Superstructure { PROCESSOR -> L3 [type=UNCONSTRAINED] PROCESSOR -> L4 [type=UNCONSTRAINED] PROCESSOR -> HANDOFF [type = NO_ALGAE] - PROCESSOR -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - PROCESSOR -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] PROCESSOR -> STOW_UP [type=UNCONSTRAINED] PROCESSOR -> L2_ALGAE [type=UNCONSTRAINED] PROCESSOR -> L3_ALGAE [type=UNCONSTRAINED] @@ -269,8 +211,6 @@ digraph Superstructure { BARGE -> L3 [type=UNCONSTRAINED] BARGE -> L4 [type=UNCONSTRAINED] BARGE -> HANDOFF [type=UNCONSTRAINED] - BARGE -> INTERMEDIATE_WAIT_FOR_ELEVATOR [type=UNCONSTRAINED] - BARGE -> INTERMEDIATE_WAIT_FOR_ARM [type=UNCONSTRAINED] BARGE -> STOW_UP [type=UNCONSTRAINED] BARGE -> L2_ALGAE [type=UNCONSTRAINED] BARGE -> L3_ALGAE [type=UNCONSTRAINED] diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 947f3a74..bcc5f4cb 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -243,7 +243,7 @@ private Optional bfs( */ private boolean isEdgeAllowed(EdgeCommand edge, V3_EpsilonSuperstructureStates goal) { return edge.getGamePieceEdge() == GamePieceEdge.UNCONSTRAINED - || RobotState.isHasAlgae() == (edge.getGamePieceEdge() == GamePieceEdge.ALGAE); + || RobotState.isHasAlgae() == (edge.getGamePieceEdge() != GamePieceEdge.NO_ALGAE); } /** Resets the superstructure to initial auto state. */ diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index 8a4db0e9..c3afe0b3 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -23,7 +23,7 @@ public class V3_EpsilonSuperstructureEdges { public static final ArrayList UNCONSTRAINED = new ArrayList<>(); - public static final ArrayList ALGAE_EDGES = new ArrayList<>(); + public static final ArrayList NO_ALGAE_EDGES = new ArrayList<>(); public record Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { public Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { @@ -39,7 +39,7 @@ public String toString() { public enum GamePieceEdge { UNCONSTRAINED, - ALGAE + NO_ALGAE } public static void loadEdgesFromDot( @@ -88,7 +88,7 @@ public static void loadEdgesFromDot( // Clear old edge lists UNCONSTRAINED.clear(); - ALGAE_EDGES.clear(); + NO_ALGAE_EDGES.clear(); // Iterate over edges to assign commands and categorize for (EdgeCommand e : graph.edgeSet()) { @@ -132,8 +132,8 @@ public static void loadEdgesFromDot( // Add to proper list Edge edge = new Edge(from, to); - if (type == V3_EpsilonSuperstructureEdges.GamePieceEdge.ALGAE) { - ALGAE_EDGES.add(edge); + if (type == V3_EpsilonSuperstructureEdges.GamePieceEdge.NO_ALGAE) { + NO_ALGAE_EDGES.add(edge); } else { UNCONSTRAINED.add(edge); } @@ -176,28 +176,41 @@ private static Command getEdgeCommand( V3_EpsilonManipulator manipulator, boolean requiresElevator, boolean requiresArm) { + V3_EpsilonSuperstructurePose pose = to.getPose(); + Command moveCommand; // This will hold the command that STARTS the movement. + + if (requiresElevator) { + // Elevator moves and waits, THEN other mechanisms move. + moveCommand = + Commands.sequence( + pose.setElevatorHeight(elevator), + Commands.waitUntil(elevator::atGoal), + pose.asCommand( + elevator, intake, manipulator) // CORRECTED: Only move the other subsystems + ); - if (requiresElevator && requiresArm) { - throw new IllegalArgumentException( - "Edge cannot require both elevator and arm to finish first"); - } else if (requiresElevator) { - // Elevator must finish before other mechanisms move - return Commands.sequence( - pose.setElevatorHeight(elevator), - Commands.waitUntil(elevator::atGoal), - pose.asCommand(elevator, intake, manipulator)); } else if (requiresArm) { - // Arm/intake must clear before elevator moves - return Commands.sequence( - pose.setManipulatorState(manipulator), - Commands.waitUntil( - () -> - manipulator.getArmAngle().getDegrees() - < ManipulatorArmState.SAFE_ANGLE.getAngle().getDegrees()), - pose.asCommand(elevator, intake, manipulator)); + // Arm moves to a safe position and waits, THEN other mechanisms move. + moveCommand = + Commands.sequence( + pose.setManipulatorState(manipulator), + Commands.waitUntil( + () -> + manipulator.getArmAngle().getDegrees() + < ManipulatorArmState.SAFE_ANGLE.getAngle().getDegrees()), + pose.asCommand( + elevator, intake, manipulator) // CORRECTED: Only move the other subsystems + ); + } else { + // Default case: All mechanisms move in parallel. + moveCommand = pose.asCommand(elevator, intake, manipulator); } - return pose.asCommand(elevator, intake, manipulator); + + // THE CRITICAL FIX: + // No matter how we start the move, we append a final wait condition. + // This ensures the command doesn't end until the robot is physically at the target pose. + return Commands.sequence(moveCommand, waitForPoseCommand(to, elevator, intake, manipulator)); } /** @@ -258,6 +271,44 @@ public static void addEdges( // NOTE: The two lines below are likely redundant. The loadEdgesFromDot method already // adds all edges to the graph. You may want to remove these calls. addEdges(graph, UNCONSTRAINED, GamePieceEdge.UNCONSTRAINED, elevator, manipulator, intake); - addEdges(graph, ALGAE_EDGES, GamePieceEdge.ALGAE, elevator, manipulator, intake); + addEdges(graph, NO_ALGAE_EDGES, GamePieceEdge.NO_ALGAE, elevator, manipulator, intake); + } + + // In V3_EpsilonSuperstructureEdges.java + + private static Command waitForPoseCommand( + V3_EpsilonSuperstructureStates state, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + V3_EpsilonSuperstructurePose pose = state.getPose(); + + // Add this command to log the check's status + Command logCheck = + Commands.runOnce( + () -> { + boolean elevatorOk = elevator.atGoal(pose.getElevatorHeight()); + boolean intakeOk = intake.pivotAtGoal(pose.getIntakeState()); + boolean armOk = manipulator.armAtGoal(pose.getArmState()); + System.out.println( + "Checking pose for: " + + state.toString() + + " -> Elevator OK: " + + elevatorOk + + ", Intake OK: " + + intakeOk + + ", Arm OK: " + + armOk); + }); + + Command wait = + Commands.waitUntil( + () -> + elevator.atGoal(pose.getElevatorHeight()) + && intake.pivotAtGoal(pose.getIntakeState()) + && manipulator.armAtGoal(pose.getArmState())); + + // Run the log once right before starting the wait + return Commands.sequence(logCheck, wait); } } From ea5d414fd9ebc38db509a91491de5683b739133b Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Mon, 1 Sep 2025 14:24:53 -0400 Subject: [PATCH 061/180] Refactor ElevatorPositions to use PositionConstants for improved structure and clarity and add V3 Elevator positions Co-authored-by: CXu965 Co-authored-by: Sriaditya Vaddadi Co-authored-by: Elliot Scher Co-authored-by: Seetha Raman, Abhiruph Co-authored-by: Joshi, Atharv --- .../shared/elevator/ElevatorConstants.java | 78 +++++++++++++++---- 1 file changed, 61 insertions(+), 17 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index d968385b..7c1f0f35 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -213,27 +213,71 @@ public static record ElevatorParameters( double MAX_HEIGHT_METERS, int NUM_MOTORS) {} + public static record PositionConstants( + double V1, + double V2, + double V3) {} + @RequiredArgsConstructor public static enum ElevatorPositions { - STOW(0.0), - CORAL_INTAKE(0.0), - ALGAE_INTAKE(0.2161583093038944 + Units.inchesToMeters(1)), - ALGAE_MID(0.7073684509805078), - ALGAE_INTAKE_TOP(1.17 - Units.inchesToMeters(8)), - ALGAE_INTAKE_BOT(0.79 - Units.inchesToMeters(8)), - ASS_TOP(1.2), - ASS_BOT(0.82), - L1(0.11295250319916351), - L2(0.37296301250898894), - L3(0.7606347556550676 + Units.inchesToMeters(1.0)), - L4(1.3864590139769697 + Units.inchesToMeters(0.5)), - L4_PLUS(1.3864590139769697 + Units.inchesToMeters(2.0)), - ALGAE_SCORE(1.3864590139769697 + Units.inchesToMeters(0.5)); - - private final double position; + STOW(new PositionConstants(0.0, + 0.0, + 0.0)), + CORAL_INTAKE(new PositionConstants(0.0, + 0.0, + Units.inchesToMeters(34.75))), + ALGAE_INTAKE(new PositionConstants(0.2161583093038944 + Units.inchesToMeters(1), + 0.2161583093038944 + Units.inchesToMeters(1), + 0.2161583093038944 + Units.inchesToMeters(1))), + ALGAE_MID(new PositionConstants(0.7073684509805078, + 0.7073684509805078, + 0.0)), // DOES NOT EXIST FOR V3 + ALGAE_INTAKE_TOP(new PositionConstants(1.17 - Units.inchesToMeters(8), + 1.17 - Units.inchesToMeters(8), + Units.inchesToMeters(40))), + ALGAE_INTAKE_BOT(new PositionConstants(0.79 - Units.inchesToMeters(8), + 0.79 - Units.inchesToMeters(8), + Units.inchesToMeters(25))), + ASS_TOP(new PositionConstants(1.2, + 0.0, + 0.0)), + ASS_BOT(new PositionConstants(0.82, + 0.0, + 0.0)), + L1(new PositionConstants(0.11295250319916351, + 0.11295250319916351, + Units.inchesToMeters(34.75))), + L2(new PositionConstants(0.37296301250898894, + 0.37296301250898894, + Units.inchesToMeters(12.5))), + L3(new PositionConstants(0.7606347556550676 + Units.inchesToMeters(1.0), + 0.7606347556550676 + Units.inchesToMeters(1.0), + Units.inchesToMeters(12.5 + 15.87))), + L4(new PositionConstants(1.3864590139769697 + Units.inchesToMeters(0.5), + 1.3864590139769697 + Units.inchesToMeters(0.5), + Units.inchesToMeters(57))), + L4_PLUS(new PositionConstants(0.0, + 1.3864590139769697 + Units.inchesToMeters(2.0), + 0.0)), // DOES NOT EXIST FOR V3 AND V1 + ALGAE_SCORE(new PositionConstants(1.3864590139769697 + Units.inchesToMeters(0.5), + 1.3864590139769697 + Units.inchesToMeters(0.5), + Units.inchesToMeters(61))); + + private final PositionConstants position; public double getPosition() { - return position; + switch(Constants.ROBOT) { + case V1_STACKUP, V1_STACKUP_SIM: + return position.V1(); + case V2_REDUNDANCY, V2_REDUNDANCY_SIM: + return position.V2(); + case V3_EPSILON, V3_EPSILON_SIM: + return position.V3(); + default: + return position.V1(); + } + } } + } From 7c861ee3c7eb9900582d46b1a20664dbdfb49756 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Mon, 1 Sep 2025 14:44:49 -0400 Subject: [PATCH 062/180] Fixed errors for v3 robot container. Should be all set now. --- .../frc/robot/commands/CompositeCommands.java | 69 +++++++++++++++++++ .../v3_Epsilon/V3_EpsilonRobotContainer.java | 65 +++++++++-------- 2 files changed, 104 insertions(+), 30 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 679a0c9f..f6746624 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -838,6 +838,75 @@ public static final Command intakeAlgaeFromReefSequence( .withTimeout(0.5))); } + /** + * Creates a command to drop algae from the reef. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param intake The intake subsystem. + * @param superstructure The superstructure subsystem. + * @param level A supplier that provides the current reef level. + * @param cameras The vision cameras. + * @return A command to drop algae from the reef. + */ + public static final Command dropAlgae( + Drive drive, + ElevatorFSM elevator, + V3_EpsilonManipulator manipulator, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Supplier level, + Camera... cameras) { + return Commands.sequence( + DriveCommands.autoAlignReefAlgae(drive, cameras), + Commands.sequence( + superstructure + .runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.INTAKE_REEF_L3; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.INTAKE_REEF_L2; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }) + .until(() -> RobotState.isHasAlgae()), + Commands.waitSeconds(2.0), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) + .withTimeout(0.5)), + superstructure.runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.DROP_REEF_L3; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.DROP_REEF_L2; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }), + Commands.waitSeconds(1.0), + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); + } + + /** + * Creates a command sequence for the floor intake of algae. + * + * @param superstructure The superstructure subsystem. + * @return A command sequence for the floor intake. + */ + public static final Command floorIntakeSequence(V3_EpsilonSuperstructure superstructure) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoalUntil( + V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> RobotState.isHasAlgae())); + } + /** * Creates a command that posts the floor intake sequence, which can either go up or down based * on whether the robot has algae. diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 537a5fca..2d8b963d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -108,39 +108,43 @@ public V3_EpsilonRobotContainer() { default: break; } - if (drive == null) { - drive = - new Drive( - new GyroIO() { - // Provide concrete implementation for GyroIO methods here - }, - new ModuleIO() {}, - new ModuleIO() {}, - new ModuleIO() {}, - new ModuleIO() {}); - } - if (elevator == null) { - elevator = new Elevator(new ElevatorIO() {}).getFSM(); - } + } - if (intake == null) { - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); - } - // if (leds == null) { - // leds = new V3_EpsilonLEDs(); - // } - if (manipulator == null) { - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); - } - // if (vision == null) { - // vision = new Vision(); - // } - superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + if (drive == null) { + drive = + new Drive( + new GyroIO() { + // Provide concrete implementation for GyroIO methods here + }, + new ModuleIO() { + }, + new ModuleIO() { + }, + new ModuleIO() { + }, + new ModuleIO() { + }); + if (elevator == null) { + elevator = new Elevator(new ElevatorIO() {}).getFSM(); + } + + if (intake == null) { + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); + } + // if (leds == null) { + // leds = new V3_EpsilonLEDs(); + // } + if (manipulator == null) { + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); + } + // if (vision == null) { + // vision = new Vision(); + // } + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); - configureButtonBindings(); - configureAutos(); + configureButtonBindings(); } - } +} public void configureButtonBindings() { // Generic triggers @@ -428,3 +432,4 @@ public Command getAutonomousCommand() { return autoChooser.selectedCommand(); } } + From 194893b7d0e8bcf66a4aca651050a8421d4d4494 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Mon, 1 Sep 2025 15:01:42 -0400 Subject: [PATCH 063/180] merge conflict --- .../frc/robot/commands/CompositeCommands.java | 87 ++++++------- .../shared/elevator/ElevatorConstants.java | 117 +++++++++--------- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 51 ++++---- 3 files changed, 125 insertions(+), 130 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index f6746624..05137a2c 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -850,49 +850,50 @@ public static final Command intakeAlgaeFromReefSequence( * @param cameras The vision cameras. * @return A command to drop algae from the reef. */ - public static final Command dropAlgae( - Drive drive, - ElevatorFSM elevator, - V3_EpsilonManipulator manipulator, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Supplier level, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefAlgae(drive, cameras), - Commands.sequence( - superstructure - .runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.INTAKE_REEF_L3; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.INTAKE_REEF_L2; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }) - .until(() -> RobotState.isHasAlgae()), - Commands.waitSeconds(2.0), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) - .withTimeout(0.5)), - superstructure.runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.DROP_REEF_L3; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.DROP_REEF_L2; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }), - Commands.waitSeconds(1.0), - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); - } + // public static final Command dropAlgae( + // Drive drive, + // ElevatorFSM elevator, + // V3_EpsilonManipulator manipulator, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // Supplier level, + // Camera... cameras) { + // return Commands.sequence( + // DriveCommands.autoAlignReefAlgae(drive, cameras), + // Commands.sequence( + // superstructure + // .runGoal( + // () -> { + // switch (level.get()) { + // case ALGAE_INTAKE_TOP: + // return V3_EpsilonSuperstructureStates.INTAKE_REEF_L3; + // case ALGAE_INTAKE_BOTTOM: + // return V3_EpsilonSuperstructureStates.INTAKE_REEF_L2; + // default: + // return V3_EpsilonSuperstructureStates.STOW_DOWN; + // } + // }) + // .until(() -> RobotState.isHasAlgae()), + // Commands.waitSeconds(2.0), + // Commands.runEnd( + // () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> + // drive.stop()) + // .withTimeout(0.5)), + // superstructure.runGoal( + // () -> { + // switch (level.get()) { + // case ALGAE_INTAKE_TOP: + // return V3_EpsilonSuperstructureStates.DROP_REEF_L3; + // case ALGAE_INTAKE_BOTTOM: + // return V3_EpsilonSuperstructureStates.DROP_REEF_L2; + // default: + // return V3_EpsilonSuperstructureStates.STOW_DOWN; + // } + // }), + // Commands.waitSeconds(1.0), + // Commands.runOnce(() -> RobotState.setHasAlgae(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); + // } /** * Creates a command sequence for the floor intake of algae. diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index 7c1f0f35..882b55e2 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -213,71 +213,70 @@ public static record ElevatorParameters( double MAX_HEIGHT_METERS, int NUM_MOTORS) {} - public static record PositionConstants( - double V1, - double V2, - double V3) {} - + public static record PositionConstants(double V1, double V2, double V3) {} + @RequiredArgsConstructor public static enum ElevatorPositions { - STOW(new PositionConstants(0.0, - 0.0, - 0.0)), - CORAL_INTAKE(new PositionConstants(0.0, - 0.0, - Units.inchesToMeters(34.75))), - ALGAE_INTAKE(new PositionConstants(0.2161583093038944 + Units.inchesToMeters(1), - 0.2161583093038944 + Units.inchesToMeters(1), - 0.2161583093038944 + Units.inchesToMeters(1))), - ALGAE_MID(new PositionConstants(0.7073684509805078, - 0.7073684509805078, - 0.0)), // DOES NOT EXIST FOR V3 - ALGAE_INTAKE_TOP(new PositionConstants(1.17 - Units.inchesToMeters(8), - 1.17 - Units.inchesToMeters(8), - Units.inchesToMeters(40))), - ALGAE_INTAKE_BOT(new PositionConstants(0.79 - Units.inchesToMeters(8), - 0.79 - Units.inchesToMeters(8), - Units.inchesToMeters(25))), - ASS_TOP(new PositionConstants(1.2, - 0.0, - 0.0)), - ASS_BOT(new PositionConstants(0.82, - 0.0, - 0.0)), - L1(new PositionConstants(0.11295250319916351, - 0.11295250319916351, - Units.inchesToMeters(34.75))), - L2(new PositionConstants(0.37296301250898894, - 0.37296301250898894, - Units.inchesToMeters(12.5))), - L3(new PositionConstants(0.7606347556550676 + Units.inchesToMeters(1.0), - 0.7606347556550676 + Units.inchesToMeters(1.0), - Units.inchesToMeters(12.5 + 15.87))), - L4(new PositionConstants(1.3864590139769697 + Units.inchesToMeters(0.5), - 1.3864590139769697 + Units.inchesToMeters(0.5), - Units.inchesToMeters(57))), - L4_PLUS(new PositionConstants(0.0, - 1.3864590139769697 + Units.inchesToMeters(2.0), - 0.0)), // DOES NOT EXIST FOR V3 AND V1 - ALGAE_SCORE(new PositionConstants(1.3864590139769697 + Units.inchesToMeters(0.5), - 1.3864590139769697 + Units.inchesToMeters(0.5), - Units.inchesToMeters(61))); + STOW(new PositionConstants(0.0, 0.0, 0.0)), + CORAL_INTAKE(new PositionConstants(0.0, 0.0, Units.inchesToMeters(34.75))), + ALGAE_INTAKE( + new PositionConstants( + 0.2161583093038944 + Units.inchesToMeters(1), + 0.2161583093038944 + Units.inchesToMeters(1), + 0.2161583093038944 + Units.inchesToMeters(1))), + ALGAE_MID( + new PositionConstants( + 0.7073684509805078, 0.7073684509805078, 0.0)), // DOES NOT EXIST FOR V3 + ALGAE_INTAKE_TOP( + new PositionConstants( + 1.17 - Units.inchesToMeters(8), + 1.17 - Units.inchesToMeters(8), + Units.inchesToMeters(40))), + ALGAE_INTAKE_BOT( + new PositionConstants( + 0.79 - Units.inchesToMeters(8), + 0.79 - Units.inchesToMeters(8), + Units.inchesToMeters(25))), + ASS_TOP(new PositionConstants(1.2, 0.0, 0.0)), + ASS_BOT(new PositionConstants(0.82, 0.0, 0.0)), + L1( + new PositionConstants( + 0.11295250319916351, 0.11295250319916351, Units.inchesToMeters(34.75))), + L2(new PositionConstants(0.37296301250898894, 0.37296301250898894, Units.inchesToMeters(12.5))), + L3( + new PositionConstants( + 0.7606347556550676 + Units.inchesToMeters(1.0), + 0.7606347556550676 + Units.inchesToMeters(1.0), + Units.inchesToMeters(12.5 + 15.87))), + L4( + new PositionConstants( + 1.3864590139769697 + Units.inchesToMeters(0.5), + 1.3864590139769697 + Units.inchesToMeters(0.5), + Units.inchesToMeters(57))), + L4_PLUS( + new PositionConstants( + 0.0, + 1.3864590139769697 + Units.inchesToMeters(2.0), + 0.0)), // DOES NOT EXIST FOR V3 AND V1 + ALGAE_SCORE( + new PositionConstants( + 1.3864590139769697 + Units.inchesToMeters(0.5), + 1.3864590139769697 + Units.inchesToMeters(0.5), + Units.inchesToMeters(61))); private final PositionConstants position; public double getPosition() { - switch(Constants.ROBOT) { - case V1_STACKUP, V1_STACKUP_SIM: - return position.V1(); - case V2_REDUNDANCY, V2_REDUNDANCY_SIM: - return position.V2(); - case V3_EPSILON, V3_EPSILON_SIM: - return position.V3(); - default: - return position.V1(); - } - + switch (Constants.ROBOT) { + case V1_STACKUP, V1_STACKUP_SIM: + return position.V1(); + case V2_REDUNDANCY, V2_REDUNDANCY_SIM: + return position.V2(); + case V3_EPSILON, V3_EPSILON_SIM: + return position.V3(); + default: + return position.V1(); + } } } - } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 2d8b963d..1e57c2de 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -116,35 +116,31 @@ public V3_EpsilonRobotContainer() { new GyroIO() { // Provide concrete implementation for GyroIO methods here }, - new ModuleIO() { - }, - new ModuleIO() { - }, - new ModuleIO() { - }, - new ModuleIO() { - }); - if (elevator == null) { - elevator = new Elevator(new ElevatorIO() {}).getFSM(); - } - - if (intake == null) { - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); - } - // if (leds == null) { - // leds = new V3_EpsilonLEDs(); - // } - if (manipulator == null) { - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); - } - // if (vision == null) { - // vision = new Vision(); - // } - superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}); + if (elevator == null) { + elevator = new Elevator(new ElevatorIO() {}).getFSM(); + } - configureButtonBindings(); + if (intake == null) { + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); + } + // if (leds == null) { + // leds = new V3_EpsilonLEDs(); + // } + if (manipulator == null) { + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); + } + // if (vision == null) { + // vision = new Vision(); + // } + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + + configureButtonBindings(); } -} + } public void configureButtonBindings() { // Generic triggers @@ -432,4 +428,3 @@ public Command getAutonomousCommand() { return autoChooser.selectedCommand(); } } - From 358e46111f809ba819907ef4e0d3274f66642e46 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Mon, 1 Sep 2025 15:02:11 -0400 Subject: [PATCH 064/180] start simulating --- src/main/java/frc/robot/Constants.java | 2 +- src/main/java/frc/robot/Robot.java | 2 + .../v3_Epsilon/V3_EpsilonRobotContainer.java | 61 ++++++++++--------- .../intake/V3_EpsilonIntake.java | 5 ++ 4 files changed, 41 insertions(+), 29 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index d181f165..6c45c947 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -5,7 +5,7 @@ public final class Constants { public static final boolean TUNING_MODE = false; public static final double LOOP_PERIOD_SECONDS = 0.02; - public static final RobotType ROBOT = RobotType.V2_REDUNDANCY; + public static final RobotType ROBOT = RobotType.V3_EPSILON_SIM; public static Mode getMode() { switch (ROBOT) { diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index aa8761af..222c6408 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -20,6 +20,7 @@ import frc.robot.subsystems.v0_Whiplash.V0_WhiplashRobotContainer; import frc.robot.subsystems.v1_StackUp.V1_StackUpRobotContainer; import frc.robot.subsystems.v2_Redundancy.V2_RedundancyRobotContainer; +import frc.robot.subsystems.v3_Epsilon.V3_EpsilonRobotContainer; import frc.robot.util.Alert; import frc.robot.util.Alert.AlertType; import frc.robot.util.CanivoreReader; @@ -155,6 +156,7 @@ public void robotInit() { V0_GOMPEIVISION_TEST_SIM -> new v0_GompeivisionTestRobotContainer(); case V1_STACKUP, V1_STACKUP_SIM -> new V1_StackUpRobotContainer(); case V2_REDUNDANCY, V2_REDUNDANCY_SIM -> new V2_RedundancyRobotContainer(); + case V3_EPSILON, V3_EPSILON_SIM -> new V3_EpsilonRobotContainer(); default -> new RobotContainer() {}; }; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 1e57c2de..2a041d21 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -1,6 +1,6 @@ package frc.robot.subsystems.v3_Epsilon; -// import edu.wpi.first.networktables.NetworkTablesJNI; +import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; @@ -17,6 +17,8 @@ import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; import frc.robot.commands.DriveCommands; import frc.robot.subsystems.shared.climber.Climber; +import frc.robot.subsystems.shared.climber.ClimberIO; +import frc.robot.subsystems.shared.climber.ClimberIOSim; // import frc.robot.subsystems.shared.climber.ClimberIO; // import frc.robot.subsystems.shared.climber.ClimberIOSim; import frc.robot.subsystems.shared.climber.ClimberIOTalonFX; @@ -49,6 +51,7 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIO; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOSim; import frc.robot.util.LoggedChoreo.ChoreoChooser; +import org.littletonrobotics.junction.Logger; public class V3_EpsilonRobotContainer implements RobotContainer { // Subsystems @@ -91,7 +94,7 @@ public V3_EpsilonRobotContainer() { // vision = new Vision(RobotCameras.V3_Epsilon_CAMS); break; case V3_EPSILON_SIM: - // climber = new Climber(new ClimberIOSim()); + climber = new Climber(new ClimberIOSim()); drive = new Drive( new GyroIO() {}, @@ -133,6 +136,9 @@ public V3_EpsilonRobotContainer() { if (manipulator == null) { manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); } + if (climber == null) { + climber = new Climber(new ClimberIO() {}); + } // if (vision == null) { // vision = new Vision(); // } @@ -397,34 +403,33 @@ private void configureAutos() { SmartDashboard.putData("Autonomous Modes", autoChooser); } - // @Override - // public void robotPeriodic() { - // RobotState.periodic( - // drive.getRawGyroRotation(), - // NetworkTablesJNI.now(), - // drive.getYawVelocity(), - // drive.getFieldRelativeVelocity(), - // drive.getModulePositions(), - // manipulator.getArmAngle(), - // elevator.getPositionMeters()); - - // LTNUpdater.updateDrive(drive); - // LTNUpdater.updateElevator(elevator); - // LTNUpdater.updateFunnel(funnel); - // LTNUpdater.updateAlgaeArm(manipulator); - // LTNUpdater.updateIntake(intake); - - // Logger.recordOutput( - // "Component Poses", - // V3_EpsilonMechanism3d.getPoses( - // elevator.getPositionMeters(), - // funnel.getAngle(), - // manipulator.getArmAngle(), - // intake.getExtension())); - // } + @Override + public void robotPeriodic() { + RobotState.periodic( + drive.getRawGyroRotation(), + NetworkTablesJNI.now(), + drive.getYawVelocity(), + drive.getModulePositions(), + null); + + // LTNUpdater.updateDrive(drive); + // LTNUpdater.updateElevator(elevator); + // LTNUpdater.updateFunnel(funnel); + // LTNUpdater.updateAlgaeArm(manipulator); + // LTNUpdater.updateIntake(intake); + + Logger.recordOutput( + "Component Poses", + V3_EpsilonMechanism3d.getPoses( + elevator.getPositionMeters(), intake.getPivotAngle(), manipulator.getArmAngle())); + } @Override public Command getAutonomousCommand() { - return autoChooser.selectedCommand(); + return superstructure + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE) + .andThen( + Commands.waitSeconds(1), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index 04850a3b..c49768e8 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -2,6 +2,7 @@ import static edu.wpi.first.units.Units.*; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; @@ -99,4 +100,8 @@ public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { public void setRollerGoal(V3_EpsilonIntakeConstants.IntakeRollerStates rollerGoal) { this.rollerGoal = rollerGoal; } + + public Rotation2d getPivotAngle() { + return inputs.pivotPosition; + } } From 2983ef88e7b9d1bd08639870733239e78484b68f Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Mon, 1 Sep 2025 15:20:35 -0400 Subject: [PATCH 065/180] temp fix --- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 40 +++++++++---------- .../V3_EpsilonSuperstructureEdges.java | 2 +- 2 files changed, 20 insertions(+), 22 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 2a041d21..ff3a101f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -123,29 +123,27 @@ public V3_EpsilonRobotContainer() { new ModuleIO() {}, new ModuleIO() {}, new ModuleIO() {}); - if (elevator == null) { - elevator = new Elevator(new ElevatorIO() {}).getFSM(); - } - - if (intake == null) { - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); - } - // if (leds == null) { - // leds = new V3_EpsilonLEDs(); - // } - if (manipulator == null) { - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); - } - if (climber == null) { - climber = new Climber(new ClimberIO() {}); - } - // if (vision == null) { - // vision = new Vision(); - // } - superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + } + if (elevator == null) { + elevator = new Elevator(new ElevatorIO() {}).getFSM(); + } - configureButtonBindings(); + if (intake == null) { + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); + } + // if (leds == null) { + // leds = new V3_EpsilonLEDs(); + // } + if (manipulator == null) { + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); + } + if (climber == null) { + climber = new Climber(new ClimberIO() {}); } + // if (vision == null) { + // vision = new Vision(); + // } + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); } public void configureButtonBindings() { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index 14abf24b..1a379f9c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -58,7 +58,7 @@ private static Command getEdgeCommand( // TODO: Implement the actual command logic - return Commands.none(); + return to.getPose().asCommand(elevator, manipulator, intake); } public static void createEdges() { From 84542c14236d5994481980c4de2edf719e606134 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Mon, 1 Sep 2025 16:42:11 -0400 Subject: [PATCH 066/180] build --- .../robot/commands/AutonomousCommands.java | 1441 ++++++++--------- .../shared/elevator/ElevatorConstants.java | 8 +- .../manipulator/V3_EpsilonManipulator.java | 6 +- 3 files changed, 730 insertions(+), 725 deletions(-) diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index 1afb6fba..1353bc9c 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -19,9 +19,6 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructure; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.util.AllianceFlipUtil; import frc.robot.util.LoggedChoreo.LoggedAutoRoutine; import frc.robot.util.LoggedChoreo.LoggedAutoTrajectory; @@ -1083,723 +1080,723 @@ public static final LoggedAutoRoutine autoDCenter( // V3 - public static final LoggedAutoRoutine autoALeft( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeft"); - - LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_LEFT_PATH4") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path3.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path4.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoALeftNashoba( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftNashoba"); - - LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_LEFT_PATH_ALT3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_LEFT_PATH_ALT4") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path3.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path4.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoALeftDAVE( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftD.A.V.E."); - - LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_LEFT_PATH4_ALT_ALT") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path3.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path4.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoARight( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoARight"); - - LoggedAutoTrajectory path1 = routine.trajectory("A_RIGHT_PATH1"); - LoggedAutoTrajectory path2 = - routine - .trajectory("A_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("A_RIGHT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path4 = - routine - .trajectory("A_RIGHT_PATH4") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path3.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.25), - Commands.deadline( - path4.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoBLeft( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBLeft"); - LoggedAutoTrajectory path1 = - routine - .trajectory("B_LEFT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("B_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); - - return routine; - } - - public static final LoggedAutoRoutine autoCLeft( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_LEFT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5), - Commands.deadline( - path3.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoCLeftPush( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_LEFT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_LEFT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_LEFT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), - () -> drive.stop()) - .withTimeout(0.5), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5), - Commands.deadline( - path3.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5))); - - return routine; - } - - public static final LoggedAutoRoutine autoCRight( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_RIGHT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_RIGHT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5), - Commands.deadline( - path3.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5))); - return routine; - } - - public static final LoggedAutoRoutine autoCRightPush( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); - LoggedAutoTrajectory path1 = - routine - .trajectory("C_RIGHT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("C_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path3 = - routine - .trajectory("C_RIGHT_PATH3") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, 1.0, 0.0)), - () -> drive.stop()) - .withTimeout(0.5), - path1.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5), - Commands.deadline( - path3.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> superstructure.atGoal())), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5))); - return routine; - } - - public static final LoggedAutoRoutine autoBRight( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBRight"); - LoggedAutoTrajectory path1 = - routine - .trajectory("B_RIGHT_PATH1") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - LoggedAutoTrajectory path2 = - routine - .trajectory("B_RIGHT_PATH2") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_PREP)), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5), - Commands.deadline( - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); - - return routine; - } - - public static final LoggedAutoRoutine autoDCenter( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoDCenter"); - LoggedAutoTrajectory path1 = - routine - .trajectory("D_CENTER_PATH") - .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), - superstructure.runActionWithTimeout( - V3_EpsilonSuperstructureStates.STOW_DOWN, - V3_EpsilonSuperstructureStates.L4_SCORE, - 0.5))); - return routine; - } + // public static final LoggedAutoRoutine autoALeft( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // Camera... cameras) { + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeft"); + + // LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("A_LEFT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path3 = + // routine + // .trajectory("A_LEFT_PATH3") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path4 = + // routine + // .trajectory("A_LEFT_PATH4") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + // path1.cmd(), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path4.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + + // return routine; + // } + + // public static final LoggedAutoRoutine autoALeftNashoba( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // Camera... cameras) { + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftNashoba"); + + // LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("A_LEFT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path3 = + // routine + // .trajectory("A_LEFT_PATH_ALT3") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path4 = + // routine + // .trajectory("A_LEFT_PATH_ALT4") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + // path1.cmd(), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path4.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + + // return routine; + // } + + // public static final LoggedAutoRoutine autoALeftDAVE( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // Camera... cameras) { + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftD.A.V.E."); + + // LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("A_LEFT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path3 = + // routine + // .trajectory("A_LEFT_PATH3") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path4 = + // routine + // .trajectory("A_LEFT_PATH4_ALT_ALT") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + // path1.cmd(), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path4.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + + // return routine; + // } + + // public static final LoggedAutoRoutine autoARight( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // Camera... cameras) { + + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoARight"); + + // LoggedAutoTrajectory path1 = routine.trajectory("A_RIGHT_PATH1"); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("A_RIGHT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path3 = + // routine + // .trajectory("A_RIGHT_PATH3") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path4 = + // routine + // .trajectory("A_RIGHT_PATH4") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + // path1.cmd(), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path4.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + + // return routine; + // } + + // public static final LoggedAutoRoutine autoBLeft( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // Camera... cameras) { + + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBLeft"); + // LoggedAutoTrajectory path1 = + // routine + // .trajectory("B_LEFT_PATH1") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("B_LEFT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + // path1.cmd(), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); + + // return routine; + // } + + // public static final LoggedAutoRoutine autoCLeft( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // Camera... cameras) { + + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); + // LoggedAutoTrajectory path1 = + // routine + // .trajectory("C_LEFT_PATH1") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("C_LEFT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path3 = + // routine + // .trajectory("C_LEFT_PATH3") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + // path1.cmd(), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + + // return routine; + // } + + // public static final LoggedAutoRoutine autoCLeftPush( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // Camera... cameras) { + + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); + // LoggedAutoTrajectory path1 = + // routine + // .trajectory("C_LEFT_PATH1") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("C_LEFT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path3 = + // routine + // .trajectory("C_LEFT_PATH3") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runEnd( + // () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), + // () -> drive.stop()) + // .withTimeout(0.5), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + // path1.cmd(), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + + // return routine; + // } + + // public static final LoggedAutoRoutine autoCRight( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // Camera... cameras) { + + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); + // LoggedAutoTrajectory path1 = + // routine + // .trajectory("C_RIGHT_PATH1") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("C_RIGHT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path3 = + // routine + // .trajectory("C_RIGHT_PATH3") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + // path1.cmd(), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + // return routine; + // } + + // public static final LoggedAutoRoutine autoCRightPush( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // Camera... cameras) { + + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); + // LoggedAutoTrajectory path1 = + // routine + // .trajectory("C_RIGHT_PATH1") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("C_RIGHT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path3 = + // routine + // .trajectory("C_RIGHT_PATH3") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + // Commands.runEnd( + // () -> drive.runVelocity(new ChassisSpeeds(0.0, 1.0, 0.0)), + // () -> drive.stop()) + // .withTimeout(0.5), + // path1.cmd(), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + // return routine; + // } + + // public static final LoggedAutoRoutine autoBRight( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // Camera... cameras) { + + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBRight"); + // LoggedAutoTrajectory path1 = + // routine + // .trajectory("B_RIGHT_PATH1") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("B_RIGHT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + // path1.cmd(), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); + + // return routine; + // } + + // public static final LoggedAutoRoutine autoDCenter( + // Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoDCenter"); + // LoggedAutoTrajectory path1 = + // routine + // .trajectory("D_CENTER_PATH") + // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + // path1.cmd(), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + // return routine; + // } } diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index 882b55e2..9602d750 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -28,9 +28,11 @@ public class ElevatorConstants { REEF_STATE_ELEVATOR_POSITION_MAP = Map.ofEntries( Map.entry(ReefState.STOW, ElevatorPositions.STOW), + Map.entry(ReefState.HIGH_STOW, ElevatorPositions.HIGH_STOW), Map.entry(ReefState.CORAL_INTAKE, ElevatorPositions.CORAL_INTAKE), Map.entry(ReefState.ALGAE_FLOOR_INTAKE, ElevatorPositions.ALGAE_INTAKE), Map.entry(ReefState.ALGAE_MID, ElevatorPositions.ALGAE_MID), + Map.entry(ReefState.HANDOFF, ElevatorPositions.HANDOFF), Map.entry(ReefState.ALGAE_INTAKE_TOP, ElevatorPositions.ALGAE_INTAKE_TOP), Map.entry(ReefState.ALGAE_INTAKE_BOTTOM, ElevatorPositions.ALGAE_INTAKE_BOT), Map.entry(ReefState.L1, ElevatorPositions.L1), @@ -262,7 +264,11 @@ public static enum ElevatorPositions { new PositionConstants( 1.3864590139769697 + Units.inchesToMeters(0.5), 1.3864590139769697 + Units.inchesToMeters(0.5), - Units.inchesToMeters(61))); + Units.inchesToMeters(61))), + + HIGH_STOW(new PositionConstants(0, 0, 0.5)), + HANDOFF(new PositionConstants(0, 0, 1)), + ; private final PositionConstants position; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index b89ca3ef..02014ddc 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -6,8 +6,8 @@ import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; import java.util.Set; -import lombok.Getter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; @@ -16,6 +16,7 @@ public class V3_EpsilonManipulator { private final ManipulatorIOInputsAutoLogged inputs; private ManipulatorArmState armState; + private ManipulatorRollerState rollerGoal; private boolean isClosedLoop; public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { @@ -24,6 +25,7 @@ public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { isClosedLoop = true; armState = ManipulatorArmState.VERTICAL_UP; + rollerGoal = ManipulatorRollerState.STOP; } public void periodic() { @@ -35,7 +37,7 @@ public void periodic() { } if (hasAlgae() - && Set.of(ManipulatorRollerStates.CORAL_INTAKE, ManipulatorRollerStates.STOP) + && Set.of(ManipulatorRollerState.CORAL_INTAKE, ManipulatorRollerState.STOP) .contains(rollerGoal)) { io.setRollerVoltage(holdVoltage()); } else { From 73e23999fe64b587cdf0a1368c7906ec27657337 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Mon, 1 Sep 2025 20:32:12 -0400 Subject: [PATCH 067/180] start simulation --- src/main/deploy/Superstructure.dot | 1 - src/main/java/frc/robot/Robot.java | 1 + .../shared/elevator/ElevatorConstants.java | 76 +++++++++++++++++++ .../v3_Epsilon/V3_EpsilonRobotContainer.java | 15 +--- .../superstructure/Superstructure.dot | 1 - .../V3_EpsilonSuperstructure.java | 28 ++++++- .../V3_EpsilonSuperstructureEdges.java | 17 ++--- .../V3_EpsilonSuperstructureStates.java | 4 +- .../intake/V3_EpsilonIntakeConstants.java | 17 ++--- .../intake/V3_EpsilonIntakeIOSim.java | 2 +- .../manipulator/V3_EpsilonManipulator.java | 25 +++--- .../V3_EpsilonManipulatorConstants.java | 2 +- 12 files changed, 140 insertions(+), 49 deletions(-) diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/Superstructure.dot index de5ea24c..9e5c4758 100644 --- a/src/main/deploy/Superstructure.dot +++ b/src/main/deploy/Superstructure.dot @@ -66,7 +66,6 @@ digraph Superstructure { L3 -> PROCESSOR [type=UNCONSTRAINED] L3 -> BARGE [type=UNCONSTRAINED] - L4 -> START [type=UNCONSTRAINED] L4 -> STOW_DOWN [type=UNCONSTRAINED] L4 -> GROUND_ACQUISITION [type=UNCONSTRAINED] L4 -> L1 [type=UNCONSTRAINED] diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 222c6408..2e0c5e82 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -123,6 +123,7 @@ public void robotInit() { case SIM: // Running a physics simulator, log to NT + setUseTiming(false); Logger.addDataReceiver(new NT4Publisher()); break; diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index 9602d750..db79a2c0 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -117,6 +117,82 @@ public class ElevatorConstants { break; } break; + + case V3_EPSILON: + case V3_EPSILON_SIM: + ELEVATOR_CAN_ID = 20; + ELEVATOR_GEAR_RATIO = 4.0; + DRUM_RADIUS = Units.inchesToMeters(2.256 / 2.0); + + ELEVATOR_SUPPLY_CURRENT_LIMIT = 40; + ELEVATOR_STATOR_CURRENT_LIMIT = 80; + + ELEVATOR_PARAMETERS = + new ElevatorParameters( + DCMotor.getKrakenX60Foc(2), 6.803886, 0.0, Units.inchesToMeters(62), 2); + + switch (Constants.getMode()) { + case REAL: + case REPLAY: + default: + GAINS = + new Gains( + new LoggedTunableNumber("Elevator/Gains/kP", 2.0), + new LoggedTunableNumber("Elevator/Gains/kD", 0.1), + new LoggedTunableNumber("Elevator/Gains/kS", 0.225), + new LoggedTunableNumber("Elevator/Gains/kG", 0.075), + new LoggedTunableNumber("Elevator/Gains/kV", 0.0), + new LoggedTunableNumber("Elevator/Gains/kA", 0.0)); + CONSTRAINTS = + new Constraints( + new LoggedTunableNumber("Elevator/Max Acceleration", 16.0), + new LoggedTunableNumber("Elevator/Cruising Velocity", 16.0), + new LoggedTunableNumber("Elevator/Goal Tolerance", 0.02)); + STOW_GAINS = + new Gains( + new LoggedTunableNumber("Elevator/Stow Gains/kP", 2.0), + new LoggedTunableNumber("Elevator/Stow Gains/kD", 0.1), + new LoggedTunableNumber("Elevator/Stow Gains/kS", 0.225), + new LoggedTunableNumber("Elevator/Stow Gains/kG", 0.075), + new LoggedTunableNumber("Elevator/Stow Gains/kV", 0.0), + new LoggedTunableNumber("Elevator/Stow Gains/kA", 0.0)); + STOW_CONSTRAINTS = + new Constraints( + new LoggedTunableNumber("Elevator/Stow Max Acceleration", 16.0), + new LoggedTunableNumber("Elevator/Stow Cruising Velocity", 16.0), + new LoggedTunableNumber("Elevator/Stow Goal Tolerance", 0.02)); + break; + case SIM: + GAINS = + new Gains( + new LoggedTunableNumber("Elevator/Gains/kP", 20.0), + new LoggedTunableNumber("Elevator/Gains/kD", 0.0), + new LoggedTunableNumber("Elevator/Gains/kS", 0.0), + new LoggedTunableNumber("Elevator/Gains/kG", 0.0), + new LoggedTunableNumber("Elevator/Gains/kV", 0.0), + new LoggedTunableNumber("Elevator/Gains/kA", 0.0)); + CONSTRAINTS = + new Constraints( + new LoggedTunableNumber("Elevator/Max Acceleration", 101.078594), + new LoggedTunableNumber("Elevator/Cruising Velocity", 11.329982), + new LoggedTunableNumber("Elevator/Goal Tolerance", 0.02)); + STOW_GAINS = + new Gains( + new LoggedTunableNumber("Elevator/Stow Gains/kP", 20.0), + new LoggedTunableNumber("Elevator/Stow Gains/kD", 0.0), + new LoggedTunableNumber("Elevator/Stow Gains/kS", 0.0), + new LoggedTunableNumber("Elevator/Stow Gains/kG", 0.0), + new LoggedTunableNumber("Elevator/Stow Gains/kV", 0.0), + new LoggedTunableNumber("Elevator/Stow Gains/kA", 0.0)); + STOW_CONSTRAINTS = + new Constraints( + new LoggedTunableNumber("Elevator/Stow Max Acceleration", 101.078594), + new LoggedTunableNumber("Elevator/Stow Cruising Velocity", 11.329982), + new LoggedTunableNumber("Elevator/Stow Goal Tolerance", 0.02)); + break; + } + break; + case V2_REDUNDANCY: case V2_REDUNDANCY_SIM: default: diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 67485c67..322c349e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -2,7 +2,6 @@ import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.Constants; import frc.robot.Constants.Mode; import frc.robot.RobotContainer; @@ -20,7 +19,6 @@ import frc.robot.subsystems.shared.elevator.ElevatorIOSim; import frc.robot.subsystems.shared.elevator.ElevatorIOTalonFX; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIO; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOSim; @@ -126,17 +124,6 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { - return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF), - Commands.waitSeconds(3), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), - Commands.waitSeconds(3), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), - Commands.waitSeconds(3), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L2), - Commands.waitSeconds(3), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L3_SCORE), - Commands.waitSeconds(3), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L1)); + return superstructure.allTransition(); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index 940605a4..53916bdd 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -78,7 +78,6 @@ digraph Superstructure { L3 -> PROCESSOR [type=UNCONSTRAINED] L3 -> BARGE [type=UNCONSTRAINED] - L4 -> START [type=UNCONSTRAINED] L4 -> STOW_DOWN [type=UNCONSTRAINED] L4 -> GROUND_ACQUISITION [type=UNCONSTRAINED] L4 -> L1 [type=UNCONSTRAINED] diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index bcc5f4cb..3e05e32d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -328,6 +328,10 @@ public boolean atGoal() { && manipulator.armAtGoal(targetState.getPose().getArmState()); } + public Command waitUntilAtGoal() { + return Commands.sequence(Commands.waitSeconds(.02), Commands.waitUntil(() -> atGoal())); + } + /** * Runs a temporary override action, returning to a previous goal after. * @@ -442,7 +446,7 @@ public Command runActionWithTimeout( DoubleSupplier timeout) { return Commands.sequence( runGoal(action), // Run the action - Commands.waitUntil(() -> atGoal()), + waitUntilAtGoal(), Commands.defer(() -> Commands.waitSeconds(timeout.getAsDouble()), Set.of())) .finallyDo(() -> setGoal(pose.get())); // Return to original pose } @@ -459,7 +463,7 @@ public Command runActionWithTimeout( V3_EpsilonSuperstructureStates pose, V3_EpsilonSuperstructureStates action, double timeout) { return Commands.sequence( runGoal(action), // Run the action - Commands.waitUntil(() -> atGoal()), + waitUntilAtGoal(), Commands.waitSeconds(timeout), runGoal(pose)) .finallyDo(() -> setGoal(pose)); // Return to original pose @@ -557,4 +561,24 @@ public Command setPosition() { public boolean elevatorAtGoal() { return elevator.atGoal(); } + + public Command allTransition() { + Command all = runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN); + for (var source : V3_EpsilonSuperstructureStates.values()) { + for (var sink : V3_EpsilonSuperstructureStates.values()) { + if (source == sink) continue; + var edge = graph.getEdge(source, sink); + if (edge != null) { + + if (source != V3_EpsilonSuperstructureStates.START + && sink != V3_EpsilonSuperstructureStates.START + && source != V3_EpsilonSuperstructureStates.OVERRIDE) { + all = all.andThen(runGoal(sink), waitUntilAtGoal()); + all = all.andThen(runGoal(source), waitUntilAtGoal()); + } + } + } + } + return all; + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index c3afe0b3..b21c17db 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -287,9 +287,9 @@ private static Command waitForPoseCommand( Command logCheck = Commands.runOnce( () -> { - boolean elevatorOk = elevator.atGoal(pose.getElevatorHeight()); - boolean intakeOk = intake.pivotAtGoal(pose.getIntakeState()); - boolean armOk = manipulator.armAtGoal(pose.getArmState()); + boolean elevatorOk = elevator.atGoal(); + boolean intakeOk = intake.pivotAtGoal(); + boolean armOk = manipulator.armAtGoal(); System.out.println( "Checking pose for: " + state.toString() @@ -302,13 +302,12 @@ private static Command waitForPoseCommand( }); Command wait = - Commands.waitUntil( - () -> - elevator.atGoal(pose.getElevatorHeight()) - && intake.pivotAtGoal(pose.getIntakeState()) - && manipulator.armAtGoal(pose.getArmState())); + Commands.sequence( + Commands.waitSeconds(0.02), + Commands.waitUntil( + () -> elevator.atGoal() && intake.pivotAtGoal() && manipulator.armAtGoal())); // Run the log once right before starting the wait - return Commands.sequence(logCheck, wait); + return Commands.sequence(wait, logCheck); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 85b7c0ef..d935f0b3 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -24,12 +24,12 @@ public enum V3_EpsilonSuperstructureStates { GROUND_ACQUISITION( "GROUND_ACQUISITION", new SubsystemPoses( - ReefState.STOW, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), + ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), SubsystemActions.empty()), GROUND_INTAKE( "GROUND_INTAKE", new SubsystemPoses( - ReefState.STOW, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), + ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.CORAL_INTAKE)), L1( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index ccdebb20..0e2bcb9f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -2,7 +2,6 @@ import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.system.plant.DCMotor; -import edu.wpi.first.math.util.Units; import lombok.Getter; import lombok.RequiredArgsConstructor; @@ -14,9 +13,9 @@ public class V3_EpsilonIntakeConstants { public static final IntakeCurrentLimits CURRENT_LIMITS = new IntakeCurrentLimits(40.0, 40.0, 40.0, 40.0); - public static final Gains PIVOT_GAINS = new Gains(100.0, 0.0, 0.5, 0.0, 0.0, 0.0); + public static final Gains PIVOT_GAINS = new Gains(1.0, 0.01, 0.0, 0.0, 0.0, 0.0); public static final Constraints PIVOT_CONSTRAINTS = - new Constraints(500.0, 500.0, Rotation2d.fromDegrees(0.01)); + new Constraints(500.0, 500.0, Rotation2d.fromDegrees(3.0)); public static final IntakeParems PIVOT_PARAMS = new IntakeParems( @@ -24,10 +23,10 @@ public class V3_EpsilonIntakeConstants { DCMotor.getKrakenX60Foc(1), 0.0042, Rotation2d.fromDegrees(0.0), - Rotation2d.fromDegrees(90.0)); + Rotation2d.fromDegrees(124.6)); public static final IntakeParems ROLLER_PARAMS = new IntakeParems( - 1, DCMotor.getKrakenX60Foc(1), 0, new Rotation2d(), Rotation2d.fromDegrees(90.0)); + 1, DCMotor.getKrakenX60Foc(1), 0, new Rotation2d(), Rotation2d.fromDegrees(0)); static { PIVOT_CAN_ID = 60; @@ -36,10 +35,10 @@ public class V3_EpsilonIntakeConstants { @RequiredArgsConstructor public enum IntakePivotState { - STOW(new Rotation2d()), - INTAKE_CORAL(new Rotation2d()), - HANDOFF(new Rotation2d(Units.degreesToRadians(90))), - L1(new Rotation2d()), + STOW(Rotation2d.fromDegrees(0)), + INTAKE_CORAL(Rotation2d.fromDegrees(123.6)), + HANDOFF(Rotation2d.fromDegrees(0)), + L1(Rotation2d.fromDegrees(-82 + 123.6)), INTAKE_ALGAE(new Rotation2d()); @Getter private final Rotation2d angle; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java index 87cd56c2..c5d27afd 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java @@ -27,7 +27,7 @@ public V3_EpsilonIntakeIOSim() { new SingleJointedArmSim( LinearSystemId.createSingleJointedArmSystem( V3_EpsilonIntakeConstants.PIVOT_PARAMS.MOTOR(), - V3_EpsilonIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO(), + V3_EpsilonIntakeConstants.PIVOT_PARAMS.MASS_KG(), V3_EpsilonIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO()), V3_EpsilonIntakeConstants.PIVOT_PARAMS.MOTOR(), V3_EpsilonIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO(), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 02014ddc..cf875fe6 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -4,10 +4,10 @@ import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; -import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; import java.util.Set; +import lombok.Getter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; @@ -15,8 +15,14 @@ public class V3_EpsilonManipulator { private final V3_EpsilonManipulatorIO io; private final ManipulatorIOInputsAutoLogged inputs; - private ManipulatorArmState armState; + @AutoLogOutput(key = "Manipulator/Arm Goal") + @Getter + private ManipulatorArmState armGoal; + + @AutoLogOutput(key = "Manipulator/Roller Goal") + @Getter private ManipulatorRollerState rollerGoal; + private boolean isClosedLoop; public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { @@ -24,7 +30,7 @@ public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { inputs = new ManipulatorIOInputsAutoLogged(); isClosedLoop = true; - armState = ManipulatorArmState.VERTICAL_UP; + armGoal = ManipulatorArmState.VERTICAL_UP; rollerGoal = ManipulatorRollerState.STOP; } @@ -33,7 +39,7 @@ public void periodic() { Logger.processInputs("Manipulator", inputs); if (isClosedLoop) { - io.setArmGoal(armState.getAngle()); + io.setArmGoal(armGoal.getAngle()); } if (hasAlgae() @@ -70,7 +76,7 @@ public Command setArmGoal(ManipulatorArmState goal) { return Commands.runOnce( () -> { isClosedLoop = true; - armState = goal; + armGoal = goal; }); } @@ -104,13 +110,14 @@ public void updateArmConstraints(double maxAcceleration, double maxVelocity) { @AutoLogOutput(key = "Manipulator/Arm At Goal") public boolean armAtGoal() { - return inputs.armPosition.getRadians() - armState.getAngle().getRadians() - <= V2_RedundancyManipulatorConstants.CONSTRAINTS.GOAL_TOLERANCE_RADIANS().get(); + return armAtGoal(armGoal); } public boolean armAtGoal(ManipulatorArmState state) { - return inputs.armPosition.getRadians() - state.getAngle().getRadians() - <= V2_RedundancyManipulatorConstants.CONSTRAINTS.GOAL_TOLERANCE_RADIANS().get(); + return Math.hypot( + inputs.armPosition.getCos() - state.getAngle().getCos(), + inputs.armPosition.getSin() - state.getAngle().getSin()) + <= V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); } public Command waitUntilArmAtGoal() { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 9382ee89..640e518e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -67,7 +67,7 @@ public class V3_EpsilonManipulatorConstants { new Constraints( new LoggedTunableNumber("Manipulator/Arm/MaxAcceleration", 20.0), new LoggedTunableNumber("Manipulator/Arm/CruisingVelocity", 50.0), - new LoggedTunableNumber("Manipulator/Arm/GoalTolerance", Units.degreesToRadians(1.5))); + new LoggedTunableNumber("Manipulator/Arm/GoalTolerance", Units.degreesToRadians(3))); ROLLER_CAN_ID = 30; ROLLER_CURRENT_THRESHOLD = 60.0; From 91c90aee4155cb10b8db398ab105f6a236a937e1 Mon Sep 17 00:00:00 2001 From: Luke Maxwell <24lbmaxwell@protonmail.com> Date: Thu, 4 Sep 2025 17:51:57 -0400 Subject: [PATCH 068/180] do not use timing in sim --- src/main/java/frc/robot/Robot.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 2e0c5e82..e4048d20 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -123,7 +123,7 @@ public void robotInit() { case SIM: // Running a physics simulator, log to NT - setUseTiming(false); + // setUseTiming(false); Logger.addDataReceiver(new NT4Publisher()); break; From 8edce608f9dc08ba079dbdab6cfb31b9c3896e0f Mon Sep 17 00:00:00 2001 From: Rishi Date: Thu, 4 Sep 2025 19:08:31 -0400 Subject: [PATCH 069/180] Made the emergencyEject and intakeAlgaeFloor commands --- src/main/java/frc/robot/Robot.java | 1 - .../frc/robot/commands/CompositeCommands.java | 24 ++++++++++++++++++- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 4 +++- .../V3_EpsilonSuperstructureStates.java | 9 +++++++ .../V3_EpsilonManipulatorConstants.java | 3 ++- 5 files changed, 37 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 2e0c5e82..222c6408 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -123,7 +123,6 @@ public void robotInit() { case SIM: // Running a physics simulator, log to NT - setUseTiming(false); Logger.addDataReceiver(new NT4Publisher()); break; diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 1faf5f98..4b1224c6 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -22,6 +22,11 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; import frc.robot.util.AllianceFlipUtil; import java.util.function.BooleanSupplier; import java.util.function.Supplier; @@ -649,5 +654,22 @@ public static final Command homingSequences( Commands.runOnce(() -> elevator.setPosition())); } - public static final class V3_EpsilonCompositeCommands {} + public static final class V3_EpsilonCompositeCommands { + public static final Command emergencyEject( + V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { + return Commands.sequence( + superstructure.override( + () -> { + manipulator.setArmGoal(ManipulatorArmState.EMERGENCY_EJECT_ANGLE); + manipulator.setRollerGoal(ManipulatorRollerState.L4_SCORE); + })); + } + + public static final Command intakeAlgaeFloor( + V3_EpsilonSuperstructure superstructure, V3_EpsilonManipulator manipulator) { + return superstructure + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .until(() -> manipulator.hasAlgae()); // add intake for algae after + } + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 322c349e..3252d736 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -6,6 +6,7 @@ import frc.robot.Constants.Mode; import frc.robot.RobotContainer; import frc.robot.RobotState; +import frc.robot.commands.CompositeCommands; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.drive.DriveConstants; import frc.robot.subsystems.shared.drive.GyroIO; @@ -124,6 +125,7 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { - return superstructure.allTransition(); + return CompositeCommands.V3_EpsilonCompositeCommands.emergencyEject( + manipulator, superstructure); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index d935f0b3..7e77b7ed 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -26,6 +26,15 @@ public enum V3_EpsilonSuperstructureStates { new SubsystemPoses( ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), SubsystemActions.empty()), + GROUND_INTAKE_ALGAE( + "GROUND_INTAKE_ALGAE", + new SubsystemPoses(ReefState.HIGH_STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), + GROUND_AQUISITION_ALGAE( + "GROUND_AQUISITION_ALGAE", + new SubsystemPoses(ReefState.HIGH_STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + SubsystemActions.empty()), + GROUND_INTAKE( "GROUND_INTAKE", new SubsystemPoses( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 640e518e..a7fd8096 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -148,7 +148,8 @@ public static enum ManipulatorArmState { TRANSITION(Rotation2d.fromDegrees(15.0)), // Placeholder value. Make sure to test VERTICAL_UP(Rotation2d.fromDegrees(0)), HANDOFF(Rotation2d.kPi), - SAFE_ANGLE(Rotation2d.fromDegrees(150)); + SAFE_ANGLE(Rotation2d.fromDegrees(150)), + EMERGENCY_EJECT_ANGLE(Rotation2d.fromDegrees(90)); private final Rotation2d angle; From f6d3b26a11451b65033295223bda031eb82b114a Mon Sep 17 00:00:00 2001 From: LordVanra Date: Thu, 4 Sep 2025 19:35:13 -0400 Subject: [PATCH 070/180] Co-authored-by: Sriaditya Vaddadi Co-authored-by: Noah Proctor Co-authored-by: Joshi, Atharv --- .../superstructure/V3_EpsilonSuperstructure.java | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 3e05e32d..6182a709 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -573,8 +573,16 @@ public Command allTransition() { if (source != V3_EpsilonSuperstructureStates.START && sink != V3_EpsilonSuperstructureStates.START && source != V3_EpsilonSuperstructureStates.OVERRIDE) { - all = all.andThen(runGoal(sink), waitUntilAtGoal()); - all = all.andThen(runGoal(source), waitUntilAtGoal()); + all = + all.andThen( + runGoal(sink), + runOnce(() -> System.out.println("Initial Pose:" + sink)), + Commands.waitSeconds(2)); + all = + all.andThen( + runGoal(source), + runOnce(() -> System.out.println("Final Pose:" + source)), + Commands.waitSeconds(2)); } } } From eb97ee600748dbd5d0351f54ed69ab5f139d3693 Mon Sep 17 00:00:00 2001 From: Rishi Date: Thu, 4 Sep 2025 19:44:02 -0400 Subject: [PATCH 071/180] Fixed the ovreride --- .../superstructure/V3_EpsilonSuperstructure.java | 2 ++ .../superstructure/V3_EpsilonSuperstructurePose.java | 4 ++-- .../manipulator/V3_EpsilonManipulator.java | 9 +++------ 3 files changed, 7 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 3e05e32d..2b60f697 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -101,6 +101,8 @@ public V3_EpsilonSuperstructure( */ @Override public void periodic() { + if (currentState != null && !currentState.equals(V3_EpsilonSuperstructureStates.OVERRIDE)) + currentState.getAction().get(intake, manipulator); if (RobotMode.disabled()) { nextState = null; } else if (edgeCommand == null || !edgeCommand.getCommand().isScheduled()) { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java index b9175e8a..51afa248 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java @@ -63,7 +63,7 @@ public Command setIntakeState(V3_EpsilonIntake intake) { * @return A Command that sets the arm state and waits until it reaches the goal. */ public Command setManipulatorState(V3_EpsilonManipulator manipulator) { - return Commands.parallel(manipulator.setArmGoal(armState)); + return Commands.parallel(Commands.runOnce(() -> manipulator.setArmGoal(armState))); } /** @@ -80,7 +80,7 @@ public Command asCommand( ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { return Commands.parallel( Commands.runOnce(() -> elevator.setPosition(() -> elevatorHeight)), - manipulator.setArmGoal(armState), + Commands.runOnce(() -> manipulator.setArmGoal(armState)), Commands.runOnce(() -> intake.setPivotGoal(intakeState))); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index cf875fe6..04ee38ef 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -72,12 +72,9 @@ public Command runArm(double volts) { () -> io.setArmVoltage(0)); } - public Command setArmGoal(ManipulatorArmState goal) { - return Commands.runOnce( - () -> { - isClosedLoop = true; - armGoal = goal; - }); + public void setArmGoal(ManipulatorArmState goal) { + isClosedLoop = true; + armGoal = goal; } public void updateArmGains( From 9c957d521eddb214761186ea07fc1034ff28ea81 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 6 Sep 2025 17:29:47 -0400 Subject: [PATCH 072/180] fix manipulator safety check --- .../V3_EpsilonSuperstructureEdges.java | 160 +++++++++--------- .../V3_EpsilonSuperstructurePose.java | 4 +- .../manipulator/V3_EpsilonManipulator.java | 16 +- 3 files changed, 95 insertions(+), 85 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index b21c17db..6ea3f405 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -6,7 +6,6 @@ import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import java.io.FileReader; import java.io.Reader; import java.util.ArrayList; @@ -54,8 +53,7 @@ public static void loadEdgesFromDot( // Create edges with placeholder commands (null) importer.setEdgeWithAttributesFactory( attributes -> { - V3_EpsilonSuperstructureEdges.GamePieceEdge type = - V3_EpsilonSuperstructureEdges.GamePieceEdge.UNCONSTRAINED; + V3_EpsilonSuperstructureEdges.GamePieceEdge type = V3_EpsilonSuperstructureEdges.GamePieceEdge.UNCONSTRAINED; if (attributes.containsKey("type")) { String value = attributes.get("type").getValue(); @@ -96,11 +94,11 @@ public static void loadEdgesFromDot( V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(e); Map attrs = edgeAttrs.get(e); - V3_EpsilonSuperstructureEdges.GamePieceEdge type = - V3_EpsilonSuperstructureEdges.GamePieceEdge.UNCONSTRAINED; + V3_EpsilonSuperstructureEdges.GamePieceEdge type = V3_EpsilonSuperstructureEdges.GamePieceEdge.UNCONSTRAINED; // START --- ADDED CODE - // Check for the 'requires' attribute to determine if motion should be sequential + // Check for the 'requires' attribute to determine if motion should be + // sequential boolean requiresElevator = false; boolean requiresArm = false; if (attrs != null && attrs.containsKey("requires")) { @@ -117,9 +115,8 @@ public static void loadEdgesFromDot( if (attrs != null && attrs.get("type") != null) { try { - type = - V3_EpsilonSuperstructureEdges.GamePieceEdge.valueOf( - attrs.get("type").getValue().toUpperCase()); + type = V3_EpsilonSuperstructureEdges.GamePieceEdge.valueOf( + attrs.get("type").getValue().toUpperCase()); } catch (IllegalArgumentException ex) { System.err.println("Unknown edge type: " + attrs.get("type").getValue()); } @@ -143,30 +140,41 @@ public static void loadEdgesFromDot( @Builder(toBuilder = true) @Getter public static class EdgeCommand extends DefaultEdge { - @Setter private Command command; - @Builder.Default private GamePieceEdge gamePieceEdge = GamePieceEdge.UNCONSTRAINED; + @Setter + private Command command; + @Builder.Default + private GamePieceEdge gamePieceEdge = GamePieceEdge.UNCONSTRAINED; // START --- ADDED CODE - @Setter @Builder.Default private boolean requiresElevator = false; - @Setter @Builder.Default private boolean requiresArm = false; + @Setter + @Builder.Default + private boolean requiresElevator = false; + @Setter + @Builder.Default + private boolean requiresArm = false; // END --- ADDED CODE } /** - * Gets the command to execute for a given edge in the superstructure state graph. This command - * typically involves coordinating the elevator, funnel, intake, and manipulator subsystems to + * Gets the command to execute for a given edge in the superstructure state + * graph. This command + * typically involves coordinating the elevator, funnel, intake, and manipulator + * subsystems to * move from one state to another. * - * @param from The starting state of the superstructure. - * @param to The target state of the superstructure. - * @param elevator The elevator subsystem. - * @param intake The intake subsystem. - * @param manipulator The manipulator subsystem. - * @param requiresElevator Flag indicating the elevator must finish its move before other - * mechanisms start. - * @param requiresArm Flag indicating the arm/intake must finish its move before the elevator - * starts. - * @return A {@link Command} that, when executed, transitions the superstructure from the 'from' - * state to the 'to' state. + * @param from The starting state of the superstructure. + * @param to The target state of the superstructure. + * @param elevator The elevator subsystem. + * @param intake The intake subsystem. + * @param manipulator The manipulator subsystem. + * @param requiresElevator Flag indicating the elevator must finish its move + * before other + * mechanisms start. + * @param requiresArm Flag indicating the arm/intake must finish its move + * before the elevator + * starts. + * @return A {@link Command} that, when executed, transitions the superstructure + * from the 'from' + * state to the 'to' state. */ private static Command getEdgeCommand( V3_EpsilonSuperstructureStates from, @@ -182,26 +190,20 @@ private static Command getEdgeCommand( if (requiresElevator) { // Elevator moves and waits, THEN other mechanisms move. - moveCommand = - Commands.sequence( - pose.setElevatorHeight(elevator), - Commands.waitUntil(elevator::atGoal), - pose.asCommand( - elevator, intake, manipulator) // CORRECTED: Only move the other subsystems - ); + moveCommand = Commands.sequence( + pose.setElevatorHeight(elevator), + elevator.waitUntilAtGoal(), + pose.asCommand( + elevator, intake, manipulator) // CORRECTED: Only move the other subsystems + ); } else if (requiresArm) { // Arm moves to a safe position and waits, THEN other mechanisms move. - moveCommand = - Commands.sequence( - pose.setManipulatorState(manipulator), - Commands.waitUntil( - () -> - manipulator.getArmAngle().getDegrees() - < ManipulatorArmState.SAFE_ANGLE.getAngle().getDegrees()), - pose.asCommand( - elevator, intake, manipulator) // CORRECTED: Only move the other subsystems - ); + moveCommand = Commands.sequence( + pose.setManipulatorState(manipulator), + Commands.waitUntil(manipulator::isSafePosition), + pose.asCommand(elevator, intake, manipulator) // CORRECTED: Only move the other subsystems + ); } else { // Default case: All mechanisms move in parallel. moveCommand = pose.asCommand(elevator, intake, manipulator); @@ -209,20 +211,24 @@ private static Command getEdgeCommand( // THE CRITICAL FIX: // No matter how we start the move, we append a final wait condition. - // This ensures the command doesn't end until the robot is physically at the target pose. + // This ensures the command doesn't end until the robot is physically at the + // target pose. return Commands.sequence(moveCommand, waitForPoseCommand(to, elevator, intake, manipulator)); } /** - * Adds edges to the superstructure state graph based on the provided list of edges and algae + * Adds edges to the superstructure state graph based on the provided list of + * edges and algae * condition. * - * @param graph The graph to which edges are added. - * @param edges A list of {@link Edge} objects representing the transitions between states. - * @param type The {@link GamePieceEdge} type associated with these edges. - * @param elevator The elevator subsystem. + * @param graph The graph to which edges are added. + * @param edges A list of {@link Edge} objects representing the + * transitions between states. + * @param type The {@link GamePieceEdge} type associated with these + * edges. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. + * @param intake The intake subsystem. */ private static void addEdges( Graph graph, @@ -248,12 +254,13 @@ private static void addEdges( } /** - * Adds all predefined edges to the superstructure state graph, categorized by algae condition. + * Adds all predefined edges to the superstructure state graph, categorized by + * algae condition. * - * @param graph The graph to which edges are added. - * @param elevator The elevator subsystem. + * @param graph The graph to which edges are added. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. + * @param intake The intake subsystem. */ public static void addEdges( Graph graph, @@ -268,7 +275,8 @@ public static void addEdges( intake, manipulator); - // NOTE: The two lines below are likely redundant. The loadEdgesFromDot method already + // NOTE: The two lines below are likely redundant. The loadEdgesFromDot method + // already // adds all edges to the graph. You may want to remove these calls. addEdges(graph, UNCONSTRAINED, GamePieceEdge.UNCONSTRAINED, elevator, manipulator, intake); addEdges(graph, NO_ALGAE_EDGES, GamePieceEdge.NO_ALGAE, elevator, manipulator, intake); @@ -284,28 +292,26 @@ private static Command waitForPoseCommand( V3_EpsilonSuperstructurePose pose = state.getPose(); // Add this command to log the check's status - Command logCheck = - Commands.runOnce( - () -> { - boolean elevatorOk = elevator.atGoal(); - boolean intakeOk = intake.pivotAtGoal(); - boolean armOk = manipulator.armAtGoal(); - System.out.println( - "Checking pose for: " - + state.toString() - + " -> Elevator OK: " - + elevatorOk - + ", Intake OK: " - + intakeOk - + ", Arm OK: " - + armOk); - }); - - Command wait = - Commands.sequence( - Commands.waitSeconds(0.02), - Commands.waitUntil( - () -> elevator.atGoal() && intake.pivotAtGoal() && manipulator.armAtGoal())); + Command logCheck = Commands.runOnce( + () -> { + boolean elevatorOk = elevator.atGoal(); + boolean intakeOk = intake.pivotAtGoal(); + boolean armOk = manipulator.armAtGoal(); + System.out.println( + "Checking pose for: " + + state.toString() + + " -> Elevator OK: " + + elevatorOk + + ", Intake OK: " + + intakeOk + + ", Arm OK: " + + armOk); + }); + + Command wait = Commands.sequence( + Commands.waitSeconds(0.02), + Commands.waitUntil( + () -> elevator.atGoal() && intake.pivotAtGoal() && manipulator.armAtGoal())); // Run the log once right before starting the wait return Commands.sequence(wait, logCheck); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java index b9175e8a..51afa248 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java @@ -63,7 +63,7 @@ public Command setIntakeState(V3_EpsilonIntake intake) { * @return A Command that sets the arm state and waits until it reaches the goal. */ public Command setManipulatorState(V3_EpsilonManipulator manipulator) { - return Commands.parallel(manipulator.setArmGoal(armState)); + return Commands.parallel(Commands.runOnce(() -> manipulator.setArmGoal(armState))); } /** @@ -80,7 +80,7 @@ public Command asCommand( ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { return Commands.parallel( Commands.runOnce(() -> elevator.setPosition(() -> elevatorHeight)), - manipulator.setArmGoal(armState), + Commands.runOnce(() -> manipulator.setArmGoal(armState)), Commands.runOnce(() -> intake.setPivotGoal(intakeState))); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index cf875fe6..1e0c9311 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -72,12 +72,9 @@ public Command runArm(double volts) { () -> io.setArmVoltage(0)); } - public Command setArmGoal(ManipulatorArmState goal) { - return Commands.runOnce( - () -> { - isClosedLoop = true; - armGoal = goal; - }); + public void setArmGoal(ManipulatorArmState goal) { + isClosedLoop = true; + armGoal = goal; } public void updateArmGains( @@ -169,4 +166,11 @@ public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState public Rotation2d getArmAngle() { return inputs.armPosition; } + + @AutoLogOutput(key = "Manipulator/Safe Position") + public boolean isSafePosition() { + double cosThresh = Math.cos(Math.PI - ManipulatorArmState.SAFE_ANGLE.getAngle().getRadians()); + // unsafe if -cos(theta) >= cosThresh + return (-inputs.armPosition.getCos()) < cosThresh; + } } From 38826d5de8fcb60ea983e289154d4cf5d1b633f2 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 6 Sep 2025 17:51:37 -0400 Subject: [PATCH 073/180] use positive for all manipulator arm states (useful when we later add ability to mirror) --- .../V3_EpsilonSuperstructureEdges.java | 147 +++++++++--------- .../V3_EpsilonManipulatorConstants.java | 10 +- 2 files changed, 75 insertions(+), 82 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index 6ea3f405..f4b14650 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -53,7 +53,8 @@ public static void loadEdgesFromDot( // Create edges with placeholder commands (null) importer.setEdgeWithAttributesFactory( attributes -> { - V3_EpsilonSuperstructureEdges.GamePieceEdge type = V3_EpsilonSuperstructureEdges.GamePieceEdge.UNCONSTRAINED; + V3_EpsilonSuperstructureEdges.GamePieceEdge type = + V3_EpsilonSuperstructureEdges.GamePieceEdge.UNCONSTRAINED; if (attributes.containsKey("type")) { String value = attributes.get("type").getValue(); @@ -94,7 +95,8 @@ public static void loadEdgesFromDot( V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(e); Map attrs = edgeAttrs.get(e); - V3_EpsilonSuperstructureEdges.GamePieceEdge type = V3_EpsilonSuperstructureEdges.GamePieceEdge.UNCONSTRAINED; + V3_EpsilonSuperstructureEdges.GamePieceEdge type = + V3_EpsilonSuperstructureEdges.GamePieceEdge.UNCONSTRAINED; // START --- ADDED CODE // Check for the 'requires' attribute to determine if motion should be @@ -115,8 +117,9 @@ public static void loadEdgesFromDot( if (attrs != null && attrs.get("type") != null) { try { - type = V3_EpsilonSuperstructureEdges.GamePieceEdge.valueOf( - attrs.get("type").getValue().toUpperCase()); + type = + V3_EpsilonSuperstructureEdges.GamePieceEdge.valueOf( + attrs.get("type").getValue().toUpperCase()); } catch (IllegalArgumentException ex) { System.err.println("Unknown edge type: " + attrs.get("type").getValue()); } @@ -140,41 +143,30 @@ public static void loadEdgesFromDot( @Builder(toBuilder = true) @Getter public static class EdgeCommand extends DefaultEdge { - @Setter - private Command command; - @Builder.Default - private GamePieceEdge gamePieceEdge = GamePieceEdge.UNCONSTRAINED; + @Setter private Command command; + @Builder.Default private GamePieceEdge gamePieceEdge = GamePieceEdge.UNCONSTRAINED; // START --- ADDED CODE - @Setter - @Builder.Default - private boolean requiresElevator = false; - @Setter - @Builder.Default - private boolean requiresArm = false; + @Setter @Builder.Default private boolean requiresElevator = false; + @Setter @Builder.Default private boolean requiresArm = false; // END --- ADDED CODE } /** - * Gets the command to execute for a given edge in the superstructure state - * graph. This command - * typically involves coordinating the elevator, funnel, intake, and manipulator - * subsystems to + * Gets the command to execute for a given edge in the superstructure state graph. This command + * typically involves coordinating the elevator, funnel, intake, and manipulator subsystems to * move from one state to another. * - * @param from The starting state of the superstructure. - * @param to The target state of the superstructure. - * @param elevator The elevator subsystem. - * @param intake The intake subsystem. - * @param manipulator The manipulator subsystem. - * @param requiresElevator Flag indicating the elevator must finish its move - * before other - * mechanisms start. - * @param requiresArm Flag indicating the arm/intake must finish its move - * before the elevator - * starts. - * @return A {@link Command} that, when executed, transitions the superstructure - * from the 'from' - * state to the 'to' state. + * @param from The starting state of the superstructure. + * @param to The target state of the superstructure. + * @param elevator The elevator subsystem. + * @param intake The intake subsystem. + * @param manipulator The manipulator subsystem. + * @param requiresElevator Flag indicating the elevator must finish its move before other + * mechanisms start. + * @param requiresArm Flag indicating the arm/intake must finish its move before the elevator + * starts. + * @return A {@link Command} that, when executed, transitions the superstructure from the 'from' + * state to the 'to' state. */ private static Command getEdgeCommand( V3_EpsilonSuperstructureStates from, @@ -190,20 +182,23 @@ private static Command getEdgeCommand( if (requiresElevator) { // Elevator moves and waits, THEN other mechanisms move. - moveCommand = Commands.sequence( - pose.setElevatorHeight(elevator), - elevator.waitUntilAtGoal(), - pose.asCommand( - elevator, intake, manipulator) // CORRECTED: Only move the other subsystems - ); + moveCommand = + Commands.sequence( + pose.setElevatorHeight(elevator), + elevator.waitUntilAtGoal(), + pose.asCommand( + elevator, intake, manipulator) // CORRECTED: Only move the other subsystems + ); } else if (requiresArm) { // Arm moves to a safe position and waits, THEN other mechanisms move. - moveCommand = Commands.sequence( - pose.setManipulatorState(manipulator), - Commands.waitUntil(manipulator::isSafePosition), - pose.asCommand(elevator, intake, manipulator) // CORRECTED: Only move the other subsystems - ); + moveCommand = + Commands.sequence( + pose.setManipulatorState(manipulator), + Commands.waitUntil(manipulator::isSafePosition), + pose.asCommand( + elevator, intake, manipulator) // CORRECTED: Only move the other subsystems + ); } else { // Default case: All mechanisms move in parallel. moveCommand = pose.asCommand(elevator, intake, manipulator); @@ -217,18 +212,15 @@ private static Command getEdgeCommand( } /** - * Adds edges to the superstructure state graph based on the provided list of - * edges and algae + * Adds edges to the superstructure state graph based on the provided list of edges and algae * condition. * - * @param graph The graph to which edges are added. - * @param edges A list of {@link Edge} objects representing the - * transitions between states. - * @param type The {@link GamePieceEdge} type associated with these - * edges. - * @param elevator The elevator subsystem. + * @param graph The graph to which edges are added. + * @param edges A list of {@link Edge} objects representing the transitions between states. + * @param type The {@link GamePieceEdge} type associated with these edges. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. + * @param intake The intake subsystem. */ private static void addEdges( Graph graph, @@ -254,13 +246,12 @@ private static void addEdges( } /** - * Adds all predefined edges to the superstructure state graph, categorized by - * algae condition. + * Adds all predefined edges to the superstructure state graph, categorized by algae condition. * - * @param graph The graph to which edges are added. - * @param elevator The elevator subsystem. + * @param graph The graph to which edges are added. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. + * @param intake The intake subsystem. */ public static void addEdges( Graph graph, @@ -292,26 +283,28 @@ private static Command waitForPoseCommand( V3_EpsilonSuperstructurePose pose = state.getPose(); // Add this command to log the check's status - Command logCheck = Commands.runOnce( - () -> { - boolean elevatorOk = elevator.atGoal(); - boolean intakeOk = intake.pivotAtGoal(); - boolean armOk = manipulator.armAtGoal(); - System.out.println( - "Checking pose for: " - + state.toString() - + " -> Elevator OK: " - + elevatorOk - + ", Intake OK: " - + intakeOk - + ", Arm OK: " - + armOk); - }); - - Command wait = Commands.sequence( - Commands.waitSeconds(0.02), - Commands.waitUntil( - () -> elevator.atGoal() && intake.pivotAtGoal() && manipulator.armAtGoal())); + Command logCheck = + Commands.runOnce( + () -> { + boolean elevatorOk = elevator.atGoal(); + boolean intakeOk = intake.pivotAtGoal(); + boolean armOk = manipulator.armAtGoal(); + System.out.println( + "Checking pose for: " + + state.toString() + + " -> Elevator OK: " + + elevatorOk + + ", Intake OK: " + + intakeOk + + ", Arm OK: " + + armOk); + }); + + Command wait = + Commands.sequence( + Commands.waitSeconds(0.02), + Commands.waitUntil( + () -> elevator.atGoal() && intake.pivotAtGoal() && manipulator.armAtGoal())); // Run the log once right before starting the wait return Commands.sequence(wait, logCheck); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 640e518e..6f1ff1e1 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -140,11 +140,11 @@ public static record ArmParameters( public static enum ManipulatorArmState { PRE_SCORE(Rotation2d.fromDegrees(50.0)), SCORE(Rotation2d.fromDegrees(55.0)), // Placeholder value. Make sure to test - PROCESSOR(Rotation2d.fromDegrees(-61.279296875 + 20)), - REEF_INTAKE(Rotation2d.fromDegrees(-61.279296875 + 15)), - INTAKE_OUT_LINE(Rotation2d.fromDegrees(-61)), - FLOOR_INTAKE(Rotation2d.fromDegrees(-68.5 - 5)), - STOW_LINE(Rotation2d.fromDegrees(-75)), + PROCESSOR(Rotation2d.fromDegrees(41.279296875)), + REEF_INTAKE(Rotation2d.fromDegrees(46.279296875)), + INTAKE_OUT_LINE(Rotation2d.fromDegrees(61)), + FLOOR_INTAKE(Rotation2d.fromDegrees(73.5)), + STOW_LINE(Rotation2d.fromDegrees(75)), TRANSITION(Rotation2d.fromDegrees(15.0)), // Placeholder value. Make sure to test VERTICAL_UP(Rotation2d.fromDegrees(0)), HANDOFF(Rotation2d.kPi), From 4e9772256ec9b87f4a18d2292b9d85e7e97b181b Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 6 Sep 2025 18:28:24 -0400 Subject: [PATCH 074/180] arm side switching and add configs to talonFX implementation of manipulator --- .../manipulator/V3_EpsilonManipulator.java | 17 ++++--- .../V3_EpsilonManipulatorConstants.java | 14 +++--- .../V3_EpsilonManipulatorIOTalonFX.java | 45 ++++++++++--------- 3 files changed, 46 insertions(+), 30 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 1e0c9311..7de3775e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -6,8 +6,10 @@ import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.Side; import java.util.Set; import lombok.Getter; +import lombok.Setter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; @@ -19,6 +21,11 @@ public class V3_EpsilonManipulator { @Getter private ManipulatorArmState armGoal; + @Setter + @Getter + @AutoLogOutput(key = "Manipulator/Arm Side") + private Side armSide; + @AutoLogOutput(key = "Manipulator/Roller Goal") @Getter private ManipulatorRollerState rollerGoal; @@ -31,6 +38,7 @@ public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { isClosedLoop = true; armGoal = ManipulatorArmState.VERTICAL_UP; + armSide = Side.POSITIVE; rollerGoal = ManipulatorRollerState.STOP; } @@ -39,7 +47,7 @@ public void periodic() { Logger.processInputs("Manipulator", inputs); if (isClosedLoop) { - io.setArmGoal(armGoal.getAngle()); + io.setArmGoal(armGoal.getAngle(armSide)); } if (hasAlgae() @@ -111,9 +119,7 @@ public boolean armAtGoal() { } public boolean armAtGoal(ManipulatorArmState state) { - return Math.hypot( - inputs.armPosition.getCos() - state.getAngle().getCos(), - inputs.armPosition.getSin() - state.getAngle().getSin()) + return Math.abs(inputs.armPosition.minus(state.getAngle(armSide)).getRadians()) <= V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); } @@ -169,7 +175,8 @@ public Rotation2d getArmAngle() { @AutoLogOutput(key = "Manipulator/Safe Position") public boolean isSafePosition() { - double cosThresh = Math.cos(Math.PI - ManipulatorArmState.SAFE_ANGLE.getAngle().getRadians()); + double cosThresh = + Math.cos(Math.PI - ManipulatorArmState.SAFE_ANGLE.getAngle(armSide).getRadians()); // unsafe if -cos(theta) >= cosThresh return (-inputs.armPosition.getCos()) < cosThresh; } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 6f1ff1e1..7bbb66bf 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -34,8 +34,6 @@ public class V3_EpsilonManipulatorConstants { ARM_PARAMETERS = new ArmParameters( DCMotor.getKrakenX60Foc(1), - Rotation2d.fromDegrees(-77.0), - Rotation2d.fromDegrees(75.0), 1, 90.0, 0.5); @@ -130,8 +128,6 @@ public static final record Voltages( public static record ArmParameters( DCMotor MOTOR_CONFIG, - Rotation2d MIN_ANGLE, - Rotation2d MAX_ANGLE, int NUM_MOTORS, double GEAR_RATIO, double LENGTH_METERS) {} @@ -152,7 +148,10 @@ public static enum ManipulatorArmState { private final Rotation2d angle; - public Rotation2d getAngle() { + public Rotation2d getAngle(Side side) { + if (side == Side.NEGATIVE) { + return angle.unaryMinus(); + } return angle; } } @@ -178,4 +177,9 @@ public double getVoltage() { return voltage; } } + + public enum Side { + POSITIVE, + NEGATIVE + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java index 25b3db39..dd98667a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java @@ -1,9 +1,12 @@ package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; import static edu.wpi.first.units.Units.RadiansPerSecond; +import static edu.wpi.first.units.Units.RotationsPerSecond; +import static edu.wpi.first.units.Units.RotationsPerSecondPerSecond; import static frc.robot.util.PhoenixUtil.*; import com.ctre.phoenix6.StatusSignal; +import com.ctre.phoenix6.configs.MotionMagicConfigs; import com.ctre.phoenix6.configs.Slot0Configs; import com.ctre.phoenix6.configs.Slot1Configs; import com.ctre.phoenix6.configs.Slot2Configs; @@ -15,7 +18,9 @@ import com.ctre.phoenix6.signals.NeutralModeValue; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.util.Units; +import edu.wpi.first.units.AccelerationUnit; import edu.wpi.first.units.measure.Angle; +import edu.wpi.first.units.measure.AngularAcceleration; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Current; import edu.wpi.first.units.measure.Temperature; @@ -56,18 +61,21 @@ public V3_EpsilonManipulatorIOTalonFX() { armConfig = new TalonFXConfiguration(); armConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; - armConfig.CurrentLimits.SupplyCurrentLimit = - V3_EpsilonManipulatorConstants.CURRENT_LIMITS.MANIPULATOR_SUPPLY_CURRENT_LIMIT(); + armConfig.CurrentLimits.SupplyCurrentLimit = V3_EpsilonManipulatorConstants.CURRENT_LIMITS + .MANIPULATOR_SUPPLY_CURRENT_LIMIT(); armConfig.CurrentLimits.SupplyCurrentLimitEnable = true; - armConfig.Feedback.SensorToMechanismRatio = - V3_EpsilonManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO(); - armConfig.Slot0 = - Slot0Configs.from(V3_EpsilonManipulatorConstants.EMPTY_GAINS.toTalonFXSlotConfigs()); - armConfig.Slot1 = - Slot1Configs.from(V3_EpsilonManipulatorConstants.CORAL_GAINS.toTalonFXSlotConfigs()); - armConfig.Slot2 = - Slot2Configs.from(V3_EpsilonManipulatorConstants.ALGAE_GAINS.toTalonFXSlotConfigs()); + armConfig.Feedback.SensorToMechanismRatio = V3_EpsilonManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO(); + armConfig.Slot0 = Slot0Configs.from(V3_EpsilonManipulatorConstants.EMPTY_GAINS.toTalonFXSlotConfigs()); + armConfig.Slot1 = Slot1Configs.from(V3_EpsilonManipulatorConstants.CORAL_GAINS.toTalonFXSlotConfigs()); + armConfig.Slot2 = Slot2Configs.from(V3_EpsilonManipulatorConstants.ALGAE_GAINS.toTalonFXSlotConfigs()); armConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; + armConfig.ClosedLoopGeneral.ContinuousWrap = true; + armConfig.MotionMagic = new MotionMagicConfigs() + .withMotionMagicAcceleration(AngularAcceleration.ofRelativeUnits( + V3_EpsilonManipulatorConstants.CONSTRAINTS.maxAccelerationRotationsPerSecondSquared().get(), + RotationsPerSecondPerSecond)) + .withMotionMagicCruiseVelocity(AngularVelocity.ofRelativeUnits( + V3_EpsilonManipulatorConstants.CONSTRAINTS.cruisingVelocityRotationsPerSecond().get(), RotationsPerSecond)); tryUntilOk(5, () -> armTalonFX.getConfigurator().apply(armConfig, 0.25)); @@ -83,8 +91,8 @@ public V3_EpsilonManipulatorIOTalonFX() { rollerConfig = new TalonFXConfiguration(); rollerConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; - rollerConfig.CurrentLimits.SupplyCurrentLimit = - V3_EpsilonManipulatorConstants.CURRENT_LIMITS.ROLLER_SUPPLY_CURRENT_LIMIT(); + rollerConfig.CurrentLimits.SupplyCurrentLimit = V3_EpsilonManipulatorConstants.CURRENT_LIMITS + .ROLLER_SUPPLY_CURRENT_LIMIT(); rollerConfig.CurrentLimits.SupplyCurrentLimitEnable = true; tryUntilOk(5, () -> rollerTalonFX.getConfigurator().apply(rollerConfig, 0.25)); @@ -123,26 +131,23 @@ public V3_EpsilonManipulatorIOTalonFX() { public void updateInputs(ManipulatorIOInputs inputs) { inputs.armPosition = new Rotation2d(armPositionRotations.getValue()); - inputs.armVelocityRadiansPerSecond = - armVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); + inputs.armVelocityRadiansPerSecond = armVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); inputs.armAppliedVolts = armAppliedVoltage.getValueAsDouble(); inputs.armSupplyCurrentAmps = armSupplyCurrentAmps.getValueAsDouble(); inputs.armTorqueCurrentAmps = armTorqueCurrentAmps.getValueAsDouble(); inputs.armTemperatureCelsius = armTemperatureCelsius.getValueAsDouble(); inputs.rollerPosition = new Rotation2d(rollerPositionRotations.getValue()); - inputs.rollerVelocityRadiansPerSecond = - Units.rotationsToRadians(rollerVelocityRotationsPerSecond.getValueAsDouble()); + inputs.rollerVelocityRadiansPerSecond = Units + .rotationsToRadians(rollerVelocityRotationsPerSecond.getValueAsDouble()); inputs.rollerAppliedVolts = rollerAppliedVoltage.getValueAsDouble(); inputs.rollerSupplyCurrentAmps = rollerSupplyCurrentAmps.getValueAsDouble(); inputs.rollerTorqueCurrentAmps = rollerTorqueCurrentAmps.getValueAsDouble(); inputs.rollerTemperatureCelsius = rollerTemperatureCelsius.getValueAsDouble(); inputs.armPositionGoal = new Rotation2d(armMotionMagicRequest.getPositionMeasure()); - inputs.armPositionSetpoint = - Rotation2d.fromRotations(armPositionSetpointRotations.getValueAsDouble()); - inputs.armPositionError = - Rotation2d.fromRotations(armPositionErrorRotations.getValueAsDouble()); + inputs.armPositionSetpoint = Rotation2d.fromRotations(armPositionSetpointRotations.getValueAsDouble()); + inputs.armPositionError = Rotation2d.fromRotations(armPositionErrorRotations.getValueAsDouble()); } @Override From aea0eb95cff384c63ba8de10fe4d81299ed309e1 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 6 Sep 2025 21:57:17 -0400 Subject: [PATCH 075/180] some small fixes --- .../V3_EpsilonSuperstructure.java | 20 +++++-- .../manipulator/V3_EpsilonManipulator.java | 16 +++++- .../V3_EpsilonManipulatorConstants.java | 12 +---- .../V3_EpsilonManipulatorIOTalonFX.java | 54 ++++++++++++------- 4 files changed, 68 insertions(+), 34 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 6182a709..3a3d3940 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -1,5 +1,6 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; @@ -11,6 +12,7 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.GamePieceEdge; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; import frc.robot.util.NTPrefixes; import java.util.HashMap; import java.util.LinkedList; @@ -101,6 +103,11 @@ public V3_EpsilonSuperstructure( */ @Override public void periodic() { + + manipulator.setClearsElevator( + elevator.getPositionMeters() + > V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() * 1.1); + if (RobotMode.disabled()) { nextState = null; } else if (edgeCommand == null || !edgeCommand.getCommand().isScheduled()) { @@ -144,6 +151,13 @@ public void periodic() { elevator.periodic(); intake.periodic(); manipulator.periodic(); + + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "Clears Base", + 0.1 + >= (manipulator.getArmAngle().rotateBy(new Rotation2d(-Math.PI / 2)).getSin() + * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() + - elevator.getPositionMeters())); } /** @@ -323,9 +337,9 @@ public Command runGoal(Supplier goal) { @AutoLogOutput(key = NTPrefixes.SUPERSTRUCTURE + "At Goal") public boolean atGoal() { return currentState == targetState - && elevator.atGoal(targetState.getPose().getElevatorHeight()) - && intake.pivotAtGoal(targetState.getPose().getIntakeState()) - && manipulator.armAtGoal(targetState.getPose().getArmState()); + && elevator.atGoal() + && intake.pivotAtGoal() + && manipulator.armAtGoal(); } public Command waitUntilAtGoal() { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 7de3775e..967f743b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -32,6 +32,8 @@ public class V3_EpsilonManipulator { private boolean isClosedLoop; + @Setter @Getter private boolean clearsElevator; + public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { this.io = io; inputs = new ManipulatorIOInputsAutoLogged(); @@ -40,6 +42,8 @@ public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { armGoal = ManipulatorArmState.VERTICAL_UP; armSide = Side.POSITIVE; rollerGoal = ManipulatorRollerState.STOP; + + clearsElevator = false; } public void periodic() { @@ -47,7 +51,17 @@ public void periodic() { Logger.processInputs("Manipulator", inputs); if (isClosedLoop) { - io.setArmGoal(armGoal.getAngle(armSide)); + Rotation2d goal = armGoal.getAngle(armSide); + + if (!isSafePosition() || clearsElevator) { + if (armSide == Side.POSITIVE) { + goal = Rotation2d.fromRotations(goal.getRotations() - 1.0); + } else { + goal = Rotation2d.fromRotations(goal.getRotations() + 1.0); + } + } + + io.setArmGoal(goal); } if (hasAlgae() diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 7bbb66bf..c84bcff5 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -31,12 +31,7 @@ public class V3_EpsilonManipulatorConstants { public static final double CORAL_CAN_RANGE_THRESHOLD = 0.5; static { - ARM_PARAMETERS = - new ArmParameters( - DCMotor.getKrakenX60Foc(1), - 1, - 90.0, - 0.5); + ARM_PARAMETERS = new ArmParameters(DCMotor.getKrakenX60Foc(1), 1, 90.0, .618); EMPTY_GAINS = new Gains( new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 50), @@ -127,10 +122,7 @@ public static final record Voltages( LoggedTunableNumber L1_VOLTS) {} public static record ArmParameters( - DCMotor MOTOR_CONFIG, - int NUM_MOTORS, - double GEAR_RATIO, - double LENGTH_METERS) {} + DCMotor MOTOR_CONFIG, int NUM_MOTORS, double GEAR_RATIO, double LENGTH_METERS) {} @RequiredArgsConstructor public static enum ManipulatorArmState { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java index dd98667a..6038f587 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java @@ -18,7 +18,6 @@ import com.ctre.phoenix6.signals.NeutralModeValue; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.util.Units; -import edu.wpi.first.units.AccelerationUnit; import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.AngularAcceleration; import edu.wpi.first.units.measure.AngularVelocity; @@ -61,21 +60,33 @@ public V3_EpsilonManipulatorIOTalonFX() { armConfig = new TalonFXConfiguration(); armConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; - armConfig.CurrentLimits.SupplyCurrentLimit = V3_EpsilonManipulatorConstants.CURRENT_LIMITS - .MANIPULATOR_SUPPLY_CURRENT_LIMIT(); + armConfig.CurrentLimits.SupplyCurrentLimit = + V3_EpsilonManipulatorConstants.CURRENT_LIMITS.MANIPULATOR_SUPPLY_CURRENT_LIMIT(); armConfig.CurrentLimits.SupplyCurrentLimitEnable = true; - armConfig.Feedback.SensorToMechanismRatio = V3_EpsilonManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO(); - armConfig.Slot0 = Slot0Configs.from(V3_EpsilonManipulatorConstants.EMPTY_GAINS.toTalonFXSlotConfigs()); - armConfig.Slot1 = Slot1Configs.from(V3_EpsilonManipulatorConstants.CORAL_GAINS.toTalonFXSlotConfigs()); - armConfig.Slot2 = Slot2Configs.from(V3_EpsilonManipulatorConstants.ALGAE_GAINS.toTalonFXSlotConfigs()); + armConfig.Feedback.SensorToMechanismRatio = + V3_EpsilonManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO(); + armConfig.Slot0 = + Slot0Configs.from(V3_EpsilonManipulatorConstants.EMPTY_GAINS.toTalonFXSlotConfigs()); + armConfig.Slot1 = + Slot1Configs.from(V3_EpsilonManipulatorConstants.CORAL_GAINS.toTalonFXSlotConfigs()); + armConfig.Slot2 = + Slot2Configs.from(V3_EpsilonManipulatorConstants.ALGAE_GAINS.toTalonFXSlotConfigs()); armConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; armConfig.ClosedLoopGeneral.ContinuousWrap = true; - armConfig.MotionMagic = new MotionMagicConfigs() - .withMotionMagicAcceleration(AngularAcceleration.ofRelativeUnits( - V3_EpsilonManipulatorConstants.CONSTRAINTS.maxAccelerationRotationsPerSecondSquared().get(), - RotationsPerSecondPerSecond)) - .withMotionMagicCruiseVelocity(AngularVelocity.ofRelativeUnits( - V3_EpsilonManipulatorConstants.CONSTRAINTS.cruisingVelocityRotationsPerSecond().get(), RotationsPerSecond)); + armConfig.MotionMagic = + new MotionMagicConfigs() + .withMotionMagicAcceleration( + AngularAcceleration.ofRelativeUnits( + V3_EpsilonManipulatorConstants.CONSTRAINTS + .maxAccelerationRotationsPerSecondSquared() + .get(), + RotationsPerSecondPerSecond)) + .withMotionMagicCruiseVelocity( + AngularVelocity.ofRelativeUnits( + V3_EpsilonManipulatorConstants.CONSTRAINTS + .cruisingVelocityRotationsPerSecond() + .get(), + RotationsPerSecond)); tryUntilOk(5, () -> armTalonFX.getConfigurator().apply(armConfig, 0.25)); @@ -91,8 +102,8 @@ public V3_EpsilonManipulatorIOTalonFX() { rollerConfig = new TalonFXConfiguration(); rollerConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; - rollerConfig.CurrentLimits.SupplyCurrentLimit = V3_EpsilonManipulatorConstants.CURRENT_LIMITS - .ROLLER_SUPPLY_CURRENT_LIMIT(); + rollerConfig.CurrentLimits.SupplyCurrentLimit = + V3_EpsilonManipulatorConstants.CURRENT_LIMITS.ROLLER_SUPPLY_CURRENT_LIMIT(); rollerConfig.CurrentLimits.SupplyCurrentLimitEnable = true; tryUntilOk(5, () -> rollerTalonFX.getConfigurator().apply(rollerConfig, 0.25)); @@ -131,23 +142,26 @@ public V3_EpsilonManipulatorIOTalonFX() { public void updateInputs(ManipulatorIOInputs inputs) { inputs.armPosition = new Rotation2d(armPositionRotations.getValue()); - inputs.armVelocityRadiansPerSecond = armVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); + inputs.armVelocityRadiansPerSecond = + armVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); inputs.armAppliedVolts = armAppliedVoltage.getValueAsDouble(); inputs.armSupplyCurrentAmps = armSupplyCurrentAmps.getValueAsDouble(); inputs.armTorqueCurrentAmps = armTorqueCurrentAmps.getValueAsDouble(); inputs.armTemperatureCelsius = armTemperatureCelsius.getValueAsDouble(); inputs.rollerPosition = new Rotation2d(rollerPositionRotations.getValue()); - inputs.rollerVelocityRadiansPerSecond = Units - .rotationsToRadians(rollerVelocityRotationsPerSecond.getValueAsDouble()); + inputs.rollerVelocityRadiansPerSecond = + Units.rotationsToRadians(rollerVelocityRotationsPerSecond.getValueAsDouble()); inputs.rollerAppliedVolts = rollerAppliedVoltage.getValueAsDouble(); inputs.rollerSupplyCurrentAmps = rollerSupplyCurrentAmps.getValueAsDouble(); inputs.rollerTorqueCurrentAmps = rollerTorqueCurrentAmps.getValueAsDouble(); inputs.rollerTemperatureCelsius = rollerTemperatureCelsius.getValueAsDouble(); inputs.armPositionGoal = new Rotation2d(armMotionMagicRequest.getPositionMeasure()); - inputs.armPositionSetpoint = Rotation2d.fromRotations(armPositionSetpointRotations.getValueAsDouble()); - inputs.armPositionError = Rotation2d.fromRotations(armPositionErrorRotations.getValueAsDouble()); + inputs.armPositionSetpoint = + Rotation2d.fromRotations(armPositionSetpointRotations.getValueAsDouble()); + inputs.armPositionError = + Rotation2d.fromRotations(armPositionErrorRotations.getValueAsDouble()); } @Override From 63268850aa08317bb80c84c11d9796c8e8600774 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 6 Sep 2025 23:44:12 -0400 Subject: [PATCH 076/180] clear arm in most states when intake is in --- .../V3_EpsilonSuperstructure.java | 2 +- .../V3_EpsilonSuperstructureStates.java | 36 ++++++++++++------- .../intake/V3_EpsilonIntakeConstants.java | 3 +- 3 files changed, 26 insertions(+), 15 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 3a3d3940..8a90ba78 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -154,7 +154,7 @@ public void periodic() { Logger.recordOutput( NTPrefixes.SUPERSTRUCTURE + "Clears Base", - 0.1 + 0.075 >= (manipulator.getArmAngle().rotateBy(new Rotation2d(-Math.PI / 2)).getSin() * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() - elevator.getPositionMeters())); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index d935f0b3..763bef33 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -13,7 +13,11 @@ public enum V3_EpsilonSuperstructureStates { START("START", new SubsystemPoses(), SubsystemActions.empty()), - STOW_DOWN("STOW_DOWN", new SubsystemPoses(), SubsystemActions.empty()), + STOW_DOWN( + "STOW_DOWN", + new SubsystemPoses( + ReefState.STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.ARM_CLEAR), + SubsystemActions.empty()), STOW_UP( "STOW_UP", new SubsystemPoses( @@ -43,20 +47,20 @@ public enum V3_EpsilonSuperstructureStates { L2( "L2", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), + new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.ARM_CLEAR), SubsystemActions.empty()), L2_SCORE( "L2_SCORE", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.SCORE, IntakePivotState.STOW), + new SubsystemPoses(ReefState.L2, ManipulatorArmState.SCORE, IntakePivotState.ARM_CLEAR), new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), L3( "L3", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), + new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.ARM_CLEAR), SubsystemActions.empty()), L3_SCORE( "L3_SCORE", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.SCORE, IntakePivotState.STOW), + new SubsystemPoses(ReefState.L3, ManipulatorArmState.SCORE, IntakePivotState.ARM_CLEAR), new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), L4( @@ -74,42 +78,48 @@ public enum V3_EpsilonSuperstructureStates { SubsystemActions.empty()), INTERMEDIATE_WAIT_FOR_ELEVATOR( "INTERMEDIATE_WAIT_FOR_ELEVATOR", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), + new SubsystemPoses( + ReefState.HANDOFF, ManipulatorArmState.VERTICAL_UP, IntakePivotState.ARM_CLEAR), SubsystemActions.empty()), INTERMEDIATE_WAIT_FOR_ARM( "INTERMEDIATE_WAIT_FOR_ARM", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.SAFE_ANGLE, IntakePivotState.STOW), + new SubsystemPoses( + ReefState.HANDOFF, ManipulatorArmState.SAFE_ANGLE, IntakePivotState.ARM_CLEAR), SubsystemActions.empty()), L2_ALGAE( "L2_ALGAE", new SubsystemPoses( - ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + ReefState.ALGAE_INTAKE_BOTTOM, + ManipulatorArmState.REEF_INTAKE, + IntakePivotState.ARM_CLEAR), SubsystemActions.empty()), L2_ALGAE_INTAKE( "L2_ALGAE_INTAKE", new SubsystemPoses( - ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + ReefState.ALGAE_INTAKE_BOTTOM, + ManipulatorArmState.REEF_INTAKE, + IntakePivotState.ARM_CLEAR), new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), L3_ALGAE( "L3_ALGAE", new SubsystemPoses( - ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.ARM_CLEAR), SubsystemActions.empty()), L3_ALGAE_INTAKE( "L3_ALGAE_INTAKE", new SubsystemPoses( - ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.ARM_CLEAR), new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), PROCESSOR( "PROCESSOR", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.ARM_CLEAR), SubsystemActions.empty()), PROCESSOR_SCORE( "PROCESSOR_SCORE", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.ARM_CLEAR), new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), BARGE( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index 0e2bcb9f..eddcbd8a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -39,7 +39,8 @@ public enum IntakePivotState { INTAKE_CORAL(Rotation2d.fromDegrees(123.6)), HANDOFF(Rotation2d.fromDegrees(0)), L1(Rotation2d.fromDegrees(-82 + 123.6)), - INTAKE_ALGAE(new Rotation2d()); + INTAKE_ALGAE(new Rotation2d()), + ARM_CLEAR(Rotation2d.fromDegrees(15.0)); @Getter private final Rotation2d angle; } From 2b1caa954d0645ca54befa1f09a951468b3af6fa Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sun, 7 Sep 2025 13:10:07 -0400 Subject: [PATCH 077/180] reduce tolerance and correct arm length (with coral) --- .../V3_EpsilonSuperstructure.java | 24 +++++++++++++------ .../intake/V3_EpsilonIntakeConstants.java | 4 ++-- .../V3_EpsilonManipulatorConstants.java | 2 +- 3 files changed, 20 insertions(+), 10 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 8a90ba78..471fd42e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -152,12 +152,20 @@ public void periodic() { intake.periodic(); manipulator.periodic(); + double armHeight = + -manipulator.getArmAngle().rotateBy(new Rotation2d(-Math.PI / 2)).getSin() + * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() + + elevator.getPositionMeters(); + Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Arm Height", armHeight); + Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Clears Base", 0.075 < armHeight); Logger.recordOutput( - NTPrefixes.SUPERSTRUCTURE + "Clears Base", - 0.075 - >= (manipulator.getArmAngle().rotateBy(new Rotation2d(-Math.PI / 2)).getSin() - * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() - - elevator.getPositionMeters())); + NTPrefixes.SUPERSTRUCTURE + "Clears Intake", + intake.getPivotAngle().getDegrees() > 15 + || armHeight > 0.37 + || Math.abs( + manipulator.getArmAngle().rotateBy(new Rotation2d(-Math.PI / 2)).getCos() + * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS()) + > 0.35); } /** @@ -591,12 +599,14 @@ public Command allTransition() { all.andThen( runGoal(sink), runOnce(() -> System.out.println("Initial Pose:" + sink)), - Commands.waitSeconds(2)); + Commands.waitUntil(this::atGoal), + Commands.waitSeconds(.05)); all = all.andThen( runGoal(source), runOnce(() -> System.out.println("Final Pose:" + source)), - Commands.waitSeconds(2)); + Commands.waitUntil(this::atGoal), + Commands.waitSeconds(.05)); } } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index eddcbd8a..1d50cb21 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -15,7 +15,7 @@ public class V3_EpsilonIntakeConstants { public static final Gains PIVOT_GAINS = new Gains(1.0, 0.01, 0.0, 0.0, 0.0, 0.0); public static final Constraints PIVOT_CONSTRAINTS = - new Constraints(500.0, 500.0, Rotation2d.fromDegrees(3.0)); + new Constraints(500.0, 500.0, Rotation2d.fromDegrees(1.5)); public static final IntakeParems PIVOT_PARAMS = new IntakeParems( @@ -40,7 +40,7 @@ public enum IntakePivotState { HANDOFF(Rotation2d.fromDegrees(0)), L1(Rotation2d.fromDegrees(-82 + 123.6)), INTAKE_ALGAE(new Rotation2d()), - ARM_CLEAR(Rotation2d.fromDegrees(15.0)); + ARM_CLEAR(Rotation2d.fromDegrees(17.0)); @Getter private final Rotation2d angle; } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index c84bcff5..c6c92916 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -31,7 +31,7 @@ public class V3_EpsilonManipulatorConstants { public static final double CORAL_CAN_RANGE_THRESHOLD = 0.5; static { - ARM_PARAMETERS = new ArmParameters(DCMotor.getKrakenX60Foc(1), 1, 90.0, .618); + ARM_PARAMETERS = new ArmParameters(DCMotor.getKrakenX60Foc(1), 1, 90.0, .695); EMPTY_GAINS = new Gains( new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 50), From d1a8c789a98999533b0587d3854d7aae484ee359 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sun, 7 Sep 2025 14:17:26 -0400 Subject: [PATCH 078/180] fixed a few transitions --- src/main/deploy/Superstructure.dot | 28 +++++++++---------- .../intake/V3_EpsilonIntakeConstants.java | 2 +- 2 files changed, 15 insertions(+), 15 deletions(-) diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/Superstructure.dot index 9e5c4758..0fcdf83e 100644 --- a/src/main/deploy/Superstructure.dot +++ b/src/main/deploy/Superstructure.dot @@ -13,31 +13,31 @@ digraph Superstructure { STOW_DOWN -> PROCESSOR [type=UNCONSTRAINED] STOW_DOWN -> BARGE [type=UNCONSTRAINED] - GROUND_ACQUISITION -> STOW_DOWN [type=UNCONSTRAINED] + GROUND_ACQUISITION -> STOW_DOWN [type=UNCONSTRAINED, requires=ARM] GROUND_ACQUISITION -> GROUND_INTAKE [type=UNCONSTRAINED] GROUND_ACQUISITION -> L1 [type=UNCONSTRAINED] - GROUND_ACQUISITION -> L2 [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L2 [type=UNCONSTRAINED, requires=ARM] GROUND_ACQUISITION -> L3 [type=UNCONSTRAINED] GROUND_ACQUISITION -> L4 [type=UNCONSTRAINED] GROUND_ACQUISITION -> HANDOFF [type=UNCONSTRAINED] - GROUND_ACQUISITION -> STOW_UP [type=UNCONSTRAINED] - GROUND_ACQUISITION -> L2_ALGAE [type=UNCONSTRAINED] + GROUND_ACQUISITION -> STOW_UP [type=UNCONSTRAINED, requires=ARM] + GROUND_ACQUISITION -> L2_ALGAE [type=UNCONSTRAINED, requires=ARM] GROUND_ACQUISITION -> L3_ALGAE [type=UNCONSTRAINED] - GROUND_ACQUISITION -> PROCESSOR [type=UNCONSTRAINED] + GROUND_ACQUISITION -> PROCESSOR [type=UNCONSTRAINED, requires=ARM] GROUND_ACQUISITION -> BARGE [type=UNCONSTRAINED] GROUND_INTAKE -> GROUND_ACQUISITION [type=UNCONSTRAINED] L1 -> GROUND_ACQUISITION [type=UNCONSTRAINED] L1 -> L2 [type=UNCONSTRAINED, requires=ARM] - L1 -> L3 [type=UNCONSTRAINED] + L1 -> L3 [type=UNCONSTRAINED, requires=ARM] L1 -> L4 [type=UNCONSTRAINED] L1 -> L1_SCORE [type=UNCONSTRAINED] L1 -> HANDOFF [type=UNCONSTRAINED] L1 -> STOW_UP [type=UNCONSTRAINED, requires=ARM] - L1 -> L2_ALGAE [type=UNCONSTRAINED] - L1 -> L3_ALGAE [type=UNCONSTRAINED] - L1 -> PROCESSOR [type=UNCONSTRAINED] + L1 -> L2_ALGAE [type=UNCONSTRAINED, requires=ARM] + L1 -> L3_ALGAE [type=UNCONSTRAINED, requires=ARM] + L1 -> PROCESSOR [type=UNCONSTRAINED, requires=ARM] L1 -> BARGE [type=UNCONSTRAINED] L2 -> STOW_DOWN [type=UNCONSTRAINED] @@ -113,7 +113,7 @@ digraph Superstructure { L4_SCORE -> L2 [type=UNCONSTRAINED] L4_SCORE -> L3 [type=UNCONSTRAINED] L4_SCORE -> L4 [type=UNCONSTRAINED] - L4_SCORE -> HANDOFF [type=UNCONSTRAINED] + L4_SCORE -> HANDOFF [type=UNCONSTRAINED, requires=ARM] L4_SCORE -> STOW_UP [type=UNCONSTRAINED] L4_SCORE -> L2_ALGAE [type=UNCONSTRAINED] L4_SCORE -> L3_ALGAE [type=UNCONSTRAINED] @@ -124,11 +124,11 @@ digraph Superstructure { HANDOFF -> GROUND_ACQUISITION [type=UNCONSTRAINED] HANDOFF -> L1 [type=UNCONSTRAINED] HANDOFF -> L2 [type=UNCONSTRAINED, requires=ARM] - HANDOFF -> L3 [type=UNCONSTRAINED] + HANDOFF -> L3 [type=UNCONSTRAINED, requires=ARM] HANDOFF -> L4 [type=UNCONSTRAINED] HANDOFF -> STOW_UP [type=UNCONSTRAINED, requires=ARM] - HANDOFF -> L2_ALGAE [type=UNCONSTRAINED] - HANDOFF -> L3_ALGAE [type=UNCONSTRAINED] + HANDOFF -> L2_ALGAE [type=UNCONSTRAINED, requires=ARM] + HANDOFF -> L3_ALGAE [type=UNCONSTRAINED, requires=ARM] HANDOFF -> PROCESSOR [type=UNCONSTRAINED, requires=ARM] HANDOFF -> BARGE [type=UNCONSTRAINED] @@ -150,7 +150,7 @@ digraph Superstructure { L2_ALGAE -> L2 [type=UNCONSTRAINED] L2_ALGAE -> L3 [type=UNCONSTRAINED] L2_ALGAE -> L4 [type=UNCONSTRAINED] - L2_ALGAE -> HANDOFF [type=NO_ALGAE] + L2_ALGAE -> HANDOFF [type=NO_ALGAE, requires=ARM] L2_ALGAE -> STOW_UP [type=UNCONSTRAINED] L2_ALGAE -> L2_ALGAE_INTAKE [type=UNCONSTRAINED] L2_ALGAE -> L3_ALGAE [type=NO_ALGAE] diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index 1d50cb21..7ea959cd 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -40,7 +40,7 @@ public enum IntakePivotState { HANDOFF(Rotation2d.fromDegrees(0)), L1(Rotation2d.fromDegrees(-82 + 123.6)), INTAKE_ALGAE(new Rotation2d()), - ARM_CLEAR(Rotation2d.fromDegrees(17.0)); + ARM_CLEAR(Rotation2d.fromDegrees(25.0)); @Getter private final Rotation2d angle; } From 4c3da7012453ddbb6e134bae0f955533337b8c06 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sun, 7 Sep 2025 17:12:55 -0400 Subject: [PATCH 079/180] fixed most collisions! --- src/main/deploy/Superstructure.dot | 24 +++---- .../shared/elevator/ElevatorConstants.java | 9 +++ .../V3_EpsilonSuperstructureEdges.java | 69 +++++++++++++++++++ .../V3_EpsilonSuperstructureStates.java | 46 ++++++------- .../intake/V3_EpsilonIntakeConstants.java | 4 +- 5 files changed, 112 insertions(+), 40 deletions(-) diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/Superstructure.dot index 0fcdf83e..3ea062c6 100644 --- a/src/main/deploy/Superstructure.dot +++ b/src/main/deploy/Superstructure.dot @@ -5,24 +5,24 @@ digraph Superstructure { STOW_DOWN -> L1 [type=UNCONSTRAINED] STOW_DOWN -> L2 [type=UNCONSTRAINED] STOW_DOWN -> L3 [type=UNCONSTRAINED] - STOW_DOWN -> L4 [type=UNCONSTRAINED] + STOW_DOWN -> L4 [type=UNCONSTRAINED, requires=ELEVATOR] STOW_DOWN -> HANDOFF [type=UNCONSTRAINED, requires=ELEVATOR] - STOW_DOWN -> STOW_UP [type=UNCONSTRAINED] + STOW_DOWN -> STOW_UP [type=UNCONSTRAINED, requires=ELEVATOR] STOW_DOWN -> L2_ALGAE [type=UNCONSTRAINED] STOW_DOWN -> L3_ALGAE [type=UNCONSTRAINED] STOW_DOWN -> PROCESSOR [type=UNCONSTRAINED] - STOW_DOWN -> BARGE [type=UNCONSTRAINED] + STOW_DOWN -> BARGE [type=UNCONSTRAINED, requires=ELEVATOR] GROUND_ACQUISITION -> STOW_DOWN [type=UNCONSTRAINED, requires=ARM] GROUND_ACQUISITION -> GROUND_INTAKE [type=UNCONSTRAINED] GROUND_ACQUISITION -> L1 [type=UNCONSTRAINED] GROUND_ACQUISITION -> L2 [type=UNCONSTRAINED, requires=ARM] - GROUND_ACQUISITION -> L3 [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L3 [type=UNCONSTRAINED, requires=ARM] GROUND_ACQUISITION -> L4 [type=UNCONSTRAINED] GROUND_ACQUISITION -> HANDOFF [type=UNCONSTRAINED] GROUND_ACQUISITION -> STOW_UP [type=UNCONSTRAINED, requires=ARM] GROUND_ACQUISITION -> L2_ALGAE [type=UNCONSTRAINED, requires=ARM] - GROUND_ACQUISITION -> L3_ALGAE [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L3_ALGAE [type=UNCONSTRAINED, requires=ARM] GROUND_ACQUISITION -> PROCESSOR [type=UNCONSTRAINED, requires=ARM] GROUND_ACQUISITION -> BARGE [type=UNCONSTRAINED] @@ -57,7 +57,7 @@ digraph Superstructure { L3 -> GROUND_ACQUISITION [type=UNCONSTRAINED] L3 -> L1 [type=UNCONSTRAINED] L3 -> L2 [type=UNCONSTRAINED] - L3 -> L4 [type=UNCONSTRAINED] + L3 -> L4 [type=UNCONSTRAINED, requires=ELEVATOR] L3 -> L3_SCORE [type=UNCONSTRAINED] L3 -> HANDOFF [type=UNCONSTRAINED] L3 -> STOW_UP [type=UNCONSTRAINED] @@ -77,7 +77,7 @@ digraph Superstructure { L4 -> L2_ALGAE [type=UNCONSTRAINED] L4 -> L3_ALGAE [type=UNCONSTRAINED] L4 -> PROCESSOR [type=UNCONSTRAINED] - L4 -> BARGE [type=UNCONSTRAINED] + L4 -> BARGE [type=UNCONSTRAINED, requires=ELEVATOR] L1_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] @@ -132,7 +132,7 @@ digraph Superstructure { HANDOFF -> PROCESSOR [type=UNCONSTRAINED, requires=ARM] HANDOFF -> BARGE [type=UNCONSTRAINED] - STOW_UP -> STOW_DOWN [type=UNCONSTRAINED, requires=ELEVATOR] + STOW_UP -> STOW_DOWN [type=UNCONSTRAINED] STOW_UP -> GROUND_ACQUISITION [type=UNCONSTRAINED, requires=ELEVATOR] STOW_UP -> L1 [type=UNCONSTRAINED, requires=ELEVATOR] STOW_UP -> L2 [type=UNCONSTRAINED] @@ -181,13 +181,13 @@ digraph Superstructure { PROCESSOR -> L1 [type=NO_ALGAE] PROCESSOR -> L2 [type=UNCONSTRAINED] PROCESSOR -> L3 [type=UNCONSTRAINED] - PROCESSOR -> L4 [type=UNCONSTRAINED] - PROCESSOR -> HANDOFF [type=NO_ALGAE] - PROCESSOR -> STOW_UP [type=UNCONSTRAINED] + PROCESSOR -> L4 [type=UNCONSTRAINED, requires=ELEVATOR] + PROCESSOR -> HANDOFF [type=NO_ALGAE, requires=ELEVATOR] + PROCESSOR -> STOW_UP [type=UNCONSTRAINED, requires=ELEVATOR] PROCESSOR -> L2_ALGAE [type=UNCONSTRAINED] PROCESSOR -> L3_ALGAE [type=UNCONSTRAINED] PROCESSOR -> PROCESSOR_SCORE [type=UNCONSTRAINED] - PROCESSOR -> BARGE [type=UNCONSTRAINED] + PROCESSOR -> BARGE [type=UNCONSTRAINED, requires=ELEVATOR] PROCESSOR_SCORE -> PROCESSOR [type=UNCONSTRAINED] diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index db79a2c0..55174dfa 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -360,5 +360,14 @@ public double getPosition() { return position.V1(); } } + + public static ElevatorPositions getPosition(ReefState state) { + for (ElevatorPositions pos : values()) { + if (REEF_STATE_ELEVATOR_POSITION_MAP.get(state) == pos) { + return pos; + } + } + return null; + } } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index f4b14650..3f4c4f5f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -1,11 +1,16 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj.Filesystem; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; +import frc.robot.subsystems.shared.elevator.ElevatorConstants; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakePivotState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.Side; import java.io.FileReader; import java.io.Reader; import java.util.ArrayList; @@ -204,6 +209,16 @@ private static Command getEdgeCommand( moveCommand = pose.asCommand(elevator, intake, manipulator); } + // move intake out of the way if it will collide + if (willCollide(from, to)) { + System.out.println("Collision predicted from " + from + " to " + to + ", moving intake out"); + moveCommand = + Commands.sequence( + Commands.runOnce(() -> intake.setPivotGoal(IntakePivotState.ARM_CLEAR)), + intake.waitUntilPivotAtGoal(), + moveCommand); + } + // THE CRITICAL FIX: // No matter how we start the move, we append a final wait condition. // This ensures the command doesn't end until the robot is physically at the @@ -211,6 +226,60 @@ private static Command getEdgeCommand( return Commands.sequence(moveCommand, waitForPoseCommand(to, elevator, intake, manipulator)); } + private static boolean willCollide( + V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { + + final int samples = 20; // number of interpolation steps + + for (int i = 0; i <= samples; i++) { + double t = i / (double) samples; + + // Interpolate elevator height + double elevHeight = + ElevatorConstants.ElevatorPositions.getPosition(from.getPose().getElevatorHeight()) + .getPosition() + * (1 - t) + + ElevatorConstants.ElevatorPositions.getPosition(to.getPose().getElevatorHeight()) + .getPosition() + * t; + + // Interpolate arm angle + Rotation2d armAngle = + from.getPose() + .getArmState() + .getAngle(Side.POSITIVE) + .interpolate(to.getPose().getArmState().getAngle(Side.POSITIVE), t); + + // Interpolate intake angle + Rotation2d intakeAngle = + from.getPose() + .getIntakeState() + .getAngle() + .interpolate(to.getPose().getIntakeState().getAngle(), t); + + // Arm height + double armHeight = + -armAngle.rotateBy(new Rotation2d(-Math.PI / 2)).getSin() + * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() + + elevHeight; + + // Arm horizontal extension + double horiz = + Math.abs( + armAngle.rotateBy(new Rotation2d(-Math.PI / 2)).getCos() + * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS()); + + // Check safety + boolean clearsIntake = intakeAngle.getDegrees() > 15 || armHeight > 0.37 || horiz > 0.35; + + if (!clearsIntake) { + return true; // Collision predicted + } + } + + return false; // Safe through transition + } + /** * Adds edges to the superstructure state graph based on the provided list of edges and algae * condition. diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 763bef33..4a19ab59 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -15,13 +15,12 @@ public enum V3_EpsilonSuperstructureStates { START("START", new SubsystemPoses(), SubsystemActions.empty()), STOW_DOWN( "STOW_DOWN", - new SubsystemPoses( - ReefState.STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.ARM_CLEAR), + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), SubsystemActions.empty()), STOW_UP( "STOW_UP", new SubsystemPoses( - ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), + ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.HANDOFF), SubsystemActions.empty()), OVERRIDE("OVERRIDE", new SubsystemPoses(), SubsystemActions.empty()), @@ -47,89 +46,84 @@ public enum V3_EpsilonSuperstructureStates { L2( "L2", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.ARM_CLEAR), + new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), SubsystemActions.empty()), L2_SCORE( "L2_SCORE", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.SCORE, IntakePivotState.ARM_CLEAR), + new SubsystemPoses(ReefState.L2, ManipulatorArmState.SCORE, IntakePivotState.STOW), new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), L3( "L3", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.ARM_CLEAR), + new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), SubsystemActions.empty()), L3_SCORE( "L3_SCORE", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.SCORE, IntakePivotState.ARM_CLEAR), + new SubsystemPoses(ReefState.L3, ManipulatorArmState.SCORE, IntakePivotState.STOW), new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), L4( "L4", - new SubsystemPoses(ReefState.L4, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), + new SubsystemPoses(ReefState.L4, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), SubsystemActions.empty()), L4_SCORE( "L4_SCORE", - new SubsystemPoses(ReefState.L4, ManipulatorArmState.SCORE, IntakePivotState.STOW), + new SubsystemPoses(ReefState.L4, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), new SubsystemActions(ManipulatorRollerState.L4_SCORE, IntakeRollerState.STOP)), HANDOFF( "HANDOFF", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.STOW), + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), SubsystemActions.empty()), INTERMEDIATE_WAIT_FOR_ELEVATOR( "INTERMEDIATE_WAIT_FOR_ELEVATOR", - new SubsystemPoses( - ReefState.HANDOFF, ManipulatorArmState.VERTICAL_UP, IntakePivotState.ARM_CLEAR), + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), SubsystemActions.empty()), INTERMEDIATE_WAIT_FOR_ARM( "INTERMEDIATE_WAIT_FOR_ARM", - new SubsystemPoses( - ReefState.HANDOFF, ManipulatorArmState.SAFE_ANGLE, IntakePivotState.ARM_CLEAR), + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.SAFE_ANGLE, IntakePivotState.STOW), SubsystemActions.empty()), L2_ALGAE( "L2_ALGAE", new SubsystemPoses( - ReefState.ALGAE_INTAKE_BOTTOM, - ManipulatorArmState.REEF_INTAKE, - IntakePivotState.ARM_CLEAR), + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), SubsystemActions.empty()), L2_ALGAE_INTAKE( "L2_ALGAE_INTAKE", new SubsystemPoses( - ReefState.ALGAE_INTAKE_BOTTOM, - ManipulatorArmState.REEF_INTAKE, - IntakePivotState.ARM_CLEAR), + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), L3_ALGAE( "L3_ALGAE", new SubsystemPoses( - ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.ARM_CLEAR), + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), SubsystemActions.empty()), L3_ALGAE_INTAKE( "L3_ALGAE_INTAKE", new SubsystemPoses( - ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.ARM_CLEAR), + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), PROCESSOR( "PROCESSOR", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.ARM_CLEAR), + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), SubsystemActions.empty()), PROCESSOR_SCORE( "PROCESSOR_SCORE", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.ARM_CLEAR), + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), BARGE( "BARGE", new SubsystemPoses( - ReefState.ALGAE_SCORE, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), + ReefState.ALGAE_SCORE, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), SubsystemActions.empty()), BARGE_SCORE( "BARGE_SCORE", - new SubsystemPoses(ReefState.ALGAE_SCORE, ManipulatorArmState.SCORE, IntakePivotState.STOW), + new SubsystemPoses( + ReefState.ALGAE_SCORE, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), ; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index 7ea959cd..1bacfd1c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -35,12 +35,12 @@ public class V3_EpsilonIntakeConstants { @RequiredArgsConstructor public enum IntakePivotState { - STOW(Rotation2d.fromDegrees(0)), + STOW(Rotation2d.fromDegrees(25.0)), INTAKE_CORAL(Rotation2d.fromDegrees(123.6)), HANDOFF(Rotation2d.fromDegrees(0)), L1(Rotation2d.fromDegrees(-82 + 123.6)), INTAKE_ALGAE(new Rotation2d()), - ARM_CLEAR(Rotation2d.fromDegrees(25.0)); + ARM_CLEAR(Rotation2d.fromDegrees(35)); @Getter private final Rotation2d angle; } From 2cb07e0ee863159a7db1ba7a34d77d0d52619602 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sun, 7 Sep 2025 17:22:34 -0400 Subject: [PATCH 080/180] revert testing change --- .../v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 471fd42e..c9d3c5b1 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -599,14 +599,12 @@ public Command allTransition() { all.andThen( runGoal(sink), runOnce(() -> System.out.println("Initial Pose:" + sink)), - Commands.waitUntil(this::atGoal), - Commands.waitSeconds(.05)); + Commands.waitSeconds(2)); all = all.andThen( runGoal(source), runOnce(() -> System.out.println("Final Pose:" + source)), - Commands.waitUntil(this::atGoal), - Commands.waitSeconds(.05)); + Commands.waitSeconds(2)); } } } From 8dcb476dd1eacf20561a9211b1898b6bb49ba572 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sun, 7 Sep 2025 22:37:33 -0400 Subject: [PATCH 081/180] fix all states --- .../shared/elevator/ElevatorConstants.java | 2 +- .../V3_EpsilonSuperstructureEdges.java | 46 ++++++++++++++++++- 2 files changed, 45 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index 55174dfa..6cd059bc 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -304,7 +304,7 @@ public static enum ElevatorPositions { 0.2161583093038944 + Units.inchesToMeters(1))), ALGAE_MID( new PositionConstants( - 0.7073684509805078, 0.7073684509805078, 0.0)), // DOES NOT EXIST FOR V3 + 0.7073684509805078, 0.7073684509805078, 1.2)), // USED AS PRE-HANDOFF FOR V3 ALGAE_INTAKE_TOP( new PositionConstants( 1.17 - Units.inchesToMeters(8), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index 3f4c4f5f..dd2714ee 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -4,6 +4,7 @@ import edu.wpi.first.wpilibj.Filesystem; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; +import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.shared.elevator.ElevatorConstants; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; @@ -209,9 +210,15 @@ private static Command getEdgeCommand( moveCommand = pose.asCommand(elevator, intake, manipulator); } + if (from == V3_EpsilonSuperstructureStates.HANDOFF) { + moveCommand = + Commands.sequence( + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.ALGAE_MID)), + elevator.waitUntilAtGoal(), + moveCommand); + } // move intake out of the way if it will collide - if (willCollide(from, to)) { - System.out.println("Collision predicted from " + from + " to " + to + ", moving intake out"); + else if (willCollide(from, to)) { moveCommand = Commands.sequence( Commands.runOnce(() -> intake.setPivotGoal(IntakePivotState.ARM_CLEAR)), @@ -219,6 +226,41 @@ private static Command getEdgeCommand( moveCommand); } + if (to == V3_EpsilonSuperstructureStates.HANDOFF) { + + if (requiresArm) { + moveCommand = + Commands.sequence( + pose.setManipulatorState(manipulator), + Commands.waitUntil(manipulator::isSafePosition), + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.ALGAE_MID)), + elevator.waitUntilAtGoal(), + pose.setIntakeState(intake), + intake.waitUntilPivotAtGoal(), + pose.setElevatorHeight(elevator)); + } else if (requiresElevator) { + moveCommand = + Commands.sequence( + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.ALGAE_MID)), + elevator.waitUntilAtGoal(), + pose.setManipulatorState(manipulator), + manipulator.waitUntilArmAtGoal(), + pose.setIntakeState(intake), + intake.waitUntilPivotAtGoal(), + pose.setElevatorHeight(elevator)); + } else { + moveCommand = + Commands.sequence( + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.ALGAE_MID)) + .alongWith(pose.setManipulatorState(manipulator)), + Commands.waitSeconds(0.02), + Commands.waitUntil(() -> elevator.atGoal() || manipulator.armAtGoal()), + pose.setIntakeState(intake), + intake.waitUntilPivotAtGoal(), + pose.setElevatorHeight(elevator)); + } + } + // THE CRITICAL FIX: // No matter how we start the move, we append a final wait condition. // This ensures the command doesn't end until the robot is physically at the From 57e4ae27efb2ddc56dade5f5f9d44822bb4a388d Mon Sep 17 00:00:00 2001 From: Rishi Date: Mon, 8 Sep 2025 18:31:53 -0400 Subject: [PATCH 082/180] Added the handoffCoral command With help from: Sriaditya Vaddadi , Seetha Raman, Abhiruph --- .../frc/robot/commands/CompositeCommands.java | 24 +++++++++++++++++++ .../v3_Epsilon/V3_EpsilonRobotContainer.java | 4 ++-- 2 files changed, 26 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 4b1224c6..b5592d53 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -24,6 +24,7 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; @@ -671,5 +672,28 @@ public static final Command intakeAlgaeFloor( .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) .until(() -> manipulator.hasAlgae()); // add intake for algae after } + + public static final Command handoffCoral( + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF), + Commands.parallel( + Commands.run( + () -> + intake.setRollerGoal( + frc.robot + .subsystems + .v3_Epsilon + .superstructure + .intake + .V3_EpsilonIntakeConstants + .IntakeRollerState + .OUTTAKE)), + Commands.run( + () -> manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE))) + .until(() -> manipulator.hasCoral())); + } } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 3252d736..27103c73 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -125,7 +125,7 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { - return CompositeCommands.V3_EpsilonCompositeCommands.emergencyEject( - manipulator, superstructure); + return CompositeCommands.V3_EpsilonCompositeCommands.handoffCoral( + superstructure, intake, manipulator); } } From efab4de43c349991dbd6c8b2e88f0dd583eb2092 Mon Sep 17 00:00:00 2001 From: Rishi Date: Mon, 8 Sep 2025 19:39:33 -0400 Subject: [PATCH 083/180] Fixed the handoff --- .../frc/robot/commands/CompositeCommands.java | 35 ++++++++++--------- .../V3_EpsilonSuperstructureStates.java | 3 +- .../intake/V3_EpsilonIntake.java | 12 +++++++ .../V3_EpsilonManipulatorConstants.java | 5 +-- 4 files changed, 35 insertions(+), 20 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index b5592d53..f323e9bd 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -677,23 +677,24 @@ public static final Command handoffCoral( V3_EpsilonSuperstructure superstructure, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { - return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF), - Commands.parallel( - Commands.run( - () -> - intake.setRollerGoal( - frc.robot - .subsystems - .v3_Epsilon - .superstructure - .intake - .V3_EpsilonIntakeConstants - .IntakeRollerState - .OUTTAKE)), - Commands.run( - () -> manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE))) - .until(() -> manipulator.hasCoral())); + // return Commands.sequence( + + return superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF); + /*Commands.parallel( + Commands.waitSeconds(10), + Commands.runOnce( + () -> + intake.setRollerGoal( + frc.robot + .subsystems + .v3_Epsilon + .superstructure + .intake + .V3_EpsilonIntakeConstants + .IntakeRollerState + .OUTTAKE)), + Commands.runOnce( + () -> manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE))));*/ } } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 7e77b7ed..19b31e1e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -80,7 +80,8 @@ public enum V3_EpsilonSuperstructureStates { HANDOFF( "HANDOFF", new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.STOW), - SubsystemActions.empty()), + new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.OUTTAKE)), + INTERMEDIATE_WAIT_FOR_ELEVATOR( "INTERMEDIATE_WAIT_FOR_ELEVATOR", new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index fd6bcd98..7e4075d9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -5,6 +5,7 @@ import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakePivotState; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakeRollerState; +import java.util.Set; import lombok.Getter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; @@ -78,6 +79,17 @@ public Command waitUntilPivotAtGoal() { public void setRollerGoal(IntakeRollerState rollerGoal) { this.rollerGoal = rollerGoal; + if (hasCoral() + && Set.of( + V3_EpsilonIntakeConstants.IntakeRollerState.ALGAE_INTAKE, + V3_EpsilonIntakeConstants.IntakeRollerState.CORAL_INTAKE, + V3_EpsilonIntakeConstants.IntakeRollerState.STOP) + .contains(rollerGoal)) { + + io.setRollerVoltage(0); + } else { + io.setRollerVoltage(rollerGoal.getVoltage()); + } } public Rotation2d getPivotAngle() { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index a7fd8096..7a706fb9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -159,6 +159,7 @@ public Rotation2d getAngle() { } // Will add more states later + @RequiredArgsConstructor public static enum ManipulatorRollerState { STOP(0.0), CORAL_INTAKE(6.0), @@ -171,9 +172,9 @@ public static enum ManipulatorRollerState { private final double voltage; - ManipulatorRollerState(double voltage) { + /*ManipulatorRollerState(double voltage) { this.voltage = voltage; - } + }*/ public double getVoltage() { return voltage; From 7f36c3a2fe5b8edd1be0c3988226bb8980387c40 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Thu, 4 Sep 2025 19:49:00 -0400 Subject: [PATCH 084/180] completed command for intaking coral --> simulated it but has issues --- .../frc/robot/commands/CompositeCommands.java | 26 ++++++++++++++++--- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 14 +++++++++- .../intake/V3_EpsilonIntake.java | 8 +++++- .../manipulator/V3_EpsilonManipulator.java | 6 ++--- .../V3_EpsilonManipulatorConstants.java | 2 +- 5 files changed, 46 insertions(+), 10 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 4b1224c6..2384dffd 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -22,11 +22,12 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; +import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants.ManipulatorArmState; +import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants.ManipulatorRollerState; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; import frc.robot.util.AllianceFlipUtil; import java.util.function.BooleanSupplier; import java.util.function.Supplier; @@ -655,13 +656,30 @@ public static final Command homingSequences( } public static final class V3_EpsilonCompositeCommands { + + public static final Command intakeCoralDriverSequence( + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoalUntil( + V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoral()), + Commands.waitSeconds(0.2), + superstructure.runGoalUntil( + V3_EpsilonSuperstructureStates.HANDOFF, () -> manipulator.hasCoral())); + // superstructure.runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE), + // Commands.waitSeconds(0.2), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF)); + } + public static final Command emergencyEject( V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { return Commands.sequence( superstructure.override( () -> { - manipulator.setArmGoal(ManipulatorArmState.EMERGENCY_EJECT_ANGLE); - manipulator.setRollerGoal(ManipulatorRollerState.L4_SCORE); + manipulator.setArmGoal(frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState.EMERGENCY_EJECT_ANGLE); + manipulator.setRollerGoal(frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState.L4_SCORE); })); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 3252d736..c719780b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -2,11 +2,14 @@ import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; +import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.Constants; import frc.robot.Constants.Mode; import frc.robot.RobotContainer; import frc.robot.RobotState; import frc.robot.commands.CompositeCommands; +import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.drive.DriveConstants; import frc.robot.subsystems.shared.drive.GyroIO; @@ -20,6 +23,7 @@ import frc.robot.subsystems.shared.elevator.ElevatorIOSim; import frc.robot.subsystems.shared.elevator.ElevatorIOTalonFX; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIO; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOSim; @@ -40,6 +44,7 @@ public class V3_EpsilonRobotContainer implements RobotContainer { private V3_EpsilonSuperstructure superstructure; // Controller + CommandXboxController driver = new CommandXboxController(0); // Auto chooser @@ -101,7 +106,14 @@ public V3_EpsilonRobotContainer() { } } - private void configureButtonBindings() {} + private void configureButtonBindings() { + driver + .rightTrigger() + .whileTrue( + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake, manipulator)) + .whileFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF)); + } private void configureAutos() {} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index fd6bcd98..f3a23515 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -12,6 +12,7 @@ public class V3_EpsilonIntake { private final V3_EpsilonIntakeIO io; private final V3_EpsilonIntakeIOInputsAutoLogged inputs; + private final double INTAKE_CORAL_THRESHOLD = 1.0; @Getter @AutoLogOutput(key = "Intake/Pivot Goal") @@ -42,9 +43,14 @@ public void periodic() { } } + // Double check if this is right @AutoLogOutput(key = "Intake/Has Coral") public boolean hasCoral() { - return false; // Udpate later + if (Math.abs(inputs.rollerTorqueCurrentAmps) > INTAKE_CORAL_THRESHOLD) { + return true; + } else { + return false; + } } @AutoLogOutput(key = "Intake/At Goal") diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 04ee38ef..cdb6685a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -149,17 +149,17 @@ public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmSta io.setManipulatorState(state); } - public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState rollerGoal) { + public void setRollerGoal(ManipulatorRollerState l4Score) { if (hasAlgae() && Set.of( V3_EpsilonManipulatorConstants.ManipulatorRollerState.ALGAE_INTAKE, V3_EpsilonManipulatorConstants.ManipulatorRollerState.CORAL_INTAKE, V3_EpsilonManipulatorConstants.ManipulatorRollerState.STOP) - .contains(rollerGoal)) { + .contains(l4Score)) { io.setRollerVoltage(holdVoltage()); } else { - io.setRollerVoltage(rollerGoal.getVoltage()); + io.setRollerVoltage(l4Score.getVoltage()); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index a7fd8096..79b4efad 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -149,7 +149,7 @@ public static enum ManipulatorArmState { VERTICAL_UP(Rotation2d.fromDegrees(0)), HANDOFF(Rotation2d.kPi), SAFE_ANGLE(Rotation2d.fromDegrees(150)), - EMERGENCY_EJECT_ANGLE(Rotation2d.fromDegrees(90)); + EMERGENCY_EJECT_ANGLE(Rotation2d.fromDegrees(90)); // Idk if tested. Looks fine but double check. private final Rotation2d angle; From 921be89f581530acd0c0b90941df25fe9b37bb57 Mon Sep 17 00:00:00 2001 From: Rishi Date: Thu, 11 Sep 2025 17:52:44 -0400 Subject: [PATCH 085/180] Finished Handoff command to stop and go into STOW_UP --- .../frc/robot/commands/CompositeCommands.java | 22 ++++--------------- 1 file changed, 4 insertions(+), 18 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index f323e9bd..73c31ceb 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -677,24 +677,10 @@ public static final Command handoffCoral( V3_EpsilonSuperstructure superstructure, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { - // return Commands.sequence( - - return superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF); - /*Commands.parallel( - Commands.waitSeconds(10), - Commands.runOnce( - () -> - intake.setRollerGoal( - frc.robot - .subsystems - .v3_Epsilon - .superstructure - .intake - .V3_EpsilonIntakeConstants - .IntakeRollerState - .OUTTAKE)), - Commands.runOnce( - () -> manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE))));*/ + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF), + Commands.waitUntil(() -> manipulator.hasCoral()), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)); } } } From a5c84d2dfafab985237ce52c7a88f424a5bce85f Mon Sep 17 00:00:00 2001 From: jasminepalit <125102672+jasminepalit@users.noreply.github.com> Date: Thu, 11 Sep 2025 17:58:38 -0400 Subject: [PATCH 086/180] Commands v3 jasmine (#131) * Added scoreCoral command * Added scoreCoral command Co-authored-by: adrikamoulik Co-authored-by: aishani1989 * undo advantagescopeassets deletion * Fixed scoreCoral and intakeAlgaeFromReef Co-authored-by: aishani1989 Co-authored-by: rddhimabora Co-authored-by: adrikamoulik --------- Co-authored-by: adrikamoulik Co-authored-by: aishani1989 Co-authored-by: Anshu Co-authored-by: rddhimabora --- .../frc/robot/commands/CompositeCommands.java | 297 +++++++++++------- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 10 +- 2 files changed, 195 insertions(+), 112 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 1faf5f98..f62926c5 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -22,15 +22,21 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.util.AllianceFlipUtil; import java.util.function.BooleanSupplier; import java.util.function.Supplier; /** - * A class that holds composite commands, which are sequences of commands for complex robot actions. + * A class that holds composite commands, which are sequences of commands for + * complex robot actions. */ public class CompositeCommands { - /** A class that holds composite commands that are shared across different robot versions. */ + /** + * A class that holds composite commands that are shared across different robot + * versions. + */ public static final class SharedCommands { /** * Creates a command to reset the robot's heading to the alliance-specific zero. @@ -40,17 +46,18 @@ public static final class SharedCommands { */ public static final Command resetHeading(Drive drive) { return Commands.runOnce( - () -> { - RobotState.resetRobotPose( - new Pose2d( - RobotState.getRobotPoseField().getTranslation(), - AllianceFlipUtil.apply(new Rotation2d()))); - }) + () -> { + RobotState.resetRobotPose( + new Pose2d( + RobotState.getRobotPoseField().getTranslation(), + AllianceFlipUtil.apply(new Rotation2d()))); + }) .ignoringDisable(true); } /** - * Creates a command to set a static reef height in the robot state. This does not move any + * Creates a command to set a static reef height in the robot state. This does + * not move any * mechanisms. * * @param height The reef height to set. @@ -66,37 +73,37 @@ public static final class V1_StackUpCompositeCommands { /** * Creates a command to intake coral from the station. * - * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. + * @param elevator The elevator subsystem. + * @param funnel The funnel subsystem. * @param manipulator The manipulator subsystem. * @return A command to intake coral. */ public static final Command intakeCoral( ElevatorCSB elevator, FunnelCSB funnel, V1_StackUpManipulator manipulator) { return Commands.sequence( - Commands.runOnce(() -> RobotState.setIntakingCoral(true)), - elevator.setPosition(() -> ReefState.CORAL_INTAKE), - Commands.waitUntil(elevator::atGoal), - Commands.race( - manipulator.intakeCoral(), funnel.intakeCoral(() -> manipulator.hasCoral()))) + Commands.runOnce(() -> RobotState.setIntakingCoral(true)), + elevator.setPosition(() -> ReefState.CORAL_INTAKE), + Commands.waitUntil(elevator::atGoal), + Commands.race( + manipulator.intakeCoral(), funnel.intakeCoral(() -> manipulator.hasCoral()))) .finallyDo(() -> RobotState.setIntakingCoral(false)); } /** * Creates a command to intake coral from the station with an override. * - * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. + * @param elevator The elevator subsystem. + * @param funnel The funnel subsystem. * @param manipulator The manipulator subsystem. * @return A command to intake coral with an override. */ public static final Command intakeCoralOverride( ElevatorCSB elevator, FunnelCSB funnel, V1_StackUpManipulator manipulator) { return Commands.sequence( - Commands.runOnce(() -> RobotState.setIntakingCoral(true)), - elevator.setPosition(() -> ReefState.CORAL_INTAKE), - Commands.waitUntil(elevator::atGoal), - Commands.parallel(manipulator.intakeCoral(), funnel.intakeCoral(() -> false))) + Commands.runOnce(() -> RobotState.setIntakingCoral(true)), + elevator.setPosition(() -> ReefState.CORAL_INTAKE), + Commands.waitUntil(elevator::atGoal), + Commands.parallel(manipulator.intakeCoral(), funnel.intakeCoral(() -> false))) .finallyDo(() -> RobotState.setIntakingCoral(false)); } @@ -113,7 +120,7 @@ public static final Command scoreCoral(V1_StackUpManipulator manipulator) { /** * Creates a command sequence to score coral, waiting for auto-alignment. * - * @param elevator The elevator subsystem. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. * @param autoAligned A supplier that returns true when the robot is aligned. * @return A command sequence to score coral. @@ -124,9 +131,8 @@ public static final Command scoreCoralSequence( Commands.either( elevator.setPosition(() -> ReefState.L3), elevator.setPosition(), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L4) - && !elevator.getPosition().equals(ElevatorPositions.L4)), + () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L4) + && !elevator.getPosition().equals(ElevatorPositions.L4)), Commands.waitUntil(() -> autoAligned.getAsBoolean()), elevator.setPosition(), Commands.waitSeconds(0.05), @@ -140,10 +146,10 @@ public static final Command scoreCoralSequence( /** * Creates a command sequence to automatically score coral. * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. + * @param cameras The vision cameras. * @return A command sequence to auto-score coral. */ public static final Command autoScoreCoralSequence( @@ -154,12 +160,11 @@ public static final Command autoScoreCoralSequence( Commands.either( elevator.setPosition(() -> ReefState.L2), Commands.none(), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L1) - || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) - || RobotState.getOIData() - .currentReefHeight() - .equals(ReefState.CORAL_INTAKE)), + () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1) + || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) + || RobotState.getOIData() + .currentReefHeight() + .equals(ReefState.CORAL_INTAKE)), Commands.parallel( DriveCommands.autoAlignReefCoral(drive, cameras), scoreCoralSequence( @@ -169,19 +174,18 @@ public static final Command autoScoreCoralSequence( elevator .setPosition(() -> ReefState.STOW) .onlyIf( - () -> - elevator.getPosition().equals(ElevatorPositions.L3) - || elevator.getPosition().equals(ElevatorPositions.L2))), + () -> elevator.getPosition().equals(ElevatorPositions.L3) + || elevator.getPosition().equals(ElevatorPositions.L2))), () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); } /** * Creates a command sequence to automatically score coral at L1. * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. + * @param cameras The vision cameras. * @return A command sequence to auto-score coral at L1. */ public static final Command autoScoreL1CoralSequence( @@ -194,8 +198,8 @@ public static final Command autoScoreL1CoralSequence( /** * Creates a command to score coral at L1. * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. * @return A command to score coral at L1. */ @@ -218,7 +222,7 @@ public static final Command scoreL1Coral( /** * Creates a command for an emergency eject of coral. * - * @param elevator The elevator subsystem. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. * @return A command to eject coral. */ @@ -233,38 +237,38 @@ public static final Command emergencyEject( } /** - * Creates a command to remove algae from the reef. This uses the closest reef tag to + * Creates a command to remove algae from the reef. This uses the closest reef + * tag to * automatically pick the reef height. * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. + * @param cameras The vision cameras. * @return A command to remove algae. */ public static final Command twerk( Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { return Commands.deferredProxy( - () -> - twerk( - drive, - elevator, - manipulator, - switch (RobotState.getReefAlignData().closestReefTag()) { - case 10, 6, 8, 21, 17, 19 -> ReefState.ASS_BOT; - case 9, 11, 7, 22, 20, 18 -> ReefState.ASS_TOP; - default -> ReefState.ASS_BOT; - }, - cameras)); + () -> twerk( + drive, + elevator, + manipulator, + switch (RobotState.getReefAlignData().closestReefTag()) { + case 10, 6, 8, 21, 17, 19 -> ReefState.ASS_BOT; + case 9, 11, 7, 22, 20, 18 -> ReefState.ASS_TOP; + default -> ReefState.ASS_BOT; + }, + cameras)); } /** * Creates a command to remove algae from the reef. * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. + * @param cameras The vision cameras. * @return A command to remove algae. */ public static final Command twerk( @@ -286,10 +290,11 @@ public static final Command twerk( } /** - * Creates a command to set the dynamic reef height in the robot state. This sets the height and + * Creates a command to set the dynamic reef height in the robot state. This + * sets the height and * then moves the elevator to that position. * - * @param height The reef height to set. + * @param height The reef height to set. * @param elevator The elevator subsystem. * @return A command to set the dynamic reef height. */ @@ -302,9 +307,9 @@ public static final Command setDynamicReefHeight(ReefState height, ElevatorCSB e * Creates a command to climb the robot. * * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. - * @param climber The climber subsystem. - * @param drive The drive subsystem. + * @param funnel The funnel subsystem. + * @param climber The climber subsystem. + * @param drive The drive subsystem. * @return A command to climb. */ public static final Command climb( @@ -328,7 +333,7 @@ public static final class V2_RedundancyCompositeCommands { * Creates a command to intake coral from the station. * * @param superstructure The superstructure subsystem. - * @param intake The intake subsystem. + * @param intake The intake subsystem. * @return A command to intake coral. */ public static final Command intakeCoralDriverSequence( @@ -341,10 +346,11 @@ public static final Command intakeCoralDriverSequence( } /** - * Creates a command to intake coral from the station using the operator sequence. + * Creates a command to intake coral from the station using the operator + * sequence. * * @param superstructure The superstructure subsystem. - * @param intake The intake subsystem. + * @param intake The intake subsystem. * @return A command to intake coral using the operator sequence. */ public static final Command intakeCoralOperatorSequence( @@ -358,7 +364,7 @@ public static final Command intakeCoralOperatorSequence( /** * Creates a command to score coral at L1. * - * @param drive The drive subsystem. + * @param drive The drive subsystem. * @param superstructure The superstructure subsystem. * @return A command to score coral at L1. */ @@ -379,7 +385,7 @@ public static final Command scoreL1Coral( /** * Creates a command sequence to score coral at L1, waiting for auto-alignment. * - * @param drive The drive subsystem. + * @param drive The drive subsystem. * @param superstructure The superstructure subsystem. * @return A command sequence to score coral at L1. */ @@ -395,9 +401,9 @@ public static final Command autoScoreL1CoralSequence( /** * Creates a command sequence to score coral, waiting for auto-alignment. * - * @param elevator The elevator subsystem. + * @param elevator The elevator subsystem. * @param superstructure The superstructure subsystem. - * @param autoAligned A supplier that returns true when the robot is aligned. + * @param autoAligned A supplier that returns true when the robot is aligned. * @return A command sequence to score coral. */ public static final Command scoreCoralSequence( @@ -408,28 +414,26 @@ public static final Command scoreCoralSequence( Commands.either( superstructure.runGoal(V2_RedundancySuperstructureStates.L3), superstructure.runReefGoal(() -> RobotState.getOIData().currentReefHeight()), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L4) - && !superstructure - .getCurrentState() - .equals(V2_RedundancySuperstructureStates.L4)), + () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L4) + && !superstructure + .getCurrentState() + .equals(V2_RedundancySuperstructureStates.L4)), Commands.waitUntil(() -> autoAligned.getAsBoolean()), superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight()), superstructure .runGoal(V2_RedundancySuperstructureStates.STOW_DOWN) .onlyIf( - () -> - elevator.getPosition().equals(ElevatorPositions.L3) - || elevator.getPosition().equals(ElevatorPositions.L2))); + () -> elevator.getPosition().equals(ElevatorPositions.L3) + || elevator.getPosition().equals(ElevatorPositions.L2))); } /** * Creates a command sequence to automatically score coral. * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. * @param superstructure The superstructure subsystem. - * @param cameras The vision cameras. + * @param cameras The vision cameras. * @return A command sequence to auto-score coral. */ public static final Command autoScoreCoralSequence( @@ -446,12 +450,11 @@ public static final Command autoScoreCoralSequence( Commands.either( superstructure.runGoal(V2_RedundancySuperstructureStates.L2), Commands.none(), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L1) - || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) - || RobotState.getOIData() - .currentReefHeight() - .equals(ReefState.CORAL_INTAKE)), + () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1) + || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) + || RobotState.getOIData() + .currentReefHeight() + .equals(ReefState.CORAL_INTAKE)), Commands.parallel( DriveCommands.autoAlignReefCoral(drive, cameras), scoreCoralSequence( @@ -465,12 +468,13 @@ public static final Command autoScoreCoralSequence( } /** - * Creates a command to intake algae from the reef. This uses the closest reef tag to + * Creates a command to intake algae from the reef. This uses the closest reef + * tag to * automatically pick the reef height and reef face. * - * @param drive The drive subsystem. + * @param drive The drive subsystem. * @param superstructure The superstructure subsystem. - * @param cameras The vision cameras. + * @param cameras The vision cameras. * @return A command to remove algae. */ public static final Command intakeAlgaeFromReefSequence( @@ -508,20 +512,20 @@ public static final Command intakeAlgaeFromReefSequence( }), () -> RobotState.isHasAlgae())), Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) + () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) .withTimeout(0.5))); } /** * Creates a command to drop algae from the reef. * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param intake The intake subsystem. * @param superstructure The superstructure subsystem. - * @param level A supplier that provides the current reef level. - * @param cameras The vision cameras. + * @param level A supplier that provides the current reef level. + * @param cameras The vision cameras. * @return A command to drop algae from the reef. */ public static final Command dropAlgae( @@ -550,7 +554,7 @@ public static final Command dropAlgae( .until(() -> RobotState.isHasAlgae()), Commands.waitSeconds(2.0), Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) + () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) .withTimeout(0.5)), superstructure.runGoal( () -> { @@ -582,7 +586,8 @@ public static final Command floorIntakeSequence(V2_RedundancySuperstructure supe } /** - * Creates a command that posts the floor intake sequence, which can either go up or down based + * Creates a command that posts the floor intake sequence, which can either go + * up or down based * on whether the robot has algae. * * @param superstructure The superstructure subsystem. @@ -597,10 +602,11 @@ public static final Command postFloorIntakeSequence( } /** - * Creates a command to set the dynamic reef height in the robot state. This sets the height and + * Creates a command to set the dynamic reef height in the robot state. This + * sets the height and * then moves the superstructure to that position. * - * @param height The reef height to set. + * @param height The reef height to set. * @param superstructure The superstructure subsystem. * @return A command to set the dynamic reef height. */ @@ -614,8 +620,8 @@ public static final Command setDynamicReefHeight( * Creates a command to climb the robot. * * @param superstructure The superstructure subsystem. - * @param climber The climber subsystem. - * @param drive The drive subsystem. + * @param climber The climber subsystem. + * @param drive The drive subsystem. * @return A command to climb. */ public static final Command climb( @@ -632,11 +638,12 @@ public static final Command climb( } /** - * Creates a command sequence for homing all subsystems in the V2_Redundancy robot. + * Creates a command sequence for homing all subsystems in the V2_Redundancy + * robot. * * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. - * @param elevator The elevator subsystem. + * @param intake The intake subsystem. + * @param elevator The elevator subsystem. * @return A command sequence to home all subsystems. */ public static final Command homingSequences( @@ -649,5 +656,73 @@ public static final Command homingSequences( Commands.runOnce(() -> elevator.setPosition())); } - public static final class V3_EpsilonCompositeCommands {} + public static final class V3_EpsilonCompositeCommands { + + /** + * Creates a command to score coral. + * + * @param superstructure The superstructure subsystem. + * @param goal This is the goal. + * @return A command to score coral. + */ + public static final Command scoreCoral( + V3_EpsilonSuperstructure superstructure, Supplier goal) { + return superstructure.runReefScoreGoal(goal); + } + + /** + * public static final Command intakeAlgaeReef(V3_EpsilonSuperstructure + * superstructure, + * V3_EpsilonSuperstructureStates goal, V3_EpsilonSuperstructureAction action, + * V3_EpsilonIntake + * intake, V3_EpsilonSuperstructure hasalgae) { return Commands.sequence( + * superstructure.runGoal(), Commands.run(() -> action.runIntake(intake)), + * superstructure.isHasAlgae() == (edge.getGamePieceEdge() != + * (GamePieceEdge.NO_ALGAE) ); ); } + */ + public static final Command intakeAlgaeFromReef( + Drive drive, V3_EpsilonSuperstructure superstructure, Supplier level) { + + return Commands.sequence( + // DriveCommands.autoAlignReefAlgae(drive), + superstructure + .runGoalUntil( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }, + () -> RobotState.isHasAlgae()) + .withTimeout(3), + Commands.parallel( + Commands.sequence( + Commands.waitSeconds(0.25), + Commands.either( + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), + superstructure.runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE; + default: + return V3_EpsilonSuperstructureStates.L2_ALGAE; + } + }), + () -> RobotState.isHasAlgae())), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), + () -> drive.stop()) + .withTimeout(0.5))); + } + } + + /** + * drive to reef go to algae level (L2 or L3) turn intake on go until it has + * algae then stow up + */ } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 322c349e..d1f70b58 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -2,10 +2,13 @@ import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.Constants; import frc.robot.Constants.Mode; +import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotContainer; import frc.robot.RobotState; +import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.drive.DriveConstants; import frc.robot.subsystems.shared.drive.GyroIO; @@ -19,6 +22,7 @@ import frc.robot.subsystems.shared.elevator.ElevatorIOSim; import frc.robot.subsystems.shared.elevator.ElevatorIOTalonFX; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIO; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOSim; @@ -124,6 +128,10 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { - return superstructure.allTransition(); + return Commands.sequence( + V3_EpsilonCompositeCommands.intakeAlgaeFromReef( + drive, superstructure, () -> ReefState.ALGAE_INTAKE_TOP), + Commands.waitSeconds(5), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); } } From df369ab91875a6cc0f4082769e9cf72aacfcef57 Mon Sep 17 00:00:00 2001 From: LordVanra <146479458+LordVanra@users.noreply.github.com> Date: Thu, 11 Sep 2025 18:08:11 -0400 Subject: [PATCH 087/180] Intake Coral From Ground (#128) * Intake Coral From Ground Co-authored-by: Noah Proctor Co-authored-by: posydon * Fixed Eliot's Complains Co-authored-by: Noah Proctor Co-authored-by: akg-022 * Fixed Anshu's Complaints * Fix coral intake state in V3_EpsilonSuperstructureStates * build --------- Co-authored-by: Noah Proctor Co-authored-by: posydon Co-authored-by: akg-022 Co-authored-by: Anshu Adiga --- .../frc/robot/commands/CompositeCommands.java | 258 +++++++++--------- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 1 + .../V3_EpsilonSuperstructureStates.java | 2 +- .../intake/V3_EpsilonIntake.java | 13 +- .../intake/V3_EpsilonIntakeConstants.java | 50 ++-- .../intake/V3_EpsilonIntakeIO.java | 35 ++- .../intake/V3_EpsilonIntakeIOSim.java | 50 +++- .../intake/V3_EpsilonIntakeIOTalonFX.java | 153 ++++++++--- 8 files changed, 350 insertions(+), 212 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index f62926c5..a0f065cf 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -24,19 +24,16 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.util.AllianceFlipUtil; import java.util.function.BooleanSupplier; import java.util.function.Supplier; /** - * A class that holds composite commands, which are sequences of commands for - * complex robot actions. + * A class that holds composite commands, which are sequences of commands for complex robot actions. */ public class CompositeCommands { - /** - * A class that holds composite commands that are shared across different robot - * versions. - */ + /** A class that holds composite commands that are shared across different robot versions. */ public static final class SharedCommands { /** * Creates a command to reset the robot's heading to the alliance-specific zero. @@ -46,18 +43,17 @@ public static final class SharedCommands { */ public static final Command resetHeading(Drive drive) { return Commands.runOnce( - () -> { - RobotState.resetRobotPose( - new Pose2d( - RobotState.getRobotPoseField().getTranslation(), - AllianceFlipUtil.apply(new Rotation2d()))); - }) + () -> { + RobotState.resetRobotPose( + new Pose2d( + RobotState.getRobotPoseField().getTranslation(), + AllianceFlipUtil.apply(new Rotation2d()))); + }) .ignoringDisable(true); } /** - * Creates a command to set a static reef height in the robot state. This does - * not move any + * Creates a command to set a static reef height in the robot state. This does not move any * mechanisms. * * @param height The reef height to set. @@ -73,37 +69,37 @@ public static final class V1_StackUpCompositeCommands { /** * Creates a command to intake coral from the station. * - * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. + * @param elevator The elevator subsystem. + * @param funnel The funnel subsystem. * @param manipulator The manipulator subsystem. * @return A command to intake coral. */ public static final Command intakeCoral( ElevatorCSB elevator, FunnelCSB funnel, V1_StackUpManipulator manipulator) { return Commands.sequence( - Commands.runOnce(() -> RobotState.setIntakingCoral(true)), - elevator.setPosition(() -> ReefState.CORAL_INTAKE), - Commands.waitUntil(elevator::atGoal), - Commands.race( - manipulator.intakeCoral(), funnel.intakeCoral(() -> manipulator.hasCoral()))) + Commands.runOnce(() -> RobotState.setIntakingCoral(true)), + elevator.setPosition(() -> ReefState.CORAL_INTAKE), + Commands.waitUntil(elevator::atGoal), + Commands.race( + manipulator.intakeCoral(), funnel.intakeCoral(() -> manipulator.hasCoral()))) .finallyDo(() -> RobotState.setIntakingCoral(false)); } /** * Creates a command to intake coral from the station with an override. * - * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. + * @param elevator The elevator subsystem. + * @param funnel The funnel subsystem. * @param manipulator The manipulator subsystem. * @return A command to intake coral with an override. */ public static final Command intakeCoralOverride( ElevatorCSB elevator, FunnelCSB funnel, V1_StackUpManipulator manipulator) { return Commands.sequence( - Commands.runOnce(() -> RobotState.setIntakingCoral(true)), - elevator.setPosition(() -> ReefState.CORAL_INTAKE), - Commands.waitUntil(elevator::atGoal), - Commands.parallel(manipulator.intakeCoral(), funnel.intakeCoral(() -> false))) + Commands.runOnce(() -> RobotState.setIntakingCoral(true)), + elevator.setPosition(() -> ReefState.CORAL_INTAKE), + Commands.waitUntil(elevator::atGoal), + Commands.parallel(manipulator.intakeCoral(), funnel.intakeCoral(() -> false))) .finallyDo(() -> RobotState.setIntakingCoral(false)); } @@ -120,7 +116,7 @@ public static final Command scoreCoral(V1_StackUpManipulator manipulator) { /** * Creates a command sequence to score coral, waiting for auto-alignment. * - * @param elevator The elevator subsystem. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. * @param autoAligned A supplier that returns true when the robot is aligned. * @return A command sequence to score coral. @@ -131,8 +127,9 @@ public static final Command scoreCoralSequence( Commands.either( elevator.setPosition(() -> ReefState.L3), elevator.setPosition(), - () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L4) - && !elevator.getPosition().equals(ElevatorPositions.L4)), + () -> + RobotState.getOIData().currentReefHeight().equals(ReefState.L4) + && !elevator.getPosition().equals(ElevatorPositions.L4)), Commands.waitUntil(() -> autoAligned.getAsBoolean()), elevator.setPosition(), Commands.waitSeconds(0.05), @@ -146,10 +143,10 @@ public static final Command scoreCoralSequence( /** * Creates a command sequence to automatically score coral. * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. + * @param cameras The vision cameras. * @return A command sequence to auto-score coral. */ public static final Command autoScoreCoralSequence( @@ -160,11 +157,12 @@ public static final Command autoScoreCoralSequence( Commands.either( elevator.setPosition(() -> ReefState.L2), Commands.none(), - () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1) - || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) - || RobotState.getOIData() - .currentReefHeight() - .equals(ReefState.CORAL_INTAKE)), + () -> + RobotState.getOIData().currentReefHeight().equals(ReefState.L1) + || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) + || RobotState.getOIData() + .currentReefHeight() + .equals(ReefState.CORAL_INTAKE)), Commands.parallel( DriveCommands.autoAlignReefCoral(drive, cameras), scoreCoralSequence( @@ -174,18 +172,19 @@ public static final Command autoScoreCoralSequence( elevator .setPosition(() -> ReefState.STOW) .onlyIf( - () -> elevator.getPosition().equals(ElevatorPositions.L3) - || elevator.getPosition().equals(ElevatorPositions.L2))), + () -> + elevator.getPosition().equals(ElevatorPositions.L3) + || elevator.getPosition().equals(ElevatorPositions.L2))), () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); } /** * Creates a command sequence to automatically score coral at L1. * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. + * @param cameras The vision cameras. * @return A command sequence to auto-score coral at L1. */ public static final Command autoScoreL1CoralSequence( @@ -198,8 +197,8 @@ public static final Command autoScoreL1CoralSequence( /** * Creates a command to score coral at L1. * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. * @return A command to score coral at L1. */ @@ -222,7 +221,7 @@ public static final Command scoreL1Coral( /** * Creates a command for an emergency eject of coral. * - * @param elevator The elevator subsystem. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. * @return A command to eject coral. */ @@ -237,38 +236,38 @@ public static final Command emergencyEject( } /** - * Creates a command to remove algae from the reef. This uses the closest reef - * tag to + * Creates a command to remove algae from the reef. This uses the closest reef tag to * automatically pick the reef height. * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. + * @param cameras The vision cameras. * @return A command to remove algae. */ public static final Command twerk( Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { return Commands.deferredProxy( - () -> twerk( - drive, - elevator, - manipulator, - switch (RobotState.getReefAlignData().closestReefTag()) { - case 10, 6, 8, 21, 17, 19 -> ReefState.ASS_BOT; - case 9, 11, 7, 22, 20, 18 -> ReefState.ASS_TOP; - default -> ReefState.ASS_BOT; - }, - cameras)); + () -> + twerk( + drive, + elevator, + manipulator, + switch (RobotState.getReefAlignData().closestReefTag()) { + case 10, 6, 8, 21, 17, 19 -> ReefState.ASS_BOT; + case 9, 11, 7, 22, 20, 18 -> ReefState.ASS_TOP; + default -> ReefState.ASS_BOT; + }, + cameras)); } /** * Creates a command to remove algae from the reef. * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. + * @param cameras The vision cameras. * @return A command to remove algae. */ public static final Command twerk( @@ -290,11 +289,10 @@ public static final Command twerk( } /** - * Creates a command to set the dynamic reef height in the robot state. This - * sets the height and + * Creates a command to set the dynamic reef height in the robot state. This sets the height and * then moves the elevator to that position. * - * @param height The reef height to set. + * @param height The reef height to set. * @param elevator The elevator subsystem. * @return A command to set the dynamic reef height. */ @@ -307,9 +305,9 @@ public static final Command setDynamicReefHeight(ReefState height, ElevatorCSB e * Creates a command to climb the robot. * * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. - * @param climber The climber subsystem. - * @param drive The drive subsystem. + * @param funnel The funnel subsystem. + * @param climber The climber subsystem. + * @param drive The drive subsystem. * @return A command to climb. */ public static final Command climb( @@ -333,7 +331,7 @@ public static final class V2_RedundancyCompositeCommands { * Creates a command to intake coral from the station. * * @param superstructure The superstructure subsystem. - * @param intake The intake subsystem. + * @param intake The intake subsystem. * @return A command to intake coral. */ public static final Command intakeCoralDriverSequence( @@ -346,11 +344,10 @@ public static final Command intakeCoralDriverSequence( } /** - * Creates a command to intake coral from the station using the operator - * sequence. + * Creates a command to intake coral from the station using the operator sequence. * * @param superstructure The superstructure subsystem. - * @param intake The intake subsystem. + * @param intake The intake subsystem. * @return A command to intake coral using the operator sequence. */ public static final Command intakeCoralOperatorSequence( @@ -364,7 +361,7 @@ public static final Command intakeCoralOperatorSequence( /** * Creates a command to score coral at L1. * - * @param drive The drive subsystem. + * @param drive The drive subsystem. * @param superstructure The superstructure subsystem. * @return A command to score coral at L1. */ @@ -385,7 +382,7 @@ public static final Command scoreL1Coral( /** * Creates a command sequence to score coral at L1, waiting for auto-alignment. * - * @param drive The drive subsystem. + * @param drive The drive subsystem. * @param superstructure The superstructure subsystem. * @return A command sequence to score coral at L1. */ @@ -401,9 +398,9 @@ public static final Command autoScoreL1CoralSequence( /** * Creates a command sequence to score coral, waiting for auto-alignment. * - * @param elevator The elevator subsystem. + * @param elevator The elevator subsystem. * @param superstructure The superstructure subsystem. - * @param autoAligned A supplier that returns true when the robot is aligned. + * @param autoAligned A supplier that returns true when the robot is aligned. * @return A command sequence to score coral. */ public static final Command scoreCoralSequence( @@ -414,26 +411,28 @@ public static final Command scoreCoralSequence( Commands.either( superstructure.runGoal(V2_RedundancySuperstructureStates.L3), superstructure.runReefGoal(() -> RobotState.getOIData().currentReefHeight()), - () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L4) - && !superstructure - .getCurrentState() - .equals(V2_RedundancySuperstructureStates.L4)), + () -> + RobotState.getOIData().currentReefHeight().equals(ReefState.L4) + && !superstructure + .getCurrentState() + .equals(V2_RedundancySuperstructureStates.L4)), Commands.waitUntil(() -> autoAligned.getAsBoolean()), superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight()), superstructure .runGoal(V2_RedundancySuperstructureStates.STOW_DOWN) .onlyIf( - () -> elevator.getPosition().equals(ElevatorPositions.L3) - || elevator.getPosition().equals(ElevatorPositions.L2))); + () -> + elevator.getPosition().equals(ElevatorPositions.L3) + || elevator.getPosition().equals(ElevatorPositions.L2))); } /** * Creates a command sequence to automatically score coral. * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. * @param superstructure The superstructure subsystem. - * @param cameras The vision cameras. + * @param cameras The vision cameras. * @return A command sequence to auto-score coral. */ public static final Command autoScoreCoralSequence( @@ -450,11 +449,12 @@ public static final Command autoScoreCoralSequence( Commands.either( superstructure.runGoal(V2_RedundancySuperstructureStates.L2), Commands.none(), - () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1) - || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) - || RobotState.getOIData() - .currentReefHeight() - .equals(ReefState.CORAL_INTAKE)), + () -> + RobotState.getOIData().currentReefHeight().equals(ReefState.L1) + || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) + || RobotState.getOIData() + .currentReefHeight() + .equals(ReefState.CORAL_INTAKE)), Commands.parallel( DriveCommands.autoAlignReefCoral(drive, cameras), scoreCoralSequence( @@ -468,13 +468,12 @@ public static final Command autoScoreCoralSequence( } /** - * Creates a command to intake algae from the reef. This uses the closest reef - * tag to + * Creates a command to intake algae from the reef. This uses the closest reef tag to * automatically pick the reef height and reef face. * - * @param drive The drive subsystem. + * @param drive The drive subsystem. * @param superstructure The superstructure subsystem. - * @param cameras The vision cameras. + * @param cameras The vision cameras. * @return A command to remove algae. */ public static final Command intakeAlgaeFromReefSequence( @@ -512,20 +511,20 @@ public static final Command intakeAlgaeFromReefSequence( }), () -> RobotState.isHasAlgae())), Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) + () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) .withTimeout(0.5))); } /** * Creates a command to drop algae from the reef. * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param intake The intake subsystem. * @param superstructure The superstructure subsystem. - * @param level A supplier that provides the current reef level. - * @param cameras The vision cameras. + * @param level A supplier that provides the current reef level. + * @param cameras The vision cameras. * @return A command to drop algae from the reef. */ public static final Command dropAlgae( @@ -554,7 +553,7 @@ public static final Command dropAlgae( .until(() -> RobotState.isHasAlgae()), Commands.waitSeconds(2.0), Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) + () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) .withTimeout(0.5)), superstructure.runGoal( () -> { @@ -586,8 +585,7 @@ public static final Command floorIntakeSequence(V2_RedundancySuperstructure supe } /** - * Creates a command that posts the floor intake sequence, which can either go - * up or down based + * Creates a command that posts the floor intake sequence, which can either go up or down based * on whether the robot has algae. * * @param superstructure The superstructure subsystem. @@ -602,11 +600,10 @@ public static final Command postFloorIntakeSequence( } /** - * Creates a command to set the dynamic reef height in the robot state. This - * sets the height and + * Creates a command to set the dynamic reef height in the robot state. This sets the height and * then moves the superstructure to that position. * - * @param height The reef height to set. + * @param height The reef height to set. * @param superstructure The superstructure subsystem. * @return A command to set the dynamic reef height. */ @@ -620,8 +617,8 @@ public static final Command setDynamicReefHeight( * Creates a command to climb the robot. * * @param superstructure The superstructure subsystem. - * @param climber The climber subsystem. - * @param drive The drive subsystem. + * @param climber The climber subsystem. + * @param drive The drive subsystem. * @return A command to climb. */ public static final Command climb( @@ -638,12 +635,11 @@ public static final Command climb( } /** - * Creates a command sequence for homing all subsystems in the V2_Redundancy - * robot. + * Creates a command sequence for homing all subsystems in the V2_Redundancy robot. * * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. - * @param elevator The elevator subsystem. + * @param intake The intake subsystem. + * @param elevator The elevator subsystem. * @return A command sequence to home all subsystems. */ public static final Command homingSequences( @@ -662,7 +658,7 @@ public static final class V3_EpsilonCompositeCommands { * Creates a command to score coral. * * @param superstructure The superstructure subsystem. - * @param goal This is the goal. + * @param goal This is the goal. * @return A command to score coral. */ public static final Command scoreCoral( @@ -671,14 +667,15 @@ public static final Command scoreCoral( } /** - * public static final Command intakeAlgaeReef(V3_EpsilonSuperstructure - * superstructure, - * V3_EpsilonSuperstructureStates goal, V3_EpsilonSuperstructureAction action, - * V3_EpsilonIntake + * public static final Command intakeAlgaeReef(V3_EpsilonSuperstructure superstructure, + * V3_EpsilonSuperstructureStates goal, V3_EpsilonSuperstructureAction action, V3_EpsilonIntake * intake, V3_EpsilonSuperstructure hasalgae) { return Commands.sequence( * superstructure.runGoal(), Commands.run(() -> action.runIntake(intake)), - * superstructure.isHasAlgae() == (edge.getGamePieceEdge() != - * (GamePieceEdge.NO_ALGAE) ); ); } + * superstructure.isHasAlgae() == (edge.getGamePieceEdge() != (GamePieceEdge.NO_ALGAE) ); ); } + */ + + /** + * drive to reef go to algae level (L2 or L3) turn intake on go until it has algae then stow up */ public static final Command intakeAlgaeFromReef( Drive drive, V3_EpsilonSuperstructure superstructure, Supplier level) { @@ -715,14 +712,17 @@ public static final Command intakeAlgaeFromReef( }), () -> RobotState.isHasAlgae())), Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), - () -> drive.stop()) + () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), + () -> drive.stop()) .withTimeout(0.5))); } - } - /** - * drive to reef go to algae level (L2 or L3) turn intake on go until it has - * algae then stow up - */ + public static final Command intakeCoralFromGround( + V3_EpsilonSuperstructure superstructure, V3_EpsilonIntake intake) { + return Commands.sequence( + superstructure.runGoalUntil( + V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoral()), + superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF)); + } + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index d1f70b58..47f70ac9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -128,6 +128,7 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { + // return superstructure.allTransition(); return Commands.sequence( V3_EpsilonCompositeCommands.intakeAlgaeFromReef( drive, superstructure, () -> ReefState.ALGAE_INTAKE_TOP), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 4a19ab59..3612a644 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -33,7 +33,7 @@ public enum V3_EpsilonSuperstructureStates { "GROUND_INTAKE", new SubsystemPoses( ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), - new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.CORAL_INTAKE)), + new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.CORAL_INTAKE)), L1( "L1", diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index fd6bcd98..fef578e7 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -44,7 +44,10 @@ public void periodic() { @AutoLogOutput(key = "Intake/Has Coral") public boolean hasCoral() { - return false; // Udpate later + return inputs.leftCANRangeDistanceMeters + > V3_EpsilonIntakeConstants.INTAKE_CAN_CORAL_DETECTED_THRESHOLD_METERS + && inputs.rightCANRangeDistanceMeters + > V3_EpsilonIntakeConstants.INTAKE_CAN_CORAL_DETECTED_THRESHOLD_METERS; } @AutoLogOutput(key = "Intake/At Goal") @@ -63,8 +66,12 @@ public void setPivotGoal(IntakePivotState goal) { this.pivotGoal = goal; } - public void setRollerVoltage(double volts) { - io.setRollerVoltage(volts); + public void setInnerRollerVoltage(double volts) { + io.setInnerRollerVoltage(volts); + } + + public void setOuterRollerVoltage(double volts) { + io.setOuterRollerVoltage(volts); } public void setPivotVoltage(double volts) { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index 1bacfd1c..f8453c4a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -8,7 +8,14 @@ public class V3_EpsilonIntakeConstants { public static final int PIVOT_CAN_ID; - public static final int ROLLER_CAN_ID; + public static final int ROLLER_CAN_ID_INNER; + public static final int ROLLER_CAN_ID_OUTER; + + public static final int LEFT_SENSOR_CAN_ID; + + public static final int RIGHT_SENSOR_CAN_ID; + + public static final double INTAKE_CAN_CORAL_DETECTED_THRESHOLD_METERS; public static final IntakeCurrentLimits CURRENT_LIMITS = new IntakeCurrentLimits(40.0, 40.0, 40.0, 40.0); @@ -30,7 +37,20 @@ public class V3_EpsilonIntakeConstants { static { PIVOT_CAN_ID = 60; - ROLLER_CAN_ID = 61; + ROLLER_CAN_ID_OUTER = + 61; // This used to be 61, but there are two motors, so I replace this with 42 until it gets + // sorted out fs + ROLLER_CAN_ID_INNER = 62; // This one I just created. + } + + static { + LEFT_SENSOR_CAN_ID = 0; // TODO: Check numbers here + RIGHT_SENSOR_CAN_ID = 1; + } + + static { + INTAKE_CAN_CORAL_DETECTED_THRESHOLD_METERS = + 42; // In meters= 42; TODO: Set value after robot built } @RequiredArgsConstructor @@ -72,20 +92,18 @@ public static record IntakeParems( // Will add more states later public static enum IntakeRollerState { - STOP(0.0), - CORAL_INTAKE(6.0), - ALGAE_INTAKE(12.0), - SCORE_CORAL(6.0), - OUTTAKE(10.0); - - private final double voltage; - - IntakeRollerState(double voltage) { - this.voltage = voltage; - } - - public double getVoltage() { - return voltage; + STOP(0.0, 0.0), + CORAL_INTAKE(6.0, 6.0), + ALGAE_INTAKE(12.0, 12.0), + SCORE_CORAL(6.0, 6.0), + OUTTAKE(10.0, 10.0); + + @Getter private final double innerVoltage; + @Getter private final double outerVoltage; + + IntakeRollerState(double innerVoltage, double outerVoltage) { + this.innerVoltage = innerVoltage; + this.outerVoltage = outerVoltage; } } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java index 9b37862b..3375045b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java @@ -17,12 +17,24 @@ public static class V3_EpsilonIntakeIOInputs { public Rotation2d pivotPositionSetpoint = new Rotation2d(); public Rotation2d pivotPositionError = new Rotation2d(); - public Rotation2d rollerPosition = new Rotation2d(); - public double rollerVelocityRadiansPerSecond = 0.0; - public double rollerAppliedVolts = 0.0; - public double rollerSupplyCurrentAmps = 0.0; - public double rollerTorqueCurrentAmps = 0.0; - public double rollerTemperatureCelsius = 0.0; + public Rotation2d rollerOuterPosition = new Rotation2d(); + public double rollerOuterVelocityRadiansPerSecond = 0.0; + public double rollerOuterAppliedVolts = 0.0; + public double rollerOuterSupplyCurrentAmps = 0.0; + public double rollerOuterTorqueCurrentAmps = 0.0; + public double rollerOuterTemperatureCelsius = 0.0; + + public Rotation2d rollerInnerPosition = new Rotation2d(); + public double rollerInnerVelocityRadiansPerSecond = 0.0; + public double rollerInnerAppliedVolts = 0.0; + public double rollerInnerSupplyCurrentAmps = 0.0; + public double rollerInnerTorqueCurrentAmps = 0.0; + public double rollerInnerTemperatureCelsius = 0.0; + + public double + leftCANRangeDistanceMeters; // Left and Right based on the robot's perspective with intake + // at the front + public double rightCANRangeDistanceMeters; } /** @@ -40,11 +52,18 @@ public default void updateInputs(V3_EpsilonIntakeIOInputs inputs) {} public default void setPivotVoltage(double volts) {} /** - * Sets the voltage for the manipulator. + * Sets the voltage for the inner manipulator roller. + * + * @param volts The voltage to set. + */ + public default void setInnerRollerVoltage(double volts) {} + + /** + * Sets the voltage for the outer manipulator roller. * * @param volts The voltage to set. */ - public default void setRollerVoltage(double volts) {} + public default void setOuterRollerVoltage(double volts) {} /** * Sets the position goal for the intake. diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java index c5d27afd..17026919 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java @@ -12,13 +12,15 @@ public class V3_EpsilonIntakeIOSim implements V3_EpsilonIntakeIO { private SingleJointedArmSim pivotMotorSim; - private DCMotorSim rollerMotorSim; + private DCMotorSim rollerInnerMotorSim; + private DCMotorSim rollerOuterMotorSim; private final ProfiledPIDController armFeedbackController; private final ArmFeedforward armFeedforwardController; private double pivotAppliedVoltage; - private double rollerAppliedVoltage; + private double rollerInnerAppliedVoltage; + private double rollerOuterAppliedVoltage; private boolean isClosedLoop; @@ -37,7 +39,15 @@ public V3_EpsilonIntakeIOSim() { true, V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getRadians()); - rollerMotorSim = + rollerInnerMotorSim = + new DCMotorSim( + LinearSystemId.createDCMotorSystem( + V3_EpsilonIntakeConstants.ROLLER_PARAMS.MOTOR(), + 0.04, + V3_EpsilonIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO()), + V3_EpsilonIntakeConstants.ROLLER_PARAMS.MOTOR()); + + rollerOuterMotorSim = new DCMotorSim( LinearSystemId.createDCMotorSystem( V3_EpsilonIntakeConstants.ROLLER_PARAMS.MOTOR(), @@ -61,7 +71,8 @@ public V3_EpsilonIntakeIOSim() { V3_EpsilonIntakeConstants.PIVOT_GAINS.kA()); pivotAppliedVoltage = 0.0; - rollerAppliedVoltage = 0.0; + rollerInnerAppliedVoltage = 0.0; + rollerOuterAppliedVoltage = 0.0; isClosedLoop = false; } @@ -75,13 +86,17 @@ public void updateInputs(V3_EpsilonIntakeIOInputs inputs) { } pivotAppliedVoltage = MathUtil.clamp(pivotAppliedVoltage, -12.0, 12.0); - rollerAppliedVoltage = MathUtil.clamp(rollerAppliedVoltage, -12.0, 12.0); + rollerInnerAppliedVoltage = MathUtil.clamp(rollerInnerAppliedVoltage, -12.0, 12.0); + rollerOuterAppliedVoltage = MathUtil.clamp(rollerOuterAppliedVoltage, -12.0, 12.0); pivotMotorSim.setInputVoltage(pivotAppliedVoltage); pivotMotorSim.update(Constants.LOOP_PERIOD_SECONDS); - rollerMotorSim.setInputVoltage(rollerAppliedVoltage); - rollerMotorSim.update(Constants.LOOP_PERIOD_SECONDS); + rollerInnerMotorSim.setInputVoltage(rollerInnerAppliedVoltage); + rollerInnerMotorSim.update(Constants.LOOP_PERIOD_SECONDS); + + rollerOuterMotorSim.setInputVoltage(rollerOuterAppliedVoltage); + rollerOuterMotorSim.update(Constants.LOOP_PERIOD_SECONDS); inputs.pivotPosition = new Rotation2d(pivotMotorSim.getAngleRads()); inputs.pivotVelocityRadiansPerSecond = pivotMotorSim.getVelocityRadPerSec(); @@ -92,10 +107,15 @@ public void updateInputs(V3_EpsilonIntakeIOInputs inputs) { inputs.pivotPositionSetpoint = new Rotation2d(armFeedbackController.getSetpoint().position); inputs.pivotPositionError = new Rotation2d(armFeedbackController.getPositionError()); - inputs.rollerPosition = new Rotation2d(rollerMotorSim.getAngularPosition()); - inputs.rollerVelocityRadiansPerSecond = rollerMotorSim.getAngularVelocityRadPerSec(); - inputs.rollerAppliedVolts = rollerAppliedVoltage; - inputs.rollerSupplyCurrentAmps = rollerMotorSim.getCurrentDrawAmps(); + inputs.rollerInnerPosition = new Rotation2d(rollerInnerMotorSim.getAngularPosition()); + inputs.rollerInnerVelocityRadiansPerSecond = rollerInnerMotorSim.getAngularVelocityRadPerSec(); + inputs.rollerInnerAppliedVolts = rollerInnerAppliedVoltage; + inputs.rollerInnerSupplyCurrentAmps = rollerInnerMotorSim.getCurrentDrawAmps(); + + inputs.rollerOuterPosition = new Rotation2d(rollerOuterMotorSim.getAngularPosition()); + inputs.rollerOuterVelocityRadiansPerSecond = rollerOuterMotorSim.getAngularVelocityRadPerSec(); + inputs.rollerOuterAppliedVolts = rollerOuterAppliedVoltage; + inputs.rollerOuterSupplyCurrentAmps = rollerOuterMotorSim.getCurrentDrawAmps(); } @Override @@ -105,8 +125,12 @@ public void setPivotVoltage(double voltage) { } @Override - public void setRollerVoltage(double voltage) { - rollerAppliedVoltage = voltage; + public void setInnerRollerVoltage(double voltage) { + rollerInnerAppliedVoltage = voltage; + } + + public void setOuterRollerVoltage(double voltage) { + rollerOuterAppliedVoltage = voltage; } @Override diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java index b9b0ef50..326b9353 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java @@ -10,6 +10,7 @@ import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.MotionMagicVoltage; import com.ctre.phoenix6.controls.VoltageOut; +import com.ctre.phoenix6.hardware.CANrange; import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.GravityTypeValue; import com.ctre.phoenix6.signals.InvertedValue; @@ -19,6 +20,7 @@ import edu.wpi.first.units.measure.AngularAcceleration; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Current; +import edu.wpi.first.units.measure.Distance; import edu.wpi.first.units.measure.Temperature; import edu.wpi.first.units.measure.Voltage; import frc.robot.util.PhoenixUtil; @@ -41,22 +43,42 @@ public class V3_EpsilonIntakeIOTalonFX implements V3_EpsilonIntakeIO { private final TalonFXConfiguration pivotConfig; - private final TalonFX rollerTalonFX; + private final TalonFX rollerTalonFXOuter; + private final TalonFX rollerTalonFXInner; - private final StatusSignal rollerPositionRotations; - private final StatusSignal rollerVelocityRotationsPerSecond; - private final StatusSignal rollerAppliedVoltage; - private final StatusSignal rollerSupplyCurrentAmps; - private final StatusSignal rollerTorqueCurrentAmps; - private final StatusSignal rollerTemperatureCelsius; + private final StatusSignal rollerInnerPositionRotations; + private final StatusSignal rollerInnerVelocityRotationsPerSecond; + private final StatusSignal rollerInnerAppliedVoltage; + private final StatusSignal rollerInnerSupplyCurrentAmps; + private final StatusSignal rollerInnerTorqueCurrentAmps; + private final StatusSignal rollerInnerTemperatureCelsius; - private final VoltageOut rollerVoltageRequest; + private final StatusSignal rollerOuterPositionRotations; + private final StatusSignal rollerOuterVelocityRotationsPerSecond; + private final StatusSignal rollerOuterAppliedVoltage; + private final StatusSignal rollerOuterSupplyCurrentAmps; + private final StatusSignal rollerOuterTorqueCurrentAmps; + private final StatusSignal rollerOuterTemperatureCelsius; - private final TalonFXConfiguration rollerConfig; + private final VoltageOut rollerInnerVoltageRequest; + private final VoltageOut rollerOuterVoltageRequest; + + private final TalonFXConfiguration rollerInnerConfig; + private final TalonFXConfiguration rollerOuterConfig; + + private final CANrange leftCANrange; + private final CANrange rightCANrange; + + private final StatusSignal leftCANrangeStatusSignal; + private final StatusSignal rightCANrangeStatusSignal; public V3_EpsilonIntakeIOTalonFX() { pivotTalonFX = new TalonFX(V3_EpsilonIntakeConstants.PIVOT_CAN_ID); - rollerTalonFX = new TalonFX(V3_EpsilonIntakeConstants.ROLLER_CAN_ID); + rollerTalonFXOuter = new TalonFX(V3_EpsilonIntakeConstants.ROLLER_CAN_ID_OUTER); + rollerTalonFXInner = new TalonFX(V3_EpsilonIntakeConstants.ROLLER_CAN_ID_INNER); + + leftCANrange = new CANrange(V3_EpsilonIntakeConstants.LEFT_SENSOR_CAN_ID); + rightCANrange = new CANrange(V3_EpsilonIntakeConstants.RIGHT_SENSOR_CAN_ID); pivotConfig = new TalonFXConfiguration(); pivotConfig.CurrentLimits.SupplyCurrentLimitEnable = true; @@ -109,32 +131,56 @@ public V3_EpsilonIntakeIOTalonFX() { pivotPositionSetpoint = pivotTalonFX.getClosedLoopReference(); pivotPositionError = pivotTalonFX.getClosedLoopError(); - rollerConfig = new TalonFXConfiguration(); - rollerConfig.CurrentLimits.SupplyCurrentLimitEnable = true; - rollerConfig.CurrentLimits.SupplyCurrentLimit = + leftCANrangeStatusSignal = leftCANrange.getDistance(); + rightCANrangeStatusSignal = rightCANrange.getDistance(); + + rollerInnerConfig = new TalonFXConfiguration(); + rollerInnerConfig.CurrentLimits.SupplyCurrentLimitEnable = true; + rollerInnerConfig.CurrentLimits.SupplyCurrentLimit = + V3_EpsilonIntakeConstants.CURRENT_LIMITS.ROLLER_SUPPLY_CURRENT_LIMIT(); + rollerInnerConfig.CurrentLimits.StatorCurrentLimitEnable = true; + rollerInnerConfig.CurrentLimits.StatorCurrentLimit = + V3_EpsilonIntakeConstants.CURRENT_LIMITS.ROLLER_STATOR_CURRENT_LIMIT(); + rollerInnerConfig.Feedback.SensorToMechanismRatio = + V3_EpsilonIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO(); + rollerInnerConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; + rollerInnerConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; + + rollerOuterConfig = new TalonFXConfiguration(); + rollerOuterConfig.CurrentLimits.SupplyCurrentLimitEnable = true; + rollerOuterConfig.CurrentLimits.SupplyCurrentLimit = V3_EpsilonIntakeConstants.CURRENT_LIMITS.ROLLER_SUPPLY_CURRENT_LIMIT(); - rollerConfig.CurrentLimits.StatorCurrentLimitEnable = true; - rollerConfig.CurrentLimits.StatorCurrentLimit = + rollerOuterConfig.CurrentLimits.StatorCurrentLimitEnable = true; + rollerOuterConfig.CurrentLimits.StatorCurrentLimit = V3_EpsilonIntakeConstants.CURRENT_LIMITS.ROLLER_STATOR_CURRENT_LIMIT(); - rollerConfig.Feedback.SensorToMechanismRatio = + rollerOuterConfig.Feedback.SensorToMechanismRatio = V3_EpsilonIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO(); - rollerConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; - rollerConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; + rollerOuterConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; + rollerOuterConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; - tryUntilOk(5, () -> rollerTalonFX.getConfigurator().apply(rollerConfig, 0.25)); + tryUntilOk(5, () -> rollerTalonFXOuter.getConfigurator().apply(rollerOuterConfig, 0.25)); + tryUntilOk(5, () -> rollerTalonFXInner.getConfigurator().apply(rollerInnerConfig, 0.25)); - rollerPositionRotations = pivotTalonFX.getPosition(); - rollerVelocityRotationsPerSecond = pivotTalonFX.getVelocity(); - rollerAppliedVoltage = pivotTalonFX.getSupplyVoltage(); - rollerSupplyCurrentAmps = pivotTalonFX.getSupplyCurrent(); - rollerTorqueCurrentAmps = pivotTalonFX.getTorqueCurrent(); - rollerTemperatureCelsius = pivotTalonFX.getDeviceTemp(); + rollerInnerPositionRotations = rollerTalonFXInner.getPosition(); + rollerInnerVelocityRotationsPerSecond = rollerTalonFXInner.getVelocity(); + rollerInnerAppliedVoltage = rollerTalonFXInner.getSupplyVoltage(); + rollerInnerSupplyCurrentAmps = rollerTalonFXInner.getSupplyCurrent(); + rollerInnerTorqueCurrentAmps = rollerTalonFXInner.getTorqueCurrent(); + rollerInnerTemperatureCelsius = rollerTalonFXInner.getDeviceTemp(); + + rollerOuterPositionRotations = rollerTalonFXOuter.getPosition(); + rollerOuterVelocityRotationsPerSecond = rollerTalonFXOuter.getVelocity(); + rollerOuterAppliedVoltage = rollerTalonFXOuter.getSupplyVoltage(); + rollerOuterSupplyCurrentAmps = rollerTalonFXOuter.getSupplyCurrent(); + rollerOuterTorqueCurrentAmps = rollerTalonFXOuter.getTorqueCurrent(); + rollerOuterTemperatureCelsius = rollerTalonFXOuter.getDeviceTemp(); pivotVoltageRequest = new VoltageOut(0); pivotMotionMagicRequest = new MotionMagicVoltage(V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getMeasure()); - rollerVoltageRequest = new VoltageOut(0); + rollerInnerVoltageRequest = new VoltageOut(0); + rollerOuterVoltageRequest = new VoltageOut(0); PhoenixUtil.registerSignals( false, @@ -144,12 +190,20 @@ public V3_EpsilonIntakeIOTalonFX() { pivotSupplyCurrentAmps, pivotTorqueCurrentAmps, pivotTemperatureCelsius, - rollerPositionRotations, - rollerVelocityRotationsPerSecond, - rollerAppliedVoltage, - rollerSupplyCurrentAmps, - rollerTorqueCurrentAmps, - rollerTemperatureCelsius); + rollerInnerPositionRotations, + rollerOuterPositionRotations, + rollerInnerVelocityRotationsPerSecond, + rollerOuterVelocityRotationsPerSecond, + rollerInnerAppliedVoltage, + rollerOuterAppliedVoltage, + rollerInnerSupplyCurrentAmps, + rollerOuterSupplyCurrentAmps, + rollerInnerTorqueCurrentAmps, + rollerOuterTorqueCurrentAmps, + rollerInnerTemperatureCelsius, + rollerOuterTemperatureCelsius, + leftCANrangeStatusSignal, + rightCANrangeStatusSignal); } @Override @@ -167,22 +221,37 @@ public void updateInputs(V3_EpsilonIntakeIOInputs inputs) { Rotation2d.fromRotations(pivotPositionSetpoint.getValueAsDouble()); inputs.pivotPositionError = Rotation2d.fromRotations(pivotPositionError.getValueAsDouble()); - inputs.rollerPosition = new Rotation2d(rollerPositionRotations.getValue()); - inputs.rollerVelocityRadiansPerSecond = - rollerVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); - inputs.rollerAppliedVolts = rollerAppliedVoltage.getValueAsDouble(); - inputs.rollerAppliedVolts = rollerAppliedVoltage.getValueAsDouble(); - inputs.rollerSupplyCurrentAmps = rollerSupplyCurrentAmps.getValueAsDouble(); - inputs.rollerTorqueCurrentAmps = rollerTorqueCurrentAmps.getValueAsDouble(); - inputs.rollerTemperatureCelsius = rollerTemperatureCelsius.getValueAsDouble(); + inputs.rollerInnerPosition = new Rotation2d(rollerInnerPositionRotations.getValue()); + inputs.rollerInnerVelocityRadiansPerSecond = + rollerInnerVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); + inputs.rollerInnerAppliedVolts = rollerInnerAppliedVoltage.getValueAsDouble(); + inputs.rollerInnerSupplyCurrentAmps = rollerInnerSupplyCurrentAmps.getValueAsDouble(); + inputs.rollerInnerTorqueCurrentAmps = rollerInnerTorqueCurrentAmps.getValueAsDouble(); + inputs.rollerInnerTemperatureCelsius = rollerInnerTemperatureCelsius.getValueAsDouble(); + + inputs.rollerOuterPosition = new Rotation2d(rollerOuterPositionRotations.getValue()); + inputs.rollerOuterVelocityRadiansPerSecond = + rollerOuterVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); + inputs.rollerOuterAppliedVolts = rollerOuterAppliedVoltage.getValueAsDouble(); + inputs.rollerOuterSupplyCurrentAmps = rollerOuterSupplyCurrentAmps.getValueAsDouble(); + inputs.rollerOuterTorqueCurrentAmps = rollerOuterTorqueCurrentAmps.getValueAsDouble(); + inputs.rollerOuterTemperatureCelsius = rollerOuterTemperatureCelsius.getValueAsDouble(); + + inputs.leftCANRangeDistanceMeters = leftCANrangeStatusSignal.getValueAsDouble(); + // result = condition ? true : false; + inputs.rightCANRangeDistanceMeters = rightCANrangeStatusSignal.getValueAsDouble(); } public void setPivotVoltage(double volts) { pivotTalonFX.setControl(pivotVoltageRequest.withOutput(volts).withEnableFOC(true)); } - public void setRollerVoltage(double volts) { - rollerTalonFX.setControl(rollerVoltageRequest.withOutput(volts).withEnableFOC(true)); + public void setInnerRollerVoltage(double volts) { + rollerTalonFXInner.setControl(rollerInnerVoltageRequest.withOutput(volts).withEnableFOC(true)); + } + + public void setOuterRollerVoltage(double volts) { + rollerTalonFXOuter.setControl(rollerOuterVoltageRequest.withOutput(volts).withEnableFOC(true)); } public void setPivotMotionMagic(Rotation2d position) { From 49de2add6f49dcb2e96edf67da372ea4766f380e Mon Sep 17 00:00:00 2001 From: Abhiraam Venigalla <134628455+Abhi52897340598327@users.noreply.github.com> Date: Thu, 11 Sep 2025 18:18:38 -0400 Subject: [PATCH 088/180] Feature v3 drive commands (#129) * completed command for intaking coral --> simulated it but has issues * robot changes * do not use timing in sim * Co-authored-by: Sriaditya Vaddadi Co-authored-by: Noah Proctor Co-authored-by: Joshi, Atharv * fix manipulator safety check * use positive for all manipulator arm states (useful when we later add ability to mirror) * arm side switching and add configs to talonFX implementation of manipulator * some small fixes * clear arm in most states when intake is in * reduce tolerance and correct arm length (with coral) * fixed a few transitions * fixed most collisions! * revert testing change * fix all states * Co-authored-by: CXu965 Co-authored-by: Kevin Reas Co-authored-by: Joshi, Atharv Co-authored-by: Anshu Co-authored-by: akg-022 * Co-authored-by: Joshi, Atharv Co-authored-by: Anshu Co-authored-by: Kevin Reas Co-authored-by: akg-022 Co-authored-by: CXu965 * Added comments for new optimalAutoAlignReefCoral * Started on autoAllignReefAlgae -- still need to simulate though * it should work theoretically (also ran sim and looked fine) * acually optimal now * continous updates during auto align (good if target face changes or we bump into smtn) * it should be runOnce else it breaks the setpoint * Refactor auto-alignment commands for scoring coral and algae; choose side for manipulator based on ScoreSide. * Resolved Pull Request comments. Co-authored-by: Anshu Co-authored-by: Seetha Raman, Abhiruph Co-authored-by: akg-022 Co-authored-by: Kevin Reas * build --------- Co-authored-by: Luke Maxwell <24lbmaxwell@protonmail.com> Co-authored-by: LordVanra Co-authored-by: Anshu Adiga Co-authored-by: Cxu965 Co-authored-by: Seetha Raman, Abhiruph Co-authored-by: akg-022 Co-authored-by: Kevin Reas --- src/main/java/frc/robot/RobotState.java | 63 +++++++++++++- .../frc/robot/commands/CompositeCommands.java | 82 +++++++++++++++++++ .../v3_Epsilon/V3_EpsilonRobotContainer.java | 37 +++++++-- .../V3_EpsilonSuperstructure.java | 5 +- .../intake/V3_EpsilonIntake.java | 1 + 5 files changed, 177 insertions(+), 11 deletions(-) diff --git a/src/main/java/frc/robot/RobotState.java b/src/main/java/frc/robot/RobotState.java index 2cc9567f..6bc60f9c 100644 --- a/src/main/java/frc/robot/RobotState.java +++ b/src/main/java/frc/robot/RobotState.java @@ -42,6 +42,7 @@ public class RobotState { @Getter @Setter private static RobotMode mode; @Getter @Setter private static boolean hasAlgae; + @Getter @Setter private static ScoreSide scoreSide; @Getter @Setter private static boolean isIntakingCoral; @Getter @Setter private static boolean isIntakingAlgae; @@ -73,6 +74,7 @@ public class RobotState { } OIData = new OperatorInputData(ReefPose.LEFT, ReefState.STOW); + scoreSide = ScoreSide.CENTER; robotHeading = new Rotation2d(); headingOffset = new Rotation2d(); @@ -139,15 +141,54 @@ public static void periodic( InternalLoggedTracer.record("Get Minimum Distance To Reef Tag", "RobotState/Periodic"); // if (RobotMode.disabled()) { - // resetRobotPose(getRobotPoseField()); + // resetRobotPose(getRobotPoseField()); // } InternalLoggedTracer.reset(); + + // Code will set the robot to the correct position based on the reef tag it is + // closest to for + // auto + // alignment to the reef to score coral + Pose2d autoAlignCoralSetpoint = OIData.currentReefHeight().equals(ReefState.L1) ? Reef.reefMap.get(closestReefTag).getPostSetpoint(ReefPose.CENTER) : Reef.reefMap.get(closestReefTag).getPostSetpoint(OIData.currentReefPost()); + if (scoreSide == ScoreSide.RIGHT) { + autoAlignCoralSetpoint = + new Pose2d( + autoAlignCoralSetpoint.getX(), + autoAlignCoralSetpoint.getY(), + autoAlignCoralSetpoint.getRotation().rotateBy(new Rotation2d(-Math.PI / 2))); + } else if (scoreSide == ScoreSide.LEFT) { + autoAlignCoralSetpoint = + new Pose2d( + autoAlignCoralSetpoint.getX(), + autoAlignCoralSetpoint.getY(), + autoAlignCoralSetpoint.getRotation().rotateBy(new Rotation2d(Math.PI / 2))); + } + + // @Author: Abhiraam Venigalla, Ananth Krishna Gomattam, Atharv Joshi, Chris Xu, + // Anshu Adiga, + // Adnan Dembele, Hartej Anand + // Code will rotate the robot if we need to score in a certain region + // Rotates the robot relative to the reef to the orientation desired + Pose2d autoAlignAlgaeSetpoint = Reef.reefMap.get(closestReefTag).getAlgaeSetpoint(); + if (scoreSide == ScoreSide.RIGHT) { + autoAlignAlgaeSetpoint = + new Pose2d( + autoAlignAlgaeSetpoint.getX(), + autoAlignAlgaeSetpoint.getY(), + autoAlignAlgaeSetpoint.getRotation().rotateBy(new Rotation2d(-Math.PI / 2))); + } else if (scoreSide == ScoreSide.LEFT) { + autoAlignAlgaeSetpoint = + new Pose2d( + autoAlignAlgaeSetpoint.getX(), + autoAlignAlgaeSetpoint.getY(), + autoAlignAlgaeSetpoint.getRotation().rotateBy(new Rotation2d(Math.PI / 2))); + } double distanceToCoralSetpoint = RobotState.getRobotPoseReef() @@ -160,10 +201,20 @@ public static void periodic( boolean atCoralSetpoint = Math.abs(distanceToCoralSetpoint) - <= DriveConstants.ALIGN_ROBOT_TO_APRIL_TAG_CONSTANTS.positionThresholdMeters().get(); + <= DriveConstants.ALIGN_ROBOT_TO_APRIL_TAG_CONSTANTS.positionThresholdMeters().get() + && Math.abs(autoAlignCoralSetpoint.getRotation().minus(robotHeading).getRadians()) + <= DriveConstants.ALIGN_ROBOT_TO_APRIL_TAG_CONSTANTS + .omegaPIDConstants() + .tolerance() + .get(); boolean atAlgaeSetpoint = Math.abs(distanceToAlgaeSetpoint) - <= DriveConstants.ALIGN_ROBOT_TO_APRIL_TAG_CONSTANTS.positionThresholdMeters().get(); + <= DriveConstants.ALIGN_ROBOT_TO_APRIL_TAG_CONSTANTS.positionThresholdMeters().get() + && Math.abs(autoAlignAlgaeSetpoint.getRotation().minus(robotHeading).getRadians()) + <= DriveConstants.ALIGN_ROBOT_TO_APRIL_TAG_CONSTANTS + .omegaPIDConstants() + .tolerance() + .get(); ReefState algaeHeight; switch (closestReefTag) { @@ -406,4 +457,10 @@ public static boolean auto() { return auto(RobotState.getMode()); } } + + public enum ScoreSide { + LEFT, + RIGHT, + CENTER + } } diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index a0f065cf..d9f0bfa2 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -1,13 +1,16 @@ package frc.robot.commands; +import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.kinematics.ChassisSpeeds; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; +import frc.robot.FieldConstants.Reef; import frc.robot.FieldConstants.Reef.ReefPose; import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotState; +import frc.robot.RobotState.ScoreSide; import frc.robot.subsystems.shared.climber.Climber; import frc.robot.subsystems.shared.climber.ClimberConstants; import frc.robot.subsystems.shared.drive.Drive; @@ -25,6 +28,7 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.util.AllianceFlipUtil; import java.util.function.BooleanSupplier; import java.util.function.Supplier; @@ -654,6 +658,84 @@ public static final Command homingSequences( public static final class V3_EpsilonCompositeCommands { + public static final Command intakeCoralDriverSequence( + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoalUntil( + V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoral()), + Commands.waitSeconds(0.2), + superstructure.runGoalUntil( + V3_EpsilonSuperstructureStates.HANDOFF, () -> manipulator.hasCoral())); + } + + /** + * Creates a command to automatically align the robot to the optimal side of the coral based on + * the current reef height and the robot's orientation. This command sets the score side in the + * RobotState and then runs the auto-alignment command. After the command ends, it resets the + * score side to center. + * + * @param drive The drive subsystem. + * @return A command to auto-align to the optimal side of the coral. + */ + public static final Command optimalAutoScoreCoralSequence( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + return Commands.sequence( + Commands.runOnce( + () -> { + if (RobotState.getOIData().currentReefHeight().equals(ReefState.L1)) { + RobotState.setScoreSide(ScoreSide.CENTER); + } else { + RobotState.setScoreSide( + optimalSide(RobotState.getReefAlignData().coralSetpoint())); + } + }) + .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), + superstructure.setPosition(), + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), + superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight())); + } + + public static final Command optimalAutoAlignReefAlgae( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + return Commands.sequence( + Commands.runOnce( + () -> { + int closestReefTag = RobotState.getReefAlignData().closestReefTag(); + if (closestReefTag != -1) { + Pose2d baseAlgaeSetpoint = + Reef.reefMap.get(closestReefTag).getAlgaeSetpoint(); + RobotState.setScoreSide(optimalSide(baseAlgaeSetpoint)); + } + }) + .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), + DriveCommands.autoAlignReefAlgae(drive, cameras)); + } + + private static final ScoreSide optimalSide(Pose2d baseSetpoint) { + if (Math.abs( + MathUtil.angleModulus( + baseSetpoint + .getRotation() + .rotateBy(Rotation2d.fromDegrees(-90)) + .minus(RobotState.getRobotPoseField().getRotation()) + .getRadians())) + <= Math.abs( + MathUtil.angleModulus( + baseSetpoint + .getRotation() + .rotateBy(Rotation2d.fromDegrees(90)) + .minus(RobotState.getRobotPoseField().getRotation()) + .getRadians()))) { + return ScoreSide.RIGHT; + } else { + return ScoreSide.LEFT; + } + } /** * Creates a command to score coral. * diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 47f70ac9..f969f5c0 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -3,12 +3,14 @@ import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; +import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.Constants; import frc.robot.Constants.Mode; -import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotContainer; import frc.robot.RobotState; +import frc.robot.commands.CompositeCommands; import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; +import frc.robot.commands.DriveCommands; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.drive.DriveConstants; import frc.robot.subsystems.shared.drive.GyroIO; @@ -43,6 +45,7 @@ public class V3_EpsilonRobotContainer implements RobotContainer { private V3_EpsilonSuperstructure superstructure; // Controller + CommandXboxController driver = new CommandXboxController(0); // Auto chooser @@ -102,9 +105,26 @@ public V3_EpsilonRobotContainer() { superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); } } + configureButtonBindings(); } - private void configureButtonBindings() {} + private void configureButtonBindings() { + drive.setDefaultCommand( + DriveCommands.joystickDrive( + drive, + () -> -driver.getLeftY(), + () -> -driver.getLeftX(), + () -> -driver.getRightX(), + () -> false, + driver.back(), + driver.povRight())); + driver + .rightTrigger() + .whileTrue( + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake, manipulator)) + .whileFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF)); + } private void configureAutos() {} @@ -128,11 +148,14 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { - // return superstructure.allTransition(); return Commands.sequence( - V3_EpsilonCompositeCommands.intakeAlgaeFromReef( - drive, superstructure, () -> ReefState.ALGAE_INTAKE_TOP), - Commands.waitSeconds(5), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure)); + // return superstructure.allTransition(); + // return Commands.sequence( + // V3_EpsilonCompositeCommands.intakeAlgaeFromReef( + // drive, superstructure, () -> ReefState.ALGAE_INTAKE_TOP), + // Commands.waitSeconds(5), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index c9d3c5b1..bf2023e4 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -7,12 +7,14 @@ import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotState; import frc.robot.RobotState.RobotMode; +import frc.robot.RobotState.ScoreSide; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.EdgeCommand; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.GamePieceEdge; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.Side; import frc.robot.util.NTPrefixes; import java.util.HashMap; import java.util.LinkedList; @@ -103,7 +105,8 @@ public V3_EpsilonSuperstructure( */ @Override public void periodic() { - + manipulator.setArmSide( + RobotState.getScoreSide().equals(ScoreSide.LEFT) ? Side.NEGATIVE : Side.POSITIVE); manipulator.setClearsElevator( elevator.getPositionMeters() > V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() * 1.1); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index fef578e7..41d9409b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -42,6 +42,7 @@ public void periodic() { } } + // Double check if this is right @AutoLogOutput(key = "Intake/Has Coral") public boolean hasCoral() { return inputs.leftCANRangeDistanceMeters From 9facbcd3e52b311ecd786e954afc80f6dc8dbb1f Mon Sep 17 00:00:00 2001 From: Katie Lam Date: Thu, 11 Sep 2025 18:58:45 -0400 Subject: [PATCH 089/180] fixed double rollers --- .../subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java | 2 -- .../v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java | 6 ++++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index f4ccd249..863f092b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -2,13 +2,11 @@ import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.Constants; import frc.robot.Constants.Mode; import frc.robot.RobotContainer; import frc.robot.RobotState; -import frc.robot.commands.CompositeCommands; import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; import frc.robot.commands.DriveCommands; import frc.robot.subsystems.shared.drive.Drive; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index c095baa5..90a6d8fd 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -94,9 +94,11 @@ public void setRollerGoal(IntakeRollerState rollerGoal) { V3_EpsilonIntakeConstants.IntakeRollerState.STOP) .contains(rollerGoal)) { - io.setRollerVoltage(0); + io.setInnerRollerVoltage(0); + io.setOuterRollerVoltage(0); } else { - io.setRollerVoltage(rollerGoal.getVoltage()); + io.setInnerRollerVoltage(rollerGoal.getInnerVoltage()); + io.setOuterRollerVoltage(rollerGoal.getOuterVoltage()); } } From ac2e6b2bd25aed8f556cd4d0e046924906c8bedb Mon Sep 17 00:00:00 2001 From: Adel B <150388135+Ade11edA@users.noreply.github.com> Date: Thu, 11 Sep 2025 19:44:10 -0400 Subject: [PATCH 090/180] V3 drop algae commands (#130) * Drop Algae Command c * drop algae command * Fixed more things * Fixed random states missing * Fixed random states missing --------- Co-authored-by: LordVanra Co-authored-by: Anshu --- .../frc/robot/commands/CompositeCommands.java | 47 ++++++++++++++++++- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 27 +++++++++-- .../superstructure/Superstructure.dot | 6 +++ .../V3_EpsilonSuperstructureStates.java | 10 ++++ 4 files changed, 86 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 6ed342de..4c147c09 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -761,6 +761,51 @@ public static final Command scoreCoral( /** * drive to reef go to algae level (L2 or L3) turn intake on go until it has algae then stow up */ + public static final Command dropAlgae( + Drive drive, + ElevatorFSM elevator, + V3_EpsilonManipulator manipulator, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Supplier level, + Camera... cameras) { + return Commands.sequence( + DriveCommands.autoAlignReefAlgae(drive, cameras), + Commands.sequence( + superstructure + .runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }) + .until(() -> RobotState.isHasAlgae()), + Commands.waitSeconds(2.0), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), + () -> drive.stop()) + .withTimeout(0.5)), + superstructure.runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE_DROP; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }), + Commands.waitSeconds(1.0), + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); + } + public static final Command intakeAlgaeFromReef( Drive drive, V3_EpsilonSuperstructure superstructure, Supplier level) { @@ -808,7 +853,7 @@ public static final Command intakeCoralFromGround( V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoral()), superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF)); } - + public static final Command emergencyEject( V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { return Commands.sequence( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 863f092b..c543f4e7 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -1,10 +1,14 @@ package frc.robot.subsystems.v3_Epsilon; +import edu.wpi.first.apriltag.AprilTagFieldLayout; +import edu.wpi.first.apriltag.AprilTagFields; import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.Constants; import frc.robot.Constants.Mode; +import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotContainer; import frc.robot.RobotState; import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; @@ -21,6 +25,8 @@ import frc.robot.subsystems.shared.elevator.ElevatorIO; import frc.robot.subsystems.shared.elevator.ElevatorIOSim; import frc.robot.subsystems.shared.elevator.ElevatorIOTalonFX; +import frc.robot.subsystems.shared.vision.Vision; +import frc.robot.subsystems.shared.vision.VisionConstants.RobotCameras; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; @@ -41,6 +47,7 @@ public class V3_EpsilonRobotContainer implements RobotContainer { private V3_EpsilonIntake intake; private V3_EpsilonManipulator manipulator; private V3_EpsilonSuperstructure superstructure; + private Vision vision; // Controller CommandXboxController driver = new CommandXboxController(0); @@ -63,6 +70,10 @@ public V3_EpsilonRobotContainer() { intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + vision = + new Vision( + () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), + RobotCameras.V2_REDUNDANCY_CAMS); break; case V3_EPSILON_SIM: drive = @@ -76,6 +87,8 @@ public V3_EpsilonRobotContainer() { intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + vision = + new Vision(() -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded)); break; default: break; @@ -103,7 +116,6 @@ public V3_EpsilonRobotContainer() { superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); } } - configureButtonBindings(); } private void configureButtonBindings() { @@ -133,7 +145,7 @@ public void robotPeriodic() { NetworkTablesJNI.now(), drive.getYawVelocity(), drive.getModulePositions(), - null); + vision.getCameras()); LTNUpdater.updateDrive(drive); LTNUpdater.updateElevator(elevator); @@ -146,6 +158,15 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { - return superstructure.allTransition(); + // return superstructure.allTransition(); + return Commands.sequence( + V3_EpsilonCompositeCommands.dropAlgae( + drive, + elevator, + manipulator, + intake, + superstructure, + () -> ReefState.ALGAE_INTAKE_TOP, + RobotCameras.V3_EPSILON_CAMS)); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index 53916bdd..a174a805 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -168,6 +168,9 @@ digraph Superstructure { L2_ALGAE -> L3_ALGAE [type = NO_ALGAE] L2_ALGAE -> PROCESSOR [type=UNCONSTRAINED] L2_ALGAE -> BARGE [type=UNCONSTRAINED] + L2_ALGAE -> L2_ALGAE_DROP + + L2_ALGAE_DROP -> L2_ALGAE L2_ALGAE_INTAKE -> STOW_UP [type=UNCONSTRAINED] L2_ALGAE_INTAKE -> L2_ALGAE [type=UNCONSTRAINED] @@ -184,6 +187,9 @@ digraph Superstructure { L3_ALGAE -> L3_ALGAE_INTAKE [type=UNCONSTRAINED] L3_ALGAE -> PROCESSOR [type=UNCONSTRAINED] L3_ALGAE -> BARGE [type=UNCONSTRAINED] + L3_ALGAE -> L3_ALGAE_DROP + + L3_ALGAE_DROP -> L3_ALGAE L3_ALGAE_INTAKE -> STOW_UP [type=UNCONSTRAINED] L3_ALGAE_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 70722675..f2e7e2ff 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -99,6 +99,11 @@ public enum V3_EpsilonSuperstructureStates { new SubsystemPoses( ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), SubsystemActions.empty()), + L2_ALGAE_DROP( + "L2_ALGAE_DROP", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.REMOVE_ALGAE, IntakeRollerState.STOP)), L2_ALGAE_INTAKE( "L2_ALGAE_INTAKE", new SubsystemPoses( @@ -110,6 +115,11 @@ public enum V3_EpsilonSuperstructureStates { new SubsystemPoses( ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), SubsystemActions.empty()), + L3_ALGAE_DROP( + "L3_ALGAE_DROP", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.REMOVE_ALGAE, IntakeRollerState.STOP)), L3_ALGAE_INTAKE( "L3_ALGAE_INTAKE", new SubsystemPoses( From cc714fc1bc24cd0f1e0815370845ed589f7e7102 Mon Sep 17 00:00:00 2001 From: ThatGuyRuchir <150929311+Ruchir-Kafle@users.noreply.github.com> Date: Thu, 11 Sep 2025 21:10:36 -0400 Subject: [PATCH 091/180] Changed auto aligning position of v3 to be a coral length further away to prevent clipping between manipulator arm and reef. (#133) Co-authored-by: Kevin Reas Co-authored-by: CXu965 Co-authored-by: Abhiraam Venigalla Co-authored-by: Anshu --- src/main/java/frc/robot/FieldConstants.java | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/FieldConstants.java b/src/main/java/frc/robot/FieldConstants.java index c29d49fa..07527847 100644 --- a/src/main/java/frc/robot/FieldConstants.java +++ b/src/main/java/frc/robot/FieldConstants.java @@ -14,7 +14,7 @@ public class FieldConstants { public static final double fieldLength = Units.inchesToMeters(690.876); public static final double fieldWidth = Units.inchesToMeters(317); public static final double startingLineX = - Units.inchesToMeters(299.438); // Measured from the inside of starting line + Units.inchesToMeters(299.438); // Measured from the inside of starting line sigma public static class Processor { public static final Pose2d centerFace = @@ -48,6 +48,8 @@ public static class CoralStation { } public static class Reef { + public static final double coralWidth = Units.inchesToMeters(4.5); + public static enum ReefPose { RIGHT, LEFT, @@ -132,8 +134,14 @@ public Pose2d getAlgaeSetpoint() { double adjustYBranch = Units.inchesToMeters(6.469); // Offset Y setpoint by center of tag to reef branch double adjustXBranch = - DriveConstants.DRIVE_CONFIG.bumperWidth() - / 2.0; // Offset X setpoint by center of robot to bumper + Constants.ROBOT.equals(Constants.RobotType.V3_EPSILON) + || Constants.ROBOT.equals(Constants.RobotType.V3_EPSILON_SIM) + ? (DriveConstants.DRIVE_CONFIG.bumperWidth() / 2.0) + + FieldConstants.Reef + .coralWidth // Offset X setpoint by center of robot to bumper + coral width + // sigma + : DriveConstants.DRIVE_CONFIG.bumperWidth() + / 2.0; // Offset X setpoint by center of robot to bumper // double adjustYAlgae = // Units.inchesToMeters(3.5); // Offset Y setpoint by center of tag to algae setpoint From c33a7065c68f7461359eba84ebe4210402f19c26 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Fri, 12 Sep 2025 09:53:36 -0400 Subject: [PATCH 092/180] run roller in periodic --- .../superstructure/intake/V3_EpsilonIntake.java | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index 90a6d8fd..f45d73ec 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -41,6 +41,9 @@ public void periodic() { if (isClosedLoop) { io.setPivotGoal(pivotGoal.getAngle()); } + + io.setInnerRollerVoltage(rollerGoal.getInnerVoltage()); + io.setOuterRollerVoltage(rollerGoal.getOuterVoltage()); } // Double check if this is right @@ -68,14 +71,6 @@ public void setPivotGoal(IntakePivotState goal) { this.pivotGoal = goal; } - public void setInnerRollerVoltage(double volts) { - io.setInnerRollerVoltage(volts); - } - - public void setOuterRollerVoltage(double volts) { - io.setOuterRollerVoltage(volts); - } - public void setPivotVoltage(double volts) { isClosedLoop = false; io.setPivotVoltage(volts); From 86e6a5a5a7950d22571fb018411df4557113fcab Mon Sep 17 00:00:00 2001 From: vaddadisri26 Date: Mon, 15 Sep 2025 18:11:22 -0400 Subject: [PATCH 093/180] Added processAlgae() composite command. --- .../java/frc/robot/commands/CompositeCommands.java | 13 +++++++++++++ .../v3_Epsilon/V3_EpsilonRobotContainer.java | 14 +++----------- 2 files changed, 16 insertions(+), 11 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 4c147c09..3cf9bdaf 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -880,5 +880,18 @@ public static final Command handoffCoral( Commands.waitUntil(() -> manipulator.hasCoral()), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)); } + + public static final Command processAlgae( + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR), + superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR_SCORE), + Commands.waitSeconds(3), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); + } + + // public static final Command climb() {} } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index c543f4e7..e64909c5 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -4,13 +4,12 @@ import edu.wpi.first.apriltag.AprilTagFields; import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.Constants; import frc.robot.Constants.Mode; -import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotContainer; import frc.robot.RobotState; +import frc.robot.commands.CompositeCommands; import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; import frc.robot.commands.DriveCommands; import frc.robot.subsystems.shared.drive.Drive; @@ -159,14 +158,7 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { // return superstructure.allTransition(); - return Commands.sequence( - V3_EpsilonCompositeCommands.dropAlgae( - drive, - elevator, - manipulator, - intake, - superstructure, - () -> ReefState.ALGAE_INTAKE_TOP, - RobotCameras.V3_EPSILON_CAMS)); + return CompositeCommands.V3_EpsilonCompositeCommands.processAlgae( + superstructure, intake, manipulator); } } From b865f71ce995707771b0d1cd0af115bfcbfab0f0 Mon Sep 17 00:00:00 2001 From: SeptimusHeap7 Date: Mon, 15 Sep 2025 18:43:35 -0400 Subject: [PATCH 094/180] Co-authored-by: Anshu Co-authored-by: Prabhudesai, Arnav Co-authored-by: Kevin Reas Co-authored-by: posydon Co-authored-by: Elliot Scher --- .../java/frc/robot/commands/CompositeCommands.java | 11 ++++++++++- .../robot/subsystems/shared/elevator/Elevator.java | 10 ++++++++++ .../robot/subsystems/shared/elevator/ElevatorIO.java | 1 + .../subsystems/shared/elevator/ElevatorIOSim.java | 6 +++++- .../subsystems/shared/elevator/ElevatorIOTalonFX.java | 8 ++++++++ .../v3_Epsilon/V3_EpsilonRobotContainer.java | 7 ++++++- .../superstructure/V3_EpsilonSuperstructureEdges.java | 8 ++++++++ .../V3_EpsilonSuperstructureStates.java | 2 +- 8 files changed, 49 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 6ed342de..7aa39d04 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -808,7 +808,7 @@ public static final Command intakeCoralFromGround( V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoral()), superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF)); } - + public static final Command emergencyEject( V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { return Commands.sequence( @@ -835,5 +835,14 @@ public static final Command handoffCoral( Commands.waitUntil(() -> manipulator.hasCoral()), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)); } + + public static final Command processScore( + V3_EpsilonSuperstructure superstructure, V3_EpsilonManipulator manipulator) { + return Commands.sequence( + Commands.runOnce( + () -> superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR_SCORE)), + Commands.waitUntil(() -> !manipulator.hasAlgae()).withTimeout(3), + Commands.runOnce(() -> superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); + } } } diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java index 895c4b16..e6547733 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java @@ -11,6 +11,8 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; +import frc.robot.Constants; +import frc.robot.Constants.Mode; import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotState; import frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions; @@ -303,6 +305,14 @@ public BooleanSupplier inFastScoringTolerance() { } public class ElevatorFSM { + public boolean pastBargeThresholdgetPositionMeters() { + if (Constants.getMode() == Mode.REAL) + return inputs.accelerationMetersPerSecondSquared < -0.01 + && inputs.velocityMetersPerSecond > 1; + else { + return inputs.positionMeters > .91; + } + } public void periodic() { ExternalLoggedTracer.reset(); diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorIO.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorIO.java index 83c7c9ff..b338dc0d 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorIO.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorIO.java @@ -7,6 +7,7 @@ public interface ElevatorIO { public static class ElevatorIOInputs { public double positionMeters = 0.0; public double velocityMetersPerSecond = 0.0; + public double accelerationMetersPerSecondSquared = 0.0; public double[] appliedVolts = {0.0, 0.0, 0.0, 0.0}; public double[] supplyCurrentAmps = {0.0, 0.0, 0.0, 0.0}; diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorIOSim.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorIOSim.java index 60099bf5..ef999615 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorIOSim.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorIOSim.java @@ -30,7 +30,6 @@ public ElevatorIOSim() { ElevatorConstants.ELEVATOR_PARAMETERS.MAX_HEIGHT_METERS(), true, ElevatorConstants.ELEVATOR_PARAMETERS.MIN_HEIGHT_METERS()); - feedback = new ProfiledPIDController( ElevatorConstants.GAINS.kP().get(), @@ -64,6 +63,7 @@ public void updateInputs(ElevatorIOInputs inputs) { // Position and velocity inputs.positionMeters = sim.getPositionMeters(); inputs.velocityMetersPerSecond = sim.getVelocityMetersPerSecond(); + inputs.accelerationMetersPerSecondSquared = 0; for (int i = 0; i < ElevatorConstants.ELEVATOR_PARAMETERS.NUM_MOTORS(); i++) { inputs.appliedVolts[i] = appliedVolts; @@ -104,4 +104,8 @@ public void updateGains(double kP, double kD, double kS, double kV, double kA, d public void updateConstraints(double maxAcceleration, double cruisingVelocity) { feedback.setConstraints(new Constraints(cruisingVelocity, maxAcceleration)); } + + public double getAcceleration(double previousVelocity, double currentVelocity) { + return (currentVelocity - previousVelocity) / 0.02; + } } diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorIOTalonFX.java index f2f12de4..d7399ba3 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorIOTalonFX.java @@ -10,6 +10,7 @@ import com.ctre.phoenix6.signals.GravityTypeValue; import com.ctre.phoenix6.signals.NeutralModeValue; import edu.wpi.first.units.measure.Angle; +import edu.wpi.first.units.measure.AngularAcceleration; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Current; import edu.wpi.first.units.measure.Temperature; @@ -30,6 +31,7 @@ public class ElevatorIOTalonFX implements ElevatorIO { // Sensor inputs private StatusSignal positionRotations; private StatusSignal velocityRotationsPerSecond; + private StatusSignal accelerationRotationsPerSecSq; private ArrayList> appliedVolts; private ArrayList> supplyCurrentAmps; private ArrayList> torqueCurrentAmps; @@ -109,6 +111,7 @@ public ElevatorIOTalonFX() { positionRotations = talonFX.getPosition(); velocityRotationsPerSecond = talonFX.getVelocity(); + accelerationRotationsPerSecSq = talonFX.getAcceleration(); appliedVolts.add(talonFX.getMotorVoltage()); supplyCurrentAmps.add(talonFX.getSupplyCurrent()); torqueCurrentAmps.add(talonFX.getTorqueCurrent()); @@ -169,6 +172,11 @@ public void updateInputs(ElevatorIOInputs inputs) { * Math.PI * ElevatorConstants.DRUM_RADIUS * 2; + inputs.accelerationMetersPerSecondSquared = + (accelerationRotationsPerSecSq.getValueAsDouble() / ElevatorConstants.ELEVATOR_GEAR_RATIO) + * Math.PI + * ElevatorConstants.DRUM_RADIUS + * 2; for (int i = 0; i < ElevatorConstants.ELEVATOR_PARAMETERS.NUM_MOTORS(); i++) { inputs.appliedVolts[i] = appliedVolts.get(i).getValueAsDouble(); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 863f092b..b35b9b2f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -2,6 +2,7 @@ import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.Constants; import frc.robot.Constants.Mode; @@ -146,6 +147,10 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { - return superstructure.allTransition(); + return superstructure + .runGoal(V3_EpsilonSuperstructureStates.BARGE) + .andThen( + Commands.waitSeconds(2), + superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE_SCORE)); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index dd2714ee..cd25a719 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -261,6 +261,14 @@ else if (willCollide(from, to)) { } } + if (to.equals(V3_EpsilonSuperstructureStates.BARGE_SCORE)) { + return Commands.sequence( + moveCommand, + Commands.race( + Commands.waitUntil(() -> elevator.pastBargeThresholdgetPositionMeters()), + waitForPoseCommand(to, elevator, intake, manipulator))); + } + // THE CRITICAL FIX: // No matter how we start the move, we append a final wait condition. // This ensures the command doesn't end until the robot is physically at the diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 70722675..d5cdfa42 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -128,7 +128,7 @@ public enum V3_EpsilonSuperstructureStates { BARGE( "BARGE", new SubsystemPoses( - ReefState.ALGAE_SCORE, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), + ReefState.HIGH_STOW, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), SubsystemActions.empty()), BARGE_SCORE( "BARGE_SCORE", From dfd36f3b3669f59bcbf5ed756a2cf54ef3d20cf3 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Mon, 15 Sep 2025 18:59:39 -0400 Subject: [PATCH 095/180] Worked on 3-piece auto --- src/main/deploy/choreo/E_LEFT_PATH_1.traj | 66 + src/main/deploy/choreo/E_LEFT_PATH_2.traj | 72 + src/main/deploy/choreo/E_LEFT_PATH_3.traj | 64 + src/main/deploy/choreo/E_LEFT_PATH_4.traj | 66 + src/main/deploy/choreo/E_LEFT_PATH_5.traj | 65 + .../robot/commands/AutonomousCommands.java | 1526 +++++++++-------- .../frc/robot/commands/CompositeCommands.java | 22 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 6 +- .../V3_EpsilonManipulatorConstants.java | 3 +- 9 files changed, 1162 insertions(+), 728 deletions(-) create mode 100644 src/main/deploy/choreo/E_LEFT_PATH_1.traj create mode 100644 src/main/deploy/choreo/E_LEFT_PATH_2.traj create mode 100644 src/main/deploy/choreo/E_LEFT_PATH_3.traj create mode 100644 src/main/deploy/choreo/E_LEFT_PATH_4.traj create mode 100644 src/main/deploy/choreo/E_LEFT_PATH_5.traj diff --git a/src/main/deploy/choreo/E_LEFT_PATH_1.traj b/src/main/deploy/choreo/E_LEFT_PATH_1.traj new file mode 100644 index 00000000..501b2e9b --- /dev/null +++ b/src/main/deploy/choreo/E_LEFT_PATH_1.traj @@ -0,0 +1,66 @@ +{ + "name":"E_LEFT_PATH_1", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.084641456604004, "y":1.5642421245574951, "heading":3.120762363350457, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":5.376737594604492, "y":2.6473031044006348, "heading":-2.5588534684945525, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"7.084641456604004 m", "val":7.084641456604004}, "y":{"exp":"1.5642421245574951 m", "val":1.5642421245574951}, "heading":{"exp":"3.120762363350457 rad", "val":3.120762363350457}, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"5.376737594604492 m", "val":5.376737594604492}, "y":{"exp":"2.6473031044006348 m", "val":2.6473031044006348}, "heading":{"exp":"-2.5588534684945525 rad", "val":-2.5588534684945525}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.12324], + "samples":[ + {"t":0.0, "x":7.08464, "y":1.56424, "heading":3.12076, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.42556, "ay":3.43998, "alpha":1.93869, "fx":[-94.68646,-84.29752,-91.02993,-99.13511], "fy":[55.42934,70.25083,61.30695,47.06539]}, + {"t":0.03623, "x":7.08108, "y":1.5665, "heading":3.12076, "vx":-0.19659, "vy":0.12464, "omega":0.07025, "ax":-5.42516, "ay":3.43973, "alpha":1.93667, "fx":[-94.67523,-84.30019,-91.02486,-99.1215], "fy":[55.42824,70.23327,61.30018,47.07389]}, + {"t":0.07247, "x":7.0704, "y":1.57327, "heading":3.12331, "vx":-0.39316, "vy":0.24928, "omega":0.14042, "ax":-5.4247, "ay":3.43945, "alpha":1.93415, "fx":[-94.64207,-84.30082,-91.0366,-99.11096], "fy":[55.46142,70.21602,61.26625,47.07271]}, + {"t":0.1087, "x":7.05259, "y":1.58456, "heading":3.1284, "vx":-0.58972, "vy":0.3739, "omega":0.2105, "ax":-5.42417, "ay":3.43913, "alpha":1.93105, "fx":[-94.58658,-84.29972,-91.06486,-99.10283], "fy":[55.52869,70.19818,61.20497,47.06243]}, + {"t":0.14493, "x":7.02766, "y":1.60037, "heading":3.13602, "vx":-0.78626, "vy":0.49851, "omega":0.28047, "ax":-5.42353, "ay":3.43875, "alpha":1.92727, "fx":[-94.50816,-84.29738,-91.10924,-99.09614], "fy":[55.62982,70.17842,61.1161,47.04401]}, + {"t":0.18117, "x":6.99561, "y":1.62069, "heading":-3.137, "vx":-0.98277, "vy":0.62311, "omega":0.3503, "ax":-5.42277, "ay":3.43829, "alpha":1.9227, "fx":[-94.40594,-84.29456,-91.16919,-99.08953], "fy":[55.7645,70.15483,60.99923,47.0188]}, + {"t":0.2174, "x":6.95644, "y":1.64552, "heading":-3.12431, "vx":-1.17926, "vy":0.74769, "omega":0.41997, "ax":-5.42184, "ay":3.43773, "alpha":1.91714, "fx":[-94.27873,-84.29221,-91.2439,-99.08104], "fy":[55.93225,70.12475,60.85384,46.98863]}, + {"t":0.25364, "x":6.91015, "y":1.67487, "heading":-3.10909, "vx":-1.37571, "vy":0.87226, "omega":0.48943, "ax":-5.42067, "ay":3.43704, "alpha":1.91032, "fx":[-94.12484,-84.29156,-91.33217,-99.06791], "fy":[56.13226,70.0845,60.67916,46.95604]}, + {"t":0.28987, "x":6.85675, "y":1.70873, "heading":-3.09136, "vx":-1.57212, "vy":0.99679, "omega":0.55865, "ax":-5.41917, "ay":3.43613, "alpha":1.90183, "fx":[-93.94178,-84.29411,-91.43212,-99.046], "fy":[56.36312,70.02877,60.47406,46.92449]}, + {"t":0.3261, "x":6.79623, "y":1.74711, "heading":-3.07111, "vx":-1.76848, "vy":1.1213, "omega":0.62756, "ax":-5.41715, "ay":3.43491, "alpha":1.89096, "fx":[-93.7257,-84.30167,-91.54066,-99.0088], "fy":[56.62237,69.94953,60.23678,46.89899]}, + {"t":0.36234, "x":6.72859, "y":1.78999, "heading":-3.04838, "vx":-1.96476, "vy":1.24576, "omega":0.69608, "ax":-5.41432, "ay":3.43319, "alpha":1.87648, "fx":[-93.46998,-84.31636,-91.65226,-98.94523], "fy":[56.90542,69.83361,59.96423,46.88713]}, + {"t":0.39857, "x":6.65385, "y":1.83738, "heading":-3.02315, "vx":-2.16094, "vy":1.37015, "omega":0.76407, "ax":-5.41004, "ay":3.43057, "alpha":1.85601, "fx":[-93.16188,-84.34056,-91.75599,-98.83424], "fy":[57.20304,69.65693,59.65037,46.90168]}, + {"t":0.4348, "x":6.572, "y":1.88928, "heading":-2.99547, "vx":-2.35697, "vy":1.49445, "omega":0.83132, "ax":-5.40285, "ay":3.42613, "alpha":1.82429, "fx":[-92.77228,-84.37581,-91.82658,-98.62917], "fy":[57.49404,69.36783,59.28112,46.96702]}, + {"t":0.47104, "x":6.48305, "y":1.94568, "heading":-2.96535, "vx":-2.55273, "vy":1.6186, "omega":0.89742, "ax":-5.38833, "ay":3.41709, "alpha":1.76713, "fx":[-92.21464,-84.41498,-91.78861,-98.19729], "fy":[57.71657,68.82486,58.8136,47.13963]}, + {"t":0.50727, "x":6.38702, "y":2.00657, "heading":-2.93283, "vx":-2.74797, "vy":1.74241, "omega":0.96145, "ax":-5.34391, "ay":3.38926, "alpha":1.62763, "fx":[-91.05953,-84.34265,-91.26477,-96.92635], "fy":[57.57387,67.41338,58.02736,47.58704]}, + {"t":0.54351, "x":6.28394, "y":2.07193, "heading":-2.89799, "vx":-2.9416, "vy":1.86522, "omega":1.02042, "ax":0.00588, "ay":0.0076, "alpha":0.05008, "fx":[0.25761,0.1949,-0.05743,0.00528], "fy":[0.03451,0.28683,0.22412,-0.0282]}, + {"t":0.57974, "x":6.17736, "y":2.13952, "heading":-2.86102, "vx":-2.94139, "vy":1.86549, "omega":1.02224, "ax":5.34415, "ay":-3.38899, "alpha":-1.62515, "fx":[90.55472,84.4405,91.6758,96.93894], "fy":[-58.36632,-67.31367,-57.37464,-47.52808]}, + {"t":0.61597, "x":6.07429, "y":2.20489, "heading":-2.82398, "vx":-2.74775, "vy":1.7427, "omega":0.96335, "ax":5.38834, "ay":-3.41711, "alpha":-1.7663, "fx":[91.10259,84.60112,92.66175,98.25119], "fy":[-59.45772,-68.62023,-57.42737,-46.99091]}, + {"t":0.65221, "x":5.97827, "y":2.26579, "heading":-2.78907, "vx":-2.55251, "vy":1.61888, "omega":0.89935, "ax":5.40274, "ay":-3.42632, "alpha":-1.82443, "fx":[91.08177,84.65445,93.13911,98.72079], "fy":[-60.13765,-69.0518,-57.19611,-46.73743]}, + {"t":0.68844, "x":5.88933, "y":2.3222, "heading":-2.75649, "vx":-2.35675, "vy":1.49473, "omega":0.83325, "ax":5.40982, "ay":-3.43089, "alpha":-1.85699, "fx":[90.93259,84.70911,93.47731,98.959], "fy":[-60.68574,-69.23213,-56.91428,-46.60158]}, + {"t":0.72467, "x":5.80748, "y":2.3741, "heading":-2.7263, "vx":-2.16073, "vy":1.37042, "omega":0.76596, "ax":5.41401, "ay":-3.43361, "alpha":-1.87824, "fx":[90.74527,84.77036,93.74943,99.09831], "fy":[-61.1583,-69.30504,-56.62865,-46.52721]}, + {"t":0.76091, "x":5.73275, "y":2.42151, "heading":-2.69854, "vx":-1.96456, "vy":1.24601, "omega":0.69791, "ax":5.41678, "ay":-3.43542, "alpha":-1.89345, "fx":[90.55045,84.8358,93.97975,99.18546], "fy":[-61.57433,-69.32327,-56.35495,-46.48974]}, + {"t":0.79714, "x":5.66512, "y":2.4644, "heading":-2.67325, "vx":-1.76829, "vy":1.12153, "omega":0.6293, "ax":5.41873, "ay":-3.43671, "alpha":-1.905, "fx":[90.36145,84.90259,94.17881,99.24166], "fy":[-61.94237,-69.31153,-56.09999,-46.47593]}, + {"t":0.83337, "x":5.6046, "y":2.50278, "heading":-2.65045, "vx":-1.57195, "vy":0.997, "omega":0.56028, "ax":5.42019, "ay":-3.43767, "alpha":-1.91414, "fx":[90.18493,84.96831,94.35197,99.27827], "fy":[-62.26705,-69.28338,-55.86716,-46.47753]}, + {"t":0.86961, "x":5.5512, "y":2.53665, "heading":-2.63015, "vx":-1.37556, "vy":0.87244, "omega":0.49092, "ax":5.42131, "ay":-3.43841, "alpha":-1.92155, "fx":[90.02456,85.03098,94.50236,99.30209], "fy":[-62.55133,-69.24713,-55.65833,-46.48882]}, + {"t":0.90584, "x":5.50492, "y":2.566, "heading":-2.61236, "vx":-1.17912, "vy":0.74786, "omega":0.42129, "ax":5.42221, "ay":-3.439, "alpha":-1.92766, "fx":[89.88245,85.08895,94.63196,99.31761], "fy":[-62.79732,-69.20835,-55.47455,-46.50556]}, + {"t":0.94208, "x":5.46576, "y":2.59084, "heading":-2.5971, "vx":-0.98266, "vy":0.62325, "omega":0.35145, "ax":5.42294, "ay":-3.43948, "alpha":-1.93275, "fx":[89.75985,85.14088,94.7421,99.32792], "fy":[-63.00663,-69.17094,-55.31646,-46.52447]}, + {"t":0.97831, "x":5.43371, "y":2.61117, "heading":-2.58436, "vx":-0.78616, "vy":0.49863, "omega":0.28142, "ax":5.42355, "ay":-3.43988, "alpha":-1.93699, "fx":[89.65753,85.18569,94.83375,99.3353], "fy":[-63.18054,-69.13776,-55.18444,-46.54292]}, + {"t":1.01454, "x":5.40879, "y":2.62698, "heading":-2.57417, "vx":-0.58965, "vy":0.37399, "omega":0.21123, "ax":5.42407, "ay":-3.44022, "alpha":-1.94052, "fx":[89.57595,85.22248,94.90763,99.34145], "fy":[-63.3201,-69.11095,-55.07871,-46.55885]}, + {"t":1.05078, "x":5.39098, "y":2.63827, "heading":-2.56651, "vx":-0.39311, "vy":0.24933, "omega":0.14092, "ax":5.42452, "ay":-3.44051, "alpha":-1.94343, "fx":[89.51541,85.25059,94.96425,99.34764], "fy":[-63.42612,-69.09213,-54.99942,-46.57064]}, + {"t":1.08701, "x":5.3803, "y":2.64504, "heading":-2.56141, "vx":-0.19656, "vy":0.12467, "omega":0.0705, "ax":5.42491, "ay":-3.44076, "alpha":-1.9458, "fx":[89.47611,85.26948,95.00402,99.35483], "fy":[-63.49924,-69.08249,-54.94665,-46.57707]}, + {"t":1.12324, "x":5.37674, "y":2.6473, "heading":-2.55885, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_LEFT_PATH_2.traj b/src/main/deploy/choreo/E_LEFT_PATH_2.traj new file mode 100644 index 00000000..942de388 --- /dev/null +++ b/src/main/deploy/choreo/E_LEFT_PATH_2.traj @@ -0,0 +1,72 @@ +{ + "name":"E_LEFT_PATH_2", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":5.348966598510742, "y":2.7028448581695557, "heading":-2.5111212813673753, "intervals":37, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.0581276416778564, "y":2.202970504760742, "heading":-3.0828368900825525, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"5.348966598510742 m", "val":5.348966598510742}, "y":{"exp":"2.7028448581695557 m", "val":2.7028448581695557}, "heading":{"exp":"-2.5111212813673753 rad", "val":-2.5111212813673753}, "intervals":37, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.0581276416778564 m", "val":2.0581276416778564}, "y":{"exp":"2.202970504760742 m", "val":2.202970504760742}, "heading":{"exp":"-3.0828368900825525 rad", "val":-3.0828368900825525}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.45697], + "samples":[ + {"t":0.0, "x":5.34897, "y":2.70284, "heading":-2.51112, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.35198, "ay":-0.96328, "alpha":-1.94512, "fx":[-109.02528,-105.79351,-107.64778,-109.71517], "fy":[-12.66193,-29.20409,-21.2697,-2.40456]}, + {"t":0.03938, "x":5.34404, "y":2.7021, "heading":-2.51112, "vx":-0.25013, "vy":-0.03793, "omega":-0.07659, "ax":-6.35236, "ay":-0.96338, "alpha":-1.91377, "fx":[-109.01122,-105.83876,-107.65589,-109.70119], "fy":[-12.71689,-29.00918,-21.18109,-2.64026]}, + {"t":0.07876, "x":5.32927, "y":2.69986, "heading":-2.51414, "vx":-0.50027, "vy":-0.07587, "omega":-0.15195, "ax":-6.35276, "ay":-0.9635, "alpha":-1.87782, "fx":[-108.99904,-105.89488,-107.65657,-109.68418], "fy":[-12.745,-28.76822,-21.12291,-2.91957]}, + {"t":0.11813, "x":5.30464, "y":2.69612, "heading":-2.52012, "vx":-0.75042, "vy":-0.11381, "omega":-0.2259, "ax":-6.35321, "ay":-0.96365, "alpha":-1.83602, "fx":[-108.98785,-105.963,-107.65099,-109.6632], "fy":[-12.75132,-28.47462,-21.08786,-3.25155]}, + {"t":0.15751, "x":5.27017, "y":2.69089, "heading":-2.52902, "vx":-1.00059, "vy":-0.15175, "omega":-0.2982, "ax":-6.3537, "ay":-0.96381, "alpha":-1.78663, "fx":[-108.97642,-106.04466,-107.64062,-109.6369], "fy":[-12.74267,-28.11907,-21.06618,-3.64871]}, + {"t":0.19689, "x":5.22584, "y":2.68417, "heading":-2.54076, "vx":-1.25079, "vy":-0.18971, "omega":-0.36855, "ax":-6.35425, "ay":-0.96401, "alpha":-1.72728, "fx":[-108.96301,-106.14203,-107.6274,-109.60327], "fy":[-12.72848,-27.68834,-21.04474,-4.1284]}, + {"t":0.23627, "x":5.17166, "y":2.67595, "heading":-2.55527, "vx":-1.501, "vy":-0.22767, "omega":-0.43656, "ax":-6.35485, "ay":-0.96424, "alpha":-1.65448, "fx":[-108.94515,-106.25814,-107.614,-109.55924], "fy":[-12.72218,-27.16322,-21.0053,-4.71518]}, + {"t":0.27564, "x":5.10763, "y":2.66624, "heading":-2.57246, "vx":-1.75124, "vy":-0.26564, "omega":-0.50171, "ax":-6.35549, "ay":-0.96453, "alpha":-1.56306, "fx":[-108.91909,-106.39734,-107.60415,-109.49995], "fy":[-12.74374,-26.51472,-20.92182,-5.44496]}, + {"t":0.31502, "x":5.03374, "y":2.65503, "heading":-2.59222, "vx":-2.0015, "vy":-0.30362, "omega":-0.56326, "ax":-6.35615, "ay":-0.96488, "alpha":-1.44488, "fx":[-108.87888,-106.56612,-107.60319,-109.4172], "fy":[-12.8244,-25.69698,-20.75536,-6.37247]}, + {"t":0.3544, "x":4.95, "y":2.64233, "heading":-2.6144, "vx":-2.25179, "vy":-0.34161, "omega":-0.62016, "ax":-6.35672, "ay":-0.96532, "alpha":-1.28639, "fx":[-108.81429,-106.77454,-107.61911,-109.29629], "fy":[-13.01636,-24.63252,-20.44441,-7.58618]}, + {"t":0.39378, "x":4.8564, "y":2.62813, "heading":-2.63882, "vx":-2.50211, "vy":-0.37962, "omega":-0.67081, "ax":-6.35692, "ay":-0.96589, "alpha":-1.06325, "fx":[-108.70576,-107.03897,-107.66414,-109.10841], "fy":[-13.41493,-23.17861,-19.88444,-9.24003]}, + {"t":0.43315, "x":4.75295, "y":2.61243, "heading":-2.66523, "vx":-2.75243, "vy":-0.41766, "omega":-0.71268, "ax":-6.35585, "ay":-0.96659, "alpha":-0.72675, "fx":[-108.51006,-107.38703,-107.75764,-108.78978], "fy":[-14.21673,-21.0393,-18.87943,-11.63011]}, + {"t":0.47253, "x":4.63964, "y":2.59524, "heading":-2.6933, "vx":-3.0027, "vy":-0.45572, "omega":-0.7413, "ax":-6.35038, "ay":-0.96726, "alpha":-0.16257, "fx":[-108.10865,-107.8624,-107.92964,-108.17207], "fy":[-15.90872,-17.48427,-17.00812,-15.41048]}, + {"t":0.51191, "x":4.51647, "y":2.57654, "heading":-2.72249, "vx":-3.25276, "vy":-0.49381, "omega":-0.7477, "ax":-6.32529, "ay":-0.96656, "alpha":0.98037, "fx":[-107.02718,-108.45923,-108.20987,-106.6695], "fy":[-20.13408,-10.11251,-13.15773,-22.35904]}, + {"t":0.55129, "x":4.38348, "y":2.55635, "heading":-2.75193, "vx":-3.50184, "vy":-0.53187, "omega":-0.7091, "ax":-6.12005, "ay":-0.95661, "alpha":4.67736, "fx":[-100.49665,-106.65948,-108.33415,-100.91085], "fy":[-37.90019,15.22165,-3.14796,-39.26016]}, + {"t":0.59066, "x":4.24084, "y":2.53466, "heading":-2.77985, "vx":-3.74283, "vy":-0.56954, "omega":-0.52491, "ax":-4.55043, "ay":-0.81413, "alpha":13.23792, "fx":[-48.34701,-73.6012,-101.80637,-85.85153], "fy":[-73.51748,61.60476,11.04017,-54.51971]}, + {"t":0.63004, "x":4.08993, "y":2.5116, "heading":-2.80052, "vx":-3.92202, "vy":-0.6016, "omega":-0.00364, "ax":-0.04133, "ay":0.13987, "alpha":0.05126, "fx":[-0.5331,-0.62211,-0.87302,-0.78405], "fy":[2.29841,2.54909,2.46005,2.20935]}, + {"t":0.66942, "x":3.93546, "y":2.48802, "heading":-2.80067, "vx":-3.92364, "vy":-0.59609, "omega":-0.00162, "ax":-0.00542, "ay":0.03566, "alpha":0.00002, "fx":[-0.09214,-0.09218,-0.0923,-0.09226], "fy":[0.60645,0.60656,0.60652,0.60641]}, + {"t":0.7088, "x":3.78095, "y":2.46458, "heading":-2.80073, "vx":-3.92386, "vy":-0.59468, "omega":-0.00162, "ax":-0.00018, "ay":0.0012, "alpha":0.0, "fx":[-0.0031,-0.0031,-0.0031,-0.0031], "fy":[0.02043,0.02043,0.02043,0.02043]}, + {"t":0.74817, "x":3.62644, "y":2.44116, "heading":-2.80079, "vx":-3.92386, "vy":-0.59464, "omega":-0.00162, "ax":0.00468, "ay":-0.0308, "alpha":-0.00002, "fx":[0.07959,0.07963,0.07973,0.07969], "fy":[-0.5239,-0.524,-0.52397,-0.52386]}, + {"t":0.78755, "x":3.47193, "y":2.41772, "heading":-2.80086, "vx":-3.92368, "vy":-0.59585, "omega":-0.00162, "ax":0.03733, "ay":-0.12289, "alpha":-0.04753, "fx":[0.47742,0.55987,0.79252,0.7101], "fy":[-2.01537,-2.24786,-2.16537,-1.93287]}, + {"t":0.82693, "x":3.31746, "y":2.39416, "heading":-2.80092, "vx":-3.92221, "vy":-0.60069, "omega":-0.00349, "ax":4.51366, "ay":0.79224, "alpha":-13.27529, "fx":[47.44047,72.48004,101.26907,85.91498], "fy":[73.48903,-61.37315,-11.87098,53.65821]}, + {"t":0.86631, "x":3.16651, "y":2.37113, "heading":-2.80106, "vx":-3.74447, "vy":-0.56949, "omega":-0.52624, "ax":6.14585, "ay":0.95615, "alpha":-4.28031, "fx":[100.95334,107.0891,108.30852,101.80564], "fy":[36.94067,-11.75394,3.00643,36.86225]}, + {"t":0.90568, "x":3.02383, "y":2.34944, "heading":-2.82178, "vx":-3.50246, "vy":-0.53184, "omega":-0.69479, "ax":6.32696, "ay":0.96703, "alpha":-0.85699, "fx":[107.03052,108.34714,108.21534,106.88637], "fy":[20.18004,11.25359,13.05576,21.30649]}, + {"t":0.94506, "x":2.89081, "y":2.32925, "heading":-2.84914, "vx":-3.25332, "vy":-0.49376, "omega":-0.72853, "ax":6.35029, "ay":0.96741, "alpha":0.20417, "fx":[108.1578,107.84204,107.87522,108.19131], "fy":[15.58109,17.62475,17.34924,15.26633]}, + {"t":0.98444, "x":2.76763, "y":2.31056, "heading":-2.87783, "vx":-3.00327, "vy":-0.45567, "omega":-0.72049, "ax":6.35583, "ay":0.9667, "alpha":0.72915, "fx":[108.62559,107.50725,107.5865,108.72391], "fy":[13.29071,20.43719,19.84852,12.19663]}, + {"t":1.02382, "x":2.6543, "y":2.29336, "heading":-2.9062, "vx":-2.75299, "vy":-0.4176, "omega":-0.69178, "ax":6.35722, "ay":0.966, "alpha":1.04377, "fx":[108.88606,107.30638,107.34844,108.99723], "fy":[11.83387,21.93178,21.54884,10.41077]}, + {"t":1.06319, "x":2.55082, "y":2.27767, "heading":-2.93344, "vx":-2.50266, "vy":-0.37956, "omega":-0.65068, "ax":6.35735, "ay":0.96541, "alpha":1.25374, "fx":[109.05468,107.18618,107.14815,109.15762], "fy":[10.78027,22.80124,22.81349,9.29036]}, + {"t":1.10257, "x":2.4572, "y":2.26347, "heading":-2.95906, "vx":-2.25232, "vy":-0.34155, "omega":-0.60131, "ax":6.35704, "ay":0.96493, "alpha":1.40393, "fx":[109.17395,107.11505,106.97658,109.26033], "fy":[9.96024,23.33101,23.80623,8.55496]}, + {"t":1.14195, "x":2.37344, "y":2.25077, "heading":-2.98274, "vx":-2.002, "vy":-0.30355, "omega":-0.54603, "ax":6.3566, "ay":0.96452, "alpha":1.51668, "fx":[109.26316,107.07436,106.82796,109.33026], "fy":[9.29375,23.66111,24.61206,8.058]}, + {"t":1.18133, "x":2.29953, "y":2.23956, "heading":-3.00424, "vx":-1.75169, "vy":-0.26557, "omega":-0.4863, "ax":6.35613, "ay":0.96418, "alpha":1.60439, "fx":[109.33238,107.05265,106.6985,109.38018], "fy":[8.7382,23.86887,25.27991,7.71457]}, + {"t":1.2207, "x":2.23548, "y":2.22985, "heading":-3.02339, "vx":-1.5014, "vy":-0.2276, "omega":-0.42313, "ax":6.35567, "ay":0.96388, "alpha":1.67454, "fx":[109.38742,107.04248,106.5856,109.41729], "fy":[8.26877,24.00088,25.84028,7.47152]}, + {"t":1.26008, "x":2.18129, "y":2.22164, "heading":-3.04005, "vx":-1.25113, "vy":-0.18965, "omega":-0.35719, "ax":6.35525, "ay":0.96363, "alpha":1.73189, "fx":[109.4319,107.03879,106.48738,109.44594], "fy":[7.86997,24.0871,26.31345,7.29347]}, + {"t":1.29946, "x":2.13695, "y":2.21492, "heading":-3.05412, "vx":-1.00088, "vy":-0.1517, "omega":-0.28899, "ax":6.35486, "ay":0.9634, "alpha":1.77964, "fx":[109.46819,107.03808,106.40241,109.46897], "fy":[7.5316,24.14783,26.71356,7.15577]}, + {"t":1.33884, "x":2.10246, "y":2.20969, "heading":-3.0655, "vx":-0.75064, "vy":-0.11377, "omega":-0.21891, "ax":6.35451, "ay":0.96321, "alpha":1.82002, "fx":[109.49795,107.0378,106.32961,109.4883], "fy":[7.24665,24.19735,27.05085,7.04055]}, + {"t":1.37821, "x":2.07783, "y":2.20596, "heading":-3.07412, "vx":-0.50041, "vy":-0.07584, "omega":-0.14725, "ax":6.35419, "ay":0.96303, "alpha":1.85464, "fx":[109.52234,107.03606,106.26812,109.50529], "fy":[7.01019,24.24605,27.33291,6.93456]}, + {"t":1.41759, "x":2.06305, "y":2.20372, "heading":-3.07991, "vx":-0.2502, "vy":-0.03792, "omega":-0.07421, "ax":6.3539, "ay":0.96288, "alpha":1.88468, "fx":[109.54223,107.03143,106.21728,109.52091], "fy":[6.81865,24.30167,27.56543,6.82775]}, + {"t":1.45697, "x":2.05813, "y":2.20297, "heading":-3.08284, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_LEFT_PATH_3.traj b/src/main/deploy/choreo/E_LEFT_PATH_3.traj new file mode 100644 index 00000000..4c930144 --- /dev/null +++ b/src/main/deploy/choreo/E_LEFT_PATH_3.traj @@ -0,0 +1,64 @@ +{ + "name":"E_LEFT_PATH_3", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":1.933159351348877, "y":2.1474287509918213, "heading":3.141592653589793, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":3.667616367340088, "y":2.670738458633423, "heading":2.5602479387771764, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"1.933159351348877 m", "val":1.933159351348877}, "y":{"exp":"2.1474287509918213 m", "val":2.1474287509918213}, "heading":{"exp":"3.141592653589793 rad", "val":3.141592653589793}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"3.667616367340088 m", "val":3.667616367340088}, "y":{"exp":"2.670738458633423 m", "val":2.670738458633423}, "heading":{"exp":"2.5602479387771764 rad", "val":2.5602479387771764}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.06353], + "samples":[ + {"t":0.0, "x":1.93316, "y":2.14743, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.1467, "ay":1.85418, "alpha":-2.08164, "fx":[100.07568,107.10259,107.986,103.05026], "fy":[45.00391,23.82217,19.57073,37.75973]}, + {"t":0.03667, "x":1.93729, "y":2.14868, "heading":3.14159, "vx":0.22542, "vy":0.068, "omega":-0.07634, "ax":6.14618, "ay":1.85403, "alpha":-2.08104, "fx":[100.06817,107.09142,107.97663,103.04281], "fy":[44.99586,23.82238,19.57239,37.75529]}, + {"t":0.07335, "x":1.94969, "y":2.15242, "heading":3.13879, "vx":0.45082, "vy":0.13599, "omega":-0.15266, "ax":6.14558, "ay":1.85384, "alpha":-2.08004, "fx":[100.05308,107.06946,107.96961,103.04596], "fy":[45.00069,23.86252,19.55244,37.71783]}, + {"t":0.11002, "x":1.97036, "y":2.15865, "heading":3.13319, "vx":0.6762, "vy":0.20398, "omega":-0.22894, "ax":6.14487, "ay":1.85363, "alpha":-2.07861, "fx":[100.03026,107.03612,107.96446,103.05937], "fy":[45.01764,23.94277,19.51125,37.64707]}, + {"t":0.14669, "x":1.99929, "y":2.16738, "heading":3.1248, "vx":0.90155, "vy":0.27196, "omega":-0.30517, "ax":6.14403, "ay":1.85337, "alpha":-2.0767, "fx":[99.99958,106.99047,107.96043,103.08253], "fy":[45.04542,24.06355,19.44948,37.5426]}, + {"t":0.18337, "x":2.03648, "y":2.1786, "heading":3.11361, "vx":1.12687, "vy":0.33993, "omega":-0.38133, "ax":6.14301, "ay":1.85305, "alpha":-2.07424, "fx":[99.9609,106.93118,107.95645,103.11474], "fy":[45.08217,24.22545,19.36809,37.40382]}, + {"t":0.22004, "x":2.08194, "y":2.19231, "heading":3.09962, "vx":1.35216, "vy":0.40788, "omega":-0.4574, "ax":6.14173, "ay":1.85266, "alpha":-2.07115, "fx":[99.91388,106.85634,107.95096,103.15491], "fy":[45.12531,24.42916,19.26838,37.22989]}, + {"t":0.25671, "x":2.13566, "y":2.20851, "heading":3.08285, "vx":1.5774, "vy":0.47583, "omega":-0.53336, "ax":6.14008, "ay":1.85216, "alpha":-2.0673, "fx":[99.85775,106.76306,107.9416,103.20132], "fy":[45.17133,24.67543,19.15208,37.01968]}, + {"t":0.29339, "x":2.19764, "y":2.22721, "heading":3.06329, "vx":1.80257, "vy":0.54375, "omega":-0.60917, "ax":6.13786, "ay":1.85149, "alpha":-2.0625, "fx":[99.79085,106.64679,107.92453,103.25109], "fy":[45.21534,24.96481,19.02139,36.77152]}, + {"t":0.33006, "x":2.26787, "y":2.2484, "heading":3.04095, "vx":2.02767, "vy":0.61165, "omega":-0.68481, "ax":6.13475, "ay":1.85055, "alpha":-2.05648, "fx":[99.70944,106.49975,107.89314,103.29903], "fy":[45.25016,25.29738,18.87917,36.48285]}, + {"t":0.36673, "x":2.34636, "y":2.27207, "heading":3.01583, "vx":2.25265, "vy":0.67952, "omega":-0.76023, "ax":6.13005, "ay":1.84915, "alpha":-2.04872, "fx":[99.60486,106.3071,107.83463,103.33475], "fy":[45.26411,25.67181,18.72909,36.14912]}, + {"t":0.40341, "x":2.43309, "y":2.29824, "heading":2.98795, "vx":2.47746, "vy":0.74733, "omega":-0.83536, "ax":6.12215, "ay":1.8468, "alpha":-2.03825, "fx":[99.45474,106.03534,107.71988,103.33407], "fy":[45.23486,26.0828,18.57587,35.76067]}, + {"t":0.44008, "x":2.52806, "y":2.32688, "heading":2.95732, "vx":2.70198, "vy":0.81506, "omega":-0.91011, "ax":6.10624, "ay":1.84206, "alpha":-2.02285, "fx":[99.187,105.58638,107.46344,103.22452], "fy":[45.10669,26.5105,18.4239,35.29046]}, + {"t":0.47675, "x":2.63126, "y":2.35801, "heading":2.92394, "vx":2.92591, "vy":0.88262, "omega":-0.98429, "ax":6.05822, "ay":1.82771, "alpha":-1.9957, "fx":[98.42283,104.47953,106.64742,102.64453], "fy":[44.64763,26.84379,18.2533,34.61044]}, + {"t":0.51343, "x":2.74264, "y":2.39161, "heading":2.88784, "vx":3.14809, "vy":0.94964, "omega":-1.05748, "ax":0.00386, "ay":0.00885, "alpha":0.29838, "fx":[0.62105,1.00988,-0.48955,-0.87845], "fy":[-0.79369,0.70577,1.09463,-0.40483]}, + {"t":0.5501, "x":2.85809, "y":2.42644, "heading":2.84906, "vx":3.14823, "vy":0.94997, "omega":-1.04654, "ax":-6.05813, "ay":-1.82732, "alpha":2.00108, "fx":[-98.36233,-104.17592,-106.70754,-102.94239], "fy":[-44.8237,-27.96907,-17.81008,-33.72609]}, + {"t":0.58677, "x":2.96947, "y":2.46005, "heading":2.81068, "vx":2.92606, "vy":0.88295, "omega":-0.97315, "ax":-6.1063, "ay":-1.84208, "alpha":2.01795, "fx":[-99.09591,-104.97529,-107.57744,-103.81684], "fy":[-45.34943,-28.81078,-17.65499,-33.51773]}, + {"t":0.62345, "x":3.07268, "y":2.4912, "heading":2.77499, "vx":2.70212, "vy":0.8154, "omega":-0.89915, "ax":-6.1223, "ay":-1.84704, "alpha":2.02696, "fx":[-99.32911,-105.13868,-107.88723,-104.19946], "fy":[-45.55194,-29.46752,-17.4875,-33.16377]}, + {"t":0.66012, "x":3.16765, "y":2.51986, "heading":2.74202, "vx":2.4776, "vy":0.74766, "omega":-0.82481, "ax":-6.13027, "ay":-1.84956, "alpha":2.03256, "fx":[-99.44747,-105.1473,-108.05129,-104.45045], "fy":[-45.64936,-30.05042,-17.34727,-32.79489]}, + {"t":0.69679, "x":3.25439, "y":2.54603, "heading":2.71177, "vx":2.25278, "vy":0.67983, "omega":-0.75027, "ax":-6.13503, "ay":-1.8511, "alpha":2.03647, "fx":[-99.52423,-105.09969,-108.1544,-104.64181], "fy":[-45.69504,-30.57804,-17.23388,-32.43949]}, + {"t":0.73347, "x":3.33289, "y":2.56972, "heading":2.68426, "vx":2.02779, "vy":0.61195, "omega":-0.67559, "ax":-6.13818, "ay":-1.85214, "alpha":2.03948, "fx":[-99.58204,-105.02963,-108.22547,-104.79758], "fy":[-45.7108,-31.05522,-17.14357,-32.10784]}, + {"t":0.77014, "x":3.40312, "y":2.59092, "heading":2.65948, "vx":1.80268, "vy":0.54402, "omega":-0.60079, "ax":-6.14042, "ay":-1.8529, "alpha":2.04195, "fx":[-99.62956,-104.95214,-108.27728,-104.92815], "fy":[-45.70826,-31.48352,-17.07259,-31.80466]}, + {"t":0.80681, "x":3.4651, "y":2.60962, "heading":2.63745, "vx":1.57749, "vy":0.47607, "omega":-0.52591, "ax":-6.14209, "ay":-1.85347, "alpha":2.04407, "fx":[-99.67045,-104.87504,-108.31645,-105.03885], "fy":[-45.69469,-31.86355,-17.01757,-31.53249]}, + {"t":0.84349, "x":3.51883, "y":2.62583, "heading":2.61816, "vx":1.35224, "vy":0.4081, "omega":-0.45095, "ax":-6.14338, "ay":-1.85393, "alpha":2.04593, "fx":[-99.70626,-104.8029,-108.34684,-105.13271], "fy":[-45.67518,-32.19564,-16.97554,-31.2928]}, + {"t":0.88016, "x":3.56429, "y":2.63955, "heading":2.60162, "vx":1.12694, "vy":0.34011, "omega":-0.37592, "ax":-6.14441, "ay":-1.85429, "alpha":2.04758, "fx":[-99.73762,-104.73861,-108.37088,-105.21164], "fy":[-45.65347,-32.48006,-16.94394,-31.08651]}, + {"t":0.91683, "x":3.60148, "y":2.65078, "heading":2.58784, "vx":0.90161, "vy":0.2721, "omega":-0.30082, "ax":-6.14525, "ay":-1.85459, "alpha":2.04902, "fx":[-99.76471,-104.68408,-108.39021,-105.2769], "fy":[-45.63244,-32.71705,-16.92058,-30.9142]}, + {"t":0.95351, "x":3.63041, "y":2.65951, "heading":2.5768, "vx":0.67624, "vy":0.20409, "omega":-0.22568, "ax":-6.14595, "ay":-1.85484, "alpha":2.05027, "fx":[-99.78749,-104.64062,-108.40598,-105.32938], "fy":[-45.61429,-32.90686,-16.90362,-30.77628]}, + {"t":0.99018, "x":3.65108, "y":2.66575, "heading":2.56853, "vx":0.45085, "vy":0.13607, "omega":-0.15049, "ax":-6.14654, "ay":-1.85504, "alpha":2.05133, "fx":[-99.80589,-104.60917,-108.41901,-105.36972], "fy":[-45.60074,-33.04973,-16.89159,-30.673]}, + {"t":1.02685, "x":3.66348, "y":2.66949, "heading":2.56301, "vx":0.22543, "vy":0.06804, "omega":-0.07526, "ax":-6.14705, "ay":-1.85522, "alpha":2.05219, "fx":[-99.81982,-104.5904,-108.42989,-105.39839], "fy":[-45.59303,-33.14586,-16.88336,-30.60454]}, + {"t":1.06353, "x":3.66762, "y":2.67074, "heading":2.56025, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_LEFT_PATH_4.traj b/src/main/deploy/choreo/E_LEFT_PATH_4.traj new file mode 100644 index 00000000..c43e270d --- /dev/null +++ b/src/main/deploy/choreo/E_LEFT_PATH_4.traj @@ -0,0 +1,66 @@ +{ + "name":"E_LEFT_PATH_4", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.7104902267456055, "y":2.7445008754730225, "heading":2.6191890324062967, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.0025863647460938, "y":4.063613414764404, "heading":3.141592653589793, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.7104902267456055 m", "val":3.7104902267456055}, "y":{"exp":"2.7445008754730225 m", "val":2.7445008754730225}, "heading":{"exp":"2.6191890324062967 rad", "val":2.6191890324062967}, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.0025863647460938 m", "val":2.0025863647460938}, "y":{"exp":"4.063613414764404 m", "val":4.063613414764404}, "heading":{"exp":"3.141592653589793 rad", "val":3.141592653589793}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.15945], + "samples":[ + {"t":0.0, "x":3.71049, "y":2.7445, "heading":2.61919, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.0914, "ay":3.9326, "alpha":1.59421, "fx":[-91.30514,-80.48278,-82.74985,-91.87511], "fy":[60.85871,74.58957,72.09273,60.0286]}, + {"t":0.0374, "x":3.70693, "y":2.74725, "heading":2.61919, "vx":-0.19043, "vy":0.14709, "omega":0.05963, "ax":-5.09105, "ay":3.93232, "alpha":1.5914, "fx":[-91.28939,-80.4885,-82.75072,-91.86069], "fy":[60.8653,74.56981,72.07951,60.03574]}, + {"t":0.0748, "x":3.69625, "y":2.7555, "heading":2.62142, "vx":-0.38084, "vy":0.29416, "omega":0.11915, "ax":-5.09065, "ay":3.93199, "alpha":1.58811, "fx":[-91.25947,-80.48522,-82.76469,-91.85282], "fy":[60.89046,74.5577,72.04938,60.03051]}, + {"t":0.1122, "x":3.67844, "y":2.76926, "heading":2.62588, "vx":-0.57124, "vy":0.44122, "omega":0.17854, "ax":-5.09019, "ay":3.93161, "alpha":1.58422, "fx":[-91.21478,-80.47336,-82.79171,-91.85081], "fy":[60.93438,74.5523,72.0019,60.01339]}, + {"t":0.14961, "x":3.65352, "y":2.78851, "heading":2.63255, "vx":-0.76162, "vy":0.58827, "omega":0.2378, "ax":-5.08964, "ay":3.93115, "alpha":1.57961, "fx":[-91.15447,-80.45356,-82.83174,-91.85368], "fy":[60.99737,74.55222,71.93642,59.98507]}, + {"t":0.18701, "x":3.62147, "y":2.81326, "heading":2.64145, "vx":-0.95198, "vy":0.7353, "omega":0.29688, "ax":-5.08899, "ay":3.93061, "alpha":1.57406, "fx":[-91.0773,-80.42668,-82.88472,-91.86004], "fy":[61.07989,74.55554,71.85205,59.94649]}, + {"t":0.22441, "x":3.58231, "y":2.84351, "heading":2.65255, "vx":-1.14231, "vy":0.88231, "omega":0.35575, "ax":-5.08818, "ay":3.92994, "alpha":1.56728, "fx":[-90.98157,-80.39393,-82.95056,-91.86797], "fy":[61.18252,74.55954,71.74749,59.89901]}, + {"t":0.26181, "x":3.53602, "y":2.87926, "heading":2.66586, "vx":-1.33262, "vy":1.0293, "omega":0.41437, "ax":-5.08717, "ay":3.9291, "alpha":1.55886, "fx":[-90.86479,-80.35694,-83.02906,-91.87461], "fy":[61.30603,74.56033,71.62088,59.84449]}, + {"t":0.29921, "x":3.48262, "y":2.9205, "heading":2.68135, "vx":-1.52289, "vy":1.17625, "omega":0.47267, "ax":-5.08587, "ay":3.92803, "alpha":1.54816, "fx":[-90.7233,-80.31799,-83.11983,-91.8757], "fy":[61.45135,74.55215,71.46942,59.78565]}, + {"t":0.33661, "x":3.42211, "y":2.96724, "heading":2.69903, "vx":-1.71311, "vy":1.32317, "omega":0.53057, "ax":-5.08413, "ay":3.92659, "alpha":1.53412, "fx":[-90.55128,-80.28033,-83.2221,-91.86435], "fy":[61.61965,74.52594,71.28861,59.72657]}, + {"t":0.37401, "x":3.35448, "y":3.01948, "heading":2.71888, "vx":-1.90326, "vy":1.47003, "omega":0.58795, "ax":-5.08166, "ay":3.92457, "alpha":1.51493, "fx":[-90.33878,-80.24894,-83.33422,-91.82869], "fy":[61.81239,74.46633,71.07072,59.67391]}, + {"t":0.41142, "x":3.27974, "y":3.07721, "heading":2.74087, "vx":-2.09332, "vy":1.61681, "omega":0.64461, "ax":-5.07794, "ay":3.92152, "alpha":1.48709, "fx":[-90.06681,-80.23214,-83.4525,-91.74583], "fy":[62.03143,74.34434,70.80075,59.63947]}, + {"t":0.44882, "x":3.19789, "y":3.14042, "heading":2.76498, "vx":-2.28324, "vy":1.76348, "omega":0.70023, "ax":-5.07166, "ay":3.9164, "alpha":1.4429, "fx":[-89.69291,-80.24543,-83.56733,-91.56441], "fy":[62.2789,74.09619,70.4448,59.64728]}, + {"t":0.48622, "x":3.10895, "y":3.20912, "heading":2.79117, "vx":-2.47293, "vy":1.90996, "omega":0.7542, "ax":-5.05889, "ay":3.90599, "alpha":1.36115, "fx":[-89.09576,-80.32206,-83.64602,-91.13722], "fy":[62.55393,73.54383,69.90454,59.75668]}, + {"t":0.52362, "x":3.01292, "y":3.28328, "heading":2.81937, "vx":-2.66214, "vy":2.05605, "omega":0.80511, "ax":-5.01939, "ay":3.87391, "alpha":1.15281, "fx":[-87.71436,-80.52668,-83.49143,-89.78111], "fy":[62.79884,71.89889,68.71463,60.164]}, + {"t":0.56102, "x":2.90984, "y":3.36289, "heading":2.84949, "vx":-2.84987, "vy":2.20094, "omega":0.84822, "ax":-0.00142, "ay":0.00099, "alpha":-0.13447, "fx":[-0.25795,-0.45899,0.20958,0.41063], "fy":[0.45159,-0.21698,-0.41803,0.25054]}, + {"t":0.59842, "x":2.80325, "y":3.44521, "heading":2.88121, "vx":-2.84993, "vy":2.20098, "omega":0.8432, "ax":5.01949, "ay":-3.87402, "alpha":-1.13949, "fx":[87.39839,80.47033,83.79184,89.85994], "fy":[-63.23088,-71.9739,-68.34887,-60.03002]}, + {"t":0.63583, "x":2.70017, "y":3.52482, "heading":2.91275, "vx":-2.66219, "vy":2.05608, "omega":0.80058, "ax":5.05895, "ay":-3.90604, "alpha":-1.35534, "fx":[88.40757,80.0681,84.30746,91.42198], "fy":[-63.5135,-73.8349,-69.10983,-59.3044]}, + {"t":0.67323, "x":2.60414, "y":3.59899, "heading":2.94269, "vx":-2.47298, "vy":1.90999, "omega":0.74988, "ax":5.07171, "ay":-3.91643, "alpha":-1.43825, "fx":[88.63412,79.82919,84.58475,92.02534], "fy":[-63.76698,-74.55973,-69.22487,-58.91787]}, + {"t":0.71063, "x":2.51519, "y":3.66769, "heading":2.97074, "vx":-2.28329, "vy":1.76351, "omega":0.69609, "ax":5.078, "ay":-3.92155, "alpha":-1.482, "fx":[88.65687,79.673,84.80569,92.36543], "fy":[-64.02065,-74.95853,-69.17922,-58.65963]}, + {"t":0.74803, "x":2.43335, "y":3.7309, "heading":2.99677, "vx":-2.09336, "vy":1.61684, "omega":0.64066, "ax":5.08173, "ay":-3.92461, "alpha":-1.50891, "fx":[88.60225,79.56249,84.99863,92.59177], "fy":[-64.26731,-75.21438,-69.07651,-58.46748]}, + {"t":0.78543, "x":2.35861, "y":3.78863, "heading":3.02073, "vx":-1.9033, "vy":1.47005, "omega":0.58423, "ax":5.0842, "ay":-3.92663, "alpha":-1.52706, "fx":[88.51487,79.48073,85.17139,92.75646], "fy":[-64.50153,-75.3928,-68.95282,-58.31644]}, + {"t":0.82283, "x":2.29098, "y":3.84086, "heading":3.04259, "vx":-1.71314, "vy":1.32319, "omega":0.52711, "ax":5.08596, "ay":-3.92808, "alpha":-1.54011, "fx":[88.41478,79.41871,85.32681,92.88274], "fy":[-64.71992,-75.52366,-68.8242,-58.19419]}, + {"t":0.86023, "x":2.23046, "y":3.88761, "heading":3.0623, "vx":-1.52292, "vy":1.17627, "omega":0.46951, "ax":5.08727, "ay":-3.92916, "alpha":-1.54993, "fx":[88.31254,79.37097,85.46607,92.98273], "fy":[-64.92022,-75.62282,-68.69899,-58.09368]}, + {"t":0.89764, "x":2.17706, "y":3.92885, "heading":3.07986, "vx":-1.33265, "vy":1.02932, "omega":0.41154, "ax":5.08829, "ay":-3.93001, "alpha":-1.55761, "fx":[88.21429,79.33389,85.58975,93.06354], "fy":[-65.10094,-75.6997,-68.58199,-58.01043]}, + {"t":0.93504, "x":2.13077, "y":3.9646, "heading":3.09525, "vx":-1.14234, "vy":0.88233, "omega":0.35328, "ax":5.0891, "ay":-3.93068, "alpha":-1.56379, "fx":[88.1239,79.3049,85.69814,93.12965], "fy":[-65.26102,-75.76037,-68.47623,-57.94135]}, + {"t":0.97244, "x":2.09161, "y":3.99485, "heading":3.10847, "vx":-0.952, "vy":0.73532, "omega":0.2948, "ax":5.08976, "ay":-3.93123, "alpha":-1.56889, "fx":[88.04398,79.28207,85.7914,93.18409], "fy":[-65.39968,-75.80897,-68.38366,-57.88417]}, + {"t":1.00984, "x":2.05956, "y":4.01961, "heading":3.11949, "vx":-0.76164, "vy":0.58828, "omega":0.23612, "ax":5.09031, "ay":-3.93169, "alpha":-1.57318, "fx":[87.97632,79.26393,85.86961,93.22902], "fy":[-65.51639,-75.84846,-68.30567,-57.8372]}, + {"t":1.04724, "x":2.03464, "y":4.03886, "heading":3.12832, "vx":-0.57125, "vy":0.44123, "omega":0.17728, "ax":5.09077, "ay":-3.93208, "alpha":-1.57687, "fx":[87.92222,79.24934,85.93285,93.266], "fy":[-65.61072,-75.88102,-68.24323,-57.79912]}, + {"t":1.08464, "x":2.01683, "y":4.05261, "heading":3.13495, "vx":-0.38085, "vy":0.29417, "omega":0.1183, "ax":5.09117, "ay":-3.93241, "alpha":-1.58007, "fx":[87.88263,79.23741,85.98114,93.2962], "fy":[-65.68237,-75.90826,-68.19705,-57.76891]}, + {"t":1.12204, "x":2.00615, "y":4.06086, "heading":3.13938, "vx":-0.19043, "vy":0.14709, "omega":0.0592, "ax":5.09151, "ay":-3.93269, "alpha":-1.58291, "fx":[87.85826,79.22747,86.01452,93.32047], "fy":[-65.73112,-75.93139,-68.16767,-57.74582]}, + {"t":1.15945, "x":2.00259, "y":4.06361, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_LEFT_PATH_5.traj b/src/main/deploy/choreo/E_LEFT_PATH_5.traj new file mode 100644 index 00000000..8e864b99 --- /dev/null +++ b/src/main/deploy/choreo/E_LEFT_PATH_5.traj @@ -0,0 +1,65 @@ +{ + "name":"E_LEFT_PATH_5", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":1.974815368652344, "y":3.9941866397857666, "heading":3.120762184569173, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":3.0856471061706543, "y":3.9941866397857666, "heading":1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"1.9748153686523438 m", "val":1.974815368652344}, "y":{"exp":"3.9941866397857666 m", "val":3.9941866397857666}, "heading":{"exp":"3.120762184569173 rad", "val":3.120762184569173}, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"3.0856471061706543 m", "val":3.0856471061706543}, "y":{"exp":"3.9941866397857666 m", "val":3.9941866397857666}, "heading":{"exp":"1.5707963267948966 rad", "val":1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.86265], + "samples":[ + {"t":0.0, "x":1.97482, "y":3.99419, "heading":3.12076, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.95818, "ay":-0.00317, "alpha":-8.60885, "fx":[96.21035,96.74173,106.05976,106.37578], "fy":[52.57026,-51.57226,-28.18082,26.96724]}, + {"t":0.02876, "x":1.97728, "y":3.99419, "heading":3.12076, "vx":0.17133, "vy":-0.00009, "omega":-0.24755, "ax":5.95728, "ay":-0.00244, "alpha":-8.61037, "fx":[96.18131,96.72855,106.05264,106.36377], "fy":[52.58847,-51.56029,-28.17243,26.97817]}, + {"t":0.05751, "x":1.98467, "y":3.99418, "heading":3.11364, "vx":0.34263, "vy":-0.00016, "omega":-0.49514, "ax":5.95651, "ay":-0.00449, "alpha":-8.60883, "fx":[96.08776,96.79389,105.98332,106.40934], "fy":[52.72129,-51.39214,-28.39089,26.75598]}, + {"t":0.08627, "x":1.99698, "y":3.99418, "heading":3.09941, "vx":0.51391, "vy":-0.00029, "omega":-0.74269, "ax":5.95607, "ay":-0.00927, "alpha":-8.60161, "fx":[95.93719,96.94547,105.85066,106.51111], "fy":[52.95304,-51.04902,-28.83307,26.29863]}, + {"t":0.11502, "x":2.01422, "y":3.99416, "heading":3.07805, "vx":0.68518, "vy":-0.00056, "omega":-0.99003, "ax":5.95632, "ay":-0.01661, "alpha":-8.58375, "fx":[95.74418,97.19833,105.65263,106.66625], "fy":[53.25454,-50.49439,-29.49304,25.60253]}, + {"t":0.14378, "x":2.03639, "y":3.99414, "heading":3.04958, "vx":0.85645, "vy":-0.00103, "omega":-1.23685, "ax":5.95779, "ay":-0.02624, "alpha":-8.54799, "fx":[95.52997,97.5747,105.38656,106.87026], "fy":[53.58444,-49.67116,-30.36134,24.6629]}, + {"t":0.17253, "x":2.06348, "y":3.9941, "heading":3.01402, "vx":1.02777, "vy":-0.00179, "omega":-1.48265, "ax":5.96117, "ay":-0.03756, "alpha":-8.48498, "fx":[95.32168,98.1033,105.04964,107.11655], "fy":[53.89125,-48.49762,-31.42378,23.47443]}, + {"t":0.20129, "x":2.0955, "y":3.99403, "heading":2.97138, "vx":1.19918, "vy":-0.00287, "omega":-1.72664, "ax":5.96723, "ay":-0.04959, "alpha":-8.38367, "fx":[95.15097,98.81699,104.6396,107.39597], "fy":[54.11544,-46.86178,-32.65957,22.03212]}, + {"t":0.23004, "x":2.13245, "y":3.99393, "heading":2.92173, "vx":1.37077, "vy":-0.0043, "omega":-1.96771, "ax":5.97675, "ay":-0.06068, "alpha":-8.23228, "fx":[95.05207,99.74749,104.15589,107.69601], "fy":[54.19127,-44.61434,-34.03806,20.33264]}, + {"t":0.2588, "x":2.17433, "y":3.99378, "heading":2.86515, "vx":1.54263, "vy":-0.00604, "omega":-2.20443, "ax":5.99033, "ay":-0.06835, "alpha":-8.01968, "fx":[95.05936,100.9143,103.60155,107.99969], "fy":[54.0468,-41.56042,-35.51268,18.37617]}, + {"t":0.28755, "x":2.22117, "y":3.99358, "heading":2.80176, "vx":1.71488, "vy":-0.00801, "omega":-2.43503, "ax":6.00801, "ay":-0.06892, "alpha":-7.73745, "fx":[95.20499,102.30347,102.98659,108.28317], "fy":[53.59902,-37.45032,-37.00764,16.16953]}, + {"t":0.31631, "x":2.27296, "y":3.99332, "heading":2.73174, "vx":1.88764, "vy":-0.00999, "omega":-2.65753, "ax":6.02877, "ay":-0.05705, "alpha":-7.38097, "fx":[95.51767,103.82776,102.33561,108.50948], "fy":[52.73407,-31.96616,-38.38236,13.73267]}, + {"t":0.34506, "x":2.32973, "y":3.99301, "heading":2.65533, "vx":2.061, "vy":-0.01163, "omega":-2.86977, "ax":6.04927, "ay":-0.024, "alpha":-6.94321, "fx":[96.02514,105.24438,101.70978,108.60641], "fy":[51.23166,-24.67514,-39.30854,11.11889]}, + {"t":0.37382, "x":2.3915, "y":3.99267, "heading":2.57281, "vx":2.23495, "vy":-0.01232, "omega":-3.06942, "ax":6.05981, "ay":0.05198, "alpha":-6.35577, "fx":[96.76896,105.8877,101.29983,108.34583], "fy":[48.36824,-14.72603,-38.62406,8.5184]}, + {"t":0.40257, "x":2.45827, "y":3.99233, "heading":2.48454, "vx":2.4092, "vy":-0.01082, "omega":-3.25218, "ax":5.97728, "ay":0.349, "alpha":-4.45126, "fx":[97.63868,101.92349,101.82423,105.30079], "fy":[37.12883,2.87298,-24.20418,7.9478]}, + {"t":0.43133, "x":2.53002, "y":3.99217, "heading":2.39103, "vx":2.58107, "vy":-0.00079, "omega":-3.38017, "ax":-5.8948, "ay":0.35172, "alpha":5.93009, "fx":[-98.61187,-100.75725,-95.39884,-106.3074], "fy":[-36.47758,12.38529,44.89336,3.12958]}, + {"t":0.46008, "x":2.6018, "y":3.99229, "heading":2.29383, "vx":2.41157, "vy":0.00933, "omega":-3.20965, "ax":-6.04077, "ay":0.09728, "alpha":6.50924, "fx":[-99.06879,-106.73669,-96.50893,-108.69236], "fy":[-44.02034,-2.21354,49.27162,3.58119]}, + {"t":0.48884, "x":2.66865, "y":3.9926, "heading":2.20154, "vx":2.23787, "vy":0.01212, "omega":-3.02248, "ax":-6.05629, "ay":0.01124, "alpha":6.77632, "fx":[-99.84024,-107.17552,-96.03257,-109.01448], "fy":[-43.80499,-13.23082,51.41051,6.39026]}, + {"t":0.51759, "x":2.73049, "y":3.99295, "heading":2.11463, "vx":2.06372, "vy":0.01245, "omega":-2.82763, "ax":-6.04667, "ay":-0.03876, "alpha":7.09011, "fx":[-100.70352,-106.21331,-95.49954,-108.99184], "fy":[-42.45178,-22.41102,52.89271,9.33288]}, + {"t":0.54635, "x":2.78734, "y":3.99329, "heading":2.03332, "vx":1.88985, "vy":0.01133, "omega":-2.62375, "ax":-6.02828, "ay":-0.06618, "alpha":7.42669, "fx":[-101.56268,-104.7041,-95.07319,-108.81716], "fy":[-40.73178,-29.85453,53.92429,12.15908]}, + {"t":0.5751, "x":2.83919, "y":3.99359, "heading":1.95787, "vx":1.7165, "vy":0.00943, "omega":-2.4102, "ax":-6.00841, "ay":-0.07676, "alpha":7.74505, "fx":[-102.37586,-103.0786,-94.79421,-108.55647], "fy":[-38.88937,-35.70676,54.58124,14.79255]}, + {"t":0.60386, "x":2.88606, "y":3.99383, "heading":1.88857, "vx":1.54373, "vy":0.00722, "omega":-2.18749, "ax":-5.99076, "ay":-0.07534, "alpha":8.01744, "fx":[-103.12123,-101.56862,-94.66803,-108.24671], "fy":[-37.04316,-40.19716,54.91523,17.19913]}, + {"t":0.63261, "x":2.92797, "y":3.99401, "heading":1.82566, "vx":1.37147, "vy":0.00506, "omega":-1.95695, "ax":-5.97691, "ay":-0.06626, "alpha":8.23181, "fx":[-103.78748,-100.27857,-94.68218,-107.91416], "fy":[-35.2657,-43.57992,54.97586,19.36151]}, + {"t":0.66137, "x":2.96494, "y":3.99412, "heading":1.76939, "vx":1.1996, "vy":0.00315, "omega":-1.72024, "ax":-5.96715, "ay":-0.05306, "alpha":8.38792, "fx":[-104.36994,-99.23558,-94.81286,-107.57939], "fy":[-33.60675,-46.09163,54.81639,21.27163]}, + {"t":0.69012, "x":2.99697, "y":3.99419, "heading":1.71993, "vx":1.02801, "vy":0.00162, "omega":-1.47904, "ax":-5.96104, "ay":-0.03841, "alpha":8.49257, "fx":[-104.86829,-98.42585,-95.02938,-107.25885], "fy":[-32.10211,-47.93291,54.49413,22.92744]}, + {"t":0.71888, "x":3.02406, "y":3.99422, "heading":1.6774, "vx":0.8566, "vy":0.00052, "omega":-1.23484, "ax":-5.95787, "ay":-0.02415, "alpha":8.55587, "fx":[-105.28495,-97.81795,-95.29802,-106.96567], "fy":[-30.77782,-49.26485,54.06866,24.3308]}, + {"t":0.74763, "x":3.04623, "y":3.99423, "heading":1.64189, "vx":0.68529, "vy":-0.00017, "omega":-0.98882, "ax":-5.95682, "ay":-0.01147, "alpha":8.58868, "fx":[-105.62382,-97.37626,-95.58537,-106.71005], "fy":[-29.65269,-50.21224,53.59897,25.48588]}, + {"t":0.77639, "x":3.06348, "y":3.99422, "heading":1.61346, "vx":0.514, "vy":-0.0005, "omega":-0.74185, "ax":-5.95716, "ay":-0.00104, "alpha":8.6011, "fx":[-105.88936,-97.06792,-95.86108,-106.49975], "fy":[-28.73996,-50.86893,53.14014,26.39788]}, + {"t":0.80514, "x":3.07579, "y":3.9942, "heading":1.59212, "vx":0.3427, "vy":-0.00053, "omega":-0.49452, "ax":-5.95824, "ay":0.00677, "alpha":8.60151, "fx":[-106.08589,-96.86595,-96.09974,-106.34046], "fy":[-28.04864,-51.30311,52.74012,27.07203]}, + {"t":0.8339, "x":3.08318, "y":3.99419, "heading":1.5779, "vx":0.17137, "vy":-0.00034, "omega":-0.24719, "ax":-5.95962, "ay":0.01181, "alpha":8.59627, "fx":[-106.21711,-96.75041,-96.28212,-106.23612], "fy":[-27.5844,-51.56171,52.43691,27.5128]}, + {"t":0.86265, "x":3.08565, "y":3.99419, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index 1353bc9c..30ee7c15 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -19,6 +19,10 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructure; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.util.AllianceFlipUtil; import frc.robot.util.LoggedChoreo.LoggedAutoRoutine; import frc.robot.util.LoggedChoreo.LoggedAutoTrajectory; @@ -148,6 +152,12 @@ public static void loadAutoTrajectories(Drive drive) { drive.getAutoFactory().cache().loadTrajectory("C_RIGHT_PATH3"); drive.getAutoFactory().cache().loadTrajectory("D_CENTER_PATH"); + + drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH1"); + drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH2"); + drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH3"); + drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH4"); + drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH5"); } public static final Command autoALeft( @@ -1080,723 +1090,801 @@ public static final LoggedAutoRoutine autoDCenter( // V3 - // public static final LoggedAutoRoutine autoALeft( - // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // Camera... cameras) { - // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeft"); - - // LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - // LoggedAutoTrajectory path2 = - // routine - // .trajectory("A_LEFT_PATH2") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path3 = - // routine - // .trajectory("A_LEFT_PATH3") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path4 = - // routine - // .trajectory("A_LEFT_PATH4") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - // routine - // .active() - // .onTrue( - // Commands.sequence( - // path1.resetOdometry(), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - // path1.cmd(), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.25), - // Commands.deadline( - // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.25), - // Commands.deadline( - // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.25), - // Commands.deadline( - // path4.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5))); - - // return routine; - // } - - // public static final LoggedAutoRoutine autoALeftNashoba( - // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // Camera... cameras) { - // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftNashoba"); - - // LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - // LoggedAutoTrajectory path2 = - // routine - // .trajectory("A_LEFT_PATH2") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path3 = - // routine - // .trajectory("A_LEFT_PATH_ALT3") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path4 = - // routine - // .trajectory("A_LEFT_PATH_ALT4") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - // routine - // .active() - // .onTrue( - // Commands.sequence( - // path1.resetOdometry(), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - // path1.cmd(), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.25), - // Commands.deadline( - // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.25), - // Commands.deadline( - // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.25), - // Commands.deadline( - // path4.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5))); - - // return routine; - // } - - // public static final LoggedAutoRoutine autoALeftDAVE( - // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // Camera... cameras) { - // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftD.A.V.E."); - - // LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); - // LoggedAutoTrajectory path2 = - // routine - // .trajectory("A_LEFT_PATH2") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path3 = - // routine - // .trajectory("A_LEFT_PATH3") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path4 = - // routine - // .trajectory("A_LEFT_PATH4_ALT_ALT") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - // routine - // .active() - // .onTrue( - // Commands.sequence( - // path1.resetOdometry(), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - // path1.cmd(), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.25), - // Commands.deadline( - // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.25), - // Commands.deadline( - // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.25), - // Commands.deadline( - // path4.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5))); - - // return routine; - // } - - // public static final LoggedAutoRoutine autoARight( - // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // Camera... cameras) { - - // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoARight"); - - // LoggedAutoTrajectory path1 = routine.trajectory("A_RIGHT_PATH1"); - // LoggedAutoTrajectory path2 = - // routine - // .trajectory("A_RIGHT_PATH2") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path3 = - // routine - // .trajectory("A_RIGHT_PATH3") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path4 = - // routine - // .trajectory("A_RIGHT_PATH4") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - // routine - // .active() - // .onTrue( - // Commands.sequence( - // path1.resetOdometry(), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - // path1.cmd(), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.25), - // Commands.deadline( - // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.25), - // Commands.deadline( - // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.25), - // Commands.deadline( - // path4.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5))); - - // return routine; - // } - - // public static final LoggedAutoRoutine autoBLeft( - // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // Camera... cameras) { - - // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBLeft"); - // LoggedAutoTrajectory path1 = - // routine - // .trajectory("B_LEFT_PATH1") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path2 = - // routine - // .trajectory("B_LEFT_PATH2") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - // routine - // .active() - // .onTrue( - // Commands.sequence( - // path1.resetOdometry(), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - // path1.cmd(), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5), - // Commands.deadline( - // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); - - // return routine; - // } - - // public static final LoggedAutoRoutine autoCLeft( - // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // Camera... cameras) { - - // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); - // LoggedAutoTrajectory path1 = - // routine - // .trajectory("C_LEFT_PATH1") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path2 = - // routine - // .trajectory("C_LEFT_PATH2") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path3 = - // routine - // .trajectory("C_LEFT_PATH3") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - // routine - // .active() - // .onTrue( - // Commands.sequence( - // path1.resetOdometry(), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - // path1.cmd(), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5), - // Commands.deadline( - // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5), - // Commands.deadline( - // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5))); - - // return routine; - // } - - // public static final LoggedAutoRoutine autoCLeftPush( - // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // Camera... cameras) { - - // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); - // LoggedAutoTrajectory path1 = - // routine - // .trajectory("C_LEFT_PATH1") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path2 = - // routine - // .trajectory("C_LEFT_PATH2") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path3 = - // routine - // .trajectory("C_LEFT_PATH3") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - // routine - // .active() - // .onTrue( - // Commands.sequence( - // path1.resetOdometry(), - // Commands.runEnd( - // () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), - // () -> drive.stop()) - // .withTimeout(0.5), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - // path1.cmd(), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5), - // Commands.deadline( - // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5), - // Commands.deadline( - // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5))); - - // return routine; - // } - - // public static final LoggedAutoRoutine autoCRight( - // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // Camera... cameras) { - - // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); - // LoggedAutoTrajectory path1 = - // routine - // .trajectory("C_RIGHT_PATH1") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path2 = - // routine - // .trajectory("C_RIGHT_PATH2") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path3 = - // routine - // .trajectory("C_RIGHT_PATH3") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // routine - // .active() - // .onTrue( - // Commands.sequence( - // path1.resetOdometry(), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - // path1.cmd(), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5), - // Commands.deadline( - // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5), - // Commands.deadline( - // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5))); - // return routine; - // } - - // public static final LoggedAutoRoutine autoCRightPush( - // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // Camera... cameras) { - - // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); - // LoggedAutoTrajectory path1 = - // routine - // .trajectory("C_RIGHT_PATH1") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path2 = - // routine - // .trajectory("C_RIGHT_PATH2") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path3 = - // routine - // .trajectory("C_RIGHT_PATH3") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // routine - // .active() - // .onTrue( - // Commands.sequence( - // path1.resetOdometry(), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - // Commands.runEnd( - // () -> drive.runVelocity(new ChassisSpeeds(0.0, 1.0, 0.0)), - // () -> drive.stop()) - // .withTimeout(0.5), - // path1.cmd(), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5), - // Commands.deadline( - // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5), - // Commands.deadline( - // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // Commands.waitUntil(() -> superstructure.atGoal())), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5))); - // return routine; - // } - - // public static final LoggedAutoRoutine autoBRight( - // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // Camera... cameras) { - - // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBRight"); - // LoggedAutoTrajectory path1 = - // routine - // .trajectory("B_RIGHT_PATH1") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - // LoggedAutoTrajectory path2 = - // routine - // .trajectory("B_RIGHT_PATH2") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - // routine - // .active() - // .onTrue( - // Commands.sequence( - // path1.resetOdometry(), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - // path1.cmd(), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5), - // Commands.deadline( - // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); - - // return routine; - // } - - // public static final LoggedAutoRoutine autoDCenter( - // Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { - // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoDCenter"); - // LoggedAutoTrajectory path1 = - // routine - // .trajectory("D_CENTER_PATH") - // .bindEvent("Funnel", Commands.runOnce(() -> RobotState.setAutoClapOverride(true))); - - // routine - // .active() - // .onTrue( - // Commands.sequence( - // path1.resetOdometry(), - // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - // path1.cmd(), - // Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), - // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, - // 0.5))); - // return routine; - // } + // public static final LoggedAutoRoutine autoALeft( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // V3_EpsilonManipulator manipulator, + // Camera... cameras) { + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeft"); + + // LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("A_LEFT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path3 = + // routine + // .trajectory("A_LEFT_PATH3") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path4 = + // routine + // .trajectory("A_LEFT_PATH4") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + // path1.cmd(), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path4.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + + // return routine; + // } + + // public static final LoggedAutoRoutine autoALeftNashoba( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // V3_EpsilonManipulator manipulator, + // Camera... cameras) { + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftNashoba"); + + // LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("A_LEFT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path3 = + // routine + // .trajectory("A_LEFT_PATH_ALT3") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path4 = + // routine + // .trajectory("A_LEFT_PATH_ALT4") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + // path1.cmd(), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path4.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + + // return routine; + // } + + // public static final LoggedAutoRoutine autoALeftDAVE( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // V3_EpsilonManipulator manipulator, + // Camera... cameras) { + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftD.A.V.E."); + + // LoggedAutoTrajectory path1 = routine.trajectory("A_LEFT_PATH1"); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("A_LEFT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path3 = + // routine + // .trajectory("A_LEFT_PATH3") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path4 = + // routine + // .trajectory("A_LEFT_PATH4_ALT_ALT") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + // path1.cmd(), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path4.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + + // return routine; + // } + + // public static final LoggedAutoRoutine autoARight( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // V3_EpsilonManipulator manipulator, + // Camera... cameras) { + + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoARight"); + + // LoggedAutoTrajectory path1 = routine.trajectory("A_RIGHT_PATH1"); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("A_RIGHT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path3 = + // routine + // .trajectory("A_RIGHT_PATH3") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path4 = + // routine + // .trajectory("A_RIGHT_PATH4") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + // path1.cmd(), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.25), + // Commands.deadline( + // path4.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + + // return routine; + // } + + // public static final LoggedAutoRoutine autoBLeft( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // V3_EpsilonManipulator manipulator, + // Camera... cameras) { + + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBLeft"); + // LoggedAutoTrajectory path1 = + // routine + // .trajectory("B_LEFT_PATH1") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("B_LEFT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + // path1.cmd(), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); + + // return routine; + // } + + // public static final LoggedAutoRoutine autoCLeft( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // V3_EpsilonManipulator manipulator, + // Camera... cameras) { + + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); + // LoggedAutoTrajectory path1 = + // routine + // .trajectory("C_LEFT_PATH1") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("C_LEFT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path3 = + // routine + // .trajectory("C_LEFT_PATH3") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + // path1.cmd(), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + + // return routine; + // } + + // public static final LoggedAutoRoutine autoCLeftPush( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // V3_EpsilonManipulator manipulator, + // Camera... cameras) { + + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); + // LoggedAutoTrajectory path1 = + // routine + // .trajectory("C_LEFT_PATH1") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("C_LEFT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path3 = + // routine + // .trajectory("C_LEFT_PATH3") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runEnd( + // () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), + // () -> drive.stop()) + // .withTimeout(0.5), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + // path1.cmd(), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + + // return routine; + // } + + // public static final LoggedAutoRoutine autoCRight( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // V3_EpsilonManipulator manipulator, + // Camera... cameras) { + + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); + // LoggedAutoTrajectory path1 = + // routine + // .trajectory("C_RIGHT_PATH1") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("C_RIGHT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path3 = + // routine + // .trajectory("C_RIGHT_PATH3") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + // path1.cmd(), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + // return routine; + // } + + // public static final LoggedAutoRoutine autoCRightPush( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // V3_EpsilonManipulator manipulator, + // Camera... cameras) { + + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); + // LoggedAutoTrajectory path1 = + // routine + // .trajectory("C_RIGHT_PATH1") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("C_RIGHT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path3 = + // routine + // .trajectory("C_RIGHT_PATH3") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + // Commands.runEnd( + // () -> drive.runVelocity(new ChassisSpeeds(0.0, 1.0, 0.0)), + // () -> drive.stop()) + // .withTimeout(0.5), + // path1.cmd(), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // Commands.waitUntil(() -> superstructure.atGoal())), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + // return routine; + // } + + // public static final LoggedAutoRoutine autoBRight( + // Drive drive, + // V3_EpsilonIntake intake, + // V3_EpsilonSuperstructure superstructure, + // V3_EpsilonManipulator manipulator, + // Camera... cameras) { + + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBRight"); + // LoggedAutoTrajectory path1 = + // routine + // .trajectory("B_RIGHT_PATH1") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + // LoggedAutoTrajectory path2 = + // routine + // .trajectory("B_RIGHT_PATH2") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + // path1.cmd(), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // Commands.deadline( + // path2.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); + + // return routine; + // } + + // public static final LoggedAutoRoutine autoDCenter( + // Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoDCenter"); + // LoggedAutoTrajectory path1 = + // routine + // .trajectory("D_CENTER_PATH") + // .bindEvent("Funnel", Commands.runOnce(() -> + // RobotState.setAutoClapOverride(true))); + + // routine + // .active() + // .onTrue( + // Commands.sequence( + // path1.resetOdometry(), + // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + // path1.cmd(), + // Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), + // superstructure.runActionWithTimeout( + // V3_EpsilonSuperstructureStates.STOW_DOWN, + // V3_EpsilonSuperstructureStates.L4_SCORE, + // 0.5))); + // return routine; + // } + + public static final LoggedAutoRoutine autoELeftPath( + Drive drive, + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator, + Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoELeftPath"); + LoggedAutoTrajectory path1 = routine.trajectory("E_LEFT_PATH_1"); + LoggedAutoTrajectory path2 = routine.trajectory("E_LEFT_PATH_2"); + LoggedAutoTrajectory path3 = routine.trajectory("E_LEFT_PATH_3"); + LoggedAutoTrajectory path4 = routine.trajectory("E_LEFT_PATH_4"); + LoggedAutoTrajectory path5 = routine.trajectory("E_LEFT_PATH_5"); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + Commands.parallel( + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake, manipulator), + path3.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + path4.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake, manipulator), + path5.cmd())); + return routine; + } } diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 2384dffd..ae5df668 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -22,8 +22,6 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; -import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants.ManipulatorArmState; -import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants.ManipulatorRollerState; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; @@ -678,8 +676,24 @@ public static final Command emergencyEject( return Commands.sequence( superstructure.override( () -> { - manipulator.setArmGoal(frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState.EMERGENCY_EJECT_ANGLE); - manipulator.setRollerGoal(frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState.L4_SCORE); + manipulator.setArmGoal( + frc.robot + .subsystems + .v3_Epsilon + .superstructure + .manipulator + .V3_EpsilonManipulatorConstants + .ManipulatorArmState + .EMERGENCY_EJECT_ANGLE); + manipulator.setRollerGoal( + frc.robot + .subsystems + .v3_Epsilon + .superstructure + .manipulator + .V3_EpsilonManipulatorConstants + .ManipulatorRollerState + .L4_SCORE); })); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index c719780b..dc60ebbd 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -2,13 +2,12 @@ import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.Constants; import frc.robot.Constants.Mode; import frc.robot.RobotContainer; import frc.robot.RobotState; -import frc.robot.commands.CompositeCommands; +import frc.robot.commands.AutonomousCommands; import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.drive.DriveConstants; @@ -137,7 +136,6 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { - return CompositeCommands.V3_EpsilonCompositeCommands.emergencyEject( - manipulator, superstructure); + return AutonomousCommands.autoELeftPath(drive, superstructure, intake, manipulator).cmd(); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 79b4efad..77badd8a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -149,7 +149,8 @@ public static enum ManipulatorArmState { VERTICAL_UP(Rotation2d.fromDegrees(0)), HANDOFF(Rotation2d.kPi), SAFE_ANGLE(Rotation2d.fromDegrees(150)), - EMERGENCY_EJECT_ANGLE(Rotation2d.fromDegrees(90)); // Idk if tested. Looks fine but double check. + EMERGENCY_EJECT_ANGLE( + Rotation2d.fromDegrees(90)); // Idk if tested. Looks fine but double check. private final Rotation2d angle; From 2fd51bcf8c00d0c507161d8250d8b12d2264cd2b Mon Sep 17 00:00:00 2001 From: vaddadisri26 Date: Mon, 15 Sep 2025 19:44:29 -0400 Subject: [PATCH 096/180] Exceedingly UNFINISHED climber code!! Co-authored-by: SeptimusHeap7 Co-authored-by: Anshu Co-authored-by: Elliot Scher --- .../v3_Epsilon/climber/V3_EpsilonClimber.java | 111 +++++++++++++++++ .../climber/V3_EpsilonClimberConstants.java | 27 +++++ .../climber/V3_EpsilonClimberIO.java | 54 +++++++++ .../climber/V3_EpsilonClimberIOSim.java | 5 + .../climber/V3_EpsilonClimberIOTalonFX.java | 114 ++++++++++++++++++ 5 files changed, 311 insertions(+) create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIO.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOSim.java create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java new file mode 100644 index 00000000..2c7e06db --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java @@ -0,0 +1,111 @@ +package frc.robot.subsystems.v3_Epsilon.climber; + +import org.littletonrobotics.junction.AutoLogOutput; + +import frc.robot.util.ExternalLoggedTracer; +import frc.robot.util.InternalLoggedTracer; +import org.littletonrobotics.junction.Logger; + +import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; +import edu.wpi.first.wpilibj2.command.SubsystemBase; + +public class V3_EpsilonClimber extends SubsystemBase{ + private final V3_EpsilonClimberIO io; + private final V3_EpsilonClimberIOInputsAutoLogged inputs; + + @AutoLogOutput(key = "Climber/override") + private boolean override; + + @AutoLogOutput(key = "Climber/isClimbed") + private boolean isClimbed; + + public V3_EpsilonClimber(V3_EpsilonClimberIO io) { + this.io = io; + inputs = new V3_EpsilonClimberIOInputsAutoLogged(); + + isClimbed = false; + + override = false; + } + + @Override + public void periodic() { + ExternalLoggedTracer.reset(); + InternalLoggedTracer.reset(); + io.updateInputs(inputs); + InternalLoggedTracer.record("Climber Input Update", "Climber/Periodic"); + + InternalLoggedTracer.reset(); + Logger.processInputs("Climber", inputs); + InternalLoggedTracer.record("Climber Input Processing", "Climber/Periodic"); + + isClimbed = io.isClimbed(); + ExternalLoggedTracer.record("Climber Total", "Climber/Periodic"); + } + + /** + * Creates a command to set the voltage of the climber deployment motor. + * + * @param volts The voltage to set. + * @return A command to set the voltage. + */ + public Command setDeploymentVoltage(double volts) { + return Commands.run(() -> io.setDeploymentVoltage(volts)); + } + + /** + * Creates a command to set the voltage of the climber roller motor. + * + * @param volts The voltage to set. + * @return A command to set the voltage. + */ + public Command setRollerVoltage(double volts) { + return Commands.run(() -> io.setRollerVoltage(volts)); + } + + +//TODO: NOTHING BELOW THIS POINT WORKS!!! + + + /** + * Creates a command to release the climber. The climber is released by applying voltage until the + * position is greater than or equal to 20 radians. + * + * @return A command to release the climber. + */ + public Command releaseClimber() { + return this.runEnd(() -> io.setVoltage(1), () -> io.setVoltage(0)) + .until(() -> inputs.positionRadians >= 20); + } + + /** + * Creates a command to winch the climber. The climber is winched by applying voltage until the + * climb is complete. + * + * @return A command to winch the climber. + */ + public Command winchClimber() { + return Commands.runEnd(() -> io.setVoltage(12), () -> io.setVoltage(0)).until(() -> isClimbed); + } + + /** + * Creates a command to manually winch the climber with a lower voltage. + * + * @return A command to manually winch the climber. + */ + public Command winchClimberManual() { + return this.runEnd(() -> io.setVoltage(4), () -> io.setVoltage(0)); + } + + /** + * Creates a command to override the climber deployment readiness check. + * + * @param override True to override, false otherwise. + * @return A command to set the override. + */ + public Command manualDeployOverride(boolean override) { // set using debug board button + return Commands.runOnce(() -> this.override = override); + } + +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java new file mode 100644 index 00000000..68238f6a --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java @@ -0,0 +1,27 @@ +package frc.robot.subsystems.v3_Epsilon.climber; + +public class V3_EpsilonClimberConstants { + public static final int DEPLOYMENT_CAN_ID; + + public static final int ROLLER_CAN_ID; + + static { + DEPLOYMENT_CAN_ID = 42; + ROLLER_CAN_ID = 42; // This used to be 61, but there are two motors, so I replace this with 42 until + } + + public static final double CLIMBER_CLIMBED_ZERO_RADIANS = 41; //TODO: None of these four lines are valid numbers i just made up stuff + public static final double CLIMBER_CLIMBED_DEPLOYED_RADIANS = 67; + public static final ClimberTimingConfig CLIMBER_TIMING_CONFIG = new ClimberTimingConfig(1.1, 0.25, 0.5); + public static final CurrentLimits CURRENT_LIMITS = new CurrentLimits(40.0, 80.0); + + public static record CurrentLimits(double SUPPLY_CURRENT_LIMIT, double STATOR_CURRENT_LIMIT) { + } + + public static record ClimberTimingConfig( + double WAIT_AFTER_RELEASE_SECONDS, + double REDUNDANCY_DELAY_SECONDS, + double REDUNDANCY_TRUSTING_TIMEOUT_SECONDS) { + } + +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIO.java new file mode 100644 index 00000000..a9f30b92 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIO.java @@ -0,0 +1,54 @@ +package frc.robot.subsystems.v3_Epsilon.climber; + +import org.littletonrobotics.junction.AutoLog; + +import edu.wpi.first.math.geometry.Rotation2d; + +public interface V3_EpsilonClimberIO { + @AutoLog + public static class V3_EpsilonClimberIOInputs { + public Rotation2d deploymentPosition = new Rotation2d(); + public double deploymentVelocityRadiansPerSecond = 0.0; + public double deploymentAppliedVolts = 0.0; + public double deploymentSupplyCurrentAmps = 0.0; + public double deploymentTorqueCurrentAmps = 0.0; + public double deploymentTemperatureCelsius = 0.0; + + public Rotation2d rollerPosition = new Rotation2d(); + public double rollerVelocityRadiansPerSecond = 0.0; + public double rollerAppliedVolts = 0.0; + public double rollerSupplyCurrentAmps = 0.0; + public double rollerTorqueCurrentAmps = 0.0; + public double rollerTemperatureCelsius = 0.0; + } + /** + * Updates the inputs for the manipulator subsystem. + * + * @param inputs The inputs to update. + */ + public default void updateInputs(V3_EpsilonClimberIOInputs inputs) {} + + /** + * Sets the voltage for the intake. + * + * @param volts The voltage to set. + */ + public default void setDeploymentVoltage(double volts) {} + + /** + * Sets the voltage for the inner manipulator roller. + * + * @param volts The voltage to set. + */ + public default void setRollerVoltage(double volts) {} + + /** + * Gets the state of the climber based on the current draw. + * + * @return The state of the climber (climbed or not). + */ + public default boolean isClimbed() { + return false; + } + +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOSim.java new file mode 100644 index 00000000..73e68550 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOSim.java @@ -0,0 +1,5 @@ +package frc.robot.subsystems.v3_Epsilon.climber; + +public class V3_EpsilonClimberIOSim { + +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java new file mode 100644 index 00000000..e63169b3 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java @@ -0,0 +1,114 @@ +package frc.robot.subsystems.v3_Epsilon.climber; + +import static edu.wpi.first.units.Units.*; +import static frc.robot.util.PhoenixUtil.*; + +import com.ctre.phoenix6.StatusSignal; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.controls.MotionMagicVoltage; +import com.ctre.phoenix6.controls.VoltageOut; +import com.ctre.phoenix6.hardware.TalonFX; + +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.units.measure.Angle; +import edu.wpi.first.units.measure.AngularVelocity; +import edu.wpi.first.units.measure.Current; +import edu.wpi.first.units.measure.Temperature; +import edu.wpi.first.units.measure.Voltage; +import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIO.V3_EpsilonClimberIOInputs; +import frc.robot.util.PhoenixUtil; + +public class V3_EpsilonClimberIOTalonFX { + + private final TalonFX rollerTalonFX; + private final TalonFX deploymentTalonFX; + + private final TalonFXConfiguration rollerConfig; + private final TalonFXConfiguration deploymentConfig; + + private final VoltageOut rollerVoltageRequest; + + private final VoltageOut deploymentVoltageRequest; + + private final StatusSignal rollerPositionRotations; + private final StatusSignal rollerVelocityRotationsPerSecond; + private final StatusSignal rollerAppliedVoltage; + private final StatusSignal rollerSupplyCurrentAmps; + private final StatusSignal rollerTorqueCurrentAmps; + private final StatusSignal rollerTemperatureCelsius; + + private final StatusSignal deploymentPositionRotations; + private final StatusSignal deploymentVelocityRotationsPerSecond; + private final StatusSignal deploymentAppliedVoltage; + private final StatusSignal deploymentSupplyCurrentAmps; + private final StatusSignal deploymentTorqueCurrentAmps; + private final StatusSignal deploymentTemperatureCelsius; + + public V3_EpsilonClimberIOTalonFX(){ + rollerTalonFX = new TalonFX(V3_EpsilonClimberConstants.ROLLER_CAN_ID); + deploymentTalonFX = new TalonFX(V3_EpsilonClimberConstants.DEPLOYMENT_CAN_ID); + + rollerConfig = new TalonFXConfiguration(); + rollerPositionRotations = rollerTalonFX.getPosition(); + rollerVelocityRotationsPerSecond = rollerTalonFX.getVelocity(); + rollerAppliedVoltage = rollerTalonFX.getSupplyVoltage(); + rollerSupplyCurrentAmps = rollerTalonFX.getSupplyCurrent(); + rollerTorqueCurrentAmps = rollerTalonFX.getTorqueCurrent(); + rollerTemperatureCelsius = rollerTalonFX.getDeviceTemp(); + tryUntilOk(5, () -> rollerTalonFX.getConfigurator().apply(rollerConfig, 0.25)); + + deploymentConfig = new TalonFXConfiguration(); + deploymentPositionRotations = deploymentTalonFX.getPosition(); + deploymentVelocityRotationsPerSecond = deploymentTalonFX.getVelocity(); + deploymentAppliedVoltage = deploymentTalonFX.getSupplyVoltage(); + deploymentSupplyCurrentAmps = deploymentTalonFX.getSupplyCurrent(); + deploymentTorqueCurrentAmps = deploymentTalonFX.getTorqueCurrent(); + deploymentTemperatureCelsius = deploymentTalonFX.getDeviceTemp(); + tryUntilOk(5, () -> deploymentTalonFX.getConfigurator().apply(deploymentConfig, 0.25)); + + deploymentVoltageRequest = new VoltageOut(0); + rollerVoltageRequest = new VoltageOut(0); + + PhoenixUtil.registerSignals( + false, + deploymentPositionRotations, + deploymentVelocityRotationsPerSecond, + deploymentAppliedVoltage, + deploymentSupplyCurrentAmps, + deploymentTorqueCurrentAmps, + deploymentTemperatureCelsius, + rollerPositionRotations, + rollerVelocityRotationsPerSecond, + rollerAppliedVoltage, + rollerSupplyCurrentAmps, + rollerTorqueCurrentAmps, + rollerTemperatureCelsius); + } + @Override + public void updateInputs(V3_EpsilonClimberIOInputs inputs) { + inputs.deploymentPosition = new Rotation2d(deploymentPositionRotations.getValue()); + inputs.deploymentVelocityRadiansPerSecond = + deploymentVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); + inputs.deploymentAppliedVolts = deploymentAppliedVoltage.getValueAsDouble(); + inputs.deploymentSupplyCurrentAmps = deploymentSupplyCurrentAmps.getValueAsDouble(); + inputs.deploymentTorqueCurrentAmps = deploymentTorqueCurrentAmps.getValueAsDouble(); + inputs.deploymentTemperatureCelsius = deploymentTemperatureCelsius.getValueAsDouble(); + + inputs.rollerPosition = new Rotation2d(rollerPositionRotations.getValue()); + inputs.rollerVelocityRadiansPerSecond = + rollerVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); + inputs.rollerAppliedVolts = rollerAppliedVoltage.getValueAsDouble(); + inputs.rollerSupplyCurrentAmps = rollerSupplyCurrentAmps.getValueAsDouble(); + inputs.rollerTorqueCurrentAmps = rollerTorqueCurrentAmps.getValueAsDouble(); + inputs.rollerTemperatureCelsius = rollerTemperatureCelsius.getValueAsDouble(); + } + + public void setdeploymentVoltage(double volts) { + deploymentTalonFX.setControl(deploymentVoltageRequest.withOutput(volts).withEnableFOC(true)); + } + + public void setRollerVoltage(double volts) { + rollerTalonFX.setControl(rollerVoltageRequest.withOutput(volts).withEnableFOC(true)); + } + +} From 23099e0029b2cabb3f92ceb8074ab9916e281a75 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Mon, 15 Sep 2025 19:46:12 -0400 Subject: [PATCH 097/180] Worked on 3-piece auto --> still in the making --- .../frc/robot/commands/AutonomousCommands.java | 14 +++++++------- .../java/frc/robot/commands/CompositeCommands.java | 6 ------ .../v3_Epsilon/V3_EpsilonRobotContainer.java | 2 -- .../V3_EpsilonSuperstructureEdges.java | 7 ++++--- .../superstructure/intake/V3_EpsilonIntakeIO.java | 2 +- 5 files changed, 12 insertions(+), 19 deletions(-) diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index 30ee7c15..78c28007 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -1869,22 +1869,22 @@ public static final LoggedAutoRoutine autoELeftPath( path1.resetOdometry(), Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), path1.cmd(), - Commands.parallel( - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, cameras), + Commands.print("Scored first coral"), path2.cmd(), CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( superstructure, intake, manipulator), path3.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), path4.cmd(), CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( superstructure, intake, manipulator), path5.cmd())); + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, cameras); return routine; } } diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 4fda046d..0c016613 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -669,11 +669,6 @@ public static final Command intakeCoralDriverSequence( Commands.waitSeconds(0.2), superstructure.runGoalUntil( V3_EpsilonSuperstructureStates.HANDOFF, () -> manipulator.hasCoral())); -<<<<<<< HEAD - // superstructure.runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE), - // Commands.waitSeconds(0.2), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF)); -======= } /** @@ -855,7 +850,6 @@ public static final Command intakeCoralFromGround( superstructure.runGoalUntil( V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoral()), superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF)); ->>>>>>> feature-v3 } public static final Command emergencyEject( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 5bff421c..e036cec2 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -7,7 +7,6 @@ import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.Constants; import frc.robot.Constants.Mode; -import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotContainer; import frc.robot.RobotState; import frc.robot.commands.AutonomousCommands; @@ -28,7 +27,6 @@ import frc.robot.subsystems.shared.vision.VisionConstants.RobotCameras; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIO; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOSim; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index badc1c9b..fe462b9a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -11,7 +11,6 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakePivotState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; import java.io.FileReader; import java.io.Reader; import java.util.ArrayList; @@ -289,8 +288,10 @@ private static boolean willCollide( Rotation2d armAngle = from.getPose() .getArmState() - .getAngle(Side.POSITIVE) - .interpolate(to.getPose().getArmState().getAngle(Side.POSITIVE), t); + .getAngle(V3_EpsilonManipulatorConstants.Side.POSITIVE) + .interpolate( + to.getPose().getArmState().getAngle(V3_EpsilonManipulatorConstants.Side.POSITIVE), + t); // Interpolate intake angle Rotation2d intakeAngle = diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java index 3375045b..076e7a40 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java @@ -5,7 +5,7 @@ public interface V3_EpsilonIntakeIO { @AutoLog - public static class V3_EpsilonIntakeIOInputs { + public class V3_EpsilonIntakeIOInputs { public Rotation2d pivotPosition = new Rotation2d(); public double pivotVelocityRadiansPerSecond = 0.0; public double pivotAppliedVolts = 0.0; From 29a931c609ea02a3d8a578481e8b5c9f19a2bdb0 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Thu, 18 Sep 2025 18:19:37 -0400 Subject: [PATCH 098/180] finally a working 3-piece --- src/main/deploy/choreo/E_LEFT_PATH_2.traj | 89 ++++++++++--------- .../robot/commands/AutonomousCommands.java | 41 +++++++-- 2 files changed, 78 insertions(+), 52 deletions(-) diff --git a/src/main/deploy/choreo/E_LEFT_PATH_2.traj b/src/main/deploy/choreo/E_LEFT_PATH_2.traj index 942de388..10315d08 100644 --- a/src/main/deploy/choreo/E_LEFT_PATH_2.traj +++ b/src/main/deploy/choreo/E_LEFT_PATH_2.traj @@ -3,8 +3,8 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":5.348966598510742, "y":2.7028448581695557, "heading":-2.5111212813673753, "intervals":37, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.0581276416778564, "y":2.202970504760742, "heading":-3.0828368900825525, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":5.517795562744141, "y":2.4597244262695312, "heading":-2.5111212813673753, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.6639331579208374, "y":2.2330267429351807, "heading":-3.0828368900825525, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -13,8 +13,8 @@ }, "params":{ "waypoints":[ - {"x":{"exp":"5.348966598510742 m", "val":5.348966598510742}, "y":{"exp":"2.7028448581695557 m", "val":2.7028448581695557}, "heading":{"exp":"-2.5111212813673753 rad", "val":-2.5111212813673753}, "intervals":37, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.0581276416778564 m", "val":2.0581276416778564}, "y":{"exp":"2.202970504760742 m", "val":2.202970504760742}, "heading":{"exp":"-3.0828368900825525 rad", "val":-3.0828368900825525}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"5.517795562744141 m", "val":5.517795562744141}, "y":{"exp":"2.4597244262695312 m", "val":2.4597244262695312}, "heading":{"exp":"-2.5111212813673753 rad", "val":-2.5111212813673753}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.6639331579208374 m", "val":1.6639331579208374}, "y":{"exp":"2.2330267429351807 m", "val":2.2330267429351807}, "heading":{"exp":"-3.0828368900825525 rad", "val":-3.0828368900825525}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -26,46 +26,49 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,1.45697], + "waypoints":[0.0,1.59126], "samples":[ - {"t":0.0, "x":5.34897, "y":2.70284, "heading":-2.51112, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.35198, "ay":-0.96328, "alpha":-1.94512, "fx":[-109.02528,-105.79351,-107.64778,-109.71517], "fy":[-12.66193,-29.20409,-21.2697,-2.40456]}, - {"t":0.03938, "x":5.34404, "y":2.7021, "heading":-2.51112, "vx":-0.25013, "vy":-0.03793, "omega":-0.07659, "ax":-6.35236, "ay":-0.96338, "alpha":-1.91377, "fx":[-109.01122,-105.83876,-107.65589,-109.70119], "fy":[-12.71689,-29.00918,-21.18109,-2.64026]}, - {"t":0.07876, "x":5.32927, "y":2.69986, "heading":-2.51414, "vx":-0.50027, "vy":-0.07587, "omega":-0.15195, "ax":-6.35276, "ay":-0.9635, "alpha":-1.87782, "fx":[-108.99904,-105.89488,-107.65657,-109.68418], "fy":[-12.745,-28.76822,-21.12291,-2.91957]}, - {"t":0.11813, "x":5.30464, "y":2.69612, "heading":-2.52012, "vx":-0.75042, "vy":-0.11381, "omega":-0.2259, "ax":-6.35321, "ay":-0.96365, "alpha":-1.83602, "fx":[-108.98785,-105.963,-107.65099,-109.6632], "fy":[-12.75132,-28.47462,-21.08786,-3.25155]}, - {"t":0.15751, "x":5.27017, "y":2.69089, "heading":-2.52902, "vx":-1.00059, "vy":-0.15175, "omega":-0.2982, "ax":-6.3537, "ay":-0.96381, "alpha":-1.78663, "fx":[-108.97642,-106.04466,-107.64062,-109.6369], "fy":[-12.74267,-28.11907,-21.06618,-3.64871]}, - {"t":0.19689, "x":5.22584, "y":2.68417, "heading":-2.54076, "vx":-1.25079, "vy":-0.18971, "omega":-0.36855, "ax":-6.35425, "ay":-0.96401, "alpha":-1.72728, "fx":[-108.96301,-106.14203,-107.6274,-109.60327], "fy":[-12.72848,-27.68834,-21.04474,-4.1284]}, - {"t":0.23627, "x":5.17166, "y":2.67595, "heading":-2.55527, "vx":-1.501, "vy":-0.22767, "omega":-0.43656, "ax":-6.35485, "ay":-0.96424, "alpha":-1.65448, "fx":[-108.94515,-106.25814,-107.614,-109.55924], "fy":[-12.72218,-27.16322,-21.0053,-4.71518]}, - {"t":0.27564, "x":5.10763, "y":2.66624, "heading":-2.57246, "vx":-1.75124, "vy":-0.26564, "omega":-0.50171, "ax":-6.35549, "ay":-0.96453, "alpha":-1.56306, "fx":[-108.91909,-106.39734,-107.60415,-109.49995], "fy":[-12.74374,-26.51472,-20.92182,-5.44496]}, - {"t":0.31502, "x":5.03374, "y":2.65503, "heading":-2.59222, "vx":-2.0015, "vy":-0.30362, "omega":-0.56326, "ax":-6.35615, "ay":-0.96488, "alpha":-1.44488, "fx":[-108.87888,-106.56612,-107.60319,-109.4172], "fy":[-12.8244,-25.69698,-20.75536,-6.37247]}, - {"t":0.3544, "x":4.95, "y":2.64233, "heading":-2.6144, "vx":-2.25179, "vy":-0.34161, "omega":-0.62016, "ax":-6.35672, "ay":-0.96532, "alpha":-1.28639, "fx":[-108.81429,-106.77454,-107.61911,-109.29629], "fy":[-13.01636,-24.63252,-20.44441,-7.58618]}, - {"t":0.39378, "x":4.8564, "y":2.62813, "heading":-2.63882, "vx":-2.50211, "vy":-0.37962, "omega":-0.67081, "ax":-6.35692, "ay":-0.96589, "alpha":-1.06325, "fx":[-108.70576,-107.03897,-107.66414,-109.10841], "fy":[-13.41493,-23.17861,-19.88444,-9.24003]}, - {"t":0.43315, "x":4.75295, "y":2.61243, "heading":-2.66523, "vx":-2.75243, "vy":-0.41766, "omega":-0.71268, "ax":-6.35585, "ay":-0.96659, "alpha":-0.72675, "fx":[-108.51006,-107.38703,-107.75764,-108.78978], "fy":[-14.21673,-21.0393,-18.87943,-11.63011]}, - {"t":0.47253, "x":4.63964, "y":2.59524, "heading":-2.6933, "vx":-3.0027, "vy":-0.45572, "omega":-0.7413, "ax":-6.35038, "ay":-0.96726, "alpha":-0.16257, "fx":[-108.10865,-107.8624,-107.92964,-108.17207], "fy":[-15.90872,-17.48427,-17.00812,-15.41048]}, - {"t":0.51191, "x":4.51647, "y":2.57654, "heading":-2.72249, "vx":-3.25276, "vy":-0.49381, "omega":-0.7477, "ax":-6.32529, "ay":-0.96656, "alpha":0.98037, "fx":[-107.02718,-108.45923,-108.20987,-106.6695], "fy":[-20.13408,-10.11251,-13.15773,-22.35904]}, - {"t":0.55129, "x":4.38348, "y":2.55635, "heading":-2.75193, "vx":-3.50184, "vy":-0.53187, "omega":-0.7091, "ax":-6.12005, "ay":-0.95661, "alpha":4.67736, "fx":[-100.49665,-106.65948,-108.33415,-100.91085], "fy":[-37.90019,15.22165,-3.14796,-39.26016]}, - {"t":0.59066, "x":4.24084, "y":2.53466, "heading":-2.77985, "vx":-3.74283, "vy":-0.56954, "omega":-0.52491, "ax":-4.55043, "ay":-0.81413, "alpha":13.23792, "fx":[-48.34701,-73.6012,-101.80637,-85.85153], "fy":[-73.51748,61.60476,11.04017,-54.51971]}, - {"t":0.63004, "x":4.08993, "y":2.5116, "heading":-2.80052, "vx":-3.92202, "vy":-0.6016, "omega":-0.00364, "ax":-0.04133, "ay":0.13987, "alpha":0.05126, "fx":[-0.5331,-0.62211,-0.87302,-0.78405], "fy":[2.29841,2.54909,2.46005,2.20935]}, - {"t":0.66942, "x":3.93546, "y":2.48802, "heading":-2.80067, "vx":-3.92364, "vy":-0.59609, "omega":-0.00162, "ax":-0.00542, "ay":0.03566, "alpha":0.00002, "fx":[-0.09214,-0.09218,-0.0923,-0.09226], "fy":[0.60645,0.60656,0.60652,0.60641]}, - {"t":0.7088, "x":3.78095, "y":2.46458, "heading":-2.80073, "vx":-3.92386, "vy":-0.59468, "omega":-0.00162, "ax":-0.00018, "ay":0.0012, "alpha":0.0, "fx":[-0.0031,-0.0031,-0.0031,-0.0031], "fy":[0.02043,0.02043,0.02043,0.02043]}, - {"t":0.74817, "x":3.62644, "y":2.44116, "heading":-2.80079, "vx":-3.92386, "vy":-0.59464, "omega":-0.00162, "ax":0.00468, "ay":-0.0308, "alpha":-0.00002, "fx":[0.07959,0.07963,0.07973,0.07969], "fy":[-0.5239,-0.524,-0.52397,-0.52386]}, - {"t":0.78755, "x":3.47193, "y":2.41772, "heading":-2.80086, "vx":-3.92368, "vy":-0.59585, "omega":-0.00162, "ax":0.03733, "ay":-0.12289, "alpha":-0.04753, "fx":[0.47742,0.55987,0.79252,0.7101], "fy":[-2.01537,-2.24786,-2.16537,-1.93287]}, - {"t":0.82693, "x":3.31746, "y":2.39416, "heading":-2.80092, "vx":-3.92221, "vy":-0.60069, "omega":-0.00349, "ax":4.51366, "ay":0.79224, "alpha":-13.27529, "fx":[47.44047,72.48004,101.26907,85.91498], "fy":[73.48903,-61.37315,-11.87098,53.65821]}, - {"t":0.86631, "x":3.16651, "y":2.37113, "heading":-2.80106, "vx":-3.74447, "vy":-0.56949, "omega":-0.52624, "ax":6.14585, "ay":0.95615, "alpha":-4.28031, "fx":[100.95334,107.0891,108.30852,101.80564], "fy":[36.94067,-11.75394,3.00643,36.86225]}, - {"t":0.90568, "x":3.02383, "y":2.34944, "heading":-2.82178, "vx":-3.50246, "vy":-0.53184, "omega":-0.69479, "ax":6.32696, "ay":0.96703, "alpha":-0.85699, "fx":[107.03052,108.34714,108.21534,106.88637], "fy":[20.18004,11.25359,13.05576,21.30649]}, - {"t":0.94506, "x":2.89081, "y":2.32925, "heading":-2.84914, "vx":-3.25332, "vy":-0.49376, "omega":-0.72853, "ax":6.35029, "ay":0.96741, "alpha":0.20417, "fx":[108.1578,107.84204,107.87522,108.19131], "fy":[15.58109,17.62475,17.34924,15.26633]}, - {"t":0.98444, "x":2.76763, "y":2.31056, "heading":-2.87783, "vx":-3.00327, "vy":-0.45567, "omega":-0.72049, "ax":6.35583, "ay":0.9667, "alpha":0.72915, "fx":[108.62559,107.50725,107.5865,108.72391], "fy":[13.29071,20.43719,19.84852,12.19663]}, - {"t":1.02382, "x":2.6543, "y":2.29336, "heading":-2.9062, "vx":-2.75299, "vy":-0.4176, "omega":-0.69178, "ax":6.35722, "ay":0.966, "alpha":1.04377, "fx":[108.88606,107.30638,107.34844,108.99723], "fy":[11.83387,21.93178,21.54884,10.41077]}, - {"t":1.06319, "x":2.55082, "y":2.27767, "heading":-2.93344, "vx":-2.50266, "vy":-0.37956, "omega":-0.65068, "ax":6.35735, "ay":0.96541, "alpha":1.25374, "fx":[109.05468,107.18618,107.14815,109.15762], "fy":[10.78027,22.80124,22.81349,9.29036]}, - {"t":1.10257, "x":2.4572, "y":2.26347, "heading":-2.95906, "vx":-2.25232, "vy":-0.34155, "omega":-0.60131, "ax":6.35704, "ay":0.96493, "alpha":1.40393, "fx":[109.17395,107.11505,106.97658,109.26033], "fy":[9.96024,23.33101,23.80623,8.55496]}, - {"t":1.14195, "x":2.37344, "y":2.25077, "heading":-2.98274, "vx":-2.002, "vy":-0.30355, "omega":-0.54603, "ax":6.3566, "ay":0.96452, "alpha":1.51668, "fx":[109.26316,107.07436,106.82796,109.33026], "fy":[9.29375,23.66111,24.61206,8.058]}, - {"t":1.18133, "x":2.29953, "y":2.23956, "heading":-3.00424, "vx":-1.75169, "vy":-0.26557, "omega":-0.4863, "ax":6.35613, "ay":0.96418, "alpha":1.60439, "fx":[109.33238,107.05265,106.6985,109.38018], "fy":[8.7382,23.86887,25.27991,7.71457]}, - {"t":1.2207, "x":2.23548, "y":2.22985, "heading":-3.02339, "vx":-1.5014, "vy":-0.2276, "omega":-0.42313, "ax":6.35567, "ay":0.96388, "alpha":1.67454, "fx":[109.38742,107.04248,106.5856,109.41729], "fy":[8.26877,24.00088,25.84028,7.47152]}, - {"t":1.26008, "x":2.18129, "y":2.22164, "heading":-3.04005, "vx":-1.25113, "vy":-0.18965, "omega":-0.35719, "ax":6.35525, "ay":0.96363, "alpha":1.73189, "fx":[109.4319,107.03879,106.48738,109.44594], "fy":[7.86997,24.0871,26.31345,7.29347]}, - {"t":1.29946, "x":2.13695, "y":2.21492, "heading":-3.05412, "vx":-1.00088, "vy":-0.1517, "omega":-0.28899, "ax":6.35486, "ay":0.9634, "alpha":1.77964, "fx":[109.46819,107.03808,106.40241,109.46897], "fy":[7.5316,24.14783,26.71356,7.15577]}, - {"t":1.33884, "x":2.10246, "y":2.20969, "heading":-3.0655, "vx":-0.75064, "vy":-0.11377, "omega":-0.21891, "ax":6.35451, "ay":0.96321, "alpha":1.82002, "fx":[109.49795,107.0378,106.32961,109.4883], "fy":[7.24665,24.19735,27.05085,7.04055]}, - {"t":1.37821, "x":2.07783, "y":2.20596, "heading":-3.07412, "vx":-0.50041, "vy":-0.07584, "omega":-0.14725, "ax":6.35419, "ay":0.96303, "alpha":1.85464, "fx":[109.52234,107.03606,106.26812,109.50529], "fy":[7.01019,24.24605,27.33291,6.93456]}, - {"t":1.41759, "x":2.06305, "y":2.20372, "heading":-3.07991, "vx":-0.2502, "vy":-0.03792, "omega":-0.07421, "ax":6.3539, "ay":0.96288, "alpha":1.88468, "fx":[109.54223,107.03143,106.21728,109.52091], "fy":[6.81865,24.30167,27.56543,6.82775]}, - {"t":1.45697, "x":2.05813, "y":2.20297, "heading":-3.08284, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":5.5178, "y":2.45972, "heading":-2.51112, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.41292, "ay":-0.37634, "alpha":-1.96876, "fx":[-109.69694,-107.90591,-109.27826,-109.44671], "fy":[-3.70309,-20.03584,-9.93912,8.07232]}, + {"t":0.03978, "x":5.51272, "y":2.45943, "heading":-2.51112, "vx":-0.25511, "vy":-0.01497, "omega":-0.07832, "ax":-6.41338, "ay":-0.37644, "alpha":-1.93509, "fx":[-109.68786,-107.93902,-109.27517,-109.45679], "fy":[-3.74607,-19.81158,-9.87086,7.81598]}, + {"t":0.07956, "x":5.4975, "y":2.45853, "heading":-2.51424, "vx":-0.51025, "vy":-0.02995, "omega":-0.1553, "ax":-6.41388, "ay":-0.37656, "alpha":-1.89635, "fx":[-109.67859,-107.97926,-109.26727,-109.46789], "fy":[-3.75796,-19.53837,-9.84042,7.51603]}, + {"t":0.11934, "x":5.47212, "y":2.45704, "heading":-2.52042, "vx":-0.7654, "vy":-0.04493, "omega":-0.23074, "ax":-6.41444, "ay":-0.3767, "alpha":-1.85115, "fx":[-109.66865,-108.02733,-109.2549,-109.48], "fy":[-3.74376,-19.2082,-9.84042,7.16185]}, + {"t":0.15913, "x":5.4366, "y":2.45496, "heading":-2.52959, "vx":-1.02058, "vy":-0.05991, "omega":-0.30438, "ax":-6.41506, "ay":-0.37688, "alpha":-1.79759, "fx":[-109.65733,-108.08423,-109.23849,-109.49301], "fy":[-3.71018,-18.80975,-9.86108,6.7388]}, + {"t":0.19891, "x":5.39092, "y":2.45228, "heading":-2.5417, "vx":-1.27578, "vy":-0.07491, "omega":-0.37589, "ax":-6.41575, "ay":-0.37708, "alpha":-1.73299, "fx":[-109.64367,-108.15126,-109.21858,-109.50663], "fy":[-3.66652,-18.32692,-9.88923,6.22642]}, + {"t":0.23869, "x":5.33509, "y":2.449, "heading":-2.55666, "vx":-1.531, "vy":-0.08991, "omega":-0.44483, "ax":-6.41652, "ay":-0.37733, "alpha":-1.65348, "fx":[-109.62626,-108.23017,-109.19592,-109.52015], "fy":[-3.6261,-17.73621,-9.9066,5.59559]}, + {"t":0.27847, "x":5.26911, "y":2.44512, "heading":-2.57435, "vx":-1.78626, "vy":-0.10492, "omega":-0.51061, "ax":-6.41736, "ay":-0.37765, "alpha":-1.55316, "fx":[-109.60297,-108.32331,-109.17151,-109.53197], "fy":[-3.6088,-17.00204,-9.88705,4.80331]}, + {"t":0.31825, "x":5.19297, "y":2.44065, "heading":-2.59467, "vx":-2.04155, "vy":-0.11994, "omega":-0.5724, "ax":-6.41824, "ay":-0.37805, "alpha":-1.42271, "fx":[-109.57038,-108.4338,-109.14676,-109.53865], "fy":[-3.64601,-16.06768,-9.79141,3.78326]}, + {"t":0.35803, "x":5.10668, "y":2.43558, "heading":-2.61744, "vx":-2.29688, "vy":-0.13498, "omega":-0.62899, "ax":-6.41904, "ay":-0.37858, "alpha":-1.24641, "fx":[-109.52242,-108.56565,-109.12345,-109.53254], "fy":[-3.79087,-14.83638,-9.55768,2.42672]}, + {"t":0.39781, "x":5.01023, "y":2.42991, "heading":-2.64246, "vx":-2.55224, "vy":-0.15004, "omega":-0.67858, "ax":-6.41941, "ay":-0.37933, "alpha":-0.99549, "fx":[-109.447,-108.72311,-109.10344,-109.4955], "fy":[-4.14223,-13.12767,-9.07996,0.54089]}, + {"t":0.4376, "x":4.90362, "y":2.42364, "heading":-2.66945, "vx":-2.80761, "vy":-0.16513, "omega":-0.71818, "ax":-6.4182, "ay":-0.38042, "alpha":-0.61115, "fx":[-109.31557,-108.90532,-109.08679,-109.37952], "fy":[-4.90996,-10.56033,-8.15843,-2.25438]}, + {"t":0.47738, "x":4.78685, "y":2.41677, "heading":-2.69802, "vx":-3.06294, "vy":-0.18026, "omega":-0.74249, "ax":-6.41113, "ay":-0.38205, "alpha":0.04933, "fx":[-109.04148,-109.07029,-109.06194,-109.03243], "fy":[-6.63932,-6.16711,-6.35863,-6.8291]}, + {"t":0.51716, "x":4.65993, "y":2.4093, "heading":-2.72756, "vx":-3.31798, "vy":-0.19546, "omega":-0.74053, "ax":-6.37525, "ay":-0.38444, "alpha":1.45025, "fx":[-108.2106,-108.80696,-108.9453,-107.80215], "fy":[-11.35268,3.38565,-2.50906,-15.68053]}, + {"t":0.55694, "x":4.52289, "y":2.40122, "heading":-2.75702, "vx":-3.5716, "vy":-0.21076, "omega":-0.68284, "ax":-6.00304, "ay":-0.42971, "alpha":6.65301, "fx":[-99.73923,-99.97772,-107.97431,-100.74902], "fy":[-37.28329,39.21902,7.9724,-39.14537]}, + {"t":0.59672, "x":4.37605, "y":2.39249, "heading":-2.78418, "vx":-3.81041, "vy":-0.22785, "omega":-0.41817, "ax":-3.79868, "ay":-0.18364, "alpha":10.4581, "fx":[-39.53907,-56.05704,-87.0549,-75.80654], "fy":[-36.56418,49.51495,14.16573,-39.61116]}, + {"t":0.6365, "x":4.22147, "y":2.38329, "heading":-2.80082, "vx":-3.96152, "vy":-0.23516, "omega":-0.00213, "ax":-0.00936, "ay":0.07093, "alpha":0.01231, "fx":[-0.11836,-0.13972,-0.19994,-0.17859], "fy":[1.18715,1.24737,1.22601,1.16579]}, + {"t":0.67628, "x":4.06386, "y":2.37399, "heading":-2.8009, "vx":-3.96189, "vy":-0.23233, "omega":-0.00164, "ax":-0.00109, "ay":0.01852, "alpha":0.00001, "fx":[-0.01847,-0.01848,-0.01851,-0.0185], "fy":[0.31495,0.31498,0.31497,0.31494]}, + {"t":0.71607, "x":3.90625, "y":2.36476, "heading":-2.80097, "vx":-3.96194, "vy":-0.2316, "omega":-0.00164, "ax":-0.00028, "ay":0.00475, "alpha":0.0, "fx":[-0.00472,-0.00472,-0.00472,-0.00472], "fy":[0.08076,0.08076,0.08076,0.08076]}, + {"t":0.75585, "x":3.74864, "y":2.35555, "heading":-2.80104, "vx":-3.96195, "vy":-0.23141, "omega":-0.00164, "ax":-0.00006, "ay":0.00097, "alpha":0.0, "fx":[-0.00096,-0.00096,-0.00096,-0.00096], "fy":[0.01647,0.01647,0.01647,0.01647]}, + {"t":0.79563, "x":3.59103, "y":2.34634, "heading":-2.8011, "vx":-3.96195, "vy":-0.23137, "omega":-0.00164, "ax":0.00005, "ay":-0.00077, "alpha":0.0, "fx":[0.00077,0.00077,0.00077,0.00077], "fy":[-0.01315,-0.01315,-0.01315,-0.01315]}, + {"t":0.83541, "x":3.43342, "y":2.33714, "heading":-2.80117, "vx":-3.96195, "vy":-0.2314, "omega":-0.00164, "ax":0.00024, "ay":-0.00414, "alpha":0.0, "fx":[0.00412,0.00412,0.00412,0.00412], "fy":[-0.07044,-0.07044,-0.07044,-0.07044]}, + {"t":0.87519, "x":3.27581, "y":2.32793, "heading":-2.80123, "vx":-3.96194, "vy":-0.23157, "omega":-0.00164, "ax":0.00095, "ay":-0.01622, "alpha":-0.00001, "fx":[0.01618,0.01619,0.01621,0.01621], "fy":[-0.27595,-0.27597,-0.27596,-0.27594]}, + {"t":0.91497, "x":3.1182, "y":2.31871, "heading":-2.8013, "vx":-3.9619, "vy":-0.23221, "omega":-0.00164, "ax":0.00859, "ay":-0.06215, "alpha":-0.01172, "fx":[0.10733,0.12764,0.185,0.16469], "fy":[-1.03858,-1.09594,-1.07563,-1.01828]}, + {"t":0.95475, "x":2.96059, "y":2.30942, "heading":-2.80136, "vx":-3.96156, "vy":-0.23468, "omega":-0.00211, "ax":3.74383, "ay":0.18381, "alpha":-10.38927, "fx":[38.63065,54.742,86.07774,75.27533], "fy":[36.6843,-48.52207,-14.50139,38.84566]}, + {"t":0.99453, "x":2.80596, "y":2.30023, "heading":-2.80145, "vx":-3.81262, "vy":-0.22737, "omega":-0.41541, "ax":6.04123, "ay":0.4178, "alpha":-6.26759, "fx":[100.2435,101.15932,107.90649,101.72891], "fy":[36.45913,-35.99892,-8.58286,36.54904]}, + {"t":1.03432, "x":2.65907, "y":2.29151, "heading":-2.81797, "vx":-3.5723, "vy":-0.21075, "omega":-0.66474, "ax":6.37756, "ay":0.38482, "alpha":-1.34794, "fx":[108.17792,108.83471,108.95104,107.95846], "fy":[11.81166,-2.29041,2.04165,14.61955]}, + {"t":1.0741, "x":2.522, "y":2.28343, "heading":-2.84442, "vx":-3.31859, "vy":-0.19544, "omega":-0.71837, "ax":6.41124, "ay":0.38226, "alpha":-0.02652, "fx":[109.04644,109.06258,109.06029,109.04403], "fy":[6.60281,6.33688,6.40162,6.66693]}, + {"t":1.11388, "x":2.39506, "y":2.27596, "heading":-2.87299, "vx":-3.06354, "vy":-0.18023, "omega":-0.71942, "ax":6.41837, "ay":0.38058, "alpha":0.59745, "fx":[109.34501,108.95767,109.0298,109.36617], "fy":[4.17916,10.04788,8.92797,2.73893]}, + {"t":1.15366, "x":2.27826, "y":2.26909, "heading":-2.90161, "vx":-2.80821, "vy":-0.16509, "omega":-0.69565, "ax":6.41991, "ay":0.37946, "alpha":0.96257, "fx":[109.49032,108.8567,108.96516,109.49099], "fy":[2.67284,12.01576,10.66012,0.46943]}, + {"t":1.19344, "x":2.17163, "y":2.26283, "heading":-2.92929, "vx":-2.55282, "vy":-0.15, "omega":-0.65736, "ax":6.41985, "ay":0.37869, "alpha":1.20288, "fx":[109.57333,108.78575,108.89156,109.54865], "fy":[1.59003,13.17432,11.96434,-0.9634]}, + {"t":1.23322, "x":2.07516, "y":2.25716, "heading":-2.95544, "vx":-2.29742, "vy":-0.13493, "omega":-0.60951, "ax":6.4193, "ay":0.37811, "alpha":1.37331, "fx":[109.62497,108.73968,108.81735,109.5795], "fy":[0.74635,13.89718,13.00174,-1.91904]}, + {"t":1.273, "x":1.98884, "y":2.25209, "heading":-2.97969, "vx":-2.04206, "vy":-0.11989, "omega":-0.55488, "ax":6.4186, "ay":0.37766, "alpha":1.50056, "fx":[109.65866,108.71125,108.74597,109.59847], "fy":[0.05801,14.36402,13.85438,-2.58053]}, + {"t":1.31279, "x":1.91268, "y":2.24762, "heading":-3.00176, "vx":-1.78672, "vy":-0.10487, "omega":-0.49518, "ax":6.4179, "ay":0.3773, "alpha":1.59923, "fx":[109.68121,108.6947,108.67908,109.61169], "fy":[-0.51833,14.67266,14.56877,-3.05177]}, + {"t":1.35257, "x":1.84668, "y":2.24375, "heading":-3.02146, "vx":-1.5314, "vy":-0.08986, "omega":-0.43156, "ax":6.41724, "ay":0.377, "alpha":1.67796, "fx":[109.69655,108.68579,108.61759,109.62183], "fy":[-1.00731,14.88138,15.17362,-3.39681]}, + {"t":1.39235, "x":1.79084, "y":2.24047, "heading":-3.03863, "vx":-1.27612, "vy":-0.07486, "omega":-0.36481, "ax":6.41664, "ay":0.37675, "alpha":1.7422, "fx":[109.70708,108.68144,108.56198,109.63007], "fy":[-1.42402,15.02738,15.68786,-3.65772]}, + {"t":1.43213, "x":1.74515, "y":2.23779, "heading":-3.05314, "vx":-1.02085, "vy":-0.05987, "omega":-0.29551, "ax":6.41609, "ay":0.37653, "alpha":1.79561, "fx":[109.71444,108.67938,108.51253,109.6369], "fy":[-1.77819,15.13566,16.12467,-3.86357]}, + {"t":1.47191, "x":1.70962, "y":2.23571, "heading":-3.0649, "vx":-0.76561, "vy":-0.0449, "omega":-0.22407, "ax":6.41559, "ay":0.37634, "alpha":1.8407, "fx":[109.71973,108.67795,108.4694,109.64252], "fy":[-2.07642,15.22374,16.49357,-4.03525]}, + {"t":1.51169, "x":1.68424, "y":2.23422, "heading":-3.07381, "vx":-0.51039, "vy":-0.02992, "omega":-0.15085, "ax":6.41515, "ay":0.37617, "alpha":1.87927, "fx":[109.72376,108.67587,108.43266,109.64694], "fy":[-2.32329,15.30432,16.8016,-4.18817]}, + {"t":1.55147, "x":1.66901, "y":2.23332, "heading":-3.07981, "vx":-0.25519, "vy":-0.01496, "omega":-0.07609, "ax":6.41474, "ay":0.37603, "alpha":1.91264, "fx":[109.72713,108.67217,108.40236,109.65012], "fy":[-2.52204,15.38678,17.05403,-4.33396]}, + {"t":1.59126, "x":1.66393, "y":2.23303, "heading":-3.08284, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index 78c28007..8ab4af0c 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -1855,6 +1855,7 @@ public static final LoggedAutoRoutine autoELeftPath( V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator, Camera... cameras) { + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoELeftPath"); LoggedAutoTrajectory path1 = routine.trajectory("E_LEFT_PATH_1"); LoggedAutoTrajectory path2 = routine.trajectory("E_LEFT_PATH_2"); @@ -1870,21 +1871,43 @@ public static final LoggedAutoRoutine autoELeftPath( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), path1.cmd(), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( - drive, superstructure, cameras), - Commands.print("Scored first coral"), + drive, superstructure, cameras) + .withTimeout(0.5), + CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral( + superstructure, () -> ReefState.L4), path2.cmd(), CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake, manipulator), + superstructure, intake, manipulator) + .withTimeout(0.5), + superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF), path3.cmd(), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( - drive, superstructure, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + drive, superstructure, cameras) + .withTimeout(0.5), + CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral( + superstructure, () -> ReefState.L4), path4.cmd(), CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake, manipulator), - path5.cmd())); - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( - drive, superstructure, cameras); + superstructure, intake, manipulator) + .withTimeout(0.5), + path5.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, cameras) + .withTimeout(0.5), + CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral(superstructure, () -> ReefState.L4))); + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // path3.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral( + // drive, superstructure, cameras), + // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // path4.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // superstructure, intake, manipulator), + // path5.cmd(), + // CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral( + // drive, superstructure, cameras)); + return routine; } } From 7453e18eca60ad1fd1a4817659e7964c6fd3b888 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Thu, 18 Sep 2025 18:21:37 -0400 Subject: [PATCH 099/180] more changes --- src/main/java/frc/robot/commands/AutonomousCommands.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index 8ab4af0c..1340a03b 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -1894,7 +1894,7 @@ public static final LoggedAutoRoutine autoELeftPath( CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, cameras) .withTimeout(0.5), - CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral(superstructure, () -> ReefState.L4))); + CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral(superstructure, () -> ReefState.L4))); // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // path3.cmd(), From b1bf165237450d7a12c2ff40b0f1c8ef47581937 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Thu, 18 Sep 2025 18:42:55 -0400 Subject: [PATCH 100/180] Co-authored-by: jasminepalit --- .../java/frc/robot/commands/AutonomousCommands.java | 3 ++- .../java/frc/robot/commands/CompositeCommands.java | 12 ++++++++++++ .../v3_Epsilon/V3_EpsilonRobotContainer.java | 2 +- .../manipulator/V3_EpsilonManipulatorConstants.java | 5 +++-- 4 files changed, 18 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index 1340a03b..0a39579b 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -1894,7 +1894,8 @@ public static final LoggedAutoRoutine autoELeftPath( CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, cameras) .withTimeout(0.5), - CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral(superstructure, () -> ReefState.L4))); + CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral( + superstructure, () -> ReefState.L4))); // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // path3.cmd(), diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 0c016613..4bbc08d1 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -25,10 +25,13 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +// Removed duplicate or conflicting import for ManipulatorArmState import frc.robot.util.AllianceFlipUtil; import java.util.function.BooleanSupplier; import java.util.function.Supplier; @@ -894,5 +897,14 @@ public static final Command handoffCoral( Commands.waitUntil(() -> manipulator.hasCoral()), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)); } + + public static final Command manipulatorGroundIntake(V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { + return Commands.sequence( + Commands.runOnce(() -> manipulator.setArmGoal(ManipulatorArmState.STOW_DOWN)), + Commands.runOnce(() -> manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE)), + Commands.waitUntil(() -> manipulator.hasCoral()).withTimeout(2), + Commands.runOnce(() -> manipulator.setArmGoal(ManipulatorArmState.HANDOFF)) + ); + } } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index e036cec2..655b4a33 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -147,6 +147,6 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { - return AutonomousCommands.autoELeftPath(drive, superstructure, intake, manipulator).cmd(); + return AutonomousCommands.(drive, superstructure, intake, manipulator).cmd(); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 7754b9a6..59075e34 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -8,7 +8,7 @@ import frc.robot.util.LoggedTunableNumber; import lombok.RequiredArgsConstructor; -public class V3_EpsilonManipulatorConstants { +public final class V3_EpsilonManipulatorConstants { public static final ArmParameters ARM_PARAMETERS; public static final Gains EMPTY_GAINS; public static final Gains CORAL_GAINS; @@ -132,7 +132,8 @@ public static enum ManipulatorArmState { REEF_INTAKE(Rotation2d.fromDegrees(46.279296875)), INTAKE_OUT_LINE(Rotation2d.fromDegrees(61)), FLOOR_INTAKE(Rotation2d.fromDegrees(73.5)), - STOW_LINE(Rotation2d.fromDegrees(75)), + STOW_LINE(Rotation2d.fromDegrees(75)), // What is STOW_LINE? + STOW_DOWN(Rotation2d.fromDegrees(75)), TRANSITION(Rotation2d.fromDegrees(15.0)), // Placeholder value. Make sure to test VERTICAL_UP(Rotation2d.fromDegrees(0)), HANDOFF(Rotation2d.kPi), From bb2ca501b95436f397dea023510562d7ec83c093 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Thu, 18 Sep 2025 19:23:45 -0400 Subject: [PATCH 101/180] changes --- .../robot/commands/AutonomousCommands.java | 68 +++++++++++++++++++ .../frc/robot/commands/CompositeCommands.java | 11 ++- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 2 +- .../V3_EpsilonManipulatorConstants.java | 2 +- 4 files changed, 75 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index 0a39579b..bbd34fdf 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -11,6 +11,7 @@ import frc.robot.RobotState; import frc.robot.commands.CompositeCommands.V1_StackUpCompositeCommands; import frc.robot.commands.CompositeCommands.V2_RedundancyCompositeCommands; +import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorCSB; import frc.robot.subsystems.shared.funnel.Funnel.FunnelCSB; @@ -1911,4 +1912,71 @@ public static final LoggedAutoRoutine autoELeftPath( return routine; } + + public static final LoggedAutoRoutine autoELeftArm( + Drive drive, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + V3_EpsilonManipulator manipulator, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoELeft"); + LoggedAutoTrajectory path1 = routine.trajectory("E_LEFT_PATH1"); + + LoggedAutoTrajectory path2 = routine.trajectory("E_LEFT_PATH2_ARM"); + + LoggedAutoTrajectory path3 = routine.trajectory("E_LEFT_PATH3"); + + LoggedAutoTrajectory path4 = routine.trajectory("E_LEFT_PATH4_ARM"); + + LoggedAutoTrajectory path5 = routine.trajectory("E_LEFT_PATH5"); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + Commands.parallel( + // DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)) + .withTimeout(3), + Commands.sequence( + V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, cameras), + V3_EpsilonCompositeCommands.scoreCoral(superstructure, () -> ReefState.L4)) + .withTimeout(2), + Commands.parallel( + path2.cmd(), + V3_EpsilonCompositeCommands.manipulatorGroundIntake(manipulator, superstructure) + .withTimeout(0.5)), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path3.cmd(), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)) + .withTimeout(0.5), + Commands.sequence( + V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, cameras), + V3_EpsilonCompositeCommands.scoreCoral(superstructure, () -> ReefState.L4)) + .withTimeout(0.5), + Commands.parallel( + path4.cmd(), + V3_EpsilonCompositeCommands.manipulatorGroundIntake(manipulator, superstructure) + .withTimeout(0.5)), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)) + .withTimeout(0.5), + Commands.sequence( + V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, cameras), + V3_EpsilonCompositeCommands.scoreCoral(superstructure, () -> ReefState.L4)) + .withTimeout(0.5))); + + return routine; + } } diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 4bbc08d1..16d42d55 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -25,13 +25,13 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; // Removed duplicate or conflicting import for ManipulatorArmState +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; import frc.robot.util.AllianceFlipUtil; import java.util.function.BooleanSupplier; import java.util.function.Supplier; @@ -898,13 +898,12 @@ public static final Command handoffCoral( superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)); } - public static final Command manipulatorGroundIntake(V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { + public static final Command manipulatorGroundIntake( + V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { return Commands.sequence( Commands.runOnce(() -> manipulator.setArmGoal(ManipulatorArmState.STOW_DOWN)), Commands.runOnce(() -> manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE)), - Commands.waitUntil(() -> manipulator.hasCoral()).withTimeout(2), - Commands.runOnce(() -> manipulator.setArmGoal(ManipulatorArmState.HANDOFF)) - ); + Commands.runOnce(() -> superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF))); } } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 655b4a33..a64f0fbb 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -147,6 +147,6 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { - return AutonomousCommands.(drive, superstructure, intake, manipulator).cmd(); + return AutonomousCommands.autoELeftArm(drive, intake, superstructure, manipulator).cmd(); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 59075e34..7cd54d00 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -133,7 +133,7 @@ public static enum ManipulatorArmState { INTAKE_OUT_LINE(Rotation2d.fromDegrees(61)), FLOOR_INTAKE(Rotation2d.fromDegrees(73.5)), STOW_LINE(Rotation2d.fromDegrees(75)), // What is STOW_LINE? - STOW_DOWN(Rotation2d.fromDegrees(75)), + STOW_DOWN(Rotation2d.fromDegrees(88)), TRANSITION(Rotation2d.fromDegrees(15.0)), // Placeholder value. Make sure to test VERTICAL_UP(Rotation2d.fromDegrees(0)), HANDOFF(Rotation2d.kPi), From c03299ddf9cabe1d3ebdd8ed09fd16d8956b1afd Mon Sep 17 00:00:00 2001 From: vaddadisri26 Date: Thu, 18 Sep 2025 19:32:00 -0400 Subject: [PATCH 102/180] Finished the climber subsystem and added the climb() Command. Co-authored-by: ThatGuyRuchir --- src/main/deploy/Superstructure.dot | 4 ++ .../frc/robot/commands/CompositeCommands.java | 18 ++++- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 14 +++- .../v3_Epsilon/climber/V3_EpsilonClimber.java | 40 +++++------ .../climber/V3_EpsilonClimberConstants.java | 51 +++++++++----- .../climber/V3_EpsilonClimberIO.java | 38 +++++------ .../climber/V3_EpsilonClimberIOSim.java | 66 ++++++++++++++++++- .../climber/V3_EpsilonClimberIOTalonFX.java | 9 +-- .../superstructure/Superstructure.dot | 10 +++ .../V3_EpsilonSuperstructureStates.java | 7 +- 10 files changed, 185 insertions(+), 72 deletions(-) diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/Superstructure.dot index 3ea062c6..174a234a 100644 --- a/src/main/deploy/Superstructure.dot +++ b/src/main/deploy/Superstructure.dot @@ -12,6 +12,7 @@ digraph Superstructure { STOW_DOWN -> L3_ALGAE [type=UNCONSTRAINED] STOW_DOWN -> PROCESSOR [type=UNCONSTRAINED] STOW_DOWN -> BARGE [type=UNCONSTRAINED, requires=ELEVATOR] + STOW_DOWN -> CLIMB [type=NO_ALGAE] GROUND_ACQUISITION -> STOW_DOWN [type=UNCONSTRAINED, requires=ARM] GROUND_ACQUISITION -> GROUND_INTAKE [type=UNCONSTRAINED] @@ -205,4 +206,7 @@ digraph Superstructure { BARGE -> BARGE_SCORE [type=UNCONSTRAINED] BARGE_SCORE -> BARGE [type=UNCONSTRAINED] + + CLIMB -> STOW_DOWN [type=UNCONSTRAINED] + CLIMB -> STOW_UP [type=UNCONSTRAINED] } \ No newline at end of file diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 3cf9bdaf..189aad60 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -25,6 +25,8 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; +import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimber; +import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberConstants; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; @@ -892,6 +894,20 @@ public static final Command processAlgae( superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); } - // public static final Command climb() {} + public static final Command climb( + V3_EpsilonSuperstructure superstructure, + Drive drive, + V3_EpsilonClimber climber, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.CLIMB), + Commands.deadline( + climber.releaseClimber(), + Commands.waitSeconds( + V3_EpsilonClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), + Commands.deadline( + climber.winchClimber(), Commands.run(drive::stop))); + } } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index e64909c5..eac5e631 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -26,6 +26,10 @@ import frc.robot.subsystems.shared.elevator.ElevatorIOTalonFX; import frc.robot.subsystems.shared.vision.Vision; import frc.robot.subsystems.shared.vision.VisionConstants.RobotCameras; +import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimber; +import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIO; +import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIOSim; +import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIOTalonFX; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; @@ -46,6 +50,7 @@ public class V3_EpsilonRobotContainer implements RobotContainer { private V3_EpsilonIntake intake; private V3_EpsilonManipulator manipulator; private V3_EpsilonSuperstructure superstructure; + private V3_EpsilonClimber climber; private Vision vision; // Controller @@ -68,6 +73,7 @@ public V3_EpsilonRobotContainer() { elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); + climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); vision = new Vision( @@ -85,6 +91,7 @@ public V3_EpsilonRobotContainer() { elevator = new Elevator(new ElevatorIOSim()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); + climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOSim()); superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); vision = new Vision(() -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded)); @@ -111,6 +118,9 @@ public V3_EpsilonRobotContainer() { if (manipulator == null) { manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); } + if (climber == null) { + climber = new V3_EpsilonClimber(new V3_EpsilonClimberIO() {}); + } if (superstructure == null) { superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); } @@ -158,7 +168,7 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { // return superstructure.allTransition(); - return CompositeCommands.V3_EpsilonCompositeCommands.processAlgae( - superstructure, intake, manipulator); + return CompositeCommands.V3_EpsilonCompositeCommands.climb( + superstructure, drive, climber, intake, manipulator); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java index 2c7e06db..f5d1253f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java @@ -1,26 +1,24 @@ package frc.robot.subsystems.v3_Epsilon.climber; -import org.littletonrobotics.junction.AutoLogOutput; - -import frc.robot.util.ExternalLoggedTracer; -import frc.robot.util.InternalLoggedTracer; -import org.littletonrobotics.junction.Logger; - import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.util.ExternalLoggedTracer; +import frc.robot.util.InternalLoggedTracer; +import org.littletonrobotics.junction.AutoLogOutput; +import org.littletonrobotics.junction.Logger; -public class V3_EpsilonClimber extends SubsystemBase{ - private final V3_EpsilonClimberIO io; - private final V3_EpsilonClimberIOInputsAutoLogged inputs; +public class V3_EpsilonClimber extends SubsystemBase { + private final V3_EpsilonClimberIO io; + private final V3_EpsilonClimberIOInputsAutoLogged inputs; - @AutoLogOutput(key = "Climber/override") - private boolean override; + @AutoLogOutput(key = "Climber/override") + private boolean override; - @AutoLogOutput(key = "Climber/isClimbed") - private boolean isClimbed; + @AutoLogOutput(key = "Climber/isClimbed") + private boolean isClimbed; - public V3_EpsilonClimber(V3_EpsilonClimberIO io) { + public V3_EpsilonClimber(V3_EpsilonClimberIO io) { this.io = io; inputs = new V3_EpsilonClimberIOInputsAutoLogged(); @@ -64,10 +62,6 @@ public Command setRollerVoltage(double volts) { return Commands.run(() -> io.setRollerVoltage(volts)); } - -//TODO: NOTHING BELOW THIS POINT WORKS!!! - - /** * Creates a command to release the climber. The climber is released by applying voltage until the * position is greater than or equal to 20 radians. @@ -75,8 +69,8 @@ public Command setRollerVoltage(double volts) { * @return A command to release the climber. */ public Command releaseClimber() { - return this.runEnd(() -> io.setVoltage(1), () -> io.setVoltage(0)) - .until(() -> inputs.positionRadians >= 20); + return this.runEnd(() -> io.setDeploymentVoltage(1), () -> io.setDeploymentVoltage(0)) + .until(() -> inputs.deploymentPosition.getRadians() >= 20); } /** @@ -86,7 +80,8 @@ public Command releaseClimber() { * @return A command to winch the climber. */ public Command winchClimber() { - return Commands.runEnd(() -> io.setVoltage(12), () -> io.setVoltage(0)).until(() -> isClimbed); + return Commands.runEnd(() -> io.setRollerVoltage(12), () -> io.setRollerVoltage(0)) + .until(() -> isClimbed); } /** @@ -95,7 +90,7 @@ public Command winchClimber() { * @return A command to manually winch the climber. */ public Command winchClimberManual() { - return this.runEnd(() -> io.setVoltage(4), () -> io.setVoltage(0)); + return this.runEnd(() -> io.setRollerVoltage(4), () -> io.setRollerVoltage(0)); } /** @@ -107,5 +102,4 @@ public Command winchClimberManual() { public Command manualDeployOverride(boolean override) { // set using debug board button return Commands.runOnce(() -> this.override = override); } - } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java index 68238f6a..262caf0f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java @@ -1,27 +1,44 @@ package frc.robot.subsystems.v3_Epsilon.climber; +import edu.wpi.first.math.system.plant.DCMotor; +import edu.wpi.first.math.util.Units; + public class V3_EpsilonClimberConstants { - public static final int DEPLOYMENT_CAN_ID; + public static final int DEPLOYMENT_CAN_ID; + + public static final int ROLLER_CAN_ID; + + public static final int MOTOR_ID; + public static final MotorParameters MOTOR_PARAMETERS; + + public static final double CLIMBER_CLIMBED_RADIANS; + + static { + DEPLOYMENT_CAN_ID = 42; + ROLLER_CAN_ID = + 42; // This used to be 61, but there are two motors, so I replace this with 42 until - public static final int ROLLER_CAN_ID; + MOTOR_ID = 50; + MOTOR_PARAMETERS = + new MotorParameters(DCMotor.getKrakenX60Foc(1), 24.0, 0.81, Units.inchesToMeters(1.78)); - static { - DEPLOYMENT_CAN_ID = 42; - ROLLER_CAN_ID = 42; // This used to be 61, but there are two motors, so I replace this with 42 until - } + CLIMBER_CLIMBED_RADIANS = 410; + } - public static final double CLIMBER_CLIMBED_ZERO_RADIANS = 41; //TODO: None of these four lines are valid numbers i just made up stuff - public static final double CLIMBER_CLIMBED_DEPLOYED_RADIANS = 67; - public static final ClimberTimingConfig CLIMBER_TIMING_CONFIG = new ClimberTimingConfig(1.1, 0.25, 0.5); - public static final CurrentLimits CURRENT_LIMITS = new CurrentLimits(40.0, 80.0); + public static record MotorParameters( + DCMotor MOTOR_CONFIG, double GEAR_RATIO, double GEARBOX_EFFICIENCY, double SPOOL_DIAMETER) {} - public static record CurrentLimits(double SUPPLY_CURRENT_LIMIT, double STATOR_CURRENT_LIMIT) { - } + public static final double CLIMBER_CLIMBED_ZERO_RADIANS = + 41; // TODO: None of these four lines are valid numbers i just made up stuff + public static final double CLIMBER_CLIMBED_DEPLOYED_RADIANS = 67; + public static final ClimberTimingConfig CLIMBER_TIMING_CONFIG = + new ClimberTimingConfig(1.1, 0.25, 0.5); + public static final CurrentLimits CURRENT_LIMITS = new CurrentLimits(40.0, 80.0); - public static record ClimberTimingConfig( - double WAIT_AFTER_RELEASE_SECONDS, - double REDUNDANCY_DELAY_SECONDS, - double REDUNDANCY_TRUSTING_TIMEOUT_SECONDS) { - } + public static record CurrentLimits(double SUPPLY_CURRENT_LIMIT, double STATOR_CURRENT_LIMIT) {} + public static record ClimberTimingConfig( + double WAIT_AFTER_RELEASE_SECONDS, + double REDUNDANCY_DELAY_SECONDS, + double REDUNDANCY_TRUSTING_TIMEOUT_SECONDS) {} } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIO.java index a9f30b92..d7f5dddd 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIO.java @@ -1,27 +1,26 @@ package frc.robot.subsystems.v3_Epsilon.climber; -import org.littletonrobotics.junction.AutoLog; - import edu.wpi.first.math.geometry.Rotation2d; +import org.littletonrobotics.junction.AutoLog; public interface V3_EpsilonClimberIO { - @AutoLog - public static class V3_EpsilonClimberIOInputs { - public Rotation2d deploymentPosition = new Rotation2d(); - public double deploymentVelocityRadiansPerSecond = 0.0; - public double deploymentAppliedVolts = 0.0; - public double deploymentSupplyCurrentAmps = 0.0; - public double deploymentTorqueCurrentAmps = 0.0; - public double deploymentTemperatureCelsius = 0.0; + @AutoLog + public static class V3_EpsilonClimberIOInputs { + public Rotation2d deploymentPosition = new Rotation2d(); + public double deploymentVelocityRadiansPerSecond = 0.0; + public double deploymentAppliedVolts = 0.0; + public double deploymentSupplyCurrentAmps = 0.0; + public double deploymentTorqueCurrentAmps = 0.0; + public double deploymentTemperatureCelsius = 0.0; - public Rotation2d rollerPosition = new Rotation2d(); - public double rollerVelocityRadiansPerSecond = 0.0; - public double rollerAppliedVolts = 0.0; - public double rollerSupplyCurrentAmps = 0.0; - public double rollerTorqueCurrentAmps = 0.0; - public double rollerTemperatureCelsius = 0.0; - } - /** + public Rotation2d rollerPosition = new Rotation2d(); + public double rollerVelocityRadiansPerSecond = 0.0; + public double rollerAppliedVolts = 0.0; + public double rollerSupplyCurrentAmps = 0.0; + public double rollerTorqueCurrentAmps = 0.0; + public double rollerTemperatureCelsius = 0.0; + } + /** * Updates the inputs for the manipulator subsystem. * * @param inputs The inputs to update. @@ -41,7 +40,7 @@ public default void setDeploymentVoltage(double volts) {} * @param volts The voltage to set. */ public default void setRollerVoltage(double volts) {} - + /** * Gets the state of the climber based on the current draw. * @@ -50,5 +49,4 @@ public default void setRollerVoltage(double volts) {} public default boolean isClimbed() { return false; } - } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOSim.java index 73e68550..6dd38f8a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOSim.java @@ -1,5 +1,67 @@ package frc.robot.subsystems.v3_Epsilon.climber; -public class V3_EpsilonClimberIOSim { - +import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.system.plant.LinearSystemId; +import edu.wpi.first.wpilibj.simulation.DCMotorSim; +import frc.robot.Constants; +import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIO.V3_EpsilonClimberIOInputs; + +public class V3_EpsilonClimberIOSim implements V3_EpsilonClimberIO { + private final DCMotorSim sim; + + private double deploymentAppliedVolts; + private double rollerAppliedVolts; + + public V3_EpsilonClimberIOSim() { + sim = + new DCMotorSim( + LinearSystemId.createDCMotorSystem( + V3_EpsilonClimberConstants.MOTOR_PARAMETERS.MOTOR_CONFIG(), + 0.004, + V3_EpsilonClimberConstants.MOTOR_PARAMETERS.GEAR_RATIO()), + V3_EpsilonClimberConstants.MOTOR_PARAMETERS.MOTOR_CONFIG()); + + deploymentAppliedVolts = 0.0; + rollerAppliedVolts = 0.0; + } + + @Override + public void updateInputs(V3_EpsilonClimberIOInputs inputs) { + deploymentAppliedVolts = MathUtil.clamp(deploymentAppliedVolts, -12.0, 12.0); + sim.setInputVoltage(deploymentAppliedVolts); + rollerAppliedVolts = MathUtil.clamp(rollerAppliedVolts, -12.0, 12.0); + sim.setInputVoltage(rollerAppliedVolts); + sim.update(Constants.LOOP_PERIOD_SECONDS); + + // Update in standardized order + inputs.deploymentPosition = Rotation2d.fromRadians(sim.getAngularPositionRad()); + inputs.deploymentVelocityRadiansPerSecond = sim.getAngularVelocityRadPerSec(); + inputs.deploymentAppliedVolts = deploymentAppliedVolts; + inputs.deploymentSupplyCurrentAmps = + sim.getCurrentDrawAmps() / V3_EpsilonClimberConstants.MOTOR_PARAMETERS.GEARBOX_EFFICIENCY(); + inputs.deploymentTorqueCurrentAmps = sim.getCurrentDrawAmps(); + + inputs.rollerPosition = Rotation2d.fromRadians(sim.getAngularPositionRad()); + inputs.rollerVelocityRadiansPerSecond = sim.getAngularVelocityRadPerSec(); + inputs.rollerAppliedVolts = rollerAppliedVolts; + inputs.rollerSupplyCurrentAmps = + sim.getCurrentDrawAmps() / V3_EpsilonClimberConstants.MOTOR_PARAMETERS.GEARBOX_EFFICIENCY(); + inputs.rollerTorqueCurrentAmps = sim.getCurrentDrawAmps(); + } + + @Override + public void setDeploymentVoltage(double volts) { + deploymentAppliedVolts = volts; + } + + @Override + public void setRollerVoltage(double volts) { + rollerAppliedVolts = volts; + } + + @Override + public boolean isClimbed() { + return false; + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java index e63169b3..8c4e4663 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java @@ -5,20 +5,17 @@ import com.ctre.phoenix6.StatusSignal; import com.ctre.phoenix6.configs.TalonFXConfiguration; -import com.ctre.phoenix6.controls.MotionMagicVoltage; import com.ctre.phoenix6.controls.VoltageOut; import com.ctre.phoenix6.hardware.TalonFX; - import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Current; import edu.wpi.first.units.measure.Temperature; import edu.wpi.first.units.measure.Voltage; -import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIO.V3_EpsilonClimberIOInputs; import frc.robot.util.PhoenixUtil; -public class V3_EpsilonClimberIOTalonFX { +public class V3_EpsilonClimberIOTalonFX implements V3_EpsilonClimberIO { private final TalonFX rollerTalonFX; private final TalonFX deploymentTalonFX; @@ -44,7 +41,7 @@ public class V3_EpsilonClimberIOTalonFX { private final StatusSignal deploymentTorqueCurrentAmps; private final StatusSignal deploymentTemperatureCelsius; - public V3_EpsilonClimberIOTalonFX(){ + public V3_EpsilonClimberIOTalonFX() { rollerTalonFX = new TalonFX(V3_EpsilonClimberConstants.ROLLER_CAN_ID); deploymentTalonFX = new TalonFX(V3_EpsilonClimberConstants.DEPLOYMENT_CAN_ID); @@ -84,6 +81,7 @@ public V3_EpsilonClimberIOTalonFX(){ rollerTorqueCurrentAmps, rollerTemperatureCelsius); } + @Override public void updateInputs(V3_EpsilonClimberIOInputs inputs) { inputs.deploymentPosition = new Rotation2d(deploymentPositionRotations.getValue()); @@ -110,5 +108,4 @@ public void setdeploymentVoltage(double volts) { public void setRollerVoltage(double volts) { rollerTalonFX.setControl(rollerVoltageRequest.withOutput(volts).withEnableFOC(true)); } - } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index a174a805..20909a0d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -12,6 +12,7 @@ digraph Superstructure { STOW_DOWN -> L3_ALGAE [type=UNCONSTRAINED] STOW_DOWN -> PROCESSOR [type=UNCONSTRAINED] STOW_DOWN -> BARGE [type=UNCONSTRAINED] + STOW_DOWN -> CLIMB [type=NO_ALGAE] GROUND_ACQUISITION -> STOW_DOWN [type=UNCONSTRAINED] GROUND_ACQUISITION -> GROUND_INTAKE [type=UNCONSTRAINED] @@ -64,6 +65,7 @@ digraph Superstructure { L2 -> L3_ALGAE [type=UNCONSTRAINED] L2 -> PROCESSOR [type=UNCONSTRAINED] L2 -> BARGE [type=UNCONSTRAINED] + L2 -> CLIMB [type=NO_ALGAE] L3 -> STOW_DOWN [type=UNCONSTRAINED] L3 -> GROUND_ACQUISITION [type=UNCONSTRAINED] @@ -77,6 +79,7 @@ digraph Superstructure { L3 -> L3_ALGAE [type=UNCONSTRAINED] L3 -> PROCESSOR [type=UNCONSTRAINED] L3 -> BARGE [type=UNCONSTRAINED] + L3 -> CLIMB [type=NO_ALGAE] L4 -> STOW_DOWN [type=UNCONSTRAINED] L4 -> GROUND_ACQUISITION [type=UNCONSTRAINED] @@ -143,6 +146,7 @@ digraph Superstructure { HANDOFF -> L3_ALGAE [type=UNCONSTRAINED] HANDOFF -> PROCESSOR [type=UNCONSTRAINED] HANDOFF -> BARGE [type=UNCONSTRAINED] + HANDOFF -> CLIMB [type=NO_ALGAE] STOW_UP -> STOW_DOWN [type=UNCONSTRAINED] STOW_UP -> GROUND_ACQUISITION [type=UNCONSTRAINED] @@ -155,6 +159,7 @@ digraph Superstructure { STOW_UP -> L3_ALGAE [type=UNCONSTRAINED] STOW_UP -> PROCESSOR [type=UNCONSTRAINED] STOW_UP -> BARGE [type=UNCONSTRAINED] + STOW_UP -> CLIMB [type=NO_ALGAE] L2_ALGAE -> STOW_DOWN [type = NO_ALGAE] L2_ALGAE -> GROUND_ACQUISITION [type = NO_ALGAE] @@ -169,6 +174,7 @@ digraph Superstructure { L2_ALGAE -> PROCESSOR [type=UNCONSTRAINED] L2_ALGAE -> BARGE [type=UNCONSTRAINED] L2_ALGAE -> L2_ALGAE_DROP + L2_ALGAE -> CLIMB [type=NO_ALGAE] L2_ALGAE_DROP -> L2_ALGAE @@ -188,6 +194,7 @@ digraph Superstructure { L3_ALGAE -> PROCESSOR [type=UNCONSTRAINED] L3_ALGAE -> BARGE [type=UNCONSTRAINED] L3_ALGAE -> L3_ALGAE_DROP + L3_ALGAE -> CLIMB [type=NO_ALGAE] L3_ALGAE_DROP -> L3_ALGAE @@ -223,4 +230,7 @@ digraph Superstructure { BARGE -> BARGE_SCORE [type=UNCONSTRAINED] BARGE_SCORE -> BARGE [type=UNCONSTRAINED] + + CLIMB -> STOW_DOWN [type=UNCONSTRAINED] + CLIMB -> STOW_UP [type=UNCONSTRAINED] } \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index f2e7e2ff..0cf797dc 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -145,7 +145,12 @@ public enum V3_EpsilonSuperstructureStates { new SubsystemPoses( ReefState.ALGAE_SCORE, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), - ; + + CLIMB( + "CLIMB", + new SubsystemPoses( + ReefState.STOW, ManipulatorArmState.EMERGENCY_EJECT_ANGLE, IntakePivotState.ARM_CLEAR), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.STOP)); // Readable name for state private final String name; From 28158928d1766c052b145f31bc1a76cff58e646f Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Thu, 18 Sep 2025 19:44:12 -0400 Subject: [PATCH 103/180] worked on auto that intakes lollipop coral with manipulator from ground --- .../robot/commands/AutonomousCommands.java | 25 +++++++++---------- .../frc/robot/commands/CompositeCommands.java | 7 +++--- 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index bbd34fdf..d6c80cb9 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -154,11 +154,11 @@ public static void loadAutoTrajectories(Drive drive) { drive.getAutoFactory().cache().loadTrajectory("D_CENTER_PATH"); - drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH1"); - drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH2"); - drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH3"); - drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH4"); - drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH5"); + drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH_1"); + drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH_2"); + drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH_3"); + drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH_4"); + drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH_5"); } public static final Command autoALeft( @@ -1921,15 +1921,15 @@ public static final LoggedAutoRoutine autoELeftArm( Camera... cameras) { LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoELeft"); - LoggedAutoTrajectory path1 = routine.trajectory("E_LEFT_PATH1"); + LoggedAutoTrajectory path1 = routine.trajectory("E_LEFT_PATH_1"); - LoggedAutoTrajectory path2 = routine.trajectory("E_LEFT_PATH2_ARM"); + LoggedAutoTrajectory path2 = routine.trajectory("E_LEFT_PATH_2"); - LoggedAutoTrajectory path3 = routine.trajectory("E_LEFT_PATH3"); + LoggedAutoTrajectory path3 = routine.trajectory("E_LEFT_PATH_3"); - LoggedAutoTrajectory path4 = routine.trajectory("E_LEFT_PATH4_ARM"); + LoggedAutoTrajectory path4 = routine.trajectory("E_LEFT_PATH_4"); - LoggedAutoTrajectory path5 = routine.trajectory("E_LEFT_PATH5"); + LoggedAutoTrajectory path5 = routine.trajectory("E_LEFT_PATH_5"); routine .active() @@ -1947,10 +1947,9 @@ public static final LoggedAutoRoutine autoELeftArm( drive, superstructure, cameras), V3_EpsilonCompositeCommands.scoreCoral(superstructure, () -> ReefState.L4)) .withTimeout(2), - Commands.parallel( - path2.cmd(), + path2.cmd(), V3_EpsilonCompositeCommands.manipulatorGroundIntake(manipulator, superstructure) - .withTimeout(0.5)), + .withTimeout(0.5), Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), path3.cmd(), Commands.parallel( diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 16d42d55..9f8c0764 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -901,9 +901,10 @@ public static final Command handoffCoral( public static final Command manipulatorGroundIntake( V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { return Commands.sequence( - Commands.runOnce(() -> manipulator.setArmGoal(ManipulatorArmState.STOW_DOWN)), - Commands.runOnce(() -> manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE)), - Commands.runOnce(() -> superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF))); + Commands.runOnce(() -> superstructure.runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE)), + Commands.runOnce(() -> + manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE)) + ); } } } From 499c0022673f6c725872d4c8733336854dd69301 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Fri, 19 Sep 2025 15:37:42 -0400 Subject: [PATCH 104/180] 4-piece! (not manipulator ground intake though) --- src/main/deploy/choreo/E_LEFT_PATH_6.traj | 71 +++++++++++++++++++ src/main/deploy/choreo/E_LEFT_PATH_7.traj | 66 +++++++++++++++++ .../robot/commands/AutonomousCommands.java | 24 +++++-- .../frc/robot/commands/CompositeCommands.java | 8 +-- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 2 +- 5 files changed, 160 insertions(+), 11 deletions(-) create mode 100644 src/main/deploy/choreo/E_LEFT_PATH_6.traj create mode 100644 src/main/deploy/choreo/E_LEFT_PATH_7.traj diff --git a/src/main/deploy/choreo/E_LEFT_PATH_6.traj b/src/main/deploy/choreo/E_LEFT_PATH_6.traj new file mode 100644 index 00000000..2d4d156d --- /dev/null +++ b/src/main/deploy/choreo/E_LEFT_PATH_6.traj @@ -0,0 +1,71 @@ +{ + "name":"E_LEFT_PATH_6", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":2.9622931480407715, "y":3.9847822189331055, "heading":1.5707963267948966, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.849413275718689, "y":5.839582443237305, "heading":3.141592653589793, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"2.9622931480407715 m", "val":2.9622931480407715}, "y":{"exp":"3.9847822189331055 m", "val":3.9847822189331055}, "heading":{"exp":"1.5707963267948966 rad", "val":1.5707963267948966}, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.849413275718689 m", "val":1.849413275718689}, "y":{"exp":"5.839582443237305 m", "val":5.839582443237305}, "heading":{"exp":"3.141592653589793 rad", "val":3.141592653589793}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.1777], + "samples":[ + {"t":0.0, "x":2.96229, "y":3.98478, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.17652, "ay":5.36941, "alpha":5.38241, "fx":[-86.86283,-42.67676,-24.14536,-62.44186], "fy":[67.02416,100.99425,107.04727,90.26304]}, + {"t":0.03271, "x":2.96059, "y":3.98766, "heading":1.5708, "vx":-0.10392, "vy":0.17565, "omega":0.17608, "ax":-3.18135, "ay":5.37156, "alpha":5.32096, "fx":[-86.57463,-42.96599,-24.5117,-62.40326], "fy":[67.38061,100.85772,106.95548,90.28109]}, + {"t":0.06543, "x":2.95549, "y":3.99628, "heading":1.57656, "vx":-0.20799, "vy":0.35138, "omega":0.35015, "ax":-3.18608, "ay":5.37368, "alpha":5.26093, "fx":[-86.2707,-42.98788,-25.02162,-62.49676], "fy":[67.75132,100.83315,106.82786,90.20648]}, + {"t":0.09814, "x":2.94698, "y":4.01065, "heading":1.58801, "vx":-0.31222, "vy":0.52717, "omega":0.52226, "ax":-3.19093, "ay":5.3758, "alpha":5.19982, "fx":[-85.93756,-42.77495,-25.67985,-62.71462], "fy":[68.15226,100.90671,106.66083,90.04363]}, + {"t":0.13086, "x":2.93506, "y":4.03077, "heading":1.6051, "vx":-0.41661, "vy":0.70304, "omega":0.69236, "ax":-3.1962, "ay":5.37798, "alpha":5.13457, "fx":[-85.55623,-42.36824,-26.49458,-63.04696], "fy":[68.60543,101.05913,106.4491,89.7977]}, + {"t":0.16357, "x":2.91972, "y":4.05665, "heading":1.62775, "vx":-0.52117, "vy":0.87897, "omega":0.86034, "ax":-3.20228, "ay":5.38025, "alpha":5.06109, "fx":[-85.10066,-41.81971,-27.47797,-63.481], "fy":[69.14009,101.26579,106.18521,89.47525]}, + {"t":0.19628, "x":2.90096, "y":4.08828, "heading":1.65589, "vx":-0.62593, "vy":1.05498, "omega":1.0259, "ax":-3.2096, "ay":5.38274, "alpha":4.97353, "fx":[-84.53541,-41.19546,-28.64713,-63.99973], "fy":[69.79454,101.49661,105.85882,89.08539]}, + {"t":0.229, "x":2.87876, "y":4.12567, "heading":1.68945, "vx":-0.73093, "vy":1.23107, "omega":1.18861, "ax":-3.21872, "ay":5.38561, "alpha":4.86331, "fx":[-83.81205,-40.58031,-30.02575,-64.57985], "fy":[70.61852,101.71531,105.45551,88.64158]}, + {"t":0.26171, "x":2.85313, "y":4.16883, "heading":1.72834, "vx":-0.83622, "vy":1.40726, "omega":1.34771, "ax":-3.23026, "ay":5.38917, "alpha":4.71782, "fx":[-82.8634,-40.08447,-31.64727,-65.1882], "fy":[71.67658,101.87749,104.95466,88.16457]}, + {"t":0.29443, "x":2.82405, "y":4.21775, "heading":1.77243, "vx":-0.9419, "vy":1.58356, "omega":1.50204, "ax":-3.24497, "ay":5.39386, "alpha":4.51838, "fx":[-81.59416,-39.85399,-33.56087,-65.77522], "fy":[73.05275,101.92614,104.32554,87.6877]}, + {"t":0.32714, "x":2.7915, "y":4.27244, "heading":1.82156, "vx":-1.04806, "vy":1.76002, "omega":1.64986, "ax":-3.26372, "ay":5.40021, "alpha":4.23701, "fx":[-79.86472,-40.0891,-35.8439,-66.262], "fy":[74.85704,101.78139,103.51918,87.26678]}, + {"t":0.35985, "x":2.75546, "y":4.33291, "heading":1.87554, "vx":-1.15482, "vy":1.93668, "omega":1.78847, "ax":-3.28757, "ay":5.40871, "alpha":3.83022, "fx":[-77.46165,-41.07941,-38.62957,-66.51196], "fy":[77.23499,101.31688,102.44985,87.00063]}, + {"t":0.39257, "x":2.71593, "y":4.39916, "heading":1.93405, "vx":-1.26237, "vy":2.11362, "omega":1.91377, "ax":-3.318, "ay":5.4191, "alpha":3.22534, "fx":[-74.03964,-43.27755,-42.1759,-66.25993], "fy":[80.38161,100.30227,100.94665,87.0787]}, + {"t":0.42528, "x":2.67285, "y":4.4712, "heading":1.99665, "vx":-1.37092, "vy":2.2909, "omega":2.01928, "ax":-3.35728, "ay":5.42805, "alpha":2.28394, "fx":[-68.99557,-47.46504,-47.06648,-64.89813], "fy":[84.56081,98.24777,98.59949,87.91026]}, + {"t":0.458, "x":2.62621, "y":4.54905, "heading":2.06271, "vx":-1.48075, "vy":2.46847, "omega":2.094, "ax":-3.40807, "ay":5.41874, "alpha":0.67234, "fx":[-61.16417,-55.14745,-54.95086,-60.61886], "fy":[90.1176,93.91502,94.09775,90.55461]}, + {"t":0.49071, "x":2.57594, "y":4.6327, "heading":2.13121, "vx":-1.59224, "vy":2.64574, "omega":2.116, "ax":-3.44854, "ay":5.28498, "alpha":-2.90877, "fx":[-48.01544,-69.39022,-72.44955,-44.7792], "fy":[97.35036,83.47817,80.31087,98.44455]}, + {"t":0.52342, "x":2.52201, "y":4.72208, "heading":2.20044, "vx":-1.70506, "vy":2.81863, "omega":2.02084, "ax":-2.8284, "ay":3.94902, "alpha":-15.18696, "fx":[-29.38592,-88.93729,-105.01323,30.89557], "fy":[103.73245,60.92653,3.47736,100.55036]}, + {"t":0.55614, "x":2.46472, "y":4.81641, "heading":2.26655, "vx":-1.79758, "vy":2.94782, "omega":1.52401, "ax":-2.72674, "ay":3.70336, "alpha":-14.10606, "fx":[-31.21237,-86.3488,-93.52676,25.56353], "fy":[98.42802,56.23737,4.70088,92.60588]}, + {"t":0.58885, "x":2.40445, "y":4.91482, "heading":2.3164, "vx":-1.88679, "vy":3.06897, "omega":1.06255, "ax":2.73736, "ay":-4.08675, "alpha":12.90321, "fx":[31.39081,85.41852,93.47232,-24.03483], "fy":[-99.982,-60.01477,-20.80034,-97.2607]}, + {"t":0.62157, "x":2.34419, "y":5.01303, "heading":2.35116, "vx":-1.79724, "vy":2.93528, "omega":1.48466, "ax":3.0584, "ay":-4.26275, "alpha":12.7568, "fx":[36.09906,89.68852,101.86847,-19.56588], "fy":[-101.79742,-59.90881,-23.83233,-104.49419]}, + {"t":0.65428, "x":2.28703, "y":5.10678, "heading":2.39973, "vx":-1.69718, "vy":2.79583, "omega":1.90199, "ax":3.32997, "ay":-4.93712, "alpha":7.69709, "fx":[43.49878,84.80094,88.24086,10.02689], "fy":[-99.60732,-67.81948,-61.02627,-107.46305]}, + {"t":0.68699, "x":2.23329, "y":5.1956, "heading":2.46195, "vx":-1.58825, "vy":2.63431, "omega":2.15379, "ax":3.41082, "ay":-5.40596, "alpha":1.11173, "fx":[55.27548,63.91943,61.25035,51.62278], "fy":[-93.87472,-88.18124,-89.93214,-95.82713]}, + {"t":0.71971, "x":2.18316, "y":5.27889, "heading":2.53241, "vx":-1.47667, "vy":2.45746, "omega":2.19016, "ax":3.37237, "ay":-5.44278, "alpha":-1.44085, "fx":[61.03333,48.67342,54.46595,65.27942], "fy":[-90.42854,-97.6888,-94.67352,-87.52971]}, + {"t":0.75242, "x":2.13666, "y":5.35637, "heading":2.60406, "vx":-1.36634, "vy":2.27941, "omega":2.14302, "ax":3.3321, "ay":-5.42784, "alpha":-2.83597, "fx":[63.38535,38.51652,52.67456,72.13552], "fy":[-88.92819,-102.29001,-95.89111,-82.19443]}, + {"t":0.78514, "x":2.09374, "y":5.42803, "heading":2.67417, "vx":-1.25734, "vy":2.10184, "omega":2.05025, "ax":3.30188, "ay":-5.40597, "alpha":-3.67939, "fx":[63.6911,31.83405,52.66895,76.46214], "fy":[-88.80565,-104.6775,-96.01107,-78.32191]}, + {"t":0.81785, "x":2.05438, "y":5.4939, "heading":2.74124, "vx":-1.14932, "vy":1.92499, "omega":1.92988, "ax":3.27878, "ay":-5.38726, "alpha":-4.22056, "fx":[62.67214,27.43657,53.43199,79.54363], "fy":[-89.60079,-105.99631,-95.66305,-75.28259]}, + {"t":0.85056, "x":2.01853, "y":5.55399, "heading":2.80437, "vx":-1.04206, "vy":1.74875, "omega":1.79181, "ax":3.25919, "ay":-5.37338, "alpha":-4.591, "fx":[60.76916,24.55309,54.53884,81.89036], "fy":[-90.96019,-106.76059,-95.08805,-72.78984]}, + {"t":0.88328, "x":1.98619, "y":5.60832, "heading":2.86299, "vx":-0.93544, "vy":1.57297, "omega":1.64162, "ax":3.2409, "ay":-5.36357, "alpha":-4.86622, "fx":[58.29404,22.68606,55.78017,83.7469], "fy":[-92.61358,-107.21777,-94.40318,-70.69694]}, + {"t":0.91599, "x":1.95732, "y":5.65691, "heading":2.9167, "vx":-0.82941, "vy":1.3975, "omega":1.48243, "ax":3.22299, "ay":-5.3565, "alpha":-5.08977, "fx":[55.49263,21.50669,57.04119,85.24776], "fy":[-94.35904,-107.49532,-93.67571,-68.92016]}, + {"t":0.94871, "x":1.93191, "y":5.69976, "heading":2.96519, "vx":-0.72398, "vy":1.22227, "omega":1.31592, "ax":3.20535, "ay":-5.35096, "alpha":-5.28532, "fx":[52.56832,20.79099,58.25395,86.47529], "fy":[-96.05354,-107.66352,-92.9494,-67.40656]}, + {"t":0.98142, "x":1.90994, "y":5.73688, "heading":3.00824, "vx":-0.61912, "vy":1.04722, "omega":1.14301, "ax":3.18834, "ay":-5.3461, "alpha":-5.46392, "fx":[49.6891,20.38162,59.37581,87.48449], "fy":[-97.60426,-107.76389,-92.25547,-66.11919]}, + {"t":1.01413, "x":1.89139, "y":5.76828, "heading":3.04563, "vx":-0.51481, "vy":0.87233, "omega":0.96427, "ax":3.17242, "ay":-5.34149, "alpha":-5.62903, "fx":[46.98934,20.16491,60.37869,88.31472], "fy":[-98.95876,-107.82272,-91.61773,-65.02987]}, + {"t":1.04685, "x":1.87625, "y":5.79396, "heading":3.07718, "vx":-0.41103, "vy":0.69759, "omega":0.78012, "ax":3.15801, "ay":-5.33699, "alpha":-5.78, "fx":[44.57151,20.05669,61.2433,88.99568], "fy":[-100.09431,-107.85785,-91.05508,-64.11561]}, + {"t":1.07956, "x":1.86449, "y":5.81393, "heading":3.1027, "vx":-0.30772, "vy":0.52299, "omega":0.59103, "ax":3.14541, "ay":-5.33268, "alpha":-5.91441, "fx":[42.50976,19.99353,61.95594,89.55053], "fy":[-101.00764,-107.88207,-90.58285,-63.3569]}, + {"t":1.11228, "x":1.85611, "y":5.82818, "heading":3.12203, "vx":-0.20482, "vy":0.34854, "omega":0.39755, "ax":3.13478, "ay":-5.32874, "alpha":-6.02947, "fx":[40.85526,19.92713,62.50658,89.99756], "fy":[-101.70608,-107.90489,-90.21341,-62.7371]}, + {"t":1.14499, "x":1.85109, "y":5.83673, "heading":3.13504, "vx":-0.10227, "vy":0.17421, "omega":0.2003, "ax":3.12618, "ay":-5.32539, "alpha":-6.1228, "fx":[39.64248,19.82068,62.88764,90.35102], "fy":[-102.20068,-107.93344,-89.95664,-62.24244]}, + {"t":1.1777, "x":1.84941, "y":5.83958, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_LEFT_PATH_7.traj b/src/main/deploy/choreo/E_LEFT_PATH_7.traj new file mode 100644 index 00000000..893f11f3 --- /dev/null +++ b/src/main/deploy/choreo/E_LEFT_PATH_7.traj @@ -0,0 +1,66 @@ +{ + "name":"E_LEFT_PATH_7", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":1.7875865697860718, "y":5.860191345214844, "heading":3.141592653589793, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":3.7660398483276367, "y":5.262533664703369, "heading":-2.5959373241304182, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"1.7875865697860718 m", "val":1.7875865697860718}, "y":{"exp":"5.860191345214844 m", "val":5.860191345214844}, "heading":{"exp":"3.141592653589793 rad", "val":3.141592653589793}, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"3.7660398483276367 m", "val":3.7660398483276367}, "y":{"exp":"5.262533664703369 m", "val":5.262533664703369}, "heading":{"exp":"-2.5959373241304182 rad", "val":-2.5959373241304182}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.13498], + "samples":[ + {"t":0.0, "x":1.78759, "y":5.86019, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.15533, "ay":-1.85931, "alpha":1.72515, "fx":[103.37094,107.60487,106.75398,101.07183], "fy":[-36.86708,-21.56181,-25.35323,-42.72345]}, + {"t":0.03661, "x":1.79171, "y":5.85895, "heading":3.14159, "vx":0.22536, "vy":-0.06807, "omega":0.06316, "ax":6.15487, "ay":-1.85917, "alpha":1.72335, "fx":[103.36506,107.59465,106.74267,101.06819], "fy":[-36.85955,-21.57011,-25.35824,-42.70809]}, + {"t":0.07322, "x":1.80409, "y":5.85521, "heading":-3.13928, "vx":0.45071, "vy":-0.13614, "omega":0.12626, "ax":6.15435, "ay":-1.85901, "alpha":1.72114, "fx":[103.3663,107.58579,106.72323,101.05962], "fy":[-36.82837,-21.56488,-25.39081,-42.70082]}, + {"t":0.10984, "x":1.82471, "y":5.84898, "heading":-3.13466, "vx":0.67603, "vy":-0.20421, "omega":0.18927, "ax":6.15374, "ay":-1.85882, "alpha":1.71845, "fx":[103.37439,107.57784,106.69519,101.04608], "fy":[-36.77332,-21.54667,-25.4511,-42.70082]}, + {"t":0.14645, "x":1.85359, "y":5.84025, "heading":-3.12773, "vx":0.90133, "vy":-0.27226, "omega":0.25219, "ax":6.15302, "ay":-1.85859, "alpha":1.71518, "fx":[103.38898,107.57018,106.65789,101.02758], "fy":[-36.69403,-21.5163,-25.53942,-42.70683]}, + {"t":0.18306, "x":1.89071, "y":5.82904, "heading":-3.11849, "vx":1.12661, "vy":-0.34031, "omega":0.31499, "ax":6.15216, "ay":-1.85832, "alpha":1.71121, "fx":[103.40956,107.56191,106.6104,101.00414], "fy":[-36.58998,-21.47491,-25.65619,-42.71712]}, + {"t":0.21967, "x":1.93609, "y":5.81534, "heading":-3.10696, "vx":1.35185, "vy":-0.40835, "omega":0.37764, "ax":6.15111, "ay":-1.85799, "alpha":1.70637, "fx":[103.43539,107.55178,106.55139,100.97573], "fy":[-36.46046,-21.4241,-25.80196,-42.72922]}, + {"t":0.25629, "x":1.9897, "y":5.79914, "heading":-3.09314, "vx":1.57706, "vy":-0.47637, "omega":0.44011, "ax":6.14979, "ay":-1.85758, "alpha":1.70038, "fx":[103.46538,107.53792,106.47893,100.94223], "fy":[-36.30447,-21.36607,-25.97741,-42.73975]}, + {"t":0.2929, "x":2.05156, "y":5.78045, "heading":-3.07702, "vx":1.80222, "vy":-0.54438, "omega":0.50237, "ax":6.14808, "ay":-1.85705, "alpha":1.69285, "fx":[103.49776,107.51752,106.39011,100.90321], "fy":[-36.12055,-21.30394,-26.18333,-42.74385]}, + {"t":0.32951, "x":2.12167, "y":5.75928, "heading":-3.05863, "vx":2.02732, "vy":-0.61237, "omega":0.56434, "ax":6.1458, "ay":-1.85634, "alpha":1.68314, "fx":[103.52959,107.48597,106.28024,100.85768], "fy":[-35.90648,-21.24233,-26.42058,-42.73418]}, + {"t":0.36612, "x":2.20001, "y":5.73561, "heading":-3.03797, "vx":2.25233, "vy":-0.68034, "omega":0.62597, "ax":6.1426, "ay":-1.85535, "alpha":1.67017, "fx":[103.55551,107.4352,106.14118,100.80324], "fy":[-35.65854,-21.18852,-26.69012,-42.69886]}, + {"t":0.40274, "x":2.28659, "y":5.70946, "heading":-3.01505, "vx":2.47722, "vy":-0.74827, "omega":0.68712, "ax":6.13775, "ay":-1.85386, "alpha":1.65185, "fx":[103.56478,107.34947,105.95707,100.73414], "fy":[-35.36979,-21.15516,-26.99287,-42.61644]}, + {"t":0.43935, "x":2.3814, "y":5.68082, "heading":-2.98989, "vx":2.70194, "vy":-0.81614, "omega":0.7476, "ax":6.12961, "ay":-1.85134, "alpha":1.62375, "fx":[103.53211,107.19279,105.69181,100.63474], "fy":[-35.02486,-21.16736,-27.32918,-42.44183]}, + {"t":0.47596, "x":2.48444, "y":5.6497, "heading":-2.96252, "vx":2.92636, "vy":-0.88392, "omega":0.80704, "ax":6.11314, "ay":-1.84626, "alpha":1.57411, "fx":[103.38071,106.85967,105.23945,100.45134], "fy":[-34.58025,-21.28615,-27.69545,-42.05526]}, + {"t":0.51257, "x":2.59567, "y":5.6161, "heading":-2.93297, "vx":3.15018, "vy":-0.95152, "omega":0.86468, "ax":6.06291, "ay":-1.83075, "alpha":1.45752, "fx":[102.71817,105.84005,104.08562,99.86994], "fy":[-33.83679,-21.71641,-28.04427,-40.96462]}, + {"t":0.54919, "x":2.71507, "y":5.58004, "heading":-2.90132, "vx":3.37215, "vy":-1.01855, "omega":0.91804, "ax":0.00143, "ay":-0.00403, "alpha":-0.15556, "fx":[-0.46399,-0.2718,0.51263,0.32044], "fy":[0.22759,-0.55684,-0.36465,0.41979]}, + {"t":0.5858, "x":2.83854, "y":5.54274, "heading":-2.8677, "vx":3.37221, "vy":-1.01869, "omega":0.91234, "ax":-6.06287, "ay":1.83063, "alpha":-1.46057, "fx":[-102.90929,-105.88169,-103.89226,-99.82735], "fy":[33.25969,21.46017,28.7346,41.09985]}, + {"t":0.62241, "x":2.95794, "y":5.50667, "heading":-2.8343, "vx":3.15023, "vy":-0.95167, "omega":0.85887, "ax":-6.11313, "ay":1.84627, "alpha":-1.57315, "fx":[-103.78728,-106.94747,-104.82612,-100.36967], "fy":[33.34823,20.78254,29.20402,42.28309]}, + {"t":0.65902, "x":3.06918, "y":5.47307, "heading":-2.80286, "vx":2.92641, "vy":-0.88407, "omega":0.80127, "ax":-6.12963, "ay":1.85143, "alpha":-1.61989, "fx":[-104.14349,-107.32587,-105.06897,-100.51472], "fy":[33.17067,20.42267,29.61727,42.75849]}, + {"t":0.69563, "x":3.17221, "y":5.44194, "heading":-2.77352, "vx":2.70199, "vy":-0.81629, "omega":0.74196, "ax":-6.1378, "ay":1.854, "alpha":-1.64553, "fx":[-104.3668,-107.52458,-105.13843,-100.57922], "fy":[32.93568,20.1873,30.00802,43.01331]}, + {"t":0.73225, "x":3.26702, "y":5.4133, "heading":-2.74635, "vx":2.47727, "vy":-0.74841, "omega":0.68172, "ax":-6.14267, "ay":1.85555, "alpha":-1.66173, "fx":[-104.53286,-107.64866,-105.14163,-100.61725], "fy":[32.69002,20.01779,30.37498,43.16695]}, + {"t":0.76886, "x":3.35361, "y":5.38714, "heading":-2.7214, "vx":2.25238, "vy":-0.68047, "omega":0.62088, "ax":-6.1459, "ay":1.85659, "alpha":-1.67294, "fx":[-104.6665,-107.73397,-105.11522,-100.64445], "fy":[32.45051,19.88964,30.71567,43.26459]}, + {"t":0.80547, "x":3.43195, "y":5.36347, "heading":-2.69866, "vx":2.02736, "vy":-0.6125, "omega":0.55963, "ax":-6.1482, "ay":1.85734, "alpha":-1.68119, "fx":[-104.77826,-107.79625,-105.07536,-100.66652], "fy":[32.22479,19.79027,31.0283,43.32787]}, + {"t":0.84208, "x":3.50206, "y":5.34229, "heading":-2.67817, "vx":1.80226, "vy":-0.5445, "omega":0.49808, "ax":-6.14991, "ay":1.8579, "alpha":-1.68755, "fx":[-104.87342,-107.84357,-105.03035,-100.68575], "fy":[32.01693,19.71218,31.31163,43.36888]}, + {"t":0.8787, "x":3.56392, "y":5.3236, "heading":-2.65994, "vx":1.5771, "vy":-0.47648, "omega":0.43629, "ax":-6.15124, "ay":1.85834, "alpha":-1.69263, "fx":[-104.95495,-107.88055,-104.98497,-100.70307], "fy":[31.82927,19.65038,31.56484,43.39514]}, + {"t":0.91531, "x":3.61754, "y":5.3074, "heading":-2.64396, "vx":1.35189, "vy":-0.40844, "omega":0.37432, "ax":-6.1523, "ay":1.8587, "alpha":-1.6968, "fx":[-105.02464,-107.91007,-104.94218,-100.71875], "fy":[31.6633,19.60131,31.7874,43.41174]}, + {"t":0.95192, "x":3.66291, "y":5.29369, "heading":-2.63026, "vx":1.12664, "vy":-0.34039, "omega":0.3122, "ax":-6.15317, "ay":1.85899, "alpha":-1.70028, "fx":[-105.08368,-107.93404,-104.90394,-100.73283], "fy":[31.51997,19.56228,31.97896,43.42231]}, + {"t":0.98853, "x":3.70003, "y":5.28248, "heading":-2.61883, "vx":0.90135, "vy":-0.27232, "omega":0.24994, "ax":-6.15389, "ay":1.85923, "alpha":-1.70324, "fx":[-105.13287,-107.95377,-104.87158,-100.74521], "fy":[31.39994,19.5312,32.13932,43.42951]}, + {"t":1.02515, "x":3.72891, "y":5.27375, "heading":-2.60968, "vx":0.67605, "vy":-0.20425, "omega":0.18759, "ax":-6.15449, "ay":1.85944, "alpha":-1.70577, "fx":[-105.17279,-107.97021,-104.84606,-100.75574], "fy":[31.30367,19.50646,32.26833,43.43538]}, + {"t":1.06176, "x":3.74954, "y":5.26752, "heading":-2.60281, "vx":0.45072, "vy":-0.13617, "omega":0.12513, "ax":-6.15502, "ay":1.85961, "alpha":-1.70795, "fx":[-105.20385,-107.98406,-104.82807,-100.76428], "fy":[31.2315,19.48677,32.36593,43.44143]}, + {"t":1.09837, "x":3.76191, "y":5.26378, "heading":-2.59823, "vx":0.22537, "vy":-0.06809, "omega":0.0626, "ax":-6.15547, "ay":1.85976, "alpha":-1.70983, "fx":[-105.22636,-107.99582,-104.81811,-100.77072], "fy":[31.18367,19.47118,32.43206,43.44883]}, + {"t":1.13498, "x":3.76604, "y":5.26253, "heading":-2.59594, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index d6c80cb9..1eac6983 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -159,6 +159,8 @@ public static void loadAutoTrajectories(Drive drive) { drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH_3"); drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH_4"); drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH_5"); + drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH_6"); + drive.getAutoFactory().cache().loadTrajectory("E_LEFT_PATH_7"); } public static final Command autoALeft( @@ -1863,6 +1865,8 @@ public static final LoggedAutoRoutine autoELeftPath( LoggedAutoTrajectory path3 = routine.trajectory("E_LEFT_PATH_3"); LoggedAutoTrajectory path4 = routine.trajectory("E_LEFT_PATH_4"); LoggedAutoTrajectory path5 = routine.trajectory("E_LEFT_PATH_5"); + LoggedAutoTrajectory path6 = routine.trajectory("E_LEFT_PATH_6"); + LoggedAutoTrajectory path7 = routine.trajectory("E_LEFT_PATH_7"); routine .active() @@ -1896,7 +1900,17 @@ public static final LoggedAutoRoutine autoELeftPath( drive, superstructure, cameras) .withTimeout(0.5), CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral( - superstructure, () -> ReefState.L4))); + superstructure, () -> ReefState.L4), + path6.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake, manipulator) + .withTimeout(0.5), + path7.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, cameras) + .withTimeout(0.5), + CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral( + superstructure, () -> ReefState.L4).withTimeout(1))); // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // path3.cmd(), @@ -1941,15 +1955,15 @@ public static final LoggedAutoRoutine autoELeftArm( Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)) - .withTimeout(3), + .withTimeout(1), Commands.sequence( V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, cameras), V3_EpsilonCompositeCommands.scoreCoral(superstructure, () -> ReefState.L4)) - .withTimeout(2), + .withTimeout(1), path2.cmd(), - V3_EpsilonCompositeCommands.manipulatorGroundIntake(manipulator, superstructure) - .withTimeout(0.5), + V3_EpsilonCompositeCommands.manipulatorGroundIntake(manipulator, superstructure) + .withTimeout(0.5), Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), path3.cmd(), Commands.parallel( diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 9f8c0764..8a2a0ce5 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -30,7 +30,6 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; // Removed duplicate or conflicting import for ManipulatorArmState -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; import frc.robot.util.AllianceFlipUtil; import java.util.function.BooleanSupplier; @@ -901,10 +900,9 @@ public static final Command handoffCoral( public static final Command manipulatorGroundIntake( V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { return Commands.sequence( - Commands.runOnce(() -> superstructure.runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE)), - Commands.runOnce(() -> - manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE)) - ); + Commands.runOnce( + () -> superstructure.runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE)), + Commands.runOnce(() -> manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE))); } } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index a64f0fbb..e036cec2 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -147,6 +147,6 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { - return AutonomousCommands.autoELeftArm(drive, intake, superstructure, manipulator).cmd(); + return AutonomousCommands.autoELeftPath(drive, superstructure, intake, manipulator).cmd(); } } From c4a01abf320b998df7fa8977b7f464ee5b2d2dbc Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Fri, 19 Sep 2025 20:10:19 -0400 Subject: [PATCH 105/180] Refactor autonomous command and update superstructure states for improved intake handling --- src/main/deploy/Superstructure.dot | 117 ++++++++------ src/main/deploy/choreo/E_LEFT_PATH_1.traj | 66 -------- src/main/deploy/choreo/E_LEFT_PATH_2.traj | 75 --------- src/main/deploy/choreo/E_LEFT_PATH_3.traj | 64 -------- src/main/deploy/choreo/E_LEFT_PATH_4.traj | 66 -------- src/main/deploy/choreo/E_LEFT_PATH_5.traj | 65 -------- src/main/deploy/choreo/E_LEFT_PATH_6.traj | 71 --------- src/main/deploy/choreo/E_LEFT_PATH_7.traj | 66 -------- src/main/deploy/choreo/E_RIGHT_PATH_1.traj | 79 ++++++++++ .../deploy/choreo/E_RIGHT_PATH_1_BACK.traj | 132 ++++++++++++++++ src/main/deploy/choreo/E_RIGHT_PATH_2.traj | 141 +++++++++++++++++ .../deploy/choreo/E_RIGHT_PATH_2_BACK.traj | 121 +++++++++++++++ src/main/deploy/choreo/E_RIGHT_PATH_3.traj | 144 ++++++++++++++++++ .../deploy/choreo/E_RIGHT_PATH_3_BACK.traj | 82 ++++++++++ src/main/deploy/choreo/E_RIGHT_PATH_4.traj | 120 +++++++++++++++ .../deploy/choreo/E_RIGHT_PATH_4_BACK.traj | 119 +++++++++++++++ .../robot/commands/AutonomousCommands.java | 143 ++++++++++------- .../frc/robot/commands/CompositeCommands.java | 19 +++ .../v3_Epsilon/V3_EpsilonRobotContainer.java | 2 +- .../superstructure/Superstructure.dot | 12 ++ .../V3_EpsilonSuperstructure.java | 2 +- .../V3_EpsilonSuperstructureStates.java | 9 +- .../intake/V3_EpsilonIntakeConstants.java | 2 +- .../V3_EpsilonManipulatorConstants.java | 8 +- 24 files changed, 1144 insertions(+), 581 deletions(-) delete mode 100644 src/main/deploy/choreo/E_LEFT_PATH_1.traj delete mode 100644 src/main/deploy/choreo/E_LEFT_PATH_2.traj delete mode 100644 src/main/deploy/choreo/E_LEFT_PATH_3.traj delete mode 100644 src/main/deploy/choreo/E_LEFT_PATH_4.traj delete mode 100644 src/main/deploy/choreo/E_LEFT_PATH_5.traj delete mode 100644 src/main/deploy/choreo/E_LEFT_PATH_6.traj delete mode 100644 src/main/deploy/choreo/E_LEFT_PATH_7.traj create mode 100644 src/main/deploy/choreo/E_RIGHT_PATH_1.traj create mode 100644 src/main/deploy/choreo/E_RIGHT_PATH_1_BACK.traj create mode 100644 src/main/deploy/choreo/E_RIGHT_PATH_2.traj create mode 100644 src/main/deploy/choreo/E_RIGHT_PATH_2_BACK.traj create mode 100644 src/main/deploy/choreo/E_RIGHT_PATH_3.traj create mode 100644 src/main/deploy/choreo/E_RIGHT_PATH_3_BACK.traj create mode 100644 src/main/deploy/choreo/E_RIGHT_PATH_4.traj create mode 100644 src/main/deploy/choreo/E_RIGHT_PATH_4_BACK.traj diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/Superstructure.dot index 3ea062c6..0b153889 100644 --- a/src/main/deploy/Superstructure.dot +++ b/src/main/deploy/Superstructure.dot @@ -5,39 +5,51 @@ digraph Superstructure { STOW_DOWN -> L1 [type=UNCONSTRAINED] STOW_DOWN -> L2 [type=UNCONSTRAINED] STOW_DOWN -> L3 [type=UNCONSTRAINED] - STOW_DOWN -> L4 [type=UNCONSTRAINED, requires=ELEVATOR] + STOW_DOWN -> L4 [type=UNCONSTRAINED] STOW_DOWN -> HANDOFF [type=UNCONSTRAINED, requires=ELEVATOR] - STOW_DOWN -> STOW_UP [type=UNCONSTRAINED, requires=ELEVATOR] + STOW_DOWN -> STOW_UP [type=UNCONSTRAINED] STOW_DOWN -> L2_ALGAE [type=UNCONSTRAINED] STOW_DOWN -> L3_ALGAE [type=UNCONSTRAINED] STOW_DOWN -> PROCESSOR [type=UNCONSTRAINED] - STOW_DOWN -> BARGE [type=UNCONSTRAINED, requires=ELEVATOR] + STOW_DOWN -> BARGE [type=UNCONSTRAINED] - GROUND_ACQUISITION -> STOW_DOWN [type=UNCONSTRAINED, requires=ARM] + GROUND_ACQUISITION -> STOW_DOWN [type=UNCONSTRAINED] GROUND_ACQUISITION -> GROUND_INTAKE [type=UNCONSTRAINED] GROUND_ACQUISITION -> L1 [type=UNCONSTRAINED] - GROUND_ACQUISITION -> L2 [type=UNCONSTRAINED, requires=ARM] - GROUND_ACQUISITION -> L3 [type=UNCONSTRAINED, requires=ARM] + GROUND_ACQUISITION -> L2 [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L3 [type=UNCONSTRAINED] GROUND_ACQUISITION -> L4 [type=UNCONSTRAINED] GROUND_ACQUISITION -> HANDOFF [type=UNCONSTRAINED] - GROUND_ACQUISITION -> STOW_UP [type=UNCONSTRAINED, requires=ARM] - GROUND_ACQUISITION -> L2_ALGAE [type=UNCONSTRAINED, requires=ARM] - GROUND_ACQUISITION -> L3_ALGAE [type=UNCONSTRAINED, requires=ARM] - GROUND_ACQUISITION -> PROCESSOR [type=UNCONSTRAINED, requires=ARM] + GROUND_ACQUISITION -> STOW_UP [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L2_ALGAE [type=UNCONSTRAINED] + GROUND_ACQUISITION -> L3_ALGAE [type=UNCONSTRAINED] + GROUND_ACQUISITION -> PROCESSOR [type=UNCONSTRAINED] GROUND_ACQUISITION -> BARGE [type=UNCONSTRAINED] + GROUND_INTAKE -> STOW_DOWN [type=UNCONSTRAINED] GROUND_INTAKE -> GROUND_ACQUISITION [type=UNCONSTRAINED] - + GROUND_INTAKE -> L1 [type=UNCONSTRAINED] + GROUND_INTAKE -> L2 [type=UNCONSTRAINED] + GROUND_INTAKE -> L3 [type=UNCONSTRAINED] + GROUND_INTAKE -> L4 [type=UNCONSTRAINED] + GROUND_INTAKE -> HANDOFF [type=UNCONSTRAINED] + GROUND_INTAKE -> STOW_UP [type=UNCONSTRAINED] + GROUND_INTAKE -> L2_ALGAE [type=UNCONSTRAINED] + GROUND_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] + GROUND_INTAKE -> PROCESSOR [type=UNCONSTRAINED] + GROUND_INTAKE -> BARGE [type=UNCONSTRAINED] + + L1 -> STOW_DOWN [type=UNCONSTRAINED] L1 -> GROUND_ACQUISITION [type=UNCONSTRAINED] - L1 -> L2 [type=UNCONSTRAINED, requires=ARM] - L1 -> L3 [type=UNCONSTRAINED, requires=ARM] + L1 -> L2 [type=UNCONSTRAINED] + L1 -> L3 [type=UNCONSTRAINED] L1 -> L4 [type=UNCONSTRAINED] L1 -> L1_SCORE [type=UNCONSTRAINED] L1 -> HANDOFF [type=UNCONSTRAINED] - L1 -> STOW_UP [type=UNCONSTRAINED, requires=ARM] - L1 -> L2_ALGAE [type=UNCONSTRAINED, requires=ARM] - L1 -> L3_ALGAE [type=UNCONSTRAINED, requires=ARM] - L1 -> PROCESSOR [type=UNCONSTRAINED, requires=ARM] + L1 -> STOW_UP [type=UNCONSTRAINED] + L1 -> L2_ALGAE [type=UNCONSTRAINED] + L1 -> L3_ALGAE [type=UNCONSTRAINED] + L1 -> PROCESSOR [type=UNCONSTRAINED] L1 -> BARGE [type=UNCONSTRAINED] L2 -> STOW_DOWN [type=UNCONSTRAINED] @@ -57,7 +69,7 @@ digraph Superstructure { L3 -> GROUND_ACQUISITION [type=UNCONSTRAINED] L3 -> L1 [type=UNCONSTRAINED] L3 -> L2 [type=UNCONSTRAINED] - L3 -> L4 [type=UNCONSTRAINED, requires=ELEVATOR] + L3 -> L4 [type=UNCONSTRAINED] L3 -> L3_SCORE [type=UNCONSTRAINED] L3 -> HANDOFF [type=UNCONSTRAINED] L3 -> STOW_UP [type=UNCONSTRAINED] @@ -77,7 +89,7 @@ digraph Superstructure { L4 -> L2_ALGAE [type=UNCONSTRAINED] L4 -> L3_ALGAE [type=UNCONSTRAINED] L4 -> PROCESSOR [type=UNCONSTRAINED] - L4 -> BARGE [type=UNCONSTRAINED, requires=ELEVATOR] + L4 -> BARGE [type=UNCONSTRAINED] L1_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] @@ -113,7 +125,7 @@ digraph Superstructure { L4_SCORE -> L2 [type=UNCONSTRAINED] L4_SCORE -> L3 [type=UNCONSTRAINED] L4_SCORE -> L4 [type=UNCONSTRAINED] - L4_SCORE -> HANDOFF [type=UNCONSTRAINED, requires=ARM] + L4_SCORE -> HANDOFF [type=UNCONSTRAINED] L4_SCORE -> STOW_UP [type=UNCONSTRAINED] L4_SCORE -> L2_ALGAE [type=UNCONSTRAINED] L4_SCORE -> L3_ALGAE [type=UNCONSTRAINED] @@ -124,70 +136,76 @@ digraph Superstructure { HANDOFF -> GROUND_ACQUISITION [type=UNCONSTRAINED] HANDOFF -> L1 [type=UNCONSTRAINED] HANDOFF -> L2 [type=UNCONSTRAINED, requires=ARM] - HANDOFF -> L3 [type=UNCONSTRAINED, requires=ARM] + HANDOFF -> L3 [type=UNCONSTRAINED] HANDOFF -> L4 [type=UNCONSTRAINED] - HANDOFF -> STOW_UP [type=UNCONSTRAINED, requires=ARM] - HANDOFF -> L2_ALGAE [type=UNCONSTRAINED, requires=ARM] - HANDOFF -> L3_ALGAE [type=UNCONSTRAINED, requires=ARM] - HANDOFF -> PROCESSOR [type=UNCONSTRAINED, requires=ARM] + HANDOFF -> STOW_UP [type=UNCONSTRAINED] + HANDOFF -> L2_ALGAE [type=UNCONSTRAINED] + HANDOFF -> L3_ALGAE [type=UNCONSTRAINED] + HANDOFF -> PROCESSOR [type=UNCONSTRAINED] HANDOFF -> BARGE [type=UNCONSTRAINED] STOW_UP -> STOW_DOWN [type=UNCONSTRAINED] - STOW_UP -> GROUND_ACQUISITION [type=UNCONSTRAINED, requires=ELEVATOR] - STOW_UP -> L1 [type=UNCONSTRAINED, requires=ELEVATOR] + STOW_UP -> GROUND_ACQUISITION [type=UNCONSTRAINED] + STOW_UP -> L1 [type=UNCONSTRAINED] STOW_UP -> L2 [type=UNCONSTRAINED] STOW_UP -> L3 [type=UNCONSTRAINED] STOW_UP -> L4 [type=UNCONSTRAINED] - STOW_UP -> HANDOFF [type=UNCONSTRAINED, requires=ELEVATOR] + STOW_UP -> HANDOFF [type=UNCONSTRAINED] STOW_UP -> L2_ALGAE [type=UNCONSTRAINED] STOW_UP -> L3_ALGAE [type=UNCONSTRAINED] STOW_UP -> PROCESSOR [type=UNCONSTRAINED] STOW_UP -> BARGE [type=UNCONSTRAINED] - L2_ALGAE -> STOW_DOWN [type=NO_ALGAE] - L2_ALGAE -> GROUND_ACQUISITION [type=NO_ALGAE] - L2_ALGAE -> L1 [type=NO_ALGAE] + L2_ALGAE -> STOW_DOWN [type = NO_ALGAE] + L2_ALGAE -> GROUND_ACQUISITION [type = NO_ALGAE] + L2_ALGAE -> L1 [type = NO_ALGAE] L2_ALGAE -> L2 [type=UNCONSTRAINED] L2_ALGAE -> L3 [type=UNCONSTRAINED] L2_ALGAE -> L4 [type=UNCONSTRAINED] - L2_ALGAE -> HANDOFF [type=NO_ALGAE, requires=ARM] + L2_ALGAE -> HANDOFF [type = NO_ALGAE] L2_ALGAE -> STOW_UP [type=UNCONSTRAINED] L2_ALGAE -> L2_ALGAE_INTAKE [type=UNCONSTRAINED] - L2_ALGAE -> L3_ALGAE [type=NO_ALGAE] + L2_ALGAE -> L3_ALGAE [type = NO_ALGAE] L2_ALGAE -> PROCESSOR [type=UNCONSTRAINED] L2_ALGAE -> BARGE [type=UNCONSTRAINED] + L2_ALGAE -> L2_ALGAE_DROP + + L2_ALGAE_DROP -> L2_ALGAE L2_ALGAE_INTAKE -> STOW_UP [type=UNCONSTRAINED] L2_ALGAE_INTAKE -> L2_ALGAE [type=UNCONSTRAINED] - L3_ALGAE -> STOW_DOWN [type=NO_ALGAE] - L3_ALGAE -> GROUND_ACQUISITION [type=NO_ALGAE] - L3_ALGAE -> L1 [type=NO_ALGAE] + L3_ALGAE -> STOW_DOWN [type = NO_ALGAE] + L3_ALGAE -> GROUND_ACQUISITION [type = NO_ALGAE] + L3_ALGAE -> L1 [type = NO_ALGAE] L3_ALGAE -> L2 [type=UNCONSTRAINED] L3_ALGAE -> L3 [type=UNCONSTRAINED] L3_ALGAE -> L4 [type=UNCONSTRAINED] - L3_ALGAE -> HANDOFF [type=NO_ALGAE] + L3_ALGAE -> HANDOFF [type = NO_ALGAE] L3_ALGAE -> STOW_UP [type=UNCONSTRAINED] - L3_ALGAE -> L2_ALGAE [type=NO_ALGAE] + L3_ALGAE -> L2_ALGAE [type = NO_ALGAE] L3_ALGAE -> L3_ALGAE_INTAKE [type=UNCONSTRAINED] L3_ALGAE -> PROCESSOR [type=UNCONSTRAINED] L3_ALGAE -> BARGE [type=UNCONSTRAINED] + L3_ALGAE -> L3_ALGAE_DROP + + L3_ALGAE_DROP -> L3_ALGAE L3_ALGAE_INTAKE -> STOW_UP [type=UNCONSTRAINED] L3_ALGAE_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] - PROCESSOR -> STOW_DOWN [type=NO_ALGAE] - PROCESSOR -> GROUND_ACQUISITION [type=NO_ALGAE] - PROCESSOR -> L1 [type=NO_ALGAE] + PROCESSOR -> STOW_DOWN [type = NO_ALGAE] + PROCESSOR -> GROUND_ACQUISITION [type = NO_ALGAE] + PROCESSOR -> L1 [type = NO_ALGAE] PROCESSOR -> L2 [type=UNCONSTRAINED] PROCESSOR -> L3 [type=UNCONSTRAINED] - PROCESSOR -> L4 [type=UNCONSTRAINED, requires=ELEVATOR] - PROCESSOR -> HANDOFF [type=NO_ALGAE, requires=ELEVATOR] - PROCESSOR -> STOW_UP [type=UNCONSTRAINED, requires=ELEVATOR] + PROCESSOR -> L4 [type=UNCONSTRAINED] + PROCESSOR -> HANDOFF [type = NO_ALGAE] + PROCESSOR -> STOW_UP [type=UNCONSTRAINED] PROCESSOR -> L2_ALGAE [type=UNCONSTRAINED] PROCESSOR -> L3_ALGAE [type=UNCONSTRAINED] PROCESSOR -> PROCESSOR_SCORE [type=UNCONSTRAINED] - PROCESSOR -> BARGE [type=UNCONSTRAINED, requires=ELEVATOR] + PROCESSOR -> BARGE [type=UNCONSTRAINED] PROCESSOR_SCORE -> PROCESSOR [type=UNCONSTRAINED] @@ -205,4 +223,13 @@ digraph Superstructure { BARGE -> BARGE_SCORE [type=UNCONSTRAINED] BARGE_SCORE -> BARGE [type=UNCONSTRAINED] + + L4_SCORE -> GROUND_AQUISITION_ALGAE + L2_SCORE -> GROUND_AQUISITION_ALGAE + + GROUND_AQUISITION_ALGAE -> STOW_UP + GROUND_AQUISITION_ALGAE -> PROCESSOR + + GROUND_AQUISITION_ALGAE -> GROUND_INTAKE_ALGAE + GROUND_INTAKE_ALGAE -> GROUND_AQUISITION_ALGAE } \ No newline at end of file diff --git a/src/main/deploy/choreo/E_LEFT_PATH_1.traj b/src/main/deploy/choreo/E_LEFT_PATH_1.traj deleted file mode 100644 index 501b2e9b..00000000 --- a/src/main/deploy/choreo/E_LEFT_PATH_1.traj +++ /dev/null @@ -1,66 +0,0 @@ -{ - "name":"E_LEFT_PATH_1", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":7.084641456604004, "y":1.5642421245574951, "heading":3.120762363350457, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":5.376737594604492, "y":2.6473031044006348, "heading":-2.5588534684945525, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"7.084641456604004 m", "val":7.084641456604004}, "y":{"exp":"1.5642421245574951 m", "val":1.5642421245574951}, "heading":{"exp":"3.120762363350457 rad", "val":3.120762363350457}, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"5.376737594604492 m", "val":5.376737594604492}, "y":{"exp":"2.6473031044006348 m", "val":2.6473031044006348}, "heading":{"exp":"-2.5588534684945525 rad", "val":-2.5588534684945525}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.12324], - "samples":[ - {"t":0.0, "x":7.08464, "y":1.56424, "heading":3.12076, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.42556, "ay":3.43998, "alpha":1.93869, "fx":[-94.68646,-84.29752,-91.02993,-99.13511], "fy":[55.42934,70.25083,61.30695,47.06539]}, - {"t":0.03623, "x":7.08108, "y":1.5665, "heading":3.12076, "vx":-0.19659, "vy":0.12464, "omega":0.07025, "ax":-5.42516, "ay":3.43973, "alpha":1.93667, "fx":[-94.67523,-84.30019,-91.02486,-99.1215], "fy":[55.42824,70.23327,61.30018,47.07389]}, - {"t":0.07247, "x":7.0704, "y":1.57327, "heading":3.12331, "vx":-0.39316, "vy":0.24928, "omega":0.14042, "ax":-5.4247, "ay":3.43945, "alpha":1.93415, "fx":[-94.64207,-84.30082,-91.0366,-99.11096], "fy":[55.46142,70.21602,61.26625,47.07271]}, - {"t":0.1087, "x":7.05259, "y":1.58456, "heading":3.1284, "vx":-0.58972, "vy":0.3739, "omega":0.2105, "ax":-5.42417, "ay":3.43913, "alpha":1.93105, "fx":[-94.58658,-84.29972,-91.06486,-99.10283], "fy":[55.52869,70.19818,61.20497,47.06243]}, - {"t":0.14493, "x":7.02766, "y":1.60037, "heading":3.13602, "vx":-0.78626, "vy":0.49851, "omega":0.28047, "ax":-5.42353, "ay":3.43875, "alpha":1.92727, "fx":[-94.50816,-84.29738,-91.10924,-99.09614], "fy":[55.62982,70.17842,61.1161,47.04401]}, - {"t":0.18117, "x":6.99561, "y":1.62069, "heading":-3.137, "vx":-0.98277, "vy":0.62311, "omega":0.3503, "ax":-5.42277, "ay":3.43829, "alpha":1.9227, "fx":[-94.40594,-84.29456,-91.16919,-99.08953], "fy":[55.7645,70.15483,60.99923,47.0188]}, - {"t":0.2174, "x":6.95644, "y":1.64552, "heading":-3.12431, "vx":-1.17926, "vy":0.74769, "omega":0.41997, "ax":-5.42184, "ay":3.43773, "alpha":1.91714, "fx":[-94.27873,-84.29221,-91.2439,-99.08104], "fy":[55.93225,70.12475,60.85384,46.98863]}, - {"t":0.25364, "x":6.91015, "y":1.67487, "heading":-3.10909, "vx":-1.37571, "vy":0.87226, "omega":0.48943, "ax":-5.42067, "ay":3.43704, "alpha":1.91032, "fx":[-94.12484,-84.29156,-91.33217,-99.06791], "fy":[56.13226,70.0845,60.67916,46.95604]}, - {"t":0.28987, "x":6.85675, "y":1.70873, "heading":-3.09136, "vx":-1.57212, "vy":0.99679, "omega":0.55865, "ax":-5.41917, "ay":3.43613, "alpha":1.90183, "fx":[-93.94178,-84.29411,-91.43212,-99.046], "fy":[56.36312,70.02877,60.47406,46.92449]}, - {"t":0.3261, "x":6.79623, "y":1.74711, "heading":-3.07111, "vx":-1.76848, "vy":1.1213, "omega":0.62756, "ax":-5.41715, "ay":3.43491, "alpha":1.89096, "fx":[-93.7257,-84.30167,-91.54066,-99.0088], "fy":[56.62237,69.94953,60.23678,46.89899]}, - {"t":0.36234, "x":6.72859, "y":1.78999, "heading":-3.04838, "vx":-1.96476, "vy":1.24576, "omega":0.69608, "ax":-5.41432, "ay":3.43319, "alpha":1.87648, "fx":[-93.46998,-84.31636,-91.65226,-98.94523], "fy":[56.90542,69.83361,59.96423,46.88713]}, - {"t":0.39857, "x":6.65385, "y":1.83738, "heading":-3.02315, "vx":-2.16094, "vy":1.37015, "omega":0.76407, "ax":-5.41004, "ay":3.43057, "alpha":1.85601, "fx":[-93.16188,-84.34056,-91.75599,-98.83424], "fy":[57.20304,69.65693,59.65037,46.90168]}, - {"t":0.4348, "x":6.572, "y":1.88928, "heading":-2.99547, "vx":-2.35697, "vy":1.49445, "omega":0.83132, "ax":-5.40285, "ay":3.42613, "alpha":1.82429, "fx":[-92.77228,-84.37581,-91.82658,-98.62917], "fy":[57.49404,69.36783,59.28112,46.96702]}, - {"t":0.47104, "x":6.48305, "y":1.94568, "heading":-2.96535, "vx":-2.55273, "vy":1.6186, "omega":0.89742, "ax":-5.38833, "ay":3.41709, "alpha":1.76713, "fx":[-92.21464,-84.41498,-91.78861,-98.19729], "fy":[57.71657,68.82486,58.8136,47.13963]}, - {"t":0.50727, "x":6.38702, "y":2.00657, "heading":-2.93283, "vx":-2.74797, "vy":1.74241, "omega":0.96145, "ax":-5.34391, "ay":3.38926, "alpha":1.62763, "fx":[-91.05953,-84.34265,-91.26477,-96.92635], "fy":[57.57387,67.41338,58.02736,47.58704]}, - {"t":0.54351, "x":6.28394, "y":2.07193, "heading":-2.89799, "vx":-2.9416, "vy":1.86522, "omega":1.02042, "ax":0.00588, "ay":0.0076, "alpha":0.05008, "fx":[0.25761,0.1949,-0.05743,0.00528], "fy":[0.03451,0.28683,0.22412,-0.0282]}, - {"t":0.57974, "x":6.17736, "y":2.13952, "heading":-2.86102, "vx":-2.94139, "vy":1.86549, "omega":1.02224, "ax":5.34415, "ay":-3.38899, "alpha":-1.62515, "fx":[90.55472,84.4405,91.6758,96.93894], "fy":[-58.36632,-67.31367,-57.37464,-47.52808]}, - {"t":0.61597, "x":6.07429, "y":2.20489, "heading":-2.82398, "vx":-2.74775, "vy":1.7427, "omega":0.96335, "ax":5.38834, "ay":-3.41711, "alpha":-1.7663, "fx":[91.10259,84.60112,92.66175,98.25119], "fy":[-59.45772,-68.62023,-57.42737,-46.99091]}, - {"t":0.65221, "x":5.97827, "y":2.26579, "heading":-2.78907, "vx":-2.55251, "vy":1.61888, "omega":0.89935, "ax":5.40274, "ay":-3.42632, "alpha":-1.82443, "fx":[91.08177,84.65445,93.13911,98.72079], "fy":[-60.13765,-69.0518,-57.19611,-46.73743]}, - {"t":0.68844, "x":5.88933, "y":2.3222, "heading":-2.75649, "vx":-2.35675, "vy":1.49473, "omega":0.83325, "ax":5.40982, "ay":-3.43089, "alpha":-1.85699, "fx":[90.93259,84.70911,93.47731,98.959], "fy":[-60.68574,-69.23213,-56.91428,-46.60158]}, - {"t":0.72467, "x":5.80748, "y":2.3741, "heading":-2.7263, "vx":-2.16073, "vy":1.37042, "omega":0.76596, "ax":5.41401, "ay":-3.43361, "alpha":-1.87824, "fx":[90.74527,84.77036,93.74943,99.09831], "fy":[-61.1583,-69.30504,-56.62865,-46.52721]}, - {"t":0.76091, "x":5.73275, "y":2.42151, "heading":-2.69854, "vx":-1.96456, "vy":1.24601, "omega":0.69791, "ax":5.41678, "ay":-3.43542, "alpha":-1.89345, "fx":[90.55045,84.8358,93.97975,99.18546], "fy":[-61.57433,-69.32327,-56.35495,-46.48974]}, - {"t":0.79714, "x":5.66512, "y":2.4644, "heading":-2.67325, "vx":-1.76829, "vy":1.12153, "omega":0.6293, "ax":5.41873, "ay":-3.43671, "alpha":-1.905, "fx":[90.36145,84.90259,94.17881,99.24166], "fy":[-61.94237,-69.31153,-56.09999,-46.47593]}, - {"t":0.83337, "x":5.6046, "y":2.50278, "heading":-2.65045, "vx":-1.57195, "vy":0.997, "omega":0.56028, "ax":5.42019, "ay":-3.43767, "alpha":-1.91414, "fx":[90.18493,84.96831,94.35197,99.27827], "fy":[-62.26705,-69.28338,-55.86716,-46.47753]}, - {"t":0.86961, "x":5.5512, "y":2.53665, "heading":-2.63015, "vx":-1.37556, "vy":0.87244, "omega":0.49092, "ax":5.42131, "ay":-3.43841, "alpha":-1.92155, "fx":[90.02456,85.03098,94.50236,99.30209], "fy":[-62.55133,-69.24713,-55.65833,-46.48882]}, - {"t":0.90584, "x":5.50492, "y":2.566, "heading":-2.61236, "vx":-1.17912, "vy":0.74786, "omega":0.42129, "ax":5.42221, "ay":-3.439, "alpha":-1.92766, "fx":[89.88245,85.08895,94.63196,99.31761], "fy":[-62.79732,-69.20835,-55.47455,-46.50556]}, - {"t":0.94208, "x":5.46576, "y":2.59084, "heading":-2.5971, "vx":-0.98266, "vy":0.62325, "omega":0.35145, "ax":5.42294, "ay":-3.43948, "alpha":-1.93275, "fx":[89.75985,85.14088,94.7421,99.32792], "fy":[-63.00663,-69.17094,-55.31646,-46.52447]}, - {"t":0.97831, "x":5.43371, "y":2.61117, "heading":-2.58436, "vx":-0.78616, "vy":0.49863, "omega":0.28142, "ax":5.42355, "ay":-3.43988, "alpha":-1.93699, "fx":[89.65753,85.18569,94.83375,99.3353], "fy":[-63.18054,-69.13776,-55.18444,-46.54292]}, - {"t":1.01454, "x":5.40879, "y":2.62698, "heading":-2.57417, "vx":-0.58965, "vy":0.37399, "omega":0.21123, "ax":5.42407, "ay":-3.44022, "alpha":-1.94052, "fx":[89.57595,85.22248,94.90763,99.34145], "fy":[-63.3201,-69.11095,-55.07871,-46.55885]}, - {"t":1.05078, "x":5.39098, "y":2.63827, "heading":-2.56651, "vx":-0.39311, "vy":0.24933, "omega":0.14092, "ax":5.42452, "ay":-3.44051, "alpha":-1.94343, "fx":[89.51541,85.25059,94.96425,99.34764], "fy":[-63.42612,-69.09213,-54.99942,-46.57064]}, - {"t":1.08701, "x":5.3803, "y":2.64504, "heading":-2.56141, "vx":-0.19656, "vy":0.12467, "omega":0.0705, "ax":5.42491, "ay":-3.44076, "alpha":-1.9458, "fx":[89.47611,85.26948,95.00402,99.35483], "fy":[-63.49924,-69.08249,-54.94665,-46.57707]}, - {"t":1.12324, "x":5.37674, "y":2.6473, "heading":-2.55885, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/E_LEFT_PATH_2.traj b/src/main/deploy/choreo/E_LEFT_PATH_2.traj deleted file mode 100644 index 10315d08..00000000 --- a/src/main/deploy/choreo/E_LEFT_PATH_2.traj +++ /dev/null @@ -1,75 +0,0 @@ -{ - "name":"E_LEFT_PATH_2", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":5.517795562744141, "y":2.4597244262695312, "heading":-2.5111212813673753, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.6639331579208374, "y":2.2330267429351807, "heading":-3.0828368900825525, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"5.517795562744141 m", "val":5.517795562744141}, "y":{"exp":"2.4597244262695312 m", "val":2.4597244262695312}, "heading":{"exp":"-2.5111212813673753 rad", "val":-2.5111212813673753}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.6639331579208374 m", "val":1.6639331579208374}, "y":{"exp":"2.2330267429351807 m", "val":2.2330267429351807}, "heading":{"exp":"-3.0828368900825525 rad", "val":-3.0828368900825525}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.59126], - "samples":[ - {"t":0.0, "x":5.5178, "y":2.45972, "heading":-2.51112, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.41292, "ay":-0.37634, "alpha":-1.96876, "fx":[-109.69694,-107.90591,-109.27826,-109.44671], "fy":[-3.70309,-20.03584,-9.93912,8.07232]}, - {"t":0.03978, "x":5.51272, "y":2.45943, "heading":-2.51112, "vx":-0.25511, "vy":-0.01497, "omega":-0.07832, "ax":-6.41338, "ay":-0.37644, "alpha":-1.93509, "fx":[-109.68786,-107.93902,-109.27517,-109.45679], "fy":[-3.74607,-19.81158,-9.87086,7.81598]}, - {"t":0.07956, "x":5.4975, "y":2.45853, "heading":-2.51424, "vx":-0.51025, "vy":-0.02995, "omega":-0.1553, "ax":-6.41388, "ay":-0.37656, "alpha":-1.89635, "fx":[-109.67859,-107.97926,-109.26727,-109.46789], "fy":[-3.75796,-19.53837,-9.84042,7.51603]}, - {"t":0.11934, "x":5.47212, "y":2.45704, "heading":-2.52042, "vx":-0.7654, "vy":-0.04493, "omega":-0.23074, "ax":-6.41444, "ay":-0.3767, "alpha":-1.85115, "fx":[-109.66865,-108.02733,-109.2549,-109.48], "fy":[-3.74376,-19.2082,-9.84042,7.16185]}, - {"t":0.15913, "x":5.4366, "y":2.45496, "heading":-2.52959, "vx":-1.02058, "vy":-0.05991, "omega":-0.30438, "ax":-6.41506, "ay":-0.37688, "alpha":-1.79759, "fx":[-109.65733,-108.08423,-109.23849,-109.49301], "fy":[-3.71018,-18.80975,-9.86108,6.7388]}, - {"t":0.19891, "x":5.39092, "y":2.45228, "heading":-2.5417, "vx":-1.27578, "vy":-0.07491, "omega":-0.37589, "ax":-6.41575, "ay":-0.37708, "alpha":-1.73299, "fx":[-109.64367,-108.15126,-109.21858,-109.50663], "fy":[-3.66652,-18.32692,-9.88923,6.22642]}, - {"t":0.23869, "x":5.33509, "y":2.449, "heading":-2.55666, "vx":-1.531, "vy":-0.08991, "omega":-0.44483, "ax":-6.41652, "ay":-0.37733, "alpha":-1.65348, "fx":[-109.62626,-108.23017,-109.19592,-109.52015], "fy":[-3.6261,-17.73621,-9.9066,5.59559]}, - {"t":0.27847, "x":5.26911, "y":2.44512, "heading":-2.57435, "vx":-1.78626, "vy":-0.10492, "omega":-0.51061, "ax":-6.41736, "ay":-0.37765, "alpha":-1.55316, "fx":[-109.60297,-108.32331,-109.17151,-109.53197], "fy":[-3.6088,-17.00204,-9.88705,4.80331]}, - {"t":0.31825, "x":5.19297, "y":2.44065, "heading":-2.59467, "vx":-2.04155, "vy":-0.11994, "omega":-0.5724, "ax":-6.41824, "ay":-0.37805, "alpha":-1.42271, "fx":[-109.57038,-108.4338,-109.14676,-109.53865], "fy":[-3.64601,-16.06768,-9.79141,3.78326]}, - {"t":0.35803, "x":5.10668, "y":2.43558, "heading":-2.61744, "vx":-2.29688, "vy":-0.13498, "omega":-0.62899, "ax":-6.41904, "ay":-0.37858, "alpha":-1.24641, "fx":[-109.52242,-108.56565,-109.12345,-109.53254], "fy":[-3.79087,-14.83638,-9.55768,2.42672]}, - {"t":0.39781, "x":5.01023, "y":2.42991, "heading":-2.64246, "vx":-2.55224, "vy":-0.15004, "omega":-0.67858, "ax":-6.41941, "ay":-0.37933, "alpha":-0.99549, "fx":[-109.447,-108.72311,-109.10344,-109.4955], "fy":[-4.14223,-13.12767,-9.07996,0.54089]}, - {"t":0.4376, "x":4.90362, "y":2.42364, "heading":-2.66945, "vx":-2.80761, "vy":-0.16513, "omega":-0.71818, "ax":-6.4182, "ay":-0.38042, "alpha":-0.61115, "fx":[-109.31557,-108.90532,-109.08679,-109.37952], "fy":[-4.90996,-10.56033,-8.15843,-2.25438]}, - {"t":0.47738, "x":4.78685, "y":2.41677, "heading":-2.69802, "vx":-3.06294, "vy":-0.18026, "omega":-0.74249, "ax":-6.41113, "ay":-0.38205, "alpha":0.04933, "fx":[-109.04148,-109.07029,-109.06194,-109.03243], "fy":[-6.63932,-6.16711,-6.35863,-6.8291]}, - {"t":0.51716, "x":4.65993, "y":2.4093, "heading":-2.72756, "vx":-3.31798, "vy":-0.19546, "omega":-0.74053, "ax":-6.37525, "ay":-0.38444, "alpha":1.45025, "fx":[-108.2106,-108.80696,-108.9453,-107.80215], "fy":[-11.35268,3.38565,-2.50906,-15.68053]}, - {"t":0.55694, "x":4.52289, "y":2.40122, "heading":-2.75702, "vx":-3.5716, "vy":-0.21076, "omega":-0.68284, "ax":-6.00304, "ay":-0.42971, "alpha":6.65301, "fx":[-99.73923,-99.97772,-107.97431,-100.74902], "fy":[-37.28329,39.21902,7.9724,-39.14537]}, - {"t":0.59672, "x":4.37605, "y":2.39249, "heading":-2.78418, "vx":-3.81041, "vy":-0.22785, "omega":-0.41817, "ax":-3.79868, "ay":-0.18364, "alpha":10.4581, "fx":[-39.53907,-56.05704,-87.0549,-75.80654], "fy":[-36.56418,49.51495,14.16573,-39.61116]}, - {"t":0.6365, "x":4.22147, "y":2.38329, "heading":-2.80082, "vx":-3.96152, "vy":-0.23516, "omega":-0.00213, "ax":-0.00936, "ay":0.07093, "alpha":0.01231, "fx":[-0.11836,-0.13972,-0.19994,-0.17859], "fy":[1.18715,1.24737,1.22601,1.16579]}, - {"t":0.67628, "x":4.06386, "y":2.37399, "heading":-2.8009, "vx":-3.96189, "vy":-0.23233, "omega":-0.00164, "ax":-0.00109, "ay":0.01852, "alpha":0.00001, "fx":[-0.01847,-0.01848,-0.01851,-0.0185], "fy":[0.31495,0.31498,0.31497,0.31494]}, - {"t":0.71607, "x":3.90625, "y":2.36476, "heading":-2.80097, "vx":-3.96194, "vy":-0.2316, "omega":-0.00164, "ax":-0.00028, "ay":0.00475, "alpha":0.0, "fx":[-0.00472,-0.00472,-0.00472,-0.00472], "fy":[0.08076,0.08076,0.08076,0.08076]}, - {"t":0.75585, "x":3.74864, "y":2.35555, "heading":-2.80104, "vx":-3.96195, "vy":-0.23141, "omega":-0.00164, "ax":-0.00006, "ay":0.00097, "alpha":0.0, "fx":[-0.00096,-0.00096,-0.00096,-0.00096], "fy":[0.01647,0.01647,0.01647,0.01647]}, - {"t":0.79563, "x":3.59103, "y":2.34634, "heading":-2.8011, "vx":-3.96195, "vy":-0.23137, "omega":-0.00164, "ax":0.00005, "ay":-0.00077, "alpha":0.0, "fx":[0.00077,0.00077,0.00077,0.00077], "fy":[-0.01315,-0.01315,-0.01315,-0.01315]}, - {"t":0.83541, "x":3.43342, "y":2.33714, "heading":-2.80117, "vx":-3.96195, "vy":-0.2314, "omega":-0.00164, "ax":0.00024, "ay":-0.00414, "alpha":0.0, "fx":[0.00412,0.00412,0.00412,0.00412], "fy":[-0.07044,-0.07044,-0.07044,-0.07044]}, - {"t":0.87519, "x":3.27581, "y":2.32793, "heading":-2.80123, "vx":-3.96194, "vy":-0.23157, "omega":-0.00164, "ax":0.00095, "ay":-0.01622, "alpha":-0.00001, "fx":[0.01618,0.01619,0.01621,0.01621], "fy":[-0.27595,-0.27597,-0.27596,-0.27594]}, - {"t":0.91497, "x":3.1182, "y":2.31871, "heading":-2.8013, "vx":-3.9619, "vy":-0.23221, "omega":-0.00164, "ax":0.00859, "ay":-0.06215, "alpha":-0.01172, "fx":[0.10733,0.12764,0.185,0.16469], "fy":[-1.03858,-1.09594,-1.07563,-1.01828]}, - {"t":0.95475, "x":2.96059, "y":2.30942, "heading":-2.80136, "vx":-3.96156, "vy":-0.23468, "omega":-0.00211, "ax":3.74383, "ay":0.18381, "alpha":-10.38927, "fx":[38.63065,54.742,86.07774,75.27533], "fy":[36.6843,-48.52207,-14.50139,38.84566]}, - {"t":0.99453, "x":2.80596, "y":2.30023, "heading":-2.80145, "vx":-3.81262, "vy":-0.22737, "omega":-0.41541, "ax":6.04123, "ay":0.4178, "alpha":-6.26759, "fx":[100.2435,101.15932,107.90649,101.72891], "fy":[36.45913,-35.99892,-8.58286,36.54904]}, - {"t":1.03432, "x":2.65907, "y":2.29151, "heading":-2.81797, "vx":-3.5723, "vy":-0.21075, "omega":-0.66474, "ax":6.37756, "ay":0.38482, "alpha":-1.34794, "fx":[108.17792,108.83471,108.95104,107.95846], "fy":[11.81166,-2.29041,2.04165,14.61955]}, - {"t":1.0741, "x":2.522, "y":2.28343, "heading":-2.84442, "vx":-3.31859, "vy":-0.19544, "omega":-0.71837, "ax":6.41124, "ay":0.38226, "alpha":-0.02652, "fx":[109.04644,109.06258,109.06029,109.04403], "fy":[6.60281,6.33688,6.40162,6.66693]}, - {"t":1.11388, "x":2.39506, "y":2.27596, "heading":-2.87299, "vx":-3.06354, "vy":-0.18023, "omega":-0.71942, "ax":6.41837, "ay":0.38058, "alpha":0.59745, "fx":[109.34501,108.95767,109.0298,109.36617], "fy":[4.17916,10.04788,8.92797,2.73893]}, - {"t":1.15366, "x":2.27826, "y":2.26909, "heading":-2.90161, "vx":-2.80821, "vy":-0.16509, "omega":-0.69565, "ax":6.41991, "ay":0.37946, "alpha":0.96257, "fx":[109.49032,108.8567,108.96516,109.49099], "fy":[2.67284,12.01576,10.66012,0.46943]}, - {"t":1.19344, "x":2.17163, "y":2.26283, "heading":-2.92929, "vx":-2.55282, "vy":-0.15, "omega":-0.65736, "ax":6.41985, "ay":0.37869, "alpha":1.20288, "fx":[109.57333,108.78575,108.89156,109.54865], "fy":[1.59003,13.17432,11.96434,-0.9634]}, - {"t":1.23322, "x":2.07516, "y":2.25716, "heading":-2.95544, "vx":-2.29742, "vy":-0.13493, "omega":-0.60951, "ax":6.4193, "ay":0.37811, "alpha":1.37331, "fx":[109.62497,108.73968,108.81735,109.5795], "fy":[0.74635,13.89718,13.00174,-1.91904]}, - {"t":1.273, "x":1.98884, "y":2.25209, "heading":-2.97969, "vx":-2.04206, "vy":-0.11989, "omega":-0.55488, "ax":6.4186, "ay":0.37766, "alpha":1.50056, "fx":[109.65866,108.71125,108.74597,109.59847], "fy":[0.05801,14.36402,13.85438,-2.58053]}, - {"t":1.31279, "x":1.91268, "y":2.24762, "heading":-3.00176, "vx":-1.78672, "vy":-0.10487, "omega":-0.49518, "ax":6.4179, "ay":0.3773, "alpha":1.59923, "fx":[109.68121,108.6947,108.67908,109.61169], "fy":[-0.51833,14.67266,14.56877,-3.05177]}, - {"t":1.35257, "x":1.84668, "y":2.24375, "heading":-3.02146, "vx":-1.5314, "vy":-0.08986, "omega":-0.43156, "ax":6.41724, "ay":0.377, "alpha":1.67796, "fx":[109.69655,108.68579,108.61759,109.62183], "fy":[-1.00731,14.88138,15.17362,-3.39681]}, - {"t":1.39235, "x":1.79084, "y":2.24047, "heading":-3.03863, "vx":-1.27612, "vy":-0.07486, "omega":-0.36481, "ax":6.41664, "ay":0.37675, "alpha":1.7422, "fx":[109.70708,108.68144,108.56198,109.63007], "fy":[-1.42402,15.02738,15.68786,-3.65772]}, - {"t":1.43213, "x":1.74515, "y":2.23779, "heading":-3.05314, "vx":-1.02085, "vy":-0.05987, "omega":-0.29551, "ax":6.41609, "ay":0.37653, "alpha":1.79561, "fx":[109.71444,108.67938,108.51253,109.6369], "fy":[-1.77819,15.13566,16.12467,-3.86357]}, - {"t":1.47191, "x":1.70962, "y":2.23571, "heading":-3.0649, "vx":-0.76561, "vy":-0.0449, "omega":-0.22407, "ax":6.41559, "ay":0.37634, "alpha":1.8407, "fx":[109.71973,108.67795,108.4694,109.64252], "fy":[-2.07642,15.22374,16.49357,-4.03525]}, - {"t":1.51169, "x":1.68424, "y":2.23422, "heading":-3.07381, "vx":-0.51039, "vy":-0.02992, "omega":-0.15085, "ax":6.41515, "ay":0.37617, "alpha":1.87927, "fx":[109.72376,108.67587,108.43266,109.64694], "fy":[-2.32329,15.30432,16.8016,-4.18817]}, - {"t":1.55147, "x":1.66901, "y":2.23332, "heading":-3.07981, "vx":-0.25519, "vy":-0.01496, "omega":-0.07609, "ax":6.41474, "ay":0.37603, "alpha":1.91264, "fx":[109.72713,108.67217,108.40236,109.65012], "fy":[-2.52204,15.38678,17.05403,-4.33396]}, - {"t":1.59126, "x":1.66393, "y":2.23303, "heading":-3.08284, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/E_LEFT_PATH_3.traj b/src/main/deploy/choreo/E_LEFT_PATH_3.traj deleted file mode 100644 index 4c930144..00000000 --- a/src/main/deploy/choreo/E_LEFT_PATH_3.traj +++ /dev/null @@ -1,64 +0,0 @@ -{ - "name":"E_LEFT_PATH_3", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":1.933159351348877, "y":2.1474287509918213, "heading":3.141592653589793, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":3.667616367340088, "y":2.670738458633423, "heading":2.5602479387771764, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"1.933159351348877 m", "val":1.933159351348877}, "y":{"exp":"2.1474287509918213 m", "val":2.1474287509918213}, "heading":{"exp":"3.141592653589793 rad", "val":3.141592653589793}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"3.667616367340088 m", "val":3.667616367340088}, "y":{"exp":"2.670738458633423 m", "val":2.670738458633423}, "heading":{"exp":"2.5602479387771764 rad", "val":2.5602479387771764}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.06353], - "samples":[ - {"t":0.0, "x":1.93316, "y":2.14743, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.1467, "ay":1.85418, "alpha":-2.08164, "fx":[100.07568,107.10259,107.986,103.05026], "fy":[45.00391,23.82217,19.57073,37.75973]}, - {"t":0.03667, "x":1.93729, "y":2.14868, "heading":3.14159, "vx":0.22542, "vy":0.068, "omega":-0.07634, "ax":6.14618, "ay":1.85403, "alpha":-2.08104, "fx":[100.06817,107.09142,107.97663,103.04281], "fy":[44.99586,23.82238,19.57239,37.75529]}, - {"t":0.07335, "x":1.94969, "y":2.15242, "heading":3.13879, "vx":0.45082, "vy":0.13599, "omega":-0.15266, "ax":6.14558, "ay":1.85384, "alpha":-2.08004, "fx":[100.05308,107.06946,107.96961,103.04596], "fy":[45.00069,23.86252,19.55244,37.71783]}, - {"t":0.11002, "x":1.97036, "y":2.15865, "heading":3.13319, "vx":0.6762, "vy":0.20398, "omega":-0.22894, "ax":6.14487, "ay":1.85363, "alpha":-2.07861, "fx":[100.03026,107.03612,107.96446,103.05937], "fy":[45.01764,23.94277,19.51125,37.64707]}, - {"t":0.14669, "x":1.99929, "y":2.16738, "heading":3.1248, "vx":0.90155, "vy":0.27196, "omega":-0.30517, "ax":6.14403, "ay":1.85337, "alpha":-2.0767, "fx":[99.99958,106.99047,107.96043,103.08253], "fy":[45.04542,24.06355,19.44948,37.5426]}, - {"t":0.18337, "x":2.03648, "y":2.1786, "heading":3.11361, "vx":1.12687, "vy":0.33993, "omega":-0.38133, "ax":6.14301, "ay":1.85305, "alpha":-2.07424, "fx":[99.9609,106.93118,107.95645,103.11474], "fy":[45.08217,24.22545,19.36809,37.40382]}, - {"t":0.22004, "x":2.08194, "y":2.19231, "heading":3.09962, "vx":1.35216, "vy":0.40788, "omega":-0.4574, "ax":6.14173, "ay":1.85266, "alpha":-2.07115, "fx":[99.91388,106.85634,107.95096,103.15491], "fy":[45.12531,24.42916,19.26838,37.22989]}, - {"t":0.25671, "x":2.13566, "y":2.20851, "heading":3.08285, "vx":1.5774, "vy":0.47583, "omega":-0.53336, "ax":6.14008, "ay":1.85216, "alpha":-2.0673, "fx":[99.85775,106.76306,107.9416,103.20132], "fy":[45.17133,24.67543,19.15208,37.01968]}, - {"t":0.29339, "x":2.19764, "y":2.22721, "heading":3.06329, "vx":1.80257, "vy":0.54375, "omega":-0.60917, "ax":6.13786, "ay":1.85149, "alpha":-2.0625, "fx":[99.79085,106.64679,107.92453,103.25109], "fy":[45.21534,24.96481,19.02139,36.77152]}, - {"t":0.33006, "x":2.26787, "y":2.2484, "heading":3.04095, "vx":2.02767, "vy":0.61165, "omega":-0.68481, "ax":6.13475, "ay":1.85055, "alpha":-2.05648, "fx":[99.70944,106.49975,107.89314,103.29903], "fy":[45.25016,25.29738,18.87917,36.48285]}, - {"t":0.36673, "x":2.34636, "y":2.27207, "heading":3.01583, "vx":2.25265, "vy":0.67952, "omega":-0.76023, "ax":6.13005, "ay":1.84915, "alpha":-2.04872, "fx":[99.60486,106.3071,107.83463,103.33475], "fy":[45.26411,25.67181,18.72909,36.14912]}, - {"t":0.40341, "x":2.43309, "y":2.29824, "heading":2.98795, "vx":2.47746, "vy":0.74733, "omega":-0.83536, "ax":6.12215, "ay":1.8468, "alpha":-2.03825, "fx":[99.45474,106.03534,107.71988,103.33407], "fy":[45.23486,26.0828,18.57587,35.76067]}, - {"t":0.44008, "x":2.52806, "y":2.32688, "heading":2.95732, "vx":2.70198, "vy":0.81506, "omega":-0.91011, "ax":6.10624, "ay":1.84206, "alpha":-2.02285, "fx":[99.187,105.58638,107.46344,103.22452], "fy":[45.10669,26.5105,18.4239,35.29046]}, - {"t":0.47675, "x":2.63126, "y":2.35801, "heading":2.92394, "vx":2.92591, "vy":0.88262, "omega":-0.98429, "ax":6.05822, "ay":1.82771, "alpha":-1.9957, "fx":[98.42283,104.47953,106.64742,102.64453], "fy":[44.64763,26.84379,18.2533,34.61044]}, - {"t":0.51343, "x":2.74264, "y":2.39161, "heading":2.88784, "vx":3.14809, "vy":0.94964, "omega":-1.05748, "ax":0.00386, "ay":0.00885, "alpha":0.29838, "fx":[0.62105,1.00988,-0.48955,-0.87845], "fy":[-0.79369,0.70577,1.09463,-0.40483]}, - {"t":0.5501, "x":2.85809, "y":2.42644, "heading":2.84906, "vx":3.14823, "vy":0.94997, "omega":-1.04654, "ax":-6.05813, "ay":-1.82732, "alpha":2.00108, "fx":[-98.36233,-104.17592,-106.70754,-102.94239], "fy":[-44.8237,-27.96907,-17.81008,-33.72609]}, - {"t":0.58677, "x":2.96947, "y":2.46005, "heading":2.81068, "vx":2.92606, "vy":0.88295, "omega":-0.97315, "ax":-6.1063, "ay":-1.84208, "alpha":2.01795, "fx":[-99.09591,-104.97529,-107.57744,-103.81684], "fy":[-45.34943,-28.81078,-17.65499,-33.51773]}, - {"t":0.62345, "x":3.07268, "y":2.4912, "heading":2.77499, "vx":2.70212, "vy":0.8154, "omega":-0.89915, "ax":-6.1223, "ay":-1.84704, "alpha":2.02696, "fx":[-99.32911,-105.13868,-107.88723,-104.19946], "fy":[-45.55194,-29.46752,-17.4875,-33.16377]}, - {"t":0.66012, "x":3.16765, "y":2.51986, "heading":2.74202, "vx":2.4776, "vy":0.74766, "omega":-0.82481, "ax":-6.13027, "ay":-1.84956, "alpha":2.03256, "fx":[-99.44747,-105.1473,-108.05129,-104.45045], "fy":[-45.64936,-30.05042,-17.34727,-32.79489]}, - {"t":0.69679, "x":3.25439, "y":2.54603, "heading":2.71177, "vx":2.25278, "vy":0.67983, "omega":-0.75027, "ax":-6.13503, "ay":-1.8511, "alpha":2.03647, "fx":[-99.52423,-105.09969,-108.1544,-104.64181], "fy":[-45.69504,-30.57804,-17.23388,-32.43949]}, - {"t":0.73347, "x":3.33289, "y":2.56972, "heading":2.68426, "vx":2.02779, "vy":0.61195, "omega":-0.67559, "ax":-6.13818, "ay":-1.85214, "alpha":2.03948, "fx":[-99.58204,-105.02963,-108.22547,-104.79758], "fy":[-45.7108,-31.05522,-17.14357,-32.10784]}, - {"t":0.77014, "x":3.40312, "y":2.59092, "heading":2.65948, "vx":1.80268, "vy":0.54402, "omega":-0.60079, "ax":-6.14042, "ay":-1.8529, "alpha":2.04195, "fx":[-99.62956,-104.95214,-108.27728,-104.92815], "fy":[-45.70826,-31.48352,-17.07259,-31.80466]}, - {"t":0.80681, "x":3.4651, "y":2.60962, "heading":2.63745, "vx":1.57749, "vy":0.47607, "omega":-0.52591, "ax":-6.14209, "ay":-1.85347, "alpha":2.04407, "fx":[-99.67045,-104.87504,-108.31645,-105.03885], "fy":[-45.69469,-31.86355,-17.01757,-31.53249]}, - {"t":0.84349, "x":3.51883, "y":2.62583, "heading":2.61816, "vx":1.35224, "vy":0.4081, "omega":-0.45095, "ax":-6.14338, "ay":-1.85393, "alpha":2.04593, "fx":[-99.70626,-104.8029,-108.34684,-105.13271], "fy":[-45.67518,-32.19564,-16.97554,-31.2928]}, - {"t":0.88016, "x":3.56429, "y":2.63955, "heading":2.60162, "vx":1.12694, "vy":0.34011, "omega":-0.37592, "ax":-6.14441, "ay":-1.85429, "alpha":2.04758, "fx":[-99.73762,-104.73861,-108.37088,-105.21164], "fy":[-45.65347,-32.48006,-16.94394,-31.08651]}, - {"t":0.91683, "x":3.60148, "y":2.65078, "heading":2.58784, "vx":0.90161, "vy":0.2721, "omega":-0.30082, "ax":-6.14525, "ay":-1.85459, "alpha":2.04902, "fx":[-99.76471,-104.68408,-108.39021,-105.2769], "fy":[-45.63244,-32.71705,-16.92058,-30.9142]}, - {"t":0.95351, "x":3.63041, "y":2.65951, "heading":2.5768, "vx":0.67624, "vy":0.20409, "omega":-0.22568, "ax":-6.14595, "ay":-1.85484, "alpha":2.05027, "fx":[-99.78749,-104.64062,-108.40598,-105.32938], "fy":[-45.61429,-32.90686,-16.90362,-30.77628]}, - {"t":0.99018, "x":3.65108, "y":2.66575, "heading":2.56853, "vx":0.45085, "vy":0.13607, "omega":-0.15049, "ax":-6.14654, "ay":-1.85504, "alpha":2.05133, "fx":[-99.80589,-104.60917,-108.41901,-105.36972], "fy":[-45.60074,-33.04973,-16.89159,-30.673]}, - {"t":1.02685, "x":3.66348, "y":2.66949, "heading":2.56301, "vx":0.22543, "vy":0.06804, "omega":-0.07526, "ax":-6.14705, "ay":-1.85522, "alpha":2.05219, "fx":[-99.81982,-104.5904,-108.42989,-105.39839], "fy":[-45.59303,-33.14586,-16.88336,-30.60454]}, - {"t":1.06353, "x":3.66762, "y":2.67074, "heading":2.56025, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/E_LEFT_PATH_4.traj b/src/main/deploy/choreo/E_LEFT_PATH_4.traj deleted file mode 100644 index c43e270d..00000000 --- a/src/main/deploy/choreo/E_LEFT_PATH_4.traj +++ /dev/null @@ -1,66 +0,0 @@ -{ - "name":"E_LEFT_PATH_4", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":3.7104902267456055, "y":2.7445008754730225, "heading":2.6191890324062967, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.0025863647460938, "y":4.063613414764404, "heading":3.141592653589793, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"3.7104902267456055 m", "val":3.7104902267456055}, "y":{"exp":"2.7445008754730225 m", "val":2.7445008754730225}, "heading":{"exp":"2.6191890324062967 rad", "val":2.6191890324062967}, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.0025863647460938 m", "val":2.0025863647460938}, "y":{"exp":"4.063613414764404 m", "val":4.063613414764404}, "heading":{"exp":"3.141592653589793 rad", "val":3.141592653589793}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.15945], - "samples":[ - {"t":0.0, "x":3.71049, "y":2.7445, "heading":2.61919, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.0914, "ay":3.9326, "alpha":1.59421, "fx":[-91.30514,-80.48278,-82.74985,-91.87511], "fy":[60.85871,74.58957,72.09273,60.0286]}, - {"t":0.0374, "x":3.70693, "y":2.74725, "heading":2.61919, "vx":-0.19043, "vy":0.14709, "omega":0.05963, "ax":-5.09105, "ay":3.93232, "alpha":1.5914, "fx":[-91.28939,-80.4885,-82.75072,-91.86069], "fy":[60.8653,74.56981,72.07951,60.03574]}, - {"t":0.0748, "x":3.69625, "y":2.7555, "heading":2.62142, "vx":-0.38084, "vy":0.29416, "omega":0.11915, "ax":-5.09065, "ay":3.93199, "alpha":1.58811, "fx":[-91.25947,-80.48522,-82.76469,-91.85282], "fy":[60.89046,74.5577,72.04938,60.03051]}, - {"t":0.1122, "x":3.67844, "y":2.76926, "heading":2.62588, "vx":-0.57124, "vy":0.44122, "omega":0.17854, "ax":-5.09019, "ay":3.93161, "alpha":1.58422, "fx":[-91.21478,-80.47336,-82.79171,-91.85081], "fy":[60.93438,74.5523,72.0019,60.01339]}, - {"t":0.14961, "x":3.65352, "y":2.78851, "heading":2.63255, "vx":-0.76162, "vy":0.58827, "omega":0.2378, "ax":-5.08964, "ay":3.93115, "alpha":1.57961, "fx":[-91.15447,-80.45356,-82.83174,-91.85368], "fy":[60.99737,74.55222,71.93642,59.98507]}, - {"t":0.18701, "x":3.62147, "y":2.81326, "heading":2.64145, "vx":-0.95198, "vy":0.7353, "omega":0.29688, "ax":-5.08899, "ay":3.93061, "alpha":1.57406, "fx":[-91.0773,-80.42668,-82.88472,-91.86004], "fy":[61.07989,74.55554,71.85205,59.94649]}, - {"t":0.22441, "x":3.58231, "y":2.84351, "heading":2.65255, "vx":-1.14231, "vy":0.88231, "omega":0.35575, "ax":-5.08818, "ay":3.92994, "alpha":1.56728, "fx":[-90.98157,-80.39393,-82.95056,-91.86797], "fy":[61.18252,74.55954,71.74749,59.89901]}, - {"t":0.26181, "x":3.53602, "y":2.87926, "heading":2.66586, "vx":-1.33262, "vy":1.0293, "omega":0.41437, "ax":-5.08717, "ay":3.9291, "alpha":1.55886, "fx":[-90.86479,-80.35694,-83.02906,-91.87461], "fy":[61.30603,74.56033,71.62088,59.84449]}, - {"t":0.29921, "x":3.48262, "y":2.9205, "heading":2.68135, "vx":-1.52289, "vy":1.17625, "omega":0.47267, "ax":-5.08587, "ay":3.92803, "alpha":1.54816, "fx":[-90.7233,-80.31799,-83.11983,-91.8757], "fy":[61.45135,74.55215,71.46942,59.78565]}, - {"t":0.33661, "x":3.42211, "y":2.96724, "heading":2.69903, "vx":-1.71311, "vy":1.32317, "omega":0.53057, "ax":-5.08413, "ay":3.92659, "alpha":1.53412, "fx":[-90.55128,-80.28033,-83.2221,-91.86435], "fy":[61.61965,74.52594,71.28861,59.72657]}, - {"t":0.37401, "x":3.35448, "y":3.01948, "heading":2.71888, "vx":-1.90326, "vy":1.47003, "omega":0.58795, "ax":-5.08166, "ay":3.92457, "alpha":1.51493, "fx":[-90.33878,-80.24894,-83.33422,-91.82869], "fy":[61.81239,74.46633,71.07072,59.67391]}, - {"t":0.41142, "x":3.27974, "y":3.07721, "heading":2.74087, "vx":-2.09332, "vy":1.61681, "omega":0.64461, "ax":-5.07794, "ay":3.92152, "alpha":1.48709, "fx":[-90.06681,-80.23214,-83.4525,-91.74583], "fy":[62.03143,74.34434,70.80075,59.63947]}, - {"t":0.44882, "x":3.19789, "y":3.14042, "heading":2.76498, "vx":-2.28324, "vy":1.76348, "omega":0.70023, "ax":-5.07166, "ay":3.9164, "alpha":1.4429, "fx":[-89.69291,-80.24543,-83.56733,-91.56441], "fy":[62.2789,74.09619,70.4448,59.64728]}, - {"t":0.48622, "x":3.10895, "y":3.20912, "heading":2.79117, "vx":-2.47293, "vy":1.90996, "omega":0.7542, "ax":-5.05889, "ay":3.90599, "alpha":1.36115, "fx":[-89.09576,-80.32206,-83.64602,-91.13722], "fy":[62.55393,73.54383,69.90454,59.75668]}, - {"t":0.52362, "x":3.01292, "y":3.28328, "heading":2.81937, "vx":-2.66214, "vy":2.05605, "omega":0.80511, "ax":-5.01939, "ay":3.87391, "alpha":1.15281, "fx":[-87.71436,-80.52668,-83.49143,-89.78111], "fy":[62.79884,71.89889,68.71463,60.164]}, - {"t":0.56102, "x":2.90984, "y":3.36289, "heading":2.84949, "vx":-2.84987, "vy":2.20094, "omega":0.84822, "ax":-0.00142, "ay":0.00099, "alpha":-0.13447, "fx":[-0.25795,-0.45899,0.20958,0.41063], "fy":[0.45159,-0.21698,-0.41803,0.25054]}, - {"t":0.59842, "x":2.80325, "y":3.44521, "heading":2.88121, "vx":-2.84993, "vy":2.20098, "omega":0.8432, "ax":5.01949, "ay":-3.87402, "alpha":-1.13949, "fx":[87.39839,80.47033,83.79184,89.85994], "fy":[-63.23088,-71.9739,-68.34887,-60.03002]}, - {"t":0.63583, "x":2.70017, "y":3.52482, "heading":2.91275, "vx":-2.66219, "vy":2.05608, "omega":0.80058, "ax":5.05895, "ay":-3.90604, "alpha":-1.35534, "fx":[88.40757,80.0681,84.30746,91.42198], "fy":[-63.5135,-73.8349,-69.10983,-59.3044]}, - {"t":0.67323, "x":2.60414, "y":3.59899, "heading":2.94269, "vx":-2.47298, "vy":1.90999, "omega":0.74988, "ax":5.07171, "ay":-3.91643, "alpha":-1.43825, "fx":[88.63412,79.82919,84.58475,92.02534], "fy":[-63.76698,-74.55973,-69.22487,-58.91787]}, - {"t":0.71063, "x":2.51519, "y":3.66769, "heading":2.97074, "vx":-2.28329, "vy":1.76351, "omega":0.69609, "ax":5.078, "ay":-3.92155, "alpha":-1.482, "fx":[88.65687,79.673,84.80569,92.36543], "fy":[-64.02065,-74.95853,-69.17922,-58.65963]}, - {"t":0.74803, "x":2.43335, "y":3.7309, "heading":2.99677, "vx":-2.09336, "vy":1.61684, "omega":0.64066, "ax":5.08173, "ay":-3.92461, "alpha":-1.50891, "fx":[88.60225,79.56249,84.99863,92.59177], "fy":[-64.26731,-75.21438,-69.07651,-58.46748]}, - {"t":0.78543, "x":2.35861, "y":3.78863, "heading":3.02073, "vx":-1.9033, "vy":1.47005, "omega":0.58423, "ax":5.0842, "ay":-3.92663, "alpha":-1.52706, "fx":[88.51487,79.48073,85.17139,92.75646], "fy":[-64.50153,-75.3928,-68.95282,-58.31644]}, - {"t":0.82283, "x":2.29098, "y":3.84086, "heading":3.04259, "vx":-1.71314, "vy":1.32319, "omega":0.52711, "ax":5.08596, "ay":-3.92808, "alpha":-1.54011, "fx":[88.41478,79.41871,85.32681,92.88274], "fy":[-64.71992,-75.52366,-68.8242,-58.19419]}, - {"t":0.86023, "x":2.23046, "y":3.88761, "heading":3.0623, "vx":-1.52292, "vy":1.17627, "omega":0.46951, "ax":5.08727, "ay":-3.92916, "alpha":-1.54993, "fx":[88.31254,79.37097,85.46607,92.98273], "fy":[-64.92022,-75.62282,-68.69899,-58.09368]}, - {"t":0.89764, "x":2.17706, "y":3.92885, "heading":3.07986, "vx":-1.33265, "vy":1.02932, "omega":0.41154, "ax":5.08829, "ay":-3.93001, "alpha":-1.55761, "fx":[88.21429,79.33389,85.58975,93.06354], "fy":[-65.10094,-75.6997,-68.58199,-58.01043]}, - {"t":0.93504, "x":2.13077, "y":3.9646, "heading":3.09525, "vx":-1.14234, "vy":0.88233, "omega":0.35328, "ax":5.0891, "ay":-3.93068, "alpha":-1.56379, "fx":[88.1239,79.3049,85.69814,93.12965], "fy":[-65.26102,-75.76037,-68.47623,-57.94135]}, - {"t":0.97244, "x":2.09161, "y":3.99485, "heading":3.10847, "vx":-0.952, "vy":0.73532, "omega":0.2948, "ax":5.08976, "ay":-3.93123, "alpha":-1.56889, "fx":[88.04398,79.28207,85.7914,93.18409], "fy":[-65.39968,-75.80897,-68.38366,-57.88417]}, - {"t":1.00984, "x":2.05956, "y":4.01961, "heading":3.11949, "vx":-0.76164, "vy":0.58828, "omega":0.23612, "ax":5.09031, "ay":-3.93169, "alpha":-1.57318, "fx":[87.97632,79.26393,85.86961,93.22902], "fy":[-65.51639,-75.84846,-68.30567,-57.8372]}, - {"t":1.04724, "x":2.03464, "y":4.03886, "heading":3.12832, "vx":-0.57125, "vy":0.44123, "omega":0.17728, "ax":5.09077, "ay":-3.93208, "alpha":-1.57687, "fx":[87.92222,79.24934,85.93285,93.266], "fy":[-65.61072,-75.88102,-68.24323,-57.79912]}, - {"t":1.08464, "x":2.01683, "y":4.05261, "heading":3.13495, "vx":-0.38085, "vy":0.29417, "omega":0.1183, "ax":5.09117, "ay":-3.93241, "alpha":-1.58007, "fx":[87.88263,79.23741,85.98114,93.2962], "fy":[-65.68237,-75.90826,-68.19705,-57.76891]}, - {"t":1.12204, "x":2.00615, "y":4.06086, "heading":3.13938, "vx":-0.19043, "vy":0.14709, "omega":0.0592, "ax":5.09151, "ay":-3.93269, "alpha":-1.58291, "fx":[87.85826,79.22747,86.01452,93.32047], "fy":[-65.73112,-75.93139,-68.16767,-57.74582]}, - {"t":1.15945, "x":2.00259, "y":4.06361, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/E_LEFT_PATH_5.traj b/src/main/deploy/choreo/E_LEFT_PATH_5.traj deleted file mode 100644 index 8e864b99..00000000 --- a/src/main/deploy/choreo/E_LEFT_PATH_5.traj +++ /dev/null @@ -1,65 +0,0 @@ -{ - "name":"E_LEFT_PATH_5", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":1.974815368652344, "y":3.9941866397857666, "heading":3.120762184569173, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":3.0856471061706543, "y":3.9941866397857666, "heading":1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"1.9748153686523438 m", "val":1.974815368652344}, "y":{"exp":"3.9941866397857666 m", "val":3.9941866397857666}, "heading":{"exp":"3.120762184569173 rad", "val":3.120762184569173}, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"3.0856471061706543 m", "val":3.0856471061706543}, "y":{"exp":"3.9941866397857666 m", "val":3.9941866397857666}, "heading":{"exp":"1.5707963267948966 rad", "val":1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,0.86265], - "samples":[ - {"t":0.0, "x":1.97482, "y":3.99419, "heading":3.12076, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.95818, "ay":-0.00317, "alpha":-8.60885, "fx":[96.21035,96.74173,106.05976,106.37578], "fy":[52.57026,-51.57226,-28.18082,26.96724]}, - {"t":0.02876, "x":1.97728, "y":3.99419, "heading":3.12076, "vx":0.17133, "vy":-0.00009, "omega":-0.24755, "ax":5.95728, "ay":-0.00244, "alpha":-8.61037, "fx":[96.18131,96.72855,106.05264,106.36377], "fy":[52.58847,-51.56029,-28.17243,26.97817]}, - {"t":0.05751, "x":1.98467, "y":3.99418, "heading":3.11364, "vx":0.34263, "vy":-0.00016, "omega":-0.49514, "ax":5.95651, "ay":-0.00449, "alpha":-8.60883, "fx":[96.08776,96.79389,105.98332,106.40934], "fy":[52.72129,-51.39214,-28.39089,26.75598]}, - {"t":0.08627, "x":1.99698, "y":3.99418, "heading":3.09941, "vx":0.51391, "vy":-0.00029, "omega":-0.74269, "ax":5.95607, "ay":-0.00927, "alpha":-8.60161, "fx":[95.93719,96.94547,105.85066,106.51111], "fy":[52.95304,-51.04902,-28.83307,26.29863]}, - {"t":0.11502, "x":2.01422, "y":3.99416, "heading":3.07805, "vx":0.68518, "vy":-0.00056, "omega":-0.99003, "ax":5.95632, "ay":-0.01661, "alpha":-8.58375, "fx":[95.74418,97.19833,105.65263,106.66625], "fy":[53.25454,-50.49439,-29.49304,25.60253]}, - {"t":0.14378, "x":2.03639, "y":3.99414, "heading":3.04958, "vx":0.85645, "vy":-0.00103, "omega":-1.23685, "ax":5.95779, "ay":-0.02624, "alpha":-8.54799, "fx":[95.52997,97.5747,105.38656,106.87026], "fy":[53.58444,-49.67116,-30.36134,24.6629]}, - {"t":0.17253, "x":2.06348, "y":3.9941, "heading":3.01402, "vx":1.02777, "vy":-0.00179, "omega":-1.48265, "ax":5.96117, "ay":-0.03756, "alpha":-8.48498, "fx":[95.32168,98.1033,105.04964,107.11655], "fy":[53.89125,-48.49762,-31.42378,23.47443]}, - {"t":0.20129, "x":2.0955, "y":3.99403, "heading":2.97138, "vx":1.19918, "vy":-0.00287, "omega":-1.72664, "ax":5.96723, "ay":-0.04959, "alpha":-8.38367, "fx":[95.15097,98.81699,104.6396,107.39597], "fy":[54.11544,-46.86178,-32.65957,22.03212]}, - {"t":0.23004, "x":2.13245, "y":3.99393, "heading":2.92173, "vx":1.37077, "vy":-0.0043, "omega":-1.96771, "ax":5.97675, "ay":-0.06068, "alpha":-8.23228, "fx":[95.05207,99.74749,104.15589,107.69601], "fy":[54.19127,-44.61434,-34.03806,20.33264]}, - {"t":0.2588, "x":2.17433, "y":3.99378, "heading":2.86515, "vx":1.54263, "vy":-0.00604, "omega":-2.20443, "ax":5.99033, "ay":-0.06835, "alpha":-8.01968, "fx":[95.05936,100.9143,103.60155,107.99969], "fy":[54.0468,-41.56042,-35.51268,18.37617]}, - {"t":0.28755, "x":2.22117, "y":3.99358, "heading":2.80176, "vx":1.71488, "vy":-0.00801, "omega":-2.43503, "ax":6.00801, "ay":-0.06892, "alpha":-7.73745, "fx":[95.20499,102.30347,102.98659,108.28317], "fy":[53.59902,-37.45032,-37.00764,16.16953]}, - {"t":0.31631, "x":2.27296, "y":3.99332, "heading":2.73174, "vx":1.88764, "vy":-0.00999, "omega":-2.65753, "ax":6.02877, "ay":-0.05705, "alpha":-7.38097, "fx":[95.51767,103.82776,102.33561,108.50948], "fy":[52.73407,-31.96616,-38.38236,13.73267]}, - {"t":0.34506, "x":2.32973, "y":3.99301, "heading":2.65533, "vx":2.061, "vy":-0.01163, "omega":-2.86977, "ax":6.04927, "ay":-0.024, "alpha":-6.94321, "fx":[96.02514,105.24438,101.70978,108.60641], "fy":[51.23166,-24.67514,-39.30854,11.11889]}, - {"t":0.37382, "x":2.3915, "y":3.99267, "heading":2.57281, "vx":2.23495, "vy":-0.01232, "omega":-3.06942, "ax":6.05981, "ay":0.05198, "alpha":-6.35577, "fx":[96.76896,105.8877,101.29983,108.34583], "fy":[48.36824,-14.72603,-38.62406,8.5184]}, - {"t":0.40257, "x":2.45827, "y":3.99233, "heading":2.48454, "vx":2.4092, "vy":-0.01082, "omega":-3.25218, "ax":5.97728, "ay":0.349, "alpha":-4.45126, "fx":[97.63868,101.92349,101.82423,105.30079], "fy":[37.12883,2.87298,-24.20418,7.9478]}, - {"t":0.43133, "x":2.53002, "y":3.99217, "heading":2.39103, "vx":2.58107, "vy":-0.00079, "omega":-3.38017, "ax":-5.8948, "ay":0.35172, "alpha":5.93009, "fx":[-98.61187,-100.75725,-95.39884,-106.3074], "fy":[-36.47758,12.38529,44.89336,3.12958]}, - {"t":0.46008, "x":2.6018, "y":3.99229, "heading":2.29383, "vx":2.41157, "vy":0.00933, "omega":-3.20965, "ax":-6.04077, "ay":0.09728, "alpha":6.50924, "fx":[-99.06879,-106.73669,-96.50893,-108.69236], "fy":[-44.02034,-2.21354,49.27162,3.58119]}, - {"t":0.48884, "x":2.66865, "y":3.9926, "heading":2.20154, "vx":2.23787, "vy":0.01212, "omega":-3.02248, "ax":-6.05629, "ay":0.01124, "alpha":6.77632, "fx":[-99.84024,-107.17552,-96.03257,-109.01448], "fy":[-43.80499,-13.23082,51.41051,6.39026]}, - {"t":0.51759, "x":2.73049, "y":3.99295, "heading":2.11463, "vx":2.06372, "vy":0.01245, "omega":-2.82763, "ax":-6.04667, "ay":-0.03876, "alpha":7.09011, "fx":[-100.70352,-106.21331,-95.49954,-108.99184], "fy":[-42.45178,-22.41102,52.89271,9.33288]}, - {"t":0.54635, "x":2.78734, "y":3.99329, "heading":2.03332, "vx":1.88985, "vy":0.01133, "omega":-2.62375, "ax":-6.02828, "ay":-0.06618, "alpha":7.42669, "fx":[-101.56268,-104.7041,-95.07319,-108.81716], "fy":[-40.73178,-29.85453,53.92429,12.15908]}, - {"t":0.5751, "x":2.83919, "y":3.99359, "heading":1.95787, "vx":1.7165, "vy":0.00943, "omega":-2.4102, "ax":-6.00841, "ay":-0.07676, "alpha":7.74505, "fx":[-102.37586,-103.0786,-94.79421,-108.55647], "fy":[-38.88937,-35.70676,54.58124,14.79255]}, - {"t":0.60386, "x":2.88606, "y":3.99383, "heading":1.88857, "vx":1.54373, "vy":0.00722, "omega":-2.18749, "ax":-5.99076, "ay":-0.07534, "alpha":8.01744, "fx":[-103.12123,-101.56862,-94.66803,-108.24671], "fy":[-37.04316,-40.19716,54.91523,17.19913]}, - {"t":0.63261, "x":2.92797, "y":3.99401, "heading":1.82566, "vx":1.37147, "vy":0.00506, "omega":-1.95695, "ax":-5.97691, "ay":-0.06626, "alpha":8.23181, "fx":[-103.78748,-100.27857,-94.68218,-107.91416], "fy":[-35.2657,-43.57992,54.97586,19.36151]}, - {"t":0.66137, "x":2.96494, "y":3.99412, "heading":1.76939, "vx":1.1996, "vy":0.00315, "omega":-1.72024, "ax":-5.96715, "ay":-0.05306, "alpha":8.38792, "fx":[-104.36994,-99.23558,-94.81286,-107.57939], "fy":[-33.60675,-46.09163,54.81639,21.27163]}, - {"t":0.69012, "x":2.99697, "y":3.99419, "heading":1.71993, "vx":1.02801, "vy":0.00162, "omega":-1.47904, "ax":-5.96104, "ay":-0.03841, "alpha":8.49257, "fx":[-104.86829,-98.42585,-95.02938,-107.25885], "fy":[-32.10211,-47.93291,54.49413,22.92744]}, - {"t":0.71888, "x":3.02406, "y":3.99422, "heading":1.6774, "vx":0.8566, "vy":0.00052, "omega":-1.23484, "ax":-5.95787, "ay":-0.02415, "alpha":8.55587, "fx":[-105.28495,-97.81795,-95.29802,-106.96567], "fy":[-30.77782,-49.26485,54.06866,24.3308]}, - {"t":0.74763, "x":3.04623, "y":3.99423, "heading":1.64189, "vx":0.68529, "vy":-0.00017, "omega":-0.98882, "ax":-5.95682, "ay":-0.01147, "alpha":8.58868, "fx":[-105.62382,-97.37626,-95.58537,-106.71005], "fy":[-29.65269,-50.21224,53.59897,25.48588]}, - {"t":0.77639, "x":3.06348, "y":3.99422, "heading":1.61346, "vx":0.514, "vy":-0.0005, "omega":-0.74185, "ax":-5.95716, "ay":-0.00104, "alpha":8.6011, "fx":[-105.88936,-97.06792,-95.86108,-106.49975], "fy":[-28.73996,-50.86893,53.14014,26.39788]}, - {"t":0.80514, "x":3.07579, "y":3.9942, "heading":1.59212, "vx":0.3427, "vy":-0.00053, "omega":-0.49452, "ax":-5.95824, "ay":0.00677, "alpha":8.60151, "fx":[-106.08589,-96.86595,-96.09974,-106.34046], "fy":[-28.04864,-51.30311,52.74012,27.07203]}, - {"t":0.8339, "x":3.08318, "y":3.99419, "heading":1.5779, "vx":0.17137, "vy":-0.00034, "omega":-0.24719, "ax":-5.95962, "ay":0.01181, "alpha":8.59627, "fx":[-106.21711,-96.75041,-96.28212,-106.23612], "fy":[-27.5844,-51.56171,52.43691,27.5128]}, - {"t":0.86265, "x":3.08565, "y":3.99419, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/E_LEFT_PATH_6.traj b/src/main/deploy/choreo/E_LEFT_PATH_6.traj deleted file mode 100644 index 2d4d156d..00000000 --- a/src/main/deploy/choreo/E_LEFT_PATH_6.traj +++ /dev/null @@ -1,71 +0,0 @@ -{ - "name":"E_LEFT_PATH_6", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":2.9622931480407715, "y":3.9847822189331055, "heading":1.5707963267948966, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.849413275718689, "y":5.839582443237305, "heading":3.141592653589793, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"2.9622931480407715 m", "val":2.9622931480407715}, "y":{"exp":"3.9847822189331055 m", "val":3.9847822189331055}, "heading":{"exp":"1.5707963267948966 rad", "val":1.5707963267948966}, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.849413275718689 m", "val":1.849413275718689}, "y":{"exp":"5.839582443237305 m", "val":5.839582443237305}, "heading":{"exp":"3.141592653589793 rad", "val":3.141592653589793}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.1777], - "samples":[ - {"t":0.0, "x":2.96229, "y":3.98478, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.17652, "ay":5.36941, "alpha":5.38241, "fx":[-86.86283,-42.67676,-24.14536,-62.44186], "fy":[67.02416,100.99425,107.04727,90.26304]}, - {"t":0.03271, "x":2.96059, "y":3.98766, "heading":1.5708, "vx":-0.10392, "vy":0.17565, "omega":0.17608, "ax":-3.18135, "ay":5.37156, "alpha":5.32096, "fx":[-86.57463,-42.96599,-24.5117,-62.40326], "fy":[67.38061,100.85772,106.95548,90.28109]}, - {"t":0.06543, "x":2.95549, "y":3.99628, "heading":1.57656, "vx":-0.20799, "vy":0.35138, "omega":0.35015, "ax":-3.18608, "ay":5.37368, "alpha":5.26093, "fx":[-86.2707,-42.98788,-25.02162,-62.49676], "fy":[67.75132,100.83315,106.82786,90.20648]}, - {"t":0.09814, "x":2.94698, "y":4.01065, "heading":1.58801, "vx":-0.31222, "vy":0.52717, "omega":0.52226, "ax":-3.19093, "ay":5.3758, "alpha":5.19982, "fx":[-85.93756,-42.77495,-25.67985,-62.71462], "fy":[68.15226,100.90671,106.66083,90.04363]}, - {"t":0.13086, "x":2.93506, "y":4.03077, "heading":1.6051, "vx":-0.41661, "vy":0.70304, "omega":0.69236, "ax":-3.1962, "ay":5.37798, "alpha":5.13457, "fx":[-85.55623,-42.36824,-26.49458,-63.04696], "fy":[68.60543,101.05913,106.4491,89.7977]}, - {"t":0.16357, "x":2.91972, "y":4.05665, "heading":1.62775, "vx":-0.52117, "vy":0.87897, "omega":0.86034, "ax":-3.20228, "ay":5.38025, "alpha":5.06109, "fx":[-85.10066,-41.81971,-27.47797,-63.481], "fy":[69.14009,101.26579,106.18521,89.47525]}, - {"t":0.19628, "x":2.90096, "y":4.08828, "heading":1.65589, "vx":-0.62593, "vy":1.05498, "omega":1.0259, "ax":-3.2096, "ay":5.38274, "alpha":4.97353, "fx":[-84.53541,-41.19546,-28.64713,-63.99973], "fy":[69.79454,101.49661,105.85882,89.08539]}, - {"t":0.229, "x":2.87876, "y":4.12567, "heading":1.68945, "vx":-0.73093, "vy":1.23107, "omega":1.18861, "ax":-3.21872, "ay":5.38561, "alpha":4.86331, "fx":[-83.81205,-40.58031,-30.02575,-64.57985], "fy":[70.61852,101.71531,105.45551,88.64158]}, - {"t":0.26171, "x":2.85313, "y":4.16883, "heading":1.72834, "vx":-0.83622, "vy":1.40726, "omega":1.34771, "ax":-3.23026, "ay":5.38917, "alpha":4.71782, "fx":[-82.8634,-40.08447,-31.64727,-65.1882], "fy":[71.67658,101.87749,104.95466,88.16457]}, - {"t":0.29443, "x":2.82405, "y":4.21775, "heading":1.77243, "vx":-0.9419, "vy":1.58356, "omega":1.50204, "ax":-3.24497, "ay":5.39386, "alpha":4.51838, "fx":[-81.59416,-39.85399,-33.56087,-65.77522], "fy":[73.05275,101.92614,104.32554,87.6877]}, - {"t":0.32714, "x":2.7915, "y":4.27244, "heading":1.82156, "vx":-1.04806, "vy":1.76002, "omega":1.64986, "ax":-3.26372, "ay":5.40021, "alpha":4.23701, "fx":[-79.86472,-40.0891,-35.8439,-66.262], "fy":[74.85704,101.78139,103.51918,87.26678]}, - {"t":0.35985, "x":2.75546, "y":4.33291, "heading":1.87554, "vx":-1.15482, "vy":1.93668, "omega":1.78847, "ax":-3.28757, "ay":5.40871, "alpha":3.83022, "fx":[-77.46165,-41.07941,-38.62957,-66.51196], "fy":[77.23499,101.31688,102.44985,87.00063]}, - {"t":0.39257, "x":2.71593, "y":4.39916, "heading":1.93405, "vx":-1.26237, "vy":2.11362, "omega":1.91377, "ax":-3.318, "ay":5.4191, "alpha":3.22534, "fx":[-74.03964,-43.27755,-42.1759,-66.25993], "fy":[80.38161,100.30227,100.94665,87.0787]}, - {"t":0.42528, "x":2.67285, "y":4.4712, "heading":1.99665, "vx":-1.37092, "vy":2.2909, "omega":2.01928, "ax":-3.35728, "ay":5.42805, "alpha":2.28394, "fx":[-68.99557,-47.46504,-47.06648,-64.89813], "fy":[84.56081,98.24777,98.59949,87.91026]}, - {"t":0.458, "x":2.62621, "y":4.54905, "heading":2.06271, "vx":-1.48075, "vy":2.46847, "omega":2.094, "ax":-3.40807, "ay":5.41874, "alpha":0.67234, "fx":[-61.16417,-55.14745,-54.95086,-60.61886], "fy":[90.1176,93.91502,94.09775,90.55461]}, - {"t":0.49071, "x":2.57594, "y":4.6327, "heading":2.13121, "vx":-1.59224, "vy":2.64574, "omega":2.116, "ax":-3.44854, "ay":5.28498, "alpha":-2.90877, "fx":[-48.01544,-69.39022,-72.44955,-44.7792], "fy":[97.35036,83.47817,80.31087,98.44455]}, - {"t":0.52342, "x":2.52201, "y":4.72208, "heading":2.20044, "vx":-1.70506, "vy":2.81863, "omega":2.02084, "ax":-2.8284, "ay":3.94902, "alpha":-15.18696, "fx":[-29.38592,-88.93729,-105.01323,30.89557], "fy":[103.73245,60.92653,3.47736,100.55036]}, - {"t":0.55614, "x":2.46472, "y":4.81641, "heading":2.26655, "vx":-1.79758, "vy":2.94782, "omega":1.52401, "ax":-2.72674, "ay":3.70336, "alpha":-14.10606, "fx":[-31.21237,-86.3488,-93.52676,25.56353], "fy":[98.42802,56.23737,4.70088,92.60588]}, - {"t":0.58885, "x":2.40445, "y":4.91482, "heading":2.3164, "vx":-1.88679, "vy":3.06897, "omega":1.06255, "ax":2.73736, "ay":-4.08675, "alpha":12.90321, "fx":[31.39081,85.41852,93.47232,-24.03483], "fy":[-99.982,-60.01477,-20.80034,-97.2607]}, - {"t":0.62157, "x":2.34419, "y":5.01303, "heading":2.35116, "vx":-1.79724, "vy":2.93528, "omega":1.48466, "ax":3.0584, "ay":-4.26275, "alpha":12.7568, "fx":[36.09906,89.68852,101.86847,-19.56588], "fy":[-101.79742,-59.90881,-23.83233,-104.49419]}, - {"t":0.65428, "x":2.28703, "y":5.10678, "heading":2.39973, "vx":-1.69718, "vy":2.79583, "omega":1.90199, "ax":3.32997, "ay":-4.93712, "alpha":7.69709, "fx":[43.49878,84.80094,88.24086,10.02689], "fy":[-99.60732,-67.81948,-61.02627,-107.46305]}, - {"t":0.68699, "x":2.23329, "y":5.1956, "heading":2.46195, "vx":-1.58825, "vy":2.63431, "omega":2.15379, "ax":3.41082, "ay":-5.40596, "alpha":1.11173, "fx":[55.27548,63.91943,61.25035,51.62278], "fy":[-93.87472,-88.18124,-89.93214,-95.82713]}, - {"t":0.71971, "x":2.18316, "y":5.27889, "heading":2.53241, "vx":-1.47667, "vy":2.45746, "omega":2.19016, "ax":3.37237, "ay":-5.44278, "alpha":-1.44085, "fx":[61.03333,48.67342,54.46595,65.27942], "fy":[-90.42854,-97.6888,-94.67352,-87.52971]}, - {"t":0.75242, "x":2.13666, "y":5.35637, "heading":2.60406, "vx":-1.36634, "vy":2.27941, "omega":2.14302, "ax":3.3321, "ay":-5.42784, "alpha":-2.83597, "fx":[63.38535,38.51652,52.67456,72.13552], "fy":[-88.92819,-102.29001,-95.89111,-82.19443]}, - {"t":0.78514, "x":2.09374, "y":5.42803, "heading":2.67417, "vx":-1.25734, "vy":2.10184, "omega":2.05025, "ax":3.30188, "ay":-5.40597, "alpha":-3.67939, "fx":[63.6911,31.83405,52.66895,76.46214], "fy":[-88.80565,-104.6775,-96.01107,-78.32191]}, - {"t":0.81785, "x":2.05438, "y":5.4939, "heading":2.74124, "vx":-1.14932, "vy":1.92499, "omega":1.92988, "ax":3.27878, "ay":-5.38726, "alpha":-4.22056, "fx":[62.67214,27.43657,53.43199,79.54363], "fy":[-89.60079,-105.99631,-95.66305,-75.28259]}, - {"t":0.85056, "x":2.01853, "y":5.55399, "heading":2.80437, "vx":-1.04206, "vy":1.74875, "omega":1.79181, "ax":3.25919, "ay":-5.37338, "alpha":-4.591, "fx":[60.76916,24.55309,54.53884,81.89036], "fy":[-90.96019,-106.76059,-95.08805,-72.78984]}, - {"t":0.88328, "x":1.98619, "y":5.60832, "heading":2.86299, "vx":-0.93544, "vy":1.57297, "omega":1.64162, "ax":3.2409, "ay":-5.36357, "alpha":-4.86622, "fx":[58.29404,22.68606,55.78017,83.7469], "fy":[-92.61358,-107.21777,-94.40318,-70.69694]}, - {"t":0.91599, "x":1.95732, "y":5.65691, "heading":2.9167, "vx":-0.82941, "vy":1.3975, "omega":1.48243, "ax":3.22299, "ay":-5.3565, "alpha":-5.08977, "fx":[55.49263,21.50669,57.04119,85.24776], "fy":[-94.35904,-107.49532,-93.67571,-68.92016]}, - {"t":0.94871, "x":1.93191, "y":5.69976, "heading":2.96519, "vx":-0.72398, "vy":1.22227, "omega":1.31592, "ax":3.20535, "ay":-5.35096, "alpha":-5.28532, "fx":[52.56832,20.79099,58.25395,86.47529], "fy":[-96.05354,-107.66352,-92.9494,-67.40656]}, - {"t":0.98142, "x":1.90994, "y":5.73688, "heading":3.00824, "vx":-0.61912, "vy":1.04722, "omega":1.14301, "ax":3.18834, "ay":-5.3461, "alpha":-5.46392, "fx":[49.6891,20.38162,59.37581,87.48449], "fy":[-97.60426,-107.76389,-92.25547,-66.11919]}, - {"t":1.01413, "x":1.89139, "y":5.76828, "heading":3.04563, "vx":-0.51481, "vy":0.87233, "omega":0.96427, "ax":3.17242, "ay":-5.34149, "alpha":-5.62903, "fx":[46.98934,20.16491,60.37869,88.31472], "fy":[-98.95876,-107.82272,-91.61773,-65.02987]}, - {"t":1.04685, "x":1.87625, "y":5.79396, "heading":3.07718, "vx":-0.41103, "vy":0.69759, "omega":0.78012, "ax":3.15801, "ay":-5.33699, "alpha":-5.78, "fx":[44.57151,20.05669,61.2433,88.99568], "fy":[-100.09431,-107.85785,-91.05508,-64.11561]}, - {"t":1.07956, "x":1.86449, "y":5.81393, "heading":3.1027, "vx":-0.30772, "vy":0.52299, "omega":0.59103, "ax":3.14541, "ay":-5.33268, "alpha":-5.91441, "fx":[42.50976,19.99353,61.95594,89.55053], "fy":[-101.00764,-107.88207,-90.58285,-63.3569]}, - {"t":1.11228, "x":1.85611, "y":5.82818, "heading":3.12203, "vx":-0.20482, "vy":0.34854, "omega":0.39755, "ax":3.13478, "ay":-5.32874, "alpha":-6.02947, "fx":[40.85526,19.92713,62.50658,89.99756], "fy":[-101.70608,-107.90489,-90.21341,-62.7371]}, - {"t":1.14499, "x":1.85109, "y":5.83673, "heading":3.13504, "vx":-0.10227, "vy":0.17421, "omega":0.2003, "ax":3.12618, "ay":-5.32539, "alpha":-6.1228, "fx":[39.64248,19.82068,62.88764,90.35102], "fy":[-102.20068,-107.93344,-89.95664,-62.24244]}, - {"t":1.1777, "x":1.84941, "y":5.83958, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/E_LEFT_PATH_7.traj b/src/main/deploy/choreo/E_LEFT_PATH_7.traj deleted file mode 100644 index 893f11f3..00000000 --- a/src/main/deploy/choreo/E_LEFT_PATH_7.traj +++ /dev/null @@ -1,66 +0,0 @@ -{ - "name":"E_LEFT_PATH_7", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":1.7875865697860718, "y":5.860191345214844, "heading":3.141592653589793, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":3.7660398483276367, "y":5.262533664703369, "heading":-2.5959373241304182, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"1.7875865697860718 m", "val":1.7875865697860718}, "y":{"exp":"5.860191345214844 m", "val":5.860191345214844}, "heading":{"exp":"3.141592653589793 rad", "val":3.141592653589793}, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"3.7660398483276367 m", "val":3.7660398483276367}, "y":{"exp":"5.262533664703369 m", "val":5.262533664703369}, "heading":{"exp":"-2.5959373241304182 rad", "val":-2.5959373241304182}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.13498], - "samples":[ - {"t":0.0, "x":1.78759, "y":5.86019, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.15533, "ay":-1.85931, "alpha":1.72515, "fx":[103.37094,107.60487,106.75398,101.07183], "fy":[-36.86708,-21.56181,-25.35323,-42.72345]}, - {"t":0.03661, "x":1.79171, "y":5.85895, "heading":3.14159, "vx":0.22536, "vy":-0.06807, "omega":0.06316, "ax":6.15487, "ay":-1.85917, "alpha":1.72335, "fx":[103.36506,107.59465,106.74267,101.06819], "fy":[-36.85955,-21.57011,-25.35824,-42.70809]}, - {"t":0.07322, "x":1.80409, "y":5.85521, "heading":-3.13928, "vx":0.45071, "vy":-0.13614, "omega":0.12626, "ax":6.15435, "ay":-1.85901, "alpha":1.72114, "fx":[103.3663,107.58579,106.72323,101.05962], "fy":[-36.82837,-21.56488,-25.39081,-42.70082]}, - {"t":0.10984, "x":1.82471, "y":5.84898, "heading":-3.13466, "vx":0.67603, "vy":-0.20421, "omega":0.18927, "ax":6.15374, "ay":-1.85882, "alpha":1.71845, "fx":[103.37439,107.57784,106.69519,101.04608], "fy":[-36.77332,-21.54667,-25.4511,-42.70082]}, - {"t":0.14645, "x":1.85359, "y":5.84025, "heading":-3.12773, "vx":0.90133, "vy":-0.27226, "omega":0.25219, "ax":6.15302, "ay":-1.85859, "alpha":1.71518, "fx":[103.38898,107.57018,106.65789,101.02758], "fy":[-36.69403,-21.5163,-25.53942,-42.70683]}, - {"t":0.18306, "x":1.89071, "y":5.82904, "heading":-3.11849, "vx":1.12661, "vy":-0.34031, "omega":0.31499, "ax":6.15216, "ay":-1.85832, "alpha":1.71121, "fx":[103.40956,107.56191,106.6104,101.00414], "fy":[-36.58998,-21.47491,-25.65619,-42.71712]}, - {"t":0.21967, "x":1.93609, "y":5.81534, "heading":-3.10696, "vx":1.35185, "vy":-0.40835, "omega":0.37764, "ax":6.15111, "ay":-1.85799, "alpha":1.70637, "fx":[103.43539,107.55178,106.55139,100.97573], "fy":[-36.46046,-21.4241,-25.80196,-42.72922]}, - {"t":0.25629, "x":1.9897, "y":5.79914, "heading":-3.09314, "vx":1.57706, "vy":-0.47637, "omega":0.44011, "ax":6.14979, "ay":-1.85758, "alpha":1.70038, "fx":[103.46538,107.53792,106.47893,100.94223], "fy":[-36.30447,-21.36607,-25.97741,-42.73975]}, - {"t":0.2929, "x":2.05156, "y":5.78045, "heading":-3.07702, "vx":1.80222, "vy":-0.54438, "omega":0.50237, "ax":6.14808, "ay":-1.85705, "alpha":1.69285, "fx":[103.49776,107.51752,106.39011,100.90321], "fy":[-36.12055,-21.30394,-26.18333,-42.74385]}, - {"t":0.32951, "x":2.12167, "y":5.75928, "heading":-3.05863, "vx":2.02732, "vy":-0.61237, "omega":0.56434, "ax":6.1458, "ay":-1.85634, "alpha":1.68314, "fx":[103.52959,107.48597,106.28024,100.85768], "fy":[-35.90648,-21.24233,-26.42058,-42.73418]}, - {"t":0.36612, "x":2.20001, "y":5.73561, "heading":-3.03797, "vx":2.25233, "vy":-0.68034, "omega":0.62597, "ax":6.1426, "ay":-1.85535, "alpha":1.67017, "fx":[103.55551,107.4352,106.14118,100.80324], "fy":[-35.65854,-21.18852,-26.69012,-42.69886]}, - {"t":0.40274, "x":2.28659, "y":5.70946, "heading":-3.01505, "vx":2.47722, "vy":-0.74827, "omega":0.68712, "ax":6.13775, "ay":-1.85386, "alpha":1.65185, "fx":[103.56478,107.34947,105.95707,100.73414], "fy":[-35.36979,-21.15516,-26.99287,-42.61644]}, - {"t":0.43935, "x":2.3814, "y":5.68082, "heading":-2.98989, "vx":2.70194, "vy":-0.81614, "omega":0.7476, "ax":6.12961, "ay":-1.85134, "alpha":1.62375, "fx":[103.53211,107.19279,105.69181,100.63474], "fy":[-35.02486,-21.16736,-27.32918,-42.44183]}, - {"t":0.47596, "x":2.48444, "y":5.6497, "heading":-2.96252, "vx":2.92636, "vy":-0.88392, "omega":0.80704, "ax":6.11314, "ay":-1.84626, "alpha":1.57411, "fx":[103.38071,106.85967,105.23945,100.45134], "fy":[-34.58025,-21.28615,-27.69545,-42.05526]}, - {"t":0.51257, "x":2.59567, "y":5.6161, "heading":-2.93297, "vx":3.15018, "vy":-0.95152, "omega":0.86468, "ax":6.06291, "ay":-1.83075, "alpha":1.45752, "fx":[102.71817,105.84005,104.08562,99.86994], "fy":[-33.83679,-21.71641,-28.04427,-40.96462]}, - {"t":0.54919, "x":2.71507, "y":5.58004, "heading":-2.90132, "vx":3.37215, "vy":-1.01855, "omega":0.91804, "ax":0.00143, "ay":-0.00403, "alpha":-0.15556, "fx":[-0.46399,-0.2718,0.51263,0.32044], "fy":[0.22759,-0.55684,-0.36465,0.41979]}, - {"t":0.5858, "x":2.83854, "y":5.54274, "heading":-2.8677, "vx":3.37221, "vy":-1.01869, "omega":0.91234, "ax":-6.06287, "ay":1.83063, "alpha":-1.46057, "fx":[-102.90929,-105.88169,-103.89226,-99.82735], "fy":[33.25969,21.46017,28.7346,41.09985]}, - {"t":0.62241, "x":2.95794, "y":5.50667, "heading":-2.8343, "vx":3.15023, "vy":-0.95167, "omega":0.85887, "ax":-6.11313, "ay":1.84627, "alpha":-1.57315, "fx":[-103.78728,-106.94747,-104.82612,-100.36967], "fy":[33.34823,20.78254,29.20402,42.28309]}, - {"t":0.65902, "x":3.06918, "y":5.47307, "heading":-2.80286, "vx":2.92641, "vy":-0.88407, "omega":0.80127, "ax":-6.12963, "ay":1.85143, "alpha":-1.61989, "fx":[-104.14349,-107.32587,-105.06897,-100.51472], "fy":[33.17067,20.42267,29.61727,42.75849]}, - {"t":0.69563, "x":3.17221, "y":5.44194, "heading":-2.77352, "vx":2.70199, "vy":-0.81629, "omega":0.74196, "ax":-6.1378, "ay":1.854, "alpha":-1.64553, "fx":[-104.3668,-107.52458,-105.13843,-100.57922], "fy":[32.93568,20.1873,30.00802,43.01331]}, - {"t":0.73225, "x":3.26702, "y":5.4133, "heading":-2.74635, "vx":2.47727, "vy":-0.74841, "omega":0.68172, "ax":-6.14267, "ay":1.85555, "alpha":-1.66173, "fx":[-104.53286,-107.64866,-105.14163,-100.61725], "fy":[32.69002,20.01779,30.37498,43.16695]}, - {"t":0.76886, "x":3.35361, "y":5.38714, "heading":-2.7214, "vx":2.25238, "vy":-0.68047, "omega":0.62088, "ax":-6.1459, "ay":1.85659, "alpha":-1.67294, "fx":[-104.6665,-107.73397,-105.11522,-100.64445], "fy":[32.45051,19.88964,30.71567,43.26459]}, - {"t":0.80547, "x":3.43195, "y":5.36347, "heading":-2.69866, "vx":2.02736, "vy":-0.6125, "omega":0.55963, "ax":-6.1482, "ay":1.85734, "alpha":-1.68119, "fx":[-104.77826,-107.79625,-105.07536,-100.66652], "fy":[32.22479,19.79027,31.0283,43.32787]}, - {"t":0.84208, "x":3.50206, "y":5.34229, "heading":-2.67817, "vx":1.80226, "vy":-0.5445, "omega":0.49808, "ax":-6.14991, "ay":1.8579, "alpha":-1.68755, "fx":[-104.87342,-107.84357,-105.03035,-100.68575], "fy":[32.01693,19.71218,31.31163,43.36888]}, - {"t":0.8787, "x":3.56392, "y":5.3236, "heading":-2.65994, "vx":1.5771, "vy":-0.47648, "omega":0.43629, "ax":-6.15124, "ay":1.85834, "alpha":-1.69263, "fx":[-104.95495,-107.88055,-104.98497,-100.70307], "fy":[31.82927,19.65038,31.56484,43.39514]}, - {"t":0.91531, "x":3.61754, "y":5.3074, "heading":-2.64396, "vx":1.35189, "vy":-0.40844, "omega":0.37432, "ax":-6.1523, "ay":1.8587, "alpha":-1.6968, "fx":[-105.02464,-107.91007,-104.94218,-100.71875], "fy":[31.6633,19.60131,31.7874,43.41174]}, - {"t":0.95192, "x":3.66291, "y":5.29369, "heading":-2.63026, "vx":1.12664, "vy":-0.34039, "omega":0.3122, "ax":-6.15317, "ay":1.85899, "alpha":-1.70028, "fx":[-105.08368,-107.93404,-104.90394,-100.73283], "fy":[31.51997,19.56228,31.97896,43.42231]}, - {"t":0.98853, "x":3.70003, "y":5.28248, "heading":-2.61883, "vx":0.90135, "vy":-0.27232, "omega":0.24994, "ax":-6.15389, "ay":1.85923, "alpha":-1.70324, "fx":[-105.13287,-107.95377,-104.87158,-100.74521], "fy":[31.39994,19.5312,32.13932,43.42951]}, - {"t":1.02515, "x":3.72891, "y":5.27375, "heading":-2.60968, "vx":0.67605, "vy":-0.20425, "omega":0.18759, "ax":-6.15449, "ay":1.85944, "alpha":-1.70577, "fx":[-105.17279,-107.97021,-104.84606,-100.75574], "fy":[31.30367,19.50646,32.26833,43.43538]}, - {"t":1.06176, "x":3.74954, "y":5.26752, "heading":-2.60281, "vx":0.45072, "vy":-0.13617, "omega":0.12513, "ax":-6.15502, "ay":1.85961, "alpha":-1.70795, "fx":[-105.20385,-107.98406,-104.82807,-100.76428], "fy":[31.2315,19.48677,32.36593,43.44143]}, - {"t":1.09837, "x":3.76191, "y":5.26378, "heading":-2.59823, "vx":0.22537, "vy":-0.06809, "omega":0.0626, "ax":-6.15547, "ay":1.85976, "alpha":-1.70983, "fx":[-105.22636,-107.99582,-104.81811,-100.77072], "fy":[31.18367,19.47118,32.43206,43.44883]}, - {"t":1.13498, "x":3.76604, "y":5.26253, "heading":-2.59594, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_1.traj b/src/main/deploy/choreo/E_RIGHT_PATH_1.traj new file mode 100644 index 00000000..4b5086f5 --- /dev/null +++ b/src/main/deploy/choreo/E_RIGHT_PATH_1.traj @@ -0,0 +1,79 @@ +{ + "name":"E_RIGHT_PATH_1", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.152472496032715, "y":0.4605357348918915, "heading":3.141592653589793, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":3.778014659881592, "y":2.6174252033233643, "heading":2.5967288478948136, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":1, "to":1, "data":{"type":"MaxVelocity", "props":{"max":3.0}}, "enabled":true}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"7.152472496032715 m", "val":7.152472496032715}, "y":{"exp":"0.4605357348918915 m", "val":0.4605357348918915}, "heading":{"exp":"pi rad", "val":3.141592653589793}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"3.778014659881592 m", "val":3.778014659881592}, "y":{"exp":"2.6174252033233643 m", "val":2.6174252033233643}, "heading":{"exp":"2.5967288478948136 rad", "val":2.5967288478948136}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":1, "to":1, "data":{"type":"MaxVelocity", "props":{"max":{"exp":"3 m / s", "val":3.0}}}, "enabled":true}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.62748], + "samples":[ + {"t":0.0, "x":7.15247, "y":0.46054, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.41378, "ay":3.46163, "alpha":-1.90657, "fx":[-90.99812,-98.92725,-94.25689,-84.16514], "fy":[61.37561,47.53023,56.18754,70.43177]}, + {"t":0.04069, "x":7.14799, "y":0.4634, "heading":3.14159, "vx":-0.22027, "vy":0.14084, "omega":-0.07757, "ax":-5.41425, "ay":3.46191, "alpha":-1.86883, "fx":[-91.01891,-98.80925,-94.20948,-84.34176], "fy":[61.3313,47.75661,56.24948,70.20712]}, + {"t":0.08137, "x":7.13455, "y":0.472, "heading":3.13844, "vx":-0.44056, "vy":0.2817, "omega":-0.15361, "ax":-5.41477, "ay":3.46222, "alpha":-1.8253, "fx":[-91.02228,-98.66598,-94.17886,-84.54786], "fy":[61.31059,48.03075,56.2806,69.94356]}, + {"t":0.12206, "x":7.11214, "y":0.48632, "heading":3.13219, "vx":-0.66087, "vy":0.42257, "omega":-0.22788, "ax":-5.41536, "ay":3.46256, "alpha":-1.77441, "fx":[-91.01117,-98.49267,-94.16051,-84.79037], "fy":[61.30857,48.36058,56.28791,69.6314]}, + {"t":0.16275, "x":7.08077, "y":0.50638, "heading":3.12291, "vx":-0.88121, "vy":0.56345, "omega":-0.30007, "ax":-5.41601, "ay":3.46293, "alpha":-1.71397, "fx":[-90.9895,-98.28255,-94.14838,-85.07876], "fy":[61.31858,48.75726,56.28066,69.25721]}, + {"t":0.20344, "x":7.04043, "y":0.53217, "heading":3.11071, "vx":-1.10157, "vy":0.70434, "omega":-0.36981, "ax":-5.41674, "ay":3.46334, "alpha":-1.64092, "fx":[-90.96271,-98.02586,-94.13432,-85.42612], "fy":[61.33135,49.2367,56.2713,68.80209]}, + {"t":0.24412, "x":6.99113, "y":0.5637, "heading":3.09566, "vx":-1.32196, "vy":0.84526, "omega":-0.43657, "ax":-5.41756, "ay":3.46378, "alpha":-1.55079, "fx":[-90.93858,-97.70812,-94.10696,-85.85087], "fy":[61.33359,49.8221,56.27706,68.23884]}, + {"t":0.28481, "x":6.93286, "y":0.60096, "heading":3.0779, "vx":-1.54238, "vy":0.98619, "omega":-0.49967, "ax":-5.41845, "ay":3.46425, "alpha":-1.43677, "fx":[-90.92878,-97.30686,-94.04998,-86.37978], "fy":[61.30526,50.54867,56.32261,67.52673]}, + {"t":0.3255, "x":6.86562, "y":0.64395, "heading":3.05757, "vx":-1.76284, "vy":1.12714, "omega":-0.55813, "ax":-5.41939, "ay":3.46469, "alpha":-1.28802, "fx":[-90.95179,-96.78532,-93.93868,-87.05336], "fy":[61.21442,51.47259,56.44483,66.60186]}, + {"t":0.36618, "x":6.78941, "y":0.69268, "heading":3.03486, "vx":-1.98334, "vy":1.26811, "omega":-0.61053, "ax":-5.42024, "ay":3.46501, "alpha":-1.08613, "fx":[-91.03889,-96.07859,-93.73331,-87.93643], "fy":[61.0062,52.68973,56.70202,65.35727]}, + {"t":0.40687, "x":6.70423, "y":0.74714, "heading":3.01002, "vx":-2.20388, "vy":1.40909, "omega":-0.65472, "ax":-5.42062, "ay":3.46488, "alpha":-0.7971, "fx":[-91.2482,-95.06016,-93.36444,-89.14013], "fy":[60.57629,54.37891,57.19317,63.59828]}, + {"t":0.44756, "x":6.61007, "y":0.80734, "heading":2.98338, "vx":-2.42443, "vy":1.55006, "omega":-0.68716, "ax":-5.41923, "ay":3.46337, "alpha":-0.35028, "fx":[-91.70263,-93.44621,-92.69649,-90.8726], "fy":[59.69568,56.91673,58.10359,60.92778]}, + {"t":0.48824, "x":6.50694, "y":0.87327, "heading":2.95542, "vx":-2.64492, "vy":1.69098, "omega":-0.70141, "ax":-5.41096, "ay":3.45697, "alpha":0.42998, "fx":[-92.71832,-90.44776,-91.41999,-93.56919], "fy":[57.73597,61.24946,59.83017,56.3927]}, + {"t":0.52893, "x":6.39485, "y":0.94494, "heading":2.92688, "vx":-2.86508, "vy":1.83163, "omega":-0.68391, "ax":-5.36728, "ay":3.42571, "alpha":2.143, "fx":[-95.42833,-82.8717,-88.63603,-98.24726], "fy":[52.10081,70.52095,63.41159,47.04811]}, + {"t":0.56962, "x":6.27383, "y":1.0223, "heading":2.89906, "vx":-3.08345, "vy":1.97101, "omega":-0.59672, "ax":-4.90263, "ay":2.92977, "alpha":9.39606, "fx":[-105.06196,-41.79507,-80.38887,-106.32374], "fy":[8.94067,98.66804,72.50689,19.22275]}, + {"t":0.61031, "x":6.14432, "y":1.10492, "heading":2.87478, "vx":-3.28293, "vy":2.09022, "omega":-0.21442, "ax":-1.51387, "ay":1.13808, "alpha":5.22755, "fx":[-17.89503,-8.72446,-33.70878,-42.6734], "fy":[2.04929,31.37038,34.80901,9.20467]}, + {"t":0.65099, "x":6.00949, "y":1.1909, "heading":2.86605, "vx":-3.34452, "vy":2.13652, "omega":-0.00173, "ax":0.022, "ay":0.03655, "alpha":0.00251, "fx":[0.37871,0.38225,0.36972,0.36618], "fy":[0.61372,0.62624,0.62979,0.61726]}, + {"t":0.69168, "x":5.87343, "y":1.27786, "heading":2.86598, "vx":-3.34363, "vy":2.13801, "omega":-0.00163, "ax":0.00578, "ay":0.00904, "alpha":0.0, "fx":[0.09829,0.09829,0.09828,0.09828], "fy":[0.1537,0.15371,0.15371,0.1537]}, + {"t":0.73237, "x":5.7374, "y":1.36486, "heading":2.86592, "vx":-3.34339, "vy":2.13838, "omega":-0.00163, "ax":0.00144, "ay":0.00225, "alpha":0.0, "fx":[0.02443,0.02443,0.02443,0.02443], "fy":[0.03819,0.03819,0.03819,0.03819]}, + {"t":0.77305, "x":5.60136, "y":1.45186, "heading":2.86585, "vx":-3.34333, "vy":2.13847, "omega":-0.00163, "ax":0.00029, "ay":0.00045, "alpha":0.0, "fx":[0.00489,0.00489,0.00489,0.00489], "fy":[0.00764,0.00764,0.00764,0.00764]}, + {"t":0.81374, "x":5.46533, "y":1.53887, "heading":2.86578, "vx":-3.34332, "vy":2.13849, "omega":-0.00163, "ax":-0.00022, "ay":-0.00035, "alpha":0.0, "fx":[-0.00378,-0.00378,-0.00378,-0.00378], "fy":[-0.0059,-0.0059,-0.00591,-0.0059]}, + {"t":0.85443, "x":5.3293, "y":1.62588, "heading":2.86572, "vx":-3.34333, "vy":2.13847, "omega":-0.00163, "ax":-0.00123, "ay":-0.00192, "alpha":0.0, "fx":[-0.02084,-0.02084,-0.02084,-0.02084], "fy":[-0.03259,-0.03259,-0.03259,-0.03259]}, + {"t":0.89512, "x":5.19327, "y":1.71289, "heading":2.86565, "vx":-3.34338, "vy":2.13839, "omega":-0.00163, "ax":-0.00495, "ay":-0.00775, "alpha":0.0, "fx":[-0.08427,-0.08427,-0.08426,-0.08426], "fy":[-0.13178,-0.13178,-0.13178,-0.13178]}, + {"t":0.9358, "x":5.05724, "y":1.79989, "heading":2.86558, "vx":-3.34358, "vy":2.13808, "omega":-0.00163, "ax":-0.01877, "ay":-0.03141, "alpha":-0.00242, "fx":[-0.32353,-0.32696,-0.31487,-0.31145], "fy":[-0.52658,-0.53866,-0.54208,-0.53]}, + {"t":0.97649, "x":4.92118, "y":1.88685, "heading":2.86552, "vx":-3.34435, "vy":2.1368, "omega":-0.00173, "ax":1.48133, "ay":-1.09441, "alpha":-5.10683, "fx":[17.61105,8.51821,32.90636,41.75224], "fy":[-1.6085,-30.09404,-33.87793,-8.88196]}, + {"t":1.01718, "x":4.78633, "y":1.97289, "heading":2.86545, "vx":-3.28407, "vy":2.09227, "omega":-0.20951, "ax":4.91954, "ay":-2.97256, "alpha":-9.14076, "fx":[105.20374,43.77661,79.81807,105.92133], "fy":[-9.99972,-97.75747,-73.11369,-21.37854]}, + {"t":1.05786, "x":4.65679, "y":2.05555, "heading":2.85692, "vx":-3.08391, "vy":1.97133, "omega":-0.58142, "ax":5.3694, "ay":-3.42683, "alpha":-2.07244, "fx":[95.78878,83.46596,88.24325,97.8298], "fy":[-51.46891,-69.80932,-63.95104,-47.92813]}, + {"t":1.09855, "x":4.53576, "y":2.13293, "heading":2.83327, "vx":-2.86545, "vy":1.8319, "omega":-0.66574, "ax":5.41121, "ay":-3.45686, "alpha":-0.41756, "fx":[92.88177,90.58729,91.26157,93.44209], "fy":[-57.47824,-61.04227,-60.07158,-56.6088]}, + {"t":1.13924, "x":4.42365, "y":2.2046, "heading":2.80618, "vx":-2.64528, "vy":1.69125, "omega":-0.68273, "ax":5.41942, "ay":-3.46329, "alpha":0.33496, "fx":[91.51657,93.29188,92.88539,91.03708], "fy":[-59.97973,-57.17334,-57.805,-60.68043]}, + {"t":1.17992, "x":4.32051, "y":2.27054, "heading":2.7784, "vx":-2.42478, "vy":1.55034, "omega":-0.6691, "ax":5.421, "ay":-3.46497, "alpha":0.76718, "fx":[90.66316,94.65385,93.94509,89.57654], "fy":[-61.44521,-55.09035,-56.24089,-62.97639]}, + {"t":1.22061, "x":4.22634, "y":2.33075, "heading":2.75118, "vx":-2.20422, "vy":1.40936, "omega":-0.63789, "ax":5.42081, "ay":-3.46526, "alpha":1.04848, "fx":[90.04423,95.44129,94.71517,88.62472], "fy":[-62.46056,-53.84498,-55.05479,-64.41225]}, + {"t":1.2613, "x":4.14114, "y":2.38523, "heading":2.72523, "vx":-1.98366, "vy":1.26837, "omega":-0.59523, "ax":5.42009, "ay":-3.46509, "alpha":1.24653, "fx":[89.55678,95.93374,95.31173,87.97443], "fy":[-63.23275,-53.05381,-54.10406,-65.36985]}, + {"t":1.30199, "x":4.06492, "y":2.43397, "heading":2.70101, "vx":-1.76313, "vy":1.12738, "omega":-0.54451, "ax":5.41925, "ay":-3.46475, "alpha":1.39367, "fx":[89.15461,96.25733,95.79228,87.51503], "fy":[-63.85257,-52.53166,-53.31651,-66.037]}, + {"t":1.34267, "x":3.99767, "y":2.47697, "heading":2.67885, "vx":-1.54264, "vy":0.98641, "omega":-0.48781, "ax":5.41841, "ay":-3.46438, "alpha":1.50737, "fx":[88.81421,96.47763,96.18878,87.18176], "fy":[-64.36587,-52.1775,-52.65154,-66.51748]}, + {"t":1.38336, "x":3.93938, "y":2.51424, "heading":2.65901, "vx":-1.32218, "vy":0.84546, "omega":-0.42647, "ax":5.41763, "ay":-3.46401, "alpha":1.59787, "fx":[88.52247,96.63234,96.52056,86.93383], "fy":[-64.7982,-51.93111,-52.08439,-66.87386]}, + {"t":1.42405, "x":3.89007, "y":2.54577, "heading":2.64165, "vx":-1.10175, "vy":0.70452, "omega":-0.36146, "ax":5.41691, "ay":-3.46367, "alpha":1.6716, "fx":[88.27157,96.74489,96.8002,86.74399], "fy":[-65.16499,-51.75406,-51.59884,-67.14654]}, + {"t":1.46473, "x":3.84973, "y":2.57157, "heading":2.62695, "vx":-0.88136, "vy":0.56359, "omega":-0.29345, "ax":5.41627, "ay":-3.46336, "alpha":1.73281, "fx":[88.05657,96.83069,97.03631,86.59321], "fy":[-65.47605,-51.6205,-51.1837,-67.36302]}, + {"t":1.50542, "x":3.81835, "y":2.59163, "heading":2.61501, "vx":-0.66098, "vy":0.42268, "omega":-0.22295, "ax":5.41569, "ay":-3.46308, "alpha":1.78442, "fx":[87.87422,96.90036,97.23503,86.46767], "fy":[-65.73797,-51.51235,-50.83092,-67.54282]}, + {"t":1.54611, "x":3.79594, "y":2.60596, "heading":2.60594, "vx":-0.44064, "vy":0.28177, "omega":-0.15034, "ax":5.41517, "ay":-3.46282, "alpha":1.82851, "fx":[87.72233,96.96151,97.40087,86.35707], "fy":[-65.95528,-51.4165,-50.53457,-67.70023]}, + {"t":1.58679, "x":3.7825, "y":2.61456, "heading":2.59982, "vx":-0.22031, "vy":0.14088, "omega":-0.07595, "ax":5.4147, "ay":-3.46259, "alpha":1.86661, "fx":[87.59938,97.01969,97.53717,86.2536], "fy":[-66.13118,-51.32324,-50.29023,-67.84595]}, + {"t":1.62748, "x":3.77801, "y":2.61743, "heading":2.59673, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_1_BACK.traj b/src/main/deploy/choreo/E_RIGHT_PATH_1_BACK.traj new file mode 100644 index 00000000..3699ba1d --- /dev/null +++ b/src/main/deploy/choreo/E_RIGHT_PATH_1_BACK.traj @@ -0,0 +1,132 @@ +{ + "name":"E_RIGHT_PATH_1_BACK", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.152472496032715, "y":0.4605357348918915, "heading":3.141592653589793, "intervals":53, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.838493585586548, "y":1.8093056678771973, "heading":0.0, "intervals":20, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":2.3785881996154785, "y":3.3401336669921875, "heading":0.0, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":2.937044858932495, "y":3.872309923171997, "heading":1.5707963267948966, "intervals":34, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"7.152472496032715 m", "val":7.152472496032715}, "y":{"exp":"0.4605357348918915 m", "val":0.4605357348918915}, "heading":{"exp":"pi rad", "val":3.141592653589793}, "intervals":53, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.838493585586548 m", "val":2.838493585586548}, "y":{"exp":"1.8093056678771973 m", "val":1.8093056678771973}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":20, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"2.3785881996154785 m", "val":2.3785881996154785}, "y":{"exp":"3.3401336669921875 m", "val":3.3401336669921875}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"2.937044858932495 m", "val":2.937044858932495}, "y":{"exp":"3.872309923171997 m", "val":3.872309923171997}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":34, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.47444,2.01312,2.55519], + "samples":[ + {"t":0.0, "x":7.15247, "y":0.46054, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.30985, "ay":1.13451, "alpha":-2.36127, "fx":[-106.15131,-109.53492,-109.38886,-104.24005], "fy":[27.85125,6.71386,8.39245,34.23341]}, + {"t":0.03429, "x":7.14876, "y":0.4612, "heading":3.14159, "vx":-0.21636, "vy":0.0389, "omega":-0.08097, "ax":-6.31061, "ay":1.13479, "alpha":-2.3233, "fx":[-106.17408,-109.51598,-109.36459,-104.31184], "fy":[27.73526,6.89733,8.59089,33.98641]}, + {"t":0.06858, "x":7.13763, "y":0.4632, "heading":3.13882, "vx":-0.43275, "vy":0.07781, "omega":-0.16063, "ax":-6.31143, "ay":1.1351, "alpha":-2.28075, "fx":[-106.19086,-109.4924,-109.34011,-104.39879], "fy":[27.6378,7.13249,8.7742,33.68674]}, + {"t":0.10287, "x":7.11909, "y":0.46654, "heading":3.13331, "vx":-0.64916, "vy":0.11674, "omega":-0.23884, "ax":-6.31232, "ay":1.13546, "alpha":-2.23259, "fx":[-106.20301,-109.46343,-109.31461,-104.50191], "fy":[27.55293,7.42251,8.9508,33.32898]}, + {"t":0.13716, "x":7.09311, "y":0.47121, "heading":3.12512, "vx":-0.86561, "vy":0.15567, "omega":-0.31539, "ax":-6.3133, "ay":1.13585, "alpha":-2.17745, "fx":[-106.21228,-109.42805,-109.28693,-104.62253], "fy":[27.47295,7.77177,9.13148,32.90592]}, + {"t":0.17145, "x":7.05972, "y":0.47722, "heading":3.1143, "vx":-1.08209, "vy":0.19462, "omega":-0.39005, "ax":-6.31439, "ay":1.1363, "alpha":-2.11357, "fx":[-106.22087,-109.38487,-109.25551,-104.76233], "fy":[27.38778,8.18626,9.33014,32.40804]}, + {"t":0.20574, "x":7.01891, "y":0.48456, "heading":3.10093, "vx":-1.2986, "vy":0.23358, "omega":-0.46253, "ax":-6.31559, "ay":1.13679, "alpha":-2.03859, "fx":[-106.23173,-109.33197,-109.21818,-104.92344], "fy":[27.28393,8.67427,9.56484,31.82288]}, + {"t":0.24003, "x":6.97066, "y":0.49323, "heading":3.08507, "vx":-1.51516, "vy":0.27256, "omega":-0.53243, "ax":-6.31692, "ay":1.13734, "alpha":-1.9493, "fx":[-106.24876,-109.26668,-109.1719,-105.10849], "fy":[27.14294,9.2474,9.85945,31.13386]}, + {"t":0.27432, "x":6.915, "y":0.50325, "heading":3.06681, "vx":-1.73177, "vy":0.31156, "omega":-0.59927, "ax":-6.31838, "ay":1.13797, "alpha":-1.84119, "fx":[-106.27735,-109.18509,-109.1122,-105.32082], "fy":[26.93882,9.92235,10.24631,30.31849]}, + {"t":0.3086, "x":6.8519, "y":0.5146, "heading":3.04626, "vx":-1.94842, "vy":0.35058, "omega":-0.6624, "ax":-6.31997, "ay":1.13867, "alpha":-1.7077, "fx":[-106.32507,-109.0813,-109.03228,-105.56466], "fy":[26.63348,10.72411,10.77058,29.34538]}, + {"t":0.34289, "x":6.78138, "y":0.52729, "heading":3.02355, "vx":-2.16513, "vy":0.38962, "omega":-0.72096, "ax":-6.32161, "ay":1.13945, "alpha":-1.5389, "fx":[-106.40294,-108.94585,-108.92116,-105.84549], "fy":[26.16844,11.69179,11.49798,28.16888]}, + {"t":0.37718, "x":6.70342, "y":0.54132, "heading":2.99883, "vx":-2.38189, "vy":0.42869, "omega":-0.77373, "ax":-6.32316, "ay":1.14034, "alpha":-1.31888, "fx":[-106.5275,-108.76246,-108.75992,-106.17059], "fy":[25.44839,12.89057,12.52902,26.71925]}, + {"t":0.41147, "x":6.61803, "y":0.55669, "heading":2.9723, "vx":-2.59871, "vy":0.4678, "omega":-0.81895, "ax":-6.32415, "ay":1.14131, "alpha":-1.02033, "fx":[-106.72448,-108.50045,-108.51326,-106.54963], "fy":[24.30538,14.43765,14.02739,24.88305]}, + {"t":0.44576, "x":6.5252, "y":0.5734, "heading":2.94422, "vx":-2.81556, "vy":0.50693, "omega":-0.85394, "ax":-6.32333, "ay":1.1423, "alpha":-0.59171, "fx":[-107.03479,-108.09421,-108.10836,-106.99481], "fy":[22.41125,16.56689,16.28154,22.46082]}, + {"t":0.48005, "x":6.42494, "y":0.59146, "heading":2.91494, "vx":-3.03238, "vy":0.5461, "omega":-0.87423, "ax":-6.31677, "ay":1.14289, "alpha":0.07813, "fx":[-107.51937,-107.37535,-107.37375,-107.517], "fy":[19.02322,19.81867,19.85443,19.06483]}, + {"t":0.51434, "x":6.31725, "y":0.61085, "heading":2.88496, "vx":-3.24898, "vy":0.58529, "omega":-0.87155, "ax":-6.2888, "ay":1.14108, "alpha":1.28669, "fx":[-108.19958,-105.7639,-105.82265,-108.09677], "fy":[12.03662,25.76334,26.00465,13.83311]}, + {"t":0.54863, "x":6.20215, "y":0.63159, "heading":2.85508, "vx":-3.46462, "vy":0.62442, "omega":-0.82743, "ax":-6.13751, "ay":1.125, "alpha":4.23689, "fx":[-107.77566,-99.70393,-101.63272,-108.477], "fy":[-7.28619,41.28126,38.08086,4.46805]}, + {"t":0.58292, "x":6.07974, "y":0.65367, "heading":2.8267, "vx":-3.67507, "vy":0.66299, "omega":-0.68215, "ax":-4.85939, "ay":1.06, "alpha":14.2065, "fx":[-82.3114,-51.32747,-90.0828,-106.90578], "fy":[-65.09645,89.6783,58.32113,-10.78204]}, + {"t":0.61721, "x":5.95086, "y":0.67702, "heading":2.80331, "vx":-3.8417, "vy":0.69934, "omega":-0.19501, "ax":-1.83896, "ay":0.16468, "alpha":5.61042, "fx":[-23.91618,-13.53294,-39.64858,-48.02298], "fy":[-18.08314,13.78057,21.68104,-6.17386]}, + {"t":0.6515, "x":5.81805, "y":0.7011, "heading":2.79663, "vx":-3.90476, "vy":0.70498, "omega":-0.00264, "ax":-0.01384, "ay":-0.06338, "alpha":0.00576, "fx":[-0.22636,-0.21624,-0.24439,-0.25451], "fy":[-1.0972,-1.06905,-1.05896,-1.0871]}, + {"t":0.68579, "x":5.68415, "y":0.72524, "heading":2.79654, "vx":-3.90523, "vy":0.70281, "omega":-0.00244, "ax":-0.00382, "ay":-0.02121, "alpha":0.00001, "fx":[-0.06492,-0.06491,-0.06494,-0.06495], "fy":[-0.36076,-0.36074,-0.36073,-0.36075]}, + {"t":0.72008, "x":5.55024, "y":0.74932, "heading":2.79645, "vx":-3.90536, "vy":0.70208, "omega":-0.00244, "ax":-0.00123, "ay":-0.00686, "alpha":0.0, "fx":[-0.02099,-0.02099,-0.02099,-0.02099], "fy":[-0.11677,-0.11677,-0.11677,-0.11677]}, + {"t":0.75437, "x":5.41633, "y":0.77339, "heading":2.79637, "vx":-3.9054, "vy":0.70185, "omega":-0.00244, "ax":-0.0003, "ay":-0.00167, "alpha":0.0, "fx":[-0.0051,-0.0051,-0.0051,-0.0051], "fy":[-0.02836,-0.02836,-0.02836,-0.02836]}, + {"t":0.78866, "x":5.28242, "y":0.79746, "heading":2.79628, "vx":-3.90541, "vy":0.70179, "omega":-0.00244, "ax":0.00024, "ay":0.00131, "alpha":0.0, "fx":[0.004,0.004,0.004,0.004], "fy":[0.02225,0.02225,0.02225,0.02225]}, + {"t":0.82295, "x":5.1485, "y":0.82152, "heading":2.7962, "vx":-3.90541, "vy":0.70184, "omega":-0.00244, "ax":0.00108, "ay":0.00603, "alpha":0.0, "fx":[0.01843,0.01843,0.01843,0.01843], "fy":[0.10251,0.10251,0.10251,0.10251]}, + {"t":0.85724, "x":5.01459, "y":0.84559, "heading":2.79612, "vx":-3.90537, "vy":0.70204, "omega":-0.00244, "ax":0.00338, "ay":0.01877, "alpha":0.0, "fx":[0.05744,0.05744,0.05744,0.05744], "fy":[0.31935,0.31935,0.31935,0.31935]}, + {"t":0.89152, "x":4.88068, "y":0.86967, "heading":2.79603, "vx":-3.90525, "vy":0.70269, "omega":-0.00244, "ax":0.01019, "ay":0.05653, "alpha":0.0, "fx":[0.17327,0.17327,0.17327,0.17327], "fy":[0.96158,0.96158,0.96158,0.96158]}, + {"t":0.92581, "x":4.74678, "y":0.8938, "heading":2.79595, "vx":-3.9049, "vy":0.70463, "omega":-0.00244, "ax":0.03071, "ay":0.16947, "alpha":0.0, "fx":[0.52239,0.52239,0.52241,0.52241], "fy":[2.88263,2.88261,2.88261,2.88263]}, + {"t":0.9601, "x":4.6129, "y":0.91806, "heading":2.79587, "vx":-3.90385, "vy":0.71044, "omega":-0.00244, "ax":0.09307, "ay":0.50497, "alpha":-0.00002, "fx":[1.583,1.58297,1.58307,1.5831], "fy":[8.58945,8.58935,8.58932,8.58942]}, + {"t":0.99439, "x":4.47909, "y":0.94272, "heading":2.79578, "vx":-3.90066, "vy":0.72775, "omega":-0.00244, "ax":0.27803, "ay":1.43912, "alpha":-0.00011, "fx":[4.72898,4.72879,4.72935,4.72954], "fy":[24.47929,24.47879,24.4786,24.4791]}, + {"t":1.02868, "x":4.3455, "y":0.96852, "heading":2.7957, "vx":-3.89113, "vy":0.7771, "omega":-0.00244, "ax":0.69862, "ay":3.25214, "alpha":-0.00043, "fx":[11.88232,11.88161,11.88427,11.88498], "fy":[55.31903,55.31754,55.31675,55.31824]}, + {"t":1.06297, "x":4.21249, "y":0.99708, "heading":2.79562, "vx":-3.86717, "vy":0.88861, "omega":-0.00246, "ax":1.21082, "ay":4.79339, "alpha":-0.00106, "fx":[20.59218,20.5908,20.59913,20.60052], "fy":[81.53635,81.53437,81.53203,81.53401]}, + {"t":1.09726, "x":4.0806, "y":1.03037, "heading":2.79553, "vx":-3.82565, "vy":1.05297, "omega":-0.00249, "ax":1.65056, "ay":5.46017, "alpha":-0.0019, "fx":[28.06788,28.06637,28.0831,28.08461], "fy":[92.87938,92.87758,92.8724,92.87421]}, + {"t":1.13155, "x":3.95039, "y":1.06968, "heading":2.79545, "vx":-3.76906, "vy":1.2402, "omega":-0.00256, "ax":2.0375, "ay":5.67987, "alpha":-0.0029, "fx":[34.64437,34.64368,34.67018,34.67087], "fy":[96.61861,96.61683,96.60732,96.6091]}, + {"t":1.16584, "x":3.82235, "y":1.11555, "heading":2.79536, "vx":-3.69919, "vy":1.43496, "omega":-0.00266, "ax":2.39714, "ay":5.71062, "alpha":-0.00409, "fx":[40.75525,40.75651,40.79404,40.79277], "fy":[97.14498,97.1426,97.12694,97.12932]}, + {"t":1.20013, "x":3.69691, "y":1.16811, "heading":2.79527, "vx":-3.61699, "vy":1.63077, "omega":-0.0028, "ax":2.73984, "ay":5.64981, "alpha":-0.00557, "fx":[46.57629,46.58091,46.63136,46.62672], "fy":[96.11583,96.11184,96.08756,96.09156]}, + {"t":1.23442, "x":3.5745, "y":1.22735, "heading":2.79517, "vx":-3.52305, "vy":1.8245, "omega":-0.00299, "ax":3.06952, "ay":5.53568, "alpha":-0.00812, "fx":[52.17051,52.18119,52.25273,52.24199], "fy":[94.18384,94.17603,94.13666,94.1445]}, + {"t":1.26871, "x":3.4555, "y":1.29316, "heading":2.79507, "vx":-3.41779, "vy":2.01432, "omega":-0.00327, "ax":3.39007, "ay":5.38335, "alpha":-0.02261, "fx":[57.54848,57.58834,57.78004,57.73987], "fy":[91.64368,91.61461,91.49471,91.5241]}, + {"t":1.303, "x":3.3403, "y":1.3654, "heading":2.79496, "vx":-3.30155, "vy":2.19891, "omega":-0.00404, "ax":3.73287, "ay":5.1779, "alpha":-0.16974, "fx":[62.62962,62.99836,64.36788,63.98427], "fy":[88.70501,88.41922,87.4344,87.73968]}, + {"t":1.33729, "x":3.22929, "y":1.44384, "heading":2.79482, "vx":-3.17355, "vy":2.37646, "omega":-0.00986, "ax":4.25578, "ay":4.7678, "alpha":-1.03725, "fx":[67.33029,70.04566,77.61074,74.57153], "fy":[85.55052,83.21438,76.2683,79.36248]}, + {"t":1.37158, "x":3.12297, "y":1.52813, "heading":2.79448, "vx":-3.02763, "vy":2.53994, "omega":-0.04543, "ax":4.87355, "ay":4.09887, "alpha":-2.41545, "fx":[72.12253,79.77089,93.66886,86.02847], "fy":[81.83135,74.11168,55.76467,67.17456]}, + {"t":1.40587, "x":3.02202, "y":1.61763, "heading":2.79292, "vx":-2.86051, "vy":2.68049, "omega":-0.12826, "ax":5.30466, "ay":3.46822, "alpha":-3.33991, "fx":[76.5997,88.69811,102.56937,93.05607], "fy":[77.8594,63.3398,37.42115,57.35314]}, + {"t":1.44016, "x":2.92705, "y":1.71159, "heading":2.78852, "vx":-2.67862, "vy":2.79941, "omega":-0.24278, "ax":5.59557, "ay":2.94295, "alpha":-3.75835, "fx":[81.18369,95.64878,106.49575,97.38764], "fy":[73.21985,52.49123,24.65011,49.87365]}, + {"t":1.47444, "x":2.83849, "y":1.80931, "heading":2.7802, "vx":-2.48675, "vy":2.90032, "omega":-0.37165, "ax":5.75508, "ay":2.51639, "alpha":-4.10958, "fx":[83.98647,99.69565,107.99334,99.89331], "fy":[69.45514,43.049,14.70893,43.99888]}, + {"t":1.49368, "x":2.79172, "y":1.86557, "heading":2.77305, "vx":-2.37603, "vy":2.94873, "omega":-0.45071, "ax":5.86468, "ay":2.1742, "alpha":-4.53218, "fx":[85.60221,102.78906,108.85901,101.77595], "fy":[67.46975,34.92275,6.00975,39.52804]}, + {"t":1.51292, "x":2.74709, "y":1.9227, "heading":2.76438, "vx":-2.26321, "vy":2.99056, "omega":-0.5379, "ax":5.96152, "ay":1.82071, "alpha":-4.85539, "fx":[87.72481,105.38842,109.04614,103.45531], "fy":[64.70424,26.00185,-1.80544,34.97842]}, + {"t":1.53216, "x":2.70465, "y":1.98057, "heading":2.75403, "vx":-2.14851, "vy":3.02559, "omega":-0.63132, "ax":6.04564, "ay":1.45945, "alpha":-5.07095, "fx":[90.36368,107.27273,108.75224,104.94956], "fy":[60.9863,16.69959,-8.67119,30.2848]}, + {"t":1.5514, "x":2.66444, "y":2.03905, "heading":2.74188, "vx":-2.03221, "vy":3.05367, "omega":-0.72887, "ax":6.12053, "ay":1.08953, "alpha":-5.13841, "fx":[93.63048,108.35407,108.16285,106.28617], "fy":[55.868,7.4931,-14.51266,25.28181]}, + {"t":1.57064, "x":2.62647, "y":2.098, "heading":2.72786, "vx":-1.91446, "vy":3.07463, "omega":-0.82773, "ax":6.18594, "ay":0.71481, "alpha":-5.03935, "fx":[97.33258,108.68263,107.42745,107.44135], "fy":[49.17148,-1.03788,-19.39631,19.89763]}, + {"t":1.58988, "x":2.59079, "y":2.15728, "heading":2.71194, "vx":-1.79545, "vy":3.08838, "omega":-0.92468, "ax":6.23751, "ay":0.34502, "alpha":-4.80217, "fx":[100.96845,108.44293,106.63067,108.35129], "fy":[41.24683,-8.48973,-23.52204,14.23973]}, + {"t":1.60911, "x":2.5574, "y":2.21676, "heading":2.69415, "vx":-1.67545, "vy":3.09502, "omega":-1.01706, "ax":6.27164, "ay":-0.0105, "alpha":-4.47557, "fx":[104.08546,107.85302,105.80969,108.96702], "fy":[32.67427,-14.78702,-27.08749,8.48593]}, + {"t":1.62835, "x":2.52633, "y":2.2763, "heading":2.67458, "vx":-1.55479, "vy":3.09482, "omega":-1.10317, "ax":6.28754, "ay":-0.34577, "alpha":-4.10262, "fx":[106.45769,107.08116,104.98286,109.27528], "fy":[23.96792,-20.05529,-30.22663,2.78822]}, + {"t":1.64759, "x":2.49758, "y":2.33578, "heading":2.65336, "vx":-1.43383, "vy":3.08817, "omega":-1.1821, "ax":6.28663, "ay":-0.65772, "alpha":-3.71397, "fx":[108.04887,106.23282,104.16274,109.29044], "fy":[15.4929,-24.47572,-33.02187,-2.74599]}, + {"t":1.66683, "x":2.47116, "y":2.39507, "heading":2.63062, "vx":-1.31288, "vy":3.07551, "omega":-1.25355, "ax":6.27142, "ay":-0.94526, "alpha":-3.32924, "fx":[108.9306,105.36744,103.35948,109.04281], "fy":[7.47578,-28.2183,-35.52592,-8.04575]}, + {"t":1.68607, "x":2.44706, "y":2.45406, "heading":2.6065, "vx":-1.19223, "vy":3.05733, "omega":-1.3176, "ax":6.24478, "ay":-1.20857, "alpha":-2.95988, "fx":[109.21982,104.51604,102.58141,108.57014], "fy":[0.03603,-31.4234,-37.77558,-13.06692]}, + {"t":1.70531, "x":2.42528, "y":2.51266, "heading":2.58115, "vx":-1.07209, "vy":3.03408, "omega":-1.37454, "ax":6.20942, "ay":-1.4487, "alpha":-2.6118, "fx":[109.0414,103.69329,101.8351,107.91231], "fy":[-6.78209,-34.20174,-39.79898,-17.7849]}, + {"t":1.72454, "x":2.4058, "y":2.57076, "heading":2.55471, "vx":-0.95263, "vy":3.0062, "omega":-1.42479, "ax":6.16776, "ay":-1.66714, "alpha":-2.28736, "fx":[108.50917,102.90484,101.12545,107.10799], "fy":[-12.98279,-36.63927,-41.61919,-22.18938]}, + {"t":1.74378, "x":2.38862, "y":2.62829, "heading":2.5273, "vx":-0.83397, "vy":2.97413, "omega":-1.46879, "ax":6.12177, "ay":-1.86566, "alpha":-1.98684, "fx":[107.71858,102.15144,100.45581,106.19272], "fy":[-18.59855,-38.80261,-43.25607,-26.28038]}, + {"t":1.76302, "x":2.37371, "y":2.68516, "heading":2.49904, "vx":-0.7162, "vy":2.93824, "omega":-1.50702, "ax":6.07305, "ay":-2.04607, "alpha":-1.70935, "fx":[106.74571,101.43135,99.82821,105.19804], "fy":[-23.67616,-40.74358,-44.72726,-30.06517]}, + {"t":1.78226, "x":2.36105, "y":2.74131, "heading":2.47005, "vx":-0.59936, "vy":2.89888, "omega":-1.5399, "ax":6.02281, "ay":-2.21013, "alpha":-1.45339, "fx":[105.64913,100.74168,99.2435,104.15107], "fy":[-28.26769,-42.50273,-46.04867,-33.55583]}, + {"t":1.8015, "x":2.35064, "y":2.79667, "heading":2.44042, "vx":-0.48349, "vy":2.85636, "omega":-1.56786, "ax":5.972, "ay":-2.35953, "alpha":-1.21726, "fx":[104.47297,100.07908,98.70158,103.07467], "fy":[-32.42513,-44.11205,-47.23483,-36.76747]}, + {"t":1.82074, "x":2.34244, "y":2.85118, "heading":2.41026, "vx":-0.3686, "vy":2.81096, "omega":-1.59128, "ax":5.92131, "ay":-2.49578, "alpha":-0.99921, "fx":[103.24986,99.44018,98.20158,101.9877], "fy":[-36.19749,-45.59694,-48.29902,-39.71685]}, + {"t":1.83998, "x":2.33644, "y":2.9048, "heading":2.37964, "vx":-0.25468, "vy":2.76295, "omega":-1.6105, "ax":5.87125, "ay":-2.6203, "alpha":-0.79756, "fx":[102.00363,98.82176,97.74201,100.90549], "fy":[-39.62933,-46.9777,-49.25349,-42.42142]}, + {"t":1.85921, "x":2.33263, "y":2.95747, "heading":2.34866, "vx":-0.14173, "vy":2.71254, "omega":-1.62585, "ax":5.82217, "ay":-2.73431, "alpha":-0.61076, "fx":[100.75151,98.22091,97.32096,99.84024], "fy":[-42.7604,-48.27066,-50.10947,-44.89859]}, + {"t":1.87845, "x":2.33098, "y":3.00915, "heading":2.31738, "vx":-0.02972, "vy":2.65993, "omega":-1.6376, "ax":5.77433, "ay":-2.83893, "alpha":-0.4374, "fx":[99.50579,97.63501,96.93615,98.80154], "fy":[-45.62561,-49.48906,-50.87729,-47.16528]}, + {"t":1.89769, "x":2.33148, "y":3.0598, "heading":2.28588, "vx":0.08137, "vy":2.60532, "omega":-1.64601, "ax":5.72789, "ay":-2.93513, "alpha":-0.27621, "fx":[98.27516,97.06177,96.58509,97.79673], "fy":[-48.25541,-50.64362,-51.56646,-49.23767]}, + {"t":1.91693, "x":2.3341, "y":3.10938, "heading":2.25421, "vx":0.19157, "vy":2.54885, "omega":-1.65133, "ax":5.68295, "ay":-3.0238, "alpha":-0.12607, "fx":[97.06566,96.49923,96.26515,96.83134], "fy":[-50.67623,-51.7431,-52.1857,-51.13097]}, + {"t":1.93617, "x":2.33884, "y":3.15785, "heading":2.22244, "vx":0.3009, "vy":2.49067, "omega":-1.65375, "ax":5.63957, "ay":-3.1057, "alpha":0.01404, "fx":[95.88141,95.9457,95.97364,95.90935], "fy":[-52.91094,-52.79466,-52.74297,-52.8594]}, + {"t":1.95541, "x":2.34567, "y":3.20519, "heading":2.19062, "vx":0.40939, "vy":2.43093, "omega":-1.65348, "ax":5.59778, "ay":-3.18149, "alpha":0.14499, "fx":[94.72517,95.39976,95.70789,95.03351], "fy":[-54.97934,-53.80418,-53.24559,-54.43612]}, + {"t":1.97465, "x":2.35459, "y":3.25137, "heading":2.15881, "vx":0.51709, "vy":2.36972, "omega":-1.65069, "ax":5.55756, "ay":-3.2518, "alpha":0.26758, "fx":[93.59868,94.86023,95.46525,94.20555], "fy":[-56.89858,-54.77647,-53.70021,-55.87327]}, + {"t":1.99388, "x":2.36556, "y":3.29636, "heading":2.12706, "vx":0.62401, "vy":2.30716, "omega":-1.64554, "ax":5.51889, "ay":-3.31713, "alpha":0.3825, "fx":[92.50297,94.32616,95.24318,93.42636], "fy":[-58.68352,-55.71551,-54.11289,-57.18205]}, + {"t":2.01312, "x":2.37859, "y":3.34013, "heading":2.0954, "vx":0.73018, "vy":2.24334, "omega":-1.63819, "ax":5.42265, "ay":-3.47679, "alpha":0.55721, "fx":[90.14165,92.91941,94.32952,91.56027], "fy":[-62.3597,-58.15056,-55.81156,-60.23507]}, + {"t":2.03776, "x":2.39823, "y":3.39435, "heading":2.05504, "vx":0.86379, "vy":2.15768, "omega":-1.62446, "ax":5.22553, "ay":-3.76015, "alpha":0.79173, "fx":[85.68758,89.96927,92.09088,87.79141], "fy":[-68.3142,-62.58251,-59.38364,-65.55574]}, + {"t":2.0624, "x":2.4211, "y":3.44638, "heading":2.01501, "vx":0.99255, "vy":2.06503, "omega":-1.60495, "ax":4.96569, "ay":-4.08851, "alpha":1.07364, "fx":[79.82255,86.16187,89.17089,82.70441], "fy":[-75.04539,-67.69132,-63.62956,-71.81097]}, + {"t":2.08704, "x":2.44706, "y":3.49602, "heading":1.97547, "vx":1.1149, "vy":1.96429, "omega":-1.57849, "ax":4.61769, "ay":-4.46615, "alpha":1.41463, "fx":[72.04943,81.20213,85.26828,75.66247], "fy":[-82.49816,-73.52894,-68.71014,-79.13467]}, + {"t":2.11168, "x":2.47593, "y":3.54306, "heading":1.93657, "vx":1.22867, "vy":1.85425, "omega":-1.54364, "ax":4.14603, "ay":-4.8915, "alpha":1.82829, "fx":[61.76765,74.70247,79.91666,65.70437], "fy":[-90.41577,-80.08451,-74.79913,-87.51261]}, + {"t":2.13632, "x":2.50746, "y":3.58726, "heading":1.89854, "vx":1.33083, "vy":1.73372, "omega":-1.49859, "ax":3.50499, "ay":-5.34874, "alpha":2.32783, "fx":[48.39053,66.1873,72.393,51.50456], "fy":[-98.1931,-87.21504,-82.02767,-96.48656]}, + {"t":2.16096, "x":2.54132, "y":3.62836, "heading":1.86161, "vx":1.41719, "vy":1.60193, "omega":-1.44123, "ax":2.64703, "ay":-5.79455, "alpha":2.91523, "fx":[31.64471,55.15324,61.6133,31.68957], "fy":[-104.76839,-94.54354,-90.32466,-104.61781]}, + {"t":2.1856, "x":2.57704, "y":3.66607, "heading":1.8261, "vx":1.48241, "vy":1.45916, "omega":-1.3694, "ax":1.55009, "ay":-6.14744, "alpha":3.54581, "fx":[12.02789,41.23792,46.13848,6.06217], "fy":[-108.76396,-101.35836,-99.04452,-109.09769]}, + {"t":2.21024, "x":2.61404, "y":3.70015, "heading":1.79236, "vx":1.52061, "vy":1.30769, "omega":-1.28204, "ax":0.26043, "ay":-6.3044, "alpha":4.07897, "fx":[-8.92067,24.51866,24.69206,-22.57094], "fy":[-109.06113,-106.62175,-106.36464,-106.89672]}, + {"t":2.23488, "x":2.65158, "y":3.73046, "heading":1.76077, "vx":1.52702, "vy":1.15235, "omega":-1.18153, "ax":-1.09361, "ay":-6.19646, "alpha":4.3451, "fx":[-29.04602,5.81006,-2.25654,-48.91554], "fy":[-105.51394,-109.2403,-109.12372,-97.72235]}, + {"t":2.25952, "x":2.68887, "y":3.75697, "heading":1.73166, "vx":1.50008, "vy":0.99968, "omega":-1.07447, "ax":-2.35046, "ay":-5.83543, "alpha":4.3476, "fx":[-46.56094,-13.36282,-30.85192,-69.14705], "fy":[-99.06771,-108.57986,-104.6957,-84.69269]}, + {"t":2.28416, "x":2.72512, "y":3.77983, "heading":1.70519, "vx":1.44216, "vy":0.85589, "omega":-0.96735, "ax":-3.38915, "ay":-5.30938, "alpha":4.23769, "fx":[-60.69408,-31.29826,-55.64728,-82.95419], "fy":[-91.13362,-104.84463,-93.94852,-71.31737]}, + {"t":2.3088, "x":2.75963, "y":3.79931, "heading":1.68135, "vx":1.35866, "vy":0.72507, "omega":-0.86294, "ax":-4.17547, "ay":-4.73023, "alpha":4.10788, "fx":[-71.57288,-46.79462,-73.82668,-91.90005], "fy":[-82.90647,-98.93465,-80.54678,-59.45133]}, + {"t":2.33343, "x":2.79184, "y":3.81574, "heading":1.66009, "vx":1.25577, "vy":0.60852, "omega":-0.76172, "ax":-4.74378, "ay":-4.17718, "alpha":3.9708, "fx":[-79.75771,-59.4268,-85.93056,-97.64657], "fy":[-75.11035,-91.94043,-67.60191,-49.55798]}, + {"t":2.35807, "x":2.82134, "y":3.82947, "heading":1.64132, "vx":1.13889, "vy":0.5056, "omega":-0.66388, "ax":-5.14925, "ay":-3.68504, "alpha":3.82583, "fx":[-85.87945,-69.36517,-93.71911,-101.38507], "fy":[-68.07084,-84.73481,-56.4369,-41.48364]}, + {"t":2.38271, "x":2.84784, "y":3.84081, "heading":1.62496, "vx":1.01202, "vy":0.4148, "omega":-0.56962, "ax":-5.44017, "ay":-3.26077, "alpha":3.67848, "fx":[-90.47794,-77.05404,-98.74262,-103.868], "fy":[-61.87094,-77.85091,-47.22712,-34.90983]}, + {"t":2.40735, "x":2.87112, "y":3.85004, "heading":1.61093, "vx":0.87797, "vy":0.33446, "omega":-0.47898, "ax":-5.65184, "ay":-2.89925, "alpha":3.53567, "fx":[-93.9662,-82.98052,-102.04376,-105.55392], "fy":[-56.47385,-71.54239,-39.71913,-29.52626]}, + {"t":2.43199, "x":2.89104, "y":3.8574, "heading":1.59912, "vx":0.73872, "vy":0.26302, "omega":-0.39186, "ax":-5.80847, "ay":-2.59173, "alpha":3.40209, "fx":[-96.64498,-87.56877,-104.26554,-106.72263], "fy":[-51.7953,-65.88727,-33.57869,-25.07736]}, + {"t":2.45663, "x":2.90748, "y":3.86309, "heading":1.58947, "vx":0.5956, "vy":0.19916, "omega":-0.30804, "ax":-5.92642, "ay":-2.3293, "alpha":3.27991, "fx":[-98.72917,-91.15307,-105.79709,-107.54773], "fy":[-47.73984,-60.87079,-28.50784,-21.36448]}, + {"t":2.48127, "x":2.92035, "y":3.86729, "heading":1.58188, "vx":0.44957, "vy":0.14177, "omega":-0.22722, "ax":-6.01674, "ay":-2.10408, "alpha":3.16957, "fx":[-100.37177,-93.98484,-106.8761,-108.13935], "fy":[-44.21693,-56.43693,-24.26924,-18.23615]}, + {"t":2.50591, "x":2.9296, "y":3.87015, "heading":1.57628, "vx":0.30133, "vy":0.08993, "omega":-0.14913, "ax":-6.08698, "ay":-1.90952, "alpha":3.07054, "fx":[-101.68224,-96.2495,-107.65073,-108.56902], "fy":[-41.14679,-52.51618,-20.68115,-15.57716]}, + {"t":2.53055, "x":2.93518, "y":3.87178, "heading":1.57261, "vx":0.15135, "vy":0.04288, "omega":-0.07347, "ax":-6.14241, "ay":-1.74027, "alpha":2.98185, "fx":[-102.73965,-98.08303,-108.21553,-108.88428], "fy":[-38.4615,-49.03917,-17.60593,-13.29951]}, + {"t":2.55519, "x":2.93704, "y":3.87231, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_2.traj b/src/main/deploy/choreo/E_RIGHT_PATH_2.traj new file mode 100644 index 00000000..6322dbfd --- /dev/null +++ b/src/main/deploy/choreo/E_RIGHT_PATH_2.traj @@ -0,0 +1,141 @@ +{ + "name":"E_RIGHT_PATH_2", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.9948270320892334, "y":2.801387310028076, "heading":2.618314122167914, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.619781017303467, "y":2.2527506351470947, "heading":1.5707963267948966, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.8137584924697876, "y":2.195854902267456, "heading":0.0, "intervals":13, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":1.2163537740707395, "y":2.1863720417022705, "heading":1.5707963267948966, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":3.462650775909424, "y":2.6634156703948975, "heading":2.618314122167914, "intervals":14, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":2, "to":3, "data":{"type":"MaxAngularVelocity", "props":{"max":0.0}}, "enabled":true}, + {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":0, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.9948270320892334 m", "val":3.9948270320892334}, "y":{"exp":"2.801387310028076 m", "val":2.801387310028076}, "heading":{"exp":"2.6183141221679134 rad", "val":2.618314122167914}, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.619781017303467 m", "val":2.619781017303467}, "y":{"exp":"2.2527506351470947 m", "val":2.2527506351470947}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.8137584924697876 m", "val":1.8137584924697876}, "y":{"exp":"2.195854902267456 m", "val":2.195854902267456}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":13, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"1.2163537740707397 m", "val":1.2163537740707395}, "y":{"exp":"2.1863720417022705 m", "val":2.1863720417022705}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"3.462650775909424 m", "val":3.462650775909424}, "y":{"exp":"2.6634156703948975 m", "val":2.6634156703948975}, "heading":{"exp":"2.6183141221679134 rad", "val":2.618314122167914}, "intervals":14, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":2, "to":3, "data":{"type":"MaxAngularVelocity", "props":{"max":{"exp":"0 rad / s", "val":0.0}}}, "enabled":true}, + {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":0, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.70417,0.93826,1.36875,2.57084], + "samples":[ + {"t":0.0, "x":3.99483, "y":2.80139, "heading":2.61831, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.26392, "ay":-2.87502, "alpha":-7.77032, "fx":[-109.39894,-101.01273,-65.94747,-81.79183], "fy":[7.60574,-42.85708,-87.65929,-72.70251]}, + {"t":0.02347, "x":3.99338, "y":2.8006, "heading":2.61831, "vx":-0.12356, "vy":-0.06748, "omega":-0.18239, "ax":-5.29273, "ay":-2.85498, "alpha":-7.62651, "fx":[-109.43396,-101.06468,-66.6976,-82.91509], "fy":[6.95037,-42.71801,-87.0799,-71.40235]}, + {"t":0.04694, "x":3.98902, "y":2.79822, "heading":2.61403, "vx":-0.24779, "vy":-0.1345, "omega":-0.3614, "ax":-5.32062, "ay":-2.83415, "alpha":-7.49341, "fx":[-109.46121,-101.18553,-67.59775,-83.76433], "fy":[6.3406,-42.41274,-86.37231,-70.38778]}, + {"t":0.07042, "x":3.98174, "y":2.79429, "heading":2.60555, "vx":-0.37268, "vy":-0.20102, "omega":-0.53729, "ax":-5.3483, "ay":-2.81217, "alpha":-7.36616, "fx":[-109.48234,-101.37096,-68.64579,-84.3928], "fy":[5.75715,-41.94725,-85.53018,-69.61657]}, + {"t":0.09389, "x":3.97152, "y":2.78879, "heading":2.59294, "vx":-0.49821, "vy":-0.26703, "omega":-0.71019, "ax":-5.37648, "ay":-2.78857, "alpha":-7.24012, "fx":[-109.49868,-101.61583,-69.84067,-84.85454], "fy":[5.17716,-41.32753,-84.54473,-69.03632]}, + {"t":0.11736, "x":3.95834, "y":2.78176, "heading":2.57627, "vx":-0.62441, "vy":-0.33248, "omega":-0.88013, "ax":-5.40592, "ay":-2.76279, "alpha":-7.11045, "fx":[-109.51123,-101.91422,-71.18235,-85.20485], "fy":[4.57359,-40.55992,-83.4044,-68.58644]}, + {"t":0.14083, "x":3.9422, "y":2.77319, "heading":2.55561, "vx":-0.7513, "vy":-0.39733, "omega":-1.04703, "ax":-5.43737, "ay":-2.73419, "alpha":-6.97177, "fx":[-109.52049,-102.25936,-72.67194,-85.50075], "fy":[3.91446,-39.65156,-82.09435,-68.1996]}, + {"t":0.16431, "x":3.92306, "y":2.76311, "heading":2.53103, "vx":-0.87893, "vy":-0.46151, "omega":-1.21067, "ax":-5.47162, "ay":-2.70209, "alpha":-6.81778, "fx":[-109.52628,-102.64359,-74.31167,-85.80144], "fy":[3.16205,-38.61091,-80.59571,-67.80253]}, + {"t":0.18778, "x":3.90092, "y":2.75154, "heading":2.50262, "vx":-1.00736, "vy":-0.52493, "omega":-1.3707, "ax":-5.50948, "ay":-2.66579, "alpha":-6.64087, "fx":[-109.52728,-103.05833,-76.10511,-86.16832], "fy":[2.27211,-37.44845,-78.88454,-67.31618]}, + {"t":0.21125, "x":3.87576, "y":2.73848, "heading":2.47044, "vx":-1.13668, "vy":-0.58751, "omega":-1.52658, "ax":-5.55177, "ay":-2.62453, "alpha":-6.43183, "fx":[-109.52034,-103.49399,-78.05725,-86.66454], "fy":[1.19333,-36.1776,-76.93032,-66.65515]}, + {"t":0.23472, "x":3.84755, "y":2.72397, "heading":2.43461, "vx":-1.26699, "vy":-0.64911, "omega":-1.67755, "ax":-5.59927, "ay":-2.57747, "alpha":-6.17959, "fx":[-109.4994,-103.93988,-80.17476,-87.35394], "fy":[-0.13272,-34.81598,-74.69363,-65.72604]}, + {"t":0.2582, "x":3.81627, "y":2.70802, "heading":2.39524, "vx":-1.39842, "vy":-0.70961, "omega":-1.8226, "ax":-5.65271, "ay":-2.52363, "alpha":-5.87111, "fx":[-109.45402,-104.38403,-82.46643,-88.29924], "fy":[-1.77072,-33.38711,-72.12259,-64.42461]}, + {"t":0.28167, "x":3.78189, "y":2.69067, "heading":2.35246, "vx":-1.5311, "vy":-0.76884, "omega":-1.9604, "ax":-5.71267, "ay":-2.46169, "alpha":-5.49126, "fx":[-109.36739,-104.81299,-84.94358,-89.55933], "fy":[-3.78887,-31.92297,-69.14726,-62.63134]}, + {"t":0.30514, "x":3.74438, "y":2.67195, "heading":2.30644, "vx":-1.66519, "vy":-0.82663, "omega":-2.0893, "ax":-5.77951, "ay":-2.38976, "alpha":-5.02288, "fx":[-109.2142,-105.21125,-87.62078,-91.18497], "fy":[-6.25348,-30.46773,-65.67021,-60.20495]}, + {"t":0.32861, "x":3.7037, "y":2.65188, "heading":2.2574, "vx":-1.80085, "vy":-0.88272, "omega":-2.2072, "ax":-5.85324, "ay":-2.30496, "alpha":-4.44666, "fx":[-108.95902,-105.56037,-90.51614,-93.21215], "fy":[-9.21935,-29.08359,-61.55055,-56.97364]}, + {"t":0.35208, "x":3.65982, "y":2.63053, "heading":2.20559, "vx":-1.93824, "vy":-0.93682, "omega":-2.31157, "ax":-5.9333, "ay":-2.20279, "alpha":-3.74063, "fx":[-108.55676,-105.83691,-93.65035,-95.65094], "fy":[-12.71518,-27.86066,-56.57534,-52.7242]}, + {"t":0.37556, "x":3.61269, "y":2.60793, "heading":2.15133, "vx":-2.07751, "vy":-0.98853, "omega":-2.39937, "ax":-6.01821, "ay":-2.07609, "alpha":-2.87802, "fx":[-107.9573,-106.00795,-97.04026,-98.46654], "fy":[-16.72405,-26.93427,-50.40638,-47.19008]}, + {"t":0.39903, "x":3.56227, "y":2.58416, "heading":2.09501, "vx":-2.21877, "vy":-1.03726, "omega":-2.46692, "ax":-6.10474, "ay":-1.91362, "alpha":-1.82114, "fx":[-107.11723,-106.02064,-100.67422,-101.54738], "fy":[-21.16208,-26.51851,-42.47687,-40.04317]}, + {"t":0.4225, "x":3.5085, "y":2.55929, "heading":2.03711, "vx":-2.36206, "vy":-1.08217, "omega":-2.50967, "ax":-6.18577, "ay":-1.69791, "alpha":-0.50525, "fx":[-106.01918,-105.77526,-104.42477,-104.6538], "fy":[-25.862,-26.97639,-31.78404,-30.90166]}, + {"t":0.44597, "x":3.45136, "y":2.53342, "heading":1.9782, "vx":-2.50725, "vy":-1.12203, "omega":-2.52153, "ax":-6.24393, "ay":-1.4024, "alpha":1.202, "fx":[-104.69559,-105.04776,-107.73976,-107.34659], "fy":[-30.57066,-28.98305,-16.48219,-19.38165]}, + {"t":0.46945, "x":3.39079, "y":2.50669, "heading":1.91902, "vx":-2.65381, "vy":-1.15494, "omega":-2.49332, "ax":-6.231, "ay":-0.99144, "alpha":3.5965, "fx":[-103.24839,-103.22544,-108.55659,-108.91942], "fy":[-34.96374,-33.95052,6.7017,-5.24384]}, + {"t":0.49292, "x":3.32678, "y":2.47931, "heading":1.86049, "vx":-2.80007, "vy":-1.17822, "omega":-2.4089, "ax":-6.00765, "ay":-0.45801, "alpha":7.29003, "fx":[-101.86442,-98.19402,-100.2649,-108.43039], "fy":[-38.64635,-45.20472,41.4019,11.28671]}, + {"t":0.51639, "x":3.2594, "y":2.45153, "heading":1.80395, "vx":-2.94108, "vy":-1.18897, "omega":-2.23778, "ax":-5.32022, "ay":-0.01162, "alpha":12.74156, "fx":[-101.00456,-82.38648,-73.39751,-105.19331], "fy":[-40.67787,-68.27065,79.61808,28.54006]}, + {"t":0.53986, "x":3.1889, "y":2.42362, "heading":1.75142, "vx":-3.06596, "vy":-1.18924, "omega":-1.93871, "ax":-5.10488, "ay":0.37721, "alpha":13.86171, "fx":[-103.1214,-81.93908,-60.21168,-102.05798], "fy":[-34.66644,-67.65967,89.90471,38.08658]}, + {"t":0.56333, "x":3.11553, "y":2.39581, "heading":1.70592, "vx":-3.18578, "vy":-1.18039, "omega":-1.61334, "ax":-5.13163, "ay":0.94105, "alpha":13.04013, "fx":[-105.70065,-92.17528,-52.73232,-98.54215], "fy":[-25.23277,-51.4034,94.41524,46.24923]}, + {"t":0.58681, "x":3.03934, "y":2.36836, "heading":1.66805, "vx":-3.30624, "vy":-1.1583, "omega":-1.30726, "ax":-5.0578, "ay":1.69461, "alpha":11.9487, "fx":[-107.58361,-101.02941,-42.04124,-93.47294], "fy":[-14.31306,-25.6754,99.63103,55.65687]}, + {"t":0.61028, "x":2.96034, "y":2.34164, "heading":1.63737, "vx":-3.42495, "vy":-1.11852, "omega":-1.0268, "ax":-4.77075, "ay":2.80652, "alpha":10.18533, "fx":[-108.37041,-99.93368,-29.64943,-86.64288], "fy":[-1.2536,22.45382,104.04871,65.70317]}, + {"t":0.63375, "x":2.87863, "y":2.31616, "heading":1.61326, "vx":-3.53693, "vy":-1.05264, "omega":-0.78773, "ax":-4.26396, "ay":3.93501, "alpha":8.30008, "fx":[-106.6632,-76.51872,-26.98257,-79.95051], "fy":[18.28039,71.04657,104.80345,73.60335]}, + {"t":0.65722, "x":2.79444, "y":2.29253, "heading":1.59477, "vx":-3.63702, "vy":-0.96028, "omega":-0.5929, "ax":-3.74983, "ay":4.65649, "alpha":6.99814, "fx":[-100.04366,-56.67862,-26.0775,-72.33406], "fy":[40.96811,89.7431,105.08291,81.02812]}, + {"t":0.6807, "x":2.70804, "y":2.27128, "heading":1.58086, "vx":-3.72504, "vy":-0.85098, "omega":-0.42864, "ax":-2.97956, "ay":5.25477, "alpha":6.56005, "fx":[-89.87969,-33.5971,-17.07127,-62.17755], "fy":[59.99527,101.42117,107.03602,89.07613]}, + {"t":0.70417, "x":2.61978, "y":2.25275, "heading":1.5708, "vx":-3.79497, "vy":-0.72764, "omega":-0.27466, "ax":-1.83706, "ay":5.8024, "alpha":5.46868, "fx":[-66.16972,-8.53721,-5.08244,-45.20217], "fy":[83.8374,105.65009,107.45577,97.84566]}, + {"t":0.71977, "x":2.56033, "y":2.2421, "heading":1.56651, "vx":-3.82364, "vy":-0.63709, "omega":-0.18932, "ax":-0.67027, "ay":6.06863, "alpha":4.97282, "fx":[-42.10944,14.94103,9.8335,-28.26935], "fy":[97.51704,104.87195,106.88346,103.62987]}, + {"t":0.73538, "x":2.50058, "y":2.2329, "heading":1.56356, "vx":-3.8341, "vy":-0.54238, "omega":-0.11171, "ax":0.88059, "ay":6.07298, "alpha":4.27279, "fx":[-6.68931,41.34393,29.57237,-4.31249], "fy":[105.54042,97.65995,103.01141,106.98687]}, + {"t":0.75099, "x":2.44085, "y":2.22517, "heading":1.56181, "vx":-3.82036, "vy":-0.44761, "omega":-0.04503, "ax":2.56521, "ay":5.6297, "alpha":3.3189, "fx":[34.15022,64.28651,50.77929,25.31808], "fy":[100.09827,84.76829,94.34294,103.82906]}, + {"t":0.76659, "x":2.38154, "y":2.21887, "heading":1.56111, "vx":-3.78033, "vy":-0.35975, "omega":0.00676, "ax":3.98558, "ay":4.80171, "alpha":2.36868, "fx":[66.28304,80.4851,69.65893,54.74732], "fy":[83.07259,70.24337,81.54574,91.84095]}, + {"t":0.7822, "x":2.32303, "y":2.21384, "heading":1.56121, "vx":-3.71813, "vy":-0.28482, "omega":0.04373, "ax":4.95564, "ay":3.86696, "alpha":1.52657, "fx":[85.12563,90.73549,84.01131,77.30393], "fy":[64.67947,57.18033,66.98865,74.25501]}, + {"t":0.7978, "x":2.26561, "y":2.20987, "heading":1.5619, "vx":-3.64079, "vy":-0.22447, "omega":0.06755, "ax":5.54679, "ay":3.02732, "alpha":0.83279, "fx":[95.12739,97.04167,93.76988,91.45826], "fy":[49.95004,46.50374,52.95061,56.57113]}, + {"t":0.81341, "x":2.20947, "y":2.20674, "heading":1.56295, "vx":-3.55423, "vy":-0.17722, "omega":0.08055, "ax":5.89331, "ay":2.34284, "alpha":0.29678, "fx":[100.52959,100.97419,99.98163,99.48894], "fy":[39.05334,38.03584,40.62612,41.68875]}, + {"t":0.82902, "x":2.15472, "y":2.20426, "heading":1.56421, "vx":-3.46226, "vy":-0.14066, "omega":0.08518, "ax":6.09669, "ay":1.8023, "alpha":-0.10968, "fx":[103.60887,103.49769,103.79979,103.90533], "fy":[31.01636,31.32724,30.29268,29.99006]}, + {"t":0.84462, "x":2.10143, "y":2.20228, "heading":1.56554, "vx":-3.36711, "vy":-0.11254, "omega":0.08347, "ax":6.21793, "ay":1.37633, "alpha":-0.42086, "fx":[105.46649,105.16855,106.09785,106.32829], "fy":[24.97005,25.95753,21.78134,20.93497]}, + {"t":0.86023, "x":2.04964, "y":2.20069, "heading":1.56684, "vx":-3.27008, "vy":-0.09106, "omega":0.0769, "ax":6.29142, "ay":1.03728, "alpha":-0.66364, "fx":[106.64465,106.30768,107.45135,107.65733], "fy":[20.30811,21.59898,14.78924,13.87931]}, + {"t":0.87583, "x":1.99937, "y":2.1994, "heading":1.56804, "vx":-3.17189, "vy":-0.07487, "omega":0.06654, "ax":6.33643, "ay":0.7636, "alpha":-0.85689, "fx":[107.42394,107.10449,108.21967,108.3752], "fy":[16.62742,18.00962,9.01706,8.30025]}, + {"t":0.89144, "x":1.95065, "y":2.19832, "heading":1.56908, "vx":-3.07301, "vy":-0.06295, "omega":0.05317, "ax":6.364, "ay":0.53938, "alpha":-1.01359, "fx":[107.95762,107.67419,108.62379,108.74361], "fy":[13.65905,15.01309,4.21237,3.81421]}, + {"t":0.90705, "x":1.90346, "y":2.1974, "heading":1.56991, "vx":-2.97369, "vy":-0.05453, "omega":0.03735, "ax":6.38063, "ay":0.35307, "alpha":-1.14275, "fx":[108.33373,108.08906,108.79996,108.90798], "fy":[11.22011,12.48029,0.17483,0.14723]}, + {"t":0.92265, "x":1.85783, "y":2.1966, "heading":1.57049, "vx":-2.87411, "vy":-0.04902, "omega":0.01952, "ax":6.39025, "ay":0.19624, "alpha":-1.25076, "fx":[108.60515,108.3958,108.83302,108.95142], "fy":[9.1833,10.31576,-3.25088,-2.8964]}, + {"t":0.93826, "x":1.81376, "y":2.19585, "heading":1.5708, "vx":-2.77439, "vy":-0.04596, "omega":0.0, "ax":6.4348, "ay":0.12424, "alpha":0.0, "fx":[109.45411,109.45411,109.45411,109.45411], "fy":[2.11325,2.11325,2.11325,2.11325]}, + {"t":0.97137, "x":1.72541, "y":2.1944, "heading":1.5708, "vx":-2.5613, "vy":-0.04185, "omega":0.0, "ax":6.43792, "ay":0.11876, "alpha":0.0, "fx":[109.50724,109.50724,109.50724,109.50724], "fy":[2.02002,2.02002,2.02002,2.02002]}, + {"t":1.00449, "x":1.64413, "y":2.19308, "heading":1.5708, "vx":-2.34811, "vy":-0.03792, "omega":0.0, "ax":6.44031, "ay":0.11456, "alpha":0.0, "fx":[109.54787,109.54787,109.54787,109.54787], "fy":[1.94862,1.94862,1.94862,1.94862]}, + {"t":1.0376, "x":1.5699, "y":2.19189, "heading":1.5708, "vx":-2.13485, "vy":-0.03412, "omega":0.0, "ax":6.4422, "ay":0.11124, "alpha":0.0, "fx":[109.57994,109.57994,109.57994,109.57994], "fy":[1.89221,1.89221,1.89221,1.89221]}, + {"t":1.07072, "x":1.50274, "y":2.19082, "heading":1.5708, "vx":-1.92152, "vy":-0.03044, "omega":0.0, "ax":6.44372, "ay":0.10856, "alpha":0.0, "fx":[109.6059,109.6059,109.6059,109.6059], "fy":[1.8465,1.8465,1.8465,1.8465]}, + {"t":1.10383, "x":1.44264, "y":2.18987, "heading":1.5708, "vx":-1.70813, "vy":-0.02684, "omega":0.0, "ax":6.44498, "ay":0.10634, "alpha":0.0, "fx":[109.62735,109.62735,109.62735,109.62735], "fy":[1.80873,1.80873,1.80873,1.80873]}, + {"t":1.13695, "x":1.38961, "y":2.18904, "heading":1.5708, "vx":-1.49471, "vy":-0.02332, "omega":0.0, "ax":6.44604, "ay":0.10447, "alpha":0.0, "fx":[109.64535,109.64535,109.64535,109.64535], "fy":[1.77699,1.77699,1.77699,1.77699]}, + {"t":1.17006, "x":1.34365, "y":2.18832, "heading":1.5708, "vx":-1.28125, "vy":-0.01986, "omega":0.0, "ax":6.44695, "ay":0.10288, "alpha":0.0, "fx":[109.66069,109.66069,109.66069,109.66069], "fy":[1.74994,1.74994,1.74994,1.74994]}, + {"t":1.20317, "x":1.30476, "y":2.18772, "heading":1.5708, "vx":-1.06777, "vy":-0.01646, "omega":0.0, "ax":6.44772, "ay":0.10151, "alpha":0.0, "fx":[109.67391,109.67391,109.67391,109.67391], "fy":[1.72662,1.72662,1.72662,1.72662]}, + {"t":1.23629, "x":1.27293, "y":2.18723, "heading":1.5708, "vx":-0.85425, "vy":-0.01309, "omega":0.0, "ax":6.4484, "ay":0.10031, "alpha":0.0, "fx":[109.68542,109.68542,109.68542,109.68542], "fy":[1.70631,1.70631,1.70631,1.70631]}, + {"t":1.2694, "x":1.24818, "y":2.18686, "heading":1.5708, "vx":-0.64072, "vy":-0.00977, "omega":0.0, "ax":6.44899, "ay":0.09926, "alpha":0.0, "fx":[109.69554,109.69554,109.69554,109.69554], "fy":[1.68846,1.68846,1.68846,1.68846]}, + {"t":1.30252, "x":1.2305, "y":2.18659, "heading":1.5708, "vx":-0.42716, "vy":-0.00649, "omega":0.0, "ax":6.44952, "ay":0.09833, "alpha":0.0, "fx":[109.7045,109.7045,109.7045,109.7045], "fy":[1.67264,1.67264,1.67264,1.67264]}, + {"t":1.33563, "x":1.21989, "y":2.18643, "heading":1.5708, "vx":-0.21359, "vy":-0.00323, "omega":0.0, "ax":6.44999, "ay":0.09751, "alpha":0.0, "fx":[109.71248,109.71248,109.71248,109.71248], "fy":[1.65854,1.65854,1.65854,1.65854]}, + {"t":1.36875, "x":1.21635, "y":2.18637, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.22326, "ay":1.30875, "alpha":3.58855, "fx":[109.55408,109.67181,104.38435,99.81312], "fy":[5.60953,3.99663,33.89718,45.54222]}, + {"t":1.40309, "x":1.22002, "y":2.18714, "heading":1.5708, "vx":0.21374, "vy":0.04495, "omega":0.12325, "ax":6.2249, "ay":1.30979, "alpha":3.54195, "fx":[109.52994,109.65627,104.41195,99.93702], "fy":[5.87654,4.20507,33.788,45.24677]}, + {"t":1.43744, "x":1.23104, "y":2.18946, "heading":1.57503, "vx":0.42754, "vy":0.08993, "omega":0.2449, "ax":6.22666, "ay":1.311, "alpha":3.49068, "fx":[109.50744,109.63561,104.41897,100.09269], "fy":[6.08122,4.50434,33.73856,44.87473]}, + {"t":1.47178, "x":1.24939, "y":2.19332, "heading":1.58344, "vx":0.64139, "vy":0.13496, "omega":0.36479, "ax":6.22857, "ay":1.3124, "alpha":3.43312, "fx":[109.4858,109.60871,104.40784,100.28275], "fy":[6.23848,4.89772,33.74084,44.41714]}, + {"t":1.50613, "x":1.2751, "y":2.19873, "heading":1.59597, "vx":0.85532, "vy":0.18004, "omega":0.4827, "ax":6.23071, "ay":1.31402, "alpha":3.36712, "fx":[109.46374,109.57398,104.3816,100.51091], "fy":[6.36819,5.39023,33.78426,43.86141]}, + {"t":1.54047, "x":1.30815, "y":2.20569, "heading":1.61255, "vx":1.06931, "vy":0.22517, "omega":0.59835, "ax":6.23313, "ay":1.31588, "alpha":3.28987, "fx":[109.43934,109.52924,104.34432,100.78196], "fy":[6.49638,5.98907,33.85466,43.19067]}, + {"t":1.57482, "x":1.34855, "y":2.2142, "heading":1.6331, "vx":1.28339, "vy":0.27036, "omega":0.71134, "ax":6.23592, "ay":1.31803, "alpha":3.19758, "fx":[109.40993,109.4715,104.3015,101.10178], "fy":[6.65705,6.70436,33.93276,42.38279]}, + {"t":1.60916, "x":1.39631, "y":2.22426, "heading":1.65753, "vx":1.49757, "vy":0.31563, "omega":0.82116, "ax":6.23918, "ay":1.32051, "alpha":3.08507, "fx":[109.37162,109.39657,104.26092,101.47742], "fy":[6.89524,7.55045,33.99166,41.4088]}, + {"t":1.64351, "x":1.45142, "y":2.23588, "heading":1.68573, "vx":1.71185, "vy":0.36098, "omega":0.92712, "ax":6.24302, "ay":1.32341, "alpha":2.94506, "fx":[109.31856,109.29839,104.23386,101.91719], "fy":[7.2721,8.54826,33.99239,40.23025]}, + {"t":1.67786, "x":1.5139, "y":2.24906, "heading":1.71757, "vx":1.92627, "vy":0.40644, "omega":1.02827, "ax":6.24756, "ay":1.32681, "alpha":2.76686, "fx":[109.24114,109.16778,104.23722,102.43089], "fy":[7.8738,9.7299,33.87595,38.79476]}, + {"t":1.7122, "x":1.58374, "y":2.2638, "heading":1.75289, "vx":2.14085, "vy":0.452, "omega":1.1233, "ax":6.25289, "ay":1.33088, "alpha":2.53392, "fx":[109.12217,108.98974,104.29738,103.03022], "fy":[8.8284,11.14782,33.54746,37.02763]}, + {"t":1.74655, "x":1.66096, "y":2.28011, "heading":1.79147, "vx":2.35561, "vy":0.49771, "omega":1.21032, "ax":6.25896, "ay":1.3359, "alpha":2.21855, "fx":[108.92782,108.73738,104.4575,103.72949], "fy":[10.33976,12.89547,32.84208,34.81547]}, + {"t":1.78089, "x":1.74555, "y":2.29799, "heading":1.83304, "vx":2.57057, "vy":0.5436, "omega":1.28652, "ax":6.26522, "ay":1.34237, "alpha":1.76962, "fx":[108.58373,108.35562,104.79244,104.5467], "fy":[12.76246,15.15871,31.44142,31.97083]}, + {"t":1.81524, "x":1.83753, "y":2.31746, "heading":1.87723, "vx":2.78575, "vy":0.5897, "omega":1.3473, "ax":6.26927, "ay":1.35122, "alpha":1.07874, "fx":[107.90253,107.70826,105.43979,105.50334], "fy":[16.78742,18.36838,28.63195,28.14767]}, + {"t":1.84958, "x":1.93691, "y":2.33851, "heading":1.9235, "vx":3.00107, "vy":0.63611, "omega":1.38435, "ax":6.25976, "ay":1.36362, "alpha":-0.13802, "fx":[106.31128,106.3411,106.64301,106.61183], "fy":[23.97491,23.79004,22.40572,22.60841]}, + {"t":1.88393, "x":2.04367, "y":2.36116, "heading":1.97105, "vx":3.21607, "vy":0.68294, "omega":1.37961, "ax":6.15663, "ay":1.37596, "alpha":-2.98553, "fx":[101.46531,101.52481,108.14063,107.75913], "fy":[38.56492,37.19027,4.41031,13.45303]}, + {"t":1.91827, "x":2.15776, "y":2.38542, "heading":2.01843, "vx":3.42752, "vy":0.7302, "omega":1.27707, "ax":4.86226, "ay":1.41308, "alpha":-13.62919, "fx":[85.19207,49.98891,88.06108,107.58049], "fy":[65.36877,90.08591,-58.10169,-1.20891]}, + {"t":1.95262, "x":2.27835, "y":2.41134, "heading":2.06229, "vx":3.59452, "vy":0.77873, "omega":0.80897, "ax":-0.06534, "ay":0.07997, "alpha":-0.18195, "fx":[-0.91776,-1.75058,-1.30509,-0.47202], "fy":[1.99951,1.55356,0.72088,1.16691]}, + {"t":1.98696, "x":2.40177, "y":2.43813, "heading":2.09007, "vx":3.59227, "vy":0.78148, "omega":0.80272, "ax":-4.93607, "ay":-1.46891, "alpha":12.95615, "fx":[-83.76624,-54.63338,-89.86078,-107.58399], "fy":[-67.09193,-86.58003,55.76602,-2.03694]}, + {"t":2.02131, "x":2.52223, "y":2.4641, "heading":2.11764, "vx":3.42274, "vy":0.73103, "omega":1.2477, "ax":-6.09291, "ay":-1.37473, "alpha":4.13597, "fx":[-98.46032,-100.26025,-108.0448,-107.78956], "fy":[-45.61903,-39.75701,5.2878,-13.44696]}, + {"t":2.05565, "x":2.6362, "y":2.4884, "heading":2.1605, "vx":3.21348, "vy":0.68381, "omega":1.38976, "ax":-6.25578, "ay":-1.36498, "alpha":0.56795, "fx":[-105.60313,-106.03852,-107.18825,-106.80609], "fy":[-26.86261,-24.88604,-19.45086,-21.67208]}, + {"t":2.09, "x":2.74287, "y":2.51108, "heading":2.20823, "vx":2.99862, "vy":0.63693, "omega":1.40926, "ax":-6.27057, "ay":-1.35283, "alpha":-0.91546, "fx":[-107.91132,-107.24319,-105.31956,-106.16867], "fy":[-16.75601,-20.85615,-28.97289,-25.45995]}, + {"t":2.12435, "x":2.84216, "y":2.53216, "heading":2.25663, "vx":2.78325, "vy":0.59047, "omega":1.37782, "ax":-6.26537, "ay":-1.34358, "alpha":-1.73196, "fx":[-108.83077,-107.6588,-103.9216,-105.8772], "fy":[-10.62549,-19.51229,-34.13075,-27.14681]}, + {"t":2.15869, "x":2.93406, "y":2.55165, "heading":2.30395, "vx":2.56807, "vy":0.54432, "omega":1.31834, "ax":-6.25725, "ay":-1.33707, "alpha":-2.24287, "fx":[-109.24467,-107.80972,-102.86135,-105.82014], "fy":[-6.59216,-19.20395,-37.47162,-27.70479]}, + {"t":2.19304, "x":3.01857, "y":2.56955, "heading":2.34923, "vx":2.35316, "vy":0.4984, "omega":1.2413, "ax":-6.24963, "ay":-1.33231, "alpha":-2.58833, "fx":[-109.4447,-107.84147,-102.02215,-105.90943], "fy":[-3.79675,-19.37643,-39.86768,-27.60801]}, + {"t":2.22738, "x":3.09571, "y":2.58589, "heading":2.39186, "vx":2.13851, "vy":0.45264, "omega":1.15241, "ax":-6.24315, "ay":-1.32859, "alpha":-2.83532, "fx":[-109.54555,-107.81097,-101.33618,-106.0842], "fy":[-1.79238,-19.78761,-41.69538,-27.12059]}, + {"t":2.26173, "x":3.16547, "y":2.60065, "heading":2.43144, "vx":1.92409, "vy":0.40701, "omega":1.05503, "ax":-6.23776, "ay":-1.32549, "alpha":-3.02003, "fx":[-109.5978,-107.74595,-100.76345,-106.30311], "fy":[-0.32153,-20.31341,-43.14462,-26.40553]}, + {"t":2.29607, "x":3.22788, "y":2.61385, "heading":2.46768, "vx":1.70985, "vy":0.36149, "omega":0.9513, "ax":-6.23328, "ay":-1.32278, "alpha":-3.16359, "fx":[-109.62549,-107.66235,-100.27883,-106.53827], "fy":[0.7766,-20.88294,-44.32283,-25.57124]}, + {"t":2.33042, "x":3.28293, "y":2.62548, "heading":2.50035, "vx":1.49577, "vy":0.31606, "omega":0.84265, "ax":-6.22949, "ay":-1.32033, "alpha":-3.27894, "fx":[-109.64056,-107.57045,-99.86544,-106.77108], "fy":[1.60894,-21.45245,-45.29653,-24.6938]}, + {"t":2.36476, "x":3.33062, "y":2.63556, "heading":2.52929, "vx":1.28181, "vy":0.27071, "omega":0.73003, "ax":-6.22625, "ay":-1.3181, "alpha":-3.37425, "fx":[-109.64903,-107.47756,-99.51118,-106.98945], "fy":[2.25012,-21.99328,-46.11004,-23.82858]}, + {"t":2.39911, "x":3.37098, "y":2.64408, "heading":2.55437, "vx":1.06797, "vy":0.22544, "omega":0.61414, "ax":-6.22344, "ay":-1.31606, "alpha":-3.45478, "fx":[-109.65396,-107.38919,-99.20693,-107.18578], "fy":[2.75424,-22.48581,-46.79459,-23.01682]}, + {"t":2.43345, "x":3.40399, "y":2.65104, "heading":2.57546, "vx":0.85422, "vy":0.18024, "omega":0.49548, "ax":-6.22097, "ay":-1.31421, "alpha":-3.52393, "fx":[-109.65679,-107.30966,-98.94551,-107.35556], "fy":[3.16164,-22.91609,-47.37319,-22.28973]}, + {"t":2.4678, "x":3.42965, "y":2.65646, "heading":2.59248, "vx":0.64056, "vy":0.1351, "omega":0.37445, "ax":-6.21877, "ay":-1.31256, "alpha":-3.58396, "fx":[-109.65818,-107.24243,-98.72118,-107.49628], "fy":[3.50298,-23.27388,-47.86326,-21.67118]}, + {"t":2.50214, "x":3.44799, "y":2.66032, "heading":2.60534, "vx":0.42698, "vy":0.09002, "omega":0.25136, "ax":-6.21681, "ay":-1.31112, "alpha":-3.63638, "fx":[-109.65832,-107.19029,-98.52935,-107.60666], "fy":[3.80185,-23.55145,-48.27818,-21.17965]}, + {"t":2.53649, "x":3.45899, "y":2.66264, "heading":2.61397, "vx":0.21346, "vy":0.04499, "omega":0.12647, "ax":-6.21505, "ay":-1.3099, "alpha":-3.68227, "fx":[-109.65719,-107.15546,-98.36636,-107.68599], "fy":[4.07644,-23.74281,-48.62818,-20.82963]}, + {"t":2.57084, "x":3.46265, "y":2.66342, "heading":2.61831, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[ + {"name":"STOW", "from":{"target":3, "targetTimestamp":1.36875, "offset":{"exp":"0.25 s", "val":0.25}}, "event":null}] +} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_2_BACK.traj b/src/main/deploy/choreo/E_RIGHT_PATH_2_BACK.traj new file mode 100644 index 00000000..c7171a1b --- /dev/null +++ b/src/main/deploy/choreo/E_RIGHT_PATH_2_BACK.traj @@ -0,0 +1,121 @@ +{ + "name":"E_RIGHT_PATH_2_BACK", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.173567533493042, "y":3.878880023956299, "heading":1.5707963267948966, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.6164592504501345, "y":2.643705368041992, "heading":2.400500524589353, "intervals":13, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.2163537740707395, "y":2.1863720417022705, "heading":2.400500524589353, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.937044858932495, "y":3.56351637840271, "heading":1.5707963267948966, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":0, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.173567533493042 m", "val":3.173567533493042}, "y":{"exp":"3.878880023956299 m", "val":3.878880023956299}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.6164592504501343 m", "val":1.6164592504501345}, "y":{"exp":"2.643705368041992 m", "val":2.643705368041992}, "heading":{"exp":"2.400500524589353 rad", "val":2.400500524589353}, "intervals":13, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.2163537740707397 m", "val":1.2163537740707395}, "y":{"exp":"2.1863720417022705 m", "val":2.1863720417022705}, "heading":{"exp":"2.400500524589353 rad", "val":2.400500524589353}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.937044858932495 m", "val":2.937044858932495}, "y":{"exp":"3.56351637840271 m", "val":3.56351637840271}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":0, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.84777,1.28242,2.45689], + "samples":[ + {"t":0.0, "x":3.17357, "y":3.87888, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.11215, "ay":-3.62513, "alpha":4.96579, "fx":[-86.54827,-62.34738,-94.37979,-104.54929], "fy":[-67.45617,-90.24474,-55.71509,-33.23338]}, + {"t":0.02649, "x":3.17177, "y":3.87761, "heading":1.5708, "vx":-0.13543, "vy":-0.09604, "omega":0.13156, "ax":-5.11305, "ay":-3.63058, "alpha":4.90647, "fx":[-86.54616,-62.69263,-94.23791,-104.40966], "fy":[-67.44805,-89.99497,-55.93352,-33.64395]}, + {"t":0.05299, "x":3.16639, "y":3.87379, "heading":1.57428, "vx":-0.27089, "vy":-0.19222, "omega":0.26154, "ax":-5.11402, "ay":-3.63617, "alpha":4.84467, "fx":[-86.48463,-63.04933,-94.17934,-104.23869], "fy":[-67.51493,-89.73382,-56.00927,-34.14275]}, + {"t":0.07948, "x":3.15742, "y":3.86742, "heading":1.58121, "vx":-0.40638, "vy":-0.28856, "omega":0.38989, "ax":-5.11503, "ay":-3.64202, "alpha":4.77915, "fx":[-86.36626,-63.42593,-94.19489,-104.03383], "fy":[-67.65293,-89.45487,-55.95844,-34.73277]}, + {"t":0.10597, "x":3.14486, "y":3.8585, "heading":1.59154, "vx":-0.54189, "vy":-0.38504, "omega":0.5165, "ax":-5.11607, "ay":-3.64829, "alpha":4.70848, "fx":[-86.19395,-63.83309,-94.27312,-103.79165], "fy":[-67.85737,-89.14982,-55.7997,-35.41849]}, + {"t":0.13246, "x":3.12871, "y":3.84702, "heading":1.60522, "vx":-0.67743, "vy":-0.4817, "omega":0.64124, "ax":-5.11712, "ay":-3.65514, "alpha":4.63098, "fx":[-85.97114,-64.28395,-94.40029,-103.50765], "fy":[-68.1226,-88.80818,-55.55485,-36.20597]}, + {"t":0.15896, "x":3.10896, "y":3.83297, "heading":1.62221, "vx":-0.81299, "vy":-0.57853, "omega":0.76393, "ax":-5.11815, "ay":-3.66278, "alpha":4.54447, "fx":[-85.70204,-64.79455,-94.56028,-103.17606], "fy":[-68.44175,-88.41675,-55.24965,-37.10316]}, + {"t":0.18545, "x":3.08563, "y":3.81636, "heading":1.64245, "vx":-0.94859, "vy":-0.67557, "omega":0.88433, "ax":-5.11913, "ay":-3.67144, "alpha":4.44611, "fx":[-85.39203,-65.38425,-94.73432,-102.7894], "fy":[-68.80634,-87.95895,-54.9147,-38.12035]}, + {"t":0.21194, "x":3.0587, "y":3.79717, "heading":1.66588, "vx":-1.08421, "vy":-0.77283, "omega":1.00212, "ax":-5.12006, "ay":-3.68138, "alpha":4.33215, "fx":[-85.04817,-66.07636,-94.90063,-102.33799], "fy":[-69.20574,-87.41396,-54.58659,-39.27069]}, + {"t":0.23843, "x":3.02818, "y":3.77541, "heading":1.69243, "vx":-1.21985, "vy":-0.87036, "omega":1.11689, "ax":-5.12092, "ay":-3.69292, "alpha":4.19754, "fx":[-84.67995,-66.89885,-95.03372,-101.80907], "fy":[-69.62643,-86.75539,-54.3093,-40.57126]}, + {"t":0.26493, "x":2.99407, "y":3.75105, "heading":1.72202, "vx":-1.35552, "vy":-0.9682, "omega":1.22809, "ax":-5.1217, "ay":-3.70642, "alpha":4.03556, "fx":[-84.30041,-67.88514,-95.10332,-101.1855], "fy":[-70.0507,-85.94954,-54.13603,-42.04455]}, + {"t":0.29142, "x":2.95636, "y":3.7241, "heading":1.75455, "vx":-1.49121, "vy":-1.06639, "omega":1.335, "ax":-5.12235, "ay":-3.72229, "alpha":3.83722, "fx":[-83.92792,-69.07515,-95.07241,-100.44353], "fy":[-70.45474,-84.95284,-54.13163,-43.72098]}, + {"t":0.31791, "x":2.91506, "y":3.69455, "heading":1.78992, "vx":-1.62691, "vy":-1.16501, "omega":1.43666, "ax":-5.12278, "ay":-3.74099, "alpha":3.59039, "fx":[-83.58889,-70.51637,-94.89402,-99.54906], "fy":[-70.80536,-83.70814,-54.37606,-45.64317]}, + {"t":0.34441, "x":2.87016, "y":3.66237, "heading":1.82798, "vx":-1.76263, "vy":-1.26411, "omega":1.53178, "ax":-5.12272, "ay":-3.76309, "alpha":3.27853, "fx":[-83.32247,-72.26513,-94.50555,-98.45081], "fy":[-71.05423,-82.13918,-54.96961,-47.87337]}, + {"t":0.3709, "x":2.82166, "y":3.62756, "heading":1.86856, "vx":-1.89834, "vy":-1.36381, "omega":1.61864, "ax":-5.12152, "ay":-3.78926, "alpha":2.87848, "fx":[-83.18884,-74.38776,-93.81884,-97.06702], "fy":[-71.12703,-80.1422,-56.04088,-50.50703]}, + {"t":0.39739, "x":2.76957, "y":3.5901, "heading":1.91144, "vx":-2.03402, "vy":-1.4642, "omega":1.6949, "ax":-5.11776, "ay":-3.82035, "alpha":2.35624, "fx":[-83.28506,-76.96145,-92.70208,-95.25782], "fy":[-70.90138,-77.57257,-57.75931,-53.69924]}, + {"t":0.42388, "x":2.71389, "y":3.54997, "heading":1.95635, "vx":-2.16961, "vy":-1.56541, "omega":1.75732, "ax":-5.10824, "ay":-3.85742, "alpha":1.65825, "fx":[-83.77776,-80.07373,-90.94576,-92.76134], "fy":[-70.15703,-74.22325,-60.35473,-57.71952]}, + {"t":0.45038, "x":2.65462, "y":3.50714, "heading":2.0029, "vx":-2.30494, "vy":-1.6676, "omega":1.80125, "ax":-5.0856, "ay":-3.90155, "alpha":0.69006, "fx":[-84.97806,-83.81769,-88.19597,-89.02664], "fy":[-68.44755,-69.78877,-64.14586,-63.07454]}, + {"t":0.47687, "x":2.59177, "y":3.46159, "heading":2.05062, "vx":-2.43967, "vy":-1.77096, "omega":1.81953, "ax":-5.03127, "ay":-3.95193, "alpha":-0.74553, "fx":[-87.53255,-88.27337,-83.8195,-82.6965], "fy":[-64.70466,-63.80637,-69.57152,-70.80225]}, + {"t":0.50336, "x":2.52537, "y":3.41329, "heading":2.09883, "vx":-2.57296, "vy":-1.87566, "omega":1.79978, "ax":-4.88897, "ay":-3.99061, "alpha":-3.17977, "fx":[-92.93579,-93.4403,-76.63947,-69.62444], "fy":[-55.65826,-55.58163,-77.16948,-83.10727]}, + {"t":0.52985, "x":2.45549, "y":3.3622, "heading":2.14651, "vx":-2.70248, "vy":-1.98138, "omega":1.71554, "ax":-4.43199, "ay":-3.83203, "alpha":-8.54048, "fx":[-103.45448,-98.94094,-64.65491,-34.49699], "fy":[-27.34485,-44.40861,-87.16042,-101.81274]}, + {"t":0.55635, "x":2.38234, "y":3.30836, "heading":2.19196, "vx":-2.8199, "vy":-2.0829, "omega":1.48928, "ax":-3.59004, "ay":-3.34267, "alpha":-14.93866, "fx":[-103.86068,-100.37882,-51.87447,11.85144], "fy":[12.9563,-39.80619,-94.85978,-105.72187]}, + {"t":0.58284, "x":2.30637, "y":3.252, "heading":2.23141, "vx":-2.91501, "vy":-2.17146, "omega":1.09352, "ax":-3.1972, "ay":-3.48301, "alpha":-15.32982, "fx":[-100.76443,-96.77586,-43.89344,23.89957], "fy":[8.41372,-45.5227,-97.82504,-102.04602]}, + {"t":0.60933, "x":2.22802, "y":3.19325, "heading":2.26038, "vx":-2.99971, "vy":-2.26373, "omega":0.68739, "ax":-1.98735, "ay":-4.21354, "alpha":-13.34435, "fx":[-73.74359,-83.19161,-23.50188,45.2201], "fy":[-31.69826,-61.59158,-102.11627,-91.27833]}, + {"t":0.63582, "x":2.14786, "y":3.1318, "heading":2.27859, "vx":-3.05236, "vy":-2.37536, "omega":0.33386, "ax":4.09202, "ay":-3.83991, "alpha":2.81522, "fx":[62.08599,77.95675,78.89252,59.48108], "fy":[-75.59115,-59.49971,-52.83343,-73.33867]}, + {"t":0.66232, "x":2.06843, "y":3.06753, "heading":2.28744, "vx":-2.94395, "vy":-2.47709, "omega":0.40844, "ax":5.00872, "ay":0.11652, "alpha":11.33623, "fx":[77.73036,105.90698,82.91057,74.23957], "fy":[-69.55939,-4.20447,63.74941,17.94206]}, + {"t":0.68881, "x":1.99219, "y":3.00194, "heading":2.29826, "vx":-2.81126, "vy":-2.47401, "omega":0.70877, "ax":5.85579, "ay":2.1648, "alpha":2.50944, "fx":[104.85081,102.68058,94.23854,96.65127], "fy":[20.3109,31.31039,51.0354,44.63365]}, + {"t":0.7153, "x":1.91977, "y":2.93716, "heading":2.31704, "vx":-2.65612, "vy":-2.41665, "omega":0.77525, "ax":5.68021, "ay":2.82975, "alpha":-1.40175, "fx":[92.83528,94.23696,100.53541,98.86748], "fy":[55.69676,52.83755,39.76317,44.23546]}, + {"t":0.7418, "x":1.85139, "y":2.87413, "heading":2.33757, "vx":-2.50564, "vy":-2.34169, "omega":0.73811, "ax":5.52776, "ay":3.06933, "alpha":-3.06491, "fx":[85.73118,87.75734,103.23995,99.3742], "fy":[67.00542,63.72665,33.64139,44.45994]}, + {"t":0.76829, "x":1.78695, "y":2.81317, "heading":2.35713, "vx":-2.35919, "vy":-2.26037, "omega":0.65692, "ax":5.42437, "ay":3.18893, "alpha":-3.99907, "fx":[81.58196,83.31383,104.68573,99.48633], "fy":[72.40955,69.84944,29.85702,44.85501]}, + {"t":0.79478, "x":1.72635, "y":2.7544, "heading":2.37453, "vx":-2.21549, "vy":-2.17589, "omega":0.55097, "ax":5.35158, "ay":3.26027, "alpha":-4.59632, "fx":[78.85467,80.2286,105.56848,99.46386], "fy":[75.60253,73.64152,27.30271,45.278]}, + {"t":0.82127, "x":1.66954, "y":2.6979, "heading":2.38913, "vx":-2.07371, "vy":-2.08952, "omega":0.4292, "ax":5.29798, "ay":3.30768, "alpha":-5.00961, "fx":[76.91525,78.00147,106.15559,99.3965], "fy":[77.72363,76.18517,25.47441,45.66757]}, + {"t":0.84777, "x":1.61646, "y":2.64371, "heading":2.4005, "vx":-1.93335, "vy":-2.00189, "omega":0.29648, "ax":5.22535, "ay":3.58659, "alpha":-3.68598, "fx":[77.89238,79.39135,101.9207,96.32267], "fy":[76.96045,75.1934,39.75517,52.11856]}, + {"t":0.8812, "x":1.55474, "y":2.57878, "heading":2.41041, "vx":-1.75864, "vy":-1.88197, "omega":0.17324, "ax":5.01898, "ay":3.94838, "alpha":-2.69491, "fx":[76.55356,77.45133,95.7165,91.76444], "fy":[78.3499,77.33136,53.12276,59.83952]}, + {"t":0.91464, "x":1.49874, "y":2.51806, "heading":2.41621, "vx":-1.59083, "vy":-1.74995, "omega":0.08314, "ax":4.83916, "ay":4.2083, "alpha":-1.95358, "fx":[75.52364,76.04551,90.07927,87.60229], "fy":[79.38876,78.80829,62.30166,65.82903]}, + {"t":0.94807, "x":1.44826, "y":2.4619, "heading":2.41899, "vx":-1.42903, "vy":-1.60925, "omega":0.01782, "ax":4.6861, "ay":4.40101, "alpha":-1.3839, "fx":[74.70427,74.98514,85.27193,83.87557], "fy":[80.19716,79.88485,68.80374,70.55361]}, + {"t":0.98151, "x":1.4031, "y":2.41056, "heading":2.41958, "vx":-1.27235, "vy":-1.4621, "omega":-0.02845, "ax":4.55632, "ay":4.5482, "alpha":-0.93386, "fx":[74.03268,74.1625,81.24821,80.56352], "fy":[80.84797,80.69914,73.56294,74.34393]}, + {"t":1.01494, "x":1.3631, "y":2.36421, "heading":2.41863, "vx":-1.12001, "vy":-1.31003, "omega":-0.05967, "ax":4.44584, "ay":4.66358, "alpha":-0.56962, "fx":[73.46785,73.51077,77.88694,77.62411], "fy":[81.38705,81.33198,77.15218,77.43364]}, + {"t":1.04838, "x":1.32814, "y":2.32302, "heading":2.41663, "vx":-0.97137, "vy":-1.1541, "omega":-0.07872, "ax":4.35112, "ay":4.75608, "alpha":-0.26873, "fx":[72.98243,72.98583,75.06585,75.01117], "fy":[81.84424,81.83422,79.93064,79.9891]}, + {"t":1.08181, "x":1.2981, "y":2.28709, "heading":2.414, "vx":-0.82589, "vy":-0.99508, "omega":-0.0877, "ax":4.26928, "ay":4.83165, "alpha":-0.01591, "fx":[72.55785,72.55709,72.68075,72.68133], "fy":[82.23944,82.23973,82.13046,82.13033]}, + {"t":1.11525, "x":1.27287, "y":2.25652, "heading":2.41107, "vx":-0.68314, "vy":-0.83354, "omega":-0.08824, "ax":4.19801, "ay":4.89441, "alpha":0.19958, "fx":[72.18139,72.20247,70.64756,70.5964], "fy":[82.58616,82.57212,83.90642,83.94517]}, + {"t":1.14868, "x":1.25237, "y":2.23139, "heading":2.40812, "vx":-0.54278, "vy":-0.66989, "omega":-0.08156, "ax":4.13548, "ay":4.94726, "alpha":0.38549, "fx":[71.84425,71.90555,68.89957,68.7237], "fy":[82.89372,82.84842,85.36488,85.49895]}, + {"t":1.18212, "x":1.23654, "y":2.21175, "heading":2.40539, "vx":-0.40451, "vy":-0.50448, "omega":-0.06867, "ax":4.08022, "ay":4.99232, "alpha":0.54754, "fx":[71.54035,71.65377,67.38397,67.03567], "fy":[83.1686,83.08133,86.5809,86.84095]}, + {"t":1.21555, "x":1.22529, "y":2.19768, "heading":2.4031, "vx":-0.26809, "vy":-0.33756, "omega":-0.05037, "ax":4.03109, "ay":5.03115, "alpha":0.69005, "fx":[71.26551,71.4373,66.05871,65.50919], "fy":[83.41531,83.28055,87.6088,88.00894]}, + {"t":1.24899, "x":1.21858, "y":2.1892, "heading":2.40141, "vx":-0.13331, "vy":-0.16935, "omega":-0.0273, "ax":3.98714, "ay":5.06492, "alpha":0.81637, "fx":[71.01692,71.24833,64.89012,64.12488], "fy":[83.63698,83.45366,88.48875,89.03221]}, + {"t":1.28242, "x":1.21635, "y":2.18637, "heading":2.4005, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.99082, "ay":4.00267, "alpha":-2.73922, "fx":[75.98676,76.51398,95.47907,91.58983], "fy":[79.18484,78.6284,54.05686,60.4672]}, + {"t":1.31801, "x":1.21951, "y":2.18891, "heading":2.4005, "vx":0.17762, "vy":0.14245, "omega":-0.09749, "ax":4.99148, "ay":4.0027, "alpha":-2.71212, "fx":[76.07288,76.61853,95.38308,91.53999], "fy":[79.09109,78.51271,54.20687,60.52862]}, + {"t":1.3536, "x":1.229, "y":2.19651, "heading":2.39703, "vx":0.35527, "vy":0.28491, "omega":-0.19401, "ax":4.99222, "ay":4.0027, "alpha":-2.68161, "fx":[76.20113,76.69703,95.25654,91.51045], "fy":[78.95493,78.42037,54.40686,60.55711]}, + {"t":1.38919, "x":1.2448, "y":2.20919, "heading":2.39013, "vx":0.53294, "vy":0.42737, "omega":-0.28945, "ax":4.99307, "ay":4.00267, "alpha":-2.64672, "fx":[76.37312,76.75537,95.09622,91.49811], "fy":[78.77401,78.34529,54.66104,60.55695]}, + {"t":1.42478, "x":1.26693, "y":2.22693, "heading":2.37982, "vx":0.71064, "vy":0.56982, "omega":-0.38365, "ax":4.99404, "ay":4.00262, "alpha":-2.60615, "fx":[76.59118,76.80154,94.89752,91.49872], "fy":[78.54492,78.27919,54.97543,60.53384]}, + {"t":1.46037, "x":1.29539, "y":2.24975, "heading":2.36617, "vx":0.88838, "vy":0.71227, "omega":-0.4764, "ax":4.99517, "ay":4.00253, "alpha":-2.55811, "fx":[76.8587,76.84621,94.65409,91.50652], "fy":[78.26282,78.21082,55.35823,60.49553]}, + {"t":1.49596, "x":1.33017, "y":2.27763, "heading":2.34922, "vx":1.06616, "vy":0.85472, "omega":-0.56744, "ax":4.99648, "ay":4.0024, "alpha":-2.50014, "fx":[77.18046,76.9038,94.35725,91.51347], "fy":[77.92086,78.12489,55.82051,60.45278]}, + {"t":1.53155, "x":1.37128, "y":2.31059, "heading":2.32902, "vx":1.24398, "vy":0.99717, "omega":-0.65642, "ax":4.99803, "ay":4.00224, "alpha":-2.42871, "fx":[77.56337,76.99418,93.99491,91.50807], "fy":[77.50914,78.00011,56.3773,60.42096]}, + {"t":1.56714, "x":1.41872, "y":2.34861, "heading":2.30566, "vx":1.42186, "vy":1.13961, "omega":-0.74286, "ax":4.99988, "ay":4.00199, "alpha":-2.33861, "fx":[78.0178,77.14557,93.54977,91.47322], "fy":[77.01276,77.80579,57.0495,60.42293]}, + {"t":1.60273, "x":1.47249, "y":2.3917, "heading":2.27922, "vx":1.59981, "vy":1.28204, "omega":-0.82609, "ax":5.00211, "ay":4.00162, "alpha":-2.22168, "fx":[78.56015,77.39985,92.99594,91.38197], "fy":[76.40811,77.4954,57.86752,60.49436]}, + {"t":1.63832, "x":1.53259, "y":2.43986, "heading":2.24982, "vx":1.77783, "vy":1.42446, "omega":-0.90516, "ax":5.00482, "ay":4.00097, "alpha":-2.06441, "fx":[79.21824,77.82299,92.29212,91.18875], "fy":[75.65484,76.99347,58.87841,60.69472]}, + {"t":1.67391, "x":1.59903, "y":2.49309, "heading":2.2176, "vx":1.95595, "vy":1.56685, "omega":-0.97863, "ax":5.00811, "ay":3.99972, "alpha":-1.8423, "fx":[80.0439,78.52726,91.3666,90.80853], "fy":[74.67698,76.16605,60.16129,61.13224]}, + {"t":1.7095, "x":1.67182, "y":2.55139, "heading":2.18278, "vx":2.13419, "vy":1.7092, "omega":-1.0442, "ax":5.012, "ay":3.99697, "alpha":-1.5055, "fx":[81.1466,79.72461,90.07964,90.05966], "fy":[73.3106,74.74497,61.86454,62.02939]}, + {"t":1.74509, "x":1.75095, "y":2.61475, "heading":2.14561, "vx":2.31257, "vy":1.85145, "omega":-1.09778, "ax":5.01562, "ay":3.98978, "alpha":-0.93309, "fx":[82.80431,81.87585,88.11136,88.46584], "fy":[71.12235,72.09295,64.31076,63.93381]}, + {"t":1.78068, "x":1.83643, "y":2.68317, "heading":2.10654, "vx":2.49107, "vy":1.99345, "omega":-1.13099, "ax":5.01107, "ay":3.96442, "alpha":0.27107, "fx":[85.97708,86.20579,84.52129,84.24321], "fy":[66.4745,66.22623,68.36909,68.66508]}, + {"t":1.81627, "x":1.92826, "y":2.75663, "heading":2.06629, "vx":2.66942, "vy":2.13454, "omega":-1.12134, "ax":4.85347, "ay":3.75102, "alpha":4.84072, "fx":[96.85671,96.84854,74.89676,61.62274], "fy":[43.88088,46.86151,77.38325,87.08931]}, + {"t":1.85186, "x":2.02634, "y":2.83497, "heading":2.02638, "vx":2.84215, "vy":2.26804, "omega":-0.94906, "ax":-0.07962, "ay":-0.11478, "alpha":0.08581, "fx":[-1.45624,-1.05623,-1.25244,-1.65246], "fy":[-2.25027,-2.05451,-1.65441,-1.85025]}, + {"t":1.88745, "x":2.12744, "y":2.91562, "heading":1.99261, "vx":2.83932, "vy":2.26395, "omega":-0.94601, "ax":-4.80123, "ay":-3.68671, "alpha":-5.86513, "fx":[-98.18136,-99.06413,-74.70621,-54.71847], "fy":[-39.75872,-41.93816,-77.63152,-91.51144]}, + {"t":1.92304, "x":2.22545, "y":2.99386, "heading":1.95894, "vx":2.66844, "vy":2.13274, "omega":-1.15475, "ax":-5.00971, "ay":-3.9628, "alpha":-0.48454, "fx":[-86.28338,-87.09872,-84.22619,-83.24657], "fy":[-66.02264,-65.0313,-68.73314,-69.83754]}, + {"t":1.95863, "x":2.31725, "y":3.06725, "heading":1.91784, "vx":2.49015, "vy":1.99171, "omega":-1.17199, "ax":-5.01583, "ay":-3.98973, "alpha":0.89473, "fx":[-83.68547,-81.52302,-87.23184,-88.83119], "fy":[-70.07944,-72.49771,-65.47975,-63.3997]}, + {"t":1.99422, "x":2.40269, "y":3.13561, "heading":1.87613, "vx":2.31164, "vy":1.84971, "omega":-1.14015, "ax":-5.01138, "ay":-3.99617, "alpha":1.53951, "fx":[-82.8479,-78.401,-88.46044,-91.25889], "fy":[-71.39017,-76.14963,-64.12989,-60.22523]}, + {"t":2.02981, "x":2.48179, "y":3.19891, "heading":1.83555, "vx":2.13328, "vy":1.70749, "omega":-1.08536, "ax":-5.00679, "ay":-3.99801, "alpha":1.91108, "fx":[-82.60951,-76.40736,-88.96727,-92.67203], "fy":[-71.84061,-78.31637,-63.62205,-58.24131]}, + {"t":2.0654, "x":2.55454, "y":3.25715, "heading":1.79692, "vx":1.95509, "vy":1.5652, "omega":-1.01734, "ax":-5.00307, "ay":-3.99848, "alpha":2.15056, "fx":[-82.6318,-75.02918,-89.11759,-93.62467], "fy":[-71.92463,-79.7461,-63.54469,-56.8367]}, + {"t":2.10099, "x":2.62096, "y":3.31032, "heading":1.76072, "vx":1.77703, "vy":1.4229, "omega":-0.9408, "ax":-5.00014, "ay":-3.9985, "alpha":2.3164, "fx":[-82.77891,-74.02776,-89.0738,-94.32316], "fy":[-71.83059,-80.75255,-63.70211,-55.7682]}, + {"t":2.13658, "x":2.68103, "y":3.35843, "heading":1.72723, "vx":1.59908, "vy":1.28059, "omega":-0.85836, "ax":-4.99779, "ay":-3.99839, "alpha":2.43732, "fx":[-82.98515,-73.27567,-88.92105,-94.86233], "fy":[-71.64718,-81.49169,-63.98755,-54.91933]}, + {"t":2.17217, "x":2.73478, "y":3.40147, "heading":1.69668, "vx":1.42121, "vy":1.13829, "omega":-0.77162, "ax":-4.99588, "ay":-3.99825, "alpha":2.52912, "fx":[-83.21469,-72.69745,-88.70963,-95.29237], "fy":[-71.42234,-82.05091,-64.3368,-54.22655]}, + {"t":2.20776, "x":2.7822, "y":3.43945, "heading":1.66922, "vx":1.2434, "vy":0.99599, "omega":-0.68161, "ax":-4.99429, "ay":-3.99813, "alpha":2.60115, "fx":[-83.44625,-72.24469,-88.47199,-95.64277], "fy":[-71.18467,-82.48375,-64.70847,-53.65159]}, + {"t":2.24335, "x":2.82329, "y":3.47237, "heading":1.64496, "vx":1.06566, "vy":0.8537, "omega":-0.58903, "ax":-4.99293, "ay":-3.99804, "alpha":2.65929, "fx":[-83.66637,-71.88442,-88.23045,-95.93225], "fy":[-70.95249,-82.82531,-65.07451,-53.16952]}, + {"t":2.27894, "x":2.85805, "y":3.50022, "heading":1.624, "vx":0.88796, "vy":0.71141, "omega":-0.49439, "ax":-4.99176, "ay":-3.99796, "alpha":2.70736, "fx":[-83.86617,-71.59306,-88.00116,-96.1735], "fy":[-70.73823,-83.09981,-65.4152,-52.7631]}, + {"t":2.31453, "x":2.88649, "y":3.52301, "heading":1.60641, "vx":0.7103, "vy":0.56912, "omega":-0.39803, "ax":-4.99074, "ay":-3.99788, "alpha":2.74792, "fx":[-84.03951,-71.35321,-87.79618,-96.37547], "fy":[-70.55069,-83.32467,-65.71629,-52.4198]}, + {"t":2.35012, "x":2.90861, "y":3.54073, "heading":1.59224, "vx":0.53268, "vy":0.42684, "omega":-0.30024, "ax":-4.98984, "ay":-3.99781, "alpha":2.78277, "fx":[-84.18203,-71.15172,-87.62472,-96.54473], "fy":[-70.3963,-83.51272,-65.96724,-52.1303]}, + {"t":2.38571, "x":2.92441, "y":3.55339, "heading":1.58155, "vx":0.35509, "vy":0.28455, "omega":-0.2012, "ax":-4.98905, "ay":-3.99773, "alpha":2.81317, "fx":[-84.29053,-70.97853,-87.49395,-96.68616], "fy":[-70.27988,-83.67359,-66.16013,-51.88751]}, + {"t":2.4213, "x":2.93389, "y":3.56098, "heading":1.57439, "vx":0.17753, "vy":0.14228, "omega":-0.10108, "ax":-4.98835, "ay":-3.99764, "alpha":2.84003, "fx":[-84.36258,-70.82592,-87.40946,-96.80343], "fy":[-70.20515,-83.81455,-66.28886,-51.68605]}, + {"t":2.45689, "x":2.93704, "y":3.56352, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_3.traj b/src/main/deploy/choreo/E_RIGHT_PATH_3.traj new file mode 100644 index 00000000..7621730b --- /dev/null +++ b/src/main/deploy/choreo/E_RIGHT_PATH_3.traj @@ -0,0 +1,144 @@ +{ + "name":"E_RIGHT_PATH_3", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.6728932857513423, "y":2.9787795543670654, "heading":2.618314122167914, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.9501848220825195, "y":2.551724433898926, "heading":0.0, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":1.8529818058013916, "y":3.307283401489258, "heading":0.7217177742033876, "intervals":16, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.2258362770080566, "y":4.026000022888184, "heading":0.7217177742033876, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.8976240158081055, "y":3.8394596576690674, "heading":1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":3, "to":3, "data":{"type":"MaxAngularVelocity", "props":{"max":0.0}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.6728932857513428 m", "val":3.6728932857513423}, "y":{"exp":"2.9787795543670654 m", "val":2.9787795543670654}, "heading":{"exp":"2.6183141221679134 rad", "val":2.618314122167914}, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.9501848220825195 m", "val":2.9501848220825195}, "y":{"exp":"2.551724433898926 m", "val":2.551724433898926}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"1.8529818058013916 m", "val":1.8529818058013916}, "y":{"exp":"3.307283401489258 m", "val":3.307283401489258}, "heading":{"exp":"0.7217177742033876 rad", "val":0.7217177742033876}, "intervals":16, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.2258362770080566 m", "val":1.2258362770080566}, "y":{"exp":"4.026000022888184 m", "val":4.026000022888184}, "heading":{"exp":"0.7217177742033876 rad", "val":0.7217177742033876}, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.8976240158081055 m", "val":2.8976240158081055}, "y":{"exp":"3.8394596576690674 m", "val":3.8394596576690674}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":3, "to":3, "data":{"type":"MaxAngularVelocity", "props":{"max":{"exp":"0 rad / s", "val":0.0}}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.59084,1.06256,1.6068,2.63463], + "samples":[ + {"t":0.0, "x":3.67289, "y":2.97878, "heading":2.61831, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.12946, "ay":-5.50084, "alpha":-4.10614, "fx":[-73.85816,-68.384,-39.00244,-31.68043], "fy":[-81.01363,-85.77522,-102.5311,-104.95119]}, + {"t":0.02363, "x":3.67202, "y":2.97724, "heading":2.61831, "vx":-0.07396, "vy":-0.13001, "omega":-0.09704, "ax":-3.24525, "ay":-5.42239, "alpha":-4.25527, "fx":[-76.61852,-70.28541,-40.42693,-33.472], "fy":[-78.3845,-84.21072,-101.96562,-104.37271]}, + {"t":0.04727, "x":3.66937, "y":2.97266, "heading":2.61602, "vx":-0.15066, "vy":-0.25816, "omega":-0.19761, "ax":-3.37657, "ay":-5.32852, "alpha":-4.42489, "fx":[-79.66304,-72.43791,-42.09798,-35.53886], "fy":[-75.26014,-82.35084,-101.2731,-103.66248]}, + {"t":0.0709, "x":3.66486, "y":2.96507, "heading":2.61135, "vx":-0.23046, "vy":-0.38409, "omega":-0.30219, "ax":-3.52633, "ay":-5.21477, "alpha":-4.61881, "fx":[-83.02767,-74.87686,-44.06434,-37.95881], "fy":[-71.49706,-80.12145,-100.41684,-102.77143]}, + {"t":0.09453, "x":3.65843, "y":2.95453, "heading":2.60421, "vx":-0.3138, "vy":-0.50733, "omega":-0.41135, "ax":-3.69803, "ay":-5.075, "alpha":-4.84123, "fx":[-86.74018,-77.64102,-46.38874,-40.83984], "fy":[-66.9027,-77.42433,-99.34532,-101.62485]}, + {"t":0.11817, "x":3.64998, "y":2.94113, "heading":2.59449, "vx":-0.4012, "vy":-0.62727, "omega":-0.52576, "ax":-3.89576, "ay":-4.90068, "alpha":-5.09613, "fx":[-90.8053,-80.77029,-49.15259,-44.33468], "fy":[-61.21926,-74.12823,-97.98454,-100.10461]}, + {"t":0.1418, "x":3.63941, "y":2.92493, "heading":2.58206, "vx":-0.49327, "vy":-0.7431, "omega":-0.6462, "ax":-4.12414, "ay":-4.67976, "alpha":-5.38569, "fx":[-95.17595,-84.30011,-52.46223,-48.6632], "fy":[-54.10722,-70.05665,-96.22561,-98.01586]}, + {"t":0.16544, "x":3.6266, "y":2.90606, "heading":2.56679, "vx":-0.59074, "vy":-0.8537, "omega":-0.77349, "ax":-4.38798, "ay":-4.39507, "alpha":-5.70664, "fx":[-99.70131,-88.24963,-56.45653,-54.14568], "fy":[-45.13796,-64.97229,-93.90398,-95.02112]}, + {"t":0.18907, "x":3.61141, "y":2.88466, "heading":2.54851, "vx":-0.69444, "vy":-0.95757, "omega":-0.90836, "ax":-4.69144, "ay":-4.02194, "alpha":-6.04252, "fx":[-104.04289,-92.59791,-61.31438,-61.24473], "fy":[-33.82097,-58.55978,-90.76407,-90.50363]}, + {"t":0.2127, "x":3.59369, "y":2.86091, "heading":2.52704, "vx":-0.80532, "vy":-1.05262, "omega":-1.05116, "ax":-5.036, "ay":-3.52454, "alpha":-6.3502, "fx":[-107.56757,-97.23963,-67.25636,-70.58036], "fy":[-19.71723,-50.41373,-86.39827,-83.27618]}, + {"t":0.23634, "x":3.57325, "y":2.83504, "heading":2.5022, "vx":-0.92434, "vy":-1.13592, "omega":-1.20124, "ax":-5.41516, "ay":-2.84973, "alpha":-6.54816, "fx":[-109.28776,-101.91046,-74.52105,-82.72231], "fy":[-2.7056,-40.05192,-80.14341,-70.9914]}, + {"t":0.25997, "x":3.5499, "y":2.8074, "heading":2.47381, "vx":-1.05232, "vy":-1.20327, "omega":-1.356, "ax":-5.79582, "ay":-1.92052, "alpha":-6.55505, "fx":[-108.02331,-106.08288,-83.26014,-96.9744], "fy":[16.6139,-26.99613,-70.92051,-49.36752]}, + {"t":0.2836, "x":3.52341, "y":2.77843, "heading":2.44176, "vx":-1.18929, "vy":-1.24866, "omega":-1.51092, "ax":-6.06706, "ay":-0.66489, "alpha":-6.47633, "fx":[-102.94558,-108.87866,-93.21029,-107.76118], "fy":[36.67484,-10.98294,-57.06863,-13.86169]}, + {"t":0.30724, "x":3.49361, "y":2.74873, "heading":2.40605, "vx":-1.33268, "vy":-1.26437, "omega":-1.66398, "ax":-6.03643, "ay":0.8298, "alpha":-6.61705, "fx":[-94.23942,-109.13538,-102.91779,-104.41924], "fy":[55.35388,7.67613,-36.53796,29.96683]}, + {"t":0.33087, "x":3.46042, "y":2.71908, "heading":2.36673, "vx":-1.47534, "vy":-1.24476, "omega":-1.82036, "ax":-5.66118, "ay":2.27882, "alpha":-6.67118, "fx":[-83.1652,-105.80909,-108.81868,-87.38717], "fy":[70.95611,27.7646,-8.46863,64.79603]}, + {"t":0.35451, "x":3.42397, "y":2.6903, "heading":2.3237, "vx":-1.60914, "vy":-1.1909, "omega":-1.97803, "ax":-5.0704, "ay":3.50775, "alpha":-6.07744, "fx":[-71.35707,-98.63749,-106.53265,-68.45708], "fy":[82.87209,47.30325,23.68734,84.80065]}, + {"t":0.37814, "x":3.38453, "y":2.66313, "heading":2.27696, "vx":-1.72897, "vy":-1.108, "omega":-2.12166, "ax":-4.37452, "ay":4.46169, "alpha":-5.04426, "fx":[-60.08922,-88.48241,-95.67878,-53.38682], "fy":[91.42256,64.35583,52.59081,95.19874]}, + {"t":0.40177, "x":3.34244, "y":2.63819, "heading":2.22681, "vx":-1.83236, "vy":-1.00256, "omega":-2.24088, "ax":-3.67527, "ay":5.13657, "alpha":-4.0107, "fx":[-50.04123,-76.889,-80.80698,-42.32375], "fy":[97.33264,77.87831,73.53602,100.73911]}, + {"t":0.42541, "x":3.29811, "y":2.61593, "heading":2.17385, "vx":-1.91922, "vy":-0.88116, "omega":-2.33566, "ax":-3.04546, "ay":5.58563, "alpha":-3.15449, "fx":[-41.42542,-65.29235,-66.28476,-34.20693], "fy":[101.34074,87.86931,86.95699,103.87267]}, + {"t":0.44904, "x":3.2519, "y":2.59667, "heading":2.11865, "vx":-1.99119, "vy":-0.74915, "omega":-2.41022, "ax":-2.50996, "ay":5.87827, "alpha":-2.4774, "fx":[-34.19199,-54.5822,-53.88405,-28.1165], "fy":[104.03971,94.93212,95.22272,105.75591]}, + {"t":0.47267, "x":3.20414, "y":2.58061, "heading":2.06169, "vx":-2.05051, "vy":-0.61023, "omega":-2.46877, "ax":-2.06482, "ay":6.06943, "alpha":-1.94076, "fx":[-28.18121,-45.1266,-43.76107,-23.41899], "fy":[105.8566,99.8081,100.34294,106.94972]}, + {"t":0.49631, "x":3.15511, "y":2.56788, "heading":2.00334, "vx":-2.09931, "vy":-0.46678, "omega":-2.51463, "ax":-1.6964, "ay":6.19573, "alpha":-1.50943, "fx":[-23.20701,-36.96975,-35.54914,-19.69536], "fy":[107.08345,103.13758,103.58761,107.74142]}, + {"t":0.51994, "x":3.10502, "y":2.55858, "heading":1.94391, "vx":-2.1394, "vy":-0.32035, "omega":-2.55031, "ax":-1.39023, "ay":6.28021, "alpha":-1.15743, "fx":[-19.09421,-30.00456,-28.82426,-16.66645], "fy":[107.91552,105.40008,105.69627,108.2867]}, + {"t":0.54357, "x":3.05407, "y":2.55276, "heading":1.88364, "vx":-2.17226, "vy":-0.17193, "omega":-2.57766, "ax":-1.13379, "ay":6.33734, "alpha":-0.86611, "fx":[-15.69113,-24.07436,-23.23398,-14.14247], "fy":[108.48247,106.93233,107.09612,108.67429]}, + {"t":0.56721, "x":3.00241, "y":2.55047, "heading":1.82272, "vx":-2.19905, "vy":-0.02215, "omega":-2.59813, "ax":-0.91705, "ay":6.37622, "alpha":-0.62193, "fx":[-12.87127,-19.0212,-18.51138,-11.99149], "fy":[108.87049,107.96453,108.03879,108.95697]}, + {"t":0.59084, "x":2.95018, "y":2.55172, "heading":1.76132, "vx":-2.22073, "vy":0.12854, "omega":-2.61283, "ax":-0.8133, "ay":6.38602, "alpha":-0.49008, "fx":[-11.54342,-16.44728,-16.24057,-11.10473], "fy":[108.92922,108.29641,108.31216,108.95959]}, + {"t":0.60769, "x":2.91266, "y":2.5548, "heading":1.7173, "vx":-2.23443, "vy":0.23612, "omega":-2.62109, "ax":-0.79833, "ay":6.38771, "alpha":-0.38685, "fx":[-11.6749,-15.57348,-15.55624,-11.51276], "fy":[108.8991,108.40999,108.39977,108.90375]}, + {"t":0.62454, "x":2.8749, "y":2.55968, "heading":1.67314, "vx":-2.24788, "vy":0.34374, "omega":-2.6276, "ax":-0.782, "ay":6.38934, "alpha":-0.27443, "fx":[-11.88385,-14.66569,-14.75557,-11.90111], "fy":[108.85888,108.51929,108.49771,108.84761]}, + {"t":0.64138, "x":2.83692, "y":2.56638, "heading":1.62888, "vx":-2.26105, "vy":0.45138, "omega":-2.63223, "ax":-0.76412, "ay":6.39087, "alpha":-0.15152, "fx":[-12.17886,-13.72184,-13.8269,-12.26204], "fy":[108.80693,108.62345,108.60471,108.79217]}, + {"t":0.65823, "x":2.79872, "y":2.57489, "heading":1.58453, "vx":-2.27393, "vy":0.55904, "omega":-2.63478, "ax":-0.74446, "ay":6.39223, "alpha":-0.01658, "fx":[-12.56971,-12.7391,-12.75655,-12.5869], "fy":[108.74118,108.72153,108.71886,108.73857]}, + {"t":0.67508, "x":2.76031, "y":2.58521, "heading":1.54014, "vx":-2.28647, "vy":0.66673, "omega":-2.63506, "ax":-0.72276, "ay":6.39336, "alpha":0.13229, "fx":[-13.06756,-11.71372,-11.52824,-12.86611], "fy":[108.65893,108.81244,108.83744,108.68814]}, + {"t":0.69192, "x":2.72168, "y":2.59735, "heading":1.49575, "vx":-2.29864, "vy":0.77444, "omega":-2.63283, "ax":-0.69868, "ay":6.39415, "alpha":0.29739, "fx":[-13.68532,-10.64061,-10.12242,-13.08897], "fy":[108.55671,108.89495,108.95662,108.64236]}, + {"t":0.70877, "x":2.68286, "y":2.61131, "heading":1.4514, "vx":-2.31042, "vy":0.88216, "omega":-2.62782, "ax":-0.67182, "ay":6.39446, "alpha":0.48155, "fx":[-14.43803,-9.51292,-8.51538,-13.24356], "fy":[108.43001,108.96756,109.07105,108.60283]}, + {"t":0.72562, "x":2.64384, "y":2.62708, "heading":1.40713, "vx":-2.32173, "vy":0.98989, "omega":-2.61971, "ax":-0.64168, "ay":6.39408, "alpha":0.68822, "fx":[-15.34346,-8.32134,-6.67808,-13.31648], "fy":[108.27289,109.02837,109.17318,108.57126]}, + {"t":0.74246, "x":2.60463, "y":2.64466, "heading":1.36299, "vx":-2.33254, "vy":1.09761, "omega":-2.60811, "ax":-0.60764, "ay":6.39273, "alpha":0.92168, "fx":[-16.42279,-7.05306,-4.57462,-13.29262], "fy":[108.07755,109.07491,109.25244,108.54937]}, + {"t":0.75931, "x":2.56525, "y":2.66406, "heading":1.31905, "vx":-2.34278, "vy":1.20531, "omega":-2.59258, "ax":-0.56889, "ay":6.39002, "alpha":1.18724, "fx":[-17.7016,-5.69023,-2.1603,-13.15478], "fy":[107.83358,109.10382,109.29372,108.53883]}, + {"t":0.77616, "x":2.5257, "y":2.68527, "heading":1.27538, "vx":-2.35236, "vy":1.31296, "omega":-2.57258, "ax":-0.52442, "ay":6.38538, "alpha":1.49155, "fx":[-19.21117,-4.2076,0.62101,-12.88322], "fy":[107.52697,109.11026,109.27535,108.54111]}, + {"t":0.79301, "x":2.486, "y":2.7083, "heading":1.23204, "vx":-2.3612, "vy":1.42053, "omega":-2.54746, "ax":-0.47287, "ay":6.37795, "alpha":1.84297, "fx":[-20.99012,-2.56865,3.84007,-12.45507], "fy":[107.1386,109.08693,109.16574,108.55726]}, + {"t":0.80985, "x":2.44615, "y":2.73313, "heading":1.18912, "vx":-2.36917, "vy":1.52798, "omega":-2.51641, "ax":-0.41246, "ay":6.36651, "alpha":2.25217, "fx":[-23.08666,-0.71928,7.58616,-11.84357], "fy":[106.64202,109.02237,108.91831,108.58764]}, + {"t":0.8267, "x":2.40618, "y":2.75978, "heading":1.14673, "vx":-2.37611, "vy":1.63524, "omega":-2.47846, "ax":-0.34075, "ay":6.3492, "alpha":2.73279, "fx":[-25.56124,1.42309,11.97126,-11.01723], "fy":[106.00015,108.8974,108.46355,108.63141]}, + {"t":0.84355, "x":2.3661, "y":2.78823, "heading":1.10497, "vx":-2.38186, "vy":1.7422, "omega":-2.43243, "ax":-0.25436, "ay":6.32317, "alpha":3.30233, "fx":[-28.48929,3.98907,17.13278,-9.93893], "fy":[105.16032,108.67805,107.69691,108.68584]}, + {"t":0.86039, "x":2.32594, "y":2.81848, "heading":1.06399, "vx":-2.38614, "vy":1.84873, "omega":-2.37679, "ax":-0.1485, "ay":6.28397, "alpha":3.98318, "fx":[-31.96213,7.19347,23.23007,-8.56543], "fy":[104.04747,108.29983,106.46147,108.7452]}, + {"t":0.87724, "x":2.28572, "y":2.85052, "heading":1.02395, "vx":-2.38864, "vy":1.95459, "omega":-2.30969, "ax":-0.01623, "ay":6.22459, "alpha":4.80322, "fx":[-36.07965,11.4031,30.42096,-6.84898], "fy":[102.55682,107.63034,104.52785,108.79898]}, + {"t":0.89409, "x":2.24548, "y":2.88433, "heading":0.98504, "vx":-2.38892, "vy":2.05946, "omega":-2.22877, "ax":0.15243, "ay":6.13407, "alpha":5.7938, "fx":[-40.91037,17.24934,38.77862,-4.74632], "fy":[100.55699,106.37672,101.59217,108.82927]}, + {"t":0.91093, "x":2.20525, "y":2.91989, "heading":0.94749, "vx":-2.38635, "vy":2.1628, "omega":-2.13116, "ax":0.36888, "ay":5.99731, "alpha":6.97253, "fx":[-46.32724,25.65348,48.02945,-2.25729], "fy":[97.96115,103.88907,97.39259,108.80739]}, + {"t":0.92778, "x":2.1651, "y":2.95718, "heading":0.91159, "vx":-2.38013, "vy":2.26384, "omega":-2.01369, "ax":0.62042, "ay":5.81208, "alpha":8.22908, "fx":[-51.42178,36.39428,56.8108,0.42921], "fy":[95.10304,99.32981,92.32103,108.69371]}, + {"t":0.94463, "x":2.12509, "y":2.99614, "heading":0.87766, "vx":-2.36968, "vy":2.36175, "omega":-1.87506, "ax":0.80786, "ay":5.64878, "alpha":9.08827, "fx":[-54.17867,43.80067,62.5451,2.79846], "fy":[93.18755,94.4893,88.20274,108.4572]}, + {"t":0.96147, "x":2.08528, "y":3.03673, "heading":0.84607, "vx":-2.35607, "vy":2.45692, "omega":-1.72195, "ax":0.907, "ay":5.53769, "alpha":9.49012, "fx":[-54.81643,45.96683,65.74914,4.81152], "fy":[92.27723,91.10727,85.31752,108.07625]}, + {"t":0.97832, "x":2.04572, "y":3.07891, "heading":0.81706, "vx":-2.34079, "vy":2.55021, "omega":-1.56207, "ax":0.97362, "ay":5.43097, "alpha":9.73659, "fx":[-54.34759,45.92992,67.90881,6.75288], "fy":[91.68538,87.6307,82.73843,107.46265]}, + {"t":0.99517, "x":2.00642, "y":3.12265, "heading":0.79075, "vx":-2.32439, "vy":2.6417, "omega":-1.39804, "ax":1.05155, "ay":5.26837, "alpha":10.03387, "fx":[-52.81286,45.83101,69.58741,8.94044], "fy":[90.92618,81.52886,79.66589,106.33313]}, + {"t":1.01202, "x":1.96741, "y":3.1679, "heading":0.7672, "vx":-2.30667, "vy":2.73046, "omega":-1.229, "ax":1.68362, "ay":3.59296, "alpha":16.82274, "fx":[-58.78224,75.45005,82.273,15.61091], "fy":[82.40054,-3.44853,62.22055,103.28801]}, + {"t":1.02886, "x":1.92879, "y":3.21441, "heading":0.74649, "vx":-2.27831, "vy":2.79099, "omega":-0.94559, "ax":1.47634, "ay":-1.20337, "alpha":24.97057, "fx":[-86.06516,30.02698,100.57969,55.90724], "fy":[-40.81542,-98.44178,-24.12552,81.5069]}, + {"t":1.04571, "x":1.89062, "y":3.26126, "heading":0.73056, "vx":-2.25344, "vy":2.77072, "omega":-0.52491, "ax":2.29501, "ay":-4.58453, "alpha":12.25796, "fx":[-35.55963,22.61031,80.18105,88.91793], "fy":[-97.38577,-103.92276,-69.13489,-41.48282]}, + {"t":1.06256, "x":1.85298, "y":3.30728, "heading":0.72172, "vx":-2.21477, "vy":2.69348, "omega":-0.3184, "ax":2.87787, "ay":-5.49198, "alpha":4.94439, "fx":[18.02477,37.49789,70.70014,69.58453], "fy":[-106.68147,-102.04233,-82.47602,-82.46831]}, + {"t":1.09657, "x":1.77931, "y":3.39573, "heading":0.71089, "vx":-2.11688, "vy":2.50667, "omega":-0.15022, "ax":3.55395, "ay":-5.27549, "alpha":2.52745, "fx":[47.21399,52.50114,71.12096,70.97059], "fy":[-98.1139,-95.61297,-82.68161,-82.52976]}, + {"t":1.13059, "x":1.70936, "y":3.47794, "heading":0.70578, "vx":-1.99599, "vy":2.32722, "omega":-0.06425, "ax":3.83043, "ay":-5.13333, "alpha":1.51811, "fx":[58.01189,59.82366,71.38204,71.40046], "fy":[-92.49876,-91.44295,-82.73005,-82.59422]}, + {"t":1.1646, "x":1.64368, "y":3.55413, "heading":0.70359, "vx":-1.8657, "vy":2.15261, "omega":-0.01261, "ax":3.97741, "ay":-5.04339, "alpha":0.96947, "fx":[63.38842,64.07378,71.55556,71.6009], "fy":[-89.09986,-88.6632,-82.74121,-82.64252]}, + {"t":1.19862, "x":1.58252, "y":3.62443, "heading":0.70316, "vx":-1.73041, "vy":1.98106, "omega":0.02037, "ax":4.06809, "ay":-4.98249, "alpha":0.62443, "fx":[66.56817,66.82743,71.67723,71.71551], "fy":[-86.87626,-86.70675,-82.74209,-82.67762]}, + {"t":1.23263, "x":1.52601, "y":3.68894, "heading":0.70386, "vx":-1.59203, "vy":1.81158, "omega":0.04161, "ax":4.12948, "ay":-4.93876, "alpha":0.38719, "fx":[68.66037,68.74846,71.76567,71.7903], "fy":[-85.3194,-85.26434,-82.74073,-82.70294]}, + {"t":1.26665, "x":1.47425, "y":3.7477, "heading":0.70527, "vx":-1.45156, "vy":1.64358, "omega":0.05478, "ax":4.17373, "ay":-4.90592, "alpha":0.21397, "fx":[70.13948,70.16106,71.83156,71.84402], "fy":[-84.17119,-84.16092,-82.73973,-82.72105]}, + {"t":1.30066, "x":1.42729, "y":3.80077, "heading":0.70713, "vx":-1.30959, "vy":1.47671, "omega":0.06206, "ax":4.20714, "ay":-4.88038, "alpha":0.08191, "fx":[71.24036,71.24137,71.88152,71.88544], "fy":[-83.2899,-83.29167,-82.73986,-82.73379]}, + {"t":1.33468, "x":1.38518, "y":3.84818, "heading":0.70925, "vx":-1.16649, "vy":1.3107, "omega":0.06484, "ax":4.23323, "ay":-4.85996, "alpha":-0.02214, "fx":[72.09189,72.09302,71.91989,71.91911], "fy":[-82.59204,-82.59042,-82.74122,-82.74253]}, + {"t":1.36869, "x":1.34795, "y":3.88995, "heading":0.71145, "vx":-1.02249, "vy":1.14539, "omega":0.06409, "ax":4.25417, "ay":-4.84328, "alpha":-0.10623, "fx":[72.77048,72.78087,71.94969,71.94752], "fy":[-82.02553,-82.01351,-82.74363,-82.7483]}, + {"t":1.40271, "x":1.31563, "y":3.92611, "heading":0.71363, "vx":-0.87778, "vy":0.98064, "omega":0.06048, "ax":4.27134, "ay":-4.82939, "alpha":-0.1756, "fx":[73.3242,73.34755,71.97309,71.97211], "fy":[-81.55628,-81.53103,-82.74683,-82.75188]}, + {"t":1.43672, "x":1.28824, "y":3.95667, "heading":0.71569, "vx":-0.73249, "vy":0.81637, "omega":0.0545, "ax":4.28567, "ay":-4.81765, "alpha":-0.23382, "fx":[73.78471,73.82223,71.99169,71.99371], "fy":[-81.16114,-81.12178,-82.75053,-82.75392]}, + {"t":1.47074, "x":1.2658, "y":3.98165, "heading":0.71754, "vx":-0.58672, "vy":0.65249, "omega":0.04655, "ax":4.29782, "ay":-4.8076, "alpha":-0.28337, "fx":[74.17374,74.22555,72.00674,72.01283], "fy":[-80.82384,-80.77036,-82.75446,-82.75493]}, + {"t":1.50475, "x":1.24833, "y":4.00107, "heading":0.71913, "vx":-0.44052, "vy":0.48896, "omega":0.03691, "ax":4.30825, "ay":-4.7989, "alpha":-0.32606, "fx":[74.50664,74.57252,72.01919,72.02978], "fy":[-80.53263,-80.46529,-82.75836,-82.75532]}, + {"t":1.53877, "x":1.23584, "y":4.01492, "heading":0.72038, "vx":-0.29398, "vy":0.32573, "omega":0.02582, "ax":4.31729, "ay":-4.79129, "alpha":-0.36322, "fx":[74.79455,74.87431,72.0298,72.04472], "fy":[-80.27884,-80.19783,-82.762,-82.75544]}, + {"t":1.57279, "x":1.22834, "y":4.02323, "heading":0.72126, "vx":-0.14712, "vy":0.16275, "omega":0.01347, "ax":4.32521, "ay":-4.78459, "alpha":-0.39586, "fx":[75.04578,75.13942,72.03918,72.05775], "fy":[-80.05594,-79.96124,-82.76517,-82.75559]}, + {"t":1.6068, "x":1.22584, "y":4.026, "heading":0.72172, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.33867, "ay":-0.70718, "alpha":3.16104, "fx":[108.84833,104.11317,109.1741,109.14027], "fy":[-13.56689,-34.66218,-11.23851,11.35165]}, + {"t":1.64106, "x":1.22956, "y":4.02558, "heading":0.72172, "vx":0.21717, "vy":-0.02423, "omega":0.1083, "ax":6.33813, "ay":-0.70712, "alpha":3.16022, "fx":[108.8359,104.10606,109.16598,109.1312], "fy":[-13.56469,-34.65318,-11.23781,11.34433]}, + {"t":1.67532, "x":1.24072, "y":4.02434, "heading":0.72543, "vx":0.43432, "vy":-0.04846, "omega":0.21657, "ax":6.33748, "ay":-0.7071, "alpha":3.15963, "fx":[108.80761,104.10459,109.16393,109.11902], "fy":[-13.67309,-34.6227,-11.1651,11.35071]}, + {"t":1.70958, "x":1.25932, "y":4.02226, "heading":0.73285, "vx":0.65145, "vy":-0.07268, "omega":0.32483, "ax":6.3367, "ay":-0.70713, "alpha":3.15931, "fx":[108.76265,104.10867,109.16746,109.10338], "fy":[-13.89162,-34.56985,-11.02046,11.36978]}, + {"t":1.74385, "x":1.28536, "y":4.01936, "heading":0.74398, "vx":0.86855, "vy":-0.09691, "omega":0.43307, "ax":6.33576, "ay":-0.7072, "alpha":3.15938, "fx":[108.69973,104.11826,109.1758,109.08386], "fy":[-14.21957,-34.49294,-10.80396,11.39964]}, + {"t":1.77811, "x":1.31883, "y":4.01562, "heading":0.75881, "vx":1.08562, "vy":-0.12114, "omega":0.54131, "ax":6.33459, "ay":-0.7073, "alpha":3.16001, "fx":[108.61694,104.13336,109.18784,109.05989], "fy":[-14.65582,-34.38951,-10.51571,11.43746]}, + {"t":1.81237, "x":1.35974, "y":4.01106, "heading":0.77736, "vx":1.30265, "vy":-0.14537, "omega":0.64958, "ax":6.33312, "ay":-0.70741, "alpha":3.16144, "fx":[108.51169,104.15382,109.20201,109.03057], "fy":[-15.19873,-34.25632,-10.15584,11.47947]}, + {"t":1.84663, "x":1.40809, "y":4.00566, "heading":0.79962, "vx":1.51963, "vy":-0.16961, "omega":0.75789, "ax":6.33124, "ay":-0.70752, "alpha":3.16392, "fx":[108.38038,104.17912,109.21606,108.99446], "fy":[-15.84588,-34.08935,-9.72454,11.52085]}, + {"t":1.88089, "x":1.46387, "y":3.99944, "heading":0.82558, "vx":1.73655, "vy":-0.19385, "omega":0.86629, "ax":6.32876, "ay":-0.70759, "alpha":3.16779, "fx":[108.2179,104.20785,109.22667,108.94901], "fy":[-16.59375,-33.88377,-9.22207,11.55577]}, + {"t":1.91515, "x":1.52708, "y":3.99238, "heading":0.85526, "vx":1.95338, "vy":-0.21809, "omega":0.97482, "ax":6.32538, "ay":-0.70757, "alpha":3.17339, "fx":[108.01651,104.23682,109.2286,108.88952], "fy":[-17.43731,-33.63389,-8.64869,11.57733]}, + {"t":1.94941, "x":1.59772, "y":3.98449, "heading":0.88866, "vx":2.17009, "vy":-0.24233, "omega":1.08355, "ax":6.32052, "ay":-0.70738, "alpha":3.18119, "fx":[107.76302,104.2588,109.21278,108.80653], "fy":[-18.36935,-33.33297,-8.00454,11.57786]}, + {"t":1.98367, "x":1.67578, "y":3.97578, "heading":0.92578, "vx":2.38664, "vy":-0.26657, "omega":1.19254, "ax":6.31297, "ay":-0.70682, "alpha":3.19191, "fx":[107.43105,104.25654,109.16096,108.67891], "fy":[-19.37939,-32.97297,-7.28901,11.55]}, + {"t":2.01793, "x":1.76125, "y":3.96623, "heading":0.96664, "vx":2.60293, "vy":-0.29078, "omega":1.30189, "ax":6.29956, "ay":-0.7055, "alpha":3.20755, "fx":[106.95446,104.18256,109.02803,108.4501], "fy":[-20.45134,-32.54415,-6.49804,11.49211]}, + {"t":2.05219, "x":1.85413, "y":3.95585, "heading":1.01125, "vx":2.81876, "vy":-0.31496, "omega":1.41179, "ax":6.26871, "ay":-0.70197, "alpha":3.23724, "fx":[106.09351,103.85796,108.65442,107.91028], "fy":[-21.55776,-32.03783,-5.60835,11.4427]}, + {"t":2.08646, "x":1.95438, "y":3.94465, "heading":1.05961, "vx":3.03353, "vy":-0.33901, "omega":1.5227, "ax":6.11912, "ay":-0.68383, "alpha":3.38762, "fx":[102.73239,101.70282,106.68852,105.21399], "fy":[-22.65131,-31.54354,-4.34649,12.01421]}, + {"t":2.12072, "x":2.0619, "y":3.93263, "heading":1.11178, "vx":3.24318, "vy":-0.36243, "omega":1.63876, "ax":-6.13652, "ay":0.69433, "alpha":-2.5629, "fx":[-103.10147,-102.71418,-106.25066,-105.45559], "fy":[20.65916,26.79742,5.29863,-5.51371]}, + {"t":2.15498, "x":2.16942, "y":3.92062, "heading":1.16793, "vx":3.03294, "vy":-0.33865, "omega":1.55096, "ax":-6.2773, "ay":0.70546, "alpha":-3.00794, "fx":[-105.55756,-104.74776,-108.69216,-108.103], "fy":[24.14487,28.95491,3.4383,-8.53967]}, + {"t":2.18924, "x":2.26965, "y":3.90943, "heading":1.22107, "vx":2.81787, "vy":-0.31448, "omega":1.4479, "ax":-6.30364, "ay":0.70721, "alpha":-3.11948, "fx":[-105.81358,-105.2692,-109.17217,-108.6374], "fy":[25.82781,28.88852,2.29411,-8.89288]}, + {"t":2.2235, "x":2.36249, "y":3.89907, "heading":1.27067, "vx":2.6019, "vy":-0.29025, "omega":1.34102, "ax":-6.31448, "ay":0.70758, "alpha":-3.177, "fx":[-105.77654,-105.58801,-109.37842,-108.88678], "fy":[27.10383,28.49902,1.32667,-8.78642]}, + {"t":2.25776, "x":2.44793, "y":3.88955, "heading":1.31662, "vx":2.38556, "vy":-0.266, "omega":1.23218, "ax":-6.32034, "ay":0.70748, "alpha":-3.21316, "fx":[-105.66026,-105.83458,-109.49041,-109.04315], "fy":[28.1509,28.01478,0.47288,-8.50227]}, + {"t":2.29202, "x":2.52595, "y":3.88085, "heading":1.35883, "vx":2.16902, "vy":-0.24177, "omega":1.12209, "ax":-6.32402, "ay":0.70718, "alpha":-3.2376, "fx":[-105.52293,-106.0418,-109.5576,-109.1567], "fy":[29.02856,27.50617,-0.28652,-8.13271]}, + {"t":2.32628, "x":2.59655, "y":3.87298, "heading":1.39728, "vx":1.95235, "vy":-0.21754, "omega":1.01117, "ax":-6.32658, "ay":0.70679, "alpha":-3.25449, "fx":[-105.38628,-106.22136,-109.59973,-109.24575], "fy":[29.76785,27.00484,-0.96058,-7.72316]}, + {"t":2.36054, "x":2.65973, "y":3.86594, "heading":1.43192, "vx":1.73559, "vy":-0.19332, "omega":0.89966, "ax":-6.32849, "ay":0.70638, "alpha":-3.26617, "fx":[-105.25958,-106.37832,-109.6266,-109.31843], "fy":[30.38956,26.52845,-1.55505,-7.30193]}, + {"t":2.39481, "x":2.71548, "y":3.85973, "heading":1.46275, "vx":1.51877, "vy":-0.16912, "omega":0.78776, "ax":-6.32998, "ay":0.70598, "alpha":-3.27418, "fx":[-105.14684,-106.51523,-109.64377,-109.37884], "fy":[30.90965,26.0882,-2.07429,-6.88932]}, + {"t":2.42907, "x":2.7638, "y":3.85435, "heading":1.48974, "vx":1.3019, "vy":-0.14493, "omega":0.67558, "ax":-6.33119, "ay":0.70563, "alpha":-3.27961, "fx":[-105.04955,-106.63355,-109.65477,-109.42934], "fy":[31.34106,25.69188,-2.52195,-6.50097]}, + {"t":2.46333, "x":2.80468, "y":3.8498, "heading":1.51288, "vx":1.08499, "vy":-0.12076, "omega":0.56322, "ax":-6.3322, "ay":0.70532, "alpha":-3.28332, "fx":[-104.96799,-106.73423,-109.66192,-109.47147], "fy":[31.69457,25.34509,-2.90118,-6.14935]}, + {"t":2.49759, "x":2.83814, "y":3.84608, "heading":1.53218, "vx":0.86804, "vy":-0.09659, "omega":0.45073, "ax":-6.33304, "ay":0.70507, "alpha":-3.28595, "fx":[-104.9018,-106.81795,-109.66689,-109.50633], "fy":[31.9791,25.05204,-3.21473,-5.84452]}, + {"t":2.53185, "x":2.86416, "y":3.84318, "heading":1.54762, "vx":0.65106, "vy":-0.07244, "omega":0.33815, "ax":-6.33375, "ay":0.70487, "alpha":-3.28802, "fx":[-104.85039,-106.88521,-109.67083,-109.53478], "fy":[32.20195,24.81587,-3.46494,-5.5945]}, + {"t":2.56611, "x":2.88275, "y":3.84111, "heading":1.55921, "vx":0.43406, "vy":-0.04829, "omega":0.2255, "ax":-6.33435, "ay":0.70472, "alpha":-3.28991, "fx":[-104.81314,-106.93642,-109.67461,-109.55751], "fy":[32.36888,24.63894,-3.6537,-5.40556]}, + {"t":2.60037, "x":2.89391, "y":3.83987, "heading":1.56693, "vx":0.21704, "vy":-0.02414, "omega":0.11278, "ax":-6.33484, "ay":0.70463, "alpha":-3.2919, "fx":[-104.78954,-106.97189,-109.67883,-109.57505], "fy":[32.4842,24.52298,-3.78247,-5.28236]}, + {"t":2.63463, "x":2.89762, "y":3.83946, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_3_BACK.traj b/src/main/deploy/choreo/E_RIGHT_PATH_3_BACK.traj new file mode 100644 index 00000000..df62627d --- /dev/null +++ b/src/main/deploy/choreo/E_RIGHT_PATH_3_BACK.traj @@ -0,0 +1,82 @@ +{ + "name":"E_RIGHT_PATH_3_BACK", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.199847936630249, "y":3.813179254531861, "heading":1.5707963267948966, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.2258362770080566, "y":4.026000022888184, "heading":1.5707963267948966, "intervals":20, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.785933017730713, "y":4.141683101654053, "heading":1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.199847936630249 m", "val":3.199847936630249}, "y":{"exp":"3.8131792545318604 m", "val":3.813179254531861}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.2258362770080566 m", "val":1.2258362770080566}, "y":{"exp":"4.026000022888184 m", "val":4.026000022888184}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":20, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.785933017730713 m", "val":2.785933017730713}, "y":{"exp":"4.141683101654053 m", "val":4.141683101654053}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.11081,2.09591], + "samples":[ + {"t":0.0, "x":3.19985, "y":3.81318, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.41597, "ay":0.69171, "alpha":0.0, "fx":[-109.13382,-109.13382,-109.13382,-109.13382], "fy":[11.76586,11.76586,11.76586,11.76586]}, + {"t":0.0483, "x":3.19237, "y":3.81399, "heading":1.5708, "vx":-0.30987, "vy":0.03341, "omega":0.0, "ax":-6.41542, "ay":0.69165, "alpha":0.0, "fx":[-109.12438,-109.12438,-109.12438,-109.12438], "fy":[11.76484,11.76484,11.76484,11.76484]}, + {"t":0.09659, "x":3.16992, "y":3.81641, "heading":1.5708, "vx":-0.61971, "vy":0.06681, "omega":0.0, "ax":-6.41474, "ay":0.69158, "alpha":0.0, "fx":[-109.11285,-109.11285,-109.11285,-109.11285], "fy":[11.7636,11.7636,11.7636,11.7636]}, + {"t":0.14489, "x":3.13251, "y":3.82044, "heading":1.5708, "vx":-0.92952, "vy":0.10021, "omega":0.0, "ax":-6.41389, "ay":0.69149, "alpha":0.0, "fx":[-109.09844,-109.09844,-109.09844,-109.09844], "fy":[11.76204,11.76204,11.76204,11.76204]}, + {"t":0.19318, "x":3.08013, "y":3.82609, "heading":1.5708, "vx":-1.23928, "vy":0.13361, "omega":0.0, "ax":-6.4128, "ay":0.69137, "alpha":0.0, "fx":[-109.07991,-109.07991,-109.07991,-109.07991], "fy":[11.76005,11.76005,11.76005,11.76005]}, + {"t":0.24148, "x":3.0128, "y":3.83334, "heading":1.5708, "vx":-1.549, "vy":0.167, "omega":0.0, "ax":-6.41135, "ay":0.69122, "alpha":0.0, "fx":[-109.05519,-109.05519,-109.05519,-109.05519], "fy":[11.75738,11.75738,11.75738,11.75738]}, + {"t":0.28978, "x":2.93052, "y":3.84222, "heading":1.5708, "vx":-1.85864, "vy":0.20038, "omega":0.0, "ax":-6.40931, "ay":0.691, "alpha":0.0, "fx":[-109.02059,-109.02059,-109.02059,-109.02059], "fy":[11.75365,11.75365,11.75365,11.75365]}, + {"t":0.33807, "x":2.83327, "y":3.8527, "heading":1.5708, "vx":-2.16819, "vy":0.23375, "omega":0.0, "ax":-6.40626, "ay":0.69067, "alpha":0.0, "fx":[-108.9687,-108.9687,-108.9687,-108.9687], "fy":[11.74806,11.74806,11.74806,11.74806]}, + {"t":0.38637, "x":2.72109, "y":3.86479, "heading":1.5708, "vx":-2.47758, "vy":0.26711, "omega":0.0, "ax":-6.40118, "ay":0.69012, "alpha":0.0, "fx":[-108.88222,-108.88222,-108.88222,-108.88222], "fy":[11.73873,11.73873,11.73873,11.73873]}, + {"t":0.43467, "x":2.59396, "y":3.8785, "heading":1.5708, "vx":-2.78674, "vy":0.30044, "omega":0.0, "ax":-6.39102, "ay":0.68902, "alpha":0.0, "fx":[-108.70939,-108.70939,-108.70939,-108.70939], "fy":[11.7201,11.7201,11.7201,11.7201]}, + {"t":0.48296, "x":2.45192, "y":3.89381, "heading":1.5708, "vx":-3.0954, "vy":0.33372, "omega":0.0, "ax":-6.36061, "ay":0.68575, "alpha":0.0, "fx":[-108.19218,-108.19218,-108.19218,-108.19218], "fy":[11.66434,11.66434,11.66434,11.66434]}, + {"t":0.53126, "x":2.29501, "y":3.91073, "heading":1.5708, "vx":-3.40259, "vy":0.36684, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.57955, "x":2.13068, "y":3.92845, "heading":1.5708, "vx":-3.40259, "vy":0.36684, "omega":0.0, "ax":6.36061, "ay":-0.68575, "alpha":0.0, "fx":[108.19218,108.19218,108.19218,108.19218], "fy":[-11.66434,-11.66434,-11.66434,-11.66434]}, + {"t":0.62785, "x":1.97376, "y":3.94537, "heading":1.5708, "vx":-3.0954, "vy":0.33372, "omega":0.0, "ax":6.39102, "ay":-0.68902, "alpha":0.0, "fx":[108.70939,108.70939,108.70939,108.70939], "fy":[-11.7201,-11.7201,-11.7201,-11.7201]}, + {"t":0.67615, "x":1.83172, "y":3.96068, "heading":1.5708, "vx":-2.78674, "vy":0.30044, "omega":0.0, "ax":6.40118, "ay":-0.69012, "alpha":0.0, "fx":[108.88222,108.88222,108.88222,108.88222], "fy":[-11.73873,-11.73873,-11.73873,-11.73873]}, + {"t":0.72444, "x":1.7046, "y":3.97438, "heading":1.5708, "vx":-2.47758, "vy":0.26711, "omega":0.0, "ax":6.40626, "ay":-0.69067, "alpha":0.0, "fx":[108.9687,108.9687,108.9687,108.9687], "fy":[-11.74806,-11.74806,-11.74806,-11.74806]}, + {"t":0.77274, "x":1.59241, "y":3.98648, "heading":1.5708, "vx":-2.16819, "vy":0.23375, "omega":0.0, "ax":6.40931, "ay":-0.691, "alpha":0.0, "fx":[109.02059,109.02059,109.02059,109.02059], "fy":[-11.75365,-11.75365,-11.75365,-11.75365]}, + {"t":0.82104, "x":1.49517, "y":3.99696, "heading":1.5708, "vx":-1.85864, "vy":0.20038, "omega":0.0, "ax":6.41135, "ay":-0.69122, "alpha":0.0, "fx":[109.05519,109.05519,109.05519,109.05519], "fy":[-11.75738,-11.75738,-11.75738,-11.75738]}, + {"t":0.86933, "x":1.41288, "y":4.00583, "heading":1.5708, "vx":-1.549, "vy":0.167, "omega":0.0, "ax":6.4128, "ay":-0.69137, "alpha":0.0, "fx":[109.07991,109.07991,109.07991,109.07991], "fy":[-11.76005,-11.76005,-11.76005,-11.76005]}, + {"t":0.91763, "x":1.34555, "y":4.01309, "heading":1.5708, "vx":-1.23928, "vy":0.13361, "omega":0.0, "ax":6.41389, "ay":-0.69149, "alpha":0.0, "fx":[109.09844,109.09844,109.09844,109.09844], "fy":[-11.76204,-11.76204,-11.76204,-11.76204]}, + {"t":0.96592, "x":1.29318, "y":4.01874, "heading":1.5708, "vx":-0.92952, "vy":0.10021, "omega":0.0, "ax":6.41474, "ay":-0.69158, "alpha":0.0, "fx":[109.11285,109.11285,109.11285,109.11285], "fy":[-11.7636,-11.7636,-11.7636,-11.7636]}, + {"t":1.01422, "x":1.25577, "y":4.02277, "heading":1.5708, "vx":-0.61971, "vy":0.06681, "omega":0.0, "ax":6.41542, "ay":-0.69165, "alpha":0.0, "fx":[109.12438,109.12438,109.12438,109.12438], "fy":[-11.76484,-11.76484,-11.76484,-11.76484]}, + {"t":1.06252, "x":1.23332, "y":4.02519, "heading":1.5708, "vx":-0.30987, "vy":0.03341, "omega":0.0, "ax":6.41597, "ay":-0.69171, "alpha":0.0, "fx":[109.13382,109.13382,109.13382,109.13382], "fy":[-11.76586,-11.76586,-11.76586,-11.76586]}, + {"t":1.11081, "x":1.22584, "y":4.026, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.43554, "ay":0.4772, "alpha":0.0, "fx":[109.46674,109.46674,109.46674,109.46674], "fy":[8.11709,8.11709,8.11709,8.11709]}, + {"t":1.16007, "x":1.23364, "y":4.02658, "heading":1.5708, "vx":0.31698, "vy":0.0235, "omega":0.0, "ax":6.4349, "ay":0.47716, "alpha":0.0, "fx":[109.45574,109.45574,109.45574,109.45574], "fy":[8.11628,8.11628,8.11628,8.11628]}, + {"t":1.20932, "x":1.25706, "y":4.02832, "heading":1.5708, "vx":0.63393, "vy":0.04701, "omega":0.0, "ax":6.43408, "ay":0.47709, "alpha":0.0, "fx":[109.4418,109.4418,109.4418,109.4418], "fy":[8.11524,8.11524,8.11524,8.11524]}, + {"t":1.25858, "x":1.29609, "y":4.03121, "heading":1.5708, "vx":0.95084, "vy":0.07051, "omega":0.0, "ax":6.43301, "ay":0.47702, "alpha":0.0, "fx":[109.42358,109.42358,109.42358,109.42358], "fy":[8.11389,8.11389,8.11389,8.11389]}, + {"t":1.30783, "x":1.35073, "y":4.03526, "heading":1.5708, "vx":1.2677, "vy":0.094, "omega":0.0, "ax":6.43154, "ay":0.47691, "alpha":0.0, "fx":[109.39873,109.39873,109.39873,109.39873], "fy":[8.11205,8.11205,8.11205,8.11205]}, + {"t":1.35709, "x":1.42097, "y":4.04047, "heading":1.5708, "vx":1.58449, "vy":0.11749, "omega":0.0, "ax":6.42943, "ay":0.47675, "alpha":0.0, "fx":[109.36284,109.36284,109.36284,109.36284], "fy":[8.10939,8.10939,8.10939,8.10939]}, + {"t":1.40634, "x":1.50681, "y":4.04683, "heading":1.5708, "vx":1.90117, "vy":0.14097, "omega":0.0, "ax":6.42612, "ay":0.4765, "alpha":0.0, "fx":[109.30646,109.30646,109.30646,109.30646], "fy":[8.10521,8.10521,8.10521,8.10521]}, + {"t":1.4556, "x":1.60825, "y":4.05436, "heading":1.5708, "vx":2.21769, "vy":0.16444, "omega":0.0, "ax":6.42016, "ay":0.47606, "alpha":0.0, "fx":[109.20503,109.20503,109.20503,109.20503], "fy":[8.09769,8.09769,8.09769,8.09769]}, + {"t":1.50485, "x":1.72527, "y":4.06303, "heading":1.5708, "vx":2.53391, "vy":0.18789, "omega":0.0, "ax":6.40626, "ay":0.47503, "alpha":0.0, "fx":[108.96867,108.96867,108.96867,108.96867], "fy":[8.08016,8.08016,8.08016,8.08016]}, + {"t":1.55411, "x":1.85785, "y":4.07286, "heading":1.5708, "vx":2.84945, "vy":0.21129, "omega":0.0, "ax":6.33721, "ay":0.46991, "alpha":0.0, "fx":[107.79411,107.79411,107.79411,107.79411], "fy":[7.99307,7.99307,7.99307,7.99307]}, + {"t":1.60336, "x":2.00588, "y":4.08384, "heading":1.5708, "vx":3.16159, "vy":0.23444, "omega":0.0, "ax":-6.33721, "ay":-0.46991, "alpha":0.0, "fx":[-107.79411,-107.79411,-107.79411,-107.79411], "fy":[-7.99307,-7.99307,-7.99307,-7.99307]}, + {"t":1.65262, "x":2.15392, "y":4.09482, "heading":1.5708, "vx":2.84945, "vy":0.21129, "omega":0.0, "ax":-6.40626, "ay":-0.47503, "alpha":0.0, "fx":[-108.96867,-108.96867,-108.96867,-108.96867], "fy":[-8.08016,-8.08016,-8.08016,-8.08016]}, + {"t":1.70187, "x":2.2865, "y":4.10465, "heading":1.5708, "vx":2.53391, "vy":0.18789, "omega":0.0, "ax":-6.42016, "ay":-0.47606, "alpha":0.0, "fx":[-109.20503,-109.20503,-109.20503,-109.20503], "fy":[-8.09769,-8.09769,-8.09769,-8.09769]}, + {"t":1.75113, "x":2.40352, "y":4.11333, "heading":1.5708, "vx":2.21769, "vy":0.16444, "omega":0.0, "ax":-6.42612, "ay":-0.4765, "alpha":0.0, "fx":[-109.30646,-109.30646,-109.30646,-109.30646], "fy":[-8.10521,-8.10521,-8.10521,-8.10521]}, + {"t":1.80038, "x":2.50496, "y":4.12085, "heading":1.5708, "vx":1.90117, "vy":0.14097, "omega":0.0, "ax":-6.42943, "ay":-0.47675, "alpha":0.0, "fx":[-109.36284,-109.36284,-109.36284,-109.36284], "fy":[-8.10939,-8.10939,-8.10939,-8.10939]}, + {"t":1.84964, "x":2.5908, "y":4.12721, "heading":1.5708, "vx":1.58449, "vy":0.11749, "omega":0.0, "ax":-6.43154, "ay":-0.47691, "alpha":0.0, "fx":[-109.39873,-109.39873,-109.39873,-109.39873], "fy":[-8.11205,-8.11205,-8.11205,-8.11205]}, + {"t":1.89889, "x":2.66104, "y":4.13242, "heading":1.5708, "vx":1.2677, "vy":0.094, "omega":0.0, "ax":-6.43301, "ay":-0.47702, "alpha":0.0, "fx":[-109.42358,-109.42358,-109.42358,-109.42358], "fy":[-8.11389,-8.11389,-8.11389,-8.11389]}, + {"t":1.94815, "x":2.71568, "y":4.13647, "heading":1.5708, "vx":0.95084, "vy":0.07051, "omega":0.0, "ax":-6.43408, "ay":-0.47709, "alpha":0.0, "fx":[-109.4418,-109.4418,-109.4418,-109.4418], "fy":[-8.11524,-8.11524,-8.11524,-8.11524]}, + {"t":1.9974, "x":2.75471, "y":4.13937, "heading":1.5708, "vx":0.63393, "vy":0.04701, "omega":0.0, "ax":-6.4349, "ay":-0.47716, "alpha":0.0, "fx":[-109.45574,-109.45574,-109.45574,-109.45574], "fy":[-8.11628,-8.11628,-8.11628,-8.11628]}, + {"t":2.04666, "x":2.77813, "y":4.1411, "heading":1.5708, "vx":0.31698, "vy":0.0235, "omega":0.0, "ax":-6.43554, "ay":-0.4772, "alpha":0.0, "fx":[-109.46674,-109.46674,-109.46674,-109.46674], "fy":[-8.11709,-8.11709,-8.11709,-8.11709]}, + {"t":2.09591, "x":2.78593, "y":4.14168, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_4.traj b/src/main/deploy/choreo/E_RIGHT_PATH_4.traj new file mode 100644 index 00000000..a688f407 --- /dev/null +++ b/src/main/deploy/choreo/E_RIGHT_PATH_4.traj @@ -0,0 +1,120 @@ +{ + "name":"E_RIGHT_PATH_4", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.2129878997802734, "y":3.852599859237671, "heading":1.5707963267948966, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.9559978246688845, "y":5.059605598449707, "heading":0.7626747895755805, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.2163536548614502, "y":5.85614538192749, "heading":0.7626747895755805, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.812213182449341, "y":4.470187187194824, "heading":1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.2129878997802734 m", "val":3.2129878997802734}, "y":{"exp":"3.852599859237671 m", "val":3.852599859237671}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.9559978246688843 m", "val":1.9559978246688845}, "y":{"exp":"5.059605598449707 m", "val":5.059605598449707}, "heading":{"exp":"0.7626747895755805 rad", "val":0.7626747895755805}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.2163536548614502 m", "val":1.2163536548614502}, "y":{"exp":"5.85614538192749 m", "val":5.85614538192749}, "heading":{"exp":"0.7626747895755805 rad", "val":0.7626747895755805}, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.812213182449341 m", "val":2.812213182449341}, "y":{"exp":"4.470187187194824 m", "val":4.470187187194824}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.75905,1.33983,2.48955], + "samples":[ + {"t":0.0, "x":3.21299, "y":3.8526, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-4.50364, "ay":4.27131, "alpha":-5.67171, "fx":[-44.63767,-78.98624,-102.05734,-80.74092], "fy":[100.19567,76.17034,40.20774,74.04096]}, + {"t":0.0253, "x":3.21155, "y":3.85397, "heading":1.5708, "vx":-0.11395, "vy":0.10807, "omega":-0.1435, "ax":-4.50731, "ay":4.27482, "alpha":-5.60813, "fx":[-45.10442,-78.98909,-101.86946,-80.70915], "fy":[99.97747,76.15804,40.6597,74.05891]}, + {"t":0.0506, "x":3.20722, "y":3.85807, "heading":1.56717, "vx":-0.22799, "vy":0.21623, "omega":-0.2854, "ax":-4.51174, "ay":4.27807, "alpha":-5.53919, "fx":[-45.56777,-78.9135,-101.63991,-80.85234], "fy":[99.75701,76.22607,41.20726,73.88462]}, + {"t":0.0759, "x":3.20001, "y":3.86491, "heading":1.55994, "vx":-0.34214, "vy":0.32447, "omega":-0.42555, "ax":-4.51686, "ay":4.28117, "alpha":-5.46412, "fx":[-46.04013,-78.76291,-101.36584,-81.15294], "fy":[99.52841,76.37024,41.85259,73.53496]}, + {"t":0.10121, "x":3.18991, "y":3.87449, "heading":1.54918, "vx":-0.45643, "vy":0.43279, "omega":-0.5638, "ax":-4.52259, "ay":4.28428, "alpha":-5.38215, "fx":[-46.53688,-78.54124,-101.04341,-81.59008], "fy":[99.28409,76.58548,42.59915,73.02862]}, + {"t":0.12651, "x":3.17691, "y":3.88681, "heading":1.53491, "vx":-0.57086, "vy":0.54119, "omega":-0.69997, "ax":-4.52884, "ay":4.28753, "alpha":-5.29233, "fx":[-47.07691,-78.25313,-100.66762,-82.13959], "fy":[99.01431,76.86561,43.45187,72.38714]}, + {"t":0.15181, "x":3.16102, "y":3.90188, "heading":1.5172, "vx":-0.68544, "vy":0.64967, "omega":-0.83388, "ax":-4.53555, "ay":4.29112, "alpha":-5.19328, "fx":[-47.68331,-77.90422,-100.23202,-82.77387], "fy":[98.70671,77.20317,44.41732,71.63602]}, + {"t":0.17711, "x":3.14222, "y":3.91969, "heading":1.4961, "vx":-0.8002, "vy":0.75824, "omega":-0.96528, "ax":-4.54264, "ay":4.29526, "alpha":-5.08291, "fx":[-48.38424,-77.50164,-99.72838,-83.46181], "fy":[98.34548,77.58905,45.50397,70.80595]}, + {"t":0.20241, "x":3.12052, "y":3.94025, "heading":1.47168, "vx":-0.91513, "vy":0.86692, "omega":-1.09388, "ax":-4.5501, "ay":4.30018, "alpha":-4.95804, "fx":[-49.21398,-77.05466,-99.14621,-84.16868], "fy":[97.91026,78.01206,46.72264,69.93406]}, + {"t":0.22771, "x":3.09591, "y":3.96356, "heading":1.444, "vx":-1.03026, "vy":0.97572, "omega":-1.21933, "ax":-4.55795, "ay":4.30615, "alpha":-4.81399, "fx":[-50.21432,-76.57554,-98.47196,-84.8559], "fy":[97.37467,78.45818,48.08715,69.06524]}, + {"t":0.25302, "x":3.06838, "y":3.98962, "heading":1.41315, "vx":-1.14558, "vy":1.08467, "omega":-1.34113, "ax":-4.5663, "ay":4.31345, "alpha":-4.64404, "fx":[-51.43611,-76.08096,-97.68788,-85.48056], "fy":[96.70393,78.90944,49.61531,68.25341]}, + {"t":0.27832, "x":3.03794, "y":4.01845, "heading":1.37922, "vx":-1.26112, "vy":1.19381, "omega":-1.45863, "ax":-4.57532, "ay":4.32235, "alpha":-4.43879, "fx":[-52.94113,-75.59402,-96.77013,-85.99457], "fy":[95.85169,79.34219,51.33061,67.56292]}, + {"t":0.30362, "x":3.00457, "y":4.05004, "heading":1.34231, "vx":-1.37688, "vy":1.30317, "omega":-1.57094, "ax":-4.58532, "ay":4.33303, "alpha":-4.18538, "fx":[-54.80406,-75.14754,-95.68575,-86.34281], "fy":[94.75519,79.72416,53.26484,67.07007]}, + {"t":0.32892, "x":2.96826, "y":4.0844, "heading":1.30257, "vx":-1.49289, "vy":1.4128, "omega":-1.67683, "ax":-4.59665, "ay":4.34554, "alpha":-3.86642, "fx":[-57.11417,-74.78934,-94.38729,-86.45983], "fy":[93.32824,80.00946,55.46269,66.86515]}, + {"t":0.35422, "x":2.92902, "y":4.12153, "heading":1.26014, "vx":-1.6092, "vy":1.52275, "omega":-1.77466, "ax":-4.60964, "ay":4.35965, "alpha":-3.45846, "fx":[-59.97604,-74.59139,-92.80305,-86.26396], "fy":[91.451,80.12939,57.98963,67.05531]}, + {"t":0.37952, "x":2.88683, "y":4.16146, "heading":1.21524, "vx":-1.72583, "vy":1.63306, "omega":-1.86216, "ax":-4.6244, "ay":4.37463, "alpha":-2.9295, "fx":[-63.50747,-74.66632,-90.818,-85.64696], "fy":[88.95522,79.97442,60.94657,67.76882]}, + {"t":0.40482, "x":2.84168, "y":4.20418, "heading":1.16812, "vx":-1.84283, "vy":1.74374, "omega":-1.93629, "ax":-4.6403, "ay":4.38894, "alpha":-2.23423, "fx":[-67.8313,-75.19966,-88.23341,-84.45616], "fy":[85.60372,79.35569,64.49787,69.16135]}, + {"t":0.43013, "x":2.79357, "y":4.2497, "heading":1.11913, "vx":-1.96024, "vy":1.85479, "omega":-1.99282, "ax":-4.65481, "ay":4.39939, "alpha":-1.30317, "fx":[-73.05417,-76.51779,-84.67262,-82.46306], "fy":[81.0642,77.91282,68.92853,71.42391]}, + {"t":0.45543, "x":2.74248, "y":4.29804, "heading":1.06871, "vx":-2.07801, "vy":1.9661, "omega":-2.02579, "ax":-4.66063, "ay":4.39891, "alpha":-0.01295, "fx":[-79.21978,-79.24363,-79.33203,-79.30831], "fy":[74.8831,74.85932,74.76525,74.78895]}, + {"t":0.48073, "x":2.68841, "y":4.34919, "heading":1.01746, "vx":-2.19593, "vy":2.0774, "omega":-2.02612, "ax":-4.63712, "ay":4.36741, "alpha":1.91326, "fx":[-86.21377,-84.66916,-70.21149,-74.40983], "fy":[66.48699,68.13232,83.01784,79.51659]}, + {"t":0.50603, "x":2.63137, "y":4.40315, "heading":0.96619, "vx":-2.31326, "vy":2.1879, "omega":-1.97771, "ax":-4.51329, "ay":4.22147, "alpha":5.30616, "fx":[-93.57007,-95.27792,-51.3687,-66.86269], "fy":[55.34414,50.87141,95.22652,85.78187]}, + {"t":0.53133, "x":2.57139, "y":4.45986, "heading":0.91615, "vx":-2.42745, "vy":2.29471, "omega":-1.84345, "ax":-4.01954, "ay":3.65258, "alpha":11.96905, "fx":[-99.509,-106.58796,-10.87232,-56.51561], "fy":[43.28554,5.82126,106.71307,92.69778]}, + {"t":0.55663, "x":2.50869, "y":4.51909, "heading":0.86951, "vx":-2.52915, "vy":2.38713, "omega":-1.54062, "ax":-3.68968, "ay":3.50021, "alpha":14.02274, "fx":[-99.03489,-105.50088,4.56931,-51.07515], "fy":[43.46178,-6.9442,106.24166,95.39097]}, + {"t":0.58194, "x":2.44352, "y":4.58061, "heading":0.83053, "vx":-2.62251, "vy":2.47569, "omega":-1.18582, "ax":-3.39874, "ay":3.41377, "alpha":15.24983, "fx":[-97.73372,-103.21354,15.88278,-46.18168], "fy":[44.77698,-13.31198,103.65582,97.14842]}, + {"t":0.60724, "x":2.37608, "y":4.64434, "heading":0.80053, "vx":-2.7085, "vy":2.56206, "omega":-0.79998, "ax":-3.23418, "ay":3.33612, "alpha":15.45209, "fx":[-95.9605,-99.74131,19.16599,-43.51435], "fy":[45.26911,-14.98512,99.86072,96.84114]}, + {"t":0.63254, "x":2.30651, "y":4.71023, "heading":0.78029, "vx":-2.79033, "vy":2.64647, "omega":-0.40902, "ax":-2.8929, "ay":3.22849, "alpha":14.43973, "fx":[-89.71819,-88.33191,19.81289,-38.59243], "fy":[46.06867,-9.0503,89.22075,93.42397]}, + {"t":0.65784, "x":2.23499, "y":4.77822, "heading":0.76994, "vx":-2.86353, "vy":2.72816, "omega":-0.04367, "ax":1.05939, "ay":1.68317, "alpha":1.3475, "fx":[12.82141,18.40825,23.13026,17.71975], "fy":[29.18185,23.8373,28.1888,33.31307]}, + {"t":0.68314, "x":2.16287, "y":4.84779, "heading":0.76883, "vx":-2.83672, "vy":2.77074, "omega":-0.00957, "ax":1.92352, "ay":1.86992, "alpha":-0.14708, "fx":[33.2563,32.63514,32.17878,32.80354], "fy":[31.70566,32.34682,31.90982,31.26494]}, + {"t":0.70844, "x":2.09172, "y":4.91849, "heading":0.76859, "vx":-2.78805, "vy":2.81806, "omega":-0.0133, "ax":4.01755, "ay":-0.28008, "alpha":-8.19216, "fx":[87.08798,70.70732,48.33855,67.21551], "fy":[-4.22614,36.75982,-6.80226,-44.78787]}, + {"t":0.73374, "x":2.02246, "y":4.9897, "heading":0.76826, "vx":-2.6864, "vy":2.81097, "omega":-0.22057, "ax":4.71315, "ay":-3.8059, "alpha":4.35366, "fx":[65.22046,68.84745,91.09306,95.51614], "fy":[-81.25402,-80.63349,-54.49669,-42.56499]}, + {"t":0.75905, "x":1.956, "y":5.05961, "heading":0.76267, "vx":-2.56715, "vy":2.71468, "omega":-0.11042, "ax":4.65411, "ay":-4.32127, "alpha":1.62441, "fx":[73.36452,73.72146,84.18313,85.39107], "fy":[-79.56035,-79.54449,-68.39403,-66.51522]}, + {"t":0.79321, "x":1.87101, "y":5.14983, "heading":0.7589, "vx":-2.40815, "vy":2.56704, "omega":-0.05492, "ax":4.53713, "ay":-4.51305, "alpha":0.8577, "fx":[74.0051,74.12854,80.1042,80.46347], "fy":[-79.8963,-79.88287,-73.89213,-73.39164]}, + {"t":0.82737, "x":1.79139, "y":5.23489, "heading":0.75703, "vx":-2.25314, "vy":2.41286, "omega":-0.02562, "ax":4.48212, "ay":-4.59365, "alpha":0.52913, "fx":[74.25739,74.31532,78.12622,78.25907], "fy":[-80.04657,-80.03755,-76.32285,-76.1397]}, + {"t":0.86154, "x":1.71702, "y":5.31465, "heading":0.75615, "vx":-2.10002, "vy":2.25592, "omega":-0.00754, "ax":4.45036, "ay":-4.63788, "alpha":0.34652, "fx":[74.39175,74.42349,76.96514,77.01686], "fy":[-80.13163,-80.12501,-77.687,-77.61215]}, + {"t":0.8957, "x":1.64788, "y":5.38901, "heading":0.75589, "vx":-1.94798, "vy":2.09747, "omega":0.0043, "ax":4.42972, "ay":-4.66579, "alpha":0.23029, "fx":[74.47519,74.49417,76.20284,76.22117], "fy":[-80.18621,-80.18102,-78.55898,-78.52849]}, + {"t":0.92987, "x":1.58391, "y":5.45795, "heading":0.75604, "vx":-1.79664, "vy":1.93807, "omega":0.01217, "ax":4.41525, "ay":-4.68499, "alpha":0.14981, "fx":[74.53216,74.54393,75.66428,75.66844], "fy":[-80.22407,-80.21999,-79.16413,-79.15321]}, + {"t":0.96403, "x":1.52511, "y":5.52142, "heading":0.75646, "vx":-1.6458, "vy":1.77801, "omega":0.01728, "ax":4.40455, "ay":-4.69901, "alpha":0.09079, "fx":[74.57365,74.58074,75.26361,75.26241], "fy":[-80.25172,-80.24874,-79.60863,-79.60613]}, + {"t":0.99819, "x":1.47145, "y":5.57943, "heading":0.75705, "vx":-1.49532, "vy":1.61748, "omega":0.02039, "ax":4.39631, "ay":-4.70969, "alpha":0.04565, "fx":[74.60534,74.60898,74.95385,74.95171], "fy":[-80.2727,-80.27092,-79.94897,-79.94938]}, + {"t":1.03236, "x":1.42293, "y":5.63194, "heading":0.75774, "vx":-1.34512, "vy":1.45658, "omega":0.02195, "ax":4.38977, "ay":-4.7181, "alpha":0.01002, "fx":[74.63042,74.63124,74.70717,74.70641], "fy":[-80.28908,-80.28862,-80.21797,-80.21837]}, + {"t":1.06652, "x":1.37954, "y":5.67895, "heading":0.75849, "vx":-1.19515, "vy":1.29539, "omega":0.02229, "ax":4.38446, "ay":-4.72489, "alpha":-0.01883, "fx":[74.65082,74.64919,74.50603,74.50792], "fy":[-80.30215,-80.30313,-80.43597,-80.43476]}, + {"t":1.10069, "x":1.34127, "y":5.72044, "heading":0.75925, "vx":-1.04536, "vy":1.13396, "omega":0.02164, "ax":4.38007, "ay":-4.73049, "alpha":-0.04266, "fx":[74.66779,74.66391,74.33887,74.34407], "fy":[-80.31278,-80.31529,-80.61625,-80.61255]}, + {"t":1.13485, "x":1.30811, "y":5.75642, "heading":0.75999, "vx":-0.89572, "vy":0.97235, "omega":0.02019, "ax":4.37636, "ay":-4.73518, "alpha":-0.06267, "fx":[74.68215,74.67617,74.19771,74.20655], "fy":[-80.32157,-80.32563,-80.76782,-80.76119]}, + {"t":1.16901, "x":1.28006, "y":5.78688, "heading":0.76068, "vx":-0.74621, "vy":0.81058, "omega":0.01805, "ax":4.3732, "ay":-4.73917, "alpha":-0.07972, "fx":[74.69448,74.68654,74.07694,74.0895], "fy":[-80.32895,-80.33456,-80.89705,-80.88729]}, + {"t":1.20318, "x":1.25712, "y":5.81181, "heading":0.7613, "vx":-0.5968, "vy":0.64867, "omega":0.01532, "ax":4.37047, "ay":-4.74261, "alpha":-0.09441, "fx":[74.70517,74.69542,73.97242,73.98869], "fy":[-80.33522,-80.34234,-81.00854,-80.99561]}, + {"t":1.23734, "x":1.23928, "y":5.8312, "heading":0.76182, "vx":-0.44749, "vy":0.48664, "omega":0.0121, "ax":4.36809, "ay":-4.7456, "alpha":-0.10721, "fx":[74.71452,74.70311,73.88111,73.90093], "fy":[-80.34062,-80.34918,-81.10568,-81.08966]}, + {"t":1.27151, "x":1.22654, "y":5.84506, "heading":0.76224, "vx":-0.29826, "vy":0.32452, "omega":0.00843, "ax":4.36599, "ay":-4.74822, "alpha":-0.11846, "fx":[74.72276,74.70986,73.80066,73.82384], "fy":[-80.34535,-80.3552,-81.19107,-81.17212]}, + {"t":1.30567, "x":1.2189, "y":5.85337, "heading":0.76252, "vx":-0.1491, "vy":0.1623, "omega":0.00439, "ax":4.36413, "ay":-4.75055, "alpha":-0.12842, "fx":[74.73004,74.71585,73.72927,73.75555], "fy":[-80.34953,-80.36054,-81.2667,-81.24501]}, + {"t":1.33983, "x":1.21635, "y":5.85615, "heading":0.76267, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.82875, "ay":-4.1988, "alpha":2.70745, "fx":[72.75349,73.46399,89.5518,92.77341], "fy":[-82.1239,-81.53275,-63.44657,-58.57843]}, + {"t":1.37576, "x":1.21947, "y":5.85344, "heading":0.76267, "vx":0.17349, "vy":-0.15086, "omega":0.09728, "ax":4.82904, "ay":-4.19876, "alpha":2.68863, "fx":[72.83116,73.51974,89.51037,92.70107], "fy":[-82.04156,-81.47167,-63.49137,-58.6745]}, + {"t":1.41169, "x":1.22882, "y":5.84531, "heading":0.76617, "vx":0.34699, "vy":-0.30171, "omega":0.19387, "ax":4.82938, "ay":-4.19869, "alpha":2.66734, "fx":[72.88099,73.61596,89.49085,92.59736], "fy":[-81.98195,-81.37234,-63.5031,-58.81685]}, + {"t":1.44762, "x":1.2444, "y":5.83175, "heading":0.77314, "vx":0.52051, "vy":-0.45257, "omega":0.28971, "ax":4.82976, "ay":-4.19859, "alpha":2.64283, "fx":[72.90758,73.7537,89.49066,92.45968], "fy":[-81.94062,-81.23311,-63.48491,-59.00835]}, + {"t":1.48355, "x":1.26622, "y":5.81278, "heading":0.78354, "vx":0.69403, "vy":-0.60342, "omega":0.38466, "ax":4.83022, "ay":-4.19844, "alpha":2.61415, "fx":[72.91736,73.93462,89.50622,92.28422], "fy":[-81.91128,-81.05154,-63.4411,-59.25333]}, + {"t":1.51948, "x":1.29428, "y":5.78839, "heading":0.79736, "vx":0.86758, "vy":-0.75426, "omega":0.47859, "ax":4.83075, "ay":-4.19826, "alpha":2.57994, "fx":[72.91908,74.16105,89.53259,92.06565], "fy":[-81.8853,-80.82412,-63.37759,-59.55776]}, + {"t":1.55541, "x":1.32857, "y":5.75859, "heading":0.81456, "vx":1.04114, "vy":-0.9051, "omega":0.57128, "ax":4.83137, "ay":-4.19803, "alpha":2.5383, "fx":[72.92477,74.43638,89.56281,91.79661], "fy":[-81.85077,-80.54591,-63.30269,-59.92978]}, + {"t":1.59133, "x":1.36909, "y":5.72336, "heading":0.83509, "vx":1.21472, "vy":-1.05593, "omega":0.66248, "ax":4.8321, "ay":-4.19774, "alpha":2.4865, "fx":[72.9512,74.76544,89.58688,91.46682], "fy":[-81.79095,-80.2097,-63.2284,-60.38045]}, + {"t":1.62726, "x":1.41585, "y":5.68271, "heading":0.85889, "vx":1.38834, "vy":-1.20675, "omega":0.75181, "ax":4.83296, "ay":-4.19737, "alpha":2.42042, "fx":[73.0226,75.15552,89.58971,91.06149], "fy":[-81.68135,-79.80469,-63.17274,-60.92527]}, + {"t":1.66319, "x":1.46885, "y":5.63664, "heading":0.8859, "vx":1.56198, "vy":-1.35756, "omega":0.83878, "ax":4.83399, "ay":-4.19685, "alpha":2.33347, "fx":[73.17574,75.6182,89.54729,90.55825], "fy":[-81.48419,-79.31363,-63.16429,-61.58698]}, + {"t":1.69912, "x":1.52809, "y":5.58516, "heading":0.91604, "vx":1.73566, "vy":-1.50834, "omega":0.92262, "ax":4.83522, "ay":-4.19608, "alpha":2.21443, "fx":[73.4704,76.17346,89.41824,89.92073], "fy":[-81.13649,-78.70666,-63.25174,-62.40148]}, + {"t":1.73505, "x":1.59357, "y":5.52826, "heading":0.94918, "vx":1.90938, "vy":-1.6591, "omega":1.00218, "ax":4.83665, "ay":-4.19475, "alpha":2.04208, "fx":[74.01337,76.85971,89.12323,89.08356], "fy":[-80.52181,-77.9261,-63.52658,-63.43145]}, + {"t":1.77098, "x":1.6653, "y":5.46594, "heading":0.98519, "vx":2.08316, "vy":-1.80982, "omega":1.07555, "ax":4.83814, "ay":-4.19205, "alpha":1.77054, "fx":[75.02185,77.76245,88.48517,87.91194], "fy":[-79.39165,-76.84185,-64.18653,-64.80221]}, + {"t":1.80691, "x":1.74327, "y":5.39821, "heading":1.02383, "vx":2.25698, "vy":-1.96043, "omega":1.13916, "ax":4.83866, "ay":-4.18509, "alpha":1.27736, "fx":[77.02888,79.1196,87.00265,86.06557], "fy":[-77.08872,-75.08142,-65.76185,-66.8169]}, + {"t":1.84284, "x":1.82748, "y":5.32507, "heading":1.06476, "vx":2.43083, "vy":-2.1108, "omega":1.18505, "ax":4.82847, "ay":-4.15752, "alpha":0.08128, "fx":[81.80523,81.92647,82.45431,82.33778], "fy":[-71.08926,-70.96634,-70.34886,-70.46819]}, + {"t":1.87877, "x":1.91793, "y":5.24655, "heading":1.10734, "vx":2.60431, "vy":-2.26017, "omega":1.18797, "ax":4.35986, "ay":-3.53315, "alpha":-8.6212, "fx":[98.67691,97.69503,33.09915,67.16874], "fy":[-37.25267,-23.82837,-97.53123,-81.7789]}, + {"t":1.91469, "x":2.01432, "y":5.16307, "heading":1.15002, "vx":2.76096, "vy":-2.38711, "omega":0.87823, "ax":-4.3683, "ay":3.54187, "alpha":8.67554, "fx":[-99.46426,-97.61552,-31.96945,-68.16497], "fy":[35.88831,25.17527,98.56491,81.35641]}, + {"t":1.95062, "x":2.11069, "y":5.07959, "heading":1.18158, "vx":2.60401, "vy":-2.25986, "omega":1.18993, "ax":-4.82711, "ay":4.16134, "alpha":0.03306, "fx":[-82.24859,-82.17568,-81.96656,-82.04024], "fy":[70.6219,70.70014,70.94468,70.866]}, + {"t":1.98655, "x":2.20114, "y":5.00108, "heading":1.22433, "vx":2.43058, "vy":-2.11035, "omega":1.19111, "ax":-4.83805, "ay":4.18719, "alpha":-1.25176, "fx":[-76.54239,-80.1913,-87.4916,-84.95001], "fy":[77.60343,73.95346,65.10348,68.23103]}, + {"t":2.02248, "x":2.28534, "y":4.92796, "heading":1.26712, "vx":2.25675, "vy":-1.95991, "omega":1.14614, "ax":-4.83734, "ay":4.19289, "alpha":-1.77806, "fx":[-73.79937,-79.75049,-89.66857,-85.90831], "fy":[80.56116,74.79293,62.50511,67.42017]}, + {"t":2.05841, "x":2.3633, "y":4.86025, "heading":1.3083, "vx":2.08295, "vy":-1.80926, "omega":1.08226, "ax":-4.83578, "ay":4.19476, "alpha":-2.06177, "fx":[-72.18118,-79.75552,-90.89376,-86.19034], "fy":[82.20111,74.97524,60.9436,67.28683]}, + {"t":2.09434, "x":2.43502, "y":4.79795, "heading":1.34719, "vx":1.90921, "vy":-1.65855, "omega":1.00818, "ax":-4.83441, "ay":4.19554, "alpha":-2.23732, "fx":[-71.11775,-79.93431,-91.70716,-86.16851], "fy":[83.23978,74.89914,59.8593,67.46138]}, + {"t":2.13027, "x":2.5005, "y":4.74107, "heading":1.38341, "vx":1.73551, "vy":-1.50781, "omega":0.9278, "ax":-4.8333, "ay":4.19594, "alpha":-2.35568, "fx":[-70.37377,-80.18581,-92.29826,-85.9943], "fy":[83.94952,74.70708,59.04466,67.78543]}, + {"t":2.1662, "x":2.55973, "y":4.6896, "heading":1.41674, "vx":1.56186, "vy":-1.35705, "omega":0.84316, "ax":-4.83239, "ay":4.19619, "alpha":-2.44047, "fx":[-69.8326,-80.46338,-92.75142,-85.74295], "fy":[84.45806,74.4637,58.40398,68.17824]}, + {"t":2.20212, "x":2.61273, "y":4.64355, "heading":1.44704, "vx":1.38824, "vy":-1.20629, "omega":0.75548, "ax":-4.83163, "ay":4.19638, "alpha":-2.50412, "fx":[-69.42846,-80.74237,-93.11058,-85.45723], "fy":[84.83434,74.20312,57.88608,68.59362]}, + {"t":2.23805, "x":2.65949, "y":4.60292, "heading":1.47418, "vx":1.21464, "vy":-1.05552, "omega":0.66551, "ax":-4.83098, "ay":4.19655, "alpha":-2.55375, "fx":[-69.12059,-81.00851,-93.40132,-85.16394], "fy":[85.11956,73.94537,57.4604,69.00293]}, + {"t":2.27398, "x":2.70001, "y":4.56771, "heading":1.49809, "vx":1.04107, "vy":-0.90474, "omega":0.57375, "ax":-4.83041, "ay":4.19669, "alpha":-2.59366, "fx":[-68.88183,-81.25293,-93.63987,-84.88111], "fy":[85.34028,73.70314,57.10706,69.38742]}, + {"t":2.30991, "x":2.7343, "y":4.53791, "heading":1.51871, "vx":0.86752, "vy":-0.75396, "omega":0.48057, "ax":-4.82991, "ay":4.19681, "alpha":-2.62661, "fx":[-68.69311,-81.46988,-93.83723,-84.62144], "fy":[85.51466,73.48496,56.81227,69.73433]}, + {"t":2.34584, "x":2.76235, "y":4.51353, "heading":1.53597, "vx":0.69399, "vy":-0.60317, "omega":0.38619, "ax":-4.82947, "ay":4.19691, "alpha":-2.65439, "fx":[-68.54055,-81.65546,-94.0012,-84.39426], "fy":[85.65562,73.29684,56.56595,70.03472]}, + {"t":2.38177, "x":2.78416, "y":4.49457, "heading":1.54985, "vx":0.52047, "vy":-0.45238, "omega":0.29083, "ax":-4.82907, "ay":4.19699, "alpha":-2.67824, "fx":[-68.41373,-81.80694,-94.13753,-84.20653], "fy":[85.77264,73.14312,56.36058,70.28216]}, + {"t":2.4177, "x":2.79975, "y":4.48102, "heading":1.5603, "vx":0.34697, "vy":-0.30159, "omega":0.1946, "ax":-4.82873, "ay":4.19705, "alpha":-2.69899, "fx":[-68.30479,-81.92234,-94.25049,-84.06356], "fy":[85.87281,73.02707,56.19041,70.47195]}, + {"t":2.45363, "x":2.8091, "y":4.4729, "heading":1.56729, "vx":0.17348, "vy":-0.1508, "omega":0.09763, "ax":-4.82843, "ay":4.19708, "alpha":-2.71728, "fx":[-68.20778,-82.00016,-94.34328,-83.9694], "fy":[85.96141,72.95116,56.05111,70.60054]}, + {"t":2.48955, "x":2.81221, "y":4.47019, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_4_BACK.traj b/src/main/deploy/choreo/E_RIGHT_PATH_4_BACK.traj new file mode 100644 index 00000000..7cedf691 --- /dev/null +++ b/src/main/deploy/choreo/E_RIGHT_PATH_4_BACK.traj @@ -0,0 +1,119 @@ +{ + "name":"E_RIGHT_PATH_4_BACK", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.1932778358459473, "y":4.194243907928467, "heading":1.5707963267948966, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.9559978246688845, "y":5.059605598449707, "heading":0.7626747895755805, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.2163536548614502, "y":5.85614538192749, "heading":0.7626747895755805, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.812213182449341, "y":4.470187187194824, "heading":1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.1932778358459473 m", "val":3.1932778358459473}, "y":{"exp":"4.194243907928467 m", "val":4.194243907928467}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.9559978246688843 m", "val":1.9559978246688845}, "y":{"exp":"5.059605598449707 m", "val":5.059605598449707}, "heading":{"exp":"0.7626747895755805 rad", "val":0.7626747895755805}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.2163536548614502 m", "val":1.2163536548614502}, "y":{"exp":"5.85614538192749 m", "val":5.85614538192749}, "heading":{"exp":"0.7626747895755805 rad", "val":0.7626747895755805}, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.812213182449341 m", "val":2.812213182449341}, "y":{"exp":"4.470187187194824 m", "val":4.470187187194824}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.70227,1.28366,2.43338], + "samples":[ + {"t":0.0, "x":3.19328, "y":4.19424, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.27912, "ay":3.28254, "alpha":-5.61057, "fx":[-63.41662,-89.03718,-106.88978,-99.84165], "fy":[89.47213,64.11986,24.64636,45.1016]}, + {"t":0.02422, "x":3.19173, "y":4.19521, "heading":1.5708, "vx":-0.12784, "vy":0.07949, "omega":-0.13587, "ax":-5.27867, "ay":3.29337, "alpha":-5.53983, "fx":[-63.75912,-89.01306,-106.76459,-99.61766], "fy":[89.21791,64.14212,25.14945,45.56776]}, + {"t":0.04843, "x":3.18709, "y":4.1981, "heading":1.56751, "vx":-0.25567, "vy":0.15924, "omega":-0.27002, "ax":-5.27798, "ay":3.30458, "alpha":-5.46873, "fx":[-64.10657,-88.92846,-106.6117,-99.46079], "fy":[88.9568,64.247,25.75455,45.88138]}, + {"t":0.07265, "x":3.17935, "y":4.20292, "heading":1.56097, "vx":-0.38348, "vy":0.23927, "omega":-0.40245, "ax":-5.27704, "ay":3.31635, "alpha":-5.39575, "fx":[-64.46636,-88.78541,-106.42854,-99.36334], "fy":[88.68313,64.43092,26.46416,46.06266]}, + {"t":0.09686, "x":3.16851, "y":4.20969, "heading":1.55122, "vx":-0.51127, "vy":0.31958, "omega":-0.53312, "ax":-5.27582, "ay":3.32892, "alpha":-5.31926, "fx":[-64.8477,-88.58603,-106.21177,-99.31537], "fy":[88.3897,64.6897,27.28201,46.13468]}, + {"t":0.12108, "x":3.15459, "y":4.2184, "heading":1.53831, "vx":-0.63903, "vy":0.40019, "omega":-0.66193, "ax":-5.27429, "ay":3.34255, "alpha":-5.23738, "fx":[-65.26171,-88.33268,-105.95715,-99.30483], "fy":[88.06753,65.01846,28.21332,46.1238]}, + {"t":0.1453, "x":3.13756, "y":4.22907, "heading":1.52228, "vx":-0.76675, "vy":0.48113, "omega":-0.78876, "ax":-5.27238, "ay":3.35752, "alpha":-5.14785, "fx":[-65.72166,-88.02814,-105.65931,-99.31757], "fy":[87.70561,65.41142,29.26491,46.06015]}, + {"t":0.16951, "x":3.11745, "y":4.24171, "heading":1.50318, "vx":-0.89443, "vy":0.56244, "omega":-0.91342, "ax":-5.27005, "ay":3.37419, "alpha":-5.04788, "fx":[-66.2432,-87.67589,-105.31151,-99.3373], "fy":[87.29049,65.86172,30.44557,45.9783]}, + {"t":0.19373, "x":3.09425, "y":4.25632, "heading":1.48106, "vx":-1.02205, "vy":0.64415, "omega":-1.03566, "ax":-5.26722, "ay":3.39293, "alpha":-4.93394, "fx":[-66.84456,-87.28034,-104.90521,-99.34537], "fy":[86.80583,66.36108,31.76648,45.91802]}, + {"t":0.21795, "x":3.06795, "y":4.27291, "heading":1.45598, "vx":-1.1496, "vy":0.72631, "omega":-1.15514, "ax":-5.26382, "ay":3.4142, "alpha":-4.80157, "fx":[-67.54685,-86.84735,-104.42946,-99.32034], "fy":[86.23172,66.89937,33.24186,45.92514]}, + {"t":0.24216, "x":3.03857, "y":4.2915, "heading":1.42801, "vx":-1.27707, "vy":0.80899, "omega":-1.27141, "ax":-5.25973, "ay":3.43849, "alpha":-4.64513, "fx":[-68.37417,-86.3848,-103.87005,-99.23718], "fy":[85.54398,67.46399,34.89001,46.05274]}, + {"t":0.26638, "x":3.0061, "y":4.3121, "heading":1.39722, "vx":-1.40444, "vy":0.89226, "omega":-1.3839, "ax":-5.25481, "ay":3.46639, "alpha":-4.45747, "fx":[-69.35371,-85.90345,-103.2081,-99.06591], "fy":[84.71313,68.03893,36.73484,46.36253]}, + {"t":0.29059, "x":2.97055, "y":4.33473, "heading":1.36371, "vx":-1.53169, "vy":0.9762, "omega":-1.49184, "ax":-5.24878, "ay":3.49862, "alpha":-4.22959, "fx":[-70.51554,-85.41824,-102.41788,-98.76935], "fy":[83.70321,68.60333,38.80836,46.92689]}, + {"t":0.31481, "x":2.93192, "y":4.35939, "heading":1.32758, "vx":-1.6588, "vy":1.06092, "omega":-1.59427, "ax":-5.24119, "ay":3.53601, "alpha":-3.95009, "fx":[-71.89217,-84.95026,-101.46304,-98.29943], "fy":[82.47039,69.12925,41.15471,47.8316]}, + {"t":0.33903, "x":2.89021, "y":4.38612, "heading":1.28897, "vx":-1.78572, "vy":1.14655, "omega":-1.68992, "ax":-5.23125, "ay":3.57966, "alpha":-3.60433, "fx":[-73.51746,-84.5299,-100.2901,-97.59107], "fy":[80.9612,69.57778,43.8369,49.17984]}, + {"t":0.36324, "x":2.84544, "y":4.41493, "heading":1.24805, "vx":-1.9124, "vy":1.23324, "omega":-1.77721, "ax":-5.21754, "ay":3.631, "alpha":-3.17303, "fx":[-75.42483,-84.20212,-98.81631,-96.5522], "fy":[79.11066,69.89228,46.94856,51.09784]}, + {"t":0.38746, "x":2.7976, "y":4.44586, "heading":1.20501, "vx":-2.03875, "vy":1.32117, "omega":-1.85405, "ax":-5.19751, "ay":3.69206, "alpha":-2.62962, "fx":[-77.64437,-84.03583,-96.90548,-95.04672], "fy":[76.84009,69.98547,50.63521,53.74263]}, + {"t":0.41167, "x":2.7467, "y":4.47894, "heading":1.16012, "vx":-2.16461, "vy":1.41057, "omega":-1.91772, "ax":-5.16649, "ay":3.7657, "alpha":-1.93478, "fx":[-80.19863,-84.14191,-94.31626,-92.8655], "fy":[74.05496,69.71272,55.13468,57.3116]}, + {"t":0.43589, "x":2.69277, "y":4.5142, "heading":1.11368, "vx":-2.28972, "vy":1.50177, "omega":-1.96458, "ax":-5.11564, "ay":3.85605, "alpha":-1.024, "fx":[-83.09674,-84.7104,-90.57928,-89.6757], "fy":[70.64276,68.81103,60.8571,62.05048]}, + {"t":0.46011, "x":2.63582, "y":4.5517, "heading":1.0661, "vx":-2.41361, "vy":1.59514, "omega":-1.98938, "ax":-5.02689, "ay":3.96836, "alpha":0.22429, "fx":[-86.32606,-86.09521,-84.66858,-84.93393], "fy":[66.47177,66.73921,68.54522,68.24646]}, + {"t":0.48432, "x":2.5759, "y":4.59149, "heading":1.01793, "vx":-2.53534, "vy":1.69124, "omega":-1.98394, "ax":-4.85902, "ay":4.10456, "alpha":2.08493, "fx":[-89.8387,-89.02401,-73.98932,-77.74992], "fy":[61.3953,62.17547,79.53672,76.1621]}, + {"t":0.50854, "x":2.51308, "y":4.63365, "heading":0.96988, "vx":-2.653, "vy":1.79064, "omega":-1.93345, "ax":-4.50248, "ay":4.2237, "alpha":5.32203, "fx":[-93.51547,-95.07917,-50.99151,-66.75721], "fy":[55.29486,50.98694,95.31456,85.77901]}, + {"t":0.53275, "x":2.44751, "y":4.67825, "heading":0.92306, "vx":-2.76204, "vy":1.89292, "omega":-1.80458, "ax":-3.6959, "ay":3.94587, "alpha":12.00321, "fx":[-96.93369,-104.85756,0.99175,-50.66499], "fy":[48.55606,16.59681,107.34336,95.97614]}, + {"t":0.55697, "x":2.37954, "y":4.72525, "heading":0.87936, "vx":-2.85154, "vy":1.98847, "omega":-1.5139, "ax":-3.10245, "ay":3.79241, "alpha":14.8783, "fx":[-94.98715,-104.10939,27.73879,-39.7293], "fy":[51.46523,2.75604,103.13796,100.67202]}, + {"t":0.58119, "x":2.30958, "y":4.77451, "heading":0.8427, "vx":-2.92667, "vy":2.08031, "omega":-1.15361, "ax":-2.55577, "ay":4.23901, "alpha":13.96139, "fx":[-88.06742,-97.34294,39.96174,-28.44285], "fy":[61.36816,24.75565,98.38878,103.90455]}, + {"t":0.6054, "x":2.23796, "y":4.82613, "heading":0.81477, "vx":-2.98856, "vy":2.18296, "omega":-0.81552, "ax":-0.72216, "ay":5.15449, "alpha":10.85612, "fx":[-72.35098,-30.87829,61.02861,-6.93421], "fy":[77.41295,80.21664,86.31444,106.76142]}, + {"t":0.62962, "x":2.16537, "y":4.88051, "heading":0.79502, "vx":-3.00604, "vy":2.30779, "omega":-0.55263, "ax":1.9802, "ay":5.54963, "alpha":5.63734, "fx":[-4.80531,51.35441,62.72135,25.45982], "fy":[103.64924,87.28615,84.17369,102.48162]}, + {"t":0.65384, "x":2.09316, "y":4.93802, "heading":0.78163, "vx":-2.95809, "vy":2.44218, "omega":-0.41611, "ax":4.92382, "ay":3.66235, "alpha":2.03505, "fx":[77.75064,90.54149,88.90168,77.81727], "fy":[69.55454,52.16645,56.56361,70.89771]}, + {"t":0.67805, "x":2.02297, "y":4.99823, "heading":0.77156, "vx":-2.83886, "vy":2.53086, "omega":-0.36683, "ax":6.0527, "ay":0.28805, "alpha":5.50721, "fx":[104.70939,101.13859,107.6909,98.27996], "fy":[8.83663,-35.11592,3.13793,42.74008]}, + {"t":0.70227, "x":1.956, "y":5.05961, "heading":0.76267, "vx":-2.69228, "vy":2.53784, "omega":-0.23347, "ax":6.0301, "ay":-1.85772, "alpha":3.16684, "fx":[100.86798,95.88802,105.39485,108.13044], "fy":[-39.24527,-51.10159,-26.93801,-9.11245]}, + {"t":0.73647, "x":1.86745, "y":5.14531, "heading":0.75469, "vx":-2.48606, "vy":2.47431, "omega":-0.12516, "ax":5.53491, "ay":-3.17708, "alpha":1.8848, "fx":[90.64275,88.42937,97.35053,100.16599], "fy":[-60.32867,-63.79999,-49.20001,-42.83652]}, + {"t":0.77067, "x":1.78567, "y":5.22807, "heading":0.75041, "vx":-2.29677, "vy":2.36565, "omega":-0.0607, "ax":5.17799, "ay":-3.77937, "alpha":1.19873, "fx":[84.99928,84.00033,90.87655,92.42818], "fy":[-68.51186,-69.84777,-60.6527,-58.1318]}, + {"t":0.80487, "x":1.71015, "y":5.30677, "heading":0.74833, "vx":-2.11968, "vy":2.2364, "omega":-0.01971, "ax":4.93828, "ay":-4.10925, "alpha":0.79489, "fx":[81.63101,81.1585,86.20677,86.99859], "fy":[-72.73188,-73.31566,-67.31442,-66.22674]}, + {"t":0.83907, "x":1.64054, "y":5.38085, "heading":0.74766, "vx":-1.9508, "vy":2.09587, "omega":0.00748, "ax":4.77084, "ay":-4.31412, "alpha":0.53249, "fx":[79.42296,79.1993,82.79617,83.18406], "fy":[-75.28227,-75.54794,-71.59043,-71.10748]}, + {"t":0.87326, "x":1.57662, "y":5.45, "heading":0.74792, "vx":-1.78764, "vy":1.94833, "omega":0.02569, "ax":4.64849, "ay":-4.45274, "alpha":0.34915, "fx":[77.87187,77.77205,80.22891,80.40529], "fy":[-76.983,-77.10042,-74.54148,-74.3341]}, + {"t":0.90746, "x":1.5182, "y":5.51403, "heading":0.74879, "vx":-1.62866, "vy":1.79605, "omega":0.03763, "ax":4.5556, "ay":-4.55239, "alpha":0.21409, "fx":[76.72568,76.68754,78.23819,78.30669], "fy":[-78.19506,-78.24117,-76.6909,-76.61209]}, + {"t":0.94166, "x":1.46516, "y":5.57279, "heading":0.75008, "vx":-1.47287, "vy":1.64036, "omega":0.04495, "ax":4.48285, "ay":-4.62733, "alpha":0.11056, "fx":[75.84573,75.83593,76.65408,76.67229], "fy":[-79.10111,-79.11444,-78.32207,-78.30028]}, + {"t":0.97586, "x":1.41741, "y":5.62618, "heading":0.75162, "vx":-1.31956, "vy":1.48211, "omega":0.04873, "ax":4.4244, "ay":-4.68565, "alpha":0.02873, "fx":[75.14982,75.14946,75.36561,75.36655], "fy":[-79.80318,-79.80443,-79.60034,-79.59854]}, + {"t":1.01006, "x":1.37487, "y":5.67413, "heading":0.75328, "vx":-1.16824, "vy":1.32186, "omega":0.04971, "ax":4.37646, "ay":-4.7323, "alpha":-0.03755, "fx":[74.58623,74.58423,74.29806,74.30108], "fy":[-80.36266,-80.36345,-80.6281,-80.62638]}, + {"t":1.04426, "x":1.33748, "y":5.71657, "heading":0.75498, "vx":-1.01857, "vy":1.16002, "omega":0.04843, "ax":4.33645, "ay":-4.77044, "alpha":-0.09232, "fx":[74.12086,74.11062,73.39963,73.41613], "fy":[-80.81864,-80.82566,-81.47191,-81.4594]}, + {"t":1.07846, "x":1.30518, "y":5.75345, "heading":0.75664, "vx":-0.87027, "vy":0.99687, "omega":0.04527, "ax":4.30256, "ay":-4.8022, "alpha":-0.13832, "fx":[73.73031,73.70795,72.63337,72.66997], "fy":[-81.19722,-81.21426,-82.17679,-82.14765]}, + {"t":1.11266, "x":1.27793, "y":5.78474, "heading":0.75819, "vx":-0.72312, "vy":0.83264, "omega":0.04054, "ax":4.2735, "ay":-4.82903, "alpha":-0.17751, "fx":[73.39797,73.36136,71.97233,72.03265], "fy":[-81.51646,-81.54556,-82.77422,-82.72553]}, + {"t":1.14686, "x":1.2557, "y":5.81039, "heading":0.75958, "vx":-0.57697, "vy":0.66749, "omega":0.03447, "ax":4.24831, "ay":-4.85201, "alpha":-0.21128, "fx":[73.11177,73.05992,71.3964,71.48216], "fy":[-81.78928,-81.83134,-83.28687,-83.21745]}, + {"t":1.18106, "x":1.23846, "y":5.83038, "heading":0.76075, "vx":-0.43168, "vy":0.50156, "omega":0.02724, "ax":4.22627, "ay":-4.87189, "alpha":-0.24069, "fx":[72.8627,72.79541,70.89031,71.00192], "fy":[-82.02512,-82.08031,-83.73142,-83.64122]}, + {"t":1.21526, "x":1.22616, "y":5.84468, "heading":0.76169, "vx":-0.28715, "vy":0.33494, "omega":0.01901, "ax":4.20682, "ay":-4.88928, "alpha":-0.26653, "fx":[72.64389,72.56156,70.44224,70.57928], "fy":[-82.23111,-82.29906,-84.12044,-84.01008]}, + {"t":1.24946, "x":1.2188, "y":5.85328, "heading":0.76234, "vx":-0.14328, "vy":0.16773, "omega":0.0099, "ax":4.18953, "ay":-4.90459, "alpha":-0.28941, "fx":[72.45003,72.35348,70.04294,70.20435], "fy":[-82.41266,-82.49265,-84.46357,-84.33413]}, + {"t":1.28366, "x":1.21635, "y":5.85615, "heading":0.76267, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.82875, "ay":-4.1988, "alpha":2.70745, "fx":[72.75349,73.46399,89.5518,92.77341], "fy":[-82.1239,-81.53275,-63.44657,-58.57843]}, + {"t":1.31958, "x":1.21947, "y":5.85344, "heading":0.76267, "vx":0.17349, "vy":-0.15086, "omega":0.09728, "ax":4.82904, "ay":-4.19876, "alpha":2.68863, "fx":[72.83116,73.51974,89.51037,92.70107], "fy":[-82.04156,-81.47167,-63.49137,-58.6745]}, + {"t":1.35551, "x":1.22882, "y":5.84531, "heading":0.76617, "vx":0.34699, "vy":-0.30171, "omega":0.19387, "ax":4.82938, "ay":-4.19869, "alpha":2.66734, "fx":[72.88099,73.61596,89.49085,92.59736], "fy":[-81.98195,-81.37234,-63.5031,-58.81685]}, + {"t":1.39144, "x":1.2444, "y":5.83175, "heading":0.77314, "vx":0.52051, "vy":-0.45257, "omega":0.28971, "ax":4.82976, "ay":-4.19859, "alpha":2.64283, "fx":[72.90758,73.7537,89.49066,92.45968], "fy":[-81.94062,-81.23311,-63.48491,-59.00835]}, + {"t":1.42737, "x":1.26622, "y":5.81278, "heading":0.78354, "vx":0.69403, "vy":-0.60342, "omega":0.38466, "ax":4.83022, "ay":-4.19844, "alpha":2.61415, "fx":[72.91736,73.93462,89.50622,92.28422], "fy":[-81.91128,-81.05154,-63.4411,-59.25333]}, + {"t":1.4633, "x":1.29428, "y":5.78839, "heading":0.79736, "vx":0.86758, "vy":-0.75426, "omega":0.47859, "ax":4.83075, "ay":-4.19826, "alpha":2.57994, "fx":[72.91908,74.16105,89.53259,92.06565], "fy":[-81.8853,-80.82412,-63.37759,-59.55776]}, + {"t":1.49923, "x":1.32857, "y":5.75859, "heading":0.81456, "vx":1.04114, "vy":-0.9051, "omega":0.57128, "ax":4.83137, "ay":-4.19803, "alpha":2.5383, "fx":[72.92477,74.43638,89.56281,91.79661], "fy":[-81.85077,-80.54591,-63.30269,-59.92978]}, + {"t":1.53516, "x":1.36909, "y":5.72336, "heading":0.83509, "vx":1.21472, "vy":-1.05593, "omega":0.66248, "ax":4.8321, "ay":-4.19774, "alpha":2.4865, "fx":[72.9512,74.76544,89.58688,91.46682], "fy":[-81.79095,-80.2097,-63.2284,-60.38045]}, + {"t":1.57109, "x":1.41585, "y":5.68271, "heading":0.85889, "vx":1.38834, "vy":-1.20675, "omega":0.75181, "ax":4.83296, "ay":-4.19737, "alpha":2.42042, "fx":[73.0226,75.15552,89.58971,91.06149], "fy":[-81.68135,-79.80469,-63.17274,-60.92527]}, + {"t":1.60701, "x":1.46885, "y":5.63664, "heading":0.8859, "vx":1.56198, "vy":-1.35756, "omega":0.83878, "ax":4.83399, "ay":-4.19685, "alpha":2.33347, "fx":[73.17574,75.6182,89.54729,90.55825], "fy":[-81.48419,-79.31363,-63.16429,-61.58698]}, + {"t":1.64294, "x":1.52809, "y":5.58516, "heading":0.91604, "vx":1.73566, "vy":-1.50834, "omega":0.92262, "ax":4.83522, "ay":-4.19608, "alpha":2.21443, "fx":[73.4704,76.17346,89.41824,89.92073], "fy":[-81.13649,-78.70666,-63.25174,-62.40148]}, + {"t":1.67887, "x":1.59357, "y":5.52826, "heading":0.94918, "vx":1.90938, "vy":-1.6591, "omega":1.00218, "ax":4.83665, "ay":-4.19475, "alpha":2.04208, "fx":[74.01337,76.85971,89.12323,89.08356], "fy":[-80.52181,-77.9261,-63.52658,-63.43145]}, + {"t":1.7148, "x":1.6653, "y":5.46594, "heading":0.98519, "vx":2.08316, "vy":-1.80982, "omega":1.07555, "ax":4.83814, "ay":-4.19205, "alpha":1.77054, "fx":[75.02185,77.76245,88.48517,87.91194], "fy":[-79.39165,-76.84185,-64.18653,-64.80221]}, + {"t":1.75073, "x":1.74327, "y":5.39821, "heading":1.02383, "vx":2.25698, "vy":-1.96043, "omega":1.13916, "ax":4.83866, "ay":-4.18509, "alpha":1.27736, "fx":[77.02888,79.1196,87.00265,86.06557], "fy":[-77.08872,-75.08142,-65.76185,-66.8169]}, + {"t":1.78666, "x":1.82748, "y":5.32507, "heading":1.06476, "vx":2.43083, "vy":-2.1108, "omega":1.18505, "ax":4.82847, "ay":-4.15752, "alpha":0.08128, "fx":[81.80523,81.92647,82.45431,82.33778], "fy":[-71.08926,-70.96634,-70.34886,-70.46819]}, + {"t":1.82259, "x":1.91793, "y":5.24655, "heading":1.10734, "vx":2.60431, "vy":-2.26017, "omega":1.18797, "ax":4.35986, "ay":-3.53315, "alpha":-8.6212, "fx":[98.67691,97.69503,33.09915,67.16874], "fy":[-37.25267,-23.82837,-97.53123,-81.7789]}, + {"t":1.85852, "x":2.01432, "y":5.16307, "heading":1.15002, "vx":2.76096, "vy":-2.38711, "omega":0.87823, "ax":-4.3683, "ay":3.54187, "alpha":8.67554, "fx":[-99.46426,-97.61552,-31.96945,-68.16497], "fy":[35.88831,25.17527,98.56491,81.35641]}, + {"t":1.89444, "x":2.11069, "y":5.07959, "heading":1.18158, "vx":2.60401, "vy":-2.25986, "omega":1.18993, "ax":-4.82711, "ay":4.16134, "alpha":0.03306, "fx":[-82.24859,-82.17568,-81.96656,-82.04024], "fy":[70.6219,70.70014,70.94468,70.866]}, + {"t":1.93037, "x":2.20114, "y":5.00108, "heading":1.22433, "vx":2.43058, "vy":-2.11035, "omega":1.19111, "ax":-4.83805, "ay":4.18719, "alpha":-1.25176, "fx":[-76.54239,-80.1913,-87.4916,-84.95001], "fy":[77.60343,73.95346,65.10348,68.23103]}, + {"t":1.9663, "x":2.28534, "y":4.92796, "heading":1.26712, "vx":2.25675, "vy":-1.95991, "omega":1.14614, "ax":-4.83734, "ay":4.19289, "alpha":-1.77806, "fx":[-73.79937,-79.75049,-89.66857,-85.90831], "fy":[80.56116,74.79293,62.50511,67.42017]}, + {"t":2.00223, "x":2.3633, "y":4.86025, "heading":1.3083, "vx":2.08295, "vy":-1.80926, "omega":1.08226, "ax":-4.83578, "ay":4.19476, "alpha":-2.06177, "fx":[-72.18118,-79.75552,-90.89376,-86.19034], "fy":[82.20111,74.97524,60.9436,67.28683]}, + {"t":2.03816, "x":2.43502, "y":4.79795, "heading":1.34719, "vx":1.90921, "vy":-1.65855, "omega":1.00818, "ax":-4.83441, "ay":4.19554, "alpha":-2.23732, "fx":[-71.11775,-79.93431,-91.70716,-86.16851], "fy":[83.23978,74.89914,59.8593,67.46138]}, + {"t":2.07409, "x":2.5005, "y":4.74107, "heading":1.38341, "vx":1.73551, "vy":-1.50781, "omega":0.9278, "ax":-4.8333, "ay":4.19594, "alpha":-2.35568, "fx":[-70.37377,-80.18581,-92.29826,-85.9943], "fy":[83.94952,74.70708,59.04466,67.78543]}, + {"t":2.11002, "x":2.55973, "y":4.6896, "heading":1.41674, "vx":1.56186, "vy":-1.35705, "omega":0.84316, "ax":-4.83239, "ay":4.19619, "alpha":-2.44047, "fx":[-69.8326,-80.46338,-92.75142,-85.74295], "fy":[84.45806,74.4637,58.40398,68.17824]}, + {"t":2.14595, "x":2.61273, "y":4.64355, "heading":1.44704, "vx":1.38824, "vy":-1.20629, "omega":0.75548, "ax":-4.83163, "ay":4.19638, "alpha":-2.50412, "fx":[-69.42846,-80.74237,-93.11058,-85.45723], "fy":[84.83434,74.20312,57.88608,68.59362]}, + {"t":2.18187, "x":2.65949, "y":4.60292, "heading":1.47418, "vx":1.21464, "vy":-1.05552, "omega":0.66551, "ax":-4.83098, "ay":4.19655, "alpha":-2.55375, "fx":[-69.12059,-81.00851,-93.40132,-85.16394], "fy":[85.11956,73.94537,57.4604,69.00293]}, + {"t":2.2178, "x":2.70001, "y":4.56771, "heading":1.49809, "vx":1.04107, "vy":-0.90474, "omega":0.57375, "ax":-4.83041, "ay":4.19669, "alpha":-2.59366, "fx":[-68.88183,-81.25293,-93.63987,-84.88111], "fy":[85.34028,73.70314,57.10706,69.38742]}, + {"t":2.25373, "x":2.7343, "y":4.53791, "heading":1.51871, "vx":0.86752, "vy":-0.75396, "omega":0.48057, "ax":-4.82991, "ay":4.19681, "alpha":-2.62661, "fx":[-68.69311,-81.46988,-93.83723,-84.62144], "fy":[85.51466,73.48496,56.81227,69.73433]}, + {"t":2.28966, "x":2.76235, "y":4.51353, "heading":1.53597, "vx":0.69399, "vy":-0.60317, "omega":0.38619, "ax":-4.82947, "ay":4.19691, "alpha":-2.65439, "fx":[-68.54055,-81.65546,-94.0012,-84.39426], "fy":[85.65562,73.29684,56.56595,70.03472]}, + {"t":2.32559, "x":2.78416, "y":4.49457, "heading":1.54985, "vx":0.52047, "vy":-0.45238, "omega":0.29083, "ax":-4.82907, "ay":4.19699, "alpha":-2.67824, "fx":[-68.41373,-81.80694,-94.13753,-84.20653], "fy":[85.77264,73.14312,56.36058,70.28216]}, + {"t":2.36152, "x":2.79975, "y":4.48102, "heading":1.5603, "vx":0.34697, "vy":-0.30159, "omega":0.1946, "ax":-4.82873, "ay":4.19705, "alpha":-2.69899, "fx":[-68.30479,-81.92234,-94.25049,-84.06356], "fy":[85.87281,73.02707,56.19041,70.47195]}, + {"t":2.39745, "x":2.8091, "y":4.4729, "heading":1.56729, "vx":0.17348, "vy":-0.1508, "omega":0.09763, "ax":-4.82843, "ay":4.19708, "alpha":-2.71728, "fx":[-68.20778,-82.00016,-94.34328,-83.9694], "fy":[85.96141,72.95116,56.05111,70.60054]}, + {"t":2.43338, "x":2.81221, "y":4.47019, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index 1eac6983..6f781f68 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -1852,21 +1852,18 @@ public static final LoggedAutoRoutine autoDCenter( // return routine; // } - public static final LoggedAutoRoutine autoELeftPath( + public static final LoggedAutoRoutine autoERight( Drive drive, V3_EpsilonSuperstructure superstructure, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator, Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoELeftPath"); - LoggedAutoTrajectory path1 = routine.trajectory("E_LEFT_PATH_1"); - LoggedAutoTrajectory path2 = routine.trajectory("E_LEFT_PATH_2"); - LoggedAutoTrajectory path3 = routine.trajectory("E_LEFT_PATH_3"); - LoggedAutoTrajectory path4 = routine.trajectory("E_LEFT_PATH_4"); - LoggedAutoTrajectory path5 = routine.trajectory("E_LEFT_PATH_5"); - LoggedAutoTrajectory path6 = routine.trajectory("E_LEFT_PATH_6"); - LoggedAutoTrajectory path7 = routine.trajectory("E_LEFT_PATH_7"); + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoERight"); + LoggedAutoTrajectory path1 = routine.trajectory("E_RIGHT_PATH_1"); + LoggedAutoTrajectory path2 = routine.trajectory("E_RIGHT_PATH_2"); + LoggedAutoTrajectory path3 = routine.trajectory("E_RIGHT_PATH_3"); + LoggedAutoTrajectory path4 = routine.trajectory("E_RIGHT_PATH_4"); routine .active() @@ -1876,53 +1873,93 @@ public static final LoggedAutoRoutine autoELeftPath( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), path1.cmd(), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( - drive, superstructure, cameras) - .withTimeout(0.5), - CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral( - superstructure, () -> ReefState.L4), - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake, manipulator) - .withTimeout(0.5), - superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF), - path3.cmd(), + drive, superstructure, ReefState.L4, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path2.cmd(), + superstructure + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .andThen(Commands.waitSeconds((2.0))) + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( - drive, superstructure, cameras) - .withTimeout(0.5), - CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral( - superstructure, () -> ReefState.L4), - path4.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake, manipulator) - .withTimeout(0.5), - path5.cmd(), + drive, superstructure, ReefState.L4, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path3.cmd(), + superstructure + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .andThen(Commands.waitSeconds((1.5))) + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( - drive, superstructure, cameras) - .withTimeout(0.5), - CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral( - superstructure, () -> ReefState.L4), - path6.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake, manipulator) - .withTimeout(0.5), - path7.cmd(), + drive, superstructure, ReefState.L4, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path4.cmd(), + superstructure + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .andThen(Commands.waitSeconds((1.5))) + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( - drive, superstructure, cameras) - .withTimeout(0.5), - CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral( - superstructure, () -> ReefState.L4).withTimeout(1))); - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake, manipulator), - // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral( - // drive, superstructure, cameras), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - // path4.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - // superstructure, intake, manipulator), - // path5.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.scoreCoral( - // drive, superstructure, cameras)); + drive, superstructure, ReefState.L4, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE))); + + return routine; + } + + public static final LoggedAutoRoutine autoERightBack( + Drive drive, + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoERightBack"); + LoggedAutoTrajectory path1 = routine.trajectory("E_RIGHT_PATH_1_BACK"); + LoggedAutoTrajectory path2 = routine.trajectory("E_RIGHT_PATH_2_BACK"); + LoggedAutoTrajectory path3 = routine.trajectory("E_RIGHT_PATH_3_BACK"); + LoggedAutoTrajectory path4 = routine.trajectory("E_RIGHT_PATH_4_BACK"); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, ReefState.L4, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + path2.cmd(), + superstructure + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .andThen(Commands.waitSeconds((1.0))) + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, ReefState.L2, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_SCORE), + Commands.parallel( + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path3.cmd(), + superstructure + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .andThen(Commands.waitSeconds((1.0))) + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, ReefState.L2, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_SCORE), + Commands.parallel( + path4.cmd(), + superstructure + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .andThen(Commands.waitSeconds((1.0))) + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, ReefState.L4, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE))); return routine; } diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 8a2a0ce5..7d67cbb7 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -701,6 +701,25 @@ public static final Command optimalAutoScoreCoralSequence( superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight())); } + public static final Command optimalAutoScoreCoralSequence( + Drive drive, V3_EpsilonSuperstructure superstructure, ReefState height, Camera... cameras) { + return Commands.sequence( + Commands.runOnce( + () -> { + if (RobotState.getOIData().currentReefHeight().equals(ReefState.L1)) { + RobotState.setScoreSide(ScoreSide.CENTER); + } else { + RobotState.setScoreSide( + optimalSide(RobotState.getReefAlignData().coralSetpoint())); + } + }) + .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), + superstructure.runReefGoal(() -> height), + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), + superstructure.runReefScoreGoal(() -> height)); + } + public static final Command optimalAutoAlignReefAlgae( Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { return Commands.sequence( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index e036cec2..aca494a8 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -147,6 +147,6 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { - return AutonomousCommands.autoELeftPath(drive, superstructure, intake, manipulator).cmd(); + return AutonomousCommands.autoERightBack(drive, superstructure, intake, manipulator).cmd(); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index a174a805..6cda9ef0 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -223,4 +223,16 @@ digraph Superstructure { BARGE -> BARGE_SCORE [type=UNCONSTRAINED] BARGE_SCORE -> BARGE [type=UNCONSTRAINED] + + HANDOFF -> GROUND_AQUISITION_ALGAE + PROCESSOR -> GROUND_AQUISITION_ALGAE + + GROUND_AQUISITION_ALGAE -> STOW_UP + GROUND_AQUISITION_ALGAE -> PROCESSOR + + GROUND_AQUISITION_ALGAE -> GROUND_INTAKE_ALGAE + GROUND_INTAKE_ALGAE -> GROUND_AQUISITION_ALGAE + + L2_SCORE -> GROUND_AQUISITION_ALGAE + } \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 74242c25..e98e7291 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -454,7 +454,7 @@ public Command runReefScoreGoal(Supplier goal) { case L1 -> 0.8; case L2 -> 0.15; case L3 -> 0.15; - case L4 -> 0.4; + case L4 -> 0.1; default -> 0; }); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index f2e7e2ff..6d155bb0 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -23,7 +23,6 @@ public enum V3_EpsilonSuperstructureStates { ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.HANDOFF), SubsystemActions.empty()), OVERRIDE("OVERRIDE", new SubsystemPoses(), SubsystemActions.empty()), - GROUND_ACQUISITION( "GROUND_ACQUISITION", new SubsystemPoses( @@ -31,11 +30,13 @@ public enum V3_EpsilonSuperstructureStates { SubsystemActions.empty()), GROUND_INTAKE_ALGAE( "GROUND_INTAKE_ALGAE", - new SubsystemPoses(ReefState.HIGH_STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + new SubsystemPoses( + ReefState.STOW, ManipulatorArmState.ALGAE_INTAKE_FLOOR, IntakePivotState.INTAKE_ALGAE), new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), GROUND_AQUISITION_ALGAE( "GROUND_AQUISITION_ALGAE", - new SubsystemPoses(ReefState.HIGH_STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + new SubsystemPoses( + ReefState.STOW, ManipulatorArmState.ALGAE_INTAKE_FLOOR, IntakePivotState.INTAKE_ALGAE), SubsystemActions.empty()), GROUND_INTAKE( @@ -77,7 +78,7 @@ public enum V3_EpsilonSuperstructureStates { SubsystemActions.empty()), L4_SCORE( "L4_SCORE", - new SubsystemPoses(ReefState.L4, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), + new SubsystemPoses(ReefState.L4, ManipulatorArmState.SCORE_L4, IntakePivotState.HANDOFF), new SubsystemActions(ManipulatorRollerState.L4_SCORE, IntakeRollerState.STOP)), HANDOFF( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index f8453c4a..03353172 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -59,7 +59,7 @@ public enum IntakePivotState { INTAKE_CORAL(Rotation2d.fromDegrees(123.6)), HANDOFF(Rotation2d.fromDegrees(0)), L1(Rotation2d.fromDegrees(-82 + 123.6)), - INTAKE_ALGAE(new Rotation2d()), + INTAKE_ALGAE(Rotation2d.fromDegrees(25.0)), ARM_CLEAR(Rotation2d.fromDegrees(35)); @Getter private final Rotation2d angle; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 7cd54d00..ad9427c6 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -31,7 +31,7 @@ public final class V3_EpsilonManipulatorConstants { public static final double CORAL_CAN_RANGE_THRESHOLD = 0.5; static { - ARM_PARAMETERS = new ArmParameters(DCMotor.getKrakenX60Foc(1), 1, 90.0, .695); + ARM_PARAMETERS = new ArmParameters(DCMotor.getKrakenX60Foc(1), 1, 55.5, .695); EMPTY_GAINS = new Gains( new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 50), @@ -58,7 +58,7 @@ public final class V3_EpsilonManipulatorConstants { new LoggedTunableNumber("Manipulator/ArmWithAlgae/kA", 0.0)); CONSTRAINTS = new Constraints( - new LoggedTunableNumber("Manipulator/Arm/MaxAcceleration", 20.0), + new LoggedTunableNumber("Manipulator/Arm/MaxAcceleration", 1000.0), new LoggedTunableNumber("Manipulator/Arm/CruisingVelocity", 50.0), new LoggedTunableNumber("Manipulator/Arm/GoalTolerance", Units.degreesToRadians(3))); @@ -128,7 +128,9 @@ public static record ArmParameters( public static enum ManipulatorArmState { PRE_SCORE(Rotation2d.fromDegrees(50.0)), SCORE(Rotation2d.fromDegrees(55.0)), // Placeholder value. Make sure to test - PROCESSOR(Rotation2d.fromDegrees(41.279296875)), + SCORE_L4(Rotation2d.kPi), + PROCESSOR(Rotation2d.fromDegrees(90)), + ALGAE_INTAKE_FLOOR(Rotation2d.fromDegrees(-99)), REEF_INTAKE(Rotation2d.fromDegrees(46.279296875)), INTAKE_OUT_LINE(Rotation2d.fromDegrees(61)), FLOOR_INTAKE(Rotation2d.fromDegrees(73.5)), From d9b406e49b073f95d131c8bedf8b4d506d5be835 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Fri, 19 Sep 2025 20:13:33 -0400 Subject: [PATCH 106/180] Remove unused auto routine and clean up intake threshold definition --- .../robot/commands/AutonomousCommands.java | 67 ------------------- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 3 + .../V3_EpsilonSuperstructureEdges.java | 1 - .../intake/V3_EpsilonIntake.java | 2 +- 4 files changed, 4 insertions(+), 69 deletions(-) diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index 6f781f68..e4e8ef40 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -11,7 +11,6 @@ import frc.robot.RobotState; import frc.robot.commands.CompositeCommands.V1_StackUpCompositeCommands; import frc.robot.commands.CompositeCommands.V2_RedundancyCompositeCommands; -import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorCSB; import frc.robot.subsystems.shared.funnel.Funnel.FunnelCSB; @@ -1963,70 +1962,4 @@ public static final LoggedAutoRoutine autoERightBack( return routine; } - - public static final LoggedAutoRoutine autoELeftArm( - Drive drive, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - V3_EpsilonManipulator manipulator, - Camera... cameras) { - - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoELeft"); - LoggedAutoTrajectory path1 = routine.trajectory("E_LEFT_PATH_1"); - - LoggedAutoTrajectory path2 = routine.trajectory("E_LEFT_PATH_2"); - - LoggedAutoTrajectory path3 = routine.trajectory("E_LEFT_PATH_3"); - - LoggedAutoTrajectory path4 = routine.trajectory("E_LEFT_PATH_4"); - - LoggedAutoTrajectory path5 = routine.trajectory("E_LEFT_PATH_5"); - - routine - .active() - .onTrue( - Commands.sequence( - path1.resetOdometry(), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path1.cmd(), - Commands.parallel( - // DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)) - .withTimeout(1), - Commands.sequence( - V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( - drive, superstructure, cameras), - V3_EpsilonCompositeCommands.scoreCoral(superstructure, () -> ReefState.L4)) - .withTimeout(1), - path2.cmd(), - V3_EpsilonCompositeCommands.manipulatorGroundIntake(manipulator, superstructure) - .withTimeout(0.5), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - path3.cmd(), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)) - .withTimeout(0.5), - Commands.sequence( - V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( - drive, superstructure, cameras), - V3_EpsilonCompositeCommands.scoreCoral(superstructure, () -> ReefState.L4)) - .withTimeout(0.5), - Commands.parallel( - path4.cmd(), - V3_EpsilonCompositeCommands.manipulatorGroundIntake(manipulator, superstructure) - .withTimeout(0.5)), - Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)) - .withTimeout(0.5), - Commands.sequence( - V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( - drive, superstructure, cameras), - V3_EpsilonCompositeCommands.scoreCoral(superstructure, () -> ReefState.L4)) - .withTimeout(0.5))); - - return routine; - } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index aca494a8..3a01c434 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -114,6 +114,9 @@ public V3_EpsilonRobotContainer() { superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); } } + + configureButtonBindings(); + configureAutos(); } private void configureButtonBindings() { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index fe462b9a..1c7f8ad1 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -392,7 +392,6 @@ private static Command waitForPoseCommand( ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { - V3_EpsilonSuperstructurePose pose = state.getPose(); // Add this command to log the check's status Command logCheck = diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index a91d17e5..fa470059 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -13,7 +13,7 @@ public class V3_EpsilonIntake { private final V3_EpsilonIntakeIO io; private final V3_EpsilonIntakeIOInputsAutoLogged inputs; - private final double INTAKE_CORAL_THRESHOLD = 1.0; + // private final double INTAKE_CORAL_THRESHOLD = 1.0; @Getter @AutoLogOutput(key = "Intake/Pivot Goal") From b3dc71c6b194911dcfc47a2c9295b24ce02639da Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Mon, 22 Sep 2025 17:44:13 -0400 Subject: [PATCH 107/180] start maplesim for algae simulation Co-authored-by: Kevin Reas --- src/main/java/frc/robot/Robot.java | 58 +++++----- .../subsystems/shared/elevator/Elevator.java | 11 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 30 +++-- .../V3_EpsilonSuperstructure.java | 104 ++++++++++++++++++ .../V3_EpsilonSuperstructureEdges.java | 4 +- .../V3_EpsilonSuperstructureStates.java | 4 +- .../manipulator/V3_EpsilonManipulator.java | 9 ++ .../V3_EpsilonManipulatorConstants.java | 1 + vendordeps/maple-sim.json | 26 +++++ 9 files changed, 203 insertions(+), 44 deletions(-) create mode 100644 vendordeps/maple-sim.json diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index e4048d20..c1bb9243 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -31,6 +31,7 @@ import java.util.HashMap; import java.util.Map; import java.util.function.BiConsumer; +import org.ironmaple.simulation.SimulatedArena; import org.littletonrobotics.junction.LogFileUtil; import org.littletonrobotics.junction.LoggedRobot; import org.littletonrobotics.junction.Logger; @@ -125,6 +126,8 @@ public void robotInit() { // Running a physics simulator, log to NT // setUseTiming(false); Logger.addDataReceiver(new NT4Publisher()); + // setting up maple sim field + SimulatedArena.getInstance(); break; case REPLAY: @@ -263,37 +266,40 @@ public void robotPeriodic() { // LoggedTracer.reset(); // var canStatus = RobotController.getCANStatus(); // if (canStatus.transmitErrorCount > 0 || canStatus.receiveErrorCount > 0) { - // canErrorTimer.restart(); + // canErrorTimer.restart(); // } // canErrorAlert.set( - // !canErrorTimer.hasElapsed(canErrorTimeThreshold) - // && !canErrorTimerInitial.hasElapsed(canErrorTimeThreshold)); + // !canErrorTimer.hasElapsed(canErrorTimeThreshold) + // && !canErrorTimerInitial.hasElapsed(canErrorTimeThreshold)); // // Log CANivore status // if (Constants.getMode() == Constants.Mode.REAL) { - // var canivoreStatus = canivoreReader.getStatus(); - // if (canivoreStatus.isPresent()) { - // Logger.recordOutput( - // NTPrefixes.CANIVORE_STATUS + "Status", canivoreStatus.get().Status.getName()); - // Logger.recordOutput( - // NTPrefixes.CANIVORE_STATUS + "Utilization", canivoreStatus.get().BusUtilization); - // Logger.recordOutput( - // NTPrefixes.CANIVORE_STATUS + "OffCount", canivoreStatus.get().BusOffCount); - // Logger.recordOutput( - // NTPrefixes.CANIVORE_STATUS + "TxFullCount", canivoreStatus.get().TxFullCount); - // Logger.recordOutput( - // NTPrefixes.CANIVORE_STATUS + "ReceiveErrorCount", canivoreStatus.get().REC); - // Logger.recordOutput( - // NTPrefixes.CANIVORE_STATUS + "TransmitErrorCount", canivoreStatus.get().TEC); - // if (!canivoreStatus.get().Status.isOK() - // || canStatus.transmitErrorCount > 0 - // || canStatus.receiveErrorCount > 0) { - // canivoreErrorTimer.restart(); - // } - // } - // canivoreErrorAlert.set( - // !canivoreErrorTimer.hasElapsed(canivoreErrorTimeThreshold) - // && !canErrorTimerInitial.hasElapsed(canErrorTimeThreshold)); + // var canivoreStatus = canivoreReader.getStatus(); + // if (canivoreStatus.isPresent()) { + // Logger.recordOutput( + // NTPrefixes.CANIVORE_STATUS + "Status", + // canivoreStatus.get().Status.getName()); + // Logger.recordOutput( + // NTPrefixes.CANIVORE_STATUS + "Utilization", + // canivoreStatus.get().BusUtilization); + // Logger.recordOutput( + // NTPrefixes.CANIVORE_STATUS + "OffCount", canivoreStatus.get().BusOffCount); + // Logger.recordOutput( + // NTPrefixes.CANIVORE_STATUS + "TxFullCount", + // canivoreStatus.get().TxFullCount); + // Logger.recordOutput( + // NTPrefixes.CANIVORE_STATUS + "ReceiveErrorCount", canivoreStatus.get().REC); + // Logger.recordOutput( + // NTPrefixes.CANIVORE_STATUS + "TransmitErrorCount", canivoreStatus.get().TEC); + // if (!canivoreStatus.get().Status.isOK() + // || canStatus.transmitErrorCount > 0 + // || canStatus.receiveErrorCount > 0) { + // canivoreErrorTimer.restart(); + // } + // } + // canivoreErrorAlert.set( + // !canivoreErrorTimer.hasElapsed(canivoreErrorTimeThreshold) + // && !canErrorTimerInitial.hasElapsed(canErrorTimeThreshold)); // } // LoggedTracer.record("Check CANivore Status", "Robot"); } diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java index e6547733..8c1527e0 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java @@ -305,12 +305,13 @@ public BooleanSupplier inFastScoringTolerance() { } public class ElevatorFSM { + @AutoLogOutput(key = "Elevator/Past Barge Threshold") public boolean pastBargeThresholdgetPositionMeters() { if (Constants.getMode() == Mode.REAL) - return inputs.accelerationMetersPerSecondSquared < -0.01 - && inputs.velocityMetersPerSecond > 1; + return inputs.accelerationMetersPerSecondSquared < -1.0 + && inputs.velocityMetersPerSecond > 4; else { - return inputs.positionMeters > .91; + return inputs.positionMeters > .95; } } @@ -384,6 +385,10 @@ public Command waitUntilAtGoal() { public BooleanSupplier inFastScoringTolerance() { return Elevator.this.inFastScoringTolerance(); } + + public double getVelocityMetersPerSecond() { + return inputs.velocityMetersPerSecond; + } } public ElevatorFSM getFSM() { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index c543f4e7..effcf85c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -2,13 +2,14 @@ import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.apriltag.AprilTagFields; +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.Constants; import frc.robot.Constants.Mode; -import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotContainer; import frc.robot.RobotState; import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; @@ -38,6 +39,7 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOSim; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOTalonFX; import frc.robot.util.LTNUpdater; +import org.ironmaple.simulation.SimulatedArena; import org.littletonrobotics.junction.Logger; public class V3_EpsilonRobotContainer implements RobotContainer { @@ -116,6 +118,7 @@ public V3_EpsilonRobotContainer() { superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); } } + configureButtonBindings(); } private void configureButtonBindings() { @@ -154,19 +157,26 @@ public void robotPeriodic() { "Component Poses", V3_EpsilonMechanism3d.getPoses( elevator.getPositionMeters(), intake.getPivotAngle(), manipulator.getArmAngle())); + Logger.recordOutput( + "FieldSimulation/Algae", SimulatedArena.getInstance().getGamePiecesArrayByType("Algae")); + Logger.recordOutput( + "FieldSimulation/Coral", SimulatedArena.getInstance().getGamePiecesArrayByType("Coral")); } @Override public Command getAutonomousCommand() { + return Commands.runOnce( + () -> RobotState.resetRobotPose(new Pose2d(7.25, 2.39, new Rotation2d(Math.PI / 2)))) + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE_SCORE)); // return superstructure.allTransition(); - return Commands.sequence( - V3_EpsilonCompositeCommands.dropAlgae( - drive, - elevator, - manipulator, - intake, - superstructure, - () -> ReefState.ALGAE_INTAKE_TOP, - RobotCameras.V3_EPSILON_CAMS)); + // return Commands.sequence( + // V3_EpsilonCompositeCommands.dropAlgae( + // drive, + // elevator, + // manipulator, + // intake, + // superstructure, + // () -> ReefState.ALGAE_INTAKE_TOP, + // RobotCameras.V3_EPSILON_CAMS)); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 74242c25..7f30eaec 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -1,9 +1,21 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; +import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.math.geometry.Translation3d; +import edu.wpi.first.math.kinematics.ChassisSpeeds; +import edu.wpi.first.units.Units; +import edu.wpi.first.units.measure.Angle; +import edu.wpi.first.units.measure.Distance; +import edu.wpi.first.units.measure.LinearVelocity; +import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import edu.wpi.first.wpilibj2.command.button.Trigger; +import frc.robot.Constants; +import frc.robot.FieldConstants; import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotState; import frc.robot.RobotState.RobotMode; @@ -14,7 +26,9 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.Side; +import frc.robot.util.AllianceFlipUtil; import frc.robot.util.NTPrefixes; import java.util.HashMap; import java.util.LinkedList; @@ -27,6 +41,8 @@ import java.util.function.Supplier; import java.util.stream.Collectors; import lombok.Getter; +import org.ironmaple.simulation.SimulatedArena; +import org.ironmaple.simulation.seasonspecific.reefscape2025.ReefscapeAlgaeOnFly; import org.jgrapht.Graph; import org.jgrapht.graph.DefaultDirectedGraph; import org.littletonrobotics.junction.AutoLogOutput; @@ -97,6 +113,94 @@ public V3_EpsilonSuperstructure( // Add edges between states V3_EpsilonSuperstructureEdges.addEdges(graph, elevator, intake, manipulator); + + // trigger to run + new Trigger( + () -> + targetState == V3_EpsilonSuperstructureStates.BARGE_SCORE + && manipulator.getRollerGoal() == ManipulatorRollerState.SCORE_ALGAE && !Constants.getMode().equals(Constants.Mode.REAL)) + .onTrue( + Commands.runOnce( + () -> { + System.out.println("Algae shot at " + Timer.getFPGATimestamp()); + Translation2d shooterPositionOnRobot = + new Translation2d( + V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() + * manipulator.getArmAngle().getSin() + - 0.05, + 0); + Distance initialHeight = + Distance.ofBaseUnits( + V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() + * manipulator.getArmAngle().getCos() + + elevator.getPositionMeters(), + Units.Meters); + + double v_x = + manipulator.getArmVelocity() + * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() + * manipulator.getArmAngle().getSin() + + -manipulator.getRollerVelocity() + * edu.wpi.first.math.util.Units.inchesToMeters(1.5) + * manipulator.getArmAngle().getSin(); + double v_y = + manipulator.getArmVelocity() + * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() + * manipulator.getArmAngle().getCos() + + -manipulator.getRollerVelocity() + * edu.wpi.first.math.util.Units.inchesToMeters(1.5) + * manipulator.getArmAngle().getCos() + + elevator.getVelocityMetersPerSecond(); + Logger.recordOutput("AlgaeCalculations/velocity/v_x", v_x); + Logger.recordOutput("AlgaeCalculations/velocity/v_y", v_y); + Angle shooterAngle = + manipulator + .getArmAngle() + .plus(Rotation2d.kCW_90deg) + .unaryMinus() + .getMeasure(); + Logger.recordOutput( + "AlgaeCalculations/shooterPositionOnRobot", shooterPositionOnRobot); + Logger.recordOutput("AlgaeCalculations/initialHeight", initialHeight); + Logger.recordOutput("AlgaeCalculations/shooterAngle", shooterAngle); + ReefscapeAlgaeOnFly algae = + new ReefscapeAlgaeOnFly( + RobotState.getRobotPoseField().getTranslation(), + shooterPositionOnRobot, // shooter position relative to bot + new ChassisSpeeds(), // maybe fix this eventually + RobotState.getRobotPoseField() + .getRotation() + .plus(Rotation2d.kCW_Pi_2), // good + initialHeight, // initial height of the ball, in meters | + // (length from arm joint to + // ball * cos (arm angle)) + elevator height + LinearVelocity.ofRelativeUnits( + Math.hypot(v_x, v_y) * .85, + Units.MetersPerSecond), // initial velocity, in m/s + shooterAngle // shooter angle + ); + algae + .withTargetPosition( + () -> { + double x = FieldConstants.Barge.middleCage.getX(); + double y = + AllianceFlipUtil.applyY(FieldConstants.Barge.middleCage.getY()); + double z = 2.018538; + return new Translation3d(x, y, z); + }) + .withTargetTolerance( + new Translation3d( + edu.wpi.first.math.util.Units.inchesToMeters(23), 1.86055, .242062)); + SimulatedArena.getInstance() + .addGamePieceProjectile( + algae.withProjectileTrajectoryDisplayCallBack( + (poses) -> + Logger.recordOutput( + "successfulShotsTrajectory", poses.toArray(Pose3d[]::new)), + (poses) -> + Logger.recordOutput( + "missedShotsTrajectory", poses.toArray(Pose3d[]::new)))); + })); } /** diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index cd25a719..ca9e910a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -264,9 +264,7 @@ else if (willCollide(from, to)) { if (to.equals(V3_EpsilonSuperstructureStates.BARGE_SCORE)) { return Commands.sequence( moveCommand, - Commands.race( - Commands.waitUntil(() -> elevator.pastBargeThresholdgetPositionMeters()), - waitForPoseCommand(to, elevator, intake, manipulator))); + Commands.race(Commands.waitUntil(() -> elevator.pastBargeThresholdgetPositionMeters()))); } // THE CRITICAL FIX: diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index d99279dc..b01c6a78 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -138,12 +138,12 @@ public enum V3_EpsilonSuperstructureStates { BARGE( "BARGE", new SubsystemPoses( - ReefState.HIGH_STOW, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), + ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.HANDOFF), SubsystemActions.empty()), BARGE_SCORE( "BARGE_SCORE", new SubsystemPoses( - ReefState.ALGAE_SCORE, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), + ReefState.ALGAE_SCORE, ManipulatorArmState.BARGE_SCORE, IntakePivotState.HANDOFF), new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), ; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 967f743b..beb84429 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -170,6 +170,7 @@ public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmSta } public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState rollerGoal) { + this.rollerGoal = rollerGoal; if (hasAlgae() && Set.of( V3_EpsilonManipulatorConstants.ManipulatorRollerState.ALGAE_INTAKE, @@ -194,4 +195,12 @@ public boolean isSafePosition() { // unsafe if -cos(theta) >= cosThresh return (-inputs.armPosition.getCos()) < cosThresh; } + + public double getArmVelocity() { + return inputs.armVelocityRadiansPerSecond; + } + + public double getRollerVelocity() { + return inputs.rollerVelocityRadiansPerSecond; + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index aef18221..86c39c48 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -128,6 +128,7 @@ public static record ArmParameters( public static enum ManipulatorArmState { PRE_SCORE(Rotation2d.fromDegrees(50.0)), SCORE(Rotation2d.fromDegrees(55.0)), // Placeholder value. Make sure to test + BARGE_SCORE(Rotation2d.fromDegrees(18.67)), PROCESSOR(Rotation2d.fromDegrees(41.279296875)), REEF_INTAKE(Rotation2d.fromDegrees(46.279296875)), INTAKE_OUT_LINE(Rotation2d.fromDegrees(61)), diff --git a/vendordeps/maple-sim.json b/vendordeps/maple-sim.json new file mode 100644 index 00000000..65f44133 --- /dev/null +++ b/vendordeps/maple-sim.json @@ -0,0 +1,26 @@ +{ + "fileName": "maple-sim.json", + "name": "maplesim", + "version": "0.3.14", + "frcYear": "2025", + "uuid": "c39481e8-4a63-4a4c-9df6-48d91e4da37b", + "mavenUrls": [ + "https://shenzhen-robotics-alliance.github.io/maple-sim/vendordep/repos/releases", + "https://repo1.maven.org/maven2" + ], + "jsonUrl": "https://shenzhen-robotics-alliance.github.io/maple-sim/vendordep/maple-sim.json", + "javaDependencies": [ + { + "groupId": "org.ironmaple", + "artifactId": "maplesim-java", + "version": "0.3.14" + }, + { + "groupId": "org.dyn4j", + "artifactId": "dyn4j", + "version": "5.0.2" + } + ], + "jniDependencies": [], + "cppDependencies": [] +} From 587536c789cae363fd54c30099a3701a515940a6 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Mon, 22 Sep 2025 17:47:20 -0400 Subject: [PATCH 108/180] remove print --- .../v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 7f30eaec..f0d631ed 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -122,7 +122,6 @@ public V3_EpsilonSuperstructure( .onTrue( Commands.runOnce( () -> { - System.out.println("Algae shot at " + Timer.getFPGATimestamp()); Translation2d shooterPositionOnRobot = new Translation2d( V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() From a7c2a50e655fab757288bd6c267c43815b65adbc Mon Sep 17 00:00:00 2001 From: LordVanra Date: Mon, 22 Sep 2025 19:38:31 -0400 Subject: [PATCH 109/180] Added javadoc comments to subsystems and a couple other files Co-authored-by: Anshu Co-authored-by: SeptimusHeap7 Co-authored-by: posydon --- .../subsystems/shared/climber/Climber.java | 6 + .../v3_Epsilon/V3_EpsilonRobotContainer.java | 20 ++- .../intake/V3_EpsilonIntake.java | 64 ++++++++- .../intake/V3_EpsilonIntakeIOTalonFX.java | 48 +++++++ .../manipulator/V3_EpsilonManipulator.java | 131 +++++++++++++++++- .../V3_EpsilonManipulatorIOTalonFX.java | 40 ++++++ 6 files changed, 306 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shared/climber/Climber.java b/src/main/java/frc/robot/subsystems/shared/climber/Climber.java index aa93b70c..d887a895 100644 --- a/src/main/java/frc/robot/subsystems/shared/climber/Climber.java +++ b/src/main/java/frc/robot/subsystems/shared/climber/Climber.java @@ -49,6 +49,12 @@ public Climber(ClimberIO io) { override = false; } +/** + * Periodic function for the climber subsystem. + * + * Updates the inputs for the climber, processes the inputs, logs the state of the climber, and + * records the total time taken by the periodic function. + */ @Override public void periodic() { ExternalLoggedTracer.reset(); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index c543f4e7..ab1ad683 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -118,6 +118,12 @@ public V3_EpsilonRobotContainer() { } } + + /** + * Configure the button bindings for the robot. This method is called in + * the constructor and is responsible for setting up the default commands + * for each button on the controllers. + */ private void configureButtonBindings() { drive.setDefaultCommand( DriveCommands.joystickDrive( @@ -138,6 +144,12 @@ private void configureButtonBindings() { private void configureAutos() {} + +/** + * Periodic function for the robot. This function is called every 20ms, + * and is responsible for updating the robot's state and logging relevant + * data. + */ @Override public void robotPeriodic() { RobotState.periodic( @@ -156,7 +168,13 @@ public void robotPeriodic() { elevator.getPositionMeters(), intake.getPivotAngle(), manipulator.getArmAngle())); } - @Override + /** + * Returns the autonomous command for the robot. This command will be scheduled + * for the entire autonomous period. + * + * @return the autonomous command for the robot + */ +/******* a3f2747b-04ef-49d3-bd1f-182e56d47707 *******/ public Command getAutonomousCommand() { // return superstructure.allTransition(); return Commands.sequence( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index f45d73ec..3aacca32 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -34,6 +34,13 @@ public V3_EpsilonIntake(V3_EpsilonIntakeIO io) { isClosedLoop = true; } + /** + * Periodic function for intake subsystem. + * Updates inputs from the intake, and then sets the goals for the pivot and roller motors. + * If the intake is in closed-loop mode, it sets the pivot motor goal to the desired angle. + * Otherwise, it does not set the pivot motor goal. + * It always sets the inner and outer roller motor goals to the desired voltage. + */ public void periodic() { io.updateInputs(inputs); Logger.processInputs("Intake", inputs); @@ -47,6 +54,15 @@ public void periodic() { } // Double check if this is right + + /** + * Checks if the intake is currently detecting coral. + * This is done by checking if both the left and right CAN range + * sensors are detecting a distance greater than the coral detection + * threshold. + * + * @return True if the intake is detecting coral, false otherwise. + */ @AutoLogOutput(key = "Intake/Has Coral") public boolean hasCoral() { return inputs.leftCANRangeDistanceMeters @@ -55,27 +71,68 @@ public boolean hasCoral() { > V3_EpsilonIntakeConstants.INTAKE_CAN_CORAL_DETECTED_THRESHOLD_METERS; } + + /** + * Checks if the pivot motor is at the goal angle. + * This is done by checking if the absolute difference between the current + * pivot motor angle and the goal angle is less than the goal tolerance. + * + * @return True if the pivot motor is at the goal angle, false otherwise. + */ @AutoLogOutput(key = "Intake/At Goal") public boolean pivotAtGoal() { return Math.abs(inputs.pivotPosition.getRadians() - pivotGoal.getAngle().getRadians()) < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); } + + /** + * Checks if the pivot motor is at the goal angle. + * This is done by checking if the absolute difference between the current + * pivot motor angle and the goal angle is less than the goal tolerance. + * + * @param goal The goal angle to check against. + * @return True if the pivot motor is at the goal angle, false otherwise. + */ public boolean pivotAtGoal(IntakePivotState goal) { - return Math.abs(inputs.pivotPosition.getRadians() - goal.getAngle().getRadians()) + return Math.abs(inputs.pivotPosition.getRadians() - goal.getAngle().getRadians()) < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); } +/** + * Sets the goal state of the pivot motor. + * If the intake is currently in open-loop mode, this method will set the isClosedLoop flag to true. + * It then sets the pivotGoal field to the specified goal state. + * The pivot motor will then be controlled in closed-loop mode to reach the specified goal state. + * + * @param goal The desired IntakePivotState for the pivot motor. + */ public void setPivotGoal(IntakePivotState goal) { isClosedLoop = true; this.pivotGoal = goal; } + +/** + * Sets the voltage for the intake pivot motor. + * + * This method is used to set the voltage for the intake pivot motor in open-loop mode. + * It sets the isClosedLoop flag to false, and then calls the setPivotVoltage method of the IO interface. + * + * @param volts The voltage to set for the intake pivot motor. + */ public void setPivotVoltage(double volts) { isClosedLoop = false; io.setPivotVoltage(volts); } +/** + * Waits until the pivot motor is at the goal angle. + * This command is created by sequencing a wait command with a waitUntil command. + * The wait command waits for 0.02 seconds, and the waitUntil command checks if the pivot motor is at the goal angle. + * The command will block until the pivot motor is at the goal angle. + * @return A Command that waits until the pivot motor is at the goal angle. + */ public Command waitUntilPivotAtGoal() { return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::pivotAtGoal)); } @@ -97,6 +154,11 @@ public void setRollerGoal(IntakeRollerState rollerGoal) { } } + /** + * Gets the current angle of the intake pivot motor. + * + * @return The current angle of the intake pivot motor, in radians. + */ public Rotation2d getPivotAngle() { return inputs.pivotPosition; } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java index 326b9353..290ae511 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java @@ -206,6 +206,15 @@ public V3_EpsilonIntakeIOTalonFX() { rightCANrangeStatusSignal); } + +/** + * Updates the inputs of the subsystem. + * + * This function is called by the robot periodic loop and should update all of the inputs + * of the subsystem. The inputs should be updated from the CAN bus and other sensors. + * + * @param inputs The inputs of the subsystem. + */ @Override public void updateInputs(V3_EpsilonIntakeIOInputs inputs) { inputs.pivotPosition = new Rotation2d(pivotPositionRotations.getValue()); @@ -242,18 +251,57 @@ public void updateInputs(V3_EpsilonIntakeIOInputs inputs) { inputs.rightCANRangeDistanceMeters = rightCANrangeStatusSignal.getValueAsDouble(); } + +/** + * Sets the voltage for the intake pivot motor. + * + * This method is used to set the voltage for the intake pivot motor in open-loop mode. + * It sets the isClosedLoop flag to false, and then calls the setPivotVoltage method of the IO interface. + * + * @param volts The voltage to set for the intake pivot motor. + */ public void setPivotVoltage(double volts) { pivotTalonFX.setControl(pivotVoltageRequest.withOutput(volts).withEnableFOC(true)); } + +/** + * Sets the voltage for the inner manipulator roller. + * + * This method is used to set the voltage for the inner manipulator roller in open-loop mode. + * It sets the isClosedLoop flag to false, and then calls the setControl method of the TalonFX + * object with the voltage request. + * + * @param volts The voltage to set for the inner manipulator roller. + */ + public void setInnerRollerVoltage(double volts) { rollerTalonFXInner.setControl(rollerInnerVoltageRequest.withOutput(volts).withEnableFOC(true)); } +/** + * Sets the voltage for the outer manipulator roller. + * + * This method is used to set the voltage for the outer manipulator roller in open-loop mode. + * It sets the isClosedLoop flag to false, and then calls the setControl method of the TalonFX + * object with the voltage request. + * + * @param volts The voltage to set for the outer manipulator roller. + */ public void setOuterRollerVoltage(double volts) { rollerTalonFXOuter.setControl(rollerOuterVoltageRequest.withOutput(volts).withEnableFOC(true)); } + +/** + * Sets the position of the intake pivot motor using Motion Magic. + * + * This method is used to set the position of the intake pivot motor using Motion Magic. + * It sets the isClosedLoop flag to true, and then calls the setControl method of the + * TalonFX object with the position request. + * + * @param position The desired position of the intake pivot motor. + */ public void setPivotMotionMagic(Rotation2d position) { pivotTalonFX.setControl( pivotMotionMagicRequest.withPosition(position.getMeasure()).withEnableFOC(true)); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 967f743b..d9aedde7 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -73,20 +73,41 @@ public void periodic() { } } +/** + * Checks if the manipulator is currently detecting coral. + * This is done by checking if the CAN range sensor is detecting a distance + * less than the coral detection threshold and greater than 0. + * + * @return True if the manipulator is detecting coral, false otherwise. + */ @AutoLogOutput(key = "Manipulator/Has Coral") public boolean hasCoral() { return inputs.canRangeDistanceMeters < V3_EpsilonManipulatorConstants.CORAL_CAN_RANGE_THRESHOLD && inputs.canRangeDistanceMeters > 0; } +/** + * Checks if the manipulator is currently detecting algae. + * This is done by checking if the CAN range sensor is detecting a distance + * less than the algae detection threshold and greater than 0. + * + * @return True if the manipulator is detecting algae, false otherwise. + */ @AutoLogOutput(key = "Manipulator/Has Algae") public boolean hasAlgae() { return inputs.canRangeDistanceMeters < V3_EpsilonManipulatorConstants.ALGAE_CAN_RANGE_THRESHOLD && inputs.canRangeDistanceMeters > 0; } +/** + * Creates a command to run the manipulator arm at a specified voltage. + * + * @param volts The voltage to set the arm to. + * @return A command to run the arm. + */ + public Command runArm(double volts) { - return Commands.runEnd( + return Commands.runEnd( () -> { isClosedLoop = false; io.setArmVoltage(volts); @@ -94,11 +115,43 @@ public Command runArm(double volts) { () -> io.setArmVoltage(0)); } + +/** + * Sets the goal for the manipulator arm to reach. + * + * @param goal The goal state to set the arm to. + */ + public void setArmGoal(ManipulatorArmState goal) { isClosedLoop = true; armGoal = goal; } + +/** + * Updates the gains for the manipulator arm. + * This function sets the PID gains for the three slots of the arm. + * The gains are used to control the arm's movement. + * + * @param kP0 The proportional gain for slot 0. + * @param kD0 The derivative gain for slot 0. + * @param kS0 The static gain for slot 0. + * @param kV0 The velocity gain for slot 0. + * @param kA0 The acceleration gain for slot 0. + * @param kG0 The gravity gain for slot 0. + * @param kP1 The proportional gain for slot 1. + * @param kD1 The derivative gain for slot 1. + * @param kS1 The static gain for slot 1. + * @param kV1 The velocity gain for slot 1. + * @param kA1 The acceleration gain for slot 1. + * @param kG1 The gravity gain for slot 1. + * @param kP2 The proportional gain for slot 2. + * @param kD2 The derivative gain for slot 2. + * @param kS2 The static gain for slot 2. + * @param kV2 The velocity gain for slot 2. + * @param kA2 The acceleration gain for slot 2. + * @param kG2 The gravity gain for slot 2. + */ public void updateArmGains( double kP0, double kD0, @@ -123,24 +176,68 @@ public void updateArmGains( io.updateSlot2ArmGains(kP2, kD2, kS2, kV2, kA2, kG2); } +/** + * Updates the constraints for the arm. + * + * @param maxAcceleration The maximum acceleration. + * @param maxVelocity The maximum velocity. + */ public void updateArmConstraints(double maxAcceleration, double maxVelocity) { io.updateArmConstraints(maxAcceleration, maxVelocity); } +/** + * Checks if the arm is at the goal position. + * + * This function checks if the arm is within the goal tolerance of the + * currently set arm goal position. If the arm is within the tolerance, it + * returns true. Otherwise, it returns false. + * + * @return If the arm is at the goal position. + */ + @AutoLogOutput(key = "Manipulator/Arm At Goal") public boolean armAtGoal() { return armAtGoal(armGoal); } +/** + * Checks if the arm is at the given goal position. + * + * This function checks if the arm is within the goal tolerance of the + * given arm goal position. If the arm is within the tolerance, it + * returns true. Otherwise, it returns false. + * + * @param state The arm goal position to check against. + * @return If the arm is at the goal position. + */ public boolean armAtGoal(ManipulatorArmState state) { return Math.abs(inputs.armPosition.minus(state.getAngle(armSide)).getRadians()) <= V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); } +/** + * Waits until the arm is at the goal position. + * + * This command waits for 0.02 seconds and then checks if the arm is at the goal position. + * If the arm is not at the goal position, it waits for 0.02 seconds and checks again. + * This process repeats until the arm is at the goal position. + * + * @return A command that waits until the arm is at the goal position. + */ public Command waitUntilArmAtGoal() { return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::armAtGoal)); } +/** + * Returns a voltage to hold the roller at the current position. + * The voltage is calculated based on the current torque current of the roller. + * The calculation is done using a piecewise polynomial function. + * The function first checks if the current torque current is less than or equal to 20. + * If it is, it uses one set of coefficients to calculate the voltage. + * Otherwise, it uses another set of coefficients. + */ + private double holdVoltage() { double y; double x = Math.abs(inputs.rollerTorqueCurrentAmps); @@ -155,6 +252,11 @@ private double holdVoltage() { V3_EpsilonManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().getAsDouble() / 1.5); } +/** + * Sets the current slot of the manipulator arm based on the current state of the subsystem. + * If the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to 1. + * Otherwise, it sets the slot to 0. + */ public void setSlot() { if (hasAlgae()) { io.setSlot(2); @@ -165,10 +267,24 @@ public void setSlot() { } } + + /** + * Sets the manipulator arm to the specified state. + * + * @param state The state to set the arm to. + */ public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmState state) { io.setManipulatorState(state); } + /** + * Sets the roller goal state of the manipulator. + * If the subsystem has algae or coral and the goal is one of the intake states, + * it sets the roller voltage to the hold voltage. Otherwise, it sets the roller voltage + * to the goal voltage. + * + * @param rollerGoal The desired state of the roller. + */ public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState rollerGoal) { if (hasAlgae() && Set.of( @@ -183,10 +299,23 @@ public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState } } + /** + * Gets the current angle of the manipulator arm. + * + * @return The current angle of the manipulator arm, in radians. + */ public Rotation2d getArmAngle() { return inputs.armPosition; } +/** + * Checks if the manipulator arm is currently in a safe position. + * A safe position is when the arm is pointing away from the robot's body. + * The safe position threshold is determined by the angle between the arm and the robot's body. + * If the angle is greater than the threshold, it is considered safe. + * + * @return true if the arm is in a safe position, false otherwise. + */ @AutoLogOutput(key = "Manipulator/Safe Position") public boolean isSafePosition() { double cosThresh = diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java index 6038f587..07f36308 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java @@ -138,6 +138,11 @@ public V3_EpsilonManipulatorIOTalonFX() { rollerTalonFX.optimizeBusUtilization(); } +/** + * Updates the inputs of the manipulator with the current state of the TalonFXs. + * + * @param inputs the inputs to update + */ @Override public void updateInputs(ManipulatorIOInputs inputs) { @@ -164,22 +169,57 @@ public void updateInputs(ManipulatorIOInputs inputs) { Rotation2d.fromRotations(armPositionErrorRotations.getValueAsDouble()); } + + + /** + * Sets the voltage of the arm TalonFX to the specified value. + * The voltage is set in terms of volts, with positive values corresponding to + * clockwise rotation and negative values corresponding to counterclockwise + * rotation. + * This method is used to control the velocity of the arm, which is useful + * for tasks such as picking up objects or depositing objects. + * @param volts the voltage to set, in volts + */ @Override public void setArmVoltage(double volts) { armTalonFX.setControl(armVoltageRequest.withOutput(volts).withEnableFOC(true)); } + + +/** + * Sets the voltage of the roller TalonFX to the specified value. + * The voltage is set in terms of volts, with positive values corresponding to clockwise rotation and negative values corresponding to counterclockwise rotation. + * This method is used to control the velocity of the roller, which is useful for tasks such as picking up objects or depositing objects. + */ @Override public void setRollerVoltage(double volts) { rollerTalonFX.setControl(rollerVoltageRequest.withOutput(volts).withEnableFOC(true)); } + + /** + * The position is set in terms of rotations of the TalonFX's motor shaft. + * This method is used to set the manipulator arm to a specific position, which is useful for tasks such as picking up objects or depositing objects. + * + * @param rotation The desired position of the manipulator arm, in terms of rotations of the TalonFX's motor shaft. + */ + @Override public void setArmGoal(Rotation2d rotation) { armTalonFX.setControl( armMotionMagicRequest.withPosition(rotation.getRotations()).withEnableFOC(true)); } + + /** + * Sets the current slot of the manipulator arm based on the current state of the subsystem. + * If the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to 1. + * Otherwise, it sets the slot to 0. + * + * @param slot The slot to set the arm to. + * @throws IllegalArgumentException If the slot is not between 0 and 2, inclusive. + */ @Override public void setSlot(int slot) { if (slot >= 0 && slot <= 2) { From 4fd85a9a4368ae82d563da039f1899dd3ede4a91 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Mon, 22 Sep 2025 21:25:27 -0400 Subject: [PATCH 110/180] Add autonomous routines to chooser and update dashboard display --- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 17 ++++++++++++++--- 1 file changed, 14 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 3a01c434..73e18265 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -3,6 +3,7 @@ import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.apriltag.AprilTagFields; import edu.wpi.first.networktables.NetworkTablesJNI; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.Constants; @@ -36,6 +37,7 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOSim; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOTalonFX; import frc.robot.util.LTNUpdater; +import frc.robot.util.LoggedChoreo.ChoreoChooser; import org.littletonrobotics.junction.Logger; public class V3_EpsilonRobotContainer implements RobotContainer { @@ -48,9 +50,10 @@ public class V3_EpsilonRobotContainer implements RobotContainer { private Vision vision; // Controller - CommandXboxController driver = new CommandXboxController(0); + private static final CommandXboxController driver = new CommandXboxController(0); // Auto chooser + private static final ChoreoChooser autoChooser = new ChoreoChooser(); public V3_EpsilonRobotContainer() { @@ -128,7 +131,15 @@ private void configureButtonBindings() { .whileFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF)); } - private void configureAutos() {} + private void configureAutos() { + autoChooser.addRoutine( + "4 Piece Early Madtown", + () -> AutonomousCommands.autoERight(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "4 Piece Late Madtown", + () -> AutonomousCommands.autoERightBack(drive, superstructure, intake, manipulator)); + SmartDashboard.putData("Autonomous Modes", autoChooser); + } @Override public void robotPeriodic() { @@ -150,6 +161,6 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { - return AutonomousCommands.autoERightBack(drive, superstructure, intake, manipulator).cmd(); + return autoChooser.selectedCommand(); } } From 93f0142087abd1ac32663c984dd706d656ef4c49 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Tue, 23 Sep 2025 14:22:59 -0400 Subject: [PATCH 111/180] choose scoreSide automatically for barge score --- .../frc/robot/commands/CompositeCommands.java | 35 ++++++++++++++++--- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 3 +- .../V3_EpsilonSuperstructure.java | 4 +-- 3 files changed, 34 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 4c147c09..5962583c 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -6,6 +6,7 @@ import edu.wpi.first.math.kinematics.ChassisSpeeds; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; +import frc.robot.FieldConstants; import frc.robot.FieldConstants.Reef; import frc.robot.FieldConstants.Reef.ReefPose; import frc.robot.FieldConstants.Reef.ReefState; @@ -691,7 +692,7 @@ public static final Command optimalAutoScoreCoralSequence( RobotState.setScoreSide(ScoreSide.CENTER); } else { RobotState.setScoreSide( - optimalSide(RobotState.getReefAlignData().coralSetpoint())); + optimalSideReef(RobotState.getReefAlignData().coralSetpoint())); } }) .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), @@ -710,7 +711,7 @@ public static final Command optimalAutoAlignReefAlgae( if (closestReefTag != -1) { Pose2d baseAlgaeSetpoint = Reef.reefMap.get(closestReefTag).getAlgaeSetpoint(); - RobotState.setScoreSide(optimalSide(baseAlgaeSetpoint)); + RobotState.setScoreSide(optimalSideReef(baseAlgaeSetpoint)); } }) .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), @@ -718,7 +719,7 @@ public static final Command optimalAutoAlignReefAlgae( DriveCommands.autoAlignReefAlgae(drive, cameras)); } - private static final ScoreSide optimalSide(Pose2d baseSetpoint) { + private static final ScoreSide optimalSideReef(Pose2d baseSetpoint) { if (Math.abs( MathUtil.angleModulus( baseSetpoint @@ -738,6 +739,27 @@ private static final ScoreSide optimalSide(Pose2d baseSetpoint) { return ScoreSide.LEFT; } } + + private static final ScoreSide optimalSideBarge() { + boolean facingPositive = + MathUtil.inputModulus( + RobotState.getRobotPoseField().getRotation().getRadians(), 0, 2 * Math.PI) + >= 0 + && MathUtil.inputModulus( + RobotState.getRobotPoseField().getRotation().getRadians(), 0, 2 * Math.PI) + < Math.PI; + + if (RobotState.getRobotPoseField().getX() < FieldConstants.fieldLength / 2) + return facingPositive ? ScoreSide.RIGHT : ScoreSide.LEFT; + else return facingPositive ? ScoreSide.LEFT : ScoreSide.RIGHT; + } + + public static final Command optimalScoreBarge(V3_EpsilonSuperstructure superstructure) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setScoreSide(optimalSideBarge())), + superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE_SCORE)); + } + /** * Creates a command to score coral. * @@ -807,10 +829,13 @@ public static final Command dropAlgae( } public static final Command intakeAlgaeFromReef( - Drive drive, V3_EpsilonSuperstructure superstructure, Supplier level) { + Drive drive, + V3_EpsilonSuperstructure superstructure, + Supplier level, + Camera... cameras) { return Commands.sequence( - // DriveCommands.autoAlignReefAlgae(drive), + optimalAutoAlignReefAlgae(drive, superstructure, cameras), superstructure .runGoalUntil( () -> { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index effcf85c..f6b322fe 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -13,6 +13,7 @@ import frc.robot.RobotContainer; import frc.robot.RobotState; import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; +import frc.robot.commands.CompositeCommands; import frc.robot.commands.DriveCommands; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.drive.DriveConstants; @@ -167,7 +168,7 @@ public void robotPeriodic() { public Command getAutonomousCommand() { return Commands.runOnce( () -> RobotState.resetRobotPose(new Pose2d(7.25, 2.39, new Rotation2d(Math.PI / 2)))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE_SCORE)); + .andThen(CompositeCommands.V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure)); // return superstructure.allTransition(); // return Commands.sequence( // V3_EpsilonCompositeCommands.dropAlgae( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index f0d631ed..e115da96 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -9,7 +9,6 @@ import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.Distance; import edu.wpi.first.units.measure.LinearVelocity; -import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; @@ -118,7 +117,8 @@ public V3_EpsilonSuperstructure( new Trigger( () -> targetState == V3_EpsilonSuperstructureStates.BARGE_SCORE - && manipulator.getRollerGoal() == ManipulatorRollerState.SCORE_ALGAE && !Constants.getMode().equals(Constants.Mode.REAL)) + && manipulator.getRollerGoal() == ManipulatorRollerState.SCORE_ALGAE + && !Constants.getMode().equals(Constants.Mode.REAL)) .onTrue( Commands.runOnce( () -> { From 3c6f6ad4df7079832df2514f49553a709732e7fd Mon Sep 17 00:00:00 2001 From: LordVanra Date: Thu, 25 Sep 2025 18:05:16 -0400 Subject: [PATCH 112/180] Finished pathing --- src/main/deploy/choreo/E_RIGHT_PATH4.traj | 91 +++++++++++++++++++++++ src/main/deploy/choreo/E_RIGHT_PATH5.traj | 58 +++++++++++++++ src/main/deploy/choreo/E_RIGHT_PATH6.traj | 78 +++++++++++++++++++ src/main/deploy/choreo/E_RIGHT_PATH7.traj | 61 +++++++++++++++ 4 files changed, 288 insertions(+) create mode 100644 src/main/deploy/choreo/E_RIGHT_PATH4.traj create mode 100644 src/main/deploy/choreo/E_RIGHT_PATH5.traj create mode 100644 src/main/deploy/choreo/E_RIGHT_PATH6.traj create mode 100644 src/main/deploy/choreo/E_RIGHT_PATH7.traj diff --git a/src/main/deploy/choreo/E_RIGHT_PATH4.traj b/src/main/deploy/choreo/E_RIGHT_PATH4.traj new file mode 100644 index 00000000..aaa7826b --- /dev/null +++ b/src/main/deploy/choreo/E_RIGHT_PATH4.traj @@ -0,0 +1,91 @@ +{ + "name":"E_RIGHT_PATH4", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.530534505844116, "y":2.730516195297241, "heading":-0.5235987755982988, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.3093485832214355, "y":3.91524887084961, "heading":-1.5707963267948966, "intervals":19, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":0.9058957099914552, "y":4.042835235595703, "heading":-1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.530534505844116 m", "val":3.530534505844116}, "y":{"exp":"2.730516195297241 m", "val":2.730516195297241}, "heading":{"exp":"-30 deg", "val":-0.5235987755982988}, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.3093485832214355 m", "val":2.3093485832214355}, "y":{"exp":"3.9152488708496094 m", "val":3.91524887084961}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":19, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"0.9058957099914551 m", "val":0.9058957099914552}, "y":{"exp":"4.042835235595703 m", "val":4.042835235595703}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.76447,1.4505], + "samples":[ + {"t":0.0, "x":3.53053, "y":2.73052, "heading":-0.5236, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.35423, "ay":5.4575, "alpha":-2.44349, "fx":[-62.48473,-41.46199,-53.61392,-70.65709], "fy":[90.12272,101.55179,95.72684,83.92085]}, + {"t":0.0273, "x":3.52928, "y":2.73255, "heading":-0.5236, "vx":-0.09158, "vy":0.149, "omega":-0.06671, "ax":-3.40191, "ay":5.42794, "alpha":-2.42956, "fx":[-63.37175,-42.47287,-54.354,-71.26353], "fy":[89.48994,101.12385,95.30034,83.39663]}, + {"t":0.0546, "x":3.52552, "y":2.73864, "heading":-0.52542, "vx":-0.18446, "vy":0.2972, "omega":-0.13305, "ax":-3.45419, "ay":5.39486, "alpha":-2.4143, "fx":[-64.36787,-43.58938,-55.14465,-71.9169], "fy":[88.76372,100.63723,94.83589,82.82301]}, + {"t":0.08191, "x":3.51919, "y":2.74877, "heading":-0.52905, "vx":-0.27877, "vy":0.44449, "omega":-0.19896, "ax":-3.51172, "ay":5.35762, "alpha":-2.39739, "fx":[-65.48168,-44.82817,-55.99844,-72.62525], "fy":[87.93151,100.07992,94.32407,82.19057]}, + {"t":0.10921, "x":3.51027, "y":2.7629, "heading":-0.53448, "vx":-0.37464, "vy":0.59077, "omega":-0.26442, "ax":-3.57533, "ay":5.31542, "alpha":-2.37843, "fx":[-66.72315,-46.20939,-56.93062,-73.39815], "fy":[86.9779,99.43661,93.75293,81.48771]}, + {"t":0.13651, "x":3.49871, "y":2.78101, "heading":-0.5417, "vx":-0.47226, "vy":0.73589, "omega":-0.32935, "ax":-3.64598, "ay":5.26726, "alpha":-2.35691, "fx":[-68.1039,-47.75749,-57.95989,-74.24716], "fy":[85.88387,98.68756,93.10718,80.69988]}, + {"t":0.16381, "x":3.48446, "y":2.80306, "heading":-0.5507, "vx":-0.5718, "vy":0.8797, "omega":-0.3937, "ax":-3.72486, "ay":5.21185, "alpha":-2.33217, "fx":[-69.63758,-49.50228,-59.10928,-75.18631], "fy":[84.62567,97.80705,92.36699,79.80863]}, + {"t":0.19112, "x":3.46746, "y":2.82902, "heading":-0.56145, "vx":-0.6735, "vy":1.02199, "omega":-0.45738, "ax":-3.81342, "ay":5.14751, "alpha":-2.30332, "fx":[-71.34019,-51.48022,-60.40752,-76.23286], "fy":[83.17333,96.76107,91.50624,78.79019]}, + {"t":0.21842, "x":3.44765, "y":2.85885, "heading":-0.57393, "vx":-0.77762, "vy":1.16253, "omega":-0.52026, "ax":-3.91343, "ay":5.07204, "alpha":-2.26916, "fx":[-73.23057,-53.73601,-61.89077,-77.40824], "fy":[81.48853,95.50411,90.48994,77.6134]}, + {"t":0.24572, "x":3.42496, "y":2.89248, "heading":-0.58814, "vx":-0.88446, "vy":1.30101, "omega":-0.58222, "ax":-4.0271, "ay":4.98249, "alpha":-2.22808, "fx":[-75.33078,-56.32455,-63.60486,-78.7392], "fy":[79.52169,93.97422,89.27029,76.23675]}, + {"t":0.27302, "x":3.39931, "y":2.92985, "heading":-0.60403, "vx":-0.99441, "vy":1.43705, "omega":-0.64305, "ax":-4.15714, "ay":4.87483, "alpha":-2.1779, "fx":[-77.66645,-59.31299,-65.60851,-80.25941], "fy":[77.20769,92.08577,87.78071,74.60385]}, + {"t":0.30033, "x":3.37061, "y":2.97091, "heading":-0.62159, "vx":-1.10791, "vy":1.57014, "omega":-0.70251, "ax":-4.30692, "ay":4.74348, "alpha":-2.11558, "fx":[-80.2667,-62.78266,-67.97722,-82.01135], "fy":[74.45979,89.71836,85.92617,72.63659]}, + {"t":0.32763, "x":3.33876, "y":3.01554, "heading":-0.64077, "vx":-1.2255, "vy":1.69965, "omega":-0.76027, "ax":-4.48052, "ay":4.58051, "alpha":-2.03692, "fx":[-83.16321,-66.82949,-70.80827,-84.04845], "fy":[71.16062,86.69999,83.56765,70.22421]}, + {"t":0.35493, "x":3.30363, "y":3.06365, "heading":-0.66153, "vx":-1.34783, "vy":1.82471, "omega":-0.81588, "ax":-4.68276, "ay":4.37445, "alpha":-1.93605, "fx":[-86.38717,-71.5601,-74.2255,-86.43693], "fy":[67.14914,82.78148,80.49617,67.20581]}, + {"t":0.38223, "x":3.26509, "y":3.1151, "heading":-0.6838, "vx":-1.47568, "vy":1.94414, "omega":-0.86874, "ax":-4.91888, "ay":4.10841, "alpha":-1.80479, "fx":[-89.96167,-77.07648,-78.381,-89.25555], "fy":[62.20164,77.59909,76.38901,63.34156]}, + {"t":0.40954, "x":3.22296, "y":3.16971, "heading":-0.70752, "vx":-1.60998, "vy":2.05631, "omega":-0.91802, "ax":-5.19334, "ay":3.75712, "alpha":-1.63177, "fx":[-93.88442,-83.43416,-83.44258,-92.58796], "fy":[56.00508,70.6249,70.73574,58.26464]}, + {"t":0.43684, "x":3.17707, "y":3.22726, "heading":-0.73259, "vx":-1.75177, "vy":2.15889, "omega":-0.96257, "ax":-5.50661, "ay":3.28289, "alpha":-1.40137, "fx":[-98.09029,-90.54378,-89.53605,-96.49308], "fy":[48.12351,61.11904,62.71957,51.40197]}, + {"t":0.46414, "x":3.12719, "y":3.28742, "heading":-0.75887, "vx":-1.90211, "vy":2.24852, "omega":-1.00083, "ax":-5.84697, "ay":2.63124, "alpha":-1.09252, "fx":[-102.37487,-97.9728,-96.55963,-100.91392], "fy":[37.96731,48.14431,51.06197,41.85269]}, + {"t":0.49144, "x":3.07308, "y":3.34979, "heading":-0.78619, "vx":-2.06175, "vy":2.32036, "omega":-1.03066, "ax":-6.17328, "ay":1.73205, "alpha":-0.67844, "fx":[-106.2516,-104.64263,-103.70084,-105.42807], "fy":[24.80482,30.80696,33.98177,28.25298]}, + {"t":0.51874, "x":3.01449, "y":3.41379, "heading":-0.81433, "vx":-2.23029, "vy":2.36765, "omega":-1.04918, "ax":-6.38797, "ay":0.52388, "alpha":-0.13582, "fx":[-108.73581,-108.64791,-108.57506,-108.67152], "fy":[7.92541,8.96324,9.8954,8.86016]}, + {"t":0.54605, "x":2.95121, "y":3.47863, "heading":-0.84297, "vx":-2.4047, "vy":2.38195, "omega":-1.05289, "ax":-6.32947, "ay":-0.97076, "alpha":0.51586, "fx":[-108.18752,-107.83605,-107.0883,-107.53788], "fy":[-12.85009,-15.77303,-20.11421,-17.31222]}, + {"t":0.57335, "x":2.8832, "y":3.5433, "heading":-0.87172, "vx":-2.57751, "vy":2.35545, "omega":-1.0388, "ax":-5.86257, "ay":-2.55309, "alpha":1.17041, "fx":[-102.68227,-101.38378,-96.81794,-97.99849], "fy":[-36.2737,-40.01284,-50.00595,-47.41665]}, + {"t":0.60065, "x":2.81064, "y":3.60666, "heading":-0.90008, "vx":-2.73757, "vy":2.28574, "omega":-1.00685, "ax":-5.04903, "ay":-3.91201, "alpha":1.64541, "fx":[-91.39425,-90.69052,-81.14374,-80.3018], "fy":[-59.22508,-60.54104,-72.83824,-73.56434]}, + {"t":0.62795, "x":2.73402, "y":3.6676, "heading":-0.92757, "vx":-2.87542, "vy":2.17893, "omega":-0.96193, "ax":-4.16705, "ay":-4.84789, "alpha":1.61476, "fx":[-76.12425,-77.90698,-66.65786,-62.83233], "fy":[-77.9835,-76.38037,-86.39896,-89.08178]}, + {"t":0.65526, "x":2.65396, "y":3.72529, "heading":-0.95384, "vx":-2.98919, "vy":2.04657, "omega":-0.91784, "ax":-3.49053, "ay":-5.37869, "alpha":0.80538, "fx":[-61.43194,-63.77919,-57.56284,-54.71744], "fy":[-90.17198,-88.59202,-92.77274,-94.42313]}, + {"t":0.68256, "x":2.57105, "y":3.77916, "heading":-0.97889, "vx":-3.08449, "vy":1.89972, "omega":-0.89585, "ax":-2.95289, "ay":-5.7022, "alpha":-0.06391, "fx":[-50.11352,-49.82921,-50.34356,-50.62521], "fy":[-97.05541,-97.19793,-96.93044,-96.78744]}, + {"t":0.70986, "x":2.48573, "y":3.8289, "heading":-1.00335, "vx":-3.16511, "vy":1.74404, "omega":-0.89759, "ax":-2.48751, "ay":-5.92084, "alpha":-0.68492, "fx":[-41.55226,-37.71489,-43.1863,-46.79399], "fy":[-101.11602,-102.57888,-100.37364,-98.7784]}, + {"t":0.73716, "x":2.39839, "y":3.87431, "heading":-1.02786, "vx":-3.23303, "vy":1.58239, "omega":-0.91629, "ax":-2.07752, "ay":-6.07551, "alpha":-1.0598, "fx":[-34.79623,-27.94811,-36.05601,-42.55205], "fy":[-103.7071,-105.72204,-103.19994,-100.74185]}, + {"t":0.76447, "x":2.30935, "y":3.91525, "heading":-1.05288, "vx":-3.28975, "vy":1.41651, "omega":-0.94523, "ax":-1.62559, "ay":-6.2059, "alpha":-1.33728, "fx":[-27.81585,-18.1541,-27.57609,-37.05755], "fy":[-105.78865,-107.82683,-105.75457,-102.87228]}, + {"t":0.79085, "x":2.22198, "y":3.95046, "heading":-1.07782, "vx":-3.33264, "vy":1.25276, "omega":-0.98052, "ax":-0.96807, "ay":-6.33534, "alpha":-1.50866, "fx":[-17.91243,-5.80578,-14.79486,-27.35327], "fy":[-107.86741,-109.14923,-108.22326,-105.80923]}, + {"t":0.81724, "x":2.13371, "y":3.98131, "heading":-1.10369, "vx":-3.35818, "vy":1.0856, "omega":-1.02032, "ax":-0.11211, "ay":-6.40723, "alpha":-1.40745, "fx":[-4.70933,7.61341,1.43231,-11.96392], "fy":[-109.19436,-108.99837,-109.17524,-108.57288]}, + {"t":0.84362, "x":2.04506, "y":4.00773, "heading":-1.13061, "vx":-3.36114, "vy":0.91654, "omega":-1.05746, "ax":0.91179, "ay":-6.34619, "alpha":-1.10548, "fx":[12.01967,22.29584,19.50517,8.21634], "fy":[-108.58212,-106.9284,-107.40319,-108.87357]}, + {"t":0.87001, "x":1.95669, "y":4.0297, "heading":-1.15851, "vx":-3.33708, "vy":0.74908, "omega":-1.08663, "ax":2.02912, "ay":-6.08618, "alpha":-0.67048, "fx":[31.65751,37.97849,37.58084,30.84239], "fy":[-104.51481,-102.38363,-102.48441,-104.71414]}, + {"t":0.8964, "x":1.86934, "y":4.04735, "heading":-1.18719, "vx":-3.28354, "vy":0.58849, "omega":-1.10432, "ax":3.12613, "ay":-5.60575, "alpha":-0.16872, "fx":[52.33317,53.83158,54.02684,52.50672], "fy":[-95.82592,-94.99377,-94.87054,-95.71866]}, + {"t":0.92278, "x":1.78379, "y":4.06093, "heading":-1.21632, "vx":-3.20106, "vy":0.44058, "omega":-1.10877, "ax":4.08718, "ay":-4.94983, "alpha":0.33539, "fx":[71.22804,68.68157,67.83785,70.33983], "fy":[-82.76661,-84.88239,-85.58367,-83.54807]}, + {"t":0.94917, "x":1.70075, "y":4.07083, "heading":-1.24558, "vx":-3.09321, "vy":0.30997, "omega":-1.09992, "ax":4.84494, "ay":-4.20884, "alpha":0.79067, "fx":[86.06235,81.42906,78.75831,83.39461], "fy":[-67.27003,-72.77136,-75.71463,-70.60844]}, + {"t":0.97555, "x":1.62082, "y":4.07754, "heading":-1.2746, "vx":-2.96537, "vy":0.19892, "omega":-1.07906, "ax":5.39484, "ay":-3.47138, "alpha":1.16948, "fx":[96.25679,91.4489,87.05914,92.29402], "fy":[-51.75168,-59.75422,-66.07504,-58.60793]}, + {"t":1.00194, "x":1.54445, "y":4.08158, "heading":-1.30308, "vx":-2.82302, "vy":0.10732, "omega":-1.0482, "ax":5.77166, "ay":-2.79393, "alpha":1.47099, "fx":[102.59213,98.70786,93.2296,98.16757], "fy":[-37.82807,-46.89478,-57.1215,-48.2513]}, + {"t":1.02833, "x":1.47197, "y":4.08344, "heading":-1.33073, "vx":-2.67073, "vy":0.0336, "omega":-1.00939, "ax":6.02037, "ay":-2.19968, "alpha":1.7089, "fx":[106.24365,103.59106,97.76896,102.01518], "fy":[-26.08134,-34.94059,-49.0372,-39.60448]}, + {"t":1.05471, "x":1.4036, "y":4.08356, "heading":-1.35737, "vx":-2.51188, "vy":-0.02444, "omega":-0.9643, "ax":6.18017, "ay":-1.69063, "alpha":1.89818, "fx":[108.20248,106.64234,101.09709,104.54948], "fy":[-16.45316,-24.26632,-41.84242,-32.46663]}, + {"t":1.0811, "x":1.33947, "y":4.08233, "heading":-1.38281, "vx":-2.34881, "vy":-0.06905, "omega":-0.91421, "ax":6.28026, "ay":-1.25883, "alpha":2.05026, "fx":[109.14678,108.3811,103.53699,106.23682], "fy":[-8.6351,-14.96348,-35.47774,-26.57322]}, + {"t":1.10749, "x":1.27968, "y":4.08007, "heading":-1.40693, "vx":-2.1831, "vy":-0.10226, "omega":-0.86011, "ax":6.34086, "ay":-0.89317, "alpha":2.17326, "fx":[109.49962,109.22484,105.32677,107.37342], "fy":[-2.27868,-6.96007,-29.85373,-21.67782]}, + {"t":1.13387, "x":1.22429, "y":4.07706, "heading":-1.42963, "vx":-2.01579, "vy":-0.12583, "omega":-0.80277, "ax":6.37547, "ay":-0.5826, "alpha":2.27307, "fx":[109.51454,109.47966,106.63879,108.14673], "fy":[2.9244,-0.11171,-24.8764,-17.57548]}, + {"t":1.16026, "x":1.17332, "y":4.07354, "heading":-1.45081, "vx":-1.84756, "vy":-0.1412, "omega":-0.74279, "ax":6.39301, "ay":-0.31738, "alpha":2.35424, "fx":[109.34108,109.35856,107.59734,108.67641], "fy":[7.22353,5.74442,-20.45862,-14.10333]}, + {"t":1.18664, "x":1.12679, "y":4.0697, "heading":-1.47041, "vx":-1.67888, "vy":-0.14958, "omega":-0.68067, "ax":6.39935, "ay":-0.08939, "alpha":2.42037, "fx":[109.06693,109.00545,108.29234,109.03993], "fy":[10.81324,10.76314,-16.52415,-11.13428]}, + {"t":1.21303, "x":1.08472, "y":4.06572, "heading":-1.48837, "vx":-1.51002, "vy":-0.15194, "omega":-0.61681, "ax":6.39835, "ay":0.10797, "alpha":2.47441, "fx":[108.74325,108.5158,108.78939,109.28826], "fy":[13.84335,15.08074,-13.00819,-8.56956]}, + {"t":1.23942, "x":1.0471, "y":4.06175, "heading":-1.50465, "vx":-1.3412, "vy":-0.14909, "omega":-0.55152, "ax":6.39259, "ay":0.28003, "alpha":2.51874, "fx":[108.39965,107.95224,109.13688,109.45549], "fy":[16.42908,18.81265,-9.85639,-6.33228]}, + {"t":1.2658, "x":1.01394, "y":4.05792, "heading":-1.5192, "vx":-1.17252, "vy":-0.1417, "omega":-0.48506, "ax":6.38376, "ay":0.43105, "alpha":2.5553, "fx":[108.05294,107.35538,109.37086,109.56481], "fy":[18.65945,22.05472,-7.02348,-4.36221]}, + {"t":1.29219, "x":0.98522, "y":4.05433, "heading":-1.532, "vx":-1.00408, "vy":-0.13033, "omega":-0.41763, "ax":6.37304, "ay":0.56447, "alpha":2.58565, "fx":[107.71227,106.75128,109.51858,109.6322], "fy":[20.60373,24.88578,-4.47174,-2.61186]}, + {"t":1.31857, "x":0.96095, "y":4.05108, "heading":-1.54302, "vx":-0.83592, "vy":-0.11543, "omega":-0.34941, "ax":6.36119, "ay":0.68305, "alpha":2.61106, "fx":[107.38222,106.15632,109.60083,109.66885], "fy":[22.3163,27.3704,-2.16968,-1.0434]}, + {"t":1.34496, "x":0.94111, "y":4.04828, "heading":-1.55224, "vx":-0.66807, "vy":-0.09741, "omega":-0.28051, "ax":6.34875, "ay":0.78903, "alpha":2.63254, "fx":[107.06467,105.58058,109.63366,109.68266], "fy":[23.84025,29.56152,-0.09087,0.37352]}, + {"t":1.37135, "x":0.92569, "y":4.04598, "heading":-1.55964, "vx":-0.50055, "vy":-0.07659, "omega":-0.21105, "ax":6.33607, "ay":0.88424, "alpha":2.65092, "fx":[106.75986,105.02991,109.62958,109.67929], "fy":[25.21003,31.50255,1.78695,1.66349]}, + {"t":1.39773, "x":0.91469, "y":4.04427, "heading":-1.56521, "vx":-0.33337, "vy":-0.05326, "omega":-0.1411, "ax":6.32338, "ay":0.97021, "alpha":2.66684, "fx":[106.4671,104.50746,109.59844,109.66281], "fy":[26.45341,33.22922,3.48269,2.84663]}, + {"t":1.42412, "x":0.90809, "y":4.0432, "heading":-1.56893, "vx":-0.16652, "vy":-0.02766, "omega":-0.07074, "ax":6.31087, "ay":1.04817, "alpha":2.68083, "fx":[106.18518,104.01465,109.54802,109.63619], "fy":[27.59298,34.77103,5.01251,3.93957]}, + {"t":1.4505, "x":0.9059, "y":4.04284, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH5.traj b/src/main/deploy/choreo/E_RIGHT_PATH5.traj new file mode 100644 index 00000000..1bc05343 --- /dev/null +++ b/src/main/deploy/choreo/E_RIGHT_PATH5.traj @@ -0,0 +1,58 @@ +{ + "name":"E_RIGHT_PATH5", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":0.9058957099914552, "y":4.042835235595703, "heading":-1.5707963267948966, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.8561482429504395, "y":3.878795623779297, "heading":-1.5707963267948966, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"0.9058957099914551 m", "val":0.9058957099914552}, "y":{"exp":"4.042835235595703 m", "val":4.042835235595703}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.8561482429504395 m", "val":2.8561482429504395}, "y":{"exp":"3.878795623779297 m", "val":3.878795623779297}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.10287], + "samples":[ + {"t":0.0, "x":0.9059, "y":4.04284, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.4304, "ay":-0.54087, "alpha":0.0, "fx":[109.37931,109.37931,109.37931,109.37931], "fy":[-9.20011,-9.20011,-9.20011,-9.20011]}, + {"t":0.04795, "x":0.91329, "y":4.04221, "heading":-1.5708, "vx":0.30834, "vy":-0.02594, "omega":0.0, "ax":6.42984, "ay":-0.54083, "alpha":0.0, "fx":[109.36979,109.36979,109.36979,109.36979], "fy":[-9.19931,-9.19931,-9.19931,-9.19931]}, + {"t":0.0959, "x":0.93547, "y":4.04035, "heading":-1.5708, "vx":0.61666, "vy":-0.05187, "omega":0.0, "ax":6.42916, "ay":-0.54077, "alpha":0.0, "fx":[109.35815,109.35815,109.35815,109.35815], "fy":[-9.19833,-9.19833,-9.19833,-9.19833]}, + {"t":0.14385, "x":0.97243, "y":4.03724, "heading":-1.5708, "vx":0.92494, "vy":-0.0778, "omega":0.0, "ax":6.4283, "ay":-0.5407, "alpha":0.0, "fx":[109.3436,109.3436,109.3436,109.3436], "fy":[-9.19711,-9.19711,-9.19711,-9.19711]}, + {"t":0.1918, "x":1.02417, "y":4.03289, "heading":-1.5708, "vx":1.23319, "vy":-0.10373, "omega":0.0, "ax":6.4272, "ay":-0.5406, "alpha":0.0, "fx":[109.3249,109.3249,109.3249,109.3249], "fy":[-9.19553,-9.19553,-9.19553,-9.19553]}, + {"t":0.23975, "x":1.09069, "y":4.02729, "heading":-1.5708, "vx":1.54138, "vy":-0.12965, "omega":0.0, "ax":6.42574, "ay":-0.54048, "alpha":0.0, "fx":[109.29995,109.29995,109.29995,109.29995], "fy":[-9.19344,-9.19344,-9.19344,-9.19344]}, + {"t":0.28771, "x":1.17199, "y":4.02045, "heading":-1.5708, "vx":1.8495, "vy":-0.15556, "omega":0.0, "ax":6.42368, "ay":-0.54031, "alpha":0.0, "fx":[109.26503,109.26503,109.26503,109.26503], "fy":[-9.1905,-9.1905,-9.1905,-9.1905]}, + {"t":0.33566, "x":1.26806, "y":4.01237, "heading":-1.5708, "vx":2.15752, "vy":-0.18147, "omega":0.0, "ax":6.4206, "ay":-0.54005, "alpha":0.0, "fx":[109.21265,109.21265,109.21265,109.21265], "fy":[-9.18609,-9.18609,-9.18609,-9.18609]}, + {"t":0.38361, "x":1.37889, "y":4.00305, "heading":-1.5708, "vx":2.46539, "vy":-0.20737, "omega":0.0, "ax":6.41547, "ay":-0.53962, "alpha":0.0, "fx":[109.12537,109.12537,109.12537,109.12537], "fy":[-9.17875,-9.17875,-9.17875,-9.17875]}, + {"t":0.43156, "x":1.50449, "y":3.99249, "heading":-1.5708, "vx":2.77302, "vy":-0.23324, "omega":0.0, "ax":6.40522, "ay":-0.53876, "alpha":0.0, "fx":[108.95094,108.95094,108.95094,108.95094], "fy":[-9.16408,-9.16408,-9.16408,-9.16408]}, + {"t":0.47951, "x":1.64482, "y":3.98068, "heading":-1.5708, "vx":3.08016, "vy":-0.25908, "omega":0.0, "ax":6.37453, "ay":-0.53617, "alpha":0.0, "fx":[108.429,108.429,108.429,108.429], "fy":[-9.12018,-9.12018,-9.12018,-9.12018]}, + {"t":0.52746, "x":1.79985, "y":3.96764, "heading":-1.5708, "vx":3.38582, "vy":-0.28479, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.57541, "x":1.9622, "y":3.95399, "heading":-1.5708, "vx":3.38582, "vy":-0.28479, "omega":0.0, "ax":-6.37453, "ay":0.53617, "alpha":0.0, "fx":[-108.429,-108.429,-108.429,-108.429], "fy":[9.12018,9.12018,9.12018,9.12018]}, + {"t":0.62336, "x":2.11722, "y":3.94095, "heading":-1.5708, "vx":3.08016, "vy":-0.25908, "omega":0.0, "ax":-6.40522, "ay":0.53876, "alpha":0.0, "fx":[-108.95094,-108.95094,-108.95094,-108.95094], "fy":[9.16408,9.16408,9.16408,9.16408]}, + {"t":0.67131, "x":2.25756, "y":3.92914, "heading":-1.5708, "vx":2.77302, "vy":-0.23324, "omega":0.0, "ax":-6.41547, "ay":0.53962, "alpha":0.0, "fx":[-109.12537,-109.12537,-109.12537,-109.12537], "fy":[9.17875,9.17875,9.17875,9.17875]}, + {"t":0.71926, "x":2.38315, "y":3.91858, "heading":-1.5708, "vx":2.46539, "vy":-0.20737, "omega":0.0, "ax":-6.4206, "ay":0.54005, "alpha":0.0, "fx":[-109.21265,-109.21265,-109.21265,-109.21265], "fy":[9.18609,9.18609,9.18609,9.18609]}, + {"t":0.76721, "x":2.49399, "y":3.90926, "heading":-1.5708, "vx":2.15752, "vy":-0.18147, "omega":0.0, "ax":-6.42368, "ay":0.54031, "alpha":0.0, "fx":[-109.26503,-109.26503,-109.26503,-109.26503], "fy":[9.1905,9.1905,9.1905,9.1905]}, + {"t":0.81517, "x":2.59006, "y":3.90118, "heading":-1.5708, "vx":1.8495, "vy":-0.15556, "omega":0.0, "ax":-6.42574, "ay":0.54048, "alpha":0.0, "fx":[-109.29995,-109.29995,-109.29995,-109.29995], "fy":[9.19344,9.19344,9.19344,9.19344]}, + {"t":0.86312, "x":2.67135, "y":3.89434, "heading":-1.5708, "vx":1.54138, "vy":-0.12965, "omega":0.0, "ax":-6.4272, "ay":0.5406, "alpha":0.0, "fx":[-109.3249,-109.3249,-109.3249,-109.3249], "fy":[9.19553,9.19553,9.19553,9.19553]}, + {"t":0.91107, "x":2.73788, "y":3.88874, "heading":-1.5708, "vx":1.23319, "vy":-0.10373, "omega":0.0, "ax":-6.4283, "ay":0.5407, "alpha":0.0, "fx":[-109.3436,-109.3436,-109.3436,-109.3436], "fy":[9.19711,9.19711,9.19711,9.19711]}, + {"t":0.95902, "x":2.78962, "y":3.88439, "heading":-1.5708, "vx":0.92494, "vy":-0.0778, "omega":0.0, "ax":-6.42916, "ay":0.54077, "alpha":0.0, "fx":[-109.35815,-109.35815,-109.35815,-109.35815], "fy":[9.19833,9.19833,9.19833,9.19833]}, + {"t":1.00697, "x":2.82658, "y":3.88128, "heading":-1.5708, "vx":0.61666, "vy":-0.05187, "omega":0.0, "ax":-6.42984, "ay":0.54083, "alpha":0.0, "fx":[-109.36979,-109.36979,-109.36979,-109.36979], "fy":[9.19931,9.19931,9.19931,9.19931]}, + {"t":1.05492, "x":2.84876, "y":3.87942, "heading":-1.5708, "vx":0.30834, "vy":-0.02594, "omega":0.0, "ax":-6.4304, "ay":0.54087, "alpha":0.0, "fx":[-109.37931,-109.37931,-109.37931,-109.37931], "fy":[9.20011,9.20011,9.20011,9.20011]}, + {"t":1.10287, "x":2.85615, "y":3.8788, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH6.traj b/src/main/deploy/choreo/E_RIGHT_PATH6.traj new file mode 100644 index 00000000..235021fc --- /dev/null +++ b/src/main/deploy/choreo/E_RIGHT_PATH6.traj @@ -0,0 +1,78 @@ +{ + "name":"E_RIGHT_PATH6", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":2.8561482429504395, "y":3.878795623779297, "heading":-1.5707963267948966, "intervals":22, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.145307779312134, "y":5.592101097106934, "heading":-1.5707963267948966, "intervals":19, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":0.8512157797813416, "y":5.810821056365967, "heading":-1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"2.8561482429504395 m", "val":2.8561482429504395}, "y":{"exp":"3.878795623779297 m", "val":3.878795623779297}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":22, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.145307779312134 m", "val":2.145307779312134}, "y":{"exp":"5.592101097106934 m", "val":5.592101097106934}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":19, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"0.8512157797813416 m", "val":0.8512157797813416}, "y":{"exp":"5.810821056365967 m", "val":5.810821056365967}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.85028,1.54355], + "samples":[ + {"t":0.0, "x":2.85615, "y":3.8788, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-0.03288, "ay":6.45173, "alpha":0.0, "fx":[-0.55927,-0.55927,-0.55927,-0.55927], "fy":[109.74203,109.74203,109.74203,109.74203]}, + {"t":0.03865, "x":2.85612, "y":3.88361, "heading":-1.5708, "vx":-0.00127, "vy":0.24935, "omega":0.0, "ax":-0.13527, "ay":6.44985, "alpha":0.0, "fx":[-2.30084,-2.30084,-2.30084,-2.30084], "fy":[109.71011,109.71011,109.71011,109.71011]}, + {"t":0.0773, "x":2.85597, "y":3.89807, "heading":-1.5708, "vx":-0.0065, "vy":0.49863, "omega":0.0, "ax":-0.25498, "ay":6.4456, "alpha":0.0, "fx":[-4.3372,-4.3372,-4.3372,-4.3372], "fy":[109.63773,109.63773,109.63773,109.63773]}, + {"t":0.11595, "x":2.85553, "y":3.92215, "heading":-1.5708, "vx":-0.01635, "vy":0.74775, "omega":0.0, "ax":-0.39667, "ay":6.43768, "alpha":0.0, "fx":[-6.74733,-6.74733,-6.74733,-6.74733], "fy":[109.50314,109.50314,109.50314,109.50314]}, + {"t":0.1546, "x":2.8546, "y":3.95586, "heading":-1.5708, "vx":-0.03168, "vy":0.99656, "omega":0.0, "ax":-0.56672, "ay":6.42405, "alpha":0.0, "fx":[-9.63973,-9.63973,-9.63973,-9.63973], "fy":[109.27132,109.27132,109.27132,109.27132]}, + {"t":0.19324, "x":2.85296, "y":3.99918, "heading":-1.5708, "vx":-0.05359, "vy":1.24484, "omega":0.0, "ax":-0.77407, "ay":6.40129, "alpha":0.0, "fx":[-13.16676,-13.16676,-13.16676,-13.16676], "fy":[108.88416,108.88416,108.88416,108.88416]}, + {"t":0.23189, "x":2.85031, "y":4.05207, "heading":-1.5708, "vx":-0.0835, "vy":1.49225, "omega":0.0, "ax":-1.03158, "ay":6.36352, "alpha":0.0, "fx":[-17.54696,-17.54696,-17.54696,-17.54696], "fy":[108.24173,108.24173,108.24173,108.24173]}, + {"t":0.27054, "x":2.84631, "y":4.1145, "heading":-1.5708, "vx":-0.12337, "vy":1.73819, "omega":0.0, "ax":-1.35805, "ay":6.30022, "alpha":0.0, "fx":[-23.1001,-23.1001,-23.1001,-23.1001], "fy":[107.16496,107.16496,107.16496,107.16496]}, + {"t":0.30919, "x":2.84053, "y":4.18638, "heading":-1.5708, "vx":-0.17586, "vy":1.98169, "omega":0.0, "ax":-1.78132, "ay":6.19165, "alpha":0.0, "fx":[-30.29968,-30.29968,-30.29968,-30.29968], "fy":[105.31814,105.31814,105.31814,105.31814]}, + {"t":0.34784, "x":2.8324, "y":4.26759, "heading":-1.5708, "vx":-0.24471, "vy":2.22099, "omega":0.0, "ax":-2.34205, "ay":5.99905, "alpha":0.0, "fx":[-39.83754,-39.83754,-39.83754,-39.83754], "fy":[102.04213,102.04213,102.04213,102.04213]}, + {"t":0.38649, "x":2.82119, "y":4.35791, "heading":-1.5708, "vx":-0.33523, "vy":2.45284, "omega":0.0, "ax":-3.09443, "ay":5.64372, "alpha":0.0, "fx":[-52.63535,-52.63535,-52.63535,-52.63535], "fy":[95.99808,95.99808,95.99808,95.99808]}, + {"t":0.42514, "x":2.80592, "y":4.45693, "heading":-1.5708, "vx":-0.45482, "vy":2.67097, "omega":0.0, "ax":-4.08459, "ay":4.96836, "alpha":0.0, "fx":[-69.47768,-69.47768,-69.47768,-69.47768], "fy":[84.51037,84.51037,84.51037,84.51037]}, + {"t":0.46379, "x":2.7853, "y":4.56387, "heading":-1.5708, "vx":-0.61269, "vy":2.86299, "omega":0.0, "ax":-5.24651, "ay":3.71216, "alpha":0.0, "fx":[-89.24159,-89.24159,-89.24159,-89.24159], "fy":[63.14277,63.14277,63.14277,63.14277]}, + {"t":0.50244, "x":2.7577, "y":4.67729, "heading":-1.5708, "vx":-0.81546, "vy":3.00646, "omega":0.0, "ax":-6.19357, "ay":1.70531, "alpha":0.0, "fx":[-105.35091,-105.35091,-105.35091,-105.35091], "fy":[29.0068,29.0068,29.0068,29.0068]}, + {"t":0.54109, "x":2.72155, "y":4.79476, "heading":-1.5708, "vx":-1.05484, "vy":3.07237, "omega":0.0, "ax":-6.39591, "ay":-0.61517, "alpha":0.0, "fx":[-108.79267,-108.79267,-108.79267,-108.79267], "fy":[-10.46392,-10.46392,-10.46392,-10.46392]}, + {"t":0.57973, "x":2.67601, "y":4.91305, "heading":-1.5708, "vx":-1.30203, "vy":3.04859, "omega":0.0, "ax":-5.93068, "ay":-2.48406, "alpha":0.0, "fx":[-100.87913,-100.87913,-100.87913,-100.87913], "fy":[-42.25308,-42.25308,-42.25308,-42.25308]}, + {"t":0.61838, "x":2.62126, "y":5.02902, "heading":-1.5708, "vx":-1.53125, "vy":2.95259, "omega":0.0, "ax":-5.26731, "ay":-3.69606, "alpha":0.0, "fx":[-89.59539,-89.59539,-89.59539,-89.59539], "fy":[-62.86897,-62.86897,-62.86897,-62.86897]}, + {"t":0.65703, "x":2.55814, "y":5.14037, "heading":-1.5708, "vx":-1.73482, "vy":2.80974, "omega":0.0, "ax":-4.66407, "ay":-4.43883, "alpha":0.0, "fx":[-79.33457,-79.33457,-79.33457,-79.33457], "fy":[-75.50329,-75.50329,-75.50329,-75.50329]}, + {"t":0.69568, "x":2.48761, "y":5.24565, "heading":-1.5708, "vx":-1.91508, "vy":2.63818, "omega":0.0, "ax":-4.17646, "ay":-4.90446, "alpha":0.0, "fx":[-71.04039,-71.04039,-71.04039,-71.04039], "fy":[-83.42349,-83.42349,-83.42349,-83.42349]}, + {"t":0.73433, "x":2.41047, "y":5.34395, "heading":-1.5708, "vx":-2.0765, "vy":2.44863, "omega":0.0, "ax":-3.79243, "ay":-5.21004, "alpha":0.0, "fx":[-64.50817,-64.50817,-64.50817,-64.50817], "fy":[-88.62122,-88.62122,-88.62122,-88.62122]}, + {"t":0.77298, "x":2.32739, "y":5.4347, "heading":-1.5708, "vx":-2.22307, "vy":2.24727, "omega":0.0, "ax":-3.48882, "ay":-5.42022, "alpha":0.0, "fx":[-59.34377,-59.34377,-59.34377,-59.34377], "fy":[-92.19642,-92.19642,-92.19642,-92.19642]}, + {"t":0.81163, "x":2.23886, "y":5.5175, "heading":-1.5708, "vx":-2.35791, "vy":2.03778, "omega":0.0, "ax":-3.24556, "ay":-5.57097, "alpha":0.0, "fx":[-55.20609,-55.20609,-55.20609,-55.20609], "fy":[-94.76054,-94.76054,-94.76054,-94.76054]}, + {"t":0.85028, "x":2.14531, "y":5.5921, "heading":-1.5708, "vx":-2.48335, "vy":1.82247, "omega":0.0, "ax":-2.96055, "ay":-5.72676, "alpha":0.0, "fx":[-50.35806,-50.35806,-50.35806,-50.35806], "fy":[-97.41047,-97.41047,-97.41047,-97.41047]}, + {"t":0.88677, "x":2.05272, "y":5.65479, "heading":-1.5708, "vx":-2.59137, "vy":1.61351, "omega":0.0, "ax":-2.51661, "ay":-5.93359, "alpha":0.0, "fx":[-42.8068,-42.8068,-42.8068,-42.8068], "fy":[-100.92866,-100.92866,-100.92866,-100.92866]}, + {"t":0.92325, "x":1.9565, "y":5.70971, "heading":-1.5708, "vx":-2.6832, "vy":1.39701, "omega":0.0, "ax":-1.92603, "ay":-6.14877, "alpha":0.0, "fx":[-32.76117,-32.76117,-32.76117,-32.76117], "fy":[-104.58881,-104.58881,-104.58881,-104.58881]}, + {"t":0.95974, "x":1.85731, "y":5.75659, "heading":-1.5708, "vx":-2.75348, "vy":1.17265, "omega":0.0, "ax":-1.13172, "ay":-6.34098, "alpha":0.0, "fx":[-19.25029,-19.25029,-19.25029,-19.25029], "fy":[-107.8582,-107.8582,-107.8582,-107.8582]}, + {"t":0.99623, "x":1.75609, "y":5.79516, "heading":-1.5708, "vx":-2.79477, "vy":0.94128, "omega":0.0, "ax":-0.07234, "ay":-6.43835, "alpha":0.0, "fx":[-1.2304,-1.2304,-1.2304,-1.2304], "fy":[-109.51456,-109.51456,-109.51456,-109.51456]}, + {"t":1.03272, "x":1.65406, "y":5.82522, "heading":-1.5708, "vx":-2.79741, "vy":0.70636, "omega":0.0, "ax":1.2733, "ay":-6.30928, "alpha":0.0, "fx":[21.65848,21.65848,21.65848,21.65848], "fy":[-107.31901,-107.31901,-107.31901,-107.31901]}, + {"t":1.06921, "x":1.55284, "y":5.84679, "heading":-1.5708, "vx":-2.75095, "vy":0.47615, "omega":0.0, "ax":2.79607, "ay":-5.79585, "alpha":0.0, "fx":[47.56039,47.56039,47.56039,47.56039], "fy":[-98.58573,-98.58573,-98.58573,-98.58573]}, + {"t":1.10569, "x":1.45432, "y":5.86031, "heading":-1.5708, "vx":-2.64893, "vy":0.26467, "omega":0.0, "ax":4.22027, "ay":-4.85803, "alpha":0.0, "fx":[71.7856,71.7856,71.7856,71.7856], "fy":[-82.63368,-82.63368,-82.63368,-82.63368]}, + {"t":1.14218, "x":1.36048, "y":5.86673, "heading":-1.5708, "vx":-2.49494, "vy":0.08741, "omega":0.0, "ax":5.27988, "ay":-3.68161, "alpha":0.0, "fx":[89.80921,89.80921,89.80921,89.80921], "fy":[-62.62313,-62.62313,-62.62313,-62.62313]}, + {"t":1.17867, "x":1.27296, "y":5.86747, "heading":-1.5708, "vx":-2.30229, "vy":-0.04692, "omega":0.0, "ax":5.92127, "ay":-2.52981, "alpha":0.0, "fx":[100.71903,100.71903,100.71903,100.71903], "fy":[-43.03142,-43.03142,-43.03142,-43.03142]}, + {"t":1.21516, "x":1.1929, "y":5.86407, "heading":-1.5708, "vx":-2.08623, "vy":-0.13923, "omega":0.0, "ax":6.25183, "ay":-1.55143, "alpha":0.0, "fx":[106.34182,106.34182,106.34182,106.34182], "fy":[-26.38945,-26.38945,-26.38945,-26.38945]}, + {"t":1.25164, "x":1.12093, "y":5.85796, "heading":-1.5708, "vx":-1.85812, "vy":-0.19584, "omega":0.0, "ax":6.39716, "ay":-0.77221, "alpha":0.0, "fx":[108.81392,108.81392,108.81392,108.81392], "fy":[-13.13501,-13.13501,-13.13501,-13.13501]}, + {"t":1.28813, "x":1.05739, "y":5.8503, "heading":-1.5708, "vx":-1.6247, "vy":-0.22402, "omega":0.0, "ax":6.44334, "ay":-0.16359, "alpha":0.0, "fx":[109.59934,109.59934,109.59934,109.59934], "fy":[-2.78267,-2.78267,-2.78267,-2.78267]}, + {"t":1.32462, "x":1.0024, "y":5.84202, "heading":-1.5708, "vx":-1.38959, "vy":-0.22999, "omega":0.0, "ax":6.43932, "ay":0.31289, "alpha":0.0, "fx":[109.53092,109.53092,109.53092,109.53092], "fy":[5.32212,5.32212,5.32212,5.32212]}, + {"t":1.36111, "x":0.95599, "y":5.83383, "heading":-1.5708, "vx":-1.15463, "vy":-0.21857, "omega":0.0, "ax":6.41109, "ay":0.69029, "alpha":0.0, "fx":[109.05089,109.05089,109.05089,109.05089], "fy":[11.74167,11.74167,11.74167,11.74167]}, + {"t":1.3976, "x":0.91812, "y":5.82632, "heading":-1.5708, "vx":-0.92071, "vy":-0.19338, "omega":0.0, "ax":6.37216, "ay":0.99369, "alpha":0.0, "fx":[108.38867,108.38867,108.38867,108.38867], "fy":[16.90232,16.90232,16.90232,16.90232]}, + {"t":1.43408, "x":0.88877, "y":5.81992, "heading":-1.5708, "vx":-0.6882, "vy":-0.15712, "omega":0.0, "ax":6.32946, "ay":1.24132, "alpha":0.0, "fx":[107.66232,107.66232,107.66232,107.66232], "fy":[21.11458,21.11458,21.11458,21.11458]}, + {"t":1.47057, "x":0.86787, "y":5.81502, "heading":-1.5708, "vx":-0.45725, "vy":-0.11183, "omega":0.0, "ax":6.28652, "ay":1.4464, "alpha":0.0, "fx":[106.93183,106.93183,106.93183,106.93183], "fy":[24.60281,24.60281,24.60281,24.60281]}, + {"t":1.50706, "x":0.85537, "y":5.8119, "heading":-1.5708, "vx":-0.22787, "vy":-0.05906, "omega":0.0, "ax":6.24507, "ay":1.61849, "alpha":0.0, "fx":[106.22678,106.22678,106.22678,106.22678], "fy":[27.53001,27.53001,27.53001,27.53001]}, + {"t":1.54355, "x":0.85122, "y":5.81082, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH7.traj b/src/main/deploy/choreo/E_RIGHT_PATH7.traj new file mode 100644 index 00000000..85cb3fa9 --- /dev/null +++ b/src/main/deploy/choreo/E_RIGHT_PATH7.traj @@ -0,0 +1,61 @@ +{ + "name":"E_RIGHT_PATH7", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":0.8512157797813416, "y":5.810821056365967, "heading":-1.5707963267948966, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.892600774765014, "y":4.152195453643799, "heading":-1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"0.8512157797813416 m", "val":0.8512157797813416}, "y":{"exp":"5.810821056365967 m", "val":5.810821056365967}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.8926007747650146 m", "val":2.892600774765014}, "y":{"exp":"4.152195453643799 m", "val":4.152195453643799}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.27916], + "samples":[ + {"t":0.0, "x":0.85122, "y":5.81082, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.00847, "ay":-4.06938, "alpha":0.0, "fx":[85.19267,85.19267,85.19267,85.19267], "fy":[-69.21905,-69.21905,-69.21905,-69.21905]}, + {"t":0.0492, "x":0.85728, "y":5.8059, "heading":-1.5708, "vx":0.24641, "vy":-0.20021, "omega":0.0, "ax":5.00809, "ay":-4.06907, "alpha":0.0, "fx":[85.18611,85.18611,85.18611,85.18611], "fy":[-69.21373,-69.21373,-69.21373,-69.21373]}, + {"t":0.0984, "x":0.87546, "y":5.79112, "heading":-1.5708, "vx":0.4928, "vy":-0.4004, "omega":0.0, "ax":5.00762, "ay":-4.06869, "alpha":0.0, "fx":[85.17824,85.17824,85.17824,85.17824], "fy":[-69.20734,-69.20734,-69.20734,-69.20734]}, + {"t":0.1476, "x":0.90577, "y":5.7665, "heading":-1.5708, "vx":0.73917, "vy":-0.60057, "omega":0.0, "ax":5.00706, "ay":-4.06824, "alpha":0.0, "fx":[85.16863,85.16863,85.16863,85.16863], "fy":[-69.19952,-69.19952,-69.19952,-69.19952]}, + {"t":0.19679, "x":0.94819, "y":5.73203, "heading":-1.5708, "vx":0.9855, "vy":-0.80072, "omega":0.0, "ax":5.00635, "ay":-4.06766, "alpha":0.0, "fx":[85.15661,85.15661,85.15661,85.15661], "fy":[-69.18975,-69.18975,-69.18975,-69.18975]}, + {"t":0.24599, "x":1.00274, "y":5.68771, "heading":-1.5708, "vx":1.23181, "vy":-1.00084, "omega":0.0, "ax":5.00544, "ay":-4.06692, "alpha":0.0, "fx":[85.14115,85.14115,85.14115,85.14115], "fy":[-69.17719,-69.17719,-69.17719,-69.17719]}, + {"t":0.29519, "x":1.0694, "y":5.63355, "heading":-1.5708, "vx":1.47807, "vy":-1.20093, "omega":0.0, "ax":5.00423, "ay":-4.06594, "alpha":0.0, "fx":[85.12053,85.12053,85.12053,85.12053], "fy":[-69.16044,-69.16044,-69.16044,-69.16044]}, + {"t":0.34439, "x":1.14817, "y":5.56954, "heading":-1.5708, "vx":1.72427, "vy":-1.40097, "omega":0.0, "ax":5.00253, "ay":-4.06456, "alpha":0.0, "fx":[85.09167,85.09167,85.09167,85.09167], "fy":[-69.13699,-69.13699,-69.13699,-69.13699]}, + {"t":0.39359, "x":1.23906, "y":5.4957, "heading":-1.5708, "vx":1.97038, "vy":-1.60094, "omega":0.0, "ax":4.99999, "ay":-4.06249, "alpha":0.0, "fx":[85.04837,85.04837,85.04837,85.04837], "fy":[-69.10181,-69.10181,-69.10181,-69.10181]}, + {"t":0.44279, "x":1.34205, "y":5.41202, "heading":-1.5708, "vx":2.21638, "vy":-1.80081, "omega":0.0, "ax":4.99575, "ay":-4.05905, "alpha":0.0, "fx":[84.97623,84.97623,84.97623,84.97623], "fy":[-69.0432,-69.0432,-69.0432,-69.0432]}, + {"t":0.49198, "x":1.45714, "y":5.31851, "heading":-1.5708, "vx":2.46216, "vy":-2.0005, "omega":0.0, "ax":4.98728, "ay":-4.05216, "alpha":0.0, "fx":[84.83216,84.83216,84.83216,84.83216], "fy":[-68.92615,-68.92615,-68.92615,-68.92615]}, + {"t":0.54118, "x":1.58431, "y":5.21518, "heading":-1.5708, "vx":2.70752, "vy":-2.19986, "omega":0.0, "ax":4.96204, "ay":-4.03166, "alpha":0.0, "fx":[84.40283,84.40283,84.40283,84.40283], "fy":[-68.57731,-68.57731,-68.57731,-68.57731]}, + {"t":0.59038, "x":1.72352, "y":5.10208, "heading":-1.5708, "vx":2.95165, "vy":-2.39822, "omega":0.0, "ax":2.62317, "ay":-2.13132, "alpha":0.0, "fx":[44.61935,44.61935,44.61935,44.61935], "fy":[-36.25323,-36.25323,-36.25323,-36.25323]}, + {"t":0.63958, "x":1.87191, "y":4.98151, "heading":-1.5708, "vx":3.0807, "vy":-2.50307, "omega":0.0, "ax":-2.62317, "ay":2.13132, "alpha":0.0, "fx":[-44.61935,-44.61935,-44.61935,-44.61935], "fy":[36.25323,36.25323,36.25323,36.25323]}, + {"t":0.68878, "x":2.0203, "y":4.86094, "heading":-1.5708, "vx":2.95165, "vy":-2.39822, "omega":0.0, "ax":-4.96204, "ay":4.03166, "alpha":0.0, "fx":[-84.40283,-84.40283,-84.40283,-84.40283], "fy":[68.57731,68.57731,68.57731,68.57731]}, + {"t":0.73798, "x":2.15951, "y":4.74783, "heading":-1.5708, "vx":2.70752, "vy":-2.19986, "omega":0.0, "ax":-4.98728, "ay":4.05216, "alpha":0.0, "fx":[-84.83216,-84.83216,-84.83216,-84.83216], "fy":[68.92615,68.92615,68.92615,68.92615]}, + {"t":0.78717, "x":2.28668, "y":4.64451, "heading":-1.5708, "vx":2.46216, "vy":-2.0005, "omega":0.0, "ax":-4.99575, "ay":4.05905, "alpha":0.0, "fx":[-84.97623,-84.97623,-84.97623,-84.97623], "fy":[69.0432,69.0432,69.0432,69.0432]}, + {"t":0.83637, "x":2.40177, "y":4.551, "heading":-1.5708, "vx":2.21638, "vy":-1.80081, "omega":0.0, "ax":-4.99999, "ay":4.06249, "alpha":0.0, "fx":[-85.04837,-85.04837,-85.04837,-85.04837], "fy":[69.10181,69.10181,69.10181,69.10181]}, + {"t":0.88557, "x":2.50476, "y":4.46732, "heading":-1.5708, "vx":1.97038, "vy":-1.60094, "omega":0.0, "ax":-5.00253, "ay":4.06456, "alpha":0.0, "fx":[-85.09167,-85.09167,-85.09167,-85.09167], "fy":[69.13699,69.13699,69.13699,69.13699]}, + {"t":0.93477, "x":2.59564, "y":4.39347, "heading":-1.5708, "vx":1.72427, "vy":-1.40097, "omega":0.0, "ax":-5.00423, "ay":4.06594, "alpha":0.0, "fx":[-85.12053,-85.12053,-85.12053,-85.12053], "fy":[69.16044,69.16044,69.16044,69.16044]}, + {"t":0.98397, "x":2.67442, "y":4.32947, "heading":-1.5708, "vx":1.47807, "vy":-1.20093, "omega":0.0, "ax":-5.00544, "ay":4.06692, "alpha":0.0, "fx":[-85.14115,-85.14115,-85.14115,-85.14115], "fy":[69.17719,69.17719,69.17719,69.17719]}, + {"t":1.03317, "x":2.74108, "y":4.27531, "heading":-1.5708, "vx":1.23181, "vy":-1.00084, "omega":0.0, "ax":-5.00635, "ay":4.06766, "alpha":0.0, "fx":[-85.15661,-85.15661,-85.15661,-85.15661], "fy":[69.18975,69.18975,69.18975,69.18975]}, + {"t":1.08236, "x":2.79562, "y":4.23099, "heading":-1.5708, "vx":0.9855, "vy":-0.80072, "omega":0.0, "ax":-5.00706, "ay":4.06824, "alpha":0.0, "fx":[-85.16863,-85.16863,-85.16863,-85.16863], "fy":[69.19952,69.19952,69.19952,69.19952]}, + {"t":1.13156, "x":2.83805, "y":4.19652, "heading":-1.5708, "vx":0.73917, "vy":-0.60057, "omega":0.0, "ax":-5.00762, "ay":4.06869, "alpha":0.0, "fx":[-85.17824,-85.17824,-85.17824,-85.17824], "fy":[69.20734,69.20734,69.20734,69.20734]}, + {"t":1.18076, "x":2.86836, "y":4.17189, "heading":-1.5708, "vx":0.4928, "vy":-0.4004, "omega":0.0, "ax":-5.00809, "ay":4.06907, "alpha":0.0, "fx":[-85.18611,-85.18611,-85.18611,-85.18611], "fy":[69.21373,69.21373,69.21373,69.21373]}, + {"t":1.22996, "x":2.88654, "y":4.15712, "heading":-1.5708, "vx":0.24641, "vy":-0.20021, "omega":0.0, "ax":-5.00847, "ay":4.06938, "alpha":0.0, "fx":[-85.19267,-85.19267,-85.19267,-85.19267], "fy":[69.21905,69.21905,69.21905,69.21905]}, + {"t":1.27916, "x":2.8926, "y":4.1522, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} From 28c2d3d24098f6e432ce5dbda2ce8f306f9a7320 Mon Sep 17 00:00:00 2001 From: vaddadisri26 Date: Thu, 25 Sep 2025 18:54:09 -0400 Subject: [PATCH 113/180] Pre-bringup code cleanup; next step is to test transitions in sim. Co-authored-by: SeptimusHeap7 Co-authored-by: Anshu Co-authored-by: jasminepalit Co-authored-by: Abhiraam Venigalla --- .../frc/robot/commands/CompositeCommands.java | 3 +- .../subsystems/shared/climber/Climber.java | 12 +- .../shared/elevator/ElevatorConstants.java | 10 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 103 +++----- .../climber/V3_EpsilonClimberConstants.java | 6 +- .../intake/V3_EpsilonIntake.java | 88 ++++--- .../intake/V3_EpsilonIntakeConstants.java | 84 ++++--- .../intake/V3_EpsilonIntakeIOTalonFX.java | 99 ++++---- .../manipulator/V3_EpsilonManipulator.java | 228 +++++++++--------- .../V3_EpsilonManipulatorConstants.java | 130 ++++++---- .../V3_EpsilonManipulatorIOTalonFX.java | 53 ++-- 11 files changed, 410 insertions(+), 406 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index a1233975..300fcaa4 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -931,8 +931,7 @@ public static final Command climb( climber.releaseClimber(), Commands.waitSeconds( V3_EpsilonClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), - Commands.deadline( - climber.winchClimber(), Commands.run(drive::stop))); + Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); } } } diff --git a/src/main/java/frc/robot/subsystems/shared/climber/Climber.java b/src/main/java/frc/robot/subsystems/shared/climber/Climber.java index d887a895..b777915a 100644 --- a/src/main/java/frc/robot/subsystems/shared/climber/Climber.java +++ b/src/main/java/frc/robot/subsystems/shared/climber/Climber.java @@ -49,12 +49,12 @@ public Climber(ClimberIO io) { override = false; } -/** - * Periodic function for the climber subsystem. - * - * Updates the inputs for the climber, processes the inputs, logs the state of the climber, and - * records the total time taken by the periodic function. - */ + /** + * Periodic function for the climber subsystem. + * + *

Updates the inputs for the climber, processes the inputs, logs the state of the climber, and + * records the total time taken by the periodic function. + */ @Override public void periodic() { ExternalLoggedTracer.reset(); diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index 6cd059bc..e59ba17c 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -296,12 +296,12 @@ public static record PositionConstants(double V1, double V2, double V3) {} @RequiredArgsConstructor public static enum ElevatorPositions { STOW(new PositionConstants(0.0, 0.0, 0.0)), - CORAL_INTAKE(new PositionConstants(0.0, 0.0, Units.inchesToMeters(34.75))), + CORAL_INTAKE(new PositionConstants(0.0, 0.0, Units.inchesToMeters(34.85))), ALGAE_INTAKE( new PositionConstants( 0.2161583093038944 + Units.inchesToMeters(1), 0.2161583093038944 + Units.inchesToMeters(1), - 0.2161583093038944 + Units.inchesToMeters(1))), + 0)), ALGAE_MID( new PositionConstants( 0.7073684509805078, 0.7073684509805078, 1.2)), // USED AS PRE-HANDOFF FOR V3 @@ -330,7 +330,7 @@ public static enum ElevatorPositions { new PositionConstants( 1.3864590139769697 + Units.inchesToMeters(0.5), 1.3864590139769697 + Units.inchesToMeters(0.5), - Units.inchesToMeters(57))), + Units.inchesToMeters(55))), L4_PLUS( new PositionConstants( 0.0, @@ -340,10 +340,10 @@ public static enum ElevatorPositions { new PositionConstants( 1.3864590139769697 + Units.inchesToMeters(0.5), 1.3864590139769697 + Units.inchesToMeters(0.5), - Units.inchesToMeters(61))), + Units.inchesToMeters(56))), HIGH_STOW(new PositionConstants(0, 0, 0.5)), - HANDOFF(new PositionConstants(0, 0, 1)), + HANDOFF(new PositionConstants(0, 0, Units.inchesToMeters(34.75))), ; private final PositionConstants position; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index c166fa12..7ff87741 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -2,19 +2,14 @@ import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.apriltag.AprilTagFields; -import edu.wpi.first.math.geometry.Pose2d; -import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.Constants; import frc.robot.Constants.Mode; import frc.robot.RobotContainer; import frc.robot.RobotState; -import frc.robot.commands.CompositeCommands; import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; -import frc.robot.commands.CompositeCommands; import frc.robot.commands.DriveCommands; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.drive.DriveConstants; @@ -68,68 +63,63 @@ public V3_EpsilonRobotContainer() { if (Constants.getMode() != Mode.REPLAY) { switch (Constants.ROBOT) { case V3_EPSILON: - drive = new Drive( - new GyroIOPigeon2(), - new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), - new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), - new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), - new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); + drive = + new Drive( + new GyroIOPigeon2(), + new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), + new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), + new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), + new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); - vision = new Vision( - () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), - RobotCameras.V2_REDUNDANCY_CAMS); + vision = + new Vision( + () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), + RobotCameras.V2_REDUNDANCY_CAMS); break; case V3_EPSILON_SIM: - drive = new Drive( - new GyroIO() { - }, - new ModuleIOSim(DriveConstants.FRONT_LEFT), - new ModuleIOSim(DriveConstants.FRONT_RIGHT), - new ModuleIOSim(DriveConstants.BACK_LEFT), - new ModuleIOSim(DriveConstants.BACK_RIGHT)); + drive = + new Drive( + new GyroIO() {}, + new ModuleIOSim(DriveConstants.FRONT_LEFT), + new ModuleIOSim(DriveConstants.FRONT_RIGHT), + new ModuleIOSim(DriveConstants.BACK_LEFT), + new ModuleIOSim(DriveConstants.BACK_RIGHT)); elevator = new Elevator(new ElevatorIOSim()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOSim()); superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); - vision = new Vision(() -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded)); + vision = + new Vision(() -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded)); break; default: break; } if (drive == null) { - drive = new Drive( - new GyroIO() { - }, - new ModuleIO() { - }, - new ModuleIO() { - }, - new ModuleIO() { - }, - new ModuleIO() { - }); + drive = + new Drive( + new GyroIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}); } if (elevator == null) { - elevator = new Elevator(new ElevatorIO() { - }).getFSM(); + elevator = new Elevator(new ElevatorIO() {}).getFSM(); } if (intake == null) { - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() { - }); + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); } if (manipulator == null) { - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() { - }); + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); } if (climber == null) { - climber = new V3_EpsilonClimber(new V3_EpsilonClimberIO() { - }); + climber = new V3_EpsilonClimber(new V3_EpsilonClimberIO() {}); } if (superstructure == null) { superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); @@ -139,9 +129,8 @@ public V3_EpsilonRobotContainer() { } /** - * Configure the button bindings for the robot. This method is called in - * the constructor and is responsible for setting up the default commands - * for each button on the controllers. + * Configure the button bindings for the robot. This method is called in the constructor and is + * responsible for setting up the default commands for each button on the controllers. */ private void configureButtonBindings() { drive.setDefaultCommand( @@ -161,13 +150,11 @@ private void configureButtonBindings() { .whileFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF)); } - private void configureAutos() { - } + private void configureAutos() {} /** - * Periodic function for the robot. This function is called every 20ms, - * and is responsible for updating the robot's state and logging relevant - * data. + * Periodic function for the robot. This function is called every 20ms, and is responsible for + * updating the robot's state and logging relevant data. */ @Override public void robotPeriodic() { @@ -193,25 +180,13 @@ public void robotPeriodic() { } /** - * Returns the autonomous command for the robot. This command will be scheduled - * for the entire autonomous period. + * Returns the autonomous command for the robot. This command will be scheduled for the entire + * autonomous period. * * @return the autonomous command for the robot */ @Override public Command getAutonomousCommand() { - return Commands.runOnce( - () -> RobotState.resetRobotPose(new Pose2d(7.25, 2.39, new Rotation2d(Math.PI / 2)))) - .andThen(CompositeCommands.V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure)); - // return superstructure.allTransition(); - // return Commands.sequence( - // V3_EpsilonCompositeCommands.dropAlgae( - // drive, - // elevator, - // manipulator, - // intake, - // superstructure, - // () -> ReefState.ALGAE_INTAKE_TOP, - // RobotCameras.V3_EPSILON_CAMS)); + return superstructure.allTransition(); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java index 262caf0f..32793a70 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java @@ -15,8 +15,7 @@ public class V3_EpsilonClimberConstants { static { DEPLOYMENT_CAN_ID = 42; - ROLLER_CAN_ID = - 42; // This used to be 61, but there are two motors, so I replace this with 42 until + ROLLER_CAN_ID = 42; MOTOR_ID = 50; MOTOR_PARAMETERS = @@ -29,7 +28,8 @@ public static record MotorParameters( DCMotor MOTOR_CONFIG, double GEAR_RATIO, double GEARBOX_EFFICIENCY, double SPOOL_DIAMETER) {} public static final double CLIMBER_CLIMBED_ZERO_RADIANS = - 41; // TODO: None of these four lines are valid numbers i just made up stuff + 41; // TODO: None of these four lines are valid numbers i + // just made up stuff public static final double CLIMBER_CLIMBED_DEPLOYED_RADIANS = 67; public static final ClimberTimingConfig CLIMBER_TIMING_CONFIG = new ClimberTimingConfig(1.1, 0.25, 0.5); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index 3aacca32..7e0ed519 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -35,11 +35,10 @@ public V3_EpsilonIntake(V3_EpsilonIntakeIO io) { } /** - * Periodic function for intake subsystem. - * Updates inputs from the intake, and then sets the goals for the pivot and roller motors. - * If the intake is in closed-loop mode, it sets the pivot motor goal to the desired angle. - * Otherwise, it does not set the pivot motor goal. - * It always sets the inner and outer roller motor goals to the desired voltage. + * Periodic function for intake subsystem. Updates inputs from the intake, and then sets the goals + * for the pivot and roller motors. If the intake is in closed-loop mode, it sets the pivot motor + * goal to the desired angle. Otherwise, it does not set the pivot motor goal. It always sets the + * inner and outer roller motor goals to the desired voltage. */ public void periodic() { io.updateInputs(inputs); @@ -54,13 +53,12 @@ public void periodic() { } // Double check if this is right - + /** - * Checks if the intake is currently detecting coral. - * This is done by checking if both the left and right CAN range - * sensors are detecting a distance greater than the coral detection + * Checks if the intake is currently detecting coral. This is done by checking if both the left + * and right CAN range sensors are detecting a distance greater than the coral detection * threshold. - * + * * @return True if the intake is detecting coral, false otherwise. */ @AutoLogOutput(key = "Intake/Has Coral") @@ -71,12 +69,11 @@ public boolean hasCoral() { > V3_EpsilonIntakeConstants.INTAKE_CAN_CORAL_DETECTED_THRESHOLD_METERS; } - /** - * Checks if the pivot motor is at the goal angle. - * This is done by checking if the absolute difference between the current - * pivot motor angle and the goal angle is less than the goal tolerance. - * + * Checks if the pivot motor is at the goal angle. This is done by checking if the absolute + * difference between the current pivot motor angle and the goal angle is less than the goal + * tolerance. + * * @return True if the pivot motor is at the goal angle, false otherwise. */ @AutoLogOutput(key = "Intake/At Goal") @@ -85,54 +82,53 @@ public boolean pivotAtGoal() { < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); } - /** - * Checks if the pivot motor is at the goal angle. - * This is done by checking if the absolute difference between the current - * pivot motor angle and the goal angle is less than the goal tolerance. - * + * Checks if the pivot motor is at the goal angle. This is done by checking if the absolute + * difference between the current pivot motor angle and the goal angle is less than the goal + * tolerance. + * * @param goal The goal angle to check against. * @return True if the pivot motor is at the goal angle, false otherwise. */ public boolean pivotAtGoal(IntakePivotState goal) { - return Math.abs(inputs.pivotPosition.getRadians() - goal.getAngle().getRadians()) + return Math.abs(inputs.pivotPosition.getRadians() - goal.getAngle().getRadians()) < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); } -/** - * Sets the goal state of the pivot motor. - * If the intake is currently in open-loop mode, this method will set the isClosedLoop flag to true. - * It then sets the pivotGoal field to the specified goal state. - * The pivot motor will then be controlled in closed-loop mode to reach the specified goal state. - * - * @param goal The desired IntakePivotState for the pivot motor. - */ + /** + * Sets the goal state of the pivot motor. If the intake is currently in open-loop mode, this + * method will set the isClosedLoop flag to true. It then sets the pivotGoal field to the + * specified goal state. The pivot motor will then be controlled in closed-loop mode to reach the + * specified goal state. + * + * @param goal The desired IntakePivotState for the pivot motor. + */ public void setPivotGoal(IntakePivotState goal) { isClosedLoop = true; this.pivotGoal = goal; } - -/** - * Sets the voltage for the intake pivot motor. - * - * This method is used to set the voltage for the intake pivot motor in open-loop mode. - * It sets the isClosedLoop flag to false, and then calls the setPivotVoltage method of the IO interface. - * - * @param volts The voltage to set for the intake pivot motor. - */ + /** + * Sets the voltage for the intake pivot motor. + * + *

This method is used to set the voltage for the intake pivot motor in open-loop mode. It sets + * the isClosedLoop flag to false, and then calls the setPivotVoltage method of the IO interface. + * + * @param volts The voltage to set for the intake pivot motor. + */ public void setPivotVoltage(double volts) { isClosedLoop = false; io.setPivotVoltage(volts); } -/** - * Waits until the pivot motor is at the goal angle. - * This command is created by sequencing a wait command with a waitUntil command. - * The wait command waits for 0.02 seconds, and the waitUntil command checks if the pivot motor is at the goal angle. - * The command will block until the pivot motor is at the goal angle. - * @return A Command that waits until the pivot motor is at the goal angle. - */ + /** + * Waits until the pivot motor is at the goal angle. This command is created by sequencing a wait + * command with a waitUntil command. The wait command waits for 0.02 seconds, and the waitUntil + * command checks if the pivot motor is at the goal angle. The command will block until the pivot + * motor is at the goal angle. + * + * @return A Command that waits until the pivot motor is at the goal angle. + */ public Command waitUntilPivotAtGoal() { return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::pivotAtGoal)); } @@ -156,7 +152,7 @@ public void setRollerGoal(IntakeRollerState rollerGoal) { /** * Gets the current angle of the intake pivot motor. - * + * * @return The current angle of the intake pivot motor, in radians. */ public Rotation2d getPivotAngle() { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index f8453c4a..e981250e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -2,64 +2,72 @@ import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.system.plant.DCMotor; +import frc.robot.Constants; import lombok.Getter; import lombok.RequiredArgsConstructor; public class V3_EpsilonIntakeConstants { - public static final int PIVOT_CAN_ID; - public static final int ROLLER_CAN_ID_INNER; + public static final int PIVOT_CAN_ID; public static final int ROLLER_CAN_ID_OUTER; - + public static final int ROLLER_CAN_ID_INNER; public static final int LEFT_SENSOR_CAN_ID; - public static final int RIGHT_SENSOR_CAN_ID; public static final double INTAKE_CAN_CORAL_DETECTED_THRESHOLD_METERS; - public static final IntakeCurrentLimits CURRENT_LIMITS = - new IntakeCurrentLimits(40.0, 40.0, 40.0, 40.0); + public static final IntakeCurrentLimits CURRENT_LIMITS; - public static final Gains PIVOT_GAINS = new Gains(1.0, 0.01, 0.0, 0.0, 0.0, 0.0); - public static final Constraints PIVOT_CONSTRAINTS = - new Constraints(500.0, 500.0, Rotation2d.fromDegrees(1.5)); + public static final Gains PIVOT_GAINS; + public static final Constraints PIVOT_CONSTRAINTS; - public static final IntakeParems PIVOT_PARAMS = - new IntakeParems( - 3.0, - DCMotor.getKrakenX60Foc(1), - 0.0042, - Rotation2d.fromDegrees(0.0), - Rotation2d.fromDegrees(124.6)); - public static final IntakeParems ROLLER_PARAMS = - new IntakeParems( - 1, DCMotor.getKrakenX60Foc(1), 0, new Rotation2d(), Rotation2d.fromDegrees(0)); + public static final IntakeParems PIVOT_PARAMS; + public static final IntakeParems ROLLER_PARAMS; static { PIVOT_CAN_ID = 60; - ROLLER_CAN_ID_OUTER = - 61; // This used to be 61, but there are two motors, so I replace this with 42 until it gets - // sorted out fs - ROLLER_CAN_ID_INNER = 62; // This one I just created. - } - - static { + ROLLER_CAN_ID_OUTER = 61; // TODO: Check numbers here + ROLLER_CAN_ID_INNER = 62; // TODO: Check numbers here LEFT_SENSOR_CAN_ID = 0; // TODO: Check numbers here RIGHT_SENSOR_CAN_ID = 1; - } - static { - INTAKE_CAN_CORAL_DETECTED_THRESHOLD_METERS = - 42; // In meters= 42; TODO: Set value after robot built + INTAKE_CAN_CORAL_DETECTED_THRESHOLD_METERS = 0.05; // TODO: Check this value + + PIVOT_PARAMS = + new IntakeParems( + 3.0, + DCMotor.getKrakenX60Foc(1), + 0.0042, + Rotation2d.fromDegrees(0.0), + Rotation2d.fromDegrees(124.6)); + ROLLER_PARAMS = + new IntakeParems( + 1, DCMotor.getKrakenX60Foc(1), 0, new Rotation2d(), Rotation2d.fromDegrees(0)); + + switch (Constants.ROBOT) { + case V3_EPSILON_SIM: + PIVOT_CONSTRAINTS = new Constraints(500.0, 500.0, Rotation2d.fromDegrees(1.5)); + PIVOT_GAINS = new Gains(0.0, 0.00, 0.0, 0.0, 0.0, 0.0); + CURRENT_LIMITS = new IntakeCurrentLimits(40.0, 40.0, 40.0, 40.0, 40.0, 40.0); + + break; + + default: + PIVOT_CONSTRAINTS = new Constraints(500.0, 500.0, Rotation2d.fromDegrees(1.5)); + PIVOT_GAINS = new Gains(0.0, 0.0, 0.0, 0.0, 0.0, 0.0); + CURRENT_LIMITS = new IntakeCurrentLimits(40.0, 40.0, 40.0, 40.0, 40.0, 40.0); + + break; + } } @RequiredArgsConstructor public enum IntakePivotState { - STOW(Rotation2d.fromDegrees(25.0)), - INTAKE_CORAL(Rotation2d.fromDegrees(123.6)), - HANDOFF(Rotation2d.fromDegrees(0)), - L1(Rotation2d.fromDegrees(-82 + 123.6)), - INTAKE_ALGAE(new Rotation2d()), + STOW(Rotation2d.fromDegrees(-123.6)), + INTAKE_CORAL(Rotation2d.fromDegrees(0)), + HANDOFF(Rotation2d.fromDegrees(-123.6)), + L1(Rotation2d.fromDegrees(-82)), + INTAKE_ALGAE(new Rotation2d(0)), ARM_CLEAR(Rotation2d.fromDegrees(35)); @Getter private final Rotation2d angle; @@ -68,8 +76,10 @@ public enum IntakePivotState { public static record IntakeCurrentLimits( double PIVOT_SUPPLY_CURRENT_LIMIT, double PIVOT_STATOR_CURRENT_LIMIT, - double ROLLER_SUPPLY_CURRENT_LIMIT, - double ROLLER_STATOR_CURRENT_LIMIT) {} + double INNER_ROLLER_SUPPLY_CURRENT_LIMIT, + double INNER_ROLLER_STATOR_CURRENT_LIMIT, + double OUTER_ROLLER_SUPPLY_CURRENT_LIMIT, + double OUTER_ROLLER_STATOR_CURRENT_LIMIT) {} public static record Gains(double kP, double kD, double kS, double kV, double kA, double kG) {} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java index 290ae511..45f1a293 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java @@ -137,10 +137,10 @@ public V3_EpsilonIntakeIOTalonFX() { rollerInnerConfig = new TalonFXConfiguration(); rollerInnerConfig.CurrentLimits.SupplyCurrentLimitEnable = true; rollerInnerConfig.CurrentLimits.SupplyCurrentLimit = - V3_EpsilonIntakeConstants.CURRENT_LIMITS.ROLLER_SUPPLY_CURRENT_LIMIT(); + V3_EpsilonIntakeConstants.CURRENT_LIMITS.INNER_ROLLER_SUPPLY_CURRENT_LIMIT(); rollerInnerConfig.CurrentLimits.StatorCurrentLimitEnable = true; rollerInnerConfig.CurrentLimits.StatorCurrentLimit = - V3_EpsilonIntakeConstants.CURRENT_LIMITS.ROLLER_STATOR_CURRENT_LIMIT(); + V3_EpsilonIntakeConstants.CURRENT_LIMITS.INNER_ROLLER_STATOR_CURRENT_LIMIT(); rollerInnerConfig.Feedback.SensorToMechanismRatio = V3_EpsilonIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO(); rollerInnerConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; @@ -149,10 +149,10 @@ public V3_EpsilonIntakeIOTalonFX() { rollerOuterConfig = new TalonFXConfiguration(); rollerOuterConfig.CurrentLimits.SupplyCurrentLimitEnable = true; rollerOuterConfig.CurrentLimits.SupplyCurrentLimit = - V3_EpsilonIntakeConstants.CURRENT_LIMITS.ROLLER_SUPPLY_CURRENT_LIMIT(); + V3_EpsilonIntakeConstants.CURRENT_LIMITS.OUTER_ROLLER_SUPPLY_CURRENT_LIMIT(); rollerOuterConfig.CurrentLimits.StatorCurrentLimitEnable = true; rollerOuterConfig.CurrentLimits.StatorCurrentLimit = - V3_EpsilonIntakeConstants.CURRENT_LIMITS.ROLLER_STATOR_CURRENT_LIMIT(); + V3_EpsilonIntakeConstants.CURRENT_LIMITS.OUTER_ROLLER_STATOR_CURRENT_LIMIT(); rollerOuterConfig.Feedback.SensorToMechanismRatio = V3_EpsilonIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO(); rollerOuterConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; @@ -206,15 +206,14 @@ public V3_EpsilonIntakeIOTalonFX() { rightCANrangeStatusSignal); } - -/** - * Updates the inputs of the subsystem. - * - * This function is called by the robot periodic loop and should update all of the inputs - * of the subsystem. The inputs should be updated from the CAN bus and other sensors. - * - * @param inputs The inputs of the subsystem. - */ + /** + * Updates the inputs of the subsystem. + * + *

This function is called by the robot periodic loop and should update all of the inputs of + * the subsystem. The inputs should be updated from the CAN bus and other sensors. + * + * @param inputs The inputs of the subsystem. + */ @Override public void updateInputs(V3_EpsilonIntakeIOInputs inputs) { inputs.pivotPosition = new Rotation2d(pivotPositionRotations.getValue()); @@ -251,57 +250,53 @@ public void updateInputs(V3_EpsilonIntakeIOInputs inputs) { inputs.rightCANRangeDistanceMeters = rightCANrangeStatusSignal.getValueAsDouble(); } - -/** - * Sets the voltage for the intake pivot motor. - * - * This method is used to set the voltage for the intake pivot motor in open-loop mode. - * It sets the isClosedLoop flag to false, and then calls the setPivotVoltage method of the IO interface. - * - * @param volts The voltage to set for the intake pivot motor. - */ + /** + * Sets the voltage for the intake pivot motor. + * + *

This method is used to set the voltage for the intake pivot motor in open-loop mode. It sets + * the isClosedLoop flag to false, and then calls the setPivotVoltage method of the IO interface. + * + * @param volts The voltage to set for the intake pivot motor. + */ public void setPivotVoltage(double volts) { pivotTalonFX.setControl(pivotVoltageRequest.withOutput(volts).withEnableFOC(true)); } - -/** - * Sets the voltage for the inner manipulator roller. - * - * This method is used to set the voltage for the inner manipulator roller in open-loop mode. - * It sets the isClosedLoop flag to false, and then calls the setControl method of the TalonFX - * object with the voltage request. - * - * @param volts The voltage to set for the inner manipulator roller. - */ - + /** + * Sets the voltage for the inner manipulator roller. + * + *

This method is used to set the voltage for the inner manipulator roller in open-loop mode. + * It sets the isClosedLoop flag to false, and then calls the setControl method of the TalonFX + * object with the voltage request. + * + * @param volts The voltage to set for the inner manipulator roller. + */ public void setInnerRollerVoltage(double volts) { rollerTalonFXInner.setControl(rollerInnerVoltageRequest.withOutput(volts).withEnableFOC(true)); } -/** - * Sets the voltage for the outer manipulator roller. - * - * This method is used to set the voltage for the outer manipulator roller in open-loop mode. - * It sets the isClosedLoop flag to false, and then calls the setControl method of the TalonFX - * object with the voltage request. - * - * @param volts The voltage to set for the outer manipulator roller. - */ + /** + * Sets the voltage for the outer manipulator roller. + * + *

This method is used to set the voltage for the outer manipulator roller in open-loop mode. + * It sets the isClosedLoop flag to false, and then calls the setControl method of the TalonFX + * object with the voltage request. + * + * @param volts The voltage to set for the outer manipulator roller. + */ public void setOuterRollerVoltage(double volts) { rollerTalonFXOuter.setControl(rollerOuterVoltageRequest.withOutput(volts).withEnableFOC(true)); } - -/** - * Sets the position of the intake pivot motor using Motion Magic. - * - * This method is used to set the position of the intake pivot motor using Motion Magic. - * It sets the isClosedLoop flag to true, and then calls the setControl method of the - * TalonFX object with the position request. - * - * @param position The desired position of the intake pivot motor. - */ + /** + * Sets the position of the intake pivot motor using Motion Magic. + * + *

This method is used to set the position of the intake pivot motor using Motion Magic. It + * sets the isClosedLoop flag to true, and then calls the setControl method of the TalonFX object + * with the position request. + * + * @param position The desired position of the intake pivot motor. + */ public void setPivotMotionMagic(Rotation2d position) { pivotTalonFX.setControl( pivotMotionMagicRequest.withPosition(position.getMeasure()).withEnableFOC(true)); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 8ff701e1..2209697e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -73,41 +73,42 @@ public void periodic() { } } -/** - * Checks if the manipulator is currently detecting coral. - * This is done by checking if the CAN range sensor is detecting a distance - * less than the coral detection threshold and greater than 0. - * - * @return True if the manipulator is detecting coral, false otherwise. - */ + /** + * Checks if the manipulator is currently detecting coral. This is done by checking if the CAN + * range sensor is detecting a distance less than the coral detection threshold and greater than + * 0. + * + * @return True if the manipulator is detecting coral, false otherwise. + */ @AutoLogOutput(key = "Manipulator/Has Coral") public boolean hasCoral() { - return inputs.canRangeDistanceMeters < V3_EpsilonManipulatorConstants.CORAL_CAN_RANGE_THRESHOLD + return inputs.canRangeDistanceMeters + < V3_EpsilonManipulatorConstants.CORAL_CAN_RANGE_THRESHOLD_METERS && inputs.canRangeDistanceMeters > 0; } -/** - * Checks if the manipulator is currently detecting algae. - * This is done by checking if the CAN range sensor is detecting a distance - * less than the algae detection threshold and greater than 0. - * - * @return True if the manipulator is detecting algae, false otherwise. - */ + /** + * Checks if the manipulator is currently detecting algae. This is done by checking if the CAN + * range sensor is detecting a distance less than the algae detection threshold and greater than + * 0. + * + * @return True if the manipulator is detecting algae, false otherwise. + */ @AutoLogOutput(key = "Manipulator/Has Algae") public boolean hasAlgae() { - return inputs.canRangeDistanceMeters < V3_EpsilonManipulatorConstants.ALGAE_CAN_RANGE_THRESHOLD + return inputs.canRangeDistanceMeters + < V3_EpsilonManipulatorConstants.ALGAE_CAN_RANGE_THRESHOLD_METERS && inputs.canRangeDistanceMeters > 0; } -/** - * Creates a command to run the manipulator arm at a specified voltage. - * - * @param volts The voltage to set the arm to. - * @return A command to run the arm. - */ - + /** + * Creates a command to run the manipulator arm at a specified voltage. + * + * @param volts The voltage to set the arm to. + * @return A command to run the arm. + */ public Command runArm(double volts) { - return Commands.runEnd( + return Commands.runEnd( () -> { isClosedLoop = false; io.setArmVoltage(volts); @@ -115,43 +116,39 @@ public Command runArm(double volts) { () -> io.setArmVoltage(0)); } - -/** - * Sets the goal for the manipulator arm to reach. - * - * @param goal The goal state to set the arm to. - */ - + /** + * Sets the goal for the manipulator arm to reach. + * + * @param goal The goal state to set the arm to. + */ public void setArmGoal(ManipulatorArmState goal) { isClosedLoop = true; armGoal = goal; } - -/** - * Updates the gains for the manipulator arm. - * This function sets the PID gains for the three slots of the arm. - * The gains are used to control the arm's movement. - * - * @param kP0 The proportional gain for slot 0. - * @param kD0 The derivative gain for slot 0. - * @param kS0 The static gain for slot 0. - * @param kV0 The velocity gain for slot 0. - * @param kA0 The acceleration gain for slot 0. - * @param kG0 The gravity gain for slot 0. - * @param kP1 The proportional gain for slot 1. - * @param kD1 The derivative gain for slot 1. - * @param kS1 The static gain for slot 1. - * @param kV1 The velocity gain for slot 1. - * @param kA1 The acceleration gain for slot 1. - * @param kG1 The gravity gain for slot 1. - * @param kP2 The proportional gain for slot 2. - * @param kD2 The derivative gain for slot 2. - * @param kS2 The static gain for slot 2. - * @param kV2 The velocity gain for slot 2. - * @param kA2 The acceleration gain for slot 2. - * @param kG2 The gravity gain for slot 2. - */ + /** + * Updates the gains for the manipulator arm. This function sets the PID gains for the three slots + * of the arm. The gains are used to control the arm's movement. + * + * @param kP0 The proportional gain for slot 0. + * @param kD0 The derivative gain for slot 0. + * @param kS0 The static gain for slot 0. + * @param kV0 The velocity gain for slot 0. + * @param kA0 The acceleration gain for slot 0. + * @param kG0 The gravity gain for slot 0. + * @param kP1 The proportional gain for slot 1. + * @param kD1 The derivative gain for slot 1. + * @param kS1 The static gain for slot 1. + * @param kV1 The velocity gain for slot 1. + * @param kA1 The acceleration gain for slot 1. + * @param kG1 The gravity gain for slot 1. + * @param kP2 The proportional gain for slot 2. + * @param kD2 The derivative gain for slot 2. + * @param kS2 The static gain for slot 2. + * @param kV2 The velocity gain for slot 2. + * @param kA2 The acceleration gain for slot 2. + * @param kG2 The gravity gain for slot 2. + */ public void updateArmGains( double kP0, double kD0, @@ -176,68 +173,63 @@ public void updateArmGains( io.updateSlot2ArmGains(kP2, kD2, kS2, kV2, kA2, kG2); } -/** - * Updates the constraints for the arm. - * - * @param maxAcceleration The maximum acceleration. - * @param maxVelocity The maximum velocity. - */ + /** + * Updates the constraints for the arm. + * + * @param maxAcceleration The maximum acceleration. + * @param maxVelocity The maximum velocity. + */ public void updateArmConstraints(double maxAcceleration, double maxVelocity) { io.updateArmConstraints(maxAcceleration, maxVelocity); } -/** - * Checks if the arm is at the goal position. - * - * This function checks if the arm is within the goal tolerance of the - * currently set arm goal position. If the arm is within the tolerance, it - * returns true. Otherwise, it returns false. - * - * @return If the arm is at the goal position. - */ - + /** + * Checks if the arm is at the goal position. + * + *

This function checks if the arm is within the goal tolerance of the currently set arm goal + * position. If the arm is within the tolerance, it returns true. Otherwise, it returns false. + * + * @return If the arm is at the goal position. + */ @AutoLogOutput(key = "Manipulator/Arm At Goal") public boolean armAtGoal() { return armAtGoal(armGoal); } -/** - * Checks if the arm is at the given goal position. - * - * This function checks if the arm is within the goal tolerance of the - * given arm goal position. If the arm is within the tolerance, it - * returns true. Otherwise, it returns false. - * - * @param state The arm goal position to check against. - * @return If the arm is at the goal position. - */ + /** + * Checks if the arm is at the given goal position. + * + *

This function checks if the arm is within the goal tolerance of the given arm goal position. + * If the arm is within the tolerance, it returns true. Otherwise, it returns false. + * + * @param state The arm goal position to check against. + * @return If the arm is at the goal position. + */ public boolean armAtGoal(ManipulatorArmState state) { return Math.abs(inputs.armPosition.minus(state.getAngle(armSide)).getRadians()) <= V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); } -/** - * Waits until the arm is at the goal position. - * - * This command waits for 0.02 seconds and then checks if the arm is at the goal position. - * If the arm is not at the goal position, it waits for 0.02 seconds and checks again. - * This process repeats until the arm is at the goal position. - * - * @return A command that waits until the arm is at the goal position. - */ + /** + * Waits until the arm is at the goal position. + * + *

This command waits for 0.02 seconds and then checks if the arm is at the goal position. If + * the arm is not at the goal position, it waits for 0.02 seconds and checks again. This process + * repeats until the arm is at the goal position. + * + * @return A command that waits until the arm is at the goal position. + */ public Command waitUntilArmAtGoal() { return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::armAtGoal)); } -/** - * Returns a voltage to hold the roller at the current position. - * The voltage is calculated based on the current torque current of the roller. - * The calculation is done using a piecewise polynomial function. - * The function first checks if the current torque current is less than or equal to 20. - * If it is, it uses one set of coefficients to calculate the voltage. - * Otherwise, it uses another set of coefficients. - */ - + /** + * Returns a voltage to hold the roller at the current position. The voltage is calculated based + * on the current torque current of the roller. The calculation is done using a piecewise + * polynomial function. The function first checks if the current torque current is less than or + * equal to 20. If it is, it uses one set of coefficients to calculate the voltage. Otherwise, it + * uses another set of coefficients. + */ private double holdVoltage() { double y; double x = Math.abs(inputs.rollerTorqueCurrentAmps); @@ -252,11 +244,11 @@ private double holdVoltage() { V3_EpsilonManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().getAsDouble() / 1.5); } -/** - * Sets the current slot of the manipulator arm based on the current state of the subsystem. - * If the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to 1. - * Otherwise, it sets the slot to 0. - */ + /** + * Sets the current slot of the manipulator arm based on the current state of the subsystem. If + * the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to + * 1. Otherwise, it sets the slot to 0. + */ public void setSlot() { if (hasAlgae()) { io.setSlot(2); @@ -267,7 +259,6 @@ public void setSlot() { } } - /** * Sets the manipulator arm to the specified state. * @@ -278,10 +269,9 @@ public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmSta } /** - * Sets the roller goal state of the manipulator. - * If the subsystem has algae or coral and the goal is one of the intake states, - * it sets the roller voltage to the hold voltage. Otherwise, it sets the roller voltage - * to the goal voltage. + * Sets the roller goal state of the manipulator. If the subsystem has algae or coral and the goal + * is one of the intake states, it sets the roller voltage to the hold voltage. Otherwise, it sets + * the roller voltage to the goal voltage. * * @param rollerGoal The desired state of the roller. */ @@ -302,21 +292,21 @@ public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState /** * Gets the current angle of the manipulator arm. - * + * * @return The current angle of the manipulator arm, in radians. */ public Rotation2d getArmAngle() { return inputs.armPosition; } -/** - * Checks if the manipulator arm is currently in a safe position. - * A safe position is when the arm is pointing away from the robot's body. - * The safe position threshold is determined by the angle between the arm and the robot's body. - * If the angle is greater than the threshold, it is considered safe. - * - * @return true if the arm is in a safe position, false otherwise. - */ + /** + * Checks if the manipulator arm is currently in a safe position. A safe position is when the arm + * is pointing away from the robot's body. The safe position threshold is determined by the angle + * between the arm and the robot's body. If the angle is greater than the threshold, it is + * considered safe. + * + * @return true if the arm is in a safe position, false otherwise. + */ @AutoLogOutput(key = "Manipulator/Safe Position") public boolean isSafePosition() { double cosThresh = diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 86c39c48..dd5d6cf5 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -5,11 +5,13 @@ import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.util.Units; +import frc.robot.Constants; import frc.robot.util.LoggedTunableNumber; import lombok.RequiredArgsConstructor; public class V3_EpsilonManipulatorConstants { public static final ArmParameters ARM_PARAMETERS; + public static final Gains EMPTY_GAINS; public static final Gains CORAL_GAINS; public static final Gains ALGAE_GAINS; @@ -22,47 +24,22 @@ public class V3_EpsilonManipulatorConstants { public static final ManipulatorCurrentLimits CURRENT_LIMITS; - public static final int ARM_CAN_ID = 42; - public static final Rotation2d TOGGLE_ARM_ROTATION; - - public static final int CAN_RANGE_ID = 41; + public static final double ALGAE_CAN_RANGE_THRESHOLD_METERS; + public static final double CORAL_CAN_RANGE_THRESHOLD_METERS; + public static final int ARM_CAN_ID; - public static final double ALGAE_CAN_RANGE_THRESHOLD = 0.5; - public static final double CORAL_CAN_RANGE_THRESHOLD = 0.5; + public static final int CAN_RANGE_ID; static { + ARM_CAN_ID = 42; + CAN_RANGE_ID = 41; + ROLLER_CAN_ID = 30; + ARM_PARAMETERS = new ArmParameters(DCMotor.getKrakenX60Foc(1), 1, 90.0, .695); - EMPTY_GAINS = - new Gains( - new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 50), - new LoggedTunableNumber("Manipulator/Arm/Empty/kD", 0), - new LoggedTunableNumber("Manipulator/Arm/Empty/kS", 0.24274), - new LoggedTunableNumber("Manipulator/Arm/Empty/kG", 0.66177), - new LoggedTunableNumber("Manipulator/Arm/Empty/kV", 0), - new LoggedTunableNumber("Manipulator/Arm/Empty/kA", 0)); - CORAL_GAINS = - new Gains( - new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kP", 125), - new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kD", 0), - new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kS", 0.24274), - new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kG", 0.66177), - new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kV", 0.0), - new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kA", 0.0)); - ALGAE_GAINS = - new Gains( - new LoggedTunableNumber("Manipulator/ArmWithAlgae/kP", 125), - new LoggedTunableNumber("Manipulator/ArmWithAlgae/kD", 0), - new LoggedTunableNumber("Manipulator/ArmWithAlgae/kS", 0.65347), - new LoggedTunableNumber("Manipulator/ArmWithAlgae/kG", 2.0762), - new LoggedTunableNumber("Manipulator/ArmWithAlgae/kV", 0.0), - new LoggedTunableNumber("Manipulator/ArmWithAlgae/kA", 0.0)); - CONSTRAINTS = - new Constraints( - new LoggedTunableNumber("Manipulator/Arm/MaxAcceleration", 20.0), - new LoggedTunableNumber("Manipulator/Arm/CruisingVelocity", 50.0), - new LoggedTunableNumber("Manipulator/Arm/GoalTolerance", Units.degreesToRadians(3))); - ROLLER_CAN_ID = 30; + ALGAE_CAN_RANGE_THRESHOLD_METERS = 0.5; + CORAL_CAN_RANGE_THRESHOLD_METERS = 0.5; + ROLLER_CURRENT_THRESHOLD = 60.0; ROLLER_TOGGLE_ARM_ROTATION = Rotation2d.fromRadians(10); ROLLER_VOLTAGES = @@ -76,9 +53,74 @@ public class V3_EpsilonManipulatorConstants { new LoggedTunableNumber("Manipulator/HalfScore Volts", 1.0 * 1.56), new LoggedTunableNumber("Manipulator/L1 Volts", 3.5 * 1.56)); - CURRENT_LIMITS = new ManipulatorCurrentLimits(40, 40, 40, 40); - - TOGGLE_ARM_ROTATION = new Rotation2d(); + switch (Constants.ROBOT) { + case V3_EPSILON_SIM: + EMPTY_GAINS = + new Gains( + new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 50), + new LoggedTunableNumber("Manipulator/Arm/Empty/kD", 0), + new LoggedTunableNumber("Manipulator/Arm/Empty/kS", 0.24274), + new LoggedTunableNumber("Manipulator/Arm/Empty/kG", 0.66177), + new LoggedTunableNumber("Manipulator/Arm/Empty/kV", 0), + new LoggedTunableNumber("Manipulator/Arm/Empty/kA", 0)); + CORAL_GAINS = + new Gains( + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kP", 125), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kD", 0), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kS", 0.24274), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kG", 0.66177), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kV", 0.0), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kA", 0.0)); + ALGAE_GAINS = + new Gains( + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kP", 125), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kD", 0), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kS", 0.65347), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kG", 2.0762), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kV", 0.0), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kA", 0.0)); + CONSTRAINTS = + new Constraints( + new LoggedTunableNumber("Manipulator/Arm/MaxAcceleration", 20.0), + new LoggedTunableNumber("Manipulator/Arm/CruisingVelocity", 50.0), + new LoggedTunableNumber( + "Manipulator/Arm/GoalTolerance", Units.degreesToRadians(3))); + CURRENT_LIMITS = new ManipulatorCurrentLimits(40, 40, 40, 40); + break; + default: + EMPTY_GAINS = + new Gains( + new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 50), + new LoggedTunableNumber("Manipulator/Arm/Empty/kD", 0), + new LoggedTunableNumber("Manipulator/Arm/Empty/kS", 0.24274), + new LoggedTunableNumber("Manipulator/Arm/Empty/kG", 0.66177), + new LoggedTunableNumber("Manipulator/Arm/Empty/kV", 0), + new LoggedTunableNumber("Manipulator/Arm/Empty/kA", 0)); + CORAL_GAINS = + new Gains( + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kP", 125), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kD", 0), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kS", 0.24274), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kG", 0.66177), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kV", 0.0), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kA", 0.0)); + ALGAE_GAINS = + new Gains( + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kP", 125), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kD", 0), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kS", 0.65347), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kG", 2.0762), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kV", 0.0), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kA", 0.0)); + CONSTRAINTS = + new Constraints( + new LoggedTunableNumber("Manipulator/Arm/MaxAcceleration", 20.0), + new LoggedTunableNumber("Manipulator/Arm/CruisingVelocity", 50.0), + new LoggedTunableNumber( + "Manipulator/Arm/GoalTolerance", Units.degreesToRadians(3))); + CURRENT_LIMITS = new ManipulatorCurrentLimits(40, 40, 40, 40); + break; + } } public static record Gains( @@ -128,7 +170,7 @@ public static record ArmParameters( public static enum ManipulatorArmState { PRE_SCORE(Rotation2d.fromDegrees(50.0)), SCORE(Rotation2d.fromDegrees(55.0)), // Placeholder value. Make sure to test - BARGE_SCORE(Rotation2d.fromDegrees(18.67)), + BARGE_SCORE(Rotation2d.fromDegrees(-10)), PROCESSOR(Rotation2d.fromDegrees(41.279296875)), REEF_INTAKE(Rotation2d.fromDegrees(46.279296875)), INTAKE_OUT_LINE(Rotation2d.fromDegrees(61)), @@ -164,9 +206,11 @@ public static enum ManipulatorRollerState { private final double voltage; - /*ManipulatorRollerState(double voltage) { - this.voltage = voltage; - }*/ + /* + * ManipulatorRollerState(double voltage) { + * this.voltage = voltage; + * } + */ public double getVoltage() { return voltage; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java index 07f36308..71746f51 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java @@ -138,11 +138,11 @@ public V3_EpsilonManipulatorIOTalonFX() { rollerTalonFX.optimizeBusUtilization(); } -/** - * Updates the inputs of the manipulator with the current state of the TalonFXs. - * - * @param inputs the inputs to update - */ + /** + * Updates the inputs of the manipulator with the current state of the TalonFXs. + * + * @param inputs the inputs to update + */ @Override public void updateInputs(ManipulatorIOInputs inputs) { @@ -169,15 +169,12 @@ public void updateInputs(ManipulatorIOInputs inputs) { Rotation2d.fromRotations(armPositionErrorRotations.getValueAsDouble()); } - - /** - * Sets the voltage of the arm TalonFX to the specified value. - * The voltage is set in terms of volts, with positive values corresponding to - * clockwise rotation and negative values corresponding to counterclockwise - * rotation. - * This method is used to control the velocity of the arm, which is useful - * for tasks such as picking up objects or depositing objects. + * Sets the voltage of the arm TalonFX to the specified value. The voltage is set in terms of + * volts, with positive values corresponding to clockwise rotation and negative values + * corresponding to counterclockwise rotation. This method is used to control the velocity of the + * arm, which is useful for tasks such as picking up objects or depositing objects. + * * @param volts the voltage to set, in volts */ @Override @@ -185,37 +182,35 @@ public void setArmVoltage(double volts) { armTalonFX.setControl(armVoltageRequest.withOutput(volts).withEnableFOC(true)); } - - -/** - * Sets the voltage of the roller TalonFX to the specified value. - * The voltage is set in terms of volts, with positive values corresponding to clockwise rotation and negative values corresponding to counterclockwise rotation. - * This method is used to control the velocity of the roller, which is useful for tasks such as picking up objects or depositing objects. - */ + /** + * Sets the voltage of the roller TalonFX to the specified value. The voltage is set in terms of + * volts, with positive values corresponding to clockwise rotation and negative values + * corresponding to counterclockwise rotation. This method is used to control the velocity of the + * roller, which is useful for tasks such as picking up objects or depositing objects. + */ @Override public void setRollerVoltage(double volts) { rollerTalonFX.setControl(rollerVoltageRequest.withOutput(volts).withEnableFOC(true)); } - /** - * The position is set in terms of rotations of the TalonFX's motor shaft. - * This method is used to set the manipulator arm to a specific position, which is useful for tasks such as picking up objects or depositing objects. + * The position is set in terms of rotations of the TalonFX's motor shaft. This method is used to + * set the manipulator arm to a specific position, which is useful for tasks such as picking up + * objects or depositing objects. * - * @param rotation The desired position of the manipulator arm, in terms of rotations of the TalonFX's motor shaft. + * @param rotation The desired position of the manipulator arm, in terms of rotations of the + * TalonFX's motor shaft. */ - @Override public void setArmGoal(Rotation2d rotation) { armTalonFX.setControl( armMotionMagicRequest.withPosition(rotation.getRotations()).withEnableFOC(true)); } - /** - * Sets the current slot of the manipulator arm based on the current state of the subsystem. - * If the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to 1. - * Otherwise, it sets the slot to 0. + * Sets the current slot of the manipulator arm based on the current state of the subsystem. If + * the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to + * 1. Otherwise, it sets the slot to 0. * * @param slot The slot to set the arm to. * @throws IllegalArgumentException If the slot is not between 0 and 2, inclusive. From 5afe3495d7520d1b6c896919cdcbf67fbc9f5de6 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Thu, 25 Sep 2025 19:00:32 -0400 Subject: [PATCH 114/180] format --- .../frc/robot/commands/CompositeCommands.java | 3 +- .../subsystems/shared/climber/Climber.java | 12 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 93 +++----- .../intake/V3_EpsilonIntake.java | 88 ++++--- .../intake/V3_EpsilonIntakeIOTalonFX.java | 91 ++++--- .../manipulator/V3_EpsilonManipulator.java | 222 +++++++++--------- .../V3_EpsilonManipulatorIOTalonFX.java | 53 ++--- 7 files changed, 260 insertions(+), 302 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index a1233975..300fcaa4 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -931,8 +931,7 @@ public static final Command climb( climber.releaseClimber(), Commands.waitSeconds( V3_EpsilonClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), - Commands.deadline( - climber.winchClimber(), Commands.run(drive::stop))); + Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); } } } diff --git a/src/main/java/frc/robot/subsystems/shared/climber/Climber.java b/src/main/java/frc/robot/subsystems/shared/climber/Climber.java index d887a895..b777915a 100644 --- a/src/main/java/frc/robot/subsystems/shared/climber/Climber.java +++ b/src/main/java/frc/robot/subsystems/shared/climber/Climber.java @@ -49,12 +49,12 @@ public Climber(ClimberIO io) { override = false; } -/** - * Periodic function for the climber subsystem. - * - * Updates the inputs for the climber, processes the inputs, logs the state of the climber, and - * records the total time taken by the periodic function. - */ + /** + * Periodic function for the climber subsystem. + * + *

Updates the inputs for the climber, processes the inputs, logs the state of the climber, and + * records the total time taken by the periodic function. + */ @Override public void periodic() { ExternalLoggedTracer.reset(); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index c166fa12..520e912f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -2,19 +2,14 @@ import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.apriltag.AprilTagFields; -import edu.wpi.first.math.geometry.Pose2d; -import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.Constants; import frc.robot.Constants.Mode; import frc.robot.RobotContainer; import frc.robot.RobotState; -import frc.robot.commands.CompositeCommands; import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; -import frc.robot.commands.CompositeCommands; import frc.robot.commands.DriveCommands; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.drive.DriveConstants; @@ -68,68 +63,63 @@ public V3_EpsilonRobotContainer() { if (Constants.getMode() != Mode.REPLAY) { switch (Constants.ROBOT) { case V3_EPSILON: - drive = new Drive( - new GyroIOPigeon2(), - new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), - new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), - new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), - new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); + drive = + new Drive( + new GyroIOPigeon2(), + new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), + new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), + new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), + new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); - vision = new Vision( - () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), - RobotCameras.V2_REDUNDANCY_CAMS); + vision = + new Vision( + () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), + RobotCameras.V2_REDUNDANCY_CAMS); break; case V3_EPSILON_SIM: - drive = new Drive( - new GyroIO() { - }, - new ModuleIOSim(DriveConstants.FRONT_LEFT), - new ModuleIOSim(DriveConstants.FRONT_RIGHT), - new ModuleIOSim(DriveConstants.BACK_LEFT), - new ModuleIOSim(DriveConstants.BACK_RIGHT)); + drive = + new Drive( + new GyroIO() {}, + new ModuleIOSim(DriveConstants.FRONT_LEFT), + new ModuleIOSim(DriveConstants.FRONT_RIGHT), + new ModuleIOSim(DriveConstants.BACK_LEFT), + new ModuleIOSim(DriveConstants.BACK_RIGHT)); elevator = new Elevator(new ElevatorIOSim()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOSim()); superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); - vision = new Vision(() -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded)); + vision = + new Vision(() -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded)); break; default: break; } if (drive == null) { - drive = new Drive( - new GyroIO() { - }, - new ModuleIO() { - }, - new ModuleIO() { - }, - new ModuleIO() { - }, - new ModuleIO() { - }); + drive = + new Drive( + new GyroIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}); } if (elevator == null) { - elevator = new Elevator(new ElevatorIO() { - }).getFSM(); + elevator = new Elevator(new ElevatorIO() {}).getFSM(); } if (intake == null) { - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() { - }); + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); } if (manipulator == null) { - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() { - }); + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); } if (climber == null) { - climber = new V3_EpsilonClimber(new V3_EpsilonClimberIO() { - }); + climber = new V3_EpsilonClimber(new V3_EpsilonClimberIO() {}); } if (superstructure == null) { superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); @@ -139,9 +129,8 @@ public V3_EpsilonRobotContainer() { } /** - * Configure the button bindings for the robot. This method is called in - * the constructor and is responsible for setting up the default commands - * for each button on the controllers. + * Configure the button bindings for the robot. This method is called in the constructor and is + * responsible for setting up the default commands for each button on the controllers. */ private void configureButtonBindings() { drive.setDefaultCommand( @@ -161,13 +150,11 @@ private void configureButtonBindings() { .whileFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF)); } - private void configureAutos() { - } + private void configureAutos() {} /** - * Periodic function for the robot. This function is called every 20ms, - * and is responsible for updating the robot's state and logging relevant - * data. + * Periodic function for the robot. This function is called every 20ms, and is responsible for + * updating the robot's state and logging relevant data. */ @Override public void robotPeriodic() { @@ -193,16 +180,14 @@ public void robotPeriodic() { } /** - * Returns the autonomous command for the robot. This command will be scheduled - * for the entire autonomous period. + * Returns the autonomous command for the robot. This command will be scheduled for the entire + * autonomous period. * * @return the autonomous command for the robot */ @Override public Command getAutonomousCommand() { - return Commands.runOnce( - () -> RobotState.resetRobotPose(new Pose2d(7.25, 2.39, new Rotation2d(Math.PI / 2)))) - .andThen(CompositeCommands.V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure)); + return superstructure.allTransition(); // return superstructure.allTransition(); // return Commands.sequence( // V3_EpsilonCompositeCommands.dropAlgae( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index 3aacca32..7e0ed519 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -35,11 +35,10 @@ public V3_EpsilonIntake(V3_EpsilonIntakeIO io) { } /** - * Periodic function for intake subsystem. - * Updates inputs from the intake, and then sets the goals for the pivot and roller motors. - * If the intake is in closed-loop mode, it sets the pivot motor goal to the desired angle. - * Otherwise, it does not set the pivot motor goal. - * It always sets the inner and outer roller motor goals to the desired voltage. + * Periodic function for intake subsystem. Updates inputs from the intake, and then sets the goals + * for the pivot and roller motors. If the intake is in closed-loop mode, it sets the pivot motor + * goal to the desired angle. Otherwise, it does not set the pivot motor goal. It always sets the + * inner and outer roller motor goals to the desired voltage. */ public void periodic() { io.updateInputs(inputs); @@ -54,13 +53,12 @@ public void periodic() { } // Double check if this is right - + /** - * Checks if the intake is currently detecting coral. - * This is done by checking if both the left and right CAN range - * sensors are detecting a distance greater than the coral detection + * Checks if the intake is currently detecting coral. This is done by checking if both the left + * and right CAN range sensors are detecting a distance greater than the coral detection * threshold. - * + * * @return True if the intake is detecting coral, false otherwise. */ @AutoLogOutput(key = "Intake/Has Coral") @@ -71,12 +69,11 @@ public boolean hasCoral() { > V3_EpsilonIntakeConstants.INTAKE_CAN_CORAL_DETECTED_THRESHOLD_METERS; } - /** - * Checks if the pivot motor is at the goal angle. - * This is done by checking if the absolute difference between the current - * pivot motor angle and the goal angle is less than the goal tolerance. - * + * Checks if the pivot motor is at the goal angle. This is done by checking if the absolute + * difference between the current pivot motor angle and the goal angle is less than the goal + * tolerance. + * * @return True if the pivot motor is at the goal angle, false otherwise. */ @AutoLogOutput(key = "Intake/At Goal") @@ -85,54 +82,53 @@ public boolean pivotAtGoal() { < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); } - /** - * Checks if the pivot motor is at the goal angle. - * This is done by checking if the absolute difference between the current - * pivot motor angle and the goal angle is less than the goal tolerance. - * + * Checks if the pivot motor is at the goal angle. This is done by checking if the absolute + * difference between the current pivot motor angle and the goal angle is less than the goal + * tolerance. + * * @param goal The goal angle to check against. * @return True if the pivot motor is at the goal angle, false otherwise. */ public boolean pivotAtGoal(IntakePivotState goal) { - return Math.abs(inputs.pivotPosition.getRadians() - goal.getAngle().getRadians()) + return Math.abs(inputs.pivotPosition.getRadians() - goal.getAngle().getRadians()) < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); } -/** - * Sets the goal state of the pivot motor. - * If the intake is currently in open-loop mode, this method will set the isClosedLoop flag to true. - * It then sets the pivotGoal field to the specified goal state. - * The pivot motor will then be controlled in closed-loop mode to reach the specified goal state. - * - * @param goal The desired IntakePivotState for the pivot motor. - */ + /** + * Sets the goal state of the pivot motor. If the intake is currently in open-loop mode, this + * method will set the isClosedLoop flag to true. It then sets the pivotGoal field to the + * specified goal state. The pivot motor will then be controlled in closed-loop mode to reach the + * specified goal state. + * + * @param goal The desired IntakePivotState for the pivot motor. + */ public void setPivotGoal(IntakePivotState goal) { isClosedLoop = true; this.pivotGoal = goal; } - -/** - * Sets the voltage for the intake pivot motor. - * - * This method is used to set the voltage for the intake pivot motor in open-loop mode. - * It sets the isClosedLoop flag to false, and then calls the setPivotVoltage method of the IO interface. - * - * @param volts The voltage to set for the intake pivot motor. - */ + /** + * Sets the voltage for the intake pivot motor. + * + *

This method is used to set the voltage for the intake pivot motor in open-loop mode. It sets + * the isClosedLoop flag to false, and then calls the setPivotVoltage method of the IO interface. + * + * @param volts The voltage to set for the intake pivot motor. + */ public void setPivotVoltage(double volts) { isClosedLoop = false; io.setPivotVoltage(volts); } -/** - * Waits until the pivot motor is at the goal angle. - * This command is created by sequencing a wait command with a waitUntil command. - * The wait command waits for 0.02 seconds, and the waitUntil command checks if the pivot motor is at the goal angle. - * The command will block until the pivot motor is at the goal angle. - * @return A Command that waits until the pivot motor is at the goal angle. - */ + /** + * Waits until the pivot motor is at the goal angle. This command is created by sequencing a wait + * command with a waitUntil command. The wait command waits for 0.02 seconds, and the waitUntil + * command checks if the pivot motor is at the goal angle. The command will block until the pivot + * motor is at the goal angle. + * + * @return A Command that waits until the pivot motor is at the goal angle. + */ public Command waitUntilPivotAtGoal() { return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::pivotAtGoal)); } @@ -156,7 +152,7 @@ public void setRollerGoal(IntakeRollerState rollerGoal) { /** * Gets the current angle of the intake pivot motor. - * + * * @return The current angle of the intake pivot motor, in radians. */ public Rotation2d getPivotAngle() { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java index 290ae511..b3aa1a0e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java @@ -206,15 +206,14 @@ public V3_EpsilonIntakeIOTalonFX() { rightCANrangeStatusSignal); } - -/** - * Updates the inputs of the subsystem. - * - * This function is called by the robot periodic loop and should update all of the inputs - * of the subsystem. The inputs should be updated from the CAN bus and other sensors. - * - * @param inputs The inputs of the subsystem. - */ + /** + * Updates the inputs of the subsystem. + * + *

This function is called by the robot periodic loop and should update all of the inputs of + * the subsystem. The inputs should be updated from the CAN bus and other sensors. + * + * @param inputs The inputs of the subsystem. + */ @Override public void updateInputs(V3_EpsilonIntakeIOInputs inputs) { inputs.pivotPosition = new Rotation2d(pivotPositionRotations.getValue()); @@ -251,57 +250,53 @@ public void updateInputs(V3_EpsilonIntakeIOInputs inputs) { inputs.rightCANRangeDistanceMeters = rightCANrangeStatusSignal.getValueAsDouble(); } - -/** - * Sets the voltage for the intake pivot motor. - * - * This method is used to set the voltage for the intake pivot motor in open-loop mode. - * It sets the isClosedLoop flag to false, and then calls the setPivotVoltage method of the IO interface. - * - * @param volts The voltage to set for the intake pivot motor. - */ + /** + * Sets the voltage for the intake pivot motor. + * + *

This method is used to set the voltage for the intake pivot motor in open-loop mode. It sets + * the isClosedLoop flag to false, and then calls the setPivotVoltage method of the IO interface. + * + * @param volts The voltage to set for the intake pivot motor. + */ public void setPivotVoltage(double volts) { pivotTalonFX.setControl(pivotVoltageRequest.withOutput(volts).withEnableFOC(true)); } - -/** - * Sets the voltage for the inner manipulator roller. - * - * This method is used to set the voltage for the inner manipulator roller in open-loop mode. - * It sets the isClosedLoop flag to false, and then calls the setControl method of the TalonFX - * object with the voltage request. - * - * @param volts The voltage to set for the inner manipulator roller. - */ - + /** + * Sets the voltage for the inner manipulator roller. + * + *

This method is used to set the voltage for the inner manipulator roller in open-loop mode. + * It sets the isClosedLoop flag to false, and then calls the setControl method of the TalonFX + * object with the voltage request. + * + * @param volts The voltage to set for the inner manipulator roller. + */ public void setInnerRollerVoltage(double volts) { rollerTalonFXInner.setControl(rollerInnerVoltageRequest.withOutput(volts).withEnableFOC(true)); } -/** - * Sets the voltage for the outer manipulator roller. - * - * This method is used to set the voltage for the outer manipulator roller in open-loop mode. - * It sets the isClosedLoop flag to false, and then calls the setControl method of the TalonFX - * object with the voltage request. - * - * @param volts The voltage to set for the outer manipulator roller. - */ + /** + * Sets the voltage for the outer manipulator roller. + * + *

This method is used to set the voltage for the outer manipulator roller in open-loop mode. + * It sets the isClosedLoop flag to false, and then calls the setControl method of the TalonFX + * object with the voltage request. + * + * @param volts The voltage to set for the outer manipulator roller. + */ public void setOuterRollerVoltage(double volts) { rollerTalonFXOuter.setControl(rollerOuterVoltageRequest.withOutput(volts).withEnableFOC(true)); } - -/** - * Sets the position of the intake pivot motor using Motion Magic. - * - * This method is used to set the position of the intake pivot motor using Motion Magic. - * It sets the isClosedLoop flag to true, and then calls the setControl method of the - * TalonFX object with the position request. - * - * @param position The desired position of the intake pivot motor. - */ + /** + * Sets the position of the intake pivot motor using Motion Magic. + * + *

This method is used to set the position of the intake pivot motor using Motion Magic. It + * sets the isClosedLoop flag to true, and then calls the setControl method of the TalonFX object + * with the position request. + * + * @param position The desired position of the intake pivot motor. + */ public void setPivotMotionMagic(Rotation2d position) { pivotTalonFX.setControl( pivotMotionMagicRequest.withPosition(position.getMeasure()).withEnableFOC(true)); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 8ff701e1..95a6829a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -73,41 +73,40 @@ public void periodic() { } } -/** - * Checks if the manipulator is currently detecting coral. - * This is done by checking if the CAN range sensor is detecting a distance - * less than the coral detection threshold and greater than 0. - * - * @return True if the manipulator is detecting coral, false otherwise. - */ + /** + * Checks if the manipulator is currently detecting coral. This is done by checking if the CAN + * range sensor is detecting a distance less than the coral detection threshold and greater than + * 0. + * + * @return True if the manipulator is detecting coral, false otherwise. + */ @AutoLogOutput(key = "Manipulator/Has Coral") public boolean hasCoral() { return inputs.canRangeDistanceMeters < V3_EpsilonManipulatorConstants.CORAL_CAN_RANGE_THRESHOLD && inputs.canRangeDistanceMeters > 0; } -/** - * Checks if the manipulator is currently detecting algae. - * This is done by checking if the CAN range sensor is detecting a distance - * less than the algae detection threshold and greater than 0. - * - * @return True if the manipulator is detecting algae, false otherwise. - */ + /** + * Checks if the manipulator is currently detecting algae. This is done by checking if the CAN + * range sensor is detecting a distance less than the algae detection threshold and greater than + * 0. + * + * @return True if the manipulator is detecting algae, false otherwise. + */ @AutoLogOutput(key = "Manipulator/Has Algae") public boolean hasAlgae() { return inputs.canRangeDistanceMeters < V3_EpsilonManipulatorConstants.ALGAE_CAN_RANGE_THRESHOLD && inputs.canRangeDistanceMeters > 0; } -/** - * Creates a command to run the manipulator arm at a specified voltage. - * - * @param volts The voltage to set the arm to. - * @return A command to run the arm. - */ - + /** + * Creates a command to run the manipulator arm at a specified voltage. + * + * @param volts The voltage to set the arm to. + * @return A command to run the arm. + */ public Command runArm(double volts) { - return Commands.runEnd( + return Commands.runEnd( () -> { isClosedLoop = false; io.setArmVoltage(volts); @@ -115,43 +114,39 @@ public Command runArm(double volts) { () -> io.setArmVoltage(0)); } - -/** - * Sets the goal for the manipulator arm to reach. - * - * @param goal The goal state to set the arm to. - */ - + /** + * Sets the goal for the manipulator arm to reach. + * + * @param goal The goal state to set the arm to. + */ public void setArmGoal(ManipulatorArmState goal) { isClosedLoop = true; armGoal = goal; } - -/** - * Updates the gains for the manipulator arm. - * This function sets the PID gains for the three slots of the arm. - * The gains are used to control the arm's movement. - * - * @param kP0 The proportional gain for slot 0. - * @param kD0 The derivative gain for slot 0. - * @param kS0 The static gain for slot 0. - * @param kV0 The velocity gain for slot 0. - * @param kA0 The acceleration gain for slot 0. - * @param kG0 The gravity gain for slot 0. - * @param kP1 The proportional gain for slot 1. - * @param kD1 The derivative gain for slot 1. - * @param kS1 The static gain for slot 1. - * @param kV1 The velocity gain for slot 1. - * @param kA1 The acceleration gain for slot 1. - * @param kG1 The gravity gain for slot 1. - * @param kP2 The proportional gain for slot 2. - * @param kD2 The derivative gain for slot 2. - * @param kS2 The static gain for slot 2. - * @param kV2 The velocity gain for slot 2. - * @param kA2 The acceleration gain for slot 2. - * @param kG2 The gravity gain for slot 2. - */ + /** + * Updates the gains for the manipulator arm. This function sets the PID gains for the three slots + * of the arm. The gains are used to control the arm's movement. + * + * @param kP0 The proportional gain for slot 0. + * @param kD0 The derivative gain for slot 0. + * @param kS0 The static gain for slot 0. + * @param kV0 The velocity gain for slot 0. + * @param kA0 The acceleration gain for slot 0. + * @param kG0 The gravity gain for slot 0. + * @param kP1 The proportional gain for slot 1. + * @param kD1 The derivative gain for slot 1. + * @param kS1 The static gain for slot 1. + * @param kV1 The velocity gain for slot 1. + * @param kA1 The acceleration gain for slot 1. + * @param kG1 The gravity gain for slot 1. + * @param kP2 The proportional gain for slot 2. + * @param kD2 The derivative gain for slot 2. + * @param kS2 The static gain for slot 2. + * @param kV2 The velocity gain for slot 2. + * @param kA2 The acceleration gain for slot 2. + * @param kG2 The gravity gain for slot 2. + */ public void updateArmGains( double kP0, double kD0, @@ -176,68 +171,63 @@ public void updateArmGains( io.updateSlot2ArmGains(kP2, kD2, kS2, kV2, kA2, kG2); } -/** - * Updates the constraints for the arm. - * - * @param maxAcceleration The maximum acceleration. - * @param maxVelocity The maximum velocity. - */ + /** + * Updates the constraints for the arm. + * + * @param maxAcceleration The maximum acceleration. + * @param maxVelocity The maximum velocity. + */ public void updateArmConstraints(double maxAcceleration, double maxVelocity) { io.updateArmConstraints(maxAcceleration, maxVelocity); } -/** - * Checks if the arm is at the goal position. - * - * This function checks if the arm is within the goal tolerance of the - * currently set arm goal position. If the arm is within the tolerance, it - * returns true. Otherwise, it returns false. - * - * @return If the arm is at the goal position. - */ - + /** + * Checks if the arm is at the goal position. + * + *

This function checks if the arm is within the goal tolerance of the currently set arm goal + * position. If the arm is within the tolerance, it returns true. Otherwise, it returns false. + * + * @return If the arm is at the goal position. + */ @AutoLogOutput(key = "Manipulator/Arm At Goal") public boolean armAtGoal() { return armAtGoal(armGoal); } -/** - * Checks if the arm is at the given goal position. - * - * This function checks if the arm is within the goal tolerance of the - * given arm goal position. If the arm is within the tolerance, it - * returns true. Otherwise, it returns false. - * - * @param state The arm goal position to check against. - * @return If the arm is at the goal position. - */ + /** + * Checks if the arm is at the given goal position. + * + *

This function checks if the arm is within the goal tolerance of the given arm goal position. + * If the arm is within the tolerance, it returns true. Otherwise, it returns false. + * + * @param state The arm goal position to check against. + * @return If the arm is at the goal position. + */ public boolean armAtGoal(ManipulatorArmState state) { return Math.abs(inputs.armPosition.minus(state.getAngle(armSide)).getRadians()) <= V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); } -/** - * Waits until the arm is at the goal position. - * - * This command waits for 0.02 seconds and then checks if the arm is at the goal position. - * If the arm is not at the goal position, it waits for 0.02 seconds and checks again. - * This process repeats until the arm is at the goal position. - * - * @return A command that waits until the arm is at the goal position. - */ + /** + * Waits until the arm is at the goal position. + * + *

This command waits for 0.02 seconds and then checks if the arm is at the goal position. If + * the arm is not at the goal position, it waits for 0.02 seconds and checks again. This process + * repeats until the arm is at the goal position. + * + * @return A command that waits until the arm is at the goal position. + */ public Command waitUntilArmAtGoal() { return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::armAtGoal)); } -/** - * Returns a voltage to hold the roller at the current position. - * The voltage is calculated based on the current torque current of the roller. - * The calculation is done using a piecewise polynomial function. - * The function first checks if the current torque current is less than or equal to 20. - * If it is, it uses one set of coefficients to calculate the voltage. - * Otherwise, it uses another set of coefficients. - */ - + /** + * Returns a voltage to hold the roller at the current position. The voltage is calculated based + * on the current torque current of the roller. The calculation is done using a piecewise + * polynomial function. The function first checks if the current torque current is less than or + * equal to 20. If it is, it uses one set of coefficients to calculate the voltage. Otherwise, it + * uses another set of coefficients. + */ private double holdVoltage() { double y; double x = Math.abs(inputs.rollerTorqueCurrentAmps); @@ -252,11 +242,11 @@ private double holdVoltage() { V3_EpsilonManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().getAsDouble() / 1.5); } -/** - * Sets the current slot of the manipulator arm based on the current state of the subsystem. - * If the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to 1. - * Otherwise, it sets the slot to 0. - */ + /** + * Sets the current slot of the manipulator arm based on the current state of the subsystem. If + * the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to + * 1. Otherwise, it sets the slot to 0. + */ public void setSlot() { if (hasAlgae()) { io.setSlot(2); @@ -267,7 +257,6 @@ public void setSlot() { } } - /** * Sets the manipulator arm to the specified state. * @@ -278,10 +267,9 @@ public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmSta } /** - * Sets the roller goal state of the manipulator. - * If the subsystem has algae or coral and the goal is one of the intake states, - * it sets the roller voltage to the hold voltage. Otherwise, it sets the roller voltage - * to the goal voltage. + * Sets the roller goal state of the manipulator. If the subsystem has algae or coral and the goal + * is one of the intake states, it sets the roller voltage to the hold voltage. Otherwise, it sets + * the roller voltage to the goal voltage. * * @param rollerGoal The desired state of the roller. */ @@ -302,21 +290,21 @@ public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState /** * Gets the current angle of the manipulator arm. - * + * * @return The current angle of the manipulator arm, in radians. */ public Rotation2d getArmAngle() { return inputs.armPosition; } -/** - * Checks if the manipulator arm is currently in a safe position. - * A safe position is when the arm is pointing away from the robot's body. - * The safe position threshold is determined by the angle between the arm and the robot's body. - * If the angle is greater than the threshold, it is considered safe. - * - * @return true if the arm is in a safe position, false otherwise. - */ + /** + * Checks if the manipulator arm is currently in a safe position. A safe position is when the arm + * is pointing away from the robot's body. The safe position threshold is determined by the angle + * between the arm and the robot's body. If the angle is greater than the threshold, it is + * considered safe. + * + * @return true if the arm is in a safe position, false otherwise. + */ @AutoLogOutput(key = "Manipulator/Safe Position") public boolean isSafePosition() { double cosThresh = diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java index 07f36308..71746f51 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java @@ -138,11 +138,11 @@ public V3_EpsilonManipulatorIOTalonFX() { rollerTalonFX.optimizeBusUtilization(); } -/** - * Updates the inputs of the manipulator with the current state of the TalonFXs. - * - * @param inputs the inputs to update - */ + /** + * Updates the inputs of the manipulator with the current state of the TalonFXs. + * + * @param inputs the inputs to update + */ @Override public void updateInputs(ManipulatorIOInputs inputs) { @@ -169,15 +169,12 @@ public void updateInputs(ManipulatorIOInputs inputs) { Rotation2d.fromRotations(armPositionErrorRotations.getValueAsDouble()); } - - /** - * Sets the voltage of the arm TalonFX to the specified value. - * The voltage is set in terms of volts, with positive values corresponding to - * clockwise rotation and negative values corresponding to counterclockwise - * rotation. - * This method is used to control the velocity of the arm, which is useful - * for tasks such as picking up objects or depositing objects. + * Sets the voltage of the arm TalonFX to the specified value. The voltage is set in terms of + * volts, with positive values corresponding to clockwise rotation and negative values + * corresponding to counterclockwise rotation. This method is used to control the velocity of the + * arm, which is useful for tasks such as picking up objects or depositing objects. + * * @param volts the voltage to set, in volts */ @Override @@ -185,37 +182,35 @@ public void setArmVoltage(double volts) { armTalonFX.setControl(armVoltageRequest.withOutput(volts).withEnableFOC(true)); } - - -/** - * Sets the voltage of the roller TalonFX to the specified value. - * The voltage is set in terms of volts, with positive values corresponding to clockwise rotation and negative values corresponding to counterclockwise rotation. - * This method is used to control the velocity of the roller, which is useful for tasks such as picking up objects or depositing objects. - */ + /** + * Sets the voltage of the roller TalonFX to the specified value. The voltage is set in terms of + * volts, with positive values corresponding to clockwise rotation and negative values + * corresponding to counterclockwise rotation. This method is used to control the velocity of the + * roller, which is useful for tasks such as picking up objects or depositing objects. + */ @Override public void setRollerVoltage(double volts) { rollerTalonFX.setControl(rollerVoltageRequest.withOutput(volts).withEnableFOC(true)); } - /** - * The position is set in terms of rotations of the TalonFX's motor shaft. - * This method is used to set the manipulator arm to a specific position, which is useful for tasks such as picking up objects or depositing objects. + * The position is set in terms of rotations of the TalonFX's motor shaft. This method is used to + * set the manipulator arm to a specific position, which is useful for tasks such as picking up + * objects or depositing objects. * - * @param rotation The desired position of the manipulator arm, in terms of rotations of the TalonFX's motor shaft. + * @param rotation The desired position of the manipulator arm, in terms of rotations of the + * TalonFX's motor shaft. */ - @Override public void setArmGoal(Rotation2d rotation) { armTalonFX.setControl( armMotionMagicRequest.withPosition(rotation.getRotations()).withEnableFOC(true)); } - /** - * Sets the current slot of the manipulator arm based on the current state of the subsystem. - * If the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to 1. - * Otherwise, it sets the slot to 0. + * Sets the current slot of the manipulator arm based on the current state of the subsystem. If + * the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to + * 1. Otherwise, it sets the slot to 0. * * @param slot The slot to set the arm to. * @throws IllegalArgumentException If the slot is not between 0 and 2, inclusive. From 615e1927796e617ba5b8bc33cf645a64861e8962 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Thu, 25 Sep 2025 19:36:11 -0400 Subject: [PATCH 115/180] fixed --- .../intake/V3_EpsilonIntakeConstants.java | 12 ++++++------ .../manipulator/V3_EpsilonManipulatorConstants.java | 2 +- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index e981250e..02b16835 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -47,7 +47,7 @@ public class V3_EpsilonIntakeConstants { switch (Constants.ROBOT) { case V3_EPSILON_SIM: PIVOT_CONSTRAINTS = new Constraints(500.0, 500.0, Rotation2d.fromDegrees(1.5)); - PIVOT_GAINS = new Gains(0.0, 0.00, 0.0, 0.0, 0.0, 0.0); + PIVOT_GAINS = new Gains(1.0, 0.01, 0.0, 0.0, 0.0, 0.0); CURRENT_LIMITS = new IntakeCurrentLimits(40.0, 40.0, 40.0, 40.0, 40.0, 40.0); break; @@ -63,11 +63,11 @@ public class V3_EpsilonIntakeConstants { @RequiredArgsConstructor public enum IntakePivotState { - STOW(Rotation2d.fromDegrees(-123.6)), - INTAKE_CORAL(Rotation2d.fromDegrees(0)), - HANDOFF(Rotation2d.fromDegrees(-123.6)), - L1(Rotation2d.fromDegrees(-82)), - INTAKE_ALGAE(new Rotation2d(0)), + STOW(Rotation2d.fromDegrees(25.0)), + INTAKE_CORAL(Rotation2d.fromDegrees(123.6)), + HANDOFF(Rotation2d.fromDegrees(0)), + L1(Rotation2d.fromDegrees(-82 + 123.6)), + INTAKE_ALGAE(new Rotation2d()), ARM_CLEAR(Rotation2d.fromDegrees(35)); @Getter private final Rotation2d angle; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index dd5d6cf5..0f011e3c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -170,7 +170,7 @@ public static record ArmParameters( public static enum ManipulatorArmState { PRE_SCORE(Rotation2d.fromDegrees(50.0)), SCORE(Rotation2d.fromDegrees(55.0)), // Placeholder value. Make sure to test - BARGE_SCORE(Rotation2d.fromDegrees(-10)), + BARGE_SCORE(Rotation2d.fromDegrees(18.67)), PROCESSOR(Rotation2d.fromDegrees(41.279296875)), REEF_INTAKE(Rotation2d.fromDegrees(46.279296875)), INTAKE_OUT_LINE(Rotation2d.fromDegrees(61)), From e3edbd6a87e603f2b2f435bf95b7cfbce2f33627 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Thu, 25 Sep 2025 21:50:29 -0400 Subject: [PATCH 116/180] fix 2 collisions and climb state --- src/main/deploy/Superstructure.dot | 6 +++--- .../superstructure/V3_EpsilonSuperstructureEdges.java | 6 ++++++ 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/Superstructure.dot index 174a234a..fb43184b 100644 --- a/src/main/deploy/Superstructure.dot +++ b/src/main/deploy/Superstructure.dot @@ -25,7 +25,7 @@ digraph Superstructure { GROUND_ACQUISITION -> L2_ALGAE [type=UNCONSTRAINED, requires=ARM] GROUND_ACQUISITION -> L3_ALGAE [type=UNCONSTRAINED, requires=ARM] GROUND_ACQUISITION -> PROCESSOR [type=UNCONSTRAINED, requires=ARM] - GROUND_ACQUISITION -> BARGE [type=UNCONSTRAINED] + GROUND_ACQUISITION -> BARGE [type=UNCONSTRAINED, requires=ARM] GROUND_INTAKE -> GROUND_ACQUISITION [type=UNCONSTRAINED] @@ -39,7 +39,7 @@ digraph Superstructure { L1 -> L2_ALGAE [type=UNCONSTRAINED, requires=ARM] L1 -> L3_ALGAE [type=UNCONSTRAINED, requires=ARM] L1 -> PROCESSOR [type=UNCONSTRAINED, requires=ARM] - L1 -> BARGE [type=UNCONSTRAINED] + L1 -> BARGE [type=UNCONSTRAINED, requires=ARM] L2 -> STOW_DOWN [type=UNCONSTRAINED] L2 -> GROUND_ACQUISITION [type=UNCONSTRAINED] @@ -207,6 +207,6 @@ digraph Superstructure { BARGE_SCORE -> BARGE [type=UNCONSTRAINED] - CLIMB -> STOW_DOWN [type=UNCONSTRAINED] + CLIMB -> STOW_DOWN [type=UNCONSTRAINED, requires=ARM] CLIMB -> STOW_UP [type=UNCONSTRAINED] } \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index ca9e910a..b201d8f7 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -4,7 +4,9 @@ import edu.wpi.first.wpilibj.Filesystem; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; +import frc.robot.RobotState; import frc.robot.FieldConstants.Reef.ReefState; +import frc.robot.RobotState.ScoreSide; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.shared.elevator.ElevatorConstants; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; @@ -267,6 +269,10 @@ else if (willCollide(from, to)) { Commands.race(Commands.waitUntil(() -> elevator.pastBargeThresholdgetPositionMeters()))); } + if (to == V3_EpsilonSuperstructureStates.CLIMB) { + return moveCommand.beforeStarting(()->RobotState.setScoreSide(ScoreSide.RIGHT)); + } + // THE CRITICAL FIX: // No matter how we start the move, we append a final wait condition. // This ensures the command doesn't end until the robot is physically at the From 1890eaea48ff49fd92746371244889b21567f05e Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Thu, 25 Sep 2025 22:06:48 -0400 Subject: [PATCH 117/180] Update Superstructure and related classes to enforce required states for transitions --- src/main/deploy/Superstructure.dot | 4 ++-- .../superstructure/V3_EpsilonSuperstructureEdges.java | 4 ++-- .../superstructure/V3_EpsilonSuperstructureStates.java | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/Superstructure.dot index fb43184b..6a8dbaa6 100644 --- a/src/main/deploy/Superstructure.dot +++ b/src/main/deploy/Superstructure.dot @@ -32,7 +32,7 @@ digraph Superstructure { L1 -> GROUND_ACQUISITION [type=UNCONSTRAINED] L1 -> L2 [type=UNCONSTRAINED, requires=ARM] L1 -> L3 [type=UNCONSTRAINED, requires=ARM] - L1 -> L4 [type=UNCONSTRAINED] + L1 -> L4 [type=UNCONSTRAINED, requires=ELEVATOR] L1 -> L1_SCORE [type=UNCONSTRAINED] L1 -> HANDOFF [type=UNCONSTRAINED] L1 -> STOW_UP [type=UNCONSTRAINED, requires=ARM] @@ -131,7 +131,7 @@ digraph Superstructure { HANDOFF -> L2_ALGAE [type=UNCONSTRAINED, requires=ARM] HANDOFF -> L3_ALGAE [type=UNCONSTRAINED, requires=ARM] HANDOFF -> PROCESSOR [type=UNCONSTRAINED, requires=ARM] - HANDOFF -> BARGE [type=UNCONSTRAINED] + HANDOFF -> BARGE [type=UNCONSTRAINED, requires=ARM] STOW_UP -> STOW_DOWN [type=UNCONSTRAINED] STOW_UP -> GROUND_ACQUISITION [type=UNCONSTRAINED, requires=ELEVATOR] diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index b201d8f7..e59a72f8 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -4,8 +4,8 @@ import edu.wpi.first.wpilibj.Filesystem; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; -import frc.robot.RobotState; import frc.robot.FieldConstants.Reef.ReefState; +import frc.robot.RobotState; import frc.robot.RobotState.ScoreSide; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.shared.elevator.ElevatorConstants; @@ -270,7 +270,7 @@ else if (willCollide(from, to)) { } if (to == V3_EpsilonSuperstructureStates.CLIMB) { - return moveCommand.beforeStarting(()->RobotState.setScoreSide(ScoreSide.RIGHT)); + return moveCommand.beforeStarting(() -> RobotState.setScoreSide(ScoreSide.RIGHT)); } // THE CRITICAL FIX: diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 2fdb18d1..0a0b7361 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -82,7 +82,7 @@ public enum V3_EpsilonSuperstructureStates { HANDOFF( "HANDOFF", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.STOW), + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.OUTTAKE)), INTERMEDIATE_WAIT_FOR_ELEVATOR( From 6112779702f2a8e701b463ee625b233895f134f4 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Thu, 25 Sep 2025 22:24:25 -0400 Subject: [PATCH 118/180] climber state fixed --- src/main/java/frc/robot/RobotState.java | 1 + .../v3_Epsilon/V3_EpsilonRobotContainer.java | 2 +- .../v3_Epsilon/climber/V3_EpsilonClimber.java | 8 +++++++- .../superstructure/V3_EpsilonSuperstructureEdges.java | 11 +++++++++-- 4 files changed, 18 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/RobotState.java b/src/main/java/frc/robot/RobotState.java index 6bc60f9c..bbf673be 100644 --- a/src/main/java/frc/robot/RobotState.java +++ b/src/main/java/frc/robot/RobotState.java @@ -48,6 +48,7 @@ public class RobotState { @Getter @Setter private static boolean isIntakingAlgae; @Getter @Setter private static boolean isAutoAligning; @Getter @Setter private static boolean autoClapOverride; + @Getter @Setter private static boolean climberReady; private static final TimeInterpolatableBuffer poseBuffer; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 520e912f..c84b291c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -78,7 +78,7 @@ public V3_EpsilonRobotContainer() { vision = new Vision( () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), - RobotCameras.V2_REDUNDANCY_CAMS); + RobotCameras.V3_EPSILON_CAMS); break; case V3_EPSILON_SIM: drive = diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java index f5d1253f..a0f4f600 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java @@ -3,6 +3,7 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.RobotState; import frc.robot.util.ExternalLoggedTracer; import frc.robot.util.InternalLoggedTracer; import org.littletonrobotics.junction.AutoLogOutput; @@ -70,7 +71,12 @@ public Command setRollerVoltage(double volts) { */ public Command releaseClimber() { return this.runEnd(() -> io.setDeploymentVoltage(1), () -> io.setDeploymentVoltage(0)) - .until(() -> inputs.deploymentPosition.getRadians() >= 20); + .until( + () -> + inputs.deploymentPosition.getRadians() + >= V3_EpsilonClimberConstants.CLIMBER_CLIMBED_DEPLOYED_RADIANS + || override) + .finallyDo(() -> RobotState.setClimberReady(true)); } /** diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index e59a72f8..3b5c5964 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -269,8 +269,16 @@ else if (willCollide(from, to)) { Commands.race(Commands.waitUntil(() -> elevator.pastBargeThresholdgetPositionMeters()))); } + // arm has to be on the right and elevator has to be up for climber to deploy if (to == V3_EpsilonSuperstructureStates.CLIMB) { - return moveCommand.beforeStarting(() -> RobotState.setScoreSide(ScoreSide.RIGHT)); + moveCommand = + Commands.sequence( + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.ALGAE_SCORE)) + .alongWith(pose.setManipulatorState(manipulator), pose.setIntakeState(intake)) + .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.RIGHT)), + elevator.waitUntilAtGoal(), + Commands.waitUntil(RobotState::isClimberReady), + pose.setElevatorHeight(elevator)); } // THE CRITICAL FIX: @@ -403,7 +411,6 @@ private static Command waitForPoseCommand( ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { - V3_EpsilonSuperstructurePose pose = state.getPose(); // Add this command to log the check's status Command logCheck = From 890da3aefa0d086e8a6761e9563277dc9d6588ca Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Thu, 25 Sep 2025 23:22:33 -0400 Subject: [PATCH 119/180] Remove unused startup script and Python HID interface; add chassis speed measurement and new autonomous routines --- ds_hid/ds_hid.py | 137 ------------ ds_hid/startup.bat | 3 - src/main/deploy/choreo/A_LEFT_PATH1.traj | 64 ------ src/main/deploy/choreo/A_LEFT_PATH2.traj | 178 ---------------- src/main/deploy/choreo/A_LEFT_PATH3.traj | 119 ----------- src/main/deploy/choreo/A_LEFT_PATH4.traj | 129 ------------ .../deploy/choreo/A_LEFT_PATH4_ALT_ALT.traj | 136 ------------ src/main/deploy/choreo/A_LEFT_PATH_ALT3.traj | 130 ------------ src/main/deploy/choreo/A_LEFT_PATH_ALT4.traj | 125 ----------- src/main/deploy/choreo/A_RIGHT_PATH1.traj | 64 ------ src/main/deploy/choreo/A_RIGHT_PATH2.traj | 180 ---------------- src/main/deploy/choreo/A_RIGHT_PATH3.traj | 118 ----------- src/main/deploy/choreo/A_RIGHT_PATH4.traj | 129 ------------ src/main/deploy/choreo/B_LEFT_PATH1.traj | 112 ---------- src/main/deploy/choreo/B_LEFT_PATH2.traj | 159 -------------- src/main/deploy/choreo/B_LEFT_PATH3.traj | 96 --------- src/main/deploy/choreo/B_RIGHT_PATH1.traj | 108 ---------- src/main/deploy/choreo/B_RIGHT_PATH2.traj | 157 -------------- src/main/deploy/choreo/B_RIGHT_PATH3.traj | 97 --------- src/main/deploy/choreo/C_LEFT_PATH1.traj | 67 ------ src/main/deploy/choreo/C_LEFT_PATH2.traj | 188 ----------------- src/main/deploy/choreo/C_LEFT_PATH3.traj | 146 ------------- src/main/deploy/choreo/C_RIGHT_PATH1.traj | 67 ------ src/main/deploy/choreo/C_RIGHT_PATH2.traj | 181 ---------------- src/main/deploy/choreo/C_RIGHT_PATH3.traj | 137 ------------ src/main/deploy/choreo/D_CENTER_PATH.traj | 55 ----- src/main/deploy/choreo/E_RIGHT_PATH_1.traj | 119 ++++++----- src/main/deploy/choreo/E_RIGHT_PATH_2.traj | 96 +++++---- src/main/deploy/choreo/E_RIGHT_PATH_3.traj | 199 ++++++++---------- src/main/deploy/choreo/E_RIGHT_PATH_4.traj | 106 ++++++---- .../robot/commands/AutonomousCommands.java | 132 +++++++++++- .../frc/robot/commands/DriveCommands.java | 67 +++++- .../robot/subsystems/shared/drive/Drive.java | 2 + .../v3_Epsilon/V3_EpsilonRobotContainer.java | 10 +- .../java/frc/robot/util/GeometryUtil.java | 50 +++++ 35 files changed, 520 insertions(+), 3343 deletions(-) delete mode 100644 ds_hid/ds_hid.py delete mode 100644 ds_hid/startup.bat delete mode 100644 src/main/deploy/choreo/A_LEFT_PATH1.traj delete mode 100644 src/main/deploy/choreo/A_LEFT_PATH2.traj delete mode 100644 src/main/deploy/choreo/A_LEFT_PATH3.traj delete mode 100644 src/main/deploy/choreo/A_LEFT_PATH4.traj delete mode 100644 src/main/deploy/choreo/A_LEFT_PATH4_ALT_ALT.traj delete mode 100644 src/main/deploy/choreo/A_LEFT_PATH_ALT3.traj delete mode 100644 src/main/deploy/choreo/A_LEFT_PATH_ALT4.traj delete mode 100644 src/main/deploy/choreo/A_RIGHT_PATH1.traj delete mode 100644 src/main/deploy/choreo/A_RIGHT_PATH2.traj delete mode 100644 src/main/deploy/choreo/A_RIGHT_PATH3.traj delete mode 100644 src/main/deploy/choreo/A_RIGHT_PATH4.traj delete mode 100644 src/main/deploy/choreo/B_LEFT_PATH1.traj delete mode 100644 src/main/deploy/choreo/B_LEFT_PATH2.traj delete mode 100644 src/main/deploy/choreo/B_LEFT_PATH3.traj delete mode 100644 src/main/deploy/choreo/B_RIGHT_PATH1.traj delete mode 100644 src/main/deploy/choreo/B_RIGHT_PATH2.traj delete mode 100644 src/main/deploy/choreo/B_RIGHT_PATH3.traj delete mode 100644 src/main/deploy/choreo/C_LEFT_PATH1.traj delete mode 100644 src/main/deploy/choreo/C_LEFT_PATH2.traj delete mode 100644 src/main/deploy/choreo/C_LEFT_PATH3.traj delete mode 100644 src/main/deploy/choreo/C_RIGHT_PATH1.traj delete mode 100644 src/main/deploy/choreo/C_RIGHT_PATH2.traj delete mode 100644 src/main/deploy/choreo/C_RIGHT_PATH3.traj delete mode 100644 src/main/deploy/choreo/D_CENTER_PATH.traj diff --git a/ds_hid/ds_hid.py b/ds_hid/ds_hid.py deleted file mode 100644 index 95f9f839..00000000 --- a/ds_hid/ds_hid.py +++ /dev/null @@ -1,137 +0,0 @@ -import usb.core -import usb.util -import usb.backend.libusb1 -from usbmonitor import USBMonitor -from networktables import NetworkTables - -# XK-80 Vendor and Product ID -VENDOR_ID = 1523 -PRODUCT_ID = 1091 - -# Networktables stuff -SERVER = '10.1.90.2' -KEYBOARD = 0 -KEYS = 80 - -connected = False -# Set up NetworkTables connection -try: - NetworkTables.initialize(server=SERVER) -except Exception as e: - print(f'Failed to initialize NetworkTables with server {SERVER}: {e}.') - -keyboard_status_table = NetworkTables.getTable('AdvantageKit/DriverStation/Keyboard'+str(KEYBOARD)) - -def on_disconnect(device_id, device_info): - keyboard_status_table.putBoolean('isConnected', False) - connected = False - print(f"Device disconnected: {device_id}") - -def on_connect(device_id, device_info): - keyboard_status_table.putBoolean('isConnected', True) - connected = True - print(f"Device connected: {device_id}") - - -monitor = USBMonitor() -monitor.start_monitoring(on_connect=on_connect, on_disconnect=on_disconnect, check_every_seconds=0.02) - -def send_data(data): - keyboard_status_table.putBoolean('isConnected', True) - for key in data: - keyboard_status_table.putBoolean(str(key), True) - -def set_up_NT(): - for i in range(KEYS): - keyboard_status_table.putBoolean(str(i), False) - -set_up_NT() - - -# Find the XK-80 device -backend = usb.backend.libusb1.get_backend() -device = usb.core.find(idVendor=VENDOR_ID, idProduct=PRODUCT_ID, backend=backend) - -if device is None: - print("XK-80 not found! Check connections.") - exit(1) - -print("XK-80 found and ready!") - -# Detach kernel driver if necessary (Linux only) -if device.is_kernel_driver_active(0): - device.detach_kernel_driver(0) - -# Set device configuration -device.set_configuration() - -# Find the HID endpoint for reading input -cfg = device.get_active_configuration() -interface = cfg[(0, 0)] -endpoint = usb.util.find_descriptor( - interface, - custom_match=lambda e: usb.util.endpoint_direction(e.bEndpointAddress) == usb.util.ENDPOINT_IN -) - -if endpoint is None: - print("No IN endpoint found on XK-80") - keyboard_status_table.putBoolean('isConnected', False) - exit(1) - -print("Listening for XK-80 key presses...") - - -try: - while True: - try: - if connected is True: - keyboard_status_table.putBoolean('isConnected', True) - pass - data = device.read(endpoint.bEndpointAddress, endpoint.wMaxPacketSize, timeout=5000) - - if data: - keyboard_status_table.putBoolean('isConnected', True) - print(f"Raw Data: {list(data)}") - - key_states = data[2:12] # 10 bytes, representing 10 columns - pressed_keys = [] - - for col_index, byte in enumerate(key_states): - for row_index in range(8): - if (byte >> row_index) & 1: - key_number = (col_index) * 8 + row_index - pressed_keys.append(key_number) - - set_up_NT() - if pressed_keys: - print(f"Keys Pressed: {pressed_keys}") - send_data(pressed_keys) - else: - print("No keys pressed.") - else: - print("No data received.") - keyboard_status_table.putBoolean('isConnected', False) - - except usb.core.USBTimeoutError: - pass # Ignore timeout errors - - except usb.core.USBError as e: - if e.errno == 5: # Input/Output Error = Disconnected device - print("Device disconnected! Exiting loop...") - keyboard_status_table.putBoolean('isConnected', False) - break # Exit the loop when the device disconnects - -except KeyboardInterrupt: - print("\nStopping script.") - -finally: - print("Cleaning up...") - monitor.stop_monitoring() - keyboard_status_table.putBoolean('isConnected', False) - NetworkTables.stopClient() - - try: - usb.util.release_interface(device, 0) - device.attach_kernel_driver(0) # Only needed on Linux - except: - pass # Ignore errors if device is already gone diff --git a/ds_hid/startup.bat b/ds_hid/startup.bat deleted file mode 100644 index 93b4e9a1..00000000 --- a/ds_hid/startup.bat +++ /dev/null @@ -1,3 +0,0 @@ -@echo off -python ./ds_hid.py -exit \ No newline at end of file diff --git a/src/main/deploy/choreo/A_LEFT_PATH1.traj b/src/main/deploy/choreo/A_LEFT_PATH1.traj deleted file mode 100644 index 9da2a0fb..00000000 --- a/src/main/deploy/choreo/A_LEFT_PATH1.traj +++ /dev/null @@ -1,64 +0,0 @@ -{ - "name":"A_LEFT_PATH1", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":7.163994312286377, "y":6.070901393890381, "heading":1.5707963267948966, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":5.37649393081665, "y":5.3462324142456055, "heading":1.102853734231975, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"7.163994312286377 m", "val":7.163994312286377}, "y":{"exp":"6.070901393890381 m", "val":6.070901393890381}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"5.37649393081665 m", "val":5.37649393081665}, "y":{"exp":"5.3462324142456055 m", "val":5.3462324142456055}, "heading":{"exp":"1.102853734231975 rad", "val":1.102853734231975}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.09622], - "samples":[ - {"t":0.0, "x":7.16399, "y":6.0709, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.96253, "ay":-2.41713, "alpha":-1.57186, "fx":[-103.44741,-105.08005,-100.10386,-97.0527], "fy":[-36.59042,-31.65986,-44.9953,-51.21333]}, - {"t":0.0378, "x":7.15973, "y":6.06917, "heading":1.5708, "vx":-0.22539, "vy":-0.09137, "omega":-0.05942, "ax":-5.96204, "ay":-2.41693, "alpha":-1.57115, "fx":[-103.43694,-105.07031,-100.09683,-97.04657], "fy":[-36.5893,-31.66144,-44.99032,-51.20434]}, - {"t":0.0756, "x":7.14696, "y":6.06399, "heading":1.56855, "vx":-0.45076, "vy":-0.18273, "omega":-0.11881, "ax":-5.96147, "ay":-2.4167, "alpha":-1.57023, "fx":[-103.4161,-105.06226,-100.09767,-97.03581], "fy":[-36.61233,-31.65217,-44.96442,-51.20078]}, - {"t":0.1134, "x":7.12566, "y":6.05536, "heading":1.56406, "vx":-0.6761, "vy":-0.27408, "omega":-0.17816, "ax":-5.9608, "ay":-2.41643, "alpha":-1.56905, "fx":[-103.38438,-105.05542,-100.10604,-97.02023], "fy":[-36.65947,-31.63227,-44.91736,-51.20207]}, - {"t":0.1512, "x":7.09584, "y":6.04327, "heading":1.55732, "vx":-0.90143, "vy":-0.36543, "omega":-0.23747, "ax":-5.95999, "ay":-2.4161, "alpha":-1.56757, "fx":[-103.34104,-105.04905,-100.12147,-96.99962], "fy":[-36.7307,-31.60212,-44.84883,-51.20732]}, - {"t":0.189, "x":7.05751, "y":6.02773, "heading":1.54835, "vx":-1.12672, "vy":-0.45676, "omega":-0.29673, "ax":-5.95901, "ay":-2.41571, "alpha":-1.56575, "fx":[-103.28503,-105.04212,-100.14328,-96.97368], "fy":[-36.82601,-31.56226,-44.75834,-51.21526]}, - {"t":0.2268, "x":7.01066, "y":6.00874, "heading":1.53713, "vx":-1.35197, "vy":-0.54807, "omega":-0.35592, "ax":-5.95778, "ay":-2.41521, "alpha":-1.56349, "fx":[-103.21477,-105.0331,-100.17045,-96.94189], "fy":[-36.94531,-31.51341,-44.6452,-51.22407]}, - {"t":0.2646, "x":6.9553, "y":5.9863, "heading":1.52368, "vx":-1.57718, "vy":-0.63937, "omega":-0.41502, "ax":-5.95619, "ay":-2.41457, "alpha":-1.5607, "fx":[-103.12789,-105.01966,-100.20134,-96.90331], "fy":[-37.08834,-31.4565,-44.50839,-51.23118]}, - {"t":0.3024, "x":6.89143, "y":5.96041, "heading":1.50799, "vx":-1.80233, "vy":-0.73064, "omega":-0.47401, "ax":-5.95407, "ay":-2.41371, "alpha":-1.55717, "fx":[-103.02053,-104.99803,-100.23324,-96.8561], "fy":[-37.25443,-31.39265,-44.34634,-51.23279]}, - {"t":0.34021, "x":6.81904, "y":5.93106, "heading":1.49007, "vx":-2.02739, "vy":-0.82188, "omega":-0.53287, "ax":-5.95109, "ay":-2.41251, "alpha":-1.55262, "fx":[-102.88598,-104.96167,-100.26119,-96.79652], "fy":[-37.44204,-31.32324,-44.15639,-51.22287]}, - {"t":0.37801, "x":6.73815, "y":5.89827, "heading":1.46993, "vx":-2.25235, "vy":-0.91307, "omega":-0.59156, "ax":-5.94661, "ay":-2.41071, "alpha":-1.54653, "fx":[-102.71116,-104.89787,-100.2753,-96.71635], "fy":[-37.64759,-31.24966,-43.93353,-51.19087]}, - {"t":0.41581, "x":6.64877, "y":5.86203, "heading":1.44757, "vx":-2.47713, "vy":-1.0042, "omega":-0.65002, "ax":-5.93912, "ay":-2.40768, "alpha":-1.53785, "fx":[-102.46609,-104.77785,-100.25236,-96.59485], "fy":[-37.86182,-31.17249,-43.66655,-51.11506]}, - {"t":0.45361, "x":6.55089, "y":5.82235, "heading":1.423, "vx":-2.70164, "vy":-1.09521, "omega":-0.70815, "ax":-5.92409, "ay":-2.4016, "alpha":-1.5242, "fx":[-102.06226,-104.51766,-100.12263,-96.36573], "fy":[-38.05524,-31.08586,-43.323,-50.93829]}, - {"t":0.49141, "x":6.44453, "y":5.77924, "heading":1.39623, "vx":-2.92557, "vy":-1.18599, "omega":-0.76577, "ax":-5.87887, "ay":-2.3833, "alpha":-1.49854, "fx":[-101.06441,-103.71112,-99.53707,-95.67875], "fy":[-38.07347,-30.9216,-42.74664,-50.41538]}, - {"t":0.52921, "x":6.32974, "y":5.73271, "heading":1.36728, "vx":-3.14779, "vy":-1.27608, "omega":-0.82242, "ax":-0.00047, "ay":-0.00284, "alpha":0.09473, "fx":[-0.29854,0.18311,0.28251,-0.19914], "fy":[-0.23942,-0.33881,0.14284,0.24223]}, - {"t":0.56701, "x":6.21075, "y":5.68447, "heading":1.33619, "vx":-3.14781, "vy":-1.27619, "omega":-0.81884, "ax":5.87886, "ay":2.38319, "alpha":1.50018, "fx":[100.8135,103.76144,99.76764,95.64862], "fy":[38.72431,30.72024,42.21021,50.49452]}, - {"t":0.60481, "x":6.09596, "y":5.63793, "heading":1.30524, "vx":-2.92559, "vy":-1.18611, "omega":-0.76213, "ax":5.9241, "ay":2.40161, "alpha":1.52277, "fx":[101.55613,104.61666,100.58388,96.31239], "fy":[39.37834,30.71842,42.24502,51.06115]}, - {"t":0.64261, "x":5.98961, "y":5.59481, "heading":1.27643, "vx":-2.70165, "vy":-1.09532, "omega":-0.70457, "ax":5.93914, "ay":2.40776, "alpha":1.53447, "fx":[101.7219,104.92371,100.92859,96.51842], "fy":[39.81075,30.64585,42.08369,51.28079]}, - {"t":0.68041, "x":5.89173, "y":5.55513, "heading":1.2498, "vx":-2.47715, "vy":-1.00431, "omega":-0.64656, "ax":5.94664, "ay":2.41083, "alpha":1.54162, "fx":[101.74752,105.08668,101.14926,96.61925], "fy":[40.17232,30.57746,41.88576,51.39479]}, - {"t":0.71821, "x":5.80234, "y":5.51888, "heading":1.22536, "vx":-2.25236, "vy":-0.91318, "omega":-0.58829, "ax":5.95113, "ay":2.41268, "alpha":1.54648, "fx":[101.72215,105.1891,101.31507,96.6815], "fy":[40.4909,30.52048,41.68496,51.45978]}, - {"t":0.75601, "x":5.72145, "y":5.48609, "heading":1.20312, "vx":-2.02741, "vy":-0.82198, "omega":-0.52983, "ax":5.95411, "ay":2.41392, "alpha":1.55002, "fx":[101.67607,105.25969,101.44898,96.72593], "fy":[40.77501,30.47464,41.49308,51.49747]}, - {"t":0.79381, "x":5.64906, "y":5.45674, "heading":1.18309, "vx":-1.80234, "vy":-0.73073, "omega":-0.47124, "ax":5.95623, "ay":2.4148, "alpha":1.55275, "fx":[101.62251,105.31113,101.56082,96.7607], "fy":[41.02805,30.43842,41.3154,51.51855]}, - {"t":0.83161, "x":5.58519, "y":5.43085, "heading":1.16528, "vx":-1.57719, "vy":-0.63945, "omega":-0.41254, "ax":5.95782, "ay":2.41547, "alpha":1.55492, "fx":[101.56824,105.35003,101.65554,96.78947], "fy":[41.2516,30.41023,41.15466,51.52921]}, - {"t":0.86941, "x":5.52983, "y":5.4084, "heading":1.14969, "vx":-1.35198, "vy":-0.54814, "omega":-0.35377, "ax":5.95905, "ay":2.41599, "alpha":1.55671, "fx":[101.51709,105.38025,101.73591,96.81396], "fy":[41.44654,30.38857,41.01243,51.53345]}, - {"t":0.90721, "x":5.48298, "y":5.38941, "heading":1.13631, "vx":-1.12672, "vy":-0.45682, "omega":-0.29492, "ax":5.96004, "ay":2.4164, "alpha":1.55821, "fx":[101.47143,105.40419,101.80361,96.83499], "fy":[41.61338,30.37214,40.88968,51.53402]}, - {"t":0.94501, "x":5.44465, "y":5.37386, "heading":1.12516, "vx":-0.90143, "vy":-0.36547, "omega":-0.23602, "ax":5.96084, "ay":2.41674, "alpha":1.55948, "fx":[101.43278,105.42349,101.85974,96.85297], "fy":[41.75249,30.35982,40.78704,51.53296]}, - {"t":0.98282, "x":5.41483, "y":5.36178, "heading":1.11624, "vx":-0.67611, "vy":-0.27412, "omega":-0.17707, "ax":5.96151, "ay":2.41702, "alpha":1.56057, "fx":[101.40219,105.43927,101.90505,96.86808], "fy":[41.86414,30.35069,40.70491,51.53178]}, - {"t":1.02062, "x":5.39353, "y":5.35314, "heading":1.10955, "vx":-0.45076, "vy":-0.18276, "omega":-0.11808, "ax":5.96208, "ay":2.41726, "alpha":1.56149, "fx":[101.38038,105.45236,101.94006,96.88039], "fy":[41.94853,30.34399,40.6436,51.5316]}, - {"t":1.05842, "x":5.38075, "y":5.34796, "heading":1.10509, "vx":-0.22539, "vy":-0.09138, "omega":-0.05906, "ax":5.96257, "ay":2.41746, "alpha":1.56228, "fx":[101.36786,105.46335,101.96516,96.88994], "fy":[42.00581,30.33915,40.6033,51.53327]}, - {"t":1.09622, "x":5.37649, "y":5.34623, "heading":1.10285, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/A_LEFT_PATH2.traj b/src/main/deploy/choreo/A_LEFT_PATH2.traj deleted file mode 100644 index bad1e596..00000000 --- a/src/main/deploy/choreo/A_LEFT_PATH2.traj +++ /dev/null @@ -1,178 +0,0 @@ -{ - "name":"A_LEFT_PATH2", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":5.005142688751221, "y":5.233847141265869, "heading":1.0513369818883893, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":4.582683086395264, "y":5.628561973571777, "heading":0.0, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":3.5206298828125, "y":5.799249172210693, "heading":0.0, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":1.924022912979126, "y":6.516302585601807, "heading":2.216612130911823, "intervals":15, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.3110252618789673, "y":7.185760498046875, "heading":2.216612130911823, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":3.2714266777038574, "y":5.901409149169922, "heading":0.0, "intervals":28, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":3.8275418281555176, "y":5.483885765075684, "heading":2.09887087685183, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":4.0}}, "enabled":true}, - {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"5.005142688751221 m", "val":5.005142688751221}, "y":{"exp":"5.233847141265869 m", "val":5.233847141265869}, "heading":{"exp":"1.0513369818883893 rad", "val":1.0513369818883893}, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"4.582683086395264 m", "val":4.582683086395264}, "y":{"exp":"5.628561973571777 m", "val":5.628561973571777}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"3.5206298828125 m", "val":3.5206298828125}, "y":{"exp":"5.799249172210693 m", "val":5.799249172210693}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"1.924022912979126 m", "val":1.924022912979126}, "y":{"exp":"6.516302585601807 m", "val":6.516302585601807}, "heading":{"exp":"2.216612130911823 rad", "val":2.216612130911823}, "intervals":15, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"7.185760498046875 m", "val":7.185760498046875}, "heading":{"exp":"2.216612130911823 rad", "val":2.216612130911823}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"3.2714266777038574 m", "val":3.2714266777038574}, "y":{"exp":"5.901409149169922 m", "val":5.901409149169922}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":28, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"3.8275418281555176 m", "val":3.8275418281555176}, "y":{"exp":"5.483885765075684 m", "val":5.483885765075684}, "heading":{"exp":"2.09887087685183 rad", "val":2.09887087685183}, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"4 m / s", "val":4.0}}}, "enabled":true}, - {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,0.44714,0.79227,1.25189,1.7841,2.65177,3.16594], - "samples":[ - {"t":0.0, "x":5.00514, "y":5.23385, "heading":1.05134, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-2.79278, "ay":5.56686, "alpha":5.4537, "fx":[-78.25422,-59.74256,-8.58369,-43.43733], "fy":[76.86009,91.8237,109.3264,100.75225]}, - {"t":0.02353, "x":5.00437, "y":5.23539, "heading":1.05134, "vx":-0.06572, "vy":0.13101, "omega":0.12835, "ax":-2.97957, "ay":5.45974, "alpha":5.55849, "fx":[-80.59071,-64.70136,-11.58782,-45.84632], "fy":[74.39401,88.37633,109.0342,99.66973]}, - {"t":0.04707, "x":5.002, "y":5.23998, "heading":1.05436, "vx":-0.13584, "vy":0.2595, "omega":0.25916, "ax":-3.18486, "ay":5.3321, "alpha":5.67263, "fx":[-83.10989,-69.89214,-15.08349,-48.60897], "fy":[71.55438,84.3049,108.58919,98.34136]}, - {"t":0.0706, "x":4.99792, "y":5.24757, "heading":1.06046, "vx":-0.2108, "vy":0.38498, "omega":0.39265, "ax":-3.41043, "ay":5.17919, "alpha":5.795, "fx":[-85.81152,-75.30109,-19.16419,-51.76485], "fy":[68.27464,79.48139,107.92484,96.7054]}, - {"t":0.09413, "x":4.99201, "y":5.25806, "heading":1.0697, "vx":-0.29105, "vy":0.50686, "omega":0.52903, "ax":-3.65776, "ay":4.99514, "alpha":5.92309, "fx":[-88.68635,-80.88279,-23.9442,-55.35657], "fy":[64.47737,73.76066,106.94425,94.68153]}, - {"t":0.11767, "x":4.98415, "y":5.27137, "heading":1.08215, "vx":-0.37714, "vy":0.62442, "omega":0.66842, "ax":-3.92782, "ay":4.77278, "alpha":6.05173, "fx":[-91.71173,-86.54492,-29.56006,-59.42751], "fy":[60.07423,66.99007,105.50505,92.16517]}, - {"t":0.1412, "x":4.97419, "y":5.28739, "heading":1.09788, "vx":-0.46957, "vy":0.73674, "omega":0.81084, "ax":-4.22056, "ay":4.50353, "alpha":6.17126, "fx":[-94.84559,-92.13207,-36.16742,-64.01698], "fy":[54.96751,59.02972,103.39737,89.02047]}, - {"t":0.16474, "x":4.96197, "y":5.30597, "heading":1.11696, "vx":-0.5689, "vy":0.84272, "omega":0.95607, "ax":-4.53434, "ay":4.17742, "alpha":6.26494, "fx":[-98.0191,-97.41468,-43.92656,-69.15122], "fy":[49.05466,49.78661,100.31325,85.07255]}, - {"t":0.18827, "x":4.94732, "y":5.32696, "heading":1.13946, "vx":-0.67561, "vy":0.94103, "omega":1.10351, "ax":-4.86506, "ay":3.78328, "alpha":6.30632, "fx":[-101.12841,-102.09326,-52.96378,-74.82756], "fy":[42.23761,39.26189,95.80992,80.10063]}, - {"t":0.2118, "x":4.93008, "y":5.35016, "heading":1.16543, "vx":-0.7901, "vy":1.03007, "omega":1.25192, "ax":-5.20488, "ay":3.30925, "alpha":6.25843, "fx":[-104.02774,-105.83019,-63.28714,-80.98871], "fy":[34.43877,27.60034,89.28185,73.83637]}, - {"t":0.23534, "x":4.91004, "y":5.37531, "heading":1.19489, "vx":-0.91259, "vy":1.10794, "omega":1.3992, "ax":-5.54038, "ay":2.74412, "alpha":6.07853, "fx":[-106.52731,-108.31391,-74.63474,-87.48502], "fy":[25.62487,15.11927,79.98657,65.97577]}, - {"t":0.25887, "x":4.88703, "y":5.40215, "heading":1.22782, "vx":-1.04297, "vy":1.17252, "omega":1.54225, "ax":-5.85024, "ay":2.08058, "alpha":5.73244, "fx":[-108.40218,-109.34148,-86.2719,-94.02802], "fy":[15.83678,2.28968,67.21494,56.21868]}, - {"t":0.2824, "x":4.86087, "y":5.43032, "heading":1.26411, "vx":-1.18065, "vy":1.22149, "omega":1.67716, "ax":-6.10433, "ay":1.32164, "alpha":5.21641, "fx":[-109.41734,-108.88441,-96.87868,-100.15151], "fy":[5.21794,-10.34077,50.69389,44.35182]}, - {"t":0.30594, "x":4.83139, "y":5.45943, "heading":1.30358, "vx":-1.32431, "vy":1.25259, "omega":1.79992, "ax":-6.26855, "ay":0.48867, "alpha":4.57046, "fx":[-109.37028,-107.10127,-104.81538,-105.21786], "fy":[-5.97184,-22.25903,31.10114,30.37847]}, - {"t":0.32947, "x":4.79849, "y":5.48904, "heading":1.34594, "vx":-1.47183, "vy":1.26409, "omega":1.90748, "ax":-6.31722, "ay":-0.37645, "alpha":3.86259, "fx":[-108.14172,-104.28866,-108.8675,-108.51823], "fy":[-17.37155,-33.08398,10.18632,14.65594]}, - {"t":0.353, "x":4.7621, "y":5.51869, "heading":1.39083, "vx":-1.62049, "vy":1.25523, "omega":1.99838, "ax":-6.24545, "ay":-1.22188, "alpha":3.15251, "fx":[-105.73534,-100.79814,-108.92086,-109.47894], "fy":[-28.56827,-42.6108,-9.90193,-2.05431]}, - {"t":0.37654, "x":4.72224, "y":5.54789, "heading":1.43786, "vx":-1.76747, "vy":1.22648, "omega":2.07257, "ax":-6.07018, "ay":-2.00278, "alpha":2.4727, "fx":[-102.28653,-96.95944,-105.87308,-107.88873], "fy":[-39.16756,-50.79818,-27.58205,-18.71897]}, - {"t":0.40007, "x":4.67896, "y":5.5762, "heading":1.48664, "vx":-1.91032, "vy":1.17934, "omega":2.13076, "ax":-5.82061, "ay":-2.6918, "alpha":1.83703, "fx":[-98.03406,-93.03488,-100.96617,-103.99229], "fy":[-48.85905,-57.72194,-42.2438,-34.32221]}, - {"t":0.4236, "x":4.63239, "y":5.60321, "heading":1.53678, "vx":-2.0473, "vy":1.116, "omega":2.17399, "ax":-5.52752, "ay":-3.27947, "alpha":1.25361, "fx":[-93.26743,-89.20633,-95.23662,-98.37582], "fy":[-57.45355,-63.52271,-54.01205,-48.14332]}, - {"t":0.44714, "x":4.58268, "y":5.62856, "heading":1.58794, "vx":-2.17739, "vy":1.03882, "omega":2.20349, "ax":-5.36296, "ay":-3.53055, "alpha":0.94655, "fx":[-90.5486,-87.3706,-92.16127,-94.80946], "fy":[-61.31709,-65.70383,-58.74218,-54.45181]}, - {"t":0.46214, "x":4.54941, "y":5.64375, "heading":1.62101, "vx":-2.25786, "vy":0.98584, "omega":2.2177, "ax":-5.36262, "ay":-3.53348, "alpha":0.68294, "fx":[-90.62064,-88.48202,-91.955,-93.80918], "fy":[-61.14368,-64.14865,-59.02542,-56.09605]}, - {"t":0.47715, "x":4.51492, "y":5.65815, "heading":1.65428, "vx":-2.33833, "vy":0.93282, "omega":2.22795, "ax":-5.36133, "ay":-3.53597, "alpha":0.38778, "fx":[-90.79089,-89.6716,-91.64556,-92.67071], "fy":[-60.813,-62.41887,-59.46255,-57.88919]}, - {"t":0.49215, "x":4.47923, "y":5.67175, "heading":1.68772, "vx":-2.41878, "vy":0.87976, "omega":2.23376, "ax":-5.35871, "ay":-3.53781, "alpha":0.05557, "fx":[-91.08245,-90.9368,-91.21881,-91.36249], "fy":[-60.28423,-60.49835,-60.06955,-59.85626]}, - {"t":0.50716, "x":4.44233, "y":5.68455, "heading":1.72123, "vx":-2.49919, "vy":0.82667, "omega":2.2346, "ax":-5.35426, "ay":-3.53864, "alpha":-0.32076, "fx":[-91.52446,-92.27333,-90.65768,-89.84193], "fy":[-59.50219,-58.36974,-60.86371,-62.02929]}, - {"t":0.52217, "x":4.40423, "y":5.69656, "heading":1.75477, "vx":-2.57953, "vy":0.77357, "omega":2.22978, "ax":-5.34725, "ay":-3.53795, "alpha":-0.75062, "fx":[-92.15391,-93.67484,-89.9414,-88.0504], "fy":[-58.39034,-56.01437,-61.86368,-64.44956]}, - {"t":0.53717, "x":4.36492, "y":5.70777, "heading":1.78823, "vx":-2.65977, "vy":0.72048, "omega":2.21852, "ax":-5.33666, "ay":-3.53491, "alpha":-1.24696, "fx":[-93.01791,-95.13257,-89.04461,-85.90534], "fy":[-56.83953,-53.41217,-63.08937,-67.1704]}, - {"t":0.55218, "x":4.32441, "y":5.71818, "heading":1.82152, "vx":-2.73985, "vy":0.66744, "omega":2.19981, "ax":-5.32101, "ay":-3.52817, "alpha":-1.82829, "fx":[-94.17605,-96.63495,-87.93647,-83.28792], "fy":[-54.68928,-50.54164,-64.56146,-70.2604]}, - {"t":0.56718, "x":4.28269, "y":5.7278, "heading":1.85452, "vx":-2.8197, "vy":0.6145, "omega":2.17238, "ax":-5.29803, "ay":-3.51537, "alpha":-2.52205, "fx":[-95.70132,-98.16702,-86.58,-80.02341], "fy":[-51.69578,-47.3799,-66.3001,-73.80585]}, - {"t":0.58219, "x":4.23979, "y":5.73662, "heading":1.88712, "vx":-2.8992, "vy":0.56175, "omega":2.13453, "ax":-5.26417, "ay":-3.49227, "alpha":-3.37011, "fx":[-97.67437,-99.70958,-84.93278,-75.85104], "fy":[-47.47647,-43.9035,-68.32153,-77.90858]}, - {"t":0.59719, "x":4.19569, "y":5.74466, "heading":1.91915, "vx":-2.97819, "vy":0.50934, "omega":2.08396, "ax":-5.2136, "ay":-3.45103, "alpha":-4.43742, "fx":[-100.15393,-101.23754,-82.95205,-70.38404], "fy":[-41.41683,-40.09119,-70.6296,-82.66652]}, - {"t":0.6122, "x":4.15041, "y":5.75191, "heading":1.95042, "vx":-3.05642, "vy":0.45756, "omega":2.01737, "ax":-5.13671, "ay":-3.377, "alpha":-5.82123, "fx":[-103.07072,-102.71622,-80.61587,-63.0931], "fy":[-32.54338,-35.93424,-73.19179,-88.09809]}, - {"t":0.6272, "x":4.10397, "y":5.7584, "heading":1.98069, "vx":-3.1335, "vy":0.40689, "omega":1.93002, "ax":-5.02004, "ay":-3.24518, "alpha":-7.63047, "fx":[-105.91373,-104.09099,-78.0092,-53.54402], "fy":[-19.57006,-31.47723,-75.85765,-93.89349]}, - {"t":0.64221, "x":4.05639, "y":5.76414, "heading":2.00966, "vx":-3.20883, "vy":0.35819, "omega":1.81552, "ax":-4.87024, "ay":-3.0321, "alpha":-9.73983, "fx":[-107.2513,-105.25361,-75.70044,-43.16052], "fy":[-2.56894,-26.98798,-78.02938,-98.71431]}, - {"t":0.65722, "x":4.00769, "y":5.76917, "heading":2.0369, "vx":-3.28191, "vy":0.31269, "omega":1.66937, "ax":-4.80404, "ay":-2.77599, "alpha":-11.15149, "fx":[-106.26924,-106.05664,-75.3508,-39.18457], "fy":[12.26122,-23.09113,-78.17166,-99.8739]}, - {"t":0.67222, "x":3.9579, "y":5.77355, "heading":2.06195, "vx":-3.354, "vy":0.27104, "omega":1.50204, "ax":-4.85187, "ay":-2.49774, "alpha":-11.71239, "fx":[-104.16834,-106.68953,-76.91794,-42.34021], "fy":[23.39531,-19.09808,-76.34583,-97.89477]}, - {"t":0.68723, "x":3.90703, "y":5.77734, "heading":2.08449, "vx":-3.4268, "vy":0.23356, "omega":1.32629, "ax":-4.93137, "ay":-2.15075, "alpha":-12.06277, "fx":[-100.65191,-107.29863,-79.4015,-48.17254], "fy":[34.95488,-13.84211,-73.362,-94.08518]}, - {"t":0.70223, "x":3.85505, "y":5.7806, "heading":2.10439, "vx":-3.5008, "vy":0.20128, "omega":1.14528, "ax":-5.00684, "ay":-1.6899, "alpha":-12.37017, "fx":[-94.59416,-107.74239,-82.60328,-55.72004], "fy":[48.54293,-6.52119,-69.16031,-87.84009]}, - {"t":0.71724, "x":3.80195, "y":5.78343, "heading":2.12157, "vx":-3.57593, "vy":0.17593, "omega":0.95966, "ax":-5.04595, "ay":-1.0446, "alpha":-12.59207, "fx":[-84.17092,-107.56515,-86.45634,-65.12841], "fy":[64.63674,3.81511,-63.38183,-76.14346]}, - {"t":0.73224, "x":3.74773, "y":5.78595, "heading":2.13598, "vx":-3.65165, "vy":0.16025, "omega":0.77071, "ax":-5.00386, "ay":0.17846, "alpha":-12.16723, "fx":[-67.40758,-105.7112,-90.87026,-76.4678], "fy":[81.88038,18.23806,-55.31922,-32.65721]}, - {"t":0.74725, "x":3.69237, "y":5.78838, "heading":2.14754, "vx":-3.72673, "vy":0.16293, "omega":0.58813, "ax":-4.44844, "ay":2.68505, "alpha":-11.48289, "fx":[-56.11801,-100.11359,-101.26348,-45.17163], "fy":[89.96162,37.12139,-27.66436,83.26908]}, - {"t":0.76225, "x":3.63595, "y":5.79112, "heading":2.15637, "vx":-3.79348, "vy":0.20322, "omega":0.41582, "ax":-3.61404, "ay":4.17631, "alpha":-9.77775, "fx":[-41.41106,-86.88839,-100.3131,-17.28261], "fy":[97.70893,61.26088,24.83415,100.34742]}, - {"t":0.77726, "x":3.57862, "y":5.79464, "heading":2.1626, "vx":-3.84771, "vy":0.26589, "omega":0.2691, "ax":-2.22155, "ay":5.46368, "alpha":-6.4529, "fx":[-23.11979,-64.34218,-66.47301,2.78301], "fy":[103.87203,84.45268,79.02834,104.38928]}, - {"t":0.79227, "x":3.52063, "y":5.79925, "heading":2.16664, "vx":-3.88105, "vy":0.34787, "omega":0.17227, "ax":-1.20433, "ay":5.95493, "alpha":-4.37991, "fx":[-11.85242,-44.75473,-35.36842,10.03436], "fy":[105.90392,96.29951,98.06687,104.89599]}, - {"t":0.80868, "x":3.45676, "y":5.80576, "heading":2.16947, "vx":-3.90082, "vy":0.44562, "omega":0.10038, "ax":-0.41358, "ay":6.09746, "alpha":-2.91966, "fx":[-2.73877,-25.70816,-13.29211,13.59958], "fy":[105.73199,102.11265,103.05165,103.96771]}, - {"t":0.8251, "x":3.39267, "y":5.8139, "heading":2.17112, "vx":-3.90761, "vy":0.54571, "omega":0.05245, "ax":0.3402, "ay":6.10513, "alpha":-1.48093, "fx":[7.05147,-4.31628,4.29614,16.11546], "fy":[104.52862,104.28172,103.59571,102.98016]}, - {"t":0.84151, "x":3.32857, "y":5.82368, "heading":2.17198, "vx":-3.90202, "vy":0.64593, "omega":0.02814, "ax":0.86101, "ay":6.02184, "alpha":-0.54742, "fx":[14.83478,10.89679,14.45347,18.39711], "fy":[102.65975,102.94669,102.25787,101.85465]}, - {"t":0.85793, "x":3.26464, "y":5.83509, "heading":2.17244, "vx":-3.88789, "vy":0.74478, "omega":0.01916, "ax":1.14666, "ay":5.92562, "alpha":-0.16621, "fx":[19.51131,18.3815,19.49853,20.62605], "fy":[100.87302,101.00712,100.718,100.57395]}, - {"t":0.87434, "x":3.20097, "y":5.84812, "heading":2.17276, "vx":-3.86907, "vy":0.84205, "omega":0.01643, "ax":1.32374, "ay":5.83293, "alpha":-0.05081, "fx":[22.50899,22.17846,22.52409,22.85425], "fy":[99.24558,99.29183,99.18773,99.14063]}, - {"t":0.89076, "x":3.13764, "y":5.86273, "heading":2.17303, "vx":-3.84734, "vy":0.9378, "omega":0.01559, "ax":1.464, "ay":5.73907, "alpha":-0.0197, "fx":[24.89652,24.77331,24.90802,25.03115], "fy":[97.63323,97.65195,97.6066,97.58776]}, - {"t":0.90717, "x":3.07468, "y":5.87889, "heading":2.17328, "vx":-3.82331, "vy":1.03201, "omega":0.01527, "ax":1.591, "ay":5.64302, "alpha":-0.01036, "fx":[27.05807,26.99574,27.06671,27.12901], "fy":[95.99426,96.00425,95.97798,95.96795]}, - {"t":0.92359, "x":3.01214, "y":5.89659, "heading":2.17353, "vx":-3.79719, "vy":1.12464, "omega":0.0151, "ax":1.71187, "ay":5.54772, "alpha":-0.00604, "fx":[29.1152,29.08024,29.12162,29.15658], "fy":[94.3706,94.37645,94.35978,94.35393]}, - {"t":0.94, "x":2.95003, "y":5.9158, "heading":2.17378, "vx":-3.76909, "vy":1.2157, "omega":0.015, "ax":1.83008, "ay":5.45821, "alpha":-0.00284, "fx":[31.12734,31.11152,31.13097,31.14679], "fy":[92.84544,92.84819,92.83975,92.837]}, - {"t":0.95642, "x":2.88841, "y":5.93649, "heading":2.17403, "vx":-3.73905, "vy":1.3053, "omega":0.01495, "ax":1.94882, "ay":5.38005, "alpha":0.00009, "fx":[33.14899,33.14949,33.14885,33.14835], "fy":[91.51296,91.51287,91.51317,91.51326]}, - {"t":0.97283, "x":2.8273, "y":5.95864, "heading":2.17427, "vx":-3.70706, "vy":1.39361, "omega":0.01496, "ax":2.07136, "ay":5.31767, "alpha":0.00297, "fx":[35.23576,35.25114,35.23064,35.21525], "fy":[90.44845,90.44546,90.45549,90.45848]}, - {"t":0.98925, "x":2.76672, "y":5.98224, "heading":2.17452, "vx":-3.67306, "vy":1.4809, "omega":0.015, "ax":2.20039, "ay":5.27276, "alpha":0.00596, "fx":[37.43391,37.4636,37.42224,37.39253], "fy":[89.68066,89.67439,89.6956,89.70186]}, - {"t":1.00566, "x":2.70673, "y":6.00726, "heading":2.17476, "vx":-3.63694, "vy":1.56746, "omega":0.0151, "ax":2.33746, "ay":5.2435, "alpha":0.00948, "fx":[39.77007,39.81554,39.74902,39.70351], "fy":[89.17797,89.16735,89.2029,89.21352]}, - {"t":1.02208, "x":2.64734, "y":6.03369, "heading":2.17501, "vx":-3.59857, "vy":1.65353, "omega":0.01526, "ax":2.4831, "ay":5.22487, "alpha":0.01581, "fx":[42.25656,42.32928,42.21704,42.1442], "fy":[88.85196,88.83294,88.89529,88.9143]}, - {"t":1.03849, "x":2.5886, "y":6.06154, "heading":2.17526, "vx":-3.55781, "vy":1.7393, "omega":0.01552, "ax":2.6395, "ay":5.20894, "alpha":0.03693, "fx":[44.94909,45.11093,44.84566,44.68312], "fy":[88.54985,88.50212,88.65547,88.70314]}, - {"t":1.05491, "x":2.53056, "y":6.09079, "heading":2.17552, "vx":-3.51448, "vy":1.8248, "omega":0.01612, "ax":2.82163, "ay":5.18022, "alpha":0.12986, "fx":[48.20162,48.73383,47.79315,47.25154], "fy":[87.91725,87.73847,88.31077,88.48952]}, - {"t":1.07132, "x":2.47325, "y":6.12145, "heading":2.17578, "vx":-3.46816, "vy":1.90984, "omega":0.01826, "ax":3.09263, "ay":5.0911, "alpha":0.51363, "fx":[53.57565,55.40197,51.7146,49.72667], "fy":[85.72087,84.99749,87.46626,88.20772]}, - {"t":1.08774, "x":2.41673, "y":6.15348, "heading":2.17608, "vx":-3.4174, "vy":1.99341, "omega":0.02669, "ax":3.59155, "ay":4.80276, "alpha":1.6836, "fx":[65.25085,69.0902,57.88024,52.14371], "fy":[77.82843,76.03048,85.23078,87.68462]}, - {"t":1.10415, "x":2.36112, "y":6.18685, "heading":2.17652, "vx":-3.35844, "vy":2.07225, "omega":0.05432, "ax":4.28537, "ay":4.16878, "alpha":3.75164, "fx":[84.29439,86.04152,65.78217,55.45368], "fy":[57.36535,58.86123,81.15517,86.25745]}, - {"t":1.12057, "x":2.30657, "y":6.22143, "heading":2.17741, "vx":-3.2881, "vy":2.14068, "omega":0.11591, "ax":4.8644, "ay":3.34972, "alpha":5.81584, "fx":[99.20585,97.11342,73.23858,61.41057], "fy":[27.7302,41.45003,76.05415,82.67662]}, - {"t":1.13698, "x":2.25325, "y":6.25702, "heading":2.17931, "vx":-3.20825, "vy":2.19566, "omega":0.21137, "ax":5.35167, "ay":2.54613, "alpha":6.24775, "fx":[104.39136,102.59341,81.7854,75.35128], "fy":[5.54571,28.54509,67.91148,71.23335]}, - {"t":1.1534, "x":2.20131, "y":6.2934, "heading":2.18278, "vx":-3.1204, "vy":2.23746, "omega":0.31393, "ax":5.98288, "ay":1.52462, "alpha":3.31317, "fx":[106.05177,105.32755,96.95917,98.73002], "fy":[3.42524,18.51879,44.52969,37.25993]}, - {"t":1.16981, "x":2.15089, "y":6.33034, "heading":2.18794, "vx":-3.02219, "vy":2.26248, "omega":0.36832, "ax":6.25649, "ay":0.66624, "alpha":0.84994, "fx":[106.93638,106.80412,105.78911,106.15494], "fy":[5.41207,9.79838,17.06394,13.0561]}, - {"t":1.18623, "x":2.10213, "y":6.36757, "heading":2.19398, "vx":-2.91949, "vy":2.27342, "omega":0.38227, "ax":6.32257, "ay":0.07036, "alpha":-0.82385, "fx":[107.43252,107.4846,107.51474,107.74837], "fy":[6.97806,2.27683,-4.69472,0.22726]}, - {"t":1.20264, "x":2.05505, "y":6.40489, "heading":2.20026, "vx":-2.8157, "vy":2.27458, "omega":0.36875, "ax":6.31232, "ay":-0.34268, "alpha":-1.96614, "fx":[107.74098,107.6452,106.11391,107.98262], "fy":[8.09036,-4.17875,-20.07477,-7.15265]}, - {"t":1.21906, "x":2.00968, "y":6.44219, "heading":2.20631, "vx":-2.71208, "vy":2.26895, "omega":0.33647, "ax":6.27757, "ay":-0.63833, "alpha":-2.76381, "fx":[107.94912,107.47375,103.81646,107.87911], "fy":[8.90169,-9.72216,-30.79778,-11.81291]}, - {"t":1.23547, "x":1.96601, "y":6.47935, "heading":2.21183, "vx":-2.60904, "vy":2.25847, "omega":0.2911, "ax":6.23718, "ay":-0.85822, "alpha":-3.34173, "fx":[108.0984,107.09682,101.47635,107.69901], "fy":[9.51456,-14.49319,-38.43672,-14.97719]}, - {"t":1.25189, "x":1.92402, "y":6.5163, "heading":2.21661, "vx":-2.50665, "vy":2.24439, "omega":0.23625, "ax":6.17118, "ay":-1.60969, "alpha":-2.5856, "fx":[108.96042,104.95663,99.65311,106.30974], "fy":[-8.67121,-30.11529,-44.96083,-25.77389]}, - {"t":1.28737, "x":1.83897, "y":6.59492, "heading":2.22499, "vx":-2.28769, "vy":2.18727, "omega":0.14451, "ax":5.85735, "ay":-2.59068, "alpha":-1.92085, "fx":[104.8469,98.08117,94.12965,101.46976], "fy":[-31.16848,-48.30297,-55.77777,-41.01736]}, - {"t":1.32285, "x":1.76149, "y":6.6709, "heading":2.23012, "vx":-2.07987, "vy":2.09535, "omega":0.07636, "ax":5.53561, "ay":-3.25428, "alpha":-1.40081, "fx":[98.91123,92.02458,89.47725,96.22344], "fy":[-46.86442,-59.21224,-63.08598,-52.25512]}, - {"t":1.35833, "x":1.69118, "y":6.74319, "heading":2.23283, "vx":-1.88346, "vy":1.97989, "omega":0.02665, "ax":5.25086, "ay":-3.71369, "alpha":-1.00404, "fx":[93.0908,87.22297,85.66627,91.28252], "fy":[-57.67538,-66.19789,-68.25202,-60.55024]}, - {"t":1.39381, "x":1.62765, "y":6.81111, "heading":2.23378, "vx":-1.69715, "vy":1.84812, "omega":-0.00897, "ax":5.01014, "ay":-4.04253, "alpha":-0.6999, "fx":[87.98783,83.46284,82.54776,86.88564], "fy":[-65.27307,-70.95992,-72.05217,-66.76392]}, - {"t":1.42929, "x":1.57059, "y":6.87413, "heading":2.23346, "vx":-1.51939, "vy":1.70469, "omega":-0.0338, "ax":4.80894, "ay":-4.2859, "alpha":-0.46264, "fx":[83.67309,80.48482,79.97574,83.06137], "fy":[-70.7763,-74.37864,-74.94253,-71.51038]}, - {"t":1.46477, "x":1.51971, "y":6.93192, "heading":2.23226, "vx":-1.34876, "vy":1.55262, "omega":-0.05022, "ax":4.64048, "ay":-4.47153, "alpha":-0.27378, "fx":[80.0552,78.08586,77.83192,79.75988], "fy":[-74.88727,-76.93724,-77.20277,-75.2105]}, - {"t":1.50026, "x":1.47477, "y":6.98419, "heading":2.23048, "vx":-1.18412, "vy":1.39397, "omega":-0.05993, "ax":4.49843, "ay":-4.61686, "alpha":-0.12052, "fx":[77.0132,76.11978,76.02529,76.90991], "fy":[-78.04602,-78.91725,-79.01165,-78.1512]}, - {"t":1.53574, "x":1.43559, "y":7.03075, "heading":2.22835, "vx":-1.02451, "vy":1.23016, "omega":-0.06421, "ax":4.37761, "ay":-4.73323, "alpha":0.00602, "fx":[74.43706,74.4827,74.4867,74.44103], "fy":[-80.53386,-80.49166,-80.48781,-80.53003]}, - {"t":1.57122, "x":1.402, "y":7.07141, "heading":2.22607, "vx":-0.86919, "vy":1.06222, "omega":-0.06399, "ax":4.2739, "ay":-4.8282, "alpha":0.11209, "fx":[72.23648,73.10024,73.16348,72.29116], "fy":[-82.5356,-81.77174,-81.71263,-82.48519]}, - {"t":1.6067, "x":1.37385, "y":7.10606, "heading":2.2238, "vx":-0.71754, "vy":0.89091, "omega":-0.06002, "ax":4.1841, "ay":-4.907, "alpha":0.20218, "fx":[70.34006,71.91833,72.01513,70.40798], "fy":[-84.17608,-82.83192,-82.74359,-84.11515]}, - {"t":1.64218, "x":1.35102, "y":7.13459, "heading":2.22167, "vx":-0.56909, "vy":0.7168, "omega":-0.05284, "ax":4.1057, "ay":-4.97332, "alpha":0.27958, "fx":[68.69196,70.89701,71.01018,68.74827], "fy":[-85.54188,-83.72363,-83.62233,-85.4914]}, - {"t":1.67766, "x":1.33341, "y":7.15689, "heading":2.2198, "vx":-0.42341, "vy":0.54035, "omega":-0.04292, "ax":4.03674, "ay":-5.02984, "alpha":0.34675, "fx":[67.24849,70.00623,70.12392,67.27661], "fy":[-86.69455,-84.48348,-84.3797,-86.66675]}, - {"t":1.71314, "x":1.32093, "y":7.17289, "heading":2.21827, "vx":-0.28019, "vy":0.36188, "omega":-0.03062, "ax":3.97565, "ay":-5.07852, "alpha":0.40557, "fx":[65.97531,69.22308,69.33665,65.96398], "fy":[-87.67882,-85.13813,-85.039,-87.68087]}, - {"t":1.74862, "x":1.31349, "y":7.18254, "heading":2.21719, "vx":-0.13913, "vy":0.18169, "omega":-0.01623, "ax":3.9212, "ay":-5.12086, "alpha":0.45748, "fx":[64.84527,68.52978,68.63257,64.78652], "fy":[-88.52788,-85.70747,-85.61815,-88.56407]}, - {"t":1.7841, "x":1.31103, "y":7.18576, "heading":2.21661, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.34243, "ay":-3.61297, "alpha":-0.38522, "fx":[92.2991,90.1677,89.46096,91.56494], "fy":[-59.32323,-62.51219,-63.52794,-60.45882]}, - {"t":1.81624, "x":1.31378, "y":7.18389, "heading":2.21661, "vx":0.17168, "vy":-0.11611, "omega":-0.01238, "ax":5.34207, "ay":-3.61273, "alpha":-0.38007, "fx":[92.27367,90.17101,89.47378,91.54974], "fy":[-59.34811,-62.49336,-63.49642,-60.4678]}, - {"t":1.84837, "x":1.32206, "y":7.1783, "heading":2.21621, "vx":0.34335, "vy":-0.2322, "omega":-0.02459, "ax":5.34166, "ay":-3.61245, "alpha":-0.37431, "fx":[92.24547,90.17527,89.48782,91.5322], "fy":[-59.37555,-62.47149,-63.46154,-60.47866]}, - {"t":1.88051, "x":1.33585, "y":7.16897, "heading":2.21542, "vx":0.51501, "vy":-0.34829, "omega":-0.03662, "ax":5.34121, "ay":-3.61215, "alpha":-0.36781, "fx":[92.21391,90.18052,89.50339,91.51199], "fy":[-59.4061,-62.44622,-63.42256,-60.49155]}, - {"t":1.91265, "x":1.35516, "y":7.15591, "heading":2.21425, "vx":0.68666, "vy":-0.46437, "omega":-0.04844, "ax":5.34069, "ay":-3.6118, "alpha":-0.36045, "fx":[92.17825,90.18681,89.52088,91.48871], "fy":[-59.44052,-62.41707,-63.37853,-60.50665]}, - {"t":1.94478, "x":1.37998, "y":7.13913, "heading":2.21269, "vx":0.85828, "vy":-0.58044, "omega":-0.06002, "ax":5.3401, "ay":-3.6114, "alpha":-0.35202, "fx":[92.13753,90.19418,89.54078,91.46186], "fy":[-59.47973,-62.38344,-63.32825,-60.52423]}, - {"t":1.97692, "x":1.41032, "y":7.11861, "heading":2.21076, "vx":1.02989, "vy":-0.69649, "omega":-0.07134, "ax":5.33942, "ay":-3.61094, "alpha":-0.34227, "fx":[92.09048,90.20272,89.56375,91.43074], "fy":[-59.52497,-62.34456,-63.27012,-60.54462]}, - {"t":2.00905, "x":1.44618, "y":7.09436, "heading":2.20847, "vx":1.20148, "vy":-0.81253, "omega":-0.08234, "ax":5.33861, "ay":-3.6104, "alpha":-0.33088, "fx":[92.03543,90.21254,89.59063,91.39444], "fy":[-59.57787,-62.29935,-63.20201,-60.56828]}, - {"t":2.04119, "x":1.48754, "y":7.06639, "heading":2.20582, "vx":1.37304, "vy":-0.92856, "omega":-0.09297, "ax":5.33766, "ay":-3.60976, "alpha":-0.31739, "fx":[91.97008,90.22378,89.6226,91.35169], "fy":[-59.64064,-62.24638,-63.12102,-60.59583]}, - {"t":2.07332, "x":1.53442, "y":7.03468, "heading":2.20284, "vx":1.54457, "vy":-1.04456, "omega":-0.10317, "ax":5.33651, "ay":-3.60899, "alpha":-0.30117, "fx":[91.89121,90.23666,89.66129,91.30071], "fy":[-59.71639,-62.1836,-63.02305,-60.62817]}, - {"t":2.10546, "x":1.58681, "y":6.99925, "heading":2.19952, "vx":1.71606, "vy":-1.16054, "omega":-0.11285, "ax":5.33509, "ay":-3.60803, "alpha":-0.28129, "fx":[91.79417,90.25147,89.70905,91.23889], "fy":[-59.80959,-62.10808,-62.90218,-60.66658]}, - {"t":2.1376, "x":1.64472, "y":6.96009, "heading":2.19589, "vx":1.88751, "vy":-1.27648, "omega":-0.12189, "ax":5.33331, "ay":-3.60683, "alpha":-0.25635, "fx":[91.67192,90.26867,89.76939,91.16227], "fy":[-59.92693,-62.01539,-62.74946,-60.71304]}, - {"t":2.16973, "x":1.70813, "y":6.91721, "heading":2.19198, "vx":2.0589, "vy":-1.39239, "omega":-0.13012, "ax":5.33099, "ay":-3.60528, "alpha":-0.22416, "fx":[91.51337,90.28896,89.84782,91.06455], "fy":[-60.07888,-61.89856,-62.55073,-60.77068]}, - {"t":2.20187, "x":1.77704, "y":6.8706, "heading":2.18779, "vx":2.23021, "vy":-1.50825, "omega":-0.13733, "ax":5.32787, "ay":-3.60317, "alpha":-0.18103, "fx":[91.29992,90.31351,89.95346,90.93503], "fy":[-60.28287,-61.74593,-62.28213,-60.84479]}, - {"t":2.234, "x":1.85146, "y":6.82027, "heading":2.18338, "vx":2.40143, "vy":-1.62404, "omega":-0.14315, "ax":5.32341, "ay":-3.60018, "alpha":-0.12027, "fx":[90.9978,90.34433,90.10263,90.75406], "fy":[-60.57008,-61.53655,-61.9002,-60.94501]}, - {"t":2.26614, "x":1.93138, "y":6.76622, "heading":2.17878, "vx":2.5725, "vy":-1.73973, "omega":-0.14701, "ax":5.31656, "ay":-3.59557, "alpha":-0.02836, "fx":[90.53876,90.38523,90.32772,90.48114], "fy":[-61.00246,-61.22853,-61.31641,-61.09097]}, - {"t":2.29827, "x":2.0168, "y":6.70846, "heading":2.17406, "vx":2.74335, "vy":-1.85528, "omega":-0.14792, "ax":5.3047, "ay":-3.58759, "alpha":0.12675, "fx":[89.7611,90.4442,90.70297,90.01778], "fy":[-61.72279,-60.72455,-60.31882,-61.32939]}, - {"t":2.33041, "x":2.1077, "y":6.64699, "heading":2.1693, "vx":2.91382, "vy":-1.97057, "omega":-0.14385, "ax":5.27932, "ay":-3.57051, "alpha":0.44326, "fx":[88.16901,90.53995,91.4429,89.04726], "fy":[-63.14807,-59.73655,-58.24457,-61.80441]}, - {"t":2.36255, "x":2.20406, "y":6.58182, "heading":2.16468, "vx":3.08348, "vy":-2.08531, "omega":-0.1296, "ax":5.18967, "ay":-3.51033, "alpha":1.43291, "fx":[83.20249,90.7023,93.47546,85.71878], "fy":[-67.18705,-56.8918,-51.49326,-63.267]}, - {"t":2.39468, "x":2.30583, "y":6.51299, "heading":2.16052, "vx":3.25025, "vy":-2.19812, "omega":-0.08356, "ax":1.12774, "ay":-0.76152, "alpha":2.58407, "fx":[17.14469,28.10464,21.53906,9.94189], "fy":[-22.43482,-14.4915,-3.37613,-11.51073]}, - {"t":2.42682, "x":2.41086, "y":6.44196, "heading":2.15783, "vx":3.28649, "vy":-2.22259, "omega":-0.00052, "ax":0.0017, "ay":-0.00075, "alpha":0.00231, "fx":[0.02724,0.03724,0.03058,0.02058], "fy":[-0.02106,-0.01441,-0.0044,-0.01106]}, - {"t":2.45895, "x":2.51648, "y":6.37054, "heading":2.15781, "vx":3.28655, "vy":-2.22262, "omega":-0.00044, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[-0.00001,-0.00001,-0.00001,-0.00001], "fy":[-0.00001,-0.00001,-0.00001,-0.00001]}, - {"t":2.49109, "x":2.62209, "y":6.29911, "heading":2.1578, "vx":3.28655, "vy":-2.22262, "omega":-0.00044, "ax":-0.0017, "ay":0.00075, "alpha":-0.00232, "fx":[-0.02726,-0.03727,-0.03061,-0.0206], "fy":[0.02104,0.01438,0.00437,0.01103]}, - {"t":2.52322, "x":2.72771, "y":6.22769, "heading":2.15779, "vx":3.28649, "vy":-2.22259, "omega":-0.00052, "ax":-1.12791, "ay":0.76163, "alpha":-2.5856, "fx":[-17.12173,-28.10651,-21.56839,-9.94517], "fy":[22.43906,14.51938,3.37727,11.4849]}, - {"t":2.55536, "x":2.83274, "y":6.15665, "heading":2.15777, "vx":3.25024, "vy":-2.19812, "omega":-0.08361, "ax":-5.18956, "ay":3.51026, "alpha":-1.43797, "fx":[-83.1613,-90.67738,-93.50502,-85.74783], "fy":[67.23552,56.93346,51.44214,63.22322]}, - {"t":2.5875, "x":2.93451, "y":6.08783, "heading":2.15508, "vx":3.08347, "vy":-2.08531, "omega":-0.12982, "ax":-5.27931, "ay":3.5705, "alpha":-0.44505, "fx":[-88.15078,-90.52012,-91.45891,-89.06832], "fy":[63.17256,59.76709,58.22019,61.77315]}, - {"t":2.61963, "x":3.03087, "y":6.02266, "heading":2.15091, "vx":2.91382, "vy":-1.97057, "omega":-0.14412, "ax":-5.3047, "ay":3.58759, "alpha":-0.12749, "fx":[-89.75332,-90.43449,-90.7104,-90.02761], "fy":[61.73377,60.73914,60.30785,61.31468]}, - {"t":2.65177, "x":3.12177, "y":5.96119, "heading":2.14628, "vx":2.74335, "vy":-1.85528, "omega":-0.14822, "ax":-5.31656, "ay":3.59557, "alpha":0.02812, "fx":[-90.53935,-90.38905,-90.32707,-90.4773], "fy":[61.00163,61.22285,61.31724,61.09662]}, - {"t":2.6839, "x":3.20718, "y":5.90342, "heading":2.14152, "vx":2.5725, "vy":-1.73973, "omega":-0.14731, "ax":-5.32341, "ay":3.60018, "alpha":0.12034, "fx":[-91.00601,-90.36333,-90.09399,-90.73543], "fy":[60.55803,61.50849,61.91245,60.97285]}, - {"t":2.71604, "x":3.2871, "y":5.84937, "heading":2.13678, "vx":2.40143, "vy":-1.62404, "omega":-0.14344, "ax":-5.32787, "ay":3.60317, "alpha":0.18129, "fx":[-91.3153,-90.34839,-89.93692,-90.90122], "fy":[60.26001,61.69466,62.30555,60.89547]}, - {"t":2.74817, "x":3.36152, "y":5.79904, "heading":2.13217, "vx":2.23021, "vy":-1.50825, "omega":-0.13762, "ax":-5.33099, "ay":3.60528, "alpha":0.22456, "fx":[-91.53555,-90.33982,-89.82359,-91.01564], "fy":[60.04565,61.82403,62.58497,60.84415]}, - {"t":2.78031, "x":3.43044, "y":5.75244, "heading":2.12775, "vx":2.0589, "vy":-1.39239, "omega":-0.1304, "ax":-5.33331, "ay":3.60683, "alpha":0.25684, "fx":[-91.70052,-90.33523,-89.73775,-91.09863], "fy":[59.88381,61.91809,62.79409,60.80876]}, - {"t":2.81245, "x":3.49385, "y":5.70955, "heading":2.12356, "vx":1.88751, "vy":-1.27648, "omega":-0.12215, "ax":-5.33509, "ay":3.60803, "alpha":0.28185, "fx":[-91.8288,-90.33317,-89.67034,-91.16112], "fy":[59.75713,61.98885,62.95669,60.78368]}, - {"t":2.84458, "x":3.55175, "y":5.6704, "heading":2.11963, "vx":1.71606, "vy":-1.16054, "omega":-0.11309, "ax":-5.33651, "ay":3.60898, "alpha":0.30179, "fx":[-91.93146,-90.33277,-89.61592,-91.20955], "fy":[59.65518,62.04355,63.08685,60.76553]}, - {"t":2.87672, "x":3.60414, "y":5.63496, "heading":2.116, "vx":1.54457, "vy":-1.04456, "omega":-0.10339, "ax":-5.33766, "ay":3.60976, "alpha":0.31806, "fx":[-92.01551,-90.33341,-89.57103,-91.24802], "fy":[59.57132,62.08682,63.19345,60.75216]}, - {"t":2.90885, "x":3.65102, "y":5.60326, "heading":2.11268, "vx":1.37304, "vy":-0.92856, "omega":-0.09317, "ax":-5.33861, "ay":3.6104, "alpha":0.33159, "fx":[-92.08559,-90.33468,-89.53335,-91.27921], "fy":[59.50111,62.12175,63.28239,60.74212]}, - {"t":2.94099, "x":3.69239, "y":5.57529, "heading":2.10968, "vx":1.20148, "vy":-0.81253, "omega":-0.08252, "ax":-5.33941, "ay":3.61094, "alpha":0.34301, "fx":[-92.14491,-90.33628,-89.50128,-91.305], "fy":[59.4415,62.15051,63.35771,60.73441]}, - {"t":2.97313, "x":3.72824, "y":5.55104, "heading":2.10703, "vx":1.02989, "vy":-0.69649, "omega":-0.07149, "ax":-5.3401, "ay":3.6114, "alpha":0.35278, "fx":[-92.19575,-90.33798,-89.47369,-91.3267], "fy":[59.39027,62.17465,63.42228,60.72831]}, - {"t":3.00526, "x":3.75858, "y":5.53052, "heading":2.10473, "vx":0.85828, "vy":-0.58044, "omega":-0.06016, "ax":-5.34069, "ay":3.6118, "alpha":0.36123, "fx":[-92.23977,-90.33963,-89.44972,-91.34529], "fy":[59.34583,62.19531,63.4782,60.72327]}, - {"t":3.0374, "x":3.78341, "y":5.51373, "heading":2.1028, "vx":0.68666, "vy":-0.46437, "omega":-0.04855, "ax":-5.34121, "ay":3.61215, "alpha":0.36862, "fx":[-92.27822,-90.34109,-89.42875,-91.3615], "fy":[59.30697,62.21335,63.52704,60.7189]}, - {"t":3.06953, "x":3.80272, "y":5.50068, "heading":2.10124, "vx":0.51501, "vy":-0.34829, "omega":-0.0367, "ax":-5.34166, "ay":3.61245, "alpha":0.37512, "fx":[-92.31205,-90.34225,-89.41031,-91.37588], "fy":[59.27276,62.22944,63.57,60.71488]}, - {"t":3.10167, "x":3.81651, "y":5.49135, "heading":2.10006, "vx":0.34335, "vy":-0.2322, "omega":-0.02465, "ax":-5.34206, "ay":3.61272, "alpha":0.3809, "fx":[-92.34201,-90.34303,-89.39402,-91.38887], "fy":[59.24249,62.24408,63.60798,60.71097]}, - {"t":3.1338, "x":3.82478, "y":5.48575, "heading":2.09927, "vx":0.17168, "vy":-0.11611, "omega":-0.01241, "ax":-5.34242, "ay":3.61296, "alpha":0.38607, "fx":[-92.36867,-90.34337,-89.37958,-91.4008], "fy":[59.21559,62.25771,63.64174,60.70696]}, - {"t":3.16594, "x":3.82754, "y":5.48389, "heading":2.09887, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[ - {"name":"Funnel", "from":{"target":5, "targetTimestamp":2.65177, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] -} diff --git a/src/main/deploy/choreo/A_LEFT_PATH3.traj b/src/main/deploy/choreo/A_LEFT_PATH3.traj deleted file mode 100644 index 21bfb17a..00000000 --- a/src/main/deploy/choreo/A_LEFT_PATH3.traj +++ /dev/null @@ -1,119 +0,0 @@ -{ - "name":"A_LEFT_PATH3", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":3.999176502227783, "y":5.206205368041992, "heading":2.1010083691287966, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.3110252618789673, "y":7.185760498046875, "heading":2.2024870470289093, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.4608945846557617, "y":6.165796279907227, "heading":0.0, "intervals":33, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":3.410642147064209, "y":5.334875106811523, "heading":2.077894951837786, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"3.999176502227783 m", "val":3.999176502227783}, "y":{"exp":"5.206205368041992 m", "val":5.206205368041992}, "heading":{"exp":"2.1010083691287966 rad", "val":2.1010083691287966}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"7.185760498046875 m", "val":7.185760498046875}, "heading":{"exp":"2.2024870470289093 rad", "val":2.2024870470289093}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.4608945846557617 m", "val":2.4608945846557617}, "y":{"exp":"6.165796279907227 m", "val":6.165796279907227}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":33, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"3.410642147064209 m", "val":3.410642147064209}, "y":{"exp":"5.334875106811523 m", "val":5.334875106811523}, "heading":{"exp":"2.077894951837786 rad", "val":2.077894951837786}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.45692,2.14786,2.77872], - "samples":[ - {"t":0.0, "x":3.99918, "y":5.20621, "heading":2.10101, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.19517, "ay":3.82571, "alpha":0.34139, "fx":[-89.74956,-87.81273,-86.99375,-88.91725], "fy":[63.17899,65.84215,66.92562,64.3502]}, - {"t":0.04415, "x":3.99411, "y":5.20993, "heading":2.10101, "vx":-0.22936, "vy":0.1689, "omega":0.01507, "ax":-5.19479, "ay":3.82543, "alpha":0.33555, "fx":[-89.71932,-87.81583,-87.01099,-88.90161], "fy":[63.2072,65.82375,66.88948,64.35768]}, - {"t":0.0883, "x":3.97892, "y":5.22112, "heading":2.10167, "vx":-0.45871, "vy":0.33779, "omega":0.02989, "ax":-5.19435, "ay":3.82511, "alpha":0.32866, "fx":[-89.68341,-87.81856,-87.03165,-88.88404], "fy":[63.24085,65.80332,66.84643,64.3653]}, - {"t":0.13245, "x":3.95361, "y":5.23976, "heading":2.10299, "vx":-0.68803, "vy":0.50666, "omega":0.0444, "ax":-5.19382, "ay":3.82472, "alpha":0.32045, "fx":[-89.64027,-87.82116,-87.05657,-88.86365], "fy":[63.28131,65.77981,66.79464,64.37356]}, - {"t":0.1766, "x":3.91817, "y":5.26586, "heading":2.10495, "vx":-0.91733, "vy":0.67552, "omega":0.05854, "ax":-5.19318, "ay":3.82424, "alpha":0.31046, "fx":[-89.58773,-87.82397,-87.08696,-88.83917], "fy":[63.3306,65.75173,66.73149,64.38315]}, - {"t":0.22074, "x":3.87261, "y":5.29941, "heading":2.10754, "vx":-1.14661, "vy":0.84436, "omega":0.07225, "ax":-5.19238, "ay":3.82365, "alpha":0.29807, "fx":[-89.52252,-87.82747,-87.12461,-88.8087], "fy":[63.39167,65.71687,66.65308,64.3951]}, - {"t":0.26489, "x":3.81693, "y":5.34041, "heading":2.11073, "vx":-1.37584, "vy":1.01317, "omega":0.08541, "ax":-5.19135, "ay":3.82289, "alpha":0.28229, "fx":[-89.43962,-87.8324,-87.1723,-88.76932], "fy":[63.46906,65.67187,66.55336,64.411]}, - {"t":0.30904, "x":3.75113, "y":5.38887, "heading":2.1145, "vx":-1.60504, "vy":1.18195, "omega":0.09787, "ax":-5.19, "ay":3.82189, "alpha":0.26151, "fx":[-89.33078,-87.83993,-87.23451,-88.71626], "fy":[63.57019,65.61126,66.42243,64.43339]}, - {"t":0.35319, "x":3.67521, "y":5.44477, "heading":2.11882, "vx":-1.83417, "vy":1.35068, "omega":0.10942, "ax":-5.18812, "ay":3.82051, "alpha":0.23289, "fx":[-89.18161,-87.85204,-87.31912,-88.64114], "fy":[63.70797,65.52553,66.24289,64.46672]}, - {"t":0.39734, "x":3.58918, "y":5.50813, "heading":2.12365, "vx":-2.06322, "vy":1.51935, "omega":0.1197, "ax":-5.18536, "ay":3.81847, "alpha":0.191, "fx":[-88.9643,-87.87246,-87.4412,-88.52772], "fy":[63.90708,65.39654,65.98105,64.51951]}, - {"t":0.44149, "x":3.49304, "y":5.57893, "heading":2.12893, "vx":-2.29215, "vy":1.68793, "omega":0.12813, "ax":-5.18087, "ay":3.81515, "alpha":0.12383, "fx":[-88.61758,-87.90905,-87.63367,-88.33985], "fy":[64.22132,65.18476,65.56213,64.61046]}, - {"t":0.48564, "x":3.38679, "y":5.65716, "heading":2.13459, "vx":-2.52088, "vy":1.85637, "omega":0.1336, "ax":-5.17232, "ay":3.80885, "alpha":-0.00133, "fx":[-87.97443,-87.98205,-87.98496,-87.97734], "fy":[64.79459,64.78428,64.78021,64.79052]}, - {"t":0.52979, "x":3.27046, "y":5.74283, "heading":2.14049, "vx":-2.74923, "vy":2.02452, "omega":0.13354, "ax":-5.14981, "ay":3.79224, "alpha":-0.31664, "fx":[-86.36185,-88.16478,-88.84034,-87.02035], "fy":[66.18458,63.78172,62.78691,65.26626]}, - {"t":0.57394, "x":3.14406, "y":5.83591, "heading":2.14639, "vx":-2.97659, "vy":2.19195, "omega":0.11956, "ax":-4.9428, "ay":3.64167, "alpha":-2.67463, "fx":[-74.77678,-89.08997,-94.03118,-78.40447], "fy":[74.64333,57.31767,46.77811,69.03584]}, - {"t":0.61809, "x":3.00783, "y":5.93623, "heading":2.15166, "vx":-3.19481, "vy":2.35272, "omega":0.00148, "ax":-0.02822, "ay":0.0196, "alpha":-0.02775, "fx":[-0.45929,-0.57972,-0.50076,-0.38029], "fy":[0.43318,0.35404,0.23364,0.31275]}, - {"t":0.66223, "x":2.86676, "y":6.04012, "heading":2.15173, "vx":-3.19606, "vy":2.35359, "omega":0.00025, "ax":-0.00012, "ay":-0.00015, "alpha":-0.00001, "fx":[-0.00211,-0.00214,-0.00212,-0.00209], "fy":[-0.00254,-0.00256,-0.00258,-0.00257]}, - {"t":0.70638, "x":2.72565, "y":6.14403, "heading":2.15174, "vx":-3.19606, "vy":2.35358, "omega":0.00025, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, - {"t":0.75053, "x":2.58455, "y":6.24794, "heading":2.15175, "vx":-3.19606, "vy":2.35358, "omega":0.00025, "ax":0.00012, "ay":0.00015, "alpha":0.00001, "fx":[0.0021,0.00213,0.00211,0.00208], "fy":[0.00252,0.00254,0.00257,0.00255]}, - {"t":0.79468, "x":2.44345, "y":6.35185, "heading":2.15176, "vx":-3.19606, "vy":2.35359, "omega":0.00025, "ax":0.02821, "ay":-0.0196, "alpha":0.02773, "fx":[0.45922,0.57957,0.50065,0.38024], "fy":[-0.43316,-0.35404,-0.23372,-0.3128]}, - {"t":0.83883, "x":2.30237, "y":6.45573, "heading":2.15177, "vx":-3.19481, "vy":2.35272, "omega":0.00148, "ax":4.9428, "ay":-3.64166, "alpha":2.67446, "fx":[74.81883,89.13137,94.01125,78.34131], "fy":[-74.60493,-57.25032,-46.80727,-69.1121]}, - {"t":0.88298, "x":2.16614, "y":6.55606, "heading":2.15184, "vx":-2.97659, "vy":2.19195, "omega":0.11955, "ax":5.14981, "ay":-3.79224, "alpha":0.3164, "fx":[86.36971,88.17801,88.83321,87.00638], "fy":[-66.17466,-63.76322,-62.79656,-65.28507]}, - {"t":0.92713, "x":2.03975, "y":6.64913, "heading":2.15712, "vx":-2.74923, "vy":2.02452, "omega":0.13352, "ax":5.17232, "ay":-3.80885, "alpha":0.00126, "fx":[87.97477,87.98202,87.9846,87.97736], "fy":[-64.79411,-64.78431,-64.78069,-64.79049]}, - {"t":0.97128, "x":1.92341, "y":6.7348, "heading":2.16301, "vx":-2.52088, "vy":1.85637, "omega":0.13358, "ax":5.18087, "ay":-3.81515, "alpha":-0.12384, "fx":[88.61018,87.89221,87.64142,88.35633], "fy":[-64.23135,-65.20754,-65.55194,-64.58784]}, - {"t":1.01543, "x":1.81717, "y":6.81304, "heading":2.16891, "vx":-2.29215, "vy":1.68793, "omega":0.12811, "ax":5.18536, "ay":-3.81847, "alpha":-0.19098, "fx":[88.94917,87.83781,87.45744,88.56125], "fy":[-63.92784,-65.44319,-65.95979,-64.47335]}, - {"t":1.05958, "x":1.72102, "y":6.88384, "heading":2.17457, "vx":-2.06322, "vy":1.51935, "omega":0.11968, "ax":5.18812, "ay":-3.82051, "alpha":-0.23285, "fx":[89.15903,87.79981,87.34374,88.69133], "fy":[-63.7392,-65.59566,-66.21076,-64.3975]}, - {"t":1.10372, "x":1.63499, "y":6.94719, "heading":2.17985, "vx":-1.83417, "vy":1.35068, "omega":0.1094, "ax":5.19, "ay":-3.82189, "alpha":-0.26146, "fx":[89.30123,87.77098,87.26709,88.78219], "fy":[-63.6113,-65.70364,-66.37999,-64.34235]}, - {"t":1.14787, "x":1.55907, "y":7.0031, "heading":2.18468, "vx":-1.60504, "vy":1.18195, "omega":0.09786, "ax":5.19135, "ay":-3.82289, "alpha":-0.28224, "fx":[89.40365,87.74802,87.21224,88.84973], "fy":[-63.51929,-65.78477,-66.50138,-64.29986]}, - {"t":1.19202, "x":1.49327, "y":7.05156, "heading":2.189, "vx":-1.37584, "vy":1.01317, "omega":0.08539, "ax":5.19238, "ay":-3.82365, "alpha":-0.29802, "fx":[89.4808,87.72918,87.17123,88.9021], "fy":[-63.45011,-65.84823,-66.59249,-64.2659]}, - {"t":1.23617, "x":1.43759, "y":7.09256, "heading":2.19277, "vx":-1.14661, "vy":0.84436, "omega":0.07224, "ax":5.19318, "ay":-3.82424, "alpha":-0.31041, "fx":[89.54097,87.71349,87.13944,88.94394], "fy":[-63.39626,-65.89923,-66.66333,-64.23815]}, - {"t":1.28032, "x":1.39203, "y":7.12611, "heading":2.19596, "vx":-0.91733, "vy":0.67552, "omega":0.05853, "ax":5.19382, "ay":-3.82472, "alpha":-0.32039, "fx":[89.58924,87.70035,87.11406,88.97803], "fy":[-63.35312,-65.941,-66.72003,-64.2152]}, - {"t":1.32447, "x":1.35659, "y":7.15221, "heading":2.19854, "vx":-0.68803, "vy":0.50666, "omega":0.04439, "ax":5.19435, "ay":-3.82511, "alpha":-0.32861, "fx":[89.62889,87.68937,87.09323,89.00618], "fy":[-63.31766,-65.97557,-66.76654,-64.19613]}, - {"t":1.36862, "x":1.33128, "y":7.17085, "heading":2.2005, "vx":-0.45871, "vy":0.33779, "omega":0.02988, "ax":5.19479, "ay":-3.82543, "alpha":-0.33549, "fx":[89.66217,87.6803,87.07571,89.02958], "fy":[-63.28785,-66.00436,-66.80556,-64.18037]}, - {"t":1.41277, "x":1.31609, "y":7.18203, "heading":2.20182, "vx":-0.22936, "vy":0.1689, "omega":0.01507, "ax":5.19517, "ay":-3.82571, "alpha":-0.34133, "fx":[89.69063,87.67297,87.06062,89.04909], "fy":[-63.26224,-66.02832,-66.83895,-64.16748]}, - {"t":1.45692, "x":1.31103, "y":7.18576, "heading":2.20249, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.83764, "ay":-4.26453, "alpha":-0.36735, "fx":[83.79976,81.3103,80.80336,83.23432], "fy":[-70.80802,-73.65156,-74.21495,-71.47952]}, - {"t":1.48696, "x":1.31321, "y":7.18384, "heading":2.20249, "vx":0.14533, "vy":-0.12811, "omega":-0.01104, "ax":4.8373, "ay":-4.26424, "alpha":-0.36503, "fx":[83.78416,81.31075,80.80705,83.22271], "fy":[-70.8141,-73.63909,-74.1994,-71.48114]}, - {"t":1.517, "x":1.31976, "y":7.17806, "heading":2.20216, "vx":0.29065, "vy":-0.25621, "omega":-0.022, "ax":4.83693, "ay":-4.2639, "alpha":-0.36245, "fx":[83.76715,81.31175,80.81081,83.20933], "fy":[-70.82048,-73.62468,-74.18247,-71.48349]}, - {"t":1.54704, "x":1.33067, "y":7.16844, "heading":2.20149, "vx":0.43595, "vy":-0.38431, "omega":-0.03289, "ax":4.83651, "ay":-4.26353, "alpha":-0.35957, "fx":[83.7484,81.31329,80.81473,83.19397], "fy":[-70.82731,-73.60811,-74.16386,-71.48658]}, - {"t":1.57708, "x":1.34595, "y":7.15497, "heading":2.20051, "vx":0.58125, "vy":-0.51239, "omega":-0.04369, "ax":4.83603, "ay":-4.26311, "alpha":-0.35633, "fx":[83.72751,81.31535,80.8189,83.17635], "fy":[-70.83473,-73.58909,-74.14316,-71.49043]}, - {"t":1.60712, "x":1.36559, "y":7.13766, "heading":2.19919, "vx":0.72653, "vy":-0.64045, "omega":-0.0544, "ax":4.83549, "ay":-4.26264, "alpha":-0.35267, "fx":[83.70401,81.31793,80.82345,83.15614], "fy":[-70.84294,-73.56728,-74.11988,-71.49507]}, - {"t":1.63716, "x":1.3896, "y":7.11649, "heading":2.19756, "vx":0.87179, "vy":-0.76851, "omega":-0.06499, "ax":4.83488, "ay":-4.2621, "alpha":-0.34848, "fx":[83.67724,81.32101,80.82855,83.1329], "fy":[-70.8522,-73.54219,-74.09337,-71.50053]}, - {"t":1.6672, "x":1.41797, "y":7.09148, "heading":2.19561, "vx":1.01703, "vy":-0.89655, "omega":-0.07546, "ax":4.83417, "ay":-4.26147, "alpha":-0.34365, "fx":[83.6464,81.32457,80.83439,83.10606], "fy":[-70.86285,-73.51324,-74.0628,-71.50683]}, - {"t":1.69724, "x":1.45071, "y":7.06263, "heading":2.19334, "vx":1.16226, "vy":-1.02457, "omega":-0.08578, "ax":4.83334, "ay":-4.26074, "alpha":-0.33802, "fx":[83.61037,81.32858,80.84124,83.07483], "fy":[-70.8753,-73.47962,-74.02706,-71.51404]}, - {"t":1.72729, "x":1.4878, "y":7.02993, "heading":2.19076, "vx":1.30746, "vy":-1.15256, "omega":-0.09594, "ax":4.83236, "ay":-4.25988, "alpha":-0.33137, "fx":[83.56767,81.33299,80.84949,83.03818], "fy":[-70.89015,-73.44024,-73.98462,-71.52221]}, - {"t":1.75733, "x":1.52926, "y":6.99338, "heading":2.18788, "vx":1.45263, "vy":-1.28053, "omega":-0.10589, "ax":4.83118, "ay":-4.25884, "alpha":-0.32341, "fx":[83.5162,81.33776,80.85961,82.99465], "fy":[-70.9082,-73.39358,-73.93338,-71.53146]}, - {"t":1.78737, "x":1.57508, "y":6.95299, "heading":2.1847, "vx":1.59776, "vy":-1.40847, "omega":-0.11561, "ax":4.82974, "ay":-4.25757, "alpha":-0.3137, "fx":[83.45299,81.34279,80.87234,82.9421], "fy":[-70.93061,-73.33744,-73.87028,-71.54189]}, - {"t":1.81741, "x":1.62526, "y":6.90876, "heading":2.18123, "vx":1.74285, "vy":-1.53638, "omega":-0.12503, "ax":4.82794, "ay":-4.25598, "alpha":-0.30159, "fx":[83.37357,81.34793,80.8887,82.87736], "fy":[-70.95906,-73.26855,-73.79078,-71.5537]}, - {"t":1.84745, "x":1.67979, "y":6.86068, "heading":2.17747, "vx":1.88789, "vy":-1.66423, "omega":-0.13409, "ax":4.82562, "ay":-4.25394, "alpha":-0.28608, "fx":[83.27096,81.35294,80.91028,82.79543], "fy":[-70.99616,-73.1818,-73.68775,-71.56716]}, - {"t":1.87749, "x":1.73868, "y":6.80877, "heading":2.17344, "vx":2.03285, "vy":-1.79202, "omega":-0.14269, "ax":4.82252, "ay":-4.2512, "alpha":-0.26551, "fx":[83.13365,81.35735,80.93965,82.688], "fy":[-71.04609,-73.06874,-73.54941,-71.58267]}, - {"t":1.90753, "x":1.80193, "y":6.75301, "heading":2.16916, "vx":2.17773, "vy":-1.91973, "omega":-0.15066, "ax":4.81817, "ay":-4.24737, "alpha":-0.23692, "fx":[82.94114,81.36024,80.98116,82.54014], "fy":[-71.11615,-72.91436,-73.35466,-71.60085]}, - {"t":1.93757, "x":1.86952, "y":6.69343, "heading":2.16463, "vx":2.32247, "vy":-2.04733, "omega":-0.15778, "ax":4.81163, "ay":-4.2416, "alpha":-0.19453, "fx":[82.6531,81.35941,81.04296,82.3221], "fy":[-71.22011,-72.68912,-73.06181,-71.62261]}, - {"t":1.96761, "x":1.94146, "y":6.63001, "heading":2.15989, "vx":2.46702, "vy":-2.17475, "omega":-0.16362, "ax":4.80069, "ay":-4.23196, "alpha":-0.12526, "fx":[82.17776,81.34876,81.14191,81.96498], "fy":[-71.38744,-72.32607,-72.57526,-71.64891]}, - {"t":1.99766, "x":2.01774, "y":6.56277, "heading":2.15498, "vx":2.61123, "vy":-2.30188, "omega":-0.16739, "ax":4.77875, "ay":-4.21262, "alpha":0.00803, "fx":[81.25205,81.30478,81.31817,81.26542], "fy":[-71.69351,-71.63415,-71.61729,-71.6767]}, - {"t":2.0277, "x":2.09834, "y":6.49172, "heading":2.14995, "vx":2.75479, "vy":-2.42844, "omega":-0.16714, "ax":4.71317, "ay":-4.15481, "alpha":0.36768, "fx":[78.69833,81.0626,81.66527,79.2525], "fy":[-72.38435,-69.76594,-68.90945,-71.62882]}, - {"t":2.05774, "x":2.18323, "y":6.41689, "heading":2.14493, "vx":2.89638, "vy":-2.55325, "omega":-0.1561, "ax":2.64747, "ay":-2.33676, "alpha":5.1734, "fx":[37.29647,60.46081,55.72315,26.65017], "fy":[-58.74226,-39.48452,-18.1357,-42.62821]}, - {"t":2.08778, "x":2.27143, "y":6.33913, "heading":2.14024, "vx":2.97591, "vy":-2.62345, "omega":-0.00068, "ax":0.0069, "ay":-0.00517, "alpha":0.01035, "fx":[0.10922,0.15446,0.12548,0.08026], "fy":[-0.12502,-0.09607,-0.05083,-0.07976]}, - {"t":2.11782, "x":2.36083, "y":6.26032, "heading":2.14022, "vx":2.97612, "vy":-2.6236, "omega":-0.00037, "ax":-0.00691, "ay":0.00515, "alpha":-0.01035, "fx":[-0.10946,-0.15473,-0.12572,-0.08048], "fy":[0.12479,0.09583,0.05056,0.07951]}, - {"t":2.14786, "x":2.45024, "y":6.1815, "heading":2.1402, "vx":2.97591, "vy":-2.62345, "omega":-0.00069, "ax":-2.64747, "ay":2.3368, "alpha":-5.17506, "fx":[-37.21389,-60.42887,-55.7994,-26.68892], "fy":[58.76407,39.57054,18.13451,42.52382]}, - {"t":2.1779, "x":2.53844, "y":6.10375, "heading":2.14018, "vx":2.89638, "vy":-2.55325, "omega":-0.15615, "ax":-4.71316, "ay":4.1548, "alpha":-0.36878, "fx":[-78.68467,-81.05094,-81.67804,-79.26458], "fy":[72.39839,69.78017,68.89504,71.61452]}, - {"t":2.20794, "x":2.62332, "y":6.02892, "heading":2.13549, "vx":2.75479, "vy":-2.42844, "omega":-0.16723, "ax":-4.77875, "ay":4.21262, "alpha":-0.00842, "fx":[-81.25006,-81.30504,-81.32015,-81.26514], "fy":[71.69575,71.6339,71.61502,71.67693]}, - {"t":2.23798, "x":2.70393, "y":5.95787, "heading":2.13047, "vx":2.61123, "vy":-2.30188, "omega":-0.16748, "ax":-4.80069, "ay":4.23196, "alpha":0.12513, "fx":[-82.18589,-81.36458,-81.13348,-81.94945], "fy":[71.37841,72.30808,72.58435,71.66683]}, - {"t":2.26802, "x":2.7802, "y":5.89063, "heading":2.12544, "vx":2.46702, "vy":-2.17475, "omega":-0.16372, "ax":-4.81163, "ay":4.2416, "alpha":0.19453, "fx":[-82.67085,-81.39181,-81.02426,-82.29064], "fy":[71.20002,72.65255,73.08206,71.65902]}, - {"t":2.29807, "x":2.85214, "y":5.82721, "heading":2.12052, "vx":2.32247, "vy":-2.04733, "omega":-0.15788, "ax":-4.81817, "ay":4.24737, "alpha":0.23699, "fx":[-82.96809,-81.40929,-80.95246,-82.49283], "fy":[71.08534,72.85922,73.38575,71.65569]}, - {"t":2.32811, "x":2.91974, "y":5.76762, "heading":2.11578, "vx":2.17773, "vy":-1.91973, "omega":-0.15076, "ax":-4.82252, "ay":4.2512, "alpha":0.26563, "fx":[-83.16938,-81.42272,-80.90131,-82.62523], "fy":[71.00496,72.9955,73.59094,71.65548]}, - {"t":2.35815, "x":2.98298, "y":5.71187, "heading":2.11125, "vx":2.03285, "vy":-1.79202, "omega":-0.14278, "ax":-4.82562, "ay":4.25393, "alpha":0.28623, "fx":[-83.31501,-81.43403,-80.86273,-82.7178], "fy":[70.9452,73.09114,73.73925,71.65725]}, - {"t":2.38819, "x":3.04188, "y":5.65995, "heading":2.10696, "vx":1.88789, "vy":-1.66423, "omega":-0.13418, "ax":-4.82794, "ay":4.25598, "alpha":0.30176, "fx":[-83.42547,-81.44401,-80.83243,-82.7856], "fy":[70.89881,73.1613,73.85171,71.66024]}, - {"t":2.41823, "x":3.09641, "y":5.61188, "heading":2.10293, "vx":1.74285, "vy":-1.53638, "omega":-0.12511, "ax":-4.82974, "ay":4.25757, "alpha":0.31389, "fx":[-83.51225,-81.45302,-80.80788,-82.83702], "fy":[70.86163,73.21455,73.94007,71.66394]}, - {"t":2.44827, "x":3.14659, "y":5.56765, "heading":2.09917, "vx":1.59776, "vy":-1.40847, "omega":-0.11569, "ax":-4.83118, "ay":4.25884, "alpha":0.32361, "fx":[-83.58229,-81.46124,-80.78753,-82.87712], "fy":[70.83109,73.25606,74.01142,71.668]}, - {"t":2.47831, "x":3.19241, "y":5.52726, "heading":2.09569, "vx":1.45262, "vy":-1.28053, "omega":-0.10596, "ax":-4.83236, "ay":4.25988, "alpha":0.33158, "fx":[-83.64004,-81.46875,-80.77035,-82.90913], "fy":[70.80554,73.28916,74.0703,71.67219]}, - {"t":2.50835, "x":3.23387, "y":5.49071, "heading":2.09251, "vx":1.30746, "vy":-1.15256, "omega":-0.096, "ax":-4.83334, "ay":4.26074, "alpha":0.33824, "fx":[-83.68849,-81.47561,-80.75565,-82.9352], "fy":[70.78382,73.3161,74.11971,71.67633]}, - {"t":2.53839, "x":3.27096, "y":5.45801, "heading":2.08963, "vx":1.16226, "vy":-1.02457, "omega":-0.08584, "ax":-4.83417, "ay":4.26147, "alpha":0.34387, "fx":[-83.72971,-81.48185,-80.74295,-82.95683], "fy":[70.76517,73.33844,74.16177,71.68029]}, - {"t":2.56844, "x":3.3037, "y":5.42915, "heading":2.08705, "vx":1.01703, "vy":-0.89655, "omega":-0.07551, "ax":-4.83488, "ay":4.2621, "alpha":0.34871, "fx":[-83.76518,-81.48746,-80.7319,-82.9751], "fy":[70.74899,73.35728,74.19798,71.68399]}, - {"t":2.59848, "x":3.33207, "y":5.40414, "heading":2.08478, "vx":0.87179, "vy":-0.76851, "omega":-0.06504, "ax":-4.83549, "ay":4.26264, "alpha":0.3529, "fx":[-83.79598,-81.49246,-80.72223,-82.99078], "fy":[70.73487,73.37347,74.22944,71.68734]}, - {"t":2.62852, "x":3.35607, "y":5.38298, "heading":2.08283, "vx":0.72653, "vy":-0.64045, "omega":-0.05443, "ax":-4.83603, "ay":4.26311, "alpha":0.35658, "fx":[-83.82296,-81.49686,-80.71375,-83.00448], "fy":[70.72249,73.38762,74.25697,71.69029]}, - {"t":2.65856, "x":3.37572, "y":5.36566, "heading":2.08119, "vx":0.58125, "vy":-0.51239, "omega":-0.04372, "ax":-4.83651, "ay":4.26353, "alpha":0.35982, "fx":[-83.84672,-81.50064,-80.70629,-83.01665], "fy":[70.7116,73.40021,74.28121,71.69278]}, - {"t":2.6886, "x":3.391, "y":5.35219, "heading":2.07988, "vx":0.43595, "vy":-0.38431, "omega":-0.03291, "ax":-4.83693, "ay":4.2639, "alpha":0.3627, "fx":[-83.86776,-81.50382,-80.69975,-83.02764], "fy":[70.702,73.41162,74.30266,71.69479]}, - {"t":2.71864, "x":3.40191, "y":5.34257, "heading":2.07889, "vx":0.29065, "vy":-0.25621, "omega":-0.02202, "ax":-4.8373, "ay":4.26423, "alpha":0.36528, "fx":[-83.88647,-81.50637,-80.69403,-83.03773], "fy":[70.69354,73.42214,74.32171,71.69628]}, - {"t":2.74868, "x":3.40846, "y":5.3368, "heading":2.07823, "vx":0.14533, "vy":-0.12811, "omega":-0.01104, "ax":-4.83764, "ay":4.26453, "alpha":0.36761, "fx":[-83.90315,-81.50832,-80.68904,-83.04715], "fy":[70.68611,73.43201,74.33866,71.69722]}, - {"t":2.77872, "x":3.41064, "y":5.33488, "heading":2.07789, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[ - {"name":"Funnel", "from":{"target":2, "targetTimestamp":2.14786, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] -} diff --git a/src/main/deploy/choreo/A_LEFT_PATH4.traj b/src/main/deploy/choreo/A_LEFT_PATH4.traj deleted file mode 100644 index 4d69136b..00000000 --- a/src/main/deploy/choreo/A_LEFT_PATH4.traj +++ /dev/null @@ -1,129 +0,0 @@ -{ - "name":"A_LEFT_PATH4", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":3.692616224288941, "y":5.020236015319824, "heading":2.0948682307415045, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.3110252618789673, "y":7.185760498046875, "heading":2.216612130911823, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.2821998596191406, "y":5.24192476272583, "heading":0.0, "intervals":35, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":2.819322109222412, "y":4.265955924987793, "heading":3.1289351796122347, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"3.6926162242889404 m", "val":3.692616224288941}, "y":{"exp":"5.020236015319824 m", "val":5.020236015319824}, "heading":{"exp":"2.0948682307415045 rad", "val":2.0948682307415045}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"7.185760498046875 m", "val":7.185760498046875}, "heading":{"exp":"2.216612130911823 rad", "val":2.216612130911823}, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.2821998596191406 m", "val":2.2821998596191406}, "y":{"exp":"5.24192476272583 m", "val":5.24192476272583}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":35, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"2.819322109222412 m", "val":2.819322109222412}, "y":{"exp":"4.265955924987793 m", "val":4.265955924987793}, "heading":{"exp":"3.1289351796122347 rad", "val":3.1289351796122347}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.42726,2.23364,2.87874], - "samples":[ - {"t":0.0, "x":3.69262, "y":5.02024, "heading":2.09487, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-4.77336, "ay":4.34029, "alpha":0.36517, "fx":[-82.80387,-80.3539,-79.60509,-82.01137], "fy":[72.03947,74.76071,75.56262,72.9455]}, - {"t":0.04325, "x":3.68815, "y":5.0243, "heading":2.09487, "vx":-0.20645, "vy":0.18772, "omega":0.01579, "ax":-4.77303, "ay":4.33999, "alpha":0.36029, "fx":[-82.77638,-80.35948,-79.62059,-81.99495], "fy":[72.05859,74.74258,75.53461,72.95195]}, - {"t":0.0865, "x":3.67476, "y":5.03647, "heading":2.09555, "vx":-0.41289, "vy":0.37543, "omega":0.03138, "ax":-4.77264, "ay":4.33963, "alpha":0.35461, "fx":[-82.74377,-80.3649,-79.63925,-81.97681], "fy":[72.08147,74.7226,75.50128,72.95832]}, - {"t":0.12975, "x":3.65244, "y":5.05677, "heading":2.09691, "vx":-0.6193, "vy":0.56312, "omega":0.04671, "ax":-4.77217, "ay":4.33921, "alpha":0.34789, "fx":[-82.70483,-80.37047,-79.66174,-81.95612], "fy":[72.10894,74.69987,75.4614,72.96497]}, - {"t":0.173, "x":3.62119, "y":5.08518, "heading":2.09893, "vx":-0.8257, "vy":0.75079, "omega":0.06176, "ax":-4.77161, "ay":4.33871, "alpha":0.33982, "fx":[-82.65783,-80.37666,-79.68899,-81.9317], "fy":[72.14215,74.67312,75.41319,72.97244]}, - {"t":0.21625, "x":3.58101, "y":5.12171, "heading":2.1016, "vx":-1.03208, "vy":0.93844, "omega":0.07646, "ax":-4.77093, "ay":4.33809, "alpha":0.32994, "fx":[-82.60029,-80.3841,-79.72234,-81.90188], "fy":[72.18278,74.64053,75.35412,72.98148]}, - {"t":0.2595, "x":3.53191, "y":5.16636, "heading":2.10491, "vx":-1.23842, "vy":1.12606, "omega":0.09073, "ax":-4.77007, "ay":4.33732, "alpha":0.31759, "fx":[-82.52847,-80.39377,-79.76384,-81.86414], "fy":[72.23331,74.59939,75.28035,72.99318]}, - {"t":0.30275, "x":3.47389, "y":5.21912, "heading":2.10883, "vx":-1.44473, "vy":1.31366, "omega":0.10446, "ax":-4.76896, "ay":4.33632, "alpha":0.3017, "fx":[-82.43651,-80.40713,-79.81665,-81.81452], "fy":[72.29765,74.54544,75.18582,73.0093]}, - {"t":0.346, "x":3.40694, "y":5.27999, "heading":2.11335, "vx":-1.65099, "vy":1.5012, "omega":0.11751, "ax":-4.76748, "ay":4.33498, "alpha":0.28048, "fx":[-82.31463,-80.4266,-79.88606,-81.7464], "fy":[72.38226,74.47165,75.06042,73.03267]}, - {"t":0.38925, "x":3.33108, "y":5.34897, "heading":2.11843, "vx":-1.85718, "vy":1.68869, "omega":0.12964, "ax":-4.76538, "ay":4.33309, "alpha":0.25074, "fx":[-82.14522,-80.45644,-79.98159,-81.64782], "fy":[72.4987,74.3654,74.88582,73.06841]}, - {"t":0.4325, "x":3.2463, "y":5.42606, "heading":2.12404, "vx":-2.06329, "vy":1.8761, "omega":0.14049, "ax":-4.7622, "ay":4.33022, "alpha":0.20608, "fx":[-81.89306,-80.50494,-80.1221,-81.49469], "fy":[72.66984,74.20164,74.62514,73.12662]}, - {"t":0.47575, "x":3.15261, "y":5.51125, "heading":2.13011, "vx":-2.26926, "vy":2.06338, "omega":0.1494, "ax":-4.75682, "ay":4.32536, "alpha":0.13158, "fx":[-81.47614,-80.59075,-80.35127,-81.23019], "fy":[72.94801,73.92248,74.19154,73.23063]}, - {"t":0.519, "x":3.05001, "y":5.60454, "heading":2.13658, "vx":-2.47499, "vy":2.25046, "omega":0.15509, "ax":-4.74572, "ay":4.31535, "alpha":-0.0174, "fx":[-80.64964,-80.76623,-80.79726,-80.68055], "fy":[73.48469,73.35701,73.32106,73.44898]}, - {"t":0.56226, "x":2.93853, "y":5.70591, "heading":2.14328, "vx":-2.68024, "vy":2.4371, "omega":0.15434, "ax":-4.71008, "ay":4.28318, "alpha":-0.46025, "fx":[-78.21717,-81.25126,-82.05793,-78.9421], "fy":[74.96378,71.68837,70.66649,74.10427]}, - {"t":0.60551, "x":2.8182, "y":5.81532, "heading":2.14996, "vx":-2.88396, "vy":2.62235, "omega":0.13443, "ax":-1.2157, "ay":1.10429, "alpha":-3.10111, "fx":[-17.91853,-31.3387,-23.99027,-9.46753], "fy":[30.0091,20.53232,7.3062,17.28695]}, - {"t":0.64876, "x":2.69233, "y":5.92977, "heading":2.15577, "vx":-2.93654, "vy":2.67011, "omega":0.00031, "ax":-0.00062, "ay":0.00028, "alpha":-0.00081, "fx":[-0.00992,-0.01341,-0.0111,-0.0076], "fy":[0.00772,0.0054,0.00191,0.00422]}, - {"t":0.69201, "x":2.56532, "y":6.04526, "heading":2.15579, "vx":-2.93656, "vy":2.67012, "omega":0.00027, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[-0.00001,-0.00001,-0.00001,-0.00001], "fy":[-0.00001,-0.00001,-0.00001,-0.00001]}, - {"t":0.73526, "x":2.43832, "y":6.16074, "heading":2.1558, "vx":-2.93656, "vy":2.67012, "omega":0.00027, "ax":0.00061, "ay":-0.00029, "alpha":0.00081, "fx":[0.00987,0.01336,0.01105,0.00755], "fy":[-0.00777,-0.00546,-0.00197,-0.00428]}, - {"t":0.77851, "x":2.31131, "y":6.27622, "heading":2.15581, "vx":-2.93654, "vy":2.67011, "omega":0.00031, "ax":1.21564, "ay":-1.10425, "alpha":3.09988, "fx":[17.98155,31.35144,23.9232,9.45427], "fy":[-30.01052,-20.46739,-7.29761,-17.35637]}, - {"t":0.82176, "x":2.18544, "y":6.39067, "heading":2.15582, "vx":-2.88396, "vy":2.62235, "omega":0.13438, "ax":4.71011, "ay":-4.2832, "alpha":0.4563, "fx":[78.24912,81.26521,82.02797,78.92834], "fy":[-74.9311,-71.67191,-70.70106,-74.12022]}, - {"t":0.86501, "x":2.06511, "y":6.50009, "heading":2.16164, "vx":-2.68025, "vy":2.4371, "omega":0.15411, "ax":4.74573, "ay":-4.31535, "alpha":0.01614, "fx":[80.65607,80.76491,80.79097,80.68202], "fy":[-73.47768,-73.35843,-73.32808,-73.44753]}, - {"t":0.90826, "x":1.95363, "y":6.60146, "heading":2.1683, "vx":-2.47499, "vy":2.25046, "omega":0.15481, "ax":4.75682, "ay":-4.32536, "alpha":-0.13197, "fx":[81.4654,80.56831,80.36251,81.25225], "fy":[-72.95981,-73.94707,-74.17961,-73.20607]}, - {"t":0.95151, "x":1.85104, "y":6.69474, "heading":2.175, "vx":-2.26926, "vy":2.06338, "omega":0.1491, "ax":4.7622, "ay":-4.33022, "alpha":-0.20605, "fx":[81.86727,80.45992,80.14932,81.5384], "fy":[-72.69857,-74.25068,-74.59625,-73.0777]}, - {"t":0.99476, "x":1.75734, "y":6.77993, "heading":2.18145, "vx":-2.06329, "vy":1.8761, "omega":0.14019, "ax":4.76538, "ay":-4.33309, "alpha":-0.25046, "fx":[82.10564,80.38905,80.0237,81.7128], "fy":[-72.54312,-74.43851,-74.8412,-72.9955]}, - {"t":1.03801, "x":1.67256, "y":6.85702, "heading":2.18751, "vx":-1.85718, "vy":1.68869, "omega":0.12936, "ax":4.76748, "ay":-4.33498, "alpha":-0.28003, "fx":[82.26239,80.33786,79.94201,81.83158], "fy":[-72.44118,-74.56765,-75.00125,-72.93696]}, - {"t":1.08126, "x":1.5967, "y":6.92601, "heading":2.1931, "vx":-1.65099, "vy":1.5012, "omega":0.11725, "ax":4.76897, "ay":-4.33632, "alpha":-0.30113, "fx":[82.37273,80.29854,79.88529,81.91843], "fy":[-72.36984,-74.6627,-75.11332,-72.89242]}, - {"t":1.12451, "x":1.52975, "y":6.98688, "heading":2.19817, "vx":-1.44473, "vy":1.31366, "omega":0.10423, "ax":4.77007, "ay":-4.33732, "alpha":-0.31695, "fx":[82.45429,80.2671,79.84396,81.98506], "fy":[-72.31749,-74.73597,-75.1958,-72.85708]}, - {"t":1.16776, "x":1.47173, "y":7.03964, "heading":2.20268, "vx":-1.23842, "vy":1.12607, "omega":0.09052, "ax":4.77093, "ay":-4.3381, "alpha":-0.32923, "fx":[82.51691,80.24134,79.81267,82.03791], "fy":[-72.2776,-74.79429,-75.25888,-72.82827]}, - {"t":1.21101, "x":1.42263, "y":7.08428, "heading":2.2066, "vx":-1.03208, "vy":0.93844, "omega":0.07628, "ax":4.77162, "ay":-4.33871, "alpha":-0.33906, "fx":[82.56647,80.21992,79.78819,82.08082], "fy":[-72.24622,-74.84177,-75.30866,-72.8044]}, - {"t":1.25426, "x":1.38245, "y":7.12081, "heading":2.2099, "vx":-0.8257, "vy":0.75079, "omega":0.06161, "ax":4.77218, "ay":-4.33922, "alpha":-0.34709, "fx":[82.60675,80.202,79.76843,82.11621], "fy":[-72.22081,-74.88101,-75.34903,-72.78449]}, - {"t":1.29751, "x":1.3512, "y":7.14923, "heading":2.21256, "vx":-0.6193, "vy":0.56312, "omega":0.0466, "ax":4.77264, "ay":-4.33964, "alpha":-0.35378, "fx":[82.64027,80.187,79.75202,82.1457], "fy":[-72.19966,-74.91375,-75.38256,-72.76786]}, - {"t":1.34076, "x":1.32888, "y":7.16952, "heading":2.21458, "vx":-0.41289, "vy":0.37543, "omega":0.0313, "ax":4.77303, "ay":-4.33999, "alpha":-0.35943, "fx":[82.66877,80.17455,79.73797,82.17038], "fy":[-72.18158,-74.94119,-75.41107,-72.75406]}, - {"t":1.38401, "x":1.31549, "y":7.1817, "heading":2.21593, "vx":-0.20645, "vy":0.18772, "omega":0.01576, "ax":4.77337, "ay":-4.34029, "alpha":-0.36428, "fx":[82.6935,80.16436,79.7256,82.19104], "fy":[-72.16572,-74.96417,-75.43584,-72.74277]}, - {"t":1.42726, "x":1.31103, "y":7.18576, "heading":2.21661, "vx":0.0, "vy":0.0, "omega":0.0, "ax":2.92009, "ay":-5.66075, "alpha":3.33895, "fx":[39.65414,64.81516,64.33176,29.87871], "fy":[-102.30195,-88.52067,-88.80521,-105.52346]}, - {"t":1.45414, "x":1.31208, "y":7.18372, "heading":2.21661, "vx":0.07849, "vy":-0.15216, "omega":0.08975, "ax":2.92076, "ay":-5.6625, "alpha":3.28889, "fx":[39.78129,64.63764,64.09729,30.20895], "fy":[-102.24494,-88.64131,-88.96343,-105.42035]}, - {"t":1.48102, "x":1.31524, "y":7.17758, "heading":2.21902, "vx":0.157, "vy":-0.30436, "omega":0.17815, "ax":2.92152, "ay":-5.66438, "alpha":3.23333, "fx":[39.96044,64.4685,63.80063,30.54705], "fy":[-102.16666,-88.75433,-89.16413,-105.31306]}, - {"t":1.5079, "x":1.32052, "y":7.16735, "heading":2.22381, "vx":0.23553, "vy":-0.45661, "omega":0.26506, "ax":2.92236, "ay":-5.66642, "alpha":3.17158, "fx":[40.19136,64.30267,63.4405,30.89943], "fy":[-102.06674,-88.86333,-89.40716,-105.1995]}, - {"t":1.53478, "x":1.32791, "y":7.15303, "heading":2.23094, "vx":0.31408, "vy":-0.60892, "omega":0.35031, "ax":2.92329, "ay":-5.66863, "alpha":3.10282, "fx":[40.474,64.13382,63.0151,31.27417], "fy":[-101.94462,-88.9727,-89.6925,-105.07696]}, - {"t":1.56166, "x":1.3374, "y":7.13462, "heading":2.24035, "vx":0.39265, "vy":-0.76129, "omega":0.43371, "ax":2.9243, "ay":-5.67102, "alpha":3.02599, "fx":[40.80843,63.95412,62.52214,31.68118], "fy":[-101.79956,-89.0878,-90.02019,-104.94198]}, - {"t":1.58854, "x":1.34902, "y":7.11211, "heading":2.25201, "vx":0.47125, "vy":-0.91372, "omega":0.51505, "ax":2.92539, "ay":-5.67362, "alpha":2.9398, "fx":[41.19492,63.75377,61.95886,32.13262], "fy":[-101.6306,-89.21524,-90.39028,-104.79017]}, - {"t":1.61542, "x":1.36274, "y":7.0855, "heading":2.26586, "vx":0.54989, "vy":-1.06623, "omega":0.59407, "ax":2.92656, "ay":-5.67644, "alpha":2.84262, "fx":[41.63397,63.52045,61.32214,32.64333], "fy":[-101.43647,-89.36318,-90.80272,-104.61597]}, - {"t":1.6423, "x":1.37858, "y":7.05479, "heading":2.28182, "vx":0.62855, "vy":-1.2188, "omega":0.67047, "ax":2.92781, "ay":-5.6795, "alpha":2.73239, "fx":[42.12644,63.23848,60.60849,33.2316], "fy":[-101.21556,-89.54186,-91.25734,-104.41219]}, - {"t":1.66918, "x":1.39653, "y":7.01997, "heading":2.29985, "vx":0.70725, "vy":-1.37146, "omega":0.74392, "ax":2.92914, "ay":-5.68283, "alpha":2.60639, "fx":[42.67369,62.8875,59.8141,33.92019], "fy":[-100.96576,-89.76422,-91.75368,-104.16943]}, - {"t":1.69606, "x":1.4166, "y":6.98106, "heading":2.31984, "vx":0.78598, "vy":-1.52421, "omega":0.81398, "ax":2.93055, "ay":-5.68642, "alpha":2.46104, "fx":[43.27782,62.44057,58.93487,34.73795], "fy":[-100.68426,-90.04694,-92.29098,-103.87514]}, - {"t":1.72293, "x":1.43878, "y":6.93803, "heading":2.34172, "vx":0.86475, "vy":-1.67706, "omega":0.88013, "ax":2.93203, "ay":-5.69027, "alpha":2.29143, "fx":[43.94217,61.86119,57.96633,35.72224], "fy":[-100.3672,-90.41183,-92.86809,-103.51201]}, - {"t":1.74981, "x":1.46309, "y":6.8909, "heading":2.36538, "vx":0.94356, "vy":-1.83001, "omega":0.94172, "ax":2.93357, "ay":-5.69433, "alpha":2.09063, "fx":[44.67201,61.0983,56.90354,36.92279], "fy":[-100.00906,-90.88801,-93.48342,-103.05551]}, - {"t":1.77669, "x":1.48951, "y":6.83965, "heading":2.39069, "vx":1.02241, "vy":-1.98307, "omega":0.99791, "ax":2.93513, "ay":-5.69853, "alpha":1.84854, "fx":[45.47599,60.07801,55.74073,38.40789], "fy":[-99.6016,-91.51532,-94.135,-102.46943]}, - {"t":1.80357, "x":1.51805, "y":6.78429, "heading":2.41751, "vx":1.10131, "vy":-2.13624, "omega":1.0476, "ax":2.9366, "ay":-5.70262, "alpha":1.54987, "fx":[46.36867,58.68866,54.47066,40.27481], "fy":[-99.13177,-92.34961,-94.82058,-101.69795]}, - {"t":1.83045, "x":1.54871, "y":6.72481, "heading":2.44567, "vx":1.18024, "vy":-2.28952, "omega":1.08926, "ax":2.93773, "ay":-5.70611, "alpha":1.17048, "fx":[47.37576,56.75272,53.08323,42.66782], "fy":[-98.57754,-93.47133,-95.53789,-100.65046]}, - {"t":1.85733, "x":1.5815, "y":6.66121, "heading":2.47495, "vx":1.2592, "vy":-2.4429, "omega":1.12072, "ax":2.93787, "ay":-5.70782, "alpha":0.67009, "fx":[48.54557,53.96968,51.56289,45.81101], "fy":[-97.8985,-94.99917,-96.28529,-99.17038]}, - {"t":1.88421, "x":1.61641, "y":6.59348, "heading":2.50507, "vx":1.33817, "vy":-2.59632, "omega":1.13873, "ax":2.93539, "ay":-5.70483, "alpha":-0.0228, "fx":[49.97722,49.78987,49.88337,50.07035], "fy":[-97.01215,-97.10922,-97.06281,-96.9657]}, - {"t":1.91109, "x":1.65343, "y":6.52164, "heading":2.53568, "vx":1.41707, "vy":-2.74966, "omega":1.13812, "ax":2.92596, "ay":-5.6891, "alpha":-1.04599, "fx":[51.90259,43.10575,47.99686,56.07385], "fy":[-95.72212,-100.0447,-97.87431,-93.43849]}, - {"t":1.93797, "x":1.69258, "y":6.44567, "heading":2.56627, "vx":1.49572, "vy":-2.90258, "omega":1.11, "ax":2.89755, "ay":-5.6345, "alpha":-2.69283, "fx":[54.99167,31.4142,45.81095,64.92903], "fy":[-93.432,-103.98317,-98.73111,-87.21837]}, - {"t":1.96485, "x":1.73383, "y":6.36562, "heading":2.59611, "vx":1.5736, "vy":-3.05403, "omega":1.03762, "ax":2.82429, "ay":-5.43028, "alpha":-5.66301, "fx":[62.0892,8.57011,43.14565,78.35624], "fy":[-87.24907,-107.74498,-99.6525,-74.82361]}, - {"t":1.99173, "x":1.77715, "y":6.28157, "heading":2.624, "vx":1.64952, "vy":-3.19999, "omega":0.88541, "ax":2.84221, "ay":-4.41824, "alpha":-11.80305, "fx":[88.41565,-29.33967,40.23429,94.07034], "fy":[-44.75962,-103.09692,-100.37834,-52.37712]}, - {"t":2.01861, "x":1.82251, "y":6.19396, "heading":2.6478, "vx":1.72591, "vy":-3.31875, "omega":0.56815, "ax":2.65628, "ay":-4.20466, "alpha":-12.33669, "fx":[78.10945,-30.80219,40.04528,93.37801], "fy":[-37.6642,-100.24818,-98.78196,-49.38559]}, - {"t":2.04548, "x":1.86986, "y":6.10323, "heading":2.66307, "vx":1.79731, "vy":-3.43177, "omega":0.23655, "ax":1.25521, "ay":-3.20772, "alpha":-8.58399, "fx":[15.77745,-15.956,27.27734,58.30418], "fy":[-29.64139,-69.27059,-75.80693,-43.53044]}, - {"t":2.07236, "x":1.91863, "y":6.00983, "heading":2.66943, "vx":1.83105, "vy":-3.51799, "omega":0.00582, "ax":-0.26015, "ay":-0.15904, "alpha":-0.05173, "fx":[-4.48384,-4.60535,-4.36621,-4.24463], "fy":[-2.52429,-2.76346,-2.8862,-2.64703]}, - {"t":2.09924, "x":1.96775, "y":5.91521, "heading":2.66959, "vx":1.82406, "vy":-3.52226, "omega":0.00443, "ax":-0.11455, "ay":-0.05933, "alpha":-0.00015, "fx":[-1.94862,-1.94897,-1.94828,-1.94792], "fy":[-1.00868,-1.00938,-1.00974,-1.00904]}, - {"t":2.12612, "x":2.01674, "y":5.82052, "heading":2.6697, "vx":1.82098, "vy":-3.52386, "omega":0.00442, "ax":-0.03251, "ay":-0.0168, "alpha":0.0, "fx":[-0.55298,-0.55299,-0.55297,-0.55296], "fy":[-0.28567,-0.28568,-0.28569,-0.28567]}, - {"t":2.153, "x":2.06567, "y":5.72579, "heading":2.66982, "vx":1.82011, "vy":-3.52431, "omega":0.00442, "ax":0.02864, "ay":0.0148, "alpha":0.0, "fx":[0.48718,0.48719,0.48718,0.48718], "fy":[0.25167,0.25168,0.25168,0.25168]}, - {"t":2.17988, "x":2.11461, "y":5.63107, "heading":2.66994, "vx":1.82088, "vy":-3.52391, "omega":0.00442, "ax":0.10819, "ay":0.05604, "alpha":0.00016, "fx":[1.8405,1.84088,1.84013,1.83975], "fy":[0.95269,0.95343,0.95381,0.95307]}, - {"t":2.20676, "x":2.16359, "y":5.53637, "heading":2.67006, "vx":1.82379, "vy":-3.5224, "omega":0.00443, "ax":0.24644, "ay":0.15396, "alpha":0.05644, "fx":[4.2562,4.38867,4.12767,3.99513], "fy":[2.42141,2.68242,2.81611,2.5551]}, - {"t":2.23364, "x":2.2127, "y":5.44174, "heading":2.67018, "vx":1.83041, "vy":-3.51827, "omega":0.00595, "ax":-1.33066, "ay":3.27673, "alpha":8.8129, "fx":[-17.24202,16.04776,-28.64778,-60.69442], "fy":[30.50691,71.35757,77.20084,43.8798]}, - {"t":2.26052, "x":2.26142, "y":5.34836, "heading":2.67034, "vx":1.79464, "vy":-3.43019, "omega":0.24283, "ax":-2.64862, "ay":4.20972, "alpha":12.25578, "fx":[-75.47202,30.38917,-41.08154,-94.04495], "fy":[39.44268,100.48306,98.39216,48.10638]}, - {"t":2.2874, "x":2.3087, "y":5.25768, "heading":2.67687, "vx":1.72345, "vy":-3.31704, "omega":0.57225, "ax":-2.84236, "ay":4.38926, "alpha":11.74826, "fx":[-84.49732,29.44199,-42.45233,-95.88295], "fy":[47.08075,103.167,99.48091,48.91165]}, - {"t":2.31428, "x":2.354, "y":5.17011, "heading":2.69225, "vx":1.64705, "vy":-3.19906, "omega":0.88804, "ax":-2.80853, "ay":5.41005, "alpha":5.89864, "fx":[-57.82793,-6.49395,-45.60659,-81.16057], "fy":[89.87376,107.94538,98.56709,71.70707]}, - {"t":2.34116, "x":2.39726, "y":5.08607, "heading":2.71612, "vx":1.57156, "vy":-3.05364, "omega":1.04659, "ax":-2.89304, "ay":5.62754, "alpha":2.87526, "fx":[-52.17808,-29.90942,-47.9273,-66.82403], "fy":[94.97657,104.45159,97.72942,85.73389]}, - {"t":2.36803, "x":2.43845, "y":5.00603, "heading":2.74425, "vx":1.4938, "vy":-2.90238, "omega":1.12387, "ax":-2.92485, "ay":5.68746, "alpha":1.14766, "fx":[-50.48874,-42.22504,-49.25193,-57.03764], "fy":[96.45651,100.42767,97.25116,92.83321]}, - {"t":2.39491, "x":2.47755, "y":4.93007, "heading":2.77446, "vx":1.41518, "vy":-2.7495, "omega":1.15472, "ax":-2.93512, "ay":5.70469, "alpha":0.06295, "fx":[-49.94765,-49.51752,-49.90401,-50.3329], "fy":[97.02084,97.24435,97.05022,96.82523]}, - {"t":2.42179, "x":2.51453, "y":4.85822, "heading":2.8055, "vx":1.33628, "vy":-2.59616, "omega":1.15641, "ax":-2.93765, "ay":5.70774, "alpha":-0.67113, "fx":[-49.89727,-54.29457,-50.09942,-45.58308], "fy":[97.21544,94.80094,97.04941,99.28238]}, - {"t":2.44867, "x":2.54939, "y":4.7905, "heading":2.83658, "vx":1.25732, "vy":-2.44274, "omega":1.13837, "ax":-2.93727, "ay":5.70568, "alpha":-1.19714, "fx":[-50.09663,-57.66296,-49.97966,-42.10956], "fy":[97.22481,92.89288,97.18937,100.90084]}, - {"t":2.47555, "x":2.58212, "y":4.7269, "heading":2.86718, "vx":1.17837, "vy":-2.28938, "omega":1.1062, "ax":-2.93577, "ay":5.70182, "alpha":-1.59116, "fx":[-50.43338,-60.1682,-49.64093,-39.50373], "fy":[97.13027,91.36764,97.42572,102.02189]}, - {"t":2.50243, "x":2.61273, "y":4.66743, "heading":2.89691, "vx":1.09946, "vy":-2.13612, "omega":1.06343, "ax":-2.93382, "ay":5.69748, "alpha":-1.89703, "fx":[-50.84671,-62.10605,-49.15137,-37.50987], "fy":[96.97421,90.12235,97.7253,102.82835]}, - {"t":2.52931, "x":2.64123, "y":4.61207, "heading":2.9255, "vx":1.0206, "vy":-1.98298, "omega":1.01244, "ax":-2.93173, "ay":5.69319, "alpha":-2.14158, "fx":[-51.30012,-63.64974,-48.56102,-35.96081], "fy":[96.78146,89.0877,98.06322,103.42558]}, - {"t":2.55619, "x":2.6676, "y":4.56082, "heading":2.95271, "vx":0.9418, "vy":-1.82995, "omega":0.95487, "ax":-2.92962, "ay":5.68914, "alpha":-2.34201, "fx":[-51.7701,-64.90736,-47.90775,-34.74268], "fy":[96.56793,88.21585,98.42072,103.8781]}, - {"t":2.58307, "x":2.69186, "y":4.51369, "heading":2.97838, "vx":0.86305, "vy":-1.67703, "omega":0.89192, "ax":-2.92754, "ay":5.6854, "alpha":-2.50976, "fx":[-52.24065,-65.95004,-47.22087,-33.77509], "fy":[96.34449,87.4728,98.78364,104.22743]}, - {"t":2.60995, "x":2.714, "y":4.47067, "heading":3.00235, "vx":0.78436, "vy":-1.52421, "omega":0.82446, "ax":-2.92553, "ay":5.68198, "alpha":-2.65266, "fx":[-52.70041,-66.82675,-46.52347,-32.99941], "fy":[96.11904,86.83356,99.1414,104.50146]}, - {"t":2.63683, "x":2.73402, "y":4.43175, "heading":3.02451, "vx":0.70573, "vy":-1.37148, "omega":0.75316, "ax":-2.92361, "ay":5.67885, "alpha":-2.77619, "fx":[-53.14105,-67.57252,-45.8339,-32.37172], "fy":[95.8975,86.27926,99.48607,104.71962]}, - {"t":2.66371, "x":2.75194, "y":4.39694, "heading":3.04476, "vx":0.62714, "vy":-1.21884, "omega":0.67854, "ax":-2.92178, "ay":5.67598, "alpha":-2.88424, "fx":[-53.55633,-68.21326,-45.16687,-31.85836], "fy":[95.68454,85.79521,99.81187,104.89589]}, - {"t":2.69059, "x":2.76774, "y":4.36623, "heading":3.06299, "vx":0.54861, "vy":-1.06627, "omega":0.60101, "ax":-2.92006, "ay":5.67336, "alpha":-2.97964, "fx":[-53.94144,-68.76874,-44.53424,-31.43299], "fy":[95.48387,85.3697,100.11458,105.0406]}, - {"t":2.71746, "x":2.78143, "y":4.33962, "heading":3.07915, "vx":0.47012, "vy":-0.91378, "omega":0.52092, "ax":-2.91844, "ay":5.67094, "alpha":-3.06448, "fx":[-54.29261,-69.25436,-43.94556,-31.07465], "fy":[95.29857,84.99323,100.39122,105.16156]}, - {"t":2.74434, "x":2.79301, "y":4.3171, "heading":3.09315, "vx":0.39167, "vy":-0.76135, "omega":0.43855, "ax":-2.91693, "ay":5.66873, "alpha":-3.14031, "fx":[-54.60683,-69.68237,-43.40859,-30.76648], "fy":[95.13118,84.65794,100.6397,105.26482]}, - {"t":2.77122, "x":2.80249, "y":4.29869, "heading":3.10494, "vx":0.31327, "vy":-0.60898, "omega":0.35414, "ax":-2.91552, "ay":5.66669, "alpha":-3.2083, "fx":[-54.88166,-70.06268,-42.92963,-30.49474], "fy":[94.98386,84.35729,100.85859,105.35511]}, - {"t":2.7981, "x":2.80985, "y":4.28437, "heading":3.11446, "vx":0.2349, "vy":-0.45666, "omega":0.26791, "ax":-2.91422, "ay":5.66481, "alpha":-3.26936, "fx":[-55.11508,-70.40332,-42.51388,-30.24814], "fy":[94.85844,84.0858,101.04691,105.43619]}, - {"t":2.82498, "x":2.81511, "y":4.27414, "heading":3.12166, "vx":0.15657, "vy":-0.3044, "omega":0.18003, "ax":-2.91303, "ay":5.66309, "alpha":-3.32422, "fx":[-55.30538,-70.71085,-42.16567,-30.01741], "fy":[94.75648,83.83891,101.20395,105.51108]}, - {"t":2.85186, "x":2.81827, "y":4.268, "heading":3.1265, "vx":0.07827, "vy":-0.15218, "omega":0.09068, "ax":-2.91194, "ay":5.66152, "alpha":-3.37343, "fx":[-55.45109,-70.99059,-41.88868,-29.79488], "fy":[94.67932,83.61282,101.32917,105.58219]}, - {"t":2.87874, "x":2.81932, "y":4.26596, "heading":3.12894, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[ - {"name":"Funnel", "from":{"target":2, "targetTimestamp":2.23364, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] -} diff --git a/src/main/deploy/choreo/A_LEFT_PATH4_ALT_ALT.traj b/src/main/deploy/choreo/A_LEFT_PATH4_ALT_ALT.traj deleted file mode 100644 index 5d00a649..00000000 --- a/src/main/deploy/choreo/A_LEFT_PATH4_ALT_ALT.traj +++ /dev/null @@ -1,136 +0,0 @@ -{ - "name":"A_LEFT_PATH4_ALT_ALT", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":3.692616224288941, "y":5.020236015319824, "heading":2.0948682307415045, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.3110252618789673, "y":7.185760498046875, "heading":2.216612130911823, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.7917816638946533, "y":6.376835346221924, "heading":0.0, "intervals":36, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":5.056673049926758, "y":5.405888557434082, "heading":1.092223810384809, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"3.6926162242889404 m", "val":3.692616224288941}, "y":{"exp":"5.020236015319824 m", "val":5.020236015319824}, "heading":{"exp":"2.0948682307415045 rad", "val":2.0948682307415045}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"7.185760498046875 m", "val":7.185760498046875}, "heading":{"exp":"2.216612130911823 rad", "val":2.216612130911823}, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.7917816638946533 m", "val":2.7917816638946533}, "y":{"exp":"6.376835346221924 m", "val":6.376835346221924}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":36, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"5.056673049926758 m", "val":5.056673049926758}, "y":{"exp":"5.405888557434082 m", "val":5.405888557434082}, "heading":{"exp":"1.092223810384809 rad", "val":1.092223810384809}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.42726,2.1948,3.0994], - "samples":[ - {"t":0.0, "x":3.69262, "y":5.02024, "heading":2.09487, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-4.77336, "ay":4.34029, "alpha":0.36517, "fx":[-82.80387,-80.3539,-79.60509,-82.01137], "fy":[72.03947,74.76071,75.56262,72.9455]}, - {"t":0.04325, "x":3.68815, "y":5.0243, "heading":2.09487, "vx":-0.20645, "vy":0.18772, "omega":0.01579, "ax":-4.77303, "ay":4.33999, "alpha":0.36029, "fx":[-82.77638,-80.35948,-79.62059,-81.99495], "fy":[72.05859,74.74258,75.53461,72.95195]}, - {"t":0.0865, "x":3.67476, "y":5.03647, "heading":2.09555, "vx":-0.41289, "vy":0.37543, "omega":0.03138, "ax":-4.77264, "ay":4.33963, "alpha":0.35461, "fx":[-82.74377,-80.3649,-79.63925,-81.97681], "fy":[72.08147,74.7226,75.50128,72.95832]}, - {"t":0.12975, "x":3.65244, "y":5.05677, "heading":2.09691, "vx":-0.6193, "vy":0.56312, "omega":0.04671, "ax":-4.77217, "ay":4.33921, "alpha":0.34789, "fx":[-82.70483,-80.37047,-79.66174,-81.95612], "fy":[72.10894,74.69987,75.4614,72.96497]}, - {"t":0.173, "x":3.62119, "y":5.08518, "heading":2.09893, "vx":-0.8257, "vy":0.75079, "omega":0.06176, "ax":-4.77161, "ay":4.33871, "alpha":0.33982, "fx":[-82.65783,-80.37666,-79.68899,-81.9317], "fy":[72.14215,74.67312,75.41319,72.97244]}, - {"t":0.21625, "x":3.58101, "y":5.12171, "heading":2.1016, "vx":-1.03208, "vy":0.93844, "omega":0.07646, "ax":-4.77093, "ay":4.33809, "alpha":0.32994, "fx":[-82.60029,-80.3841,-79.72234,-81.90188], "fy":[72.18278,74.64053,75.35412,72.98148]}, - {"t":0.2595, "x":3.53191, "y":5.16636, "heading":2.10491, "vx":-1.23842, "vy":1.12606, "omega":0.09073, "ax":-4.77007, "ay":4.33732, "alpha":0.31759, "fx":[-82.52847,-80.39377,-79.76384,-81.86414], "fy":[72.23331,74.59939,75.28035,72.99318]}, - {"t":0.30275, "x":3.47389, "y":5.21912, "heading":2.10883, "vx":-1.44473, "vy":1.31366, "omega":0.10446, "ax":-4.76896, "ay":4.33632, "alpha":0.3017, "fx":[-82.43651,-80.40713,-79.81665,-81.81452], "fy":[72.29765,74.54544,75.18582,73.0093]}, - {"t":0.346, "x":3.40694, "y":5.27999, "heading":2.11335, "vx":-1.65099, "vy":1.5012, "omega":0.11751, "ax":-4.76748, "ay":4.33498, "alpha":0.28048, "fx":[-82.31463,-80.4266,-79.88606,-81.7464], "fy":[72.38226,74.47165,75.06042,73.03267]}, - {"t":0.38925, "x":3.33108, "y":5.34897, "heading":2.11843, "vx":-1.85718, "vy":1.68869, "omega":0.12964, "ax":-4.76538, "ay":4.33309, "alpha":0.25074, "fx":[-82.14522,-80.45644,-79.98159,-81.64782], "fy":[72.4987,74.3654,74.88582,73.06841]}, - {"t":0.4325, "x":3.2463, "y":5.42606, "heading":2.12404, "vx":-2.06329, "vy":1.8761, "omega":0.14049, "ax":-4.7622, "ay":4.33022, "alpha":0.20608, "fx":[-81.89306,-80.50494,-80.1221,-81.49469], "fy":[72.66984,74.20164,74.62514,73.12662]}, - {"t":0.47575, "x":3.15261, "y":5.51125, "heading":2.13011, "vx":-2.26926, "vy":2.06338, "omega":0.1494, "ax":-4.75682, "ay":4.32536, "alpha":0.13158, "fx":[-81.47614,-80.59075,-80.35127,-81.23019], "fy":[72.94801,73.92248,74.19154,73.23063]}, - {"t":0.519, "x":3.05001, "y":5.60454, "heading":2.13658, "vx":-2.47499, "vy":2.25046, "omega":0.15509, "ax":-4.74572, "ay":4.31535, "alpha":-0.0174, "fx":[-80.64964,-80.76623,-80.79726,-80.68055], "fy":[73.48469,73.35701,73.32106,73.44898]}, - {"t":0.56226, "x":2.93853, "y":5.70591, "heading":2.14328, "vx":-2.68024, "vy":2.4371, "omega":0.15434, "ax":-4.71008, "ay":4.28318, "alpha":-0.46025, "fx":[-78.21717,-81.25126,-82.05793,-78.9421], "fy":[74.96378,71.68837,70.66649,74.10427]}, - {"t":0.60551, "x":2.8182, "y":5.81532, "heading":2.14996, "vx":-2.88396, "vy":2.62235, "omega":0.13443, "ax":-1.2157, "ay":1.10429, "alpha":-3.10111, "fx":[-17.91854,-31.3387,-23.99025,-9.46752], "fy":[30.0091,20.53234,7.30622,17.28692]}, - {"t":0.64876, "x":2.69233, "y":5.92977, "heading":2.15577, "vx":-2.93654, "vy":2.67011, "omega":0.00031, "ax":-0.00062, "ay":0.00028, "alpha":-0.00081, "fx":[-0.00992,-0.01341,-0.0111,-0.0076], "fy":[0.00772,0.0054,0.00191,0.00422]}, - {"t":0.69201, "x":2.56532, "y":6.04526, "heading":2.15579, "vx":-2.93656, "vy":2.67012, "omega":0.00027, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[-0.00001,-0.00001,-0.00001,-0.00001], "fy":[-0.00001,-0.00001,-0.00001,-0.00001]}, - {"t":0.73526, "x":2.43832, "y":6.16074, "heading":2.1558, "vx":-2.93656, "vy":2.67012, "omega":0.00027, "ax":0.00061, "ay":-0.00029, "alpha":0.00081, "fx":[0.00987,0.01336,0.01104,0.00755], "fy":[-0.00777,-0.00546,-0.00197,-0.00428]}, - {"t":0.77851, "x":2.31131, "y":6.27622, "heading":2.15581, "vx":-2.93654, "vy":2.67011, "omega":0.00031, "ax":1.21564, "ay":-1.10425, "alpha":3.09988, "fx":[17.98156,31.35145,23.92319,9.45426], "fy":[-30.01053,-20.4674,-7.29763,-17.35634]}, - {"t":0.82176, "x":2.18544, "y":6.39067, "heading":2.15582, "vx":-2.88396, "vy":2.62235, "omega":0.13438, "ax":4.71011, "ay":-4.2832, "alpha":0.4563, "fx":[78.24912,81.26521,82.02797,78.92834], "fy":[-74.9311,-71.67191,-70.70106,-74.12022]}, - {"t":0.86501, "x":2.06511, "y":6.50009, "heading":2.16164, "vx":-2.68025, "vy":2.4371, "omega":0.15411, "ax":4.74573, "ay":-4.31535, "alpha":0.01614, "fx":[80.65607,80.76491,80.79097,80.68202], "fy":[-73.47768,-73.35843,-73.32808,-73.44753]}, - {"t":0.90826, "x":1.95363, "y":6.60146, "heading":2.1683, "vx":-2.47499, "vy":2.25046, "omega":0.15481, "ax":4.75682, "ay":-4.32536, "alpha":-0.13197, "fx":[81.4654,80.56831,80.36251,81.25225], "fy":[-72.95981,-73.94707,-74.17961,-73.20607]}, - {"t":0.95151, "x":1.85104, "y":6.69474, "heading":2.175, "vx":-2.26926, "vy":2.06338, "omega":0.1491, "ax":4.7622, "ay":-4.33022, "alpha":-0.20605, "fx":[81.86727,80.45992,80.14932,81.5384], "fy":[-72.69857,-74.25068,-74.59625,-73.0777]}, - {"t":0.99476, "x":1.75734, "y":6.77993, "heading":2.18145, "vx":-2.06329, "vy":1.8761, "omega":0.14019, "ax":4.76538, "ay":-4.33309, "alpha":-0.25046, "fx":[82.10564,80.38905,80.0237,81.7128], "fy":[-72.54312,-74.43851,-74.8412,-72.9955]}, - {"t":1.03801, "x":1.67256, "y":6.85702, "heading":2.18751, "vx":-1.85718, "vy":1.68869, "omega":0.12936, "ax":4.76748, "ay":-4.33498, "alpha":-0.28003, "fx":[82.26239,80.33786,79.94201,81.83158], "fy":[-72.44118,-74.56765,-75.00125,-72.93696]}, - {"t":1.08126, "x":1.5967, "y":6.92601, "heading":2.1931, "vx":-1.65099, "vy":1.5012, "omega":0.11725, "ax":4.76897, "ay":-4.33632, "alpha":-0.30113, "fx":[82.37273,80.29854,79.88529,81.91843], "fy":[-72.36984,-74.6627,-75.11332,-72.89242]}, - {"t":1.12451, "x":1.52975, "y":6.98688, "heading":2.19817, "vx":-1.44473, "vy":1.31366, "omega":0.10423, "ax":4.77007, "ay":-4.33732, "alpha":-0.31695, "fx":[82.45429,80.2671,79.84396,81.98506], "fy":[-72.31749,-74.73597,-75.1958,-72.85708]}, - {"t":1.16776, "x":1.47173, "y":7.03964, "heading":2.20268, "vx":-1.23842, "vy":1.12607, "omega":0.09052, "ax":4.77093, "ay":-4.3381, "alpha":-0.32923, "fx":[82.51691,80.24134,79.81267,82.03791], "fy":[-72.2776,-74.79429,-75.25888,-72.82827]}, - {"t":1.21101, "x":1.42263, "y":7.08428, "heading":2.2066, "vx":-1.03208, "vy":0.93844, "omega":0.07628, "ax":4.77162, "ay":-4.33871, "alpha":-0.33906, "fx":[82.56647,80.21992,79.78819,82.08082], "fy":[-72.24622,-74.84177,-75.30866,-72.8044]}, - {"t":1.25426, "x":1.38245, "y":7.12081, "heading":2.2099, "vx":-0.8257, "vy":0.75079, "omega":0.06161, "ax":4.77218, "ay":-4.33922, "alpha":-0.34709, "fx":[82.60675,80.202,79.76843,82.11621], "fy":[-72.22081,-74.88101,-75.34903,-72.78449]}, - {"t":1.29751, "x":1.3512, "y":7.14923, "heading":2.21256, "vx":-0.6193, "vy":0.56312, "omega":0.0466, "ax":4.77264, "ay":-4.33964, "alpha":-0.35378, "fx":[82.64027,80.187,79.75202,82.1457], "fy":[-72.19966,-74.91375,-75.38256,-72.76786]}, - {"t":1.34076, "x":1.32888, "y":7.16952, "heading":2.21458, "vx":-0.41289, "vy":0.37543, "omega":0.0313, "ax":4.77303, "ay":-4.33999, "alpha":-0.35943, "fx":[82.66877,80.17455,79.73797,82.17038], "fy":[-72.18158,-74.94119,-75.41107,-72.75406]}, - {"t":1.38401, "x":1.31549, "y":7.1817, "heading":2.21593, "vx":-0.20645, "vy":0.18772, "omega":0.01576, "ax":4.77337, "ay":-4.34029, "alpha":-0.36428, "fx":[82.6935,80.16436,79.7256,82.19104], "fy":[-72.16572,-74.96417,-75.43584,-72.74277]}, - {"t":1.42726, "x":1.31103, "y":7.18576, "heading":2.21661, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.69543, "ay":-2.72937, "alpha":-4.29178, "fx":[108.41847,92.65459,84.41152,102.02591], "fy":[-16.62657,-58.6035,-70.08158,-40.39136]}, - {"t":1.45468, "x":1.31317, "y":7.18474, "heading":2.21661, "vx":0.15612, "vy":-0.07482, "omega":-0.11765, "ax":5.69903, "ay":-2.73025, "alpha":-4.22534, "fx":[108.33022,92.79401,84.64533,101.98581], "fy":[-17.13776,-58.36409,-69.78708,-40.47396]}, - {"t":1.48209, "x":1.31959, "y":7.18166, "heading":2.21339, "vx":0.31235, "vy":-0.14966, "omega":-0.23347, "ax":5.70306, "ay":-2.73123, "alpha":-4.14917, "fx":[108.22999,93.01099,84.87589,101.91296], "fy":[-17.70283,-57.99729,-69.49303,-40.63661]}, - {"t":1.5095, "x":1.33029, "y":7.17653, "heading":2.20699, "vx":0.46868, "vy":-0.22453, "omega":-0.34721, "ax":5.70753, "ay":-2.73233, "alpha":-4.06262, "fx":[108.11548,93.3003,85.11039,101.80793], "fy":[-18.32944,-57.50807,-69.19043,-40.87639]}, - {"t":1.53691, "x":1.34528, "y":7.16935, "heading":2.19747, "vx":0.62513, "vy":-0.29943, "omega":-0.45857, "ax":5.71245, "ay":-2.73354, "alpha":-3.96487, "fx":[107.98364,93.65588,85.35768,101.67129], "fy":[-19.02771,-56.90185,-68.86783,-41.18987]}, - {"t":1.56432, "x":1.36457, "y":7.16011, "heading":2.1849, "vx":0.78172, "vy":-0.37436, "omega":-0.56726, "ax":5.71781, "ay":-2.7349, "alpha":-3.85485, "fx":[107.83043,94.07065,85.62866,101.50367], "fy":[-19.81059,-56.18516,-68.51082,-41.57297]}, - {"t":1.59174, "x":1.38814, "y":7.14882, "heading":2.16935, "vx":0.93846, "vy":-0.44933, "omega":-0.67293, "ax":5.72363, "ay":-2.73642, "alpha":-3.73108, "fx":[107.65052,94.53626,85.93674,101.30588], "fy":[-20.69435,-55.36625,-68.10121,-42.0208]}, - {"t":1.61915, "x":1.41602, "y":7.13548, "heading":2.1509, "vx":1.09536, "vy":-0.52434, "omega":-0.77521, "ax":5.72992, "ay":-2.73812, "alpha":-3.59156, "fx":[107.43688,95.04284,86.29839,101.07897], "fy":[-21.69934,-54.45595,-67.61591,-42.52744]}, - {"t":1.64656, "x":1.4482, "y":7.12008, "heading":2.12965, "vx":1.25243, "vy":-0.5994, "omega":-0.87366, "ax":5.73668, "ay":-2.74006, "alpha":-3.43343, "fx":[107.17998,95.57876,86.73401,100.82449], "fy":[-22.85115,-53.46868,-67.02526,-43.08557]}, - {"t":1.67397, "x":1.48468, "y":7.10262, "heading":2.1057, "vx":1.40968, "vy":-0.67451, "omega":-0.96778, "ax":5.74393, "ay":-2.7423, "alpha":-3.25264, "fx":[106.86681,96.1303,87.26897,100.54466], "fy":[-24.18247,-52.42361,-66.29056,-43.68603]}, - {"t":1.70138, "x":1.52548, "y":7.0831, "heading":2.07918, "vx":1.56713, "vy":-0.74968, "omega":-1.05694, "ax":5.75169, "ay":-2.74489, "alpha":-3.0433, "fx":[106.47904,96.68136,87.93512,100.24277], "fy":[-25.73593,-51.34606,-65.36033,-44.31697]}, - {"t":1.7288, "x":1.5706, "y":7.06152, "heading":2.0502, "vx":1.7248, "vy":-0.82492, "omega":-1.14036, "ax":5.75994, "ay":-2.74792, "alpha":-2.79678, "fx":[105.99013,97.21305,88.7727,99.92371], "fy":[-27.56871,-50.26926,-64.16442,-44.96265]}, - {"t":1.75621, "x":1.62005, "y":7.03787, "heading":2.01894, "vx":1.88269, "vy":-0.90025, "omega":-1.21703, "ax":5.76863, "ay":-2.7514, "alpha":-2.50027, "fx":[105.36013,97.70304,89.83301,99.59491], "fy":[-29.76014,-49.23646,-62.60453,-45.60129]}, - {"t":1.78362, "x":1.67382, "y":7.01216, "heading":1.98558, "vx":2.04082, "vy":-0.97567, "omega":-1.28556, "ax":5.77758, "ay":-2.75531, "alpha":-2.13442, "fx":[104.52614,98.12456,91.1816,99.26787], "fy":[-32.42456,-48.30381,-60.53834,-46.20116]}, - {"t":1.81103, "x":1.73194, "y":6.98438, "heading":1.95034, "vx":2.1992, "vy":-1.0512, "omega":-1.34407, "ax":5.78626, "ay":-2.75936, "alpha":-1.66942, "fx":[103.38364,98.44448,92.90161,98.96108], "fy":[-35.73416,-47.54423,-57.75201,-46.71312]}, - {"t":1.83844, "x":1.7944, "y":6.95453, "heading":1.9135, "vx":2.35781, "vy":-1.12684, "omega":-1.38983, "ax":5.79327, "ay":-2.76282, "alpha":-1.05778, "fx":[101.74694,98.61991,95.09473,98.7058], "fy":[-39.96086,-47.05325,-53.91049,-47.0545]}, - {"t":1.86586, "x":1.86121, "y":6.9226, "heading":1.8754, "vx":2.51662, "vy":-1.20257, "omega":-1.41883, "ax":5.79492, "ay":-2.76385, "alpha":-0.22086, "fx":[99.25811,98.59174,97.87045,98.55931], "fy":[-45.55661,-46.95787,-48.46444,-47.07016]}, - {"t":1.89327, "x":1.93237, "y":6.8886, "heading":1.83651, "vx":2.67547, "vy":-1.27834, "omega":-1.42488, "ax":5.78136, "ay":-2.75773, "alpha":0.9787, "fx":[95.15429,98.27241,101.29051,98.63963], "fy":[-53.30858,-47.43081,-40.47275,-46.42036]}, - {"t":1.92068, "x":2.00788, "y":6.85252, "heading":1.79745, "vx":2.83395, "vy":-1.35393, "omega":-1.39806, "ax":5.72492, "ay":-2.7302, "alpha":2.79551, "fx":[87.6067,97.52225,105.15132,99.23704], "fy":[-64.59925,-48.71264,-28.28642,-44.16141]}, - {"t":1.94809, "x":2.08772, "y":6.81438, "heading":1.75912, "vx":2.99088, "vy":-1.42877, "omega":-1.32143, "ax":5.5469, "ay":-2.61628, "alpha":5.73283, "fx":[71.80278,96.10728,108.23559,101.2593], "fy":[-81.33589,-51.1353,-9.2585,-36.27903]}, - {"t":1.97551, "x":2.17179, "y":6.77423, "heading":1.7229, "vx":3.14293, "vy":-1.50049, "omega":-1.16428, "ax":5.03645, "ay":-1.84246, "alpha":11.39546, "fx":[40.70594,93.79304,107.0976,101.07798], "fy":[-100.00617,-54.81332,15.99903,13.4616]}, - {"t":2.00292, "x":2.25983, "y":6.73241, "heading":1.69099, "vx":3.28099, "vy":-1.551, "omega":-0.8519, "ax":4.82966, "ay":-1.68353, "alpha":12.591, "fx":[36.12063,92.14167,106.34395,93.99814], "fy":[-100.71097,-56.3884,15.91466,26.63934]}, - {"t":2.03033, "x":2.35159, "y":6.68926, "heading":1.66763, "vx":3.41338, "vy":-1.59714, "omega":-0.50676, "ax":4.62113, "ay":-1.78364, "alpha":12.43957, "fx":[34.60181,89.65226,104.42953,85.733], "fy":[-98.2217,-56.92656,13.0275,20.76373]}, - {"t":2.05774, "x":2.44689, "y":6.64481, "heading":1.65374, "vx":3.54006, "vy":-1.64604, "omega":-0.16576, "ax":1.76404, "ay":-1.58193, "alpha":5.81708, "fx":[15.18929,43.60969,46.4284,14.79605], "fy":[-45.69691,-38.2842,-9.29478,-14.35664]}, - {"t":2.08515, "x":2.54459, "y":6.59909, "heading":1.6492, "vx":3.58841, "vy":-1.6894, "omega":-0.0063, "ax":-0.15503, "ay":-0.35066, "alpha":0.02374, "fx":[-2.69363,-2.57066,-2.58043,-2.70362], "fy":[-6.03072,-6.02131,-5.89865,-5.90797]}, - {"t":2.11257, "x":2.6429, "y":6.55265, "heading":1.64902, "vx":3.58416, "vy":-1.69901, "omega":-0.00565, "ax":-0.07373, "ay":-0.15537, "alpha":0.0001, "fx":[-1.25433,-1.25381,-1.25386,-1.25437], "fy":[-2.64315,-2.64311,-2.64259,-2.64263]}, - {"t":2.13998, "x":2.74112, "y":6.50602, "heading":1.64887, "vx":3.58214, "vy":-1.70327, "omega":-0.00565, "ax":-0.03304, "ay":-0.06944, "alpha":0.00001, "fx":[-0.56205,-0.56199,-0.562,-0.56206], "fy":[-1.18126,-1.18126,-1.1812,-1.18121]}, - {"t":2.16739, "x":2.8393, "y":6.4593, "heading":1.64872, "vx":3.58124, "vy":-1.70518, "omega":-0.00565, "ax":-0.01471, "ay":-0.03088, "alpha":0.0, "fx":[-0.25014,-0.25012,-0.25012,-0.25014], "fy":[-0.52519,-0.52519,-0.52518,-0.52518]}, - {"t":2.1948, "x":2.93747, "y":6.41255, "heading":1.64856, "vx":3.58083, "vy":-1.70602, "omega":-0.00565, "ax":-0.00637, "ay":-0.01338, "alpha":0.0, "fx":[-0.10841,-0.10841,-0.10841,-0.10841], "fy":[-0.22752,-0.22752,-0.22753,-0.22753]}, - {"t":2.22221, "x":3.03562, "y":6.36577, "heading":1.64841, "vx":3.58066, "vy":-1.70639, "omega":-0.00565, "ax":-0.00239, "ay":-0.005, "alpha":0.0, "fx":[-0.04057,-0.04058,-0.04058,-0.04057], "fy":[-0.08513,-0.08513,-0.08514,-0.08514]}, - {"t":2.24963, "x":3.13378, "y":6.319, "heading":1.64825, "vx":3.58059, "vy":-1.70653, "omega":-0.00565, "ax":-0.00002, "ay":-0.00005, "alpha":0.0, "fx":[-0.00039,-0.00041,-0.00041,-0.00039], "fy":[-0.00083,-0.00083,-0.00084,-0.00084]}, - {"t":2.27704, "x":3.23193, "y":6.27222, "heading":1.6481, "vx":3.58059, "vy":-1.70653, "omega":-0.00565, "ax":0.00232, "ay":0.00487, "alpha":0.0, "fx":[0.03951,0.03949,0.03949,0.03951], "fy":[0.08291,0.0829,0.08289,0.08289]}, - {"t":2.30445, "x":3.33008, "y":6.22544, "heading":1.64794, "vx":3.58066, "vy":-1.70639, "omega":-0.00565, "ax":0.00625, "ay":0.01312, "alpha":-0.00001, "fx":[0.10635,0.10633,0.10633,0.10636], "fy":[0.2232,0.2232,0.22317,0.22317]}, - {"t":2.33186, "x":3.42824, "y":6.17867, "heading":1.64779, "vx":3.58083, "vy":-1.70604, "omega":-0.00565, "ax":0.01444, "ay":0.03032, "alpha":-0.00001, "fx":[0.24567,0.24563,0.24563,0.24567], "fy":[0.5158,0.5158,0.51575,0.51576]}, - {"t":2.35927, "x":3.5264, "y":6.13191, "heading":1.64763, "vx":3.58122, "vy":-1.7052, "omega":-0.00565, "ax":0.03246, "ay":0.06822, "alpha":-0.00002, "fx":[0.55213,0.55205,0.55206,0.55214], "fy":[1.16038,1.16037,1.16029,1.1603]}, - {"t":2.38669, "x":3.62458, "y":6.0852, "heading":1.64748, "vx":3.58211, "vy":-1.70333, "omega":-0.00565, "ax":0.07244, "ay":0.15263, "alpha":-0.00009, "fx":[1.23234,1.23185,1.23189,1.23238], "fy":[2.59649,2.59646,2.59597,2.596]}, - {"t":2.4141, "x":3.7228, "y":6.03856, "heading":1.64732, "vx":3.5841, "vy":-1.69915, "omega":-0.00565, "ax":0.15343, "ay":0.344, "alpha":-0.02029, "fx":[2.65818,2.55313,2.56121,2.66651], "fy":[5.90767,5.8998,5.79493,5.80271]}, - {"t":2.44151, "x":3.82111, "y":5.99211, "heading":1.64717, "vx":3.5883, "vy":-1.68972, "omega":-0.00621, "ax":-1.55776, "ay":1.50469, "alpha":-5.2689, "fx":[-13.08145,-39.15723,-41.26543,-12.4841], "fy":[42.07515,36.23238,10.00466,14.06494]}, - {"t":2.46892, "x":3.91888, "y":5.94636, "heading":1.647, "vx":3.5456, "vy":-1.64847, "omega":-0.15064, "ax":-4.61299, "ay":1.78453, "alpha":-12.52758, "fx":[-34.14673,-89.08014,-104.5332,-86.10274], "fy":[98.216,57.70535,-11.86425,-22.6396]}, - {"t":2.49633, "x":4.01434, "y":5.90184, "heading":1.64287, "vx":3.41915, "vy":-1.59956, "omega":-0.49405, "ax":-4.80874, "ay":1.69118, "alpha":-12.86503, "fx":[-35.24099,-90.94095,-106.74446,-94.25492], "fy":[100.90695,58.26484,-13.15086,-30.95476]}, - {"t":2.52375, "x":4.10626, "y":5.85863, "heading":1.62932, "vx":3.28733, "vy":-1.5532, "omega":-0.84671, "ax":-5.07727, "ay":1.96185, "alpha":-11.17081, "fx":[-42.65255,-91.79888,-107.97237,-103.02763], "fy":[99.06016,58.04584,-8.73312,-14.89081]}, - {"t":2.55116, "x":4.19447, "y":5.81679, "heading":1.60611, "vx":3.14816, "vy":-1.49942, "omega":-1.15292, "ax":-5.58582, "ay":2.63144, "alpha":-5.30741, "fx":[-74.8056,-94.20042,-107.522,-103.52493], "fy":[78.50076,54.53275,15.85043,30.15597]}, - {"t":2.57857, "x":4.27867, "y":5.77668, "heading":1.57451, "vx":2.99504, "vy":-1.42729, "omega":-1.29841, "ax":-5.73822, "ay":2.73357, "alpha":-2.47919, "fx":[-89.27474,-96.06781,-104.1425,-100.93701], "fy":[62.23397,51.5049,31.94011,40.31014]}, - {"t":2.60598, "x":4.35861, "y":5.73858, "heading":1.53892, "vx":2.83774, "vy":-1.35235, "omega":-1.36637, "ax":-5.78466, "ay":2.75721, "alpha":-0.81344, "fx":[-95.90386,-97.60116,-100.68927,-99.38729], "fy":[51.94385,48.79656,42.00073,44.85622]}, - {"t":2.6334, "x":4.43422, "y":5.70255, "heading":1.50146, "vx":2.67917, "vy":-1.27677, "omega":-1.38867, "ax":-5.79581, "ay":2.76255, "alpha":0.27057, "fx":[-99.35763,-98.92508,-97.79038,-98.26687], "fy":[45.36644,46.2657,48.63213,47.69632]}, - {"t":2.66081, "x":4.50549, "y":5.66859, "heading":1.4634, "vx":2.52029, "vy":-1.20104, "omega":-1.38125, "ax":-5.79449, "ay":2.76189, "alpha":1.03192, "fx":[-101.34719,-100.09318,-95.46139,-97.34886], "fy":[41.0188,43.86015,53.2341,49.80293]}, - {"t":2.68822, "x":4.5724, "y":5.6367, "heading":1.42553, "vx":2.36146, "vy":-1.12534, "omega":-1.35296, "ax":-5.78867, "ay":2.75892, "alpha":1.59912, "fx":[-102.57626,-101.13044,-93.60499,-96.54274], "fy":[38.06768,41.56724,56.5596,51.51927]}, - {"t":2.71563, "x":4.63496, "y":5.60689, "heading":1.38845, "vx":2.20278, "vy":-1.04971, "omega":-1.30913, "ax":-5.78132, "ay":2.75506, "alpha":2.04127, "fx":[-103.37187,-102.05077,-92.12309,-95.8084], "fy":[36.03204,39.38999,59.03589,52.99288]}, - {"t":2.74304, "x":4.69317, "y":5.57915, "heading":1.35256, "vx":2.0443, "vy":-0.97419, "omega":-1.25317, "ax":-5.77361, "ay":2.75095, "alpha":2.39803, "fx":[-103.90235,-102.86414,-90.93646,-95.12686], "fy":[34.61918,37.33626,60.92025,54.29588]}, - {"t":2.77046, "x":4.74704, "y":5.55348, "heading":1.31821, "vx":1.88603, "vy":-0.89878, "omega":-1.18744, "ax":-5.76603, "ay":2.74694, "alpha":2.69342, "fx":[-104.26184,-103.57938,-89.98384,-94.48896], "fy":[33.64142,35.4139,62.37659,55.46687]}, - {"t":2.79787, "x":4.79657, "y":5.52987, "heading":1.28566, "vx":1.72797, "vy":-0.82348, "omega":-1.1136, "ax":-5.75877, "ay":2.7432, "alpha":2.94268, "fx":[-104.50677,-104.20514,-89.21774,-93.89045], "fy":[32.97271,33.62853,63.51491,56.52801]}, - {"t":2.82528, "x":4.84177, "y":5.50833, "heading":1.25513, "vx":1.57011, "vy":-0.74828, "omega":-1.03294, "ax":-5.75191, "ay":2.73981, "alpha":3.15597, "fx":[-104.67306,-104.75008,-88.60063,-93.32964], "fy":[32.52496,31.9829,64.41259,57.49284]}, - {"t":2.85269, "x":4.88265, "y":5.48885, "heading":1.22682, "vx":1.41244, "vy":-0.67318, "omega":-0.94643, "ax":-5.74548, "ay":2.73679, "alpha":3.34036, "fx":[-104.78477,-105.22273,-88.10214,-92.80615], "fy":[32.23448,30.47685,65.1265,58.37007]}, - {"t":2.8801, "x":4.91921, "y":5.47142, "heading":1.20087, "vx":1.25495, "vy":-0.59816, "omega":-0.85486, "ax":-5.73948, "ay":2.73413, "alpha":3.50104, "fx":[-104.85875,-105.63127,-87.69711,-92.32034], "fy":[32.0539,29.10777,65.70008,59.16562]}, - {"t":2.90752, "x":4.95146, "y":5.45605, "heading":1.17744, "vx":1.09761, "vy":-0.52321, "omega":-0.75889, "ax":-5.7339, "ay":2.73181, "alpha":3.64197, "fx":[-104.90732,-105.98337,-87.36426,-91.87292], "fy":[31.94712,27.8711,66.16762,59.88372]}, - {"t":2.93493, "x":4.97939, "y":5.44274, "heading":1.15664, "vx":0.94044, "vy":-0.44832, "omega":-0.65906, "ax":-5.72872, "ay":2.72979, "alpha":3.76631, "fx":[-104.93975,-106.28605,-87.08537,-91.46472], "fy":[31.8861,26.76092,66.55695,60.5275]}, - {"t":2.96234, "x":5.00302, "y":5.43147, "heading":1.13857, "vx":0.7834, "vy":-0.37349, "omega":-0.55581, "ax":-5.72394, "ay":2.728, "alpha":3.87665, "fx":[-104.96323,-106.54556,-86.84464,-91.09666], "fy":[31.84867,25.7706,66.89109,61.09938]}, - {"t":2.98975, "x":5.02234, "y":5.42226, "heading":1.12333, "vx":0.6265, "vy":-0.29871, "omega":-0.44955, "ax":-5.71951, "ay":2.7264, "alpha":3.97517, "fx":[-104.98348,-106.76739,-86.62836,-90.76964], "fy":[31.8171,24.8932,67.18934,61.6012]}, - {"t":3.01716, "x":5.03736, "y":5.4151, "heading":1.11101, "vx":0.46971, "vy":-0.22398, "omega":-0.34058, "ax":-5.71542, "ay":2.72493, "alpha":4.06371, "fx":[-105.00507,-106.95629,-86.42461,-90.48453], "fy":[31.77704,24.12201,67.468,62.0344]}, - {"t":3.04458, "x":5.04809, "y":5.40998, "heading":1.10167, "vx":0.31304, "vy":-0.14928, "omega":-0.22919, "ax":-5.71164, "ay":2.72357, "alpha":4.14385, "fx":[-105.03173,-107.11622,-86.22311,-90.2422], "fy":[31.71675,23.45084,67.74073,62.4]}, - {"t":3.07199, "x":5.05453, "y":5.40691, "heading":1.09539, "vx":0.15647, "vy":-0.07462, "omega":-0.11559, "ax":-5.70814, "ay":2.72225, "alpha":4.2169, "fx":[-105.06645,-107.25048,-86.0151,-90.04352], "fy":[31.6266,22.87437,68.0189,62.69867]}, - {"t":3.0994, "x":5.05667, "y":5.40589, "heading":1.09222, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[ - {"name":"Funnel", "from":{"target":2, "targetTimestamp":2.1948, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] -} diff --git a/src/main/deploy/choreo/A_LEFT_PATH_ALT3.traj b/src/main/deploy/choreo/A_LEFT_PATH_ALT3.traj deleted file mode 100644 index a2dddcdd..00000000 --- a/src/main/deploy/choreo/A_LEFT_PATH_ALT3.traj +++ /dev/null @@ -1,130 +0,0 @@ -{ - "name":"A_LEFT_PATH_ALT3", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":3.999176502227783, "y":5.206205368041992, "heading":2.1010083691287966, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.3110252618789673, "y":7.185760498046875, "heading":2.216612130911823, "intervals":34, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.9979817867279053, "y":5.904665946960449, "heading":0.0, "intervals":40, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":2.819322109222412, "y":4.265955924987793, "heading":3.1289351796122347, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"3.999176502227783 m", "val":3.999176502227783}, "y":{"exp":"5.206205368041992 m", "val":5.206205368041992}, "heading":{"exp":"2.1010083691287966 rad", "val":2.1010083691287966}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"7.185760498046875 m", "val":7.185760498046875}, "heading":{"exp":"2.216612130911823 rad", "val":2.216612130911823}, "intervals":34, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.9979817867279053 m", "val":1.9979817867279053}, "y":{"exp":"5.904665946960449 m", "val":5.904665946960449}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":40, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"2.819322109222412 m", "val":2.819322109222412}, "y":{"exp":"4.265955924987793 m", "val":4.265955924987793}, "heading":{"exp":"3.1289351796122347 rad", "val":3.1289351796122347}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.45694,2.14306,2.90835], - "samples":[ - {"t":0.0, "x":3.99918, "y":5.20621, "heading":2.10101, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.19496, "ay":3.82555, "alpha":0.39071, "fx":[-89.94595,-87.72831,-86.79243,-88.99263], "fy":[62.89889,65.95408,67.18673,64.24646]}, - {"t":0.04415, "x":3.99411, "y":5.20993, "heading":2.10101, "vx":-0.22936, "vy":0.1689, "omega":0.01725, "ax":-5.1946, "ay":3.82528, "alpha":0.38384, "fx":[-89.91168,-87.73324,-86.81393,-88.97553], "fy":[62.93309,65.93326,67.14531,64.25605]}, - {"t":0.0883, "x":3.97892, "y":5.22112, "heading":2.10177, "vx":-0.45869, "vy":0.33778, "omega":0.0342, "ax":-5.19416, "ay":3.82496, "alpha":0.37576, "fx":[-89.87093,-87.73784,-86.8397,-88.95649], "fy":[62.97391,65.91036,67.09591,64.26579]}, - {"t":0.13245, "x":3.95361, "y":5.23976, "heading":2.10328, "vx":-0.68801, "vy":0.50665, "omega":0.05079, "ax":-5.19365, "ay":3.82458, "alpha":0.36611, "fx":[-89.82196,-87.74247,-86.8708,-88.93454], "fy":[63.02302,65.88419,67.03642,64.27632]}, - {"t":0.1766, "x":3.91817, "y":5.26585, "heading":2.10552, "vx":-0.91731, "vy":0.6755, "omega":0.06695, "ax":-5.19302, "ay":3.82411, "alpha":0.35438, "fx":[-89.76229,-87.74764,-86.90873,-88.90824], "fy":[63.08283,65.85302,66.96386,64.28854]}, - {"t":0.22075, "x":3.87261, "y":5.29941, "heading":2.10848, "vx":-1.14658, "vy":0.84434, "omega":0.0826, "ax":-5.19223, "ay":3.82353, "alpha":0.33984, "fx":[-89.68826,-87.75407,-86.95571,-88.87549], "fy":[63.15689,65.81433,66.87378,64.3038]}, - {"t":0.2649, "x":3.81693, "y":5.34041, "heading":2.11212, "vx":-1.37582, "vy":1.01314, "omega":0.0976, "ax":-5.19123, "ay":3.82279, "alpha":0.32132, "fx":[-89.59419,-87.7629,-87.01517,-88.83305], "fy":[63.25069,65.76426,66.75929,64.32412]}, - {"t":0.30905, "x":3.75113, "y":5.38886, "heading":2.11643, "vx":-1.60501, "vy":1.18192, "omega":0.11178, "ax":-5.1899, "ay":3.82181, "alpha":0.29693, "fx":[-89.47081,-87.77588,-87.09267,-88.77563], "fy":[63.3731,65.69657,66.6091,64.35282]}, - {"t":0.3532, "x":3.67521, "y":5.44477, "heading":2.12137, "vx":-1.83414, "vy":1.35065, "omega":0.12489, "ax":-5.18806, "ay":3.82045, "alpha":0.26338, "fx":[-89.30191,-87.79606,-87.19795,-88.69391], "fy":[63.53962,65.60043,66.40339,64.39564]}, - {"t":0.39735, "x":3.58918, "y":5.50812, "heading":2.12688, "vx":-2.06319, "vy":1.51932, "omega":0.13652, "ax":-5.18534, "ay":3.81844, "alpha":0.21432, "fx":[-89.05627,-87.82908,-87.34962,-88.5699], "fy":[63.77976,65.45524,66.1038,64.46357]}, - {"t":0.4415, "x":3.49304, "y":5.57892, "heading":2.13291, "vx":-2.29212, "vy":1.6879, "omega":0.14598, "ax":-5.18092, "ay":3.81517, "alpha":0.13577, "fx":[-88.66516,-87.88696,-87.58829,-88.36357], "fy":[64.15767,65.2163,65.62522,64.58079]}, - {"t":0.48565, "x":3.38679, "y":5.65716, "heading":2.13935, "vx":-2.52085, "vy":1.85634, "omega":0.15198, "ax":-5.17248, "ay":3.80893, "alpha":-0.01024, "fx":[-87.94194,-88.00063,-88.02274,-87.96403], "fy":[64.84395,64.76463,64.73368,64.81307]}, - {"t":0.52979, "x":3.27046, "y":5.74283, "heading":2.14606, "vx":-2.74922, "vy":2.02451, "omega":0.15153, "ax":-5.15007, "ay":3.79238, "alpha":-0.3759, "fx":[-86.14022,-88.28249,-89.07485,-86.9075], "fy":[66.49212,63.6417,62.46831,65.42703]}, - {"t":0.57394, "x":3.14406, "y":5.83591, "heading":2.15275, "vx":-2.97659, "vy":2.19194, "omega":0.13493, "ax":-4.94016, "ay":3.64082, "alpha":-3.01549, "fx":[-73.70551,-89.71966,-95.22365,-77.47397], "fy":[76.01416,56.75556,44.70381,70.24384]}, - {"t":0.61809, "x":3.00783, "y":5.93623, "heading":2.15871, "vx":-3.1947, "vy":2.35268, "omega":0.0018, "ax":-0.03066, "ay":0.02067, "alpha":-0.03411, "fx":[-0.4969,-0.64427,-0.54605,-0.39867], "fy":[0.47431,0.37608,0.22871,0.32694]}, - {"t":0.66224, "x":2.86676, "y":6.04012, "heading":2.15879, "vx":-3.19605, "vy":2.35359, "omega":0.00029, "ax":-0.0002, "ay":-0.00025, "alpha":-0.00001, "fx":[-0.00334,-0.00337,-0.00335,-0.00331], "fy":[-0.00418,-0.0042,-0.00423,-0.00421]}, - {"t":0.70639, "x":2.72565, "y":6.14403, "heading":2.1588, "vx":-3.19606, "vy":2.35358, "omega":0.00029, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[-0.00001,-0.00001,-0.00001,-0.00001]}, - {"t":0.75054, "x":2.58455, "y":6.24794, "heading":2.15882, "vx":-3.19606, "vy":2.35358, "omega":0.00029, "ax":0.0002, "ay":0.00025, "alpha":0.00001, "fx":[0.00331,0.00335,0.00333,0.00329], "fy":[0.00415,0.00417,0.0042,0.00418]}, - {"t":0.79469, "x":2.44344, "y":6.35185, "heading":2.15883, "vx":-3.19605, "vy":2.35359, "omega":0.00029, "ax":0.03065, "ay":-0.02067, "alpha":0.03409, "fx":[0.49673,0.64398,0.54582,0.39857], "fy":[-0.47429,-0.37611,-0.22887,-0.32705]}, - {"t":0.83884, "x":2.30237, "y":6.45574, "heading":2.15884, "vx":-3.1947, "vy":2.35268, "omega":0.0018, "ax":4.94017, "ay":-3.64081, "alpha":3.01523, "fx":[73.7617,89.77041,95.19886,77.3926], "fy":[-75.96371,-56.67141,-44.74216,-70.33939]}, - {"t":0.88299, "x":2.16614, "y":6.55606, "heading":2.15892, "vx":-2.97659, "vy":2.19194, "omega":0.13492, "ax":5.15007, "ay":-3.79238, "alpha":0.37551, "fx":[86.1513,88.29998,89.06494,86.88884], "fy":[-66.47819,-63.61711,-62.48186,-65.45206]}, - {"t":0.92714, "x":2.03974, "y":6.64914, "heading":2.16488, "vx":-2.74922, "vy":2.02451, "omega":0.1515, "ax":5.17248, "ay":-3.80893, "alpha":0.01011, "fx":[87.94293,88.0014,88.02174,87.96325], "fy":[-64.84262,-64.76357,-64.73501,-64.81414]}, - {"t":0.97129, "x":1.92341, "y":6.7348, "heading":2.17157, "vx":-2.52085, "vy":1.85634, "omega":0.15194, "ax":5.18092, "ay":-3.81517, "alpha":-0.13579, "fx":[88.65587,87.86604,87.59805,88.384], "fy":[-64.17027,-65.24458,-65.61241,-64.55271]}, - {"t":1.01544, "x":1.81716, "y":6.81304, "heading":2.17828, "vx":-2.29212, "vy":1.6879, "omega":0.14595, "ax":5.18534, "ay":-3.81844, "alpha":-0.21429, "fx":[89.03677,87.78499,87.37069,88.6124], "fy":[-63.8066,-65.51453,-66.07628,-64.40497]}, - {"t":1.05959, "x":1.72102, "y":6.88384, "heading":2.18472, "vx":-2.06319, "vy":1.51932, "omega":0.13649, "ax":5.18806, "ay":-3.82045, "alpha":-0.26332, "fx":[89.2726,87.72899,87.23022,88.75802], "fy":[-63.58034,-65.69031,-66.36141,-64.30703]}, - {"t":1.10374, "x":1.63499, "y":6.9472, "heading":2.19074, "vx":-1.83414, "vy":1.35065, "omega":0.12486, "ax":5.1899, "ay":-3.82181, "alpha":-0.29685, "fx":[89.43228,87.68691,87.13562,88.8602], "fy":[-63.42695,-65.81551,-66.55338,-64.23577]}, - {"t":1.14789, "x":1.55907, "y":7.0031, "heading":2.19626, "vx":-1.60501, "vy":1.18192, "omega":0.11176, "ax":5.19123, "ay":-3.82279, "alpha":-0.32123, "fx":[89.54719,87.65365,87.06802,88.93646], "fy":[-63.31666,-65.91005,-66.69084,-64.18083]}, - {"t":1.19204, "x":1.49327, "y":7.05156, "heading":2.20119, "vx":-1.37582, "vy":1.01314, "omega":0.09757, "ax":5.19223, "ay":-3.82353, "alpha":-0.33974, "fx":[89.63365,87.62654,87.01754,88.99583], "fy":[-63.23381,-65.9843,-66.79382,-64.1369]}, - {"t":1.23619, "x":1.43759, "y":7.09256, "heading":2.2055, "vx":-1.14658, "vy":0.84434, "omega":0.08257, "ax":5.19302, "ay":-3.82411, "alpha":-0.35429, "fx":[89.70101,87.60405,86.97847,89.04339], "fy":[-63.16937,-66.04417,-66.87376,-64.10098]}, - {"t":1.28034, "x":1.39203, "y":7.12611, "heading":2.20914, "vx":-0.91731, "vy":0.6755, "omega":0.06693, "ax":5.19365, "ay":-3.82458, "alpha":-0.36601, "fx":[89.75501,87.58526,86.9473,89.08222], "fy":[-63.11777,-66.0933,-66.93766,-64.07124]}, - {"t":1.32449, "x":1.35659, "y":7.15221, "heading":2.2121, "vx":-0.68801, "vy":0.50665, "omega":0.05077, "ax":5.19416, "ay":-3.82496, "alpha":-0.37566, "fx":[89.79937,87.56957,86.92175,89.11431], "fy":[-63.07537,-66.13402,-66.99006,-64.04655]}, - {"t":1.36864, "x":1.33128, "y":7.17085, "heading":2.21434, "vx":-0.45869, "vy":0.33778, "omega":0.03419, "ax":5.1946, "ay":-3.82528, "alpha":-0.38375, "fx":[89.83661,87.55659,86.90024,89.14098], "fy":[-63.03969,-66.16791,-67.03403,-64.02611]}, - {"t":1.41279, "x":1.31609, "y":7.18203, "heading":2.21585, "vx":-0.22936, "vy":0.1689, "omega":0.01725, "ax":5.19496, "ay":-3.82555, "alpha":-0.39062, "fx":[89.8685,87.54604,86.88169,89.16314], "fy":[-63.009,-66.19607,-67.07171,-64.0094]}, - {"t":1.45694, "x":1.31103, "y":7.18576, "heading":2.21661, "vx":0.0, "vy":0.0, "omega":0.0, "ax":2.91839, "ay":-5.65805, "alpha":3.40262, "fx":[39.48205,65.02586,64.61227,29.44361], "fy":[-102.36619,-88.36314,-88.59594,-105.64181]}, - {"t":1.48332, "x":1.31204, "y":7.18379, "heading":2.21661, "vx":0.07701, "vy":-0.14931, "omega":0.08979, "ax":2.91913, "ay":-5.66, "alpha":3.34887, "fx":[39.6176,64.83716,64.36044,29.79895], "fy":[-102.30624,-88.49267,-88.76799,-105.53318]}, - {"t":1.50971, "x":1.31509, "y":7.17788, "heading":2.21898, "vx":0.15405, "vy":-0.29868, "omega":0.17817, "ax":2.91996, "ay":-5.6621, "alpha":3.2894, "fx":[39.80559,64.65602,64.04562,30.16369], "fy":[-102.22492,-88.61512,-88.98326,-105.41983]}, - {"t":1.5361, "x":1.32017, "y":7.16803, "heading":2.22368, "vx":0.2311, "vy":-0.4481, "omega":0.26497, "ax":2.92089, "ay":-5.66437, "alpha":3.22353, "fx":[40.04574,64.47722,63.66661,30.5443], "fy":[-102.12189,-88.7342,-89.24148,-105.29966]}, - {"t":1.56249, "x":1.32729, "y":7.15423, "heading":2.23068, "vx":0.30819, "vy":-0.59758, "omega":0.35004, "ax":2.9219, "ay":-5.66681, "alpha":3.15043, "fx":[40.33789,64.29435,63.22173,30.94889], "fy":[-101.99663,-88.85439,-89.54248,-105.16994]}, - {"t":1.58888, "x":1.33644, "y":7.13649, "heading":2.23991, "vx":0.38529, "vy":-0.74712, "omega":0.43318, "ax":2.923, "ay":-5.66945, "alpha":3.06905, "fx":[40.682,64.09947,62.70886,31.38735], "fy":[-101.84843,-88.98114,-89.88613,-105.02725]}, - {"t":1.61527, "x":1.34762, "y":7.1148, "heading":2.25134, "vx":0.46243, "vy":-0.89673, "omega":0.51417, "ax":2.92418, "ay":-5.6723, "alpha":2.97813, "fx":[41.07821,63.88275,62.12549,31.87171], "fy":[-101.67637,-89.12112,-90.27228,-104.86723]}, - {"t":1.64166, "x":1.36085, "y":7.08916, "heading":2.26491, "vx":0.5396, "vy":-1.04642, "omega":0.59276, "ax":2.92545, "ay":-5.67539, "alpha":2.87607, "fx":[41.5269,63.6319,61.46878,32.41657], "fy":[-101.47926,-89.28251,-90.70066,-104.68437]}, - {"t":1.66805, "x":1.3761, "y":7.05957, "heading":2.28056, "vx":0.6168, "vy":-1.19619, "omega":0.66866, "ax":2.92679, "ay":-5.67872, "alpha":2.76088, "fx":[42.02873,63.33136,60.73568,33.03977], "fy":[-101.25558,-89.47544,-91.17078,-104.47163]}, - {"t":1.69444, "x":1.3934, "y":7.02602, "heading":2.2982, "vx":0.69403, "vy":-1.34605, "omega":0.74152, "ax":2.92821, "ay":-5.68231, "alpha":2.62994, "fx":[42.58483,62.96117,59.92292,33.76328], "fy":[-101.00335,-89.71264,-91.68186,-104.21987]}, - {"t":1.72083, "x":1.41273, "y":6.98852, "heading":2.31777, "vx":0.77131, "vy":-1.496, "omega":0.81092, "ax":2.92971, "ay":-5.68616, "alpha":2.47986, "fx":[43.19701,62.49514,59.02714,34.61467], "fy":[-100.71998,-90.01029,-92.23273,-103.91693]}, - {"t":1.74722, "x":1.43411, "y":6.94706, "heading":2.33917, "vx":0.84862, "vy":-1.64606, "omega":0.87636, "ax":2.93127, "ay":-5.69027, "alpha":2.30599, "fx":[43.86815,61.89823,58.04489,35.62917], "fy":[-100.40192,-90.38927,-92.82174,-103.54634]}, - {"t":1.77361, "x":1.45752, "y":6.90164, "heading":2.3623, "vx":0.92598, "vy":-1.79622, "omega":0.93721, "ax":2.93289, "ay":-5.69458, "alpha":2.10192, "fx":[44.60285,61.12215,56.97259,36.85291], "fy":[-100.04419,-90.87701,-93.44675,-103.08498]}, - {"t":1.8, "x":1.48298, "y":6.85226, "heading":2.38703, "vx":1.00337, "vy":-1.9465, "omega":0.99268, "ax":2.93452, "ay":-5.69901, "alpha":1.85844, "fx":[45.40861,60.09823,55.8064,38.34811], "fy":[-99.63944,-91.5103,-94.10506,-102.49939]}, - {"t":1.82639, "x":1.51048, "y":6.79891, "heading":2.41322, "vx":1.08081, "vy":-2.09689, "omega":1.04173, "ax":2.93606, "ay":-5.70334, "alpha":1.56188, "fx":[46.29793,58.72498,54.54179,40.20141], "fy":[-99.1763,-92.33952,-94.79355,-101.73909]}, - {"t":1.85278, "x":1.54003, "y":6.74159, "heading":2.44072, "vx":1.15829, "vy":-2.2474, "omega":1.08294, "ax":2.93727, "ay":-5.7071, "alpha":1.19118, "fx":[47.29253,56.84547,53.17277,42.53788], "fy":[-98.63604,-93.43521,-95.50878,-100.72438]}, - {"t":1.87917, "x":1.57162, "y":6.68029, "heading":2.46929, "vx":1.23581, "vy":-2.39801, "omega":1.11438, "ax":2.9376, "ay":-5.70928, "alpha":0.7124, "fx":[48.43201,54.20329,51.69022,45.54549], "fy":[-97.98548,-94.89786,-96.24747,-99.32232]}, - {"t":1.90556, "x":1.60525, "y":6.61502, "heading":2.4987, "vx":1.31333, "vy":-2.54867, "omega":1.13318, "ax":2.93572, "ay":-5.70754, "alpha":0.06775, "fx":[49.79433,50.35081,50.07865,49.51894], "fy":[-97.16003,-96.87068,-97.00719,-97.29627]}, - {"t":1.93194, "x":1.64093, "y":6.54578, "heading":2.52861, "vx":1.3908, "vy":-2.69929, "omega":1.13497, "ax":2.92833, "ay":-5.69586, "alpha":-0.84792, "fx":[51.55043,44.44059,48.30972,54.93974], "fy":[-96.0166,-99.54477,-97.78779,-94.19046]}, - {"t":1.95833, "x":1.67865, "y":6.47256, "heading":2.55856, "vx":1.46808, "vy":-2.8496, "omega":1.11259, "ax":2.9071, "ay":-5.6569, "alpha":-2.24194, "fx":[54.14386,34.70909,46.32882,62.61428], "fy":[-94.16971,-103.0837,-98.59387,-89.04167]}, - {"t":1.98472, "x":1.71841, "y":6.39539, "heading":2.58792, "vx":1.54479, "vy":-2.99888, "omega":1.05343, "ax":2.85299, "ay":-5.52938, "alpha":-4.56218, "fx":[59.10984,17.16539,44.02846,73.81081], "fy":[-90.15708,-107.00648,-99.43786,-79.61144]}, - {"t":2.01111, "x":1.76017, "y":6.31433, "heading":2.61572, "vx":1.62008, "vy":-3.1448, "omega":0.93303, "ax":2.79815, "ay":-4.98803, "alpha":-9.01602, "fx":[75.78419,-16.01911,41.2385,89.37926], "fy":[-71.70497,-106.53896,-100.31945,-60.81674]}, - {"t":2.0375, "x":1.80389, "y":6.2296, "heading":2.64034, "vx":1.69392, "vy":-3.27643, "omega":0.69511, "ax":2.80117, "ay":-4.244, "alpha":-12.47506, "fx":[87.08726,-31.67238,40.36251,94.81072], "fy":[-37.0699,-101.82161,-99.92089,-49.94447]}, - {"t":2.06389, "x":1.84957, "y":6.14166, "heading":2.65868, "vx":1.76785, "vy":-3.38843, "omega":0.3659, "ax":2.4803, "ay":-4.17912, "alpha":-12.08742, "fx":[67.24676,-29.6511,39.6292,91.53168], "fy":[-39.52566,-98.46412,-97.43575,-48.91732]}, - {"t":2.09028, "x":1.89709, "y":6.05079, "heading":2.66834, "vx":1.8333, "vy":-3.49871, "omega":0.04692, "ax":-0.17626, "ay":-0.79246, "alpha":-1.59461, "fx":[-4.88922,-8.60653,-1.16703,2.67027], "fy":[-7.95051,-15.23915,-18.95774,-11.77039]}, - {"t":2.11667, "x":1.9454, "y":5.95818, "heading":2.66958, "vx":1.82865, "vy":-3.51962, "omega":0.00483, "ax":-0.21212, "ay":-0.11241, "alpha":-0.0049, "fx":[-3.61367,-3.62521,-3.60254,-3.59099], "fy":[-1.8949,-1.91758,-1.9292,-1.90651]}, - {"t":2.14306, "x":1.99359, "y":5.86526, "heading":2.6697, "vx":1.82305, "vy":-3.52259, "omega":0.00471, "ax":-0.08289, "ay":-0.04288, "alpha":-0.00002, "fx":[-1.40998,-1.41004,-1.40993,-1.40987], "fy":[-0.72922,-0.72932,-0.72938,-0.72927]}, - {"t":2.16945, "x":2.04167, "y":5.77229, "heading":2.66983, "vx":1.82086, "vy":-3.52372, "omega":0.0047, "ax":-0.00264, "ay":-0.00137, "alpha":0.0, "fx":[-0.04497,-0.04498,-0.04497,-0.04497], "fy":[-0.02324,-0.02324,-0.02324,-0.02324]}, - {"t":2.19584, "x":2.08972, "y":5.6793, "heading":2.66995, "vx":1.82079, "vy":-3.52376, "omega":0.0047, "ax":0.076, "ay":0.03931, "alpha":0.00002, "fx":[1.29284,1.29289,1.29279,1.29273], "fy":[0.66858,0.66869,0.66874,0.66863]}, - {"t":2.22223, "x":2.1378, "y":5.58632, "heading":2.67008, "vx":1.8228, "vy":-3.52272, "omega":0.00471, "ax":0.19937, "ay":0.10611, "alpha":0.0056, "fx":[3.39755,3.41072,3.38482,3.37164], "fy":[1.78536,1.81127,1.82452,1.7986]}, - {"t":2.24862, "x":2.18597, "y":5.4934, "heading":2.6702, "vx":1.82806, "vy":-3.51992, "omega":0.00485, "ax":0.10974, "ay":0.85433, "alpha":1.81008, "fx":[4.02114,8.24784,-0.21231,-4.58986], "fy":[8.2734,16.55734,20.71561,12.581]}, - {"t":2.27501, "x":2.23425, "y":5.4008, "heading":2.67033, "vx":1.83096, "vy":-3.49737, "omega":0.05262, "ax":-2.49086, "ay":4.18272, "alpha":12.07721, "fx":[-66.56241,29.43815,-40.28373,-92.06745], "fy":[40.24007,98.78279,97.32182,48.24305]}, - {"t":2.3014, "x":2.2817, "y":5.30997, "heading":2.67172, "vx":1.76522, "vy":-3.38699, "omega":0.37133, "ax":-2.80078, "ay":4.24401, "alpha":12.3592, "fx":[-84.24281,31.25583,-41.78246,-95.79235], "fy":[39.28078,102.05607,99.37277,48.04789]}, - {"t":2.32779, "x":2.32731, "y":5.22206, "heading":2.68152, "vx":1.69131, "vy":-3.275, "omega":0.69748, "ax":-2.78293, "ay":4.9578, "alpha":9.12859, "fx":[-71.38725,17.62037,-43.59148,-91.98874], "fy":[74.85424,106.3754,99.34714,56.74624]}, - {"t":2.35418, "x":2.37097, "y":5.13737, "heading":2.69992, "vx":1.61787, "vy":-3.14416, "omega":0.93838, "ax":-2.84329, "ay":5.51657, "alpha":4.76045, "fx":[-55.19964,-15.50463,-46.49254,-76.25749], "fy":[92.48434,107.30773,98.32617,77.22271]}, - {"t":2.38057, "x":2.41267, "y":5.05631, "heading":2.72469, "vx":1.54284, "vy":-2.99859, "omega":1.06401, "ax":-2.90459, "ay":5.65224, "alpha":2.38707, "fx":[-51.5818,-33.48444,-48.35433,-64.2043], "fy":[95.56357,103.51219,97.62517,87.8713]}, - {"t":2.40695, "x":2.45238, "y":4.97915, "heading":2.75276, "vx":1.46619, "vy":-2.84943, "omega":1.127, "ax":-2.92793, "ay":5.69472, "alpha":0.9275, "fx":[-50.32755,-43.73417,-49.42923,-55.72197], "fy":[96.65128,99.86543,97.22998,93.71553]}, - {"t":2.43334, "x":2.49005, "y":4.90594, "heading":2.7825, "vx":1.38892, "vy":-2.69915, "omega":1.15148, "ax":-2.93579, "ay":5.70739, "alpha":-0.03964, "fx":[-49.92543,-50.19383,-49.94885,-49.67998], "fy":[97.08923,96.94881,97.0731,97.21292]}, - {"t":2.45973, "x":2.52568, "y":4.8367, "heading":2.81289, "vx":1.31145, "vy":-2.54853, "omega":1.15043, "ax":-2.93762, "ay":5.70909, "alpha":-0.71994, "fx":[-49.92673,-54.6101,-50.07471,-45.26087], "fy":[97.23292,94.65225,97.09332,99.46124]}, - {"t":2.48612, "x":2.55927, "y":4.77143, "heading":2.84325, "vx":1.23393, "vy":-2.39787, "omega":1.13143, "ax":-2.93701, "ay":5.70654, "alpha":-1.22142, "fx":[-50.14565,-57.81836,-49.91912,-41.94764], "fy":[97.21933,92.8174,97.24166,100.98832]}, - {"t":2.51251, "x":2.59081, "y":4.71014, "heading":2.87311, "vx":1.15642, "vy":-2.24728, "omega":1.0992, "ax":-2.93539, "ay":5.70243, "alpha":-1.60522, "fx":[-50.48885,-60.25659,-49.56237,-39.41258], "fy":[97.11384,91.32315,97.47992,102.07002]}, - {"t":2.5389, "x":2.6203, "y":4.65282, "heading":2.90212, "vx":1.07896, "vy":-2.0968, "omega":1.05684, "ax":-2.93335, "ay":5.69788, "alpha":-1.90817, "fx":[-50.90314,-62.17349,-49.06376,-37.44146], "fy":[96.95239,90.08468,97.77855,102.86149]}, - {"t":2.56529, "x":2.64775, "y":4.59947, "heading":2.93001, "vx":1.00155, "vy":-1.94643, "omega":1.00648, "ax":-2.93116, "ay":5.69336, "alpha":-2.15361, "fx":[-51.35545,-63.72001,-48.46831,-35.88915], "fy":[96.75692,89.04285,98.11467,103.45555]}, - {"t":2.59168, "x":2.67316, "y":4.55009, "heading":2.95657, "vx":0.9242, "vy":-1.79619, "omega":0.94965, "ax":-2.92894, "ay":5.68909, "alpha":-2.35694, "fx":[-51.82382,-64.993,-47.81108,-34.65391], "fy":[96.54189,88.15573,98.47061,103.91066]}, - {"t":2.61807, "x":2.69653, "y":4.50467, "heading":2.98163, "vx":0.8469, "vy":-1.64606, "omega":0.88745, "ax":-2.92675, "ay":5.68511, "alpha":-2.52862, "fx":[-52.29301,-66.05761,-47.11983,-33.66211], "fy":[96.31745,87.39276,98.83275,104.26535]}, - {"t":2.64446, "x":2.71786, "y":4.46321, "heading":3.00505, "vx":0.76967, "vy":-1.49603, "omega":0.82072, "ax":-2.92461, "ay":5.68144, "alpha":-2.67593, "fx":[-52.75199,-66.95948,-46.41687,-32.85904], "fy":[96.09109,86.73108,99.19069,104.54596]}, - {"t":2.67085, "x":2.73715, "y":4.42571, "heading":3.0267, "vx":0.69249, "vy":-1.3461, "omega":0.75011, "ax":-2.92256, "ay":5.67807, "alpha":-2.80405, "fx":[-53.19256,-67.73178,-45.72022,-32.20301], "fy":[95.86856,86.15311,99.53653,104.77111]}, - {"t":2.69724, "x":2.75441, "y":4.39216, "heading":3.0465, "vx":0.61536, "vy":-1.19626, "omega":0.67611, "ax":-2.9206, "ay":5.67497, "alpha":-2.9167, "fx":[-53.60849,-68.3993,-45.04457,-31.66163], "fy":[95.65441,85.64501,99.86439,104.95434]}, - {"t":2.72363, "x":2.76963, "y":4.36257, "heading":3.06434, "vx":0.53829, "vy":-1.0465, "omega":0.59914, "ax":-2.91873, "ay":5.67211, "alpha":-3.01661, "fx":[-53.9949,-68.98114,-44.40188,-31.20925], "fy":[95.45233,85.19562,100.16993,105.10576]}, - {"t":2.75002, "x":2.78282, "y":4.33693, "heading":3.08015, "vx":0.46127, "vy":-0.89682, "omega":0.51953, "ax":-2.91697, "ay":5.66947, "alpha":-3.10582, "fx":[-54.34796,-69.49231,-43.80197,-30.8253], "fy":[95.2654,84.79578,100.45,105.23308]}, - {"t":2.77641, "x":2.79398, "y":4.31524, "heading":3.09386, "vx":0.38429, "vy":-0.7472, "omega":0.43757, "ax":-2.91532, "ay":5.66704, "alpha":-3.18585, "fx":[-54.66457,-69.94482,-43.25286,-30.49304], "fy":[95.09617,84.43787,100.70237,105.34228]}, - {"t":2.8028, "x":2.8031, "y":4.29749, "heading":3.10541, "vx":0.30736, "vy":-0.59765, "omega":0.3535, "ax":-2.91378, "ay":5.66479, "alpha":-3.25785, "fx":[-54.94219,-70.34843,-42.76118,-30.19875], "fy":[94.94686,84.1155,100.92546,105.43808]}, - {"t":2.82919, "x":2.8102, "y":4.28369, "heading":3.11474, "vx":0.23046, "vy":-0.44816, "omega":0.26753, "ax":-2.91236, "ay":5.66272, "alpha":-3.32272, "fx":[-55.1787,-70.71109,-42.33242,-29.93111], "fy":[94.81932,83.8233,101.11816,105.52425]}, - {"t":2.85557, "x":2.81527, "y":4.27384, "heading":3.1218, "vx":0.15361, "vy":-0.29873, "omega":0.17984, "ax":-2.91104, "ay":5.66082, "alpha":-3.38117, "fx":[-55.3723,-71.03932,-41.97122,-29.68072], "fy":[94.71517,83.55674,101.27967,105.60382]}, - {"t":2.88196, "x":2.81831, "y":4.26793, "heading":3.12654, "vx":0.07679, "vy":-0.14934, "omega":0.09062, "ax":-2.90983, "ay":5.65907, "alpha":-3.43377, "fx":[-55.52143,-71.33844,-41.68155,-29.43978], "fy":[94.6358,83.3121,101.40933,105.67923]}, - {"t":2.90835, "x":2.81932, "y":4.26596, "heading":3.12894, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[ - {"name":"Funnel", "from":{"target":2, "targetTimestamp":2.14306, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] -} diff --git a/src/main/deploy/choreo/A_LEFT_PATH_ALT4.traj b/src/main/deploy/choreo/A_LEFT_PATH_ALT4.traj deleted file mode 100644 index 1849290b..00000000 --- a/src/main/deploy/choreo/A_LEFT_PATH_ALT4.traj +++ /dev/null @@ -1,125 +0,0 @@ -{ - "name":"A_LEFT_PATH_ALT4", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":3.1724631786346436, "y":4.214198112487793, "heading":3.141592653589793, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.3110252618789673, "y":7.185760498046875, "heading":2.2024870470289093, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.5126070976257324, "y":6.151042938232422, "heading":0.0, "intervals":32, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":3.4538493156433105, "y":5.355730056762695, "heading":2.077894951837786, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"3.1724631786346436 m", "val":3.1724631786346436}, "y":{"exp":"4.214198112487793 m", "val":4.214198112487793}, "heading":{"exp":"pi rad", "val":3.141592653589793}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"7.185760498046875 m", "val":7.185760498046875}, "heading":{"exp":"2.2024870470289093 rad", "val":2.2024870470289093}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.5126070976257324 m", "val":2.5126070976257324}, "y":{"exp":"6.151042938232422 m", "val":6.151042938232422}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":32, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"3.4538493156433105 m", "val":3.4538493156433105}, "y":{"exp":"5.355730056762695 m", "val":5.355730056762695}, "heading":{"exp":"2.077894951837786 rad", "val":2.077894951837786}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.5067,2.21611,2.83299], - "samples":[ - {"t":0.0, "x":3.17246, "y":4.2142, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.36966, "ay":5.40045, "alpha":-3.44275, "fx":[-62.09191,-78.25296,-51.70889,-37.21437], "fy":[90.51089,76.93128,96.75254,103.24557]}, - {"t":0.03767, "x":3.17007, "y":4.21803, "heading":3.14159, "vx":-0.12693, "vy":0.20342, "omega":-0.12968, "ax":-3.37146, "ay":5.40272, "alpha":-3.3749, "fx":[-62.0235,-77.87333,-51.87327,-37.62047], "fy":[90.54897,77.30324,96.65326,103.08971]}, - {"t":0.07533, "x":3.1629, "y":4.22952, "heading":3.13671, "vx":-0.25392, "vy":0.40693, "omega":-0.2568, "ax":-3.37356, "ay":5.40531, "alpha":-3.29497, "fx":[-61.86428,-77.43332,-52.18886,-38.04645], "fy":[90.64765,77.73019,96.47036,102.92322]}, - {"t":0.113, "x":3.15094, "y":4.24869, "heading":3.12703, "vx":-0.38099, "vy":0.61053, "omega":-0.38092, "ax":-3.37595, "ay":5.40826, "alpha":-3.20095, "fx":[-61.61822,-76.91871,-52.64431,-38.51441], "fy":[90.80322,78.22377,96.20778,102.73718]}, - {"t":0.15067, "x":3.1342, "y":4.27552, "heading":3.11269, "vx":-0.50816, "vy":0.81425, "omega":-0.50149, "ax":-3.37865, "ay":5.41162, "alpha":-3.09005, "fx":[-61.29023,-76.30936,-53.22554,-39.05432], "fy":[91.01089,78.80024,95.87025,102.51903]}, - {"t":0.18834, "x":3.11266, "y":4.31003, "heading":3.0938, "vx":-0.63542, "vy":1.01809, "omega":-0.61788, "ax":-3.38167, "ay":5.41546, "alpha":-2.95829, "fx":[-60.8867,-75.57702,-53.91444,-39.70693], "fy":[91.26444,79.48174,95.46437,102.25097]}, - {"t":0.226, "x":3.08632, "y":4.35222, "heading":3.07052, "vx":-0.7628, "vy":1.22208, "omega":-0.72931, "ax":-3.38503, "ay":5.41986, "alpha":-2.79967, "fx":[-60.41643,-74.6815,-54.68705,-40.52842], "fy":[91.55572,80.29855,94.99995,101.90718]}, - {"t":0.26367, "x":3.05519, "y":4.4021, "heading":3.04305, "vx":-0.89031, "vy":1.42623, "omega":-0.83477, "ax":-3.38873, "ay":5.42495, "alpha":-2.60496, "fx":[-59.89201,-73.56392,-55.51099,-41.59814], "fy":[91.87359,81.29292,94.49205,101.44896]}, - {"t":0.30134, "x":3.01925, "y":4.45967, "heading":3.01161, "vx":-1.01795, "vy":1.63057, "omega":-0.93289, "ax":-3.39277, "ay":5.43083, "alpha":-2.35936, "fx":[-59.33252,-72.13396,-56.34167,-43.03191], "fy":[92.20216,82.52603,93.96382,100.81544]}, - {"t":0.33901, "x":2.9785, "y":4.52494, "heading":2.97647, "vx":-1.14575, "vy":1.83514, "omega":-1.02176, "ax":-3.39711, "ay":5.43754, "alpha":-2.03817, "fx":[-58.76862,-70.24404,-57.11614,-45.0064], "fy":[92.51709,84.091,93.45091,99.90496]}, - {"t":0.37667, "x":2.93293, "y":4.59792, "heading":2.93798, "vx":-1.27371, "vy":2.03996, "omega":-1.09854, "ax":-3.40152, "ay":5.44481, "alpha":-1.59792, "fx":[-58.25381,-67.63286,-57.74233,-47.80639], "fy":[92.77726,86.13858,93.00845,98.53416]}, - {"t":0.41434, "x":2.88254, "y":4.67863, "heading":2.8966, "vx":-1.40183, "vy":2.24505, "omega":-1.15872, "ax":-3.40512, "ay":5.45122, "alpha":-0.9563, "fx":[-57.89267,-63.78629,-58.07814,-51.92318], "fy":[92.90305,88.93029,92.72339,96.33827]}, - {"t":0.45201, "x":2.82732, "y":4.76706, "heading":2.85296, "vx":-1.5301, "vy":2.45038, "omega":-1.19475, "ax":-3.40434, "ay":5.4511, "alpha":0.05931, "fx":[-57.92859,-57.53962,-57.88568,-58.2734], "fy":[92.70599,92.95028,92.73783,92.49233]}, - {"t":0.48968, "x":2.76727, "y":4.86323, "heading":2.80795, "vx":-1.65833, "vy":2.65571, "omega":-1.19251, "ax":-3.38346, "ay":5.41932, "alpha":1.86897, "fx":[-59.12278,-45.68013,-56.71837,-68.68573], "fy":[91.56501,99.07383,93.29846,84.78723]}, - {"t":0.52734, "x":2.70241, "y":4.9671, "heading":2.76303, "vx":-1.78578, "vy":2.85984, "omega":-1.12211, "ax":-3.27392, "ay":5.19551, "alpha":5.72964, "fx":[-65.9464,-16.82934,-53.60084,-86.37698], "fy":[85.25021,107.31393,94.86356,66.06889]}, - {"t":0.56501, "x":2.63282, "y":5.07851, "heading":2.72077, "vx":-1.9091, "vy":3.05554, "omega":-0.90629, "ax":-3.21612, "ay":4.03303, "alpha":12.43881, "fx":[-93.99681,23.20508,-48.75187,-99.27722], "fy":[30.39183,104.97799,96.75253,42.28044]}, - {"t":0.60268, "x":2.55863, "y":5.19647, "heading":2.68663, "vx":-2.03024, "vy":3.20746, "omega":-0.43775, "ax":-2.37439, "ay":3.88617, "alpha":11.48043, "fx":[-53.75757,20.95626,-41.62353,-87.12561], "fy":[34.04057,93.76683,91.61278,44.99046]}, - {"t":0.64035, "x":2.48047, "y":5.32004, "heading":2.67014, "vx":-2.11968, "vy":3.35384, "omega":-0.00532, "ax":0.30346, "ay":0.21618, "alpha":0.05582, "fx":[5.22562,5.35624,5.09798,4.96727], "fy":[3.48194,3.73998,3.87255,3.61451]}, - {"t":0.67801, "x":2.40084, "y":5.44653, "heading":2.66994, "vx":-2.10825, "vy":3.36198, "omega":-0.00321, "ax":0.08845, "ay":0.05542, "alpha":0.00005, "fx":[1.5045,1.5046,1.5044,1.50429], "fy":[0.94258,0.94278,0.94289,0.94268]}, - {"t":0.71568, "x":2.32149, "y":5.5732, "heading":2.66982, "vx":-2.10491, "vy":3.36407, "omega":-0.00321, "ax":0.01858, "ay":0.01162, "alpha":0.0, "fx":[0.31602,0.31602,0.31602,0.31602], "fy":[0.19769,0.19769,0.19769,0.19769]}, - {"t":0.75335, "x":2.24222, "y":5.69993, "heading":2.6697, "vx":-2.10421, "vy":3.36451, "omega":-0.00321, "ax":-0.01819, "ay":-0.01138, "alpha":0.0, "fx":[-0.30946,-0.30946,-0.30946,-0.30945], "fy":[-0.19358,-0.19359,-0.19359,-0.19358]}, - {"t":0.79102, "x":2.16295, "y":5.82665, "heading":2.66958, "vx":-2.1049, "vy":3.36408, "omega":-0.00321, "ax":-0.08737, "ay":-0.05475, "alpha":-0.00004, "fx":[-1.48626,-1.48636,-1.48617,-1.48607], "fy":[-0.93111,-0.9313,-0.9314,-0.93121]}, - {"t":0.82868, "x":2.0836, "y":5.95333, "heading":2.66946, "vx":-2.10819, "vy":3.36202, "omega":-0.00321, "ax":-0.30109, "ay":-0.21188, "alpha":-0.04937, "fx":[-5.17778,-5.29348,-5.06515,-4.94938], "fy":[-3.43124,-3.65939,-3.77678,-3.54863]}, - {"t":0.86635, "x":2.00397, "y":6.07982, "heading":2.66933, "vx":-2.11953, "vy":3.35404, "omega":-0.00507, "ax":2.31284, "ay":-3.85705, "alpha":-11.38264, "fx":[52.47339,-20.95994,40.32826,85.52111], "fy":[-33.14746,-92.3422,-91.1986,-45.74104]}, - {"t":0.90402, "x":1.92578, "y":6.20342, "heading":2.66914, "vx":-2.03241, "vy":3.20875, "omega":-0.43383, "ax":3.19567, "ay":-4.03811, "alpha":-12.67439, "fx":[96.71132,-23.83337,46.59444,97.95737], "fy":[-26.9726,-104.72388,-97.77698,-45.27523]}, - {"t":0.94169, "x":1.85149, "y":6.32142, "heading":2.6528, "vx":-1.91204, "vy":3.05665, "omega":-0.91124, "ax":3.29389, "ay":-5.21984, "alpha":-5.40693, "fx":[69.95359,19.77798,51.07303,83.30778], "fy":[-82.21796,-106.76153,-96.22824,-69.94452]}, - {"t":0.97935, "x":1.7818, "y":6.43285, "heading":2.61848, "vx":-1.78797, "vy":2.86003, "omega":-1.1149, "ax":3.38778, "ay":-5.4229, "alpha":-1.67528, "fx":[61.10263,47.24684,55.08283,67.06863], "fy":[-90.284,-98.32353,-94.2663,-86.09377]}, - {"t":1.01702, "x":1.71686, "y":6.53673, "heading":2.57648, "vx":-1.66036, "vy":2.65576, "omega":-1.17801, "ax":3.40547, "ay":-5.4506, "alpha":0.0089, "fx":[57.90788,57.97804,57.94414,57.87392], "fy":[-92.72484,-92.68076,-92.70148,-92.74556]}, - {"t":1.05469, "x":1.65673, "y":6.6329, "heading":2.53211, "vx":-1.53208, "vy":2.45045, "omega":-1.17767, "ax":3.40602, "ay":-5.45082, "alpha":0.95347, "fx":[55.90815,63.25176,60.30589,52.27593], "fy":[-94.11035,-89.32431,-91.29516,-96.13792]}, - {"t":1.09236, "x":1.60144, "y":6.72134, "heading":2.48775, "vx":-1.40379, "vy":2.24513, "omega":-1.14176, "ax":3.40292, "ay":-5.44512, "alpha":1.55959, "fx":[54.35636,66.20304,62.36449,48.60713], "fy":[-95.11037,-87.26167,-89.98305,-98.12435]}, - {"t":1.13002, "x":1.55098, "y":6.80204, "heading":2.44474, "vx":-1.27561, "vy":2.04003, "omega":-1.08301, "ax":3.39925, "ay":-5.43832, "alpha":1.98502, "fx":[53.0387,67.97533,64.1906,46.07617], "fy":[-95.913,-85.95892,-88.75175,-99.39362]}, - {"t":1.16769, "x":1.50534, "y":6.87503, "heading":2.40395, "vx":-1.14757, "vy":1.83518, "omega":-1.00824, "ax":3.39571, "ay":-5.43176, "alpha":2.3027, "fx":[51.87681,69.07898,65.81463,44.26992], "fy":[-96.58938,-85.12602,-87.60326,-100.25199]}, - {"t":1.20536, "x":1.46452, "y":6.9403, "heading":2.36597, "vx":-1.01966, "vy":1.63058, "omega":-0.92151, "ax":3.39246, "ay":-5.42579, "alpha":2.55043, "fx":[50.83785,69.77672,67.25364,42.95103], "fy":[-97.17192,-84.59406,-86.54316,-100.85537]}, - {"t":1.24303, "x":1.42852, "y":6.99787, "heading":2.33126, "vx":-0.89187, "vy":1.4262, "omega":-0.82544, "ax":3.3895, "ay":-5.42049, "alpha":2.74961, "fx":[49.90692,70.21887,68.52055,41.97108], "fy":[-97.67762,-84.25788,-85.5764,-101.29188]}, - {"t":1.28069, "x":1.39733, "y":7.04775, "heading":2.30017, "vx":-0.7642, "vy":1.22203, "omega":-0.72187, "ax":3.38679, "ay":-5.41583, "alpha":2.91326, "fx":[49.077,70.49868,69.62722,41.23031], "fy":[-98.11649,-84.04829,-84.70594,-101.61586]}, - {"t":1.31836, "x":1.37095, "y":7.08994, "heading":2.27298, "vx":-0.63663, "vy":1.01803, "omega":-0.61213, "ax":3.38432, "ay":-5.41174, "alpha":3.04989, "fx":[48.3447,70.67777,70.5852,40.65752], "fy":[-98.49501,-83.91764,-83.93268,-101.86322]}, - {"t":1.35603, "x":1.34937, "y":7.12444, "heading":2.24992, "vx":-0.50915, "vy":0.81418, "omega":-0.49725, "ax":3.38207, "ay":-5.40815, "alpha":3.16538, "fx":[47.70844,70.7989,71.40566,40.19949], "fy":[-98.81774,-83.83198,-83.25579,-102.05915]}, - {"t":1.39369, "x":1.33259, "y":7.15128, "heading":2.23119, "vx":-0.38176, "vy":0.61047, "omega":-0.37802, "ax":3.38005, "ay":-5.405, "alpha":3.264, "fx":[47.16753,70.89287,72.09906,39.81516], "fy":[-99.08802,-83.76641,-82.67329,-102.22205]}, - {"t":1.43136, "x":1.32061, "y":7.17044, "heading":2.21695, "vx":-0.25444, "vy":0.40688, "omega":-0.25507, "ax":3.37824, "ay":-5.40219, "alpha":3.34895, "fx":[46.72186,70.9825,72.67471,39.47229], "fy":[-99.30832,-83.70228,-82.18271,-102.36576]}, - {"t":1.46903, "x":1.31342, "y":7.18193, "heading":2.20734, "vx":-0.12719, "vy":0.20339, "omega":-0.12893, "ax":3.37664, "ay":-5.39968, "alpha":3.42272, "fx":[46.37171,71.08498,73.14039,39.14549], "fy":[-99.48046,-83.62544,-81.7816,-102.50077]}, - {"t":1.5067, "x":1.31103, "y":7.18576, "heading":2.20249, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.90382, "ay":-4.18798, "alpha":-0.43874, "fx":[85.20621,82.29237,81.65761,84.49414], "fy":[-69.1148,-72.55754,-73.28009,-69.9926]}, - {"t":1.53754, "x":1.31336, "y":7.18377, "heading":2.20249, "vx":0.15125, "vy":-0.12917, "omega":-0.01353, "ax":4.9035, "ay":-4.1877, "alpha":-0.43206, "fx":[85.17298,82.30425,81.67881,84.47257], "fy":[-69.14314,-72.53196,-73.24483,-70.00653]}, - {"t":1.56839, "x":1.32036, "y":7.17779, "heading":2.20207, "vx":0.3025, "vy":-0.25834, "omega":-0.02686, "ax":4.90315, "ay":-4.1874, "alpha":-0.42461, "fx":[85.13641,82.31821,81.70194,84.44784], "fy":[-69.17415,-72.50266,-73.20605,-70.02289]}, - {"t":1.59923, "x":1.33202, "y":7.16783, "heading":2.20124, "vx":0.45373, "vy":-0.38749, "omega":-0.03996, "ax":4.90275, "ay":-4.18706, "alpha":-0.41626, "fx":[85.09578,82.33441,81.72747,84.41953], "fy":[-69.20844,-72.46918,-73.16297,-70.0419]}, - {"t":1.63007, "x":1.34834, "y":7.15389, "heading":2.20001, "vx":0.60495, "vy":-0.51664, "omega":-0.05279, "ax":4.90229, "ay":-4.18667, "alpha":-0.40685, "fx":[85.0502,82.3531,81.756,84.38715], "fy":[-69.24677,-72.43093,-73.11464,-70.06385]}, - {"t":1.66092, "x":1.36934, "y":7.13596, "heading":2.19838, "vx":0.75615, "vy":-0.64577, "omega":-0.06534, "ax":4.90178, "ay":-4.18623, "alpha":-0.39615, "fx":[84.99854,82.37456,81.78827,84.35003], "fy":[-69.29012,-72.38719,-73.0598,-70.08911]}, - {"t":1.69176, "x":1.39499, "y":7.11405, "heading":2.19636, "vx":0.90734, "vy":-0.77489, "omega":-0.07756, "ax":4.90119, "ay":-4.18572, "alpha":-0.38387, "fx":[84.93932,82.39918,81.82524,84.30734], "fy":[-69.33971,-72.337,-72.99686,-70.11817]}, - {"t":1.7226, "x":1.42531, "y":7.08816, "heading":2.19397, "vx":1.05852, "vy":-0.904, "omega":-0.0894, "ax":4.9005, "ay":-4.18513, "alpha":-0.36965, "fx":[84.87064,82.42746,81.86818,84.25794], "fy":[-69.39717,-72.27911,-72.9237,-70.15167]}, - {"t":1.75345, "x":1.46029, "y":7.05829, "heading":2.19122, "vx":1.20967, "vy":-1.03308, "omega":-0.1008, "ax":4.89969, "ay":-4.18444, "alpha":-0.35298, "fx":[84.7899,82.46008,81.91876,84.20032], "fy":[-69.46469,-72.21184,-72.83749,-70.19048]}, - {"t":1.78429, "x":1.49993, "y":7.02443, "heading":2.18811, "vx":1.36079, "vy":-1.16215, "omega":-0.11169, "ax":4.89872, "ay":-4.18361, "alpha":-0.33316, "fx":[84.69358,82.49797,81.97931,84.13236], "fy":[-69.54521,-72.13285,-72.73432,-70.23581]}, - {"t":1.81514, "x":1.54423, "y":6.9866, "heading":2.18466, "vx":1.51189, "vy":-1.29119, "omega":-0.12197, "ax":4.89754, "ay":-4.18261, "alpha":-0.30923, "fx":[84.57666,82.54245,82.05307,84.05104], "fy":[-69.64291,-72.03887,-72.60864,-70.28937]}, - {"t":1.84598, "x":1.59319, "y":6.94478, "heading":2.1809, "vx":1.66295, "vy":-1.42019, "omega":-0.1315, "ax":4.89609, "ay":-4.18136, "alpha":-0.27975, "fx":[84.43186,82.59543,82.14479,83.95194], "fy":[-69.76381,-71.92511,-72.45234,-70.35371]}, - {"t":1.87682, "x":1.64681, "y":6.89899, "heading":2.17684, "vx":1.81396, "vy":-1.54916, "omega":-0.14013, "ax":4.89423, "ay":-4.17977, "alpha":-0.24253, "fx":[84.24808,82.65981,82.26165,83.82822], "fy":[-69.91702,-71.7843,-72.25297,-70.43272]}, - {"t":1.90767, "x":1.70509, "y":6.84922, "heading":2.17252, "vx":1.96492, "vy":-1.67809, "omega":-0.14761, "ax":4.89179, "ay":-4.17769, "alpha":-0.19409, "fx":[84.00757,82.74019,82.41509,83.66879], "fy":[-70.11693,-71.60485,-71.99053,-70.53267]}, - {"t":1.93851, "x":1.76803, "y":6.79547, "heading":2.16797, "vx":2.1158, "vy":-1.80694, "omega":-0.1536, "ax":4.88843, "ay":-4.17482, "alpha":-0.12846, "fx":[83.68012,82.84428,82.62452,83.45446], "fy":[-70.38777,-71.3671,-71.63058,-70.66438]}, - {"t":1.96936, "x":1.83561, "y":6.73775, "heading":2.16323, "vx":2.26658, "vy":-1.93571, "omega":-0.15756, "ax":4.88354, "ay":-4.17063, "alpha":-0.03452, "fx":[83.20969,82.98608,82.92569,83.14888], "fy":[-70.77369,-71.03491,-71.1084,-70.84812]}, - {"t":2.0002, "x":1.90784, "y":6.67606, "heading":2.15837, "vx":2.41721, "vy":-2.06435, "omega":-0.15863, "ax":4.87574, "ay":-4.16397, "alpha":0.11099, "fx":[82.47942,83.19383,83.39259,82.67394], "fy":[-71.36453,-70.53386,-70.28638,-71.12676]}, - {"t":2.03104, "x":1.98472, "y":6.61041, "heading":2.15348, "vx":2.56759, "vy":-2.19278, "omega":-0.1552, "ax":4.86142, "ay":-4.15173, "alpha":0.36645, "fx":[81.19884,83.5339,84.20661,81.82628], "fy":[-72.37529,-69.68288,-68.81166,-71.609]}, - {"t":2.06189, "x":2.06623, "y":6.5408, "heading":2.14869, "vx":2.71754, "vy":-2.32084, "omega":-0.1439, "ax":4.82697, "ay":-4.12232, "alpha":0.9314, "fx":[78.39557,84.20597,85.9579,79.86239], "fy":[-74.47626,-67.89917,-65.43051,-72.67166]}, - {"t":2.09273, "x":2.15234, "y":6.46726, "heading":2.14425, "vx":2.86642, "vy":-2.44799, "omega":-0.11517, "ax":4.64855, "ay":-3.97406, "alpha":3.2318, "fx":[67.76566,86.17117,91.9929,70.3521], "fy":[-81.20362,-61.75885,-50.40969,-77.01848]}, - {"t":2.12358, "x":2.24296, "y":6.38986, "heading":2.1407, "vx":3.0098, "vy":-2.57056, "omega":-0.01549, "ax":0.23293, "ay":-0.19706, "alpha":0.48557, "fx":[3.57861,5.7007,4.34833,2.22098], "fy":[-5.09446,-3.72986,-1.60882,-2.97491]}, - {"t":2.15442, "x":2.33591, "y":6.31048, "heading":2.14022, "vx":3.01699, "vy":-2.57664, "omega":-0.00051, "ax":0.0, "ay":-0.00001, "alpha":0.0, "fx":[-0.00008,-0.00008,-0.00008,-0.00008], "fy":[-0.00009,-0.00009,-0.00009,-0.00009]}, - {"t":2.18526, "x":2.42897, "y":6.23101, "heading":2.14021, "vx":3.01699, "vy":-2.57664, "omega":-0.00051, "ax":-0.23301, "ay":0.1971, "alpha":-0.48592, "fx":[-3.57874,-5.70303,-4.35074,-2.22118], "fy":[5.09616,3.73161,1.60837,2.9744]}, - {"t":2.21611, "x":2.52191, "y":6.15163, "heading":2.14019, "vx":3.0098, "vy":-2.57056, "omega":-0.0155, "ax":-4.64848, "ay":3.97405, "alpha":-3.23289, "fx":[-67.71752,-86.13427,-92.01765,-70.40812], "fy":[81.24113,61.81305,50.37345,76.96196]}, - {"t":2.24695, "x":2.61253, "y":6.07423, "heading":2.13971, "vx":2.86642, "vy":-2.44798, "omega":-0.11522, "ax":-4.82697, "ay":4.12231, "alpha":-0.93206, "fx":[-78.37103,-84.17567,-85.97756,-79.89716], "fy":[74.50101,67.9375,65.4062,72.63251]}, - {"t":2.2778, "x":2.69865, "y":6.00069, "heading":2.13616, "vx":2.71754, "vy":-2.32084, "omega":-0.14397, "ax":-4.86142, "ay":4.15173, "alpha":-0.36676, "fx":[-81.18228,-83.50912,-84.2217,-81.8525], "fy":[72.3933,69.71293,68.79386,71.57865]}, - {"t":2.30864, "x":2.78016, "y":5.93108, "heading":2.13172, "vx":2.56759, "vy":-2.19278, "omega":-0.15528, "ax":-4.87574, "ay":4.16397, "alpha":-0.11111, "fx":[-82.47206,-83.18195,-83.39976,-82.68605], "fy":[71.37284,70.54801,70.2781,71.11257]}, - {"t":2.33948, "x":2.85703, "y":5.86543, "heading":2.12693, "vx":2.41721, "vy":-2.06435, "omega":-0.15871, "ax":-4.88354, "ay":4.17063, "alpha":0.03451, "fx":[-83.2125,-82.99133,-82.92287,-83.14367], "fy":[70.77046,71.02874,71.11163,70.85428]}, - {"t":2.37033, "x":2.92926, "y":5.80374, "heading":2.12203, "vx":2.26658, "vy":-1.93571, "omega":-0.15764, "ax":-4.88843, "ay":4.17482, "alpha":0.12852, "fx":[-83.69358,-82.86896,-82.61057,-83.43028], "fy":[70.37204,71.33829,71.6464,70.69308]}, - {"t":2.40117, "x":2.99685, "y":5.74602, "heading":2.11717, "vx":2.1158, "vy":-1.80694, "omega":-0.15368, "ax":-4.89179, "ay":4.17769, "alpha":0.1942, "fx":[-84.03181,-82.7854,-82.3895,-83.62493], "fy":[70.08832,71.55234,72.01942,70.58489]}, - {"t":2.43202, "x":3.05978, "y":5.69227, "heading":2.11243, "vx":1.96492, "vy":-1.67808, "omega":-0.14769, "ax":-4.89423, "ay":4.17977, "alpha":0.24267, "fx":[-84.28297,-82.72589,-82.22428,-83.76459], "fy":[69.8755,71.70783,72.29499,70.50865]}, - {"t":2.46286, "x":3.11806, "y":5.6425, "heading":2.10788, "vx":1.81396, "vy":-1.54916, "omega":-0.1402, "ax":-4.89608, "ay":4.18136, "alpha":0.2799, "fx":[-84.47712,-82.68219,-82.09579,-83.86889], "fy":[69.70964,71.825,72.50727,70.45302]}, - {"t":2.4937, "x":3.17168, "y":5.59671, "heading":2.10355, "vx":1.66295, "vy":-1.42019, "omega":-0.13157, "ax":-4.89754, "ay":4.18261, "alpha":0.3094, "fx":[-84.63185,-82.64933,-81.9928,-83.94921], "fy":[69.57654,71.91583,72.67606,70.41132]}, - {"t":2.52455, "x":3.22064, "y":5.55489, "heading":2.09949, "vx":1.51189, "vy":-1.29119, "omega":-0.12203, "ax":-4.89872, "ay":4.18361, "alpha":0.33334, "fx":[-84.75816,-82.62412,-81.90827,-84.01261], "fy":[69.46724,71.9879,72.81363,70.37937]}, - {"t":2.55539, "x":3.26495, "y":5.51706, "heading":2.09573, "vx":1.36079, "vy":-1.16215, "omega":-0.11174, "ax":-4.89969, "ay":4.18444, "alpha":0.35316, "fx":[-84.86327,-82.60443,-81.83758,-84.06373], "fy":[69.37583,72.04624,72.92798,70.35439]}, - {"t":2.58623, "x":3.30459, "y":5.4832, "heading":2.09228, "vx":1.20967, "vy":-1.03308, "omega":-0.10085, "ax":-4.9005, "ay":4.18513, "alpha":0.36984, "fx":[-84.95211,-82.58876,-81.77757,-84.10572], "fy":[69.29823,72.09431,73.02457,70.3345]}, - {"t":2.61708, "x":3.33957, "y":5.45333, "heading":2.08917, "vx":1.05852, "vy":-0.904, "omega":-0.08944, "ax":-4.90119, "ay":4.18572, "alpha":0.38406, "fx":[-85.02817,-82.57605,-81.72601,-84.1408], "fy":[69.23156,72.13459,73.10721,70.31833]}, - {"t":2.64792, "x":3.36988, "y":5.42744, "heading":2.08641, "vx":0.90734, "vy":-0.77489, "omega":-0.0776, "ax":-4.90178, "ay":4.18623, "alpha":0.39634, "fx":[-85.09399,-82.56549,-81.68126,-84.1706], "fy":[69.1737,72.16889,73.17868,70.3049]}, - {"t":2.67877, "x":3.39554, "y":5.40553, "heading":2.08402, "vx":0.75615, "vy":-0.64577, "omega":-0.06537, "ax":-4.90229, "ay":4.18667, "alpha":0.40704, "fx":[-85.15145,-82.55649,-81.64212,-84.19633], "fy":[69.12307,72.19857,73.24105,70.29345]}, - {"t":2.70961, "x":3.41653, "y":5.3876, "heading":2.082, "vx":0.60495, "vy":-0.51664, "omega":-0.05282, "ax":-4.90274, "ay":4.18706, "alpha":0.41646, "fx":[-85.20198,-82.54858,-81.60767,-84.21889], "fy":[69.07849,72.22468,73.29586,70.28341]}, - {"t":2.74045, "x":3.43286, "y":5.37366, "heading":2.08037, "vx":0.45373, "vy":-0.38749, "omega":-0.03997, "ax":-4.90314, "ay":4.1874, "alpha":0.4248, "fx":[-85.2467,-82.5414,-81.5772,-84.23902], "fy":[69.03901,72.24802,73.34432,70.27435]}, - {"t":2.7713, "x":3.44452, "y":5.3637, "heading":2.07914, "vx":0.3025, "vy":-0.25834, "omega":-0.02687, "ax":-4.9035, "ay":4.1877, "alpha":0.43225, "fx":[-85.28647,-82.53466,-81.55015,-84.25726], "fy":[69.00391,72.26925,73.38736,70.2659]}, - {"t":2.80214, "x":3.45152, "y":5.35772, "heading":2.07831, "vx":0.15125, "vy":-0.12917, "omega":-0.01354, "ax":-4.90382, "ay":4.18797, "alpha":0.43893, "fx":[-85.32198,-82.52812,-81.52608,-84.27408], "fy":[68.9726,72.28887,73.42573,70.25778]}, - {"t":2.83299, "x":3.45385, "y":5.35573, "heading":2.07789, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[ - {"name":"Funnel", "from":{"target":2, "targetTimestamp":2.21611, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] -} diff --git a/src/main/deploy/choreo/A_RIGHT_PATH1.traj b/src/main/deploy/choreo/A_RIGHT_PATH1.traj deleted file mode 100644 index 112634ab..00000000 --- a/src/main/deploy/choreo/A_RIGHT_PATH1.traj +++ /dev/null @@ -1,64 +0,0 @@ -{ - "name":"A_RIGHT_PATH1", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":7.15808629989624, "y":2.0309269428253174, "heading":-1.5707963267948966, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":5.37649393081665, "y":2.7055675857543946, "heading":-1.102853734231975, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"7.15808629989624 m", "val":7.15808629989624}, "y":{"exp":"2.0309269428253174 m", "val":2.0309269428253174}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"5.37649393081665 m", "val":5.37649393081665}, "y":{"exp":"(8.0518 - 5.3462324142456055) m", "val":2.7055675857543946}, "heading":{"exp":"-1.102853734231975 rad", "val":-1.102853734231975}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.08949], - "samples":[ - {"t":0.0, "x":7.15809, "y":2.03093, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.01649, "ay":2.27816, "alpha":1.59134, "fx":[-98.19083,-101.01269,-105.78201,-104.36955], "fy":[48.99331,42.91447,29.22736,33.868]}, - {"t":0.03757, "x":7.15384, "y":2.03253, "heading":-1.5708, "vx":-0.22603, "vy":0.08559, "omega":0.05978, "ax":-6.01599, "ay":2.27797, "alpha":1.59069, "fx":[-98.18424,-101.0055,-105.77238,-104.35901], "fy":[48.98479,42.90966,29.22878,33.86708]}, - {"t":0.07514, "x":7.1411, "y":2.03736, "heading":-1.56855, "vx":-0.45204, "vy":0.17117, "omega":0.11954, "ax":-6.01541, "ay":2.27775, "alpha":1.58982, "fx":[-98.17279,-101.00576,-105.76437,-104.33873], "fy":[48.98247,42.88369,29.21868,33.89054]}, - {"t":0.11271, "x":7.11988, "y":2.0454, "heading":-1.56406, "vx":-0.67803, "vy":0.25674, "omega":0.17927, "ax":-6.01473, "ay":2.27749, "alpha":1.5887, "fx":[-98.15627,-101.01314,-105.75749,-104.30821], "fy":[48.9858,42.83635,29.19725,33.93835]}, - {"t":0.15027, "x":7.09016, "y":2.05665, "heading":-1.55732, "vx":-0.904, "vy":0.3423, "omega":0.23896, "ax":-6.01391, "ay":2.27718, "alpha":1.58729, "fx":[-98.13444,-101.02715,-105.75103,-104.26668], "fy":[48.99391,42.76731,29.16487,34.01054]}, - {"t":0.18784, "x":7.05195, "y":2.07111, "heading":-1.54835, "vx":-1.12993, "vy":0.42785, "omega":0.29859, "ax":-6.0129, "ay":2.2768, "alpha":1.58556, "fx":[-98.10694,-101.04711,-105.74398,-104.21309], "fy":[49.00554,42.67608,29.12207,34.10714]}, - {"t":0.22541, "x":7.00526, "y":2.0888, "heading":-1.53713, "vx":-1.35583, "vy":0.51339, "omega":0.35816, "ax":-6.01165, "ay":2.27633, "alpha":1.58341, "fx":[-98.0732,-101.07198,-105.73482,-104.14583], "fy":[49.01893,42.56198,29.06954,34.22814]}, - {"t":0.26298, "x":6.95008, "y":2.10969, "heading":-1.52367, "vx":-1.58168, "vy":0.59891, "omega":0.41764, "ax":-6.01004, "ay":2.27572, "alpha":1.58074, "fx":[-98.03215,-101.1001,-105.72127,-104.0625], "fy":[49.03157,42.42402,29.00819,34.37336]}, - {"t":0.30055, "x":6.88642, "y":2.13379, "heading":-1.50798, "vx":-1.80747, "vy":0.6844, "omega":0.47703, "ax":-6.00788, "ay":2.2749, "alpha":1.57738, "fx":[-97.98182,-101.12872,-105.6996,-103.95919], "fy":[49.03978,42.26063,28.93911,34.54228]}, - {"t":0.33812, "x":6.81427, "y":2.16111, "heading":-1.49006, "vx":-2.03317, "vy":0.76987, "omega":0.53629, "ax":-6.00485, "ay":2.27376, "alpha":1.57308, "fx":[-97.91819,-101.15283,-105.66334,-103.82908], "fy":[49.03777,42.06923,28.8636,34.73358]}, - {"t":0.37569, "x":6.73365, "y":2.19164, "heading":-1.46992, "vx":-2.25877, "vy":0.85529, "omega":0.59539, "ax":-6.0003, "ay":2.27205, "alpha":1.56734, "fx":[-97.83256,-101.16236,-105.5999,-103.65888], "fy":[49.01543,41.84497,28.78295,34.94406]}, - {"t":0.41325, "x":6.64456, "y":2.22537, "heading":-1.44755, "vx":-2.48419, "vy":0.94065, "omega":0.65427, "ax":-5.99269, "ay":2.26917, "alpha":1.55925, "fx":[-97.70313,-101.13381,-105.48065,-103.41816], "fy":[48.95216,41.57705,28.69757,35.16524]}, - {"t":0.45082, "x":6.547, "y":2.26231, "heading":-1.42297, "vx":-2.70933, "vy":1.02589, "omega":0.71285, "ax":-5.97741, "ay":2.2634, "alpha":1.54673, "fx":[-97.46079,-100.99644,-105.22186,-103.01704], "fy":[48.79387,41.23436,28.60144,35.36978]}, - {"t":0.48839, "x":6.441, "y":2.30245, "heading":-1.39619, "vx":-2.93389, "vy":1.11093, "omega":0.77096, "ax":-5.93147, "ay":2.24604, "alpha":1.52369, "fx":[-96.7438,-100.39652,-104.41662,-102.01337], "fy":[48.30803,40.66756,28.42889,35.41345]}, - {"t":0.52596, "x":6.32659, "y":2.34577, "heading":-1.36722, "vx":-3.15673, "vy":1.19531, "omega":0.8282, "ax":-0.0008, "ay":0.00281, "alpha":-0.10855, "fx":[-0.23259,0.31932,0.20539,-0.34651], "fy":[-0.28503,-0.17111,0.3808,0.26687]}, - {"t":0.56353, "x":6.208, "y":2.39068, "heading":-1.33611, "vx":-3.15676, "vy":1.19541, "omega":0.82412, "ax":5.93146, "ay":-2.24592, "alpha":-1.5256, "fx":[96.70697,100.61835,104.46736,101.77677], "fy":[-48.40524,-40.121,-28.20666,-36.07714]}, - {"t":0.6011, "x":6.09359, "y":2.43401, "heading":-1.30515, "vx":-2.93392, "vy":1.11104, "omega":0.76681, "ax":5.97742, "ay":-2.26341, "alpha":-1.5451, "fx":[97.3954,101.43954,105.32122,102.54092], "fy":[-48.94782,-40.13671,-28.19756,-36.71781]}, - {"t":0.63867, "x":5.98758, "y":2.47415, "heading":-1.27634, "vx":-2.70936, "vy":1.026, "omega":0.70876, "ax":5.99272, "ay":-2.26925, "alpha":-1.5554, "fx":[97.60927,101.78284,105.62689,102.71891], "fy":[-49.16204,-39.96639,-28.11931,-37.14936]}, - {"t":0.67623, "x":5.89003, "y":2.51109, "heading":-1.24971, "vx":-2.48422, "vy":0.94075, "omega":0.65032, "ax":6.00035, "ay":-2.27217, "alpha":-1.56175, "fx":[97.71297,102.00069,105.78917,102.75399], "fy":[-49.27569,-39.76211,-28.045,-37.51318]}, - {"t":0.7138, "x":5.80093, "y":2.54483, "heading":-1.22528, "vx":-2.25879, "vy":0.85539, "omega":0.59165, "ax":6.00491, "ay":-2.27393, "alpha":-1.56607, "fx":[97.77599,102.16335,105.89139,102.73658], "fy":[-49.34215,-39.55616,-27.98219,-37.83512]}, - {"t":0.75137, "x":5.72031, "y":2.57536, "heading":-1.20305, "vx":-2.0332, "vy":0.76996, "omega":0.53282, "ax":6.00795, "ay":-2.27511, "alpha":-1.56923, "fx":[97.8202,102.29413,105.96205,102.69737], "fy":[-49.38198,-39.35987,-27.93079,-38.12301]}, - {"t":0.78894, "x":5.64817, "y":2.60269, "heading":-1.18304, "vx":-1.80749, "vy":0.68449, "omega":0.47386, "ax":6.01011, "ay":-2.27595, "alpha":-1.57166, "fx":[97.85428,102.40303,106.01377,102.64978], "fy":[-49.40536,-39.17832,-27.88945,-38.37987]}, - {"t":0.82651, "x":5.5845, "y":2.62679, "heading":-1.16523, "vx":-1.5817, "vy":0.59899, "omega":0.41482, "ax":6.01173, "ay":-2.27658, "alpha":-1.5736, "fx":[97.88212,102.49506,106.05307,102.60069], "fy":[-49.41824,-39.01419,-27.85662,-38.6071]}, - {"t":0.86408, "x":5.52932, "y":2.64769, "heading":-1.14965, "vx":-1.35584, "vy":0.51346, "omega":0.3557, "ax":6.01298, "ay":-2.27708, "alpha":-1.57521, "fx":[97.90563,102.57303,106.08372,102.55401], "fy":[-49.42449,-38.86902,-27.83087,-38.80542]}, - {"t":0.90165, "x":5.48263, "y":2.66537, "heading":-1.13629, "vx":-1.12995, "vy":0.42791, "omega":0.29652, "ax":6.01398, "ay":-2.27747, "alpha":-1.57656, "fx":[97.92574,102.63866,106.1081,102.51213], "fy":[-49.42682,-38.74375,-27.8109,-38.97526]}, - {"t":0.93921, "x":5.44442, "y":2.67984, "heading":-1.12515, "vx":-0.90401, "vy":0.34235, "omega":0.23729, "ax":6.0148, "ay":-2.2778, "alpha":-1.57771, "fx":[97.94291,102.69306,106.1278,102.47662], "fy":[-49.42722,-38.639,-27.79563,-39.11692]}, - {"t":0.97678, "x":5.41471, "y":2.6911, "heading":-1.11623, "vx":-0.67804, "vy":0.25678, "omega":0.17802, "ax":6.01549, "ay":-2.27807, "alpha":-1.5787, "fx":[97.95737,102.73698,106.14393,102.44854], "fy":[-49.42718,-38.55518,-27.78413,-39.23061]}, - {"t":1.01435, "x":5.39348, "y":2.69914, "heading":-1.10954, "vx":-0.45205, "vy":0.17119, "omega":0.11871, "ax":6.01606, "ay":-2.27829, "alpha":-1.57956, "fx":[97.96923,102.77096,106.15727,102.42864], "fy":[-49.42781,-38.49259,-27.77564,-39.31649]}, - {"t":1.05192, "x":5.38074, "y":2.70396, "heading":-1.10508, "vx":-0.22603, "vy":0.0856, "omega":0.05937, "ax":6.01656, "ay":-2.27849, "alpha":-1.58029, "fx":[97.97856,102.79538,106.16841,102.41746], "fy":[-49.42996,-38.45143,-27.76962,-39.37469]}, - {"t":1.08949, "x":5.37649, "y":2.70557, "heading":-1.10285, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/A_RIGHT_PATH2.traj b/src/main/deploy/choreo/A_RIGHT_PATH2.traj deleted file mode 100644 index 81fbf791..00000000 --- a/src/main/deploy/choreo/A_RIGHT_PATH2.traj +++ /dev/null @@ -1,180 +0,0 @@ -{ - "name":"A_RIGHT_PATH2", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":5.005142688751221, "y":2.817952858734131, "heading":-1.0513369818883893, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":4.582683086395264, "y":2.4232380264282227, "heading":0.0, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":3.5206298828125, "y":2.2525508277893067, "heading":0.0, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":1.924022912979126, "y":1.5354974143981934, "heading":-2.216612130911823, "intervals":15, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.3110252618789673, "y":0.8660395019531251, "heading":-2.216612130911823, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.76132869720459, "y":1.7727476358413696, "heading":0.0, "intervals":33, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":3.8275418281555176, "y":2.5679142349243165, "heading":-2.09887087685183, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":4.0}}, "enabled":true}, - {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"5.005142688751221 m", "val":5.005142688751221}, "y":{"exp":"(8.0518 - 5.233847141265869) m", "val":2.817952858734131}, "heading":{"exp":"-1.0513369818883893 rad", "val":-1.0513369818883893}, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"4.582683086395264 m", "val":4.582683086395264}, "y":{"exp":"(8.0518 - 5.628561973571777) m", "val":2.4232380264282227}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"3.5206298828125 m", "val":3.5206298828125}, "y":{"exp":"(8.0518 - 5.799249172210693) m", "val":2.2525508277893067}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"1.924022912979126 m", "val":1.924022912979126}, "y":{"exp":"(8.0518 - 6.516302585601807) m", "val":1.5354974143981934}, "heading":{"exp":"-2.216612130911823 rad", "val":-2.216612130911823}, "intervals":15, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"(8.0518 - 7.185760498046875) m", "val":0.8660395019531251}, "heading":{"exp":"-2.216612130911823 rad", "val":-2.216612130911823}, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.76132869720459 m", "val":2.76132869720459}, "y":{"exp":"1.7727476358413696 m", "val":1.7727476358413696}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":33, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"3.8275418281555176 m", "val":3.8275418281555176}, "y":{"exp":"(8.0518 - 5.483885765075684) m", "val":2.5679142349243165}, "heading":{"exp":"-2.09887087685183 rad", "val":-2.09887087685183}, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"4 m / s", "val":4.0}}}, "enabled":true}, - {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,0.44714,0.79227,1.25189,1.7841,2.52107,3.16592], - "samples":[ - {"t":0.0, "x":5.00514, "y":2.81795, "heading":-1.05134, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-2.79278, "ay":-5.56686, "alpha":-5.4537, "fx":[-43.43733,-8.58369,-59.74256,-78.25422], "fy":[-100.75225,-109.3264,-91.8237,-76.86009]}, - {"t":0.02353, "x":5.00437, "y":2.81641, "heading":-1.05134, "vx":-0.06572, "vy":-0.13101, "omega":-0.12835, "ax":-2.97957, "ay":-5.45974, "alpha":-5.55849, "fx":[-45.84632,-11.58782,-64.70136,-80.59071], "fy":[-99.66973,-109.0342,-88.37633,-74.39401]}, - {"t":0.04707, "x":5.002, "y":2.81182, "heading":-1.05436, "vx":-0.13584, "vy":-0.2595, "omega":-0.25916, "ax":-3.18486, "ay":-5.3321, "alpha":-5.67263, "fx":[-48.60897,-15.08349,-69.89214,-83.10989], "fy":[-98.34136,-108.58919,-84.3049,-71.55438]}, - {"t":0.0706, "x":4.99792, "y":2.80423, "heading":-1.06046, "vx":-0.2108, "vy":-0.38498, "omega":-0.39265, "ax":-3.41043, "ay":-5.17919, "alpha":-5.795, "fx":[-51.76485,-19.16419,-75.30109,-85.81152], "fy":[-96.7054,-107.92484,-79.48139,-68.27464]}, - {"t":0.09413, "x":4.99201, "y":2.79374, "heading":-1.0697, "vx":-0.29105, "vy":-0.50686, "omega":-0.52903, "ax":-3.65776, "ay":-4.99514, "alpha":-5.92309, "fx":[-55.35657,-23.9442,-80.88279,-88.68635], "fy":[-94.68153,-106.94425,-73.76066,-64.47737]}, - {"t":0.11767, "x":4.98415, "y":2.78043, "heading":-1.08215, "vx":-0.37714, "vy":-0.62442, "omega":-0.66842, "ax":-3.92782, "ay":-4.77278, "alpha":-6.05173, "fx":[-59.42751,-29.56006,-86.54492,-91.71173], "fy":[-92.16517,-105.50505,-66.99007,-60.07423]}, - {"t":0.1412, "x":4.97419, "y":2.76441, "heading":-1.09788, "vx":-0.46957, "vy":-0.73674, "omega":-0.81084, "ax":-4.22056, "ay":-4.50353, "alpha":-6.17126, "fx":[-64.01698,-36.16742,-92.13207,-94.84559], "fy":[-89.02047,-103.39737,-59.02972,-54.96751]}, - {"t":0.16474, "x":4.96197, "y":2.74583, "heading":-1.11696, "vx":-0.5689, "vy":-0.84272, "omega":-0.95607, "ax":-4.53434, "ay":-4.17742, "alpha":-6.26494, "fx":[-69.15122,-43.92656,-97.41468,-98.0191], "fy":[-85.07255,-100.31325,-49.78661,-49.05466]}, - {"t":0.18827, "x":4.94732, "y":2.72484, "heading":-1.13946, "vx":-0.67561, "vy":-0.94103, "omega":-1.10351, "ax":-4.86506, "ay":-3.78328, "alpha":-6.30632, "fx":[-74.82756,-52.96378,-102.09326,-101.12841], "fy":[-80.10063,-95.80992,-39.26189,-42.23761]}, - {"t":0.2118, "x":4.93008, "y":2.70164, "heading":-1.16543, "vx":-0.7901, "vy":-1.03007, "omega":-1.25192, "ax":-5.20488, "ay":-3.30925, "alpha":-6.25843, "fx":[-80.98871,-63.28714,-105.83019,-104.02774], "fy":[-73.83637,-89.28185,-27.60034,-34.43877]}, - {"t":0.23534, "x":4.91004, "y":2.67649, "heading":-1.19489, "vx":-0.91259, "vy":-1.10794, "omega":-1.3992, "ax":-5.54038, "ay":-2.74412, "alpha":-6.07853, "fx":[-87.48502,-74.63474,-108.31391,-106.52731], "fy":[-65.97577,-79.98657,-15.11927,-25.62487]}, - {"t":0.25887, "x":4.88703, "y":2.64965, "heading":-1.22782, "vx":-1.04297, "vy":-1.17252, "omega":-1.54225, "ax":-5.85024, "ay":-2.08058, "alpha":-5.73244, "fx":[-94.02802,-86.2719,-109.34148,-108.40218], "fy":[-56.21868,-67.21494,-2.28968,-15.83678]}, - {"t":0.2824, "x":4.86087, "y":2.62148, "heading":-1.26411, "vx":-1.18065, "vy":-1.22149, "omega":-1.67716, "ax":-6.10433, "ay":-1.32164, "alpha":-5.21641, "fx":[-100.15151,-96.87868,-108.88441,-109.41734], "fy":[-44.35182,-50.69389,10.34077,-5.21794]}, - {"t":0.30594, "x":4.83139, "y":2.59237, "heading":-1.30358, "vx":-1.32431, "vy":-1.25259, "omega":-1.79992, "ax":-6.26855, "ay":-0.48867, "alpha":-4.57046, "fx":[-105.21786,-104.81538,-107.10127,-109.37028], "fy":[-30.37847,-31.10114,22.25903,5.97184]}, - {"t":0.32947, "x":4.79849, "y":2.56276, "heading":-1.34594, "vx":-1.47183, "vy":-1.26409, "omega":-1.90748, "ax":-6.31722, "ay":0.37645, "alpha":-3.86259, "fx":[-108.51823,-108.8675,-104.28866,-108.14172], "fy":[-14.65594,-10.18632,33.08398,17.37155]}, - {"t":0.353, "x":4.7621, "y":2.53311, "heading":-1.39083, "vx":-1.62049, "vy":-1.25523, "omega":-1.99838, "ax":-6.24545, "ay":1.22188, "alpha":-3.15251, "fx":[-109.47894,-108.92086,-100.79814,-105.73534], "fy":[2.05431,9.90193,42.6108,28.56827]}, - {"t":0.37654, "x":4.72224, "y":2.50391, "heading":-1.43786, "vx":-1.76747, "vy":-1.22648, "omega":-2.07257, "ax":-6.07018, "ay":2.00278, "alpha":-2.4727, "fx":[-107.88873,-105.87308,-96.95944,-102.28653], "fy":[18.71897,27.58205,50.79818,39.16756]}, - {"t":0.40007, "x":4.67896, "y":2.4756, "heading":-1.48664, "vx":-1.91032, "vy":-1.17934, "omega":-2.13076, "ax":-5.82061, "ay":2.6918, "alpha":-1.83703, "fx":[-103.99229,-100.96617,-93.03488,-98.03406], "fy":[34.32221,42.2438,57.72194,48.85905]}, - {"t":0.4236, "x":4.63239, "y":2.44859, "heading":-1.53678, "vx":-2.0473, "vy":-1.116, "omega":-2.17399, "ax":-5.52752, "ay":3.27947, "alpha":-1.25361, "fx":[-98.37582,-95.23662,-89.20633,-93.26743], "fy":[48.14332,54.01205,63.52271,57.45355]}, - {"t":0.44714, "x":4.58268, "y":2.42324, "heading":-1.58794, "vx":-2.17739, "vy":-1.03882, "omega":-2.20349, "ax":-5.36296, "ay":3.53055, "alpha":-0.94655, "fx":[-94.80946,-92.16127,-87.3706,-90.5486], "fy":[54.45181,58.74218,65.70383,61.31709]}, - {"t":0.46214, "x":4.54941, "y":2.40805, "heading":-1.62101, "vx":-2.25786, "vy":-0.98584, "omega":-2.2177, "ax":-5.36262, "ay":3.53348, "alpha":-0.68294, "fx":[-93.80918,-91.955,-88.48202,-90.62064], "fy":[56.09605,59.02542,64.14865,61.14368]}, - {"t":0.47715, "x":4.51492, "y":2.39365, "heading":-1.65428, "vx":-2.33833, "vy":-0.93282, "omega":-2.22795, "ax":-5.36133, "ay":3.53597, "alpha":-0.38778, "fx":[-92.67071,-91.64556,-89.6716,-90.79089], "fy":[57.88919,59.46255,62.41887,60.813]}, - {"t":0.49215, "x":4.47923, "y":2.38005, "heading":-1.68772, "vx":-2.41878, "vy":-0.87976, "omega":-2.23376, "ax":-5.35871, "ay":3.53781, "alpha":-0.05557, "fx":[-91.36249,-91.21881,-90.9368,-91.08245], "fy":[59.85626,60.06955,60.49835,60.28423]}, - {"t":0.50716, "x":4.44233, "y":2.36725, "heading":-1.72123, "vx":-2.49919, "vy":-0.82667, "omega":-2.2346, "ax":-5.35426, "ay":3.53864, "alpha":0.32076, "fx":[-89.84193,-90.65768,-92.27333,-91.52446], "fy":[62.02929,60.86371,58.36974,59.50219]}, - {"t":0.52217, "x":4.40423, "y":2.35524, "heading":-1.75477, "vx":-2.57953, "vy":-0.77357, "omega":-2.22978, "ax":-5.34725, "ay":3.53795, "alpha":0.75062, "fx":[-88.0504,-89.9414,-93.67484,-92.15391], "fy":[64.44956,61.86368,56.01437,58.39034]}, - {"t":0.53717, "x":4.36492, "y":2.34403, "heading":-1.78823, "vx":-2.65977, "vy":-0.72048, "omega":-2.21852, "ax":-5.33666, "ay":3.53491, "alpha":1.24696, "fx":[-85.90534,-89.04461,-95.13257,-93.01791], "fy":[67.1704,63.08937,53.41217,56.83953]}, - {"t":0.55218, "x":4.32441, "y":2.33362, "heading":-1.82152, "vx":-2.73985, "vy":-0.66744, "omega":-2.19981, "ax":-5.32101, "ay":3.52817, "alpha":1.82829, "fx":[-83.28792,-87.93647,-96.63495,-94.17605], "fy":[70.2604,64.56146,50.54164,54.68928]}, - {"t":0.56718, "x":4.28269, "y":2.324, "heading":-1.85452, "vx":-2.8197, "vy":-0.6145, "omega":-2.17238, "ax":-5.29803, "ay":3.51537, "alpha":2.52205, "fx":[-80.02341,-86.58,-98.16702,-95.70132], "fy":[73.80585,66.3001,47.3799,51.69578]}, - {"t":0.58219, "x":4.23979, "y":2.31518, "heading":-1.88712, "vx":-2.8992, "vy":-0.56175, "omega":-2.13453, "ax":-5.26417, "ay":3.49227, "alpha":3.37011, "fx":[-75.85104,-84.93278,-99.70958,-97.67437], "fy":[77.90858,68.32153,43.9035,47.47647]}, - {"t":0.59719, "x":4.19569, "y":2.30714, "heading":-1.91915, "vx":-2.97819, "vy":-0.50934, "omega":-2.08396, "ax":-5.2136, "ay":3.45103, "alpha":4.43742, "fx":[-70.38404,-82.95205,-101.23754,-100.15393], "fy":[82.66652,70.6296,40.09119,41.41683]}, - {"t":0.6122, "x":4.15041, "y":2.29989, "heading":-1.95042, "vx":-3.05642, "vy":-0.45756, "omega":-2.01737, "ax":-5.13671, "ay":3.377, "alpha":5.82123, "fx":[-63.0931,-80.61587,-102.71622,-103.07072], "fy":[88.09809,73.19179,35.93424,32.54338]}, - {"t":0.6272, "x":4.10397, "y":2.2934, "heading":-1.98069, "vx":-3.1335, "vy":-0.40689, "omega":-1.93002, "ax":-5.02004, "ay":3.24518, "alpha":7.63047, "fx":[-53.54402,-78.0092,-104.09099,-105.91373], "fy":[93.89349,75.85765,31.47723,19.57006]}, - {"t":0.64221, "x":4.05639, "y":2.28766, "heading":-2.00966, "vx":-3.20883, "vy":-0.35819, "omega":-1.81552, "ax":-4.87024, "ay":3.0321, "alpha":9.73983, "fx":[-43.16052,-75.70044,-105.25361,-107.2513], "fy":[98.71431,78.02938,26.98798,2.56894]}, - {"t":0.65722, "x":4.00769, "y":2.28263, "heading":-2.0369, "vx":-3.28191, "vy":-0.31269, "omega":-1.66937, "ax":-4.80404, "ay":2.77599, "alpha":11.15149, "fx":[-39.18457,-75.3508,-106.05664,-106.26924], "fy":[99.8739,78.17166,23.09113,-12.26122]}, - {"t":0.67222, "x":3.9579, "y":2.27825, "heading":-2.06195, "vx":-3.354, "vy":-0.27104, "omega":-1.50204, "ax":-4.85187, "ay":2.49774, "alpha":11.71239, "fx":[-42.34021,-76.91794,-106.68953,-104.16834], "fy":[97.89477,76.34583,19.09808,-23.39531]}, - {"t":0.68723, "x":3.90703, "y":2.27446, "heading":-2.08449, "vx":-3.4268, "vy":-0.23356, "omega":-1.32629, "ax":-4.93137, "ay":2.15075, "alpha":12.06277, "fx":[-48.17254,-79.4015,-107.29863,-100.65191], "fy":[94.08518,73.362,13.84211,-34.95488]}, - {"t":0.70223, "x":3.85505, "y":2.2712, "heading":-2.10439, "vx":-3.5008, "vy":-0.20128, "omega":-1.14528, "ax":-5.00684, "ay":1.6899, "alpha":12.37017, "fx":[-55.72004,-82.60328,-107.74239,-94.59416], "fy":[87.84009,69.16031,6.52119,-48.54293]}, - {"t":0.71724, "x":3.80195, "y":2.26837, "heading":-2.12157, "vx":-3.57593, "vy":-0.17593, "omega":-0.95966, "ax":-5.04595, "ay":1.0446, "alpha":12.59207, "fx":[-65.12841,-86.45634,-107.56515,-84.17092], "fy":[76.14346,63.38183,-3.81511,-64.63674]}, - {"t":0.73224, "x":3.74773, "y":2.26585, "heading":-2.13598, "vx":-3.65165, "vy":-0.16025, "omega":-0.77071, "ax":-5.00386, "ay":-0.17846, "alpha":12.16723, "fx":[-76.4678,-90.87026,-105.7112,-67.40758], "fy":[32.65721,55.31922,-18.23806,-81.88038]}, - {"t":0.74725, "x":3.69237, "y":2.26342, "heading":-2.14754, "vx":-3.72673, "vy":-0.16293, "omega":-0.58813, "ax":-4.44844, "ay":-2.68505, "alpha":11.48289, "fx":[-45.17163,-101.26348,-100.11359,-56.11801], "fy":[-83.26908,27.66436,-37.12139,-89.96162]}, - {"t":0.76225, "x":3.63595, "y":2.26068, "heading":-2.15637, "vx":-3.79348, "vy":-0.20322, "omega":-0.41582, "ax":-3.61404, "ay":-4.17631, "alpha":9.77775, "fx":[-17.28261,-100.3131,-86.88839,-41.41106], "fy":[-100.34742,-24.83415,-61.26088,-97.70893]}, - {"t":0.77726, "x":3.57862, "y":2.25716, "heading":-2.1626, "vx":-3.84771, "vy":-0.26589, "omega":-0.2691, "ax":-2.22155, "ay":-5.46368, "alpha":6.4529, "fx":[2.78301,-66.47301,-64.34218,-23.11979], "fy":[-104.38928,-79.02834,-84.45268,-103.87203]}, - {"t":0.79227, "x":3.52063, "y":2.25255, "heading":-2.16664, "vx":-3.88105, "vy":-0.34787, "omega":-0.17227, "ax":-1.20433, "ay":-5.95493, "alpha":4.37991, "fx":[10.03436,-35.36842,-44.75473,-11.85242], "fy":[-104.89599,-98.06687,-96.29951,-105.90392]}, - {"t":0.80868, "x":3.45676, "y":2.24604, "heading":-2.16947, "vx":-3.90082, "vy":-0.44562, "omega":-0.10038, "ax":-0.41358, "ay":-6.09746, "alpha":2.91966, "fx":[13.59958,-13.29211,-25.70816,-2.73877], "fy":[-103.96771,-103.05165,-102.11265,-105.73199]}, - {"t":0.8251, "x":3.39267, "y":2.2379, "heading":-2.17112, "vx":-3.90761, "vy":-0.54571, "omega":-0.05245, "ax":0.3402, "ay":-6.10513, "alpha":1.48093, "fx":[16.11546,4.29614,-4.31628,7.05147], "fy":[-102.98016,-103.59571,-104.28172,-104.52862]}, - {"t":0.84151, "x":3.32857, "y":2.22812, "heading":-2.17198, "vx":-3.90202, "vy":-0.64593, "omega":-0.02814, "ax":0.86101, "ay":-6.02184, "alpha":0.54742, "fx":[18.39711,14.45347,10.89679,14.83478], "fy":[-101.85465,-102.25787,-102.94669,-102.65975]}, - {"t":0.85793, "x":3.26464, "y":2.21671, "heading":-2.17244, "vx":-3.88789, "vy":-0.74478, "omega":-0.01916, "ax":1.14666, "ay":-5.92562, "alpha":0.16621, "fx":[20.62605,19.49853,18.3815,19.51131], "fy":[-100.57395,-100.718,-101.00712,-100.87302]}, - {"t":0.87434, "x":3.20097, "y":2.20368, "heading":-2.17276, "vx":-3.86907, "vy":-0.84205, "omega":-0.01643, "ax":1.32374, "ay":-5.83293, "alpha":0.05081, "fx":[22.85425,22.52409,22.17846,22.50899], "fy":[-99.14063,-99.18773,-99.29183,-99.24558]}, - {"t":0.89076, "x":3.13764, "y":2.18907, "heading":-2.17303, "vx":-3.84734, "vy":-0.9378, "omega":-0.01559, "ax":1.464, "ay":-5.73907, "alpha":0.0197, "fx":[25.03115,24.90802,24.77331,24.89652], "fy":[-97.58776,-97.6066,-97.65195,-97.63323]}, - {"t":0.90717, "x":3.07468, "y":2.17291, "heading":-2.17328, "vx":-3.82331, "vy":-1.03201, "omega":-0.01527, "ax":1.591, "ay":-5.64302, "alpha":0.01036, "fx":[27.12901,27.06671,26.99574,27.05807], "fy":[-95.96795,-95.97798,-96.00425,-95.99426]}, - {"t":0.92359, "x":3.01214, "y":2.15521, "heading":-2.17353, "vx":-3.79719, "vy":-1.12464, "omega":-0.0151, "ax":1.71187, "ay":-5.54772, "alpha":0.00604, "fx":[29.15658,29.12162,29.08024,29.1152], "fy":[-94.35393,-94.35978,-94.37645,-94.3706]}, - {"t":0.94, "x":2.95003, "y":2.136, "heading":-2.17378, "vx":-3.76909, "vy":-1.2157, "omega":-0.015, "ax":1.83008, "ay":-5.45821, "alpha":0.00284, "fx":[31.14679,31.13097,31.11152,31.12734], "fy":[-92.837,-92.83975,-92.84819,-92.84544]}, - {"t":0.95642, "x":2.88841, "y":2.11531, "heading":-2.17403, "vx":-3.73905, "vy":-1.3053, "omega":-0.01495, "ax":1.94882, "ay":-5.38005, "alpha":-0.00009, "fx":[33.14835,33.14885,33.14949,33.14899], "fy":[-91.51326,-91.51317,-91.51287,-91.51296]}, - {"t":0.97283, "x":2.8273, "y":2.09316, "heading":-2.17427, "vx":-3.70706, "vy":-1.39361, "omega":-0.01496, "ax":2.07136, "ay":-5.31767, "alpha":-0.00297, "fx":[35.21525,35.23064,35.25114,35.23576], "fy":[-90.45848,-90.45549,-90.44546,-90.44845]}, - {"t":0.98925, "x":2.76672, "y":2.06956, "heading":-2.17452, "vx":-3.67306, "vy":-1.4809, "omega":-0.015, "ax":2.20039, "ay":-5.27276, "alpha":-0.00596, "fx":[37.39253,37.42224,37.4636,37.43391], "fy":[-89.70186,-89.6956,-89.67439,-89.68066]}, - {"t":1.00566, "x":2.70673, "y":2.04454, "heading":-2.17476, "vx":-3.63694, "vy":-1.56746, "omega":-0.0151, "ax":2.33746, "ay":-5.2435, "alpha":-0.00948, "fx":[39.70351,39.74902,39.81554,39.77007], "fy":[-89.21352,-89.2029,-89.16735,-89.17797]}, - {"t":1.02208, "x":2.64734, "y":2.01811, "heading":-2.17501, "vx":-3.59857, "vy":-1.65353, "omega":-0.01526, "ax":2.4831, "ay":-5.22487, "alpha":-0.01581, "fx":[42.1442,42.21704,42.32928,42.25656], "fy":[-88.9143,-88.89529,-88.83294,-88.85196]}, - {"t":1.03849, "x":2.5886, "y":1.99026, "heading":-2.17526, "vx":-3.55781, "vy":-1.7393, "omega":-0.01552, "ax":2.6395, "ay":-5.20894, "alpha":-0.03693, "fx":[44.68312,44.84566,45.11093,44.94909], "fy":[-88.70314,-88.65547,-88.50212,-88.54985]}, - {"t":1.05491, "x":2.53056, "y":1.96101, "heading":-2.17552, "vx":-3.51448, "vy":-1.8248, "omega":-0.01612, "ax":2.82163, "ay":-5.18022, "alpha":-0.12986, "fx":[47.25154,47.79315,48.73383,48.20162], "fy":[-88.48952,-88.31077,-87.73847,-87.91725]}, - {"t":1.07132, "x":2.47325, "y":1.93035, "heading":-2.17578, "vx":-3.46816, "vy":-1.90984, "omega":-0.01826, "ax":3.09263, "ay":-5.0911, "alpha":-0.51363, "fx":[49.72667,51.7146,55.40197,53.57565], "fy":[-88.20772,-87.46626,-84.99749,-85.72087]}, - {"t":1.08774, "x":2.41673, "y":1.89832, "heading":-2.17608, "vx":-3.4174, "vy":-1.99341, "omega":-0.02669, "ax":3.59155, "ay":-4.80276, "alpha":-1.6836, "fx":[52.14371,57.88024,69.0902,65.25085], "fy":[-87.68462,-85.23078,-76.03048,-77.82843]}, - {"t":1.10415, "x":2.36112, "y":1.86495, "heading":-2.17652, "vx":-3.35844, "vy":-2.07225, "omega":-0.05432, "ax":4.28537, "ay":-4.16878, "alpha":-3.75164, "fx":[55.45368,65.78217,86.04152,84.29439], "fy":[-86.25745,-81.15517,-58.86123,-57.36535]}, - {"t":1.12057, "x":2.30657, "y":1.83037, "heading":-2.17741, "vx":-3.2881, "vy":-2.14068, "omega":-0.11591, "ax":4.8644, "ay":-3.34972, "alpha":-5.81584, "fx":[61.41057,73.23858,97.11342,99.20585], "fy":[-82.67662,-76.05415,-41.45003,-27.7302]}, - {"t":1.13698, "x":2.25325, "y":1.79478, "heading":-2.17931, "vx":-3.20825, "vy":-2.19566, "omega":-0.21137, "ax":5.35167, "ay":-2.54613, "alpha":-6.24775, "fx":[75.35128,81.7854,102.59341,104.39136], "fy":[-71.23335,-67.91148,-28.54509,-5.54571]}, - {"t":1.1534, "x":2.20131, "y":1.7584, "heading":-2.18278, "vx":-3.1204, "vy":-2.23746, "omega":-0.31393, "ax":5.98288, "ay":-1.52462, "alpha":-3.31317, "fx":[98.73002,96.95917,105.32755,106.05177], "fy":[-37.25993,-44.52969,-18.51879,-3.42524]}, - {"t":1.16981, "x":2.15089, "y":1.72146, "heading":-2.18794, "vx":-3.02219, "vy":-2.26248, "omega":-0.36832, "ax":6.25649, "ay":-0.66624, "alpha":-0.84994, "fx":[106.15494,105.78911,106.80412,106.93638], "fy":[-13.0561,-17.06394,-9.79838,-5.41207]}, - {"t":1.18623, "x":2.10213, "y":1.68423, "heading":-2.19398, "vx":-2.91949, "vy":-2.27342, "omega":-0.38227, "ax":6.32257, "ay":-0.07036, "alpha":0.82385, "fx":[107.74837,107.51474,107.4846,107.43252], "fy":[-0.22726,4.69472,-2.27683,-6.97806]}, - {"t":1.20264, "x":2.05505, "y":1.64691, "heading":-2.20026, "vx":-2.8157, "vy":-2.27458, "omega":-0.36875, "ax":6.31232, "ay":0.34268, "alpha":1.96614, "fx":[107.98262,106.11391,107.6452,107.74098], "fy":[7.15265,20.07477,4.17875,-8.09036]}, - {"t":1.21906, "x":2.00968, "y":1.60961, "heading":-2.20631, "vx":-2.71208, "vy":-2.26895, "omega":-0.33647, "ax":6.27757, "ay":0.63833, "alpha":2.76381, "fx":[107.87911,103.81646,107.47375,107.94912], "fy":[11.81291,30.79778,9.72216,-8.90169]}, - {"t":1.23547, "x":1.96601, "y":1.57245, "heading":-2.21183, "vx":-2.60904, "vy":-2.25847, "omega":-0.2911, "ax":6.23718, "ay":0.85822, "alpha":3.34173, "fx":[107.69901,101.47635,107.09682,108.0984], "fy":[14.97719,38.43672,14.49319,-9.51456]}, - {"t":1.25189, "x":1.92402, "y":1.5355, "heading":-2.21661, "vx":-2.50665, "vy":-2.24439, "omega":-0.23625, "ax":6.17118, "ay":1.60969, "alpha":2.5856, "fx":[106.30974,99.65311,104.95663,108.96042], "fy":[25.77389,44.96083,30.11529,8.67121]}, - {"t":1.28737, "x":1.83897, "y":1.45688, "heading":-2.22499, "vx":-2.28769, "vy":-2.18727, "omega":-0.14451, "ax":5.85735, "ay":2.59068, "alpha":1.92085, "fx":[101.46976,94.12965,98.08117,104.8469], "fy":[41.01736,55.77777,48.30297,31.16848]}, - {"t":1.32285, "x":1.76149, "y":1.3809, "heading":-2.23012, "vx":-2.07987, "vy":-2.09535, "omega":-0.07636, "ax":5.53561, "ay":3.25428, "alpha":1.40081, "fx":[96.22344,89.47725,92.02458,98.91123], "fy":[52.25512,63.08598,59.21224,46.86442]}, - {"t":1.35833, "x":1.69118, "y":1.30861, "heading":-2.23283, "vx":-1.88346, "vy":-1.97989, "omega":-0.02665, "ax":5.25086, "ay":3.71369, "alpha":1.00404, "fx":[91.28252,85.66627,87.22297,93.0908], "fy":[60.55024,68.25202,66.19789,57.67538]}, - {"t":1.39381, "x":1.62765, "y":1.24069, "heading":-2.23378, "vx":-1.69715, "vy":-1.84812, "omega":0.00897, "ax":5.01014, "ay":4.04253, "alpha":0.6999, "fx":[86.88564,82.54776,83.46284,87.98783], "fy":[66.76392,72.05217,70.95992,65.27307]}, - {"t":1.42929, "x":1.57059, "y":1.17767, "heading":-2.23346, "vx":-1.51939, "vy":-1.70469, "omega":0.0338, "ax":4.80894, "ay":4.2859, "alpha":0.46264, "fx":[83.06137,79.97574,80.48482,83.67309], "fy":[71.51038,74.94253,74.37864,70.7763]}, - {"t":1.46477, "x":1.51971, "y":1.11988, "heading":-2.23226, "vx":-1.34876, "vy":-1.55262, "omega":0.05022, "ax":4.64048, "ay":4.47153, "alpha":0.27378, "fx":[79.75988,77.83192,78.08586,80.0552], "fy":[75.2105,77.20277,76.93724,74.88727]}, - {"t":1.50026, "x":1.47477, "y":1.06761, "heading":-2.23048, "vx":-1.18412, "vy":-1.39397, "omega":0.05993, "ax":4.49843, "ay":4.61686, "alpha":0.12052, "fx":[76.90991,76.02529,76.11978,77.0132], "fy":[78.1512,79.01165,78.91725,78.04602]}, - {"t":1.53574, "x":1.43559, "y":1.02105, "heading":-2.22835, "vx":-1.02451, "vy":-1.23016, "omega":0.06421, "ax":4.37761, "ay":4.73323, "alpha":-0.00602, "fx":[74.44103,74.4867,74.4827,74.43706], "fy":[80.53003,80.48781,80.49166,80.53386]}, - {"t":1.57122, "x":1.402, "y":0.98039, "heading":-2.22607, "vx":-0.86919, "vy":-1.06222, "omega":0.06399, "ax":4.2739, "ay":4.8282, "alpha":-0.11209, "fx":[72.29116,73.16348,73.10024,72.23648], "fy":[82.48519,81.71263,81.77174,82.5356]}, - {"t":1.6067, "x":1.37385, "y":0.94574, "heading":-2.2238, "vx":-0.71754, "vy":-0.89091, "omega":0.06002, "ax":4.1841, "ay":4.907, "alpha":-0.20218, "fx":[70.40798,72.01513,71.91833,70.34006], "fy":[84.11515,82.74359,82.83192,84.17608]}, - {"t":1.64218, "x":1.35102, "y":0.91721, "heading":-2.22167, "vx":-0.56909, "vy":-0.7168, "omega":0.05284, "ax":4.1057, "ay":4.97332, "alpha":-0.27958, "fx":[68.74827,71.01018,70.89701,68.69196], "fy":[85.4914,83.62233,83.72363,85.54188]}, - {"t":1.67766, "x":1.33341, "y":0.89491, "heading":-2.2198, "vx":-0.42341, "vy":-0.54035, "omega":0.04292, "ax":4.03674, "ay":5.02984, "alpha":-0.34675, "fx":[67.27661,70.12392,70.00623,67.24849], "fy":[86.66675,84.3797,84.48348,86.69455]}, - {"t":1.71314, "x":1.32093, "y":0.87891, "heading":-2.21827, "vx":-0.28019, "vy":-0.36188, "omega":0.03062, "ax":3.97565, "ay":5.07852, "alpha":-0.40557, "fx":[65.96398,69.33665,69.22308,65.97531], "fy":[87.68087,85.039,85.13813,87.67882]}, - {"t":1.74862, "x":1.31349, "y":0.86926, "heading":-2.21719, "vx":-0.13913, "vy":-0.18169, "omega":0.01623, "ax":3.9212, "ay":5.12086, "alpha":-0.45748, "fx":[64.78652,68.63257,68.52978,64.84527], "fy":[88.56407,85.61815,85.70747,88.52788]}, - {"t":1.7841, "x":1.31103, "y":0.86604, "heading":-2.21661, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.34201, "ay":3.61269, "alpha":0.40718, "fx":[91.59705,89.37406,90.11985,92.37347], "fy":[60.39922,63.63948,62.56939,59.19527]}, - {"t":1.81481, "x":1.31354, "y":0.86774, "heading":-2.21661, "vx":0.16404, "vy":0.11093, "omega":0.0125, "ax":5.34166, "ay":3.61245, "alpha":0.40111, "fx":[91.58035,89.39036,90.12501,92.34473], "fy":[60.41055,63.60318,62.54798,59.22547]}, - {"t":1.84552, "x":1.3211, "y":0.87285, "heading":-2.21623, "vx":0.32806, "vy":0.22186, "omega":0.02482, "ax":5.34127, "ay":3.61219, "alpha":0.39435, "fx":[91.56122,89.4082,90.13133,92.31301], "fy":[60.42399,63.56318,62.52333,59.25865]}, - {"t":1.87622, "x":1.33369, "y":0.88137, "heading":-2.21547, "vx":0.49208, "vy":0.33278, "omega":0.03693, "ax":5.34083, "ay":3.61189, "alpha":0.38678, "fx":[91.53934,89.42793,90.13885,92.27769], "fy":[60.4397,63.5187,62.49509,59.29546]}, - {"t":1.90693, "x":1.35132, "y":0.89329, "heading":-2.21433, "vx":0.65608, "vy":0.44369, "omega":0.04881, "ax":5.34033, "ay":3.61156, "alpha":0.37825, "fx":[91.51432,89.44997,90.14766,92.23803], "fy":[60.4579,63.46877,62.46278,59.33666]}, - {"t":1.93764, "x":1.37398, "y":0.90862, "heading":-2.21283, "vx":0.82006, "vy":0.55459, "omega":0.06042, "ax":5.33977, "ay":3.61117, "alpha":0.36856, "fx":[91.48568,89.4749,90.15785,92.19307], "fy":[60.47889,63.41216,62.42582,59.38328]}, - {"t":1.96834, "x":1.40168, "y":0.92735, "heading":-2.21098, "vx":0.98403, "vy":0.66548, "omega":0.07174, "ax":5.33912, "ay":3.61074, "alpha":0.35745, "fx":[91.45278,89.5034,90.16954,92.14159], "fy":[60.50302,63.34727,62.38345,59.43658]}, - {"t":1.99905, "x":1.43442, "y":0.94949, "heading":-2.20878, "vx":1.14798, "vy":0.77636, "omega":0.08271, "ax":5.33836, "ay":3.61023, "alpha":0.34461, "fx":[91.41475,89.53642,90.18291,92.08197], "fy":[60.53079,63.27202,62.33467,59.49824]}, - {"t":2.02976, "x":1.47218, "y":0.97503, "heading":-2.20624, "vx":1.31191, "vy":0.88722, "omega":0.0933, "ax":5.33748, "ay":3.60963, "alpha":0.32957, "fx":[91.37046,89.57519,90.19818,92.01205], "fy":[60.56287,63.18361,62.27812,59.57051]}, - {"t":2.06047, "x":1.51499, "y":1.00397, "heading":-2.20337, "vx":1.4758, "vy":0.99806, "omega":0.10342, "ax":5.33642, "ay":3.60892, "alpha":0.31174, "fx":[91.31832,89.6214,90.21566,91.92887], "fy":[60.60017,63.0782,62.21198,59.65642]}, - {"t":2.09117, "x":1.56282, "y":1.03632, "heading":-2.20019, "vx":1.63967, "vy":1.10888, "omega":0.11299, "ax":5.33515, "ay":3.60806, "alpha":0.29025, "fx":[91.2561,89.6774,90.23579,91.82825], "fy":[60.64399,62.95038,62.13363,59.76024]}, - {"t":2.12188, "x":1.61568, "y":1.07207, "heading":-2.19673, "vx":1.8035, "vy":1.21967, "omega":0.1219, "ax":5.33358, "ay":3.607, "alpha":0.26385, "fx":[91.18048,89.74661,90.25921,91.70415], "fy":[60.69627,62.79224,62.0393,59.88816]}, - {"t":2.15259, "x":1.67358, "y":1.11123, "heading":-2.19298, "vx":1.96727, "vy":1.33043, "omega":0.13, "ax":5.33158, "ay":3.60565, "alpha":0.23065, "fx":[91.08644,89.83415,90.28689,91.54738], "fy":[60.75993,62.59181,61.92331,60.04942]}, - {"t":2.18329, "x":1.7365, "y":1.15378, "heading":-2.18899, "vx":2.13099, "vy":1.44115, "omega":0.13709, "ax":5.32898, "ay":3.6039, "alpha":0.18764, "fx":[90.96589,89.9481,90.32033,91.34337], "fy":[60.83966,62.32999,61.77663,60.25863]}, - {"t":2.214, "x":1.80445, "y":1.19973, "heading":-2.18478, "vx":2.29463, "vy":1.55181, "omega":0.14285, "ax":5.32543, "ay":3.6015, "alpha":0.12973, "fx":[90.80497,90.10195,90.36206,91.06749], "fy":[60.94348,61.97434,61.58416,60.54014]}, - {"t":2.24471, "x":1.87742, "y":1.24908, "heading":-2.18039, "vx":2.45816, "vy":1.6624, "omega":0.14683, "ax":5.32033, "ay":3.59806, "alpha":0.04761, "fx":[90.57784,90.32008,90.4165,90.67458], "fy":[61.08623,61.46497,61.31846,60.93796]}, - {"t":2.27542, "x":1.95541, "y":1.30183, "heading":-2.17589, "vx":2.62153, "vy":1.77289, "omega":0.14829, "ax":5.31235, "ay":3.59267, "alpha":-0.07785, "fx":[90.23025,90.6514,90.49234,90.072], "fy":[61.29866,60.67786,60.92425,61.54038]}, - {"t":2.30612, "x":2.03842, "y":1.35796, "heading":-2.17133, "vx":2.78465, "vy":1.88321, "omega":0.1459, "ax":5.29816, "ay":3.5831, "alpha":-0.29295, "fx":[89.62617,91.21033,90.60875,89.03551], "fy":[61.65634,59.30805,60.27125,62.55407]}, - {"t":2.33683, "x":2.12642, "y":1.41748, "heading":-2.16685, "vx":2.94735, "vy":1.99324, "omega":0.13691, "ax":5.26623, "ay":3.56156, "alpha":-0.74565, "fx":[88.30312,92.33748,90.81683,86.85103], "fy":[62.40585,56.35557,58.96438,64.59853]}, - {"t":2.36754, "x":2.21941, "y":1.48036, "heading":-2.16265, "vx":3.10906, "vy":2.1026, "omega":0.11401, "ax":5.1361, "ay":3.47485, "alpha":-2.29297, "fx":[83.11238,95.56409,91.28397,79.49372], "fy":[65.0361,45.7092,55.01646,70.66281]}, - {"t":2.39824, "x":2.3173, "y":1.54657, "heading":-2.15915, "vx":3.26677, "vy":2.2093, "omega":0.0436, "ax":0.63596, "ay":0.42892, "alpha":-1.40199, "fx":[5.78223,11.91329,15.79756,9.77664], "fy":[6.35528,2.20271,8.24903,12.37609]}, - {"t":2.42895, "x":2.41791, "y":1.61461, "heading":-2.15781, "vx":3.2863, "vy":2.22247, "omega":0.00055, "ax":0.00117, "ay":0.00038, "alpha":-0.00143, "fx":[0.01467,0.02085,0.02497,0.01878], "fy":[0.00551,0.0014,0.00758,0.0117]}, - {"t":2.45966, "x":2.51883, "y":1.68285, "heading":-2.15779, "vx":3.28633, "vy":2.22248, "omega":0.00051, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[-0.00001,-0.00001,-0.00001,-0.00001], "fy":[0.00001,0.00001,0.00001,0.00001]}, - {"t":2.49036, "x":2.61974, "y":1.7511, "heading":-2.15778, "vx":3.28633, "vy":2.22248, "omega":0.00051, "ax":-0.00117, "ay":-0.00038, "alpha":0.00143, "fx":[-0.01469,-0.02088,-0.02499,-0.01881], "fy":[-0.00549,-0.00137,-0.00756,-0.01167]}, - {"t":2.52107, "x":2.72065, "y":1.81935, "heading":-2.15776, "vx":3.2863, "vy":2.22247, "omega":0.00055, "ax":-0.6361, "ay":-0.42901, "alpha":1.40281, "fx":[-5.78311,-11.92333,-15.80134,-9.77147], "fy":[-6.34913,-2.2026,-8.25807,-12.37937]}, - {"t":2.55178, "x":2.82127, "y":1.88739, "heading":-2.15774, "vx":3.26677, "vy":2.2093, "omega":0.04363, "ax":-5.136, "ay":-3.47479, "alpha":2.29596, "fx":[-83.15254,-95.58622,-91.25484,-79.45369], "fy":[-64.97993,-45.66862,-55.067,-70.70494]}, - {"t":2.58249, "x":2.91916, "y":1.95359, "heading":-2.1564, "vx":3.10905, "vy":2.1026, "omega":0.11413, "ax":-5.26622, "ay":-3.56155, "alpha":0.74679, "fx":[-88.33164,-92.35272,-90.79153,-86.83172], "fy":[-62.36451,-56.33201,-59.00398,-64.62326]}, - {"t":2.61319, "x":3.01214, "y":2.01648, "heading":-2.1529, "vx":2.94734, "vy":1.99323, "omega":0.13706, "ax":-5.29816, "ay":-3.58309, "alpha":0.29344, "fx":[-89.64597,-91.22049,-90.58987,-89.02423], "fy":[-61.62717,-59.293,-60.2999,-62.56952]}, - {"t":2.6439, "x":3.10015, "y":2.07599, "heading":-2.14869, "vx":2.78465, "vy":1.88321, "omega":0.14607, "ax":-5.31235, "ay":-3.59267, "alpha":0.07802, "fx":[-90.23795,-90.65544,-90.48473,-90.06782], "fy":[-61.28723,-60.67197,-60.93563,-61.5463]}, - {"t":2.67461, "x":3.18315, "y":2.13213, "heading":-2.1442, "vx":2.62153, "vy":1.77289, "omega":0.14847, "ax":-5.32033, "ay":-3.59806, "alpha":-0.04762, "fx":[-90.57142,-90.31719,-90.42297,-90.6774], "fy":[-61.09579,-61.46909,-61.30887,-60.93387]}, - {"t":2.70531, "x":3.26115, "y":2.18487, "heading":-2.13965, "vx":2.45816, "vy":1.6624, "omega":0.147, "ax":-5.32543, "ay":-3.6015, "alpha":-0.12987, "fx":[-90.78341,-90.09168,-90.3841,-91.07725], "fy":[-60.97573,-61.98895,-61.55164,-60.52578]}, - {"t":2.73602, "x":3.33412, "y":2.23422, "heading":-2.13513, "vx":2.29463, "vy":1.55181, "omega":0.14302, "ax":-5.32898, "ay":-3.60389, "alpha":-0.18786, "fx":[-90.92881,-89.93025,-90.35865,-91.35993], "fy":[-60.89526,-62.35528,-61.72035,-60.23399]}, - {"t":2.76673, "x":3.40207, "y":2.28017, "heading":-2.13074, "vx":2.13099, "vy":1.44115, "omega":0.13725, "ax":-5.33158, "ay":-3.60565, "alpha":-0.23093, "fx":[-91.03388,-89.80874,-90.34163,-91.57055], "fy":[-60.8389,-62.62769,-61.84314,-60.01469]}, - {"t":2.79743, "x":3.46499, "y":2.32273, "heading":-2.12653, "vx":1.96727, "vy":1.33043, "omega":0.13016, "ax":-5.33358, "ay":-3.607, "alpha":-0.26417, "fx":[-91.11276,-89.7138,-90.33015,-91.73366], "fy":[-60.79817,-62.83846,-61.93565,-59.84364]}, - {"t":2.82814, "x":3.52288, "y":2.36188, "heading":-2.12253, "vx":1.8035, "vy":1.21967, "omega":0.12204, "ax":-5.33515, "ay":-3.60806, "alpha":-0.2906, "fx":[-91.17376,-89.63745,-90.32244,-91.86379], "fy":[-60.76801,-63.00655,-62.00725,-59.70637]}, - {"t":2.85885, "x":3.57575, "y":2.39763, "heading":-2.11878, "vx":1.63967, "vy":1.10887, "omega":0.11312, "ax":-5.33642, "ay":-3.60892, "alpha":-0.31212, "fx":[-91.2221,-89.57465,-90.31732,-91.97007], "fy":[-60.74524,-63.14383,-62.06393,-59.5937]}, - {"t":2.88956, "x":3.62358, "y":2.42998, "heading":-2.11531, "vx":1.4758, "vy":0.99806, "omega":0.10354, "ax":-5.33748, "ay":-3.60963, "alpha":-0.32997, "fx":[-91.26119,-89.52207,-90.314,-92.05852], "fy":[-60.72774,-63.2581,-62.10967,-59.49952]}, - {"t":2.92026, "x":3.66638, "y":2.45893, "heading":-2.11213, "vx":1.31191, "vy":0.88721, "omega":0.0934, "ax":-5.33836, "ay":-3.61023, "alpha":-0.34502, "fx":[-91.29338,-89.47738,-90.3119,-92.13328], "fy":[-60.71403,-63.35472,-62.14726,-59.41963]}, - {"t":2.95097, "x":3.70415, "y":2.48447, "heading":-2.10926, "vx":1.14798, "vy":0.77636, "omega":0.08281, "ax":-5.33911, "ay":-3.61073, "alpha":-0.35788, "fx":[-91.32034,-89.43894,-90.31061,-92.19729], "fy":[-60.70307,-63.43746,-62.17867,-59.35103]}, - {"t":2.98168, "x":3.73688, "y":2.5066, "heading":-2.10672, "vx":0.98403, "vy":0.66548, "omega":0.07182, "ax":-5.33976, "ay":-3.61117, "alpha":-0.36899, "fx":[-91.3433,-89.40556,-90.30982,-92.25269], "fy":[-60.69407,-63.50909,-62.20538,-59.29151]}, - {"t":3.01238, "x":3.76458, "y":2.52534, "heading":-2.10451, "vx":0.82006, "vy":0.55459, "omega":0.06049, "ax":-5.34033, "ay":-3.61155, "alpha":-0.37869, "fx":[-91.36315,-89.37634,-90.30929,-92.30108], "fy":[-60.68646,-63.57165,-62.22849,-59.23943]}, - {"t":3.04309, "x":3.78725, "y":2.54066, "heading":-2.10265, "vx":0.65608, "vy":0.44369, "omega":0.04886, "ax":-5.34083, "ay":-3.61189, "alpha":-0.38723, "fx":[-91.38059,-89.35058,-90.30883,-92.34366], "fy":[-60.67977,-63.62669,-62.24883,-59.19354]}, - {"t":3.0738, "x":3.80488, "y":2.55259, "heading":-2.10115, "vx":0.49208, "vy":0.33278, "omega":0.03697, "ax":-5.34127, "ay":-3.61219, "alpha":-0.3948, "fx":[-91.39617,-89.32776,-90.30829,-92.38138], "fy":[-60.67367,-63.67543,-62.26709,-59.15287]}, - {"t":3.1045, "x":3.81747, "y":2.5611, "heading":-2.10002, "vx":0.32806, "vy":0.22186, "omega":0.02485, "ax":-5.34166, "ay":-3.61245, "alpha":-0.40157, "fx":[-91.41031,-89.30746,-90.30755,-92.41499], "fy":[-60.66787,-63.71881,-62.28377,-59.11663]}, - {"t":3.13521, "x":3.82502, "y":2.56621, "heading":-2.09926, "vx":0.16404, "vy":0.11093, "omega":0.01252, "ax":-5.34201, "ay":-3.61269, "alpha":-0.40765, "fx":[-91.42334,-89.28934,-90.30652,-92.44507], "fy":[-60.66214,-63.75757,-62.29931,-59.08423]}, - {"t":3.16592, "x":3.82754, "y":2.56791, "heading":-2.09887, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[ - {"name":"Funnel", "from":{"target":5, "targetTimestamp":2.52107, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] -} diff --git a/src/main/deploy/choreo/A_RIGHT_PATH3.traj b/src/main/deploy/choreo/A_RIGHT_PATH3.traj deleted file mode 100644 index e75d4f96..00000000 --- a/src/main/deploy/choreo/A_RIGHT_PATH3.traj +++ /dev/null @@ -1,118 +0,0 @@ -{ - "name":"A_RIGHT_PATH3", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":3.999176502227783, "y":2.845594631958008, "heading":-2.1010083691287966, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.3110252618789673, "y":0.8660395019531251, "heading":-2.2024870470289093, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.495954990386963, "y":1.9211212396621704, "heading":0.0, "intervals":32, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":3.410642147064209, "y":2.7169248931884766, "heading":-2.077894951837786, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"3.999176502227783 m", "val":3.999176502227783}, "y":{"exp":"(8.0518 - 5.206205368041992) m", "val":2.845594631958008}, "heading":{"exp":"-2.1010083691287966 rad", "val":-2.1010083691287966}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"(8.0518 - 7.185760498046875) m", "val":0.8660395019531251}, "heading":{"exp":"-2.2024870470289093 rad", "val":-2.2024870470289093}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.495954990386963 m", "val":2.495954990386963}, "y":{"exp":"1.9211212396621704 m", "val":1.9211212396621704}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":32, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"3.410642147064209 m", "val":3.410642147064209}, "y":{"exp":"(8.0518 - 5.334875106811523) m", "val":2.7169248931884766}, "heading":{"exp":"-2.077894951837786 rad", "val":-2.077894951837786}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.45692,2.1638,2.77848], - "samples":[ - {"t":0.0, "x":3.99918, "y":2.84559, "heading":-2.10101, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.19517, "ay":-3.82571, "alpha":-0.34139, "fx":[-88.91725,-86.99375,-87.81273,-89.74956], "fy":[-64.3502,-66.92562,-65.84215,-63.17899]}, - {"t":0.04415, "x":3.99411, "y":2.84187, "heading":-2.10101, "vx":-0.22936, "vy":-0.1689, "omega":-0.01507, "ax":-5.19479, "ay":-3.82543, "alpha":-0.33555, "fx":[-88.90161,-87.01099,-87.81583,-89.71932], "fy":[-64.35768,-66.88948,-65.82375,-63.2072]}, - {"t":0.0883, "x":3.97892, "y":2.83068, "heading":-2.10167, "vx":-0.45871, "vy":-0.33779, "omega":-0.02989, "ax":-5.19435, "ay":-3.82511, "alpha":-0.32866, "fx":[-88.88404,-87.03165,-87.81856,-89.68341], "fy":[-64.3653,-66.84643,-65.80332,-63.24085]}, - {"t":0.13245, "x":3.95361, "y":2.81204, "heading":-2.10299, "vx":-0.68803, "vy":-0.50666, "omega":-0.0444, "ax":-5.19382, "ay":-3.82472, "alpha":-0.32045, "fx":[-88.86366,-87.05657,-87.82116,-89.64027], "fy":[-64.37356,-66.79464,-65.77981,-63.28131]}, - {"t":0.1766, "x":3.91817, "y":2.78594, "heading":-2.10495, "vx":-0.91733, "vy":-0.67552, "omega":-0.05854, "ax":-5.19318, "ay":-3.82424, "alpha":-0.31046, "fx":[-88.83917,-87.08696,-87.82397,-89.58773], "fy":[-64.38315,-66.73149,-65.75173,-63.3306]}, - {"t":0.22074, "x":3.87261, "y":2.75239, "heading":-2.10754, "vx":-1.14661, "vy":-0.84436, "omega":-0.07225, "ax":-5.19238, "ay":-3.82365, "alpha":-0.29807, "fx":[-88.8087,-87.12461,-87.82747,-89.52252], "fy":[-64.3951,-66.65308,-65.71687,-63.39167]}, - {"t":0.26489, "x":3.81693, "y":2.71139, "heading":-2.11073, "vx":-1.37584, "vy":-1.01317, "omega":-0.08541, "ax":-5.19135, "ay":-3.82289, "alpha":-0.28229, "fx":[-88.76932,-87.1723,-87.8324,-89.43962], "fy":[-64.411,-66.55336,-65.67187,-63.46906]}, - {"t":0.30904, "x":3.75113, "y":2.66293, "heading":-2.1145, "vx":-1.60504, "vy":-1.18195, "omega":-0.09787, "ax":-5.19, "ay":-3.82189, "alpha":-0.26151, "fx":[-88.71626,-87.23451,-87.83993,-89.33078], "fy":[-64.43339,-66.42243,-65.61126,-63.57019]}, - {"t":0.35319, "x":3.67521, "y":2.60703, "heading":-2.11882, "vx":-1.83417, "vy":-1.35068, "omega":-0.10942, "ax":-5.18812, "ay":-3.82051, "alpha":-0.23289, "fx":[-88.64114,-87.31912,-87.85204,-89.18161], "fy":[-64.46672,-66.24289,-65.52553,-63.70797]}, - {"t":0.39734, "x":3.58918, "y":2.54367, "heading":-2.12365, "vx":-2.06322, "vy":-1.51935, "omega":-0.1197, "ax":-5.18536, "ay":-3.81847, "alpha":-0.191, "fx":[-88.52772,-87.4412,-87.87246,-88.9643], "fy":[-64.51951,-65.98105,-65.39654,-63.90708]}, - {"t":0.44149, "x":3.49304, "y":2.47287, "heading":-2.12893, "vx":-2.29215, "vy":-1.68793, "omega":-0.12813, "ax":-5.18087, "ay":-3.81515, "alpha":-0.12383, "fx":[-88.33985,-87.63367,-87.90905,-88.61758], "fy":[-64.61046,-65.56213,-65.18476,-64.22132]}, - {"t":0.48564, "x":3.38679, "y":2.39464, "heading":-2.13459, "vx":-2.52088, "vy":-1.85637, "omega":-0.1336, "ax":-5.17232, "ay":-3.80885, "alpha":0.00133, "fx":[-87.97734,-87.98496,-87.98205,-87.97442], "fy":[-64.79052,-64.78021,-64.78428,-64.79459]}, - {"t":0.52979, "x":3.27046, "y":2.30897, "heading":-2.14049, "vx":-2.74923, "vy":-2.02452, "omega":-0.13354, "ax":-5.14981, "ay":-3.79224, "alpha":0.31664, "fx":[-87.02035,-88.84034,-88.16478,-86.36184], "fy":[-65.26627,-62.78691,-63.78172,-66.18458]}, - {"t":0.57394, "x":3.14406, "y":2.21589, "heading":-2.14639, "vx":-2.97659, "vy":-2.19195, "omega":-0.11956, "ax":-4.9428, "ay":-3.64167, "alpha":2.67463, "fx":[-78.40448,-94.03118,-89.08997,-74.77678], "fy":[-69.03584,-46.77811,-57.31767,-74.64333]}, - {"t":0.61809, "x":3.00783, "y":2.11557, "heading":-2.15166, "vx":-3.19481, "vy":-2.35272, "omega":-0.00148, "ax":-0.02822, "ay":-0.0196, "alpha":0.02775, "fx":[-0.38028,-0.50071,-0.57975,-0.45932], "fy":[-0.31272,-0.23366,-0.35409,-0.43314]}, - {"t":0.66223, "x":2.86676, "y":2.01168, "heading":-2.15173, "vx":-3.19606, "vy":-2.35359, "omega":-0.00025, "ax":-0.00012, "ay":0.00015, "alpha":0.00001, "fx":[-0.00209,-0.00212,-0.00214,-0.00211], "fy":[0.00257,0.00258,0.00256,0.00254]}, - {"t":0.70638, "x":2.72565, "y":1.90777, "heading":-2.15174, "vx":-3.19606, "vy":-2.35358, "omega":-0.00025, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, - {"t":0.75053, "x":2.58455, "y":1.80386, "heading":-2.15175, "vx":-3.19606, "vy":-2.35358, "omega":-0.00025, "ax":0.00012, "ay":-0.00015, "alpha":-0.00001, "fx":[0.00208,0.00211,0.00213,0.0021], "fy":[-0.00255,-0.00257,-0.00254,-0.00252]}, - {"t":0.79468, "x":2.44345, "y":1.69995, "heading":-2.15176, "vx":-3.19606, "vy":-2.35359, "omega":-0.00025, "ax":0.02821, "ay":0.0196, "alpha":-0.02773, "fx":[0.38023,0.50059,0.57961,0.45925], "fy":[0.31276,0.23374,0.35409,0.43312]}, - {"t":0.83883, "x":2.30237, "y":1.59607, "heading":-2.15177, "vx":-3.19481, "vy":-2.35272, "omega":-0.00148, "ax":4.9428, "ay":3.64166, "alpha":-2.67446, "fx":[78.34131,94.01125,89.13137,74.81883], "fy":[69.1121,46.80728,57.25032,74.60493]}, - {"t":0.88298, "x":2.16614, "y":1.49574, "heading":-2.15184, "vx":-2.97659, "vy":-2.19195, "omega":-0.11955, "ax":5.14981, "ay":3.79224, "alpha":-0.3164, "fx":[87.00638,88.83321,88.17801,86.36971], "fy":[65.28507,62.79656,63.76322,66.17466]}, - {"t":0.92713, "x":2.03975, "y":1.40267, "heading":-2.15712, "vx":-2.74923, "vy":-2.02452, "omega":-0.13352, "ax":5.17232, "ay":3.80885, "alpha":-0.00126, "fx":[87.97736,87.9846,87.98202,87.97477], "fy":[64.79049,64.78069,64.78431,64.79411]}, - {"t":0.97128, "x":1.92341, "y":1.317, "heading":-2.16301, "vx":-2.52088, "vy":-1.85637, "omega":-0.13358, "ax":5.18087, "ay":3.81515, "alpha":0.12384, "fx":[88.35633,87.64142,87.89221,88.61017], "fy":[64.58784,65.55194,65.20754,64.23135]}, - {"t":1.01543, "x":1.81717, "y":1.23876, "heading":-2.16891, "vx":-2.29215, "vy":-1.68793, "omega":-0.12811, "ax":5.18536, "ay":3.81847, "alpha":0.19098, "fx":[88.56125,87.45744,87.83781,88.94917], "fy":[64.47335,65.95979,65.44319,63.92784]}, - {"t":1.05958, "x":1.72102, "y":1.16796, "heading":-2.17457, "vx":-2.06322, "vy":-1.51935, "omega":-0.11968, "ax":5.18812, "ay":3.82051, "alpha":0.23285, "fx":[88.69133,87.34374,87.79981,89.15903], "fy":[64.3975,66.21076,65.59566,63.7392]}, - {"t":1.10372, "x":1.63499, "y":1.10461, "heading":-2.17985, "vx":-1.83417, "vy":-1.35068, "omega":-0.1094, "ax":5.19, "ay":3.82189, "alpha":0.26146, "fx":[88.78219,87.26709,87.77098,89.30123], "fy":[64.34235,66.37999,65.70364,63.6113]}, - {"t":1.14787, "x":1.55907, "y":1.0487, "heading":-2.18468, "vx":-1.60504, "vy":-1.18195, "omega":-0.09786, "ax":5.19135, "ay":3.82289, "alpha":0.28224, "fx":[88.84973,87.21224,87.74802,89.40365], "fy":[64.29986,66.50138,65.78477,63.51929]}, - {"t":1.19202, "x":1.49327, "y":1.00024, "heading":-2.189, "vx":-1.37584, "vy":-1.01317, "omega":-0.08539, "ax":5.19238, "ay":3.82365, "alpha":0.29802, "fx":[88.9021,87.17123,87.72918,89.4808], "fy":[64.2659,66.59249,65.84823,63.45011]}, - {"t":1.23617, "x":1.43759, "y":0.95924, "heading":-2.19277, "vx":-1.14661, "vy":-0.84436, "omega":-0.07224, "ax":5.19318, "ay":3.82424, "alpha":0.31041, "fx":[88.94394,87.13944,87.71349,89.54097], "fy":[64.23815,66.66333,65.89923,63.39626]}, - {"t":1.28032, "x":1.39203, "y":0.92569, "heading":-2.19596, "vx":-0.91733, "vy":-0.67552, "omega":-0.05853, "ax":5.19382, "ay":3.82472, "alpha":0.32039, "fx":[88.97803,87.11406,87.70035,89.58924], "fy":[64.2152,66.72003,65.941,63.35312]}, - {"t":1.32447, "x":1.35659, "y":0.89959, "heading":-2.19854, "vx":-0.68803, "vy":-0.50666, "omega":-0.04439, "ax":5.19435, "ay":3.82511, "alpha":0.32861, "fx":[89.00618,87.09323,87.68937,89.62889], "fy":[64.19613,66.76654,65.97557,63.31766]}, - {"t":1.36862, "x":1.33128, "y":0.88095, "heading":-2.2005, "vx":-0.45871, "vy":-0.33779, "omega":-0.02988, "ax":5.19479, "ay":3.82543, "alpha":0.33549, "fx":[89.02958,87.07571,87.6803,89.66217], "fy":[64.18037,66.80556,66.00436,63.28785]}, - {"t":1.41277, "x":1.31609, "y":0.86977, "heading":-2.20182, "vx":-0.22936, "vy":-0.1689, "omega":-0.01507, "ax":5.19517, "ay":3.82571, "alpha":0.34133, "fx":[89.04909,87.06062,87.67297,89.69063], "fy":[64.16748,66.83895,66.02832,63.26224]}, - {"t":1.45692, "x":1.31103, "y":0.86604, "heading":-2.20249, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.8375, "ay":4.26441, "alpha":0.43459, "fx":[83.40227,80.53297,81.12588,84.07703], "fy":[71.28937,74.51367,73.8589,70.48332]}, - {"t":1.48765, "x":1.31331, "y":0.86805, "heading":-2.20249, "vx":0.14868, "vy":0.13106, "omega":0.01336, "ax":4.83719, "ay":4.26413, "alpha":0.42793, "fx":[83.38017,80.55431,81.13855,84.04375], "fy":[71.30339,74.47921,73.83316,70.5107]}, - {"t":1.51838, "x":1.32016, "y":0.8741, "heading":-2.20208, "vx":0.29734, "vy":0.26212, "omega":0.02651, "ax":4.83684, "ay":4.26382, "alpha":0.42052, "fx":[83.35486,80.57759,81.15335,84.00716], "fy":[71.31981,74.44134,73.80374,70.54062]}, - {"t":1.54912, "x":1.33159, "y":0.88417, "heading":-2.20126, "vx":0.446, "vy":0.39316, "omega":0.03943, "ax":4.83645, "ay":4.26348, "alpha":0.41223, "fx":[83.32595,80.60325,81.17048,83.96656], "fy":[71.33883,74.39932,73.77018,70.57366]}, - {"t":1.57985, "x":1.34758, "y":0.89826, "heading":-2.20005, "vx":0.59464, "vy":0.52419, "omega":0.0521, "ax":4.836, "ay":4.26309, "alpha":0.40289, "fx":[83.29293,80.63189,81.19018,83.92106], "fy":[71.36075,74.35222,73.73192,70.61055]}, - {"t":1.61059, "x":1.36814, "y":0.91639, "heading":-2.19845, "vx":0.74327, "vy":0.65521, "omega":0.06448, "ax":4.8355, "ay":4.26264, "alpha":0.39227, "fx":[83.25513,80.66425,81.21277,83.86956], "fy":[71.38593,74.29884,73.68823,70.6522]}, - {"t":1.64132, "x":1.39327, "y":0.93854, "heading":-2.19647, "vx":0.89188, "vy":0.78622, "omega":0.07654, "ax":4.83492, "ay":4.26213, "alpha":0.38012, "fx":[83.21171,80.70127,81.23864,83.81061], "fy":[71.41487,74.23767,73.63815,70.69979]}, - {"t":1.67205, "x":1.42296, "y":0.96471, "heading":-2.19411, "vx":1.04048, "vy":0.91721, "omega":0.08822, "ax":4.83424, "ay":4.26154, "alpha":0.36605, "fx":[83.16155,80.7442,81.26833,83.74235], "fy":[71.44818,74.16667,73.58047,70.75485]}, - {"t":1.70279, "x":1.45722, "y":0.99492, "heading":-2.1914, "vx":1.18905, "vy":1.04819, "omega":0.09947, "ax":4.83345, "ay":4.26084, "alpha":0.3496, "fx":[83.10311,80.79469,81.30256,83.66226], "fy":[71.48673,74.08316,73.51351,70.81942]}, - {"t":1.73352, "x":1.49605, "y":1.02914, "heading":-2.18835, "vx":1.33761, "vy":1.17914, "omega":0.11022, "ax":4.83251, "ay":4.26001, "alpha":0.33009, "fx":[83.03431,80.85499,81.34231,83.56691], "fy":[71.5317,73.98344,73.43501,70.89627]}, - {"t":1.76426, "x":1.53944, "y":1.06739, "heading":-2.18496, "vx":1.48613, "vy":1.31007, "omega":0.12036, "ax":4.83137, "ay":4.25901, "alpha":0.30658, "fx":[82.95216,80.92829,81.38894,83.45148], "fy":[71.58477,73.86226,73.34177,70.98929]}, - {"t":1.79499, "x":1.5874, "y":1.10967, "heading":-2.18126, "vx":1.63461, "vy":1.44096, "omega":0.12979, "ax":4.82996, "ay":4.25777, "alpha":0.27771, "fx":[82.8523,81.01918,81.44445,83.30895], "fy":[71.64841,73.71201,73.22914,71.10407]}, - {"t":1.82572, "x":1.63992, "y":1.15597, "heading":-2.17727, "vx":1.78306, "vy":1.57182, "omega":0.13832, "ax":4.82817, "ay":4.25619, "alpha":0.2414, "fx":[82.72805,81.13456,81.51184,83.12874], "fy":[71.72635,73.5211,73.09012,71.24899]}, - {"t":1.85646, "x":1.697, "y":1.20628, "heading":-2.17302, "vx":1.93145, "vy":1.70263, "omega":0.14574, "ax":4.82583, "ay":4.25413, "alpha":0.19439, "fx":[82.56868,81.28537,81.5958,82.89408], "fy":[71.82461,73.27102,72.91363,71.4372]}, - {"t":1.88719, "x":1.75864, "y":1.26062, "heading":-2.16854, "vx":2.07976, "vy":1.83338, "omega":0.15171, "ax":4.82264, "ay":4.25132, "alpha":0.1311, "fx":[82.3558,81.48997,81.70417,82.5767], "fy":[71.95338,72.93024,72.68106,71.69058]}, - {"t":1.91793, "x":1.82483, "y":1.31898, "heading":-2.16388, "vx":2.22798, "vy":1.96404, "omega":0.15574, "ax":4.81802, "ay":4.24727, "alpha":0.04135, "fx":[82.05507,81.78175,81.85096,82.12495], "fy":[72.13153,72.44038,72.35868,72.04848]}, - {"t":1.94866, "x":1.89558, "y":1.38135, "heading":-2.15909, "vx":2.37606, "vy":2.09457, "omega":0.15701, "ax":4.81078, "ay":4.2409, "alpha":-0.09577, "fx":[81.59437,82.22848,82.06397,81.43332], "fy":[72.3981,71.67985,71.87833,72.58937]}, - {"t":1.97939, "x":1.97088, "y":1.44772, "heading":-2.15426, "vx":2.52391, "vy":2.22491, "omega":0.15407, "ax":4.79783, "ay":4.22949, "alpha":-0.33105, "fx":[80.79229,82.9915,82.40672,80.2481], "fy":[72.84871,70.34697,71.07905,73.49525]}, - {"t":2.01013, "x":2.05072, "y":1.5181, "heading":-2.14953, "vx":2.67137, "vy":2.3549, "omega":0.1439, "ax":4.76829, "ay":4.20352, "alpha":-0.82778, "fx":[79.02897,84.5688,83.06156,77.7696], "fy":[73.79403,67.43528,69.47006,75.30334]}, - {"t":2.04086, "x":2.13507, "y":1.59246, "heading":-2.14511, "vx":2.81792, "vy":2.48409, "omega":0.11846, "ax":4.64293, "ay":4.09487, "alpha":-2.55799, "fx":[72.00735,89.48447,84.818,69.5897], "fy":[77.08043,56.47865,64.54519,80.50578]}, - {"t":2.07159, "x":2.22387, "y":1.67074, "heading":-2.14147, "vx":2.96061, "vy":2.60994, "omega":0.03984, "ax":0.50591, "ay":0.44471, "alpha":-1.27872, "fx":[4.01605,9.67363,13.15487,7.57687], "fy":[6.61874,2.95461,8.52299,12.16154]}, - {"t":2.10233, "x":2.3151, "y":1.75117, "heading":-2.14024, "vx":2.97616, "vy":2.62361, "omega":0.00054, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[-0.00007,-0.00007,-0.00007,-0.00007], "fy":[0.00007,0.00007,0.00007,0.00007]}, - {"t":2.13306, "x":2.40657, "y":1.8318, "heading":-2.14023, "vx":2.97616, "vy":2.62361, "omega":0.00054, "ax":-0.50606, "ay":-0.44482, "alpha":1.2796, "fx":[-4.01673,-9.68266,-13.15922,-7.57306], "fy":[-6.61422,-2.95452,-8.53117,-12.16545]}, - {"t":2.1638, "x":2.4978, "y":1.91222, "heading":-2.14021, "vx":2.96061, "vy":2.60994, "omega":0.03987, "ax":-4.64282, "ay":-4.09479, "alpha":2.56107, "fx":[-72.05372,-89.51798,-84.78278,-69.53736], "fy":[-77.03211,-56.43063,-64.59378,-80.54861]}, - {"t":2.19453, "x":2.5866, "y":1.9905, "heading":-2.13898, "vx":2.81792, "vy":2.48409, "omega":0.11858, "ax":-4.76828, "ay":-4.20351, "alpha":0.82895, "fx":[-79.06398,-84.59245,-83.03025,-77.74138], "fy":[-73.75548,-67.40689,-69.50821,-75.33141]}, - {"t":2.22526, "x":2.67095, "y":2.06486, "heading":-2.13534, "vx":2.67137, "vy":2.3549, "omega":0.14405, "ax":-4.79782, "ay":-4.22949, "alpha":0.33156, "fx":[-80.81779,-83.00797,-82.38239,-80.23028], "fy":[-72.82001,-70.32808,-71.10757,-73.51416]}, - {"t":2.256, "x":2.75079, "y":2.13524, "heading":-2.13091, "vx":2.52391, "vy":2.22491, "omega":0.15424, "ax":-4.81078, "ay":-4.24089, "alpha":0.09595, "fx":[-81.60532,-82.23559,-82.05315,-81.42603], "fy":[-72.38563,-71.67185,-71.89077,-72.59736]}, - {"t":2.28673, "x":2.82608, "y":2.20162, "heading":-2.12617, "vx":2.37606, "vy":2.09457, "omega":0.15719, "ax":-4.81802, "ay":-4.24727, "alpha":-0.04137, "fx":[-82.04859,-81.77792,-81.85748,-82.12872], "fy":[-72.13895,-72.4446,-72.35125,-72.04425]}, - {"t":2.31747, "x":2.89683, "y":2.26399, "heading":-2.12134, "vx":2.22798, "vy":1.96404, "omega":0.15592, "ax":-4.82264, "ay":-4.25132, "alpha":-0.13124, "fx":[-82.33037,-81.47432,-81.73009,-82.59182], "fy":[-71.98262,-72.94744,-72.65174,-71.67344]}, - {"t":2.3482, "x":2.96303, "y":2.32234, "heading":-2.11655, "vx":2.07976, "vy":1.83338, "omega":0.15189, "ax":-4.82583, "ay":-4.25413, "alpha":-0.19462, "fx":[-82.5237,-81.25752,-81.64212,-82.92055], "fy":[-71.87652,-73.3015,-72.8615,-71.40689]}, - {"t":2.37893, "x":3.02467, "y":2.37668, "heading":-2.11188, "vx":1.93145, "vy":1.70263, "omega":0.14591, "ax":-4.82817, "ay":-4.25619, "alpha":-0.24169, "fx":[-82.66345,-81.09447,-81.57884,-83.16637], "fy":[-71.80108,-73.56482,-73.01501,-71.2056]}, - {"t":2.40967, "x":3.08175, "y":2.427, "heading":-2.1074, "vx":1.78306, "vy":1.57182, "omega":0.13848, "ax":-4.82996, "ay":-4.25777, "alpha":-0.27804, "fx":[-82.76844,-80.96705,-81.53192,-83.35738], "fy":[-71.7456,-73.7687,-73.13138,-71.0479]}, - {"t":2.4404, "x":3.13427, "y":2.4733, "heading":-2.10314, "vx":1.63461, "vy":1.44096, "omega":0.12993, "ax":-4.83137, "ay":-4.25901, "alpha":-0.30695, "fx":[-82.84969,-80.86454,-81.4963,-83.51026], "fy":[-71.7037,-73.93144,-73.22206,-70.92082]}, - {"t":2.47114, "x":3.18223, "y":2.51557, "heading":-2.09915, "vx":1.48613, "vy":1.31007, "omega":0.1205, "ax":-4.83251, "ay":-4.26001, "alpha":-0.33048, "fx":[-82.9141,-80.78015,-81.46871,-83.63546], "fy":[-71.67138,-74.0645,-73.29433,-70.81612]}, - {"t":2.50187, "x":3.22562, "y":2.55382, "heading":-2.09544, "vx":1.3376, "vy":1.17914, "omega":0.11034, "ax":-4.83345, "ay":-4.26084, "alpha":-0.35001, "fx":[-82.96622,-80.7094,-81.44694,-83.73994], "fy":[-71.64595,-74.17539,-73.35308,-70.72831]}, - {"t":2.5326, "x":3.26445, "y":2.58805, "heading":-2.09205, "vx":1.18905, "vy":1.04819, "omega":0.09959, "ax":-4.83424, "ay":-4.26154, "alpha":-0.36648, "fx":[-83.00917,-80.64922,-81.42946,-83.82846], "fy":[-71.62556,-74.26924,-73.40166,-70.6536]}, - {"t":2.56334, "x":3.29871, "y":2.61825, "heading":-2.08899, "vx":1.04048, "vy":0.91721, "omega":0.08832, "ax":-4.83492, "ay":-4.26213, "alpha":-0.38055, "fx":[-83.04515,-80.59742,-81.41515,-83.90438], "fy":[-71.6089,-74.34969,-73.44249,-70.58928]}, - {"t":2.59407, "x":3.3284, "y":2.64443, "heading":-2.08628, "vx":0.89188, "vy":0.78622, "omega":0.07663, "ax":-4.8355, "ay":-4.26264, "alpha":-0.39272, "fx":[-83.07579,-80.5524,-81.40318,-83.97019], "fy":[-71.59498,-74.41938,-73.47736,-70.53337]}, - {"t":2.62481, "x":3.35353, "y":2.66658, "heading":-2.08392, "vx":0.74327, "vy":0.65521, "omega":0.06456, "ax":-4.836, "ay":-4.26308, "alpha":-0.40334, "fx":[-83.10228,-80.51297,-81.39293,-84.02773], "fy":[-71.58308,-74.48027,-73.50759,-70.48438]}, - {"t":2.65554, "x":3.37409, "y":2.6847, "heading":-2.08194, "vx":0.59464, "vy":0.52419, "omega":0.05216, "ax":-4.83644, "ay":-4.26347, "alpha":-0.41269, "fx":[-83.12556,-80.47823,-81.3839,-84.07839], "fy":[-71.57263,-74.53383,-73.53422,-70.44119]}, - {"t":2.68627, "x":3.39008, "y":2.6988, "heading":-2.08033, "vx":0.446, "vy":0.39316, "omega":0.03948, "ax":-4.83684, "ay":-4.26382, "alpha":-0.42099, "fx":[-83.14634,-80.44748,-81.37572,-84.12326], "fy":[-71.56319,-74.58124,-73.55805,-70.4029]}, - {"t":2.71701, "x":3.4015, "y":2.70887, "heading":-2.07912, "vx":0.29734, "vy":0.26212, "omega":0.02654, "ax":-4.83719, "ay":-4.26413, "alpha":-0.4284, "fx":[-83.16518,-80.42015,-81.36807,-84.1632], "fy":[-71.55441,-74.62338,-73.5797,-70.36884]}, - {"t":2.74774, "x":3.40836, "y":2.71491, "heading":-2.07831, "vx":0.14868, "vy":0.13106, "omega":0.01337, "ax":-4.8375, "ay":-4.2644, "alpha":-0.43506, "fx":[-83.18253,-80.39582,-81.36072,-84.1989], "fy":[-71.54601,-74.66098,-73.5997,-70.33844]}, - {"t":2.77848, "x":3.41064, "y":2.71692, "heading":-2.07789, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[ - {"name":"Funnel", "from":{"target":2, "targetTimestamp":2.1638, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] -} diff --git a/src/main/deploy/choreo/A_RIGHT_PATH4.traj b/src/main/deploy/choreo/A_RIGHT_PATH4.traj deleted file mode 100644 index c1f93e1b..00000000 --- a/src/main/deploy/choreo/A_RIGHT_PATH4.traj +++ /dev/null @@ -1,129 +0,0 @@ -{ - "name":"A_RIGHT_PATH4", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":3.692616224288941, "y":3.031563984680176, "heading":-2.0948682307415045, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.3110252618789673, "y":0.8660395019531251, "heading":-2.216612130911823, "intervals":37, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.174586296081543, "y":2.617419958114624, "heading":0.0, "intervals":36, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":2.819322109222412, "y":3.785844075012207, "heading":-3.1289351796122347, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"3.6926162242889404 m", "val":3.692616224288941}, "y":{"exp":"(8.0518 - 5.020236015319824) m", "val":3.031563984680176}, "heading":{"exp":"-2.0948682307415045 rad", "val":-2.0948682307415045}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"(8.0518 - 7.185760498046875) m", "val":0.8660395019531251}, "heading":{"exp":"-2.216612130911823 rad", "val":-2.216612130911823}, "intervals":37, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.174586296081543 m", "val":2.174586296081543}, "y":{"exp":"2.617419958114624 m", "val":2.617419958114624}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":36, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"2.819322109222412 m", "val":2.819322109222412}, "y":{"exp":"(8.0518 - 4.265955924987793) m", "val":3.785844075012207}, "heading":{"exp":"-3.1289351796122347 rad", "val":-3.1289351796122347}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.42726,2.20676,2.87874], - "samples":[ - {"t":0.0, "x":3.69262, "y":3.03156, "heading":-2.09487, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-4.77336, "ay":-4.34029, "alpha":-0.36517, "fx":[-82.01137,-79.60509,-80.3539,-82.80387], "fy":[-72.9455,-75.56262,-74.76071,-72.03947]}, - {"t":0.04325, "x":3.68815, "y":3.0275, "heading":-2.09487, "vx":-0.20645, "vy":-0.18772, "omega":-0.01579, "ax":-4.77303, "ay":-4.33999, "alpha":-0.36029, "fx":[-81.99495,-79.62059,-80.35948,-82.77638], "fy":[-72.95195,-75.53461,-74.74258,-72.05859]}, - {"t":0.0865, "x":3.67476, "y":3.01533, "heading":-2.09555, "vx":-0.41289, "vy":-0.37543, "omega":-0.03138, "ax":-4.77264, "ay":-4.33963, "alpha":-0.35461, "fx":[-81.97681,-79.63925,-80.3649,-82.74377], "fy":[-72.95832,-75.50128,-74.7226,-72.08147]}, - {"t":0.12975, "x":3.65244, "y":2.99503, "heading":-2.09691, "vx":-0.6193, "vy":-0.56312, "omega":-0.04671, "ax":-4.77217, "ay":-4.33921, "alpha":-0.34789, "fx":[-81.95612,-79.66174,-80.37047,-82.70483], "fy":[-72.96497,-75.4614,-74.69987,-72.10894]}, - {"t":0.173, "x":3.62119, "y":2.96662, "heading":-2.09893, "vx":-0.8257, "vy":-0.75079, "omega":-0.06176, "ax":-4.77161, "ay":-4.33871, "alpha":-0.33982, "fx":[-81.9317,-79.68899,-80.37666,-82.65783], "fy":[-72.97244,-75.41319,-74.67312,-72.14215]}, - {"t":0.21625, "x":3.58101, "y":2.93009, "heading":-2.1016, "vx":-1.03208, "vy":-0.93844, "omega":-0.07646, "ax":-4.77093, "ay":-4.33809, "alpha":-0.32994, "fx":[-81.90188,-79.72234,-80.3841,-82.60029], "fy":[-72.98148,-75.35412,-74.64053,-72.18278]}, - {"t":0.2595, "x":3.53191, "y":2.88544, "heading":-2.10491, "vx":-1.23842, "vy":-1.12606, "omega":-0.09073, "ax":-4.77007, "ay":-4.33732, "alpha":-0.31759, "fx":[-81.86414,-79.76384,-80.39377,-82.52847], "fy":[-72.99318,-75.28035,-74.59939,-72.23331]}, - {"t":0.30275, "x":3.47389, "y":2.83268, "heading":-2.10883, "vx":-1.44473, "vy":-1.31366, "omega":-0.10446, "ax":-4.76896, "ay":-4.33632, "alpha":-0.3017, "fx":[-81.81452,-79.81665,-80.40713,-82.43651], "fy":[-73.0093,-75.18582,-74.54544,-72.29765]}, - {"t":0.346, "x":3.40694, "y":2.77181, "heading":-2.11335, "vx":-1.65099, "vy":-1.5012, "omega":-0.11751, "ax":-4.76748, "ay":-4.33498, "alpha":-0.28048, "fx":[-81.7464,-79.88606,-80.4266,-82.31463], "fy":[-73.03267,-75.06042,-74.47165,-72.38226]}, - {"t":0.38925, "x":3.33108, "y":2.70283, "heading":-2.11843, "vx":-1.85718, "vy":-1.68869, "omega":-0.12964, "ax":-4.76538, "ay":-4.33309, "alpha":-0.25074, "fx":[-81.64782,-79.98159,-80.45644,-82.14522], "fy":[-73.06841,-74.88582,-74.3654,-72.4987]}, - {"t":0.4325, "x":3.2463, "y":2.62574, "heading":-2.12404, "vx":-2.06329, "vy":-1.8761, "omega":-0.14049, "ax":-4.7622, "ay":-4.33022, "alpha":-0.20608, "fx":[-81.49469,-80.1221,-80.50494,-81.89306], "fy":[-73.12662,-74.62514,-74.20164,-72.66984]}, - {"t":0.47575, "x":3.15261, "y":2.54055, "heading":-2.13011, "vx":-2.26926, "vy":-2.06338, "omega":-0.1494, "ax":-4.75682, "ay":-4.32536, "alpha":-0.13158, "fx":[-81.23019,-80.35127,-80.59075,-81.47614], "fy":[-73.23063,-74.19154,-73.92248,-72.94801]}, - {"t":0.519, "x":3.05001, "y":2.44726, "heading":-2.13658, "vx":-2.47499, "vy":-2.25046, "omega":-0.15509, "ax":-4.74572, "ay":-4.31535, "alpha":0.0174, "fx":[-80.68055,-80.79726,-80.76623,-80.64964], "fy":[-73.44898,-73.32106,-73.35701,-73.48469]}, - {"t":0.56226, "x":2.93853, "y":2.34589, "heading":-2.14328, "vx":-2.68024, "vy":-2.4371, "omega":-0.15434, "ax":-4.71008, "ay":-4.28318, "alpha":0.46025, "fx":[-78.9421,-82.05793,-81.25126,-78.21717], "fy":[-74.10427,-70.66649,-71.68837,-74.96378]}, - {"t":0.60551, "x":2.8182, "y":2.23648, "heading":-2.14996, "vx":-2.88396, "vy":-2.62235, "omega":-0.13443, "ax":-1.2157, "ay":-1.10429, "alpha":3.10111, "fx":[-9.46753,-23.99027,-31.3387,-17.91853], "fy":[-17.28695,-7.3062,-20.53232,-30.0091]}, - {"t":0.64876, "x":2.69233, "y":2.12203, "heading":-2.15577, "vx":-2.93654, "vy":-2.67011, "omega":-0.00031, "ax":-0.00062, "ay":-0.00028, "alpha":0.00081, "fx":[-0.0076,-0.0111,-0.01341,-0.00992], "fy":[-0.00422,-0.00191,-0.0054,-0.00772]}, - {"t":0.69201, "x":2.56532, "y":2.00654, "heading":-2.15579, "vx":-2.93656, "vy":-2.67012, "omega":-0.00027, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[-0.00001,-0.00001,-0.00001,-0.00001], "fy":[0.00001,0.00001,0.00001,0.00001]}, - {"t":0.73526, "x":2.43832, "y":1.89106, "heading":-2.1558, "vx":-2.93656, "vy":-2.67012, "omega":-0.00027, "ax":0.00061, "ay":0.00029, "alpha":-0.00081, "fx":[0.00755,0.01105,0.01336,0.00987], "fy":[0.00428,0.00197,0.00546,0.00777]}, - {"t":0.77851, "x":2.31131, "y":1.77558, "heading":-2.15581, "vx":-2.93654, "vy":-2.67011, "omega":-0.00031, "ax":1.21564, "ay":1.10425, "alpha":-3.09988, "fx":[9.45427,23.9232,31.35144,17.98155], "fy":[17.35637,7.29761,20.46739,30.01052]}, - {"t":0.82176, "x":2.18544, "y":1.66113, "heading":-2.15582, "vx":-2.88396, "vy":-2.62235, "omega":-0.13438, "ax":4.71011, "ay":4.2832, "alpha":-0.4563, "fx":[78.92834,82.02797,81.26521,78.24912], "fy":[74.12022,70.70106,71.67191,74.9311]}, - {"t":0.86501, "x":2.06511, "y":1.55171, "heading":-2.16164, "vx":-2.68025, "vy":-2.4371, "omega":-0.15411, "ax":4.74573, "ay":4.31535, "alpha":-0.01614, "fx":[80.68202,80.79097,80.76491,80.65607], "fy":[73.44753,73.32808,73.35843,73.47768]}, - {"t":0.90826, "x":1.95363, "y":1.45034, "heading":-2.1683, "vx":-2.47499, "vy":-2.25046, "omega":-0.15481, "ax":4.75682, "ay":4.32536, "alpha":0.13197, "fx":[81.25225,80.36251,80.56831,81.4654], "fy":[73.20607,74.17961,73.94707,72.95981]}, - {"t":0.95151, "x":1.85104, "y":1.35706, "heading":-2.175, "vx":-2.26926, "vy":-2.06338, "omega":-0.1491, "ax":4.7622, "ay":4.33022, "alpha":0.20605, "fx":[81.5384,80.14932,80.45992,81.86727], "fy":[73.0777,74.59625,74.25068,72.69857]}, - {"t":0.99476, "x":1.75734, "y":1.27187, "heading":-2.18145, "vx":-2.06329, "vy":-1.8761, "omega":-0.14019, "ax":4.76538, "ay":4.33309, "alpha":0.25046, "fx":[81.7128,80.0237,80.38905,82.10564], "fy":[72.9955,74.8412,74.43851,72.54312]}, - {"t":1.03801, "x":1.67256, "y":1.19478, "heading":-2.18751, "vx":-1.85718, "vy":-1.68869, "omega":-0.12936, "ax":4.76748, "ay":4.33498, "alpha":0.28003, "fx":[81.83158,79.94201,80.33786,82.26239], "fy":[72.93696,75.00125,74.56765,72.44118]}, - {"t":1.08126, "x":1.5967, "y":1.12579, "heading":-2.1931, "vx":-1.65099, "vy":-1.5012, "omega":-0.11725, "ax":4.76897, "ay":4.33632, "alpha":0.30113, "fx":[81.91843,79.88529,80.29854,82.37273], "fy":[72.89242,75.11332,74.6627,72.36984]}, - {"t":1.12451, "x":1.52975, "y":1.06492, "heading":-2.19817, "vx":-1.44473, "vy":-1.31366, "omega":-0.10423, "ax":4.77007, "ay":4.33732, "alpha":0.31695, "fx":[81.98506,79.84396,80.2671,82.45429], "fy":[72.85708,75.1958,74.73597,72.31749]}, - {"t":1.16776, "x":1.47173, "y":1.01216, "heading":-2.20268, "vx":-1.23842, "vy":-1.12607, "omega":-0.09052, "ax":4.77093, "ay":4.3381, "alpha":0.32923, "fx":[82.03791,79.81267,80.24134,82.51691], "fy":[72.82827,75.25888,74.79429,72.2776]}, - {"t":1.21101, "x":1.42263, "y":0.96752, "heading":-2.2066, "vx":-1.03208, "vy":-0.93844, "omega":-0.07628, "ax":4.77162, "ay":4.33871, "alpha":0.33906, "fx":[82.08082,79.78819,80.21992,82.56647], "fy":[72.8044,75.30866,74.84177,72.24622]}, - {"t":1.25426, "x":1.38245, "y":0.93099, "heading":-2.2099, "vx":-0.8257, "vy":-0.75079, "omega":-0.06161, "ax":4.77218, "ay":4.33922, "alpha":0.34709, "fx":[82.11621,79.76843,80.202,82.60675], "fy":[72.78449,75.34903,74.88101,72.22081]}, - {"t":1.29751, "x":1.3512, "y":0.90257, "heading":-2.21256, "vx":-0.6193, "vy":-0.56312, "omega":-0.0466, "ax":4.77264, "ay":4.33964, "alpha":0.35378, "fx":[82.1457,79.75202,80.187,82.64027], "fy":[72.76786,75.38256,74.91375,72.19966]}, - {"t":1.34076, "x":1.32888, "y":0.88228, "heading":-2.21458, "vx":-0.41289, "vy":-0.37543, "omega":-0.0313, "ax":4.77303, "ay":4.33999, "alpha":0.35943, "fx":[82.17038,79.73797,80.17455,82.66877], "fy":[72.75406,75.41107,74.94119,72.18158]}, - {"t":1.38401, "x":1.31549, "y":0.8701, "heading":-2.21593, "vx":-0.20645, "vy":-0.18772, "omega":-0.01576, "ax":4.77337, "ay":4.34029, "alpha":0.36428, "fx":[82.19104,79.7256,80.16436,82.6935], "fy":[72.74277,75.43584,74.96417,72.16572]}, - {"t":1.42726, "x":1.31103, "y":0.86604, "heading":-2.21661, "vx":0.0, "vy":0.0, "omega":0.0, "ax":2.92009, "ay":5.66075, "alpha":-3.33895, "fx":[29.87871,64.33176,64.81516,39.65414], "fy":[105.52346,88.80521,88.52067,102.30195]}, - {"t":1.45414, "x":1.31208, "y":0.86808, "heading":-2.21661, "vx":0.07849, "vy":0.15216, "omega":-0.08975, "ax":2.92076, "ay":5.6625, "alpha":-3.28889, "fx":[30.20895,64.09729,64.63764,39.78129], "fy":[105.42035,88.96343,88.64131,102.24494]}, - {"t":1.48102, "x":1.31524, "y":0.87422, "heading":-2.21902, "vx":0.157, "vy":0.30436, "omega":-0.17815, "ax":2.92152, "ay":5.66438, "alpha":-3.23333, "fx":[30.54705,63.80063,64.4685,39.96044], "fy":[105.31306,89.16413,88.75433,102.16666]}, - {"t":1.5079, "x":1.32052, "y":0.88445, "heading":-2.22381, "vx":0.23553, "vy":0.45661, "omega":-0.26506, "ax":2.92236, "ay":5.66642, "alpha":-3.17158, "fx":[30.89943,63.4405,64.30267,40.19136], "fy":[105.1995,89.40716,88.86333,102.06674]}, - {"t":1.53478, "x":1.32791, "y":0.89877, "heading":-2.23094, "vx":0.31408, "vy":0.60892, "omega":-0.35031, "ax":2.92329, "ay":5.66863, "alpha":-3.10282, "fx":[31.27417,63.0151,64.13382,40.474], "fy":[105.07696,89.6925,88.9727,101.94462]}, - {"t":1.56166, "x":1.3374, "y":0.91718, "heading":-2.24035, "vx":0.39265, "vy":0.76129, "omega":-0.43371, "ax":2.9243, "ay":5.67102, "alpha":-3.02599, "fx":[31.68118,62.52214,63.95412,40.80843], "fy":[104.94198,90.02019,89.0878,101.79956]}, - {"t":1.58854, "x":1.34902, "y":0.93969, "heading":-2.25201, "vx":0.47125, "vy":0.91372, "omega":-0.51505, "ax":2.92539, "ay":5.67362, "alpha":-2.9398, "fx":[32.13262,61.95886,63.75377,41.19492], "fy":[104.79017,90.39028,89.21524,101.6306]}, - {"t":1.61542, "x":1.36274, "y":0.9663, "heading":-2.26586, "vx":0.54989, "vy":1.06623, "omega":-0.59407, "ax":2.92656, "ay":5.67644, "alpha":-2.84262, "fx":[32.64333,61.32214,63.52045,41.63397], "fy":[104.61597,90.80272,89.36318,101.43647]}, - {"t":1.6423, "x":1.37858, "y":0.99701, "heading":-2.28182, "vx":0.62855, "vy":1.2188, "omega":-0.67047, "ax":2.92781, "ay":5.6795, "alpha":-2.73239, "fx":[33.2316,60.60849,63.23848,42.12644], "fy":[104.41219,91.25734,89.54186,101.21556]}, - {"t":1.66918, "x":1.39653, "y":1.03183, "heading":-2.29985, "vx":0.70725, "vy":1.37146, "omega":-0.74392, "ax":2.92914, "ay":5.68283, "alpha":-2.60639, "fx":[33.92019,59.8141,62.8875,42.67369], "fy":[104.16943,91.75368,89.76422,100.96576]}, - {"t":1.69606, "x":1.4166, "y":1.07074, "heading":-2.31984, "vx":0.78598, "vy":1.52421, "omega":-0.81398, "ax":2.93055, "ay":5.68642, "alpha":-2.46104, "fx":[34.73795,58.93487,62.44057,43.27782], "fy":[103.87514,92.29098,90.04694,100.68426]}, - {"t":1.72293, "x":1.43878, "y":1.11377, "heading":-2.34172, "vx":0.86475, "vy":1.67706, "omega":-0.88013, "ax":2.93203, "ay":5.69027, "alpha":-2.29143, "fx":[35.72224,57.96633,61.86119,43.94217], "fy":[103.51201,92.86809,90.41183,100.3672]}, - {"t":1.74981, "x":1.46309, "y":1.1609, "heading":-2.36538, "vx":0.94356, "vy":1.83001, "omega":-0.94172, "ax":2.93357, "ay":5.69433, "alpha":-2.09063, "fx":[36.92279,56.90354,61.0983,44.67201], "fy":[103.05551,93.48342,90.88801,100.00906]}, - {"t":1.77669, "x":1.48951, "y":1.21215, "heading":-2.39069, "vx":1.02241, "vy":1.98307, "omega":-0.99791, "ax":2.93513, "ay":5.69853, "alpha":-1.84854, "fx":[38.40789,55.74073,60.07801,45.47599], "fy":[102.46943,94.135,91.51532,99.6016]}, - {"t":1.80357, "x":1.51805, "y":1.26751, "heading":-2.41751, "vx":1.10131, "vy":2.13624, "omega":-1.0476, "ax":2.9366, "ay":5.70262, "alpha":-1.54987, "fx":[40.27481,54.47066,58.68866,46.36867], "fy":[101.69795,94.82058,92.34961,99.13177]}, - {"t":1.83045, "x":1.54871, "y":1.32699, "heading":-2.44567, "vx":1.18024, "vy":2.28952, "omega":-1.08926, "ax":2.93773, "ay":5.70611, "alpha":-1.17048, "fx":[42.66782,53.08323,56.75272,47.37576], "fy":[100.65046,95.53789,93.47133,98.57754]}, - {"t":1.85733, "x":1.5815, "y":1.39059, "heading":-2.47495, "vx":1.2592, "vy":2.4429, "omega":-1.12072, "ax":2.93787, "ay":5.70782, "alpha":-0.67009, "fx":[45.81101,51.56289,53.96968,48.54557], "fy":[99.17038,96.28529,94.99917,97.8985]}, - {"t":1.88421, "x":1.61641, "y":1.45832, "heading":-2.50507, "vx":1.33817, "vy":2.59632, "omega":-1.13873, "ax":2.93539, "ay":5.70483, "alpha":0.0228, "fx":[50.07035,49.88337,49.78987,49.97722], "fy":[96.9657,97.06281,97.10922,97.01215]}, - {"t":1.91109, "x":1.65343, "y":1.53016, "heading":-2.53568, "vx":1.41707, "vy":2.74966, "omega":-1.13812, "ax":2.92596, "ay":5.6891, "alpha":1.04599, "fx":[56.07385,47.99686,43.10575,51.90259], "fy":[93.43849,97.87431,100.0447,95.72212]}, - {"t":1.93797, "x":1.69258, "y":1.60613, "heading":-2.56627, "vx":1.49572, "vy":2.90258, "omega":-1.11, "ax":2.89755, "ay":5.6345, "alpha":2.69283, "fx":[64.92903,45.81095,31.4142,54.99167], "fy":[87.21837,98.73111,103.98317,93.432]}, - {"t":1.96485, "x":1.73383, "y":1.68618, "heading":-2.59611, "vx":1.5736, "vy":3.05403, "omega":-1.03762, "ax":2.82429, "ay":5.43028, "alpha":5.66301, "fx":[78.35624,43.14565,8.57011,62.0892], "fy":[74.82361,99.6525,107.74498,87.24907]}, - {"t":1.99173, "x":1.77715, "y":1.77023, "heading":-2.624, "vx":1.64952, "vy":3.19999, "omega":-0.88541, "ax":2.84221, "ay":4.41824, "alpha":11.80305, "fx":[94.07034,40.23429,-29.33967,88.41565], "fy":[52.37712,100.37834,103.09692,44.75962]}, - {"t":2.01861, "x":1.82251, "y":1.85784, "heading":-2.6478, "vx":1.72591, "vy":3.31875, "omega":-0.56815, "ax":2.65628, "ay":4.20466, "alpha":12.33669, "fx":[93.37801,40.04528,-30.80219,78.10945], "fy":[49.38559,98.78196,100.24818,37.6642]}, - {"t":2.04548, "x":1.86986, "y":1.94857, "heading":-2.66307, "vx":1.79731, "vy":3.43177, "omega":-0.23655, "ax":1.25521, "ay":3.20772, "alpha":8.58399, "fx":[58.30418,27.27734,-15.956,15.77745], "fy":[43.53044,75.80693,69.27059,29.64139]}, - {"t":2.07236, "x":1.91863, "y":2.04197, "heading":-2.66943, "vx":1.83105, "vy":3.51799, "omega":-0.00582, "ax":-0.26015, "ay":0.15904, "alpha":0.05173, "fx":[-4.24463,-4.36621,-4.60535,-4.48384], "fy":[2.64703,2.8862,2.76346,2.52429]}, - {"t":2.09924, "x":1.96775, "y":2.13659, "heading":-2.66959, "vx":1.82406, "vy":3.52226, "omega":-0.00443, "ax":-0.11455, "ay":0.05933, "alpha":0.00015, "fx":[-1.94792,-1.94828,-1.94897,-1.94862], "fy":[1.00904,1.00974,1.00938,1.00868]}, - {"t":2.12612, "x":2.01674, "y":2.23128, "heading":-2.6697, "vx":1.82098, "vy":3.52386, "omega":-0.00442, "ax":-0.03251, "ay":0.0168, "alpha":0.0, "fx":[-0.55296,-0.55297,-0.55299,-0.55298], "fy":[0.28567,0.28569,0.28568,0.28567]}, - {"t":2.153, "x":2.06567, "y":2.32601, "heading":-2.66982, "vx":1.82011, "vy":3.52431, "omega":-0.00442, "ax":0.02864, "ay":-0.0148, "alpha":0.0, "fx":[0.48718,0.48718,0.48719,0.48718], "fy":[-0.25168,-0.25168,-0.25168,-0.25167]}, - {"t":2.17988, "x":2.11461, "y":2.42073, "heading":-2.66994, "vx":1.82088, "vy":3.52391, "omega":-0.00442, "ax":0.10819, "ay":-0.05604, "alpha":-0.00016, "fx":[1.83975,1.84013,1.84088,1.8405], "fy":[-0.95307,-0.95381,-0.95343,-0.95269]}, - {"t":2.20676, "x":2.16359, "y":2.51543, "heading":-2.67006, "vx":1.82379, "vy":3.5224, "omega":-0.00443, "ax":0.24644, "ay":-0.15396, "alpha":-0.05644, "fx":[3.99513,4.12767,4.38867,4.2562], "fy":[-2.5551,-2.81611,-2.68242,-2.42141]}, - {"t":2.23364, "x":2.2127, "y":2.61006, "heading":-2.67018, "vx":1.83041, "vy":3.51827, "omega":-0.00595, "ax":-1.33066, "ay":-3.27673, "alpha":-8.8129, "fx":[-60.69442,-28.64778,16.04776,-17.24202], "fy":[-43.8798,-77.20084,-71.35757,-30.50691]}, - {"t":2.26052, "x":2.26142, "y":2.70344, "heading":-2.67034, "vx":1.79464, "vy":3.43019, "omega":-0.24283, "ax":-2.64862, "ay":-4.20972, "alpha":-12.25578, "fx":[-94.04495,-41.08154,30.38917,-75.47202], "fy":[-48.10638,-98.39216,-100.48306,-39.44268]}, - {"t":2.2874, "x":2.3087, "y":2.79412, "heading":-2.67687, "vx":1.72345, "vy":3.31704, "omega":-0.57225, "ax":-2.84236, "ay":-4.38926, "alpha":-11.74826, "fx":[-95.88295,-42.45233,29.44199,-84.49732], "fy":[-48.91165,-99.48091,-103.167,-47.08075]}, - {"t":2.31428, "x":2.354, "y":2.88169, "heading":-2.69225, "vx":1.64705, "vy":3.19906, "omega":-0.88804, "ax":-2.80853, "ay":-5.41005, "alpha":-5.89864, "fx":[-81.16057,-45.60659,-6.49395,-57.82793], "fy":[-71.70707,-98.56709,-107.94538,-89.87376]}, - {"t":2.34116, "x":2.39726, "y":2.96573, "heading":-2.71612, "vx":1.57156, "vy":3.05364, "omega":-1.04659, "ax":-2.89304, "ay":-5.62754, "alpha":-2.87526, "fx":[-66.82403,-47.9273,-29.90942,-52.17808], "fy":[-85.73389,-97.72942,-104.45159,-94.97657]}, - {"t":2.36803, "x":2.43845, "y":3.04577, "heading":-2.74425, "vx":1.4938, "vy":2.90238, "omega":-1.12387, "ax":-2.92485, "ay":-5.68746, "alpha":-1.14766, "fx":[-57.03764,-49.25193,-42.22504,-50.48874], "fy":[-92.83321,-97.25116,-100.42767,-96.45651]}, - {"t":2.39491, "x":2.47755, "y":3.12173, "heading":-2.77446, "vx":1.41518, "vy":2.7495, "omega":-1.15472, "ax":-2.93512, "ay":-5.70469, "alpha":-0.06295, "fx":[-50.3329,-49.90401,-49.51752,-49.94765], "fy":[-96.82523,-97.05022,-97.24435,-97.02084]}, - {"t":2.42179, "x":2.51453, "y":3.19358, "heading":-2.8055, "vx":1.33628, "vy":2.59616, "omega":-1.15641, "ax":-2.93765, "ay":-5.70774, "alpha":0.67113, "fx":[-45.58308,-50.09942,-54.29457,-49.89727], "fy":[-99.28238,-97.04941,-94.80094,-97.21544]}, - {"t":2.44867, "x":2.54939, "y":3.2613, "heading":-2.83658, "vx":1.25732, "vy":2.44274, "omega":-1.13837, "ax":-2.93727, "ay":-5.70568, "alpha":1.19714, "fx":[-42.10956,-49.97966,-57.66296,-50.09663], "fy":[-100.90084,-97.18937,-92.89288,-97.22481]}, - {"t":2.47555, "x":2.58212, "y":3.3249, "heading":-2.86718, "vx":1.17837, "vy":2.28938, "omega":-1.1062, "ax":-2.93577, "ay":-5.70182, "alpha":1.59116, "fx":[-39.50373,-49.64093,-60.1682,-50.43338], "fy":[-102.02189,-97.42572,-91.36764,-97.13027]}, - {"t":2.50243, "x":2.61273, "y":3.38437, "heading":-2.89691, "vx":1.09946, "vy":2.13612, "omega":-1.06343, "ax":-2.93382, "ay":-5.69748, "alpha":1.89703, "fx":[-37.50987,-49.15137,-62.10605,-50.84671], "fy":[-102.82835,-97.7253,-90.12235,-96.97421]}, - {"t":2.52931, "x":2.64123, "y":3.43973, "heading":-2.9255, "vx":1.0206, "vy":1.98298, "omega":-1.01244, "ax":-2.93173, "ay":-5.69319, "alpha":2.14158, "fx":[-35.96081,-48.56102,-63.64974,-51.30012], "fy":[-103.42558,-98.06322,-89.0877,-96.78146]}, - {"t":2.55619, "x":2.6676, "y":3.49098, "heading":-2.95271, "vx":0.9418, "vy":1.82995, "omega":-0.95487, "ax":-2.92962, "ay":-5.68914, "alpha":2.34201, "fx":[-34.74268,-47.90775,-64.90736,-51.7701], "fy":[-103.8781,-98.42072,-88.21585,-96.56793]}, - {"t":2.58307, "x":2.69186, "y":3.53811, "heading":-2.97838, "vx":0.86305, "vy":1.67703, "omega":-0.89192, "ax":-2.92754, "ay":-5.6854, "alpha":2.50976, "fx":[-33.77509,-47.22087,-65.95004,-52.24065], "fy":[-104.22743,-98.78364,-87.4728,-96.34449]}, - {"t":2.60995, "x":2.714, "y":3.58113, "heading":-3.00235, "vx":0.78436, "vy":1.52421, "omega":-0.82446, "ax":-2.92553, "ay":-5.68198, "alpha":2.65266, "fx":[-32.99941,-46.52347,-66.82675,-52.70041], "fy":[-104.50146,-99.1414,-86.83356,-96.11904]}, - {"t":2.63683, "x":2.73402, "y":3.62005, "heading":-3.02451, "vx":0.70573, "vy":1.37148, "omega":-0.75316, "ax":-2.92361, "ay":-5.67885, "alpha":2.77619, "fx":[-32.37172,-45.8339,-67.57252,-53.14105], "fy":[-104.71962,-99.48607,-86.27926,-95.8975]}, - {"t":2.66371, "x":2.75194, "y":3.65486, "heading":-3.04476, "vx":0.62714, "vy":1.21884, "omega":-0.67854, "ax":-2.92178, "ay":-5.67598, "alpha":2.88424, "fx":[-31.85836,-45.16687,-68.21326,-53.55633], "fy":[-104.89589,-99.81187,-85.79521,-95.68454]}, - {"t":2.69059, "x":2.76774, "y":3.68557, "heading":-3.06299, "vx":0.54861, "vy":1.06627, "omega":-0.60101, "ax":-2.92006, "ay":-5.67336, "alpha":2.97964, "fx":[-31.43299,-44.53424,-68.76874,-53.94144], "fy":[-105.0406,-100.11458,-85.3697,-95.48387]}, - {"t":2.71746, "x":2.78143, "y":3.71218, "heading":-3.07915, "vx":0.47012, "vy":0.91378, "omega":-0.52092, "ax":-2.91844, "ay":-5.67094, "alpha":3.06448, "fx":[-31.07465,-43.94556,-69.25436,-54.29261], "fy":[-105.16156,-100.39122,-84.99323,-95.29857]}, - {"t":2.74434, "x":2.79301, "y":3.7347, "heading":-3.09315, "vx":0.39167, "vy":0.76135, "omega":-0.43855, "ax":-2.91693, "ay":-5.66873, "alpha":3.14031, "fx":[-30.76648,-43.40859,-69.68237,-54.60683], "fy":[-105.26482,-100.6397,-84.65794,-95.13118]}, - {"t":2.77122, "x":2.80249, "y":3.75311, "heading":-3.10494, "vx":0.31327, "vy":0.60898, "omega":-0.35414, "ax":-2.91552, "ay":-5.66669, "alpha":3.2083, "fx":[-30.49474,-42.92963,-70.06268,-54.88166], "fy":[-105.35511,-100.85859,-84.35729,-94.98386]}, - {"t":2.7981, "x":2.80985, "y":3.76743, "heading":-3.11446, "vx":0.2349, "vy":0.45666, "omega":-0.26791, "ax":-2.91422, "ay":-5.66481, "alpha":3.26936, "fx":[-30.24814,-42.51388,-70.40332,-55.11508], "fy":[-105.43619,-101.04691,-84.0858,-94.85844]}, - {"t":2.82498, "x":2.81511, "y":3.77766, "heading":-3.12166, "vx":0.15657, "vy":0.3044, "omega":-0.18003, "ax":-2.91303, "ay":-5.66309, "alpha":3.32422, "fx":[-30.01741,-42.16567,-70.71085,-55.30538], "fy":[-105.51108,-101.20395,-83.83891,-94.75648]}, - {"t":2.85186, "x":2.81827, "y":3.7838, "heading":-3.1265, "vx":0.07827, "vy":0.15218, "omega":-0.09068, "ax":-2.91194, "ay":-5.66152, "alpha":3.37343, "fx":[-29.79488,-41.88868,-70.99059,-55.45109], "fy":[-105.58219,-101.32917,-83.61282,-94.67932]}, - {"t":2.87874, "x":2.81932, "y":3.78584, "heading":-3.12894, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[ - {"name":"Funnel", "from":{"target":2, "targetTimestamp":2.20676, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] -} diff --git a/src/main/deploy/choreo/B_LEFT_PATH1.traj b/src/main/deploy/choreo/B_LEFT_PATH1.traj deleted file mode 100644 index 85cc38e0..00000000 --- a/src/main/deploy/choreo/B_LEFT_PATH1.traj +++ /dev/null @@ -1,112 +0,0 @@ -{ - "name":"B_LEFT_PATH1", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":7.163801670074463, "y":7.307990074157715, "heading":1.5707963267948966, "intervals":50, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.6384241580963135, "y":5.683813095092773, "heading":0.0, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":2.650822401046753, "y":4.146424770355225, "heading":3.141592653589793, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"7.163801670074463 m", "val":7.163801670074463}, "y":{"exp":"7.307990074157715 m", "val":7.307990074157715}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":50, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.6384241580963135 m", "val":2.6384241580963135}, "y":{"exp":"5.683813095092773 m", "val":5.683813095092773}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"2.650822401046753 m", "val":2.650822401046753}, "y":{"exp":"4.146424770355225 m", "val":4.146424770355225}, "heading":{"exp":"3.141592653589793 rad", "val":3.141592653589793}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.61256,2.35601], - "samples":[ - {"t":0.0, "x":7.1638, "y":7.30799, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.31433, "ay":-0.66516, "alpha":3.79591, "fx":[-106.77168,-103.94195,-109.33802,-109.56787], "fy":[-25.40488,-35.10787,8.94297,6.31308]}, - {"t":0.03506, "x":7.15992, "y":7.30758, "heading":1.5708, "vx":-0.22135, "vy":-0.02332, "omega":0.13307, "ax":-6.31805, "ay":-0.66589, "alpha":3.71408, "fx":[-106.81858,-104.10848,-109.36818,-109.57783], "fy":[-25.17548,-34.5823,8.44681,6.00465]}, - {"t":0.07011, "x":7.14828, "y":7.30635, "heading":1.57546, "vx":-0.44284, "vy":-0.04666, "omega":0.26327, "ax":-6.3221, "ay":-0.66678, "alpha":3.62279, "fx":[-106.85199,-104.31176,-109.3927,-109.59209], "fy":[-24.9969,-33.93075,7.98356,5.57705]}, - {"t":0.10517, "x":7.12887, "y":7.30431, "heading":1.58469, "vx":-0.66446, "vy":-0.07004, "omega":0.39027, "ax":-6.32654, "ay":-0.66782, "alpha":3.51952, "fx":[-106.87556,-104.55273,-109.41341,-109.60916], "fy":[-24.85341,-33.14133,7.52986,5.0273]}, - {"t":0.14022, "x":7.10169, "y":7.30144, "heading":1.59837, "vx":-0.88624, "vy":-0.09345, "omega":0.51365, "ax":-6.33147, "ay":-0.66898, "alpha":3.40104, "fx":[-106.89389,-104.83265,-109.43211,-109.6271], "fy":[-24.72441,-32.1979,7.05523,4.3505]}, - {"t":0.17528, "x":7.06673, "y":7.29776, "heading":1.61638, "vx":-1.1082, "vy":-0.1169, "omega":0.63287, "ax":-6.33696, "ay":-0.67024, "alpha":3.26317, "fx":[-106.91286,-105.15273,-109.45049,-109.64337], "fy":[-24.58256,-31.07985,6.52059,3.53933]}, - {"t":0.21033, "x":7.02399, "y":7.29325, "heading":1.63856, "vx":-1.33035, "vy":-0.14039, "omega":0.74727, "ax":-6.34312, "ay":-0.67158, "alpha":3.10048, "fx":[-106.94024,-105.51371,-109.46988,-109.65467], "fy":[-24.3909,-29.76173,5.87587,2.58307]}, - {"t":0.24539, "x":6.97346, "y":7.28791, "heading":1.66476, "vx":-1.55271, "vy":-0.16394, "omega":0.85596, "ax":-6.35003, "ay":-0.67298, "alpha":2.90572, "fx":[-106.9864,-105.91525,-109.49064,-109.65656], "fy":[-24.09817,-28.21259,5.05623,1.46607]}, - {"t":0.28045, "x":6.91512, "y":7.28175, "heading":1.69477, "vx":-1.77531, "vy":-0.18753, "omega":0.95782, "ax":-6.35776, "ay":-0.6744, "alpha":2.6689, "fx":[-107.06547,-106.35517,-109.51101,-109.64291], "fy":[-23.63074,-26.3949,3.97543,0.1647]}, - {"t":0.3155, "x":6.84898, "y":7.27476, "heading":1.72834, "vx":-1.99819, "vy":-0.21117, "omega":1.05138, "ax":-6.36628, "ay":-0.67586, "alpha":2.37558, "fx":[-107.19667,-106.82848,-109.52457,-109.60471], "fy":[-22.87817,-24.2625,2.51457,-1.35842]}, - {"t":0.35056, "x":6.77502, "y":7.26695, "heading":1.7652, "vx":-2.22136, "vy":-0.23486, "omega":1.13466, "ax":-6.37539, "ay":-0.67736, "alpha":2.00341, "fx":[-107.40603,-107.326,-109.51481,-109.5276], "fy":[-21.66545,-21.75676,0.5013,-3.16619]}, - {"t":0.38561, "x":6.69323, "y":7.2583, "heading":1.80498, "vx":-2.44486, "vy":-0.25861, "omega":1.20489, "ax":-6.3844, "ay":-0.67897, "alpha":1.5152, "fx":[-107.72683,-107.83237,-109.44229,-109.38592], "fy":[-19.69481,-18.79894,-2.32966,-5.37322]}, - {"t":0.42067, "x":6.6036, "y":7.24881, "heading":1.84721, "vx":-2.66867, "vy":-0.28241, "omega":1.258, "ax":-6.39124, "ay":-0.68069, "alpha":0.84273, "fx":[-108.19188,-108.32235,-109.21236,-109.1264], "fy":[-16.4114,-15.27442,-6.41667,-8.21065]}, - {"t":0.45572, "x":6.50612, "y":7.2385, "heading":1.89131, "vx":-2.89272, "vy":-0.30627, "omega":1.28755, "ax":-6.38942, "ay":-0.68209, "alpha":-0.15507, "fx":[-108.77955,-108.75268,-108.58356,-108.61294], "fy":[-10.64886,-10.99902,-12.54451,-12.21598]}, - {"t":0.49078, "x":6.40079, "y":7.22734, "heading":1.93645, "vx":-3.1167, "vy":-0.33018, "omega":1.28211, "ax":-6.35451, "ay":-0.68136, "alpha":-1.82433, "fx":[-109.07056,-109.04051,-106.8714,-107.37107], "fy":[0.47067,-5.6432,-22.24008,-18.94625]}, - {"t":0.52584, "x":6.28763, "y":7.21535, "heading":1.98139, "vx":-3.33946, "vy":-0.35407, "omega":1.21816, "ax":-6.15681, "ay":-0.68805, "alpha":-5.28855, "fx":[-105.59082,-108.99546,-101.85362,-102.46247], "fy":[25.42423,1.43619,-38.60211,-35.07231]}, - {"t":0.56089, "x":6.16678, "y":7.20251, "heading":2.0241, "vx":-3.5553, "vy":-0.37819, "omega":1.03276, "ax":-5.08959, "ay":-0.96681, "alpha":-13.30588, "fx":[-83.1462,-108.29115,-90.35543,-64.4974], "fy":[68.52344,9.02412,-60.04031,-83.28796]}, - {"t":0.59595, "x":6.03902, "y":7.18866, "heading":2.0603, "vx":-3.73372, "vy":-0.41208, "omega":0.56631, "ax":-4.946, "ay":-0.91653, "alpha":-13.31055, "fx":[-80.29201,-107.08233,-88.19314,-60.95254], "fy":[68.6648,8.36479,-60.54766,-78.84188]}, - {"t":0.631, "x":5.90509, "y":7.17365, "heading":2.08016, "vx":-3.9071, "vy":-0.44421, "omega":0.0997, "ax":-1.07534, "ay":0.49336, "alpha":-2.72579, "fx":[-15.5327,-27.49389,-21.35461,-8.7838], "fy":[18.30479,10.92264,-1.49623,5.83655]}, - {"t":0.66606, "x":5.76746, "y":7.15838, "heading":2.08365, "vx":-3.9448, "vy":-0.42692, "omega":0.00415, "ax":-0.02315, "ay":0.20411, "alpha":-0.00308, "fx":[-0.39077,-0.40473,-0.3969,-0.38293], "fy":[3.48265,3.47484,3.4609,3.46872]}, - {"t":0.70111, "x":5.62916, "y":7.14354, "heading":2.0838, "vx":-3.94561, "vy":-0.41976, "omega":0.00404, "ax":-0.00687, "ay":0.06477, "alpha":-0.00001, "fx":[-0.11691,-0.11697,-0.11694,-0.11688], "fy":[1.10174,1.10171,1.10165,1.10168]}, - {"t":0.73617, "x":5.49084, "y":7.12887, "heading":2.08394, "vx":-3.94585, "vy":-0.41749, "omega":0.00404, "ax":-0.00182, "ay":0.01717, "alpha":0.0, "fx":[-0.03087,-0.03089,-0.03088,-0.03086], "fy":[0.292,0.29199,0.29198,0.29198]}, - {"t":0.77123, "x":5.35252, "y":7.11424, "heading":2.08408, "vx":-3.94591, "vy":-0.41689, "omega":0.00404, "ax":0.00064, "ay":-0.00604, "alpha":0.0, "fx":[0.01086,0.01086,0.01086,0.01086], "fy":[-0.10274,-0.10275,-0.10275,-0.10275]}, - {"t":0.80628, "x":5.21419, "y":7.09962, "heading":2.08422, "vx":-3.94589, "vy":-0.4171, "omega":0.00404, "ax":0.00401, "ay":-0.03783, "alpha":0.0, "fx":[0.06814,0.06815,0.06814,0.06813], "fy":[-0.64354,-0.64353,-0.64352,-0.64353]}, - {"t":0.84134, "x":5.07587, "y":7.08498, "heading":2.08436, "vx":-3.94575, "vy":-0.41843, "omega":0.00404, "ax":0.01315, "ay":-0.12336, "alpha":0.00001, "fx":[0.2237,0.22377,0.22373,0.22366], "fy":[-2.0984,-2.09837,-2.0983,-2.09834]}, - {"t":0.87639, "x":4.93755, "y":7.07023, "heading":2.0845, "vx":-3.94529, "vy":-0.42275, "omega":0.00404, "ax":0.0417, "ay":-0.38291, "alpha":0.00006, "fx":[0.70925,0.70951,0.70937,0.70911], "fy":[-6.51341,-6.51327,-6.51301,-6.51316]}, - {"t":0.91145, "x":4.79927, "y":7.05518, "heading":2.08465, "vx":-3.94383, "vy":-0.43617, "omega":0.00404, "ax":0.13327, "ay":-1.15045, "alpha":0.00023, "fx":[2.26662,2.26772,2.26711,2.26601], "fy":[-19.56967,-19.56908,-19.56806,-19.56865]}, - {"t":0.9465, "x":4.6611, "y":7.03918, "heading":2.08479, "vx":-3.93916, "vy":-0.4765, "omega":0.00405, "ax":0.38708, "ay":-2.88535, "alpha":0.00085, "fx":[6.58303,6.58774,6.58535,6.58065], "fy":[-49.08147,-49.07952,-49.07655,-49.0785]}, - {"t":0.98156, "x":4.52325, "y":7.0207, "heading":2.08493, "vx":-3.92559, "vy":-0.57765, "omega":0.00408, "ax":0.78846, "ay":-4.67063, "alpha":0.00207, "fx":[13.40709,13.42214,13.41582,13.40077], "fy":[-79.45011,-79.44586,-79.44219,-79.44644]}, - {"t":1.01662, "x":4.38612, "y":6.99759, "heading":2.08507, "vx":-3.89795, "vy":-0.74138, "omega":0.00415, "ax":1.19202, "ay":-5.5066, "alpha":0.00367, "fx":[20.26579,20.29678,20.28616,20.25516], "fy":[-93.67082,-93.66273,-93.66059,-93.66867]}, - {"t":1.05167, "x":4.25021, "y":6.96821, "heading":2.08522, "vx":-3.85616, "vy":-0.93442, "omega":0.00428, "ax":1.57297, "ay":-5.801, "alpha":0.00554, "fx":[26.73775,26.78768,26.77391,26.72396], "fy":[-98.68064,-98.66611,-98.66598,-98.6805]}, - {"t":1.08673, "x":4.11599, "y":6.93189, "heading":2.08537, "vx":-3.80102, "vy":-1.13778, "omega":0.00448, "ax":1.93896, "ay":-5.87337, "alpha":0.0078, "fx":[32.95278,33.02481,33.00948,32.93739], "fy":[-99.91571,-99.89124,-99.89284,-99.91732]}, - {"t":1.12178, "x":3.98394, "y":6.8884, "heading":2.08553, "vx":-3.73305, "vy":-1.34368, "omega":0.00475, "ax":2.29416, "ay":-5.84237, "alpha":0.01111, "fx":[38.97924,39.0824,39.06666,38.9634], "fy":[-99.39609,-99.35509,-99.35787,-99.39889]}, - {"t":1.15684, "x":3.85448, "y":6.8377, "heading":2.08569, "vx":-3.65262, "vy":-1.54848, "omega":0.00514, "ax":2.64248, "ay":-5.75159, "alpha":0.02616, "fx":[44.83879,45.07942,45.05713,44.81589], "fy":[-97.88616,-97.77508,-97.77945,-97.89075]}, - {"t":1.19189, "x":3.72806, "y":6.77989, "heading":2.08587, "vx":-3.55999, "vy":-1.75011, "omega":0.00606, "ax":3.01865, "ay":-5.60066, "alpha":0.19141, "fx":[50.5176,52.22499,52.19078,50.45238], "fy":[-95.7296,-94.80826,-94.79359,-95.73084]}, - {"t":1.22695, "x":3.60512, "y":6.71509, "heading":2.08608, "vx":-3.45417, "vy":-1.94644, "omega":0.01277, "ax":3.60553, "ay":-5.2551, "alpha":1.27445, "fx":[55.8629,65.99099,67.38428,56.07805], "fy":[-93.21179,-86.35181,-85.08178,-92.90566]}, - {"t":1.26201, "x":3.48624, "y":6.64363, "heading":2.08653, "vx":-3.32777, "vy":-2.13067, "omega":0.05744, "ax":4.29187, "ay":-4.66929, "alpha":2.86258, "fx":[61.4836,80.38461,86.48035,63.66529], "fy":[-89.97029,-73.63397,-65.98976,-88.09886]}, - {"t":1.29706, "x":3.37222, "y":6.56607, "heading":2.08855, "vx":-3.17732, "vy":-2.29435, "omega":0.15779, "ax":4.79653, "ay":-4.09967, "alpha":3.78485, "fx":[67.22082,88.89522,97.733,72.50168], "fy":[-86.0102,-63.45553,-48.27699,-81.19446]}, - {"t":1.33212, "x":3.26379, "y":6.48312, "heading":2.09408, "vx":-3.00917, "vy":-2.43807, "omega":0.29047, "ax":5.14217, "ay":-3.63, "alpha":4.19206, "fx":[72.30458,93.96445,103.27626,80.32208], "fy":[-81.95402,-55.93539,-35.4107,-73.68085]}, - {"t":1.36717, "x":3.16146, "y":6.39542, "heading":2.10426, "vx":-2.82891, "vy":-2.56532, "omega":0.43743, "ax":5.39135, "ay":-3.24812, "alpha":4.28534, "fx":[76.91758,97.27577,105.98271,86.64505], "fy":[-77.76953,-50.15111,-26.73613,-66.34158]}, - {"t":1.40223, "x":3.0656, "y":6.3035, "heading":2.11959, "vx":-2.63991, "vy":-2.67919, "omega":0.58766, "ax":5.5826, "ay":-2.92924, "alpha":4.18911, "fx":[81.24844,99.64999,107.35668,91.57834], "fy":[-73.33495,-45.4029,-21.01373,-59.55081]}, - {"t":1.43728, "x":2.97649, "y":6.20777, "heading":2.14019, "vx":-2.44421, "vy":-2.78187, "omega":0.73451, "ax":5.73743, "ay":-2.65327, "alpha":3.96566, "fx":[85.39966,101.48501,108.08299,95.40064], "fy":[-68.5399,-41.26077,-17.31846,-53.40657]}, - {"t":1.47234, "x":2.89433, "y":6.10862, "heading":2.16594, "vx":-2.24308, "vy":-2.87489, "omega":0.87353, "ax":5.86865, "ay":-2.40469, "alpha":3.64047, "fx":[89.42975,102.98388,108.47173,98.41085], "fy":[-63.26318,-37.46422,-15.07033,-47.81429]}, - {"t":1.5074, "x":2.8193, "y":6.00637, "heading":2.19657, "vx":-2.03735, "vy":-2.95918, "omega":1.00115, "ax":5.98348, "ay":-2.17193, "alpha":3.22395, "fx":[93.34334,104.2516,108.66795,100.84608], "fy":[-57.39567,-33.86211,-13.90944,-42.60865]}, - {"t":1.54245, "x":2.75156, "y":5.90129, "heading":2.23166, "vx":-1.8276, "vy":-3.03532, "omega":1.11416, "ax":6.08309, "ay":-1.95124, "alpha":2.74257, "fx":[96.99087,105.32698,108.74978,102.8188], "fy":[-51.04944,-30.42668,-13.52491,-37.75879]}, - {"t":1.57751, "x":2.69123, "y":5.79369, "heading":2.27072, "vx":-1.61435, "vy":-3.10372, "omega":1.21031, "ax":6.1652, "ay":-1.74704, "alpha":2.2471, "fx":[100.12584,106.21227,108.76939,104.36543], "fy":[-44.64481,-27.24262,-13.58754,-33.39147]}, - {"t":1.61256, "x":2.63842, "y":5.68381, "heading":2.31315, "vx":-1.39822, "vy":-3.16497, "omega":1.28908, "ax":6.22802, "ay":-1.51109, "alpha":2.06343, "fx":[102.14338,107.06692,108.99228,105.54463], "fy":[-39.58478,-23.30258,-10.8244,-29.10098]}, - {"t":1.6382, "x":2.60463, "y":5.60218, "heading":2.34619, "vx":-1.23856, "vy":-3.20371, "omega":1.34198, "ax":6.29629, "ay":-1.19159, "alpha":2.03359, "fx":[104.03881,108.0486,109.36667,106.93842], "fy":[-34.21134,-18.07502,-5.459,-23.32897]}, - {"t":1.66384, "x":2.57494, "y":5.51966, "heading":2.3806, "vx":-1.07715, "vy":-3.23425, "omega":1.39411, "ax":6.35723, "ay":-0.80753, "alpha":1.96526, "fx":[105.98267,108.87619,109.47248,108.20729], "fy":[-27.48828,-11.88639,0.68823,-16.25721]}, - {"t":1.68947, "x":2.54942, "y":5.43648, "heading":2.41634, "vx":-0.91418, "vy":-3.25496, "omega":1.44449, "ax":6.4007, "ay":-0.34358, "alpha":1.83845, "fx":[107.79931,109.39956,109.17307,109.12407], "fy":[-18.96828,-4.4984,7.69687,-7.60677]}, - {"t":1.71511, "x":2.52809, "y":5.35292, "heading":2.45337, "vx":-0.75009, "vy":-3.26376, "omega":1.49162, "ax":6.40941, "ay":0.21505, "alpha":1.63368, "fx":[109.11133,109.36932,108.2876,109.32063], "fy":[-8.18128,4.35987,15.64185,2.81138]}, - {"t":1.74074, "x":2.51096, "y":5.26932, "heading":2.49161, "vx":-0.58578, "vy":-3.25825, "omega":1.5335, "ax":6.35697, "ay":0.87751, "alpha":1.33816, "fx":[109.25364,108.39003,106.5791,108.29844], "fy":[5.20582,14.94598,24.5843,14.96849]}, - {"t":1.76638, "x":2.49803, "y":5.18608, "heading":2.53092, "vx":-0.42281, "vy":-3.23575, "omega":1.56781, "ax":6.20838, "ay":1.64129, "alpha":0.94581, "fx":[107.26459,105.87678,103.75421,105.51565], "fy":[21.1967,27.42659,34.51453,28.53373]}, - {"t":1.79202, "x":2.48924, "y":5.10367, "heading":2.57111, "vx":-0.26365, "vy":-3.19368, "omega":1.59206, "ax":5.92515, "ay":2.48412, "alpha":0.45991, "fx":[102.04444,101.05091,99.49619,100.54905], "fy":[39.17964,41.72492,45.27644,42.83543]}, - {"t":1.81765, "x":2.48442, "y":5.02261, "heading":2.61193, "vx":-0.11175, "vy":-3.13, "omega":1.60385, "ax":5.47809, "ay":3.35733, "alpha":-0.09966, "fx":[92.81744,93.06746,93.54364,93.2942], "fy":[57.7001,57.28685,56.51093,56.93081]}, - {"t":1.84329, "x":2.48336, "y":4.94348, "heading":2.65304, "vx":0.02868, "vy":-3.04393, "omega":1.60129, "ax":4.86546, "ay":4.19033, "alpha":-0.69506, "fx":[79.7678,81.37885,85.80562,84.08793], "fy":[74.71281,72.89982,67.65791,69.8346]}, - {"t":1.86892, "x":2.48569, "y":4.86682, "heading":2.69409, "vx":0.15341, "vy":-2.9365, "omega":1.58347, "ax":4.12395, "ay":4.91154, "alpha":-1.28169, "fx":[64.24052,66.24951,76.46428,73.63445], "fy":[88.44646,86.86426,78.05165,80.81292]}, - {"t":1.89456, "x":2.49098, "y":4.79315, "heading":2.73469, "vx":0.25914, "vy":-2.81059, "omega":1.55062, "ax":3.31924, "ay":5.47496, "alpha":-1.82091, "fx":[48.11596,48.97017,65.98894,62.76205], "fy":[98.19453,97.66419,87.09453,89.55684]}, - {"t":1.9202, "x":2.49871, "y":4.7229, "heading":2.77444, "vx":0.34423, "vy":-2.67023, "omega":1.50394, "ax":2.52073, "ay":5.87264, "alpha":-2.28531, "fx":[32.93006,31.37636,55.02542,52.17555], "fy":[104.31688,104.67884,94.42248,96.14981]}, - {"t":1.94583, "x":2.50837, "y":4.65637, "heading":2.81299, "vx":0.40885, "vy":-2.51968, "omega":1.44535, "ax":1.77939, "ay":6.12649, "alpha":-2.6619, "fx":[19.48881,15.02796,44.21596,42.33461], "fy":[107.68392,108.27929,99.96734,100.90881]}, - {"t":1.97147, "x":2.51943, "y":4.59379, "heading":2.85005, "vx":0.45447, "vy":-2.36262, "omega":1.37711, "ax":1.12093, "ay":6.27083, "alpha":-2.95303, "fx":[7.99376,0.76013,34.05277,33.46031], "fy":[109.18062,109.35579,103.89955,104.22412]}, - {"t":1.9971, "x":2.53145, "y":4.53528, "heading":2.88535, "vx":0.4832, "vy":-2.20187, "omega":1.3014, "ax":0.55117, "ay":6.33887, "alpha":-3.17135, "fx":[-1.68353,-11.24168,24.82371,25.60278], "fy":[109.49552,108.82021,106.51369,106.45977]}, - {"t":2.02274, "x":2.54402, "y":4.48092, "heading":2.91871, "vx":0.49733, "vy":-2.03936, "omega":1.2201, "ax":0.06458, "ay":6.35685, "alpha":-3.33275, "fx":[-9.79463,-21.16054,16.63603,18.71343], "fy":[109.10099,107.37218,108.12658,107.91335]}, - {"t":2.04838, "x":2.55679, "y":4.43073, "heading":2.94999, "vx":0.49899, "vy":-1.8764, "omega":1.13467, "ax":-0.34907, "ay":6.34349, "alpha":-3.45177, "fx":[-16.60578,-29.31527,9.47309,12.69796], "fy":[108.30137,105.47368,109.01778,108.8113]}, - {"t":2.07401, "x":2.56947, "y":4.38471, "heading":2.97908, "vx":0.49004, "vy":-1.71378, "omega":1.04618, "ax":-0.70092, "ay":6.31136, "alpha":-3.53993, "fx":[-22.35412,-36.03408,3.24962,7.44856], "fy":[107.28667,103.40366,109.40827,109.31924]}, - {"t":2.09965, "x":2.5818, "y":4.34285, "heading":3.0059, "vx":0.47207, "vy":-1.55198, "omega":0.95543, "ax":-1.00131, "ay":6.26864, "alpha":-3.60569, "fx":[-27.23624,-41.60413,-2.14847,2.86054], "fy":[106.17369,101.32014,109.46125,109.55581]}, - {"t":2.12528, "x":2.59357, "y":4.30512, "heading":3.03039, "vx":0.4464, "vy":-1.39127, "omega":0.86299, "ax":-1.25913, "ay":6.22053, "alpha":-3.65508, "fx":[-31.40987,-46.25967,-6.8401,-1.16034], "fy":[105.03353,99.30721,109.29212,109.60518]}, - {"t":2.15092, "x":2.60461, "y":4.2715, "heading":3.05252, "vx":0.41412, "vy":-1.2318, "omega":0.76929, "ax":-1.48177, "ay":6.17032, "alpha":-3.69231, "fx":[-34.99991,-50.18585,-10.9367,-4.69555], "fy":[103.9091,97.40564,108.98004,109.52687]}, - {"t":2.17656, "x":2.61473, "y":4.24195, "heading":3.07224, "vx":0.37614, "vy":-1.07362, "omega":0.67463, "ax":-1.67527, "ay":6.12001, "alpha":-3.72034, "fx":[-38.10495,-53.52715,-14.53708,-7.81411], "fy":[102.82594,95.63159,108.57809,109.36307]}, - {"t":2.20219, "x":2.62383, "y":4.21644, "heading":3.08953, "vx":0.33319, "vy":-0.91673, "omega":0.57926, "ax":-1.84452, "ay":6.07082, "alpha":-3.74125, "fx":[-40.80291,-56.39601,-17.72623,-10.57384], "fy":[101.79885,93.98768,108.12111,109.14374]}, - {"t":2.22783, "x":2.63176, "y":4.19493, "heading":3.10438, "vx":0.2859, "vy":-0.7611, "omega":0.48335, "ax":-1.99349, "ay":6.02343, "alpha":-3.75653, "fx":[-43.15573,-58.88007,-20.57603,-13.02296], "fy":[100.83597,92.46939,107.63143,108.89028]}, - {"t":2.25346, "x":2.63844, "y":4.1774, "heading":3.11677, "vx":0.2348, "vy":-0.60668, "omega":0.38704, "ax":-2.12539, "ay":5.97822, "alpha":-3.76722, "fx":[-45.21292,-61.04804,-23.14678,-15.2017], "fy":[99.94137,91.06878,107.12284,108.618]}, - {"t":2.2791, "x":2.64376, "y":4.16381, "heading":3.1267, "vx":0.18031, "vy":-0.45342, "omega":0.29047, "ax":-2.24285, "ay":5.93535, "alpha":-3.77411, "fx":[-47.01437,-62.95407,-25.4889,-17.14367], "fy":[99.11657,89.77654,106.60337,108.33791]}, - {"t":2.30474, "x":2.64764, "y":4.15414, "heading":3.13414, "vx":0.12281, "vy":-0.30126, "omega":0.19371, "ax":-2.348, "ay":5.89486, "alpha":-3.77775, "fx":[-48.59244,-64.64112,-27.64456,-18.87714], "fy":[98.36155,88.58321,106.07717,108.05791]}, - {"t":2.33037, "x":2.65002, "y":4.14835, "heading":3.13911, "vx":0.06262, "vy":-0.15014, "omega":0.09687, "ax":-2.44261, "ay":5.85672, "alpha":-3.77857, "fx":[-49.97358,-66.14344,-29.64915,-20.42596], "fy":[97.67535,87.4798,105.54578,107.78365]}, - {"t":2.35601, "x":2.65082, "y":4.14642, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/B_LEFT_PATH2.traj b/src/main/deploy/choreo/B_LEFT_PATH2.traj deleted file mode 100644 index c52280b7..00000000 --- a/src/main/deploy/choreo/B_LEFT_PATH2.traj +++ /dev/null @@ -1,159 +0,0 @@ -{ - "name":"B_LEFT_PATH2", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":3.171550750732422, "y":4.146424770355225, "heading":3.141592653589793, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.7844728231430054, "y":6.438039302825928, "heading":0.0, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":0.9014043211936952, "y":7.158551216125488, "heading":2.179485408307156, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.4965330362319946, "y":4.913652420043945, "heading":0.0, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":2.9235854148864746, "y":3.9604506492614746, "heading":3.141592653589793, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":true}, - {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"3.171550750732422 m", "val":3.171550750732422}, "y":{"exp":"4.146424770355225 m", "val":4.146424770355225}, "heading":{"exp":"180 deg", "val":3.141592653589793}, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.7844728231430054 m", "val":1.7844728231430054}, "y":{"exp":"6.438039302825928 m", "val":6.438039302825928}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"0.9014043211936951 m", "val":0.9014043211936952}, "y":{"exp":"7.158551216125488 m", "val":7.158551216125488}, "heading":{"exp":"2.1794854083071558 rad", "val":2.179485408307156}, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.4965330362319946 m", "val":1.4965330362319946}, "y":{"exp":"4.913652420043945 m", "val":4.913652420043945}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"2.9235854148864746 m", "val":2.9235854148864746}, "y":{"exp":"3.9604506492614746 m", "val":3.9604506492614746}, "heading":{"exp":"180 deg", "val":3.141592653589793}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":true}, - {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,0.99188,1.59067,2.50142,3.25943], - "samples":[ - {"t":0.0, "x":3.17155, "y":4.14642, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-2.98514, "ay":5.61149, "alpha":-3.59953, "fx":[-57.08165,-73.47949,-42.54754,-29.99696], "fy":[93.72379,81.45843,101.0745,105.54261]}, - {"t":0.03006, "x":3.1702, "y":4.14896, "heading":3.14159, "vx":-0.08972, "vy":0.16867, "omega":-0.10819, "ax":-2.9869, "ay":5.61371, "alpha":-3.53646, "fx":[-57.00186,-73.11056,-42.75603,-30.35708], "fy":[93.76417,81.77848,100.97629,105.43164]}, - {"t":0.06011, "x":3.16616, "y":4.15656, "heading":3.13834, "vx":-0.1795, "vy":0.3374, "omega":-0.21449, "ax":-2.98886, "ay":5.61619, "alpha":-3.46459, "fx":[-56.85552,-72.7007,-43.07679,-30.72527], "fy":[93.84386,82.13081,100.82856,105.31595]}, - {"t":0.09017, "x":3.15941, "y":4.16924, "heading":3.13189, "vx":-0.26934, "vy":0.5062, "omega":-0.31862, "ax":-2.991, "ay":5.61894, "alpha":-3.38295, "fx":[-56.64467,-72.24211,-43.50381,-31.11335], "fy":[93.96103,82.52103,100.63246,105.19175]}, - {"t":0.12023, "x":3.14996, "y":4.187, "heading":3.12232, "vx":-0.35924, "vy":0.67509, "omega":-0.4203, "ax":-2.99333, "ay":5.62198, "alpha":-3.29031, "fx":[-56.3717,-71.72448,-44.03017,-31.53629], "fy":[94.11344,82.95646,100.38919,105.05406]}, - {"t":0.15029, "x":3.13781, "y":4.20983, "heading":3.10968, "vx":-0.44921, "vy":0.84407, "omega":-0.5192, "ax":-2.99585, "ay":5.62534, "alpha":-3.18505, "fx":[-56.03939,-71.1344,-44.64763,-32.01303], "fy":[94.29842,83.44639,100.10029,104.89635]}, - {"t":0.18034, "x":3.12296, "y":4.23774, "heading":3.09408, "vx":-0.53926, "vy":1.01315, "omega":-0.61493, "ax":-2.99857, "ay":5.62904, "alpha":-3.06498, "fx":[-55.65117,-70.4545,-45.34612,-32.56761], "fy":[94.51272,84.0025,99.76795,104.70994]}, - {"t":0.2104, "x":3.1054, "y":4.27073, "heading":3.0756, "vx":-0.62938, "vy":1.18235, "omega":-0.70706, "ax":-3.00148, "ay":5.63311, "alpha":-2.92708, "fx":[-55.21129,-69.66205,-46.11302,-33.23079], "fy":[94.75244,84.63947,99.39551,104.48316]}, - {"t":0.24046, "x":3.08512, "y":4.30882, "heading":3.05434, "vx":-0.7196, "vy":1.35166, "omega":-0.79504, "ax":-3.00456, "ay":5.63761, "alpha":-2.76716, "fx":[-54.72529,-68.72688,-46.93242,-34.04253], "fy":[95.01273,85.3759,98.98802,104.19997]}, - {"t":0.27051, "x":3.06214, "y":4.35199, "heading":3.03045, "vx":-0.80991, "vy":1.52111, "omega":-0.87821, "ax":-3.00781, "ay":5.64257, "alpha":-2.57917, "fx":[-54.20051,-67.60794,-47.78405,-35.05559], "fy":[95.28748,86.2358,98.55295,103.83772]}, - {"t":0.30057, "x":3.03643, "y":4.40026, "heading":3.00405, "vx":-0.90032, "vy":1.69071, "omega":-0.95573, "ax":-3.01119, "ay":5.64801, "alpha":-2.35432, "fx":[-53.64706,-66.24749,-48.64195,-36.34127], "fy":[95.56871,87.25088,98.10115,103.36337]}, - {"t":0.33063, "x":3.00801, "y":4.45363, "heading":2.97532, "vx":-0.99082, "vy":1.86047, "omega":-1.0265, "ax":-3.01462, "ay":5.6539, "alpha":-2.07939, "fx":[-53.07933,-64.56118,-49.47261,-37.99849], "fy":[95.84556,88.46421,97.64808,102.72679]}, - {"t":0.36069, "x":2.97687, "y":4.5121, "heading":2.94447, "vx":-1.08143, "vy":2.03041, "omega":-1.089, "ax":-3.01798, "ay":5.66004, "alpha":-1.73409, "fx":[-52.5189,-62.41977,-50.23223,-40.1689], "fy":[96.10228,89.9362,97.21549,101.84839]}, - {"t":0.39074, "x":2.943, "y":4.57569, "heading":2.91174, "vx":-1.17215, "vy":2.20054, "omega":-1.14112, "ax":-3.02091, "ay":5.66583, "alpha":-1.28595, "fx":[-52.00004,-59.61385,-50.86241,-43.06279], "fy":[96.31427,91.7541,96.83373,100.59473]}, - {"t":0.4208, "x":2.90641, "y":4.64439, "heading":2.87744, "vx":-1.26294, "vy":2.37084, "omega":-1.17977, "ax":-3.02254, "ay":5.66967, "alpha":-0.68081, "fx":[-51.58213,-55.78014,-51.28295,-47.00515], "fy":[96.43891,94.04683,96.54513,98.72724]}, - {"t":0.45086, "x":2.86708, "y":4.71821, "heading":2.84198, "vx":-1.35379, "vy":2.54125, "omega":-1.20023, "ax":-3.02052, "ay":5.66717, "alpha":0.1773, "fx":[-51.38099,-50.23407,-51.379,-52.51861], "fy":[96.39139,97.00245,96.40914,95.78489]}, - {"t":0.48091, "x":2.82503, "y":4.79715, "heading":2.8059, "vx":-1.44458, "vy":2.71159, "omega":-1.19491, "ax":-3.00793, "ay":5.64561, "alpha":1.47097, "fx":[-51.66754,-41.54786,-50.97666,-60.46399], "fy":[95.96526,100.85373,96.51041,90.79167]}, - {"t":0.51097, "x":2.78025, "y":4.8812, "heading":2.76999, "vx":-1.53499, "vy":2.88128, "omega":-1.15069, "ax":-2.96396, "ay":5.56258, "alpha":3.57493, "fx":[-53.29944,-26.39281,-49.79443,-72.17765], "fy":[94.46051,105.56359,96.97099,81.47653]}, - {"t":0.54103, "x":2.73277, "y":4.97032, "heading":2.7354, "vx":-1.62408, "vy":3.04847, "omega":-1.04324, "ax":-2.85544, "ay":5.22785, "alpha":7.30869, "fx":[-61.37561,3.14255,-47.35378,-88.69429], "fy":[86.94175,108.31657,97.95738,62.48124]}, - {"t":0.57108, "x":2.68267, "y":5.06431, "heading":2.70404, "vx":-1.70991, "vy":3.20561, "omega":-0.82356, "ax":-2.93526, "ay":4.225, "alpha":12.29747, "fx":[-87.43373,29.83058,-44.33927,-97.7695], "fy":[39.7038,103.35388,98.85425,45.55251]}, - {"t":0.60114, "x":2.62994, "y":5.16257, "heading":2.67929, "vx":-1.79813, "vy":3.3326, "omega":-0.45394, "ax":-2.70973, "ay":4.17, "alpha":12.30676, "fx":[-76.88178,29.33749,-42.16935,-94.65307], "fy":[37.7942,100.86886,97.98906,47.06959]}, - {"t":0.6312, "x":2.57467, "y":5.26462, "heading":2.66565, "vx":-1.87958, "vy":3.45794, "omega":-0.08403, "ax":-0.08616, "ay":1.13743, "alpha":2.64549, "fx":[1.6224,7.9991,-4.39432,-11.08926], "fy":[10.2734,22.37221,28.18654,16.5575]}, - {"t":0.66126, "x":2.51814, "y":5.36907, "heading":2.66312, "vx":-1.88217, "vy":3.49213, "omega":-0.00452, "ax":0.03027, "ay":0.01888, "alpha":0.00522, "fx":[0.52068,0.53316,0.5091,0.49663], "fy":[0.30291,0.32697,0.33944,0.31539]}, - {"t":0.69131, "x":2.46158, "y":5.47404, "heading":2.66298, "vx":-1.88126, "vy":3.49269, "omega":-0.00436, "ax":-0.33184, "ay":-0.17934, "alpha":-0.00001, "fx":[-5.64451,-5.64454,-5.64448,-5.64445], "fy":[-3.05052,-3.05058,-3.05061,-3.05055]}, - {"t":0.72137, "x":2.40489, "y":5.57894, "heading":2.66285, "vx":-1.89123, "vy":3.4873, "omega":-0.00436, "ax":-0.9593, "ay":-0.52546, "alpha":-0.00015, "fx":[-16.31754,-16.31788,-16.31718,-16.31684], "fy":[-8.93739,-8.9381,-8.93848,-8.93778]}, - {"t":0.75143, "x":2.34761, "y":5.68352, "heading":2.66272, "vx":-1.92007, "vy":3.47151, "omega":-0.00436, "ax":-2.12622, "ay":-1.20212, "alpha":-0.00056, "fx":[-36.16716,-36.16808,-36.16555,-36.16463], "fy":[-20.44558,-20.44817,-20.44991,-20.44732]}, - {"t":0.78148, "x":2.28894, "y":5.78732, "heading":2.66259, "vx":-1.98397, "vy":3.43538, "omega":-0.00438, "ax":-3.49453, "ay":-2.09158, "alpha":-0.00143, "fx":[-59.44406,-59.44453,-59.43796,-59.43749], "fy":[-35.57068,-35.57732,-35.5837,-35.57706]}, - {"t":0.81154, "x":2.22773, "y":5.88964, "heading":2.66246, "vx":-2.08901, "vy":3.37251, "omega":-0.00442, "ax":-4.33537, "ay":-2.8061, "alpha":-0.00274, "fx":[-73.75127,-73.74874,-73.73558,-73.73811], "fy":[-47.71702,-47.72914,-47.7448,-47.73268]}, - {"t":0.8416, "x":2.16298, "y":5.98974, "heading":2.66233, "vx":-2.21932, "vy":3.28817, "omega":-0.00451, "ax":-4.66824, "ay":-3.30409, "alpha":-0.00633, "fx":[-79.42694,-79.41657,-79.38379,-79.39416], "fy":[-56.16847,-56.19405,-56.23473,-56.20917]}, - {"t":0.87166, "x":2.09416, "y":6.08708, "heading":2.66219, "vx":-2.35963, "vy":3.18885, "omega":-0.0047, "ax":-4.71603, "ay":-3.70867, "alpha":-0.1145, "fx":[-80.65574,-80.43101,-79.78185,-80.00483], "fy":[-62.49285,-62.90163,-63.6699,-63.26908]}, - {"t":0.90171, "x":2.02111, "y":6.18125, "heading":2.66205, "vx":-2.50138, "vy":3.07738, "omega":-0.00814, "ax":-3.90487, "ay":-4.68621, "alpha":-2.84029, "fx":[-79.57417,-74.29393,-55.27066,-56.54383], "fy":[-67.36567,-74.81335,-89.5601,-87.10547]}, - {"t":0.93177, "x":1.94416, "y":6.27163, "heading":2.66181, "vx":-2.61875, "vy":2.93653, "omega":-0.09351, "ax":-1.47832, "ay":-5.59564, "alpha":-8.52097, "fx":[-66.5734,-58.54014,-6.37704,30.90711], "fy":[-81.19805,-90.2517,-107.57367,-101.6974]}, - {"t":0.96183, "x":1.86478, "y":6.35737, "heading":2.659, "vx":-2.66318, "vy":2.76834, "omega":-0.34962, "ax":-0.57627, "ay":-5.60997, "alpha":-10.00491, "fx":[-55.91851,-52.75274,8.95459,60.50824], "fy":[-89.5528,-94.67611,-108.23952,-89.2273]}, - {"t":0.99188, "x":1.78447, "y":6.43804, "heading":2.64849, "vx":-2.68051, "vy":2.59972, "omega":-0.65034, "ax":0.65999, "ay":-5.76388, "alpha":-8.47293, "fx":[-10.18212,-39.339,21.56126,72.86499], "fy":[-104.70691,-100.98153,-106.54642,-79.9326]}, - {"t":1.01683, "x":1.7178, "y":6.50111, "heading":2.63226, "vx":-2.66404, "vy":2.45592, "omega":-0.86174, "ax":2.319, "ay":-5.68181, "alpha":-5.63997, "fx":[47.32077,-1.10229,37.65358,73.90972], "fy":[-96.49738,-108.46014,-102.10399,-79.52246]}, - {"t":1.04178, "x":1.65206, "y":6.56061, "heading":2.61076, "vx":-2.60618, "vy":2.31416, "omega":-1.00245, "ax":3.21065, "ay":-5.42105, "alpha":-3.55157, "fx":[62.90687,31.34024,50.33077,73.87095], "fy":[-88.2681,-104.06098,-96.61181,-79.90086]}, - {"t":1.06673, "x":1.58803, "y":6.61666, "heading":2.58575, "vx":-2.52608, "vy":2.17891, "omega":-1.09106, "ax":3.75568, "ay":-5.1533, "alpha":-1.95835, "fx":[69.04764,52.55734,60.14797,73.77933], "fy":[-84.09627,-95.37008,-90.94396,-80.21465]}, - {"t":1.09168, "x":1.52618, "y":6.66942, "heading":2.55853, "vx":-2.43238, "vy":2.05034, "omega":-1.13992, "ax":4.10393, "ay":-4.92165, "alpha":-0.82613, "fx":[72.10419,65.58642,67.77707,73.75871], "fy":[-81.80455,-87.14162,-85.52008,-80.39696]}, - {"t":1.11663, "x":1.46677, "y":6.71904, "heading":2.53009, "vx":-2.32999, "vy":1.92754, "omega":-1.16053, "ax":4.33807, "ay":-4.73204, "alpha":-0.00763, "fx":[73.81129,73.75468,73.76753,73.8241], "fy":[-80.47012,-80.52215,-80.51101,-80.45901]}, - {"t":1.14158, "x":1.40999, "y":6.76566, "heading":2.50114, "vx":-2.22175, "vy":1.80948, "omega":-1.16072, "ax":4.50348, "ay":-4.57807, "alpha":0.60822, "fx":[74.81702,79.09634,78.5292,73.96888], "fy":[-79.67675,-75.42359,-75.96593,-80.4206]}, - {"t":1.16653, "x":1.35596, "y":6.80938, "heading":2.47218, "vx":-2.1094, "vy":1.69526, "omega":-1.14555, "ax":4.62526, "ay":-4.45209, "alpha":1.0893, "fx":[75.41684,82.7383,82.36028,74.18218], "fy":[-79.21254,-71.5244,-71.87831,-80.29952]}, - {"t":1.19148, "x":1.30477, "y":6.85029, "heading":2.4436, "vx":-1.994, "vy":1.58419, "omega":-1.11837, "ax":4.71799, "ay":-4.34775, "alpha":1.47638, "fx":[75.76492,85.31128,85.47748,74.45286], "fy":[-78.95851,-68.529,-68.21817,-80.11051]}, - {"t":1.21643, "x":1.25649, "y":6.88846, "heading":2.41569, "vx":-1.87629, "vy":1.47571, "omega":-1.08153, "ax":4.79053, "ay":-4.2603, "alpha":1.79472, "fx":[75.9498,87.18256,88.03973,74.77037], "fy":[-78.84273,-66.20981,-64.9474,-79.86594]}, - {"t":1.24138, "x":1.21117, "y":6.92395, "heading":2.38871, "vx":-1.75677, "vy":1.36942, "omega":-1.03676, "ax":4.84858, "ay":-4.18616, "alpha":2.0608, "fx":[76.02619,88.57587,90.16503,75.12485], "fy":[-78.81912,-64.3991,-62.02667,-79.57652]}, - {"t":1.26633, "x":1.16885, "y":6.95682, "heading":2.36284, "vx":-1.6358, "vy":1.26498, "omega":-0.98534, "ax":4.89592, "ay":-4.12266, "alpha":2.28589, "fx":[76.02977,89.63352,91.94232,75.50707], "fy":[-78.85686,-62.97388,-59.4185,-79.25182]}, - {"t":1.29128, "x":1.12956, "y":6.98709, "heading":2.33826, "vx":-1.51365, "vy":1.16212, "omega":-0.92831, "ax":4.93516, "ay":-4.06777, "alpha":2.47809, "fx":[75.98488,90.44967,93.43954,75.90831], "fy":[-78.9346,-61.84312,-57.08836,-78.90067]}, - {"t":1.31623, "x":1.09333, "y":7.01482, "heading":2.3151, "vx":-1.39052, "vy":1.06063, "omega":-0.86648, "ax":4.96815, "ay":-4.01994, "alpha":2.64348, "fx":[75.90866,91.0888,94.70931,76.32039], "fy":[-79.03721,-60.93854,-55.00501,-78.53135]}, - {"t":1.34117, "x":1.06018, "y":7.04003, "heading":2.29348, "vx":-1.26657, "vy":0.96034, "omega":-0.80053, "ax":4.99624, "ay":-3.97793, "alpha":2.78676, "fx":[75.81351,91.59649,95.79286,76.73563], "fy":[-79.15369,-60.20816,-53.14043,-78.15171]}, - {"t":1.36612, "x":1.03014, "y":7.06276, "heading":2.27351, "vx":-1.14191, "vy":0.86109, "omega":-0.731, "ax":5.02043, "ay":-3.94079, "alpha":2.91166, "fx":[75.70861,92.00583,96.72286,77.14686], "fy":[-79.27598,-59.6118,-51.46958,-77.76923]}, - {"t":1.39107, "x":1.00321, "y":7.08301, "heading":2.25527, "vx":-1.01666, "vy":0.76277, "omega":-0.65836, "ax":5.04146, "ay":-3.90773, "alpha":3.02125, "fx":[75.60084,92.34146,97.52544,77.54744], "fy":[-79.39804,-59.11795,-49.97021,-77.39105]}, - {"t":1.41602, "x":0.97942, "y":7.10083, "heading":2.23884, "vx":-0.89088, "vy":0.66528, "omega":-0.58298, "ax":5.05991, "ay":-3.87813, "alpha":3.11802, "fx":[75.49547,92.62208,98.22165,77.93124], "fy":[-79.51535,-58.70165,-48.62254,-77.02395]}, - {"t":1.44097, "x":0.95876, "y":7.11622, "heading":2.2243, "vx":-0.76464, "vy":0.56852, "omega":-0.50519, "ax":5.07622, "ay":-3.85149, "alpha":3.20407, "fx":[75.39654,92.86218,98.82861,78.29268], "fy":[-79.62444,-58.3428,-47.40908,-76.67432]}, - {"t":1.46592, "x":0.94127, "y":7.1292, "heading":2.2117, "vx":-0.63799, "vy":0.47243, "omega":-0.42525, "ax":5.09073, "ay":-3.82738, "alpha":3.28115, "fx":[75.30725,93.07317,99.36029,78.62671], "fy":[-79.72266,-58.02511,-46.31435,-76.34817]}, - {"t":1.49087, "x":0.92693, "y":7.1398, "heading":2.20109, "vx":-0.51098, "vy":0.37694, "omega":-0.34339, "ax":5.10372, "ay":-3.80546, "alpha":3.35074, "fx":[75.23013,93.26417,99.82817,78.92877], "fy":[-79.80792,-57.73523,-45.32473,-76.05107]}, - {"t":1.51582, "x":0.91577, "y":7.14802, "heading":2.19252, "vx":-0.38364, "vy":0.282, "omega":-0.25979, "ax":5.1154, "ay":-3.78544, "alpha":3.41409, "fx":[75.16726,93.44253,100.24168,79.19482], "fy":[-79.87853,-57.46208,-44.4283,-75.78814]}, - {"t":1.54077, "x":0.90779, "y":7.15388, "heading":2.18604, "vx":-0.25602, "vy":0.18755, "omega":-0.17461, "ax":5.12596, "ay":-3.76709, "alpha":3.47228, "fx":[75.12035,93.61425,100.60863,79.42126], "fy":[-79.9331,-57.19644,-43.61466,-75.56404]}, - {"t":1.56572, "x":0.903, "y":7.15738, "heading":2.18168, "vx":-0.12813, "vy":0.09356, "omega":-0.08798, "ax":5.13553, "ay":-3.75019, "alpha":3.52621, "fx":[75.09089,93.78429,100.93546,79.60495], "fy":[-79.97041,-56.93051,-42.87481,-75.38289]}, - {"t":1.59067, "x":0.9014, "y":7.15855, "heading":2.17949, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.17889, "ay":-6.37469, "alpha":3.15871, "fx":[-0.90927,24.55382,9.0288,-20.5021], "fy":[-109.72956,-106.93301,-109.29357,-107.77041]}, - {"t":1.62005, "x":0.90148, "y":7.1558, "heading":2.17949, "vx":0.00526, "vy":-0.18728, "omega":0.0928, "ax":0.2068, "ay":-6.37612, "alpha":3.09928, "fx":[-0.4454,24.59677,9.4828,-19.56395], "fy":[-109.72558,-106.9156,-109.24647,-107.9365]}, - {"t":1.64943, "x":0.90173, "y":7.14755, "heading":2.18221, "vx":0.01133, "vy":-0.37461, "omega":0.18385, "ax":0.23773, "ay":-6.37755, "alpha":3.03244, "fx":[0.12289,24.66635,9.90649,-18.52067], "fy":[-109.71882,-106.89115,-109.1994,-108.11151]}, - {"t":1.67881, "x":0.90216, "y":7.13379, "heading":2.18761, "vx":0.01832, "vy":-0.56197, "omega":0.27294, "ax":0.27221, "ay":-6.3789, "alpha":2.95719, "fx":[0.80105,24.76124,10.31459,-17.3561], "fy":[-109.70747,-106.85977,-109.15119,-108.29482]}, - {"t":1.70818, "x":0.90282, "y":7.11452, "heading":2.19563, "vx":0.02631, "vy":-0.74938, "omega":0.35982, "ax":0.31086, "ay":-6.38012, "alpha":2.87232, "fx":[1.5961,24.87965,10.72437,-16.04978], "fy":[-109.68923,-106.82162,-109.1002,-108.48533]}, - {"t":1.73756, "x":0.90372, "y":7.08976, "heading":2.2062, "vx":0.03545, "vy":-0.93682, "omega":0.44421, "ax":0.35446, "ay":-6.38111, "alpha":2.77626, "fx":[2.51718,25.01942,11.15631,-14.57589], "fy":[-109.66112,-106.77692,-109.04414,-108.68117]}, - {"t":1.76694, "x":0.90492, "y":7.05948, "heading":2.21925, "vx":0.04586, "vy":-1.1243, "omega":0.52577, "ax":0.404, "ay":-6.38171, "alpha":2.66699, "fx":[3.57634,25.17804,11.63507,-12.90157], "fy":[-109.61929,-106.72589,-108.97994,-108.87914]}, - {"t":1.79632, "x":0.90644, "y":7.02369, "heading":2.2347, "vx":0.05773, "vy":-1.31178, "omega":0.60413, "ax":0.46074, "ay":-6.38172, "alpha":2.54188, "fx":[4.78968,25.35273,12.19062,-10.98469], "fy":[-109.55866,-106.66876,-108.90335,-109.07393]}, - {"t":1.8257, "x":0.90833, "y":6.9824, "heading":2.25245, "vx":0.07126, "vy":-1.49927, "omega":0.67881, "ax":0.5263, "ay":-6.38082, "alpha":2.39742, "fx":[6.17911,25.54056,12.85985,-8.77058], "fy":[-109.47235,-106.60571,-108.80854,-109.25676]}, - {"t":1.85508, "x":0.91066, "y":6.9356, "heading":2.27239, "vx":0.08673, "vy":-1.68674, "omega":0.74924, "ax":0.60282, "ay":-6.37853, "alpha":2.22887, "fx":[7.77501,25.73861,13.68865,-6.1872], "fy":[-109.35078,-106.53678,-108.68722,-109.41321]}, - {"t":1.88446, "x":0.91346, "y":6.88329, "heading":2.2944, "vx":0.10444, "vy":-1.87413, "omega":0.81472, "ax":0.69316, "ay":-6.37413, "alpha":2.02973, "fx":[9.6205,25.94417,14.73474,-3.13789], "fy":[-109.18006,-106.46177,-108.52736,-109.51931]}, - {"t":1.91384, "x":0.91683, "y":6.82548, "heading":2.31834, "vx":0.1248, "vy":-2.0614, "omega":0.87436, "ax":0.80123, "ay":-6.36644, "alpha":1.79091, "fx":[11.77857,26.15523,16.07153,0.50954], "fy":[-108.93916,-106.38008,-108.31102,-109.53479]}, - {"t":1.94322, "x":0.92084, "y":6.76217, "heading":2.34403, "vx":0.14834, "vy":-2.24844, "omega":0.92697, "ax":0.93253, "ay":-6.35352, "alpha":1.49942, "fx":[14.34428,26.371,17.79351,4.93954], "fy":[-108.59449,-106.29034,-108.01079,-109.39033]}, - {"t":1.9726, "x":0.9256, "y":6.69337, "heading":2.37126, "vx":0.17574, "vy":-2.4351, "omega":0.97102, "ax":1.09494, "ay":-6.33205, "alpha":1.13629, "fx":[17.4669,26.59312,20.02378,10.41435], "fy":[-108.08897,-106.1899,-107.5836,-108.96326]}, - {"t":2.00198, "x":0.93124, "y":6.6191, "heading":2.39979, "vx":0.20791, "vy":-2.62113, "omega":1.00441, "ax":1.30008, "ay":-6.29613, "alpha":0.67304, "fx":[21.39253,26.82766,22.92447,17.31138], "fy":[-107.31795,-106.07386,-106.96021,-108.02914]}, - {"t":2.03135, "x":0.93791, "y":6.53937, "heading":2.4293, "vx":0.2461, "vy":-2.80611, "omega":1.02418, "ax":1.56561, "ay":-6.23458, "alpha":0.06576, "fx":[26.55141,27.08932,26.7107,26.17094], "fy":[-106.07105,-105.93305,-106.02642,-106.16286]}, - {"t":2.06073, "x":0.94581, "y":6.45424, "heading":2.45939, "vx":0.2921, "vy":-2.98927, "omega":1.02611, "ax":1.91883, "ay":-6.12516, "alpha":-0.7552, "fx":[33.75064,27.41102,31.66767,37.72575], "fy":[-103.87259,-105.74969,-104.58963,-102.53681]}, - {"t":2.09011, "x":0.95522, "y":6.36378, "heading":2.48953, "vx":0.34847, "vy":-3.16922, "omega":1.00392, "ax":2.40203, "ay":-5.92046, "alpha":-1.90465, "fx":[44.62124,27.87033,38.16576,52.77391], "fy":[-99.47092,-105.48608,-102.31862,-95.54567]}, - {"t":2.11949, "x":0.9665, "y":6.26811, "heading":2.51903, "vx":0.41904, "vy":-3.34316, "omega":0.94797, "ax":3.07603, "ay":-5.51098, "alpha":-3.60194, "fx":[62.51946,28.68368,46.65557,71.43103], "fy":[-88.90274,-105.04711,-98.63737,-82.37388]}, - {"t":2.14887, "x":0.98014, "y":6.16751, "heading":2.54688, "vx":0.50941, "vy":-3.50507, "omega":0.84214, "ax":3.97335, "ay":-4.62908, "alpha":-6.44487, "fx":[90.97075,30.77207,57.60689,90.99249], "fy":[-58.46736,-104.07492,-92.54019,-59.87506]}, - {"t":2.17825, "x":0.99682, "y":6.06254, "heading":2.57162, "vx":0.62615, "vy":-3.64107, "omega":0.6528, "ax":4.84009, "ay":-3.2041, "alpha":-9.32655, "fx":[107.75486,45.99319,72.04929,103.51713], "fy":[-5.11693,-97.62953,-81.60097,-33.65591]}, - {"t":2.20763, "x":1.0173, "y":5.95419, "heading":2.5908, "vx":0.76834, "vy":-3.7352, "omega":0.37879, "ax":5.77186, "ay":-1.69755, "alpha":-7.12479, "fx":[106.30767,87.7812,90.66204,107.95956], "fy":[19.56951,-62.04562,-59.87378,-13.14963]}, - {"t":2.23701, "x":1.04237, "y":5.84372, "heading":2.60193, "vx":0.93792, "vy":-3.78507, "omega":0.16947, "ax":6.26529, "ay":0.08848, "alpha":-3.8098, "fx":[104.223,107.6697,105.92718,108.46309], "fy":[29.5701,-6.85093,-23.46945,6.77021]}, - {"t":2.26639, "x":1.07263, "y":5.73255, "heading":2.60691, "vx":1.12198, "vy":-3.78248, "omega":0.05755, "ax":6.20204, "ay":1.44484, "alpha":-1.33751, "fx":[103.08238,105.63576,107.49176,105.76992], "fy":[33.99225,24.3698,15.10216,24.8411]}, - {"t":2.29577, "x":1.10826, "y":5.62205, "heading":2.6086, "vx":1.3042, "vy":-3.74003, "omega":0.01825, "ax":6.01375, "ay":2.16302, "alpha":-0.25313, "fx":[101.66808,102.22234,102.90421,102.37398], "fy":[38.51098,36.9516,35.06338,36.64348]}, - {"t":2.32515, "x":1.14918, "y":5.51311, "heading":2.60913, "vx":1.48087, "vy":-3.67648, "omega":0.01081, "ax":5.86701, "ay":2.55771, "alpha":0.05958, "fx":[99.96643,99.82729,99.6254,99.76558], "fy":[43.11281,43.44527,43.89819,43.56735]}, - {"t":2.35453, "x":1.19522, "y":5.4062, "heading":2.60945, "vx":1.65324, "vy":-3.60134, "omega":0.01256, "ax":5.70443, "ay":2.9173, "alpha":0.30411, "fx":[98.00704,97.27028,96.04539,96.80029], "fy":[47.68269,49.21354,51.53607,50.05714]}, - {"t":2.3839, "x":1.24625, "y":5.30165, "heading":2.60982, "vx":1.82083, "vy":-3.51563, "omega":0.0215, "ax":5.48866, "ay":3.3123, "alpha":0.68599, "fx":[95.81727,94.13664,90.8876,92.6003], "fy":[52.15489,55.21203,60.37249,57.62565]}, - {"t":2.41328, "x":1.30211, "y":5.1998, "heading":2.61045, "vx":1.98208, "vy":-3.41832, "omega":0.04165, "ax":5.22841, "ay":3.70855, "alpha":1.13325, "fx":[93.39712,90.65581,84.52198,87.15981], "fy":[56.53488,60.94296,69.1594,65.6885]}, - {"t":2.44266, "x":1.3626, "y":5.10097, "heading":2.61168, "vx":2.13569, "vy":-3.30936, "omega":0.07495, "ax":4.95666, "ay":4.06002, "alpha":1.52159, "fx":[90.75953,87.1934,78.12315,81.16925], "fy":[60.80444,65.93842,76.43346,73.06273]}, - {"t":2.47204, "x":1.42748, "y":5.00549, "heading":2.61388, "vx":2.28131, "vy":-3.19008, "omega":0.11965, "ax":4.69592, "ay":4.35499, "alpha":1.79507, "fx":[87.89679,83.87864,72.41812,75.31179], "fy":[64.97506,70.20821,81.95113,79.17412]}, - {"t":2.50142, "x":1.49653, "y":4.91365, "heading":2.61739, "vx":2.41928, "vy":-3.06214, "omega":0.17239, "ax":4.39991, "ay":4.63449, "alpha":2.20621, "fx":[85.1327,80.49827,65.68671,68.04749], "fy":[68.4725,74.02064,87.40633,85.42588]}, - {"t":2.52849, "x":1.56364, "y":4.83245, "heading":2.62206, "vx":2.53839, "vy":-2.93667, "omega":0.23211, "ax":3.99012, "ay":4.95338, "alpha":2.93816, "fx":[82.15346,76.53489,56.14609,56.64872], "fy":[71.89554,78.06598,93.78479,93.27614]}, - {"t":2.55556, "x":1.63382, "y":4.75477, "heading":2.62834, "vx":2.64641, "vy":-2.80257, "omega":0.31166, "ax":3.47048, "ay":5.27188, "alpha":3.89505, "fx":[78.53494,72.02423,44.77802,40.79009], "fy":[75.68118,82.20284,99.68735,101.12121]}, - {"t":2.58264, "x":1.70674, "y":4.68083, "heading":2.63678, "vx":2.74036, "vy":-2.65985, "omega":0.4171, "ax":2.81653, "ay":5.56756, "alpha":5.02448, "fx":[73.3549,66.58437,31.85599,19.83832], "fy":[80.53123,86.62647,104.51892,107.13377]}, - {"t":2.60971, "x":1.78195, "y":4.61086, "heading":2.64807, "vx":2.81661, "vy":-2.50913, "omega":0.55312, "ax":1.9652, "ay":5.86314, "alpha":5.73393, "fx":[61.67203,57.86125,17.70022,-3.52343], "fy":[89.61224,92.63361,107.8096,108.86567]}, - {"t":2.63678, "x":1.85893, "y":4.54508, "heading":2.66305, "vx":2.86981, "vy":-2.3504, "omega":0.70835, "ax":0.80629, "ay":6.17292, "alpha":5.10302, "fx":[34.57326,41.02433,2.11832,-22.85667], "fy":[103.07253,101.16698,109.21674,106.54226]}, - {"t":2.66385, "x":1.93691, "y":4.48371, "heading":2.68222, "vx":2.89164, "vy":-2.18329, "omega":0.8465, "ax":-0.49612, "ay":6.27656, "alpha":3.98983, "fx":[0.95292,17.51036,-14.413,-37.80572], "fy":[108.78078,107.71996,108.27426,102.27508]}, - {"t":2.69092, "x":2.01501, "y":4.42691, "heading":2.70514, "vx":2.87821, "vy":-2.01337, "omega":0.95451, "ax":-1.7072, "ay":6.1198, "alpha":2.90088, "fx":[-27.30378,-8.80732,-30.69417,-49.35042], "fy":[105.45214,108.78062,104.83376,97.31737]}, - {"t":2.718, "x":2.09231, "y":4.37465, "heading":2.73098, "vx":2.83199, "vy":-1.8477, "omega":1.03305, "ax":-2.7073, "ay":5.79128, "alpha":1.88235, "fx":[-47.08486,-33.35238,-45.56915,-58.19518], "fy":[98.39222,103.95765,99.29628,92.38613]}, - {"t":2.74507, "x":2.16798, "y":4.32675, "heading":2.75895, "vx":2.7587, "vy":-1.69092, "omega":1.084, "ax":-3.47942, "ay":5.39013, "alpha":0.97585, "fx":[-60.30637,-53.15768,-58.30828,-64.96346], "fy":[91.03973,95.43251,92.4262,87.8397]}, - {"t":2.77214, "x":2.24139, "y":4.28295, "heading":2.78829, "vx":2.66451, "vy":-1.545, "omega":1.11042, "ax":-4.05604, "ay":4.98398, "alpha":0.21559, "fx":[-69.29801,-67.80031,-68.70081,-70.16929], "fy":[84.52341,85.73695,85.02935,83.81433]}, - {"t":2.79921, "x":2.31204, "y":4.24295, "heading":2.81835, "vx":2.5547, "vy":-1.41007, "omega":1.11626, "ax":-4.48289, "ay":4.60725, "alpha":-0.40331, "fx":[-75.64516,-78.24019,-76.91522,-74.2099], "fy":[78.99931,76.41826,77.72742,80.32675]}, - {"t":2.82628, "x":2.37955, "y":4.20646, "heading":2.84857, "vx":2.43334, "vy":-1.28534, "omega":1.10534, "ax":-4.80078, "ay":4.27214, "alpha":-0.90474, "fx":[-80.30515,-85.65494,-83.29791,-77.38167], "fy":[74.34582,68.09044,70.89788,77.33751]}, - {"t":2.85336, "x":2.44367, "y":4.17323, "heading":2.8785, "vx":2.30338, "vy":-1.16969, "omega":1.08085, "ax":-5.04073, "ay":3.97957, "alpha":-1.31383, "fx":[-83.8499,-90.98693,-88.22612,-79.90237], "fy":[70.39838,60.86411,64.71702,74.78584]}, - {"t":2.88043, "x":2.50418, "y":4.14302, "heading":2.90776, "vx":2.16691, "vy":-1.06195, "omega":1.04528, "ax":-5.2248, "ay":3.7258, "alpha":-1.6512, "fx":[-86.62896,-94.89411,-92.03512,-81.93135], "fy":[67.0128,54.64939,59.22988,72.60726]}, - {"t":2.9075, "x":2.56093, "y":4.11564, "heading":2.93605, "vx":2.02547, "vy":-0.96109, "omega":1.00058, "ax":-5.3684, "ay":3.50575, "alpha":-1.93255, "fx":[-88.86309,-97.81562,-94.99578,-83.58553], "fy":[64.07579,49.30119,54.40889,70.74163]}, - {"t":2.93457, "x":2.61379, "y":4.0909, "heading":2.96314, "vx":1.88013, "vy":-0.86618, "omega":0.94826, "ax":-5.48226, "ay":3.31438, "alpha":-2.16968, "fx":[-90.69644,-100.04251,-97.31669,-84.95119], "fy":[61.50142,44.67629,50.19243,69.13619]}, - {"t":2.96164, "x":2.66268, "y":4.06867, "heading":2.98881, "vx":1.73172, "vy":-0.77646, "omega":0.88952, "ax":-5.57392, "ay":3.14717, "alpha":-2.3715, "fx":[-92.22615,-101.7696,-99.15474,-86.09254], "fy":[59.22511,40.6512,46.50708,67.74616]}, - {"t":2.98872, "x":2.70752, "y":4.0488, "heading":3.01289, "vx":1.58082, "vy":-0.69126, "omega":0.82532, "ax":-5.64874, "ay":3.00029, "alpha":-2.54483, "fx":[-93.51964,-103.12954,-100.62683,-87.05773], "fy":[57.19826,37.12487,43.27912,66.53429]}, - {"t":3.01579, "x":2.74825, "y":4.03119, "heading":3.03524, "vx":1.4279, "vy":-0.61003, "omega":0.75643, "ax":-5.7106, "ay":2.87057, "alpha":-2.69495, "fx":[-94.62492,-104.21448,-101.81994,-87.8832], "fy":[55.38406,34.0163,40.43994,65.46996]}, - {"t":3.04286, "x":2.78481, "y":4.01573, "heading":3.05572, "vx":1.2733, "vy":-0.53232, "omega":0.68347, "ax":-5.76233, "ay":2.75536, "alpha":-2.82605, "fx":[-95.57699,-105.08974,-102.79898,-88.5968], "fy":[53.75443,31.26098,37.92802,64.52812]}, - {"t":3.06993, "x":2.81717, "y":4.00232, "heading":3.07422, "vx":1.11731, "vy":-0.45773, "omega":0.60696, "ax":-5.80605, "ay":2.6525, "alpha":-2.94145, "fx":[-96.40194,-105.80253,-103.61269,-89.21996], "fy":[52.28772,28.80747,35.68932,63.68836]}, - {"t":3.097, "x":2.84529, "y":3.99091, "heading":3.09065, "vx":0.96013, "vy":-0.38592, "omega":0.52733, "ax":-5.84334, "ay":2.56019, "alpha":-3.04385, "fx":[-97.11954,-106.38762,-104.29794,-89.76936], "fy":[50.9671,26.61459,33.67685,62.93403]}, - {"t":3.12407, "x":2.86914, "y":3.9814, "heading":3.10493, "vx":0.80194, "vy":-0.31661, "omega":0.44493, "ax":-5.87542, "ay":2.47697, "alpha":-3.13545, "fx":[-97.74506,-106.87106,-104.88278,-90.25812], "fy":[49.77939,24.64918,31.84994,62.25148]}, - {"t":3.15115, "x":2.8887, "y":3.97373, "heading":3.11697, "vx":0.64288, "vy":-0.24955, "omega":0.36005, "ax":-5.90322, "ay":2.40159, "alpha":-3.21808, "fx":[-98.29047,-107.27265,-105.38875,-90.69666], "fy":[48.71414,22.88439,30.17351,61.62947]}, - {"t":3.17822, "x":2.90394, "y":3.96786, "heading":3.12672, "vx":0.48307, "vy":-0.18454, "omega":0.27293, "ax":-5.92748, "ay":2.33304, "alpha":-3.29325, "fx":[-98.76526,-107.60767,-105.83242,-91.09339], "fy":[47.763,21.29836,28.61732,61.05862]}, - {"t":3.20529, "x":2.91485, "y":3.96372, "heading":3.13411, "vx":0.3226, "vy":-0.12138, "omega":0.18377, "ax":-5.94876, "ay":2.27045, "alpha":-3.36224, "fx":[-99.17706,-107.88805,-106.22665,-91.45521], "fy":[46.91926,19.87323,27.15531,60.53097]}, - {"t":3.23236, "x":2.9214, "y":3.96126, "heading":3.13908, "vx":0.16155, "vy":-0.05991, "omega":0.09275, "ax":-5.96754, "ay":2.2131, "alpha":-3.42613, "fx":[-99.53203,-108.12319,-106.58137,-91.7879], "fy":[46.17744,18.59436,25.76508,60.03961]}, - {"t":3.25943, "x":2.92359, "y":3.96045, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/B_LEFT_PATH3.traj b/src/main/deploy/choreo/B_LEFT_PATH3.traj deleted file mode 100644 index 5a0f2ef1..00000000 --- a/src/main/deploy/choreo/B_LEFT_PATH3.traj +++ /dev/null @@ -1,96 +0,0 @@ -{ - "name":"B_LEFT_PATH3", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":3.17155122756958, "y":3.923255681991577, "heading":3.141592653589793, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.8201370239257812, "y":6.117753982543945, "heading":0.0, "intervals":34, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":0.8395776748657227, "y":7.055506706237793, "heading":2.179485408307156, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"3.17155122756958 m", "val":3.17155122756958}, "y":{"exp":"3.923255681991577 m", "val":3.923255681991577}, "heading":{"exp":"180 deg", "val":3.141592653589793}, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.8201370239257812 m", "val":1.8201370239257812}, "y":{"exp":"6.117753982543945 m", "val":6.117753982543945}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":34, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"0.8395776748657227 m", "val":0.8395776748657227}, "y":{"exp":"7.055506706237793 m", "val":7.055506706237793}, "heading":{"exp":"2.1794854083071558 rad", "val":2.179485408307156}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,0.96245,1.61644], - "samples":[ - {"t":0.0, "x":3.17155, "y":3.92326, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.19148, "ay":5.49712, "alpha":-3.58356, "fx":[-59.86321,-76.4734,-47.33505,-33.47278], "fy":[91.96744,78.6493,98.91474,104.48636]}, - {"t":0.02917, "x":3.17019, "y":3.92559, "heading":3.14159, "vx":-0.09308, "vy":0.16033, "omega":-0.10452, "ax":-3.19293, "ay":5.49902, "alpha":-3.52859, "fx":[-59.80029,-76.15831,-47.49117,-33.79356], "fy":[92.00002,78.94275,98.82922,104.37492]}, - {"t":0.05833, "x":3.16612, "y":3.93261, "heading":3.13854, "vx":-0.1862, "vy":0.32071, "omega":-0.20743, "ax":-3.19457, "ay":5.50112, "alpha":-3.46603, "fx":[-59.67738,-75.80711,-47.74909,-34.12099], "fy":[92.0705,79.26732,98.69305,104.25917]}, - {"t":0.0875, "x":3.15933, "y":3.9443, "heading":3.13249, "vx":-0.27937, "vy":0.48115, "omega":-0.30852, "ax":-3.19638, "ay":5.50345, "alpha":-3.39507, "fx":[-59.49631,-75.41354,-48.10343,-34.46492], "fy":[92.17719,79.62788,98.50772,104.13561]}, - {"t":0.11666, "x":3.14982, "y":3.96067, "heading":3.1235, "vx":-0.3726, "vy":0.64166, "omega":-0.40753, "ax":-3.19838, "ay":5.50602, "alpha":-3.31467, "fx":[-59.25919,-74.96936,-48.54798,-34.8378], "fy":[92.31804,80.03078,98.27475,103.99964]}, - {"t":0.14583, "x":3.1376, "y":3.98173, "heading":3.11161, "vx":-0.46588, "vy":0.80224, "omega":-0.50421, "ax":-3.20057, "ay":5.50885, "alpha":-3.22348, "fx":[-58.96854,-74.46389,-49.07533,-35.25531], "fy":[92.49057,80.48412,97.99606,103.84532]}, - {"t":0.17499, "x":3.12265, "y":4.00747, "heading":3.09691, "vx":-0.55922, "vy":0.96291, "omega":-0.59822, "ax":-3.20294, "ay":5.51198, "alpha":-3.1197, "fx":[-58.62743,-73.88333,-49.67647,-35.73724], "fy":[92.69177,80.99807,97.67421,103.66482]}, - {"t":0.20416, "x":3.10498, "y":4.0379, "heading":3.07946, "vx":-0.65264, "vy":1.12367, "omega":-0.68921, "ax":-3.2055, "ay":5.51544, "alpha":-3.00089, "fx":[-58.23972,-73.20978,-50.34019,-36.30878], "fy":[92.91798,81.58541,97.31281,103.44781]}, - {"t":0.23332, "x":3.08458, "y":4.07302, "heading":3.05936, "vx":-0.74613, "vy":1.28453, "omega":-0.77673, "ax":-3.20824, "ay":5.51926, "alpha":-2.86363, "fx":[-57.81044,-72.41962,-51.05244,-37.00238], "fy":[93.16462,82.26236,96.91708,103.18033]}, - {"t":0.26249, "x":3.06145, "y":4.11283, "heading":3.0367, "vx":-0.8397, "vy":1.4455, "omega":-0.86025, "ax":-3.21115, "ay":5.52351, "alpha":-2.7031, "fx":[-57.34623,-71.48106,-51.79542,-37.86047], "fy":[93.42593,83.04981,96.49445,102.84306]}, - {"t":0.29165, "x":3.0356, "y":4.15734, "heading":3.01161, "vx":-0.93335, "vy":1.60659, "omega":-0.93908, "ax":-3.21423, "ay":5.52822, "alpha":-2.51233, "fx":[-56.85627,-70.34996,-52.54637,-38.93976], "fy":[93.69432,83.9753,96.05548,102.40849]}, - {"t":0.32082, "x":3.00701, "y":4.20654, "heading":2.98423, "vx":-1.0271, "vy":1.76782, "omega":-1.01236, "ax":-3.21743, "ay":5.53341, "alpha":-2.28102, "fx":[-56.35352,-68.96285,-53.27593,-40.31787], "fy":[93.95951,85.07624,95.61501,101.836]}, - {"t":0.34998, "x":2.97569, "y":4.26046, "heading":2.9547, "vx":-1.12093, "vy":1.92921, "omega":-1.07888, "ax":-3.22068, "ay":5.53902, "alpha":-1.99354, "fx":[-55.85723,-67.22424,-53.94564,-42.10431], "fy":[94.20674,86.40508,95.19373,101.06307]}, - {"t":0.37915, "x":2.94162, "y":4.31908, "heading":2.92323, "vx":-1.21486, "vy":2.09075, "omega":-1.13703, "ax":-3.2238, "ay":5.54478, "alpha":-1.62536, "fx":[-55.39749,-64.98281,-54.50401,-44.45903], "fy":[94.41337,88.0382,94.82053,99.98857]}, - {"t":0.40831, "x":2.90482, "y":4.38241, "heading":2.89007, "vx":-1.30889, "vy":2.25247, "omega":-1.18443, "ax":-3.22628, "ay":5.54988, "alpha":-1.13635, "fx":[-55.02483,-61.98278,-54.88,-47.62505], "fy":[94.54154,90.09092,94.53583,98.4389]}, - {"t":0.43748, "x":2.86527, "y":4.45047, "heading":2.85553, "vx":-1.40298, "vy":2.41433, "omega":-1.21757, "ax":-3.22681, "ay":5.55202, "alpha":-0.45701, "fx":[-54.83295,-57.75645,-54.97122,-51.98791], "fy":[94.52013,92.74244,94.39706,96.09374]}, - {"t":0.46664, "x":2.82298, "y":4.52324, "heading":2.82002, "vx":-1.49709, "vy":2.57626, "omega":-1.2309, "ax":-3.2215, "ay":5.54473, "alpha":0.54208, "fx":[-55.02233,-51.35944,-54.62161,-58.18387], "fy":[94.19217,96.26874,94.48747,92.30837]}, - {"t":0.49581, "x":2.77795, "y":4.60074, "heading":2.78412, "vx":-1.59105, "vy":2.73797, "omega":-1.21509, "ax":-3.19834, "ay":5.50723, "alpha":2.12502, "fx":[-56.12913,-40.63544,-53.57594,-67.27086], "fy":[93.11388,101.01365,94.93096,85.64695]}, - {"t":0.52497, "x":2.73019, "y":4.68293, "heading":2.74868, "vx":-1.68433, "vy":2.89859, "omega":-1.15311, "ax":-3.12202, "ay":5.35654, "alpha":4.88832, "fx":[-60.29168,-20.02168,-51.38451,-80.72089], "fy":[89.30581,106.61057,95.91293,72.62346]}, - {"t":0.55414, "x":2.67973, "y":4.76975, "heading":2.71505, "vx":-1.77538, "vy":3.05482, "omega":-1.01054, "ax":-3.08399, "ay":4.46001, "alpha":10.85039, "fx":[-86.07114,20.87639,-47.37991,-97.25656], "fy":[53.01761,105.72271,97.58762,47.12611]}, - {"t":0.58331, "x":2.62664, "y":4.86074, "heading":2.68558, "vx":-1.86533, "vy":3.1849, "omega":-0.69409, "ax":-2.96181, "ay":4.09056, "alpha":12.45209, "fx":[-86.53847,26.41422,-44.86379,-96.52996], "fy":[32.61301,102.71181,97.56885,45.42365]}, - {"t":0.61247, "x":2.57098, "y":4.95537, "heading":2.66533, "vx":-1.95171, "vy":3.3042, "omega":-0.33092, "ax":-2.11594, "ay":3.84617, "alpha":11.06626, "fx":[-44.69331,21.26689,-38.18573,-82.35401], "fy":[34.95504,89.86986,90.19962,46.66472]}, - {"t":0.64164, "x":2.51316, "y":5.05337, "heading":2.65568, "vx":-2.01342, "vy":3.41637, "omega":-0.00817, "ax":0.32194, "ay":0.24717, "alpha":0.13057, "fx":[5.61926,5.93296,5.33323,5.019], "fy":[3.74531,4.34413,4.6633,4.06451]}, - {"t":0.6708, "x":2.45457, "y":5.15312, "heading":2.65544, "vx":-2.00403, "vy":3.42358, "omega":-0.00436, "ax":0.10651, "ay":0.06241, "alpha":0.00027, "fx":[1.81193,1.81259,1.81134,1.81069], "fy":[1.06067,1.06192,1.06258,1.06133]}, - {"t":0.69997, "x":2.39617, "y":5.253, "heading":2.65532, "vx":-2.00093, "vy":3.4254, "omega":-0.00435, "ax":-0.04794, "ay":-0.02802, "alpha":-0.00001, "fx":[-0.81539,-0.81541,-0.81538,-0.81537], "fy":[-0.47652,-0.47655,-0.47656,-0.47654]}, - {"t":0.72913, "x":2.33779, "y":5.35289, "heading":2.65519, "vx":-2.00233, "vy":3.42458, "omega":-0.00436, "ax":-0.2414, "ay":-0.14149, "alpha":-0.00003, "fx":[-4.10622,-4.1063,-4.10615,-4.10607], "fy":[-2.40655,-2.40669,-2.40677,-2.40662]}, - {"t":0.7583, "x":2.27929, "y":5.4527, "heading":2.65506, "vx":-2.00937, "vy":3.42046, "omega":-0.00436, "ax":-0.62549, "ay":-0.36974, "alpha":-0.0001, "fx":[-10.63954,-10.63978,-10.63931,-10.63907], "fy":[-6.28876,-6.28923,-6.28948,-6.28901]}, - {"t":0.78746, "x":2.22042, "y":5.55231, "heading":2.65493, "vx":-2.02761, "vy":3.40967, "omega":-0.00436, "ax":-1.4308, "ay":-0.86295, "alpha":-0.00034, "fx":[-24.33796,-24.33865,-24.33712,-24.33642], "fy":[-14.67735,-14.67889,-14.67982,-14.67828]}, - {"t":0.81663, "x":2.16068, "y":5.65138, "heading":2.65481, "vx":-2.06934, "vy":3.38451, "omega":-0.00437, "ax":-2.70335, "ay":-1.69732, "alpha":-0.00094, "fx":[-45.98481,-45.9859,-45.98155,-45.98046], "fy":[-28.86714,-28.87141,-28.87487,-28.87061]}, - {"t":0.84579, "x":2.09917, "y":5.74937, "heading":2.65468, "vx":-2.14818, "vy":3.335, "omega":-0.0044, "ax":-3.81765, "ay":-2.5526, "alpha":-0.00199, "fx":[-64.94217,-64.9418,-64.93218,-64.93254], "fy":[-43.40969,-43.41833,-43.42836,-43.41973]}, - {"t":0.87496, "x":2.0349, "y":5.84555, "heading":2.65455, "vx":-2.25953, "vy":3.26056, "omega":-0.00445, "ax":-4.38346, "ay":-3.17103, "alpha":-0.00351, "fx":[-74.5726,-74.56852,-74.55024,-74.55433], "fy":[-53.9207,-53.93468,-53.95584,-53.94187]}, - {"t":0.90412, "x":1.96713, "y":5.9393, "heading":2.65442, "vx":-2.38737, "vy":3.16807, "omega":-0.00456, "ax":-4.57489, "ay":-3.61212, "alpha":-0.01587, "fx":[-77.87562,-77.8492,-77.75958,-77.78597], "fy":[-61.36124,-61.41733,-61.52083,-61.46488]}, - {"t":0.93329, "x":1.89556, "y":6.03016, "heading":2.65429, "vx":-2.5208, "vy":3.06272, "omega":-0.00502, "ax":-4.47579, "ay":-4.07045, "alpha":-0.43552, "fx":[-77.90965,-77.1107,-74.37999,-75.12746], "fy":[-67.14082,-68.44105,-71.27159,-70.09501]}, - {"t":0.96245, "x":1.82014, "y":6.11775, "heading":2.65414, "vx":-2.65134, "vy":2.94401, "omega":-0.01772, "ax":-2.16908, "ay":-5.34462, "alpha":-6.74418, "fx":[-68.75699,-61.94732,-19.64209,2.76486], "fy":[-74.05138,-84.58305,-103.15674,-101.85087]}, - {"t":0.98761, "x":1.75276, "y":6.19012, "heading":2.6537, "vx":-2.7059, "vy":2.80957, "omega":-0.18736, "ax":0.50709, "ay":-5.17312, "alpha":-11.23804, "fx":[-26.05789,-46.87782,24.35018,83.08737], "fy":[-86.36251,-95.4847,-104.41698,-65.70883]}, - {"t":1.01276, "x":1.68486, "y":6.25915, "heading":2.64898, "vx":-2.69314, "vy":2.67945, "omega":-0.47004, "ax":2.78983, "ay":-4.16998, "alpha":-12.99986, "fx":[88.92624,-34.80021,39.90091,95.78998], "fy":[-32.73474,-101.43201,-100.50901,-49.04474]}, - {"t":1.03791, "x":1.618, "y":6.32523, "heading":2.63716, "vx":-2.62297, "vy":2.57456, "omega":-0.79703, "ax":3.48456, "ay":-4.73743, "alpha":-7.9995, "fx":[85.8237,7.44859,51.8335,91.97969], "fy":[-62.34646,-107.51853,-95.34125,-57.12287]}, - {"t":1.06307, "x":1.55312, "y":6.38849, "heading":2.61711, "vx":-2.53532, "vy":2.4554, "omega":-0.99824, "ax":3.97749, "ay":-4.82015, "alpha":-4.21805, "fx":[80.4872,43.20933,61.1002,85.82682], "fy":[-72.03871,-99.35456,-89.96137,-66.60285]}, - {"t":1.08822, "x":1.49061, "y":6.44872, "heading":2.592, "vx":-2.43527, "vy":2.33416, "omega":-1.10434, "ax":4.237, "ay":-4.74922, "alpha":-2.10129, "fx":[78.20037,61.17476,67.60872,81.29667], "fy":[-75.43459,-89.89241,-85.39172,-72.413]}, - {"t":1.11337, "x":1.4307, "y":6.50593, "heading":2.56423, "vx":-2.3287, "vy":2.2147, "omega":-1.15719, "ax":4.37894, "ay":-4.67257, "alpha":-0.80532, "fx":[76.8001,70.68397,72.41951,78.03463], "fy":[-77.29855,-82.95089,-81.52197,-76.1446]}, - {"t":1.13853, "x":1.37351, "y":6.56016, "heading":2.53512, "vx":-2.21855, "vy":2.09717, "omega":-1.17745, "ax":4.46471, "ay":-4.60862, "alpha":0.06557, "fx":[75.75476,76.22914,76.13375,75.65606], "fy":[-78.57803,-78.11673,-78.20364,-78.66706]}, - {"t":1.16368, "x":1.31912, "y":6.61146, "heading":2.5055, "vx":-2.10625, "vy":1.98124, "omega":-1.1758, "ax":4.52099, "ay":-4.55694, "alpha":0.69392, "fx":[74.88561,79.7223,79.09786,73.89704], "fy":[-79.57242,-74.71789,-75.32026,-80.43827]}, - {"t":1.18884, "x":1.26757, "y":6.65985, "heading":2.47593, "vx":-1.99253, "vy":1.86662, "omega":-1.15835, "ax":4.56025, "ay":-4.5149, "alpha":1.17125, "fx":[74.11949,82.0481,81.52249,72.58408], "fy":[-80.40249,-72.28492,-72.78729,-81.71416]}, - {"t":1.21399, "x":1.21889, "y":6.70537, "heading":2.44679, "vx":-1.87782, "vy":1.75305, "omega":-1.12889, "ax":4.58891, "ay":-4.48026, "alpha":1.54773, "fx":[73.42262,83.658,83.54272,71.60103], "fy":[-81.12491,-70.51602,-70.54374,-82.64731]}, - {"t":1.23914, "x":1.17311, "y":6.74805, "heading":2.41839, "vx":-1.7624, "vy":1.64036, "omega":-1.08996, "ax":4.61057, "ay":-4.45133, "alpha":1.85299, "fx":[72.77808,84.80283,85.24944,70.86753], "fy":[-81.76923,-69.2154,-68.54474,-83.33417]}, - {"t":1.2643, "x":1.13024, "y":6.7879, "heading":2.39098, "vx":-1.64643, "vy":1.52839, "omega":-1.04335, "ax":4.62738, "ay":-4.42688, "alpha":2.10567, "fx":[72.17699,85.63209,86.70652,70.32593], "fy":[-82.35214,-68.25232,-66.75627,-83.83895]}, - {"t":1.28945, "x":1.09029, "y":6.82495, "heading":2.36473, "vx":-1.53003, "vy":1.41704, "omega":-0.99038, "ax":4.64071, "ay":-4.40599, "alpha":2.31816, "fx":[71.61455,86.24021,87.96059,69.93338], "fy":[-82.88371,-67.5366,-65.15172,-84.20646]}, - {"t":1.3146, "x":1.05327, "y":6.8592, "heading":2.33982, "vx":-1.4133, "vy":1.30622, "omega":-0.93207, "ax":4.65148, "ay":-4.38798, "alpha":2.49907, "fx":[71.0881,86.68978,89.0468,69.65693], "fy":[-83.37037,-67.00419,-63.70954,-84.46934]}, - {"t":1.33976, "x":1.01919, "y":6.89067, "heading":2.31638, "vx":-1.2963, "vy":1.19584, "omega":-0.86921, "ax":4.66032, "ay":-4.37234, "alpha":2.65463, "fx":[70.59614,87.02404,89.99243,69.47051], "fy":[-83.81649,-66.60828,-62.41175,-84.65225]}, - {"t":1.36491, "x":0.98806, "y":6.91936, "heading":2.29451, "vx":-1.17908, "vy":1.08587, "omega":-0.80244, "ax":4.66768, "ay":-4.35864, "alpha":2.78954, "fx":[70.13784,87.2739,90.81912,69.35294], "fy":[-84.22521,-66.31391,-61.24305,-84.7745]}, - {"t":1.39006, "x":0.95988, "y":6.9453, "heading":2.27433, "vx":-1.06167, "vy":0.97623, "omega":-0.73227, "ax":4.67389, "ay":-4.34656, "alpha":2.90741, "fx":[69.71269,87.46214,91.54435,69.28663], "fy":[-84.59886,-66.09435,-60.19009,-84.85165]}, - {"t":1.41522, "x":0.93465, "y":6.96848, "heading":2.25591, "vx":-0.9441, "vy":0.8669, "omega":-0.65914, "ax":4.67917, "ay":-4.33584, "alpha":3.01112, "fx":[69.3204,87.60598,92.18249,69.25676], "fy":[-84.93929,-65.92886,-59.24115,-84.89654]}, - {"t":1.44037, "x":0.91238, "y":6.98891, "heading":2.23933, "vx":-0.82641, "vy":0.75784, "omega":-0.5834, "ax":4.68373, "ay":-4.32628, "alpha":3.10299, "fx":[68.96076,87.71873,92.74544,69.25065], "fy":[-85.24799,-65.80104,-58.38583,-84.91999]}, - {"t":1.46552, "x":0.89308, "y":7.0066, "heading":2.22466, "vx":-0.7086, "vy":0.64902, "omega":-0.50535, "ax":4.68769, "ay":-4.31768, "alpha":3.18495, "fx":[68.63364,87.81088,93.24317,69.25737], "fy":[-85.5262,-65.69777,-57.61485,-84.93127]}, - {"t":1.49068, "x":0.87674, "y":7.02156, "heading":2.21195, "vx":-0.59068, "vy":0.54041, "omega":-0.42524, "ax":4.69116, "ay":-4.30992, "alpha":3.25859, "fx":[68.33895,87.89082,93.68404,69.26743], "fy":[-85.77494,-65.60842,-56.91999,-84.93837]}, - {"t":1.51583, "x":0.86336, "y":7.03379, "heading":2.20125, "vx":-0.47269, "vy":0.432, "omega":-0.34327, "ax":4.69422, "ay":-4.30286, "alpha":3.32525, "fx":[68.07665,87.96535,94.07511,69.27257], "fy":[-85.99508,-65.52428,-56.29398,-84.94822]}, - {"t":1.54098, "x":0.85296, "y":7.0433, "heading":2.19261, "vx":-0.35461, "vy":0.32377, "omega":-0.25963, "ax":4.69694, "ay":-4.29641, "alpha":3.38607, "fx":[67.84673,88.04005,94.42231,69.26559], "fy":[-86.18731,-65.43814,-55.73039,-84.96687]}, - {"t":1.56614, "x":0.84553, "y":7.05008, "heading":2.18608, "vx":-0.23647, "vy":0.2157, "omega":-0.17446, "ax":4.69937, "ay":-4.29048, "alpha":3.442, "fx":[67.64927,88.11954,94.73063,69.24024], "fy":[-86.35217,-65.34399,-55.22369,-84.99953]}, - {"t":1.59129, "x":0.84106, "y":7.05415, "heading":2.1817, "vx":-0.11826, "vy":0.10778, "omega":-0.08788, "ax":4.70154, "ay":-4.285, "alpha":3.49387, "fx":[67.48441,88.20765,95.00422,69.19111], "fy":[-86.49004,-65.23677,-54.76911,-85.0507]}, - {"t":1.61644, "x":0.83958, "y":7.05551, "heading":2.17949, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/B_RIGHT_PATH1.traj b/src/main/deploy/choreo/B_RIGHT_PATH1.traj deleted file mode 100644 index 16e22f61..00000000 --- a/src/main/deploy/choreo/B_RIGHT_PATH1.traj +++ /dev/null @@ -1,108 +0,0 @@ -{ - "name":"B_RIGHT_PATH1", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":7.163801670074463, "y":0.7438099258422852, "heading":-1.5707963267948966, "intervals":48, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":3.046499013900757, "y":2.6794681549072266, "heading":0.0, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":2.638746500015259, "y":3.6656603813171382, "heading":-3.141592653589793, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"7.163801670074463 m", "val":7.163801670074463}, "y":{"exp":"(8.0518 - 7.307990074157715) m", "val":0.7438099258422852}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":48, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"3.046499013900757 m", "val":3.046499013900757}, "y":{"exp":"2.6794681549072266 m", "val":2.6794681549072266}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"2.638746500015259 m", "val":2.638746500015259}, "y":{"exp":"3.6656603813171387 m", "val":3.6656603813171382}, "heading":{"exp":"-3.141592653589793 rad", "val":-3.141592653589793}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.49581,2.08565], - "samples":[ - {"t":0.0, "x":7.1638, "y":0.74381, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.91906, "ay":2.02549, "alpha":-5.2346, "fx":[-109.44437,-108.82681,-85.4664,-98.98863], "fy":[8.09554,13.52768,68.78251,47.40598]}, - {"t":0.03324, "x":7.16053, "y":0.74493, "heading":-1.5708, "vx":-0.19675, "vy":0.06733, "omega":-0.174, "ax":-5.92525, "ay":2.0302, "alpha":-5.12574, "fx":[-109.40072,-108.7357,-85.95208,-99.0589], "fy":[8.56872,14.16114,68.15976,47.24272]}, - {"t":0.06648, "x":7.15072, "y":0.74829, "heading":-1.57658, "vx":-0.39371, "vy":0.13481, "omega":-0.34438, "ax":-5.93159, "ay":2.03527, "alpha":-5.01178, "fx":[-109.33991,-108.66225,-86.50336,-99.0732], "fy":[9.21224,14.63014,67.44125,47.19406]}, - {"t":0.09972, "x":7.13435, "y":0.75389, "heading":-1.58803, "vx":-0.59087, "vy":0.20246, "omega":-0.51097, "ax":-5.93829, "ay":2.0408, "alpha":-4.88832, "fx":[-109.25836,-108.60265,-87.13411,-99.0393], "fy":[10.02962,14.97663,66.60367,47.24356]}, - {"t":0.13296, "x":7.11143, "y":0.76175, "heading":-1.60501, "vx":-0.78826, "vy":0.2703, "omega":-0.67346, "ax":-5.94558, "ay":2.04687, "alpha":-4.74992, "fx":[-109.15119,-108.55044,-87.86225,-98.96672], "fy":[11.02751,15.25352,65.61561,47.37023]}, - {"t":0.1662, "x":7.08195, "y":0.77187, "heading":-1.6274, "vx":-0.9859, "vy":0.33834, "omega":-0.83135, "ax":-5.95374, "ay":2.05361, "alpha":-4.58974, "fx":[-109.01181,-108.49657,-88.70936,-98.86779], "fy":[12.21615,15.52575,64.43644,47.5467]}, - {"t":0.19944, "x":7.04589, "y":0.78425, "heading":-1.65503, "vx":-1.1838, "vy":0.4066, "omega":-0.98391, "ax":-5.96306, "ay":2.06108, "alpha":-4.39918, "fx":[-108.83149,-108.42912,-89.69996,-98.75914], "fy":[13.61022,15.87224,63.01482,47.73649]}, - {"t":0.23268, "x":7.00324, "y":0.7989, "heading":-1.68774, "vx":-1.38201, "vy":0.47511, "omega":-1.13014, "ax":-5.97386, "ay":2.06935, "alpha":-4.16734, "fx":[-108.59842,-108.33227,-90.8602,-98.66403], "fy":[15.2305,16.38901,61.28696,47.88964]}, - {"t":0.26592, "x":6.954, "y":0.81584, "heading":-1.7253, "vx":-1.58059, "vy":0.5439, "omega":-1.26867, "ax":-5.98646, "ay":2.07839, "alpha":-3.88027, "fx":[-108.29624,-108.18395,-92.21563,-98.61583], "fy":[17.10697,17.19442,59.17474,47.93521]}, - {"t":0.29916, "x":6.89816, "y":0.83507, "heading":-1.76747, "vx":-1.77958, "vy":0.61298, "omega":-1.39765, "ax":-6.00103, "ay":2.08814, "alpha":-3.51976, "fx":[-107.90117,-107.95082,-93.78748,-98.66366], "fy":[19.28483,18.43811,56.5838,47.76817]}, - {"t":0.3324, "x":6.83569, "y":0.8566, "heading":-1.81393, "vx":-1.97905, "vy":0.68239, "omega":-1.51464, "ax":-6.0175, "ay":2.0985, "alpha":-3.06089, "fx":[-107.37616,-107.57837,-95.58728,-98.88169], "fy":[21.83683,20.31688,53.40188,47.22421]}, - {"t":0.36564, "x":6.76658, "y":0.88044, "heading":-1.86428, "vx":-2.17908, "vy":0.75215, "omega":-1.61639, "ax":-6.03512, "ay":2.10936, "alpha":-2.46671, "fx":[-106.65788,-106.9704,-97.60925,-99.38524], "fy":[24.88982,23.10363,49.49757,46.02775]}, - {"t":0.39888, "x":6.69081, "y":0.9066, "heading":-1.91801, "vx":-2.37968, "vy":0.82227, "omega":-1.69838, "ax":-6.05164, "ay":2.12055, "alpha":-1.67541, "fx":[-105.62334,-105.9444,-99.82054,-100.35856], "fy":[28.68757,27.20092,44.7188,43.67269]}, - {"t":0.43212, "x":6.60837, "y":0.93511, "heading":-1.97446, "vx":-2.58084, "vy":0.89275, "omega":-1.75407, "ax":-6.06068, "ay":2.13116, "alpha":-0.5659, "fx":[-103.98977,-104.12688,-102.14968,-102.09573], "fy":[33.76043,33.24077,38.88895,39.11162]}, - {"t":0.46536, "x":6.51923, "y":0.96596, "heading":-2.03277, "vx":-2.7823, "vy":0.96359, "omega":-1.77288, "ax":-6.04167, "ay":2.13613, "alpha":1.14973, "fx":[-100.92762,-100.68697,-104.47251,-104.98123], "fy":[41.48107,42.25891,31.79438,29.80528]}, - {"t":0.4986, "x":6.42341, "y":0.99917, "heading":-2.0917, "vx":-2.98313, "vy":1.0346, "omega":-1.73467, "ax":-5.90007, "ay":2.11399, "alpha":4.36328, "fx":[-92.79076,-93.6278,-106.58878,-108.42653], "fy":[56.47576,55.88316,23.15746,8.31723]}, - {"t":0.53184, "x":6.32099, "y":1.03473, "heading":-2.14936, "vx":-3.17925, "vy":1.10487, "omega":-1.58963, "ax":-4.92498, "ay":2.05406, "alpha":12.67932, "fx":[-49.09744,-78.88543,-108.11334,-98.99358], "fy":[95.06649,74.93749,13.04843,-43.29661]}, - {"t":0.56508, "x":6.21259, "y":1.07259, "heading":-2.2022, "vx":-3.34295, "vy":1.17315, "omega":-1.16817, "ax":-4.63738, "ay":2.0277, "alpha":14.0127, "fx":[-37.99985,-75.31908,-107.65188,-94.55112], "fy":[97.7375,77.77164,13.10862,-50.65512]}, - {"t":0.59832, "x":6.09891, "y":1.11271, "heading":-2.24103, "vx":-3.4971, "vy":1.24055, "omega":-0.70238, "ax":-4.59528, "ay":1.93443, "alpha":13.50275, "fx":[-40.1392,-73.84315,-106.22639,-92.44896], "fy":[90.80283,76.97225,13.60339,-49.76235]}, - {"t":0.63156, "x":5.98013, "y":1.15501, "heading":-2.26438, "vx":-3.64985, "vy":1.30485, "omega":-0.25355, "ax":-2.83012, "ay":0.20564, "alpha":7.41891, "fx":[-23.99632,-50.982,-69.15928,-48.42073], "fy":[8.55681,34.09739,0.50103,-29.16388]}, - {"t":0.6648, "x":5.85724, "y":1.1985, "heading":-2.27281, "vx":-3.74392, "vy":1.31168, "omega":-0.00694, "ax":-0.13155, "ay":-0.35444, "alpha":0.02058, "fx":[-2.16216,-2.24415,-2.3131,-2.23118], "fy":[-6.0227,-5.95371,-6.03501,-6.10396]}, - {"t":0.69804, "x":5.73272, "y":1.2419, "heading":-2.27304, "vx":-3.7483, "vy":1.2999, "omega":-0.00626, "ax":-0.04325, "ay":-0.12488, "alpha":0.00009, "fx":[-0.73533,-0.73571,-0.73601,-0.73564], "fy":[-2.12406,-2.12375,-2.12413,-2.12444]}, - {"t":0.73128, "x":5.6081, "y":1.28504, "heading":-2.27325, "vx":-3.74973, "vy":1.29575, "omega":-0.00626, "ax":-0.01502, "ay":-0.04348, "alpha":0.00002, "fx":[-0.25535,-0.25545,-0.25553,-0.25543], "fy":[-0.73953,-0.73945,-0.73955,-0.73963]}, - {"t":0.76452, "x":5.48345, "y":1.32809, "heading":-2.27345, "vx":-3.75023, "vy":1.2943, "omega":-0.00625, "ax":-0.00515, "ay":-0.01492, "alpha":0.00001, "fx":[-0.08753,-0.08758,-0.08762,-0.08757], "fy":[-0.25374,-0.2537,-0.25375,-0.25379]}, - {"t":0.79776, "x":5.35879, "y":1.3711, "heading":-2.27366, "vx":-3.7504, "vy":1.29381, "omega":-0.00625, "ax":-0.00156, "ay":-0.00451, "alpha":0.00001, "fx":[-0.02644,-0.02647,-0.0265,-0.02647], "fy":[-0.0767,-0.07668,-0.07671,-0.07674]}, - {"t":0.83101, "x":5.23412, "y":1.41411, "heading":-2.27387, "vx":-3.75046, "vy":1.29366, "omega":-0.00625, "ax":0.00014, "ay":0.00041, "alpha":0.00001, "fx":[0.00242,0.0024,0.00237,0.0024], "fy":[0.00698,0.007,0.00697,0.00695]}, - {"t":0.86425, "x":5.10946, "y":1.45711, "heading":-2.27408, "vx":-3.75045, "vy":1.29367, "omega":-0.00625, "ax":0.00201, "ay":0.00583, "alpha":0.0, "fx":[0.03421,0.03419,0.03418,0.0342], "fy":[0.09914,0.09915,0.09914,0.09912]}, - {"t":0.89749, "x":4.98479, "y":1.50011, "heading":-2.27428, "vx":-3.75038, "vy":1.29387, "omega":-0.00625, "ax":0.00633, "ay":0.01834, "alpha":0.0, "fx":[0.10766,0.10766,0.10766,0.10766], "fy":[0.31196,0.31196,0.31196,0.31196]}, - {"t":0.93073, "x":4.86013, "y":1.54313, "heading":-2.27449, "vx":-3.75017, "vy":1.29448, "omega":-0.00625, "ax":0.01837, "ay":0.05317, "alpha":-0.00001, "fx":[0.31237,0.31243,0.31248,0.31242], "fy":[0.90433,0.90428,0.90434,0.90439]}, - {"t":0.96397, "x":4.73549, "y":1.58619, "heading":-2.2747, "vx":-3.74956, "vy":1.29624, "omega":-0.00625, "ax":0.05287, "ay":0.15257, "alpha":-0.00006, "fx":[0.89906,0.89929,0.89948,0.89925], "fy":[2.59517,2.59498,2.5952,2.59539]}, - {"t":0.99721, "x":4.61088, "y":1.62936, "heading":-2.27491, "vx":-3.74781, "vy":1.30131, "omega":-0.00626, "ax":0.15211, "ay":0.43526, "alpha":-0.00019, "fx":[2.58657,2.58734,2.58799,2.58722], "fy":[7.40359,7.40294,7.4037,7.40434]}, - {"t":1.03045, "x":4.48639, "y":1.67286, "heading":-2.27512, "vx":-3.74275, "vy":1.31578, "omega":-0.00626, "ax":0.42936, "ay":1.20037, "alpha":-0.00066, "fx":[7.3008,7.30352,7.30573,7.303], "fy":[20.41775,20.41555,20.41801,20.42021]}, - {"t":1.06369, "x":4.36221, "y":1.71726, "heading":-2.27532, "vx":-3.72848, "vy":1.35568, "omega":-0.00628, "ax":1.04535, "ay":2.76624, "alpha":-0.00196, "fx":[17.77296,17.78284,17.78939,17.77951], "fy":[47.0535,47.04687,47.05249,47.05911]}, - {"t":1.09693, "x":4.23886, "y":1.76385, "heading":-2.27553, "vx":-3.69373, "vy":1.44763, "omega":-0.00635, "ax":1.7882, "ay":4.30912, "alpha":-0.00419, "fx":[30.39619,30.42407,30.43723,30.40935], "fy":[73.30179,73.28677,73.29203,73.30705]}, - {"t":1.13017, "x":4.11706, "y":1.81435, "heading":-2.27574, "vx":-3.63429, "vy":1.59087, "omega":-0.00649, "ax":2.34931, "ay":5.03794, "alpha":-0.00689, "fx":[39.92499,39.9784,39.99716,39.94377], "fy":[85.70714,85.67952,85.68065,85.70826]}, - {"t":1.16341, "x":3.99756, "y":1.87002, "heading":-2.27596, "vx":-3.5562, "vy":1.75833, "omega":-0.00672, "ax":2.7761, "ay":5.27015, "alpha":-0.01074, "fx":[47.16465,47.25294,47.27665,47.18844], "fy":[89.66962,89.62107,89.61776,89.66629]}, - {"t":1.19665, "x":3.88088, "y":1.93137, "heading":-2.27618, "vx":-3.46392, "vy":1.93351, "omega":-0.00707, "ax":3.14581, "ay":5.28209, "alpha":-0.0432, "fx":[53.29281,53.65385,53.72524,53.36567], "fy":[89.96571,89.74672,89.72824,89.94663]}, - {"t":1.22989, "x":3.76748, "y":1.99856, "heading":-2.27642, "vx":-3.35935, "vy":2.10909, "omega":-0.00851, "ax":3.62329, "ay":5.08922, "alpha":-0.66538, "fx":[58.53741,64.12336,64.55252,59.31121], "fy":[88.63237,84.65277,84.60253,88.37694]}, - {"t":1.26313, "x":3.65781, "y":2.07148, "heading":-2.2767, "vx":-3.23891, "vy":2.27826, "omega":-0.03063, "ax":4.62274, "ay":4.11284, "alpha":-4.24001, "fx":[63.66671,95.27552,89.46173,66.1221], "fy":[85.74248,48.73927,60.23894,85.112]}, - {"t":1.29637, "x":3.55271, "y":2.14948, "heading":-2.27772, "vx":-3.08525, "vy":2.41497, "omega":-0.17157, "ax":5.14841, "ay":3.14906, "alpha":-6.76063, "fx":[71.51003,107.40796,99.92805,71.44601], "fy":[79.79688,10.33257,42.53075,81.59815]}, - {"t":1.32961, "x":3.453, "y":2.2315, "heading":-2.28342, "vx":-2.91412, "vy":2.51964, "omega":-0.39629, "ax":5.4369, "ay":2.54678, "alpha":-7.26571, "fx":[81.44123,108.21294,103.76887,76.49734], "fy":[70.31242,-7.65465,33.23957,77.38275]}, - {"t":1.36285, "x":3.35913, "y":2.31666, "heading":-2.2966, "vx":-2.73339, "vy":2.6043, "omega":-0.63781, "ax":5.62257, "ay":2.14391, "alpha":-7.24437, "fx":[88.76824,107.56232,105.69,80.53252], "fy":[61.54987,-16.55904,27.3652,73.51331]}, - {"t":1.39609, "x":3.27138, "y":2.40441, "heading":-2.3178, "vx":-2.5465, "vy":2.67556, "omega":-0.87861, "ax":5.75114, "ay":1.84898, "alpha":-7.10398, "fx":[93.60759,106.88505,106.87566,83.93289], "fy":[54.60567,-21.608,22.95321,69.85155]}, - {"t":1.42933, "x":3.18991, "y":2.49437, "heading":-2.347, "vx":-2.35533, "vy":2.73702, "omega":-1.11475, "ax":5.89012, "ay":1.56012, "alpha":-6.66167, "fx":[98.20336,106.58113,107.78333,88.1895], "fy":[46.56195,-23.75321,18.7609,64.57898]}, - {"t":1.46257, "x":3.11488, "y":2.58621, "heading":-2.38406, "vx":-2.15954, "vy":2.78888, "omega":-1.33618, "ax":6.16737, "ay":1.00948, "alpha":-4.91371, "fx":[105.54421,107.48826,108.76625,97.82225], "fy":[27.41718,-19.88842,12.237,48.91795]}, - {"t":1.49581, "x":3.0465, "y":2.67947, "heading":-2.42847, "vx":-1.95454, "vy":2.82244, "omega":-1.49952, "ax":6.29967, "ay":0.30014, "alpha":-3.85308, "fx":[108.42726,106.53931,109.25142,104.40419], "fy":[9.74331,-23.62533,2.40214,31.90112]}, - {"t":1.5185, "x":3.00378, "y":2.74358, "heading":-2.46249, "vx":-1.81162, "vy":2.82925, "omega":-1.58693, "ax":6.31511, "ay":-0.60443, "alpha":-3.12191, "fx":[108.4517,104.06427,108.7308,108.4259], "fy":[-10.06159,-32.87166,-10.61902,12.42748]}, - {"t":1.54118, "x":2.96431, "y":2.80761, "heading":-2.49849, "vx":-1.66835, "vy":2.81553, "omega":-1.65775, "ax":6.1966, "ay":-1.50809, "alpha":-2.29202, "fx":[105.43431,100.97789,106.45297,108.74434], "fy":[-27.62723,-41.42788,-24.44977,-9.10381]}, - {"t":1.56387, "x":2.92805, "y":2.87109, "heading":-2.5361, "vx":-1.52778, "vy":2.78132, "omega":-1.70975, "ax":5.95467, "ay":-2.35248, "alpha":-1.41222, "fx":[100.61211,97.47084,102.23511,104.83081], "fy":[-42.13251,-49.15887,-38.40413,-30.36478]}, - {"t":1.58655, "x":2.89492, "y":2.93358, "heading":-2.57489, "vx":-1.39269, "vy":2.72795, "omega":-1.74179, "ax":5.62078, "ay":-3.0953, "alpha":-0.55148, "fx":[95.04834,93.74518,96.1828,97.4553], "fy":[-53.67927,-55.98654,-51.72007,-49.21449]}, - {"t":1.60924, "x":2.86478, "y":2.99467, "heading":-2.6144, "vx":-1.26517, "vy":2.65773, "omega":-1.7543, "ax":5.23509, "ay":-3.71762, "alpha":0.2373, "fx":[89.40675,89.98424,88.68586,88.11263], "fy":[-62.75472,-61.90121,-63.73707,-64.5495]}, - {"t":1.63193, "x":2.83742, "y":3.05401, "heading":-2.6542, "vx":-1.14641, "vy":2.57339, "omega":-1.74891, "ax":4.83343, "ay":-4.22149, "alpha":0.93284, "fx":[84.02369,86.33286,80.30514,78.19955], "fy":[-69.89894,-66.94991,-74.04129,-76.33515]}, - {"t":1.65461, "x":2.81266, "y":3.11131, "heading":-2.69388, "vx":-1.03676, "vy":2.47762, "omega":-1.72775, "ax":4.44099, "ay":-4.62109, "alpha":1.53571, "fx":[79.03574,82.89048,71.61532,68.61812], "fy":[-75.57388,-71.21608,-82.50512,-85.1185]}, - {"t":1.6773, "x":2.79028, "y":3.16632, "heading":-2.73307, "vx":-0.93601, "vy":2.37279, "omega":-1.69291, "ax":4.07234, "ay":-4.93469, "alpha":2.05521, "fx":[74.47538,79.71438,63.08516,59.80249], "fy":[-80.13734,-74.80009,-89.2287,-91.58419]}, - {"t":1.69999, "x":2.77009, "y":3.21888, "heading":-2.77148, "vx":-0.84362, "vy":2.26084, "omega":-1.64629, "ax":3.73424, "ay":-5.17996, "alpha":2.50234, "fx":[70.32706,76.82816,55.03006,51.88832], "fy":[-83.8554,-77.80461,-94.44153,-96.33704]}, - {"t":1.72267, "x":2.75192, "y":3.26884, "heading":-2.80883, "vx":-0.75891, "vy":2.14333, "omega":-1.58952, "ax":3.42847, "ay":-5.37207, "alpha":2.88749, "fx":[66.55656,74.23154,47.6219,44.85927], "fy":[-86.92326,-80.32559,-98.41597,-99.84453]}, - {"t":1.74536, "x":2.73558, "y":3.31608, "heading":-2.84489, "vx":-0.68113, "vy":2.02145, "omega":-1.52401, "ax":3.15401, "ay":-5.5232, "alpha":3.21987, "fx":[63.12522,71.90913,40.92474,38.63614], "fy":[-89.48406,-82.44785,-101.41286,-102.44779]}, - {"t":1.76804, "x":2.72094, "y":3.36052, "heading":-2.87946, "vx":-0.60957, "vy":1.89615, "omega":-1.45097, "ax":2.90847, "ay":-5.64286, "alpha":3.50746, "fx":[59.99619,69.83724,34.933,33.12225], "fy":[-91.64351,-84.24367,-103.65632,-104.39025]}, - {"t":1.79073, "x":2.70786, "y":3.40209, "heading":-2.91238, "vx":-0.54359, "vy":1.76814, "omega":-1.37139, "ax":2.68892, "ay":-5.73828, "alpha":3.75714, "fx":[57.13683,67.98876,29.60176,28.22376], "fy":[-93.48052,-85.77319,-105.32744,-105.84498]}, - {"t":1.81342, "x":2.69622, "y":3.44072, "heading":-2.94349, "vx":-0.48259, "vy":1.63796, "omega":-1.28616, "ax":2.4924, "ay":-5.81496, "alpha":3.97478, "fx":[54.51928,66.33622,24.86723,23.85726], "fy":[-95.05472,-87.0856,-106.56719,-106.93573]}, - {"t":1.8361, "x":2.68591, "y":3.47638, "heading":-2.97267, "vx":-0.42605, "vy":1.50604, "omega":-1.19599, "ax":2.3161, "ay":-5.87705, "alpha":4.16537, "fx":[52.1202,64.85365,20.65938,19.95156], "fy":[-96.41182,-88.2208,-107.48295,-107.75195]}, - {"t":1.85879, "x":2.67684, "y":3.50904, "heading":-2.9998, "vx":-0.3735, "vy":1.37271, "omega":-1.10149, "ax":2.1575, "ay":-5.92768, "alpha":4.33314, "fx":[49.92026,63.51752,16.90889,16.44709], "fy":[-97.58727,-89.21088,-108.15541,-108.35914]}, - {"t":1.88148, "x":2.66893, "y":3.53865, "heading":-3.02479, "vx":-0.32456, "vy":1.23823, "omega":-1.00319, "ax":2.01437, "ay":-5.96926, "alpha":4.48171, "fx":[47.9035,62.30707,13.55076,13.29439], "fy":[-98.609,-90.08163,-108.64474,-108.80597]}, - {"t":1.90416, "x":2.66208, "y":3.56521, "heading":-3.04755, "vx":-0.27886, "vy":1.10281, "omega":-0.90151, "ax":1.8848, "ay":-6.00359, "alpha":4.61415, "fx":[46.05676,61.2043,10.52584,10.45248], "fy":[-99.49923,-90.85376,-108.99555,-109.1291]}, - {"t":1.92685, "x":2.65624, "y":3.58868, "heading":-3.068, "vx":-0.2361, "vy":0.96661, "omega":-0.79684, "ax":1.7671, "ay":-6.0321, "alpha":4.7331, "fx":[44.36918,60.19376,7.78127,7.88744], "fy":[-100.27589,-91.54395,-109.24076,-109.35654]}, - {"t":1.94953, "x":2.65134, "y":3.60906, "heading":-3.08608, "vx":-0.19601, "vy":0.82977, "omega":-0.68946, "ax":1.65987, "ay":-6.05586, "alpha":4.84084, "fx":[42.83176,59.26222,5.27032,5.57106], "fy":[-100.95358,-92.16568,-109.40458,-109.50997]}, - {"t":1.97222, "x":2.64732, "y":3.62632, "heading":-3.10172, "vx":-0.15835, "vy":0.69238, "omega":-0.57964, "ax":1.56186, "ay":-6.07572, "alpha":4.93932, "fx":[41.43703,58.39831,2.95204,3.47991], "fy":[-101.54433,-92.73,-109.50468,-109.60637]}, - {"t":1.99491, "x":2.64413, "y":3.64047, "heading":-3.11487, "vx":-0.12292, "vy":0.55455, "omega":-0.46758, "ax":1.47204, "ay":-6.09236, "alpha":5.03023, "fx":[40.17873,57.59216,0.79077,1.5944], "fy":[-102.05808,-93.24602,-109.55382,-109.65919]}, - {"t":2.01759, "x":2.64172, "y":3.65148, "heading":-3.12547, "vx":-0.08953, "vy":0.41633, "omega":-0.35347, "ax":1.38951, "ay":-6.10629, "alpha":5.115, "fx":[39.05159,56.83503,-1.24434,-0.10177], "fy":[-102.50312,-93.72144,-109.56112,-109.67919]}, - {"t":2.04028, "x":2.64004, "y":3.65936, "heading":-3.13349, "vx":-0.058, "vy":0.27781, "omega":-0.23743, "ax":1.31349, "ay":-6.11793, "alpha":5.19487, "fx":[38.05113,56.11898,-3.17969,-1.62225], "fy":[-102.88641,-94.16287,-109.53293,-109.67506]}, - {"t":2.06297, "x":2.63907, "y":3.66408, "heading":-3.13888, "vx":-0.02821, "vy":0.13901, "omega":-0.11958, "ax":1.24332, "ay":-6.12764, "alpha":5.27084, "fx":[37.17352,55.4366,-5.03766,-2.97835], "fy":[-103.21379,-94.57615,-109.47357,-109.65388]}, - {"t":2.08565, "x":2.63875, "y":3.66566, "heading":-3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/B_RIGHT_PATH2.traj b/src/main/deploy/choreo/B_RIGHT_PATH2.traj deleted file mode 100644 index 48a05270..00000000 --- a/src/main/deploy/choreo/B_RIGHT_PATH2.traj +++ /dev/null @@ -1,157 +0,0 @@ -{ - "name":"B_RIGHT_PATH2", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":3.168461322784424, "y":3.8475184440612793, "heading":-3.141592653589793, "intervals":42, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.9325261116027832, "y":1.9262405633926392, "heading":0.0, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":0.9888414144515992, "y":1.0097386837005615, "heading":-2.179485408307156, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.920522093772888, "y":1.9157768487930296, "heading":0.0, "intervals":43, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":2.9235854148864746, "y":4.0913493507385255, "heading":-3.141592653589793, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":true}, - {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"3.168461322784424 m", "val":3.168461322784424}, "y":{"exp":"3.8475184440612793 m", "val":3.8475184440612793}, "heading":{"exp":"-180 deg", "val":-3.141592653589793}, "intervals":42, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.9325261116027832 m", "val":1.9325261116027832}, "y":{"exp":"1.9262405633926392 m", "val":1.9262405633926392}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"0.9888414144515991 m", "val":0.9888414144515992}, "y":{"exp":"1.0097386837005615 m", "val":1.0097386837005615}, "heading":{"exp":"-2.1794854083071558 rad", "val":-2.179485408307156}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.9205220937728882 m", "val":1.920522093772888}, "y":{"exp":"1.9157768487930298 m", "val":1.9157768487930296}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":43, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"2.9235854148864746 m", "val":2.9235854148864746}, "y":{"exp":"(8.0518 - 3.9604506492614746) m", "val":4.0913493507385255}, "heading":{"exp":"-180 deg", "val":-3.141592653589793}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":true}, - {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,0.8885,1.53211,2.1725,3.09129], - "samples":[ - {"t":0.0, "x":3.16846, "y":3.84752, "heading":-3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.29322, "ay":-5.43609, "alpha":3.59014, "fx":[-35.13188,-49.6732,-78.00698,-61.25495], "fy":[-103.93754,-97.75742,-77.12622,-91.04441]}, - {"t":0.02866, "x":3.16711, "y":3.84529, "heading":-3.14159, "vx":-0.09439, "vy":-0.15581, "omega":0.1029, "ax":-3.29495, "ay":-5.43802, "alpha":3.53227, "fx":[-35.47645,-49.82916,-77.6832,-61.19554], "fy":[-103.81232,-97.66745,-77.44061,-91.076]}, - {"t":0.05732, "x":3.16305, "y":3.83859, "heading":-3.13864, "vx":-0.18883, "vy":-0.31167, "omega":0.20414, "ax":-3.29686, "ay":-5.44014, "alpha":3.46678, "fx":[-35.83084,-50.08317,-77.32206,-61.07861], "fy":[-103.68143,-97.52579,-77.78847,-91.14519]}, - {"t":0.08598, "x":3.15628, "y":3.82742, "heading":-3.13279, "vx":-0.28332, "vy":-0.46759, "omega":0.3035, "ax":-3.29897, "ay":-5.44248, "alpha":3.39287, "fx":[-36.20488,-50.42938,-76.91756,-60.90614], "fy":[-103.54113,-97.33434,-78.17456,-91.25016]}, - {"t":0.11465, "x":3.14681, "y":3.81178, "heading":-3.12409, "vx":-0.37787, "vy":-0.62358, "omega":0.40074, "ax":-3.30126, "ay":-5.44506, "alpha":3.30949, "fx":[-36.61089,-50.86105,-76.46183,-60.68043], "fy":[-103.3866,-97.09515,-78.60506,-91.38874]}, - {"t":0.14331, "x":3.13462, "y":3.79167, "heading":-3.11261, "vx":-0.47249, "vy":-0.77964, "omega":0.4956, "ax":-3.30375, "ay":-5.44789, "alpha":3.21532, "fx":[-37.06426,-51.37026,-75.9447,-60.40422], "fy":[-103.21161,-96.81073,-79.08782,-91.55831]}, - {"t":0.17197, "x":3.11972, "y":3.76709, "heading":-3.0984, "vx":-0.56718, "vy":-0.93578, "omega":0.58775, "ax":-3.30643, "ay":-5.45101, "alpha":3.10859, "fx":[-37.58425,-51.94745,-75.35316,-60.08081], "fy":[-103.00808,-96.48434,-79.63264,-91.7557]}, - {"t":0.20063, "x":3.10211, "y":3.73803, "heading":-3.08156, "vx":-0.66195, "vy":-1.09202, "omega":0.67685, "ax":-3.3093, "ay":-5.45445, "alpha":2.98693, "fx":[-38.19511,-52.58097,-74.67036,-59.71438], "fy":[-102.7654,-96.12036,-80.25178,-91.97708]}, - {"t":0.22929, "x":3.08178, "y":3.70449, "heading":-3.06216, "vx":-0.75679, "vy":-1.24835, "omega":0.76246, "ax":-3.31235, "ay":-5.45824, "alpha":2.84704, "fx":[-38.92771,-53.25646,-73.87426,-59.31025], "fy":[-102.46939,-95.72484,-80.96069,-92.21769]}, - {"t":0.25795, "x":3.05873, "y":3.66647, "heading":-3.04031, "vx":-0.85173, "vy":-1.40479, "omega":0.84406, "ax":-3.31559, "ay":-5.46243, "alpha":2.68435, "fx":[-39.82189,-53.95608,-72.93543,-58.87545], "fy":[-102.10069,-95.30607,-81.77911,-92.47155]}, - {"t":0.28661, "x":3.03295, "y":3.62396, "heading":-3.01611, "vx":-0.94676, "vy":-1.56135, "omega":0.921, "ax":-3.31899, "ay":-5.46704, "alpha":2.49232, "fx":[-40.92998,-54.65744,-71.81352,-58.41952], "fy":[-101.63219,-94.8754,-82.73278,-92.73089]}, - {"t":0.31527, "x":3.00445, "y":3.57697, "heading":-2.98972, "vx":-1.04189, "vy":-1.71804, "omega":0.99243, "ax":-3.32254, "ay":-5.47208, "alpha":2.26147, "fx":[-42.32226,-55.33226,-70.45126,-57.95578], "fy":[-101.02465,-94.44828,-83.8562,-92.98526]}, - {"t":0.34394, "x":2.97323, "y":3.52548, "heading":-2.96127, "vx":-1.13711, "vy":-1.87488, "omega":1.05725, "ax":-3.32615, "ay":-5.47748, "alpha":1.97776, "fx":[-44.09547,-55.94429,-68.76415,-57.50363], "fy":[-100.21919,-94.04563,-85.19697,-93.21987]}, - {"t":0.3726, "x":2.93927, "y":3.46949, "heading":-2.93097, "vx":-1.23245, "vy":-2.03187, "omega":1.11393, "ax":-3.32967, "ay":-5.48297, "alpha":1.61971, "fx":[-46.38681,-56.44618,-66.6214,-57.09271], "fy":[-99.12352,-93.69574,-86.82293,-93.41254]}, - {"t":0.40126, "x":2.90258, "y":3.40901, "heading":-2.89904, "vx":-1.32788, "vy":-2.18902, "omega":1.16035, "ax":-3.33268, "ay":-5.4878, "alpha":1.15335, "fx":[-49.39724,-56.77437,-63.80866,-56.77125], "fy":[-97.5854,-93.43702,-88.83411,-93.52731]}, - {"t":0.42992, "x":2.86315, "y":3.34401, "heading":-2.86579, "vx":-1.4234, "vy":-2.3463, "omega":1.19341, "ax":-3.33407, "ay":-5.49012, "alpha":0.5223, "fx":[-53.43146,-56.84039,-59.94949,-56.62482], "fy":[-95.33801,-93.32207,-91.38178,-93.49955]}, - {"t":0.45858, "x":2.82099, "y":3.27451, "heading":-2.83158, "vx":-1.51896, "vy":-2.50366, "omega":1.20838, "ax":-3.33088, "ay":-5.48501, "alpha":-0.37295, "fx":[-58.9654,-56.5151,-54.32398,-56.82465], "fy":[-91.87907,-93.42409,-94.69457,-93.19606]}, - {"t":0.48724, "x":2.77608, "y":3.2005, "heading":-2.79695, "vx":-1.61442, "vy":-2.66087, "omega":1.19769, "ax":-3.3147, "ay":-5.45847, "alpha":-1.72214, "fx":[-66.74498,-55.5986,-45.40386,-57.78103], "fy":[-86.1828,-93.84691,-99.07755,-92.28062]}, - {"t":0.5159, "x":2.72845, "y":3.12199, "heading":-2.76262, "vx":-1.70943, "vy":-2.81731, "omega":1.14833, "ax":-3.26205, "ay":-5.36274, "alpha":-3.92215, "fx":[-77.80997,-53.76099,-29.55635,-60.81858], "fy":[-75.98957,-94.73904,-104.585,-89.56093]}, - {"t":0.54456, "x":2.67812, "y":3.03904, "heading":-2.72971, "vx":-1.80292, "vy":-2.97102, "omega":1.03592, "ax":-3.1566, "ay":-4.95232, "alpha":-7.97251, "fx":[-92.49875,-50.44791,1.80402,-73.62849], "fy":[-56.50983,-96.29005,-108.14565,-76.005]}, - {"t":0.57323, "x":2.62515, "y":2.95185, "heading":-2.70002, "vx":-1.89339, "vy":-3.11296, "omega":0.80742, "ax":-3.15344, "ay":-4.06427, "alpha":-12.45943, "fx":[-98.34378,-47.24063,24.25595,-93.22821], "fy":[-43.93198,-97.3214,-104.47369,-30.80142]}, - {"t":0.60189, "x":2.56958, "y":2.86096, "heading":-2.67688, "vx":-1.98378, "vy":-3.22944, "omega":0.45031, "ax":-2.93275, "ay":-4.00747, "alpha":-12.42398, "fx":[-95.31494,-45.04056,24.10503,-83.29022], "fy":[-45.06549,-96.36283,-101.61182,-29.62334]}, - {"t":0.63055, "x":2.51152, "y":2.76676, "heading":-2.66397, "vx":-2.06783, "vy":-3.3443, "omega":0.09422, "ax":-0.27589, "ay":-1.25627, "alpha":-3.12075, "fx":[-16.13756,-8.02354,6.57513,-1.18523], "fy":[-18.03918,-31.65566,-25.08443,-10.69624]}, - {"t":0.65921, "x":2.45214, "y":2.67039, "heading":-2.66127, "vx":-2.07574, "vy":-3.38031, "omega":0.00478, "ax":-0.04151, "ay":0.02169, "alpha":-0.00759, "fx":[-0.73272,-0.71453,-0.67957,-0.69776], "fy":[0.37724,0.34228,0.36053,0.39547]}, - {"t":0.68787, "x":2.39263, "y":2.57351, "heading":-2.66113, "vx":-2.07693, "vy":-3.37969, "omega":0.00456, "ax":-0.48579, "ay":0.29992, "alpha":0.00005, "fx":[-8.26292,-8.26303,-8.26324,-8.26313], "fy":[5.10144,5.10167,5.10155,5.10131]}, - {"t":0.71653, "x":2.3329, "y":2.47677, "heading":-2.661, "vx":-2.09085, "vy":-3.37109, "omega":0.00456, "ax":-1.24065, "ay":0.77873, "alpha":0.00028, "fx":[-21.10213,-21.10273,-21.10403,-21.10343], "fy":[13.24573,13.24702,13.24627,13.24497]}, - {"t":0.74519, "x":2.27247, "y":2.38047, "heading":-2.66087, "vx":-2.12641, "vy":-3.34877, "omega":0.00457, "ax":-2.43894, "ay":1.58536, "alpha":0.00084, "fx":[-41.48308,-41.48421,-41.48814,-41.487], "fy":[26.96606,26.96987,26.96697,26.96316]}, - {"t":0.77385, "x":2.21052, "y":2.28514, "heading":-2.66074, "vx":-2.19631, "vy":-3.30333, "omega":0.0046, "ax":-3.59234, "ay":2.47214, "alpha":0.00186, "fx":[-61.10008,-61.10018,-61.10925,-61.10916], "fy":[42.0508,42.05886,42.05001,42.04196]}, - {"t":0.80252, "x":2.1461, "y":2.19148, "heading":-2.66061, "vx":-2.29927, "vy":-3.23248, "omega":0.00465, "ax":-4.23421, "ay":3.13739, "alpha":0.00386, "fx":[-72.01445,-72.01061,-72.03084,-72.03469], "fy":[53.36968,53.38498,53.3626,53.34729]}, - {"t":0.83118, "x":2.07846, "y":2.10012, "heading":-2.66047, "vx":-2.42063, "vy":-3.14256, "omega":0.00476, "ax":-4.46808, "ay":3.61471, "alpha":0.05027, "fx":[-75.89656,-75.81843,-76.10483,-76.18339], "fy":[61.55736,61.73275,61.41356,61.23678]}, - {"t":0.85984, "x":2.00724, "y":2.01154, "heading":-2.66034, "vx":-2.54869, "vy":-3.03896, "omega":0.0062, "ax":-4.0589, "ay":4.39529, "alpha":1.73328, "fx":[-63.85409,-62.16727,-73.60928,-76.53218], "fy":[78.67005,81.5812,71.7898,67.00952]}, - {"t":0.8885, "x":1.93253, "y":1.92624, "heading":-2.66016, "vx":-2.66503, "vy":-2.91298, "omega":0.05588, "ax":-0.64988, "ay":5.42449, "alpha":9.65572, "fx":[53.96431,6.5805,-51.80304,-52.9591], "fy":[88.53851,105.88653,91.87312,82.77767]}, - {"t":0.91325, "x":1.86636, "y":1.85579, "heading":-2.65878, "vx":-2.68111, "vy":-2.7787, "omega":0.2949, "ax":1.51519, "ay":4.73656, "alpha":12.17135, "fx":[92.21731,32.22152,-44.92907,23.58219], "fy":[53.86423,102.74559,96.87702,68.78322]}, - {"t":0.93801, "x":1.80045, "y":1.78846, "heading":-2.65148, "vx":-2.64361, "vy":-2.66145, "omega":0.59619, "ax":3.06627, "ay":4.26994, "alpha":11.9727, "fx":[96.21888,44.22723,-24.88966,93.06932], "fy":[48.84616,98.87362,104.50839,38.29362]}, - {"t":0.96276, "x":1.73595, "y":1.72389, "heading":-2.63672, "vx":-2.5677, "vy":-2.55575, "omega":0.89256, "ax":3.65977, "ay":4.81858, "alpha":6.51202, "fx":[89.76589,55.12646,21.18449,82.92954], "fy":[60.77868,93.57108,105.87883,67.62216]}, - {"t":0.98752, "x":1.67351, "y":1.6621, "heading":-2.61462, "vx":-2.47711, "vy":-2.43647, "omega":1.05376, "ax":4.0456, "ay":4.82618, "alpha":3.46072, "fx":[84.01231,62.91879,49.28306,79.04395], "fy":[68.99432,88.76324,96.63655,73.97335]}, - {"t":1.01227, "x":1.61343, "y":1.60326, "heading":-2.58854, "vx":-2.37696, "vy":-2.31701, "omega":1.13943, "ax":4.25086, "ay":4.75707, "alpha":1.67789, "fx":[79.78963,68.57491,63.74751,77.11157], "fy":[74.13476,84.66173,88.18039,76.68855]}, - {"t":1.03702, "x":1.55589, "y":1.54737, "heading":-2.56033, "vx":-2.27174, "vy":-2.19925, "omega":1.18096, "ax":4.3679, "ay":4.68927, "alpha":0.5393, "fx":[76.70825,72.87807,71.77239,75.82829], "fy":[77.51859,81.14231,82.06921,78.3223]}, - {"t":1.06178, "x":1.501, "y":1.49436, "heading":-2.5311, "vx":-2.16361, "vy":-2.08317, "omega":1.19431, "ax":4.44103, "ay":4.63262, "alpha":-0.24991, "fx":[74.42998,76.27752,76.62707,74.82778], "fy":[79.85118,78.08363,77.76329,79.50038]}, - {"t":1.08653, "x":1.4488, "y":1.44421, "heading":-2.50154, "vx":-2.05368, "vy":-1.96849, "omega":1.18813, "ax":4.49018, "ay":4.58628, "alpha":-0.83197, "fx":[72.72405,79.04,79.76635,73.9761], "fy":[81.51443,75.39413,74.69448,80.44187]}, - {"t":1.11129, "x":1.39934, "y":1.39689, "heading":-2.47212, "vx":-1.94253, "vy":-1.85496, "omega":1.16753, "ax":4.52507, "ay":4.54811, "alpha":-1.28127, "fx":[71.43646,81.33242,81.8959,73.21558], "fy":[82.72772,73.00761,72.47244,81.2407]}, - {"t":1.13604, "x":1.35264, "y":1.35237, "heading":-2.44322, "vx":-1.83052, "vy":-1.74238, "omega":1.13582, "ax":4.55086, "ay":4.51633, "alpha":-1.63991, "fx":[70.46232,83.26461,83.39004,72.51864], "fy":[83.62487,70.87594,70.84221,81.94277]}, - {"t":1.1608, "x":1.30872, "y":1.31062, "heading":-2.41511, "vx":-1.71786, "vy":-1.63058, "omega":1.09522, "ax":4.57054, "ay":4.48954, "alpha":-1.93343, "fx":[69.72784,84.91226,84.46323,71.87122], "fy":[84.29209,68.96326,69.63511,82.57276]}, - {"t":1.18555, "x":1.2676, "y":1.27163, "heading":-2.388, "vx":-1.60472, "vy":-1.51945, "omega":1.04736, "ax":4.58593, "ay":4.46673, "alpha":-2.17821, "fx":[69.17935,86.3297,85.24646,71.26584], "fy":[84.78769,67.24195,68.73642,83.14489]}, - {"t":1.2103, "x":1.22928, "y":1.23539, "heading":-2.36207, "vx":-1.4912, "vy":-1.40888, "omega":0.99344, "ax":4.5982, "ay":4.44712, "alpha":-2.3853, "fx":[68.77642,87.55738,85.8241,70.69843], "fy":[85.15289,65.69,68.06579,83.66794]}, - {"t":1.23506, "x":1.19377, "y":1.20187, "heading":-2.33748, "vx":-1.37738, "vy":-1.29879, "omega":0.9344, "ax":4.60816, "ay":4.43012, "alpha":-2.56251, "fx":[68.48765,88.62635,86.25303,70.16674], "fy":[85.41802,64.28927,67.56533,84.14761]}, - {"t":1.25981, "x":1.16109, "y":1.17108, "heading":-2.31435, "vx":-1.26331, "vy":-1.18913, "omega":0.87096, "ax":4.61636, "ay":4.41528, "alpha":-2.71553, "fx":[68.28796,89.56108,86.57306,69.66955], "fy":[85.60622,63.02432,67.19228,84.58781]}, - {"t":1.28457, "x":1.13123, "y":1.143, "heading":-2.29279, "vx":-1.14903, "vy":-1.07983, "omega":0.80374, "ax":4.6232, "ay":4.40224, "alpha":-2.8487, "fx":[68.15681,90.38128,86.81298,69.20617], "fy":[85.73575,61.88177,66.91436,84.9914]}, - {"t":1.30932, "x":1.10421, "y":1.11762, "heading":-2.27289, "vx":-1.03459, "vy":-0.97086, "omega":0.73323, "ax":4.62898, "ay":4.3907, "alpha":-2.9654, "fx":[68.07704,91.10307,86.99422,68.77621], "fy":[85.82139,60.84977,66.70672,85.36052]}, - {"t":1.33407, "x":1.08001, "y":1.09493, "heading":-2.25474, "vx":-0.92, "vy":-0.86217, "omega":0.65982, "ax":4.63392, "ay":4.38044, "alpha":-3.06833, "fx":[68.03412,91.73983,87.13311,68.37946], "fy":[85.87541,59.91776,66.54988,85.6969]}, - {"t":1.35883, "x":1.05866, "y":1.07493, "heading":-2.23841, "vx":-0.80529, "vy":-0.75374, "omega":0.58387, "ax":4.63818, "ay":4.37125, "alpha":-3.15969, "fx":[68.01553,92.30277,87.24237,68.01578], "fy":[85.90818,59.07625,66.4284,86.00193]}, - {"t":1.38358, "x":1.04015, "y":1.05761, "heading":-2.22395, "vx":-0.69048, "vy":-0.64553, "omega":0.50565, "ax":4.64189, "ay":4.36298, "alpha":-3.24133, "fx":[68.01045,92.80133,87.33206,67.68507], "fy":[85.92862,58.31671,66.32983,86.27678]}, - {"t":1.40834, "x":1.02448, "y":1.04297, "heading":-2.21144, "vx":-0.57557, "vy":-0.53753, "omega":0.42541, "ax":4.64515, "ay":4.35549, "alpha":-3.31476, "fx":[68.00947,93.24352,87.41029,67.3873], "fy":[85.94442,57.6315,66.24404,86.52243]}, - {"t":1.43309, "x":1.01165, "y":1.031, "heading":-2.20091, "vx":-0.46059, "vy":-0.42971, "omega":0.34336, "ax":4.64803, "ay":4.34867, "alpha":-3.38128, "fx":[68.00435,93.6361,87.48366,67.12245], "fy":[85.96229,57.01381,66.1627,86.73968]}, - {"t":1.45785, "x":1.00167, "y":1.02169, "heading":-2.19241, "vx":-0.34553, "vy":-0.32206, "omega":0.25966, "ax":4.65059, "ay":4.34243, "alpha":-3.442, "fx":[67.98791,93.98482,87.55761,66.89054], "fy":[85.98806,56.4576,66.0789,86.92922]}, - {"t":1.4826, "x":0.99455, "y":1.01505, "heading":-2.18598, "vx":-0.23041, "vy":-0.21457, "omega":0.17446, "ax":4.65288, "ay":4.33668, "alpha":-3.49786, "fx":[67.9539,94.29452,87.63664,66.69166], "fy":[86.0268,55.95761,65.98684,87.09156]}, - {"t":1.50735, "x":0.99027, "y":1.01107, "heading":-2.18166, "vx":-0.11523, "vy":-0.10722, "omega":0.08787, "ax":4.65494, "ay":4.33136, "alpha":-3.54966, "fx":[67.89691,94.56923,87.72449,66.52597], "fy":[86.08285,55.50935,65.88165,87.22709]}, - {"t":1.53211, "x":0.98884, "y":1.00974, "heading":-2.17949, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.78418, "ay":4.18595, "alpha":-3.58289, "fx":[70.92187,96.53539,89.41392,68.63909], "fy":[83.61535,52.03183,63.57971,85.58025]}, - {"t":1.55772, "x":0.99041, "y":1.01111, "heading":-2.17949, "vx":0.12255, "vy":0.10723, "omega":-0.09178, "ax":4.77608, "ay":4.19916, "alpha":-3.52153, "fx":[70.92012,96.17594,89.19118,68.6721], "fy":[83.60551,52.67572,63.87995,85.54465]}, - {"t":1.58334, "x":0.99512, "y":1.01524, "heading":-2.18184, "vx":0.24489, "vy":0.21479, "omega":-0.18199, "ax":4.76714, "ay":4.21349, "alpha":-3.45551, "fx":[70.8759,95.76943,88.971,68.73408], "fy":[83.63088,53.39213,64.17324,85.48494]}, - {"t":1.60896, "x":1.00295, "y":1.02212, "heading":-2.1865, "vx":0.36701, "vy":0.32272, "omega":-0.2705, "ax":4.7572, "ay":4.22912, "alpha":-3.38384, "fx":[70.79338,95.30944,88.74808,68.8237], "fy":[83.68772,54.18823,64.46685,85.40195]}, - {"t":1.63457, "x":1.01392, "y":1.03178, "heading":-2.19343, "vx":0.48887, "vy":0.43106, "omega":-0.35718, "ax":4.74613, "ay":4.24625, "alpha":-3.30535, "fx":[70.67749,94.78806,88.51588,68.93952], "fy":[83.77156,55.07256,64.76944,85.29655]}, - {"t":1.66019, "x":1.028, "y":1.04421, "heading":-2.20258, "vx":0.61044, "vy":0.53983, "omega":-0.44185, "ax":4.73371, "ay":4.26511, "alpha":-3.21868, "fx":[70.53396,94.19566,88.26634,69.07993], "fy":[83.87721,56.05514,65.09145,85.16966]}, - {"t":1.6858, "x":1.04519, "y":1.05944, "heading":-2.2139, "vx":0.7317, "vy":0.64908, "omega":-0.5243, "ax":4.71969, "ay":4.286, "alpha":-3.12218, "fx":[70.36938,93.5205,87.98943,69.24305], "fy":[83.99872,57.14759,65.44555,85.02235]}, - {"t":1.71142, "x":1.06548, "y":1.07747, "heading":-2.22733, "vx":0.8526, "vy":0.75887, "omega":-0.60428, "ax":4.70376, "ay":4.30924, "alpha":-3.01391, "fx":[70.19129,92.74825,87.67252,69.4266], "fy":[84.12938,58.36323,65.84728,84.85596]}, - {"t":1.73703, "x":1.08886, "y":1.09832, "heading":-2.2428, "vx":0.97309, "vy":0.86926, "omega":-0.68148, "ax":4.68551, "ay":4.33527, "alpha":-2.89154, "fx":[70.0083,91.86142,87.29947,69.62774], "fy":[84.26161,59.71727,66.31594,84.67221]}, - {"t":1.76265, "x":1.11533, "y":1.12201, "heading":-2.26026, "vx":1.09312, "vy":0.98031, "omega":-0.75555, "ax":4.66441, "ay":4.36461, "alpha":-2.75221, "fx":[69.83022,90.8385,86.84932,69.8428], "fy":[84.38689,61.22694,66.87574,84.47336]}, - {"t":1.78827, "x":1.14486, "y":1.14856, "heading":-2.27962, "vx":1.2126, "vy":1.09211, "omega":-0.82605, "ax":4.63974, "ay":4.39789, "alpha":-2.59245, "fx":[69.66829,89.65288,86.29429,70.06703], "fy":[84.49555,62.9117,67.5575,84.26253]}, - {"t":1.81388, "x":1.17744, "y":1.17797, "heading":-2.30078, "vx":1.33145, "vy":1.20477, "omega":-0.89246, "ax":4.61057, "ay":4.43592, "alpha":-2.40786, "fx":[69.5354,88.27141,85.59679,70.29405], "fy":[84.57654,64.79342,68.40099,84.044]}, - {"t":1.8395, "x":1.21306, "y":1.21029, "heading":-2.32364, "vx":1.44955, "vy":1.3184, "omega":-0.95414, "ax":4.5756, "ay":4.47973, "alpha":-2.19281, "fx":[69.4466,86.65229,84.70449,70.51521], "fy":[84.61694,66.89665,69.45838,83.82373]}, - {"t":1.86511, "x":1.25169, "y":1.24553, "heading":-2.34808, "vx":1.56676, "vy":1.43315, "omega":-1.01031, "ax":4.53304, "ay":4.53064, "alpha":-1.93985, "fx":[69.41967,84.74227,83.54246,70.71845], "fy":[84.6013,69.24874,70.79919,83.61023]}, - {"t":1.89073, "x":1.29331, "y":1.28373, "heading":-2.37396, "vx":1.68288, "vy":1.54921, "omega":-1.06, "ax":4.4803, "ay":4.59038, "alpha":-1.63869, "fx":[69.47614,82.47246,81.9996,70.88646], "fy":[84.51052,71.87989,72.51773,83.41586]}, - {"t":1.91635, "x":1.33789, "y":1.32492, "heading":-2.40111, "vx":1.79764, "vy":1.66679, "omega":-1.10198, "ax":4.41356, "ay":4.66125, "alpha":-1.27455, "fx":[69.64289,79.75246,79.90456,70.99339], "fy":[84.31997,74.8229,74.74395,83.25912]}, - {"t":1.94196, "x":1.38539, "y":1.36915, "heading":-2.42934, "vx":1.9107, "vy":1.78619, "omega":-1.13462, "ax":4.32688, "ay":4.74635, "alpha":-0.82502, "fx":[69.95467,76.46151,76.98095,70.99869], "fy":[83.99645,78.11205,77.65861,83.16892]}, - {"t":1.96758, "x":1.43575, "y":1.41646, "heading":-2.4584, "vx":2.02154, "vy":1.90778, "omega":-1.15576, "ax":4.21065, "ay":4.84983, "alpha":-0.25427, "fx":[70.45842,72.43549,72.75977,70.83415], "fy":[83.49287,81.78009,81.511,83.19301]}, - {"t":1.99319, "x":1.48892, "y":1.46692, "heading":-2.48801, "vx":2.1294, "vy":2.03201, "omega":-1.16227, "ax":4.04833, "ay":4.977, "alpha":0.49824, "fx":[71.22042,67.44758,66.40147,70.37432], "fy":[82.73857,85.85107,86.62294,83.41674]}, - {"t":2.01881, "x":1.54479, "y":1.5206, "heading":-2.51778, "vx":2.2331, "vy":2.1595, "omega":-1.14951, "ax":3.80971, "ay":5.13316, "alpha":1.53857, "fx":[72.3387,61.18036,56.33189,69.35704], "fy":[81.6213,90.32389,93.29898,84.01043]}, - {"t":2.04442, "x":1.60324, "y":1.5776, "heading":-2.54723, "vx":2.33069, "vy":2.29099, "omega":-1.1101, "ax":3.43731, "ay":5.31704, "alpha":3.04656, "fx":[73.96349,53.18903,39.59694,67.12135], "fy":[79.9521,95.13581,101.30546,85.37227]}, - {"t":2.07004, "x":1.66407, "y":1.63803, "heading":-2.57566, "vx":2.41874, "vy":2.42719, "omega":-1.03206, "ax":2.82516, "ay":5.49758, "alpha":5.23364, "fx":[76.31956,42.86813,11.64253,61.39029], "fy":[77.40333,100.08369,107.87644,88.68582]}, - {"t":2.09566, "x":1.72696, "y":1.70201, "heading":-2.6021, "vx":2.49111, "vy":2.56801, "omega":-0.89799, "ax":1.73667, "ay":5.60365, "alpha":7.91376, "fx":[79.54787,29.50388,-28.33839,37.44781], "fy":[73.57445,104.66179,104.51996,98.50945]}, - {"t":2.12127, "x":1.79134, "y":1.76963, "heading":-2.6251, "vx":2.53559, "vy":2.71156, "omega":-0.69527, "ax":-0.21298, "ay":5.48408, "alpha":10.68067, "fx":[72.33913,14.26956,-52.73572,-48.36396], "fy":[79.86039,107.57339,94.45085,91.24582]}, - {"t":2.14689, "x":1.85622, "y":1.84089, "heading":-2.64291, "vx":2.53014, "vy":2.85204, "omega":-0.42168, "ax":-1.55936, "ay":5.57289, "alpha":8.78196, "fx":[31.42162,-7.62117,-60.61686,-69.28091], "fy":[102.15139,107.84874,89.33049,79.84224]}, - {"t":2.1725, "x":1.92052, "y":1.91578, "heading":-2.65371, "vx":2.49019, "vy":2.99479, "omega":-0.19672, "ax":-3.20258, "ay":5.17612, "alpha":5.46147, "fx":[-27.63461,-36.7868,-71.89235,-81.58639], "fy":[102.59484,101.11967,80.1223,68.34066]}, - {"t":2.20122, "x":1.9907, "y":2.0039, "heading":-2.65936, "vx":2.39824, "vy":3.14341, "omega":-0.03991, "ax":-4.76505, "ay":3.98742, "alpha":1.14392, "fx":[-78.77232,-76.42479,-83.20982,-85.80156], "fy":[70.25519,73.40638,65.84151,61.7962]}, - {"t":2.22993, "x":2.05759, "y":2.09579, "heading":-2.66051, "vx":2.26143, "vy":3.25789, "omega":-0.00707, "ax":-5.09665, "ay":3.40296, "alpha":0.06881, "fx":[-86.59764,-86.44253,-86.78743,-86.94248], "fy":[57.98267,58.26982,57.78549,57.49559]}, - {"t":2.25864, "x":2.12042, "y":2.19074, "heading":-2.66071, "vx":2.11509, "vy":3.3556, "omega":-0.00509, "ax":-5.11798, "ay":3.07845, "alpha":0.00801, "fx":[-87.04517,-87.02884,-87.06549,-87.08182], "fy":[52.37234,52.40946,52.35464,52.31749]}, - {"t":2.28735, "x":2.17904, "y":2.28835, "heading":-2.66086, "vx":1.96814, "vy":3.44399, "omega":-0.00486, "ax":-4.99997, "ay":2.72519, "alpha":0.00431, "fx":[-85.04236,-85.03538,-85.05362,-85.0606], "fy":[46.35785,46.37928,46.35162,46.33018]}, - {"t":2.31606, "x":2.23349, "y":2.38836, "heading":-2.661, "vx":1.82459, "vy":3.52223, "omega":-0.00474, "ax":-4.6303, "ay":2.29166, "alpha":0.00272, "fx":[-78.75584,-78.75347,-78.76444,-78.76681], "fy":[38.98114,38.99519,38.97977,38.96572]}, - {"t":2.34478, "x":2.28397, "y":2.49043, "heading":-2.66113, "vx":1.69164, "vy":3.58803, "omega":-0.00466, "ax":-3.79528, "ay":1.72082, "alpha":0.00144, "fx":[-64.5534,-64.55383,-64.55973,-64.5593], "fy":[29.27025,29.27763,29.27114,29.26376]}, - {"t":2.37349, "x":2.33098, "y":2.59416, "heading":-2.66127, "vx":1.58267, "vy":3.63744, "omega":-0.00462, "ax":-2.43807, "ay":1.03349, "alpha":0.00055, "fx":[-41.46917,-41.47004,-41.47245,-41.47158], "fy":[17.5789,17.58159,17.5798,17.57711]}, - {"t":2.4022, "x":2.37541, "y":2.69903, "heading":-2.6614, "vx":1.51267, "vy":3.66711, "omega":-0.0046, "ax":-1.15334, "ay":0.46665, "alpha":-0.00644, "fx":[-19.63966,-19.62542,-19.59616,-19.6104], "fy":[7.94421,7.91413,7.93081,7.96088]}, - {"t":2.43091, "x":2.41837, "y":2.80451, "heading":-2.66153, "vx":1.47955, "vy":3.68051, "omega":-0.00479, "ax":-0.73836, "ay":-0.8984, "alpha":-2.77605, "fx":[-22.40803,-15.3557,-2.66364,-9.80956], "fy":[-12.09165,-24.68573,-18.79806,-5.5509]}, - {"t":2.45962, "x":2.46055, "y":2.90981, "heading":-2.66167, "vx":1.45835, "vy":3.65472, "omega":-0.0845, "ax":-2.09502, "ay":-4.45018, "alpha":-12.05778, "fx":[-91.6247,-35.76007,37.61663,-52.77444], "fy":[-51.66076,-100.22301,-97.88103,-53.02011]}, - {"t":2.48834, "x":2.50155, "y":3.01291, "heading":-2.6641, "vx":1.3982, "vy":3.52694, "omega":-0.4307, "ax":-2.31807, "ay":-4.52076, "alpha":-12.18269, "fx":[-94.67457,-36.3544,40.51317,-67.20303], "fy":[-51.16372,-101.92446,-99.53566,-54.96329]}, - {"t":2.51705, "x":2.54074, "y":3.11232, "heading":-2.67646, "vx":1.33165, "vy":3.39714, "omega":-0.78049, "ax":-2.19418, "ay":-5.42181, "alpha":-8.03194, "fx":[-85.60141,-37.65468,20.68686,-46.72029], "fy":[-66.39824,-101.99372,-106.26464,-94.23681]}, - {"t":2.54576, "x":2.57807, "y":3.20762, "heading":-2.69887, "vx":1.26865, "vy":3.24147, "omega":-1.0111, "ax":-2.28837, "ay":-5.82648, "alpha":-4.19064, "fx":[-66.20204,-39.08124,-9.60092,-40.8138], "fy":[-86.25335,-101.68921,-108.28681,-100.19769]}, - {"t":2.57447, "x":2.61356, "y":3.29829, "heading":-2.7279, "vx":1.20294, "vy":3.07418, "omega":-1.13142, "ax":-2.32991, "ay":-5.93958, "alpha":-1.93437, "fx":[-52.57889,-39.81127,-26.35043,-39.78383], "fy":[-95.4734,-101.56299,-105.7604,-101.32568]}, - {"t":2.60318, "x":2.64713, "y":3.3841, "heading":-2.76039, "vx":1.13605, "vy":2.90364, "omega":-1.18696, "ax":-2.34239, "ay":-5.97313, "alpha":-0.53349, "fx":[-43.45644,-39.97139,-36.21318,-39.73221], "fy":[-100.14694,-101.61404,-102.98934,-101.65493]}, - {"t":2.6319, "x":2.67879, "y":3.46501, "heading":-2.79447, "vx":1.06879, "vy":2.73214, "omega":-1.20228, "ax":-2.34485, "ay":-5.98072, "alpha":0.39703, "fx":[-37.18924,-39.70742,-42.57666,-40.06752], "fy":[-102.76829,-101.8039,-100.65368,-101.69522]}, - {"t":2.66061, "x":2.70851, "y":3.54099, "heading":-2.82899, "vx":1.00147, "vy":2.56043, "omega":-1.19088, "ax":-2.34378, "ay":-5.9791, "alpha":1.05276, "fx":[-32.74357,-39.13799,-46.99411,-40.5925], "fy":[-104.36203,-102.09201,-98.76059,-101.59631]}, - {"t":2.68932, "x":2.7363, "y":3.61204, "heading":-2.86318, "vx":0.93417, "vy":2.38875, "omega":-1.16065, "ax":-2.34141, "ay":-5.97423, "alpha":1.53784, "fx":[-29.50469,-38.35455,-50.23218,-41.21576], "fy":[-105.39219,-102.44362,-97.22273,-101.42091]}, - {"t":2.71803, "x":2.76215, "y":3.67817, "heading":-2.8965, "vx":0.86695, "vy":2.21722, "omega":-1.1165, "ax":-2.33857, "ay":-5.96838, "alpha":1.91133, "fx":[-27.09632,-37.4276,-52.70319,-41.88668], "fy":[-106.08984,-102.83099,-95.95943,-101.2013]}, - {"t":2.74674, "x":2.78608, "y":3.73937, "heading":-2.92856, "vx":0.7998, "vy":2.04586, "omega":-1.06162, "ax":-2.33558, "ay":-5.96245, "alpha":2.20868, "fx":[-25.27788,-36.41206,-54.64637,-42.57396], "fy":[-106.57965,-103.23279,-94.90924,-100.95668]}, - {"t":2.77546, "x":2.80808, "y":3.79565, "heading":-2.95904, "vx":0.73274, "vy":1.87466, "omega":-0.9982, "ax":-2.33259, "ay":-5.95679, "alpha":2.45212, "fx":[-23.88875,-35.35118,-56.20976,-43.25674], "fy":[-106.93348,-103.63308,-94.02691,-100.69966]}, - {"t":2.80417, "x":2.82816, "y":3.84702, "heading":-2.9877, "vx":0.66577, "vy":1.70363, "omega":-0.9278, "ax":-2.32966, "ay":-5.9515, "alpha":2.6561, "fx":[-22.81744,-34.2792,-57.4902,-43.92043], "fy":[-107.19511,-104.02033,-93.27885,-100.43922]}, - {"t":2.83288, "x":2.84631, "y":3.89348, "heading":-3.01434, "vx":0.59888, "vy":1.53275, "omega":-0.85154, "ax":-2.32684, "ay":-5.94661, "alpha":2.83024, "fx":[-21.98383,-33.22326,-58.55411,-44.55441], "fy":[-107.3925,-104.38653,-92.63959,-100.18214]}, - {"t":2.86159, "x":2.86255, "y":3.93504, "heading":-3.03879, "vx":0.53207, "vy":1.36202, "omega":-0.77027, "ax":-2.32416, "ay":-5.9421, "alpha":2.98114, "fx":[-21.3287,-32.20482,-59.44902,-45.15073], "fy":[-107.54429,-104.7264,-92.08928,-99.93378]}, - {"t":2.8903, "x":2.87687, "y":3.97169, "heading":-3.06091, "vx":0.46534, "vy":1.19141, "omega":-0.68468, "ax":-2.32163, "ay":-5.93794, "alpha":3.1134, "fx":[-20.80708,-31.24071,-60.21022,-45.70327], "fy":[-107.66333,-105.03676,-91.61209,-99.69847]}, - {"t":2.91902, "x":2.88927, "y":4.00345, "heading":-3.08057, "vx":0.39868, "vy":1.02092, "omega":-0.59529, "ax":-2.31927, "ay":-5.9341, "alpha":3.23027, "fx":[-20.38415,-30.34403,-60.86469,-46.20729], "fy":[-107.7588,-105.31593,-91.19506,-99.47987]}, - {"t":2.94773, "x":2.89976, "y":4.03032, "heading":-3.09766, "vx":0.33209, "vy":0.85054, "omega":-0.50254, "ax":-2.31706, "ay":-5.93057, "alpha":3.33414, "fx":[-20.03249,-29.52494,-61.43363,-46.65897], "fy":[-107.83744,-105.56334,-90.82744,-99.28103]}, - {"t":2.97644, "x":2.90834, "y":4.0523, "heading":-3.11209, "vx":0.26556, "vy":0.68026, "omega":-0.40681, "ax":-2.31501, "ay":-5.92732, "alpha":3.42676, "fx":[-19.73015,-28.79124,-61.93399,-47.05524], "fy":[-107.90431,-105.77912,-90.50019,-99.10459]}, - {"t":3.00515, "x":2.91501, "y":4.06939, "heading":-3.12377, "vx":0.19909, "vy":0.51007, "omega":-0.30842, "ax":-2.31311, "ay":-5.92434, "alpha":3.50948, "fx":[-19.45942,-28.14899,-62.37948,-47.39356], "fy":[-107.96329,-105.96383,-90.20568,-98.95281]}, - {"t":3.03386, "x":2.91978, "y":4.08159, "heading":-3.13262, "vx":0.13268, "vy":0.33997, "omega":-0.20766, "ax":-2.31135, "ay":-5.92163, "alpha":3.58333, "fx":[-19.20593,-27.60297,-62.78122,-47.67174], "fy":[-108.0174,-106.11819,-89.93748,-98.82765]}, - {"t":3.06258, "x":2.92263, "y":4.08891, "heading":-3.13858, "vx":0.06632, "vy":0.16995, "omega":-0.10477, "ax":-2.30973, "ay":-5.91916, "alpha":3.64912, "fx":[-18.95794,-27.15714,-63.14821,-47.88792], "fy":[-108.06897,-106.24295,-89.69026,-98.7308]}, - {"t":3.09129, "x":2.92359, "y":4.09135, "heading":-3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/B_RIGHT_PATH3.traj b/src/main/deploy/choreo/B_RIGHT_PATH3.traj deleted file mode 100644 index d9e7ebb4..00000000 --- a/src/main/deploy/choreo/B_RIGHT_PATH3.traj +++ /dev/null @@ -1,97 +0,0 @@ -{ - "name":"B_RIGHT_PATH3", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":3.17155122756958, "y":4.128544318008423, "heading":-3.141592653589793, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.8201370239257812, "y":1.9340460174560548, "heading":0.0, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":0.7159243226051331, "y":0.8728400468826294, "heading":-2.179485408307156, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"3.17155122756958 m", "val":3.17155122756958}, "y":{"exp":"(8.0518 - 3.923255681991577) m", "val":4.128544318008423}, "heading":{"exp":"-180 deg", "val":-3.141592653589793}, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.8201370239257812 m", "val":1.8201370239257812}, "y":{"exp":"(8.0518 - 6.117753982543945) m", "val":1.9340460174560548}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"0.7159243226051331 m", "val":0.7159243226051331}, "y":{"exp":"0.8728400468826294 m", "val":0.8728400468826294}, "heading":{"exp":"-2.1794854083071558 rad", "val":-2.179485408307156}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,0.96199,1.65997], - "samples":[ - {"t":0.0, "x":3.17155, "y":4.12854, "heading":-3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.23174, "ay":-5.47655, "alpha":3.53305, "fx":[-34.41351,-48.37199,-76.76202,-60.33611], "fy":[-104.17988,-98.41253,-78.36801,-91.65752]}, - {"t":0.02915, "x":3.17018, "y":4.12622, "heading":-3.14159, "vx":-0.09421, "vy":-0.15965, "omega":0.10299, "ax":-3.23314, "ay":-5.47837, "alpha":3.47908, "fx":[-34.73027,-48.5194,-76.45369,-60.27562], "fy":[-104.06654,-98.32924,-78.65712,-91.68893]}, - {"t":0.0583, "x":3.16606, "y":4.11924, "heading":-3.13859, "vx":-0.18846, "vy":-0.31935, "omega":0.20441, "ax":-3.23471, "ay":-5.48038, "alpha":3.41774, "fx":[-35.05447,-48.76489,-76.10991,-60.15695], "fy":[-103.94858,-98.19589,-78.97705,-91.75749]}, - {"t":0.08745, "x":3.15919, "y":4.1076, "heading":-3.13263, "vx":-0.28276, "vy":-0.47911, "omega":0.30404, "ax":-3.23647, "ay":-5.48261, "alpha":3.34823, "fx":[-35.39571,-49.10322,-75.72457,-59.98189], "fy":[-103.82247,-98.014,-79.33259,-91.86156]}, - {"t":0.11661, "x":3.14957, "y":4.0913, "heading":-3.12377, "vx":-0.3771, "vy":-0.63894, "omega":0.40165, "ax":-3.23839, "ay":-5.48507, "alpha":3.26951, "fx":[-35.76609,-49.52833,-75.28965,-59.75252], "fy":[-103.68361,-97.78521,-79.73,-91.9991]}, - {"t":0.14576, "x":3.1372, "y":4.07034, "heading":-3.11206, "vx":-0.47151, "vy":-0.79883, "omega":0.49696, "ax":-3.2405, "ay":-5.48778, "alpha":3.18023, "fx":[-36.18087,-50.03302,-74.79474,-59.4713], "fy":[-103.52602,-97.51149,-80.17722,-92.16769]}, - {"t":0.17491, "x":3.12208, "y":4.04473, "heading":-3.09757, "vx":-0.56597, "vy":-0.95881, "omega":0.58967, "ax":-3.24279, "ay":-5.49077, "alpha":3.07861, "fx":[-36.65933,-50.60854,-74.2264,-59.14124], "fy":[-103.34189,-97.1955,-80.68427,-92.36437]}, - {"t":0.20406, "x":3.1042, "y":4.01444, "heading":-3.08038, "vx":-0.6605, "vy":-1.11887, "omega":0.67941, "ax":-3.24525, "ay":-5.49408, "alpha":2.96223, "fx":[-37.22595,-51.24402,-73.56721,-58.76616], "fy":[-103.1209,-96.84093,-81.26373,-92.58552]}, - {"t":0.23321, "x":3.08357, "y":3.97949, "heading":-3.06058, "vx":-0.75511, "vy":-1.27903, "omega":0.76577, "ax":-3.2479, "ay":-5.49775, "alpha":2.82774, "fx":[-37.91228,-51.92585,-72.79417,-58.35097], "fy":[-102.8491,-96.45301,-81.9316,-92.82664]}, - {"t":0.26236, "x":3.06018, "y":3.93987, "heading":-3.03825, "vx":-0.84979, "vy":-1.4393, "omega":0.8482, "ax":-3.25071, "ay":-5.50181, "alpha":2.67038, "fx":[-38.75955,-52.63682,-71.87629,-57.90221], "fy":[-102.50727,-96.03918,-82.7085,-93.082]}, - {"t":0.29151, "x":3.03402, "y":3.89558, "heading":-3.01353, "vx":-0.94455, "vy":-1.59968, "omega":0.92604, "ax":-3.25369, "ay":-5.50632, "alpha":2.48331, "fx":[-39.82285,-53.35493,-70.7706,-57.42885], "fy":[-102.06807,-95.60989,-83.62166,-93.34413]}, - {"t":0.32066, "x":3.00511, "y":3.8466, "heading":-2.98653, "vx":-1.0394, "vy":-1.7602, "omega":0.99844, "ax":-3.25679, "ay":-5.51129, "alpha":2.25644, "fx":[-41.17756,-54.05178,-69.41526,-56.94365], "fy":[-101.49128,-95.17975,-84.7081,-93.60279]}, - {"t":0.34982, "x":2.97342, "y":3.79295, "heading":-2.95743, "vx":-1.13434, "vy":-1.92086, "omega":1.06421, "ax":-3.25995, "ay":-5.51666, "alpha":1.97449, "fx":[-42.93001,-54.69016,-67.71734,-56.46546], "fy":[-100.71512,-94.76913,-86.01983,-93.84334]}, - {"t":0.37897, "x":2.93897, "y":3.73461, "heading":-2.9264, "vx":-1.22937, "vy":-2.08168, "omega":1.12177, "ax":-3.26297, "ay":-5.52217, "alpha":1.61351, "fx":[-45.23544,-55.22014,-65.52963,-56.02374], "fy":[-99.63999,-94.40639,-87.63274,-94.04329]}, - {"t":0.40812, "x":2.90175, "y":3.67158, "heading":-2.8937, "vx":-1.32449, "vy":-2.24266, "omega":1.16881, "ax":-3.2654, "ay":-5.52704, "alpha":1.13433, "fx":[-48.32976,-55.57265,-62.60354,-55.66788], "fy":[-98.09546,-94.1313,-89.66168,-94.16502]}, - {"t":0.43727, "x":2.86175, "y":3.60385, "heading":-2.85963, "vx":-1.41968, "vy":-2.40378, "omega":1.20188, "ax":-3.26592, "ay":-5.52909, "alpha":0.46919, "fx":[-52.58744,-55.64784,-58.48493,-55.48926], "fy":[-95.76812,-94.00047,-92.28615,-94.13808]}, - {"t":0.46642, "x":2.81898, "y":3.53143, "heading":-2.82459, "vx":-1.51489, "vy":-2.56496, "omega":1.21555, "ax":-3.2608, "ay":-5.52213, "alpha":-0.50816, "fx":[-58.62775,-55.29294,-52.25758,-55.6825], "fy":[-92.02905,-94.09635,-95.78617,-93.80766]}, - {"t":0.49557, "x":2.77343, "y":3.45431, "heading":-2.78916, "vx":-1.60994, "vy":-2.72593, "omega":1.20074, "ax":-3.2384, "ay":-5.48643, "alpha":-2.05587, "fx":[-67.48692,-54.25692,-41.82871,-56.76416], "fy":[-85.47983,-94.54257,-100.52838,-92.73979]}, - {"t":0.52472, "x":2.72512, "y":3.37252, "heading":-2.75416, "vx":-1.70435, "vy":-2.88587, "omega":1.14081, "ax":-3.16386, "ay":-5.34318, "alpha":-4.76102, "fx":[-80.645,-52.09415,-21.76358,-60.76236], "fy":[-72.71082,-95.52662,-106.27219,-89.03451]}, - {"t":0.55387, "x":2.67409, "y":3.28612, "heading":-2.7209, "vx":-1.79658, "vy":-3.04163, "omega":1.00202, "ax":-3.10919, "ay":-4.49061, "alpha":-10.60776, "fx":[-97.21085,-48.0988,19.0455,-85.28129], "fy":[-47.215,-97.23104,-106.06385,-55.02634]}, - {"t":0.58303, "x":2.6204, "y":3.19554, "heading":-2.69169, "vx":-1.88721, "vy":-3.17254, "omega":0.69279, "ax":-2.99161, "ay":-4.06982, "alpha":-12.45004, "fx":[-96.81852,-45.52916,25.64857,-86.84694], "fy":[-44.79529,-97.25487,-102.89571,-31.95993]}, - {"t":0.61218, "x":2.56411, "y":3.10133, "heading":-2.67149, "vx":-1.97442, "vy":-3.29118, "omega":0.32985, "ax":-2.13652, "ay":-3.82205, "alpha":-11.04068, "fx":[-82.43415,-38.73218,20.47772,-44.67754], "fy":[-46.05676,-89.75982,-89.77055,-34.46069]}, - {"t":0.64133, "x":2.50565, "y":3.00377, "heading":-2.66188, "vx":-2.0367, "vy":-3.4026, "omega":0.008, "ax":0.32083, "ay":-0.24817, "alpha":-0.12696, "fx":[5.01355,5.31547,5.90054,5.59911], "fy":[-4.08265,-4.66678,-4.36006,-3.77589]}, - {"t":0.67048, "x":2.44641, "y":2.90447, "heading":-2.66165, "vx":-2.02735, "vy":-3.40983, "omega":0.0043, "ax":0.12592, "ay":-0.0749, "alpha":-0.00026, "fx":[2.14086,2.14149,2.14271,2.14208], "fy":[-1.27378,-1.275,-1.27436,-1.27314]}, - {"t":0.69963, "x":2.38737, "y":2.80504, "heading":-2.66152, "vx":-2.02368, "vy":-3.41202, "omega":0.00429, "ax":0.00829, "ay":-0.00492, "alpha":0.0, "fx":[0.14108,0.14109,0.14109,0.14109], "fy":[-0.08368,-0.08368,-0.08368,-0.08368]}, - {"t":0.72878, "x":2.32838, "y":2.70557, "heading":-2.66139, "vx":-2.02344, "vy":-3.41216, "omega":0.00429, "ax":-0.1026, "ay":0.0609, "alpha":0.00001, "fx":[-1.74512,-1.74515,-1.74521,-1.74518], "fy":[1.03595,1.03601,1.03598,1.03593]}, - {"t":0.75793, "x":2.26935, "y":2.60613, "heading":-2.66127, "vx":-2.02643, "vy":-3.41038, "omega":0.00429, "ax":-0.29691, "ay":0.17694, "alpha":0.00004, "fx":[-5.05024,-5.05033,-5.0505,-5.05041], "fy":[3.00972,3.00989,3.0098,3.00962]}, - {"t":0.78709, "x":2.21015, "y":2.50679, "heading":-2.66114, "vx":-2.03509, "vy":-3.40523, "omega":0.0043, "ax":-0.72306, "ay":0.43523, "alpha":0.00012, "fx":[-12.2987,-12.29899,-12.29955,-12.29927], "fy":[7.40296,7.40352,7.40321,7.40265]}, - {"t":0.81624, "x":2.15052, "y":2.4077, "heading":-2.66102, "vx":-2.05616, "vy":-3.39254, "omega":0.0043, "ax":-1.60856, "ay":0.99046, "alpha":0.00039, "fx":[-27.35987,-27.36064,-27.36245,-27.36168], "fy":[16.84713,16.84894,16.84782,16.84601]}, - {"t":0.84539, "x":2.08989, "y":2.30923, "heading":-2.66089, "vx":-2.10306, "vy":-3.36366, "omega":0.00431, "ax":-2.90209, "ay":1.86672, "alpha":0.00106, "fx":[-49.36084,-49.36182,-49.36677,-49.36579], "fy":[31.75197,31.75676,31.75265,31.74787]}, - {"t":0.87454, "x":2.02735, "y":2.21197, "heading":-2.66077, "vx":-2.18766, "vy":-3.30925, "omega":0.00434, "ax":-3.92513, "ay":2.69614, "alpha":0.00215, "fx":[-66.76048,-66.75961,-66.77019,-66.77106], "fy":[45.86151,45.87072,45.85953,45.85032]}, - {"t":0.90369, "x":1.96191, "y":2.11664, "heading":-2.66064, "vx":-2.30208, "vy":-3.23065, "omega":0.0044, "ax":-4.41039, "ay":3.28178, "alpha":0.00367, "fx":[-75.01208,-75.00734,-75.02682,-75.03156], "fy":[55.82615,55.84043,55.81807,55.80379]}, - {"t":0.93284, "x":1.89293, "y":2.02386, "heading":-2.66051, "vx":-2.43065, "vy":-3.13498, "omega":0.00451, "ax":-4.55507, "ay":3.70876, "alpha":0.00325, "fx":[-77.47386,-77.46825,-77.48702,-77.49264], "fy":[63.09006,63.1012,63.07997,63.06883]}, - {"t":0.96199, "x":1.82014, "y":1.93405, "heading":-2.66038, "vx":-2.56343, "vy":-3.02687, "omega":0.00461, "ax":-4.38264, "ay":3.88051, "alpha":0.02798, "fx":[-74.48432,-74.43998,-74.61064,-74.65517], "fy":[66.0526,66.13911,65.96045,65.87348]}, - {"t":0.98784, "x":1.75241, "y":1.85709, "heading":-2.66026, "vx":-2.67673, "vy":-2.92655, "omega":0.00533, "ax":-4.03628, "ay":3.98127, "alpha":0.32152, "fx":[-67.80558,-67.44722,-69.48983,-69.88135], "fy":[68.24529,69.11627,67.22391,66.29564]}, - {"t":1.0137, "x":1.68186, "y":1.78277, "heading":-2.66012, "vx":-2.78107, "vy":-2.82363, "omega":0.01364, "ax":-0.49257, "ay":5.11316, "alpha":9.13517, "fx":[49.66346,6.87629,-47.54531,-42.50858], "fy":[83.04805,101.3982,88.29235,75.15504]}, - {"t":1.03955, "x":1.6098, "y":1.71149, "heading":-2.65977, "vx":-2.7938, "vy":-2.69145, "omega":0.24979, "ax":2.95271, "ay":3.86702, "alpha":13.35963, "fx":[96.18937,44.10141,-27.61501,88.22323], "fy":[44.75094,97.35247,101.47574,19.52858]}, - {"t":1.0654, "x":1.53857, "y":1.6432, "heading":-2.65331, "vx":-2.71747, "vy":-2.59149, "omega":0.59515, "ax":3.57147, "ay":3.67581, "alpha":13.13097, "fx":[99.94699,53.01857,-11.86125,101.89473], "fy":[40.2595,94.17264,106.1343,9.53171]}, - {"t":1.09125, "x":1.46951, "y":1.57744, "heading":-2.63793, "vx":-2.62515, "vy":-2.49646, "omega":0.9346, "ax":4.14684, "ay":4.42975, "alpha":6.33186, "fx":[93.56252,62.43588,34.87453,91.27322], "fy":[54.65746,88.74615,101.9967,55.99463]}, - {"t":1.1171, "x":1.40303, "y":1.51438, "heading":-2.61377, "vx":-2.51795, "vy":-2.38195, "omega":1.09829, "ax":4.41406, "ay":4.52549, "alpha":2.93557, "fx":[86.81048,69.33888,60.23497,83.94332], "fy":[65.42479,83.79897,90.20678,68.4784]}, - {"t":1.14295, "x":1.33942, "y":1.45432, "heading":-2.58538, "vx":-2.40384, "vy":-2.26496, "omega":1.17418, "ax":4.52701, "ay":4.51151, "alpha":1.18299, "fx":[81.91967,74.10279,71.56018,80.42983], "fy":[71.7899,79.86193,82.01325,73.29268]}, - {"t":1.1688, "x":1.27879, "y":1.39727, "heading":-2.55502, "vx":-2.28681, "vy":-2.14833, "omega":1.20476, "ax":4.58216, "ay":4.48564, "alpha":0.11387, "fx":[78.42126,77.62062,77.45616,78.26659], "fy":[75.81298,76.63472,76.78917,75.96068]}, - {"t":1.19465, "x":1.2212, "y":1.34323, "heading":-2.52388, "vx":-2.16836, "vy":-2.03238, "omega":1.2077, "ax":4.6127, "ay":4.46128, "alpha":-0.61181, "fx":[75.87994,80.35254,80.90223,76.70813], "fy":[78.50728,73.91391,73.36858,77.75045]}, - {"t":1.2205, "x":1.16669, "y":1.29219, "heading":-2.49266, "vx":-2.04912, "vy":-1.91705, "omega":1.19188, "ax":4.63121, "ay":4.44028, "alpha":-1.14032, "fx":[74.00412,82.55104,83.07434,75.4724], "fy":[80.38848,71.57126,71.05791,79.09359]}, - {"t":1.24635, "x":1.11526, "y":1.24411, "heading":-2.46185, "vx":-1.92939, "vy":-1.80226, "omega":1.16241, "ax":4.64313, "ay":4.42247, "alpha":-1.54442, "fx":[72.60398,84.36531,84.51124,74.43293], "fy":[81.73968,69.52422,69.46178,80.17394]}, - {"t":1.27221, "x":1.06694, "y":1.199, "heading":-2.4318, "vx":-1.80936, "vy":-1.68794, "omega":1.12248, "ax":4.65116, "ay":4.40737, "alpha":-1.86435, "fx":[71.55316,85.88948,85.4907,73.52594], "fy":[82.72771,67.71749,68.34509,81.08195]}, - {"t":1.29806, "x":1.02172, "y":1.15684, "heading":-2.40278, "vx":-1.68913, "vy":-1.574, "omega":1.07429, "ax":4.65671, "ay":4.3945, "alpha":-2.12421, "fx":[70.76456,87.18649,86.16971,72.71647], "fy":[83.45721,66.1123,67.56058,81.86693]}, - {"t":1.32391, "x":0.97961, "y":1.11762, "heading":-2.37501, "vx":-1.56875, "vy":-1.4604, "omega":1.01937, "ax":4.66063, "ay":4.38348, "alpha":-2.33939, "fx":[70.17588,88.30058,86.64363,71.98405], "fy":[83.99746,64.68012,67.01154,82.55794]}, - {"t":1.34976, "x":0.94061, "y":1.08133, "heading":-2.34866, "vx":-1.44826, "vy":-1.34708, "omega":0.9589, "ax":4.66344, "ay":4.37398, "alpha":-2.52023, "fx":[69.74093,89.26423,86.97391,71.31611], "fy":[84.39657,63.39898,66.6318,83.17327]}, - {"t":1.37561, "x":0.90473, "y":1.04797, "heading":-2.32387, "vx":-1.32771, "vy":-1.23401, "omega":0.89375, "ax":4.66547, "ay":4.36574, "alpha":-2.67403, "fx":[69.42436,90.10216,87.20208,70.70453], "fy":[84.68937,62.2512,66.37444,83.72501]}, - {"t":1.40146, "x":0.87197, "y":1.01753, "heading":-2.30076, "vx":-1.2071, "vy":-1.12115, "omega":0.82462, "ax":4.66694, "ay":4.35855, "alpha":-2.80613, "fx":[69.19829,90.83374,87.35737,70.14389], "fy":[84.90212,61.22207,66.20519,84.2216]}, - {"t":1.42731, "x":0.84232, "y":0.99, "heading":-2.27945, "vx":-1.08646, "vy":-1.00848, "omega":0.75208, "ax":4.66801, "ay":4.35224, "alpha":-2.92057, "fx":[69.04025,91.47453,87.46107,69.63039], "fy":[85.05518,60.29904,66.09842,84.66913]}, - {"t":1.45316, "x":0.8158, "y":0.96538, "heading":-2.26001, "vx":-0.96578, "vy":-0.89597, "omega":0.67658, "ax":4.66879, "ay":4.34667, "alpha":-3.02052, "fx":[68.93171,92.03726,87.52916,69.1613], "fy":[85.16487,59.47114,66.03449,85.07221]}, - {"t":1.47901, "x":0.79239, "y":0.94367, "heading":-2.24251, "vx":-0.84509, "vy":-0.7836, "omega":0.5985, "ax":4.66936, "ay":4.34172, "alpha":-3.10847, "fx":[68.85717,92.53246,87.57389,68.73458], "fy":[85.24455,58.72876,65.99812,85.43438]}, - {"t":1.50486, "x":0.7721, "y":0.92487, "heading":-2.22704, "vx":-0.72438, "vy":-0.67136, "omega":0.51814, "ax":4.66977, "ay":4.33729, "alpha":-3.18647, "fx":[68.80352,92.96894,87.60489,68.34867], "fy":[85.30534,58.06337,65.9772,85.75847]}, - {"t":1.53072, "x":0.75494, "y":0.90896, "heading":-2.21365, "vx":-0.60366, "vy":-0.55924, "omega":0.43577, "ax":4.67006, "ay":4.3333, "alpha":-3.25619, "fx":[68.75957,93.35411,87.62982,68.00235], "fy":[85.35663,57.46742,65.96203,86.04673]}, - {"t":1.55657, "x":0.74089, "y":0.89595, "heading":-2.20238, "vx":-0.48294, "vy":-0.44722, "omega":0.35159, "ax":4.67026, "ay":4.32968, "alpha":-3.31902, "fx":[68.7157,93.6942,87.65489,67.69469], "fy":[85.40642,56.93426,65.94473,86.301]}, - {"t":1.58242, "x":0.72997, "y":0.88584, "heading":-2.19329, "vx":-0.36221, "vy":-0.33529, "omega":0.26579, "ax":4.67039, "ay":4.32637, "alpha":-3.37614, "fx":[68.66365,93.99446,87.68518,67.42495], "fy":[85.46155,56.4581,65.91882,86.52276]}, - {"t":1.60827, "x":0.72217, "y":0.87862, "heading":-2.18642, "vx":-0.24147, "vy":-0.22345, "omega":0.17851, "ax":4.67047, "ay":4.32332, "alpha":-3.42851, "fx":[68.59634,94.25927,87.72488,67.19262], "fy":[85.52784,56.03394,65.87895,86.71319]}, - {"t":1.63412, "x":0.71748, "y":0.87428, "heading":-2.18181, "vx":-0.12074, "vy":-0.11169, "omega":0.08988, "ax":4.67049, "ay":4.3205, "alpha":-3.47697, "fx":[68.50769,94.49225,87.77745,66.99735], "fy":[85.61021,55.65755,65.82064,86.87318]}, - {"t":1.65997, "x":0.71592, "y":0.87284, "heading":-2.17949, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/C_LEFT_PATH1.traj b/src/main/deploy/choreo/C_LEFT_PATH1.traj deleted file mode 100644 index 374e73c6..00000000 --- a/src/main/deploy/choreo/C_LEFT_PATH1.traj +++ /dev/null @@ -1,67 +0,0 @@ -{ - "name":"C_LEFT_PATH1", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":7.142665386199951, "y":6.064190864562988, "heading":1.5707963267948966, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":5.227500915527344, "y":5.382014274597168, "heading":1.102853734231975, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":3.0}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"7.142665386199951 m", "val":7.142665386199951}, "y":{"exp":"6.064190864562988 m", "val":6.064190864562988}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"5.227500915527344 m", "val":5.227500915527344}, "y":{"exp":"5.382014274597168 m", "val":5.382014274597168}, "heading":{"exp":"1.102853734231975 rad", "val":1.102853734231975}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"3 m / s", "val":3.0}}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.14388], - "samples":[ - {"t":0.0, "x":7.14267, "y":6.06419, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.07535, "ay":-2.16461, "alpha":-0.55986, "fx":[-103.96916,-104.54507,-102.796,-102.04932], "fy":[-35.11041,-33.37658,-38.4328,-40.35796]}, - {"t":0.03813, "x":7.13825, "y":6.06262, "heading":1.5708, "vx":-0.23165, "vy":-0.08254, "omega":-0.02135, "ax":-6.07468, "ay":-2.16441, "alpha":-0.56671, "fx":[-103.96569,-104.54812,-102.77901,-102.02166], "fy":[-35.08543,-33.33199,-38.44844,-40.39787]}, - {"t":0.07626, "x":7.125, "y":6.0579, "heading":1.56998, "vx":-0.46327, "vy":-0.16506, "omega":-0.04296, "ax":-6.07389, "ay":-2.16416, "alpha":-0.57494, "fx":[-103.9605,-104.55224,-102.75969,-101.98791], "fy":[-35.05844,-33.27703,-38.46437,-40.44707]}, - {"t":0.11439, "x":7.10292, "y":6.05003, "heading":1.56834, "vx":-0.69487, "vy":-0.24758, "omega":-0.06488, "ax":-6.07291, "ay":-2.16386, "alpha":-0.58499, "fx":[-103.95329,-104.55762,-102.737,-101.9462], "fy":[-35.02795,-33.20863,-38.48143,-40.50828]}, - {"t":0.15252, "x":7.07201, "y":6.03902, "heading":1.56587, "vx":-0.92642, "vy":-0.33009, "omega":-0.08718, "ax":-6.0717, "ay":-2.16348, "alpha":-0.59756, "fx":[-103.9436,-104.56459,-102.70936,-101.89366], "fy":[-34.99174,-33.12224,-38.5009,-40.58561]}, - {"t":0.19065, "x":7.03227, "y":6.02486, "heading":1.56255, "vx":-1.15793, "vy":-0.41258, "omega":-0.10997, "ax":-6.07013, "ay":-2.16299, "alpha":-0.61373, "fx":[-103.93072,-104.57362,-102.6743,-101.82581], "fy":[-34.94628,-33.0107,-38.5248,-40.68549]}, - {"t":0.22878, "x":6.98371, "y":6.00755, "heading":1.55835, "vx":-1.38938, "vy":-0.49505, "omega":-0.13337, "ax":-6.06803, "ay":-2.16234, "alpha":-0.63529, "fx":[-103.91346,-104.58551,-102.62771,-101.73514], "fy":[-34.88564,-32.8621,-38.55647,-40.81864]}, - {"t":0.26691, "x":6.92632, "y":5.98711, "heading":1.55327, "vx":-1.62075, "vy":-0.5775, "omega":-0.15759, "ax":-6.06509, "ay":-2.16142, "alpha":-0.66549, "fx":[-103.88968,-104.6016,-102.56223,-101.60807], "fy":[-34.7991,-32.65507,-38.60192,-41.00434]}, - {"t":0.30503, "x":6.86012, "y":5.96352, "heading":1.54726, "vx":-1.85201, "vy":-0.65991, "omega":-0.18297, "ax":-6.06066, "ay":-2.16004, "alpha":-0.7108, "fx":[-103.85505,-104.62447,-102.46323,-101.41732], "fy":[-34.66507,-32.34709,-38.67312,-41.28107]}, - {"t":0.34316, "x":6.78509, "y":5.93678, "heading":1.54028, "vx":-2.0831, "vy":-0.74227, "omega":-0.21007, "ax":-6.05323, "ay":-2.15771, "alpha":-0.78631, "fx":[-103.79935,-104.65959,-102.29698,-101.09865], "fy":[-34.43269,-31.83964,-38.7976,-41.7384]}, - {"t":0.38129, "x":6.70127, "y":5.90691, "heading":1.53227, "vx":-2.3139, "vy":-0.82455, "omega":-0.24005, "ax":-6.03821, "ay":-2.153, "alpha":-0.93706, "fx":[-103.691,-104.72058,-101.9645,-100.4569], "fy":[-33.94749,-30.84161,-39.05574,-42.64302]}, - {"t":0.41942, "x":6.60865, "y":5.87391, "heading":1.52312, "vx":-2.54414, "vy":-0.90664, "omega":-0.27578, "ax":-5.99205, "ay":-2.13836, "alpha":-1.38517, "fx":[-103.36024,-104.84398,-100.99753,-98.49039], "fy":[-32.41771,-27.95378,-39.82187,-45.29842]}, - {"t":0.45755, "x":6.50729, "y":5.83778, "heading":1.51261, "vx":-2.77261, "vy":-0.98817, "omega":-0.32859, "ax":-1.39276, "ay":-0.44577, "alpha":-22.77719, "fx":[41.89701,-81.61998,-77.51021,22.47171], "fy":[65.40251,43.88496,-54.65635,-84.9607]}, - {"t":0.49568, "x":6.40056, "y":5.79978, "heading":1.50008, "vx":-2.82571, "vy":-1.00517, "omega":-1.19707, "ax":0.00411, "ay":-0.01321, "alpha":-20.06101, "fx":[55.79014,-48.29105,-55.45924,48.23971], "fy":[47.99473,55.44482,-48.5349,-55.80367]}, - {"t":0.53381, "x":6.29282, "y":5.76145, "heading":1.45443, "vx":-2.82556, "vy":-1.00567, "omega":-1.96199, "ax":-0.0015, "ay":0.0046, "alpha":-7.30239, "fx":[20.99868,-16.64812,-21.05808,16.60545], "fy":[16.70763,21.10409,-16.54594,-20.95262]}, - {"t":0.57194, "x":6.18508, "y":5.7231, "heading":1.37962, "vx":-2.82561, "vy":-1.0055, "omega":-2.24042, "ax":0.0046, "ay":-0.01329, "alpha":7.4473, "fx":[-22.56365,15.37358,22.74261,-15.23936], "fy":[-15.54232,-22.86931,15.0706,22.43649]}, - {"t":0.61007, "x":6.07735, "y":5.68475, "heading":1.2942, "vx":-2.82544, "vy":-1.00601, "omega":-1.95646, "ax":-0.00028, "ay":0.00251, "alpha":19.96237, "fx":[-64.02004,35.70858,63.98045,-35.68796], "fy":[-35.6438,-63.96932,35.75271,64.03114]}, - {"t":0.6482, "x":5.96961, "y":5.6464, "heading":1.2196, "vx":-2.82545, "vy":-1.00591, "omega":-1.19531, "ax":1.38358, "ay":0.47192, "alpha":22.69589, "fx":[-64.80192,69.32857,87.42025,2.19052], "fy":[-36.28161,-59.4983,37.67827,90.2106]}, - {"t":0.68633, "x":5.86289, "y":5.60839, "heading":1.17402, "vx":-2.77269, "vy":-0.98792, "omega":-0.32993, "ax":5.99296, "ay":2.13634, "alpha":1.3793, "fx":[102.19497,105.07849,102.1267,98.35425], "fy":[35.8889,26.90174,36.85692,45.70644]}, - {"t":0.72446, "x":5.76152, "y":5.57227, "heading":1.16144, "vx":-2.54419, "vy":-0.90646, "omega":-0.27734, "ax":6.0386, "ay":2.15192, "alpha":0.9382, "fx":[102.85445,104.90933,102.78287,100.31287], "fy":[36.39158,30.13973,36.85873,43.02381]}, - {"t":0.76259, "x":5.6689, "y":5.53927, "heading":1.15087, "vx":-2.31394, "vy":-0.82441, "omega":-0.24157, "ax":6.05346, "ay":2.15697, "alpha":0.78903, "fx":[103.06211,104.83107,103.01935,100.9583], "fy":[36.57319,31.23938,36.84292,42.1025]}, - {"t":0.80072, "x":5.58507, "y":5.50941, "heading":1.14166, "vx":-2.08312, "vy":-0.74216, "omega":-0.21148, "ax":6.06082, "ay":2.15947, "alpha":0.71418, "fx":[103.16073,104.7879,103.14369,101.27912], "fy":[36.67469,31.7919,36.8243,41.63729]}, - {"t":0.83885, "x":5.51005, "y":5.48268, "heading":1.13359, "vx":-1.85203, "vy":-0.65982, "omega":-0.18425, "ax":6.06521, "ay":2.16097, "alpha":0.66922, "fx":[103.21691,104.76073,103.22148,101.47097], "fy":[36.74269,32.12407,36.8062,41.35669]}, - {"t":0.87697, "x":5.44384, "y":5.45909, "heading":1.12657, "vx":-1.62077, "vy":-0.57743, "omega":-0.15873, "ax":6.06813, "ay":2.16196, "alpha":0.63925, "fx":[103.25254,104.7421,103.2752,101.59861], "fy":[36.79254,32.34577,36.78975,41.16896]}, - {"t":0.9151, "x":5.38646, "y":5.43864, "heading":1.12052, "vx":-1.38939, "vy":-0.49499, "omega":-0.13436, "ax":6.0702, "ay":2.16266, "alpha":0.61784, "fx":[103.27695,104.72852,103.31463,101.68967], "fy":[36.83079,32.50429,36.77544,41.0345]}, - {"t":0.95323, "x":5.33789, "y":5.42134, "heading":1.11539, "vx":-1.15794, "vy":-0.41253, "omega":-0.1108, "ax":6.07176, "ay":2.16319, "alpha":0.60179, "fx":[103.29476,104.71818,103.34471,101.75789], "fy":[36.86072,32.6233,36.76346,40.93345]}, - {"t":0.99136, "x":5.29815, "y":5.40719, "heading":1.11117, "vx":-0.92643, "vy":-0.33005, "omega":-0.08785, "ax":6.07297, "ay":2.1636, "alpha":0.5893, "fx":[103.30851,104.71004,103.36823,101.81091], "fy":[36.88416,32.71596,36.75395,40.85474]}, - {"t":1.02949, "x":5.26725, "y":5.39617, "heading":1.10782, "vx":-0.69487, "vy":-0.24756, "omega":-0.06538, "ax":6.07393, "ay":2.16393, "alpha":0.57932, "fx":[103.31974,104.70345,103.38685,101.85327], "fy":[36.90222,32.79017,36.74694,40.79176]}, - {"t":1.06762, "x":5.24517, "y":5.38831, "heading":1.10533, "vx":-0.46328, "vy":-0.16505, "omega":-0.0433, "ax":6.07472, "ay":2.16419, "alpha":0.57115, "fx":[103.32941,104.69802,103.40166,101.88787], "fy":[36.9156,32.85095,36.74248,40.74027]}, - {"t":1.10575, "x":5.23192, "y":5.38359, "heading":1.10367, "vx":-0.23165, "vy":-0.08253, "omega":-0.02152, "ax":6.07538, "ay":2.16442, "alpha":0.56435, "fx":[103.33816,104.69346,103.41337,101.91664], "fy":[36.9248,32.90164,36.74056,40.69746]}, - {"t":1.14388, "x":5.2275, "y":5.38201, "heading":1.10285, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/C_LEFT_PATH2.traj b/src/main/deploy/choreo/C_LEFT_PATH2.traj deleted file mode 100644 index 67944916..00000000 --- a/src/main/deploy/choreo/C_LEFT_PATH2.traj +++ /dev/null @@ -1,188 +0,0 @@ -{ - "name":"C_LEFT_PATH2", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":5.281756401062012, "y":5.087327480316162, "heading":1.0513369818883893, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":4.582683086395264, "y":5.628561973571777, "heading":0.0, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":3.5206298828125, "y":5.799249172210693, "heading":0.0, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":1.73851478099823, "y":6.708444118499756, "heading":2.216612130911823, "intervals":18, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.0347819328308103, "y":7.59406852722168, "heading":2.216612130911823, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.7602181434631348, "y":6.701209545135498, "heading":2.216612130911823, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":3.4258036613464355, "y":5.675975322723389, "heading":2.09887087685183, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":3.0}}, "enabled":true}, - {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":3, "to":4, "data":{"type":"MaxVelocity", "props":{"max":2.0}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"5.281756401062012 m", "val":5.281756401062012}, "y":{"exp":"5.087327480316162 m", "val":5.087327480316162}, "heading":{"exp":"1.0513369818883893 rad", "val":1.0513369818883893}, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"4.582683086395264 m", "val":4.582683086395264}, "y":{"exp":"5.628561973571777 m", "val":5.628561973571777}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"3.5206298828125 m", "val":3.5206298828125}, "y":{"exp":"5.799249172210693 m", "val":5.799249172210693}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"1.73851478099823 m", "val":1.73851478099823}, "y":{"exp":"6.708444118499756 m", "val":6.708444118499756}, "heading":{"exp":"2.216612130911823 rad", "val":2.216612130911823}, "intervals":18, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.0347819328308105 m", "val":1.0347819328308103}, "y":{"exp":"7.59406852722168 m", "val":7.59406852722168}, "heading":{"exp":"2.216612130911823 rad", "val":2.216612130911823}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.7602181434631348 m", "val":1.7602181434631348}, "y":{"exp":"6.701209545135498 m", "val":6.701209545135498}, "heading":{"exp":"2.216612130911823 rad", "val":2.216612130911823}, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"3.4258036613464355 m", "val":3.4258036613464355}, "y":{"exp":"5.675975322723389 m", "val":5.675975322723389}, "heading":{"exp":"2.09887087685183 rad", "val":2.09887087685183}, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"3 m / s", "val":3.0}}}, "enabled":true}, - {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":3, "to":4, "data":{"type":"MaxVelocity", "props":{"max":{"exp":"2 m / s", "val":2.0}}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,0.53094,0.89279,1.58918,2.31195,2.92887,3.8144], - "samples":[ - {"t":0.0, "x":5.28176, "y":5.08733, "heading":1.05134, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-4.55618, "ay":4.56195, "alpha":0.2017, "fx":[-78.40073,-78.02431,-76.58228,-76.99006], "fy":[76.69549,77.0735,78.50784,78.11275]}, - {"t":0.02413, "x":5.28043, "y":5.08866, "heading":1.05134, "vx":-0.10996, "vy":0.1101, "omega":0.00487, "ax":-4.58632, "ay":4.5308, "alpha":0.20633, "fx":[-78.92408,-78.55165,-77.08355,-77.4887], "fy":[76.14281,76.52164,78.00173,77.60444]}, - {"t":0.04827, "x":5.27644, "y":5.09263, "heading":1.05145, "vx":-0.22064, "vy":0.21944, "omega":0.00985, "ax":-4.61958, "ay":4.49594, "alpha":0.21147, "fx":[-79.50115,-79.13353,-77.63716,-78.039], "fy":[75.5244,75.90368,77.43506,77.03572]}, - {"t":0.0724, "x":5.26977, "y":5.09924, "heading":1.05169, "vx":-0.33213, "vy":0.32795, "omega":0.01495, "ax":-4.65646, "ay":4.45667, "alpha":0.2172, "fx":[-80.14045,-79.77872,-78.25159,-78.64925], "fy":[74.82801,75.20716,76.79645,76.39535]}, - {"t":0.09653, "x":5.2604, "y":5.10845, "heading":1.05205, "vx":-0.44451, "vy":0.4355, "omega":0.02019, "ax":-4.69757, "ay":4.41211, "alpha":0.22363, "fx":[-80.85234,-80.49788,-78.93723,-79.32955], "fy":[74.03819,74.41633,76.07149,75.66915]}, - {"t":0.12067, "x":5.2483, "y":5.12025, "heading":1.05254, "vx":-0.55788, "vy":0.54198, "omega":0.02559, "ax":-4.74365, "ay":4.36114, "alpha":0.23091, "fx":[-81.64948,-81.30412,-79.70692,-80.09232], "fy":[73.13521,73.51104,75.2417,74.83899]}, - {"t":0.1448, "x":5.23346, "y":5.1346, "heading":1.05316, "vx":-0.67236, "vy":0.64723, "omega":0.03116, "ax":-4.79566, "ay":4.30229, "alpha":0.23919, "fx":[-82.54757,-82.21372,-80.57663,-80.953], "fy":[72.0935,72.46505,74.28306,73.88136]}, - {"t":0.16894, "x":5.21583, "y":5.15147, "heading":1.05391, "vx":-0.7881, "vy":0.75106, "omega":0.03693, "ax":-4.85474, "ay":4.23364, "alpha":0.2487, "fx":[-83.56616,-83.24702,-81.5665,-81.93099], "fy":[70.87933,71.24368,73.16378,72.76523]}, - {"t":0.19307, "x":5.1954, "y":5.17083, "heading":1.0548, "vx":-0.90526, "vy":0.85324, "omega":0.04294, "ax":-4.92237, "ay":4.15259, "alpha":0.25973, "fx":[-84.72984,-84.42971,-82.7021,-83.05082], "fy":[69.4474,69.80016,71.84092,71.44888]}, - {"t":0.2172, "x":5.17212, "y":5.19263, "heading":1.05584, "vx":-1.02406, "vy":0.95346, "omega":0.0492, "ax":-5.00044, "ay":4.05557, "alpha":0.27265, "fx":[-86.06972,-85.79444,-84.01634,-84.34391], "fy":[67.73562,68.07008,70.25528,69.87503]}, - {"t":0.24134, "x":5.14595, "y":5.21682, "heading":1.05702, "vx":-1.14474, "vy":1.05133, "omega":0.05579, "ax":-5.09137, "ay":3.93754, "alpha":0.28799, "fx":[-87.62535,-87.38286,-85.5518,-85.85072], "fy":[65.65679,65.96253,68.32305,67.96304]}, - {"t":0.26547, "x":5.11684, "y":5.24334, "heading":1.05837, "vx":-1.26761, "vy":1.14636, "omega":0.06274, "ax":-5.19824, "ay":3.79121, "alpha":0.30646, "fx":[-89.44683,-89.24804,-87.36388,-87.6236], "fy":[63.08515,63.34559,65.92229,65.59625]}, - {"t":0.2896, "x":5.08473, "y":5.27211, "heading":1.05989, "vx":-1.39306, "vy":1.23785, "omega":0.07013, "ax":-5.325, "ay":3.60567, "alpha":0.32903, "fx":[-91.59651,-91.45634,-89.52422,-89.72984], "fy":[59.83385,60.02188,62.86953,62.60047]}, - {"t":0.31374, "x":5.04956, "y":5.30303, "heading":1.06158, "vx":-1.52157, "vy":1.32487, "omega":0.07807, "ax":-5.47644, "ay":3.36405, "alpha":0.35714, "fx":[-94.14798,-94.08632,-92.12288,-92.2535], "fy":[55.61594,55.6857,58.87848,58.70621]}, - {"t":0.33787, "x":5.01125, "y":5.33599, "heading":1.06346, "vx":-1.65374, "vy":1.40606, "omega":0.08669, "ax":-5.6577, "ay":3.03922, "alpha":0.39278, "fx":[-97.17466,-97.21589,-95.26258,-95.29022], "fy":[49.97493,49.84608,53.48391,53.48004]}, - {"t":0.36201, "x":4.96969, "y":5.37081, "heading":1.06555, "vx":-1.79028, "vy":1.47941, "omega":0.09617, "ax":-5.87183, "ay":2.58591, "alpha":0.43877, "fx":[-100.7047,-100.87033,-99.02238,-98.91548], "fy":[42.16046,41.68745,45.898,46.19666]}, - {"t":0.38614, "x":4.92477, "y":5.40726, "heading":1.06788, "vx":-1.93199, "vy":1.54182, "omega":0.10676, "ax":-6.11105, "ay":1.92682, "alpha":0.49864, "fx":[-104.57032,-104.84527,-103.31231,-103.06063], "fy":[30.9164,29.83196,34.74534,35.6049]}, - {"t":0.41027, "x":4.87637, "y":5.44503, "heading":1.07045, "vx":-2.07947, "vy":1.58832, "omega":0.11879, "ax":-6.32803, "ay":0.93327, "alpha":0.57471, "fx":[-107.94554,-108.15732,-107.36303,-107.08625], "fy":[14.21243,12.05424,17.66384,19.56833]}, - {"t":0.43441, "x":4.82434, "y":5.48364, "heading":1.07332, "vx":-2.23219, "vy":1.61084, "omega":0.13266, "ax":-6.35781, "ay":-0.56658, "alpha":0.65987, "fx":[-108.16396,-107.6649,-108.22585,-108.52316], "fy":[-10.55171,-14.34876,-8.65071,-4.99838]}, - {"t":0.45854, "x":4.76862, "y":5.52235, "heading":1.07652, "vx":-2.38563, "vy":1.59717, "omega":0.14859, "ax":-5.81875, "ay":-2.59575, "alpha":0.71758, "fx":[-99.34949,-96.84337,-98.68147,-101.02688], "fy":[-43.62222,-48.81464,-44.78814,-39.38684]}, - {"t":0.48267, "x":4.70935, "y":5.56014, "heading":1.08011, "vx":-2.52606, "vy":1.53452, "omega":0.16591, "ax":-4.43028, "ay":-4.57797, "alpha":0.68649, "fx":[-77.08758,-72.30962,-73.531,-78.50292], "fy":[-76.319,-80.82924,-79.59516,-74.73655]}, - {"t":0.50681, "x":4.64709, "y":5.59584, "heading":1.08411, "vx":-2.63298, "vy":1.42404, "omega":0.18247, "ax":-2.97641, "ay":-5.64416, "alpha":0.57431, "fx":[-53.18367,-48.11355,-47.93239,-53.28169], "fy":[-94.69912,-97.37316,-97.38538,-94.56461]}, - {"t":0.53094, "x":4.58268, "y":5.62856, "heading":1.08851, "vx":-2.70481, "vy":1.28782, "omega":0.19633, "ax":-2.71508, "ay":-5.73256, "alpha":0.54224, "fx":[-48.73577,-43.8723,-43.50216,-48.62057], "fy":[-96.3511,-98.66465,-98.72172,-96.29924]}, - {"t":0.54668, "x":4.53979, "y":5.64811, "heading":1.0916, "vx":-2.74753, "vy":1.19763, "omega":0.20487, "ax":-2.44834, "ay":-5.83501, "alpha":0.58796, "fx":[-44.56455,-39.22469,-38.57364,-44.21915], "fy":[-98.08233,-100.34697,-100.47183,-98.10651]}, - {"t":0.56241, "x":4.49626, "y":5.66623, "heading":1.09483, "vx":-2.78604, "vy":1.10583, "omega":0.21412, "ax":-2.23697, "ay":-5.89966, "alpha":0.64166, "fx":[-41.35024,-35.49242,-34.56752,-40.7907], "fy":[-99.16274,-101.42335,-101.58763,-99.23264]}, - {"t":0.57814, "x":4.45216, "y":5.6829, "heading":1.09819, "vx":-2.82124, "vy":1.01302, "omega":0.22421, "ax":-2.03176, "ay":-5.94968, "alpha":0.70569, "fx":[-38.2984,-31.84595,-30.60114,-37.49313], "fy":[-99.99774,-102.26129,-102.44935,-100.10107]}, - {"t":0.59387, "x":4.40752, "y":5.6981, "heading":1.10172, "vx":-2.8532, "vy":0.91941, "omega":0.23531, "ax":-1.8259, "ay":-5.98678, "alpha":0.78312, "fx":[-35.31447,-28.16727,-26.53485,-34.21579], "fy":[-100.62044,-102.88907,-103.08098,-100.74322]}, - {"t":0.60961, "x":4.3624, "y":5.71183, "heading":1.10542, "vx":-2.88193, "vy":0.82522, "omega":0.24763, "ax":-1.61906, "ay":-6.00931, "alpha":0.87827, "fx":[-32.41607,-24.44495,-22.33558,-30.9626], "fy":[-101.00599,-103.28343,-103.44956,-101.12754]}, - {"t":0.62534, "x":4.31686, "y":5.72407, "heading":1.10932, "vx":-2.9074, "vy":0.73068, "omega":0.26145, "ax":-1.41174, "ay":-6.01442, "alpha":0.99743, "fx":[-29.64368,-20.67928,-17.97376,-27.75643], "fy":[-101.11089,-103.40499,-103.49966,-101.19897]}, - {"t":0.64107, "x":4.27095, "y":5.73482, "heading":1.11343, "vx":-2.92961, "vy":0.63606, "omega":0.27714, "ax":-1.20468, "ay":-5.99779, "alpha":1.15008, "fx":[-27.0556,-16.87123,-13.40659,-24.63138], "fy":[-100.86945,-103.19576,-103.14604,-100.8717]}, - {"t":0.6568, "x":4.22471, "y":5.74408, "heading":1.11779, "vx":-2.94856, "vy":0.5417, "omega":0.29524, "ax":-0.99891, "ay":-5.95259, "alpha":1.35111, "fx":[-24.73641,-13.02125,-8.56833,-21.63839], "fy":[-100.17952,-102.56828,-102.25294,-100.00646]}, - {"t":0.67254, "x":4.1782, "y":5.75187, "heading":1.12244, "vx":-2.96428, "vy":0.44805, "omega":0.31649, "ax":-0.79594, "ay":-5.86749, "alpha":1.62518, "fx":[-22.81302,-9.12898,-3.35505,-18.85759], "fy":[-98.87494,-101.3857,-100.59285,-98.36349]}, - {"t":0.68827, "x":4.13146, "y":5.75819, "heading":1.12742, "vx":-2.9768, "vy":0.35574, "omega":0.34206, "ax":-0.59813, "ay":-5.72249, "alpha":2.01596, "fx":[-21.48299,-5.19267,2.4031,-16.42329], "fy":[-96.67013,-99.42416,-97.75994,-95.49758]}, - {"t":0.704, "x":4.08455, "y":5.76308, "heading":1.1328, "vx":-2.98621, "vy":0.26571, "omega":0.37378, "ax":-0.40942, "ay":-5.47917, "alpha":2.60803, "fx":[-21.06588,-1.20709,8.99363,-14.57719], "fy":[-93.03908,-96.29627,-92.96882,-90.49231]}, - {"t":0.71973, "x":4.03752, "y":5.76658, "heading":1.13868, "vx":-2.99265, "vy":0.17951, "omega":0.41481, "ax":-0.23698, "ay":-5.05429, "alpha":3.58663, "fx":[-22.09485,2.84527,16.91134,-13.78545], "fy":[-86.92042,-91.27699,-84.52569,-81.16524]}, - {"t":0.73547, "x":3.99041, "y":5.76878, "heading":1.14521, "vx":-2.99638, "vy":0.09999, "omega":0.47124, "ax":-0.09505, "ay":-4.23463, "alpha":5.42677, "fx":[-25.45484,7.02708,26.87789,-14.91729], "fy":[-75.88806,-82.8334,-68.23925,-61.15861]}, - {"t":0.7512, "x":3.94326, "y":5.76983, "heading":1.15262, "vx":-2.99788, "vy":0.03337, "omega":0.55661, "ax":-0.01201, "ay":-2.43816, "alpha":9.14852, "fx":[-32.37343,11.39798,37.83964,-17.68165], "fy":[-53.43893,-66.97644,-33.27863,-12.19528]}, - {"t":0.76693, "x":3.89609, "y":5.77005, "heading":1.16138, "vx":-2.99807, "vy":-0.00499, "omega":0.70055, "ax":0.0, "ay":0.52928, "alpha":11.14004, "fx":[-39.08927,16.02587,37.37673,-14.31361], "fy":[-4.96443,-29.73889,24.76553,45.94973]}, - {"t":0.78267, "x":3.84892, "y":5.77004, "heading":1.1724, "vx":-2.99807, "vy":0.00333, "omega":0.87581, "ax":0.03267, "ay":3.28534, "alpha":6.6929, "fx":[-30.06523,15.39098,26.24032,-9.34329], "fy":[49.85421,38.03266,63.38206,72.26204]}, - {"t":0.7984, "x":3.80176, "y":5.7705, "heading":1.18618, "vx":-2.99755, "vy":0.05502, "omega":0.9811, "ax":0.14267, "ay":4.64013, "alpha":3.6217, "fx":[-17.1606,12.2155,19.3603,-4.70817], "fy":[76.61382,72.93218,81.03837,85.12456]}, - {"t":0.81413, "x":3.75462, "y":5.77194, "heading":1.20161, "vx":-2.99531, "vy":0.12802, "omega":1.03808, "ax":0.29939, "ay":5.26613, "alpha":2.22518, "fx":[-7.71127,11.88424,16.54909,-0.35209], "fy":[88.89097,86.9038,90.06756,92.43939]}, - {"t":0.82986, "x":3.70753, "y":5.7746, "heading":1.21794, "vx":-2.9906, "vy":0.21087, "omega":1.07309, "ax":0.47977, "ay":5.60257, "alpha":1.48946, "fx":[-0.56192,13.18502,16.1596,3.86044], "fy":[95.29823,93.79,95.2105,96.89398]}, - {"t":0.8456, "x":3.66054, "y":5.77861, "heading":1.23483, "vx":-2.98305, "vy":0.29902, "omega":1.09652, "ax":0.67301, "ay":5.79837, "alpha":1.05533, "fx":[5.29998,15.33251,17.18474,7.9733], "fy":[98.91582,97.61187,98.31328,99.67333]}, - {"t":0.86133, "x":3.61369, "y":5.78404, "heading":1.25208, "vx":-2.97246, "vy":0.39024, "omega":1.11313, "ax":0.87529, "ay":5.91438, "alpha":0.77865, "fx":[10.4424,17.98559,19.09136,12.03404], "fy":[101.00098,99.82322,100.20231,101.38113]}, - {"t":0.87706, "x":3.56704, "y":5.79091, "heading":1.26959, "vx":-2.95869, "vy":0.48329, "omega":1.12538, "ax":1.14546, "ay":5.96835, "alpha":0.59209, "fx":[16.23652,22.03289,22.58284,17.08387], "fy":[101.97628,100.83953,101.07714,102.18684]}, - {"t":0.89279, "x":3.52063, "y":5.79925, "heading":1.2873, "vx":-2.94067, "vy":0.57719, "omega":1.13469, "ax":1.26649, "ay":6.06002, "alpha":0.55482, "fx":[18.54729,24.07227,24.40195,19.14926], "fy":[103.58933,102.42655,102.58741,103.71326]}, - {"t":0.91681, "x":3.45038, "y":5.81486, "heading":1.31454, "vx":-2.91026, "vy":0.72271, "omega":1.14802, "ax":1.60581, "ay":5.8604, "alpha":0.69501, "fx":[23.91573,30.67583,30.51123,24.15445], "fy":[100.39735,98.54759,99.02736,100.76235]}, - {"t":0.94082, "x":3.38096, "y":5.8339, "heading":1.34211, "vx":-2.8717, "vy":0.86344, "omega":1.16471, "ax":1.82416, "ay":5.58939, "alpha":0.91158, "fx":[26.99551,35.51866,34.75188,26.84766], "fy":[95.93902,93.20493,94.33449,96.81721]}, - {"t":0.96483, "x":3.31252, "y":5.85625, "heading":1.37008, "vx":-2.82789, "vy":0.99766, "omega":1.1866, "ax":1.949, "ay":5.16017, "alpha":1.26801, "fx":[28.13294,39.23392,37.67748,27.56347], "fy":[88.60788,84.64817,87.18933,90.64685]}, - {"t":0.98885, "x":3.24518, "y":5.88169, "heading":1.39857, "vx":-2.78109, "vy":1.12157, "omega":1.21705, "ax":1.88538, "ay":4.42806, "alpha":1.87127, "fx":[25.45825,40.1628,37.89474,24.76335], "fy":[75.35536,70.07014,75.70201,80.15295]}, - {"t":1.01286, "x":3.17894, "y":5.9099, "heading":1.4278, "vx":-2.73582, "vy":1.2279, "omega":1.26198, "ax":1.50187, "ay":3.22298, "alpha":2.72767, "fx":[16.79581,35.06811,33.25657,17.06479], "fy":[52.03664,46.8168,57.94681,62.48784]}, - {"t":1.03687, "x":3.11368, "y":5.94032, "heading":1.4581, "vx":-2.69975, "vy":1.3053, "omega":1.32748, "ax":0.89221, "ay":1.80808, "alpha":3.16756, "fx":[5.70859,23.91435,23.90427,7.17793], "fy":[24.62349,21.67284,36.85263,39.87051]}, - {"t":1.06089, "x":3.0491, "y":5.97218, "heading":1.48998, "vx":-2.67833, "vy":1.34871, "omega":1.40354, "ax":0.42474, "ay":0.83565, "alpha":2.70936, "fx":[-0.46478,13.99816,14.66682,0.69861], "fy":[7.9457,6.65778,20.41489,21.83801]}, - {"t":1.0849, "x":2.98491, "y":6.00481, "heading":1.52368, "vx":-2.66813, "vy":1.36878, "omega":1.46861, "ax":0.18551, "ay":0.36016, "alpha":1.98633, "fx":[-2.26275,8.11964,8.51755,-1.75234], "fy":[1.23593,0.74083,10.99447,11.53367]}, - {"t":1.10891, "x":2.92089, "y":6.03778, "heading":1.55895, "vx":-2.66367, "vy":1.37743, "omega":1.5163, "ax":0.07901, "ay":0.15251, "alpha":1.35037, "fx":[-2.20753,4.81625,4.88462,-2.11779], "fy":[-0.86855,-0.95039,6.05168,6.14391]}, - {"t":1.13293, "x":2.85695, "y":6.0709, "heading":1.59536, "vx":-2.66177, "vy":1.38109, "omega":1.54873, "ax":0.03354, "ay":0.06459, "alpha":0.84379, "fx":[-1.56607,2.81529,2.70552,-1.67244], "fy":[-1.14491,-1.03677,3.34128,3.23513]}, - {"t":1.15694, "x":2.79304, "y":6.10409, "heading":1.63255, "vx":-2.66097, "vy":1.38264, "omega":1.56899, "ax":0.01458, "ay":0.02804, "alpha":0.44167, "fx":[-0.82566,1.46318,1.32142,-0.96703], "fy":[-0.73813,-0.59653,1.69192,1.55059]}, - {"t":1.18095, "x":2.72915, "y":6.1373, "heading":1.67023, "vx":-2.66062, "vy":1.38332, "omega":1.5796, "ax":0.00712, "ay":0.01369, "alpha":0.10949, "fx":[-0.1335,0.43214,0.37571,-0.18992], "fy":[-0.0782,-0.02177,0.54386,0.48744]}, - {"t":1.20497, "x":2.66526, "y":6.17052, "heading":1.70816, "vx":-2.66045, "vy":1.38365, "omega":1.58223, "ax":0.00515, "ay":0.0099, "alpha":-0.18803, "fx":[0.50426,-0.46271,-0.32905,0.63794], "fy":[0.71876,0.5851,-0.38188,-0.24821]}, - {"t":1.22898, "x":2.60138, "y":6.20375, "heading":1.74616, "vx":-2.66032, "vy":1.38388, "omega":1.57771, "ax":0.00704, "ay":0.01353, "alpha":-0.48639, "fx":[1.14256,-1.34378,-0.90332,1.58321], "fy":[1.69352,1.25309,-1.23344,-0.79281]}, - {"t":1.25299, "x":2.5375, "y":6.23698, "heading":1.78404, "vx":-2.66016, "vy":1.38421, "omega":1.56603, "ax":0.01425, "ay":0.02738, "alpha":-0.82223, "fx":[1.87638,-2.29524,-1.39223,2.78036], "fy":[3.00306,2.10036,-2.07229,-1.16835]}, - {"t":1.27701, "x":2.47362, "y":6.27023, "heading":1.82165, "vx":-2.65981, "vy":1.38487, "omega":1.54629, "ax":0.03253, "ay":0.06244, "alpha":-1.23421, "fx":[2.86016,-3.34489,-1.7559,4.45368], "fy":[4.95873,3.37228,-2.83788,-1.24466]}, - {"t":1.30102, "x":2.40976, "y":6.3035, "heading":1.85878, "vx":-2.65903, "vy":1.38636, "omega":1.51665, "ax":0.07639, "ay":0.14629, "alpha":-1.76195, "fx":[4.37901,-4.38405,-1.78995,6.99221], "fy":[8.16054,5.58502,-3.20078,-0.59143]}, - {"t":1.32503, "x":2.34593, "y":6.33684, "heading":1.8952, "vx":-2.6572, "vy":1.38988, "omega":1.47434, "ax":0.18003, "ay":0.34291, "alpha":-2.43574, "fx":[7.00627,-4.9553,-0.91839,11.11642], "fy":[13.77439,9.8648,-2.18711,1.8789]}, - {"t":1.34905, "x":2.28217, "y":6.37031, "heading":1.9306, "vx":-2.65288, "vy":1.39811, "omega":1.41585, "ax":0.41914, "ay":0.78847, "alpha":-3.2145, "fx":[11.82875,-3.74639,2.31574,18.11998], "fy":[23.81875,18.55452,2.69333,8.57975]}, - {"t":1.37306, "x":2.21859, "y":6.40411, "heading":1.9646, "vx":-2.64281, "vy":1.41705, "omega":1.33866, "ax":0.92296, "ay":1.68983, "alpha":-3.72548, "fx":[20.16047,2.17806,11.0877,29.37094], "fy":[40.04659,35.02602,16.66995,23.23146]}, - {"t":1.39707, "x":2.15539, "y":6.43863, "heading":1.99675, "vx":-2.62065, "vy":1.45762, "omega":1.2492, "ax":1.72392, "ay":2.98758, "alpha":-3.22779, "fx":[31.4872,15.51239,27.46891,42.82512], "fy":[59.06549,57.39507,41.97319,44.83808]}, - {"t":1.42109, "x":2.09296, "y":6.47449, "heading":2.02674, "vx":-2.57925, "vy":1.52937, "omega":1.17169, "ax":5.10723, "ay":1.12859, "alpha":-1.55307, "fx":[86.17129,84.14589,87.62962,89.5433], "fy":[26.92443,23.99824,10.76308,15.10224]}, - {"t":1.4451, "x":2.03249, "y":6.51154, "heading":2.05488, "vx":-2.45661, "vy":1.55647, "omega":1.13439, "ax":5.80476, "ay":-2.3769, "alpha":-0.27846, "fx":[99.47599,98.62474,97.98566,98.86296], "fy":[-38.59114,-40.57506,-42.25772,-40.29796]}, - {"t":1.46911, "x":1.97518, "y":6.54823, "heading":2.08212, "vx":-2.31722, "vy":1.49939, "omega":1.12771, "ax":5.77747, "ay":-2.65871, "alpha":-0.18267, "fx":[98.81334,98.17076,97.72843,98.38019], "fy":[-44.03366,-45.40716,-46.40658,-45.04812]}, - {"t":1.49313, "x":1.9212, "y":6.58347, "heading":2.1092, "vx":-2.17848, "vy":1.43555, "omega":1.12332, "ax":5.76449, "ay":-2.7608, "alpha":-0.15035, "fx":[98.51143,97.94986,97.59048,98.15724], "fy":[-45.99077,-47.15406,-47.92425,-46.77281]}, - {"t":1.51714, "x":1.87055, "y":6.61715, "heading":2.13618, "vx":-2.04006, "vy":1.36925, "omega":1.11971, "ax":5.75711, "ay":-2.8135, "alpha":-0.13486, "fx":[98.3438,97.82058,97.508,98.03466], "fy":[-46.99497,-48.06133,-48.7135,-47.65766]}, - {"t":1.54115, "x":1.82322, "y":6.64922, "heading":2.16306, "vx":-1.90181, "vy":1.30169, "omega":1.11647, "ax":5.75237, "ay":-2.84568, "alpha":-0.12608, "fx":[98.23765,97.73437,97.45345,97.95913], "fy":[-47.60555,-48.62107,-49.19775,-48.19214]}, - {"t":1.56517, "x":1.77921, "y":6.67965, "heading":2.18987, "vx":-1.76367, "vy":1.23335, "omega":1.11344, "ax":5.74907, "ay":-2.86737, "alpha":-0.12058, "fx":[98.16428,97.67166,97.41494,97.90922], "fy":[-48.01636,-49.00361,-49.52495,-48.54734]}, - {"t":1.58918, "x":1.73851, "y":6.70844, "heading":2.21661, "vx":-1.62562, "vy":1.1645, "omega":1.11055, "ax":3.96406, "ay":4.84948, "alpha":-0.9629, "fx":[64.95696,62.64462,70.24963,71.85859], "fy":[84.79999,86.1889,80.00821,78.95579]}, - {"t":1.62933, "x":1.67644, "y":6.75911, "heading":2.26121, "vx":-1.46645, "vy":1.35922, "omega":1.07188, "ax":4.1774, "ay":4.01198, "alpha":-2.726, "fx":[65.04669,59.62464,79.15002,80.40415], "fy":[76.81907,78.07621,57.73405,60.34141]}, - {"t":1.66949, "x":1.62092, "y":6.81693, "heading":2.30425, "vx":-1.29871, "vy":1.52032, "omega":0.96243, "ax":2.10888, "ay":1.70449, "alpha":-11.82808, "fx":[35.42025,-11.79754,46.92093,72.94236], "fy":[67.496,45.44279,-21.17906,24.21156]}, - {"t":1.70964, "x":1.57047, "y":6.87935, "heading":2.34289, "vx":-1.21403, "vy":1.58876, "omega":0.48748, "ax":0.34002, "ay":0.25752, "alpha":-13.07521, "fx":[7.26292,-43.26472,6.46656,52.66957], "fy":[51.53475,6.12989,-44.51337,4.37038]}, - {"t":1.7498, "x":1.522, "y":6.94335, "heading":2.36246, "vx":-1.20038, "vy":1.5991, "omega":-0.03754, "ax":0.04615, "ay":0.0346, "alpha":-10.22534, "fx":[0.63897,-36.84398,1.11612,38.22905], "fy":[38.05867,0.42398,-37.01664,0.88833]}, - {"t":1.78995, "x":1.47383, "y":7.00759, "heading":2.36096, "vx":-1.19852, "vy":1.60049, "omega":-0.44813, "ax":0.00548, "ay":0.0041, "alpha":-6.74386, "fx":[-0.02001,-24.66839,0.21589,24.84521], "fy":[24.82308,-0.04463,-24.69055,0.19115]}, - {"t":1.8301, "x":1.42571, "y":7.07186, "heading":2.34296, "vx":-1.1983, "vy":1.60066, "omega":-0.71892, "ax":0.00058, "ay":0.00043, "alpha":-2.79586, "fx":[0.14571,-10.2531,-0.12588,10.27259], "fy":[10.27014,0.14322,-10.25555,-0.12837]}, - {"t":1.87026, "x":1.3776, "y":7.13613, "heading":2.3141, "vx":-1.19828, "vy":1.60067, "omega":-0.83119, "ax":0.00006, "ay":0.00004, "alpha":1.38027, "fx":[-0.2123,5.0635,0.21421,-5.0616], "fy":[-5.06183,-0.21254,5.06326,0.21397]}, - {"t":1.91041, "x":1.32948, "y":7.2004, "heading":2.28072, "vx":-1.19828, "vy":1.60068, "omega":-0.77576, "ax":0.0, "ay":0.0, "alpha":5.44082, "fx":[-1.50602,19.91671,1.50608,-19.91665], "fy":[-19.91666,-1.50603,19.91671,1.50608]}, - {"t":1.95057, "x":1.28137, "y":7.26468, "heading":2.24957, "vx":-1.19828, "vy":1.60068, "omega":-0.55729, "ax":0.00016, "ay":-0.00028, "alpha":9.09844, "fx":[-3.55149,33.21364,3.55769,-33.20881], "fy":[-33.21567,-3.5598,33.20678,3.54938]}, - {"t":1.99072, "x":1.23325, "y":7.32895, "heading":2.22719, "vx":-1.19827, "vy":1.60067, "omega":-0.19195, "ax":2.82278, "ay":-3.77062, "alpha":4.24398, "fx":[39.77136,62.83269,60.0716,29.38334], "fy":[-76.89365,-59.44048,-48.54879,-71.66542]}, - {"t":2.03087, "x":1.18741, "y":7.39018, "heading":2.21949, "vx":-1.08492, "vy":1.44926, "omega":-0.02154, "ax":3.84192, "ay":-5.13211, "alpha":0.14422, "fx":[64.76608,65.94784,65.94204,64.74411], "fy":[-87.73993,-86.8551,-86.84566,-87.74245]}, - {"t":2.07103, "x":1.14694, "y":7.44424, "heading":2.21862, "vx":-0.93066, "vy":1.24319, "omega":-0.01575, "ax":3.85608, "ay":-5.15102, "alpha":0.09088, "fx":[65.21924,65.96856,65.96575,65.20996], "fy":[-87.89789,-87.33689,-87.3346,-87.90038]}, - {"t":2.11118, "x":1.11268, "y":7.49001, "heading":2.21799, "vx":-0.77582, "vy":1.03635, "omega":-0.0121, "ax":3.86089, "ay":-5.15744, "alpha":0.07281, "fx":[65.37374,65.97534,65.97351,65.36775], "fy":[-87.95147,-87.50109,-87.50009,-87.95356]}, - {"t":2.15134, "x":1.08464, "y":7.52746, "heading":2.2175, "vx":-0.62079, "vy":0.82926, "omega":-0.00918, "ax":3.8633, "ay":-5.16067, "alpha":0.06372, "fx":[65.45163,65.97869,65.97737,65.44711], "fy":[-87.97844,-87.58386,-87.5833,-87.98024]}, - {"t":2.19149, "x":1.06283, "y":7.5566, "heading":2.21713, "vx":-0.46566, "vy":0.62204, "omega":-0.00662, "ax":3.86476, "ay":-5.16261, "alpha":0.05825, "fx":[65.49856,65.98069,65.97967,65.49488], "fy":[-87.99468,-87.63374,-87.63337,-87.99628]}, - {"t":2.23164, "x":1.04725, "y":7.57741, "heading":2.21687, "vx":-0.31048, "vy":0.41474, "omega":-0.00428, "ax":3.86573, "ay":-5.16391, "alpha":0.0546, "fx":[65.52994,65.98203,65.9812,65.52677], "fy":[-88.00552,-87.66708,-87.66681,-88.00699]}, - {"t":2.2718, "x":1.0379, "y":7.5899, "heading":2.2167, "vx":-0.15525, "vy":0.20739, "omega":-0.00209, "ax":3.86643, "ay":-5.16484, "alpha":0.05199, "fx":[65.55241,65.98299,65.98228,65.54958], "fy":[-88.01327,-87.69093,-87.69073,-88.01465]}, - {"t":2.31195, "x":1.03478, "y":7.59407, "heading":2.21661, "vx":0.0, "vy":0.0, "omega":0.0, "ax":3.93183, "ay":-5.11322, "alpha":-0.01564, "fx":[66.9442,66.81553,66.81451,66.94299], "fy":[-86.92431,-87.02325,-87.02431,-86.92551]}, - {"t":2.3428, "x":1.03665, "y":7.59164, "heading":2.21661, "vx":0.12128, "vy":-0.15772, "omega":-0.00048, "ax":3.93157, "ay":-5.11264, "alpha":-0.01593, "fx":[66.94103,66.81,66.80897,66.9398], "fy":[-86.91352,-87.01429,-87.01537,-86.91477]}, - {"t":2.37364, "x":1.04226, "y":7.58434, "heading":2.2166, "vx":0.24255, "vy":-0.31543, "omega":-0.00097, "ax":3.93128, "ay":-5.11197, "alpha":-0.01626, "fx":[66.93738,66.80362,66.80257,66.93613], "fy":[-86.90107,-87.00394,-87.00507,-86.90236]}, - {"t":2.40449, "x":1.05162, "y":7.57218, "heading":2.21657, "vx":0.36382, "vy":-0.47311, "omega":-0.00148, "ax":3.93093, "ay":-5.11119, "alpha":-0.01665, "fx":[66.93311,66.79617,66.7951,66.93184], "fy":[-86.88653,-86.99186,-86.99303,-86.88788]}, - {"t":2.43534, "x":1.06471, "y":7.55515, "heading":2.21652, "vx":0.48507, "vy":-0.63077, "omega":-0.00199, "ax":3.93053, "ay":-5.11026, "alpha":-0.01711, "fx":[66.92807,66.78736,66.78627,66.92676], "fy":[-86.86934,-86.97757,-86.97881,-86.87076]}, - {"t":2.46618, "x":1.08154, "y":7.53326, "heading":2.21646, "vx":0.60631, "vy":-0.7884, "omega":-0.00252, "ax":3.93004, "ay":-5.10915, "alpha":-0.01767, "fx":[66.92202,66.77678,66.77567,66.92067], "fy":[-86.8487,-86.96042,-86.96173,-86.8502]}, - {"t":2.49703, "x":1.10211, "y":7.50651, "heading":2.21638, "vx":0.72754, "vy":-0.946, "omega":-0.00306, "ax":3.92944, "ay":-5.1078, "alpha":-0.01835, "fx":[66.91462,66.76385,66.76271,66.91322], "fy":[-86.82345,-86.93943,-86.94084,-86.82506]}, - {"t":2.52787, "x":1.12642, "y":7.4749, "heading":2.21629, "vx":0.84875, "vy":-1.10355, "omega":-0.00363, "ax":3.92869, "ay":-5.1061, "alpha":-0.01919, "fx":[66.90536,66.74766,66.74648,66.90389], "fy":[-86.79186,-86.91318,-86.91472,-86.79361]}, - {"t":2.55872, "x":1.15447, "y":7.43843, "heading":2.21618, "vx":0.96993, "vy":-1.26106, "omega":-0.00422, "ax":3.92772, "ay":-5.10392, "alpha":-0.02029, "fx":[66.89344,66.72683,66.7256,66.89189], "fy":[-86.75119,-86.8794,-86.8811,-86.75314]}, - {"t":2.58957, "x":1.18626, "y":7.39711, "heading":2.21605, "vx":1.09109, "vy":-1.41849, "omega":-0.00485, "ax":3.92643, "ay":-5.101, "alpha":-0.02175, "fx":[66.87752,66.69901,66.69773,66.87587], "fy":[-86.69689,-86.83429,-86.83622,-86.69911]}, - {"t":2.62041, "x":1.22178, "y":7.35093, "heading":2.2159, "vx":1.2122, "vy":-1.57584, "omega":-0.00552, "ax":3.92463, "ay":-5.09692, "alpha":-0.0238, "fx":[66.85518,66.65998,66.65864,66.85341], "fy":[-86.62072,-86.77102,-86.7733,-86.62334]}, - {"t":2.65126, "x":1.26104, "y":7.29989, "heading":2.21573, "vx":1.33326, "vy":-1.73306, "omega":-0.00625, "ax":3.92191, "ay":-5.09077, "alpha":-0.02689, "fx":[66.82158,66.60127,66.59987,66.81962], "fy":[-86.50618,-86.67589,-86.67873,-86.50945]}, - {"t":2.6821, "x":1.30403, "y":7.24401, "heading":2.21553, "vx":1.45424, "vy":-1.89009, "omega":-0.00708, "ax":3.91736, "ay":-5.08049, "alpha":-0.03206, "fx":[66.76529,66.50301,66.50159,66.76309], "fy":[-86.31454,-86.51675,-86.52065,-86.31906]}, - {"t":2.71295, "x":1.35076, "y":7.18329, "heading":2.21532, "vx":1.57507, "vy":-2.0468, "omega":-0.00807, "ax":3.90821, "ay":-5.05982, "alpha":-0.04252, "fx":[66.65171,66.30513,66.30397,66.64919], "fy":[-85.92882,-86.19646,-86.20295,-85.93639]}, - {"t":2.7438, "x":1.4012, "y":7.11775, "heading":2.21507, "vx":1.69562, "vy":-2.20288, "omega":-0.00938, "ax":3.8803, "ay":-4.99707, "alpha":-0.07453, "fx":[66.30328,65.70226,65.70434,66.30127], "fy":[-84.75564,-85.22207,-85.24024,-84.77708]}, - {"t":2.77464, "x":1.45535, "y":7.04742, "heading":2.21478, "vx":1.81532, "vy":-2.35702, "omega":-0.01168, "ax":1.0751, "ay":-0.1485, "alpha":-2.84907, "fx":[19.95146,8.06574,16.92688,28.20459], "fy":[8.0915,-1.06749,-13.18837,-3.93963]}, - {"t":2.80549, "x":1.51186, "y":6.97465, "heading":2.21442, "vx":1.84848, "vy":-2.3616, "omega":-0.09956, "ax":1.56493, "ay":1.25097, "alpha":-2.14402, "fx":[27.08628,18.77561,26.3781,34.23583], "fy":[28.97803,23.30265,13.27069,19.56295]}, - {"t":2.83633, "x":1.56962, "y":6.9024, "heading":2.21135, "vx":1.89675, "vy":-2.32301, "omega":-0.1657, "ax":3.14875, "ay":2.68488, "alpha":-0.95686, "fx":[52.68932,50.03866,54.55979,56.94989], "fy":[49.08886,47.6938,42.09622,43.79733]}, - {"t":2.86718, "x":1.62962, "y":6.83202, "heading":2.20623, "vx":1.99388, "vy":-2.24019, "omega":-0.19521, "ax":3.96128, "ay":3.73014, "alpha":-0.34254, "fx":[66.69419,66.04188,68.09617,68.68875], "fy":[64.59837,64.53874,62.27172,62.38572]}, - {"t":2.89803, "x":1.69301, "y":6.76469, "heading":2.20021, "vx":2.11607, "vy":-2.12513, "omega":-0.20578, "ax":4.06659, "ay":4.34701, "alpha":-0.14329, "fx":[68.82086,68.54993,69.52903,69.78651], "fy":[74.36008,74.46106,73.51807,73.42607]}, - {"t":2.92887, "x":1.76022, "y":6.70121, "heading":2.19387, "vx":2.2415, "vy":-1.99104, "omega":-0.2102, "ax":3.83779, "ay":4.59586, "alpha":-0.12342, "fx":[64.98856,64.69948,65.57588,65.85462], "fy":[78.4897,78.61571,77.85634,77.73554]}, - {"t":2.96429, "x":1.84202, "y":6.63357, "heading":2.18642, "vx":2.37744, "vy":-1.82825, "omega":-0.21457, "ax":3.11979, "ay":4.33254, "alpha":-0.23562, "fx":[52.69911,51.92777,53.44861,54.19168], "fy":[74.26545,74.36514,73.11911,73.03132]}, - {"t":2.99971, "x":1.92819, "y":6.57153, "heading":2.17882, "vx":2.48795, "vy":-1.67479, "omega":-0.22292, "ax":1.8349, "ay":2.84694, "alpha":-0.50488, "fx":[31.12879,29.08708,31.31464,33.31375], "fy":[49.95012,49.18314,46.87919,47.68976]}, - {"t":3.03514, "x":2.01747, "y":6.51399, "heading":2.17092, "vx":2.55294, "vy":-1.57395, "omega":-0.2408, "ax":0.55656, "ay":0.91563, "alpha":-0.52712, "fx":[9.78266,7.53091,9.15365,11.40037], "fy":[17.43847,15.97836,13.70011,15.18153]}, - {"t":3.07056, "x":2.10825, "y":6.45881, "heading":2.16239, "vx":2.57266, "vy":-1.54152, "omega":-0.25947, "ax":0.131, "ay":0.21938, "alpha":-0.25979, "fx":[2.41092,1.29152,2.04588,3.16508], "fy":[4.66622,3.9168,2.79644,3.54716]}, - {"t":3.10598, "x":2.19945, "y":6.40435, "heading":2.1532, "vx":2.5773, "vy":-1.53374, "omega":-0.26867, "ax":0.03034, "ay":0.05102, "alpha":0.01872, "fx":[0.50221,0.58339,0.52992,0.44874], "fy":[0.80057,0.85403,0.93521,0.88175]}, - {"t":3.1414, "x":2.29076, "y":6.35005, "heading":2.14369, "vx":2.57837, "vy":-1.53194, "omega":-0.26801, "ax":0.00703, "ay":0.01184, "alpha":0.29926, "fx":[-0.11209,1.19349,0.35131,-0.95428], "fy":[-0.87255,-0.03034,1.2752,0.43308]}, - {"t":3.17682, "x":2.3821, "y":6.2958, "heading":2.13419, "vx":2.57862, "vy":-1.53152, "omega":-0.25741, "ax":0.00163, "ay":0.00275, "alpha":0.59934, "fx":[-0.45671,2.17397,0.51219,-2.1185], "fy":[-2.09955,-0.43773,2.19291,0.53117]}, - {"t":3.21224, "x":2.47344, "y":6.24155, "heading":2.12508, "vx":2.57868, "vy":-1.53142, "omega":-0.23618, "ax":0.00038, "ay":0.00064, "alpha":0.93838, "fx":[-0.78266,3.35968,0.79553,-3.34681], "fy":[-3.34242,-0.77825,3.36407,0.79994]}, - {"t":3.24766, "x":2.56478, "y":6.18731, "heading":2.11671, "vx":2.57869, "vy":-1.5314, "omega":-0.20294, "ax":0.00009, "ay":0.00015, "alpha":1.33778, "fx":[-1.16341,4.77239,1.16641,-4.7694], "fy":[-4.76839,-1.16239,4.77341,1.16743]}, - {"t":3.28308, "x":2.65612, "y":6.13306, "heading":2.10952, "vx":2.5787, "vy":-1.53139, "omega":-0.15556, "ax":-0.00008, "ay":0.0001, "alpha":1.82189, "fx":[-1.63455,6.48441,1.63171,-6.48721], "fy":[-6.48419,-1.63151,6.48743,1.63475]}, - {"t":3.31851, "x":2.74746, "y":6.07882, "heading":2.10401, "vx":2.57869, "vy":-1.53139, "omega":-0.09102, "ax":-0.87523, "ay":0.51978, "alpha":2.30221, "fx":[-17.24721,-6.74574,-12.72322,-22.83379], "fy":[0.50926,6.89358,17.15826,10.80431]}, - {"t":3.35393, "x":2.83825, "y":6.0249, "heading":2.10079, "vx":2.54769, "vy":-1.51298, "omega":-0.00947, "ax":-5.46887, "ay":3.24775, "alpha":0.04885, "fx":[-93.19585,-92.96949,-92.85175,-93.0783], "fy":[54.95034,55.32517,55.53563,55.16231]}, - {"t":3.38935, "x":2.92506, "y":5.97335, "heading":2.10045, "vx":2.35398, "vy":-1.39794, "omega":-0.00774, "ax":-5.51125, "ay":3.27293, "alpha":0.03002, "fx":[-93.85176,-93.71258,-93.63785,-93.7771], "fy":[55.49037,55.72286,55.85238,55.62047]}, - {"t":3.42477, "x":3.00498, "y":5.92588, "heading":2.10018, "vx":2.15876, "vy":-1.28201, "omega":-0.00668, "ax":-5.52532, "ay":3.28128, "alpha":0.02381, "fx":[-94.06929,-93.95889,-93.89897,-94.00942], "fy":[55.66968,55.85462,55.95742,55.77285]}, - {"t":3.46019, "x":3.07798, "y":5.88253, "heading":2.09994, "vx":1.96305, "vy":-1.16578, "omega":-0.00584, "ax":-5.53234, "ay":3.28545, "alpha":0.02072, "fx":[-94.17776,-94.08169,-94.02925,-94.12536], "fy":[55.75911,55.9203,56.00982,55.84891]}, - {"t":3.49561, "x":3.14405, "y":5.8433, "heading":2.09973, "vx":1.76709, "vy":-1.04941, "omega":-0.0051, "ax":-5.53654, "ay":3.28794, "alpha":0.01888, "fx":[-94.24274,-94.15523,-94.1073,-94.19484], "fy":[55.81268,55.95963,56.04121,55.89449]}, - {"t":3.53103, "x":3.20317, "y":5.80819, "heading":2.09955, "vx":1.57098, "vy":-0.93294, "omega":-0.00443, "ax":-5.53934, "ay":3.28961, "alpha":0.01765, "fx":[-94.28602,-94.20419,-94.15927,-94.24112], "fy":[55.84834,55.98581,56.06212,55.92486]}, - {"t":3.56645, "x":3.25534, "y":5.77721, "heading":2.0994, "vx":1.37477, "vy":-0.81642, "omega":-0.00381, "ax":-5.54134, "ay":3.29079, "alpha":0.01678, "fx":[-94.3169,-94.23914,-94.19636,-94.27415], "fy":[55.8738,56.0045,56.07705,55.94653]}, - {"t":3.60187, "x":3.30056, "y":5.75036, "heading":2.09926, "vx":1.17849, "vy":-0.69986, "omega":-0.00322, "ax":-5.54284, "ay":3.29168, "alpha":0.01612, "fx":[-94.34004,-94.26532,-94.22417,-94.29891], "fy":[55.89287,56.0185,56.08824,55.96278]}, - {"t":3.6373, "x":3.33882, "y":5.72763, "heading":2.09915, "vx":0.98215, "vy":-0.58326, "omega":-0.00264, "ax":-5.544, "ay":3.29237, "alpha":0.01561, "fx":[-94.35804,-94.28568,-94.24578,-94.31816], "fy":[55.90769,56.02938,56.09694,55.97541]}, - {"t":3.67272, "x":3.37013, "y":5.70904, "heading":2.09905, "vx":0.78578, "vy":-0.46664, "omega":-0.00209, "ax":-5.54493, "ay":3.29293, "alpha":0.01521, "fx":[-94.37243,-94.30195,-94.26306,-94.33355], "fy":[55.91955,56.03809,56.10389,55.98551]}, - {"t":3.70814, "x":3.39449, "y":5.69457, "heading":2.09898, "vx":0.58937, "vy":-0.35, "omega":-0.00155, "ax":-5.5457, "ay":3.29338, "alpha":0.01487, "fx":[-94.3842,-94.31526,-94.27719,-94.34615], "fy":[55.92924,56.04521,56.10958,55.99377]}, - {"t":3.74356, "x":3.41189, "y":5.68424, "heading":2.09893, "vx":0.39293, "vy":-0.23335, "omega":-0.00103, "ax":-5.54633, "ay":3.29376, "alpha":0.0146, "fx":[-94.394,-94.32635,-94.28897,-94.35664], "fy":[55.93732,56.05114,56.11432,56.00065]}, - {"t":3.77898, "x":3.42232, "y":5.67804, "heading":2.09889, "vx":0.19648, "vy":-0.11668, "omega":-0.00051, "ax":-5.54687, "ay":3.29408, "alpha":0.01436, "fx":[-94.40229,-94.33573,-94.29893,-94.36551], "fy":[55.94415,56.05616,56.11833,56.00646]}, - {"t":3.8144, "x":3.4258, "y":5.67598, "heading":2.09887, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/C_LEFT_PATH3.traj b/src/main/deploy/choreo/C_LEFT_PATH3.traj deleted file mode 100644 index 309d9a44..00000000 --- a/src/main/deploy/choreo/C_LEFT_PATH3.traj +++ /dev/null @@ -1,146 +0,0 @@ -{ - "name":"C_LEFT_PATH3", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":3.999176502227783, "y":5.206205368041992, "heading":2.1010083691287966, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.5805233716964722, "y":7.047026634216309, "heading":0.0, "intervals":34, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":1.0536435842514038, "y":7.575206756591797, "heading":2.217924532332081, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.5711495876312256, "y":7.018905162811279, "heading":0.0, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":3.5301125049591064, "y":5.400979518890381, "heading":2.077894951837786, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":3.0}}, "enabled":true}, - {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":1, "to":2, "data":{"type":"MaxVelocity", "props":{"max":1.0}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"3.999176502227783 m", "val":3.999176502227783}, "y":{"exp":"5.206205368041992 m", "val":5.206205368041992}, "heading":{"exp":"2.1010083691287966 rad", "val":2.1010083691287966}, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.5805233716964722 m", "val":1.5805233716964722}, "y":{"exp":"7.047026634216309 m", "val":7.047026634216309}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":34, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"1.0536435842514038 m", "val":1.0536435842514038}, "y":{"exp":"7.575206756591797 m", "val":7.575206756591797}, "heading":{"exp":"2.217924532332081 rad", "val":2.217924532332081}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.5711495876312256 m", "val":1.5711495876312256}, "y":{"exp":"7.018905162811279 m", "val":7.018905162811279}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"3.5301125049591064 m", "val":3.5301125049591064}, "y":{"exp":"5.400979518890381 m", "val":5.400979518890381}, "heading":{"exp":"2.077894951837786 rad", "val":2.077894951837786}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"3 m / s", "val":3.0}}}, "enabled":true}, - {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":1, "to":2, "data":{"type":"MaxVelocity", "props":{"max":{"exp":"1 m / s", "val":1.0}}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.34999,2.17412,2.66047,3.74072], - "samples":[ - {"t":0.0, "x":3.99918, "y":5.20621, "heading":2.10101, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.14437, "ay":3.89483, "alpha":0.00135, "fx":[-87.50979,-87.502,-87.49879,-87.50658], "fy":[66.24276,66.25304,66.2573,66.24702]}, - {"t":0.04219, "x":3.9946, "y":5.20967, "heading":2.10101, "vx":-0.21703, "vy":0.16431, "omega":0.00006, "ax":-5.14387, "ay":3.89445, "alpha":0.00137, "fx":[-87.50136,-87.4934,-87.49012,-87.49808], "fy":[66.23613,66.24663,66.25098,66.24049]}, - {"t":0.08437, "x":3.98087, "y":5.22007, "heading":2.10101, "vx":-0.43403, "vy":0.32861, "omega":0.00011, "ax":-5.14325, "ay":3.89399, "alpha":0.00141, "fx":[-87.49104,-87.48288,-87.47952,-87.48768], "fy":[66.22802,66.23879,66.24325,66.23249]}, - {"t":0.12656, "x":3.95798, "y":5.2374, "heading":2.10102, "vx":-0.65101, "vy":0.49289, "omega":0.00017, "ax":-5.14248, "ay":3.89341, "alpha":0.00145, "fx":[-87.47813,-87.46972,-87.46625,-87.47466], "fy":[66.21787,66.22897,66.23358,66.22248]}, - {"t":0.16875, "x":3.92594, "y":5.26166, "heading":2.10102, "vx":-0.86796, "vy":0.65714, "omega":0.00024, "ax":-5.14149, "ay":3.89266, "alpha":0.00151, "fx":[-87.46149,-87.45275,-87.44915,-87.45789], "fy":[66.2048,66.21633,66.22111,66.20959]}, - {"t":0.21094, "x":3.88475, "y":5.29284, "heading":2.10103, "vx":-1.08486, "vy":0.82136, "omega":0.0003, "ax":-5.14017, "ay":3.89165, "alpha":0.00159, "fx":[-87.43925,-87.43007,-87.4263,-87.43548], "fy":[66.18732,66.19942,66.20445,66.19235]}, - {"t":0.25312, "x":3.8344, "y":5.33096, "heading":2.10105, "vx":-1.30171, "vy":0.98554, "omega":0.00037, "ax":-5.13831, "ay":3.89024, "alpha":0.00169, "fx":[-87.40802,-87.39822,-87.3942,-87.40399], "fy":[66.16276,66.17568,66.18105,66.16814]}, - {"t":0.29531, "x":3.77492, "y":5.37599, "heading":2.10106, "vx":-1.51849, "vy":1.14965, "omega":0.00044, "ax":-5.1355, "ay":3.88812, "alpha":0.00185, "fx":[-87.36093,-87.3502,-87.34581,-87.35653], "fy":[66.12575,66.13989,66.14578,66.13164]}, - {"t":0.3375, "x":3.70628, "y":5.42796, "heading":2.10108, "vx":-1.73514, "vy":1.31368, "omega":0.00052, "ax":-5.13079, "ay":3.88455, "alpha":0.00213, "fx":[-87.28185,-87.26956,-87.26454,-87.27683], "fy":[66.0636,66.07978,66.08653,66.07035]}, - {"t":0.37969, "x":3.62852, "y":5.48683, "heading":2.1011, "vx":-1.95159, "vy":1.47756, "omega":0.00061, "ax":-5.12123, "ay":3.87731, "alpha":0.00268, "fx":[-87.12147,-87.106,-87.09973,-87.1152], "fy":[65.93754,65.95788,65.96639,65.94606]}, - {"t":0.42187, "x":3.54163, "y":5.55262, "heading":2.10113, "vx":-2.16764, "vy":1.64113, "omega":0.00072, "ax":-5.0915, "ay":3.85481, "alpha":0.0044, "fx":[-86.62275,-86.59738,-86.58732,-86.61269], "fy":[65.54556,65.57876,65.59282,65.55964]}, - {"t":0.46406, "x":3.44565, "y":5.62528, "heading":2.10116, "vx":-2.38244, "vy":1.80376, "omega":0.0009, "ax":-0.20864, "ay":0.15796, "alpha":0.29051, "fx":[-3.81983,-2.51736,-3.27871,-4.57953], "fy":[1.65395,2.41938,3.71966,2.95446]}, - {"t":0.50625, "x":3.34496, "y":5.70152, "heading":2.1012, "vx":-2.39124, "vy":1.81042, "omega":0.01316, "ax":-0.00001, "ay":0.00001, "alpha":0.2198, "fx":[-0.20373,0.78059,0.20333,-0.78099], "fy":[-0.78064,-0.20338,0.78094,0.20368]}, - {"t":0.54843, "x":3.24408, "y":5.7779, "heading":2.10175, "vx":-2.39124, "vy":1.81042, "omega":0.02243, "ax":0.0, "ay":0.0, "alpha":0.16816, "fx":[-0.15539,0.59746,0.15539,-0.59746], "fy":[-0.59746,-0.15539,0.59746,0.15539]}, - {"t":0.59062, "x":3.1432, "y":5.85427, "heading":2.1027, "vx":-2.39124, "vy":1.81042, "omega":0.02953, "ax":0.0, "ay":0.0, "alpha":0.13187, "fx":[-0.1214,0.46861,0.1214,-0.46861], "fy":[-0.46861,-0.1214,0.46861,0.1214]}, - {"t":0.63281, "x":3.04232, "y":5.93065, "heading":2.10394, "vx":-2.39124, "vy":1.81042, "omega":0.03509, "ax":0.0, "ay":0.0, "alpha":0.10759, "fx":[-0.09858,0.38248,0.09858,-0.38248], "fy":[-0.38248,-0.09858,0.38248,0.09858]}, - {"t":0.675, "x":2.94144, "y":6.00703, "heading":2.10542, "vx":-2.39124, "vy":1.81042, "omega":0.03963, "ax":0.0, "ay":0.0, "alpha":0.09314, "fx":[-0.08484,0.33122,0.08485,-0.33122], "fy":[-0.33122,-0.08484,0.33122,0.08485]}, - {"t":0.71718, "x":2.84056, "y":6.0834, "heading":2.10709, "vx":-2.39124, "vy":1.81042, "omega":0.04356, "ax":0.0, "ay":0.0, "alpha":0.08718, "fx":[-0.07888,0.31018,0.07892,-0.31015], "fy":[-0.31014,-0.07888,0.31019,0.07892]}, - {"t":0.75937, "x":2.73968, "y":6.15978, "heading":2.10893, "vx":-2.39124, "vy":1.81042, "omega":0.04724, "ax":0.00001, "ay":0.00001, "alpha":0.08918, "fx":[-0.08002,0.31752,0.08023,-0.31732], "fy":[-0.31728,-0.07999,0.31755,0.08026]}, - {"t":0.80156, "x":2.6388, "y":6.23616, "heading":2.11092, "vx":-2.39124, "vy":1.81042, "omega":0.051, "ax":0.00004, "ay":0.00005, "alpha":0.09931, "fx":[-0.08791,0.35428,0.08914,-0.35306], "fy":[-0.35286,-0.08772,0.35448,0.08934]}, - {"t":0.84374, "x":2.53792, "y":6.31253, "heading":2.11308, "vx":-2.39124, "vy":1.81043, "omega":0.05519, "ax":0.00022, "ay":0.00029, "alpha":0.11851, "fx":[-0.10097,0.42603,0.10849,-0.41851], "fy":[-0.41731,-0.09977,0.42724,0.1097]}, - {"t":0.88593, "x":2.43704, "y":6.38891, "heading":2.1154, "vx":-2.39123, "vy":1.81044, "omega":0.06019, "ax":0.00135, "ay":0.00179, "alpha":0.14853, "fx":[-0.107,0.55256,0.15306,-0.5065], "fy":[-0.49912,-0.09961,0.55995,0.16045]}, - {"t":0.92812, "x":2.33616, "y":6.46529, "heading":2.11794, "vx":-2.39117, "vy":1.81051, "omega":0.06645, "ax":0.0083, "ay":0.01095, "alpha":0.19211, "fx":[-0.02533,0.82642,0.30754,-0.54422], "fy":[-0.49901,0.01988,0.87162,0.35276]}, - {"t":0.97031, "x":2.23529, "y":6.54168, "heading":2.12075, "vx":-2.39082, "vy":1.81098, "omega":0.07456, "ax":0.05098, "ay":0.06696, "alpha":0.25315, "fx":[0.65045,1.7708,1.08374,-0.03669], "fy":[0.2352,0.92207,2.04239,1.35592]}, - {"t":1.01249, "x":2.13447, "y":6.61814, "heading":2.12389, "vx":-2.38867, "vy":1.8138, "omega":0.08524, "ax":2.15306, "ay":-1.07756, "alpha":0.25513, "fx":[36.32611,37.43242,36.92419,35.8093], "fy":[-19.33975,-18.46187,-17.31711,-18.19748]}, - {"t":1.05468, "x":2.03562, "y":6.6937, "heading":2.12749, "vx":-2.29784, "vy":1.76834, "omega":0.096, "ax":5.10185, "ay":-3.8486, "alpha":0.00438, "fx":[86.7637,86.7891,86.79849,86.77308], "fy":[-65.48692,-65.45353,-65.44034,-65.47375]}, - {"t":1.09687, "x":1.94322, "y":6.76488, "heading":2.13154, "vx":-2.08261, "vy":1.60598, "omega":0.09619, "ax":5.12558, "ay":-3.87341, "alpha":0.00231, "fx":[87.17538,87.18885,87.19385,87.18038], "fy":[-65.89788,-65.88013,-65.87331,-65.89106]}, - {"t":1.13906, "x":1.85992, "y":6.82918, "heading":2.1356, "vx":-1.86637, "vy":1.44257, "omega":0.09628, "ax":5.13352, "ay":-3.88175, "alpha":0.00151, "fx":[87.31369,87.32253,87.32579,87.31695], "fy":[-66.03551,-66.02386,-66.01946,-66.03111]}, - {"t":1.18124, "x":1.78575, "y":6.88658, "heading":2.13966, "vx":-1.6498, "vy":1.27881, "omega":0.09635, "ax":5.1375, "ay":-3.88594, "alpha":0.00106, "fx":[87.38311,87.38933,87.39161,87.38539], "fy":[-66.10431,-66.09609,-66.09303,-66.10125]}, - {"t":1.22343, "x":1.72072, "y":6.93708, "heading":2.14372, "vx":-1.43307, "vy":1.11487, "omega":0.09639, "ax":5.13988, "ay":-3.88845, "alpha":0.00077, "fx":[87.42486,87.42937,87.431,87.42649], "fy":[-66.14553,-66.13958,-66.1374,-66.14335]}, - {"t":1.26562, "x":1.66484, "y":6.98065, "heading":2.14779, "vx":-1.21623, "vy":0.95083, "omega":0.09642, "ax":5.14147, "ay":-3.89013, "alpha":0.00056, "fx":[87.45275,87.45602,87.4572,87.45392], "fy":[-66.17298,-66.16865,-66.16708,-66.17141]}, - {"t":1.3078, "x":1.61811, "y":7.0173, "heading":2.15186, "vx":-0.99932, "vy":0.78672, "omega":0.09645, "ax":5.14261, "ay":-3.89133, "alpha":0.0004, "fx":[87.47269,87.47504,87.47587,87.47352], "fy":[-66.19256,-66.18946,-66.18835,-66.19145]}, - {"t":1.34999, "x":1.58052, "y":7.04703, "heading":2.15593, "vx":-0.78237, "vy":0.62255, "omega":0.09646, "ax":1.92733, "ay":2.15504, "alpha":0.13226, "fx":[32.77991,33.28834,32.78788,32.27704], "fy":[36.20975,36.46822,37.10172,36.84659]}, - {"t":1.38924, "x":1.5513, "y":7.07312, "heading":2.15971, "vx":-0.70674, "vy":0.70712, "omega":0.10165, "ax":0.07504, "ay":0.07469, "alpha":0.1549, "fx":[1.1656,1.83415,1.38732,0.71869], "fy":[0.71277,1.15937,1.82812,1.38169]}, - {"t":1.42848, "x":1.52363, "y":7.10093, "heading":2.1637, "vx":-0.70379, "vy":0.71005, "omega":0.10773, "ax":0.00221, "ay":0.00219, "alpha":0.114, "fx":[-0.04254,0.44831,0.11759,-0.37325], "fy":[-0.37359,-0.04287,0.44797,0.11726]}, - {"t":1.46772, "x":1.49601, "y":7.12879, "heading":2.16793, "vx":-0.7037, "vy":0.71014, "omega":0.11221, "ax":0.00006, "ay":0.00006, "alpha":0.07492, "fx":[-0.05037,0.27127,0.05257,-0.26907], "fy":[-0.26908,-0.05038,0.27126,0.05256]}, - {"t":1.50697, "x":1.46839, "y":7.15666, "heading":2.17233, "vx":-0.7037, "vy":0.71014, "omega":0.11515, "ax":0.0, "ay":0.0, "alpha":0.03708, "fx":[-0.02485,0.13386,0.02492,-0.1338], "fy":[-0.1338,-0.02486,0.13386,0.02492]}, - {"t":1.54621, "x":1.44078, "y":7.18453, "heading":2.17685, "vx":-0.7037, "vy":0.71014, "omega":0.1166, "ax":0.0, "ay":0.0, "alpha":-0.00014, "fx":[0.00009,-0.00051,-0.00009,0.00051], "fy":[0.00051,0.00009,-0.00051,-0.00009]}, - {"t":1.58546, "x":1.41316, "y":7.2124, "heading":2.18143, "vx":-0.7037, "vy":0.71014, "omega":0.1166, "ax":0.0, "ay":0.0, "alpha":-0.03737, "fx":[0.02385,-0.13508,-0.02385,0.13508], "fy":[0.13508,0.02385,-0.13508,-0.02385]}, - {"t":1.6247, "x":1.38554, "y":7.24027, "heading":2.186, "vx":-0.7037, "vy":0.71014, "omega":0.11513, "ax":0.0, "ay":0.0, "alpha":-0.07521, "fx":[0.04676,-0.27212,-0.04676,0.27212], "fy":[0.27212,0.04676,-0.27212,-0.04676]}, - {"t":1.66395, "x":1.35793, "y":7.26814, "heading":2.19052, "vx":-0.7037, "vy":0.71014, "omega":0.11218, "ax":0.0, "ay":0.0, "alpha":-0.11431, "fx":[0.0692,-0.41389,-0.0692,0.41389], "fy":[0.41389,0.0692,-0.41389,-0.0692]}, - {"t":1.70319, "x":1.33031, "y":7.29601, "heading":2.19492, "vx":-0.7037, "vy":0.71014, "omega":0.10769, "ax":0.0, "ay":0.0, "alpha":-0.15531, "fx":[0.09155,-0.56274,-0.09155,0.56274], "fy":[0.56274,0.09155,-0.56274,-0.09155]}, - {"t":1.74243, "x":1.30269, "y":7.32388, "heading":2.19915, "vx":-0.7037, "vy":0.71014, "omega":0.1016, "ax":0.0, "ay":0.0, "alpha":-0.19888, "fx":[0.11419,-0.72113,-0.11419,0.72113], "fy":[0.72113,0.11419,-0.72113,-0.11419]}, - {"t":1.78168, "x":1.27508, "y":7.35174, "heading":2.20314, "vx":-0.7037, "vy":0.71014, "omega":0.09379, "ax":0.0, "ay":0.0, "alpha":-0.24577, "fx":[0.13755,-0.89168,-0.13755,0.89168], "fy":[0.89168,0.13755,-0.89168,-0.13755]}, - {"t":1.82092, "x":1.24746, "y":7.37961, "heading":2.20682, "vx":-0.7037, "vy":0.71014, "omega":0.08415, "ax":0.0, "ay":0.0, "alpha":-0.29674, "fx":[0.16212,-1.07721,-0.16212,1.07721], "fy":[1.07721,0.16212,-1.07721,-0.16212]}, - {"t":1.86017, "x":1.21985, "y":7.40748, "heading":2.21012, "vx":-0.7037, "vy":0.71014, "omega":0.0725, "ax":0.0, "ay":0.0, "alpha":-0.35263, "fx":[0.18843,-1.28076,-0.18843,1.28076], "fy":[1.28076,0.18843,-1.28076,-0.18843]}, - {"t":1.89941, "x":1.19223, "y":7.43535, "heading":2.21297, "vx":-0.7037, "vy":0.71014, "omega":0.05866, "ax":0.0, "ay":0.0, "alpha":-0.41439, "fx":[0.21714,-1.50566,-0.21714,1.50566], "fy":[1.50566,0.21714,-1.50566,-0.21714]}, - {"t":1.93865, "x":1.16461, "y":7.46322, "heading":2.21527, "vx":-0.7037, "vy":0.71014, "omega":0.0424, "ax":0.0, "ay":0.0, "alpha":-0.48302, "fx":[0.24906,-1.7556,-0.24906,1.7556], "fy":[1.7556,0.24906,-1.7556,-0.24906]}, - {"t":1.9779, "x":1.137, "y":7.49109, "heading":2.21693, "vx":-0.7037, "vy":0.71014, "omega":0.02345, "ax":0.00038, "ay":-0.00039, "alpha":-0.55965, "fx":[0.2917,-2.02813,-0.27868,2.04113], "fy":[2.02807,0.27863,-2.04119,-0.29176]}, - {"t":2.01714, "x":1.10938, "y":7.51896, "heading":2.21785, "vx":-0.70369, "vy":0.71013, "omega":0.00148, "ax":4.3236, "ay":-4.36317, "alpha":-0.03239, "fx":[73.66636,73.43912,73.42026,73.64694], "fy":[-74.08453,-74.30677,-74.34779,-74.12626]}, - {"t":2.05639, "x":1.0851, "y":7.54347, "heading":2.21791, "vx":-0.53401, "vy":0.5389, "omega":0.00021, "ax":4.52954, "ay":-4.571, "alpha":-0.00268, "fx":[77.05715,77.03761,77.03505,77.05459], "fy":[-77.74033,-77.75968,-77.76235,-77.74301]}, - {"t":2.09563, "x":1.06763, "y":7.5611, "heading":2.21792, "vx":-0.35625, "vy":0.35951, "omega":0.00011, "ax":4.53752, "ay":-4.57906, "alpha":-0.00156, "fx":[77.18842,77.17707,77.17556,77.18692], "fy":[-77.88209,-77.89333,-77.89487,-77.88362]}, - {"t":2.13488, "x":1.05714, "y":7.57168, "heading":2.21792, "vx":-0.17818, "vy":0.17981, "omega":0.00005, "ax":4.54033, "ay":-4.58189, "alpha":-0.00116, "fx":[77.23446,77.22598,77.22485,77.23333], "fy":[-77.9318,-77.9402,-77.94134,-77.93294]}, - {"t":2.17412, "x":1.05364, "y":7.57521, "heading":2.21792, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.35868, "ay":-4.75366, "alpha":-0.01435, "fx":[74.19962,74.09039,74.0802,74.1893], "fy":[-80.80345,-80.90359,-80.9132,-80.81321]}, - {"t":2.20273, "x":1.05543, "y":7.57326, "heading":2.21792, "vx":0.1247, "vy":-0.136, "omega":-0.00041, "ax":4.35982, "ay":-4.75177, "alpha":-0.0146, "fx":[74.22015,74.10904,74.09865,74.20963], "fy":[-80.77028,-80.87222,-80.88205,-80.78027]}, - {"t":2.23134, "x":1.06078, "y":7.56743, "heading":2.21791, "vx":0.24942, "vy":-0.27194, "omega":-0.00083, "ax":4.36113, "ay":-4.74961, "alpha":-0.01489, "fx":[74.24361,74.13034,74.11972,74.23285], "fy":[-80.73237,-80.83636,-80.84644,-80.74261]}, - {"t":2.25995, "x":1.0697, "y":7.5577, "heading":2.21789, "vx":0.37419, "vy":-0.40782, "omega":-0.00125, "ax":4.36264, "ay":-4.74711, "alpha":-0.01523, "fx":[74.27067,74.1549,74.14401,74.25963], "fy":[-80.68861,-80.79498,-80.80535,-80.69915]}, - {"t":2.28855, "x":1.08219, "y":7.54409, "heading":2.21785, "vx":0.499, "vy":-0.54363, "omega":-0.00169, "ax":4.3644, "ay":-4.7442, "alpha":-0.01562, "fx":[74.30221,74.18354,74.17233,74.29085], "fy":[-80.63754,-80.74668,-80.7574,-80.64843]}, - {"t":2.31716, "x":1.09825, "y":7.5266, "heading":2.2178, "vx":0.62386, "vy":-0.67935, "omega":-0.00214, "ax":4.36648, "ay":-4.74076, "alpha":-0.01608, "fx":[74.33946,74.21737,74.20578,74.32771], "fy":[-80.57716,-80.68959,-80.70072,-80.58848]}, - {"t":2.34577, "x":1.11789, "y":7.50522, "heading":2.21774, "vx":0.74878, "vy":-0.81498, "omega":-0.0026, "ax":4.36897, "ay":-4.73663, "alpha":-0.01664, "fx":[74.38411,74.25791,74.24586,74.37188], "fy":[-80.50468,-80.62105,-80.63269,-80.51652]}, - {"t":2.37438, "x":1.1411, "y":7.47997, "heading":2.21767, "vx":0.87377, "vy":-0.95049, "omega":-0.00307, "ax":4.37201, "ay":-4.73158, "alpha":-0.01732, "fx":[74.43862,74.3074,74.29478,74.4258], "fy":[-80.41606,-80.53726,-80.54952,-80.42854]}, - {"t":2.40299, "x":1.16788, "y":7.45084, "heading":2.21758, "vx":0.99885, "vy":-1.08585, "omega":-0.00357, "ax":4.3758, "ay":-4.72527, "alpha":-0.01817, "fx":[74.50663,74.36917,74.35583,74.49308], "fy":[-80.30524,-80.43248,-80.44554,-80.31854]}, - {"t":2.4316, "x":1.19825, "y":7.41784, "heading":2.21748, "vx":1.12403, "vy":-1.22104, "omega":-0.00409, "ax":4.38067, "ay":-4.71715, "alpha":-0.01926, "fx":[74.59387,74.4484,74.43412,74.57936], "fy":[-80.16267,-80.2977,-80.31182,-80.17706]}, - {"t":2.46021, "x":1.2322, "y":7.38098, "heading":2.21736, "vx":1.24936, "vy":-1.35599, "omega":-0.00464, "ax":4.38714, "ay":-4.70631, "alpha":-0.02072, "fx":[74.70983,74.55372,74.53818,74.69402], "fy":[-79.97249,-80.11792,-80.13349,-79.98837]}, - {"t":2.48882, "x":1.26974, "y":7.34026, "heading":2.21723, "vx":1.37487, "vy":-1.49063, "omega":-0.00523, "ax":4.39615, "ay":-4.69114, "alpha":-0.02276, "fx":[74.87145,74.70053,74.68318,74.85377], "fy":[-79.70606,-79.86611,-79.88381,-79.72414]}, - {"t":2.51742, "x":1.31087, "y":7.2957, "heading":2.21708, "vx":1.50064, "vy":-1.62484, "omega":-0.00588, "ax":4.40957, "ay":-4.66838, "alpha":-0.02582, "fx":[75.11222,74.91929,74.89914,75.09167], "fy":[-79.30618,-79.48823,-79.50931,-79.32774]}, - {"t":2.54603, "x":1.3556, "y":7.2473, "heading":2.21691, "vx":1.62679, "vy":-1.75839, "omega":-0.00662, "ax":4.43169, "ay":-4.63045, "alpha":-0.03092, "fx":[75.50889,75.27982,75.25483,75.48333], "fy":[-78.63937,-78.85829,-78.88548,-78.66726]}, - {"t":2.57464, "x":1.40396, "y":7.1951, "heading":2.21672, "vx":1.75357, "vy":-1.89086, "omega":-0.00751, "ax":4.47489, "ay":-4.55466, "alpha":-0.04108, "fx":[76.28417,75.985,75.94966,76.24786], "fy":[-77.30597,-77.59916,-77.64046,-77.34851]}, - {"t":2.60325, "x":1.45596, "y":7.13914, "heading":2.21651, "vx":1.8816, "vy":-2.02117, "omega":-0.00868, "ax":4.59605, "ay":-4.32909, "alpha":-0.07108, "fx":[78.45891,77.96794,77.89743,78.38589], "fy":[-73.32776,-73.84554,-73.94338,-73.42937]}, - {"t":2.63186, "x":1.51167, "y":7.07955, "heading":2.21626, "vx":2.01308, "vy":-2.14502, "omega":-0.01071, "ax":4.61835, "ay":1.76787, "alpha":-0.70026, "fx":[77.7783,76.96656,79.36469,80.11765], "fy":[33.52559,31.64456,26.49515,28.61867]}, - {"t":2.66047, "x":1.57115, "y":7.01891, "heading":2.21595, "vx":2.14521, "vy":-2.09444, "omega":-0.03075, "ax":3.12543, "ay":3.34556, "alpha":-0.9193, "fx":[52.05254,49.39253,54.43013,56.77555], "fy":[59.83166,59.10361,53.84712,54.84564]}, - {"t":2.69772, "x":1.65323, "y":6.94321, "heading":2.21481, "vx":2.26163, "vy":-1.96982, "omega":-0.06499, "ax":1.20522, "ay":1.41641, "alpha":-1.7957, "fx":[20.96643,13.75323,20.15567,27.12663], "fy":[30.35824,25.64476,17.62601,22.74205]}, - {"t":2.73497, "x":1.73831, "y":6.87081, "heading":2.21239, "vx":2.30652, "vy":-1.91706, "omega":-0.13188, "ax":0.27095, "ay":0.32775, "alpha":-1.58538, "fx":[5.42708,-1.16741,3.8067,10.36878], "fy":[11.30811,6.45153,-0.19551,4.73558]}, - {"t":2.77222, "x":1.82442, "y":6.79963, "heading":2.20747, "vx":2.31662, "vy":-1.90485, "omega":-0.19094, "ax":0.05686, "ay":0.06923, "alpha":-1.18942, "fx":[1.61426,-3.35227,0.32188,5.28474], "fy":[5.49327,1.82756,-3.14261,0.53201]}, - {"t":2.80947, "x":1.91075, "y":6.72872, "heading":2.20036, "vx":2.31874, "vy":-1.90227, "omega":-0.23524, "ax":0.0119, "ay":0.0145, "alpha":-0.86491, "fx":[0.69522,-2.93443,-0.29032,3.33894], "fy":[3.38314,0.73978,-2.8902,-0.24585]}, - {"t":2.84672, "x":1.99713, "y":6.65787, "heading":2.1916, "vx":2.31918, "vy":-1.90173, "omega":-0.26746, "ax":0.00249, "ay":0.00303, "alpha":-0.60213, "fx":[0.4045,-2.13827,-0.31987,2.22286], "fy":[2.23214,0.41381,-2.12899,-0.31057]}, - {"t":2.88397, "x":2.08352, "y":6.58704, "heading":2.18164, "vx":2.31927, "vy":-1.90161, "omega":-0.28989, "ax":0.00052, "ay":0.00063, "alpha":-0.383, "fx":[0.25302,-1.3758,-0.23535,1.39347], "fy":[1.39541,0.25497,-1.37386,-0.2334]}, - {"t":2.92122, "x":2.16992, "y":6.5162, "heading":2.17084, "vx":2.31929, "vy":-1.90159, "omega":-0.30416, "ax":0.00011, "ay":0.00013, "alpha":-0.19183, "fx":[0.13163,-0.69031,-0.12794,0.694], "fy":[0.69441,0.13204,-0.6899,-0.12754]}, - {"t":2.95847, "x":2.25631, "y":6.44537, "heading":2.15951, "vx":2.31929, "vy":-1.90159, "omega":-0.3113, "ax":0.00002, "ay":0.00003, "alpha":-0.01474, "fx":[0.01096,-0.05268,-0.01019,0.05345], "fy":[0.05353,0.01104,-0.05259,-0.0101]}, - {"t":2.99572, "x":2.3427, "y":6.37453, "heading":2.14791, "vx":2.3193, "vy":-1.90159, "omega":-0.31185, "ax":0.0, "ay":0.00001, "alpha":0.16124, "fx":[-0.12231,0.5792,0.12248,-0.57904], "fy":[-0.57902,-0.1223,0.57922,0.12249]}, - {"t":3.03297, "x":2.4291, "y":6.3037, "heading":2.13629, "vx":2.3193, "vy":-1.90159, "omega":-0.30585, "ax":0.0, "ay":0.0, "alpha":0.34899, "fx":[-0.27944,1.25033,0.27948,-1.25029], "fy":[-1.25028,-0.27944,1.25033,0.27948]}, - {"t":3.07022, "x":2.51549, "y":6.23287, "heading":2.1249, "vx":2.3193, "vy":-1.90159, "omega":-0.29285, "ax":0.0, "ay":0.0, "alpha":0.5622, "fx":[-0.47311,2.00893,0.47312,-2.00892], "fy":[-2.00892,-0.47311,2.00893,0.47312]}, - {"t":3.10747, "x":2.60189, "y":6.16203, "heading":2.11399, "vx":2.3193, "vy":-1.90159, "omega":-0.2719, "ax":0.0, "ay":0.0, "alpha":0.81625, "fx":[-0.71867,2.90903,0.71868,-2.90902], "fy":[-2.90902,-0.71867,2.90903,0.71868]}, - {"t":3.14472, "x":2.68828, "y":6.0912, "heading":2.10386, "vx":2.3193, "vy":-1.90159, "omega":-0.2415, "ax":0.0, "ay":0.0, "alpha":1.12908, "fx":[-1.03482,4.01367,1.03483,-4.01366], "fy":[-4.01366,-1.03482,4.01366,1.03482]}, - {"t":3.18197, "x":2.77467, "y":6.02036, "heading":2.09487, "vx":2.3193, "vy":-1.90159, "omega":-0.19944, "ax":0.0, "ay":0.0, "alpha":1.52224, "fx":[-1.44379,5.39849,1.44377,-5.39851], "fy":[-5.39852,-1.4438,5.39849,1.44377]}, - {"t":3.21922, "x":2.86107, "y":5.94953, "heading":2.08744, "vx":2.3193, "vy":-1.90159, "omega":-0.14274, "ax":-0.00032, "ay":0.00025, "alpha":2.02178, "fx":[-1.97624,7.15023,1.96533,-7.16101], "fy":[-7.15131,-1.96647,7.15993,1.97511]}, - {"t":3.25647, "x":2.94746, "y":5.87869, "heading":2.08212, "vx":2.31928, "vy":-1.90158, "omega":-0.06743, "ax":-2.53363, "ay":2.07733, "alpha":1.57542, "fx":[-46.10168,-38.08022,-40.32598,-47.87721], "fy":[29.00782,35.18781,41.4857,35.65767]}, - {"t":3.29372, "x":3.0321, "y":5.8093, "heading":2.07961, "vx":2.22491, "vy":-1.82419, "omega":-0.00874, "ax":-4.9288, "ay":4.04111, "alpha":0.04565, "fx":[-84.02855,-83.75062,-83.64659,-83.92411], "fy":[68.50204,68.83797,68.97343,68.63905]}, - {"t":3.33097, "x":3.11156, "y":5.74415, "heading":2.07929, "vx":2.04131, "vy":-1.67366, "omega":-0.00704, "ax":-4.96136, "ay":4.0678, "alpha":0.02812, "fx":[-84.51012,-84.33842,-84.27244,-84.44398], "fy":[69.04622,69.25471,69.33782,69.12992]}, - {"t":3.36822, "x":3.18415, "y":5.68463, "heading":2.07902, "vx":1.8565, "vy":-1.52214, "omega":-0.00599, "ax":-4.97236, "ay":4.07683, "alpha":0.02222, "fx":[-84.67275,-84.53692,-84.48425,-84.61998], "fy":[69.23018,69.39538,69.461,69.29617]}, - {"t":3.40547, "x":3.24986, "y":5.63076, "heading":2.0788, "vx":1.67128, "vy":-1.37027, "omega":-0.00517, "ax":-4.97789, "ay":4.08136, "alpha":0.01927, "fx":[-84.75444,-84.63661,-84.5907,-84.70845], "fy":[69.32259,69.46601,69.52289,69.37976]}, - {"t":3.44272, "x":3.30866, "y":5.58255, "heading":2.07861, "vx":1.48585, "vy":-1.21824, "omega":-0.00445, "ax":-4.98122, "ay":4.08409, "alpha":0.0175, "fx":[-84.80357,-84.69656,-84.65473,-84.76168], "fy":[69.37817,69.50848,69.56013,69.43005]}, - {"t":3.47997, "x":3.36055, "y":5.54, "heading":2.07844, "vx":1.3003, "vy":-1.06611, "omega":-0.0038, "ax":-4.98344, "ay":4.08591, "alpha":0.01631, "fx":[-84.83636,-84.73657,-84.69748,-84.79722], "fy":[69.41527,69.53683,69.58499,69.46363]}, - {"t":3.51722, "x":3.40553, "y":5.50312, "heading":2.0783, "vx":1.11466, "vy":-0.91391, "omega":-0.00319, "ax":-4.98503, "ay":4.08721, "alpha":0.01547, "fx":[-84.85981,-84.76518,-84.72805,-84.82263], "fy":[69.44179,69.5571,69.60277,69.48765]}, - {"t":3.55447, "x":3.44359, "y":5.47192, "heading":2.07818, "vx":0.92897, "vy":-0.76166, "omega":-0.00261, "ax":-4.98622, "ay":4.08819, "alpha":0.01484, "fx":[-84.87741,-84.78664,-84.75098,-84.84171], "fy":[69.46169,69.5723,69.61611,69.50567]}, - {"t":3.59172, "x":3.47474, "y":5.44638, "heading":2.07808, "vx":0.74323, "vy":-0.60938, "omega":-0.00206, "ax":-4.98715, "ay":4.08895, "alpha":0.01434, "fx":[-84.8911,-84.80334,-84.76883,-84.85655], "fy":[69.47717,69.58414,69.6265,69.51969]}, - {"t":3.62897, "x":3.49896, "y":5.42652, "heading":2.07801, "vx":0.55746, "vy":-0.45706, "omega":-0.00152, "ax":-4.98789, "ay":4.08956, "alpha":0.01395, "fx":[-84.90206,-84.81671,-84.78312,-84.86843], "fy":[69.48956,69.59361,69.63481,69.53091]}, - {"t":3.66622, "x":3.51627, "y":5.41233, "heading":2.07795, "vx":0.37166, "vy":-0.30473, "omega":-0.00101, "ax":-4.9885, "ay":4.09006, "alpha":0.01363, "fx":[-84.91103,-84.82764,-84.79481,-84.87815], "fy":[69.4997,69.60136,69.64161,69.5401]}, - {"t":3.70347, "x":3.52665, "y":5.40382, "heading":2.07791, "vx":0.18584, "vy":-0.15237, "omega":-0.0005, "ax":-4.989, "ay":4.09047, "alpha":0.01336, "fx":[-84.9185,-84.83676,-84.80455,-84.88626], "fy":[69.50816,69.60782,69.64728,69.54775]}, - {"t":3.74072, "x":3.53011, "y":5.40098, "heading":2.07789, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/C_RIGHT_PATH1.traj b/src/main/deploy/choreo/C_RIGHT_PATH1.traj deleted file mode 100644 index 2561be80..00000000 --- a/src/main/deploy/choreo/C_RIGHT_PATH1.traj +++ /dev/null @@ -1,67 +0,0 @@ -{ - "name":"C_RIGHT_PATH1", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":7.171988010406494, "y":2.0378777980804443, "heading":-1.5707963267948966, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":5.227500915527344, "y":2.669785725402832, "heading":-1.102853734231975, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":3.0}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"7.171988010406494 m", "val":7.171988010406494}, "y":{"exp":"2.0378777980804443 m", "val":2.0378777980804443}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"5.227500915527344 m", "val":5.227500915527344}, "y":{"exp":"(8.0518 - 5.382014274597168) m", "val":2.669785725402832}, "heading":{"exp":"-1.102853734231975 rad", "val":-1.102853734231975}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"3 m / s", "val":3.0}}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.14764], - "samples":[ - {"t":0.0, "x":7.17199, "y":2.03788, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.13369, "ay":1.99373, "alpha":0.54554, "fx":[-103.18885,-103.8138,-105.39894,-104.92794], "fy":[37.34934,35.5929,30.5751,32.13399]}, - {"t":0.03825, "x":7.1675, "y":2.03934, "heading":-1.5708, "vx":-0.23464, "vy":0.07627, "omega":0.02087, "ax":-6.13303, "ay":1.99353, "alpha":0.55225, "fx":[-103.16301,-103.79708,-105.40046,-104.92409], "fy":[37.38834,35.60953,30.53177,32.10819]}, - {"t":0.07651, "x":7.15404, "y":2.04371, "heading":-1.57, "vx":-0.46926, "vy":0.15253, "omega":0.042, "ax":-6.13224, "ay":1.9933, "alpha":0.5603, "fx":[-103.13149,-103.77795,-105.4027,-104.91859], "fy":[37.43649,35.62677,30.47829,32.08006]}, - {"t":0.11476, "x":7.1316, "y":2.05101, "heading":-1.56839, "vx":-0.70385, "vy":0.22879, "omega":0.06343, "ax":-6.13127, "ay":1.993, "alpha":0.57014, "fx":[-103.0925,-103.75538,-105.40576,-104.91112], "fy":[37.49648,35.64556,30.41168,32.04805]}, - {"t":0.15302, "x":7.10019, "y":2.06122, "heading":-1.56596, "vx":-0.9384, "vy":0.30503, "omega":0.08524, "ax":-6.13006, "ay":1.99264, "alpha":0.58244, "fx":[-103.04338,-103.72779,-105.4098,-104.90119], "fy":[37.57233,35.66728,30.3275,32.00982]}, - {"t":0.19127, "x":7.0598, "y":2.07434, "heading":-1.5627, "vx":-1.1729, "vy":0.38126, "omega":0.10752, "ax":-6.12849, "ay":1.99217, "alpha":0.59828, "fx":[-102.97992,-103.69272,-105.41508,-104.88806], "fy":[37.67037,35.69411,30.21875,31.96169]}, - {"t":0.22953, "x":7.01045, "y":2.09039, "heading":-1.55859, "vx":-1.40735, "vy":0.45747, "omega":0.13041, "ax":-6.12641, "ay":1.99154, "alpha":0.6194, "fx":[-102.89508,-103.64611,-105.42197,-104.87045], "fy":[37.80112,35.7297,30.07384,31.89747]}, - {"t":0.26778, "x":6.95213, "y":2.10934, "heading":-1.5536, "vx":-1.64171, "vy":0.53365, "omega":0.1541, "ax":-6.12347, "ay":1.99066, "alpha":0.649, "fx":[-102.77611,-103.58061,-105.43112,-104.8461], "fy":[37.98358,35.7806,29.87189,31.80594]}, - {"t":0.30604, "x":6.88484, "y":2.13122, "heading":-1.54771, "vx":-1.87597, "vy":0.6098, "omega":0.17893, "ax":-6.11905, "ay":1.98932, "alpha":0.69345, "fx":[-102.59737,-103.48164,-105.44369,-104.81042], "fy":[38.25568,35.85984,29.57135,31.66448]}, - {"t":0.34429, "x":6.8086, "y":2.156, "heading":-1.54086, "vx":-2.11005, "vy":0.68591, "omega":0.20546, "ax":-6.11163, "ay":1.98709, "alpha":0.76761, "fx":[-102.29835,-103.31553,-105.46193,-104.75249], "fy":[38.70588,35.99747,29.07588,31.41981]}, - {"t":0.38255, "x":6.72341, "y":2.18369, "heading":-1.533, "vx":-2.34385, "vy":0.76192, "omega":0.23482, "ax":-6.09661, "ay":1.98254, "alpha":0.916, "fx":[-101.69461,-102.98304,-105.49005,-104.63854], "fy":[39.59866,36.2815,28.10007,30.90973]}, - {"t":0.4208, "x":6.62929, "y":2.21429, "heading":-1.52402, "vx":-2.57707, "vy":0.83776, "omega":0.26987, "ax":-6.0502, "ay":1.9684, "alpha":1.35978, "fx":[-99.83146,-102.01087,-105.52058,-104.2856], "fy":[42.23835,37.12497,25.26533,29.29874]}, - {"t":0.45906, "x":6.52627, "y":2.24778, "heading":-1.5137, "vx":-2.80852, "vy":0.91306, "omega":0.32188, "ax":-1.15127, "ay":0.34475, "alpha":23.14124, "fx":[29.40485,-76.22442,-78.22874,46.71744], "fy":[81.92133,54.45671,-47.97777,-64.94369]}, - {"t":0.49731, "x":6.41799, "y":2.28296, "heading":-1.50138, "vx":-2.85256, "vy":0.92625, "omega":1.20715, "ax":0.00113, "ay":0.00488, "alpha":19.89595, "fx":[47.92404,-55.0499,-47.95598,55.15868], "fy":[55.17379,48.03647,-55.03466,-47.84338]}, - {"t":0.53557, "x":6.30887, "y":2.3184, "heading":-1.4552, "vx":-2.85252, "vy":0.92644, "omega":1.96826, "ax":-0.00296, "ay":-0.00951, "alpha":7.26449, "fx":[16.51487,-20.96547,-16.59833,20.84761], "fy":[20.74972,16.38973,-21.06312,-16.72342]}, - {"t":0.57382, "x":6.19974, "y":2.35383, "heading":-1.37991, "vx":-2.85263, "vy":0.92607, "omega":2.24617, "ax":0.00447, "ay":0.01414, "alpha":-7.40226, "fx":[-15.15614,22.59981,15.28443,-22.42382], "fy":[-22.28081,-14.96991,22.7423,15.47061]}, - {"t":0.61208, "x":6.09062, "y":2.38927, "heading":-1.29398, "vx":-2.85246, "vy":0.92662, "omega":1.96299, "ax":0.00047, "ay":0.00003, "alpha":-19.77502, "fx":[-35.33973,63.4137,35.35921,-63.40087], "fy":[-63.40989,-35.34584,63.40468,35.3531]}, - {"t":0.65033, "x":5.9815, "y":2.42472, "heading":-1.21889, "vx":-2.85244, "vy":0.92662, "omega":1.2065, "ax":1.14734, "ay":-0.3575, "alpha":-23.08858, "fx":[-4.47729,86.49693,64.10522,-68.06119], "fy":[-89.01342,-36.76432,63.86289,37.59063]}, - {"t":0.68859, "x":5.87322, "y":2.4599, "heading":-1.17273, "vx":-2.80855, "vy":0.91294, "omega":0.32325, "ax":6.05065, "ay":-1.96747, "alpha":-1.35374, "fx":[99.65943,103.03896,105.73861,103.24207], "fy":[-42.76097,-34.19842,-24.16251,-32.74282]}, - {"t":0.72684, "x":5.7702, "y":2.49339, "heading":-1.16037, "vx":-2.57709, "vy":0.83768, "omega":0.27147, "ax":6.09677, "ay":-1.98203, "alpha":-0.91712, "fx":[101.53333,103.72236,105.67002,103.89138], "fy":[-40.05526,-34.12236,-27.35748,-33.31985]}, - {"t":0.7651, "x":5.67608, "y":2.52398, "heading":-1.14998, "vx":-2.34386, "vy":0.76185, "omega":0.23638, "ax":6.11172, "ay":-1.98673, "alpha":-0.77035, "fx":[102.14572,103.9662,105.62691,104.09531], "fy":[-39.13368,-34.07979,-28.43739,-33.52411]}, - {"t":0.80335, "x":5.59089, "y":2.55167, "heading":-1.14094, "vx":-2.11005, "vy":0.68585, "omega":0.20691, "ax":6.1191, "ay":-1.98905, "alpha":-0.69688, "fx":[102.4491,104.09354,105.6017,104.19237], "fy":[-38.67004,-34.04791,-28.97879,-33.63624]}, - {"t":0.84161, "x":5.51465, "y":2.57645, "heading":-1.13302, "vx":-1.87597, "vy":0.60976, "omega":0.18025, "ax":6.1235, "ay":-1.99044, "alpha":-0.65281, "fx":[102.63014,104.17276,105.58546,104.24788], "fy":[-38.39106,-34.02201,-29.30377,-33.71027]}, - {"t":0.87986, "x":5.44736, "y":2.59832, "heading":-1.12613, "vx":-1.64171, "vy":0.53362, "omega":0.15528, "ax":6.12643, "ay":-1.99136, "alpha":-0.62345, "fx":[102.75042,104.22722,105.57419,104.28325], "fy":[-38.20473,-34.00049,-29.52043,-33.76393]}, - {"t":0.91812, "x":5.38904, "y":2.61728, "heading":-1.12019, "vx":-1.40735, "vy":0.45744, "omega":0.13143, "ax":6.12851, "ay":-1.99201, "alpha":-0.60249, "fx":[102.83614,104.26705,105.56591,104.30757], "fy":[-38.07144,-33.98262,-29.67521,-33.80479]}, - {"t":0.95637, "x":5.33969, "y":2.63332, "heading":-1.11516, "vx":-1.1729, "vy":0.38123, "omega":0.10838, "ax":6.13007, "ay":-1.9925, "alpha":-0.58678, "fx":[102.90032,104.29738,105.55957,104.32536], "fy":[-37.97136,-33.96801,-29.79134,-33.83663]}, - {"t":0.99463, "x":5.2993, "y":2.64645, "heading":-1.11101, "vx":-0.9384, "vy":0.30501, "omega":0.08593, "ax":6.13127, "ay":-1.99288, "alpha":-0.57457, "fx":[102.95017,104.32107,105.55455,104.3391], "fy":[-37.89345,-33.95645,-29.88173,-33.86153]}, - {"t":1.03288, "x":5.26789, "y":2.65666, "heading":-1.10773, "vx":-0.70385, "vy":0.22877, "omega":0.06395, "ax":6.13224, "ay":-1.99318, "alpha":-0.56481, "fx":[102.98999,104.33985,105.55047,104.35029], "fy":[-37.83111,-33.94779,-29.95412,-33.88079]}, - {"t":1.07114, "x":5.24545, "y":2.66395, "heading":-1.10528, "vx":-0.46926, "vy":0.15252, "omega":0.04235, "ax":6.13303, "ay":-1.99343, "alpha":-0.55682, "fx":[103.02253,104.35484,105.54708,104.35986], "fy":[-37.78012,-33.94192,-30.01343,-33.89519]}, - {"t":1.10939, "x":5.23199, "y":2.66833, "heading":-1.10366, "vx":-0.23464, "vy":0.07627, "omega":0.02105, "ax":6.13369, "ay":-1.99364, "alpha":-0.55017, "fx":[103.0496,104.36677,105.54421,104.36845], "fy":[-37.73768,-33.93878,-30.06294,-33.9053]}, - {"t":1.14764, "x":5.2275, "y":2.66979, "heading":-1.10285, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/C_RIGHT_PATH2.traj b/src/main/deploy/choreo/C_RIGHT_PATH2.traj deleted file mode 100644 index 0e9b845a..00000000 --- a/src/main/deploy/choreo/C_RIGHT_PATH2.traj +++ /dev/null @@ -1,181 +0,0 @@ -{ - "name":"C_RIGHT_PATH2", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":5.281756401062012, "y":2.964472519683838, "heading":-1.0513369818883893, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":4.582683086395264, "y":2.4232380264282227, "heading":0.0, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":3.5206298828125, "y":2.2525508277893067, "heading":0.0, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":1.6289232969284058, "y":1.3508695363998413, "heading":-2.216612130911823, "intervals":22, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.0456665754318235, "y":0.6667511463165283, "heading":-2.216612130911823, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":3.599963426589966, "y":2.7183375358581543, "heading":-2.09887087685183, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":3.0}}, "enabled":true}, - {"from":3, "to":4, "data":{"type":"MaxVelocity", "props":{"max":1.0}}, "enabled":true}, - {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"5.281756401062012 m", "val":5.281756401062012}, "y":{"exp":"(8.0518 - 5.087327480316162) m", "val":2.964472519683838}, "heading":{"exp":"-1.0513369818883893 rad", "val":-1.0513369818883893}, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"4.582683086395264 m", "val":4.582683086395264}, "y":{"exp":"(8.0518 - 5.628561973571777) m", "val":2.4232380264282227}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"3.5206298828125 m", "val":3.5206298828125}, "y":{"exp":"(8.0518 - 5.799249172210693) m", "val":2.2525508277893067}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"1.6289232969284058 m", "val":1.6289232969284058}, "y":{"exp":"1.3508695363998413 m", "val":1.3508695363998413}, "heading":{"exp":"-2.216612130911823 rad", "val":-2.216612130911823}, "intervals":22, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.0456665754318237 m", "val":1.0456665754318235}, "y":{"exp":"0.6667511463165283 m", "val":0.6667511463165283}, "heading":{"exp":"-2.216612130911823 rad", "val":-2.216612130911823}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"3.599963426589966 m", "val":3.599963426589966}, "y":{"exp":"2.7183375358581543 m", "val":2.7183375358581543}, "heading":{"exp":"-2.09887087685183 rad", "val":-2.09887087685183}, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"3 m / s", "val":3.0}}}, "enabled":true}, - {"from":3, "to":4, "data":{"type":"MaxVelocity", "props":{"max":{"exp":"1 m / s", "val":1.0}}}, "enabled":true}, - {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,0.53079,0.89269,1.69734,2.67683,4.23537], - "samples":[ - {"t":0.0, "x":5.28176, "y":2.96447, "heading":-1.05134, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-4.57103, "ay":-4.54736, "alpha":-0.10718, "fx":[-77.4787,-77.26901,-78.02964,-78.23048], "fy":[-77.62662,-77.83278,-77.0695,-76.86824]}, - {"t":0.02413, "x":5.28043, "y":2.96315, "heading":-1.05134, "vx":-0.11028, "vy":-0.10971, "omega":-0.00259, "ax":-4.60002, "ay":-4.51721, "alpha":-0.1097, "fx":[-77.96409,-77.75568,-78.53047,-78.72964], "fy":[-77.12521,-77.33254,-76.54488,-76.34284]}, - {"t":0.04825, "x":5.27643, "y":2.95919, "heading":-1.0514, "vx":-0.22127, "vy":-0.2187, "omega":-0.00523, "ax":-4.63201, "ay":-4.48346, "alpha":-0.1125, "fx":[-78.49989,-78.29313,-79.08331,-79.28039], "fy":[-76.56425,-76.77263,-75.95763,-75.755]}, - {"t":0.07238, "x":5.26974, "y":2.95261, "heading":-1.05153, "vx":-0.33302, "vy":-0.32687, "omega":-0.00795, "ax":-4.6675, "ay":-4.44545, "alpha":-0.11562, "fx":[-79.09421,-78.8896,-79.69655,-79.89098], "fy":[-75.93264,-76.14186,-75.29598,-75.09305]}, - {"t":0.09651, "x":5.26035, "y":2.94343, "heading":-1.05172, "vx":-0.44563, "vy":-0.43412, "omega":-0.01074, "ax":-4.70708, "ay":-4.40234, "alpha":-0.11913, "fx":[-79.75696,-79.55516,-80.38042,-80.5715], "fy":[-75.21636,-75.42608,-74.54509,-74.3423]}, - {"t":0.12063, "x":5.24823, "y":2.93167, "heading":-1.05198, "vx":-0.5592, "vy":-0.54034, "omega":-0.01361, "ax":-4.75147, "ay":-4.35302, "alpha":-0.12309, "fx":[-80.50037,-80.30224,-81.14753,-81.33431], "fy":[-74.39749,-74.60719,-73.68594,-73.48394]}, - {"t":0.14476, "x":5.23335, "y":2.91737, "heading":-1.0523, "vx":-0.67384, "vy":-0.64536, "omega":-0.01658, "ax":-4.80158, "ay":-4.2961, "alpha":-0.1276, "fx":[-81.33965,-81.14633,-82.01355,-82.19478], "fy":[-73.45276,-73.66162,-72.6938,-72.49358]}, - {"t":0.16889, "x":5.2157, "y":2.90055, "heading":-1.0527, "vx":-0.78968, "vy":-0.74901, "omega":-0.01966, "ax":-4.85856, "ay":-4.22971, "alpha":-0.13279, "fx":[-82.29389,-82.10694,-82.99814,-83.17217], "fy":[-72.35145,-72.55823,-71.53599,-71.33901]}, - {"t":0.19301, "x":5.19523, "y":2.88124, "heading":-1.05318, "vx":-0.9069, "vy":-0.85106, "omega":-0.02286, "ax":-4.92385, "ay":-4.15134, "alpha":-0.13881, "fx":[-83.38738,-83.2089,-84.12622,-84.29082], "fy":[-71.05221,-71.25501,-70.16845,-69.97692]}, - {"t":0.21714, "x":5.17192, "y":2.8595, "heading":-1.05373, "vx":-1.0257, "vy":-0.95122, "omega":-0.02621, "ax":-4.9993, "ay":-4.05754, "alpha":-0.14587, "fx":[-84.65122,-84.48411,-85.42965,-85.58179], "fy":[-69.49817,-69.69402,-68.53048,-68.34777]}, - {"t":0.24127, "x":5.14571, "y":2.83537, "heading":-1.05436, "vx":-1.14632, "vy":-1.04911, "omega":-0.02973, "ax":-5.0873, "ay":-3.94343, "alpha":-0.15426, "fx":[-86.12565,-85.97393,-86.94941,-87.08492], "fy":[-67.60918,-67.79339,-66.53637,-66.36776]}, - {"t":0.26539, "x":5.11658, "y":2.80891, "heading":-1.05508, "vx":-1.26906, "vy":-1.14425, "omega":-0.03345, "ax":-5.19093, "ay":-3.80195, "alpha":-0.16438, "fx":[-87.86291,-87.73223,-88.73831,-88.85142], "fy":[-65.269,-65.43397,-64.06166,-63.91556]}, - {"t":0.28952, "x":5.08445, "y":2.7802, "heading":-1.05589, "vx":-1.3943, "vy":-1.23598, "omega":-0.03742, "ax":-5.31416, "ay":-3.62249, "alpha":-0.17677, "fx":[-89.93056,-89.8289,-90.86372,-90.94642], "fy":[-62.3036,-62.43669,-60.91972,-60.80999]}, - {"t":0.31365, "x":5.04926, "y":2.74932, "heading":-1.05679, "vx":-1.52251, "vy":-1.32338, "omega":-0.04168, "ax":-5.46194, "ay":-3.3886, "alpha":-0.19225, "fx":[-92.41367,-92.35221,-93.40831,-93.44965], "fy":[-58.44275,-58.52213,-56.82051,-56.77076]}, - {"t":0.33777, "x":5.01094, "y":2.71641, "heading":-1.0578, "vx":-1.65429, "vy":-1.40514, "omega":-0.04632, "ax":-5.63977, "ay":-3.07366, "alpha":-0.21196, "fx":[-95.41038,-95.40412,-96.46165,-96.44759], "fy":[-53.24954,-53.23604,-51.29532,-51.34737]}, - {"t":0.3619, "x":4.96938, "y":2.68161, "heading":-1.05891, "vx":-1.79036, "vy":-1.47929, "omega":-0.05144, "ax":-5.85169, "ay":-2.63291, "alpha":-0.23757, "fx":[-99.00115,-99.06707,-100.07876,-99.99513], "fy":[-45.98766,-45.80783,-43.55689,-43.78773]}, - {"t":0.38603, "x":4.92449, "y":2.64516, "heading":-1.06015, "vx":-1.93154, "vy":-1.54282, "omega":-0.05717, "ax":-6.092, "ay":-1.9887, "alpha":-0.27128, "fx":[-103.12403,-103.26765,-104.12629,-103.97491], "fy":[-35.3739,-34.88566,-32.2472,-32.80207]}, - {"t":0.41015, "x":4.87611, "y":2.60736, "heading":-1.06153, "vx":-2.07852, "vy":-1.5908, "omega":-0.06371, "ax":-6.31727, "ay":-1.00833, "alpha":-0.31496, "fx":[-107.13215,-107.2879,-107.76842,-107.63104], "fy":[-19.18542,-18.11987,-15.07915,-16.22148]}, - {"t":0.43428, "x":4.82413, "y":2.56868, "heading":-1.06307, "vx":-2.23093, "vy":-1.61513, "omega":-0.07131, "ax":-6.3642, "ay":0.49544, "alpha":-0.36558, "fx":[-108.44602,-108.27935,-108.02962,-108.25764], "fy":[5.84661,7.88773,11.03063,8.94422]}, - {"t":0.45841, "x":4.76845, "y":2.52986, "heading":-1.06479, "vx":-2.38448, "vy":-1.60317, "omega":-0.08013, "ax":-5.82917, "ay":2.57168, "alpha":-0.40224, "fx":[-100.30034,-98.96956,-97.97999,-99.36025], "fy":[41.08311,44.10673,46.37033,43.41397]}, - {"t":0.48253, "x":4.70922, "y":2.49193, "heading":-1.06672, "vx":-2.52512, "vy":-1.54113, "omega":-0.08984, "ax":-4.39081, "ay":4.61485, "alpha":-0.38625, "fx":[-76.43841,-73.6238,-72.96755,-75.71569], "fy":[76.79097,79.47381,80.1485,77.57577]}, - {"t":0.50666, "x":4.64702, "y":2.45609, "heading":-1.06889, "vx":-2.63105, "vy":-1.42979, "omega":-0.09916, "ax":-2.95433, "ay":5.65491, "alpha":-0.32251, "fx":[-51.7005,-48.72507,-48.8485,-51.73484], "fy":[95.40889,96.96314,96.94587,95.43591]}, - {"t":0.53079, "x":4.58268, "y":2.42324, "heading":-1.07128, "vx":-2.70233, "vy":-1.29335, "omega":-0.10694, "ax":-2.72065, "ay":5.72767, "alpha":-0.30504, "fx":[-47.60832,-44.76456,-44.98701,-47.74975], "fy":[96.76165,98.1133,98.07382,96.7554]}, - {"t":0.54652, "x":4.53983, "y":2.4036, "heading":-1.07297, "vx":-2.74514, "vy":-1.20323, "omega":-0.11174, "ax":-2.45789, "ay":5.82834, "alpha":-0.33197, "fx":[-43.212,-40.07016,-40.45274,-43.4971], "fy":[98.50707,99.83415,99.75453,98.45799]}, - {"t":0.56226, "x":4.49633, "y":2.38539, "heading":-1.07473, "vx":-2.78381, "vy":-1.11152, "omega":-0.11696, "ax":-2.24759, "ay":5.89245, "alpha":-0.36375, "fx":[-39.72464,-36.25358,-36.79547,-40.14942], "fy":[99.61017,100.93809,100.83338,99.53372]}, - {"t":0.57799, "x":4.45225, "y":2.36863, "heading":-1.07657, "vx":-2.81918, "vy":-1.0188, "omega":-0.12268, "ax":-2.0426, "ay":5.94212, "alpha":-0.4018, "fx":[-36.34133,-32.48785,-33.21766,-36.92947], "fy":[100.46265,101.79414,101.67242,100.36565]}, - {"t":0.59373, "x":4.40764, "y":2.35333, "heading":-1.0785, "vx":-2.85132, "vy":-0.92531, "omega":-0.12901, "ax":-1.83683, "ay":5.97873, "alpha":-0.44804, "fx":[-32.96053,-28.65486,-29.61383,-33.7465], "fy":[101.08869,102.4231,102.29492,100.97946]}, - {"t":0.60946, "x":4.36254, "y":2.33951, "heading":-1.08053, "vx":-2.88022, "vy":-0.83123, "omega":-0.13606, "ax":-1.63004, "ay":6.00053, "alpha":-0.50513, "fx":[-29.58324,-24.73422,-25.97683,-30.61199], "fy":[101.45593,102.79256,102.6739,101.34712]}, - {"t":0.62519, "x":4.31702, "y":2.32717, "heading":-1.08267, "vx":-2.90587, "vy":-0.73682, "omega":-0.144, "ax":-1.42277, "ay":6.00459, "alpha":-0.57699, "fx":[-26.22529,-20.71157,-22.3107,-27.55599], "fy":[101.51005,102.84899,102.76497,101.42166]}, - {"t":0.64093, "x":4.27112, "y":2.31632, "heading":-1.08493, "vx":-2.92825, "vy":-0.64234, "omega":-0.15308, "ax":-1.21576, "ay":5.98648, "alpha":-0.6695, "fx":[-22.90981,-16.56602,-18.62144,-24.62183], "fy":[101.16755,102.51099,102.5023,101.13245]}, - {"t":0.65666, "x":4.2249, "y":2.30696, "heading":-1.08734, "vx":-2.94738, "vy":-0.54814, "omega":-0.16362, "ax":-1.01008, "ay":5.93928, "alpha":-0.7919, "fx":[-19.67026,-12.26498,-14.91695,-21.87236], "fy":[100.29536,101.65046,101.78572,100.36994]}, - {"t":0.6724, "x":4.1784, "y":2.29907, "heading":-1.08992, "vx":-2.96328, "vy":-0.45469, "omega":-0.17608, "ax":-0.80726, "ay":5.85167, "alpha":-0.95942, "fx":[-16.55759,-7.75674,-11.2083,-19.40213], "fy":[98.67021,100.05656,100.45705,98.95685]}, - {"t":0.68813, "x":4.13167, "y":2.29264, "heading":-1.09269, "vx":-2.97598, "vy":-0.36261, "omega":-0.19117, "ax":-0.60969, "ay":5.70411, "alpha":-1.19877, "fx":[-13.6539,-2.95754,-7.51237,-17.35883], "fy":[95.89265,97.36222,98.25529,96.59095]}, - {"t":0.70387, "x":4.08477, "y":2.28764, "heading":-1.09569, "vx":-2.98557, "vy":-0.27286, "omega":-0.21004, "ax":-0.42134, "ay":5.46033, "alpha":-1.56063, "fx":[-11.10009,2.27129,-3.85647,-15.98243], "fy":[91.18511,92.88156,94.72572,92.72254]}, - {"t":0.7196, "x":4.03774, "y":2.28402, "heading":-1.099, "vx":-2.9922, "vy":-0.18694, "omega":-0.23459, "ax":-0.2492, "ay":5.04615, "alpha":-2.15207, "fx":[-9.1533,8.1604,-0.28665,-15.67563], "fy":[82.84878,85.20633,89.01649,86.26276]}, - {"t":0.73534, "x":3.99063, "y":2.28171, "heading":-1.10269, "vx":-2.99612, "vy":-0.10754, "omega":-0.26845, "ax":-0.10637, "ay":4.28785, "alpha":-3.23079, "fx":[-8.28869,15.04289,3.12012,-17.11127], "fy":[66.54156,71.05942,79.35026,74.78914]}, - {"t":0.75107, "x":3.94347, "y":2.28054, "heading":-1.10691, "vx":-2.9978, "vy":-0.04008, "omega":-0.31929, "ax":-0.01737, "ay":2.72851, "alpha":-5.38723, "fx":[-8.96148,22.68557,6.22797,-21.13408], "fy":[30.19631,42.00114,61.32714,52.1198]}, - {"t":0.76681, "x":3.8963, "y":2.28025, "heading":-1.11194, "vx":-2.99807, "vy":0.00286, "omega":-0.40406, "ax":-0.00005, "ay":-0.17273, "alpha":-7.24236, "fx":[-8.43206,25.09263,8.63965,-25.3034], "fy":[-27.96809,-11.59533,22.36469,5.44618]}, - {"t":0.78254, "x":3.84912, "y":2.28027, "heading":-1.1183, "vx":-2.99807, "vy":0.00014, "omega":-0.51801, "ax":0.02368, "ay":-2.98096, "alpha":-4.60385, "fx":[-5.58718,18.71657,8.21326,-19.7318], "fy":[-62.95264,-55.41375,-37.60167,-46.85308]}, - {"t":0.79828, "x":3.80195, "y":2.27991, "heading":-1.12645, "vx":-2.9977, "vy":-0.04677, "omega":-0.59045, "ax":0.1209, "ay":-4.41579, "alpha":-2.52804, "fx":[-2.25847,14.24117,7.43032,-11.18679], "fy":[-79.88316,-76.53928,-70.39047,-73.63231]}, - {"t":0.81401, "x":3.7548, "y":2.27863, "heading":-1.13574, "vx":-2.9958, "vy":-0.11625, "omega":-0.63023, "ax":0.26854, "ay":-5.11625, "alpha":-1.55202, "fx":[1.29196,12.84951,8.40018,-4.27031], "fy":[-89.20699,-87.36628,-84.94579,-86.58464]}, - {"t":0.82975, "x":3.7077, "y":2.27616, "heading":-1.14565, "vx":-2.99157, "vy":-0.19675, "omega":-0.65465, "ax":0.44337, "ay":-5.50207, "alpha":-1.03692, "fx":[4.96113,13.35764,10.42846,1.41918], "fy":[-94.76805,-93.52245,-92.46715,-93.59702]}, - {"t":0.84548, "x":3.66068, "y":2.27239, "heading":-1.15595, "vx":-2.98459, "vy":-0.28332, "omega":-0.67097, "ax":0.63328, "ay":-5.73008, "alpha":-0.73441, "fx":[8.68553,14.9782,13.03628,6.38784], "fy":[-98.20943,-97.2358,-96.75131,-97.67134]}, - {"t":0.86122, "x":3.6138, "y":2.26722, "heading":-1.16651, "vx":-2.97463, "vy":-0.37348, "omega":-0.68252, "ax":0.83312, "ay":-5.86778, "alpha":-0.54275, "fx":[12.4502,17.28781,16.00008,10.9464], "fy":[-100.34183,-99.51349,-99.28678,-100.09492]}, - {"t":0.87695, "x":3.56709, "y":2.26062, "heading":-1.17725, "vx":-2.96152, "vy":-0.46581, "omega":-0.69106, "ax":1.09063, "ay":-5.93934, "alpha":-0.41426, "fx":[17.09343,20.89033,20.07779,16.14396], "fy":[-101.46435,-100.69635,-100.58933,-101.35592]}, - {"t":0.89269, "x":3.52063, "y":2.25255, "heading":-1.18813, "vx":-2.94436, "vy":-0.55927, "omega":-0.69758, "ax":1.25632, "ay":-6.05749, "alpha":-0.40157, "fx":[19.84501,23.62184,22.96332,19.04852], "fy":[-103.46043,-102.6345,-102.60938,-103.44033]}, - {"t":0.91951, "x":3.44211, "y":2.23537, "heading":-1.20684, "vx":-2.91066, "vy":-0.72174, "omega":-0.70835, "ax":1.61015, "ay":-5.82093, "alpha":-0.54725, "fx":[25.18852,30.16406,29.71226,24.48765], "fy":[-99.82829,-98.40689,-98.17276,-99.64155]}, - {"t":0.94633, "x":3.36462, "y":2.21392, "heading":-1.22583, "vx":-2.86748, "vy":-0.87787, "omega":-0.72303, "ax":1.82486, "ay":-5.45716, "alpha":-0.80819, "fx":[27.81519,34.69901,34.50885,27.13829], "fy":[-94.37316,-92.04667,-91.19935,-93.67954]}, - {"t":0.97315, "x":3.28837, "y":2.18841, "heading":-1.24523, "vx":-2.81853, "vy":-1.02424, "omega":-0.74471, "ax":1.86789, "ay":-4.79458, "alpha":-1.32319, "fx":[27.00166,36.97868,37.05488,26.05412], "fy":[-84.69334,-80.94224,-78.20244,-82.3799]}, - {"t":0.99997, "x":3.21344, "y":2.15921, "heading":-1.2652, "vx":-2.76843, "vy":-1.15283, "omega":-0.7802, "ax":1.54645, "ay":-3.54047, "alpha":-2.30164, "fx":[19.97081,34.13745,33.58599,17.52445], "fy":[-66.71894,-61.39518,-53.33319,-59.44218]}, - {"t":1.02679, "x":3.13974, "y":2.12702, "heading":-1.28613, "vx":-2.72695, "vy":-1.2478, "omega":-0.84193, "ax":0.87189, "ay":-1.86019, "alpha":-3.20637, "fx":[8.42749,24.9836,22.06831,3.84298], "fy":[-41.62666,-36.2154,-21.4577,-27.26572]}, - {"t":1.05362, "x":3.06691, "y":2.09288, "heading":-1.30871, "vx":-2.70357, "vy":-1.29769, "omega":-0.92793, "ax":0.3627, "ay":-0.7485, "alpha":-3.06366, "fx":[0.51255,15.79205,12.12374,-3.75072], "fy":[-22.42972,-18.18144,-3.00549,-7.31041]}, - {"t":1.08044, "x":2.99453, "y":2.05781, "heading":-1.3336, "vx":-2.69384, "vy":-1.31777, "omega":-1.0101, "ax":0.13671, "ay":-0.27849, "alpha":-2.54743, "fx":[-2.53143,10.2712,7.25887,-5.69678], "fy":[-12.71503,-9.59013,3.24252,0.11432]}, - {"t":1.10726, "x":2.92233, "y":2.02236, "heading":-1.36069, "vx":-2.69017, "vy":-1.32524, "omega":-1.07843, "ax":0.05032, "ay":-0.102, "alpha":-2.08359, "fx":[-3.2988,7.26445,5.02926,-5.57147], "fy":[-8.15291,-5.89396,4.68219,2.42465]}, - {"t":1.13408, "x":2.85019, "y":1.98678, "heading":-1.38962, "vx":-2.68882, "vy":-1.32797, "omega":-1.13432, "ax":0.01845, "ay":-0.03733, "alpha":-1.72985, "fx":[-3.29186,5.53748,3.92419,-4.91457], "fy":[-5.8612,-4.24225,4.59079,2.97276]}, - {"t":1.1609, "x":2.77808, "y":1.95115, "heading":-1.42004, "vx":-2.68833, "vy":-1.32897, "omega":-1.18071, "ax":0.00699, "ay":-0.01413, "alpha":-1.48337, "fx":[-3.10906,4.50346,3.3482,-4.26692], "fy":[-4.6257,-3.46887,4.14468,2.98826]}, - {"t":1.18772, "x":2.70597, "y":1.9155, "heading":-1.45171, "vx":-2.68814, "vy":-1.32935, "omega":-1.2205, "ax":0.00339, "ay":-0.00684, "alpha":-1.33772, "fx":[-2.9775,3.91781,3.09322,-3.80311], "fy":[-3.97688,-3.15166,3.74404,2.91904]}, - {"t":1.21455, "x":2.63387, "y":1.87984, "heading":-1.48445, "vx":-2.68805, "vy":-1.32954, "omega":-1.25638, "ax":0.00365, "ay":-0.00737, "alpha":-1.29054, "fx":[-2.98631,3.68828,3.11095,-3.56463], "fy":[-3.75189,-3.17391,3.50101,2.92332]}, - {"t":1.24137, "x":2.56178, "y":1.84418, "heading":-1.51814, "vx":-2.68795, "vy":-1.32973, "omega":-1.29099, "ax":0.00808, "ay":-0.01631, "alpha":-1.34543, "fx":[-3.16595,3.80826,3.44187,-3.53469], "fy":[-3.94919,-3.58111,3.39377,3.02655]}, - {"t":1.26819, "x":2.48969, "y":1.80851, "heading":-1.55277, "vx":-2.68773, "vy":-1.33017, "omega":-1.32708, "ax":0.0216, "ay":-0.04361, "alpha":-1.51378, "fx":[-3.48905,4.36514,4.22769,-3.63422], "fy":[-4.7424,-4.59865,3.2571,3.11684]}, - {"t":1.29501, "x":2.4176, "y":1.77281, "heading":-1.58837, "vx":-2.68716, "vy":-1.33134, "omega":-1.36768, "ax":0.05925, "ay":-0.11939, "alpha":-1.81681, "fx":[-3.78593,5.63255,5.81616,-3.63171], "fy":[-6.66771,-6.82228,2.5982,2.76864]}, - {"t":1.32183, "x":2.34555, "y":1.73706, "heading":-1.62505, "vx":-2.68557, "vy":-1.33454, "omega":-1.41641, "ax":0.16249, "ay":-0.32563, "alpha":-2.28238, "fx":[-3.469,8.32351,9.05714,-2.8562], "fy":[-11.15749,-11.73098,0.0415,0.69173]}, - {"t":1.34865, "x":2.27358, "y":1.70115, "heading":-1.66304, "vx":-2.68121, "vy":-1.34328, "omega":-1.47763, "ax":0.44116, "ay":-0.86506, "alpha":-2.88019, "fx":[-0.73857,14.08698,15.98345,0.68426], "fy":[-21.61003,-22.53538,-7.98813,-6.72443]}, - {"t":1.37548, "x":2.20182, "y":1.66481, "heading":-1.70267, "vx":-2.66938, "vy":-1.36648, "omega":-1.55488, "ax":4.32147, "ay":0.54788, "alpha":-1.53896, "fx":[71.42755,75.90201,75.66374,71.03478], "fy":[4.62477,2.72155,13.52502,16.406]}, - {"t":1.4023, "x":2.13178, "y":1.62835, "heading":-1.74438, "vx":-2.55347, "vy":-1.35178, "omega":-1.59616, "ax":5.7045, "ay":2.67727, "alpha":-0.11131, "fx":[97.07439,97.36726,96.99274,96.69352], "fy":[45.40666,44.83006,45.67171,46.24967]}, - {"t":1.42912, "x":2.06534, "y":1.59306, "heading":-1.78719, "vx":-2.40046, "vy":-1.27997, "omega":-1.59914, "ax":5.74631, "ay":2.76648, "alpha":-0.05229, "fx":[97.75885,97.90649,97.72795,97.57893], "fy":[47.01394,46.71815,47.10006,47.39587]}, - {"t":1.45594, "x":2.00303, "y":1.55972, "heading":-1.83008, "vx":-2.24634, "vy":-1.20577, "omega":-1.60055, "ax":5.76061, "ay":2.79777, "alpha":-0.02817, "fx":[97.99155,98.07577,97.98143,97.89683], "fy":[47.57492,47.40536,47.60372,47.77322]}, - {"t":1.48276, "x":1.94485, "y":1.52839, "heading":-1.87301, "vx":-2.09183, "vy":-1.13073, "omega":-1.6013, "ax":5.76782, "ay":2.81373, "alpha":-0.01421, "fx":[98.10974,98.15439,98.10826,98.06352], "fy":[47.85781,47.76772,47.86385,47.9539]}, - {"t":1.50958, "x":1.89081, "y":1.49907, "heading":-1.91596, "vx":-1.93712, "vy":-1.05526, "omega":-1.60168, "ax":5.77216, "ay":2.82342, "alpha":-0.00482, "fx":[98.18234,98.1982,98.18312,98.16725], "fy":[48.02593,47.9939,48.02516,48.05718]}, - {"t":1.53641, "x":1.84093, "y":1.47179, "heading":-1.95892, "vx":-1.7823, "vy":-0.97953, "omega":-1.60181, "ax":5.77505, "ay":2.82992, "alpha":0.00202, "fx":[98.23237,98.22546,98.2315,98.2384], "fy":[48.13541,48.14937,48.1369,48.12294]}, - {"t":1.56323, "x":1.79521, "y":1.44653, "heading":-2.00188, "vx":-1.62741, "vy":-0.90363, "omega":-1.60176, "ax":5.77712, "ay":2.83459, "alpha":0.00727, "fx":[98.26964,98.24379,98.26453,98.29036], "fy":[48.21081,48.26307,48.22035,48.16807]}, - {"t":1.59005, "x":1.75364, "y":1.42331, "heading":-2.04484, "vx":-1.47246, "vy":-0.8276, "omega":-1.60156, "ax":5.77866, "ay":2.83811, "alpha":0.01145, "fx":[98.29902,98.25691,98.28786,98.32994], "fy":[48.26463,48.3498,48.28616,48.20092]}, - {"t":1.61687, "x":1.71622, "y":1.40214, "heading":-2.0878, "vx":-1.31746, "vy":-0.75148, "omega":-1.60126, "ax":5.77987, "ay":2.84085, "alpha":0.01487, "fx":[98.3232,98.2668,98.30466,98.36101], "fy":[48.3039,48.41798,48.34023,48.22604]}, - {"t":1.64369, "x":1.68296, "y":1.383, "heading":-2.13075, "vx":-1.16244, "vy":-0.67528, "omega":-1.60086, "ax":5.78083, "ay":2.84305, "alpha":0.01771, "fx":[98.34374,98.27463,98.31688,98.38593], "fy":[48.33292,48.47274,48.38608,48.24608]}, - {"t":1.67051, "x":1.65386, "y":1.36591, "heading":-2.17369, "vx":-1.00739, "vy":-0.59903, "omega":-1.60038, "ax":5.78162, "ay":2.84485, "alpha":0.02013, "fx":[98.36166,98.28111,98.32574,98.40623], "fy":[48.35446,48.51743,48.42595,48.26271]}, - {"t":1.69734, "x":1.62892, "y":1.35087, "heading":-2.21661, "vx":-0.85231, "vy":-0.52272, "omega":-1.59984, "ax":3.86553, "ay":-4.7164, "alpha":0.70926, "fx":[69.00756,67.67086,62.31603,64.01169], "fy":[-77.7202,-78.36816,-82.81858,-81.9916]}, - {"t":1.74186, "x":1.59481, "y":1.32292, "heading":-2.28784, "vx":-0.68021, "vy":-0.73271, "omega":-1.56827, "ax":0.86763, "ay":-0.76488, "alpha":9.04916, "fx":[46.62442,14.84838,-19.52034,17.08033], "fy":[-10.98486,21.59778,-17.82732,-44.82716]}, - {"t":1.78638, "x":1.56538, "y":1.28954, "heading":-2.35766, "vx":-0.64158, "vy":-0.76676, "omega":-1.16537, "ax":0.02284, "ay":-0.01909, "alpha":8.39322, "fx":[31.16983,0.46522,-30.45394,0.37324], "fy":[-0.39476,30.51281,-0.30557,-31.11132]}, - {"t":1.8309, "x":1.53684, "y":1.25538, "heading":-2.40955, "vx":-0.64056, "vy":-0.76761, "omega":-0.79169, "ax":0.00055, "ay":-0.00046, "alpha":7.26453, "fx":[26.63938,1.43224,-26.62177,-1.41223], "fy":[-1.43048,26.62312,1.41398,-26.63802]}, - {"t":1.87543, "x":1.50832, "y":1.22121, "heading":-2.4448, "vx":-0.64054, "vy":-0.76763, "omega":-0.46825, "ax":0.00001, "ay":-0.00001, "alpha":6.20759, "fx":[22.69924,2.01672,-22.69883,-2.01626], "fy":[-2.01668,22.69886,2.0163,-22.69921]}, - {"t":1.91995, "x":1.4798, "y":1.18703, "heading":-2.46565, "vx":-0.64054, "vy":-0.76764, "omega":-0.19187, "ax":0.0, "ay":0.0, "alpha":5.22335, "fx":[19.06049,2.09456,-19.06048,-2.09455], "fy":[-2.09456,19.06048,2.09456,-19.06049]}, - {"t":1.96447, "x":1.45128, "y":1.15285, "heading":-2.47419, "vx":-0.64054, "vy":-0.76764, "omega":0.04068, "ax":0.0, "ay":0.0, "alpha":4.3089, "fx":[15.70822,1.86212,-15.70822,-1.86212], "fy":[-1.86212,15.70822,1.86212,-15.70822]}, - {"t":2.00899, "x":1.42277, "y":1.11868, "heading":-2.47238, "vx":-0.64054, "vy":-0.76764, "omega":0.23253, "ax":0.0, "ay":0.0, "alpha":3.45826, "fx":[12.60989,1.47167,-12.60989,-1.47167], "fy":[-1.47167,12.60989,1.47167,-12.60989]}, - {"t":2.05352, "x":1.39425, "y":1.0845, "heading":-2.46202, "vx":-0.64054, "vy":-0.76764, "omega":0.3865, "ax":0.0, "ay":0.0, "alpha":2.66309, "fx":[9.72164,1.0327,-9.72164,-1.0327], "fy":[-1.0327,9.72164,1.0327,-9.72164]}, - {"t":2.09804, "x":1.36573, "y":1.05032, "heading":-2.44482, "vx":-0.64054, "vy":-0.76764, "omega":0.50507, "ax":0.0, "ay":0.0, "alpha":1.91323, "fx":[6.99603,0.62163,-6.99603,-0.62163], "fy":[-0.62163,6.99603,0.62163,-6.99603]}, - {"t":2.14256, "x":1.33721, "y":1.01615, "heading":-2.42233, "vx":-0.64054, "vy":-0.76764, "omega":0.59025, "ax":0.0, "ay":0.0, "alpha":1.19737, "fx":[4.38599,0.29049,-4.38599,-0.29049], "fy":[-0.29049,4.38599,0.29049,-4.38599]}, - {"t":2.18708, "x":1.30869, "y":0.98197, "heading":-2.39605, "vx":-0.64054, "vy":-0.76764, "omega":0.64356, "ax":0.0, "ay":0.0, "alpha":0.50337, "fx":[1.84644,0.07363,-1.84644,-0.07363], "fy":[-0.07363,1.84644,0.07363,-1.84644]}, - {"t":2.23161, "x":1.28017, "y":0.94779, "heading":-2.3674, "vx":-0.64054, "vy":-0.76764, "omega":0.66597, "ax":0.0, "ay":0.0, "alpha":-0.18128, "fx":[-0.66546,-0.00746,0.66546,0.00746], "fy":[0.00746,-0.66546,-0.00746,0.66546]}, - {"t":2.27613, "x":1.25166, "y":0.91361, "heading":-2.33775, "vx":-0.64054, "vy":-0.76764, "omega":0.6579, "ax":0.0, "ay":0.0, "alpha":-0.86931, "fx":[-3.19075,0.05887,3.19075,-0.05887], "fy":[-0.05887,-3.19075,0.05887,3.19075]}, - {"t":2.32065, "x":1.22314, "y":0.87944, "heading":-2.30846, "vx":-0.64054, "vy":-0.76764, "omega":0.61919, "ax":0.0, "ay":0.0, "alpha":-1.57336, "fx":[-5.76932,0.27563,5.76932,-0.27563], "fy":[-0.27563,-5.76932,0.27563,5.76932]}, - {"t":2.36517, "x":1.19462, "y":0.84526, "heading":-2.28089, "vx":-0.64054, "vy":-0.76764, "omega":0.54914, "ax":0.0, "ay":0.0, "alpha":-2.30578, "fx":[-8.44065,0.63685,8.44065,-0.63685], "fy":[-0.63685,-8.44065,0.63685,8.44065]}, - {"t":2.4097, "x":1.1661, "y":0.81108, "heading":-2.25644, "vx":-0.64054, "vy":-0.76764, "omega":0.44648, "ax":0.0, "ay":0.0, "alpha":-3.07831, "fx":[-11.24447,1.12545,11.24447,-1.12545], "fy":[-1.12545,-11.24447,1.12545,11.24447]}, - {"t":2.45422, "x":1.13758, "y":0.77691, "heading":-2.23656, "vx":-0.64054, "vy":-0.76764, "omega":0.30943, "ax":0.00001, "ay":0.00001, "alpha":-3.90172, "fx":[-14.22083,1.70975,14.22131,-1.70926], "fy":[-1.70925,-14.22083,1.70976,14.22131]}, - {"t":2.49874, "x":1.10906, "y":0.74273, "heading":-2.22278, "vx":-0.64054, "vy":-0.76763, "omega":0.13572, "ax":1.99642, "ay":2.39256, "alpha":-3.01086, "fx":[22.36249,38.52059,44.52576,30.42506], "fy":[42.21741,29.46236,39.98658,51.12049]}, - {"t":2.54326, "x":1.08252, "y":0.71092, "heading":-2.21674, "vx":-0.55165, "vy":-0.66111, "omega":0.00166, "ax":4.12514, "ay":4.94367, "alpha":-0.01839, "fx":[70.09786,70.24394,70.23698,70.09114], "fy":[84.14805,84.02618,84.03278,84.15442]}, - {"t":2.58779, "x":1.06205, "y":0.68639, "heading":-2.21667, "vx":-0.36799, "vy":-0.44101, "omega":0.00085, "ax":4.13155, "ay":4.95134, "alpha":-0.01077, "fx":[70.23566,70.32134,70.31717,70.23156], "fy":[84.25485,84.18336,84.18707,84.25848]}, - {"t":2.63231, "x":1.04976, "y":0.67166, "heading":-2.21663, "vx":-0.18404, "vy":-0.22056, "omega":0.00037, "ax":4.13369, "ay":4.95391, "alpha":-0.00823, "fx":[70.28172,70.3472,70.34398,70.27855], "fy":[84.29053,84.23589,84.23869,84.29328]}, - {"t":2.67683, "x":1.04567, "y":0.66675, "heading":-2.21661, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.03084, "ay":4.04072, "alpha":0.00858, "fx":[85.59341,85.53936,85.55299,85.60706], "fy":[68.7065,68.77374,68.75666,68.68936]}, - {"t":2.72136, "x":1.05065, "y":0.67076, "heading":-2.21661, "vx":0.22402, "vy":0.17993, "omega":0.00038, "ax":5.03032, "ay":4.0403, "alpha":0.00879, "fx":[85.58497,85.52961,85.54356,85.59895], "fy":[68.69872,68.76759,68.75009,68.68116]}, - {"t":2.76589, "x":1.06562, "y":0.68278, "heading":-2.2166, "vx":0.44802, "vy":0.35985, "omega":0.00077, "ax":5.02966, "ay":4.03978, "alpha":0.00905, "fx":[85.57443,85.51743,85.53178,85.58881], "fy":[68.689,68.75991,68.74188,68.67091]}, - {"t":2.81042, "x":1.09055, "y":0.7028, "heading":-2.21656, "vx":0.67199, "vy":0.53974, "omega":0.00118, "ax":5.02882, "ay":4.0391, "alpha":0.00939, "fx":[85.56087,85.50176,85.51664,85.57578], "fy":[68.67651,68.75003,68.73133,68.65773]}, - {"t":2.85495, "x":1.12546, "y":0.73084, "heading":-2.21651, "vx":0.89592, "vy":0.7196, "omega":0.00159, "ax":5.02769, "ay":4.03819, "alpha":0.00984, "fx":[85.54281,85.48089,85.49645,85.55841], "fy":[68.65986,68.73687,68.71726,68.64017]}, - {"t":2.89948, "x":1.17034, "y":0.76689, "heading":-2.21644, "vx":1.1198, "vy":0.89942, "omega":0.00203, "ax":5.02612, "ay":4.03693, "alpha":0.01047, "fx":[85.51753,85.45167,85.4682,85.5341], "fy":[68.63656,68.71846,68.69758,68.61559]}, - {"t":2.94401, "x":1.22519, "y":0.81094, "heading":-2.21635, "vx":1.34362, "vy":1.07918, "omega":0.0025, "ax":5.02376, "ay":4.03504, "alpha":0.01141, "fx":[85.47965,85.40788,85.42586,85.49767], "fy":[68.60164,68.69085,68.66807,68.57875]}, - {"t":2.98854, "x":1.29, "y":0.863, "heading":-2.21624, "vx":1.56732, "vy":1.25886, "omega":0.00301, "ax":5.01984, "ay":4.03188, "alpha":0.01298, "fx":[85.4166,85.335,85.35536,85.43702], "fy":[68.54352,68.64492,68.61895,68.51742]}, - {"t":3.03307, "x":1.36477, "y":0.92305, "heading":-2.2161, "vx":1.79085, "vy":1.4384, "omega":0.00359, "ax":5.01201, "ay":4.0256, "alpha":0.01612, "fx":[85.2909,85.18967,85.21473,85.31605], "fy":[68.42764,68.55332,68.52096,68.39507]}, - {"t":3.0776, "x":1.44949, "y":0.9911, "heading":-2.21594, "vx":2.01404, "vy":1.61766, "omega":0.0043, "ax":4.98872, "ay":4.00689, "alpha":0.02551, "fx":[84.91715,84.75755,84.79607,84.9559], "fy":[68.08318,68.28081,68.22917,68.03102]}, - {"t":3.12213, "x":1.54412, "y":1.0671, "heading":-2.21575, "vx":2.23618, "vy":1.79608, "omega":0.00544, "ax":2.29611, "ay":1.84422, "alpha":1.32384, "fx":[43.43518,37.51154,34.5143,40.76385], "fy":[31.16918,36.46583,31.70577,26.1377]}, - {"t":3.16666, "x":1.64597, "y":1.14891, "heading":-2.21551, "vx":2.33843, "vy":1.8782, "omega":0.06439, "ax":0.00013, "ay":0.0001, "alpha":1.454, "fx":[5.2872,-0.74623,-5.28276,0.7507], "fy":[0.75023,5.28674,-0.74671,-5.28322]}, - {"t":3.21119, "x":1.7501, "y":1.23255, "heading":-2.21264, "vx":2.33843, "vy":1.87821, "omega":0.12914, "ax":0.0, "ay":0.0, "alpha":1.0371, "fx":[3.76808,-0.54467,-3.76808,0.54467], "fy":[0.54467,3.76808,-0.54467,-3.76808]}, - {"t":3.25572, "x":1.85423, "y":1.31618, "heading":-2.20689, "vx":2.33843, "vy":1.87821, "omega":0.17532, "ax":0.0, "ay":0.0, "alpha":0.72503, "fx":[2.632,-0.39592,-2.63201,0.39591], "fy":[0.39592,2.63201,-0.39591,-2.63201]}, - {"t":3.30025, "x":1.95836, "y":1.39982, "heading":-2.19908, "vx":2.33843, "vy":1.87821, "omega":0.2076, "ax":0.0, "ay":0.0, "alpha":0.48703, "fx":[1.76588,-0.27975,-1.76589,0.27974], "fy":[0.27975,1.76588,-0.27974,-1.76588]}, - {"t":3.34478, "x":2.06249, "y":1.48345, "heading":-2.18984, "vx":2.33843, "vy":1.87821, "omega":0.22929, "ax":0.0, "ay":0.0, "alpha":0.29914, "fx":[1.08298,-0.18184,-1.08299,0.18184], "fy":[0.18184,1.08299,-0.18184,-1.08298]}, - {"t":3.38931, "x":2.16662, "y":1.56709, "heading":-2.17963, "vx":2.33843, "vy":1.87821, "omega":0.24261, "ax":0.0, "ay":0.0, "alpha":0.14217, "fx":[0.51379,-0.09167,-0.51379,0.09167], "fy":[0.09167,0.51379,-0.09167,-0.51379]}, - {"t":3.43384, "x":2.27075, "y":1.65073, "heading":-2.16883, "vx":2.33843, "vy":1.87821, "omega":0.24894, "ax":0.0, "ay":0.0, "alpha":-0.00006, "fx":[-0.00021,0.00004,0.00021,-0.00004], "fy":[-0.00004,-0.00021,0.00004,0.00021]}, - {"t":3.47837, "x":2.37488, "y":1.73436, "heading":-2.15774, "vx":2.33843, "vy":1.87821, "omega":0.24894, "ax":0.0, "ay":0.0, "alpha":-0.14227, "fx":[-0.51203,0.10297,0.51203,-0.10297], "fy":[-0.10297,-0.51203,0.10297,0.51203]}, - {"t":3.5229, "x":2.47901, "y":1.818, "heading":-2.14666, "vx":2.33843, "vy":1.87821, "omega":0.2426, "ax":0.0, "ay":0.0, "alpha":-0.2992, "fx":[-1.07435,0.22847,1.07435,-0.22847], "fy":[-0.22847,-1.07435,0.22847,1.07435]}, - {"t":3.56743, "x":2.58314, "y":1.90163, "heading":-2.13585, "vx":2.33843, "vy":1.87821, "omega":0.22928, "ax":0.0, "ay":0.0, "alpha":-0.48704, "fx":[-1.74472,0.39078,1.74472,-0.39078], "fy":[-0.39078,-1.74472,0.39078,1.74472]}, - {"t":3.61196, "x":2.68727, "y":1.98527, "heading":-2.12564, "vx":2.33843, "vy":1.87821, "omega":0.20759, "ax":0.0, "ay":0.0, "alpha":-0.725, "fx":[-2.59109,0.6082,2.59109,-0.60819], "fy":[-0.6082,-2.59109,0.60819,2.59109]}, - {"t":3.65649, "x":2.7914, "y":2.06891, "heading":-2.1164, "vx":2.33843, "vy":1.87821, "omega":0.17531, "ax":0.0, "ay":0.0, "alpha":-1.03706, "fx":[-3.69816,0.9042,3.69815,-0.9042], "fy":[-0.9042,-3.69815,0.9042,3.69816]}, - {"t":3.70102, "x":2.89553, "y":2.15254, "heading":-2.10859, "vx":2.33843, "vy":1.87821, "omega":0.12913, "ax":-0.00013, "ay":-0.0001, "alpha":-1.45399, "fx":[-5.17711,1.30592,5.17266,-1.31039], "fy":[-1.30992,-5.17664,1.3064,5.17313]}, - {"t":3.74555, "x":2.99966, "y":2.23618, "heading":-2.10284, "vx":2.33843, "vy":1.8782, "omega":0.06438, "ax":-2.29611, "ay":-1.84422, "alpha":-1.32369, "fx":[-43.22717,-37.01729,-34.72878,-41.2516], "fy":[-31.73612,-36.47882,-31.10481,-26.15874]}, - {"t":3.79008, "x":3.10151, "y":2.31799, "heading":-2.09998, "vx":2.23618, "vy":1.79608, "omega":0.00544, "ax":-4.98872, "ay":-4.00689, "alpha":-0.02551, "fx":[-84.9053,-84.75118,-84.80797,-84.96222], "fy":[-68.09811,-68.28843,-68.21423,-68.02342]}, - {"t":3.8346, "x":3.19614, "y":2.39399, "heading":-2.09973, "vx":2.01404, "vy":1.61766, "omega":0.0043, "ax":-5.01201, "ay":-4.0256, "alpha":-0.01612, "fx":[-85.28332,-85.18567,-85.22233,-85.32004], "fy":[-68.43714,-68.5582,-68.51146,-68.39019]}, - {"t":3.87913, "x":3.28086, "y":2.46204, "heading":-2.09954, "vx":1.79085, "vy":1.4384, "omega":0.00359, "ax":-5.01984, "ay":-4.03188, "alpha":-0.01298, "fx":[-85.41046,-85.33178,-85.36152,-85.44024], "fy":[-68.5512,-68.64888,-68.61127,-68.51346]}, - {"t":3.92366, "x":3.35563, "y":2.52209, "heading":-2.09938, "vx":1.56732, "vy":1.25886, "omega":0.00301, "ax":-5.02376, "ay":-4.03504, "alpha":-0.01141, "fx":[-85.47423,-85.40504,-85.43128,-85.5005], "fy":[-68.6084,-68.69435,-68.6613,-68.57525]}, - {"t":3.96819, "x":3.42044, "y":2.57415, "heading":-2.09925, "vx":1.34362, "vy":1.07918, "omega":0.0025, "ax":-5.02612, "ay":-4.03693, "alpha":-0.01047, "fx":[-85.51255,-85.44906,-85.47319,-85.5367], "fy":[-68.64278,-68.72167,-68.69136,-68.61237]}, - {"t":4.01272, "x":3.47529, "y":2.6182, "heading":-2.09914, "vx":1.1198, "vy":0.89942, "omega":0.00203, "ax":-5.02769, "ay":-4.03819, "alpha":-0.00984, "fx":[-85.53811,-85.47843,-85.50115,-85.56085], "fy":[-68.66571,-68.7399,-68.7114,-68.63714]}, - {"t":4.05725, "x":3.52017, "y":2.65425, "heading":-2.09905, "vx":0.89592, "vy":0.7196, "omega":0.0016, "ax":-5.02882, "ay":-4.0391, "alpha":-0.00939, "fx":[-85.55639,-85.49942,-85.52113,-85.57811], "fy":[-68.68211,-68.75293,-68.72573,-68.65484]}, - {"t":4.10178, "x":3.55508, "y":2.68228, "heading":-2.09897, "vx":0.67199, "vy":0.53974, "omega":0.00118, "ax":-5.02966, "ay":-4.03978, "alpha":-0.00905, "fx":[-85.5701,-85.51517,-85.53612,-85.59106], "fy":[-68.6944,-68.76271,-68.73648,-68.66811]}, - {"t":4.14631, "x":3.58001, "y":2.70231, "heading":-2.09892, "vx":0.44802, "vy":0.35985, "omega":0.00077, "ax":-5.03032, "ay":-4.0403, "alpha":-0.00879, "fx":[-85.58076,-85.52742,-85.54778,-85.60114], "fy":[-68.70397,-68.77031,-68.74484,-68.67844]}, - {"t":4.19084, "x":3.59498, "y":2.71433, "heading":-2.09889, "vx":0.22402, "vy":0.17993, "omega":0.00038, "ax":-5.03084, "ay":-4.04072, "alpha":-0.00858, "fx":[-85.5893,-85.53722,-85.5571,-85.6092], "fy":[-68.71162,-68.7764,-68.75153,-68.6867]}, - {"t":4.23537, "x":3.59996, "y":2.71834, "heading":-2.09887, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/C_RIGHT_PATH3.traj b/src/main/deploy/choreo/C_RIGHT_PATH3.traj deleted file mode 100644 index d384cbbf..00000000 --- a/src/main/deploy/choreo/C_RIGHT_PATH3.traj +++ /dev/null @@ -1,137 +0,0 @@ -{ - "name":"C_RIGHT_PATH3", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":3.999176502227783, "y":2.845594631958008, "heading":-2.1010083691287966, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.8789600133895872, "y":1.543542504310608, "heading":-2.217924532332081, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.1281020641326904, "y":0.6461422443389893, "heading":-2.217924532332081, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":3.533947706222534, "y":2.756060838699341, "heading":-2.077894951837786, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":3.0}}, "enabled":true}, - {"from":1, "to":2, "data":{"type":"MaxVelocity", "props":{"max":1.0}}, "enabled":true}, - {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"3.999176502227783 m", "val":3.999176502227783}, "y":{"exp":"(8.0518 - 5.206205368041992) m", "val":2.845594631958008}, "heading":{"exp":"-2.1010083691287966 rad", "val":-2.1010083691287966}, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.8789600133895874 m", "val":1.8789600133895872}, "y":{"exp":"1.543542504310608 m", "val":1.543542504310608}, "heading":{"exp":"-2.217924532332081 rad", "val":-2.217924532332081}, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.1281020641326904 m", "val":1.1281020641326904}, "y":{"exp":"0.6461422443389893 m", "val":0.6461422443389893}, "heading":{"exp":"-2.217924532332081 rad", "val":-2.217924532332081}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"3.533947706222534 m", "val":3.533947706222534}, "y":{"exp":"2.756060838699341 m", "val":2.756060838699341}, "heading":{"exp":"-2.077894951837786 rad", "val":-2.077894951837786}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"3 m / s", "val":3.0}}}, "enabled":true}, - {"from":1, "to":2, "data":{"type":"MaxVelocity", "props":{"max":{"exp":"1 m / s", "val":1.0}}}, "enabled":true}, - {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.16593,2.41619,3.94926], - "samples":[ - {"t":0.0, "x":3.99918, "y":2.84559, "heading":-2.10101, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.52646, "ay":-3.32919, "alpha":-0.00621, "fx":[-94.01019,-93.98097,-93.99681,-94.02602], "fy":[-56.61761,-56.66604,-56.63965,-56.5912]}, - {"t":0.03886, "x":3.995, "y":2.84308, "heading":-2.10101, "vx":-0.21478, "vy":-0.12939, "omega":-0.00024, "ax":-5.52589, "ay":-3.32885, "alpha":-0.00635, "fx":[-94.00069,-93.97081,-93.98699,-94.01687], "fy":[-56.61155,-56.66106,-56.63407,-56.58453]}, - {"t":0.07773, "x":3.98248, "y":2.83554, "heading":-2.10102, "vx":-0.42954, "vy":-0.25876, "omega":-0.00049, "ax":-5.5252, "ay":-3.32844, "alpha":-0.00652, "fx":[-93.98918,-93.9585,-93.97511,-94.00579], "fy":[-56.6042,-56.65504,-56.62733,-56.57647]}, - {"t":0.11659, "x":3.96162, "y":2.82297, "heading":-2.10104, "vx":-0.64428, "vy":-0.38812, "omega":-0.00074, "ax":-5.52436, "ay":-3.32793, "alpha":-0.00673, "fx":[-93.97497,-93.9433,-93.96043,-93.9921], "fy":[-56.59513,-56.6476,-56.61899,-56.5665]}, - {"t":0.15546, "x":3.9324, "y":2.80537, "heading":-2.10107, "vx":-0.85898, "vy":-0.51746, "omega":-0.001, "ax":-5.52328, "ay":-3.32728, "alpha":-0.007, "fx":[-93.95697,-93.92404,-93.94184,-93.97477], "fy":[-56.58365,-56.63817,-56.60844,-56.55388]}, - {"t":0.19432, "x":3.89485, "y":2.78275, "heading":-2.1011, "vx":-1.07363, "vy":-0.64677, "omega":-0.00127, "ax":-5.52187, "ay":-3.32643, "alpha":-0.00735, "fx":[-93.93343,-93.89887,-93.91753,-93.9521], "fy":[-56.56863,-56.62585,-56.59464,-56.53738]}, - {"t":0.23319, "x":3.84895, "y":2.7551, "heading":-2.10115, "vx":-1.28824, "vy":-0.77605, "omega":-0.00156, "ax":-5.51996, "ay":-3.32528, "alpha":-0.00782, "fx":[-93.90135,-93.86454,-93.88439,-93.92119], "fy":[-56.54815,-56.60906,-56.57582,-56.51488]}, - {"t":0.27205, "x":3.79472, "y":2.72243, "heading":-2.10121, "vx":-1.50277, "vy":-0.90528, "omega":-0.00186, "ax":-5.51719, "ay":-3.32361, "alpha":-0.00851, "fx":[-93.85502,-93.81498,-93.83653,-93.87656], "fy":[-56.51859,-56.5848,-56.54865,-56.48239]}, - {"t":0.31091, "x":3.73215, "y":2.68473, "heading":-2.10129, "vx":-1.71719, "vy":-1.03445, "omega":-0.0022, "ax":-5.51284, "ay":-3.32099, "alpha":-0.00959, "fx":[-93.78228,-93.73714,-93.76135,-93.80647], "fy":[-56.47216,-56.54672,-56.50597,-56.43136]}, - {"t":0.34978, "x":3.66125, "y":2.64202, "heading":-2.10137, "vx":-1.93144, "vy":-1.16352, "omega":-0.00257, "ax":-5.50502, "ay":-3.31628, "alpha":-0.01154, "fx":[-93.65152,-93.59722,-93.62617,-93.68047], "fy":[-56.38871,-56.47825,-56.42924,-56.33961]}, - {"t":0.38864, "x":3.58202, "y":2.5943, "heading":-2.10147, "vx":-2.14539, "vy":-1.2924, "omega":-0.00302, "ax":-5.48684, "ay":-3.30533, "alpha":-0.01609, "fx":[-93.34754,-93.27185,-93.31167,-93.38734], "fy":[-56.19473,-56.319,-56.25068,-56.12623]}, - {"t":0.42751, "x":3.4945, "y":2.54157, "heading":-2.10159, "vx":-2.35863, "vy":-1.42086, "omega":-0.00364, "ax":-5.39749, "ay":-3.2515, "alpha":-0.03869, "fx":[-91.85595,-91.67418,-91.76355,-91.94522], "fy":[-55.24334,-55.53556,-55.37128,-55.07811]}, - {"t":0.46637, "x":3.39876, "y":2.4839, "heading":-2.10173, "vx":-2.5684, "vy":-1.54723, "omega":-0.00515, "ax":-0.01733, "ay":-0.01044, "alpha":-1.19309, "fx":[-4.53305,0.80725,3.94461,-1.39788], "fy":[-1.2801,-4.41645,0.9249,4.06132]}, - {"t":0.50524, "x":3.29893, "y":2.42376, "heading":-2.10193, "vx":-2.56908, "vy":-1.54764, "omega":-0.05151, "ax":0.0, "ay":0.0, "alpha":-0.91408, "fx":[-3.24776,0.84405,3.24776,-0.84406], "fy":[-0.8441,-3.24781,0.84401,3.24771]}, - {"t":0.5441, "x":3.19908, "y":2.36361, "heading":-2.10393, "vx":-2.56908, "vy":-1.54764, "omega":-0.08704, "ax":0.00001, "ay":-0.00001, "alpha":-0.70533, "fx":[-2.50726,0.64639,2.50748,-0.64617], "fy":[-0.64646,-2.50755,0.6461,2.50719]}, - {"t":0.58296, "x":3.09924, "y":2.30346, "heading":-2.10732, "vx":-2.56908, "vy":-1.54764, "omega":-0.11445, "ax":0.00003, "ay":-0.00005, "alpha":-0.55112, "fx":[-1.96031,0.49891,1.96142,-0.49779], "fy":[-0.49927,-1.96179,0.49743,1.95994]}, - {"t":0.62183, "x":2.99939, "y":2.24331, "heading":-2.11176, "vx":-2.56907, "vy":-1.54764, "omega":-0.13587, "ax":0.00017, "ay":-0.00028, "alpha":-0.4397, "fx":[-1.56331,0.39352,1.56908,-0.38775], "fy":[-0.39543,-1.57098,0.38584,1.5614]}, - {"t":0.66069, "x":2.89955, "y":2.18317, "heading":-2.11704, "vx":-2.56907, "vy":-1.54765, "omega":-0.15296, "ax":0.00088, "ay":-0.00146, "alpha":-0.36253, "fx":[-1.27802,0.33022,1.30797,-0.30028], "fy":[-0.34011,-1.31784,0.2904,1.26815]}, - {"t":0.69956, "x":2.7997, "y":2.12302, "heading":-2.12299, "vx":-2.56903, "vy":-1.54771, "omega":-0.16705, "ax":0.00457, "ay":-0.00758, "alpha":-0.31366, "fx":[-1.04264,0.34378,1.19798,-0.18843], "fy":[-0.39503,-1.2492,0.13718,0.99141]}, - {"t":0.73842, "x":2.69986, "y":2.06286, "heading":-2.12948, "vx":-2.56886, "vy":-1.548, "omega":-0.17924, "ax":0.0237, "ay":-0.03931, "alpha":-0.28931, "fx":[-0.63175,0.64187,1.4381,0.1645], "fy":[-0.90745,-1.70339,-0.42992,0.36631]}, - {"t":0.77729, "x":2.60004, "y":2.00267, "heading":-2.13645, "vx":-2.56793, "vy":-1.54953, "omega":-0.19048, "ax":0.12318, "ay":-0.20342, "alpha":-0.2869, "fx":[1.06644,2.32384,3.12408,1.86685], "fy":[-3.69118,-4.48675,-3.22983,-2.43279]}, - {"t":0.81615, "x":2.50033, "y":1.94229, "heading":-2.14385, "vx":-2.56315, "vy":-1.55743, "omega":-0.20163, "ax":0.68443, "ay":-0.97902, "alpha":-0.28813, "fx":[10.58831,11.83482,12.69485,11.45019], "fy":[-16.90807,-17.66569,-16.40104,-15.63635]}, - {"t":0.85501, "x":2.40124, "y":1.88103, "heading":-2.15169, "vx":-2.53655, "vy":-1.59548, "omega":-0.21283, "ax":5.48291, "ay":3.21429, "alpha":-0.00563, "fx":[93.25556,93.282,93.2698,93.24336], "fy":[54.6851,54.6408,54.66326,54.70754]}, - {"t":0.89388, "x":2.3068, "y":1.82145, "heading":-2.15996, "vx":-2.32346, "vy":-1.47056, "omega":-0.21305, "ax":5.51111, "ay":3.28047, "alpha":-0.00181, "fx":[93.74016,93.74881,93.74481,93.73616], "fy":[55.80354,55.78911,55.79606,55.81048]}, - {"t":0.93274, "x":2.22066, "y":1.76677, "heading":-2.16824, "vx":-2.10927, "vy":-1.34307, "omega":-0.21312, "ax":5.51891, "ay":3.29915, "alpha":-0.00041, "fx":[93.87458,93.87654,93.87565,93.87369], "fy":[56.11848,56.11522,56.11675,56.12001]}, - {"t":0.97161, "x":2.14285, "y":1.71706, "heading":-2.17652, "vx":-1.89478, "vy":-1.21485, "omega":-0.21314, "ax":5.52256, "ay":3.30797, "alpha":0.0004, "fx":[93.93765,93.93571,93.93657,93.93852], "fy":[56.26674,56.26997,56.2685,56.26526]}, - {"t":1.01047, "x":2.07338, "y":1.67235, "heading":-2.1848, "vx":-1.68015, "vy":-1.08629, "omega":-0.21312, "ax":5.52467, "ay":3.31311, "alpha":0.00094, "fx":[93.97429,93.96967,93.97169,93.9763], "fy":[56.35286,56.36053,56.35712,56.34945]}, - {"t":1.04934, "x":2.01226, "y":1.63263, "heading":-2.19309, "vx":-1.46544, "vy":-0.95753, "omega":-0.21308, "ax":5.52604, "ay":3.31647, "alpha":0.00134, "fx":[93.99825,93.99166,93.99448,94.00107], "fy":[56.4091,56.42005,56.4153,56.40434]}, - {"t":1.0882, "x":1.95948, "y":1.59792, "heading":-2.20137, "vx":-1.25068, "vy":-0.82863, "omega":-0.21303, "ax":5.52701, "ay":3.31884, "alpha":0.00165, "fx":[94.01516,94.00703,94.01043,94.01856], "fy":[56.44867,56.46218,56.45646,56.44295]}, - {"t":1.12707, "x":1.91504, "y":1.56823, "heading":-2.20965, "vx":-1.03587, "vy":-0.69965, "omega":-0.21297, "ax":5.52772, "ay":3.32061, "alpha":0.00189, "fx":[94.02774,94.01838,94.02221,94.03157], "fy":[56.47802,56.49357,56.48715,56.47159]}, - {"t":1.16593, "x":1.87896, "y":1.54354, "heading":-2.21792, "vx":-0.82104, "vy":-0.5706, "omega":-0.21289, "ax":3.68794, "ay":-4.07774, "alpha":0.19661, "fx":[63.56392,63.14491,61.88694,62.3274], "fy":[-68.75719,-68.7661,-69.97251,-69.94872]}, - {"t":1.21224, "x":1.84489, "y":1.51275, "heading":-2.22778, "vx":-0.65027, "vy":-0.75942, "omega":-0.20379, "ax":0.28252, "ay":-0.23777, "alpha":1.04598, "fx":[8.60888,4.3309,0.99349,5.28925], "fy":[-3.54645,-0.22937,-4.55501,-7.84695]}, - {"t":1.25854, "x":1.81509, "y":1.47733, "heading":-2.23722, "vx":-0.63718, "vy":-0.77043, "omega":-0.15535, "ax":0.00534, "ay":-0.00441, "alpha":0.89993, "fx":[3.37102,-0.30131,-3.18965,0.48294], "fy":[0.31702,3.20539,-0.46725,-3.35528]}, - {"t":1.30485, "x":1.78559, "y":1.44165, "heading":-2.24441, "vx":-0.63694, "vy":-0.77064, "omega":-0.11368, "ax":0.0001, "ay":-0.00008, "alpha":0.7677, "fx":[2.80237,-0.31268,-2.79898,0.31607], "fy":[0.31297,2.79928,-0.31578,-2.80208]}, - {"t":1.35115, "x":1.75609, "y":1.40596, "heading":-2.24968, "vx":-0.63693, "vy":-0.77064, "omega":-0.07813, "ax":0.0, "ay":0.0, "alpha":0.65313, "fx":[2.38414,-0.25488,-2.38407,0.25494], "fy":[0.25489,2.38408,-0.25494,-2.38413]}, - {"t":1.39746, "x":1.7266, "y":1.37028, "heading":-2.2533, "vx":-0.63693, "vy":-0.77064, "omega":-0.04789, "ax":0.0, "ay":0.0, "alpha":0.55362, "fx":[2.02164,-0.20876,-2.02164,0.20876], "fy":[0.20876,2.02164,-0.20876,-2.02164]}, - {"t":1.44377, "x":1.6971, "y":1.33459, "heading":-2.25551, "vx":-0.63693, "vy":-0.77064, "omega":-0.02225, "ax":0.0, "ay":0.0, "alpha":0.46689, "fx":[1.70529,-0.17227,-1.70529,0.17227], "fy":[0.17227,1.70529,-0.17227,-1.70529]}, - {"t":1.49007, "x":1.66761, "y":1.29891, "heading":-2.25654, "vx":-0.63693, "vy":-0.77064, "omega":-0.00063, "ax":0.0, "ay":0.0, "alpha":0.39093, "fx":[1.42802,-0.14278,-1.42802,0.14278], "fy":[0.14278,1.42802,-0.14278,-1.42802]}, - {"t":1.53638, "x":1.63812, "y":1.26322, "heading":-2.25657, "vx":-0.63693, "vy":-0.77064, "omega":0.01747, "ax":0.0, "ay":0.0, "alpha":0.32401, "fx":[1.18357,-0.1183,-1.18357,0.1183], "fy":[0.1183,1.18357,-0.1183,-1.18357]}, - {"t":1.58268, "x":1.60862, "y":1.22754, "heading":-2.25576, "vx":-0.63693, "vy":-0.77064, "omega":0.03247, "ax":0.0, "ay":0.0, "alpha":0.26458, "fx":[0.9664,-0.09738,-0.9664,0.09738], "fy":[0.09738,0.9664,-0.09738,-0.9664]}, - {"t":1.62899, "x":1.57913, "y":1.19185, "heading":-2.25426, "vx":-0.63693, "vy":-0.77064, "omega":0.04473, "ax":0.0, "ay":0.0, "alpha":0.21127, "fx":[0.77156,-0.07892,-0.77156,0.07892], "fy":[0.07892,0.77156,-0.07892,-0.77156]}, - {"t":1.6753, "x":1.54964, "y":1.15617, "heading":-2.25219, "vx":-0.63693, "vy":-0.77064, "omega":0.05451, "ax":0.0, "ay":0.0, "alpha":0.16285, "fx":[0.5946,-0.06207,-0.5946,0.06207], "fy":[0.06207,0.5946,-0.06207,-0.5946]}, - {"t":1.7216, "x":1.52014, "y":1.12048, "heading":-2.24966, "vx":-0.63693, "vy":-0.77064, "omega":0.06205, "ax":0.0, "ay":0.0, "alpha":0.1182, "fx":[0.43144,-0.04614,-0.43144,0.04614], "fy":[0.04614,0.43144,-0.04614,-0.43144]}, - {"t":1.76791, "x":1.49065, "y":1.08479, "heading":-2.24679, "vx":-0.63693, "vy":-0.77064, "omega":0.06752, "ax":0.0, "ay":0.0, "alpha":0.07628, "fx":[0.27834,-0.03057,-0.27834,0.03057], "fy":[0.03057,0.27834,-0.03057,-0.27834]}, - {"t":1.81421, "x":1.46115, "y":1.04911, "heading":-2.24366, "vx":-0.63693, "vy":-0.77064, "omega":0.07105, "ax":0.0, "ay":0.0, "alpha":0.03612, "fx":[0.13177,-0.01489,-0.13177,0.01489], "fy":[0.01489,0.13177,-0.01489,-0.13177]}, - {"t":1.86052, "x":1.43166, "y":1.01342, "heading":-2.24037, "vx":-0.63693, "vy":-0.77064, "omega":0.07273, "ax":0.0, "ay":0.0, "alpha":-0.00319, "fx":[-0.01164,0.00135,0.01164,-0.00135], "fy":[-0.00135,-0.01164,0.00135,0.01164]}, - {"t":1.90683, "x":1.40217, "y":0.97774, "heading":-2.23701, "vx":-0.63693, "vy":-0.77064, "omega":0.07258, "ax":0.0, "ay":0.0, "alpha":-0.04258, "fx":[-0.15521,0.01859,0.15521,-0.01859], "fy":[-0.01859,-0.15521,0.01859,0.15521]}, - {"t":1.95313, "x":1.37267, "y":0.94205, "heading":-2.23365, "vx":-0.63693, "vy":-0.77064, "omega":0.07061, "ax":0.0, "ay":0.0, "alpha":-0.08296, "fx":[-0.30226,0.03723,0.30226,-0.03723], "fy":[-0.03723,-0.30226,0.03723,0.30226]}, - {"t":1.99944, "x":1.34318, "y":0.90637, "heading":-2.23038, "vx":-0.63693, "vy":-0.77064, "omega":0.06677, "ax":0.0, "ay":0.0, "alpha":-0.12526, "fx":[-0.45618,0.0577,0.45618,-0.0577], "fy":[-0.0577,-0.45618,0.0577,0.45618]}, - {"t":2.04574, "x":1.31369, "y":0.87068, "heading":-2.22728, "vx":-0.63693, "vy":-0.77064, "omega":0.06097, "ax":0.0, "ay":0.0, "alpha":-0.17045, "fx":[-0.62054,0.08044,0.62054,-0.08044], "fy":[-0.08044,-0.62054,0.08044,0.62054]}, - {"t":2.09205, "x":1.28419, "y":0.835, "heading":-2.22446, "vx":-0.63693, "vy":-0.77064, "omega":0.05307, "ax":0.0, "ay":0.0, "alpha":-0.21959, "fx":[-0.79914,0.10589,0.79914,-0.10589], "fy":[-0.10589,-0.79914,0.10589,0.79914]}, - {"t":2.13836, "x":1.2547, "y":0.79931, "heading":-2.222, "vx":-0.63693, "vy":-0.77064, "omega":0.04291, "ax":0.0, "ay":0.0, "alpha":-0.27381, "fx":[-0.99614,0.13448,0.99614,-0.13448], "fy":[-0.13448,-0.99614,0.13448,0.99614]}, - {"t":2.18466, "x":1.2252, "y":0.76363, "heading":-2.22002, "vx":-0.63693, "vy":-0.77064, "omega":0.03023, "ax":0.00001, "ay":0.00001, "alpha":-0.33436, "fx":[-1.21598,0.16675,1.21622,-0.16652], "fy":[-0.1665,-1.21596,0.16678,1.21624]}, - {"t":2.23097, "x":1.19571, "y":0.72794, "heading":-2.21862, "vx":-0.63693, "vy":-0.77064, "omega":0.01474, "ax":1.43266, "ay":1.73341, "alpha":-0.31559, "fx":[23.21043,24.6721,25.52018,24.07378], "fy":[29.46899,28.34161,29.50621,30.62223]}, - {"t":2.27728, "x":1.16775, "y":0.69412, "heading":-2.21793, "vx":-0.57059, "vy":-0.69037, "omega":0.00013, "ax":4.10277, "ay":4.96403, "alpha":-0.00138, "fx":[69.78159,69.79263,69.79218,69.78114], "fy":[84.44109,84.43196,84.43239,84.44151]}, - {"t":2.32358, "x":1.14573, "y":0.66747, "heading":-2.21793, "vx":-0.38061, "vy":-0.46051, "omega":0.00007, "ax":4.10871, "ay":4.97122, "alpha":-0.0008, "fx":[69.88486,69.89127,69.89099,69.88459], "fy":[84.56152,84.55623,84.55647,84.56176]}, - {"t":2.36989, "x":1.13251, "y":0.65147, "heading":-2.21793, "vx":-0.19035, "vy":-0.23031, "omega":0.00003, "ax":4.11069, "ay":4.97362, "alpha":-0.00061, "fx":[69.91934,69.9242,69.92399,69.91913], "fy":[84.60173,84.59772,84.59789,84.60191]}, - {"t":2.41619, "x":1.1281, "y":0.64614, "heading":-2.21792, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.85121, "ay":4.2545, "alpha":0.01131, "fx":[82.54785,82.47214,82.48767,82.56344], "fy":[72.33362,72.4199,72.40205,72.31566]}, - {"t":2.46, "x":1.13276, "y":0.65022, "heading":-2.21792, "vx":0.21249, "vy":0.18635, "omega":0.0005, "ax":4.8507, "ay":4.25405, "alpha":0.0116, "fx":[82.53983,82.46217,82.47809,82.55581], "fy":[72.32503,72.41353,72.39521,72.3066]}, - {"t":2.5038, "x":1.14672, "y":0.66247, "heading":-2.2179, "vx":0.42496, "vy":0.37269, "omega":0.001, "ax":4.85005, "ay":4.25348, "alpha":0.01196, "fx":[82.52981,82.44971,82.46612,82.54628], "fy":[72.3143,72.40557,72.38666,72.29528]}, - {"t":2.5476, "x":1.16998, "y":0.68287, "heading":-2.21786, "vx":0.6374, "vy":0.559, "omega":0.00153, "ax":4.84922, "ay":4.25275, "alpha":0.01243, "fx":[82.51694,82.4337,82.45074,82.53404], "fy":[72.30051,72.39534,72.37568,72.28072]}, - {"t":2.5914, "x":1.20255, "y":0.71144, "heading":-2.21779, "vx":0.84981, "vy":0.74528, "omega":0.00207, "ax":4.84811, "ay":4.25178, "alpha":0.01306, "fx":[82.49978,82.41237,82.43025,82.51773], "fy":[72.28214,72.38172,72.36104,72.26133]}, - {"t":2.6352, "x":1.24443, "y":0.74816, "heading":-2.2177, "vx":1.06216, "vy":0.93151, "omega":0.00264, "ax":4.84657, "ay":4.25042, "alpha":0.01394, "fx":[82.4758,82.38255,82.40159,82.49492], "fy":[72.25645,72.36266,72.34057,72.23421]}, - {"t":2.679, "x":1.2956, "y":0.79304, "heading":-2.21759, "vx":1.27445, "vy":1.11769, "omega":0.00325, "ax":4.84425, "ay":4.24839, "alpha":0.01525, "fx":[82.43988,82.33789,82.35866,82.46076], "fy":[72.21799,72.33414,72.30992,72.19359]}, - {"t":2.72281, "x":1.35607, "y":0.84607, "heading":-2.21744, "vx":1.48664, "vy":1.30378, "omega":0.00392, "ax":4.8404, "ay":4.24501, "alpha":0.01744, "fx":[82.38021,82.26367,82.28731,82.40398], "fy":[72.15407,72.28673,72.25897,72.12606]}, - {"t":2.76661, "x":1.42583, "y":0.90725, "heading":-2.21727, "vx":1.69866, "vy":1.48972, "omega":0.00469, "ax":4.83274, "ay":4.23829, "alpha":0.02179, "fx":[82.26155,82.11607,82.14531,82.291], "fy":[72.02697,72.19244,72.15757,71.99172]}, - {"t":2.81041, "x":1.50487, "y":0.97657, "heading":-2.21707, "vx":1.91034, "vy":1.67536, "omega":0.00564, "ax":4.8101, "ay":4.21844, "alpha":0.03473, "fx":[81.91121,81.68033,81.72542,81.95683], "fy":[71.65185,71.9139,71.85763,71.59463]}, - {"t":2.85421, "x":1.59317, "y":1.054, "heading":-2.21682, "vx":2.12103, "vy":1.86014, "omega":0.00716, "ax":3.05791, "ay":2.68178, "alpha":1.19578, "fx":[55.8047,49.82347,48.03484,54.39352], "fy":[44.65064,50.32144,46.7923,40.70087]}, - {"t":2.89801, "x":1.689, "y":1.13805, "heading":-2.21651, "vx":2.25497, "vy":1.9776, "omega":0.05954, "ax":0.00024, "ay":0.00021, "alpha":1.99877, "fx":[7.27022,-1.0175,-7.26201,1.0258], "fy":[1.02523,7.26967,-1.01808,-7.26256]}, - {"t":2.94182, "x":1.78778, "y":1.22467, "heading":-2.2139, "vx":2.25498, "vy":1.97761, "omega":0.14709, "ax":0.0, "ay":0.0, "alpha":1.43258, "fx":[5.20591,-0.74583,-5.20591,0.74583], "fy":[0.74582,5.20591,-0.74583,-5.20592]}, - {"t":2.98562, "x":1.88655, "y":1.3113, "heading":-2.20745, "vx":2.25498, "vy":1.97761, "omega":0.20984, "ax":0.0, "ay":0.0, "alpha":1.00521, "fx":[3.64944,-0.54686,-3.64944,0.54685], "fy":[0.54686,3.64944,-0.54686,-3.64944]}, - {"t":3.02942, "x":1.98532, "y":1.39792, "heading":-2.19826, "vx":2.25498, "vy":1.97761, "omega":0.25387, "ax":0.0, "ay":0.0, "alpha":0.67709, "fx":[2.4547,-0.39093,-2.45471,0.39093], "fy":[0.39093,2.45471,-0.39093,-2.4547]}, - {"t":3.07322, "x":2.08409, "y":1.48454, "heading":-2.18714, "vx":2.25498, "vy":1.97761, "omega":0.28353, "ax":0.0, "ay":0.0, "alpha":0.41666, "fx":[1.50776,-0.25735,-1.50777,0.25734], "fy":[0.25735,1.50777,-0.25734,-1.50777]}, - {"t":3.11702, "x":2.18287, "y":1.57117, "heading":-2.17472, "vx":2.25498, "vy":1.97761, "omega":0.30178, "ax":0.0, "ay":0.0, "alpha":0.19822, "fx":[0.71572,-0.13133,-0.71573,0.13133], "fy":[0.13133,0.71572,-0.13133,-0.71572]}, - {"t":3.16082, "x":2.28164, "y":1.65779, "heading":-2.16151, "vx":2.25498, "vy":1.97761, "omega":0.31046, "ax":0.0, "ay":0.0, "alpha":-0.00013, "fx":[-0.00046,0.00009,0.00046,-0.00009], "fy":[-0.00009,-0.00046,0.00009,0.00046]}, - {"t":3.20463, "x":2.38041, "y":1.74441, "heading":-2.14791, "vx":2.25498, "vy":1.97761, "omega":0.31045, "ax":0.0, "ay":0.0, "alpha":-0.19844, "fx":[-0.71274,0.15064,0.71274,-0.15064], "fy":[-0.15064,-0.71274,0.15064,0.71274]}, - {"t":3.24843, "x":2.47918, "y":1.83104, "heading":-2.13431, "vx":2.25498, "vy":1.97761, "omega":0.30176, "ax":0.0, "ay":0.0, "alpha":-0.41679, "fx":[-1.49255,0.33672,1.49256,-0.33672], "fy":[-0.33672,-1.49256,0.33672,1.49255]}, - {"t":3.29223, "x":2.57796, "y":1.91766, "heading":-2.12109, "vx":2.25498, "vy":1.97761, "omega":0.28351, "ax":0.0, "ay":0.0, "alpha":-0.67712, "fx":[-2.41735,0.57904,2.41736,-0.57903], "fy":[-0.57904,-2.41736,0.57903,2.41735]}, - {"t":3.33603, "x":2.67673, "y":2.00428, "heading":-2.10867, "vx":2.25498, "vy":1.97761, "omega":0.25385, "ax":0.0, "ay":0.0, "alpha":-1.00516, "fx":[-3.57752,0.90406,3.57752,-0.90405], "fy":[-0.90405,-3.57752,0.90405,3.57752]}, - {"t":3.37983, "x":2.7755, "y":2.09091, "heading":-2.09755, "vx":2.25498, "vy":1.97761, "omega":0.20982, "ax":0.0, "ay":0.0, "alpha":-1.43251, "fx":[-5.08392,1.34503,5.08391,-1.34504], "fy":[-1.34503,-5.08391,1.34504,5.08392]}, - {"t":3.42364, "x":2.87427, "y":2.17753, "heading":-2.08836, "vx":2.25498, "vy":1.97761, "omega":0.14707, "ax":-0.00024, "ay":-0.00021, "alpha":-1.99878, "fx":[-7.08015,1.93767,7.07192,-1.946], "fy":[-1.94539,-7.07958,1.93828,7.07249]}, - {"t":3.46744, "x":2.97305, "y":2.26415, "heading":-2.08192, "vx":2.25497, "vy":1.9776, "omega":0.05952, "ax":-3.05791, "ay":-2.68178, "alpha":-1.19536, "fx":[-55.47543,-49.31048,-48.39096,-54.8796], "fy":[-45.29012,-50.43614,-46.11938,-40.61968]}, - {"t":3.51124, "x":3.06888, "y":2.3482, "heading":-2.07931, "vx":2.12103, "vy":1.86014, "omega":0.00716, "ax":-4.8101, "ay":-4.21844, "alpha":-0.03473, "fx":[-81.89141,-81.66882,-81.74533,-81.96824], "fy":[-71.67472,-71.92653,-71.83473,-71.58201]}, - {"t":3.55504, "x":3.15718, "y":2.42563, "heading":-2.079, "vx":1.91034, "vy":1.67536, "omega":0.00564, "ax":-4.83274, "ay":-4.23829, "alpha":-0.0218, "fx":[-82.24896,-82.10887,-82.15794,-82.29816], "fy":[-72.04142,-72.2005,-72.14312,-71.98367]}, - {"t":3.59884, "x":3.23622, "y":2.49495, "heading":-2.07875, "vx":1.69866, "vy":1.48972, "omega":0.00469, "ax":-4.8404, "ay":-4.24501, "alpha":-0.01744, "fx":[-82.37008,-82.2579,-82.29746,-82.40972], "fy":[-72.16567,-72.29322,-72.24736,-72.11958]}, - {"t":3.64265, "x":3.30598, "y":2.55613, "heading":-2.07855, "vx":1.48664, "vy":1.30378, "omega":0.00392, "ax":-4.84425, "ay":-4.24839, "alpha":-0.01525, "fx":[-82.43099,-82.33284,-82.36758,-82.46579], "fy":[-72.22817,-72.33984,-72.29974,-72.18789]}, - {"t":3.68645, "x":3.36645, "y":2.60916, "heading":-2.07838, "vx":1.27445, "vy":1.11769, "omega":0.00325, "ax":-4.84657, "ay":-4.25042, "alpha":-0.01394, "fx":[-82.46765,-82.37793,-82.40976,-82.49953], "fy":[-72.26577,-72.36789,-72.33125,-72.22898]}, - {"t":3.73025, "x":3.41762, "y":2.65404, "heading":-2.07823, "vx":1.06216, "vy":0.93151, "omega":0.00264, "ax":-4.84811, "ay":-4.25178, "alpha":-0.01306, "fx":[-82.49213,-82.40804,-82.43792,-82.52205], "fy":[-72.29089,-72.38663,-72.35229,-72.25642]}, - {"t":3.77405, "x":3.4595, "y":2.69077, "heading":-2.07812, "vx":0.84981, "vy":0.74528, "omega":0.00207, "ax":-4.84922, "ay":-4.25275, "alpha":-0.01243, "fx":[-82.50963,-82.42957,-82.45805,-82.53816], "fy":[-72.30886,-72.40003,-72.36733,-72.27604]}, - {"t":3.81785, "x":3.49207, "y":2.71933, "heading":-2.07803, "vx":0.6374, "vy":0.559, "omega":0.00153, "ax":-4.85005, "ay":-4.25348, "alpha":-0.01196, "fx":[-82.52278,-82.44573,-82.47317,-82.55025], "fy":[-72.32234,-72.41008,-72.37862,-72.29076]}, - {"t":3.86165, "x":3.51533, "y":2.73974, "heading":-2.07796, "vx":0.42496, "vy":0.37269, "omega":0.001, "ax":-4.8507, "ay":-4.25405, "alpha":-0.0116, "fx":[-82.53301,-82.45831,-82.48492,-82.55966], "fy":[-72.33283,-72.41791,-72.38741,-72.30222]}, - {"t":3.90546, "x":3.52929, "y":2.75198, "heading":-2.07792, "vx":0.21249, "vy":0.18635, "omega":0.0005, "ax":-4.85121, "ay":-4.2545, "alpha":-0.01131, "fx":[-82.54119,-82.46837,-82.49434,-82.56719], "fy":[-72.34123,-72.42417,-72.39444,-72.31139]}, - {"t":3.94926, "x":3.53395, "y":2.75606, "heading":-2.07789, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/D_CENTER_PATH.traj b/src/main/deploy/choreo/D_CENTER_PATH.traj deleted file mode 100644 index d555bce8..00000000 --- a/src/main/deploy/choreo/D_CENTER_PATH.traj +++ /dev/null @@ -1,55 +0,0 @@ -{ - "name":"D_CENTER_PATH", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":7.1445207595825195, "y":4.035357475280762, "heading":0.0, "intervals":18, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":5.994441509246826, "y":4.235998630523682, "heading":0.0, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":3.0}}, "enabled":true}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"7.1445207595825195 m", "val":7.1445207595825195}, "y":{"exp":"4.035357475280762 m", "val":4.035357475280762}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":18, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"5.994441509246826 m", "val":5.994441509246826}, "y":{"exp":"4.235998630523682 m", "val":4.235998630523682}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"3 m / s", "val":3.0}}}, "enabled":true}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,0.85103], - "samples":[ - {"t":0.0, "x":7.14452, "y":4.03536, "heading":0.0, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.35693, "ay":1.10902, "alpha":0.0, "fx":[-108.12962,-108.12962,-108.12962,-108.12962], "fy":[18.86414,18.86414,18.86414,18.86414]}, - {"t":0.04728, "x":7.13742, "y":4.0366, "heading":0.0, "vx":-0.30055, "vy":0.05243, "omega":0.0, "ax":-6.35617, "ay":1.10889, "alpha":0.0, "fx":[-108.11671,-108.11671,-108.11671,-108.11671], "fy":[18.86188,18.86188,18.86188,18.86188]}, - {"t":0.09456, "x":7.1161, "y":4.04032, "heading":0.0, "vx":-0.60107, "vy":0.10486, "omega":0.0, "ax":-6.35518, "ay":1.10872, "alpha":0.0, "fx":[-108.09983,-108.09983,-108.09983,-108.09983], "fy":[18.85894,18.85894,18.85894,18.85894]}, - {"t":0.14184, "x":7.08058, "y":4.04651, "heading":0.0, "vx":-0.90153, "vy":0.15728, "omega":0.0, "ax":-6.35383, "ay":1.10848, "alpha":0.0, "fx":[-108.07681,-108.07681,-108.07681,-108.07681], "fy":[18.85492,18.85492,18.85492,18.85492]}, - {"t":0.18912, "x":7.03086, "y":4.05519, "heading":0.0, "vx":-1.20194, "vy":0.20969, "omega":0.0, "ax":-6.35187, "ay":1.10814, "alpha":0.0, "fx":[-108.04356,-108.04356,-108.04356,-108.04356], "fy":[18.84912,18.84912,18.84912,18.84912]}, - {"t":0.2364, "x":6.96693, "y":4.06634, "heading":0.0, "vx":-1.50225, "vy":0.26208, "omega":0.0, "ax":-6.3488, "ay":1.1076, "alpha":0.0, "fx":[-107.99133,-107.99133,-107.99133,-107.99133], "fy":[18.84001,18.84001,18.84001,18.84001]}, - {"t":0.28368, "x":6.88881, "y":4.07997, "heading":0.0, "vx":-1.80242, "vy":0.31445, "omega":0.0, "ax":-6.34328, "ay":1.10664, "alpha":0.0, "fx":[-107.89735,-107.89735,-107.89735,-107.89735], "fy":[18.82361,18.82361,18.82361,18.82361]}, - {"t":0.33095, "x":6.7965, "y":4.09607, "heading":0.0, "vx":-2.10232, "vy":0.36677, "omega":0.0, "ax":-6.3304, "ay":1.10439, "alpha":0.0, "fx":[-107.67829,-107.67829,-107.67829,-107.67829], "fy":[18.7854,18.7854,18.7854,18.7854]}, - {"t":0.37823, "x":6.69003, "y":4.11465, "heading":0.0, "vx":-2.40162, "vy":0.41898, "omega":0.0, "ax":-6.26635, "ay":1.09322, "alpha":0.0, "fx":[-106.58874,-106.58874,-106.58874,-106.58874], "fy":[18.59532,18.59532,18.59532,18.59532]}, - {"t":0.42551, "x":6.56948, "y":4.13568, "heading":0.0, "vx":-2.69788, "vy":0.47067, "omega":0.0, "ax":6.26635, "ay":-1.09322, "alpha":0.0, "fx":[106.58874,106.58874,106.58874,106.58874], "fy":[-18.59532,-18.59532,-18.59532,-18.59532]}, - {"t":0.47279, "x":6.44893, "y":4.15671, "heading":0.0, "vx":-2.40162, "vy":0.41898, "omega":0.0, "ax":6.3304, "ay":-1.10439, "alpha":0.0, "fx":[107.67829,107.67829,107.67829,107.67829], "fy":[-18.7854,-18.7854,-18.7854,-18.7854]}, - {"t":0.52007, "x":6.34246, "y":4.17528, "heading":0.0, "vx":-2.10232, "vy":0.36677, "omega":0.0, "ax":6.34328, "ay":-1.10664, "alpha":0.0, "fx":[107.89735,107.89735,107.89735,107.89735], "fy":[-18.82361,-18.82361,-18.82361,-18.82361]}, - {"t":0.56735, "x":6.25015, "y":4.19139, "heading":0.0, "vx":-1.80242, "vy":0.31445, "omega":0.0, "ax":6.3488, "ay":-1.1076, "alpha":0.0, "fx":[107.99133,107.99133,107.99133,107.99133], "fy":[-18.84001,-18.84001,-18.84001,-18.84001]}, - {"t":0.61463, "x":6.17203, "y":4.20502, "heading":0.0, "vx":-1.50225, "vy":0.26208, "omega":0.0, "ax":6.35187, "ay":-1.10814, "alpha":0.0, "fx":[108.04356,108.04356,108.04356,108.04356], "fy":[-18.84912,-18.84912,-18.84912,-18.84912]}, - {"t":0.66191, "x":6.10811, "y":4.21617, "heading":0.0, "vx":-1.20194, "vy":0.20969, "omega":0.0, "ax":6.35383, "ay":-1.10848, "alpha":0.0, "fx":[108.07681,108.07681,108.07681,108.07681], "fy":[-18.85492,-18.85492,-18.85492,-18.85492]}, - {"t":0.70919, "x":6.05838, "y":4.22484, "heading":0.0, "vx":-0.90153, "vy":0.15728, "omega":0.0, "ax":6.35518, "ay":-1.10872, "alpha":0.0, "fx":[108.09983,108.09983,108.09983,108.09983], "fy":[-18.85894,-18.85894,-18.85894,-18.85894]}, - {"t":0.75647, "x":6.02286, "y":4.23104, "heading":0.0, "vx":-0.60107, "vy":0.10486, "omega":0.0, "ax":6.35617, "ay":-1.10889, "alpha":0.0, "fx":[108.11671,108.11671,108.11671,108.11671], "fy":[-18.86188,-18.86188,-18.86188,-18.86188]}, - {"t":0.80375, "x":6.00155, "y":4.23476, "heading":0.0, "vx":-0.30055, "vy":0.05243, "omega":0.0, "ax":6.35693, "ay":-1.10902, "alpha":0.0, "fx":[108.12962,108.12962,108.12962,108.12962], "fy":[-18.86414,-18.86414,-18.86414,-18.86414]}, - {"t":0.85103, "x":5.99444, "y":4.236, "heading":0.0, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_1.traj b/src/main/deploy/choreo/E_RIGHT_PATH_1.traj index 4b5086f5..edc3f462 100644 --- a/src/main/deploy/choreo/E_RIGHT_PATH_1.traj +++ b/src/main/deploy/choreo/E_RIGHT_PATH_1.traj @@ -3,26 +3,24 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":7.152472496032715, "y":0.4605357348918915, "heading":3.141592653589793, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":3.778014659881592, "y":2.6174252033233643, "heading":2.5967288478948136, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":7.152472496032715, "y":0.4605357348918915, "heading":3.141592653589793, "intervals":50, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":3.458690404891968, "y":1.516339898109436, "heading":0.0, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":3.624938726425171, "y":2.281198024749756, "heading":2.5967288478948136, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":1, "to":1, "data":{"type":"MaxVelocity", "props":{"max":3.0}}, "enabled":true}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + {"from":1, "to":2, "data":{"type":"MaxVelocity", "props":{"max":2.0}}, "enabled":true}], "targetDt":0.05 }, "params":{ "waypoints":[ - {"x":{"exp":"7.152472496032715 m", "val":7.152472496032715}, "y":{"exp":"0.4605357348918915 m", "val":0.4605357348918915}, "heading":{"exp":"pi rad", "val":3.141592653589793}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"3.778014659881592 m", "val":3.778014659881592}, "y":{"exp":"2.6174252033233643 m", "val":2.6174252033233643}, "heading":{"exp":"2.5967288478948136 rad", "val":2.5967288478948136}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"7.152472496032715 m", "val":7.152472496032715}, "y":{"exp":"0.4605357348918915 m", "val":0.4605357348918915}, "heading":{"exp":"pi rad", "val":3.141592653589793}, "intervals":50, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"3.4586904048919678 m", "val":3.458690404891968}, "y":{"exp":"1.516339898109436 m", "val":1.516339898109436}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"3.624938726425171 m", "val":3.624938726425171}, "y":{"exp":"2.281198024749756 m", "val":2.281198024749756}, "heading":{"exp":"2.5967288478948136 rad", "val":2.5967288478948136}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":1, "to":1, "data":{"type":"MaxVelocity", "props":{"max":{"exp":"3 m / s", "val":3.0}}}, "enabled":true}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + {"from":1, "to":2, "data":{"type":"MaxVelocity", "props":{"max":{"exp":"2 m / s", "val":2.0}}}, "enabled":true}], "targetDt":{ "exp":"0.05 s", "val":0.05 @@ -30,49 +28,66 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,1.62748], + "waypoints":[0.0,1.43204,1.85318], "samples":[ - {"t":0.0, "x":7.15247, "y":0.46054, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.41378, "ay":3.46163, "alpha":-1.90657, "fx":[-90.99812,-98.92725,-94.25689,-84.16514], "fy":[61.37561,47.53023,56.18754,70.43177]}, - {"t":0.04069, "x":7.14799, "y":0.4634, "heading":3.14159, "vx":-0.22027, "vy":0.14084, "omega":-0.07757, "ax":-5.41425, "ay":3.46191, "alpha":-1.86883, "fx":[-91.01891,-98.80925,-94.20948,-84.34176], "fy":[61.3313,47.75661,56.24948,70.20712]}, - {"t":0.08137, "x":7.13455, "y":0.472, "heading":3.13844, "vx":-0.44056, "vy":0.2817, "omega":-0.15361, "ax":-5.41477, "ay":3.46222, "alpha":-1.8253, "fx":[-91.02228,-98.66598,-94.17886,-84.54786], "fy":[61.31059,48.03075,56.2806,69.94356]}, - {"t":0.12206, "x":7.11214, "y":0.48632, "heading":3.13219, "vx":-0.66087, "vy":0.42257, "omega":-0.22788, "ax":-5.41536, "ay":3.46256, "alpha":-1.77441, "fx":[-91.01117,-98.49267,-94.16051,-84.79037], "fy":[61.30857,48.36058,56.28791,69.6314]}, - {"t":0.16275, "x":7.08077, "y":0.50638, "heading":3.12291, "vx":-0.88121, "vy":0.56345, "omega":-0.30007, "ax":-5.41601, "ay":3.46293, "alpha":-1.71397, "fx":[-90.9895,-98.28255,-94.14838,-85.07876], "fy":[61.31858,48.75726,56.28066,69.25721]}, - {"t":0.20344, "x":7.04043, "y":0.53217, "heading":3.11071, "vx":-1.10157, "vy":0.70434, "omega":-0.36981, "ax":-5.41674, "ay":3.46334, "alpha":-1.64092, "fx":[-90.96271,-98.02586,-94.13432,-85.42612], "fy":[61.33135,49.2367,56.2713,68.80209]}, - {"t":0.24412, "x":6.99113, "y":0.5637, "heading":3.09566, "vx":-1.32196, "vy":0.84526, "omega":-0.43657, "ax":-5.41756, "ay":3.46378, "alpha":-1.55079, "fx":[-90.93858,-97.70812,-94.10696,-85.85087], "fy":[61.33359,49.8221,56.27706,68.23884]}, - {"t":0.28481, "x":6.93286, "y":0.60096, "heading":3.0779, "vx":-1.54238, "vy":0.98619, "omega":-0.49967, "ax":-5.41845, "ay":3.46425, "alpha":-1.43677, "fx":[-90.92878,-97.30686,-94.04998,-86.37978], "fy":[61.30526,50.54867,56.32261,67.52673]}, - {"t":0.3255, "x":6.86562, "y":0.64395, "heading":3.05757, "vx":-1.76284, "vy":1.12714, "omega":-0.55813, "ax":-5.41939, "ay":3.46469, "alpha":-1.28802, "fx":[-90.95179,-96.78532,-93.93868,-87.05336], "fy":[61.21442,51.47259,56.44483,66.60186]}, - {"t":0.36618, "x":6.78941, "y":0.69268, "heading":3.03486, "vx":-1.98334, "vy":1.26811, "omega":-0.61053, "ax":-5.42024, "ay":3.46501, "alpha":-1.08613, "fx":[-91.03889,-96.07859,-93.73331,-87.93643], "fy":[61.0062,52.68973,56.70202,65.35727]}, - {"t":0.40687, "x":6.70423, "y":0.74714, "heading":3.01002, "vx":-2.20388, "vy":1.40909, "omega":-0.65472, "ax":-5.42062, "ay":3.46488, "alpha":-0.7971, "fx":[-91.2482,-95.06016,-93.36444,-89.14013], "fy":[60.57629,54.37891,57.19317,63.59828]}, - {"t":0.44756, "x":6.61007, "y":0.80734, "heading":2.98338, "vx":-2.42443, "vy":1.55006, "omega":-0.68716, "ax":-5.41923, "ay":3.46337, "alpha":-0.35028, "fx":[-91.70263,-93.44621,-92.69649,-90.8726], "fy":[59.69568,56.91673,58.10359,60.92778]}, - {"t":0.48824, "x":6.50694, "y":0.87327, "heading":2.95542, "vx":-2.64492, "vy":1.69098, "omega":-0.70141, "ax":-5.41096, "ay":3.45697, "alpha":0.42998, "fx":[-92.71832,-90.44776,-91.41999,-93.56919], "fy":[57.73597,61.24946,59.83017,56.3927]}, - {"t":0.52893, "x":6.39485, "y":0.94494, "heading":2.92688, "vx":-2.86508, "vy":1.83163, "omega":-0.68391, "ax":-5.36728, "ay":3.42571, "alpha":2.143, "fx":[-95.42833,-82.8717,-88.63603,-98.24726], "fy":[52.10081,70.52095,63.41159,47.04811]}, - {"t":0.56962, "x":6.27383, "y":1.0223, "heading":2.89906, "vx":-3.08345, "vy":1.97101, "omega":-0.59672, "ax":-4.90263, "ay":2.92977, "alpha":9.39606, "fx":[-105.06196,-41.79507,-80.38887,-106.32374], "fy":[8.94067,98.66804,72.50689,19.22275]}, - {"t":0.61031, "x":6.14432, "y":1.10492, "heading":2.87478, "vx":-3.28293, "vy":2.09022, "omega":-0.21442, "ax":-1.51387, "ay":1.13808, "alpha":5.22755, "fx":[-17.89503,-8.72446,-33.70878,-42.6734], "fy":[2.04929,31.37038,34.80901,9.20467]}, - {"t":0.65099, "x":6.00949, "y":1.1909, "heading":2.86605, "vx":-3.34452, "vy":2.13652, "omega":-0.00173, "ax":0.022, "ay":0.03655, "alpha":0.00251, "fx":[0.37871,0.38225,0.36972,0.36618], "fy":[0.61372,0.62624,0.62979,0.61726]}, - {"t":0.69168, "x":5.87343, "y":1.27786, "heading":2.86598, "vx":-3.34363, "vy":2.13801, "omega":-0.00163, "ax":0.00578, "ay":0.00904, "alpha":0.0, "fx":[0.09829,0.09829,0.09828,0.09828], "fy":[0.1537,0.15371,0.15371,0.1537]}, - {"t":0.73237, "x":5.7374, "y":1.36486, "heading":2.86592, "vx":-3.34339, "vy":2.13838, "omega":-0.00163, "ax":0.00144, "ay":0.00225, "alpha":0.0, "fx":[0.02443,0.02443,0.02443,0.02443], "fy":[0.03819,0.03819,0.03819,0.03819]}, - {"t":0.77305, "x":5.60136, "y":1.45186, "heading":2.86585, "vx":-3.34333, "vy":2.13847, "omega":-0.00163, "ax":0.00029, "ay":0.00045, "alpha":0.0, "fx":[0.00489,0.00489,0.00489,0.00489], "fy":[0.00764,0.00764,0.00764,0.00764]}, - {"t":0.81374, "x":5.46533, "y":1.53887, "heading":2.86578, "vx":-3.34332, "vy":2.13849, "omega":-0.00163, "ax":-0.00022, "ay":-0.00035, "alpha":0.0, "fx":[-0.00378,-0.00378,-0.00378,-0.00378], "fy":[-0.0059,-0.0059,-0.00591,-0.0059]}, - {"t":0.85443, "x":5.3293, "y":1.62588, "heading":2.86572, "vx":-3.34333, "vy":2.13847, "omega":-0.00163, "ax":-0.00123, "ay":-0.00192, "alpha":0.0, "fx":[-0.02084,-0.02084,-0.02084,-0.02084], "fy":[-0.03259,-0.03259,-0.03259,-0.03259]}, - {"t":0.89512, "x":5.19327, "y":1.71289, "heading":2.86565, "vx":-3.34338, "vy":2.13839, "omega":-0.00163, "ax":-0.00495, "ay":-0.00775, "alpha":0.0, "fx":[-0.08427,-0.08427,-0.08426,-0.08426], "fy":[-0.13178,-0.13178,-0.13178,-0.13178]}, - {"t":0.9358, "x":5.05724, "y":1.79989, "heading":2.86558, "vx":-3.34358, "vy":2.13808, "omega":-0.00163, "ax":-0.01877, "ay":-0.03141, "alpha":-0.00242, "fx":[-0.32353,-0.32696,-0.31487,-0.31145], "fy":[-0.52658,-0.53866,-0.54208,-0.53]}, - {"t":0.97649, "x":4.92118, "y":1.88685, "heading":2.86552, "vx":-3.34435, "vy":2.1368, "omega":-0.00173, "ax":1.48133, "ay":-1.09441, "alpha":-5.10683, "fx":[17.61105,8.51821,32.90636,41.75224], "fy":[-1.6085,-30.09404,-33.87793,-8.88196]}, - {"t":1.01718, "x":4.78633, "y":1.97289, "heading":2.86545, "vx":-3.28407, "vy":2.09227, "omega":-0.20951, "ax":4.91954, "ay":-2.97256, "alpha":-9.14076, "fx":[105.20374,43.77661,79.81807,105.92133], "fy":[-9.99972,-97.75747,-73.11369,-21.37854]}, - {"t":1.05786, "x":4.65679, "y":2.05555, "heading":2.85692, "vx":-3.08391, "vy":1.97133, "omega":-0.58142, "ax":5.3694, "ay":-3.42683, "alpha":-2.07244, "fx":[95.78878,83.46596,88.24325,97.8298], "fy":[-51.46891,-69.80932,-63.95104,-47.92813]}, - {"t":1.09855, "x":4.53576, "y":2.13293, "heading":2.83327, "vx":-2.86545, "vy":1.8319, "omega":-0.66574, "ax":5.41121, "ay":-3.45686, "alpha":-0.41756, "fx":[92.88177,90.58729,91.26157,93.44209], "fy":[-57.47824,-61.04227,-60.07158,-56.6088]}, - {"t":1.13924, "x":4.42365, "y":2.2046, "heading":2.80618, "vx":-2.64528, "vy":1.69125, "omega":-0.68273, "ax":5.41942, "ay":-3.46329, "alpha":0.33496, "fx":[91.51657,93.29188,92.88539,91.03708], "fy":[-59.97973,-57.17334,-57.805,-60.68043]}, - {"t":1.17992, "x":4.32051, "y":2.27054, "heading":2.7784, "vx":-2.42478, "vy":1.55034, "omega":-0.6691, "ax":5.421, "ay":-3.46497, "alpha":0.76718, "fx":[90.66316,94.65385,93.94509,89.57654], "fy":[-61.44521,-55.09035,-56.24089,-62.97639]}, - {"t":1.22061, "x":4.22634, "y":2.33075, "heading":2.75118, "vx":-2.20422, "vy":1.40936, "omega":-0.63789, "ax":5.42081, "ay":-3.46526, "alpha":1.04848, "fx":[90.04423,95.44129,94.71517,88.62472], "fy":[-62.46056,-53.84498,-55.05479,-64.41225]}, - {"t":1.2613, "x":4.14114, "y":2.38523, "heading":2.72523, "vx":-1.98366, "vy":1.26837, "omega":-0.59523, "ax":5.42009, "ay":-3.46509, "alpha":1.24653, "fx":[89.55678,95.93374,95.31173,87.97443], "fy":[-63.23275,-53.05381,-54.10406,-65.36985]}, - {"t":1.30199, "x":4.06492, "y":2.43397, "heading":2.70101, "vx":-1.76313, "vy":1.12738, "omega":-0.54451, "ax":5.41925, "ay":-3.46475, "alpha":1.39367, "fx":[89.15461,96.25733,95.79228,87.51503], "fy":[-63.85257,-52.53166,-53.31651,-66.037]}, - {"t":1.34267, "x":3.99767, "y":2.47697, "heading":2.67885, "vx":-1.54264, "vy":0.98641, "omega":-0.48781, "ax":5.41841, "ay":-3.46438, "alpha":1.50737, "fx":[88.81421,96.47763,96.18878,87.18176], "fy":[-64.36587,-52.1775,-52.65154,-66.51748]}, - {"t":1.38336, "x":3.93938, "y":2.51424, "heading":2.65901, "vx":-1.32218, "vy":0.84546, "omega":-0.42647, "ax":5.41763, "ay":-3.46401, "alpha":1.59787, "fx":[88.52247,96.63234,96.52056,86.93383], "fy":[-64.7982,-51.93111,-52.08439,-66.87386]}, - {"t":1.42405, "x":3.89007, "y":2.54577, "heading":2.64165, "vx":-1.10175, "vy":0.70452, "omega":-0.36146, "ax":5.41691, "ay":-3.46367, "alpha":1.6716, "fx":[88.27157,96.74489,96.8002,86.74399], "fy":[-65.16499,-51.75406,-51.59884,-67.14654]}, - {"t":1.46473, "x":3.84973, "y":2.57157, "heading":2.62695, "vx":-0.88136, "vy":0.56359, "omega":-0.29345, "ax":5.41627, "ay":-3.46336, "alpha":1.73281, "fx":[88.05657,96.83069,97.03631,86.59321], "fy":[-65.47605,-51.6205,-51.1837,-67.36302]}, - {"t":1.50542, "x":3.81835, "y":2.59163, "heading":2.61501, "vx":-0.66098, "vy":0.42268, "omega":-0.22295, "ax":5.41569, "ay":-3.46308, "alpha":1.78442, "fx":[87.87422,96.90036,97.23503,86.46767], "fy":[-65.73797,-51.51235,-50.83092,-67.54282]}, - {"t":1.54611, "x":3.79594, "y":2.60596, "heading":2.60594, "vx":-0.44064, "vy":0.28177, "omega":-0.15034, "ax":5.41517, "ay":-3.46282, "alpha":1.82851, "fx":[87.72233,96.96151,97.40087,86.35707], "fy":[-65.95528,-51.4165,-50.53457,-67.70023]}, - {"t":1.58679, "x":3.7825, "y":2.61456, "heading":2.59982, "vx":-0.22031, "vy":0.14088, "omega":-0.07595, "ax":5.4147, "ay":-3.46259, "alpha":1.86661, "fx":[87.59938,97.01969,97.53717,86.2536], "fy":[-66.13118,-51.32324,-50.29023,-67.84595]}, - {"t":1.62748, "x":3.77801, "y":2.61743, "heading":2.59673, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":7.15247, "y":0.46054, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.43977, "ay":0.38656, "alpha":-0.2428, "fx":[-109.47113,-109.61816,-109.60954,-109.45564], "fy":[7.74027,5.25975,5.38163,7.91913]}, + {"t":0.0387, "x":7.14765, "y":0.46083, "heading":3.14159, "vx":-0.24924, "vy":0.01496, "omega":-0.0094, "ax":-6.43929, "ay":0.38653, "alpha":-0.2399, "fx":[-109.46388,-109.60917,-109.60043,-109.44843], "fy":[7.72601,5.27498,5.39572,7.90237]}, + {"t":0.07741, "x":7.13318, "y":0.46169, "heading":3.14123, "vx":-0.49847, "vy":0.02992, "omega":-0.01868, "ax":-6.43874, "ay":0.3865, "alpha":-0.23656, "fx":[-109.45549,-109.5988,-109.58997,-109.44016], "fy":[7.71006,5.29292,5.41146,7.88267]}, + {"t":0.11611, "x":7.10906, "y":0.46314, "heading":3.14051, "vx":-0.74767, "vy":0.04488, "omega":-0.02784, "ax":-6.4381, "ay":0.38647, "alpha":-0.23267, "fx":[-109.44569,-109.5867,-109.57781,-109.43056], "fy":[7.69186,5.31413,5.42939,7.85943]}, + {"t":0.15482, "x":7.0753, "y":0.46517, "heading":3.13943, "vx":-0.99685, "vy":0.05984, "omega":-0.03684, "ax":-6.43734, "ay":0.38643, "alpha":-0.22809, "fx":[-109.43412,-109.57241,-109.5635,-109.41925], "fy":[7.67065,5.33934,5.45026,7.83186]}, + {"t":0.19352, "x":7.0319, "y":0.46777, "heading":3.138, "vx":-1.246, "vy":0.07479, "omega":-0.04567, "ax":-6.43644, "ay":0.38638, "alpha":-0.22262, "fx":[-109.42025,-109.55531,-109.54639,-109.40573], "fy":[7.64539,5.36956,5.4751,7.79883]}, + {"t":0.23222, "x":6.97885, "y":0.47096, "heading":3.13623, "vx":-1.49512, "vy":0.08975, "omega":-0.05429, "ax":-6.43533, "ay":0.38632, "alpha":-0.21596, "fx":[-109.40336,-109.53448,-109.52556,-109.38925], "fy":[7.61457,5.40627,5.50536,7.75875]}, + {"t":0.27093, "x":6.91617, "y":0.47472, "heading":3.13413, "vx":-1.74419, "vy":0.1047, "omega":-0.06265, "ax":-6.43396, "ay":0.38625, "alpha":-0.20769, "fx":[-109.38233,-109.50854,-109.49965,-109.36873], "fy":[7.57595,5.45164,5.54322,7.70923]}, + {"t":0.30963, "x":6.84384, "y":0.47906, "heading":3.13171, "vx":-1.99321, "vy":0.11965, "omega":-0.07068, "ax":-6.4322, "ay":0.38616, "alpha":-0.19713, "fx":[-109.35546,-109.47538,-109.46653,-109.34246], "fy":[7.52609,5.50907,5.59201,7.6466]}, + {"t":0.34834, "x":6.76188, "y":0.48398, "heading":3.12897, "vx":-2.24216, "vy":0.1346, "omega":-0.07831, "ax":-6.42988, "ay":0.38604, "alpha":-0.18319, "fx":[-109.3199,-109.43148,-109.42271,-109.30764], "fy":[7.45932,5.58413,5.65719,7.56483]}, + {"t":0.38704, "x":6.67028, "y":0.48948, "heading":3.12594, "vx":-2.49102, "vy":0.14954, "omega":-0.0854, "ax":-6.42666, "ay":0.38587, "alpha":-0.16393, "fx":[-109.27061,-109.37061,-109.36204,-109.25932], "fy":[7.36566,5.68662,5.74832,7.45336]}, + {"t":0.42574, "x":6.56906, "y":0.49556, "heading":3.12264, "vx":-2.73976, "vy":0.16447, "omega":-0.09175, "ax":-6.4219, "ay":0.38562, "alpha":-0.13563, "fx":[-109.1977,-109.28059,-109.27253,-109.18785], "fy":[7.22578,5.83561,5.88381,7.29175]}, + {"t":0.46445, "x":6.45821, "y":0.50221, "heading":3.11909, "vx":-2.98831, "vy":0.1794, "omega":-0.097, "ax":-6.41415, "ay":0.38521, "alpha":-0.08993, "fx":[-109.07873,-109.13382,-109.12736,-109.0715], "fy":[6.99646,6.0737,6.10425,7.03481]}, + {"t":0.50315, "x":6.33774, "y":0.50944, "heading":3.11533, "vx":-3.23656, "vy":0.19431, "omega":-0.10048, "ax":-6.39933, "ay":0.38443, "alpha":-0.00371, "fx":[-108.84974,-108.85202,-108.85166,-108.84938], "fy":[6.55747,6.51934,6.5206,6.55874]}, + {"t":0.54185, "x":6.20768, "y":0.51725, "heading":3.11144, "vx":-3.48424, "vy":0.20919, "omega":-0.10062, "ax":-6.35974, "ay":0.38234, "alpha":0.22009, "fx":[-108.22813,-108.09176,-108.12865,-108.26091], "fy":[5.40004,7.67241,7.58401,5.35765]}, + {"t":0.58056, "x":6.06807, "y":0.52564, "heading":3.10755, "vx":-3.73039, "vy":0.22398, "omega":-0.0921, "ax":-5.94158, "ay":0.35983, "alpha":2.35627, "fx":[-100.83823,-99.32967,-101.47744,-102.61289], "fy":[-6.02327,18.72383,16.00682,-4.22516]}, + {"t":0.61926, "x":5.91924, "y":0.53457, "heading":3.10398, "vx":-3.96035, "vy":0.23791, "omega":-0.00091, "ax":-0.02747, "ay":0.03408, "alpha":0.01827, "fx":[-0.4216,-0.41802,-0.51279,-0.51638], "fy":[0.53056,0.62535,0.62889,0.53411]}, + {"t":0.65797, "x":5.76593, "y":0.54381, "heading":3.10395, "vx":-3.96142, "vy":0.23923, "omega":-0.0002, "ax":0.00641, "ay":0.10544, "alpha":0.00001, "fx":[0.10899,0.10899,0.10896,0.10896], "fy":[1.79344,1.79347,1.79347,1.79344]}, + {"t":0.69667, "x":5.61262, "y":0.55315, "heading":3.10394, "vx":-3.96117, "vy":0.24331, "omega":-0.0002, "ax":0.02411, "ay":0.38088, "alpha":0.0, "fx":[0.41015,0.41015,0.41015,0.41015], "fy":[6.47867,6.47867,6.47867,6.47867]}, + {"t":0.73537, "x":5.45932, "y":0.56285, "heading":3.10393, "vx":-3.96023, "vy":0.25805, "omega":-0.0002, "ax":0.09573, "ay":1.3341, "alpha":-0.00001, "fx":[1.6284,1.6284,1.62843,1.62843], "fy":[22.69273,22.6927,22.6927,22.69273]}, + {"t":0.77408, "x":5.30612, "y":0.57383, "heading":3.10393, "vx":-3.95653, "vy":0.30969, "omega":-0.0002, "ax":0.33472, "ay":3.49968, "alpha":-0.00003, "fx":[5.69333,5.69333,5.69355,5.69355], "fy":[59.52869,59.52857,59.52856,59.52868]}, + {"t":0.81278, "x":5.15323, "y":0.58844, "heading":3.10392, "vx":-3.94357, "vy":0.44514, "omega":-0.0002, "ax":0.72213, "ay":5.19375, "alpha":-0.00009, "fx":[12.28283,12.28289,12.28368,12.28363], "fy":[88.34433,88.34415,88.34406,88.34423]}, + {"t":0.85149, "x":5.00114, "y":0.60956, "heading":3.10391, "vx":-3.91562, "vy":0.64616, "omega":-0.0002, "ax":1.13019, "ay":5.79426, "alpha":-0.00019, "fx":[19.22313,19.22338,19.22516,19.22492], "fy":[98.55899,98.55877,98.55845,98.55866]}, + {"t":0.89019, "x":4.85044, "y":0.63891, "heading":3.1039, "vx":-3.87188, "vy":0.87042, "omega":-0.00021, "ax":1.53381, "ay":5.9638, "alpha":-0.00284, "fx":[26.07359,26.07905,26.10576,26.10029], "fy":[101.4472,101.44445,101.43787,101.44063]}, + {"t":0.92889, "x":4.70173, "y":0.67706, "heading":3.10389, "vx":-3.81252, "vy":1.10124, "omega":-0.00032, "ax":2.00103, "ay":5.94587, "alpha":-0.21879, "fx":[32.7525,33.30897,35.33727,34.74911], "fy":[101.58984,101.34351,100.67401,100.94296]}, + {"t":0.9676, "x":4.55567, "y":0.72414, "heading":3.10388, "vx":-3.73507, "vy":1.33137, "omega":-0.00879, "ax":4.04991, "ay":4.68021, "alpha":-4.5705, "fx":[43.89469,65.97451,92.55565,73.12646], "fy":[98.72123,84.24058,55.50597,79.96825]}, + {"t":1.0063, "x":4.41414, "y":0.77917, "heading":3.10354, "vx":-3.57832, "vy":1.51251, "omega":-0.18569, "ax":5.79589, "ay":2.51438, "alpha":-3.27227, "fx":[87.91838,103.02786,106.24749,97.15184], "fy":[63.95797,34.03173,23.74428,49.34162]}, + {"t":1.04501, "x":4.27999, "y":0.8396, "heading":3.09635, "vx":-3.354, "vy":1.60983, "omega":-0.31234, "ax":6.20747, "ay":1.50414, "alpha":-2.06547, "fx":[101.90409,107.62634,108.35079,104.46766], "fy":[39.02549,17.69701,13.68249,31.93485]}, + {"t":1.08371, "x":4.15483, "y":0.90303, "heading":3.08427, "vx":-3.11375, "vy":1.66804, "omega":-0.39228, "ax":6.33596, "ay":0.99799, "alpha":-1.43537, "fx":[106.17628,108.76291,109.02967,107.12276], "fy":[26.06197,10.92721,8.74739,22.16533]}, + {"t":1.12241, "x":4.03906, "y":0.96834, "heading":3.06908, "vx":-2.86852, "vy":1.70667, "omega":-0.44783, "ax":6.38873, "ay":0.70194, "alpha":-1.06629, "fx":[107.86408,109.19652,109.3244,108.29684], "fy":[18.55143,7.28733,5.82827,16.09189]}, + {"t":1.16112, "x":3.93282, "y":1.03492, "heading":3.05175, "vx":-2.62125, "vy":1.73384, "omega":-0.4891, "ax":6.41445, "ay":0.50922, "alpha":-0.82643, "fx":[108.66102,109.40457,109.47564,108.89046], "fy":[13.72622,5.02155,3.90489,11.99441]}, + {"t":1.19982, "x":3.83617, "y":1.10241, "heading":3.03282, "vx":-2.37299, "vy":1.75354, "omega":-0.52109, "ax":6.42847, "ay":0.37422, "alpha":-0.65862, "fx":[109.08469,109.5194,109.56212,109.21926], "fy":[10.38212,3.47483,2.54587,9.05881]}, + {"t":1.23852, "x":3.74914, "y":1.17056, "heading":3.01265, "vx":-2.12418, "vy":1.76803, "omega":-0.54658, "ax":6.43672, "ay":0.27453, "alpha":-0.53481, "fx":[109.32906,109.58901,109.61548,109.41337], "fy":[7.93202,2.34978,1.5377,6.85948]}, + {"t":1.27723, "x":3.67175, "y":1.23919, "heading":2.9915, "vx":-1.87505, "vy":1.77865, "omega":-0.56728, "ax":6.44185, "ay":0.19797, "alpha":-0.43979, "fx":[109.47835,109.63411,109.65035,109.53327], "fy":[6.06,1.49247,0.76258,5.15459]}, + {"t":1.31593, "x":3.604, "y":1.30818, "heading":2.96954, "vx":-1.62573, "vy":1.78632, "omega":-0.5843, "ax":6.44517, "ay":0.13735, "alpha":-0.36458, "fx":[109.57338,109.6648,109.67419,109.60972], "fy":[4.58224,0.81539,0.15018,3.79728]}, + {"t":1.35464, "x":3.54591, "y":1.37742, "heading":2.94693, "vx":-1.37628, "vy":1.79163, "omega":-0.59841, "ax":6.44739, "ay":0.08818, "alpha":-0.3036, "fx":[109.63561,109.68647,109.6911,109.65954], "fy":[3.38497,0.26524,-0.3441,2.69348]}, + {"t":1.39334, "x":3.49747, "y":1.44683, "heading":2.92377, "vx":-1.12674, "vy":1.79504, "omega":-0.61016, "ax":6.44889, "ay":0.0475, "alpha":-0.25316, "fx":[109.67712,109.70221,109.70349,109.69241], "fy":[2.3942,-0.19233,-0.74997,1.78022]}, + {"t":1.43204, "x":3.45869, "y":1.51634, "heading":2.90015, "vx":-0.87714, "vy":1.79688, "omega":-0.61996, "ax":6.01604, "ay":2.29643, "alpha":-0.26718, "fx":[101.63396,102.46005,103.00873,102.22165], "fy":[40.86201,38.73071,37.26678,39.38681]}, + {"t":1.4531, "x":3.44155, "y":1.55469, "heading":2.8871, "vx":-0.75046, "vy":1.84524, "omega":-0.62558, "ax":6.08604, "ay":2.09777, "alpha":-0.27934, "fx":[102.8568,103.65807,104.16555,103.40684], "fy":[37.58058,35.29395,33.79244,36.06255]}, + {"t":1.47416, "x":3.4271, "y":1.59401, "heading":2.87392, "vx":-0.62231, "vy":1.88941, "omega":-0.63147, "ax":6.17032, "ay":1.82664, "alpha":-0.29356, "fx":[104.34846,105.09883,105.53926,104.83528], "fy":[33.08136,30.5927,29.07247,31.536]}, + {"t":1.49521, "x":3.41537, "y":1.6342, "heading":2.86063, "vx":-0.49238, "vy":1.92787, "omega":-0.63765, "ax":6.25797, "ay":1.4865, "alpha":-0.31031, "fx":[105.92594,106.59066,106.94159,106.32679], "fy":[27.42067,24.68167,23.16814,25.86926]}, + {"t":1.51627, "x":3.40638, "y":1.67512, "heading":2.8472, "vx":-0.36061, "vy":1.95918, "omega":-0.64418, "ax":6.33804, "ay":1.07464, "alpha":-0.33007, "fx":[107.40912,107.9389,108.18139,107.70357], "fy":[20.5477,17.50817,16.03882,19.02247]}, + {"t":1.53733, "x":3.4002, "y":1.71661, "heading":2.83363, "vx":-0.22715, "vy":1.9818, "omega":-0.65113, "ax":6.3954, "ay":0.60598, "alpha":-0.35332, "fx":[108.53992,108.87494,109.00239,108.71831], "fy":[12.7094,9.32611,7.94554,11.24925]}, + {"t":1.55839, "x":3.39683, "y":1.75848, "heading":2.81992, "vx":-0.09248, "vy":1.99456, "omega":-0.65857, "ax":6.41722, "ay":0.12626, "alpha":-0.38073, "fx":[109.08632,109.1744,109.20078,109.15859], "fy":[4.68228,0.92656,-0.3329,3.31472]}, + {"t":1.57944, "x":3.39631, "y":1.8005, "heading":2.80606, "vx":0.04264, "vy":1.99722, "omega":-0.66659, "ax":6.40277, "ay":-0.33124, "alpha":-0.41343, "fx":[109.02546,108.82419,108.77494,109.01272], "fy":[-2.96031,-7.11594,-8.2375,-4.22325]}, + {"t":1.6005, "x":3.39862, "y":1.84249, "heading":2.79202, "vx":0.17747, "vy":1.99025, "omega":-0.67529, "ax":6.35549, "ay":-0.77065, "alpha":-0.45306, "fx":[108.42072,107.87611,107.77879,108.34467], "fy":[-10.28268,-14.88043,-15.84376,-11.42731]}, + {"t":1.62156, "x":3.40377, "y":1.88422, "heading":2.7778, "vx":0.31129, "vy":1.97402, "omega":-0.68483, "ax":6.27616, "ay":-1.19878, "alpha":-0.50194, "fx":[107.29362,106.33099,106.21898,107.17886], "fy":[-17.39518,-22.49542,-23.27118,-18.40159]}, + {"t":1.64261, "x":3.41172, "y":1.92553, "heading":2.76338, "vx":0.44345, "vy":1.94878, "omega":-0.6954, "ax":6.16425, "ay":-1.61578, "alpha":-0.56345, "fx":[105.64327,104.16226,104.08102,105.5219], "fy":[-24.29246,-29.97826,-30.52883,-25.13635]}, + {"t":1.66367, "x":3.42242, "y":1.9662, "heading":2.74874, "vx":0.57325, "vy":1.91475, "omega":-0.70727, "ax":6.01853, "ay":-2.01871, "alpha":-0.6427, "fx":[103.45864,101.32227,101.3374,103.37535], "fy":[-30.91102,-37.29848,-37.5766,-31.56441]}, + {"t":1.68473, "x":3.43583, "y":2.00607, "heading":2.73384, "vx":0.69998, "vy":1.87225, "omega":-0.7208, "ax":5.83647, "ay":-2.40249, "alpha":-0.74784, "fx":[100.71136,97.72617,97.93753,100.73181], "fy":[-37.14332,-44.39934,-44.34489,-37.57524]}, + {"t":1.70578, "x":3.45186, "y":2.04496, "heading":2.71867, "vx":0.82288, "vy":1.82166, "omega":-0.73655, "ax":5.61285, "ay":-2.75873, "alpha":-0.8924, "fx":[97.3326,93.21495,93.78452,97.56003], "fy":[-42.80975,-51.18173,-50.71867,-42.99038]}, + {"t":1.72684, "x":3.47043, "y":2.08271, "heading":2.70316, "vx":0.94107, "vy":1.76357, "omega":-0.75534, "ax":5.33623, "ay":-3.07172, "alpha":-1.10002, "fx":[93.1514,87.47291,88.68352,93.76334], "fy":[-47.57702,-57.44164,-56.48223,-47.49542]}, + {"t":1.7479, "x":3.49143, "y":2.11917, "heading":2.68725, "vx":1.05343, "vy":1.69889, "omega":-0.7785, "ax":4.97982, "ay":-3.3078, "alpha":-1.41334, "fx":[87.71364,79.83362,82.21973,89.05428], "fy":[-50.74356,-62.67413,-61.16442,-50.47688]}, + {"t":1.76895, "x":3.51472, "y":2.15421, "heading":2.67086, "vx":1.15829, "vy":1.62924, "omega":-0.80826, "ax":4.47607, "ay":-3.3847, "alpha":-1.90434, "fx":[79.70132,68.8403,73.46185,82.54346], "fy":[-50.65772,-65.41844,-63.58096,-50.63391]}, + {"t":1.79001, "x":3.5401, "y":2.18776, "heading":2.65384, "vx":1.25254, "vy":1.55796, "omega":-0.84836, "ax":3.65591, "ay":-3.09362, "alpha":-2.60749, "fx":[65.241,51.74951,60.34406,71.40908], "fy":[-43.50251,-61.20283,-60.5084,-45.27282]}, + {"t":1.81107, "x":3.56728, "y":2.21988, "heading":2.63598, "vx":1.32953, "vy":1.49282, "omega":-0.90327, "ax":2.28202, "ay":-2.10002, "alpha":-2.72235, "fx":[38.59745,28.51376,39.56193,48.59321], "fy":[-26.13813,-41.13501,-44.49542,-31.11458]}, + {"t":1.83212, "x":3.59578, "y":2.25085, "heading":2.61696, "vx":1.37758, "vy":1.4486, "omega":-0.96059, "ax":0.66237, "ay":-0.69928, "alpha":0.33448, "fx":[11.55793,12.46104,10.97672,10.07138], "fy":[-13.07051,-11.55398,-10.71467,-12.23905]}, + {"t":1.85318, "x":3.62494, "y":2.2812, "heading":2.59673, "vx":1.39153, "vy":1.43388, "omega":-0.95355, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_2.traj b/src/main/deploy/choreo/E_RIGHT_PATH_2.traj index 6322dbfd..e5795611 100644 --- a/src/main/deploy/choreo/E_RIGHT_PATH_2.traj +++ b/src/main/deploy/choreo/E_RIGHT_PATH_2.traj @@ -6,14 +6,14 @@ {"x":3.9948270320892334, "y":2.801387310028076, "heading":2.618314122167914, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":2.619781017303467, "y":2.2527506351470947, "heading":1.5707963267948966, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":1.8137584924697876, "y":2.195854902267456, "heading":0.0, "intervals":13, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":1.2163537740707395, "y":2.1863720417022705, "heading":1.5707963267948966, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":3.462650775909424, "y":2.6634156703948975, "heading":2.618314122167914, "intervals":14, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":1.2163537740707395, "y":2.1863720417022705, "heading":1.5707963267948966, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.7802374362945557, "y":1.8250209093093872, "heading":0.0, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":2.7930970191955566, "y":2.08547043800354, "heading":2.618314122167914, "intervals":14, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":2, "to":3, "data":{"type":"MaxAngularVelocity", "props":{"max":0.0}}, "enabled":true}, - {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":0, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], "targetDt":0.05 }, @@ -22,14 +22,14 @@ {"x":{"exp":"3.9948270320892334 m", "val":3.9948270320892334}, "y":{"exp":"2.801387310028076 m", "val":2.801387310028076}, "heading":{"exp":"2.6183141221679134 rad", "val":2.618314122167914}, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":{"exp":"2.619781017303467 m", "val":2.619781017303467}, "y":{"exp":"2.2527506351470947 m", "val":2.2527506351470947}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":{"exp":"1.8137584924697876 m", "val":1.8137584924697876}, "y":{"exp":"2.195854902267456 m", "val":2.195854902267456}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":13, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"1.2163537740707397 m", "val":1.2163537740707395}, "y":{"exp":"2.1863720417022705 m", "val":2.1863720417022705}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"3.462650775909424 m", "val":3.462650775909424}, "y":{"exp":"2.6634156703948975 m", "val":2.6634156703948975}, "heading":{"exp":"2.6183141221679134 rad", "val":2.618314122167914}, "intervals":14, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"1.2163537740707397 m", "val":1.2163537740707395}, "y":{"exp":"2.1863720417022705 m", "val":2.1863720417022705}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.7802374362945557 m", "val":1.7802374362945557}, "y":{"exp":"1.8250209093093872 m", "val":1.8250209093093872}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"2.7930970191955566 m", "val":2.7930970191955566}, "y":{"exp":"2.08547043800354 m", "val":2.08547043800354}, "heading":{"exp":"2.6183141221679134 rad", "val":2.618314122167914}, "intervals":14, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":2, "to":3, "data":{"type":"MaxAngularVelocity", "props":{"max":{"exp":"0 rad / s", "val":0.0}}}, "enabled":true}, - {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":0, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], "targetDt":{ "exp":"0.05 s", @@ -38,7 +38,7 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,0.70417,0.93826,1.36875,2.57084], + "waypoints":[0.0,0.70417,0.93826,1.36875,1.86431,2.22482], "samples":[ {"t":0.0, "x":3.99483, "y":2.80139, "heading":2.61831, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.26392, "ay":-2.87502, "alpha":-7.77032, "fx":[-109.39894,-101.01273,-65.94747,-81.79183], "fy":[7.60574,-42.85708,-87.65929,-72.70251]}, {"t":0.02347, "x":3.99338, "y":2.8006, "heading":2.61831, "vx":-0.12356, "vy":-0.06748, "omega":-0.18239, "ax":-5.29273, "ay":-2.85498, "alpha":-7.62651, "fx":[-109.43396,-101.06468,-66.6976,-82.91509], "fy":[6.95037,-42.71801,-87.0799,-71.40235]}, @@ -98,42 +98,52 @@ {"t":1.2694, "x":1.24818, "y":2.18686, "heading":1.5708, "vx":-0.64072, "vy":-0.00977, "omega":0.0, "ax":6.44899, "ay":0.09926, "alpha":0.0, "fx":[109.69554,109.69554,109.69554,109.69554], "fy":[1.68846,1.68846,1.68846,1.68846]}, {"t":1.30252, "x":1.2305, "y":2.18659, "heading":1.5708, "vx":-0.42716, "vy":-0.00649, "omega":0.0, "ax":6.44952, "ay":0.09833, "alpha":0.0, "fx":[109.7045,109.7045,109.7045,109.7045], "fy":[1.67264,1.67264,1.67264,1.67264]}, {"t":1.33563, "x":1.21989, "y":2.18643, "heading":1.5708, "vx":-0.21359, "vy":-0.00323, "omega":0.0, "ax":6.44999, "ay":0.09751, "alpha":0.0, "fx":[109.71248,109.71248,109.71248,109.71248], "fy":[1.65854,1.65854,1.65854,1.65854]}, - {"t":1.36875, "x":1.21635, "y":2.18637, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.22326, "ay":1.30875, "alpha":3.58855, "fx":[109.55408,109.67181,104.38435,99.81312], "fy":[5.60953,3.99663,33.89718,45.54222]}, - {"t":1.40309, "x":1.22002, "y":2.18714, "heading":1.5708, "vx":0.21374, "vy":0.04495, "omega":0.12325, "ax":6.2249, "ay":1.30979, "alpha":3.54195, "fx":[109.52994,109.65627,104.41195,99.93702], "fy":[5.87654,4.20507,33.788,45.24677]}, - {"t":1.43744, "x":1.23104, "y":2.18946, "heading":1.57503, "vx":0.42754, "vy":0.08993, "omega":0.2449, "ax":6.22666, "ay":1.311, "alpha":3.49068, "fx":[109.50744,109.63561,104.41897,100.09269], "fy":[6.08122,4.50434,33.73856,44.87473]}, - {"t":1.47178, "x":1.24939, "y":2.19332, "heading":1.58344, "vx":0.64139, "vy":0.13496, "omega":0.36479, "ax":6.22857, "ay":1.3124, "alpha":3.43312, "fx":[109.4858,109.60871,104.40784,100.28275], "fy":[6.23848,4.89772,33.74084,44.41714]}, - {"t":1.50613, "x":1.2751, "y":2.19873, "heading":1.59597, "vx":0.85532, "vy":0.18004, "omega":0.4827, "ax":6.23071, "ay":1.31402, "alpha":3.36712, "fx":[109.46374,109.57398,104.3816,100.51091], "fy":[6.36819,5.39023,33.78426,43.86141]}, - {"t":1.54047, "x":1.30815, "y":2.20569, "heading":1.61255, "vx":1.06931, "vy":0.22517, "omega":0.59835, "ax":6.23313, "ay":1.31588, "alpha":3.28987, "fx":[109.43934,109.52924,104.34432,100.78196], "fy":[6.49638,5.98907,33.85466,43.19067]}, - {"t":1.57482, "x":1.34855, "y":2.2142, "heading":1.6331, "vx":1.28339, "vy":0.27036, "omega":0.71134, "ax":6.23592, "ay":1.31803, "alpha":3.19758, "fx":[109.40993,109.4715,104.3015,101.10178], "fy":[6.65705,6.70436,33.93276,42.38279]}, - {"t":1.60916, "x":1.39631, "y":2.22426, "heading":1.65753, "vx":1.49757, "vy":0.31563, "omega":0.82116, "ax":6.23918, "ay":1.32051, "alpha":3.08507, "fx":[109.37162,109.39657,104.26092,101.47742], "fy":[6.89524,7.55045,33.99166,41.4088]}, - {"t":1.64351, "x":1.45142, "y":2.23588, "heading":1.68573, "vx":1.71185, "vy":0.36098, "omega":0.92712, "ax":6.24302, "ay":1.32341, "alpha":2.94506, "fx":[109.31856,109.29839,104.23386,101.91719], "fy":[7.2721,8.54826,33.99239,40.23025]}, - {"t":1.67786, "x":1.5139, "y":2.24906, "heading":1.71757, "vx":1.92627, "vy":0.40644, "omega":1.02827, "ax":6.24756, "ay":1.32681, "alpha":2.76686, "fx":[109.24114,109.16778,104.23722,102.43089], "fy":[7.8738,9.7299,33.87595,38.79476]}, - {"t":1.7122, "x":1.58374, "y":2.2638, "heading":1.75289, "vx":2.14085, "vy":0.452, "omega":1.1233, "ax":6.25289, "ay":1.33088, "alpha":2.53392, "fx":[109.12217,108.98974,104.29738,103.03022], "fy":[8.8284,11.14782,33.54746,37.02763]}, - {"t":1.74655, "x":1.66096, "y":2.28011, "heading":1.79147, "vx":2.35561, "vy":0.49771, "omega":1.21032, "ax":6.25896, "ay":1.3359, "alpha":2.21855, "fx":[108.92782,108.73738,104.4575,103.72949], "fy":[10.33976,12.89547,32.84208,34.81547]}, - {"t":1.78089, "x":1.74555, "y":2.29799, "heading":1.83304, "vx":2.57057, "vy":0.5436, "omega":1.28652, "ax":6.26522, "ay":1.34237, "alpha":1.76962, "fx":[108.58373,108.35562,104.79244,104.5467], "fy":[12.76246,15.15871,31.44142,31.97083]}, - {"t":1.81524, "x":1.83753, "y":2.31746, "heading":1.87723, "vx":2.78575, "vy":0.5897, "omega":1.3473, "ax":6.26927, "ay":1.35122, "alpha":1.07874, "fx":[107.90253,107.70826,105.43979,105.50334], "fy":[16.78742,18.36838,28.63195,28.14767]}, - {"t":1.84958, "x":1.93691, "y":2.33851, "heading":1.9235, "vx":3.00107, "vy":0.63611, "omega":1.38435, "ax":6.25976, "ay":1.36362, "alpha":-0.13802, "fx":[106.31128,106.3411,106.64301,106.61183], "fy":[23.97491,23.79004,22.40572,22.60841]}, - {"t":1.88393, "x":2.04367, "y":2.36116, "heading":1.97105, "vx":3.21607, "vy":0.68294, "omega":1.37961, "ax":6.15663, "ay":1.37596, "alpha":-2.98553, "fx":[101.46531,101.52481,108.14063,107.75913], "fy":[38.56492,37.19027,4.41031,13.45303]}, - {"t":1.91827, "x":2.15776, "y":2.38542, "heading":2.01843, "vx":3.42752, "vy":0.7302, "omega":1.27707, "ax":4.86226, "ay":1.41308, "alpha":-13.62919, "fx":[85.19207,49.98891,88.06108,107.58049], "fy":[65.36877,90.08591,-58.10169,-1.20891]}, - {"t":1.95262, "x":2.27835, "y":2.41134, "heading":2.06229, "vx":3.59452, "vy":0.77873, "omega":0.80897, "ax":-0.06534, "ay":0.07997, "alpha":-0.18195, "fx":[-0.91776,-1.75058,-1.30509,-0.47202], "fy":[1.99951,1.55356,0.72088,1.16691]}, - {"t":1.98696, "x":2.40177, "y":2.43813, "heading":2.09007, "vx":3.59227, "vy":0.78148, "omega":0.80272, "ax":-4.93607, "ay":-1.46891, "alpha":12.95615, "fx":[-83.76624,-54.63338,-89.86078,-107.58399], "fy":[-67.09193,-86.58003,55.76602,-2.03694]}, - {"t":2.02131, "x":2.52223, "y":2.4641, "heading":2.11764, "vx":3.42274, "vy":0.73103, "omega":1.2477, "ax":-6.09291, "ay":-1.37473, "alpha":4.13597, "fx":[-98.46032,-100.26025,-108.0448,-107.78956], "fy":[-45.61903,-39.75701,5.2878,-13.44696]}, - {"t":2.05565, "x":2.6362, "y":2.4884, "heading":2.1605, "vx":3.21348, "vy":0.68381, "omega":1.38976, "ax":-6.25578, "ay":-1.36498, "alpha":0.56795, "fx":[-105.60313,-106.03852,-107.18825,-106.80609], "fy":[-26.86261,-24.88604,-19.45086,-21.67208]}, - {"t":2.09, "x":2.74287, "y":2.51108, "heading":2.20823, "vx":2.99862, "vy":0.63693, "omega":1.40926, "ax":-6.27057, "ay":-1.35283, "alpha":-0.91546, "fx":[-107.91132,-107.24319,-105.31956,-106.16867], "fy":[-16.75601,-20.85615,-28.97289,-25.45995]}, - {"t":2.12435, "x":2.84216, "y":2.53216, "heading":2.25663, "vx":2.78325, "vy":0.59047, "omega":1.37782, "ax":-6.26537, "ay":-1.34358, "alpha":-1.73196, "fx":[-108.83077,-107.6588,-103.9216,-105.8772], "fy":[-10.62549,-19.51229,-34.13075,-27.14681]}, - {"t":2.15869, "x":2.93406, "y":2.55165, "heading":2.30395, "vx":2.56807, "vy":0.54432, "omega":1.31834, "ax":-6.25725, "ay":-1.33707, "alpha":-2.24287, "fx":[-109.24467,-107.80972,-102.86135,-105.82014], "fy":[-6.59216,-19.20395,-37.47162,-27.70479]}, - {"t":2.19304, "x":3.01857, "y":2.56955, "heading":2.34923, "vx":2.35316, "vy":0.4984, "omega":1.2413, "ax":-6.24963, "ay":-1.33231, "alpha":-2.58833, "fx":[-109.4447,-107.84147,-102.02215,-105.90943], "fy":[-3.79675,-19.37643,-39.86768,-27.60801]}, - {"t":2.22738, "x":3.09571, "y":2.58589, "heading":2.39186, "vx":2.13851, "vy":0.45264, "omega":1.15241, "ax":-6.24315, "ay":-1.32859, "alpha":-2.83532, "fx":[-109.54555,-107.81097,-101.33618,-106.0842], "fy":[-1.79238,-19.78761,-41.69538,-27.12059]}, - {"t":2.26173, "x":3.16547, "y":2.60065, "heading":2.43144, "vx":1.92409, "vy":0.40701, "omega":1.05503, "ax":-6.23776, "ay":-1.32549, "alpha":-3.02003, "fx":[-109.5978,-107.74595,-100.76345,-106.30311], "fy":[-0.32153,-20.31341,-43.14462,-26.40553]}, - {"t":2.29607, "x":3.22788, "y":2.61385, "heading":2.46768, "vx":1.70985, "vy":0.36149, "omega":0.9513, "ax":-6.23328, "ay":-1.32278, "alpha":-3.16359, "fx":[-109.62549,-107.66235,-100.27883,-106.53827], "fy":[0.7766,-20.88294,-44.32283,-25.57124]}, - {"t":2.33042, "x":3.28293, "y":2.62548, "heading":2.50035, "vx":1.49577, "vy":0.31606, "omega":0.84265, "ax":-6.22949, "ay":-1.32033, "alpha":-3.27894, "fx":[-109.64056,-107.57045,-99.86544,-106.77108], "fy":[1.60894,-21.45245,-45.29653,-24.6938]}, - {"t":2.36476, "x":3.33062, "y":2.63556, "heading":2.52929, "vx":1.28181, "vy":0.27071, "omega":0.73003, "ax":-6.22625, "ay":-1.3181, "alpha":-3.37425, "fx":[-109.64903,-107.47756,-99.51118,-106.98945], "fy":[2.25012,-21.99328,-46.11004,-23.82858]}, - {"t":2.39911, "x":3.37098, "y":2.64408, "heading":2.55437, "vx":1.06797, "vy":0.22544, "omega":0.61414, "ax":-6.22344, "ay":-1.31606, "alpha":-3.45478, "fx":[-109.65396,-107.38919,-99.20693,-107.18578], "fy":[2.75424,-22.48581,-46.79459,-23.01682]}, - {"t":2.43345, "x":3.40399, "y":2.65104, "heading":2.57546, "vx":0.85422, "vy":0.18024, "omega":0.49548, "ax":-6.22097, "ay":-1.31421, "alpha":-3.52393, "fx":[-109.65679,-107.30966,-98.94551,-107.35556], "fy":[3.16164,-22.91609,-47.37319,-22.28973]}, - {"t":2.4678, "x":3.42965, "y":2.65646, "heading":2.59248, "vx":0.64056, "vy":0.1351, "omega":0.37445, "ax":-6.21877, "ay":-1.31256, "alpha":-3.58396, "fx":[-109.65818,-107.24243,-98.72118,-107.49628], "fy":[3.50298,-23.27388,-47.86326,-21.67118]}, - {"t":2.50214, "x":3.44799, "y":2.66032, "heading":2.60534, "vx":0.42698, "vy":0.09002, "omega":0.25136, "ax":-6.21681, "ay":-1.31112, "alpha":-3.63638, "fx":[-109.65832,-107.19029,-98.52935,-107.60666], "fy":[3.80185,-23.55145,-48.27818,-21.17965]}, - {"t":2.53649, "x":3.45899, "y":2.66264, "heading":2.61397, "vx":0.21346, "vy":0.04499, "omega":0.12647, "ax":-6.21505, "ay":-1.3099, "alpha":-3.68227, "fx":[-109.65719,-107.15546,-98.36636,-107.68599], "fy":[4.07644,-23.74281,-48.62818,-20.82963]}, - {"t":2.57084, "x":3.46265, "y":2.66342, "heading":2.61831, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":1.36875, "x":1.21635, "y":2.18637, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":3.24699, "ay":-5.47285, "alpha":3.39824, "fx":[35.40708,60.34585,76.16112,49.00745], "fy":[-103.80892,-91.61316,-78.89831,-98.04618]}, + {"t":1.39235, "x":1.21726, "y":2.18485, "heading":1.5708, "vx":0.07662, "vy":-0.12915, "omega":0.08019, "ax":3.41994, "ay":-5.36005, "alpha":3.4864, "fx":[37.84599,62.83436,79.21432,52.79431], "fy":[-102.93019,-89.91197,-75.81379,-96.03602]}, + {"t":1.41594, "x":1.22002, "y":2.18031, "heading":1.57269, "vx":0.15733, "vy":-0.25564, "omega":0.16247, "ax":3.61503, "ay":-5.22299, "alpha":3.58348, "fx":[40.675,65.64247,82.53204,57.11325], "fy":[-101.82844,-87.86824,-72.16627,-93.5034]}, + {"t":1.43954, "x":1.22474, "y":2.17282, "heading":1.57652, "vx":0.24264, "vy":-0.37889, "omega":0.24703, "ax":3.8356, "ay":-5.05446, "alpha":3.69037, "fx":[43.97625,68.81156,86.11704,62.06516], "fy":[-100.42698,-85.39231,-67.82249,-90.25806]}, + {"t":1.46314, "x":1.23153, "y":2.16247, "heading":1.58235, "vx":0.33315, "vy":-0.49817, "omega":0.33411, "ax":4.08506, "ay":-4.84469, "alpha":3.80811, "fx":[47.85306,72.38416,89.95044,67.75498], "fy":[-98.61496,-82.36597,-62.61887,-86.02703]}, + {"t":1.48674, "x":1.24053, "y":2.14937, "heading":1.59024, "vx":0.42955, "vy":-0.61249, "omega":0.42398, "ax":4.36627, "ay":-4.58037, "alpha":3.93823, "fx":[52.43368,76.39884,93.97613,74.26739], "fy":[-96.22919,-78.63301,-56.36054,-80.42006]}, + {"t":1.51034, "x":1.25188, "y":2.13364, "heading":1.60024, "vx":0.53259, "vy":-0.72058, "omega":0.51691, "ax":4.68027, "ay":-4.24366, "alpha":4.08329, "fx":[57.87199,80.87987,98.07839,81.60975], "fy":[-93.02528,-73.98797,-48.82795,-72.89265]}, + {"t":1.53393, "x":1.26575, "y":2.11545, "heading":1.61244, "vx":0.64303, "vy":-0.82072, "omega":0.61327, "ax":5.02367, "ay":-3.81152, "alpha":4.24747, "fx":[64.33788,85.81766,102.0535,89.59546], "fy":[-88.63313,-68.16479,-39.79885,-62.73438]}, + {"t":1.55753, "x":1.28233, "y":2.09502, "heading":1.62691, "vx":0.76158, "vy":-0.91067, "omega":0.71351, "ax":5.38436, "ay":-3.25668, "alpha":4.43508, "fx":[71.97935,91.13465,105.58235,97.64905], "fy":[-82.49311,-60.83118,-29.096,-49.16029]}, + {"t":1.58113, "x":1.3018, "y":2.07263, "heading":1.64375, "vx":0.88864, "vy":-0.98752, "omega":0.81817, "ax":5.73599, "ay":-2.55297, "alpha":4.64125, "fx":[80.818,96.63142,108.22235,104.5982], "fy":[-73.78433,-51.60218,-16.66808,-31.6465]}, + {"t":1.60473, "x":1.32437, "y":2.04861, "heading":1.66306, "vx":1.024, "vy":-1.04777, "omega":0.92769, "ax":6.03503, "ay":-1.68699, "alpha":4.82717, "fx":[90.51395,101.91564,109.44916,108.73772], "fy":[-61.41181,-40.09915,-2.69413,-10.57569]}, + {"t":1.62833, "x":1.35021, "y":2.02342, "heading":1.68495, "vx":1.16642, "vy":-1.08758, "omega":1.0416, "ax":6.22655, "ay":-0.67288, "alpha":4.89543, "fx":[99.97156,106.3427,108.77489,108.55822], "fy":[-44.25631,-26.08881,12.33389,12.2292]}, + {"t":1.65193, "x":1.37947, "y":1.99757, "heading":1.70953, "vx":1.31335, "vy":-1.10345, "omega":1.15713, "ax":6.25915, "ay":0.43941, "alpha":4.72737, "fx":[107.05142,109.04483,105.92526,103.84403], "fy":[-22.00917,-9.71086,27.62744,33.98945]}, + {"t":1.67552, "x":1.41221, "y":1.97165, "heading":1.73683, "vx":1.46106, "vy":-1.09308, "omega":1.26868, "ax":6.10325, "ay":1.56683, "alpha":4.29792, "fx":[109.2182,109.1497,100.98548,95.90505], "fy":[3.60014,8.30045,42.26618,52.43824]}, + {"t":1.69912, "x":1.44838, "y":1.94629, "heading":1.76677, "vx":1.60508, "vy":-1.05611, "omega":1.37011, "ax":5.77042, "ay":2.61125, "alpha":3.71792, "fx":[105.42862,106.17601,94.40367,86.60421], "fy":[28.81797,26.62754,55.45306,66.76791]}, + {"t":1.72272, "x":1.48787, "y":1.92209, "heading":1.79911, "vx":1.74125, "vy":-0.99449, "omega":1.45784, "ax":5.3163, "ay":3.49759, "alpha":3.12253, "fx":[97.1609,100.34465,86.83493,77.37431], "fy":[50.14726,43.76642,66.71226,77.34578]}, + {"t":1.74632, "x":1.53044, "y":1.8996, "heading":1.83351, "vx":1.86671, "vy":-0.91195, "omega":1.53153, "ax":4.81191, "ay":4.20077, "alpha":2.57958, "fx":[87.00396,92.49867,78.9317,68.96253], "fy":[66.30855,58.58817,75.9277,84.99096]}, + {"t":1.76992, "x":1.57583, "y":1.87925, "heading":1.86965, "vx":1.98026, "vy":-0.81282, "omega":1.5924, "ax":4.31255, "ay":4.73633, "alpha":2.10388, "fx":[76.91044,83.692,71.20039,61.61841], "fy":[77.86364,70.6353,83.24892,90.50672]}, + {"t":1.79351, "x":1.62376, "y":1.86139, "heading":1.90723, "vx":2.08203, "vy":-0.70105, "omega":1.64205, "ax":3.84916, "ay":5.13647, "alpha":1.69273, "fx":[67.79637,74.80358,63.96017,55.33228], "fy":[85.9762,80.02272,88.95832,94.52223]}, + {"t":1.81711, "x":1.67396, "y":1.84627, "heading":1.94598, "vx":2.17286, "vy":-0.57984, "omega":1.682, "ax":3.43405, "ay":5.43393, "alpha":1.33988, "fx":[59.90085,66.38808,57.37008,49.99], "fy":[91.70057,87.16227,93.36778,97.48772]}, + {"t":1.84071, "x":1.72619, "y":1.8341, "heading":1.98567, "vx":2.2539, "vy":-0.45161, "omega":1.71361, "ax":3.06885, "ay":5.65582, "alpha":1.03819, "fx":[53.15906,58.71268,51.47859,45.45073], "fy":[95.80555,92.53395,96.76204,99.71405]}, + {"t":1.86431, "x":1.78024, "y":1.82502, "heading":2.02611, "vx":2.32632, "vy":-0.31814, "omega":1.73811, "ax":2.89467, "ay":5.73933, "alpha":0.90021, "fx":[50.12311,54.97229,48.53218,43.32216], "fy":[97.25443,94.63391,98.11449,100.49481]}, + {"t":1.87933, "x":1.81551, "y":1.82089, "heading":2.05222, "vx":2.3698, "vy":-0.23193, "omega":1.75164, "ax":2.88367, "ay":5.74468, "alpha":0.81994, "fx":[49.98406,54.2601,48.27855,43.67877], "fy":[97.30533,95.02154,98.21622,100.31808]}, + {"t":1.89435, "x":1.85143, "y":1.81805, "heading":2.07853, "vx":2.41312, "vy":-0.14564, "omega":1.76395, "ax":2.87156, "ay":5.75041, "alpha":0.7318, "fx":[49.78883,53.48133,48.0384,44.06919], "fy":[97.38298,95.43723,98.30804,100.12292]}, + {"t":1.90937, "x":1.888, "y":1.81651, "heading":2.10502, "vx":2.45625, "vy":-0.05926, "omega":1.77495, "ax":2.85817, "ay":5.75657, "alpha":0.63458, "fx":[49.52957,52.62639,47.81463,44.49608], "fy":[97.49071,95.88389,98.38827,99.90733]}, + {"t":1.9244, "x":1.92522, "y":1.81627, "heading":2.13169, "vx":2.49919, "vy":0.02721, "omega":1.78448, "ax":2.84328, "ay":5.76319, "alpha":0.52686, "fx":[49.19709,51.68343,47.61071,44.96248], "fy":[97.63226,96.36492,98.45482,99.66904]}, + {"t":1.93942, "x":1.96309, "y":1.81733, "heading":2.15849, "vx":2.5419, "vy":0.11379, "omega":1.79239, "ax":2.82663, "ay":5.77033, "alpha":0.4069, "fx":[48.78047,50.63767,47.43086,45.47195], "fy":[97.81183,96.88438,98.50514,99.40529]}, + {"t":1.95444, "x":2.00159, "y":1.81969, "heading":2.18542, "vx":2.58436, "vy":0.20046, "omega":1.7985, "ax":2.8079, "ay":5.77802, "alpha":0.27252, "fx":[48.26662,49.47044,47.28029,46.02866], "fy":[98.03415,97.4471,98.53605,99.1128]}, + {"t":1.96946, "x":2.04073, "y":1.82336, "heading":2.21243, "vx":2.62654, "vy":0.28726, "omega":1.8026, "ax":2.78665, "ay":5.78632, "alpha":0.12104, "fx":[47.63971,48.15779,47.16552,46.6376], "fy":[98.30457,98.05881,98.54347,98.78757]}, + {"t":1.98448, "x":2.08049, "y":1.82832, "heading":2.23951, "vx":2.6684, "vy":0.37418, "omega":1.80442, "ax":2.76237, "ay":5.79525, "alpha":-0.05096, "fx":[46.88032,46.66855,47.0949,47.30486], "fy":[98.62911,98.72635,98.52213,98.42465]}, + {"t":1.9995, "x":2.12089, "y":1.8346, "heading":2.26662, "vx":2.70989, "vy":0.46123, "omega":1.80365, "ax":2.73436, "ay":5.80485, "alpha":-0.24792, "fx":[45.96441,44.96146,47.07926,48.03789], "fy":[99.01456,99.45777,98.46499,98.01784]}, + {"t":2.01452, "x":2.1619, "y":1.84218, "heading":2.29371, "vx":2.75097, "vy":0.54843, "omega":1.79993, "ax":2.70172, "ay":5.8151, "alpha":-0.47565, "fx":[44.86182,42.98088,47.13307,48.84605], "fy":[99.46852,100.26236,98.36248,97.55925]}, + {"t":2.02955, "x":2.20353, "y":1.85108, "heading":2.32075, "vx":2.79155, "vy":0.63578, "omega":1.79278, "ax":2.66321, "ay":5.82593, "alpha":-0.74198, "fx":[43.53424,40.6502,47.2761,49.7412], "fy":[99.99926,101.15032,98.20111,97.03863]}, + {"t":2.04457, "x":2.24577, "y":1.86128, "heading":2.34768, "vx":2.83155, "vy":0.72329, "omega":1.78164, "ax":2.61716, "ay":5.83712, "alpha":-1.0577, "fx":[41.93243,37.86155,47.53629,50.73863], "fy":[100.61557,102.13174,97.96134,96.44246]}, + {"t":2.05959, "x":2.2886, "y":1.87281, "heading":2.37444, "vx":2.87087, "vy":0.81098, "omega":1.76575, "ax":2.56125, "ay":5.84821, "alpha":-1.43807, "fx":[39.99237,34.4593,47.95441,51.8582], "fy":[101.32602,103.21351,97.61357,95.7526]}, + {"t":2.07461, "x":2.33201, "y":1.88565, "heading":2.40096, "vx":2.90934, "vy":0.89883, "omega":1.74415, "ax":2.49214, "ay":5.85818, "alpha":-1.90537, "fx":[37.63012,30.21337,48.59249,53.12603], "fy":[102.13744,104.39158,97.11095,94.9442]}, + {"t":2.08963, "x":2.37599, "y":1.89981, "heading":2.42716, "vx":2.94678, "vy":0.98682, "omega":1.71552, "ax":2.40506, "ay":5.8649, "alpha":-2.4931, "fx":[34.73571,24.77622,49.54942,54.57623], "fy":[103.05158,105.6316,96.37494,93.98281]}, + {"t":2.10465, "x":2.42053, "y":1.9153, "heading":2.45293, "vx":2.9829, "vy":1.07492, "omega":1.67807, "ax":2.29325, "ay":5.86377, "alpha":-3.25292, "fx":[31.16827,17.61913,50.99096,56.25183], "fy":[104.058,106.82087,95.26475,92.82069]}, + {"t":2.11967, "x":2.4656, "y":1.93211, "heading":2.47814, "vx":3.01735, "vy":1.16301, "omega":1.62921, "ax":2.14794, "ay":5.84482, "alpha":-4.26429, "fx":[26.76429,7.97171,53.20796,58.19956], "fy":[105.11874,107.65247,93.50862,91.39473]}, + {"t":2.1347, "x":2.51116, "y":1.95024, "heading":2.50261, "vx":3.04962, "vy":1.2508, "omega":1.56515, "ax":1.96245, "ay":5.78675, "alpha":-5.63424, "fx":[21.41412,-5.02787,56.70335,60.43295], "fy":[106.13552,107.39213,90.55366,89.64224]}, + {"t":2.14972, "x":2.55719, "y":1.96968, "heading":2.52612, "vx":3.0791, "vy":1.33773, "omega":1.48052, "ax":1.75459, "ay":5.65592, "alpha":-7.38497, "fx":[15.47327,-20.83885,62.00708,62.73903], "fy":[106.88307,104.85016,85.46276,87.62657]}, + {"t":2.16474, "x":2.60364, "y":1.99041, "heading":2.54836, "vx":3.10545, "vy":1.42269, "omega":1.36959, "ax":1.61548, "ay":5.48002, "alpha":-8.85884, "fx":[11.0779,-32.46262,67.23269,64.06733], "fy":[106.96315,100.91165,78.99091,85.98853]}, + {"t":2.17976, "x":2.65048, "y":2.0124, "heading":2.56894, "vx":3.12972, "vy":1.50501, "omega":1.23651, "ax":1.57828, "ay":5.34628, "alpha":-9.35931, "fx":[9.59628,-34.89201,68.87229,63.80797], "fy":[106.20397,98.41727,74.19302,84.94055]}, + {"t":2.19478, "x":2.69767, "y":2.03561, "heading":2.58751, "vx":3.15343, "vy":1.58532, "omega":1.09592, "ax":1.56711, "ay":5.15839, "alpha":-9.40568, "fx":[9.44218,-32.95599,67.51879,62.61931], "fy":[104.11935,95.28135,68.58349,82.98705]}, + {"t":2.2098, "x":2.74521, "y":2.06001, "heading":2.60397, "vx":3.17697, "vy":1.6628, "omega":0.95464, "ax":1.43234, "ay":4.31894, "alpha":-9.83483, "fx":[8.93122,-30.02417,59.1977,59.35025], "fy":[94.9271,79.54919,46.39146,72.98774]}, + {"t":2.22482, "x":2.7931, "y":2.08547, "heading":2.61831, "vx":3.19848, "vy":1.72768, "omega":0.8069, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[ diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_3.traj b/src/main/deploy/choreo/E_RIGHT_PATH_3.traj index 7621730b..bd2c3368 100644 --- a/src/main/deploy/choreo/E_RIGHT_PATH_3.traj +++ b/src/main/deploy/choreo/E_RIGHT_PATH_3.traj @@ -4,30 +4,28 @@ "snapshot":{ "waypoints":[ {"x":3.6728932857513423, "y":2.9787795543670654, "heading":2.618314122167914, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.9501848220825195, "y":2.551724433898926, "heading":0.0, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":1.8529818058013916, "y":3.307283401489258, "heading":0.7217177742033876, "intervals":16, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.2258362770080566, "y":4.026000022888184, "heading":0.7217177742033876, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.8976240158081055, "y":3.8394596576690674, "heading":1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":2.9501848220825195, "y":2.551724433898926, "heading":0.0, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":2.232835292816162, "y":3.684377908706665, "heading":1.5707963267948966, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.2258362770080566, "y":4.026000022888184, "heading":1.5707963267948966, "intervals":13, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.8381152153015137, "y":3.927910327911377, "heading":1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":3, "to":3, "data":{"type":"MaxAngularVelocity", "props":{"max":0.0}}, "enabled":true}], "targetDt":0.05 }, "params":{ "waypoints":[ {"x":{"exp":"3.6728932857513428 m", "val":3.6728932857513423}, "y":{"exp":"2.9787795543670654 m", "val":2.9787795543670654}, "heading":{"exp":"2.6183141221679134 rad", "val":2.618314122167914}, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.9501848220825195 m", "val":2.9501848220825195}, "y":{"exp":"2.551724433898926 m", "val":2.551724433898926}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"1.8529818058013916 m", "val":1.8529818058013916}, "y":{"exp":"3.307283401489258 m", "val":3.307283401489258}, "heading":{"exp":"0.7217177742033876 rad", "val":0.7217177742033876}, "intervals":16, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.2258362770080566 m", "val":1.2258362770080566}, "y":{"exp":"4.026000022888184 m", "val":4.026000022888184}, "heading":{"exp":"0.7217177742033876 rad", "val":0.7217177742033876}, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.8976240158081055 m", "val":2.8976240158081055}, "y":{"exp":"3.8394596576690674 m", "val":3.8394596576690674}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"2.9501848220825195 m", "val":2.9501848220825195}, "y":{"exp":"2.551724433898926 m", "val":2.551724433898926}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"2.232835292816162 m", "val":2.232835292816162}, "y":{"exp":"3.684377908706665 m", "val":3.684377908706665}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.2258362770080566 m", "val":1.2258362770080566}, "y":{"exp":"4.026000022888184 m", "val":4.026000022888184}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":13, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.8381152153015137 m", "val":1.8381152153015137}, "y":{"exp":"3.927910327911377 m", "val":3.927910327911377}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":3, "to":3, "data":{"type":"MaxAngularVelocity", "props":{"max":{"exp":"0 rad / s", "val":0.0}}}, "enabled":true}], "targetDt":{ "exp":"0.05 s", @@ -36,108 +34,87 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,0.59084,1.06256,1.6068,2.63463], + "waypoints":[0.0,0.66638,1.23554,1.85262,2.29133], "samples":[ - {"t":0.0, "x":3.67289, "y":2.97878, "heading":2.61831, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.12946, "ay":-5.50084, "alpha":-4.10614, "fx":[-73.85816,-68.384,-39.00244,-31.68043], "fy":[-81.01363,-85.77522,-102.5311,-104.95119]}, - {"t":0.02363, "x":3.67202, "y":2.97724, "heading":2.61831, "vx":-0.07396, "vy":-0.13001, "omega":-0.09704, "ax":-3.24525, "ay":-5.42239, "alpha":-4.25527, "fx":[-76.61852,-70.28541,-40.42693,-33.472], "fy":[-78.3845,-84.21072,-101.96562,-104.37271]}, - {"t":0.04727, "x":3.66937, "y":2.97266, "heading":2.61602, "vx":-0.15066, "vy":-0.25816, "omega":-0.19761, "ax":-3.37657, "ay":-5.32852, "alpha":-4.42489, "fx":[-79.66304,-72.43791,-42.09798,-35.53886], "fy":[-75.26014,-82.35084,-101.2731,-103.66248]}, - {"t":0.0709, "x":3.66486, "y":2.96507, "heading":2.61135, "vx":-0.23046, "vy":-0.38409, "omega":-0.30219, "ax":-3.52633, "ay":-5.21477, "alpha":-4.61881, "fx":[-83.02767,-74.87686,-44.06434,-37.95881], "fy":[-71.49706,-80.12145,-100.41684,-102.77143]}, - {"t":0.09453, "x":3.65843, "y":2.95453, "heading":2.60421, "vx":-0.3138, "vy":-0.50733, "omega":-0.41135, "ax":-3.69803, "ay":-5.075, "alpha":-4.84123, "fx":[-86.74018,-77.64102,-46.38874,-40.83984], "fy":[-66.9027,-77.42433,-99.34532,-101.62485]}, - {"t":0.11817, "x":3.64998, "y":2.94113, "heading":2.59449, "vx":-0.4012, "vy":-0.62727, "omega":-0.52576, "ax":-3.89576, "ay":-4.90068, "alpha":-5.09613, "fx":[-90.8053,-80.77029,-49.15259,-44.33468], "fy":[-61.21926,-74.12823,-97.98454,-100.10461]}, - {"t":0.1418, "x":3.63941, "y":2.92493, "heading":2.58206, "vx":-0.49327, "vy":-0.7431, "omega":-0.6462, "ax":-4.12414, "ay":-4.67976, "alpha":-5.38569, "fx":[-95.17595,-84.30011,-52.46223,-48.6632], "fy":[-54.10722,-70.05665,-96.22561,-98.01586]}, - {"t":0.16544, "x":3.6266, "y":2.90606, "heading":2.56679, "vx":-0.59074, "vy":-0.8537, "omega":-0.77349, "ax":-4.38798, "ay":-4.39507, "alpha":-5.70664, "fx":[-99.70131,-88.24963,-56.45653,-54.14568], "fy":[-45.13796,-64.97229,-93.90398,-95.02112]}, - {"t":0.18907, "x":3.61141, "y":2.88466, "heading":2.54851, "vx":-0.69444, "vy":-0.95757, "omega":-0.90836, "ax":-4.69144, "ay":-4.02194, "alpha":-6.04252, "fx":[-104.04289,-92.59791,-61.31438,-61.24473], "fy":[-33.82097,-58.55978,-90.76407,-90.50363]}, - {"t":0.2127, "x":3.59369, "y":2.86091, "heading":2.52704, "vx":-0.80532, "vy":-1.05262, "omega":-1.05116, "ax":-5.036, "ay":-3.52454, "alpha":-6.3502, "fx":[-107.56757,-97.23963,-67.25636,-70.58036], "fy":[-19.71723,-50.41373,-86.39827,-83.27618]}, - {"t":0.23634, "x":3.57325, "y":2.83504, "heading":2.5022, "vx":-0.92434, "vy":-1.13592, "omega":-1.20124, "ax":-5.41516, "ay":-2.84973, "alpha":-6.54816, "fx":[-109.28776,-101.91046,-74.52105,-82.72231], "fy":[-2.7056,-40.05192,-80.14341,-70.9914]}, - {"t":0.25997, "x":3.5499, "y":2.8074, "heading":2.47381, "vx":-1.05232, "vy":-1.20327, "omega":-1.356, "ax":-5.79582, "ay":-1.92052, "alpha":-6.55505, "fx":[-108.02331,-106.08288,-83.26014,-96.9744], "fy":[16.6139,-26.99613,-70.92051,-49.36752]}, - {"t":0.2836, "x":3.52341, "y":2.77843, "heading":2.44176, "vx":-1.18929, "vy":-1.24866, "omega":-1.51092, "ax":-6.06706, "ay":-0.66489, "alpha":-6.47633, "fx":[-102.94558,-108.87866,-93.21029,-107.76118], "fy":[36.67484,-10.98294,-57.06863,-13.86169]}, - {"t":0.30724, "x":3.49361, "y":2.74873, "heading":2.40605, "vx":-1.33268, "vy":-1.26437, "omega":-1.66398, "ax":-6.03643, "ay":0.8298, "alpha":-6.61705, "fx":[-94.23942,-109.13538,-102.91779,-104.41924], "fy":[55.35388,7.67613,-36.53796,29.96683]}, - {"t":0.33087, "x":3.46042, "y":2.71908, "heading":2.36673, "vx":-1.47534, "vy":-1.24476, "omega":-1.82036, "ax":-5.66118, "ay":2.27882, "alpha":-6.67118, "fx":[-83.1652,-105.80909,-108.81868,-87.38717], "fy":[70.95611,27.7646,-8.46863,64.79603]}, - {"t":0.35451, "x":3.42397, "y":2.6903, "heading":2.3237, "vx":-1.60914, "vy":-1.1909, "omega":-1.97803, "ax":-5.0704, "ay":3.50775, "alpha":-6.07744, "fx":[-71.35707,-98.63749,-106.53265,-68.45708], "fy":[82.87209,47.30325,23.68734,84.80065]}, - {"t":0.37814, "x":3.38453, "y":2.66313, "heading":2.27696, "vx":-1.72897, "vy":-1.108, "omega":-2.12166, "ax":-4.37452, "ay":4.46169, "alpha":-5.04426, "fx":[-60.08922,-88.48241,-95.67878,-53.38682], "fy":[91.42256,64.35583,52.59081,95.19874]}, - {"t":0.40177, "x":3.34244, "y":2.63819, "heading":2.22681, "vx":-1.83236, "vy":-1.00256, "omega":-2.24088, "ax":-3.67527, "ay":5.13657, "alpha":-4.0107, "fx":[-50.04123,-76.889,-80.80698,-42.32375], "fy":[97.33264,77.87831,73.53602,100.73911]}, - {"t":0.42541, "x":3.29811, "y":2.61593, "heading":2.17385, "vx":-1.91922, "vy":-0.88116, "omega":-2.33566, "ax":-3.04546, "ay":5.58563, "alpha":-3.15449, "fx":[-41.42542,-65.29235,-66.28476,-34.20693], "fy":[101.34074,87.86931,86.95699,103.87267]}, - {"t":0.44904, "x":3.2519, "y":2.59667, "heading":2.11865, "vx":-1.99119, "vy":-0.74915, "omega":-2.41022, "ax":-2.50996, "ay":5.87827, "alpha":-2.4774, "fx":[-34.19199,-54.5822,-53.88405,-28.1165], "fy":[104.03971,94.93212,95.22272,105.75591]}, - {"t":0.47267, "x":3.20414, "y":2.58061, "heading":2.06169, "vx":-2.05051, "vy":-0.61023, "omega":-2.46877, "ax":-2.06482, "ay":6.06943, "alpha":-1.94076, "fx":[-28.18121,-45.1266,-43.76107,-23.41899], "fy":[105.8566,99.8081,100.34294,106.94972]}, - {"t":0.49631, "x":3.15511, "y":2.56788, "heading":2.00334, "vx":-2.09931, "vy":-0.46678, "omega":-2.51463, "ax":-1.6964, "ay":6.19573, "alpha":-1.50943, "fx":[-23.20701,-36.96975,-35.54914,-19.69536], "fy":[107.08345,103.13758,103.58761,107.74142]}, - {"t":0.51994, "x":3.10502, "y":2.55858, "heading":1.94391, "vx":-2.1394, "vy":-0.32035, "omega":-2.55031, "ax":-1.39023, "ay":6.28021, "alpha":-1.15743, "fx":[-19.09421,-30.00456,-28.82426,-16.66645], "fy":[107.91552,105.40008,105.69627,108.2867]}, - {"t":0.54357, "x":3.05407, "y":2.55276, "heading":1.88364, "vx":-2.17226, "vy":-0.17193, "omega":-2.57766, "ax":-1.13379, "ay":6.33734, "alpha":-0.86611, "fx":[-15.69113,-24.07436,-23.23398,-14.14247], "fy":[108.48247,106.93233,107.09612,108.67429]}, - {"t":0.56721, "x":3.00241, "y":2.55047, "heading":1.82272, "vx":-2.19905, "vy":-0.02215, "omega":-2.59813, "ax":-0.91705, "ay":6.37622, "alpha":-0.62193, "fx":[-12.87127,-19.0212,-18.51138,-11.99149], "fy":[108.87049,107.96453,108.03879,108.95697]}, - {"t":0.59084, "x":2.95018, "y":2.55172, "heading":1.76132, "vx":-2.22073, "vy":0.12854, "omega":-2.61283, "ax":-0.8133, "ay":6.38602, "alpha":-0.49008, "fx":[-11.54342,-16.44728,-16.24057,-11.10473], "fy":[108.92922,108.29641,108.31216,108.95959]}, - {"t":0.60769, "x":2.91266, "y":2.5548, "heading":1.7173, "vx":-2.23443, "vy":0.23612, "omega":-2.62109, "ax":-0.79833, "ay":6.38771, "alpha":-0.38685, "fx":[-11.6749,-15.57348,-15.55624,-11.51276], "fy":[108.8991,108.40999,108.39977,108.90375]}, - {"t":0.62454, "x":2.8749, "y":2.55968, "heading":1.67314, "vx":-2.24788, "vy":0.34374, "omega":-2.6276, "ax":-0.782, "ay":6.38934, "alpha":-0.27443, "fx":[-11.88385,-14.66569,-14.75557,-11.90111], "fy":[108.85888,108.51929,108.49771,108.84761]}, - {"t":0.64138, "x":2.83692, "y":2.56638, "heading":1.62888, "vx":-2.26105, "vy":0.45138, "omega":-2.63223, "ax":-0.76412, "ay":6.39087, "alpha":-0.15152, "fx":[-12.17886,-13.72184,-13.8269,-12.26204], "fy":[108.80693,108.62345,108.60471,108.79217]}, - {"t":0.65823, "x":2.79872, "y":2.57489, "heading":1.58453, "vx":-2.27393, "vy":0.55904, "omega":-2.63478, "ax":-0.74446, "ay":6.39223, "alpha":-0.01658, "fx":[-12.56971,-12.7391,-12.75655,-12.5869], "fy":[108.74118,108.72153,108.71886,108.73857]}, - {"t":0.67508, "x":2.76031, "y":2.58521, "heading":1.54014, "vx":-2.28647, "vy":0.66673, "omega":-2.63506, "ax":-0.72276, "ay":6.39336, "alpha":0.13229, "fx":[-13.06756,-11.71372,-11.52824,-12.86611], "fy":[108.65893,108.81244,108.83744,108.68814]}, - {"t":0.69192, "x":2.72168, "y":2.59735, "heading":1.49575, "vx":-2.29864, "vy":0.77444, "omega":-2.63283, "ax":-0.69868, "ay":6.39415, "alpha":0.29739, "fx":[-13.68532,-10.64061,-10.12242,-13.08897], "fy":[108.55671,108.89495,108.95662,108.64236]}, - {"t":0.70877, "x":2.68286, "y":2.61131, "heading":1.4514, "vx":-2.31042, "vy":0.88216, "omega":-2.62782, "ax":-0.67182, "ay":6.39446, "alpha":0.48155, "fx":[-14.43803,-9.51292,-8.51538,-13.24356], "fy":[108.43001,108.96756,109.07105,108.60283]}, - {"t":0.72562, "x":2.64384, "y":2.62708, "heading":1.40713, "vx":-2.32173, "vy":0.98989, "omega":-2.61971, "ax":-0.64168, "ay":6.39408, "alpha":0.68822, "fx":[-15.34346,-8.32134,-6.67808,-13.31648], "fy":[108.27289,109.02837,109.17318,108.57126]}, - {"t":0.74246, "x":2.60463, "y":2.64466, "heading":1.36299, "vx":-2.33254, "vy":1.09761, "omega":-2.60811, "ax":-0.60764, "ay":6.39273, "alpha":0.92168, "fx":[-16.42279,-7.05306,-4.57462,-13.29262], "fy":[108.07755,109.07491,109.25244,108.54937]}, - {"t":0.75931, "x":2.56525, "y":2.66406, "heading":1.31905, "vx":-2.34278, "vy":1.20531, "omega":-2.59258, "ax":-0.56889, "ay":6.39002, "alpha":1.18724, "fx":[-17.7016,-5.69023,-2.1603,-13.15478], "fy":[107.83358,109.10382,109.29372,108.53883]}, - {"t":0.77616, "x":2.5257, "y":2.68527, "heading":1.27538, "vx":-2.35236, "vy":1.31296, "omega":-2.57258, "ax":-0.52442, "ay":6.38538, "alpha":1.49155, "fx":[-19.21117,-4.2076,0.62101,-12.88322], "fy":[107.52697,109.11026,109.27535,108.54111]}, - {"t":0.79301, "x":2.486, "y":2.7083, "heading":1.23204, "vx":-2.3612, "vy":1.42053, "omega":-2.54746, "ax":-0.47287, "ay":6.37795, "alpha":1.84297, "fx":[-20.99012,-2.56865,3.84007,-12.45507], "fy":[107.1386,109.08693,109.16574,108.55726]}, - {"t":0.80985, "x":2.44615, "y":2.73313, "heading":1.18912, "vx":-2.36917, "vy":1.52798, "omega":-2.51641, "ax":-0.41246, "ay":6.36651, "alpha":2.25217, "fx":[-23.08666,-0.71928,7.58616,-11.84357], "fy":[106.64202,109.02237,108.91831,108.58764]}, - {"t":0.8267, "x":2.40618, "y":2.75978, "heading":1.14673, "vx":-2.37611, "vy":1.63524, "omega":-2.47846, "ax":-0.34075, "ay":6.3492, "alpha":2.73279, "fx":[-25.56124,1.42309,11.97126,-11.01723], "fy":[106.00015,108.8974,108.46355,108.63141]}, - {"t":0.84355, "x":2.3661, "y":2.78823, "heading":1.10497, "vx":-2.38186, "vy":1.7422, "omega":-2.43243, "ax":-0.25436, "ay":6.32317, "alpha":3.30233, "fx":[-28.48929,3.98907,17.13278,-9.93893], "fy":[105.16032,108.67805,107.69691,108.68584]}, - {"t":0.86039, "x":2.32594, "y":2.81848, "heading":1.06399, "vx":-2.38614, "vy":1.84873, "omega":-2.37679, "ax":-0.1485, "ay":6.28397, "alpha":3.98318, "fx":[-31.96213,7.19347,23.23007,-8.56543], "fy":[104.04747,108.29983,106.46147,108.7452]}, - {"t":0.87724, "x":2.28572, "y":2.85052, "heading":1.02395, "vx":-2.38864, "vy":1.95459, "omega":-2.30969, "ax":-0.01623, "ay":6.22459, "alpha":4.80322, "fx":[-36.07965,11.4031,30.42096,-6.84898], "fy":[102.55682,107.63034,104.52785,108.79898]}, - {"t":0.89409, "x":2.24548, "y":2.88433, "heading":0.98504, "vx":-2.38892, "vy":2.05946, "omega":-2.22877, "ax":0.15243, "ay":6.13407, "alpha":5.7938, "fx":[-40.91037,17.24934,38.77862,-4.74632], "fy":[100.55699,106.37672,101.59217,108.82927]}, - {"t":0.91093, "x":2.20525, "y":2.91989, "heading":0.94749, "vx":-2.38635, "vy":2.1628, "omega":-2.13116, "ax":0.36888, "ay":5.99731, "alpha":6.97253, "fx":[-46.32724,25.65348,48.02945,-2.25729], "fy":[97.96115,103.88907,97.39259,108.80739]}, - {"t":0.92778, "x":2.1651, "y":2.95718, "heading":0.91159, "vx":-2.38013, "vy":2.26384, "omega":-2.01369, "ax":0.62042, "ay":5.81208, "alpha":8.22908, "fx":[-51.42178,36.39428,56.8108,0.42921], "fy":[95.10304,99.32981,92.32103,108.69371]}, - {"t":0.94463, "x":2.12509, "y":2.99614, "heading":0.87766, "vx":-2.36968, "vy":2.36175, "omega":-1.87506, "ax":0.80786, "ay":5.64878, "alpha":9.08827, "fx":[-54.17867,43.80067,62.5451,2.79846], "fy":[93.18755,94.4893,88.20274,108.4572]}, - {"t":0.96147, "x":2.08528, "y":3.03673, "heading":0.84607, "vx":-2.35607, "vy":2.45692, "omega":-1.72195, "ax":0.907, "ay":5.53769, "alpha":9.49012, "fx":[-54.81643,45.96683,65.74914,4.81152], "fy":[92.27723,91.10727,85.31752,108.07625]}, - {"t":0.97832, "x":2.04572, "y":3.07891, "heading":0.81706, "vx":-2.34079, "vy":2.55021, "omega":-1.56207, "ax":0.97362, "ay":5.43097, "alpha":9.73659, "fx":[-54.34759,45.92992,67.90881,6.75288], "fy":[91.68538,87.6307,82.73843,107.46265]}, - {"t":0.99517, "x":2.00642, "y":3.12265, "heading":0.79075, "vx":-2.32439, "vy":2.6417, "omega":-1.39804, "ax":1.05155, "ay":5.26837, "alpha":10.03387, "fx":[-52.81286,45.83101,69.58741,8.94044], "fy":[90.92618,81.52886,79.66589,106.33313]}, - {"t":1.01202, "x":1.96741, "y":3.1679, "heading":0.7672, "vx":-2.30667, "vy":2.73046, "omega":-1.229, "ax":1.68362, "ay":3.59296, "alpha":16.82274, "fx":[-58.78224,75.45005,82.273,15.61091], "fy":[82.40054,-3.44853,62.22055,103.28801]}, - {"t":1.02886, "x":1.92879, "y":3.21441, "heading":0.74649, "vx":-2.27831, "vy":2.79099, "omega":-0.94559, "ax":1.47634, "ay":-1.20337, "alpha":24.97057, "fx":[-86.06516,30.02698,100.57969,55.90724], "fy":[-40.81542,-98.44178,-24.12552,81.5069]}, - {"t":1.04571, "x":1.89062, "y":3.26126, "heading":0.73056, "vx":-2.25344, "vy":2.77072, "omega":-0.52491, "ax":2.29501, "ay":-4.58453, "alpha":12.25796, "fx":[-35.55963,22.61031,80.18105,88.91793], "fy":[-97.38577,-103.92276,-69.13489,-41.48282]}, - {"t":1.06256, "x":1.85298, "y":3.30728, "heading":0.72172, "vx":-2.21477, "vy":2.69348, "omega":-0.3184, "ax":2.87787, "ay":-5.49198, "alpha":4.94439, "fx":[18.02477,37.49789,70.70014,69.58453], "fy":[-106.68147,-102.04233,-82.47602,-82.46831]}, - {"t":1.09657, "x":1.77931, "y":3.39573, "heading":0.71089, "vx":-2.11688, "vy":2.50667, "omega":-0.15022, "ax":3.55395, "ay":-5.27549, "alpha":2.52745, "fx":[47.21399,52.50114,71.12096,70.97059], "fy":[-98.1139,-95.61297,-82.68161,-82.52976]}, - {"t":1.13059, "x":1.70936, "y":3.47794, "heading":0.70578, "vx":-1.99599, "vy":2.32722, "omega":-0.06425, "ax":3.83043, "ay":-5.13333, "alpha":1.51811, "fx":[58.01189,59.82366,71.38204,71.40046], "fy":[-92.49876,-91.44295,-82.73005,-82.59422]}, - {"t":1.1646, "x":1.64368, "y":3.55413, "heading":0.70359, "vx":-1.8657, "vy":2.15261, "omega":-0.01261, "ax":3.97741, "ay":-5.04339, "alpha":0.96947, "fx":[63.38842,64.07378,71.55556,71.6009], "fy":[-89.09986,-88.6632,-82.74121,-82.64252]}, - {"t":1.19862, "x":1.58252, "y":3.62443, "heading":0.70316, "vx":-1.73041, "vy":1.98106, "omega":0.02037, "ax":4.06809, "ay":-4.98249, "alpha":0.62443, "fx":[66.56817,66.82743,71.67723,71.71551], "fy":[-86.87626,-86.70675,-82.74209,-82.67762]}, - {"t":1.23263, "x":1.52601, "y":3.68894, "heading":0.70386, "vx":-1.59203, "vy":1.81158, "omega":0.04161, "ax":4.12948, "ay":-4.93876, "alpha":0.38719, "fx":[68.66037,68.74846,71.76567,71.7903], "fy":[-85.3194,-85.26434,-82.74073,-82.70294]}, - {"t":1.26665, "x":1.47425, "y":3.7477, "heading":0.70527, "vx":-1.45156, "vy":1.64358, "omega":0.05478, "ax":4.17373, "ay":-4.90592, "alpha":0.21397, "fx":[70.13948,70.16106,71.83156,71.84402], "fy":[-84.17119,-84.16092,-82.73973,-82.72105]}, - {"t":1.30066, "x":1.42729, "y":3.80077, "heading":0.70713, "vx":-1.30959, "vy":1.47671, "omega":0.06206, "ax":4.20714, "ay":-4.88038, "alpha":0.08191, "fx":[71.24036,71.24137,71.88152,71.88544], "fy":[-83.2899,-83.29167,-82.73986,-82.73379]}, - {"t":1.33468, "x":1.38518, "y":3.84818, "heading":0.70925, "vx":-1.16649, "vy":1.3107, "omega":0.06484, "ax":4.23323, "ay":-4.85996, "alpha":-0.02214, "fx":[72.09189,72.09302,71.91989,71.91911], "fy":[-82.59204,-82.59042,-82.74122,-82.74253]}, - {"t":1.36869, "x":1.34795, "y":3.88995, "heading":0.71145, "vx":-1.02249, "vy":1.14539, "omega":0.06409, "ax":4.25417, "ay":-4.84328, "alpha":-0.10623, "fx":[72.77048,72.78087,71.94969,71.94752], "fy":[-82.02553,-82.01351,-82.74363,-82.7483]}, - {"t":1.40271, "x":1.31563, "y":3.92611, "heading":0.71363, "vx":-0.87778, "vy":0.98064, "omega":0.06048, "ax":4.27134, "ay":-4.82939, "alpha":-0.1756, "fx":[73.3242,73.34755,71.97309,71.97211], "fy":[-81.55628,-81.53103,-82.74683,-82.75188]}, - {"t":1.43672, "x":1.28824, "y":3.95667, "heading":0.71569, "vx":-0.73249, "vy":0.81637, "omega":0.0545, "ax":4.28567, "ay":-4.81765, "alpha":-0.23382, "fx":[73.78471,73.82223,71.99169,71.99371], "fy":[-81.16114,-81.12178,-82.75053,-82.75392]}, - {"t":1.47074, "x":1.2658, "y":3.98165, "heading":0.71754, "vx":-0.58672, "vy":0.65249, "omega":0.04655, "ax":4.29782, "ay":-4.8076, "alpha":-0.28337, "fx":[74.17374,74.22555,72.00674,72.01283], "fy":[-80.82384,-80.77036,-82.75446,-82.75493]}, - {"t":1.50475, "x":1.24833, "y":4.00107, "heading":0.71913, "vx":-0.44052, "vy":0.48896, "omega":0.03691, "ax":4.30825, "ay":-4.7989, "alpha":-0.32606, "fx":[74.50664,74.57252,72.01919,72.02978], "fy":[-80.53263,-80.46529,-82.75836,-82.75532]}, - {"t":1.53877, "x":1.23584, "y":4.01492, "heading":0.72038, "vx":-0.29398, "vy":0.32573, "omega":0.02582, "ax":4.31729, "ay":-4.79129, "alpha":-0.36322, "fx":[74.79455,74.87431,72.0298,72.04472], "fy":[-80.27884,-80.19783,-82.762,-82.75544]}, - {"t":1.57279, "x":1.22834, "y":4.02323, "heading":0.72126, "vx":-0.14712, "vy":0.16275, "omega":0.01347, "ax":4.32521, "ay":-4.78459, "alpha":-0.39586, "fx":[75.04578,75.13942,72.03918,72.05775], "fy":[-80.05594,-79.96124,-82.76517,-82.75559]}, - {"t":1.6068, "x":1.22584, "y":4.026, "heading":0.72172, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.33867, "ay":-0.70718, "alpha":3.16104, "fx":[108.84833,104.11317,109.1741,109.14027], "fy":[-13.56689,-34.66218,-11.23851,11.35165]}, - {"t":1.64106, "x":1.22956, "y":4.02558, "heading":0.72172, "vx":0.21717, "vy":-0.02423, "omega":0.1083, "ax":6.33813, "ay":-0.70712, "alpha":3.16022, "fx":[108.8359,104.10606,109.16598,109.1312], "fy":[-13.56469,-34.65318,-11.23781,11.34433]}, - {"t":1.67532, "x":1.24072, "y":4.02434, "heading":0.72543, "vx":0.43432, "vy":-0.04846, "omega":0.21657, "ax":6.33748, "ay":-0.7071, "alpha":3.15963, "fx":[108.80761,104.10459,109.16393,109.11902], "fy":[-13.67309,-34.6227,-11.1651,11.35071]}, - {"t":1.70958, "x":1.25932, "y":4.02226, "heading":0.73285, "vx":0.65145, "vy":-0.07268, "omega":0.32483, "ax":6.3367, "ay":-0.70713, "alpha":3.15931, "fx":[108.76265,104.10867,109.16746,109.10338], "fy":[-13.89162,-34.56985,-11.02046,11.36978]}, - {"t":1.74385, "x":1.28536, "y":4.01936, "heading":0.74398, "vx":0.86855, "vy":-0.09691, "omega":0.43307, "ax":6.33576, "ay":-0.7072, "alpha":3.15938, "fx":[108.69973,104.11826,109.1758,109.08386], "fy":[-14.21957,-34.49294,-10.80396,11.39964]}, - {"t":1.77811, "x":1.31883, "y":4.01562, "heading":0.75881, "vx":1.08562, "vy":-0.12114, "omega":0.54131, "ax":6.33459, "ay":-0.7073, "alpha":3.16001, "fx":[108.61694,104.13336,109.18784,109.05989], "fy":[-14.65582,-34.38951,-10.51571,11.43746]}, - {"t":1.81237, "x":1.35974, "y":4.01106, "heading":0.77736, "vx":1.30265, "vy":-0.14537, "omega":0.64958, "ax":6.33312, "ay":-0.70741, "alpha":3.16144, "fx":[108.51169,104.15382,109.20201,109.03057], "fy":[-15.19873,-34.25632,-10.15584,11.47947]}, - {"t":1.84663, "x":1.40809, "y":4.00566, "heading":0.79962, "vx":1.51963, "vy":-0.16961, "omega":0.75789, "ax":6.33124, "ay":-0.70752, "alpha":3.16392, "fx":[108.38038,104.17912,109.21606,108.99446], "fy":[-15.84588,-34.08935,-9.72454,11.52085]}, - {"t":1.88089, "x":1.46387, "y":3.99944, "heading":0.82558, "vx":1.73655, "vy":-0.19385, "omega":0.86629, "ax":6.32876, "ay":-0.70759, "alpha":3.16779, "fx":[108.2179,104.20785,109.22667,108.94901], "fy":[-16.59375,-33.88377,-9.22207,11.55577]}, - {"t":1.91515, "x":1.52708, "y":3.99238, "heading":0.85526, "vx":1.95338, "vy":-0.21809, "omega":0.97482, "ax":6.32538, "ay":-0.70757, "alpha":3.17339, "fx":[108.01651,104.23682,109.2286,108.88952], "fy":[-17.43731,-33.63389,-8.64869,11.57733]}, - {"t":1.94941, "x":1.59772, "y":3.98449, "heading":0.88866, "vx":2.17009, "vy":-0.24233, "omega":1.08355, "ax":6.32052, "ay":-0.70738, "alpha":3.18119, "fx":[107.76302,104.2588,109.21278,108.80653], "fy":[-18.36935,-33.33297,-8.00454,11.57786]}, - {"t":1.98367, "x":1.67578, "y":3.97578, "heading":0.92578, "vx":2.38664, "vy":-0.26657, "omega":1.19254, "ax":6.31297, "ay":-0.70682, "alpha":3.19191, "fx":[107.43105,104.25654,109.16096,108.67891], "fy":[-19.37939,-32.97297,-7.28901,11.55]}, - {"t":2.01793, "x":1.76125, "y":3.96623, "heading":0.96664, "vx":2.60293, "vy":-0.29078, "omega":1.30189, "ax":6.29956, "ay":-0.7055, "alpha":3.20755, "fx":[106.95446,104.18256,109.02803,108.4501], "fy":[-20.45134,-32.54415,-6.49804,11.49211]}, - {"t":2.05219, "x":1.85413, "y":3.95585, "heading":1.01125, "vx":2.81876, "vy":-0.31496, "omega":1.41179, "ax":6.26871, "ay":-0.70197, "alpha":3.23724, "fx":[106.09351,103.85796,108.65442,107.91028], "fy":[-21.55776,-32.03783,-5.60835,11.4427]}, - {"t":2.08646, "x":1.95438, "y":3.94465, "heading":1.05961, "vx":3.03353, "vy":-0.33901, "omega":1.5227, "ax":6.11912, "ay":-0.68383, "alpha":3.38762, "fx":[102.73239,101.70282,106.68852,105.21399], "fy":[-22.65131,-31.54354,-4.34649,12.01421]}, - {"t":2.12072, "x":2.0619, "y":3.93263, "heading":1.11178, "vx":3.24318, "vy":-0.36243, "omega":1.63876, "ax":-6.13652, "ay":0.69433, "alpha":-2.5629, "fx":[-103.10147,-102.71418,-106.25066,-105.45559], "fy":[20.65916,26.79742,5.29863,-5.51371]}, - {"t":2.15498, "x":2.16942, "y":3.92062, "heading":1.16793, "vx":3.03294, "vy":-0.33865, "omega":1.55096, "ax":-6.2773, "ay":0.70546, "alpha":-3.00794, "fx":[-105.55756,-104.74776,-108.69216,-108.103], "fy":[24.14487,28.95491,3.4383,-8.53967]}, - {"t":2.18924, "x":2.26965, "y":3.90943, "heading":1.22107, "vx":2.81787, "vy":-0.31448, "omega":1.4479, "ax":-6.30364, "ay":0.70721, "alpha":-3.11948, "fx":[-105.81358,-105.2692,-109.17217,-108.6374], "fy":[25.82781,28.88852,2.29411,-8.89288]}, - {"t":2.2235, "x":2.36249, "y":3.89907, "heading":1.27067, "vx":2.6019, "vy":-0.29025, "omega":1.34102, "ax":-6.31448, "ay":0.70758, "alpha":-3.177, "fx":[-105.77654,-105.58801,-109.37842,-108.88678], "fy":[27.10383,28.49902,1.32667,-8.78642]}, - {"t":2.25776, "x":2.44793, "y":3.88955, "heading":1.31662, "vx":2.38556, "vy":-0.266, "omega":1.23218, "ax":-6.32034, "ay":0.70748, "alpha":-3.21316, "fx":[-105.66026,-105.83458,-109.49041,-109.04315], "fy":[28.1509,28.01478,0.47288,-8.50227]}, - {"t":2.29202, "x":2.52595, "y":3.88085, "heading":1.35883, "vx":2.16902, "vy":-0.24177, "omega":1.12209, "ax":-6.32402, "ay":0.70718, "alpha":-3.2376, "fx":[-105.52293,-106.0418,-109.5576,-109.1567], "fy":[29.02856,27.50617,-0.28652,-8.13271]}, - {"t":2.32628, "x":2.59655, "y":3.87298, "heading":1.39728, "vx":1.95235, "vy":-0.21754, "omega":1.01117, "ax":-6.32658, "ay":0.70679, "alpha":-3.25449, "fx":[-105.38628,-106.22136,-109.59973,-109.24575], "fy":[29.76785,27.00484,-0.96058,-7.72316]}, - {"t":2.36054, "x":2.65973, "y":3.86594, "heading":1.43192, "vx":1.73559, "vy":-0.19332, "omega":0.89966, "ax":-6.32849, "ay":0.70638, "alpha":-3.26617, "fx":[-105.25958,-106.37832,-109.6266,-109.31843], "fy":[30.38956,26.52845,-1.55505,-7.30193]}, - {"t":2.39481, "x":2.71548, "y":3.85973, "heading":1.46275, "vx":1.51877, "vy":-0.16912, "omega":0.78776, "ax":-6.32998, "ay":0.70598, "alpha":-3.27418, "fx":[-105.14684,-106.51523,-109.64377,-109.37884], "fy":[30.90965,26.0882,-2.07429,-6.88932]}, - {"t":2.42907, "x":2.7638, "y":3.85435, "heading":1.48974, "vx":1.3019, "vy":-0.14493, "omega":0.67558, "ax":-6.33119, "ay":0.70563, "alpha":-3.27961, "fx":[-105.04955,-106.63355,-109.65477,-109.42934], "fy":[31.34106,25.69188,-2.52195,-6.50097]}, - {"t":2.46333, "x":2.80468, "y":3.8498, "heading":1.51288, "vx":1.08499, "vy":-0.12076, "omega":0.56322, "ax":-6.3322, "ay":0.70532, "alpha":-3.28332, "fx":[-104.96799,-106.73423,-109.66192,-109.47147], "fy":[31.69457,25.34509,-2.90118,-6.14935]}, - {"t":2.49759, "x":2.83814, "y":3.84608, "heading":1.53218, "vx":0.86804, "vy":-0.09659, "omega":0.45073, "ax":-6.33304, "ay":0.70507, "alpha":-3.28595, "fx":[-104.9018,-106.81795,-109.66689,-109.50633], "fy":[31.9791,25.05204,-3.21473,-5.84452]}, - {"t":2.53185, "x":2.86416, "y":3.84318, "heading":1.54762, "vx":0.65106, "vy":-0.07244, "omega":0.33815, "ax":-6.33375, "ay":0.70487, "alpha":-3.28802, "fx":[-104.85039,-106.88521,-109.67083,-109.53478], "fy":[32.20195,24.81587,-3.46494,-5.5945]}, - {"t":2.56611, "x":2.88275, "y":3.84111, "heading":1.55921, "vx":0.43406, "vy":-0.04829, "omega":0.2255, "ax":-6.33435, "ay":0.70472, "alpha":-3.28991, "fx":[-104.81314,-106.93642,-109.67461,-109.55751], "fy":[32.36888,24.63894,-3.6537,-5.40556]}, - {"t":2.60037, "x":2.89391, "y":3.83987, "heading":1.56693, "vx":0.21704, "vy":-0.02414, "omega":0.11278, "ax":-6.33484, "ay":0.70463, "alpha":-3.2919, "fx":[-104.78954,-106.97189,-109.67883,-109.57505], "fy":[32.4842,24.52298,-3.78247,-5.28236]}, - {"t":2.63463, "x":2.89762, "y":3.83946, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":3.67289, "y":2.97878, "heading":2.61831, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.42941, "ay":-5.44705, "alpha":-1.35023, "fx":[-64.79624,-63.66172,-52.59453,-52.28035], "fy":[-88.51856,-89.36133,-96.29093,-96.43991]}, + {"t":0.03029, "x":3.67132, "y":2.97628, "heading":2.61831, "vx":-0.10388, "vy":-0.16499, "omega":-0.0409, "ax":-3.49791, "ay":-5.40047, "alpha":-1.42396, "fx":[-66.3419,-64.97455,-53.44354,-53.23399], "fy":[-87.34485,-88.39407,-95.80597,-95.89684]}, + {"t":0.06058, "x":3.66657, "y":2.96881, "heading":2.61708, "vx":-0.20983, "vy":-0.32857, "omega":-0.08403, "ax":-3.58119, "ay":-5.34196, "alpha":-1.51443, "fx":[-68.2147,-66.56126,-54.48318,-54.40123], "fy":[-85.86353,-87.1842,-95.19852,-95.21462]}, + {"t":0.09087, "x":3.65857, "y":2.9564, "heading":2.61453, "vx":-0.3183, "vy":-0.49038, "omega":-0.1299, "ax":-3.68449, "ay":-5.26641, "alpha":-1.62792, "fx":[-70.5302,-68.51094,-55.78057,-55.86651], "fy":[-83.93758,-85.6337,-94.41897,-94.33041]}, + {"t":0.12116, "x":3.64724, "y":2.93913, "heading":2.6106, "vx":-0.42991, "vy":-0.6499, "omega":-0.17921, "ax":-3.81573, "ay":-5.16543, "alpha":-1.77427, "fx":[-73.46091,-70.95418,-57.43851,-57.76412], "fy":[-81.33917,-83.58552,-93.38701,-93.13804]}, + {"t":0.15145, "x":3.63247, "y":2.91708, "heading":2.60517, "vx":-0.54548, "vy":-0.80636, "omega":-0.23295, "ax":-3.98745, "ay":-5.02428, "alpha":-1.96953, "fx":[-77.27088,-74.08785,-59.6224,-60.32048], "fy":[-77.66462,-80.77371,-91.96417,-91.44408]}, + {"t":0.18174, "x":3.61411, "y":2.89035, "heading":2.59811, "vx":-0.66626, "vy":-0.95854, "omega":-0.29261, "ax":-4.22028, "ay":-4.81501, "alpha":-2.24124, "fx":[-82.36698,-78.21564,-62.61445,-63.94576], "fy":[-72.14111,-76.71622,-89.89153,-88.85885]}, + {"t":0.21203, "x":3.592, "y":2.85911, "heading":2.58925, "vx":-0.7941, "vy":-1.10439, "omega":-0.3605, "ax":-4.54919, "ay":-4.47868, "alpha":-2.63873, "fx":[-89.33379,-83.80438,-66.93203,-69.45135], "fy":[-63.14892,-70.46471,-86.62984,-84.48109]}, + {"t":0.24232, "x":3.56586, "y":2.8236, "heading":2.57833, "vx":-0.93189, "vy":-1.24005, "omega":-0.44043, "ax":-5.03131, "ay":-3.8743, "alpha":-3.2464, "fx":[-98.63882,-91.48947,-73.60315,-78.59344], "fy":[-46.98695,-59.97045,-80.8763,-75.76924]}, + {"t":0.27261, "x":3.53532, "y":2.78426, "heading":2.56499, "vx":-1.08429, "vy":-1.3574, "omega":-0.53876, "ax":-5.71771, "ay":-2.61483, "alpha":-4.1419, "fx":[-107.95762,-101.47056,-84.75928,-94.83875], "fy":[-15.41923,-40.46546,-68.75595,-53.26968]}, + {"t":0.3029, "x":3.49986, "y":2.74195, "heading":2.54867, "vx":-1.25748, "vy":-1.43661, "omega":-0.66422, "ax":-6.16992, "ay":0.30125, "alpha":-5.42545, "fx":[-101.68578,-109.01504,-102.7199,-106.37336], "fy":[38.92114,-2.17589,-35.60891,19.36041]}, + {"t":0.33319, "x":3.45894, "y":2.69857, "heading":2.52855, "vx":-1.44436, "vy":-1.42748, "omega":-0.82855, "ax":-4.45087, "ay":4.27336, "alpha":-5.64126, "fx":[-65.34357,-93.61414,-95.7833,-48.09107], "fy":[87.2115,55.70171,50.58593,97.25558]}, + {"t":0.36348, "x":3.41315, "y":2.65729, "heading":2.50345, "vx":-1.57918, "vy":-1.29804, "omega":-0.99943, "ax":-1.87443, "ay":6.04455, "alpha":-3.35688, "fx":[-29.31581,-53.74834,-36.81734,-7.65291], "fy":[105.18388,94.92752,102.38677,108.76594]}, + {"t":0.39377, "x":3.36445, "y":2.62075, "heading":2.47318, "vx":-1.63596, "vy":-1.11495, "omega":-1.10111, "ax":-0.3601, "ay":6.38063, "alpha":-2.16507, "fx":[-7.00842,-21.98337,-5.02653,9.5173], "fy":[109.13189,107.05047,109.06922,108.87907]}, + {"t":0.42406, "x":3.31473, "y":2.5899, "heading":2.43983, "vx":-1.64687, "vy":-0.92168, "omega":-1.16669, "ax":0.46246, "ay":6.40074, "alpha":-1.47365, "fx":[6.3608,-2.92546,9.7326,18.29743], "fy":[109.27921,109.38173,108.94462,107.89347]}, + {"t":0.45435, "x":3.26506, "y":2.56492, "heading":2.40449, "vx":-1.63286, "vy":-0.7278, "omega":-1.21132, "ax":0.95492, "ay":6.35921, "alpha":-1.04134, "fx":[14.87867,8.73643,17.84459,23.51202], "fy":[108.5212,109.16123,108.02492,106.96608]}, + {"t":0.48464, "x":3.21604, "y":2.54579, "heading":2.3678, "vx":-1.60393, "vy":-0.53518, "omega":-1.24287, "ax":1.27713, "ay":6.30982, "alpha":-0.75161, "fx":[20.65948,16.38196,22.92351,26.92954], "fy":[107.62234,108.33963,107.13405,106.21659]}, + {"t":0.51493, "x":3.16804, "y":2.53248, "heading":2.33015, "vx":-1.56525, "vy":-0.34406, "omega":-1.26563, "ax":1.50263, "ay":6.2645, "alpha":-0.54573, "fx":[24.78858,21.72016,26.40311,29.32557], "fy":[106.78543,107.44122,106.37974,105.62293]}, + {"t":0.54522, "x":3.12132, "y":2.52493, "heading":2.29182, "vx":-1.51973, "vy":-0.15431, "omega":-1.28216, "ax":1.66864, "ay":6.22534, "alpha":-0.39255, "fx":[27.85739,25.64004,28.94586,31.08927], "fy":[106.05588,106.60711,105.75263,105.14953]}, + {"t":0.57551, "x":3.07606, "y":2.52311, "heading":2.25298, "vx":-1.46919, "vy":0.03426, "omega":-1.29405, "ax":1.79569, "ay":6.19199, "alpha":-0.27438, "fx":[30.20951,28.63475,30.89586,32.43626], "fy":[105.43344,105.86792,105.22728,104.767]}, + {"t":0.6058, "x":3.03238, "y":2.52699, "heading":2.21378, "vx":-1.4148, "vy":0.22181, "omega":-1.30236, "ax":1.89591, "ay":6.16356, "alpha":-0.18057, "fx":[32.05629,30.99547,32.44834,33.49535], "fy":[104.9057,105.22162,104.78089,104.45338]}, + {"t":0.63609, "x":2.99039, "y":2.53653, "heading":2.17433, "vx":-1.35737, "vy":0.40851, "omega":-1.30783, "ax":1.97693, "ay":6.1392, "alpha":-0.10435, "fx":[33.53413,32.90369,33.72184,34.3481], "fy":[104.45837,104.65743,104.39571,104.1926]}, + {"t":0.66638, "x":2.95018, "y":2.55172, "heading":2.13472, "vx":-1.29749, "vy":0.59446, "omega":-1.31099, "ax":1.9906, "ay":6.13141, "alpha":-0.06082, "fx":[33.82092,33.4371,33.89867,34.28131], "fy":[104.30739,104.4301,104.28038,104.15619]}, + {"t":0.68827, "x":2.92226, "y":2.56621, "heading":2.10602, "vx":-1.25392, "vy":0.72868, "omega":-1.31233, "ax":1.94601, "ay":6.14488, "alpha":-0.02013, "fx":[33.09319,32.96063,33.1089,33.24136], "fy":[104.52545,104.56699,104.51985,104.47813]}, + {"t":0.71016, "x":2.89528, "y":2.58363, "heading":2.07729, "vx":-1.21132, "vy":0.8632, "omega":-1.31277, "ax":1.89494, "ay":6.15984, "alpha":0.02635, "fx":[32.23584,32.4168,32.22888,32.0478], "fy":[104.77573,104.72034,104.77875,104.83383]}, + {"t":0.73205, "x":2.86921, "y":2.604, "heading":2.04856, "vx":-1.16984, "vy":0.99804, "omega":-1.31219, "ax":1.83588, "ay":6.17654, "alpha":0.07993, "fx":[31.21704,31.78874,31.23883,30.66647], "fy":[105.06378,104.89363,105.06015,105.22726]}, + {"t":0.75394, "x":2.84404, "y":2.62733, "heading":2.01983, "vx":-1.12965, "vy":1.13325, "omega":-1.31044, "ax":1.76682, "ay":6.19525, "alpha":0.14235, "fx":[29.9939,31.05384,30.11268,29.05228], "fy":[105.39611,105.09131,105.36771,105.66247]}, + {"t":0.77583, "x":2.81974, "y":2.65362, "heading":1.99114, "vx":-1.09097, "vy":1.26887, "omega":-1.30732, "ax":1.68504, "ay":6.21627, "alpha":0.21596, "fx":[28.50723,30.18111,28.81536,27.14443], "fy":[105.78023,105.31902,105.7057,106.14314]}, + {"t":0.79772, "x":2.79626, "y":2.68289, "heading":1.96253, "vx":-1.05408, "vy":1.40495, "omega":-1.3026, "ax":1.58671, "ay":6.23994, "alpha":0.30401, "fx":[26.67318,29.12689,27.29864,24.85928], "fy":[106.22428,105.58396,106.07905,106.67141]}, + {"t":0.81961, "x":2.77357, "y":2.71514, "heading":1.93401, "vx":-1.01935, "vy":1.54154, "omega":-1.29594, "ax":1.46637, "ay":6.26656, "alpha":0.41112, "fx":[24.36912,27.82777,25.49453,22.07882], "fy":[106.73578,105.89538,106.493,107.24545]}, + {"t":0.8415, "x":2.7516, "y":2.75039, "heading":1.90564, "vx":-0.98725, "vy":1.67872, "omega":-1.28694, "ax":1.31591, "ay":6.29624, "alpha":0.54412, "fx":[21.40905,26.18805,23.30422,18.63202], "fy":[107.31793,106.26489,106.95224,107.85396]}, + {"t":0.8634, "x":2.73031, "y":2.78864, "heading":1.87747, "vx":-0.95844, "vy":1.81655, "omega":-1.27503, "ax":1.12285, "ay":6.32856, "alpha":0.71343, "fx":[17.49852,24.05664,20.57893,14.26341], "fy":[107.95945,106.70629,107.45842,108.46393]}, + {"t":0.88529, "x":2.7096, "y":2.82992, "heading":1.84956, "vx":-0.93386, "vy":1.95509, "omega":-1.25941, "ax":0.86704, "ay":6.36157, "alpha":0.9358, "fx":[12.14763,21.18084,17.08506,8.57916], "fy":[108.60567,107.23291,108.0034,108.99214]}, + {"t":0.90718, "x":2.68936, "y":2.87425, "heading":1.82199, "vx":-0.91488, "vy":2.09435, "omega":-1.23893, "ax":0.5143, "ay":6.38905, "alpha":1.23978, "fx":[4.49468,17.1066,12.43702,0.95377], "fy":[109.07215,107.84529,108.55053,109.23577]}, + {"t":0.92907, "x":2.66946, "y":2.92162, "heading":1.79487, "vx":-0.90362, "vy":2.23421, "omega":-1.21179, "ax":0.00322, "ay":6.39223, "alpha":1.67741, "fx":[-7.05713,10.93837,5.95977,-9.6222], "fy":[108.76556,108.47877,108.9799,108.6958]}, + {"t":0.95096, "x":2.64968, "y":2.97206, "heading":1.76834, "vx":-0.90355, "vy":2.37414, "omega":-1.17507, "ax":-0.7809, "ay":6.31265, "alpha":2.34766, "fx":[-25.48647,0.6848,-3.60757,-24.72217], "fy":[105.71227,108.76126,108.91287,106.11928]}, + {"t":0.97285, "x":2.62971, "y":3.02555, "heading":1.74262, "vx":-0.92065, "vy":2.51233, "omega":-1.12368, "ax":-2.03968, "ay":5.96046, "alpha":3.39656, "fx":[-55.02758,-18.72957,-18.74462,-46.27568], "fy":[93.38113,106.65596,107.08671,98.41909]}, + {"t":0.99474, "x":2.60907, "y":3.08197, "heading":1.71802, "vx":-0.9653, "vy":2.6428, "omega":-1.04932, "ax":-3.95677, "ay":4.77902, "alpha":4.58691, "fx":[-91.5817,-59.59896,-44.00545,-74.02779], "fy":[57.43055,89.36667,98.97956,79.38232]}, + {"t":1.01663, "x":2.58699, "y":3.14097, "heading":1.69505, "vx":-1.05191, "vy":2.74742, "omega":-0.94891, "ax":-5.79941, "ay":1.96933, "alpha":5.5506, "fx":[-108.19438,-105.78524,-81.62452,-98.98099], "fy":[3.12001,16.03308,70.50213,44.33554]}, + {"t":1.03852, "x":2.56257, "y":3.20158, "heading":1.67428, "vx":-1.17887, "vy":2.79053, "omega":-0.82741, "ax":-6.08639, "ay":-1.0138, "alpha":5.30411, "fx":[-102.41179,-96.07958,-107.10233,-108.517], "fy":[-36.15216,-49.16241,12.57479,3.76177]}, + {"t":1.06041, "x":2.53531, "y":3.26243, "heading":1.65617, "vx":-1.3121, "vy":2.76834, "omega":-0.71129, "ax":-5.59492, "ay":-2.8384, "alpha":3.99685, "fx":[-92.63835,-80.46448,-102.24913,-105.31997], "fy":[-57.24897,-72.89496,-35.67902,-27.29857]}, + {"t":1.0823, "x":2.50524, "y":3.32235, "heading":1.6406, "vx":-1.43458, "vy":2.7062, "omega":-0.6238, "ax":-5.05927, "ay":-3.8062, "alpha":3.18088, "fx":[-84.66308,-70.86171,-90.39607,-98.30588], "fy":[-68.8117,-82.71714,-60.36365,-47.07733]}, + {"t":1.10419, "x":2.47263, "y":3.38068, "heading":1.62694, "vx":-1.54533, "vy":2.62288, "omega":-0.55417, "ax":-4.64625, "ay":-4.34761, "alpha":2.68253, "fx":[-78.72257,-64.84818,-81.0115,-91.54304], "fy":[-75.73293,-87.76599,-72.86883,-59.43885]}, + {"t":1.12608, "x":2.43769, "y":3.43705, "heading":1.61481, "vx":-1.64704, "vy":2.52771, "omega":-0.49545, "ax":-4.34064, "ay":-4.67977, "alpha":2.34627, "fx":[-74.2808,-60.80938,-74.31369,-85.92829], "fy":[-80.22674,-90.77154,-79.92596,-67.48217]}, + {"t":1.14797, "x":2.40059, "y":3.49127, "heading":1.60396, "vx":-1.74206, "vy":2.42527, "omega":-0.44409, "ax":-4.11094, "ay":-4.90006, "alpha":2.10395, "fx":[-70.88267,-57.9308,-69.4718,-81.41841], "fy":[-83.33882,-92.74493,-84.32451,-72.98597]}, + {"t":1.16986, "x":2.36147, "y":3.54318, "heading":1.59424, "vx":-1.83205, "vy":2.318, "omega":-0.39803, "ax":-3.93385, "ay":-5.0552, "alpha":1.92139, "fx":[-68.21731,-55.78219,-65.86071,-77.79449], "fy":[-85.60481,-94.13251,-87.28334,-76.92919]}, + {"t":1.19176, "x":2.32042, "y":3.59271, "heading":1.58553, "vx":-1.91816, "vy":2.20734, "omega":-0.35597, "ax":-3.7939, "ay":-5.16965, "alpha":1.77925, "fx":[-66.07844,-54.11972,-63.08363,-74.85092], "fy":[-87.32095,-95.15836,-89.39159,-79.86613]}, + {"t":1.21365, "x":2.27753, "y":3.63979, "heading":1.57774, "vx":-2.00122, "vy":2.09417, "omega":-0.31702, "ax":-3.68086, "ay":-5.25721, "alpha":1.66566, "fx":[-64.32743,-52.79617,-60.89037,-72.42751], "fy":[-88.66217,-95.94625,-90.96139,-82.12501]}, + {"t":1.23554, "x":2.23284, "y":3.68438, "heading":1.5708, "vx":-2.08179, "vy":1.97909, "omega":-0.28056, "ax":-3.41832, "ay":-5.44517, "alpha":1.52191, "fx":[-60.21633,-49.04289,-55.92445,-67.39499], "fy":[-91.65165,-98.07031,-94.28111,-86.47989]}, + {"t":1.27184, "x":2.15502, "y":3.75263, "heading":1.56061, "vx":-2.20587, "vy":1.78144, "omega":-0.22531, "ax":-2.86207, "ay":-5.75435, "alpha":1.55044, "fx":[-51.84052,-39.3517,-45.07859,-58.46143], "fy":[-96.60484,-102.31585,-99.88568,-92.71306]}, + {"t":1.30813, "x":2.07306, "y":3.8135, "heading":1.55243, "vx":-2.30976, "vy":1.57256, "omega":-0.16903, "ax":-2.0951, "ay":-6.07318, "alpha":1.56566, "fx":[-40.19928,-26.45056,-30.28032,-45.61805], "fy":[-101.96355,-106.35142,-105.28085,-99.61642]}, + {"t":1.34443, "x":1.98784, "y":3.86658, "heading":1.5463, "vx":-2.38581, "vy":1.35211, "omega":-0.1122, "ax":-1.04255, "ay":-6.33741, "alpha":1.54409, "fx":[-23.92081,-9.43049,-10.48532,-27.09737], "fy":[-106.91952,-109.15087,-109.00676,-106.11268]}, + {"t":1.38073, "x":1.90055, "y":3.91149, "heading":1.54223, "vx":-2.42366, "vy":1.12207, "omega":-0.05615, "ax":0.33713, "ay":-6.41366, "alpha":1.44603, "fx":[-1.77997,12.06596,14.23385,-1.58208], "fy":[-109.50824,-108.85928,-108.54893,-109.46191]}, + {"t":1.41703, "x":1.8128, "y":3.94799, "heading":1.54019, "vx":-2.41142, "vy":0.88926, "omega":-0.00366, "ax":1.95061, "ay":-6.12196, "alpha":1.23803, "fx":[25.67076,36.68762,41.16918,29.18981], "fy":[-106.44098,-103.17675,-101.42905,-105.48403]}, + {"t":1.45333, "x":1.72655, "y":3.97624, "heading":1.54005, "vx":-2.34061, "vy":0.66704, "omega":0.04127, "ax":3.51306, "ay":-5.38563, "alpha":0.93655, "fx":[54.12073,60.77545,65.40672,58.72135], "fy":[-95.17546,-91.09077,-87.79276,-92.3728]}, + {"t":1.48963, "x":1.6439, "y":3.9969, "heading":1.54155, "vx":-2.21309, "vy":0.47155, "omega":0.07527, "ax":4.72813, "ay":-4.36573, "alpha":0.60383, "fx":[77.39193,80.26766,83.37553,80.66163], "fy":[-77.47705,-74.51467,-71.00107,-74.04616]}, + {"t":1.52593, "x":1.56668, "y":4.01114, "heading":1.54428, "vx":-2.04147, "vy":0.31308, "omega":0.09719, "ax":5.51629, "ay":-3.32265, "alpha":0.30131, "fx":[92.71807,93.54631,94.91516,94.14276], "fy":[-58.34231,-57.01942,-54.70204,-56.00543]}, + {"t":1.56223, "x":1.49622, "y":4.02032, "heading":1.54781, "vx":-1.84123, "vy":0.19247, "omega":0.10813, "ax":5.97306, "ay":-2.41447, "alpha":0.05679, "fx":[101.45718,101.53727,101.7421,101.66385], "fy":[-41.42126,-41.22816,-40.71869,-40.90998]}, + {"t":1.59853, "x":1.43332, "y":4.02572, "heading":1.55174, "vx":-1.62442, "vy":0.10483, "omega":0.11019, "ax":6.22206, "ay":-1.67867, "alpha":-0.13121, "fx":[106.04926,105.96459,105.61788,105.71022], "fy":[-27.76176,-28.07196,-29.35221,-29.0287]}, + {"t":1.63482, "x":1.37845, "y":4.02841, "heading":1.55574, "vx":-1.39857, "vy":0.0439, "omega":0.10542, "ax":6.3519, "ay":-1.09627, "alpha":-0.27446, "fx":[108.31717,108.24788,107.75934,107.85162], "fy":[-17.06276,-17.46298,-20.26519,-19.79784]}, + {"t":1.67112, "x":1.33187, "y":4.02929, "heading":1.55956, "vx":-1.168, "vy":0.0041, "omega":0.09546, "ax":6.4153, "ay":-0.63533, "alpha":-0.38464, "fx":[109.33232,109.30329,108.89921,108.95475], "fy":[-8.6935,-8.96871,-12.9902,-12.5746]}, + {"t":1.70742, "x":1.2937, "y":4.02902, "heading":1.56303, "vx":-0.93513, "vy":-0.01896, "omega":0.0815, "ax":6.44177, "ay":-0.26691, "alpha":-0.47077, "fx":[109.6778,109.6693,109.45954,109.48422], "fy":[-2.07654,-2.1321,-7.11127,-6.84022]}, + {"t":1.74372, "x":1.264, "y":4.02815, "heading":1.56599, "vx":-0.7013, "vy":-0.02865, "omega":0.06441, "ax":6.44768, "ay":0.03154, "alpha":-0.5393, "fx":[109.66632,109.65269,109.68205,109.69155], "fy":[3.23258,3.4286,-2.30151,-2.2136]}, + {"t":1.78002, "x":1.24279, "y":4.02713, "heading":1.56833, "vx":-0.46726, "vy":-0.0275, "omega":0.04484, "ax":6.44216, "ay":0.27674, "alpha":-0.59478, "fx":[109.46704,109.42737,109.70666,109.71598], "fy":[7.55809,8.00786,1.68511,1.5783]}, + {"t":1.81632, "x":1.23007, "y":4.02632, "heading":1.56995, "vx":-0.23342, "vy":-0.01746, "omega":0.02325, "ax":6.43041, "ay":0.48095, "alpha":-0.6404, "fx":[109.17291,109.09245,109.61558,109.6366], "fy":[11.13363,11.82662,5.03169,4.73112]}, + {"t":1.85262, "x":1.22584, "y":4.026, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.36956, "ay":-1.02043, "alpha":0.0, "fx":[108.34442,108.34442,108.34442,108.34442], "fy":[-17.35724,-17.35724,-17.35724,-17.35724]}, + {"t":1.88636, "x":1.22946, "y":4.02542, "heading":1.5708, "vx":0.21495, "vy":-0.03444, "omega":0.0, "ax":6.36888, "ay":-1.02032, "alpha":0.0, "fx":[108.33282,108.33282,108.33282,108.33282], "fy":[-17.35538,-17.35538,-17.35538,-17.35538]}, + {"t":1.92011, "x":1.24034, "y":4.02368, "heading":1.5708, "vx":0.42989, "vy":-0.06887, "omega":0.0, "ax":6.36807, "ay":-1.02019, "alpha":0.0, "fx":[108.31901,108.31901,108.31901,108.31901], "fy":[-17.35317,-17.35317,-17.35317,-17.35317]}, + {"t":1.95386, "x":1.25848, "y":4.02077, "heading":1.5708, "vx":0.64479, "vy":-0.1033, "omega":0.0, "ax":6.36709, "ay":-1.02003, "alpha":0.0, "fx":[108.30229,108.30229,108.30229,108.30229], "fy":[-17.35049,-17.35049,-17.35049,-17.35049]}, + {"t":1.98761, "x":1.28386, "y":4.0167, "heading":1.5708, "vx":0.85966, "vy":-0.13772, "omega":0.0, "ax":6.36587, "ay":-1.01984, "alpha":0.0, "fx":[108.28165,108.28165,108.28165,108.28165], "fy":[-17.34718,-17.34718,-17.34718,-17.34718]}, + {"t":2.02135, "x":1.3165, "y":4.01148, "heading":1.5708, "vx":1.07449, "vy":-0.17214, "omega":0.0, "ax":6.36433, "ay":-1.01959, "alpha":0.0, "fx":[108.2555,108.2555,108.2555,108.2555], "fy":[-17.34299,-17.34299,-17.34299,-17.34299]}, + {"t":2.0551, "x":1.35638, "y":4.00509, "heading":1.5708, "vx":1.28927, "vy":-0.20655, "omega":0.0, "ax":6.36232, "ay":-1.01927, "alpha":0.0, "fx":[108.22131,108.22131,108.22131,108.22131], "fy":[-17.33752,-17.33752,-17.33752,-17.33752]}, + {"t":2.08885, "x":1.40352, "y":3.99753, "heading":1.5708, "vx":1.50398, "vy":-0.24094, "omega":0.0, "ax":6.35958, "ay":-1.01883, "alpha":0.0, "fx":[108.1747,108.1747,108.1747,108.1747], "fy":[-17.33005,-17.33005,-17.33005,-17.33005]}, + {"t":2.12259, "x":1.45789, "y":3.98882, "heading":1.5708, "vx":1.7186, "vy":-0.27533, "omega":0.0, "ax":6.35563, "ay":-1.0182, "alpha":0.0, "fx":[108.10741,108.10741,108.10741,108.10741], "fy":[-17.31927,-17.31927,-17.31927,-17.31927]}, + {"t":2.15634, "x":1.51951, "y":3.97895, "heading":1.5708, "vx":1.93308, "vy":-0.30969, "omega":0.0, "ax":6.34941, "ay":-1.0172, "alpha":0.0, "fx":[108.00172,108.00172,108.00172,108.00172], "fy":[-17.30234,-17.30234,-17.30234,-17.30234]}, + {"t":2.19009, "x":1.58836, "y":3.96792, "heading":1.5708, "vx":2.14736, "vy":-0.34402, "omega":0.0, "ax":6.33824, "ay":-1.01541, "alpha":0.0, "fx":[107.81168,107.81168,107.81168,107.81168], "fy":[-17.27189,-17.27189,-17.27189,-17.27189]}, + {"t":2.22384, "x":1.66444, "y":3.95573, "heading":1.5708, "vx":2.36126, "vy":-0.37828, "omega":0.0, "ax":6.31224, "ay":-1.01125, "alpha":0.0, "fx":[107.36932,107.36932,107.36932,107.36932], "fy":[-17.20102,-17.20102,-17.20102,-17.20102]}, + {"t":2.25758, "x":1.74772, "y":3.94239, "heading":1.5708, "vx":2.57428, "vy":-0.41241, "omega":0.0, "ax":6.18355, "ay":-0.99063, "alpha":0.0, "fx":[105.18048,105.18048,105.18048,105.18048], "fy":[-16.85036,-16.85036,-16.85036,-16.85036]}, + {"t":2.29133, "x":1.83812, "y":3.92791, "heading":1.5708, "vx":2.78296, "vy":-0.44584, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_4.traj b/src/main/deploy/choreo/E_RIGHT_PATH_4.traj index a688f407..c7c6caab 100644 --- a/src/main/deploy/choreo/E_RIGHT_PATH_4.traj +++ b/src/main/deploy/choreo/E_RIGHT_PATH_4.traj @@ -5,26 +5,26 @@ "waypoints":[ {"x":3.2129878997802734, "y":3.852599859237671, "heading":1.5707963267948966, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":1.9559978246688845, "y":5.059605598449707, "heading":0.7626747895755805, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.2163536548614502, "y":5.85614538192749, "heading":0.7626747895755805, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.812213182449341, "y":4.470187187194824, "heading":1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":1.2163536548614502, "y":5.85614538192749, "heading":0.7626747895755805, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.3943861722946167, "y":4.593503475189209, "heading":0.0, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":2.108211040496826, "y":4.333054065704346, "heading":1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], "targetDt":0.05 }, "params":{ "waypoints":[ {"x":{"exp":"3.2129878997802734 m", "val":3.2129878997802734}, "y":{"exp":"3.852599859237671 m", "val":3.852599859237671}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":{"exp":"1.9559978246688843 m", "val":1.9559978246688845}, "y":{"exp":"5.059605598449707 m", "val":5.059605598449707}, "heading":{"exp":"0.7626747895755805 rad", "val":0.7626747895755805}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.2163536548614502 m", "val":1.2163536548614502}, "y":{"exp":"5.85614538192749 m", "val":5.85614538192749}, "heading":{"exp":"0.7626747895755805 rad", "val":0.7626747895755805}, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.812213182449341 m", "val":2.812213182449341}, "y":{"exp":"4.470187187194824 m", "val":4.470187187194824}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"1.2163536548614502 m", "val":1.2163536548614502}, "y":{"exp":"5.85614538192749 m", "val":5.85614538192749}, "heading":{"exp":"0.7626747895755805 rad", "val":0.7626747895755805}, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.3943861722946167 m", "val":1.3943861722946167}, "y":{"exp":"4.593503475189209 m", "val":4.593503475189209}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"2.108211040496826 m", "val":2.108211040496826}, "y":{"exp":"4.333054065704346 m", "val":4.333054065704346}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], "targetDt":{ "exp":"0.05 s", "val":0.05 @@ -32,7 +32,7 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,0.75905,1.33983,2.48955], + "waypoints":[0.0,0.75905,1.33983,2.09545,2.38656], "samples":[ {"t":0.0, "x":3.21299, "y":3.8526, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-4.50364, "ay":4.27131, "alpha":-5.67171, "fx":[-44.63767,-78.98624,-102.05734,-80.74092], "fy":[100.19567,76.17034,40.20774,74.04096]}, {"t":0.0253, "x":3.21155, "y":3.85397, "heading":1.5708, "vx":-0.11395, "vy":0.10807, "omega":-0.1435, "ax":-4.50731, "ay":4.27482, "alpha":-5.60813, "fx":[-45.10442,-78.98909,-101.86946,-80.70915], "fy":[99.97747,76.15804,40.6597,74.05891]}, @@ -60,10 +60,10 @@ {"t":0.58194, "x":2.44352, "y":4.58061, "heading":0.83053, "vx":-2.62251, "vy":2.47569, "omega":-1.18582, "ax":-3.39874, "ay":3.41377, "alpha":15.24983, "fx":[-97.73372,-103.21354,15.88278,-46.18168], "fy":[44.77698,-13.31198,103.65582,97.14842]}, {"t":0.60724, "x":2.37608, "y":4.64434, "heading":0.80053, "vx":-2.7085, "vy":2.56206, "omega":-0.79998, "ax":-3.23418, "ay":3.33612, "alpha":15.45209, "fx":[-95.9605,-99.74131,19.16599,-43.51435], "fy":[45.26911,-14.98512,99.86072,96.84114]}, {"t":0.63254, "x":2.30651, "y":4.71023, "heading":0.78029, "vx":-2.79033, "vy":2.64647, "omega":-0.40902, "ax":-2.8929, "ay":3.22849, "alpha":14.43973, "fx":[-89.71819,-88.33191,19.81289,-38.59243], "fy":[46.06867,-9.0503,89.22075,93.42397]}, - {"t":0.65784, "x":2.23499, "y":4.77822, "heading":0.76994, "vx":-2.86353, "vy":2.72816, "omega":-0.04367, "ax":1.05939, "ay":1.68317, "alpha":1.3475, "fx":[12.82141,18.40825,23.13026,17.71975], "fy":[29.18185,23.8373,28.1888,33.31307]}, - {"t":0.68314, "x":2.16287, "y":4.84779, "heading":0.76883, "vx":-2.83672, "vy":2.77074, "omega":-0.00957, "ax":1.92352, "ay":1.86992, "alpha":-0.14708, "fx":[33.2563,32.63514,32.17878,32.80354], "fy":[31.70566,32.34682,31.90982,31.26494]}, - {"t":0.70844, "x":2.09172, "y":4.91849, "heading":0.76859, "vx":-2.78805, "vy":2.81806, "omega":-0.0133, "ax":4.01755, "ay":-0.28008, "alpha":-8.19216, "fx":[87.08798,70.70732,48.33855,67.21551], "fy":[-4.22614,36.75982,-6.80226,-44.78787]}, - {"t":0.73374, "x":2.02246, "y":4.9897, "heading":0.76826, "vx":-2.6864, "vy":2.81097, "omega":-0.22057, "ax":4.71315, "ay":-3.8059, "alpha":4.35366, "fx":[65.22046,68.84745,91.09306,95.51614], "fy":[-81.25402,-80.63349,-54.49669,-42.56499]}, + {"t":0.65784, "x":2.23499, "y":4.77822, "heading":0.76994, "vx":-2.86353, "vy":2.72816, "omega":-0.04367, "ax":1.05939, "ay":1.68317, "alpha":1.3475, "fx":[12.82141,18.40826,23.13025,17.71975], "fy":[29.18184,23.83731,28.1888,33.31307]}, + {"t":0.68314, "x":2.16287, "y":4.84779, "heading":0.76883, "vx":-2.83672, "vy":2.77074, "omega":-0.00957, "ax":1.92352, "ay":1.86992, "alpha":-0.14708, "fx":[33.2563,32.63514,32.17878,32.80354], "fy":[31.70565,32.34682,31.90982,31.26494]}, + {"t":0.70844, "x":2.09172, "y":4.91849, "heading":0.76859, "vx":-2.78805, "vy":2.81806, "omega":-0.0133, "ax":4.01755, "ay":-0.28008, "alpha":-8.19216, "fx":[87.08798,70.70732,48.33855,67.21551], "fy":[-4.22615,36.75982,-6.80226,-44.78787]}, + {"t":0.73374, "x":2.02246, "y":4.9897, "heading":0.76826, "vx":-2.6864, "vy":2.81097, "omega":-0.22057, "ax":4.71315, "ay":-3.8059, "alpha":4.35366, "fx":[65.22046,68.84746,91.09306,95.51614], "fy":[-81.25402,-80.63349,-54.49669,-42.56499]}, {"t":0.75905, "x":1.956, "y":5.05961, "heading":0.76267, "vx":-2.56715, "vy":2.71468, "omega":-0.11042, "ax":4.65411, "ay":-4.32127, "alpha":1.62441, "fx":[73.36452,73.72146,84.18313,85.39107], "fy":[-79.56035,-79.54449,-68.39403,-66.51522]}, {"t":0.79321, "x":1.87101, "y":5.14983, "heading":0.7589, "vx":-2.40815, "vy":2.56704, "omega":-0.05492, "ax":4.53713, "ay":-4.51305, "alpha":0.8577, "fx":[74.0051,74.12854,80.1042,80.46347], "fy":[-79.8963,-79.88287,-73.89213,-73.39164]}, {"t":0.82737, "x":1.79139, "y":5.23489, "heading":0.75703, "vx":-2.25314, "vy":2.41286, "omega":-0.02562, "ax":4.48212, "ay":-4.59365, "alpha":0.52913, "fx":[74.25739,74.31532,78.12622,78.25907], "fy":[-80.04657,-80.03755,-76.32285,-76.1397]}, @@ -81,39 +81,53 @@ {"t":1.23734, "x":1.23928, "y":5.8312, "heading":0.76182, "vx":-0.44749, "vy":0.48664, "omega":0.0121, "ax":4.36809, "ay":-4.7456, "alpha":-0.10721, "fx":[74.71452,74.70311,73.88111,73.90093], "fy":[-80.34062,-80.34918,-81.10568,-81.08966]}, {"t":1.27151, "x":1.22654, "y":5.84506, "heading":0.76224, "vx":-0.29826, "vy":0.32452, "omega":0.00843, "ax":4.36599, "ay":-4.74822, "alpha":-0.11846, "fx":[74.72276,74.70986,73.80066,73.82384], "fy":[-80.34535,-80.3552,-81.19107,-81.17212]}, {"t":1.30567, "x":1.2189, "y":5.85337, "heading":0.76252, "vx":-0.1491, "vy":0.1623, "omega":0.00439, "ax":4.36413, "ay":-4.75055, "alpha":-0.12842, "fx":[74.73004,74.71585,73.72927,73.75555], "fy":[-80.34953,-80.36054,-81.2667,-81.24501]}, - {"t":1.33983, "x":1.21635, "y":5.85615, "heading":0.76267, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.82875, "ay":-4.1988, "alpha":2.70745, "fx":[72.75349,73.46399,89.5518,92.77341], "fy":[-82.1239,-81.53275,-63.44657,-58.57843]}, - {"t":1.37576, "x":1.21947, "y":5.85344, "heading":0.76267, "vx":0.17349, "vy":-0.15086, "omega":0.09728, "ax":4.82904, "ay":-4.19876, "alpha":2.68863, "fx":[72.83116,73.51974,89.51037,92.70107], "fy":[-82.04156,-81.47167,-63.49137,-58.6745]}, - {"t":1.41169, "x":1.22882, "y":5.84531, "heading":0.76617, "vx":0.34699, "vy":-0.30171, "omega":0.19387, "ax":4.82938, "ay":-4.19869, "alpha":2.66734, "fx":[72.88099,73.61596,89.49085,92.59736], "fy":[-81.98195,-81.37234,-63.5031,-58.81685]}, - {"t":1.44762, "x":1.2444, "y":5.83175, "heading":0.77314, "vx":0.52051, "vy":-0.45257, "omega":0.28971, "ax":4.82976, "ay":-4.19859, "alpha":2.64283, "fx":[72.90758,73.7537,89.49066,92.45968], "fy":[-81.94062,-81.23311,-63.48491,-59.00835]}, - {"t":1.48355, "x":1.26622, "y":5.81278, "heading":0.78354, "vx":0.69403, "vy":-0.60342, "omega":0.38466, "ax":4.83022, "ay":-4.19844, "alpha":2.61415, "fx":[72.91736,73.93462,89.50622,92.28422], "fy":[-81.91128,-81.05154,-63.4411,-59.25333]}, - {"t":1.51948, "x":1.29428, "y":5.78839, "heading":0.79736, "vx":0.86758, "vy":-0.75426, "omega":0.47859, "ax":4.83075, "ay":-4.19826, "alpha":2.57994, "fx":[72.91908,74.16105,89.53259,92.06565], "fy":[-81.8853,-80.82412,-63.37759,-59.55776]}, - {"t":1.55541, "x":1.32857, "y":5.75859, "heading":0.81456, "vx":1.04114, "vy":-0.9051, "omega":0.57128, "ax":4.83137, "ay":-4.19803, "alpha":2.5383, "fx":[72.92477,74.43638,89.56281,91.79661], "fy":[-81.85077,-80.54591,-63.30269,-59.92978]}, - {"t":1.59133, "x":1.36909, "y":5.72336, "heading":0.83509, "vx":1.21472, "vy":-1.05593, "omega":0.66248, "ax":4.8321, "ay":-4.19774, "alpha":2.4865, "fx":[72.9512,74.76544,89.58688,91.46682], "fy":[-81.79095,-80.2097,-63.2284,-60.38045]}, - {"t":1.62726, "x":1.41585, "y":5.68271, "heading":0.85889, "vx":1.38834, "vy":-1.20675, "omega":0.75181, "ax":4.83296, "ay":-4.19737, "alpha":2.42042, "fx":[73.0226,75.15552,89.58971,91.06149], "fy":[-81.68135,-79.80469,-63.17274,-60.92527]}, - {"t":1.66319, "x":1.46885, "y":5.63664, "heading":0.8859, "vx":1.56198, "vy":-1.35756, "omega":0.83878, "ax":4.83399, "ay":-4.19685, "alpha":2.33347, "fx":[73.17574,75.6182,89.54729,90.55825], "fy":[-81.48419,-79.31363,-63.16429,-61.58698]}, - {"t":1.69912, "x":1.52809, "y":5.58516, "heading":0.91604, "vx":1.73566, "vy":-1.50834, "omega":0.92262, "ax":4.83522, "ay":-4.19608, "alpha":2.21443, "fx":[73.4704,76.17346,89.41824,89.92073], "fy":[-81.13649,-78.70666,-63.25174,-62.40148]}, - {"t":1.73505, "x":1.59357, "y":5.52826, "heading":0.94918, "vx":1.90938, "vy":-1.6591, "omega":1.00218, "ax":4.83665, "ay":-4.19475, "alpha":2.04208, "fx":[74.01337,76.85971,89.12323,89.08356], "fy":[-80.52181,-77.9261,-63.52658,-63.43145]}, - {"t":1.77098, "x":1.6653, "y":5.46594, "heading":0.98519, "vx":2.08316, "vy":-1.80982, "omega":1.07555, "ax":4.83814, "ay":-4.19205, "alpha":1.77054, "fx":[75.02185,77.76245,88.48517,87.91194], "fy":[-79.39165,-76.84185,-64.18653,-64.80221]}, - {"t":1.80691, "x":1.74327, "y":5.39821, "heading":1.02383, "vx":2.25698, "vy":-1.96043, "omega":1.13916, "ax":4.83866, "ay":-4.18509, "alpha":1.27736, "fx":[77.02888,79.1196,87.00265,86.06557], "fy":[-77.08872,-75.08142,-65.76185,-66.8169]}, - {"t":1.84284, "x":1.82748, "y":5.32507, "heading":1.06476, "vx":2.43083, "vy":-2.1108, "omega":1.18505, "ax":4.82847, "ay":-4.15752, "alpha":0.08128, "fx":[81.80523,81.92647,82.45431,82.33778], "fy":[-71.08926,-70.96634,-70.34886,-70.46819]}, - {"t":1.87877, "x":1.91793, "y":5.24655, "heading":1.10734, "vx":2.60431, "vy":-2.26017, "omega":1.18797, "ax":4.35986, "ay":-3.53315, "alpha":-8.6212, "fx":[98.67691,97.69503,33.09915,67.16874], "fy":[-37.25267,-23.82837,-97.53123,-81.7789]}, - {"t":1.91469, "x":2.01432, "y":5.16307, "heading":1.15002, "vx":2.76096, "vy":-2.38711, "omega":0.87823, "ax":-4.3683, "ay":3.54187, "alpha":8.67554, "fx":[-99.46426,-97.61552,-31.96945,-68.16497], "fy":[35.88831,25.17527,98.56491,81.35641]}, - {"t":1.95062, "x":2.11069, "y":5.07959, "heading":1.18158, "vx":2.60401, "vy":-2.25986, "omega":1.18993, "ax":-4.82711, "ay":4.16134, "alpha":0.03306, "fx":[-82.24859,-82.17568,-81.96656,-82.04024], "fy":[70.6219,70.70014,70.94468,70.866]}, - {"t":1.98655, "x":2.20114, "y":5.00108, "heading":1.22433, "vx":2.43058, "vy":-2.11035, "omega":1.19111, "ax":-4.83805, "ay":4.18719, "alpha":-1.25176, "fx":[-76.54239,-80.1913,-87.4916,-84.95001], "fy":[77.60343,73.95346,65.10348,68.23103]}, - {"t":2.02248, "x":2.28534, "y":4.92796, "heading":1.26712, "vx":2.25675, "vy":-1.95991, "omega":1.14614, "ax":-4.83734, "ay":4.19289, "alpha":-1.77806, "fx":[-73.79937,-79.75049,-89.66857,-85.90831], "fy":[80.56116,74.79293,62.50511,67.42017]}, - {"t":2.05841, "x":2.3633, "y":4.86025, "heading":1.3083, "vx":2.08295, "vy":-1.80926, "omega":1.08226, "ax":-4.83578, "ay":4.19476, "alpha":-2.06177, "fx":[-72.18118,-79.75552,-90.89376,-86.19034], "fy":[82.20111,74.97524,60.9436,67.28683]}, - {"t":2.09434, "x":2.43502, "y":4.79795, "heading":1.34719, "vx":1.90921, "vy":-1.65855, "omega":1.00818, "ax":-4.83441, "ay":4.19554, "alpha":-2.23732, "fx":[-71.11775,-79.93431,-91.70716,-86.16851], "fy":[83.23978,74.89914,59.8593,67.46138]}, - {"t":2.13027, "x":2.5005, "y":4.74107, "heading":1.38341, "vx":1.73551, "vy":-1.50781, "omega":0.9278, "ax":-4.8333, "ay":4.19594, "alpha":-2.35568, "fx":[-70.37377,-80.18581,-92.29826,-85.9943], "fy":[83.94952,74.70708,59.04466,67.78543]}, - {"t":2.1662, "x":2.55973, "y":4.6896, "heading":1.41674, "vx":1.56186, "vy":-1.35705, "omega":0.84316, "ax":-4.83239, "ay":4.19619, "alpha":-2.44047, "fx":[-69.8326,-80.46338,-92.75142,-85.74295], "fy":[84.45806,74.4637,58.40398,68.17824]}, - {"t":2.20212, "x":2.61273, "y":4.64355, "heading":1.44704, "vx":1.38824, "vy":-1.20629, "omega":0.75548, "ax":-4.83163, "ay":4.19638, "alpha":-2.50412, "fx":[-69.42846,-80.74237,-93.11058,-85.45723], "fy":[84.83434,74.20312,57.88608,68.59362]}, - {"t":2.23805, "x":2.65949, "y":4.60292, "heading":1.47418, "vx":1.21464, "vy":-1.05552, "omega":0.66551, "ax":-4.83098, "ay":4.19655, "alpha":-2.55375, "fx":[-69.12059,-81.00851,-93.40132,-85.16394], "fy":[85.11956,73.94537,57.4604,69.00293]}, - {"t":2.27398, "x":2.70001, "y":4.56771, "heading":1.49809, "vx":1.04107, "vy":-0.90474, "omega":0.57375, "ax":-4.83041, "ay":4.19669, "alpha":-2.59366, "fx":[-68.88183,-81.25293,-93.63987,-84.88111], "fy":[85.34028,73.70314,57.10706,69.38742]}, - {"t":2.30991, "x":2.7343, "y":4.53791, "heading":1.51871, "vx":0.86752, "vy":-0.75396, "omega":0.48057, "ax":-4.82991, "ay":4.19681, "alpha":-2.62661, "fx":[-68.69311,-81.46988,-93.83723,-84.62144], "fy":[85.51466,73.48496,56.81227,69.73433]}, - {"t":2.34584, "x":2.76235, "y":4.51353, "heading":1.53597, "vx":0.69399, "vy":-0.60317, "omega":0.38619, "ax":-4.82947, "ay":4.19691, "alpha":-2.65439, "fx":[-68.54055,-81.65546,-94.0012,-84.39426], "fy":[85.65562,73.29684,56.56595,70.03472]}, - {"t":2.38177, "x":2.78416, "y":4.49457, "heading":1.54985, "vx":0.52047, "vy":-0.45238, "omega":0.29083, "ax":-4.82907, "ay":4.19699, "alpha":-2.67824, "fx":[-68.41373,-81.80694,-94.13753,-84.20653], "fy":[85.77264,73.14312,56.36058,70.28216]}, - {"t":2.4177, "x":2.79975, "y":4.48102, "heading":1.5603, "vx":0.34697, "vy":-0.30159, "omega":0.1946, "ax":-4.82873, "ay":4.19705, "alpha":-2.69899, "fx":[-68.30479,-81.92234,-94.25049,-84.06356], "fy":[85.87281,73.02707,56.19041,70.47195]}, - {"t":2.45363, "x":2.8091, "y":4.4729, "heading":1.56729, "vx":0.17348, "vy":-0.1508, "omega":0.09763, "ax":-4.82843, "ay":4.19708, "alpha":-2.71728, "fx":[-68.20778,-82.00016,-94.34328,-83.9694], "fy":[85.96141,72.95116,56.05111,70.60054]}, - {"t":2.48955, "x":2.81221, "y":4.47019, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":1.33983, "x":1.21635, "y":5.85615, "heading":0.76267, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-2.39275, "ay":-5.98084, "alpha":1.06363, "fx":[-47.26881,-38.36626,-33.71734,-43.44735], "fy":[-99.00968,-102.79341,-104.39714,-100.7292]}, + {"t":1.37006, "x":1.21526, "y":5.85341, "heading":0.76267, "vx":-0.07232, "vy":-0.18077, "omega":0.03215, "ax":-2.29039, "ay":-6.01918, "alpha":1.11341, "fx":[-45.92217,-36.62239,-31.55577,-41.73526], "fy":[-99.6284,-103.41598,-105.05777,-101.43574]}, + {"t":1.40028, "x":1.21203, "y":5.8452, "heading":0.76365, "vx":-0.14155, "vy":-0.3627, "omega":0.0658, "ax":-2.16927, "ay":-6.06197, "alpha":1.17147, "fx":[-44.32655,-34.56732,-29.00209,-39.69883], "fy":[-100.33337,-104.10756,-105.77618,-102.23256]}, + {"t":1.43051, "x":1.20676, "y":5.83147, "heading":0.76564, "vx":-0.20711, "vy":-0.54592, "omega":0.10121, "ax":-2.02392, "ay":-6.10973, "alpha":1.23994, "fx":[-42.40915,-32.11544,-25.9438,-37.23698], "fy":[-101.14097,-104.8743,-106.54992,-103.13419]}, + {"t":1.46073, "x":1.19958, "y":5.81218, "heading":0.76869, "vx":-0.26828, "vy":-0.73058, "omega":0.13868, "ax":-1.84663, "ay":-6.16281, "alpha":1.3217, "fx":[-40.06653,-29.14814,-22.22407,-34.20381], "fy":[-102.07044,-105.71908,-107.36651,-104.15469]}, + {"t":1.49096, "x":1.19062, "y":5.78728, "heading":0.77289, "vx":-0.3241, "vy":-0.91685, "omega":0.17863, "ax":-1.62623, "ay":-6.22107, "alpha":1.42069, "fx":[-37.14733,-25.49729,-17.61999,-30.38228], "fy":[-103.14301,-106.63652,-108.1923,-105.30262]}, + {"t":1.52118, "x":1.18008, "y":5.75673, "heading":0.77829, "vx":-0.37325, "vy":-1.10488, "omega":0.22157, "ax":-1.34613, "ay":-6.28311, "alpha":1.54233, "fx":[-33.42245,-20.91905,-11.80893,-25.43852], "fy":[-104.37783,-107.60171,-108.9491,-106.56713]}, + {"t":1.55141, "x":1.16819, "y":5.72046, "heading":0.78498, "vx":-0.41394, "vy":-1.29479, "omega":0.26819, "ax":-0.98095, "ay":-6.34446, "alpha":1.69414, "fx":[-28.53163,-15.05175,-4.31872,-18.84071], "fy":[-105.77943,-108.54522,-109.46413,-107.8809]}, + {"t":1.58163, "x":1.15523, "y":5.67843, "heading":0.79309, "vx":-0.44359, "vy":-1.48655, "omega":0.31939, "ax":-0.49111, "ay":-6.39306, "alpha":1.88637, "fx":[-21.88482,-7.34991,5.53631,-9.71608], "fy":[-107.30013,-109.29602,-109.36167,-109.01876]}, + {"t":1.61186, "x":1.1416, "y":5.63058, "heading":0.80274, "vx":-0.45843, "vy":-1.67977, "omega":0.37641, "ax":0.18519, "ay":-6.39818, "alpha":2.13236, "fx":[-12.47824,3.00753,18.69429,3.3765], "fy":[-108.7273,-109.44928,-107.83392,-109.31416]}, + {"t":1.64208, "x":1.12783, "y":5.57689, "heading":0.81412, "vx":-0.45283, "vy":-1.87316, "omega":0.44086, "ax":1.13772, "ay":-6.28325, "alpha":2.44753, "fx":[1.42126,17.18871,36.17712,22.62192], "fy":[-109.33796,-108.06577,-103.21483,-106.88653]}, + {"t":1.67231, "x":1.11466, "y":5.5174, "heading":0.82744, "vx":-0.41844, "vy":-2.06307, "omega":0.51483, "ax":2.45728, "ay":-5.87139, "alpha":2.83748, "fx":[22.56228,36.49492,58.16566,49.96743], "fy":[-106.86443,-103.07395,-92.53393,-97.0103]}, + {"t":1.70253, "x":1.10313, "y":5.45236, "heading":0.843, "vx":-0.34417, "vy":-2.24053, "omega":0.6006, "ax":4.08108, "ay":-4.85798, "alpha":3.19807, "fx":[53.26103,60.98699,81.75889,81.66515], "fy":[-95.18537,-90.65764,-72.45336,-72.23474]}, + {"t":1.73275, "x":1.0946, "y":5.38243, "heading":0.86116, "vx":-0.22083, "vy":-2.38736, "omega":0.69726, "ax":5.54338, "ay":-3.08774, "alpha":3.14523, "fx":[87.18131,86.23267,100.12374,103.62775], "fy":[-65.40714,-67.01831,-43.69015,-33.97068]}, + {"t":1.76298, "x":1.09045, "y":5.30886, "heading":0.88223, "vx":-0.05328, "vy":-2.48068, "omega":0.79232, "ax":6.2844, "ay":-1.03281, "alpha":2.65085, "fx":[106.48116,103.48421,108.45805,109.1597], "fy":[-23.56398,-34.96578,-13.47907,1.73788]}, + {"t":1.7932, "x":1.09171, "y":5.23341, "heading":0.90618, "vx":0.13667, "vy":-2.5119, "omega":0.87244, "ax":6.35976, "ay":0.65223, "alpha":2.11451, "fx":[108.66671,109.21968,108.76979,106.05478], "fy":[10.80604,-4.27865,11.41099,26.43853]}, + {"t":1.82343, "x":1.09875, "y":5.15779, "heading":0.93255, "vx":0.32889, "vy":-2.49219, "omega":0.93635, "ax":6.14817, "ay":1.81712, "alpha":1.6653, "fx":[104.28995,107.71053,105.37731,100.93677], "fy":[32.82393,19.07901,29.53628,42.19572]}, + {"t":1.85365, "x":1.1115, "y":5.08329, "heading":0.96085, "vx":0.51471, "vy":-2.43726, "omega":0.98669, "ax":5.87556, "ay":2.59498, "alpha":1.31592, "fx":[99.06293,103.60041,101.00111,96.10179], "fy":[46.49368,35.33542,42.29321,52.43714]}, + {"t":1.88388, "x":1.12974, "y":5.01081, "heading":0.99067, "vx":0.6923, "vy":-2.35883, "omega":1.02646, "ax":5.6204, "ay":3.12562, "alpha":1.05078, "fx":[94.48237,99.12861,96.76343,92.03084], "fy":[55.35084,46.56193,51.35512,59.39585]}, + {"t":1.9141, "x":1.15323, "y":4.94094, "heading":1.0217, "vx":0.86218, "vy":-2.26436, "omega":1.05822, "ax":5.40098, "ay":3.50104, "alpha":0.84852, "fx":[90.7251,95.0468,93.00748,88.69731], "fy":[61.40905,54.50388,57.95292,64.34083]}, + {"t":1.94433, "x":1.18176, "y":4.8741, "heading":1.05368, "vx":1.02542, "vy":-2.15854, "omega":1.08386, "ax":5.21675, "ay":3.77656, "alpha":0.69153, "fx":[87.67247,91.51852,89.77931,85.97132], "fy":[65.76004,60.30638,62.89173,67.99441]}, + {"t":1.97455, "x":1.21513, "y":4.81059, "heading":1.08644, "vx":1.18309, "vy":-2.0444, "omega":1.10477, "ax":5.06247, "ay":3.98547, "alpha":0.56719, "fx":[85.17388,88.51606,87.02905,83.72536], "fy":[69.015,64.68183,66.68686,70.78309]}, + {"t":2.00478, "x":1.2532, "y":4.75062, "heading":1.11983, "vx":1.3361, "vy":-1.92394, "omega":1.12191, "ax":4.93258, "ay":4.14837, "alpha":0.46679, "fx":[83.10303,85.96312,84.68506,81.85585], "fy":[71.53316,68.07575,69.67186,72.96975]}, + {"t":2.035, "x":1.29584, "y":4.69436, "heading":1.15374, "vx":1.48519, "vy":-1.79856, "omega":1.13602, "ax":4.82234, "ay":4.27845, "alpha":0.38428, "fx":[81.36331,83.78125,82.67878,80.28301], "fy":[73.53612,70.77357,72.06756,74.72327]}, + {"t":2.06523, "x":1.34293, "y":4.64195, "heading":1.18808, "vx":1.63094, "vy":-1.66924, "omega":1.14763, "ax":4.72793, "ay":4.38441, "alpha":0.31542, "fx":[79.88253,81.90271,80.95164,78.94616], "fy":[75.16659,72.96352,74.02399,76.15619]}, + {"t":2.09545, "x":1.39439, "y":4.5935, "heading":1.22276, "vx":1.77384, "vy":-1.53672, "omega":1.15717, "ax":4.67696, "ay":4.42224, "alpha":0.29427, "fx":[79.08057,80.95866,80.02182,78.15394], "fy":[75.72361,73.71927,74.7482,76.6928]}, + {"t":2.10931, "x":1.41943, "y":4.57263, "heading":1.2388, "vx":1.83868, "vy":-1.47542, "omega":1.16125, "ax":4.67594, "ay":4.42172, "alpha":0.29284, "fx":[79.08821,80.94101,79.9805,78.13577], "fy":[75.68802,73.71085,74.76547,76.68456]}, + {"t":2.12318, "x":1.44536, "y":4.5526, "heading":1.2549, "vx":1.9035, "vy":-1.41413, "omega":1.1653, "ax":4.67481, "ay":4.42115, "alpha":0.29127, "fx":[79.09419,80.92053,79.93727,78.11688], "fy":[75.65118,73.70253,74.78186,76.67416]}, + {"t":2.13704, "x":1.4722, "y":4.53342, "heading":1.27105, "vx":1.9683, "vy":-1.35284, "omega":1.16934, "ax":4.67356, "ay":4.4205, "alpha":0.28956, "fx":[79.09821,80.89684,79.89186,78.09709], "fy":[75.61288,73.69422,74.79713,76.66129]}, + {"t":2.1509, "x":1.49993, "y":4.51509, "heading":1.28726, "vx":2.03309, "vy":-1.29156, "omega":1.17336, "ax":4.67218, "ay":4.41976, "alpha":0.28768, "fx":[79.09991,80.8695,79.84395,78.07616], "fy":[75.5729,73.68577,74.81103,76.64558]}, + {"t":2.16476, "x":1.52856, "y":4.49761, "heading":1.30353, "vx":2.09785, "vy":-1.23029, "omega":1.17734, "ax":4.67062, "ay":4.41891, "alpha":0.28561, "fx":[79.09881,80.83792,79.79311,78.0538], "fy":[75.53091,73.677,74.8232,76.62655]}, + {"t":2.17862, "x":1.55809, "y":4.48098, "heading":1.31985, "vx":2.1626, "vy":-1.16904, "omega":1.1813, "ax":4.66887, "ay":4.41793, "alpha":0.28331, "fx":[79.09435,80.80141,79.73884,78.02963], "fy":[75.48651,73.66767,74.83321,76.60361]}, + {"t":2.19249, "x":1.58852, "y":4.4652, "heading":1.33623, "vx":2.22732, "vy":-1.10779, "omega":1.18523, "ax":4.66687, "ay":4.41679, "alpha":0.28075, "fx":[79.08578,80.75905,79.68045,78.00316], "fy":[75.43917,73.65744,74.84049,76.57599]}, + {"t":2.20635, "x":1.61985, "y":4.45027, "heading":1.35266, "vx":2.29201, "vy":-1.04657, "omega":1.18912, "ax":4.66458, "ay":4.41543, "alpha":0.27788, "fx":[79.07212,80.70966,79.61705,77.97371], "fy":[75.38818,73.64586,74.84428,76.54268]}, + {"t":2.22021, "x":1.65207, "y":4.43618, "heading":1.36914, "vx":2.35668, "vy":-0.98536, "omega":1.19297, "ax":4.66192, "ay":4.41381, "alpha":0.27464, "fx":[79.05209,80.65165,79.54743,77.94039], "fy":[75.33256,73.63232,74.84357,76.50232]}, + {"t":2.23407, "x":1.68518, "y":4.42295, "heading":1.38568, "vx":2.4213, "vy":-0.92417, "omega":1.19678, "ax":4.65879, "ay":4.41184, "alpha":0.27093, "fx":[79.02391,80.58288,79.46995,77.90195], "fy":[75.27096,73.61589,74.83697,76.45306]}, + {"t":2.24794, "x":1.7192, "y":4.41056, "heading":1.40227, "vx":2.48588, "vy":-0.86302, "omega":1.20054, "ax":4.65505, "ay":4.40941, "alpha":0.26665, "fx":[78.98509,80.50033,79.38226,77.85659], "fy":[75.20142,73.59528,74.82246,76.39228]}, + {"t":2.2618, "x":1.7541, "y":4.39902, "heading":1.41891, "vx":2.55041, "vy":-0.80189, "omega":1.20423, "ax":4.65049, "ay":4.40635, "alpha":0.26163, "fx":[78.93202,80.39961,79.2809,77.80168], "fy":[75.12106,73.5685,74.79712,76.31614]}, + {"t":2.27566, "x":1.7899, "y":4.38833, "heading":1.4356, "vx":2.61488, "vy":-0.74081, "omega":1.20786, "ax":4.6448, "ay":4.40238, "alpha":0.25562, "fx":[78.85918,80.27409,79.16062,77.73313], "fy":[75.0254,73.53242,74.75642,76.2188]}, + {"t":2.28952, "x":1.8266, "y":4.37848, "heading":1.45235, "vx":2.67927, "vy":-0.67978, "omega":1.2114, "ax":4.63747, "ay":4.39709, "alpha":0.24823, "fx":[78.75777,80.11315,79.01295,77.64434], "fy":[74.90719,73.4819,74.69304,76.09087]}, + {"t":2.30339, "x":1.86419, "y":4.36948, "heading":1.46914, "vx":2.74355, "vy":-0.61883, "omega":1.21485, "ax":4.62763, "ay":4.38973, "alpha":0.23884, "fx":[78.61273,79.8987,78.82328,77.52386], "fy":[74.75383,73.40788,74.59433,75.91622]}, + {"t":2.31725, "x":1.90266, "y":4.36133, "heading":1.48598, "vx":2.8077, "vy":-0.55798, "omega":1.21816, "ax":4.61364, "ay":4.3789, "alpha":0.22625, "fx":[78.39586,79.59689,78.56416,77.35005], "fy":[74.54152,73.29302,74.4364,75.66461]}, + {"t":2.33111, "x":1.94203, "y":4.35401, "heading":1.50287, "vx":2.87166, "vy":-0.49727, "omega":1.22129, "ax":4.59204, "ay":4.36161, "alpha":0.20801, "fx":[78.04743,79.13606,78.17696,77.07654], "fy":[74.21938,73.09976,74.16805,75.27171]}, + {"t":2.34497, "x":1.98228, "y":4.34754, "heading":1.5198, "vx":2.93531, "vy":-0.43681, "omega":1.22418, "ax":4.55387, "ay":4.3301, "alpha":0.17779, "fx":[77.41448,78.33234,77.51013,76.58327], "fy":[73.65616,72.73,73.65658,74.57209]}, + {"t":2.35883, "x":2.0234, "y":4.3419, "heading":1.53677, "vx":2.99844, "vy":-0.37679, "omega":1.22664, "ax":4.46692, "ay":4.25632, "alpha":0.11265, "fx":[75.95031,76.5254,76.01341,75.43474], "fy":[72.38044,71.82501,72.41896,72.97067]}, + {"t":2.3727, "x":2.0654, "y":4.33708, "heading":1.55377, "vx":3.06036, "vy":-0.31779, "omega":1.2282, "ax":4.05866, "ay":3.90166, "alpha":-0.19203, "fx":[69.15819,68.17478,68.91872,69.89494], "fy":[66.48761,67.25855,66.24813,65.47049]}, + {"t":2.38656, "x":2.10821, "y":4.33305, "heading":1.5708, "vx":3.11662, "vy":-0.2637, "omega":1.22554, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index e4e8ef40..848ddef1 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -24,6 +24,7 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.util.AllianceFlipUtil; +import frc.robot.util.GeometryUtil; import frc.robot.util.LoggedChoreo.LoggedAutoRoutine; import frc.robot.util.LoggedChoreo.LoggedAutoTrajectory; import java.util.Optional; @@ -1870,7 +1871,8 @@ public static final LoggedAutoRoutine autoERight( Commands.sequence( path1.resetOdometry(), Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), + Commands.parallel( + path1.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), @@ -1879,8 +1881,8 @@ public static final LoggedAutoRoutine autoERight( path2.cmd(), superstructure .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) - .andThen(Commands.waitSeconds((2.0))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), + .andThen(Commands.waitSeconds((1.5))) + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), @@ -1890,12 +1892,73 @@ public static final LoggedAutoRoutine autoERight( superstructure .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) .andThen(Commands.waitSeconds((1.5))) + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4))), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, ReefState.L4, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path4.cmd(), + superstructure + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .andThen(Commands.waitSeconds((1.5))) + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4))), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, ReefState.L4, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE))); + + return routine; + } + + public static final LoggedAutoRoutine autoELeft( + Drive drive, + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoELeft"); + LoggedAutoTrajectory path1 = + routine.trajectory(GeometryUtil.mirrorTrajectory(routine.trajectory("E_RIGHT_PATH_1"))); + LoggedAutoTrajectory path2 = + routine.trajectory(GeometryUtil.mirrorTrajectory(routine.trajectory("E_RIGHT_PATH_2"))); + LoggedAutoTrajectory path3 = + routine.trajectory(GeometryUtil.mirrorTrajectory(routine.trajectory("E_RIGHT_PATH_3"))); + LoggedAutoTrajectory path4 = + routine.trajectory(GeometryUtil.mirrorTrajectory(routine.trajectory("E_RIGHT_PATH_4"))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, ReefState.L4, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path2.cmd(), + superstructure + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .andThen(Commands.waitSeconds((2.0))) .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path3.cmd(), + superstructure + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .andThen(Commands.waitSeconds((1.5))) + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, ReefState.L4, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), path4.cmd(), superstructure .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) @@ -1962,4 +2025,67 @@ public static final LoggedAutoRoutine autoERightBack( return routine; } + + public static final LoggedAutoRoutine autoELeftBack( + Drive drive, + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoELeftBack"); + LoggedAutoTrajectory path1 = + routine.trajectory( + GeometryUtil.mirrorTrajectory(routine.trajectory("E_RIGHT_PATH_1_BACK"))); + LoggedAutoTrajectory path2 = + routine.trajectory( + GeometryUtil.mirrorTrajectory(routine.trajectory("E_RIGHT_PATH_2_BACK"))); + LoggedAutoTrajectory path3 = + routine.trajectory( + GeometryUtil.mirrorTrajectory(routine.trajectory("E_RIGHT_PATH_3_BACK"))); + LoggedAutoTrajectory path4 = + routine.trajectory( + GeometryUtil.mirrorTrajectory(routine.trajectory("E_RIGHT_PATH_4_BACK"))); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), + path1.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, ReefState.L4, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.parallel( + path2.cmd(), + superstructure + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .andThen(Commands.waitSeconds((1.0))) + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, ReefState.L2, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_SCORE), + Commands.parallel( + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path3.cmd(), + superstructure + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .andThen(Commands.waitSeconds((1.0))) + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, ReefState.L2, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_SCORE), + Commands.parallel( + path4.cmd(), + superstructure + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .andThen(Commands.waitSeconds((1.0))) + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, ReefState.L4, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE))); + + return routine; + } } diff --git a/src/main/java/frc/robot/commands/DriveCommands.java b/src/main/java/frc/robot/commands/DriveCommands.java index 36320981..eee42a9f 100644 --- a/src/main/java/frc/robot/commands/DriveCommands.java +++ b/src/main/java/frc/robot/commands/DriveCommands.java @@ -430,6 +430,35 @@ public static Command autoAlignReefCoral(Drive drive, Camera... cameras) { .coralSetpoint() .getRotation() .getRadians()); + + ChassisSpeeds measuredSpeeds = drive.getMeasuredChassisSpeeds(); + double vx_prime = + measuredSpeeds.vxMetersPerSecond + * Math.cos( + RobotState.getReefAlignData() + .algaeSetpoint() + .getRotation() + .getRadians()) + + measuredSpeeds.vyMetersPerSecond + * Math.sin( + RobotState.getReefAlignData() + .algaeSetpoint() + .getRotation() + .getRadians()); + + double vy_prime = + -measuredSpeeds.vxMetersPerSecond + * Math.sin( + RobotState.getReefAlignData() + .algaeSetpoint() + .getRotation() + .getRadians()) + + measuredSpeeds.vyMetersPerSecond + * Math.cos( + RobotState.getReefAlignData() + .algaeSetpoint() + .getRotation() + .getRadians()); InternalLoggedTracer.record( "Create Rotated Errors", "Command Scheduler/Drive Commands/Auto Align Coral"); @@ -441,7 +470,7 @@ public static Command autoAlignReefCoral(Drive drive, Camera... cameras) { "Create XSpeed", "Command Scheduler/Drive Commands/Auto Align Algae"); } else { InternalLoggedTracer.reset(); - alignXController.reset(ex_prime); + alignXController.reset(ex_prime, vx_prime); InternalLoggedTracer.record( "Reset XSpeed", "Command Scheduler/Drive Commands/Auto Align Algae"); } @@ -453,7 +482,7 @@ public static Command autoAlignReefCoral(Drive drive, Camera... cameras) { } else { InternalLoggedTracer.reset(); - alignYController.reset(ey_prime); + alignYController.reset(ey_prime, vy_prime); InternalLoggedTracer.record( "Reset YSpeed", "Command Scheduler/Drive Commands/Auto Align Algae"); } @@ -603,6 +632,36 @@ public static Command autoAlignReefAlgae(Drive drive, Camera... cameras) { .algaeSetpoint() .getRotation() .getRadians()); + + ChassisSpeeds measuredSpeeds = drive.getMeasuredChassisSpeeds(); + double vx_prime = + measuredSpeeds.vxMetersPerSecond + * Math.cos( + RobotState.getReefAlignData() + .algaeSetpoint() + .getRotation() + .getRadians()) + + measuredSpeeds.vyMetersPerSecond + * Math.sin( + RobotState.getReefAlignData() + .algaeSetpoint() + .getRotation() + .getRadians()); + + double vy_prime = + -measuredSpeeds.vxMetersPerSecond + * Math.sin( + RobotState.getReefAlignData() + .algaeSetpoint() + .getRotation() + .getRadians()) + + measuredSpeeds.vyMetersPerSecond + * Math.cos( + RobotState.getReefAlignData() + .algaeSetpoint() + .getRotation() + .getRadians()); + InternalLoggedTracer.record( "Create Rotated Errors", "Command Scheduler/Drive Commands/Auto Align Algae"); @@ -614,7 +673,7 @@ public static Command autoAlignReefAlgae(Drive drive, Camera... cameras) { "Create XSpeed", "Command Scheduler/Drive Commands/Auto Align Algae"); } else { InternalLoggedTracer.reset(); - alignXController.reset(ex_prime); + alignXController.reset(ex_prime, vx_prime); InternalLoggedTracer.record( "Reset XSpeed", "Command Scheduler/Drive Commands/Auto Align Algae"); } @@ -626,7 +685,7 @@ public static Command autoAlignReefAlgae(Drive drive, Camera... cameras) { } else { InternalLoggedTracer.reset(); - alignYController.reset(ey_prime); + alignYController.reset(ey_prime, vy_prime); InternalLoggedTracer.record( "Reset YSpeed", "Command Scheduler/Drive Commands/Auto Align Algae"); } diff --git a/src/main/java/frc/robot/subsystems/shared/drive/Drive.java b/src/main/java/frc/robot/subsystems/shared/drive/Drive.java index a97d344b..c66f44ca 100644 --- a/src/main/java/frc/robot/subsystems/shared/drive/Drive.java +++ b/src/main/java/frc/robot/subsystems/shared/drive/Drive.java @@ -56,6 +56,7 @@ public class Drive extends SubsystemBase { private final SwerveDriveKinematics kinematics; @Getter private Rotation2d rawGyroRotation; private SwerveModulePosition[] lastModulePositions; + @Getter private ChassisSpeeds measuredChassisSpeeds; @Getter private final LoggedAutoFactory autoFactory; @@ -178,6 +179,7 @@ public void periodic() { } ChassisSpeeds chassisSpeeds = kinematics.toChassisSpeeds(getModuleStates()); + measuredChassisSpeeds = chassisSpeeds; Translation2d rawFieldRelativeVelocity = new Translation2d(chassisSpeeds.vxMetersPerSecond, chassisSpeeds.vyMetersPerSecond) .rotateBy(getRawGyroRotation()); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 73e18265..85a68523 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -133,11 +133,17 @@ private void configureButtonBindings() { private void configureAutos() { autoChooser.addRoutine( - "4 Piece Early Madtown", + "4 Piece Right Early Madtown", () -> AutonomousCommands.autoERight(drive, superstructure, intake, manipulator)); autoChooser.addRoutine( - "4 Piece Late Madtown", + "4 Piece Right Late Madtown", () -> AutonomousCommands.autoERightBack(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "4 Piece Left Early Madtown", + () -> AutonomousCommands.autoELeft(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "4 Piece Left Late Madtown", + () -> AutonomousCommands.autoELeftBack(drive, superstructure, intake, manipulator)); SmartDashboard.putData("Autonomous Modes", autoChooser); } diff --git a/src/main/java/frc/robot/util/GeometryUtil.java b/src/main/java/frc/robot/util/GeometryUtil.java index cf8249f5..559d9765 100644 --- a/src/main/java/frc/robot/util/GeometryUtil.java +++ b/src/main/java/frc/robot/util/GeometryUtil.java @@ -1,9 +1,15 @@ package frc.robot.util; +import choreo.trajectory.SwerveSample; +import choreo.trajectory.Trajectory; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Transform2d; import edu.wpi.first.math.geometry.Translation2d; +import frc.robot.FieldConstants; +import frc.robot.util.LoggedChoreo.LoggedAutoTrajectory; +import java.util.ArrayList; +import java.util.List; public class GeometryUtil { /** @@ -67,4 +73,48 @@ public static final boolean isZero(Translation2d translation) { public static final boolean isZero(Rotation2d rotation) { return rotation.getDegrees() == 0.0; } + + public static final Trajectory mirrorTrajectory( + LoggedAutoTrajectory inputAutoPath) { + List mirroredSamples = new ArrayList<>(); + Trajectory trajectory = inputAutoPath.getRawTrajectory(); + trajectory + .samples() + .forEach( + sample -> { + mirroredSamples.add( + new SwerveSample( + sample.t, + sample.x, + FieldConstants.fieldWidth - (sample.y), + -sample.heading, + sample.vx, + -sample.vy, + -sample.omega, + sample.ax, + -sample.ay, + -sample.alpha, + // TODO: VERIFY THIS + // FL, FR, BL, BR + // Mirrored + // FR, FL, BR, BL + new double[] { + sample.moduleForcesX()[1], + sample.moduleForcesX()[0], + sample.moduleForcesX()[3], + sample.moduleForcesX()[2] + }, + // FL, FR, BL, BR + // Mirrored + // -FR, -FL, -BR, -BL + new double[] { + -sample.moduleForcesY()[1], + -sample.moduleForcesY()[0], + -sample.moduleForcesY()[3], + -sample.moduleForcesY()[2] + })); + }); + return new Trajectory( + trajectory.name(), mirroredSamples, trajectory.splits(), trajectory.events()); + } } From 0a93bfe4119c34eaf5bbad6a31e270be38d8e589 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Fri, 26 Sep 2025 00:04:26 -0400 Subject: [PATCH 120/180] Add armBelowThreshold method and update runReefScoreGoal command to include arm angle check --- src/main/java/frc/robot/commands/CompositeCommands.java | 4 +++- .../v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java | 4 ++++ 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 7d67cbb7..1a4f265f 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -717,7 +717,9 @@ public static final Command optimalAutoScoreCoralSequence( superstructure.runReefGoal(() -> height), DriveCommands.autoAlignReefCoral(drive, cameras), Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), - superstructure.runReefScoreGoal(() -> height)); + superstructure + .runReefScoreGoal(() -> height) + .until(() -> superstructure.armBelowThreshold())); } public static final Command optimalAutoAlignReefAlgae( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index e98e7291..bcd07dfb 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -616,4 +616,8 @@ public Command allTransition() { } return all; } + + public boolean armBelowThreshold() { + return manipulator.getArmAngle().getDegrees() >= 130; + } } From bd2cb9c67c7b398a49891192b12869837f7aa2e1 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Fri, 26 Sep 2025 08:57:15 -0400 Subject: [PATCH 121/180] Update armBelowThreshold logic and refine reef scoring command conditions --- src/main/java/frc/robot/commands/CompositeCommands.java | 6 +++++- .../v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java | 2 +- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 1a4f265f..7b34bdcd 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -719,7 +719,11 @@ public static final Command optimalAutoScoreCoralSequence( Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), superstructure .runReefScoreGoal(() -> height) - .until(() -> superstructure.armBelowThreshold())); + .until( + () -> { + if (height.equals(ReefState.L4)) return superstructure.armBelowThreshold(); + else return false; + })); } public static final Command optimalAutoAlignReefAlgae( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index bcd07dfb..06ac9d0d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -618,6 +618,6 @@ public Command allTransition() { } public boolean armBelowThreshold() { - return manipulator.getArmAngle().getDegrees() >= 130; + return manipulator.getArmAngle().getDegrees() >= 90; } } From dc8e741523ebe8278ccb51dd1b9bc2f80ff53084 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Tue, 14 Oct 2025 12:44:30 -0400 Subject: [PATCH 122/180] ik --- dh2fk.py | 51 ++++++++ .../frc/robot/commands/CompositeCommands.java | 50 +++++++- .../subsystems/shared/elevator/Elevator.java | 116 +++++++++++++----- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 6 +- .../V3_EpsilonSuperstructure.java | 7 ++ .../V3_EpsilonSuperstructureEdges.java | 6 +- .../V3_EpsilonSuperstructureKinematics.java | 96 +++++++++++++++ .../V3_EpsilonSuperstructurePose.java | 2 +- .../V3_EpsilonSuperstructureStates.java | 3 - .../manipulator/V3_EpsilonManipulator.java | 15 ++- .../frc/robot/util/TrajectoryGenerator.java | 96 +++++++++++++++ 11 files changed, 400 insertions(+), 48 deletions(-) create mode 100644 dh2fk.py create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureKinematics.java create mode 100644 src/main/java/frc/robot/util/TrajectoryGenerator.java diff --git a/dh2fk.py b/dh2fk.py new file mode 100644 index 00000000..be161999 --- /dev/null +++ b/dh2fk.py @@ -0,0 +1,51 @@ +from readline import redisplay +from numpy import disp +import sympy as sp + +# Use this in a Jupyter Notebook or similar for nicely formatted math output +sp.init_printing(use_unicode=True) + +# ------------------------------------------------------------------- +# Part 1: Symbolic Derivation +# ------------------------------------------------------------------- + +# 1. Define the symbolic variables +l1, l3, d3, l5, theta5, l7 = sp.symbols('l1 l3 d3 l5 theta5 l7') + +# 2. Define the DH table using the symbolic variables +# [theta, d, a/r, alpha] in radians +dh_table = [ + [0, 0, -l1, 0], + [sp.pi/2, 0, 0, 0], + [0, l3+d3, 0, 0], + [0, 0, 0, sp.pi/2], + [0, l5, 0, 0], + [theta5, 0, 0, -sp.pi/2], + [-sp.pi/2, l7, 0, 0] +] + +def create_symbolic_transform(dh_row): + """Creates a 4x4 symbolic transformation matrix from a DH table row.""" + theta, d, a, alpha = dh_row + + return sp.Matrix([ + [sp.cos(theta), -sp.sin(theta)*sp.cos(alpha), sp.sin(theta)*sp.sin(alpha), a*sp.cos(theta)], + [sp.sin(theta), sp.cos(theta)*sp.cos(alpha), -sp.cos(theta)*sp.sin(alpha), a*sp.sin(theta)], + [0, sp.sin(alpha), sp.cos(alpha), d], + [0, 0, 0, 1] + ]) + +# 3. Initialize the final transformation matrix as a 4x4 identity matrix +T_final_symbolic = sp.eye(4) + +# 4. Loop through the DH table and multiply the matrices +for row in dh_table: + T_final_symbolic = T_final_symbolic * create_symbolic_transform(row) + +# 5. Simplify the final expression for a cleaner result +T_final_symbolic = sp.simplify(T_final_symbolic) + +# 6. Display the final symbolic transformation matrix row by row +print("Final Symbolic Transformation Matrix:") +for i in range(T_final_symbolic.rows): + print(T_final_symbolic.row(i)) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 7b34bdcd..fe9b9245 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -1,9 +1,13 @@ package frc.robot.commands; import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.Matrix; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.kinematics.ChassisSpeeds; +import edu.wpi.first.math.numbers.N1; +import edu.wpi.first.math.numbers.N6; +import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.FieldConstants.Reef; @@ -29,9 +33,9 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; -// Removed duplicate or conflicting import for ManipulatorArmState import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; import frc.robot.util.AllianceFlipUtil; +import frc.robot.util.TrajectoryGenerator; import java.util.function.BooleanSupplier; import java.util.function.Supplier; @@ -929,5 +933,49 @@ public static final Command manipulatorGroundIntake( () -> superstructure.runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE)), Commands.runOnce(() -> manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE))); } + + public static final Command runIK( + Matrix[] trajectory, + V3_EpsilonSuperstructure superstructure, + double t, + Timer timer) { + return Commands.sequence( + Commands.print("Started"), + Commands.runOnce(() -> timer.start()), + Commands.run( + () -> { + if (timer.hasElapsed(t)) return; + double ypos = + TrajectoryGenerator.evaluateQuinticTrajectory(trajectory[0], timer.get()); + double zpos = + TrajectoryGenerator.evaluateQuinticTrajectory(trajectory[1], timer.get()); + + superstructure.runIK(ypos, zpos); + })); + } + + public static final Command createTrajectoryTestCommand( + V3_EpsilonSuperstructure superstructure, Timer timer) { + // 1. Define the start and end points of a simple trajectory + // For example, a 2-second move from (y=0.5, z=0.5) to (y=1.0, z=0.75) + double startY = 0.55, endY = -0.55; + double startZ = 1, endZ = 2; + double duration = 4.0; + + // 2. Generate the trajectory coefficients for Y and Z axes + // We assume the arm starts and ends at rest (zero velocity and acceleration) + @SuppressWarnings("unchecked") + Matrix[] trajectoryCoeffs = + new Matrix[] { + TrajectoryGenerator.generateQuinticTrajectory(startY, 0, 0, endY, 0, 0, 0, duration), + TrajectoryGenerator.generateQuinticTrajectory(startZ, 0, 0, endZ, 0, 0, 0, duration) + }; + + // 3. Return the composite command + return Commands.sequence( + Commands.runOnce(() -> superstructure.runIK(startY, startZ)), + Commands.waitSeconds(2), + runIK(trajectoryCoeffs, superstructure, duration, timer)); + } } } diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java index e6547733..193a07fa 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java @@ -32,14 +32,18 @@ public class Elevator { private final ElevatorIO io; private final ElevatorIOInputsAutoLogged inputs; - private ElevatorPositions position; + // --- MODIFIED: Store the goal primarily as a double for flexibility --- + private double positionGoalMeters; + private ElevatorPositions lastKnownPositionEnum; // Keep track of the last named position private boolean isClosedLoop; public Elevator(ElevatorIO io) { this.io = io; this.inputs = new ElevatorIOInputsAutoLogged(); - position = ElevatorPositions.STOW; + // Initialize to STOW position + this.lastKnownPositionEnum = ElevatorPositions.STOW; + this.positionGoalMeters = lastKnownPositionEnum.getPosition(); isClosedLoop = true; } @@ -52,11 +56,14 @@ private void periodic() { Logger.processInputs("Elevator", inputs); InternalLoggedTracer.record("Process Inputs", "Elevator/Periodic"); - Logger.recordOutput("Elevator/Position", position.name()); + Logger.recordOutput( + "Elevator/Position", + lastKnownPositionEnum != null ? lastKnownPositionEnum.name() : "CUSTOM"); InternalLoggedTracer.reset(); if (isClosedLoop) { - io.setPositionGoal(position.getPosition()); + // Always use the double goal for the IO layer + io.setPositionGoal(positionGoalMeters); } InternalLoggedTracer.record("Set Position Goal", "Elevator/Periodic"); } @@ -134,7 +141,7 @@ private boolean atGoal(double position) { */ @AutoLogOutput(key = "Elevator/At Goal") private boolean atGoal() { - return Math.abs(inputs.positionGoalMeters - inputs.positionMeters) + return Math.abs(positionGoalMeters - inputs.positionMeters) <= ElevatorConstants.CONSTRAINTS.goalToleranceMeters().get(); } @@ -165,7 +172,7 @@ private Command waitUntilAtGoal() { * tolerance, false otherwise. */ private BooleanSupplier inFastScoringTolerance() { - return () -> Math.abs(inputs.positionMeters - inputs.positionGoalMeters) <= 0.03; + return () -> Math.abs(inputs.positionMeters - positionGoalMeters) <= 0.03; } /** @@ -210,28 +217,29 @@ private Command sysIdRoutine(Subsystem subsystem) { () -> Elevator.this.atGoal( ElevatorPositions.STOW.getPosition() + Units.inchesToMeters(12.0))), - subsystem.runOnce(() -> setPosition(() -> ReefState.STOW))); + subsystem.runOnce(() -> setPositionFromReef(() -> ReefState.STOW))); } - /** - * Sets the position of the elevator. - * - * @return A command that sets the elevator position. - */ - private void setPosition() { - setPosition(() -> RobotState.getOIData().currentReefHeight()); + /** Private method to set position based on ReefState. */ + private void setPositionFromReef(Supplier newPosition) { + isClosedLoop = true; + this.lastKnownPositionEnum = getPosition(newPosition.get()); + this.positionGoalMeters = this.lastKnownPositionEnum.getPosition(); } - /** - * Sets the position of the elevator. - * - * @param positionRadians The desired elevator position. - * @return A command that sets the elevator position. - */ - private void setPosition(Supplier newPosition) { + /** Private method to set position based on ElevatorPositions enum. */ + private void setPositionFromEnum(ElevatorPositions newPosition) { + isClosedLoop = true; + this.lastKnownPositionEnum = newPosition; + this.positionGoalMeters = this.lastKnownPositionEnum.getPosition(); + } + + /** Private method to set position based on a double value. */ + private void setPositionFromDouble(double newPositionMeters) { isClosedLoop = true; - Elevator.this.position = Elevator.this.getPosition(newPosition.get()); - io.setPositionGoal(Elevator.this.position.getPosition()); + this.positionGoalMeters = newPositionMeters; + // When a raw double is commanded, there's no corresponding enum state. + this.lastKnownPositionEnum = null; } public class ElevatorCSB extends SubsystemBase { @@ -243,16 +251,38 @@ public void periodic() { ExternalLoggedTracer.record("Elevator Total", "Elevator/Periodic"); } - public Command setPosition() { - return this.runOnce(() -> Elevator.this.setPosition()); + public ElevatorPositions getPosition() { + return Elevator.this.lastKnownPositionEnum; } - public ElevatorPositions getPosition() { - return Elevator.this.position; + /** + * Creates a command to set the elevator to a pre-defined position. + * + * @param newPosition The target ElevatorPositions enum. + * @return A command that sets the elevator position. + */ + public Command setPosition(ElevatorPositions newPosition) { + return this.runOnce(() -> Elevator.this.setPositionFromEnum(newPosition)); + } + + /** + * Creates a command to set the elevator to a specific height in meters. + * + * @param newPositionMeters The target height in meters. + * @return A command that sets the elevator position. + */ + public Command setPosition(double newPositionMeters) { + return this.runOnce(() -> Elevator.this.setPositionFromDouble(newPositionMeters)); } public Command setPosition(Supplier newPosition) { - return this.runOnce(() -> Elevator.this.setPosition(newPosition)); + return this.runOnce(() -> Elevator.this.setPositionFromReef(newPosition)); + } + + public Command setPosition() { + return Commands.runOnce( + () -> + Elevator.this.setPositionFromReef(() -> RobotState.getOIData().currentReefHeight())); } public Command setVoltage(double volts) { @@ -265,7 +295,7 @@ public Command setVoltage(double volts) { } public Command resetPosition() { - return runOnce(() -> Elevator.this.position = ElevatorPositions.STOW) + return runOnce(() -> Elevator.this.lastKnownPositionEnum = ElevatorPositions.STOW) .andThen( runOnce( () -> io.setPosition(ElevatorConstants.ELEVATOR_PARAMETERS.MIN_HEIGHT_METERS()))); @@ -321,19 +351,37 @@ public void periodic() { } public ElevatorPositions getPosition() { - return Elevator.this.position; + return Elevator.this.lastKnownPositionEnum; } - public void setPosition() { - Elevator.this.setPosition(); + /** + * Sets the elevator to a pre-defined position. + * + * @param newPosition The target ElevatorPositions enum. + */ + public void setPosition(ElevatorPositions newPosition) { + Elevator.this.setPositionFromEnum(newPosition); + } + + /** + * Sets the elevator to a specific height in meters. + * + * @param newPositionMeters The target height in meters. + */ + public void setPosition(double newPositionMeters) { + Elevator.this.setPositionFromDouble(newPositionMeters); } public void setPosition(Supplier newPosition) { - Elevator.this.setPosition(newPosition); + Elevator.this.setPositionFromReef(newPosition); + } + + public void setPosition() { + Elevator.this.setPositionFromReef(() -> RobotState.getOIData().currentReefHeight()); } public Command resetPosition() { - return Commands.runOnce(() -> Elevator.this.position = ElevatorPositions.STOW) + return Commands.runOnce(() -> Elevator.this.lastKnownPositionEnum = ElevatorPositions.STOW) .andThen( Commands.runOnce( () -> io.setPosition(ElevatorConstants.ELEVATOR_PARAMETERS.MIN_HEIGHT_METERS()))); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 85a68523..dbdc9a6d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -3,6 +3,7 @@ import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.apriltag.AprilTagFields; import edu.wpi.first.networktables.NetworkTablesJNI; +import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; @@ -11,6 +12,7 @@ import frc.robot.RobotContainer; import frc.robot.RobotState; import frc.robot.commands.AutonomousCommands; +import frc.robot.commands.CompositeCommands; import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.drive.DriveConstants; @@ -167,6 +169,8 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { - return autoChooser.selectedCommand(); + return CompositeCommands.V3_EpsilonCompositeCommands.createTrajectoryTestCommand( + superstructure, new Timer()); + // return autoChooser.selectedCommand(); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 06ac9d0d..0c69cbfe 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -11,6 +11,7 @@ import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.EdgeCommand; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.GamePieceEdge; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureKinematics.JointSolution; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; @@ -620,4 +621,10 @@ public Command allTransition() { public boolean armBelowThreshold() { return manipulator.getArmAngle().getDegrees() >= 90; } + + public void runIK(double py, double pz) { + JointSolution sol = V3_EpsilonSuperstructureKinematics.ik(py, pz); + elevator.setPosition(sol.d3()); + manipulator.setArmGoal(sol.theta5()); + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index c25bb111..f3c87260 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -191,7 +191,7 @@ private static Command getEdgeCommand( Commands.sequence( pose.setElevatorHeight(elevator), elevator.waitUntilAtGoal(), - pose.asCommand( + pose.asConfigurationSpaceCommand( elevator, intake, manipulator) // CORRECTED: Only move the other subsystems ); @@ -201,12 +201,12 @@ private static Command getEdgeCommand( Commands.sequence( pose.setManipulatorState(manipulator), Commands.waitUntil(manipulator::isSafePosition), - pose.asCommand( + pose.asConfigurationSpaceCommand( elevator, intake, manipulator) // CORRECTED: Only move the other subsystems ); } else { // Default case: All mechanisms move in parallel. - moveCommand = pose.asCommand(elevator, intake, manipulator); + moveCommand = pose.asConfigurationSpaceCommand(elevator, intake, manipulator); } if (from == V3_EpsilonSuperstructureStates.HANDOFF) { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureKinematics.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureKinematics.java new file mode 100644 index 00000000..40eb09b1 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureKinematics.java @@ -0,0 +1,96 @@ +package frc.robot.subsystems.v3_Epsilon.superstructure; + +import edu.wpi.first.math.MatBuilder; +import edu.wpi.first.math.Matrix; +import edu.wpi.first.math.Nat; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.numbers.N4; +import edu.wpi.first.math.util.Units; + +public class V3_EpsilonSuperstructureKinematics { + + // -------------------------- DH Parameters ------------------------- + // [0 0 -l1 0] + // [pi/2 0 0 0] + // [0 l3+d3 0 0] + // [0 0 0 pi/2] + // [0 l5 0 0] + // [theta5 0 0 -pi/2] + // [-pi/2 l7 0 0] + + // -------- Homogeneous Transform from Base to End Effector --------- + // [1, 0, 0, -l1 + l5] + // [0, cos(theta5), -sin(theta5), -l7*sin(theta5)] + // [0, sin(theta5), cos(theta5), d3 + l3 + l7*cos(theta5)] + // [0, 0, 0, 1] + + private static final double l1; + private static final double l3; + private static final double l5; + private static final double l7; + + static { + l1 = Units.inchesToMeters(7.0); + l3 = Units.inchesToMeters(11.351122); + l5 = Units.inchesToMeters(7.0); + l7 = Units.inchesToMeters(22.259494); + } + + private static final Matrix fkMat(double d3, Rotation2d theta5) { + double cos5 = theta5.getCos(); + double sin5 = theta5.getSin(); + + return MatBuilder.fill( + Nat.N4(), + Nat.N4(), + 1, + 0, + 0, + -l1 + l5, + 0, + cos5, + -sin5, + -l7 * sin5, + 0, + sin5, + cos5, + d3 + l3 + l7 * cos5, + 0, + 0, + 0, + 1); + } + + /** + * (Forward Kinematics) Calculates the end-effector's world coordinates. + * + * @return A Translation2d representing the (x, y) world coordinate. + */ + public static EndEffectorPose fk(double d3, Rotation2d theta5) { + Matrix t = fkMat(d3, theta5); + // Note: The FK matrix seems to be in the YZ plane based on the ik function signature. + // We'll return the y and z components. + return new EndEffectorPose(t.get(1, 3), t.get(2, 3)); + } + + /** + * (Inverse Kinematics) Calculates the required joint states for a target coordinate. + * + * @param py The target y-position in the robot's frame. + * @param pz The target z-position in the robot's frame. + * @return A JointSolution containing the required d3 and theta5 values. + */ + public static JointSolution ik(double py, double pz) { + Rotation2d theta5 = + Rotation2d.fromRadians(Math.atan2(Math.sqrt(1 - Math.pow((py / l7), 2)), py / l7)) + .minus(Rotation2d.kCCW_Pi_2); + double d3 = + pz - l3 - (l7 * Math.sin(Math.atan2(Math.sqrt(1 - Math.pow((py / l7), 2)), py / l7))); + + return new JointSolution(d3, theta5); + } + + public static record EndEffectorPose(double y, double z) {} + + public static record JointSolution(double d3, Rotation2d theta5) {} +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java index 51afa248..6b372cd2 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java @@ -76,7 +76,7 @@ public Command setManipulatorState(V3_EpsilonManipulator manipulator) { * @param manipulator The manipulator subsystem. * @return A Command that sets all subsystems to their respective states in parallel. */ - public Command asCommand( + public Command asConfigurationSpaceCommand( ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { return Commands.parallel( Commands.runOnce(() -> elevator.setPosition(() -> elevatorHeight)), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index ffac056c..6e90927f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -8,9 +8,6 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; -// correct package -// path - public enum V3_EpsilonSuperstructureStates { START("START", new SubsystemPoses(), SubsystemActions.empty()), STOW_DOWN( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 324e3518..2b757854 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -19,7 +19,7 @@ public class V3_EpsilonManipulator { @AutoLogOutput(key = "Manipulator/Arm Goal") @Getter - private ManipulatorArmState armGoal; + private Rotation2d armGoal; @Setter @Getter @@ -39,7 +39,7 @@ public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { inputs = new ManipulatorIOInputsAutoLogged(); isClosedLoop = true; - armGoal = ManipulatorArmState.VERTICAL_UP; + armGoal = ManipulatorArmState.VERTICAL_UP.getAngle(armSide); armSide = Side.POSITIVE; rollerGoal = ManipulatorRollerState.STOP; @@ -51,7 +51,7 @@ public void periodic() { Logger.processInputs("Manipulator", inputs); if (isClosedLoop) { - Rotation2d goal = armGoal.getAngle(armSide); + Rotation2d goal = armGoal; if (!isSafePosition() || clearsElevator) { if (armSide == Side.POSITIVE) { @@ -95,6 +95,11 @@ public Command runArm(double volts) { } public void setArmGoal(ManipulatorArmState goal) { + isClosedLoop = true; + armGoal = goal.getAngle(armSide); + } + + public void setArmGoal(Rotation2d goal) { isClosedLoop = true; armGoal = goal; } @@ -132,8 +137,8 @@ public boolean armAtGoal() { return armAtGoal(armGoal); } - public boolean armAtGoal(ManipulatorArmState state) { - return Math.abs(inputs.armPosition.minus(state.getAngle(armSide)).getRadians()) + public boolean armAtGoal(Rotation2d state) { + return Math.abs(inputs.armPosition.minus(state).getRadians()) <= V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); } diff --git a/src/main/java/frc/robot/util/TrajectoryGenerator.java b/src/main/java/frc/robot/util/TrajectoryGenerator.java new file mode 100644 index 00000000..0aa52f16 --- /dev/null +++ b/src/main/java/frc/robot/util/TrajectoryGenerator.java @@ -0,0 +1,96 @@ +package frc.robot.util; + +import edu.wpi.first.math.Matrix; +import edu.wpi.first.math.Nat; +import edu.wpi.first.math.numbers.N1; +import edu.wpi.first.math.numbers.N6; + +public class TrajectoryGenerator { + /** + * Generates the 6 coefficients for a quintic polynomial trajectory. + * + * @param x_i Initial position + * @param v_i Initial velocity + * @param a_i Initial acceleration + * @param x_f Final position + * @param v_f Final velocity + * @param a_f Final acceleration + * @param t_i Initial time + * @param t_f Final time + * @return A 6x1 column vector of the polynomial coefficients (c₀ to c₅). + */ + public static final Matrix generateQuinticTrajectory( + double x_i, + double v_i, + double a_i, + double x_f, + double v_f, + double a_f, + double t_i, + double t_f) { + Matrix A = + new Matrix<>( + Nat.N6(), + Nat.N6(), + new double[] { + 1, + t_i, + Math.pow(t_i, 2), + Math.pow(t_i, 3), + Math.pow(t_i, 4), + Math.pow(t_i, 5), + 0, + 1, + 2 * t_i, + 3 * Math.pow(t_i, 2), + 4 * Math.pow(t_i, 3), + 5 * Math.pow(t_i, 4), + 0, + 0, + 2, + 6 * t_i, + 12 * Math.pow(t_i, 2), + 20 * Math.pow(t_i, 3), + 1, + t_f, + Math.pow(t_f, 2), + Math.pow(t_f, 3), + Math.pow(t_f, 4), + Math.pow(t_f, 5), + 0, + 1, + 2 * t_f, + 3 * Math.pow(t_f, 2), + 4 * Math.pow(t_f, 3), + 5 * Math.pow(t_f, 4), + 0, + 0, + 2, + 6 * t_f, + 12 * Math.pow(t_f, 2), + 20 * Math.pow(t_f, 3) + }); + + // The vector of boundary conditions + Matrix B = + new Matrix<>(Nat.N6(), Nat.N1(), new double[] {x_i, v_i, a_i, x_f, v_f, a_f}); + + return A.solve(B); + } + + /** + * Evaluates the position at a given time using the calculated trajectory coefficients. + * + * @param coeffs The 6x1 coefficient vector from generateQuinticTrajectory. + * @param t The time at which to evaluate the position. + * @return The position at time t. + */ + public static final double evaluateQuinticTrajectory(Matrix coeffs, double t) { + return coeffs.get(0, 0) + + coeffs.get(1, 0) * t + + coeffs.get(2, 0) * Math.pow(t, 2) + + coeffs.get(3, 0) * Math.pow(t, 3) + + coeffs.get(4, 0) * Math.pow(t, 4) + + coeffs.get(5, 0) * Math.pow(t, 5); + } +} From 27775666d00140aa6295f80706a69f189b2cbf44 Mon Sep 17 00:00:00 2001 From: Anshu Date: Thu, 16 Oct 2025 12:20:00 -0400 Subject: [PATCH 123/180] V3 bringup sim (#144) * set up for tuning Co-authored-by: SeptimusHeap7 Co-authored-by: Sriaditya Vaddadi Co-authored-by: Abhiraam Venigalla Co-authored-by: jasminepalit Co-authored-by: Prabhudesai, Arnav * implement updates in talonfx * LTN fix (#140) Fix LTNs (and make it more readable) * progress from today --------- Co-authored-by: SeptimusHeap7 Co-authored-by: Sriaditya Vaddadi Co-authored-by: Abhiraam Venigalla Co-authored-by: jasminepalit Co-authored-by: Prabhudesai, Arnav --- src/main/java/frc/robot/Constants.java | 2 +- .../shared/elevator/ElevatorConstants.java | 16 +- .../v0_Funky/V0_FunkyRobotContainer.java | 5 +- .../V0_WhiplashRobotContainer.java | 4 +- .../v1_StackUp/V1_StackUpRobotContainer.java | 17 +- .../V2_RedundancyRobotContainer.java | 9 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 75 +++++---- .../intake/V3_EpsilonIntake.java | 46 +++++ .../intake/V3_EpsilonIntakeConstants.java | 46 ++++- .../intake/V3_EpsilonIntakeIOSim.java | 12 +- .../intake/V3_EpsilonIntakeIOTalonFX.java | 44 ++++- .../manipulator/V3_EpsilonManipulator.java | 36 ++++ .../V3_EpsilonManipulatorConstants.java | 8 +- .../manipulator/V3_EpsilonManipulatorIO.java | 2 + .../V3_EpsilonManipulatorIOSim.java | 4 +- .../V3_EpsilonManipulatorIOTalonFX.java | 53 ++++++ src/main/java/frc/robot/util/LTNUpdater.java | 158 +++++++++++++++--- .../frc/robot/util/LoggedTunableNumber.java | 108 +++++++++++- 18 files changed, 532 insertions(+), 113 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 77e7e874..0b2ef474 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -3,7 +3,7 @@ import edu.wpi.first.wpilibj.RobotBase; public final class Constants { - public static final boolean TUNING_MODE = false; + public static final boolean TUNING_MODE = true; public static final double LOOP_PERIOD_SECONDS = 0.02; public static final RobotType ROBOT = RobotType.V3_EPSILON_SIM; diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index e59ba17c..874c3a42 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -62,7 +62,7 @@ public class ElevatorConstants { default: GAINS = new Gains( - new LoggedTunableNumber("Elevator/Gains/kP", 2.0), + new LoggedTunableNumber("Elevator/Gains/kP", 67.000000), new LoggedTunableNumber("Elevator/Gains/kD", 0.1), new LoggedTunableNumber("Elevator/Gains/kS", 0.225), new LoggedTunableNumber("Elevator/Gains/kG", 0.075), @@ -70,12 +70,12 @@ public class ElevatorConstants { new LoggedTunableNumber("Elevator/Gains/kA", 0.0)); CONSTRAINTS = new Constraints( - new LoggedTunableNumber("Elevator/Max Acceleration", 16.0), - new LoggedTunableNumber("Elevator/Cruising Velocity", 16.0), + new LoggedTunableNumber("Elevator/Max Acceleration", 190.0), + new LoggedTunableNumber("Elevator/Cruising Velocity", 41.0), new LoggedTunableNumber("Elevator/Goal Tolerance", 0.02)); STOW_GAINS = new Gains( - new LoggedTunableNumber("Elevator/Gains/kP", 2.0), + new LoggedTunableNumber("Elevator/Gains/kP", 67.000000), new LoggedTunableNumber("Elevator/Gains/kD", 0.1), new LoggedTunableNumber("Elevator/Gains/kS", 0.225), new LoggedTunableNumber("Elevator/Gains/kG", 0.075), @@ -213,16 +213,16 @@ public class ElevatorConstants { default: GAINS = new Gains( - new LoggedTunableNumber("Elevator/Gains/kP", 2.0), - new LoggedTunableNumber("Elevator/Gains/kD", 0.1), + new LoggedTunableNumber("Elevator/Gains/kP", 1), + new LoggedTunableNumber("Elevator/Gains/kD", 0.0), new LoggedTunableNumber("Elevator/Gains/kS", 0.225), new LoggedTunableNumber("Elevator/Gains/kG", 0.075), new LoggedTunableNumber("Elevator/Gains/kV", 0.0), new LoggedTunableNumber("Elevator/Gains/kA", 0.0)); CONSTRAINTS = new Constraints( - new LoggedTunableNumber("Elevator/Max Acceleration", 16.0), - new LoggedTunableNumber("Elevator/Cruising Velocity", 16.0), + new LoggedTunableNumber("Elevator/Max Acceleration", 1), + new LoggedTunableNumber("Elevator/Cruising Velocity", 1), new LoggedTunableNumber("Elevator/Goal Tolerance", 0.02)); STOW_GAINS = new Gains( diff --git a/src/main/java/frc/robot/subsystems/v0_Funky/V0_FunkyRobotContainer.java b/src/main/java/frc/robot/subsystems/v0_Funky/V0_FunkyRobotContainer.java index 86bced52..d3ff93bb 100644 --- a/src/main/java/frc/robot/subsystems/v0_Funky/V0_FunkyRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v0_Funky/V0_FunkyRobotContainer.java @@ -25,6 +25,7 @@ import frc.robot.subsystems.v0_Funky.kitbot_roller.V0_FunkyRollerIO; import frc.robot.subsystems.v0_Funky.kitbot_roller.V0_FunkyRollerIOTalonFX; import frc.robot.util.LTNUpdater; +import frc.robot.util.LoggedTunableNumber; import org.littletonrobotics.junction.networktables.LoggedDashboardChooser; public class V0_FunkyRobotContainer implements RobotContainer { @@ -75,6 +76,8 @@ public V0_FunkyRobotContainer() { break; } } + + LTNUpdater.registerDrive(drive); } public void configureButtonBindings() { @@ -112,7 +115,7 @@ public void robotPeriodic() { drive.getModulePositions(), vision.getCameras()); - LTNUpdater.updateDrive(drive); + LoggedTunableNumber.updateAll(); } @Override diff --git a/src/main/java/frc/robot/subsystems/v0_Whiplash/V0_WhiplashRobotContainer.java b/src/main/java/frc/robot/subsystems/v0_Whiplash/V0_WhiplashRobotContainer.java index 257275d0..6067944a 100644 --- a/src/main/java/frc/robot/subsystems/v0_Whiplash/V0_WhiplashRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v0_Whiplash/V0_WhiplashRobotContainer.java @@ -19,7 +19,7 @@ import frc.robot.subsystems.shared.drive.ModuleIOSim; import frc.robot.subsystems.shared.drive.ModuleIOTalonFX; import frc.robot.subsystems.shared.vision.Vision; -import frc.robot.util.LTNUpdater; +import frc.robot.util.LoggedTunableNumber; import org.littletonrobotics.junction.networktables.LoggedDashboardChooser; public class V0_WhiplashRobotContainer implements RobotContainer { @@ -108,7 +108,7 @@ public void robotPeriodic() { drive.getYawVelocity(), drive.getModulePositions(), vision.getCameras()); - LTNUpdater.updateDrive(drive); + LoggedTunableNumber.updateAll(); } @Override diff --git a/src/main/java/frc/robot/subsystems/v1_StackUp/V1_StackUpRobotContainer.java b/src/main/java/frc/robot/subsystems/v1_StackUp/V1_StackUpRobotContainer.java index 7749ad61..5e995bbb 100644 --- a/src/main/java/frc/robot/subsystems/v1_StackUp/V1_StackUpRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v1_StackUp/V1_StackUpRobotContainer.java @@ -50,6 +50,7 @@ import frc.robot.subsystems.v1_StackUp.manipulator.V1_StackUpManipulatorIOSim; import frc.robot.subsystems.v1_StackUp.manipulator.V1_StackUpManipulatorIOTalonFX; import frc.robot.util.LTNUpdater; +import frc.robot.util.LoggedTunableNumber; import org.littletonrobotics.junction.Logger; public class V1_StackUpRobotContainer implements RobotContainer { @@ -137,6 +138,7 @@ public V1_StackUpRobotContainer() { if (vision == null) { vision = new Vision(() -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded)); } + LTNUpdater.registerAll(drive, elevator, funnel); configureButtonBindings(); configureAutos(); @@ -208,10 +210,13 @@ private void configureButtonBindings() { driver.rightBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))); // Driver algae - /*driver.back().onTrue(manipulator.toggleAlgaeArm()); - driver - .start() - .onTrue(AlgaeCommands.twerk(drive, elevator, manipulator, RobotCameras.V1_STACKUP_CAMS));*/ + /* + * driver.back().onTrue(manipulator.toggleAlgaeArm()); + * driver + * .start() + * .onTrue(AlgaeCommands.twerk(drive, elevator, manipulator, + * RobotCameras.V1_STACKUP_CAMS)); + */ // Driver POV driver.povUp().onTrue(elevator.setPosition()); @@ -327,9 +332,7 @@ public void robotPeriodic() { drive.getModulePositions(), vision.getCameras()); - LTNUpdater.updateDrive(drive); - LTNUpdater.updateElevator(elevator); - LTNUpdater.updateFunnel(funnel); + LoggedTunableNumber.updateAll(); if (Constants.getMode().equals(Mode.SIM)) { Logger.recordOutput( diff --git a/src/main/java/frc/robot/subsystems/v2_Redundancy/V2_RedundancyRobotContainer.java b/src/main/java/frc/robot/subsystems/v2_Redundancy/V2_RedundancyRobotContainer.java index 8039fd68..6593e392 100644 --- a/src/main/java/frc/robot/subsystems/v2_Redundancy/V2_RedundancyRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v2_Redundancy/V2_RedundancyRobotContainer.java @@ -57,6 +57,7 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorIOTalonFX; import frc.robot.util.LTNUpdater; import frc.robot.util.LoggedChoreo.ChoreoChooser; +import frc.robot.util.LoggedTunableNumber; import org.littletonrobotics.junction.Logger; public class V2_RedundancyRobotContainer implements RobotContainer { @@ -155,6 +156,8 @@ public V2_RedundancyRobotContainer() { } superstructure = new V2_RedundancySuperstructure(elevator, funnel, intake, manipulator); + LTNUpdater.registerAll(drive, elevator, funnel, intake, manipulator); + configureButtonBindings(); configureAutos(); } @@ -428,11 +431,7 @@ public void robotPeriodic() { drive.getModulePositions(), vision.getCameras()); - LTNUpdater.updateDrive(drive); - LTNUpdater.updateElevator(elevator); - LTNUpdater.updateFunnel(funnel); - LTNUpdater.updateAlgaeArm(manipulator); - LTNUpdater.updateIntake(intake); + LoggedTunableNumber.updateAll(); Logger.recordOutput( "Component Poses", diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index c84b291c..bb7c4988 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -36,10 +36,12 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOSim; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOTalonFX; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIO; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOSim; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOTalonFX; import frc.robot.util.LTNUpdater; +import frc.robot.util.LoggedTunableNumber; import org.ironmaple.simulation.SimulatedArena; import org.littletonrobotics.junction.Logger; @@ -99,32 +101,35 @@ public V3_EpsilonRobotContainer() { default: break; } + } - if (drive == null) { - drive = - new Drive( - new GyroIO() {}, - new ModuleIO() {}, - new ModuleIO() {}, - new ModuleIO() {}, - new ModuleIO() {}); - } - if (elevator == null) { - elevator = new Elevator(new ElevatorIO() {}).getFSM(); - } - if (intake == null) { - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); - } - if (manipulator == null) { - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); - } - if (climber == null) { - climber = new V3_EpsilonClimber(new V3_EpsilonClimberIO() {}); - } - if (superstructure == null) { - superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); - } + if (drive == null) { + drive = + new Drive( + new GyroIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}); + } + if (elevator == null) { + elevator = new Elevator(new ElevatorIO() {}).getFSM(); } + if (intake == null) { + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); + } + if (manipulator == null) { + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); + } + if (climber == null) { + climber = new V3_EpsilonClimber(new V3_EpsilonClimberIO() {}); + } + if (superstructure == null) { + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + } + + LTNUpdater.registerAll(drive, elevator, intake, manipulator); + configureButtonBindings(); } @@ -148,6 +153,13 @@ private void configureButtonBindings() { V3_EpsilonCompositeCommands.intakeCoralDriverSequence( superstructure, intake, manipulator)) .whileFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF)); + + driver + .a() + .toggleOnTrue( + superstructure.override(() -> manipulator.setArmGoal(ManipulatorArmState.HANDOFF))) + .toggleOnFalse( + superstructure.override(() -> manipulator.setArmGoal(ManipulatorArmState.VERTICAL_UP))); } private void configureAutos() {} @@ -165,8 +177,7 @@ public void robotPeriodic() { drive.getModulePositions(), vision.getCameras()); - LTNUpdater.updateDrive(drive); - LTNUpdater.updateElevator(elevator); + LoggedTunableNumber.updateAll(); Logger.recordOutput( "Component Poses", @@ -187,16 +198,6 @@ public void robotPeriodic() { */ @Override public Command getAutonomousCommand() { - return superstructure.allTransition(); - // return superstructure.allTransition(); - // return Commands.sequence( - // V3_EpsilonCompositeCommands.dropAlgae( - // drive, - // elevator, - // manipulator, - // intake, - // superstructure, - // () -> ReefState.ALGAE_INTAKE_TOP, - // RobotCameras.V3_EPSILON_CAMS)); + return manipulator.sysIdRoutine(superstructure); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index 7e0ed519..cc8703a4 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -1,8 +1,13 @@ package frc.robot.subsystems.v3_Epsilon.superstructure.intake; +import static edu.wpi.first.units.Units.*; + import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; +import edu.wpi.first.wpilibj2.command.Subsystem; +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakePivotState; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakeRollerState; import java.util.Set; @@ -150,6 +155,39 @@ public void setRollerGoal(IntakeRollerState rollerGoal) { } } + /** + * Runs the SysId routine for the intake subsystem + * + * @param subsystem The subsystem to run the SysId routine on. + * @return A command that runs the SysId routine. + */ + public Command sysIdRoutine(Subsystem subsystem) { + + SysIdRoutine characterizationRoutine = + new SysIdRoutine( + new SysIdRoutine.Config( + Volts.of(0.1).per(Second), + Volts.of(1), + Seconds.of(6), + (state) -> Logger.recordOutput("Intake/SysID State", state.toString())), + new SysIdRoutine.Mechanism( + (volts) -> io.setPivotVoltage(volts.in(Volts)), null, subsystem)); + + return Commands.sequence( + characterizationRoutine + .quasistatic(Direction.kForward) + .until(() -> pivotAtGoal(IntakePivotState.INTAKE_CORAL)), + characterizationRoutine + .quasistatic(Direction.kReverse) + .until(() -> pivotAtGoal(IntakePivotState.HANDOFF)), + characterizationRoutine + .dynamic(Direction.kForward) + .until(() -> pivotAtGoal(IntakePivotState.INTAKE_CORAL)), + characterizationRoutine + .dynamic(Direction.kReverse) + .until(() -> pivotAtGoal(IntakePivotState.HANDOFF))); + } + /** * Gets the current angle of the intake pivot motor. * @@ -158,4 +196,12 @@ public void setRollerGoal(IntakeRollerState rollerGoal) { public Rotation2d getPivotAngle() { return inputs.pivotPosition; } + + public void updateIntakeGains(double kP, double kD, double kS, double kV, double kA, double kG) { + io.updateIntakeGains(kP, kD, kS, kV, kA, kG); + } + + public void updateIntakeConstraints(double maxAcceleration, double cruisingVelocity) { + io.updateIntakeConstraints(maxAcceleration, cruisingVelocity); + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index 02b16835..d105b879 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -3,6 +3,7 @@ import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.system.plant.DCMotor; import frc.robot.Constants; +import frc.robot.util.LoggedTunableNumber; import lombok.Getter; import lombok.RequiredArgsConstructor; @@ -46,15 +47,37 @@ public class V3_EpsilonIntakeConstants { switch (Constants.ROBOT) { case V3_EPSILON_SIM: - PIVOT_CONSTRAINTS = new Constraints(500.0, 500.0, Rotation2d.fromDegrees(1.5)); - PIVOT_GAINS = new Gains(1.0, 0.01, 0.0, 0.0, 0.0, 0.0); + PIVOT_CONSTRAINTS = + new Constraints( + new LoggedTunableNumber("Intake/Max Acceleration", 100.0), + new LoggedTunableNumber("Intake/Cruising Velocity", 75.0), + Rotation2d.fromDegrees(1.5)); + PIVOT_GAINS = + new Gains( + new LoggedTunableNumber("Intake/kP", 1.85), + new LoggedTunableNumber("Intake/kD", 0.1), + new LoggedTunableNumber("Intake/kS", 0.0), + new LoggedTunableNumber("Intake/kV", 0.0), + new LoggedTunableNumber("Intake/kA", 0.011537), + new LoggedTunableNumber("Intake/kG", 0.15326)); CURRENT_LIMITS = new IntakeCurrentLimits(40.0, 40.0, 40.0, 40.0, 40.0, 40.0); break; default: - PIVOT_CONSTRAINTS = new Constraints(500.0, 500.0, Rotation2d.fromDegrees(1.5)); - PIVOT_GAINS = new Gains(0.0, 0.0, 0.0, 0.0, 0.0, 0.0); + PIVOT_CONSTRAINTS = + new Constraints( + new LoggedTunableNumber("Intake/Max Acceleration", 0.0), + new LoggedTunableNumber("Intake/Cruising Velocity", 0.0), + Rotation2d.fromDegrees(1.5)); + PIVOT_GAINS = + new Gains( + new LoggedTunableNumber("Intake/kP", 1.85), + new LoggedTunableNumber("Intake/kD", 0.1), + new LoggedTunableNumber("Intake/kS", 0.0), + new LoggedTunableNumber("Intake/kV", 0.0), + new LoggedTunableNumber("Intake/kA", 0.0), + new LoggedTunableNumber("Intake/kG", 0.0)); CURRENT_LIMITS = new IntakeCurrentLimits(40.0, 40.0, 40.0, 40.0, 40.0, 40.0); break; @@ -81,15 +104,22 @@ public static record IntakeCurrentLimits( double OUTER_ROLLER_SUPPLY_CURRENT_LIMIT, double OUTER_ROLLER_STATOR_CURRENT_LIMIT) {} - public static record Gains(double kP, double kD, double kS, double kV, double kA, double kG) {} + public static record Gains( + LoggedTunableNumber kP, + LoggedTunableNumber kD, + LoggedTunableNumber kS, + LoggedTunableNumber kV, + LoggedTunableNumber kA, + LoggedTunableNumber kG) {} public static record Constraints( - double MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED, - double CRUISING_VELOCITY_RADIANS_PER_SECOND, + LoggedTunableNumber MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED, + LoggedTunableNumber CRUISING_VELOCITY_RADIANS_PER_SECOND, Rotation2d GOAL_TOLERANCE) { public edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints getTrapezoidConstraints() { return new edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints( - CRUISING_VELOCITY_RADIANS_PER_SECOND, MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED); + CRUISING_VELOCITY_RADIANS_PER_SECOND.get(), + MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED.get()); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java index 17026919..8de107a9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java @@ -57,18 +57,18 @@ public V3_EpsilonIntakeIOSim() { armFeedbackController = new ProfiledPIDController( - V3_EpsilonIntakeConstants.PIVOT_GAINS.kP(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kP().get(), 0.0, - V3_EpsilonIntakeConstants.PIVOT_GAINS.kD(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kD().get(), V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.getTrapezoidConstraints()); armFeedbackController.disableContinuousInput(); armFeedforwardController = new ArmFeedforward( - V3_EpsilonIntakeConstants.PIVOT_GAINS.kS(), - V3_EpsilonIntakeConstants.PIVOT_GAINS.kA(), - V3_EpsilonIntakeConstants.PIVOT_GAINS.kV(), - V3_EpsilonIntakeConstants.PIVOT_GAINS.kA()); + V3_EpsilonIntakeConstants.PIVOT_GAINS.kS().get(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kA().get(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kV().get(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kA().get()); pivotAppliedVoltage = 0.0; rollerInnerAppliedVoltage = 0.0; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java index 45f1a293..e3185f75 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java @@ -2,6 +2,8 @@ import static edu.wpi.first.units.Units.RadiansPerSecond; import static edu.wpi.first.units.Units.RadiansPerSecondPerSecond; +import static edu.wpi.first.units.Units.RotationsPerSecond; +import static edu.wpi.first.units.Units.RotationsPerSecondPerSecond; import static frc.robot.util.PhoenixUtil.*; import com.ctre.phoenix6.StatusSignal; @@ -100,23 +102,25 @@ public V3_EpsilonIntakeIOTalonFX() { pivotConfig.Slot0 = new Slot0Configs() .withGravityType(GravityTypeValue.Arm_Cosine) - .withKP(V3_EpsilonIntakeConstants.PIVOT_GAINS.kP()) - .withKD(V3_EpsilonIntakeConstants.PIVOT_GAINS.kD()) - .withKA(V3_EpsilonIntakeConstants.PIVOT_GAINS.kA()) - .withKV(V3_EpsilonIntakeConstants.PIVOT_GAINS.kV()) - .withKS(V3_EpsilonIntakeConstants.PIVOT_GAINS.kS()) - .withKG(V3_EpsilonIntakeConstants.PIVOT_GAINS.kG()); + .withKP(V3_EpsilonIntakeConstants.PIVOT_GAINS.kP().get()) + .withKD(V3_EpsilonIntakeConstants.PIVOT_GAINS.kD().get()) + .withKA(V3_EpsilonIntakeConstants.PIVOT_GAINS.kA().get()) + .withKV(V3_EpsilonIntakeConstants.PIVOT_GAINS.kV().get()) + .withKS(V3_EpsilonIntakeConstants.PIVOT_GAINS.kS().get()) + .withKG(V3_EpsilonIntakeConstants.PIVOT_GAINS.kG().get()); pivotConfig.MotionMagic = new MotionMagicConfigs() .withMotionMagicCruiseVelocity( AngularVelocity.ofRelativeUnits( V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS - .CRUISING_VELOCITY_RADIANS_PER_SECOND(), + .CRUISING_VELOCITY_RADIANS_PER_SECOND() + .get(), RadiansPerSecond)) .withMotionMagicAcceleration( AngularAcceleration.ofRelativeUnits( V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS - .MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED(), + .MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED() + .get(), RadiansPerSecondPerSecond)); tryUntilOk(5, () -> pivotTalonFX.getConfigurator().apply(pivotConfig, 0.25)); @@ -301,4 +305,28 @@ public void setPivotMotionMagic(Rotation2d position) { pivotTalonFX.setControl( pivotMotionMagicRequest.withPosition(position.getMeasure()).withEnableFOC(true)); } + + public void updateIntakeGains(double kP, double kD, double kS, double kG, double kV, double kA) { + pivotConfig.Slot0.kP = kP; + pivotConfig.Slot0.kD = kD; + pivotConfig.Slot0.kS = kS; + pivotConfig.Slot0.kG = kG; + pivotConfig.Slot0.kV = kV; + pivotConfig.Slot0.kA = kA; + + tryUntilOk(5, () -> pivotTalonFX.getConfigurator().apply(pivotConfig, 0.25)); + } + + public void updateIntakeConstraints( + double maxVelocityRadiansPerSecond, double maxAccelerationRadiansPerSecondSquared) { + pivotConfig.MotionMagic.MotionMagicCruiseVelocity = + AngularVelocity.ofRelativeUnits(maxVelocityRadiansPerSecond, RadiansPerSecond) + .in(RotationsPerSecond); + pivotConfig.MotionMagic.MotionMagicAcceleration = + AngularAcceleration.ofRelativeUnits( + maxAccelerationRadiansPerSecondSquared, RadiansPerSecondPerSecond) + .in(RotationsPerSecondPerSecond); + + tryUntilOk(5, () -> pivotTalonFX.getConfigurator().apply(pivotConfig, 0.25)); + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 2209697e..68bccf79 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -1,9 +1,17 @@ package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; +import static edu.wpi.first.units.Units.Second; +import static edu.wpi.first.units.Units.Seconds; +import static edu.wpi.first.units.Units.Volts; + import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; +import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; +import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.Side; @@ -259,6 +267,34 @@ public void setSlot() { } } + /** + * Creates a command to run the SysId routine for the manipulator arm, generating the constants + * and gains for a PID. + * + * @param superstructure The V3 Epsiolon Superstructure. + * @return A command to run the SysId routine for the manipulator arm. + */ + public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { + SysIdRoutine algaeCharacterizationRoutine = + new SysIdRoutine( + new SysIdRoutine.Config( + Volts.of(0.5).per(Second), + Volts.of(6), + Seconds.of(4), + (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), + new SysIdRoutine.Mechanism( + (volts) -> io.setArmVoltage(volts.in(Volts)), null, superstructure)); + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), + Commands.runOnce(() -> isClosedLoop = false), + algaeCharacterizationRoutine.quasistatic(Direction.kForward), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.quasistatic(Direction.kReverse), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.dynamic(Direction.kForward), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.dynamic(Direction.kReverse)); + } /** * Sets the manipulator arm to the specified state. * diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 0f011e3c..a1e517f9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -90,12 +90,12 @@ public class V3_EpsilonManipulatorConstants { default: EMPTY_GAINS = new Gains( - new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 50), + new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 1), new LoggedTunableNumber("Manipulator/Arm/Empty/kD", 0), - new LoggedTunableNumber("Manipulator/Arm/Empty/kS", 0.24274), + new LoggedTunableNumber("Manipulator/Arm/Empty/kS", 0.00014503), new LoggedTunableNumber("Manipulator/Arm/Empty/kG", 0.66177), - new LoggedTunableNumber("Manipulator/Arm/Empty/kV", 0), - new LoggedTunableNumber("Manipulator/Arm/Empty/kA", 0)); + new LoggedTunableNumber("Manipulator/Arm/Empty/kV", 1.7708), + new LoggedTunableNumber("Manipulator/Arm/Empty/kA", 0.00032712)); CORAL_GAINS = new Gains( new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kP", 125), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java index 2967a0df..61ca50d7 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java @@ -35,6 +35,8 @@ public static class ManipulatorIOInputs { */ public default void updateInputs(ManipulatorIOInputs inputs) {} + public default void setPosition() {} + /** * Sets the voltage for the manipulator. * diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java index 42f88bb6..4d5c572a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java @@ -32,7 +32,7 @@ public V3_EpsilonManipulatorIOSim() { new SingleJointedArmSim( LinearSystemId.createSingleJointedArmSystem( V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MOTOR_CONFIG(), - 0.004, + 0.4389150229, V3_EpsilonManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO()), V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MOTOR_CONFIG(), V3_EpsilonManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO(), @@ -43,7 +43,7 @@ public V3_EpsilonManipulatorIOSim() { 0.0); rollerMotorSim = new DCMotorSim( - LinearSystemId.createDCMotorSystem(DCMotor.getKrakenX60Foc(1), 0.004, 3.0), + LinearSystemId.createDCMotorSystem(DCMotor.getKrakenX60Foc(1), 0.4389150229, 3.0), DCMotor.getKrakenX60Foc(1)); slot0 = diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java index 71746f51..b17375a9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java @@ -14,6 +14,7 @@ import com.ctre.phoenix6.controls.MotionMagicVoltage; import com.ctre.phoenix6.controls.VoltageOut; import com.ctre.phoenix6.hardware.TalonFX; +import com.ctre.phoenix6.signals.GravityTypeValue; import com.ctre.phoenix6.signals.InvertedValue; import com.ctre.phoenix6.signals.NeutralModeValue; import edu.wpi.first.math.geometry.Rotation2d; @@ -223,4 +224,56 @@ public void setSlot(int slot) { throw new IllegalArgumentException("Invalid slot: " + slot); } } + + public void updateSlot0ArmGains( + double kP, double kD, double kS, double kV, double kA, double kG) { + armConfig.Slot0 = + new Slot0Configs() + .withKP(kP) + .withKD(kD) + .withKS(kS) + .withKV(kV) + .withKA(kA) + .withKG(kG) + .withGravityType(GravityTypeValue.Arm_Cosine); + tryUntilOk(5, () -> armTalonFX.getConfigurator().apply(armConfig, 0.25)); + } + + public void updateSlot1ArmGains( + double kP, double kD, double kS, double kV, double kA, double kG) { + armConfig.Slot1 = + new Slot1Configs() + .withKP(kP) + .withKD(kD) + .withKS(kS) + .withKV(kV) + .withKA(kA) + .withKG(kG) + .withGravityType(GravityTypeValue.Arm_Cosine); + tryUntilOk(5, () -> armTalonFX.getConfigurator().apply(armConfig, 0.25)); + } + + public void updateSlot2ArmGains( + double kP, double kD, double kS, double kV, double kA, double kG) { + armConfig.Slot2 = + new Slot2Configs() + .withKP(kP) + .withKD(kD) + .withKS(kS) + .withKV(kV) + .withKA(kA) + .withKG(kG) + .withGravityType(GravityTypeValue.Arm_Cosine); + tryUntilOk(5, () -> armTalonFX.getConfigurator().apply(armConfig, 0.25)); + } + + public void updateArmConstraints(double maxAcceleration, double cruisingVelocity) { + armConfig.MotionMagic = + new MotionMagicConfigs() + .withMotionMagicAcceleration( + AngularAcceleration.ofRelativeUnits(maxAcceleration, RotationsPerSecondPerSecond)) + .withMotionMagicCruiseVelocity( + AngularVelocity.ofRelativeUnits(cruisingVelocity, RotationsPerSecond)); + tryUntilOk(5, () -> armTalonFX.getConfigurator().apply(armConfig, 0.25)); + } } diff --git a/src/main/java/frc/robot/util/LTNUpdater.java b/src/main/java/frc/robot/util/LTNUpdater.java index 3a1c2db9..d7c24b50 100644 --- a/src/main/java/frc/robot/util/LTNUpdater.java +++ b/src/main/java/frc/robot/util/LTNUpdater.java @@ -13,11 +13,15 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntakeConstants; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; public class LTNUpdater { - public static final void updateDrive(Drive drive) { - LoggedTunableNumber.ifChanged( - drive.hashCode(), + + public static void registerDrive(Drive drive) { + LoggedTunableNumber.createGroup( () -> { drive.setPIDGains( DriveConstants.GAINS.drive_Kp().get(), @@ -34,8 +38,7 @@ public static final void updateDrive(Drive drive) { DriveConstants.GAINS.turn_Kp(), DriveConstants.GAINS.turn_Kd()); - LoggedTunableNumber.ifChanged( - drive.hashCode(), + LoggedTunableNumber.createGroup( () -> { DriveCommands.setRotationPID( DriveConstants.AUTO_ALIGN_GAINS.rotation_Kp().get(), @@ -50,9 +53,8 @@ public static final void updateDrive(Drive drive) { DriveConstants.AUTO_ALIGN_GAINS.translation_Kd()); } - public static final void updateElevator(ElevatorCSB elevator) { - LoggedTunableNumber.ifChanged( - elevator.hashCode(), + public static void registerElevator(ElevatorCSB elevator) { + LoggedTunableNumber.createGroup( () -> { elevator.setGains( ElevatorConstants.GAINS.kP().get(), @@ -75,9 +77,8 @@ public static final void updateElevator(ElevatorCSB elevator) { ElevatorConstants.CONSTRAINTS.cruisingVelocityMetersPerSecond()); } - public static final void updateElevator(ElevatorFSM elevator) { - LoggedTunableNumber.ifChanged( - elevator.hashCode(), + public static void registerElevator(ElevatorFSM elevator) { + LoggedTunableNumber.createGroup( () -> { elevator.setGains( ElevatorConstants.GAINS.kP().get(), @@ -100,9 +101,8 @@ public static final void updateElevator(ElevatorFSM elevator) { ElevatorConstants.CONSTRAINTS.cruisingVelocityMetersPerSecond()); } - public static final void updateFunnel(FunnelCSB funnel) { - LoggedTunableNumber.ifChanged( - funnel.hashCode(), + public static void registerFunnel(FunnelCSB funnel) { + LoggedTunableNumber.createGroup( () -> { funnel.updateGains( FunnelConstants.CLAP_DADDY_MOTOR_GAINS.kP().get(), @@ -123,9 +123,8 @@ public static final void updateFunnel(FunnelCSB funnel) { FunnelConstants.CLAP_DADDY_MOTOR_CONSTRAINTS.MAX_VELOCITY()); } - public static final void updateFunnel(FunnelFSM funnel) { - LoggedTunableNumber.ifChanged( - funnel.hashCode(), + public static void registerFunnel(FunnelFSM funnel) { + LoggedTunableNumber.createGroup( () -> { funnel.updateGains( FunnelConstants.CLAP_DADDY_MOTOR_GAINS.kP().get(), @@ -146,9 +145,8 @@ public static final void updateFunnel(FunnelFSM funnel) { FunnelConstants.CLAP_DADDY_MOTOR_CONSTRAINTS.MAX_VELOCITY()); } - public static final void updateAlgaeArm(V2_RedundancyManipulator manipulator) { - LoggedTunableNumber.ifChanged( - manipulator.hashCode(), + public static void registerAlgaeArm(V2_RedundancyManipulator manipulator) { + LoggedTunableNumber.createGroup( () -> { manipulator.updateArmGains( V2_RedundancyManipulatorConstants.WITHOUT_ALGAE_GAINS.kP().get(), @@ -189,9 +187,8 @@ public static final void updateAlgaeArm(V2_RedundancyManipulator manipulator) { .MAX_ACCELERATION_ROTATIONS_PER_SECOND_SQUARED()); } - public static final void updateIntake(V2_RedundancyIntake intake) { - LoggedTunableNumber.ifChanged( - intake.hashCode(), + public static void registerIntake(V2_RedundancyIntake intake) { + LoggedTunableNumber.createGroup( () -> { intake.updateGains( V2_RedundancyIntakeConstants.EXTENSION_MOTOR_GAINS.kP().get(), @@ -211,4 +208,119 @@ public static final void updateIntake(V2_RedundancyIntake intake) { V2_RedundancyIntakeConstants.EXTENSION_MOTOR_CONSTRAINTS.MAX_ACCELERATION(), V2_RedundancyIntakeConstants.EXTENSION_MOTOR_CONSTRAINTS.MAX_VELOCITY()); } + + public static void registerIntake(V3_EpsilonIntake intake) { + LoggedTunableNumber.createGroup( + () -> { + intake.updateIntakeGains( + V3_EpsilonIntakeConstants.PIVOT_GAINS.kP().get(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kD().get(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kS().get(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kV().get(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kA().get(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kG().get()); + intake.updateIntakeConstraints( + V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS + .MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED() + .get(), + V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS + .CRUISING_VELOCITY_RADIANS_PER_SECOND() + .get()); + }, + V3_EpsilonIntakeConstants.PIVOT_GAINS.kP(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kD(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kS(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kV(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kA(), + V3_EpsilonIntakeConstants.PIVOT_GAINS.kG(), + V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED(), + V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.CRUISING_VELOCITY_RADIANS_PER_SECOND()); + } + + public static void registerManipulatorArm(V3_EpsilonManipulator manipulator) { + LoggedTunableNumber.createGroup( + () -> { + manipulator.updateArmGains( + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kP().get(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kD().get(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kS().get(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kV().get(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kA().get(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kG().get(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kP().get(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kD().get(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kS().get(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kV().get(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kA().get(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kG().get(), + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kP().get(), + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kD().get(), + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kS().get(), + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kV().get(), + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kA().get(), + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kG().get()); + manipulator.updateArmConstraints( + V3_EpsilonManipulatorConstants.CONSTRAINTS + .maxAccelerationRotationsPerSecondSquared() + .get(), + V3_EpsilonManipulatorConstants.CONSTRAINTS + .cruisingVelocityRotationsPerSecond() + .get()); + }, + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kP(), + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kD(), + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kS(), + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kV(), + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kA(), + V3_EpsilonManipulatorConstants.ALGAE_GAINS.kG(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kP(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kD(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kS(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kV(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kA(), + V3_EpsilonManipulatorConstants.EMPTY_GAINS.kG(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kP(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kD(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kS(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kV(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kA(), + V3_EpsilonManipulatorConstants.CORAL_GAINS.kG(), + V3_EpsilonManipulatorConstants.CONSTRAINTS.maxAccelerationRotationsPerSecondSquared(), + V3_EpsilonManipulatorConstants.CONSTRAINTS.cruisingVelocityRotationsPerSecond(), + V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians()); + } + + /** + * Register all subsystem auto-updates. Call this once during robot initialization. Then call + * LoggedTunableNumber.updateAll() periodically in robotPeriodic(). + */ + public static void registerAll(Drive drive, ElevatorCSB elevator, FunnelCSB funnel) { + registerDrive(drive); + registerElevator(elevator); + registerFunnel(funnel); + } + + public static void registerAll( + Drive drive, + ElevatorFSM elevator, + FunnelFSM funnel, + V2_RedundancyIntake intake, + V2_RedundancyManipulator manipulator) { + registerDrive(drive); + registerElevator(elevator); + registerFunnel(funnel); + registerIntake(intake); + registerAlgaeArm(manipulator); + } + + public static void registerAll( + Drive drive, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + registerDrive(drive); + registerElevator(elevator); + registerIntake(intake); + registerManipulatorArm(manipulator); + } } diff --git a/src/main/java/frc/robot/util/LoggedTunableNumber.java b/src/main/java/frc/robot/util/LoggedTunableNumber.java index a9956984..2a0b848c 100644 --- a/src/main/java/frc/robot/util/LoggedTunableNumber.java +++ b/src/main/java/frc/robot/util/LoggedTunableNumber.java @@ -8,8 +8,10 @@ package frc.robot.util; import frc.robot.Constants; +import java.util.ArrayList; import java.util.Arrays; import java.util.HashMap; +import java.util.List; import java.util.Map; import java.util.function.Consumer; import java.util.function.DoubleSupplier; @@ -17,16 +19,20 @@ /** * Class for a tunable number. Gets value from dashboard in tuning mode, returns default if not or - * value not in dashboard. + * value not in dashboard. Automatically executes callbacks when values change. */ public class LoggedTunableNumber implements DoubleSupplier { private static final String tableKey = "TunableNumbers"; + private static final ArrayList strayTunableNumbers = new ArrayList<>(); + private static final List autoUpdateGroups = new ArrayList<>(); private final String key; private boolean hasDefault = false; private double defaultValue; private LoggedNetworkNumber dashboardNumber; private Map lastHasChangedValues = new HashMap<>(); + private double lastKnownValue = Double.NaN; + private List callbacks = new ArrayList<>(); /** * Create a new LoggedTunableNumber @@ -35,6 +41,7 @@ public class LoggedTunableNumber implements DoubleSupplier { */ public LoggedTunableNumber(String dashboardKey) { this.key = tableKey + "/" + dashboardKey; + strayTunableNumbers.add(this); } /** @@ -120,4 +127,103 @@ public static void ifChanged(int id, Runnable action, LoggedTunableNumber... tun public double getAsDouble() { return get(); } + + /** + * Register a callback to be executed when this tunable number changes + * + * @param callback The callback to execute when value changes + */ + public void onChange(Runnable callback) { + callbacks.add(callback); + } + + /** Check if value has changed and execute callbacks if so */ + private void checkAndUpdate() { + double currentValue = get(); + if (Double.isNaN(lastKnownValue) || currentValue != lastKnownValue) { + lastKnownValue = currentValue; + callbacks.forEach(Runnable::run); + } + } + + /** + * Create a group of tunable numbers that will execute a callback when any of them change + * + * @param callback The callback to execute when any tunable number in the group changes + * @param tunableNumbers The tunable numbers to monitor + * @return AutoUpdateGroup for further configuration if needed + */ + public static AutoUpdateGroup createGroup( + Runnable callback, LoggedTunableNumber... tunableNumbers) { + AutoUpdateGroup group = new AutoUpdateGroup(callback, tunableNumbers); + autoUpdateGroups.add(group); + strayTunableNumbers.removeAll(Arrays.asList(tunableNumbers)); + return group; + } + + /** + * Create a group of tunable numbers that will execute a callback with values when any of them + * change + * + * @param callback The callback to execute with current values when any tunable number changes + * @param tunableNumbers The tunable numbers to monitor + * @return AutoUpdateGroup for further configuration if needed + */ + public static AutoUpdateGroup createGroup( + Consumer callback, LoggedTunableNumber... tunableNumbers) { + AutoUpdateGroup group = + new AutoUpdateGroup( + () -> + callback.accept( + Arrays.stream(tunableNumbers).mapToDouble(LoggedTunableNumber::get).toArray()), + tunableNumbers); + autoUpdateGroups.add(group); + return group; + } + + /** + * Call this method periodically (e.g., in robotPeriodic) to check for changes and execute + * callbacks + */ + public static void updateAll() { + if (Constants.TUNING_MODE) { + // Update un grouped tunable numbers + strayTunableNumbers.forEach(LoggedTunableNumber::checkAndUpdate); + + // Update groups + autoUpdateGroups.forEach(AutoUpdateGroup::checkAndUpdate); + } + } + + /** Helper class for managing groups of tunable numbers */ + public static class AutoUpdateGroup { + private final Runnable callback; + private final LoggedTunableNumber[] tunableNumbers; + private final Map lastValues = new HashMap<>(); + + private AutoUpdateGroup(Runnable callback, LoggedTunableNumber... tunableNumbers) { + this.callback = callback; + this.tunableNumbers = tunableNumbers; + // Initialize last values + for (LoggedTunableNumber number : tunableNumbers) { + lastValues.put(number, number.get()); + } + } + + private void checkAndUpdate() { + boolean hasChanged = false; + for (LoggedTunableNumber number : tunableNumbers) { + double currentValue = number.get(); + Double lastValue = lastValues.get(number); + if (lastValue == null || currentValue != lastValue) { + lastValues.put(number, currentValue); + hasChanged = true; + } + } + + if (hasChanged) { + callback.run(); + } + } + } } From 52eb9353fe8caf20d93747878e928102f757b10e Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Fri, 17 Oct 2025 19:47:25 -0400 Subject: [PATCH 124/180] started superstructure stuff --- src/main/deploy/Superstructure.dot | 26 +- src/main/java/frc/robot/Robot.java | 2 +- .../shared/elevator/ElevatorConstants.java | 6 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 6 +- .../superstructure/Superstructure.dot | 13 +- .../V3_EpsilonSuperstructure.java | 60 ++- .../V3_EpsilonSuperstructureEdges.java | 341 ++---------------- .../V3_EpsilonSuperstructurePose.java | 25 +- .../V3_EpsilonSuperstructureStates.java | 45 ++- ...ilonSuperstructureTransitionCondition.java | 6 + .../V3_EpsilonManipulatorConstants.java | 7 +- 11 files changed, 163 insertions(+), 374 deletions(-) create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureTransitionCondition.java diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/Superstructure.dot index 0b153889..66cded18 100644 --- a/src/main/deploy/Superstructure.dot +++ b/src/main/deploy/Superstructure.dot @@ -1,19 +1,18 @@ digraph Superstructure { START -> STOW_DOWN [type=UNCONSTRAINED] - STOW_DOWN -> GROUND_ACQUISITION [type=UNCONSTRAINED, requires=ELEVATOR] - STOW_DOWN -> L1 [type=UNCONSTRAINED] + STOW_DOWN -> FLIP_DOWN [type=UNCONSTRAINED] STOW_DOWN -> L2 [type=UNCONSTRAINED] STOW_DOWN -> L3 [type=UNCONSTRAINED] STOW_DOWN -> L4 [type=UNCONSTRAINED] - STOW_DOWN -> HANDOFF [type=UNCONSTRAINED, requires=ELEVATOR] STOW_DOWN -> STOW_UP [type=UNCONSTRAINED] STOW_DOWN -> L2_ALGAE [type=UNCONSTRAINED] STOW_DOWN -> L3_ALGAE [type=UNCONSTRAINED] STOW_DOWN -> PROCESSOR [type=UNCONSTRAINED] STOW_DOWN -> BARGE [type=UNCONSTRAINED] + STOW_DOWN -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] - GROUND_ACQUISITION -> STOW_DOWN [type=UNCONSTRAINED] + GROUND_ACQUISITION -> FLIP_UP [type=UNCONSTRAINED] GROUND_ACQUISITION -> GROUND_INTAKE [type=UNCONSTRAINED] GROUND_ACQUISITION -> L1 [type=UNCONSTRAINED] GROUND_ACQUISITION -> L2 [type=UNCONSTRAINED] @@ -26,7 +25,7 @@ digraph Superstructure { GROUND_ACQUISITION -> PROCESSOR [type=UNCONSTRAINED] GROUND_ACQUISITION -> BARGE [type=UNCONSTRAINED] - GROUND_INTAKE -> STOW_DOWN [type=UNCONSTRAINED] + GROUND_INTAKE -> FLIP_UP [type=UNCONSTRAINED] GROUND_INTAKE -> GROUND_ACQUISITION [type=UNCONSTRAINED] GROUND_INTAKE -> L1 [type=UNCONSTRAINED] GROUND_INTAKE -> L2 [type=UNCONSTRAINED] @@ -39,7 +38,7 @@ digraph Superstructure { GROUND_INTAKE -> PROCESSOR [type=UNCONSTRAINED] GROUND_INTAKE -> BARGE [type=UNCONSTRAINED] - L1 -> STOW_DOWN [type=UNCONSTRAINED] + L1 -> FLIP_UP [type=UNCONSTRAINED] L1 -> GROUND_ACQUISITION [type=UNCONSTRAINED] L1 -> L2 [type=UNCONSTRAINED] L1 -> L3 [type=UNCONSTRAINED] @@ -119,7 +118,7 @@ digraph Superstructure { L3_SCORE -> PROCESSOR [type=UNCONSTRAINED] L3_SCORE -> BARGE [type=UNCONSTRAINED] - L4_SCORE -> STOW_DOWN [type=UNCONSTRAINED] + L4_SCORE -> FLIP_UP [type=UNCONSTRAINED] L4_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] L4_SCORE -> L1 [type=UNCONSTRAINED] L4_SCORE -> L2 [type=UNCONSTRAINED] @@ -132,10 +131,10 @@ digraph Superstructure { L4_SCORE -> PROCESSOR [type=UNCONSTRAINED] L4_SCORE -> BARGE [type=UNCONSTRAINED] - HANDOFF -> STOW_DOWN [type=UNCONSTRAINED, requires=ARM] + HANDOFF -> STOW_DOWN [type=UNCONSTRAINED] HANDOFF -> GROUND_ACQUISITION [type=UNCONSTRAINED] HANDOFF -> L1 [type=UNCONSTRAINED] - HANDOFF -> L2 [type=UNCONSTRAINED, requires=ARM] + HANDOFF -> L2 [type=UNCONSTRAINED] HANDOFF -> L3 [type=UNCONSTRAINED] HANDOFF -> L4 [type=UNCONSTRAINED] HANDOFF -> STOW_UP [type=UNCONSTRAINED] @@ -195,7 +194,7 @@ digraph Superstructure { L3_ALGAE_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] PROCESSOR -> STOW_DOWN [type = NO_ALGAE] - PROCESSOR -> GROUND_ACQUISITION [type = NO_ALGAE] + PROCESSOR -> FLIP_DOWN [type = NO_ALGAE] PROCESSOR -> L1 [type = NO_ALGAE] PROCESSOR -> L2 [type=UNCONSTRAINED] PROCESSOR -> L3 [type=UNCONSTRAINED] @@ -229,7 +228,14 @@ digraph Superstructure { GROUND_AQUISITION_ALGAE -> STOW_UP GROUND_AQUISITION_ALGAE -> PROCESSOR + GROUND_AQUISITION_ALGAE -> FLIP_DOWN GROUND_AQUISITION_ALGAE -> GROUND_INTAKE_ALGAE GROUND_INTAKE_ALGAE -> GROUND_AQUISITION_ALGAE + + FLIP_DOWN -> GROUND_ACQUISITION [type=UNCONSTRAINED] + FLIP_DOWN -> L1 [type=UNCONSTRAINED] + FLIP_DOWN -> HANDOFF [type=UNCONSTRAINED] + + FLIP_UP -> STOW_DOWN [type=UNCONSTRAINED] } \ No newline at end of file diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index e4048d20..2e0c5e82 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -123,7 +123,7 @@ public void robotInit() { case SIM: // Running a physics simulator, log to NT - // setUseTiming(false); + setUseTiming(false); Logger.addDataReceiver(new NT4Publisher()); break; diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index 6cd059bc..cf5cc32e 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -165,7 +165,7 @@ public class ElevatorConstants { case SIM: GAINS = new Gains( - new LoggedTunableNumber("Elevator/Gains/kP", 20.0), + new LoggedTunableNumber("Elevator/Gains/kP", 50.0), new LoggedTunableNumber("Elevator/Gains/kD", 0.0), new LoggedTunableNumber("Elevator/Gains/kS", 0.0), new LoggedTunableNumber("Elevator/Gains/kG", 0.0), @@ -173,8 +173,8 @@ public class ElevatorConstants { new LoggedTunableNumber("Elevator/Gains/kA", 0.0)); CONSTRAINTS = new Constraints( - new LoggedTunableNumber("Elevator/Max Acceleration", 101.078594), - new LoggedTunableNumber("Elevator/Cruising Velocity", 11.329982), + new LoggedTunableNumber("Elevator/Max Acceleration", 201.078594), + new LoggedTunableNumber("Elevator/Cruising Velocity", 21.329982), new LoggedTunableNumber("Elevator/Goal Tolerance", 0.02)); STOW_GAINS = new Gains( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index dbdc9a6d..6d0db064 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -3,7 +3,6 @@ import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.apriltag.AprilTagFields; import edu.wpi.first.networktables.NetworkTablesJNI; -import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; @@ -12,7 +11,6 @@ import frc.robot.RobotContainer; import frc.robot.RobotState; import frc.robot.commands.AutonomousCommands; -import frc.robot.commands.CompositeCommands; import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.drive.DriveConstants; @@ -169,8 +167,6 @@ public void robotPeriodic() { @Override public Command getAutonomousCommand() { - return CompositeCommands.V3_EpsilonCompositeCommands.createTrajectoryTestCommand( - superstructure, new Timer()); - // return autoChooser.selectedCommand(); + return superstructure.allTransition(); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index 6cda9ef0..ddbe0723 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -1,12 +1,10 @@ digraph Superstructure { START -> STOW_DOWN [type=UNCONSTRAINED] - STOW_DOWN -> GROUND_ACQUISITION [type=UNCONSTRAINED, requires=ELEVATOR] - STOW_DOWN -> L1 [type=UNCONSTRAINED] + STOW_DOWN -> FLIP_DOWN [type=UNCONSTRAINED] STOW_DOWN -> L2 [type=UNCONSTRAINED] STOW_DOWN -> L3 [type=UNCONSTRAINED] STOW_DOWN -> L4 [type=UNCONSTRAINED] - STOW_DOWN -> HANDOFF [type=UNCONSTRAINED, requires=ELEVATOR] STOW_DOWN -> STOW_UP [type=UNCONSTRAINED] STOW_DOWN -> L2_ALGAE [type=UNCONSTRAINED] STOW_DOWN -> L3_ALGAE [type=UNCONSTRAINED] @@ -224,8 +222,8 @@ digraph Superstructure { BARGE_SCORE -> BARGE [type=UNCONSTRAINED] - HANDOFF -> GROUND_AQUISITION_ALGAE - PROCESSOR -> GROUND_AQUISITION_ALGAE + L4_SCORE -> GROUND_AQUISITION_ALGAE + L2_SCORE -> GROUND_AQUISITION_ALGAE GROUND_AQUISITION_ALGAE -> STOW_UP GROUND_AQUISITION_ALGAE -> PROCESSOR @@ -233,6 +231,9 @@ digraph Superstructure { GROUND_AQUISITION_ALGAE -> GROUND_INTAKE_ALGAE GROUND_INTAKE_ALGAE -> GROUND_AQUISITION_ALGAE - L2_SCORE -> GROUND_AQUISITION_ALGAE + FLIP_DOWN -> GROUND_ACQUISITION + FLIP_DOWN -> L1 + FLIP_DOWN -> HANDOFF + FLIP_UP -> STOW_DOWN } \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 0c69cbfe..4930133f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -590,34 +590,60 @@ public boolean elevatorAtGoal() { return elevator.atGoal(); } + @AutoLogOutput(key = NTPrefixes.SUPERSTRUCTURE + "IsTransitioning") + public boolean isTransitioning() { + return edgeCommand != null && edgeCommand.getCommand().isScheduled(); + } + public Command allTransition() { Command all = runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN); for (var source : V3_EpsilonSuperstructureStates.values()) { for (var sink : V3_EpsilonSuperstructureStates.values()) { if (source == sink) continue; - var edge = graph.getEdge(source, sink); - if (edge != null) { - - if (source != V3_EpsilonSuperstructureStates.START - && sink != V3_EpsilonSuperstructureStates.START - && source != V3_EpsilonSuperstructureStates.OVERRIDE) { - all = - all.andThen( - runGoal(sink), - runOnce(() -> System.out.println("Initial Pose:" + sink)), - Commands.waitSeconds(2)); - all = - all.andThen( - runGoal(source), - runOnce(() -> System.out.println("Final Pose:" + source)), - Commands.waitSeconds(2)); - } + if (source != V3_EpsilonSuperstructureStates.START + && sink != V3_EpsilonSuperstructureStates.START + && source != V3_EpsilonSuperstructureStates.OVERRIDE + && sink != V3_EpsilonSuperstructureStates.OVERRIDE) { + all = + all.andThen( + runGoal(sink), + runOnce(() -> System.out.println("Initial Pose:" + sink)), + Commands.waitUntil(() -> atGoal())); + all = + all.andThen( + runGoal(source), + runOnce(() -> System.out.println("Final Pose:" + source)), + Commands.waitUntil(() -> atGoal())); } } } return all; } + public Command stateTransitions(V3_EpsilonSuperstructureStates source) { + Command all = Commands.none(); + + for (var sink : V3_EpsilonSuperstructureStates.values()) { + if (sink == source + || sink == V3_EpsilonSuperstructureStates.START + || sink == V3_EpsilonSuperstructureStates.OVERRIDE) continue; + + all = + all.andThen( + Commands.sequence( + runOnce(() -> System.out.println("→ " + source + " to " + sink)), + runGoal(sink), + Commands.waitUntil(this::atGoal), + Commands.waitSeconds(1.0), + runOnce(() -> System.out.println("← " + sink + " back to " + source)), + runGoal(source), + Commands.waitUntil(this::atGoal), + Commands.waitSeconds(1.0))); + } + + return all; + } + public boolean armBelowThreshold() { return manipulator.getArmAngle().getDegrees() >= 90; } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index f3c87260..e44a78a8 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -1,28 +1,19 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; -import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj.Filesystem; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; -import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; -import frc.robot.subsystems.shared.elevator.ElevatorConstants; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakePivotState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; import java.io.FileReader; import java.io.Reader; import java.util.ArrayList; -import java.util.HashMap; -import java.util.List; -import java.util.Map; import lombok.Builder; import lombok.Getter; import lombok.Setter; import org.jgrapht.Graph; import org.jgrapht.graph.DefaultEdge; -import org.jgrapht.nio.Attribute; import org.jgrapht.nio.dot.DOTImporter; public class V3_EpsilonSuperstructureEdges { @@ -55,94 +46,51 @@ public static void loadEdgesFromDot( DOTImporter importer = new DOTImporter<>(); - // Create edges with placeholder commands (null) + // --- Fix 1: safer vertex factory --- + importer.setVertexFactory( + id -> { + try { + return V3_EpsilonSuperstructureStates.valueOf(id); + } catch (IllegalArgumentException e) { + System.err.println("[DOT Import] Unknown vertex in DOT: " + id); + return null; + } + }); + + // --- Fix 2: ensure edge objects are valid --- importer.setEdgeWithAttributesFactory( attributes -> { - V3_EpsilonSuperstructureEdges.GamePieceEdge type = - V3_EpsilonSuperstructureEdges.GamePieceEdge.UNCONSTRAINED; + GamePieceEdge type = GamePieceEdge.UNCONSTRAINED; if (attributes.containsKey("type")) { - String value = attributes.get("type").getValue(); try { - type = V3_EpsilonSuperstructureEdges.GamePieceEdge.valueOf(value.toUpperCase()); - } catch (IllegalArgumentException e) { - System.err.println("Unknown edge type: " + value + ", defaulting to UNCONSTRAINED"); + type = GamePieceEdge.valueOf(attributes.get("type").getValue().toUpperCase()); + } catch (Exception e) { + System.err.println("[DOT Import] Invalid edge type, defaulting to UNCONSTRAINED"); } } - return V3_EpsilonSuperstructureEdges.EdgeCommand.builder() - .gamePieceEdge(type) - .command(null) // placeholder - .build(); + // Create a proper EdgeCommand with no command yet + return EdgeCommand.builder().gamePieceEdge(type).command(null).build(); }); - // Map DOT node id -> enum - importer.setVertexFactory(id -> V3_EpsilonSuperstructureStates.valueOf(id)); - - // Capture edge attributes - Map> edgeAttrs = new HashMap<>(); - importer.addEdgeWithAttributesConsumer((e, attrs) -> edgeAttrs.put(e, new HashMap<>(attrs))); - - // Import the DOT file + // --- Fix 3: actually import the file and verify success --- try (Reader r = new FileReader(path)) { importer.importGraph(graph, r); } catch (Exception ex) { - throw new RuntimeException("Failed to parse DOT: " + path, ex); + throw new RuntimeException("Failed to parse DOT file: " + path, ex); } - // Clear old edge lists - UNCONSTRAINED.clear(); - NO_ALGAE_EDGES.clear(); - - // Iterate over edges to assign commands and categorize + // --- Fix 4: assign the edge commands after load --- for (EdgeCommand e : graph.edgeSet()) { V3_EpsilonSuperstructureStates from = graph.getEdgeSource(e); V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(e); - - Map attrs = edgeAttrs.get(e); - V3_EpsilonSuperstructureEdges.GamePieceEdge type = - V3_EpsilonSuperstructureEdges.GamePieceEdge.UNCONSTRAINED; - - // START --- ADDED CODE - // Check for the 'requires' attribute to determine if motion should be - // sequential - boolean requiresElevator = false; - boolean requiresArm = false; - if (attrs != null && attrs.containsKey("requires")) { - String value = attrs.get("requires").getValue(); - if ("elevator".equalsIgnoreCase(value)) { - requiresElevator = true; - } else if ("arm".equalsIgnoreCase(value)) { - requiresArm = true; - } - } - e.setRequiresElevator(requiresElevator); - e.setRequiresArm(requiresArm); - // END --- ADDED CODE - - if (attrs != null && attrs.get("type") != null) { - try { - type = - V3_EpsilonSuperstructureEdges.GamePieceEdge.valueOf( - attrs.get("type").getValue().toUpperCase()); - } catch (IllegalArgumentException ex) { - System.err.println("Unknown edge type: " + attrs.get("type").getValue()); - } - } - - // Assign the actual command, passing the new flags - e.setCommand( - V3_EpsilonSuperstructureEdges.getEdgeCommand( - from, to, elevator, intake, manipulator, requiresElevator, requiresArm)); - - // Add to proper list - Edge edge = new Edge(from, to); - if (type == V3_EpsilonSuperstructureEdges.GamePieceEdge.NO_ALGAE) { - NO_ALGAE_EDGES.add(edge); - } else { - UNCONSTRAINED.add(edge); - } + e.setCommand(getEdgeCommand(from, to, elevator, intake, manipulator)); } + + System.out.printf( + "[DOT Import] Loaded %d vertices, %d edges%n", + graph.vertexSet().size(), graph.edgeSet().size()); } @Builder(toBuilder = true) @@ -150,10 +98,6 @@ public static void loadEdgesFromDot( public static class EdgeCommand extends DefaultEdge { @Setter private Command command; @Builder.Default private GamePieceEdge gamePieceEdge = GamePieceEdge.UNCONSTRAINED; - // START --- ADDED CODE - @Setter @Builder.Default private boolean requiresElevator = false; - @Setter @Builder.Default private boolean requiresArm = false; - // END --- ADDED CODE } /** @@ -166,10 +110,6 @@ public static class EdgeCommand extends DefaultEdge { * @param elevator The elevator subsystem. * @param intake The intake subsystem. * @param manipulator The manipulator subsystem. - * @param requiresElevator Flag indicating the elevator must finish its move before other - * mechanisms start. - * @param requiresArm Flag indicating the arm/intake must finish its move before the elevator - * starts. * @return A {@link Command} that, when executed, transitions the superstructure from the 'from' * state to the 'to' state. */ @@ -178,191 +118,13 @@ private static Command getEdgeCommand( V3_EpsilonSuperstructureStates to, ElevatorFSM elevator, V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator, - boolean requiresElevator, - boolean requiresArm) { + V3_EpsilonManipulator manipulator) { V3_EpsilonSuperstructurePose pose = to.getPose(); - Command moveCommand; // This will hold the command that STARTS the movement. - - if (requiresElevator) { - // Elevator moves and waits, THEN other mechanisms move. - moveCommand = - Commands.sequence( - pose.setElevatorHeight(elevator), - elevator.waitUntilAtGoal(), - pose.asConfigurationSpaceCommand( - elevator, intake, manipulator) // CORRECTED: Only move the other subsystems - ); - - } else if (requiresArm) { - // Arm moves to a safe position and waits, THEN other mechanisms move. - moveCommand = - Commands.sequence( - pose.setManipulatorState(manipulator), - Commands.waitUntil(manipulator::isSafePosition), - pose.asConfigurationSpaceCommand( - elevator, intake, manipulator) // CORRECTED: Only move the other subsystems - ); - } else { - // Default case: All mechanisms move in parallel. - moveCommand = pose.asConfigurationSpaceCommand(elevator, intake, manipulator); - } - - if (from == V3_EpsilonSuperstructureStates.HANDOFF) { - moveCommand = - Commands.sequence( - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.ALGAE_MID)), - elevator.waitUntilAtGoal(), - moveCommand); - } - // move intake out of the way if it will collide - else if (willCollide(from, to)) { - moveCommand = - Commands.sequence( - Commands.runOnce(() -> intake.setPivotGoal(IntakePivotState.ARM_CLEAR)), - intake.waitUntilPivotAtGoal(), - moveCommand); - } - if (to == V3_EpsilonSuperstructureStates.HANDOFF) { - - if (requiresArm) { - moveCommand = - Commands.sequence( - pose.setManipulatorState(manipulator), - Commands.waitUntil(manipulator::isSafePosition), - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.ALGAE_MID)), - elevator.waitUntilAtGoal(), - pose.setIntakeState(intake), - intake.waitUntilPivotAtGoal(), - pose.setElevatorHeight(elevator)); - } else if (requiresElevator) { - moveCommand = - Commands.sequence( - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.ALGAE_MID)), - elevator.waitUntilAtGoal(), - pose.setManipulatorState(manipulator), - manipulator.waitUntilArmAtGoal(), - pose.setIntakeState(intake), - intake.waitUntilPivotAtGoal(), - pose.setElevatorHeight(elevator)); - } else { - moveCommand = - Commands.sequence( - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.ALGAE_MID)) - .alongWith(pose.setManipulatorState(manipulator)), - Commands.waitSeconds(0.02), - Commands.waitUntil(() -> elevator.atGoal() || manipulator.armAtGoal()), - pose.setIntakeState(intake), - intake.waitUntilPivotAtGoal(), - pose.setElevatorHeight(elevator)); - } - } - - if (to.equals(V3_EpsilonSuperstructureStates.BARGE_SCORE)) { - return Commands.sequence( - moveCommand, - Commands.race( - Commands.waitUntil(() -> elevator.pastBargeThresholdgetPositionMeters()), - waitForPoseCommand(to, elevator, intake, manipulator))); - } - - // THE CRITICAL FIX: - // No matter how we start the move, we append a final wait condition. - // This ensures the command doesn't end until the robot is physically at the - // target pose. - return Commands.sequence(moveCommand, waitForPoseCommand(to, elevator, intake, manipulator)); - } - - private static boolean willCollide( - V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { - - final int samples = 20; // number of interpolation steps - - for (int i = 0; i <= samples; i++) { - double t = i / (double) samples; - - // Interpolate elevator height - double elevHeight = - ElevatorConstants.ElevatorPositions.getPosition(from.getPose().getElevatorHeight()) - .getPosition() - * (1 - t) - + ElevatorConstants.ElevatorPositions.getPosition(to.getPose().getElevatorHeight()) - .getPosition() - * t; - - // Interpolate arm angle - Rotation2d armAngle = - from.getPose() - .getArmState() - .getAngle(V3_EpsilonManipulatorConstants.Side.POSITIVE) - .interpolate( - to.getPose().getArmState().getAngle(V3_EpsilonManipulatorConstants.Side.POSITIVE), - t); - - // Interpolate intake angle - Rotation2d intakeAngle = - from.getPose() - .getIntakeState() - .getAngle() - .interpolate(to.getPose().getIntakeState().getAngle(), t); - - // Arm height - double armHeight = - -armAngle.rotateBy(new Rotation2d(-Math.PI / 2)).getSin() - * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() - + elevHeight; - - // Arm horizontal extension - double horiz = - Math.abs( - armAngle.rotateBy(new Rotation2d(-Math.PI / 2)).getCos() - * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS()); - - // Check safety - boolean clearsIntake = intakeAngle.getDegrees() > 15 || armHeight > 0.37 || horiz > 0.35; - - if (!clearsIntake) { - return true; // Collision predicted - } - } - - return false; // Safe through transition - } - - /** - * Adds edges to the superstructure state graph based on the provided list of edges and algae - * condition. - * - * @param graph The graph to which edges are added. - * @param edges A list of {@link Edge} objects representing the transitions between states. - * @param type The {@link GamePieceEdge} type associated with these edges. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. - */ - private static void addEdges( - Graph graph, - List edges, - GamePieceEdge type, - ElevatorFSM elevator, - V3_EpsilonManipulator manipulator, - V3_EpsilonIntake intake) { - // Iterate through each edge in the provided list - for (Edge edge : edges) { - // Add the edge to the graph with its associated command and algae type - graph.addEdge( - edge.from(), - edge.to(), - EdgeCommand.builder() - // Updated to call new signature with default 'false' values for requirements - .command( - getEdgeCommand( - edge.from(), edge.to(), elevator, intake, manipulator, false, false)) - .gamePieceEdge(type) - .build()); - } + return Commands.sequence( + pose.asConfigurationSpaceCommand(elevator, intake, manipulator), + pose.wait(elevator, intake, manipulator, to.getTransitionCondition())); } /** @@ -378,54 +140,11 @@ public static void addEdges( ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { - // This method populates the graph by parsing the DOT file. loadEdgesFromDot( Filesystem.getDeployDirectory().toPath().resolve("Superstructure.dot").toString(), graph, elevator, intake, manipulator); - - // NOTE: The two lines below are likely redundant. The loadEdgesFromDot method - // already - // adds all edges to the graph. You may want to remove these calls. - addEdges(graph, UNCONSTRAINED, GamePieceEdge.UNCONSTRAINED, elevator, manipulator, intake); - addEdges(graph, NO_ALGAE_EDGES, GamePieceEdge.NO_ALGAE, elevator, manipulator, intake); - } - - // In V3_EpsilonSuperstructureEdges.java - - private static Command waitForPoseCommand( - V3_EpsilonSuperstructureStates state, - ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - - // Add this command to log the check's status - Command logCheck = - Commands.runOnce( - () -> { - boolean elevatorOk = elevator.atGoal(); - boolean intakeOk = intake.pivotAtGoal(); - boolean armOk = manipulator.armAtGoal(); - System.out.println( - "Checking pose for: " - + state.toString() - + " -> Elevator OK: " - + elevatorOk - + ", Intake OK: " - + intakeOk - + ", Arm OK: " - + armOk); - }); - - Command wait = - Commands.sequence( - Commands.waitSeconds(0.02), - Commands.waitUntil( - () -> elevator.atGoal() && intake.pivotAtGoal() && manipulator.armAtGoal())); - - // Run the log once right before starting the wait - return Commands.sequence(wait, logCheck); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java index 6b372cd2..ab7c2ef0 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java @@ -8,6 +8,7 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakePivotState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; +import java.util.Optional; import lombok.Getter; /** @@ -85,11 +86,25 @@ public Command asConfigurationSpaceCommand( } public Command wait( - ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { - return Commands.parallel( - elevator.waitUntilAtGoal(), - manipulator.waitUntilArmAtGoal(), - intake.waitUntilPivotAtGoal()); + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator, + Optional condition) { + return Commands.sequence( + Commands.parallel( + elevator.waitUntilAtGoal(), + manipulator.waitUntilArmAtGoal(), + intake.waitUntilPivotAtGoal()), + Commands.either( + Commands.either( + elevator.waitUntilAtGoal(), + manipulator.waitUntilArmAtGoal(), + () -> + condition + .get() + .equals(V3_EpsilonSuperstructureTransitionCondition.ELEVATOR_AT_GOAL)), + Commands.none(), + () -> condition.isPresent())); } /** diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 6e90927f..941bfd91 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -7,6 +7,7 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakeRollerState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; +import java.util.Optional; public enum V3_EpsilonSuperstructureStates { START("START", new SubsystemPoses(), SubsystemActions.empty()), @@ -48,7 +49,7 @@ public enum V3_EpsilonSuperstructureStates { SubsystemActions.empty()), L1_SCORE( "L1_SCORE", - new SubsystemPoses(ReefState.L1, ManipulatorArmState.HANDOFF, IntakePivotState.L1), + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.SCORE_CORAL)), L2( @@ -80,18 +81,9 @@ public enum V3_EpsilonSuperstructureStates { HANDOFF( "HANDOFF", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.STOW), + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.OUTTAKE)), - INTERMEDIATE_WAIT_FOR_ELEVATOR( - "INTERMEDIATE_WAIT_FOR_ELEVATOR", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), - SubsystemActions.empty()), - INTERMEDIATE_WAIT_FOR_ARM( - "INTERMEDIATE_WAIT_FOR_ARM", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.SAFE_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty()), - L2_ALGAE( "L2_ALGAE", new SubsystemPoses( @@ -136,14 +128,23 @@ public enum V3_EpsilonSuperstructureStates { BARGE( "BARGE", new SubsystemPoses( - ReefState.HIGH_STOW, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), + ReefState.ALGAE_SCORE, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), SubsystemActions.empty()), BARGE_SCORE( "BARGE_SCORE", new SubsystemPoses( ReefState.ALGAE_SCORE, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), - ; + FLIP_DOWN( + "FLIP_DOWN", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), + SubsystemActions.empty(), + V3_EpsilonSuperstructureTransitionCondition.ELEVATOR_AT_GOAL), + FLIP_UP( + "FLIP_UP", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), + SubsystemActions.empty(), + V3_EpsilonSuperstructureTransitionCondition.MANIPULATOR_AT_GOAL); // Readable name for state private final String name; @@ -154,6 +155,8 @@ public enum V3_EpsilonSuperstructureStates { // Actions to perform for all subsystems in this state private final SubsystemActions subsystemActions; + private final Optional transitionCondition; + /** * Constructor for V3_SuperstructureStates. * @@ -165,6 +168,18 @@ public enum V3_EpsilonSuperstructureStates { this.name = name; this.subsystemPoses = pose; this.subsystemActions = action; + this.transitionCondition = Optional.empty(); + } + + V3_EpsilonSuperstructureStates( + String name, + SubsystemPoses pose, + SubsystemActions action, + V3_EpsilonSuperstructureTransitionCondition condition) { + this.name = name; + this.subsystemPoses = pose; + this.subsystemActions = action; + this.transitionCondition = Optional.of(condition); } /** @@ -186,6 +201,10 @@ public V3_EpsilonSuperstructureAction getAction() { return new V3_EpsilonSuperstructureAction(name, subsystemActions); } + public Optional getTransitionCondition() { + return transitionCondition; + } + /** * Returns the name of the superstructure state. * diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureTransitionCondition.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureTransitionCondition.java new file mode 100644 index 00000000..6c67c30d --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureTransitionCondition.java @@ -0,0 +1,6 @@ +package frc.robot.subsystems.v3_Epsilon.superstructure; + +public enum V3_EpsilonSuperstructureTransitionCondition { + ELEVATOR_AT_GOAL, + MANIPULATOR_AT_GOAL, +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index ad9427c6..30472f4d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -34,7 +34,7 @@ public final class V3_EpsilonManipulatorConstants { ARM_PARAMETERS = new ArmParameters(DCMotor.getKrakenX60Foc(1), 1, 55.5, .695); EMPTY_GAINS = new Gains( - new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 50), + new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 25), new LoggedTunableNumber("Manipulator/Arm/Empty/kD", 0), new LoggedTunableNumber("Manipulator/Arm/Empty/kS", 0.24274), new LoggedTunableNumber("Manipulator/Arm/Empty/kG", 0.66177), @@ -59,7 +59,7 @@ public final class V3_EpsilonManipulatorConstants { CONSTRAINTS = new Constraints( new LoggedTunableNumber("Manipulator/Arm/MaxAcceleration", 1000.0), - new LoggedTunableNumber("Manipulator/Arm/CruisingVelocity", 50.0), + new LoggedTunableNumber("Manipulator/Arm/CruisingVelocity", 25.0), new LoggedTunableNumber("Manipulator/Arm/GoalTolerance", Units.degreesToRadians(3))); ROLLER_CAN_ID = 30; @@ -130,7 +130,7 @@ public static enum ManipulatorArmState { SCORE(Rotation2d.fromDegrees(55.0)), // Placeholder value. Make sure to test SCORE_L4(Rotation2d.kPi), PROCESSOR(Rotation2d.fromDegrees(90)), - ALGAE_INTAKE_FLOOR(Rotation2d.fromDegrees(-99)), + ALGAE_INTAKE_FLOOR(Rotation2d.fromDegrees(99)), REEF_INTAKE(Rotation2d.fromDegrees(46.279296875)), INTAKE_OUT_LINE(Rotation2d.fromDegrees(61)), FLOOR_INTAKE(Rotation2d.fromDegrees(73.5)), @@ -140,6 +140,7 @@ public static enum ManipulatorArmState { VERTICAL_UP(Rotation2d.fromDegrees(0)), HANDOFF(Rotation2d.kPi), SAFE_ANGLE(Rotation2d.fromDegrees(150)), + FLIP_ANGLE(Rotation2d.fromDegrees(135)), EMERGENCY_EJECT_ANGLE( Rotation2d.fromDegrees(90)); // Idk if tested. Looks fine but double check. From 68e96c052762fd8c364d064bb96f80ae40a02d84 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Fri, 17 Oct 2025 21:25:57 -0400 Subject: [PATCH 125/180] preliminary leds --- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 45 ++++--- .../v3_Epsilon/leds/V3_EpsilonLEDs.java | 122 ++++++++++++++++++ 2 files changed, 144 insertions(+), 23 deletions(-) create mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/leds/V3_EpsilonLEDs.java diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index bb7c4988..6c3125eb 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -14,35 +14,29 @@ import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.drive.DriveConstants; import frc.robot.subsystems.shared.drive.GyroIO; -import frc.robot.subsystems.shared.drive.GyroIOPigeon2; import frc.robot.subsystems.shared.drive.ModuleIO; import frc.robot.subsystems.shared.drive.ModuleIOSim; -import frc.robot.subsystems.shared.drive.ModuleIOTalonFX; import frc.robot.subsystems.shared.elevator.Elevator; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.shared.elevator.ElevatorIO; import frc.robot.subsystems.shared.elevator.ElevatorIOSim; -import frc.robot.subsystems.shared.elevator.ElevatorIOTalonFX; import frc.robot.subsystems.shared.vision.Vision; import frc.robot.subsystems.shared.vision.VisionConstants.RobotCameras; import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimber; import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIO; import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIOSim; -import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIOTalonFX; +import frc.robot.subsystems.v3_Epsilon.leds.V3_EpsilonLEDs; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIO; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOSim; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOTalonFX; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIO; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOSim; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOTalonFX; import frc.robot.util.LTNUpdater; import frc.robot.util.LoggedTunableNumber; -import org.ironmaple.simulation.SimulatedArena; import org.littletonrobotics.junction.Logger; public class V3_EpsilonRobotContainer implements RobotContainer { @@ -53,6 +47,7 @@ public class V3_EpsilonRobotContainer implements RobotContainer { private V3_EpsilonManipulator manipulator; private V3_EpsilonSuperstructure superstructure; private V3_EpsilonClimber climber; + private V3_EpsilonLEDs leds; private Vision vision; // Controller @@ -65,18 +60,18 @@ public V3_EpsilonRobotContainer() { if (Constants.getMode() != Mode.REPLAY) { switch (Constants.ROBOT) { case V3_EPSILON: - drive = - new Drive( - new GyroIOPigeon2(), - new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), - new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), - new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), - new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); - elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); - climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); - superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + // drive = + // new Drive( + // new GyroIOPigeon2(), + // new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), + // new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), + // new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), + // new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); + // elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); + // intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); + // manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); + // climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); + // superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); vision = new Vision( () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), @@ -95,6 +90,7 @@ public V3_EpsilonRobotContainer() { manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOSim()); superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + leds = new V3_EpsilonLEDs(); vision = new Vision(() -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded)); break; @@ -124,6 +120,9 @@ public V3_EpsilonRobotContainer() { if (climber == null) { climber = new V3_EpsilonClimber(new V3_EpsilonClimberIO() {}); } + if (leds == null) { + leds = new V3_EpsilonLEDs(); + } if (superstructure == null) { superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); } @@ -184,10 +183,10 @@ public void robotPeriodic() { V3_EpsilonMechanism3d.getPoses( elevator.getPositionMeters(), intake.getPivotAngle(), manipulator.getArmAngle())); - Logger.recordOutput( - "FieldSimulation/Algae", SimulatedArena.getInstance().getGamePiecesArrayByType("Algae")); - Logger.recordOutput( - "FieldSimulation/Coral", SimulatedArena.getInstance().getGamePiecesArrayByType("Coral")); + // Logger.recordOutput( + // "FieldSimulation/Algae", SimulatedArena.getInstance().getGamePiecesArrayByType("Algae")); + // Logger.recordOutput( + // "FieldSimulation/Coral", SimulatedArena.getInstance().getGamePiecesArrayByType("Coral")); } /** diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/leds/V3_EpsilonLEDs.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/leds/V3_EpsilonLEDs.java new file mode 100644 index 00000000..d0d8e51a --- /dev/null +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/leds/V3_EpsilonLEDs.java @@ -0,0 +1,122 @@ +package frc.robot.subsystems.v3_Epsilon.leds; + +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.RobotController; +import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj.util.Color; +import frc.robot.FieldConstants.Reef.ReefPose; +import frc.robot.Robot; +import frc.robot.RobotState; +import frc.robot.RobotState.RobotMode; +import frc.robot.subsystems.shared.leds.Leds; + +public class V3_EpsilonLEDs extends Leds { + private static Leds instance; + + // Robot state tracking + public int loopCycleCount = 0; + public boolean autoFinished = false; + public boolean lowBatteryAlert = false; + + private boolean lastEnabledAuto = false; + private double lastEnabledTime = 0.0; + private boolean estopped = false; + + private static final int LENGTH = 203; + private static final int PORT = 0; + private static final int LEFT_LENGTH_START = 0; + private static final int LEFT_LENGTH_END = 33; + private static final int RIGHT_LENGTH_START = 34; + private static final int RIGHT_LENGTH_END = 68; + + public V3_EpsilonLEDs() { + super(LENGTH, PORT); + } + + public static Leds getInstance() { + if (instance == null) { + instance = new V3_EpsilonLEDs(); + } + return instance; + } + + public synchronized void periodic() { + lowBatteryAlert = RobotController.getBatteryVoltage() <= 11.5; + // Update auto state + if (RobotMode.disabled()) { + autoFinished = false; + } else { + lastEnabledAuto = RobotMode.auto(); + lastEnabledTime = Timer.getFPGATimestamp(); + } + + // Update estop state + if (DriverStation.isEStopped()) { + estopped = true; + } + + // Exit during initial cycles + loopCycleCount += 1; + if (loopCycleCount < Leds.MIN_LOOP_CYCLE_COUNT) { + return; + } + + // Stop loading notifier if running + loadingNotifier.stop(); + + setPattern(); + + // Update LEDs + leds.setData(buffer); + } + + private void setPattern() { + // Select LED mode + solid(Color.kBlack); // Default to off% + if (estopped) { + solid(Color.kRed); + } else if (RobotMode.disabled()) { + if (lastEnabledAuto && Timer.getFPGATimestamp() - lastEnabledTime < AUTO_FADE_MAX_TIME) { + // Auto fade + solid(1.0 - ((Timer.getFPGATimestamp() - lastEnabledTime) / AUTO_FADE_TIME), Color.kGreen); + } else if (lowBatteryAlert) { + // Low battery + strobe(Color.kOrangeRed, Color.kBlack, STROBE_FAST_DURATION); + } else if (Robot.isJitting()) { + rainbow(LENGTH, 5); + } else { + rainbow(LENGTH, 5); + } + } else if (RobotMode.enabled()) { + if (RobotState.isAutoAligning()) { + rainbow(LENGTH, 0.25); + } else if (RobotState.isHasAlgae()) { + wave(Color.kBlack, Color.kDarkGreen, RAINBOW_CYCLE_LENGTH, 1.0); + } else { + if (RobotState.getOIData().currentReefPost().equals(ReefPose.RIGHT)) { + if (RobotState.isIntakingCoral()) { + solid(Color.kAqua, LEFT_LENGTH_START, LEFT_LENGTH_END); + } else { + breath( + Color.kBlack, + Color.kDarkViolet, + Timer.getFPGATimestamp(), + LEFT_LENGTH_START, + LEFT_LENGTH_END); + } + } else if (RobotState.getOIData().currentReefPost().equals(ReefPose.LEFT)) { + if (RobotState.isIntakingCoral()) { + solid(Color.kAqua, RIGHT_LENGTH_START, RIGHT_LENGTH_END); + } else { + breath( + Color.kBlack, + Color.kDarkViolet, + Timer.getFPGATimestamp(), + RIGHT_LENGTH_START, + RIGHT_LENGTH_END); + } + } + } + } + } +} From f30fc73e060ea78bdf1f4b871972df9144bcb02a Mon Sep 17 00:00:00 2001 From: Anshu Date: Fri, 17 Oct 2025 22:34:21 -0400 Subject: [PATCH 126/180] Did v3 drive train Bringup (#145) Co-authored-by: RishiGandhi77 --- src/main/java/frc/robot/Constants.java | 2 +- src/main/java/frc/robot/Robot.java | 3 +- .../shared/drive/DriveConstants.java | 46 ++++ .../drive/TunerConstantsV3_Epsilon.java | 230 ++++++++++++++++++ .../v3_Epsilon/V3_EpsilonRobotContainer.java | 53 ++-- 5 files changed, 313 insertions(+), 21 deletions(-) create mode 100644 src/main/java/frc/robot/subsystems/shared/drive/TunerConstantsV3_Epsilon.java diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 0b2ef474..4b343dc0 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -5,7 +5,7 @@ public final class Constants { public static final boolean TUNING_MODE = true; public static final double LOOP_PERIOD_SECONDS = 0.02; - public static final RobotType ROBOT = RobotType.V3_EPSILON_SIM; + public static final RobotType ROBOT = RobotType.V3_EPSILON; public static Mode getMode() { switch (ROBOT) { diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index c1bb9243..acd3599f 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -31,7 +31,6 @@ import java.util.HashMap; import java.util.Map; import java.util.function.BiConsumer; -import org.ironmaple.simulation.SimulatedArena; import org.littletonrobotics.junction.LogFileUtil; import org.littletonrobotics.junction.LoggedRobot; import org.littletonrobotics.junction.Logger; @@ -127,7 +126,7 @@ public void robotInit() { // setUseTiming(false); Logger.addDataReceiver(new NT4Publisher()); // setting up maple sim field - SimulatedArena.getInstance(); + // SimulatedArena.getInstance(); break; case REPLAY: diff --git a/src/main/java/frc/robot/subsystems/shared/drive/DriveConstants.java b/src/main/java/frc/robot/subsystems/shared/drive/DriveConstants.java index eb5b898d..17b74547 100644 --- a/src/main/java/frc/robot/subsystems/shared/drive/DriveConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/drive/DriveConstants.java @@ -234,6 +234,52 @@ public class DriveConstants { DRIVER_DEADBAND = 0.025; OPERATOR_DEADBAND = 0.25; break; + case V3_EPSILON: + case V3_EPSILON_SIM: + FRONT_LEFT = TunerConstantsV3_Epsilon.FrontLeft; + FRONT_RIGHT = TunerConstantsV3_Epsilon.FrontRight; + BACK_LEFT = TunerConstantsV3_Epsilon.BackLeft; + BACK_RIGHT = TunerConstantsV3_Epsilon.BackRight; + + DRIVE_CONFIG = + new DriveConfig( + TunerConstantsV3_Epsilon.DrivetrainConstants.CANBusName, + TunerConstantsV3_Epsilon.DrivetrainConstants.Pigeon2Id, + TunerConstantsV3_Epsilon.kSpeedAt12Volts.in(MetersPerSecond), + TunerConstantsV3_Epsilon.kWheelRadius.in(Meters), + DCMotor.getKrakenX60Foc(1), + DCMotor.getKrakenX60Foc(1), + FRONT_LEFT, + FRONT_RIGHT, + BACK_LEFT, + BACK_RIGHT, + Units.inchesToMeters(34.5), + Units.inchesToMeters(34.5)); + + GAINS = + new Gains( + new LoggedTunableNumber("Drive/Drive KS", TunerConstantsV3_Epsilon.driveGains.kS), + new LoggedTunableNumber("Drive/Drive KV", TunerConstantsV3_Epsilon.driveGains.kV), + new LoggedTunableNumber("Drive/Drive KP", TunerConstantsV3_Epsilon.driveGains.kP), + new LoggedTunableNumber("Drive/Drive KD", TunerConstantsV3_Epsilon.driveGains.kD), + new LoggedTunableNumber("Drive/Turn KP", TunerConstantsV3_Epsilon.steerGains.kP), + new LoggedTunableNumber("Drive/Turn KD", TunerConstantsV3_Epsilon.steerGains.kD)); + AUTO_ALIGN_GAINS = + new AutoAlignGains( + new LoggedTunableNumber("Drive/Translation KP", 4.0), + new LoggedTunableNumber("Drive/Translation KD", 0.0), + new LoggedTunableNumber("Drive/Rotation KP", 5.0), + new LoggedTunableNumber("Drive/Rotation KD", 0.05)); + AUTO_GAINS = + new AutoAlignGains( + new LoggedTunableNumber("Drive/Auto Gains/Translation KP", 10.0), + new LoggedTunableNumber("Drive/Auto Gains/Translation KD", 0.0), + new LoggedTunableNumber("Drive/Auto Gains/Rotation KP", 5.0), + new LoggedTunableNumber("Drive/Auto Gains/Rotation KD", 0.00)); + ODOMETRY_FREQUENCY = 250.0; + DRIVER_DEADBAND = 0.025; + OPERATOR_DEADBAND = 0.25; + break; } ALIGN_ROBOT_TO_APRIL_TAG_CONSTANTS = new AlignRobotToAprilTagConstants( diff --git a/src/main/java/frc/robot/subsystems/shared/drive/TunerConstantsV3_Epsilon.java b/src/main/java/frc/robot/subsystems/shared/drive/TunerConstantsV3_Epsilon.java new file mode 100644 index 00000000..5ffbd375 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/shared/drive/TunerConstantsV3_Epsilon.java @@ -0,0 +1,230 @@ +package frc.robot.subsystems.shared.drive; + +import static edu.wpi.first.units.Units.*; + +import com.ctre.phoenix6.CANBus; +import com.ctre.phoenix6.configs.*; +import com.ctre.phoenix6.hardware.*; +import com.ctre.phoenix6.signals.*; +import com.ctre.phoenix6.swerve.*; +import com.ctre.phoenix6.swerve.SwerveModuleConstants.*; +import edu.wpi.first.units.measure.*; + +// Generated by the Tuner X Swerve Project Generator +// https://v6.docs.ctr-electronics.com/en/stable/docs/tuner/tuner-swerve/index.html +public class TunerConstantsV3_Epsilon { + // Both sets of gains need to be tuned to your individual robot. + + // The steer motor uses any SwerveModule.SteerRequestType control request with the + // output type specified by SwerveModuleConstants.SteerMotorClosedLoopOutput + public static final Slot0Configs steerGains = + new Slot0Configs() + .withKP(3700) + .withKI(0) + .withKD(41) + .withKS(0.1) + .withKV(2.33) + .withKA(0) + .withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign); + // When using closed-loop control, the drive motor uses the control + // output type specified by SwerveModuleConstants.DriveMotorClosedLoopOutput + public static final Slot0Configs driveGains = + new Slot0Configs().withKP(47).withKI(0).withKD(0.001).withKS(7.266685).withKV(0); + + // The closed-loop output type to use for the steer motors; + // This affects the PID/FF gains for the steer motors + public static final ClosedLoopOutputType kSteerClosedLoopOutput = + ClosedLoopOutputType.TorqueCurrentFOC; + // The closed-loop output type to use for the drive motors; + // This affects the PID/FF gains for the drive motors + public static final ClosedLoopOutputType kDriveClosedLoopOutput = + ClosedLoopOutputType.TorqueCurrentFOC; + + // The type of motor used for the drive motor + public static final DriveMotorArrangement kDriveMotorType = + DriveMotorArrangement.TalonFX_Integrated; + // The type of motor used for the drive motor + public static final SteerMotorArrangement kSteerMotorType = + SteerMotorArrangement.TalonFX_Integrated; + + // The remote sensor feedback type to use for the steer motors; + // When not Pro-licensed, Fused*/Sync* automatically fall back to Remote* + public static final SteerFeedbackType kSteerFeedbackType = SteerFeedbackType.FusedCANcoder; + + // The stator current at which the wheels start to slip; + // This needs to be tuned to your individual robot + public static final Current kSlipCurrent = Amps.of(120.0); + + // Initial configs for the drive and steer motors and the azimuth encoder; these cannot be null. + // Some configs will be overwritten; check the `with*InitialConfigs()` API documentation. + public static final TalonFXConfiguration driveInitialConfigs = new TalonFXConfiguration(); + public static final TalonFXConfiguration steerInitialConfigs = + new TalonFXConfiguration() + .withCurrentLimits( + new CurrentLimitsConfigs() + // Swerve azimuth does not require much torque output, so we can set a relatively + // low + // stator current limit to help avoid brownouts without impacting performance. + .withStatorCurrentLimit(Amps.of(60)) + .withStatorCurrentLimitEnable(true)); + public static final CANcoderConfiguration encoderInitialConfigs = new CANcoderConfiguration(); + // Configs for the Pigeon 2; leave this null to skip applying Pigeon 2 configs + public static final Pigeon2Configuration pigeonConfigs = null; + + // CAN bus that the devices are located on; + // All swerve devices must share the same CAN bus + public static final CANBus kCANBus = new CANBus("Drive"); + + // Theoretical free speed (m/s) at 12 V applied output; + // This needs to be tuned to your individual robot + public static final LinearVelocity kSpeedAt12Volts = MetersPerSecond.of(4.48); + + // Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns; + // This may need to be tuned to your individual robot + public static final double kCoupleRatio = 3.125; + + public static final double kDriveGearRatio = 7.125; + public static final double kSteerGearRatio = 18.75; + public static final Distance kWheelRadius = Inches.of(1.955); + + public static final boolean kInvertLeftSide = false; + public static final boolean kInvertRightSide = true; + + public static final int kPigeonId = 15; + + // These are only used for simulation + public static final MomentOfInertia kSteerInertia = KilogramSquareMeters.of(0.01); + public static final MomentOfInertia kDriveInertia = KilogramSquareMeters.of(0.01); + // Simulated voltage necessary to overcome friction + public static final Voltage kSteerFrictionVoltage = Volts.of(0.2); + public static final Voltage kDriveFrictionVoltage = Volts.of(0.2); + + public static final SwerveDrivetrainConstants DrivetrainConstants = + new SwerveDrivetrainConstants() + .withCANBusName(kCANBus.getName()) + .withPigeon2Id(kPigeonId) + .withPigeon2Configs(pigeonConfigs); + + public static final SwerveModuleConstantsFactory< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + ConstantCreator = + new SwerveModuleConstantsFactory< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration>() + .withDriveMotorGearRatio(kDriveGearRatio) + .withSteerMotorGearRatio(kSteerGearRatio) + .withCouplingGearRatio(kCoupleRatio) + .withWheelRadius(kWheelRadius) + .withSteerMotorGains(steerGains) + .withDriveMotorGains(driveGains) + .withSteerMotorClosedLoopOutput(kSteerClosedLoopOutput) + .withDriveMotorClosedLoopOutput(kDriveClosedLoopOutput) + .withSlipCurrent(kSlipCurrent) + .withSpeedAt12Volts(kSpeedAt12Volts) + .withDriveMotorType(kDriveMotorType) + .withSteerMotorType(kSteerMotorType) + .withFeedbackSource(kSteerFeedbackType) + .withDriveMotorInitialConfigs(driveInitialConfigs) + .withSteerMotorInitialConfigs(steerInitialConfigs) + .withEncoderInitialConfigs(encoderInitialConfigs) + .withSteerInertia(kSteerInertia) + .withDriveInertia(kDriveInertia) + .withSteerFrictionVoltage(kSteerFrictionVoltage) + .withDriveFrictionVoltage(kDriveFrictionVoltage); + + // Front Left + public static final int kFrontLeftDriveMotorId = 1; + public static final int kFrontLeftSteerMotorId = 2; + public static final int kFrontLeftEncoderId = 11; + public static final Angle kFrontLeftEncoderOffset = Rotations.of(-0.4423828125); + public static final boolean kFrontLeftSteerMotorInverted = true; + public static final boolean kFrontLeftEncoderInverted = false; + + public static final Distance kFrontLeftXPos = Inches.of(11.5); + public static final Distance kFrontLeftYPos = Inches.of(11.5); + + // Front Right + public static final int kFrontRightDriveMotorId = 3; + public static final int kFrontRightSteerMotorId = 4; + public static final int kFrontRightEncoderId = 12; + public static final Angle kFrontRightEncoderOffset = Rotations.of(0.37109375); + public static final boolean kFrontRightSteerMotorInverted = true; + public static final boolean kFrontRightEncoderInverted = false; + + public static final Distance kFrontRightXPos = Inches.of(11.5); + public static final Distance kFrontRightYPos = Inches.of(-11.5); + + // Back Left + public static final int kBackLeftDriveMotorId = 5; + public static final int kBackLeftSteerMotorId = 6; + public static final int kBackLeftEncoderId = 13; + public static final Angle kBackLeftEncoderOffset = Rotations.of(-0.240966796875); + public static final boolean kBackLeftSteerMotorInverted = true; + public static final boolean kBackLeftEncoderInverted = false; + + public static final Distance kBackLeftXPos = Inches.of(-11.5); + public static final Distance kBackLeftYPos = Inches.of(11.5); + + // Back Right + public static final int kBackRightDriveMotorId = 7; + public static final int kBackRightSteerMotorId = 8; + public static final int kBackRightEncoderId = 14; + public static final Angle kBackRightEncoderOffset = Rotations.of(-0.322998046875); + public static final boolean kBackRightSteerMotorInverted = true; + public static final boolean kBackRightEncoderInverted = false; + + public static final Distance kBackRightXPos = Inches.of(-11.5); + public static final Distance kBackRightYPos = Inches.of(-11.5); + + public static final SwerveModuleConstants< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + FrontLeft = + ConstantCreator.createModuleConstants( + kFrontLeftSteerMotorId, + kFrontLeftDriveMotorId, + kFrontLeftEncoderId, + kFrontLeftEncoderOffset, + kFrontLeftXPos, + kFrontLeftYPos, + kInvertLeftSide, + kFrontLeftSteerMotorInverted, + kFrontLeftEncoderInverted); + public static final SwerveModuleConstants< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + FrontRight = + ConstantCreator.createModuleConstants( + kFrontRightSteerMotorId, + kFrontRightDriveMotorId, + kFrontRightEncoderId, + kFrontRightEncoderOffset, + kFrontRightXPos, + kFrontRightYPos, + kInvertRightSide, + kFrontRightSteerMotorInverted, + kFrontRightEncoderInverted); + public static final SwerveModuleConstants< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + BackLeft = + ConstantCreator.createModuleConstants( + kBackLeftSteerMotorId, + kBackLeftDriveMotorId, + kBackLeftEncoderId, + kBackLeftEncoderOffset, + kBackLeftXPos, + kBackLeftYPos, + kInvertLeftSide, + kBackLeftSteerMotorInverted, + kBackLeftEncoderInverted); + public static final SwerveModuleConstants< + TalonFXConfiguration, TalonFXConfiguration, CANcoderConfiguration> + BackRight = + ConstantCreator.createModuleConstants( + kBackRightSteerMotorId, + kBackRightDriveMotorId, + kBackRightEncoderId, + kBackRightEncoderOffset, + kBackRightXPos, + kBackRightYPos, + kInvertRightSide, + kBackRightSteerMotorInverted, + kBackRightEncoderInverted); +} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 6c3125eb..ddcf451a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -3,6 +3,7 @@ import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.apriltag.AprilTagFields; import edu.wpi.first.networktables.NetworkTablesJNI; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.Constants; @@ -21,7 +22,6 @@ import frc.robot.subsystems.shared.elevator.ElevatorIO; import frc.robot.subsystems.shared.elevator.ElevatorIOSim; import frc.robot.subsystems.shared.vision.Vision; -import frc.robot.subsystems.shared.vision.VisionConstants.RobotCameras; import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimber; import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIO; import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIOSim; @@ -36,6 +36,7 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIO; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOSim; import frc.robot.util.LTNUpdater; +import frc.robot.util.LoggedChoreo.ChoreoChooser; import frc.robot.util.LoggedTunableNumber; import org.littletonrobotics.junction.Logger; @@ -54,28 +55,27 @@ public class V3_EpsilonRobotContainer implements RobotContainer { CommandXboxController driver = new CommandXboxController(0); // Auto chooser + private final ChoreoChooser autoChooser = new ChoreoChooser(); public V3_EpsilonRobotContainer() { if (Constants.getMode() != Mode.REPLAY) { switch (Constants.ROBOT) { case V3_EPSILON: - // drive = - // new Drive( - // new GyroIOPigeon2(), - // new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), - // new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), - // new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), - // new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); + drive = + new Drive( + new GyroIOPigeon2(), + new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), + new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), + new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), + new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); // elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); - // intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); - // manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); + // intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); + // manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); // climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); - // superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + // superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); vision = - new Vision( - () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), - RobotCameras.V3_EPSILON_CAMS); + new Vision(() -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded)); break; case V3_EPSILON_SIM: drive = @@ -130,6 +130,7 @@ public V3_EpsilonRobotContainer() { LTNUpdater.registerAll(drive, elevator, intake, manipulator); configureButtonBindings(); + configureAutos(); } /** @@ -161,7 +162,13 @@ private void configureButtonBindings() { superstructure.override(() -> manipulator.setArmGoal(ManipulatorArmState.VERTICAL_UP))); } - private void configureAutos() {} + private void configureAutos() { + autoChooser.addCmd( + "Drive FF Characterization", () -> DriveCommands.feedforwardCharacterization(drive)); + autoChooser.addCmd( + "Wheel Radius Characterization", () -> DriveCommands.wheelRadiusCharacterization(drive)); + SmartDashboard.putData("Autonomous Modes", autoChooser); + } /** * Periodic function for the robot. This function is called every 20ms, and is responsible for @@ -184,9 +191,9 @@ public void robotPeriodic() { elevator.getPositionMeters(), intake.getPivotAngle(), manipulator.getArmAngle())); // Logger.recordOutput( - // "FieldSimulation/Algae", SimulatedArena.getInstance().getGamePiecesArrayByType("Algae")); + // "FieldSimulation/Algae", SimulatedArena.getInstance().getGamePiecesArrayByType("Algae")); // Logger.recordOutput( - // "FieldSimulation/Coral", SimulatedArena.getInstance().getGamePiecesArrayByType("Coral")); + // "FieldSimulation/Coral", SimulatedArena.getInstance().getGamePiecesArrayByType("Coral")); } /** @@ -197,6 +204,16 @@ public void robotPeriodic() { */ @Override public Command getAutonomousCommand() { - return manipulator.sysIdRoutine(superstructure); + return autoChooser.selectedCommand(); + // return superstructure.allTransition(); + // return Commands.sequence( + // V3_EpsilonCompositeCommands.dropAlgae( + // drive, + // elevator, + // manipulator, + // intake, + // superstructure, + // () -> ReefState.ALGAE_INTAKE_TOP, + // RobotCameras.V3_EPSILON_CAMS)); } } From 84cbf5bb327a3a491bda7f44245683d97a6a75fa Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Sat, 18 Oct 2025 15:24:21 -0400 Subject: [PATCH 127/180] more fixing --- src/main/deploy/Superstructure.dot | 60 ++++++------------- src/main/java/frc/robot/FieldConstants.java | 1 + src/main/java/frc/robot/Robot.java | 2 +- .../shared/elevator/ElevatorConstants.java | 2 + .../V3_EpsilonSuperstructure.java | 22 +++++-- .../V3_EpsilonSuperstructureStates.java | 7 ++- 6 files changed, 47 insertions(+), 47 deletions(-) diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/Superstructure.dot index 66cded18..1e590004 100644 --- a/src/main/deploy/Superstructure.dot +++ b/src/main/deploy/Superstructure.dot @@ -15,45 +15,30 @@ digraph Superstructure { GROUND_ACQUISITION -> FLIP_UP [type=UNCONSTRAINED] GROUND_ACQUISITION -> GROUND_INTAKE [type=UNCONSTRAINED] GROUND_ACQUISITION -> L1 [type=UNCONSTRAINED] - GROUND_ACQUISITION -> L2 [type=UNCONSTRAINED] - GROUND_ACQUISITION -> L3 [type=UNCONSTRAINED] GROUND_ACQUISITION -> L4 [type=UNCONSTRAINED] GROUND_ACQUISITION -> HANDOFF [type=UNCONSTRAINED] - GROUND_ACQUISITION -> STOW_UP [type=UNCONSTRAINED] - GROUND_ACQUISITION -> L2_ALGAE [type=UNCONSTRAINED] GROUND_ACQUISITION -> L3_ALGAE [type=UNCONSTRAINED] - GROUND_ACQUISITION -> PROCESSOR [type=UNCONSTRAINED] GROUND_ACQUISITION -> BARGE [type=UNCONSTRAINED] GROUND_INTAKE -> FLIP_UP [type=UNCONSTRAINED] GROUND_INTAKE -> GROUND_ACQUISITION [type=UNCONSTRAINED] GROUND_INTAKE -> L1 [type=UNCONSTRAINED] - GROUND_INTAKE -> L2 [type=UNCONSTRAINED] - GROUND_INTAKE -> L3 [type=UNCONSTRAINED] GROUND_INTAKE -> L4 [type=UNCONSTRAINED] GROUND_INTAKE -> HANDOFF [type=UNCONSTRAINED] - GROUND_INTAKE -> STOW_UP [type=UNCONSTRAINED] - GROUND_INTAKE -> L2_ALGAE [type=UNCONSTRAINED] GROUND_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] - GROUND_INTAKE -> PROCESSOR [type=UNCONSTRAINED] GROUND_INTAKE -> BARGE [type=UNCONSTRAINED] L1 -> FLIP_UP [type=UNCONSTRAINED] L1 -> GROUND_ACQUISITION [type=UNCONSTRAINED] - L1 -> L2 [type=UNCONSTRAINED] - L1 -> L3 [type=UNCONSTRAINED] L1 -> L4 [type=UNCONSTRAINED] L1 -> L1_SCORE [type=UNCONSTRAINED] L1 -> HANDOFF [type=UNCONSTRAINED] - L1 -> STOW_UP [type=UNCONSTRAINED] - L1 -> L2_ALGAE [type=UNCONSTRAINED] L1 -> L3_ALGAE [type=UNCONSTRAINED] - L1 -> PROCESSOR [type=UNCONSTRAINED] L1 -> BARGE [type=UNCONSTRAINED] L2 -> STOW_DOWN [type=UNCONSTRAINED] L2 -> GROUND_ACQUISITION [type=UNCONSTRAINED] - L2 -> L1 [type=UNCONSTRAINED] + L2 -> FLIP_DOWN [type=UNCONSTRAINED] L2 -> L3 [type=UNCONSTRAINED] L2 -> L4 [type=UNCONSTRAINED] L2 -> L2_SCORE [type=UNCONSTRAINED] @@ -65,8 +50,7 @@ digraph Superstructure { L2 -> BARGE [type=UNCONSTRAINED] L3 -> STOW_DOWN [type=UNCONSTRAINED] - L3 -> GROUND_ACQUISITION [type=UNCONSTRAINED] - L3 -> L1 [type=UNCONSTRAINED] + L3 -> FLIP_DOWN [type=UNCONSTRAINED] L3 -> L2 [type=UNCONSTRAINED] L3 -> L4 [type=UNCONSTRAINED] L3 -> L3_SCORE [type=UNCONSTRAINED] @@ -90,10 +74,10 @@ digraph Superstructure { L4 -> PROCESSOR [type=UNCONSTRAINED] L4 -> BARGE [type=UNCONSTRAINED] - L1_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L1_SCORE -> L1 [type=UNCONSTRAINED] L2_SCORE -> STOW_DOWN [type=UNCONSTRAINED] - L2_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L2_SCORE -> FLIP_DOWN [type=UNCONSTRAINED] L2_SCORE -> L1 [type=UNCONSTRAINED] L2_SCORE -> L2 [type=UNCONSTRAINED] L2_SCORE -> L3 [type=UNCONSTRAINED] @@ -106,7 +90,7 @@ digraph Superstructure { L2_SCORE -> BARGE [type=UNCONSTRAINED] L3_SCORE -> STOW_DOWN [type=UNCONSTRAINED] - L3_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L3_SCORE -> FLIP_DOWN [type=UNCONSTRAINED] L3_SCORE -> L1 [type=UNCONSTRAINED] L3_SCORE -> L2 [type=UNCONSTRAINED] L3_SCORE -> L3 [type=UNCONSTRAINED] @@ -131,33 +115,30 @@ digraph Superstructure { L4_SCORE -> PROCESSOR [type=UNCONSTRAINED] L4_SCORE -> BARGE [type=UNCONSTRAINED] - HANDOFF -> STOW_DOWN [type=UNCONSTRAINED] + HANDOFF -> FLIP_UP [type=UNCONSTRAINED] HANDOFF -> GROUND_ACQUISITION [type=UNCONSTRAINED] HANDOFF -> L1 [type=UNCONSTRAINED] HANDOFF -> L2 [type=UNCONSTRAINED] HANDOFF -> L3 [type=UNCONSTRAINED] HANDOFF -> L4 [type=UNCONSTRAINED] - HANDOFF -> STOW_UP [type=UNCONSTRAINED] HANDOFF -> L2_ALGAE [type=UNCONSTRAINED] HANDOFF -> L3_ALGAE [type=UNCONSTRAINED] HANDOFF -> PROCESSOR [type=UNCONSTRAINED] HANDOFF -> BARGE [type=UNCONSTRAINED] STOW_UP -> STOW_DOWN [type=UNCONSTRAINED] - STOW_UP -> GROUND_ACQUISITION [type=UNCONSTRAINED] - STOW_UP -> L1 [type=UNCONSTRAINED] + STOW_UP -> FLIP_DOWN [type=UNCONSTRAINED] STOW_UP -> L2 [type=UNCONSTRAINED] STOW_UP -> L3 [type=UNCONSTRAINED] STOW_UP -> L4 [type=UNCONSTRAINED] - STOW_UP -> HANDOFF [type=UNCONSTRAINED] STOW_UP -> L2_ALGAE [type=UNCONSTRAINED] STOW_UP -> L3_ALGAE [type=UNCONSTRAINED] STOW_UP -> PROCESSOR [type=UNCONSTRAINED] STOW_UP -> BARGE [type=UNCONSTRAINED] + STOW_UP -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] L2_ALGAE -> STOW_DOWN [type = NO_ALGAE] - L2_ALGAE -> GROUND_ACQUISITION [type = NO_ALGAE] - L2_ALGAE -> L1 [type = NO_ALGAE] + L2_ALGAE -> FLIP_DOWN [type = NO_ALGAE] L2_ALGAE -> L2 [type=UNCONSTRAINED] L2_ALGAE -> L3 [type=UNCONSTRAINED] L2_ALGAE -> L4 [type=UNCONSTRAINED] @@ -193,18 +174,8 @@ digraph Superstructure { L3_ALGAE_INTAKE -> STOW_UP [type=UNCONSTRAINED] L3_ALGAE_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] - PROCESSOR -> STOW_DOWN [type = NO_ALGAE] - PROCESSOR -> FLIP_DOWN [type = NO_ALGAE] - PROCESSOR -> L1 [type = NO_ALGAE] - PROCESSOR -> L2 [type=UNCONSTRAINED] - PROCESSOR -> L3 [type=UNCONSTRAINED] - PROCESSOR -> L4 [type=UNCONSTRAINED] - PROCESSOR -> HANDOFF [type = NO_ALGAE] - PROCESSOR -> STOW_UP [type=UNCONSTRAINED] - PROCESSOR -> L2_ALGAE [type=UNCONSTRAINED] - PROCESSOR -> L3_ALGAE [type=UNCONSTRAINED] + PROCESSOR -> POST_PROCESSOR [type = NO_ALGAE] PROCESSOR -> PROCESSOR_SCORE [type=UNCONSTRAINED] - PROCESSOR -> BARGE [type=UNCONSTRAINED] PROCESSOR_SCORE -> PROCESSOR [type=UNCONSTRAINED] @@ -226,9 +197,8 @@ digraph Superstructure { L4_SCORE -> GROUND_AQUISITION_ALGAE L2_SCORE -> GROUND_AQUISITION_ALGAE - GROUND_AQUISITION_ALGAE -> STOW_UP GROUND_AQUISITION_ALGAE -> PROCESSOR - GROUND_AQUISITION_ALGAE -> FLIP_DOWN + GROUND_AQUISITION_ALGAE -> POST_PROCESSOR GROUND_AQUISITION_ALGAE -> GROUND_INTAKE_ALGAE GROUND_INTAKE_ALGAE -> GROUND_AQUISITION_ALGAE @@ -238,4 +208,12 @@ digraph Superstructure { FLIP_DOWN -> HANDOFF [type=UNCONSTRAINED] FLIP_UP -> STOW_DOWN [type=UNCONSTRAINED] + FLIP_UP -> STOW_UP [type=UNCONSTRAINED] + FLIP_UP -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] + FLIP_UP -> L2 [type=UNCONSTRAINED] + FLIP_UP -> L3 [type=UNCONSTRAINED] + FLIP_UP -> PROCESSOR [type=UNCONSTRAINED] + + POST_PROCESSOR -> FLIP_DOWN [type = NO_ALGAE] + POST_PROCESSOR -> STOW_UP [type = UNCONSTRAINED] } \ No newline at end of file diff --git a/src/main/java/frc/robot/FieldConstants.java b/src/main/java/frc/robot/FieldConstants.java index 07527847..91327442 100644 --- a/src/main/java/frc/robot/FieldConstants.java +++ b/src/main/java/frc/robot/FieldConstants.java @@ -59,6 +59,7 @@ public static enum ReefPose { public static enum ReefState { STOW, + POST_PROCESSOR, HIGH_STOW, CORAL_INTAKE, ALGAE_FLOOR_INTAKE, diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 2e0c5e82..e4048d20 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -123,7 +123,7 @@ public void robotInit() { case SIM: // Running a physics simulator, log to NT - setUseTiming(false); + // setUseTiming(false); Logger.addDataReceiver(new NT4Publisher()); break; diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index cf5cc32e..8125133d 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -28,6 +28,7 @@ public class ElevatorConstants { REEF_STATE_ELEVATOR_POSITION_MAP = Map.ofEntries( Map.entry(ReefState.STOW, ElevatorPositions.STOW), + Map.entry(ReefState.POST_PROCESSOR, ElevatorPositions.POST_PROCESSOR), Map.entry(ReefState.HIGH_STOW, ElevatorPositions.HIGH_STOW), Map.entry(ReefState.CORAL_INTAKE, ElevatorPositions.CORAL_INTAKE), Map.entry(ReefState.ALGAE_FLOOR_INTAKE, ElevatorPositions.ALGAE_INTAKE), @@ -296,6 +297,7 @@ public static record PositionConstants(double V1, double V2, double V3) {} @RequiredArgsConstructor public static enum ElevatorPositions { STOW(new PositionConstants(0.0, 0.0, 0.0)), + POST_PROCESSOR(new PositionConstants(0.5, 0.5, 0.5)), CORAL_INTAKE(new PositionConstants(0.0, 0.0, Units.inchesToMeters(34.75))), ALGAE_INTAKE( new PositionConstants( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 4930133f..ecf317d7 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -600,6 +600,9 @@ public Command allTransition() { for (var source : V3_EpsilonSuperstructureStates.values()) { for (var sink : V3_EpsilonSuperstructureStates.values()) { if (source == sink) continue; + if (source == V3_EpsilonSuperstructureStates.STOW_DOWN) continue; + if (source == V3_EpsilonSuperstructureStates.STOW_UP) continue; + if (source != V3_EpsilonSuperstructureStates.START && sink != V3_EpsilonSuperstructureStates.START && source != V3_EpsilonSuperstructureStates.OVERRIDE @@ -607,13 +610,24 @@ public Command allTransition() { all = all.andThen( runGoal(sink), - runOnce(() -> System.out.println("Initial Pose:" + sink)), - Commands.waitUntil(() -> atGoal())); + runOnce( + () -> + Logger.recordOutput( + "Superstructure/Current Objective", + source.toString() + " -> " + sink.toString())), + Commands.waitUntil(() -> atGoal()), + Commands.waitSeconds(1.0)); all = all.andThen( runGoal(source), - runOnce(() -> System.out.println("Final Pose:" + source)), - Commands.waitUntil(() -> atGoal())); + runOnce( + () -> + Logger.recordOutput( + "Superstructure/Current Objective", + sink.toString() + " -> " + source.toString())), + Commands.waitUntil(() -> atGoal()), + Commands.waitUntil(() -> atGoal()), + Commands.waitSeconds(1.0)); } } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 941bfd91..23123b2f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -18,7 +18,7 @@ public enum V3_EpsilonSuperstructureStates { STOW_UP( "STOW_UP", new SubsystemPoses( - ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.HANDOFF), + ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), SubsystemActions.empty()), OVERRIDE("OVERRIDE", new SubsystemPoses(), SubsystemActions.empty()), GROUND_ACQUISITION( @@ -120,6 +120,11 @@ public enum V3_EpsilonSuperstructureStates { "PROCESSOR", new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), SubsystemActions.empty()), + POST_PROCESSOR( + "POST_PROCESSOR", + new SubsystemPoses( + ReefState.POST_PROCESSOR, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + SubsystemActions.empty()), PROCESSOR_SCORE( "PROCESSOR_SCORE", new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), From 580b84a62140b62605abc1e471c61f98110f29de Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Sat, 18 Oct 2025 23:09:21 -0400 Subject: [PATCH 128/180] done --- src/main/deploy/Superstructure.dot | 31 +++++++++---------- .../V3_EpsilonSuperstructure.java | 12 +++---- 2 files changed, 19 insertions(+), 24 deletions(-) diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/Superstructure.dot index 1e590004..497eace6 100644 --- a/src/main/deploy/Superstructure.dot +++ b/src/main/deploy/Superstructure.dot @@ -37,12 +37,10 @@ digraph Superstructure { L1 -> BARGE [type=UNCONSTRAINED] L2 -> STOW_DOWN [type=UNCONSTRAINED] - L2 -> GROUND_ACQUISITION [type=UNCONSTRAINED] L2 -> FLIP_DOWN [type=UNCONSTRAINED] L2 -> L3 [type=UNCONSTRAINED] L2 -> L4 [type=UNCONSTRAINED] L2 -> L2_SCORE [type=UNCONSTRAINED] - L2 -> HANDOFF [type=UNCONSTRAINED] L2 -> STOW_UP [type=UNCONSTRAINED] L2 -> L2_ALGAE [type=UNCONSTRAINED] L2 -> L3_ALGAE [type=UNCONSTRAINED] @@ -60,6 +58,7 @@ digraph Superstructure { L3 -> L3_ALGAE [type=UNCONSTRAINED] L3 -> PROCESSOR [type=UNCONSTRAINED] L3 -> BARGE [type=UNCONSTRAINED] + L3 -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] L4 -> STOW_DOWN [type=UNCONSTRAINED] L4 -> GROUND_ACQUISITION [type=UNCONSTRAINED] @@ -73,16 +72,15 @@ digraph Superstructure { L4 -> L3_ALGAE [type=UNCONSTRAINED] L4 -> PROCESSOR [type=UNCONSTRAINED] L4 -> BARGE [type=UNCONSTRAINED] + L4 -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] L1_SCORE -> L1 [type=UNCONSTRAINED] L2_SCORE -> STOW_DOWN [type=UNCONSTRAINED] L2_SCORE -> FLIP_DOWN [type=UNCONSTRAINED] - L2_SCORE -> L1 [type=UNCONSTRAINED] L2_SCORE -> L2 [type=UNCONSTRAINED] L2_SCORE -> L3 [type=UNCONSTRAINED] L2_SCORE -> L4 [type=UNCONSTRAINED] - L2_SCORE -> HANDOFF [type=UNCONSTRAINED] L2_SCORE -> STOW_UP [type=UNCONSTRAINED] L2_SCORE -> L2_ALGAE [type=UNCONSTRAINED] L2_SCORE -> L3_ALGAE [type=UNCONSTRAINED] @@ -91,39 +89,30 @@ digraph Superstructure { L3_SCORE -> STOW_DOWN [type=UNCONSTRAINED] L3_SCORE -> FLIP_DOWN [type=UNCONSTRAINED] - L3_SCORE -> L1 [type=UNCONSTRAINED] L3_SCORE -> L2 [type=UNCONSTRAINED] - L3_SCORE -> L3 [type=UNCONSTRAINED] L3_SCORE -> L4 [type=UNCONSTRAINED] + L3_SCORE -> L3_SCORE [type=UNCONSTRAINED] L3_SCORE -> HANDOFF [type=UNCONSTRAINED] L3_SCORE -> STOW_UP [type=UNCONSTRAINED] L3_SCORE -> L2_ALGAE [type=UNCONSTRAINED] L3_SCORE -> L3_ALGAE [type=UNCONSTRAINED] L3_SCORE -> PROCESSOR [type=UNCONSTRAINED] L3_SCORE -> BARGE [type=UNCONSTRAINED] + L3_SCORE -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] L4_SCORE -> FLIP_UP [type=UNCONSTRAINED] L4_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] L4_SCORE -> L1 [type=UNCONSTRAINED] - L4_SCORE -> L2 [type=UNCONSTRAINED] L4_SCORE -> L3 [type=UNCONSTRAINED] L4_SCORE -> L4 [type=UNCONSTRAINED] L4_SCORE -> HANDOFF [type=UNCONSTRAINED] - L4_SCORE -> STOW_UP [type=UNCONSTRAINED] - L4_SCORE -> L2_ALGAE [type=UNCONSTRAINED] - L4_SCORE -> L3_ALGAE [type=UNCONSTRAINED] - L4_SCORE -> PROCESSOR [type=UNCONSTRAINED] L4_SCORE -> BARGE [type=UNCONSTRAINED] HANDOFF -> FLIP_UP [type=UNCONSTRAINED] HANDOFF -> GROUND_ACQUISITION [type=UNCONSTRAINED] HANDOFF -> L1 [type=UNCONSTRAINED] - HANDOFF -> L2 [type=UNCONSTRAINED] - HANDOFF -> L3 [type=UNCONSTRAINED] HANDOFF -> L4 [type=UNCONSTRAINED] - HANDOFF -> L2_ALGAE [type=UNCONSTRAINED] HANDOFF -> L3_ALGAE [type=UNCONSTRAINED] - HANDOFF -> PROCESSOR [type=UNCONSTRAINED] HANDOFF -> BARGE [type=UNCONSTRAINED] STOW_UP -> STOW_DOWN [type=UNCONSTRAINED] @@ -149,10 +138,11 @@ digraph Superstructure { L2_ALGAE -> PROCESSOR [type=UNCONSTRAINED] L2_ALGAE -> BARGE [type=UNCONSTRAINED] L2_ALGAE -> L2_ALGAE_DROP + L2_ALGAE -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] L2_ALGAE_DROP -> L2_ALGAE - L2_ALGAE_INTAKE -> STOW_UP [type=UNCONSTRAINED] + L2_ALGAE_INTAKE -> FLIP_DOWN [type=UNCONSTRAINED] L2_ALGAE_INTAKE -> L2_ALGAE [type=UNCONSTRAINED] L3_ALGAE -> STOW_DOWN [type = NO_ALGAE] @@ -168,6 +158,7 @@ digraph Superstructure { L3_ALGAE -> PROCESSOR [type=UNCONSTRAINED] L3_ALGAE -> BARGE [type=UNCONSTRAINED] L3_ALGAE -> L3_ALGAE_DROP + L3_ALGAE -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] L3_ALGAE_DROP -> L3_ALGAE @@ -176,6 +167,7 @@ digraph Superstructure { PROCESSOR -> POST_PROCESSOR [type = NO_ALGAE] PROCESSOR -> PROCESSOR_SCORE [type=UNCONSTRAINED] + PROCESSOR -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] PROCESSOR_SCORE -> PROCESSOR [type=UNCONSTRAINED] @@ -191,6 +183,7 @@ digraph Superstructure { BARGE -> L3_ALGAE [type=UNCONSTRAINED] BARGE -> PROCESSOR [type=UNCONSTRAINED] BARGE -> BARGE_SCORE [type=UNCONSTRAINED] + BARGE -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] BARGE_SCORE -> BARGE [type=UNCONSTRAINED] @@ -216,4 +209,10 @@ digraph Superstructure { POST_PROCESSOR -> FLIP_DOWN [type = NO_ALGAE] POST_PROCESSOR -> STOW_UP [type = UNCONSTRAINED] + POST_PROCESSOR -> L2_ALGAE [type = UNCONSTRAINED] + POST_PROCESSOR -> L3_ALGAE [type = UNCONSTRAINED] + POST_PROCESSOR -> L2 [type = UNCONSTRAINED] + POST_PROCESSOR -> L3 [type = UNCONSTRAINED] + POST_PROCESSOR -> L4 [type = UNCONSTRAINED] + POST_PROCESSOR -> BARGE [type = UNCONSTRAINED] } \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index ecf317d7..f480d6e4 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -600,9 +600,8 @@ public Command allTransition() { for (var source : V3_EpsilonSuperstructureStates.values()) { for (var sink : V3_EpsilonSuperstructureStates.values()) { if (source == sink) continue; - if (source == V3_EpsilonSuperstructureStates.STOW_DOWN) continue; - if (source == V3_EpsilonSuperstructureStates.STOW_UP) continue; - + if (sink == V3_EpsilonSuperstructureStates.FLIP_DOWN) continue; + if (sink == V3_EpsilonSuperstructureStates.FLIP_UP) continue; if (source != V3_EpsilonSuperstructureStates.START && sink != V3_EpsilonSuperstructureStates.START && source != V3_EpsilonSuperstructureStates.OVERRIDE @@ -615,8 +614,7 @@ public Command allTransition() { Logger.recordOutput( "Superstructure/Current Objective", source.toString() + " -> " + sink.toString())), - Commands.waitUntil(() -> atGoal()), - Commands.waitSeconds(1.0)); + Commands.waitUntil(() -> atGoal())); all = all.andThen( runGoal(source), @@ -625,9 +623,7 @@ public Command allTransition() { Logger.recordOutput( "Superstructure/Current Objective", sink.toString() + " -> " + source.toString())), - Commands.waitUntil(() -> atGoal()), - Commands.waitUntil(() -> atGoal()), - Commands.waitSeconds(1.0)); + Commands.waitUntil(() -> atGoal())); } } } From be947bd5cc3c59fb14d1b001789e1dfc30561658 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Sat, 18 Oct 2025 23:13:04 -0400 Subject: [PATCH 129/180] remove ik --- .../frc/robot/commands/CompositeCommands.java | 44 --------- .../V3_EpsilonSuperstructure.java | 7 -- .../V3_EpsilonSuperstructureKinematics.java | 96 ------------------- 3 files changed, 147 deletions(-) delete mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureKinematics.java diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index fe9b9245..e68e3c85 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -933,49 +933,5 @@ public static final Command manipulatorGroundIntake( () -> superstructure.runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE)), Commands.runOnce(() -> manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE))); } - - public static final Command runIK( - Matrix[] trajectory, - V3_EpsilonSuperstructure superstructure, - double t, - Timer timer) { - return Commands.sequence( - Commands.print("Started"), - Commands.runOnce(() -> timer.start()), - Commands.run( - () -> { - if (timer.hasElapsed(t)) return; - double ypos = - TrajectoryGenerator.evaluateQuinticTrajectory(trajectory[0], timer.get()); - double zpos = - TrajectoryGenerator.evaluateQuinticTrajectory(trajectory[1], timer.get()); - - superstructure.runIK(ypos, zpos); - })); - } - - public static final Command createTrajectoryTestCommand( - V3_EpsilonSuperstructure superstructure, Timer timer) { - // 1. Define the start and end points of a simple trajectory - // For example, a 2-second move from (y=0.5, z=0.5) to (y=1.0, z=0.75) - double startY = 0.55, endY = -0.55; - double startZ = 1, endZ = 2; - double duration = 4.0; - - // 2. Generate the trajectory coefficients for Y and Z axes - // We assume the arm starts and ends at rest (zero velocity and acceleration) - @SuppressWarnings("unchecked") - Matrix[] trajectoryCoeffs = - new Matrix[] { - TrajectoryGenerator.generateQuinticTrajectory(startY, 0, 0, endY, 0, 0, 0, duration), - TrajectoryGenerator.generateQuinticTrajectory(startZ, 0, 0, endZ, 0, 0, 0, duration) - }; - - // 3. Return the composite command - return Commands.sequence( - Commands.runOnce(() -> superstructure.runIK(startY, startZ)), - Commands.waitSeconds(2), - runIK(trajectoryCoeffs, superstructure, duration, timer)); - } } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index f480d6e4..dd414e3c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -11,7 +11,6 @@ import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.EdgeCommand; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.GamePieceEdge; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureKinematics.JointSolution; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; @@ -657,10 +656,4 @@ public Command stateTransitions(V3_EpsilonSuperstructureStates source) { public boolean armBelowThreshold() { return manipulator.getArmAngle().getDegrees() >= 90; } - - public void runIK(double py, double pz) { - JointSolution sol = V3_EpsilonSuperstructureKinematics.ik(py, pz); - elevator.setPosition(sol.d3()); - manipulator.setArmGoal(sol.theta5()); - } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureKinematics.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureKinematics.java deleted file mode 100644 index 40eb09b1..00000000 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureKinematics.java +++ /dev/null @@ -1,96 +0,0 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure; - -import edu.wpi.first.math.MatBuilder; -import edu.wpi.first.math.Matrix; -import edu.wpi.first.math.Nat; -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.numbers.N4; -import edu.wpi.first.math.util.Units; - -public class V3_EpsilonSuperstructureKinematics { - - // -------------------------- DH Parameters ------------------------- - // [0 0 -l1 0] - // [pi/2 0 0 0] - // [0 l3+d3 0 0] - // [0 0 0 pi/2] - // [0 l5 0 0] - // [theta5 0 0 -pi/2] - // [-pi/2 l7 0 0] - - // -------- Homogeneous Transform from Base to End Effector --------- - // [1, 0, 0, -l1 + l5] - // [0, cos(theta5), -sin(theta5), -l7*sin(theta5)] - // [0, sin(theta5), cos(theta5), d3 + l3 + l7*cos(theta5)] - // [0, 0, 0, 1] - - private static final double l1; - private static final double l3; - private static final double l5; - private static final double l7; - - static { - l1 = Units.inchesToMeters(7.0); - l3 = Units.inchesToMeters(11.351122); - l5 = Units.inchesToMeters(7.0); - l7 = Units.inchesToMeters(22.259494); - } - - private static final Matrix fkMat(double d3, Rotation2d theta5) { - double cos5 = theta5.getCos(); - double sin5 = theta5.getSin(); - - return MatBuilder.fill( - Nat.N4(), - Nat.N4(), - 1, - 0, - 0, - -l1 + l5, - 0, - cos5, - -sin5, - -l7 * sin5, - 0, - sin5, - cos5, - d3 + l3 + l7 * cos5, - 0, - 0, - 0, - 1); - } - - /** - * (Forward Kinematics) Calculates the end-effector's world coordinates. - * - * @return A Translation2d representing the (x, y) world coordinate. - */ - public static EndEffectorPose fk(double d3, Rotation2d theta5) { - Matrix t = fkMat(d3, theta5); - // Note: The FK matrix seems to be in the YZ plane based on the ik function signature. - // We'll return the y and z components. - return new EndEffectorPose(t.get(1, 3), t.get(2, 3)); - } - - /** - * (Inverse Kinematics) Calculates the required joint states for a target coordinate. - * - * @param py The target y-position in the robot's frame. - * @param pz The target z-position in the robot's frame. - * @return A JointSolution containing the required d3 and theta5 values. - */ - public static JointSolution ik(double py, double pz) { - Rotation2d theta5 = - Rotation2d.fromRadians(Math.atan2(Math.sqrt(1 - Math.pow((py / l7), 2)), py / l7)) - .minus(Rotation2d.kCCW_Pi_2); - double d3 = - pz - l3 - (l7 * Math.sin(Math.atan2(Math.sqrt(1 - Math.pow((py / l7), 2)), py / l7))); - - return new JointSolution(d3, theta5); - } - - public static record EndEffectorPose(double y, double z) {} - - public static record JointSolution(double d3, Rotation2d theta5) {} -} From fb4b2c2f6893ccabb26279f1de20263b4bff0fd5 Mon Sep 17 00:00:00 2001 From: jasminepalit Date: Sun, 19 Oct 2025 14:55:46 -0400 Subject: [PATCH 130/180] Elevator Bringup --- .OutlineViewer/outlineviewer.json | 3 ++ .SysId/sysid.json | 1 + .../subsystems/shared/elevator/Elevator.java | 8 +++-- .../shared/elevator/ElevatorConstants.java | 34 +++++++++---------- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 13 +++++-- .../V3_EpsilonSuperstructure.java | 4 +-- 6 files changed, 39 insertions(+), 24 deletions(-) create mode 100644 .SysId/sysid.json diff --git a/.OutlineViewer/outlineviewer.json b/.OutlineViewer/outlineviewer.json index 5dabee93..68109c91 100644 --- a/.OutlineViewer/outlineviewer.json +++ b/.OutlineViewer/outlineviewer.json @@ -37,6 +37,9 @@ "Gains": { "open": true }, + "Stow Gains": { + "open": true + }, "open": true }, "Funnel": { diff --git a/.SysId/sysid.json b/.SysId/sysid.json new file mode 100644 index 00000000..0967ef42 --- /dev/null +++ b/.SysId/sysid.json @@ -0,0 +1 @@ +{} diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java index 8c1527e0..c8ccc6aa 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java @@ -180,12 +180,16 @@ private Command sysIdRoutine(Subsystem subsystem) { new SysIdRoutine( new SysIdRoutine.Config( Volts.of(1).per(Second), - Volts.of(6), - Seconds.of(10), + Volts.of(3), + Seconds.of(3), (state) -> Logger.recordOutput("Elevator/SysID State", state.toString())), new SysIdRoutine.Mechanism((volts) -> io.setVoltage(volts.in(Volts)), null, subsystem)); return Commands.sequence( + Commands.runOnce( + () -> { + isClosedLoop = false; + }), characterizationRoutine .quasistatic(Direction.kForward) .until( diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index 874c3a42..4b5d4268 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -122,14 +122,14 @@ public class ElevatorConstants { case V3_EPSILON_SIM: ELEVATOR_CAN_ID = 20; ELEVATOR_GEAR_RATIO = 4.0; - DRUM_RADIUS = Units.inchesToMeters(2.256 / 2.0); + DRUM_RADIUS = Units.inchesToMeters(2.211 / 2.0); ELEVATOR_SUPPLY_CURRENT_LIMIT = 40; ELEVATOR_STATOR_CURRENT_LIMIT = 80; ELEVATOR_PARAMETERS = new ElevatorParameters( - DCMotor.getKrakenX60Foc(2), 6.803886, 0.0, Units.inchesToMeters(62), 2); + DCMotor.getKrakenX60Foc(2), 6.803886, 0.0, Units.inchesToMeters(53), 2); switch (Constants.getMode()) { case REAL: @@ -137,29 +137,29 @@ public class ElevatorConstants { default: GAINS = new Gains( - new LoggedTunableNumber("Elevator/Gains/kP", 2.0), - new LoggedTunableNumber("Elevator/Gains/kD", 0.1), - new LoggedTunableNumber("Elevator/Gains/kS", 0.225), - new LoggedTunableNumber("Elevator/Gains/kG", 0.075), - new LoggedTunableNumber("Elevator/Gains/kV", 0.0), + new LoggedTunableNumber("Elevator/Gains/kP", 5), + new LoggedTunableNumber("Elevator/Gains/kD", 0), + new LoggedTunableNumber("Elevator/Gains/kS", 0.070776), + new LoggedTunableNumber("Elevator/Gains/kG", 0.35521), + new LoggedTunableNumber("Elevator/Gains/kV", 0), new LoggedTunableNumber("Elevator/Gains/kA", 0.0)); CONSTRAINTS = new Constraints( - new LoggedTunableNumber("Elevator/Max Acceleration", 16.0), - new LoggedTunableNumber("Elevator/Cruising Velocity", 16.0), + new LoggedTunableNumber("Elevator/Max Acceleration", 11), + new LoggedTunableNumber("Elevator/Cruising Velocity", 5), new LoggedTunableNumber("Elevator/Goal Tolerance", 0.02)); STOW_GAINS = new Gains( - new LoggedTunableNumber("Elevator/Stow Gains/kP", 2.0), - new LoggedTunableNumber("Elevator/Stow Gains/kD", 0.1), - new LoggedTunableNumber("Elevator/Stow Gains/kS", 0.225), - new LoggedTunableNumber("Elevator/Stow Gains/kG", 0.075), + new LoggedTunableNumber("Elevator/Stow Gains/kP", 5), + new LoggedTunableNumber("Elevator/Stow Gains/kD", 0), + new LoggedTunableNumber("Elevator/Stow Gains/kS", 0), + new LoggedTunableNumber("Elevator/Stow Gains/kG", 0), new LoggedTunableNumber("Elevator/Stow Gains/kV", 0.0), new LoggedTunableNumber("Elevator/Stow Gains/kA", 0.0)); STOW_CONSTRAINTS = new Constraints( - new LoggedTunableNumber("Elevator/Stow Max Acceleration", 16.0), - new LoggedTunableNumber("Elevator/Stow Cruising Velocity", 16.0), + new LoggedTunableNumber("Elevator/Stow Max Acceleration", 11), + new LoggedTunableNumber("Elevator/Stow Cruising Velocity", 5), new LoggedTunableNumber("Elevator/Stow Goal Tolerance", 0.02)); break; case SIM: @@ -330,7 +330,7 @@ public static enum ElevatorPositions { new PositionConstants( 1.3864590139769697 + Units.inchesToMeters(0.5), 1.3864590139769697 + Units.inchesToMeters(0.5), - Units.inchesToMeters(55))), + Units.inchesToMeters(48))), L4_PLUS( new PositionConstants( 0.0, @@ -357,7 +357,7 @@ public double getPosition() { case V3_EPSILON, V3_EPSILON_SIM: return position.V3(); default: - return position.V1(); + return position.V3(); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index ddcf451a..355ee146 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -15,12 +15,15 @@ import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.drive.DriveConstants; import frc.robot.subsystems.shared.drive.GyroIO; +import frc.robot.subsystems.shared.drive.GyroIOPigeon2; import frc.robot.subsystems.shared.drive.ModuleIO; import frc.robot.subsystems.shared.drive.ModuleIOSim; +import frc.robot.subsystems.shared.drive.ModuleIOTalonFX; import frc.robot.subsystems.shared.elevator.Elevator; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.shared.elevator.ElevatorIO; import frc.robot.subsystems.shared.elevator.ElevatorIOSim; +import frc.robot.subsystems.shared.elevator.ElevatorIOTalonFX; import frc.robot.subsystems.shared.vision.Vision; import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimber; import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIO; @@ -69,7 +72,7 @@ public V3_EpsilonRobotContainer() { new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); - // elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); + elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); // intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); // manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); // climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); @@ -90,7 +93,7 @@ public V3_EpsilonRobotContainer() { manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOSim()); superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); - leds = new V3_EpsilonLEDs(); + // leds = new V3_EpsilonLEDs(); vision = new Vision(() -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded)); break; @@ -160,6 +163,10 @@ private void configureButtonBindings() { superstructure.override(() -> manipulator.setArmGoal(ManipulatorArmState.HANDOFF))) .toggleOnFalse( superstructure.override(() -> manipulator.setArmGoal(ManipulatorArmState.VERTICAL_UP))); + + driver.b().onTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)); + + driver.x().onTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); } private void configureAutos() { @@ -204,7 +211,7 @@ public void robotPeriodic() { */ @Override public Command getAutonomousCommand() { - return autoChooser.selectedCommand(); + return elevator.sysIdRoutine(superstructure); // return superstructure.allTransition(); // return Commands.sequence( // V3_EpsilonCompositeCommands.dropAlgae( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index e115da96..5d8743e9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -98,10 +98,10 @@ public V3_EpsilonSuperstructure( this.manipulator = manipulator; previousState = null; - currentState = V3_EpsilonSuperstructureStates.START; + currentState = V3_EpsilonSuperstructureStates.STOW_DOWN; nextState = null; - targetState = V3_EpsilonSuperstructureStates.START; + targetState = V3_EpsilonSuperstructureStates.STOW_DOWN; // Initialize the graph graph = new DefaultDirectedGraph<>(EdgeCommand.class); From 9d72743fc882f8a841c75cf795abc3e21588a962 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Sun, 19 Oct 2025 16:24:44 -0400 Subject: [PATCH 131/180] start manipulator --- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 11 ++--- .../manipulator/V3_EpsilonManipulator.java | 9 ++-- .../V3_EpsilonManipulatorConstants.java | 39 ++++++++++++++-- .../V3_EpsilonManipulatorIOTalonFX.java | 45 +++++++++++++------ 4 files changed, 79 insertions(+), 25 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 355ee146..562ef9b4 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -38,6 +38,7 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIO; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOSim; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOTalonFX; import frc.robot.util.LTNUpdater; import frc.robot.util.LoggedChoreo.ChoreoChooser; import frc.robot.util.LoggedTunableNumber; @@ -74,9 +75,9 @@ public V3_EpsilonRobotContainer() { new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); // intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); - // manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); // climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); - // superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + // superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); vision = new Vision(() -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded)); break; @@ -124,7 +125,7 @@ public V3_EpsilonRobotContainer() { climber = new V3_EpsilonClimber(new V3_EpsilonClimberIO() {}); } if (leds == null) { - leds = new V3_EpsilonLEDs(); + // leds = new V3_EpsilonLEDs(); } if (superstructure == null) { superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); @@ -166,7 +167,7 @@ private void configureButtonBindings() { driver.b().onTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)); - driver.x().onTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); + driver.x().onTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF)); } private void configureAutos() { @@ -211,7 +212,7 @@ public void robotPeriodic() { */ @Override public Command getAutonomousCommand() { - return elevator.sysIdRoutine(superstructure); + return manipulator.sysIdRoutine(superstructure, elevator); // return superstructure.allTransition(); // return Commands.sequence( // V3_EpsilonCompositeCommands.dropAlgae( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 68bccf79..71fe64e3 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -10,6 +10,8 @@ import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; +import frc.robot.FieldConstants.Reef.ReefState; +import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; @@ -274,18 +276,19 @@ public void setSlot() { * @param superstructure The V3 Epsiolon Superstructure. * @return A command to run the SysId routine for the manipulator arm. */ - public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { + public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure, ElevatorFSM elevator) { SysIdRoutine algaeCharacterizationRoutine = new SysIdRoutine( new SysIdRoutine.Config( Volts.of(0.5).per(Second), - Volts.of(6), - Seconds.of(4), + Volts.of(8), + Seconds.of(10), (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), new SysIdRoutine.Mechanism( (volts) -> io.setArmVoltage(volts.in(Volts)), null, superstructure)); return Commands.sequence( superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.L4)), Commands.runOnce(() -> isClosedLoop = false), algaeCharacterizationRoutine.quasistatic(Direction.kForward), Commands.waitSeconds(.25), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index a1e517f9..da8e9776 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -31,9 +31,9 @@ public class V3_EpsilonManipulatorConstants { public static final int CAN_RANGE_ID; static { - ARM_CAN_ID = 42; - CAN_RANGE_ID = 41; - ROLLER_CAN_ID = 30; + ARM_CAN_ID = 30; + CAN_RANGE_ID = 32; + ROLLER_CAN_ID = 31; ARM_PARAMETERS = new ArmParameters(DCMotor.getKrakenX60Foc(1), 1, 90.0, .695); @@ -54,6 +54,39 @@ public class V3_EpsilonManipulatorConstants { new LoggedTunableNumber("Manipulator/L1 Volts", 3.5 * 1.56)); switch (Constants.ROBOT) { + case V3_EPSILON: + EMPTY_GAINS = + new Gains( + new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 60), + new LoggedTunableNumber("Manipulator/Arm/Empty/kD", 0), + new LoggedTunableNumber("Manipulator/Arm/Empty/kS", 0.16975), + new LoggedTunableNumber("Manipulator/Arm/Empty/kG", 0.062944), + new LoggedTunableNumber("Manipulator/Arm/Empty/kV", 0), + new LoggedTunableNumber("Manipulator/Arm/Empty/kA", 0)); + CORAL_GAINS = + new Gains( + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kP", 0), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kD", 0), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kS", 0), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kG", 0), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kV", 0.0), + new LoggedTunableNumber("Manipulator/ArmWithoutAlgae/kA", 0.0)); + ALGAE_GAINS = + new Gains( + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kP", 0), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kD", 0), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kS", 0), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kG", 0), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kV", 0.0), + new LoggedTunableNumber("Manipulator/ArmWithAlgae/kA", 0.0)); + CONSTRAINTS = + new Constraints( + new LoggedTunableNumber("Manipulator/Arm/MaxAcceleration", 5), + new LoggedTunableNumber("Manipulator/Arm/CruisingVelocity", 3), + new LoggedTunableNumber( + "Manipulator/Arm/GoalTolerance", Units.degreesToRadians(1))); + CURRENT_LIMITS = new ManipulatorCurrentLimits(40, 40, 40, 40); + break; case V3_EPSILON_SIM: EMPTY_GAINS = new Gains( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java index b17375a9..f890bfb2 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java @@ -5,6 +5,7 @@ import static edu.wpi.first.units.Units.RotationsPerSecondPerSecond; import static frc.robot.util.PhoenixUtil.*; +import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.StatusSignal; import com.ctre.phoenix6.configs.MotionMagicConfigs; import com.ctre.phoenix6.configs.Slot0Configs; @@ -25,6 +26,8 @@ import edu.wpi.first.units.measure.Current; import edu.wpi.first.units.measure.Temperature; import edu.wpi.first.units.measure.Voltage; +import frc.robot.util.PhoenixUtil; +import java.util.ArrayList; public class V3_EpsilonManipulatorIOTalonFX implements V3_EpsilonManipulatorIO { @@ -51,6 +54,8 @@ public class V3_EpsilonManipulatorIOTalonFX implements V3_EpsilonManipulatorIO { private final StatusSignal rollerTorqueCurrentAmps; private final StatusSignal rollerTemperatureCelsius; + private StatusSignal[] statusSignals; + private final VoltageOut rollerVoltageRequest; private final TalonFXConfiguration rollerConfig; @@ -120,23 +125,35 @@ public V3_EpsilonManipulatorIOTalonFX() { armVoltageRequest = new VoltageOut(0); armMotionMagicRequest = new MotionMagicVoltage(0); - registerSignals( - false, - armPositionRotations, - armVelocityRotationsPerSecond, - armAppliedVoltage, - armSupplyCurrentAmps, - armTorqueCurrentAmps, - armTemperatureCelsius, - rollerPositionRotations, - rollerVelocityRotationsPerSecond, - rollerAppliedVoltage, - rollerSupplyCurrentAmps, - rollerTorqueCurrentAmps, - rollerTemperatureCelsius); + var signalsList = new ArrayList>(); + + signalsList.add(armPositionRotations); + signalsList.add(armVelocityRotationsPerSecond); + signalsList.add(armAppliedVoltage); + signalsList.add(armSupplyCurrentAmps); + signalsList.add(armTorqueCurrentAmps); + signalsList.add(armTemperatureCelsius); + signalsList.add(armPositionSetpointRotations); + signalsList.add(armPositionErrorRotations); + signalsList.add(rollerPositionRotations); + signalsList.add(rollerVelocityRotationsPerSecond); + signalsList.add(rollerAppliedVoltage); + signalsList.add(rollerSupplyCurrentAmps); + signalsList.add(rollerTorqueCurrentAmps); + signalsList.add(rollerTemperatureCelsius); + + statusSignals = new StatusSignal[signalsList.size()]; + + for (int i = 0; i < signalsList.size(); i++) { + statusSignals[i] = signalsList.get(i); + } + + BaseStatusSignal.setUpdateFrequencyForAll(50, statusSignals); armTalonFX.optimizeBusUtilization(); rollerTalonFX.optimizeBusUtilization(); + + PhoenixUtil.registerSignals(false, statusSignals); } /** From a3c745c2d6167250e6c379695a2a6861d83254eb Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Sun, 19 Oct 2025 21:31:17 -0400 Subject: [PATCH 132/180] Refactor intake and climber IOs; update elevator constants and superstructure states --- .../frc/robot/commands/CompositeCommands.java | 46 +++------ .../drive/TunerConstantsV3_Epsilon.java | 1 - .../shared/elevator/ElevatorConstants.java | 4 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 42 +++++---- .../climber/V3_EpsilonClimberIOSim.java | 1 - .../V3_EpsilonSuperstructure.java | 13 +++ .../V3_EpsilonSuperstructureStates.java | 4 +- .../intake/V3_EpsilonIntake.java | 29 +++--- .../intake/V3_EpsilonIntakeConstants.java | 52 ++++++---- .../intake/V3_EpsilonIntakeIO.java | 5 +- .../intake/V3_EpsilonIntakeIOTalonFX.java | 94 ++++++++++++------- .../manipulator/V3_EpsilonManipulator.java | 4 +- .../V3_EpsilonManipulatorConstants.java | 18 ++-- 13 files changed, 177 insertions(+), 136 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 07530afa..1cd96096 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -1,13 +1,9 @@ package frc.robot.commands; import edu.wpi.first.math.MathUtil; -import edu.wpi.first.math.Matrix; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.kinematics.ChassisSpeeds; -import edu.wpi.first.math.numbers.N1; -import edu.wpi.first.math.numbers.N6; -import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.FieldConstants; @@ -30,15 +26,12 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; -import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimber; -import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberConstants; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; import frc.robot.util.AllianceFlipUtil; -import frc.robot.util.TrajectoryGenerator; import java.util.function.BooleanSupplier; import java.util.function.Supplier; @@ -674,10 +667,20 @@ public static final Command intakeCoralDriverSequence( return Commands.sequence( Commands.runOnce(() -> RobotState.setHasAlgae(false)), superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoral()), + V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoralLoose()), Commands.waitSeconds(0.2), superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.HANDOFF, () -> manipulator.hasCoral())); + V3_EpsilonSuperstructureStates.L1, () -> intake.hasCoralLocked())); + } + + public static final Command postIntakeCoralSequence( + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + return Commands.sequence( + superstructure.runGoalUntil( + V3_EpsilonSuperstructureStates.HANDOFF, () -> manipulator.hasCoral()), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)); } /** @@ -717,7 +720,7 @@ public static final Command optimalAutoScoreCoralSequence( RobotState.setScoreSide(ScoreSide.CENTER); } else { RobotState.setScoreSide( - optimalSide(RobotState.getReefAlignData().coralSetpoint())); + optimalSideReef(RobotState.getReefAlignData().coralSetpoint())); } }) .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), @@ -902,14 +905,6 @@ public static final Command intakeAlgaeFromReef( .withTimeout(0.5))); } - public static final Command intakeCoralFromGround( - V3_EpsilonSuperstructure superstructure, V3_EpsilonIntake intake) { - return Commands.sequence( - superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoral()), - superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF)); - } - public static final Command emergencyEject( V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { return Commands.sequence( @@ -964,21 +959,6 @@ public static final Command processAlgae( superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); } - public static final Command climb( - V3_EpsilonSuperstructure superstructure, - Drive drive, - V3_EpsilonClimber climber, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.CLIMB), - Commands.deadline( - climber.releaseClimber(), - Commands.waitSeconds( - V3_EpsilonClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), - Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); - } - public static final Command manipulatorGroundIntake( V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { return Commands.sequence( diff --git a/src/main/java/frc/robot/subsystems/shared/drive/TunerConstantsV3_Epsilon.java b/src/main/java/frc/robot/subsystems/shared/drive/TunerConstantsV3_Epsilon.java index 5ffbd375..e83723de 100644 --- a/src/main/java/frc/robot/subsystems/shared/drive/TunerConstantsV3_Epsilon.java +++ b/src/main/java/frc/robot/subsystems/shared/drive/TunerConstantsV3_Epsilon.java @@ -4,7 +4,6 @@ import com.ctre.phoenix6.CANBus; import com.ctre.phoenix6.configs.*; -import com.ctre.phoenix6.hardware.*; import com.ctre.phoenix6.signals.*; import com.ctre.phoenix6.swerve.*; import com.ctre.phoenix6.swerve.SwerveModuleConstants.*; diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index 972b8eb7..331b40e7 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -342,10 +342,10 @@ public static enum ElevatorPositions { new PositionConstants( 1.3864590139769697 + Units.inchesToMeters(0.5), 1.3864590139769697 + Units.inchesToMeters(0.5), - Units.inchesToMeters(56))), + Units.inchesToMeters(50))), HIGH_STOW(new PositionConstants(0, 0, 0.5)), - HANDOFF(new PositionConstants(0, 0, Units.inchesToMeters(34.75))), + HANDOFF(new PositionConstants(0, 0, Units.inchesToMeters(33.25))), ; private final PositionConstants position; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 09c43c33..50719633 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -4,15 +4,16 @@ import edu.wpi.first.apriltag.AprilTagFields; import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj.util.Color; import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import frc.robot.Constants; import frc.robot.Constants.Mode; import frc.robot.RobotContainer; import frc.robot.RobotState; -import frc.robot.commands.AutonomousCommands; import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; +import frc.robot.commands.DriveCommands; import frc.robot.subsystems.shared.drive.Drive; import frc.robot.subsystems.shared.drive.DriveConstants; import frc.robot.subsystems.shared.drive.GyroIO; @@ -35,8 +36,8 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIO; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOSim; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOTalonFX; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIO; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOSim; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOTalonFX; @@ -75,10 +76,11 @@ public V3_EpsilonRobotContainer() { new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); - // intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); // climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); - // superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + leds = new V3_EpsilonLEDs(); vision = new Vision(() -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded)); break; @@ -95,7 +97,7 @@ public V3_EpsilonRobotContainer() { manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOSim()); superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); - // leds = new V3_EpsilonLEDs(); + leds = new V3_EpsilonLEDs(); vision = new Vision(() -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded)); break; @@ -143,23 +145,27 @@ public V3_EpsilonRobotContainer() { * responsible for setting up the default commands for each button on the controllers. */ private void configureButtonBindings() { + drive.setDefaultCommand( + DriveCommands.joystickDrive( + drive, + () -> -driver.getLeftY(), + () -> -driver.getLeftX(), + () -> -driver.getRightX(), + () -> false)); + driver .rightTrigger() .whileTrue( V3_EpsilonCompositeCommands.intakeCoralDriverSequence( superstructure, intake, manipulator)) - .whileFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF)); - - driver - .a() - .toggleOnTrue( - superstructure.override(() -> manipulator.setArmGoal(ManipulatorArmState.HANDOFF))) - .toggleOnFalse( - superstructure.override(() -> manipulator.setArmGoal(ManipulatorArmState.VERTICAL_UP))); + .whileFalse( + V3_EpsilonCompositeCommands.postIntakeCoralSequence( + superstructure, intake, manipulator)); - driver.b().onTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)); + driver.x().onTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)); + driver.y().onTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)); - driver.x().onTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF)); + driver.b().onTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); } private void configureAutos() { @@ -204,8 +210,8 @@ public void robotPeriodic() { */ @Override public Command getAutonomousCommand() { - return manipulator.sysIdRoutine(superstructure, elevator); - // return superstructure.allTransition(); + return Commands.sequence( + superstructure.allTransition(), Commands.runOnce(() -> leds.solid(Color.kGreen))); // return Commands.sequence( // V3_EpsilonCompositeCommands.dropAlgae( // drive, diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOSim.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOSim.java index 6dd38f8a..1510df00 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOSim.java @@ -5,7 +5,6 @@ import edu.wpi.first.math.system.plant.LinearSystemId; import edu.wpi.first.wpilibj.simulation.DCMotorSim; import frc.robot.Constants; -import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIO.V3_EpsilonClimberIOInputs; public class V3_EpsilonClimberIOSim implements V3_EpsilonClimberIO { private final DCMotorSim sim; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index f6ac09fa..e8b79d65 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -704,6 +704,19 @@ public Command allTransition() { if (source == sink) continue; if (sink == V3_EpsilonSuperstructureStates.FLIP_DOWN) continue; if (sink == V3_EpsilonSuperstructureStates.FLIP_UP) continue; + if (sink == V3_EpsilonSuperstructureStates.STOW_DOWN) continue; + if (sink == V3_EpsilonSuperstructureStates.STOW_UP) continue; + if (sink == V3_EpsilonSuperstructureStates.GROUND_ACQUISITION) continue; + if (sink == V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) continue; + if (sink == V3_EpsilonSuperstructureStates.GROUND_AQUISITION_ALGAE) continue; + if (sink == V3_EpsilonSuperstructureStates.GROUND_INTAKE) continue; + if (sink == V3_EpsilonSuperstructureStates.L1) continue; + if (sink == V3_EpsilonSuperstructureStates.L1_SCORE) continue; + if (sink == V3_EpsilonSuperstructureStates.L2) continue; + if (sink == V3_EpsilonSuperstructureStates.L2_SCORE) continue; + if (sink == V3_EpsilonSuperstructureStates.L3) continue; + if (sink == V3_EpsilonSuperstructureStates.L3_SCORE) continue; + if (source != V3_EpsilonSuperstructureStates.START && sink != V3_EpsilonSuperstructureStates.START && source != V3_EpsilonSuperstructureStates.OVERRIDE diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 023322ee..a1a8e439 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -46,7 +46,7 @@ public enum V3_EpsilonSuperstructureStates { L1( "L1", new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), - SubsystemActions.empty()), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.CORAL_INTAKE)), L1_SCORE( "L1_SCORE", new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), @@ -138,7 +138,7 @@ public enum V3_EpsilonSuperstructureStates { BARGE_SCORE( "BARGE_SCORE", new SubsystemPoses( - ReefState.ALGAE_SCORE, ManipulatorArmState.BARGE_SCORE, IntakePivotState.HANDOFF), + ReefState.ALGAE_SCORE, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), FLIP_DOWN( "FLIP_DOWN", diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index 0228ce08..d1f3c4e0 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -68,11 +68,12 @@ public void periodic() { * @return True if the intake is detecting coral, false otherwise. */ @AutoLogOutput(key = "Intake/Has Coral") - public boolean hasCoral() { - return inputs.leftCANRangeDistanceMeters - > V3_EpsilonIntakeConstants.INTAKE_CAN_CORAL_DETECTED_THRESHOLD_METERS - && inputs.rightCANRangeDistanceMeters - > V3_EpsilonIntakeConstants.INTAKE_CAN_CORAL_DETECTED_THRESHOLD_METERS; + public boolean hasCoralLocked() { + return inputs.leftCANRange && inputs.rightCANRange; + } + + public boolean hasCoralLoose() { + return inputs.leftCANRange || inputs.rightCANRange; } /** @@ -141,12 +142,13 @@ public Command waitUntilPivotAtGoal() { public void setRollerGoal(IntakeRollerState rollerGoal) { this.rollerGoal = rollerGoal; - if (hasCoral() - && Set.of( - V3_EpsilonIntakeConstants.IntakeRollerState.ALGAE_INTAKE, - V3_EpsilonIntakeConstants.IntakeRollerState.CORAL_INTAKE, - V3_EpsilonIntakeConstants.IntakeRollerState.STOP) - .contains(rollerGoal)) { + if (hasCoralLocked() + || hasCoralLoose() + && Set.of( + V3_EpsilonIntakeConstants.IntakeRollerState.ALGAE_INTAKE, + V3_EpsilonIntakeConstants.IntakeRollerState.CORAL_INTAKE, + V3_EpsilonIntakeConstants.IntakeRollerState.STOP) + .contains(rollerGoal)) { io.setInnerRollerVoltage(0); io.setOuterRollerVoltage(0); @@ -168,13 +170,14 @@ public Command sysIdRoutine(Subsystem subsystem) { new SysIdRoutine( new SysIdRoutine.Config( Volts.of(0.1).per(Second), - Volts.of(1), - Seconds.of(6), + Volts.of(3), + Seconds.of(10), (state) -> Logger.recordOutput("Intake/SysID State", state.toString())), new SysIdRoutine.Mechanism( (volts) -> io.setPivotVoltage(volts.in(Volts)), null, subsystem)); return Commands.sequence( + Commands.runOnce(() -> isClosedLoop = false), characterizationRoutine .quasistatic(Direction.kForward) .until(() -> pivotAtGoal(IntakePivotState.INTAKE_CORAL)), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index d48a33eb..1cd57f5a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -26,26 +26,44 @@ public class V3_EpsilonIntakeConstants { public static final IntakeParems ROLLER_PARAMS; static { - PIVOT_CAN_ID = 60; - ROLLER_CAN_ID_OUTER = 61; // TODO: Check numbers here - ROLLER_CAN_ID_INNER = 62; // TODO: Check numbers here - LEFT_SENSOR_CAN_ID = 0; // TODO: Check numbers here - RIGHT_SENSOR_CAN_ID = 1; + PIVOT_CAN_ID = 40; + ROLLER_CAN_ID_OUTER = 41; + ROLLER_CAN_ID_INNER = 42; + LEFT_SENSOR_CAN_ID = 44; + RIGHT_SENSOR_CAN_ID = 43; - INTAKE_CAN_CORAL_DETECTED_THRESHOLD_METERS = 0.05; // TODO: Check this value + INTAKE_CAN_CORAL_DETECTED_THRESHOLD_METERS = 0.05; PIVOT_PARAMS = new IntakeParems( - 3.0, + (60.0 / 12.0) * (52.0 / 28.0) * (64.0 / 18.0) * (20.0 / 9.0), DCMotor.getKrakenX60Foc(1), 0.0042, - Rotation2d.fromDegrees(0.0), - Rotation2d.fromDegrees(124.6)); + Rotation2d.fromDegrees(40.0), + Rotation2d.fromDegrees(124.6 + 48)); ROLLER_PARAMS = new IntakeParems( 1, DCMotor.getKrakenX60Foc(1), 0, new Rotation2d(), Rotation2d.fromDegrees(0)); switch (Constants.ROBOT) { + case V3_EPSILON: + PIVOT_CONSTRAINTS = + new Constraints( + new LoggedTunableNumber("Intake/Max Acceleration", 160), + new LoggedTunableNumber("Intake/Cruising Velocity", 80), + Rotation2d.fromDegrees(1.5)); + PIVOT_GAINS = + new Gains( + new LoggedTunableNumber("Intake/kP", 175.0), + new LoggedTunableNumber("Intake/kD", 5.0), + new LoggedTunableNumber("Intake/kS", 0.38466), + new LoggedTunableNumber("Intake/kV", 0.0), + new LoggedTunableNumber("Intake/kA", 0), + new LoggedTunableNumber("Intake/kG", 0.083386)); + CURRENT_LIMITS = new IntakeCurrentLimits(40.0, 40.0, 40.0, 40.0, 40.0, 40.0); + + break; + case V3_EPSILON_SIM: PIVOT_CONSTRAINTS = new Constraints( @@ -86,12 +104,12 @@ public class V3_EpsilonIntakeConstants { @RequiredArgsConstructor public enum IntakePivotState { - STOW(Rotation2d.fromDegrees(25.0)), - INTAKE_CORAL(Rotation2d.fromDegrees(123.6)), - HANDOFF(Rotation2d.fromDegrees(0)), - L1(Rotation2d.fromDegrees(-82 + 123.6)), - INTAKE_ALGAE(Rotation2d.fromDegrees(25.0)), - ARM_CLEAR(Rotation2d.fromDegrees(35)); + STOW(Rotation2d.fromDegrees(-82 + 123.6 + 48)), + INTAKE_CORAL(Rotation2d.fromDegrees(123.6 + 48)), + HANDOFF(Rotation2d.fromDegrees(48)), + L1(Rotation2d.fromDegrees(-82 + 123.6 + 48)), + INTAKE_ALGAE(Rotation2d.fromDegrees(25.0 + 48)), + ARM_CLEAR(Rotation2d.fromDegrees(35 + 48)); @Getter private final Rotation2d angle; } @@ -133,10 +151,10 @@ public static record IntakeParems( // Will add more states later public static enum IntakeRollerState { STOP(0.0, 0.0), - CORAL_INTAKE(6.0, 6.0), + CORAL_INTAKE(-12.0, -12.0), ALGAE_INTAKE(12.0, 12.0), SCORE_CORAL(6.0, 6.0), - OUTTAKE(10.0, 10.0); + OUTTAKE(12.0, 12.0); @Getter private final double innerVoltage; @Getter private final double outerVoltage; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java index 076e7a40..9d5e7364 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java @@ -31,10 +31,9 @@ public class V3_EpsilonIntakeIOInputs { public double rollerInnerTorqueCurrentAmps = 0.0; public double rollerInnerTemperatureCelsius = 0.0; - public double - leftCANRangeDistanceMeters; // Left and Right based on the robot's perspective with intake + public boolean leftCANRange; // Left and Right based on the robot's perspective with intake // at the front - public double rightCANRangeDistanceMeters; + public boolean rightCANRange; } /** diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java index e3185f75..46cf0c99 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java @@ -6,6 +6,7 @@ import static edu.wpi.first.units.Units.RotationsPerSecondPerSecond; import static frc.robot.util.PhoenixUtil.*; +import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.StatusSignal; import com.ctre.phoenix6.configs.MotionMagicConfigs; import com.ctre.phoenix6.configs.Slot0Configs; @@ -18,14 +19,15 @@ import com.ctre.phoenix6.signals.InvertedValue; import com.ctre.phoenix6.signals.NeutralModeValue; import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.util.Units; import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.AngularAcceleration; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Current; -import edu.wpi.first.units.measure.Distance; import edu.wpi.first.units.measure.Temperature; import edu.wpi.first.units.measure.Voltage; import frc.robot.util.PhoenixUtil; +import java.util.ArrayList; public class V3_EpsilonIntakeIOTalonFX implements V3_EpsilonIntakeIO { private final TalonFX pivotTalonFX; @@ -71,8 +73,10 @@ public class V3_EpsilonIntakeIOTalonFX implements V3_EpsilonIntakeIO { private final CANrange leftCANrange; private final CANrange rightCANrange; - private final StatusSignal leftCANrangeStatusSignal; - private final StatusSignal rightCANrangeStatusSignal; + private final StatusSignal leftCANrangeStatusSignal; + private final StatusSignal rightCANrangeStatusSignal; + + private StatusSignal[] statusSignals; public V3_EpsilonIntakeIOTalonFX() { pivotTalonFX = new TalonFX(V3_EpsilonIntakeConstants.PIVOT_CAN_ID); @@ -93,10 +97,10 @@ public V3_EpsilonIntakeIOTalonFX() { V3_EpsilonIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO(); pivotConfig.SoftwareLimitSwitch.ForwardSoftLimitEnable = true; pivotConfig.SoftwareLimitSwitch.ForwardSoftLimitThreshold = - V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getRotations(); + V3_EpsilonIntakeConstants.PIVOT_PARAMS.MAX_ANGLE().getRotations(); pivotConfig.SoftwareLimitSwitch.ReverseSoftLimitEnable = true; pivotConfig.SoftwareLimitSwitch.ReverseSoftLimitThreshold = - V3_EpsilonIntakeConstants.PIVOT_PARAMS.MAX_ANGLE().getRotations(); + V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getRotations(); pivotConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; pivotConfig.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive; pivotConfig.Slot0 = @@ -127,7 +131,7 @@ public V3_EpsilonIntakeIOTalonFX() { pivotPositionRotations = pivotTalonFX.getPosition(); pivotVelocityRotationsPerSecond = pivotTalonFX.getVelocity(); - pivotAppliedVoltage = pivotTalonFX.getSupplyVoltage(); + pivotAppliedVoltage = pivotTalonFX.getMotorVoltage(); pivotSupplyCurrentAmps = pivotTalonFX.getSupplyCurrent(); pivotTorqueCurrentAmps = pivotTalonFX.getTorqueCurrent(); pivotTemperatureCelsius = pivotTalonFX.getDeviceTemp(); @@ -135,8 +139,8 @@ public V3_EpsilonIntakeIOTalonFX() { pivotPositionSetpoint = pivotTalonFX.getClosedLoopReference(); pivotPositionError = pivotTalonFX.getClosedLoopError(); - leftCANrangeStatusSignal = leftCANrange.getDistance(); - rightCANrangeStatusSignal = rightCANrange.getDistance(); + leftCANrangeStatusSignal = leftCANrange.getIsDetected(); + rightCANrangeStatusSignal = rightCANrange.getIsDetected(); rollerInnerConfig = new TalonFXConfiguration(); rollerInnerConfig.CurrentLimits.SupplyCurrentLimitEnable = true; @@ -167,14 +171,14 @@ public V3_EpsilonIntakeIOTalonFX() { rollerInnerPositionRotations = rollerTalonFXInner.getPosition(); rollerInnerVelocityRotationsPerSecond = rollerTalonFXInner.getVelocity(); - rollerInnerAppliedVoltage = rollerTalonFXInner.getSupplyVoltage(); + rollerInnerAppliedVoltage = rollerTalonFXInner.getMotorVoltage(); rollerInnerSupplyCurrentAmps = rollerTalonFXInner.getSupplyCurrent(); rollerInnerTorqueCurrentAmps = rollerTalonFXInner.getTorqueCurrent(); rollerInnerTemperatureCelsius = rollerTalonFXInner.getDeviceTemp(); rollerOuterPositionRotations = rollerTalonFXOuter.getPosition(); rollerOuterVelocityRotationsPerSecond = rollerTalonFXOuter.getVelocity(); - rollerOuterAppliedVoltage = rollerTalonFXOuter.getSupplyVoltage(); + rollerOuterAppliedVoltage = rollerTalonFXOuter.getMotorVoltage(); rollerOuterSupplyCurrentAmps = rollerTalonFXOuter.getSupplyCurrent(); rollerOuterTorqueCurrentAmps = rollerTalonFXOuter.getTorqueCurrent(); rollerOuterTemperatureCelsius = rollerTalonFXOuter.getDeviceTemp(); @@ -186,28 +190,46 @@ public V3_EpsilonIntakeIOTalonFX() { rollerInnerVoltageRequest = new VoltageOut(0); rollerOuterVoltageRequest = new VoltageOut(0); - PhoenixUtil.registerSignals( - false, - pivotPositionRotations, - pivotVelocityRotationsPerSecond, - pivotAppliedVoltage, - pivotSupplyCurrentAmps, - pivotTorqueCurrentAmps, - pivotTemperatureCelsius, - rollerInnerPositionRotations, - rollerOuterPositionRotations, - rollerInnerVelocityRotationsPerSecond, - rollerOuterVelocityRotationsPerSecond, - rollerInnerAppliedVoltage, - rollerOuterAppliedVoltage, - rollerInnerSupplyCurrentAmps, - rollerOuterSupplyCurrentAmps, - rollerInnerTorqueCurrentAmps, - rollerOuterTorqueCurrentAmps, - rollerInnerTemperatureCelsius, - rollerOuterTemperatureCelsius, - leftCANrangeStatusSignal, - rightCANrangeStatusSignal); + var signalsList = new ArrayList>(); + + signalsList.add(pivotPositionRotations); + signalsList.add(pivotVelocityRotationsPerSecond); + signalsList.add(pivotAppliedVoltage); + signalsList.add(pivotSupplyCurrentAmps); + signalsList.add(pivotTorqueCurrentAmps); + signalsList.add(pivotTemperatureCelsius); + signalsList.add(rollerInnerPositionRotations); + signalsList.add(rollerOuterPositionRotations); + signalsList.add(rollerInnerVelocityRotationsPerSecond); + signalsList.add(rollerOuterVelocityRotationsPerSecond); + signalsList.add(rollerInnerAppliedVoltage); + signalsList.add(rollerOuterAppliedVoltage); + signalsList.add(rollerInnerSupplyCurrentAmps); + signalsList.add(rollerOuterSupplyCurrentAmps); + signalsList.add(rollerInnerTorqueCurrentAmps); + signalsList.add(rollerOuterTorqueCurrentAmps); + signalsList.add(rollerInnerTemperatureCelsius); + signalsList.add(rollerOuterTemperatureCelsius); + signalsList.add(leftCANrangeStatusSignal); + signalsList.add(rightCANrangeStatusSignal); + + statusSignals = new StatusSignal[signalsList.size()]; + + for (int i = 0; i < signalsList.size(); i++) { + statusSignals[i] = signalsList.get(i); + } + + BaseStatusSignal.setUpdateFrequencyForAll(50, statusSignals); + + pivotTalonFX.optimizeBusUtilization(); + rollerTalonFXInner.optimizeBusUtilization(); + rollerTalonFXOuter.optimizeBusUtilization(); + leftCANrange.optimizeBusUtilization(); + rightCANrange.optimizeBusUtilization(); + + PhoenixUtil.registerSignals(false, statusSignals); + + pivotTalonFX.setPosition(Units.degreesToRotations(48)); } /** @@ -249,9 +271,9 @@ public void updateInputs(V3_EpsilonIntakeIOInputs inputs) { inputs.rollerOuterTorqueCurrentAmps = rollerOuterTorqueCurrentAmps.getValueAsDouble(); inputs.rollerOuterTemperatureCelsius = rollerOuterTemperatureCelsius.getValueAsDouble(); - inputs.leftCANRangeDistanceMeters = leftCANrangeStatusSignal.getValueAsDouble(); + inputs.leftCANRange = leftCANrangeStatusSignal.getValue(); // result = condition ? true : false; - inputs.rightCANRangeDistanceMeters = rightCANrangeStatusSignal.getValueAsDouble(); + inputs.rightCANRange = rightCANrangeStatusSignal.getValue(); } /** @@ -301,7 +323,9 @@ public void setOuterRollerVoltage(double volts) { * * @param position The desired position of the intake pivot motor. */ - public void setPivotMotionMagic(Rotation2d position) { + @Override + public void setPivotGoal(Rotation2d position) { + pivotTalonFX.setControl( pivotMotionMagicRequest.withPosition(position.getMeasure()).withEnableFOC(true)); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index ec855159..62b29434 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -317,11 +317,11 @@ public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState V3_EpsilonManipulatorConstants.ManipulatorRollerState.ALGAE_INTAKE, V3_EpsilonManipulatorConstants.ManipulatorRollerState.CORAL_INTAKE, V3_EpsilonManipulatorConstants.ManipulatorRollerState.STOP) - .contains(l4Score)) { + .contains(rollerGoal)) { io.setRollerVoltage(holdVoltage()); } else { - io.setRollerVoltage(l4Score.getVoltage()); + io.setRollerVoltage(rollerGoal.getVoltage()); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 62883b89..c83ae7a5 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -35,7 +35,7 @@ public final class V3_EpsilonManipulatorConstants { CAN_RANGE_ID = 32; ROLLER_CAN_ID = 31; - ARM_PARAMETERS = new ArmParameters(DCMotor.getKrakenX60Foc(1), 1, 90.0, .695); + ARM_PARAMETERS = new ArmParameters(DCMotor.getKrakenX60Foc(1), 1, 55.5, .695); ALGAE_CAN_RANGE_THRESHOLD_METERS = 0.5; CORAL_CAN_RANGE_THRESHOLD_METERS = 0.5; @@ -57,10 +57,10 @@ public final class V3_EpsilonManipulatorConstants { case V3_EPSILON: EMPTY_GAINS = new Gains( - new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 60), + new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 100), new LoggedTunableNumber("Manipulator/Arm/Empty/kD", 0), - new LoggedTunableNumber("Manipulator/Arm/Empty/kS", 0.16975), - new LoggedTunableNumber("Manipulator/Arm/Empty/kG", 0.062944), + new LoggedTunableNumber("Manipulator/Arm/Empty/kS", 0.12926), + new LoggedTunableNumber("Manipulator/Arm/Empty/kG", 0.024193), new LoggedTunableNumber("Manipulator/Arm/Empty/kV", 0), new LoggedTunableNumber("Manipulator/Arm/Empty/kA", 0)); CORAL_GAINS = @@ -81,11 +81,11 @@ public final class V3_EpsilonManipulatorConstants { new LoggedTunableNumber("Manipulator/ArmWithAlgae/kA", 0.0)); CONSTRAINTS = new Constraints( - new LoggedTunableNumber("Manipulator/Arm/MaxAcceleration", 5), - new LoggedTunableNumber("Manipulator/Arm/CruisingVelocity", 3), + new LoggedTunableNumber("Manipulator/Arm/MaxAcceleration", 8), + new LoggedTunableNumber("Manipulator/Arm/CruisingVelocity", 5), new LoggedTunableNumber( "Manipulator/Arm/GoalTolerance", Units.degreesToRadians(1))); - CURRENT_LIMITS = new ManipulatorCurrentLimits(40, 40, 40, 40); + CURRENT_LIMITS = new ManipulatorCurrentLimits(40, 20, 40, 20); break; case V3_EPSILON_SIM: EMPTY_GAINS = @@ -205,7 +205,7 @@ public static enum ManipulatorArmState { SCORE(Rotation2d.fromDegrees(55.0)), // Placeholder value. Make sure to test SCORE_L4(Rotation2d.kPi), PROCESSOR(Rotation2d.fromDegrees(90)), - ALGAE_INTAKE_FLOOR(Rotation2d.fromDegrees(99)), + ALGAE_INTAKE_FLOOR(Rotation2d.fromDegrees(90)), REEF_INTAKE(Rotation2d.fromDegrees(46.279296875)), INTAKE_OUT_LINE(Rotation2d.fromDegrees(61)), FLOOR_INTAKE(Rotation2d.fromDegrees(73.5)), @@ -233,7 +233,7 @@ public Rotation2d getAngle(Side side) { @RequiredArgsConstructor public static enum ManipulatorRollerState { STOP(0.0), - CORAL_INTAKE(6.0), + CORAL_INTAKE(-12.0), ALGAE_INTAKE(12.0), L4_SCORE(4.6 * 1.56), SCORE_CORAL(4.8 * 1.56), From 5b8d06a89e6db62ddd68918ce7f21ae1f3a97262 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Mon, 20 Oct 2025 16:32:33 -0400 Subject: [PATCH 133/180] handoff works! --- src/main/deploy/Superstructure.dot | 3 +++ .../frc/robot/commands/CompositeCommands.java | 5 ++-- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 5 +++- .../V3_EpsilonSuperstructureStates.java | 5 ++++ .../intake/V3_EpsilonIntake.java | 9 +++++-- .../intake/V3_EpsilonIntakeConstants.java | 5 ++-- .../manipulator/V3_EpsilonManipulator.java | 25 +++++-------------- .../V3_EpsilonManipulatorConstants.java | 6 +++-- .../manipulator/V3_EpsilonManipulatorIO.java | 2 +- .../V3_EpsilonManipulatorIOTalonFX.java | 14 +++++++++++ 10 files changed, 49 insertions(+), 30 deletions(-) diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/Superstructure.dot index 497eace6..2d9c8f8c 100644 --- a/src/main/deploy/Superstructure.dot +++ b/src/main/deploy/Superstructure.dot @@ -215,4 +215,7 @@ digraph Superstructure { POST_PROCESSOR -> L3 [type = UNCONSTRAINED] POST_PROCESSOR -> L4 [type = UNCONSTRAINED] POST_PROCESSOR -> BARGE [type = UNCONSTRAINED] + + HANDOFF_SPIN -> HANDOFF + HANDOFF -> HANDOFF_SPIN } \ No newline at end of file diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 1cd96096..ae1f18d2 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -668,9 +668,8 @@ public static final Command intakeCoralDriverSequence( Commands.runOnce(() -> RobotState.setHasAlgae(false)), superstructure.runGoalUntil( V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoralLoose()), - Commands.waitSeconds(0.2), superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.L1, () -> intake.hasCoralLocked())); + V3_EpsilonSuperstructureStates.HANDOFF, () -> intake.hasCoralLocked())); } public static final Command postIntakeCoralSequence( @@ -679,7 +678,7 @@ public static final Command postIntakeCoralSequence( V3_EpsilonManipulator manipulator) { return Commands.sequence( superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.HANDOFF, () -> manipulator.hasCoral()), + V3_EpsilonSuperstructureStates.HANDOFF_SPIN, () -> manipulator.hasCoral()), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 50719633..ebd019ac 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -12,6 +12,7 @@ import frc.robot.Constants.Mode; import frc.robot.RobotContainer; import frc.robot.RobotState; +import frc.robot.commands.CompositeCommands.SharedCommands; import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; import frc.robot.commands.DriveCommands; import frc.robot.subsystems.shared.drive.Drive; @@ -128,7 +129,7 @@ public V3_EpsilonRobotContainer() { climber = new V3_EpsilonClimber(new V3_EpsilonClimberIO() {}); } if (leds == null) { - // leds = new V3_EpsilonLEDs(); + leds = new V3_EpsilonLEDs(); } if (superstructure == null) { superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); @@ -153,6 +154,8 @@ private void configureButtonBindings() { () -> -driver.getRightX(), () -> false)); + driver.povDown().onTrue(SharedCommands.resetHeading(drive)); + driver .rightTrigger() .whileTrue( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index a1a8e439..e70f943b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -80,6 +80,11 @@ public enum V3_EpsilonSuperstructureStates { new SubsystemActions(ManipulatorRollerState.L4_SCORE, IntakeRollerState.STOP)), HANDOFF( + "HANDOFF", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.CENTERING)), + + HANDOFF_SPIN( "HANDOFF", new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.OUTTAKE)), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index d1f3c4e0..77a11449 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -54,8 +54,13 @@ public void periodic() { io.setPivotGoal(pivotGoal.getAngle()); } - io.setInnerRollerVoltage(rollerGoal.getInnerVoltage()); - io.setOuterRollerVoltage(rollerGoal.getOuterVoltage()); + if (hasCoralLocked() && !rollerGoal.equals(IntakeRollerState.OUTTAKE)) { + io.setInnerRollerVoltage(IntakeRollerState.STOP.getInnerVoltage()); + io.setOuterRollerVoltage(IntakeRollerState.STOP.getOuterVoltage()); + } else { + io.setInnerRollerVoltage(rollerGoal.getInnerVoltage()); + io.setOuterRollerVoltage(rollerGoal.getOuterVoltage()); + } } // Double check if this is right diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index 1cd57f5a..d77de11e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -60,7 +60,7 @@ public class V3_EpsilonIntakeConstants { new LoggedTunableNumber("Intake/kV", 0.0), new LoggedTunableNumber("Intake/kA", 0), new LoggedTunableNumber("Intake/kG", 0.083386)); - CURRENT_LIMITS = new IntakeCurrentLimits(40.0, 40.0, 40.0, 40.0, 40.0, 40.0); + CURRENT_LIMITS = new IntakeCurrentLimits(40.0, 40.0, 40.0, 80.0, 40.0, 80.0); break; @@ -151,10 +151,11 @@ public static record IntakeParems( // Will add more states later public static enum IntakeRollerState { STOP(0.0, 0.0), + CENTERING(-12.0, -12.0), CORAL_INTAKE(-12.0, -12.0), ALGAE_INTAKE(12.0, 12.0), SCORE_CORAL(6.0, 6.0), - OUTTAKE(12.0, 12.0); + OUTTAKE(0.0, 12.0); @Getter private final double innerVoltage; @Getter private final double outerVoltage; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 62b29434..341df33a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -4,7 +4,6 @@ import static edu.wpi.first.units.Units.Seconds; import static edu.wpi.first.units.Units.Volts; -import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; @@ -78,6 +77,8 @@ public void periodic() { && Set.of(ManipulatorRollerState.CORAL_INTAKE, ManipulatorRollerState.STOP) .contains(rollerGoal)) { io.setRollerVoltage(holdVoltage()); + } else if (hasCoral()) { + io.setRollerVoltage(holdVoltage()); } else { io.setRollerVoltage(rollerGoal.getVoltage()); } @@ -92,9 +93,7 @@ public void periodic() { */ @AutoLogOutput(key = "Manipulator/Has Coral") public boolean hasCoral() { - return inputs.canRangeDistanceMeters - < V3_EpsilonManipulatorConstants.CORAL_CAN_RANGE_THRESHOLD_METERS - && inputs.canRangeDistanceMeters > 0; + return inputs.canRangeGot; } /** @@ -106,9 +105,7 @@ public boolean hasCoral() { */ @AutoLogOutput(key = "Manipulator/Has Algae") public boolean hasAlgae() { - return inputs.canRangeDistanceMeters - < V3_EpsilonManipulatorConstants.ALGAE_CAN_RANGE_THRESHOLD_METERS - && inputs.canRangeDistanceMeters > 0; + return inputs.canRangeGot; } /** @@ -237,17 +234,7 @@ public Command waitUntilArmAtGoal() { * uses another set of coefficients. */ private double holdVoltage() { - double y; - double x = Math.abs(inputs.rollerTorqueCurrentAmps); - if (x <= 20) { - y = -0.0003 * Math.pow(x, 3) + 0.0124286 * Math.pow(x, 2) - 0.241071 * x + 4.00643; - } else { - y = 0.0005 * Math.pow(x, 2) - 0.1015 * x + 3.7425; - } - return MathUtil.clamp( - 1.25 * y, - 0.10, - V3_EpsilonManipulatorConstants.ROLLER_VOLTAGES.ALGAE_INTAKE_VOLTS().getAsDouble() / 1.5); + return -1; } /** @@ -312,7 +299,7 @@ public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmSta */ public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState rollerGoal) { this.rollerGoal = rollerGoal; - if (hasAlgae() + if ((hasAlgae() || hasCoral()) && Set.of( V3_EpsilonManipulatorConstants.ManipulatorRollerState.ALGAE_INTAKE, V3_EpsilonManipulatorConstants.ManipulatorRollerState.CORAL_INTAKE, diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index c83ae7a5..e8ae9c33 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -35,7 +35,9 @@ public final class V3_EpsilonManipulatorConstants { CAN_RANGE_ID = 32; ROLLER_CAN_ID = 31; - ARM_PARAMETERS = new ArmParameters(DCMotor.getKrakenX60Foc(1), 1, 55.5, .695); + ARM_PARAMETERS = + new ArmParameters( + DCMotor.getKrakenX60Foc(1), 1, (60.0 / 12.0) * (40.0 / 18.0) * (80.0 / 16.0), .695); ALGAE_CAN_RANGE_THRESHOLD_METERS = 0.5; CORAL_CAN_RANGE_THRESHOLD_METERS = 0.5; @@ -234,7 +236,7 @@ public Rotation2d getAngle(Side side) { public static enum ManipulatorRollerState { STOP(0.0), CORAL_INTAKE(-12.0), - ALGAE_INTAKE(12.0), + ALGAE_INTAKE(-12.0), L4_SCORE(4.6 * 1.56), SCORE_CORAL(4.8 * 1.56), SCORE_ALGAE(-6), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java index 61ca50d7..c61a5357 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java @@ -25,7 +25,7 @@ public static class ManipulatorIOInputs { public double rollerTorqueCurrentAmps = 0.0; public double rollerTemperatureCelsius = 0.0; - public double canRangeDistanceMeters = 0.0; + public boolean canRangeGot = false; } /** diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java index f890bfb2..6b00dbcf 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java @@ -14,6 +14,7 @@ import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.MotionMagicVoltage; import com.ctre.phoenix6.controls.VoltageOut; +import com.ctre.phoenix6.hardware.CANrange; import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.GravityTypeValue; import com.ctre.phoenix6.signals.InvertedValue; @@ -59,9 +60,13 @@ public class V3_EpsilonManipulatorIOTalonFX implements V3_EpsilonManipulatorIO { private final VoltageOut rollerVoltageRequest; private final TalonFXConfiguration rollerConfig; + private final CANrange canRange; + private final StatusSignal isDetected; + public V3_EpsilonManipulatorIOTalonFX() { armTalonFX = new TalonFX(V3_EpsilonManipulatorConstants.ARM_CAN_ID); rollerTalonFX = new TalonFX(V3_EpsilonManipulatorConstants.ROLLER_CAN_ID); + canRange = new CANrange(V3_EpsilonManipulatorConstants.CAN_RANGE_ID); armConfig = new TalonFXConfiguration(); @@ -69,6 +74,9 @@ public V3_EpsilonManipulatorIOTalonFX() { armConfig.CurrentLimits.SupplyCurrentLimit = V3_EpsilonManipulatorConstants.CURRENT_LIMITS.MANIPULATOR_SUPPLY_CURRENT_LIMIT(); armConfig.CurrentLimits.SupplyCurrentLimitEnable = true; + armConfig.CurrentLimits.StatorCurrentLimit = + V3_EpsilonManipulatorConstants.CURRENT_LIMITS.MANIPULATOR_STATOR_CURRENT_LIMIT(); + armConfig.CurrentLimits.StatorCurrentLimitEnable = true; armConfig.Feedback.SensorToMechanismRatio = V3_EpsilonManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO(); armConfig.Slot0 = @@ -125,6 +133,8 @@ public V3_EpsilonManipulatorIOTalonFX() { armVoltageRequest = new VoltageOut(0); armMotionMagicRequest = new MotionMagicVoltage(0); + isDetected = canRange.getIsDetected(); + var signalsList = new ArrayList>(); signalsList.add(armPositionRotations); @@ -141,6 +151,7 @@ public V3_EpsilonManipulatorIOTalonFX() { signalsList.add(rollerSupplyCurrentAmps); signalsList.add(rollerTorqueCurrentAmps); signalsList.add(rollerTemperatureCelsius); + signalsList.add(isDetected); statusSignals = new StatusSignal[signalsList.size()]; @@ -152,6 +163,7 @@ public V3_EpsilonManipulatorIOTalonFX() { armTalonFX.optimizeBusUtilization(); rollerTalonFX.optimizeBusUtilization(); + canRange.optimizeBusUtilization(); PhoenixUtil.registerSignals(false, statusSignals); } @@ -185,6 +197,8 @@ public void updateInputs(ManipulatorIOInputs inputs) { Rotation2d.fromRotations(armPositionSetpointRotations.getValueAsDouble()); inputs.armPositionError = Rotation2d.fromRotations(armPositionErrorRotations.getValueAsDouble()); + + inputs.canRangeGot = isDetected.getValue(); } /** From 294711b995da878faa37c8f636b65dd4a7e37ca7 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Mon, 20 Oct 2025 18:45:17 -0400 Subject: [PATCH 134/180] deploy folder based on robot (so we can have different deploy folders for different robots) --- build.gradle | 40 +++- .../v2_redundancy/choreo/A_LEFT_PATH1.traj | 64 ++++++ .../v2_redundancy/choreo/A_LEFT_PATH2.traj | 178 +++++++++++++++++ .../v2_redundancy/choreo/A_LEFT_PATH3.traj | 119 +++++++++++ .../v2_redundancy/choreo/A_LEFT_PATH4.traj | 129 ++++++++++++ .../choreo/A_LEFT_PATH4_ALT_ALT.traj | 136 +++++++++++++ .../choreo/A_LEFT_PATH_ALT3.traj | 130 ++++++++++++ .../choreo/A_LEFT_PATH_ALT4.traj | 125 ++++++++++++ .../v2_redundancy/choreo/A_RIGHT_PATH1.traj | 64 ++++++ .../v2_redundancy/choreo/A_RIGHT_PATH2.traj | 180 +++++++++++++++++ .../v2_redundancy/choreo/A_RIGHT_PATH3.traj | 118 +++++++++++ .../v2_redundancy/choreo/A_RIGHT_PATH4.traj | 129 ++++++++++++ .../v2_redundancy/choreo/B_LEFT_PATH1.traj | 112 +++++++++++ .../v2_redundancy/choreo/B_LEFT_PATH2.traj | 159 +++++++++++++++ .../v2_redundancy/choreo/B_LEFT_PATH3.traj | 96 +++++++++ .../v2_redundancy/choreo/B_RIGHT_PATH1.traj | 108 ++++++++++ .../v2_redundancy/choreo/B_RIGHT_PATH2.traj | 157 +++++++++++++++ .../v2_redundancy/choreo/B_RIGHT_PATH3.traj | 97 +++++++++ .../v2_redundancy/choreo/C_LEFT_PATH1.traj | 67 +++++++ .../v2_redundancy/choreo/C_LEFT_PATH2.traj | 188 ++++++++++++++++++ .../v2_redundancy/choreo/C_LEFT_PATH3.traj | 146 ++++++++++++++ .../v2_redundancy/choreo/C_RIGHT_PATH1.traj | 67 +++++++ .../v2_redundancy/choreo/C_RIGHT_PATH2.traj | 181 +++++++++++++++++ .../v2_redundancy/choreo/C_RIGHT_PATH3.traj | 137 +++++++++++++ .../{ => v2_redundancy}/choreo/Choreo.chor | 0 .../v2_redundancy/choreo/D_CENTER_PATH.traj | 55 +++++ .../{ => v3_epsilon}/Superstructure.dot | 0 src/main/deploy/v3_epsilon/choreo/Choreo.chor | 86 ++++++++ .../choreo/E_RIGHT_PATH_1.traj | 0 .../choreo/E_RIGHT_PATH_1_BACK.traj | 0 .../choreo/E_RIGHT_PATH_2.traj | 0 .../choreo/E_RIGHT_PATH_2_BACK.traj | 0 .../choreo/E_RIGHT_PATH_3.traj | 0 .../choreo/E_RIGHT_PATH_3_BACK.traj | 0 .../choreo/E_RIGHT_PATH_4.traj | 0 .../choreo/E_RIGHT_PATH_4_BACK.traj | 0 src/main/java/frc/robot/Constants.java | 2 +- .../V3_EpsilonSuperstructureEdges.java | 6 +- 38 files changed, 3073 insertions(+), 3 deletions(-) create mode 100644 src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH1.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH2.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH3.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH4.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH4_ALT_ALT.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH_ALT3.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH_ALT4.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/A_RIGHT_PATH1.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/A_RIGHT_PATH2.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/A_RIGHT_PATH3.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/A_RIGHT_PATH4.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/B_LEFT_PATH1.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/B_LEFT_PATH2.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/B_LEFT_PATH3.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/B_RIGHT_PATH1.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/B_RIGHT_PATH2.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/B_RIGHT_PATH3.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/C_LEFT_PATH1.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/C_LEFT_PATH2.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/C_LEFT_PATH3.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/C_RIGHT_PATH1.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/C_RIGHT_PATH2.traj create mode 100644 src/main/deploy/v2_redundancy/choreo/C_RIGHT_PATH3.traj rename src/main/deploy/{ => v2_redundancy}/choreo/Choreo.chor (100%) create mode 100644 src/main/deploy/v2_redundancy/choreo/D_CENTER_PATH.traj rename src/main/deploy/{ => v3_epsilon}/Superstructure.dot (100%) create mode 100644 src/main/deploy/v3_epsilon/choreo/Choreo.chor rename src/main/deploy/{ => v3_epsilon}/choreo/E_RIGHT_PATH_1.traj (100%) rename src/main/deploy/{ => v3_epsilon}/choreo/E_RIGHT_PATH_1_BACK.traj (100%) rename src/main/deploy/{ => v3_epsilon}/choreo/E_RIGHT_PATH_2.traj (100%) rename src/main/deploy/{ => v3_epsilon}/choreo/E_RIGHT_PATH_2_BACK.traj (100%) rename src/main/deploy/{ => v3_epsilon}/choreo/E_RIGHT_PATH_3.traj (100%) rename src/main/deploy/{ => v3_epsilon}/choreo/E_RIGHT_PATH_3_BACK.traj (100%) rename src/main/deploy/{ => v3_epsilon}/choreo/E_RIGHT_PATH_4.traj (100%) rename src/main/deploy/{ => v3_epsilon}/choreo/E_RIGHT_PATH_4_BACK.traj (100%) diff --git a/build.gradle b/build.gradle index 17f28036..c3f50906 100755 --- a/build.gradle +++ b/build.gradle @@ -6,6 +6,10 @@ plugins { id "com.diffplug.spotless" version "6.12.0" } +ext { + deploySrcDir = "src/main/deploy" +} + java { sourceCompatibility = JavaVersion.VERSION_17 targetCompatibility = JavaVersion.VERSION_17 @@ -13,6 +17,40 @@ java { def ROBOT_MAIN_CLASS = "frc.robot.Main" +gradle.projectsEvaluated { + def buildDir = new File("${project.buildDir}/classes/java/main") + if (!buildDir.exists()) { + println "⚠️ Warning: compiled classes not found. Make sure compileJava runs first." + project.ext.deploySrcDir = "src/main/deploy" + return + } + + try { + def loader = new URLClassLoader([buildDir.toURI().toURL()] as URL[], this.class.classLoader) + def constantsClass = loader.loadClass("frc.robot.Constants") + def robotField = constantsClass.getDeclaredField("ROBOT") + robotField.setAccessible(true) + def robotEnumValue = robotField.get(null) // static field + + println "Detected RobotType: ${robotEnumValue}" + + def baseName = robotEnumValue.toString().toLowerCase().replaceAll(/_sim$/, "") + def candidateDir = "src/main/deploy/${baseName}" + + if (file(candidateDir).exists()) { + project.ext.deploySrcDir = candidateDir + } else { + println "Folder '${candidateDir}' does not exist. Using default deploy folder." + } + + println "deploySrcDir set to: ${project.ext.deploySrcDir}" + + } catch (Throwable e) { + println "Could not read RobotType: ${e.message}" + project.ext.deploySrcDir = "src/main/deploy" + } +} + // Define my targets (RoboRIO) and artifacts (deployable files) // This is added by GradleRIO's backing project DeployUtils. deploy { @@ -53,7 +91,7 @@ deploy { // Static files artifact frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { - files = project.fileTree('src/main/deploy') + files = project.fileTree(project.ext.deploySrcDir) directory = '/home/lvuser/deploy' // Change to true to delete files on roboRIO that no // longer exist in deploy directory on roboRIO diff --git a/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH1.traj b/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH1.traj new file mode 100644 index 00000000..9da2a0fb --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH1.traj @@ -0,0 +1,64 @@ +{ + "name":"A_LEFT_PATH1", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.163994312286377, "y":6.070901393890381, "heading":1.5707963267948966, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":5.37649393081665, "y":5.3462324142456055, "heading":1.102853734231975, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"7.163994312286377 m", "val":7.163994312286377}, "y":{"exp":"6.070901393890381 m", "val":6.070901393890381}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"5.37649393081665 m", "val":5.37649393081665}, "y":{"exp":"5.3462324142456055 m", "val":5.3462324142456055}, "heading":{"exp":"1.102853734231975 rad", "val":1.102853734231975}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.09622], + "samples":[ + {"t":0.0, "x":7.16399, "y":6.0709, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.96253, "ay":-2.41713, "alpha":-1.57186, "fx":[-103.44741,-105.08005,-100.10386,-97.0527], "fy":[-36.59042,-31.65986,-44.9953,-51.21333]}, + {"t":0.0378, "x":7.15973, "y":6.06917, "heading":1.5708, "vx":-0.22539, "vy":-0.09137, "omega":-0.05942, "ax":-5.96204, "ay":-2.41693, "alpha":-1.57115, "fx":[-103.43694,-105.07031,-100.09683,-97.04657], "fy":[-36.5893,-31.66144,-44.99032,-51.20434]}, + {"t":0.0756, "x":7.14696, "y":6.06399, "heading":1.56855, "vx":-0.45076, "vy":-0.18273, "omega":-0.11881, "ax":-5.96147, "ay":-2.4167, "alpha":-1.57023, "fx":[-103.4161,-105.06226,-100.09767,-97.03581], "fy":[-36.61233,-31.65217,-44.96442,-51.20078]}, + {"t":0.1134, "x":7.12566, "y":6.05536, "heading":1.56406, "vx":-0.6761, "vy":-0.27408, "omega":-0.17816, "ax":-5.9608, "ay":-2.41643, "alpha":-1.56905, "fx":[-103.38438,-105.05542,-100.10604,-97.02023], "fy":[-36.65947,-31.63227,-44.91736,-51.20207]}, + {"t":0.1512, "x":7.09584, "y":6.04327, "heading":1.55732, "vx":-0.90143, "vy":-0.36543, "omega":-0.23747, "ax":-5.95999, "ay":-2.4161, "alpha":-1.56757, "fx":[-103.34104,-105.04905,-100.12147,-96.99962], "fy":[-36.7307,-31.60212,-44.84883,-51.20732]}, + {"t":0.189, "x":7.05751, "y":6.02773, "heading":1.54835, "vx":-1.12672, "vy":-0.45676, "omega":-0.29673, "ax":-5.95901, "ay":-2.41571, "alpha":-1.56575, "fx":[-103.28503,-105.04212,-100.14328,-96.97368], "fy":[-36.82601,-31.56226,-44.75834,-51.21526]}, + {"t":0.2268, "x":7.01066, "y":6.00874, "heading":1.53713, "vx":-1.35197, "vy":-0.54807, "omega":-0.35592, "ax":-5.95778, "ay":-2.41521, "alpha":-1.56349, "fx":[-103.21477,-105.0331,-100.17045,-96.94189], "fy":[-36.94531,-31.51341,-44.6452,-51.22407]}, + {"t":0.2646, "x":6.9553, "y":5.9863, "heading":1.52368, "vx":-1.57718, "vy":-0.63937, "omega":-0.41502, "ax":-5.95619, "ay":-2.41457, "alpha":-1.5607, "fx":[-103.12789,-105.01966,-100.20134,-96.90331], "fy":[-37.08834,-31.4565,-44.50839,-51.23118]}, + {"t":0.3024, "x":6.89143, "y":5.96041, "heading":1.50799, "vx":-1.80233, "vy":-0.73064, "omega":-0.47401, "ax":-5.95407, "ay":-2.41371, "alpha":-1.55717, "fx":[-103.02053,-104.99803,-100.23324,-96.8561], "fy":[-37.25443,-31.39265,-44.34634,-51.23279]}, + {"t":0.34021, "x":6.81904, "y":5.93106, "heading":1.49007, "vx":-2.02739, "vy":-0.82188, "omega":-0.53287, "ax":-5.95109, "ay":-2.41251, "alpha":-1.55262, "fx":[-102.88598,-104.96167,-100.26119,-96.79652], "fy":[-37.44204,-31.32324,-44.15639,-51.22287]}, + {"t":0.37801, "x":6.73815, "y":5.89827, "heading":1.46993, "vx":-2.25235, "vy":-0.91307, "omega":-0.59156, "ax":-5.94661, "ay":-2.41071, "alpha":-1.54653, "fx":[-102.71116,-104.89787,-100.2753,-96.71635], "fy":[-37.64759,-31.24966,-43.93353,-51.19087]}, + {"t":0.41581, "x":6.64877, "y":5.86203, "heading":1.44757, "vx":-2.47713, "vy":-1.0042, "omega":-0.65002, "ax":-5.93912, "ay":-2.40768, "alpha":-1.53785, "fx":[-102.46609,-104.77785,-100.25236,-96.59485], "fy":[-37.86182,-31.17249,-43.66655,-51.11506]}, + {"t":0.45361, "x":6.55089, "y":5.82235, "heading":1.423, "vx":-2.70164, "vy":-1.09521, "omega":-0.70815, "ax":-5.92409, "ay":-2.4016, "alpha":-1.5242, "fx":[-102.06226,-104.51766,-100.12263,-96.36573], "fy":[-38.05524,-31.08586,-43.323,-50.93829]}, + {"t":0.49141, "x":6.44453, "y":5.77924, "heading":1.39623, "vx":-2.92557, "vy":-1.18599, "omega":-0.76577, "ax":-5.87887, "ay":-2.3833, "alpha":-1.49854, "fx":[-101.06441,-103.71112,-99.53707,-95.67875], "fy":[-38.07347,-30.9216,-42.74664,-50.41538]}, + {"t":0.52921, "x":6.32974, "y":5.73271, "heading":1.36728, "vx":-3.14779, "vy":-1.27608, "omega":-0.82242, "ax":-0.00047, "ay":-0.00284, "alpha":0.09473, "fx":[-0.29854,0.18311,0.28251,-0.19914], "fy":[-0.23942,-0.33881,0.14284,0.24223]}, + {"t":0.56701, "x":6.21075, "y":5.68447, "heading":1.33619, "vx":-3.14781, "vy":-1.27619, "omega":-0.81884, "ax":5.87886, "ay":2.38319, "alpha":1.50018, "fx":[100.8135,103.76144,99.76764,95.64862], "fy":[38.72431,30.72024,42.21021,50.49452]}, + {"t":0.60481, "x":6.09596, "y":5.63793, "heading":1.30524, "vx":-2.92559, "vy":-1.18611, "omega":-0.76213, "ax":5.9241, "ay":2.40161, "alpha":1.52277, "fx":[101.55613,104.61666,100.58388,96.31239], "fy":[39.37834,30.71842,42.24502,51.06115]}, + {"t":0.64261, "x":5.98961, "y":5.59481, "heading":1.27643, "vx":-2.70165, "vy":-1.09532, "omega":-0.70457, "ax":5.93914, "ay":2.40776, "alpha":1.53447, "fx":[101.7219,104.92371,100.92859,96.51842], "fy":[39.81075,30.64585,42.08369,51.28079]}, + {"t":0.68041, "x":5.89173, "y":5.55513, "heading":1.2498, "vx":-2.47715, "vy":-1.00431, "omega":-0.64656, "ax":5.94664, "ay":2.41083, "alpha":1.54162, "fx":[101.74752,105.08668,101.14926,96.61925], "fy":[40.17232,30.57746,41.88576,51.39479]}, + {"t":0.71821, "x":5.80234, "y":5.51888, "heading":1.22536, "vx":-2.25236, "vy":-0.91318, "omega":-0.58829, "ax":5.95113, "ay":2.41268, "alpha":1.54648, "fx":[101.72215,105.1891,101.31507,96.6815], "fy":[40.4909,30.52048,41.68496,51.45978]}, + {"t":0.75601, "x":5.72145, "y":5.48609, "heading":1.20312, "vx":-2.02741, "vy":-0.82198, "omega":-0.52983, "ax":5.95411, "ay":2.41392, "alpha":1.55002, "fx":[101.67607,105.25969,101.44898,96.72593], "fy":[40.77501,30.47464,41.49308,51.49747]}, + {"t":0.79381, "x":5.64906, "y":5.45674, "heading":1.18309, "vx":-1.80234, "vy":-0.73073, "omega":-0.47124, "ax":5.95623, "ay":2.4148, "alpha":1.55275, "fx":[101.62251,105.31113,101.56082,96.7607], "fy":[41.02805,30.43842,41.3154,51.51855]}, + {"t":0.83161, "x":5.58519, "y":5.43085, "heading":1.16528, "vx":-1.57719, "vy":-0.63945, "omega":-0.41254, "ax":5.95782, "ay":2.41547, "alpha":1.55492, "fx":[101.56824,105.35003,101.65554,96.78947], "fy":[41.2516,30.41023,41.15466,51.52921]}, + {"t":0.86941, "x":5.52983, "y":5.4084, "heading":1.14969, "vx":-1.35198, "vy":-0.54814, "omega":-0.35377, "ax":5.95905, "ay":2.41599, "alpha":1.55671, "fx":[101.51709,105.38025,101.73591,96.81396], "fy":[41.44654,30.38857,41.01243,51.53345]}, + {"t":0.90721, "x":5.48298, "y":5.38941, "heading":1.13631, "vx":-1.12672, "vy":-0.45682, "omega":-0.29492, "ax":5.96004, "ay":2.4164, "alpha":1.55821, "fx":[101.47143,105.40419,101.80361,96.83499], "fy":[41.61338,30.37214,40.88968,51.53402]}, + {"t":0.94501, "x":5.44465, "y":5.37386, "heading":1.12516, "vx":-0.90143, "vy":-0.36547, "omega":-0.23602, "ax":5.96084, "ay":2.41674, "alpha":1.55948, "fx":[101.43278,105.42349,101.85974,96.85297], "fy":[41.75249,30.35982,40.78704,51.53296]}, + {"t":0.98282, "x":5.41483, "y":5.36178, "heading":1.11624, "vx":-0.67611, "vy":-0.27412, "omega":-0.17707, "ax":5.96151, "ay":2.41702, "alpha":1.56057, "fx":[101.40219,105.43927,101.90505,96.86808], "fy":[41.86414,30.35069,40.70491,51.53178]}, + {"t":1.02062, "x":5.39353, "y":5.35314, "heading":1.10955, "vx":-0.45076, "vy":-0.18276, "omega":-0.11808, "ax":5.96208, "ay":2.41726, "alpha":1.56149, "fx":[101.38038,105.45236,101.94006,96.88039], "fy":[41.94853,30.34399,40.6436,51.5316]}, + {"t":1.05842, "x":5.38075, "y":5.34796, "heading":1.10509, "vx":-0.22539, "vy":-0.09138, "omega":-0.05906, "ax":5.96257, "ay":2.41746, "alpha":1.56228, "fx":[101.36786,105.46335,101.96516,96.88994], "fy":[42.00581,30.33915,40.6033,51.53327]}, + {"t":1.09622, "x":5.37649, "y":5.34623, "heading":1.10285, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH2.traj b/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH2.traj new file mode 100644 index 00000000..bad1e596 --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH2.traj @@ -0,0 +1,178 @@ +{ + "name":"A_LEFT_PATH2", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":5.005142688751221, "y":5.233847141265869, "heading":1.0513369818883893, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":4.582683086395264, "y":5.628561973571777, "heading":0.0, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":3.5206298828125, "y":5.799249172210693, "heading":0.0, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":1.924022912979126, "y":6.516302585601807, "heading":2.216612130911823, "intervals":15, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.3110252618789673, "y":7.185760498046875, "heading":2.216612130911823, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":3.2714266777038574, "y":5.901409149169922, "heading":0.0, "intervals":28, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":3.8275418281555176, "y":5.483885765075684, "heading":2.09887087685183, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":4.0}}, "enabled":true}, + {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"5.005142688751221 m", "val":5.005142688751221}, "y":{"exp":"5.233847141265869 m", "val":5.233847141265869}, "heading":{"exp":"1.0513369818883893 rad", "val":1.0513369818883893}, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"4.582683086395264 m", "val":4.582683086395264}, "y":{"exp":"5.628561973571777 m", "val":5.628561973571777}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"3.5206298828125 m", "val":3.5206298828125}, "y":{"exp":"5.799249172210693 m", "val":5.799249172210693}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"1.924022912979126 m", "val":1.924022912979126}, "y":{"exp":"6.516302585601807 m", "val":6.516302585601807}, "heading":{"exp":"2.216612130911823 rad", "val":2.216612130911823}, "intervals":15, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"7.185760498046875 m", "val":7.185760498046875}, "heading":{"exp":"2.216612130911823 rad", "val":2.216612130911823}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"3.2714266777038574 m", "val":3.2714266777038574}, "y":{"exp":"5.901409149169922 m", "val":5.901409149169922}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":28, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"3.8275418281555176 m", "val":3.8275418281555176}, "y":{"exp":"5.483885765075684 m", "val":5.483885765075684}, "heading":{"exp":"2.09887087685183 rad", "val":2.09887087685183}, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"4 m / s", "val":4.0}}}, "enabled":true}, + {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.44714,0.79227,1.25189,1.7841,2.65177,3.16594], + "samples":[ + {"t":0.0, "x":5.00514, "y":5.23385, "heading":1.05134, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-2.79278, "ay":5.56686, "alpha":5.4537, "fx":[-78.25422,-59.74256,-8.58369,-43.43733], "fy":[76.86009,91.8237,109.3264,100.75225]}, + {"t":0.02353, "x":5.00437, "y":5.23539, "heading":1.05134, "vx":-0.06572, "vy":0.13101, "omega":0.12835, "ax":-2.97957, "ay":5.45974, "alpha":5.55849, "fx":[-80.59071,-64.70136,-11.58782,-45.84632], "fy":[74.39401,88.37633,109.0342,99.66973]}, + {"t":0.04707, "x":5.002, "y":5.23998, "heading":1.05436, "vx":-0.13584, "vy":0.2595, "omega":0.25916, "ax":-3.18486, "ay":5.3321, "alpha":5.67263, "fx":[-83.10989,-69.89214,-15.08349,-48.60897], "fy":[71.55438,84.3049,108.58919,98.34136]}, + {"t":0.0706, "x":4.99792, "y":5.24757, "heading":1.06046, "vx":-0.2108, "vy":0.38498, "omega":0.39265, "ax":-3.41043, "ay":5.17919, "alpha":5.795, "fx":[-85.81152,-75.30109,-19.16419,-51.76485], "fy":[68.27464,79.48139,107.92484,96.7054]}, + {"t":0.09413, "x":4.99201, "y":5.25806, "heading":1.0697, "vx":-0.29105, "vy":0.50686, "omega":0.52903, "ax":-3.65776, "ay":4.99514, "alpha":5.92309, "fx":[-88.68635,-80.88279,-23.9442,-55.35657], "fy":[64.47737,73.76066,106.94425,94.68153]}, + {"t":0.11767, "x":4.98415, "y":5.27137, "heading":1.08215, "vx":-0.37714, "vy":0.62442, "omega":0.66842, "ax":-3.92782, "ay":4.77278, "alpha":6.05173, "fx":[-91.71173,-86.54492,-29.56006,-59.42751], "fy":[60.07423,66.99007,105.50505,92.16517]}, + {"t":0.1412, "x":4.97419, "y":5.28739, "heading":1.09788, "vx":-0.46957, "vy":0.73674, "omega":0.81084, "ax":-4.22056, "ay":4.50353, "alpha":6.17126, "fx":[-94.84559,-92.13207,-36.16742,-64.01698], "fy":[54.96751,59.02972,103.39737,89.02047]}, + {"t":0.16474, "x":4.96197, "y":5.30597, "heading":1.11696, "vx":-0.5689, "vy":0.84272, "omega":0.95607, "ax":-4.53434, "ay":4.17742, "alpha":6.26494, "fx":[-98.0191,-97.41468,-43.92656,-69.15122], "fy":[49.05466,49.78661,100.31325,85.07255]}, + {"t":0.18827, "x":4.94732, "y":5.32696, "heading":1.13946, "vx":-0.67561, "vy":0.94103, "omega":1.10351, "ax":-4.86506, "ay":3.78328, "alpha":6.30632, "fx":[-101.12841,-102.09326,-52.96378,-74.82756], "fy":[42.23761,39.26189,95.80992,80.10063]}, + {"t":0.2118, "x":4.93008, "y":5.35016, "heading":1.16543, "vx":-0.7901, "vy":1.03007, "omega":1.25192, "ax":-5.20488, "ay":3.30925, "alpha":6.25843, "fx":[-104.02774,-105.83019,-63.28714,-80.98871], "fy":[34.43877,27.60034,89.28185,73.83637]}, + {"t":0.23534, "x":4.91004, "y":5.37531, "heading":1.19489, "vx":-0.91259, "vy":1.10794, "omega":1.3992, "ax":-5.54038, "ay":2.74412, "alpha":6.07853, "fx":[-106.52731,-108.31391,-74.63474,-87.48502], "fy":[25.62487,15.11927,79.98657,65.97577]}, + {"t":0.25887, "x":4.88703, "y":5.40215, "heading":1.22782, "vx":-1.04297, "vy":1.17252, "omega":1.54225, "ax":-5.85024, "ay":2.08058, "alpha":5.73244, "fx":[-108.40218,-109.34148,-86.2719,-94.02802], "fy":[15.83678,2.28968,67.21494,56.21868]}, + {"t":0.2824, "x":4.86087, "y":5.43032, "heading":1.26411, "vx":-1.18065, "vy":1.22149, "omega":1.67716, "ax":-6.10433, "ay":1.32164, "alpha":5.21641, "fx":[-109.41734,-108.88441,-96.87868,-100.15151], "fy":[5.21794,-10.34077,50.69389,44.35182]}, + {"t":0.30594, "x":4.83139, "y":5.45943, "heading":1.30358, "vx":-1.32431, "vy":1.25259, "omega":1.79992, "ax":-6.26855, "ay":0.48867, "alpha":4.57046, "fx":[-109.37028,-107.10127,-104.81538,-105.21786], "fy":[-5.97184,-22.25903,31.10114,30.37847]}, + {"t":0.32947, "x":4.79849, "y":5.48904, "heading":1.34594, "vx":-1.47183, "vy":1.26409, "omega":1.90748, "ax":-6.31722, "ay":-0.37645, "alpha":3.86259, "fx":[-108.14172,-104.28866,-108.8675,-108.51823], "fy":[-17.37155,-33.08398,10.18632,14.65594]}, + {"t":0.353, "x":4.7621, "y":5.51869, "heading":1.39083, "vx":-1.62049, "vy":1.25523, "omega":1.99838, "ax":-6.24545, "ay":-1.22188, "alpha":3.15251, "fx":[-105.73534,-100.79814,-108.92086,-109.47894], "fy":[-28.56827,-42.6108,-9.90193,-2.05431]}, + {"t":0.37654, "x":4.72224, "y":5.54789, "heading":1.43786, "vx":-1.76747, "vy":1.22648, "omega":2.07257, "ax":-6.07018, "ay":-2.00278, "alpha":2.4727, "fx":[-102.28653,-96.95944,-105.87308,-107.88873], "fy":[-39.16756,-50.79818,-27.58205,-18.71897]}, + {"t":0.40007, "x":4.67896, "y":5.5762, "heading":1.48664, "vx":-1.91032, "vy":1.17934, "omega":2.13076, "ax":-5.82061, "ay":-2.6918, "alpha":1.83703, "fx":[-98.03406,-93.03488,-100.96617,-103.99229], "fy":[-48.85905,-57.72194,-42.2438,-34.32221]}, + {"t":0.4236, "x":4.63239, "y":5.60321, "heading":1.53678, "vx":-2.0473, "vy":1.116, "omega":2.17399, "ax":-5.52752, "ay":-3.27947, "alpha":1.25361, "fx":[-93.26743,-89.20633,-95.23662,-98.37582], "fy":[-57.45355,-63.52271,-54.01205,-48.14332]}, + {"t":0.44714, "x":4.58268, "y":5.62856, "heading":1.58794, "vx":-2.17739, "vy":1.03882, "omega":2.20349, "ax":-5.36296, "ay":-3.53055, "alpha":0.94655, "fx":[-90.5486,-87.3706,-92.16127,-94.80946], "fy":[-61.31709,-65.70383,-58.74218,-54.45181]}, + {"t":0.46214, "x":4.54941, "y":5.64375, "heading":1.62101, "vx":-2.25786, "vy":0.98584, "omega":2.2177, "ax":-5.36262, "ay":-3.53348, "alpha":0.68294, "fx":[-90.62064,-88.48202,-91.955,-93.80918], "fy":[-61.14368,-64.14865,-59.02542,-56.09605]}, + {"t":0.47715, "x":4.51492, "y":5.65815, "heading":1.65428, "vx":-2.33833, "vy":0.93282, "omega":2.22795, "ax":-5.36133, "ay":-3.53597, "alpha":0.38778, "fx":[-90.79089,-89.6716,-91.64556,-92.67071], "fy":[-60.813,-62.41887,-59.46255,-57.88919]}, + {"t":0.49215, "x":4.47923, "y":5.67175, "heading":1.68772, "vx":-2.41878, "vy":0.87976, "omega":2.23376, "ax":-5.35871, "ay":-3.53781, "alpha":0.05557, "fx":[-91.08245,-90.9368,-91.21881,-91.36249], "fy":[-60.28423,-60.49835,-60.06955,-59.85626]}, + {"t":0.50716, "x":4.44233, "y":5.68455, "heading":1.72123, "vx":-2.49919, "vy":0.82667, "omega":2.2346, "ax":-5.35426, "ay":-3.53864, "alpha":-0.32076, "fx":[-91.52446,-92.27333,-90.65768,-89.84193], "fy":[-59.50219,-58.36974,-60.86371,-62.02929]}, + {"t":0.52217, "x":4.40423, "y":5.69656, "heading":1.75477, "vx":-2.57953, "vy":0.77357, "omega":2.22978, "ax":-5.34725, "ay":-3.53795, "alpha":-0.75062, "fx":[-92.15391,-93.67484,-89.9414,-88.0504], "fy":[-58.39034,-56.01437,-61.86368,-64.44956]}, + {"t":0.53717, "x":4.36492, "y":5.70777, "heading":1.78823, "vx":-2.65977, "vy":0.72048, "omega":2.21852, "ax":-5.33666, "ay":-3.53491, "alpha":-1.24696, "fx":[-93.01791,-95.13257,-89.04461,-85.90534], "fy":[-56.83953,-53.41217,-63.08937,-67.1704]}, + {"t":0.55218, "x":4.32441, "y":5.71818, "heading":1.82152, "vx":-2.73985, "vy":0.66744, "omega":2.19981, "ax":-5.32101, "ay":-3.52817, "alpha":-1.82829, "fx":[-94.17605,-96.63495,-87.93647,-83.28792], "fy":[-54.68928,-50.54164,-64.56146,-70.2604]}, + {"t":0.56718, "x":4.28269, "y":5.7278, "heading":1.85452, "vx":-2.8197, "vy":0.6145, "omega":2.17238, "ax":-5.29803, "ay":-3.51537, "alpha":-2.52205, "fx":[-95.70132,-98.16702,-86.58,-80.02341], "fy":[-51.69578,-47.3799,-66.3001,-73.80585]}, + {"t":0.58219, "x":4.23979, "y":5.73662, "heading":1.88712, "vx":-2.8992, "vy":0.56175, "omega":2.13453, "ax":-5.26417, "ay":-3.49227, "alpha":-3.37011, "fx":[-97.67437,-99.70958,-84.93278,-75.85104], "fy":[-47.47647,-43.9035,-68.32153,-77.90858]}, + {"t":0.59719, "x":4.19569, "y":5.74466, "heading":1.91915, "vx":-2.97819, "vy":0.50934, "omega":2.08396, "ax":-5.2136, "ay":-3.45103, "alpha":-4.43742, "fx":[-100.15393,-101.23754,-82.95205,-70.38404], "fy":[-41.41683,-40.09119,-70.6296,-82.66652]}, + {"t":0.6122, "x":4.15041, "y":5.75191, "heading":1.95042, "vx":-3.05642, "vy":0.45756, "omega":2.01737, "ax":-5.13671, "ay":-3.377, "alpha":-5.82123, "fx":[-103.07072,-102.71622,-80.61587,-63.0931], "fy":[-32.54338,-35.93424,-73.19179,-88.09809]}, + {"t":0.6272, "x":4.10397, "y":5.7584, "heading":1.98069, "vx":-3.1335, "vy":0.40689, "omega":1.93002, "ax":-5.02004, "ay":-3.24518, "alpha":-7.63047, "fx":[-105.91373,-104.09099,-78.0092,-53.54402], "fy":[-19.57006,-31.47723,-75.85765,-93.89349]}, + {"t":0.64221, "x":4.05639, "y":5.76414, "heading":2.00966, "vx":-3.20883, "vy":0.35819, "omega":1.81552, "ax":-4.87024, "ay":-3.0321, "alpha":-9.73983, "fx":[-107.2513,-105.25361,-75.70044,-43.16052], "fy":[-2.56894,-26.98798,-78.02938,-98.71431]}, + {"t":0.65722, "x":4.00769, "y":5.76917, "heading":2.0369, "vx":-3.28191, "vy":0.31269, "omega":1.66937, "ax":-4.80404, "ay":-2.77599, "alpha":-11.15149, "fx":[-106.26924,-106.05664,-75.3508,-39.18457], "fy":[12.26122,-23.09113,-78.17166,-99.8739]}, + {"t":0.67222, "x":3.9579, "y":5.77355, "heading":2.06195, "vx":-3.354, "vy":0.27104, "omega":1.50204, "ax":-4.85187, "ay":-2.49774, "alpha":-11.71239, "fx":[-104.16834,-106.68953,-76.91794,-42.34021], "fy":[23.39531,-19.09808,-76.34583,-97.89477]}, + {"t":0.68723, "x":3.90703, "y":5.77734, "heading":2.08449, "vx":-3.4268, "vy":0.23356, "omega":1.32629, "ax":-4.93137, "ay":-2.15075, "alpha":-12.06277, "fx":[-100.65191,-107.29863,-79.4015,-48.17254], "fy":[34.95488,-13.84211,-73.362,-94.08518]}, + {"t":0.70223, "x":3.85505, "y":5.7806, "heading":2.10439, "vx":-3.5008, "vy":0.20128, "omega":1.14528, "ax":-5.00684, "ay":-1.6899, "alpha":-12.37017, "fx":[-94.59416,-107.74239,-82.60328,-55.72004], "fy":[48.54293,-6.52119,-69.16031,-87.84009]}, + {"t":0.71724, "x":3.80195, "y":5.78343, "heading":2.12157, "vx":-3.57593, "vy":0.17593, "omega":0.95966, "ax":-5.04595, "ay":-1.0446, "alpha":-12.59207, "fx":[-84.17092,-107.56515,-86.45634,-65.12841], "fy":[64.63674,3.81511,-63.38183,-76.14346]}, + {"t":0.73224, "x":3.74773, "y":5.78595, "heading":2.13598, "vx":-3.65165, "vy":0.16025, "omega":0.77071, "ax":-5.00386, "ay":0.17846, "alpha":-12.16723, "fx":[-67.40758,-105.7112,-90.87026,-76.4678], "fy":[81.88038,18.23806,-55.31922,-32.65721]}, + {"t":0.74725, "x":3.69237, "y":5.78838, "heading":2.14754, "vx":-3.72673, "vy":0.16293, "omega":0.58813, "ax":-4.44844, "ay":2.68505, "alpha":-11.48289, "fx":[-56.11801,-100.11359,-101.26348,-45.17163], "fy":[89.96162,37.12139,-27.66436,83.26908]}, + {"t":0.76225, "x":3.63595, "y":5.79112, "heading":2.15637, "vx":-3.79348, "vy":0.20322, "omega":0.41582, "ax":-3.61404, "ay":4.17631, "alpha":-9.77775, "fx":[-41.41106,-86.88839,-100.3131,-17.28261], "fy":[97.70893,61.26088,24.83415,100.34742]}, + {"t":0.77726, "x":3.57862, "y":5.79464, "heading":2.1626, "vx":-3.84771, "vy":0.26589, "omega":0.2691, "ax":-2.22155, "ay":5.46368, "alpha":-6.4529, "fx":[-23.11979,-64.34218,-66.47301,2.78301], "fy":[103.87203,84.45268,79.02834,104.38928]}, + {"t":0.79227, "x":3.52063, "y":5.79925, "heading":2.16664, "vx":-3.88105, "vy":0.34787, "omega":0.17227, "ax":-1.20433, "ay":5.95493, "alpha":-4.37991, "fx":[-11.85242,-44.75473,-35.36842,10.03436], "fy":[105.90392,96.29951,98.06687,104.89599]}, + {"t":0.80868, "x":3.45676, "y":5.80576, "heading":2.16947, "vx":-3.90082, "vy":0.44562, "omega":0.10038, "ax":-0.41358, "ay":6.09746, "alpha":-2.91966, "fx":[-2.73877,-25.70816,-13.29211,13.59958], "fy":[105.73199,102.11265,103.05165,103.96771]}, + {"t":0.8251, "x":3.39267, "y":5.8139, "heading":2.17112, "vx":-3.90761, "vy":0.54571, "omega":0.05245, "ax":0.3402, "ay":6.10513, "alpha":-1.48093, "fx":[7.05147,-4.31628,4.29614,16.11546], "fy":[104.52862,104.28172,103.59571,102.98016]}, + {"t":0.84151, "x":3.32857, "y":5.82368, "heading":2.17198, "vx":-3.90202, "vy":0.64593, "omega":0.02814, "ax":0.86101, "ay":6.02184, "alpha":-0.54742, "fx":[14.83478,10.89679,14.45347,18.39711], "fy":[102.65975,102.94669,102.25787,101.85465]}, + {"t":0.85793, "x":3.26464, "y":5.83509, "heading":2.17244, "vx":-3.88789, "vy":0.74478, "omega":0.01916, "ax":1.14666, "ay":5.92562, "alpha":-0.16621, "fx":[19.51131,18.3815,19.49853,20.62605], "fy":[100.87302,101.00712,100.718,100.57395]}, + {"t":0.87434, "x":3.20097, "y":5.84812, "heading":2.17276, "vx":-3.86907, "vy":0.84205, "omega":0.01643, "ax":1.32374, "ay":5.83293, "alpha":-0.05081, "fx":[22.50899,22.17846,22.52409,22.85425], "fy":[99.24558,99.29183,99.18773,99.14063]}, + {"t":0.89076, "x":3.13764, "y":5.86273, "heading":2.17303, "vx":-3.84734, "vy":0.9378, "omega":0.01559, "ax":1.464, "ay":5.73907, "alpha":-0.0197, "fx":[24.89652,24.77331,24.90802,25.03115], "fy":[97.63323,97.65195,97.6066,97.58776]}, + {"t":0.90717, "x":3.07468, "y":5.87889, "heading":2.17328, "vx":-3.82331, "vy":1.03201, "omega":0.01527, "ax":1.591, "ay":5.64302, "alpha":-0.01036, "fx":[27.05807,26.99574,27.06671,27.12901], "fy":[95.99426,96.00425,95.97798,95.96795]}, + {"t":0.92359, "x":3.01214, "y":5.89659, "heading":2.17353, "vx":-3.79719, "vy":1.12464, "omega":0.0151, "ax":1.71187, "ay":5.54772, "alpha":-0.00604, "fx":[29.1152,29.08024,29.12162,29.15658], "fy":[94.3706,94.37645,94.35978,94.35393]}, + {"t":0.94, "x":2.95003, "y":5.9158, "heading":2.17378, "vx":-3.76909, "vy":1.2157, "omega":0.015, "ax":1.83008, "ay":5.45821, "alpha":-0.00284, "fx":[31.12734,31.11152,31.13097,31.14679], "fy":[92.84544,92.84819,92.83975,92.837]}, + {"t":0.95642, "x":2.88841, "y":5.93649, "heading":2.17403, "vx":-3.73905, "vy":1.3053, "omega":0.01495, "ax":1.94882, "ay":5.38005, "alpha":0.00009, "fx":[33.14899,33.14949,33.14885,33.14835], "fy":[91.51296,91.51287,91.51317,91.51326]}, + {"t":0.97283, "x":2.8273, "y":5.95864, "heading":2.17427, "vx":-3.70706, "vy":1.39361, "omega":0.01496, "ax":2.07136, "ay":5.31767, "alpha":0.00297, "fx":[35.23576,35.25114,35.23064,35.21525], "fy":[90.44845,90.44546,90.45549,90.45848]}, + {"t":0.98925, "x":2.76672, "y":5.98224, "heading":2.17452, "vx":-3.67306, "vy":1.4809, "omega":0.015, "ax":2.20039, "ay":5.27276, "alpha":0.00596, "fx":[37.43391,37.4636,37.42224,37.39253], "fy":[89.68066,89.67439,89.6956,89.70186]}, + {"t":1.00566, "x":2.70673, "y":6.00726, "heading":2.17476, "vx":-3.63694, "vy":1.56746, "omega":0.0151, "ax":2.33746, "ay":5.2435, "alpha":0.00948, "fx":[39.77007,39.81554,39.74902,39.70351], "fy":[89.17797,89.16735,89.2029,89.21352]}, + {"t":1.02208, "x":2.64734, "y":6.03369, "heading":2.17501, "vx":-3.59857, "vy":1.65353, "omega":0.01526, "ax":2.4831, "ay":5.22487, "alpha":0.01581, "fx":[42.25656,42.32928,42.21704,42.1442], "fy":[88.85196,88.83294,88.89529,88.9143]}, + {"t":1.03849, "x":2.5886, "y":6.06154, "heading":2.17526, "vx":-3.55781, "vy":1.7393, "omega":0.01552, "ax":2.6395, "ay":5.20894, "alpha":0.03693, "fx":[44.94909,45.11093,44.84566,44.68312], "fy":[88.54985,88.50212,88.65547,88.70314]}, + {"t":1.05491, "x":2.53056, "y":6.09079, "heading":2.17552, "vx":-3.51448, "vy":1.8248, "omega":0.01612, "ax":2.82163, "ay":5.18022, "alpha":0.12986, "fx":[48.20162,48.73383,47.79315,47.25154], "fy":[87.91725,87.73847,88.31077,88.48952]}, + {"t":1.07132, "x":2.47325, "y":6.12145, "heading":2.17578, "vx":-3.46816, "vy":1.90984, "omega":0.01826, "ax":3.09263, "ay":5.0911, "alpha":0.51363, "fx":[53.57565,55.40197,51.7146,49.72667], "fy":[85.72087,84.99749,87.46626,88.20772]}, + {"t":1.08774, "x":2.41673, "y":6.15348, "heading":2.17608, "vx":-3.4174, "vy":1.99341, "omega":0.02669, "ax":3.59155, "ay":4.80276, "alpha":1.6836, "fx":[65.25085,69.0902,57.88024,52.14371], "fy":[77.82843,76.03048,85.23078,87.68462]}, + {"t":1.10415, "x":2.36112, "y":6.18685, "heading":2.17652, "vx":-3.35844, "vy":2.07225, "omega":0.05432, "ax":4.28537, "ay":4.16878, "alpha":3.75164, "fx":[84.29439,86.04152,65.78217,55.45368], "fy":[57.36535,58.86123,81.15517,86.25745]}, + {"t":1.12057, "x":2.30657, "y":6.22143, "heading":2.17741, "vx":-3.2881, "vy":2.14068, "omega":0.11591, "ax":4.8644, "ay":3.34972, "alpha":5.81584, "fx":[99.20585,97.11342,73.23858,61.41057], "fy":[27.7302,41.45003,76.05415,82.67662]}, + {"t":1.13698, "x":2.25325, "y":6.25702, "heading":2.17931, "vx":-3.20825, "vy":2.19566, "omega":0.21137, "ax":5.35167, "ay":2.54613, "alpha":6.24775, "fx":[104.39136,102.59341,81.7854,75.35128], "fy":[5.54571,28.54509,67.91148,71.23335]}, + {"t":1.1534, "x":2.20131, "y":6.2934, "heading":2.18278, "vx":-3.1204, "vy":2.23746, "omega":0.31393, "ax":5.98288, "ay":1.52462, "alpha":3.31317, "fx":[106.05177,105.32755,96.95917,98.73002], "fy":[3.42524,18.51879,44.52969,37.25993]}, + {"t":1.16981, "x":2.15089, "y":6.33034, "heading":2.18794, "vx":-3.02219, "vy":2.26248, "omega":0.36832, "ax":6.25649, "ay":0.66624, "alpha":0.84994, "fx":[106.93638,106.80412,105.78911,106.15494], "fy":[5.41207,9.79838,17.06394,13.0561]}, + {"t":1.18623, "x":2.10213, "y":6.36757, "heading":2.19398, "vx":-2.91949, "vy":2.27342, "omega":0.38227, "ax":6.32257, "ay":0.07036, "alpha":-0.82385, "fx":[107.43252,107.4846,107.51474,107.74837], "fy":[6.97806,2.27683,-4.69472,0.22726]}, + {"t":1.20264, "x":2.05505, "y":6.40489, "heading":2.20026, "vx":-2.8157, "vy":2.27458, "omega":0.36875, "ax":6.31232, "ay":-0.34268, "alpha":-1.96614, "fx":[107.74098,107.6452,106.11391,107.98262], "fy":[8.09036,-4.17875,-20.07477,-7.15265]}, + {"t":1.21906, "x":2.00968, "y":6.44219, "heading":2.20631, "vx":-2.71208, "vy":2.26895, "omega":0.33647, "ax":6.27757, "ay":-0.63833, "alpha":-2.76381, "fx":[107.94912,107.47375,103.81646,107.87911], "fy":[8.90169,-9.72216,-30.79778,-11.81291]}, + {"t":1.23547, "x":1.96601, "y":6.47935, "heading":2.21183, "vx":-2.60904, "vy":2.25847, "omega":0.2911, "ax":6.23718, "ay":-0.85822, "alpha":-3.34173, "fx":[108.0984,107.09682,101.47635,107.69901], "fy":[9.51456,-14.49319,-38.43672,-14.97719]}, + {"t":1.25189, "x":1.92402, "y":6.5163, "heading":2.21661, "vx":-2.50665, "vy":2.24439, "omega":0.23625, "ax":6.17118, "ay":-1.60969, "alpha":-2.5856, "fx":[108.96042,104.95663,99.65311,106.30974], "fy":[-8.67121,-30.11529,-44.96083,-25.77389]}, + {"t":1.28737, "x":1.83897, "y":6.59492, "heading":2.22499, "vx":-2.28769, "vy":2.18727, "omega":0.14451, "ax":5.85735, "ay":-2.59068, "alpha":-1.92085, "fx":[104.8469,98.08117,94.12965,101.46976], "fy":[-31.16848,-48.30297,-55.77777,-41.01736]}, + {"t":1.32285, "x":1.76149, "y":6.6709, "heading":2.23012, "vx":-2.07987, "vy":2.09535, "omega":0.07636, "ax":5.53561, "ay":-3.25428, "alpha":-1.40081, "fx":[98.91123,92.02458,89.47725,96.22344], "fy":[-46.86442,-59.21224,-63.08598,-52.25512]}, + {"t":1.35833, "x":1.69118, "y":6.74319, "heading":2.23283, "vx":-1.88346, "vy":1.97989, "omega":0.02665, "ax":5.25086, "ay":-3.71369, "alpha":-1.00404, "fx":[93.0908,87.22297,85.66627,91.28252], "fy":[-57.67538,-66.19789,-68.25202,-60.55024]}, + {"t":1.39381, "x":1.62765, "y":6.81111, "heading":2.23378, "vx":-1.69715, "vy":1.84812, "omega":-0.00897, "ax":5.01014, "ay":-4.04253, "alpha":-0.6999, "fx":[87.98783,83.46284,82.54776,86.88564], "fy":[-65.27307,-70.95992,-72.05217,-66.76392]}, + {"t":1.42929, "x":1.57059, "y":6.87413, "heading":2.23346, "vx":-1.51939, "vy":1.70469, "omega":-0.0338, "ax":4.80894, "ay":-4.2859, "alpha":-0.46264, "fx":[83.67309,80.48482,79.97574,83.06137], "fy":[-70.7763,-74.37864,-74.94253,-71.51038]}, + {"t":1.46477, "x":1.51971, "y":6.93192, "heading":2.23226, "vx":-1.34876, "vy":1.55262, "omega":-0.05022, "ax":4.64048, "ay":-4.47153, "alpha":-0.27378, "fx":[80.0552,78.08586,77.83192,79.75988], "fy":[-74.88727,-76.93724,-77.20277,-75.2105]}, + {"t":1.50026, "x":1.47477, "y":6.98419, "heading":2.23048, "vx":-1.18412, "vy":1.39397, "omega":-0.05993, "ax":4.49843, "ay":-4.61686, "alpha":-0.12052, "fx":[77.0132,76.11978,76.02529,76.90991], "fy":[-78.04602,-78.91725,-79.01165,-78.1512]}, + {"t":1.53574, "x":1.43559, "y":7.03075, "heading":2.22835, "vx":-1.02451, "vy":1.23016, "omega":-0.06421, "ax":4.37761, "ay":-4.73323, "alpha":0.00602, "fx":[74.43706,74.4827,74.4867,74.44103], "fy":[-80.53386,-80.49166,-80.48781,-80.53003]}, + {"t":1.57122, "x":1.402, "y":7.07141, "heading":2.22607, "vx":-0.86919, "vy":1.06222, "omega":-0.06399, "ax":4.2739, "ay":-4.8282, "alpha":0.11209, "fx":[72.23648,73.10024,73.16348,72.29116], "fy":[-82.5356,-81.77174,-81.71263,-82.48519]}, + {"t":1.6067, "x":1.37385, "y":7.10606, "heading":2.2238, "vx":-0.71754, "vy":0.89091, "omega":-0.06002, "ax":4.1841, "ay":-4.907, "alpha":0.20218, "fx":[70.34006,71.91833,72.01513,70.40798], "fy":[-84.17608,-82.83192,-82.74359,-84.11515]}, + {"t":1.64218, "x":1.35102, "y":7.13459, "heading":2.22167, "vx":-0.56909, "vy":0.7168, "omega":-0.05284, "ax":4.1057, "ay":-4.97332, "alpha":0.27958, "fx":[68.69196,70.89701,71.01018,68.74827], "fy":[-85.54188,-83.72363,-83.62233,-85.4914]}, + {"t":1.67766, "x":1.33341, "y":7.15689, "heading":2.2198, "vx":-0.42341, "vy":0.54035, "omega":-0.04292, "ax":4.03674, "ay":-5.02984, "alpha":0.34675, "fx":[67.24849,70.00623,70.12392,67.27661], "fy":[-86.69455,-84.48348,-84.3797,-86.66675]}, + {"t":1.71314, "x":1.32093, "y":7.17289, "heading":2.21827, "vx":-0.28019, "vy":0.36188, "omega":-0.03062, "ax":3.97565, "ay":-5.07852, "alpha":0.40557, "fx":[65.97531,69.22308,69.33665,65.96398], "fy":[-87.67882,-85.13813,-85.039,-87.68087]}, + {"t":1.74862, "x":1.31349, "y":7.18254, "heading":2.21719, "vx":-0.13913, "vy":0.18169, "omega":-0.01623, "ax":3.9212, "ay":-5.12086, "alpha":0.45748, "fx":[64.84527,68.52978,68.63257,64.78652], "fy":[-88.52788,-85.70747,-85.61815,-88.56407]}, + {"t":1.7841, "x":1.31103, "y":7.18576, "heading":2.21661, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.34243, "ay":-3.61297, "alpha":-0.38522, "fx":[92.2991,90.1677,89.46096,91.56494], "fy":[-59.32323,-62.51219,-63.52794,-60.45882]}, + {"t":1.81624, "x":1.31378, "y":7.18389, "heading":2.21661, "vx":0.17168, "vy":-0.11611, "omega":-0.01238, "ax":5.34207, "ay":-3.61273, "alpha":-0.38007, "fx":[92.27367,90.17101,89.47378,91.54974], "fy":[-59.34811,-62.49336,-63.49642,-60.4678]}, + {"t":1.84837, "x":1.32206, "y":7.1783, "heading":2.21621, "vx":0.34335, "vy":-0.2322, "omega":-0.02459, "ax":5.34166, "ay":-3.61245, "alpha":-0.37431, "fx":[92.24547,90.17527,89.48782,91.5322], "fy":[-59.37555,-62.47149,-63.46154,-60.47866]}, + {"t":1.88051, "x":1.33585, "y":7.16897, "heading":2.21542, "vx":0.51501, "vy":-0.34829, "omega":-0.03662, "ax":5.34121, "ay":-3.61215, "alpha":-0.36781, "fx":[92.21391,90.18052,89.50339,91.51199], "fy":[-59.4061,-62.44622,-63.42256,-60.49155]}, + {"t":1.91265, "x":1.35516, "y":7.15591, "heading":2.21425, "vx":0.68666, "vy":-0.46437, "omega":-0.04844, "ax":5.34069, "ay":-3.6118, "alpha":-0.36045, "fx":[92.17825,90.18681,89.52088,91.48871], "fy":[-59.44052,-62.41707,-63.37853,-60.50665]}, + {"t":1.94478, "x":1.37998, "y":7.13913, "heading":2.21269, "vx":0.85828, "vy":-0.58044, "omega":-0.06002, "ax":5.3401, "ay":-3.6114, "alpha":-0.35202, "fx":[92.13753,90.19418,89.54078,91.46186], "fy":[-59.47973,-62.38344,-63.32825,-60.52423]}, + {"t":1.97692, "x":1.41032, "y":7.11861, "heading":2.21076, "vx":1.02989, "vy":-0.69649, "omega":-0.07134, "ax":5.33942, "ay":-3.61094, "alpha":-0.34227, "fx":[92.09048,90.20272,89.56375,91.43074], "fy":[-59.52497,-62.34456,-63.27012,-60.54462]}, + {"t":2.00905, "x":1.44618, "y":7.09436, "heading":2.20847, "vx":1.20148, "vy":-0.81253, "omega":-0.08234, "ax":5.33861, "ay":-3.6104, "alpha":-0.33088, "fx":[92.03543,90.21254,89.59063,91.39444], "fy":[-59.57787,-62.29935,-63.20201,-60.56828]}, + {"t":2.04119, "x":1.48754, "y":7.06639, "heading":2.20582, "vx":1.37304, "vy":-0.92856, "omega":-0.09297, "ax":5.33766, "ay":-3.60976, "alpha":-0.31739, "fx":[91.97008,90.22378,89.6226,91.35169], "fy":[-59.64064,-62.24638,-63.12102,-60.59583]}, + {"t":2.07332, "x":1.53442, "y":7.03468, "heading":2.20284, "vx":1.54457, "vy":-1.04456, "omega":-0.10317, "ax":5.33651, "ay":-3.60899, "alpha":-0.30117, "fx":[91.89121,90.23666,89.66129,91.30071], "fy":[-59.71639,-62.1836,-63.02305,-60.62817]}, + {"t":2.10546, "x":1.58681, "y":6.99925, "heading":2.19952, "vx":1.71606, "vy":-1.16054, "omega":-0.11285, "ax":5.33509, "ay":-3.60803, "alpha":-0.28129, "fx":[91.79417,90.25147,89.70905,91.23889], "fy":[-59.80959,-62.10808,-62.90218,-60.66658]}, + {"t":2.1376, "x":1.64472, "y":6.96009, "heading":2.19589, "vx":1.88751, "vy":-1.27648, "omega":-0.12189, "ax":5.33331, "ay":-3.60683, "alpha":-0.25635, "fx":[91.67192,90.26867,89.76939,91.16227], "fy":[-59.92693,-62.01539,-62.74946,-60.71304]}, + {"t":2.16973, "x":1.70813, "y":6.91721, "heading":2.19198, "vx":2.0589, "vy":-1.39239, "omega":-0.13012, "ax":5.33099, "ay":-3.60528, "alpha":-0.22416, "fx":[91.51337,90.28896,89.84782,91.06455], "fy":[-60.07888,-61.89856,-62.55073,-60.77068]}, + {"t":2.20187, "x":1.77704, "y":6.8706, "heading":2.18779, "vx":2.23021, "vy":-1.50825, "omega":-0.13733, "ax":5.32787, "ay":-3.60317, "alpha":-0.18103, "fx":[91.29992,90.31351,89.95346,90.93503], "fy":[-60.28287,-61.74593,-62.28213,-60.84479]}, + {"t":2.234, "x":1.85146, "y":6.82027, "heading":2.18338, "vx":2.40143, "vy":-1.62404, "omega":-0.14315, "ax":5.32341, "ay":-3.60018, "alpha":-0.12027, "fx":[90.9978,90.34433,90.10263,90.75406], "fy":[-60.57008,-61.53655,-61.9002,-60.94501]}, + {"t":2.26614, "x":1.93138, "y":6.76622, "heading":2.17878, "vx":2.5725, "vy":-1.73973, "omega":-0.14701, "ax":5.31656, "ay":-3.59557, "alpha":-0.02836, "fx":[90.53876,90.38523,90.32772,90.48114], "fy":[-61.00246,-61.22853,-61.31641,-61.09097]}, + {"t":2.29827, "x":2.0168, "y":6.70846, "heading":2.17406, "vx":2.74335, "vy":-1.85528, "omega":-0.14792, "ax":5.3047, "ay":-3.58759, "alpha":0.12675, "fx":[89.7611,90.4442,90.70297,90.01778], "fy":[-61.72279,-60.72455,-60.31882,-61.32939]}, + {"t":2.33041, "x":2.1077, "y":6.64699, "heading":2.1693, "vx":2.91382, "vy":-1.97057, "omega":-0.14385, "ax":5.27932, "ay":-3.57051, "alpha":0.44326, "fx":[88.16901,90.53995,91.4429,89.04726], "fy":[-63.14807,-59.73655,-58.24457,-61.80441]}, + {"t":2.36255, "x":2.20406, "y":6.58182, "heading":2.16468, "vx":3.08348, "vy":-2.08531, "omega":-0.1296, "ax":5.18967, "ay":-3.51033, "alpha":1.43291, "fx":[83.20249,90.7023,93.47546,85.71878], "fy":[-67.18705,-56.8918,-51.49326,-63.267]}, + {"t":2.39468, "x":2.30583, "y":6.51299, "heading":2.16052, "vx":3.25025, "vy":-2.19812, "omega":-0.08356, "ax":1.12774, "ay":-0.76152, "alpha":2.58407, "fx":[17.14469,28.10464,21.53906,9.94189], "fy":[-22.43482,-14.4915,-3.37613,-11.51073]}, + {"t":2.42682, "x":2.41086, "y":6.44196, "heading":2.15783, "vx":3.28649, "vy":-2.22259, "omega":-0.00052, "ax":0.0017, "ay":-0.00075, "alpha":0.00231, "fx":[0.02724,0.03724,0.03058,0.02058], "fy":[-0.02106,-0.01441,-0.0044,-0.01106]}, + {"t":2.45895, "x":2.51648, "y":6.37054, "heading":2.15781, "vx":3.28655, "vy":-2.22262, "omega":-0.00044, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[-0.00001,-0.00001,-0.00001,-0.00001], "fy":[-0.00001,-0.00001,-0.00001,-0.00001]}, + {"t":2.49109, "x":2.62209, "y":6.29911, "heading":2.1578, "vx":3.28655, "vy":-2.22262, "omega":-0.00044, "ax":-0.0017, "ay":0.00075, "alpha":-0.00232, "fx":[-0.02726,-0.03727,-0.03061,-0.0206], "fy":[0.02104,0.01438,0.00437,0.01103]}, + {"t":2.52322, "x":2.72771, "y":6.22769, "heading":2.15779, "vx":3.28649, "vy":-2.22259, "omega":-0.00052, "ax":-1.12791, "ay":0.76163, "alpha":-2.5856, "fx":[-17.12173,-28.10651,-21.56839,-9.94517], "fy":[22.43906,14.51938,3.37727,11.4849]}, + {"t":2.55536, "x":2.83274, "y":6.15665, "heading":2.15777, "vx":3.25024, "vy":-2.19812, "omega":-0.08361, "ax":-5.18956, "ay":3.51026, "alpha":-1.43797, "fx":[-83.1613,-90.67738,-93.50502,-85.74783], "fy":[67.23552,56.93346,51.44214,63.22322]}, + {"t":2.5875, "x":2.93451, "y":6.08783, "heading":2.15508, "vx":3.08347, "vy":-2.08531, "omega":-0.12982, "ax":-5.27931, "ay":3.5705, "alpha":-0.44505, "fx":[-88.15078,-90.52012,-91.45891,-89.06832], "fy":[63.17256,59.76709,58.22019,61.77315]}, + {"t":2.61963, "x":3.03087, "y":6.02266, "heading":2.15091, "vx":2.91382, "vy":-1.97057, "omega":-0.14412, "ax":-5.3047, "ay":3.58759, "alpha":-0.12749, "fx":[-89.75332,-90.43449,-90.7104,-90.02761], "fy":[61.73377,60.73914,60.30785,61.31468]}, + {"t":2.65177, "x":3.12177, "y":5.96119, "heading":2.14628, "vx":2.74335, "vy":-1.85528, "omega":-0.14822, "ax":-5.31656, "ay":3.59557, "alpha":0.02812, "fx":[-90.53935,-90.38905,-90.32707,-90.4773], "fy":[61.00163,61.22285,61.31724,61.09662]}, + {"t":2.6839, "x":3.20718, "y":5.90342, "heading":2.14152, "vx":2.5725, "vy":-1.73973, "omega":-0.14731, "ax":-5.32341, "ay":3.60018, "alpha":0.12034, "fx":[-91.00601,-90.36333,-90.09399,-90.73543], "fy":[60.55803,61.50849,61.91245,60.97285]}, + {"t":2.71604, "x":3.2871, "y":5.84937, "heading":2.13678, "vx":2.40143, "vy":-1.62404, "omega":-0.14344, "ax":-5.32787, "ay":3.60317, "alpha":0.18129, "fx":[-91.3153,-90.34839,-89.93692,-90.90122], "fy":[60.26001,61.69466,62.30555,60.89547]}, + {"t":2.74817, "x":3.36152, "y":5.79904, "heading":2.13217, "vx":2.23021, "vy":-1.50825, "omega":-0.13762, "ax":-5.33099, "ay":3.60528, "alpha":0.22456, "fx":[-91.53555,-90.33982,-89.82359,-91.01564], "fy":[60.04565,61.82403,62.58497,60.84415]}, + {"t":2.78031, "x":3.43044, "y":5.75244, "heading":2.12775, "vx":2.0589, "vy":-1.39239, "omega":-0.1304, "ax":-5.33331, "ay":3.60683, "alpha":0.25684, "fx":[-91.70052,-90.33523,-89.73775,-91.09863], "fy":[59.88381,61.91809,62.79409,60.80876]}, + {"t":2.81245, "x":3.49385, "y":5.70955, "heading":2.12356, "vx":1.88751, "vy":-1.27648, "omega":-0.12215, "ax":-5.33509, "ay":3.60803, "alpha":0.28185, "fx":[-91.8288,-90.33317,-89.67034,-91.16112], "fy":[59.75713,61.98885,62.95669,60.78368]}, + {"t":2.84458, "x":3.55175, "y":5.6704, "heading":2.11963, "vx":1.71606, "vy":-1.16054, "omega":-0.11309, "ax":-5.33651, "ay":3.60898, "alpha":0.30179, "fx":[-91.93146,-90.33277,-89.61592,-91.20955], "fy":[59.65518,62.04355,63.08685,60.76553]}, + {"t":2.87672, "x":3.60414, "y":5.63496, "heading":2.116, "vx":1.54457, "vy":-1.04456, "omega":-0.10339, "ax":-5.33766, "ay":3.60976, "alpha":0.31806, "fx":[-92.01551,-90.33341,-89.57103,-91.24802], "fy":[59.57132,62.08682,63.19345,60.75216]}, + {"t":2.90885, "x":3.65102, "y":5.60326, "heading":2.11268, "vx":1.37304, "vy":-0.92856, "omega":-0.09317, "ax":-5.33861, "ay":3.6104, "alpha":0.33159, "fx":[-92.08559,-90.33468,-89.53335,-91.27921], "fy":[59.50111,62.12175,63.28239,60.74212]}, + {"t":2.94099, "x":3.69239, "y":5.57529, "heading":2.10968, "vx":1.20148, "vy":-0.81253, "omega":-0.08252, "ax":-5.33941, "ay":3.61094, "alpha":0.34301, "fx":[-92.14491,-90.33628,-89.50128,-91.305], "fy":[59.4415,62.15051,63.35771,60.73441]}, + {"t":2.97313, "x":3.72824, "y":5.55104, "heading":2.10703, "vx":1.02989, "vy":-0.69649, "omega":-0.07149, "ax":-5.3401, "ay":3.6114, "alpha":0.35278, "fx":[-92.19575,-90.33798,-89.47369,-91.3267], "fy":[59.39027,62.17465,63.42228,60.72831]}, + {"t":3.00526, "x":3.75858, "y":5.53052, "heading":2.10473, "vx":0.85828, "vy":-0.58044, "omega":-0.06016, "ax":-5.34069, "ay":3.6118, "alpha":0.36123, "fx":[-92.23977,-90.33963,-89.44972,-91.34529], "fy":[59.34583,62.19531,63.4782,60.72327]}, + {"t":3.0374, "x":3.78341, "y":5.51373, "heading":2.1028, "vx":0.68666, "vy":-0.46437, "omega":-0.04855, "ax":-5.34121, "ay":3.61215, "alpha":0.36862, "fx":[-92.27822,-90.34109,-89.42875,-91.3615], "fy":[59.30697,62.21335,63.52704,60.7189]}, + {"t":3.06953, "x":3.80272, "y":5.50068, "heading":2.10124, "vx":0.51501, "vy":-0.34829, "omega":-0.0367, "ax":-5.34166, "ay":3.61245, "alpha":0.37512, "fx":[-92.31205,-90.34225,-89.41031,-91.37588], "fy":[59.27276,62.22944,63.57,60.71488]}, + {"t":3.10167, "x":3.81651, "y":5.49135, "heading":2.10006, "vx":0.34335, "vy":-0.2322, "omega":-0.02465, "ax":-5.34206, "ay":3.61272, "alpha":0.3809, "fx":[-92.34201,-90.34303,-89.39402,-91.38887], "fy":[59.24249,62.24408,63.60798,60.71097]}, + {"t":3.1338, "x":3.82478, "y":5.48575, "heading":2.09927, "vx":0.17168, "vy":-0.11611, "omega":-0.01241, "ax":-5.34242, "ay":3.61296, "alpha":0.38607, "fx":[-92.36867,-90.34337,-89.37958,-91.4008], "fy":[59.21559,62.25771,63.64174,60.70696]}, + {"t":3.16594, "x":3.82754, "y":5.48389, "heading":2.09887, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[ + {"name":"Funnel", "from":{"target":5, "targetTimestamp":2.65177, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] +} diff --git a/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH3.traj b/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH3.traj new file mode 100644 index 00000000..21bfb17a --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH3.traj @@ -0,0 +1,119 @@ +{ + "name":"A_LEFT_PATH3", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.999176502227783, "y":5.206205368041992, "heading":2.1010083691287966, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.3110252618789673, "y":7.185760498046875, "heading":2.2024870470289093, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.4608945846557617, "y":6.165796279907227, "heading":0.0, "intervals":33, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":3.410642147064209, "y":5.334875106811523, "heading":2.077894951837786, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.999176502227783 m", "val":3.999176502227783}, "y":{"exp":"5.206205368041992 m", "val":5.206205368041992}, "heading":{"exp":"2.1010083691287966 rad", "val":2.1010083691287966}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"7.185760498046875 m", "val":7.185760498046875}, "heading":{"exp":"2.2024870470289093 rad", "val":2.2024870470289093}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.4608945846557617 m", "val":2.4608945846557617}, "y":{"exp":"6.165796279907227 m", "val":6.165796279907227}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":33, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"3.410642147064209 m", "val":3.410642147064209}, "y":{"exp":"5.334875106811523 m", "val":5.334875106811523}, "heading":{"exp":"2.077894951837786 rad", "val":2.077894951837786}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.45692,2.14786,2.77872], + "samples":[ + {"t":0.0, "x":3.99918, "y":5.20621, "heading":2.10101, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.19517, "ay":3.82571, "alpha":0.34139, "fx":[-89.74956,-87.81273,-86.99375,-88.91725], "fy":[63.17899,65.84215,66.92562,64.3502]}, + {"t":0.04415, "x":3.99411, "y":5.20993, "heading":2.10101, "vx":-0.22936, "vy":0.1689, "omega":0.01507, "ax":-5.19479, "ay":3.82543, "alpha":0.33555, "fx":[-89.71932,-87.81583,-87.01099,-88.90161], "fy":[63.2072,65.82375,66.88948,64.35768]}, + {"t":0.0883, "x":3.97892, "y":5.22112, "heading":2.10167, "vx":-0.45871, "vy":0.33779, "omega":0.02989, "ax":-5.19435, "ay":3.82511, "alpha":0.32866, "fx":[-89.68341,-87.81856,-87.03165,-88.88404], "fy":[63.24085,65.80332,66.84643,64.3653]}, + {"t":0.13245, "x":3.95361, "y":5.23976, "heading":2.10299, "vx":-0.68803, "vy":0.50666, "omega":0.0444, "ax":-5.19382, "ay":3.82472, "alpha":0.32045, "fx":[-89.64027,-87.82116,-87.05657,-88.86365], "fy":[63.28131,65.77981,66.79464,64.37356]}, + {"t":0.1766, "x":3.91817, "y":5.26586, "heading":2.10495, "vx":-0.91733, "vy":0.67552, "omega":0.05854, "ax":-5.19318, "ay":3.82424, "alpha":0.31046, "fx":[-89.58773,-87.82397,-87.08696,-88.83917], "fy":[63.3306,65.75173,66.73149,64.38315]}, + {"t":0.22074, "x":3.87261, "y":5.29941, "heading":2.10754, "vx":-1.14661, "vy":0.84436, "omega":0.07225, "ax":-5.19238, "ay":3.82365, "alpha":0.29807, "fx":[-89.52252,-87.82747,-87.12461,-88.8087], "fy":[63.39167,65.71687,66.65308,64.3951]}, + {"t":0.26489, "x":3.81693, "y":5.34041, "heading":2.11073, "vx":-1.37584, "vy":1.01317, "omega":0.08541, "ax":-5.19135, "ay":3.82289, "alpha":0.28229, "fx":[-89.43962,-87.8324,-87.1723,-88.76932], "fy":[63.46906,65.67187,66.55336,64.411]}, + {"t":0.30904, "x":3.75113, "y":5.38887, "heading":2.1145, "vx":-1.60504, "vy":1.18195, "omega":0.09787, "ax":-5.19, "ay":3.82189, "alpha":0.26151, "fx":[-89.33078,-87.83993,-87.23451,-88.71626], "fy":[63.57019,65.61126,66.42243,64.43339]}, + {"t":0.35319, "x":3.67521, "y":5.44477, "heading":2.11882, "vx":-1.83417, "vy":1.35068, "omega":0.10942, "ax":-5.18812, "ay":3.82051, "alpha":0.23289, "fx":[-89.18161,-87.85204,-87.31912,-88.64114], "fy":[63.70797,65.52553,66.24289,64.46672]}, + {"t":0.39734, "x":3.58918, "y":5.50813, "heading":2.12365, "vx":-2.06322, "vy":1.51935, "omega":0.1197, "ax":-5.18536, "ay":3.81847, "alpha":0.191, "fx":[-88.9643,-87.87246,-87.4412,-88.52772], "fy":[63.90708,65.39654,65.98105,64.51951]}, + {"t":0.44149, "x":3.49304, "y":5.57893, "heading":2.12893, "vx":-2.29215, "vy":1.68793, "omega":0.12813, "ax":-5.18087, "ay":3.81515, "alpha":0.12383, "fx":[-88.61758,-87.90905,-87.63367,-88.33985], "fy":[64.22132,65.18476,65.56213,64.61046]}, + {"t":0.48564, "x":3.38679, "y":5.65716, "heading":2.13459, "vx":-2.52088, "vy":1.85637, "omega":0.1336, "ax":-5.17232, "ay":3.80885, "alpha":-0.00133, "fx":[-87.97443,-87.98205,-87.98496,-87.97734], "fy":[64.79459,64.78428,64.78021,64.79052]}, + {"t":0.52979, "x":3.27046, "y":5.74283, "heading":2.14049, "vx":-2.74923, "vy":2.02452, "omega":0.13354, "ax":-5.14981, "ay":3.79224, "alpha":-0.31664, "fx":[-86.36185,-88.16478,-88.84034,-87.02035], "fy":[66.18458,63.78172,62.78691,65.26626]}, + {"t":0.57394, "x":3.14406, "y":5.83591, "heading":2.14639, "vx":-2.97659, "vy":2.19195, "omega":0.11956, "ax":-4.9428, "ay":3.64167, "alpha":-2.67463, "fx":[-74.77678,-89.08997,-94.03118,-78.40447], "fy":[74.64333,57.31767,46.77811,69.03584]}, + {"t":0.61809, "x":3.00783, "y":5.93623, "heading":2.15166, "vx":-3.19481, "vy":2.35272, "omega":0.00148, "ax":-0.02822, "ay":0.0196, "alpha":-0.02775, "fx":[-0.45929,-0.57972,-0.50076,-0.38029], "fy":[0.43318,0.35404,0.23364,0.31275]}, + {"t":0.66223, "x":2.86676, "y":6.04012, "heading":2.15173, "vx":-3.19606, "vy":2.35359, "omega":0.00025, "ax":-0.00012, "ay":-0.00015, "alpha":-0.00001, "fx":[-0.00211,-0.00214,-0.00212,-0.00209], "fy":[-0.00254,-0.00256,-0.00258,-0.00257]}, + {"t":0.70638, "x":2.72565, "y":6.14403, "heading":2.15174, "vx":-3.19606, "vy":2.35358, "omega":0.00025, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.75053, "x":2.58455, "y":6.24794, "heading":2.15175, "vx":-3.19606, "vy":2.35358, "omega":0.00025, "ax":0.00012, "ay":0.00015, "alpha":0.00001, "fx":[0.0021,0.00213,0.00211,0.00208], "fy":[0.00252,0.00254,0.00257,0.00255]}, + {"t":0.79468, "x":2.44345, "y":6.35185, "heading":2.15176, "vx":-3.19606, "vy":2.35359, "omega":0.00025, "ax":0.02821, "ay":-0.0196, "alpha":0.02773, "fx":[0.45922,0.57957,0.50065,0.38024], "fy":[-0.43316,-0.35404,-0.23372,-0.3128]}, + {"t":0.83883, "x":2.30237, "y":6.45573, "heading":2.15177, "vx":-3.19481, "vy":2.35272, "omega":0.00148, "ax":4.9428, "ay":-3.64166, "alpha":2.67446, "fx":[74.81883,89.13137,94.01125,78.34131], "fy":[-74.60493,-57.25032,-46.80727,-69.1121]}, + {"t":0.88298, "x":2.16614, "y":6.55606, "heading":2.15184, "vx":-2.97659, "vy":2.19195, "omega":0.11955, "ax":5.14981, "ay":-3.79224, "alpha":0.3164, "fx":[86.36971,88.17801,88.83321,87.00638], "fy":[-66.17466,-63.76322,-62.79656,-65.28507]}, + {"t":0.92713, "x":2.03975, "y":6.64913, "heading":2.15712, "vx":-2.74923, "vy":2.02452, "omega":0.13352, "ax":5.17232, "ay":-3.80885, "alpha":0.00126, "fx":[87.97477,87.98202,87.9846,87.97736], "fy":[-64.79411,-64.78431,-64.78069,-64.79049]}, + {"t":0.97128, "x":1.92341, "y":6.7348, "heading":2.16301, "vx":-2.52088, "vy":1.85637, "omega":0.13358, "ax":5.18087, "ay":-3.81515, "alpha":-0.12384, "fx":[88.61018,87.89221,87.64142,88.35633], "fy":[-64.23135,-65.20754,-65.55194,-64.58784]}, + {"t":1.01543, "x":1.81717, "y":6.81304, "heading":2.16891, "vx":-2.29215, "vy":1.68793, "omega":0.12811, "ax":5.18536, "ay":-3.81847, "alpha":-0.19098, "fx":[88.94917,87.83781,87.45744,88.56125], "fy":[-63.92784,-65.44319,-65.95979,-64.47335]}, + {"t":1.05958, "x":1.72102, "y":6.88384, "heading":2.17457, "vx":-2.06322, "vy":1.51935, "omega":0.11968, "ax":5.18812, "ay":-3.82051, "alpha":-0.23285, "fx":[89.15903,87.79981,87.34374,88.69133], "fy":[-63.7392,-65.59566,-66.21076,-64.3975]}, + {"t":1.10372, "x":1.63499, "y":6.94719, "heading":2.17985, "vx":-1.83417, "vy":1.35068, "omega":0.1094, "ax":5.19, "ay":-3.82189, "alpha":-0.26146, "fx":[89.30123,87.77098,87.26709,88.78219], "fy":[-63.6113,-65.70364,-66.37999,-64.34235]}, + {"t":1.14787, "x":1.55907, "y":7.0031, "heading":2.18468, "vx":-1.60504, "vy":1.18195, "omega":0.09786, "ax":5.19135, "ay":-3.82289, "alpha":-0.28224, "fx":[89.40365,87.74802,87.21224,88.84973], "fy":[-63.51929,-65.78477,-66.50138,-64.29986]}, + {"t":1.19202, "x":1.49327, "y":7.05156, "heading":2.189, "vx":-1.37584, "vy":1.01317, "omega":0.08539, "ax":5.19238, "ay":-3.82365, "alpha":-0.29802, "fx":[89.4808,87.72918,87.17123,88.9021], "fy":[-63.45011,-65.84823,-66.59249,-64.2659]}, + {"t":1.23617, "x":1.43759, "y":7.09256, "heading":2.19277, "vx":-1.14661, "vy":0.84436, "omega":0.07224, "ax":5.19318, "ay":-3.82424, "alpha":-0.31041, "fx":[89.54097,87.71349,87.13944,88.94394], "fy":[-63.39626,-65.89923,-66.66333,-64.23815]}, + {"t":1.28032, "x":1.39203, "y":7.12611, "heading":2.19596, "vx":-0.91733, "vy":0.67552, "omega":0.05853, "ax":5.19382, "ay":-3.82472, "alpha":-0.32039, "fx":[89.58924,87.70035,87.11406,88.97803], "fy":[-63.35312,-65.941,-66.72003,-64.2152]}, + {"t":1.32447, "x":1.35659, "y":7.15221, "heading":2.19854, "vx":-0.68803, "vy":0.50666, "omega":0.04439, "ax":5.19435, "ay":-3.82511, "alpha":-0.32861, "fx":[89.62889,87.68937,87.09323,89.00618], "fy":[-63.31766,-65.97557,-66.76654,-64.19613]}, + {"t":1.36862, "x":1.33128, "y":7.17085, "heading":2.2005, "vx":-0.45871, "vy":0.33779, "omega":0.02988, "ax":5.19479, "ay":-3.82543, "alpha":-0.33549, "fx":[89.66217,87.6803,87.07571,89.02958], "fy":[-63.28785,-66.00436,-66.80556,-64.18037]}, + {"t":1.41277, "x":1.31609, "y":7.18203, "heading":2.20182, "vx":-0.22936, "vy":0.1689, "omega":0.01507, "ax":5.19517, "ay":-3.82571, "alpha":-0.34133, "fx":[89.69063,87.67297,87.06062,89.04909], "fy":[-63.26224,-66.02832,-66.83895,-64.16748]}, + {"t":1.45692, "x":1.31103, "y":7.18576, "heading":2.20249, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.83764, "ay":-4.26453, "alpha":-0.36735, "fx":[83.79976,81.3103,80.80336,83.23432], "fy":[-70.80802,-73.65156,-74.21495,-71.47952]}, + {"t":1.48696, "x":1.31321, "y":7.18384, "heading":2.20249, "vx":0.14533, "vy":-0.12811, "omega":-0.01104, "ax":4.8373, "ay":-4.26424, "alpha":-0.36503, "fx":[83.78416,81.31075,80.80705,83.22271], "fy":[-70.8141,-73.63909,-74.1994,-71.48114]}, + {"t":1.517, "x":1.31976, "y":7.17806, "heading":2.20216, "vx":0.29065, "vy":-0.25621, "omega":-0.022, "ax":4.83693, "ay":-4.2639, "alpha":-0.36245, "fx":[83.76715,81.31175,80.81081,83.20933], "fy":[-70.82048,-73.62468,-74.18247,-71.48349]}, + {"t":1.54704, "x":1.33067, "y":7.16844, "heading":2.20149, "vx":0.43595, "vy":-0.38431, "omega":-0.03289, "ax":4.83651, "ay":-4.26353, "alpha":-0.35957, "fx":[83.7484,81.31329,80.81473,83.19397], "fy":[-70.82731,-73.60811,-74.16386,-71.48658]}, + {"t":1.57708, "x":1.34595, "y":7.15497, "heading":2.20051, "vx":0.58125, "vy":-0.51239, "omega":-0.04369, "ax":4.83603, "ay":-4.26311, "alpha":-0.35633, "fx":[83.72751,81.31535,80.8189,83.17635], "fy":[-70.83473,-73.58909,-74.14316,-71.49043]}, + {"t":1.60712, "x":1.36559, "y":7.13766, "heading":2.19919, "vx":0.72653, "vy":-0.64045, "omega":-0.0544, "ax":4.83549, "ay":-4.26264, "alpha":-0.35267, "fx":[83.70401,81.31793,80.82345,83.15614], "fy":[-70.84294,-73.56728,-74.11988,-71.49507]}, + {"t":1.63716, "x":1.3896, "y":7.11649, "heading":2.19756, "vx":0.87179, "vy":-0.76851, "omega":-0.06499, "ax":4.83488, "ay":-4.2621, "alpha":-0.34848, "fx":[83.67724,81.32101,80.82855,83.1329], "fy":[-70.8522,-73.54219,-74.09337,-71.50053]}, + {"t":1.6672, "x":1.41797, "y":7.09148, "heading":2.19561, "vx":1.01703, "vy":-0.89655, "omega":-0.07546, "ax":4.83417, "ay":-4.26147, "alpha":-0.34365, "fx":[83.6464,81.32457,80.83439,83.10606], "fy":[-70.86285,-73.51324,-74.0628,-71.50683]}, + {"t":1.69724, "x":1.45071, "y":7.06263, "heading":2.19334, "vx":1.16226, "vy":-1.02457, "omega":-0.08578, "ax":4.83334, "ay":-4.26074, "alpha":-0.33802, "fx":[83.61037,81.32858,80.84124,83.07483], "fy":[-70.8753,-73.47962,-74.02706,-71.51404]}, + {"t":1.72729, "x":1.4878, "y":7.02993, "heading":2.19076, "vx":1.30746, "vy":-1.15256, "omega":-0.09594, "ax":4.83236, "ay":-4.25988, "alpha":-0.33137, "fx":[83.56767,81.33299,80.84949,83.03818], "fy":[-70.89015,-73.44024,-73.98462,-71.52221]}, + {"t":1.75733, "x":1.52926, "y":6.99338, "heading":2.18788, "vx":1.45263, "vy":-1.28053, "omega":-0.10589, "ax":4.83118, "ay":-4.25884, "alpha":-0.32341, "fx":[83.5162,81.33776,80.85961,82.99465], "fy":[-70.9082,-73.39358,-73.93338,-71.53146]}, + {"t":1.78737, "x":1.57508, "y":6.95299, "heading":2.1847, "vx":1.59776, "vy":-1.40847, "omega":-0.11561, "ax":4.82974, "ay":-4.25757, "alpha":-0.3137, "fx":[83.45299,81.34279,80.87234,82.9421], "fy":[-70.93061,-73.33744,-73.87028,-71.54189]}, + {"t":1.81741, "x":1.62526, "y":6.90876, "heading":2.18123, "vx":1.74285, "vy":-1.53638, "omega":-0.12503, "ax":4.82794, "ay":-4.25598, "alpha":-0.30159, "fx":[83.37357,81.34793,80.8887,82.87736], "fy":[-70.95906,-73.26855,-73.79078,-71.5537]}, + {"t":1.84745, "x":1.67979, "y":6.86068, "heading":2.17747, "vx":1.88789, "vy":-1.66423, "omega":-0.13409, "ax":4.82562, "ay":-4.25394, "alpha":-0.28608, "fx":[83.27096,81.35294,80.91028,82.79543], "fy":[-70.99616,-73.1818,-73.68775,-71.56716]}, + {"t":1.87749, "x":1.73868, "y":6.80877, "heading":2.17344, "vx":2.03285, "vy":-1.79202, "omega":-0.14269, "ax":4.82252, "ay":-4.2512, "alpha":-0.26551, "fx":[83.13365,81.35735,80.93965,82.688], "fy":[-71.04609,-73.06874,-73.54941,-71.58267]}, + {"t":1.90753, "x":1.80193, "y":6.75301, "heading":2.16916, "vx":2.17773, "vy":-1.91973, "omega":-0.15066, "ax":4.81817, "ay":-4.24737, "alpha":-0.23692, "fx":[82.94114,81.36024,80.98116,82.54014], "fy":[-71.11615,-72.91436,-73.35466,-71.60085]}, + {"t":1.93757, "x":1.86952, "y":6.69343, "heading":2.16463, "vx":2.32247, "vy":-2.04733, "omega":-0.15778, "ax":4.81163, "ay":-4.2416, "alpha":-0.19453, "fx":[82.6531,81.35941,81.04296,82.3221], "fy":[-71.22011,-72.68912,-73.06181,-71.62261]}, + {"t":1.96761, "x":1.94146, "y":6.63001, "heading":2.15989, "vx":2.46702, "vy":-2.17475, "omega":-0.16362, "ax":4.80069, "ay":-4.23196, "alpha":-0.12526, "fx":[82.17776,81.34876,81.14191,81.96498], "fy":[-71.38744,-72.32607,-72.57526,-71.64891]}, + {"t":1.99766, "x":2.01774, "y":6.56277, "heading":2.15498, "vx":2.61123, "vy":-2.30188, "omega":-0.16739, "ax":4.77875, "ay":-4.21262, "alpha":0.00803, "fx":[81.25205,81.30478,81.31817,81.26542], "fy":[-71.69351,-71.63415,-71.61729,-71.6767]}, + {"t":2.0277, "x":2.09834, "y":6.49172, "heading":2.14995, "vx":2.75479, "vy":-2.42844, "omega":-0.16714, "ax":4.71317, "ay":-4.15481, "alpha":0.36768, "fx":[78.69833,81.0626,81.66527,79.2525], "fy":[-72.38435,-69.76594,-68.90945,-71.62882]}, + {"t":2.05774, "x":2.18323, "y":6.41689, "heading":2.14493, "vx":2.89638, "vy":-2.55325, "omega":-0.1561, "ax":2.64747, "ay":-2.33676, "alpha":5.1734, "fx":[37.29647,60.46081,55.72315,26.65017], "fy":[-58.74226,-39.48452,-18.1357,-42.62821]}, + {"t":2.08778, "x":2.27143, "y":6.33913, "heading":2.14024, "vx":2.97591, "vy":-2.62345, "omega":-0.00068, "ax":0.0069, "ay":-0.00517, "alpha":0.01035, "fx":[0.10922,0.15446,0.12548,0.08026], "fy":[-0.12502,-0.09607,-0.05083,-0.07976]}, + {"t":2.11782, "x":2.36083, "y":6.26032, "heading":2.14022, "vx":2.97612, "vy":-2.6236, "omega":-0.00037, "ax":-0.00691, "ay":0.00515, "alpha":-0.01035, "fx":[-0.10946,-0.15473,-0.12572,-0.08048], "fy":[0.12479,0.09583,0.05056,0.07951]}, + {"t":2.14786, "x":2.45024, "y":6.1815, "heading":2.1402, "vx":2.97591, "vy":-2.62345, "omega":-0.00069, "ax":-2.64747, "ay":2.3368, "alpha":-5.17506, "fx":[-37.21389,-60.42887,-55.7994,-26.68892], "fy":[58.76407,39.57054,18.13451,42.52382]}, + {"t":2.1779, "x":2.53844, "y":6.10375, "heading":2.14018, "vx":2.89638, "vy":-2.55325, "omega":-0.15615, "ax":-4.71316, "ay":4.1548, "alpha":-0.36878, "fx":[-78.68467,-81.05094,-81.67804,-79.26458], "fy":[72.39839,69.78017,68.89504,71.61452]}, + {"t":2.20794, "x":2.62332, "y":6.02892, "heading":2.13549, "vx":2.75479, "vy":-2.42844, "omega":-0.16723, "ax":-4.77875, "ay":4.21262, "alpha":-0.00842, "fx":[-81.25006,-81.30504,-81.32015,-81.26514], "fy":[71.69575,71.6339,71.61502,71.67693]}, + {"t":2.23798, "x":2.70393, "y":5.95787, "heading":2.13047, "vx":2.61123, "vy":-2.30188, "omega":-0.16748, "ax":-4.80069, "ay":4.23196, "alpha":0.12513, "fx":[-82.18589,-81.36458,-81.13348,-81.94945], "fy":[71.37841,72.30808,72.58435,71.66683]}, + {"t":2.26802, "x":2.7802, "y":5.89063, "heading":2.12544, "vx":2.46702, "vy":-2.17475, "omega":-0.16372, "ax":-4.81163, "ay":4.2416, "alpha":0.19453, "fx":[-82.67085,-81.39181,-81.02426,-82.29064], "fy":[71.20002,72.65255,73.08206,71.65902]}, + {"t":2.29807, "x":2.85214, "y":5.82721, "heading":2.12052, "vx":2.32247, "vy":-2.04733, "omega":-0.15788, "ax":-4.81817, "ay":4.24737, "alpha":0.23699, "fx":[-82.96809,-81.40929,-80.95246,-82.49283], "fy":[71.08534,72.85922,73.38575,71.65569]}, + {"t":2.32811, "x":2.91974, "y":5.76762, "heading":2.11578, "vx":2.17773, "vy":-1.91973, "omega":-0.15076, "ax":-4.82252, "ay":4.2512, "alpha":0.26563, "fx":[-83.16938,-81.42272,-80.90131,-82.62523], "fy":[71.00496,72.9955,73.59094,71.65548]}, + {"t":2.35815, "x":2.98298, "y":5.71187, "heading":2.11125, "vx":2.03285, "vy":-1.79202, "omega":-0.14278, "ax":-4.82562, "ay":4.25393, "alpha":0.28623, "fx":[-83.31501,-81.43403,-80.86273,-82.7178], "fy":[70.9452,73.09114,73.73925,71.65725]}, + {"t":2.38819, "x":3.04188, "y":5.65995, "heading":2.10696, "vx":1.88789, "vy":-1.66423, "omega":-0.13418, "ax":-4.82794, "ay":4.25598, "alpha":0.30176, "fx":[-83.42547,-81.44401,-80.83243,-82.7856], "fy":[70.89881,73.1613,73.85171,71.66024]}, + {"t":2.41823, "x":3.09641, "y":5.61188, "heading":2.10293, "vx":1.74285, "vy":-1.53638, "omega":-0.12511, "ax":-4.82974, "ay":4.25757, "alpha":0.31389, "fx":[-83.51225,-81.45302,-80.80788,-82.83702], "fy":[70.86163,73.21455,73.94007,71.66394]}, + {"t":2.44827, "x":3.14659, "y":5.56765, "heading":2.09917, "vx":1.59776, "vy":-1.40847, "omega":-0.11569, "ax":-4.83118, "ay":4.25884, "alpha":0.32361, "fx":[-83.58229,-81.46124,-80.78753,-82.87712], "fy":[70.83109,73.25606,74.01142,71.668]}, + {"t":2.47831, "x":3.19241, "y":5.52726, "heading":2.09569, "vx":1.45262, "vy":-1.28053, "omega":-0.10596, "ax":-4.83236, "ay":4.25988, "alpha":0.33158, "fx":[-83.64004,-81.46875,-80.77035,-82.90913], "fy":[70.80554,73.28916,74.0703,71.67219]}, + {"t":2.50835, "x":3.23387, "y":5.49071, "heading":2.09251, "vx":1.30746, "vy":-1.15256, "omega":-0.096, "ax":-4.83334, "ay":4.26074, "alpha":0.33824, "fx":[-83.68849,-81.47561,-80.75565,-82.9352], "fy":[70.78382,73.3161,74.11971,71.67633]}, + {"t":2.53839, "x":3.27096, "y":5.45801, "heading":2.08963, "vx":1.16226, "vy":-1.02457, "omega":-0.08584, "ax":-4.83417, "ay":4.26147, "alpha":0.34387, "fx":[-83.72971,-81.48185,-80.74295,-82.95683], "fy":[70.76517,73.33844,74.16177,71.68029]}, + {"t":2.56844, "x":3.3037, "y":5.42915, "heading":2.08705, "vx":1.01703, "vy":-0.89655, "omega":-0.07551, "ax":-4.83488, "ay":4.2621, "alpha":0.34871, "fx":[-83.76518,-81.48746,-80.7319,-82.9751], "fy":[70.74899,73.35728,74.19798,71.68399]}, + {"t":2.59848, "x":3.33207, "y":5.40414, "heading":2.08478, "vx":0.87179, "vy":-0.76851, "omega":-0.06504, "ax":-4.83549, "ay":4.26264, "alpha":0.3529, "fx":[-83.79598,-81.49246,-80.72223,-82.99078], "fy":[70.73487,73.37347,74.22944,71.68734]}, + {"t":2.62852, "x":3.35607, "y":5.38298, "heading":2.08283, "vx":0.72653, "vy":-0.64045, "omega":-0.05443, "ax":-4.83603, "ay":4.26311, "alpha":0.35658, "fx":[-83.82296,-81.49686,-80.71375,-83.00448], "fy":[70.72249,73.38762,74.25697,71.69029]}, + {"t":2.65856, "x":3.37572, "y":5.36566, "heading":2.08119, "vx":0.58125, "vy":-0.51239, "omega":-0.04372, "ax":-4.83651, "ay":4.26353, "alpha":0.35982, "fx":[-83.84672,-81.50064,-80.70629,-83.01665], "fy":[70.7116,73.40021,74.28121,71.69278]}, + {"t":2.6886, "x":3.391, "y":5.35219, "heading":2.07988, "vx":0.43595, "vy":-0.38431, "omega":-0.03291, "ax":-4.83693, "ay":4.2639, "alpha":0.3627, "fx":[-83.86776,-81.50382,-80.69975,-83.02764], "fy":[70.702,73.41162,74.30266,71.69479]}, + {"t":2.71864, "x":3.40191, "y":5.34257, "heading":2.07889, "vx":0.29065, "vy":-0.25621, "omega":-0.02202, "ax":-4.8373, "ay":4.26423, "alpha":0.36528, "fx":[-83.88647,-81.50637,-80.69403,-83.03773], "fy":[70.69354,73.42214,74.32171,71.69628]}, + {"t":2.74868, "x":3.40846, "y":5.3368, "heading":2.07823, "vx":0.14533, "vy":-0.12811, "omega":-0.01104, "ax":-4.83764, "ay":4.26453, "alpha":0.36761, "fx":[-83.90315,-81.50832,-80.68904,-83.04715], "fy":[70.68611,73.43201,74.33866,71.69722]}, + {"t":2.77872, "x":3.41064, "y":5.33488, "heading":2.07789, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[ + {"name":"Funnel", "from":{"target":2, "targetTimestamp":2.14786, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] +} diff --git a/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH4.traj b/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH4.traj new file mode 100644 index 00000000..4d69136b --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH4.traj @@ -0,0 +1,129 @@ +{ + "name":"A_LEFT_PATH4", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.692616224288941, "y":5.020236015319824, "heading":2.0948682307415045, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.3110252618789673, "y":7.185760498046875, "heading":2.216612130911823, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.2821998596191406, "y":5.24192476272583, "heading":0.0, "intervals":35, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":2.819322109222412, "y":4.265955924987793, "heading":3.1289351796122347, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.6926162242889404 m", "val":3.692616224288941}, "y":{"exp":"5.020236015319824 m", "val":5.020236015319824}, "heading":{"exp":"2.0948682307415045 rad", "val":2.0948682307415045}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"7.185760498046875 m", "val":7.185760498046875}, "heading":{"exp":"2.216612130911823 rad", "val":2.216612130911823}, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.2821998596191406 m", "val":2.2821998596191406}, "y":{"exp":"5.24192476272583 m", "val":5.24192476272583}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":35, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"2.819322109222412 m", "val":2.819322109222412}, "y":{"exp":"4.265955924987793 m", "val":4.265955924987793}, "heading":{"exp":"3.1289351796122347 rad", "val":3.1289351796122347}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.42726,2.23364,2.87874], + "samples":[ + {"t":0.0, "x":3.69262, "y":5.02024, "heading":2.09487, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-4.77336, "ay":4.34029, "alpha":0.36517, "fx":[-82.80387,-80.3539,-79.60509,-82.01137], "fy":[72.03947,74.76071,75.56262,72.9455]}, + {"t":0.04325, "x":3.68815, "y":5.0243, "heading":2.09487, "vx":-0.20645, "vy":0.18772, "omega":0.01579, "ax":-4.77303, "ay":4.33999, "alpha":0.36029, "fx":[-82.77638,-80.35948,-79.62059,-81.99495], "fy":[72.05859,74.74258,75.53461,72.95195]}, + {"t":0.0865, "x":3.67476, "y":5.03647, "heading":2.09555, "vx":-0.41289, "vy":0.37543, "omega":0.03138, "ax":-4.77264, "ay":4.33963, "alpha":0.35461, "fx":[-82.74377,-80.3649,-79.63925,-81.97681], "fy":[72.08147,74.7226,75.50128,72.95832]}, + {"t":0.12975, "x":3.65244, "y":5.05677, "heading":2.09691, "vx":-0.6193, "vy":0.56312, "omega":0.04671, "ax":-4.77217, "ay":4.33921, "alpha":0.34789, "fx":[-82.70483,-80.37047,-79.66174,-81.95612], "fy":[72.10894,74.69987,75.4614,72.96497]}, + {"t":0.173, "x":3.62119, "y":5.08518, "heading":2.09893, "vx":-0.8257, "vy":0.75079, "omega":0.06176, "ax":-4.77161, "ay":4.33871, "alpha":0.33982, "fx":[-82.65783,-80.37666,-79.68899,-81.9317], "fy":[72.14215,74.67312,75.41319,72.97244]}, + {"t":0.21625, "x":3.58101, "y":5.12171, "heading":2.1016, "vx":-1.03208, "vy":0.93844, "omega":0.07646, "ax":-4.77093, "ay":4.33809, "alpha":0.32994, "fx":[-82.60029,-80.3841,-79.72234,-81.90188], "fy":[72.18278,74.64053,75.35412,72.98148]}, + {"t":0.2595, "x":3.53191, "y":5.16636, "heading":2.10491, "vx":-1.23842, "vy":1.12606, "omega":0.09073, "ax":-4.77007, "ay":4.33732, "alpha":0.31759, "fx":[-82.52847,-80.39377,-79.76384,-81.86414], "fy":[72.23331,74.59939,75.28035,72.99318]}, + {"t":0.30275, "x":3.47389, "y":5.21912, "heading":2.10883, "vx":-1.44473, "vy":1.31366, "omega":0.10446, "ax":-4.76896, "ay":4.33632, "alpha":0.3017, "fx":[-82.43651,-80.40713,-79.81665,-81.81452], "fy":[72.29765,74.54544,75.18582,73.0093]}, + {"t":0.346, "x":3.40694, "y":5.27999, "heading":2.11335, "vx":-1.65099, "vy":1.5012, "omega":0.11751, "ax":-4.76748, "ay":4.33498, "alpha":0.28048, "fx":[-82.31463,-80.4266,-79.88606,-81.7464], "fy":[72.38226,74.47165,75.06042,73.03267]}, + {"t":0.38925, "x":3.33108, "y":5.34897, "heading":2.11843, "vx":-1.85718, "vy":1.68869, "omega":0.12964, "ax":-4.76538, "ay":4.33309, "alpha":0.25074, "fx":[-82.14522,-80.45644,-79.98159,-81.64782], "fy":[72.4987,74.3654,74.88582,73.06841]}, + {"t":0.4325, "x":3.2463, "y":5.42606, "heading":2.12404, "vx":-2.06329, "vy":1.8761, "omega":0.14049, "ax":-4.7622, "ay":4.33022, "alpha":0.20608, "fx":[-81.89306,-80.50494,-80.1221,-81.49469], "fy":[72.66984,74.20164,74.62514,73.12662]}, + {"t":0.47575, "x":3.15261, "y":5.51125, "heading":2.13011, "vx":-2.26926, "vy":2.06338, "omega":0.1494, "ax":-4.75682, "ay":4.32536, "alpha":0.13158, "fx":[-81.47614,-80.59075,-80.35127,-81.23019], "fy":[72.94801,73.92248,74.19154,73.23063]}, + {"t":0.519, "x":3.05001, "y":5.60454, "heading":2.13658, "vx":-2.47499, "vy":2.25046, "omega":0.15509, "ax":-4.74572, "ay":4.31535, "alpha":-0.0174, "fx":[-80.64964,-80.76623,-80.79726,-80.68055], "fy":[73.48469,73.35701,73.32106,73.44898]}, + {"t":0.56226, "x":2.93853, "y":5.70591, "heading":2.14328, "vx":-2.68024, "vy":2.4371, "omega":0.15434, "ax":-4.71008, "ay":4.28318, "alpha":-0.46025, "fx":[-78.21717,-81.25126,-82.05793,-78.9421], "fy":[74.96378,71.68837,70.66649,74.10427]}, + {"t":0.60551, "x":2.8182, "y":5.81532, "heading":2.14996, "vx":-2.88396, "vy":2.62235, "omega":0.13443, "ax":-1.2157, "ay":1.10429, "alpha":-3.10111, "fx":[-17.91853,-31.3387,-23.99027,-9.46753], "fy":[30.0091,20.53232,7.3062,17.28695]}, + {"t":0.64876, "x":2.69233, "y":5.92977, "heading":2.15577, "vx":-2.93654, "vy":2.67011, "omega":0.00031, "ax":-0.00062, "ay":0.00028, "alpha":-0.00081, "fx":[-0.00992,-0.01341,-0.0111,-0.0076], "fy":[0.00772,0.0054,0.00191,0.00422]}, + {"t":0.69201, "x":2.56532, "y":6.04526, "heading":2.15579, "vx":-2.93656, "vy":2.67012, "omega":0.00027, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[-0.00001,-0.00001,-0.00001,-0.00001], "fy":[-0.00001,-0.00001,-0.00001,-0.00001]}, + {"t":0.73526, "x":2.43832, "y":6.16074, "heading":2.1558, "vx":-2.93656, "vy":2.67012, "omega":0.00027, "ax":0.00061, "ay":-0.00029, "alpha":0.00081, "fx":[0.00987,0.01336,0.01105,0.00755], "fy":[-0.00777,-0.00546,-0.00197,-0.00428]}, + {"t":0.77851, "x":2.31131, "y":6.27622, "heading":2.15581, "vx":-2.93654, "vy":2.67011, "omega":0.00031, "ax":1.21564, "ay":-1.10425, "alpha":3.09988, "fx":[17.98155,31.35144,23.9232,9.45427], "fy":[-30.01052,-20.46739,-7.29761,-17.35637]}, + {"t":0.82176, "x":2.18544, "y":6.39067, "heading":2.15582, "vx":-2.88396, "vy":2.62235, "omega":0.13438, "ax":4.71011, "ay":-4.2832, "alpha":0.4563, "fx":[78.24912,81.26521,82.02797,78.92834], "fy":[-74.9311,-71.67191,-70.70106,-74.12022]}, + {"t":0.86501, "x":2.06511, "y":6.50009, "heading":2.16164, "vx":-2.68025, "vy":2.4371, "omega":0.15411, "ax":4.74573, "ay":-4.31535, "alpha":0.01614, "fx":[80.65607,80.76491,80.79097,80.68202], "fy":[-73.47768,-73.35843,-73.32808,-73.44753]}, + {"t":0.90826, "x":1.95363, "y":6.60146, "heading":2.1683, "vx":-2.47499, "vy":2.25046, "omega":0.15481, "ax":4.75682, "ay":-4.32536, "alpha":-0.13197, "fx":[81.4654,80.56831,80.36251,81.25225], "fy":[-72.95981,-73.94707,-74.17961,-73.20607]}, + {"t":0.95151, "x":1.85104, "y":6.69474, "heading":2.175, "vx":-2.26926, "vy":2.06338, "omega":0.1491, "ax":4.7622, "ay":-4.33022, "alpha":-0.20605, "fx":[81.86727,80.45992,80.14932,81.5384], "fy":[-72.69857,-74.25068,-74.59625,-73.0777]}, + {"t":0.99476, "x":1.75734, "y":6.77993, "heading":2.18145, "vx":-2.06329, "vy":1.8761, "omega":0.14019, "ax":4.76538, "ay":-4.33309, "alpha":-0.25046, "fx":[82.10564,80.38905,80.0237,81.7128], "fy":[-72.54312,-74.43851,-74.8412,-72.9955]}, + {"t":1.03801, "x":1.67256, "y":6.85702, "heading":2.18751, "vx":-1.85718, "vy":1.68869, "omega":0.12936, "ax":4.76748, "ay":-4.33498, "alpha":-0.28003, "fx":[82.26239,80.33786,79.94201,81.83158], "fy":[-72.44118,-74.56765,-75.00125,-72.93696]}, + {"t":1.08126, "x":1.5967, "y":6.92601, "heading":2.1931, "vx":-1.65099, "vy":1.5012, "omega":0.11725, "ax":4.76897, "ay":-4.33632, "alpha":-0.30113, "fx":[82.37273,80.29854,79.88529,81.91843], "fy":[-72.36984,-74.6627,-75.11332,-72.89242]}, + {"t":1.12451, "x":1.52975, "y":6.98688, "heading":2.19817, "vx":-1.44473, "vy":1.31366, "omega":0.10423, "ax":4.77007, "ay":-4.33732, "alpha":-0.31695, "fx":[82.45429,80.2671,79.84396,81.98506], "fy":[-72.31749,-74.73597,-75.1958,-72.85708]}, + {"t":1.16776, "x":1.47173, "y":7.03964, "heading":2.20268, "vx":-1.23842, "vy":1.12607, "omega":0.09052, "ax":4.77093, "ay":-4.3381, "alpha":-0.32923, "fx":[82.51691,80.24134,79.81267,82.03791], "fy":[-72.2776,-74.79429,-75.25888,-72.82827]}, + {"t":1.21101, "x":1.42263, "y":7.08428, "heading":2.2066, "vx":-1.03208, "vy":0.93844, "omega":0.07628, "ax":4.77162, "ay":-4.33871, "alpha":-0.33906, "fx":[82.56647,80.21992,79.78819,82.08082], "fy":[-72.24622,-74.84177,-75.30866,-72.8044]}, + {"t":1.25426, "x":1.38245, "y":7.12081, "heading":2.2099, "vx":-0.8257, "vy":0.75079, "omega":0.06161, "ax":4.77218, "ay":-4.33922, "alpha":-0.34709, "fx":[82.60675,80.202,79.76843,82.11621], "fy":[-72.22081,-74.88101,-75.34903,-72.78449]}, + {"t":1.29751, "x":1.3512, "y":7.14923, "heading":2.21256, "vx":-0.6193, "vy":0.56312, "omega":0.0466, "ax":4.77264, "ay":-4.33964, "alpha":-0.35378, "fx":[82.64027,80.187,79.75202,82.1457], "fy":[-72.19966,-74.91375,-75.38256,-72.76786]}, + {"t":1.34076, "x":1.32888, "y":7.16952, "heading":2.21458, "vx":-0.41289, "vy":0.37543, "omega":0.0313, "ax":4.77303, "ay":-4.33999, "alpha":-0.35943, "fx":[82.66877,80.17455,79.73797,82.17038], "fy":[-72.18158,-74.94119,-75.41107,-72.75406]}, + {"t":1.38401, "x":1.31549, "y":7.1817, "heading":2.21593, "vx":-0.20645, "vy":0.18772, "omega":0.01576, "ax":4.77337, "ay":-4.34029, "alpha":-0.36428, "fx":[82.6935,80.16436,79.7256,82.19104], "fy":[-72.16572,-74.96417,-75.43584,-72.74277]}, + {"t":1.42726, "x":1.31103, "y":7.18576, "heading":2.21661, "vx":0.0, "vy":0.0, "omega":0.0, "ax":2.92009, "ay":-5.66075, "alpha":3.33895, "fx":[39.65414,64.81516,64.33176,29.87871], "fy":[-102.30195,-88.52067,-88.80521,-105.52346]}, + {"t":1.45414, "x":1.31208, "y":7.18372, "heading":2.21661, "vx":0.07849, "vy":-0.15216, "omega":0.08975, "ax":2.92076, "ay":-5.6625, "alpha":3.28889, "fx":[39.78129,64.63764,64.09729,30.20895], "fy":[-102.24494,-88.64131,-88.96343,-105.42035]}, + {"t":1.48102, "x":1.31524, "y":7.17758, "heading":2.21902, "vx":0.157, "vy":-0.30436, "omega":0.17815, "ax":2.92152, "ay":-5.66438, "alpha":3.23333, "fx":[39.96044,64.4685,63.80063,30.54705], "fy":[-102.16666,-88.75433,-89.16413,-105.31306]}, + {"t":1.5079, "x":1.32052, "y":7.16735, "heading":2.22381, "vx":0.23553, "vy":-0.45661, "omega":0.26506, "ax":2.92236, "ay":-5.66642, "alpha":3.17158, "fx":[40.19136,64.30267,63.4405,30.89943], "fy":[-102.06674,-88.86333,-89.40716,-105.1995]}, + {"t":1.53478, "x":1.32791, "y":7.15303, "heading":2.23094, "vx":0.31408, "vy":-0.60892, "omega":0.35031, "ax":2.92329, "ay":-5.66863, "alpha":3.10282, "fx":[40.474,64.13382,63.0151,31.27417], "fy":[-101.94462,-88.9727,-89.6925,-105.07696]}, + {"t":1.56166, "x":1.3374, "y":7.13462, "heading":2.24035, "vx":0.39265, "vy":-0.76129, "omega":0.43371, "ax":2.9243, "ay":-5.67102, "alpha":3.02599, "fx":[40.80843,63.95412,62.52214,31.68118], "fy":[-101.79956,-89.0878,-90.02019,-104.94198]}, + {"t":1.58854, "x":1.34902, "y":7.11211, "heading":2.25201, "vx":0.47125, "vy":-0.91372, "omega":0.51505, "ax":2.92539, "ay":-5.67362, "alpha":2.9398, "fx":[41.19492,63.75377,61.95886,32.13262], "fy":[-101.6306,-89.21524,-90.39028,-104.79017]}, + {"t":1.61542, "x":1.36274, "y":7.0855, "heading":2.26586, "vx":0.54989, "vy":-1.06623, "omega":0.59407, "ax":2.92656, "ay":-5.67644, "alpha":2.84262, "fx":[41.63397,63.52045,61.32214,32.64333], "fy":[-101.43647,-89.36318,-90.80272,-104.61597]}, + {"t":1.6423, "x":1.37858, "y":7.05479, "heading":2.28182, "vx":0.62855, "vy":-1.2188, "omega":0.67047, "ax":2.92781, "ay":-5.6795, "alpha":2.73239, "fx":[42.12644,63.23848,60.60849,33.2316], "fy":[-101.21556,-89.54186,-91.25734,-104.41219]}, + {"t":1.66918, "x":1.39653, "y":7.01997, "heading":2.29985, "vx":0.70725, "vy":-1.37146, "omega":0.74392, "ax":2.92914, "ay":-5.68283, "alpha":2.60639, "fx":[42.67369,62.8875,59.8141,33.92019], "fy":[-100.96576,-89.76422,-91.75368,-104.16943]}, + {"t":1.69606, "x":1.4166, "y":6.98106, "heading":2.31984, "vx":0.78598, "vy":-1.52421, "omega":0.81398, "ax":2.93055, "ay":-5.68642, "alpha":2.46104, "fx":[43.27782,62.44057,58.93487,34.73795], "fy":[-100.68426,-90.04694,-92.29098,-103.87514]}, + {"t":1.72293, "x":1.43878, "y":6.93803, "heading":2.34172, "vx":0.86475, "vy":-1.67706, "omega":0.88013, "ax":2.93203, "ay":-5.69027, "alpha":2.29143, "fx":[43.94217,61.86119,57.96633,35.72224], "fy":[-100.3672,-90.41183,-92.86809,-103.51201]}, + {"t":1.74981, "x":1.46309, "y":6.8909, "heading":2.36538, "vx":0.94356, "vy":-1.83001, "omega":0.94172, "ax":2.93357, "ay":-5.69433, "alpha":2.09063, "fx":[44.67201,61.0983,56.90354,36.92279], "fy":[-100.00906,-90.88801,-93.48342,-103.05551]}, + {"t":1.77669, "x":1.48951, "y":6.83965, "heading":2.39069, "vx":1.02241, "vy":-1.98307, "omega":0.99791, "ax":2.93513, "ay":-5.69853, "alpha":1.84854, "fx":[45.47599,60.07801,55.74073,38.40789], "fy":[-99.6016,-91.51532,-94.135,-102.46943]}, + {"t":1.80357, "x":1.51805, "y":6.78429, "heading":2.41751, "vx":1.10131, "vy":-2.13624, "omega":1.0476, "ax":2.9366, "ay":-5.70262, "alpha":1.54987, "fx":[46.36867,58.68866,54.47066,40.27481], "fy":[-99.13177,-92.34961,-94.82058,-101.69795]}, + {"t":1.83045, "x":1.54871, "y":6.72481, "heading":2.44567, "vx":1.18024, "vy":-2.28952, "omega":1.08926, "ax":2.93773, "ay":-5.70611, "alpha":1.17048, "fx":[47.37576,56.75272,53.08323,42.66782], "fy":[-98.57754,-93.47133,-95.53789,-100.65046]}, + {"t":1.85733, "x":1.5815, "y":6.66121, "heading":2.47495, "vx":1.2592, "vy":-2.4429, "omega":1.12072, "ax":2.93787, "ay":-5.70782, "alpha":0.67009, "fx":[48.54557,53.96968,51.56289,45.81101], "fy":[-97.8985,-94.99917,-96.28529,-99.17038]}, + {"t":1.88421, "x":1.61641, "y":6.59348, "heading":2.50507, "vx":1.33817, "vy":-2.59632, "omega":1.13873, "ax":2.93539, "ay":-5.70483, "alpha":-0.0228, "fx":[49.97722,49.78987,49.88337,50.07035], "fy":[-97.01215,-97.10922,-97.06281,-96.9657]}, + {"t":1.91109, "x":1.65343, "y":6.52164, "heading":2.53568, "vx":1.41707, "vy":-2.74966, "omega":1.13812, "ax":2.92596, "ay":-5.6891, "alpha":-1.04599, "fx":[51.90259,43.10575,47.99686,56.07385], "fy":[-95.72212,-100.0447,-97.87431,-93.43849]}, + {"t":1.93797, "x":1.69258, "y":6.44567, "heading":2.56627, "vx":1.49572, "vy":-2.90258, "omega":1.11, "ax":2.89755, "ay":-5.6345, "alpha":-2.69283, "fx":[54.99167,31.4142,45.81095,64.92903], "fy":[-93.432,-103.98317,-98.73111,-87.21837]}, + {"t":1.96485, "x":1.73383, "y":6.36562, "heading":2.59611, "vx":1.5736, "vy":-3.05403, "omega":1.03762, "ax":2.82429, "ay":-5.43028, "alpha":-5.66301, "fx":[62.0892,8.57011,43.14565,78.35624], "fy":[-87.24907,-107.74498,-99.6525,-74.82361]}, + {"t":1.99173, "x":1.77715, "y":6.28157, "heading":2.624, "vx":1.64952, "vy":-3.19999, "omega":0.88541, "ax":2.84221, "ay":-4.41824, "alpha":-11.80305, "fx":[88.41565,-29.33967,40.23429,94.07034], "fy":[-44.75962,-103.09692,-100.37834,-52.37712]}, + {"t":2.01861, "x":1.82251, "y":6.19396, "heading":2.6478, "vx":1.72591, "vy":-3.31875, "omega":0.56815, "ax":2.65628, "ay":-4.20466, "alpha":-12.33669, "fx":[78.10945,-30.80219,40.04528,93.37801], "fy":[-37.6642,-100.24818,-98.78196,-49.38559]}, + {"t":2.04548, "x":1.86986, "y":6.10323, "heading":2.66307, "vx":1.79731, "vy":-3.43177, "omega":0.23655, "ax":1.25521, "ay":-3.20772, "alpha":-8.58399, "fx":[15.77745,-15.956,27.27734,58.30418], "fy":[-29.64139,-69.27059,-75.80693,-43.53044]}, + {"t":2.07236, "x":1.91863, "y":6.00983, "heading":2.66943, "vx":1.83105, "vy":-3.51799, "omega":0.00582, "ax":-0.26015, "ay":-0.15904, "alpha":-0.05173, "fx":[-4.48384,-4.60535,-4.36621,-4.24463], "fy":[-2.52429,-2.76346,-2.8862,-2.64703]}, + {"t":2.09924, "x":1.96775, "y":5.91521, "heading":2.66959, "vx":1.82406, "vy":-3.52226, "omega":0.00443, "ax":-0.11455, "ay":-0.05933, "alpha":-0.00015, "fx":[-1.94862,-1.94897,-1.94828,-1.94792], "fy":[-1.00868,-1.00938,-1.00974,-1.00904]}, + {"t":2.12612, "x":2.01674, "y":5.82052, "heading":2.6697, "vx":1.82098, "vy":-3.52386, "omega":0.00442, "ax":-0.03251, "ay":-0.0168, "alpha":0.0, "fx":[-0.55298,-0.55299,-0.55297,-0.55296], "fy":[-0.28567,-0.28568,-0.28569,-0.28567]}, + {"t":2.153, "x":2.06567, "y":5.72579, "heading":2.66982, "vx":1.82011, "vy":-3.52431, "omega":0.00442, "ax":0.02864, "ay":0.0148, "alpha":0.0, "fx":[0.48718,0.48719,0.48718,0.48718], "fy":[0.25167,0.25168,0.25168,0.25168]}, + {"t":2.17988, "x":2.11461, "y":5.63107, "heading":2.66994, "vx":1.82088, "vy":-3.52391, "omega":0.00442, "ax":0.10819, "ay":0.05604, "alpha":0.00016, "fx":[1.8405,1.84088,1.84013,1.83975], "fy":[0.95269,0.95343,0.95381,0.95307]}, + {"t":2.20676, "x":2.16359, "y":5.53637, "heading":2.67006, "vx":1.82379, "vy":-3.5224, "omega":0.00443, "ax":0.24644, "ay":0.15396, "alpha":0.05644, "fx":[4.2562,4.38867,4.12767,3.99513], "fy":[2.42141,2.68242,2.81611,2.5551]}, + {"t":2.23364, "x":2.2127, "y":5.44174, "heading":2.67018, "vx":1.83041, "vy":-3.51827, "omega":0.00595, "ax":-1.33066, "ay":3.27673, "alpha":8.8129, "fx":[-17.24202,16.04776,-28.64778,-60.69442], "fy":[30.50691,71.35757,77.20084,43.8798]}, + {"t":2.26052, "x":2.26142, "y":5.34836, "heading":2.67034, "vx":1.79464, "vy":-3.43019, "omega":0.24283, "ax":-2.64862, "ay":4.20972, "alpha":12.25578, "fx":[-75.47202,30.38917,-41.08154,-94.04495], "fy":[39.44268,100.48306,98.39216,48.10638]}, + {"t":2.2874, "x":2.3087, "y":5.25768, "heading":2.67687, "vx":1.72345, "vy":-3.31704, "omega":0.57225, "ax":-2.84236, "ay":4.38926, "alpha":11.74826, "fx":[-84.49732,29.44199,-42.45233,-95.88295], "fy":[47.08075,103.167,99.48091,48.91165]}, + {"t":2.31428, "x":2.354, "y":5.17011, "heading":2.69225, "vx":1.64705, "vy":-3.19906, "omega":0.88804, "ax":-2.80853, "ay":5.41005, "alpha":5.89864, "fx":[-57.82793,-6.49395,-45.60659,-81.16057], "fy":[89.87376,107.94538,98.56709,71.70707]}, + {"t":2.34116, "x":2.39726, "y":5.08607, "heading":2.71612, "vx":1.57156, "vy":-3.05364, "omega":1.04659, "ax":-2.89304, "ay":5.62754, "alpha":2.87526, "fx":[-52.17808,-29.90942,-47.9273,-66.82403], "fy":[94.97657,104.45159,97.72942,85.73389]}, + {"t":2.36803, "x":2.43845, "y":5.00603, "heading":2.74425, "vx":1.4938, "vy":-2.90238, "omega":1.12387, "ax":-2.92485, "ay":5.68746, "alpha":1.14766, "fx":[-50.48874,-42.22504,-49.25193,-57.03764], "fy":[96.45651,100.42767,97.25116,92.83321]}, + {"t":2.39491, "x":2.47755, "y":4.93007, "heading":2.77446, "vx":1.41518, "vy":-2.7495, "omega":1.15472, "ax":-2.93512, "ay":5.70469, "alpha":0.06295, "fx":[-49.94765,-49.51752,-49.90401,-50.3329], "fy":[97.02084,97.24435,97.05022,96.82523]}, + {"t":2.42179, "x":2.51453, "y":4.85822, "heading":2.8055, "vx":1.33628, "vy":-2.59616, "omega":1.15641, "ax":-2.93765, "ay":5.70774, "alpha":-0.67113, "fx":[-49.89727,-54.29457,-50.09942,-45.58308], "fy":[97.21544,94.80094,97.04941,99.28238]}, + {"t":2.44867, "x":2.54939, "y":4.7905, "heading":2.83658, "vx":1.25732, "vy":-2.44274, "omega":1.13837, "ax":-2.93727, "ay":5.70568, "alpha":-1.19714, "fx":[-50.09663,-57.66296,-49.97966,-42.10956], "fy":[97.22481,92.89288,97.18937,100.90084]}, + {"t":2.47555, "x":2.58212, "y":4.7269, "heading":2.86718, "vx":1.17837, "vy":-2.28938, "omega":1.1062, "ax":-2.93577, "ay":5.70182, "alpha":-1.59116, "fx":[-50.43338,-60.1682,-49.64093,-39.50373], "fy":[97.13027,91.36764,97.42572,102.02189]}, + {"t":2.50243, "x":2.61273, "y":4.66743, "heading":2.89691, "vx":1.09946, "vy":-2.13612, "omega":1.06343, "ax":-2.93382, "ay":5.69748, "alpha":-1.89703, "fx":[-50.84671,-62.10605,-49.15137,-37.50987], "fy":[96.97421,90.12235,97.7253,102.82835]}, + {"t":2.52931, "x":2.64123, "y":4.61207, "heading":2.9255, "vx":1.0206, "vy":-1.98298, "omega":1.01244, "ax":-2.93173, "ay":5.69319, "alpha":-2.14158, "fx":[-51.30012,-63.64974,-48.56102,-35.96081], "fy":[96.78146,89.0877,98.06322,103.42558]}, + {"t":2.55619, "x":2.6676, "y":4.56082, "heading":2.95271, "vx":0.9418, "vy":-1.82995, "omega":0.95487, "ax":-2.92962, "ay":5.68914, "alpha":-2.34201, "fx":[-51.7701,-64.90736,-47.90775,-34.74268], "fy":[96.56793,88.21585,98.42072,103.8781]}, + {"t":2.58307, "x":2.69186, "y":4.51369, "heading":2.97838, "vx":0.86305, "vy":-1.67703, "omega":0.89192, "ax":-2.92754, "ay":5.6854, "alpha":-2.50976, "fx":[-52.24065,-65.95004,-47.22087,-33.77509], "fy":[96.34449,87.4728,98.78364,104.22743]}, + {"t":2.60995, "x":2.714, "y":4.47067, "heading":3.00235, "vx":0.78436, "vy":-1.52421, "omega":0.82446, "ax":-2.92553, "ay":5.68198, "alpha":-2.65266, "fx":[-52.70041,-66.82675,-46.52347,-32.99941], "fy":[96.11904,86.83356,99.1414,104.50146]}, + {"t":2.63683, "x":2.73402, "y":4.43175, "heading":3.02451, "vx":0.70573, "vy":-1.37148, "omega":0.75316, "ax":-2.92361, "ay":5.67885, "alpha":-2.77619, "fx":[-53.14105,-67.57252,-45.8339,-32.37172], "fy":[95.8975,86.27926,99.48607,104.71962]}, + {"t":2.66371, "x":2.75194, "y":4.39694, "heading":3.04476, "vx":0.62714, "vy":-1.21884, "omega":0.67854, "ax":-2.92178, "ay":5.67598, "alpha":-2.88424, "fx":[-53.55633,-68.21326,-45.16687,-31.85836], "fy":[95.68454,85.79521,99.81187,104.89589]}, + {"t":2.69059, "x":2.76774, "y":4.36623, "heading":3.06299, "vx":0.54861, "vy":-1.06627, "omega":0.60101, "ax":-2.92006, "ay":5.67336, "alpha":-2.97964, "fx":[-53.94144,-68.76874,-44.53424,-31.43299], "fy":[95.48387,85.3697,100.11458,105.0406]}, + {"t":2.71746, "x":2.78143, "y":4.33962, "heading":3.07915, "vx":0.47012, "vy":-0.91378, "omega":0.52092, "ax":-2.91844, "ay":5.67094, "alpha":-3.06448, "fx":[-54.29261,-69.25436,-43.94556,-31.07465], "fy":[95.29857,84.99323,100.39122,105.16156]}, + {"t":2.74434, "x":2.79301, "y":4.3171, "heading":3.09315, "vx":0.39167, "vy":-0.76135, "omega":0.43855, "ax":-2.91693, "ay":5.66873, "alpha":-3.14031, "fx":[-54.60683,-69.68237,-43.40859,-30.76648], "fy":[95.13118,84.65794,100.6397,105.26482]}, + {"t":2.77122, "x":2.80249, "y":4.29869, "heading":3.10494, "vx":0.31327, "vy":-0.60898, "omega":0.35414, "ax":-2.91552, "ay":5.66669, "alpha":-3.2083, "fx":[-54.88166,-70.06268,-42.92963,-30.49474], "fy":[94.98386,84.35729,100.85859,105.35511]}, + {"t":2.7981, "x":2.80985, "y":4.28437, "heading":3.11446, "vx":0.2349, "vy":-0.45666, "omega":0.26791, "ax":-2.91422, "ay":5.66481, "alpha":-3.26936, "fx":[-55.11508,-70.40332,-42.51388,-30.24814], "fy":[94.85844,84.0858,101.04691,105.43619]}, + {"t":2.82498, "x":2.81511, "y":4.27414, "heading":3.12166, "vx":0.15657, "vy":-0.3044, "omega":0.18003, "ax":-2.91303, "ay":5.66309, "alpha":-3.32422, "fx":[-55.30538,-70.71085,-42.16567,-30.01741], "fy":[94.75648,83.83891,101.20395,105.51108]}, + {"t":2.85186, "x":2.81827, "y":4.268, "heading":3.1265, "vx":0.07827, "vy":-0.15218, "omega":0.09068, "ax":-2.91194, "ay":5.66152, "alpha":-3.37343, "fx":[-55.45109,-70.99059,-41.88868,-29.79488], "fy":[94.67932,83.61282,101.32917,105.58219]}, + {"t":2.87874, "x":2.81932, "y":4.26596, "heading":3.12894, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[ + {"name":"Funnel", "from":{"target":2, "targetTimestamp":2.23364, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] +} diff --git a/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH4_ALT_ALT.traj b/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH4_ALT_ALT.traj new file mode 100644 index 00000000..5d00a649 --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH4_ALT_ALT.traj @@ -0,0 +1,136 @@ +{ + "name":"A_LEFT_PATH4_ALT_ALT", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.692616224288941, "y":5.020236015319824, "heading":2.0948682307415045, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.3110252618789673, "y":7.185760498046875, "heading":2.216612130911823, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.7917816638946533, "y":6.376835346221924, "heading":0.0, "intervals":36, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":5.056673049926758, "y":5.405888557434082, "heading":1.092223810384809, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.6926162242889404 m", "val":3.692616224288941}, "y":{"exp":"5.020236015319824 m", "val":5.020236015319824}, "heading":{"exp":"2.0948682307415045 rad", "val":2.0948682307415045}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"7.185760498046875 m", "val":7.185760498046875}, "heading":{"exp":"2.216612130911823 rad", "val":2.216612130911823}, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.7917816638946533 m", "val":2.7917816638946533}, "y":{"exp":"6.376835346221924 m", "val":6.376835346221924}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":36, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"5.056673049926758 m", "val":5.056673049926758}, "y":{"exp":"5.405888557434082 m", "val":5.405888557434082}, "heading":{"exp":"1.092223810384809 rad", "val":1.092223810384809}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.42726,2.1948,3.0994], + "samples":[ + {"t":0.0, "x":3.69262, "y":5.02024, "heading":2.09487, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-4.77336, "ay":4.34029, "alpha":0.36517, "fx":[-82.80387,-80.3539,-79.60509,-82.01137], "fy":[72.03947,74.76071,75.56262,72.9455]}, + {"t":0.04325, "x":3.68815, "y":5.0243, "heading":2.09487, "vx":-0.20645, "vy":0.18772, "omega":0.01579, "ax":-4.77303, "ay":4.33999, "alpha":0.36029, "fx":[-82.77638,-80.35948,-79.62059,-81.99495], "fy":[72.05859,74.74258,75.53461,72.95195]}, + {"t":0.0865, "x":3.67476, "y":5.03647, "heading":2.09555, "vx":-0.41289, "vy":0.37543, "omega":0.03138, "ax":-4.77264, "ay":4.33963, "alpha":0.35461, "fx":[-82.74377,-80.3649,-79.63925,-81.97681], "fy":[72.08147,74.7226,75.50128,72.95832]}, + {"t":0.12975, "x":3.65244, "y":5.05677, "heading":2.09691, "vx":-0.6193, "vy":0.56312, "omega":0.04671, "ax":-4.77217, "ay":4.33921, "alpha":0.34789, "fx":[-82.70483,-80.37047,-79.66174,-81.95612], "fy":[72.10894,74.69987,75.4614,72.96497]}, + {"t":0.173, "x":3.62119, "y":5.08518, "heading":2.09893, "vx":-0.8257, "vy":0.75079, "omega":0.06176, "ax":-4.77161, "ay":4.33871, "alpha":0.33982, "fx":[-82.65783,-80.37666,-79.68899,-81.9317], "fy":[72.14215,74.67312,75.41319,72.97244]}, + {"t":0.21625, "x":3.58101, "y":5.12171, "heading":2.1016, "vx":-1.03208, "vy":0.93844, "omega":0.07646, "ax":-4.77093, "ay":4.33809, "alpha":0.32994, "fx":[-82.60029,-80.3841,-79.72234,-81.90188], "fy":[72.18278,74.64053,75.35412,72.98148]}, + {"t":0.2595, "x":3.53191, "y":5.16636, "heading":2.10491, "vx":-1.23842, "vy":1.12606, "omega":0.09073, "ax":-4.77007, "ay":4.33732, "alpha":0.31759, "fx":[-82.52847,-80.39377,-79.76384,-81.86414], "fy":[72.23331,74.59939,75.28035,72.99318]}, + {"t":0.30275, "x":3.47389, "y":5.21912, "heading":2.10883, "vx":-1.44473, "vy":1.31366, "omega":0.10446, "ax":-4.76896, "ay":4.33632, "alpha":0.3017, "fx":[-82.43651,-80.40713,-79.81665,-81.81452], "fy":[72.29765,74.54544,75.18582,73.0093]}, + {"t":0.346, "x":3.40694, "y":5.27999, "heading":2.11335, "vx":-1.65099, "vy":1.5012, "omega":0.11751, "ax":-4.76748, "ay":4.33498, "alpha":0.28048, "fx":[-82.31463,-80.4266,-79.88606,-81.7464], "fy":[72.38226,74.47165,75.06042,73.03267]}, + {"t":0.38925, "x":3.33108, "y":5.34897, "heading":2.11843, "vx":-1.85718, "vy":1.68869, "omega":0.12964, "ax":-4.76538, "ay":4.33309, "alpha":0.25074, "fx":[-82.14522,-80.45644,-79.98159,-81.64782], "fy":[72.4987,74.3654,74.88582,73.06841]}, + {"t":0.4325, "x":3.2463, "y":5.42606, "heading":2.12404, "vx":-2.06329, "vy":1.8761, "omega":0.14049, "ax":-4.7622, "ay":4.33022, "alpha":0.20608, "fx":[-81.89306,-80.50494,-80.1221,-81.49469], "fy":[72.66984,74.20164,74.62514,73.12662]}, + {"t":0.47575, "x":3.15261, "y":5.51125, "heading":2.13011, "vx":-2.26926, "vy":2.06338, "omega":0.1494, "ax":-4.75682, "ay":4.32536, "alpha":0.13158, "fx":[-81.47614,-80.59075,-80.35127,-81.23019], "fy":[72.94801,73.92248,74.19154,73.23063]}, + {"t":0.519, "x":3.05001, "y":5.60454, "heading":2.13658, "vx":-2.47499, "vy":2.25046, "omega":0.15509, "ax":-4.74572, "ay":4.31535, "alpha":-0.0174, "fx":[-80.64964,-80.76623,-80.79726,-80.68055], "fy":[73.48469,73.35701,73.32106,73.44898]}, + {"t":0.56226, "x":2.93853, "y":5.70591, "heading":2.14328, "vx":-2.68024, "vy":2.4371, "omega":0.15434, "ax":-4.71008, "ay":4.28318, "alpha":-0.46025, "fx":[-78.21717,-81.25126,-82.05793,-78.9421], "fy":[74.96378,71.68837,70.66649,74.10427]}, + {"t":0.60551, "x":2.8182, "y":5.81532, "heading":2.14996, "vx":-2.88396, "vy":2.62235, "omega":0.13443, "ax":-1.2157, "ay":1.10429, "alpha":-3.10111, "fx":[-17.91854,-31.3387,-23.99025,-9.46752], "fy":[30.0091,20.53234,7.30622,17.28692]}, + {"t":0.64876, "x":2.69233, "y":5.92977, "heading":2.15577, "vx":-2.93654, "vy":2.67011, "omega":0.00031, "ax":-0.00062, "ay":0.00028, "alpha":-0.00081, "fx":[-0.00992,-0.01341,-0.0111,-0.0076], "fy":[0.00772,0.0054,0.00191,0.00422]}, + {"t":0.69201, "x":2.56532, "y":6.04526, "heading":2.15579, "vx":-2.93656, "vy":2.67012, "omega":0.00027, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[-0.00001,-0.00001,-0.00001,-0.00001], "fy":[-0.00001,-0.00001,-0.00001,-0.00001]}, + {"t":0.73526, "x":2.43832, "y":6.16074, "heading":2.1558, "vx":-2.93656, "vy":2.67012, "omega":0.00027, "ax":0.00061, "ay":-0.00029, "alpha":0.00081, "fx":[0.00987,0.01336,0.01104,0.00755], "fy":[-0.00777,-0.00546,-0.00197,-0.00428]}, + {"t":0.77851, "x":2.31131, "y":6.27622, "heading":2.15581, "vx":-2.93654, "vy":2.67011, "omega":0.00031, "ax":1.21564, "ay":-1.10425, "alpha":3.09988, "fx":[17.98156,31.35145,23.92319,9.45426], "fy":[-30.01053,-20.4674,-7.29763,-17.35634]}, + {"t":0.82176, "x":2.18544, "y":6.39067, "heading":2.15582, "vx":-2.88396, "vy":2.62235, "omega":0.13438, "ax":4.71011, "ay":-4.2832, "alpha":0.4563, "fx":[78.24912,81.26521,82.02797,78.92834], "fy":[-74.9311,-71.67191,-70.70106,-74.12022]}, + {"t":0.86501, "x":2.06511, "y":6.50009, "heading":2.16164, "vx":-2.68025, "vy":2.4371, "omega":0.15411, "ax":4.74573, "ay":-4.31535, "alpha":0.01614, "fx":[80.65607,80.76491,80.79097,80.68202], "fy":[-73.47768,-73.35843,-73.32808,-73.44753]}, + {"t":0.90826, "x":1.95363, "y":6.60146, "heading":2.1683, "vx":-2.47499, "vy":2.25046, "omega":0.15481, "ax":4.75682, "ay":-4.32536, "alpha":-0.13197, "fx":[81.4654,80.56831,80.36251,81.25225], "fy":[-72.95981,-73.94707,-74.17961,-73.20607]}, + {"t":0.95151, "x":1.85104, "y":6.69474, "heading":2.175, "vx":-2.26926, "vy":2.06338, "omega":0.1491, "ax":4.7622, "ay":-4.33022, "alpha":-0.20605, "fx":[81.86727,80.45992,80.14932,81.5384], "fy":[-72.69857,-74.25068,-74.59625,-73.0777]}, + {"t":0.99476, "x":1.75734, "y":6.77993, "heading":2.18145, "vx":-2.06329, "vy":1.8761, "omega":0.14019, "ax":4.76538, "ay":-4.33309, "alpha":-0.25046, "fx":[82.10564,80.38905,80.0237,81.7128], "fy":[-72.54312,-74.43851,-74.8412,-72.9955]}, + {"t":1.03801, "x":1.67256, "y":6.85702, "heading":2.18751, "vx":-1.85718, "vy":1.68869, "omega":0.12936, "ax":4.76748, "ay":-4.33498, "alpha":-0.28003, "fx":[82.26239,80.33786,79.94201,81.83158], "fy":[-72.44118,-74.56765,-75.00125,-72.93696]}, + {"t":1.08126, "x":1.5967, "y":6.92601, "heading":2.1931, "vx":-1.65099, "vy":1.5012, "omega":0.11725, "ax":4.76897, "ay":-4.33632, "alpha":-0.30113, "fx":[82.37273,80.29854,79.88529,81.91843], "fy":[-72.36984,-74.6627,-75.11332,-72.89242]}, + {"t":1.12451, "x":1.52975, "y":6.98688, "heading":2.19817, "vx":-1.44473, "vy":1.31366, "omega":0.10423, "ax":4.77007, "ay":-4.33732, "alpha":-0.31695, "fx":[82.45429,80.2671,79.84396,81.98506], "fy":[-72.31749,-74.73597,-75.1958,-72.85708]}, + {"t":1.16776, "x":1.47173, "y":7.03964, "heading":2.20268, "vx":-1.23842, "vy":1.12607, "omega":0.09052, "ax":4.77093, "ay":-4.3381, "alpha":-0.32923, "fx":[82.51691,80.24134,79.81267,82.03791], "fy":[-72.2776,-74.79429,-75.25888,-72.82827]}, + {"t":1.21101, "x":1.42263, "y":7.08428, "heading":2.2066, "vx":-1.03208, "vy":0.93844, "omega":0.07628, "ax":4.77162, "ay":-4.33871, "alpha":-0.33906, "fx":[82.56647,80.21992,79.78819,82.08082], "fy":[-72.24622,-74.84177,-75.30866,-72.8044]}, + {"t":1.25426, "x":1.38245, "y":7.12081, "heading":2.2099, "vx":-0.8257, "vy":0.75079, "omega":0.06161, "ax":4.77218, "ay":-4.33922, "alpha":-0.34709, "fx":[82.60675,80.202,79.76843,82.11621], "fy":[-72.22081,-74.88101,-75.34903,-72.78449]}, + {"t":1.29751, "x":1.3512, "y":7.14923, "heading":2.21256, "vx":-0.6193, "vy":0.56312, "omega":0.0466, "ax":4.77264, "ay":-4.33964, "alpha":-0.35378, "fx":[82.64027,80.187,79.75202,82.1457], "fy":[-72.19966,-74.91375,-75.38256,-72.76786]}, + {"t":1.34076, "x":1.32888, "y":7.16952, "heading":2.21458, "vx":-0.41289, "vy":0.37543, "omega":0.0313, "ax":4.77303, "ay":-4.33999, "alpha":-0.35943, "fx":[82.66877,80.17455,79.73797,82.17038], "fy":[-72.18158,-74.94119,-75.41107,-72.75406]}, + {"t":1.38401, "x":1.31549, "y":7.1817, "heading":2.21593, "vx":-0.20645, "vy":0.18772, "omega":0.01576, "ax":4.77337, "ay":-4.34029, "alpha":-0.36428, "fx":[82.6935,80.16436,79.7256,82.19104], "fy":[-72.16572,-74.96417,-75.43584,-72.74277]}, + {"t":1.42726, "x":1.31103, "y":7.18576, "heading":2.21661, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.69543, "ay":-2.72937, "alpha":-4.29178, "fx":[108.41847,92.65459,84.41152,102.02591], "fy":[-16.62657,-58.6035,-70.08158,-40.39136]}, + {"t":1.45468, "x":1.31317, "y":7.18474, "heading":2.21661, "vx":0.15612, "vy":-0.07482, "omega":-0.11765, "ax":5.69903, "ay":-2.73025, "alpha":-4.22534, "fx":[108.33022,92.79401,84.64533,101.98581], "fy":[-17.13776,-58.36409,-69.78708,-40.47396]}, + {"t":1.48209, "x":1.31959, "y":7.18166, "heading":2.21339, "vx":0.31235, "vy":-0.14966, "omega":-0.23347, "ax":5.70306, "ay":-2.73123, "alpha":-4.14917, "fx":[108.22999,93.01099,84.87589,101.91296], "fy":[-17.70283,-57.99729,-69.49303,-40.63661]}, + {"t":1.5095, "x":1.33029, "y":7.17653, "heading":2.20699, "vx":0.46868, "vy":-0.22453, "omega":-0.34721, "ax":5.70753, "ay":-2.73233, "alpha":-4.06262, "fx":[108.11548,93.3003,85.11039,101.80793], "fy":[-18.32944,-57.50807,-69.19043,-40.87639]}, + {"t":1.53691, "x":1.34528, "y":7.16935, "heading":2.19747, "vx":0.62513, "vy":-0.29943, "omega":-0.45857, "ax":5.71245, "ay":-2.73354, "alpha":-3.96487, "fx":[107.98364,93.65588,85.35768,101.67129], "fy":[-19.02771,-56.90185,-68.86783,-41.18987]}, + {"t":1.56432, "x":1.36457, "y":7.16011, "heading":2.1849, "vx":0.78172, "vy":-0.37436, "omega":-0.56726, "ax":5.71781, "ay":-2.7349, "alpha":-3.85485, "fx":[107.83043,94.07065,85.62866,101.50367], "fy":[-19.81059,-56.18516,-68.51082,-41.57297]}, + {"t":1.59174, "x":1.38814, "y":7.14882, "heading":2.16935, "vx":0.93846, "vy":-0.44933, "omega":-0.67293, "ax":5.72363, "ay":-2.73642, "alpha":-3.73108, "fx":[107.65052,94.53626,85.93674,101.30588], "fy":[-20.69435,-55.36625,-68.10121,-42.0208]}, + {"t":1.61915, "x":1.41602, "y":7.13548, "heading":2.1509, "vx":1.09536, "vy":-0.52434, "omega":-0.77521, "ax":5.72992, "ay":-2.73812, "alpha":-3.59156, "fx":[107.43688,95.04284,86.29839,101.07897], "fy":[-21.69934,-54.45595,-67.61591,-42.52744]}, + {"t":1.64656, "x":1.4482, "y":7.12008, "heading":2.12965, "vx":1.25243, "vy":-0.5994, "omega":-0.87366, "ax":5.73668, "ay":-2.74006, "alpha":-3.43343, "fx":[107.17998,95.57876,86.73401,100.82449], "fy":[-22.85115,-53.46868,-67.02526,-43.08557]}, + {"t":1.67397, "x":1.48468, "y":7.10262, "heading":2.1057, "vx":1.40968, "vy":-0.67451, "omega":-0.96778, "ax":5.74393, "ay":-2.7423, "alpha":-3.25264, "fx":[106.86681,96.1303,87.26897,100.54466], "fy":[-24.18247,-52.42361,-66.29056,-43.68603]}, + {"t":1.70138, "x":1.52548, "y":7.0831, "heading":2.07918, "vx":1.56713, "vy":-0.74968, "omega":-1.05694, "ax":5.75169, "ay":-2.74489, "alpha":-3.0433, "fx":[106.47904,96.68136,87.93512,100.24277], "fy":[-25.73593,-51.34606,-65.36033,-44.31697]}, + {"t":1.7288, "x":1.5706, "y":7.06152, "heading":2.0502, "vx":1.7248, "vy":-0.82492, "omega":-1.14036, "ax":5.75994, "ay":-2.74792, "alpha":-2.79678, "fx":[105.99013,97.21305,88.7727,99.92371], "fy":[-27.56871,-50.26926,-64.16442,-44.96265]}, + {"t":1.75621, "x":1.62005, "y":7.03787, "heading":2.01894, "vx":1.88269, "vy":-0.90025, "omega":-1.21703, "ax":5.76863, "ay":-2.7514, "alpha":-2.50027, "fx":[105.36013,97.70304,89.83301,99.59491], "fy":[-29.76014,-49.23646,-62.60453,-45.60129]}, + {"t":1.78362, "x":1.67382, "y":7.01216, "heading":1.98558, "vx":2.04082, "vy":-0.97567, "omega":-1.28556, "ax":5.77758, "ay":-2.75531, "alpha":-2.13442, "fx":[104.52614,98.12456,91.1816,99.26787], "fy":[-32.42456,-48.30381,-60.53834,-46.20116]}, + {"t":1.81103, "x":1.73194, "y":6.98438, "heading":1.95034, "vx":2.1992, "vy":-1.0512, "omega":-1.34407, "ax":5.78626, "ay":-2.75936, "alpha":-1.66942, "fx":[103.38364,98.44448,92.90161,98.96108], "fy":[-35.73416,-47.54423,-57.75201,-46.71312]}, + {"t":1.83844, "x":1.7944, "y":6.95453, "heading":1.9135, "vx":2.35781, "vy":-1.12684, "omega":-1.38983, "ax":5.79327, "ay":-2.76282, "alpha":-1.05778, "fx":[101.74694,98.61991,95.09473,98.7058], "fy":[-39.96086,-47.05325,-53.91049,-47.0545]}, + {"t":1.86586, "x":1.86121, "y":6.9226, "heading":1.8754, "vx":2.51662, "vy":-1.20257, "omega":-1.41883, "ax":5.79492, "ay":-2.76385, "alpha":-0.22086, "fx":[99.25811,98.59174,97.87045,98.55931], "fy":[-45.55661,-46.95787,-48.46444,-47.07016]}, + {"t":1.89327, "x":1.93237, "y":6.8886, "heading":1.83651, "vx":2.67547, "vy":-1.27834, "omega":-1.42488, "ax":5.78136, "ay":-2.75773, "alpha":0.9787, "fx":[95.15429,98.27241,101.29051,98.63963], "fy":[-53.30858,-47.43081,-40.47275,-46.42036]}, + {"t":1.92068, "x":2.00788, "y":6.85252, "heading":1.79745, "vx":2.83395, "vy":-1.35393, "omega":-1.39806, "ax":5.72492, "ay":-2.7302, "alpha":2.79551, "fx":[87.6067,97.52225,105.15132,99.23704], "fy":[-64.59925,-48.71264,-28.28642,-44.16141]}, + {"t":1.94809, "x":2.08772, "y":6.81438, "heading":1.75912, "vx":2.99088, "vy":-1.42877, "omega":-1.32143, "ax":5.5469, "ay":-2.61628, "alpha":5.73283, "fx":[71.80278,96.10728,108.23559,101.2593], "fy":[-81.33589,-51.1353,-9.2585,-36.27903]}, + {"t":1.97551, "x":2.17179, "y":6.77423, "heading":1.7229, "vx":3.14293, "vy":-1.50049, "omega":-1.16428, "ax":5.03645, "ay":-1.84246, "alpha":11.39546, "fx":[40.70594,93.79304,107.0976,101.07798], "fy":[-100.00617,-54.81332,15.99903,13.4616]}, + {"t":2.00292, "x":2.25983, "y":6.73241, "heading":1.69099, "vx":3.28099, "vy":-1.551, "omega":-0.8519, "ax":4.82966, "ay":-1.68353, "alpha":12.591, "fx":[36.12063,92.14167,106.34395,93.99814], "fy":[-100.71097,-56.3884,15.91466,26.63934]}, + {"t":2.03033, "x":2.35159, "y":6.68926, "heading":1.66763, "vx":3.41338, "vy":-1.59714, "omega":-0.50676, "ax":4.62113, "ay":-1.78364, "alpha":12.43957, "fx":[34.60181,89.65226,104.42953,85.733], "fy":[-98.2217,-56.92656,13.0275,20.76373]}, + {"t":2.05774, "x":2.44689, "y":6.64481, "heading":1.65374, "vx":3.54006, "vy":-1.64604, "omega":-0.16576, "ax":1.76404, "ay":-1.58193, "alpha":5.81708, "fx":[15.18929,43.60969,46.4284,14.79605], "fy":[-45.69691,-38.2842,-9.29478,-14.35664]}, + {"t":2.08515, "x":2.54459, "y":6.59909, "heading":1.6492, "vx":3.58841, "vy":-1.6894, "omega":-0.0063, "ax":-0.15503, "ay":-0.35066, "alpha":0.02374, "fx":[-2.69363,-2.57066,-2.58043,-2.70362], "fy":[-6.03072,-6.02131,-5.89865,-5.90797]}, + {"t":2.11257, "x":2.6429, "y":6.55265, "heading":1.64902, "vx":3.58416, "vy":-1.69901, "omega":-0.00565, "ax":-0.07373, "ay":-0.15537, "alpha":0.0001, "fx":[-1.25433,-1.25381,-1.25386,-1.25437], "fy":[-2.64315,-2.64311,-2.64259,-2.64263]}, + {"t":2.13998, "x":2.74112, "y":6.50602, "heading":1.64887, "vx":3.58214, "vy":-1.70327, "omega":-0.00565, "ax":-0.03304, "ay":-0.06944, "alpha":0.00001, "fx":[-0.56205,-0.56199,-0.562,-0.56206], "fy":[-1.18126,-1.18126,-1.1812,-1.18121]}, + {"t":2.16739, "x":2.8393, "y":6.4593, "heading":1.64872, "vx":3.58124, "vy":-1.70518, "omega":-0.00565, "ax":-0.01471, "ay":-0.03088, "alpha":0.0, "fx":[-0.25014,-0.25012,-0.25012,-0.25014], "fy":[-0.52519,-0.52519,-0.52518,-0.52518]}, + {"t":2.1948, "x":2.93747, "y":6.41255, "heading":1.64856, "vx":3.58083, "vy":-1.70602, "omega":-0.00565, "ax":-0.00637, "ay":-0.01338, "alpha":0.0, "fx":[-0.10841,-0.10841,-0.10841,-0.10841], "fy":[-0.22752,-0.22752,-0.22753,-0.22753]}, + {"t":2.22221, "x":3.03562, "y":6.36577, "heading":1.64841, "vx":3.58066, "vy":-1.70639, "omega":-0.00565, "ax":-0.00239, "ay":-0.005, "alpha":0.0, "fx":[-0.04057,-0.04058,-0.04058,-0.04057], "fy":[-0.08513,-0.08513,-0.08514,-0.08514]}, + {"t":2.24963, "x":3.13378, "y":6.319, "heading":1.64825, "vx":3.58059, "vy":-1.70653, "omega":-0.00565, "ax":-0.00002, "ay":-0.00005, "alpha":0.0, "fx":[-0.00039,-0.00041,-0.00041,-0.00039], "fy":[-0.00083,-0.00083,-0.00084,-0.00084]}, + {"t":2.27704, "x":3.23193, "y":6.27222, "heading":1.6481, "vx":3.58059, "vy":-1.70653, "omega":-0.00565, "ax":0.00232, "ay":0.00487, "alpha":0.0, "fx":[0.03951,0.03949,0.03949,0.03951], "fy":[0.08291,0.0829,0.08289,0.08289]}, + {"t":2.30445, "x":3.33008, "y":6.22544, "heading":1.64794, "vx":3.58066, "vy":-1.70639, "omega":-0.00565, "ax":0.00625, "ay":0.01312, "alpha":-0.00001, "fx":[0.10635,0.10633,0.10633,0.10636], "fy":[0.2232,0.2232,0.22317,0.22317]}, + {"t":2.33186, "x":3.42824, "y":6.17867, "heading":1.64779, "vx":3.58083, "vy":-1.70604, "omega":-0.00565, "ax":0.01444, "ay":0.03032, "alpha":-0.00001, "fx":[0.24567,0.24563,0.24563,0.24567], "fy":[0.5158,0.5158,0.51575,0.51576]}, + {"t":2.35927, "x":3.5264, "y":6.13191, "heading":1.64763, "vx":3.58122, "vy":-1.7052, "omega":-0.00565, "ax":0.03246, "ay":0.06822, "alpha":-0.00002, "fx":[0.55213,0.55205,0.55206,0.55214], "fy":[1.16038,1.16037,1.16029,1.1603]}, + {"t":2.38669, "x":3.62458, "y":6.0852, "heading":1.64748, "vx":3.58211, "vy":-1.70333, "omega":-0.00565, "ax":0.07244, "ay":0.15263, "alpha":-0.00009, "fx":[1.23234,1.23185,1.23189,1.23238], "fy":[2.59649,2.59646,2.59597,2.596]}, + {"t":2.4141, "x":3.7228, "y":6.03856, "heading":1.64732, "vx":3.5841, "vy":-1.69915, "omega":-0.00565, "ax":0.15343, "ay":0.344, "alpha":-0.02029, "fx":[2.65818,2.55313,2.56121,2.66651], "fy":[5.90767,5.8998,5.79493,5.80271]}, + {"t":2.44151, "x":3.82111, "y":5.99211, "heading":1.64717, "vx":3.5883, "vy":-1.68972, "omega":-0.00621, "ax":-1.55776, "ay":1.50469, "alpha":-5.2689, "fx":[-13.08145,-39.15723,-41.26543,-12.4841], "fy":[42.07515,36.23238,10.00466,14.06494]}, + {"t":2.46892, "x":3.91888, "y":5.94636, "heading":1.647, "vx":3.5456, "vy":-1.64847, "omega":-0.15064, "ax":-4.61299, "ay":1.78453, "alpha":-12.52758, "fx":[-34.14673,-89.08014,-104.5332,-86.10274], "fy":[98.216,57.70535,-11.86425,-22.6396]}, + {"t":2.49633, "x":4.01434, "y":5.90184, "heading":1.64287, "vx":3.41915, "vy":-1.59956, "omega":-0.49405, "ax":-4.80874, "ay":1.69118, "alpha":-12.86503, "fx":[-35.24099,-90.94095,-106.74446,-94.25492], "fy":[100.90695,58.26484,-13.15086,-30.95476]}, + {"t":2.52375, "x":4.10626, "y":5.85863, "heading":1.62932, "vx":3.28733, "vy":-1.5532, "omega":-0.84671, "ax":-5.07727, "ay":1.96185, "alpha":-11.17081, "fx":[-42.65255,-91.79888,-107.97237,-103.02763], "fy":[99.06016,58.04584,-8.73312,-14.89081]}, + {"t":2.55116, "x":4.19447, "y":5.81679, "heading":1.60611, "vx":3.14816, "vy":-1.49942, "omega":-1.15292, "ax":-5.58582, "ay":2.63144, "alpha":-5.30741, "fx":[-74.8056,-94.20042,-107.522,-103.52493], "fy":[78.50076,54.53275,15.85043,30.15597]}, + {"t":2.57857, "x":4.27867, "y":5.77668, "heading":1.57451, "vx":2.99504, "vy":-1.42729, "omega":-1.29841, "ax":-5.73822, "ay":2.73357, "alpha":-2.47919, "fx":[-89.27474,-96.06781,-104.1425,-100.93701], "fy":[62.23397,51.5049,31.94011,40.31014]}, + {"t":2.60598, "x":4.35861, "y":5.73858, "heading":1.53892, "vx":2.83774, "vy":-1.35235, "omega":-1.36637, "ax":-5.78466, "ay":2.75721, "alpha":-0.81344, "fx":[-95.90386,-97.60116,-100.68927,-99.38729], "fy":[51.94385,48.79656,42.00073,44.85622]}, + {"t":2.6334, "x":4.43422, "y":5.70255, "heading":1.50146, "vx":2.67917, "vy":-1.27677, "omega":-1.38867, "ax":-5.79581, "ay":2.76255, "alpha":0.27057, "fx":[-99.35763,-98.92508,-97.79038,-98.26687], "fy":[45.36644,46.2657,48.63213,47.69632]}, + {"t":2.66081, "x":4.50549, "y":5.66859, "heading":1.4634, "vx":2.52029, "vy":-1.20104, "omega":-1.38125, "ax":-5.79449, "ay":2.76189, "alpha":1.03192, "fx":[-101.34719,-100.09318,-95.46139,-97.34886], "fy":[41.0188,43.86015,53.2341,49.80293]}, + {"t":2.68822, "x":4.5724, "y":5.6367, "heading":1.42553, "vx":2.36146, "vy":-1.12534, "omega":-1.35296, "ax":-5.78867, "ay":2.75892, "alpha":1.59912, "fx":[-102.57626,-101.13044,-93.60499,-96.54274], "fy":[38.06768,41.56724,56.5596,51.51927]}, + {"t":2.71563, "x":4.63496, "y":5.60689, "heading":1.38845, "vx":2.20278, "vy":-1.04971, "omega":-1.30913, "ax":-5.78132, "ay":2.75506, "alpha":2.04127, "fx":[-103.37187,-102.05077,-92.12309,-95.8084], "fy":[36.03204,39.38999,59.03589,52.99288]}, + {"t":2.74304, "x":4.69317, "y":5.57915, "heading":1.35256, "vx":2.0443, "vy":-0.97419, "omega":-1.25317, "ax":-5.77361, "ay":2.75095, "alpha":2.39803, "fx":[-103.90235,-102.86414,-90.93646,-95.12686], "fy":[34.61918,37.33626,60.92025,54.29588]}, + {"t":2.77046, "x":4.74704, "y":5.55348, "heading":1.31821, "vx":1.88603, "vy":-0.89878, "omega":-1.18744, "ax":-5.76603, "ay":2.74694, "alpha":2.69342, "fx":[-104.26184,-103.57938,-89.98384,-94.48896], "fy":[33.64142,35.4139,62.37659,55.46687]}, + {"t":2.79787, "x":4.79657, "y":5.52987, "heading":1.28566, "vx":1.72797, "vy":-0.82348, "omega":-1.1136, "ax":-5.75877, "ay":2.7432, "alpha":2.94268, "fx":[-104.50677,-104.20514,-89.21774,-93.89045], "fy":[32.97271,33.62853,63.51491,56.52801]}, + {"t":2.82528, "x":4.84177, "y":5.50833, "heading":1.25513, "vx":1.57011, "vy":-0.74828, "omega":-1.03294, "ax":-5.75191, "ay":2.73981, "alpha":3.15597, "fx":[-104.67306,-104.75008,-88.60063,-93.32964], "fy":[32.52496,31.9829,64.41259,57.49284]}, + {"t":2.85269, "x":4.88265, "y":5.48885, "heading":1.22682, "vx":1.41244, "vy":-0.67318, "omega":-0.94643, "ax":-5.74548, "ay":2.73679, "alpha":3.34036, "fx":[-104.78477,-105.22273,-88.10214,-92.80615], "fy":[32.23448,30.47685,65.1265,58.37007]}, + {"t":2.8801, "x":4.91921, "y":5.47142, "heading":1.20087, "vx":1.25495, "vy":-0.59816, "omega":-0.85486, "ax":-5.73948, "ay":2.73413, "alpha":3.50104, "fx":[-104.85875,-105.63127,-87.69711,-92.32034], "fy":[32.0539,29.10777,65.70008,59.16562]}, + {"t":2.90752, "x":4.95146, "y":5.45605, "heading":1.17744, "vx":1.09761, "vy":-0.52321, "omega":-0.75889, "ax":-5.7339, "ay":2.73181, "alpha":3.64197, "fx":[-104.90732,-105.98337,-87.36426,-91.87292], "fy":[31.94712,27.8711,66.16762,59.88372]}, + {"t":2.93493, "x":4.97939, "y":5.44274, "heading":1.15664, "vx":0.94044, "vy":-0.44832, "omega":-0.65906, "ax":-5.72872, "ay":2.72979, "alpha":3.76631, "fx":[-104.93975,-106.28605,-87.08537,-91.46472], "fy":[31.8861,26.76092,66.55695,60.5275]}, + {"t":2.96234, "x":5.00302, "y":5.43147, "heading":1.13857, "vx":0.7834, "vy":-0.37349, "omega":-0.55581, "ax":-5.72394, "ay":2.728, "alpha":3.87665, "fx":[-104.96323,-106.54556,-86.84464,-91.09666], "fy":[31.84867,25.7706,66.89109,61.09938]}, + {"t":2.98975, "x":5.02234, "y":5.42226, "heading":1.12333, "vx":0.6265, "vy":-0.29871, "omega":-0.44955, "ax":-5.71951, "ay":2.7264, "alpha":3.97517, "fx":[-104.98348,-106.76739,-86.62836,-90.76964], "fy":[31.8171,24.8932,67.18934,61.6012]}, + {"t":3.01716, "x":5.03736, "y":5.4151, "heading":1.11101, "vx":0.46971, "vy":-0.22398, "omega":-0.34058, "ax":-5.71542, "ay":2.72493, "alpha":4.06371, "fx":[-105.00507,-106.95629,-86.42461,-90.48453], "fy":[31.77704,24.12201,67.468,62.0344]}, + {"t":3.04458, "x":5.04809, "y":5.40998, "heading":1.10167, "vx":0.31304, "vy":-0.14928, "omega":-0.22919, "ax":-5.71164, "ay":2.72357, "alpha":4.14385, "fx":[-105.03173,-107.11622,-86.22311,-90.2422], "fy":[31.71675,23.45084,67.74073,62.4]}, + {"t":3.07199, "x":5.05453, "y":5.40691, "heading":1.09539, "vx":0.15647, "vy":-0.07462, "omega":-0.11559, "ax":-5.70814, "ay":2.72225, "alpha":4.2169, "fx":[-105.06645,-107.25048,-86.0151,-90.04352], "fy":[31.6266,22.87437,68.0189,62.69867]}, + {"t":3.0994, "x":5.05667, "y":5.40589, "heading":1.09222, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[ + {"name":"Funnel", "from":{"target":2, "targetTimestamp":2.1948, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] +} diff --git a/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH_ALT3.traj b/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH_ALT3.traj new file mode 100644 index 00000000..a2dddcdd --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH_ALT3.traj @@ -0,0 +1,130 @@ +{ + "name":"A_LEFT_PATH_ALT3", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.999176502227783, "y":5.206205368041992, "heading":2.1010083691287966, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.3110252618789673, "y":7.185760498046875, "heading":2.216612130911823, "intervals":34, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.9979817867279053, "y":5.904665946960449, "heading":0.0, "intervals":40, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":2.819322109222412, "y":4.265955924987793, "heading":3.1289351796122347, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.999176502227783 m", "val":3.999176502227783}, "y":{"exp":"5.206205368041992 m", "val":5.206205368041992}, "heading":{"exp":"2.1010083691287966 rad", "val":2.1010083691287966}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"7.185760498046875 m", "val":7.185760498046875}, "heading":{"exp":"2.216612130911823 rad", "val":2.216612130911823}, "intervals":34, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.9979817867279053 m", "val":1.9979817867279053}, "y":{"exp":"5.904665946960449 m", "val":5.904665946960449}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":40, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"2.819322109222412 m", "val":2.819322109222412}, "y":{"exp":"4.265955924987793 m", "val":4.265955924987793}, "heading":{"exp":"3.1289351796122347 rad", "val":3.1289351796122347}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.45694,2.14306,2.90835], + "samples":[ + {"t":0.0, "x":3.99918, "y":5.20621, "heading":2.10101, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.19496, "ay":3.82555, "alpha":0.39071, "fx":[-89.94595,-87.72831,-86.79243,-88.99263], "fy":[62.89889,65.95408,67.18673,64.24646]}, + {"t":0.04415, "x":3.99411, "y":5.20993, "heading":2.10101, "vx":-0.22936, "vy":0.1689, "omega":0.01725, "ax":-5.1946, "ay":3.82528, "alpha":0.38384, "fx":[-89.91168,-87.73324,-86.81393,-88.97553], "fy":[62.93309,65.93326,67.14531,64.25605]}, + {"t":0.0883, "x":3.97892, "y":5.22112, "heading":2.10177, "vx":-0.45869, "vy":0.33778, "omega":0.0342, "ax":-5.19416, "ay":3.82496, "alpha":0.37576, "fx":[-89.87093,-87.73784,-86.8397,-88.95649], "fy":[62.97391,65.91036,67.09591,64.26579]}, + {"t":0.13245, "x":3.95361, "y":5.23976, "heading":2.10328, "vx":-0.68801, "vy":0.50665, "omega":0.05079, "ax":-5.19365, "ay":3.82458, "alpha":0.36611, "fx":[-89.82196,-87.74247,-86.8708,-88.93454], "fy":[63.02302,65.88419,67.03642,64.27632]}, + {"t":0.1766, "x":3.91817, "y":5.26585, "heading":2.10552, "vx":-0.91731, "vy":0.6755, "omega":0.06695, "ax":-5.19302, "ay":3.82411, "alpha":0.35438, "fx":[-89.76229,-87.74764,-86.90873,-88.90824], "fy":[63.08283,65.85302,66.96386,64.28854]}, + {"t":0.22075, "x":3.87261, "y":5.29941, "heading":2.10848, "vx":-1.14658, "vy":0.84434, "omega":0.0826, "ax":-5.19223, "ay":3.82353, "alpha":0.33984, "fx":[-89.68826,-87.75407,-86.95571,-88.87549], "fy":[63.15689,65.81433,66.87378,64.3038]}, + {"t":0.2649, "x":3.81693, "y":5.34041, "heading":2.11212, "vx":-1.37582, "vy":1.01314, "omega":0.0976, "ax":-5.19123, "ay":3.82279, "alpha":0.32132, "fx":[-89.59419,-87.7629,-87.01517,-88.83305], "fy":[63.25069,65.76426,66.75929,64.32412]}, + {"t":0.30905, "x":3.75113, "y":5.38886, "heading":2.11643, "vx":-1.60501, "vy":1.18192, "omega":0.11178, "ax":-5.1899, "ay":3.82181, "alpha":0.29693, "fx":[-89.47081,-87.77588,-87.09267,-88.77563], "fy":[63.3731,65.69657,66.6091,64.35282]}, + {"t":0.3532, "x":3.67521, "y":5.44477, "heading":2.12137, "vx":-1.83414, "vy":1.35065, "omega":0.12489, "ax":-5.18806, "ay":3.82045, "alpha":0.26338, "fx":[-89.30191,-87.79606,-87.19795,-88.69391], "fy":[63.53962,65.60043,66.40339,64.39564]}, + {"t":0.39735, "x":3.58918, "y":5.50812, "heading":2.12688, "vx":-2.06319, "vy":1.51932, "omega":0.13652, "ax":-5.18534, "ay":3.81844, "alpha":0.21432, "fx":[-89.05627,-87.82908,-87.34962,-88.5699], "fy":[63.77976,65.45524,66.1038,64.46357]}, + {"t":0.4415, "x":3.49304, "y":5.57892, "heading":2.13291, "vx":-2.29212, "vy":1.6879, "omega":0.14598, "ax":-5.18092, "ay":3.81517, "alpha":0.13577, "fx":[-88.66516,-87.88696,-87.58829,-88.36357], "fy":[64.15767,65.2163,65.62522,64.58079]}, + {"t":0.48565, "x":3.38679, "y":5.65716, "heading":2.13935, "vx":-2.52085, "vy":1.85634, "omega":0.15198, "ax":-5.17248, "ay":3.80893, "alpha":-0.01024, "fx":[-87.94194,-88.00063,-88.02274,-87.96403], "fy":[64.84395,64.76463,64.73368,64.81307]}, + {"t":0.52979, "x":3.27046, "y":5.74283, "heading":2.14606, "vx":-2.74922, "vy":2.02451, "omega":0.15153, "ax":-5.15007, "ay":3.79238, "alpha":-0.3759, "fx":[-86.14022,-88.28249,-89.07485,-86.9075], "fy":[66.49212,63.6417,62.46831,65.42703]}, + {"t":0.57394, "x":3.14406, "y":5.83591, "heading":2.15275, "vx":-2.97659, "vy":2.19194, "omega":0.13493, "ax":-4.94016, "ay":3.64082, "alpha":-3.01549, "fx":[-73.70551,-89.71966,-95.22365,-77.47397], "fy":[76.01416,56.75556,44.70381,70.24384]}, + {"t":0.61809, "x":3.00783, "y":5.93623, "heading":2.15871, "vx":-3.1947, "vy":2.35268, "omega":0.0018, "ax":-0.03066, "ay":0.02067, "alpha":-0.03411, "fx":[-0.4969,-0.64427,-0.54605,-0.39867], "fy":[0.47431,0.37608,0.22871,0.32694]}, + {"t":0.66224, "x":2.86676, "y":6.04012, "heading":2.15879, "vx":-3.19605, "vy":2.35359, "omega":0.00029, "ax":-0.0002, "ay":-0.00025, "alpha":-0.00001, "fx":[-0.00334,-0.00337,-0.00335,-0.00331], "fy":[-0.00418,-0.0042,-0.00423,-0.00421]}, + {"t":0.70639, "x":2.72565, "y":6.14403, "heading":2.1588, "vx":-3.19606, "vy":2.35358, "omega":0.00029, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[-0.00001,-0.00001,-0.00001,-0.00001]}, + {"t":0.75054, "x":2.58455, "y":6.24794, "heading":2.15882, "vx":-3.19606, "vy":2.35358, "omega":0.00029, "ax":0.0002, "ay":0.00025, "alpha":0.00001, "fx":[0.00331,0.00335,0.00333,0.00329], "fy":[0.00415,0.00417,0.0042,0.00418]}, + {"t":0.79469, "x":2.44344, "y":6.35185, "heading":2.15883, "vx":-3.19605, "vy":2.35359, "omega":0.00029, "ax":0.03065, "ay":-0.02067, "alpha":0.03409, "fx":[0.49673,0.64398,0.54582,0.39857], "fy":[-0.47429,-0.37611,-0.22887,-0.32705]}, + {"t":0.83884, "x":2.30237, "y":6.45574, "heading":2.15884, "vx":-3.1947, "vy":2.35268, "omega":0.0018, "ax":4.94017, "ay":-3.64081, "alpha":3.01523, "fx":[73.7617,89.77041,95.19886,77.3926], "fy":[-75.96371,-56.67141,-44.74216,-70.33939]}, + {"t":0.88299, "x":2.16614, "y":6.55606, "heading":2.15892, "vx":-2.97659, "vy":2.19194, "omega":0.13492, "ax":5.15007, "ay":-3.79238, "alpha":0.37551, "fx":[86.1513,88.29998,89.06494,86.88884], "fy":[-66.47819,-63.61711,-62.48186,-65.45206]}, + {"t":0.92714, "x":2.03974, "y":6.64914, "heading":2.16488, "vx":-2.74922, "vy":2.02451, "omega":0.1515, "ax":5.17248, "ay":-3.80893, "alpha":0.01011, "fx":[87.94293,88.0014,88.02174,87.96325], "fy":[-64.84262,-64.76357,-64.73501,-64.81414]}, + {"t":0.97129, "x":1.92341, "y":6.7348, "heading":2.17157, "vx":-2.52085, "vy":1.85634, "omega":0.15194, "ax":5.18092, "ay":-3.81517, "alpha":-0.13579, "fx":[88.65587,87.86604,87.59805,88.384], "fy":[-64.17027,-65.24458,-65.61241,-64.55271]}, + {"t":1.01544, "x":1.81716, "y":6.81304, "heading":2.17828, "vx":-2.29212, "vy":1.6879, "omega":0.14595, "ax":5.18534, "ay":-3.81844, "alpha":-0.21429, "fx":[89.03677,87.78499,87.37069,88.6124], "fy":[-63.8066,-65.51453,-66.07628,-64.40497]}, + {"t":1.05959, "x":1.72102, "y":6.88384, "heading":2.18472, "vx":-2.06319, "vy":1.51932, "omega":0.13649, "ax":5.18806, "ay":-3.82045, "alpha":-0.26332, "fx":[89.2726,87.72899,87.23022,88.75802], "fy":[-63.58034,-65.69031,-66.36141,-64.30703]}, + {"t":1.10374, "x":1.63499, "y":6.9472, "heading":2.19074, "vx":-1.83414, "vy":1.35065, "omega":0.12486, "ax":5.1899, "ay":-3.82181, "alpha":-0.29685, "fx":[89.43228,87.68691,87.13562,88.8602], "fy":[-63.42695,-65.81551,-66.55338,-64.23577]}, + {"t":1.14789, "x":1.55907, "y":7.0031, "heading":2.19626, "vx":-1.60501, "vy":1.18192, "omega":0.11176, "ax":5.19123, "ay":-3.82279, "alpha":-0.32123, "fx":[89.54719,87.65365,87.06802,88.93646], "fy":[-63.31666,-65.91005,-66.69084,-64.18083]}, + {"t":1.19204, "x":1.49327, "y":7.05156, "heading":2.20119, "vx":-1.37582, "vy":1.01314, "omega":0.09757, "ax":5.19223, "ay":-3.82353, "alpha":-0.33974, "fx":[89.63365,87.62654,87.01754,88.99583], "fy":[-63.23381,-65.9843,-66.79382,-64.1369]}, + {"t":1.23619, "x":1.43759, "y":7.09256, "heading":2.2055, "vx":-1.14658, "vy":0.84434, "omega":0.08257, "ax":5.19302, "ay":-3.82411, "alpha":-0.35429, "fx":[89.70101,87.60405,86.97847,89.04339], "fy":[-63.16937,-66.04417,-66.87376,-64.10098]}, + {"t":1.28034, "x":1.39203, "y":7.12611, "heading":2.20914, "vx":-0.91731, "vy":0.6755, "omega":0.06693, "ax":5.19365, "ay":-3.82458, "alpha":-0.36601, "fx":[89.75501,87.58526,86.9473,89.08222], "fy":[-63.11777,-66.0933,-66.93766,-64.07124]}, + {"t":1.32449, "x":1.35659, "y":7.15221, "heading":2.2121, "vx":-0.68801, "vy":0.50665, "omega":0.05077, "ax":5.19416, "ay":-3.82496, "alpha":-0.37566, "fx":[89.79937,87.56957,86.92175,89.11431], "fy":[-63.07537,-66.13402,-66.99006,-64.04655]}, + {"t":1.36864, "x":1.33128, "y":7.17085, "heading":2.21434, "vx":-0.45869, "vy":0.33778, "omega":0.03419, "ax":5.1946, "ay":-3.82528, "alpha":-0.38375, "fx":[89.83661,87.55659,86.90024,89.14098], "fy":[-63.03969,-66.16791,-67.03403,-64.02611]}, + {"t":1.41279, "x":1.31609, "y":7.18203, "heading":2.21585, "vx":-0.22936, "vy":0.1689, "omega":0.01725, "ax":5.19496, "ay":-3.82555, "alpha":-0.39062, "fx":[89.8685,87.54604,86.88169,89.16314], "fy":[-63.009,-66.19607,-67.07171,-64.0094]}, + {"t":1.45694, "x":1.31103, "y":7.18576, "heading":2.21661, "vx":0.0, "vy":0.0, "omega":0.0, "ax":2.91839, "ay":-5.65805, "alpha":3.40262, "fx":[39.48205,65.02586,64.61227,29.44361], "fy":[-102.36619,-88.36314,-88.59594,-105.64181]}, + {"t":1.48332, "x":1.31204, "y":7.18379, "heading":2.21661, "vx":0.07701, "vy":-0.14931, "omega":0.08979, "ax":2.91913, "ay":-5.66, "alpha":3.34887, "fx":[39.6176,64.83716,64.36044,29.79895], "fy":[-102.30624,-88.49267,-88.76799,-105.53318]}, + {"t":1.50971, "x":1.31509, "y":7.17788, "heading":2.21898, "vx":0.15405, "vy":-0.29868, "omega":0.17817, "ax":2.91996, "ay":-5.6621, "alpha":3.2894, "fx":[39.80559,64.65602,64.04562,30.16369], "fy":[-102.22492,-88.61512,-88.98326,-105.41983]}, + {"t":1.5361, "x":1.32017, "y":7.16803, "heading":2.22368, "vx":0.2311, "vy":-0.4481, "omega":0.26497, "ax":2.92089, "ay":-5.66437, "alpha":3.22353, "fx":[40.04574,64.47722,63.66661,30.5443], "fy":[-102.12189,-88.7342,-89.24148,-105.29966]}, + {"t":1.56249, "x":1.32729, "y":7.15423, "heading":2.23068, "vx":0.30819, "vy":-0.59758, "omega":0.35004, "ax":2.9219, "ay":-5.66681, "alpha":3.15043, "fx":[40.33789,64.29435,63.22173,30.94889], "fy":[-101.99663,-88.85439,-89.54248,-105.16994]}, + {"t":1.58888, "x":1.33644, "y":7.13649, "heading":2.23991, "vx":0.38529, "vy":-0.74712, "omega":0.43318, "ax":2.923, "ay":-5.66945, "alpha":3.06905, "fx":[40.682,64.09947,62.70886,31.38735], "fy":[-101.84843,-88.98114,-89.88613,-105.02725]}, + {"t":1.61527, "x":1.34762, "y":7.1148, "heading":2.25134, "vx":0.46243, "vy":-0.89673, "omega":0.51417, "ax":2.92418, "ay":-5.6723, "alpha":2.97813, "fx":[41.07821,63.88275,62.12549,31.87171], "fy":[-101.67637,-89.12112,-90.27228,-104.86723]}, + {"t":1.64166, "x":1.36085, "y":7.08916, "heading":2.26491, "vx":0.5396, "vy":-1.04642, "omega":0.59276, "ax":2.92545, "ay":-5.67539, "alpha":2.87607, "fx":[41.5269,63.6319,61.46878,32.41657], "fy":[-101.47926,-89.28251,-90.70066,-104.68437]}, + {"t":1.66805, "x":1.3761, "y":7.05957, "heading":2.28056, "vx":0.6168, "vy":-1.19619, "omega":0.66866, "ax":2.92679, "ay":-5.67872, "alpha":2.76088, "fx":[42.02873,63.33136,60.73568,33.03977], "fy":[-101.25558,-89.47544,-91.17078,-104.47163]}, + {"t":1.69444, "x":1.3934, "y":7.02602, "heading":2.2982, "vx":0.69403, "vy":-1.34605, "omega":0.74152, "ax":2.92821, "ay":-5.68231, "alpha":2.62994, "fx":[42.58483,62.96117,59.92292,33.76328], "fy":[-101.00335,-89.71264,-91.68186,-104.21987]}, + {"t":1.72083, "x":1.41273, "y":6.98852, "heading":2.31777, "vx":0.77131, "vy":-1.496, "omega":0.81092, "ax":2.92971, "ay":-5.68616, "alpha":2.47986, "fx":[43.19701,62.49514,59.02714,34.61467], "fy":[-100.71998,-90.01029,-92.23273,-103.91693]}, + {"t":1.74722, "x":1.43411, "y":6.94706, "heading":2.33917, "vx":0.84862, "vy":-1.64606, "omega":0.87636, "ax":2.93127, "ay":-5.69027, "alpha":2.30599, "fx":[43.86815,61.89823,58.04489,35.62917], "fy":[-100.40192,-90.38927,-92.82174,-103.54634]}, + {"t":1.77361, "x":1.45752, "y":6.90164, "heading":2.3623, "vx":0.92598, "vy":-1.79622, "omega":0.93721, "ax":2.93289, "ay":-5.69458, "alpha":2.10192, "fx":[44.60285,61.12215,56.97259,36.85291], "fy":[-100.04419,-90.87701,-93.44675,-103.08498]}, + {"t":1.8, "x":1.48298, "y":6.85226, "heading":2.38703, "vx":1.00337, "vy":-1.9465, "omega":0.99268, "ax":2.93452, "ay":-5.69901, "alpha":1.85844, "fx":[45.40861,60.09823,55.8064,38.34811], "fy":[-99.63944,-91.5103,-94.10506,-102.49939]}, + {"t":1.82639, "x":1.51048, "y":6.79891, "heading":2.41322, "vx":1.08081, "vy":-2.09689, "omega":1.04173, "ax":2.93606, "ay":-5.70334, "alpha":1.56188, "fx":[46.29793,58.72498,54.54179,40.20141], "fy":[-99.1763,-92.33952,-94.79355,-101.73909]}, + {"t":1.85278, "x":1.54003, "y":6.74159, "heading":2.44072, "vx":1.15829, "vy":-2.2474, "omega":1.08294, "ax":2.93727, "ay":-5.7071, "alpha":1.19118, "fx":[47.29253,56.84547,53.17277,42.53788], "fy":[-98.63604,-93.43521,-95.50878,-100.72438]}, + {"t":1.87917, "x":1.57162, "y":6.68029, "heading":2.46929, "vx":1.23581, "vy":-2.39801, "omega":1.11438, "ax":2.9376, "ay":-5.70928, "alpha":0.7124, "fx":[48.43201,54.20329,51.69022,45.54549], "fy":[-97.98548,-94.89786,-96.24747,-99.32232]}, + {"t":1.90556, "x":1.60525, "y":6.61502, "heading":2.4987, "vx":1.31333, "vy":-2.54867, "omega":1.13318, "ax":2.93572, "ay":-5.70754, "alpha":0.06775, "fx":[49.79433,50.35081,50.07865,49.51894], "fy":[-97.16003,-96.87068,-97.00719,-97.29627]}, + {"t":1.93194, "x":1.64093, "y":6.54578, "heading":2.52861, "vx":1.3908, "vy":-2.69929, "omega":1.13497, "ax":2.92833, "ay":-5.69586, "alpha":-0.84792, "fx":[51.55043,44.44059,48.30972,54.93974], "fy":[-96.0166,-99.54477,-97.78779,-94.19046]}, + {"t":1.95833, "x":1.67865, "y":6.47256, "heading":2.55856, "vx":1.46808, "vy":-2.8496, "omega":1.11259, "ax":2.9071, "ay":-5.6569, "alpha":-2.24194, "fx":[54.14386,34.70909,46.32882,62.61428], "fy":[-94.16971,-103.0837,-98.59387,-89.04167]}, + {"t":1.98472, "x":1.71841, "y":6.39539, "heading":2.58792, "vx":1.54479, "vy":-2.99888, "omega":1.05343, "ax":2.85299, "ay":-5.52938, "alpha":-4.56218, "fx":[59.10984,17.16539,44.02846,73.81081], "fy":[-90.15708,-107.00648,-99.43786,-79.61144]}, + {"t":2.01111, "x":1.76017, "y":6.31433, "heading":2.61572, "vx":1.62008, "vy":-3.1448, "omega":0.93303, "ax":2.79815, "ay":-4.98803, "alpha":-9.01602, "fx":[75.78419,-16.01911,41.2385,89.37926], "fy":[-71.70497,-106.53896,-100.31945,-60.81674]}, + {"t":2.0375, "x":1.80389, "y":6.2296, "heading":2.64034, "vx":1.69392, "vy":-3.27643, "omega":0.69511, "ax":2.80117, "ay":-4.244, "alpha":-12.47506, "fx":[87.08726,-31.67238,40.36251,94.81072], "fy":[-37.0699,-101.82161,-99.92089,-49.94447]}, + {"t":2.06389, "x":1.84957, "y":6.14166, "heading":2.65868, "vx":1.76785, "vy":-3.38843, "omega":0.3659, "ax":2.4803, "ay":-4.17912, "alpha":-12.08742, "fx":[67.24676,-29.6511,39.6292,91.53168], "fy":[-39.52566,-98.46412,-97.43575,-48.91732]}, + {"t":2.09028, "x":1.89709, "y":6.05079, "heading":2.66834, "vx":1.8333, "vy":-3.49871, "omega":0.04692, "ax":-0.17626, "ay":-0.79246, "alpha":-1.59461, "fx":[-4.88922,-8.60653,-1.16703,2.67027], "fy":[-7.95051,-15.23915,-18.95774,-11.77039]}, + {"t":2.11667, "x":1.9454, "y":5.95818, "heading":2.66958, "vx":1.82865, "vy":-3.51962, "omega":0.00483, "ax":-0.21212, "ay":-0.11241, "alpha":-0.0049, "fx":[-3.61367,-3.62521,-3.60254,-3.59099], "fy":[-1.8949,-1.91758,-1.9292,-1.90651]}, + {"t":2.14306, "x":1.99359, "y":5.86526, "heading":2.6697, "vx":1.82305, "vy":-3.52259, "omega":0.00471, "ax":-0.08289, "ay":-0.04288, "alpha":-0.00002, "fx":[-1.40998,-1.41004,-1.40993,-1.40987], "fy":[-0.72922,-0.72932,-0.72938,-0.72927]}, + {"t":2.16945, "x":2.04167, "y":5.77229, "heading":2.66983, "vx":1.82086, "vy":-3.52372, "omega":0.0047, "ax":-0.00264, "ay":-0.00137, "alpha":0.0, "fx":[-0.04497,-0.04498,-0.04497,-0.04497], "fy":[-0.02324,-0.02324,-0.02324,-0.02324]}, + {"t":2.19584, "x":2.08972, "y":5.6793, "heading":2.66995, "vx":1.82079, "vy":-3.52376, "omega":0.0047, "ax":0.076, "ay":0.03931, "alpha":0.00002, "fx":[1.29284,1.29289,1.29279,1.29273], "fy":[0.66858,0.66869,0.66874,0.66863]}, + {"t":2.22223, "x":2.1378, "y":5.58632, "heading":2.67008, "vx":1.8228, "vy":-3.52272, "omega":0.00471, "ax":0.19937, "ay":0.10611, "alpha":0.0056, "fx":[3.39755,3.41072,3.38482,3.37164], "fy":[1.78536,1.81127,1.82452,1.7986]}, + {"t":2.24862, "x":2.18597, "y":5.4934, "heading":2.6702, "vx":1.82806, "vy":-3.51992, "omega":0.00485, "ax":0.10974, "ay":0.85433, "alpha":1.81008, "fx":[4.02114,8.24784,-0.21231,-4.58986], "fy":[8.2734,16.55734,20.71561,12.581]}, + {"t":2.27501, "x":2.23425, "y":5.4008, "heading":2.67033, "vx":1.83096, "vy":-3.49737, "omega":0.05262, "ax":-2.49086, "ay":4.18272, "alpha":12.07721, "fx":[-66.56241,29.43815,-40.28373,-92.06745], "fy":[40.24007,98.78279,97.32182,48.24305]}, + {"t":2.3014, "x":2.2817, "y":5.30997, "heading":2.67172, "vx":1.76522, "vy":-3.38699, "omega":0.37133, "ax":-2.80078, "ay":4.24401, "alpha":12.3592, "fx":[-84.24281,31.25583,-41.78246,-95.79235], "fy":[39.28078,102.05607,99.37277,48.04789]}, + {"t":2.32779, "x":2.32731, "y":5.22206, "heading":2.68152, "vx":1.69131, "vy":-3.275, "omega":0.69748, "ax":-2.78293, "ay":4.9578, "alpha":9.12859, "fx":[-71.38725,17.62037,-43.59148,-91.98874], "fy":[74.85424,106.3754,99.34714,56.74624]}, + {"t":2.35418, "x":2.37097, "y":5.13737, "heading":2.69992, "vx":1.61787, "vy":-3.14416, "omega":0.93838, "ax":-2.84329, "ay":5.51657, "alpha":4.76045, "fx":[-55.19964,-15.50463,-46.49254,-76.25749], "fy":[92.48434,107.30773,98.32617,77.22271]}, + {"t":2.38057, "x":2.41267, "y":5.05631, "heading":2.72469, "vx":1.54284, "vy":-2.99859, "omega":1.06401, "ax":-2.90459, "ay":5.65224, "alpha":2.38707, "fx":[-51.5818,-33.48444,-48.35433,-64.2043], "fy":[95.56357,103.51219,97.62517,87.8713]}, + {"t":2.40695, "x":2.45238, "y":4.97915, "heading":2.75276, "vx":1.46619, "vy":-2.84943, "omega":1.127, "ax":-2.92793, "ay":5.69472, "alpha":0.9275, "fx":[-50.32755,-43.73417,-49.42923,-55.72197], "fy":[96.65128,99.86543,97.22998,93.71553]}, + {"t":2.43334, "x":2.49005, "y":4.90594, "heading":2.7825, "vx":1.38892, "vy":-2.69915, "omega":1.15148, "ax":-2.93579, "ay":5.70739, "alpha":-0.03964, "fx":[-49.92543,-50.19383,-49.94885,-49.67998], "fy":[97.08923,96.94881,97.0731,97.21292]}, + {"t":2.45973, "x":2.52568, "y":4.8367, "heading":2.81289, "vx":1.31145, "vy":-2.54853, "omega":1.15043, "ax":-2.93762, "ay":5.70909, "alpha":-0.71994, "fx":[-49.92673,-54.6101,-50.07471,-45.26087], "fy":[97.23292,94.65225,97.09332,99.46124]}, + {"t":2.48612, "x":2.55927, "y":4.77143, "heading":2.84325, "vx":1.23393, "vy":-2.39787, "omega":1.13143, "ax":-2.93701, "ay":5.70654, "alpha":-1.22142, "fx":[-50.14565,-57.81836,-49.91912,-41.94764], "fy":[97.21933,92.8174,97.24166,100.98832]}, + {"t":2.51251, "x":2.59081, "y":4.71014, "heading":2.87311, "vx":1.15642, "vy":-2.24728, "omega":1.0992, "ax":-2.93539, "ay":5.70243, "alpha":-1.60522, "fx":[-50.48885,-60.25659,-49.56237,-39.41258], "fy":[97.11384,91.32315,97.47992,102.07002]}, + {"t":2.5389, "x":2.6203, "y":4.65282, "heading":2.90212, "vx":1.07896, "vy":-2.0968, "omega":1.05684, "ax":-2.93335, "ay":5.69788, "alpha":-1.90817, "fx":[-50.90314,-62.17349,-49.06376,-37.44146], "fy":[96.95239,90.08468,97.77855,102.86149]}, + {"t":2.56529, "x":2.64775, "y":4.59947, "heading":2.93001, "vx":1.00155, "vy":-1.94643, "omega":1.00648, "ax":-2.93116, "ay":5.69336, "alpha":-2.15361, "fx":[-51.35545,-63.72001,-48.46831,-35.88915], "fy":[96.75692,89.04285,98.11467,103.45555]}, + {"t":2.59168, "x":2.67316, "y":4.55009, "heading":2.95657, "vx":0.9242, "vy":-1.79619, "omega":0.94965, "ax":-2.92894, "ay":5.68909, "alpha":-2.35694, "fx":[-51.82382,-64.993,-47.81108,-34.65391], "fy":[96.54189,88.15573,98.47061,103.91066]}, + {"t":2.61807, "x":2.69653, "y":4.50467, "heading":2.98163, "vx":0.8469, "vy":-1.64606, "omega":0.88745, "ax":-2.92675, "ay":5.68511, "alpha":-2.52862, "fx":[-52.29301,-66.05761,-47.11983,-33.66211], "fy":[96.31745,87.39276,98.83275,104.26535]}, + {"t":2.64446, "x":2.71786, "y":4.46321, "heading":3.00505, "vx":0.76967, "vy":-1.49603, "omega":0.82072, "ax":-2.92461, "ay":5.68144, "alpha":-2.67593, "fx":[-52.75199,-66.95948,-46.41687,-32.85904], "fy":[96.09109,86.73108,99.19069,104.54596]}, + {"t":2.67085, "x":2.73715, "y":4.42571, "heading":3.0267, "vx":0.69249, "vy":-1.3461, "omega":0.75011, "ax":-2.92256, "ay":5.67807, "alpha":-2.80405, "fx":[-53.19256,-67.73178,-45.72022,-32.20301], "fy":[95.86856,86.15311,99.53653,104.77111]}, + {"t":2.69724, "x":2.75441, "y":4.39216, "heading":3.0465, "vx":0.61536, "vy":-1.19626, "omega":0.67611, "ax":-2.9206, "ay":5.67497, "alpha":-2.9167, "fx":[-53.60849,-68.3993,-45.04457,-31.66163], "fy":[95.65441,85.64501,99.86439,104.95434]}, + {"t":2.72363, "x":2.76963, "y":4.36257, "heading":3.06434, "vx":0.53829, "vy":-1.0465, "omega":0.59914, "ax":-2.91873, "ay":5.67211, "alpha":-3.01661, "fx":[-53.9949,-68.98114,-44.40188,-31.20925], "fy":[95.45233,85.19562,100.16993,105.10576]}, + {"t":2.75002, "x":2.78282, "y":4.33693, "heading":3.08015, "vx":0.46127, "vy":-0.89682, "omega":0.51953, "ax":-2.91697, "ay":5.66947, "alpha":-3.10582, "fx":[-54.34796,-69.49231,-43.80197,-30.8253], "fy":[95.2654,84.79578,100.45,105.23308]}, + {"t":2.77641, "x":2.79398, "y":4.31524, "heading":3.09386, "vx":0.38429, "vy":-0.7472, "omega":0.43757, "ax":-2.91532, "ay":5.66704, "alpha":-3.18585, "fx":[-54.66457,-69.94482,-43.25286,-30.49304], "fy":[95.09617,84.43787,100.70237,105.34228]}, + {"t":2.8028, "x":2.8031, "y":4.29749, "heading":3.10541, "vx":0.30736, "vy":-0.59765, "omega":0.3535, "ax":-2.91378, "ay":5.66479, "alpha":-3.25785, "fx":[-54.94219,-70.34843,-42.76118,-30.19875], "fy":[94.94686,84.1155,100.92546,105.43808]}, + {"t":2.82919, "x":2.8102, "y":4.28369, "heading":3.11474, "vx":0.23046, "vy":-0.44816, "omega":0.26753, "ax":-2.91236, "ay":5.66272, "alpha":-3.32272, "fx":[-55.1787,-70.71109,-42.33242,-29.93111], "fy":[94.81932,83.8233,101.11816,105.52425]}, + {"t":2.85557, "x":2.81527, "y":4.27384, "heading":3.1218, "vx":0.15361, "vy":-0.29873, "omega":0.17984, "ax":-2.91104, "ay":5.66082, "alpha":-3.38117, "fx":[-55.3723,-71.03932,-41.97122,-29.68072], "fy":[94.71517,83.55674,101.27967,105.60382]}, + {"t":2.88196, "x":2.81831, "y":4.26793, "heading":3.12654, "vx":0.07679, "vy":-0.14934, "omega":0.09062, "ax":-2.90983, "ay":5.65907, "alpha":-3.43377, "fx":[-55.52143,-71.33844,-41.68155,-29.43978], "fy":[94.6358,83.3121,101.40933,105.67923]}, + {"t":2.90835, "x":2.81932, "y":4.26596, "heading":3.12894, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[ + {"name":"Funnel", "from":{"target":2, "targetTimestamp":2.14306, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] +} diff --git a/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH_ALT4.traj b/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH_ALT4.traj new file mode 100644 index 00000000..1849290b --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/A_LEFT_PATH_ALT4.traj @@ -0,0 +1,125 @@ +{ + "name":"A_LEFT_PATH_ALT4", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.1724631786346436, "y":4.214198112487793, "heading":3.141592653589793, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.3110252618789673, "y":7.185760498046875, "heading":2.2024870470289093, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.5126070976257324, "y":6.151042938232422, "heading":0.0, "intervals":32, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":3.4538493156433105, "y":5.355730056762695, "heading":2.077894951837786, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.1724631786346436 m", "val":3.1724631786346436}, "y":{"exp":"4.214198112487793 m", "val":4.214198112487793}, "heading":{"exp":"pi rad", "val":3.141592653589793}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"7.185760498046875 m", "val":7.185760498046875}, "heading":{"exp":"2.2024870470289093 rad", "val":2.2024870470289093}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.5126070976257324 m", "val":2.5126070976257324}, "y":{"exp":"6.151042938232422 m", "val":6.151042938232422}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":32, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"3.4538493156433105 m", "val":3.4538493156433105}, "y":{"exp":"5.355730056762695 m", "val":5.355730056762695}, "heading":{"exp":"2.077894951837786 rad", "val":2.077894951837786}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.5067,2.21611,2.83299], + "samples":[ + {"t":0.0, "x":3.17246, "y":4.2142, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.36966, "ay":5.40045, "alpha":-3.44275, "fx":[-62.09191,-78.25296,-51.70889,-37.21437], "fy":[90.51089,76.93128,96.75254,103.24557]}, + {"t":0.03767, "x":3.17007, "y":4.21803, "heading":3.14159, "vx":-0.12693, "vy":0.20342, "omega":-0.12968, "ax":-3.37146, "ay":5.40272, "alpha":-3.3749, "fx":[-62.0235,-77.87333,-51.87327,-37.62047], "fy":[90.54897,77.30324,96.65326,103.08971]}, + {"t":0.07533, "x":3.1629, "y":4.22952, "heading":3.13671, "vx":-0.25392, "vy":0.40693, "omega":-0.2568, "ax":-3.37356, "ay":5.40531, "alpha":-3.29497, "fx":[-61.86428,-77.43332,-52.18886,-38.04645], "fy":[90.64765,77.73019,96.47036,102.92322]}, + {"t":0.113, "x":3.15094, "y":4.24869, "heading":3.12703, "vx":-0.38099, "vy":0.61053, "omega":-0.38092, "ax":-3.37595, "ay":5.40826, "alpha":-3.20095, "fx":[-61.61822,-76.91871,-52.64431,-38.51441], "fy":[90.80322,78.22377,96.20778,102.73718]}, + {"t":0.15067, "x":3.1342, "y":4.27552, "heading":3.11269, "vx":-0.50816, "vy":0.81425, "omega":-0.50149, "ax":-3.37865, "ay":5.41162, "alpha":-3.09005, "fx":[-61.29023,-76.30936,-53.22554,-39.05432], "fy":[91.01089,78.80024,95.87025,102.51903]}, + {"t":0.18834, "x":3.11266, "y":4.31003, "heading":3.0938, "vx":-0.63542, "vy":1.01809, "omega":-0.61788, "ax":-3.38167, "ay":5.41546, "alpha":-2.95829, "fx":[-60.8867,-75.57702,-53.91444,-39.70693], "fy":[91.26444,79.48174,95.46437,102.25097]}, + {"t":0.226, "x":3.08632, "y":4.35222, "heading":3.07052, "vx":-0.7628, "vy":1.22208, "omega":-0.72931, "ax":-3.38503, "ay":5.41986, "alpha":-2.79967, "fx":[-60.41643,-74.6815,-54.68705,-40.52842], "fy":[91.55572,80.29855,94.99995,101.90718]}, + {"t":0.26367, "x":3.05519, "y":4.4021, "heading":3.04305, "vx":-0.89031, "vy":1.42623, "omega":-0.83477, "ax":-3.38873, "ay":5.42495, "alpha":-2.60496, "fx":[-59.89201,-73.56392,-55.51099,-41.59814], "fy":[91.87359,81.29292,94.49205,101.44896]}, + {"t":0.30134, "x":3.01925, "y":4.45967, "heading":3.01161, "vx":-1.01795, "vy":1.63057, "omega":-0.93289, "ax":-3.39277, "ay":5.43083, "alpha":-2.35936, "fx":[-59.33252,-72.13396,-56.34167,-43.03191], "fy":[92.20216,82.52603,93.96382,100.81544]}, + {"t":0.33901, "x":2.9785, "y":4.52494, "heading":2.97647, "vx":-1.14575, "vy":1.83514, "omega":-1.02176, "ax":-3.39711, "ay":5.43754, "alpha":-2.03817, "fx":[-58.76862,-70.24404,-57.11614,-45.0064], "fy":[92.51709,84.091,93.45091,99.90496]}, + {"t":0.37667, "x":2.93293, "y":4.59792, "heading":2.93798, "vx":-1.27371, "vy":2.03996, "omega":-1.09854, "ax":-3.40152, "ay":5.44481, "alpha":-1.59792, "fx":[-58.25381,-67.63286,-57.74233,-47.80639], "fy":[92.77726,86.13858,93.00845,98.53416]}, + {"t":0.41434, "x":2.88254, "y":4.67863, "heading":2.8966, "vx":-1.40183, "vy":2.24505, "omega":-1.15872, "ax":-3.40512, "ay":5.45122, "alpha":-0.9563, "fx":[-57.89267,-63.78629,-58.07814,-51.92318], "fy":[92.90305,88.93029,92.72339,96.33827]}, + {"t":0.45201, "x":2.82732, "y":4.76706, "heading":2.85296, "vx":-1.5301, "vy":2.45038, "omega":-1.19475, "ax":-3.40434, "ay":5.4511, "alpha":0.05931, "fx":[-57.92859,-57.53962,-57.88568,-58.2734], "fy":[92.70599,92.95028,92.73783,92.49233]}, + {"t":0.48968, "x":2.76727, "y":4.86323, "heading":2.80795, "vx":-1.65833, "vy":2.65571, "omega":-1.19251, "ax":-3.38346, "ay":5.41932, "alpha":1.86897, "fx":[-59.12278,-45.68013,-56.71837,-68.68573], "fy":[91.56501,99.07383,93.29846,84.78723]}, + {"t":0.52734, "x":2.70241, "y":4.9671, "heading":2.76303, "vx":-1.78578, "vy":2.85984, "omega":-1.12211, "ax":-3.27392, "ay":5.19551, "alpha":5.72964, "fx":[-65.9464,-16.82934,-53.60084,-86.37698], "fy":[85.25021,107.31393,94.86356,66.06889]}, + {"t":0.56501, "x":2.63282, "y":5.07851, "heading":2.72077, "vx":-1.9091, "vy":3.05554, "omega":-0.90629, "ax":-3.21612, "ay":4.03303, "alpha":12.43881, "fx":[-93.99681,23.20508,-48.75187,-99.27722], "fy":[30.39183,104.97799,96.75253,42.28044]}, + {"t":0.60268, "x":2.55863, "y":5.19647, "heading":2.68663, "vx":-2.03024, "vy":3.20746, "omega":-0.43775, "ax":-2.37439, "ay":3.88617, "alpha":11.48043, "fx":[-53.75757,20.95626,-41.62353,-87.12561], "fy":[34.04057,93.76683,91.61278,44.99046]}, + {"t":0.64035, "x":2.48047, "y":5.32004, "heading":2.67014, "vx":-2.11968, "vy":3.35384, "omega":-0.00532, "ax":0.30346, "ay":0.21618, "alpha":0.05582, "fx":[5.22562,5.35624,5.09798,4.96727], "fy":[3.48194,3.73998,3.87255,3.61451]}, + {"t":0.67801, "x":2.40084, "y":5.44653, "heading":2.66994, "vx":-2.10825, "vy":3.36198, "omega":-0.00321, "ax":0.08845, "ay":0.05542, "alpha":0.00005, "fx":[1.5045,1.5046,1.5044,1.50429], "fy":[0.94258,0.94278,0.94289,0.94268]}, + {"t":0.71568, "x":2.32149, "y":5.5732, "heading":2.66982, "vx":-2.10491, "vy":3.36407, "omega":-0.00321, "ax":0.01858, "ay":0.01162, "alpha":0.0, "fx":[0.31602,0.31602,0.31602,0.31602], "fy":[0.19769,0.19769,0.19769,0.19769]}, + {"t":0.75335, "x":2.24222, "y":5.69993, "heading":2.6697, "vx":-2.10421, "vy":3.36451, "omega":-0.00321, "ax":-0.01819, "ay":-0.01138, "alpha":0.0, "fx":[-0.30946,-0.30946,-0.30946,-0.30945], "fy":[-0.19358,-0.19359,-0.19359,-0.19358]}, + {"t":0.79102, "x":2.16295, "y":5.82665, "heading":2.66958, "vx":-2.1049, "vy":3.36408, "omega":-0.00321, "ax":-0.08737, "ay":-0.05475, "alpha":-0.00004, "fx":[-1.48626,-1.48636,-1.48617,-1.48607], "fy":[-0.93111,-0.9313,-0.9314,-0.93121]}, + {"t":0.82868, "x":2.0836, "y":5.95333, "heading":2.66946, "vx":-2.10819, "vy":3.36202, "omega":-0.00321, "ax":-0.30109, "ay":-0.21188, "alpha":-0.04937, "fx":[-5.17778,-5.29348,-5.06515,-4.94938], "fy":[-3.43124,-3.65939,-3.77678,-3.54863]}, + {"t":0.86635, "x":2.00397, "y":6.07982, "heading":2.66933, "vx":-2.11953, "vy":3.35404, "omega":-0.00507, "ax":2.31284, "ay":-3.85705, "alpha":-11.38264, "fx":[52.47339,-20.95994,40.32826,85.52111], "fy":[-33.14746,-92.3422,-91.1986,-45.74104]}, + {"t":0.90402, "x":1.92578, "y":6.20342, "heading":2.66914, "vx":-2.03241, "vy":3.20875, "omega":-0.43383, "ax":3.19567, "ay":-4.03811, "alpha":-12.67439, "fx":[96.71132,-23.83337,46.59444,97.95737], "fy":[-26.9726,-104.72388,-97.77698,-45.27523]}, + {"t":0.94169, "x":1.85149, "y":6.32142, "heading":2.6528, "vx":-1.91204, "vy":3.05665, "omega":-0.91124, "ax":3.29389, "ay":-5.21984, "alpha":-5.40693, "fx":[69.95359,19.77798,51.07303,83.30778], "fy":[-82.21796,-106.76153,-96.22824,-69.94452]}, + {"t":0.97935, "x":1.7818, "y":6.43285, "heading":2.61848, "vx":-1.78797, "vy":2.86003, "omega":-1.1149, "ax":3.38778, "ay":-5.4229, "alpha":-1.67528, "fx":[61.10263,47.24684,55.08283,67.06863], "fy":[-90.284,-98.32353,-94.2663,-86.09377]}, + {"t":1.01702, "x":1.71686, "y":6.53673, "heading":2.57648, "vx":-1.66036, "vy":2.65576, "omega":-1.17801, "ax":3.40547, "ay":-5.4506, "alpha":0.0089, "fx":[57.90788,57.97804,57.94414,57.87392], "fy":[-92.72484,-92.68076,-92.70148,-92.74556]}, + {"t":1.05469, "x":1.65673, "y":6.6329, "heading":2.53211, "vx":-1.53208, "vy":2.45045, "omega":-1.17767, "ax":3.40602, "ay":-5.45082, "alpha":0.95347, "fx":[55.90815,63.25176,60.30589,52.27593], "fy":[-94.11035,-89.32431,-91.29516,-96.13792]}, + {"t":1.09236, "x":1.60144, "y":6.72134, "heading":2.48775, "vx":-1.40379, "vy":2.24513, "omega":-1.14176, "ax":3.40292, "ay":-5.44512, "alpha":1.55959, "fx":[54.35636,66.20304,62.36449,48.60713], "fy":[-95.11037,-87.26167,-89.98305,-98.12435]}, + {"t":1.13002, "x":1.55098, "y":6.80204, "heading":2.44474, "vx":-1.27561, "vy":2.04003, "omega":-1.08301, "ax":3.39925, "ay":-5.43832, "alpha":1.98502, "fx":[53.0387,67.97533,64.1906,46.07617], "fy":[-95.913,-85.95892,-88.75175,-99.39362]}, + {"t":1.16769, "x":1.50534, "y":6.87503, "heading":2.40395, "vx":-1.14757, "vy":1.83518, "omega":-1.00824, "ax":3.39571, "ay":-5.43176, "alpha":2.3027, "fx":[51.87681,69.07898,65.81463,44.26992], "fy":[-96.58938,-85.12602,-87.60326,-100.25199]}, + {"t":1.20536, "x":1.46452, "y":6.9403, "heading":2.36597, "vx":-1.01966, "vy":1.63058, "omega":-0.92151, "ax":3.39246, "ay":-5.42579, "alpha":2.55043, "fx":[50.83785,69.77672,67.25364,42.95103], "fy":[-97.17192,-84.59406,-86.54316,-100.85537]}, + {"t":1.24303, "x":1.42852, "y":6.99787, "heading":2.33126, "vx":-0.89187, "vy":1.4262, "omega":-0.82544, "ax":3.3895, "ay":-5.42049, "alpha":2.74961, "fx":[49.90692,70.21887,68.52055,41.97108], "fy":[-97.67762,-84.25788,-85.5764,-101.29188]}, + {"t":1.28069, "x":1.39733, "y":7.04775, "heading":2.30017, "vx":-0.7642, "vy":1.22203, "omega":-0.72187, "ax":3.38679, "ay":-5.41583, "alpha":2.91326, "fx":[49.077,70.49868,69.62722,41.23031], "fy":[-98.11649,-84.04829,-84.70594,-101.61586]}, + {"t":1.31836, "x":1.37095, "y":7.08994, "heading":2.27298, "vx":-0.63663, "vy":1.01803, "omega":-0.61213, "ax":3.38432, "ay":-5.41174, "alpha":3.04989, "fx":[48.3447,70.67777,70.5852,40.65752], "fy":[-98.49501,-83.91764,-83.93268,-101.86322]}, + {"t":1.35603, "x":1.34937, "y":7.12444, "heading":2.24992, "vx":-0.50915, "vy":0.81418, "omega":-0.49725, "ax":3.38207, "ay":-5.40815, "alpha":3.16538, "fx":[47.70844,70.7989,71.40566,40.19949], "fy":[-98.81774,-83.83198,-83.25579,-102.05915]}, + {"t":1.39369, "x":1.33259, "y":7.15128, "heading":2.23119, "vx":-0.38176, "vy":0.61047, "omega":-0.37802, "ax":3.38005, "ay":-5.405, "alpha":3.264, "fx":[47.16753,70.89287,72.09906,39.81516], "fy":[-99.08802,-83.76641,-82.67329,-102.22205]}, + {"t":1.43136, "x":1.32061, "y":7.17044, "heading":2.21695, "vx":-0.25444, "vy":0.40688, "omega":-0.25507, "ax":3.37824, "ay":-5.40219, "alpha":3.34895, "fx":[46.72186,70.9825,72.67471,39.47229], "fy":[-99.30832,-83.70228,-82.18271,-102.36576]}, + {"t":1.46903, "x":1.31342, "y":7.18193, "heading":2.20734, "vx":-0.12719, "vy":0.20339, "omega":-0.12893, "ax":3.37664, "ay":-5.39968, "alpha":3.42272, "fx":[46.37171,71.08498,73.14039,39.14549], "fy":[-99.48046,-83.62544,-81.7816,-102.50077]}, + {"t":1.5067, "x":1.31103, "y":7.18576, "heading":2.20249, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.90382, "ay":-4.18798, "alpha":-0.43874, "fx":[85.20621,82.29237,81.65761,84.49414], "fy":[-69.1148,-72.55754,-73.28009,-69.9926]}, + {"t":1.53754, "x":1.31336, "y":7.18377, "heading":2.20249, "vx":0.15125, "vy":-0.12917, "omega":-0.01353, "ax":4.9035, "ay":-4.1877, "alpha":-0.43206, "fx":[85.17298,82.30425,81.67881,84.47257], "fy":[-69.14314,-72.53196,-73.24483,-70.00653]}, + {"t":1.56839, "x":1.32036, "y":7.17779, "heading":2.20207, "vx":0.3025, "vy":-0.25834, "omega":-0.02686, "ax":4.90315, "ay":-4.1874, "alpha":-0.42461, "fx":[85.13641,82.31821,81.70194,84.44784], "fy":[-69.17415,-72.50266,-73.20605,-70.02289]}, + {"t":1.59923, "x":1.33202, "y":7.16783, "heading":2.20124, "vx":0.45373, "vy":-0.38749, "omega":-0.03996, "ax":4.90275, "ay":-4.18706, "alpha":-0.41626, "fx":[85.09578,82.33441,81.72747,84.41953], "fy":[-69.20844,-72.46918,-73.16297,-70.0419]}, + {"t":1.63007, "x":1.34834, "y":7.15389, "heading":2.20001, "vx":0.60495, "vy":-0.51664, "omega":-0.05279, "ax":4.90229, "ay":-4.18667, "alpha":-0.40685, "fx":[85.0502,82.3531,81.756,84.38715], "fy":[-69.24677,-72.43093,-73.11464,-70.06385]}, + {"t":1.66092, "x":1.36934, "y":7.13596, "heading":2.19838, "vx":0.75615, "vy":-0.64577, "omega":-0.06534, "ax":4.90178, "ay":-4.18623, "alpha":-0.39615, "fx":[84.99854,82.37456,81.78827,84.35003], "fy":[-69.29012,-72.38719,-73.0598,-70.08911]}, + {"t":1.69176, "x":1.39499, "y":7.11405, "heading":2.19636, "vx":0.90734, "vy":-0.77489, "omega":-0.07756, "ax":4.90119, "ay":-4.18572, "alpha":-0.38387, "fx":[84.93932,82.39918,81.82524,84.30734], "fy":[-69.33971,-72.337,-72.99686,-70.11817]}, + {"t":1.7226, "x":1.42531, "y":7.08816, "heading":2.19397, "vx":1.05852, "vy":-0.904, "omega":-0.0894, "ax":4.9005, "ay":-4.18513, "alpha":-0.36965, "fx":[84.87064,82.42746,81.86818,84.25794], "fy":[-69.39717,-72.27911,-72.9237,-70.15167]}, + {"t":1.75345, "x":1.46029, "y":7.05829, "heading":2.19122, "vx":1.20967, "vy":-1.03308, "omega":-0.1008, "ax":4.89969, "ay":-4.18444, "alpha":-0.35298, "fx":[84.7899,82.46008,81.91876,84.20032], "fy":[-69.46469,-72.21184,-72.83749,-70.19048]}, + {"t":1.78429, "x":1.49993, "y":7.02443, "heading":2.18811, "vx":1.36079, "vy":-1.16215, "omega":-0.11169, "ax":4.89872, "ay":-4.18361, "alpha":-0.33316, "fx":[84.69358,82.49797,81.97931,84.13236], "fy":[-69.54521,-72.13285,-72.73432,-70.23581]}, + {"t":1.81514, "x":1.54423, "y":6.9866, "heading":2.18466, "vx":1.51189, "vy":-1.29119, "omega":-0.12197, "ax":4.89754, "ay":-4.18261, "alpha":-0.30923, "fx":[84.57666,82.54245,82.05307,84.05104], "fy":[-69.64291,-72.03887,-72.60864,-70.28937]}, + {"t":1.84598, "x":1.59319, "y":6.94478, "heading":2.1809, "vx":1.66295, "vy":-1.42019, "omega":-0.1315, "ax":4.89609, "ay":-4.18136, "alpha":-0.27975, "fx":[84.43186,82.59543,82.14479,83.95194], "fy":[-69.76381,-71.92511,-72.45234,-70.35371]}, + {"t":1.87682, "x":1.64681, "y":6.89899, "heading":2.17684, "vx":1.81396, "vy":-1.54916, "omega":-0.14013, "ax":4.89423, "ay":-4.17977, "alpha":-0.24253, "fx":[84.24808,82.65981,82.26165,83.82822], "fy":[-69.91702,-71.7843,-72.25297,-70.43272]}, + {"t":1.90767, "x":1.70509, "y":6.84922, "heading":2.17252, "vx":1.96492, "vy":-1.67809, "omega":-0.14761, "ax":4.89179, "ay":-4.17769, "alpha":-0.19409, "fx":[84.00757,82.74019,82.41509,83.66879], "fy":[-70.11693,-71.60485,-71.99053,-70.53267]}, + {"t":1.93851, "x":1.76803, "y":6.79547, "heading":2.16797, "vx":2.1158, "vy":-1.80694, "omega":-0.1536, "ax":4.88843, "ay":-4.17482, "alpha":-0.12846, "fx":[83.68012,82.84428,82.62452,83.45446], "fy":[-70.38777,-71.3671,-71.63058,-70.66438]}, + {"t":1.96936, "x":1.83561, "y":6.73775, "heading":2.16323, "vx":2.26658, "vy":-1.93571, "omega":-0.15756, "ax":4.88354, "ay":-4.17063, "alpha":-0.03452, "fx":[83.20969,82.98608,82.92569,83.14888], "fy":[-70.77369,-71.03491,-71.1084,-70.84812]}, + {"t":2.0002, "x":1.90784, "y":6.67606, "heading":2.15837, "vx":2.41721, "vy":-2.06435, "omega":-0.15863, "ax":4.87574, "ay":-4.16397, "alpha":0.11099, "fx":[82.47942,83.19383,83.39259,82.67394], "fy":[-71.36453,-70.53386,-70.28638,-71.12676]}, + {"t":2.03104, "x":1.98472, "y":6.61041, "heading":2.15348, "vx":2.56759, "vy":-2.19278, "omega":-0.1552, "ax":4.86142, "ay":-4.15173, "alpha":0.36645, "fx":[81.19884,83.5339,84.20661,81.82628], "fy":[-72.37529,-69.68288,-68.81166,-71.609]}, + {"t":2.06189, "x":2.06623, "y":6.5408, "heading":2.14869, "vx":2.71754, "vy":-2.32084, "omega":-0.1439, "ax":4.82697, "ay":-4.12232, "alpha":0.9314, "fx":[78.39557,84.20597,85.9579,79.86239], "fy":[-74.47626,-67.89917,-65.43051,-72.67166]}, + {"t":2.09273, "x":2.15234, "y":6.46726, "heading":2.14425, "vx":2.86642, "vy":-2.44799, "omega":-0.11517, "ax":4.64855, "ay":-3.97406, "alpha":3.2318, "fx":[67.76566,86.17117,91.9929,70.3521], "fy":[-81.20362,-61.75885,-50.40969,-77.01848]}, + {"t":2.12358, "x":2.24296, "y":6.38986, "heading":2.1407, "vx":3.0098, "vy":-2.57056, "omega":-0.01549, "ax":0.23293, "ay":-0.19706, "alpha":0.48557, "fx":[3.57861,5.7007,4.34833,2.22098], "fy":[-5.09446,-3.72986,-1.60882,-2.97491]}, + {"t":2.15442, "x":2.33591, "y":6.31048, "heading":2.14022, "vx":3.01699, "vy":-2.57664, "omega":-0.00051, "ax":0.0, "ay":-0.00001, "alpha":0.0, "fx":[-0.00008,-0.00008,-0.00008,-0.00008], "fy":[-0.00009,-0.00009,-0.00009,-0.00009]}, + {"t":2.18526, "x":2.42897, "y":6.23101, "heading":2.14021, "vx":3.01699, "vy":-2.57664, "omega":-0.00051, "ax":-0.23301, "ay":0.1971, "alpha":-0.48592, "fx":[-3.57874,-5.70303,-4.35074,-2.22118], "fy":[5.09616,3.73161,1.60837,2.9744]}, + {"t":2.21611, "x":2.52191, "y":6.15163, "heading":2.14019, "vx":3.0098, "vy":-2.57056, "omega":-0.0155, "ax":-4.64848, "ay":3.97405, "alpha":-3.23289, "fx":[-67.71752,-86.13427,-92.01765,-70.40812], "fy":[81.24113,61.81305,50.37345,76.96196]}, + {"t":2.24695, "x":2.61253, "y":6.07423, "heading":2.13971, "vx":2.86642, "vy":-2.44798, "omega":-0.11522, "ax":-4.82697, "ay":4.12231, "alpha":-0.93206, "fx":[-78.37103,-84.17567,-85.97756,-79.89716], "fy":[74.50101,67.9375,65.4062,72.63251]}, + {"t":2.2778, "x":2.69865, "y":6.00069, "heading":2.13616, "vx":2.71754, "vy":-2.32084, "omega":-0.14397, "ax":-4.86142, "ay":4.15173, "alpha":-0.36676, "fx":[-81.18228,-83.50912,-84.2217,-81.8525], "fy":[72.3933,69.71293,68.79386,71.57865]}, + {"t":2.30864, "x":2.78016, "y":5.93108, "heading":2.13172, "vx":2.56759, "vy":-2.19278, "omega":-0.15528, "ax":-4.87574, "ay":4.16397, "alpha":-0.11111, "fx":[-82.47206,-83.18195,-83.39976,-82.68605], "fy":[71.37284,70.54801,70.2781,71.11257]}, + {"t":2.33948, "x":2.85703, "y":5.86543, "heading":2.12693, "vx":2.41721, "vy":-2.06435, "omega":-0.15871, "ax":-4.88354, "ay":4.17063, "alpha":0.03451, "fx":[-83.2125,-82.99133,-82.92287,-83.14367], "fy":[70.77046,71.02874,71.11163,70.85428]}, + {"t":2.37033, "x":2.92926, "y":5.80374, "heading":2.12203, "vx":2.26658, "vy":-1.93571, "omega":-0.15764, "ax":-4.88843, "ay":4.17482, "alpha":0.12852, "fx":[-83.69358,-82.86896,-82.61057,-83.43028], "fy":[70.37204,71.33829,71.6464,70.69308]}, + {"t":2.40117, "x":2.99685, "y":5.74602, "heading":2.11717, "vx":2.1158, "vy":-1.80694, "omega":-0.15368, "ax":-4.89179, "ay":4.17769, "alpha":0.1942, "fx":[-84.03181,-82.7854,-82.3895,-83.62493], "fy":[70.08832,71.55234,72.01942,70.58489]}, + {"t":2.43202, "x":3.05978, "y":5.69227, "heading":2.11243, "vx":1.96492, "vy":-1.67808, "omega":-0.14769, "ax":-4.89423, "ay":4.17977, "alpha":0.24267, "fx":[-84.28297,-82.72589,-82.22428,-83.76459], "fy":[69.8755,71.70783,72.29499,70.50865]}, + {"t":2.46286, "x":3.11806, "y":5.6425, "heading":2.10788, "vx":1.81396, "vy":-1.54916, "omega":-0.1402, "ax":-4.89608, "ay":4.18136, "alpha":0.2799, "fx":[-84.47712,-82.68219,-82.09579,-83.86889], "fy":[69.70964,71.825,72.50727,70.45302]}, + {"t":2.4937, "x":3.17168, "y":5.59671, "heading":2.10355, "vx":1.66295, "vy":-1.42019, "omega":-0.13157, "ax":-4.89754, "ay":4.18261, "alpha":0.3094, "fx":[-84.63185,-82.64933,-81.9928,-83.94921], "fy":[69.57654,71.91583,72.67606,70.41132]}, + {"t":2.52455, "x":3.22064, "y":5.55489, "heading":2.09949, "vx":1.51189, "vy":-1.29119, "omega":-0.12203, "ax":-4.89872, "ay":4.18361, "alpha":0.33334, "fx":[-84.75816,-82.62412,-81.90827,-84.01261], "fy":[69.46724,71.9879,72.81363,70.37937]}, + {"t":2.55539, "x":3.26495, "y":5.51706, "heading":2.09573, "vx":1.36079, "vy":-1.16215, "omega":-0.11174, "ax":-4.89969, "ay":4.18444, "alpha":0.35316, "fx":[-84.86327,-82.60443,-81.83758,-84.06373], "fy":[69.37583,72.04624,72.92798,70.35439]}, + {"t":2.58623, "x":3.30459, "y":5.4832, "heading":2.09228, "vx":1.20967, "vy":-1.03308, "omega":-0.10085, "ax":-4.9005, "ay":4.18513, "alpha":0.36984, "fx":[-84.95211,-82.58876,-81.77757,-84.10572], "fy":[69.29823,72.09431,73.02457,70.3345]}, + {"t":2.61708, "x":3.33957, "y":5.45333, "heading":2.08917, "vx":1.05852, "vy":-0.904, "omega":-0.08944, "ax":-4.90119, "ay":4.18572, "alpha":0.38406, "fx":[-85.02817,-82.57605,-81.72601,-84.1408], "fy":[69.23156,72.13459,73.10721,70.31833]}, + {"t":2.64792, "x":3.36988, "y":5.42744, "heading":2.08641, "vx":0.90734, "vy":-0.77489, "omega":-0.0776, "ax":-4.90178, "ay":4.18623, "alpha":0.39634, "fx":[-85.09399,-82.56549,-81.68126,-84.1706], "fy":[69.1737,72.16889,73.17868,70.3049]}, + {"t":2.67877, "x":3.39554, "y":5.40553, "heading":2.08402, "vx":0.75615, "vy":-0.64577, "omega":-0.06537, "ax":-4.90229, "ay":4.18667, "alpha":0.40704, "fx":[-85.15145,-82.55649,-81.64212,-84.19633], "fy":[69.12307,72.19857,73.24105,70.29345]}, + {"t":2.70961, "x":3.41653, "y":5.3876, "heading":2.082, "vx":0.60495, "vy":-0.51664, "omega":-0.05282, "ax":-4.90274, "ay":4.18706, "alpha":0.41646, "fx":[-85.20198,-82.54858,-81.60767,-84.21889], "fy":[69.07849,72.22468,73.29586,70.28341]}, + {"t":2.74045, "x":3.43286, "y":5.37366, "heading":2.08037, "vx":0.45373, "vy":-0.38749, "omega":-0.03997, "ax":-4.90314, "ay":4.1874, "alpha":0.4248, "fx":[-85.2467,-82.5414,-81.5772,-84.23902], "fy":[69.03901,72.24802,73.34432,70.27435]}, + {"t":2.7713, "x":3.44452, "y":5.3637, "heading":2.07914, "vx":0.3025, "vy":-0.25834, "omega":-0.02687, "ax":-4.9035, "ay":4.1877, "alpha":0.43225, "fx":[-85.28647,-82.53466,-81.55015,-84.25726], "fy":[69.00391,72.26925,73.38736,70.2659]}, + {"t":2.80214, "x":3.45152, "y":5.35772, "heading":2.07831, "vx":0.15125, "vy":-0.12917, "omega":-0.01354, "ax":-4.90382, "ay":4.18797, "alpha":0.43893, "fx":[-85.32198,-82.52812,-81.52608,-84.27408], "fy":[68.9726,72.28887,73.42573,70.25778]}, + {"t":2.83299, "x":3.45385, "y":5.35573, "heading":2.07789, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[ + {"name":"Funnel", "from":{"target":2, "targetTimestamp":2.21611, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] +} diff --git a/src/main/deploy/v2_redundancy/choreo/A_RIGHT_PATH1.traj b/src/main/deploy/v2_redundancy/choreo/A_RIGHT_PATH1.traj new file mode 100644 index 00000000..112634ab --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/A_RIGHT_PATH1.traj @@ -0,0 +1,64 @@ +{ + "name":"A_RIGHT_PATH1", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.15808629989624, "y":2.0309269428253174, "heading":-1.5707963267948966, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":5.37649393081665, "y":2.7055675857543946, "heading":-1.102853734231975, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"7.15808629989624 m", "val":7.15808629989624}, "y":{"exp":"2.0309269428253174 m", "val":2.0309269428253174}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"5.37649393081665 m", "val":5.37649393081665}, "y":{"exp":"(8.0518 - 5.3462324142456055) m", "val":2.7055675857543946}, "heading":{"exp":"-1.102853734231975 rad", "val":-1.102853734231975}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.08949], + "samples":[ + {"t":0.0, "x":7.15809, "y":2.03093, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.01649, "ay":2.27816, "alpha":1.59134, "fx":[-98.19083,-101.01269,-105.78201,-104.36955], "fy":[48.99331,42.91447,29.22736,33.868]}, + {"t":0.03757, "x":7.15384, "y":2.03253, "heading":-1.5708, "vx":-0.22603, "vy":0.08559, "omega":0.05978, "ax":-6.01599, "ay":2.27797, "alpha":1.59069, "fx":[-98.18424,-101.0055,-105.77238,-104.35901], "fy":[48.98479,42.90966,29.22878,33.86708]}, + {"t":0.07514, "x":7.1411, "y":2.03736, "heading":-1.56855, "vx":-0.45204, "vy":0.17117, "omega":0.11954, "ax":-6.01541, "ay":2.27775, "alpha":1.58982, "fx":[-98.17279,-101.00576,-105.76437,-104.33873], "fy":[48.98247,42.88369,29.21868,33.89054]}, + {"t":0.11271, "x":7.11988, "y":2.0454, "heading":-1.56406, "vx":-0.67803, "vy":0.25674, "omega":0.17927, "ax":-6.01473, "ay":2.27749, "alpha":1.5887, "fx":[-98.15627,-101.01314,-105.75749,-104.30821], "fy":[48.9858,42.83635,29.19725,33.93835]}, + {"t":0.15027, "x":7.09016, "y":2.05665, "heading":-1.55732, "vx":-0.904, "vy":0.3423, "omega":0.23896, "ax":-6.01391, "ay":2.27718, "alpha":1.58729, "fx":[-98.13444,-101.02715,-105.75103,-104.26668], "fy":[48.99391,42.76731,29.16487,34.01054]}, + {"t":0.18784, "x":7.05195, "y":2.07111, "heading":-1.54835, "vx":-1.12993, "vy":0.42785, "omega":0.29859, "ax":-6.0129, "ay":2.2768, "alpha":1.58556, "fx":[-98.10694,-101.04711,-105.74398,-104.21309], "fy":[49.00554,42.67608,29.12207,34.10714]}, + {"t":0.22541, "x":7.00526, "y":2.0888, "heading":-1.53713, "vx":-1.35583, "vy":0.51339, "omega":0.35816, "ax":-6.01165, "ay":2.27633, "alpha":1.58341, "fx":[-98.0732,-101.07198,-105.73482,-104.14583], "fy":[49.01893,42.56198,29.06954,34.22814]}, + {"t":0.26298, "x":6.95008, "y":2.10969, "heading":-1.52367, "vx":-1.58168, "vy":0.59891, "omega":0.41764, "ax":-6.01004, "ay":2.27572, "alpha":1.58074, "fx":[-98.03215,-101.1001,-105.72127,-104.0625], "fy":[49.03157,42.42402,29.00819,34.37336]}, + {"t":0.30055, "x":6.88642, "y":2.13379, "heading":-1.50798, "vx":-1.80747, "vy":0.6844, "omega":0.47703, "ax":-6.00788, "ay":2.2749, "alpha":1.57738, "fx":[-97.98182,-101.12872,-105.6996,-103.95919], "fy":[49.03978,42.26063,28.93911,34.54228]}, + {"t":0.33812, "x":6.81427, "y":2.16111, "heading":-1.49006, "vx":-2.03317, "vy":0.76987, "omega":0.53629, "ax":-6.00485, "ay":2.27376, "alpha":1.57308, "fx":[-97.91819,-101.15283,-105.66334,-103.82908], "fy":[49.03777,42.06923,28.8636,34.73358]}, + {"t":0.37569, "x":6.73365, "y":2.19164, "heading":-1.46992, "vx":-2.25877, "vy":0.85529, "omega":0.59539, "ax":-6.0003, "ay":2.27205, "alpha":1.56734, "fx":[-97.83256,-101.16236,-105.5999,-103.65888], "fy":[49.01543,41.84497,28.78295,34.94406]}, + {"t":0.41325, "x":6.64456, "y":2.22537, "heading":-1.44755, "vx":-2.48419, "vy":0.94065, "omega":0.65427, "ax":-5.99269, "ay":2.26917, "alpha":1.55925, "fx":[-97.70313,-101.13381,-105.48065,-103.41816], "fy":[48.95216,41.57705,28.69757,35.16524]}, + {"t":0.45082, "x":6.547, "y":2.26231, "heading":-1.42297, "vx":-2.70933, "vy":1.02589, "omega":0.71285, "ax":-5.97741, "ay":2.2634, "alpha":1.54673, "fx":[-97.46079,-100.99644,-105.22186,-103.01704], "fy":[48.79387,41.23436,28.60144,35.36978]}, + {"t":0.48839, "x":6.441, "y":2.30245, "heading":-1.39619, "vx":-2.93389, "vy":1.11093, "omega":0.77096, "ax":-5.93147, "ay":2.24604, "alpha":1.52369, "fx":[-96.7438,-100.39652,-104.41662,-102.01337], "fy":[48.30803,40.66756,28.42889,35.41345]}, + {"t":0.52596, "x":6.32659, "y":2.34577, "heading":-1.36722, "vx":-3.15673, "vy":1.19531, "omega":0.8282, "ax":-0.0008, "ay":0.00281, "alpha":-0.10855, "fx":[-0.23259,0.31932,0.20539,-0.34651], "fy":[-0.28503,-0.17111,0.3808,0.26687]}, + {"t":0.56353, "x":6.208, "y":2.39068, "heading":-1.33611, "vx":-3.15676, "vy":1.19541, "omega":0.82412, "ax":5.93146, "ay":-2.24592, "alpha":-1.5256, "fx":[96.70697,100.61835,104.46736,101.77677], "fy":[-48.40524,-40.121,-28.20666,-36.07714]}, + {"t":0.6011, "x":6.09359, "y":2.43401, "heading":-1.30515, "vx":-2.93392, "vy":1.11104, "omega":0.76681, "ax":5.97742, "ay":-2.26341, "alpha":-1.5451, "fx":[97.3954,101.43954,105.32122,102.54092], "fy":[-48.94782,-40.13671,-28.19756,-36.71781]}, + {"t":0.63867, "x":5.98758, "y":2.47415, "heading":-1.27634, "vx":-2.70936, "vy":1.026, "omega":0.70876, "ax":5.99272, "ay":-2.26925, "alpha":-1.5554, "fx":[97.60927,101.78284,105.62689,102.71891], "fy":[-49.16204,-39.96639,-28.11931,-37.14936]}, + {"t":0.67623, "x":5.89003, "y":2.51109, "heading":-1.24971, "vx":-2.48422, "vy":0.94075, "omega":0.65032, "ax":6.00035, "ay":-2.27217, "alpha":-1.56175, "fx":[97.71297,102.00069,105.78917,102.75399], "fy":[-49.27569,-39.76211,-28.045,-37.51318]}, + {"t":0.7138, "x":5.80093, "y":2.54483, "heading":-1.22528, "vx":-2.25879, "vy":0.85539, "omega":0.59165, "ax":6.00491, "ay":-2.27393, "alpha":-1.56607, "fx":[97.77599,102.16335,105.89139,102.73658], "fy":[-49.34215,-39.55616,-27.98219,-37.83512]}, + {"t":0.75137, "x":5.72031, "y":2.57536, "heading":-1.20305, "vx":-2.0332, "vy":0.76996, "omega":0.53282, "ax":6.00795, "ay":-2.27511, "alpha":-1.56923, "fx":[97.8202,102.29413,105.96205,102.69737], "fy":[-49.38198,-39.35987,-27.93079,-38.12301]}, + {"t":0.78894, "x":5.64817, "y":2.60269, "heading":-1.18304, "vx":-1.80749, "vy":0.68449, "omega":0.47386, "ax":6.01011, "ay":-2.27595, "alpha":-1.57166, "fx":[97.85428,102.40303,106.01377,102.64978], "fy":[-49.40536,-39.17832,-27.88945,-38.37987]}, + {"t":0.82651, "x":5.5845, "y":2.62679, "heading":-1.16523, "vx":-1.5817, "vy":0.59899, "omega":0.41482, "ax":6.01173, "ay":-2.27658, "alpha":-1.5736, "fx":[97.88212,102.49506,106.05307,102.60069], "fy":[-49.41824,-39.01419,-27.85662,-38.6071]}, + {"t":0.86408, "x":5.52932, "y":2.64769, "heading":-1.14965, "vx":-1.35584, "vy":0.51346, "omega":0.3557, "ax":6.01298, "ay":-2.27708, "alpha":-1.57521, "fx":[97.90563,102.57303,106.08372,102.55401], "fy":[-49.42449,-38.86902,-27.83087,-38.80542]}, + {"t":0.90165, "x":5.48263, "y":2.66537, "heading":-1.13629, "vx":-1.12995, "vy":0.42791, "omega":0.29652, "ax":6.01398, "ay":-2.27747, "alpha":-1.57656, "fx":[97.92574,102.63866,106.1081,102.51213], "fy":[-49.42682,-38.74375,-27.8109,-38.97526]}, + {"t":0.93921, "x":5.44442, "y":2.67984, "heading":-1.12515, "vx":-0.90401, "vy":0.34235, "omega":0.23729, "ax":6.0148, "ay":-2.2778, "alpha":-1.57771, "fx":[97.94291,102.69306,106.1278,102.47662], "fy":[-49.42722,-38.639,-27.79563,-39.11692]}, + {"t":0.97678, "x":5.41471, "y":2.6911, "heading":-1.11623, "vx":-0.67804, "vy":0.25678, "omega":0.17802, "ax":6.01549, "ay":-2.27807, "alpha":-1.5787, "fx":[97.95737,102.73698,106.14393,102.44854], "fy":[-49.42718,-38.55518,-27.78413,-39.23061]}, + {"t":1.01435, "x":5.39348, "y":2.69914, "heading":-1.10954, "vx":-0.45205, "vy":0.17119, "omega":0.11871, "ax":6.01606, "ay":-2.27829, "alpha":-1.57956, "fx":[97.96923,102.77096,106.15727,102.42864], "fy":[-49.42781,-38.49259,-27.77564,-39.31649]}, + {"t":1.05192, "x":5.38074, "y":2.70396, "heading":-1.10508, "vx":-0.22603, "vy":0.0856, "omega":0.05937, "ax":6.01656, "ay":-2.27849, "alpha":-1.58029, "fx":[97.97856,102.79538,106.16841,102.41746], "fy":[-49.42996,-38.45143,-27.76962,-39.37469]}, + {"t":1.08949, "x":5.37649, "y":2.70557, "heading":-1.10285, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/v2_redundancy/choreo/A_RIGHT_PATH2.traj b/src/main/deploy/v2_redundancy/choreo/A_RIGHT_PATH2.traj new file mode 100644 index 00000000..81fbf791 --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/A_RIGHT_PATH2.traj @@ -0,0 +1,180 @@ +{ + "name":"A_RIGHT_PATH2", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":5.005142688751221, "y":2.817952858734131, "heading":-1.0513369818883893, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":4.582683086395264, "y":2.4232380264282227, "heading":0.0, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":3.5206298828125, "y":2.2525508277893067, "heading":0.0, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":1.924022912979126, "y":1.5354974143981934, "heading":-2.216612130911823, "intervals":15, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.3110252618789673, "y":0.8660395019531251, "heading":-2.216612130911823, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.76132869720459, "y":1.7727476358413696, "heading":0.0, "intervals":33, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":3.8275418281555176, "y":2.5679142349243165, "heading":-2.09887087685183, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":4.0}}, "enabled":true}, + {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"5.005142688751221 m", "val":5.005142688751221}, "y":{"exp":"(8.0518 - 5.233847141265869) m", "val":2.817952858734131}, "heading":{"exp":"-1.0513369818883893 rad", "val":-1.0513369818883893}, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"4.582683086395264 m", "val":4.582683086395264}, "y":{"exp":"(8.0518 - 5.628561973571777) m", "val":2.4232380264282227}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"3.5206298828125 m", "val":3.5206298828125}, "y":{"exp":"(8.0518 - 5.799249172210693) m", "val":2.2525508277893067}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"1.924022912979126 m", "val":1.924022912979126}, "y":{"exp":"(8.0518 - 6.516302585601807) m", "val":1.5354974143981934}, "heading":{"exp":"-2.216612130911823 rad", "val":-2.216612130911823}, "intervals":15, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"(8.0518 - 7.185760498046875) m", "val":0.8660395019531251}, "heading":{"exp":"-2.216612130911823 rad", "val":-2.216612130911823}, "intervals":36, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.76132869720459 m", "val":2.76132869720459}, "y":{"exp":"1.7727476358413696 m", "val":1.7727476358413696}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":33, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"3.8275418281555176 m", "val":3.8275418281555176}, "y":{"exp":"(8.0518 - 5.483885765075684) m", "val":2.5679142349243165}, "heading":{"exp":"-2.09887087685183 rad", "val":-2.09887087685183}, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"4 m / s", "val":4.0}}}, "enabled":true}, + {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.44714,0.79227,1.25189,1.7841,2.52107,3.16592], + "samples":[ + {"t":0.0, "x":5.00514, "y":2.81795, "heading":-1.05134, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-2.79278, "ay":-5.56686, "alpha":-5.4537, "fx":[-43.43733,-8.58369,-59.74256,-78.25422], "fy":[-100.75225,-109.3264,-91.8237,-76.86009]}, + {"t":0.02353, "x":5.00437, "y":2.81641, "heading":-1.05134, "vx":-0.06572, "vy":-0.13101, "omega":-0.12835, "ax":-2.97957, "ay":-5.45974, "alpha":-5.55849, "fx":[-45.84632,-11.58782,-64.70136,-80.59071], "fy":[-99.66973,-109.0342,-88.37633,-74.39401]}, + {"t":0.04707, "x":5.002, "y":2.81182, "heading":-1.05436, "vx":-0.13584, "vy":-0.2595, "omega":-0.25916, "ax":-3.18486, "ay":-5.3321, "alpha":-5.67263, "fx":[-48.60897,-15.08349,-69.89214,-83.10989], "fy":[-98.34136,-108.58919,-84.3049,-71.55438]}, + {"t":0.0706, "x":4.99792, "y":2.80423, "heading":-1.06046, "vx":-0.2108, "vy":-0.38498, "omega":-0.39265, "ax":-3.41043, "ay":-5.17919, "alpha":-5.795, "fx":[-51.76485,-19.16419,-75.30109,-85.81152], "fy":[-96.7054,-107.92484,-79.48139,-68.27464]}, + {"t":0.09413, "x":4.99201, "y":2.79374, "heading":-1.0697, "vx":-0.29105, "vy":-0.50686, "omega":-0.52903, "ax":-3.65776, "ay":-4.99514, "alpha":-5.92309, "fx":[-55.35657,-23.9442,-80.88279,-88.68635], "fy":[-94.68153,-106.94425,-73.76066,-64.47737]}, + {"t":0.11767, "x":4.98415, "y":2.78043, "heading":-1.08215, "vx":-0.37714, "vy":-0.62442, "omega":-0.66842, "ax":-3.92782, "ay":-4.77278, "alpha":-6.05173, "fx":[-59.42751,-29.56006,-86.54492,-91.71173], "fy":[-92.16517,-105.50505,-66.99007,-60.07423]}, + {"t":0.1412, "x":4.97419, "y":2.76441, "heading":-1.09788, "vx":-0.46957, "vy":-0.73674, "omega":-0.81084, "ax":-4.22056, "ay":-4.50353, "alpha":-6.17126, "fx":[-64.01698,-36.16742,-92.13207,-94.84559], "fy":[-89.02047,-103.39737,-59.02972,-54.96751]}, + {"t":0.16474, "x":4.96197, "y":2.74583, "heading":-1.11696, "vx":-0.5689, "vy":-0.84272, "omega":-0.95607, "ax":-4.53434, "ay":-4.17742, "alpha":-6.26494, "fx":[-69.15122,-43.92656,-97.41468,-98.0191], "fy":[-85.07255,-100.31325,-49.78661,-49.05466]}, + {"t":0.18827, "x":4.94732, "y":2.72484, "heading":-1.13946, "vx":-0.67561, "vy":-0.94103, "omega":-1.10351, "ax":-4.86506, "ay":-3.78328, "alpha":-6.30632, "fx":[-74.82756,-52.96378,-102.09326,-101.12841], "fy":[-80.10063,-95.80992,-39.26189,-42.23761]}, + {"t":0.2118, "x":4.93008, "y":2.70164, "heading":-1.16543, "vx":-0.7901, "vy":-1.03007, "omega":-1.25192, "ax":-5.20488, "ay":-3.30925, "alpha":-6.25843, "fx":[-80.98871,-63.28714,-105.83019,-104.02774], "fy":[-73.83637,-89.28185,-27.60034,-34.43877]}, + {"t":0.23534, "x":4.91004, "y":2.67649, "heading":-1.19489, "vx":-0.91259, "vy":-1.10794, "omega":-1.3992, "ax":-5.54038, "ay":-2.74412, "alpha":-6.07853, "fx":[-87.48502,-74.63474,-108.31391,-106.52731], "fy":[-65.97577,-79.98657,-15.11927,-25.62487]}, + {"t":0.25887, "x":4.88703, "y":2.64965, "heading":-1.22782, "vx":-1.04297, "vy":-1.17252, "omega":-1.54225, "ax":-5.85024, "ay":-2.08058, "alpha":-5.73244, "fx":[-94.02802,-86.2719,-109.34148,-108.40218], "fy":[-56.21868,-67.21494,-2.28968,-15.83678]}, + {"t":0.2824, "x":4.86087, "y":2.62148, "heading":-1.26411, "vx":-1.18065, "vy":-1.22149, "omega":-1.67716, "ax":-6.10433, "ay":-1.32164, "alpha":-5.21641, "fx":[-100.15151,-96.87868,-108.88441,-109.41734], "fy":[-44.35182,-50.69389,10.34077,-5.21794]}, + {"t":0.30594, "x":4.83139, "y":2.59237, "heading":-1.30358, "vx":-1.32431, "vy":-1.25259, "omega":-1.79992, "ax":-6.26855, "ay":-0.48867, "alpha":-4.57046, "fx":[-105.21786,-104.81538,-107.10127,-109.37028], "fy":[-30.37847,-31.10114,22.25903,5.97184]}, + {"t":0.32947, "x":4.79849, "y":2.56276, "heading":-1.34594, "vx":-1.47183, "vy":-1.26409, "omega":-1.90748, "ax":-6.31722, "ay":0.37645, "alpha":-3.86259, "fx":[-108.51823,-108.8675,-104.28866,-108.14172], "fy":[-14.65594,-10.18632,33.08398,17.37155]}, + {"t":0.353, "x":4.7621, "y":2.53311, "heading":-1.39083, "vx":-1.62049, "vy":-1.25523, "omega":-1.99838, "ax":-6.24545, "ay":1.22188, "alpha":-3.15251, "fx":[-109.47894,-108.92086,-100.79814,-105.73534], "fy":[2.05431,9.90193,42.6108,28.56827]}, + {"t":0.37654, "x":4.72224, "y":2.50391, "heading":-1.43786, "vx":-1.76747, "vy":-1.22648, "omega":-2.07257, "ax":-6.07018, "ay":2.00278, "alpha":-2.4727, "fx":[-107.88873,-105.87308,-96.95944,-102.28653], "fy":[18.71897,27.58205,50.79818,39.16756]}, + {"t":0.40007, "x":4.67896, "y":2.4756, "heading":-1.48664, "vx":-1.91032, "vy":-1.17934, "omega":-2.13076, "ax":-5.82061, "ay":2.6918, "alpha":-1.83703, "fx":[-103.99229,-100.96617,-93.03488,-98.03406], "fy":[34.32221,42.2438,57.72194,48.85905]}, + {"t":0.4236, "x":4.63239, "y":2.44859, "heading":-1.53678, "vx":-2.0473, "vy":-1.116, "omega":-2.17399, "ax":-5.52752, "ay":3.27947, "alpha":-1.25361, "fx":[-98.37582,-95.23662,-89.20633,-93.26743], "fy":[48.14332,54.01205,63.52271,57.45355]}, + {"t":0.44714, "x":4.58268, "y":2.42324, "heading":-1.58794, "vx":-2.17739, "vy":-1.03882, "omega":-2.20349, "ax":-5.36296, "ay":3.53055, "alpha":-0.94655, "fx":[-94.80946,-92.16127,-87.3706,-90.5486], "fy":[54.45181,58.74218,65.70383,61.31709]}, + {"t":0.46214, "x":4.54941, "y":2.40805, "heading":-1.62101, "vx":-2.25786, "vy":-0.98584, "omega":-2.2177, "ax":-5.36262, "ay":3.53348, "alpha":-0.68294, "fx":[-93.80918,-91.955,-88.48202,-90.62064], "fy":[56.09605,59.02542,64.14865,61.14368]}, + {"t":0.47715, "x":4.51492, "y":2.39365, "heading":-1.65428, "vx":-2.33833, "vy":-0.93282, "omega":-2.22795, "ax":-5.36133, "ay":3.53597, "alpha":-0.38778, "fx":[-92.67071,-91.64556,-89.6716,-90.79089], "fy":[57.88919,59.46255,62.41887,60.813]}, + {"t":0.49215, "x":4.47923, "y":2.38005, "heading":-1.68772, "vx":-2.41878, "vy":-0.87976, "omega":-2.23376, "ax":-5.35871, "ay":3.53781, "alpha":-0.05557, "fx":[-91.36249,-91.21881,-90.9368,-91.08245], "fy":[59.85626,60.06955,60.49835,60.28423]}, + {"t":0.50716, "x":4.44233, "y":2.36725, "heading":-1.72123, "vx":-2.49919, "vy":-0.82667, "omega":-2.2346, "ax":-5.35426, "ay":3.53864, "alpha":0.32076, "fx":[-89.84193,-90.65768,-92.27333,-91.52446], "fy":[62.02929,60.86371,58.36974,59.50219]}, + {"t":0.52217, "x":4.40423, "y":2.35524, "heading":-1.75477, "vx":-2.57953, "vy":-0.77357, "omega":-2.22978, "ax":-5.34725, "ay":3.53795, "alpha":0.75062, "fx":[-88.0504,-89.9414,-93.67484,-92.15391], "fy":[64.44956,61.86368,56.01437,58.39034]}, + {"t":0.53717, "x":4.36492, "y":2.34403, "heading":-1.78823, "vx":-2.65977, "vy":-0.72048, "omega":-2.21852, "ax":-5.33666, "ay":3.53491, "alpha":1.24696, "fx":[-85.90534,-89.04461,-95.13257,-93.01791], "fy":[67.1704,63.08937,53.41217,56.83953]}, + {"t":0.55218, "x":4.32441, "y":2.33362, "heading":-1.82152, "vx":-2.73985, "vy":-0.66744, "omega":-2.19981, "ax":-5.32101, "ay":3.52817, "alpha":1.82829, "fx":[-83.28792,-87.93647,-96.63495,-94.17605], "fy":[70.2604,64.56146,50.54164,54.68928]}, + {"t":0.56718, "x":4.28269, "y":2.324, "heading":-1.85452, "vx":-2.8197, "vy":-0.6145, "omega":-2.17238, "ax":-5.29803, "ay":3.51537, "alpha":2.52205, "fx":[-80.02341,-86.58,-98.16702,-95.70132], "fy":[73.80585,66.3001,47.3799,51.69578]}, + {"t":0.58219, "x":4.23979, "y":2.31518, "heading":-1.88712, "vx":-2.8992, "vy":-0.56175, "omega":-2.13453, "ax":-5.26417, "ay":3.49227, "alpha":3.37011, "fx":[-75.85104,-84.93278,-99.70958,-97.67437], "fy":[77.90858,68.32153,43.9035,47.47647]}, + {"t":0.59719, "x":4.19569, "y":2.30714, "heading":-1.91915, "vx":-2.97819, "vy":-0.50934, "omega":-2.08396, "ax":-5.2136, "ay":3.45103, "alpha":4.43742, "fx":[-70.38404,-82.95205,-101.23754,-100.15393], "fy":[82.66652,70.6296,40.09119,41.41683]}, + {"t":0.6122, "x":4.15041, "y":2.29989, "heading":-1.95042, "vx":-3.05642, "vy":-0.45756, "omega":-2.01737, "ax":-5.13671, "ay":3.377, "alpha":5.82123, "fx":[-63.0931,-80.61587,-102.71622,-103.07072], "fy":[88.09809,73.19179,35.93424,32.54338]}, + {"t":0.6272, "x":4.10397, "y":2.2934, "heading":-1.98069, "vx":-3.1335, "vy":-0.40689, "omega":-1.93002, "ax":-5.02004, "ay":3.24518, "alpha":7.63047, "fx":[-53.54402,-78.0092,-104.09099,-105.91373], "fy":[93.89349,75.85765,31.47723,19.57006]}, + {"t":0.64221, "x":4.05639, "y":2.28766, "heading":-2.00966, "vx":-3.20883, "vy":-0.35819, "omega":-1.81552, "ax":-4.87024, "ay":3.0321, "alpha":9.73983, "fx":[-43.16052,-75.70044,-105.25361,-107.2513], "fy":[98.71431,78.02938,26.98798,2.56894]}, + {"t":0.65722, "x":4.00769, "y":2.28263, "heading":-2.0369, "vx":-3.28191, "vy":-0.31269, "omega":-1.66937, "ax":-4.80404, "ay":2.77599, "alpha":11.15149, "fx":[-39.18457,-75.3508,-106.05664,-106.26924], "fy":[99.8739,78.17166,23.09113,-12.26122]}, + {"t":0.67222, "x":3.9579, "y":2.27825, "heading":-2.06195, "vx":-3.354, "vy":-0.27104, "omega":-1.50204, "ax":-4.85187, "ay":2.49774, "alpha":11.71239, "fx":[-42.34021,-76.91794,-106.68953,-104.16834], "fy":[97.89477,76.34583,19.09808,-23.39531]}, + {"t":0.68723, "x":3.90703, "y":2.27446, "heading":-2.08449, "vx":-3.4268, "vy":-0.23356, "omega":-1.32629, "ax":-4.93137, "ay":2.15075, "alpha":12.06277, "fx":[-48.17254,-79.4015,-107.29863,-100.65191], "fy":[94.08518,73.362,13.84211,-34.95488]}, + {"t":0.70223, "x":3.85505, "y":2.2712, "heading":-2.10439, "vx":-3.5008, "vy":-0.20128, "omega":-1.14528, "ax":-5.00684, "ay":1.6899, "alpha":12.37017, "fx":[-55.72004,-82.60328,-107.74239,-94.59416], "fy":[87.84009,69.16031,6.52119,-48.54293]}, + {"t":0.71724, "x":3.80195, "y":2.26837, "heading":-2.12157, "vx":-3.57593, "vy":-0.17593, "omega":-0.95966, "ax":-5.04595, "ay":1.0446, "alpha":12.59207, "fx":[-65.12841,-86.45634,-107.56515,-84.17092], "fy":[76.14346,63.38183,-3.81511,-64.63674]}, + {"t":0.73224, "x":3.74773, "y":2.26585, "heading":-2.13598, "vx":-3.65165, "vy":-0.16025, "omega":-0.77071, "ax":-5.00386, "ay":-0.17846, "alpha":12.16723, "fx":[-76.4678,-90.87026,-105.7112,-67.40758], "fy":[32.65721,55.31922,-18.23806,-81.88038]}, + {"t":0.74725, "x":3.69237, "y":2.26342, "heading":-2.14754, "vx":-3.72673, "vy":-0.16293, "omega":-0.58813, "ax":-4.44844, "ay":-2.68505, "alpha":11.48289, "fx":[-45.17163,-101.26348,-100.11359,-56.11801], "fy":[-83.26908,27.66436,-37.12139,-89.96162]}, + {"t":0.76225, "x":3.63595, "y":2.26068, "heading":-2.15637, "vx":-3.79348, "vy":-0.20322, "omega":-0.41582, "ax":-3.61404, "ay":-4.17631, "alpha":9.77775, "fx":[-17.28261,-100.3131,-86.88839,-41.41106], "fy":[-100.34742,-24.83415,-61.26088,-97.70893]}, + {"t":0.77726, "x":3.57862, "y":2.25716, "heading":-2.1626, "vx":-3.84771, "vy":-0.26589, "omega":-0.2691, "ax":-2.22155, "ay":-5.46368, "alpha":6.4529, "fx":[2.78301,-66.47301,-64.34218,-23.11979], "fy":[-104.38928,-79.02834,-84.45268,-103.87203]}, + {"t":0.79227, "x":3.52063, "y":2.25255, "heading":-2.16664, "vx":-3.88105, "vy":-0.34787, "omega":-0.17227, "ax":-1.20433, "ay":-5.95493, "alpha":4.37991, "fx":[10.03436,-35.36842,-44.75473,-11.85242], "fy":[-104.89599,-98.06687,-96.29951,-105.90392]}, + {"t":0.80868, "x":3.45676, "y":2.24604, "heading":-2.16947, "vx":-3.90082, "vy":-0.44562, "omega":-0.10038, "ax":-0.41358, "ay":-6.09746, "alpha":2.91966, "fx":[13.59958,-13.29211,-25.70816,-2.73877], "fy":[-103.96771,-103.05165,-102.11265,-105.73199]}, + {"t":0.8251, "x":3.39267, "y":2.2379, "heading":-2.17112, "vx":-3.90761, "vy":-0.54571, "omega":-0.05245, "ax":0.3402, "ay":-6.10513, "alpha":1.48093, "fx":[16.11546,4.29614,-4.31628,7.05147], "fy":[-102.98016,-103.59571,-104.28172,-104.52862]}, + {"t":0.84151, "x":3.32857, "y":2.22812, "heading":-2.17198, "vx":-3.90202, "vy":-0.64593, "omega":-0.02814, "ax":0.86101, "ay":-6.02184, "alpha":0.54742, "fx":[18.39711,14.45347,10.89679,14.83478], "fy":[-101.85465,-102.25787,-102.94669,-102.65975]}, + {"t":0.85793, "x":3.26464, "y":2.21671, "heading":-2.17244, "vx":-3.88789, "vy":-0.74478, "omega":-0.01916, "ax":1.14666, "ay":-5.92562, "alpha":0.16621, "fx":[20.62605,19.49853,18.3815,19.51131], "fy":[-100.57395,-100.718,-101.00712,-100.87302]}, + {"t":0.87434, "x":3.20097, "y":2.20368, "heading":-2.17276, "vx":-3.86907, "vy":-0.84205, "omega":-0.01643, "ax":1.32374, "ay":-5.83293, "alpha":0.05081, "fx":[22.85425,22.52409,22.17846,22.50899], "fy":[-99.14063,-99.18773,-99.29183,-99.24558]}, + {"t":0.89076, "x":3.13764, "y":2.18907, "heading":-2.17303, "vx":-3.84734, "vy":-0.9378, "omega":-0.01559, "ax":1.464, "ay":-5.73907, "alpha":0.0197, "fx":[25.03115,24.90802,24.77331,24.89652], "fy":[-97.58776,-97.6066,-97.65195,-97.63323]}, + {"t":0.90717, "x":3.07468, "y":2.17291, "heading":-2.17328, "vx":-3.82331, "vy":-1.03201, "omega":-0.01527, "ax":1.591, "ay":-5.64302, "alpha":0.01036, "fx":[27.12901,27.06671,26.99574,27.05807], "fy":[-95.96795,-95.97798,-96.00425,-95.99426]}, + {"t":0.92359, "x":3.01214, "y":2.15521, "heading":-2.17353, "vx":-3.79719, "vy":-1.12464, "omega":-0.0151, "ax":1.71187, "ay":-5.54772, "alpha":0.00604, "fx":[29.15658,29.12162,29.08024,29.1152], "fy":[-94.35393,-94.35978,-94.37645,-94.3706]}, + {"t":0.94, "x":2.95003, "y":2.136, "heading":-2.17378, "vx":-3.76909, "vy":-1.2157, "omega":-0.015, "ax":1.83008, "ay":-5.45821, "alpha":0.00284, "fx":[31.14679,31.13097,31.11152,31.12734], "fy":[-92.837,-92.83975,-92.84819,-92.84544]}, + {"t":0.95642, "x":2.88841, "y":2.11531, "heading":-2.17403, "vx":-3.73905, "vy":-1.3053, "omega":-0.01495, "ax":1.94882, "ay":-5.38005, "alpha":-0.00009, "fx":[33.14835,33.14885,33.14949,33.14899], "fy":[-91.51326,-91.51317,-91.51287,-91.51296]}, + {"t":0.97283, "x":2.8273, "y":2.09316, "heading":-2.17427, "vx":-3.70706, "vy":-1.39361, "omega":-0.01496, "ax":2.07136, "ay":-5.31767, "alpha":-0.00297, "fx":[35.21525,35.23064,35.25114,35.23576], "fy":[-90.45848,-90.45549,-90.44546,-90.44845]}, + {"t":0.98925, "x":2.76672, "y":2.06956, "heading":-2.17452, "vx":-3.67306, "vy":-1.4809, "omega":-0.015, "ax":2.20039, "ay":-5.27276, "alpha":-0.00596, "fx":[37.39253,37.42224,37.4636,37.43391], "fy":[-89.70186,-89.6956,-89.67439,-89.68066]}, + {"t":1.00566, "x":2.70673, "y":2.04454, "heading":-2.17476, "vx":-3.63694, "vy":-1.56746, "omega":-0.0151, "ax":2.33746, "ay":-5.2435, "alpha":-0.00948, "fx":[39.70351,39.74902,39.81554,39.77007], "fy":[-89.21352,-89.2029,-89.16735,-89.17797]}, + {"t":1.02208, "x":2.64734, "y":2.01811, "heading":-2.17501, "vx":-3.59857, "vy":-1.65353, "omega":-0.01526, "ax":2.4831, "ay":-5.22487, "alpha":-0.01581, "fx":[42.1442,42.21704,42.32928,42.25656], "fy":[-88.9143,-88.89529,-88.83294,-88.85196]}, + {"t":1.03849, "x":2.5886, "y":1.99026, "heading":-2.17526, "vx":-3.55781, "vy":-1.7393, "omega":-0.01552, "ax":2.6395, "ay":-5.20894, "alpha":-0.03693, "fx":[44.68312,44.84566,45.11093,44.94909], "fy":[-88.70314,-88.65547,-88.50212,-88.54985]}, + {"t":1.05491, "x":2.53056, "y":1.96101, "heading":-2.17552, "vx":-3.51448, "vy":-1.8248, "omega":-0.01612, "ax":2.82163, "ay":-5.18022, "alpha":-0.12986, "fx":[47.25154,47.79315,48.73383,48.20162], "fy":[-88.48952,-88.31077,-87.73847,-87.91725]}, + {"t":1.07132, "x":2.47325, "y":1.93035, "heading":-2.17578, "vx":-3.46816, "vy":-1.90984, "omega":-0.01826, "ax":3.09263, "ay":-5.0911, "alpha":-0.51363, "fx":[49.72667,51.7146,55.40197,53.57565], "fy":[-88.20772,-87.46626,-84.99749,-85.72087]}, + {"t":1.08774, "x":2.41673, "y":1.89832, "heading":-2.17608, "vx":-3.4174, "vy":-1.99341, "omega":-0.02669, "ax":3.59155, "ay":-4.80276, "alpha":-1.6836, "fx":[52.14371,57.88024,69.0902,65.25085], "fy":[-87.68462,-85.23078,-76.03048,-77.82843]}, + {"t":1.10415, "x":2.36112, "y":1.86495, "heading":-2.17652, "vx":-3.35844, "vy":-2.07225, "omega":-0.05432, "ax":4.28537, "ay":-4.16878, "alpha":-3.75164, "fx":[55.45368,65.78217,86.04152,84.29439], "fy":[-86.25745,-81.15517,-58.86123,-57.36535]}, + {"t":1.12057, "x":2.30657, "y":1.83037, "heading":-2.17741, "vx":-3.2881, "vy":-2.14068, "omega":-0.11591, "ax":4.8644, "ay":-3.34972, "alpha":-5.81584, "fx":[61.41057,73.23858,97.11342,99.20585], "fy":[-82.67662,-76.05415,-41.45003,-27.7302]}, + {"t":1.13698, "x":2.25325, "y":1.79478, "heading":-2.17931, "vx":-3.20825, "vy":-2.19566, "omega":-0.21137, "ax":5.35167, "ay":-2.54613, "alpha":-6.24775, "fx":[75.35128,81.7854,102.59341,104.39136], "fy":[-71.23335,-67.91148,-28.54509,-5.54571]}, + {"t":1.1534, "x":2.20131, "y":1.7584, "heading":-2.18278, "vx":-3.1204, "vy":-2.23746, "omega":-0.31393, "ax":5.98288, "ay":-1.52462, "alpha":-3.31317, "fx":[98.73002,96.95917,105.32755,106.05177], "fy":[-37.25993,-44.52969,-18.51879,-3.42524]}, + {"t":1.16981, "x":2.15089, "y":1.72146, "heading":-2.18794, "vx":-3.02219, "vy":-2.26248, "omega":-0.36832, "ax":6.25649, "ay":-0.66624, "alpha":-0.84994, "fx":[106.15494,105.78911,106.80412,106.93638], "fy":[-13.0561,-17.06394,-9.79838,-5.41207]}, + {"t":1.18623, "x":2.10213, "y":1.68423, "heading":-2.19398, "vx":-2.91949, "vy":-2.27342, "omega":-0.38227, "ax":6.32257, "ay":-0.07036, "alpha":0.82385, "fx":[107.74837,107.51474,107.4846,107.43252], "fy":[-0.22726,4.69472,-2.27683,-6.97806]}, + {"t":1.20264, "x":2.05505, "y":1.64691, "heading":-2.20026, "vx":-2.8157, "vy":-2.27458, "omega":-0.36875, "ax":6.31232, "ay":0.34268, "alpha":1.96614, "fx":[107.98262,106.11391,107.6452,107.74098], "fy":[7.15265,20.07477,4.17875,-8.09036]}, + {"t":1.21906, "x":2.00968, "y":1.60961, "heading":-2.20631, "vx":-2.71208, "vy":-2.26895, "omega":-0.33647, "ax":6.27757, "ay":0.63833, "alpha":2.76381, "fx":[107.87911,103.81646,107.47375,107.94912], "fy":[11.81291,30.79778,9.72216,-8.90169]}, + {"t":1.23547, "x":1.96601, "y":1.57245, "heading":-2.21183, "vx":-2.60904, "vy":-2.25847, "omega":-0.2911, "ax":6.23718, "ay":0.85822, "alpha":3.34173, "fx":[107.69901,101.47635,107.09682,108.0984], "fy":[14.97719,38.43672,14.49319,-9.51456]}, + {"t":1.25189, "x":1.92402, "y":1.5355, "heading":-2.21661, "vx":-2.50665, "vy":-2.24439, "omega":-0.23625, "ax":6.17118, "ay":1.60969, "alpha":2.5856, "fx":[106.30974,99.65311,104.95663,108.96042], "fy":[25.77389,44.96083,30.11529,8.67121]}, + {"t":1.28737, "x":1.83897, "y":1.45688, "heading":-2.22499, "vx":-2.28769, "vy":-2.18727, "omega":-0.14451, "ax":5.85735, "ay":2.59068, "alpha":1.92085, "fx":[101.46976,94.12965,98.08117,104.8469], "fy":[41.01736,55.77777,48.30297,31.16848]}, + {"t":1.32285, "x":1.76149, "y":1.3809, "heading":-2.23012, "vx":-2.07987, "vy":-2.09535, "omega":-0.07636, "ax":5.53561, "ay":3.25428, "alpha":1.40081, "fx":[96.22344,89.47725,92.02458,98.91123], "fy":[52.25512,63.08598,59.21224,46.86442]}, + {"t":1.35833, "x":1.69118, "y":1.30861, "heading":-2.23283, "vx":-1.88346, "vy":-1.97989, "omega":-0.02665, "ax":5.25086, "ay":3.71369, "alpha":1.00404, "fx":[91.28252,85.66627,87.22297,93.0908], "fy":[60.55024,68.25202,66.19789,57.67538]}, + {"t":1.39381, "x":1.62765, "y":1.24069, "heading":-2.23378, "vx":-1.69715, "vy":-1.84812, "omega":0.00897, "ax":5.01014, "ay":4.04253, "alpha":0.6999, "fx":[86.88564,82.54776,83.46284,87.98783], "fy":[66.76392,72.05217,70.95992,65.27307]}, + {"t":1.42929, "x":1.57059, "y":1.17767, "heading":-2.23346, "vx":-1.51939, "vy":-1.70469, "omega":0.0338, "ax":4.80894, "ay":4.2859, "alpha":0.46264, "fx":[83.06137,79.97574,80.48482,83.67309], "fy":[71.51038,74.94253,74.37864,70.7763]}, + {"t":1.46477, "x":1.51971, "y":1.11988, "heading":-2.23226, "vx":-1.34876, "vy":-1.55262, "omega":0.05022, "ax":4.64048, "ay":4.47153, "alpha":0.27378, "fx":[79.75988,77.83192,78.08586,80.0552], "fy":[75.2105,77.20277,76.93724,74.88727]}, + {"t":1.50026, "x":1.47477, "y":1.06761, "heading":-2.23048, "vx":-1.18412, "vy":-1.39397, "omega":0.05993, "ax":4.49843, "ay":4.61686, "alpha":0.12052, "fx":[76.90991,76.02529,76.11978,77.0132], "fy":[78.1512,79.01165,78.91725,78.04602]}, + {"t":1.53574, "x":1.43559, "y":1.02105, "heading":-2.22835, "vx":-1.02451, "vy":-1.23016, "omega":0.06421, "ax":4.37761, "ay":4.73323, "alpha":-0.00602, "fx":[74.44103,74.4867,74.4827,74.43706], "fy":[80.53003,80.48781,80.49166,80.53386]}, + {"t":1.57122, "x":1.402, "y":0.98039, "heading":-2.22607, "vx":-0.86919, "vy":-1.06222, "omega":0.06399, "ax":4.2739, "ay":4.8282, "alpha":-0.11209, "fx":[72.29116,73.16348,73.10024,72.23648], "fy":[82.48519,81.71263,81.77174,82.5356]}, + {"t":1.6067, "x":1.37385, "y":0.94574, "heading":-2.2238, "vx":-0.71754, "vy":-0.89091, "omega":0.06002, "ax":4.1841, "ay":4.907, "alpha":-0.20218, "fx":[70.40798,72.01513,71.91833,70.34006], "fy":[84.11515,82.74359,82.83192,84.17608]}, + {"t":1.64218, "x":1.35102, "y":0.91721, "heading":-2.22167, "vx":-0.56909, "vy":-0.7168, "omega":0.05284, "ax":4.1057, "ay":4.97332, "alpha":-0.27958, "fx":[68.74827,71.01018,70.89701,68.69196], "fy":[85.4914,83.62233,83.72363,85.54188]}, + {"t":1.67766, "x":1.33341, "y":0.89491, "heading":-2.2198, "vx":-0.42341, "vy":-0.54035, "omega":0.04292, "ax":4.03674, "ay":5.02984, "alpha":-0.34675, "fx":[67.27661,70.12392,70.00623,67.24849], "fy":[86.66675,84.3797,84.48348,86.69455]}, + {"t":1.71314, "x":1.32093, "y":0.87891, "heading":-2.21827, "vx":-0.28019, "vy":-0.36188, "omega":0.03062, "ax":3.97565, "ay":5.07852, "alpha":-0.40557, "fx":[65.96398,69.33665,69.22308,65.97531], "fy":[87.68087,85.039,85.13813,87.67882]}, + {"t":1.74862, "x":1.31349, "y":0.86926, "heading":-2.21719, "vx":-0.13913, "vy":-0.18169, "omega":0.01623, "ax":3.9212, "ay":5.12086, "alpha":-0.45748, "fx":[64.78652,68.63257,68.52978,64.84527], "fy":[88.56407,85.61815,85.70747,88.52788]}, + {"t":1.7841, "x":1.31103, "y":0.86604, "heading":-2.21661, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.34201, "ay":3.61269, "alpha":0.40718, "fx":[91.59705,89.37406,90.11985,92.37347], "fy":[60.39922,63.63948,62.56939,59.19527]}, + {"t":1.81481, "x":1.31354, "y":0.86774, "heading":-2.21661, "vx":0.16404, "vy":0.11093, "omega":0.0125, "ax":5.34166, "ay":3.61245, "alpha":0.40111, "fx":[91.58035,89.39036,90.12501,92.34473], "fy":[60.41055,63.60318,62.54798,59.22547]}, + {"t":1.84552, "x":1.3211, "y":0.87285, "heading":-2.21623, "vx":0.32806, "vy":0.22186, "omega":0.02482, "ax":5.34127, "ay":3.61219, "alpha":0.39435, "fx":[91.56122,89.4082,90.13133,92.31301], "fy":[60.42399,63.56318,62.52333,59.25865]}, + {"t":1.87622, "x":1.33369, "y":0.88137, "heading":-2.21547, "vx":0.49208, "vy":0.33278, "omega":0.03693, "ax":5.34083, "ay":3.61189, "alpha":0.38678, "fx":[91.53934,89.42793,90.13885,92.27769], "fy":[60.4397,63.5187,62.49509,59.29546]}, + {"t":1.90693, "x":1.35132, "y":0.89329, "heading":-2.21433, "vx":0.65608, "vy":0.44369, "omega":0.04881, "ax":5.34033, "ay":3.61156, "alpha":0.37825, "fx":[91.51432,89.44997,90.14766,92.23803], "fy":[60.4579,63.46877,62.46278,59.33666]}, + {"t":1.93764, "x":1.37398, "y":0.90862, "heading":-2.21283, "vx":0.82006, "vy":0.55459, "omega":0.06042, "ax":5.33977, "ay":3.61117, "alpha":0.36856, "fx":[91.48568,89.4749,90.15785,92.19307], "fy":[60.47889,63.41216,62.42582,59.38328]}, + {"t":1.96834, "x":1.40168, "y":0.92735, "heading":-2.21098, "vx":0.98403, "vy":0.66548, "omega":0.07174, "ax":5.33912, "ay":3.61074, "alpha":0.35745, "fx":[91.45278,89.5034,90.16954,92.14159], "fy":[60.50302,63.34727,62.38345,59.43658]}, + {"t":1.99905, "x":1.43442, "y":0.94949, "heading":-2.20878, "vx":1.14798, "vy":0.77636, "omega":0.08271, "ax":5.33836, "ay":3.61023, "alpha":0.34461, "fx":[91.41475,89.53642,90.18291,92.08197], "fy":[60.53079,63.27202,62.33467,59.49824]}, + {"t":2.02976, "x":1.47218, "y":0.97503, "heading":-2.20624, "vx":1.31191, "vy":0.88722, "omega":0.0933, "ax":5.33748, "ay":3.60963, "alpha":0.32957, "fx":[91.37046,89.57519,90.19818,92.01205], "fy":[60.56287,63.18361,62.27812,59.57051]}, + {"t":2.06047, "x":1.51499, "y":1.00397, "heading":-2.20337, "vx":1.4758, "vy":0.99806, "omega":0.10342, "ax":5.33642, "ay":3.60892, "alpha":0.31174, "fx":[91.31832,89.6214,90.21566,91.92887], "fy":[60.60017,63.0782,62.21198,59.65642]}, + {"t":2.09117, "x":1.56282, "y":1.03632, "heading":-2.20019, "vx":1.63967, "vy":1.10888, "omega":0.11299, "ax":5.33515, "ay":3.60806, "alpha":0.29025, "fx":[91.2561,89.6774,90.23579,91.82825], "fy":[60.64399,62.95038,62.13363,59.76024]}, + {"t":2.12188, "x":1.61568, "y":1.07207, "heading":-2.19673, "vx":1.8035, "vy":1.21967, "omega":0.1219, "ax":5.33358, "ay":3.607, "alpha":0.26385, "fx":[91.18048,89.74661,90.25921,91.70415], "fy":[60.69627,62.79224,62.0393,59.88816]}, + {"t":2.15259, "x":1.67358, "y":1.11123, "heading":-2.19298, "vx":1.96727, "vy":1.33043, "omega":0.13, "ax":5.33158, "ay":3.60565, "alpha":0.23065, "fx":[91.08644,89.83415,90.28689,91.54738], "fy":[60.75993,62.59181,61.92331,60.04942]}, + {"t":2.18329, "x":1.7365, "y":1.15378, "heading":-2.18899, "vx":2.13099, "vy":1.44115, "omega":0.13709, "ax":5.32898, "ay":3.6039, "alpha":0.18764, "fx":[90.96589,89.9481,90.32033,91.34337], "fy":[60.83966,62.32999,61.77663,60.25863]}, + {"t":2.214, "x":1.80445, "y":1.19973, "heading":-2.18478, "vx":2.29463, "vy":1.55181, "omega":0.14285, "ax":5.32543, "ay":3.6015, "alpha":0.12973, "fx":[90.80497,90.10195,90.36206,91.06749], "fy":[60.94348,61.97434,61.58416,60.54014]}, + {"t":2.24471, "x":1.87742, "y":1.24908, "heading":-2.18039, "vx":2.45816, "vy":1.6624, "omega":0.14683, "ax":5.32033, "ay":3.59806, "alpha":0.04761, "fx":[90.57784,90.32008,90.4165,90.67458], "fy":[61.08623,61.46497,61.31846,60.93796]}, + {"t":2.27542, "x":1.95541, "y":1.30183, "heading":-2.17589, "vx":2.62153, "vy":1.77289, "omega":0.14829, "ax":5.31235, "ay":3.59267, "alpha":-0.07785, "fx":[90.23025,90.6514,90.49234,90.072], "fy":[61.29866,60.67786,60.92425,61.54038]}, + {"t":2.30612, "x":2.03842, "y":1.35796, "heading":-2.17133, "vx":2.78465, "vy":1.88321, "omega":0.1459, "ax":5.29816, "ay":3.5831, "alpha":-0.29295, "fx":[89.62617,91.21033,90.60875,89.03551], "fy":[61.65634,59.30805,60.27125,62.55407]}, + {"t":2.33683, "x":2.12642, "y":1.41748, "heading":-2.16685, "vx":2.94735, "vy":1.99324, "omega":0.13691, "ax":5.26623, "ay":3.56156, "alpha":-0.74565, "fx":[88.30312,92.33748,90.81683,86.85103], "fy":[62.40585,56.35557,58.96438,64.59853]}, + {"t":2.36754, "x":2.21941, "y":1.48036, "heading":-2.16265, "vx":3.10906, "vy":2.1026, "omega":0.11401, "ax":5.1361, "ay":3.47485, "alpha":-2.29297, "fx":[83.11238,95.56409,91.28397,79.49372], "fy":[65.0361,45.7092,55.01646,70.66281]}, + {"t":2.39824, "x":2.3173, "y":1.54657, "heading":-2.15915, "vx":3.26677, "vy":2.2093, "omega":0.0436, "ax":0.63596, "ay":0.42892, "alpha":-1.40199, "fx":[5.78223,11.91329,15.79756,9.77664], "fy":[6.35528,2.20271,8.24903,12.37609]}, + {"t":2.42895, "x":2.41791, "y":1.61461, "heading":-2.15781, "vx":3.2863, "vy":2.22247, "omega":0.00055, "ax":0.00117, "ay":0.00038, "alpha":-0.00143, "fx":[0.01467,0.02085,0.02497,0.01878], "fy":[0.00551,0.0014,0.00758,0.0117]}, + {"t":2.45966, "x":2.51883, "y":1.68285, "heading":-2.15779, "vx":3.28633, "vy":2.22248, "omega":0.00051, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[-0.00001,-0.00001,-0.00001,-0.00001], "fy":[0.00001,0.00001,0.00001,0.00001]}, + {"t":2.49036, "x":2.61974, "y":1.7511, "heading":-2.15778, "vx":3.28633, "vy":2.22248, "omega":0.00051, "ax":-0.00117, "ay":-0.00038, "alpha":0.00143, "fx":[-0.01469,-0.02088,-0.02499,-0.01881], "fy":[-0.00549,-0.00137,-0.00756,-0.01167]}, + {"t":2.52107, "x":2.72065, "y":1.81935, "heading":-2.15776, "vx":3.2863, "vy":2.22247, "omega":0.00055, "ax":-0.6361, "ay":-0.42901, "alpha":1.40281, "fx":[-5.78311,-11.92333,-15.80134,-9.77147], "fy":[-6.34913,-2.2026,-8.25807,-12.37937]}, + {"t":2.55178, "x":2.82127, "y":1.88739, "heading":-2.15774, "vx":3.26677, "vy":2.2093, "omega":0.04363, "ax":-5.136, "ay":-3.47479, "alpha":2.29596, "fx":[-83.15254,-95.58622,-91.25484,-79.45369], "fy":[-64.97993,-45.66862,-55.067,-70.70494]}, + {"t":2.58249, "x":2.91916, "y":1.95359, "heading":-2.1564, "vx":3.10905, "vy":2.1026, "omega":0.11413, "ax":-5.26622, "ay":-3.56155, "alpha":0.74679, "fx":[-88.33164,-92.35272,-90.79153,-86.83172], "fy":[-62.36451,-56.33201,-59.00398,-64.62326]}, + {"t":2.61319, "x":3.01214, "y":2.01648, "heading":-2.1529, "vx":2.94734, "vy":1.99323, "omega":0.13706, "ax":-5.29816, "ay":-3.58309, "alpha":0.29344, "fx":[-89.64597,-91.22049,-90.58987,-89.02423], "fy":[-61.62717,-59.293,-60.2999,-62.56952]}, + {"t":2.6439, "x":3.10015, "y":2.07599, "heading":-2.14869, "vx":2.78465, "vy":1.88321, "omega":0.14607, "ax":-5.31235, "ay":-3.59267, "alpha":0.07802, "fx":[-90.23795,-90.65544,-90.48473,-90.06782], "fy":[-61.28723,-60.67197,-60.93563,-61.5463]}, + {"t":2.67461, "x":3.18315, "y":2.13213, "heading":-2.1442, "vx":2.62153, "vy":1.77289, "omega":0.14847, "ax":-5.32033, "ay":-3.59806, "alpha":-0.04762, "fx":[-90.57142,-90.31719,-90.42297,-90.6774], "fy":[-61.09579,-61.46909,-61.30887,-60.93387]}, + {"t":2.70531, "x":3.26115, "y":2.18487, "heading":-2.13965, "vx":2.45816, "vy":1.6624, "omega":0.147, "ax":-5.32543, "ay":-3.6015, "alpha":-0.12987, "fx":[-90.78341,-90.09168,-90.3841,-91.07725], "fy":[-60.97573,-61.98895,-61.55164,-60.52578]}, + {"t":2.73602, "x":3.33412, "y":2.23422, "heading":-2.13513, "vx":2.29463, "vy":1.55181, "omega":0.14302, "ax":-5.32898, "ay":-3.60389, "alpha":-0.18786, "fx":[-90.92881,-89.93025,-90.35865,-91.35993], "fy":[-60.89526,-62.35528,-61.72035,-60.23399]}, + {"t":2.76673, "x":3.40207, "y":2.28017, "heading":-2.13074, "vx":2.13099, "vy":1.44115, "omega":0.13725, "ax":-5.33158, "ay":-3.60565, "alpha":-0.23093, "fx":[-91.03388,-89.80874,-90.34163,-91.57055], "fy":[-60.8389,-62.62769,-61.84314,-60.01469]}, + {"t":2.79743, "x":3.46499, "y":2.32273, "heading":-2.12653, "vx":1.96727, "vy":1.33043, "omega":0.13016, "ax":-5.33358, "ay":-3.607, "alpha":-0.26417, "fx":[-91.11276,-89.7138,-90.33015,-91.73366], "fy":[-60.79817,-62.83846,-61.93565,-59.84364]}, + {"t":2.82814, "x":3.52288, "y":2.36188, "heading":-2.12253, "vx":1.8035, "vy":1.21967, "omega":0.12204, "ax":-5.33515, "ay":-3.60806, "alpha":-0.2906, "fx":[-91.17376,-89.63745,-90.32244,-91.86379], "fy":[-60.76801,-63.00655,-62.00725,-59.70637]}, + {"t":2.85885, "x":3.57575, "y":2.39763, "heading":-2.11878, "vx":1.63967, "vy":1.10887, "omega":0.11312, "ax":-5.33642, "ay":-3.60892, "alpha":-0.31212, "fx":[-91.2221,-89.57465,-90.31732,-91.97007], "fy":[-60.74524,-63.14383,-62.06393,-59.5937]}, + {"t":2.88956, "x":3.62358, "y":2.42998, "heading":-2.11531, "vx":1.4758, "vy":0.99806, "omega":0.10354, "ax":-5.33748, "ay":-3.60963, "alpha":-0.32997, "fx":[-91.26119,-89.52207,-90.314,-92.05852], "fy":[-60.72774,-63.2581,-62.10967,-59.49952]}, + {"t":2.92026, "x":3.66638, "y":2.45893, "heading":-2.11213, "vx":1.31191, "vy":0.88721, "omega":0.0934, "ax":-5.33836, "ay":-3.61023, "alpha":-0.34502, "fx":[-91.29338,-89.47738,-90.3119,-92.13328], "fy":[-60.71403,-63.35472,-62.14726,-59.41963]}, + {"t":2.95097, "x":3.70415, "y":2.48447, "heading":-2.10926, "vx":1.14798, "vy":0.77636, "omega":0.08281, "ax":-5.33911, "ay":-3.61073, "alpha":-0.35788, "fx":[-91.32034,-89.43894,-90.31061,-92.19729], "fy":[-60.70307,-63.43746,-62.17867,-59.35103]}, + {"t":2.98168, "x":3.73688, "y":2.5066, "heading":-2.10672, "vx":0.98403, "vy":0.66548, "omega":0.07182, "ax":-5.33976, "ay":-3.61117, "alpha":-0.36899, "fx":[-91.3433,-89.40556,-90.30982,-92.25269], "fy":[-60.69407,-63.50909,-62.20538,-59.29151]}, + {"t":3.01238, "x":3.76458, "y":2.52534, "heading":-2.10451, "vx":0.82006, "vy":0.55459, "omega":0.06049, "ax":-5.34033, "ay":-3.61155, "alpha":-0.37869, "fx":[-91.36315,-89.37634,-90.30929,-92.30108], "fy":[-60.68646,-63.57165,-62.22849,-59.23943]}, + {"t":3.04309, "x":3.78725, "y":2.54066, "heading":-2.10265, "vx":0.65608, "vy":0.44369, "omega":0.04886, "ax":-5.34083, "ay":-3.61189, "alpha":-0.38723, "fx":[-91.38059,-89.35058,-90.30883,-92.34366], "fy":[-60.67977,-63.62669,-62.24883,-59.19354]}, + {"t":3.0738, "x":3.80488, "y":2.55259, "heading":-2.10115, "vx":0.49208, "vy":0.33278, "omega":0.03697, "ax":-5.34127, "ay":-3.61219, "alpha":-0.3948, "fx":[-91.39617,-89.32776,-90.30829,-92.38138], "fy":[-60.67367,-63.67543,-62.26709,-59.15287]}, + {"t":3.1045, "x":3.81747, "y":2.5611, "heading":-2.10002, "vx":0.32806, "vy":0.22186, "omega":0.02485, "ax":-5.34166, "ay":-3.61245, "alpha":-0.40157, "fx":[-91.41031,-89.30746,-90.30755,-92.41499], "fy":[-60.66787,-63.71881,-62.28377,-59.11663]}, + {"t":3.13521, "x":3.82502, "y":2.56621, "heading":-2.09926, "vx":0.16404, "vy":0.11093, "omega":0.01252, "ax":-5.34201, "ay":-3.61269, "alpha":-0.40765, "fx":[-91.42334,-89.28934,-90.30652,-92.44507], "fy":[-60.66214,-63.75757,-62.29931,-59.08423]}, + {"t":3.16592, "x":3.82754, "y":2.56791, "heading":-2.09887, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[ + {"name":"Funnel", "from":{"target":5, "targetTimestamp":2.52107, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] +} diff --git a/src/main/deploy/v2_redundancy/choreo/A_RIGHT_PATH3.traj b/src/main/deploy/v2_redundancy/choreo/A_RIGHT_PATH3.traj new file mode 100644 index 00000000..e75d4f96 --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/A_RIGHT_PATH3.traj @@ -0,0 +1,118 @@ +{ + "name":"A_RIGHT_PATH3", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.999176502227783, "y":2.845594631958008, "heading":-2.1010083691287966, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.3110252618789673, "y":0.8660395019531251, "heading":-2.2024870470289093, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.495954990386963, "y":1.9211212396621704, "heading":0.0, "intervals":32, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":3.410642147064209, "y":2.7169248931884766, "heading":-2.077894951837786, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.999176502227783 m", "val":3.999176502227783}, "y":{"exp":"(8.0518 - 5.206205368041992) m", "val":2.845594631958008}, "heading":{"exp":"-2.1010083691287966 rad", "val":-2.1010083691287966}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"(8.0518 - 7.185760498046875) m", "val":0.8660395019531251}, "heading":{"exp":"-2.2024870470289093 rad", "val":-2.2024870470289093}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.495954990386963 m", "val":2.495954990386963}, "y":{"exp":"1.9211212396621704 m", "val":1.9211212396621704}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":32, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"3.410642147064209 m", "val":3.410642147064209}, "y":{"exp":"(8.0518 - 5.334875106811523) m", "val":2.7169248931884766}, "heading":{"exp":"-2.077894951837786 rad", "val":-2.077894951837786}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.45692,2.1638,2.77848], + "samples":[ + {"t":0.0, "x":3.99918, "y":2.84559, "heading":-2.10101, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.19517, "ay":-3.82571, "alpha":-0.34139, "fx":[-88.91725,-86.99375,-87.81273,-89.74956], "fy":[-64.3502,-66.92562,-65.84215,-63.17899]}, + {"t":0.04415, "x":3.99411, "y":2.84187, "heading":-2.10101, "vx":-0.22936, "vy":-0.1689, "omega":-0.01507, "ax":-5.19479, "ay":-3.82543, "alpha":-0.33555, "fx":[-88.90161,-87.01099,-87.81583,-89.71932], "fy":[-64.35768,-66.88948,-65.82375,-63.2072]}, + {"t":0.0883, "x":3.97892, "y":2.83068, "heading":-2.10167, "vx":-0.45871, "vy":-0.33779, "omega":-0.02989, "ax":-5.19435, "ay":-3.82511, "alpha":-0.32866, "fx":[-88.88404,-87.03165,-87.81856,-89.68341], "fy":[-64.3653,-66.84643,-65.80332,-63.24085]}, + {"t":0.13245, "x":3.95361, "y":2.81204, "heading":-2.10299, "vx":-0.68803, "vy":-0.50666, "omega":-0.0444, "ax":-5.19382, "ay":-3.82472, "alpha":-0.32045, "fx":[-88.86366,-87.05657,-87.82116,-89.64027], "fy":[-64.37356,-66.79464,-65.77981,-63.28131]}, + {"t":0.1766, "x":3.91817, "y":2.78594, "heading":-2.10495, "vx":-0.91733, "vy":-0.67552, "omega":-0.05854, "ax":-5.19318, "ay":-3.82424, "alpha":-0.31046, "fx":[-88.83917,-87.08696,-87.82397,-89.58773], "fy":[-64.38315,-66.73149,-65.75173,-63.3306]}, + {"t":0.22074, "x":3.87261, "y":2.75239, "heading":-2.10754, "vx":-1.14661, "vy":-0.84436, "omega":-0.07225, "ax":-5.19238, "ay":-3.82365, "alpha":-0.29807, "fx":[-88.8087,-87.12461,-87.82747,-89.52252], "fy":[-64.3951,-66.65308,-65.71687,-63.39167]}, + {"t":0.26489, "x":3.81693, "y":2.71139, "heading":-2.11073, "vx":-1.37584, "vy":-1.01317, "omega":-0.08541, "ax":-5.19135, "ay":-3.82289, "alpha":-0.28229, "fx":[-88.76932,-87.1723,-87.8324,-89.43962], "fy":[-64.411,-66.55336,-65.67187,-63.46906]}, + {"t":0.30904, "x":3.75113, "y":2.66293, "heading":-2.1145, "vx":-1.60504, "vy":-1.18195, "omega":-0.09787, "ax":-5.19, "ay":-3.82189, "alpha":-0.26151, "fx":[-88.71626,-87.23451,-87.83993,-89.33078], "fy":[-64.43339,-66.42243,-65.61126,-63.57019]}, + {"t":0.35319, "x":3.67521, "y":2.60703, "heading":-2.11882, "vx":-1.83417, "vy":-1.35068, "omega":-0.10942, "ax":-5.18812, "ay":-3.82051, "alpha":-0.23289, "fx":[-88.64114,-87.31912,-87.85204,-89.18161], "fy":[-64.46672,-66.24289,-65.52553,-63.70797]}, + {"t":0.39734, "x":3.58918, "y":2.54367, "heading":-2.12365, "vx":-2.06322, "vy":-1.51935, "omega":-0.1197, "ax":-5.18536, "ay":-3.81847, "alpha":-0.191, "fx":[-88.52772,-87.4412,-87.87246,-88.9643], "fy":[-64.51951,-65.98105,-65.39654,-63.90708]}, + {"t":0.44149, "x":3.49304, "y":2.47287, "heading":-2.12893, "vx":-2.29215, "vy":-1.68793, "omega":-0.12813, "ax":-5.18087, "ay":-3.81515, "alpha":-0.12383, "fx":[-88.33985,-87.63367,-87.90905,-88.61758], "fy":[-64.61046,-65.56213,-65.18476,-64.22132]}, + {"t":0.48564, "x":3.38679, "y":2.39464, "heading":-2.13459, "vx":-2.52088, "vy":-1.85637, "omega":-0.1336, "ax":-5.17232, "ay":-3.80885, "alpha":0.00133, "fx":[-87.97734,-87.98496,-87.98205,-87.97442], "fy":[-64.79052,-64.78021,-64.78428,-64.79459]}, + {"t":0.52979, "x":3.27046, "y":2.30897, "heading":-2.14049, "vx":-2.74923, "vy":-2.02452, "omega":-0.13354, "ax":-5.14981, "ay":-3.79224, "alpha":0.31664, "fx":[-87.02035,-88.84034,-88.16478,-86.36184], "fy":[-65.26627,-62.78691,-63.78172,-66.18458]}, + {"t":0.57394, "x":3.14406, "y":2.21589, "heading":-2.14639, "vx":-2.97659, "vy":-2.19195, "omega":-0.11956, "ax":-4.9428, "ay":-3.64167, "alpha":2.67463, "fx":[-78.40448,-94.03118,-89.08997,-74.77678], "fy":[-69.03584,-46.77811,-57.31767,-74.64333]}, + {"t":0.61809, "x":3.00783, "y":2.11557, "heading":-2.15166, "vx":-3.19481, "vy":-2.35272, "omega":-0.00148, "ax":-0.02822, "ay":-0.0196, "alpha":0.02775, "fx":[-0.38028,-0.50071,-0.57975,-0.45932], "fy":[-0.31272,-0.23366,-0.35409,-0.43314]}, + {"t":0.66223, "x":2.86676, "y":2.01168, "heading":-2.15173, "vx":-3.19606, "vy":-2.35359, "omega":-0.00025, "ax":-0.00012, "ay":0.00015, "alpha":0.00001, "fx":[-0.00209,-0.00212,-0.00214,-0.00211], "fy":[0.00257,0.00258,0.00256,0.00254]}, + {"t":0.70638, "x":2.72565, "y":1.90777, "heading":-2.15174, "vx":-3.19606, "vy":-2.35358, "omega":-0.00025, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.75053, "x":2.58455, "y":1.80386, "heading":-2.15175, "vx":-3.19606, "vy":-2.35358, "omega":-0.00025, "ax":0.00012, "ay":-0.00015, "alpha":-0.00001, "fx":[0.00208,0.00211,0.00213,0.0021], "fy":[-0.00255,-0.00257,-0.00254,-0.00252]}, + {"t":0.79468, "x":2.44345, "y":1.69995, "heading":-2.15176, "vx":-3.19606, "vy":-2.35359, "omega":-0.00025, "ax":0.02821, "ay":0.0196, "alpha":-0.02773, "fx":[0.38023,0.50059,0.57961,0.45925], "fy":[0.31276,0.23374,0.35409,0.43312]}, + {"t":0.83883, "x":2.30237, "y":1.59607, "heading":-2.15177, "vx":-3.19481, "vy":-2.35272, "omega":-0.00148, "ax":4.9428, "ay":3.64166, "alpha":-2.67446, "fx":[78.34131,94.01125,89.13137,74.81883], "fy":[69.1121,46.80728,57.25032,74.60493]}, + {"t":0.88298, "x":2.16614, "y":1.49574, "heading":-2.15184, "vx":-2.97659, "vy":-2.19195, "omega":-0.11955, "ax":5.14981, "ay":3.79224, "alpha":-0.3164, "fx":[87.00638,88.83321,88.17801,86.36971], "fy":[65.28507,62.79656,63.76322,66.17466]}, + {"t":0.92713, "x":2.03975, "y":1.40267, "heading":-2.15712, "vx":-2.74923, "vy":-2.02452, "omega":-0.13352, "ax":5.17232, "ay":3.80885, "alpha":-0.00126, "fx":[87.97736,87.9846,87.98202,87.97477], "fy":[64.79049,64.78069,64.78431,64.79411]}, + {"t":0.97128, "x":1.92341, "y":1.317, "heading":-2.16301, "vx":-2.52088, "vy":-1.85637, "omega":-0.13358, "ax":5.18087, "ay":3.81515, "alpha":0.12384, "fx":[88.35633,87.64142,87.89221,88.61017], "fy":[64.58784,65.55194,65.20754,64.23135]}, + {"t":1.01543, "x":1.81717, "y":1.23876, "heading":-2.16891, "vx":-2.29215, "vy":-1.68793, "omega":-0.12811, "ax":5.18536, "ay":3.81847, "alpha":0.19098, "fx":[88.56125,87.45744,87.83781,88.94917], "fy":[64.47335,65.95979,65.44319,63.92784]}, + {"t":1.05958, "x":1.72102, "y":1.16796, "heading":-2.17457, "vx":-2.06322, "vy":-1.51935, "omega":-0.11968, "ax":5.18812, "ay":3.82051, "alpha":0.23285, "fx":[88.69133,87.34374,87.79981,89.15903], "fy":[64.3975,66.21076,65.59566,63.7392]}, + {"t":1.10372, "x":1.63499, "y":1.10461, "heading":-2.17985, "vx":-1.83417, "vy":-1.35068, "omega":-0.1094, "ax":5.19, "ay":3.82189, "alpha":0.26146, "fx":[88.78219,87.26709,87.77098,89.30123], "fy":[64.34235,66.37999,65.70364,63.6113]}, + {"t":1.14787, "x":1.55907, "y":1.0487, "heading":-2.18468, "vx":-1.60504, "vy":-1.18195, "omega":-0.09786, "ax":5.19135, "ay":3.82289, "alpha":0.28224, "fx":[88.84973,87.21224,87.74802,89.40365], "fy":[64.29986,66.50138,65.78477,63.51929]}, + {"t":1.19202, "x":1.49327, "y":1.00024, "heading":-2.189, "vx":-1.37584, "vy":-1.01317, "omega":-0.08539, "ax":5.19238, "ay":3.82365, "alpha":0.29802, "fx":[88.9021,87.17123,87.72918,89.4808], "fy":[64.2659,66.59249,65.84823,63.45011]}, + {"t":1.23617, "x":1.43759, "y":0.95924, "heading":-2.19277, "vx":-1.14661, "vy":-0.84436, "omega":-0.07224, "ax":5.19318, "ay":3.82424, "alpha":0.31041, "fx":[88.94394,87.13944,87.71349,89.54097], "fy":[64.23815,66.66333,65.89923,63.39626]}, + {"t":1.28032, "x":1.39203, "y":0.92569, "heading":-2.19596, "vx":-0.91733, "vy":-0.67552, "omega":-0.05853, "ax":5.19382, "ay":3.82472, "alpha":0.32039, "fx":[88.97803,87.11406,87.70035,89.58924], "fy":[64.2152,66.72003,65.941,63.35312]}, + {"t":1.32447, "x":1.35659, "y":0.89959, "heading":-2.19854, "vx":-0.68803, "vy":-0.50666, "omega":-0.04439, "ax":5.19435, "ay":3.82511, "alpha":0.32861, "fx":[89.00618,87.09323,87.68937,89.62889], "fy":[64.19613,66.76654,65.97557,63.31766]}, + {"t":1.36862, "x":1.33128, "y":0.88095, "heading":-2.2005, "vx":-0.45871, "vy":-0.33779, "omega":-0.02988, "ax":5.19479, "ay":3.82543, "alpha":0.33549, "fx":[89.02958,87.07571,87.6803,89.66217], "fy":[64.18037,66.80556,66.00436,63.28785]}, + {"t":1.41277, "x":1.31609, "y":0.86977, "heading":-2.20182, "vx":-0.22936, "vy":-0.1689, "omega":-0.01507, "ax":5.19517, "ay":3.82571, "alpha":0.34133, "fx":[89.04909,87.06062,87.67297,89.69063], "fy":[64.16748,66.83895,66.02832,63.26224]}, + {"t":1.45692, "x":1.31103, "y":0.86604, "heading":-2.20249, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.8375, "ay":4.26441, "alpha":0.43459, "fx":[83.40227,80.53297,81.12588,84.07703], "fy":[71.28937,74.51367,73.8589,70.48332]}, + {"t":1.48765, "x":1.31331, "y":0.86805, "heading":-2.20249, "vx":0.14868, "vy":0.13106, "omega":0.01336, "ax":4.83719, "ay":4.26413, "alpha":0.42793, "fx":[83.38017,80.55431,81.13855,84.04375], "fy":[71.30339,74.47921,73.83316,70.5107]}, + {"t":1.51838, "x":1.32016, "y":0.8741, "heading":-2.20208, "vx":0.29734, "vy":0.26212, "omega":0.02651, "ax":4.83684, "ay":4.26382, "alpha":0.42052, "fx":[83.35486,80.57759,81.15335,84.00716], "fy":[71.31981,74.44134,73.80374,70.54062]}, + {"t":1.54912, "x":1.33159, "y":0.88417, "heading":-2.20126, "vx":0.446, "vy":0.39316, "omega":0.03943, "ax":4.83645, "ay":4.26348, "alpha":0.41223, "fx":[83.32595,80.60325,81.17048,83.96656], "fy":[71.33883,74.39932,73.77018,70.57366]}, + {"t":1.57985, "x":1.34758, "y":0.89826, "heading":-2.20005, "vx":0.59464, "vy":0.52419, "omega":0.0521, "ax":4.836, "ay":4.26309, "alpha":0.40289, "fx":[83.29293,80.63189,81.19018,83.92106], "fy":[71.36075,74.35222,73.73192,70.61055]}, + {"t":1.61059, "x":1.36814, "y":0.91639, "heading":-2.19845, "vx":0.74327, "vy":0.65521, "omega":0.06448, "ax":4.8355, "ay":4.26264, "alpha":0.39227, "fx":[83.25513,80.66425,81.21277,83.86956], "fy":[71.38593,74.29884,73.68823,70.6522]}, + {"t":1.64132, "x":1.39327, "y":0.93854, "heading":-2.19647, "vx":0.89188, "vy":0.78622, "omega":0.07654, "ax":4.83492, "ay":4.26213, "alpha":0.38012, "fx":[83.21171,80.70127,81.23864,83.81061], "fy":[71.41487,74.23767,73.63815,70.69979]}, + {"t":1.67205, "x":1.42296, "y":0.96471, "heading":-2.19411, "vx":1.04048, "vy":0.91721, "omega":0.08822, "ax":4.83424, "ay":4.26154, "alpha":0.36605, "fx":[83.16155,80.7442,81.26833,83.74235], "fy":[71.44818,74.16667,73.58047,70.75485]}, + {"t":1.70279, "x":1.45722, "y":0.99492, "heading":-2.1914, "vx":1.18905, "vy":1.04819, "omega":0.09947, "ax":4.83345, "ay":4.26084, "alpha":0.3496, "fx":[83.10311,80.79469,81.30256,83.66226], "fy":[71.48673,74.08316,73.51351,70.81942]}, + {"t":1.73352, "x":1.49605, "y":1.02914, "heading":-2.18835, "vx":1.33761, "vy":1.17914, "omega":0.11022, "ax":4.83251, "ay":4.26001, "alpha":0.33009, "fx":[83.03431,80.85499,81.34231,83.56691], "fy":[71.5317,73.98344,73.43501,70.89627]}, + {"t":1.76426, "x":1.53944, "y":1.06739, "heading":-2.18496, "vx":1.48613, "vy":1.31007, "omega":0.12036, "ax":4.83137, "ay":4.25901, "alpha":0.30658, "fx":[82.95216,80.92829,81.38894,83.45148], "fy":[71.58477,73.86226,73.34177,70.98929]}, + {"t":1.79499, "x":1.5874, "y":1.10967, "heading":-2.18126, "vx":1.63461, "vy":1.44096, "omega":0.12979, "ax":4.82996, "ay":4.25777, "alpha":0.27771, "fx":[82.8523,81.01918,81.44445,83.30895], "fy":[71.64841,73.71201,73.22914,71.10407]}, + {"t":1.82572, "x":1.63992, "y":1.15597, "heading":-2.17727, "vx":1.78306, "vy":1.57182, "omega":0.13832, "ax":4.82817, "ay":4.25619, "alpha":0.2414, "fx":[82.72805,81.13456,81.51184,83.12874], "fy":[71.72635,73.5211,73.09012,71.24899]}, + {"t":1.85646, "x":1.697, "y":1.20628, "heading":-2.17302, "vx":1.93145, "vy":1.70263, "omega":0.14574, "ax":4.82583, "ay":4.25413, "alpha":0.19439, "fx":[82.56868,81.28537,81.5958,82.89408], "fy":[71.82461,73.27102,72.91363,71.4372]}, + {"t":1.88719, "x":1.75864, "y":1.26062, "heading":-2.16854, "vx":2.07976, "vy":1.83338, "omega":0.15171, "ax":4.82264, "ay":4.25132, "alpha":0.1311, "fx":[82.3558,81.48997,81.70417,82.5767], "fy":[71.95338,72.93024,72.68106,71.69058]}, + {"t":1.91793, "x":1.82483, "y":1.31898, "heading":-2.16388, "vx":2.22798, "vy":1.96404, "omega":0.15574, "ax":4.81802, "ay":4.24727, "alpha":0.04135, "fx":[82.05507,81.78175,81.85096,82.12495], "fy":[72.13153,72.44038,72.35868,72.04848]}, + {"t":1.94866, "x":1.89558, "y":1.38135, "heading":-2.15909, "vx":2.37606, "vy":2.09457, "omega":0.15701, "ax":4.81078, "ay":4.2409, "alpha":-0.09577, "fx":[81.59437,82.22848,82.06397,81.43332], "fy":[72.3981,71.67985,71.87833,72.58937]}, + {"t":1.97939, "x":1.97088, "y":1.44772, "heading":-2.15426, "vx":2.52391, "vy":2.22491, "omega":0.15407, "ax":4.79783, "ay":4.22949, "alpha":-0.33105, "fx":[80.79229,82.9915,82.40672,80.2481], "fy":[72.84871,70.34697,71.07905,73.49525]}, + {"t":2.01013, "x":2.05072, "y":1.5181, "heading":-2.14953, "vx":2.67137, "vy":2.3549, "omega":0.1439, "ax":4.76829, "ay":4.20352, "alpha":-0.82778, "fx":[79.02897,84.5688,83.06156,77.7696], "fy":[73.79403,67.43528,69.47006,75.30334]}, + {"t":2.04086, "x":2.13507, "y":1.59246, "heading":-2.14511, "vx":2.81792, "vy":2.48409, "omega":0.11846, "ax":4.64293, "ay":4.09487, "alpha":-2.55799, "fx":[72.00735,89.48447,84.818,69.5897], "fy":[77.08043,56.47865,64.54519,80.50578]}, + {"t":2.07159, "x":2.22387, "y":1.67074, "heading":-2.14147, "vx":2.96061, "vy":2.60994, "omega":0.03984, "ax":0.50591, "ay":0.44471, "alpha":-1.27872, "fx":[4.01605,9.67363,13.15487,7.57687], "fy":[6.61874,2.95461,8.52299,12.16154]}, + {"t":2.10233, "x":2.3151, "y":1.75117, "heading":-2.14024, "vx":2.97616, "vy":2.62361, "omega":0.00054, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[-0.00007,-0.00007,-0.00007,-0.00007], "fy":[0.00007,0.00007,0.00007,0.00007]}, + {"t":2.13306, "x":2.40657, "y":1.8318, "heading":-2.14023, "vx":2.97616, "vy":2.62361, "omega":0.00054, "ax":-0.50606, "ay":-0.44482, "alpha":1.2796, "fx":[-4.01673,-9.68266,-13.15922,-7.57306], "fy":[-6.61422,-2.95452,-8.53117,-12.16545]}, + {"t":2.1638, "x":2.4978, "y":1.91222, "heading":-2.14021, "vx":2.96061, "vy":2.60994, "omega":0.03987, "ax":-4.64282, "ay":-4.09479, "alpha":2.56107, "fx":[-72.05372,-89.51798,-84.78278,-69.53736], "fy":[-77.03211,-56.43063,-64.59378,-80.54861]}, + {"t":2.19453, "x":2.5866, "y":1.9905, "heading":-2.13898, "vx":2.81792, "vy":2.48409, "omega":0.11858, "ax":-4.76828, "ay":-4.20351, "alpha":0.82895, "fx":[-79.06398,-84.59245,-83.03025,-77.74138], "fy":[-73.75548,-67.40689,-69.50821,-75.33141]}, + {"t":2.22526, "x":2.67095, "y":2.06486, "heading":-2.13534, "vx":2.67137, "vy":2.3549, "omega":0.14405, "ax":-4.79782, "ay":-4.22949, "alpha":0.33156, "fx":[-80.81779,-83.00797,-82.38239,-80.23028], "fy":[-72.82001,-70.32808,-71.10757,-73.51416]}, + {"t":2.256, "x":2.75079, "y":2.13524, "heading":-2.13091, "vx":2.52391, "vy":2.22491, "omega":0.15424, "ax":-4.81078, "ay":-4.24089, "alpha":0.09595, "fx":[-81.60532,-82.23559,-82.05315,-81.42603], "fy":[-72.38563,-71.67185,-71.89077,-72.59736]}, + {"t":2.28673, "x":2.82608, "y":2.20162, "heading":-2.12617, "vx":2.37606, "vy":2.09457, "omega":0.15719, "ax":-4.81802, "ay":-4.24727, "alpha":-0.04137, "fx":[-82.04859,-81.77792,-81.85748,-82.12872], "fy":[-72.13895,-72.4446,-72.35125,-72.04425]}, + {"t":2.31747, "x":2.89683, "y":2.26399, "heading":-2.12134, "vx":2.22798, "vy":1.96404, "omega":0.15592, "ax":-4.82264, "ay":-4.25132, "alpha":-0.13124, "fx":[-82.33037,-81.47432,-81.73009,-82.59182], "fy":[-71.98262,-72.94744,-72.65174,-71.67344]}, + {"t":2.3482, "x":2.96303, "y":2.32234, "heading":-2.11655, "vx":2.07976, "vy":1.83338, "omega":0.15189, "ax":-4.82583, "ay":-4.25413, "alpha":-0.19462, "fx":[-82.5237,-81.25752,-81.64212,-82.92055], "fy":[-71.87652,-73.3015,-72.8615,-71.40689]}, + {"t":2.37893, "x":3.02467, "y":2.37668, "heading":-2.11188, "vx":1.93145, "vy":1.70263, "omega":0.14591, "ax":-4.82817, "ay":-4.25619, "alpha":-0.24169, "fx":[-82.66345,-81.09447,-81.57884,-83.16637], "fy":[-71.80108,-73.56482,-73.01501,-71.2056]}, + {"t":2.40967, "x":3.08175, "y":2.427, "heading":-2.1074, "vx":1.78306, "vy":1.57182, "omega":0.13848, "ax":-4.82996, "ay":-4.25777, "alpha":-0.27804, "fx":[-82.76844,-80.96705,-81.53192,-83.35738], "fy":[-71.7456,-73.7687,-73.13138,-71.0479]}, + {"t":2.4404, "x":3.13427, "y":2.4733, "heading":-2.10314, "vx":1.63461, "vy":1.44096, "omega":0.12993, "ax":-4.83137, "ay":-4.25901, "alpha":-0.30695, "fx":[-82.84969,-80.86454,-81.4963,-83.51026], "fy":[-71.7037,-73.93144,-73.22206,-70.92082]}, + {"t":2.47114, "x":3.18223, "y":2.51557, "heading":-2.09915, "vx":1.48613, "vy":1.31007, "omega":0.1205, "ax":-4.83251, "ay":-4.26001, "alpha":-0.33048, "fx":[-82.9141,-80.78015,-81.46871,-83.63546], "fy":[-71.67138,-74.0645,-73.29433,-70.81612]}, + {"t":2.50187, "x":3.22562, "y":2.55382, "heading":-2.09544, "vx":1.3376, "vy":1.17914, "omega":0.11034, "ax":-4.83345, "ay":-4.26084, "alpha":-0.35001, "fx":[-82.96622,-80.7094,-81.44694,-83.73994], "fy":[-71.64595,-74.17539,-73.35308,-70.72831]}, + {"t":2.5326, "x":3.26445, "y":2.58805, "heading":-2.09205, "vx":1.18905, "vy":1.04819, "omega":0.09959, "ax":-4.83424, "ay":-4.26154, "alpha":-0.36648, "fx":[-83.00917,-80.64922,-81.42946,-83.82846], "fy":[-71.62556,-74.26924,-73.40166,-70.6536]}, + {"t":2.56334, "x":3.29871, "y":2.61825, "heading":-2.08899, "vx":1.04048, "vy":0.91721, "omega":0.08832, "ax":-4.83492, "ay":-4.26213, "alpha":-0.38055, "fx":[-83.04515,-80.59742,-81.41515,-83.90438], "fy":[-71.6089,-74.34969,-73.44249,-70.58928]}, + {"t":2.59407, "x":3.3284, "y":2.64443, "heading":-2.08628, "vx":0.89188, "vy":0.78622, "omega":0.07663, "ax":-4.8355, "ay":-4.26264, "alpha":-0.39272, "fx":[-83.07579,-80.5524,-81.40318,-83.97019], "fy":[-71.59498,-74.41938,-73.47736,-70.53337]}, + {"t":2.62481, "x":3.35353, "y":2.66658, "heading":-2.08392, "vx":0.74327, "vy":0.65521, "omega":0.06456, "ax":-4.836, "ay":-4.26308, "alpha":-0.40334, "fx":[-83.10228,-80.51297,-81.39293,-84.02773], "fy":[-71.58308,-74.48027,-73.50759,-70.48438]}, + {"t":2.65554, "x":3.37409, "y":2.6847, "heading":-2.08194, "vx":0.59464, "vy":0.52419, "omega":0.05216, "ax":-4.83644, "ay":-4.26347, "alpha":-0.41269, "fx":[-83.12556,-80.47823,-81.3839,-84.07839], "fy":[-71.57263,-74.53383,-73.53422,-70.44119]}, + {"t":2.68627, "x":3.39008, "y":2.6988, "heading":-2.08033, "vx":0.446, "vy":0.39316, "omega":0.03948, "ax":-4.83684, "ay":-4.26382, "alpha":-0.42099, "fx":[-83.14634,-80.44748,-81.37572,-84.12326], "fy":[-71.56319,-74.58124,-73.55805,-70.4029]}, + {"t":2.71701, "x":3.4015, "y":2.70887, "heading":-2.07912, "vx":0.29734, "vy":0.26212, "omega":0.02654, "ax":-4.83719, "ay":-4.26413, "alpha":-0.4284, "fx":[-83.16518,-80.42015,-81.36807,-84.1632], "fy":[-71.55441,-74.62338,-73.5797,-70.36884]}, + {"t":2.74774, "x":3.40836, "y":2.71491, "heading":-2.07831, "vx":0.14868, "vy":0.13106, "omega":0.01337, "ax":-4.8375, "ay":-4.2644, "alpha":-0.43506, "fx":[-83.18253,-80.39582,-81.36072,-84.1989], "fy":[-71.54601,-74.66098,-73.5997,-70.33844]}, + {"t":2.77848, "x":3.41064, "y":2.71692, "heading":-2.07789, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[ + {"name":"Funnel", "from":{"target":2, "targetTimestamp":2.1638, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] +} diff --git a/src/main/deploy/v2_redundancy/choreo/A_RIGHT_PATH4.traj b/src/main/deploy/v2_redundancy/choreo/A_RIGHT_PATH4.traj new file mode 100644 index 00000000..c1f93e1b --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/A_RIGHT_PATH4.traj @@ -0,0 +1,129 @@ +{ + "name":"A_RIGHT_PATH4", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.692616224288941, "y":3.031563984680176, "heading":-2.0948682307415045, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.3110252618789673, "y":0.8660395019531251, "heading":-2.216612130911823, "intervals":37, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.174586296081543, "y":2.617419958114624, "heading":0.0, "intervals":36, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":2.819322109222412, "y":3.785844075012207, "heading":-3.1289351796122347, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.6926162242889404 m", "val":3.692616224288941}, "y":{"exp":"(8.0518 - 5.020236015319824) m", "val":3.031563984680176}, "heading":{"exp":"-2.0948682307415045 rad", "val":-2.0948682307415045}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.3110252618789673 m", "val":1.3110252618789673}, "y":{"exp":"(8.0518 - 7.185760498046875) m", "val":0.8660395019531251}, "heading":{"exp":"-2.216612130911823 rad", "val":-2.216612130911823}, "intervals":37, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.174586296081543 m", "val":2.174586296081543}, "y":{"exp":"2.617419958114624 m", "val":2.617419958114624}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":36, "split":false, "fixTranslation":false, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"2.819322109222412 m", "val":2.819322109222412}, "y":{"exp":"(8.0518 - 4.265955924987793) m", "val":3.785844075012207}, "heading":{"exp":"-3.1289351796122347 rad", "val":-3.1289351796122347}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.42726,2.20676,2.87874], + "samples":[ + {"t":0.0, "x":3.69262, "y":3.03156, "heading":-2.09487, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-4.77336, "ay":-4.34029, "alpha":-0.36517, "fx":[-82.01137,-79.60509,-80.3539,-82.80387], "fy":[-72.9455,-75.56262,-74.76071,-72.03947]}, + {"t":0.04325, "x":3.68815, "y":3.0275, "heading":-2.09487, "vx":-0.20645, "vy":-0.18772, "omega":-0.01579, "ax":-4.77303, "ay":-4.33999, "alpha":-0.36029, "fx":[-81.99495,-79.62059,-80.35948,-82.77638], "fy":[-72.95195,-75.53461,-74.74258,-72.05859]}, + {"t":0.0865, "x":3.67476, "y":3.01533, "heading":-2.09555, "vx":-0.41289, "vy":-0.37543, "omega":-0.03138, "ax":-4.77264, "ay":-4.33963, "alpha":-0.35461, "fx":[-81.97681,-79.63925,-80.3649,-82.74377], "fy":[-72.95832,-75.50128,-74.7226,-72.08147]}, + {"t":0.12975, "x":3.65244, "y":2.99503, "heading":-2.09691, "vx":-0.6193, "vy":-0.56312, "omega":-0.04671, "ax":-4.77217, "ay":-4.33921, "alpha":-0.34789, "fx":[-81.95612,-79.66174,-80.37047,-82.70483], "fy":[-72.96497,-75.4614,-74.69987,-72.10894]}, + {"t":0.173, "x":3.62119, "y":2.96662, "heading":-2.09893, "vx":-0.8257, "vy":-0.75079, "omega":-0.06176, "ax":-4.77161, "ay":-4.33871, "alpha":-0.33982, "fx":[-81.9317,-79.68899,-80.37666,-82.65783], "fy":[-72.97244,-75.41319,-74.67312,-72.14215]}, + {"t":0.21625, "x":3.58101, "y":2.93009, "heading":-2.1016, "vx":-1.03208, "vy":-0.93844, "omega":-0.07646, "ax":-4.77093, "ay":-4.33809, "alpha":-0.32994, "fx":[-81.90188,-79.72234,-80.3841,-82.60029], "fy":[-72.98148,-75.35412,-74.64053,-72.18278]}, + {"t":0.2595, "x":3.53191, "y":2.88544, "heading":-2.10491, "vx":-1.23842, "vy":-1.12606, "omega":-0.09073, "ax":-4.77007, "ay":-4.33732, "alpha":-0.31759, "fx":[-81.86414,-79.76384,-80.39377,-82.52847], "fy":[-72.99318,-75.28035,-74.59939,-72.23331]}, + {"t":0.30275, "x":3.47389, "y":2.83268, "heading":-2.10883, "vx":-1.44473, "vy":-1.31366, "omega":-0.10446, "ax":-4.76896, "ay":-4.33632, "alpha":-0.3017, "fx":[-81.81452,-79.81665,-80.40713,-82.43651], "fy":[-73.0093,-75.18582,-74.54544,-72.29765]}, + {"t":0.346, "x":3.40694, "y":2.77181, "heading":-2.11335, "vx":-1.65099, "vy":-1.5012, "omega":-0.11751, "ax":-4.76748, "ay":-4.33498, "alpha":-0.28048, "fx":[-81.7464,-79.88606,-80.4266,-82.31463], "fy":[-73.03267,-75.06042,-74.47165,-72.38226]}, + {"t":0.38925, "x":3.33108, "y":2.70283, "heading":-2.11843, "vx":-1.85718, "vy":-1.68869, "omega":-0.12964, "ax":-4.76538, "ay":-4.33309, "alpha":-0.25074, "fx":[-81.64782,-79.98159,-80.45644,-82.14522], "fy":[-73.06841,-74.88582,-74.3654,-72.4987]}, + {"t":0.4325, "x":3.2463, "y":2.62574, "heading":-2.12404, "vx":-2.06329, "vy":-1.8761, "omega":-0.14049, "ax":-4.7622, "ay":-4.33022, "alpha":-0.20608, "fx":[-81.49469,-80.1221,-80.50494,-81.89306], "fy":[-73.12662,-74.62514,-74.20164,-72.66984]}, + {"t":0.47575, "x":3.15261, "y":2.54055, "heading":-2.13011, "vx":-2.26926, "vy":-2.06338, "omega":-0.1494, "ax":-4.75682, "ay":-4.32536, "alpha":-0.13158, "fx":[-81.23019,-80.35127,-80.59075,-81.47614], "fy":[-73.23063,-74.19154,-73.92248,-72.94801]}, + {"t":0.519, "x":3.05001, "y":2.44726, "heading":-2.13658, "vx":-2.47499, "vy":-2.25046, "omega":-0.15509, "ax":-4.74572, "ay":-4.31535, "alpha":0.0174, "fx":[-80.68055,-80.79726,-80.76623,-80.64964], "fy":[-73.44898,-73.32106,-73.35701,-73.48469]}, + {"t":0.56226, "x":2.93853, "y":2.34589, "heading":-2.14328, "vx":-2.68024, "vy":-2.4371, "omega":-0.15434, "ax":-4.71008, "ay":-4.28318, "alpha":0.46025, "fx":[-78.9421,-82.05793,-81.25126,-78.21717], "fy":[-74.10427,-70.66649,-71.68837,-74.96378]}, + {"t":0.60551, "x":2.8182, "y":2.23648, "heading":-2.14996, "vx":-2.88396, "vy":-2.62235, "omega":-0.13443, "ax":-1.2157, "ay":-1.10429, "alpha":3.10111, "fx":[-9.46753,-23.99027,-31.3387,-17.91853], "fy":[-17.28695,-7.3062,-20.53232,-30.0091]}, + {"t":0.64876, "x":2.69233, "y":2.12203, "heading":-2.15577, "vx":-2.93654, "vy":-2.67011, "omega":-0.00031, "ax":-0.00062, "ay":-0.00028, "alpha":0.00081, "fx":[-0.0076,-0.0111,-0.01341,-0.00992], "fy":[-0.00422,-0.00191,-0.0054,-0.00772]}, + {"t":0.69201, "x":2.56532, "y":2.00654, "heading":-2.15579, "vx":-2.93656, "vy":-2.67012, "omega":-0.00027, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[-0.00001,-0.00001,-0.00001,-0.00001], "fy":[0.00001,0.00001,0.00001,0.00001]}, + {"t":0.73526, "x":2.43832, "y":1.89106, "heading":-2.1558, "vx":-2.93656, "vy":-2.67012, "omega":-0.00027, "ax":0.00061, "ay":0.00029, "alpha":-0.00081, "fx":[0.00755,0.01105,0.01336,0.00987], "fy":[0.00428,0.00197,0.00546,0.00777]}, + {"t":0.77851, "x":2.31131, "y":1.77558, "heading":-2.15581, "vx":-2.93654, "vy":-2.67011, "omega":-0.00031, "ax":1.21564, "ay":1.10425, "alpha":-3.09988, "fx":[9.45427,23.9232,31.35144,17.98155], "fy":[17.35637,7.29761,20.46739,30.01052]}, + {"t":0.82176, "x":2.18544, "y":1.66113, "heading":-2.15582, "vx":-2.88396, "vy":-2.62235, "omega":-0.13438, "ax":4.71011, "ay":4.2832, "alpha":-0.4563, "fx":[78.92834,82.02797,81.26521,78.24912], "fy":[74.12022,70.70106,71.67191,74.9311]}, + {"t":0.86501, "x":2.06511, "y":1.55171, "heading":-2.16164, "vx":-2.68025, "vy":-2.4371, "omega":-0.15411, "ax":4.74573, "ay":4.31535, "alpha":-0.01614, "fx":[80.68202,80.79097,80.76491,80.65607], "fy":[73.44753,73.32808,73.35843,73.47768]}, + {"t":0.90826, "x":1.95363, "y":1.45034, "heading":-2.1683, "vx":-2.47499, "vy":-2.25046, "omega":-0.15481, "ax":4.75682, "ay":4.32536, "alpha":0.13197, "fx":[81.25225,80.36251,80.56831,81.4654], "fy":[73.20607,74.17961,73.94707,72.95981]}, + {"t":0.95151, "x":1.85104, "y":1.35706, "heading":-2.175, "vx":-2.26926, "vy":-2.06338, "omega":-0.1491, "ax":4.7622, "ay":4.33022, "alpha":0.20605, "fx":[81.5384,80.14932,80.45992,81.86727], "fy":[73.0777,74.59625,74.25068,72.69857]}, + {"t":0.99476, "x":1.75734, "y":1.27187, "heading":-2.18145, "vx":-2.06329, "vy":-1.8761, "omega":-0.14019, "ax":4.76538, "ay":4.33309, "alpha":0.25046, "fx":[81.7128,80.0237,80.38905,82.10564], "fy":[72.9955,74.8412,74.43851,72.54312]}, + {"t":1.03801, "x":1.67256, "y":1.19478, "heading":-2.18751, "vx":-1.85718, "vy":-1.68869, "omega":-0.12936, "ax":4.76748, "ay":4.33498, "alpha":0.28003, "fx":[81.83158,79.94201,80.33786,82.26239], "fy":[72.93696,75.00125,74.56765,72.44118]}, + {"t":1.08126, "x":1.5967, "y":1.12579, "heading":-2.1931, "vx":-1.65099, "vy":-1.5012, "omega":-0.11725, "ax":4.76897, "ay":4.33632, "alpha":0.30113, "fx":[81.91843,79.88529,80.29854,82.37273], "fy":[72.89242,75.11332,74.6627,72.36984]}, + {"t":1.12451, "x":1.52975, "y":1.06492, "heading":-2.19817, "vx":-1.44473, "vy":-1.31366, "omega":-0.10423, "ax":4.77007, "ay":4.33732, "alpha":0.31695, "fx":[81.98506,79.84396,80.2671,82.45429], "fy":[72.85708,75.1958,74.73597,72.31749]}, + {"t":1.16776, "x":1.47173, "y":1.01216, "heading":-2.20268, "vx":-1.23842, "vy":-1.12607, "omega":-0.09052, "ax":4.77093, "ay":4.3381, "alpha":0.32923, "fx":[82.03791,79.81267,80.24134,82.51691], "fy":[72.82827,75.25888,74.79429,72.2776]}, + {"t":1.21101, "x":1.42263, "y":0.96752, "heading":-2.2066, "vx":-1.03208, "vy":-0.93844, "omega":-0.07628, "ax":4.77162, "ay":4.33871, "alpha":0.33906, "fx":[82.08082,79.78819,80.21992,82.56647], "fy":[72.8044,75.30866,74.84177,72.24622]}, + {"t":1.25426, "x":1.38245, "y":0.93099, "heading":-2.2099, "vx":-0.8257, "vy":-0.75079, "omega":-0.06161, "ax":4.77218, "ay":4.33922, "alpha":0.34709, "fx":[82.11621,79.76843,80.202,82.60675], "fy":[72.78449,75.34903,74.88101,72.22081]}, + {"t":1.29751, "x":1.3512, "y":0.90257, "heading":-2.21256, "vx":-0.6193, "vy":-0.56312, "omega":-0.0466, "ax":4.77264, "ay":4.33964, "alpha":0.35378, "fx":[82.1457,79.75202,80.187,82.64027], "fy":[72.76786,75.38256,74.91375,72.19966]}, + {"t":1.34076, "x":1.32888, "y":0.88228, "heading":-2.21458, "vx":-0.41289, "vy":-0.37543, "omega":-0.0313, "ax":4.77303, "ay":4.33999, "alpha":0.35943, "fx":[82.17038,79.73797,80.17455,82.66877], "fy":[72.75406,75.41107,74.94119,72.18158]}, + {"t":1.38401, "x":1.31549, "y":0.8701, "heading":-2.21593, "vx":-0.20645, "vy":-0.18772, "omega":-0.01576, "ax":4.77337, "ay":4.34029, "alpha":0.36428, "fx":[82.19104,79.7256,80.16436,82.6935], "fy":[72.74277,75.43584,74.96417,72.16572]}, + {"t":1.42726, "x":1.31103, "y":0.86604, "heading":-2.21661, "vx":0.0, "vy":0.0, "omega":0.0, "ax":2.92009, "ay":5.66075, "alpha":-3.33895, "fx":[29.87871,64.33176,64.81516,39.65414], "fy":[105.52346,88.80521,88.52067,102.30195]}, + {"t":1.45414, "x":1.31208, "y":0.86808, "heading":-2.21661, "vx":0.07849, "vy":0.15216, "omega":-0.08975, "ax":2.92076, "ay":5.6625, "alpha":-3.28889, "fx":[30.20895,64.09729,64.63764,39.78129], "fy":[105.42035,88.96343,88.64131,102.24494]}, + {"t":1.48102, "x":1.31524, "y":0.87422, "heading":-2.21902, "vx":0.157, "vy":0.30436, "omega":-0.17815, "ax":2.92152, "ay":5.66438, "alpha":-3.23333, "fx":[30.54705,63.80063,64.4685,39.96044], "fy":[105.31306,89.16413,88.75433,102.16666]}, + {"t":1.5079, "x":1.32052, "y":0.88445, "heading":-2.22381, "vx":0.23553, "vy":0.45661, "omega":-0.26506, "ax":2.92236, "ay":5.66642, "alpha":-3.17158, "fx":[30.89943,63.4405,64.30267,40.19136], "fy":[105.1995,89.40716,88.86333,102.06674]}, + {"t":1.53478, "x":1.32791, "y":0.89877, "heading":-2.23094, "vx":0.31408, "vy":0.60892, "omega":-0.35031, "ax":2.92329, "ay":5.66863, "alpha":-3.10282, "fx":[31.27417,63.0151,64.13382,40.474], "fy":[105.07696,89.6925,88.9727,101.94462]}, + {"t":1.56166, "x":1.3374, "y":0.91718, "heading":-2.24035, "vx":0.39265, "vy":0.76129, "omega":-0.43371, "ax":2.9243, "ay":5.67102, "alpha":-3.02599, "fx":[31.68118,62.52214,63.95412,40.80843], "fy":[104.94198,90.02019,89.0878,101.79956]}, + {"t":1.58854, "x":1.34902, "y":0.93969, "heading":-2.25201, "vx":0.47125, "vy":0.91372, "omega":-0.51505, "ax":2.92539, "ay":5.67362, "alpha":-2.9398, "fx":[32.13262,61.95886,63.75377,41.19492], "fy":[104.79017,90.39028,89.21524,101.6306]}, + {"t":1.61542, "x":1.36274, "y":0.9663, "heading":-2.26586, "vx":0.54989, "vy":1.06623, "omega":-0.59407, "ax":2.92656, "ay":5.67644, "alpha":-2.84262, "fx":[32.64333,61.32214,63.52045,41.63397], "fy":[104.61597,90.80272,89.36318,101.43647]}, + {"t":1.6423, "x":1.37858, "y":0.99701, "heading":-2.28182, "vx":0.62855, "vy":1.2188, "omega":-0.67047, "ax":2.92781, "ay":5.6795, "alpha":-2.73239, "fx":[33.2316,60.60849,63.23848,42.12644], "fy":[104.41219,91.25734,89.54186,101.21556]}, + {"t":1.66918, "x":1.39653, "y":1.03183, "heading":-2.29985, "vx":0.70725, "vy":1.37146, "omega":-0.74392, "ax":2.92914, "ay":5.68283, "alpha":-2.60639, "fx":[33.92019,59.8141,62.8875,42.67369], "fy":[104.16943,91.75368,89.76422,100.96576]}, + {"t":1.69606, "x":1.4166, "y":1.07074, "heading":-2.31984, "vx":0.78598, "vy":1.52421, "omega":-0.81398, "ax":2.93055, "ay":5.68642, "alpha":-2.46104, "fx":[34.73795,58.93487,62.44057,43.27782], "fy":[103.87514,92.29098,90.04694,100.68426]}, + {"t":1.72293, "x":1.43878, "y":1.11377, "heading":-2.34172, "vx":0.86475, "vy":1.67706, "omega":-0.88013, "ax":2.93203, "ay":5.69027, "alpha":-2.29143, "fx":[35.72224,57.96633,61.86119,43.94217], "fy":[103.51201,92.86809,90.41183,100.3672]}, + {"t":1.74981, "x":1.46309, "y":1.1609, "heading":-2.36538, "vx":0.94356, "vy":1.83001, "omega":-0.94172, "ax":2.93357, "ay":5.69433, "alpha":-2.09063, "fx":[36.92279,56.90354,61.0983,44.67201], "fy":[103.05551,93.48342,90.88801,100.00906]}, + {"t":1.77669, "x":1.48951, "y":1.21215, "heading":-2.39069, "vx":1.02241, "vy":1.98307, "omega":-0.99791, "ax":2.93513, "ay":5.69853, "alpha":-1.84854, "fx":[38.40789,55.74073,60.07801,45.47599], "fy":[102.46943,94.135,91.51532,99.6016]}, + {"t":1.80357, "x":1.51805, "y":1.26751, "heading":-2.41751, "vx":1.10131, "vy":2.13624, "omega":-1.0476, "ax":2.9366, "ay":5.70262, "alpha":-1.54987, "fx":[40.27481,54.47066,58.68866,46.36867], "fy":[101.69795,94.82058,92.34961,99.13177]}, + {"t":1.83045, "x":1.54871, "y":1.32699, "heading":-2.44567, "vx":1.18024, "vy":2.28952, "omega":-1.08926, "ax":2.93773, "ay":5.70611, "alpha":-1.17048, "fx":[42.66782,53.08323,56.75272,47.37576], "fy":[100.65046,95.53789,93.47133,98.57754]}, + {"t":1.85733, "x":1.5815, "y":1.39059, "heading":-2.47495, "vx":1.2592, "vy":2.4429, "omega":-1.12072, "ax":2.93787, "ay":5.70782, "alpha":-0.67009, "fx":[45.81101,51.56289,53.96968,48.54557], "fy":[99.17038,96.28529,94.99917,97.8985]}, + {"t":1.88421, "x":1.61641, "y":1.45832, "heading":-2.50507, "vx":1.33817, "vy":2.59632, "omega":-1.13873, "ax":2.93539, "ay":5.70483, "alpha":0.0228, "fx":[50.07035,49.88337,49.78987,49.97722], "fy":[96.9657,97.06281,97.10922,97.01215]}, + {"t":1.91109, "x":1.65343, "y":1.53016, "heading":-2.53568, "vx":1.41707, "vy":2.74966, "omega":-1.13812, "ax":2.92596, "ay":5.6891, "alpha":1.04599, "fx":[56.07385,47.99686,43.10575,51.90259], "fy":[93.43849,97.87431,100.0447,95.72212]}, + {"t":1.93797, "x":1.69258, "y":1.60613, "heading":-2.56627, "vx":1.49572, "vy":2.90258, "omega":-1.11, "ax":2.89755, "ay":5.6345, "alpha":2.69283, "fx":[64.92903,45.81095,31.4142,54.99167], "fy":[87.21837,98.73111,103.98317,93.432]}, + {"t":1.96485, "x":1.73383, "y":1.68618, "heading":-2.59611, "vx":1.5736, "vy":3.05403, "omega":-1.03762, "ax":2.82429, "ay":5.43028, "alpha":5.66301, "fx":[78.35624,43.14565,8.57011,62.0892], "fy":[74.82361,99.6525,107.74498,87.24907]}, + {"t":1.99173, "x":1.77715, "y":1.77023, "heading":-2.624, "vx":1.64952, "vy":3.19999, "omega":-0.88541, "ax":2.84221, "ay":4.41824, "alpha":11.80305, "fx":[94.07034,40.23429,-29.33967,88.41565], "fy":[52.37712,100.37834,103.09692,44.75962]}, + {"t":2.01861, "x":1.82251, "y":1.85784, "heading":-2.6478, "vx":1.72591, "vy":3.31875, "omega":-0.56815, "ax":2.65628, "ay":4.20466, "alpha":12.33669, "fx":[93.37801,40.04528,-30.80219,78.10945], "fy":[49.38559,98.78196,100.24818,37.6642]}, + {"t":2.04548, "x":1.86986, "y":1.94857, "heading":-2.66307, "vx":1.79731, "vy":3.43177, "omega":-0.23655, "ax":1.25521, "ay":3.20772, "alpha":8.58399, "fx":[58.30418,27.27734,-15.956,15.77745], "fy":[43.53044,75.80693,69.27059,29.64139]}, + {"t":2.07236, "x":1.91863, "y":2.04197, "heading":-2.66943, "vx":1.83105, "vy":3.51799, "omega":-0.00582, "ax":-0.26015, "ay":0.15904, "alpha":0.05173, "fx":[-4.24463,-4.36621,-4.60535,-4.48384], "fy":[2.64703,2.8862,2.76346,2.52429]}, + {"t":2.09924, "x":1.96775, "y":2.13659, "heading":-2.66959, "vx":1.82406, "vy":3.52226, "omega":-0.00443, "ax":-0.11455, "ay":0.05933, "alpha":0.00015, "fx":[-1.94792,-1.94828,-1.94897,-1.94862], "fy":[1.00904,1.00974,1.00938,1.00868]}, + {"t":2.12612, "x":2.01674, "y":2.23128, "heading":-2.6697, "vx":1.82098, "vy":3.52386, "omega":-0.00442, "ax":-0.03251, "ay":0.0168, "alpha":0.0, "fx":[-0.55296,-0.55297,-0.55299,-0.55298], "fy":[0.28567,0.28569,0.28568,0.28567]}, + {"t":2.153, "x":2.06567, "y":2.32601, "heading":-2.66982, "vx":1.82011, "vy":3.52431, "omega":-0.00442, "ax":0.02864, "ay":-0.0148, "alpha":0.0, "fx":[0.48718,0.48718,0.48719,0.48718], "fy":[-0.25168,-0.25168,-0.25168,-0.25167]}, + {"t":2.17988, "x":2.11461, "y":2.42073, "heading":-2.66994, "vx":1.82088, "vy":3.52391, "omega":-0.00442, "ax":0.10819, "ay":-0.05604, "alpha":-0.00016, "fx":[1.83975,1.84013,1.84088,1.8405], "fy":[-0.95307,-0.95381,-0.95343,-0.95269]}, + {"t":2.20676, "x":2.16359, "y":2.51543, "heading":-2.67006, "vx":1.82379, "vy":3.5224, "omega":-0.00443, "ax":0.24644, "ay":-0.15396, "alpha":-0.05644, "fx":[3.99513,4.12767,4.38867,4.2562], "fy":[-2.5551,-2.81611,-2.68242,-2.42141]}, + {"t":2.23364, "x":2.2127, "y":2.61006, "heading":-2.67018, "vx":1.83041, "vy":3.51827, "omega":-0.00595, "ax":-1.33066, "ay":-3.27673, "alpha":-8.8129, "fx":[-60.69442,-28.64778,16.04776,-17.24202], "fy":[-43.8798,-77.20084,-71.35757,-30.50691]}, + {"t":2.26052, "x":2.26142, "y":2.70344, "heading":-2.67034, "vx":1.79464, "vy":3.43019, "omega":-0.24283, "ax":-2.64862, "ay":-4.20972, "alpha":-12.25578, "fx":[-94.04495,-41.08154,30.38917,-75.47202], "fy":[-48.10638,-98.39216,-100.48306,-39.44268]}, + {"t":2.2874, "x":2.3087, "y":2.79412, "heading":-2.67687, "vx":1.72345, "vy":3.31704, "omega":-0.57225, "ax":-2.84236, "ay":-4.38926, "alpha":-11.74826, "fx":[-95.88295,-42.45233,29.44199,-84.49732], "fy":[-48.91165,-99.48091,-103.167,-47.08075]}, + {"t":2.31428, "x":2.354, "y":2.88169, "heading":-2.69225, "vx":1.64705, "vy":3.19906, "omega":-0.88804, "ax":-2.80853, "ay":-5.41005, "alpha":-5.89864, "fx":[-81.16057,-45.60659,-6.49395,-57.82793], "fy":[-71.70707,-98.56709,-107.94538,-89.87376]}, + {"t":2.34116, "x":2.39726, "y":2.96573, "heading":-2.71612, "vx":1.57156, "vy":3.05364, "omega":-1.04659, "ax":-2.89304, "ay":-5.62754, "alpha":-2.87526, "fx":[-66.82403,-47.9273,-29.90942,-52.17808], "fy":[-85.73389,-97.72942,-104.45159,-94.97657]}, + {"t":2.36803, "x":2.43845, "y":3.04577, "heading":-2.74425, "vx":1.4938, "vy":2.90238, "omega":-1.12387, "ax":-2.92485, "ay":-5.68746, "alpha":-1.14766, "fx":[-57.03764,-49.25193,-42.22504,-50.48874], "fy":[-92.83321,-97.25116,-100.42767,-96.45651]}, + {"t":2.39491, "x":2.47755, "y":3.12173, "heading":-2.77446, "vx":1.41518, "vy":2.7495, "omega":-1.15472, "ax":-2.93512, "ay":-5.70469, "alpha":-0.06295, "fx":[-50.3329,-49.90401,-49.51752,-49.94765], "fy":[-96.82523,-97.05022,-97.24435,-97.02084]}, + {"t":2.42179, "x":2.51453, "y":3.19358, "heading":-2.8055, "vx":1.33628, "vy":2.59616, "omega":-1.15641, "ax":-2.93765, "ay":-5.70774, "alpha":0.67113, "fx":[-45.58308,-50.09942,-54.29457,-49.89727], "fy":[-99.28238,-97.04941,-94.80094,-97.21544]}, + {"t":2.44867, "x":2.54939, "y":3.2613, "heading":-2.83658, "vx":1.25732, "vy":2.44274, "omega":-1.13837, "ax":-2.93727, "ay":-5.70568, "alpha":1.19714, "fx":[-42.10956,-49.97966,-57.66296,-50.09663], "fy":[-100.90084,-97.18937,-92.89288,-97.22481]}, + {"t":2.47555, "x":2.58212, "y":3.3249, "heading":-2.86718, "vx":1.17837, "vy":2.28938, "omega":-1.1062, "ax":-2.93577, "ay":-5.70182, "alpha":1.59116, "fx":[-39.50373,-49.64093,-60.1682,-50.43338], "fy":[-102.02189,-97.42572,-91.36764,-97.13027]}, + {"t":2.50243, "x":2.61273, "y":3.38437, "heading":-2.89691, "vx":1.09946, "vy":2.13612, "omega":-1.06343, "ax":-2.93382, "ay":-5.69748, "alpha":1.89703, "fx":[-37.50987,-49.15137,-62.10605,-50.84671], "fy":[-102.82835,-97.7253,-90.12235,-96.97421]}, + {"t":2.52931, "x":2.64123, "y":3.43973, "heading":-2.9255, "vx":1.0206, "vy":1.98298, "omega":-1.01244, "ax":-2.93173, "ay":-5.69319, "alpha":2.14158, "fx":[-35.96081,-48.56102,-63.64974,-51.30012], "fy":[-103.42558,-98.06322,-89.0877,-96.78146]}, + {"t":2.55619, "x":2.6676, "y":3.49098, "heading":-2.95271, "vx":0.9418, "vy":1.82995, "omega":-0.95487, "ax":-2.92962, "ay":-5.68914, "alpha":2.34201, "fx":[-34.74268,-47.90775,-64.90736,-51.7701], "fy":[-103.8781,-98.42072,-88.21585,-96.56793]}, + {"t":2.58307, "x":2.69186, "y":3.53811, "heading":-2.97838, "vx":0.86305, "vy":1.67703, "omega":-0.89192, "ax":-2.92754, "ay":-5.6854, "alpha":2.50976, "fx":[-33.77509,-47.22087,-65.95004,-52.24065], "fy":[-104.22743,-98.78364,-87.4728,-96.34449]}, + {"t":2.60995, "x":2.714, "y":3.58113, "heading":-3.00235, "vx":0.78436, "vy":1.52421, "omega":-0.82446, "ax":-2.92553, "ay":-5.68198, "alpha":2.65266, "fx":[-32.99941,-46.52347,-66.82675,-52.70041], "fy":[-104.50146,-99.1414,-86.83356,-96.11904]}, + {"t":2.63683, "x":2.73402, "y":3.62005, "heading":-3.02451, "vx":0.70573, "vy":1.37148, "omega":-0.75316, "ax":-2.92361, "ay":-5.67885, "alpha":2.77619, "fx":[-32.37172,-45.8339,-67.57252,-53.14105], "fy":[-104.71962,-99.48607,-86.27926,-95.8975]}, + {"t":2.66371, "x":2.75194, "y":3.65486, "heading":-3.04476, "vx":0.62714, "vy":1.21884, "omega":-0.67854, "ax":-2.92178, "ay":-5.67598, "alpha":2.88424, "fx":[-31.85836,-45.16687,-68.21326,-53.55633], "fy":[-104.89589,-99.81187,-85.79521,-95.68454]}, + {"t":2.69059, "x":2.76774, "y":3.68557, "heading":-3.06299, "vx":0.54861, "vy":1.06627, "omega":-0.60101, "ax":-2.92006, "ay":-5.67336, "alpha":2.97964, "fx":[-31.43299,-44.53424,-68.76874,-53.94144], "fy":[-105.0406,-100.11458,-85.3697,-95.48387]}, + {"t":2.71746, "x":2.78143, "y":3.71218, "heading":-3.07915, "vx":0.47012, "vy":0.91378, "omega":-0.52092, "ax":-2.91844, "ay":-5.67094, "alpha":3.06448, "fx":[-31.07465,-43.94556,-69.25436,-54.29261], "fy":[-105.16156,-100.39122,-84.99323,-95.29857]}, + {"t":2.74434, "x":2.79301, "y":3.7347, "heading":-3.09315, "vx":0.39167, "vy":0.76135, "omega":-0.43855, "ax":-2.91693, "ay":-5.66873, "alpha":3.14031, "fx":[-30.76648,-43.40859,-69.68237,-54.60683], "fy":[-105.26482,-100.6397,-84.65794,-95.13118]}, + {"t":2.77122, "x":2.80249, "y":3.75311, "heading":-3.10494, "vx":0.31327, "vy":0.60898, "omega":-0.35414, "ax":-2.91552, "ay":-5.66669, "alpha":3.2083, "fx":[-30.49474,-42.92963,-70.06268,-54.88166], "fy":[-105.35511,-100.85859,-84.35729,-94.98386]}, + {"t":2.7981, "x":2.80985, "y":3.76743, "heading":-3.11446, "vx":0.2349, "vy":0.45666, "omega":-0.26791, "ax":-2.91422, "ay":-5.66481, "alpha":3.26936, "fx":[-30.24814,-42.51388,-70.40332,-55.11508], "fy":[-105.43619,-101.04691,-84.0858,-94.85844]}, + {"t":2.82498, "x":2.81511, "y":3.77766, "heading":-3.12166, "vx":0.15657, "vy":0.3044, "omega":-0.18003, "ax":-2.91303, "ay":-5.66309, "alpha":3.32422, "fx":[-30.01741,-42.16567,-70.71085,-55.30538], "fy":[-105.51108,-101.20395,-83.83891,-94.75648]}, + {"t":2.85186, "x":2.81827, "y":3.7838, "heading":-3.1265, "vx":0.07827, "vy":0.15218, "omega":-0.09068, "ax":-2.91194, "ay":-5.66152, "alpha":3.37343, "fx":[-29.79488,-41.88868,-70.99059,-55.45109], "fy":[-105.58219,-101.32917,-83.61282,-94.67932]}, + {"t":2.87874, "x":2.81932, "y":3.78584, "heading":-3.12894, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[ + {"name":"Funnel", "from":{"target":2, "targetTimestamp":2.20676, "offset":{"exp":"0 s", "val":0.0}}, "event":null}] +} diff --git a/src/main/deploy/v2_redundancy/choreo/B_LEFT_PATH1.traj b/src/main/deploy/v2_redundancy/choreo/B_LEFT_PATH1.traj new file mode 100644 index 00000000..85cc38e0 --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/B_LEFT_PATH1.traj @@ -0,0 +1,112 @@ +{ + "name":"B_LEFT_PATH1", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.163801670074463, "y":7.307990074157715, "heading":1.5707963267948966, "intervals":50, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.6384241580963135, "y":5.683813095092773, "heading":0.0, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":2.650822401046753, "y":4.146424770355225, "heading":3.141592653589793, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"7.163801670074463 m", "val":7.163801670074463}, "y":{"exp":"7.307990074157715 m", "val":7.307990074157715}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":50, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.6384241580963135 m", "val":2.6384241580963135}, "y":{"exp":"5.683813095092773 m", "val":5.683813095092773}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"2.650822401046753 m", "val":2.650822401046753}, "y":{"exp":"4.146424770355225 m", "val":4.146424770355225}, "heading":{"exp":"3.141592653589793 rad", "val":3.141592653589793}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.61256,2.35601], + "samples":[ + {"t":0.0, "x":7.1638, "y":7.30799, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.31433, "ay":-0.66516, "alpha":3.79591, "fx":[-106.77168,-103.94195,-109.33802,-109.56787], "fy":[-25.40488,-35.10787,8.94297,6.31308]}, + {"t":0.03506, "x":7.15992, "y":7.30758, "heading":1.5708, "vx":-0.22135, "vy":-0.02332, "omega":0.13307, "ax":-6.31805, "ay":-0.66589, "alpha":3.71408, "fx":[-106.81858,-104.10848,-109.36818,-109.57783], "fy":[-25.17548,-34.5823,8.44681,6.00465]}, + {"t":0.07011, "x":7.14828, "y":7.30635, "heading":1.57546, "vx":-0.44284, "vy":-0.04666, "omega":0.26327, "ax":-6.3221, "ay":-0.66678, "alpha":3.62279, "fx":[-106.85199,-104.31176,-109.3927,-109.59209], "fy":[-24.9969,-33.93075,7.98356,5.57705]}, + {"t":0.10517, "x":7.12887, "y":7.30431, "heading":1.58469, "vx":-0.66446, "vy":-0.07004, "omega":0.39027, "ax":-6.32654, "ay":-0.66782, "alpha":3.51952, "fx":[-106.87556,-104.55273,-109.41341,-109.60916], "fy":[-24.85341,-33.14133,7.52986,5.0273]}, + {"t":0.14022, "x":7.10169, "y":7.30144, "heading":1.59837, "vx":-0.88624, "vy":-0.09345, "omega":0.51365, "ax":-6.33147, "ay":-0.66898, "alpha":3.40104, "fx":[-106.89389,-104.83265,-109.43211,-109.6271], "fy":[-24.72441,-32.1979,7.05523,4.3505]}, + {"t":0.17528, "x":7.06673, "y":7.29776, "heading":1.61638, "vx":-1.1082, "vy":-0.1169, "omega":0.63287, "ax":-6.33696, "ay":-0.67024, "alpha":3.26317, "fx":[-106.91286,-105.15273,-109.45049,-109.64337], "fy":[-24.58256,-31.07985,6.52059,3.53933]}, + {"t":0.21033, "x":7.02399, "y":7.29325, "heading":1.63856, "vx":-1.33035, "vy":-0.14039, "omega":0.74727, "ax":-6.34312, "ay":-0.67158, "alpha":3.10048, "fx":[-106.94024,-105.51371,-109.46988,-109.65467], "fy":[-24.3909,-29.76173,5.87587,2.58307]}, + {"t":0.24539, "x":6.97346, "y":7.28791, "heading":1.66476, "vx":-1.55271, "vy":-0.16394, "omega":0.85596, "ax":-6.35003, "ay":-0.67298, "alpha":2.90572, "fx":[-106.9864,-105.91525,-109.49064,-109.65656], "fy":[-24.09817,-28.21259,5.05623,1.46607]}, + {"t":0.28045, "x":6.91512, "y":7.28175, "heading":1.69477, "vx":-1.77531, "vy":-0.18753, "omega":0.95782, "ax":-6.35776, "ay":-0.6744, "alpha":2.6689, "fx":[-107.06547,-106.35517,-109.51101,-109.64291], "fy":[-23.63074,-26.3949,3.97543,0.1647]}, + {"t":0.3155, "x":6.84898, "y":7.27476, "heading":1.72834, "vx":-1.99819, "vy":-0.21117, "omega":1.05138, "ax":-6.36628, "ay":-0.67586, "alpha":2.37558, "fx":[-107.19667,-106.82848,-109.52457,-109.60471], "fy":[-22.87817,-24.2625,2.51457,-1.35842]}, + {"t":0.35056, "x":6.77502, "y":7.26695, "heading":1.7652, "vx":-2.22136, "vy":-0.23486, "omega":1.13466, "ax":-6.37539, "ay":-0.67736, "alpha":2.00341, "fx":[-107.40603,-107.326,-109.51481,-109.5276], "fy":[-21.66545,-21.75676,0.5013,-3.16619]}, + {"t":0.38561, "x":6.69323, "y":7.2583, "heading":1.80498, "vx":-2.44486, "vy":-0.25861, "omega":1.20489, "ax":-6.3844, "ay":-0.67897, "alpha":1.5152, "fx":[-107.72683,-107.83237,-109.44229,-109.38592], "fy":[-19.69481,-18.79894,-2.32966,-5.37322]}, + {"t":0.42067, "x":6.6036, "y":7.24881, "heading":1.84721, "vx":-2.66867, "vy":-0.28241, "omega":1.258, "ax":-6.39124, "ay":-0.68069, "alpha":0.84273, "fx":[-108.19188,-108.32235,-109.21236,-109.1264], "fy":[-16.4114,-15.27442,-6.41667,-8.21065]}, + {"t":0.45572, "x":6.50612, "y":7.2385, "heading":1.89131, "vx":-2.89272, "vy":-0.30627, "omega":1.28755, "ax":-6.38942, "ay":-0.68209, "alpha":-0.15507, "fx":[-108.77955,-108.75268,-108.58356,-108.61294], "fy":[-10.64886,-10.99902,-12.54451,-12.21598]}, + {"t":0.49078, "x":6.40079, "y":7.22734, "heading":1.93645, "vx":-3.1167, "vy":-0.33018, "omega":1.28211, "ax":-6.35451, "ay":-0.68136, "alpha":-1.82433, "fx":[-109.07056,-109.04051,-106.8714,-107.37107], "fy":[0.47067,-5.6432,-22.24008,-18.94625]}, + {"t":0.52584, "x":6.28763, "y":7.21535, "heading":1.98139, "vx":-3.33946, "vy":-0.35407, "omega":1.21816, "ax":-6.15681, "ay":-0.68805, "alpha":-5.28855, "fx":[-105.59082,-108.99546,-101.85362,-102.46247], "fy":[25.42423,1.43619,-38.60211,-35.07231]}, + {"t":0.56089, "x":6.16678, "y":7.20251, "heading":2.0241, "vx":-3.5553, "vy":-0.37819, "omega":1.03276, "ax":-5.08959, "ay":-0.96681, "alpha":-13.30588, "fx":[-83.1462,-108.29115,-90.35543,-64.4974], "fy":[68.52344,9.02412,-60.04031,-83.28796]}, + {"t":0.59595, "x":6.03902, "y":7.18866, "heading":2.0603, "vx":-3.73372, "vy":-0.41208, "omega":0.56631, "ax":-4.946, "ay":-0.91653, "alpha":-13.31055, "fx":[-80.29201,-107.08233,-88.19314,-60.95254], "fy":[68.6648,8.36479,-60.54766,-78.84188]}, + {"t":0.631, "x":5.90509, "y":7.17365, "heading":2.08016, "vx":-3.9071, "vy":-0.44421, "omega":0.0997, "ax":-1.07534, "ay":0.49336, "alpha":-2.72579, "fx":[-15.5327,-27.49389,-21.35461,-8.7838], "fy":[18.30479,10.92264,-1.49623,5.83655]}, + {"t":0.66606, "x":5.76746, "y":7.15838, "heading":2.08365, "vx":-3.9448, "vy":-0.42692, "omega":0.00415, "ax":-0.02315, "ay":0.20411, "alpha":-0.00308, "fx":[-0.39077,-0.40473,-0.3969,-0.38293], "fy":[3.48265,3.47484,3.4609,3.46872]}, + {"t":0.70111, "x":5.62916, "y":7.14354, "heading":2.0838, "vx":-3.94561, "vy":-0.41976, "omega":0.00404, "ax":-0.00687, "ay":0.06477, "alpha":-0.00001, "fx":[-0.11691,-0.11697,-0.11694,-0.11688], "fy":[1.10174,1.10171,1.10165,1.10168]}, + {"t":0.73617, "x":5.49084, "y":7.12887, "heading":2.08394, "vx":-3.94585, "vy":-0.41749, "omega":0.00404, "ax":-0.00182, "ay":0.01717, "alpha":0.0, "fx":[-0.03087,-0.03089,-0.03088,-0.03086], "fy":[0.292,0.29199,0.29198,0.29198]}, + {"t":0.77123, "x":5.35252, "y":7.11424, "heading":2.08408, "vx":-3.94591, "vy":-0.41689, "omega":0.00404, "ax":0.00064, "ay":-0.00604, "alpha":0.0, "fx":[0.01086,0.01086,0.01086,0.01086], "fy":[-0.10274,-0.10275,-0.10275,-0.10275]}, + {"t":0.80628, "x":5.21419, "y":7.09962, "heading":2.08422, "vx":-3.94589, "vy":-0.4171, "omega":0.00404, "ax":0.00401, "ay":-0.03783, "alpha":0.0, "fx":[0.06814,0.06815,0.06814,0.06813], "fy":[-0.64354,-0.64353,-0.64352,-0.64353]}, + {"t":0.84134, "x":5.07587, "y":7.08498, "heading":2.08436, "vx":-3.94575, "vy":-0.41843, "omega":0.00404, "ax":0.01315, "ay":-0.12336, "alpha":0.00001, "fx":[0.2237,0.22377,0.22373,0.22366], "fy":[-2.0984,-2.09837,-2.0983,-2.09834]}, + {"t":0.87639, "x":4.93755, "y":7.07023, "heading":2.0845, "vx":-3.94529, "vy":-0.42275, "omega":0.00404, "ax":0.0417, "ay":-0.38291, "alpha":0.00006, "fx":[0.70925,0.70951,0.70937,0.70911], "fy":[-6.51341,-6.51327,-6.51301,-6.51316]}, + {"t":0.91145, "x":4.79927, "y":7.05518, "heading":2.08465, "vx":-3.94383, "vy":-0.43617, "omega":0.00404, "ax":0.13327, "ay":-1.15045, "alpha":0.00023, "fx":[2.26662,2.26772,2.26711,2.26601], "fy":[-19.56967,-19.56908,-19.56806,-19.56865]}, + {"t":0.9465, "x":4.6611, "y":7.03918, "heading":2.08479, "vx":-3.93916, "vy":-0.4765, "omega":0.00405, "ax":0.38708, "ay":-2.88535, "alpha":0.00085, "fx":[6.58303,6.58774,6.58535,6.58065], "fy":[-49.08147,-49.07952,-49.07655,-49.0785]}, + {"t":0.98156, "x":4.52325, "y":7.0207, "heading":2.08493, "vx":-3.92559, "vy":-0.57765, "omega":0.00408, "ax":0.78846, "ay":-4.67063, "alpha":0.00207, "fx":[13.40709,13.42214,13.41582,13.40077], "fy":[-79.45011,-79.44586,-79.44219,-79.44644]}, + {"t":1.01662, "x":4.38612, "y":6.99759, "heading":2.08507, "vx":-3.89795, "vy":-0.74138, "omega":0.00415, "ax":1.19202, "ay":-5.5066, "alpha":0.00367, "fx":[20.26579,20.29678,20.28616,20.25516], "fy":[-93.67082,-93.66273,-93.66059,-93.66867]}, + {"t":1.05167, "x":4.25021, "y":6.96821, "heading":2.08522, "vx":-3.85616, "vy":-0.93442, "omega":0.00428, "ax":1.57297, "ay":-5.801, "alpha":0.00554, "fx":[26.73775,26.78768,26.77391,26.72396], "fy":[-98.68064,-98.66611,-98.66598,-98.6805]}, + {"t":1.08673, "x":4.11599, "y":6.93189, "heading":2.08537, "vx":-3.80102, "vy":-1.13778, "omega":0.00448, "ax":1.93896, "ay":-5.87337, "alpha":0.0078, "fx":[32.95278,33.02481,33.00948,32.93739], "fy":[-99.91571,-99.89124,-99.89284,-99.91732]}, + {"t":1.12178, "x":3.98394, "y":6.8884, "heading":2.08553, "vx":-3.73305, "vy":-1.34368, "omega":0.00475, "ax":2.29416, "ay":-5.84237, "alpha":0.01111, "fx":[38.97924,39.0824,39.06666,38.9634], "fy":[-99.39609,-99.35509,-99.35787,-99.39889]}, + {"t":1.15684, "x":3.85448, "y":6.8377, "heading":2.08569, "vx":-3.65262, "vy":-1.54848, "omega":0.00514, "ax":2.64248, "ay":-5.75159, "alpha":0.02616, "fx":[44.83879,45.07942,45.05713,44.81589], "fy":[-97.88616,-97.77508,-97.77945,-97.89075]}, + {"t":1.19189, "x":3.72806, "y":6.77989, "heading":2.08587, "vx":-3.55999, "vy":-1.75011, "omega":0.00606, "ax":3.01865, "ay":-5.60066, "alpha":0.19141, "fx":[50.5176,52.22499,52.19078,50.45238], "fy":[-95.7296,-94.80826,-94.79359,-95.73084]}, + {"t":1.22695, "x":3.60512, "y":6.71509, "heading":2.08608, "vx":-3.45417, "vy":-1.94644, "omega":0.01277, "ax":3.60553, "ay":-5.2551, "alpha":1.27445, "fx":[55.8629,65.99099,67.38428,56.07805], "fy":[-93.21179,-86.35181,-85.08178,-92.90566]}, + {"t":1.26201, "x":3.48624, "y":6.64363, "heading":2.08653, "vx":-3.32777, "vy":-2.13067, "omega":0.05744, "ax":4.29187, "ay":-4.66929, "alpha":2.86258, "fx":[61.4836,80.38461,86.48035,63.66529], "fy":[-89.97029,-73.63397,-65.98976,-88.09886]}, + {"t":1.29706, "x":3.37222, "y":6.56607, "heading":2.08855, "vx":-3.17732, "vy":-2.29435, "omega":0.15779, "ax":4.79653, "ay":-4.09967, "alpha":3.78485, "fx":[67.22082,88.89522,97.733,72.50168], "fy":[-86.0102,-63.45553,-48.27699,-81.19446]}, + {"t":1.33212, "x":3.26379, "y":6.48312, "heading":2.09408, "vx":-3.00917, "vy":-2.43807, "omega":0.29047, "ax":5.14217, "ay":-3.63, "alpha":4.19206, "fx":[72.30458,93.96445,103.27626,80.32208], "fy":[-81.95402,-55.93539,-35.4107,-73.68085]}, + {"t":1.36717, "x":3.16146, "y":6.39542, "heading":2.10426, "vx":-2.82891, "vy":-2.56532, "omega":0.43743, "ax":5.39135, "ay":-3.24812, "alpha":4.28534, "fx":[76.91758,97.27577,105.98271,86.64505], "fy":[-77.76953,-50.15111,-26.73613,-66.34158]}, + {"t":1.40223, "x":3.0656, "y":6.3035, "heading":2.11959, "vx":-2.63991, "vy":-2.67919, "omega":0.58766, "ax":5.5826, "ay":-2.92924, "alpha":4.18911, "fx":[81.24844,99.64999,107.35668,91.57834], "fy":[-73.33495,-45.4029,-21.01373,-59.55081]}, + {"t":1.43728, "x":2.97649, "y":6.20777, "heading":2.14019, "vx":-2.44421, "vy":-2.78187, "omega":0.73451, "ax":5.73743, "ay":-2.65327, "alpha":3.96566, "fx":[85.39966,101.48501,108.08299,95.40064], "fy":[-68.5399,-41.26077,-17.31846,-53.40657]}, + {"t":1.47234, "x":2.89433, "y":6.10862, "heading":2.16594, "vx":-2.24308, "vy":-2.87489, "omega":0.87353, "ax":5.86865, "ay":-2.40469, "alpha":3.64047, "fx":[89.42975,102.98388,108.47173,98.41085], "fy":[-63.26318,-37.46422,-15.07033,-47.81429]}, + {"t":1.5074, "x":2.8193, "y":6.00637, "heading":2.19657, "vx":-2.03735, "vy":-2.95918, "omega":1.00115, "ax":5.98348, "ay":-2.17193, "alpha":3.22395, "fx":[93.34334,104.2516,108.66795,100.84608], "fy":[-57.39567,-33.86211,-13.90944,-42.60865]}, + {"t":1.54245, "x":2.75156, "y":5.90129, "heading":2.23166, "vx":-1.8276, "vy":-3.03532, "omega":1.11416, "ax":6.08309, "ay":-1.95124, "alpha":2.74257, "fx":[96.99087,105.32698,108.74978,102.8188], "fy":[-51.04944,-30.42668,-13.52491,-37.75879]}, + {"t":1.57751, "x":2.69123, "y":5.79369, "heading":2.27072, "vx":-1.61435, "vy":-3.10372, "omega":1.21031, "ax":6.1652, "ay":-1.74704, "alpha":2.2471, "fx":[100.12584,106.21227,108.76939,104.36543], "fy":[-44.64481,-27.24262,-13.58754,-33.39147]}, + {"t":1.61256, "x":2.63842, "y":5.68381, "heading":2.31315, "vx":-1.39822, "vy":-3.16497, "omega":1.28908, "ax":6.22802, "ay":-1.51109, "alpha":2.06343, "fx":[102.14338,107.06692,108.99228,105.54463], "fy":[-39.58478,-23.30258,-10.8244,-29.10098]}, + {"t":1.6382, "x":2.60463, "y":5.60218, "heading":2.34619, "vx":-1.23856, "vy":-3.20371, "omega":1.34198, "ax":6.29629, "ay":-1.19159, "alpha":2.03359, "fx":[104.03881,108.0486,109.36667,106.93842], "fy":[-34.21134,-18.07502,-5.459,-23.32897]}, + {"t":1.66384, "x":2.57494, "y":5.51966, "heading":2.3806, "vx":-1.07715, "vy":-3.23425, "omega":1.39411, "ax":6.35723, "ay":-0.80753, "alpha":1.96526, "fx":[105.98267,108.87619,109.47248,108.20729], "fy":[-27.48828,-11.88639,0.68823,-16.25721]}, + {"t":1.68947, "x":2.54942, "y":5.43648, "heading":2.41634, "vx":-0.91418, "vy":-3.25496, "omega":1.44449, "ax":6.4007, "ay":-0.34358, "alpha":1.83845, "fx":[107.79931,109.39956,109.17307,109.12407], "fy":[-18.96828,-4.4984,7.69687,-7.60677]}, + {"t":1.71511, "x":2.52809, "y":5.35292, "heading":2.45337, "vx":-0.75009, "vy":-3.26376, "omega":1.49162, "ax":6.40941, "ay":0.21505, "alpha":1.63368, "fx":[109.11133,109.36932,108.2876,109.32063], "fy":[-8.18128,4.35987,15.64185,2.81138]}, + {"t":1.74074, "x":2.51096, "y":5.26932, "heading":2.49161, "vx":-0.58578, "vy":-3.25825, "omega":1.5335, "ax":6.35697, "ay":0.87751, "alpha":1.33816, "fx":[109.25364,108.39003,106.5791,108.29844], "fy":[5.20582,14.94598,24.5843,14.96849]}, + {"t":1.76638, "x":2.49803, "y":5.18608, "heading":2.53092, "vx":-0.42281, "vy":-3.23575, "omega":1.56781, "ax":6.20838, "ay":1.64129, "alpha":0.94581, "fx":[107.26459,105.87678,103.75421,105.51565], "fy":[21.1967,27.42659,34.51453,28.53373]}, + {"t":1.79202, "x":2.48924, "y":5.10367, "heading":2.57111, "vx":-0.26365, "vy":-3.19368, "omega":1.59206, "ax":5.92515, "ay":2.48412, "alpha":0.45991, "fx":[102.04444,101.05091,99.49619,100.54905], "fy":[39.17964,41.72492,45.27644,42.83543]}, + {"t":1.81765, "x":2.48442, "y":5.02261, "heading":2.61193, "vx":-0.11175, "vy":-3.13, "omega":1.60385, "ax":5.47809, "ay":3.35733, "alpha":-0.09966, "fx":[92.81744,93.06746,93.54364,93.2942], "fy":[57.7001,57.28685,56.51093,56.93081]}, + {"t":1.84329, "x":2.48336, "y":4.94348, "heading":2.65304, "vx":0.02868, "vy":-3.04393, "omega":1.60129, "ax":4.86546, "ay":4.19033, "alpha":-0.69506, "fx":[79.7678,81.37885,85.80562,84.08793], "fy":[74.71281,72.89982,67.65791,69.8346]}, + {"t":1.86892, "x":2.48569, "y":4.86682, "heading":2.69409, "vx":0.15341, "vy":-2.9365, "omega":1.58347, "ax":4.12395, "ay":4.91154, "alpha":-1.28169, "fx":[64.24052,66.24951,76.46428,73.63445], "fy":[88.44646,86.86426,78.05165,80.81292]}, + {"t":1.89456, "x":2.49098, "y":4.79315, "heading":2.73469, "vx":0.25914, "vy":-2.81059, "omega":1.55062, "ax":3.31924, "ay":5.47496, "alpha":-1.82091, "fx":[48.11596,48.97017,65.98894,62.76205], "fy":[98.19453,97.66419,87.09453,89.55684]}, + {"t":1.9202, "x":2.49871, "y":4.7229, "heading":2.77444, "vx":0.34423, "vy":-2.67023, "omega":1.50394, "ax":2.52073, "ay":5.87264, "alpha":-2.28531, "fx":[32.93006,31.37636,55.02542,52.17555], "fy":[104.31688,104.67884,94.42248,96.14981]}, + {"t":1.94583, "x":2.50837, "y":4.65637, "heading":2.81299, "vx":0.40885, "vy":-2.51968, "omega":1.44535, "ax":1.77939, "ay":6.12649, "alpha":-2.6619, "fx":[19.48881,15.02796,44.21596,42.33461], "fy":[107.68392,108.27929,99.96734,100.90881]}, + {"t":1.97147, "x":2.51943, "y":4.59379, "heading":2.85005, "vx":0.45447, "vy":-2.36262, "omega":1.37711, "ax":1.12093, "ay":6.27083, "alpha":-2.95303, "fx":[7.99376,0.76013,34.05277,33.46031], "fy":[109.18062,109.35579,103.89955,104.22412]}, + {"t":1.9971, "x":2.53145, "y":4.53528, "heading":2.88535, "vx":0.4832, "vy":-2.20187, "omega":1.3014, "ax":0.55117, "ay":6.33887, "alpha":-3.17135, "fx":[-1.68353,-11.24168,24.82371,25.60278], "fy":[109.49552,108.82021,106.51369,106.45977]}, + {"t":2.02274, "x":2.54402, "y":4.48092, "heading":2.91871, "vx":0.49733, "vy":-2.03936, "omega":1.2201, "ax":0.06458, "ay":6.35685, "alpha":-3.33275, "fx":[-9.79463,-21.16054,16.63603,18.71343], "fy":[109.10099,107.37218,108.12658,107.91335]}, + {"t":2.04838, "x":2.55679, "y":4.43073, "heading":2.94999, "vx":0.49899, "vy":-1.8764, "omega":1.13467, "ax":-0.34907, "ay":6.34349, "alpha":-3.45177, "fx":[-16.60578,-29.31527,9.47309,12.69796], "fy":[108.30137,105.47368,109.01778,108.8113]}, + {"t":2.07401, "x":2.56947, "y":4.38471, "heading":2.97908, "vx":0.49004, "vy":-1.71378, "omega":1.04618, "ax":-0.70092, "ay":6.31136, "alpha":-3.53993, "fx":[-22.35412,-36.03408,3.24962,7.44856], "fy":[107.28667,103.40366,109.40827,109.31924]}, + {"t":2.09965, "x":2.5818, "y":4.34285, "heading":3.0059, "vx":0.47207, "vy":-1.55198, "omega":0.95543, "ax":-1.00131, "ay":6.26864, "alpha":-3.60569, "fx":[-27.23624,-41.60413,-2.14847,2.86054], "fy":[106.17369,101.32014,109.46125,109.55581]}, + {"t":2.12528, "x":2.59357, "y":4.30512, "heading":3.03039, "vx":0.4464, "vy":-1.39127, "omega":0.86299, "ax":-1.25913, "ay":6.22053, "alpha":-3.65508, "fx":[-31.40987,-46.25967,-6.8401,-1.16034], "fy":[105.03353,99.30721,109.29212,109.60518]}, + {"t":2.15092, "x":2.60461, "y":4.2715, "heading":3.05252, "vx":0.41412, "vy":-1.2318, "omega":0.76929, "ax":-1.48177, "ay":6.17032, "alpha":-3.69231, "fx":[-34.99991,-50.18585,-10.9367,-4.69555], "fy":[103.9091,97.40564,108.98004,109.52687]}, + {"t":2.17656, "x":2.61473, "y":4.24195, "heading":3.07224, "vx":0.37614, "vy":-1.07362, "omega":0.67463, "ax":-1.67527, "ay":6.12001, "alpha":-3.72034, "fx":[-38.10495,-53.52715,-14.53708,-7.81411], "fy":[102.82594,95.63159,108.57809,109.36307]}, + {"t":2.20219, "x":2.62383, "y":4.21644, "heading":3.08953, "vx":0.33319, "vy":-0.91673, "omega":0.57926, "ax":-1.84452, "ay":6.07082, "alpha":-3.74125, "fx":[-40.80291,-56.39601,-17.72623,-10.57384], "fy":[101.79885,93.98768,108.12111,109.14374]}, + {"t":2.22783, "x":2.63176, "y":4.19493, "heading":3.10438, "vx":0.2859, "vy":-0.7611, "omega":0.48335, "ax":-1.99349, "ay":6.02343, "alpha":-3.75653, "fx":[-43.15573,-58.88007,-20.57603,-13.02296], "fy":[100.83597,92.46939,107.63143,108.89028]}, + {"t":2.25346, "x":2.63844, "y":4.1774, "heading":3.11677, "vx":0.2348, "vy":-0.60668, "omega":0.38704, "ax":-2.12539, "ay":5.97822, "alpha":-3.76722, "fx":[-45.21292,-61.04804,-23.14678,-15.2017], "fy":[99.94137,91.06878,107.12284,108.618]}, + {"t":2.2791, "x":2.64376, "y":4.16381, "heading":3.1267, "vx":0.18031, "vy":-0.45342, "omega":0.29047, "ax":-2.24285, "ay":5.93535, "alpha":-3.77411, "fx":[-47.01437,-62.95407,-25.4889,-17.14367], "fy":[99.11657,89.77654,106.60337,108.33791]}, + {"t":2.30474, "x":2.64764, "y":4.15414, "heading":3.13414, "vx":0.12281, "vy":-0.30126, "omega":0.19371, "ax":-2.348, "ay":5.89486, "alpha":-3.77775, "fx":[-48.59244,-64.64112,-27.64456,-18.87714], "fy":[98.36155,88.58321,106.07717,108.05791]}, + {"t":2.33037, "x":2.65002, "y":4.14835, "heading":3.13911, "vx":0.06262, "vy":-0.15014, "omega":0.09687, "ax":-2.44261, "ay":5.85672, "alpha":-3.77857, "fx":[-49.97358,-66.14344,-29.64915,-20.42596], "fy":[97.67535,87.4798,105.54578,107.78365]}, + {"t":2.35601, "x":2.65082, "y":4.14642, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/v2_redundancy/choreo/B_LEFT_PATH2.traj b/src/main/deploy/v2_redundancy/choreo/B_LEFT_PATH2.traj new file mode 100644 index 00000000..c52280b7 --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/B_LEFT_PATH2.traj @@ -0,0 +1,159 @@ +{ + "name":"B_LEFT_PATH2", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.171550750732422, "y":4.146424770355225, "heading":3.141592653589793, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.7844728231430054, "y":6.438039302825928, "heading":0.0, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":0.9014043211936952, "y":7.158551216125488, "heading":2.179485408307156, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.4965330362319946, "y":4.913652420043945, "heading":0.0, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":2.9235854148864746, "y":3.9604506492614746, "heading":3.141592653589793, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":true}, + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.171550750732422 m", "val":3.171550750732422}, "y":{"exp":"4.146424770355225 m", "val":4.146424770355225}, "heading":{"exp":"180 deg", "val":3.141592653589793}, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.7844728231430054 m", "val":1.7844728231430054}, "y":{"exp":"6.438039302825928 m", "val":6.438039302825928}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"0.9014043211936951 m", "val":0.9014043211936952}, "y":{"exp":"7.158551216125488 m", "val":7.158551216125488}, "heading":{"exp":"2.1794854083071558 rad", "val":2.179485408307156}, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.4965330362319946 m", "val":1.4965330362319946}, "y":{"exp":"4.913652420043945 m", "val":4.913652420043945}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"2.9235854148864746 m", "val":2.9235854148864746}, "y":{"exp":"3.9604506492614746 m", "val":3.9604506492614746}, "heading":{"exp":"180 deg", "val":3.141592653589793}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":true}, + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.99188,1.59067,2.50142,3.25943], + "samples":[ + {"t":0.0, "x":3.17155, "y":4.14642, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-2.98514, "ay":5.61149, "alpha":-3.59953, "fx":[-57.08165,-73.47949,-42.54754,-29.99696], "fy":[93.72379,81.45843,101.0745,105.54261]}, + {"t":0.03006, "x":3.1702, "y":4.14896, "heading":3.14159, "vx":-0.08972, "vy":0.16867, "omega":-0.10819, "ax":-2.9869, "ay":5.61371, "alpha":-3.53646, "fx":[-57.00186,-73.11056,-42.75603,-30.35708], "fy":[93.76417,81.77848,100.97629,105.43164]}, + {"t":0.06011, "x":3.16616, "y":4.15656, "heading":3.13834, "vx":-0.1795, "vy":0.3374, "omega":-0.21449, "ax":-2.98886, "ay":5.61619, "alpha":-3.46459, "fx":[-56.85552,-72.7007,-43.07679,-30.72527], "fy":[93.84386,82.13081,100.82856,105.31595]}, + {"t":0.09017, "x":3.15941, "y":4.16924, "heading":3.13189, "vx":-0.26934, "vy":0.5062, "omega":-0.31862, "ax":-2.991, "ay":5.61894, "alpha":-3.38295, "fx":[-56.64467,-72.24211,-43.50381,-31.11335], "fy":[93.96103,82.52103,100.63246,105.19175]}, + {"t":0.12023, "x":3.14996, "y":4.187, "heading":3.12232, "vx":-0.35924, "vy":0.67509, "omega":-0.4203, "ax":-2.99333, "ay":5.62198, "alpha":-3.29031, "fx":[-56.3717,-71.72448,-44.03017,-31.53629], "fy":[94.11344,82.95646,100.38919,105.05406]}, + {"t":0.15029, "x":3.13781, "y":4.20983, "heading":3.10968, "vx":-0.44921, "vy":0.84407, "omega":-0.5192, "ax":-2.99585, "ay":5.62534, "alpha":-3.18505, "fx":[-56.03939,-71.1344,-44.64763,-32.01303], "fy":[94.29842,83.44639,100.10029,104.89635]}, + {"t":0.18034, "x":3.12296, "y":4.23774, "heading":3.09408, "vx":-0.53926, "vy":1.01315, "omega":-0.61493, "ax":-2.99857, "ay":5.62904, "alpha":-3.06498, "fx":[-55.65117,-70.4545,-45.34612,-32.56761], "fy":[94.51272,84.0025,99.76795,104.70994]}, + {"t":0.2104, "x":3.1054, "y":4.27073, "heading":3.0756, "vx":-0.62938, "vy":1.18235, "omega":-0.70706, "ax":-3.00148, "ay":5.63311, "alpha":-2.92708, "fx":[-55.21129,-69.66205,-46.11302,-33.23079], "fy":[94.75244,84.63947,99.39551,104.48316]}, + {"t":0.24046, "x":3.08512, "y":4.30882, "heading":3.05434, "vx":-0.7196, "vy":1.35166, "omega":-0.79504, "ax":-3.00456, "ay":5.63761, "alpha":-2.76716, "fx":[-54.72529,-68.72688,-46.93242,-34.04253], "fy":[95.01273,85.3759,98.98802,104.19997]}, + {"t":0.27051, "x":3.06214, "y":4.35199, "heading":3.03045, "vx":-0.80991, "vy":1.52111, "omega":-0.87821, "ax":-3.00781, "ay":5.64257, "alpha":-2.57917, "fx":[-54.20051,-67.60794,-47.78405,-35.05559], "fy":[95.28748,86.2358,98.55295,103.83772]}, + {"t":0.30057, "x":3.03643, "y":4.40026, "heading":3.00405, "vx":-0.90032, "vy":1.69071, "omega":-0.95573, "ax":-3.01119, "ay":5.64801, "alpha":-2.35432, "fx":[-53.64706,-66.24749,-48.64195,-36.34127], "fy":[95.56871,87.25088,98.10115,103.36337]}, + {"t":0.33063, "x":3.00801, "y":4.45363, "heading":2.97532, "vx":-0.99082, "vy":1.86047, "omega":-1.0265, "ax":-3.01462, "ay":5.6539, "alpha":-2.07939, "fx":[-53.07933,-64.56118,-49.47261,-37.99849], "fy":[95.84556,88.46421,97.64808,102.72679]}, + {"t":0.36069, "x":2.97687, "y":4.5121, "heading":2.94447, "vx":-1.08143, "vy":2.03041, "omega":-1.089, "ax":-3.01798, "ay":5.66004, "alpha":-1.73409, "fx":[-52.5189,-62.41977,-50.23223,-40.1689], "fy":[96.10228,89.9362,97.21549,101.84839]}, + {"t":0.39074, "x":2.943, "y":4.57569, "heading":2.91174, "vx":-1.17215, "vy":2.20054, "omega":-1.14112, "ax":-3.02091, "ay":5.66583, "alpha":-1.28595, "fx":[-52.00004,-59.61385,-50.86241,-43.06279], "fy":[96.31427,91.7541,96.83373,100.59473]}, + {"t":0.4208, "x":2.90641, "y":4.64439, "heading":2.87744, "vx":-1.26294, "vy":2.37084, "omega":-1.17977, "ax":-3.02254, "ay":5.66967, "alpha":-0.68081, "fx":[-51.58213,-55.78014,-51.28295,-47.00515], "fy":[96.43891,94.04683,96.54513,98.72724]}, + {"t":0.45086, "x":2.86708, "y":4.71821, "heading":2.84198, "vx":-1.35379, "vy":2.54125, "omega":-1.20023, "ax":-3.02052, "ay":5.66717, "alpha":0.1773, "fx":[-51.38099,-50.23407,-51.379,-52.51861], "fy":[96.39139,97.00245,96.40914,95.78489]}, + {"t":0.48091, "x":2.82503, "y":4.79715, "heading":2.8059, "vx":-1.44458, "vy":2.71159, "omega":-1.19491, "ax":-3.00793, "ay":5.64561, "alpha":1.47097, "fx":[-51.66754,-41.54786,-50.97666,-60.46399], "fy":[95.96526,100.85373,96.51041,90.79167]}, + {"t":0.51097, "x":2.78025, "y":4.8812, "heading":2.76999, "vx":-1.53499, "vy":2.88128, "omega":-1.15069, "ax":-2.96396, "ay":5.56258, "alpha":3.57493, "fx":[-53.29944,-26.39281,-49.79443,-72.17765], "fy":[94.46051,105.56359,96.97099,81.47653]}, + {"t":0.54103, "x":2.73277, "y":4.97032, "heading":2.7354, "vx":-1.62408, "vy":3.04847, "omega":-1.04324, "ax":-2.85544, "ay":5.22785, "alpha":7.30869, "fx":[-61.37561,3.14255,-47.35378,-88.69429], "fy":[86.94175,108.31657,97.95738,62.48124]}, + {"t":0.57108, "x":2.68267, "y":5.06431, "heading":2.70404, "vx":-1.70991, "vy":3.20561, "omega":-0.82356, "ax":-2.93526, "ay":4.225, "alpha":12.29747, "fx":[-87.43373,29.83058,-44.33927,-97.7695], "fy":[39.7038,103.35388,98.85425,45.55251]}, + {"t":0.60114, "x":2.62994, "y":5.16257, "heading":2.67929, "vx":-1.79813, "vy":3.3326, "omega":-0.45394, "ax":-2.70973, "ay":4.17, "alpha":12.30676, "fx":[-76.88178,29.33749,-42.16935,-94.65307], "fy":[37.7942,100.86886,97.98906,47.06959]}, + {"t":0.6312, "x":2.57467, "y":5.26462, "heading":2.66565, "vx":-1.87958, "vy":3.45794, "omega":-0.08403, "ax":-0.08616, "ay":1.13743, "alpha":2.64549, "fx":[1.6224,7.9991,-4.39432,-11.08926], "fy":[10.2734,22.37221,28.18654,16.5575]}, + {"t":0.66126, "x":2.51814, "y":5.36907, "heading":2.66312, "vx":-1.88217, "vy":3.49213, "omega":-0.00452, "ax":0.03027, "ay":0.01888, "alpha":0.00522, "fx":[0.52068,0.53316,0.5091,0.49663], "fy":[0.30291,0.32697,0.33944,0.31539]}, + {"t":0.69131, "x":2.46158, "y":5.47404, "heading":2.66298, "vx":-1.88126, "vy":3.49269, "omega":-0.00436, "ax":-0.33184, "ay":-0.17934, "alpha":-0.00001, "fx":[-5.64451,-5.64454,-5.64448,-5.64445], "fy":[-3.05052,-3.05058,-3.05061,-3.05055]}, + {"t":0.72137, "x":2.40489, "y":5.57894, "heading":2.66285, "vx":-1.89123, "vy":3.4873, "omega":-0.00436, "ax":-0.9593, "ay":-0.52546, "alpha":-0.00015, "fx":[-16.31754,-16.31788,-16.31718,-16.31684], "fy":[-8.93739,-8.9381,-8.93848,-8.93778]}, + {"t":0.75143, "x":2.34761, "y":5.68352, "heading":2.66272, "vx":-1.92007, "vy":3.47151, "omega":-0.00436, "ax":-2.12622, "ay":-1.20212, "alpha":-0.00056, "fx":[-36.16716,-36.16808,-36.16555,-36.16463], "fy":[-20.44558,-20.44817,-20.44991,-20.44732]}, + {"t":0.78148, "x":2.28894, "y":5.78732, "heading":2.66259, "vx":-1.98397, "vy":3.43538, "omega":-0.00438, "ax":-3.49453, "ay":-2.09158, "alpha":-0.00143, "fx":[-59.44406,-59.44453,-59.43796,-59.43749], "fy":[-35.57068,-35.57732,-35.5837,-35.57706]}, + {"t":0.81154, "x":2.22773, "y":5.88964, "heading":2.66246, "vx":-2.08901, "vy":3.37251, "omega":-0.00442, "ax":-4.33537, "ay":-2.8061, "alpha":-0.00274, "fx":[-73.75127,-73.74874,-73.73558,-73.73811], "fy":[-47.71702,-47.72914,-47.7448,-47.73268]}, + {"t":0.8416, "x":2.16298, "y":5.98974, "heading":2.66233, "vx":-2.21932, "vy":3.28817, "omega":-0.00451, "ax":-4.66824, "ay":-3.30409, "alpha":-0.00633, "fx":[-79.42694,-79.41657,-79.38379,-79.39416], "fy":[-56.16847,-56.19405,-56.23473,-56.20917]}, + {"t":0.87166, "x":2.09416, "y":6.08708, "heading":2.66219, "vx":-2.35963, "vy":3.18885, "omega":-0.0047, "ax":-4.71603, "ay":-3.70867, "alpha":-0.1145, "fx":[-80.65574,-80.43101,-79.78185,-80.00483], "fy":[-62.49285,-62.90163,-63.6699,-63.26908]}, + {"t":0.90171, "x":2.02111, "y":6.18125, "heading":2.66205, "vx":-2.50138, "vy":3.07738, "omega":-0.00814, "ax":-3.90487, "ay":-4.68621, "alpha":-2.84029, "fx":[-79.57417,-74.29393,-55.27066,-56.54383], "fy":[-67.36567,-74.81335,-89.5601,-87.10547]}, + {"t":0.93177, "x":1.94416, "y":6.27163, "heading":2.66181, "vx":-2.61875, "vy":2.93653, "omega":-0.09351, "ax":-1.47832, "ay":-5.59564, "alpha":-8.52097, "fx":[-66.5734,-58.54014,-6.37704,30.90711], "fy":[-81.19805,-90.2517,-107.57367,-101.6974]}, + {"t":0.96183, "x":1.86478, "y":6.35737, "heading":2.659, "vx":-2.66318, "vy":2.76834, "omega":-0.34962, "ax":-0.57627, "ay":-5.60997, "alpha":-10.00491, "fx":[-55.91851,-52.75274,8.95459,60.50824], "fy":[-89.5528,-94.67611,-108.23952,-89.2273]}, + {"t":0.99188, "x":1.78447, "y":6.43804, "heading":2.64849, "vx":-2.68051, "vy":2.59972, "omega":-0.65034, "ax":0.65999, "ay":-5.76388, "alpha":-8.47293, "fx":[-10.18212,-39.339,21.56126,72.86499], "fy":[-104.70691,-100.98153,-106.54642,-79.9326]}, + {"t":1.01683, "x":1.7178, "y":6.50111, "heading":2.63226, "vx":-2.66404, "vy":2.45592, "omega":-0.86174, "ax":2.319, "ay":-5.68181, "alpha":-5.63997, "fx":[47.32077,-1.10229,37.65358,73.90972], "fy":[-96.49738,-108.46014,-102.10399,-79.52246]}, + {"t":1.04178, "x":1.65206, "y":6.56061, "heading":2.61076, "vx":-2.60618, "vy":2.31416, "omega":-1.00245, "ax":3.21065, "ay":-5.42105, "alpha":-3.55157, "fx":[62.90687,31.34024,50.33077,73.87095], "fy":[-88.2681,-104.06098,-96.61181,-79.90086]}, + {"t":1.06673, "x":1.58803, "y":6.61666, "heading":2.58575, "vx":-2.52608, "vy":2.17891, "omega":-1.09106, "ax":3.75568, "ay":-5.1533, "alpha":-1.95835, "fx":[69.04764,52.55734,60.14797,73.77933], "fy":[-84.09627,-95.37008,-90.94396,-80.21465]}, + {"t":1.09168, "x":1.52618, "y":6.66942, "heading":2.55853, "vx":-2.43238, "vy":2.05034, "omega":-1.13992, "ax":4.10393, "ay":-4.92165, "alpha":-0.82613, "fx":[72.10419,65.58642,67.77707,73.75871], "fy":[-81.80455,-87.14162,-85.52008,-80.39696]}, + {"t":1.11663, "x":1.46677, "y":6.71904, "heading":2.53009, "vx":-2.32999, "vy":1.92754, "omega":-1.16053, "ax":4.33807, "ay":-4.73204, "alpha":-0.00763, "fx":[73.81129,73.75468,73.76753,73.8241], "fy":[-80.47012,-80.52215,-80.51101,-80.45901]}, + {"t":1.14158, "x":1.40999, "y":6.76566, "heading":2.50114, "vx":-2.22175, "vy":1.80948, "omega":-1.16072, "ax":4.50348, "ay":-4.57807, "alpha":0.60822, "fx":[74.81702,79.09634,78.5292,73.96888], "fy":[-79.67675,-75.42359,-75.96593,-80.4206]}, + {"t":1.16653, "x":1.35596, "y":6.80938, "heading":2.47218, "vx":-2.1094, "vy":1.69526, "omega":-1.14555, "ax":4.62526, "ay":-4.45209, "alpha":1.0893, "fx":[75.41684,82.7383,82.36028,74.18218], "fy":[-79.21254,-71.5244,-71.87831,-80.29952]}, + {"t":1.19148, "x":1.30477, "y":6.85029, "heading":2.4436, "vx":-1.994, "vy":1.58419, "omega":-1.11837, "ax":4.71799, "ay":-4.34775, "alpha":1.47638, "fx":[75.76492,85.31128,85.47748,74.45286], "fy":[-78.95851,-68.529,-68.21817,-80.11051]}, + {"t":1.21643, "x":1.25649, "y":6.88846, "heading":2.41569, "vx":-1.87629, "vy":1.47571, "omega":-1.08153, "ax":4.79053, "ay":-4.2603, "alpha":1.79472, "fx":[75.9498,87.18256,88.03973,74.77037], "fy":[-78.84273,-66.20981,-64.9474,-79.86594]}, + {"t":1.24138, "x":1.21117, "y":6.92395, "heading":2.38871, "vx":-1.75677, "vy":1.36942, "omega":-1.03676, "ax":4.84858, "ay":-4.18616, "alpha":2.0608, "fx":[76.02619,88.57587,90.16503,75.12485], "fy":[-78.81912,-64.3991,-62.02667,-79.57652]}, + {"t":1.26633, "x":1.16885, "y":6.95682, "heading":2.36284, "vx":-1.6358, "vy":1.26498, "omega":-0.98534, "ax":4.89592, "ay":-4.12266, "alpha":2.28589, "fx":[76.02977,89.63352,91.94232,75.50707], "fy":[-78.85686,-62.97388,-59.4185,-79.25182]}, + {"t":1.29128, "x":1.12956, "y":6.98709, "heading":2.33826, "vx":-1.51365, "vy":1.16212, "omega":-0.92831, "ax":4.93516, "ay":-4.06777, "alpha":2.47809, "fx":[75.98488,90.44967,93.43954,75.90831], "fy":[-78.9346,-61.84312,-57.08836,-78.90067]}, + {"t":1.31623, "x":1.09333, "y":7.01482, "heading":2.3151, "vx":-1.39052, "vy":1.06063, "omega":-0.86648, "ax":4.96815, "ay":-4.01994, "alpha":2.64348, "fx":[75.90866,91.0888,94.70931,76.32039], "fy":[-79.03721,-60.93854,-55.00501,-78.53135]}, + {"t":1.34117, "x":1.06018, "y":7.04003, "heading":2.29348, "vx":-1.26657, "vy":0.96034, "omega":-0.80053, "ax":4.99624, "ay":-3.97793, "alpha":2.78676, "fx":[75.81351,91.59649,95.79286,76.73563], "fy":[-79.15369,-60.20816,-53.14043,-78.15171]}, + {"t":1.36612, "x":1.03014, "y":7.06276, "heading":2.27351, "vx":-1.14191, "vy":0.86109, "omega":-0.731, "ax":5.02043, "ay":-3.94079, "alpha":2.91166, "fx":[75.70861,92.00583,96.72286,77.14686], "fy":[-79.27598,-59.6118,-51.46958,-77.76923]}, + {"t":1.39107, "x":1.00321, "y":7.08301, "heading":2.25527, "vx":-1.01666, "vy":0.76277, "omega":-0.65836, "ax":5.04146, "ay":-3.90773, "alpha":3.02125, "fx":[75.60084,92.34146,97.52544,77.54744], "fy":[-79.39804,-59.11795,-49.97021,-77.39105]}, + {"t":1.41602, "x":0.97942, "y":7.10083, "heading":2.23884, "vx":-0.89088, "vy":0.66528, "omega":-0.58298, "ax":5.05991, "ay":-3.87813, "alpha":3.11802, "fx":[75.49547,92.62208,98.22165,77.93124], "fy":[-79.51535,-58.70165,-48.62254,-77.02395]}, + {"t":1.44097, "x":0.95876, "y":7.11622, "heading":2.2243, "vx":-0.76464, "vy":0.56852, "omega":-0.50519, "ax":5.07622, "ay":-3.85149, "alpha":3.20407, "fx":[75.39654,92.86218,98.82861,78.29268], "fy":[-79.62444,-58.3428,-47.40908,-76.67432]}, + {"t":1.46592, "x":0.94127, "y":7.1292, "heading":2.2117, "vx":-0.63799, "vy":0.47243, "omega":-0.42525, "ax":5.09073, "ay":-3.82738, "alpha":3.28115, "fx":[75.30725,93.07317,99.36029,78.62671], "fy":[-79.72266,-58.02511,-46.31435,-76.34817]}, + {"t":1.49087, "x":0.92693, "y":7.1398, "heading":2.20109, "vx":-0.51098, "vy":0.37694, "omega":-0.34339, "ax":5.10372, "ay":-3.80546, "alpha":3.35074, "fx":[75.23013,93.26417,99.82817,78.92877], "fy":[-79.80792,-57.73523,-45.32473,-76.05107]}, + {"t":1.51582, "x":0.91577, "y":7.14802, "heading":2.19252, "vx":-0.38364, "vy":0.282, "omega":-0.25979, "ax":5.1154, "ay":-3.78544, "alpha":3.41409, "fx":[75.16726,93.44253,100.24168,79.19482], "fy":[-79.87853,-57.46208,-44.4283,-75.78814]}, + {"t":1.54077, "x":0.90779, "y":7.15388, "heading":2.18604, "vx":-0.25602, "vy":0.18755, "omega":-0.17461, "ax":5.12596, "ay":-3.76709, "alpha":3.47228, "fx":[75.12035,93.61425,100.60863,79.42126], "fy":[-79.9331,-57.19644,-43.61466,-75.56404]}, + {"t":1.56572, "x":0.903, "y":7.15738, "heading":2.18168, "vx":-0.12813, "vy":0.09356, "omega":-0.08798, "ax":5.13553, "ay":-3.75019, "alpha":3.52621, "fx":[75.09089,93.78429,100.93546,79.60495], "fy":[-79.97041,-56.93051,-42.87481,-75.38289]}, + {"t":1.59067, "x":0.9014, "y":7.15855, "heading":2.17949, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.17889, "ay":-6.37469, "alpha":3.15871, "fx":[-0.90927,24.55382,9.0288,-20.5021], "fy":[-109.72956,-106.93301,-109.29357,-107.77041]}, + {"t":1.62005, "x":0.90148, "y":7.1558, "heading":2.17949, "vx":0.00526, "vy":-0.18728, "omega":0.0928, "ax":0.2068, "ay":-6.37612, "alpha":3.09928, "fx":[-0.4454,24.59677,9.4828,-19.56395], "fy":[-109.72558,-106.9156,-109.24647,-107.9365]}, + {"t":1.64943, "x":0.90173, "y":7.14755, "heading":2.18221, "vx":0.01133, "vy":-0.37461, "omega":0.18385, "ax":0.23773, "ay":-6.37755, "alpha":3.03244, "fx":[0.12289,24.66635,9.90649,-18.52067], "fy":[-109.71882,-106.89115,-109.1994,-108.11151]}, + {"t":1.67881, "x":0.90216, "y":7.13379, "heading":2.18761, "vx":0.01832, "vy":-0.56197, "omega":0.27294, "ax":0.27221, "ay":-6.3789, "alpha":2.95719, "fx":[0.80105,24.76124,10.31459,-17.3561], "fy":[-109.70747,-106.85977,-109.15119,-108.29482]}, + {"t":1.70818, "x":0.90282, "y":7.11452, "heading":2.19563, "vx":0.02631, "vy":-0.74938, "omega":0.35982, "ax":0.31086, "ay":-6.38012, "alpha":2.87232, "fx":[1.5961,24.87965,10.72437,-16.04978], "fy":[-109.68923,-106.82162,-109.1002,-108.48533]}, + {"t":1.73756, "x":0.90372, "y":7.08976, "heading":2.2062, "vx":0.03545, "vy":-0.93682, "omega":0.44421, "ax":0.35446, "ay":-6.38111, "alpha":2.77626, "fx":[2.51718,25.01942,11.15631,-14.57589], "fy":[-109.66112,-106.77692,-109.04414,-108.68117]}, + {"t":1.76694, "x":0.90492, "y":7.05948, "heading":2.21925, "vx":0.04586, "vy":-1.1243, "omega":0.52577, "ax":0.404, "ay":-6.38171, "alpha":2.66699, "fx":[3.57634,25.17804,11.63507,-12.90157], "fy":[-109.61929,-106.72589,-108.97994,-108.87914]}, + {"t":1.79632, "x":0.90644, "y":7.02369, "heading":2.2347, "vx":0.05773, "vy":-1.31178, "omega":0.60413, "ax":0.46074, "ay":-6.38172, "alpha":2.54188, "fx":[4.78968,25.35273,12.19062,-10.98469], "fy":[-109.55866,-106.66876,-108.90335,-109.07393]}, + {"t":1.8257, "x":0.90833, "y":6.9824, "heading":2.25245, "vx":0.07126, "vy":-1.49927, "omega":0.67881, "ax":0.5263, "ay":-6.38082, "alpha":2.39742, "fx":[6.17911,25.54056,12.85985,-8.77058], "fy":[-109.47235,-106.60571,-108.80854,-109.25676]}, + {"t":1.85508, "x":0.91066, "y":6.9356, "heading":2.27239, "vx":0.08673, "vy":-1.68674, "omega":0.74924, "ax":0.60282, "ay":-6.37853, "alpha":2.22887, "fx":[7.77501,25.73861,13.68865,-6.1872], "fy":[-109.35078,-106.53678,-108.68722,-109.41321]}, + {"t":1.88446, "x":0.91346, "y":6.88329, "heading":2.2944, "vx":0.10444, "vy":-1.87413, "omega":0.81472, "ax":0.69316, "ay":-6.37413, "alpha":2.02973, "fx":[9.6205,25.94417,14.73474,-3.13789], "fy":[-109.18006,-106.46177,-108.52736,-109.51931]}, + {"t":1.91384, "x":0.91683, "y":6.82548, "heading":2.31834, "vx":0.1248, "vy":-2.0614, "omega":0.87436, "ax":0.80123, "ay":-6.36644, "alpha":1.79091, "fx":[11.77857,26.15523,16.07153,0.50954], "fy":[-108.93916,-106.38008,-108.31102,-109.53479]}, + {"t":1.94322, "x":0.92084, "y":6.76217, "heading":2.34403, "vx":0.14834, "vy":-2.24844, "omega":0.92697, "ax":0.93253, "ay":-6.35352, "alpha":1.49942, "fx":[14.34428,26.371,17.79351,4.93954], "fy":[-108.59449,-106.29034,-108.01079,-109.39033]}, + {"t":1.9726, "x":0.9256, "y":6.69337, "heading":2.37126, "vx":0.17574, "vy":-2.4351, "omega":0.97102, "ax":1.09494, "ay":-6.33205, "alpha":1.13629, "fx":[17.4669,26.59312,20.02378,10.41435], "fy":[-108.08897,-106.1899,-107.5836,-108.96326]}, + {"t":2.00198, "x":0.93124, "y":6.6191, "heading":2.39979, "vx":0.20791, "vy":-2.62113, "omega":1.00441, "ax":1.30008, "ay":-6.29613, "alpha":0.67304, "fx":[21.39253,26.82766,22.92447,17.31138], "fy":[-107.31795,-106.07386,-106.96021,-108.02914]}, + {"t":2.03135, "x":0.93791, "y":6.53937, "heading":2.4293, "vx":0.2461, "vy":-2.80611, "omega":1.02418, "ax":1.56561, "ay":-6.23458, "alpha":0.06576, "fx":[26.55141,27.08932,26.7107,26.17094], "fy":[-106.07105,-105.93305,-106.02642,-106.16286]}, + {"t":2.06073, "x":0.94581, "y":6.45424, "heading":2.45939, "vx":0.2921, "vy":-2.98927, "omega":1.02611, "ax":1.91883, "ay":-6.12516, "alpha":-0.7552, "fx":[33.75064,27.41102,31.66767,37.72575], "fy":[-103.87259,-105.74969,-104.58963,-102.53681]}, + {"t":2.09011, "x":0.95522, "y":6.36378, "heading":2.48953, "vx":0.34847, "vy":-3.16922, "omega":1.00392, "ax":2.40203, "ay":-5.92046, "alpha":-1.90465, "fx":[44.62124,27.87033,38.16576,52.77391], "fy":[-99.47092,-105.48608,-102.31862,-95.54567]}, + {"t":2.11949, "x":0.9665, "y":6.26811, "heading":2.51903, "vx":0.41904, "vy":-3.34316, "omega":0.94797, "ax":3.07603, "ay":-5.51098, "alpha":-3.60194, "fx":[62.51946,28.68368,46.65557,71.43103], "fy":[-88.90274,-105.04711,-98.63737,-82.37388]}, + {"t":2.14887, "x":0.98014, "y":6.16751, "heading":2.54688, "vx":0.50941, "vy":-3.50507, "omega":0.84214, "ax":3.97335, "ay":-4.62908, "alpha":-6.44487, "fx":[90.97075,30.77207,57.60689,90.99249], "fy":[-58.46736,-104.07492,-92.54019,-59.87506]}, + {"t":2.17825, "x":0.99682, "y":6.06254, "heading":2.57162, "vx":0.62615, "vy":-3.64107, "omega":0.6528, "ax":4.84009, "ay":-3.2041, "alpha":-9.32655, "fx":[107.75486,45.99319,72.04929,103.51713], "fy":[-5.11693,-97.62953,-81.60097,-33.65591]}, + {"t":2.20763, "x":1.0173, "y":5.95419, "heading":2.5908, "vx":0.76834, "vy":-3.7352, "omega":0.37879, "ax":5.77186, "ay":-1.69755, "alpha":-7.12479, "fx":[106.30767,87.7812,90.66204,107.95956], "fy":[19.56951,-62.04562,-59.87378,-13.14963]}, + {"t":2.23701, "x":1.04237, "y":5.84372, "heading":2.60193, "vx":0.93792, "vy":-3.78507, "omega":0.16947, "ax":6.26529, "ay":0.08848, "alpha":-3.8098, "fx":[104.223,107.6697,105.92718,108.46309], "fy":[29.5701,-6.85093,-23.46945,6.77021]}, + {"t":2.26639, "x":1.07263, "y":5.73255, "heading":2.60691, "vx":1.12198, "vy":-3.78248, "omega":0.05755, "ax":6.20204, "ay":1.44484, "alpha":-1.33751, "fx":[103.08238,105.63576,107.49176,105.76992], "fy":[33.99225,24.3698,15.10216,24.8411]}, + {"t":2.29577, "x":1.10826, "y":5.62205, "heading":2.6086, "vx":1.3042, "vy":-3.74003, "omega":0.01825, "ax":6.01375, "ay":2.16302, "alpha":-0.25313, "fx":[101.66808,102.22234,102.90421,102.37398], "fy":[38.51098,36.9516,35.06338,36.64348]}, + {"t":2.32515, "x":1.14918, "y":5.51311, "heading":2.60913, "vx":1.48087, "vy":-3.67648, "omega":0.01081, "ax":5.86701, "ay":2.55771, "alpha":0.05958, "fx":[99.96643,99.82729,99.6254,99.76558], "fy":[43.11281,43.44527,43.89819,43.56735]}, + {"t":2.35453, "x":1.19522, "y":5.4062, "heading":2.60945, "vx":1.65324, "vy":-3.60134, "omega":0.01256, "ax":5.70443, "ay":2.9173, "alpha":0.30411, "fx":[98.00704,97.27028,96.04539,96.80029], "fy":[47.68269,49.21354,51.53607,50.05714]}, + {"t":2.3839, "x":1.24625, "y":5.30165, "heading":2.60982, "vx":1.82083, "vy":-3.51563, "omega":0.0215, "ax":5.48866, "ay":3.3123, "alpha":0.68599, "fx":[95.81727,94.13664,90.8876,92.6003], "fy":[52.15489,55.21203,60.37249,57.62565]}, + {"t":2.41328, "x":1.30211, "y":5.1998, "heading":2.61045, "vx":1.98208, "vy":-3.41832, "omega":0.04165, "ax":5.22841, "ay":3.70855, "alpha":1.13325, "fx":[93.39712,90.65581,84.52198,87.15981], "fy":[56.53488,60.94296,69.1594,65.6885]}, + {"t":2.44266, "x":1.3626, "y":5.10097, "heading":2.61168, "vx":2.13569, "vy":-3.30936, "omega":0.07495, "ax":4.95666, "ay":4.06002, "alpha":1.52159, "fx":[90.75953,87.1934,78.12315,81.16925], "fy":[60.80444,65.93842,76.43346,73.06273]}, + {"t":2.47204, "x":1.42748, "y":5.00549, "heading":2.61388, "vx":2.28131, "vy":-3.19008, "omega":0.11965, "ax":4.69592, "ay":4.35499, "alpha":1.79507, "fx":[87.89679,83.87864,72.41812,75.31179], "fy":[64.97506,70.20821,81.95113,79.17412]}, + {"t":2.50142, "x":1.49653, "y":4.91365, "heading":2.61739, "vx":2.41928, "vy":-3.06214, "omega":0.17239, "ax":4.39991, "ay":4.63449, "alpha":2.20621, "fx":[85.1327,80.49827,65.68671,68.04749], "fy":[68.4725,74.02064,87.40633,85.42588]}, + {"t":2.52849, "x":1.56364, "y":4.83245, "heading":2.62206, "vx":2.53839, "vy":-2.93667, "omega":0.23211, "ax":3.99012, "ay":4.95338, "alpha":2.93816, "fx":[82.15346,76.53489,56.14609,56.64872], "fy":[71.89554,78.06598,93.78479,93.27614]}, + {"t":2.55556, "x":1.63382, "y":4.75477, "heading":2.62834, "vx":2.64641, "vy":-2.80257, "omega":0.31166, "ax":3.47048, "ay":5.27188, "alpha":3.89505, "fx":[78.53494,72.02423,44.77802,40.79009], "fy":[75.68118,82.20284,99.68735,101.12121]}, + {"t":2.58264, "x":1.70674, "y":4.68083, "heading":2.63678, "vx":2.74036, "vy":-2.65985, "omega":0.4171, "ax":2.81653, "ay":5.56756, "alpha":5.02448, "fx":[73.3549,66.58437,31.85599,19.83832], "fy":[80.53123,86.62647,104.51892,107.13377]}, + {"t":2.60971, "x":1.78195, "y":4.61086, "heading":2.64807, "vx":2.81661, "vy":-2.50913, "omega":0.55312, "ax":1.9652, "ay":5.86314, "alpha":5.73393, "fx":[61.67203,57.86125,17.70022,-3.52343], "fy":[89.61224,92.63361,107.8096,108.86567]}, + {"t":2.63678, "x":1.85893, "y":4.54508, "heading":2.66305, "vx":2.86981, "vy":-2.3504, "omega":0.70835, "ax":0.80629, "ay":6.17292, "alpha":5.10302, "fx":[34.57326,41.02433,2.11832,-22.85667], "fy":[103.07253,101.16698,109.21674,106.54226]}, + {"t":2.66385, "x":1.93691, "y":4.48371, "heading":2.68222, "vx":2.89164, "vy":-2.18329, "omega":0.8465, "ax":-0.49612, "ay":6.27656, "alpha":3.98983, "fx":[0.95292,17.51036,-14.413,-37.80572], "fy":[108.78078,107.71996,108.27426,102.27508]}, + {"t":2.69092, "x":2.01501, "y":4.42691, "heading":2.70514, "vx":2.87821, "vy":-2.01337, "omega":0.95451, "ax":-1.7072, "ay":6.1198, "alpha":2.90088, "fx":[-27.30378,-8.80732,-30.69417,-49.35042], "fy":[105.45214,108.78062,104.83376,97.31737]}, + {"t":2.718, "x":2.09231, "y":4.37465, "heading":2.73098, "vx":2.83199, "vy":-1.8477, "omega":1.03305, "ax":-2.7073, "ay":5.79128, "alpha":1.88235, "fx":[-47.08486,-33.35238,-45.56915,-58.19518], "fy":[98.39222,103.95765,99.29628,92.38613]}, + {"t":2.74507, "x":2.16798, "y":4.32675, "heading":2.75895, "vx":2.7587, "vy":-1.69092, "omega":1.084, "ax":-3.47942, "ay":5.39013, "alpha":0.97585, "fx":[-60.30637,-53.15768,-58.30828,-64.96346], "fy":[91.03973,95.43251,92.4262,87.8397]}, + {"t":2.77214, "x":2.24139, "y":4.28295, "heading":2.78829, "vx":2.66451, "vy":-1.545, "omega":1.11042, "ax":-4.05604, "ay":4.98398, "alpha":0.21559, "fx":[-69.29801,-67.80031,-68.70081,-70.16929], "fy":[84.52341,85.73695,85.02935,83.81433]}, + {"t":2.79921, "x":2.31204, "y":4.24295, "heading":2.81835, "vx":2.5547, "vy":-1.41007, "omega":1.11626, "ax":-4.48289, "ay":4.60725, "alpha":-0.40331, "fx":[-75.64516,-78.24019,-76.91522,-74.2099], "fy":[78.99931,76.41826,77.72742,80.32675]}, + {"t":2.82628, "x":2.37955, "y":4.20646, "heading":2.84857, "vx":2.43334, "vy":-1.28534, "omega":1.10534, "ax":-4.80078, "ay":4.27214, "alpha":-0.90474, "fx":[-80.30515,-85.65494,-83.29791,-77.38167], "fy":[74.34582,68.09044,70.89788,77.33751]}, + {"t":2.85336, "x":2.44367, "y":4.17323, "heading":2.8785, "vx":2.30338, "vy":-1.16969, "omega":1.08085, "ax":-5.04073, "ay":3.97957, "alpha":-1.31383, "fx":[-83.8499,-90.98693,-88.22612,-79.90237], "fy":[70.39838,60.86411,64.71702,74.78584]}, + {"t":2.88043, "x":2.50418, "y":4.14302, "heading":2.90776, "vx":2.16691, "vy":-1.06195, "omega":1.04528, "ax":-5.2248, "ay":3.7258, "alpha":-1.6512, "fx":[-86.62896,-94.89411,-92.03512,-81.93135], "fy":[67.0128,54.64939,59.22988,72.60726]}, + {"t":2.9075, "x":2.56093, "y":4.11564, "heading":2.93605, "vx":2.02547, "vy":-0.96109, "omega":1.00058, "ax":-5.3684, "ay":3.50575, "alpha":-1.93255, "fx":[-88.86309,-97.81562,-94.99578,-83.58553], "fy":[64.07579,49.30119,54.40889,70.74163]}, + {"t":2.93457, "x":2.61379, "y":4.0909, "heading":2.96314, "vx":1.88013, "vy":-0.86618, "omega":0.94826, "ax":-5.48226, "ay":3.31438, "alpha":-2.16968, "fx":[-90.69644,-100.04251,-97.31669,-84.95119], "fy":[61.50142,44.67629,50.19243,69.13619]}, + {"t":2.96164, "x":2.66268, "y":4.06867, "heading":2.98881, "vx":1.73172, "vy":-0.77646, "omega":0.88952, "ax":-5.57392, "ay":3.14717, "alpha":-2.3715, "fx":[-92.22615,-101.7696,-99.15474,-86.09254], "fy":[59.22511,40.6512,46.50708,67.74616]}, + {"t":2.98872, "x":2.70752, "y":4.0488, "heading":3.01289, "vx":1.58082, "vy":-0.69126, "omega":0.82532, "ax":-5.64874, "ay":3.00029, "alpha":-2.54483, "fx":[-93.51964,-103.12954,-100.62683,-87.05773], "fy":[57.19826,37.12487,43.27912,66.53429]}, + {"t":3.01579, "x":2.74825, "y":4.03119, "heading":3.03524, "vx":1.4279, "vy":-0.61003, "omega":0.75643, "ax":-5.7106, "ay":2.87057, "alpha":-2.69495, "fx":[-94.62492,-104.21448,-101.81994,-87.8832], "fy":[55.38406,34.0163,40.43994,65.46996]}, + {"t":3.04286, "x":2.78481, "y":4.01573, "heading":3.05572, "vx":1.2733, "vy":-0.53232, "omega":0.68347, "ax":-5.76233, "ay":2.75536, "alpha":-2.82605, "fx":[-95.57699,-105.08974,-102.79898,-88.5968], "fy":[53.75443,31.26098,37.92802,64.52812]}, + {"t":3.06993, "x":2.81717, "y":4.00232, "heading":3.07422, "vx":1.11731, "vy":-0.45773, "omega":0.60696, "ax":-5.80605, "ay":2.6525, "alpha":-2.94145, "fx":[-96.40194,-105.80253,-103.61269,-89.21996], "fy":[52.28772,28.80747,35.68932,63.68836]}, + {"t":3.097, "x":2.84529, "y":3.99091, "heading":3.09065, "vx":0.96013, "vy":-0.38592, "omega":0.52733, "ax":-5.84334, "ay":2.56019, "alpha":-3.04385, "fx":[-97.11954,-106.38762,-104.29794,-89.76936], "fy":[50.9671,26.61459,33.67685,62.93403]}, + {"t":3.12407, "x":2.86914, "y":3.9814, "heading":3.10493, "vx":0.80194, "vy":-0.31661, "omega":0.44493, "ax":-5.87542, "ay":2.47697, "alpha":-3.13545, "fx":[-97.74506,-106.87106,-104.88278,-90.25812], "fy":[49.77939,24.64918,31.84994,62.25148]}, + {"t":3.15115, "x":2.8887, "y":3.97373, "heading":3.11697, "vx":0.64288, "vy":-0.24955, "omega":0.36005, "ax":-5.90322, "ay":2.40159, "alpha":-3.21808, "fx":[-98.29047,-107.27265,-105.38875,-90.69666], "fy":[48.71414,22.88439,30.17351,61.62947]}, + {"t":3.17822, "x":2.90394, "y":3.96786, "heading":3.12672, "vx":0.48307, "vy":-0.18454, "omega":0.27293, "ax":-5.92748, "ay":2.33304, "alpha":-3.29325, "fx":[-98.76526,-107.60767,-105.83242,-91.09339], "fy":[47.763,21.29836,28.61732,61.05862]}, + {"t":3.20529, "x":2.91485, "y":3.96372, "heading":3.13411, "vx":0.3226, "vy":-0.12138, "omega":0.18377, "ax":-5.94876, "ay":2.27045, "alpha":-3.36224, "fx":[-99.17706,-107.88805,-106.22665,-91.45521], "fy":[46.91926,19.87323,27.15531,60.53097]}, + {"t":3.23236, "x":2.9214, "y":3.96126, "heading":3.13908, "vx":0.16155, "vy":-0.05991, "omega":0.09275, "ax":-5.96754, "ay":2.2131, "alpha":-3.42613, "fx":[-99.53203,-108.12319,-106.58137,-91.7879], "fy":[46.17744,18.59436,25.76508,60.03961]}, + {"t":3.25943, "x":2.92359, "y":3.96045, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/v2_redundancy/choreo/B_LEFT_PATH3.traj b/src/main/deploy/v2_redundancy/choreo/B_LEFT_PATH3.traj new file mode 100644 index 00000000..5a0f2ef1 --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/B_LEFT_PATH3.traj @@ -0,0 +1,96 @@ +{ + "name":"B_LEFT_PATH3", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.17155122756958, "y":3.923255681991577, "heading":3.141592653589793, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.8201370239257812, "y":6.117753982543945, "heading":0.0, "intervals":34, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":0.8395776748657227, "y":7.055506706237793, "heading":2.179485408307156, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.17155122756958 m", "val":3.17155122756958}, "y":{"exp":"3.923255681991577 m", "val":3.923255681991577}, "heading":{"exp":"180 deg", "val":3.141592653589793}, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.8201370239257812 m", "val":1.8201370239257812}, "y":{"exp":"6.117753982543945 m", "val":6.117753982543945}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":34, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"0.8395776748657227 m", "val":0.8395776748657227}, "y":{"exp":"7.055506706237793 m", "val":7.055506706237793}, "heading":{"exp":"2.1794854083071558 rad", "val":2.179485408307156}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.96245,1.61644], + "samples":[ + {"t":0.0, "x":3.17155, "y":3.92326, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.19148, "ay":5.49712, "alpha":-3.58356, "fx":[-59.86321,-76.4734,-47.33505,-33.47278], "fy":[91.96744,78.6493,98.91474,104.48636]}, + {"t":0.02917, "x":3.17019, "y":3.92559, "heading":3.14159, "vx":-0.09308, "vy":0.16033, "omega":-0.10452, "ax":-3.19293, "ay":5.49902, "alpha":-3.52859, "fx":[-59.80029,-76.15831,-47.49117,-33.79356], "fy":[92.00002,78.94275,98.82922,104.37492]}, + {"t":0.05833, "x":3.16612, "y":3.93261, "heading":3.13854, "vx":-0.1862, "vy":0.32071, "omega":-0.20743, "ax":-3.19457, "ay":5.50112, "alpha":-3.46603, "fx":[-59.67738,-75.80711,-47.74909,-34.12099], "fy":[92.0705,79.26732,98.69305,104.25917]}, + {"t":0.0875, "x":3.15933, "y":3.9443, "heading":3.13249, "vx":-0.27937, "vy":0.48115, "omega":-0.30852, "ax":-3.19638, "ay":5.50345, "alpha":-3.39507, "fx":[-59.49631,-75.41354,-48.10343,-34.46492], "fy":[92.17719,79.62788,98.50772,104.13561]}, + {"t":0.11666, "x":3.14982, "y":3.96067, "heading":3.1235, "vx":-0.3726, "vy":0.64166, "omega":-0.40753, "ax":-3.19838, "ay":5.50602, "alpha":-3.31467, "fx":[-59.25919,-74.96936,-48.54798,-34.8378], "fy":[92.31804,80.03078,98.27475,103.99964]}, + {"t":0.14583, "x":3.1376, "y":3.98173, "heading":3.11161, "vx":-0.46588, "vy":0.80224, "omega":-0.50421, "ax":-3.20057, "ay":5.50885, "alpha":-3.22348, "fx":[-58.96854,-74.46389,-49.07533,-35.25531], "fy":[92.49057,80.48412,97.99606,103.84532]}, + {"t":0.17499, "x":3.12265, "y":4.00747, "heading":3.09691, "vx":-0.55922, "vy":0.96291, "omega":-0.59822, "ax":-3.20294, "ay":5.51198, "alpha":-3.1197, "fx":[-58.62743,-73.88333,-49.67647,-35.73724], "fy":[92.69177,80.99807,97.67421,103.66482]}, + {"t":0.20416, "x":3.10498, "y":4.0379, "heading":3.07946, "vx":-0.65264, "vy":1.12367, "omega":-0.68921, "ax":-3.2055, "ay":5.51544, "alpha":-3.00089, "fx":[-58.23972,-73.20978,-50.34019,-36.30878], "fy":[92.91798,81.58541,97.31281,103.44781]}, + {"t":0.23332, "x":3.08458, "y":4.07302, "heading":3.05936, "vx":-0.74613, "vy":1.28453, "omega":-0.77673, "ax":-3.20824, "ay":5.51926, "alpha":-2.86363, "fx":[-57.81044,-72.41962,-51.05244,-37.00238], "fy":[93.16462,82.26236,96.91708,103.18033]}, + {"t":0.26249, "x":3.06145, "y":4.11283, "heading":3.0367, "vx":-0.8397, "vy":1.4455, "omega":-0.86025, "ax":-3.21115, "ay":5.52351, "alpha":-2.7031, "fx":[-57.34623,-71.48106,-51.79542,-37.86047], "fy":[93.42593,83.04981,96.49445,102.84306]}, + {"t":0.29165, "x":3.0356, "y":4.15734, "heading":3.01161, "vx":-0.93335, "vy":1.60659, "omega":-0.93908, "ax":-3.21423, "ay":5.52822, "alpha":-2.51233, "fx":[-56.85627,-70.34996,-52.54637,-38.93976], "fy":[93.69432,83.9753,96.05548,102.40849]}, + {"t":0.32082, "x":3.00701, "y":4.20654, "heading":2.98423, "vx":-1.0271, "vy":1.76782, "omega":-1.01236, "ax":-3.21743, "ay":5.53341, "alpha":-2.28102, "fx":[-56.35352,-68.96285,-53.27593,-40.31787], "fy":[93.95951,85.07624,95.61501,101.836]}, + {"t":0.34998, "x":2.97569, "y":4.26046, "heading":2.9547, "vx":-1.12093, "vy":1.92921, "omega":-1.07888, "ax":-3.22068, "ay":5.53902, "alpha":-1.99354, "fx":[-55.85723,-67.22424,-53.94564,-42.10431], "fy":[94.20674,86.40508,95.19373,101.06307]}, + {"t":0.37915, "x":2.94162, "y":4.31908, "heading":2.92323, "vx":-1.21486, "vy":2.09075, "omega":-1.13703, "ax":-3.2238, "ay":5.54478, "alpha":-1.62536, "fx":[-55.39749,-64.98281,-54.50401,-44.45903], "fy":[94.41337,88.0382,94.82053,99.98857]}, + {"t":0.40831, "x":2.90482, "y":4.38241, "heading":2.89007, "vx":-1.30889, "vy":2.25247, "omega":-1.18443, "ax":-3.22628, "ay":5.54988, "alpha":-1.13635, "fx":[-55.02483,-61.98278,-54.88,-47.62505], "fy":[94.54154,90.09092,94.53583,98.4389]}, + {"t":0.43748, "x":2.86527, "y":4.45047, "heading":2.85553, "vx":-1.40298, "vy":2.41433, "omega":-1.21757, "ax":-3.22681, "ay":5.55202, "alpha":-0.45701, "fx":[-54.83295,-57.75645,-54.97122,-51.98791], "fy":[94.52013,92.74244,94.39706,96.09374]}, + {"t":0.46664, "x":2.82298, "y":4.52324, "heading":2.82002, "vx":-1.49709, "vy":2.57626, "omega":-1.2309, "ax":-3.2215, "ay":5.54473, "alpha":0.54208, "fx":[-55.02233,-51.35944,-54.62161,-58.18387], "fy":[94.19217,96.26874,94.48747,92.30837]}, + {"t":0.49581, "x":2.77795, "y":4.60074, "heading":2.78412, "vx":-1.59105, "vy":2.73797, "omega":-1.21509, "ax":-3.19834, "ay":5.50723, "alpha":2.12502, "fx":[-56.12913,-40.63544,-53.57594,-67.27086], "fy":[93.11388,101.01365,94.93096,85.64695]}, + {"t":0.52497, "x":2.73019, "y":4.68293, "heading":2.74868, "vx":-1.68433, "vy":2.89859, "omega":-1.15311, "ax":-3.12202, "ay":5.35654, "alpha":4.88832, "fx":[-60.29168,-20.02168,-51.38451,-80.72089], "fy":[89.30581,106.61057,95.91293,72.62346]}, + {"t":0.55414, "x":2.67973, "y":4.76975, "heading":2.71505, "vx":-1.77538, "vy":3.05482, "omega":-1.01054, "ax":-3.08399, "ay":4.46001, "alpha":10.85039, "fx":[-86.07114,20.87639,-47.37991,-97.25656], "fy":[53.01761,105.72271,97.58762,47.12611]}, + {"t":0.58331, "x":2.62664, "y":4.86074, "heading":2.68558, "vx":-1.86533, "vy":3.1849, "omega":-0.69409, "ax":-2.96181, "ay":4.09056, "alpha":12.45209, "fx":[-86.53847,26.41422,-44.86379,-96.52996], "fy":[32.61301,102.71181,97.56885,45.42365]}, + {"t":0.61247, "x":2.57098, "y":4.95537, "heading":2.66533, "vx":-1.95171, "vy":3.3042, "omega":-0.33092, "ax":-2.11594, "ay":3.84617, "alpha":11.06626, "fx":[-44.69331,21.26689,-38.18573,-82.35401], "fy":[34.95504,89.86986,90.19962,46.66472]}, + {"t":0.64164, "x":2.51316, "y":5.05337, "heading":2.65568, "vx":-2.01342, "vy":3.41637, "omega":-0.00817, "ax":0.32194, "ay":0.24717, "alpha":0.13057, "fx":[5.61926,5.93296,5.33323,5.019], "fy":[3.74531,4.34413,4.6633,4.06451]}, + {"t":0.6708, "x":2.45457, "y":5.15312, "heading":2.65544, "vx":-2.00403, "vy":3.42358, "omega":-0.00436, "ax":0.10651, "ay":0.06241, "alpha":0.00027, "fx":[1.81193,1.81259,1.81134,1.81069], "fy":[1.06067,1.06192,1.06258,1.06133]}, + {"t":0.69997, "x":2.39617, "y":5.253, "heading":2.65532, "vx":-2.00093, "vy":3.4254, "omega":-0.00435, "ax":-0.04794, "ay":-0.02802, "alpha":-0.00001, "fx":[-0.81539,-0.81541,-0.81538,-0.81537], "fy":[-0.47652,-0.47655,-0.47656,-0.47654]}, + {"t":0.72913, "x":2.33779, "y":5.35289, "heading":2.65519, "vx":-2.00233, "vy":3.42458, "omega":-0.00436, "ax":-0.2414, "ay":-0.14149, "alpha":-0.00003, "fx":[-4.10622,-4.1063,-4.10615,-4.10607], "fy":[-2.40655,-2.40669,-2.40677,-2.40662]}, + {"t":0.7583, "x":2.27929, "y":5.4527, "heading":2.65506, "vx":-2.00937, "vy":3.42046, "omega":-0.00436, "ax":-0.62549, "ay":-0.36974, "alpha":-0.0001, "fx":[-10.63954,-10.63978,-10.63931,-10.63907], "fy":[-6.28876,-6.28923,-6.28948,-6.28901]}, + {"t":0.78746, "x":2.22042, "y":5.55231, "heading":2.65493, "vx":-2.02761, "vy":3.40967, "omega":-0.00436, "ax":-1.4308, "ay":-0.86295, "alpha":-0.00034, "fx":[-24.33796,-24.33865,-24.33712,-24.33642], "fy":[-14.67735,-14.67889,-14.67982,-14.67828]}, + {"t":0.81663, "x":2.16068, "y":5.65138, "heading":2.65481, "vx":-2.06934, "vy":3.38451, "omega":-0.00437, "ax":-2.70335, "ay":-1.69732, "alpha":-0.00094, "fx":[-45.98481,-45.9859,-45.98155,-45.98046], "fy":[-28.86714,-28.87141,-28.87487,-28.87061]}, + {"t":0.84579, "x":2.09917, "y":5.74937, "heading":2.65468, "vx":-2.14818, "vy":3.335, "omega":-0.0044, "ax":-3.81765, "ay":-2.5526, "alpha":-0.00199, "fx":[-64.94217,-64.9418,-64.93218,-64.93254], "fy":[-43.40969,-43.41833,-43.42836,-43.41973]}, + {"t":0.87496, "x":2.0349, "y":5.84555, "heading":2.65455, "vx":-2.25953, "vy":3.26056, "omega":-0.00445, "ax":-4.38346, "ay":-3.17103, "alpha":-0.00351, "fx":[-74.5726,-74.56852,-74.55024,-74.55433], "fy":[-53.9207,-53.93468,-53.95584,-53.94187]}, + {"t":0.90412, "x":1.96713, "y":5.9393, "heading":2.65442, "vx":-2.38737, "vy":3.16807, "omega":-0.00456, "ax":-4.57489, "ay":-3.61212, "alpha":-0.01587, "fx":[-77.87562,-77.8492,-77.75958,-77.78597], "fy":[-61.36124,-61.41733,-61.52083,-61.46488]}, + {"t":0.93329, "x":1.89556, "y":6.03016, "heading":2.65429, "vx":-2.5208, "vy":3.06272, "omega":-0.00502, "ax":-4.47579, "ay":-4.07045, "alpha":-0.43552, "fx":[-77.90965,-77.1107,-74.37999,-75.12746], "fy":[-67.14082,-68.44105,-71.27159,-70.09501]}, + {"t":0.96245, "x":1.82014, "y":6.11775, "heading":2.65414, "vx":-2.65134, "vy":2.94401, "omega":-0.01772, "ax":-2.16908, "ay":-5.34462, "alpha":-6.74418, "fx":[-68.75699,-61.94732,-19.64209,2.76486], "fy":[-74.05138,-84.58305,-103.15674,-101.85087]}, + {"t":0.98761, "x":1.75276, "y":6.19012, "heading":2.6537, "vx":-2.7059, "vy":2.80957, "omega":-0.18736, "ax":0.50709, "ay":-5.17312, "alpha":-11.23804, "fx":[-26.05789,-46.87782,24.35018,83.08737], "fy":[-86.36251,-95.4847,-104.41698,-65.70883]}, + {"t":1.01276, "x":1.68486, "y":6.25915, "heading":2.64898, "vx":-2.69314, "vy":2.67945, "omega":-0.47004, "ax":2.78983, "ay":-4.16998, "alpha":-12.99986, "fx":[88.92624,-34.80021,39.90091,95.78998], "fy":[-32.73474,-101.43201,-100.50901,-49.04474]}, + {"t":1.03791, "x":1.618, "y":6.32523, "heading":2.63716, "vx":-2.62297, "vy":2.57456, "omega":-0.79703, "ax":3.48456, "ay":-4.73743, "alpha":-7.9995, "fx":[85.8237,7.44859,51.8335,91.97969], "fy":[-62.34646,-107.51853,-95.34125,-57.12287]}, + {"t":1.06307, "x":1.55312, "y":6.38849, "heading":2.61711, "vx":-2.53532, "vy":2.4554, "omega":-0.99824, "ax":3.97749, "ay":-4.82015, "alpha":-4.21805, "fx":[80.4872,43.20933,61.1002,85.82682], "fy":[-72.03871,-99.35456,-89.96137,-66.60285]}, + {"t":1.08822, "x":1.49061, "y":6.44872, "heading":2.592, "vx":-2.43527, "vy":2.33416, "omega":-1.10434, "ax":4.237, "ay":-4.74922, "alpha":-2.10129, "fx":[78.20037,61.17476,67.60872,81.29667], "fy":[-75.43459,-89.89241,-85.39172,-72.413]}, + {"t":1.11337, "x":1.4307, "y":6.50593, "heading":2.56423, "vx":-2.3287, "vy":2.2147, "omega":-1.15719, "ax":4.37894, "ay":-4.67257, "alpha":-0.80532, "fx":[76.8001,70.68397,72.41951,78.03463], "fy":[-77.29855,-82.95089,-81.52197,-76.1446]}, + {"t":1.13853, "x":1.37351, "y":6.56016, "heading":2.53512, "vx":-2.21855, "vy":2.09717, "omega":-1.17745, "ax":4.46471, "ay":-4.60862, "alpha":0.06557, "fx":[75.75476,76.22914,76.13375,75.65606], "fy":[-78.57803,-78.11673,-78.20364,-78.66706]}, + {"t":1.16368, "x":1.31912, "y":6.61146, "heading":2.5055, "vx":-2.10625, "vy":1.98124, "omega":-1.1758, "ax":4.52099, "ay":-4.55694, "alpha":0.69392, "fx":[74.88561,79.7223,79.09786,73.89704], "fy":[-79.57242,-74.71789,-75.32026,-80.43827]}, + {"t":1.18884, "x":1.26757, "y":6.65985, "heading":2.47593, "vx":-1.99253, "vy":1.86662, "omega":-1.15835, "ax":4.56025, "ay":-4.5149, "alpha":1.17125, "fx":[74.11949,82.0481,81.52249,72.58408], "fy":[-80.40249,-72.28492,-72.78729,-81.71416]}, + {"t":1.21399, "x":1.21889, "y":6.70537, "heading":2.44679, "vx":-1.87782, "vy":1.75305, "omega":-1.12889, "ax":4.58891, "ay":-4.48026, "alpha":1.54773, "fx":[73.42262,83.658,83.54272,71.60103], "fy":[-81.12491,-70.51602,-70.54374,-82.64731]}, + {"t":1.23914, "x":1.17311, "y":6.74805, "heading":2.41839, "vx":-1.7624, "vy":1.64036, "omega":-1.08996, "ax":4.61057, "ay":-4.45133, "alpha":1.85299, "fx":[72.77808,84.80283,85.24944,70.86753], "fy":[-81.76923,-69.2154,-68.54474,-83.33417]}, + {"t":1.2643, "x":1.13024, "y":6.7879, "heading":2.39098, "vx":-1.64643, "vy":1.52839, "omega":-1.04335, "ax":4.62738, "ay":-4.42688, "alpha":2.10567, "fx":[72.17699,85.63209,86.70652,70.32593], "fy":[-82.35214,-68.25232,-66.75627,-83.83895]}, + {"t":1.28945, "x":1.09029, "y":6.82495, "heading":2.36473, "vx":-1.53003, "vy":1.41704, "omega":-0.99038, "ax":4.64071, "ay":-4.40599, "alpha":2.31816, "fx":[71.61455,86.24021,87.96059,69.93338], "fy":[-82.88371,-67.5366,-65.15172,-84.20646]}, + {"t":1.3146, "x":1.05327, "y":6.8592, "heading":2.33982, "vx":-1.4133, "vy":1.30622, "omega":-0.93207, "ax":4.65148, "ay":-4.38798, "alpha":2.49907, "fx":[71.0881,86.68978,89.0468,69.65693], "fy":[-83.37037,-67.00419,-63.70954,-84.46934]}, + {"t":1.33976, "x":1.01919, "y":6.89067, "heading":2.31638, "vx":-1.2963, "vy":1.19584, "omega":-0.86921, "ax":4.66032, "ay":-4.37234, "alpha":2.65463, "fx":[70.59614,87.02404,89.99243,69.47051], "fy":[-83.81649,-66.60828,-62.41175,-84.65225]}, + {"t":1.36491, "x":0.98806, "y":6.91936, "heading":2.29451, "vx":-1.17908, "vy":1.08587, "omega":-0.80244, "ax":4.66768, "ay":-4.35864, "alpha":2.78954, "fx":[70.13784,87.2739,90.81912,69.35294], "fy":[-84.22521,-66.31391,-61.24305,-84.7745]}, + {"t":1.39006, "x":0.95988, "y":6.9453, "heading":2.27433, "vx":-1.06167, "vy":0.97623, "omega":-0.73227, "ax":4.67389, "ay":-4.34656, "alpha":2.90741, "fx":[69.71269,87.46214,91.54435,69.28663], "fy":[-84.59886,-66.09435,-60.19009,-84.85165]}, + {"t":1.41522, "x":0.93465, "y":6.96848, "heading":2.25591, "vx":-0.9441, "vy":0.8669, "omega":-0.65914, "ax":4.67917, "ay":-4.33584, "alpha":3.01112, "fx":[69.3204,87.60598,92.18249,69.25676], "fy":[-84.93929,-65.92886,-59.24115,-84.89654]}, + {"t":1.44037, "x":0.91238, "y":6.98891, "heading":2.23933, "vx":-0.82641, "vy":0.75784, "omega":-0.5834, "ax":4.68373, "ay":-4.32628, "alpha":3.10299, "fx":[68.96076,87.71873,92.74544,69.25065], "fy":[-85.24799,-65.80104,-58.38583,-84.91999]}, + {"t":1.46552, "x":0.89308, "y":7.0066, "heading":2.22466, "vx":-0.7086, "vy":0.64902, "omega":-0.50535, "ax":4.68769, "ay":-4.31768, "alpha":3.18495, "fx":[68.63364,87.81088,93.24317,69.25737], "fy":[-85.5262,-65.69777,-57.61485,-84.93127]}, + {"t":1.49068, "x":0.87674, "y":7.02156, "heading":2.21195, "vx":-0.59068, "vy":0.54041, "omega":-0.42524, "ax":4.69116, "ay":-4.30992, "alpha":3.25859, "fx":[68.33895,87.89082,93.68404,69.26743], "fy":[-85.77494,-65.60842,-56.91999,-84.93837]}, + {"t":1.51583, "x":0.86336, "y":7.03379, "heading":2.20125, "vx":-0.47269, "vy":0.432, "omega":-0.34327, "ax":4.69422, "ay":-4.30286, "alpha":3.32525, "fx":[68.07665,87.96535,94.07511,69.27257], "fy":[-85.99508,-65.52428,-56.29398,-84.94822]}, + {"t":1.54098, "x":0.85296, "y":7.0433, "heading":2.19261, "vx":-0.35461, "vy":0.32377, "omega":-0.25963, "ax":4.69694, "ay":-4.29641, "alpha":3.38607, "fx":[67.84673,88.04005,94.42231,69.26559], "fy":[-86.18731,-65.43814,-55.73039,-84.96687]}, + {"t":1.56614, "x":0.84553, "y":7.05008, "heading":2.18608, "vx":-0.23647, "vy":0.2157, "omega":-0.17446, "ax":4.69937, "ay":-4.29048, "alpha":3.442, "fx":[67.64927,88.11954,94.73063,69.24024], "fy":[-86.35217,-65.34399,-55.22369,-84.99953]}, + {"t":1.59129, "x":0.84106, "y":7.05415, "heading":2.1817, "vx":-0.11826, "vy":0.10778, "omega":-0.08788, "ax":4.70154, "ay":-4.285, "alpha":3.49387, "fx":[67.48441,88.20765,95.00422,69.19111], "fy":[-86.49004,-65.23677,-54.76911,-85.0507]}, + {"t":1.61644, "x":0.83958, "y":7.05551, "heading":2.17949, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/v2_redundancy/choreo/B_RIGHT_PATH1.traj b/src/main/deploy/v2_redundancy/choreo/B_RIGHT_PATH1.traj new file mode 100644 index 00000000..16e22f61 --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/B_RIGHT_PATH1.traj @@ -0,0 +1,108 @@ +{ + "name":"B_RIGHT_PATH1", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.163801670074463, "y":0.7438099258422852, "heading":-1.5707963267948966, "intervals":48, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":3.046499013900757, "y":2.6794681549072266, "heading":0.0, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":2.638746500015259, "y":3.6656603813171382, "heading":-3.141592653589793, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"7.163801670074463 m", "val":7.163801670074463}, "y":{"exp":"(8.0518 - 7.307990074157715) m", "val":0.7438099258422852}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":48, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"3.046499013900757 m", "val":3.046499013900757}, "y":{"exp":"2.6794681549072266 m", "val":2.6794681549072266}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"2.638746500015259 m", "val":2.638746500015259}, "y":{"exp":"3.6656603813171387 m", "val":3.6656603813171382}, "heading":{"exp":"-3.141592653589793 rad", "val":-3.141592653589793}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.49581,2.08565], + "samples":[ + {"t":0.0, "x":7.1638, "y":0.74381, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.91906, "ay":2.02549, "alpha":-5.2346, "fx":[-109.44437,-108.82681,-85.4664,-98.98863], "fy":[8.09554,13.52768,68.78251,47.40598]}, + {"t":0.03324, "x":7.16053, "y":0.74493, "heading":-1.5708, "vx":-0.19675, "vy":0.06733, "omega":-0.174, "ax":-5.92525, "ay":2.0302, "alpha":-5.12574, "fx":[-109.40072,-108.7357,-85.95208,-99.0589], "fy":[8.56872,14.16114,68.15976,47.24272]}, + {"t":0.06648, "x":7.15072, "y":0.74829, "heading":-1.57658, "vx":-0.39371, "vy":0.13481, "omega":-0.34438, "ax":-5.93159, "ay":2.03527, "alpha":-5.01178, "fx":[-109.33991,-108.66225,-86.50336,-99.0732], "fy":[9.21224,14.63014,67.44125,47.19406]}, + {"t":0.09972, "x":7.13435, "y":0.75389, "heading":-1.58803, "vx":-0.59087, "vy":0.20246, "omega":-0.51097, "ax":-5.93829, "ay":2.0408, "alpha":-4.88832, "fx":[-109.25836,-108.60265,-87.13411,-99.0393], "fy":[10.02962,14.97663,66.60367,47.24356]}, + {"t":0.13296, "x":7.11143, "y":0.76175, "heading":-1.60501, "vx":-0.78826, "vy":0.2703, "omega":-0.67346, "ax":-5.94558, "ay":2.04687, "alpha":-4.74992, "fx":[-109.15119,-108.55044,-87.86225,-98.96672], "fy":[11.02751,15.25352,65.61561,47.37023]}, + {"t":0.1662, "x":7.08195, "y":0.77187, "heading":-1.6274, "vx":-0.9859, "vy":0.33834, "omega":-0.83135, "ax":-5.95374, "ay":2.05361, "alpha":-4.58974, "fx":[-109.01181,-108.49657,-88.70936,-98.86779], "fy":[12.21615,15.52575,64.43644,47.5467]}, + {"t":0.19944, "x":7.04589, "y":0.78425, "heading":-1.65503, "vx":-1.1838, "vy":0.4066, "omega":-0.98391, "ax":-5.96306, "ay":2.06108, "alpha":-4.39918, "fx":[-108.83149,-108.42912,-89.69996,-98.75914], "fy":[13.61022,15.87224,63.01482,47.73649]}, + {"t":0.23268, "x":7.00324, "y":0.7989, "heading":-1.68774, "vx":-1.38201, "vy":0.47511, "omega":-1.13014, "ax":-5.97386, "ay":2.06935, "alpha":-4.16734, "fx":[-108.59842,-108.33227,-90.8602,-98.66403], "fy":[15.2305,16.38901,61.28696,47.88964]}, + {"t":0.26592, "x":6.954, "y":0.81584, "heading":-1.7253, "vx":-1.58059, "vy":0.5439, "omega":-1.26867, "ax":-5.98646, "ay":2.07839, "alpha":-3.88027, "fx":[-108.29624,-108.18395,-92.21563,-98.61583], "fy":[17.10697,17.19442,59.17474,47.93521]}, + {"t":0.29916, "x":6.89816, "y":0.83507, "heading":-1.76747, "vx":-1.77958, "vy":0.61298, "omega":-1.39765, "ax":-6.00103, "ay":2.08814, "alpha":-3.51976, "fx":[-107.90117,-107.95082,-93.78748,-98.66366], "fy":[19.28483,18.43811,56.5838,47.76817]}, + {"t":0.3324, "x":6.83569, "y":0.8566, "heading":-1.81393, "vx":-1.97905, "vy":0.68239, "omega":-1.51464, "ax":-6.0175, "ay":2.0985, "alpha":-3.06089, "fx":[-107.37616,-107.57837,-95.58728,-98.88169], "fy":[21.83683,20.31688,53.40188,47.22421]}, + {"t":0.36564, "x":6.76658, "y":0.88044, "heading":-1.86428, "vx":-2.17908, "vy":0.75215, "omega":-1.61639, "ax":-6.03512, "ay":2.10936, "alpha":-2.46671, "fx":[-106.65788,-106.9704,-97.60925,-99.38524], "fy":[24.88982,23.10363,49.49757,46.02775]}, + {"t":0.39888, "x":6.69081, "y":0.9066, "heading":-1.91801, "vx":-2.37968, "vy":0.82227, "omega":-1.69838, "ax":-6.05164, "ay":2.12055, "alpha":-1.67541, "fx":[-105.62334,-105.9444,-99.82054,-100.35856], "fy":[28.68757,27.20092,44.7188,43.67269]}, + {"t":0.43212, "x":6.60837, "y":0.93511, "heading":-1.97446, "vx":-2.58084, "vy":0.89275, "omega":-1.75407, "ax":-6.06068, "ay":2.13116, "alpha":-0.5659, "fx":[-103.98977,-104.12688,-102.14968,-102.09573], "fy":[33.76043,33.24077,38.88895,39.11162]}, + {"t":0.46536, "x":6.51923, "y":0.96596, "heading":-2.03277, "vx":-2.7823, "vy":0.96359, "omega":-1.77288, "ax":-6.04167, "ay":2.13613, "alpha":1.14973, "fx":[-100.92762,-100.68697,-104.47251,-104.98123], "fy":[41.48107,42.25891,31.79438,29.80528]}, + {"t":0.4986, "x":6.42341, "y":0.99917, "heading":-2.0917, "vx":-2.98313, "vy":1.0346, "omega":-1.73467, "ax":-5.90007, "ay":2.11399, "alpha":4.36328, "fx":[-92.79076,-93.6278,-106.58878,-108.42653], "fy":[56.47576,55.88316,23.15746,8.31723]}, + {"t":0.53184, "x":6.32099, "y":1.03473, "heading":-2.14936, "vx":-3.17925, "vy":1.10487, "omega":-1.58963, "ax":-4.92498, "ay":2.05406, "alpha":12.67932, "fx":[-49.09744,-78.88543,-108.11334,-98.99358], "fy":[95.06649,74.93749,13.04843,-43.29661]}, + {"t":0.56508, "x":6.21259, "y":1.07259, "heading":-2.2022, "vx":-3.34295, "vy":1.17315, "omega":-1.16817, "ax":-4.63738, "ay":2.0277, "alpha":14.0127, "fx":[-37.99985,-75.31908,-107.65188,-94.55112], "fy":[97.7375,77.77164,13.10862,-50.65512]}, + {"t":0.59832, "x":6.09891, "y":1.11271, "heading":-2.24103, "vx":-3.4971, "vy":1.24055, "omega":-0.70238, "ax":-4.59528, "ay":1.93443, "alpha":13.50275, "fx":[-40.1392,-73.84315,-106.22639,-92.44896], "fy":[90.80283,76.97225,13.60339,-49.76235]}, + {"t":0.63156, "x":5.98013, "y":1.15501, "heading":-2.26438, "vx":-3.64985, "vy":1.30485, "omega":-0.25355, "ax":-2.83012, "ay":0.20564, "alpha":7.41891, "fx":[-23.99632,-50.982,-69.15928,-48.42073], "fy":[8.55681,34.09739,0.50103,-29.16388]}, + {"t":0.6648, "x":5.85724, "y":1.1985, "heading":-2.27281, "vx":-3.74392, "vy":1.31168, "omega":-0.00694, "ax":-0.13155, "ay":-0.35444, "alpha":0.02058, "fx":[-2.16216,-2.24415,-2.3131,-2.23118], "fy":[-6.0227,-5.95371,-6.03501,-6.10396]}, + {"t":0.69804, "x":5.73272, "y":1.2419, "heading":-2.27304, "vx":-3.7483, "vy":1.2999, "omega":-0.00626, "ax":-0.04325, "ay":-0.12488, "alpha":0.00009, "fx":[-0.73533,-0.73571,-0.73601,-0.73564], "fy":[-2.12406,-2.12375,-2.12413,-2.12444]}, + {"t":0.73128, "x":5.6081, "y":1.28504, "heading":-2.27325, "vx":-3.74973, "vy":1.29575, "omega":-0.00626, "ax":-0.01502, "ay":-0.04348, "alpha":0.00002, "fx":[-0.25535,-0.25545,-0.25553,-0.25543], "fy":[-0.73953,-0.73945,-0.73955,-0.73963]}, + {"t":0.76452, "x":5.48345, "y":1.32809, "heading":-2.27345, "vx":-3.75023, "vy":1.2943, "omega":-0.00625, "ax":-0.00515, "ay":-0.01492, "alpha":0.00001, "fx":[-0.08753,-0.08758,-0.08762,-0.08757], "fy":[-0.25374,-0.2537,-0.25375,-0.25379]}, + {"t":0.79776, "x":5.35879, "y":1.3711, "heading":-2.27366, "vx":-3.7504, "vy":1.29381, "omega":-0.00625, "ax":-0.00156, "ay":-0.00451, "alpha":0.00001, "fx":[-0.02644,-0.02647,-0.0265,-0.02647], "fy":[-0.0767,-0.07668,-0.07671,-0.07674]}, + {"t":0.83101, "x":5.23412, "y":1.41411, "heading":-2.27387, "vx":-3.75046, "vy":1.29366, "omega":-0.00625, "ax":0.00014, "ay":0.00041, "alpha":0.00001, "fx":[0.00242,0.0024,0.00237,0.0024], "fy":[0.00698,0.007,0.00697,0.00695]}, + {"t":0.86425, "x":5.10946, "y":1.45711, "heading":-2.27408, "vx":-3.75045, "vy":1.29367, "omega":-0.00625, "ax":0.00201, "ay":0.00583, "alpha":0.0, "fx":[0.03421,0.03419,0.03418,0.0342], "fy":[0.09914,0.09915,0.09914,0.09912]}, + {"t":0.89749, "x":4.98479, "y":1.50011, "heading":-2.27428, "vx":-3.75038, "vy":1.29387, "omega":-0.00625, "ax":0.00633, "ay":0.01834, "alpha":0.0, "fx":[0.10766,0.10766,0.10766,0.10766], "fy":[0.31196,0.31196,0.31196,0.31196]}, + {"t":0.93073, "x":4.86013, "y":1.54313, "heading":-2.27449, "vx":-3.75017, "vy":1.29448, "omega":-0.00625, "ax":0.01837, "ay":0.05317, "alpha":-0.00001, "fx":[0.31237,0.31243,0.31248,0.31242], "fy":[0.90433,0.90428,0.90434,0.90439]}, + {"t":0.96397, "x":4.73549, "y":1.58619, "heading":-2.2747, "vx":-3.74956, "vy":1.29624, "omega":-0.00625, "ax":0.05287, "ay":0.15257, "alpha":-0.00006, "fx":[0.89906,0.89929,0.89948,0.89925], "fy":[2.59517,2.59498,2.5952,2.59539]}, + {"t":0.99721, "x":4.61088, "y":1.62936, "heading":-2.27491, "vx":-3.74781, "vy":1.30131, "omega":-0.00626, "ax":0.15211, "ay":0.43526, "alpha":-0.00019, "fx":[2.58657,2.58734,2.58799,2.58722], "fy":[7.40359,7.40294,7.4037,7.40434]}, + {"t":1.03045, "x":4.48639, "y":1.67286, "heading":-2.27512, "vx":-3.74275, "vy":1.31578, "omega":-0.00626, "ax":0.42936, "ay":1.20037, "alpha":-0.00066, "fx":[7.3008,7.30352,7.30573,7.303], "fy":[20.41775,20.41555,20.41801,20.42021]}, + {"t":1.06369, "x":4.36221, "y":1.71726, "heading":-2.27532, "vx":-3.72848, "vy":1.35568, "omega":-0.00628, "ax":1.04535, "ay":2.76624, "alpha":-0.00196, "fx":[17.77296,17.78284,17.78939,17.77951], "fy":[47.0535,47.04687,47.05249,47.05911]}, + {"t":1.09693, "x":4.23886, "y":1.76385, "heading":-2.27553, "vx":-3.69373, "vy":1.44763, "omega":-0.00635, "ax":1.7882, "ay":4.30912, "alpha":-0.00419, "fx":[30.39619,30.42407,30.43723,30.40935], "fy":[73.30179,73.28677,73.29203,73.30705]}, + {"t":1.13017, "x":4.11706, "y":1.81435, "heading":-2.27574, "vx":-3.63429, "vy":1.59087, "omega":-0.00649, "ax":2.34931, "ay":5.03794, "alpha":-0.00689, "fx":[39.92499,39.9784,39.99716,39.94377], "fy":[85.70714,85.67952,85.68065,85.70826]}, + {"t":1.16341, "x":3.99756, "y":1.87002, "heading":-2.27596, "vx":-3.5562, "vy":1.75833, "omega":-0.00672, "ax":2.7761, "ay":5.27015, "alpha":-0.01074, "fx":[47.16465,47.25294,47.27665,47.18844], "fy":[89.66962,89.62107,89.61776,89.66629]}, + {"t":1.19665, "x":3.88088, "y":1.93137, "heading":-2.27618, "vx":-3.46392, "vy":1.93351, "omega":-0.00707, "ax":3.14581, "ay":5.28209, "alpha":-0.0432, "fx":[53.29281,53.65385,53.72524,53.36567], "fy":[89.96571,89.74672,89.72824,89.94663]}, + {"t":1.22989, "x":3.76748, "y":1.99856, "heading":-2.27642, "vx":-3.35935, "vy":2.10909, "omega":-0.00851, "ax":3.62329, "ay":5.08922, "alpha":-0.66538, "fx":[58.53741,64.12336,64.55252,59.31121], "fy":[88.63237,84.65277,84.60253,88.37694]}, + {"t":1.26313, "x":3.65781, "y":2.07148, "heading":-2.2767, "vx":-3.23891, "vy":2.27826, "omega":-0.03063, "ax":4.62274, "ay":4.11284, "alpha":-4.24001, "fx":[63.66671,95.27552,89.46173,66.1221], "fy":[85.74248,48.73927,60.23894,85.112]}, + {"t":1.29637, "x":3.55271, "y":2.14948, "heading":-2.27772, "vx":-3.08525, "vy":2.41497, "omega":-0.17157, "ax":5.14841, "ay":3.14906, "alpha":-6.76063, "fx":[71.51003,107.40796,99.92805,71.44601], "fy":[79.79688,10.33257,42.53075,81.59815]}, + {"t":1.32961, "x":3.453, "y":2.2315, "heading":-2.28342, "vx":-2.91412, "vy":2.51964, "omega":-0.39629, "ax":5.4369, "ay":2.54678, "alpha":-7.26571, "fx":[81.44123,108.21294,103.76887,76.49734], "fy":[70.31242,-7.65465,33.23957,77.38275]}, + {"t":1.36285, "x":3.35913, "y":2.31666, "heading":-2.2966, "vx":-2.73339, "vy":2.6043, "omega":-0.63781, "ax":5.62257, "ay":2.14391, "alpha":-7.24437, "fx":[88.76824,107.56232,105.69,80.53252], "fy":[61.54987,-16.55904,27.3652,73.51331]}, + {"t":1.39609, "x":3.27138, "y":2.40441, "heading":-2.3178, "vx":-2.5465, "vy":2.67556, "omega":-0.87861, "ax":5.75114, "ay":1.84898, "alpha":-7.10398, "fx":[93.60759,106.88505,106.87566,83.93289], "fy":[54.60567,-21.608,22.95321,69.85155]}, + {"t":1.42933, "x":3.18991, "y":2.49437, "heading":-2.347, "vx":-2.35533, "vy":2.73702, "omega":-1.11475, "ax":5.89012, "ay":1.56012, "alpha":-6.66167, "fx":[98.20336,106.58113,107.78333,88.1895], "fy":[46.56195,-23.75321,18.7609,64.57898]}, + {"t":1.46257, "x":3.11488, "y":2.58621, "heading":-2.38406, "vx":-2.15954, "vy":2.78888, "omega":-1.33618, "ax":6.16737, "ay":1.00948, "alpha":-4.91371, "fx":[105.54421,107.48826,108.76625,97.82225], "fy":[27.41718,-19.88842,12.237,48.91795]}, + {"t":1.49581, "x":3.0465, "y":2.67947, "heading":-2.42847, "vx":-1.95454, "vy":2.82244, "omega":-1.49952, "ax":6.29967, "ay":0.30014, "alpha":-3.85308, "fx":[108.42726,106.53931,109.25142,104.40419], "fy":[9.74331,-23.62533,2.40214,31.90112]}, + {"t":1.5185, "x":3.00378, "y":2.74358, "heading":-2.46249, "vx":-1.81162, "vy":2.82925, "omega":-1.58693, "ax":6.31511, "ay":-0.60443, "alpha":-3.12191, "fx":[108.4517,104.06427,108.7308,108.4259], "fy":[-10.06159,-32.87166,-10.61902,12.42748]}, + {"t":1.54118, "x":2.96431, "y":2.80761, "heading":-2.49849, "vx":-1.66835, "vy":2.81553, "omega":-1.65775, "ax":6.1966, "ay":-1.50809, "alpha":-2.29202, "fx":[105.43431,100.97789,106.45297,108.74434], "fy":[-27.62723,-41.42788,-24.44977,-9.10381]}, + {"t":1.56387, "x":2.92805, "y":2.87109, "heading":-2.5361, "vx":-1.52778, "vy":2.78132, "omega":-1.70975, "ax":5.95467, "ay":-2.35248, "alpha":-1.41222, "fx":[100.61211,97.47084,102.23511,104.83081], "fy":[-42.13251,-49.15887,-38.40413,-30.36478]}, + {"t":1.58655, "x":2.89492, "y":2.93358, "heading":-2.57489, "vx":-1.39269, "vy":2.72795, "omega":-1.74179, "ax":5.62078, "ay":-3.0953, "alpha":-0.55148, "fx":[95.04834,93.74518,96.1828,97.4553], "fy":[-53.67927,-55.98654,-51.72007,-49.21449]}, + {"t":1.60924, "x":2.86478, "y":2.99467, "heading":-2.6144, "vx":-1.26517, "vy":2.65773, "omega":-1.7543, "ax":5.23509, "ay":-3.71762, "alpha":0.2373, "fx":[89.40675,89.98424,88.68586,88.11263], "fy":[-62.75472,-61.90121,-63.73707,-64.5495]}, + {"t":1.63193, "x":2.83742, "y":3.05401, "heading":-2.6542, "vx":-1.14641, "vy":2.57339, "omega":-1.74891, "ax":4.83343, "ay":-4.22149, "alpha":0.93284, "fx":[84.02369,86.33286,80.30514,78.19955], "fy":[-69.89894,-66.94991,-74.04129,-76.33515]}, + {"t":1.65461, "x":2.81266, "y":3.11131, "heading":-2.69388, "vx":-1.03676, "vy":2.47762, "omega":-1.72775, "ax":4.44099, "ay":-4.62109, "alpha":1.53571, "fx":[79.03574,82.89048,71.61532,68.61812], "fy":[-75.57388,-71.21608,-82.50512,-85.1185]}, + {"t":1.6773, "x":2.79028, "y":3.16632, "heading":-2.73307, "vx":-0.93601, "vy":2.37279, "omega":-1.69291, "ax":4.07234, "ay":-4.93469, "alpha":2.05521, "fx":[74.47538,79.71438,63.08516,59.80249], "fy":[-80.13734,-74.80009,-89.2287,-91.58419]}, + {"t":1.69999, "x":2.77009, "y":3.21888, "heading":-2.77148, "vx":-0.84362, "vy":2.26084, "omega":-1.64629, "ax":3.73424, "ay":-5.17996, "alpha":2.50234, "fx":[70.32706,76.82816,55.03006,51.88832], "fy":[-83.8554,-77.80461,-94.44153,-96.33704]}, + {"t":1.72267, "x":2.75192, "y":3.26884, "heading":-2.80883, "vx":-0.75891, "vy":2.14333, "omega":-1.58952, "ax":3.42847, "ay":-5.37207, "alpha":2.88749, "fx":[66.55656,74.23154,47.6219,44.85927], "fy":[-86.92326,-80.32559,-98.41597,-99.84453]}, + {"t":1.74536, "x":2.73558, "y":3.31608, "heading":-2.84489, "vx":-0.68113, "vy":2.02145, "omega":-1.52401, "ax":3.15401, "ay":-5.5232, "alpha":3.21987, "fx":[63.12522,71.90913,40.92474,38.63614], "fy":[-89.48406,-82.44785,-101.41286,-102.44779]}, + {"t":1.76804, "x":2.72094, "y":3.36052, "heading":-2.87946, "vx":-0.60957, "vy":1.89615, "omega":-1.45097, "ax":2.90847, "ay":-5.64286, "alpha":3.50746, "fx":[59.99619,69.83724,34.933,33.12225], "fy":[-91.64351,-84.24367,-103.65632,-104.39025]}, + {"t":1.79073, "x":2.70786, "y":3.40209, "heading":-2.91238, "vx":-0.54359, "vy":1.76814, "omega":-1.37139, "ax":2.68892, "ay":-5.73828, "alpha":3.75714, "fx":[57.13683,67.98876,29.60176,28.22376], "fy":[-93.48052,-85.77319,-105.32744,-105.84498]}, + {"t":1.81342, "x":2.69622, "y":3.44072, "heading":-2.94349, "vx":-0.48259, "vy":1.63796, "omega":-1.28616, "ax":2.4924, "ay":-5.81496, "alpha":3.97478, "fx":[54.51928,66.33622,24.86723,23.85726], "fy":[-95.05472,-87.0856,-106.56719,-106.93573]}, + {"t":1.8361, "x":2.68591, "y":3.47638, "heading":-2.97267, "vx":-0.42605, "vy":1.50604, "omega":-1.19599, "ax":2.3161, "ay":-5.87705, "alpha":4.16537, "fx":[52.1202,64.85365,20.65938,19.95156], "fy":[-96.41182,-88.2208,-107.48295,-107.75195]}, + {"t":1.85879, "x":2.67684, "y":3.50904, "heading":-2.9998, "vx":-0.3735, "vy":1.37271, "omega":-1.10149, "ax":2.1575, "ay":-5.92768, "alpha":4.33314, "fx":[49.92026,63.51752,16.90889,16.44709], "fy":[-97.58727,-89.21088,-108.15541,-108.35914]}, + {"t":1.88148, "x":2.66893, "y":3.53865, "heading":-3.02479, "vx":-0.32456, "vy":1.23823, "omega":-1.00319, "ax":2.01437, "ay":-5.96926, "alpha":4.48171, "fx":[47.9035,62.30707,13.55076,13.29439], "fy":[-98.609,-90.08163,-108.64474,-108.80597]}, + {"t":1.90416, "x":2.66208, "y":3.56521, "heading":-3.04755, "vx":-0.27886, "vy":1.10281, "omega":-0.90151, "ax":1.8848, "ay":-6.00359, "alpha":4.61415, "fx":[46.05676,61.2043,10.52584,10.45248], "fy":[-99.49923,-90.85376,-108.99555,-109.1291]}, + {"t":1.92685, "x":2.65624, "y":3.58868, "heading":-3.068, "vx":-0.2361, "vy":0.96661, "omega":-0.79684, "ax":1.7671, "ay":-6.0321, "alpha":4.7331, "fx":[44.36918,60.19376,7.78127,7.88744], "fy":[-100.27589,-91.54395,-109.24076,-109.35654]}, + {"t":1.94953, "x":2.65134, "y":3.60906, "heading":-3.08608, "vx":-0.19601, "vy":0.82977, "omega":-0.68946, "ax":1.65987, "ay":-6.05586, "alpha":4.84084, "fx":[42.83176,59.26222,5.27032,5.57106], "fy":[-100.95358,-92.16568,-109.40458,-109.50997]}, + {"t":1.97222, "x":2.64732, "y":3.62632, "heading":-3.10172, "vx":-0.15835, "vy":0.69238, "omega":-0.57964, "ax":1.56186, "ay":-6.07572, "alpha":4.93932, "fx":[41.43703,58.39831,2.95204,3.47991], "fy":[-101.54433,-92.73,-109.50468,-109.60637]}, + {"t":1.99491, "x":2.64413, "y":3.64047, "heading":-3.11487, "vx":-0.12292, "vy":0.55455, "omega":-0.46758, "ax":1.47204, "ay":-6.09236, "alpha":5.03023, "fx":[40.17873,57.59216,0.79077,1.5944], "fy":[-102.05808,-93.24602,-109.55382,-109.65919]}, + {"t":2.01759, "x":2.64172, "y":3.65148, "heading":-3.12547, "vx":-0.08953, "vy":0.41633, "omega":-0.35347, "ax":1.38951, "ay":-6.10629, "alpha":5.115, "fx":[39.05159,56.83503,-1.24434,-0.10177], "fy":[-102.50312,-93.72144,-109.56112,-109.67919]}, + {"t":2.04028, "x":2.64004, "y":3.65936, "heading":-3.13349, "vx":-0.058, "vy":0.27781, "omega":-0.23743, "ax":1.31349, "ay":-6.11793, "alpha":5.19487, "fx":[38.05113,56.11898,-3.17969,-1.62225], "fy":[-102.88641,-94.16287,-109.53293,-109.67506]}, + {"t":2.06297, "x":2.63907, "y":3.66408, "heading":-3.13888, "vx":-0.02821, "vy":0.13901, "omega":-0.11958, "ax":1.24332, "ay":-6.12764, "alpha":5.27084, "fx":[37.17352,55.4366,-5.03766,-2.97835], "fy":[-103.21379,-94.57615,-109.47357,-109.65388]}, + {"t":2.08565, "x":2.63875, "y":3.66566, "heading":-3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/v2_redundancy/choreo/B_RIGHT_PATH2.traj b/src/main/deploy/v2_redundancy/choreo/B_RIGHT_PATH2.traj new file mode 100644 index 00000000..48a05270 --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/B_RIGHT_PATH2.traj @@ -0,0 +1,157 @@ +{ + "name":"B_RIGHT_PATH2", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.168461322784424, "y":3.8475184440612793, "heading":-3.141592653589793, "intervals":42, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.9325261116027832, "y":1.9262405633926392, "heading":0.0, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":0.9888414144515992, "y":1.0097386837005615, "heading":-2.179485408307156, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.920522093772888, "y":1.9157768487930296, "heading":0.0, "intervals":43, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":2.9235854148864746, "y":4.0913493507385255, "heading":-3.141592653589793, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":true}, + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.168461322784424 m", "val":3.168461322784424}, "y":{"exp":"3.8475184440612793 m", "val":3.8475184440612793}, "heading":{"exp":"-180 deg", "val":-3.141592653589793}, "intervals":42, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.9325261116027832 m", "val":1.9325261116027832}, "y":{"exp":"1.9262405633926392 m", "val":1.9262405633926392}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"0.9888414144515991 m", "val":0.9888414144515992}, "y":{"exp":"1.0097386837005615 m", "val":1.0097386837005615}, "heading":{"exp":"-2.1794854083071558 rad", "val":-2.179485408307156}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.9205220937728882 m", "val":1.920522093772888}, "y":{"exp":"1.9157768487930298 m", "val":1.9157768487930296}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":43, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"2.9235854148864746 m", "val":2.9235854148864746}, "y":{"exp":"(8.0518 - 3.9604506492614746) m", "val":4.0913493507385255}, "heading":{"exp":"-180 deg", "val":-3.141592653589793}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":true}, + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.8885,1.53211,2.1725,3.09129], + "samples":[ + {"t":0.0, "x":3.16846, "y":3.84752, "heading":-3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.29322, "ay":-5.43609, "alpha":3.59014, "fx":[-35.13188,-49.6732,-78.00698,-61.25495], "fy":[-103.93754,-97.75742,-77.12622,-91.04441]}, + {"t":0.02866, "x":3.16711, "y":3.84529, "heading":-3.14159, "vx":-0.09439, "vy":-0.15581, "omega":0.1029, "ax":-3.29495, "ay":-5.43802, "alpha":3.53227, "fx":[-35.47645,-49.82916,-77.6832,-61.19554], "fy":[-103.81232,-97.66745,-77.44061,-91.076]}, + {"t":0.05732, "x":3.16305, "y":3.83859, "heading":-3.13864, "vx":-0.18883, "vy":-0.31167, "omega":0.20414, "ax":-3.29686, "ay":-5.44014, "alpha":3.46678, "fx":[-35.83084,-50.08317,-77.32206,-61.07861], "fy":[-103.68143,-97.52579,-77.78847,-91.14519]}, + {"t":0.08598, "x":3.15628, "y":3.82742, "heading":-3.13279, "vx":-0.28332, "vy":-0.46759, "omega":0.3035, "ax":-3.29897, "ay":-5.44248, "alpha":3.39287, "fx":[-36.20488,-50.42938,-76.91756,-60.90614], "fy":[-103.54113,-97.33434,-78.17456,-91.25016]}, + {"t":0.11465, "x":3.14681, "y":3.81178, "heading":-3.12409, "vx":-0.37787, "vy":-0.62358, "omega":0.40074, "ax":-3.30126, "ay":-5.44506, "alpha":3.30949, "fx":[-36.61089,-50.86105,-76.46183,-60.68043], "fy":[-103.3866,-97.09515,-78.60506,-91.38874]}, + {"t":0.14331, "x":3.13462, "y":3.79167, "heading":-3.11261, "vx":-0.47249, "vy":-0.77964, "omega":0.4956, "ax":-3.30375, "ay":-5.44789, "alpha":3.21532, "fx":[-37.06426,-51.37026,-75.9447,-60.40422], "fy":[-103.21161,-96.81073,-79.08782,-91.55831]}, + {"t":0.17197, "x":3.11972, "y":3.76709, "heading":-3.0984, "vx":-0.56718, "vy":-0.93578, "omega":0.58775, "ax":-3.30643, "ay":-5.45101, "alpha":3.10859, "fx":[-37.58425,-51.94745,-75.35316,-60.08081], "fy":[-103.00808,-96.48434,-79.63264,-91.7557]}, + {"t":0.20063, "x":3.10211, "y":3.73803, "heading":-3.08156, "vx":-0.66195, "vy":-1.09202, "omega":0.67685, "ax":-3.3093, "ay":-5.45445, "alpha":2.98693, "fx":[-38.19511,-52.58097,-74.67036,-59.71438], "fy":[-102.7654,-96.12036,-80.25178,-91.97708]}, + {"t":0.22929, "x":3.08178, "y":3.70449, "heading":-3.06216, "vx":-0.75679, "vy":-1.24835, "omega":0.76246, "ax":-3.31235, "ay":-5.45824, "alpha":2.84704, "fx":[-38.92771,-53.25646,-73.87426,-59.31025], "fy":[-102.46939,-95.72484,-80.96069,-92.21769]}, + {"t":0.25795, "x":3.05873, "y":3.66647, "heading":-3.04031, "vx":-0.85173, "vy":-1.40479, "omega":0.84406, "ax":-3.31559, "ay":-5.46243, "alpha":2.68435, "fx":[-39.82189,-53.95608,-72.93543,-58.87545], "fy":[-102.10069,-95.30607,-81.77911,-92.47155]}, + {"t":0.28661, "x":3.03295, "y":3.62396, "heading":-3.01611, "vx":-0.94676, "vy":-1.56135, "omega":0.921, "ax":-3.31899, "ay":-5.46704, "alpha":2.49232, "fx":[-40.92998,-54.65744,-71.81352,-58.41952], "fy":[-101.63219,-94.8754,-82.73278,-92.73089]}, + {"t":0.31527, "x":3.00445, "y":3.57697, "heading":-2.98972, "vx":-1.04189, "vy":-1.71804, "omega":0.99243, "ax":-3.32254, "ay":-5.47208, "alpha":2.26147, "fx":[-42.32226,-55.33226,-70.45126,-57.95578], "fy":[-101.02465,-94.44828,-83.8562,-92.98526]}, + {"t":0.34394, "x":2.97323, "y":3.52548, "heading":-2.96127, "vx":-1.13711, "vy":-1.87488, "omega":1.05725, "ax":-3.32615, "ay":-5.47748, "alpha":1.97776, "fx":[-44.09547,-55.94429,-68.76415,-57.50363], "fy":[-100.21919,-94.04563,-85.19697,-93.21987]}, + {"t":0.3726, "x":2.93927, "y":3.46949, "heading":-2.93097, "vx":-1.23245, "vy":-2.03187, "omega":1.11393, "ax":-3.32967, "ay":-5.48297, "alpha":1.61971, "fx":[-46.38681,-56.44618,-66.6214,-57.09271], "fy":[-99.12352,-93.69574,-86.82293,-93.41254]}, + {"t":0.40126, "x":2.90258, "y":3.40901, "heading":-2.89904, "vx":-1.32788, "vy":-2.18902, "omega":1.16035, "ax":-3.33268, "ay":-5.4878, "alpha":1.15335, "fx":[-49.39724,-56.77437,-63.80866,-56.77125], "fy":[-97.5854,-93.43702,-88.83411,-93.52731]}, + {"t":0.42992, "x":2.86315, "y":3.34401, "heading":-2.86579, "vx":-1.4234, "vy":-2.3463, "omega":1.19341, "ax":-3.33407, "ay":-5.49012, "alpha":0.5223, "fx":[-53.43146,-56.84039,-59.94949,-56.62482], "fy":[-95.33801,-93.32207,-91.38178,-93.49955]}, + {"t":0.45858, "x":2.82099, "y":3.27451, "heading":-2.83158, "vx":-1.51896, "vy":-2.50366, "omega":1.20838, "ax":-3.33088, "ay":-5.48501, "alpha":-0.37295, "fx":[-58.9654,-56.5151,-54.32398,-56.82465], "fy":[-91.87907,-93.42409,-94.69457,-93.19606]}, + {"t":0.48724, "x":2.77608, "y":3.2005, "heading":-2.79695, "vx":-1.61442, "vy":-2.66087, "omega":1.19769, "ax":-3.3147, "ay":-5.45847, "alpha":-1.72214, "fx":[-66.74498,-55.5986,-45.40386,-57.78103], "fy":[-86.1828,-93.84691,-99.07755,-92.28062]}, + {"t":0.5159, "x":2.72845, "y":3.12199, "heading":-2.76262, "vx":-1.70943, "vy":-2.81731, "omega":1.14833, "ax":-3.26205, "ay":-5.36274, "alpha":-3.92215, "fx":[-77.80997,-53.76099,-29.55635,-60.81858], "fy":[-75.98957,-94.73904,-104.585,-89.56093]}, + {"t":0.54456, "x":2.67812, "y":3.03904, "heading":-2.72971, "vx":-1.80292, "vy":-2.97102, "omega":1.03592, "ax":-3.1566, "ay":-4.95232, "alpha":-7.97251, "fx":[-92.49875,-50.44791,1.80402,-73.62849], "fy":[-56.50983,-96.29005,-108.14565,-76.005]}, + {"t":0.57323, "x":2.62515, "y":2.95185, "heading":-2.70002, "vx":-1.89339, "vy":-3.11296, "omega":0.80742, "ax":-3.15344, "ay":-4.06427, "alpha":-12.45943, "fx":[-98.34378,-47.24063,24.25595,-93.22821], "fy":[-43.93198,-97.3214,-104.47369,-30.80142]}, + {"t":0.60189, "x":2.56958, "y":2.86096, "heading":-2.67688, "vx":-1.98378, "vy":-3.22944, "omega":0.45031, "ax":-2.93275, "ay":-4.00747, "alpha":-12.42398, "fx":[-95.31494,-45.04056,24.10503,-83.29022], "fy":[-45.06549,-96.36283,-101.61182,-29.62334]}, + {"t":0.63055, "x":2.51152, "y":2.76676, "heading":-2.66397, "vx":-2.06783, "vy":-3.3443, "omega":0.09422, "ax":-0.27589, "ay":-1.25627, "alpha":-3.12075, "fx":[-16.13756,-8.02354,6.57513,-1.18523], "fy":[-18.03918,-31.65566,-25.08443,-10.69624]}, + {"t":0.65921, "x":2.45214, "y":2.67039, "heading":-2.66127, "vx":-2.07574, "vy":-3.38031, "omega":0.00478, "ax":-0.04151, "ay":0.02169, "alpha":-0.00759, "fx":[-0.73272,-0.71453,-0.67957,-0.69776], "fy":[0.37724,0.34228,0.36053,0.39547]}, + {"t":0.68787, "x":2.39263, "y":2.57351, "heading":-2.66113, "vx":-2.07693, "vy":-3.37969, "omega":0.00456, "ax":-0.48579, "ay":0.29992, "alpha":0.00005, "fx":[-8.26292,-8.26303,-8.26324,-8.26313], "fy":[5.10144,5.10167,5.10155,5.10131]}, + {"t":0.71653, "x":2.3329, "y":2.47677, "heading":-2.661, "vx":-2.09085, "vy":-3.37109, "omega":0.00456, "ax":-1.24065, "ay":0.77873, "alpha":0.00028, "fx":[-21.10213,-21.10273,-21.10403,-21.10343], "fy":[13.24573,13.24702,13.24627,13.24497]}, + {"t":0.74519, "x":2.27247, "y":2.38047, "heading":-2.66087, "vx":-2.12641, "vy":-3.34877, "omega":0.00457, "ax":-2.43894, "ay":1.58536, "alpha":0.00084, "fx":[-41.48308,-41.48421,-41.48814,-41.487], "fy":[26.96606,26.96987,26.96697,26.96316]}, + {"t":0.77385, "x":2.21052, "y":2.28514, "heading":-2.66074, "vx":-2.19631, "vy":-3.30333, "omega":0.0046, "ax":-3.59234, "ay":2.47214, "alpha":0.00186, "fx":[-61.10008,-61.10018,-61.10925,-61.10916], "fy":[42.0508,42.05886,42.05001,42.04196]}, + {"t":0.80252, "x":2.1461, "y":2.19148, "heading":-2.66061, "vx":-2.29927, "vy":-3.23248, "omega":0.00465, "ax":-4.23421, "ay":3.13739, "alpha":0.00386, "fx":[-72.01445,-72.01061,-72.03084,-72.03469], "fy":[53.36968,53.38498,53.3626,53.34729]}, + {"t":0.83118, "x":2.07846, "y":2.10012, "heading":-2.66047, "vx":-2.42063, "vy":-3.14256, "omega":0.00476, "ax":-4.46808, "ay":3.61471, "alpha":0.05027, "fx":[-75.89656,-75.81843,-76.10483,-76.18339], "fy":[61.55736,61.73275,61.41356,61.23678]}, + {"t":0.85984, "x":2.00724, "y":2.01154, "heading":-2.66034, "vx":-2.54869, "vy":-3.03896, "omega":0.0062, "ax":-4.0589, "ay":4.39529, "alpha":1.73328, "fx":[-63.85409,-62.16727,-73.60928,-76.53218], "fy":[78.67005,81.5812,71.7898,67.00952]}, + {"t":0.8885, "x":1.93253, "y":1.92624, "heading":-2.66016, "vx":-2.66503, "vy":-2.91298, "omega":0.05588, "ax":-0.64988, "ay":5.42449, "alpha":9.65572, "fx":[53.96431,6.5805,-51.80304,-52.9591], "fy":[88.53851,105.88653,91.87312,82.77767]}, + {"t":0.91325, "x":1.86636, "y":1.85579, "heading":-2.65878, "vx":-2.68111, "vy":-2.7787, "omega":0.2949, "ax":1.51519, "ay":4.73656, "alpha":12.17135, "fx":[92.21731,32.22152,-44.92907,23.58219], "fy":[53.86423,102.74559,96.87702,68.78322]}, + {"t":0.93801, "x":1.80045, "y":1.78846, "heading":-2.65148, "vx":-2.64361, "vy":-2.66145, "omega":0.59619, "ax":3.06627, "ay":4.26994, "alpha":11.9727, "fx":[96.21888,44.22723,-24.88966,93.06932], "fy":[48.84616,98.87362,104.50839,38.29362]}, + {"t":0.96276, "x":1.73595, "y":1.72389, "heading":-2.63672, "vx":-2.5677, "vy":-2.55575, "omega":0.89256, "ax":3.65977, "ay":4.81858, "alpha":6.51202, "fx":[89.76589,55.12646,21.18449,82.92954], "fy":[60.77868,93.57108,105.87883,67.62216]}, + {"t":0.98752, "x":1.67351, "y":1.6621, "heading":-2.61462, "vx":-2.47711, "vy":-2.43647, "omega":1.05376, "ax":4.0456, "ay":4.82618, "alpha":3.46072, "fx":[84.01231,62.91879,49.28306,79.04395], "fy":[68.99432,88.76324,96.63655,73.97335]}, + {"t":1.01227, "x":1.61343, "y":1.60326, "heading":-2.58854, "vx":-2.37696, "vy":-2.31701, "omega":1.13943, "ax":4.25086, "ay":4.75707, "alpha":1.67789, "fx":[79.78963,68.57491,63.74751,77.11157], "fy":[74.13476,84.66173,88.18039,76.68855]}, + {"t":1.03702, "x":1.55589, "y":1.54737, "heading":-2.56033, "vx":-2.27174, "vy":-2.19925, "omega":1.18096, "ax":4.3679, "ay":4.68927, "alpha":0.5393, "fx":[76.70825,72.87807,71.77239,75.82829], "fy":[77.51859,81.14231,82.06921,78.3223]}, + {"t":1.06178, "x":1.501, "y":1.49436, "heading":-2.5311, "vx":-2.16361, "vy":-2.08317, "omega":1.19431, "ax":4.44103, "ay":4.63262, "alpha":-0.24991, "fx":[74.42998,76.27752,76.62707,74.82778], "fy":[79.85118,78.08363,77.76329,79.50038]}, + {"t":1.08653, "x":1.4488, "y":1.44421, "heading":-2.50154, "vx":-2.05368, "vy":-1.96849, "omega":1.18813, "ax":4.49018, "ay":4.58628, "alpha":-0.83197, "fx":[72.72405,79.04,79.76635,73.9761], "fy":[81.51443,75.39413,74.69448,80.44187]}, + {"t":1.11129, "x":1.39934, "y":1.39689, "heading":-2.47212, "vx":-1.94253, "vy":-1.85496, "omega":1.16753, "ax":4.52507, "ay":4.54811, "alpha":-1.28127, "fx":[71.43646,81.33242,81.8959,73.21558], "fy":[82.72772,73.00761,72.47244,81.2407]}, + {"t":1.13604, "x":1.35264, "y":1.35237, "heading":-2.44322, "vx":-1.83052, "vy":-1.74238, "omega":1.13582, "ax":4.55086, "ay":4.51633, "alpha":-1.63991, "fx":[70.46232,83.26461,83.39004,72.51864], "fy":[83.62487,70.87594,70.84221,81.94277]}, + {"t":1.1608, "x":1.30872, "y":1.31062, "heading":-2.41511, "vx":-1.71786, "vy":-1.63058, "omega":1.09522, "ax":4.57054, "ay":4.48954, "alpha":-1.93343, "fx":[69.72784,84.91226,84.46323,71.87122], "fy":[84.29209,68.96326,69.63511,82.57276]}, + {"t":1.18555, "x":1.2676, "y":1.27163, "heading":-2.388, "vx":-1.60472, "vy":-1.51945, "omega":1.04736, "ax":4.58593, "ay":4.46673, "alpha":-2.17821, "fx":[69.17935,86.3297,85.24646,71.26584], "fy":[84.78769,67.24195,68.73642,83.14489]}, + {"t":1.2103, "x":1.22928, "y":1.23539, "heading":-2.36207, "vx":-1.4912, "vy":-1.40888, "omega":0.99344, "ax":4.5982, "ay":4.44712, "alpha":-2.3853, "fx":[68.77642,87.55738,85.8241,70.69843], "fy":[85.15289,65.69,68.06579,83.66794]}, + {"t":1.23506, "x":1.19377, "y":1.20187, "heading":-2.33748, "vx":-1.37738, "vy":-1.29879, "omega":0.9344, "ax":4.60816, "ay":4.43012, "alpha":-2.56251, "fx":[68.48765,88.62635,86.25303,70.16674], "fy":[85.41802,64.28927,67.56533,84.14761]}, + {"t":1.25981, "x":1.16109, "y":1.17108, "heading":-2.31435, "vx":-1.26331, "vy":-1.18913, "omega":0.87096, "ax":4.61636, "ay":4.41528, "alpha":-2.71553, "fx":[68.28796,89.56108,86.57306,69.66955], "fy":[85.60622,63.02432,67.19228,84.58781]}, + {"t":1.28457, "x":1.13123, "y":1.143, "heading":-2.29279, "vx":-1.14903, "vy":-1.07983, "omega":0.80374, "ax":4.6232, "ay":4.40224, "alpha":-2.8487, "fx":[68.15681,90.38128,86.81298,69.20617], "fy":[85.73575,61.88177,66.91436,84.9914]}, + {"t":1.30932, "x":1.10421, "y":1.11762, "heading":-2.27289, "vx":-1.03459, "vy":-0.97086, "omega":0.73323, "ax":4.62898, "ay":4.3907, "alpha":-2.9654, "fx":[68.07704,91.10307,86.99422,68.77621], "fy":[85.82139,60.84977,66.70672,85.36052]}, + {"t":1.33407, "x":1.08001, "y":1.09493, "heading":-2.25474, "vx":-0.92, "vy":-0.86217, "omega":0.65982, "ax":4.63392, "ay":4.38044, "alpha":-3.06833, "fx":[68.03412,91.73983,87.13311,68.37946], "fy":[85.87541,59.91776,66.54988,85.6969]}, + {"t":1.35883, "x":1.05866, "y":1.07493, "heading":-2.23841, "vx":-0.80529, "vy":-0.75374, "omega":0.58387, "ax":4.63818, "ay":4.37125, "alpha":-3.15969, "fx":[68.01553,92.30277,87.24237,68.01578], "fy":[85.90818,59.07625,66.4284,86.00193]}, + {"t":1.38358, "x":1.04015, "y":1.05761, "heading":-2.22395, "vx":-0.69048, "vy":-0.64553, "omega":0.50565, "ax":4.64189, "ay":4.36298, "alpha":-3.24133, "fx":[68.01045,92.80133,87.33206,67.68507], "fy":[85.92862,58.31671,66.32983,86.27678]}, + {"t":1.40834, "x":1.02448, "y":1.04297, "heading":-2.21144, "vx":-0.57557, "vy":-0.53753, "omega":0.42541, "ax":4.64515, "ay":4.35549, "alpha":-3.31476, "fx":[68.00947,93.24352,87.41029,67.3873], "fy":[85.94442,57.6315,66.24404,86.52243]}, + {"t":1.43309, "x":1.01165, "y":1.031, "heading":-2.20091, "vx":-0.46059, "vy":-0.42971, "omega":0.34336, "ax":4.64803, "ay":4.34867, "alpha":-3.38128, "fx":[68.00435,93.6361,87.48366,67.12245], "fy":[85.96229,57.01381,66.1627,86.73968]}, + {"t":1.45785, "x":1.00167, "y":1.02169, "heading":-2.19241, "vx":-0.34553, "vy":-0.32206, "omega":0.25966, "ax":4.65059, "ay":4.34243, "alpha":-3.442, "fx":[67.98791,93.98482,87.55761,66.89054], "fy":[85.98806,56.4576,66.0789,86.92922]}, + {"t":1.4826, "x":0.99455, "y":1.01505, "heading":-2.18598, "vx":-0.23041, "vy":-0.21457, "omega":0.17446, "ax":4.65288, "ay":4.33668, "alpha":-3.49786, "fx":[67.9539,94.29452,87.63664,66.69166], "fy":[86.0268,55.95761,65.98684,87.09156]}, + {"t":1.50735, "x":0.99027, "y":1.01107, "heading":-2.18166, "vx":-0.11523, "vy":-0.10722, "omega":0.08787, "ax":4.65494, "ay":4.33136, "alpha":-3.54966, "fx":[67.89691,94.56923,87.72449,66.52597], "fy":[86.08285,55.50935,65.88165,87.22709]}, + {"t":1.53211, "x":0.98884, "y":1.00974, "heading":-2.17949, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.78418, "ay":4.18595, "alpha":-3.58289, "fx":[70.92187,96.53539,89.41392,68.63909], "fy":[83.61535,52.03183,63.57971,85.58025]}, + {"t":1.55772, "x":0.99041, "y":1.01111, "heading":-2.17949, "vx":0.12255, "vy":0.10723, "omega":-0.09178, "ax":4.77608, "ay":4.19916, "alpha":-3.52153, "fx":[70.92012,96.17594,89.19118,68.6721], "fy":[83.60551,52.67572,63.87995,85.54465]}, + {"t":1.58334, "x":0.99512, "y":1.01524, "heading":-2.18184, "vx":0.24489, "vy":0.21479, "omega":-0.18199, "ax":4.76714, "ay":4.21349, "alpha":-3.45551, "fx":[70.8759,95.76943,88.971,68.73408], "fy":[83.63088,53.39213,64.17324,85.48494]}, + {"t":1.60896, "x":1.00295, "y":1.02212, "heading":-2.1865, "vx":0.36701, "vy":0.32272, "omega":-0.2705, "ax":4.7572, "ay":4.22912, "alpha":-3.38384, "fx":[70.79338,95.30944,88.74808,68.8237], "fy":[83.68772,54.18823,64.46685,85.40195]}, + {"t":1.63457, "x":1.01392, "y":1.03178, "heading":-2.19343, "vx":0.48887, "vy":0.43106, "omega":-0.35718, "ax":4.74613, "ay":4.24625, "alpha":-3.30535, "fx":[70.67749,94.78806,88.51588,68.93952], "fy":[83.77156,55.07256,64.76944,85.29655]}, + {"t":1.66019, "x":1.028, "y":1.04421, "heading":-2.20258, "vx":0.61044, "vy":0.53983, "omega":-0.44185, "ax":4.73371, "ay":4.26511, "alpha":-3.21868, "fx":[70.53396,94.19566,88.26634,69.07993], "fy":[83.87721,56.05514,65.09145,85.16966]}, + {"t":1.6858, "x":1.04519, "y":1.05944, "heading":-2.2139, "vx":0.7317, "vy":0.64908, "omega":-0.5243, "ax":4.71969, "ay":4.286, "alpha":-3.12218, "fx":[70.36938,93.5205,87.98943,69.24305], "fy":[83.99872,57.14759,65.44555,85.02235]}, + {"t":1.71142, "x":1.06548, "y":1.07747, "heading":-2.22733, "vx":0.8526, "vy":0.75887, "omega":-0.60428, "ax":4.70376, "ay":4.30924, "alpha":-3.01391, "fx":[70.19129,92.74825,87.67252,69.4266], "fy":[84.12938,58.36323,65.84728,84.85596]}, + {"t":1.73703, "x":1.08886, "y":1.09832, "heading":-2.2428, "vx":0.97309, "vy":0.86926, "omega":-0.68148, "ax":4.68551, "ay":4.33527, "alpha":-2.89154, "fx":[70.0083,91.86142,87.29947,69.62774], "fy":[84.26161,59.71727,66.31594,84.67221]}, + {"t":1.76265, "x":1.11533, "y":1.12201, "heading":-2.26026, "vx":1.09312, "vy":0.98031, "omega":-0.75555, "ax":4.66441, "ay":4.36461, "alpha":-2.75221, "fx":[69.83022,90.8385,86.84932,69.8428], "fy":[84.38689,61.22694,66.87574,84.47336]}, + {"t":1.78827, "x":1.14486, "y":1.14856, "heading":-2.27962, "vx":1.2126, "vy":1.09211, "omega":-0.82605, "ax":4.63974, "ay":4.39789, "alpha":-2.59245, "fx":[69.66829,89.65288,86.29429,70.06703], "fy":[84.49555,62.9117,67.5575,84.26253]}, + {"t":1.81388, "x":1.17744, "y":1.17797, "heading":-2.30078, "vx":1.33145, "vy":1.20477, "omega":-0.89246, "ax":4.61057, "ay":4.43592, "alpha":-2.40786, "fx":[69.5354,88.27141,85.59679,70.29405], "fy":[84.57654,64.79342,68.40099,84.044]}, + {"t":1.8395, "x":1.21306, "y":1.21029, "heading":-2.32364, "vx":1.44955, "vy":1.3184, "omega":-0.95414, "ax":4.5756, "ay":4.47973, "alpha":-2.19281, "fx":[69.4466,86.65229,84.70449,70.51521], "fy":[84.61694,66.89665,69.45838,83.82373]}, + {"t":1.86511, "x":1.25169, "y":1.24553, "heading":-2.34808, "vx":1.56676, "vy":1.43315, "omega":-1.01031, "ax":4.53304, "ay":4.53064, "alpha":-1.93985, "fx":[69.41967,84.74227,83.54246,70.71845], "fy":[84.6013,69.24874,70.79919,83.61023]}, + {"t":1.89073, "x":1.29331, "y":1.28373, "heading":-2.37396, "vx":1.68288, "vy":1.54921, "omega":-1.06, "ax":4.4803, "ay":4.59038, "alpha":-1.63869, "fx":[69.47614,82.47246,81.9996,70.88646], "fy":[84.51052,71.87989,72.51773,83.41586]}, + {"t":1.91635, "x":1.33789, "y":1.32492, "heading":-2.40111, "vx":1.79764, "vy":1.66679, "omega":-1.10198, "ax":4.41356, "ay":4.66125, "alpha":-1.27455, "fx":[69.64289,79.75246,79.90456,70.99339], "fy":[84.31997,74.8229,74.74395,83.25912]}, + {"t":1.94196, "x":1.38539, "y":1.36915, "heading":-2.42934, "vx":1.9107, "vy":1.78619, "omega":-1.13462, "ax":4.32688, "ay":4.74635, "alpha":-0.82502, "fx":[69.95467,76.46151,76.98095,70.99869], "fy":[83.99645,78.11205,77.65861,83.16892]}, + {"t":1.96758, "x":1.43575, "y":1.41646, "heading":-2.4584, "vx":2.02154, "vy":1.90778, "omega":-1.15576, "ax":4.21065, "ay":4.84983, "alpha":-0.25427, "fx":[70.45842,72.43549,72.75977,70.83415], "fy":[83.49287,81.78009,81.511,83.19301]}, + {"t":1.99319, "x":1.48892, "y":1.46692, "heading":-2.48801, "vx":2.1294, "vy":2.03201, "omega":-1.16227, "ax":4.04833, "ay":4.977, "alpha":0.49824, "fx":[71.22042,67.44758,66.40147,70.37432], "fy":[82.73857,85.85107,86.62294,83.41674]}, + {"t":2.01881, "x":1.54479, "y":1.5206, "heading":-2.51778, "vx":2.2331, "vy":2.1595, "omega":-1.14951, "ax":3.80971, "ay":5.13316, "alpha":1.53857, "fx":[72.3387,61.18036,56.33189,69.35704], "fy":[81.6213,90.32389,93.29898,84.01043]}, + {"t":2.04442, "x":1.60324, "y":1.5776, "heading":-2.54723, "vx":2.33069, "vy":2.29099, "omega":-1.1101, "ax":3.43731, "ay":5.31704, "alpha":3.04656, "fx":[73.96349,53.18903,39.59694,67.12135], "fy":[79.9521,95.13581,101.30546,85.37227]}, + {"t":2.07004, "x":1.66407, "y":1.63803, "heading":-2.57566, "vx":2.41874, "vy":2.42719, "omega":-1.03206, "ax":2.82516, "ay":5.49758, "alpha":5.23364, "fx":[76.31956,42.86813,11.64253,61.39029], "fy":[77.40333,100.08369,107.87644,88.68582]}, + {"t":2.09566, "x":1.72696, "y":1.70201, "heading":-2.6021, "vx":2.49111, "vy":2.56801, "omega":-0.89799, "ax":1.73667, "ay":5.60365, "alpha":7.91376, "fx":[79.54787,29.50388,-28.33839,37.44781], "fy":[73.57445,104.66179,104.51996,98.50945]}, + {"t":2.12127, "x":1.79134, "y":1.76963, "heading":-2.6251, "vx":2.53559, "vy":2.71156, "omega":-0.69527, "ax":-0.21298, "ay":5.48408, "alpha":10.68067, "fx":[72.33913,14.26956,-52.73572,-48.36396], "fy":[79.86039,107.57339,94.45085,91.24582]}, + {"t":2.14689, "x":1.85622, "y":1.84089, "heading":-2.64291, "vx":2.53014, "vy":2.85204, "omega":-0.42168, "ax":-1.55936, "ay":5.57289, "alpha":8.78196, "fx":[31.42162,-7.62117,-60.61686,-69.28091], "fy":[102.15139,107.84874,89.33049,79.84224]}, + {"t":2.1725, "x":1.92052, "y":1.91578, "heading":-2.65371, "vx":2.49019, "vy":2.99479, "omega":-0.19672, "ax":-3.20258, "ay":5.17612, "alpha":5.46147, "fx":[-27.63461,-36.7868,-71.89235,-81.58639], "fy":[102.59484,101.11967,80.1223,68.34066]}, + {"t":2.20122, "x":1.9907, "y":2.0039, "heading":-2.65936, "vx":2.39824, "vy":3.14341, "omega":-0.03991, "ax":-4.76505, "ay":3.98742, "alpha":1.14392, "fx":[-78.77232,-76.42479,-83.20982,-85.80156], "fy":[70.25519,73.40638,65.84151,61.7962]}, + {"t":2.22993, "x":2.05759, "y":2.09579, "heading":-2.66051, "vx":2.26143, "vy":3.25789, "omega":-0.00707, "ax":-5.09665, "ay":3.40296, "alpha":0.06881, "fx":[-86.59764,-86.44253,-86.78743,-86.94248], "fy":[57.98267,58.26982,57.78549,57.49559]}, + {"t":2.25864, "x":2.12042, "y":2.19074, "heading":-2.66071, "vx":2.11509, "vy":3.3556, "omega":-0.00509, "ax":-5.11798, "ay":3.07845, "alpha":0.00801, "fx":[-87.04517,-87.02884,-87.06549,-87.08182], "fy":[52.37234,52.40946,52.35464,52.31749]}, + {"t":2.28735, "x":2.17904, "y":2.28835, "heading":-2.66086, "vx":1.96814, "vy":3.44399, "omega":-0.00486, "ax":-4.99997, "ay":2.72519, "alpha":0.00431, "fx":[-85.04236,-85.03538,-85.05362,-85.0606], "fy":[46.35785,46.37928,46.35162,46.33018]}, + {"t":2.31606, "x":2.23349, "y":2.38836, "heading":-2.661, "vx":1.82459, "vy":3.52223, "omega":-0.00474, "ax":-4.6303, "ay":2.29166, "alpha":0.00272, "fx":[-78.75584,-78.75347,-78.76444,-78.76681], "fy":[38.98114,38.99519,38.97977,38.96572]}, + {"t":2.34478, "x":2.28397, "y":2.49043, "heading":-2.66113, "vx":1.69164, "vy":3.58803, "omega":-0.00466, "ax":-3.79528, "ay":1.72082, "alpha":0.00144, "fx":[-64.5534,-64.55383,-64.55973,-64.5593], "fy":[29.27025,29.27763,29.27114,29.26376]}, + {"t":2.37349, "x":2.33098, "y":2.59416, "heading":-2.66127, "vx":1.58267, "vy":3.63744, "omega":-0.00462, "ax":-2.43807, "ay":1.03349, "alpha":0.00055, "fx":[-41.46917,-41.47004,-41.47245,-41.47158], "fy":[17.5789,17.58159,17.5798,17.57711]}, + {"t":2.4022, "x":2.37541, "y":2.69903, "heading":-2.6614, "vx":1.51267, "vy":3.66711, "omega":-0.0046, "ax":-1.15334, "ay":0.46665, "alpha":-0.00644, "fx":[-19.63966,-19.62542,-19.59616,-19.6104], "fy":[7.94421,7.91413,7.93081,7.96088]}, + {"t":2.43091, "x":2.41837, "y":2.80451, "heading":-2.66153, "vx":1.47955, "vy":3.68051, "omega":-0.00479, "ax":-0.73836, "ay":-0.8984, "alpha":-2.77605, "fx":[-22.40803,-15.3557,-2.66364,-9.80956], "fy":[-12.09165,-24.68573,-18.79806,-5.5509]}, + {"t":2.45962, "x":2.46055, "y":2.90981, "heading":-2.66167, "vx":1.45835, "vy":3.65472, "omega":-0.0845, "ax":-2.09502, "ay":-4.45018, "alpha":-12.05778, "fx":[-91.6247,-35.76007,37.61663,-52.77444], "fy":[-51.66076,-100.22301,-97.88103,-53.02011]}, + {"t":2.48834, "x":2.50155, "y":3.01291, "heading":-2.6641, "vx":1.3982, "vy":3.52694, "omega":-0.4307, "ax":-2.31807, "ay":-4.52076, "alpha":-12.18269, "fx":[-94.67457,-36.3544,40.51317,-67.20303], "fy":[-51.16372,-101.92446,-99.53566,-54.96329]}, + {"t":2.51705, "x":2.54074, "y":3.11232, "heading":-2.67646, "vx":1.33165, "vy":3.39714, "omega":-0.78049, "ax":-2.19418, "ay":-5.42181, "alpha":-8.03194, "fx":[-85.60141,-37.65468,20.68686,-46.72029], "fy":[-66.39824,-101.99372,-106.26464,-94.23681]}, + {"t":2.54576, "x":2.57807, "y":3.20762, "heading":-2.69887, "vx":1.26865, "vy":3.24147, "omega":-1.0111, "ax":-2.28837, "ay":-5.82648, "alpha":-4.19064, "fx":[-66.20204,-39.08124,-9.60092,-40.8138], "fy":[-86.25335,-101.68921,-108.28681,-100.19769]}, + {"t":2.57447, "x":2.61356, "y":3.29829, "heading":-2.7279, "vx":1.20294, "vy":3.07418, "omega":-1.13142, "ax":-2.32991, "ay":-5.93958, "alpha":-1.93437, "fx":[-52.57889,-39.81127,-26.35043,-39.78383], "fy":[-95.4734,-101.56299,-105.7604,-101.32568]}, + {"t":2.60318, "x":2.64713, "y":3.3841, "heading":-2.76039, "vx":1.13605, "vy":2.90364, "omega":-1.18696, "ax":-2.34239, "ay":-5.97313, "alpha":-0.53349, "fx":[-43.45644,-39.97139,-36.21318,-39.73221], "fy":[-100.14694,-101.61404,-102.98934,-101.65493]}, + {"t":2.6319, "x":2.67879, "y":3.46501, "heading":-2.79447, "vx":1.06879, "vy":2.73214, "omega":-1.20228, "ax":-2.34485, "ay":-5.98072, "alpha":0.39703, "fx":[-37.18924,-39.70742,-42.57666,-40.06752], "fy":[-102.76829,-101.8039,-100.65368,-101.69522]}, + {"t":2.66061, "x":2.70851, "y":3.54099, "heading":-2.82899, "vx":1.00147, "vy":2.56043, "omega":-1.19088, "ax":-2.34378, "ay":-5.9791, "alpha":1.05276, "fx":[-32.74357,-39.13799,-46.99411,-40.5925], "fy":[-104.36203,-102.09201,-98.76059,-101.59631]}, + {"t":2.68932, "x":2.7363, "y":3.61204, "heading":-2.86318, "vx":0.93417, "vy":2.38875, "omega":-1.16065, "ax":-2.34141, "ay":-5.97423, "alpha":1.53784, "fx":[-29.50469,-38.35455,-50.23218,-41.21576], "fy":[-105.39219,-102.44362,-97.22273,-101.42091]}, + {"t":2.71803, "x":2.76215, "y":3.67817, "heading":-2.8965, "vx":0.86695, "vy":2.21722, "omega":-1.1165, "ax":-2.33857, "ay":-5.96838, "alpha":1.91133, "fx":[-27.09632,-37.4276,-52.70319,-41.88668], "fy":[-106.08984,-102.83099,-95.95943,-101.2013]}, + {"t":2.74674, "x":2.78608, "y":3.73937, "heading":-2.92856, "vx":0.7998, "vy":2.04586, "omega":-1.06162, "ax":-2.33558, "ay":-5.96245, "alpha":2.20868, "fx":[-25.27788,-36.41206,-54.64637,-42.57396], "fy":[-106.57965,-103.23279,-94.90924,-100.95668]}, + {"t":2.77546, "x":2.80808, "y":3.79565, "heading":-2.95904, "vx":0.73274, "vy":1.87466, "omega":-0.9982, "ax":-2.33259, "ay":-5.95679, "alpha":2.45212, "fx":[-23.88875,-35.35118,-56.20976,-43.25674], "fy":[-106.93348,-103.63308,-94.02691,-100.69966]}, + {"t":2.80417, "x":2.82816, "y":3.84702, "heading":-2.9877, "vx":0.66577, "vy":1.70363, "omega":-0.9278, "ax":-2.32966, "ay":-5.9515, "alpha":2.6561, "fx":[-22.81744,-34.2792,-57.4902,-43.92043], "fy":[-107.19511,-104.02033,-93.27885,-100.43922]}, + {"t":2.83288, "x":2.84631, "y":3.89348, "heading":-3.01434, "vx":0.59888, "vy":1.53275, "omega":-0.85154, "ax":-2.32684, "ay":-5.94661, "alpha":2.83024, "fx":[-21.98383,-33.22326,-58.55411,-44.55441], "fy":[-107.3925,-104.38653,-92.63959,-100.18214]}, + {"t":2.86159, "x":2.86255, "y":3.93504, "heading":-3.03879, "vx":0.53207, "vy":1.36202, "omega":-0.77027, "ax":-2.32416, "ay":-5.9421, "alpha":2.98114, "fx":[-21.3287,-32.20482,-59.44902,-45.15073], "fy":[-107.54429,-104.7264,-92.08928,-99.93378]}, + {"t":2.8903, "x":2.87687, "y":3.97169, "heading":-3.06091, "vx":0.46534, "vy":1.19141, "omega":-0.68468, "ax":-2.32163, "ay":-5.93794, "alpha":3.1134, "fx":[-20.80708,-31.24071,-60.21022,-45.70327], "fy":[-107.66333,-105.03676,-91.61209,-99.69847]}, + {"t":2.91902, "x":2.88927, "y":4.00345, "heading":-3.08057, "vx":0.39868, "vy":1.02092, "omega":-0.59529, "ax":-2.31927, "ay":-5.9341, "alpha":3.23027, "fx":[-20.38415,-30.34403,-60.86469,-46.20729], "fy":[-107.7588,-105.31593,-91.19506,-99.47987]}, + {"t":2.94773, "x":2.89976, "y":4.03032, "heading":-3.09766, "vx":0.33209, "vy":0.85054, "omega":-0.50254, "ax":-2.31706, "ay":-5.93057, "alpha":3.33414, "fx":[-20.03249,-29.52494,-61.43363,-46.65897], "fy":[-107.83744,-105.56334,-90.82744,-99.28103]}, + {"t":2.97644, "x":2.90834, "y":4.0523, "heading":-3.11209, "vx":0.26556, "vy":0.68026, "omega":-0.40681, "ax":-2.31501, "ay":-5.92732, "alpha":3.42676, "fx":[-19.73015,-28.79124,-61.93399,-47.05524], "fy":[-107.90431,-105.77912,-90.50019,-99.10459]}, + {"t":3.00515, "x":2.91501, "y":4.06939, "heading":-3.12377, "vx":0.19909, "vy":0.51007, "omega":-0.30842, "ax":-2.31311, "ay":-5.92434, "alpha":3.50948, "fx":[-19.45942,-28.14899,-62.37948,-47.39356], "fy":[-107.96329,-105.96383,-90.20568,-98.95281]}, + {"t":3.03386, "x":2.91978, "y":4.08159, "heading":-3.13262, "vx":0.13268, "vy":0.33997, "omega":-0.20766, "ax":-2.31135, "ay":-5.92163, "alpha":3.58333, "fx":[-19.20593,-27.60297,-62.78122,-47.67174], "fy":[-108.0174,-106.11819,-89.93748,-98.82765]}, + {"t":3.06258, "x":2.92263, "y":4.08891, "heading":-3.13858, "vx":0.06632, "vy":0.16995, "omega":-0.10477, "ax":-2.30973, "ay":-5.91916, "alpha":3.64912, "fx":[-18.95794,-27.15714,-63.14821,-47.88792], "fy":[-108.06897,-106.24295,-89.69026,-98.7308]}, + {"t":3.09129, "x":2.92359, "y":4.09135, "heading":-3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/v2_redundancy/choreo/B_RIGHT_PATH3.traj b/src/main/deploy/v2_redundancy/choreo/B_RIGHT_PATH3.traj new file mode 100644 index 00000000..d9e7ebb4 --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/B_RIGHT_PATH3.traj @@ -0,0 +1,97 @@ +{ + "name":"B_RIGHT_PATH3", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.17155122756958, "y":4.128544318008423, "heading":-3.141592653589793, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.8201370239257812, "y":1.9340460174560548, "heading":0.0, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":0.7159243226051331, "y":0.8728400468826294, "heading":-2.179485408307156, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.17155122756958 m", "val":3.17155122756958}, "y":{"exp":"(8.0518 - 3.923255681991577) m", "val":4.128544318008423}, "heading":{"exp":"-180 deg", "val":-3.141592653589793}, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.8201370239257812 m", "val":1.8201370239257812}, "y":{"exp":"(8.0518 - 6.117753982543945) m", "val":1.9340460174560548}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"0.7159243226051331 m", "val":0.7159243226051331}, "y":{"exp":"0.8728400468826294 m", "val":0.8728400468826294}, "heading":{"exp":"-2.1794854083071558 rad", "val":-2.179485408307156}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.96199,1.65997], + "samples":[ + {"t":0.0, "x":3.17155, "y":4.12854, "heading":-3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.23174, "ay":-5.47655, "alpha":3.53305, "fx":[-34.41351,-48.37199,-76.76202,-60.33611], "fy":[-104.17988,-98.41253,-78.36801,-91.65752]}, + {"t":0.02915, "x":3.17018, "y":4.12622, "heading":-3.14159, "vx":-0.09421, "vy":-0.15965, "omega":0.10299, "ax":-3.23314, "ay":-5.47837, "alpha":3.47908, "fx":[-34.73027,-48.5194,-76.45369,-60.27562], "fy":[-104.06654,-98.32924,-78.65712,-91.68893]}, + {"t":0.0583, "x":3.16606, "y":4.11924, "heading":-3.13859, "vx":-0.18846, "vy":-0.31935, "omega":0.20441, "ax":-3.23471, "ay":-5.48038, "alpha":3.41774, "fx":[-35.05447,-48.76489,-76.10991,-60.15695], "fy":[-103.94858,-98.19589,-78.97705,-91.75749]}, + {"t":0.08745, "x":3.15919, "y":4.1076, "heading":-3.13263, "vx":-0.28276, "vy":-0.47911, "omega":0.30404, "ax":-3.23647, "ay":-5.48261, "alpha":3.34823, "fx":[-35.39571,-49.10322,-75.72457,-59.98189], "fy":[-103.82247,-98.014,-79.33259,-91.86156]}, + {"t":0.11661, "x":3.14957, "y":4.0913, "heading":-3.12377, "vx":-0.3771, "vy":-0.63894, "omega":0.40165, "ax":-3.23839, "ay":-5.48507, "alpha":3.26951, "fx":[-35.76609,-49.52833,-75.28965,-59.75252], "fy":[-103.68361,-97.78521,-79.73,-91.9991]}, + {"t":0.14576, "x":3.1372, "y":4.07034, "heading":-3.11206, "vx":-0.47151, "vy":-0.79883, "omega":0.49696, "ax":-3.2405, "ay":-5.48778, "alpha":3.18023, "fx":[-36.18087,-50.03302,-74.79474,-59.4713], "fy":[-103.52602,-97.51149,-80.17722,-92.16769]}, + {"t":0.17491, "x":3.12208, "y":4.04473, "heading":-3.09757, "vx":-0.56597, "vy":-0.95881, "omega":0.58967, "ax":-3.24279, "ay":-5.49077, "alpha":3.07861, "fx":[-36.65933,-50.60854,-74.2264,-59.14124], "fy":[-103.34189,-97.1955,-80.68427,-92.36437]}, + {"t":0.20406, "x":3.1042, "y":4.01444, "heading":-3.08038, "vx":-0.6605, "vy":-1.11887, "omega":0.67941, "ax":-3.24525, "ay":-5.49408, "alpha":2.96223, "fx":[-37.22595,-51.24402,-73.56721,-58.76616], "fy":[-103.1209,-96.84093,-81.26373,-92.58552]}, + {"t":0.23321, "x":3.08357, "y":3.97949, "heading":-3.06058, "vx":-0.75511, "vy":-1.27903, "omega":0.76577, "ax":-3.2479, "ay":-5.49775, "alpha":2.82774, "fx":[-37.91228,-51.92585,-72.79417,-58.35097], "fy":[-102.8491,-96.45301,-81.9316,-92.82664]}, + {"t":0.26236, "x":3.06018, "y":3.93987, "heading":-3.03825, "vx":-0.84979, "vy":-1.4393, "omega":0.8482, "ax":-3.25071, "ay":-5.50181, "alpha":2.67038, "fx":[-38.75955,-52.63682,-71.87629,-57.90221], "fy":[-102.50727,-96.03918,-82.7085,-93.082]}, + {"t":0.29151, "x":3.03402, "y":3.89558, "heading":-3.01353, "vx":-0.94455, "vy":-1.59968, "omega":0.92604, "ax":-3.25369, "ay":-5.50632, "alpha":2.48331, "fx":[-39.82285,-53.35493,-70.7706,-57.42885], "fy":[-102.06807,-95.60989,-83.62166,-93.34413]}, + {"t":0.32066, "x":3.00511, "y":3.8466, "heading":-2.98653, "vx":-1.0394, "vy":-1.7602, "omega":0.99844, "ax":-3.25679, "ay":-5.51129, "alpha":2.25644, "fx":[-41.17756,-54.05178,-69.41526,-56.94365], "fy":[-101.49128,-95.17975,-84.7081,-93.60279]}, + {"t":0.34982, "x":2.97342, "y":3.79295, "heading":-2.95743, "vx":-1.13434, "vy":-1.92086, "omega":1.06421, "ax":-3.25995, "ay":-5.51666, "alpha":1.97449, "fx":[-42.93001,-54.69016,-67.71734,-56.46546], "fy":[-100.71512,-94.76913,-86.01983,-93.84334]}, + {"t":0.37897, "x":2.93897, "y":3.73461, "heading":-2.9264, "vx":-1.22937, "vy":-2.08168, "omega":1.12177, "ax":-3.26297, "ay":-5.52217, "alpha":1.61351, "fx":[-45.23544,-55.22014,-65.52963,-56.02374], "fy":[-99.63999,-94.40639,-87.63274,-94.04329]}, + {"t":0.40812, "x":2.90175, "y":3.67158, "heading":-2.8937, "vx":-1.32449, "vy":-2.24266, "omega":1.16881, "ax":-3.2654, "ay":-5.52704, "alpha":1.13433, "fx":[-48.32976,-55.57265,-62.60354,-55.66788], "fy":[-98.09546,-94.1313,-89.66168,-94.16502]}, + {"t":0.43727, "x":2.86175, "y":3.60385, "heading":-2.85963, "vx":-1.41968, "vy":-2.40378, "omega":1.20188, "ax":-3.26592, "ay":-5.52909, "alpha":0.46919, "fx":[-52.58744,-55.64784,-58.48493,-55.48926], "fy":[-95.76812,-94.00047,-92.28615,-94.13808]}, + {"t":0.46642, "x":2.81898, "y":3.53143, "heading":-2.82459, "vx":-1.51489, "vy":-2.56496, "omega":1.21555, "ax":-3.2608, "ay":-5.52213, "alpha":-0.50816, "fx":[-58.62775,-55.29294,-52.25758,-55.6825], "fy":[-92.02905,-94.09635,-95.78617,-93.80766]}, + {"t":0.49557, "x":2.77343, "y":3.45431, "heading":-2.78916, "vx":-1.60994, "vy":-2.72593, "omega":1.20074, "ax":-3.2384, "ay":-5.48643, "alpha":-2.05587, "fx":[-67.48692,-54.25692,-41.82871,-56.76416], "fy":[-85.47983,-94.54257,-100.52838,-92.73979]}, + {"t":0.52472, "x":2.72512, "y":3.37252, "heading":-2.75416, "vx":-1.70435, "vy":-2.88587, "omega":1.14081, "ax":-3.16386, "ay":-5.34318, "alpha":-4.76102, "fx":[-80.645,-52.09415,-21.76358,-60.76236], "fy":[-72.71082,-95.52662,-106.27219,-89.03451]}, + {"t":0.55387, "x":2.67409, "y":3.28612, "heading":-2.7209, "vx":-1.79658, "vy":-3.04163, "omega":1.00202, "ax":-3.10919, "ay":-4.49061, "alpha":-10.60776, "fx":[-97.21085,-48.0988,19.0455,-85.28129], "fy":[-47.215,-97.23104,-106.06385,-55.02634]}, + {"t":0.58303, "x":2.6204, "y":3.19554, "heading":-2.69169, "vx":-1.88721, "vy":-3.17254, "omega":0.69279, "ax":-2.99161, "ay":-4.06982, "alpha":-12.45004, "fx":[-96.81852,-45.52916,25.64857,-86.84694], "fy":[-44.79529,-97.25487,-102.89571,-31.95993]}, + {"t":0.61218, "x":2.56411, "y":3.10133, "heading":-2.67149, "vx":-1.97442, "vy":-3.29118, "omega":0.32985, "ax":-2.13652, "ay":-3.82205, "alpha":-11.04068, "fx":[-82.43415,-38.73218,20.47772,-44.67754], "fy":[-46.05676,-89.75982,-89.77055,-34.46069]}, + {"t":0.64133, "x":2.50565, "y":3.00377, "heading":-2.66188, "vx":-2.0367, "vy":-3.4026, "omega":0.008, "ax":0.32083, "ay":-0.24817, "alpha":-0.12696, "fx":[5.01355,5.31547,5.90054,5.59911], "fy":[-4.08265,-4.66678,-4.36006,-3.77589]}, + {"t":0.67048, "x":2.44641, "y":2.90447, "heading":-2.66165, "vx":-2.02735, "vy":-3.40983, "omega":0.0043, "ax":0.12592, "ay":-0.0749, "alpha":-0.00026, "fx":[2.14086,2.14149,2.14271,2.14208], "fy":[-1.27378,-1.275,-1.27436,-1.27314]}, + {"t":0.69963, "x":2.38737, "y":2.80504, "heading":-2.66152, "vx":-2.02368, "vy":-3.41202, "omega":0.00429, "ax":0.00829, "ay":-0.00492, "alpha":0.0, "fx":[0.14108,0.14109,0.14109,0.14109], "fy":[-0.08368,-0.08368,-0.08368,-0.08368]}, + {"t":0.72878, "x":2.32838, "y":2.70557, "heading":-2.66139, "vx":-2.02344, "vy":-3.41216, "omega":0.00429, "ax":-0.1026, "ay":0.0609, "alpha":0.00001, "fx":[-1.74512,-1.74515,-1.74521,-1.74518], "fy":[1.03595,1.03601,1.03598,1.03593]}, + {"t":0.75793, "x":2.26935, "y":2.60613, "heading":-2.66127, "vx":-2.02643, "vy":-3.41038, "omega":0.00429, "ax":-0.29691, "ay":0.17694, "alpha":0.00004, "fx":[-5.05024,-5.05033,-5.0505,-5.05041], "fy":[3.00972,3.00989,3.0098,3.00962]}, + {"t":0.78709, "x":2.21015, "y":2.50679, "heading":-2.66114, "vx":-2.03509, "vy":-3.40523, "omega":0.0043, "ax":-0.72306, "ay":0.43523, "alpha":0.00012, "fx":[-12.2987,-12.29899,-12.29955,-12.29927], "fy":[7.40296,7.40352,7.40321,7.40265]}, + {"t":0.81624, "x":2.15052, "y":2.4077, "heading":-2.66102, "vx":-2.05616, "vy":-3.39254, "omega":0.0043, "ax":-1.60856, "ay":0.99046, "alpha":0.00039, "fx":[-27.35987,-27.36064,-27.36245,-27.36168], "fy":[16.84713,16.84894,16.84782,16.84601]}, + {"t":0.84539, "x":2.08989, "y":2.30923, "heading":-2.66089, "vx":-2.10306, "vy":-3.36366, "omega":0.00431, "ax":-2.90209, "ay":1.86672, "alpha":0.00106, "fx":[-49.36084,-49.36182,-49.36677,-49.36579], "fy":[31.75197,31.75676,31.75265,31.74787]}, + {"t":0.87454, "x":2.02735, "y":2.21197, "heading":-2.66077, "vx":-2.18766, "vy":-3.30925, "omega":0.00434, "ax":-3.92513, "ay":2.69614, "alpha":0.00215, "fx":[-66.76048,-66.75961,-66.77019,-66.77106], "fy":[45.86151,45.87072,45.85953,45.85032]}, + {"t":0.90369, "x":1.96191, "y":2.11664, "heading":-2.66064, "vx":-2.30208, "vy":-3.23065, "omega":0.0044, "ax":-4.41039, "ay":3.28178, "alpha":0.00367, "fx":[-75.01208,-75.00734,-75.02682,-75.03156], "fy":[55.82615,55.84043,55.81807,55.80379]}, + {"t":0.93284, "x":1.89293, "y":2.02386, "heading":-2.66051, "vx":-2.43065, "vy":-3.13498, "omega":0.00451, "ax":-4.55507, "ay":3.70876, "alpha":0.00325, "fx":[-77.47386,-77.46825,-77.48702,-77.49264], "fy":[63.09006,63.1012,63.07997,63.06883]}, + {"t":0.96199, "x":1.82014, "y":1.93405, "heading":-2.66038, "vx":-2.56343, "vy":-3.02687, "omega":0.00461, "ax":-4.38264, "ay":3.88051, "alpha":0.02798, "fx":[-74.48432,-74.43998,-74.61064,-74.65517], "fy":[66.0526,66.13911,65.96045,65.87348]}, + {"t":0.98784, "x":1.75241, "y":1.85709, "heading":-2.66026, "vx":-2.67673, "vy":-2.92655, "omega":0.00533, "ax":-4.03628, "ay":3.98127, "alpha":0.32152, "fx":[-67.80558,-67.44722,-69.48983,-69.88135], "fy":[68.24529,69.11627,67.22391,66.29564]}, + {"t":1.0137, "x":1.68186, "y":1.78277, "heading":-2.66012, "vx":-2.78107, "vy":-2.82363, "omega":0.01364, "ax":-0.49257, "ay":5.11316, "alpha":9.13517, "fx":[49.66346,6.87629,-47.54531,-42.50858], "fy":[83.04805,101.3982,88.29235,75.15504]}, + {"t":1.03955, "x":1.6098, "y":1.71149, "heading":-2.65977, "vx":-2.7938, "vy":-2.69145, "omega":0.24979, "ax":2.95271, "ay":3.86702, "alpha":13.35963, "fx":[96.18937,44.10141,-27.61501,88.22323], "fy":[44.75094,97.35247,101.47574,19.52858]}, + {"t":1.0654, "x":1.53857, "y":1.6432, "heading":-2.65331, "vx":-2.71747, "vy":-2.59149, "omega":0.59515, "ax":3.57147, "ay":3.67581, "alpha":13.13097, "fx":[99.94699,53.01857,-11.86125,101.89473], "fy":[40.2595,94.17264,106.1343,9.53171]}, + {"t":1.09125, "x":1.46951, "y":1.57744, "heading":-2.63793, "vx":-2.62515, "vy":-2.49646, "omega":0.9346, "ax":4.14684, "ay":4.42975, "alpha":6.33186, "fx":[93.56252,62.43588,34.87453,91.27322], "fy":[54.65746,88.74615,101.9967,55.99463]}, + {"t":1.1171, "x":1.40303, "y":1.51438, "heading":-2.61377, "vx":-2.51795, "vy":-2.38195, "omega":1.09829, "ax":4.41406, "ay":4.52549, "alpha":2.93557, "fx":[86.81048,69.33888,60.23497,83.94332], "fy":[65.42479,83.79897,90.20678,68.4784]}, + {"t":1.14295, "x":1.33942, "y":1.45432, "heading":-2.58538, "vx":-2.40384, "vy":-2.26496, "omega":1.17418, "ax":4.52701, "ay":4.51151, "alpha":1.18299, "fx":[81.91967,74.10279,71.56018,80.42983], "fy":[71.7899,79.86193,82.01325,73.29268]}, + {"t":1.1688, "x":1.27879, "y":1.39727, "heading":-2.55502, "vx":-2.28681, "vy":-2.14833, "omega":1.20476, "ax":4.58216, "ay":4.48564, "alpha":0.11387, "fx":[78.42126,77.62062,77.45616,78.26659], "fy":[75.81298,76.63472,76.78917,75.96068]}, + {"t":1.19465, "x":1.2212, "y":1.34323, "heading":-2.52388, "vx":-2.16836, "vy":-2.03238, "omega":1.2077, "ax":4.6127, "ay":4.46128, "alpha":-0.61181, "fx":[75.87994,80.35254,80.90223,76.70813], "fy":[78.50728,73.91391,73.36858,77.75045]}, + {"t":1.2205, "x":1.16669, "y":1.29219, "heading":-2.49266, "vx":-2.04912, "vy":-1.91705, "omega":1.19188, "ax":4.63121, "ay":4.44028, "alpha":-1.14032, "fx":[74.00412,82.55104,83.07434,75.4724], "fy":[80.38848,71.57126,71.05791,79.09359]}, + {"t":1.24635, "x":1.11526, "y":1.24411, "heading":-2.46185, "vx":-1.92939, "vy":-1.80226, "omega":1.16241, "ax":4.64313, "ay":4.42247, "alpha":-1.54442, "fx":[72.60398,84.36531,84.51124,74.43293], "fy":[81.73968,69.52422,69.46178,80.17394]}, + {"t":1.27221, "x":1.06694, "y":1.199, "heading":-2.4318, "vx":-1.80936, "vy":-1.68794, "omega":1.12248, "ax":4.65116, "ay":4.40737, "alpha":-1.86435, "fx":[71.55316,85.88948,85.4907,73.52594], "fy":[82.72771,67.71749,68.34509,81.08195]}, + {"t":1.29806, "x":1.02172, "y":1.15684, "heading":-2.40278, "vx":-1.68913, "vy":-1.574, "omega":1.07429, "ax":4.65671, "ay":4.3945, "alpha":-2.12421, "fx":[70.76456,87.18649,86.16971,72.71647], "fy":[83.45721,66.1123,67.56058,81.86693]}, + {"t":1.32391, "x":0.97961, "y":1.11762, "heading":-2.37501, "vx":-1.56875, "vy":-1.4604, "omega":1.01937, "ax":4.66063, "ay":4.38348, "alpha":-2.33939, "fx":[70.17588,88.30058,86.64363,71.98405], "fy":[83.99746,64.68012,67.01154,82.55794]}, + {"t":1.34976, "x":0.94061, "y":1.08133, "heading":-2.34866, "vx":-1.44826, "vy":-1.34708, "omega":0.9589, "ax":4.66344, "ay":4.37398, "alpha":-2.52023, "fx":[69.74093,89.26423,86.97391,71.31611], "fy":[84.39657,63.39898,66.6318,83.17327]}, + {"t":1.37561, "x":0.90473, "y":1.04797, "heading":-2.32387, "vx":-1.32771, "vy":-1.23401, "omega":0.89375, "ax":4.66547, "ay":4.36574, "alpha":-2.67403, "fx":[69.42436,90.10216,87.20208,70.70453], "fy":[84.68937,62.2512,66.37444,83.72501]}, + {"t":1.40146, "x":0.87197, "y":1.01753, "heading":-2.30076, "vx":-1.2071, "vy":-1.12115, "omega":0.82462, "ax":4.66694, "ay":4.35855, "alpha":-2.80613, "fx":[69.19829,90.83374,87.35737,70.14389], "fy":[84.90212,61.22207,66.20519,84.2216]}, + {"t":1.42731, "x":0.84232, "y":0.99, "heading":-2.27945, "vx":-1.08646, "vy":-1.00848, "omega":0.75208, "ax":4.66801, "ay":4.35224, "alpha":-2.92057, "fx":[69.04025,91.47453,87.46107,69.63039], "fy":[85.05518,60.29904,66.09842,84.66913]}, + {"t":1.45316, "x":0.8158, "y":0.96538, "heading":-2.26001, "vx":-0.96578, "vy":-0.89597, "omega":0.67658, "ax":4.66879, "ay":4.34667, "alpha":-3.02052, "fx":[68.93171,92.03726,87.52916,69.1613], "fy":[85.16487,59.47114,66.03449,85.07221]}, + {"t":1.47901, "x":0.79239, "y":0.94367, "heading":-2.24251, "vx":-0.84509, "vy":-0.7836, "omega":0.5985, "ax":4.66936, "ay":4.34172, "alpha":-3.10847, "fx":[68.85717,92.53246,87.57389,68.73458], "fy":[85.24455,58.72876,65.99812,85.43438]}, + {"t":1.50486, "x":0.7721, "y":0.92487, "heading":-2.22704, "vx":-0.72438, "vy":-0.67136, "omega":0.51814, "ax":4.66977, "ay":4.33729, "alpha":-3.18647, "fx":[68.80352,92.96894,87.60489,68.34867], "fy":[85.30534,58.06337,65.9772,85.75847]}, + {"t":1.53072, "x":0.75494, "y":0.90896, "heading":-2.21365, "vx":-0.60366, "vy":-0.55924, "omega":0.43577, "ax":4.67006, "ay":4.3333, "alpha":-3.25619, "fx":[68.75957,93.35411,87.62982,68.00235], "fy":[85.35663,57.46742,65.96203,86.04673]}, + {"t":1.55657, "x":0.74089, "y":0.89595, "heading":-2.20238, "vx":-0.48294, "vy":-0.44722, "omega":0.35159, "ax":4.67026, "ay":4.32968, "alpha":-3.31902, "fx":[68.7157,93.6942,87.65489,67.69469], "fy":[85.40642,56.93426,65.94473,86.301]}, + {"t":1.58242, "x":0.72997, "y":0.88584, "heading":-2.19329, "vx":-0.36221, "vy":-0.33529, "omega":0.26579, "ax":4.67039, "ay":4.32637, "alpha":-3.37614, "fx":[68.66365,93.99446,87.68518,67.42495], "fy":[85.46155,56.4581,65.91882,86.52276]}, + {"t":1.60827, "x":0.72217, "y":0.87862, "heading":-2.18642, "vx":-0.24147, "vy":-0.22345, "omega":0.17851, "ax":4.67047, "ay":4.32332, "alpha":-3.42851, "fx":[68.59634,94.25927,87.72488,67.19262], "fy":[85.52784,56.03394,65.87895,86.71319]}, + {"t":1.63412, "x":0.71748, "y":0.87428, "heading":-2.18181, "vx":-0.12074, "vy":-0.11169, "omega":0.08988, "ax":4.67049, "ay":4.3205, "alpha":-3.47697, "fx":[68.50769,94.49225,87.77745,66.99735], "fy":[85.61021,55.65755,65.82064,86.87318]}, + {"t":1.65997, "x":0.71592, "y":0.87284, "heading":-2.17949, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/v2_redundancy/choreo/C_LEFT_PATH1.traj b/src/main/deploy/v2_redundancy/choreo/C_LEFT_PATH1.traj new file mode 100644 index 00000000..374e73c6 --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/C_LEFT_PATH1.traj @@ -0,0 +1,67 @@ +{ + "name":"C_LEFT_PATH1", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.142665386199951, "y":6.064190864562988, "heading":1.5707963267948966, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":5.227500915527344, "y":5.382014274597168, "heading":1.102853734231975, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":3.0}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"7.142665386199951 m", "val":7.142665386199951}, "y":{"exp":"6.064190864562988 m", "val":6.064190864562988}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"5.227500915527344 m", "val":5.227500915527344}, "y":{"exp":"5.382014274597168 m", "val":5.382014274597168}, "heading":{"exp":"1.102853734231975 rad", "val":1.102853734231975}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"3 m / s", "val":3.0}}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.14388], + "samples":[ + {"t":0.0, "x":7.14267, "y":6.06419, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.07535, "ay":-2.16461, "alpha":-0.55986, "fx":[-103.96916,-104.54507,-102.796,-102.04932], "fy":[-35.11041,-33.37658,-38.4328,-40.35796]}, + {"t":0.03813, "x":7.13825, "y":6.06262, "heading":1.5708, "vx":-0.23165, "vy":-0.08254, "omega":-0.02135, "ax":-6.07468, "ay":-2.16441, "alpha":-0.56671, "fx":[-103.96569,-104.54812,-102.77901,-102.02166], "fy":[-35.08543,-33.33199,-38.44844,-40.39787]}, + {"t":0.07626, "x":7.125, "y":6.0579, "heading":1.56998, "vx":-0.46327, "vy":-0.16506, "omega":-0.04296, "ax":-6.07389, "ay":-2.16416, "alpha":-0.57494, "fx":[-103.9605,-104.55224,-102.75969,-101.98791], "fy":[-35.05844,-33.27703,-38.46437,-40.44707]}, + {"t":0.11439, "x":7.10292, "y":6.05003, "heading":1.56834, "vx":-0.69487, "vy":-0.24758, "omega":-0.06488, "ax":-6.07291, "ay":-2.16386, "alpha":-0.58499, "fx":[-103.95329,-104.55762,-102.737,-101.9462], "fy":[-35.02795,-33.20863,-38.48143,-40.50828]}, + {"t":0.15252, "x":7.07201, "y":6.03902, "heading":1.56587, "vx":-0.92642, "vy":-0.33009, "omega":-0.08718, "ax":-6.0717, "ay":-2.16348, "alpha":-0.59756, "fx":[-103.9436,-104.56459,-102.70936,-101.89366], "fy":[-34.99174,-33.12224,-38.5009,-40.58561]}, + {"t":0.19065, "x":7.03227, "y":6.02486, "heading":1.56255, "vx":-1.15793, "vy":-0.41258, "omega":-0.10997, "ax":-6.07013, "ay":-2.16299, "alpha":-0.61373, "fx":[-103.93072,-104.57362,-102.6743,-101.82581], "fy":[-34.94628,-33.0107,-38.5248,-40.68549]}, + {"t":0.22878, "x":6.98371, "y":6.00755, "heading":1.55835, "vx":-1.38938, "vy":-0.49505, "omega":-0.13337, "ax":-6.06803, "ay":-2.16234, "alpha":-0.63529, "fx":[-103.91346,-104.58551,-102.62771,-101.73514], "fy":[-34.88564,-32.8621,-38.55647,-40.81864]}, + {"t":0.26691, "x":6.92632, "y":5.98711, "heading":1.55327, "vx":-1.62075, "vy":-0.5775, "omega":-0.15759, "ax":-6.06509, "ay":-2.16142, "alpha":-0.66549, "fx":[-103.88968,-104.6016,-102.56223,-101.60807], "fy":[-34.7991,-32.65507,-38.60192,-41.00434]}, + {"t":0.30503, "x":6.86012, "y":5.96352, "heading":1.54726, "vx":-1.85201, "vy":-0.65991, "omega":-0.18297, "ax":-6.06066, "ay":-2.16004, "alpha":-0.7108, "fx":[-103.85505,-104.62447,-102.46323,-101.41732], "fy":[-34.66507,-32.34709,-38.67312,-41.28107]}, + {"t":0.34316, "x":6.78509, "y":5.93678, "heading":1.54028, "vx":-2.0831, "vy":-0.74227, "omega":-0.21007, "ax":-6.05323, "ay":-2.15771, "alpha":-0.78631, "fx":[-103.79935,-104.65959,-102.29698,-101.09865], "fy":[-34.43269,-31.83964,-38.7976,-41.7384]}, + {"t":0.38129, "x":6.70127, "y":5.90691, "heading":1.53227, "vx":-2.3139, "vy":-0.82455, "omega":-0.24005, "ax":-6.03821, "ay":-2.153, "alpha":-0.93706, "fx":[-103.691,-104.72058,-101.9645,-100.4569], "fy":[-33.94749,-30.84161,-39.05574,-42.64302]}, + {"t":0.41942, "x":6.60865, "y":5.87391, "heading":1.52312, "vx":-2.54414, "vy":-0.90664, "omega":-0.27578, "ax":-5.99205, "ay":-2.13836, "alpha":-1.38517, "fx":[-103.36024,-104.84398,-100.99753,-98.49039], "fy":[-32.41771,-27.95378,-39.82187,-45.29842]}, + {"t":0.45755, "x":6.50729, "y":5.83778, "heading":1.51261, "vx":-2.77261, "vy":-0.98817, "omega":-0.32859, "ax":-1.39276, "ay":-0.44577, "alpha":-22.77719, "fx":[41.89701,-81.61998,-77.51021,22.47171], "fy":[65.40251,43.88496,-54.65635,-84.9607]}, + {"t":0.49568, "x":6.40056, "y":5.79978, "heading":1.50008, "vx":-2.82571, "vy":-1.00517, "omega":-1.19707, "ax":0.00411, "ay":-0.01321, "alpha":-20.06101, "fx":[55.79014,-48.29105,-55.45924,48.23971], "fy":[47.99473,55.44482,-48.5349,-55.80367]}, + {"t":0.53381, "x":6.29282, "y":5.76145, "heading":1.45443, "vx":-2.82556, "vy":-1.00567, "omega":-1.96199, "ax":-0.0015, "ay":0.0046, "alpha":-7.30239, "fx":[20.99868,-16.64812,-21.05808,16.60545], "fy":[16.70763,21.10409,-16.54594,-20.95262]}, + {"t":0.57194, "x":6.18508, "y":5.7231, "heading":1.37962, "vx":-2.82561, "vy":-1.0055, "omega":-2.24042, "ax":0.0046, "ay":-0.01329, "alpha":7.4473, "fx":[-22.56365,15.37358,22.74261,-15.23936], "fy":[-15.54232,-22.86931,15.0706,22.43649]}, + {"t":0.61007, "x":6.07735, "y":5.68475, "heading":1.2942, "vx":-2.82544, "vy":-1.00601, "omega":-1.95646, "ax":-0.00028, "ay":0.00251, "alpha":19.96237, "fx":[-64.02004,35.70858,63.98045,-35.68796], "fy":[-35.6438,-63.96932,35.75271,64.03114]}, + {"t":0.6482, "x":5.96961, "y":5.6464, "heading":1.2196, "vx":-2.82545, "vy":-1.00591, "omega":-1.19531, "ax":1.38358, "ay":0.47192, "alpha":22.69589, "fx":[-64.80192,69.32857,87.42025,2.19052], "fy":[-36.28161,-59.4983,37.67827,90.2106]}, + {"t":0.68633, "x":5.86289, "y":5.60839, "heading":1.17402, "vx":-2.77269, "vy":-0.98792, "omega":-0.32993, "ax":5.99296, "ay":2.13634, "alpha":1.3793, "fx":[102.19497,105.07849,102.1267,98.35425], "fy":[35.8889,26.90174,36.85692,45.70644]}, + {"t":0.72446, "x":5.76152, "y":5.57227, "heading":1.16144, "vx":-2.54419, "vy":-0.90646, "omega":-0.27734, "ax":6.0386, "ay":2.15192, "alpha":0.9382, "fx":[102.85445,104.90933,102.78287,100.31287], "fy":[36.39158,30.13973,36.85873,43.02381]}, + {"t":0.76259, "x":5.6689, "y":5.53927, "heading":1.15087, "vx":-2.31394, "vy":-0.82441, "omega":-0.24157, "ax":6.05346, "ay":2.15697, "alpha":0.78903, "fx":[103.06211,104.83107,103.01935,100.9583], "fy":[36.57319,31.23938,36.84292,42.1025]}, + {"t":0.80072, "x":5.58507, "y":5.50941, "heading":1.14166, "vx":-2.08312, "vy":-0.74216, "omega":-0.21148, "ax":6.06082, "ay":2.15947, "alpha":0.71418, "fx":[103.16073,104.7879,103.14369,101.27912], "fy":[36.67469,31.7919,36.8243,41.63729]}, + {"t":0.83885, "x":5.51005, "y":5.48268, "heading":1.13359, "vx":-1.85203, "vy":-0.65982, "omega":-0.18425, "ax":6.06521, "ay":2.16097, "alpha":0.66922, "fx":[103.21691,104.76073,103.22148,101.47097], "fy":[36.74269,32.12407,36.8062,41.35669]}, + {"t":0.87697, "x":5.44384, "y":5.45909, "heading":1.12657, "vx":-1.62077, "vy":-0.57743, "omega":-0.15873, "ax":6.06813, "ay":2.16196, "alpha":0.63925, "fx":[103.25254,104.7421,103.2752,101.59861], "fy":[36.79254,32.34577,36.78975,41.16896]}, + {"t":0.9151, "x":5.38646, "y":5.43864, "heading":1.12052, "vx":-1.38939, "vy":-0.49499, "omega":-0.13436, "ax":6.0702, "ay":2.16266, "alpha":0.61784, "fx":[103.27695,104.72852,103.31463,101.68967], "fy":[36.83079,32.50429,36.77544,41.0345]}, + {"t":0.95323, "x":5.33789, "y":5.42134, "heading":1.11539, "vx":-1.15794, "vy":-0.41253, "omega":-0.1108, "ax":6.07176, "ay":2.16319, "alpha":0.60179, "fx":[103.29476,104.71818,103.34471,101.75789], "fy":[36.86072,32.6233,36.76346,40.93345]}, + {"t":0.99136, "x":5.29815, "y":5.40719, "heading":1.11117, "vx":-0.92643, "vy":-0.33005, "omega":-0.08785, "ax":6.07297, "ay":2.1636, "alpha":0.5893, "fx":[103.30851,104.71004,103.36823,101.81091], "fy":[36.88416,32.71596,36.75395,40.85474]}, + {"t":1.02949, "x":5.26725, "y":5.39617, "heading":1.10782, "vx":-0.69487, "vy":-0.24756, "omega":-0.06538, "ax":6.07393, "ay":2.16393, "alpha":0.57932, "fx":[103.31974,104.70345,103.38685,101.85327], "fy":[36.90222,32.79017,36.74694,40.79176]}, + {"t":1.06762, "x":5.24517, "y":5.38831, "heading":1.10533, "vx":-0.46328, "vy":-0.16505, "omega":-0.0433, "ax":6.07472, "ay":2.16419, "alpha":0.57115, "fx":[103.32941,104.69802,103.40166,101.88787], "fy":[36.9156,32.85095,36.74248,40.74027]}, + {"t":1.10575, "x":5.23192, "y":5.38359, "heading":1.10367, "vx":-0.23165, "vy":-0.08253, "omega":-0.02152, "ax":6.07538, "ay":2.16442, "alpha":0.56435, "fx":[103.33816,104.69346,103.41337,101.91664], "fy":[36.9248,32.90164,36.74056,40.69746]}, + {"t":1.14388, "x":5.2275, "y":5.38201, "heading":1.10285, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/v2_redundancy/choreo/C_LEFT_PATH2.traj b/src/main/deploy/v2_redundancy/choreo/C_LEFT_PATH2.traj new file mode 100644 index 00000000..67944916 --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/C_LEFT_PATH2.traj @@ -0,0 +1,188 @@ +{ + "name":"C_LEFT_PATH2", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":5.281756401062012, "y":5.087327480316162, "heading":1.0513369818883893, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":4.582683086395264, "y":5.628561973571777, "heading":0.0, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":3.5206298828125, "y":5.799249172210693, "heading":0.0, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":1.73851478099823, "y":6.708444118499756, "heading":2.216612130911823, "intervals":18, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.0347819328308103, "y":7.59406852722168, "heading":2.216612130911823, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.7602181434631348, "y":6.701209545135498, "heading":2.216612130911823, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":3.4258036613464355, "y":5.675975322723389, "heading":2.09887087685183, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":3.0}}, "enabled":true}, + {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":3, "to":4, "data":{"type":"MaxVelocity", "props":{"max":2.0}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"5.281756401062012 m", "val":5.281756401062012}, "y":{"exp":"5.087327480316162 m", "val":5.087327480316162}, "heading":{"exp":"1.0513369818883893 rad", "val":1.0513369818883893}, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"4.582683086395264 m", "val":4.582683086395264}, "y":{"exp":"5.628561973571777 m", "val":5.628561973571777}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"3.5206298828125 m", "val":3.5206298828125}, "y":{"exp":"5.799249172210693 m", "val":5.799249172210693}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"1.73851478099823 m", "val":1.73851478099823}, "y":{"exp":"6.708444118499756 m", "val":6.708444118499756}, "heading":{"exp":"2.216612130911823 rad", "val":2.216612130911823}, "intervals":18, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.0347819328308105 m", "val":1.0347819328308103}, "y":{"exp":"7.59406852722168 m", "val":7.59406852722168}, "heading":{"exp":"2.216612130911823 rad", "val":2.216612130911823}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.7602181434631348 m", "val":1.7602181434631348}, "y":{"exp":"6.701209545135498 m", "val":6.701209545135498}, "heading":{"exp":"2.216612130911823 rad", "val":2.216612130911823}, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"3.4258036613464355 m", "val":3.4258036613464355}, "y":{"exp":"5.675975322723389 m", "val":5.675975322723389}, "heading":{"exp":"2.09887087685183 rad", "val":2.09887087685183}, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"3 m / s", "val":3.0}}}, "enabled":true}, + {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":3, "to":4, "data":{"type":"MaxVelocity", "props":{"max":{"exp":"2 m / s", "val":2.0}}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.53094,0.89279,1.58918,2.31195,2.92887,3.8144], + "samples":[ + {"t":0.0, "x":5.28176, "y":5.08733, "heading":1.05134, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-4.55618, "ay":4.56195, "alpha":0.2017, "fx":[-78.40073,-78.02431,-76.58228,-76.99006], "fy":[76.69549,77.0735,78.50784,78.11275]}, + {"t":0.02413, "x":5.28043, "y":5.08866, "heading":1.05134, "vx":-0.10996, "vy":0.1101, "omega":0.00487, "ax":-4.58632, "ay":4.5308, "alpha":0.20633, "fx":[-78.92408,-78.55165,-77.08355,-77.4887], "fy":[76.14281,76.52164,78.00173,77.60444]}, + {"t":0.04827, "x":5.27644, "y":5.09263, "heading":1.05145, "vx":-0.22064, "vy":0.21944, "omega":0.00985, "ax":-4.61958, "ay":4.49594, "alpha":0.21147, "fx":[-79.50115,-79.13353,-77.63716,-78.039], "fy":[75.5244,75.90368,77.43506,77.03572]}, + {"t":0.0724, "x":5.26977, "y":5.09924, "heading":1.05169, "vx":-0.33213, "vy":0.32795, "omega":0.01495, "ax":-4.65646, "ay":4.45667, "alpha":0.2172, "fx":[-80.14045,-79.77872,-78.25159,-78.64925], "fy":[74.82801,75.20716,76.79645,76.39535]}, + {"t":0.09653, "x":5.2604, "y":5.10845, "heading":1.05205, "vx":-0.44451, "vy":0.4355, "omega":0.02019, "ax":-4.69757, "ay":4.41211, "alpha":0.22363, "fx":[-80.85234,-80.49788,-78.93723,-79.32955], "fy":[74.03819,74.41633,76.07149,75.66915]}, + {"t":0.12067, "x":5.2483, "y":5.12025, "heading":1.05254, "vx":-0.55788, "vy":0.54198, "omega":0.02559, "ax":-4.74365, "ay":4.36114, "alpha":0.23091, "fx":[-81.64948,-81.30412,-79.70692,-80.09232], "fy":[73.13521,73.51104,75.2417,74.83899]}, + {"t":0.1448, "x":5.23346, "y":5.1346, "heading":1.05316, "vx":-0.67236, "vy":0.64723, "omega":0.03116, "ax":-4.79566, "ay":4.30229, "alpha":0.23919, "fx":[-82.54757,-82.21372,-80.57663,-80.953], "fy":[72.0935,72.46505,74.28306,73.88136]}, + {"t":0.16894, "x":5.21583, "y":5.15147, "heading":1.05391, "vx":-0.7881, "vy":0.75106, "omega":0.03693, "ax":-4.85474, "ay":4.23364, "alpha":0.2487, "fx":[-83.56616,-83.24702,-81.5665,-81.93099], "fy":[70.87933,71.24368,73.16378,72.76523]}, + {"t":0.19307, "x":5.1954, "y":5.17083, "heading":1.0548, "vx":-0.90526, "vy":0.85324, "omega":0.04294, "ax":-4.92237, "ay":4.15259, "alpha":0.25973, "fx":[-84.72984,-84.42971,-82.7021,-83.05082], "fy":[69.4474,69.80016,71.84092,71.44888]}, + {"t":0.2172, "x":5.17212, "y":5.19263, "heading":1.05584, "vx":-1.02406, "vy":0.95346, "omega":0.0492, "ax":-5.00044, "ay":4.05557, "alpha":0.27265, "fx":[-86.06972,-85.79444,-84.01634,-84.34391], "fy":[67.73562,68.07008,70.25528,69.87503]}, + {"t":0.24134, "x":5.14595, "y":5.21682, "heading":1.05702, "vx":-1.14474, "vy":1.05133, "omega":0.05579, "ax":-5.09137, "ay":3.93754, "alpha":0.28799, "fx":[-87.62535,-87.38286,-85.5518,-85.85072], "fy":[65.65679,65.96253,68.32305,67.96304]}, + {"t":0.26547, "x":5.11684, "y":5.24334, "heading":1.05837, "vx":-1.26761, "vy":1.14636, "omega":0.06274, "ax":-5.19824, "ay":3.79121, "alpha":0.30646, "fx":[-89.44683,-89.24804,-87.36388,-87.6236], "fy":[63.08515,63.34559,65.92229,65.59625]}, + {"t":0.2896, "x":5.08473, "y":5.27211, "heading":1.05989, "vx":-1.39306, "vy":1.23785, "omega":0.07013, "ax":-5.325, "ay":3.60567, "alpha":0.32903, "fx":[-91.59651,-91.45634,-89.52422,-89.72984], "fy":[59.83385,60.02188,62.86953,62.60047]}, + {"t":0.31374, "x":5.04956, "y":5.30303, "heading":1.06158, "vx":-1.52157, "vy":1.32487, "omega":0.07807, "ax":-5.47644, "ay":3.36405, "alpha":0.35714, "fx":[-94.14798,-94.08632,-92.12288,-92.2535], "fy":[55.61594,55.6857,58.87848,58.70621]}, + {"t":0.33787, "x":5.01125, "y":5.33599, "heading":1.06346, "vx":-1.65374, "vy":1.40606, "omega":0.08669, "ax":-5.6577, "ay":3.03922, "alpha":0.39278, "fx":[-97.17466,-97.21589,-95.26258,-95.29022], "fy":[49.97493,49.84608,53.48391,53.48004]}, + {"t":0.36201, "x":4.96969, "y":5.37081, "heading":1.06555, "vx":-1.79028, "vy":1.47941, "omega":0.09617, "ax":-5.87183, "ay":2.58591, "alpha":0.43877, "fx":[-100.7047,-100.87033,-99.02238,-98.91548], "fy":[42.16046,41.68745,45.898,46.19666]}, + {"t":0.38614, "x":4.92477, "y":5.40726, "heading":1.06788, "vx":-1.93199, "vy":1.54182, "omega":0.10676, "ax":-6.11105, "ay":1.92682, "alpha":0.49864, "fx":[-104.57032,-104.84527,-103.31231,-103.06063], "fy":[30.9164,29.83196,34.74534,35.6049]}, + {"t":0.41027, "x":4.87637, "y":5.44503, "heading":1.07045, "vx":-2.07947, "vy":1.58832, "omega":0.11879, "ax":-6.32803, "ay":0.93327, "alpha":0.57471, "fx":[-107.94554,-108.15732,-107.36303,-107.08625], "fy":[14.21243,12.05424,17.66384,19.56833]}, + {"t":0.43441, "x":4.82434, "y":5.48364, "heading":1.07332, "vx":-2.23219, "vy":1.61084, "omega":0.13266, "ax":-6.35781, "ay":-0.56658, "alpha":0.65987, "fx":[-108.16396,-107.6649,-108.22585,-108.52316], "fy":[-10.55171,-14.34876,-8.65071,-4.99838]}, + {"t":0.45854, "x":4.76862, "y":5.52235, "heading":1.07652, "vx":-2.38563, "vy":1.59717, "omega":0.14859, "ax":-5.81875, "ay":-2.59575, "alpha":0.71758, "fx":[-99.34949,-96.84337,-98.68147,-101.02688], "fy":[-43.62222,-48.81464,-44.78814,-39.38684]}, + {"t":0.48267, "x":4.70935, "y":5.56014, "heading":1.08011, "vx":-2.52606, "vy":1.53452, "omega":0.16591, "ax":-4.43028, "ay":-4.57797, "alpha":0.68649, "fx":[-77.08758,-72.30962,-73.531,-78.50292], "fy":[-76.319,-80.82924,-79.59516,-74.73655]}, + {"t":0.50681, "x":4.64709, "y":5.59584, "heading":1.08411, "vx":-2.63298, "vy":1.42404, "omega":0.18247, "ax":-2.97641, "ay":-5.64416, "alpha":0.57431, "fx":[-53.18367,-48.11355,-47.93239,-53.28169], "fy":[-94.69912,-97.37316,-97.38538,-94.56461]}, + {"t":0.53094, "x":4.58268, "y":5.62856, "heading":1.08851, "vx":-2.70481, "vy":1.28782, "omega":0.19633, "ax":-2.71508, "ay":-5.73256, "alpha":0.54224, "fx":[-48.73577,-43.8723,-43.50216,-48.62057], "fy":[-96.3511,-98.66465,-98.72172,-96.29924]}, + {"t":0.54668, "x":4.53979, "y":5.64811, "heading":1.0916, "vx":-2.74753, "vy":1.19763, "omega":0.20487, "ax":-2.44834, "ay":-5.83501, "alpha":0.58796, "fx":[-44.56455,-39.22469,-38.57364,-44.21915], "fy":[-98.08233,-100.34697,-100.47183,-98.10651]}, + {"t":0.56241, "x":4.49626, "y":5.66623, "heading":1.09483, "vx":-2.78604, "vy":1.10583, "omega":0.21412, "ax":-2.23697, "ay":-5.89966, "alpha":0.64166, "fx":[-41.35024,-35.49242,-34.56752,-40.7907], "fy":[-99.16274,-101.42335,-101.58763,-99.23264]}, + {"t":0.57814, "x":4.45216, "y":5.6829, "heading":1.09819, "vx":-2.82124, "vy":1.01302, "omega":0.22421, "ax":-2.03176, "ay":-5.94968, "alpha":0.70569, "fx":[-38.2984,-31.84595,-30.60114,-37.49313], "fy":[-99.99774,-102.26129,-102.44935,-100.10107]}, + {"t":0.59387, "x":4.40752, "y":5.6981, "heading":1.10172, "vx":-2.8532, "vy":0.91941, "omega":0.23531, "ax":-1.8259, "ay":-5.98678, "alpha":0.78312, "fx":[-35.31447,-28.16727,-26.53485,-34.21579], "fy":[-100.62044,-102.88907,-103.08098,-100.74322]}, + {"t":0.60961, "x":4.3624, "y":5.71183, "heading":1.10542, "vx":-2.88193, "vy":0.82522, "omega":0.24763, "ax":-1.61906, "ay":-6.00931, "alpha":0.87827, "fx":[-32.41607,-24.44495,-22.33558,-30.9626], "fy":[-101.00599,-103.28343,-103.44956,-101.12754]}, + {"t":0.62534, "x":4.31686, "y":5.72407, "heading":1.10932, "vx":-2.9074, "vy":0.73068, "omega":0.26145, "ax":-1.41174, "ay":-6.01442, "alpha":0.99743, "fx":[-29.64368,-20.67928,-17.97376,-27.75643], "fy":[-101.11089,-103.40499,-103.49966,-101.19897]}, + {"t":0.64107, "x":4.27095, "y":5.73482, "heading":1.11343, "vx":-2.92961, "vy":0.63606, "omega":0.27714, "ax":-1.20468, "ay":-5.99779, "alpha":1.15008, "fx":[-27.0556,-16.87123,-13.40659,-24.63138], "fy":[-100.86945,-103.19576,-103.14604,-100.8717]}, + {"t":0.6568, "x":4.22471, "y":5.74408, "heading":1.11779, "vx":-2.94856, "vy":0.5417, "omega":0.29524, "ax":-0.99891, "ay":-5.95259, "alpha":1.35111, "fx":[-24.73641,-13.02125,-8.56833,-21.63839], "fy":[-100.17952,-102.56828,-102.25294,-100.00646]}, + {"t":0.67254, "x":4.1782, "y":5.75187, "heading":1.12244, "vx":-2.96428, "vy":0.44805, "omega":0.31649, "ax":-0.79594, "ay":-5.86749, "alpha":1.62518, "fx":[-22.81302,-9.12898,-3.35505,-18.85759], "fy":[-98.87494,-101.3857,-100.59285,-98.36349]}, + {"t":0.68827, "x":4.13146, "y":5.75819, "heading":1.12742, "vx":-2.9768, "vy":0.35574, "omega":0.34206, "ax":-0.59813, "ay":-5.72249, "alpha":2.01596, "fx":[-21.48299,-5.19267,2.4031,-16.42329], "fy":[-96.67013,-99.42416,-97.75994,-95.49758]}, + {"t":0.704, "x":4.08455, "y":5.76308, "heading":1.1328, "vx":-2.98621, "vy":0.26571, "omega":0.37378, "ax":-0.40942, "ay":-5.47917, "alpha":2.60803, "fx":[-21.06588,-1.20709,8.99363,-14.57719], "fy":[-93.03908,-96.29627,-92.96882,-90.49231]}, + {"t":0.71973, "x":4.03752, "y":5.76658, "heading":1.13868, "vx":-2.99265, "vy":0.17951, "omega":0.41481, "ax":-0.23698, "ay":-5.05429, "alpha":3.58663, "fx":[-22.09485,2.84527,16.91134,-13.78545], "fy":[-86.92042,-91.27699,-84.52569,-81.16524]}, + {"t":0.73547, "x":3.99041, "y":5.76878, "heading":1.14521, "vx":-2.99638, "vy":0.09999, "omega":0.47124, "ax":-0.09505, "ay":-4.23463, "alpha":5.42677, "fx":[-25.45484,7.02708,26.87789,-14.91729], "fy":[-75.88806,-82.8334,-68.23925,-61.15861]}, + {"t":0.7512, "x":3.94326, "y":5.76983, "heading":1.15262, "vx":-2.99788, "vy":0.03337, "omega":0.55661, "ax":-0.01201, "ay":-2.43816, "alpha":9.14852, "fx":[-32.37343,11.39798,37.83964,-17.68165], "fy":[-53.43893,-66.97644,-33.27863,-12.19528]}, + {"t":0.76693, "x":3.89609, "y":5.77005, "heading":1.16138, "vx":-2.99807, "vy":-0.00499, "omega":0.70055, "ax":0.0, "ay":0.52928, "alpha":11.14004, "fx":[-39.08927,16.02587,37.37673,-14.31361], "fy":[-4.96443,-29.73889,24.76553,45.94973]}, + {"t":0.78267, "x":3.84892, "y":5.77004, "heading":1.1724, "vx":-2.99807, "vy":0.00333, "omega":0.87581, "ax":0.03267, "ay":3.28534, "alpha":6.6929, "fx":[-30.06523,15.39098,26.24032,-9.34329], "fy":[49.85421,38.03266,63.38206,72.26204]}, + {"t":0.7984, "x":3.80176, "y":5.7705, "heading":1.18618, "vx":-2.99755, "vy":0.05502, "omega":0.9811, "ax":0.14267, "ay":4.64013, "alpha":3.6217, "fx":[-17.1606,12.2155,19.3603,-4.70817], "fy":[76.61382,72.93218,81.03837,85.12456]}, + {"t":0.81413, "x":3.75462, "y":5.77194, "heading":1.20161, "vx":-2.99531, "vy":0.12802, "omega":1.03808, "ax":0.29939, "ay":5.26613, "alpha":2.22518, "fx":[-7.71127,11.88424,16.54909,-0.35209], "fy":[88.89097,86.9038,90.06756,92.43939]}, + {"t":0.82986, "x":3.70753, "y":5.7746, "heading":1.21794, "vx":-2.9906, "vy":0.21087, "omega":1.07309, "ax":0.47977, "ay":5.60257, "alpha":1.48946, "fx":[-0.56192,13.18502,16.1596,3.86044], "fy":[95.29823,93.79,95.2105,96.89398]}, + {"t":0.8456, "x":3.66054, "y":5.77861, "heading":1.23483, "vx":-2.98305, "vy":0.29902, "omega":1.09652, "ax":0.67301, "ay":5.79837, "alpha":1.05533, "fx":[5.29998,15.33251,17.18474,7.9733], "fy":[98.91582,97.61187,98.31328,99.67333]}, + {"t":0.86133, "x":3.61369, "y":5.78404, "heading":1.25208, "vx":-2.97246, "vy":0.39024, "omega":1.11313, "ax":0.87529, "ay":5.91438, "alpha":0.77865, "fx":[10.4424,17.98559,19.09136,12.03404], "fy":[101.00098,99.82322,100.20231,101.38113]}, + {"t":0.87706, "x":3.56704, "y":5.79091, "heading":1.26959, "vx":-2.95869, "vy":0.48329, "omega":1.12538, "ax":1.14546, "ay":5.96835, "alpha":0.59209, "fx":[16.23652,22.03289,22.58284,17.08387], "fy":[101.97628,100.83953,101.07714,102.18684]}, + {"t":0.89279, "x":3.52063, "y":5.79925, "heading":1.2873, "vx":-2.94067, "vy":0.57719, "omega":1.13469, "ax":1.26649, "ay":6.06002, "alpha":0.55482, "fx":[18.54729,24.07227,24.40195,19.14926], "fy":[103.58933,102.42655,102.58741,103.71326]}, + {"t":0.91681, "x":3.45038, "y":5.81486, "heading":1.31454, "vx":-2.91026, "vy":0.72271, "omega":1.14802, "ax":1.60581, "ay":5.8604, "alpha":0.69501, "fx":[23.91573,30.67583,30.51123,24.15445], "fy":[100.39735,98.54759,99.02736,100.76235]}, + {"t":0.94082, "x":3.38096, "y":5.8339, "heading":1.34211, "vx":-2.8717, "vy":0.86344, "omega":1.16471, "ax":1.82416, "ay":5.58939, "alpha":0.91158, "fx":[26.99551,35.51866,34.75188,26.84766], "fy":[95.93902,93.20493,94.33449,96.81721]}, + {"t":0.96483, "x":3.31252, "y":5.85625, "heading":1.37008, "vx":-2.82789, "vy":0.99766, "omega":1.1866, "ax":1.949, "ay":5.16017, "alpha":1.26801, "fx":[28.13294,39.23392,37.67748,27.56347], "fy":[88.60788,84.64817,87.18933,90.64685]}, + {"t":0.98885, "x":3.24518, "y":5.88169, "heading":1.39857, "vx":-2.78109, "vy":1.12157, "omega":1.21705, "ax":1.88538, "ay":4.42806, "alpha":1.87127, "fx":[25.45825,40.1628,37.89474,24.76335], "fy":[75.35536,70.07014,75.70201,80.15295]}, + {"t":1.01286, "x":3.17894, "y":5.9099, "heading":1.4278, "vx":-2.73582, "vy":1.2279, "omega":1.26198, "ax":1.50187, "ay":3.22298, "alpha":2.72767, "fx":[16.79581,35.06811,33.25657,17.06479], "fy":[52.03664,46.8168,57.94681,62.48784]}, + {"t":1.03687, "x":3.11368, "y":5.94032, "heading":1.4581, "vx":-2.69975, "vy":1.3053, "omega":1.32748, "ax":0.89221, "ay":1.80808, "alpha":3.16756, "fx":[5.70859,23.91435,23.90427,7.17793], "fy":[24.62349,21.67284,36.85263,39.87051]}, + {"t":1.06089, "x":3.0491, "y":5.97218, "heading":1.48998, "vx":-2.67833, "vy":1.34871, "omega":1.40354, "ax":0.42474, "ay":0.83565, "alpha":2.70936, "fx":[-0.46478,13.99816,14.66682,0.69861], "fy":[7.9457,6.65778,20.41489,21.83801]}, + {"t":1.0849, "x":2.98491, "y":6.00481, "heading":1.52368, "vx":-2.66813, "vy":1.36878, "omega":1.46861, "ax":0.18551, "ay":0.36016, "alpha":1.98633, "fx":[-2.26275,8.11964,8.51755,-1.75234], "fy":[1.23593,0.74083,10.99447,11.53367]}, + {"t":1.10891, "x":2.92089, "y":6.03778, "heading":1.55895, "vx":-2.66367, "vy":1.37743, "omega":1.5163, "ax":0.07901, "ay":0.15251, "alpha":1.35037, "fx":[-2.20753,4.81625,4.88462,-2.11779], "fy":[-0.86855,-0.95039,6.05168,6.14391]}, + {"t":1.13293, "x":2.85695, "y":6.0709, "heading":1.59536, "vx":-2.66177, "vy":1.38109, "omega":1.54873, "ax":0.03354, "ay":0.06459, "alpha":0.84379, "fx":[-1.56607,2.81529,2.70552,-1.67244], "fy":[-1.14491,-1.03677,3.34128,3.23513]}, + {"t":1.15694, "x":2.79304, "y":6.10409, "heading":1.63255, "vx":-2.66097, "vy":1.38264, "omega":1.56899, "ax":0.01458, "ay":0.02804, "alpha":0.44167, "fx":[-0.82566,1.46318,1.32142,-0.96703], "fy":[-0.73813,-0.59653,1.69192,1.55059]}, + {"t":1.18095, "x":2.72915, "y":6.1373, "heading":1.67023, "vx":-2.66062, "vy":1.38332, "omega":1.5796, "ax":0.00712, "ay":0.01369, "alpha":0.10949, "fx":[-0.1335,0.43214,0.37571,-0.18992], "fy":[-0.0782,-0.02177,0.54386,0.48744]}, + {"t":1.20497, "x":2.66526, "y":6.17052, "heading":1.70816, "vx":-2.66045, "vy":1.38365, "omega":1.58223, "ax":0.00515, "ay":0.0099, "alpha":-0.18803, "fx":[0.50426,-0.46271,-0.32905,0.63794], "fy":[0.71876,0.5851,-0.38188,-0.24821]}, + {"t":1.22898, "x":2.60138, "y":6.20375, "heading":1.74616, "vx":-2.66032, "vy":1.38388, "omega":1.57771, "ax":0.00704, "ay":0.01353, "alpha":-0.48639, "fx":[1.14256,-1.34378,-0.90332,1.58321], "fy":[1.69352,1.25309,-1.23344,-0.79281]}, + {"t":1.25299, "x":2.5375, "y":6.23698, "heading":1.78404, "vx":-2.66016, "vy":1.38421, "omega":1.56603, "ax":0.01425, "ay":0.02738, "alpha":-0.82223, "fx":[1.87638,-2.29524,-1.39223,2.78036], "fy":[3.00306,2.10036,-2.07229,-1.16835]}, + {"t":1.27701, "x":2.47362, "y":6.27023, "heading":1.82165, "vx":-2.65981, "vy":1.38487, "omega":1.54629, "ax":0.03253, "ay":0.06244, "alpha":-1.23421, "fx":[2.86016,-3.34489,-1.7559,4.45368], "fy":[4.95873,3.37228,-2.83788,-1.24466]}, + {"t":1.30102, "x":2.40976, "y":6.3035, "heading":1.85878, "vx":-2.65903, "vy":1.38636, "omega":1.51665, "ax":0.07639, "ay":0.14629, "alpha":-1.76195, "fx":[4.37901,-4.38405,-1.78995,6.99221], "fy":[8.16054,5.58502,-3.20078,-0.59143]}, + {"t":1.32503, "x":2.34593, "y":6.33684, "heading":1.8952, "vx":-2.6572, "vy":1.38988, "omega":1.47434, "ax":0.18003, "ay":0.34291, "alpha":-2.43574, "fx":[7.00627,-4.9553,-0.91839,11.11642], "fy":[13.77439,9.8648,-2.18711,1.8789]}, + {"t":1.34905, "x":2.28217, "y":6.37031, "heading":1.9306, "vx":-2.65288, "vy":1.39811, "omega":1.41585, "ax":0.41914, "ay":0.78847, "alpha":-3.2145, "fx":[11.82875,-3.74639,2.31574,18.11998], "fy":[23.81875,18.55452,2.69333,8.57975]}, + {"t":1.37306, "x":2.21859, "y":6.40411, "heading":1.9646, "vx":-2.64281, "vy":1.41705, "omega":1.33866, "ax":0.92296, "ay":1.68983, "alpha":-3.72548, "fx":[20.16047,2.17806,11.0877,29.37094], "fy":[40.04659,35.02602,16.66995,23.23146]}, + {"t":1.39707, "x":2.15539, "y":6.43863, "heading":1.99675, "vx":-2.62065, "vy":1.45762, "omega":1.2492, "ax":1.72392, "ay":2.98758, "alpha":-3.22779, "fx":[31.4872,15.51239,27.46891,42.82512], "fy":[59.06549,57.39507,41.97319,44.83808]}, + {"t":1.42109, "x":2.09296, "y":6.47449, "heading":2.02674, "vx":-2.57925, "vy":1.52937, "omega":1.17169, "ax":5.10723, "ay":1.12859, "alpha":-1.55307, "fx":[86.17129,84.14589,87.62962,89.5433], "fy":[26.92443,23.99824,10.76308,15.10224]}, + {"t":1.4451, "x":2.03249, "y":6.51154, "heading":2.05488, "vx":-2.45661, "vy":1.55647, "omega":1.13439, "ax":5.80476, "ay":-2.3769, "alpha":-0.27846, "fx":[99.47599,98.62474,97.98566,98.86296], "fy":[-38.59114,-40.57506,-42.25772,-40.29796]}, + {"t":1.46911, "x":1.97518, "y":6.54823, "heading":2.08212, "vx":-2.31722, "vy":1.49939, "omega":1.12771, "ax":5.77747, "ay":-2.65871, "alpha":-0.18267, "fx":[98.81334,98.17076,97.72843,98.38019], "fy":[-44.03366,-45.40716,-46.40658,-45.04812]}, + {"t":1.49313, "x":1.9212, "y":6.58347, "heading":2.1092, "vx":-2.17848, "vy":1.43555, "omega":1.12332, "ax":5.76449, "ay":-2.7608, "alpha":-0.15035, "fx":[98.51143,97.94986,97.59048,98.15724], "fy":[-45.99077,-47.15406,-47.92425,-46.77281]}, + {"t":1.51714, "x":1.87055, "y":6.61715, "heading":2.13618, "vx":-2.04006, "vy":1.36925, "omega":1.11971, "ax":5.75711, "ay":-2.8135, "alpha":-0.13486, "fx":[98.3438,97.82058,97.508,98.03466], "fy":[-46.99497,-48.06133,-48.7135,-47.65766]}, + {"t":1.54115, "x":1.82322, "y":6.64922, "heading":2.16306, "vx":-1.90181, "vy":1.30169, "omega":1.11647, "ax":5.75237, "ay":-2.84568, "alpha":-0.12608, "fx":[98.23765,97.73437,97.45345,97.95913], "fy":[-47.60555,-48.62107,-49.19775,-48.19214]}, + {"t":1.56517, "x":1.77921, "y":6.67965, "heading":2.18987, "vx":-1.76367, "vy":1.23335, "omega":1.11344, "ax":5.74907, "ay":-2.86737, "alpha":-0.12058, "fx":[98.16428,97.67166,97.41494,97.90922], "fy":[-48.01636,-49.00361,-49.52495,-48.54734]}, + {"t":1.58918, "x":1.73851, "y":6.70844, "heading":2.21661, "vx":-1.62562, "vy":1.1645, "omega":1.11055, "ax":3.96406, "ay":4.84948, "alpha":-0.9629, "fx":[64.95696,62.64462,70.24963,71.85859], "fy":[84.79999,86.1889,80.00821,78.95579]}, + {"t":1.62933, "x":1.67644, "y":6.75911, "heading":2.26121, "vx":-1.46645, "vy":1.35922, "omega":1.07188, "ax":4.1774, "ay":4.01198, "alpha":-2.726, "fx":[65.04669,59.62464,79.15002,80.40415], "fy":[76.81907,78.07621,57.73405,60.34141]}, + {"t":1.66949, "x":1.62092, "y":6.81693, "heading":2.30425, "vx":-1.29871, "vy":1.52032, "omega":0.96243, "ax":2.10888, "ay":1.70449, "alpha":-11.82808, "fx":[35.42025,-11.79754,46.92093,72.94236], "fy":[67.496,45.44279,-21.17906,24.21156]}, + {"t":1.70964, "x":1.57047, "y":6.87935, "heading":2.34289, "vx":-1.21403, "vy":1.58876, "omega":0.48748, "ax":0.34002, "ay":0.25752, "alpha":-13.07521, "fx":[7.26292,-43.26472,6.46656,52.66957], "fy":[51.53475,6.12989,-44.51337,4.37038]}, + {"t":1.7498, "x":1.522, "y":6.94335, "heading":2.36246, "vx":-1.20038, "vy":1.5991, "omega":-0.03754, "ax":0.04615, "ay":0.0346, "alpha":-10.22534, "fx":[0.63897,-36.84398,1.11612,38.22905], "fy":[38.05867,0.42398,-37.01664,0.88833]}, + {"t":1.78995, "x":1.47383, "y":7.00759, "heading":2.36096, "vx":-1.19852, "vy":1.60049, "omega":-0.44813, "ax":0.00548, "ay":0.0041, "alpha":-6.74386, "fx":[-0.02001,-24.66839,0.21589,24.84521], "fy":[24.82308,-0.04463,-24.69055,0.19115]}, + {"t":1.8301, "x":1.42571, "y":7.07186, "heading":2.34296, "vx":-1.1983, "vy":1.60066, "omega":-0.71892, "ax":0.00058, "ay":0.00043, "alpha":-2.79586, "fx":[0.14571,-10.2531,-0.12588,10.27259], "fy":[10.27014,0.14322,-10.25555,-0.12837]}, + {"t":1.87026, "x":1.3776, "y":7.13613, "heading":2.3141, "vx":-1.19828, "vy":1.60067, "omega":-0.83119, "ax":0.00006, "ay":0.00004, "alpha":1.38027, "fx":[-0.2123,5.0635,0.21421,-5.0616], "fy":[-5.06183,-0.21254,5.06326,0.21397]}, + {"t":1.91041, "x":1.32948, "y":7.2004, "heading":2.28072, "vx":-1.19828, "vy":1.60068, "omega":-0.77576, "ax":0.0, "ay":0.0, "alpha":5.44082, "fx":[-1.50602,19.91671,1.50608,-19.91665], "fy":[-19.91666,-1.50603,19.91671,1.50608]}, + {"t":1.95057, "x":1.28137, "y":7.26468, "heading":2.24957, "vx":-1.19828, "vy":1.60068, "omega":-0.55729, "ax":0.00016, "ay":-0.00028, "alpha":9.09844, "fx":[-3.55149,33.21364,3.55769,-33.20881], "fy":[-33.21567,-3.5598,33.20678,3.54938]}, + {"t":1.99072, "x":1.23325, "y":7.32895, "heading":2.22719, "vx":-1.19827, "vy":1.60067, "omega":-0.19195, "ax":2.82278, "ay":-3.77062, "alpha":4.24398, "fx":[39.77136,62.83269,60.0716,29.38334], "fy":[-76.89365,-59.44048,-48.54879,-71.66542]}, + {"t":2.03087, "x":1.18741, "y":7.39018, "heading":2.21949, "vx":-1.08492, "vy":1.44926, "omega":-0.02154, "ax":3.84192, "ay":-5.13211, "alpha":0.14422, "fx":[64.76608,65.94784,65.94204,64.74411], "fy":[-87.73993,-86.8551,-86.84566,-87.74245]}, + {"t":2.07103, "x":1.14694, "y":7.44424, "heading":2.21862, "vx":-0.93066, "vy":1.24319, "omega":-0.01575, "ax":3.85608, "ay":-5.15102, "alpha":0.09088, "fx":[65.21924,65.96856,65.96575,65.20996], "fy":[-87.89789,-87.33689,-87.3346,-87.90038]}, + {"t":2.11118, "x":1.11268, "y":7.49001, "heading":2.21799, "vx":-0.77582, "vy":1.03635, "omega":-0.0121, "ax":3.86089, "ay":-5.15744, "alpha":0.07281, "fx":[65.37374,65.97534,65.97351,65.36775], "fy":[-87.95147,-87.50109,-87.50009,-87.95356]}, + {"t":2.15134, "x":1.08464, "y":7.52746, "heading":2.2175, "vx":-0.62079, "vy":0.82926, "omega":-0.00918, "ax":3.8633, "ay":-5.16067, "alpha":0.06372, "fx":[65.45163,65.97869,65.97737,65.44711], "fy":[-87.97844,-87.58386,-87.5833,-87.98024]}, + {"t":2.19149, "x":1.06283, "y":7.5566, "heading":2.21713, "vx":-0.46566, "vy":0.62204, "omega":-0.00662, "ax":3.86476, "ay":-5.16261, "alpha":0.05825, "fx":[65.49856,65.98069,65.97967,65.49488], "fy":[-87.99468,-87.63374,-87.63337,-87.99628]}, + {"t":2.23164, "x":1.04725, "y":7.57741, "heading":2.21687, "vx":-0.31048, "vy":0.41474, "omega":-0.00428, "ax":3.86573, "ay":-5.16391, "alpha":0.0546, "fx":[65.52994,65.98203,65.9812,65.52677], "fy":[-88.00552,-87.66708,-87.66681,-88.00699]}, + {"t":2.2718, "x":1.0379, "y":7.5899, "heading":2.2167, "vx":-0.15525, "vy":0.20739, "omega":-0.00209, "ax":3.86643, "ay":-5.16484, "alpha":0.05199, "fx":[65.55241,65.98299,65.98228,65.54958], "fy":[-88.01327,-87.69093,-87.69073,-88.01465]}, + {"t":2.31195, "x":1.03478, "y":7.59407, "heading":2.21661, "vx":0.0, "vy":0.0, "omega":0.0, "ax":3.93183, "ay":-5.11322, "alpha":-0.01564, "fx":[66.9442,66.81553,66.81451,66.94299], "fy":[-86.92431,-87.02325,-87.02431,-86.92551]}, + {"t":2.3428, "x":1.03665, "y":7.59164, "heading":2.21661, "vx":0.12128, "vy":-0.15772, "omega":-0.00048, "ax":3.93157, "ay":-5.11264, "alpha":-0.01593, "fx":[66.94103,66.81,66.80897,66.9398], "fy":[-86.91352,-87.01429,-87.01537,-86.91477]}, + {"t":2.37364, "x":1.04226, "y":7.58434, "heading":2.2166, "vx":0.24255, "vy":-0.31543, "omega":-0.00097, "ax":3.93128, "ay":-5.11197, "alpha":-0.01626, "fx":[66.93738,66.80362,66.80257,66.93613], "fy":[-86.90107,-87.00394,-87.00507,-86.90236]}, + {"t":2.40449, "x":1.05162, "y":7.57218, "heading":2.21657, "vx":0.36382, "vy":-0.47311, "omega":-0.00148, "ax":3.93093, "ay":-5.11119, "alpha":-0.01665, "fx":[66.93311,66.79617,66.7951,66.93184], "fy":[-86.88653,-86.99186,-86.99303,-86.88788]}, + {"t":2.43534, "x":1.06471, "y":7.55515, "heading":2.21652, "vx":0.48507, "vy":-0.63077, "omega":-0.00199, "ax":3.93053, "ay":-5.11026, "alpha":-0.01711, "fx":[66.92807,66.78736,66.78627,66.92676], "fy":[-86.86934,-86.97757,-86.97881,-86.87076]}, + {"t":2.46618, "x":1.08154, "y":7.53326, "heading":2.21646, "vx":0.60631, "vy":-0.7884, "omega":-0.00252, "ax":3.93004, "ay":-5.10915, "alpha":-0.01767, "fx":[66.92202,66.77678,66.77567,66.92067], "fy":[-86.8487,-86.96042,-86.96173,-86.8502]}, + {"t":2.49703, "x":1.10211, "y":7.50651, "heading":2.21638, "vx":0.72754, "vy":-0.946, "omega":-0.00306, "ax":3.92944, "ay":-5.1078, "alpha":-0.01835, "fx":[66.91462,66.76385,66.76271,66.91322], "fy":[-86.82345,-86.93943,-86.94084,-86.82506]}, + {"t":2.52787, "x":1.12642, "y":7.4749, "heading":2.21629, "vx":0.84875, "vy":-1.10355, "omega":-0.00363, "ax":3.92869, "ay":-5.1061, "alpha":-0.01919, "fx":[66.90536,66.74766,66.74648,66.90389], "fy":[-86.79186,-86.91318,-86.91472,-86.79361]}, + {"t":2.55872, "x":1.15447, "y":7.43843, "heading":2.21618, "vx":0.96993, "vy":-1.26106, "omega":-0.00422, "ax":3.92772, "ay":-5.10392, "alpha":-0.02029, "fx":[66.89344,66.72683,66.7256,66.89189], "fy":[-86.75119,-86.8794,-86.8811,-86.75314]}, + {"t":2.58957, "x":1.18626, "y":7.39711, "heading":2.21605, "vx":1.09109, "vy":-1.41849, "omega":-0.00485, "ax":3.92643, "ay":-5.101, "alpha":-0.02175, "fx":[66.87752,66.69901,66.69773,66.87587], "fy":[-86.69689,-86.83429,-86.83622,-86.69911]}, + {"t":2.62041, "x":1.22178, "y":7.35093, "heading":2.2159, "vx":1.2122, "vy":-1.57584, "omega":-0.00552, "ax":3.92463, "ay":-5.09692, "alpha":-0.0238, "fx":[66.85518,66.65998,66.65864,66.85341], "fy":[-86.62072,-86.77102,-86.7733,-86.62334]}, + {"t":2.65126, "x":1.26104, "y":7.29989, "heading":2.21573, "vx":1.33326, "vy":-1.73306, "omega":-0.00625, "ax":3.92191, "ay":-5.09077, "alpha":-0.02689, "fx":[66.82158,66.60127,66.59987,66.81962], "fy":[-86.50618,-86.67589,-86.67873,-86.50945]}, + {"t":2.6821, "x":1.30403, "y":7.24401, "heading":2.21553, "vx":1.45424, "vy":-1.89009, "omega":-0.00708, "ax":3.91736, "ay":-5.08049, "alpha":-0.03206, "fx":[66.76529,66.50301,66.50159,66.76309], "fy":[-86.31454,-86.51675,-86.52065,-86.31906]}, + {"t":2.71295, "x":1.35076, "y":7.18329, "heading":2.21532, "vx":1.57507, "vy":-2.0468, "omega":-0.00807, "ax":3.90821, "ay":-5.05982, "alpha":-0.04252, "fx":[66.65171,66.30513,66.30397,66.64919], "fy":[-85.92882,-86.19646,-86.20295,-85.93639]}, + {"t":2.7438, "x":1.4012, "y":7.11775, "heading":2.21507, "vx":1.69562, "vy":-2.20288, "omega":-0.00938, "ax":3.8803, "ay":-4.99707, "alpha":-0.07453, "fx":[66.30328,65.70226,65.70434,66.30127], "fy":[-84.75564,-85.22207,-85.24024,-84.77708]}, + {"t":2.77464, "x":1.45535, "y":7.04742, "heading":2.21478, "vx":1.81532, "vy":-2.35702, "omega":-0.01168, "ax":1.0751, "ay":-0.1485, "alpha":-2.84907, "fx":[19.95146,8.06574,16.92688,28.20459], "fy":[8.0915,-1.06749,-13.18837,-3.93963]}, + {"t":2.80549, "x":1.51186, "y":6.97465, "heading":2.21442, "vx":1.84848, "vy":-2.3616, "omega":-0.09956, "ax":1.56493, "ay":1.25097, "alpha":-2.14402, "fx":[27.08628,18.77561,26.3781,34.23583], "fy":[28.97803,23.30265,13.27069,19.56295]}, + {"t":2.83633, "x":1.56962, "y":6.9024, "heading":2.21135, "vx":1.89675, "vy":-2.32301, "omega":-0.1657, "ax":3.14875, "ay":2.68488, "alpha":-0.95686, "fx":[52.68932,50.03866,54.55979,56.94989], "fy":[49.08886,47.6938,42.09622,43.79733]}, + {"t":2.86718, "x":1.62962, "y":6.83202, "heading":2.20623, "vx":1.99388, "vy":-2.24019, "omega":-0.19521, "ax":3.96128, "ay":3.73014, "alpha":-0.34254, "fx":[66.69419,66.04188,68.09617,68.68875], "fy":[64.59837,64.53874,62.27172,62.38572]}, + {"t":2.89803, "x":1.69301, "y":6.76469, "heading":2.20021, "vx":2.11607, "vy":-2.12513, "omega":-0.20578, "ax":4.06659, "ay":4.34701, "alpha":-0.14329, "fx":[68.82086,68.54993,69.52903,69.78651], "fy":[74.36008,74.46106,73.51807,73.42607]}, + {"t":2.92887, "x":1.76022, "y":6.70121, "heading":2.19387, "vx":2.2415, "vy":-1.99104, "omega":-0.2102, "ax":3.83779, "ay":4.59586, "alpha":-0.12342, "fx":[64.98856,64.69948,65.57588,65.85462], "fy":[78.4897,78.61571,77.85634,77.73554]}, + {"t":2.96429, "x":1.84202, "y":6.63357, "heading":2.18642, "vx":2.37744, "vy":-1.82825, "omega":-0.21457, "ax":3.11979, "ay":4.33254, "alpha":-0.23562, "fx":[52.69911,51.92777,53.44861,54.19168], "fy":[74.26545,74.36514,73.11911,73.03132]}, + {"t":2.99971, "x":1.92819, "y":6.57153, "heading":2.17882, "vx":2.48795, "vy":-1.67479, "omega":-0.22292, "ax":1.8349, "ay":2.84694, "alpha":-0.50488, "fx":[31.12879,29.08708,31.31464,33.31375], "fy":[49.95012,49.18314,46.87919,47.68976]}, + {"t":3.03514, "x":2.01747, "y":6.51399, "heading":2.17092, "vx":2.55294, "vy":-1.57395, "omega":-0.2408, "ax":0.55656, "ay":0.91563, "alpha":-0.52712, "fx":[9.78266,7.53091,9.15365,11.40037], "fy":[17.43847,15.97836,13.70011,15.18153]}, + {"t":3.07056, "x":2.10825, "y":6.45881, "heading":2.16239, "vx":2.57266, "vy":-1.54152, "omega":-0.25947, "ax":0.131, "ay":0.21938, "alpha":-0.25979, "fx":[2.41092,1.29152,2.04588,3.16508], "fy":[4.66622,3.9168,2.79644,3.54716]}, + {"t":3.10598, "x":2.19945, "y":6.40435, "heading":2.1532, "vx":2.5773, "vy":-1.53374, "omega":-0.26867, "ax":0.03034, "ay":0.05102, "alpha":0.01872, "fx":[0.50221,0.58339,0.52992,0.44874], "fy":[0.80057,0.85403,0.93521,0.88175]}, + {"t":3.1414, "x":2.29076, "y":6.35005, "heading":2.14369, "vx":2.57837, "vy":-1.53194, "omega":-0.26801, "ax":0.00703, "ay":0.01184, "alpha":0.29926, "fx":[-0.11209,1.19349,0.35131,-0.95428], "fy":[-0.87255,-0.03034,1.2752,0.43308]}, + {"t":3.17682, "x":2.3821, "y":6.2958, "heading":2.13419, "vx":2.57862, "vy":-1.53152, "omega":-0.25741, "ax":0.00163, "ay":0.00275, "alpha":0.59934, "fx":[-0.45671,2.17397,0.51219,-2.1185], "fy":[-2.09955,-0.43773,2.19291,0.53117]}, + {"t":3.21224, "x":2.47344, "y":6.24155, "heading":2.12508, "vx":2.57868, "vy":-1.53142, "omega":-0.23618, "ax":0.00038, "ay":0.00064, "alpha":0.93838, "fx":[-0.78266,3.35968,0.79553,-3.34681], "fy":[-3.34242,-0.77825,3.36407,0.79994]}, + {"t":3.24766, "x":2.56478, "y":6.18731, "heading":2.11671, "vx":2.57869, "vy":-1.5314, "omega":-0.20294, "ax":0.00009, "ay":0.00015, "alpha":1.33778, "fx":[-1.16341,4.77239,1.16641,-4.7694], "fy":[-4.76839,-1.16239,4.77341,1.16743]}, + {"t":3.28308, "x":2.65612, "y":6.13306, "heading":2.10952, "vx":2.5787, "vy":-1.53139, "omega":-0.15556, "ax":-0.00008, "ay":0.0001, "alpha":1.82189, "fx":[-1.63455,6.48441,1.63171,-6.48721], "fy":[-6.48419,-1.63151,6.48743,1.63475]}, + {"t":3.31851, "x":2.74746, "y":6.07882, "heading":2.10401, "vx":2.57869, "vy":-1.53139, "omega":-0.09102, "ax":-0.87523, "ay":0.51978, "alpha":2.30221, "fx":[-17.24721,-6.74574,-12.72322,-22.83379], "fy":[0.50926,6.89358,17.15826,10.80431]}, + {"t":3.35393, "x":2.83825, "y":6.0249, "heading":2.10079, "vx":2.54769, "vy":-1.51298, "omega":-0.00947, "ax":-5.46887, "ay":3.24775, "alpha":0.04885, "fx":[-93.19585,-92.96949,-92.85175,-93.0783], "fy":[54.95034,55.32517,55.53563,55.16231]}, + {"t":3.38935, "x":2.92506, "y":5.97335, "heading":2.10045, "vx":2.35398, "vy":-1.39794, "omega":-0.00774, "ax":-5.51125, "ay":3.27293, "alpha":0.03002, "fx":[-93.85176,-93.71258,-93.63785,-93.7771], "fy":[55.49037,55.72286,55.85238,55.62047]}, + {"t":3.42477, "x":3.00498, "y":5.92588, "heading":2.10018, "vx":2.15876, "vy":-1.28201, "omega":-0.00668, "ax":-5.52532, "ay":3.28128, "alpha":0.02381, "fx":[-94.06929,-93.95889,-93.89897,-94.00942], "fy":[55.66968,55.85462,55.95742,55.77285]}, + {"t":3.46019, "x":3.07798, "y":5.88253, "heading":2.09994, "vx":1.96305, "vy":-1.16578, "omega":-0.00584, "ax":-5.53234, "ay":3.28545, "alpha":0.02072, "fx":[-94.17776,-94.08169,-94.02925,-94.12536], "fy":[55.75911,55.9203,56.00982,55.84891]}, + {"t":3.49561, "x":3.14405, "y":5.8433, "heading":2.09973, "vx":1.76709, "vy":-1.04941, "omega":-0.0051, "ax":-5.53654, "ay":3.28794, "alpha":0.01888, "fx":[-94.24274,-94.15523,-94.1073,-94.19484], "fy":[55.81268,55.95963,56.04121,55.89449]}, + {"t":3.53103, "x":3.20317, "y":5.80819, "heading":2.09955, "vx":1.57098, "vy":-0.93294, "omega":-0.00443, "ax":-5.53934, "ay":3.28961, "alpha":0.01765, "fx":[-94.28602,-94.20419,-94.15927,-94.24112], "fy":[55.84834,55.98581,56.06212,55.92486]}, + {"t":3.56645, "x":3.25534, "y":5.77721, "heading":2.0994, "vx":1.37477, "vy":-0.81642, "omega":-0.00381, "ax":-5.54134, "ay":3.29079, "alpha":0.01678, "fx":[-94.3169,-94.23914,-94.19636,-94.27415], "fy":[55.8738,56.0045,56.07705,55.94653]}, + {"t":3.60187, "x":3.30056, "y":5.75036, "heading":2.09926, "vx":1.17849, "vy":-0.69986, "omega":-0.00322, "ax":-5.54284, "ay":3.29168, "alpha":0.01612, "fx":[-94.34004,-94.26532,-94.22417,-94.29891], "fy":[55.89287,56.0185,56.08824,55.96278]}, + {"t":3.6373, "x":3.33882, "y":5.72763, "heading":2.09915, "vx":0.98215, "vy":-0.58326, "omega":-0.00264, "ax":-5.544, "ay":3.29237, "alpha":0.01561, "fx":[-94.35804,-94.28568,-94.24578,-94.31816], "fy":[55.90769,56.02938,56.09694,55.97541]}, + {"t":3.67272, "x":3.37013, "y":5.70904, "heading":2.09905, "vx":0.78578, "vy":-0.46664, "omega":-0.00209, "ax":-5.54493, "ay":3.29293, "alpha":0.01521, "fx":[-94.37243,-94.30195,-94.26306,-94.33355], "fy":[55.91955,56.03809,56.10389,55.98551]}, + {"t":3.70814, "x":3.39449, "y":5.69457, "heading":2.09898, "vx":0.58937, "vy":-0.35, "omega":-0.00155, "ax":-5.5457, "ay":3.29338, "alpha":0.01487, "fx":[-94.3842,-94.31526,-94.27719,-94.34615], "fy":[55.92924,56.04521,56.10958,55.99377]}, + {"t":3.74356, "x":3.41189, "y":5.68424, "heading":2.09893, "vx":0.39293, "vy":-0.23335, "omega":-0.00103, "ax":-5.54633, "ay":3.29376, "alpha":0.0146, "fx":[-94.394,-94.32635,-94.28897,-94.35664], "fy":[55.93732,56.05114,56.11432,56.00065]}, + {"t":3.77898, "x":3.42232, "y":5.67804, "heading":2.09889, "vx":0.19648, "vy":-0.11668, "omega":-0.00051, "ax":-5.54687, "ay":3.29408, "alpha":0.01436, "fx":[-94.40229,-94.33573,-94.29893,-94.36551], "fy":[55.94415,56.05616,56.11833,56.00646]}, + {"t":3.8144, "x":3.4258, "y":5.67598, "heading":2.09887, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/v2_redundancy/choreo/C_LEFT_PATH3.traj b/src/main/deploy/v2_redundancy/choreo/C_LEFT_PATH3.traj new file mode 100644 index 00000000..309d9a44 --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/C_LEFT_PATH3.traj @@ -0,0 +1,146 @@ +{ + "name":"C_LEFT_PATH3", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.999176502227783, "y":5.206205368041992, "heading":2.1010083691287966, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.5805233716964722, "y":7.047026634216309, "heading":0.0, "intervals":34, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":1.0536435842514038, "y":7.575206756591797, "heading":2.217924532332081, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.5711495876312256, "y":7.018905162811279, "heading":0.0, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":3.5301125049591064, "y":5.400979518890381, "heading":2.077894951837786, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":3.0}}, "enabled":true}, + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":1, "to":2, "data":{"type":"MaxVelocity", "props":{"max":1.0}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.999176502227783 m", "val":3.999176502227783}, "y":{"exp":"5.206205368041992 m", "val":5.206205368041992}, "heading":{"exp":"2.1010083691287966 rad", "val":2.1010083691287966}, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.5805233716964722 m", "val":1.5805233716964722}, "y":{"exp":"7.047026634216309 m", "val":7.047026634216309}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":34, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"1.0536435842514038 m", "val":1.0536435842514038}, "y":{"exp":"7.575206756591797 m", "val":7.575206756591797}, "heading":{"exp":"2.217924532332081 rad", "val":2.217924532332081}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.5711495876312256 m", "val":1.5711495876312256}, "y":{"exp":"7.018905162811279 m", "val":7.018905162811279}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"3.5301125049591064 m", "val":3.5301125049591064}, "y":{"exp":"5.400979518890381 m", "val":5.400979518890381}, "heading":{"exp":"2.077894951837786 rad", "val":2.077894951837786}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"3 m / s", "val":3.0}}}, "enabled":true}, + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":1, "to":2, "data":{"type":"MaxVelocity", "props":{"max":{"exp":"1 m / s", "val":1.0}}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.34999,2.17412,2.66047,3.74072], + "samples":[ + {"t":0.0, "x":3.99918, "y":5.20621, "heading":2.10101, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.14437, "ay":3.89483, "alpha":0.00135, "fx":[-87.50979,-87.502,-87.49879,-87.50658], "fy":[66.24276,66.25304,66.2573,66.24702]}, + {"t":0.04219, "x":3.9946, "y":5.20967, "heading":2.10101, "vx":-0.21703, "vy":0.16431, "omega":0.00006, "ax":-5.14387, "ay":3.89445, "alpha":0.00137, "fx":[-87.50136,-87.4934,-87.49012,-87.49808], "fy":[66.23613,66.24663,66.25098,66.24049]}, + {"t":0.08437, "x":3.98087, "y":5.22007, "heading":2.10101, "vx":-0.43403, "vy":0.32861, "omega":0.00011, "ax":-5.14325, "ay":3.89399, "alpha":0.00141, "fx":[-87.49104,-87.48288,-87.47952,-87.48768], "fy":[66.22802,66.23879,66.24325,66.23249]}, + {"t":0.12656, "x":3.95798, "y":5.2374, "heading":2.10102, "vx":-0.65101, "vy":0.49289, "omega":0.00017, "ax":-5.14248, "ay":3.89341, "alpha":0.00145, "fx":[-87.47813,-87.46972,-87.46625,-87.47466], "fy":[66.21787,66.22897,66.23358,66.22248]}, + {"t":0.16875, "x":3.92594, "y":5.26166, "heading":2.10102, "vx":-0.86796, "vy":0.65714, "omega":0.00024, "ax":-5.14149, "ay":3.89266, "alpha":0.00151, "fx":[-87.46149,-87.45275,-87.44915,-87.45789], "fy":[66.2048,66.21633,66.22111,66.20959]}, + {"t":0.21094, "x":3.88475, "y":5.29284, "heading":2.10103, "vx":-1.08486, "vy":0.82136, "omega":0.0003, "ax":-5.14017, "ay":3.89165, "alpha":0.00159, "fx":[-87.43925,-87.43007,-87.4263,-87.43548], "fy":[66.18732,66.19942,66.20445,66.19235]}, + {"t":0.25312, "x":3.8344, "y":5.33096, "heading":2.10105, "vx":-1.30171, "vy":0.98554, "omega":0.00037, "ax":-5.13831, "ay":3.89024, "alpha":0.00169, "fx":[-87.40802,-87.39822,-87.3942,-87.40399], "fy":[66.16276,66.17568,66.18105,66.16814]}, + {"t":0.29531, "x":3.77492, "y":5.37599, "heading":2.10106, "vx":-1.51849, "vy":1.14965, "omega":0.00044, "ax":-5.1355, "ay":3.88812, "alpha":0.00185, "fx":[-87.36093,-87.3502,-87.34581,-87.35653], "fy":[66.12575,66.13989,66.14578,66.13164]}, + {"t":0.3375, "x":3.70628, "y":5.42796, "heading":2.10108, "vx":-1.73514, "vy":1.31368, "omega":0.00052, "ax":-5.13079, "ay":3.88455, "alpha":0.00213, "fx":[-87.28185,-87.26956,-87.26454,-87.27683], "fy":[66.0636,66.07978,66.08653,66.07035]}, + {"t":0.37969, "x":3.62852, "y":5.48683, "heading":2.1011, "vx":-1.95159, "vy":1.47756, "omega":0.00061, "ax":-5.12123, "ay":3.87731, "alpha":0.00268, "fx":[-87.12147,-87.106,-87.09973,-87.1152], "fy":[65.93754,65.95788,65.96639,65.94606]}, + {"t":0.42187, "x":3.54163, "y":5.55262, "heading":2.10113, "vx":-2.16764, "vy":1.64113, "omega":0.00072, "ax":-5.0915, "ay":3.85481, "alpha":0.0044, "fx":[-86.62275,-86.59738,-86.58732,-86.61269], "fy":[65.54556,65.57876,65.59282,65.55964]}, + {"t":0.46406, "x":3.44565, "y":5.62528, "heading":2.10116, "vx":-2.38244, "vy":1.80376, "omega":0.0009, "ax":-0.20864, "ay":0.15796, "alpha":0.29051, "fx":[-3.81983,-2.51736,-3.27871,-4.57953], "fy":[1.65395,2.41938,3.71966,2.95446]}, + {"t":0.50625, "x":3.34496, "y":5.70152, "heading":2.1012, "vx":-2.39124, "vy":1.81042, "omega":0.01316, "ax":-0.00001, "ay":0.00001, "alpha":0.2198, "fx":[-0.20373,0.78059,0.20333,-0.78099], "fy":[-0.78064,-0.20338,0.78094,0.20368]}, + {"t":0.54843, "x":3.24408, "y":5.7779, "heading":2.10175, "vx":-2.39124, "vy":1.81042, "omega":0.02243, "ax":0.0, "ay":0.0, "alpha":0.16816, "fx":[-0.15539,0.59746,0.15539,-0.59746], "fy":[-0.59746,-0.15539,0.59746,0.15539]}, + {"t":0.59062, "x":3.1432, "y":5.85427, "heading":2.1027, "vx":-2.39124, "vy":1.81042, "omega":0.02953, "ax":0.0, "ay":0.0, "alpha":0.13187, "fx":[-0.1214,0.46861,0.1214,-0.46861], "fy":[-0.46861,-0.1214,0.46861,0.1214]}, + {"t":0.63281, "x":3.04232, "y":5.93065, "heading":2.10394, "vx":-2.39124, "vy":1.81042, "omega":0.03509, "ax":0.0, "ay":0.0, "alpha":0.10759, "fx":[-0.09858,0.38248,0.09858,-0.38248], "fy":[-0.38248,-0.09858,0.38248,0.09858]}, + {"t":0.675, "x":2.94144, "y":6.00703, "heading":2.10542, "vx":-2.39124, "vy":1.81042, "omega":0.03963, "ax":0.0, "ay":0.0, "alpha":0.09314, "fx":[-0.08484,0.33122,0.08485,-0.33122], "fy":[-0.33122,-0.08484,0.33122,0.08485]}, + {"t":0.71718, "x":2.84056, "y":6.0834, "heading":2.10709, "vx":-2.39124, "vy":1.81042, "omega":0.04356, "ax":0.0, "ay":0.0, "alpha":0.08718, "fx":[-0.07888,0.31018,0.07892,-0.31015], "fy":[-0.31014,-0.07888,0.31019,0.07892]}, + {"t":0.75937, "x":2.73968, "y":6.15978, "heading":2.10893, "vx":-2.39124, "vy":1.81042, "omega":0.04724, "ax":0.00001, "ay":0.00001, "alpha":0.08918, "fx":[-0.08002,0.31752,0.08023,-0.31732], "fy":[-0.31728,-0.07999,0.31755,0.08026]}, + {"t":0.80156, "x":2.6388, "y":6.23616, "heading":2.11092, "vx":-2.39124, "vy":1.81042, "omega":0.051, "ax":0.00004, "ay":0.00005, "alpha":0.09931, "fx":[-0.08791,0.35428,0.08914,-0.35306], "fy":[-0.35286,-0.08772,0.35448,0.08934]}, + {"t":0.84374, "x":2.53792, "y":6.31253, "heading":2.11308, "vx":-2.39124, "vy":1.81043, "omega":0.05519, "ax":0.00022, "ay":0.00029, "alpha":0.11851, "fx":[-0.10097,0.42603,0.10849,-0.41851], "fy":[-0.41731,-0.09977,0.42724,0.1097]}, + {"t":0.88593, "x":2.43704, "y":6.38891, "heading":2.1154, "vx":-2.39123, "vy":1.81044, "omega":0.06019, "ax":0.00135, "ay":0.00179, "alpha":0.14853, "fx":[-0.107,0.55256,0.15306,-0.5065], "fy":[-0.49912,-0.09961,0.55995,0.16045]}, + {"t":0.92812, "x":2.33616, "y":6.46529, "heading":2.11794, "vx":-2.39117, "vy":1.81051, "omega":0.06645, "ax":0.0083, "ay":0.01095, "alpha":0.19211, "fx":[-0.02533,0.82642,0.30754,-0.54422], "fy":[-0.49901,0.01988,0.87162,0.35276]}, + {"t":0.97031, "x":2.23529, "y":6.54168, "heading":2.12075, "vx":-2.39082, "vy":1.81098, "omega":0.07456, "ax":0.05098, "ay":0.06696, "alpha":0.25315, "fx":[0.65045,1.7708,1.08374,-0.03669], "fy":[0.2352,0.92207,2.04239,1.35592]}, + {"t":1.01249, "x":2.13447, "y":6.61814, "heading":2.12389, "vx":-2.38867, "vy":1.8138, "omega":0.08524, "ax":2.15306, "ay":-1.07756, "alpha":0.25513, "fx":[36.32611,37.43242,36.92419,35.8093], "fy":[-19.33975,-18.46187,-17.31711,-18.19748]}, + {"t":1.05468, "x":2.03562, "y":6.6937, "heading":2.12749, "vx":-2.29784, "vy":1.76834, "omega":0.096, "ax":5.10185, "ay":-3.8486, "alpha":0.00438, "fx":[86.7637,86.7891,86.79849,86.77308], "fy":[-65.48692,-65.45353,-65.44034,-65.47375]}, + {"t":1.09687, "x":1.94322, "y":6.76488, "heading":2.13154, "vx":-2.08261, "vy":1.60598, "omega":0.09619, "ax":5.12558, "ay":-3.87341, "alpha":0.00231, "fx":[87.17538,87.18885,87.19385,87.18038], "fy":[-65.89788,-65.88013,-65.87331,-65.89106]}, + {"t":1.13906, "x":1.85992, "y":6.82918, "heading":2.1356, "vx":-1.86637, "vy":1.44257, "omega":0.09628, "ax":5.13352, "ay":-3.88175, "alpha":0.00151, "fx":[87.31369,87.32253,87.32579,87.31695], "fy":[-66.03551,-66.02386,-66.01946,-66.03111]}, + {"t":1.18124, "x":1.78575, "y":6.88658, "heading":2.13966, "vx":-1.6498, "vy":1.27881, "omega":0.09635, "ax":5.1375, "ay":-3.88594, "alpha":0.00106, "fx":[87.38311,87.38933,87.39161,87.38539], "fy":[-66.10431,-66.09609,-66.09303,-66.10125]}, + {"t":1.22343, "x":1.72072, "y":6.93708, "heading":2.14372, "vx":-1.43307, "vy":1.11487, "omega":0.09639, "ax":5.13988, "ay":-3.88845, "alpha":0.00077, "fx":[87.42486,87.42937,87.431,87.42649], "fy":[-66.14553,-66.13958,-66.1374,-66.14335]}, + {"t":1.26562, "x":1.66484, "y":6.98065, "heading":2.14779, "vx":-1.21623, "vy":0.95083, "omega":0.09642, "ax":5.14147, "ay":-3.89013, "alpha":0.00056, "fx":[87.45275,87.45602,87.4572,87.45392], "fy":[-66.17298,-66.16865,-66.16708,-66.17141]}, + {"t":1.3078, "x":1.61811, "y":7.0173, "heading":2.15186, "vx":-0.99932, "vy":0.78672, "omega":0.09645, "ax":5.14261, "ay":-3.89133, "alpha":0.0004, "fx":[87.47269,87.47504,87.47587,87.47352], "fy":[-66.19256,-66.18946,-66.18835,-66.19145]}, + {"t":1.34999, "x":1.58052, "y":7.04703, "heading":2.15593, "vx":-0.78237, "vy":0.62255, "omega":0.09646, "ax":1.92733, "ay":2.15504, "alpha":0.13226, "fx":[32.77991,33.28834,32.78788,32.27704], "fy":[36.20975,36.46822,37.10172,36.84659]}, + {"t":1.38924, "x":1.5513, "y":7.07312, "heading":2.15971, "vx":-0.70674, "vy":0.70712, "omega":0.10165, "ax":0.07504, "ay":0.07469, "alpha":0.1549, "fx":[1.1656,1.83415,1.38732,0.71869], "fy":[0.71277,1.15937,1.82812,1.38169]}, + {"t":1.42848, "x":1.52363, "y":7.10093, "heading":2.1637, "vx":-0.70379, "vy":0.71005, "omega":0.10773, "ax":0.00221, "ay":0.00219, "alpha":0.114, "fx":[-0.04254,0.44831,0.11759,-0.37325], "fy":[-0.37359,-0.04287,0.44797,0.11726]}, + {"t":1.46772, "x":1.49601, "y":7.12879, "heading":2.16793, "vx":-0.7037, "vy":0.71014, "omega":0.11221, "ax":0.00006, "ay":0.00006, "alpha":0.07492, "fx":[-0.05037,0.27127,0.05257,-0.26907], "fy":[-0.26908,-0.05038,0.27126,0.05256]}, + {"t":1.50697, "x":1.46839, "y":7.15666, "heading":2.17233, "vx":-0.7037, "vy":0.71014, "omega":0.11515, "ax":0.0, "ay":0.0, "alpha":0.03708, "fx":[-0.02485,0.13386,0.02492,-0.1338], "fy":[-0.1338,-0.02486,0.13386,0.02492]}, + {"t":1.54621, "x":1.44078, "y":7.18453, "heading":2.17685, "vx":-0.7037, "vy":0.71014, "omega":0.1166, "ax":0.0, "ay":0.0, "alpha":-0.00014, "fx":[0.00009,-0.00051,-0.00009,0.00051], "fy":[0.00051,0.00009,-0.00051,-0.00009]}, + {"t":1.58546, "x":1.41316, "y":7.2124, "heading":2.18143, "vx":-0.7037, "vy":0.71014, "omega":0.1166, "ax":0.0, "ay":0.0, "alpha":-0.03737, "fx":[0.02385,-0.13508,-0.02385,0.13508], "fy":[0.13508,0.02385,-0.13508,-0.02385]}, + {"t":1.6247, "x":1.38554, "y":7.24027, "heading":2.186, "vx":-0.7037, "vy":0.71014, "omega":0.11513, "ax":0.0, "ay":0.0, "alpha":-0.07521, "fx":[0.04676,-0.27212,-0.04676,0.27212], "fy":[0.27212,0.04676,-0.27212,-0.04676]}, + {"t":1.66395, "x":1.35793, "y":7.26814, "heading":2.19052, "vx":-0.7037, "vy":0.71014, "omega":0.11218, "ax":0.0, "ay":0.0, "alpha":-0.11431, "fx":[0.0692,-0.41389,-0.0692,0.41389], "fy":[0.41389,0.0692,-0.41389,-0.0692]}, + {"t":1.70319, "x":1.33031, "y":7.29601, "heading":2.19492, "vx":-0.7037, "vy":0.71014, "omega":0.10769, "ax":0.0, "ay":0.0, "alpha":-0.15531, "fx":[0.09155,-0.56274,-0.09155,0.56274], "fy":[0.56274,0.09155,-0.56274,-0.09155]}, + {"t":1.74243, "x":1.30269, "y":7.32388, "heading":2.19915, "vx":-0.7037, "vy":0.71014, "omega":0.1016, "ax":0.0, "ay":0.0, "alpha":-0.19888, "fx":[0.11419,-0.72113,-0.11419,0.72113], "fy":[0.72113,0.11419,-0.72113,-0.11419]}, + {"t":1.78168, "x":1.27508, "y":7.35174, "heading":2.20314, "vx":-0.7037, "vy":0.71014, "omega":0.09379, "ax":0.0, "ay":0.0, "alpha":-0.24577, "fx":[0.13755,-0.89168,-0.13755,0.89168], "fy":[0.89168,0.13755,-0.89168,-0.13755]}, + {"t":1.82092, "x":1.24746, "y":7.37961, "heading":2.20682, "vx":-0.7037, "vy":0.71014, "omega":0.08415, "ax":0.0, "ay":0.0, "alpha":-0.29674, "fx":[0.16212,-1.07721,-0.16212,1.07721], "fy":[1.07721,0.16212,-1.07721,-0.16212]}, + {"t":1.86017, "x":1.21985, "y":7.40748, "heading":2.21012, "vx":-0.7037, "vy":0.71014, "omega":0.0725, "ax":0.0, "ay":0.0, "alpha":-0.35263, "fx":[0.18843,-1.28076,-0.18843,1.28076], "fy":[1.28076,0.18843,-1.28076,-0.18843]}, + {"t":1.89941, "x":1.19223, "y":7.43535, "heading":2.21297, "vx":-0.7037, "vy":0.71014, "omega":0.05866, "ax":0.0, "ay":0.0, "alpha":-0.41439, "fx":[0.21714,-1.50566,-0.21714,1.50566], "fy":[1.50566,0.21714,-1.50566,-0.21714]}, + {"t":1.93865, "x":1.16461, "y":7.46322, "heading":2.21527, "vx":-0.7037, "vy":0.71014, "omega":0.0424, "ax":0.0, "ay":0.0, "alpha":-0.48302, "fx":[0.24906,-1.7556,-0.24906,1.7556], "fy":[1.7556,0.24906,-1.7556,-0.24906]}, + {"t":1.9779, "x":1.137, "y":7.49109, "heading":2.21693, "vx":-0.7037, "vy":0.71014, "omega":0.02345, "ax":0.00038, "ay":-0.00039, "alpha":-0.55965, "fx":[0.2917,-2.02813,-0.27868,2.04113], "fy":[2.02807,0.27863,-2.04119,-0.29176]}, + {"t":2.01714, "x":1.10938, "y":7.51896, "heading":2.21785, "vx":-0.70369, "vy":0.71013, "omega":0.00148, "ax":4.3236, "ay":-4.36317, "alpha":-0.03239, "fx":[73.66636,73.43912,73.42026,73.64694], "fy":[-74.08453,-74.30677,-74.34779,-74.12626]}, + {"t":2.05639, "x":1.0851, "y":7.54347, "heading":2.21791, "vx":-0.53401, "vy":0.5389, "omega":0.00021, "ax":4.52954, "ay":-4.571, "alpha":-0.00268, "fx":[77.05715,77.03761,77.03505,77.05459], "fy":[-77.74033,-77.75968,-77.76235,-77.74301]}, + {"t":2.09563, "x":1.06763, "y":7.5611, "heading":2.21792, "vx":-0.35625, "vy":0.35951, "omega":0.00011, "ax":4.53752, "ay":-4.57906, "alpha":-0.00156, "fx":[77.18842,77.17707,77.17556,77.18692], "fy":[-77.88209,-77.89333,-77.89487,-77.88362]}, + {"t":2.13488, "x":1.05714, "y":7.57168, "heading":2.21792, "vx":-0.17818, "vy":0.17981, "omega":0.00005, "ax":4.54033, "ay":-4.58189, "alpha":-0.00116, "fx":[77.23446,77.22598,77.22485,77.23333], "fy":[-77.9318,-77.9402,-77.94134,-77.93294]}, + {"t":2.17412, "x":1.05364, "y":7.57521, "heading":2.21792, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.35868, "ay":-4.75366, "alpha":-0.01435, "fx":[74.19962,74.09039,74.0802,74.1893], "fy":[-80.80345,-80.90359,-80.9132,-80.81321]}, + {"t":2.20273, "x":1.05543, "y":7.57326, "heading":2.21792, "vx":0.1247, "vy":-0.136, "omega":-0.00041, "ax":4.35982, "ay":-4.75177, "alpha":-0.0146, "fx":[74.22015,74.10904,74.09865,74.20963], "fy":[-80.77028,-80.87222,-80.88205,-80.78027]}, + {"t":2.23134, "x":1.06078, "y":7.56743, "heading":2.21791, "vx":0.24942, "vy":-0.27194, "omega":-0.00083, "ax":4.36113, "ay":-4.74961, "alpha":-0.01489, "fx":[74.24361,74.13034,74.11972,74.23285], "fy":[-80.73237,-80.83636,-80.84644,-80.74261]}, + {"t":2.25995, "x":1.0697, "y":7.5577, "heading":2.21789, "vx":0.37419, "vy":-0.40782, "omega":-0.00125, "ax":4.36264, "ay":-4.74711, "alpha":-0.01523, "fx":[74.27067,74.1549,74.14401,74.25963], "fy":[-80.68861,-80.79498,-80.80535,-80.69915]}, + {"t":2.28855, "x":1.08219, "y":7.54409, "heading":2.21785, "vx":0.499, "vy":-0.54363, "omega":-0.00169, "ax":4.3644, "ay":-4.7442, "alpha":-0.01562, "fx":[74.30221,74.18354,74.17233,74.29085], "fy":[-80.63754,-80.74668,-80.7574,-80.64843]}, + {"t":2.31716, "x":1.09825, "y":7.5266, "heading":2.2178, "vx":0.62386, "vy":-0.67935, "omega":-0.00214, "ax":4.36648, "ay":-4.74076, "alpha":-0.01608, "fx":[74.33946,74.21737,74.20578,74.32771], "fy":[-80.57716,-80.68959,-80.70072,-80.58848]}, + {"t":2.34577, "x":1.11789, "y":7.50522, "heading":2.21774, "vx":0.74878, "vy":-0.81498, "omega":-0.0026, "ax":4.36897, "ay":-4.73663, "alpha":-0.01664, "fx":[74.38411,74.25791,74.24586,74.37188], "fy":[-80.50468,-80.62105,-80.63269,-80.51652]}, + {"t":2.37438, "x":1.1411, "y":7.47997, "heading":2.21767, "vx":0.87377, "vy":-0.95049, "omega":-0.00307, "ax":4.37201, "ay":-4.73158, "alpha":-0.01732, "fx":[74.43862,74.3074,74.29478,74.4258], "fy":[-80.41606,-80.53726,-80.54952,-80.42854]}, + {"t":2.40299, "x":1.16788, "y":7.45084, "heading":2.21758, "vx":0.99885, "vy":-1.08585, "omega":-0.00357, "ax":4.3758, "ay":-4.72527, "alpha":-0.01817, "fx":[74.50663,74.36917,74.35583,74.49308], "fy":[-80.30524,-80.43248,-80.44554,-80.31854]}, + {"t":2.4316, "x":1.19825, "y":7.41784, "heading":2.21748, "vx":1.12403, "vy":-1.22104, "omega":-0.00409, "ax":4.38067, "ay":-4.71715, "alpha":-0.01926, "fx":[74.59387,74.4484,74.43412,74.57936], "fy":[-80.16267,-80.2977,-80.31182,-80.17706]}, + {"t":2.46021, "x":1.2322, "y":7.38098, "heading":2.21736, "vx":1.24936, "vy":-1.35599, "omega":-0.00464, "ax":4.38714, "ay":-4.70631, "alpha":-0.02072, "fx":[74.70983,74.55372,74.53818,74.69402], "fy":[-79.97249,-80.11792,-80.13349,-79.98837]}, + {"t":2.48882, "x":1.26974, "y":7.34026, "heading":2.21723, "vx":1.37487, "vy":-1.49063, "omega":-0.00523, "ax":4.39615, "ay":-4.69114, "alpha":-0.02276, "fx":[74.87145,74.70053,74.68318,74.85377], "fy":[-79.70606,-79.86611,-79.88381,-79.72414]}, + {"t":2.51742, "x":1.31087, "y":7.2957, "heading":2.21708, "vx":1.50064, "vy":-1.62484, "omega":-0.00588, "ax":4.40957, "ay":-4.66838, "alpha":-0.02582, "fx":[75.11222,74.91929,74.89914,75.09167], "fy":[-79.30618,-79.48823,-79.50931,-79.32774]}, + {"t":2.54603, "x":1.3556, "y":7.2473, "heading":2.21691, "vx":1.62679, "vy":-1.75839, "omega":-0.00662, "ax":4.43169, "ay":-4.63045, "alpha":-0.03092, "fx":[75.50889,75.27982,75.25483,75.48333], "fy":[-78.63937,-78.85829,-78.88548,-78.66726]}, + {"t":2.57464, "x":1.40396, "y":7.1951, "heading":2.21672, "vx":1.75357, "vy":-1.89086, "omega":-0.00751, "ax":4.47489, "ay":-4.55466, "alpha":-0.04108, "fx":[76.28417,75.985,75.94966,76.24786], "fy":[-77.30597,-77.59916,-77.64046,-77.34851]}, + {"t":2.60325, "x":1.45596, "y":7.13914, "heading":2.21651, "vx":1.8816, "vy":-2.02117, "omega":-0.00868, "ax":4.59605, "ay":-4.32909, "alpha":-0.07108, "fx":[78.45891,77.96794,77.89743,78.38589], "fy":[-73.32776,-73.84554,-73.94338,-73.42937]}, + {"t":2.63186, "x":1.51167, "y":7.07955, "heading":2.21626, "vx":2.01308, "vy":-2.14502, "omega":-0.01071, "ax":4.61835, "ay":1.76787, "alpha":-0.70026, "fx":[77.7783,76.96656,79.36469,80.11765], "fy":[33.52559,31.64456,26.49515,28.61867]}, + {"t":2.66047, "x":1.57115, "y":7.01891, "heading":2.21595, "vx":2.14521, "vy":-2.09444, "omega":-0.03075, "ax":3.12543, "ay":3.34556, "alpha":-0.9193, "fx":[52.05254,49.39253,54.43013,56.77555], "fy":[59.83166,59.10361,53.84712,54.84564]}, + {"t":2.69772, "x":1.65323, "y":6.94321, "heading":2.21481, "vx":2.26163, "vy":-1.96982, "omega":-0.06499, "ax":1.20522, "ay":1.41641, "alpha":-1.7957, "fx":[20.96643,13.75323,20.15567,27.12663], "fy":[30.35824,25.64476,17.62601,22.74205]}, + {"t":2.73497, "x":1.73831, "y":6.87081, "heading":2.21239, "vx":2.30652, "vy":-1.91706, "omega":-0.13188, "ax":0.27095, "ay":0.32775, "alpha":-1.58538, "fx":[5.42708,-1.16741,3.8067,10.36878], "fy":[11.30811,6.45153,-0.19551,4.73558]}, + {"t":2.77222, "x":1.82442, "y":6.79963, "heading":2.20747, "vx":2.31662, "vy":-1.90485, "omega":-0.19094, "ax":0.05686, "ay":0.06923, "alpha":-1.18942, "fx":[1.61426,-3.35227,0.32188,5.28474], "fy":[5.49327,1.82756,-3.14261,0.53201]}, + {"t":2.80947, "x":1.91075, "y":6.72872, "heading":2.20036, "vx":2.31874, "vy":-1.90227, "omega":-0.23524, "ax":0.0119, "ay":0.0145, "alpha":-0.86491, "fx":[0.69522,-2.93443,-0.29032,3.33894], "fy":[3.38314,0.73978,-2.8902,-0.24585]}, + {"t":2.84672, "x":1.99713, "y":6.65787, "heading":2.1916, "vx":2.31918, "vy":-1.90173, "omega":-0.26746, "ax":0.00249, "ay":0.00303, "alpha":-0.60213, "fx":[0.4045,-2.13827,-0.31987,2.22286], "fy":[2.23214,0.41381,-2.12899,-0.31057]}, + {"t":2.88397, "x":2.08352, "y":6.58704, "heading":2.18164, "vx":2.31927, "vy":-1.90161, "omega":-0.28989, "ax":0.00052, "ay":0.00063, "alpha":-0.383, "fx":[0.25302,-1.3758,-0.23535,1.39347], "fy":[1.39541,0.25497,-1.37386,-0.2334]}, + {"t":2.92122, "x":2.16992, "y":6.5162, "heading":2.17084, "vx":2.31929, "vy":-1.90159, "omega":-0.30416, "ax":0.00011, "ay":0.00013, "alpha":-0.19183, "fx":[0.13163,-0.69031,-0.12794,0.694], "fy":[0.69441,0.13204,-0.6899,-0.12754]}, + {"t":2.95847, "x":2.25631, "y":6.44537, "heading":2.15951, "vx":2.31929, "vy":-1.90159, "omega":-0.3113, "ax":0.00002, "ay":0.00003, "alpha":-0.01474, "fx":[0.01096,-0.05268,-0.01019,0.05345], "fy":[0.05353,0.01104,-0.05259,-0.0101]}, + {"t":2.99572, "x":2.3427, "y":6.37453, "heading":2.14791, "vx":2.3193, "vy":-1.90159, "omega":-0.31185, "ax":0.0, "ay":0.00001, "alpha":0.16124, "fx":[-0.12231,0.5792,0.12248,-0.57904], "fy":[-0.57902,-0.1223,0.57922,0.12249]}, + {"t":3.03297, "x":2.4291, "y":6.3037, "heading":2.13629, "vx":2.3193, "vy":-1.90159, "omega":-0.30585, "ax":0.0, "ay":0.0, "alpha":0.34899, "fx":[-0.27944,1.25033,0.27948,-1.25029], "fy":[-1.25028,-0.27944,1.25033,0.27948]}, + {"t":3.07022, "x":2.51549, "y":6.23287, "heading":2.1249, "vx":2.3193, "vy":-1.90159, "omega":-0.29285, "ax":0.0, "ay":0.0, "alpha":0.5622, "fx":[-0.47311,2.00893,0.47312,-2.00892], "fy":[-2.00892,-0.47311,2.00893,0.47312]}, + {"t":3.10747, "x":2.60189, "y":6.16203, "heading":2.11399, "vx":2.3193, "vy":-1.90159, "omega":-0.2719, "ax":0.0, "ay":0.0, "alpha":0.81625, "fx":[-0.71867,2.90903,0.71868,-2.90902], "fy":[-2.90902,-0.71867,2.90903,0.71868]}, + {"t":3.14472, "x":2.68828, "y":6.0912, "heading":2.10386, "vx":2.3193, "vy":-1.90159, "omega":-0.2415, "ax":0.0, "ay":0.0, "alpha":1.12908, "fx":[-1.03482,4.01367,1.03483,-4.01366], "fy":[-4.01366,-1.03482,4.01366,1.03482]}, + {"t":3.18197, "x":2.77467, "y":6.02036, "heading":2.09487, "vx":2.3193, "vy":-1.90159, "omega":-0.19944, "ax":0.0, "ay":0.0, "alpha":1.52224, "fx":[-1.44379,5.39849,1.44377,-5.39851], "fy":[-5.39852,-1.4438,5.39849,1.44377]}, + {"t":3.21922, "x":2.86107, "y":5.94953, "heading":2.08744, "vx":2.3193, "vy":-1.90159, "omega":-0.14274, "ax":-0.00032, "ay":0.00025, "alpha":2.02178, "fx":[-1.97624,7.15023,1.96533,-7.16101], "fy":[-7.15131,-1.96647,7.15993,1.97511]}, + {"t":3.25647, "x":2.94746, "y":5.87869, "heading":2.08212, "vx":2.31928, "vy":-1.90158, "omega":-0.06743, "ax":-2.53363, "ay":2.07733, "alpha":1.57542, "fx":[-46.10168,-38.08022,-40.32598,-47.87721], "fy":[29.00782,35.18781,41.4857,35.65767]}, + {"t":3.29372, "x":3.0321, "y":5.8093, "heading":2.07961, "vx":2.22491, "vy":-1.82419, "omega":-0.00874, "ax":-4.9288, "ay":4.04111, "alpha":0.04565, "fx":[-84.02855,-83.75062,-83.64659,-83.92411], "fy":[68.50204,68.83797,68.97343,68.63905]}, + {"t":3.33097, "x":3.11156, "y":5.74415, "heading":2.07929, "vx":2.04131, "vy":-1.67366, "omega":-0.00704, "ax":-4.96136, "ay":4.0678, "alpha":0.02812, "fx":[-84.51012,-84.33842,-84.27244,-84.44398], "fy":[69.04622,69.25471,69.33782,69.12992]}, + {"t":3.36822, "x":3.18415, "y":5.68463, "heading":2.07902, "vx":1.8565, "vy":-1.52214, "omega":-0.00599, "ax":-4.97236, "ay":4.07683, "alpha":0.02222, "fx":[-84.67275,-84.53692,-84.48425,-84.61998], "fy":[69.23018,69.39538,69.461,69.29617]}, + {"t":3.40547, "x":3.24986, "y":5.63076, "heading":2.0788, "vx":1.67128, "vy":-1.37027, "omega":-0.00517, "ax":-4.97789, "ay":4.08136, "alpha":0.01927, "fx":[-84.75444,-84.63661,-84.5907,-84.70845], "fy":[69.32259,69.46601,69.52289,69.37976]}, + {"t":3.44272, "x":3.30866, "y":5.58255, "heading":2.07861, "vx":1.48585, "vy":-1.21824, "omega":-0.00445, "ax":-4.98122, "ay":4.08409, "alpha":0.0175, "fx":[-84.80357,-84.69656,-84.65473,-84.76168], "fy":[69.37817,69.50848,69.56013,69.43005]}, + {"t":3.47997, "x":3.36055, "y":5.54, "heading":2.07844, "vx":1.3003, "vy":-1.06611, "omega":-0.0038, "ax":-4.98344, "ay":4.08591, "alpha":0.01631, "fx":[-84.83636,-84.73657,-84.69748,-84.79722], "fy":[69.41527,69.53683,69.58499,69.46363]}, + {"t":3.51722, "x":3.40553, "y":5.50312, "heading":2.0783, "vx":1.11466, "vy":-0.91391, "omega":-0.00319, "ax":-4.98503, "ay":4.08721, "alpha":0.01547, "fx":[-84.85981,-84.76518,-84.72805,-84.82263], "fy":[69.44179,69.5571,69.60277,69.48765]}, + {"t":3.55447, "x":3.44359, "y":5.47192, "heading":2.07818, "vx":0.92897, "vy":-0.76166, "omega":-0.00261, "ax":-4.98622, "ay":4.08819, "alpha":0.01484, "fx":[-84.87741,-84.78664,-84.75098,-84.84171], "fy":[69.46169,69.5723,69.61611,69.50567]}, + {"t":3.59172, "x":3.47474, "y":5.44638, "heading":2.07808, "vx":0.74323, "vy":-0.60938, "omega":-0.00206, "ax":-4.98715, "ay":4.08895, "alpha":0.01434, "fx":[-84.8911,-84.80334,-84.76883,-84.85655], "fy":[69.47717,69.58414,69.6265,69.51969]}, + {"t":3.62897, "x":3.49896, "y":5.42652, "heading":2.07801, "vx":0.55746, "vy":-0.45706, "omega":-0.00152, "ax":-4.98789, "ay":4.08956, "alpha":0.01395, "fx":[-84.90206,-84.81671,-84.78312,-84.86843], "fy":[69.48956,69.59361,69.63481,69.53091]}, + {"t":3.66622, "x":3.51627, "y":5.41233, "heading":2.07795, "vx":0.37166, "vy":-0.30473, "omega":-0.00101, "ax":-4.9885, "ay":4.09006, "alpha":0.01363, "fx":[-84.91103,-84.82764,-84.79481,-84.87815], "fy":[69.4997,69.60136,69.64161,69.5401]}, + {"t":3.70347, "x":3.52665, "y":5.40382, "heading":2.07791, "vx":0.18584, "vy":-0.15237, "omega":-0.0005, "ax":-4.989, "ay":4.09047, "alpha":0.01336, "fx":[-84.9185,-84.83676,-84.80455,-84.88626], "fy":[69.50816,69.60782,69.64728,69.54775]}, + {"t":3.74072, "x":3.53011, "y":5.40098, "heading":2.07789, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/v2_redundancy/choreo/C_RIGHT_PATH1.traj b/src/main/deploy/v2_redundancy/choreo/C_RIGHT_PATH1.traj new file mode 100644 index 00000000..2561be80 --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/C_RIGHT_PATH1.traj @@ -0,0 +1,67 @@ +{ + "name":"C_RIGHT_PATH1", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.171988010406494, "y":2.0378777980804443, "heading":-1.5707963267948966, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":5.227500915527344, "y":2.669785725402832, "heading":-1.102853734231975, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":3.0}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"7.171988010406494 m", "val":7.171988010406494}, "y":{"exp":"2.0378777980804443 m", "val":2.0378777980804443}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"5.227500915527344 m", "val":5.227500915527344}, "y":{"exp":"(8.0518 - 5.382014274597168) m", "val":2.669785725402832}, "heading":{"exp":"-1.102853734231975 rad", "val":-1.102853734231975}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"3 m / s", "val":3.0}}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.14764], + "samples":[ + {"t":0.0, "x":7.17199, "y":2.03788, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.13369, "ay":1.99373, "alpha":0.54554, "fx":[-103.18885,-103.8138,-105.39894,-104.92794], "fy":[37.34934,35.5929,30.5751,32.13399]}, + {"t":0.03825, "x":7.1675, "y":2.03934, "heading":-1.5708, "vx":-0.23464, "vy":0.07627, "omega":0.02087, "ax":-6.13303, "ay":1.99353, "alpha":0.55225, "fx":[-103.16301,-103.79708,-105.40046,-104.92409], "fy":[37.38834,35.60953,30.53177,32.10819]}, + {"t":0.07651, "x":7.15404, "y":2.04371, "heading":-1.57, "vx":-0.46926, "vy":0.15253, "omega":0.042, "ax":-6.13224, "ay":1.9933, "alpha":0.5603, "fx":[-103.13149,-103.77795,-105.4027,-104.91859], "fy":[37.43649,35.62677,30.47829,32.08006]}, + {"t":0.11476, "x":7.1316, "y":2.05101, "heading":-1.56839, "vx":-0.70385, "vy":0.22879, "omega":0.06343, "ax":-6.13127, "ay":1.993, "alpha":0.57014, "fx":[-103.0925,-103.75538,-105.40576,-104.91112], "fy":[37.49648,35.64556,30.41168,32.04805]}, + {"t":0.15302, "x":7.10019, "y":2.06122, "heading":-1.56596, "vx":-0.9384, "vy":0.30503, "omega":0.08524, "ax":-6.13006, "ay":1.99264, "alpha":0.58244, "fx":[-103.04338,-103.72779,-105.4098,-104.90119], "fy":[37.57233,35.66728,30.3275,32.00982]}, + {"t":0.19127, "x":7.0598, "y":2.07434, "heading":-1.5627, "vx":-1.1729, "vy":0.38126, "omega":0.10752, "ax":-6.12849, "ay":1.99217, "alpha":0.59828, "fx":[-102.97992,-103.69272,-105.41508,-104.88806], "fy":[37.67037,35.69411,30.21875,31.96169]}, + {"t":0.22953, "x":7.01045, "y":2.09039, "heading":-1.55859, "vx":-1.40735, "vy":0.45747, "omega":0.13041, "ax":-6.12641, "ay":1.99154, "alpha":0.6194, "fx":[-102.89508,-103.64611,-105.42197,-104.87045], "fy":[37.80112,35.7297,30.07384,31.89747]}, + {"t":0.26778, "x":6.95213, "y":2.10934, "heading":-1.5536, "vx":-1.64171, "vy":0.53365, "omega":0.1541, "ax":-6.12347, "ay":1.99066, "alpha":0.649, "fx":[-102.77611,-103.58061,-105.43112,-104.8461], "fy":[37.98358,35.7806,29.87189,31.80594]}, + {"t":0.30604, "x":6.88484, "y":2.13122, "heading":-1.54771, "vx":-1.87597, "vy":0.6098, "omega":0.17893, "ax":-6.11905, "ay":1.98932, "alpha":0.69345, "fx":[-102.59737,-103.48164,-105.44369,-104.81042], "fy":[38.25568,35.85984,29.57135,31.66448]}, + {"t":0.34429, "x":6.8086, "y":2.156, "heading":-1.54086, "vx":-2.11005, "vy":0.68591, "omega":0.20546, "ax":-6.11163, "ay":1.98709, "alpha":0.76761, "fx":[-102.29835,-103.31553,-105.46193,-104.75249], "fy":[38.70588,35.99747,29.07588,31.41981]}, + {"t":0.38255, "x":6.72341, "y":2.18369, "heading":-1.533, "vx":-2.34385, "vy":0.76192, "omega":0.23482, "ax":-6.09661, "ay":1.98254, "alpha":0.916, "fx":[-101.69461,-102.98304,-105.49005,-104.63854], "fy":[39.59866,36.2815,28.10007,30.90973]}, + {"t":0.4208, "x":6.62929, "y":2.21429, "heading":-1.52402, "vx":-2.57707, "vy":0.83776, "omega":0.26987, "ax":-6.0502, "ay":1.9684, "alpha":1.35978, "fx":[-99.83146,-102.01087,-105.52058,-104.2856], "fy":[42.23835,37.12497,25.26533,29.29874]}, + {"t":0.45906, "x":6.52627, "y":2.24778, "heading":-1.5137, "vx":-2.80852, "vy":0.91306, "omega":0.32188, "ax":-1.15127, "ay":0.34475, "alpha":23.14124, "fx":[29.40485,-76.22442,-78.22874,46.71744], "fy":[81.92133,54.45671,-47.97777,-64.94369]}, + {"t":0.49731, "x":6.41799, "y":2.28296, "heading":-1.50138, "vx":-2.85256, "vy":0.92625, "omega":1.20715, "ax":0.00113, "ay":0.00488, "alpha":19.89595, "fx":[47.92404,-55.0499,-47.95598,55.15868], "fy":[55.17379,48.03647,-55.03466,-47.84338]}, + {"t":0.53557, "x":6.30887, "y":2.3184, "heading":-1.4552, "vx":-2.85252, "vy":0.92644, "omega":1.96826, "ax":-0.00296, "ay":-0.00951, "alpha":7.26449, "fx":[16.51487,-20.96547,-16.59833,20.84761], "fy":[20.74972,16.38973,-21.06312,-16.72342]}, + {"t":0.57382, "x":6.19974, "y":2.35383, "heading":-1.37991, "vx":-2.85263, "vy":0.92607, "omega":2.24617, "ax":0.00447, "ay":0.01414, "alpha":-7.40226, "fx":[-15.15614,22.59981,15.28443,-22.42382], "fy":[-22.28081,-14.96991,22.7423,15.47061]}, + {"t":0.61208, "x":6.09062, "y":2.38927, "heading":-1.29398, "vx":-2.85246, "vy":0.92662, "omega":1.96299, "ax":0.00047, "ay":0.00003, "alpha":-19.77502, "fx":[-35.33973,63.4137,35.35921,-63.40087], "fy":[-63.40989,-35.34584,63.40468,35.3531]}, + {"t":0.65033, "x":5.9815, "y":2.42472, "heading":-1.21889, "vx":-2.85244, "vy":0.92662, "omega":1.2065, "ax":1.14734, "ay":-0.3575, "alpha":-23.08858, "fx":[-4.47729,86.49693,64.10522,-68.06119], "fy":[-89.01342,-36.76432,63.86289,37.59063]}, + {"t":0.68859, "x":5.87322, "y":2.4599, "heading":-1.17273, "vx":-2.80855, "vy":0.91294, "omega":0.32325, "ax":6.05065, "ay":-1.96747, "alpha":-1.35374, "fx":[99.65943,103.03896,105.73861,103.24207], "fy":[-42.76097,-34.19842,-24.16251,-32.74282]}, + {"t":0.72684, "x":5.7702, "y":2.49339, "heading":-1.16037, "vx":-2.57709, "vy":0.83768, "omega":0.27147, "ax":6.09677, "ay":-1.98203, "alpha":-0.91712, "fx":[101.53333,103.72236,105.67002,103.89138], "fy":[-40.05526,-34.12236,-27.35748,-33.31985]}, + {"t":0.7651, "x":5.67608, "y":2.52398, "heading":-1.14998, "vx":-2.34386, "vy":0.76185, "omega":0.23638, "ax":6.11172, "ay":-1.98673, "alpha":-0.77035, "fx":[102.14572,103.9662,105.62691,104.09531], "fy":[-39.13368,-34.07979,-28.43739,-33.52411]}, + {"t":0.80335, "x":5.59089, "y":2.55167, "heading":-1.14094, "vx":-2.11005, "vy":0.68585, "omega":0.20691, "ax":6.1191, "ay":-1.98905, "alpha":-0.69688, "fx":[102.4491,104.09354,105.6017,104.19237], "fy":[-38.67004,-34.04791,-28.97879,-33.63624]}, + {"t":0.84161, "x":5.51465, "y":2.57645, "heading":-1.13302, "vx":-1.87597, "vy":0.60976, "omega":0.18025, "ax":6.1235, "ay":-1.99044, "alpha":-0.65281, "fx":[102.63014,104.17276,105.58546,104.24788], "fy":[-38.39106,-34.02201,-29.30377,-33.71027]}, + {"t":0.87986, "x":5.44736, "y":2.59832, "heading":-1.12613, "vx":-1.64171, "vy":0.53362, "omega":0.15528, "ax":6.12643, "ay":-1.99136, "alpha":-0.62345, "fx":[102.75042,104.22722,105.57419,104.28325], "fy":[-38.20473,-34.00049,-29.52043,-33.76393]}, + {"t":0.91812, "x":5.38904, "y":2.61728, "heading":-1.12019, "vx":-1.40735, "vy":0.45744, "omega":0.13143, "ax":6.12851, "ay":-1.99201, "alpha":-0.60249, "fx":[102.83614,104.26705,105.56591,104.30757], "fy":[-38.07144,-33.98262,-29.67521,-33.80479]}, + {"t":0.95637, "x":5.33969, "y":2.63332, "heading":-1.11516, "vx":-1.1729, "vy":0.38123, "omega":0.10838, "ax":6.13007, "ay":-1.9925, "alpha":-0.58678, "fx":[102.90032,104.29738,105.55957,104.32536], "fy":[-37.97136,-33.96801,-29.79134,-33.83663]}, + {"t":0.99463, "x":5.2993, "y":2.64645, "heading":-1.11101, "vx":-0.9384, "vy":0.30501, "omega":0.08593, "ax":6.13127, "ay":-1.99288, "alpha":-0.57457, "fx":[102.95017,104.32107,105.55455,104.3391], "fy":[-37.89345,-33.95645,-29.88173,-33.86153]}, + {"t":1.03288, "x":5.26789, "y":2.65666, "heading":-1.10773, "vx":-0.70385, "vy":0.22877, "omega":0.06395, "ax":6.13224, "ay":-1.99318, "alpha":-0.56481, "fx":[102.98999,104.33985,105.55047,104.35029], "fy":[-37.83111,-33.94779,-29.95412,-33.88079]}, + {"t":1.07114, "x":5.24545, "y":2.66395, "heading":-1.10528, "vx":-0.46926, "vy":0.15252, "omega":0.04235, "ax":6.13303, "ay":-1.99343, "alpha":-0.55682, "fx":[103.02253,104.35484,105.54708,104.35986], "fy":[-37.78012,-33.94192,-30.01343,-33.89519]}, + {"t":1.10939, "x":5.23199, "y":2.66833, "heading":-1.10366, "vx":-0.23464, "vy":0.07627, "omega":0.02105, "ax":6.13369, "ay":-1.99364, "alpha":-0.55017, "fx":[103.0496,104.36677,105.54421,104.36845], "fy":[-37.73768,-33.93878,-30.06294,-33.9053]}, + {"t":1.14764, "x":5.2275, "y":2.66979, "heading":-1.10285, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/v2_redundancy/choreo/C_RIGHT_PATH2.traj b/src/main/deploy/v2_redundancy/choreo/C_RIGHT_PATH2.traj new file mode 100644 index 00000000..0e9b845a --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/C_RIGHT_PATH2.traj @@ -0,0 +1,181 @@ +{ + "name":"C_RIGHT_PATH2", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":5.281756401062012, "y":2.964472519683838, "heading":-1.0513369818883893, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":4.582683086395264, "y":2.4232380264282227, "heading":0.0, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":3.5206298828125, "y":2.2525508277893067, "heading":0.0, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":1.6289232969284058, "y":1.3508695363998413, "heading":-2.216612130911823, "intervals":22, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.0456665754318235, "y":0.6667511463165283, "heading":-2.216612130911823, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":3.599963426589966, "y":2.7183375358581543, "heading":-2.09887087685183, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":3.0}}, "enabled":true}, + {"from":3, "to":4, "data":{"type":"MaxVelocity", "props":{"max":1.0}}, "enabled":true}, + {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"5.281756401062012 m", "val":5.281756401062012}, "y":{"exp":"(8.0518 - 5.087327480316162) m", "val":2.964472519683838}, "heading":{"exp":"-1.0513369818883893 rad", "val":-1.0513369818883893}, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"4.582683086395264 m", "val":4.582683086395264}, "y":{"exp":"(8.0518 - 5.628561973571777) m", "val":2.4232380264282227}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"3.5206298828125 m", "val":3.5206298828125}, "y":{"exp":"(8.0518 - 5.799249172210693) m", "val":2.2525508277893067}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"1.6289232969284058 m", "val":1.6289232969284058}, "y":{"exp":"1.3508695363998413 m", "val":1.3508695363998413}, "heading":{"exp":"-2.216612130911823 rad", "val":-2.216612130911823}, "intervals":22, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.0456665754318237 m", "val":1.0456665754318235}, "y":{"exp":"0.6667511463165283 m", "val":0.6667511463165283}, "heading":{"exp":"-2.216612130911823 rad", "val":-2.216612130911823}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"3.599963426589966 m", "val":3.599963426589966}, "y":{"exp":"2.7183375358581543 m", "val":2.7183375358581543}, "heading":{"exp":"-2.09887087685183 rad", "val":-2.09887087685183}, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"3 m / s", "val":3.0}}}, "enabled":true}, + {"from":3, "to":4, "data":{"type":"MaxVelocity", "props":{"max":{"exp":"1 m / s", "val":1.0}}}, "enabled":true}, + {"from":4, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.53079,0.89269,1.69734,2.67683,4.23537], + "samples":[ + {"t":0.0, "x":5.28176, "y":2.96447, "heading":-1.05134, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-4.57103, "ay":-4.54736, "alpha":-0.10718, "fx":[-77.4787,-77.26901,-78.02964,-78.23048], "fy":[-77.62662,-77.83278,-77.0695,-76.86824]}, + {"t":0.02413, "x":5.28043, "y":2.96315, "heading":-1.05134, "vx":-0.11028, "vy":-0.10971, "omega":-0.00259, "ax":-4.60002, "ay":-4.51721, "alpha":-0.1097, "fx":[-77.96409,-77.75568,-78.53047,-78.72964], "fy":[-77.12521,-77.33254,-76.54488,-76.34284]}, + {"t":0.04825, "x":5.27643, "y":2.95919, "heading":-1.0514, "vx":-0.22127, "vy":-0.2187, "omega":-0.00523, "ax":-4.63201, "ay":-4.48346, "alpha":-0.1125, "fx":[-78.49989,-78.29313,-79.08331,-79.28039], "fy":[-76.56425,-76.77263,-75.95763,-75.755]}, + {"t":0.07238, "x":5.26974, "y":2.95261, "heading":-1.05153, "vx":-0.33302, "vy":-0.32687, "omega":-0.00795, "ax":-4.6675, "ay":-4.44545, "alpha":-0.11562, "fx":[-79.09421,-78.8896,-79.69655,-79.89098], "fy":[-75.93264,-76.14186,-75.29598,-75.09305]}, + {"t":0.09651, "x":5.26035, "y":2.94343, "heading":-1.05172, "vx":-0.44563, "vy":-0.43412, "omega":-0.01074, "ax":-4.70708, "ay":-4.40234, "alpha":-0.11913, "fx":[-79.75696,-79.55516,-80.38042,-80.5715], "fy":[-75.21636,-75.42608,-74.54509,-74.3423]}, + {"t":0.12063, "x":5.24823, "y":2.93167, "heading":-1.05198, "vx":-0.5592, "vy":-0.54034, "omega":-0.01361, "ax":-4.75147, "ay":-4.35302, "alpha":-0.12309, "fx":[-80.50037,-80.30224,-81.14753,-81.33431], "fy":[-74.39749,-74.60719,-73.68594,-73.48394]}, + {"t":0.14476, "x":5.23335, "y":2.91737, "heading":-1.0523, "vx":-0.67384, "vy":-0.64536, "omega":-0.01658, "ax":-4.80158, "ay":-4.2961, "alpha":-0.1276, "fx":[-81.33965,-81.14633,-82.01355,-82.19478], "fy":[-73.45276,-73.66162,-72.6938,-72.49358]}, + {"t":0.16889, "x":5.2157, "y":2.90055, "heading":-1.0527, "vx":-0.78968, "vy":-0.74901, "omega":-0.01966, "ax":-4.85856, "ay":-4.22971, "alpha":-0.13279, "fx":[-82.29389,-82.10694,-82.99814,-83.17217], "fy":[-72.35145,-72.55823,-71.53599,-71.33901]}, + {"t":0.19301, "x":5.19523, "y":2.88124, "heading":-1.05318, "vx":-0.9069, "vy":-0.85106, "omega":-0.02286, "ax":-4.92385, "ay":-4.15134, "alpha":-0.13881, "fx":[-83.38738,-83.2089,-84.12622,-84.29082], "fy":[-71.05221,-71.25501,-70.16845,-69.97692]}, + {"t":0.21714, "x":5.17192, "y":2.8595, "heading":-1.05373, "vx":-1.0257, "vy":-0.95122, "omega":-0.02621, "ax":-4.9993, "ay":-4.05754, "alpha":-0.14587, "fx":[-84.65122,-84.48411,-85.42965,-85.58179], "fy":[-69.49817,-69.69402,-68.53048,-68.34777]}, + {"t":0.24127, "x":5.14571, "y":2.83537, "heading":-1.05436, "vx":-1.14632, "vy":-1.04911, "omega":-0.02973, "ax":-5.0873, "ay":-3.94343, "alpha":-0.15426, "fx":[-86.12565,-85.97393,-86.94941,-87.08492], "fy":[-67.60918,-67.79339,-66.53637,-66.36776]}, + {"t":0.26539, "x":5.11658, "y":2.80891, "heading":-1.05508, "vx":-1.26906, "vy":-1.14425, "omega":-0.03345, "ax":-5.19093, "ay":-3.80195, "alpha":-0.16438, "fx":[-87.86291,-87.73223,-88.73831,-88.85142], "fy":[-65.269,-65.43397,-64.06166,-63.91556]}, + {"t":0.28952, "x":5.08445, "y":2.7802, "heading":-1.05589, "vx":-1.3943, "vy":-1.23598, "omega":-0.03742, "ax":-5.31416, "ay":-3.62249, "alpha":-0.17677, "fx":[-89.93056,-89.8289,-90.86372,-90.94642], "fy":[-62.3036,-62.43669,-60.91972,-60.80999]}, + {"t":0.31365, "x":5.04926, "y":2.74932, "heading":-1.05679, "vx":-1.52251, "vy":-1.32338, "omega":-0.04168, "ax":-5.46194, "ay":-3.3886, "alpha":-0.19225, "fx":[-92.41367,-92.35221,-93.40831,-93.44965], "fy":[-58.44275,-58.52213,-56.82051,-56.77076]}, + {"t":0.33777, "x":5.01094, "y":2.71641, "heading":-1.0578, "vx":-1.65429, "vy":-1.40514, "omega":-0.04632, "ax":-5.63977, "ay":-3.07366, "alpha":-0.21196, "fx":[-95.41038,-95.40412,-96.46165,-96.44759], "fy":[-53.24954,-53.23604,-51.29532,-51.34737]}, + {"t":0.3619, "x":4.96938, "y":2.68161, "heading":-1.05891, "vx":-1.79036, "vy":-1.47929, "omega":-0.05144, "ax":-5.85169, "ay":-2.63291, "alpha":-0.23757, "fx":[-99.00115,-99.06707,-100.07876,-99.99513], "fy":[-45.98766,-45.80783,-43.55689,-43.78773]}, + {"t":0.38603, "x":4.92449, "y":2.64516, "heading":-1.06015, "vx":-1.93154, "vy":-1.54282, "omega":-0.05717, "ax":-6.092, "ay":-1.9887, "alpha":-0.27128, "fx":[-103.12403,-103.26765,-104.12629,-103.97491], "fy":[-35.3739,-34.88566,-32.2472,-32.80207]}, + {"t":0.41015, "x":4.87611, "y":2.60736, "heading":-1.06153, "vx":-2.07852, "vy":-1.5908, "omega":-0.06371, "ax":-6.31727, "ay":-1.00833, "alpha":-0.31496, "fx":[-107.13215,-107.2879,-107.76842,-107.63104], "fy":[-19.18542,-18.11987,-15.07915,-16.22148]}, + {"t":0.43428, "x":4.82413, "y":2.56868, "heading":-1.06307, "vx":-2.23093, "vy":-1.61513, "omega":-0.07131, "ax":-6.3642, "ay":0.49544, "alpha":-0.36558, "fx":[-108.44602,-108.27935,-108.02962,-108.25764], "fy":[5.84661,7.88773,11.03063,8.94422]}, + {"t":0.45841, "x":4.76845, "y":2.52986, "heading":-1.06479, "vx":-2.38448, "vy":-1.60317, "omega":-0.08013, "ax":-5.82917, "ay":2.57168, "alpha":-0.40224, "fx":[-100.30034,-98.96956,-97.97999,-99.36025], "fy":[41.08311,44.10673,46.37033,43.41397]}, + {"t":0.48253, "x":4.70922, "y":2.49193, "heading":-1.06672, "vx":-2.52512, "vy":-1.54113, "omega":-0.08984, "ax":-4.39081, "ay":4.61485, "alpha":-0.38625, "fx":[-76.43841,-73.6238,-72.96755,-75.71569], "fy":[76.79097,79.47381,80.1485,77.57577]}, + {"t":0.50666, "x":4.64702, "y":2.45609, "heading":-1.06889, "vx":-2.63105, "vy":-1.42979, "omega":-0.09916, "ax":-2.95433, "ay":5.65491, "alpha":-0.32251, "fx":[-51.7005,-48.72507,-48.8485,-51.73484], "fy":[95.40889,96.96314,96.94587,95.43591]}, + {"t":0.53079, "x":4.58268, "y":2.42324, "heading":-1.07128, "vx":-2.70233, "vy":-1.29335, "omega":-0.10694, "ax":-2.72065, "ay":5.72767, "alpha":-0.30504, "fx":[-47.60832,-44.76456,-44.98701,-47.74975], "fy":[96.76165,98.1133,98.07382,96.7554]}, + {"t":0.54652, "x":4.53983, "y":2.4036, "heading":-1.07297, "vx":-2.74514, "vy":-1.20323, "omega":-0.11174, "ax":-2.45789, "ay":5.82834, "alpha":-0.33197, "fx":[-43.212,-40.07016,-40.45274,-43.4971], "fy":[98.50707,99.83415,99.75453,98.45799]}, + {"t":0.56226, "x":4.49633, "y":2.38539, "heading":-1.07473, "vx":-2.78381, "vy":-1.11152, "omega":-0.11696, "ax":-2.24759, "ay":5.89245, "alpha":-0.36375, "fx":[-39.72464,-36.25358,-36.79547,-40.14942], "fy":[99.61017,100.93809,100.83338,99.53372]}, + {"t":0.57799, "x":4.45225, "y":2.36863, "heading":-1.07657, "vx":-2.81918, "vy":-1.0188, "omega":-0.12268, "ax":-2.0426, "ay":5.94212, "alpha":-0.4018, "fx":[-36.34133,-32.48785,-33.21766,-36.92947], "fy":[100.46265,101.79414,101.67242,100.36565]}, + {"t":0.59373, "x":4.40764, "y":2.35333, "heading":-1.0785, "vx":-2.85132, "vy":-0.92531, "omega":-0.12901, "ax":-1.83683, "ay":5.97873, "alpha":-0.44804, "fx":[-32.96053,-28.65486,-29.61383,-33.7465], "fy":[101.08869,102.4231,102.29492,100.97946]}, + {"t":0.60946, "x":4.36254, "y":2.33951, "heading":-1.08053, "vx":-2.88022, "vy":-0.83123, "omega":-0.13606, "ax":-1.63004, "ay":6.00053, "alpha":-0.50513, "fx":[-29.58324,-24.73422,-25.97683,-30.61199], "fy":[101.45593,102.79256,102.6739,101.34712]}, + {"t":0.62519, "x":4.31702, "y":2.32717, "heading":-1.08267, "vx":-2.90587, "vy":-0.73682, "omega":-0.144, "ax":-1.42277, "ay":6.00459, "alpha":-0.57699, "fx":[-26.22529,-20.71157,-22.3107,-27.55599], "fy":[101.51005,102.84899,102.76497,101.42166]}, + {"t":0.64093, "x":4.27112, "y":2.31632, "heading":-1.08493, "vx":-2.92825, "vy":-0.64234, "omega":-0.15308, "ax":-1.21576, "ay":5.98648, "alpha":-0.6695, "fx":[-22.90981,-16.56602,-18.62144,-24.62183], "fy":[101.16755,102.51099,102.5023,101.13245]}, + {"t":0.65666, "x":4.2249, "y":2.30696, "heading":-1.08734, "vx":-2.94738, "vy":-0.54814, "omega":-0.16362, "ax":-1.01008, "ay":5.93928, "alpha":-0.7919, "fx":[-19.67026,-12.26498,-14.91695,-21.87236], "fy":[100.29536,101.65046,101.78572,100.36994]}, + {"t":0.6724, "x":4.1784, "y":2.29907, "heading":-1.08992, "vx":-2.96328, "vy":-0.45469, "omega":-0.17608, "ax":-0.80726, "ay":5.85167, "alpha":-0.95942, "fx":[-16.55759,-7.75674,-11.2083,-19.40213], "fy":[98.67021,100.05656,100.45705,98.95685]}, + {"t":0.68813, "x":4.13167, "y":2.29264, "heading":-1.09269, "vx":-2.97598, "vy":-0.36261, "omega":-0.19117, "ax":-0.60969, "ay":5.70411, "alpha":-1.19877, "fx":[-13.6539,-2.95754,-7.51237,-17.35883], "fy":[95.89265,97.36222,98.25529,96.59095]}, + {"t":0.70387, "x":4.08477, "y":2.28764, "heading":-1.09569, "vx":-2.98557, "vy":-0.27286, "omega":-0.21004, "ax":-0.42134, "ay":5.46033, "alpha":-1.56063, "fx":[-11.10009,2.27129,-3.85647,-15.98243], "fy":[91.18511,92.88156,94.72572,92.72254]}, + {"t":0.7196, "x":4.03774, "y":2.28402, "heading":-1.099, "vx":-2.9922, "vy":-0.18694, "omega":-0.23459, "ax":-0.2492, "ay":5.04615, "alpha":-2.15207, "fx":[-9.1533,8.1604,-0.28665,-15.67563], "fy":[82.84878,85.20633,89.01649,86.26276]}, + {"t":0.73534, "x":3.99063, "y":2.28171, "heading":-1.10269, "vx":-2.99612, "vy":-0.10754, "omega":-0.26845, "ax":-0.10637, "ay":4.28785, "alpha":-3.23079, "fx":[-8.28869,15.04289,3.12012,-17.11127], "fy":[66.54156,71.05942,79.35026,74.78914]}, + {"t":0.75107, "x":3.94347, "y":2.28054, "heading":-1.10691, "vx":-2.9978, "vy":-0.04008, "omega":-0.31929, "ax":-0.01737, "ay":2.72851, "alpha":-5.38723, "fx":[-8.96148,22.68557,6.22797,-21.13408], "fy":[30.19631,42.00114,61.32714,52.1198]}, + {"t":0.76681, "x":3.8963, "y":2.28025, "heading":-1.11194, "vx":-2.99807, "vy":0.00286, "omega":-0.40406, "ax":-0.00005, "ay":-0.17273, "alpha":-7.24236, "fx":[-8.43206,25.09263,8.63965,-25.3034], "fy":[-27.96809,-11.59533,22.36469,5.44618]}, + {"t":0.78254, "x":3.84912, "y":2.28027, "heading":-1.1183, "vx":-2.99807, "vy":0.00014, "omega":-0.51801, "ax":0.02368, "ay":-2.98096, "alpha":-4.60385, "fx":[-5.58718,18.71657,8.21326,-19.7318], "fy":[-62.95264,-55.41375,-37.60167,-46.85308]}, + {"t":0.79828, "x":3.80195, "y":2.27991, "heading":-1.12645, "vx":-2.9977, "vy":-0.04677, "omega":-0.59045, "ax":0.1209, "ay":-4.41579, "alpha":-2.52804, "fx":[-2.25847,14.24117,7.43032,-11.18679], "fy":[-79.88316,-76.53928,-70.39047,-73.63231]}, + {"t":0.81401, "x":3.7548, "y":2.27863, "heading":-1.13574, "vx":-2.9958, "vy":-0.11625, "omega":-0.63023, "ax":0.26854, "ay":-5.11625, "alpha":-1.55202, "fx":[1.29196,12.84951,8.40018,-4.27031], "fy":[-89.20699,-87.36628,-84.94579,-86.58464]}, + {"t":0.82975, "x":3.7077, "y":2.27616, "heading":-1.14565, "vx":-2.99157, "vy":-0.19675, "omega":-0.65465, "ax":0.44337, "ay":-5.50207, "alpha":-1.03692, "fx":[4.96113,13.35764,10.42846,1.41918], "fy":[-94.76805,-93.52245,-92.46715,-93.59702]}, + {"t":0.84548, "x":3.66068, "y":2.27239, "heading":-1.15595, "vx":-2.98459, "vy":-0.28332, "omega":-0.67097, "ax":0.63328, "ay":-5.73008, "alpha":-0.73441, "fx":[8.68553,14.9782,13.03628,6.38784], "fy":[-98.20943,-97.2358,-96.75131,-97.67134]}, + {"t":0.86122, "x":3.6138, "y":2.26722, "heading":-1.16651, "vx":-2.97463, "vy":-0.37348, "omega":-0.68252, "ax":0.83312, "ay":-5.86778, "alpha":-0.54275, "fx":[12.4502,17.28781,16.00008,10.9464], "fy":[-100.34183,-99.51349,-99.28678,-100.09492]}, + {"t":0.87695, "x":3.56709, "y":2.26062, "heading":-1.17725, "vx":-2.96152, "vy":-0.46581, "omega":-0.69106, "ax":1.09063, "ay":-5.93934, "alpha":-0.41426, "fx":[17.09343,20.89033,20.07779,16.14396], "fy":[-101.46435,-100.69635,-100.58933,-101.35592]}, + {"t":0.89269, "x":3.52063, "y":2.25255, "heading":-1.18813, "vx":-2.94436, "vy":-0.55927, "omega":-0.69758, "ax":1.25632, "ay":-6.05749, "alpha":-0.40157, "fx":[19.84501,23.62184,22.96332,19.04852], "fy":[-103.46043,-102.6345,-102.60938,-103.44033]}, + {"t":0.91951, "x":3.44211, "y":2.23537, "heading":-1.20684, "vx":-2.91066, "vy":-0.72174, "omega":-0.70835, "ax":1.61015, "ay":-5.82093, "alpha":-0.54725, "fx":[25.18852,30.16406,29.71226,24.48765], "fy":[-99.82829,-98.40689,-98.17276,-99.64155]}, + {"t":0.94633, "x":3.36462, "y":2.21392, "heading":-1.22583, "vx":-2.86748, "vy":-0.87787, "omega":-0.72303, "ax":1.82486, "ay":-5.45716, "alpha":-0.80819, "fx":[27.81519,34.69901,34.50885,27.13829], "fy":[-94.37316,-92.04667,-91.19935,-93.67954]}, + {"t":0.97315, "x":3.28837, "y":2.18841, "heading":-1.24523, "vx":-2.81853, "vy":-1.02424, "omega":-0.74471, "ax":1.86789, "ay":-4.79458, "alpha":-1.32319, "fx":[27.00166,36.97868,37.05488,26.05412], "fy":[-84.69334,-80.94224,-78.20244,-82.3799]}, + {"t":0.99997, "x":3.21344, "y":2.15921, "heading":-1.2652, "vx":-2.76843, "vy":-1.15283, "omega":-0.7802, "ax":1.54645, "ay":-3.54047, "alpha":-2.30164, "fx":[19.97081,34.13745,33.58599,17.52445], "fy":[-66.71894,-61.39518,-53.33319,-59.44218]}, + {"t":1.02679, "x":3.13974, "y":2.12702, "heading":-1.28613, "vx":-2.72695, "vy":-1.2478, "omega":-0.84193, "ax":0.87189, "ay":-1.86019, "alpha":-3.20637, "fx":[8.42749,24.9836,22.06831,3.84298], "fy":[-41.62666,-36.2154,-21.4577,-27.26572]}, + {"t":1.05362, "x":3.06691, "y":2.09288, "heading":-1.30871, "vx":-2.70357, "vy":-1.29769, "omega":-0.92793, "ax":0.3627, "ay":-0.7485, "alpha":-3.06366, "fx":[0.51255,15.79205,12.12374,-3.75072], "fy":[-22.42972,-18.18144,-3.00549,-7.31041]}, + {"t":1.08044, "x":2.99453, "y":2.05781, "heading":-1.3336, "vx":-2.69384, "vy":-1.31777, "omega":-1.0101, "ax":0.13671, "ay":-0.27849, "alpha":-2.54743, "fx":[-2.53143,10.2712,7.25887,-5.69678], "fy":[-12.71503,-9.59013,3.24252,0.11432]}, + {"t":1.10726, "x":2.92233, "y":2.02236, "heading":-1.36069, "vx":-2.69017, "vy":-1.32524, "omega":-1.07843, "ax":0.05032, "ay":-0.102, "alpha":-2.08359, "fx":[-3.2988,7.26445,5.02926,-5.57147], "fy":[-8.15291,-5.89396,4.68219,2.42465]}, + {"t":1.13408, "x":2.85019, "y":1.98678, "heading":-1.38962, "vx":-2.68882, "vy":-1.32797, "omega":-1.13432, "ax":0.01845, "ay":-0.03733, "alpha":-1.72985, "fx":[-3.29186,5.53748,3.92419,-4.91457], "fy":[-5.8612,-4.24225,4.59079,2.97276]}, + {"t":1.1609, "x":2.77808, "y":1.95115, "heading":-1.42004, "vx":-2.68833, "vy":-1.32897, "omega":-1.18071, "ax":0.00699, "ay":-0.01413, "alpha":-1.48337, "fx":[-3.10906,4.50346,3.3482,-4.26692], "fy":[-4.6257,-3.46887,4.14468,2.98826]}, + {"t":1.18772, "x":2.70597, "y":1.9155, "heading":-1.45171, "vx":-2.68814, "vy":-1.32935, "omega":-1.2205, "ax":0.00339, "ay":-0.00684, "alpha":-1.33772, "fx":[-2.9775,3.91781,3.09322,-3.80311], "fy":[-3.97688,-3.15166,3.74404,2.91904]}, + {"t":1.21455, "x":2.63387, "y":1.87984, "heading":-1.48445, "vx":-2.68805, "vy":-1.32954, "omega":-1.25638, "ax":0.00365, "ay":-0.00737, "alpha":-1.29054, "fx":[-2.98631,3.68828,3.11095,-3.56463], "fy":[-3.75189,-3.17391,3.50101,2.92332]}, + {"t":1.24137, "x":2.56178, "y":1.84418, "heading":-1.51814, "vx":-2.68795, "vy":-1.32973, "omega":-1.29099, "ax":0.00808, "ay":-0.01631, "alpha":-1.34543, "fx":[-3.16595,3.80826,3.44187,-3.53469], "fy":[-3.94919,-3.58111,3.39377,3.02655]}, + {"t":1.26819, "x":2.48969, "y":1.80851, "heading":-1.55277, "vx":-2.68773, "vy":-1.33017, "omega":-1.32708, "ax":0.0216, "ay":-0.04361, "alpha":-1.51378, "fx":[-3.48905,4.36514,4.22769,-3.63422], "fy":[-4.7424,-4.59865,3.2571,3.11684]}, + {"t":1.29501, "x":2.4176, "y":1.77281, "heading":-1.58837, "vx":-2.68716, "vy":-1.33134, "omega":-1.36768, "ax":0.05925, "ay":-0.11939, "alpha":-1.81681, "fx":[-3.78593,5.63255,5.81616,-3.63171], "fy":[-6.66771,-6.82228,2.5982,2.76864]}, + {"t":1.32183, "x":2.34555, "y":1.73706, "heading":-1.62505, "vx":-2.68557, "vy":-1.33454, "omega":-1.41641, "ax":0.16249, "ay":-0.32563, "alpha":-2.28238, "fx":[-3.469,8.32351,9.05714,-2.8562], "fy":[-11.15749,-11.73098,0.0415,0.69173]}, + {"t":1.34865, "x":2.27358, "y":1.70115, "heading":-1.66304, "vx":-2.68121, "vy":-1.34328, "omega":-1.47763, "ax":0.44116, "ay":-0.86506, "alpha":-2.88019, "fx":[-0.73857,14.08698,15.98345,0.68426], "fy":[-21.61003,-22.53538,-7.98813,-6.72443]}, + {"t":1.37548, "x":2.20182, "y":1.66481, "heading":-1.70267, "vx":-2.66938, "vy":-1.36648, "omega":-1.55488, "ax":4.32147, "ay":0.54788, "alpha":-1.53896, "fx":[71.42755,75.90201,75.66374,71.03478], "fy":[4.62477,2.72155,13.52502,16.406]}, + {"t":1.4023, "x":2.13178, "y":1.62835, "heading":-1.74438, "vx":-2.55347, "vy":-1.35178, "omega":-1.59616, "ax":5.7045, "ay":2.67727, "alpha":-0.11131, "fx":[97.07439,97.36726,96.99274,96.69352], "fy":[45.40666,44.83006,45.67171,46.24967]}, + {"t":1.42912, "x":2.06534, "y":1.59306, "heading":-1.78719, "vx":-2.40046, "vy":-1.27997, "omega":-1.59914, "ax":5.74631, "ay":2.76648, "alpha":-0.05229, "fx":[97.75885,97.90649,97.72795,97.57893], "fy":[47.01394,46.71815,47.10006,47.39587]}, + {"t":1.45594, "x":2.00303, "y":1.55972, "heading":-1.83008, "vx":-2.24634, "vy":-1.20577, "omega":-1.60055, "ax":5.76061, "ay":2.79777, "alpha":-0.02817, "fx":[97.99155,98.07577,97.98143,97.89683], "fy":[47.57492,47.40536,47.60372,47.77322]}, + {"t":1.48276, "x":1.94485, "y":1.52839, "heading":-1.87301, "vx":-2.09183, "vy":-1.13073, "omega":-1.6013, "ax":5.76782, "ay":2.81373, "alpha":-0.01421, "fx":[98.10974,98.15439,98.10826,98.06352], "fy":[47.85781,47.76772,47.86385,47.9539]}, + {"t":1.50958, "x":1.89081, "y":1.49907, "heading":-1.91596, "vx":-1.93712, "vy":-1.05526, "omega":-1.60168, "ax":5.77216, "ay":2.82342, "alpha":-0.00482, "fx":[98.18234,98.1982,98.18312,98.16725], "fy":[48.02593,47.9939,48.02516,48.05718]}, + {"t":1.53641, "x":1.84093, "y":1.47179, "heading":-1.95892, "vx":-1.7823, "vy":-0.97953, "omega":-1.60181, "ax":5.77505, "ay":2.82992, "alpha":0.00202, "fx":[98.23237,98.22546,98.2315,98.2384], "fy":[48.13541,48.14937,48.1369,48.12294]}, + {"t":1.56323, "x":1.79521, "y":1.44653, "heading":-2.00188, "vx":-1.62741, "vy":-0.90363, "omega":-1.60176, "ax":5.77712, "ay":2.83459, "alpha":0.00727, "fx":[98.26964,98.24379,98.26453,98.29036], "fy":[48.21081,48.26307,48.22035,48.16807]}, + {"t":1.59005, "x":1.75364, "y":1.42331, "heading":-2.04484, "vx":-1.47246, "vy":-0.8276, "omega":-1.60156, "ax":5.77866, "ay":2.83811, "alpha":0.01145, "fx":[98.29902,98.25691,98.28786,98.32994], "fy":[48.26463,48.3498,48.28616,48.20092]}, + {"t":1.61687, "x":1.71622, "y":1.40214, "heading":-2.0878, "vx":-1.31746, "vy":-0.75148, "omega":-1.60126, "ax":5.77987, "ay":2.84085, "alpha":0.01487, "fx":[98.3232,98.2668,98.30466,98.36101], "fy":[48.3039,48.41798,48.34023,48.22604]}, + {"t":1.64369, "x":1.68296, "y":1.383, "heading":-2.13075, "vx":-1.16244, "vy":-0.67528, "omega":-1.60086, "ax":5.78083, "ay":2.84305, "alpha":0.01771, "fx":[98.34374,98.27463,98.31688,98.38593], "fy":[48.33292,48.47274,48.38608,48.24608]}, + {"t":1.67051, "x":1.65386, "y":1.36591, "heading":-2.17369, "vx":-1.00739, "vy":-0.59903, "omega":-1.60038, "ax":5.78162, "ay":2.84485, "alpha":0.02013, "fx":[98.36166,98.28111,98.32574,98.40623], "fy":[48.35446,48.51743,48.42595,48.26271]}, + {"t":1.69734, "x":1.62892, "y":1.35087, "heading":-2.21661, "vx":-0.85231, "vy":-0.52272, "omega":-1.59984, "ax":3.86553, "ay":-4.7164, "alpha":0.70926, "fx":[69.00756,67.67086,62.31603,64.01169], "fy":[-77.7202,-78.36816,-82.81858,-81.9916]}, + {"t":1.74186, "x":1.59481, "y":1.32292, "heading":-2.28784, "vx":-0.68021, "vy":-0.73271, "omega":-1.56827, "ax":0.86763, "ay":-0.76488, "alpha":9.04916, "fx":[46.62442,14.84838,-19.52034,17.08033], "fy":[-10.98486,21.59778,-17.82732,-44.82716]}, + {"t":1.78638, "x":1.56538, "y":1.28954, "heading":-2.35766, "vx":-0.64158, "vy":-0.76676, "omega":-1.16537, "ax":0.02284, "ay":-0.01909, "alpha":8.39322, "fx":[31.16983,0.46522,-30.45394,0.37324], "fy":[-0.39476,30.51281,-0.30557,-31.11132]}, + {"t":1.8309, "x":1.53684, "y":1.25538, "heading":-2.40955, "vx":-0.64056, "vy":-0.76761, "omega":-0.79169, "ax":0.00055, "ay":-0.00046, "alpha":7.26453, "fx":[26.63938,1.43224,-26.62177,-1.41223], "fy":[-1.43048,26.62312,1.41398,-26.63802]}, + {"t":1.87543, "x":1.50832, "y":1.22121, "heading":-2.4448, "vx":-0.64054, "vy":-0.76763, "omega":-0.46825, "ax":0.00001, "ay":-0.00001, "alpha":6.20759, "fx":[22.69924,2.01672,-22.69883,-2.01626], "fy":[-2.01668,22.69886,2.0163,-22.69921]}, + {"t":1.91995, "x":1.4798, "y":1.18703, "heading":-2.46565, "vx":-0.64054, "vy":-0.76764, "omega":-0.19187, "ax":0.0, "ay":0.0, "alpha":5.22335, "fx":[19.06049,2.09456,-19.06048,-2.09455], "fy":[-2.09456,19.06048,2.09456,-19.06049]}, + {"t":1.96447, "x":1.45128, "y":1.15285, "heading":-2.47419, "vx":-0.64054, "vy":-0.76764, "omega":0.04068, "ax":0.0, "ay":0.0, "alpha":4.3089, "fx":[15.70822,1.86212,-15.70822,-1.86212], "fy":[-1.86212,15.70822,1.86212,-15.70822]}, + {"t":2.00899, "x":1.42277, "y":1.11868, "heading":-2.47238, "vx":-0.64054, "vy":-0.76764, "omega":0.23253, "ax":0.0, "ay":0.0, "alpha":3.45826, "fx":[12.60989,1.47167,-12.60989,-1.47167], "fy":[-1.47167,12.60989,1.47167,-12.60989]}, + {"t":2.05352, "x":1.39425, "y":1.0845, "heading":-2.46202, "vx":-0.64054, "vy":-0.76764, "omega":0.3865, "ax":0.0, "ay":0.0, "alpha":2.66309, "fx":[9.72164,1.0327,-9.72164,-1.0327], "fy":[-1.0327,9.72164,1.0327,-9.72164]}, + {"t":2.09804, "x":1.36573, "y":1.05032, "heading":-2.44482, "vx":-0.64054, "vy":-0.76764, "omega":0.50507, "ax":0.0, "ay":0.0, "alpha":1.91323, "fx":[6.99603,0.62163,-6.99603,-0.62163], "fy":[-0.62163,6.99603,0.62163,-6.99603]}, + {"t":2.14256, "x":1.33721, "y":1.01615, "heading":-2.42233, "vx":-0.64054, "vy":-0.76764, "omega":0.59025, "ax":0.0, "ay":0.0, "alpha":1.19737, "fx":[4.38599,0.29049,-4.38599,-0.29049], "fy":[-0.29049,4.38599,0.29049,-4.38599]}, + {"t":2.18708, "x":1.30869, "y":0.98197, "heading":-2.39605, "vx":-0.64054, "vy":-0.76764, "omega":0.64356, "ax":0.0, "ay":0.0, "alpha":0.50337, "fx":[1.84644,0.07363,-1.84644,-0.07363], "fy":[-0.07363,1.84644,0.07363,-1.84644]}, + {"t":2.23161, "x":1.28017, "y":0.94779, "heading":-2.3674, "vx":-0.64054, "vy":-0.76764, "omega":0.66597, "ax":0.0, "ay":0.0, "alpha":-0.18128, "fx":[-0.66546,-0.00746,0.66546,0.00746], "fy":[0.00746,-0.66546,-0.00746,0.66546]}, + {"t":2.27613, "x":1.25166, "y":0.91361, "heading":-2.33775, "vx":-0.64054, "vy":-0.76764, "omega":0.6579, "ax":0.0, "ay":0.0, "alpha":-0.86931, "fx":[-3.19075,0.05887,3.19075,-0.05887], "fy":[-0.05887,-3.19075,0.05887,3.19075]}, + {"t":2.32065, "x":1.22314, "y":0.87944, "heading":-2.30846, "vx":-0.64054, "vy":-0.76764, "omega":0.61919, "ax":0.0, "ay":0.0, "alpha":-1.57336, "fx":[-5.76932,0.27563,5.76932,-0.27563], "fy":[-0.27563,-5.76932,0.27563,5.76932]}, + {"t":2.36517, "x":1.19462, "y":0.84526, "heading":-2.28089, "vx":-0.64054, "vy":-0.76764, "omega":0.54914, "ax":0.0, "ay":0.0, "alpha":-2.30578, "fx":[-8.44065,0.63685,8.44065,-0.63685], "fy":[-0.63685,-8.44065,0.63685,8.44065]}, + {"t":2.4097, "x":1.1661, "y":0.81108, "heading":-2.25644, "vx":-0.64054, "vy":-0.76764, "omega":0.44648, "ax":0.0, "ay":0.0, "alpha":-3.07831, "fx":[-11.24447,1.12545,11.24447,-1.12545], "fy":[-1.12545,-11.24447,1.12545,11.24447]}, + {"t":2.45422, "x":1.13758, "y":0.77691, "heading":-2.23656, "vx":-0.64054, "vy":-0.76764, "omega":0.30943, "ax":0.00001, "ay":0.00001, "alpha":-3.90172, "fx":[-14.22083,1.70975,14.22131,-1.70926], "fy":[-1.70925,-14.22083,1.70976,14.22131]}, + {"t":2.49874, "x":1.10906, "y":0.74273, "heading":-2.22278, "vx":-0.64054, "vy":-0.76763, "omega":0.13572, "ax":1.99642, "ay":2.39256, "alpha":-3.01086, "fx":[22.36249,38.52059,44.52576,30.42506], "fy":[42.21741,29.46236,39.98658,51.12049]}, + {"t":2.54326, "x":1.08252, "y":0.71092, "heading":-2.21674, "vx":-0.55165, "vy":-0.66111, "omega":0.00166, "ax":4.12514, "ay":4.94367, "alpha":-0.01839, "fx":[70.09786,70.24394,70.23698,70.09114], "fy":[84.14805,84.02618,84.03278,84.15442]}, + {"t":2.58779, "x":1.06205, "y":0.68639, "heading":-2.21667, "vx":-0.36799, "vy":-0.44101, "omega":0.00085, "ax":4.13155, "ay":4.95134, "alpha":-0.01077, "fx":[70.23566,70.32134,70.31717,70.23156], "fy":[84.25485,84.18336,84.18707,84.25848]}, + {"t":2.63231, "x":1.04976, "y":0.67166, "heading":-2.21663, "vx":-0.18404, "vy":-0.22056, "omega":0.00037, "ax":4.13369, "ay":4.95391, "alpha":-0.00823, "fx":[70.28172,70.3472,70.34398,70.27855], "fy":[84.29053,84.23589,84.23869,84.29328]}, + {"t":2.67683, "x":1.04567, "y":0.66675, "heading":-2.21661, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.03084, "ay":4.04072, "alpha":0.00858, "fx":[85.59341,85.53936,85.55299,85.60706], "fy":[68.7065,68.77374,68.75666,68.68936]}, + {"t":2.72136, "x":1.05065, "y":0.67076, "heading":-2.21661, "vx":0.22402, "vy":0.17993, "omega":0.00038, "ax":5.03032, "ay":4.0403, "alpha":0.00879, "fx":[85.58497,85.52961,85.54356,85.59895], "fy":[68.69872,68.76759,68.75009,68.68116]}, + {"t":2.76589, "x":1.06562, "y":0.68278, "heading":-2.2166, "vx":0.44802, "vy":0.35985, "omega":0.00077, "ax":5.02966, "ay":4.03978, "alpha":0.00905, "fx":[85.57443,85.51743,85.53178,85.58881], "fy":[68.689,68.75991,68.74188,68.67091]}, + {"t":2.81042, "x":1.09055, "y":0.7028, "heading":-2.21656, "vx":0.67199, "vy":0.53974, "omega":0.00118, "ax":5.02882, "ay":4.0391, "alpha":0.00939, "fx":[85.56087,85.50176,85.51664,85.57578], "fy":[68.67651,68.75003,68.73133,68.65773]}, + {"t":2.85495, "x":1.12546, "y":0.73084, "heading":-2.21651, "vx":0.89592, "vy":0.7196, "omega":0.00159, "ax":5.02769, "ay":4.03819, "alpha":0.00984, "fx":[85.54281,85.48089,85.49645,85.55841], "fy":[68.65986,68.73687,68.71726,68.64017]}, + {"t":2.89948, "x":1.17034, "y":0.76689, "heading":-2.21644, "vx":1.1198, "vy":0.89942, "omega":0.00203, "ax":5.02612, "ay":4.03693, "alpha":0.01047, "fx":[85.51753,85.45167,85.4682,85.5341], "fy":[68.63656,68.71846,68.69758,68.61559]}, + {"t":2.94401, "x":1.22519, "y":0.81094, "heading":-2.21635, "vx":1.34362, "vy":1.07918, "omega":0.0025, "ax":5.02376, "ay":4.03504, "alpha":0.01141, "fx":[85.47965,85.40788,85.42586,85.49767], "fy":[68.60164,68.69085,68.66807,68.57875]}, + {"t":2.98854, "x":1.29, "y":0.863, "heading":-2.21624, "vx":1.56732, "vy":1.25886, "omega":0.00301, "ax":5.01984, "ay":4.03188, "alpha":0.01298, "fx":[85.4166,85.335,85.35536,85.43702], "fy":[68.54352,68.64492,68.61895,68.51742]}, + {"t":3.03307, "x":1.36477, "y":0.92305, "heading":-2.2161, "vx":1.79085, "vy":1.4384, "omega":0.00359, "ax":5.01201, "ay":4.0256, "alpha":0.01612, "fx":[85.2909,85.18967,85.21473,85.31605], "fy":[68.42764,68.55332,68.52096,68.39507]}, + {"t":3.0776, "x":1.44949, "y":0.9911, "heading":-2.21594, "vx":2.01404, "vy":1.61766, "omega":0.0043, "ax":4.98872, "ay":4.00689, "alpha":0.02551, "fx":[84.91715,84.75755,84.79607,84.9559], "fy":[68.08318,68.28081,68.22917,68.03102]}, + {"t":3.12213, "x":1.54412, "y":1.0671, "heading":-2.21575, "vx":2.23618, "vy":1.79608, "omega":0.00544, "ax":2.29611, "ay":1.84422, "alpha":1.32384, "fx":[43.43518,37.51154,34.5143,40.76385], "fy":[31.16918,36.46583,31.70577,26.1377]}, + {"t":3.16666, "x":1.64597, "y":1.14891, "heading":-2.21551, "vx":2.33843, "vy":1.8782, "omega":0.06439, "ax":0.00013, "ay":0.0001, "alpha":1.454, "fx":[5.2872,-0.74623,-5.28276,0.7507], "fy":[0.75023,5.28674,-0.74671,-5.28322]}, + {"t":3.21119, "x":1.7501, "y":1.23255, "heading":-2.21264, "vx":2.33843, "vy":1.87821, "omega":0.12914, "ax":0.0, "ay":0.0, "alpha":1.0371, "fx":[3.76808,-0.54467,-3.76808,0.54467], "fy":[0.54467,3.76808,-0.54467,-3.76808]}, + {"t":3.25572, "x":1.85423, "y":1.31618, "heading":-2.20689, "vx":2.33843, "vy":1.87821, "omega":0.17532, "ax":0.0, "ay":0.0, "alpha":0.72503, "fx":[2.632,-0.39592,-2.63201,0.39591], "fy":[0.39592,2.63201,-0.39591,-2.63201]}, + {"t":3.30025, "x":1.95836, "y":1.39982, "heading":-2.19908, "vx":2.33843, "vy":1.87821, "omega":0.2076, "ax":0.0, "ay":0.0, "alpha":0.48703, "fx":[1.76588,-0.27975,-1.76589,0.27974], "fy":[0.27975,1.76588,-0.27974,-1.76588]}, + {"t":3.34478, "x":2.06249, "y":1.48345, "heading":-2.18984, "vx":2.33843, "vy":1.87821, "omega":0.22929, "ax":0.0, "ay":0.0, "alpha":0.29914, "fx":[1.08298,-0.18184,-1.08299,0.18184], "fy":[0.18184,1.08299,-0.18184,-1.08298]}, + {"t":3.38931, "x":2.16662, "y":1.56709, "heading":-2.17963, "vx":2.33843, "vy":1.87821, "omega":0.24261, "ax":0.0, "ay":0.0, "alpha":0.14217, "fx":[0.51379,-0.09167,-0.51379,0.09167], "fy":[0.09167,0.51379,-0.09167,-0.51379]}, + {"t":3.43384, "x":2.27075, "y":1.65073, "heading":-2.16883, "vx":2.33843, "vy":1.87821, "omega":0.24894, "ax":0.0, "ay":0.0, "alpha":-0.00006, "fx":[-0.00021,0.00004,0.00021,-0.00004], "fy":[-0.00004,-0.00021,0.00004,0.00021]}, + {"t":3.47837, "x":2.37488, "y":1.73436, "heading":-2.15774, "vx":2.33843, "vy":1.87821, "omega":0.24894, "ax":0.0, "ay":0.0, "alpha":-0.14227, "fx":[-0.51203,0.10297,0.51203,-0.10297], "fy":[-0.10297,-0.51203,0.10297,0.51203]}, + {"t":3.5229, "x":2.47901, "y":1.818, "heading":-2.14666, "vx":2.33843, "vy":1.87821, "omega":0.2426, "ax":0.0, "ay":0.0, "alpha":-0.2992, "fx":[-1.07435,0.22847,1.07435,-0.22847], "fy":[-0.22847,-1.07435,0.22847,1.07435]}, + {"t":3.56743, "x":2.58314, "y":1.90163, "heading":-2.13585, "vx":2.33843, "vy":1.87821, "omega":0.22928, "ax":0.0, "ay":0.0, "alpha":-0.48704, "fx":[-1.74472,0.39078,1.74472,-0.39078], "fy":[-0.39078,-1.74472,0.39078,1.74472]}, + {"t":3.61196, "x":2.68727, "y":1.98527, "heading":-2.12564, "vx":2.33843, "vy":1.87821, "omega":0.20759, "ax":0.0, "ay":0.0, "alpha":-0.725, "fx":[-2.59109,0.6082,2.59109,-0.60819], "fy":[-0.6082,-2.59109,0.60819,2.59109]}, + {"t":3.65649, "x":2.7914, "y":2.06891, "heading":-2.1164, "vx":2.33843, "vy":1.87821, "omega":0.17531, "ax":0.0, "ay":0.0, "alpha":-1.03706, "fx":[-3.69816,0.9042,3.69815,-0.9042], "fy":[-0.9042,-3.69815,0.9042,3.69816]}, + {"t":3.70102, "x":2.89553, "y":2.15254, "heading":-2.10859, "vx":2.33843, "vy":1.87821, "omega":0.12913, "ax":-0.00013, "ay":-0.0001, "alpha":-1.45399, "fx":[-5.17711,1.30592,5.17266,-1.31039], "fy":[-1.30992,-5.17664,1.3064,5.17313]}, + {"t":3.74555, "x":2.99966, "y":2.23618, "heading":-2.10284, "vx":2.33843, "vy":1.8782, "omega":0.06438, "ax":-2.29611, "ay":-1.84422, "alpha":-1.32369, "fx":[-43.22717,-37.01729,-34.72878,-41.2516], "fy":[-31.73612,-36.47882,-31.10481,-26.15874]}, + {"t":3.79008, "x":3.10151, "y":2.31799, "heading":-2.09998, "vx":2.23618, "vy":1.79608, "omega":0.00544, "ax":-4.98872, "ay":-4.00689, "alpha":-0.02551, "fx":[-84.9053,-84.75118,-84.80797,-84.96222], "fy":[-68.09811,-68.28843,-68.21423,-68.02342]}, + {"t":3.8346, "x":3.19614, "y":2.39399, "heading":-2.09973, "vx":2.01404, "vy":1.61766, "omega":0.0043, "ax":-5.01201, "ay":-4.0256, "alpha":-0.01612, "fx":[-85.28332,-85.18567,-85.22233,-85.32004], "fy":[-68.43714,-68.5582,-68.51146,-68.39019]}, + {"t":3.87913, "x":3.28086, "y":2.46204, "heading":-2.09954, "vx":1.79085, "vy":1.4384, "omega":0.00359, "ax":-5.01984, "ay":-4.03188, "alpha":-0.01298, "fx":[-85.41046,-85.33178,-85.36152,-85.44024], "fy":[-68.5512,-68.64888,-68.61127,-68.51346]}, + {"t":3.92366, "x":3.35563, "y":2.52209, "heading":-2.09938, "vx":1.56732, "vy":1.25886, "omega":0.00301, "ax":-5.02376, "ay":-4.03504, "alpha":-0.01141, "fx":[-85.47423,-85.40504,-85.43128,-85.5005], "fy":[-68.6084,-68.69435,-68.6613,-68.57525]}, + {"t":3.96819, "x":3.42044, "y":2.57415, "heading":-2.09925, "vx":1.34362, "vy":1.07918, "omega":0.0025, "ax":-5.02612, "ay":-4.03693, "alpha":-0.01047, "fx":[-85.51255,-85.44906,-85.47319,-85.5367], "fy":[-68.64278,-68.72167,-68.69136,-68.61237]}, + {"t":4.01272, "x":3.47529, "y":2.6182, "heading":-2.09914, "vx":1.1198, "vy":0.89942, "omega":0.00203, "ax":-5.02769, "ay":-4.03819, "alpha":-0.00984, "fx":[-85.53811,-85.47843,-85.50115,-85.56085], "fy":[-68.66571,-68.7399,-68.7114,-68.63714]}, + {"t":4.05725, "x":3.52017, "y":2.65425, "heading":-2.09905, "vx":0.89592, "vy":0.7196, "omega":0.0016, "ax":-5.02882, "ay":-4.0391, "alpha":-0.00939, "fx":[-85.55639,-85.49942,-85.52113,-85.57811], "fy":[-68.68211,-68.75293,-68.72573,-68.65484]}, + {"t":4.10178, "x":3.55508, "y":2.68228, "heading":-2.09897, "vx":0.67199, "vy":0.53974, "omega":0.00118, "ax":-5.02966, "ay":-4.03978, "alpha":-0.00905, "fx":[-85.5701,-85.51517,-85.53612,-85.59106], "fy":[-68.6944,-68.76271,-68.73648,-68.66811]}, + {"t":4.14631, "x":3.58001, "y":2.70231, "heading":-2.09892, "vx":0.44802, "vy":0.35985, "omega":0.00077, "ax":-5.03032, "ay":-4.0403, "alpha":-0.00879, "fx":[-85.58076,-85.52742,-85.54778,-85.60114], "fy":[-68.70397,-68.77031,-68.74484,-68.67844]}, + {"t":4.19084, "x":3.59498, "y":2.71433, "heading":-2.09889, "vx":0.22402, "vy":0.17993, "omega":0.00038, "ax":-5.03084, "ay":-4.04072, "alpha":-0.00858, "fx":[-85.5893,-85.53722,-85.5571,-85.6092], "fy":[-68.71162,-68.7764,-68.75153,-68.6867]}, + {"t":4.23537, "x":3.59996, "y":2.71834, "heading":-2.09887, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/v2_redundancy/choreo/C_RIGHT_PATH3.traj b/src/main/deploy/v2_redundancy/choreo/C_RIGHT_PATH3.traj new file mode 100644 index 00000000..d384cbbf --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/C_RIGHT_PATH3.traj @@ -0,0 +1,137 @@ +{ + "name":"C_RIGHT_PATH3", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.999176502227783, "y":2.845594631958008, "heading":-2.1010083691287966, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.8789600133895872, "y":1.543542504310608, "heading":-2.217924532332081, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.1281020641326904, "y":0.6461422443389893, "heading":-2.217924532332081, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":3.533947706222534, "y":2.756060838699341, "heading":-2.077894951837786, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":3.0}}, "enabled":true}, + {"from":1, "to":2, "data":{"type":"MaxVelocity", "props":{"max":1.0}}, "enabled":true}, + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.999176502227783 m", "val":3.999176502227783}, "y":{"exp":"(8.0518 - 5.206205368041992) m", "val":2.845594631958008}, "heading":{"exp":"-2.1010083691287966 rad", "val":-2.1010083691287966}, "intervals":30, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.8789600133895874 m", "val":1.8789600133895872}, "y":{"exp":"1.543542504310608 m", "val":1.543542504310608}, "heading":{"exp":"-2.217924532332081 rad", "val":-2.217924532332081}, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.1281020641326904 m", "val":1.1281020641326904}, "y":{"exp":"0.6461422443389893 m", "val":0.6461422443389893}, "heading":{"exp":"-2.217924532332081 rad", "val":-2.217924532332081}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"3.533947706222534 m", "val":3.533947706222534}, "y":{"exp":"2.756060838699341 m", "val":2.756060838699341}, "heading":{"exp":"-2.077894951837786 rad", "val":-2.077894951837786}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"3 m / s", "val":3.0}}}, "enabled":true}, + {"from":1, "to":2, "data":{"type":"MaxVelocity", "props":{"max":{"exp":"1 m / s", "val":1.0}}}, "enabled":true}, + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.16593,2.41619,3.94926], + "samples":[ + {"t":0.0, "x":3.99918, "y":2.84559, "heading":-2.10101, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.52646, "ay":-3.32919, "alpha":-0.00621, "fx":[-94.01019,-93.98097,-93.99681,-94.02602], "fy":[-56.61761,-56.66604,-56.63965,-56.5912]}, + {"t":0.03886, "x":3.995, "y":2.84308, "heading":-2.10101, "vx":-0.21478, "vy":-0.12939, "omega":-0.00024, "ax":-5.52589, "ay":-3.32885, "alpha":-0.00635, "fx":[-94.00069,-93.97081,-93.98699,-94.01687], "fy":[-56.61155,-56.66106,-56.63407,-56.58453]}, + {"t":0.07773, "x":3.98248, "y":2.83554, "heading":-2.10102, "vx":-0.42954, "vy":-0.25876, "omega":-0.00049, "ax":-5.5252, "ay":-3.32844, "alpha":-0.00652, "fx":[-93.98918,-93.9585,-93.97511,-94.00579], "fy":[-56.6042,-56.65504,-56.62733,-56.57647]}, + {"t":0.11659, "x":3.96162, "y":2.82297, "heading":-2.10104, "vx":-0.64428, "vy":-0.38812, "omega":-0.00074, "ax":-5.52436, "ay":-3.32793, "alpha":-0.00673, "fx":[-93.97497,-93.9433,-93.96043,-93.9921], "fy":[-56.59513,-56.6476,-56.61899,-56.5665]}, + {"t":0.15546, "x":3.9324, "y":2.80537, "heading":-2.10107, "vx":-0.85898, "vy":-0.51746, "omega":-0.001, "ax":-5.52328, "ay":-3.32728, "alpha":-0.007, "fx":[-93.95697,-93.92404,-93.94184,-93.97477], "fy":[-56.58365,-56.63817,-56.60844,-56.55388]}, + {"t":0.19432, "x":3.89485, "y":2.78275, "heading":-2.1011, "vx":-1.07363, "vy":-0.64677, "omega":-0.00127, "ax":-5.52187, "ay":-3.32643, "alpha":-0.00735, "fx":[-93.93343,-93.89887,-93.91753,-93.9521], "fy":[-56.56863,-56.62585,-56.59464,-56.53738]}, + {"t":0.23319, "x":3.84895, "y":2.7551, "heading":-2.10115, "vx":-1.28824, "vy":-0.77605, "omega":-0.00156, "ax":-5.51996, "ay":-3.32528, "alpha":-0.00782, "fx":[-93.90135,-93.86454,-93.88439,-93.92119], "fy":[-56.54815,-56.60906,-56.57582,-56.51488]}, + {"t":0.27205, "x":3.79472, "y":2.72243, "heading":-2.10121, "vx":-1.50277, "vy":-0.90528, "omega":-0.00186, "ax":-5.51719, "ay":-3.32361, "alpha":-0.00851, "fx":[-93.85502,-93.81498,-93.83653,-93.87656], "fy":[-56.51859,-56.5848,-56.54865,-56.48239]}, + {"t":0.31091, "x":3.73215, "y":2.68473, "heading":-2.10129, "vx":-1.71719, "vy":-1.03445, "omega":-0.0022, "ax":-5.51284, "ay":-3.32099, "alpha":-0.00959, "fx":[-93.78228,-93.73714,-93.76135,-93.80647], "fy":[-56.47216,-56.54672,-56.50597,-56.43136]}, + {"t":0.34978, "x":3.66125, "y":2.64202, "heading":-2.10137, "vx":-1.93144, "vy":-1.16352, "omega":-0.00257, "ax":-5.50502, "ay":-3.31628, "alpha":-0.01154, "fx":[-93.65152,-93.59722,-93.62617,-93.68047], "fy":[-56.38871,-56.47825,-56.42924,-56.33961]}, + {"t":0.38864, "x":3.58202, "y":2.5943, "heading":-2.10147, "vx":-2.14539, "vy":-1.2924, "omega":-0.00302, "ax":-5.48684, "ay":-3.30533, "alpha":-0.01609, "fx":[-93.34754,-93.27185,-93.31167,-93.38734], "fy":[-56.19473,-56.319,-56.25068,-56.12623]}, + {"t":0.42751, "x":3.4945, "y":2.54157, "heading":-2.10159, "vx":-2.35863, "vy":-1.42086, "omega":-0.00364, "ax":-5.39749, "ay":-3.2515, "alpha":-0.03869, "fx":[-91.85595,-91.67418,-91.76355,-91.94522], "fy":[-55.24334,-55.53556,-55.37128,-55.07811]}, + {"t":0.46637, "x":3.39876, "y":2.4839, "heading":-2.10173, "vx":-2.5684, "vy":-1.54723, "omega":-0.00515, "ax":-0.01733, "ay":-0.01044, "alpha":-1.19309, "fx":[-4.53305,0.80725,3.94461,-1.39788], "fy":[-1.2801,-4.41645,0.9249,4.06132]}, + {"t":0.50524, "x":3.29893, "y":2.42376, "heading":-2.10193, "vx":-2.56908, "vy":-1.54764, "omega":-0.05151, "ax":0.0, "ay":0.0, "alpha":-0.91408, "fx":[-3.24776,0.84405,3.24776,-0.84406], "fy":[-0.8441,-3.24781,0.84401,3.24771]}, + {"t":0.5441, "x":3.19908, "y":2.36361, "heading":-2.10393, "vx":-2.56908, "vy":-1.54764, "omega":-0.08704, "ax":0.00001, "ay":-0.00001, "alpha":-0.70533, "fx":[-2.50726,0.64639,2.50748,-0.64617], "fy":[-0.64646,-2.50755,0.6461,2.50719]}, + {"t":0.58296, "x":3.09924, "y":2.30346, "heading":-2.10732, "vx":-2.56908, "vy":-1.54764, "omega":-0.11445, "ax":0.00003, "ay":-0.00005, "alpha":-0.55112, "fx":[-1.96031,0.49891,1.96142,-0.49779], "fy":[-0.49927,-1.96179,0.49743,1.95994]}, + {"t":0.62183, "x":2.99939, "y":2.24331, "heading":-2.11176, "vx":-2.56907, "vy":-1.54764, "omega":-0.13587, "ax":0.00017, "ay":-0.00028, "alpha":-0.4397, "fx":[-1.56331,0.39352,1.56908,-0.38775], "fy":[-0.39543,-1.57098,0.38584,1.5614]}, + {"t":0.66069, "x":2.89955, "y":2.18317, "heading":-2.11704, "vx":-2.56907, "vy":-1.54765, "omega":-0.15296, "ax":0.00088, "ay":-0.00146, "alpha":-0.36253, "fx":[-1.27802,0.33022,1.30797,-0.30028], "fy":[-0.34011,-1.31784,0.2904,1.26815]}, + {"t":0.69956, "x":2.7997, "y":2.12302, "heading":-2.12299, "vx":-2.56903, "vy":-1.54771, "omega":-0.16705, "ax":0.00457, "ay":-0.00758, "alpha":-0.31366, "fx":[-1.04264,0.34378,1.19798,-0.18843], "fy":[-0.39503,-1.2492,0.13718,0.99141]}, + {"t":0.73842, "x":2.69986, "y":2.06286, "heading":-2.12948, "vx":-2.56886, "vy":-1.548, "omega":-0.17924, "ax":0.0237, "ay":-0.03931, "alpha":-0.28931, "fx":[-0.63175,0.64187,1.4381,0.1645], "fy":[-0.90745,-1.70339,-0.42992,0.36631]}, + {"t":0.77729, "x":2.60004, "y":2.00267, "heading":-2.13645, "vx":-2.56793, "vy":-1.54953, "omega":-0.19048, "ax":0.12318, "ay":-0.20342, "alpha":-0.2869, "fx":[1.06644,2.32384,3.12408,1.86685], "fy":[-3.69118,-4.48675,-3.22983,-2.43279]}, + {"t":0.81615, "x":2.50033, "y":1.94229, "heading":-2.14385, "vx":-2.56315, "vy":-1.55743, "omega":-0.20163, "ax":0.68443, "ay":-0.97902, "alpha":-0.28813, "fx":[10.58831,11.83482,12.69485,11.45019], "fy":[-16.90807,-17.66569,-16.40104,-15.63635]}, + {"t":0.85501, "x":2.40124, "y":1.88103, "heading":-2.15169, "vx":-2.53655, "vy":-1.59548, "omega":-0.21283, "ax":5.48291, "ay":3.21429, "alpha":-0.00563, "fx":[93.25556,93.282,93.2698,93.24336], "fy":[54.6851,54.6408,54.66326,54.70754]}, + {"t":0.89388, "x":2.3068, "y":1.82145, "heading":-2.15996, "vx":-2.32346, "vy":-1.47056, "omega":-0.21305, "ax":5.51111, "ay":3.28047, "alpha":-0.00181, "fx":[93.74016,93.74881,93.74481,93.73616], "fy":[55.80354,55.78911,55.79606,55.81048]}, + {"t":0.93274, "x":2.22066, "y":1.76677, "heading":-2.16824, "vx":-2.10927, "vy":-1.34307, "omega":-0.21312, "ax":5.51891, "ay":3.29915, "alpha":-0.00041, "fx":[93.87458,93.87654,93.87565,93.87369], "fy":[56.11848,56.11522,56.11675,56.12001]}, + {"t":0.97161, "x":2.14285, "y":1.71706, "heading":-2.17652, "vx":-1.89478, "vy":-1.21485, "omega":-0.21314, "ax":5.52256, "ay":3.30797, "alpha":0.0004, "fx":[93.93765,93.93571,93.93657,93.93852], "fy":[56.26674,56.26997,56.2685,56.26526]}, + {"t":1.01047, "x":2.07338, "y":1.67235, "heading":-2.1848, "vx":-1.68015, "vy":-1.08629, "omega":-0.21312, "ax":5.52467, "ay":3.31311, "alpha":0.00094, "fx":[93.97429,93.96967,93.97169,93.9763], "fy":[56.35286,56.36053,56.35712,56.34945]}, + {"t":1.04934, "x":2.01226, "y":1.63263, "heading":-2.19309, "vx":-1.46544, "vy":-0.95753, "omega":-0.21308, "ax":5.52604, "ay":3.31647, "alpha":0.00134, "fx":[93.99825,93.99166,93.99448,94.00107], "fy":[56.4091,56.42005,56.4153,56.40434]}, + {"t":1.0882, "x":1.95948, "y":1.59792, "heading":-2.20137, "vx":-1.25068, "vy":-0.82863, "omega":-0.21303, "ax":5.52701, "ay":3.31884, "alpha":0.00165, "fx":[94.01516,94.00703,94.01043,94.01856], "fy":[56.44867,56.46218,56.45646,56.44295]}, + {"t":1.12707, "x":1.91504, "y":1.56823, "heading":-2.20965, "vx":-1.03587, "vy":-0.69965, "omega":-0.21297, "ax":5.52772, "ay":3.32061, "alpha":0.00189, "fx":[94.02774,94.01838,94.02221,94.03157], "fy":[56.47802,56.49357,56.48715,56.47159]}, + {"t":1.16593, "x":1.87896, "y":1.54354, "heading":-2.21792, "vx":-0.82104, "vy":-0.5706, "omega":-0.21289, "ax":3.68794, "ay":-4.07774, "alpha":0.19661, "fx":[63.56392,63.14491,61.88694,62.3274], "fy":[-68.75719,-68.7661,-69.97251,-69.94872]}, + {"t":1.21224, "x":1.84489, "y":1.51275, "heading":-2.22778, "vx":-0.65027, "vy":-0.75942, "omega":-0.20379, "ax":0.28252, "ay":-0.23777, "alpha":1.04598, "fx":[8.60888,4.3309,0.99349,5.28925], "fy":[-3.54645,-0.22937,-4.55501,-7.84695]}, + {"t":1.25854, "x":1.81509, "y":1.47733, "heading":-2.23722, "vx":-0.63718, "vy":-0.77043, "omega":-0.15535, "ax":0.00534, "ay":-0.00441, "alpha":0.89993, "fx":[3.37102,-0.30131,-3.18965,0.48294], "fy":[0.31702,3.20539,-0.46725,-3.35528]}, + {"t":1.30485, "x":1.78559, "y":1.44165, "heading":-2.24441, "vx":-0.63694, "vy":-0.77064, "omega":-0.11368, "ax":0.0001, "ay":-0.00008, "alpha":0.7677, "fx":[2.80237,-0.31268,-2.79898,0.31607], "fy":[0.31297,2.79928,-0.31578,-2.80208]}, + {"t":1.35115, "x":1.75609, "y":1.40596, "heading":-2.24968, "vx":-0.63693, "vy":-0.77064, "omega":-0.07813, "ax":0.0, "ay":0.0, "alpha":0.65313, "fx":[2.38414,-0.25488,-2.38407,0.25494], "fy":[0.25489,2.38408,-0.25494,-2.38413]}, + {"t":1.39746, "x":1.7266, "y":1.37028, "heading":-2.2533, "vx":-0.63693, "vy":-0.77064, "omega":-0.04789, "ax":0.0, "ay":0.0, "alpha":0.55362, "fx":[2.02164,-0.20876,-2.02164,0.20876], "fy":[0.20876,2.02164,-0.20876,-2.02164]}, + {"t":1.44377, "x":1.6971, "y":1.33459, "heading":-2.25551, "vx":-0.63693, "vy":-0.77064, "omega":-0.02225, "ax":0.0, "ay":0.0, "alpha":0.46689, "fx":[1.70529,-0.17227,-1.70529,0.17227], "fy":[0.17227,1.70529,-0.17227,-1.70529]}, + {"t":1.49007, "x":1.66761, "y":1.29891, "heading":-2.25654, "vx":-0.63693, "vy":-0.77064, "omega":-0.00063, "ax":0.0, "ay":0.0, "alpha":0.39093, "fx":[1.42802,-0.14278,-1.42802,0.14278], "fy":[0.14278,1.42802,-0.14278,-1.42802]}, + {"t":1.53638, "x":1.63812, "y":1.26322, "heading":-2.25657, "vx":-0.63693, "vy":-0.77064, "omega":0.01747, "ax":0.0, "ay":0.0, "alpha":0.32401, "fx":[1.18357,-0.1183,-1.18357,0.1183], "fy":[0.1183,1.18357,-0.1183,-1.18357]}, + {"t":1.58268, "x":1.60862, "y":1.22754, "heading":-2.25576, "vx":-0.63693, "vy":-0.77064, "omega":0.03247, "ax":0.0, "ay":0.0, "alpha":0.26458, "fx":[0.9664,-0.09738,-0.9664,0.09738], "fy":[0.09738,0.9664,-0.09738,-0.9664]}, + {"t":1.62899, "x":1.57913, "y":1.19185, "heading":-2.25426, "vx":-0.63693, "vy":-0.77064, "omega":0.04473, "ax":0.0, "ay":0.0, "alpha":0.21127, "fx":[0.77156,-0.07892,-0.77156,0.07892], "fy":[0.07892,0.77156,-0.07892,-0.77156]}, + {"t":1.6753, "x":1.54964, "y":1.15617, "heading":-2.25219, "vx":-0.63693, "vy":-0.77064, "omega":0.05451, "ax":0.0, "ay":0.0, "alpha":0.16285, "fx":[0.5946,-0.06207,-0.5946,0.06207], "fy":[0.06207,0.5946,-0.06207,-0.5946]}, + {"t":1.7216, "x":1.52014, "y":1.12048, "heading":-2.24966, "vx":-0.63693, "vy":-0.77064, "omega":0.06205, "ax":0.0, "ay":0.0, "alpha":0.1182, "fx":[0.43144,-0.04614,-0.43144,0.04614], "fy":[0.04614,0.43144,-0.04614,-0.43144]}, + {"t":1.76791, "x":1.49065, "y":1.08479, "heading":-2.24679, "vx":-0.63693, "vy":-0.77064, "omega":0.06752, "ax":0.0, "ay":0.0, "alpha":0.07628, "fx":[0.27834,-0.03057,-0.27834,0.03057], "fy":[0.03057,0.27834,-0.03057,-0.27834]}, + {"t":1.81421, "x":1.46115, "y":1.04911, "heading":-2.24366, "vx":-0.63693, "vy":-0.77064, "omega":0.07105, "ax":0.0, "ay":0.0, "alpha":0.03612, "fx":[0.13177,-0.01489,-0.13177,0.01489], "fy":[0.01489,0.13177,-0.01489,-0.13177]}, + {"t":1.86052, "x":1.43166, "y":1.01342, "heading":-2.24037, "vx":-0.63693, "vy":-0.77064, "omega":0.07273, "ax":0.0, "ay":0.0, "alpha":-0.00319, "fx":[-0.01164,0.00135,0.01164,-0.00135], "fy":[-0.00135,-0.01164,0.00135,0.01164]}, + {"t":1.90683, "x":1.40217, "y":0.97774, "heading":-2.23701, "vx":-0.63693, "vy":-0.77064, "omega":0.07258, "ax":0.0, "ay":0.0, "alpha":-0.04258, "fx":[-0.15521,0.01859,0.15521,-0.01859], "fy":[-0.01859,-0.15521,0.01859,0.15521]}, + {"t":1.95313, "x":1.37267, "y":0.94205, "heading":-2.23365, "vx":-0.63693, "vy":-0.77064, "omega":0.07061, "ax":0.0, "ay":0.0, "alpha":-0.08296, "fx":[-0.30226,0.03723,0.30226,-0.03723], "fy":[-0.03723,-0.30226,0.03723,0.30226]}, + {"t":1.99944, "x":1.34318, "y":0.90637, "heading":-2.23038, "vx":-0.63693, "vy":-0.77064, "omega":0.06677, "ax":0.0, "ay":0.0, "alpha":-0.12526, "fx":[-0.45618,0.0577,0.45618,-0.0577], "fy":[-0.0577,-0.45618,0.0577,0.45618]}, + {"t":2.04574, "x":1.31369, "y":0.87068, "heading":-2.22728, "vx":-0.63693, "vy":-0.77064, "omega":0.06097, "ax":0.0, "ay":0.0, "alpha":-0.17045, "fx":[-0.62054,0.08044,0.62054,-0.08044], "fy":[-0.08044,-0.62054,0.08044,0.62054]}, + {"t":2.09205, "x":1.28419, "y":0.835, "heading":-2.22446, "vx":-0.63693, "vy":-0.77064, "omega":0.05307, "ax":0.0, "ay":0.0, "alpha":-0.21959, "fx":[-0.79914,0.10589,0.79914,-0.10589], "fy":[-0.10589,-0.79914,0.10589,0.79914]}, + {"t":2.13836, "x":1.2547, "y":0.79931, "heading":-2.222, "vx":-0.63693, "vy":-0.77064, "omega":0.04291, "ax":0.0, "ay":0.0, "alpha":-0.27381, "fx":[-0.99614,0.13448,0.99614,-0.13448], "fy":[-0.13448,-0.99614,0.13448,0.99614]}, + {"t":2.18466, "x":1.2252, "y":0.76363, "heading":-2.22002, "vx":-0.63693, "vy":-0.77064, "omega":0.03023, "ax":0.00001, "ay":0.00001, "alpha":-0.33436, "fx":[-1.21598,0.16675,1.21622,-0.16652], "fy":[-0.1665,-1.21596,0.16678,1.21624]}, + {"t":2.23097, "x":1.19571, "y":0.72794, "heading":-2.21862, "vx":-0.63693, "vy":-0.77064, "omega":0.01474, "ax":1.43266, "ay":1.73341, "alpha":-0.31559, "fx":[23.21043,24.6721,25.52018,24.07378], "fy":[29.46899,28.34161,29.50621,30.62223]}, + {"t":2.27728, "x":1.16775, "y":0.69412, "heading":-2.21793, "vx":-0.57059, "vy":-0.69037, "omega":0.00013, "ax":4.10277, "ay":4.96403, "alpha":-0.00138, "fx":[69.78159,69.79263,69.79218,69.78114], "fy":[84.44109,84.43196,84.43239,84.44151]}, + {"t":2.32358, "x":1.14573, "y":0.66747, "heading":-2.21793, "vx":-0.38061, "vy":-0.46051, "omega":0.00007, "ax":4.10871, "ay":4.97122, "alpha":-0.0008, "fx":[69.88486,69.89127,69.89099,69.88459], "fy":[84.56152,84.55623,84.55647,84.56176]}, + {"t":2.36989, "x":1.13251, "y":0.65147, "heading":-2.21793, "vx":-0.19035, "vy":-0.23031, "omega":0.00003, "ax":4.11069, "ay":4.97362, "alpha":-0.00061, "fx":[69.91934,69.9242,69.92399,69.91913], "fy":[84.60173,84.59772,84.59789,84.60191]}, + {"t":2.41619, "x":1.1281, "y":0.64614, "heading":-2.21792, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.85121, "ay":4.2545, "alpha":0.01131, "fx":[82.54785,82.47214,82.48767,82.56344], "fy":[72.33362,72.4199,72.40205,72.31566]}, + {"t":2.46, "x":1.13276, "y":0.65022, "heading":-2.21792, "vx":0.21249, "vy":0.18635, "omega":0.0005, "ax":4.8507, "ay":4.25405, "alpha":0.0116, "fx":[82.53983,82.46217,82.47809,82.55581], "fy":[72.32503,72.41353,72.39521,72.3066]}, + {"t":2.5038, "x":1.14672, "y":0.66247, "heading":-2.2179, "vx":0.42496, "vy":0.37269, "omega":0.001, "ax":4.85005, "ay":4.25348, "alpha":0.01196, "fx":[82.52981,82.44971,82.46612,82.54628], "fy":[72.3143,72.40557,72.38666,72.29528]}, + {"t":2.5476, "x":1.16998, "y":0.68287, "heading":-2.21786, "vx":0.6374, "vy":0.559, "omega":0.00153, "ax":4.84922, "ay":4.25275, "alpha":0.01243, "fx":[82.51694,82.4337,82.45074,82.53404], "fy":[72.30051,72.39534,72.37568,72.28072]}, + {"t":2.5914, "x":1.20255, "y":0.71144, "heading":-2.21779, "vx":0.84981, "vy":0.74528, "omega":0.00207, "ax":4.84811, "ay":4.25178, "alpha":0.01306, "fx":[82.49978,82.41237,82.43025,82.51773], "fy":[72.28214,72.38172,72.36104,72.26133]}, + {"t":2.6352, "x":1.24443, "y":0.74816, "heading":-2.2177, "vx":1.06216, "vy":0.93151, "omega":0.00264, "ax":4.84657, "ay":4.25042, "alpha":0.01394, "fx":[82.4758,82.38255,82.40159,82.49492], "fy":[72.25645,72.36266,72.34057,72.23421]}, + {"t":2.679, "x":1.2956, "y":0.79304, "heading":-2.21759, "vx":1.27445, "vy":1.11769, "omega":0.00325, "ax":4.84425, "ay":4.24839, "alpha":0.01525, "fx":[82.43988,82.33789,82.35866,82.46076], "fy":[72.21799,72.33414,72.30992,72.19359]}, + {"t":2.72281, "x":1.35607, "y":0.84607, "heading":-2.21744, "vx":1.48664, "vy":1.30378, "omega":0.00392, "ax":4.8404, "ay":4.24501, "alpha":0.01744, "fx":[82.38021,82.26367,82.28731,82.40398], "fy":[72.15407,72.28673,72.25897,72.12606]}, + {"t":2.76661, "x":1.42583, "y":0.90725, "heading":-2.21727, "vx":1.69866, "vy":1.48972, "omega":0.00469, "ax":4.83274, "ay":4.23829, "alpha":0.02179, "fx":[82.26155,82.11607,82.14531,82.291], "fy":[72.02697,72.19244,72.15757,71.99172]}, + {"t":2.81041, "x":1.50487, "y":0.97657, "heading":-2.21707, "vx":1.91034, "vy":1.67536, "omega":0.00564, "ax":4.8101, "ay":4.21844, "alpha":0.03473, "fx":[81.91121,81.68033,81.72542,81.95683], "fy":[71.65185,71.9139,71.85763,71.59463]}, + {"t":2.85421, "x":1.59317, "y":1.054, "heading":-2.21682, "vx":2.12103, "vy":1.86014, "omega":0.00716, "ax":3.05791, "ay":2.68178, "alpha":1.19578, "fx":[55.8047,49.82347,48.03484,54.39352], "fy":[44.65064,50.32144,46.7923,40.70087]}, + {"t":2.89801, "x":1.689, "y":1.13805, "heading":-2.21651, "vx":2.25497, "vy":1.9776, "omega":0.05954, "ax":0.00024, "ay":0.00021, "alpha":1.99877, "fx":[7.27022,-1.0175,-7.26201,1.0258], "fy":[1.02523,7.26967,-1.01808,-7.26256]}, + {"t":2.94182, "x":1.78778, "y":1.22467, "heading":-2.2139, "vx":2.25498, "vy":1.97761, "omega":0.14709, "ax":0.0, "ay":0.0, "alpha":1.43258, "fx":[5.20591,-0.74583,-5.20591,0.74583], "fy":[0.74582,5.20591,-0.74583,-5.20592]}, + {"t":2.98562, "x":1.88655, "y":1.3113, "heading":-2.20745, "vx":2.25498, "vy":1.97761, "omega":0.20984, "ax":0.0, "ay":0.0, "alpha":1.00521, "fx":[3.64944,-0.54686,-3.64944,0.54685], "fy":[0.54686,3.64944,-0.54686,-3.64944]}, + {"t":3.02942, "x":1.98532, "y":1.39792, "heading":-2.19826, "vx":2.25498, "vy":1.97761, "omega":0.25387, "ax":0.0, "ay":0.0, "alpha":0.67709, "fx":[2.4547,-0.39093,-2.45471,0.39093], "fy":[0.39093,2.45471,-0.39093,-2.4547]}, + {"t":3.07322, "x":2.08409, "y":1.48454, "heading":-2.18714, "vx":2.25498, "vy":1.97761, "omega":0.28353, "ax":0.0, "ay":0.0, "alpha":0.41666, "fx":[1.50776,-0.25735,-1.50777,0.25734], "fy":[0.25735,1.50777,-0.25734,-1.50777]}, + {"t":3.11702, "x":2.18287, "y":1.57117, "heading":-2.17472, "vx":2.25498, "vy":1.97761, "omega":0.30178, "ax":0.0, "ay":0.0, "alpha":0.19822, "fx":[0.71572,-0.13133,-0.71573,0.13133], "fy":[0.13133,0.71572,-0.13133,-0.71572]}, + {"t":3.16082, "x":2.28164, "y":1.65779, "heading":-2.16151, "vx":2.25498, "vy":1.97761, "omega":0.31046, "ax":0.0, "ay":0.0, "alpha":-0.00013, "fx":[-0.00046,0.00009,0.00046,-0.00009], "fy":[-0.00009,-0.00046,0.00009,0.00046]}, + {"t":3.20463, "x":2.38041, "y":1.74441, "heading":-2.14791, "vx":2.25498, "vy":1.97761, "omega":0.31045, "ax":0.0, "ay":0.0, "alpha":-0.19844, "fx":[-0.71274,0.15064,0.71274,-0.15064], "fy":[-0.15064,-0.71274,0.15064,0.71274]}, + {"t":3.24843, "x":2.47918, "y":1.83104, "heading":-2.13431, "vx":2.25498, "vy":1.97761, "omega":0.30176, "ax":0.0, "ay":0.0, "alpha":-0.41679, "fx":[-1.49255,0.33672,1.49256,-0.33672], "fy":[-0.33672,-1.49256,0.33672,1.49255]}, + {"t":3.29223, "x":2.57796, "y":1.91766, "heading":-2.12109, "vx":2.25498, "vy":1.97761, "omega":0.28351, "ax":0.0, "ay":0.0, "alpha":-0.67712, "fx":[-2.41735,0.57904,2.41736,-0.57903], "fy":[-0.57904,-2.41736,0.57903,2.41735]}, + {"t":3.33603, "x":2.67673, "y":2.00428, "heading":-2.10867, "vx":2.25498, "vy":1.97761, "omega":0.25385, "ax":0.0, "ay":0.0, "alpha":-1.00516, "fx":[-3.57752,0.90406,3.57752,-0.90405], "fy":[-0.90405,-3.57752,0.90405,3.57752]}, + {"t":3.37983, "x":2.7755, "y":2.09091, "heading":-2.09755, "vx":2.25498, "vy":1.97761, "omega":0.20982, "ax":0.0, "ay":0.0, "alpha":-1.43251, "fx":[-5.08392,1.34503,5.08391,-1.34504], "fy":[-1.34503,-5.08391,1.34504,5.08392]}, + {"t":3.42364, "x":2.87427, "y":2.17753, "heading":-2.08836, "vx":2.25498, "vy":1.97761, "omega":0.14707, "ax":-0.00024, "ay":-0.00021, "alpha":-1.99878, "fx":[-7.08015,1.93767,7.07192,-1.946], "fy":[-1.94539,-7.07958,1.93828,7.07249]}, + {"t":3.46744, "x":2.97305, "y":2.26415, "heading":-2.08192, "vx":2.25497, "vy":1.9776, "omega":0.05952, "ax":-3.05791, "ay":-2.68178, "alpha":-1.19536, "fx":[-55.47543,-49.31048,-48.39096,-54.8796], "fy":[-45.29012,-50.43614,-46.11938,-40.61968]}, + {"t":3.51124, "x":3.06888, "y":2.3482, "heading":-2.07931, "vx":2.12103, "vy":1.86014, "omega":0.00716, "ax":-4.8101, "ay":-4.21844, "alpha":-0.03473, "fx":[-81.89141,-81.66882,-81.74533,-81.96824], "fy":[-71.67472,-71.92653,-71.83473,-71.58201]}, + {"t":3.55504, "x":3.15718, "y":2.42563, "heading":-2.079, "vx":1.91034, "vy":1.67536, "omega":0.00564, "ax":-4.83274, "ay":-4.23829, "alpha":-0.0218, "fx":[-82.24896,-82.10887,-82.15794,-82.29816], "fy":[-72.04142,-72.2005,-72.14312,-71.98367]}, + {"t":3.59884, "x":3.23622, "y":2.49495, "heading":-2.07875, "vx":1.69866, "vy":1.48972, "omega":0.00469, "ax":-4.8404, "ay":-4.24501, "alpha":-0.01744, "fx":[-82.37008,-82.2579,-82.29746,-82.40972], "fy":[-72.16567,-72.29322,-72.24736,-72.11958]}, + {"t":3.64265, "x":3.30598, "y":2.55613, "heading":-2.07855, "vx":1.48664, "vy":1.30378, "omega":0.00392, "ax":-4.84425, "ay":-4.24839, "alpha":-0.01525, "fx":[-82.43099,-82.33284,-82.36758,-82.46579], "fy":[-72.22817,-72.33984,-72.29974,-72.18789]}, + {"t":3.68645, "x":3.36645, "y":2.60916, "heading":-2.07838, "vx":1.27445, "vy":1.11769, "omega":0.00325, "ax":-4.84657, "ay":-4.25042, "alpha":-0.01394, "fx":[-82.46765,-82.37793,-82.40976,-82.49953], "fy":[-72.26577,-72.36789,-72.33125,-72.22898]}, + {"t":3.73025, "x":3.41762, "y":2.65404, "heading":-2.07823, "vx":1.06216, "vy":0.93151, "omega":0.00264, "ax":-4.84811, "ay":-4.25178, "alpha":-0.01306, "fx":[-82.49213,-82.40804,-82.43792,-82.52205], "fy":[-72.29089,-72.38663,-72.35229,-72.25642]}, + {"t":3.77405, "x":3.4595, "y":2.69077, "heading":-2.07812, "vx":0.84981, "vy":0.74528, "omega":0.00207, "ax":-4.84922, "ay":-4.25275, "alpha":-0.01243, "fx":[-82.50963,-82.42957,-82.45805,-82.53816], "fy":[-72.30886,-72.40003,-72.36733,-72.27604]}, + {"t":3.81785, "x":3.49207, "y":2.71933, "heading":-2.07803, "vx":0.6374, "vy":0.559, "omega":0.00153, "ax":-4.85005, "ay":-4.25348, "alpha":-0.01196, "fx":[-82.52278,-82.44573,-82.47317,-82.55025], "fy":[-72.32234,-72.41008,-72.37862,-72.29076]}, + {"t":3.86165, "x":3.51533, "y":2.73974, "heading":-2.07796, "vx":0.42496, "vy":0.37269, "omega":0.001, "ax":-4.8507, "ay":-4.25405, "alpha":-0.0116, "fx":[-82.53301,-82.45831,-82.48492,-82.55966], "fy":[-72.33283,-72.41791,-72.38741,-72.30222]}, + {"t":3.90546, "x":3.52929, "y":2.75198, "heading":-2.07792, "vx":0.21249, "vy":0.18635, "omega":0.0005, "ax":-4.85121, "ay":-4.2545, "alpha":-0.01131, "fx":[-82.54119,-82.46837,-82.49434,-82.56719], "fy":[-72.34123,-72.42417,-72.39444,-72.31139]}, + {"t":3.94926, "x":3.53395, "y":2.75606, "heading":-2.07789, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/Choreo.chor b/src/main/deploy/v2_redundancy/choreo/Choreo.chor similarity index 100% rename from src/main/deploy/choreo/Choreo.chor rename to src/main/deploy/v2_redundancy/choreo/Choreo.chor diff --git a/src/main/deploy/v2_redundancy/choreo/D_CENTER_PATH.traj b/src/main/deploy/v2_redundancy/choreo/D_CENTER_PATH.traj new file mode 100644 index 00000000..d555bce8 --- /dev/null +++ b/src/main/deploy/v2_redundancy/choreo/D_CENTER_PATH.traj @@ -0,0 +1,55 @@ +{ + "name":"D_CENTER_PATH", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.1445207595825195, "y":4.035357475280762, "heading":0.0, "intervals":18, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":5.994441509246826, "y":4.235998630523682, "heading":0.0, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":3.0}}, "enabled":true}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"7.1445207595825195 m", "val":7.1445207595825195}, "y":{"exp":"4.035357475280762 m", "val":4.035357475280762}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":18, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"5.994441509246826 m", "val":5.994441509246826}, "y":{"exp":"4.235998630523682 m", "val":4.235998630523682}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"3 m / s", "val":3.0}}}, "enabled":true}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.85103], + "samples":[ + {"t":0.0, "x":7.14452, "y":4.03536, "heading":0.0, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.35693, "ay":1.10902, "alpha":0.0, "fx":[-108.12962,-108.12962,-108.12962,-108.12962], "fy":[18.86414,18.86414,18.86414,18.86414]}, + {"t":0.04728, "x":7.13742, "y":4.0366, "heading":0.0, "vx":-0.30055, "vy":0.05243, "omega":0.0, "ax":-6.35617, "ay":1.10889, "alpha":0.0, "fx":[-108.11671,-108.11671,-108.11671,-108.11671], "fy":[18.86188,18.86188,18.86188,18.86188]}, + {"t":0.09456, "x":7.1161, "y":4.04032, "heading":0.0, "vx":-0.60107, "vy":0.10486, "omega":0.0, "ax":-6.35518, "ay":1.10872, "alpha":0.0, "fx":[-108.09983,-108.09983,-108.09983,-108.09983], "fy":[18.85894,18.85894,18.85894,18.85894]}, + {"t":0.14184, "x":7.08058, "y":4.04651, "heading":0.0, "vx":-0.90153, "vy":0.15728, "omega":0.0, "ax":-6.35383, "ay":1.10848, "alpha":0.0, "fx":[-108.07681,-108.07681,-108.07681,-108.07681], "fy":[18.85492,18.85492,18.85492,18.85492]}, + {"t":0.18912, "x":7.03086, "y":4.05519, "heading":0.0, "vx":-1.20194, "vy":0.20969, "omega":0.0, "ax":-6.35187, "ay":1.10814, "alpha":0.0, "fx":[-108.04356,-108.04356,-108.04356,-108.04356], "fy":[18.84912,18.84912,18.84912,18.84912]}, + {"t":0.2364, "x":6.96693, "y":4.06634, "heading":0.0, "vx":-1.50225, "vy":0.26208, "omega":0.0, "ax":-6.3488, "ay":1.1076, "alpha":0.0, "fx":[-107.99133,-107.99133,-107.99133,-107.99133], "fy":[18.84001,18.84001,18.84001,18.84001]}, + {"t":0.28368, "x":6.88881, "y":4.07997, "heading":0.0, "vx":-1.80242, "vy":0.31445, "omega":0.0, "ax":-6.34328, "ay":1.10664, "alpha":0.0, "fx":[-107.89735,-107.89735,-107.89735,-107.89735], "fy":[18.82361,18.82361,18.82361,18.82361]}, + {"t":0.33095, "x":6.7965, "y":4.09607, "heading":0.0, "vx":-2.10232, "vy":0.36677, "omega":0.0, "ax":-6.3304, "ay":1.10439, "alpha":0.0, "fx":[-107.67829,-107.67829,-107.67829,-107.67829], "fy":[18.7854,18.7854,18.7854,18.7854]}, + {"t":0.37823, "x":6.69003, "y":4.11465, "heading":0.0, "vx":-2.40162, "vy":0.41898, "omega":0.0, "ax":-6.26635, "ay":1.09322, "alpha":0.0, "fx":[-106.58874,-106.58874,-106.58874,-106.58874], "fy":[18.59532,18.59532,18.59532,18.59532]}, + {"t":0.42551, "x":6.56948, "y":4.13568, "heading":0.0, "vx":-2.69788, "vy":0.47067, "omega":0.0, "ax":6.26635, "ay":-1.09322, "alpha":0.0, "fx":[106.58874,106.58874,106.58874,106.58874], "fy":[-18.59532,-18.59532,-18.59532,-18.59532]}, + {"t":0.47279, "x":6.44893, "y":4.15671, "heading":0.0, "vx":-2.40162, "vy":0.41898, "omega":0.0, "ax":6.3304, "ay":-1.10439, "alpha":0.0, "fx":[107.67829,107.67829,107.67829,107.67829], "fy":[-18.7854,-18.7854,-18.7854,-18.7854]}, + {"t":0.52007, "x":6.34246, "y":4.17528, "heading":0.0, "vx":-2.10232, "vy":0.36677, "omega":0.0, "ax":6.34328, "ay":-1.10664, "alpha":0.0, "fx":[107.89735,107.89735,107.89735,107.89735], "fy":[-18.82361,-18.82361,-18.82361,-18.82361]}, + {"t":0.56735, "x":6.25015, "y":4.19139, "heading":0.0, "vx":-1.80242, "vy":0.31445, "omega":0.0, "ax":6.3488, "ay":-1.1076, "alpha":0.0, "fx":[107.99133,107.99133,107.99133,107.99133], "fy":[-18.84001,-18.84001,-18.84001,-18.84001]}, + {"t":0.61463, "x":6.17203, "y":4.20502, "heading":0.0, "vx":-1.50225, "vy":0.26208, "omega":0.0, "ax":6.35187, "ay":-1.10814, "alpha":0.0, "fx":[108.04356,108.04356,108.04356,108.04356], "fy":[-18.84912,-18.84912,-18.84912,-18.84912]}, + {"t":0.66191, "x":6.10811, "y":4.21617, "heading":0.0, "vx":-1.20194, "vy":0.20969, "omega":0.0, "ax":6.35383, "ay":-1.10848, "alpha":0.0, "fx":[108.07681,108.07681,108.07681,108.07681], "fy":[-18.85492,-18.85492,-18.85492,-18.85492]}, + {"t":0.70919, "x":6.05838, "y":4.22484, "heading":0.0, "vx":-0.90153, "vy":0.15728, "omega":0.0, "ax":6.35518, "ay":-1.10872, "alpha":0.0, "fx":[108.09983,108.09983,108.09983,108.09983], "fy":[-18.85894,-18.85894,-18.85894,-18.85894]}, + {"t":0.75647, "x":6.02286, "y":4.23104, "heading":0.0, "vx":-0.60107, "vy":0.10486, "omega":0.0, "ax":6.35617, "ay":-1.10889, "alpha":0.0, "fx":[108.11671,108.11671,108.11671,108.11671], "fy":[-18.86188,-18.86188,-18.86188,-18.86188]}, + {"t":0.80375, "x":6.00155, "y":4.23476, "heading":0.0, "vx":-0.30055, "vy":0.05243, "omega":0.0, "ax":6.35693, "ay":-1.10902, "alpha":0.0, "fx":[108.12962,108.12962,108.12962,108.12962], "fy":[-18.86414,-18.86414,-18.86414,-18.86414]}, + {"t":0.85103, "x":5.99444, "y":4.236, "heading":0.0, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/v3_epsilon/Superstructure.dot similarity index 100% rename from src/main/deploy/Superstructure.dot rename to src/main/deploy/v3_epsilon/Superstructure.dot diff --git a/src/main/deploy/v3_epsilon/choreo/Choreo.chor b/src/main/deploy/v3_epsilon/choreo/Choreo.chor new file mode 100644 index 00000000..dd321a96 --- /dev/null +++ b/src/main/deploy/v3_epsilon/choreo/Choreo.chor @@ -0,0 +1,86 @@ +{ + "name":"Choreo", + "version":1, + "type":"Swerve", + "variables":{ + "expressions":{ + "MAX_VELO":{ + "dimension":"Number", + "var":{ + "exp":"5.763493039050549", + "val":5.763493039050549 + } + } + }, + "poses":{} + }, + "config":{ + "frontLeft":{ + "x":{ + "exp":"11.375 in", + "val":0.288925 + }, + "y":{ + "exp":"11.375 in", + "val":0.288925 + } + }, + "backLeft":{ + "x":{ + "exp":"-11.375 in", + "val":-0.288925 + }, + "y":{ + "exp":"11.375 in", + "val":0.288925 + } + }, + "mass":{ + "exp":"150 lbs", + "val":68.0388555 + }, + "inertia":{ + "exp":"6 kg m ^ 2", + "val":6.0 + }, + "gearing":{ + "exp":"7.125", + "val":7.125 + }, + "radius":{ + "exp":"1.915 in", + "val":0.048641 + }, + "vmax":{ + "exp":"5557 RPM", + "val":581.9276791999494 + }, + "tmax":{ + "exp":"0.75 N * m", + "val":0.75 + }, + "cof":{ + "exp":"1", + "val":1.0 + }, + "bumper":{ + "front":{ + "exp":"18 in", + "val":0.4572 + }, + "side":{ + "exp":"18 in", + "val":0.4572 + }, + "back":{ + "exp":"18 in", + "val":0.4572 + } + }, + "differentialTrackWidth":{ + "exp":"22 in", + "val":0.5588 + } + }, + "generationFeatures":[] +} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_1.traj b/src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_1.traj similarity index 100% rename from src/main/deploy/choreo/E_RIGHT_PATH_1.traj rename to src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_1.traj diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_1_BACK.traj b/src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_1_BACK.traj similarity index 100% rename from src/main/deploy/choreo/E_RIGHT_PATH_1_BACK.traj rename to src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_1_BACK.traj diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_2.traj b/src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_2.traj similarity index 100% rename from src/main/deploy/choreo/E_RIGHT_PATH_2.traj rename to src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_2.traj diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_2_BACK.traj b/src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_2_BACK.traj similarity index 100% rename from src/main/deploy/choreo/E_RIGHT_PATH_2_BACK.traj rename to src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_2_BACK.traj diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_3.traj b/src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_3.traj similarity index 100% rename from src/main/deploy/choreo/E_RIGHT_PATH_3.traj rename to src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_3.traj diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_3_BACK.traj b/src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_3_BACK.traj similarity index 100% rename from src/main/deploy/choreo/E_RIGHT_PATH_3_BACK.traj rename to src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_3_BACK.traj diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_4.traj b/src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_4.traj similarity index 100% rename from src/main/deploy/choreo/E_RIGHT_PATH_4.traj rename to src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_4.traj diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_4_BACK.traj b/src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_4_BACK.traj similarity index 100% rename from src/main/deploy/choreo/E_RIGHT_PATH_4_BACK.traj rename to src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_4_BACK.traj diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 4b343dc0..0b2ef474 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -5,7 +5,7 @@ public final class Constants { public static final boolean TUNING_MODE = true; public static final double LOOP_PERIOD_SECONDS = 0.02; - public static final RobotType ROBOT = RobotType.V3_EPSILON; + public static final RobotType ROBOT = RobotType.V3_EPSILON_SIM; public static Mode getMode() { switch (ROBOT) { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index e44a78a8..13e60cbf 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -1,6 +1,7 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; import edu.wpi.first.wpilibj.Filesystem; +import edu.wpi.first.wpilibj.RobotBase; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; @@ -141,7 +142,10 @@ public static void addEdges( V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { loadEdgesFromDot( - Filesystem.getDeployDirectory().toPath().resolve("Superstructure.dot").toString(), + Filesystem.getDeployDirectory() + .toPath() + .resolve(!RobotBase.isSimulation() ? "" : "v3_epsilon/" + "Superstructure.dot") + .toString(), graph, elevator, intake, From b4d6eefcc26e126d2ad0b18213c907839f74483d Mon Sep 17 00:00:00 2001 From: Anshu Date: Mon, 20 Oct 2025 18:55:22 -0400 Subject: [PATCH 135/180] V3 bringup oct20 (#147) * Finished pathing * Bringup for button bindings Co-authored-by: Anshu Co-authored-by: SeptimusHeap7 Co-authored-by: Abhiraam Venigalla Co-authored-by: jasminepalit * fix ts method name (setDynamicReefHeight) --------- Co-authored-by: LordVanra Co-authored-by: ArnavPrabhudesai Co-authored-by: SeptimusHeap7 Co-authored-by: Abhiraam Venigalla Co-authored-by: jasminepalit --- src/main/deploy/choreo/E_RIGHT_PATH4.traj | 91 +++++++++++ src/main/deploy/choreo/E_RIGHT_PATH5.traj | 58 +++++++ src/main/deploy/choreo/E_RIGHT_PATH6.traj | 78 +++++++++ src/main/deploy/choreo/E_RIGHT_PATH7.traj | 61 +++++++ src/main/java/frc/robot/Robot.java | 3 +- .../frc/robot/commands/CompositeCommands.java | 23 +-- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 154 +++++++++++++++++- .../V3_EpsilonSuperstructure.java | 4 +- 8 files changed, 450 insertions(+), 22 deletions(-) create mode 100644 src/main/deploy/choreo/E_RIGHT_PATH4.traj create mode 100644 src/main/deploy/choreo/E_RIGHT_PATH5.traj create mode 100644 src/main/deploy/choreo/E_RIGHT_PATH6.traj create mode 100644 src/main/deploy/choreo/E_RIGHT_PATH7.traj diff --git a/src/main/deploy/choreo/E_RIGHT_PATH4.traj b/src/main/deploy/choreo/E_RIGHT_PATH4.traj new file mode 100644 index 00000000..aaa7826b --- /dev/null +++ b/src/main/deploy/choreo/E_RIGHT_PATH4.traj @@ -0,0 +1,91 @@ +{ + "name":"E_RIGHT_PATH4", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":3.530534505844116, "y":2.730516195297241, "heading":-0.5235987755982988, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.3093485832214355, "y":3.91524887084961, "heading":-1.5707963267948966, "intervals":19, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":0.9058957099914552, "y":4.042835235595703, "heading":-1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"3.530534505844116 m", "val":3.530534505844116}, "y":{"exp":"2.730516195297241 m", "val":2.730516195297241}, "heading":{"exp":"-30 deg", "val":-0.5235987755982988}, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.3093485832214355 m", "val":2.3093485832214355}, "y":{"exp":"3.9152488708496094 m", "val":3.91524887084961}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":19, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"0.9058957099914551 m", "val":0.9058957099914552}, "y":{"exp":"4.042835235595703 m", "val":4.042835235595703}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.76447,1.4505], + "samples":[ + {"t":0.0, "x":3.53053, "y":2.73052, "heading":-0.5236, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.35423, "ay":5.4575, "alpha":-2.44349, "fx":[-62.48473,-41.46199,-53.61392,-70.65709], "fy":[90.12272,101.55179,95.72684,83.92085]}, + {"t":0.0273, "x":3.52928, "y":2.73255, "heading":-0.5236, "vx":-0.09158, "vy":0.149, "omega":-0.06671, "ax":-3.40191, "ay":5.42794, "alpha":-2.42956, "fx":[-63.37175,-42.47287,-54.354,-71.26353], "fy":[89.48994,101.12385,95.30034,83.39663]}, + {"t":0.0546, "x":3.52552, "y":2.73864, "heading":-0.52542, "vx":-0.18446, "vy":0.2972, "omega":-0.13305, "ax":-3.45419, "ay":5.39486, "alpha":-2.4143, "fx":[-64.36787,-43.58938,-55.14465,-71.9169], "fy":[88.76372,100.63723,94.83589,82.82301]}, + {"t":0.08191, "x":3.51919, "y":2.74877, "heading":-0.52905, "vx":-0.27877, "vy":0.44449, "omega":-0.19896, "ax":-3.51172, "ay":5.35762, "alpha":-2.39739, "fx":[-65.48168,-44.82817,-55.99844,-72.62525], "fy":[87.93151,100.07992,94.32407,82.19057]}, + {"t":0.10921, "x":3.51027, "y":2.7629, "heading":-0.53448, "vx":-0.37464, "vy":0.59077, "omega":-0.26442, "ax":-3.57533, "ay":5.31542, "alpha":-2.37843, "fx":[-66.72315,-46.20939,-56.93062,-73.39815], "fy":[86.9779,99.43661,93.75293,81.48771]}, + {"t":0.13651, "x":3.49871, "y":2.78101, "heading":-0.5417, "vx":-0.47226, "vy":0.73589, "omega":-0.32935, "ax":-3.64598, "ay":5.26726, "alpha":-2.35691, "fx":[-68.1039,-47.75749,-57.95989,-74.24716], "fy":[85.88387,98.68756,93.10718,80.69988]}, + {"t":0.16381, "x":3.48446, "y":2.80306, "heading":-0.5507, "vx":-0.5718, "vy":0.8797, "omega":-0.3937, "ax":-3.72486, "ay":5.21185, "alpha":-2.33217, "fx":[-69.63758,-49.50228,-59.10928,-75.18631], "fy":[84.62567,97.80705,92.36699,79.80863]}, + {"t":0.19112, "x":3.46746, "y":2.82902, "heading":-0.56145, "vx":-0.6735, "vy":1.02199, "omega":-0.45738, "ax":-3.81342, "ay":5.14751, "alpha":-2.30332, "fx":[-71.34019,-51.48022,-60.40752,-76.23286], "fy":[83.17333,96.76107,91.50624,78.79019]}, + {"t":0.21842, "x":3.44765, "y":2.85885, "heading":-0.57393, "vx":-0.77762, "vy":1.16253, "omega":-0.52026, "ax":-3.91343, "ay":5.07204, "alpha":-2.26916, "fx":[-73.23057,-53.73601,-61.89077,-77.40824], "fy":[81.48853,95.50411,90.48994,77.6134]}, + {"t":0.24572, "x":3.42496, "y":2.89248, "heading":-0.58814, "vx":-0.88446, "vy":1.30101, "omega":-0.58222, "ax":-4.0271, "ay":4.98249, "alpha":-2.22808, "fx":[-75.33078,-56.32455,-63.60486,-78.7392], "fy":[79.52169,93.97422,89.27029,76.23675]}, + {"t":0.27302, "x":3.39931, "y":2.92985, "heading":-0.60403, "vx":-0.99441, "vy":1.43705, "omega":-0.64305, "ax":-4.15714, "ay":4.87483, "alpha":-2.1779, "fx":[-77.66645,-59.31299,-65.60851,-80.25941], "fy":[77.20769,92.08577,87.78071,74.60385]}, + {"t":0.30033, "x":3.37061, "y":2.97091, "heading":-0.62159, "vx":-1.10791, "vy":1.57014, "omega":-0.70251, "ax":-4.30692, "ay":4.74348, "alpha":-2.11558, "fx":[-80.2667,-62.78266,-67.97722,-82.01135], "fy":[74.45979,89.71836,85.92617,72.63659]}, + {"t":0.32763, "x":3.33876, "y":3.01554, "heading":-0.64077, "vx":-1.2255, "vy":1.69965, "omega":-0.76027, "ax":-4.48052, "ay":4.58051, "alpha":-2.03692, "fx":[-83.16321,-66.82949,-70.80827,-84.04845], "fy":[71.16062,86.69999,83.56765,70.22421]}, + {"t":0.35493, "x":3.30363, "y":3.06365, "heading":-0.66153, "vx":-1.34783, "vy":1.82471, "omega":-0.81588, "ax":-4.68276, "ay":4.37445, "alpha":-1.93605, "fx":[-86.38717,-71.5601,-74.2255,-86.43693], "fy":[67.14914,82.78148,80.49617,67.20581]}, + {"t":0.38223, "x":3.26509, "y":3.1151, "heading":-0.6838, "vx":-1.47568, "vy":1.94414, "omega":-0.86874, "ax":-4.91888, "ay":4.10841, "alpha":-1.80479, "fx":[-89.96167,-77.07648,-78.381,-89.25555], "fy":[62.20164,77.59909,76.38901,63.34156]}, + {"t":0.40954, "x":3.22296, "y":3.16971, "heading":-0.70752, "vx":-1.60998, "vy":2.05631, "omega":-0.91802, "ax":-5.19334, "ay":3.75712, "alpha":-1.63177, "fx":[-93.88442,-83.43416,-83.44258,-92.58796], "fy":[56.00508,70.6249,70.73574,58.26464]}, + {"t":0.43684, "x":3.17707, "y":3.22726, "heading":-0.73259, "vx":-1.75177, "vy":2.15889, "omega":-0.96257, "ax":-5.50661, "ay":3.28289, "alpha":-1.40137, "fx":[-98.09029,-90.54378,-89.53605,-96.49308], "fy":[48.12351,61.11904,62.71957,51.40197]}, + {"t":0.46414, "x":3.12719, "y":3.28742, "heading":-0.75887, "vx":-1.90211, "vy":2.24852, "omega":-1.00083, "ax":-5.84697, "ay":2.63124, "alpha":-1.09252, "fx":[-102.37487,-97.9728,-96.55963,-100.91392], "fy":[37.96731,48.14431,51.06197,41.85269]}, + {"t":0.49144, "x":3.07308, "y":3.34979, "heading":-0.78619, "vx":-2.06175, "vy":2.32036, "omega":-1.03066, "ax":-6.17328, "ay":1.73205, "alpha":-0.67844, "fx":[-106.2516,-104.64263,-103.70084,-105.42807], "fy":[24.80482,30.80696,33.98177,28.25298]}, + {"t":0.51874, "x":3.01449, "y":3.41379, "heading":-0.81433, "vx":-2.23029, "vy":2.36765, "omega":-1.04918, "ax":-6.38797, "ay":0.52388, "alpha":-0.13582, "fx":[-108.73581,-108.64791,-108.57506,-108.67152], "fy":[7.92541,8.96324,9.8954,8.86016]}, + {"t":0.54605, "x":2.95121, "y":3.47863, "heading":-0.84297, "vx":-2.4047, "vy":2.38195, "omega":-1.05289, "ax":-6.32947, "ay":-0.97076, "alpha":0.51586, "fx":[-108.18752,-107.83605,-107.0883,-107.53788], "fy":[-12.85009,-15.77303,-20.11421,-17.31222]}, + {"t":0.57335, "x":2.8832, "y":3.5433, "heading":-0.87172, "vx":-2.57751, "vy":2.35545, "omega":-1.0388, "ax":-5.86257, "ay":-2.55309, "alpha":1.17041, "fx":[-102.68227,-101.38378,-96.81794,-97.99849], "fy":[-36.2737,-40.01284,-50.00595,-47.41665]}, + {"t":0.60065, "x":2.81064, "y":3.60666, "heading":-0.90008, "vx":-2.73757, "vy":2.28574, "omega":-1.00685, "ax":-5.04903, "ay":-3.91201, "alpha":1.64541, "fx":[-91.39425,-90.69052,-81.14374,-80.3018], "fy":[-59.22508,-60.54104,-72.83824,-73.56434]}, + {"t":0.62795, "x":2.73402, "y":3.6676, "heading":-0.92757, "vx":-2.87542, "vy":2.17893, "omega":-0.96193, "ax":-4.16705, "ay":-4.84789, "alpha":1.61476, "fx":[-76.12425,-77.90698,-66.65786,-62.83233], "fy":[-77.9835,-76.38037,-86.39896,-89.08178]}, + {"t":0.65526, "x":2.65396, "y":3.72529, "heading":-0.95384, "vx":-2.98919, "vy":2.04657, "omega":-0.91784, "ax":-3.49053, "ay":-5.37869, "alpha":0.80538, "fx":[-61.43194,-63.77919,-57.56284,-54.71744], "fy":[-90.17198,-88.59202,-92.77274,-94.42313]}, + {"t":0.68256, "x":2.57105, "y":3.77916, "heading":-0.97889, "vx":-3.08449, "vy":1.89972, "omega":-0.89585, "ax":-2.95289, "ay":-5.7022, "alpha":-0.06391, "fx":[-50.11352,-49.82921,-50.34356,-50.62521], "fy":[-97.05541,-97.19793,-96.93044,-96.78744]}, + {"t":0.70986, "x":2.48573, "y":3.8289, "heading":-1.00335, "vx":-3.16511, "vy":1.74404, "omega":-0.89759, "ax":-2.48751, "ay":-5.92084, "alpha":-0.68492, "fx":[-41.55226,-37.71489,-43.1863,-46.79399], "fy":[-101.11602,-102.57888,-100.37364,-98.7784]}, + {"t":0.73716, "x":2.39839, "y":3.87431, "heading":-1.02786, "vx":-3.23303, "vy":1.58239, "omega":-0.91629, "ax":-2.07752, "ay":-6.07551, "alpha":-1.0598, "fx":[-34.79623,-27.94811,-36.05601,-42.55205], "fy":[-103.7071,-105.72204,-103.19994,-100.74185]}, + {"t":0.76447, "x":2.30935, "y":3.91525, "heading":-1.05288, "vx":-3.28975, "vy":1.41651, "omega":-0.94523, "ax":-1.62559, "ay":-6.2059, "alpha":-1.33728, "fx":[-27.81585,-18.1541,-27.57609,-37.05755], "fy":[-105.78865,-107.82683,-105.75457,-102.87228]}, + {"t":0.79085, "x":2.22198, "y":3.95046, "heading":-1.07782, "vx":-3.33264, "vy":1.25276, "omega":-0.98052, "ax":-0.96807, "ay":-6.33534, "alpha":-1.50866, "fx":[-17.91243,-5.80578,-14.79486,-27.35327], "fy":[-107.86741,-109.14923,-108.22326,-105.80923]}, + {"t":0.81724, "x":2.13371, "y":3.98131, "heading":-1.10369, "vx":-3.35818, "vy":1.0856, "omega":-1.02032, "ax":-0.11211, "ay":-6.40723, "alpha":-1.40745, "fx":[-4.70933,7.61341,1.43231,-11.96392], "fy":[-109.19436,-108.99837,-109.17524,-108.57288]}, + {"t":0.84362, "x":2.04506, "y":4.00773, "heading":-1.13061, "vx":-3.36114, "vy":0.91654, "omega":-1.05746, "ax":0.91179, "ay":-6.34619, "alpha":-1.10548, "fx":[12.01967,22.29584,19.50517,8.21634], "fy":[-108.58212,-106.9284,-107.40319,-108.87357]}, + {"t":0.87001, "x":1.95669, "y":4.0297, "heading":-1.15851, "vx":-3.33708, "vy":0.74908, "omega":-1.08663, "ax":2.02912, "ay":-6.08618, "alpha":-0.67048, "fx":[31.65751,37.97849,37.58084,30.84239], "fy":[-104.51481,-102.38363,-102.48441,-104.71414]}, + {"t":0.8964, "x":1.86934, "y":4.04735, "heading":-1.18719, "vx":-3.28354, "vy":0.58849, "omega":-1.10432, "ax":3.12613, "ay":-5.60575, "alpha":-0.16872, "fx":[52.33317,53.83158,54.02684,52.50672], "fy":[-95.82592,-94.99377,-94.87054,-95.71866]}, + {"t":0.92278, "x":1.78379, "y":4.06093, "heading":-1.21632, "vx":-3.20106, "vy":0.44058, "omega":-1.10877, "ax":4.08718, "ay":-4.94983, "alpha":0.33539, "fx":[71.22804,68.68157,67.83785,70.33983], "fy":[-82.76661,-84.88239,-85.58367,-83.54807]}, + {"t":0.94917, "x":1.70075, "y":4.07083, "heading":-1.24558, "vx":-3.09321, "vy":0.30997, "omega":-1.09992, "ax":4.84494, "ay":-4.20884, "alpha":0.79067, "fx":[86.06235,81.42906,78.75831,83.39461], "fy":[-67.27003,-72.77136,-75.71463,-70.60844]}, + {"t":0.97555, "x":1.62082, "y":4.07754, "heading":-1.2746, "vx":-2.96537, "vy":0.19892, "omega":-1.07906, "ax":5.39484, "ay":-3.47138, "alpha":1.16948, "fx":[96.25679,91.4489,87.05914,92.29402], "fy":[-51.75168,-59.75422,-66.07504,-58.60793]}, + {"t":1.00194, "x":1.54445, "y":4.08158, "heading":-1.30308, "vx":-2.82302, "vy":0.10732, "omega":-1.0482, "ax":5.77166, "ay":-2.79393, "alpha":1.47099, "fx":[102.59213,98.70786,93.2296,98.16757], "fy":[-37.82807,-46.89478,-57.1215,-48.2513]}, + {"t":1.02833, "x":1.47197, "y":4.08344, "heading":-1.33073, "vx":-2.67073, "vy":0.0336, "omega":-1.00939, "ax":6.02037, "ay":-2.19968, "alpha":1.7089, "fx":[106.24365,103.59106,97.76896,102.01518], "fy":[-26.08134,-34.94059,-49.0372,-39.60448]}, + {"t":1.05471, "x":1.4036, "y":4.08356, "heading":-1.35737, "vx":-2.51188, "vy":-0.02444, "omega":-0.9643, "ax":6.18017, "ay":-1.69063, "alpha":1.89818, "fx":[108.20248,106.64234,101.09709,104.54948], "fy":[-16.45316,-24.26632,-41.84242,-32.46663]}, + {"t":1.0811, "x":1.33947, "y":4.08233, "heading":-1.38281, "vx":-2.34881, "vy":-0.06905, "omega":-0.91421, "ax":6.28026, "ay":-1.25883, "alpha":2.05026, "fx":[109.14678,108.3811,103.53699,106.23682], "fy":[-8.6351,-14.96348,-35.47774,-26.57322]}, + {"t":1.10749, "x":1.27968, "y":4.08007, "heading":-1.40693, "vx":-2.1831, "vy":-0.10226, "omega":-0.86011, "ax":6.34086, "ay":-0.89317, "alpha":2.17326, "fx":[109.49962,109.22484,105.32677,107.37342], "fy":[-2.27868,-6.96007,-29.85373,-21.67782]}, + {"t":1.13387, "x":1.22429, "y":4.07706, "heading":-1.42963, "vx":-2.01579, "vy":-0.12583, "omega":-0.80277, "ax":6.37547, "ay":-0.5826, "alpha":2.27307, "fx":[109.51454,109.47966,106.63879,108.14673], "fy":[2.9244,-0.11171,-24.8764,-17.57548]}, + {"t":1.16026, "x":1.17332, "y":4.07354, "heading":-1.45081, "vx":-1.84756, "vy":-0.1412, "omega":-0.74279, "ax":6.39301, "ay":-0.31738, "alpha":2.35424, "fx":[109.34108,109.35856,107.59734,108.67641], "fy":[7.22353,5.74442,-20.45862,-14.10333]}, + {"t":1.18664, "x":1.12679, "y":4.0697, "heading":-1.47041, "vx":-1.67888, "vy":-0.14958, "omega":-0.68067, "ax":6.39935, "ay":-0.08939, "alpha":2.42037, "fx":[109.06693,109.00545,108.29234,109.03993], "fy":[10.81324,10.76314,-16.52415,-11.13428]}, + {"t":1.21303, "x":1.08472, "y":4.06572, "heading":-1.48837, "vx":-1.51002, "vy":-0.15194, "omega":-0.61681, "ax":6.39835, "ay":0.10797, "alpha":2.47441, "fx":[108.74325,108.5158,108.78939,109.28826], "fy":[13.84335,15.08074,-13.00819,-8.56956]}, + {"t":1.23942, "x":1.0471, "y":4.06175, "heading":-1.50465, "vx":-1.3412, "vy":-0.14909, "omega":-0.55152, "ax":6.39259, "ay":0.28003, "alpha":2.51874, "fx":[108.39965,107.95224,109.13688,109.45549], "fy":[16.42908,18.81265,-9.85639,-6.33228]}, + {"t":1.2658, "x":1.01394, "y":4.05792, "heading":-1.5192, "vx":-1.17252, "vy":-0.1417, "omega":-0.48506, "ax":6.38376, "ay":0.43105, "alpha":2.5553, "fx":[108.05294,107.35538,109.37086,109.56481], "fy":[18.65945,22.05472,-7.02348,-4.36221]}, + {"t":1.29219, "x":0.98522, "y":4.05433, "heading":-1.532, "vx":-1.00408, "vy":-0.13033, "omega":-0.41763, "ax":6.37304, "ay":0.56447, "alpha":2.58565, "fx":[107.71227,106.75128,109.51858,109.6322], "fy":[20.60373,24.88578,-4.47174,-2.61186]}, + {"t":1.31857, "x":0.96095, "y":4.05108, "heading":-1.54302, "vx":-0.83592, "vy":-0.11543, "omega":-0.34941, "ax":6.36119, "ay":0.68305, "alpha":2.61106, "fx":[107.38222,106.15632,109.60083,109.66885], "fy":[22.3163,27.3704,-2.16968,-1.0434]}, + {"t":1.34496, "x":0.94111, "y":4.04828, "heading":-1.55224, "vx":-0.66807, "vy":-0.09741, "omega":-0.28051, "ax":6.34875, "ay":0.78903, "alpha":2.63254, "fx":[107.06467,105.58058,109.63366,109.68266], "fy":[23.84025,29.56152,-0.09087,0.37352]}, + {"t":1.37135, "x":0.92569, "y":4.04598, "heading":-1.55964, "vx":-0.50055, "vy":-0.07659, "omega":-0.21105, "ax":6.33607, "ay":0.88424, "alpha":2.65092, "fx":[106.75986,105.02991,109.62958,109.67929], "fy":[25.21003,31.50255,1.78695,1.66349]}, + {"t":1.39773, "x":0.91469, "y":4.04427, "heading":-1.56521, "vx":-0.33337, "vy":-0.05326, "omega":-0.1411, "ax":6.32338, "ay":0.97021, "alpha":2.66684, "fx":[106.4671,104.50746,109.59844,109.66281], "fy":[26.45341,33.22922,3.48269,2.84663]}, + {"t":1.42412, "x":0.90809, "y":4.0432, "heading":-1.56893, "vx":-0.16652, "vy":-0.02766, "omega":-0.07074, "ax":6.31087, "ay":1.04817, "alpha":2.68083, "fx":[106.18518,104.01465,109.54802,109.63619], "fy":[27.59298,34.77103,5.01251,3.93957]}, + {"t":1.4505, "x":0.9059, "y":4.04284, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH5.traj b/src/main/deploy/choreo/E_RIGHT_PATH5.traj new file mode 100644 index 00000000..1bc05343 --- /dev/null +++ b/src/main/deploy/choreo/E_RIGHT_PATH5.traj @@ -0,0 +1,58 @@ +{ + "name":"E_RIGHT_PATH5", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":0.9058957099914552, "y":4.042835235595703, "heading":-1.5707963267948966, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.8561482429504395, "y":3.878795623779297, "heading":-1.5707963267948966, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"0.9058957099914551 m", "val":0.9058957099914552}, "y":{"exp":"4.042835235595703 m", "val":4.042835235595703}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.8561482429504395 m", "val":2.8561482429504395}, "y":{"exp":"3.878795623779297 m", "val":3.878795623779297}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.10287], + "samples":[ + {"t":0.0, "x":0.9059, "y":4.04284, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.4304, "ay":-0.54087, "alpha":0.0, "fx":[109.37931,109.37931,109.37931,109.37931], "fy":[-9.20011,-9.20011,-9.20011,-9.20011]}, + {"t":0.04795, "x":0.91329, "y":4.04221, "heading":-1.5708, "vx":0.30834, "vy":-0.02594, "omega":0.0, "ax":6.42984, "ay":-0.54083, "alpha":0.0, "fx":[109.36979,109.36979,109.36979,109.36979], "fy":[-9.19931,-9.19931,-9.19931,-9.19931]}, + {"t":0.0959, "x":0.93547, "y":4.04035, "heading":-1.5708, "vx":0.61666, "vy":-0.05187, "omega":0.0, "ax":6.42916, "ay":-0.54077, "alpha":0.0, "fx":[109.35815,109.35815,109.35815,109.35815], "fy":[-9.19833,-9.19833,-9.19833,-9.19833]}, + {"t":0.14385, "x":0.97243, "y":4.03724, "heading":-1.5708, "vx":0.92494, "vy":-0.0778, "omega":0.0, "ax":6.4283, "ay":-0.5407, "alpha":0.0, "fx":[109.3436,109.3436,109.3436,109.3436], "fy":[-9.19711,-9.19711,-9.19711,-9.19711]}, + {"t":0.1918, "x":1.02417, "y":4.03289, "heading":-1.5708, "vx":1.23319, "vy":-0.10373, "omega":0.0, "ax":6.4272, "ay":-0.5406, "alpha":0.0, "fx":[109.3249,109.3249,109.3249,109.3249], "fy":[-9.19553,-9.19553,-9.19553,-9.19553]}, + {"t":0.23975, "x":1.09069, "y":4.02729, "heading":-1.5708, "vx":1.54138, "vy":-0.12965, "omega":0.0, "ax":6.42574, "ay":-0.54048, "alpha":0.0, "fx":[109.29995,109.29995,109.29995,109.29995], "fy":[-9.19344,-9.19344,-9.19344,-9.19344]}, + {"t":0.28771, "x":1.17199, "y":4.02045, "heading":-1.5708, "vx":1.8495, "vy":-0.15556, "omega":0.0, "ax":6.42368, "ay":-0.54031, "alpha":0.0, "fx":[109.26503,109.26503,109.26503,109.26503], "fy":[-9.1905,-9.1905,-9.1905,-9.1905]}, + {"t":0.33566, "x":1.26806, "y":4.01237, "heading":-1.5708, "vx":2.15752, "vy":-0.18147, "omega":0.0, "ax":6.4206, "ay":-0.54005, "alpha":0.0, "fx":[109.21265,109.21265,109.21265,109.21265], "fy":[-9.18609,-9.18609,-9.18609,-9.18609]}, + {"t":0.38361, "x":1.37889, "y":4.00305, "heading":-1.5708, "vx":2.46539, "vy":-0.20737, "omega":0.0, "ax":6.41547, "ay":-0.53962, "alpha":0.0, "fx":[109.12537,109.12537,109.12537,109.12537], "fy":[-9.17875,-9.17875,-9.17875,-9.17875]}, + {"t":0.43156, "x":1.50449, "y":3.99249, "heading":-1.5708, "vx":2.77302, "vy":-0.23324, "omega":0.0, "ax":6.40522, "ay":-0.53876, "alpha":0.0, "fx":[108.95094,108.95094,108.95094,108.95094], "fy":[-9.16408,-9.16408,-9.16408,-9.16408]}, + {"t":0.47951, "x":1.64482, "y":3.98068, "heading":-1.5708, "vx":3.08016, "vy":-0.25908, "omega":0.0, "ax":6.37453, "ay":-0.53617, "alpha":0.0, "fx":[108.429,108.429,108.429,108.429], "fy":[-9.12018,-9.12018,-9.12018,-9.12018]}, + {"t":0.52746, "x":1.79985, "y":3.96764, "heading":-1.5708, "vx":3.38582, "vy":-0.28479, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.57541, "x":1.9622, "y":3.95399, "heading":-1.5708, "vx":3.38582, "vy":-0.28479, "omega":0.0, "ax":-6.37453, "ay":0.53617, "alpha":0.0, "fx":[-108.429,-108.429,-108.429,-108.429], "fy":[9.12018,9.12018,9.12018,9.12018]}, + {"t":0.62336, "x":2.11722, "y":3.94095, "heading":-1.5708, "vx":3.08016, "vy":-0.25908, "omega":0.0, "ax":-6.40522, "ay":0.53876, "alpha":0.0, "fx":[-108.95094,-108.95094,-108.95094,-108.95094], "fy":[9.16408,9.16408,9.16408,9.16408]}, + {"t":0.67131, "x":2.25756, "y":3.92914, "heading":-1.5708, "vx":2.77302, "vy":-0.23324, "omega":0.0, "ax":-6.41547, "ay":0.53962, "alpha":0.0, "fx":[-109.12537,-109.12537,-109.12537,-109.12537], "fy":[9.17875,9.17875,9.17875,9.17875]}, + {"t":0.71926, "x":2.38315, "y":3.91858, "heading":-1.5708, "vx":2.46539, "vy":-0.20737, "omega":0.0, "ax":-6.4206, "ay":0.54005, "alpha":0.0, "fx":[-109.21265,-109.21265,-109.21265,-109.21265], "fy":[9.18609,9.18609,9.18609,9.18609]}, + {"t":0.76721, "x":2.49399, "y":3.90926, "heading":-1.5708, "vx":2.15752, "vy":-0.18147, "omega":0.0, "ax":-6.42368, "ay":0.54031, "alpha":0.0, "fx":[-109.26503,-109.26503,-109.26503,-109.26503], "fy":[9.1905,9.1905,9.1905,9.1905]}, + {"t":0.81517, "x":2.59006, "y":3.90118, "heading":-1.5708, "vx":1.8495, "vy":-0.15556, "omega":0.0, "ax":-6.42574, "ay":0.54048, "alpha":0.0, "fx":[-109.29995,-109.29995,-109.29995,-109.29995], "fy":[9.19344,9.19344,9.19344,9.19344]}, + {"t":0.86312, "x":2.67135, "y":3.89434, "heading":-1.5708, "vx":1.54138, "vy":-0.12965, "omega":0.0, "ax":-6.4272, "ay":0.5406, "alpha":0.0, "fx":[-109.3249,-109.3249,-109.3249,-109.3249], "fy":[9.19553,9.19553,9.19553,9.19553]}, + {"t":0.91107, "x":2.73788, "y":3.88874, "heading":-1.5708, "vx":1.23319, "vy":-0.10373, "omega":0.0, "ax":-6.4283, "ay":0.5407, "alpha":0.0, "fx":[-109.3436,-109.3436,-109.3436,-109.3436], "fy":[9.19711,9.19711,9.19711,9.19711]}, + {"t":0.95902, "x":2.78962, "y":3.88439, "heading":-1.5708, "vx":0.92494, "vy":-0.0778, "omega":0.0, "ax":-6.42916, "ay":0.54077, "alpha":0.0, "fx":[-109.35815,-109.35815,-109.35815,-109.35815], "fy":[9.19833,9.19833,9.19833,9.19833]}, + {"t":1.00697, "x":2.82658, "y":3.88128, "heading":-1.5708, "vx":0.61666, "vy":-0.05187, "omega":0.0, "ax":-6.42984, "ay":0.54083, "alpha":0.0, "fx":[-109.36979,-109.36979,-109.36979,-109.36979], "fy":[9.19931,9.19931,9.19931,9.19931]}, + {"t":1.05492, "x":2.84876, "y":3.87942, "heading":-1.5708, "vx":0.30834, "vy":-0.02594, "omega":0.0, "ax":-6.4304, "ay":0.54087, "alpha":0.0, "fx":[-109.37931,-109.37931,-109.37931,-109.37931], "fy":[9.20011,9.20011,9.20011,9.20011]}, + {"t":1.10287, "x":2.85615, "y":3.8788, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH6.traj b/src/main/deploy/choreo/E_RIGHT_PATH6.traj new file mode 100644 index 00000000..235021fc --- /dev/null +++ b/src/main/deploy/choreo/E_RIGHT_PATH6.traj @@ -0,0 +1,78 @@ +{ + "name":"E_RIGHT_PATH6", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":2.8561482429504395, "y":3.878795623779297, "heading":-1.5707963267948966, "intervals":22, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.145307779312134, "y":5.592101097106934, "heading":-1.5707963267948966, "intervals":19, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":0.8512157797813416, "y":5.810821056365967, "heading":-1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"2.8561482429504395 m", "val":2.8561482429504395}, "y":{"exp":"3.878795623779297 m", "val":3.878795623779297}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":22, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.145307779312134 m", "val":2.145307779312134}, "y":{"exp":"5.592101097106934 m", "val":5.592101097106934}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":19, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"0.8512157797813416 m", "val":0.8512157797813416}, "y":{"exp":"5.810821056365967 m", "val":5.810821056365967}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.85028,1.54355], + "samples":[ + {"t":0.0, "x":2.85615, "y":3.8788, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-0.03288, "ay":6.45173, "alpha":0.0, "fx":[-0.55927,-0.55927,-0.55927,-0.55927], "fy":[109.74203,109.74203,109.74203,109.74203]}, + {"t":0.03865, "x":2.85612, "y":3.88361, "heading":-1.5708, "vx":-0.00127, "vy":0.24935, "omega":0.0, "ax":-0.13527, "ay":6.44985, "alpha":0.0, "fx":[-2.30084,-2.30084,-2.30084,-2.30084], "fy":[109.71011,109.71011,109.71011,109.71011]}, + {"t":0.0773, "x":2.85597, "y":3.89807, "heading":-1.5708, "vx":-0.0065, "vy":0.49863, "omega":0.0, "ax":-0.25498, "ay":6.4456, "alpha":0.0, "fx":[-4.3372,-4.3372,-4.3372,-4.3372], "fy":[109.63773,109.63773,109.63773,109.63773]}, + {"t":0.11595, "x":2.85553, "y":3.92215, "heading":-1.5708, "vx":-0.01635, "vy":0.74775, "omega":0.0, "ax":-0.39667, "ay":6.43768, "alpha":0.0, "fx":[-6.74733,-6.74733,-6.74733,-6.74733], "fy":[109.50314,109.50314,109.50314,109.50314]}, + {"t":0.1546, "x":2.8546, "y":3.95586, "heading":-1.5708, "vx":-0.03168, "vy":0.99656, "omega":0.0, "ax":-0.56672, "ay":6.42405, "alpha":0.0, "fx":[-9.63973,-9.63973,-9.63973,-9.63973], "fy":[109.27132,109.27132,109.27132,109.27132]}, + {"t":0.19324, "x":2.85296, "y":3.99918, "heading":-1.5708, "vx":-0.05359, "vy":1.24484, "omega":0.0, "ax":-0.77407, "ay":6.40129, "alpha":0.0, "fx":[-13.16676,-13.16676,-13.16676,-13.16676], "fy":[108.88416,108.88416,108.88416,108.88416]}, + {"t":0.23189, "x":2.85031, "y":4.05207, "heading":-1.5708, "vx":-0.0835, "vy":1.49225, "omega":0.0, "ax":-1.03158, "ay":6.36352, "alpha":0.0, "fx":[-17.54696,-17.54696,-17.54696,-17.54696], "fy":[108.24173,108.24173,108.24173,108.24173]}, + {"t":0.27054, "x":2.84631, "y":4.1145, "heading":-1.5708, "vx":-0.12337, "vy":1.73819, "omega":0.0, "ax":-1.35805, "ay":6.30022, "alpha":0.0, "fx":[-23.1001,-23.1001,-23.1001,-23.1001], "fy":[107.16496,107.16496,107.16496,107.16496]}, + {"t":0.30919, "x":2.84053, "y":4.18638, "heading":-1.5708, "vx":-0.17586, "vy":1.98169, "omega":0.0, "ax":-1.78132, "ay":6.19165, "alpha":0.0, "fx":[-30.29968,-30.29968,-30.29968,-30.29968], "fy":[105.31814,105.31814,105.31814,105.31814]}, + {"t":0.34784, "x":2.8324, "y":4.26759, "heading":-1.5708, "vx":-0.24471, "vy":2.22099, "omega":0.0, "ax":-2.34205, "ay":5.99905, "alpha":0.0, "fx":[-39.83754,-39.83754,-39.83754,-39.83754], "fy":[102.04213,102.04213,102.04213,102.04213]}, + {"t":0.38649, "x":2.82119, "y":4.35791, "heading":-1.5708, "vx":-0.33523, "vy":2.45284, "omega":0.0, "ax":-3.09443, "ay":5.64372, "alpha":0.0, "fx":[-52.63535,-52.63535,-52.63535,-52.63535], "fy":[95.99808,95.99808,95.99808,95.99808]}, + {"t":0.42514, "x":2.80592, "y":4.45693, "heading":-1.5708, "vx":-0.45482, "vy":2.67097, "omega":0.0, "ax":-4.08459, "ay":4.96836, "alpha":0.0, "fx":[-69.47768,-69.47768,-69.47768,-69.47768], "fy":[84.51037,84.51037,84.51037,84.51037]}, + {"t":0.46379, "x":2.7853, "y":4.56387, "heading":-1.5708, "vx":-0.61269, "vy":2.86299, "omega":0.0, "ax":-5.24651, "ay":3.71216, "alpha":0.0, "fx":[-89.24159,-89.24159,-89.24159,-89.24159], "fy":[63.14277,63.14277,63.14277,63.14277]}, + {"t":0.50244, "x":2.7577, "y":4.67729, "heading":-1.5708, "vx":-0.81546, "vy":3.00646, "omega":0.0, "ax":-6.19357, "ay":1.70531, "alpha":0.0, "fx":[-105.35091,-105.35091,-105.35091,-105.35091], "fy":[29.0068,29.0068,29.0068,29.0068]}, + {"t":0.54109, "x":2.72155, "y":4.79476, "heading":-1.5708, "vx":-1.05484, "vy":3.07237, "omega":0.0, "ax":-6.39591, "ay":-0.61517, "alpha":0.0, "fx":[-108.79267,-108.79267,-108.79267,-108.79267], "fy":[-10.46392,-10.46392,-10.46392,-10.46392]}, + {"t":0.57973, "x":2.67601, "y":4.91305, "heading":-1.5708, "vx":-1.30203, "vy":3.04859, "omega":0.0, "ax":-5.93068, "ay":-2.48406, "alpha":0.0, "fx":[-100.87913,-100.87913,-100.87913,-100.87913], "fy":[-42.25308,-42.25308,-42.25308,-42.25308]}, + {"t":0.61838, "x":2.62126, "y":5.02902, "heading":-1.5708, "vx":-1.53125, "vy":2.95259, "omega":0.0, "ax":-5.26731, "ay":-3.69606, "alpha":0.0, "fx":[-89.59539,-89.59539,-89.59539,-89.59539], "fy":[-62.86897,-62.86897,-62.86897,-62.86897]}, + {"t":0.65703, "x":2.55814, "y":5.14037, "heading":-1.5708, "vx":-1.73482, "vy":2.80974, "omega":0.0, "ax":-4.66407, "ay":-4.43883, "alpha":0.0, "fx":[-79.33457,-79.33457,-79.33457,-79.33457], "fy":[-75.50329,-75.50329,-75.50329,-75.50329]}, + {"t":0.69568, "x":2.48761, "y":5.24565, "heading":-1.5708, "vx":-1.91508, "vy":2.63818, "omega":0.0, "ax":-4.17646, "ay":-4.90446, "alpha":0.0, "fx":[-71.04039,-71.04039,-71.04039,-71.04039], "fy":[-83.42349,-83.42349,-83.42349,-83.42349]}, + {"t":0.73433, "x":2.41047, "y":5.34395, "heading":-1.5708, "vx":-2.0765, "vy":2.44863, "omega":0.0, "ax":-3.79243, "ay":-5.21004, "alpha":0.0, "fx":[-64.50817,-64.50817,-64.50817,-64.50817], "fy":[-88.62122,-88.62122,-88.62122,-88.62122]}, + {"t":0.77298, "x":2.32739, "y":5.4347, "heading":-1.5708, "vx":-2.22307, "vy":2.24727, "omega":0.0, "ax":-3.48882, "ay":-5.42022, "alpha":0.0, "fx":[-59.34377,-59.34377,-59.34377,-59.34377], "fy":[-92.19642,-92.19642,-92.19642,-92.19642]}, + {"t":0.81163, "x":2.23886, "y":5.5175, "heading":-1.5708, "vx":-2.35791, "vy":2.03778, "omega":0.0, "ax":-3.24556, "ay":-5.57097, "alpha":0.0, "fx":[-55.20609,-55.20609,-55.20609,-55.20609], "fy":[-94.76054,-94.76054,-94.76054,-94.76054]}, + {"t":0.85028, "x":2.14531, "y":5.5921, "heading":-1.5708, "vx":-2.48335, "vy":1.82247, "omega":0.0, "ax":-2.96055, "ay":-5.72676, "alpha":0.0, "fx":[-50.35806,-50.35806,-50.35806,-50.35806], "fy":[-97.41047,-97.41047,-97.41047,-97.41047]}, + {"t":0.88677, "x":2.05272, "y":5.65479, "heading":-1.5708, "vx":-2.59137, "vy":1.61351, "omega":0.0, "ax":-2.51661, "ay":-5.93359, "alpha":0.0, "fx":[-42.8068,-42.8068,-42.8068,-42.8068], "fy":[-100.92866,-100.92866,-100.92866,-100.92866]}, + {"t":0.92325, "x":1.9565, "y":5.70971, "heading":-1.5708, "vx":-2.6832, "vy":1.39701, "omega":0.0, "ax":-1.92603, "ay":-6.14877, "alpha":0.0, "fx":[-32.76117,-32.76117,-32.76117,-32.76117], "fy":[-104.58881,-104.58881,-104.58881,-104.58881]}, + {"t":0.95974, "x":1.85731, "y":5.75659, "heading":-1.5708, "vx":-2.75348, "vy":1.17265, "omega":0.0, "ax":-1.13172, "ay":-6.34098, "alpha":0.0, "fx":[-19.25029,-19.25029,-19.25029,-19.25029], "fy":[-107.8582,-107.8582,-107.8582,-107.8582]}, + {"t":0.99623, "x":1.75609, "y":5.79516, "heading":-1.5708, "vx":-2.79477, "vy":0.94128, "omega":0.0, "ax":-0.07234, "ay":-6.43835, "alpha":0.0, "fx":[-1.2304,-1.2304,-1.2304,-1.2304], "fy":[-109.51456,-109.51456,-109.51456,-109.51456]}, + {"t":1.03272, "x":1.65406, "y":5.82522, "heading":-1.5708, "vx":-2.79741, "vy":0.70636, "omega":0.0, "ax":1.2733, "ay":-6.30928, "alpha":0.0, "fx":[21.65848,21.65848,21.65848,21.65848], "fy":[-107.31901,-107.31901,-107.31901,-107.31901]}, + {"t":1.06921, "x":1.55284, "y":5.84679, "heading":-1.5708, "vx":-2.75095, "vy":0.47615, "omega":0.0, "ax":2.79607, "ay":-5.79585, "alpha":0.0, "fx":[47.56039,47.56039,47.56039,47.56039], "fy":[-98.58573,-98.58573,-98.58573,-98.58573]}, + {"t":1.10569, "x":1.45432, "y":5.86031, "heading":-1.5708, "vx":-2.64893, "vy":0.26467, "omega":0.0, "ax":4.22027, "ay":-4.85803, "alpha":0.0, "fx":[71.7856,71.7856,71.7856,71.7856], "fy":[-82.63368,-82.63368,-82.63368,-82.63368]}, + {"t":1.14218, "x":1.36048, "y":5.86673, "heading":-1.5708, "vx":-2.49494, "vy":0.08741, "omega":0.0, "ax":5.27988, "ay":-3.68161, "alpha":0.0, "fx":[89.80921,89.80921,89.80921,89.80921], "fy":[-62.62313,-62.62313,-62.62313,-62.62313]}, + {"t":1.17867, "x":1.27296, "y":5.86747, "heading":-1.5708, "vx":-2.30229, "vy":-0.04692, "omega":0.0, "ax":5.92127, "ay":-2.52981, "alpha":0.0, "fx":[100.71903,100.71903,100.71903,100.71903], "fy":[-43.03142,-43.03142,-43.03142,-43.03142]}, + {"t":1.21516, "x":1.1929, "y":5.86407, "heading":-1.5708, "vx":-2.08623, "vy":-0.13923, "omega":0.0, "ax":6.25183, "ay":-1.55143, "alpha":0.0, "fx":[106.34182,106.34182,106.34182,106.34182], "fy":[-26.38945,-26.38945,-26.38945,-26.38945]}, + {"t":1.25164, "x":1.12093, "y":5.85796, "heading":-1.5708, "vx":-1.85812, "vy":-0.19584, "omega":0.0, "ax":6.39716, "ay":-0.77221, "alpha":0.0, "fx":[108.81392,108.81392,108.81392,108.81392], "fy":[-13.13501,-13.13501,-13.13501,-13.13501]}, + {"t":1.28813, "x":1.05739, "y":5.8503, "heading":-1.5708, "vx":-1.6247, "vy":-0.22402, "omega":0.0, "ax":6.44334, "ay":-0.16359, "alpha":0.0, "fx":[109.59934,109.59934,109.59934,109.59934], "fy":[-2.78267,-2.78267,-2.78267,-2.78267]}, + {"t":1.32462, "x":1.0024, "y":5.84202, "heading":-1.5708, "vx":-1.38959, "vy":-0.22999, "omega":0.0, "ax":6.43932, "ay":0.31289, "alpha":0.0, "fx":[109.53092,109.53092,109.53092,109.53092], "fy":[5.32212,5.32212,5.32212,5.32212]}, + {"t":1.36111, "x":0.95599, "y":5.83383, "heading":-1.5708, "vx":-1.15463, "vy":-0.21857, "omega":0.0, "ax":6.41109, "ay":0.69029, "alpha":0.0, "fx":[109.05089,109.05089,109.05089,109.05089], "fy":[11.74167,11.74167,11.74167,11.74167]}, + {"t":1.3976, "x":0.91812, "y":5.82632, "heading":-1.5708, "vx":-0.92071, "vy":-0.19338, "omega":0.0, "ax":6.37216, "ay":0.99369, "alpha":0.0, "fx":[108.38867,108.38867,108.38867,108.38867], "fy":[16.90232,16.90232,16.90232,16.90232]}, + {"t":1.43408, "x":0.88877, "y":5.81992, "heading":-1.5708, "vx":-0.6882, "vy":-0.15712, "omega":0.0, "ax":6.32946, "ay":1.24132, "alpha":0.0, "fx":[107.66232,107.66232,107.66232,107.66232], "fy":[21.11458,21.11458,21.11458,21.11458]}, + {"t":1.47057, "x":0.86787, "y":5.81502, "heading":-1.5708, "vx":-0.45725, "vy":-0.11183, "omega":0.0, "ax":6.28652, "ay":1.4464, "alpha":0.0, "fx":[106.93183,106.93183,106.93183,106.93183], "fy":[24.60281,24.60281,24.60281,24.60281]}, + {"t":1.50706, "x":0.85537, "y":5.8119, "heading":-1.5708, "vx":-0.22787, "vy":-0.05906, "omega":0.0, "ax":6.24507, "ay":1.61849, "alpha":0.0, "fx":[106.22678,106.22678,106.22678,106.22678], "fy":[27.53001,27.53001,27.53001,27.53001]}, + {"t":1.54355, "x":0.85122, "y":5.81082, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH7.traj b/src/main/deploy/choreo/E_RIGHT_PATH7.traj new file mode 100644 index 00000000..85cb3fa9 --- /dev/null +++ b/src/main/deploy/choreo/E_RIGHT_PATH7.traj @@ -0,0 +1,61 @@ +{ + "name":"E_RIGHT_PATH7", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":0.8512157797813416, "y":5.810821056365967, "heading":-1.5707963267948966, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":2.892600774765014, "y":4.152195453643799, "heading":-1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"0.8512157797813416 m", "val":0.8512157797813416}, "y":{"exp":"5.810821056365967 m", "val":5.810821056365967}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"2.8926007747650146 m", "val":2.892600774765014}, "y":{"exp":"4.152195453643799 m", "val":4.152195453643799}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.27916], + "samples":[ + {"t":0.0, "x":0.85122, "y":5.81082, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.00847, "ay":-4.06938, "alpha":0.0, "fx":[85.19267,85.19267,85.19267,85.19267], "fy":[-69.21905,-69.21905,-69.21905,-69.21905]}, + {"t":0.0492, "x":0.85728, "y":5.8059, "heading":-1.5708, "vx":0.24641, "vy":-0.20021, "omega":0.0, "ax":5.00809, "ay":-4.06907, "alpha":0.0, "fx":[85.18611,85.18611,85.18611,85.18611], "fy":[-69.21373,-69.21373,-69.21373,-69.21373]}, + {"t":0.0984, "x":0.87546, "y":5.79112, "heading":-1.5708, "vx":0.4928, "vy":-0.4004, "omega":0.0, "ax":5.00762, "ay":-4.06869, "alpha":0.0, "fx":[85.17824,85.17824,85.17824,85.17824], "fy":[-69.20734,-69.20734,-69.20734,-69.20734]}, + {"t":0.1476, "x":0.90577, "y":5.7665, "heading":-1.5708, "vx":0.73917, "vy":-0.60057, "omega":0.0, "ax":5.00706, "ay":-4.06824, "alpha":0.0, "fx":[85.16863,85.16863,85.16863,85.16863], "fy":[-69.19952,-69.19952,-69.19952,-69.19952]}, + {"t":0.19679, "x":0.94819, "y":5.73203, "heading":-1.5708, "vx":0.9855, "vy":-0.80072, "omega":0.0, "ax":5.00635, "ay":-4.06766, "alpha":0.0, "fx":[85.15661,85.15661,85.15661,85.15661], "fy":[-69.18975,-69.18975,-69.18975,-69.18975]}, + {"t":0.24599, "x":1.00274, "y":5.68771, "heading":-1.5708, "vx":1.23181, "vy":-1.00084, "omega":0.0, "ax":5.00544, "ay":-4.06692, "alpha":0.0, "fx":[85.14115,85.14115,85.14115,85.14115], "fy":[-69.17719,-69.17719,-69.17719,-69.17719]}, + {"t":0.29519, "x":1.0694, "y":5.63355, "heading":-1.5708, "vx":1.47807, "vy":-1.20093, "omega":0.0, "ax":5.00423, "ay":-4.06594, "alpha":0.0, "fx":[85.12053,85.12053,85.12053,85.12053], "fy":[-69.16044,-69.16044,-69.16044,-69.16044]}, + {"t":0.34439, "x":1.14817, "y":5.56954, "heading":-1.5708, "vx":1.72427, "vy":-1.40097, "omega":0.0, "ax":5.00253, "ay":-4.06456, "alpha":0.0, "fx":[85.09167,85.09167,85.09167,85.09167], "fy":[-69.13699,-69.13699,-69.13699,-69.13699]}, + {"t":0.39359, "x":1.23906, "y":5.4957, "heading":-1.5708, "vx":1.97038, "vy":-1.60094, "omega":0.0, "ax":4.99999, "ay":-4.06249, "alpha":0.0, "fx":[85.04837,85.04837,85.04837,85.04837], "fy":[-69.10181,-69.10181,-69.10181,-69.10181]}, + {"t":0.44279, "x":1.34205, "y":5.41202, "heading":-1.5708, "vx":2.21638, "vy":-1.80081, "omega":0.0, "ax":4.99575, "ay":-4.05905, "alpha":0.0, "fx":[84.97623,84.97623,84.97623,84.97623], "fy":[-69.0432,-69.0432,-69.0432,-69.0432]}, + {"t":0.49198, "x":1.45714, "y":5.31851, "heading":-1.5708, "vx":2.46216, "vy":-2.0005, "omega":0.0, "ax":4.98728, "ay":-4.05216, "alpha":0.0, "fx":[84.83216,84.83216,84.83216,84.83216], "fy":[-68.92615,-68.92615,-68.92615,-68.92615]}, + {"t":0.54118, "x":1.58431, "y":5.21518, "heading":-1.5708, "vx":2.70752, "vy":-2.19986, "omega":0.0, "ax":4.96204, "ay":-4.03166, "alpha":0.0, "fx":[84.40283,84.40283,84.40283,84.40283], "fy":[-68.57731,-68.57731,-68.57731,-68.57731]}, + {"t":0.59038, "x":1.72352, "y":5.10208, "heading":-1.5708, "vx":2.95165, "vy":-2.39822, "omega":0.0, "ax":2.62317, "ay":-2.13132, "alpha":0.0, "fx":[44.61935,44.61935,44.61935,44.61935], "fy":[-36.25323,-36.25323,-36.25323,-36.25323]}, + {"t":0.63958, "x":1.87191, "y":4.98151, "heading":-1.5708, "vx":3.0807, "vy":-2.50307, "omega":0.0, "ax":-2.62317, "ay":2.13132, "alpha":0.0, "fx":[-44.61935,-44.61935,-44.61935,-44.61935], "fy":[36.25323,36.25323,36.25323,36.25323]}, + {"t":0.68878, "x":2.0203, "y":4.86094, "heading":-1.5708, "vx":2.95165, "vy":-2.39822, "omega":0.0, "ax":-4.96204, "ay":4.03166, "alpha":0.0, "fx":[-84.40283,-84.40283,-84.40283,-84.40283], "fy":[68.57731,68.57731,68.57731,68.57731]}, + {"t":0.73798, "x":2.15951, "y":4.74783, "heading":-1.5708, "vx":2.70752, "vy":-2.19986, "omega":0.0, "ax":-4.98728, "ay":4.05216, "alpha":0.0, "fx":[-84.83216,-84.83216,-84.83216,-84.83216], "fy":[68.92615,68.92615,68.92615,68.92615]}, + {"t":0.78717, "x":2.28668, "y":4.64451, "heading":-1.5708, "vx":2.46216, "vy":-2.0005, "omega":0.0, "ax":-4.99575, "ay":4.05905, "alpha":0.0, "fx":[-84.97623,-84.97623,-84.97623,-84.97623], "fy":[69.0432,69.0432,69.0432,69.0432]}, + {"t":0.83637, "x":2.40177, "y":4.551, "heading":-1.5708, "vx":2.21638, "vy":-1.80081, "omega":0.0, "ax":-4.99999, "ay":4.06249, "alpha":0.0, "fx":[-85.04837,-85.04837,-85.04837,-85.04837], "fy":[69.10181,69.10181,69.10181,69.10181]}, + {"t":0.88557, "x":2.50476, "y":4.46732, "heading":-1.5708, "vx":1.97038, "vy":-1.60094, "omega":0.0, "ax":-5.00253, "ay":4.06456, "alpha":0.0, "fx":[-85.09167,-85.09167,-85.09167,-85.09167], "fy":[69.13699,69.13699,69.13699,69.13699]}, + {"t":0.93477, "x":2.59564, "y":4.39347, "heading":-1.5708, "vx":1.72427, "vy":-1.40097, "omega":0.0, "ax":-5.00423, "ay":4.06594, "alpha":0.0, "fx":[-85.12053,-85.12053,-85.12053,-85.12053], "fy":[69.16044,69.16044,69.16044,69.16044]}, + {"t":0.98397, "x":2.67442, "y":4.32947, "heading":-1.5708, "vx":1.47807, "vy":-1.20093, "omega":0.0, "ax":-5.00544, "ay":4.06692, "alpha":0.0, "fx":[-85.14115,-85.14115,-85.14115,-85.14115], "fy":[69.17719,69.17719,69.17719,69.17719]}, + {"t":1.03317, "x":2.74108, "y":4.27531, "heading":-1.5708, "vx":1.23181, "vy":-1.00084, "omega":0.0, "ax":-5.00635, "ay":4.06766, "alpha":0.0, "fx":[-85.15661,-85.15661,-85.15661,-85.15661], "fy":[69.18975,69.18975,69.18975,69.18975]}, + {"t":1.08236, "x":2.79562, "y":4.23099, "heading":-1.5708, "vx":0.9855, "vy":-0.80072, "omega":0.0, "ax":-5.00706, "ay":4.06824, "alpha":0.0, "fx":[-85.16863,-85.16863,-85.16863,-85.16863], "fy":[69.19952,69.19952,69.19952,69.19952]}, + {"t":1.13156, "x":2.83805, "y":4.19652, "heading":-1.5708, "vx":0.73917, "vy":-0.60057, "omega":0.0, "ax":-5.00762, "ay":4.06869, "alpha":0.0, "fx":[-85.17824,-85.17824,-85.17824,-85.17824], "fy":[69.20734,69.20734,69.20734,69.20734]}, + {"t":1.18076, "x":2.86836, "y":4.17189, "heading":-1.5708, "vx":0.4928, "vy":-0.4004, "omega":0.0, "ax":-5.00809, "ay":4.06907, "alpha":0.0, "fx":[-85.18611,-85.18611,-85.18611,-85.18611], "fy":[69.21373,69.21373,69.21373,69.21373]}, + {"t":1.22996, "x":2.88654, "y":4.15712, "heading":-1.5708, "vx":0.24641, "vy":-0.20021, "omega":0.0, "ax":-5.00847, "ay":4.06938, "alpha":0.0, "fx":[-85.19267,-85.19267,-85.19267,-85.19267], "fy":[69.21905,69.21905,69.21905,69.21905]}, + {"t":1.27916, "x":2.8926, "y":4.1522, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index acd3599f..c1bb9243 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -31,6 +31,7 @@ import java.util.HashMap; import java.util.Map; import java.util.function.BiConsumer; +import org.ironmaple.simulation.SimulatedArena; import org.littletonrobotics.junction.LogFileUtil; import org.littletonrobotics.junction.LoggedRobot; import org.littletonrobotics.junction.Logger; @@ -126,7 +127,7 @@ public void robotInit() { // setUseTiming(false); Logger.addDataReceiver(new NT4Publisher()); // setting up maple sim field - // SimulatedArena.getInstance(); + SimulatedArena.getInstance(); break; case REPLAY: diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index ae1f18d2..02c3a1e9 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -904,6 +904,12 @@ public static final Command intakeAlgaeFromReef( .withTimeout(0.5))); } + public static final Command intakeAlgaeFromReef( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + return intakeAlgaeFromReef( + drive, superstructure, () -> RobotState.getReefAlignData().algaeIntakeHeight(), cameras); + } + public static final Command emergencyEject( V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { return Commands.sequence( @@ -947,17 +953,6 @@ public static final Command handoffCoral( superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)); } - public static final Command processAlgae( - V3_EpsilonSuperstructure superstructure, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR), - superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR_SCORE), - Commands.waitSeconds(3), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); - } - public static final Command manipulatorGroundIntake( V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { return Commands.sequence( @@ -965,5 +960,11 @@ public static final Command manipulatorGroundIntake( () -> superstructure.runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE)), Commands.runOnce(() -> manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE))); } + + public static final Command setDynamicReefHeight( + ReefState height, V3_EpsilonSuperstructure superstructure) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setReefHeight(height)), superstructure.setPosition()); + } } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index ebd019ac..4a79f717 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -8,8 +8,11 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; +import edu.wpi.first.wpilibj2.command.button.Trigger; import frc.robot.Constants; import frc.robot.Constants.Mode; +import frc.robot.FieldConstants.Reef.ReefPose; +import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotContainer; import frc.robot.RobotState; import frc.robot.commands.CompositeCommands.SharedCommands; @@ -24,6 +27,7 @@ import frc.robot.subsystems.shared.drive.ModuleIOTalonFX; import frc.robot.subsystems.shared.elevator.Elevator; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; +import frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions; import frc.robot.subsystems.shared.elevator.ElevatorIO; import frc.robot.subsystems.shared.elevator.ElevatorIOSim; import frc.robot.subsystems.shared.elevator.ElevatorIOTalonFX; @@ -39,12 +43,14 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOSim; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOTalonFX; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIO; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOSim; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOTalonFX; import frc.robot.util.LTNUpdater; import frc.robot.util.LoggedChoreo.ChoreoChooser; import frc.robot.util.LoggedTunableNumber; +import org.ironmaple.simulation.SimulatedArena; import org.littletonrobotics.junction.Logger; public class V3_EpsilonRobotContainer implements RobotContainer { @@ -60,6 +66,7 @@ public class V3_EpsilonRobotContainer implements RobotContainer { // Controller private static final CommandXboxController driver = new CommandXboxController(0); + private static final CommandXboxController operator = new CommandXboxController(1); // Auto chooser private final ChoreoChooser autoChooser = new ChoreoChooser(); @@ -146,16 +153,50 @@ public V3_EpsilonRobotContainer() { * responsible for setting up the default commands for each button on the controllers. */ private void configureButtonBindings() { + Trigger elevatorStow = + new Trigger( + () -> + elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) + || elevator.getPosition().equals(ElevatorPositions.STOW)); + Trigger elevatorNotStow = + new Trigger( + () -> + !elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) + && !elevator.getPosition().equals(ElevatorPositions.STOW)); drive.setDefaultCommand( DriveCommands.joystickDrive( drive, () -> -driver.getLeftY(), () -> -driver.getLeftX(), () -> -driver.getRightX(), - () -> false)); + () -> false, + operator.back(), + driver.povRight())); driver.povDown().onTrue(SharedCommands.resetHeading(drive)); + driver.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); + driver.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); + driver.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); + driver.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); + + driver + .y() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); + driver + .x() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); + driver + .b() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); + driver + .a() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); + driver .rightTrigger() .whileTrue( @@ -164,11 +205,106 @@ private void configureButtonBindings() { .whileFalse( V3_EpsilonCompositeCommands.postIntakeCoralSequence( superstructure, intake, manipulator)); + driver + .leftTrigger(0.5) + .whileTrue( + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake, manipulator)) + .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); + + driver + .leftBumper() + .whileTrue(V3_EpsilonCompositeCommands.intakeAlgaeFloor(superstructure, manipulator)) + .onFalse( + Commands.either( + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), + () -> RobotState.isHasAlgae())); + driver.rightBumper().onTrue(Commands.runOnce(() -> RobotState.toggleReefPost())); + + driver.povUp().onTrue(superstructure.setPosition()); + driver.povDown().onTrue(SharedCommands.resetHeading(drive)); + driver.povLeft().onTrue(DriveCommands.inchMovement(drive, -0.5, .07)); + + driver + .leftStick() + .onTrue(V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence(drive, superstructure)); + + driver.back().whileTrue(V3_EpsilonCompositeCommands.intakeAlgaeFromReef(drive, superstructure)); + + driver + .start() + .whileTrue( + V3_EpsilonCompositeCommands.dropAlgae( + drive, + elevator, + manipulator, + intake, + superstructure, + () -> RobotState.getReefAlignData().algaeIntakeHeight())); + + operator.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); + operator.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); + operator.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); + operator.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); - driver.x().onTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)); - driver.y().onTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)); + operator + .y() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); + operator + .x() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); + operator + .b() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); + operator + .a() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); - driver.b().onTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); + operator + .leftTrigger(0.5) + .whileTrue( + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake, manipulator)) + .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); + operator + .rightTrigger(0.5) + .whileTrue( + superstructure.override( + () -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_CORAL), 0.4)); + + operator.leftBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))); + operator.rightBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))); + + // operator.povUp().onTrue(V3_EpsilonCompositeCommands.climb(superstructure, + // climber, drive)); fix later + // operator.povDown().whileTrue(climber.winchClimberManual()); + operator + .povLeft() + .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR)) + .onFalse( + superstructure + .runActionWithTimeout(V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, 1) + .finallyDo(() -> RobotState.setHasAlgae(false))); + operator + .povRight() + .whileTrue( + superstructure + .override(() -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_ALGAE)) + .finallyDo(() -> RobotState.setHasAlgae(false))); + operator.start().whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)); + + operator + .back() + .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)) + .onFalse( + superstructure + .runActionWithTimeout(V3_EpsilonSuperstructureStates.BARGE_SCORE, 0.1) + .finallyDo(() -> RobotState.setHasAlgae(false))); } private void configureAutos() { @@ -199,10 +335,12 @@ public void robotPeriodic() { V3_EpsilonMechanism3d.getPoses( elevator.getPositionMeters(), intake.getPivotAngle(), manipulator.getArmAngle())); - // Logger.recordOutput( - // "FieldSimulation/Algae", SimulatedArena.getInstance().getGamePiecesArrayByType("Algae")); - // Logger.recordOutput( - // "FieldSimulation/Coral", SimulatedArena.getInstance().getGamePiecesArrayByType("Coral")); + if (!Constants.getMode().equals(Constants.Mode.REAL)) { + Logger.recordOutput( + "FieldSimulation/Algae", SimulatedArena.getInstance().getGamePiecesArrayByType("Algae")); + Logger.recordOutput( + "FieldSimulation/Coral", SimulatedArena.getInstance().getGamePiecesArrayByType("Coral")); + } } /** diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index e8b79d65..f4c1343c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -98,10 +98,10 @@ public V3_EpsilonSuperstructure( this.manipulator = manipulator; previousState = null; - currentState = V3_EpsilonSuperstructureStates.STOW_DOWN; + currentState = V3_EpsilonSuperstructureStates.START; nextState = null; - targetState = V3_EpsilonSuperstructureStates.STOW_DOWN; + targetState = V3_EpsilonSuperstructureStates.START; // Initialize the graph graph = new DefaultDirectedGraph<>(EdgeCommand.class); From 5c37c6a082d6f2a9dceeb2a9e27e1770754181eb Mon Sep 17 00:00:00 2001 From: ArnavPrabhudesai Date: Mon, 20 Oct 2025 20:11:02 -0400 Subject: [PATCH 136/180] More bringup for button commands and fixed some logic for certain bindings Co-authored-by: Anshu Co-authored-by: SeptimusHeap7 Co-authored-by: Abhiraam Venigalla Co-authored-by: jasminepalit --- .../frc/robot/commands/CompositeCommands.java | 36 +++++++------ .../v3_Epsilon/V3_EpsilonRobotContainer.java | 12 ++--- .../V3_EpsilonSuperstructure.java | 50 ++++++++++++------- .../V3_EpsilonManipulatorConstants.java | 2 +- 4 files changed, 59 insertions(+), 41 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 02c3a1e9..e4c2bfe1 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -694,19 +694,20 @@ public static final Command postIntakeCoralSequence( public static final Command optimalAutoScoreCoralSequence( Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { return Commands.sequence( - Commands.runOnce( - () -> { - if (RobotState.getOIData().currentReefHeight().equals(ReefState.L1)) { - RobotState.setScoreSide(ScoreSide.CENTER); - } else { - RobotState.setScoreSide( - optimalSideReef(RobotState.getReefAlignData().coralSetpoint())); - } - }) - .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), + // Commands.runOnce( + // () -> { + // if (RobotState.getOIData().currentReefHeight().equals(ReefState.L1)) { + // RobotState.setScoreSide(ScoreSide.CENTER); + // } else { + // RobotState.setScoreSide( + // optimalSideReef(RobotState.getReefAlignData().coralSetpoint())); + // } + // }) + // .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), superstructure.setPosition(), - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), + // DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitSeconds(1), + // Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight())); } @@ -724,8 +725,9 @@ public static final Command optimalAutoScoreCoralSequence( }) .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), superstructure.runReefGoal(() -> height), - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), + // DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitSeconds(2), + // Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), superstructure .runReefScoreGoal(() -> height) .until( @@ -749,7 +751,8 @@ public static final Command optimalAutoAlignReefAlgae( }) .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), - DriveCommands.autoAlignReefAlgae(drive, cameras)); + // DriveCommands.autoAlignReefAlgae(drive, cameras) + Commands.waitSeconds(2)); } private static final ScoreSide optimalSideReef(Pose2d baseSetpoint) { @@ -825,7 +828,8 @@ public static final Command dropAlgae( Supplier level, Camera... cameras) { return Commands.sequence( - DriveCommands.autoAlignReefAlgae(drive, cameras), + // DriveCommands.autoAlignReefAlgae(drive, cameras), + Commands.waitSeconds(2), Commands.sequence( superstructure .runGoal( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 4a79f717..6897b44d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -198,13 +198,9 @@ private void configureButtonBindings() { .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); driver - .rightTrigger() + .rightTrigger(0.5) .whileTrue( - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake, manipulator)) - .whileFalse( - V3_EpsilonCompositeCommands.postIntakeCoralSequence( - superstructure, intake, manipulator)); + V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence(drive, superstructure)); driver .leftTrigger(0.5) .whileTrue( @@ -270,7 +266,9 @@ private void configureButtonBindings() { .whileTrue( V3_EpsilonCompositeCommands.intakeCoralDriverSequence( superstructure, intake, manipulator)) - .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); + .whileFalse( + V3_EpsilonCompositeCommands.postIntakeCoralSequence( + superstructure, intake, manipulator)); operator .rightTrigger(0.5) .whileTrue( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index f4c1343c..ec31a351 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -543,23 +543,39 @@ public Command runReefGoal(Supplier goal) { */ public Command runReefScoreGoal(Supplier goal) { // Run appropriate action sequence depending on reef level - return runActionWithTimeout( - () -> - switch (goal.get()) { - case L1 -> V3_EpsilonSuperstructureStates.L1; - case L2 -> V3_EpsilonSuperstructureStates.L2; - case L3 -> V3_EpsilonSuperstructureStates.L3; - case L4 -> V3_EpsilonSuperstructureStates.L4; - default -> V3_EpsilonSuperstructureStates.STOW_DOWN; - }, - () -> - switch (goal.get()) { - case L1 -> 0.8; - case L2 -> 0.15; - case L3 -> 0.15; - case L4 -> 0.1; - default -> 0; - }); + return this.runGoal( + () -> { + switch (goal.get()) { + case L1: + return V3_EpsilonSuperstructureStates.L1_SCORE; + case L2: + return V3_EpsilonSuperstructureStates.L2_SCORE; + case L3: + return V3_EpsilonSuperstructureStates.L3_SCORE; + case L4: + return V3_EpsilonSuperstructureStates.L4_SCORE; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }); + + // return runActionWithTimeout( + // () -> + // switch (goal.get()) { + // case L1 -> V3_EpsilonSuperstructureStates.L1; + // case L2 -> V3_EpsilonSuperstructureStates.L2; + // case L3 -> V3_EpsilonSuperstructureStates.L3; + // case L4 -> V3_EpsilonSuperstructureStates.L4; + // default -> V3_EpsilonSuperstructureStates.STOW_DOWN; + // }, + // () -> + // switch (goal.get()) { + // case L1 -> 0.8; + // case L2 -> 0.15; + // case L3 -> 0.15; + // case L4 -> 0.1; + // default -> 0; + // }); } /** diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index e8ae9c33..82ef784b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -239,7 +239,7 @@ public static enum ManipulatorRollerState { ALGAE_INTAKE(-12.0), L4_SCORE(4.6 * 1.56), SCORE_CORAL(4.8 * 1.56), - SCORE_ALGAE(-6), + SCORE_ALGAE(6), REMOVE_ALGAE(-12), L1_SCORE(3.5 * 1.56); From 241efbeeb7f97e8a6ad6ff02595e12d169800b1d Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Tue, 21 Oct 2025 02:31:41 -0400 Subject: [PATCH 137/180] initial GV attempt. May need to recal cameras --- src/main/java/frc/robot/Constants.java | 2 +- .../frc/robot/commands/CompositeCommands.java | 17 +- .../subsystems/shared/vision/Camera.java | 11 +- .../shared/vision/VisionConstants.java | 185 ++++++++++-------- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 13 +- .../V3_EpsilonManipulatorIOTalonFX.java | 2 + 6 files changed, 136 insertions(+), 94 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 4b343dc0..0b2ef474 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -5,7 +5,7 @@ public final class Constants { public static final boolean TUNING_MODE = true; public static final double LOOP_PERIOD_SECONDS = 0.02; - public static final RobotType ROBOT = RobotType.V3_EPSILON; + public static final RobotType ROBOT = RobotType.V3_EPSILON_SIM; public static Mode getMode() { switch (ROBOT) { diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index e4c2bfe1..e326a4df 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -669,7 +669,7 @@ public static final Command intakeCoralDriverSequence( superstructure.runGoalUntil( V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoralLoose()), superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.HANDOFF, () -> intake.hasCoralLocked())); + V3_EpsilonSuperstructureStates.HANDOFF_SPIN, () -> intake.hasCoralLocked())); } public static final Command postIntakeCoralSequence( @@ -705,9 +705,8 @@ public static final Command optimalAutoScoreCoralSequence( // }) // .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), superstructure.setPosition(), - // DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitSeconds(1), - // Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight())); } @@ -725,9 +724,8 @@ public static final Command optimalAutoScoreCoralSequence( }) .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), superstructure.runReefGoal(() -> height), - // DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitSeconds(2), - // Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), superstructure .runReefScoreGoal(() -> height) .until( @@ -751,8 +749,7 @@ public static final Command optimalAutoAlignReefAlgae( }) .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), - // DriveCommands.autoAlignReefAlgae(drive, cameras) - Commands.waitSeconds(2)); + DriveCommands.autoAlignReefAlgae(drive, cameras)); } private static final ScoreSide optimalSideReef(Pose2d baseSetpoint) { @@ -828,7 +825,7 @@ public static final Command dropAlgae( Supplier level, Camera... cameras) { return Commands.sequence( - // DriveCommands.autoAlignReefAlgae(drive, cameras), + DriveCommands.autoAlignReefAlgae(drive, cameras), Commands.waitSeconds(2), Commands.sequence( superstructure diff --git a/src/main/java/frc/robot/subsystems/shared/vision/Camera.java b/src/main/java/frc/robot/subsystems/shared/vision/Camera.java index b4df6fbe..cbb93e44 100644 --- a/src/main/java/frc/robot/subsystems/shared/vision/Camera.java +++ b/src/main/java/frc/robot/subsystems/shared/vision/Camera.java @@ -27,7 +27,7 @@ public class Camera { private final CameraIOInputsAutoLogged inputs; private final CameraIO io; - private final String name; + @Getter private final String name; @Getter int[] validIds; private final Map tagPoses2d = new HashMap<>(); @@ -169,10 +169,19 @@ public void periodic() { // txTyObservations.stream() // .sorted(Comparator.comparingDouble(VisionObservation::timestamp)) // .forEach(RobotState::addReefLocalizerVisionMeasurement); + + Logger.recordOutput( + "Vision/Cameras/" + name + "/RobotToCamera", + new Pose3d(RobotState.getRobotPoseField()) + .transformBy(io.getGompeiVisionConfig().robotToCameraTransform())); } public void setValidTags(int... validIds) { this.validIds = validIds; io.setValidTags(validIds); } + + public Transform3d getTransform() { + return io.getGompeiVisionConfig().robotToCameraTransform(); + } } diff --git a/src/main/java/frc/robot/subsystems/shared/vision/VisionConstants.java b/src/main/java/frc/robot/subsystems/shared/vision/VisionConstants.java index a8aa7f46..efb9e7de 100644 --- a/src/main/java/frc/robot/subsystems/shared/vision/VisionConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/vision/VisionConstants.java @@ -183,10 +183,10 @@ public static class RobotCameras { new Rotation3d(0, 0, Units.degreesToRadians(-225)))) .build(); - private static final GompeiVisionConfig BACK_TOP_LEFT = + private static final GompeiVisionConfig BACK_BOTTOM_LEFT = // Back Right robot relative GompeiVisionConfig.builder() - .key("camera_backtopleft") - .hardwareID("camera_backtopleft") + .key("camera_backbottomleft") + .hardwareID("camera_backbottomleft") .cameraType(CameraType.THRIFTYCAM) .exposure(50.0) .gain(0.0) @@ -198,59 +198,39 @@ public static class RobotCameras { MatBuilder.fill( N3.instance, N3.instance, - 1624.2147990980468, - 0.0, - 678.5977326688123, - 0.0, - 1623.8010651757406, - 581.2937963816543, - 0.0, - 0.0, - 1.0))) + 1381.859898393546, + 0, + 741.0665606797552, + 0, + 1388.430990713648, + 626.5683262179745, + 0, + 0, + 1))) .distortionCoefficients( new Matrix( MatBuilder.fill( N5.instance, N1.instance, - 0.0962739678996323, - -0.17425866758812222, - -0.0010256591695401809, - 0.00203018525003567, - 0.1499388749754604))) + -0.026870821933410, + 0.034738098307543, + -0.0005183171, + 0.0005800466, + -0.050574364954119))) .verticalFOV(ThriftyCamConstants.VERTICAL_FOV) .singletagXYStdev(ThriftyCamConstants.SINGLETAG_XY_STANDARD_DEVIATION_COEFFICIENT) .thetaStdev(ThriftyCamConstants.THETA_STANDARD_DEVIATION_COEFFICIENT) .multitagXYStdev(ThriftyCamConstants.MULTITAG_XY_STANDARD_DEVIATION_COEFFICIENT) .cameraDuties(List.of(CameraDuty.FIELD_LOCALIZATION, CameraDuty.REEF_LOCALIZATION)) - .robotToCameraTransform(new Transform3d(0, 0, 0, new Rotation3d(0, 0, 0))) - .build(); - - private static final GompeiVisionConfig BACK_BOTTOM_LEFT = - GompeiVisionConfig.builder() - .key("camera_backbottomleft") - .hardwareID("camera_backbottomleft") - .cameraType(CameraType.THRIFTYCAM) - .exposure(50.0) - .gain(0.0) - .horizontalFOV(ThriftyCamConstants.HORIZONTAL_FOV) - .width(ThriftyCamConstants.WIDTH) - .height(ThriftyCamConstants.HEIGHT) - .cameraMatrix( - new Matrix( - MatBuilder.fill( - N3.instance, N3.instance, 1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0))) - .distortionCoefficients( - new Matrix( - MatBuilder.fill(N5.instance, N1.instance, 0.0, 0.0, 0.0, 0.0, 0.0))) - .verticalFOV(ThriftyCamConstants.VERTICAL_FOV) - .singletagXYStdev(ThriftyCamConstants.SINGLETAG_XY_STANDARD_DEVIATION_COEFFICIENT) - .thetaStdev(ThriftyCamConstants.THETA_STANDARD_DEVIATION_COEFFICIENT) - .multitagXYStdev(ThriftyCamConstants.MULTITAG_XY_STANDARD_DEVIATION_COEFFICIENT) - .cameraDuties(List.of(CameraDuty.FIELD_LOCALIZATION, CameraDuty.REEF_LOCALIZATION)) - .robotToCameraTransform(new Transform3d(0, 0, 0, new Rotation3d(0, 0, 0))) + .robotToCameraTransform( + new Transform3d( + Units.inchesToMeters(-11.0), + Units.inchesToMeters(-11.75), + Units.inchesToMeters(9.182678), + new Rotation3d(0, Units.degreesToRadians(-20), Units.degreesToRadians(-65)))) .build(); - private static final GompeiVisionConfig BACK_RIGHT = + private static final GompeiVisionConfig BACK_RIGHT = // Front Left robot relative GompeiVisionConfig.builder() .key("camera_backright") .hardwareID("camera_backright") @@ -263,19 +243,42 @@ public static class RobotCameras { .cameraMatrix( new Matrix( MatBuilder.fill( - N3.instance, N3.instance, 1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0))) + N3.instance, + N3.instance, + 1364.233774114576, + 0, + 833.9370492297464, + 0, + 1359.524805084978, + 697.4271592073976, + 0, + 0, + 1))) .distortionCoefficients( new Matrix( - MatBuilder.fill(N5.instance, N1.instance, 0.0, 0.0, 0.0, 0.0, 0.0))) + MatBuilder.fill( + N5.instance, + N1.instance, + -0.032643825214208, + 0.006677356066269, + 0.0009003298, + 0.0000022707354437, + 0.004509255043043))) .verticalFOV(ThriftyCamConstants.VERTICAL_FOV) .singletagXYStdev(ThriftyCamConstants.SINGLETAG_XY_STANDARD_DEVIATION_COEFFICIENT) .thetaStdev(ThriftyCamConstants.THETA_STANDARD_DEVIATION_COEFFICIENT) .multitagXYStdev(ThriftyCamConstants.MULTITAG_XY_STANDARD_DEVIATION_COEFFICIENT) .cameraDuties(List.of(CameraDuty.FIELD_LOCALIZATION, CameraDuty.REEF_LOCALIZATION)) - .robotToCameraTransform(new Transform3d(0, 0, 0, new Rotation3d(0, 0, 0))) + .robotToCameraTransform( + new Transform3d( + Units.inchesToMeters(11.0), + Units.inchesToMeters(11.75), + Units.inchesToMeters(9.182678), + new Rotation3d( + 0, Units.degreesToRadians(-20.0), Units.degreesToRadians(115.0)))) .build(); - private static final GompeiVisionConfig FRONT_RIGHT = + private static final GompeiVisionConfig FRONT_RIGHT = // Back Left robot relative GompeiVisionConfig.builder() .key("camera_frontright") .hardwareID("camera_frontright") @@ -290,34 +293,39 @@ public static class RobotCameras { MatBuilder.fill( N3.instance, N3.instance, - 1624.2147990980468, - 0.0, - 678.5977326688123, - 0.0, - 1623.8010651757406, - 581.2937963816543, - 0.0, - 0.0, - 1.0))) + 1369.692474966544, + 0, + 787.7364691969475, + 0, + 1369.438576249971, + 623.5492216309891, + 0, + 0, + 1))) .distortionCoefficients( new Matrix( MatBuilder.fill( N5.instance, N1.instance, - 0.0962739678996323, - -0.17425866758812222, - -0.0010256591695401809, - 0.00203018525003567, - 0.1499388749754604))) + -0.012505958090617, + -0.055114601985320, + 0.000799901335506, + 0.003926554248417, + 0.079675565790226))) .verticalFOV(ThriftyCamConstants.VERTICAL_FOV) .singletagXYStdev(ThriftyCamConstants.SINGLETAG_XY_STANDARD_DEVIATION_COEFFICIENT) .thetaStdev(ThriftyCamConstants.THETA_STANDARD_DEVIATION_COEFFICIENT) .multitagXYStdev(ThriftyCamConstants.MULTITAG_XY_STANDARD_DEVIATION_COEFFICIENT) .cameraDuties(List.of(CameraDuty.FIELD_LOCALIZATION, CameraDuty.REEF_LOCALIZATION)) - .robotToCameraTransform(new Transform3d(0, 0, 0, new Rotation3d(0, 0, 0))) + .robotToCameraTransform( + new Transform3d( + Units.inchesToMeters(-11.0), + Units.inchesToMeters(11.75), + Units.inchesToMeters(9.182678), + new Rotation3d(0, Units.degreesToRadians(-20.0), Units.degreesToRadians(65.0)))) .build(); - private static final GompeiVisionConfig FRONT_LEFT = + private static final GompeiVisionConfig FRONT_LEFT = // Front Right robot relative GompeiVisionConfig.builder() .key("camera_frontleft") .hardwareID("camera_frontleft") @@ -330,16 +338,39 @@ public static class RobotCameras { .cameraMatrix( new Matrix( MatBuilder.fill( - N3.instance, N3.instance, 1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0))) + N3.instance, + N3.instance, + 1387.928742097397, + 0, + 736.9807673004121, + 0, + 1380.979555171942, + 621.6284332514149, + 0, + 0, + 1))) .distortionCoefficients( new Matrix( - MatBuilder.fill(N5.instance, N1.instance, 0.0, 0.0, 0.0, 0.0, 0.0))) + MatBuilder.fill( + N5.instance, + N1.instance, + 0.006931789004551, + -0.124967324063348, + -0.003115210783801, + -0.002924665828185, + 0.169363227039459))) .verticalFOV(ThriftyCamConstants.VERTICAL_FOV) .singletagXYStdev(ThriftyCamConstants.SINGLETAG_XY_STANDARD_DEVIATION_COEFFICIENT) .thetaStdev(ThriftyCamConstants.THETA_STANDARD_DEVIATION_COEFFICIENT) .multitagXYStdev(ThriftyCamConstants.MULTITAG_XY_STANDARD_DEVIATION_COEFFICIENT) .cameraDuties(List.of(CameraDuty.FIELD_LOCALIZATION, CameraDuty.REEF_LOCALIZATION)) - .robotToCameraTransform(new Transform3d(0, 0, 0, new Rotation3d(0, 0, 0))) + .robotToCameraTransform( + new Transform3d( + Units.inchesToMeters(11.0), + Units.inchesToMeters(-11.75), + Units.inchesToMeters(9.182678), + new Rotation3d( + 0, Units.degreesToRadians(-20.0), Units.degreesToRadians(-115.0)))) .build(); public static final Camera[] V0_FUNKY_CAMS = { @@ -358,22 +389,18 @@ public static class RobotCameras { new Camera(new CameraIOLimelight(V2_REDUNDANCY_RIGHT)) }; public static final Camera[] V3_EPSILON_CAMS = { - new Camera( - new CameraIOGompeiVision( - BACK_TOP_LEFT, - () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), new Camera( new CameraIOGompeiVision( BACK_BOTTOM_LEFT, () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), - new Camera( - new CameraIOGompeiVision( - BACK_RIGHT, - () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), - new Camera( - new CameraIOGompeiVision( - FRONT_RIGHT, - () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), + new Camera( + new CameraIOGompeiVision( + BACK_RIGHT, + () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), + new Camera( + new CameraIOGompeiVision( + FRONT_RIGHT, + () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), new Camera( new CameraIOGompeiVision( FRONT_LEFT, diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 6897b44d..c3b65559 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -32,6 +32,7 @@ import frc.robot.subsystems.shared.elevator.ElevatorIOSim; import frc.robot.subsystems.shared.elevator.ElevatorIOTalonFX; import frc.robot.subsystems.shared.vision.Vision; +import frc.robot.subsystems.shared.vision.VisionConstants.RobotCameras; import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimber; import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIO; import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIOSim; @@ -90,7 +91,9 @@ public V3_EpsilonRobotContainer() { superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); leds = new V3_EpsilonLEDs(); vision = - new Vision(() -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded)); + new Vision( + () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), + RobotCameras.V3_EPSILON_CAMS); break; case V3_EPSILON_SIM: drive = @@ -107,7 +110,9 @@ public V3_EpsilonRobotContainer() { superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); leds = new V3_EpsilonLEDs(); vision = - new Vision(() -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded)); + new Vision( + () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), + RobotCameras.V3_EPSILON_CAMS); break; default: break; @@ -206,7 +211,9 @@ private void configureButtonBindings() { .whileTrue( V3_EpsilonCompositeCommands.intakeCoralDriverSequence( superstructure, intake, manipulator)) - .onFalse(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); + .onFalse( + V3_EpsilonCompositeCommands.postIntakeCoralSequence( + superstructure, intake, manipulator)); driver .leftBumper() diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java index 6b00dbcf..c49bc314 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java @@ -166,6 +166,8 @@ public V3_EpsilonManipulatorIOTalonFX() { canRange.optimizeBusUtilization(); PhoenixUtil.registerSignals(false, statusSignals); + + armTalonFX.setPosition(0); } /** From a01ad1bf3821b3c329b5638e1b7f7aec213c6d46 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Tue, 21 Oct 2025 14:32:57 -0400 Subject: [PATCH 138/180] calibdb --- src/main/java/frc/robot/Constants.java | 2 +- .../subsystems/shared/vision/Camera.java | 15 ++--- .../shared/vision/CameraIOGompeiVision.java | 20 +++--- .../shared/vision/VisionConstants.java | 61 ++++++++++--------- 4 files changed, 51 insertions(+), 47 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 0b2ef474..4b343dc0 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -5,7 +5,7 @@ public final class Constants { public static final boolean TUNING_MODE = true; public static final double LOOP_PERIOD_SECONDS = 0.02; - public static final RobotType ROBOT = RobotType.V3_EPSILON_SIM; + public static final RobotType ROBOT = RobotType.V3_EPSILON; public static Mode getMode() { switch (ROBOT) { diff --git a/src/main/java/frc/robot/subsystems/shared/vision/Camera.java b/src/main/java/frc/robot/subsystems/shared/vision/Camera.java index cbb93e44..125654d0 100644 --- a/src/main/java/frc/robot/subsystems/shared/vision/Camera.java +++ b/src/main/java/frc/robot/subsystems/shared/vision/Camera.java @@ -76,6 +76,8 @@ public void periodic() { thetaStdev = Double.POSITIVE_INFINITY; } + thetaStdev = Double.POSITIVE_INFINITY; + // Add observation to list double xyStdDev = xyStdevCoeff @@ -120,8 +122,8 @@ public void periodic() { Pose3d cameraPose = new Pose3d( - io.getGompeiVisionConfig().robotToCameraTransform().getTranslation(), - io.getGompeiVisionConfig().robotToCameraTransform().getRotation()); + io.getGompeiVisionConfig().robotRelativePose().getTranslation(), + io.getGompeiVisionConfig().robotRelativePose().getRotation()); // Use 3D distance and tag angles to find robot pose Translation2d camToTagTranslation = @@ -169,11 +171,6 @@ public void periodic() { // txTyObservations.stream() // .sorted(Comparator.comparingDouble(VisionObservation::timestamp)) // .forEach(RobotState::addReefLocalizerVisionMeasurement); - - Logger.recordOutput( - "Vision/Cameras/" + name + "/RobotToCamera", - new Pose3d(RobotState.getRobotPoseField()) - .transformBy(io.getGompeiVisionConfig().robotToCameraTransform())); } public void setValidTags(int... validIds) { @@ -181,7 +178,7 @@ public void setValidTags(int... validIds) { io.setValidTags(validIds); } - public Transform3d getTransform() { - return io.getGompeiVisionConfig().robotToCameraTransform(); + public Pose3d getTransform() { + return io.getGompeiVisionConfig().robotRelativePose(); } } diff --git a/src/main/java/frc/robot/subsystems/shared/vision/CameraIOGompeiVision.java b/src/main/java/frc/robot/subsystems/shared/vision/CameraIOGompeiVision.java index 69300f9a..d74ba8e5 100644 --- a/src/main/java/frc/robot/subsystems/shared/vision/CameraIOGompeiVision.java +++ b/src/main/java/frc/robot/subsystems/shared/vision/CameraIOGompeiVision.java @@ -6,7 +6,7 @@ import edu.wpi.first.math.geometry.Quaternion; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Rotation3d; -import edu.wpi.first.math.geometry.Transform3d; +import edu.wpi.first.math.geometry.Transform2d; import edu.wpi.first.networktables.BooleanSubscriber; import edu.wpi.first.networktables.ConnectionInfo; import edu.wpi.first.networktables.DoubleArraySubscriber; @@ -17,6 +17,7 @@ import frc.robot.FieldConstants; import frc.robot.RobotState; import frc.robot.subsystems.shared.vision.VisionConstants.GompeiVisionConfig; +import frc.robot.util.GeometryUtil; import java.util.ArrayList; import java.util.HashMap; import java.util.List; @@ -24,8 +25,10 @@ import java.util.Optional; import java.util.function.Supplier; import lombok.Getter; +import lombok.experimental.ExtensionMethod; import org.littletonrobotics.junction.Logger; +@ExtensionMethod({GeometryUtil.class}) public class CameraIOGompeiVision implements CameraIO { private final GompeiVisionConfig config; private final Supplier aprilTagLayoutSupplier; @@ -144,7 +147,10 @@ public void updateInputs(CameraIOInputs inputs) { values[3], values[4], new Rotation3d(new Quaternion(values[5], values[6], values[7], values[8]))); - robotPose = cameraPose.transformBy(config.robotToCameraTransform().inverse()).toPose2d(); + robotPose = + cameraPose + .toPose2d() + .transformBy(config.robotRelativePose().toPose2d().toTransform2d().inverse()); break; case 2: @@ -164,14 +170,14 @@ public void updateInputs(CameraIOInputs inputs) { values[11], values[12], new Rotation3d(new Quaternion(values[13], values[14], values[15], values[16]))); - Transform3d cameraToRobot = config.robotToCameraTransform().inverse(); - - Pose2d robotPose0 = cameraPose0.transformBy(cameraToRobot).toPose2d(); - Pose2d robotPose1 = cameraPose1.transformBy(cameraToRobot).toPose2d(); + Transform2d cameraToRobot = + config.robotRelativePose().toPose2d().toTransform2d().inverse(); + Pose2d robotPose0 = cameraPose0.toPose2d().transformBy(cameraToRobot); + Pose2d robotPose1 = cameraPose1.toPose2d().transformBy(cameraToRobot); if (error0 < error1 * VisionConstants.AMBIGUITY_THRESHOLD || error1 < error0 * VisionConstants.AMBIGUITY_THRESHOLD) { - Rotation2d currentRotation = RobotState.getHeadingData().robotHeading(); + Rotation2d currentRotation = RobotState.getRobotPoseField().getRotation(); Rotation2d visionRotation0 = robotPose0.getRotation(); Rotation2d visionRotation1 = robotPose1.getRotation(); if (Math.abs(currentRotation.minus(visionRotation0).getRadians()) diff --git a/src/main/java/frc/robot/subsystems/shared/vision/VisionConstants.java b/src/main/java/frc/robot/subsystems/shared/vision/VisionConstants.java index efb9e7de..f0ac5531 100644 --- a/src/main/java/frc/robot/subsystems/shared/vision/VisionConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/vision/VisionConstants.java @@ -4,6 +4,7 @@ import edu.wpi.first.apriltag.AprilTagFields; import edu.wpi.first.math.MatBuilder; import edu.wpi.first.math.Matrix; +import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation3d; import edu.wpi.first.math.geometry.Transform3d; import edu.wpi.first.math.numbers.N1; @@ -222,8 +223,8 @@ public static class RobotCameras { .thetaStdev(ThriftyCamConstants.THETA_STANDARD_DEVIATION_COEFFICIENT) .multitagXYStdev(ThriftyCamConstants.MULTITAG_XY_STANDARD_DEVIATION_COEFFICIENT) .cameraDuties(List.of(CameraDuty.FIELD_LOCALIZATION, CameraDuty.REEF_LOCALIZATION)) - .robotToCameraTransform( - new Transform3d( + .robotRelativePose( + new Pose3d( Units.inchesToMeters(-11.0), Units.inchesToMeters(-11.75), Units.inchesToMeters(9.182678), @@ -269,8 +270,8 @@ public static class RobotCameras { .thetaStdev(ThriftyCamConstants.THETA_STANDARD_DEVIATION_COEFFICIENT) .multitagXYStdev(ThriftyCamConstants.MULTITAG_XY_STANDARD_DEVIATION_COEFFICIENT) .cameraDuties(List.of(CameraDuty.FIELD_LOCALIZATION, CameraDuty.REEF_LOCALIZATION)) - .robotToCameraTransform( - new Transform3d( + .robotRelativePose( + new Pose3d( Units.inchesToMeters(11.0), Units.inchesToMeters(11.75), Units.inchesToMeters(9.182678), @@ -317,8 +318,8 @@ public static class RobotCameras { .thetaStdev(ThriftyCamConstants.THETA_STANDARD_DEVIATION_COEFFICIENT) .multitagXYStdev(ThriftyCamConstants.MULTITAG_XY_STANDARD_DEVIATION_COEFFICIENT) .cameraDuties(List.of(CameraDuty.FIELD_LOCALIZATION, CameraDuty.REEF_LOCALIZATION)) - .robotToCameraTransform( - new Transform3d( + .robotRelativePose( + new Pose3d( Units.inchesToMeters(-11.0), Units.inchesToMeters(11.75), Units.inchesToMeters(9.182678), @@ -340,12 +341,12 @@ public static class RobotCameras { MatBuilder.fill( N3.instance, N3.instance, - 1387.928742097397, + 1110.6402873755883, 0, - 736.9807673004121, + 613.8829964701134, 0, - 1380.979555171942, - 621.6284332514149, + 1105.8384147122115, + 492.2432667528521, 0, 0, 1))) @@ -354,18 +355,18 @@ public static class RobotCameras { MatBuilder.fill( N5.instance, N1.instance, - 0.006931789004551, - -0.124967324063348, - -0.003115210783801, - -0.002924665828185, - 0.169363227039459))) + -0.028655371446734232, + -0.011652596818001043, + -0.0013733428778411353, + 0.003188600213446814, + 0.03699152783241122))) .verticalFOV(ThriftyCamConstants.VERTICAL_FOV) .singletagXYStdev(ThriftyCamConstants.SINGLETAG_XY_STANDARD_DEVIATION_COEFFICIENT) .thetaStdev(ThriftyCamConstants.THETA_STANDARD_DEVIATION_COEFFICIENT) .multitagXYStdev(ThriftyCamConstants.MULTITAG_XY_STANDARD_DEVIATION_COEFFICIENT) .cameraDuties(List.of(CameraDuty.FIELD_LOCALIZATION, CameraDuty.REEF_LOCALIZATION)) - .robotToCameraTransform( - new Transform3d( + .robotRelativePose( + new Pose3d( Units.inchesToMeters(11.0), Units.inchesToMeters(-11.75), Units.inchesToMeters(9.182678), @@ -389,18 +390,18 @@ public static class RobotCameras { new Camera(new CameraIOLimelight(V2_REDUNDANCY_RIGHT)) }; public static final Camera[] V3_EPSILON_CAMS = { - new Camera( - new CameraIOGompeiVision( - BACK_BOTTOM_LEFT, - () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), - new Camera( - new CameraIOGompeiVision( - BACK_RIGHT, - () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), - new Camera( - new CameraIOGompeiVision( - FRONT_RIGHT, - () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), + // new Camera( + // new CameraIOGompeiVision( + // BACK_BOTTOM_LEFT, + // () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), + // new Camera( + // new CameraIOGompeiVision( + // BACK_RIGHT, + // () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), + // new Camera( + // new CameraIOGompeiVision( + // FRONT_RIGHT, + // () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), new Camera( new CameraIOGompeiVision( FRONT_LEFT, @@ -437,5 +438,5 @@ public record GompeiVisionConfig( double thetaStdev, double multitagXYStdev, List cameraDuties, - Transform3d robotToCameraTransform) {} + Pose3d robotRelativePose) {} } From e2423cf86e620beccc657216fd929ddb428c1188 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Wed, 22 Oct 2025 17:37:00 -0400 Subject: [PATCH 139/180] Refactor vision and drive constants, update coral width, and adjust robot state for improved alignment and scoring logic --- src/main/java/frc/robot/FieldConstants.java | 2 +- src/main/java/frc/robot/RobotState.java | 14 +- .../frc/robot/commands/CompositeCommands.java | 4 +- .../shared/drive/DriveConstants.java | 4 +- .../subsystems/shared/vision/Camera.java | 159 ++++++++++-------- .../shared/vision/CameraIOGompeiVision.java | 49 ++++-- .../shared/vision/VisionConstants.java | 24 +-- .../V3_EpsilonSuperstructureStates.java | 8 +- 8 files changed, 153 insertions(+), 111 deletions(-) diff --git a/src/main/java/frc/robot/FieldConstants.java b/src/main/java/frc/robot/FieldConstants.java index 91327442..9b6fa82a 100644 --- a/src/main/java/frc/robot/FieldConstants.java +++ b/src/main/java/frc/robot/FieldConstants.java @@ -48,7 +48,7 @@ public static class CoralStation { } public static class Reef { - public static final double coralWidth = Units.inchesToMeters(4.5); + public static final double coralWidth = Units.inchesToMeters(2.0); // ffudge public static enum ReefPose { RIGHT, diff --git a/src/main/java/frc/robot/RobotState.java b/src/main/java/frc/robot/RobotState.java index bbf673be..2ae14697 100644 --- a/src/main/java/frc/robot/RobotState.java +++ b/src/main/java/frc/robot/RobotState.java @@ -75,7 +75,7 @@ public class RobotState { } OIData = new OperatorInputData(ReefPose.LEFT, ReefState.STOW); - scoreSide = ScoreSide.CENTER; + scoreSide = ScoreSide.RIGHT; robotHeading = new Rotation2d(); headingOffset = new Rotation2d(); @@ -203,7 +203,11 @@ public static void periodic( boolean atCoralSetpoint = Math.abs(distanceToCoralSetpoint) <= DriveConstants.ALIGN_ROBOT_TO_APRIL_TAG_CONSTANTS.positionThresholdMeters().get() - && Math.abs(autoAlignCoralSetpoint.getRotation().minus(robotHeading).getRadians()) + && Math.abs( + autoAlignCoralSetpoint + .getRotation() + .minus(getRobotPoseReef().getRotation()) + .getRadians()) <= DriveConstants.ALIGN_ROBOT_TO_APRIL_TAG_CONSTANTS .omegaPIDConstants() .tolerance() @@ -211,7 +215,11 @@ public static void periodic( boolean atAlgaeSetpoint = Math.abs(distanceToAlgaeSetpoint) <= DriveConstants.ALIGN_ROBOT_TO_APRIL_TAG_CONSTANTS.positionThresholdMeters().get() - && Math.abs(autoAlignAlgaeSetpoint.getRotation().minus(robotHeading).getRadians()) + && Math.abs( + autoAlignAlgaeSetpoint + .getRotation() + .minus(getRobotPoseReef().getRotation()) + .getRadians()) <= DriveConstants.ALIGN_ROBOT_TO_APRIL_TAG_CONSTANTS .omegaPIDConstants() .tolerance() diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index e326a4df..a6087e44 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -705,8 +705,8 @@ public static final Command optimalAutoScoreCoralSequence( // }) // .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), superstructure.setPosition(), - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), + DriveCommands.autoAlignReefCoral(drive, cameras) + .until(() -> RobotState.getReefAlignData().atCoralSetpoint()), superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight())); } diff --git a/src/main/java/frc/robot/subsystems/shared/drive/DriveConstants.java b/src/main/java/frc/robot/subsystems/shared/drive/DriveConstants.java index 17b74547..7db9c82c 100644 --- a/src/main/java/frc/robot/subsystems/shared/drive/DriveConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/drive/DriveConstants.java @@ -303,11 +303,11 @@ public class DriveConstants { new LoggedTunableNumber("Drive/Align Robot To April Tag/Omega Constants/kD", 0.05), new LoggedTunableNumber( "Drive/Align Robot To April Tag/Omega Constants/tolerance", - Units.degreesToRadians(0.25)), + Units.degreesToRadians(1)), new LoggedTunableNumber( "Drive/Align Robot To April Tag/Omega Constants/maxVelocity", Math.PI)), new LoggedTunableNumber( - "Drive/Align Robot To April Tag/positionThresholdDegrees", 0.03)); + "Drive/Align Robot To April Tag/positionThresholdDegrees", 0.02)); } public record DriveConfig( diff --git a/src/main/java/frc/robot/subsystems/shared/vision/Camera.java b/src/main/java/frc/robot/subsystems/shared/vision/Camera.java index 125654d0..0760ca52 100644 --- a/src/main/java/frc/robot/subsystems/shared/vision/Camera.java +++ b/src/main/java/frc/robot/subsystems/shared/vision/Camera.java @@ -4,11 +4,8 @@ import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.geometry.Rotation3d; import edu.wpi.first.math.geometry.Transform2d; -import edu.wpi.first.math.geometry.Transform3d; import edu.wpi.first.math.geometry.Translation2d; -import edu.wpi.first.math.geometry.Translation3d; import frc.robot.FieldConstants; import frc.robot.RobotState; import frc.robot.RobotState.VisionObservation; @@ -91,73 +88,74 @@ public void periodic() { VecBuilder.fill(xyStdDev, xyStdDev, thetaStdev))); // ONLY DO THIS IF WE ARE RUNNING GOMPEIVISION - if (io instanceof CameraIOGompeiVision) { - for (int i = 0; i < frame.preciseTagIds().length; i++) { - final int tagIdIndex = i; - // Check if tag is valid - if (java.util.Arrays.stream(validIds) - .noneMatch(id -> id == frame.preciseTagIds()[tagIdIndex])) { - continue; - } - // Get rotation at timestamp - var sample = RobotState.getBufferedPose(frame.timestamp()); - if (sample.isEmpty()) { - // exit if not there - return; - } - Rotation2d robotRotation = - RobotState.getRobotPoseField() - .transformBy(new Transform2d(RobotState.getRobotPoseOdometry(), sample.get())) - .getRotation(); - - // Average tx's and ty's - double tx = 0.0; - double ty = 0.0; - for (int j = 0; j < 4; j++) { - tx += frame.preciseTx()[i][j]; - ty += frame.preciseTy()[i][j]; - } - tx /= 4.0; - ty /= 4.0; - - Pose3d cameraPose = - new Pose3d( - io.getGompeiVisionConfig().robotRelativePose().getTranslation(), - io.getGompeiVisionConfig().robotRelativePose().getRotation()); - - // Use 3D distance and tag angles to find robot pose - Translation2d camToTagTranslation = - new Pose3d(Translation3d.kZero, new Rotation3d(0, ty, -tx)) - .transformBy( - new Transform3d( - new Translation3d(frame.preciseDistance()[i], 0, 0), Rotation3d.kZero)) - .getTranslation() - .rotateBy(new Rotation3d(0, cameraPose.getRotation().getY(), 0)) - .toTranslation2d(); - Rotation2d camToTagRotation = - robotRotation.plus( - cameraPose.toPose2d().getRotation().plus(camToTagTranslation.getAngle())); - var tagPose2d = tagPoses2d.get(frame.preciseTagIds()[i]); - if (tagPose2d == null) return; - Translation2d fieldToCameraTranslation = - new Pose2d(tagPose2d.getTranslation(), camToTagRotation.plus(Rotation2d.kPi)) - .transformBy(GeometryUtil.toTransform2d(camToTagTranslation.getNorm(), 0.0)) - .getTranslation(); - robotPose = - new Pose2d( - fieldToCameraTranslation, - robotRotation.plus(cameraPose.toPose2d().getRotation())) - .transformBy(new Transform2d(cameraPose.toPose2d(), Pose2d.kZero)); - // Use gyro angle at time for robot rotation - robotPose = new Pose2d(robotPose.getTranslation(), robotRotation); - - // Add transform to current odometry based pose for latency correction - txTyObservations.add( - new VisionObservation( - robotPose, - frame.timestamp(), - VecBuilder.fill(xyStdDev, xyStdDev, Double.POSITIVE_INFINITY))); + // ONLY do this if using GompeiVision + // Loop over each processed frame + // Only do this if we are running GompeiVision + if (!(io instanceof CameraIOGompeiVision)) continue; + + for (int i = 0; i < frame.preciseTagIds().length; i++) { + int tagId = frame.preciseTagIds()[i]; + + // Skip invalid tags + if (java.util.Arrays.stream(validIds).noneMatch(id -> id == tagId)) continue; + + // Get odometry-based pose at the timestamp + var sample = RobotState.getBufferedPose(frame.timestamp()); + if (sample.isEmpty()) continue; + + // Average tx and ty over four corners + double tx = 0.0; + double ty = 0.0; + for (int j = 0; j < 4; j++) { + tx += frame.preciseTx()[i][j]; + ty += frame.preciseTy()[i][j]; } + tx /= 4.0; + ty /= 4.0; + + Pose3d cameraPose = io.getGompeiVisionConfig().robotRelativePose(); + + // Project 3D distance onto horizontal plane + double distance2d = + frame.preciseDistance()[i] + * Math.cos(-cameraPose.getRotation().getY() - ty); // pitch + tag vertical angle + + // Compute rotation from camera to tag + Rotation2d camToTagRotation = + sample + .get() + .getRotation() + .plus(cameraPose.toPose2d().getRotation().plus(Rotation2d.fromRadians(-tx))); + + Pose2d tagPose2d = tagPoses2d.get(tagId); + if (tagPose2d == null) continue; + + // Compute camera position in field frame + Translation2d fieldToCameraTranslation = + new Pose2d(tagPose2d.getTranslation(), camToTagRotation.plus(Rotation2d.kPi)) + .transformBy(GeometryUtil.toTransform2d(distance2d, 0.0)) + .getTranslation(); + + // Compute robot pose + Pose2d robotPose = + new Pose2d( + fieldToCameraTranslation, + sample.get().getRotation().plus(cameraPose.toPose2d().getRotation())) + .transformBy(new Transform2d(cameraPose.toPose2d(), Pose2d.kZero)); + + // Use odometry rotation only + robotPose = new Pose2d(robotPose.getTranslation(), sample.get().getRotation()); + + // Store observation for fusion + xyStdDev = + io.getPrimaryXYStandardDeviationCoefficient() + * Math.pow(frame.averageDistance(), 1.2) + / Math.pow(frame.totalTargets(), 2.0); + txTyObservations.add( + new VisionObservation( + robotPose, + frame.timestamp(), + VecBuilder.fill(xyStdDev, xyStdDev, Double.POSITIVE_INFINITY))); } } @@ -165,12 +163,27 @@ public void periodic() { poseObservations.stream() .sorted(Comparator.comparingDouble(VisionObservation::timestamp)) .forEach(RobotState::addFieldLocalizerVisionMeasurement); - poseObservations.stream() - .sorted(Comparator.comparingDouble(VisionObservation::timestamp)) - .forEach(RobotState::addReefLocalizerVisionMeasurement); - // txTyObservations.stream() + // poseObservations.stream() // .sorted(Comparator.comparingDouble(VisionObservation::timestamp)) // .forEach(RobotState::addReefLocalizerVisionMeasurement); + txTyObservations.stream() + .sorted(Comparator.comparingDouble(VisionObservation::timestamp)) + .forEach(RobotState::addReefLocalizerVisionMeasurement); + + List imprecisePoses = new ArrayList<>(); + for (VisionObservation obs : poseObservations) { + imprecisePoses.add(obs.pose()); + } + + List precisePoses = new ArrayList<>(); + for (VisionObservation obs : txTyObservations) { + precisePoses.add(obs.pose()); + } + + Logger.recordOutput( + "Vision/Camera/" + name + "/Imprecise Poses", imprecisePoses.toArray(Pose2d[]::new)); + Logger.recordOutput( + "Vision/Camera/" + name + "/Precise Poses", precisePoses.toArray(Pose2d[]::new)); } public void setValidTags(int... validIds) { diff --git a/src/main/java/frc/robot/subsystems/shared/vision/CameraIOGompeiVision.java b/src/main/java/frc/robot/subsystems/shared/vision/CameraIOGompeiVision.java index d74ba8e5..4079f509 100644 --- a/src/main/java/frc/robot/subsystems/shared/vision/CameraIOGompeiVision.java +++ b/src/main/java/frc/robot/subsystems/shared/vision/CameraIOGompeiVision.java @@ -213,17 +213,19 @@ public void updateInputs(CameraIOInputs inputs) { for (int i = (values[0] == 1 ? 9 : 17); i < values.length; i += 10) { int tagId = (int) values[i]; lastTagDetectionTimes.put(tagId, Timer.getTimestamp()); - Optional tagPose = aprilTagLayoutSupplier.get().getTagPose((int) values[i]); + Optional tagPose = aprilTagLayoutSupplier.get().getTagPose(tagId); tagPose.ifPresent(tagPoses::add); } - int[] tagIds = new int[tagPoses.size()]; - double[][] txs = new double[tagPoses.size()][]; - double[][] tys = new double[tagPoses.size()][]; - double[] distances = new double[tagPoses.size()]; + // Prepare arrays + int totalTags = tagPoses.size(); + int[] tagIds = new int[totalTags]; + double[][] txs = new double[totalTags][]; + double[][] tys = new double[totalTags][]; + double[] distances = new double[totalTags]; if (!tagPoses.isEmpty()) { - // Calculate average distance to tag + // Calculate average distance double totalDistance = 0.0; for (Pose3d tagPose : tagPoses) { totalDistance += tagPose.getTranslation().getDistance(cameraPose.getTranslation()); @@ -231,7 +233,7 @@ public void updateInputs(CameraIOInputs inputs) { averageDistance = totalDistance / tagPoses.size(); totalTargets = tagPoses.size(); - // Add TxTy observations + // --- Parse tag angle + distance data --- int tagEstimationDataEndIndex = switch ((int) values[0]) { default -> 0; @@ -240,21 +242,40 @@ public void updateInputs(CameraIOInputs inputs) { }; int indexCounter = 0; - for (int index = tagEstimationDataEndIndex + 1; index < values.length; index += 10) { + + // Step through each 10-value chunk safely + for (int index = tagEstimationDataEndIndex + 1; index + 9 < values.length; index += 10) { + int tagId = (int) values[index]; double[] tx = new double[4]; double[] ty = new double[4]; + + // Read 4 corner pairs for (int i = 0; i < 4; i++) { tx[i] = values[index + 1 + (2 * i)]; ty[i] = values[index + 1 + (2 * i) + 1]; } - int tagId = (int) values[index]; + double distance = values[index + 9]; - tagIds[indexCounter] = tagId; - txs[indexCounter] = tx; - tys[indexCounter] = ty; - distances[indexCounter] = distance; - indexCounter++; + // Store data + if (indexCounter < totalTags) { + tagIds[indexCounter] = tagId; + txs[indexCounter] = tx; + tys[indexCounter] = ty; + distances[indexCounter] = distance; + indexCounter++; + } else { + System.out.println("[WARN] More tag data than expected: indexCounter=" + indexCounter); + } + } + + // Optional debug check + if ((values.length - (tagEstimationDataEndIndex + 1)) % 10 != 0) { + System.out.println( + "[WARN] Observation array not multiple of 10! Length=" + + values.length + + " start=" + + (tagEstimationDataEndIndex + 1)); } } diff --git a/src/main/java/frc/robot/subsystems/shared/vision/VisionConstants.java b/src/main/java/frc/robot/subsystems/shared/vision/VisionConstants.java index f0ac5531..fb0f3ec8 100644 --- a/src/main/java/frc/robot/subsystems/shared/vision/VisionConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/vision/VisionConstants.java @@ -390,18 +390,18 @@ public static class RobotCameras { new Camera(new CameraIOLimelight(V2_REDUNDANCY_RIGHT)) }; public static final Camera[] V3_EPSILON_CAMS = { - // new Camera( - // new CameraIOGompeiVision( - // BACK_BOTTOM_LEFT, - // () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), - // new Camera( - // new CameraIOGompeiVision( - // BACK_RIGHT, - // () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), - // new Camera( - // new CameraIOGompeiVision( - // FRONT_RIGHT, - // () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), + new Camera( + new CameraIOGompeiVision( + BACK_BOTTOM_LEFT, + () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), + new Camera( + new CameraIOGompeiVision( + BACK_RIGHT, + () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), + new Camera( + new CameraIOGompeiVision( + FRONT_RIGHT, + () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeAndyMark))), new Camera( new CameraIOGompeiVision( FRONT_LEFT, diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index e70f943b..024ae4d7 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -54,20 +54,20 @@ public enum V3_EpsilonSuperstructureStates { L2( "L2", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), + new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), SubsystemActions.empty()), L2_SCORE( "L2_SCORE", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.SCORE, IntakePivotState.STOW), + new SubsystemPoses(ReefState.L2, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), L3( "L3", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.STOW), + new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), SubsystemActions.empty()), L3_SCORE( "L3_SCORE", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.SCORE, IntakePivotState.STOW), + new SubsystemPoses(ReefState.L3, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), L4( From 86eaa4767eb61a2bab17079fce0db959730fe28a Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Wed, 22 Oct 2025 18:30:32 -0400 Subject: [PATCH 140/180] Update robot constants for simulation mode and adjust manipulator angles for improved performance --- src/main/java/frc/robot/Constants.java | 2 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 13 +------------ .../intake/V3_EpsilonIntakeConstants.java | 2 +- .../manipulator/V3_EpsilonManipulatorConstants.java | 4 ++-- 4 files changed, 5 insertions(+), 16 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 4b343dc0..0b2ef474 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -5,7 +5,7 @@ public final class Constants { public static final boolean TUNING_MODE = true; public static final double LOOP_PERIOD_SECONDS = 0.02; - public static final RobotType ROBOT = RobotType.V3_EPSILON; + public static final RobotType ROBOT = RobotType.V3_EPSILON_SIM; public static Mode getMode() { switch (ROBOT) { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index c3b65559..4d2995eb 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -4,7 +4,6 @@ import edu.wpi.first.apriltag.AprilTagFields; import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import edu.wpi.first.wpilibj.util.Color; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; @@ -356,16 +355,6 @@ public void robotPeriodic() { */ @Override public Command getAutonomousCommand() { - return Commands.sequence( - superstructure.allTransition(), Commands.runOnce(() -> leds.solid(Color.kGreen))); - // return Commands.sequence( - // V3_EpsilonCompositeCommands.dropAlgae( - // drive, - // elevator, - // manipulator, - // intake, - // superstructure, - // () -> ReefState.ALGAE_INTAKE_TOP, - // RobotCameras.V3_EPSILON_CAMS)); + return autoChooser.selectedCommand(); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index d77de11e..7bc8df7d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -72,7 +72,7 @@ public class V3_EpsilonIntakeConstants { Rotation2d.fromDegrees(1.5)); PIVOT_GAINS = new Gains( - new LoggedTunableNumber("Intake/kP", 1.85), + new LoggedTunableNumber("Intake/kP", 100), new LoggedTunableNumber("Intake/kD", 0.1), new LoggedTunableNumber("Intake/kS", 0.0), new LoggedTunableNumber("Intake/kV", 0.0), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 82ef784b..38a76f11 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -204,7 +204,7 @@ public static record ArmParameters( @RequiredArgsConstructor public static enum ManipulatorArmState { PRE_SCORE(Rotation2d.fromDegrees(50.0)), - SCORE(Rotation2d.fromDegrees(55.0)), // Placeholder value. Make sure to test + SCORE(Rotation2d.fromDegrees(70.0)), // Placeholder value. Make sure to test SCORE_L4(Rotation2d.kPi), PROCESSOR(Rotation2d.fromDegrees(90)), ALGAE_INTAKE_FLOOR(Rotation2d.fromDegrees(90)), @@ -213,7 +213,7 @@ public static enum ManipulatorArmState { FLOOR_INTAKE(Rotation2d.fromDegrees(73.5)), STOW_LINE(Rotation2d.fromDegrees(75)), // What is STOW_LINE? STOW_DOWN(Rotation2d.fromDegrees(88)), - TRANSITION(Rotation2d.fromDegrees(15.0)), // Placeholder value. Make sure to test + TRANSITION(Rotation2d.fromDegrees(25.0)), // Placeholder value. Make sure to test VERTICAL_UP(Rotation2d.fromDegrees(0)), HANDOFF(Rotation2d.kPi), SAFE_ANGLE(Rotation2d.fromDegrees(150)), From df15169696af1a7ec86f4c1657ef2effae7d0c97 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Thu, 23 Oct 2025 02:33:25 -0400 Subject: [PATCH 141/180] Update robot constants and adjust superstructure states for improved scoring and intake functionality --- src/main/deploy/Superstructure.dot | 4 + src/main/deploy/choreo/E_RIGHT_PATH4.traj | 91 ----------- src/main/deploy/choreo/E_RIGHT_PATH5.traj | 58 ------- src/main/deploy/choreo/E_RIGHT_PATH6.traj | 78 --------- src/main/deploy/choreo/E_RIGHT_PATH7.traj | 61 -------- src/main/java/frc/robot/Constants.java | 2 +- src/main/java/frc/robot/FieldConstants.java | 5 + .../robot/commands/AutonomousCommands.java | 3 + .../frc/robot/commands/CompositeCommands.java | 148 +++++++++--------- .../shared/elevator/ElevatorConstants.java | 2 +- .../v3_Epsilon/V3_EpsilonMechanism3d.java | 8 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 23 ++- .../V3_EpsilonSuperstructureStates.java | 8 +- .../intake/V3_EpsilonIntake.java | 5 +- .../intake/V3_EpsilonIntakeConstants.java | 2 +- .../manipulator/V3_EpsilonManipulator.java | 19 ++- .../V3_EpsilonManipulatorConstants.java | 9 +- 17 files changed, 140 insertions(+), 386 deletions(-) delete mode 100644 src/main/deploy/choreo/E_RIGHT_PATH4.traj delete mode 100644 src/main/deploy/choreo/E_RIGHT_PATH5.traj delete mode 100644 src/main/deploy/choreo/E_RIGHT_PATH6.traj delete mode 100644 src/main/deploy/choreo/E_RIGHT_PATH7.traj diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/Superstructure.dot index 2d9c8f8c..5588a243 100644 --- a/src/main/deploy/Superstructure.dot +++ b/src/main/deploy/Superstructure.dot @@ -144,6 +144,8 @@ digraph Superstructure { L2_ALGAE_INTAKE -> FLIP_DOWN [type=UNCONSTRAINED] L2_ALGAE_INTAKE -> L2_ALGAE [type=UNCONSTRAINED] + L2_ALGAE_INTAKE -> L2_ALGAE_DROP [type=UNCONSTRAINED] + L3_ALGAE -> STOW_DOWN [type = NO_ALGAE] L3_ALGAE -> GROUND_ACQUISITION [type = NO_ALGAE] @@ -164,6 +166,8 @@ digraph Superstructure { L3_ALGAE_INTAKE -> STOW_UP [type=UNCONSTRAINED] L3_ALGAE_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] + L3_ALGAE_INTAKE -> L3_ALGAE_DROP [type=UNCONSTRAINED] + PROCESSOR -> POST_PROCESSOR [type = NO_ALGAE] PROCESSOR -> PROCESSOR_SCORE [type=UNCONSTRAINED] diff --git a/src/main/deploy/choreo/E_RIGHT_PATH4.traj b/src/main/deploy/choreo/E_RIGHT_PATH4.traj deleted file mode 100644 index aaa7826b..00000000 --- a/src/main/deploy/choreo/E_RIGHT_PATH4.traj +++ /dev/null @@ -1,91 +0,0 @@ -{ - "name":"E_RIGHT_PATH4", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":3.530534505844116, "y":2.730516195297241, "heading":-0.5235987755982988, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.3093485832214355, "y":3.91524887084961, "heading":-1.5707963267948966, "intervals":19, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":0.9058957099914552, "y":4.042835235595703, "heading":-1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"3.530534505844116 m", "val":3.530534505844116}, "y":{"exp":"2.730516195297241 m", "val":2.730516195297241}, "heading":{"exp":"-30 deg", "val":-0.5235987755982988}, "intervals":31, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.3093485832214355 m", "val":2.3093485832214355}, "y":{"exp":"3.9152488708496094 m", "val":3.91524887084961}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":19, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, - {"x":{"exp":"0.9058957099914551 m", "val":0.9058957099914552}, "y":{"exp":"4.042835235595703 m", "val":4.042835235595703}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,0.76447,1.4505], - "samples":[ - {"t":0.0, "x":3.53053, "y":2.73052, "heading":-0.5236, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.35423, "ay":5.4575, "alpha":-2.44349, "fx":[-62.48473,-41.46199,-53.61392,-70.65709], "fy":[90.12272,101.55179,95.72684,83.92085]}, - {"t":0.0273, "x":3.52928, "y":2.73255, "heading":-0.5236, "vx":-0.09158, "vy":0.149, "omega":-0.06671, "ax":-3.40191, "ay":5.42794, "alpha":-2.42956, "fx":[-63.37175,-42.47287,-54.354,-71.26353], "fy":[89.48994,101.12385,95.30034,83.39663]}, - {"t":0.0546, "x":3.52552, "y":2.73864, "heading":-0.52542, "vx":-0.18446, "vy":0.2972, "omega":-0.13305, "ax":-3.45419, "ay":5.39486, "alpha":-2.4143, "fx":[-64.36787,-43.58938,-55.14465,-71.9169], "fy":[88.76372,100.63723,94.83589,82.82301]}, - {"t":0.08191, "x":3.51919, "y":2.74877, "heading":-0.52905, "vx":-0.27877, "vy":0.44449, "omega":-0.19896, "ax":-3.51172, "ay":5.35762, "alpha":-2.39739, "fx":[-65.48168,-44.82817,-55.99844,-72.62525], "fy":[87.93151,100.07992,94.32407,82.19057]}, - {"t":0.10921, "x":3.51027, "y":2.7629, "heading":-0.53448, "vx":-0.37464, "vy":0.59077, "omega":-0.26442, "ax":-3.57533, "ay":5.31542, "alpha":-2.37843, "fx":[-66.72315,-46.20939,-56.93062,-73.39815], "fy":[86.9779,99.43661,93.75293,81.48771]}, - {"t":0.13651, "x":3.49871, "y":2.78101, "heading":-0.5417, "vx":-0.47226, "vy":0.73589, "omega":-0.32935, "ax":-3.64598, "ay":5.26726, "alpha":-2.35691, "fx":[-68.1039,-47.75749,-57.95989,-74.24716], "fy":[85.88387,98.68756,93.10718,80.69988]}, - {"t":0.16381, "x":3.48446, "y":2.80306, "heading":-0.5507, "vx":-0.5718, "vy":0.8797, "omega":-0.3937, "ax":-3.72486, "ay":5.21185, "alpha":-2.33217, "fx":[-69.63758,-49.50228,-59.10928,-75.18631], "fy":[84.62567,97.80705,92.36699,79.80863]}, - {"t":0.19112, "x":3.46746, "y":2.82902, "heading":-0.56145, "vx":-0.6735, "vy":1.02199, "omega":-0.45738, "ax":-3.81342, "ay":5.14751, "alpha":-2.30332, "fx":[-71.34019,-51.48022,-60.40752,-76.23286], "fy":[83.17333,96.76107,91.50624,78.79019]}, - {"t":0.21842, "x":3.44765, "y":2.85885, "heading":-0.57393, "vx":-0.77762, "vy":1.16253, "omega":-0.52026, "ax":-3.91343, "ay":5.07204, "alpha":-2.26916, "fx":[-73.23057,-53.73601,-61.89077,-77.40824], "fy":[81.48853,95.50411,90.48994,77.6134]}, - {"t":0.24572, "x":3.42496, "y":2.89248, "heading":-0.58814, "vx":-0.88446, "vy":1.30101, "omega":-0.58222, "ax":-4.0271, "ay":4.98249, "alpha":-2.22808, "fx":[-75.33078,-56.32455,-63.60486,-78.7392], "fy":[79.52169,93.97422,89.27029,76.23675]}, - {"t":0.27302, "x":3.39931, "y":2.92985, "heading":-0.60403, "vx":-0.99441, "vy":1.43705, "omega":-0.64305, "ax":-4.15714, "ay":4.87483, "alpha":-2.1779, "fx":[-77.66645,-59.31299,-65.60851,-80.25941], "fy":[77.20769,92.08577,87.78071,74.60385]}, - {"t":0.30033, "x":3.37061, "y":2.97091, "heading":-0.62159, "vx":-1.10791, "vy":1.57014, "omega":-0.70251, "ax":-4.30692, "ay":4.74348, "alpha":-2.11558, "fx":[-80.2667,-62.78266,-67.97722,-82.01135], "fy":[74.45979,89.71836,85.92617,72.63659]}, - {"t":0.32763, "x":3.33876, "y":3.01554, "heading":-0.64077, "vx":-1.2255, "vy":1.69965, "omega":-0.76027, "ax":-4.48052, "ay":4.58051, "alpha":-2.03692, "fx":[-83.16321,-66.82949,-70.80827,-84.04845], "fy":[71.16062,86.69999,83.56765,70.22421]}, - {"t":0.35493, "x":3.30363, "y":3.06365, "heading":-0.66153, "vx":-1.34783, "vy":1.82471, "omega":-0.81588, "ax":-4.68276, "ay":4.37445, "alpha":-1.93605, "fx":[-86.38717,-71.5601,-74.2255,-86.43693], "fy":[67.14914,82.78148,80.49617,67.20581]}, - {"t":0.38223, "x":3.26509, "y":3.1151, "heading":-0.6838, "vx":-1.47568, "vy":1.94414, "omega":-0.86874, "ax":-4.91888, "ay":4.10841, "alpha":-1.80479, "fx":[-89.96167,-77.07648,-78.381,-89.25555], "fy":[62.20164,77.59909,76.38901,63.34156]}, - {"t":0.40954, "x":3.22296, "y":3.16971, "heading":-0.70752, "vx":-1.60998, "vy":2.05631, "omega":-0.91802, "ax":-5.19334, "ay":3.75712, "alpha":-1.63177, "fx":[-93.88442,-83.43416,-83.44258,-92.58796], "fy":[56.00508,70.6249,70.73574,58.26464]}, - {"t":0.43684, "x":3.17707, "y":3.22726, "heading":-0.73259, "vx":-1.75177, "vy":2.15889, "omega":-0.96257, "ax":-5.50661, "ay":3.28289, "alpha":-1.40137, "fx":[-98.09029,-90.54378,-89.53605,-96.49308], "fy":[48.12351,61.11904,62.71957,51.40197]}, - {"t":0.46414, "x":3.12719, "y":3.28742, "heading":-0.75887, "vx":-1.90211, "vy":2.24852, "omega":-1.00083, "ax":-5.84697, "ay":2.63124, "alpha":-1.09252, "fx":[-102.37487,-97.9728,-96.55963,-100.91392], "fy":[37.96731,48.14431,51.06197,41.85269]}, - {"t":0.49144, "x":3.07308, "y":3.34979, "heading":-0.78619, "vx":-2.06175, "vy":2.32036, "omega":-1.03066, "ax":-6.17328, "ay":1.73205, "alpha":-0.67844, "fx":[-106.2516,-104.64263,-103.70084,-105.42807], "fy":[24.80482,30.80696,33.98177,28.25298]}, - {"t":0.51874, "x":3.01449, "y":3.41379, "heading":-0.81433, "vx":-2.23029, "vy":2.36765, "omega":-1.04918, "ax":-6.38797, "ay":0.52388, "alpha":-0.13582, "fx":[-108.73581,-108.64791,-108.57506,-108.67152], "fy":[7.92541,8.96324,9.8954,8.86016]}, - {"t":0.54605, "x":2.95121, "y":3.47863, "heading":-0.84297, "vx":-2.4047, "vy":2.38195, "omega":-1.05289, "ax":-6.32947, "ay":-0.97076, "alpha":0.51586, "fx":[-108.18752,-107.83605,-107.0883,-107.53788], "fy":[-12.85009,-15.77303,-20.11421,-17.31222]}, - {"t":0.57335, "x":2.8832, "y":3.5433, "heading":-0.87172, "vx":-2.57751, "vy":2.35545, "omega":-1.0388, "ax":-5.86257, "ay":-2.55309, "alpha":1.17041, "fx":[-102.68227,-101.38378,-96.81794,-97.99849], "fy":[-36.2737,-40.01284,-50.00595,-47.41665]}, - {"t":0.60065, "x":2.81064, "y":3.60666, "heading":-0.90008, "vx":-2.73757, "vy":2.28574, "omega":-1.00685, "ax":-5.04903, "ay":-3.91201, "alpha":1.64541, "fx":[-91.39425,-90.69052,-81.14374,-80.3018], "fy":[-59.22508,-60.54104,-72.83824,-73.56434]}, - {"t":0.62795, "x":2.73402, "y":3.6676, "heading":-0.92757, "vx":-2.87542, "vy":2.17893, "omega":-0.96193, "ax":-4.16705, "ay":-4.84789, "alpha":1.61476, "fx":[-76.12425,-77.90698,-66.65786,-62.83233], "fy":[-77.9835,-76.38037,-86.39896,-89.08178]}, - {"t":0.65526, "x":2.65396, "y":3.72529, "heading":-0.95384, "vx":-2.98919, "vy":2.04657, "omega":-0.91784, "ax":-3.49053, "ay":-5.37869, "alpha":0.80538, "fx":[-61.43194,-63.77919,-57.56284,-54.71744], "fy":[-90.17198,-88.59202,-92.77274,-94.42313]}, - {"t":0.68256, "x":2.57105, "y":3.77916, "heading":-0.97889, "vx":-3.08449, "vy":1.89972, "omega":-0.89585, "ax":-2.95289, "ay":-5.7022, "alpha":-0.06391, "fx":[-50.11352,-49.82921,-50.34356,-50.62521], "fy":[-97.05541,-97.19793,-96.93044,-96.78744]}, - {"t":0.70986, "x":2.48573, "y":3.8289, "heading":-1.00335, "vx":-3.16511, "vy":1.74404, "omega":-0.89759, "ax":-2.48751, "ay":-5.92084, "alpha":-0.68492, "fx":[-41.55226,-37.71489,-43.1863,-46.79399], "fy":[-101.11602,-102.57888,-100.37364,-98.7784]}, - {"t":0.73716, "x":2.39839, "y":3.87431, "heading":-1.02786, "vx":-3.23303, "vy":1.58239, "omega":-0.91629, "ax":-2.07752, "ay":-6.07551, "alpha":-1.0598, "fx":[-34.79623,-27.94811,-36.05601,-42.55205], "fy":[-103.7071,-105.72204,-103.19994,-100.74185]}, - {"t":0.76447, "x":2.30935, "y":3.91525, "heading":-1.05288, "vx":-3.28975, "vy":1.41651, "omega":-0.94523, "ax":-1.62559, "ay":-6.2059, "alpha":-1.33728, "fx":[-27.81585,-18.1541,-27.57609,-37.05755], "fy":[-105.78865,-107.82683,-105.75457,-102.87228]}, - {"t":0.79085, "x":2.22198, "y":3.95046, "heading":-1.07782, "vx":-3.33264, "vy":1.25276, "omega":-0.98052, "ax":-0.96807, "ay":-6.33534, "alpha":-1.50866, "fx":[-17.91243,-5.80578,-14.79486,-27.35327], "fy":[-107.86741,-109.14923,-108.22326,-105.80923]}, - {"t":0.81724, "x":2.13371, "y":3.98131, "heading":-1.10369, "vx":-3.35818, "vy":1.0856, "omega":-1.02032, "ax":-0.11211, "ay":-6.40723, "alpha":-1.40745, "fx":[-4.70933,7.61341,1.43231,-11.96392], "fy":[-109.19436,-108.99837,-109.17524,-108.57288]}, - {"t":0.84362, "x":2.04506, "y":4.00773, "heading":-1.13061, "vx":-3.36114, "vy":0.91654, "omega":-1.05746, "ax":0.91179, "ay":-6.34619, "alpha":-1.10548, "fx":[12.01967,22.29584,19.50517,8.21634], "fy":[-108.58212,-106.9284,-107.40319,-108.87357]}, - {"t":0.87001, "x":1.95669, "y":4.0297, "heading":-1.15851, "vx":-3.33708, "vy":0.74908, "omega":-1.08663, "ax":2.02912, "ay":-6.08618, "alpha":-0.67048, "fx":[31.65751,37.97849,37.58084,30.84239], "fy":[-104.51481,-102.38363,-102.48441,-104.71414]}, - {"t":0.8964, "x":1.86934, "y":4.04735, "heading":-1.18719, "vx":-3.28354, "vy":0.58849, "omega":-1.10432, "ax":3.12613, "ay":-5.60575, "alpha":-0.16872, "fx":[52.33317,53.83158,54.02684,52.50672], "fy":[-95.82592,-94.99377,-94.87054,-95.71866]}, - {"t":0.92278, "x":1.78379, "y":4.06093, "heading":-1.21632, "vx":-3.20106, "vy":0.44058, "omega":-1.10877, "ax":4.08718, "ay":-4.94983, "alpha":0.33539, "fx":[71.22804,68.68157,67.83785,70.33983], "fy":[-82.76661,-84.88239,-85.58367,-83.54807]}, - {"t":0.94917, "x":1.70075, "y":4.07083, "heading":-1.24558, "vx":-3.09321, "vy":0.30997, "omega":-1.09992, "ax":4.84494, "ay":-4.20884, "alpha":0.79067, "fx":[86.06235,81.42906,78.75831,83.39461], "fy":[-67.27003,-72.77136,-75.71463,-70.60844]}, - {"t":0.97555, "x":1.62082, "y":4.07754, "heading":-1.2746, "vx":-2.96537, "vy":0.19892, "omega":-1.07906, "ax":5.39484, "ay":-3.47138, "alpha":1.16948, "fx":[96.25679,91.4489,87.05914,92.29402], "fy":[-51.75168,-59.75422,-66.07504,-58.60793]}, - {"t":1.00194, "x":1.54445, "y":4.08158, "heading":-1.30308, "vx":-2.82302, "vy":0.10732, "omega":-1.0482, "ax":5.77166, "ay":-2.79393, "alpha":1.47099, "fx":[102.59213,98.70786,93.2296,98.16757], "fy":[-37.82807,-46.89478,-57.1215,-48.2513]}, - {"t":1.02833, "x":1.47197, "y":4.08344, "heading":-1.33073, "vx":-2.67073, "vy":0.0336, "omega":-1.00939, "ax":6.02037, "ay":-2.19968, "alpha":1.7089, "fx":[106.24365,103.59106,97.76896,102.01518], "fy":[-26.08134,-34.94059,-49.0372,-39.60448]}, - {"t":1.05471, "x":1.4036, "y":4.08356, "heading":-1.35737, "vx":-2.51188, "vy":-0.02444, "omega":-0.9643, "ax":6.18017, "ay":-1.69063, "alpha":1.89818, "fx":[108.20248,106.64234,101.09709,104.54948], "fy":[-16.45316,-24.26632,-41.84242,-32.46663]}, - {"t":1.0811, "x":1.33947, "y":4.08233, "heading":-1.38281, "vx":-2.34881, "vy":-0.06905, "omega":-0.91421, "ax":6.28026, "ay":-1.25883, "alpha":2.05026, "fx":[109.14678,108.3811,103.53699,106.23682], "fy":[-8.6351,-14.96348,-35.47774,-26.57322]}, - {"t":1.10749, "x":1.27968, "y":4.08007, "heading":-1.40693, "vx":-2.1831, "vy":-0.10226, "omega":-0.86011, "ax":6.34086, "ay":-0.89317, "alpha":2.17326, "fx":[109.49962,109.22484,105.32677,107.37342], "fy":[-2.27868,-6.96007,-29.85373,-21.67782]}, - {"t":1.13387, "x":1.22429, "y":4.07706, "heading":-1.42963, "vx":-2.01579, "vy":-0.12583, "omega":-0.80277, "ax":6.37547, "ay":-0.5826, "alpha":2.27307, "fx":[109.51454,109.47966,106.63879,108.14673], "fy":[2.9244,-0.11171,-24.8764,-17.57548]}, - {"t":1.16026, "x":1.17332, "y":4.07354, "heading":-1.45081, "vx":-1.84756, "vy":-0.1412, "omega":-0.74279, "ax":6.39301, "ay":-0.31738, "alpha":2.35424, "fx":[109.34108,109.35856,107.59734,108.67641], "fy":[7.22353,5.74442,-20.45862,-14.10333]}, - {"t":1.18664, "x":1.12679, "y":4.0697, "heading":-1.47041, "vx":-1.67888, "vy":-0.14958, "omega":-0.68067, "ax":6.39935, "ay":-0.08939, "alpha":2.42037, "fx":[109.06693,109.00545,108.29234,109.03993], "fy":[10.81324,10.76314,-16.52415,-11.13428]}, - {"t":1.21303, "x":1.08472, "y":4.06572, "heading":-1.48837, "vx":-1.51002, "vy":-0.15194, "omega":-0.61681, "ax":6.39835, "ay":0.10797, "alpha":2.47441, "fx":[108.74325,108.5158,108.78939,109.28826], "fy":[13.84335,15.08074,-13.00819,-8.56956]}, - {"t":1.23942, "x":1.0471, "y":4.06175, "heading":-1.50465, "vx":-1.3412, "vy":-0.14909, "omega":-0.55152, "ax":6.39259, "ay":0.28003, "alpha":2.51874, "fx":[108.39965,107.95224,109.13688,109.45549], "fy":[16.42908,18.81265,-9.85639,-6.33228]}, - {"t":1.2658, "x":1.01394, "y":4.05792, "heading":-1.5192, "vx":-1.17252, "vy":-0.1417, "omega":-0.48506, "ax":6.38376, "ay":0.43105, "alpha":2.5553, "fx":[108.05294,107.35538,109.37086,109.56481], "fy":[18.65945,22.05472,-7.02348,-4.36221]}, - {"t":1.29219, "x":0.98522, "y":4.05433, "heading":-1.532, "vx":-1.00408, "vy":-0.13033, "omega":-0.41763, "ax":6.37304, "ay":0.56447, "alpha":2.58565, "fx":[107.71227,106.75128,109.51858,109.6322], "fy":[20.60373,24.88578,-4.47174,-2.61186]}, - {"t":1.31857, "x":0.96095, "y":4.05108, "heading":-1.54302, "vx":-0.83592, "vy":-0.11543, "omega":-0.34941, "ax":6.36119, "ay":0.68305, "alpha":2.61106, "fx":[107.38222,106.15632,109.60083,109.66885], "fy":[22.3163,27.3704,-2.16968,-1.0434]}, - {"t":1.34496, "x":0.94111, "y":4.04828, "heading":-1.55224, "vx":-0.66807, "vy":-0.09741, "omega":-0.28051, "ax":6.34875, "ay":0.78903, "alpha":2.63254, "fx":[107.06467,105.58058,109.63366,109.68266], "fy":[23.84025,29.56152,-0.09087,0.37352]}, - {"t":1.37135, "x":0.92569, "y":4.04598, "heading":-1.55964, "vx":-0.50055, "vy":-0.07659, "omega":-0.21105, "ax":6.33607, "ay":0.88424, "alpha":2.65092, "fx":[106.75986,105.02991,109.62958,109.67929], "fy":[25.21003,31.50255,1.78695,1.66349]}, - {"t":1.39773, "x":0.91469, "y":4.04427, "heading":-1.56521, "vx":-0.33337, "vy":-0.05326, "omega":-0.1411, "ax":6.32338, "ay":0.97021, "alpha":2.66684, "fx":[106.4671,104.50746,109.59844,109.66281], "fy":[26.45341,33.22922,3.48269,2.84663]}, - {"t":1.42412, "x":0.90809, "y":4.0432, "heading":-1.56893, "vx":-0.16652, "vy":-0.02766, "omega":-0.07074, "ax":6.31087, "ay":1.04817, "alpha":2.68083, "fx":[106.18518,104.01465,109.54802,109.63619], "fy":[27.59298,34.77103,5.01251,3.93957]}, - {"t":1.4505, "x":0.9059, "y":4.04284, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH5.traj b/src/main/deploy/choreo/E_RIGHT_PATH5.traj deleted file mode 100644 index 1bc05343..00000000 --- a/src/main/deploy/choreo/E_RIGHT_PATH5.traj +++ /dev/null @@ -1,58 +0,0 @@ -{ - "name":"E_RIGHT_PATH5", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":0.9058957099914552, "y":4.042835235595703, "heading":-1.5707963267948966, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.8561482429504395, "y":3.878795623779297, "heading":-1.5707963267948966, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"0.9058957099914551 m", "val":0.9058957099914552}, "y":{"exp":"4.042835235595703 m", "val":4.042835235595703}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.8561482429504395 m", "val":2.8561482429504395}, "y":{"exp":"3.878795623779297 m", "val":3.878795623779297}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.10287], - "samples":[ - {"t":0.0, "x":0.9059, "y":4.04284, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.4304, "ay":-0.54087, "alpha":0.0, "fx":[109.37931,109.37931,109.37931,109.37931], "fy":[-9.20011,-9.20011,-9.20011,-9.20011]}, - {"t":0.04795, "x":0.91329, "y":4.04221, "heading":-1.5708, "vx":0.30834, "vy":-0.02594, "omega":0.0, "ax":6.42984, "ay":-0.54083, "alpha":0.0, "fx":[109.36979,109.36979,109.36979,109.36979], "fy":[-9.19931,-9.19931,-9.19931,-9.19931]}, - {"t":0.0959, "x":0.93547, "y":4.04035, "heading":-1.5708, "vx":0.61666, "vy":-0.05187, "omega":0.0, "ax":6.42916, "ay":-0.54077, "alpha":0.0, "fx":[109.35815,109.35815,109.35815,109.35815], "fy":[-9.19833,-9.19833,-9.19833,-9.19833]}, - {"t":0.14385, "x":0.97243, "y":4.03724, "heading":-1.5708, "vx":0.92494, "vy":-0.0778, "omega":0.0, "ax":6.4283, "ay":-0.5407, "alpha":0.0, "fx":[109.3436,109.3436,109.3436,109.3436], "fy":[-9.19711,-9.19711,-9.19711,-9.19711]}, - {"t":0.1918, "x":1.02417, "y":4.03289, "heading":-1.5708, "vx":1.23319, "vy":-0.10373, "omega":0.0, "ax":6.4272, "ay":-0.5406, "alpha":0.0, "fx":[109.3249,109.3249,109.3249,109.3249], "fy":[-9.19553,-9.19553,-9.19553,-9.19553]}, - {"t":0.23975, "x":1.09069, "y":4.02729, "heading":-1.5708, "vx":1.54138, "vy":-0.12965, "omega":0.0, "ax":6.42574, "ay":-0.54048, "alpha":0.0, "fx":[109.29995,109.29995,109.29995,109.29995], "fy":[-9.19344,-9.19344,-9.19344,-9.19344]}, - {"t":0.28771, "x":1.17199, "y":4.02045, "heading":-1.5708, "vx":1.8495, "vy":-0.15556, "omega":0.0, "ax":6.42368, "ay":-0.54031, "alpha":0.0, "fx":[109.26503,109.26503,109.26503,109.26503], "fy":[-9.1905,-9.1905,-9.1905,-9.1905]}, - {"t":0.33566, "x":1.26806, "y":4.01237, "heading":-1.5708, "vx":2.15752, "vy":-0.18147, "omega":0.0, "ax":6.4206, "ay":-0.54005, "alpha":0.0, "fx":[109.21265,109.21265,109.21265,109.21265], "fy":[-9.18609,-9.18609,-9.18609,-9.18609]}, - {"t":0.38361, "x":1.37889, "y":4.00305, "heading":-1.5708, "vx":2.46539, "vy":-0.20737, "omega":0.0, "ax":6.41547, "ay":-0.53962, "alpha":0.0, "fx":[109.12537,109.12537,109.12537,109.12537], "fy":[-9.17875,-9.17875,-9.17875,-9.17875]}, - {"t":0.43156, "x":1.50449, "y":3.99249, "heading":-1.5708, "vx":2.77302, "vy":-0.23324, "omega":0.0, "ax":6.40522, "ay":-0.53876, "alpha":0.0, "fx":[108.95094,108.95094,108.95094,108.95094], "fy":[-9.16408,-9.16408,-9.16408,-9.16408]}, - {"t":0.47951, "x":1.64482, "y":3.98068, "heading":-1.5708, "vx":3.08016, "vy":-0.25908, "omega":0.0, "ax":6.37453, "ay":-0.53617, "alpha":0.0, "fx":[108.429,108.429,108.429,108.429], "fy":[-9.12018,-9.12018,-9.12018,-9.12018]}, - {"t":0.52746, "x":1.79985, "y":3.96764, "heading":-1.5708, "vx":3.38582, "vy":-0.28479, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, - {"t":0.57541, "x":1.9622, "y":3.95399, "heading":-1.5708, "vx":3.38582, "vy":-0.28479, "omega":0.0, "ax":-6.37453, "ay":0.53617, "alpha":0.0, "fx":[-108.429,-108.429,-108.429,-108.429], "fy":[9.12018,9.12018,9.12018,9.12018]}, - {"t":0.62336, "x":2.11722, "y":3.94095, "heading":-1.5708, "vx":3.08016, "vy":-0.25908, "omega":0.0, "ax":-6.40522, "ay":0.53876, "alpha":0.0, "fx":[-108.95094,-108.95094,-108.95094,-108.95094], "fy":[9.16408,9.16408,9.16408,9.16408]}, - {"t":0.67131, "x":2.25756, "y":3.92914, "heading":-1.5708, "vx":2.77302, "vy":-0.23324, "omega":0.0, "ax":-6.41547, "ay":0.53962, "alpha":0.0, "fx":[-109.12537,-109.12537,-109.12537,-109.12537], "fy":[9.17875,9.17875,9.17875,9.17875]}, - {"t":0.71926, "x":2.38315, "y":3.91858, "heading":-1.5708, "vx":2.46539, "vy":-0.20737, "omega":0.0, "ax":-6.4206, "ay":0.54005, "alpha":0.0, "fx":[-109.21265,-109.21265,-109.21265,-109.21265], "fy":[9.18609,9.18609,9.18609,9.18609]}, - {"t":0.76721, "x":2.49399, "y":3.90926, "heading":-1.5708, "vx":2.15752, "vy":-0.18147, "omega":0.0, "ax":-6.42368, "ay":0.54031, "alpha":0.0, "fx":[-109.26503,-109.26503,-109.26503,-109.26503], "fy":[9.1905,9.1905,9.1905,9.1905]}, - {"t":0.81517, "x":2.59006, "y":3.90118, "heading":-1.5708, "vx":1.8495, "vy":-0.15556, "omega":0.0, "ax":-6.42574, "ay":0.54048, "alpha":0.0, "fx":[-109.29995,-109.29995,-109.29995,-109.29995], "fy":[9.19344,9.19344,9.19344,9.19344]}, - {"t":0.86312, "x":2.67135, "y":3.89434, "heading":-1.5708, "vx":1.54138, "vy":-0.12965, "omega":0.0, "ax":-6.4272, "ay":0.5406, "alpha":0.0, "fx":[-109.3249,-109.3249,-109.3249,-109.3249], "fy":[9.19553,9.19553,9.19553,9.19553]}, - {"t":0.91107, "x":2.73788, "y":3.88874, "heading":-1.5708, "vx":1.23319, "vy":-0.10373, "omega":0.0, "ax":-6.4283, "ay":0.5407, "alpha":0.0, "fx":[-109.3436,-109.3436,-109.3436,-109.3436], "fy":[9.19711,9.19711,9.19711,9.19711]}, - {"t":0.95902, "x":2.78962, "y":3.88439, "heading":-1.5708, "vx":0.92494, "vy":-0.0778, "omega":0.0, "ax":-6.42916, "ay":0.54077, "alpha":0.0, "fx":[-109.35815,-109.35815,-109.35815,-109.35815], "fy":[9.19833,9.19833,9.19833,9.19833]}, - {"t":1.00697, "x":2.82658, "y":3.88128, "heading":-1.5708, "vx":0.61666, "vy":-0.05187, "omega":0.0, "ax":-6.42984, "ay":0.54083, "alpha":0.0, "fx":[-109.36979,-109.36979,-109.36979,-109.36979], "fy":[9.19931,9.19931,9.19931,9.19931]}, - {"t":1.05492, "x":2.84876, "y":3.87942, "heading":-1.5708, "vx":0.30834, "vy":-0.02594, "omega":0.0, "ax":-6.4304, "ay":0.54087, "alpha":0.0, "fx":[-109.37931,-109.37931,-109.37931,-109.37931], "fy":[9.20011,9.20011,9.20011,9.20011]}, - {"t":1.10287, "x":2.85615, "y":3.8788, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH6.traj b/src/main/deploy/choreo/E_RIGHT_PATH6.traj deleted file mode 100644 index 235021fc..00000000 --- a/src/main/deploy/choreo/E_RIGHT_PATH6.traj +++ /dev/null @@ -1,78 +0,0 @@ -{ - "name":"E_RIGHT_PATH6", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":2.8561482429504395, "y":3.878795623779297, "heading":-1.5707963267948966, "intervals":22, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.145307779312134, "y":5.592101097106934, "heading":-1.5707963267948966, "intervals":19, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":0.8512157797813416, "y":5.810821056365967, "heading":-1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"2.8561482429504395 m", "val":2.8561482429504395}, "y":{"exp":"3.878795623779297 m", "val":3.878795623779297}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":22, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.145307779312134 m", "val":2.145307779312134}, "y":{"exp":"5.592101097106934 m", "val":5.592101097106934}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":19, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"0.8512157797813416 m", "val":0.8512157797813416}, "y":{"exp":"5.810821056365967 m", "val":5.810821056365967}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,0.85028,1.54355], - "samples":[ - {"t":0.0, "x":2.85615, "y":3.8788, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-0.03288, "ay":6.45173, "alpha":0.0, "fx":[-0.55927,-0.55927,-0.55927,-0.55927], "fy":[109.74203,109.74203,109.74203,109.74203]}, - {"t":0.03865, "x":2.85612, "y":3.88361, "heading":-1.5708, "vx":-0.00127, "vy":0.24935, "omega":0.0, "ax":-0.13527, "ay":6.44985, "alpha":0.0, "fx":[-2.30084,-2.30084,-2.30084,-2.30084], "fy":[109.71011,109.71011,109.71011,109.71011]}, - {"t":0.0773, "x":2.85597, "y":3.89807, "heading":-1.5708, "vx":-0.0065, "vy":0.49863, "omega":0.0, "ax":-0.25498, "ay":6.4456, "alpha":0.0, "fx":[-4.3372,-4.3372,-4.3372,-4.3372], "fy":[109.63773,109.63773,109.63773,109.63773]}, - {"t":0.11595, "x":2.85553, "y":3.92215, "heading":-1.5708, "vx":-0.01635, "vy":0.74775, "omega":0.0, "ax":-0.39667, "ay":6.43768, "alpha":0.0, "fx":[-6.74733,-6.74733,-6.74733,-6.74733], "fy":[109.50314,109.50314,109.50314,109.50314]}, - {"t":0.1546, "x":2.8546, "y":3.95586, "heading":-1.5708, "vx":-0.03168, "vy":0.99656, "omega":0.0, "ax":-0.56672, "ay":6.42405, "alpha":0.0, "fx":[-9.63973,-9.63973,-9.63973,-9.63973], "fy":[109.27132,109.27132,109.27132,109.27132]}, - {"t":0.19324, "x":2.85296, "y":3.99918, "heading":-1.5708, "vx":-0.05359, "vy":1.24484, "omega":0.0, "ax":-0.77407, "ay":6.40129, "alpha":0.0, "fx":[-13.16676,-13.16676,-13.16676,-13.16676], "fy":[108.88416,108.88416,108.88416,108.88416]}, - {"t":0.23189, "x":2.85031, "y":4.05207, "heading":-1.5708, "vx":-0.0835, "vy":1.49225, "omega":0.0, "ax":-1.03158, "ay":6.36352, "alpha":0.0, "fx":[-17.54696,-17.54696,-17.54696,-17.54696], "fy":[108.24173,108.24173,108.24173,108.24173]}, - {"t":0.27054, "x":2.84631, "y":4.1145, "heading":-1.5708, "vx":-0.12337, "vy":1.73819, "omega":0.0, "ax":-1.35805, "ay":6.30022, "alpha":0.0, "fx":[-23.1001,-23.1001,-23.1001,-23.1001], "fy":[107.16496,107.16496,107.16496,107.16496]}, - {"t":0.30919, "x":2.84053, "y":4.18638, "heading":-1.5708, "vx":-0.17586, "vy":1.98169, "omega":0.0, "ax":-1.78132, "ay":6.19165, "alpha":0.0, "fx":[-30.29968,-30.29968,-30.29968,-30.29968], "fy":[105.31814,105.31814,105.31814,105.31814]}, - {"t":0.34784, "x":2.8324, "y":4.26759, "heading":-1.5708, "vx":-0.24471, "vy":2.22099, "omega":0.0, "ax":-2.34205, "ay":5.99905, "alpha":0.0, "fx":[-39.83754,-39.83754,-39.83754,-39.83754], "fy":[102.04213,102.04213,102.04213,102.04213]}, - {"t":0.38649, "x":2.82119, "y":4.35791, "heading":-1.5708, "vx":-0.33523, "vy":2.45284, "omega":0.0, "ax":-3.09443, "ay":5.64372, "alpha":0.0, "fx":[-52.63535,-52.63535,-52.63535,-52.63535], "fy":[95.99808,95.99808,95.99808,95.99808]}, - {"t":0.42514, "x":2.80592, "y":4.45693, "heading":-1.5708, "vx":-0.45482, "vy":2.67097, "omega":0.0, "ax":-4.08459, "ay":4.96836, "alpha":0.0, "fx":[-69.47768,-69.47768,-69.47768,-69.47768], "fy":[84.51037,84.51037,84.51037,84.51037]}, - {"t":0.46379, "x":2.7853, "y":4.56387, "heading":-1.5708, "vx":-0.61269, "vy":2.86299, "omega":0.0, "ax":-5.24651, "ay":3.71216, "alpha":0.0, "fx":[-89.24159,-89.24159,-89.24159,-89.24159], "fy":[63.14277,63.14277,63.14277,63.14277]}, - {"t":0.50244, "x":2.7577, "y":4.67729, "heading":-1.5708, "vx":-0.81546, "vy":3.00646, "omega":0.0, "ax":-6.19357, "ay":1.70531, "alpha":0.0, "fx":[-105.35091,-105.35091,-105.35091,-105.35091], "fy":[29.0068,29.0068,29.0068,29.0068]}, - {"t":0.54109, "x":2.72155, "y":4.79476, "heading":-1.5708, "vx":-1.05484, "vy":3.07237, "omega":0.0, "ax":-6.39591, "ay":-0.61517, "alpha":0.0, "fx":[-108.79267,-108.79267,-108.79267,-108.79267], "fy":[-10.46392,-10.46392,-10.46392,-10.46392]}, - {"t":0.57973, "x":2.67601, "y":4.91305, "heading":-1.5708, "vx":-1.30203, "vy":3.04859, "omega":0.0, "ax":-5.93068, "ay":-2.48406, "alpha":0.0, "fx":[-100.87913,-100.87913,-100.87913,-100.87913], "fy":[-42.25308,-42.25308,-42.25308,-42.25308]}, - {"t":0.61838, "x":2.62126, "y":5.02902, "heading":-1.5708, "vx":-1.53125, "vy":2.95259, "omega":0.0, "ax":-5.26731, "ay":-3.69606, "alpha":0.0, "fx":[-89.59539,-89.59539,-89.59539,-89.59539], "fy":[-62.86897,-62.86897,-62.86897,-62.86897]}, - {"t":0.65703, "x":2.55814, "y":5.14037, "heading":-1.5708, "vx":-1.73482, "vy":2.80974, "omega":0.0, "ax":-4.66407, "ay":-4.43883, "alpha":0.0, "fx":[-79.33457,-79.33457,-79.33457,-79.33457], "fy":[-75.50329,-75.50329,-75.50329,-75.50329]}, - {"t":0.69568, "x":2.48761, "y":5.24565, "heading":-1.5708, "vx":-1.91508, "vy":2.63818, "omega":0.0, "ax":-4.17646, "ay":-4.90446, "alpha":0.0, "fx":[-71.04039,-71.04039,-71.04039,-71.04039], "fy":[-83.42349,-83.42349,-83.42349,-83.42349]}, - {"t":0.73433, "x":2.41047, "y":5.34395, "heading":-1.5708, "vx":-2.0765, "vy":2.44863, "omega":0.0, "ax":-3.79243, "ay":-5.21004, "alpha":0.0, "fx":[-64.50817,-64.50817,-64.50817,-64.50817], "fy":[-88.62122,-88.62122,-88.62122,-88.62122]}, - {"t":0.77298, "x":2.32739, "y":5.4347, "heading":-1.5708, "vx":-2.22307, "vy":2.24727, "omega":0.0, "ax":-3.48882, "ay":-5.42022, "alpha":0.0, "fx":[-59.34377,-59.34377,-59.34377,-59.34377], "fy":[-92.19642,-92.19642,-92.19642,-92.19642]}, - {"t":0.81163, "x":2.23886, "y":5.5175, "heading":-1.5708, "vx":-2.35791, "vy":2.03778, "omega":0.0, "ax":-3.24556, "ay":-5.57097, "alpha":0.0, "fx":[-55.20609,-55.20609,-55.20609,-55.20609], "fy":[-94.76054,-94.76054,-94.76054,-94.76054]}, - {"t":0.85028, "x":2.14531, "y":5.5921, "heading":-1.5708, "vx":-2.48335, "vy":1.82247, "omega":0.0, "ax":-2.96055, "ay":-5.72676, "alpha":0.0, "fx":[-50.35806,-50.35806,-50.35806,-50.35806], "fy":[-97.41047,-97.41047,-97.41047,-97.41047]}, - {"t":0.88677, "x":2.05272, "y":5.65479, "heading":-1.5708, "vx":-2.59137, "vy":1.61351, "omega":0.0, "ax":-2.51661, "ay":-5.93359, "alpha":0.0, "fx":[-42.8068,-42.8068,-42.8068,-42.8068], "fy":[-100.92866,-100.92866,-100.92866,-100.92866]}, - {"t":0.92325, "x":1.9565, "y":5.70971, "heading":-1.5708, "vx":-2.6832, "vy":1.39701, "omega":0.0, "ax":-1.92603, "ay":-6.14877, "alpha":0.0, "fx":[-32.76117,-32.76117,-32.76117,-32.76117], "fy":[-104.58881,-104.58881,-104.58881,-104.58881]}, - {"t":0.95974, "x":1.85731, "y":5.75659, "heading":-1.5708, "vx":-2.75348, "vy":1.17265, "omega":0.0, "ax":-1.13172, "ay":-6.34098, "alpha":0.0, "fx":[-19.25029,-19.25029,-19.25029,-19.25029], "fy":[-107.8582,-107.8582,-107.8582,-107.8582]}, - {"t":0.99623, "x":1.75609, "y":5.79516, "heading":-1.5708, "vx":-2.79477, "vy":0.94128, "omega":0.0, "ax":-0.07234, "ay":-6.43835, "alpha":0.0, "fx":[-1.2304,-1.2304,-1.2304,-1.2304], "fy":[-109.51456,-109.51456,-109.51456,-109.51456]}, - {"t":1.03272, "x":1.65406, "y":5.82522, "heading":-1.5708, "vx":-2.79741, "vy":0.70636, "omega":0.0, "ax":1.2733, "ay":-6.30928, "alpha":0.0, "fx":[21.65848,21.65848,21.65848,21.65848], "fy":[-107.31901,-107.31901,-107.31901,-107.31901]}, - {"t":1.06921, "x":1.55284, "y":5.84679, "heading":-1.5708, "vx":-2.75095, "vy":0.47615, "omega":0.0, "ax":2.79607, "ay":-5.79585, "alpha":0.0, "fx":[47.56039,47.56039,47.56039,47.56039], "fy":[-98.58573,-98.58573,-98.58573,-98.58573]}, - {"t":1.10569, "x":1.45432, "y":5.86031, "heading":-1.5708, "vx":-2.64893, "vy":0.26467, "omega":0.0, "ax":4.22027, "ay":-4.85803, "alpha":0.0, "fx":[71.7856,71.7856,71.7856,71.7856], "fy":[-82.63368,-82.63368,-82.63368,-82.63368]}, - {"t":1.14218, "x":1.36048, "y":5.86673, "heading":-1.5708, "vx":-2.49494, "vy":0.08741, "omega":0.0, "ax":5.27988, "ay":-3.68161, "alpha":0.0, "fx":[89.80921,89.80921,89.80921,89.80921], "fy":[-62.62313,-62.62313,-62.62313,-62.62313]}, - {"t":1.17867, "x":1.27296, "y":5.86747, "heading":-1.5708, "vx":-2.30229, "vy":-0.04692, "omega":0.0, "ax":5.92127, "ay":-2.52981, "alpha":0.0, "fx":[100.71903,100.71903,100.71903,100.71903], "fy":[-43.03142,-43.03142,-43.03142,-43.03142]}, - {"t":1.21516, "x":1.1929, "y":5.86407, "heading":-1.5708, "vx":-2.08623, "vy":-0.13923, "omega":0.0, "ax":6.25183, "ay":-1.55143, "alpha":0.0, "fx":[106.34182,106.34182,106.34182,106.34182], "fy":[-26.38945,-26.38945,-26.38945,-26.38945]}, - {"t":1.25164, "x":1.12093, "y":5.85796, "heading":-1.5708, "vx":-1.85812, "vy":-0.19584, "omega":0.0, "ax":6.39716, "ay":-0.77221, "alpha":0.0, "fx":[108.81392,108.81392,108.81392,108.81392], "fy":[-13.13501,-13.13501,-13.13501,-13.13501]}, - {"t":1.28813, "x":1.05739, "y":5.8503, "heading":-1.5708, "vx":-1.6247, "vy":-0.22402, "omega":0.0, "ax":6.44334, "ay":-0.16359, "alpha":0.0, "fx":[109.59934,109.59934,109.59934,109.59934], "fy":[-2.78267,-2.78267,-2.78267,-2.78267]}, - {"t":1.32462, "x":1.0024, "y":5.84202, "heading":-1.5708, "vx":-1.38959, "vy":-0.22999, "omega":0.0, "ax":6.43932, "ay":0.31289, "alpha":0.0, "fx":[109.53092,109.53092,109.53092,109.53092], "fy":[5.32212,5.32212,5.32212,5.32212]}, - {"t":1.36111, "x":0.95599, "y":5.83383, "heading":-1.5708, "vx":-1.15463, "vy":-0.21857, "omega":0.0, "ax":6.41109, "ay":0.69029, "alpha":0.0, "fx":[109.05089,109.05089,109.05089,109.05089], "fy":[11.74167,11.74167,11.74167,11.74167]}, - {"t":1.3976, "x":0.91812, "y":5.82632, "heading":-1.5708, "vx":-0.92071, "vy":-0.19338, "omega":0.0, "ax":6.37216, "ay":0.99369, "alpha":0.0, "fx":[108.38867,108.38867,108.38867,108.38867], "fy":[16.90232,16.90232,16.90232,16.90232]}, - {"t":1.43408, "x":0.88877, "y":5.81992, "heading":-1.5708, "vx":-0.6882, "vy":-0.15712, "omega":0.0, "ax":6.32946, "ay":1.24132, "alpha":0.0, "fx":[107.66232,107.66232,107.66232,107.66232], "fy":[21.11458,21.11458,21.11458,21.11458]}, - {"t":1.47057, "x":0.86787, "y":5.81502, "heading":-1.5708, "vx":-0.45725, "vy":-0.11183, "omega":0.0, "ax":6.28652, "ay":1.4464, "alpha":0.0, "fx":[106.93183,106.93183,106.93183,106.93183], "fy":[24.60281,24.60281,24.60281,24.60281]}, - {"t":1.50706, "x":0.85537, "y":5.8119, "heading":-1.5708, "vx":-0.22787, "vy":-0.05906, "omega":0.0, "ax":6.24507, "ay":1.61849, "alpha":0.0, "fx":[106.22678,106.22678,106.22678,106.22678], "fy":[27.53001,27.53001,27.53001,27.53001]}, - {"t":1.54355, "x":0.85122, "y":5.81082, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/E_RIGHT_PATH7.traj b/src/main/deploy/choreo/E_RIGHT_PATH7.traj deleted file mode 100644 index 85cb3fa9..00000000 --- a/src/main/deploy/choreo/E_RIGHT_PATH7.traj +++ /dev/null @@ -1,61 +0,0 @@ -{ - "name":"E_RIGHT_PATH7", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":0.8512157797813416, "y":5.810821056365967, "heading":-1.5707963267948966, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.892600774765014, "y":4.152195453643799, "heading":-1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"0.8512157797813416 m", "val":0.8512157797813416}, "y":{"exp":"5.810821056365967 m", "val":5.810821056365967}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":26, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.8926007747650146 m", "val":2.892600774765014}, "y":{"exp":"4.152195453643799 m", "val":4.152195453643799}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.27916], - "samples":[ - {"t":0.0, "x":0.85122, "y":5.81082, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.00847, "ay":-4.06938, "alpha":0.0, "fx":[85.19267,85.19267,85.19267,85.19267], "fy":[-69.21905,-69.21905,-69.21905,-69.21905]}, - {"t":0.0492, "x":0.85728, "y":5.8059, "heading":-1.5708, "vx":0.24641, "vy":-0.20021, "omega":0.0, "ax":5.00809, "ay":-4.06907, "alpha":0.0, "fx":[85.18611,85.18611,85.18611,85.18611], "fy":[-69.21373,-69.21373,-69.21373,-69.21373]}, - {"t":0.0984, "x":0.87546, "y":5.79112, "heading":-1.5708, "vx":0.4928, "vy":-0.4004, "omega":0.0, "ax":5.00762, "ay":-4.06869, "alpha":0.0, "fx":[85.17824,85.17824,85.17824,85.17824], "fy":[-69.20734,-69.20734,-69.20734,-69.20734]}, - {"t":0.1476, "x":0.90577, "y":5.7665, "heading":-1.5708, "vx":0.73917, "vy":-0.60057, "omega":0.0, "ax":5.00706, "ay":-4.06824, "alpha":0.0, "fx":[85.16863,85.16863,85.16863,85.16863], "fy":[-69.19952,-69.19952,-69.19952,-69.19952]}, - {"t":0.19679, "x":0.94819, "y":5.73203, "heading":-1.5708, "vx":0.9855, "vy":-0.80072, "omega":0.0, "ax":5.00635, "ay":-4.06766, "alpha":0.0, "fx":[85.15661,85.15661,85.15661,85.15661], "fy":[-69.18975,-69.18975,-69.18975,-69.18975]}, - {"t":0.24599, "x":1.00274, "y":5.68771, "heading":-1.5708, "vx":1.23181, "vy":-1.00084, "omega":0.0, "ax":5.00544, "ay":-4.06692, "alpha":0.0, "fx":[85.14115,85.14115,85.14115,85.14115], "fy":[-69.17719,-69.17719,-69.17719,-69.17719]}, - {"t":0.29519, "x":1.0694, "y":5.63355, "heading":-1.5708, "vx":1.47807, "vy":-1.20093, "omega":0.0, "ax":5.00423, "ay":-4.06594, "alpha":0.0, "fx":[85.12053,85.12053,85.12053,85.12053], "fy":[-69.16044,-69.16044,-69.16044,-69.16044]}, - {"t":0.34439, "x":1.14817, "y":5.56954, "heading":-1.5708, "vx":1.72427, "vy":-1.40097, "omega":0.0, "ax":5.00253, "ay":-4.06456, "alpha":0.0, "fx":[85.09167,85.09167,85.09167,85.09167], "fy":[-69.13699,-69.13699,-69.13699,-69.13699]}, - {"t":0.39359, "x":1.23906, "y":5.4957, "heading":-1.5708, "vx":1.97038, "vy":-1.60094, "omega":0.0, "ax":4.99999, "ay":-4.06249, "alpha":0.0, "fx":[85.04837,85.04837,85.04837,85.04837], "fy":[-69.10181,-69.10181,-69.10181,-69.10181]}, - {"t":0.44279, "x":1.34205, "y":5.41202, "heading":-1.5708, "vx":2.21638, "vy":-1.80081, "omega":0.0, "ax":4.99575, "ay":-4.05905, "alpha":0.0, "fx":[84.97623,84.97623,84.97623,84.97623], "fy":[-69.0432,-69.0432,-69.0432,-69.0432]}, - {"t":0.49198, "x":1.45714, "y":5.31851, "heading":-1.5708, "vx":2.46216, "vy":-2.0005, "omega":0.0, "ax":4.98728, "ay":-4.05216, "alpha":0.0, "fx":[84.83216,84.83216,84.83216,84.83216], "fy":[-68.92615,-68.92615,-68.92615,-68.92615]}, - {"t":0.54118, "x":1.58431, "y":5.21518, "heading":-1.5708, "vx":2.70752, "vy":-2.19986, "omega":0.0, "ax":4.96204, "ay":-4.03166, "alpha":0.0, "fx":[84.40283,84.40283,84.40283,84.40283], "fy":[-68.57731,-68.57731,-68.57731,-68.57731]}, - {"t":0.59038, "x":1.72352, "y":5.10208, "heading":-1.5708, "vx":2.95165, "vy":-2.39822, "omega":0.0, "ax":2.62317, "ay":-2.13132, "alpha":0.0, "fx":[44.61935,44.61935,44.61935,44.61935], "fy":[-36.25323,-36.25323,-36.25323,-36.25323]}, - {"t":0.63958, "x":1.87191, "y":4.98151, "heading":-1.5708, "vx":3.0807, "vy":-2.50307, "omega":0.0, "ax":-2.62317, "ay":2.13132, "alpha":0.0, "fx":[-44.61935,-44.61935,-44.61935,-44.61935], "fy":[36.25323,36.25323,36.25323,36.25323]}, - {"t":0.68878, "x":2.0203, "y":4.86094, "heading":-1.5708, "vx":2.95165, "vy":-2.39822, "omega":0.0, "ax":-4.96204, "ay":4.03166, "alpha":0.0, "fx":[-84.40283,-84.40283,-84.40283,-84.40283], "fy":[68.57731,68.57731,68.57731,68.57731]}, - {"t":0.73798, "x":2.15951, "y":4.74783, "heading":-1.5708, "vx":2.70752, "vy":-2.19986, "omega":0.0, "ax":-4.98728, "ay":4.05216, "alpha":0.0, "fx":[-84.83216,-84.83216,-84.83216,-84.83216], "fy":[68.92615,68.92615,68.92615,68.92615]}, - {"t":0.78717, "x":2.28668, "y":4.64451, "heading":-1.5708, "vx":2.46216, "vy":-2.0005, "omega":0.0, "ax":-4.99575, "ay":4.05905, "alpha":0.0, "fx":[-84.97623,-84.97623,-84.97623,-84.97623], "fy":[69.0432,69.0432,69.0432,69.0432]}, - {"t":0.83637, "x":2.40177, "y":4.551, "heading":-1.5708, "vx":2.21638, "vy":-1.80081, "omega":0.0, "ax":-4.99999, "ay":4.06249, "alpha":0.0, "fx":[-85.04837,-85.04837,-85.04837,-85.04837], "fy":[69.10181,69.10181,69.10181,69.10181]}, - {"t":0.88557, "x":2.50476, "y":4.46732, "heading":-1.5708, "vx":1.97038, "vy":-1.60094, "omega":0.0, "ax":-5.00253, "ay":4.06456, "alpha":0.0, "fx":[-85.09167,-85.09167,-85.09167,-85.09167], "fy":[69.13699,69.13699,69.13699,69.13699]}, - {"t":0.93477, "x":2.59564, "y":4.39347, "heading":-1.5708, "vx":1.72427, "vy":-1.40097, "omega":0.0, "ax":-5.00423, "ay":4.06594, "alpha":0.0, "fx":[-85.12053,-85.12053,-85.12053,-85.12053], "fy":[69.16044,69.16044,69.16044,69.16044]}, - {"t":0.98397, "x":2.67442, "y":4.32947, "heading":-1.5708, "vx":1.47807, "vy":-1.20093, "omega":0.0, "ax":-5.00544, "ay":4.06692, "alpha":0.0, "fx":[-85.14115,-85.14115,-85.14115,-85.14115], "fy":[69.17719,69.17719,69.17719,69.17719]}, - {"t":1.03317, "x":2.74108, "y":4.27531, "heading":-1.5708, "vx":1.23181, "vy":-1.00084, "omega":0.0, "ax":-5.00635, "ay":4.06766, "alpha":0.0, "fx":[-85.15661,-85.15661,-85.15661,-85.15661], "fy":[69.18975,69.18975,69.18975,69.18975]}, - {"t":1.08236, "x":2.79562, "y":4.23099, "heading":-1.5708, "vx":0.9855, "vy":-0.80072, "omega":0.0, "ax":-5.00706, "ay":4.06824, "alpha":0.0, "fx":[-85.16863,-85.16863,-85.16863,-85.16863], "fy":[69.19952,69.19952,69.19952,69.19952]}, - {"t":1.13156, "x":2.83805, "y":4.19652, "heading":-1.5708, "vx":0.73917, "vy":-0.60057, "omega":0.0, "ax":-5.00762, "ay":4.06869, "alpha":0.0, "fx":[-85.17824,-85.17824,-85.17824,-85.17824], "fy":[69.20734,69.20734,69.20734,69.20734]}, - {"t":1.18076, "x":2.86836, "y":4.17189, "heading":-1.5708, "vx":0.4928, "vy":-0.4004, "omega":0.0, "ax":-5.00809, "ay":4.06907, "alpha":0.0, "fx":[-85.18611,-85.18611,-85.18611,-85.18611], "fy":[69.21373,69.21373,69.21373,69.21373]}, - {"t":1.22996, "x":2.88654, "y":4.15712, "heading":-1.5708, "vx":0.24641, "vy":-0.20021, "omega":0.0, "ax":-5.00847, "ay":4.06938, "alpha":0.0, "fx":[-85.19267,-85.19267,-85.19267,-85.19267], "fy":[69.21905,69.21905,69.21905,69.21905]}, - {"t":1.27916, "x":2.8926, "y":4.1522, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 0b2ef474..4b343dc0 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -5,7 +5,7 @@ public final class Constants { public static final boolean TUNING_MODE = true; public static final double LOOP_PERIOD_SECONDS = 0.02; - public static final RobotType ROBOT = RobotType.V3_EPSILON_SIM; + public static final RobotType ROBOT = RobotType.V3_EPSILON; public static Mode getMode() { switch (ROBOT) { diff --git a/src/main/java/frc/robot/FieldConstants.java b/src/main/java/frc/robot/FieldConstants.java index 9b6fa82a..6c93cf90 100644 --- a/src/main/java/frc/robot/FieldConstants.java +++ b/src/main/java/frc/robot/FieldConstants.java @@ -150,6 +150,11 @@ public Pose2d getAlgaeSetpoint() { DriveConstants.DRIVE_CONFIG.bumperWidth() / 2.0 + Units.inchesToMeters(2); // Offset X setpoint by center of robot to bumper + // if (Constants.ROBOT.equals(Constants.RobotType.V3_EPSILON) + // || Constants.ROBOT.equals(Constants.RobotType.V3_EPSILON_SIM)) { + // adjustXAlgae += Units.inchesToMeters(5); + // } + reefMap.put( 18, new FaceSetpoints( diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index 848ddef1..91717e0e 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -1994,6 +1994,7 @@ public static final LoggedAutoRoutine autoERightBack( CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + Commands.waitUntil(superstructure::armBelowThreshold), Commands.parallel( path2.cmd(), superstructure @@ -2003,6 +2004,7 @@ public static final LoggedAutoRoutine autoERightBack( CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L2, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_SCORE), + Commands.waitUntil(superstructure::atGoal), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), path3.cmd(), @@ -2013,6 +2015,7 @@ public static final LoggedAutoRoutine autoERightBack( CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L2, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_SCORE), + Commands.waitUntil(superstructure::atGoal), Commands.parallel( path4.cmd(), superstructure diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index a6087e44..f2ccf65d 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -32,6 +32,7 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; import frc.robot.util.AllianceFlipUtil; +import java.util.Set; import java.util.function.BooleanSupplier; import java.util.function.Supplier; @@ -669,17 +670,21 @@ public static final Command intakeCoralDriverSequence( superstructure.runGoalUntil( V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoralLoose()), superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.HANDOFF_SPIN, () -> intake.hasCoralLocked())); + V3_EpsilonSuperstructureStates.HANDOFF_SPIN, () -> intake.hasCoralLocked()), + postIntakeCoralSequence(superstructure, intake, manipulator)); } public static final Command postIntakeCoralSequence( V3_EpsilonSuperstructure superstructure, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { - return Commands.sequence( - superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.HANDOFF_SPIN, () -> manipulator.hasCoral()), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)); + return Commands.either( + Commands.sequence( + superstructure.runGoalUntil( + V3_EpsilonSuperstructureStates.HANDOFF_SPIN, () -> manipulator.hasCoral()), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L1), + () -> !RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); } /** @@ -693,21 +698,24 @@ public static final Command postIntakeCoralSequence( */ public static final Command optimalAutoScoreCoralSequence( Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { - return Commands.sequence( - // Commands.runOnce( - // () -> { - // if (RobotState.getOIData().currentReefHeight().equals(ReefState.L1)) { - // RobotState.setScoreSide(ScoreSide.CENTER); - // } else { - // RobotState.setScoreSide( - // optimalSideReef(RobotState.getReefAlignData().coralSetpoint())); - // } - // }) - // .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), - superstructure.setPosition(), - DriveCommands.autoAlignReefCoral(drive, cameras) - .until(() -> RobotState.getReefAlignData().atCoralSetpoint()), - superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight())); + return Commands.either( + Commands.sequence( + // Commands.runOnce( + // () -> { + // if (RobotState.getOIData().currentReefHeight().equals(ReefState.L1)) { + // RobotState.setScoreSide(ScoreSide.CENTER); + // } else { + // RobotState.setScoreSide( + // optimalSideReef(RobotState.getReefAlignData().coralSetpoint())); + // } + // }) + // .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), + superstructure.setPosition(), + DriveCommands.autoAlignReefCoral(drive, cameras) + .until(() -> RobotState.getReefAlignData().atCoralSetpoint()), + superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight())), + superstructure.runGoalUntil(V3_EpsilonSuperstructureStates.L1_SCORE, () -> false), + () -> !RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); } public static final Command optimalAutoScoreCoralSequence( @@ -825,11 +833,8 @@ public static final Command dropAlgae( Supplier level, Camera... cameras) { return Commands.sequence( - DriveCommands.autoAlignReefAlgae(drive, cameras), - Commands.waitSeconds(2), - Commands.sequence( - superstructure - .runGoal( + Commands.parallel( + superstructure.runGoalUntil( () -> { switch (level.get()) { case ALGAE_INTAKE_TOP: @@ -839,27 +844,38 @@ public static final Command dropAlgae( default: return V3_EpsilonSuperstructureStates.STOW_DOWN; } - }) - .until(() -> RobotState.isHasAlgae()), - Commands.waitSeconds(2.0), + }, + () -> RobotState.isHasAlgae()), + DriveCommands.autoAlignReefAlgae(drive, cameras)), Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), - () -> drive.stop()) - .withTimeout(0.5)), - superstructure.runGoal( + () -> drive.runVelocity(new ChassisSpeeds(0.0, 2.0, 0.0)), () -> drive.stop()) + .withTimeout(0.5), + superstructure.runActionWithTimeout( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE_DROP; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + default: + return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + } + }, + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE_DROP; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + default: + return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + } + }, + () -> 2)) + .finallyDo( () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE_DROP; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }), - Commands.waitSeconds(1.0), - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN)); + RobotState.setHasAlgae(false); + }); } public static final Command intakeAlgaeFromReef( @@ -869,9 +885,8 @@ public static final Command intakeAlgaeFromReef( Camera... cameras) { return Commands.sequence( - optimalAutoAlignReefAlgae(drive, superstructure, cameras), - superstructure - .runGoalUntil( + Commands.parallel( + superstructure.runGoalUntil( () -> { switch (level.get()) { case ALGAE_INTAKE_TOP: @@ -882,27 +897,11 @@ public static final Command intakeAlgaeFromReef( return V3_EpsilonSuperstructureStates.STOW_DOWN; } }, - () -> RobotState.isHasAlgae()) - .withTimeout(3), - Commands.parallel( - Commands.sequence( - Commands.waitSeconds(0.25), - Commands.either( - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), - superstructure.runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE; - default: - return V3_EpsilonSuperstructureStates.L2_ALGAE; - } - }), - () -> RobotState.isHasAlgae())), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, -1.0, 0.0)), - () -> drive.stop()) - .withTimeout(0.5))); + () -> RobotState.isHasAlgae()), + DriveCommands.autoAlignReefAlgae(drive, cameras)), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, 2.0, 0.0)), () -> drive.stop()) + .withTimeout(0.5)); } public static final Command intakeAlgaeFromReef( @@ -964,8 +963,17 @@ public static final Command manipulatorGroundIntake( public static final Command setDynamicReefHeight( ReefState height, V3_EpsilonSuperstructure superstructure) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setReefHeight(height)), superstructure.setPosition()); + return Commands.either( + Commands.sequence( + Commands.runOnce(() -> RobotState.setReefHeight(height)), + superstructure.setPosition()), + Commands.none(), + () -> + Set.of( + V3_EpsilonSuperstructureStates.L2, + V3_EpsilonSuperstructureStates.L3, + V3_EpsilonSuperstructureStates.L4) + .contains(superstructure.getCurrentState())); } } } diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index 331b40e7..6850807a 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -316,7 +316,7 @@ public static enum ElevatorPositions { new PositionConstants( 0.79 - Units.inchesToMeters(8), 0.79 - Units.inchesToMeters(8), - Units.inchesToMeters(25))), + Units.inchesToMeters(24))), ASS_TOP(new PositionConstants(1.2, 0.0, 0.0)), ASS_BOT(new PositionConstants(0.82, 0.0, 0.0)), L1( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonMechanism3d.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonMechanism3d.java index adde42b5..2705c29f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonMechanism3d.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonMechanism3d.java @@ -46,8 +46,7 @@ public static final Pose3d[] getPoses( new Transform3d(0, 0, stage1Height - ELEVATOR_STAGE_1_MIN_HEIGHT, new Rotation3d())); Pose3d ELEVATOR_CARRIAGE_POSE = ELEVATOR_CARRIAGE_MANIPULATOR.transformBy( - new Transform3d( - 0, 0, carriageHeight - ELEVATOR_CARRIAGE_MANIPULATOR_MIN_HEIGHT, new Rotation3d())); + new Transform3d(0, 0, carriageHeight, new Rotation3d())); Logger.recordOutput( "Zero Poses", @@ -62,10 +61,7 @@ public static final Pose3d[] getPoses( new Pose3d(-0.15381615, 0, 0.270855, new Rotation3d()) .transformBy( new Transform3d( - 0, - 0, - carriageHeight - ELEVATOR_CARRIAGE_MANIPULATOR_MIN_HEIGHT, - new Rotation3d(armAngle.getRadians(), 0.0, 0.0))), + 0, 0, carriageHeight, new Rotation3d(armAngle.getRadians(), 0.0, 0.0))), }; } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 4d2995eb..6a352e74 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -14,6 +14,7 @@ import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotContainer; import frc.robot.RobotState; +import frc.robot.commands.AutonomousCommands; import frc.robot.commands.CompositeCommands.SharedCommands; import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; import frc.robot.commands.DriveCommands; @@ -174,7 +175,7 @@ private void configureButtonBindings() { () -> -driver.getLeftX(), () -> -driver.getRightX(), () -> false, - operator.back(), + () -> false, driver.povRight())); driver.povDown().onTrue(SharedCommands.resetHeading(drive)); @@ -245,10 +246,10 @@ private void configureButtonBindings() { superstructure, () -> RobotState.getReefAlignData().algaeIntakeHeight())); - operator.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); - operator.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); - operator.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); - operator.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); + operator.y().onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); + operator.x().onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); + operator.b().onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); + operator.a().onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); operator .y() @@ -316,6 +317,18 @@ private void configureAutos() { "Drive FF Characterization", () -> DriveCommands.feedforwardCharacterization(drive)); autoChooser.addCmd( "Wheel Radius Characterization", () -> DriveCommands.wheelRadiusCharacterization(drive)); + autoChooser.addRoutine( + "4 Piece Right Early Madtown", + () -> AutonomousCommands.autoERight(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "4 Piece Right Late Madtown", + () -> AutonomousCommands.autoERightBack(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "4 Piece Left Early Madtown", + () -> AutonomousCommands.autoELeft(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "4 Piece Left Late Madtown", + () -> AutonomousCommands.autoELeftBack(drive, superstructure, intake, manipulator)); SmartDashboard.putData("Autonomous Modes", autoChooser); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 024ae4d7..eb86a89c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -46,7 +46,7 @@ public enum V3_EpsilonSuperstructureStates { L1( "L1", new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), - new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.CORAL_INTAKE)), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.STOP)), L1_SCORE( "L1_SCORE", new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), @@ -98,7 +98,7 @@ public enum V3_EpsilonSuperstructureStates { "L2_ALGAE_DROP", new SubsystemPoses( ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.REMOVE_ALGAE, IntakeRollerState.STOP)), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), L2_ALGAE_INTAKE( "L2_ALGAE_INTAKE", new SubsystemPoses( @@ -114,7 +114,7 @@ public enum V3_EpsilonSuperstructureStates { "L3_ALGAE_DROP", new SubsystemPoses( ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.REMOVE_ALGAE, IntakeRollerState.STOP)), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), L3_ALGAE_INTAKE( "L3_ALGAE_INTAKE", new SubsystemPoses( @@ -143,7 +143,7 @@ public enum V3_EpsilonSuperstructureStates { BARGE_SCORE( "BARGE_SCORE", new SubsystemPoses( - ReefState.ALGAE_SCORE, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), + ReefState.ALGAE_SCORE, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), FLIP_DOWN( "FLIP_DOWN", diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java index 77a11449..0538ad00 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java @@ -54,7 +54,10 @@ public void periodic() { io.setPivotGoal(pivotGoal.getAngle()); } - if (hasCoralLocked() && !rollerGoal.equals(IntakeRollerState.OUTTAKE)) { + if (rollerGoal.equals(IntakeRollerState.SCORE_CORAL)) { + io.setInnerRollerVoltage(IntakeRollerState.SCORE_CORAL.getInnerVoltage()); + io.setOuterRollerVoltage(IntakeRollerState.SCORE_CORAL.getOuterVoltage()); + } else if (hasCoralLocked() && (!rollerGoal.equals(IntakeRollerState.OUTTAKE))) { io.setInnerRollerVoltage(IntakeRollerState.STOP.getInnerVoltage()); io.setOuterRollerVoltage(IntakeRollerState.STOP.getOuterVoltage()); } else { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java index 7bc8df7d..894ac580 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java @@ -154,7 +154,7 @@ public static enum IntakeRollerState { CENTERING(-12.0, -12.0), CORAL_INTAKE(-12.0, -12.0), ALGAE_INTAKE(12.0, 12.0), - SCORE_CORAL(6.0, 6.0), + SCORE_CORAL(0.0, 6.0), OUTTAKE(0.0, 12.0); @Getter private final double innerVoltage; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 341df33a..b26bd643 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -10,6 +10,7 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import frc.robot.FieldConstants.Reef.ReefState; +import frc.robot.RobotState; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; @@ -73,9 +74,16 @@ public void periodic() { io.setArmGoal(goal); } - if (hasAlgae() - && Set.of(ManipulatorRollerState.CORAL_INTAKE, ManipulatorRollerState.STOP) - .contains(rollerGoal)) { + if (rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { + io.setRollerVoltage(ManipulatorRollerState.SCORE_ALGAE.getVoltage()); + } else if (hasAlgae() + && Set.of( + ManipulatorRollerState.CORAL_INTAKE, + ManipulatorRollerState.STOP, + ManipulatorRollerState.ALGAE_INTAKE) + .contains(rollerGoal) + && !rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { + RobotState.setHasAlgae(true); io.setRollerVoltage(holdVoltage()); } else if (hasCoral()) { io.setRollerVoltage(holdVoltage()); @@ -105,7 +113,8 @@ public boolean hasCoral() { */ @AutoLogOutput(key = "Manipulator/Has Algae") public boolean hasAlgae() { - return inputs.canRangeGot; + boolean hasAlgae = rollerGoal.equals(ManipulatorRollerState.ALGAE_INTAKE) && inputs.canRangeGot; + return hasAlgae; } /** @@ -234,7 +243,7 @@ public Command waitUntilArmAtGoal() { * uses another set of coefficients. */ private double holdVoltage() { - return -1; + return hasAlgae() ? -12.0 : -1; } /** diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 38a76f11..74cb7b64 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -204,11 +204,11 @@ public static record ArmParameters( @RequiredArgsConstructor public static enum ManipulatorArmState { PRE_SCORE(Rotation2d.fromDegrees(50.0)), - SCORE(Rotation2d.fromDegrees(70.0)), // Placeholder value. Make sure to test + SCORE(Rotation2d.fromDegrees(90.0)), // Placeholder value. Make sure to test SCORE_L4(Rotation2d.kPi), PROCESSOR(Rotation2d.fromDegrees(90)), ALGAE_INTAKE_FLOOR(Rotation2d.fromDegrees(90)), - REEF_INTAKE(Rotation2d.fromDegrees(46.279296875)), + REEF_INTAKE(Rotation2d.fromDegrees(90)), INTAKE_OUT_LINE(Rotation2d.fromDegrees(61)), FLOOR_INTAKE(Rotation2d.fromDegrees(73.5)), STOW_LINE(Rotation2d.fromDegrees(75)), // What is STOW_LINE? @@ -239,9 +239,10 @@ public static enum ManipulatorRollerState { ALGAE_INTAKE(-12.0), L4_SCORE(4.6 * 1.56), SCORE_CORAL(4.8 * 1.56), - SCORE_ALGAE(6), + SCORE_ALGAE(12), REMOVE_ALGAE(-12), - L1_SCORE(3.5 * 1.56); + L1_SCORE(3.5 * 1.56), + ALGAE_HOLD(-12); private final double voltage; From fb38ab41656ab4dc4247e71a3e2cde1a7c81ab65 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Thu, 23 Oct 2025 17:28:55 -0400 Subject: [PATCH 142/180] Enhance superstructure states and manipulator constants for improved coral intake and scoring functionality --- src/main/deploy/Superstructure.dot | 9 ++ src/main/deploy/choreo/F_PATH_1.traj | 52 ++++++++ src/main/deploy/choreo/F_PATH_2.traj | 47 ++++++++ src/main/deploy/choreo/F_PATH_3.traj | 75 ++++++++++++ src/main/deploy/choreo/F_PATH_4.traj | 73 ++++++++++++ src/main/deploy/choreo/F_PATH_5.traj | 76 ++++++++++++ src/main/deploy/choreo/F_PATH_6.traj | 85 ++++++++++++++ src/main/deploy/choreo/F_PATH_7.traj | 79 +++++++++++++ src/main/deploy/choreo/F_PATH_8.traj | 70 +++++++++++ .../robot/commands/AutonomousCommands.java | 111 ++++++++++++++---- .../frc/robot/commands/CompositeCommands.java | 12 +- .../shared/elevator/ElevatorConstants.java | 2 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 12 +- .../v3_Epsilon/climber/V3_EpsilonClimber.java | 5 + .../V3_EpsilonSuperstructureStates.java | 18 +++ .../V3_EpsilonManipulatorConstants.java | 6 +- 16 files changed, 702 insertions(+), 30 deletions(-) create mode 100644 src/main/deploy/choreo/F_PATH_1.traj create mode 100644 src/main/deploy/choreo/F_PATH_2.traj create mode 100644 src/main/deploy/choreo/F_PATH_3.traj create mode 100644 src/main/deploy/choreo/F_PATH_4.traj create mode 100644 src/main/deploy/choreo/F_PATH_5.traj create mode 100644 src/main/deploy/choreo/F_PATH_6.traj create mode 100644 src/main/deploy/choreo/F_PATH_7.traj create mode 100644 src/main/deploy/choreo/F_PATH_8.traj diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/Superstructure.dot index 5588a243..3e83e71a 100644 --- a/src/main/deploy/Superstructure.dot +++ b/src/main/deploy/Superstructure.dot @@ -222,4 +222,13 @@ digraph Superstructure { HANDOFF_SPIN -> HANDOFF HANDOFF -> HANDOFF_SPIN + + INVERSE_FLIP_DOWN -> GROUND_INTAKE_CORAL + GROUND_INTAKE_CORAL -> INVERSE_FLIP_UP + + L4_SCORE -> INVERSE_FLIP_DOWN + L2_SCORE -> INVERSE_FLIP_DOWN + + INVERSE_FLIP_UP -> L2 + INVERSE_FLIP_UP -> L4 } \ No newline at end of file diff --git a/src/main/deploy/choreo/F_PATH_1.traj b/src/main/deploy/choreo/F_PATH_1.traj new file mode 100644 index 00000000..f91dc86d --- /dev/null +++ b/src/main/deploy/choreo/F_PATH_1.traj @@ -0,0 +1,52 @@ +{ + "name":"F_PATH_1", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.152472496032715, "y":4.007034778594971, "heading":1.5707963267948966, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":6.099902153015137, "y":4.149273872375488, "heading":1.5656151542552748, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"7.152472496032715 m", "val":7.152472496032715}, "y":{"exp":"4.007034778594971 m", "val":4.007034778594971}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"6.099902153015137 m", "val":6.099902153015137}, "y":{"exp":"4.149273872375488 m", "val":4.149273872375488}, "heading":{"exp":"1.5656151542552748 rad", "val":1.5656151542552748}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.8131], + "samples":[ + {"t":0.0, "x":7.15247, "y":4.00703, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.39488, "ay":0.86417, "alpha":-0.03147, "fx":[-108.75032,-108.75658,-108.79974,-108.79373], "fy":[14.88148,14.83775,14.51762,14.56044]}, + {"t":0.04783, "x":7.14516, "y":4.00802, "heading":1.5708, "vx":-0.30586, "vy":0.04133, "omega":-0.00151, "ax":-6.39407, "ay":0.86406, "alpha":-0.03146, "fx":[-108.73656,-108.74287,-108.78601,-108.77996], "fy":[14.87958,14.83586,14.5158,14.55861]}, + {"t":0.09566, "x":7.12322, "y":4.01099, "heading":1.57072, "vx":-0.61168, "vy":0.08266, "omega":-0.00301, "ax":-6.393, "ay":0.86392, "alpha":-0.03146, "fx":[-108.71822,-108.72457,-108.7677,-108.7616], "fy":[14.87704,14.83336,14.51339,14.55616]}, + {"t":0.14349, "x":7.08665, "y":4.01593, "heading":1.57058, "vx":-0.91746, "vy":0.12398, "omega":-0.00451, "ax":-6.39149, "ay":0.86371, "alpha":-0.03146, "fx":[-108.69255,-108.69896,-108.74206,-108.7359], "fy":[14.87349,14.82988,14.51001,14.55271]}, + {"t":0.19132, "x":7.03545, "y":4.02285, "heading":1.57036, "vx":-1.22315, "vy":0.16529, "omega":-0.00602, "ax":-6.38923, "ay":0.86341, "alpha":-0.03145, "fx":[-108.65404,-108.66056,-108.70363,-108.69736], "fy":[14.86816,14.82466,14.50494,14.54754]}, + {"t":0.23915, "x":6.96964, "y":4.03174, "heading":1.57008, "vx":-1.52875, "vy":0.20659, "omega":-0.00752, "ax":-6.38546, "ay":0.8629, "alpha":-0.03144, "fx":[-108.5899,-108.59659,-108.63959,-108.63315], "fy":[14.8593,14.81595,14.49648,14.53892]}, + {"t":0.28697, "x":6.88922, "y":4.04261, "heading":1.56972, "vx":-1.83416, "vy":0.24786, "omega":-0.00903, "ax":-6.37793, "ay":0.86188, "alpha":-0.03143, "fx":[-108.4617,-108.46875,-108.51164,-108.50485], "fy":[14.84165,14.79853,14.47951,14.52172]}, + {"t":0.3348, "x":6.7942, "y":4.05545, "heading":1.56928, "vx":-2.13921, "vy":0.28908, "omega":-0.01053, "ax":-6.35539, "ay":0.85884, "alpha":-0.03142, "fx":[-108.078,-108.08612,-108.1287,-108.12082], "fy":[14.78901,14.74635,14.42855,14.47031]}, + {"t":0.38263, "x":6.68461, "y":4.07026, "heading":1.56878, "vx":-2.44318, "vy":0.33016, "omega":-0.01203, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.43046, "x":6.56776, "y":4.08605, "heading":1.56821, "vx":-2.44318, "vy":0.33016, "omega":-0.01203, "ax":6.35539, "ay":-0.85884, "alpha":0.03142, "fx":[108.07802,108.08609,108.12868,108.12085], "fy":[-14.78886,-14.74655,-14.4287,-14.47011]}, + {"t":0.47829, "x":6.45817, "y":4.10086, "heading":1.56763, "vx":-2.13921, "vy":0.28908, "omega":-0.01053, "ax":6.37793, "ay":-0.86188, "alpha":0.03143, "fx":[108.46174,108.46869,108.5116,108.5049], "fy":[-14.84136,-14.79891,-14.4798,-14.52135]}, + {"t":0.52612, "x":6.36315, "y":4.1137, "heading":1.56713, "vx":-1.83416, "vy":0.24786, "omega":-0.00903, "ax":6.38546, "ay":-0.8629, "alpha":0.03144, "fx":[108.58995,108.59651,108.63954,108.63322], "fy":[-14.85889,-14.81648,-14.49689,-14.53839]}, + {"t":0.57395, "x":6.28273, "y":4.12457, "heading":1.56669, "vx":-1.52875, "vy":0.20659, "omega":-0.00752, "ax":6.38923, "ay":-0.86341, "alpha":0.03145, "fx":[108.65411,108.66047,108.70356,108.69745], "fy":[-14.86765,-14.82532,-14.50545,-14.54687]}, + {"t":0.62178, "x":6.21692, "y":4.13346, "heading":1.56633, "vx":-1.22315, "vy":0.16529, "omega":-0.00602, "ax":6.39149, "ay":-0.86371, "alpha":0.03146, "fx":[108.69262,108.69886,108.74199,108.736], "fy":[-14.8729,-14.83065,-14.5106,-14.55194]}, + {"t":0.66961, "x":6.16573, "y":4.14038, "heading":1.56605, "vx":-0.91746, "vy":0.12398, "omega":-0.00451, "ax":6.393, "ay":-0.86392, "alpha":0.03146, "fx":[108.71831,108.72446,108.76761,108.76171], "fy":[-14.87639,-14.83421,-14.51404,-14.55531]}, + {"t":0.71744, "x":6.12916, "y":4.14532, "heading":1.56583, "vx":-0.61168, "vy":0.08266, "omega":-0.00301, "ax":6.39407, "ay":-0.86406, "alpha":0.03146, "fx":[108.73665,108.74274,108.78592,108.78008], "fy":[-14.87889,-14.83676,-14.51649,-14.55771]}, + {"t":0.76527, "x":6.10722, "y":4.14829, "heading":1.56569, "vx":-0.30586, "vy":0.04133, "omega":-0.00151, "ax":6.39488, "ay":-0.86417, "alpha":0.03147, "fx":[108.75042,108.75646,108.79965,108.79385], "fy":[-14.88077,-14.83867,-14.51833,-14.55951]}, + {"t":0.8131, "x":6.0999, "y":4.14927, "heading":1.56562, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/F_PATH_2.traj b/src/main/deploy/choreo/F_PATH_2.traj new file mode 100644 index 00000000..e4a800d6 --- /dev/null +++ b/src/main/deploy/choreo/F_PATH_2.traj @@ -0,0 +1,47 @@ +{ + "name":"F_PATH_2", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":6.099902153015137, "y":4.149273872375488, "heading":1.5656151542552748, "intervals":12, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":6.555067539215088, "y":3.969104051589966, "heading":1.5707963267948966, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"6.099902153015137 m", "val":6.099902153015137}, "y":{"exp":"4.149273872375488 m", "val":4.149273872375488}, "heading":{"exp":"1.5656151542552748 rad", "val":1.5656151542552748}, "intervals":12, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"6.555067539215088 m", "val":6.555067539215088}, "y":{"exp":"3.969104051589966 m", "val":3.969104051589966}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,0.55109], + "samples":[ + {"t":0.0, "x":6.0999, "y":4.14927, "heading":1.56562, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.99964, "ay":-2.37486, "alpha":0.06825, "fx":[101.88256,101.97912,102.22032,102.12643], "fy":[-40.82242,-40.58229,-39.97019,-40.20777]}, + {"t":0.04592, "x":6.10623, "y":4.14677, "heading":1.56562, "vx":0.27553, "vy":-0.10906, "omega":0.00313, "ax":5.99837, "ay":-2.37436, "alpha":0.06824, "fx":[101.86105,101.95771,102.1988,102.1048], "fy":[-40.81378,-40.57376,-39.96179,-40.19926]}, + {"t":0.09185, "x":6.12521, "y":4.13926, "heading":1.56576, "vx":0.551, "vy":-0.2181, "omega":0.00627, "ax":5.99638, "ay":-2.37357, "alpha":0.06824, "fx":[101.82724,101.9241,102.16501,102.07081], "fy":[-40.80025,-40.56031,-39.94857,-40.18596]}, + {"t":0.13777, "x":6.15684, "y":4.12674, "heading":1.56605, "vx":0.82638, "vy":-0.32711, "omega":0.0094, "ax":5.99281, "ay":-2.37216, "alpha":0.06824, "fx":[101.7664,101.86364,102.10422,102.00964], "fy":[-40.77591,-40.53609,-39.92477,-40.16203]}, + {"t":0.1837, "x":6.20111, "y":4.10921, "heading":1.56648, "vx":1.10159, "vy":-0.43605, "omega":0.01254, "ax":5.98448, "ay":-2.36886, "alpha":0.06823, "fx":[101.6246,101.72265,101.96251,101.86711], "fy":[-40.71915,-40.47976,-39.8693,-40.10614]}, + {"t":0.22962, "x":6.25801, "y":4.08669, "heading":1.56705, "vx":1.37643, "vy":-0.54484, "omega":0.01567, "ax":5.94298, "ay":-2.35243, "alpha":0.06822, "fx":[100.91864,101.02034,101.25682,101.15771], "fy":[-40.43635,-40.19998,-39.59329,-39.82715]}, + {"t":0.27555, "x":6.32748, "y":4.05919, "heading":1.56777, "vx":1.64935, "vy":-0.65287, "omega":0.0188, "ax":-5.94298, "ay":2.35243, "alpha":-0.06822, "fx":[-100.91859,-101.02046,-101.25687,-101.15759], "fy":[40.43648,40.19967,39.59315,39.82746]}, + {"t":0.32147, "x":6.39696, "y":4.03169, "heading":1.56864, "vx":1.37643, "vy":-0.54484, "omega":0.01567, "ax":-5.98448, "ay":2.36886, "alpha":-0.06823, "fx":[-101.62445,-101.72301,-101.96267,-101.86675], "fy":[40.71955,40.47885,39.86889,40.10707]}, + {"t":0.36739, "x":6.45386, "y":4.00916, "heading":1.56936, "vx":1.10159, "vy":-0.43605, "omega":0.01254, "ax":-5.99281, "ay":2.37216, "alpha":-0.06824, "fx":[-101.76616,-101.8642,-102.10446,-102.00909], "fy":[40.77652,40.53469,39.92414,40.16345]}, + {"t":0.41332, "x":6.49813, "y":3.99164, "heading":1.56993, "vx":0.82638, "vy":-0.32711, "omega":0.0094, "ax":-5.99638, "ay":2.37357, "alpha":-0.06824, "fx":[-101.82693,-101.92481,-102.16531,-102.0701], "fy":[40.80102,40.55854,39.94779,40.18775]}, + {"t":0.45924, "x":6.52976, "y":3.97912, "heading":1.57036, "vx":0.551, "vy":-0.2181, "omega":0.00627, "ax":-5.99837, "ay":2.37436, "alpha":-0.06824, "fx":[-101.8607,-101.95851,-102.19915,-102.104], "fy":[40.81466,40.57175,39.9609,40.2013]}, + {"t":0.50517, "x":6.54874, "y":3.97161, "heading":1.57065, "vx":0.27553, "vy":-0.10906, "omega":0.00313, "ax":-5.99964, "ay":2.37486, "alpha":-0.06825, "fx":[-101.88219,-101.97997,-102.22069,-102.12558], "fy":[40.82335,40.58015,39.96924,40.20992]}, + {"t":0.55109, "x":6.55507, "y":3.9691, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/F_PATH_3.traj b/src/main/deploy/choreo/F_PATH_3.traj new file mode 100644 index 00000000..254c24e9 --- /dev/null +++ b/src/main/deploy/choreo/F_PATH_3.traj @@ -0,0 +1,75 @@ +{ + "name":"F_PATH_3", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":5.948180198669434, "y":4.026000022888184, "heading":1.5656151542552748, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":7.664534091949463, "y":4.822539806365967, "heading":-1.5707963267948966, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"5.948180198669434 m", "val":5.948180198669434}, "y":{"exp":"4.026000022888184 m", "val":4.026000022888184}, "heading":{"exp":"1.5656151542552748 rad", "val":1.5656151542552748}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"7.664534091949463 m", "val":7.664534091949463}, "y":{"exp":"4.822539806365967 m", "val":4.822539806365967}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.17407], + "samples":[ + {"t":0.0, "x":5.94818, "y":4.026, "heading":1.56562, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.04993, "ay":2.20393, "alpha":-11.50228, "fx":[89.29942,36.1142,108.50929,109.66883], "fy":[63.81818,103.58191,-13.61321,-3.83416]}, + {"t":0.02935, "x":5.95036, "y":4.02695, "heading":1.56562, "vx":0.14822, "vy":0.06469, "omega":-0.33761, "ax":5.05391, "ay":2.21116, "alpha":-11.45481, "fx":[89.31821,36.33746,108.54205,109.66433], "fy":[63.78033,103.49236,-13.10256,-3.72518]}, + {"t":0.0587, "x":5.95688, "y":4.0298, "heading":1.55571, "vx":0.29657, "vy":0.12959, "omega":-0.67383, "ax":5.07214, "ay":2.23435, "alpha":-11.25022, "fx":[89.61741,37.06634,108.77103,109.64765], "fy":[63.34587,103.22152,-10.62989,-3.91491]}, + {"t":0.08806, "x":5.96777, "y":4.03457, "heading":1.53593, "vx":0.44544, "vy":0.19517, "omega":-1.00404, "ax":5.10279, "ay":2.27662, "alpha":-10.8889, "fx":[90.18776,38.31069,109.07161,109.61803], "fy":[62.51543,102.75333,-5.99808,-4.37219]}, + {"t":0.11741, "x":5.98305, "y":4.04128, "heading":1.50646, "vx":0.59522, "vy":0.262, "omega":-1.32365, "ax":5.14148, "ay":2.34254, "alpha":-10.38245, "fx":[91.00849,40.07153,109.16646,109.5739], "fy":[61.29558,102.06547,1.06727,-5.04476]}, + {"t":0.14676, "x":6.00273, "y":4.04998, "heading":1.46761, "vx":0.74613, "vy":0.33075, "omega":-1.62839, "ax":5.18042, "ay":2.43554, "alpha":-9.76857, "fx":[92.04762,42.3396,108.56799,109.51456], "fy":[59.70055,101.12978,10.73699,-5.85598]}, + {"t":0.17611, "x":6.02686, "y":4.06073, "heading":1.41981, "vx":0.89818, "vy":0.40224, "omega":-1.91512, "ax":5.20911, "ay":2.55327, "alpha":-9.12487, "fx":[93.2631,45.09645,106.61982,109.44228], "fy":[57.75406,99.91227,22.75453,-6.69916]}, + {"t":0.20546, "x":6.05547, "y":4.07364, "heading":1.3636, "vx":1.05108, "vy":0.47718, "omega":-2.18295, "ax":5.21889, "ay":2.68281, "alpha":-8.56005, "fx":[94.60488,48.3208,102.79714,109.36469], "fy":[55.49091,98.37063,36.10031,-7.42644]}, + {"t":0.23481, "x":6.08857, "y":4.0888, "heading":1.29952, "vx":1.20426, "vy":0.55593, "omega":-2.4342, "ax":5.21094, "ay":2.80168, "alpha":-8.16095, "fx":[96.01712,52.00147,97.23116,109.29686], "fy":[52.95899,96.44657,49.04298,-7.82567]}, + {"t":0.26417, "x":6.12616, "y":4.10632, "heading":1.22808, "vx":1.35721, "vy":0.63816, "omega":-2.67374, "ax":5.2003, "ay":2.88816, "alpha":-7.92142, "fx":[97.43863,56.15552,90.96748,109.26115], "fy":[50.22497,94.04989,59.80611,-7.5742]}, + {"t":0.29352, "x":6.16824, "y":4.1263, "heading":1.1496, "vx":1.50985, "vy":0.72293, "omega":-2.90625, "ax":5.20999, "ay":2.933, "alpha":-7.71842, "fx":[98.79787,60.85087,85.5556,109.27726], "fy":[47.39224,91.02791,67.28541,-6.14768]}, + {"t":0.32287, "x":6.2148, "y":4.14878, "heading":1.06429, "vx":1.66277, "vy":0.80902, "omega":-3.1328, "ax":5.26094, "ay":2.94233, "alpha":-7.33941, "fx":[99.99573,66.2424,82.39621,109.31387], "fy":[44.64975,87.10061,71.08359,-2.64085]}, + {"t":0.35222, "x":6.26587, "y":4.1738, "heading":0.97234, "vx":1.81719, "vy":0.89539, "omega":-3.34822, "ax":5.36561, "ay":2.93377, "alpha":-6.49134, "fx":[100.85596,72.65649,82.4608,109.097], "fy":[42.40428,81.68935,70.94934,4.56748]}, + {"t":0.38157, "x":6.32152, "y":4.20134, "heading":0.87407, "vx":1.97468, "vy":0.9815, "omega":-3.53875, "ax":5.51965, "ay":2.93006, "alpha":-4.73915, "fx":[100.94565,80.83353,86.34847,107.42317], "fy":[41.70048,73.3376,66.05142,18.26855]}, + {"t":0.41092, "x":6.38186, "y":4.23141, "heading":0.7702, "vx":2.13669, "vy":1.0675, "omega":-3.67785, "ax":5.66759, "ay":2.92477, "alpha":-1.33707, "fx":[98.54544,92.62118,94.14191,100.30756], "fy":[46.08182,56.99487,54.15304,41.76815]}, + {"t":0.44028, "x":6.44701, "y":4.264, "heading":0.66225, "vx":2.30304, "vy":1.15335, "omega":-3.7171, "ax":5.44266, "ay":2.68523, "alpha":6.34576, "fx":[77.44198,107.48337,103.82829,81.55845], "fy":[74.10161,5.91686,31.34088,71.34037]}, + {"t":0.46963, "x":6.51696, "y":4.29901, "heading":0.55314, "vx":2.4628, "vy":1.23216, "omega":-3.53084, "ax":5.34374, "ay":1.78709, "alpha":9.92952, "fx":[70.50771,101.00645,107.44849,84.61961], "fy":[77.83103,-34.14337,11.07203,66.83203]}, + {"t":0.49898, "x":6.59155, "y":4.33595, "heading":0.44951, "vx":2.61964, "vy":1.28462, "omega":-3.23939, "ax":4.16153, "ay":1.35994, "alpha":17.20536, "fx":[19.35652,75.68844,107.08592,81.01482], "fy":[99.14027,-72.14782,-4.23759,69.77372]}, + {"t":0.52833, "x":6.67023, "y":4.37424, "heading":0.35442, "vx":2.74179, "vy":1.32453, "omega":-2.73438, "ax":4.25946, "ay":1.2705, "alpha":15.46784, "fx":[28.66001,75.09962,104.0836,81.96579], "fy":[90.97166,-62.91522,-5.67269,64.05986]}, + {"t":0.55768, "x":6.75254, "y":4.41367, "heading":0.27417, "vx":2.86681, "vy":1.36182, "omega":-2.28038, "ax":0.62332, "ay":-1.9921, "alpha":1.1002, "fx":[6.84392,8.29786,14.25882,13.00914], "fy":[-32.30251,-37.20861,-35.49527,-30.53353]}, + {"t":0.58703, "x":6.83695, "y":4.45278, "heading":0.20723, "vx":2.88511, "vy":1.30335, "omega":-2.24808, "ax":-4.61706, "ay":-2.16267, "alpha":-11.16979, "fx":[-38.01698,-91.91795,-103.19774,-81.007], "fy":[-91.97577,16.89943,-6.77506,-65.29444]}, + {"t":0.61639, "x":6.91965, "y":4.4901, "heading":0.14125, "vx":2.74959, "vy":1.23987, "omega":-2.57594, "ax":-4.93279, "ay":-2.06072, "alpha":-11.22969, "fx":[-43.79061,-98.98632,-106.53768,-86.30654], "fy":[-95.06755,20.06161,-2.09126,-63.11211]}, + {"t":0.64574, "x":6.99823, "y":4.52561, "heading":0.06564, "vx":2.60481, "vy":1.17939, "omega":-2.90555, "ax":-5.05136, "ay":-1.98798, "alpha":-11.16628, "fx":[-45.46054,-101.41342,-107.58571,-89.22932], "fy":[-96.32552,19.61618,2.13117,-60.68169]}, + {"t":0.67509, "x":7.07251, "y":4.55937, "heading":-0.01964, "vx":2.45654, "vy":1.12104, "omega":-3.2333, "ax":-5.08871, "ay":-1.90586, "alpha":-11.2563, "fx":[-44.6367,-102.26016,-107.87882,-91.45411], "fy":[-97.75806,19.02655,7.27379,-58.21498]}, + {"t":0.70444, "x":7.14242, "y":4.59145, "heading":-0.11455, "vx":2.30718, "vy":1.0651, "omega":-3.56369, "ax":-5.06354, "ay":-1.79668, "alpha":-11.55704, "fx":[-41.80883,-101.79263,-107.50949,-93.40645], "fy":[-99.63973,18.96819,14.05711,-55.6299]}, + {"t":0.73379, "x":7.20796, "y":4.62194, "heading":-0.21915, "vx":2.15855, "vy":1.01236, "omega":-3.90291, "ax":-4.96676, "ay":-1.68497, "alpha":-12.00667, "fx":[-37.80356,-98.63933,-106.16005,-95.32957], "fy":[-101.6634,16.76198,22.955,-52.69689]}, + {"t":0.76314, "x":7.26918, "y":4.65093, "heading":-0.3337, "vx":2.01277, "vy":0.96291, "omega":-4.25532, "ax":-5.32904, "ay":-2.77189, "alpha":-7.00057, "fx":[-62.89058,-93.75103,-108.68205,-97.25812], "fy":[-88.67425,-51.84941,1.13948,-49.21198]}, + {"t":0.7925, "x":7.32596, "y":4.678, "heading":-0.45861, "vx":1.85635, "vy":0.88155, "omega":-4.4608, "ax":-5.66204, "ay":-2.99498, "alpha":-0.15154, "fx":[-95.80011,-96.2211,-96.81632,-96.40122], "fy":[-51.90475,-51.0975,-49.9773,-50.79554]}, + {"t":0.82185, "x":7.37801, "y":4.70258, "heading":-0.58954, "vx":1.69016, "vy":0.79364, "omega":-4.46525, "ax":-5.55715, "ay":-2.98319, "alpha":3.91485, "fx":[-106.39109,-99.35352,-82.04074,-90.31664], "fy":[-24.34184,-45.58161,-72.12497,-60.92454]}, + {"t":0.8512, "x":7.42522, "y":4.72459, "heading":-0.7206, "vx":1.52705, "vy":0.70608, "omega":-4.35034, "ax":-5.3451, "ay":-2.95159, "alpha":6.73563, "fx":[-109.12399,-102.22143,-75.00505,-77.32434], "fy":[-5.21052,-39.15498,-79.65776,-76.79924]}, + {"t":0.88055, "x":7.46774, "y":4.74405, "heading":-0.84829, "vx":1.37016, "vy":0.61944, "omega":-4.15264, "ax":-5.09257, "ay":-2.88702, "alpha":9.28659, "fx":[-108.95268,-104.62864,-73.05374,-59.85765], "fy":[8.83166,-32.4571,-81.59475,-91.20901]}, + {"t":0.9099, "x":7.50576, "y":4.76098, "heading":-0.97018, "vx":1.22069, "vy":0.5347, "omega":-3.88006, "ax":-4.87905, "ay":-2.75056, "alpha":11.42185, "fx":[-107.56234,-106.52352,-73.69751,-44.18188], "fy":[19.65195,-25.78282,-81.107,-99.90725]}, + {"t":0.93925, "x":7.53949, "y":4.77549, "heading":-1.08406, "vx":1.07748, "vy":0.45397, "omega":-3.54481, "ax":-4.74217, "ay":-2.56655, "alpha":12.94613, "fx":[-105.64302,-107.91697,-75.54705,-33.54508], "fy":[28.25444,-19.33103,-79.4521,-104.09611]}, + {"t":0.96861, "x":7.56908, "y":4.78771, "heading":-1.18811, "vx":0.93829, "vy":0.37864, "omega":-3.16482, "ax":-4.66807, "ay":-2.36948, "alpha":13.94294, "fx":[-103.51501,-108.8572,-77.84913,-27.38856], "fy":[35.2587,-13.24674,-77.24575,-105.98269]}, + {"t":0.99796, "x":7.5946, "y":4.79781, "heading":-1.281, "vx":0.80127, "vy":0.30909, "omega":-2.75557, "ax":-4.63086, "ay":-2.17778, "alpha":14.58452, "fx":[-101.30961,-109.41417,-80.19441,-24.1599], "fy":[41.1365,-7.62765,-74.84497,-106.83763]}, + {"t":1.02731, "x":7.61613, "y":4.80594, "heading":-1.36188, "vx":0.66535, "vy":0.24517, "omega":-2.32749, "ax":-4.6096, "ay":-1.99766, "alpha":15.02359, "fx":[-99.01805,-109.666,-82.36303,-22.58483], "fy":[46.33149,-2.53421,-72.48106,-107.2347]}, + {"t":1.05666, "x":7.63367, "y":4.81228, "heading":-1.4302, "vx":0.53005, "vy":0.18653, "omega":-1.88652, "ax":-4.58905, "ay":-1.82878, "alpha":15.38106, "fx":[-96.49294,-109.69004,-84.23983,-21.81075], "fy":[51.32385,1.99726,-70.31508,-107.43426]}, + {"t":1.08601, "x":7.64725, "y":4.81696, "heading":-1.48557, "vx":0.39535, "vy":0.13285, "omega":-1.43506, "ax":-4.55686, "ay":-1.66734, "alpha":15.75722, "fx":[-93.42975,-109.55839,-85.76599,-21.28952], "fy":[56.64802,5.94228,-68.46544,-107.56866]}, + {"t":1.11537, "x":7.65689, "y":4.82014, "heading":-1.52769, "vx":0.2616, "vy":0.08392, "omega":-0.97256, "ax":-4.50135, "ay":-1.5085, "alpha":16.23941, "fx":[-89.35836,-109.3365,-86.9104,-20.66126], "fy":[62.8238,9.27769,-67.02391,-107.71416]}, + {"t":1.14472, "x":7.66263, "y":4.82196, "heading":-1.55624, "vx":0.12948, "vy":0.03964, "omega":-0.49591, "ax":-4.41128, "ay":-1.35045, "alpha":16.89534, "fx":[-83.72687,-109.08358,-87.65181,-19.67599], "fy":[70.12728,11.9724,-66.06614,-107.91649]}, + {"t":1.17407, "x":7.66453, "y":4.82254, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/F_PATH_4.traj b/src/main/deploy/choreo/F_PATH_4.traj new file mode 100644 index 00000000..d1366828 --- /dev/null +++ b/src/main/deploy/choreo/F_PATH_4.traj @@ -0,0 +1,73 @@ +{ + "name":"F_PATH_4", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.664534091949463, "y":4.822539806365967, "heading":-1.5707963267948966, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":5.63525390625, "y":5.723388195037842, "heading":2.627672932910526, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"7.664534091949463 m", "val":7.664534091949463}, "y":{"exp":"4.822539806365967 m", "val":4.822539806365967}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"5.63525390625 m", "val":5.63525390625}, "y":{"exp":"5.723388195037842 m", "val":5.723388195037842}, "heading":{"exp":"2.627672932910526 rad", "val":2.627672932910526}, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.21111], + "samples":[ + {"t":0.0, "x":7.66453, "y":4.82254, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.5471, "ay":2.33477, "alpha":-7.78924, "fx":[-109.66343,-109.18134,-64.49676,-94.07713], "fy":[4.14124,9.43922,88.73725,56.53705]}, + {"t":0.03187, "x":7.66172, "y":4.82373, "heading":-1.5708, "vx":-0.17679, "vy":0.07441, "omega":-0.24825, "ax":-5.55785, "ay":2.35044, "alpha":-7.63446, "fx":[-109.63036,-109.05684,-65.31819,-94.14457], "fy":[4.75017,10.63928,88.12112,56.4105]}, + {"t":0.06374, "x":7.65326, "y":4.82729, "heading":-1.57871, "vx":-0.35393, "vy":0.14932, "omega":-0.49157, "ax":-5.5671, "ay":2.36595, "alpha":-7.49743, "fx":[-109.57867,-108.97155,-66.15539,-94.07367], "fy":[5.64458,11.34134,87.47824,56.51226]}, + {"t":0.09561, "x":7.63915, "y":4.83325, "heading":-1.59438, "vx":-0.53136, "vy":0.22473, "omega":-0.73052, "ax":-5.57554, "ay":2.38202, "alpha":-7.36814, "fx":[-109.50103,-108.92371,-67.05283,-93.87583], "fy":[6.82509,11.65078,86.77264,56.82122]}, + {"t":0.12748, "x":7.61938, "y":4.84162, "heading":-1.61766, "vx":-0.70906, "vy":0.30065, "omega":-0.96536, "ax":-5.5839, "ay":2.39957, "alpha":-7.23442, "fx":[-109.38732,-108.90212,-68.06925,-93.56379], "fy":[8.29791,11.70119,85.95364,57.31118]}, + {"t":0.15936, "x":7.59395, "y":4.85242, "heading":-1.64843, "vx":-0.88702, "vy":0.37712, "omega":-1.19593, "ax":-5.5931, "ay":2.41961, "alpha":-7.08075, "fx":[-109.22402,-108.88969,-69.28023,-93.15394], "fy":[10.07512,11.65275,84.95108,57.94831]}, + {"t":0.19123, "x":7.56284, "y":4.86567, "heading":-1.68654, "vx":-1.06528, "vy":0.45424, "omega":-1.4216, "ax":-5.60429, "ay":2.44306, "alpha":-6.88694, "fx":[-108.99322,-108.86579,-70.78068,-92.66984], "fy":[12.17535,11.6924,83.66838,58.68716]}, + {"t":0.2231, "x":7.52604, "y":4.88139, "heading":-1.73185, "vx":-1.2439, "vy":0.5321, "omega":-1.64109, "ax":-5.619, "ay":2.47062, "alpha":-6.62675, "fx":[-108.67114,-108.80574,-72.68545,-92.14766], "fy":[14.62534,12.03603,81.97304,59.46396]}, + {"t":0.25497, "x":7.48354, "y":4.8996, "heading":-1.78415, "vx":-1.42298, "vy":0.61085, "omega":-1.8523, "ax":-5.639, "ay":2.50252, "alpha":-6.26674, "fx":[-108.22538,-108.67564,-75.12509,-91.64527], "fy":[17.4635,12.93515,79.68464,60.18501]}, + {"t":0.28684, "x":7.43533, "y":4.92034, "heading":-1.84319, "vx":-1.60271, "vy":0.6906, "omega":-2.05203, "ax":-5.66613, "ay":2.53837, "alpha":-5.76523, "fx":[-107.60983,-108.41878,-78.23039,-91.25786], "fy":[20.74812,14.69247,76.56275,60.70476]}, + {"t":0.31871, "x":7.38137, "y":4.94364, "heading":-1.90859, "vx":-1.78329, "vy":0.7715, "omega":-2.23577, "ax":-5.70149, "ay":2.57729, "alpha":-5.07085, "fx":[-106.75327,-107.92628,-82.09645,-91.14709], "fy":[24.57663,17.696,72.30289,60.78003]}, + {"t":0.35058, "x":7.32164, "y":4.96954, "heading":-1.97985, "vx":-1.96501, "vy":0.85365, "omega":-2.39738, "ax":-5.74404, "ay":2.61832, "alpha":-4.11689, "fx":[-105.5307,-106.97206,-86.71624,-91.59907], "fy":[29.13415,22.48973,66.56046,59.96283]}, + {"t":0.38245, "x":7.25609, "y":4.99808, "heading":-2.05625, "vx":-2.14808, "vy":0.93709, "omega":-2.5286, "ax":-5.78739, "ay":2.66158, "alpha":-2.79673, "fx":[-103.67661,-105.05506,-91.88792,-93.14812], "fy":[34.82992,29.91438,59.03842,57.30812]}, + {"t":0.41433, "x":7.18469, "y":5.0293, "heading":-2.13684, "vx":-2.33253, "vy":1.02192, "omega":-2.61773, "ax":-5.81134, "ay":2.70728, "alpha":-0.86234, "fx":[-100.44941,-100.97354,-97.14391,-96.82989], "fy":[42.76083,41.358,49.67228,50.40912]}, + {"t":0.4462, "x":7.1074, "y":5.06324, "heading":-2.22027, "vx":-2.51774, "vy":1.10821, "omega":-2.64521, "ax":-5.73467, "ay":2.73523, "alpha":2.53036, "fx":[-92.62541,-91.61166,-101.80655,-104.13688], "fy":[56.88022,58.95761,38.87877,31.38551]}, + {"t":0.47807, "x":7.02424, "y":5.09995, "heading":-2.30458, "vx":-2.70051, "vy":1.19538, "omega":-2.56457, "ax":-4.78171, "ay":2.66424, "alpha":11.63579, "fx":[-45.81234,-69.64889,-105.19702,-104.68416], "fy":[96.43567,83.46869,27.87267,-26.50499]}, + {"t":0.50994, "x":6.93575, "y":5.1394, "heading":-2.38631, "vx":-2.85291, "vy":1.28029, "omega":-2.19372, "ax":-4.31109, "ay":2.62943, "alpha":13.90563, "fx":[-25.90107,-62.69881,-104.58015,-100.14139], "fy":[100.72871,88.14586,28.53702,-38.50812]}, + {"t":0.54181, "x":6.84263, "y":5.18154, "heading":-2.45623, "vx":-2.99031, "vy":1.3641, "omega":-1.75053, "ax":-4.28996, "ay":2.57704, "alpha":13.20528, "fx":[-30.39479,-59.8464,-102.73119,-98.91176], "fy":[92.84774,88.32766,30.69967,-36.5364]}, + {"t":0.57368, "x":6.74515, "y":5.22633, "heading":-2.51202, "vx":-3.12704, "vy":1.44623, "omega":-1.32966, "ax":-3.70497, "ay":2.04123, "alpha":10.93016, "fx":[-27.50564,-51.15403,-89.62017,-83.80235], "fy":[52.85846,76.58207,31.44933,-22.00724]}, + {"t":0.60555, "x":6.6436, "y":5.27346, "heading":-2.5544, "vx":-3.24512, "vy":1.51129, "omega":-0.98131, "ax":4.38045, "ay":-2.33944, "alpha":-12.12345, "fx":[42.83833,56.97827,100.8634,97.36052], "fy":[-74.74465,-88.01873,-32.34854,35.93925]}, + {"t":0.63742, "x":6.5424, "y":5.32043, "heading":-2.58568, "vx":-3.10551, "vy":1.43673, "omega":-1.3677, "ax":4.44365, "ay":-2.60231, "alpha":-12.32512, "fx":[44.02842,55.44645,102.2664,100.59936], "fy":[-86.69931,-92.21874,-35.05677,36.91642]}, + {"t":0.6693, "x":6.44568, "y":5.3649, "heading":-2.62927, "vx":-2.96388, "vy":1.35379, "omega":-1.76051, "ax":4.43471, "ay":-2.70926, "alpha":-12.30679, "fx":[45.40828,52.59302,102.06272,101.66868], "fy":[-88.95214,-94.77306,-37.51351,36.90378]}, + {"t":0.70117, "x":6.35347, "y":5.40667, "heading":-2.68538, "vx":-2.82255, "vy":1.26744, "omega":-2.15274, "ax":4.4587, "ay":-2.74155, "alpha":-12.04642, "fx":[51.00988,48.73001,101.31173,102.31332], "fy":[-85.54188,-97.22406,-40.31483,36.54859]}, + {"t":0.73304, "x":6.26578, "y":5.44568, "heading":-2.75399, "vx":-2.68044, "vy":1.18006, "omega":-2.53668, "ax":5.61985, "ay":-2.51278, "alpha":-5.69532, "fx":[98.07953,75.46739,99.94894,108.87212], "fy":[-45.56436,-78.54958,-43.83718,-3.01523]}, + {"t":0.76491, "x":6.1832, "y":5.48201, "heading":-2.83483, "vx":-2.50133, "vy":1.09998, "omega":-2.7182, "ax":5.85196, "ay":-2.59863, "alpha":-1.34832, "fx":[99.94409,95.32999,99.57449,103.3124], "fy":[-43.66171,-53.12971,-44.81937,-35.19702]}, + {"t":0.79678, "x":6.10645, "y":5.51575, "heading":-2.92147, "vx":-2.31482, "vy":1.01716, "omega":-2.76117, "ax":5.86376, "ay":-2.59694, "alpha":1.31923, "fx":[99.43778,103.38122,100.51009,95.63422], "fy":[-45.47745,-35.50423,-42.80404,-52.90703]}, + {"t":0.82865, "x":6.03566, "y":5.54685, "heading":-3.00947, "vx":-2.12793, "vy":0.93439, "omega":-2.71912, "ax":5.82387, "ay":-2.57214, "alpha":2.99811, "fx":[98.29273,106.52818,102.38855,89.04014], "fy":[-48.20592,-25.03301,-38.22302,-63.54323]}, + {"t":0.86052, "x":5.97079, "y":5.57532, "heading":-3.09613, "vx":-1.94232, "vy":0.85241, "omega":-2.62357, "ax":5.77586, "ay":-2.53818, "alpha":4.1926, "fx":[96.84936,107.81902,104.62524,83.68953], "fy":[-51.21045,-19.19747,-31.74817,-70.53908]}, + {"t":0.89239, "x":5.91182, "y":5.6012, "heading":3.10344, "vx":-1.75824, "vy":0.77152, "omega":-2.48995, "ax":5.72692, "ay":-2.49983, "alpha":5.16134, "fx":[95.2461,108.37183,106.66694,79.36821], "fy":[-54.23654,-16.19413,-24.22291,-75.43191]}, + {"t":0.92427, "x":5.8587, "y":5.62452, "heading":3.02408, "vx":-1.57571, "vy":0.69184, "omega":-2.32545, "ax":5.67656, "ay":-2.46282, "alpha":6.00766, "fx":[93.56561,108.59927,108.17608,75.88542], "fy":[-57.155,-14.91932,-16.51455,-78.97855]}, + {"t":0.95614, "x":5.81136, "y":5.64532, "heading":2.94997, "vx":-1.39479, "vy":0.61335, "omega":-2.13398, "ax":5.62486, "ay":-2.43248, "alpha":6.75514, "fx":[91.86947,108.66332,109.07665,73.09961], "fy":[-59.89138,-14.69578,-9.32062,-81.59558]}, + {"t":0.98801, "x":5.76976, "y":5.66363, "heading":2.88195, "vx":-1.21552, "vy":0.53583, "omega":-1.91868, "ax":5.57349, "ay":-2.41161, "alpha":7.39966, "fx":[90.2088,108.6351,109.47267,70.89738], "fy":[-62.40015,-15.09085,-3.05219,-83.54024]}, + {"t":1.01988, "x":5.73385, "y":5.67948, "heading":2.8208, "vx":-1.03789, "vy":0.45896, "omega":-1.68285, "ax":5.52457, "ay":-2.40017, "alpha":7.93777, "fx":[88.62752,108.5524,109.53031,69.17511], "fy":[-64.65361,-15.81594,2.15578,-84.9909]}, + {"t":1.05175, "x":5.70358, "y":5.69289, "heading":2.76717, "vx":-0.86181, "vy":0.38247, "omega":-1.42986, "ax":5.47968, "ay":-2.39621, "alpha":8.3759, "fx":[87.16322,108.44076,109.39821,67.82886], "fy":[-66.63615,-16.67171,6.35736,-86.08498]}, + {"t":1.08362, "x":5.6789, "y":5.70386, "heading":2.7216, "vx":-0.68717, "vy":0.3061, "omega":-1.16291, "ax":5.43952, "ay":-2.39706, "alpha":8.72929, "fx":[85.84758,108.32093,109.17905,66.75135], "fy":[-68.34038,-17.51707,9.70104,-86.93703]}, + {"t":1.11549, "x":5.65976, "y":5.7124, "heading":2.68453, "vx":-0.51381, "vy":0.2297, "omega":-0.8847, "ax":5.40403, "ay":-2.40008, "alpha":9.01773, "fx":[84.70689,108.21101,108.93204,65.83412], "fy":[-69.76406,-18.25039,12.36222,-87.64644]}, + {"t":1.14736, "x":5.64613, "y":5.7185, "heading":2.65634, "vx":-0.34157, "vy":0.15321, "omega":-0.59729, "ax":5.37264, "ay":-2.40301, "alpha":9.26159, "fx":[83.76299,108.12677,108.6858,64.97293], "fy":[-70.90733,-18.79735,14.50578,-88.29902]}, + {"t":1.17924, "x":5.63797, "y":5.72217, "heading":2.6373, "vx":-0.17034, "vy":0.07662, "omega":-0.30211, "ax":5.34462, "ay":-2.40405, "alpha":9.4791, "fx":[83.03429,108.08127,108.451,64.07508], "fy":[-71.77048,-19.10264,16.2695,-88.96493]}, + {"t":1.21111, "x":5.63525, "y":5.72339, "heading":2.62767, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/F_PATH_5.traj b/src/main/deploy/choreo/F_PATH_5.traj new file mode 100644 index 00000000..9d58e0c8 --- /dev/null +++ b/src/main/deploy/choreo/F_PATH_5.traj @@ -0,0 +1,76 @@ +{ + "name":"F_PATH_5", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":5.218018531799316, "y":5.192361831665039, "heading":2.627672932910526, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":7.749877452850342, "y":6.150105953216553, "heading":-1.5707963267948966, "intervals":37, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"5.218018531799316 m", "val":5.218018531799316}, "y":{"exp":"5.192361831665039 m", "val":5.192361831665039}, "heading":{"exp":"2.627672932910526 rad", "val":2.627672932910526}, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"7.749877452850342 m", "val":7.749877452850342}, "y":{"exp":"6.150105953216553 m", "val":6.150105953216553}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":37, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.33519], + "samples":[ + {"t":0.0, "x":5.21802, "y":5.19236, "heading":2.62767, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.69438, "ay":2.1659, "alpha":6.86402, "fx":[108.78364,103.92462,75.76116,98.9699], "fy":[-14.34489,35.32299,79.38435,47.00312]}, + {"t":0.03257, "x":5.22104, "y":5.19351, "heading":2.62767, "vx":0.18544, "vy":0.07053, "omega":0.22353, "ax":5.70457, "ay":2.16618, "alpha":6.77068, "fx":[108.87417,103.90854,76.25281,99.09685], "fy":[-13.5699,35.3498,78.90065,46.70414]}, + {"t":0.06513, "x":5.2301, "y":5.19696, "heading":2.63495, "vx":0.37121, "vy":0.14108, "omega":0.44402, "ax":5.71799, "ay":2.16402, "alpha":6.65204, "fx":[108.98873,103.80487,76.69809,99.55385], "fy":[-12.53355,35.62988,78.45406,45.68699]}, + {"t":0.0977, "x":5.24522, "y":5.2027, "heading":2.64941, "vx":0.55743, "vy":0.21155, "omega":0.66065, "ax":5.73414, "ay":2.16005, "alpha":6.51009, "fx":[109.12049,103.61612,77.12809,100.27965], "fy":[-11.22716,36.14863,78.01482,44.03109]}, + {"t":0.13026, "x":5.26642, "y":5.21073, "heading":2.67093, "vx":0.74416, "vy":0.28189, "omega":0.87266, "ax":5.75241, "ay":2.15501, "alpha":6.34774, "fx":[109.26074,103.34489,77.58425,101.19751], "fy":[-9.63589,36.88657,77.54124,41.83242]}, + {"t":0.16283, "x":5.2937, "y":5.22106, "heading":2.69935, "vx":0.93149, "vy":0.35207, "omega":1.07938, "ax":5.7722, "ay":2.14984, "alpha":6.16696, "fx":[109.3982,102.99471,78.12143,102.21958], "fy":[-7.73711,37.81818,76.97574,39.21551]}, + {"t":0.19539, "x":5.3271, "y":5.23366, "heading":2.7345, "vx":1.11947, "vy":0.42208, "omega":1.28021, "ax":5.79309, "ay":2.14576, "alpha":5.9664, "fx":[109.51799,102.57162,78.81216,103.25328], "fy":[-5.49775,38.9099,76.23851,36.34467]}, + {"t":0.22796, "x":5.36662, "y":5.24854, "heading":2.77619, "vx":1.30812, "vy":0.49196, "omega":1.47451, "ax":5.81503, "ay":2.1443, "alpha":5.73802, "fx":[109.59972,102.08637,79.75229,104.20929], "fy":[-2.87001,40.11655,75.21722,33.43222]}, + {"t":0.26053, "x":5.41231, "y":5.2657, "heading":2.82421, "vx":1.49749, "vy":0.56179, "omega":1.66137, "ax":5.83856, "ay":2.14706, "alpha":5.46309, "fx":[109.6142,101.55839,81.06776,105.00892], "fy":[0.21619,41.37478,73.75014,30.74238]}, + {"t":0.29309, "x":5.46417, "y":5.28514, "heading":2.87831, "vx":1.68763, "vy":0.63171, "omega":1.83928, "ax":5.86499, "ay":2.15535, "alpha":5.10729, "fx":[109.51706,101.02257,82.92096,105.58679], "fy":[3.86697,42.59038,71.59856,28.59167]}, + {"t":0.32566, "x":5.52224, "y":5.30685, "heading":2.93821, "vx":1.87863, "vy":0.7019, "omega":2.0056, "ax":5.89622, "ay":2.16959, "alpha":4.61492, "fx":[109.23561,100.54201,85.51098,105.88317], "fy":[8.25153,43.6126,68.40208,27.35019]}, + {"t":0.35822, "x":5.58655, "y":5.33086, "heading":3.00352, "vx":2.07064, "vy":0.77256, "omega":2.15589, "ax":5.93399, "ay":2.18844, "alpha":3.90129, "fx":[108.63786,100.23328,89.05179,105.81887], "fy":[13.66031,44.1773,63.6101,27.45129]}, + {"t":0.39079, "x":5.65712, "y":5.35718, "heading":3.07373, "vx":2.26389, "vy":0.84383, "omega":2.28294, "ax":5.97746, "ay":2.20785, "alpha":2.84022, "fx":[107.44893,100.3208,93.68894,105.2409], "fy":[20.64362,43.7631,56.39317,29.41991]}, + {"t":0.42335, "x":5.73402, "y":5.38583, "heading":-3.13511, "vx":2.45855, "vy":0.91573, "omega":2.37543, "ax":6.01608, "ay":2.22019, "alpha":1.23207, "fx":[104.97647,101.26242,99.27517,103.81312], "fy":[30.385,41.15338,45.5931,33.92742]}, + {"t":0.45592, "x":5.81727, "y":5.41683, "heading":-3.05775, "vx":2.65447, "vy":0.98803, "omega":2.41555, "ax":6.00631, "ay":2.20959, "alpha":-1.34524, "fx":[98.94422,103.99951,104.92497,100.79371], "fy":[45.84191,32.69098,29.95148,41.85358]}, + {"t":0.48849, "x":5.9069, "y":5.45018, "heading":-2.97909, "vx":2.85007, "vy":1.05999, "omega":2.37175, "ax":5.73524, "ay":2.06546, "alpha":-6.56941, "fx":[78.74298,108.24751,108.58543,94.64327], "fy":[74.694,2.42748,9.27214,54.13819]}, + {"t":0.52105, "x":6.00276, "y":5.48579, "heading":-2.90185, "vx":3.03684, "vy":1.12725, "omega":2.15781, "ax":5.04307, "ay":1.8197, "alpha":-12.59492, "fx":[46.69691,100.05798,108.78478,87.58531], "fy":[97.1911,-38.57907,0.58231,64.61615]}, + {"t":0.55362, "x":6.10433, "y":5.52346, "heading":-2.83158, "vx":3.20107, "vy":1.18651, "omega":1.74765, "ax":4.66732, "ay":1.97016, "alpha":-14.26366, "fx":[31.04242,96.42574,108.29465,81.79618], "fy":[102.38514,-44.37487,4.79651,71.2408]}, + {"t":0.58618, "x":6.21105, "y":5.56315, "heading":-2.77467, "vx":3.35306, "vy":1.25067, "omega":1.28314, "ax":4.33815, "ay":1.88413, "alpha":-15.82617, "fx":[20.00816,89.33408,107.54266,78.278], "fy":[103.2194,-54.06508,5.04302,73.99657]}, + {"t":0.61875, "x":6.32254, "y":5.60488, "heading":-2.73288, "vx":3.49434, "vy":1.31203, "omega":0.76775, "ax":4.23967, "ay":1.907, "alpha":-15.00778, "fx":[21.01741,86.73409,105.05095,75.66008], "fy":[97.50023,-48.3743,7.32791,73.2965]}, + {"t":0.65131, "x":6.43859, "y":5.64861, "heading":-2.70788, "vx":3.63241, "vy":1.37413, "omega":0.27901, "ax":-2.09586, "ay":1.32705, "alpha":4.76519, "fx":[-20.15282,-28.64073,-49.59995,-44.2065], "fy":[18.47043,40.60688,26.89271,4.32096]}, + {"t":0.68388, "x":6.55577, "y":5.69407, "heading":-2.69879, "vx":3.56415, "vy":1.41735, "omega":0.43419, "ax":-4.46735, "ay":-1.60841, "alpha":14.59368, "fx":[-33.0457,-85.26117,-105.78326,-79.86341], "fy":[-93.21968,55.23465,-2.377,-69.07201]}, + {"t":0.71645, "x":6.66947, "y":5.73937, "heading":-2.68465, "vx":3.41867, "vy":1.36497, "omega":0.90945, "ax":-4.63841, "ay":-1.88492, "alpha":14.25152, "fx":[-35.22301,-93.11119,-107.57255,-79.68568], "fy":[-98.45168,49.66437,-6.98065,-72.47984]}, + {"t":0.74901, "x":6.77834, "y":5.78282, "heading":-2.65504, "vx":3.26762, "vy":1.30358, "omega":1.37356, "ax":-4.75834, "ay":-2.09163, "alpha":13.47898, "fx":[-38.82892,-98.18383,-107.89217,-78.84736], "fy":[-99.06808,42.53796,-11.34342,-74.43841]}, + {"t":0.78158, "x":6.88223, "y":5.82417, "heading":-2.61031, "vx":3.11266, "vy":1.23547, "omega":1.81251, "ax":-4.84825, "ay":-2.27485, "alpha":12.64658, "fx":[-42.82984,-101.74157,-107.6837,-77.61461], "fy":[-98.35863,35.60685,-15.79728,-76.2291]}, + {"t":0.81414, "x":6.98102, "y":5.86319, "heading":-2.55128, "vx":2.95477, "vy":1.16139, "omega":2.22435, "ax":-4.94185, "ay":-2.43931, "alpha":11.66577, "fx":[-48.37768,-104.44134,-107.11269,-76.30593], "fy":[-96.31056,28.62007,-20.4483,-77.8293]}, + {"t":0.84671, "x":7.07463, "y":5.89972, "heading":-2.47884, "vx":2.79384, "vy":1.08195, "omega":2.60426, "ax":-5.71406, "ay":-2.54877, "alpha":4.59164, "fx":[-88.56107,-107.95785,-104.36525,-87.89409], "fy":[-62.99246,-13.84853,-31.94849,-64.62582]}, + {"t":0.87927, "x":7.16258, "y":5.9336, "heading":-2.39403, "vx":2.60775, "vy":0.99895, "omega":2.75379, "ax":-5.90708, "ay":-2.51144, "alpha":0.31028, "fx":[-100.0885,-101.27375,-100.8664,-99.68225], "fy":[-43.62083,-40.81195,-41.85578,-44.58701]}, + {"t":0.91184, "x":7.24437, "y":5.9648, "heading":-2.30435, "vx":2.41539, "vy":0.91716, "omega":2.76389, "ax":-5.90789, "ay":-2.4478, "alpha":-2.13007, "fx":[-102.73491,-94.90222,-98.49006,-105.839], "fy":[-37.58751,-54.34374,-47.28202,-27.33257]}, + {"t":0.94441, "x":7.3199, "y":5.99337, "heading":-2.21435, "vx":2.22299, "vy":0.83744, "omega":2.69453, "ax":-5.86446, "ay":-2.39368, "alpha":-3.68972, "fx":[-103.31785,-89.64356,-97.62191,-108.42776], "fy":[-36.29937,-62.81103,-49.12535,-14.62742]}, + {"t":0.97697, "x":7.38918, "y":6.01938, "heading":-2.1266, "vx":2.03201, "vy":0.75949, "omega":2.57437, "ax":-5.81735, "ay":-2.35184, "alpha":-4.69458, "fx":[-103.13116,-85.16812,-98.18606,-109.32024], "fy":[-37.03333,-68.8566,-48.04887,-6.07792]}, + {"t":1.00954, "x":7.45227, "y":6.04286, "heading":-2.04276, "vx":1.84257, "vy":0.6829, "omega":2.42148, "ax":-5.77941, "ay":-2.31304, "alpha":-5.36697, "fx":[-102.56562,-81.25214,-99.85833,-109.54834], "fy":[-38.70449,-73.50003,-44.52675,-0.64552]}, + {"t":1.0421, "x":7.50921, "y":6.06388, "heading":-1.9639, "vx":1.65436, "vy":0.60758, "omega":2.24671, "ax":-5.75109, "ay":-2.26919, "alpha":-5.87396, "fx":[-101.78736,-77.77842,-102.16561,-109.56588], "fy":[-40.79678,-77.21017,-39.00777,2.62181]}, + {"t":1.07467, "x":7.56004, "y":6.08246, "heading":-1.89074, "vx":1.46707, "vy":0.53368, "omega":2.05542, "ax":-5.72773, "ay":-2.21752, "alpha":-6.32872, "fx":[-100.88911,-74.6886,-104.58673,-109.54403], "fy":[-43.03345,-80.23449,-32.04032,4.43088]}, + {"t":1.10723, "x":7.60478, "y":6.09866, "heading":-1.8238, "vx":1.28054, "vy":0.46146, "omega":1.84932, "ax":-5.70416, "ay":-2.16044, "alpha":-6.79071, "fx":[-99.93475,-71.9545,-106.68027,-109.53506], "fy":[-45.252,-82.71923,-24.29896,5.27665]}, + {"t":1.1398, "x":7.64345, "y":6.11254, "heading":-1.76358, "vx":1.09478, "vy":0.39111, "omega":1.62817, "ax":-5.67728, "ay":-2.10321, "alpha":-7.27264, "fx":[-98.97526,-69.56196,-108.19233,-109.54641], "fy":[-47.34911,-84.75999,-16.49679,5.5057]}, + {"t":1.17237, "x":7.67609, "y":6.12417, "heading":-1.71056, "vx":0.9099, "vy":0.32262, "omega":1.39133, "ax":-5.64693, "ay":-2.05113, "alpha":-7.7564, "fx":[-98.05499,-67.50138,-109.08254,-109.57149], "fy":[-49.2542,-86.42548,-9.24356,5.36673]}, + {"t":1.20493, "x":7.70273, "y":6.13358, "heading":-1.66525, "vx":0.726, "vy":0.25582, "omega":1.13874, "ax":-5.61504, "ay":-2.00749, "alpha":-8.21246, "fx":[-97.21384,-65.76225,-109.46338,-109.60161], "fy":[-50.91642,-87.76928,-2.94512,5.04369]}, + {"t":1.2375, "x":7.7234, "y":6.14085, "heading":-1.62816, "vx":0.54314, "vy":0.19044, "omega":0.8713, "ax":-5.5844, "ay":-1.97314, "alpha":-8.61439, "fx":[-96.4875,-64.33079,-109.50774,-109.63006], "fy":[-52.298,-88.83557,2.20758,4.67564]}, + {"t":1.27006, "x":7.73812, "y":6.14601, "heading":-1.59979, "vx":0.36128, "vy":0.12619, "omega":0.59076, "ax":-5.55754, "ay":-1.94714, "alpha":-8.94496, "fx":[-95.90687,-63.19018,-109.37912,-109.65278], "fy":[-53.37067,-89.66132,6.18219,4.36853]}, + {"t":1.30263, "x":7.74694, "y":6.14908, "heading":-1.58055, "vx":0.1803, "vy":0.06278, "omega":0.29946, "ax":-5.53638, "ay":-1.9277, "alpha":-9.1957, "fx":[-95.49725,-62.32277,-109.20115,-109.66766], "fy":[-54.11339,-90.27671,9.02933,4.20227]}, + {"t":1.33519, "x":7.74988, "y":6.15011, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/F_PATH_6.traj b/src/main/deploy/choreo/F_PATH_6.traj new file mode 100644 index 00000000..17ef0175 --- /dev/null +++ b/src/main/deploy/choreo/F_PATH_6.traj @@ -0,0 +1,85 @@ +{ + "name":"F_PATH_6", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.749877452850342, "y":6.150105953216553, "heading":-1.5707963267948966, "intervals":50, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":5.483531951904297, "y":2.3855068683624268, "heading":0.558599362427265, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"7.749877452850342 m", "val":7.749877452850342}, "y":{"exp":"6.150105953216553 m", "val":6.150105953216553}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":50, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"5.483531951904297 m", "val":5.483531951904297}, "y":{"exp":"2.3855068683624268 m", "val":2.3855068683624268}, "heading":{"exp":"0.558599362427265 rad", "val":0.558599362427265}, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.76157], + "samples":[ + {"t":0.0, "x":7.74988, "y":6.15011, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.00144, "ay":-5.17868, "alpha":7.93248, "fx":[-29.78587,-98.03161,-65.00344,-11.39336], "fy":[-105.44655,-49.2917,-88.45555,-109.15784]}, + {"t":0.03523, "x":7.74801, "y":6.14689, "heading":-1.5708, "vx":-0.10574, "vy":-0.18245, "omega":0.27947, "ax":-3.02122, "ay":-5.1855, "alpha":7.79187, "fx":[-30.92861,-97.58605,-64.94138,-12.10427], "fy":[-105.1024,-50.14728,-88.4929,-109.0732]}, + {"t":0.07046, "x":7.74241, "y":6.13725, "heading":-1.56095, "vx":-0.21219, "vy":-0.36514, "omega":0.55399, "ax":-3.04881, "ay":-5.19522, "alpha":7.58044, "fx":[-33.23511,-96.95215,-64.56121,-12.68915], "fy":[-104.37856,-51.34037,-88.76113,-108.99687]}, + {"t":0.10569, "x":7.73305, "y":6.12116, "heading":-1.54143, "vx":-0.3196, "vy":-0.54818, "omega":0.82106, "ax":-3.0833, "ay":-5.20693, "alpha":7.30796, "fx":[-36.57807,-96.11132,-63.87861,-13.21612], "fy":[-103.23438,-52.87465,-89.24254,-108.92221]}, + {"t":0.14093, "x":7.71987, "y":6.09861, "heading":-1.51251, "vx":-0.42823, "vy":-0.73163, "omega":1.07853, "ax":-3.12342, "ay":-5.21956, "alpha":6.98789, "fx":[-40.77994,-95.03556,-62.91561,-13.7829], "fy":[-101.62516,-54.75973,-89.91089,-108.83714]}, + {"t":0.17616, "x":7.70285, "y":6.0696, "heading":-1.47451, "vx":-0.53827, "vy":-0.91552, "omega":1.32472, "ax":-3.16728, "ay":-5.23237, "alpha":6.63477, "fx":[-45.58321,-93.68445,-61.70335,-14.52696], "fy":[-99.53847,-57.01286,-90.73125,-108.72192]}, + {"t":0.21139, "x":7.68192, "y":6.03409, "heading":-1.42783, "vx":-0.64986, "vy":-1.09986, "omega":1.55848, "ax":-3.21234, "ay":-5.2456, "alpha":6.25821, "fx":[-50.63607,-91.99961,-60.28668,-15.64189], "fy":[-97.03915,-59.66213,-91.65913,-108.54392]}, + {"t":0.24662, "x":7.65703, "y":5.99209, "heading":-1.37293, "vx":-0.76304, "vy":-1.28467, "omega":1.77896, "ax":-3.25604, "ay":-5.26091, "alpha":5.85308, "fx":[-55.5061,-89.89432,-58.7327,-17.404], "fy":[-94.31052,-62.75258,-92.63782,-108.24566]}, + {"t":0.28185, "x":7.62812, "y":5.94356, "heading":-1.31025, "vx":-0.87775, "vy":-1.47002, "omega":1.98517, "ax":-3.29686, "ay":-5.28136, "alpha":5.38647, "fx":[-59.71965,-87.23334,-57.14776,-20.21405], "fy":[-91.67157,-66.35715,-93.59143,-107.71761]}, + {"t":0.31708, "x":7.59515, "y":5.88849, "heading":-1.24031, "vx":-0.9939, "vy":-1.65609, "omega":2.17495, "ax":-3.3358, "ay":-5.31018, "alpha":4.78354, "fx":[-62.80299,-83.79109,-55.71351,-24.65656], "fy":[-89.55645,-70.59719,-94.40768,-106.73702]}, + {"t":0.35231, "x":7.55807, "y":5.82685, "heading":-1.16369, "vx":-1.11143, "vy":-1.84318, "omega":2.34348, "ax":-3.3771, "ay":-5.348, "alpha":3.91277, "fx":[-64.28742,-79.15493,-54.77014,-31.56128], "fy":[-88.46198,-75.68339,-94.89284,-104.8337]}, + {"t":0.38755, "x":7.51681, "y":5.75859, "heading":-1.08112, "vx":-1.23041, "vy":-2.0316, "omega":2.48133, "ax":-3.42628, "ay":-5.38725, "alpha":2.56779, "fx":[-63.64581,-72.46707,-55.03435,-41.97282], "fy":[-88.88287,-82.00272,-94.63486,-101.02209]}, + {"t":0.42278, "x":7.47134, "y":5.68368, "heading":-0.9937, "vx":-1.35112, "vy":-2.2214, "omega":2.5718, "ax":-3.47935, "ay":-5.40014, "alpha":0.42645, "fx":[-60.14087,-61.59892,-58.29172,-56.69959], "fy":[-91.23863,-90.28654,-92.46673,-93.42766]}, + {"t":0.45801, "x":7.42158, "y":5.60206, "heading":-0.90309, "vx":-1.4737, "vy":-2.41165, "omega":2.58682, "ax":-3.49091, "ay":-5.29078, "alpha":-3.23558, "fx":[-52.59854,-39.9152,-70.19292,-74.81085], "fy":[-95.71923,-101.46293,-83.28727,-79.50948]}, + {"t":0.49324, "x":7.36749, "y":5.51381, "heading":-0.81195, "vx":-1.59669, "vy":-2.59805, "omega":2.47283, "ax":-3.28715, "ay":-4.52048, "alpha":-11.09421, "fx":[-40.39128,8.43929,-101.48065,-90.22108], "fy":[-101.38487,-108.1905,-36.70093,-61.29224]}, + {"t":0.52847, "x":7.3092, "y":5.41947, "heading":-0.72483, "vx":-1.7125, "vy":-2.75732, "omega":2.08196, "ax":-3.04738, "ay":-4.39405, "alpha":-12.72624, "fx":[-34.02245,19.52988,-104.16666,-88.681], "fy":[-103.47598,-106.22873,-26.1099,-63.15143]}, + {"t":0.5637, "x":7.24697, "y":5.3196, "heading":-0.65148, "vx":-1.81987, "vy":-2.91212, "omega":1.6336, "ax":-2.77265, "ay":-4.33548, "alpha":-13.83557, "fx":[-27.56334,29.48552,-104.39242,-86.17777], "fy":[-105.00373,-103.03285,-21.01846,-65.92612]}, + {"t":0.59893, "x":7.18113, "y":5.21431, "heading":-0.59393, "vx":-1.91755, "vy":-3.06487, "omega":1.14615, "ax":-2.43265, "ay":-4.22411, "alpha":-15.02853, "fx":[-20.43176,41.32437,-103.18902,-83.21829], "fy":[-105.84931,-97.07679,-16.08378,-68.39406]}, + {"t":0.63417, "x":7.11207, "y":5.10371, "heading":-0.55355, "vx":-2.00326, "vy":-3.21369, "omega":0.61668, "ax":-2.21024, "ay":-3.99987, "alpha":-15.38659, "fx":[-16.79233,44.66525,-97.83013,-80.42491], "fy":[-103.96,-89.50023,-10.90363,-67.78292]}, + {"t":0.6694, "x":7.04012, "y":4.98801, "heading":-0.53182, "vx":-2.08113, "vy":-3.35461, "omega":0.07459, "ax":0.53397, "ay":-0.96542, "alpha":-1.84388, "fx":[10.64867,15.77368,7.52336,2.38523], "fy":[-22.76526,-14.65506,-9.94351,-18.32206]}, + {"t":0.70463, "x":6.96713, "y":4.86922, "heading":-0.52919, "vx":-2.06231, "vy":-3.38863, "omega":0.00962, "ax":0.27116, "ay":-0.16602, "alpha":-0.00415, "fx":[4.61624,4.62712,4.60856,4.59769], "fy":[-2.83872,-2.8201,-2.80925,-2.82787]}, + {"t":0.73986, "x":6.89464, "y":4.74973, "heading":-0.52886, "vx":-2.05276, "vy":-3.39447, "omega":0.00948, "ax":0.08734, "ay":-0.05277, "alpha":0.0, "fx":[1.48566,1.48567,1.48566,1.48565], "fy":[-0.89758,-0.89756,-0.89755,-0.89757]}, + {"t":0.77509, "x":6.82237, "y":4.63011, "heading":-0.52852, "vx":-2.04968, "vy":-3.39633, "omega":0.00948, "ax":0.02808, "ay":-0.01694, "alpha":0.0, "fx":[0.47758,0.47758,0.47758,0.47758], "fy":[-0.28812,-0.28812,-0.28813,-0.28812]}, + {"t":0.81032, "x":6.75017, "y":4.51044, "heading":-0.52819, "vx":-2.04869, "vy":-3.39693, "omega":0.00948, "ax":0.0093, "ay":-0.00561, "alpha":0.0, "fx":[0.15823,0.15824,0.15823,0.15822], "fy":[-0.09543,-0.09542,-0.09542,-0.09542]}, + {"t":0.84555, "x":6.678, "y":4.39075, "heading":-0.52785, "vx":-2.04837, "vy":-3.39713, "omega":0.00948, "ax":0.00395, "ay":-0.00238, "alpha":0.0, "fx":[0.0672,0.06721,0.0672,0.06719], "fy":[-0.04053,-0.04052,-0.04051,-0.04052]}, + {"t":0.88079, "x":6.60584, "y":4.27107, "heading":-0.52752, "vx":-2.04823, "vy":-3.39721, "omega":0.00948, "ax":0.0043, "ay":-0.00259, "alpha":0.0, "fx":[0.07308,0.07308,0.07307,0.07307], "fy":[-0.04407,-0.04406,-0.04405,-0.04406]}, + {"t":0.91602, "x":6.53368, "y":4.15138, "heading":-0.52719, "vx":-2.04808, "vy":-3.3973, "omega":0.00948, "ax":0.01084, "ay":-0.00653, "alpha":0.0, "fx":[0.18436,0.18436,0.18436,0.18435], "fy":[-0.11113,-0.11113,-0.11112,-0.11113]}, + {"t":0.95125, "x":6.46153, "y":4.03168, "heading":-0.52685, "vx":-2.04769, "vy":-3.39753, "omega":0.00948, "ax":0.03303, "ay":-0.0199, "alpha":0.0, "fx":[0.56182,0.56182,0.56182,0.56183], "fy":[-0.33846,-0.33847,-0.33848,-0.33847]}, + {"t":0.98648, "x":6.3894, "y":3.91197, "heading":-0.52652, "vx":-2.04653, "vy":-3.39823, "omega":0.00948, "ax":0.10293, "ay":-0.0619, "alpha":0.00003, "fx":[1.75075,1.75067,1.75081,1.75088], "fy":[-1.05284,-1.05298,-1.05305,-1.05292]}, + {"t":1.02171, "x":6.31737, "y":3.79221, "heading":-0.52618, "vx":-2.0429, "vy":-3.40042, "omega":0.00948, "ax":0.32207, "ay":-0.19003, "alpha":0.00757, "fx":[5.47126,5.45144,5.48535,5.50515], "fy":[-3.20554,-3.23962,-3.25931,-3.22521]}, + {"t":1.05694, "x":6.24559, "y":3.67229, "heading":-0.52585, "vx":-2.03156, "vy":-3.40711, "omega":0.00974, "ax":1.41204, "ay":0.24654, "alpha":3.17727, "fx":[21.2012,13.08045,27.2772,34.51479], "fy":[16.11174,1.15477,-7.54649,7.0545]}, + {"t":1.09217, "x":6.17489, "y":3.5524, "heading":-0.52551, "vx":-1.98181, "vy":-3.39842, "omega":0.12168, "ax":2.51454, "ay":3.85102, "alpha":15.42274, "fx":[22.25314,-36.2199,100.83361,84.2194], "fy":[103.182,92.41511,2.57825,63.84377]}, + {"t":1.12741, "x":6.10663, "y":3.43506, "heading":-0.52122, "vx":-1.89322, "vy":-3.26275, "omega":0.66505, "ax":2.58233, "ay":4.12296, "alpha":15.153, "fx":[21.97339,-35.76083,105.06776,84.41827], "fy":[105.55713,98.63111,9.18903,67.14397]}, + {"t":1.16264, "x":6.04153, "y":3.32267, "heading":-0.49779, "vx":-1.80224, "vy":-3.11749, "omega":1.19891, "ax":2.55174, "ay":4.4138, "alpha":14.17537, "fx":[19.95719,-33.03548,104.98234,81.71316], "fy":[106.68807,101.52858,20.62524,71.46798]}, + {"t":1.19787, "x":5.97962, "y":3.21557, "heading":-0.45555, "vx":-1.71234, "vy":-2.96199, "omega":1.69833, "ax":2.49362, "ay":4.68138, "alpha":13.07116, "fx":[17.56743,-29.1487,103.0449,78.19942], "fy":[107.45676,103.59831,31.67137,75.78942]}, + {"t":1.2331, "x":5.92084, "y":3.11413, "heading":-0.39572, "vx":-1.62448, "vy":-2.79705, "omega":2.15884, "ax":2.46834, "ay":4.95764, "alpha":11.56758, "fx":[15.7881,-21.1857,99.35233,73.98857], "fy":[107.93083,106.01061,43.18866,80.18199]}, + {"t":1.26833, "x":5.86514, "y":3.01866, "heading":-0.31966, "vx":-1.53752, "vy":-2.62239, "omega":2.56639, "ax":2.98827, "ay":5.58007, "alpha":3.40914, "fx":[35.66544,36.09166,69.94151,61.62005], "fy":[103.18098,102.75758,83.57251,90.15066]}, + {"t":1.30356, "x":5.81283, "y":2.92973, "heading":-0.22924, "vx":-1.43224, "vy":-2.4258, "omega":2.6865, "ax":3.10927, "ay":5.62026, "alpha":-0.47267, "fx":[55.55218,54.33541,50.2904,51.37293], "fy":[94.09728,94.83323,97.03149,96.43403]}, + {"t":1.33879, "x":5.7643, "y":2.84775, "heading":-0.13459, "vx":-1.3227, "vy":-2.22779, "omega":2.66984, "ax":3.12938, "ay":5.55824, "alpha":-2.71722, "fx":[69.6137,59.47275,38.50087,45.33182], "fy":[84.36062,91.9034,102.44162,99.47042]}, + {"t":1.37403, "x":5.71964, "y":2.77272, "heading":-0.04053, "vx":-1.21244, "vy":-2.03196, "omega":2.57411, "ax":3.11702, "ay":5.48881, "alpha":-4.1457, "fx":[78.55176,60.47991,30.07338,42.97372], "fy":[76.23505,91.35619,105.31125,100.5499]}, + {"t":1.40926, "x":5.67886, "y":2.70453, "heading":0.05016, "vx":-1.10263, "vy":-1.83858, "omega":2.42805, "ax":3.09846, "ay":5.43153, "alpha":-5.04639, "fx":[83.9588,59.77432,23.41012,43.67244], "fy":[70.34536,91.88887,107.04388,100.27725]}, + {"t":1.44449, "x":5.64193, "y":2.64313, "heading":0.13571, "vx":-0.99346, "vy":-1.64722, "omega":2.25026, "ax":3.08785, "ay":5.3845, "alpha":-5.62335, "fx":[87.15309,58.26728,17.86527,46.8081], "fy":[66.43592,92.89827,108.14422,98.87672]}, + {"t":1.47972, "x":5.60885, "y":2.58844, "heading":0.21499, "vx":-0.88467, "vy":-1.45752, "omega":2.05214, "ax":3.08994, "ay":5.34071, "alpha":-6.03368, "fx":[88.99199,56.38889,13.13988,51.7155], "fy":[64.02258,94.0832,108.84587,96.42417]}, + {"t":1.51495, "x":5.5796, "y":2.5404, "heading":0.28729, "vx":-0.77581, "vy":-1.26936, "omega":1.83957, "ax":3.10287, "ay":5.29459, "alpha":-6.38657, "fx":[89.99639,54.37629,9.07975,57.66337], "fy":[62.65874,95.28492,109.27944,93.01475]}, + {"t":1.55018, "x":5.55419, "y":2.49897, "heading":0.3521, "vx":-0.66649, "vy":-1.08282, "omega":1.61456, "ax":3.12132, "ay":5.24418, "alpha":-6.74257, "fx":[90.48438,52.37705,5.5978,63.91195], "fy":[61.99609,96.41701,109.52872,88.86586]}, + {"t":1.58541, "x":5.53265, "y":2.46407, "heading":0.40898, "vx":-0.55652, "vy":-0.89806, "omega":1.37701, "ax":3.13964, "ay":5.19101, "alpha":-7.11871, "fx":[90.65867,50.49317,2.63998,69.82592], "fy":[61.77602,97.43152,109.65273,84.33034]}, + {"t":1.62065, "x":5.51499, "y":2.43565, "heading":0.45749, "vx":-0.44591, "vy":-0.71518, "omega":1.12621, "ax":3.15404, "ay":5.13867, "alpha":-7.50149, "fx":[90.65646,48.80152,0.16822,74.97113], "fy":[61.80737,98.30164,109.69525,79.82519]}, + {"t":1.65588, "x":5.50123, "y":2.41365, "heading":0.49717, "vx":-0.33479, "vy":-0.53413, "omega":0.86192, "ax":3.16332, "ay":5.09093, "alpha":-7.86362, "fx":[90.57638,47.36342,-1.84826,79.13686], "fy":[61.94737,99.01238,109.68935,75.7321]}, + {"t":1.69111, "x":5.4914, "y":2.39799, "heading":0.52754, "vx":-0.22334, "vy":-0.35477, "omega":0.58487, "ax":3.16833, "ay":5.05059, "alpha":-8.17771, "fx":[90.49241,46.22872,-3.4369,82.28515], "fy":[62.08851,99.55549,109.65974,72.33234]}, + {"t":1.72634, "x":5.4855, "y":2.38862, "heading":0.54814, "vx":-0.11172, "vy":-0.17683, "omega":0.29676, "ax":3.17093, "ay":5.01917, "alpha":-8.42318, "fx":[90.46063,45.43722,-4.62248,84.47085], "fy":[62.15005,99.92629,109.62428,69.79771]}, + {"t":1.76157, "x":5.48353, "y":2.38551, "heading":0.5586, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/F_PATH_7.traj b/src/main/deploy/choreo/F_PATH_7.traj new file mode 100644 index 00000000..c4ba3538 --- /dev/null +++ b/src/main/deploy/choreo/F_PATH_7.traj @@ -0,0 +1,79 @@ +{ + "name":"F_PATH_7", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":5.483531951904297, "y":2.3855068683624268, "heading":0.558599362427265, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":7.740394592285156, "y":4.784609317779541, "heading":-1.5707963267948966, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"5.483531951904297 m", "val":5.483531951904297}, "y":{"exp":"2.3855068683624268 m", "val":2.3855068683624268}, "heading":{"exp":"0.558599362427265 rad", "val":0.558599362427265}, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"7.740394592285156 m", "val":7.740394592285156}, "y":{"exp":"4.784609317779541 m", "val":4.784609317779541}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.48526], + "samples":[ + {"t":0.0, "x":5.48353, "y":2.38551, "heading":0.5586, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.06902, "ay":4.07773, "alpha":-10.176, "fx":[99.2944,58.27962,13.52489,105.75279], "fy":[46.76627,93.01673,108.85581,28.80536]}, + {"t":0.03376, "x":5.48585, "y":2.38783, "heading":0.5586, "vx":0.13735, "vy":0.13765, "omega":-0.3435, "ax":4.08032, "ay":4.11044, "alpha":-9.9224, "fx":[99.02037,58.47816,14.94797,105.17382], "fy":[47.32598,92.88381,108.6582,30.80179]}, + {"t":0.06751, "x":5.49281, "y":2.39482, "heading":0.547, "vx":0.27509, "vy":0.2764, "omega":-0.67844, "ax":4.09975, "ay":4.14843, "alpha":-9.57171, "fx":[98.85905,59.10274,16.73494,104.24589], "fy":[47.64071,92.47818,108.38587,33.74988]}, + {"t":0.10127, "x":5.50443, "y":2.40651, "heading":0.5241, "vx":0.41348, "vy":0.41643, "omega":-1.00154, "ax":4.12518, "ay":4.19332, "alpha":-9.12138, "fx":[98.77786,60.12659,18.91062,102.85715], "fy":[47.78285,91.80473,108.01559,37.70564]}, + {"t":0.13502, "x":5.52074, "y":2.42296, "heading":0.49029, "vx":0.55273, "vy":0.55798, "omega":-1.30944, "ax":4.15368, "ay":4.24686, "alpha":-8.57053, "fx":[98.72768,61.51163,21.52118,100.85098], "fy":[47.85454,90.8693,107.51312,42.71466]}, + {"t":0.16878, "x":5.54177, "y":2.44421, "heading":0.44609, "vx":0.69294, "vy":0.70134, "omega":-1.59875, "ax":4.1818, "ay":4.30999, "alpha":-7.92578, "fx":[98.63845,63.20698,24.6304,98.04915], "fy":[47.99858,89.68209,106.82938,48.73644]}, + {"t":0.20254, "x":5.56754, "y":2.47034, "heading":0.39213, "vx":0.8341, "vy":0.84683, "omega":-1.86629, "ax":4.20631, "ay":4.3817, "alpha":-7.2051, "fx":[98.4102,65.14687,28.31867,94.31692], "fy":[48.4152,88.26253,105.89455,55.55346]}, + {"t":0.23629, "x":5.59809, "y":2.50143, "heading":0.32913, "vx":0.97609, "vy":0.99474, "omega":-2.10951, "ax":4.22569, "ay":4.45846, "alpha":-6.43345, "fx":[97.894,67.24715,32.68893,89.68132], "fy":[49.3882,86.64636,104.60718,62.70702]}, + {"t":0.27005, "x":5.63345, "y":2.53754, "heading":0.25792, "vx":1.11873, "vy":1.14524, "omega":-2.32668, "ax":4.24166, "ay":4.53512, "alpha":-5.62262, "fx":[96.85103,69.39807,37.88443,84.46387], "fy":[51.32494,84.89733,102.81236,69.52949]}, + {"t":0.3038, "x":5.67363, "y":2.57879, "heading":0.17938, "vx":1.26191, "vy":1.29832, "omega":-2.51647, "ax":4.2588, "ay":4.60761, "alpha":-4.73537, "fx":[94.86489,71.44585,44.12513,79.32795], "fy":[54.81177,83.13027,100.25488,75.29941]}, + {"t":0.33756, "x":5.71865, "y":2.62524, "heading":0.09443, "vx":1.40567, "vy":1.45386, "omega":-2.67632, "ax":4.28048, "ay":4.67561, "alpha":-3.64533, "fx":[91.15682,73.14291,51.7759,75.16314], "fy":[60.66115,81.56415,96.47117,79.42682]}, + {"t":0.37132, "x":5.76854, "y":2.67698, "heading":0.00409, "vx":1.55017, "vy":1.61169, "omega":-2.79937, "ax":4.30009, "ay":4.74004, "alpha":-2.10648, "fx":[84.23774,73.99829,61.47356,72.8633], "fy":[69.81662,80.66326,90.51284,81.51409]}, + {"t":0.40507, "x":5.82332, "y":2.73408, "heading":-0.0904, "vx":1.69532, "vy":1.77169, "omega":-2.87048, "ax":4.28732, "ay":4.78573, "alpha":0.25984, "fx":[71.52664,72.71666,74.32226,73.13899], "fy":[82.64922,81.5891,80.14076,81.23657]}, + {"t":0.43883, "x":5.88299, "y":2.79661, "heading":-0.1873, "vx":1.84004, "vy":1.93324, "omega":-2.86171, "ax":4.14871, "ay":4.73893, "alpha":4.01935, "fx":[50.2715,64.00829,91.587,76.40658], "fy":[96.93528,88.06907,59.29467,78.13239]}, + {"t":0.47258, "x":5.94746, "y":2.86457, "heading":-0.2839, "vx":1.98009, "vy":2.09321, "omega":-2.72603, "ax":3.35276, "ay":4.45626, "alpha":10.89643, "fx":[25.28838,13.354,107.25533,82.22057], "fy":[106.15393,106.70838,18.41288,71.92333]}, + {"t":0.50634, "x":6.01621, "y":2.93777, "heading":-0.37592, "vx":2.09326, "vy":2.24363, "omega":-2.35821, "ax":3.30318, "ay":4.30238, "alpha":12.02432, "fx":[28.45596,3.01676,107.80118,85.47042], "fy":[105.20955,107.17855,12.53243,67.80849]}, + {"t":0.5401, "x":6.08876, "y":3.01596, "heading":-0.45552, "vx":2.20476, "vy":2.38886, "omega":-1.95232, "ax":3.34209, "ay":4.14885, "alpha":12.64734, "fx":[32.24447,-0.90487,107.79129,88.26089], "fy":[103.88292,106.72178,7.90826,63.76982]}, + {"t":0.57385, "x":6.16508, "y":3.09896, "heading":-0.52143, "vx":2.31758, "vy":2.52891, "omega":-1.52539, "ax":3.35633, "ay":3.9557, "alpha":13.39265, "fx":[35.27119,-4.99371,107.32368,90.75967], "fy":[102.49235,105.60532,1.54191,59.50176]}, + {"t":0.60761, "x":6.24523, "y":3.18658, "heading":-0.57292, "vx":2.43088, "vy":2.66244, "omega":-1.07331, "ax":3.35561, "ay":3.71586, "alpha":14.08667, "fx":[37.90162,-8.02534,105.68447,92.75139], "fy":[100.69205,103.16598,-5.93213,54.89722]}, + {"t":0.64136, "x":6.3292, "y":3.27857, "heading":-0.60915, "vx":2.54415, "vy":2.78787, "omega":-0.5978, "ax":3.34078, "ay":3.34837, "alpha":14.30528, "fx":[40.52935,-7.08386,100.51418,93.34331], "fy":[96.84707,95.69831,-13.72679,49.00101]}, + {"t":0.67512, "x":6.41698, "y":3.37458, "heading":-0.62933, "vx":2.65692, "vy":2.9009, "omega":-0.11491, "ax":1.81758, "ay":-0.37365, "alpha":3.06665, "fx":[29.90176,20.3295,32.40234,41.03248], "fy":[5.72588,-8.80447,-18.05291,-4.29119]}, + {"t":0.70888, "x":6.5077, "y":3.47229, "heading":-0.63321, "vx":2.71827, "vy":2.88829, "omega":-0.0114, "ax":0.37865, "ay":-0.35326, "alpha":0.01104, "fx":[6.43482,6.40062,6.44659,6.48079], "fy":[-5.96873,-6.01518,-6.04882,-6.00237]}, + {"t":0.74263, "x":6.59968, "y":3.56959, "heading":-0.63359, "vx":2.73105, "vy":2.87636, "omega":-0.01102, "ax":-0.04307, "ay":0.04071, "alpha":-0.00042, "fx":[-0.73236,-0.73106,-0.73283,-0.73414], "fy":[0.69096,0.69273,0.69404,0.69226]}, + {"t":0.77639, "x":6.69184, "y":3.66671, "heading":-0.63396, "vx":2.7296, "vy":2.87774, "omega":-0.01104, "ax":-0.5397, "ay":0.45789, "alpha":-0.11947, "fx":[-9.11941,-8.74664,-9.24124,-9.61359], "fy":[7.35483,7.86024,8.2221,7.71734]}, + {"t":0.81014, "x":6.78367, "y":3.76411, "heading":-0.63434, "vx":2.71138, "vy":2.89319, "omega":-0.01507, "ax":-3.11184, "ay":-2.21952, "alpha":-11.67954, "fx":[-42.20876,-8.19689,-77.22652,-84.09353], "fy":[-77.96489,-55.04617,17.29493,-35.29735]}, + {"t":0.8439, "x":6.87343, "y":3.86051, "heading":-0.63484, "vx":2.60634, "vy":2.81827, "omega":-0.40933, "ax":-3.25197, "ay":-3.50799, "alpha":-14.7624, "fx":[-39.06778,13.77849,-102.55728,-93.41379], "fy":[-98.87048,-99.49557,10.88684,-51.20047]}, + {"t":0.87766, "x":6.95955, "y":3.95364, "heading":-0.64866, "vx":2.49657, "vy":2.69986, "omega":-0.90764, "ax":-3.18859, "ay":-3.65721, "alpha":-15.31521, "fx":[-37.55816,20.19117,-105.67133,-93.90978], "fy":[-101.26428,-103.18337,9.11055,-53.49543]}, + {"t":0.91141, "x":7.04201, "y":4.04269, "heading":-0.6793, "vx":2.38893, "vy":2.5764, "omega":-1.42462, "ax":-3.10468, "ay":-3.67428, "alpha":-15.91338, "fx":[-36.62462,26.4219,-106.6824,-94.35389], "fy":[-102.28121,-103.5993,9.77339,-53.88642]}, + {"t":0.94517, "x":7.12088, "y":4.12757, "heading":-0.72739, "vx":2.28413, "vy":2.45238, "omega":-1.9618, "ax":-3.70625, "ay":-4.32027, "alpha":-10.30673, "fx":[-45.62335,-10.9932,-104.16124,-91.39133], "fy":[-98.91931,-107.44207,-28.31794,-59.26683]}, + {"t":0.97892, "x":7.19587, "y":4.20789, "heading":-0.79361, "vx":2.15902, "vy":2.30654, "omega":-2.30971, "ax":-4.2332, "ay":-4.75289, "alpha":-2.44203, "fx":[-64.58305,-60.9058,-81.58757,-80.94542], "fy":[-87.91137,-90.26737,-72.09173,-73.1108]}, + {"t":1.01268, "x":7.26634, "y":4.28304, "heading":-0.87158, "vx":2.01613, "vy":2.1461, "omega":-2.39214, "ax":-4.3147, "ay":-4.7513, "alpha":0.64919, "fx":[-75.58229,-76.11092,-71.36476,-70.5093], "fy":[-78.81382,-78.35812,-82.71023,-83.39059]}, + {"t":1.04644, "x":7.33194, "y":4.35278, "heading":-0.95233, "vx":1.87048, "vy":1.98572, "omega":-2.37023, "ax":-4.32003, "ay":-4.70275, "alpha":2.45779, "fx":[-81.70891,-83.41018,-67.54619,-61.26485], "fy":[-72.56636,-70.79059,-86.08041,-90.53258]}, + {"t":1.08019, "x":7.39262, "y":4.41713, "heading":-1.03234, "vx":1.72465, "vy":1.82697, "omega":-2.28726, "ax":-4.30853, "ay":-4.64923, "alpha":3.66074, "fx":[-85.01306,-87.95941,-66.44973,-53.72538], "fy":[-68.76032,-65.20812,-87.05604,-95.30356]}, + {"t":1.11395, "x":7.44838, "y":4.47615, "heading":-1.10955, "vx":1.57921, "vy":1.67003, "omega":-2.16369, "ax":-4.29646, "ay":-4.60018, "alpha":4.47907, "fx":[-86.56503,-91.20043,-66.63958,-47.92106], "fy":[-66.8684,-60.70022,-86.99187,-98.43016]}, + {"t":1.1477, "x":7.49924, "y":4.52991, "heading":-1.18258, "vx":1.43418, "vy":1.51475, "omega":-2.0125, "ax":-4.28734, "ay":-4.55918, "alpha":5.03258, "fx":[-86.93664,-93.67892,-67.46376,-43.62668], "fy":[-66.44113,-56.88027,-86.41064,-100.46946]}, + {"t":1.18146, "x":7.54521, "y":4.57844, "heading":-1.25052, "vx":1.28946, "vy":1.36085, "omega":-1.84262, "ax":-4.28042, "ay":-4.52732, "alpha":5.4055, "fx":[-86.46149,-95.64916,-68.5867,-40.53771], "fy":[-67.10372,-53.56303,-85.56354,-101.80363]}, + {"t":1.21522, "x":7.5863, "y":4.6218, "heading":-1.31272, "vx":1.14497, "vy":1.20802, "omega":-1.66015, "ax":-4.27396, "ay":-4.50413, "alpha":5.66102, "fx":[-85.36306,-97.24969,-69.82071,-38.36184], "fy":[-68.53327,-50.64938,-84.59143,-102.68169]}, + {"t":1.24897, "x":7.62251, "y":4.66001, "heading":-1.36876, "vx":1.0007, "vy":1.05598, "omega":-1.46906, "ax":-4.26655, "ay":-4.48822, "alpha":5.84549, "fx":[-83.8184,-98.56557,-71.05499,-36.85256], "fy":[-70.44633,-48.08062,-83.58256,-103.26361]}, + {"t":1.28273, "x":7.65386, "y":4.6931, "heading":-1.41835, "vx":0.85668, "vy":0.90448, "omega":-1.27174, "ax":-4.25753, "ay":-4.47781, "alpha":5.99078, "fx":[-81.9883,-99.65382,-72.22174,-35.81386], "fy":[-72.59652,-45.81871,-82.59698,-103.65316]}, + {"t":1.31648, "x":7.68035, "y":4.72108, "heading":-1.46127, "vx":0.71296, "vy":0.75333, "omega":-1.06951, "ax":-4.24693, "ay":-4.47114, "alpha":6.1166, "fx":[-80.02871,-100.55511,-73.27816,-35.09396], "fy":[-74.77671,-43.83718,-81.6782,-103.9193]}, + {"t":1.35024, "x":7.702, "y":4.74396, "heading":-1.49738, "vx":0.5696, "vy":0.6024, "omega":-0.86304, "ax":-4.23528, "ay":-4.46666, "alpha":6.23314, "fx":[-78.09129,-101.29966,-74.19641,-34.5763], "fy":[-76.82095,-42.11665,-80.8593,-104.10933]}, + {"t":1.384, "x":7.71882, "y":4.76175, "heading":-1.52651, "vx":0.42663, "vy":0.45162, "omega":-0.65263, "ax":-4.22345, "ay":-4.46317, "alpha":6.34376, "fx":[-76.31906,-101.91042,-74.95764,-34.17131], "fy":[-78.60298,-40.64249,-80.16639,-104.2568]}, + {"t":1.41775, "x":7.73081, "y":4.77445, "heading":-1.54854, "vx":0.28407, "vy":0.30096, "omega":-0.43849, "ax":-4.21236, "ay":-4.45982, "alpha":6.4477, "fx":[-74.84109,-102.40504,-75.54846,-33.80985], "fy":[-80.03076,-39.40366,-79.62043,-104.38617]}, + {"t":1.45151, "x":7.738, "y":4.78207, "heading":-1.56334, "vx":0.14187, "vy":0.15042, "omega":-0.22084, "ax":-4.20293, "ay":-4.45604, "alpha":6.54238, "fx":[-73.76891,-102.79698,-75.95871,-33.43827], "fy":[-81.03769,-38.39205,-79.23838,-104.51554]}, + {"t":1.48526, "x":7.74039, "y":4.78461, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/deploy/choreo/F_PATH_8.traj b/src/main/deploy/choreo/F_PATH_8.traj new file mode 100644 index 00000000..e46d47d3 --- /dev/null +++ b/src/main/deploy/choreo/F_PATH_8.traj @@ -0,0 +1,70 @@ +{ + "name":"F_PATH_8", + "version":1, + "snapshot":{ + "waypoints":[ + {"x":7.740394592285156, "y":4.784609317779541, "heading":-1.5707963267948966, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":6.061971664428711, "y":6.538893699645996, "heading":-2.5127963756685157, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + "targetDt":0.05 + }, + "params":{ + "waypoints":[ + {"x":{"exp":"7.740394592285156 m", "val":7.740394592285156}, "y":{"exp":"4.784609317779541 m", "val":4.784609317779541}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"6.061971664428711 m", "val":6.061971664428711}, "y":{"exp":"6.538893699645996 m", "val":6.538893699645996}, "heading":{"exp":"-2.5127963756685157 rad", "val":-2.5127963756685157}, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + "constraints":[ + {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + "targetDt":{ + "exp":"0.05 s", + "val":0.05 + } + }, + "trajectory":{ + "sampleType":"Swerve", + "waypoints":[0.0,1.23464], + "samples":[ + {"t":0.0, "x":7.74039, "y":4.78461, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-4.39722, "ay":4.60767, "alpha":-3.34929, "fx":[-91.67478,-75.18501,-56.19697,-76.12526], "fy":[60.30966,79.87288,94.2534,79.06454]}, + {"t":0.03528, "x":7.73766, "y":4.78748, "heading":-1.5708, "vx":-0.15511, "vy":0.16254, "omega":-0.11815, "ax":-4.39888, "ay":4.60889, "alpha":-3.29802, "fx":[-91.45621,-75.19481,-56.52452,-76.119], "fy":[60.62542,79.84975,94.04761,79.06054]}, + {"t":0.07055, "x":7.72945, "y":4.79608, "heading":-1.57496, "vx":-0.31029, "vy":0.32512, "omega":-0.23449, "ax":-4.40079, "ay":4.61019, "alpha":-3.23931, "fx":[-91.19464,-75.30051,-56.87767,-76.05202], "fy":[61.0012,79.73436,93.82321,79.11349]}, + {"t":0.10583, "x":7.71577, "y":4.81041, "heading":-1.58324, "vx":-0.46553, "vy":0.48774, "omega":-0.34875, "ax":-4.40299, "ay":4.61162, "alpha":-3.17159, "fx":[-90.88325,-75.4927,-57.27013,-75.9281], "fy":[61.44499,79.53452,93.57101,79.21914]}, + {"t":0.1411, "x":7.69661, "y":4.83049, "heading":-1.59554, "vx":-0.62084, "vy":0.65042, "omega":-0.46063, "ax":-4.40549, "ay":4.61322, "alpha":-3.09282, "fx":[-90.5125,-75.75947,-57.72028,-75.75202], "fy":[61.96792,79.25987,93.27851,79.37199]}, + {"t":0.17638, "x":7.67196, "y":4.8563, "heading":-1.61179, "vx":-0.77625, "vy":0.81315, "omega":-0.56973, "ax":-4.40833, "ay":4.61503, "alpha":-3.00017, "fx":[-90.0691,-76.08571,-58.2525,-75.53008], "fy":[62.58528,78.92283,92.92858,79.5648]}, + {"t":0.21165, "x":7.64184, "y":4.88786, "heading":-1.63188, "vx":-0.93175, "vy":0.97595, "omega":-0.67557, "ax":-4.41155, "ay":4.61712, "alpha":-2.88958, "fx":[-89.53451,-76.45201,-58.89946,-75.27087], "fy":[63.31789,78.53996,92.49756,79.78787]}, + {"t":0.24693, "x":7.60623, "y":4.92516, "heading":-1.65572, "vx":-1.08737, "vy":1.13882, "omega":-0.7775, "ax":-4.41523, "ay":4.61954, "alpha":-2.75508, "fx":[-88.88215,-76.83299,-59.70547,-74.98665], "fy":[64.19474,78.13381,91.95193,80.02778]}, + {"t":0.2822, "x":7.56512, "y":4.9682, "heading":-1.68314, "vx":-1.24312, "vy":1.30178, "omega":-0.87468, "ax":-4.41946, "ay":4.62238, "alpha":-2.58757, "fx":[-88.07259,-77.19479,-60.7322,-74.69558], "fy":[65.25738,77.73583,91.24271,80.26521]}, + {"t":0.31748, "x":7.51852, "y":5.017, "heading":-1.714, "vx":-1.39902, "vy":1.46483, "omega":-0.96596, "ax":-4.42437, "ay":4.62566, "alpha":-2.37278, "fx":[-87.04423,-77.49072,-62.0682,-74.42593], "fy":[66.56816,77.39077,90.29508,80.47077]}, + {"t":0.35275, "x":7.46642, "y":5.07155, "heading":-1.74807, "vx":-1.55509, "vy":1.62801, "omega":-1.04966, "ax":-4.43009, "ay":4.62935, "alpha":-2.08733, "fx":[-85.69416,-77.65353,-63.84611,-74.22432], "fy":[68.2264,77.16411,88.9883,80.59653]}, + {"t":0.38803, "x":7.4088, "y":5.13186, "heading":-1.7851, "vx":-1.71136, "vy":1.79131, "omega":-1.12329, "ax":-4.43665, "ay":4.63305, "alpha":-1.69069, "fx":[-83.83498,-77.58034,-66.27526,-74.1741], "fy":[70.40248,77.15528,87.11318,80.55665]}, + {"t":0.4233, "x":7.34567, "y":5.19793, "heading":-1.82472, "vx":-1.86787, "vy":1.95474, "omega":-1.18293, "ax":-4.44353, "ay":4.63543, "alpha":-1.10648, "fx":[-81.08354,-77.10041,-69.7075,-74.4414], "fy":[73.41727,77.52339,84.27272,80.17624]}, + {"t":0.45858, "x":7.27702, "y":5.26977, "heading":-1.86645, "vx":-2.02462, "vy":2.11826, "omega":-1.22197, "ax":-4.44761, "ay":4.63169, "alpha":-0.17161, "fx":[-76.51863,-75.89819,-74.77683,-75.41638], "fy":[77.95062,78.54229,79.61762,79.02427]}, + {"t":0.49386, "x":7.20283, "y":5.34738, "heading":-1.90956, "vx":-2.18151, "vy":2.28164, "omega":-1.22802, "ax":-4.43256, "ay":4.60101, "alpha":1.54039, "fx":[-67.3082,-73.30115,-82.68197,-78.29512], "fy":[85.65646,80.72992,71.01819,75.64285]}, + {"t":0.52913, "x":7.12312, "y":5.43072, "heading":-1.95288, "vx":-2.33787, "vy":2.44394, "omega":-1.17368, "ax":-4.29931, "ay":4.37661, "alpha":5.69984, "fx":[-40.59475,-67.58614,-95.26812,-89.07121], "fy":[100.30535,85.16282,52.05223,60.25915]}, + {"t":0.56441, "x":7.03798, "y":5.51966, "heading":-1.99428, "vx":-2.48953, "vy":2.59833, "omega":-0.97262, "ax":-3.86221, "ay":3.37396, "alpha":12.975, "fx":[1.46992,-60.3707,-102.32563,-101.55376], "fy":[106.16856,89.23546,32.5833,1.57314]}, + {"t":0.59968, "x":6.94776, "y":5.61341, "heading":-2.02859, "vx":-2.62577, "vy":2.71735, "omega":-0.51492, "ax":-0.01618, "ay":0.09252, "alpha":0.09239, "fx":[0.04605,-0.38427,-0.59634,-0.166], "fy":[1.68296,1.89485,1.46468,1.25274]}, + {"t":0.63496, "x":6.85512, "y":5.70933, "heading":-2.04675, "vx":-2.62634, "vy":2.72061, "omega":-0.51166, "ax":3.80731, "ay":-3.35795, "alpha":-13.42152, "fx":[-3.25342,58.38795,101.74157,102.16887], "fy":[-105.97819,-90.53055,-34.4909,2.52864]}, + {"t":0.67023, "x":6.76484, "y":5.80321, "heading":-2.0648, "vx":-2.49203, "vy":2.60216, "omega":-0.98511, "ax":4.33216, "ay":-4.43784, "alpha":-4.88212, "fx":[47.3847,66.40692,91.99519,88.96844], "fy":[-97.27079,-86.05501,-57.6973,-60.92258]}, + {"t":0.70551, "x":6.67963, "y":5.89224, "heading":-2.09955, "vx":-2.33922, "vy":2.44561, "omega":-1.15733, "ax":4.43799, "ay":-4.60622, "alpha":-1.2117, "fx":[69.64503,72.7109,80.77542,78.82434], "fy":[-83.77828,-81.25516,-73.20905,-75.15954]}, + {"t":0.74078, "x":6.59988, "y":5.97564, "heading":-2.14038, "vx":-2.18266, "vy":2.28313, "omega":-1.20007, "ax":4.44799, "ay":-4.63147, "alpha":0.28652, "fx":[76.93405,76.45554,74.35225,74.89429], "fy":[-77.55831,-78.00692,-80.01979,-79.53497]}, + {"t":0.77606, "x":6.52565, "y":6.0533, "heading":-2.18271, "vx":-2.02576, "vy":2.11975, "omega":-1.18996, "ax":4.44394, "ay":-4.63531, "alpha":1.11384, "fx":[80.24185,79.07386,70.46076,72.58411], "fy":[-74.3591,-75.5261,-83.63396,-81.86213]}, + {"t":0.81133, "x":6.45696, "y":6.12519, "heading":-2.22469, "vx":-1.869, "vy":1.95624, "omega":-1.15067, "ax":4.43784, "ay":-4.6339, "alpha":1.64399, "fx":[81.98643,81.07025,67.96273,70.92617], "fy":[-72.57339,-73.50343,-85.78312,-83.42518]}, + {"t":0.84661, "x":6.39379, "y":6.19132, "heading":-2.26528, "vx":-1.71245, "vy":1.79278, "omega":-1.09268, "ax":4.43195, "ay":-4.63111, "alpha":2.01519, "fx":[82.97093,82.66658,66.29937,69.6082], "fy":[-71.54248,-71.79684,-87.14916,-84.60713]}, + {"t":0.88188, "x":6.33614, "y":6.25168, "heading":-2.30382, "vx":-1.55611, "vy":1.62941, "omega":-1.02159, "ax":4.42669, "ay":-4.62814, "alpha":2.29047, "fx":[83.53682,83.97764,65.17043,68.50235], "fy":[-70.95061,-70.33175,-88.05102,-85.56018]}, + {"t":0.91716, "x":6.284, "y":6.30627, "heading":-2.33986, "vx":-1.39996, "vy":1.46615, "omega":-0.9408, "ax":4.42207, "ay":-4.62538, "alpha":2.50279, "fx":[83.85477,85.07096,64.39929,67.54782], "fy":[-70.62697,-69.06377,-88.65837,-86.35645]}, + {"t":0.95244, "x":6.23737, "y":6.35511, "heading":-2.37304, "vx":-1.24397, "vy":1.30299, "omega":-0.85251, "ax":4.41802, "ay":-4.62294, "alpha":2.67119, "fx":[84.02053,85.99062,63.87353,66.71237], "fy":[-70.47041,-67.96319,-89.07107,-87.0347]}, + {"t":0.98771, "x":6.19623, "y":6.3982, "heading":-2.40312, "vx":-1.08812, "vy":1.13991, "omega":-0.75828, "ax":4.41446, "ay":-4.62082, "alpha":2.8076, "fx":[84.09269,86.76783,63.5167,65.97744], "fy":[-70.41674,-67.008,-89.35293,-87.61784]}, + {"t":1.02299, "x":6.1606, "y":6.43554, "heading":-2.42987, "vx":-0.9324, "vy":0.97691, "omega":-0.65924, "ax":4.41132, "ay":-4.619, "alpha":2.92001, "fx":[84.10958,87.426,63.27392,65.33154], "fy":[-70.42299,-66.18065,-89.54757,-88.12057]}, + {"t":1.05826, "x":6.13045, "y":6.46713, "heading":-2.45312, "vx":-0.77679, "vy":0.81397, "omega":-0.55624, "ax":4.40854, "ay":-4.61744, "alpha":3.01405, "fx":[84.09764,87.9834,63.10413,64.7671], "fy":[-70.45914,-65.46653,-89.68644,-88.55289]}, + {"t":1.09354, "x":6.10579, "y":6.49297, "heading":-2.47274, "vx":-0.62128, "vy":0.65109, "omega":-0.44992, "ax":4.40609, "ay":-4.61607, "alpha":3.09384, "fx":[84.07583,88.45461,62.97567,64.27889], "fy":[-70.50355,-64.85318,-89.7932,-88.92195]}, + {"t":1.12881, "x":6.08662, "y":6.51306, "heading":-2.48861, "vx":-0.46585, "vy":0.48826, "omega":-0.34078, "ax":4.4039, "ay":-4.61485, "alpha":3.16251, "fx":[84.05823,88.85133,62.86359,63.86317], "fy":[-70.54019,-64.33002,-89.8861,-89.23302]}, + {"t":1.16409, "x":6.07292, "y":6.52741, "heading":-2.50063, "vx":-0.3105, "vy":0.32547, "omega":-0.22922, "ax":4.40195, "ay":-4.61376, "alpha":3.22246, "fx":[84.05549,89.18294,62.74806,63.51726], "fy":[-70.55695,-63.8882,-89.97951,-89.49003]}, + {"t":1.19936, "x":6.06471, "y":6.53602, "heading":-2.50872, "vx":-0.15522, "vy":0.16272, "omega":-0.11555, "ax":4.40021, "ay":-4.61274, "alpha":3.27558, "fx":[84.07578,89.45683,62.61327,63.23929], "fy":[-70.54449,-63.52053,-90.0847,-89.69585]}, + {"t":1.23464, "x":6.06197, "y":6.53889, "heading":-2.5128, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + "splits":[0] + }, + "events":[] +} diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index 91717e0e..fa0fb1b0 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -1876,31 +1876,34 @@ public static final LoggedAutoRoutine autoERight( CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.waitUntilAtGoal(), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), path2.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.5))) .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.waitUntilAtGoal(), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), path3.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.5))) .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.waitUntilAtGoal(), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), path4.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.5))) .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( @@ -1937,31 +1940,34 @@ public static final LoggedAutoRoutine autoELeft( CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.waitUntilAtGoal(), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), path2.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((2.0))) .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.waitUntilAtGoal(), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), path3.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.5))) .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.waitUntilAtGoal(), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), path4.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.5))) .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( @@ -1994,34 +2000,34 @@ public static final LoggedAutoRoutine autoERightBack( CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), - Commands.waitUntil(superstructure::armBelowThreshold), + superstructure.waitUntilAtGoal(), Commands.parallel( path2.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.0))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L2))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L2, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_SCORE), - Commands.waitUntil(superstructure::atGoal), + superstructure.waitUntilAtGoal(), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), path3.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.0))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L2))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L2, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_SCORE), - Commands.waitUntil(superstructure::atGoal), + superstructure.waitUntilAtGoal(), Commands.parallel( path4.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.0))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE))); @@ -2060,35 +2066,98 @@ public static final LoggedAutoRoutine autoELeftBack( CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.waitUntilAtGoal(), Commands.parallel( path2.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.0))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L2))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L2, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_SCORE), + superstructure.waitUntilAtGoal(), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), path3.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.0))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L2))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L2, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_SCORE), + superstructure.waitUntilAtGoal(), Commands.parallel( path4.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.0))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), + .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4))), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE))); return routine; } + + public static final LoggedAutoRoutine autoFLeft( + Drive drive, + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoELeftBack"); + LoggedAutoTrajectory path1 = (routine.trajectory("F_PATH_1")); + LoggedAutoTrajectory path2 = (routine.trajectory("F_PATH_2")); + LoggedAutoTrajectory path3 = (routine.trajectory("F_PATH_3")); + LoggedAutoTrajectory path4 = (routine.trajectory("F_PATH_4")); + LoggedAutoTrajectory path5 = (routine.trajectory("F_PATH_5")); + LoggedAutoTrajectory path6 = (routine.trajectory("F_PATH_6")); + LoggedAutoTrajectory path7 = (routine.trajectory("F_PATH_7")); + LoggedAutoTrajectory path8 = (routine.trajectory("F_PATH_8")); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + path1.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, ReefState.L4, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.waitUntilAtGoal(), + path2.cmd(), + CompositeCommands.V3_EpsilonCompositeCommands.intakeAlgaeFromReef( + drive, superstructure, cameras) + .withTimeout(1), + Commands.parallel( + path3.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), + Commands.runOnce(() -> drive.stop()), + CompositeCommands.V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure), + Commands.parallel( + path4.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), + CompositeCommands.V3_EpsilonCompositeCommands.intakeAlgaeFromReef( + drive, superstructure, cameras) + .withTimeout(1), + Commands.parallel( + path5.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), + Commands.runOnce(() -> drive.stop()), + CompositeCommands.V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure), + Commands.parallel( + path6.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), + CompositeCommands.V3_EpsilonCompositeCommands.intakeAlgaeFromReef( + drive, superstructure, cameras) + .withTimeout(1), + Commands.parallel( + path7.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), + Commands.runOnce(() -> drive.stop()), + CompositeCommands.V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure), + Commands.parallel( + path8.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)))); + + return routine; + } } diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index f2ccf65d..4f0500bf 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -798,7 +798,9 @@ private static final ScoreSide optimalSideBarge() { public static final Command optimalScoreBarge(V3_EpsilonSuperstructure superstructure) { return Commands.sequence( Commands.runOnce(() -> RobotState.setScoreSide(optimalSideBarge())), - superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE_SCORE)); + superstructure + .runGoalUntil(V3_EpsilonSuperstructureStates.BARGE_SCORE, () -> false) + .withTimeout(0.5)); } /** @@ -901,7 +903,13 @@ public static final Command intakeAlgaeFromReef( DriveCommands.autoAlignReefAlgae(drive, cameras)), Commands.runEnd( () -> drive.runVelocity(new ChassisSpeeds(0.0, 2.0, 0.0)), () -> drive.stop()) - .withTimeout(0.5)); + .withTimeout(0.5), + postIntakeAlgaeFromReef(drive, superstructure, cameras)); + } + + public static final Command postIntakeAlgaeFromReef( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + return superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP); } public static final Command intakeAlgaeFromReef( diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index 6850807a..748dc24d 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -342,7 +342,7 @@ public static enum ElevatorPositions { new PositionConstants( 1.3864590139769697 + Units.inchesToMeters(0.5), 1.3864590139769697 + Units.inchesToMeters(0.5), - Units.inchesToMeters(50))), + Units.inchesToMeters(53))), HIGH_STOW(new PositionConstants(0, 0, 0.5)), HANDOFF(new PositionConstants(0, 0, Units.inchesToMeters(33.25))), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 6a352e74..dafff28f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -233,7 +233,10 @@ private void configureButtonBindings() { .leftStick() .onTrue(V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence(drive, superstructure)); - driver.back().whileTrue(V3_EpsilonCompositeCommands.intakeAlgaeFromReef(drive, superstructure)); + driver + .back() + .whileTrue(V3_EpsilonCompositeCommands.intakeAlgaeFromReef(drive, superstructure)) + .whileFalse(V3_EpsilonCompositeCommands.postIntakeAlgaeFromReef(drive, superstructure)); driver .start() @@ -285,9 +288,8 @@ private void configureButtonBindings() { operator.leftBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))); operator.rightBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))); - // operator.povUp().onTrue(V3_EpsilonCompositeCommands.climb(superstructure, - // climber, drive)); fix later - // operator.povDown().whileTrue(climber.winchClimberManual()); + operator.povUp().onTrue(climber.releaseClimber()).onFalse(climber.winchClimber()); + operator.povDown().whileTrue(climber.winchClimberManual()); operator .povLeft() .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR)) @@ -329,6 +331,8 @@ private void configureAutos() { autoChooser.addRoutine( "4 Piece Left Late Madtown", () -> AutonomousCommands.autoELeftBack(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "Algae", () -> AutonomousCommands.autoFLeft(drive, superstructure, intake, manipulator)); SmartDashboard.putData("Autonomous Modes", autoChooser); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java index a0f4f600..132a35cb 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java @@ -40,6 +40,11 @@ public void periodic() { InternalLoggedTracer.record("Climber Input Processing", "Climber/Periodic"); isClimbed = io.isClimbed(); + + if (RobotState.isClimberReady()) { + io.setRollerVoltage(12); + } + ExternalLoggedTracer.record("Climber Total", "Climber/Periodic"); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index eb86a89c..113dde68 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -37,6 +37,12 @@ public enum V3_EpsilonSuperstructureStates { ReefState.STOW, ManipulatorArmState.ALGAE_INTAKE_FLOOR, IntakePivotState.INTAKE_ALGAE), SubsystemActions.empty()), + GROUND_INTAKE_CORAL( + "GROUND_INTAKE_CORAL", + new SubsystemPoses( + ReefState.STOW, ManipulatorArmState.CORAL_INTAKE_FLOOR, IntakePivotState.INTAKE_CORAL), + new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.STOP)), + GROUND_INTAKE( "GROUND_INTAKE", new SubsystemPoses( @@ -154,6 +160,18 @@ public enum V3_EpsilonSuperstructureStates { "FLIP_UP", new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), SubsystemActions.empty(), + V3_EpsilonSuperstructureTransitionCondition.MANIPULATOR_AT_GOAL), + INVERSE_FLIP_DOWN( + "INVERSE_FLIP_DOWN", + new SubsystemPoses( + ReefState.HANDOFF, ManipulatorArmState.INVERSE_FLIP_ANGLE, IntakePivotState.STOW), + SubsystemActions.empty(), + V3_EpsilonSuperstructureTransitionCondition.ELEVATOR_AT_GOAL), + INVERSE_FLIP_UP( + "FLIP_UP", + new SubsystemPoses( + ReefState.HANDOFF, ManipulatorArmState.INVERSE_FLIP_ANGLE, IntakePivotState.STOW), + SubsystemActions.empty(), V3_EpsilonSuperstructureTransitionCondition.MANIPULATOR_AT_GOAL); // Readable name for state diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index 74cb7b64..ec8ac59f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -92,7 +92,7 @@ public final class V3_EpsilonManipulatorConstants { case V3_EPSILON_SIM: EMPTY_GAINS = new Gains( - new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 50), + new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 100), new LoggedTunableNumber("Manipulator/Arm/Empty/kD", 0), new LoggedTunableNumber("Manipulator/Arm/Empty/kS", 0.24274), new LoggedTunableNumber("Manipulator/Arm/Empty/kG", 0.66177), @@ -116,7 +116,7 @@ public final class V3_EpsilonManipulatorConstants { new LoggedTunableNumber("Manipulator/ArmWithAlgae/kA", 0.0)); CONSTRAINTS = new Constraints( - new LoggedTunableNumber("Manipulator/Arm/MaxAcceleration", 20.0), + new LoggedTunableNumber("Manipulator/Arm/MaxAcceleration", 100.0), new LoggedTunableNumber("Manipulator/Arm/CruisingVelocity", 50.0), new LoggedTunableNumber( "Manipulator/Arm/GoalTolerance", Units.degreesToRadians(3))); @@ -208,6 +208,7 @@ public static enum ManipulatorArmState { SCORE_L4(Rotation2d.kPi), PROCESSOR(Rotation2d.fromDegrees(90)), ALGAE_INTAKE_FLOOR(Rotation2d.fromDegrees(90)), + CORAL_INTAKE_FLOOR(Rotation2d.fromDegrees(-99)), REEF_INTAKE(Rotation2d.fromDegrees(90)), INTAKE_OUT_LINE(Rotation2d.fromDegrees(61)), FLOOR_INTAKE(Rotation2d.fromDegrees(73.5)), @@ -218,6 +219,7 @@ public static enum ManipulatorArmState { HANDOFF(Rotation2d.kPi), SAFE_ANGLE(Rotation2d.fromDegrees(150)), FLIP_ANGLE(Rotation2d.fromDegrees(135)), + INVERSE_FLIP_ANGLE(Rotation2d.fromDegrees(135).unaryMinus()), EMERGENCY_EJECT_ANGLE( Rotation2d.fromDegrees(90)); // Idk if tested. Looks fine but double check. From a6d29177f11d2c0a955c0c3e6702c0779656bee5 Mon Sep 17 00:00:00 2001 From: Luke Maxwell <24lbmaxwell@protonmail.com> Date: Thu, 23 Oct 2025 22:54:17 -0400 Subject: [PATCH 143/180] negative trajectory --- src/main/deploy/choreo/F_PATH_1.traj | 46 +++++------ src/main/deploy/choreo/F_PATH_2.traj | 34 ++++----- src/main/deploy/choreo/F_PATH_3.traj | 92 +++++++++++----------- src/main/deploy/choreo/F_PATH_4.traj | 89 +++++++++++----------- src/main/deploy/choreo/F_PATH_5.traj | 94 +++++++++++------------ src/main/deploy/choreo/F_PATH_6.traj | 110 +++++++++++++-------------- src/main/deploy/choreo/F_PATH_7.traj | 98 ++++++++++++------------ src/main/deploy/choreo/F_PATH_8.traj | 82 ++++++++++---------- 8 files changed, 323 insertions(+), 322 deletions(-) diff --git a/src/main/deploy/choreo/F_PATH_1.traj b/src/main/deploy/choreo/F_PATH_1.traj index f91dc86d..a541a42c 100644 --- a/src/main/deploy/choreo/F_PATH_1.traj +++ b/src/main/deploy/choreo/F_PATH_1.traj @@ -3,8 +3,8 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":7.152472496032715, "y":4.007034778594971, "heading":1.5707963267948966, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":6.099902153015137, "y":4.149273872375488, "heading":1.5656151542552748, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":7.152472496032715, "y":4.007034778594971, "heading":4.71238898038469, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":6.099902153015137, "y":4.149273872375488, "heading":4.71238898038469, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -13,8 +13,8 @@ }, "params":{ "waypoints":[ - {"x":{"exp":"7.152472496032715 m", "val":7.152472496032715}, "y":{"exp":"4.007034778594971 m", "val":4.007034778594971}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"6.099902153015137 m", "val":6.099902153015137}, "y":{"exp":"4.149273872375488 m", "val":4.149273872375488}, "heading":{"exp":"1.5656151542552748 rad", "val":1.5656151542552748}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"7.152472496032715 m", "val":7.152472496032715}, "y":{"exp":"4.007034778594971 m", "val":4.007034778594971}, "heading":{"exp":"270 deg", "val":4.71238898038469}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"6.099902153015137 m", "val":6.099902153015137}, "y":{"exp":"4.149273872375488 m", "val":4.149273872375488}, "heading":{"exp":"270 deg", "val":4.71238898038469}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -26,26 +26,26 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,0.8131], + "waypoints":[0.0,0.81309], "samples":[ - {"t":0.0, "x":7.15247, "y":4.00703, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.39488, "ay":0.86417, "alpha":-0.03147, "fx":[-108.75032,-108.75658,-108.79974,-108.79373], "fy":[14.88148,14.83775,14.51762,14.56044]}, - {"t":0.04783, "x":7.14516, "y":4.00802, "heading":1.5708, "vx":-0.30586, "vy":0.04133, "omega":-0.00151, "ax":-6.39407, "ay":0.86406, "alpha":-0.03146, "fx":[-108.73656,-108.74287,-108.78601,-108.77996], "fy":[14.87958,14.83586,14.5158,14.55861]}, - {"t":0.09566, "x":7.12322, "y":4.01099, "heading":1.57072, "vx":-0.61168, "vy":0.08266, "omega":-0.00301, "ax":-6.393, "ay":0.86392, "alpha":-0.03146, "fx":[-108.71822,-108.72457,-108.7677,-108.7616], "fy":[14.87704,14.83336,14.51339,14.55616]}, - {"t":0.14349, "x":7.08665, "y":4.01593, "heading":1.57058, "vx":-0.91746, "vy":0.12398, "omega":-0.00451, "ax":-6.39149, "ay":0.86371, "alpha":-0.03146, "fx":[-108.69255,-108.69896,-108.74206,-108.7359], "fy":[14.87349,14.82988,14.51001,14.55271]}, - {"t":0.19132, "x":7.03545, "y":4.02285, "heading":1.57036, "vx":-1.22315, "vy":0.16529, "omega":-0.00602, "ax":-6.38923, "ay":0.86341, "alpha":-0.03145, "fx":[-108.65404,-108.66056,-108.70363,-108.69736], "fy":[14.86816,14.82466,14.50494,14.54754]}, - {"t":0.23915, "x":6.96964, "y":4.03174, "heading":1.57008, "vx":-1.52875, "vy":0.20659, "omega":-0.00752, "ax":-6.38546, "ay":0.8629, "alpha":-0.03144, "fx":[-108.5899,-108.59659,-108.63959,-108.63315], "fy":[14.8593,14.81595,14.49648,14.53892]}, - {"t":0.28697, "x":6.88922, "y":4.04261, "heading":1.56972, "vx":-1.83416, "vy":0.24786, "omega":-0.00903, "ax":-6.37793, "ay":0.86188, "alpha":-0.03143, "fx":[-108.4617,-108.46875,-108.51164,-108.50485], "fy":[14.84165,14.79853,14.47951,14.52172]}, - {"t":0.3348, "x":6.7942, "y":4.05545, "heading":1.56928, "vx":-2.13921, "vy":0.28908, "omega":-0.01053, "ax":-6.35539, "ay":0.85884, "alpha":-0.03142, "fx":[-108.078,-108.08612,-108.1287,-108.12082], "fy":[14.78901,14.74635,14.42855,14.47031]}, - {"t":0.38263, "x":6.68461, "y":4.07026, "heading":1.56878, "vx":-2.44318, "vy":0.33016, "omega":-0.01203, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, - {"t":0.43046, "x":6.56776, "y":4.08605, "heading":1.56821, "vx":-2.44318, "vy":0.33016, "omega":-0.01203, "ax":6.35539, "ay":-0.85884, "alpha":0.03142, "fx":[108.07802,108.08609,108.12868,108.12085], "fy":[-14.78886,-14.74655,-14.4287,-14.47011]}, - {"t":0.47829, "x":6.45817, "y":4.10086, "heading":1.56763, "vx":-2.13921, "vy":0.28908, "omega":-0.01053, "ax":6.37793, "ay":-0.86188, "alpha":0.03143, "fx":[108.46174,108.46869,108.5116,108.5049], "fy":[-14.84136,-14.79891,-14.4798,-14.52135]}, - {"t":0.52612, "x":6.36315, "y":4.1137, "heading":1.56713, "vx":-1.83416, "vy":0.24786, "omega":-0.00903, "ax":6.38546, "ay":-0.8629, "alpha":0.03144, "fx":[108.58995,108.59651,108.63954,108.63322], "fy":[-14.85889,-14.81648,-14.49689,-14.53839]}, - {"t":0.57395, "x":6.28273, "y":4.12457, "heading":1.56669, "vx":-1.52875, "vy":0.20659, "omega":-0.00752, "ax":6.38923, "ay":-0.86341, "alpha":0.03145, "fx":[108.65411,108.66047,108.70356,108.69745], "fy":[-14.86765,-14.82532,-14.50545,-14.54687]}, - {"t":0.62178, "x":6.21692, "y":4.13346, "heading":1.56633, "vx":-1.22315, "vy":0.16529, "omega":-0.00602, "ax":6.39149, "ay":-0.86371, "alpha":0.03146, "fx":[108.69262,108.69886,108.74199,108.736], "fy":[-14.8729,-14.83065,-14.5106,-14.55194]}, - {"t":0.66961, "x":6.16573, "y":4.14038, "heading":1.56605, "vx":-0.91746, "vy":0.12398, "omega":-0.00451, "ax":6.393, "ay":-0.86392, "alpha":0.03146, "fx":[108.71831,108.72446,108.76761,108.76171], "fy":[-14.87639,-14.83421,-14.51404,-14.55531]}, - {"t":0.71744, "x":6.12916, "y":4.14532, "heading":1.56583, "vx":-0.61168, "vy":0.08266, "omega":-0.00301, "ax":6.39407, "ay":-0.86406, "alpha":0.03146, "fx":[108.73665,108.74274,108.78592,108.78008], "fy":[-14.87889,-14.83676,-14.51649,-14.55771]}, - {"t":0.76527, "x":6.10722, "y":4.14829, "heading":1.56569, "vx":-0.30586, "vy":0.04133, "omega":-0.00151, "ax":6.39488, "ay":-0.86417, "alpha":0.03147, "fx":[108.75042,108.75646,108.79965,108.79385], "fy":[-14.88077,-14.83867,-14.51833,-14.55951]}, - {"t":0.8131, "x":6.0999, "y":4.14927, "heading":1.56562, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":7.15247, "y":4.00703, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.39489, "ay":0.86417, "alpha":0.0, "fx":[-108.77521,-108.77521,-108.77521,-108.77521], "fy":[14.69934,14.69934,14.69934,14.69934]}, + {"t":0.04783, "x":7.14516, "y":4.00802, "heading":-1.5708, "vx":-0.30586, "vy":0.04133, "omega":0.0, "ax":-6.39408, "ay":0.86406, "alpha":0.0, "fx":[-108.76147,-108.76147,-108.76147,-108.76147], "fy":[14.69748,14.69748,14.69748,14.69748]}, + {"t":0.09566, "x":7.12322, "y":4.01099, "heading":-1.5708, "vx":-0.61168, "vy":0.08266, "omega":0.0, "ax":-6.393, "ay":0.86392, "alpha":0.0, "fx":[-108.74314,-108.74314,-108.74314,-108.74314], "fy":[14.695,14.695,14.695,14.695]}, + {"t":0.14349, "x":7.08665, "y":4.01593, "heading":-1.5708, "vx":-0.91746, "vy":0.12398, "omega":0.0, "ax":-6.39149, "ay":0.86371, "alpha":0.0, "fx":[-108.71749,-108.71749,-108.71749,-108.71749], "fy":[14.69154,14.69154,14.69154,14.69154]}, + {"t":0.19132, "x":7.03545, "y":4.02285, "heading":-1.5708, "vx":-1.22316, "vy":0.16529, "omega":0.0, "ax":-6.38923, "ay":0.86341, "alpha":0.0, "fx":[-108.67902,-108.67902,-108.67902,-108.67902], "fy":[14.68634,14.68634,14.68634,14.68634]}, + {"t":0.23915, "x":6.96964, "y":4.03174, "heading":-1.5708, "vx":-1.52875, "vy":0.20659, "omega":0.0, "ax":-6.38546, "ay":0.8629, "alpha":0.0, "fx":[-108.61493,-108.61493,-108.61493,-108.61493], "fy":[14.67768,14.67768,14.67768,14.67768]}, + {"t":0.28697, "x":6.88922, "y":4.04261, "heading":-1.5708, "vx":-1.83416, "vy":0.24786, "omega":0.0, "ax":-6.37794, "ay":0.86188, "alpha":0.0, "fx":[-108.48685,-108.48685,-108.48685,-108.48685], "fy":[14.66037,14.66037,14.66037,14.66037]}, + {"t":0.3348, "x":6.7942, "y":4.05545, "heading":-1.5708, "vx":-2.13921, "vy":0.28908, "omega":0.0, "ax":-6.3554, "ay":0.85884, "alpha":0.0, "fx":[-108.10353,-108.10353,-108.10353,-108.10353], "fy":[14.60857,14.60857,14.60857,14.60857]}, + {"t":0.38263, "x":6.68461, "y":4.07026, "heading":-1.5708, "vx":-2.44318, "vy":0.33016, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.43046, "x":6.56776, "y":4.08605, "heading":-1.5708, "vx":-2.44318, "vy":0.33016, "omega":0.0, "ax":6.3554, "ay":-0.85884, "alpha":0.0, "fx":[108.10353,108.10353,108.10353,108.10353], "fy":[-14.60857,-14.60857,-14.60857,-14.60857]}, + {"t":0.47829, "x":6.45817, "y":4.10086, "heading":-1.5708, "vx":-2.13921, "vy":0.28908, "omega":0.0, "ax":6.37794, "ay":-0.86188, "alpha":0.0, "fx":[108.48685,108.48685,108.48685,108.48685], "fy":[-14.66037,-14.66037,-14.66037,-14.66037]}, + {"t":0.52612, "x":6.36315, "y":4.1137, "heading":-1.5708, "vx":-1.83416, "vy":0.24786, "omega":0.0, "ax":6.38546, "ay":-0.8629, "alpha":0.0, "fx":[108.61493,108.61493,108.61493,108.61493], "fy":[-14.67768,-14.67768,-14.67768,-14.67768]}, + {"t":0.57395, "x":6.28273, "y":4.12457, "heading":-1.5708, "vx":-1.52875, "vy":0.20659, "omega":0.0, "ax":6.38923, "ay":-0.86341, "alpha":0.0, "fx":[108.67902,108.67902,108.67902,108.67902], "fy":[-14.68634,-14.68634,-14.68634,-14.68634]}, + {"t":0.62178, "x":6.21692, "y":4.13346, "heading":-1.5708, "vx":-1.22316, "vy":0.16529, "omega":0.0, "ax":6.39149, "ay":-0.86371, "alpha":0.0, "fx":[108.71749,108.71749,108.71749,108.71749], "fy":[-14.69154,-14.69154,-14.69154,-14.69154]}, + {"t":0.66961, "x":6.16573, "y":4.14038, "heading":-1.5708, "vx":-0.91746, "vy":0.12398, "omega":0.0, "ax":6.393, "ay":-0.86392, "alpha":0.0, "fx":[108.74314,108.74314,108.74314,108.74314], "fy":[-14.695,-14.695,-14.695,-14.695]}, + {"t":0.71744, "x":6.12916, "y":4.14532, "heading":-1.5708, "vx":-0.61168, "vy":0.08266, "omega":0.0, "ax":6.39408, "ay":-0.86406, "alpha":0.0, "fx":[108.76147,108.76147,108.76147,108.76147], "fy":[-14.69748,-14.69748,-14.69748,-14.69748]}, + {"t":0.76527, "x":6.10722, "y":4.14829, "heading":-1.5708, "vx":-0.30586, "vy":0.04133, "omega":0.0, "ax":6.39489, "ay":-0.86417, "alpha":0.0, "fx":[108.77521,108.77521,108.77521,108.77521], "fy":[-14.69934,-14.69934,-14.69934,-14.69934]}, + {"t":0.81309, "x":6.0999, "y":4.14927, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/F_PATH_2.traj b/src/main/deploy/choreo/F_PATH_2.traj index e4a800d6..c38c49f0 100644 --- a/src/main/deploy/choreo/F_PATH_2.traj +++ b/src/main/deploy/choreo/F_PATH_2.traj @@ -3,8 +3,8 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":6.099902153015137, "y":4.149273872375488, "heading":1.5656151542552748, "intervals":12, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":6.555067539215088, "y":3.969104051589966, "heading":1.5707963267948966, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":6.099902153015137, "y":4.149273872375488, "heading":4.71238898038469, "intervals":12, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":6.555067539215088, "y":3.969104051589966, "heading":4.71238898038469, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -13,8 +13,8 @@ }, "params":{ "waypoints":[ - {"x":{"exp":"6.099902153015137 m", "val":6.099902153015137}, "y":{"exp":"4.149273872375488 m", "val":4.149273872375488}, "heading":{"exp":"1.5656151542552748 rad", "val":1.5656151542552748}, "intervals":12, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"6.555067539215088 m", "val":6.555067539215088}, "y":{"exp":"3.969104051589966 m", "val":3.969104051589966}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"6.099902153015137 m", "val":6.099902153015137}, "y":{"exp":"4.149273872375488 m", "val":4.149273872375488}, "heading":{"exp":"270 deg", "val":4.71238898038469}, "intervals":12, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"6.555067539215088 m", "val":6.555067539215088}, "y":{"exp":"3.969104051589966 m", "val":3.969104051589966}, "heading":{"exp":"270 deg", "val":4.71238898038469}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -28,19 +28,19 @@ "sampleType":"Swerve", "waypoints":[0.0,0.55109], "samples":[ - {"t":0.0, "x":6.0999, "y":4.14927, "heading":1.56562, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.99964, "ay":-2.37486, "alpha":0.06825, "fx":[101.88256,101.97912,102.22032,102.12643], "fy":[-40.82242,-40.58229,-39.97019,-40.20777]}, - {"t":0.04592, "x":6.10623, "y":4.14677, "heading":1.56562, "vx":0.27553, "vy":-0.10906, "omega":0.00313, "ax":5.99837, "ay":-2.37436, "alpha":0.06824, "fx":[101.86105,101.95771,102.1988,102.1048], "fy":[-40.81378,-40.57376,-39.96179,-40.19926]}, - {"t":0.09185, "x":6.12521, "y":4.13926, "heading":1.56576, "vx":0.551, "vy":-0.2181, "omega":0.00627, "ax":5.99638, "ay":-2.37357, "alpha":0.06824, "fx":[101.82724,101.9241,102.16501,102.07081], "fy":[-40.80025,-40.56031,-39.94857,-40.18596]}, - {"t":0.13777, "x":6.15684, "y":4.12674, "heading":1.56605, "vx":0.82638, "vy":-0.32711, "omega":0.0094, "ax":5.99281, "ay":-2.37216, "alpha":0.06824, "fx":[101.7664,101.86364,102.10422,102.00964], "fy":[-40.77591,-40.53609,-39.92477,-40.16203]}, - {"t":0.1837, "x":6.20111, "y":4.10921, "heading":1.56648, "vx":1.10159, "vy":-0.43605, "omega":0.01254, "ax":5.98448, "ay":-2.36886, "alpha":0.06823, "fx":[101.6246,101.72265,101.96251,101.86711], "fy":[-40.71915,-40.47976,-39.8693,-40.10614]}, - {"t":0.22962, "x":6.25801, "y":4.08669, "heading":1.56705, "vx":1.37643, "vy":-0.54484, "omega":0.01567, "ax":5.94298, "ay":-2.35243, "alpha":0.06822, "fx":[100.91864,101.02034,101.25682,101.15771], "fy":[-40.43635,-40.19998,-39.59329,-39.82715]}, - {"t":0.27555, "x":6.32748, "y":4.05919, "heading":1.56777, "vx":1.64935, "vy":-0.65287, "omega":0.0188, "ax":-5.94298, "ay":2.35243, "alpha":-0.06822, "fx":[-100.91859,-101.02046,-101.25687,-101.15759], "fy":[40.43648,40.19967,39.59315,39.82746]}, - {"t":0.32147, "x":6.39696, "y":4.03169, "heading":1.56864, "vx":1.37643, "vy":-0.54484, "omega":0.01567, "ax":-5.98448, "ay":2.36886, "alpha":-0.06823, "fx":[-101.62445,-101.72301,-101.96267,-101.86675], "fy":[40.71955,40.47885,39.86889,40.10707]}, - {"t":0.36739, "x":6.45386, "y":4.00916, "heading":1.56936, "vx":1.10159, "vy":-0.43605, "omega":0.01254, "ax":-5.99281, "ay":2.37216, "alpha":-0.06824, "fx":[-101.76616,-101.8642,-102.10446,-102.00909], "fy":[40.77652,40.53469,39.92414,40.16345]}, - {"t":0.41332, "x":6.49813, "y":3.99164, "heading":1.56993, "vx":0.82638, "vy":-0.32711, "omega":0.0094, "ax":-5.99638, "ay":2.37357, "alpha":-0.06824, "fx":[-101.82693,-101.92481,-102.16531,-102.0701], "fy":[40.80102,40.55854,39.94779,40.18775]}, - {"t":0.45924, "x":6.52976, "y":3.97912, "heading":1.57036, "vx":0.551, "vy":-0.2181, "omega":0.00627, "ax":-5.99837, "ay":2.37436, "alpha":-0.06824, "fx":[-101.8607,-101.95851,-102.19915,-102.104], "fy":[40.81466,40.57175,39.9609,40.2013]}, - {"t":0.50517, "x":6.54874, "y":3.97161, "heading":1.57065, "vx":0.27553, "vy":-0.10906, "omega":0.00313, "ax":-5.99964, "ay":2.37486, "alpha":-0.06825, "fx":[-101.88219,-101.97997,-102.22069,-102.12558], "fy":[40.82335,40.58015,39.96924,40.20992]}, - {"t":0.55109, "x":6.55507, "y":3.9691, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":6.0999, "y":4.14927, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.99967, "ay":-2.37487, "alpha":0.0, "fx":[102.05264,102.05264,102.05264,102.05264], "fy":[-40.39588,-40.39588,-40.39588,-40.39588]}, + {"t":0.04592, "x":6.10623, "y":4.14677, "heading":-1.5708, "vx":0.27553, "vy":-0.10906, "omega":0.0, "ax":5.9984, "ay":-2.37437, "alpha":0.0, "fx":[102.03112,102.03112,102.03112,102.03112], "fy":[-40.38736,-40.38736,-40.38736,-40.38736]}, + {"t":0.09185, "x":6.12521, "y":4.13926, "heading":-1.5708, "vx":0.551, "vy":-0.2181, "omega":0.0, "ax":5.99642, "ay":-2.37358, "alpha":0.0, "fx":[101.99732,101.99732,101.99732,101.99732], "fy":[-40.37398,-40.37398,-40.37398,-40.37398]}, + {"t":0.13777, "x":6.15684, "y":4.12674, "heading":-1.5708, "vx":0.82638, "vy":-0.32711, "omega":0.0, "ax":5.99284, "ay":-2.37217, "alpha":0.0, "fx":[101.93651,101.93651,101.93651,101.93651], "fy":[-40.34991,-40.34991,-40.34991,-40.34991]}, + {"t":0.1837, "x":6.20111, "y":4.10921, "heading":-1.5708, "vx":1.1016, "vy":-0.43605, "omega":0.0, "ax":5.98451, "ay":-2.36887, "alpha":0.0, "fx":[101.79475,101.79475,101.79475,101.79475], "fy":[-40.2938,-40.2938,-40.2938,-40.2938]}, + {"t":0.22962, "x":6.25801, "y":4.08669, "heading":-1.5708, "vx":1.37643, "vy":-0.54484, "omega":0.0, "ax":5.94301, "ay":-2.35244, "alpha":0.0, "fx":[101.08891,101.08891,101.08891,101.08891], "fy":[-40.0144,-40.0144,-40.0144,-40.0144]}, + {"t":0.27554, "x":6.32748, "y":4.05919, "heading":-1.5708, "vx":1.64936, "vy":-0.65287, "omega":0.0, "ax":-5.94301, "ay":2.35244, "alpha":0.0, "fx":[-101.08891,-101.08891,-101.08891,-101.08891], "fy":[40.0144,40.0144,40.0144,40.0144]}, + {"t":0.32147, "x":6.39696, "y":4.03169, "heading":-1.5708, "vx":1.37643, "vy":-0.54484, "omega":0.0, "ax":-5.98451, "ay":2.36887, "alpha":0.0, "fx":[-101.79475,-101.79475,-101.79475,-101.79475], "fy":[40.2938,40.2938,40.2938,40.2938]}, + {"t":0.36739, "x":6.45386, "y":4.00916, "heading":-1.5708, "vx":1.1016, "vy":-0.43605, "omega":0.0, "ax":-5.99284, "ay":2.37217, "alpha":0.0, "fx":[-101.93651,-101.93651,-101.93651,-101.93651], "fy":[40.34991,40.34991,40.34991,40.34991]}, + {"t":0.41332, "x":6.49813, "y":3.99164, "heading":-1.5708, "vx":0.82638, "vy":-0.32711, "omega":0.0, "ax":-5.99642, "ay":2.37358, "alpha":0.0, "fx":[-101.99732,-101.99732,-101.99732,-101.99732], "fy":[40.37398,40.37398,40.37398,40.37398]}, + {"t":0.45924, "x":6.52976, "y":3.97912, "heading":-1.5708, "vx":0.551, "vy":-0.2181, "omega":0.0, "ax":-5.9984, "ay":2.37437, "alpha":0.0, "fx":[-102.03112,-102.03112,-102.03112,-102.03112], "fy":[40.38736,40.38736,40.38736,40.38736]}, + {"t":0.50517, "x":6.54874, "y":3.97161, "heading":-1.5708, "vx":0.27553, "vy":-0.10906, "omega":0.0, "ax":-5.99967, "ay":2.37487, "alpha":0.0, "fx":[-102.05264,-102.05264,-102.05264,-102.05264], "fy":[40.39588,40.39588,40.39588,40.39588]}, + {"t":0.55109, "x":6.55507, "y":3.9691, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/F_PATH_3.traj b/src/main/deploy/choreo/F_PATH_3.traj index 254c24e9..54a99f41 100644 --- a/src/main/deploy/choreo/F_PATH_3.traj +++ b/src/main/deploy/choreo/F_PATH_3.traj @@ -3,8 +3,8 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":5.948180198669434, "y":4.026000022888184, "heading":1.5656151542552748, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":7.664534091949463, "y":4.822539806365967, "heading":-1.5707963267948966, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":5.948180198669434, "y":4.026000022888184, "heading":4.71238898038469, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":7.664534091949463, "y":4.822539806365967, "heading":1.5707963267948966, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -13,8 +13,8 @@ }, "params":{ "waypoints":[ - {"x":{"exp":"5.948180198669434 m", "val":5.948180198669434}, "y":{"exp":"4.026000022888184 m", "val":4.026000022888184}, "heading":{"exp":"1.5656151542552748 rad", "val":1.5656151542552748}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"7.664534091949463 m", "val":7.664534091949463}, "y":{"exp":"4.822539806365967 m", "val":4.822539806365967}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"5.948180198669434 m", "val":5.948180198669434}, "y":{"exp":"4.026000022888184 m", "val":4.026000022888184}, "heading":{"exp":"270 deg", "val":4.71238898038469}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"7.664534091949463 m", "val":7.664534091949463}, "y":{"exp":"4.822539806365967 m", "val":4.822539806365967}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -26,49 +26,49 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,1.17407], + "waypoints":[0.0,1.17692], "samples":[ - {"t":0.0, "x":5.94818, "y":4.026, "heading":1.56562, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.04993, "ay":2.20393, "alpha":-11.50228, "fx":[89.29942,36.1142,108.50929,109.66883], "fy":[63.81818,103.58191,-13.61321,-3.83416]}, - {"t":0.02935, "x":5.95036, "y":4.02695, "heading":1.56562, "vx":0.14822, "vy":0.06469, "omega":-0.33761, "ax":5.05391, "ay":2.21116, "alpha":-11.45481, "fx":[89.31821,36.33746,108.54205,109.66433], "fy":[63.78033,103.49236,-13.10256,-3.72518]}, - {"t":0.0587, "x":5.95688, "y":4.0298, "heading":1.55571, "vx":0.29657, "vy":0.12959, "omega":-0.67383, "ax":5.07214, "ay":2.23435, "alpha":-11.25022, "fx":[89.61741,37.06634,108.77103,109.64765], "fy":[63.34587,103.22152,-10.62989,-3.91491]}, - {"t":0.08806, "x":5.96777, "y":4.03457, "heading":1.53593, "vx":0.44544, "vy":0.19517, "omega":-1.00404, "ax":5.10279, "ay":2.27662, "alpha":-10.8889, "fx":[90.18776,38.31069,109.07161,109.61803], "fy":[62.51543,102.75333,-5.99808,-4.37219]}, - {"t":0.11741, "x":5.98305, "y":4.04128, "heading":1.50646, "vx":0.59522, "vy":0.262, "omega":-1.32365, "ax":5.14148, "ay":2.34254, "alpha":-10.38245, "fx":[91.00849,40.07153,109.16646,109.5739], "fy":[61.29558,102.06547,1.06727,-5.04476]}, - {"t":0.14676, "x":6.00273, "y":4.04998, "heading":1.46761, "vx":0.74613, "vy":0.33075, "omega":-1.62839, "ax":5.18042, "ay":2.43554, "alpha":-9.76857, "fx":[92.04762,42.3396,108.56799,109.51456], "fy":[59.70055,101.12978,10.73699,-5.85598]}, - {"t":0.17611, "x":6.02686, "y":4.06073, "heading":1.41981, "vx":0.89818, "vy":0.40224, "omega":-1.91512, "ax":5.20911, "ay":2.55327, "alpha":-9.12487, "fx":[93.2631,45.09645,106.61982,109.44228], "fy":[57.75406,99.91227,22.75453,-6.69916]}, - {"t":0.20546, "x":6.05547, "y":4.07364, "heading":1.3636, "vx":1.05108, "vy":0.47718, "omega":-2.18295, "ax":5.21889, "ay":2.68281, "alpha":-8.56005, "fx":[94.60488,48.3208,102.79714,109.36469], "fy":[55.49091,98.37063,36.10031,-7.42644]}, - {"t":0.23481, "x":6.08857, "y":4.0888, "heading":1.29952, "vx":1.20426, "vy":0.55593, "omega":-2.4342, "ax":5.21094, "ay":2.80168, "alpha":-8.16095, "fx":[96.01712,52.00147,97.23116,109.29686], "fy":[52.95899,96.44657,49.04298,-7.82567]}, - {"t":0.26417, "x":6.12616, "y":4.10632, "heading":1.22808, "vx":1.35721, "vy":0.63816, "omega":-2.67374, "ax":5.2003, "ay":2.88816, "alpha":-7.92142, "fx":[97.43863,56.15552,90.96748,109.26115], "fy":[50.22497,94.04989,59.80611,-7.5742]}, - {"t":0.29352, "x":6.16824, "y":4.1263, "heading":1.1496, "vx":1.50985, "vy":0.72293, "omega":-2.90625, "ax":5.20999, "ay":2.933, "alpha":-7.71842, "fx":[98.79787,60.85087,85.5556,109.27726], "fy":[47.39224,91.02791,67.28541,-6.14768]}, - {"t":0.32287, "x":6.2148, "y":4.14878, "heading":1.06429, "vx":1.66277, "vy":0.80902, "omega":-3.1328, "ax":5.26094, "ay":2.94233, "alpha":-7.33941, "fx":[99.99573,66.2424,82.39621,109.31387], "fy":[44.64975,87.10061,71.08359,-2.64085]}, - {"t":0.35222, "x":6.26587, "y":4.1738, "heading":0.97234, "vx":1.81719, "vy":0.89539, "omega":-3.34822, "ax":5.36561, "ay":2.93377, "alpha":-6.49134, "fx":[100.85596,72.65649,82.4608,109.097], "fy":[42.40428,81.68935,70.94934,4.56748]}, - {"t":0.38157, "x":6.32152, "y":4.20134, "heading":0.87407, "vx":1.97468, "vy":0.9815, "omega":-3.53875, "ax":5.51965, "ay":2.93006, "alpha":-4.73915, "fx":[100.94565,80.83353,86.34847,107.42317], "fy":[41.70048,73.3376,66.05142,18.26855]}, - {"t":0.41092, "x":6.38186, "y":4.23141, "heading":0.7702, "vx":2.13669, "vy":1.0675, "omega":-3.67785, "ax":5.66759, "ay":2.92477, "alpha":-1.33707, "fx":[98.54544,92.62118,94.14191,100.30756], "fy":[46.08182,56.99487,54.15304,41.76815]}, - {"t":0.44028, "x":6.44701, "y":4.264, "heading":0.66225, "vx":2.30304, "vy":1.15335, "omega":-3.7171, "ax":5.44266, "ay":2.68523, "alpha":6.34576, "fx":[77.44198,107.48337,103.82829,81.55845], "fy":[74.10161,5.91686,31.34088,71.34037]}, - {"t":0.46963, "x":6.51696, "y":4.29901, "heading":0.55314, "vx":2.4628, "vy":1.23216, "omega":-3.53084, "ax":5.34374, "ay":1.78709, "alpha":9.92952, "fx":[70.50771,101.00645,107.44849,84.61961], "fy":[77.83103,-34.14337,11.07203,66.83203]}, - {"t":0.49898, "x":6.59155, "y":4.33595, "heading":0.44951, "vx":2.61964, "vy":1.28462, "omega":-3.23939, "ax":4.16153, "ay":1.35994, "alpha":17.20536, "fx":[19.35652,75.68844,107.08592,81.01482], "fy":[99.14027,-72.14782,-4.23759,69.77372]}, - {"t":0.52833, "x":6.67023, "y":4.37424, "heading":0.35442, "vx":2.74179, "vy":1.32453, "omega":-2.73438, "ax":4.25946, "ay":1.2705, "alpha":15.46784, "fx":[28.66001,75.09962,104.0836,81.96579], "fy":[90.97166,-62.91522,-5.67269,64.05986]}, - {"t":0.55768, "x":6.75254, "y":4.41367, "heading":0.27417, "vx":2.86681, "vy":1.36182, "omega":-2.28038, "ax":0.62332, "ay":-1.9921, "alpha":1.1002, "fx":[6.84392,8.29786,14.25882,13.00914], "fy":[-32.30251,-37.20861,-35.49527,-30.53353]}, - {"t":0.58703, "x":6.83695, "y":4.45278, "heading":0.20723, "vx":2.88511, "vy":1.30335, "omega":-2.24808, "ax":-4.61706, "ay":-2.16267, "alpha":-11.16979, "fx":[-38.01698,-91.91795,-103.19774,-81.007], "fy":[-91.97577,16.89943,-6.77506,-65.29444]}, - {"t":0.61639, "x":6.91965, "y":4.4901, "heading":0.14125, "vx":2.74959, "vy":1.23987, "omega":-2.57594, "ax":-4.93279, "ay":-2.06072, "alpha":-11.22969, "fx":[-43.79061,-98.98632,-106.53768,-86.30654], "fy":[-95.06755,20.06161,-2.09126,-63.11211]}, - {"t":0.64574, "x":6.99823, "y":4.52561, "heading":0.06564, "vx":2.60481, "vy":1.17939, "omega":-2.90555, "ax":-5.05136, "ay":-1.98798, "alpha":-11.16628, "fx":[-45.46054,-101.41342,-107.58571,-89.22932], "fy":[-96.32552,19.61618,2.13117,-60.68169]}, - {"t":0.67509, "x":7.07251, "y":4.55937, "heading":-0.01964, "vx":2.45654, "vy":1.12104, "omega":-3.2333, "ax":-5.08871, "ay":-1.90586, "alpha":-11.2563, "fx":[-44.6367,-102.26016,-107.87882,-91.45411], "fy":[-97.75806,19.02655,7.27379,-58.21498]}, - {"t":0.70444, "x":7.14242, "y":4.59145, "heading":-0.11455, "vx":2.30718, "vy":1.0651, "omega":-3.56369, "ax":-5.06354, "ay":-1.79668, "alpha":-11.55704, "fx":[-41.80883,-101.79263,-107.50949,-93.40645], "fy":[-99.63973,18.96819,14.05711,-55.6299]}, - {"t":0.73379, "x":7.20796, "y":4.62194, "heading":-0.21915, "vx":2.15855, "vy":1.01236, "omega":-3.90291, "ax":-4.96676, "ay":-1.68497, "alpha":-12.00667, "fx":[-37.80356,-98.63933,-106.16005,-95.32957], "fy":[-101.6634,16.76198,22.955,-52.69689]}, - {"t":0.76314, "x":7.26918, "y":4.65093, "heading":-0.3337, "vx":2.01277, "vy":0.96291, "omega":-4.25532, "ax":-5.32904, "ay":-2.77189, "alpha":-7.00057, "fx":[-62.89058,-93.75103,-108.68205,-97.25812], "fy":[-88.67425,-51.84941,1.13948,-49.21198]}, - {"t":0.7925, "x":7.32596, "y":4.678, "heading":-0.45861, "vx":1.85635, "vy":0.88155, "omega":-4.4608, "ax":-5.66204, "ay":-2.99498, "alpha":-0.15154, "fx":[-95.80011,-96.2211,-96.81632,-96.40122], "fy":[-51.90475,-51.0975,-49.9773,-50.79554]}, - {"t":0.82185, "x":7.37801, "y":4.70258, "heading":-0.58954, "vx":1.69016, "vy":0.79364, "omega":-4.46525, "ax":-5.55715, "ay":-2.98319, "alpha":3.91485, "fx":[-106.39109,-99.35352,-82.04074,-90.31664], "fy":[-24.34184,-45.58161,-72.12497,-60.92454]}, - {"t":0.8512, "x":7.42522, "y":4.72459, "heading":-0.7206, "vx":1.52705, "vy":0.70608, "omega":-4.35034, "ax":-5.3451, "ay":-2.95159, "alpha":6.73563, "fx":[-109.12399,-102.22143,-75.00505,-77.32434], "fy":[-5.21052,-39.15498,-79.65776,-76.79924]}, - {"t":0.88055, "x":7.46774, "y":4.74405, "heading":-0.84829, "vx":1.37016, "vy":0.61944, "omega":-4.15264, "ax":-5.09257, "ay":-2.88702, "alpha":9.28659, "fx":[-108.95268,-104.62864,-73.05374,-59.85765], "fy":[8.83166,-32.4571,-81.59475,-91.20901]}, - {"t":0.9099, "x":7.50576, "y":4.76098, "heading":-0.97018, "vx":1.22069, "vy":0.5347, "omega":-3.88006, "ax":-4.87905, "ay":-2.75056, "alpha":11.42185, "fx":[-107.56234,-106.52352,-73.69751,-44.18188], "fy":[19.65195,-25.78282,-81.107,-99.90725]}, - {"t":0.93925, "x":7.53949, "y":4.77549, "heading":-1.08406, "vx":1.07748, "vy":0.45397, "omega":-3.54481, "ax":-4.74217, "ay":-2.56655, "alpha":12.94613, "fx":[-105.64302,-107.91697,-75.54705,-33.54508], "fy":[28.25444,-19.33103,-79.4521,-104.09611]}, - {"t":0.96861, "x":7.56908, "y":4.78771, "heading":-1.18811, "vx":0.93829, "vy":0.37864, "omega":-3.16482, "ax":-4.66807, "ay":-2.36948, "alpha":13.94294, "fx":[-103.51501,-108.8572,-77.84913,-27.38856], "fy":[35.2587,-13.24674,-77.24575,-105.98269]}, - {"t":0.99796, "x":7.5946, "y":4.79781, "heading":-1.281, "vx":0.80127, "vy":0.30909, "omega":-2.75557, "ax":-4.63086, "ay":-2.17778, "alpha":14.58452, "fx":[-101.30961,-109.41417,-80.19441,-24.1599], "fy":[41.1365,-7.62765,-74.84497,-106.83763]}, - {"t":1.02731, "x":7.61613, "y":4.80594, "heading":-1.36188, "vx":0.66535, "vy":0.24517, "omega":-2.32749, "ax":-4.6096, "ay":-1.99766, "alpha":15.02359, "fx":[-99.01805,-109.666,-82.36303,-22.58483], "fy":[46.33149,-2.53421,-72.48106,-107.2347]}, - {"t":1.05666, "x":7.63367, "y":4.81228, "heading":-1.4302, "vx":0.53005, "vy":0.18653, "omega":-1.88652, "ax":-4.58905, "ay":-1.82878, "alpha":15.38106, "fx":[-96.49294,-109.69004,-84.23983,-21.81075], "fy":[51.32385,1.99726,-70.31508,-107.43426]}, - {"t":1.08601, "x":7.64725, "y":4.81696, "heading":-1.48557, "vx":0.39535, "vy":0.13285, "omega":-1.43506, "ax":-4.55686, "ay":-1.66734, "alpha":15.75722, "fx":[-93.42975,-109.55839,-85.76599,-21.28952], "fy":[56.64802,5.94228,-68.46544,-107.56866]}, - {"t":1.11537, "x":7.65689, "y":4.82014, "heading":-1.52769, "vx":0.2616, "vy":0.08392, "omega":-0.97256, "ax":-4.50135, "ay":-1.5085, "alpha":16.23941, "fx":[-89.35836,-109.3365,-86.9104,-20.66126], "fy":[62.8238,9.27769,-67.02391,-107.71416]}, - {"t":1.14472, "x":7.66263, "y":4.82196, "heading":-1.55624, "vx":0.12948, "vy":0.03964, "omega":-0.49591, "ax":-4.41128, "ay":-1.35045, "alpha":16.89534, "fx":[-83.72687,-109.08358,-87.65181,-19.67599], "fy":[70.12728,11.9724,-66.06614,-107.91649]}, - {"t":1.17407, "x":7.66453, "y":4.82254, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":5.94818, "y":4.026, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.38951, "ay":1.33028, "alpha":16.96732, "fx":[87.69216,19.09249,82.84233,109.02999], "fy":[66.01385,108.02505,-71.08104,-12.44686]}, + {"t":0.02942, "x":5.95008, "y":4.02658, "heading":-1.5708, "vx":0.12915, "vy":0.03914, "omega":0.49923, "ax":4.51582, "ay":1.46105, "alpha":16.09449, "fx":[87.80683,21.06865,89.22912,109.14678], "fy":[65.84723,107.64321,-62.80586,-11.27622]}, + {"t":0.05885, "x":5.95583, "y":4.02836, "heading":-1.55611, "vx":0.26202, "vy":0.08213, "omega":0.97278, "ax":4.60583, "ay":1.60375, "alpha":15.39677, "fx":[87.46923,22.46084,94.1257,109.31991], "fy":[66.27865,107.34342,-55.18521,-9.31949]}, + {"t":0.08827, "x":5.96554, "y":4.03147, "heading":-1.52749, "vx":0.39754, "vy":0.12932, "omega":1.4258, "ax":4.66414, "ay":1.74846, "alpha":14.87121, "fx":[86.72221,23.48188,97.6349,109.50366], "fy":[67.23387,107.10152,-48.74606,-6.6258]}, + {"t":0.11769, "x":5.97925, "y":4.03603, "heading":-1.48553, "vx":0.53477, "vy":0.18076, "omega":1.86335, "ax":4.70114, "ay":1.89625, "alpha":14.45588, "fx":[85.60281,24.39654,100.21839,109.6423], "fy":[68.63049,106.86669,-43.25454,-3.22404]}, + {"t":0.14712, "x":5.99702, "y":4.04217, "heading":-1.43071, "vx":0.67309, "vy":0.23656, "omega":2.28869, "ax":4.72832, "ay":2.05319, "alpha":14.06171, "fx":[84.15346,25.56924,102.31759,109.66941], "fy":[70.37223,106.55229,-38.10315,0.87532]}, + {"t":0.17654, "x":6.01887, "y":4.05002, "heading":-1.36337, "vx":0.81222, "vy":0.29697, "omega":2.70243, "ax":4.75772, "ay":2.22532, "alpha":13.58351, "fx":[82.44088,27.54165,104.22179,109.50528], "fy":[72.33616,106.0058,-32.6095,5.67608]}, + {"t":0.20596, "x":6.04483, "y":4.05972, "heading":-1.28385, "vx":0.9522, "vy":0.36244, "omega":3.1021, "ax":4.80365, "ay":2.41559, "alpha":12.89211, "fx":[80.58811,31.14622,106.04771,109.05296], "fy":[74.34975,104.92931,-26.11699,11.19218]}, + {"t":0.23538, "x":6.07493, "y":4.07143, "heading":-1.19258, "vx":1.09354, "vy":0.43352, "omega":3.48142, "ax":4.88504, "ay":2.62073, "alpha":11.81762, "fx":[78.83371,37.61967,107.72715,108.19221], "fy":[76.14661,102.68319,-17.9649,17.44668]}, + {"t":0.26481, "x":6.10922, "y":4.08532, "heading":-1.09015, "vx":1.23727, "vy":0.51063, "omega":3.82913, "ax":5.02396, "ay":2.82571, "alpha":10.14703, "fx":[77.65051,48.46135,108.94535,106.76712], "fy":[77.26511,97.89187,-7.38028,24.48133]}, + {"t":0.29423, "x":6.1478, "y":4.10157, "heading":-0.97748, "vx":1.38509, "vy":0.59377, "omega":4.12769, "ax":5.2276, "ay":2.99962, "alpha":7.70494, "fx":[78.00809,64.17847,108.94361,104.54988], "fy":[76.7656,88.20951,6.71316,32.40238]}, + {"t":0.32365, "x":6.19081, "y":4.12034, "heading":-0.85603, "vx":1.5389, "vy":0.68202, "omega":4.35439, "ax":5.4451, "ay":3.11848, "alpha":4.50916, "fx":[81.98452,81.46744,105.92949,101.09663], "fy":[72.25057,72.37485,25.9863,41.56586]}, + {"t":0.35308, "x":6.23845, "y":4.14175, "heading":-0.72791, "vx":1.69912, "vy":0.77378, "omega":4.48706, "ax":5.55572, "ay":3.18687, "alpha":0.27233, "fx":[93.62772,94.04472,95.37966,94.95251], "fy":[55.73508,54.98432,52.65044,53.46135]}, + {"t":0.3825, "x":6.29085, "y":4.1659, "heading":-0.59589, "vx":1.86258, "vy":0.86755, "omega":4.49508, "ax":5.1287, "ay":3.08416, "alpha":-7.43128, "fx":[108.47036,99.74418,67.21356,73.5228], "fy":[1.95592,43.87131,85.56545,78.45019]}, + {"t":0.41192, "x":6.34787, "y":4.19276, "heading":-0.46363, "vx":2.01348, "vy":0.95829, "omega":4.27643, "ax":4.1242, "ay":3.06737, "alpha":-12.87839, "fx":[103.96803,99.64234,46.27866,30.71685], "fy":[-30.6386,43.95,98.26907,97.12019]}, + {"t":0.44135, "x":6.4089, "y":4.22229, "heading":-0.33781, "vx":2.13483, "vy":1.04854, "omega":3.8975, "ax":4.46879, "ay":2.46007, "alpha":-12.05426, "fx":[103.52197,97.68479,38.50997,64.33457], "fy":[-31.6994,47.76727,101.20956,50.10263]}, + {"t":0.47077, "x":6.47365, "y":4.2542, "heading":-0.22313, "vx":2.26632, "vy":1.12093, "omega":3.54283, "ax":4.96916, "ay":1.76007, "alpha":-11.55187, "fx":[105.69848,95.35094,40.24201,96.80457], "fy":[-22.06087,51.64744,99.94176,-9.77529]}, + {"t":0.50019, "x":6.54248, "y":4.28794, "heading":-0.11889, "vx":2.41252, "vy":1.17271, "omega":3.20294, "ax":5.0149, "ay":1.82273, "alpha":-11.27773, "fx":[106.59227,93.02218,42.91973,98.674], "fy":[-13.53973,54.7482,97.8384,-15.03019]}, + {"t":0.52961, "x":6.61563, "y":4.32324, "heading":-0.02465, "vx":2.56008, "vy":1.22634, "omega":2.87112, "ax":4.95904, "ay":1.88058, "alpha":-11.15589, "fx":[106.1148,90.39347,44.07311,96.82572], "fy":[-7.3113,57.14792,95.3896,-17.27347]}, + {"t":0.55904, "x":6.6931, "y":4.36013, "heading":0.05983, "vx":2.70599, "vy":1.28168, "omega":2.54288, "ax":4.73772, "ay":1.88333, "alpha":-10.92382, "fx":[103.09949,86.35722,43.39629,89.49588], "fy":[-2.50958,57.97353,90.07624,-17.40041]}, + {"t":0.58846, "x":6.77477, "y":4.39866, "heading":0.13465, "vx":2.84538, "vy":1.33709, "omega":2.22146, "ax":0.32243, "ay":-0.24496, "alpha":1.73007, "fx":[0.4328,1.64007,10.49976,9.36483], "fy":[-0.32036,-9.25336,-7.98541,0.89239]}, + {"t":0.61788, "x":6.85863, "y":4.4379, "heading":0.20001, "vx":2.85487, "vy":1.32988, "omega":2.27237, "ax":-4.26991, "ay":-1.57292, "alpha":14.65754, "fx":[-103.58428,-81.8474,-26.31445,-78.77393], "fy":[3.75176,-64.39656,-95.26431,48.88947]}, + {"t":0.64731, "x":6.94078, "y":4.47634, "heading":0.26687, "vx":2.72924, "vy":1.2836, "omega":2.70364, "ax":-4.37459, "ay":-1.46586, "alpha":16.0532, "fx":[-106.78895,-83.68512,-25.9507,-81.21749], "fy":[4.98073,-66.68455,-100.38374,62.35241]}, + {"t":0.67673, "x":7.01919, "y":4.51348, "heading":0.34642, "vx":2.60052, "vy":1.24047, "omega":3.17597, "ax":-4.27291, "ay":-1.38806, "alpha":17.25537, "fx":[-107.86904,-83.31289,-21.63972,-77.90235], "fy":[5.70991,-68.69188,-102.91678,71.45681]}, + {"t":0.70615, "x":7.09386, "y":4.54937, "heading":0.43986, "vx":2.4748, "vy":1.19963, "omega":3.68368, "ax":-5.75094, "ay":-2.14927, "alpha":5.48442, "fx":[-106.56363,-91.41597,-85.80187,-107.50598], "fy":[-19.77202,-58.15275,-64.63161,-3.67734]}, + {"t":0.73558, "x":7.16419, "y":4.58374, "heading":0.54825, "vx":2.30559, "vy":1.13639, "omega":3.84504, "ax":-5.81323, "ay":-2.58747, "alpha":-1.96586, "fx":[-94.92696,-103.5253,-102.33008,-94.74322], "fy":[-52.70815,-32.85663,-37.00489,-53.47897]}, + {"t":0.765, "x":7.22951, "y":4.61606, "heading":0.66138, "vx":2.13455, "vy":1.06026, "omega":3.7872, "ax":-5.58991, "ay":-2.69021, "alpha":-5.43432, "fx":[-83.18418,-108.30658,-104.25233,-84.5878], "fy":[-70.02825,-11.39636,-32.58079,-69.0333]}, + {"t":0.79442, "x":7.28989, "y":4.64609, "heading":0.77281, "vx":1.97008, "vy":0.98111, "omega":3.62731, "ax":-5.37709, "ay":-2.75171, "alpha":-7.39669, "fx":[-75.49464,-109.11406,-104.12764,-77.11458], "fy":[-78.38967,2.2898,-33.58413,-77.53927]}, + {"t":0.82384, "x":7.34553, "y":4.67377, "heading":0.87954, "vx":1.81187, "vy":0.90014, "omega":3.40968, "ax":-5.21858, "ay":-2.81605, "alpha":-8.39439, "fx":[-72.03154,-108.86225,-103.29914,-70.87302], "fy":[-81.64707,9.82292,-36.36496,-83.41147]}, + {"t":0.85327, "x":7.39658, "y":4.69903, "heading":0.97986, "vx":1.65832, "vy":0.81729, "omega":3.16269, "ax":-5.12203, "ay":-2.87246, "alpha":-8.7781, "fx":[-72.45039,-108.58523,-102.11373,-65.34791], "fy":[-81.29557,13.49412,-39.75271,-87.88467]}, + {"t":0.88269, "x":7.44316, "y":4.72183, "heading":1.07292, "vx":1.50761, "vy":0.73277, "omega":2.90441, "ax":-5.08458, "ay":-2.90157, "alpha":-8.7994, "fx":[-76.39848,-108.4863,-100.72435,-60.33971], "fy":[-77.58988,14.88327,-43.26612,-91.44688]}, + {"t":0.91211, "x":7.48531, "y":4.74214, "heading":1.15837, "vx":1.35801, "vy":0.6474, "omega":2.6455, "ax":-5.09708, "ay":-2.88421, "alpha":-8.66893, "fx":[-83.26858,-108.53941,-99.22317,-55.7686], "fy":[-70.14919,14.93344,-46.68258,-94.3402]}, + {"t":0.94154, "x":7.52307, "y":4.75994, "heading":1.23621, "vx":1.20804, "vy":0.56254, "omega":2.39044, "ax":-5.14027, "ay":-2.80724, "alpha":-8.59488, "fx":[-91.76779,-108.68338,-97.67564,-51.6112], "fy":[-58.59644,14.19264,-49.89354,-96.70396]}, + {"t":0.97096, "x":7.55638, "y":4.77528, "heading":1.30655, "vx":1.0568, "vy":0.47994, "omega":2.13755, "ax":-5.18402, "ay":-2.67502, "alpha":-8.75718, "fx":[-99.83746,-108.86811,-96.1336,-47.87568], "fy":[-43.52068,12.98597,-52.84342,-98.6273]}, + {"t":1.00038, "x":7.58523, "y":4.78824, "heading":1.36944, "vx":0.90427, "vy":0.40123, "omega":1.87989, "ax":-5.20072, "ay":-2.51641, "alpha":-9.21409, "fx":[-105.56203,-109.05912,-94.64293,-44.5867], "fy":[-27.06276,11.522,-55.49915,-100.17349]}, + {"t":1.02981, "x":7.60959, "y":4.79896, "heading":1.42475, "vx":0.75125, "vy":0.32719, "omega":1.60878, "ax":-5.18322, "ay":-2.37001, "alpha":-9.86121, "fx":[-108.40287,-109.23419,-93.24894,-41.77416], "fy":[-11.98019,9.95399,-57.8342,-101.39207]}, + {"t":1.05923, "x":7.62945, "y":4.80756, "heading":1.47209, "vx":0.59874, "vy":0.25746, "omega":1.31863, "ax":-5.14409, "ay":-2.26022, "alpha":-10.52767, "fx":[-109.15318,-109.38065,-91.99826,-39.46588], "fy":[-0.04467,8.40842,-59.82249,-102.32413]}, + {"t":1.08865, "x":7.64484, "y":4.81415, "heading":1.51089, "vx":0.44739, "vy":0.19096, "omega":1.00888, "ax":-5.10039, "ay":-2.19105, "alpha":-11.08792, "fx":[-108.91232,-109.49374,-90.9367,-37.68214], "fy":[8.37548,6.99242,-61.43956,-103.00455]}, + {"t":1.11808, "x":7.6558, "y":4.81882, "heading":1.54057, "vx":0.29732, "vy":0.12649, "omega":0.68264, "ax":-5.06402, "ay":-2.15527, "alpha":-11.48688, "fx":[-108.43876,-109.57474,-90.10484,-36.43199], "fy":[13.6941,5.79244,-62.66608,-103.46273]}, + {"t":1.1475, "x":7.66235, "y":4.82161, "heading":1.56066, "vx":0.14832, "vy":0.06307, "omega":0.34466, "ax":-5.04089, "ay":-2.14368, "alpha":-11.71394, "fx":[-108.10169,-109.62848,-89.53421,-35.71214], "fy":[16.48554,4.8727,-63.48973,-103.72237]}, + {"t":1.17692, "x":7.66453, "y":4.82254, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/F_PATH_4.traj b/src/main/deploy/choreo/F_PATH_4.traj index d1366828..66d94b7e 100644 --- a/src/main/deploy/choreo/F_PATH_4.traj +++ b/src/main/deploy/choreo/F_PATH_4.traj @@ -3,8 +3,8 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":7.664534091949463, "y":4.822539806365967, "heading":-1.5707963267948966, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":5.63525390625, "y":5.723388195037842, "heading":2.627672932910526, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":7.664534091949463, "y":4.822539806365967, "heading":1.5707963267948966, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":5.63525390625, "y":5.723388195037842, "heading":5.759586531581287, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -13,8 +13,8 @@ }, "params":{ "waypoints":[ - {"x":{"exp":"7.664534091949463 m", "val":7.664534091949463}, "y":{"exp":"4.822539806365967 m", "val":4.822539806365967}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"5.63525390625 m", "val":5.63525390625}, "y":{"exp":"5.723388195037842 m", "val":5.723388195037842}, "heading":{"exp":"2.627672932910526 rad", "val":2.627672932910526}, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"7.664534091949463 m", "val":7.664534091949463}, "y":{"exp":"4.822539806365967 m", "val":4.822539806365967}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"5.63525390625 m", "val":5.63525390625}, "y":{"exp":"5.723388195037842 m", "val":5.723388195037842}, "heading":{"exp":"330 deg", "val":5.759586531581287}, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -26,47 +26,48 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,1.21111], + "waypoints":[0.0,1.21167], "samples":[ - {"t":0.0, "x":7.66453, "y":4.82254, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.5471, "ay":2.33477, "alpha":-7.78924, "fx":[-109.66343,-109.18134,-64.49676,-94.07713], "fy":[4.14124,9.43922,88.73725,56.53705]}, - {"t":0.03187, "x":7.66172, "y":4.82373, "heading":-1.5708, "vx":-0.17679, "vy":0.07441, "omega":-0.24825, "ax":-5.55785, "ay":2.35044, "alpha":-7.63446, "fx":[-109.63036,-109.05684,-65.31819,-94.14457], "fy":[4.75017,10.63928,88.12112,56.4105]}, - {"t":0.06374, "x":7.65326, "y":4.82729, "heading":-1.57871, "vx":-0.35393, "vy":0.14932, "omega":-0.49157, "ax":-5.5671, "ay":2.36595, "alpha":-7.49743, "fx":[-109.57867,-108.97155,-66.15539,-94.07367], "fy":[5.64458,11.34134,87.47824,56.51226]}, - {"t":0.09561, "x":7.63915, "y":4.83325, "heading":-1.59438, "vx":-0.53136, "vy":0.22473, "omega":-0.73052, "ax":-5.57554, "ay":2.38202, "alpha":-7.36814, "fx":[-109.50103,-108.92371,-67.05283,-93.87583], "fy":[6.82509,11.65078,86.77264,56.82122]}, - {"t":0.12748, "x":7.61938, "y":4.84162, "heading":-1.61766, "vx":-0.70906, "vy":0.30065, "omega":-0.96536, "ax":-5.5839, "ay":2.39957, "alpha":-7.23442, "fx":[-109.38732,-108.90212,-68.06925,-93.56379], "fy":[8.29791,11.70119,85.95364,57.31118]}, - {"t":0.15936, "x":7.59395, "y":4.85242, "heading":-1.64843, "vx":-0.88702, "vy":0.37712, "omega":-1.19593, "ax":-5.5931, "ay":2.41961, "alpha":-7.08075, "fx":[-109.22402,-108.88969,-69.28023,-93.15394], "fy":[10.07512,11.65275,84.95108,57.94831]}, - {"t":0.19123, "x":7.56284, "y":4.86567, "heading":-1.68654, "vx":-1.06528, "vy":0.45424, "omega":-1.4216, "ax":-5.60429, "ay":2.44306, "alpha":-6.88694, "fx":[-108.99322,-108.86579,-70.78068,-92.66984], "fy":[12.17535,11.6924,83.66838,58.68716]}, - {"t":0.2231, "x":7.52604, "y":4.88139, "heading":-1.73185, "vx":-1.2439, "vy":0.5321, "omega":-1.64109, "ax":-5.619, "ay":2.47062, "alpha":-6.62675, "fx":[-108.67114,-108.80574,-72.68545,-92.14766], "fy":[14.62534,12.03603,81.97304,59.46396]}, - {"t":0.25497, "x":7.48354, "y":4.8996, "heading":-1.78415, "vx":-1.42298, "vy":0.61085, "omega":-1.8523, "ax":-5.639, "ay":2.50252, "alpha":-6.26674, "fx":[-108.22538,-108.67564,-75.12509,-91.64527], "fy":[17.4635,12.93515,79.68464,60.18501]}, - {"t":0.28684, "x":7.43533, "y":4.92034, "heading":-1.84319, "vx":-1.60271, "vy":0.6906, "omega":-2.05203, "ax":-5.66613, "ay":2.53837, "alpha":-5.76523, "fx":[-107.60983,-108.41878,-78.23039,-91.25786], "fy":[20.74812,14.69247,76.56275,60.70476]}, - {"t":0.31871, "x":7.38137, "y":4.94364, "heading":-1.90859, "vx":-1.78329, "vy":0.7715, "omega":-2.23577, "ax":-5.70149, "ay":2.57729, "alpha":-5.07085, "fx":[-106.75327,-107.92628,-82.09645,-91.14709], "fy":[24.57663,17.696,72.30289,60.78003]}, - {"t":0.35058, "x":7.32164, "y":4.96954, "heading":-1.97985, "vx":-1.96501, "vy":0.85365, "omega":-2.39738, "ax":-5.74404, "ay":2.61832, "alpha":-4.11689, "fx":[-105.5307,-106.97206,-86.71624,-91.59907], "fy":[29.13415,22.48973,66.56046,59.96283]}, - {"t":0.38245, "x":7.25609, "y":4.99808, "heading":-2.05625, "vx":-2.14808, "vy":0.93709, "omega":-2.5286, "ax":-5.78739, "ay":2.66158, "alpha":-2.79673, "fx":[-103.67661,-105.05506,-91.88792,-93.14812], "fy":[34.82992,29.91438,59.03842,57.30812]}, - {"t":0.41433, "x":7.18469, "y":5.0293, "heading":-2.13684, "vx":-2.33253, "vy":1.02192, "omega":-2.61773, "ax":-5.81134, "ay":2.70728, "alpha":-0.86234, "fx":[-100.44941,-100.97354,-97.14391,-96.82989], "fy":[42.76083,41.358,49.67228,50.40912]}, - {"t":0.4462, "x":7.1074, "y":5.06324, "heading":-2.22027, "vx":-2.51774, "vy":1.10821, "omega":-2.64521, "ax":-5.73467, "ay":2.73523, "alpha":2.53036, "fx":[-92.62541,-91.61166,-101.80655,-104.13688], "fy":[56.88022,58.95761,38.87877,31.38551]}, - {"t":0.47807, "x":7.02424, "y":5.09995, "heading":-2.30458, "vx":-2.70051, "vy":1.19538, "omega":-2.56457, "ax":-4.78171, "ay":2.66424, "alpha":11.63579, "fx":[-45.81234,-69.64889,-105.19702,-104.68416], "fy":[96.43567,83.46869,27.87267,-26.50499]}, - {"t":0.50994, "x":6.93575, "y":5.1394, "heading":-2.38631, "vx":-2.85291, "vy":1.28029, "omega":-2.19372, "ax":-4.31109, "ay":2.62943, "alpha":13.90563, "fx":[-25.90107,-62.69881,-104.58015,-100.14139], "fy":[100.72871,88.14586,28.53702,-38.50812]}, - {"t":0.54181, "x":6.84263, "y":5.18154, "heading":-2.45623, "vx":-2.99031, "vy":1.3641, "omega":-1.75053, "ax":-4.28996, "ay":2.57704, "alpha":13.20528, "fx":[-30.39479,-59.8464,-102.73119,-98.91176], "fy":[92.84774,88.32766,30.69967,-36.5364]}, - {"t":0.57368, "x":6.74515, "y":5.22633, "heading":-2.51202, "vx":-3.12704, "vy":1.44623, "omega":-1.32966, "ax":-3.70497, "ay":2.04123, "alpha":10.93016, "fx":[-27.50564,-51.15403,-89.62017,-83.80235], "fy":[52.85846,76.58207,31.44933,-22.00724]}, - {"t":0.60555, "x":6.6436, "y":5.27346, "heading":-2.5544, "vx":-3.24512, "vy":1.51129, "omega":-0.98131, "ax":4.38045, "ay":-2.33944, "alpha":-12.12345, "fx":[42.83833,56.97827,100.8634,97.36052], "fy":[-74.74465,-88.01873,-32.34854,35.93925]}, - {"t":0.63742, "x":6.5424, "y":5.32043, "heading":-2.58568, "vx":-3.10551, "vy":1.43673, "omega":-1.3677, "ax":4.44365, "ay":-2.60231, "alpha":-12.32512, "fx":[44.02842,55.44645,102.2664,100.59936], "fy":[-86.69931,-92.21874,-35.05677,36.91642]}, - {"t":0.6693, "x":6.44568, "y":5.3649, "heading":-2.62927, "vx":-2.96388, "vy":1.35379, "omega":-1.76051, "ax":4.43471, "ay":-2.70926, "alpha":-12.30679, "fx":[45.40828,52.59302,102.06272,101.66868], "fy":[-88.95214,-94.77306,-37.51351,36.90378]}, - {"t":0.70117, "x":6.35347, "y":5.40667, "heading":-2.68538, "vx":-2.82255, "vy":1.26744, "omega":-2.15274, "ax":4.4587, "ay":-2.74155, "alpha":-12.04642, "fx":[51.00988,48.73001,101.31173,102.31332], "fy":[-85.54188,-97.22406,-40.31483,36.54859]}, - {"t":0.73304, "x":6.26578, "y":5.44568, "heading":-2.75399, "vx":-2.68044, "vy":1.18006, "omega":-2.53668, "ax":5.61985, "ay":-2.51278, "alpha":-5.69532, "fx":[98.07953,75.46739,99.94894,108.87212], "fy":[-45.56436,-78.54958,-43.83718,-3.01523]}, - {"t":0.76491, "x":6.1832, "y":5.48201, "heading":-2.83483, "vx":-2.50133, "vy":1.09998, "omega":-2.7182, "ax":5.85196, "ay":-2.59863, "alpha":-1.34832, "fx":[99.94409,95.32999,99.57449,103.3124], "fy":[-43.66171,-53.12971,-44.81937,-35.19702]}, - {"t":0.79678, "x":6.10645, "y":5.51575, "heading":-2.92147, "vx":-2.31482, "vy":1.01716, "omega":-2.76117, "ax":5.86376, "ay":-2.59694, "alpha":1.31923, "fx":[99.43778,103.38122,100.51009,95.63422], "fy":[-45.47745,-35.50423,-42.80404,-52.90703]}, - {"t":0.82865, "x":6.03566, "y":5.54685, "heading":-3.00947, "vx":-2.12793, "vy":0.93439, "omega":-2.71912, "ax":5.82387, "ay":-2.57214, "alpha":2.99811, "fx":[98.29273,106.52818,102.38855,89.04014], "fy":[-48.20592,-25.03301,-38.22302,-63.54323]}, - {"t":0.86052, "x":5.97079, "y":5.57532, "heading":-3.09613, "vx":-1.94232, "vy":0.85241, "omega":-2.62357, "ax":5.77586, "ay":-2.53818, "alpha":4.1926, "fx":[96.84936,107.81902,104.62524,83.68953], "fy":[-51.21045,-19.19747,-31.74817,-70.53908]}, - {"t":0.89239, "x":5.91182, "y":5.6012, "heading":3.10344, "vx":-1.75824, "vy":0.77152, "omega":-2.48995, "ax":5.72692, "ay":-2.49983, "alpha":5.16134, "fx":[95.2461,108.37183,106.66694,79.36821], "fy":[-54.23654,-16.19413,-24.22291,-75.43191]}, - {"t":0.92427, "x":5.8587, "y":5.62452, "heading":3.02408, "vx":-1.57571, "vy":0.69184, "omega":-2.32545, "ax":5.67656, "ay":-2.46282, "alpha":6.00766, "fx":[93.56561,108.59927,108.17608,75.88542], "fy":[-57.155,-14.91932,-16.51455,-78.97855]}, - {"t":0.95614, "x":5.81136, "y":5.64532, "heading":2.94997, "vx":-1.39479, "vy":0.61335, "omega":-2.13398, "ax":5.62486, "ay":-2.43248, "alpha":6.75514, "fx":[91.86947,108.66332,109.07665,73.09961], "fy":[-59.89138,-14.69578,-9.32062,-81.59558]}, - {"t":0.98801, "x":5.76976, "y":5.66363, "heading":2.88195, "vx":-1.21552, "vy":0.53583, "omega":-1.91868, "ax":5.57349, "ay":-2.41161, "alpha":7.39966, "fx":[90.2088,108.6351,109.47267,70.89738], "fy":[-62.40015,-15.09085,-3.05219,-83.54024]}, - {"t":1.01988, "x":5.73385, "y":5.67948, "heading":2.8208, "vx":-1.03789, "vy":0.45896, "omega":-1.68285, "ax":5.52457, "ay":-2.40017, "alpha":7.93777, "fx":[88.62752,108.5524,109.53031,69.17511], "fy":[-64.65361,-15.81594,2.15578,-84.9909]}, - {"t":1.05175, "x":5.70358, "y":5.69289, "heading":2.76717, "vx":-0.86181, "vy":0.38247, "omega":-1.42986, "ax":5.47968, "ay":-2.39621, "alpha":8.3759, "fx":[87.16322,108.44076,109.39821,67.82886], "fy":[-66.63615,-16.67171,6.35736,-86.08498]}, - {"t":1.08362, "x":5.6789, "y":5.70386, "heading":2.7216, "vx":-0.68717, "vy":0.3061, "omega":-1.16291, "ax":5.43952, "ay":-2.39706, "alpha":8.72929, "fx":[85.84758,108.32093,109.17905,66.75135], "fy":[-68.34038,-17.51707,9.70104,-86.93703]}, - {"t":1.11549, "x":5.65976, "y":5.7124, "heading":2.68453, "vx":-0.51381, "vy":0.2297, "omega":-0.8847, "ax":5.40403, "ay":-2.40008, "alpha":9.01773, "fx":[84.70689,108.21101,108.93204,65.83412], "fy":[-69.76406,-18.25039,12.36222,-87.64644]}, - {"t":1.14736, "x":5.64613, "y":5.7185, "heading":2.65634, "vx":-0.34157, "vy":0.15321, "omega":-0.59729, "ax":5.37264, "ay":-2.40301, "alpha":9.26159, "fx":[83.76299,108.12677,108.6858,64.97293], "fy":[-70.90733,-18.79735,14.50578,-88.29902]}, - {"t":1.17924, "x":5.63797, "y":5.72217, "heading":2.6373, "vx":-0.17034, "vy":0.07662, "omega":-0.30211, "ax":5.34462, "ay":-2.40405, "alpha":9.4791, "fx":[83.03429,108.08127,108.451,64.07508], "fy":[-71.77048,-19.10264,16.2695,-88.96493]}, - {"t":1.21111, "x":5.63525, "y":5.72339, "heading":2.62767, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":7.66453, "y":4.82254, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.55385, "ay":2.3377, "alpha":-7.72046, "fx":[-64.94315,-94.13923,-109.65289,-109.14212], "fy":[88.40789,56.43005,4.36042,9.8564]}, + {"t":0.03107, "x":7.66185, "y":4.82367, "heading":1.5708, "vx":-0.17255, "vy":0.07263, "omega":-0.23986, "ax":-5.56459, "ay":2.35307, "alpha":-7.56577, "fx":[-65.7665,-94.20808,-109.61865,-109.01485], "fy":[87.78412,56.30105,4.97179,11.04324]}, + {"t":0.06214, "x":7.65381, "y":4.82706, "heading":1.56334, "vx":-0.34543, "vy":0.14573, "omega":-0.47492, "ax":-5.57401, "ay":2.36831, "alpha":-7.42658, "fx":[-66.60996,-94.14827,-109.56604,-108.92494], "fy":[87.13013,56.38493,5.85298,11.76921]}, + {"t":0.09321, "x":7.64039, "y":4.83273, "heading":1.54859, "vx":-0.51861, "vy":0.21931, "omega":-0.70565, "ax":-5.58275, "ay":2.38407, "alpha":-7.29361, "fx":[-67.51441,-93.9707,-109.48829,-108.87072], "fy":[86.41217,56.66175,7.00441,12.13089]}, + {"t":0.12427, "x":7.62158, "y":4.8407, "heading":1.52667, "vx":-0.69206, "vy":0.29338, "omega":-0.93225, "ax":-5.59149, "ay":2.40115, "alpha":-7.15569, "fx":[-68.53319,-93.68756,-109.37608,-108.84201], "fy":[85.58336,57.10693,8.43139,12.24951]}, + {"t":0.15534, "x":7.59738, "y":4.85097, "heading":1.4977, "vx":-0.86577, "vy":0.36798, "omega":-1.15457, "ax":-5.60104, "ay":2.42042, "alpha":-6.99883, "fx":[-69.73403,-93.31435,-109.2171,-108.82309], "fy":[84.57962,57.68905,10.14444,12.26941]}, + {"t":0.18641, "x":7.56778, "y":4.86357, "heading":1.46183, "vx":-1.03979, "vy":0.44318, "omega":-1.37201, "ax":-5.61243, "ay":2.44269, "alpha":-6.80505, "fx":[-71.20076,-92.87282,-108.99525,-108.79463], "fy":[83.31405,58.36642,12.15975,12.3579]}, + {"t":0.21748, "x":7.53276, "y":4.87852, "heading":1.41921, "vx":-1.21416, "vy":0.51907, "omega":-1.58343, "ax":-5.62696, "ay":2.46856, "alpha":-6.55134, "fx":[-73.03343,-92.3955,-108.68934,-108.73344], "fy":[81.66929,59.08151,14.50048,12.70679]}, + {"t":0.24855, "x":7.49233, "y":4.89584, "heading":1.37001, "vx":-1.38898, "vy":0.59577, "omega":-1.78697, "ax":-5.64614, "ay":2.49823, "alpha":-6.20875, "fx":[-75.34437,-91.93303,-108.27097,-108.60855], "fy":[79.48835,59.75157,17.19951,13.53716]}, + {"t":0.27962, "x":7.44645, "y":4.91555, "heading":1.31449, "vx":-1.5644, "vy":0.67338, "omega":-1.97987, "ax":-5.67151, "ay":2.53139, "alpha":-5.74163, "fx":[-78.24557,-91.56629,-107.70055,-108.37093], "fy":[76.56566,60.25142,20.3056,15.11027]}, + {"t":0.31068, "x":7.39511, "y":4.93769, "heading":1.25298, "vx":-1.7406, "vy":0.75203, "omega":-2.15825, "ax":-5.70409, "ay":2.56725, "alpha":-5.10682, "fx":[-81.82063,-91.42814,-106.91894,-107.93195], "fy":[72.64456,60.37934,23.89734,17.75123]}, + {"t":0.34175, "x":7.33828, "y":4.9623, "heading":1.18593, "vx":-1.91782, "vy":0.83179, "omega":-2.31691, "ax":-5.74326, "ay":2.60483, "alpha":-4.25035, "fx":[-86.07448,-91.7444,-105.82773,-107.11814], "fy":[67.43533,59.78176,28.11646,21.8964]}, + {"t":0.37282, "x":7.27592, "y":4.9894, "heading":1.11394, "vx":-2.09625, "vy":0.91272, "omega":-2.44896, "ax":-5.78468, "ay":2.64381, "alpha":-3.09312, "fx":[-90.86283,-92.91602,-104.23467,-105.56941], "fy":[60.67824,57.76449,33.25438,28.18479]}, + {"t":0.40389, "x":7.208, "y":5.01903, "heading":1.03786, "vx":-2.27597, "vy":0.99486, "omega":-2.54506, "ax":-5.81538, "ay":2.68444, "alpha":-1.47473, "fx":[-95.83185,-95.68208,-101.67014,-102.48773], "fy":[52.27618,52.73754,40.01356,37.61928]}, + {"t":0.43496, "x":7.13448, "y":5.05123, "heading":0.95879, "vx":-2.45665, "vy":1.07826, "omega":-2.59088, "ax":-5.79404, "ay":2.71875, "alpha":1.06712, "fx":[-100.43824,-101.2724,-96.53598,-95.97335], "fy":[42.48072,40.22977,50.5134,51.75701]}, + {"t":0.46603, "x":7.05536, "y":5.08605, "heading":0.87829, "vx":-2.63666, "vy":1.16273, "omega":-2.55773, "ax":-5.47753, "ay":2.69168, "alpha":6.365, "fx":[-104.111,-108.28634,-78.85908,-81.42841], "fy":[32.0376,5.01301,73.8508,72.23766]}, + {"t":0.49709, "x":6.9708, "y":5.12347, "heading":0.79883, "vx":-2.80684, "vy":1.24635, "omega":-2.35998, "ax":-4.33895, "ay":2.60646, "alpha":14.13383, "fx":[-105.35271,-100.32436,-24.98242,-64.55795], "fy":[26.82559,-39.38171,102.62335,87.2735]}, + {"t":0.52816, "x":6.88151, "y":5.16345, "heading":0.72551, "vx":-2.94164, "vy":1.32733, "omega":-1.92086, "ax":-4.33193, "ay":2.60199, "alpha":13.61148, "fx":[-104.17777,-99.74191,-28.81674,-62.00335], "fy":[29.04454,-38.52676,98.2847,88.23426]}, + {"t":0.55923, "x":6.78802, "y":5.20594, "heading":0.66583, "vx":-3.07623, "vy":1.40817, "omega":-1.49797, "ax":-4.28619, "ay":2.48702, "alpha":12.90751, "fx":[-101.93853,-97.71249,-32.7662,-59.21056], "fy":[30.62596,-36.35785,87.38319,87.56289]}, + {"t":0.5903, "x":6.69038, "y":5.25089, "heading":0.61929, "vx":-3.20939, "vy":1.48544, "omega":-1.09696, "ax":1.35485, "ay":-0.34783, "alpha":-3.1858, "fx":[33.84381,25.39316,11.77765,21.16788], "fy":[-7.65958,6.10815,-4.15166,-17.96308]}, + {"t":0.62137, "x":6.59132, "y":5.29688, "heading":0.58521, "vx":-3.1673, "vy":1.47463, "omega":-1.19594, "ax":4.39407, "ay":-2.46566, "alpha":-12.16784, "fx":[101.20072,98.75159,42.32281,56.69212], "fy":[-33.5277,35.07948,-80.04837,-89.26414]}, + {"t":0.65244, "x":6.49504, "y":5.3415, "heading":0.54805, "vx":-3.03078, "vy":1.39803, "omega":-1.57397, "ax":4.4401, "ay":-2.64914, "alpha":-12.27491, "fx":[102.0754,101.10022,44.0765,54.84702], "fy":[-35.93443,36.01606,-87.58828,-92.73791]}, + {"t":0.68351, "x":6.40302, "y":5.38366, "heading":0.49915, "vx":-2.89284, "vy":1.31572, "omega":-1.95533, "ax":4.42228, "ay":-2.73679, "alpha":-12.26899, "fx":[101.7464,101.94343,45.61323,51.58405], "fy":[-38.4384,36.27649,-88.68625,-95.35971]}, + {"t":0.71457, "x":6.31528, "y":5.42321, "heading":0.4384, "vx":-2.75544, "vy":1.2307, "omega":-2.33651, "ax":4.77427, "ay":-2.6278, "alpha":-10.7276, "fx":[100.85525,103.65377,70.12552,50.2011], "fy":[-41.43441,32.57619,-73.47362,-96.46077]}, + {"t":0.74564, "x":6.23198, "y":5.46018, "heading":0.36581, "vx":-2.60712, "vy":1.14905, "omega":-2.6698, "ax":5.71849, "ay":-2.56166, "alpha":-4.28735, "fx":[99.59205,107.99489,98.96689,82.52586], "fy":[-44.56876,-14.21721,-44.41015,-71.09627]}, + {"t":0.77671, "x":6.15374, "y":5.49464, "heading":0.28287, "vx":-2.42945, "vy":1.06947, "omega":-2.803, "ax":5.86084, "ay":-2.60976, "alpha":-0.40668, "fx":[99.6285,100.87488,99.79505,98.46659], "fy":[-44.62745,-41.68959,-44.15866,-47.08918]}, + {"t":0.80778, "x":6.08109, "y":5.52661, "heading":0.19578, "vx":-2.24736, "vy":0.98839, "omega":-2.81564, "ax":5.84867, "ay":-2.59507, "alpha":1.93862, "fx":[100.92955,93.274,99.06662,104.66635], "fy":[-41.7335,-56.96195,-46.32698,-31.54342]}, + {"t":0.83885, "x":6.01409, "y":5.55607, "heading":0.1083, "vx":-2.06565, "vy":0.90776, "omega":-2.75541, "ax":5.80386, "ay":-2.56449, "alpha":3.45135, "fx":[103.02259,86.95906,97.82334,107.08287], "fy":[-36.40592,-66.35207,-49.16534,-22.56137]}, + {"t":0.86992, "x":5.95271, "y":5.58303, "heading":0.0227, "vx":-1.88534, "vy":0.82809, "omega":-2.64818, "ax":5.75491, "ay":-2.52639, "alpha":4.57121, "fx":[105.29052,81.86093,96.3258,108.08009], "fy":[-29.38897,-72.63958,-52.19036,-17.67386]}, + {"t":0.90098, "x":5.89692, "y":5.60754, "heading":-0.05958, "vx":-1.70654, "vy":0.7496, "omega":-2.50616, "ax":5.70499, "ay":-2.48566, "alpha":5.50752, "fx":[107.21697,77.74699,94.69201,108.50522], "fy":[-21.57158,-77.087,-55.19498,-15.26769]}, + {"t":0.93205, "x":5.84665, "y":5.62963, "heading":-0.13744, "vx":-1.5293, "vy":0.67237, "omega":-2.33505, "ax":5.65329, "ay":-2.44837, "alpha":6.33432, "fx":[108.54029,74.43547,92.99678,108.67092], "fy":[-13.81045,-80.3313,-58.07053,-14.3723]}, + {"t":0.96312, "x":5.80186, "y":5.64934, "heading":-0.20999, "vx":-1.35366, "vy":0.5963, "omega":-2.13825, "ax":5.60043, "ay":-2.41944, "alpha":7.06192, "fx":[109.25492,71.79295,91.29759,108.70143], "fy":[-6.73968,-82.73222,-60.75329,-14.39066]}, + {"t":0.99419, "x":5.76251, "y":5.66669, "heading":-0.27642, "vx":-1.17966, "vy":0.52114, "omega":-1.91885, "ax":5.54844, "ay":-2.40082, "alpha":7.68338, "fx":[109.50326,69.71067,89.64263,108.65307], "fy":[-0.68864,-84.51772,-63.20421,-14.9386]}, + {"t":1.02526, "x":5.72854, "y":5.68173, "heading":-0.33603, "vx":-1.00728, "vy":0.44655, "omega":-1.68014, "ax":5.49947, "ay":-2.39176, "alpha":8.19709, "fx":[109.45947,68.08737,88.0733,108.55758], "fy":[4.27534,-85.84964,-65.4,-15.75804]}, + {"t":1.05633, "x":5.6999, "y":5.69445, "heading":-0.38823, "vx":-0.83642, "vy":0.37224, "omega":-1.42547, "ax":5.45493, "ay":-2.38989, "alpha":8.6121, "fx":[109.26416,66.82056,86.62485,108.43774], "fy":[8.24795,-86.85505,-67.32811,-16.66985]}, + {"t":1.08739, "x":5.67655, "y":5.70486, "heading":-0.43252, "vx":-0.66694, "vy":0.29799, "omega":-1.1579, "ax":5.41532, "ay":-2.39238, "alpha":8.94543, "fx":[109.00788,65.80448,85.32677,108.3128], "fy":[11.39685,-87.64129,-68.98334,-17.54685]}, + {"t":1.11846, "x":5.65844, "y":5.71296, "heading":-0.46849, "vx":-0.4987, "vy":0.22366, "omega":-0.87998, "ax":5.38039, "ay":-2.3966, "alpha":9.2176, "fx":[108.73943,64.93254,84.20349,108.19984], "fy":[13.90248,-88.30214,-70.36486,-18.29722]}, + {"t":1.14953, "x":5.64554, "y":5.71875, "heading":-0.49583, "vx":-0.33154, "vy":0.1492, "omega":-0.59361, "ax":5.34947, "ay":-2.40037, "alpha":9.44897, "fx":[108.4801,64.10283,83.27525,108.11378], "fy":[15.92787,-88.91879,-71.47379,-18.85364]}, + {"t":1.1806, "x":5.63782, "y":5.72223, "heading":-0.51428, "vx":-0.16534, "vy":0.07463, "omega":-0.30004, "ax":5.32177, "ay":-2.40198, "alpha":9.65743, "fx":[108.23586,63.22515,82.55916,108.06697], "fy":[17.60652,-89.55749,-72.31104,-19.16585]}, + {"t":1.21167, "x":5.63525, "y":5.72339, "heading":-0.5236, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/F_PATH_5.traj b/src/main/deploy/choreo/F_PATH_5.traj index 9d58e0c8..0ae9f4a8 100644 --- a/src/main/deploy/choreo/F_PATH_5.traj +++ b/src/main/deploy/choreo/F_PATH_5.traj @@ -3,8 +3,8 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":5.218018531799316, "y":5.192361831665039, "heading":2.627672932910526, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":7.749877452850342, "y":6.150105953216553, "heading":-1.5707963267948966, "intervals":37, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":5.218018531799316, "y":5.192361831665039, "heading":5.759586531581287, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":7.749877452850342, "y":6.150105953216553, "heading":1.5707963267948966, "intervals":37, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -13,8 +13,8 @@ }, "params":{ "waypoints":[ - {"x":{"exp":"5.218018531799316 m", "val":5.218018531799316}, "y":{"exp":"5.192361831665039 m", "val":5.192361831665039}, "heading":{"exp":"2.627672932910526 rad", "val":2.627672932910526}, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"7.749877452850342 m", "val":7.749877452850342}, "y":{"exp":"6.150105953216553 m", "val":6.150105953216553}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":37, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"5.218018531799316 m", "val":5.218018531799316}, "y":{"exp":"5.192361831665039 m", "val":5.192361831665039}, "heading":{"exp":"330 deg", "val":5.759586531581287}, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"7.749877452850342 m", "val":7.749877452850342}, "y":{"exp":"6.150105953216553 m", "val":6.150105953216553}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":37, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -26,50 +26,50 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,1.33519], + "waypoints":[0.0,1.33553], "samples":[ - {"t":0.0, "x":5.21802, "y":5.19236, "heading":2.62767, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.69438, "ay":2.1659, "alpha":6.86402, "fx":[108.78364,103.92462,75.76116,98.9699], "fy":[-14.34489,35.32299,79.38435,47.00312]}, - {"t":0.03257, "x":5.22104, "y":5.19351, "heading":2.62767, "vx":0.18544, "vy":0.07053, "omega":0.22353, "ax":5.70457, "ay":2.16618, "alpha":6.77068, "fx":[108.87417,103.90854,76.25281,99.09685], "fy":[-13.5699,35.3498,78.90065,46.70414]}, - {"t":0.06513, "x":5.2301, "y":5.19696, "heading":2.63495, "vx":0.37121, "vy":0.14108, "omega":0.44402, "ax":5.71799, "ay":2.16402, "alpha":6.65204, "fx":[108.98873,103.80487,76.69809,99.55385], "fy":[-12.53355,35.62988,78.45406,45.68699]}, - {"t":0.0977, "x":5.24522, "y":5.2027, "heading":2.64941, "vx":0.55743, "vy":0.21155, "omega":0.66065, "ax":5.73414, "ay":2.16005, "alpha":6.51009, "fx":[109.12049,103.61612,77.12809,100.27965], "fy":[-11.22716,36.14863,78.01482,44.03109]}, - {"t":0.13026, "x":5.26642, "y":5.21073, "heading":2.67093, "vx":0.74416, "vy":0.28189, "omega":0.87266, "ax":5.75241, "ay":2.15501, "alpha":6.34774, "fx":[109.26074,103.34489,77.58425,101.19751], "fy":[-9.63589,36.88657,77.54124,41.83242]}, - {"t":0.16283, "x":5.2937, "y":5.22106, "heading":2.69935, "vx":0.93149, "vy":0.35207, "omega":1.07938, "ax":5.7722, "ay":2.14984, "alpha":6.16696, "fx":[109.3982,102.99471,78.12143,102.21958], "fy":[-7.73711,37.81818,76.97574,39.21551]}, - {"t":0.19539, "x":5.3271, "y":5.23366, "heading":2.7345, "vx":1.11947, "vy":0.42208, "omega":1.28021, "ax":5.79309, "ay":2.14576, "alpha":5.9664, "fx":[109.51799,102.57162,78.81216,103.25328], "fy":[-5.49775,38.9099,76.23851,36.34467]}, - {"t":0.22796, "x":5.36662, "y":5.24854, "heading":2.77619, "vx":1.30812, "vy":0.49196, "omega":1.47451, "ax":5.81503, "ay":2.1443, "alpha":5.73802, "fx":[109.59972,102.08637,79.75229,104.20929], "fy":[-2.87001,40.11655,75.21722,33.43222]}, - {"t":0.26053, "x":5.41231, "y":5.2657, "heading":2.82421, "vx":1.49749, "vy":0.56179, "omega":1.66137, "ax":5.83856, "ay":2.14706, "alpha":5.46309, "fx":[109.6142,101.55839,81.06776,105.00892], "fy":[0.21619,41.37478,73.75014,30.74238]}, - {"t":0.29309, "x":5.46417, "y":5.28514, "heading":2.87831, "vx":1.68763, "vy":0.63171, "omega":1.83928, "ax":5.86499, "ay":2.15535, "alpha":5.10729, "fx":[109.51706,101.02257,82.92096,105.58679], "fy":[3.86697,42.59038,71.59856,28.59167]}, - {"t":0.32566, "x":5.52224, "y":5.30685, "heading":2.93821, "vx":1.87863, "vy":0.7019, "omega":2.0056, "ax":5.89622, "ay":2.16959, "alpha":4.61492, "fx":[109.23561,100.54201,85.51098,105.88317], "fy":[8.25153,43.6126,68.40208,27.35019]}, - {"t":0.35822, "x":5.58655, "y":5.33086, "heading":3.00352, "vx":2.07064, "vy":0.77256, "omega":2.15589, "ax":5.93399, "ay":2.18844, "alpha":3.90129, "fx":[108.63786,100.23328,89.05179,105.81887], "fy":[13.66031,44.1773,63.6101,27.45129]}, - {"t":0.39079, "x":5.65712, "y":5.35718, "heading":3.07373, "vx":2.26389, "vy":0.84383, "omega":2.28294, "ax":5.97746, "ay":2.20785, "alpha":2.84022, "fx":[107.44893,100.3208,93.68894,105.2409], "fy":[20.64362,43.7631,56.39317,29.41991]}, - {"t":0.42335, "x":5.73402, "y":5.38583, "heading":-3.13511, "vx":2.45855, "vy":0.91573, "omega":2.37543, "ax":6.01608, "ay":2.22019, "alpha":1.23207, "fx":[104.97647,101.26242,99.27517,103.81312], "fy":[30.385,41.15338,45.5931,33.92742]}, - {"t":0.45592, "x":5.81727, "y":5.41683, "heading":-3.05775, "vx":2.65447, "vy":0.98803, "omega":2.41555, "ax":6.00631, "ay":2.20959, "alpha":-1.34524, "fx":[98.94422,103.99951,104.92497,100.79371], "fy":[45.84191,32.69098,29.95148,41.85358]}, - {"t":0.48849, "x":5.9069, "y":5.45018, "heading":-2.97909, "vx":2.85007, "vy":1.05999, "omega":2.37175, "ax":5.73524, "ay":2.06546, "alpha":-6.56941, "fx":[78.74298,108.24751,108.58543,94.64327], "fy":[74.694,2.42748,9.27214,54.13819]}, - {"t":0.52105, "x":6.00276, "y":5.48579, "heading":-2.90185, "vx":3.03684, "vy":1.12725, "omega":2.15781, "ax":5.04307, "ay":1.8197, "alpha":-12.59492, "fx":[46.69691,100.05798,108.78478,87.58531], "fy":[97.1911,-38.57907,0.58231,64.61615]}, - {"t":0.55362, "x":6.10433, "y":5.52346, "heading":-2.83158, "vx":3.20107, "vy":1.18651, "omega":1.74765, "ax":4.66732, "ay":1.97016, "alpha":-14.26366, "fx":[31.04242,96.42574,108.29465,81.79618], "fy":[102.38514,-44.37487,4.79651,71.2408]}, - {"t":0.58618, "x":6.21105, "y":5.56315, "heading":-2.77467, "vx":3.35306, "vy":1.25067, "omega":1.28314, "ax":4.33815, "ay":1.88413, "alpha":-15.82617, "fx":[20.00816,89.33408,107.54266,78.278], "fy":[103.2194,-54.06508,5.04302,73.99657]}, - {"t":0.61875, "x":6.32254, "y":5.60488, "heading":-2.73288, "vx":3.49434, "vy":1.31203, "omega":0.76775, "ax":4.23967, "ay":1.907, "alpha":-15.00778, "fx":[21.01741,86.73409,105.05095,75.66008], "fy":[97.50023,-48.3743,7.32791,73.2965]}, - {"t":0.65131, "x":6.43859, "y":5.64861, "heading":-2.70788, "vx":3.63241, "vy":1.37413, "omega":0.27901, "ax":-2.09586, "ay":1.32705, "alpha":4.76519, "fx":[-20.15282,-28.64073,-49.59995,-44.2065], "fy":[18.47043,40.60688,26.89271,4.32096]}, - {"t":0.68388, "x":6.55577, "y":5.69407, "heading":-2.69879, "vx":3.56415, "vy":1.41735, "omega":0.43419, "ax":-4.46735, "ay":-1.60841, "alpha":14.59368, "fx":[-33.0457,-85.26117,-105.78326,-79.86341], "fy":[-93.21968,55.23465,-2.377,-69.07201]}, - {"t":0.71645, "x":6.66947, "y":5.73937, "heading":-2.68465, "vx":3.41867, "vy":1.36497, "omega":0.90945, "ax":-4.63841, "ay":-1.88492, "alpha":14.25152, "fx":[-35.22301,-93.11119,-107.57255,-79.68568], "fy":[-98.45168,49.66437,-6.98065,-72.47984]}, - {"t":0.74901, "x":6.77834, "y":5.78282, "heading":-2.65504, "vx":3.26762, "vy":1.30358, "omega":1.37356, "ax":-4.75834, "ay":-2.09163, "alpha":13.47898, "fx":[-38.82892,-98.18383,-107.89217,-78.84736], "fy":[-99.06808,42.53796,-11.34342,-74.43841]}, - {"t":0.78158, "x":6.88223, "y":5.82417, "heading":-2.61031, "vx":3.11266, "vy":1.23547, "omega":1.81251, "ax":-4.84825, "ay":-2.27485, "alpha":12.64658, "fx":[-42.82984,-101.74157,-107.6837,-77.61461], "fy":[-98.35863,35.60685,-15.79728,-76.2291]}, - {"t":0.81414, "x":6.98102, "y":5.86319, "heading":-2.55128, "vx":2.95477, "vy":1.16139, "omega":2.22435, "ax":-4.94185, "ay":-2.43931, "alpha":11.66577, "fx":[-48.37768,-104.44134,-107.11269,-76.30593], "fy":[-96.31056,28.62007,-20.4483,-77.8293]}, - {"t":0.84671, "x":7.07463, "y":5.89972, "heading":-2.47884, "vx":2.79384, "vy":1.08195, "omega":2.60426, "ax":-5.71406, "ay":-2.54877, "alpha":4.59164, "fx":[-88.56107,-107.95785,-104.36525,-87.89409], "fy":[-62.99246,-13.84853,-31.94849,-64.62582]}, - {"t":0.87927, "x":7.16258, "y":5.9336, "heading":-2.39403, "vx":2.60775, "vy":0.99895, "omega":2.75379, "ax":-5.90708, "ay":-2.51144, "alpha":0.31028, "fx":[-100.0885,-101.27375,-100.8664,-99.68225], "fy":[-43.62083,-40.81195,-41.85578,-44.58701]}, - {"t":0.91184, "x":7.24437, "y":5.9648, "heading":-2.30435, "vx":2.41539, "vy":0.91716, "omega":2.76389, "ax":-5.90789, "ay":-2.4478, "alpha":-2.13007, "fx":[-102.73491,-94.90222,-98.49006,-105.839], "fy":[-37.58751,-54.34374,-47.28202,-27.33257]}, - {"t":0.94441, "x":7.3199, "y":5.99337, "heading":-2.21435, "vx":2.22299, "vy":0.83744, "omega":2.69453, "ax":-5.86446, "ay":-2.39368, "alpha":-3.68972, "fx":[-103.31785,-89.64356,-97.62191,-108.42776], "fy":[-36.29937,-62.81103,-49.12535,-14.62742]}, - {"t":0.97697, "x":7.38918, "y":6.01938, "heading":-2.1266, "vx":2.03201, "vy":0.75949, "omega":2.57437, "ax":-5.81735, "ay":-2.35184, "alpha":-4.69458, "fx":[-103.13116,-85.16812,-98.18606,-109.32024], "fy":[-37.03333,-68.8566,-48.04887,-6.07792]}, - {"t":1.00954, "x":7.45227, "y":6.04286, "heading":-2.04276, "vx":1.84257, "vy":0.6829, "omega":2.42148, "ax":-5.77941, "ay":-2.31304, "alpha":-5.36697, "fx":[-102.56562,-81.25214,-99.85833,-109.54834], "fy":[-38.70449,-73.50003,-44.52675,-0.64552]}, - {"t":1.0421, "x":7.50921, "y":6.06388, "heading":-1.9639, "vx":1.65436, "vy":0.60758, "omega":2.24671, "ax":-5.75109, "ay":-2.26919, "alpha":-5.87396, "fx":[-101.78736,-77.77842,-102.16561,-109.56588], "fy":[-40.79678,-77.21017,-39.00777,2.62181]}, - {"t":1.07467, "x":7.56004, "y":6.08246, "heading":-1.89074, "vx":1.46707, "vy":0.53368, "omega":2.05542, "ax":-5.72773, "ay":-2.21752, "alpha":-6.32872, "fx":[-100.88911,-74.6886,-104.58673,-109.54403], "fy":[-43.03345,-80.23449,-32.04032,4.43088]}, - {"t":1.10723, "x":7.60478, "y":6.09866, "heading":-1.8238, "vx":1.28054, "vy":0.46146, "omega":1.84932, "ax":-5.70416, "ay":-2.16044, "alpha":-6.79071, "fx":[-99.93475,-71.9545,-106.68027,-109.53506], "fy":[-45.252,-82.71923,-24.29896,5.27665]}, - {"t":1.1398, "x":7.64345, "y":6.11254, "heading":-1.76358, "vx":1.09478, "vy":0.39111, "omega":1.62817, "ax":-5.67728, "ay":-2.10321, "alpha":-7.27264, "fx":[-98.97526,-69.56196,-108.19233,-109.54641], "fy":[-47.34911,-84.75999,-16.49679,5.5057]}, - {"t":1.17237, "x":7.67609, "y":6.12417, "heading":-1.71056, "vx":0.9099, "vy":0.32262, "omega":1.39133, "ax":-5.64693, "ay":-2.05113, "alpha":-7.7564, "fx":[-98.05499,-67.50138,-109.08254,-109.57149], "fy":[-49.2542,-86.42548,-9.24356,5.36673]}, - {"t":1.20493, "x":7.70273, "y":6.13358, "heading":-1.66525, "vx":0.726, "vy":0.25582, "omega":1.13874, "ax":-5.61504, "ay":-2.00749, "alpha":-8.21246, "fx":[-97.21384,-65.76225,-109.46338,-109.60161], "fy":[-50.91642,-87.76928,-2.94512,5.04369]}, - {"t":1.2375, "x":7.7234, "y":6.14085, "heading":-1.62816, "vx":0.54314, "vy":0.19044, "omega":0.8713, "ax":-5.5844, "ay":-1.97314, "alpha":-8.61439, "fx":[-96.4875,-64.33079,-109.50774,-109.63006], "fy":[-52.298,-88.83557,2.20758,4.67564]}, - {"t":1.27006, "x":7.73812, "y":6.14601, "heading":-1.59979, "vx":0.36128, "vy":0.12619, "omega":0.59076, "ax":-5.55754, "ay":-1.94714, "alpha":-8.94496, "fx":[-95.90687,-63.19018,-109.37912,-109.65278], "fy":[-53.37067,-89.66132,6.18219,4.36853]}, - {"t":1.30263, "x":7.74694, "y":6.14908, "heading":-1.58055, "vx":0.1803, "vy":0.06278, "omega":0.29946, "ax":-5.53638, "ay":-1.9277, "alpha":-9.1957, "fx":[-95.49725,-62.32277,-109.20115,-109.66766], "fy":[-54.11339,-90.27671,9.02933,4.20227]}, - {"t":1.33519, "x":7.74988, "y":6.15011, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":5.21802, "y":5.19236, "heading":-0.5236, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.68659, "ay":2.16829, "alpha":6.92679, "fx":[75.70755,98.44791,108.70287,104.05053], "fy":[79.43627,48.08191,-14.94123,34.95091]}, + {"t":0.03257, "x":5.22104, "y":5.19351, "heading":-0.5236, "vx":0.18523, "vy":0.07063, "omega":0.22563, "ax":5.69716, "ay":2.1681, "alpha":6.83238, "fx":[76.19772,98.59826,108.79826,104.03389], "fy":[78.95468,47.74257,-14.16168,34.97974]}, + {"t":0.06515, "x":5.23009, "y":5.19696, "heading":-0.51625, "vx":0.37081, "vy":0.14125, "omega":0.44819, "ax":5.71119, "ay":2.1654, "alpha":6.71072, "fx":[76.6391,99.09488,108.9196,103.92911], "fy":[78.51254,46.66857,-13.11618,35.26636]}, + {"t":0.09772, "x":5.2452, "y":5.20271, "heading":-0.50165, "vx":0.55685, "vy":0.21179, "omega":0.66679, "ax":5.72813, "ay":2.1608, "alpha":6.56423, "fx":[77.06326,99.87335,109.0599,103.73866], "fy":[78.07974,44.93888,-11.79595,35.796]}, + {"t":0.1303, "x":5.26638, "y":5.21076, "heading":-0.47993, "vx":0.74344, "vy":0.28217, "omega":0.88061, "ax":5.74731, "ay":2.15504, "alpha":6.3963, "fx":[77.51231,100.85297,109.21022,103.46499], "fy":[77.61403,42.64939,-10.18604,36.54884]}, + {"t":0.16287, "x":5.29364, "y":5.22109, "heading":-0.45125, "vx":0.93065, "vy":0.35237, "omega":1.08896, "ax":5.76808, "ay":2.14904, "alpha":6.20952, "fx":[78.04214,101.94114,109.35906,103.11156], "fy":[77.05699,39.92577,-8.26359,37.49887]}, + {"t":0.19544, "x":5.32702, "y":5.23371, "heading":-0.41577, "vx":1.11854, "vy":0.42238, "omega":1.29123, "ax":5.78996, "ay":2.14407, "alpha":6.00309, "fx":[78.72678,103.04013,109.49121,102.6843], "fy":[76.32749,36.9356,-5.99516,38.6119]}, + {"t":0.22802, "x":5.36653, "y":5.24861, "heading":-0.37371, "vx":1.30714, "vy":0.49222, "omega":1.48677, "ax":5.81285, "ay":2.14168, "alpha":5.76936, "fx":[79.66425,104.05576,109.58592,102.19395], "fy":[75.31117,33.89691,-3.33226,39.84193]}, + {"t":0.26059, "x":5.41219, "y":5.26578, "heading":-0.32528, "vx":1.49649, "vy":0.56198, "omega":1.6747, "ax":5.83729, "ay":2.14356, "alpha":5.48958, "fx":[80.98372,104.90566,109.61342,101.66002], "fy":[73.84294,31.08187,-0.2036,41.12447]}, + {"t":0.29317, "x":5.46403, "y":5.28522, "heading":-0.27073, "vx":1.68663, "vy":0.6318, "omega":1.85352, "ax":5.8646, "ay":2.15109, "alpha":5.12882, "fx":[82.85219,105.52253,109.52851,101.11773], "fy":[71.67834,28.81637,3.49907,42.36364]}, + {"t":0.32574, "x":5.52208, "y":5.30694, "heading":-0.21035, "vx":1.87766, "vy":0.70187, "omega":2.02059, "ax":5.89677, "ay":2.16467, "alpha":4.62995, "fx":[85.47487,105.84663,109.2569,100.63107], "fy":[68.44685,27.47997,7.94882,43.40577]}, + {"t":0.35831, "x":5.58637, "y":5.33095, "heading":-0.14454, "vx":2.06974, "vy":0.77238, "omega":2.1714, "ax":5.93564, "ay":2.18285, "alpha":3.90575, "fx":[89.07238,105.79986,108.66334,100.31875], "fy":[63.57996,27.51446,13.4436,43.98077]}, + {"t":0.39089, "x":5.65694, "y":5.35727, "heading":-0.07381, "vx":2.26309, "vy":0.84349, "omega":2.29863, "ax":5.98036, "ay":2.20128, "alpha":2.82619, "fx":[93.7921,105.22994,107.46459,100.41019], "fy":[56.21852,29.45133,20.54965,43.55297]}, + {"t":0.42346, "x":5.73383, "y":5.38591, "heading":0.00107, "vx":2.4579, "vy":0.91519, "omega":2.39069, "ax":6.01987, "ay":2.21171, "alpha":1.18567, "fx":[99.46852,103.79897,104.94216,101.37535], "fy":[45.16422,33.96588,30.48919,40.86302]}, + {"t":0.45603, "x":5.81709, "y":5.4169, "heading":0.07894, "vx":2.65399, "vy":0.98724, "omega":2.42931, "ax":6.0083, "ay":2.19698, "alpha":-1.45284, "fx":[105.15092,100.75878,98.71007,104.1778], "fy":[29.13917,41.93593,46.32535,32.07929]}, + {"t":0.48861, "x":5.90673, "y":5.45022, "heading":0.15808, "vx":2.8497, "vy":1.0588, "omega":2.38198, "ax":5.71802, "ay":2.0351, "alpha":-6.86002, "fx":[108.68129,94.56623,77.56378,108.2365], "fy":[8.06108,54.27401,75.89434,0.23663]}, + {"t":0.52118, "x":6.00259, "y":5.48579, "heading":0.23567, "vx":3.03596, "vy":1.12509, "omega":2.15853, "ax":5.04762, "ay":1.80487, "alpha":-12.59735, "fx":[108.78357,87.78405,46.92441,99.94238], "fy":[0.22831,64.34287,97.07954,-38.84971]}, + {"t":0.55376, "x":6.10416, "y":5.5234, "heading":0.30598, "vx":3.20038, "vy":1.18388, "omega":1.74818, "ax":4.69417, "ay":1.96558, "alpha":-14.12077, "fx":[108.29833,82.1571,32.20349,96.72716], "fy":[4.61032,70.81818,102.02499,-43.71752]}, + {"t":0.58633, "x":6.2109, "y":5.563, "heading":0.36292, "vx":3.35329, "vy":1.24791, "omega":1.28821, "ax":4.33368, "ay":1.88663, "alpha":-15.83756, "fx":[107.53569,78.26056,19.73888,89.32329], "fy":[5.0197,74.01286,103.29642,-53.96478]}, + {"t":0.6189, "x":6.32243, "y":5.60465, "heading":0.40489, "vx":3.49445, "vy":1.30937, "omega":0.77232, "ax":4.2312, "ay":1.91464, "alpha":-15.02764, "fx":[105.03051,75.57147,20.57547,86.70861], "fy":[7.39097,73.38713,97.66379,-48.17169]}, + {"t":0.65148, "x":6.4385, "y":5.64832, "heading":0.43004, "vx":3.63228, "vy":1.37173, "omega":0.28281, "ax":-2.10553, "ay":1.40638, "alpha":4.72168, "fx":[-49.61013,-44.52574,-20.45323,-28.66841], "fy":[28.13527,5.82958,19.99998,41.72354]}, + {"t":0.68405, "x":6.5557, "y":5.69375, "heading":0.43926, "vx":3.56369, "vy":1.41754, "omega":0.43662, "ax":-4.46689, "ay":-1.59583, "alpha":14.61465, "fx":[-105.7764,-80.02552,-33.09454,-85.0259], "fy":[-2.05956,-68.86578,-93.18081,55.52776]}, + {"t":0.71663, "x":6.66942, "y":5.73908, "heading":0.45348, "vx":3.41819, "vy":1.36556, "omega":0.91267, "ax":-4.63823, "ay":-1.87754, "alpha":14.26732, "fx":[-107.57885,-79.80322,-35.19989,-92.99791], "fy":[-6.76594,-72.3425,-98.45922,49.8221]}, + {"t":0.7492, "x":6.7783, "y":5.78256, "heading":0.48321, "vx":3.2671, "vy":1.3044, "omega":1.37742, "ax":-4.75875, "ay":-2.08758, "alpha":13.48651, "fx":[-107.90296,-78.94263,-38.78634,-98.14816], "fy":[-11.19279,-74.33274,-99.08733,42.57643]}, + {"t":0.78177, "x":6.8822, "y":5.82395, "heading":0.52808, "vx":3.11209, "vy":1.2364, "omega":1.81672, "ax":-4.84913, "ay":-2.27341, "alpha":12.64609, "fx":[-107.69482,-77.69709,-42.78531,-101.75215], "fy":[-15.69654,-76.14192,-98.38165,35.54]}, + {"t":0.81435, "x":6.981, "y":5.86301, "heading":0.58725, "vx":2.95414, "vy":1.16235, "omega":2.22866, "ax":-4.94052, "ay":-2.43962, "alpha":11.67527, "fx":[-107.12433,-76.35768,-48.21531,-104.44996], "fy":[-20.37301,-77.77639,-96.39485,28.55507]}, + {"t":0.84692, "x":7.0746, "y":5.89958, "heading":0.65985, "vx":2.79321, "vy":1.08288, "omega":2.60897, "ax":-5.70656, "ay":-2.55347, "alpha":4.66557, "fx":[-104.4003,-87.69918,-88.1737,-107.9949], "fy":[-31.82925,-64.88837,-63.5183,-13.49922]}, + {"t":0.8795, "x":7.16256, "y":5.9335, "heading":0.74483, "vx":2.60732, "vy":0.9997, "omega":2.76094, "ax":-5.90487, "ay":-2.51604, "alpha":0.33412, "fx":[-100.8623,-99.58362,-100.01694,-101.29743], "fy":[-41.86252,-44.80291,-43.77677,-40.74602]}, + {"t":0.91207, "x":7.24436, "y":5.96473, "heading":0.83477, "vx":2.41498, "vy":0.91775, "omega":2.77183, "ax":-5.9064, "ay":-2.45158, "alpha":-2.12547, "fx":[-98.44363,-105.80838,-102.72051,-94.89205], "fy":[-47.37596,-27.44471,-37.62302,-54.35928]}, + {"t":0.94464, "x":7.31989, "y":5.99332, "heading":0.92506, "vx":2.22258, "vy":0.83789, "omega":2.70259, "ax":-5.86278, "ay":-2.39678, "alpha":-3.69628, "fx":[-97.54483,-108.42428,-103.31928,-89.60825], "fy":[-49.27558,-14.64443,-36.29347,-62.86056]}, + {"t":0.97722, "x":7.38918, "y":6.01935, "heading":1.01309, "vx":2.03161, "vy":0.75982, "omega":2.58219, "ax":-5.81531, "ay":-2.35456, "alpha":-4.7069, "fx":[-98.09569,-109.32207,-103.1374,-85.11177], "fy":[-48.23009,-6.03047,-37.01511,-68.92593]}, + {"t":1.00979, "x":7.45227, "y":6.04285, "heading":1.0972, "vx":1.84218, "vy":0.68312, "omega":2.42887, "ax":-5.77714, "ay":-2.31552, "alpha":-5.38134, "fx":[-99.77282,-109.54829,-102.57232,-81.17643], "fy":[-44.71437,-0.56077,-38.68638,-73.58355]}, + {"t":1.04237, "x":7.50921, "y":6.06387, "heading":1.17632, "vx":1.654, "vy":0.60769, "omega":2.25357, "ax":-5.74876, "ay":-2.27135, "alpha":-5.88854, "fx":[-102.09942,-109.56303,-101.79229,-77.68428], "fy":[-39.17605,2.72532,-40.78441,-77.3049]}, + {"t":1.07494, "x":7.56004, "y":6.08246, "heading":1.24973, "vx":1.46674, "vy":0.53371, "omega":2.06176, "ax":-5.72546, "ay":-2.21918, "alpha":-6.34332, "fx":[-104.54672,-109.53931,-100.89091,-74.57688], "fy":[-32.16468,4.54158,-43.02929,-80.33841]}, + {"t":1.10751, "x":7.60478, "y":6.09867, "heading":1.31689, "vx":1.28024, "vy":0.46142, "omega":1.85514, "ax":-5.70193, "ay":-2.16143, "alpha":-6.80626, "fx":[-106.66431,-109.52957,-99.93257,-71.8263], "fy":[-24.36113,5.38756,-45.25693,-82.83065]}, + {"t":1.14009, "x":7.64346, "y":6.11255, "heading":1.37732, "vx":1.0945, "vy":0.39101, "omega":1.63343, "ax":-5.675, "ay":-2.10346, "alpha":-7.29038, "fx":[-108.19184,-109.54095,-98.96865,-69.41878], "fy":[-16.48924,5.61272,-47.36308,-84.87738]}, + {"t":1.17266, "x":7.6761, "y":6.12417, "heading":1.43052, "vx":0.90964, "vy":0.3225, "omega":1.39595, "ax":-5.64446, "ay":-2.05068, "alpha":-7.77719, "fx":[-109.08731,-109.56651,-98.04382,-67.34513], "fy":[-9.16992,5.46764,-49.27659,-86.54737]}, + {"t":1.20524, "x":7.70273, "y":6.13359, "heading":1.476, "vx":0.72578, "vy":0.2557, "omega":1.14262, "ax":-5.61233, "ay":-2.00649, "alpha":-8.23648, "fx":[-109.46552,-109.59728,-97.19833,-65.59521], "fy":[-2.81658,5.13759,-50.9462,-87.89427]}, + {"t":1.23781, "x":7.7234, "y":6.14085, "heading":1.51322, "vx":0.54297, "vy":0.19034, "omega":0.87432, "ax":-5.58142, "ay":-1.97176, "alpha":-8.64127, "fx":[-109.50314,-109.62637,-96.46818,-64.15552], "fy":[2.37694,4.76259,-52.3338,-88.96229]}, + {"t":1.27038, "x":7.73812, "y":6.14601, "heading":1.5417, "vx":0.36116, "vy":0.12611, "omega":0.59284, "ax":-5.55433, "ay":-1.94552, "alpha":-8.97397, "fx":[-109.36694,-109.64959,-95.88455,-63.00944], "fy":[6.37887,4.4493,-53.41093,-89.78849]}, + {"t":1.30296, "x":7.74694, "y":6.14908, "heading":1.56101, "vx":0.18023, "vy":0.06274, "omega":0.30053, "ax":-5.53301, "ay":-1.92595, "alpha":-9.226, "fx":[-109.1826,-109.66479,-95.47298,-62.13938], "fy":[9.24197,4.27813,-54.15638,-90.40309]}, + {"t":1.33553, "x":7.74988, "y":6.15011, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/F_PATH_6.traj b/src/main/deploy/choreo/F_PATH_6.traj index 17ef0175..91304e23 100644 --- a/src/main/deploy/choreo/F_PATH_6.traj +++ b/src/main/deploy/choreo/F_PATH_6.traj @@ -3,8 +3,8 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":7.749877452850342, "y":6.150105953216553, "heading":-1.5707963267948966, "intervals":50, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":5.483531951904297, "y":2.3855068683624268, "heading":0.558599362427265, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":7.749877452850342, "y":6.150105953216553, "heading":1.5707963267948966, "intervals":50, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":5.483531951904297, "y":2.3855068683624268, "heading":3.7000980142279785, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -13,8 +13,8 @@ }, "params":{ "waypoints":[ - {"x":{"exp":"7.749877452850342 m", "val":7.749877452850342}, "y":{"exp":"6.150105953216553 m", "val":6.150105953216553}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":50, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"5.483531951904297 m", "val":5.483531951904297}, "y":{"exp":"2.3855068683624268 m", "val":2.3855068683624268}, "heading":{"exp":"0.558599362427265 rad", "val":0.558599362427265}, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"7.749877452850342 m", "val":7.749877452850342}, "y":{"exp":"6.150105953216553 m", "val":6.150105953216553}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":50, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"5.483531951904297 m", "val":5.483531951904297}, "y":{"exp":"2.3855068683624268 m", "val":2.3855068683624268}, "heading":{"exp":"212 deg", "val":3.7000980142279785}, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -28,57 +28,57 @@ "sampleType":"Swerve", "waypoints":[0.0,1.76157], "samples":[ - {"t":0.0, "x":7.74988, "y":6.15011, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.00144, "ay":-5.17868, "alpha":7.93248, "fx":[-29.78587,-98.03161,-65.00344,-11.39336], "fy":[-105.44655,-49.2917,-88.45555,-109.15784]}, - {"t":0.03523, "x":7.74801, "y":6.14689, "heading":-1.5708, "vx":-0.10574, "vy":-0.18245, "omega":0.27947, "ax":-3.02122, "ay":-5.1855, "alpha":7.79187, "fx":[-30.92861,-97.58605,-64.94138,-12.10427], "fy":[-105.1024,-50.14728,-88.4929,-109.0732]}, - {"t":0.07046, "x":7.74241, "y":6.13725, "heading":-1.56095, "vx":-0.21219, "vy":-0.36514, "omega":0.55399, "ax":-3.04881, "ay":-5.19522, "alpha":7.58044, "fx":[-33.23511,-96.95215,-64.56121,-12.68915], "fy":[-104.37856,-51.34037,-88.76113,-108.99687]}, - {"t":0.10569, "x":7.73305, "y":6.12116, "heading":-1.54143, "vx":-0.3196, "vy":-0.54818, "omega":0.82106, "ax":-3.0833, "ay":-5.20693, "alpha":7.30796, "fx":[-36.57807,-96.11132,-63.87861,-13.21612], "fy":[-103.23438,-52.87465,-89.24254,-108.92221]}, - {"t":0.14093, "x":7.71987, "y":6.09861, "heading":-1.51251, "vx":-0.42823, "vy":-0.73163, "omega":1.07853, "ax":-3.12342, "ay":-5.21956, "alpha":6.98789, "fx":[-40.77994,-95.03556,-62.91561,-13.7829], "fy":[-101.62516,-54.75973,-89.91089,-108.83714]}, - {"t":0.17616, "x":7.70285, "y":6.0696, "heading":-1.47451, "vx":-0.53827, "vy":-0.91552, "omega":1.32472, "ax":-3.16728, "ay":-5.23237, "alpha":6.63477, "fx":[-45.58321,-93.68445,-61.70335,-14.52696], "fy":[-99.53847,-57.01286,-90.73125,-108.72192]}, - {"t":0.21139, "x":7.68192, "y":6.03409, "heading":-1.42783, "vx":-0.64986, "vy":-1.09986, "omega":1.55848, "ax":-3.21234, "ay":-5.2456, "alpha":6.25821, "fx":[-50.63607,-91.99961,-60.28668,-15.64189], "fy":[-97.03915,-59.66213,-91.65913,-108.54392]}, - {"t":0.24662, "x":7.65703, "y":5.99209, "heading":-1.37293, "vx":-0.76304, "vy":-1.28467, "omega":1.77896, "ax":-3.25604, "ay":-5.26091, "alpha":5.85308, "fx":[-55.5061,-89.89432,-58.7327,-17.404], "fy":[-94.31052,-62.75258,-92.63782,-108.24566]}, - {"t":0.28185, "x":7.62812, "y":5.94356, "heading":-1.31025, "vx":-0.87775, "vy":-1.47002, "omega":1.98517, "ax":-3.29686, "ay":-5.28136, "alpha":5.38647, "fx":[-59.71965,-87.23334,-57.14776,-20.21405], "fy":[-91.67157,-66.35715,-93.59143,-107.71761]}, - {"t":0.31708, "x":7.59515, "y":5.88849, "heading":-1.24031, "vx":-0.9939, "vy":-1.65609, "omega":2.17495, "ax":-3.3358, "ay":-5.31018, "alpha":4.78354, "fx":[-62.80299,-83.79109,-55.71351,-24.65656], "fy":[-89.55645,-70.59719,-94.40768,-106.73702]}, - {"t":0.35231, "x":7.55807, "y":5.82685, "heading":-1.16369, "vx":-1.11143, "vy":-1.84318, "omega":2.34348, "ax":-3.3771, "ay":-5.348, "alpha":3.91277, "fx":[-64.28742,-79.15493,-54.77014,-31.56128], "fy":[-88.46198,-75.68339,-94.89284,-104.8337]}, - {"t":0.38755, "x":7.51681, "y":5.75859, "heading":-1.08112, "vx":-1.23041, "vy":-2.0316, "omega":2.48133, "ax":-3.42628, "ay":-5.38725, "alpha":2.56779, "fx":[-63.64581,-72.46707,-55.03435,-41.97282], "fy":[-88.88287,-82.00272,-94.63486,-101.02209]}, - {"t":0.42278, "x":7.47134, "y":5.68368, "heading":-0.9937, "vx":-1.35112, "vy":-2.2214, "omega":2.5718, "ax":-3.47935, "ay":-5.40014, "alpha":0.42645, "fx":[-60.14087,-61.59892,-58.29172,-56.69959], "fy":[-91.23863,-90.28654,-92.46673,-93.42766]}, - {"t":0.45801, "x":7.42158, "y":5.60206, "heading":-0.90309, "vx":-1.4737, "vy":-2.41165, "omega":2.58682, "ax":-3.49091, "ay":-5.29078, "alpha":-3.23558, "fx":[-52.59854,-39.9152,-70.19292,-74.81085], "fy":[-95.71923,-101.46293,-83.28727,-79.50948]}, - {"t":0.49324, "x":7.36749, "y":5.51381, "heading":-0.81195, "vx":-1.59669, "vy":-2.59805, "omega":2.47283, "ax":-3.28715, "ay":-4.52048, "alpha":-11.09421, "fx":[-40.39128,8.43929,-101.48065,-90.22108], "fy":[-101.38487,-108.1905,-36.70093,-61.29224]}, - {"t":0.52847, "x":7.3092, "y":5.41947, "heading":-0.72483, "vx":-1.7125, "vy":-2.75732, "omega":2.08196, "ax":-3.04738, "ay":-4.39405, "alpha":-12.72624, "fx":[-34.02245,19.52988,-104.16666,-88.681], "fy":[-103.47598,-106.22873,-26.1099,-63.15143]}, - {"t":0.5637, "x":7.24697, "y":5.3196, "heading":-0.65148, "vx":-1.81987, "vy":-2.91212, "omega":1.6336, "ax":-2.77265, "ay":-4.33548, "alpha":-13.83557, "fx":[-27.56334,29.48552,-104.39242,-86.17777], "fy":[-105.00373,-103.03285,-21.01846,-65.92612]}, - {"t":0.59893, "x":7.18113, "y":5.21431, "heading":-0.59393, "vx":-1.91755, "vy":-3.06487, "omega":1.14615, "ax":-2.43265, "ay":-4.22411, "alpha":-15.02853, "fx":[-20.43176,41.32437,-103.18902,-83.21829], "fy":[-105.84931,-97.07679,-16.08378,-68.39406]}, - {"t":0.63417, "x":7.11207, "y":5.10371, "heading":-0.55355, "vx":-2.00326, "vy":-3.21369, "omega":0.61668, "ax":-2.21024, "ay":-3.99987, "alpha":-15.38659, "fx":[-16.79233,44.66525,-97.83013,-80.42491], "fy":[-103.96,-89.50023,-10.90363,-67.78292]}, - {"t":0.6694, "x":7.04012, "y":4.98801, "heading":-0.53182, "vx":-2.08113, "vy":-3.35461, "omega":0.07459, "ax":0.53397, "ay":-0.96542, "alpha":-1.84388, "fx":[10.64867,15.77368,7.52336,2.38523], "fy":[-22.76526,-14.65506,-9.94351,-18.32206]}, - {"t":0.70463, "x":6.96713, "y":4.86922, "heading":-0.52919, "vx":-2.06231, "vy":-3.38863, "omega":0.00962, "ax":0.27116, "ay":-0.16602, "alpha":-0.00415, "fx":[4.61624,4.62712,4.60856,4.59769], "fy":[-2.83872,-2.8201,-2.80925,-2.82787]}, - {"t":0.73986, "x":6.89464, "y":4.74973, "heading":-0.52886, "vx":-2.05276, "vy":-3.39447, "omega":0.00948, "ax":0.08734, "ay":-0.05277, "alpha":0.0, "fx":[1.48566,1.48567,1.48566,1.48565], "fy":[-0.89758,-0.89756,-0.89755,-0.89757]}, - {"t":0.77509, "x":6.82237, "y":4.63011, "heading":-0.52852, "vx":-2.04968, "vy":-3.39633, "omega":0.00948, "ax":0.02808, "ay":-0.01694, "alpha":0.0, "fx":[0.47758,0.47758,0.47758,0.47758], "fy":[-0.28812,-0.28812,-0.28813,-0.28812]}, - {"t":0.81032, "x":6.75017, "y":4.51044, "heading":-0.52819, "vx":-2.04869, "vy":-3.39693, "omega":0.00948, "ax":0.0093, "ay":-0.00561, "alpha":0.0, "fx":[0.15823,0.15824,0.15823,0.15822], "fy":[-0.09543,-0.09542,-0.09542,-0.09542]}, - {"t":0.84555, "x":6.678, "y":4.39075, "heading":-0.52785, "vx":-2.04837, "vy":-3.39713, "omega":0.00948, "ax":0.00395, "ay":-0.00238, "alpha":0.0, "fx":[0.0672,0.06721,0.0672,0.06719], "fy":[-0.04053,-0.04052,-0.04051,-0.04052]}, - {"t":0.88079, "x":6.60584, "y":4.27107, "heading":-0.52752, "vx":-2.04823, "vy":-3.39721, "omega":0.00948, "ax":0.0043, "ay":-0.00259, "alpha":0.0, "fx":[0.07308,0.07308,0.07307,0.07307], "fy":[-0.04407,-0.04406,-0.04405,-0.04406]}, - {"t":0.91602, "x":6.53368, "y":4.15138, "heading":-0.52719, "vx":-2.04808, "vy":-3.3973, "omega":0.00948, "ax":0.01084, "ay":-0.00653, "alpha":0.0, "fx":[0.18436,0.18436,0.18436,0.18435], "fy":[-0.11113,-0.11113,-0.11112,-0.11113]}, - {"t":0.95125, "x":6.46153, "y":4.03168, "heading":-0.52685, "vx":-2.04769, "vy":-3.39753, "omega":0.00948, "ax":0.03303, "ay":-0.0199, "alpha":0.0, "fx":[0.56182,0.56182,0.56182,0.56183], "fy":[-0.33846,-0.33847,-0.33848,-0.33847]}, - {"t":0.98648, "x":6.3894, "y":3.91197, "heading":-0.52652, "vx":-2.04653, "vy":-3.39823, "omega":0.00948, "ax":0.10293, "ay":-0.0619, "alpha":0.00003, "fx":[1.75075,1.75067,1.75081,1.75088], "fy":[-1.05284,-1.05298,-1.05305,-1.05292]}, - {"t":1.02171, "x":6.31737, "y":3.79221, "heading":-0.52618, "vx":-2.0429, "vy":-3.40042, "omega":0.00948, "ax":0.32207, "ay":-0.19003, "alpha":0.00757, "fx":[5.47126,5.45144,5.48535,5.50515], "fy":[-3.20554,-3.23962,-3.25931,-3.22521]}, - {"t":1.05694, "x":6.24559, "y":3.67229, "heading":-0.52585, "vx":-2.03156, "vy":-3.40711, "omega":0.00974, "ax":1.41204, "ay":0.24654, "alpha":3.17727, "fx":[21.2012,13.08045,27.2772,34.51479], "fy":[16.11174,1.15477,-7.54649,7.0545]}, - {"t":1.09217, "x":6.17489, "y":3.5524, "heading":-0.52551, "vx":-1.98181, "vy":-3.39842, "omega":0.12168, "ax":2.51454, "ay":3.85102, "alpha":15.42274, "fx":[22.25314,-36.2199,100.83361,84.2194], "fy":[103.182,92.41511,2.57825,63.84377]}, - {"t":1.12741, "x":6.10663, "y":3.43506, "heading":-0.52122, "vx":-1.89322, "vy":-3.26275, "omega":0.66505, "ax":2.58233, "ay":4.12296, "alpha":15.153, "fx":[21.97339,-35.76083,105.06776,84.41827], "fy":[105.55713,98.63111,9.18903,67.14397]}, - {"t":1.16264, "x":6.04153, "y":3.32267, "heading":-0.49779, "vx":-1.80224, "vy":-3.11749, "omega":1.19891, "ax":2.55174, "ay":4.4138, "alpha":14.17537, "fx":[19.95719,-33.03548,104.98234,81.71316], "fy":[106.68807,101.52858,20.62524,71.46798]}, - {"t":1.19787, "x":5.97962, "y":3.21557, "heading":-0.45555, "vx":-1.71234, "vy":-2.96199, "omega":1.69833, "ax":2.49362, "ay":4.68138, "alpha":13.07116, "fx":[17.56743,-29.1487,103.0449,78.19942], "fy":[107.45676,103.59831,31.67137,75.78942]}, - {"t":1.2331, "x":5.92084, "y":3.11413, "heading":-0.39572, "vx":-1.62448, "vy":-2.79705, "omega":2.15884, "ax":2.46834, "ay":4.95764, "alpha":11.56758, "fx":[15.7881,-21.1857,99.35233,73.98857], "fy":[107.93083,106.01061,43.18866,80.18199]}, - {"t":1.26833, "x":5.86514, "y":3.01866, "heading":-0.31966, "vx":-1.53752, "vy":-2.62239, "omega":2.56639, "ax":2.98827, "ay":5.58007, "alpha":3.40914, "fx":[35.66544,36.09166,69.94151,61.62005], "fy":[103.18098,102.75758,83.57251,90.15066]}, - {"t":1.30356, "x":5.81283, "y":2.92973, "heading":-0.22924, "vx":-1.43224, "vy":-2.4258, "omega":2.6865, "ax":3.10927, "ay":5.62026, "alpha":-0.47267, "fx":[55.55218,54.33541,50.2904,51.37293], "fy":[94.09728,94.83323,97.03149,96.43403]}, - {"t":1.33879, "x":5.7643, "y":2.84775, "heading":-0.13459, "vx":-1.3227, "vy":-2.22779, "omega":2.66984, "ax":3.12938, "ay":5.55824, "alpha":-2.71722, "fx":[69.6137,59.47275,38.50087,45.33182], "fy":[84.36062,91.9034,102.44162,99.47042]}, - {"t":1.37403, "x":5.71964, "y":2.77272, "heading":-0.04053, "vx":-1.21244, "vy":-2.03196, "omega":2.57411, "ax":3.11702, "ay":5.48881, "alpha":-4.1457, "fx":[78.55176,60.47991,30.07338,42.97372], "fy":[76.23505,91.35619,105.31125,100.5499]}, - {"t":1.40926, "x":5.67886, "y":2.70453, "heading":0.05016, "vx":-1.10263, "vy":-1.83858, "omega":2.42805, "ax":3.09846, "ay":5.43153, "alpha":-5.04639, "fx":[83.9588,59.77432,23.41012,43.67244], "fy":[70.34536,91.88887,107.04388,100.27725]}, - {"t":1.44449, "x":5.64193, "y":2.64313, "heading":0.13571, "vx":-0.99346, "vy":-1.64722, "omega":2.25026, "ax":3.08785, "ay":5.3845, "alpha":-5.62335, "fx":[87.15309,58.26728,17.86527,46.8081], "fy":[66.43592,92.89827,108.14422,98.87672]}, - {"t":1.47972, "x":5.60885, "y":2.58844, "heading":0.21499, "vx":-0.88467, "vy":-1.45752, "omega":2.05214, "ax":3.08994, "ay":5.34071, "alpha":-6.03368, "fx":[88.99199,56.38889,13.13988,51.7155], "fy":[64.02258,94.0832,108.84587,96.42417]}, - {"t":1.51495, "x":5.5796, "y":2.5404, "heading":0.28729, "vx":-0.77581, "vy":-1.26936, "omega":1.83957, "ax":3.10287, "ay":5.29459, "alpha":-6.38657, "fx":[89.99639,54.37629,9.07975,57.66337], "fy":[62.65874,95.28492,109.27944,93.01475]}, - {"t":1.55018, "x":5.55419, "y":2.49897, "heading":0.3521, "vx":-0.66649, "vy":-1.08282, "omega":1.61456, "ax":3.12132, "ay":5.24418, "alpha":-6.74257, "fx":[90.48438,52.37705,5.5978,63.91195], "fy":[61.99609,96.41701,109.52872,88.86586]}, - {"t":1.58541, "x":5.53265, "y":2.46407, "heading":0.40898, "vx":-0.55652, "vy":-0.89806, "omega":1.37701, "ax":3.13964, "ay":5.19101, "alpha":-7.11871, "fx":[90.65867,50.49317,2.63998,69.82592], "fy":[61.77602,97.43152,109.65273,84.33034]}, - {"t":1.62065, "x":5.51499, "y":2.43565, "heading":0.45749, "vx":-0.44591, "vy":-0.71518, "omega":1.12621, "ax":3.15404, "ay":5.13867, "alpha":-7.50149, "fx":[90.65646,48.80152,0.16822,74.97113], "fy":[61.80737,98.30164,109.69525,79.82519]}, - {"t":1.65588, "x":5.50123, "y":2.41365, "heading":0.49717, "vx":-0.33479, "vy":-0.53413, "omega":0.86192, "ax":3.16332, "ay":5.09093, "alpha":-7.86362, "fx":[90.57638,47.36342,-1.84826,79.13686], "fy":[61.94737,99.01238,109.68935,75.7321]}, - {"t":1.69111, "x":5.4914, "y":2.39799, "heading":0.52754, "vx":-0.22334, "vy":-0.35477, "omega":0.58487, "ax":3.16833, "ay":5.05059, "alpha":-8.17771, "fx":[90.49241,46.22872,-3.4369,82.28515], "fy":[62.08851,99.55549,109.65974,72.33234]}, - {"t":1.72634, "x":5.4855, "y":2.38862, "heading":0.54814, "vx":-0.11172, "vy":-0.17683, "omega":0.29676, "ax":3.17093, "ay":5.01917, "alpha":-8.42318, "fx":[90.46063,45.43722,-4.62248,84.47085], "fy":[62.15005,99.92629,109.62428,69.79771]}, - {"t":1.76157, "x":5.48353, "y":2.38551, "heading":0.5586, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":7.74988, "y":6.15011, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.00145, "ay":-5.17869, "alpha":7.93235, "fx":[-65.00331,-11.39395,-29.78674,-98.03113], "fy":[-88.45565,-109.15778,-105.44631,-49.29264]}, + {"t":0.03523, "x":7.74801, "y":6.14689, "heading":1.5708, "vx":-0.10575, "vy":-0.18245, "omega":0.27947, "ax":-3.02123, "ay":-5.18552, "alpha":7.79174, "fx":[-64.94125,-12.10486,-30.92944,-97.58557], "fy":[-88.493,-109.07314,-105.10216,-50.14821]}, + {"t":0.07046, "x":7.74241, "y":6.13725, "heading":1.58064, "vx":-0.21219, "vy":-0.36515, "omega":0.55398, "ax":-3.04882, "ay":-5.19523, "alpha":7.58032, "fx":[-64.5611,-12.68975,-33.23583,-96.95167], "fy":[-88.76122,-108.9968,-104.37834,-51.34128]}, + {"t":0.10569, "x":7.73305, "y":6.12116, "heading":1.60016, "vx":-0.3196, "vy":-0.54818, "omega":0.82105, "ax":-3.08331, "ay":-5.20694, "alpha":7.30784, "fx":[-63.87851,-13.21673,-36.57862,-96.11084], "fy":[-89.24261,-108.92213,-103.23419,-52.87552]}, + {"t":0.14093, "x":7.71987, "y":6.09861, "heading":1.62909, "vx":-0.42823, "vy":-0.73163, "omega":1.07851, "ax":-3.12343, "ay":-5.21957, "alpha":6.98779, "fx":[-62.91554,-13.78354,-40.78029,-95.03509], "fy":[-89.91093,-108.83706,-101.62503,-54.76054]}, + {"t":0.17616, "x":7.70285, "y":6.0696, "heading":1.66708, "vx":-0.53827, "vy":-0.91552, "omega":1.3247, "ax":-3.16728, "ay":-5.23238, "alpha":6.63467, "fx":[-61.70332,-14.52762,-45.58332,-93.684], "fy":[-90.73127,-108.72183,-99.53843,-57.0136]}, + {"t":0.21139, "x":7.68192, "y":6.03409, "heading":1.71375, "vx":-0.64986, "vy":-1.09986, "omega":1.55845, "ax":-3.21235, "ay":-5.2456, "alpha":6.25813, "fx":[-60.2867,-15.64255,-50.63595,-91.99918], "fy":[-91.65912,-108.54383,-97.03923,-59.66279]}, + {"t":0.24662, "x":7.65703, "y":5.99209, "heading":1.76866, "vx":-0.76304, "vy":-1.28467, "omega":1.77893, "ax":-3.25604, "ay":-5.26092, "alpha":5.853, "fx":[-58.73276,-17.40466,-55.50579,-89.89393], "fy":[-92.63778,-108.24556,-94.31071,-62.75314]}, + {"t":0.28185, "x":7.62812, "y":5.94356, "heading":1.83134, "vx":-0.87775, "vy":-1.47002, "omega":1.98514, "ax":-3.29686, "ay":-5.28137, "alpha":5.38639, "fx":[-57.14786,-20.21466,-59.71922,-87.233], "fy":[-93.59136,-107.7175,-91.67186,-66.35759]}, + {"t":0.31708, "x":7.59515, "y":5.88849, "heading":1.90127, "vx":-0.9939, "vy":-1.65609, "omega":2.17491, "ax":-3.3358, "ay":-5.31018, "alpha":4.78347, "fx":[-55.71365,-24.65706,-62.80252,-83.79082], "fy":[-94.4076,-106.73691,-89.55679,-70.59751]}, + {"t":0.35231, "x":7.55807, "y":5.82685, "heading":1.9779, "vx":-1.11143, "vy":-1.84318, "omega":2.34344, "ax":-3.37709, "ay":-5.34801, "alpha":3.91272, "fx":[-54.77029,-31.56156,-64.28703,-79.15477], "fy":[-94.89275,-104.83363,-88.46227,-75.68355]}, + {"t":0.38754, "x":7.51681, "y":5.7586, "heading":2.06046, "vx":-1.23041, "vy":-2.0316, "omega":2.48129, "ax":-3.42628, "ay":-5.38725, "alpha":2.5678, "fx":[-55.03444,-41.97272,-63.64561,-72.46712], "fy":[-94.63481,-101.02214,-88.88302,-82.00268]}, + {"t":0.42278, "x":7.47134, "y":5.68368, "heading":2.14788, "vx":-1.35112, "vy":-2.2214, "omega":2.57176, "ax":-3.47935, "ay":-5.40014, "alpha":0.42655, "fx":[-58.29152,-56.69898,-60.14102,-61.59941], "fy":[-92.46686,-93.42804,-91.23853,-90.28621]}, + {"t":0.45801, "x":7.42158, "y":5.60206, "heading":2.23849, "vx":-1.4737, "vy":-2.41165, "omega":2.58678, "ax":-3.49091, "ay":-5.2908, "alpha":-3.23529, "fx":[-70.19163,-74.80988,-52.59927,-39.91705], "fy":[-83.28841,-79.5104,-95.71884,-101.46223]}, + {"t":0.49324, "x":7.36749, "y":5.51381, "heading":2.32962, "vx":-1.59669, "vy":-2.59805, "omega":2.4728, "ax":-3.28718, "ay":-4.52051, "alpha":-11.09388, "fx":[-101.47982,-90.22117,-40.39226,8.43733], "fy":[-36.70332,-61.29212,-101.38449,-108.19069]}, + {"t":0.52847, "x":7.3092, "y":5.41947, "heading":2.41674, "vx":-1.7125, "vy":-2.75732, "omega":2.08195, "ax":-3.04742, "ay":-4.39402, "alpha":-12.72622, "fx":[-104.16682,-88.68168,-34.02355,19.52906], "fy":[-26.10932,-63.1505,-103.47564,-106.22893]}, + {"t":0.5637, "x":7.24697, "y":5.3196, "heading":2.49009, "vx":-1.81987, "vy":-2.91212, "omega":1.63359, "ax":-2.77272, "ay":-4.33545, "alpha":-13.8355, "fx":[-104.39267,-86.17872,-27.56499,29.48371], "fy":[-21.01747,-65.92491,-105.00332,-103.03342]}, + {"t":0.59893, "x":7.18113, "y":5.21431, "heading":2.54765, "vx":-1.91755, "vy":-3.06487, "omega":1.14614, "ax":-2.43277, "ay":-4.22411, "alpha":-15.02823, "fx":[-103.18919,-83.21948,-20.43435,41.32042], "fy":[-16.08373,-68.39268,-105.84884,-97.07853]}, + {"t":0.63416, "x":7.11207, "y":5.10371, "heading":2.58803, "vx":-2.00326, "vy":-3.21369, "omega":0.61668, "ax":-2.21023, "ay":-3.99987, "alpha":-15.38664, "fx":[-97.82992,-80.42513,-16.79244,44.66622], "fy":[-10.90378,-67.78276,-103.9601,-89.50026]}, + {"t":0.6694, "x":7.04012, "y":4.98801, "heading":2.60975, "vx":-2.08113, "vy":-3.35461, "omega":0.07459, "ax":0.53416, "ay":-0.96553, "alpha":-1.84387, "fx":[7.52672,2.38835,10.65163,15.77683], "fy":[-9.94537,-18.32386,-22.76707,-14.65696]}, + {"t":0.70463, "x":6.96713, "y":4.86922, "heading":2.61238, "vx":-2.06231, "vy":-3.38863, "omega":0.00962, "ax":0.27123, "ay":-0.16606, "alpha":-0.00415, "fx":[4.60966,4.59879,4.61733,4.62822], "fy":[-2.80991,-2.82853,-2.83938,-2.82076]}, + {"t":0.73986, "x":6.89464, "y":4.74973, "heading":2.61272, "vx":-2.05276, "vy":-3.39448, "omega":0.00948, "ax":0.08736, "ay":-0.05278, "alpha":0.0, "fx":[1.48602,1.48601,1.48602,1.48603], "fy":[-0.89777,-0.89778,-0.89779,-0.89778]}, + {"t":0.77509, "x":6.82237, "y":4.63011, "heading":2.61305, "vx":-2.04968, "vy":-3.39634, "omega":0.00948, "ax":0.02808, "ay":-0.01694, "alpha":0.0, "fx":[0.4777,0.4777,0.4777,0.4777], "fy":[-0.28819,-0.28819,-0.28819,-0.28819]}, + {"t":0.81032, "x":6.75018, "y":4.51044, "heading":2.61339, "vx":-2.04869, "vy":-3.39693, "omega":0.00948, "ax":0.0093, "ay":-0.00561, "alpha":0.0, "fx":[0.15826,0.15826,0.15827,0.15827], "fy":[-0.09544,-0.09544,-0.09545,-0.09544]}, + {"t":0.84555, "x":6.678, "y":4.39076, "heading":2.61372, "vx":-2.04836, "vy":-3.39713, "omega":0.00948, "ax":0.00395, "ay":-0.00238, "alpha":0.0, "fx":[0.0672,0.0672,0.06721,0.06721], "fy":[-0.04052,-0.04053,-0.04053,-0.04052]}, + {"t":0.88078, "x":6.60584, "y":4.27107, "heading":2.61406, "vx":-2.04822, "vy":-3.39721, "omega":0.00948, "ax":0.0043, "ay":-0.00259, "alpha":0.0, "fx":[0.07306,0.07305,0.07306,0.07307], "fy":[-0.04404,-0.04405,-0.04406,-0.04405]}, + {"t":0.91601, "x":6.53368, "y":4.15138, "heading":2.61439, "vx":-2.04807, "vy":-3.39731, "omega":0.00948, "ax":0.01083, "ay":-0.00653, "alpha":0.0, "fx":[0.18429,0.18429,0.18429,0.1843], "fy":[-0.11108,-0.11109,-0.11109,-0.11109]}, + {"t":0.95125, "x":6.46153, "y":4.03169, "heading":2.61472, "vx":-2.04769, "vy":-3.39754, "omega":0.00948, "ax":0.03302, "ay":-0.01989, "alpha":0.0, "fx":[0.56161,0.56162,0.56161,0.5616], "fy":[-0.33835,-0.33834,-0.33834,-0.33834]}, + {"t":0.98648, "x":6.38941, "y":3.91197, "heading":2.61506, "vx":-2.04653, "vy":-3.39824, "omega":0.00948, "ax":0.10289, "ay":-0.06188, "alpha":0.00003, "fx":[1.75013,1.75021,1.75007,1.75], "fy":[-1.05265,-1.05251,-1.05244,-1.05257]}, + {"t":1.02171, "x":6.31737, "y":3.79221, "heading":2.61539, "vx":-2.0429, "vy":-3.40042, "omega":0.00948, "ax":0.32194, "ay":-0.18996, "alpha":0.00757, "fx":[5.48323,5.50302,5.46915,5.44934], "fy":[-3.25805,-3.22398,-3.20431,-3.23838]}, + {"t":1.05694, "x":6.2456, "y":3.67229, "heading":2.61572, "vx":-2.03156, "vy":-3.40711, "omega":0.00974, "ax":1.41152, "ay":0.24638, "alpha":3.17589, "fx":[27.26657,34.50207,21.19378,13.07611], "fy":[-7.54394,7.05038,16.10335,1.15346]}, + {"t":1.09217, "x":6.1749, "y":3.55241, "heading":2.61607, "vx":-1.98183, "vy":-3.39843, "omega":0.12164, "ax":2.5145, "ay":3.85102, "alpha":15.42282, "fx":[100.83295,84.21921,22.25285,-36.22155], "fy":[2.57861,63.8437,103.18193,92.41451]}, + {"t":1.1274, "x":6.10663, "y":3.43507, "heading":2.62035, "vx":-1.89324, "vy":-3.26275, "omega":0.665, "ax":2.58238, "ay":4.12287, "alpha":15.15327, "fx":[105.06806,84.41975,21.97504,-35.76083], "fy":[9.1853,67.1421,105.55678,98.63108]}, + {"t":1.16263, "x":6.04154, "y":3.32267, "heading":2.64378, "vx":-1.80226, "vy":-3.1175, "omega":1.19887, "ax":2.5518, "ay":4.41373, "alpha":14.17555, "fx":[104.9829,81.71461,19.95888,-33.03506], "fy":[20.62238,71.46634,106.68777,101.52874]}, + {"t":1.19787, "x":5.97962, "y":3.21558, "heading":2.68602, "vx":-1.71236, "vy":-2.962, "omega":1.6983, "ax":2.49368, "ay":4.68133, "alpha":13.07129, "fx":[103.0455,78.20075,17.56897,-29.14839], "fy":[31.66942,75.78806,107.45652,103.59845]}, + {"t":1.2331, "x":5.92084, "y":3.11413, "heading":2.74585, "vx":-1.6245, "vy":-2.79707, "omega":2.15882, "ax":2.46849, "ay":4.95772, "alpha":11.56657, "fx":[99.35033,73.98895,15.79161,-21.17743], "fy":[43.19335,80.18166,107.93033,106.01237]}, + {"t":1.26833, "x":5.86514, "y":3.01866, "heading":2.82191, "vx":-1.53753, "vy":-2.6224, "omega":2.56632, "ax":2.98843, "ay":5.5801, "alpha":3.40721, "fx":[69.93286,61.61747,35.6752,36.10379], "fy":[83.57991,90.15242,103.17762,102.75351]}, + {"t":1.30356, "x":5.81283, "y":2.92974, "heading":2.91233, "vx":-1.43225, "vy":-2.42581, "omega":2.68636, "ax":3.10934, "ay":5.62022, "alpha":-0.47353, "fx":[50.28697,51.37128,55.55826,54.33922], "fy":[97.03332,96.43492,94.09371,94.83112]}, + {"t":1.33879, "x":5.7643, "y":2.84776, "heading":3.00697, "vx":-1.3227, "vy":-2.2278, "omega":2.66968, "ax":3.12942, "ay":5.55819, "alpha":-2.71763, "fx":[38.49998,45.33087,69.61671,59.47465], "fy":[102.44199,99.47086,84.35816,91.9022]}, + {"t":1.37402, "x":5.71964, "y":2.77272, "heading":3.10103, "vx":-1.21245, "vy":-2.03197, "omega":2.57393, "ax":3.11706, "ay":5.48878, "alpha":-4.14583, "fx":[30.07399,42.97298,78.55293,60.48134], "fy":[105.31109,100.55024,76.23385,91.35526]}, + {"t":1.40925, "x":5.67886, "y":2.70454, "heading":-3.09148, "vx":-1.10263, "vy":-1.8386, "omega":2.42787, "ax":3.09849, "ay":5.43152, "alpha":-5.04638, "fx":[23.41177,43.67132,83.95907,59.77576], "fy":[107.04353,100.27776,70.34505,91.88794]}, + {"t":1.44449, "x":5.64193, "y":2.64313, "heading":-3.00594, "vx":-0.99347, "vy":-1.64724, "omega":2.25008, "ax":3.08788, "ay":5.38449, "alpha":-5.62324, "fx":[17.86773,46.80605,87.15297,58.26892], "fy":[108.14382,98.87772,66.43608,92.89725]}, + {"t":1.47972, "x":5.60885, "y":2.58844, "heading":-2.92667, "vx":-0.88468, "vy":-1.45753, "omega":2.05196, "ax":3.08997, "ay":5.34072, "alpha":-6.03349, "fx":[13.14301,51.71211,88.99176,56.39081], "fy":[108.8455,96.42601,64.02289,94.08205]}, + {"t":1.51495, "x":5.5796, "y":2.5404, "heading":-2.85437, "vx":-0.77581, "vy":-1.26937, "omega":1.8394, "ax":3.10288, "ay":5.29462, "alpha":-6.38629, "fx":[9.08342,57.65845,89.99619,54.37854], "fy":[109.27914,93.01782,62.65901,95.28363]}, + {"t":1.55018, "x":5.55419, "y":2.49897, "heading":-2.78957, "vx":-0.66649, "vy":-1.08284, "omega":1.6144, "ax":3.12133, "ay":5.24422, "alpha":-6.74215, "fx":[5.60192,63.90561,90.4843,52.37964], "fy":[109.52852,88.87045,61.9962,96.4156]}, + {"t":1.58541, "x":5.53265, "y":2.46407, "heading":-2.73269, "vx":-0.55652, "vy":-0.89808, "omega":1.37686, "ax":3.13964, "ay":5.19108, "alpha":-7.11814, "fx":[2.64445,69.81848,90.65874,50.49609], "fy":[109.65263,84.33652,61.77591,97.43001]}, + {"t":1.62064, "x":5.51499, "y":2.43565, "heading":-2.68418, "vx":-0.44591, "vy":-0.71519, "omega":1.12608, "ax":3.15404, "ay":5.13876, "alpha":-7.50078, "fx":[0.17296,74.96301,90.65669,48.80474], "fy":[109.69525,79.83283,61.80702,98.30004]}, + {"t":1.65587, "x":5.50123, "y":2.41365, "heading":-2.64451, "vx":-0.33479, "vy":-0.53414, "omega":0.86182, "ax":3.16332, "ay":5.09103, "alpha":-7.86277, "fx":[-1.84333,79.12842,90.57677,47.3669], "fy":[109.68944,75.74092,61.94679,99.01071]}, + {"t":1.6911, "x":5.4914, "y":2.39799, "heading":-2.61414, "vx":-0.22334, "vy":-0.35478, "omega":0.5848, "ax":3.16834, "ay":5.05069, "alpha":-8.17677, "fx":[-3.43186,82.27663,90.49294,46.2324], "fy":[109.65991,72.34203,62.08772,99.55378]}, + {"t":1.72634, "x":5.4855, "y":2.38862, "heading":-2.59354, "vx":-0.11172, "vy":-0.17684, "omega":0.29672, "ax":3.17094, "ay":5.01928, "alpha":-8.42218, "fx":[-4.61739,84.46237,90.46127,45.44104], "fy":[109.6245,69.80796,62.1491,99.92455]}, + {"t":1.76157, "x":5.48353, "y":2.38551, "heading":-2.58309, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/F_PATH_7.traj b/src/main/deploy/choreo/F_PATH_7.traj index c4ba3538..7ce234bf 100644 --- a/src/main/deploy/choreo/F_PATH_7.traj +++ b/src/main/deploy/choreo/F_PATH_7.traj @@ -3,8 +3,8 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":5.483531951904297, "y":2.3855068683624268, "heading":0.558599362427265, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":7.740394592285156, "y":4.784609317779541, "heading":-1.5707963267948966, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":5.483531951904297, "y":2.3855068683624268, "heading":3.7000980142279785, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":7.740394592285156, "y":4.784609317779541, "heading":1.5707963267948966, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -13,8 +13,8 @@ }, "params":{ "waypoints":[ - {"x":{"exp":"5.483531951904297 m", "val":5.483531951904297}, "y":{"exp":"2.3855068683624268 m", "val":2.3855068683624268}, "heading":{"exp":"0.558599362427265 rad", "val":0.558599362427265}, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"7.740394592285156 m", "val":7.740394592285156}, "y":{"exp":"4.784609317779541 m", "val":4.784609317779541}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"5.483531951904297 m", "val":5.483531951904297}, "y":{"exp":"2.3855068683624268 m", "val":2.3855068683624268}, "heading":{"exp":"212 deg", "val":3.7000980142279785}, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"7.740394592285156 m", "val":7.740394592285156}, "y":{"exp":"4.784609317779541 m", "val":4.784609317779541}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -28,51 +28,51 @@ "sampleType":"Swerve", "waypoints":[0.0,1.48526], "samples":[ - {"t":0.0, "x":5.48353, "y":2.38551, "heading":0.5586, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.06902, "ay":4.07773, "alpha":-10.176, "fx":[99.2944,58.27962,13.52489,105.75279], "fy":[46.76627,93.01673,108.85581,28.80536]}, - {"t":0.03376, "x":5.48585, "y":2.38783, "heading":0.5586, "vx":0.13735, "vy":0.13765, "omega":-0.3435, "ax":4.08032, "ay":4.11044, "alpha":-9.9224, "fx":[99.02037,58.47816,14.94797,105.17382], "fy":[47.32598,92.88381,108.6582,30.80179]}, - {"t":0.06751, "x":5.49281, "y":2.39482, "heading":0.547, "vx":0.27509, "vy":0.2764, "omega":-0.67844, "ax":4.09975, "ay":4.14843, "alpha":-9.57171, "fx":[98.85905,59.10274,16.73494,104.24589], "fy":[47.64071,92.47818,108.38587,33.74988]}, - {"t":0.10127, "x":5.50443, "y":2.40651, "heading":0.5241, "vx":0.41348, "vy":0.41643, "omega":-1.00154, "ax":4.12518, "ay":4.19332, "alpha":-9.12138, "fx":[98.77786,60.12659,18.91062,102.85715], "fy":[47.78285,91.80473,108.01559,37.70564]}, - {"t":0.13502, "x":5.52074, "y":2.42296, "heading":0.49029, "vx":0.55273, "vy":0.55798, "omega":-1.30944, "ax":4.15368, "ay":4.24686, "alpha":-8.57053, "fx":[98.72768,61.51163,21.52118,100.85098], "fy":[47.85454,90.8693,107.51312,42.71466]}, - {"t":0.16878, "x":5.54177, "y":2.44421, "heading":0.44609, "vx":0.69294, "vy":0.70134, "omega":-1.59875, "ax":4.1818, "ay":4.30999, "alpha":-7.92578, "fx":[98.63845,63.20698,24.6304,98.04915], "fy":[47.99858,89.68209,106.82938,48.73644]}, - {"t":0.20254, "x":5.56754, "y":2.47034, "heading":0.39213, "vx":0.8341, "vy":0.84683, "omega":-1.86629, "ax":4.20631, "ay":4.3817, "alpha":-7.2051, "fx":[98.4102,65.14687,28.31867,94.31692], "fy":[48.4152,88.26253,105.89455,55.55346]}, - {"t":0.23629, "x":5.59809, "y":2.50143, "heading":0.32913, "vx":0.97609, "vy":0.99474, "omega":-2.10951, "ax":4.22569, "ay":4.45846, "alpha":-6.43345, "fx":[97.894,67.24715,32.68893,89.68132], "fy":[49.3882,86.64636,104.60718,62.70702]}, - {"t":0.27005, "x":5.63345, "y":2.53754, "heading":0.25792, "vx":1.11873, "vy":1.14524, "omega":-2.32668, "ax":4.24166, "ay":4.53512, "alpha":-5.62262, "fx":[96.85103,69.39807,37.88443,84.46387], "fy":[51.32494,84.89733,102.81236,69.52949]}, - {"t":0.3038, "x":5.67363, "y":2.57879, "heading":0.17938, "vx":1.26191, "vy":1.29832, "omega":-2.51647, "ax":4.2588, "ay":4.60761, "alpha":-4.73537, "fx":[94.86489,71.44585,44.12513,79.32795], "fy":[54.81177,83.13027,100.25488,75.29941]}, - {"t":0.33756, "x":5.71865, "y":2.62524, "heading":0.09443, "vx":1.40567, "vy":1.45386, "omega":-2.67632, "ax":4.28048, "ay":4.67561, "alpha":-3.64533, "fx":[91.15682,73.14291,51.7759,75.16314], "fy":[60.66115,81.56415,96.47117,79.42682]}, - {"t":0.37132, "x":5.76854, "y":2.67698, "heading":0.00409, "vx":1.55017, "vy":1.61169, "omega":-2.79937, "ax":4.30009, "ay":4.74004, "alpha":-2.10648, "fx":[84.23774,73.99829,61.47356,72.8633], "fy":[69.81662,80.66326,90.51284,81.51409]}, - {"t":0.40507, "x":5.82332, "y":2.73408, "heading":-0.0904, "vx":1.69532, "vy":1.77169, "omega":-2.87048, "ax":4.28732, "ay":4.78573, "alpha":0.25984, "fx":[71.52664,72.71666,74.32226,73.13899], "fy":[82.64922,81.5891,80.14076,81.23657]}, - {"t":0.43883, "x":5.88299, "y":2.79661, "heading":-0.1873, "vx":1.84004, "vy":1.93324, "omega":-2.86171, "ax":4.14871, "ay":4.73893, "alpha":4.01935, "fx":[50.2715,64.00829,91.587,76.40658], "fy":[96.93528,88.06907,59.29467,78.13239]}, - {"t":0.47258, "x":5.94746, "y":2.86457, "heading":-0.2839, "vx":1.98009, "vy":2.09321, "omega":-2.72603, "ax":3.35276, "ay":4.45626, "alpha":10.89643, "fx":[25.28838,13.354,107.25533,82.22057], "fy":[106.15393,106.70838,18.41288,71.92333]}, - {"t":0.50634, "x":6.01621, "y":2.93777, "heading":-0.37592, "vx":2.09326, "vy":2.24363, "omega":-2.35821, "ax":3.30318, "ay":4.30238, "alpha":12.02432, "fx":[28.45596,3.01676,107.80118,85.47042], "fy":[105.20955,107.17855,12.53243,67.80849]}, - {"t":0.5401, "x":6.08876, "y":3.01596, "heading":-0.45552, "vx":2.20476, "vy":2.38886, "omega":-1.95232, "ax":3.34209, "ay":4.14885, "alpha":12.64734, "fx":[32.24447,-0.90487,107.79129,88.26089], "fy":[103.88292,106.72178,7.90826,63.76982]}, - {"t":0.57385, "x":6.16508, "y":3.09896, "heading":-0.52143, "vx":2.31758, "vy":2.52891, "omega":-1.52539, "ax":3.35633, "ay":3.9557, "alpha":13.39265, "fx":[35.27119,-4.99371,107.32368,90.75967], "fy":[102.49235,105.60532,1.54191,59.50176]}, - {"t":0.60761, "x":6.24523, "y":3.18658, "heading":-0.57292, "vx":2.43088, "vy":2.66244, "omega":-1.07331, "ax":3.35561, "ay":3.71586, "alpha":14.08667, "fx":[37.90162,-8.02534,105.68447,92.75139], "fy":[100.69205,103.16598,-5.93213,54.89722]}, - {"t":0.64136, "x":6.3292, "y":3.27857, "heading":-0.60915, "vx":2.54415, "vy":2.78787, "omega":-0.5978, "ax":3.34078, "ay":3.34837, "alpha":14.30528, "fx":[40.52935,-7.08386,100.51418,93.34331], "fy":[96.84707,95.69831,-13.72679,49.00101]}, - {"t":0.67512, "x":6.41698, "y":3.37458, "heading":-0.62933, "vx":2.65692, "vy":2.9009, "omega":-0.11491, "ax":1.81758, "ay":-0.37365, "alpha":3.06665, "fx":[29.90176,20.3295,32.40234,41.03248], "fy":[5.72588,-8.80447,-18.05291,-4.29119]}, - {"t":0.70888, "x":6.5077, "y":3.47229, "heading":-0.63321, "vx":2.71827, "vy":2.88829, "omega":-0.0114, "ax":0.37865, "ay":-0.35326, "alpha":0.01104, "fx":[6.43482,6.40062,6.44659,6.48079], "fy":[-5.96873,-6.01518,-6.04882,-6.00237]}, - {"t":0.74263, "x":6.59968, "y":3.56959, "heading":-0.63359, "vx":2.73105, "vy":2.87636, "omega":-0.01102, "ax":-0.04307, "ay":0.04071, "alpha":-0.00042, "fx":[-0.73236,-0.73106,-0.73283,-0.73414], "fy":[0.69096,0.69273,0.69404,0.69226]}, - {"t":0.77639, "x":6.69184, "y":3.66671, "heading":-0.63396, "vx":2.7296, "vy":2.87774, "omega":-0.01104, "ax":-0.5397, "ay":0.45789, "alpha":-0.11947, "fx":[-9.11941,-8.74664,-9.24124,-9.61359], "fy":[7.35483,7.86024,8.2221,7.71734]}, - {"t":0.81014, "x":6.78367, "y":3.76411, "heading":-0.63434, "vx":2.71138, "vy":2.89319, "omega":-0.01507, "ax":-3.11184, "ay":-2.21952, "alpha":-11.67954, "fx":[-42.20876,-8.19689,-77.22652,-84.09353], "fy":[-77.96489,-55.04617,17.29493,-35.29735]}, - {"t":0.8439, "x":6.87343, "y":3.86051, "heading":-0.63484, "vx":2.60634, "vy":2.81827, "omega":-0.40933, "ax":-3.25197, "ay":-3.50799, "alpha":-14.7624, "fx":[-39.06778,13.77849,-102.55728,-93.41379], "fy":[-98.87048,-99.49557,10.88684,-51.20047]}, - {"t":0.87766, "x":6.95955, "y":3.95364, "heading":-0.64866, "vx":2.49657, "vy":2.69986, "omega":-0.90764, "ax":-3.18859, "ay":-3.65721, "alpha":-15.31521, "fx":[-37.55816,20.19117,-105.67133,-93.90978], "fy":[-101.26428,-103.18337,9.11055,-53.49543]}, - {"t":0.91141, "x":7.04201, "y":4.04269, "heading":-0.6793, "vx":2.38893, "vy":2.5764, "omega":-1.42462, "ax":-3.10468, "ay":-3.67428, "alpha":-15.91338, "fx":[-36.62462,26.4219,-106.6824,-94.35389], "fy":[-102.28121,-103.5993,9.77339,-53.88642]}, - {"t":0.94517, "x":7.12088, "y":4.12757, "heading":-0.72739, "vx":2.28413, "vy":2.45238, "omega":-1.9618, "ax":-3.70625, "ay":-4.32027, "alpha":-10.30673, "fx":[-45.62335,-10.9932,-104.16124,-91.39133], "fy":[-98.91931,-107.44207,-28.31794,-59.26683]}, - {"t":0.97892, "x":7.19587, "y":4.20789, "heading":-0.79361, "vx":2.15902, "vy":2.30654, "omega":-2.30971, "ax":-4.2332, "ay":-4.75289, "alpha":-2.44203, "fx":[-64.58305,-60.9058,-81.58757,-80.94542], "fy":[-87.91137,-90.26737,-72.09173,-73.1108]}, - {"t":1.01268, "x":7.26634, "y":4.28304, "heading":-0.87158, "vx":2.01613, "vy":2.1461, "omega":-2.39214, "ax":-4.3147, "ay":-4.7513, "alpha":0.64919, "fx":[-75.58229,-76.11092,-71.36476,-70.5093], "fy":[-78.81382,-78.35812,-82.71023,-83.39059]}, - {"t":1.04644, "x":7.33194, "y":4.35278, "heading":-0.95233, "vx":1.87048, "vy":1.98572, "omega":-2.37023, "ax":-4.32003, "ay":-4.70275, "alpha":2.45779, "fx":[-81.70891,-83.41018,-67.54619,-61.26485], "fy":[-72.56636,-70.79059,-86.08041,-90.53258]}, - {"t":1.08019, "x":7.39262, "y":4.41713, "heading":-1.03234, "vx":1.72465, "vy":1.82697, "omega":-2.28726, "ax":-4.30853, "ay":-4.64923, "alpha":3.66074, "fx":[-85.01306,-87.95941,-66.44973,-53.72538], "fy":[-68.76032,-65.20812,-87.05604,-95.30356]}, - {"t":1.11395, "x":7.44838, "y":4.47615, "heading":-1.10955, "vx":1.57921, "vy":1.67003, "omega":-2.16369, "ax":-4.29646, "ay":-4.60018, "alpha":4.47907, "fx":[-86.56503,-91.20043,-66.63958,-47.92106], "fy":[-66.8684,-60.70022,-86.99187,-98.43016]}, - {"t":1.1477, "x":7.49924, "y":4.52991, "heading":-1.18258, "vx":1.43418, "vy":1.51475, "omega":-2.0125, "ax":-4.28734, "ay":-4.55918, "alpha":5.03258, "fx":[-86.93664,-93.67892,-67.46376,-43.62668], "fy":[-66.44113,-56.88027,-86.41064,-100.46946]}, - {"t":1.18146, "x":7.54521, "y":4.57844, "heading":-1.25052, "vx":1.28946, "vy":1.36085, "omega":-1.84262, "ax":-4.28042, "ay":-4.52732, "alpha":5.4055, "fx":[-86.46149,-95.64916,-68.5867,-40.53771], "fy":[-67.10372,-53.56303,-85.56354,-101.80363]}, - {"t":1.21522, "x":7.5863, "y":4.6218, "heading":-1.31272, "vx":1.14497, "vy":1.20802, "omega":-1.66015, "ax":-4.27396, "ay":-4.50413, "alpha":5.66102, "fx":[-85.36306,-97.24969,-69.82071,-38.36184], "fy":[-68.53327,-50.64938,-84.59143,-102.68169]}, - {"t":1.24897, "x":7.62251, "y":4.66001, "heading":-1.36876, "vx":1.0007, "vy":1.05598, "omega":-1.46906, "ax":-4.26655, "ay":-4.48822, "alpha":5.84549, "fx":[-83.8184,-98.56557,-71.05499,-36.85256], "fy":[-70.44633,-48.08062,-83.58256,-103.26361]}, - {"t":1.28273, "x":7.65386, "y":4.6931, "heading":-1.41835, "vx":0.85668, "vy":0.90448, "omega":-1.27174, "ax":-4.25753, "ay":-4.47781, "alpha":5.99078, "fx":[-81.9883,-99.65382,-72.22174,-35.81386], "fy":[-72.59652,-45.81871,-82.59698,-103.65316]}, - {"t":1.31648, "x":7.68035, "y":4.72108, "heading":-1.46127, "vx":0.71296, "vy":0.75333, "omega":-1.06951, "ax":-4.24693, "ay":-4.47114, "alpha":6.1166, "fx":[-80.02871,-100.55511,-73.27816,-35.09396], "fy":[-74.77671,-43.83718,-81.6782,-103.9193]}, - {"t":1.35024, "x":7.702, "y":4.74396, "heading":-1.49738, "vx":0.5696, "vy":0.6024, "omega":-0.86304, "ax":-4.23528, "ay":-4.46666, "alpha":6.23314, "fx":[-78.09129,-101.29966,-74.19641,-34.5763], "fy":[-76.82095,-42.11665,-80.8593,-104.10933]}, - {"t":1.384, "x":7.71882, "y":4.76175, "heading":-1.52651, "vx":0.42663, "vy":0.45162, "omega":-0.65263, "ax":-4.22345, "ay":-4.46317, "alpha":6.34376, "fx":[-76.31906,-101.91042,-74.95764,-34.17131], "fy":[-78.60298,-40.64249,-80.16639,-104.2568]}, - {"t":1.41775, "x":7.73081, "y":4.77445, "heading":-1.54854, "vx":0.28407, "vy":0.30096, "omega":-0.43849, "ax":-4.21236, "ay":-4.45982, "alpha":6.4477, "fx":[-74.84109,-102.40504,-75.54846,-33.80985], "fy":[-80.03076,-39.40366,-79.62043,-104.38617]}, - {"t":1.45151, "x":7.738, "y":4.78207, "heading":-1.56334, "vx":0.14187, "vy":0.15042, "omega":-0.22084, "ax":-4.20293, "ay":-4.45604, "alpha":6.54238, "fx":[-73.76891,-102.79698,-75.95871,-33.43827], "fy":[-81.03769,-38.39205,-79.23838,-104.51554]}, - {"t":1.48526, "x":7.74039, "y":4.78461, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":5.48353, "y":2.38551, "heading":-2.58309, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.0691, "ay":4.07779, "alpha":-10.17511, "fx":[13.52822,105.7504,99.29536,58.28315], "fy":[108.85541,28.81407,46.76423,93.01452]}, + {"t":0.03376, "x":5.48585, "y":2.38783, "heading":-2.58309, "vx":0.13736, "vy":0.13765, "omega":-0.34347, "ax":4.08039, "ay":4.1105, "alpha":-9.92156, "fx":[14.95102,105.17135,99.02134,58.48162], "fy":[108.65779,30.81017,47.32394,92.88163]}, + {"t":0.06751, "x":5.49281, "y":2.39482, "heading":-2.59468, "vx":0.27509, "vy":0.2764, "omega":-0.67838, "ax":4.09982, "ay":4.14849, "alpha":-9.57092, "fx":[16.7377,104.24325,98.85999,59.10607], "fy":[108.38545,33.75799,47.63874,92.47605]}, + {"t":0.10127, "x":5.50443, "y":2.40651, "heading":-2.61758, "vx":0.41349, "vy":0.41644, "omega":-1.00146, "ax":4.12523, "ay":4.19337, "alpha":-9.12064, "fx":[18.9131,102.85426,98.77876,60.12972], "fy":[108.01517,37.71349,47.781,91.80268]}, + {"t":0.13502, "x":5.52074, "y":2.42296, "heading":-2.65139, "vx":0.55274, "vy":0.55799, "omega":-1.30933, "ax":4.15372, "ay":4.24691, "alpha":-8.56987, "fx":[21.52336,100.84781,98.7285,61.51452], "fy":[107.5127,42.72211,47.85285,90.86735]}, + {"t":0.16878, "x":5.54177, "y":2.44421, "heading":-2.69558, "vx":0.69295, "vy":0.70135, "omega":-1.59862, "ax":4.18183, "ay":4.31003, "alpha":-7.92522, "fx":[24.63224,98.04574,98.63918,63.20958], "fy":[106.82897,48.74328,47.99707,89.68026]}, + {"t":0.20254, "x":5.56754, "y":2.47034, "heading":-2.74955, "vx":0.83411, "vy":0.84684, "omega":-1.86614, "ax":4.20632, "ay":4.38174, "alpha":-7.20467, "fx":[28.3201,94.31343,98.41086,65.14913], "fy":[105.89418,55.55938,48.41387,88.26086]}, + {"t":0.23629, "x":5.59809, "y":2.50143, "heading":-2.81254, "vx":0.9761, "vy":0.99475, "omega":-2.10934, "ax":4.2257, "ay":4.45849, "alpha":-6.43318, "fx":[32.68985,89.67801,97.8946,67.24906], "fy":[104.6069,62.71176,49.38701,86.64489]}, + {"t":0.27005, "x":5.63345, "y":2.53754, "heading":-2.88374, "vx":1.11874, "vy":1.14525, "omega":-2.3265, "ax":4.24165, "ay":4.53513, "alpha":-5.62253, "fx":[37.88472,84.46105,96.85165,69.3996], "fy":[102.81227,69.53292,51.32378,84.89609]}, + {"t":0.3038, "x":5.67363, "y":2.57879, "heading":-2.96227, "vx":1.26192, "vy":1.29833, "omega":-2.51629, "ax":4.25879, "ay":4.60761, "alpha":-4.73544, "fx":[44.12461,79.32583,94.86566,71.44701], "fy":[100.25513,75.30164,54.81043,83.12928]}, + {"t":0.33756, "x":5.71865, "y":2.62524, "heading":-3.04721, "vx":1.40568, "vy":1.45387, "omega":-2.67614, "ax":4.28046, "ay":4.67561, "alpha":-3.64559, "fx":[51.77434,75.16174,91.15809,73.14373], "fy":[96.47203,79.42814,60.65927,81.56344]}, + {"t":0.37131, "x":5.76854, "y":2.67698, "heading":-3.13755, "vx":1.55017, "vy":1.6117, "omega":-2.7992, "ax":4.30007, "ay":4.74003, "alpha":-2.10699, "fx":[61.4706,72.86244,84.24019,73.99887], "fy":[90.51487,81.51485,69.81368,80.66276]}, + {"t":0.40507, "x":5.82332, "y":2.73408, "heading":3.05115, "vx":1.69533, "vy":1.7717, "omega":-2.87032, "ax":4.28733, "ay":4.78573, "alpha":0.25893, "fx":[74.31747,73.13839,71.53163,72.71741], "fy":[80.14524,81.23711,82.64493,81.58851]}, + {"t":0.43883, "x":5.88299, "y":2.79662, "heading":2.95426, "vx":1.84005, "vy":1.93325, "omega":-2.86158, "ax":4.14879, "ay":4.73898, "alpha":4.01783, "fx":[91.5806,76.40598,50.28036,64.01176], "fy":[59.30462,78.13296,96.9307,88.06679]}, + {"t":0.47258, "x":5.94747, "y":2.86457, "heading":2.85766, "vx":1.98009, "vy":2.09322, "omega":-2.72596, "ax":3.353, "ay":4.45633, "alpha":10.89508, "fx":[107.25402,82.22066,25.29354,13.36613], "fy":[18.42043,71.92322,106.1527,106.70729]}, + {"t":0.50634, "x":6.01622, "y":2.93777, "heading":2.76564, "vx":2.09328, "vy":2.24364, "omega":-2.35818, "ax":3.30319, "ay":4.30238, "alpha":12.02434, "fx":[107.80105,85.4709,28.45723,3.0158], "fy":[12.53331,67.80788,105.20922,107.17874]}, + {"t":0.54009, "x":6.08876, "y":3.01596, "heading":2.68604, "vx":2.20478, "vy":2.38888, "omega":-1.95229, "ax":3.34209, "ay":4.14884, "alpha":12.64743, "fx":[107.79121,88.26137,32.24544,-0.90621], "fy":[7.90864,63.76914,103.88263,106.72191]}, + {"t":0.57385, "x":6.16509, "y":3.09896, "heading":2.62014, "vx":2.31759, "vy":2.52892, "omega":-1.52536, "ax":3.35632, "ay":3.95568, "alpha":13.39279, "fx":[107.32358,90.76015,35.272,-4.99527], "fy":[1.5418,59.501,102.49207,105.60539]}, + {"t":0.60761, "x":6.24523, "y":3.18658, "heading":2.56865, "vx":2.43089, "vy":2.66245, "omega":-1.07328, "ax":3.3556, "ay":3.71584, "alpha":14.08685, "fx":[105.68424,92.75183,37.90231,-8.02703], "fy":[-5.93269,54.89636,100.69176,103.16596]}, + {"t":0.64136, "x":6.3292, "y":3.27857, "heading":2.53242, "vx":2.54416, "vy":2.78788, "omega":-0.59776, "ax":3.34076, "ay":3.34833, "alpha":14.30544, "fx":[100.51336,93.34354,40.52994,-7.08546], "fy":[-13.72765,48.99995,96.84654,95.69791]}, + {"t":0.67512, "x":6.41698, "y":3.37459, "heading":2.51224, "vx":2.65693, "vy":2.90091, "omega":-0.11487, "ax":1.81717, "ay":-0.37382, "alpha":3.06543, "fx":[32.39433,41.02199,29.89525,20.32632], "fy":[-18.05089,-4.29512,5.71771,-8.80603]}, + {"t":0.70887, "x":6.50771, "y":3.4723, "heading":2.50836, "vx":2.71827, "vy":2.88829, "omega":-0.0114, "ax":0.37858, "ay":-0.35319, "alpha":0.01104, "fx":[6.44544,6.47963,6.43368,6.3995], "fy":[-6.04775,-6.00133,-5.9677,-6.01413]}, + {"t":0.74263, "x":6.59968, "y":3.56959, "heading":2.50798, "vx":2.73105, "vy":2.87637, "omega":-0.01102, "ax":-0.04307, "ay":0.04071, "alpha":-0.00042, "fx":[-0.73289,-0.73419,-0.73241,-0.73111], "fy":[0.69409,0.69231,0.69101,0.69278]}, + {"t":0.77639, "x":6.69184, "y":3.66671, "heading":2.50761, "vx":2.7296, "vy":2.87774, "omega":-0.01104, "ax":-0.53965, "ay":0.45784, "alpha":-0.11946, "fx":[-9.24025,-9.61259,-9.11845,-8.74569], "fy":[8.22121,7.71649,7.35399,7.85935]}, + {"t":0.81014, "x":6.78368, "y":3.76411, "heading":2.50723, "vx":2.71138, "vy":2.8932, "omega":-0.01507, "ax":-3.11176, "ay":-2.21957, "alpha":-11.67971, "fx":[-77.22549,-84.09319,-42.20817,-8.19368], "fy":[17.29431,-35.29756,-77.96533,-55.04871]}, + {"t":0.8439, "x":6.87343, "y":3.86051, "heading":2.50673, "vx":2.60634, "vy":2.81827, "omega":-0.40933, "ax":-3.25195, "ay":-3.50798, "alpha":-14.76257, "fx":[-102.55712,-93.41407,-39.06809,13.78026], "fy":[10.88714,-51.19999,-98.87043,-99.49579]}, + {"t":0.87765, "x":6.95956, "y":3.95364, "heading":2.49291, "vx":2.49657, "vy":2.69986, "omega":-0.90765, "ax":-3.18858, "ay":-3.65719, "alpha":-15.31538, "fx":[-105.6712,-93.91015,-37.55856,20.19268], "fy":[9.11117,-53.4948,-101.26418,-103.1833]}, + {"t":0.91141, "x":7.04201, "y":4.0427, "heading":2.46227, "vx":2.38894, "vy":2.57641, "omega":-1.42464, "ax":-3.10468, "ay":-3.67425, "alpha":-15.91351, "fx":[-106.68227,-94.35433,-36.62514,26.42291], "fy":[9.77417,-53.88568,-102.28104,-103.59918]}, + {"t":0.94517, "x":7.12088, "y":4.12757, "heading":2.41418, "vx":2.28413, "vy":2.45238, "omega":-1.96181, "ax":-3.70643, "ay":-4.3204, "alpha":-10.30505, "fx":[-104.15854,-91.39059,-45.62704,-11.00485], "fy":[-28.32828,-59.26797,-98.91761,-107.44101]}, + {"t":0.97892, "x":7.19588, "y":4.20789, "heading":2.34796, "vx":2.15902, "vy":2.30654, "omega":-2.30967, "ax":-4.23323, "ay":-4.75289, "alpha":-2.44156, "fx":[-81.58591,-80.94453,-64.58497,-60.9085], "fy":[-72.09369,-73.11179,-87.90997,-90.2656]}, + {"t":1.01268, "x":7.26634, "y":4.28304, "heading":2.26999, "vx":2.01612, "vy":2.1461, "omega":-2.39209, "ax":-4.31471, "ay":-4.75129, "alpha":0.64937, "fx":[-71.36446,-70.50862,-75.58302,-76.11184], "fy":[-82.71052,-83.39118,-78.81313,-78.35725]}, + {"t":1.04643, "x":7.33194, "y":4.35278, "heading":2.18925, "vx":1.87048, "vy":1.98572, "omega":-2.37016, "ax":-4.32004, "ay":-4.70275, "alpha":2.45783, "fx":[-67.54639,-61.26459,-81.70896,-83.41054], "fy":[-86.08026,-90.53277,-72.56631,-70.79018]}, + {"t":1.08019, "x":7.39262, "y":4.41713, "heading":2.10924, "vx":1.72465, "vy":1.82697, "omega":-2.2872, "ax":-4.30854, "ay":-4.64923, "alpha":3.6607, "fx":[-66.45012,-53.72557,-85.01272,-87.95949], "fy":[-87.05576,-95.30346,-68.76075,-65.20801]}, + {"t":1.11394, "x":7.44838, "y":4.47615, "heading":2.03203, "vx":1.57921, "vy":1.67003, "omega":-2.16363, "ax":-4.29646, "ay":-4.60018, "alpha":4.47897, "fx":[-66.64,-47.92162,-86.56445,-91.20035], "fy":[-86.99155,-98.42989,-66.86915,-60.70034]}, + {"t":1.1477, "x":7.49924, "y":4.52991, "heading":1.959, "vx":1.43418, "vy":1.51475, "omega":-2.01244, "ax":-4.28735, "ay":-4.55919, "alpha":5.03244, "fx":[-67.46416,-43.62752,-86.93593,-93.67872], "fy":[-86.41033,-100.4691,-66.44207,-56.88059]}, + {"t":1.18146, "x":7.54521, "y":4.57844, "heading":1.89107, "vx":1.28946, "vy":1.36085, "omega":-1.84256, "ax":-4.28043, "ay":-4.52734, "alpha":5.40535, "fx":[-68.58705,-40.53873,-86.46071,-95.64888], "fy":[-85.56327,-101.80323,-67.10474,-53.56353]}, + {"t":1.21521, "x":7.5863, "y":4.6218, "heading":1.82887, "vx":1.14497, "vy":1.20803, "omega":-1.6601, "ax":-4.27396, "ay":-4.50414, "alpha":5.66086, "fx":[-69.82098,-38.36297,-85.36227,-97.24935], "fy":[-84.5912,-102.68127,-68.53426,-50.65005]}, + {"t":1.24897, "x":7.62251, "y":4.66001, "heading":1.77283, "vx":1.0007, "vy":1.05598, "omega":-1.46901, "ax":-4.26656, "ay":-4.48823, "alpha":5.84532, "fx":[-71.0552,-36.85375,-83.81765,-98.56517], "fy":[-83.58238,-103.26318,-70.44723,-48.08143]}, + {"t":1.28272, "x":7.65386, "y":4.6931, "heading":1.72324, "vx":0.85667, "vy":0.90448, "omega":-1.2717, "ax":-4.25754, "ay":-4.47783, "alpha":5.99061, "fx":[-72.22189,-35.81508,-81.98763,-99.65338], "fy":[-82.59685,-103.65274,-72.59728,-45.81965]}, + {"t":1.31648, "x":7.68035, "y":4.72108, "heading":1.68031, "vx":0.71296, "vy":0.75333, "omega":-1.06948, "ax":-4.24693, "ay":-4.47116, "alpha":6.11644, "fx":[-73.27825,-35.09519,-80.02816,-100.55465], "fy":[-81.67812,-103.91889,-74.77731,-43.83824]}, + {"t":1.35024, "x":7.702, "y":4.74396, "heading":1.64421, "vx":0.5696, "vy":0.6024, "omega":-0.86301, "ax":-4.23529, "ay":-4.46667, "alpha":6.23298, "fx":[-74.19645,-34.57753,-78.09088,-101.29917], "fy":[-80.85927,-104.10893,-76.82138,-42.11782]}, + {"t":1.38399, "x":7.71882, "y":4.76175, "heading":1.61508, "vx":0.42663, "vy":0.45162, "omega":-0.65261, "ax":-4.22345, "ay":-4.46318, "alpha":6.34359, "fx":[-74.95764,-34.17254,-76.31878,-101.90992], "fy":[-80.16639,-104.2564,-78.60327,-40.64375]}, + {"t":1.41775, "x":7.73081, "y":4.77445, "heading":1.59305, "vx":0.28407, "vy":0.30096, "omega":-0.43848, "ax":-4.21237, "ay":-4.45984, "alpha":6.44754, "fx":[-75.54842,-33.81107,-74.84094,-102.40453], "fy":[-79.62047,-104.38577,-80.03092,-39.40499]}, + {"t":1.4515, "x":7.738, "y":4.78207, "heading":1.57825, "vx":0.14187, "vy":0.15042, "omega":-0.22084, "ax":-4.20294, "ay":-4.45605, "alpha":6.54221, "fx":[-75.95866,-33.43949,-73.76884,-102.79646], "fy":[-79.23844,-104.51515,-81.03776,-38.39344]}, + {"t":1.48526, "x":7.74039, "y":4.78461, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/F_PATH_8.traj b/src/main/deploy/choreo/F_PATH_8.traj index e46d47d3..cef87d7d 100644 --- a/src/main/deploy/choreo/F_PATH_8.traj +++ b/src/main/deploy/choreo/F_PATH_8.traj @@ -3,8 +3,8 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":7.740394592285156, "y":4.784609317779541, "heading":-1.5707963267948966, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":6.061971664428711, "y":6.538893699645996, "heading":-2.5127963756685157, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":7.740394592285156, "y":4.784609317779541, "heading":1.5707963267948966, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":6.061971664428711, "y":6.538893699645996, "heading":0.6108652381980153, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -13,8 +13,8 @@ }, "params":{ "waypoints":[ - {"x":{"exp":"7.740394592285156 m", "val":7.740394592285156}, "y":{"exp":"4.784609317779541 m", "val":4.784609317779541}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"6.061971664428711 m", "val":6.061971664428711}, "y":{"exp":"6.538893699645996 m", "val":6.538893699645996}, "heading":{"exp":"-2.5127963756685157 rad", "val":-2.5127963756685157}, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"7.740394592285156 m", "val":7.740394592285156}, "y":{"exp":"4.784609317779541 m", "val":4.784609317779541}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"6.061971664428711 m", "val":6.061971664428711}, "y":{"exp":"6.538893699645996 m", "val":6.538893699645996}, "heading":{"exp":"35 deg", "val":0.6108652381980153}, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -26,44 +26,44 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,1.23464], + "waypoints":[0.0,1.2349], "samples":[ - {"t":0.0, "x":7.74039, "y":4.78461, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-4.39722, "ay":4.60767, "alpha":-3.34929, "fx":[-91.67478,-75.18501,-56.19697,-76.12526], "fy":[60.30966,79.87288,94.2534,79.06454]}, - {"t":0.03528, "x":7.73766, "y":4.78748, "heading":-1.5708, "vx":-0.15511, "vy":0.16254, "omega":-0.11815, "ax":-4.39888, "ay":4.60889, "alpha":-3.29802, "fx":[-91.45621,-75.19481,-56.52452,-76.119], "fy":[60.62542,79.84975,94.04761,79.06054]}, - {"t":0.07055, "x":7.72945, "y":4.79608, "heading":-1.57496, "vx":-0.31029, "vy":0.32512, "omega":-0.23449, "ax":-4.40079, "ay":4.61019, "alpha":-3.23931, "fx":[-91.19464,-75.30051,-56.87767,-76.05202], "fy":[61.0012,79.73436,93.82321,79.11349]}, - {"t":0.10583, "x":7.71577, "y":4.81041, "heading":-1.58324, "vx":-0.46553, "vy":0.48774, "omega":-0.34875, "ax":-4.40299, "ay":4.61162, "alpha":-3.17159, "fx":[-90.88325,-75.4927,-57.27013,-75.9281], "fy":[61.44499,79.53452,93.57101,79.21914]}, - {"t":0.1411, "x":7.69661, "y":4.83049, "heading":-1.59554, "vx":-0.62084, "vy":0.65042, "omega":-0.46063, "ax":-4.40549, "ay":4.61322, "alpha":-3.09282, "fx":[-90.5125,-75.75947,-57.72028,-75.75202], "fy":[61.96792,79.25987,93.27851,79.37199]}, - {"t":0.17638, "x":7.67196, "y":4.8563, "heading":-1.61179, "vx":-0.77625, "vy":0.81315, "omega":-0.56973, "ax":-4.40833, "ay":4.61503, "alpha":-3.00017, "fx":[-90.0691,-76.08571,-58.2525,-75.53008], "fy":[62.58528,78.92283,92.92858,79.5648]}, - {"t":0.21165, "x":7.64184, "y":4.88786, "heading":-1.63188, "vx":-0.93175, "vy":0.97595, "omega":-0.67557, "ax":-4.41155, "ay":4.61712, "alpha":-2.88958, "fx":[-89.53451,-76.45201,-58.89946,-75.27087], "fy":[63.31789,78.53996,92.49756,79.78787]}, - {"t":0.24693, "x":7.60623, "y":4.92516, "heading":-1.65572, "vx":-1.08737, "vy":1.13882, "omega":-0.7775, "ax":-4.41523, "ay":4.61954, "alpha":-2.75508, "fx":[-88.88215,-76.83299,-59.70547,-74.98665], "fy":[64.19474,78.13381,91.95193,80.02778]}, - {"t":0.2822, "x":7.56512, "y":4.9682, "heading":-1.68314, "vx":-1.24312, "vy":1.30178, "omega":-0.87468, "ax":-4.41946, "ay":4.62238, "alpha":-2.58757, "fx":[-88.07259,-77.19479,-60.7322,-74.69558], "fy":[65.25738,77.73583,91.24271,80.26521]}, - {"t":0.31748, "x":7.51852, "y":5.017, "heading":-1.714, "vx":-1.39902, "vy":1.46483, "omega":-0.96596, "ax":-4.42437, "ay":4.62566, "alpha":-2.37278, "fx":[-87.04423,-77.49072,-62.0682,-74.42593], "fy":[66.56816,77.39077,90.29508,80.47077]}, - {"t":0.35275, "x":7.46642, "y":5.07155, "heading":-1.74807, "vx":-1.55509, "vy":1.62801, "omega":-1.04966, "ax":-4.43009, "ay":4.62935, "alpha":-2.08733, "fx":[-85.69416,-77.65353,-63.84611,-74.22432], "fy":[68.2264,77.16411,88.9883,80.59653]}, - {"t":0.38803, "x":7.4088, "y":5.13186, "heading":-1.7851, "vx":-1.71136, "vy":1.79131, "omega":-1.12329, "ax":-4.43665, "ay":4.63305, "alpha":-1.69069, "fx":[-83.83498,-77.58034,-66.27526,-74.1741], "fy":[70.40248,77.15528,87.11318,80.55665]}, - {"t":0.4233, "x":7.34567, "y":5.19793, "heading":-1.82472, "vx":-1.86787, "vy":1.95474, "omega":-1.18293, "ax":-4.44353, "ay":4.63543, "alpha":-1.10648, "fx":[-81.08354,-77.10041,-69.7075,-74.4414], "fy":[73.41727,77.52339,84.27272,80.17624]}, - {"t":0.45858, "x":7.27702, "y":5.26977, "heading":-1.86645, "vx":-2.02462, "vy":2.11826, "omega":-1.22197, "ax":-4.44761, "ay":4.63169, "alpha":-0.17161, "fx":[-76.51863,-75.89819,-74.77683,-75.41638], "fy":[77.95062,78.54229,79.61762,79.02427]}, - {"t":0.49386, "x":7.20283, "y":5.34738, "heading":-1.90956, "vx":-2.18151, "vy":2.28164, "omega":-1.22802, "ax":-4.43256, "ay":4.60101, "alpha":1.54039, "fx":[-67.3082,-73.30115,-82.68197,-78.29512], "fy":[85.65646,80.72992,71.01819,75.64285]}, - {"t":0.52913, "x":7.12312, "y":5.43072, "heading":-1.95288, "vx":-2.33787, "vy":2.44394, "omega":-1.17368, "ax":-4.29931, "ay":4.37661, "alpha":5.69984, "fx":[-40.59475,-67.58614,-95.26812,-89.07121], "fy":[100.30535,85.16282,52.05223,60.25915]}, - {"t":0.56441, "x":7.03798, "y":5.51966, "heading":-1.99428, "vx":-2.48953, "vy":2.59833, "omega":-0.97262, "ax":-3.86221, "ay":3.37396, "alpha":12.975, "fx":[1.46992,-60.3707,-102.32563,-101.55376], "fy":[106.16856,89.23546,32.5833,1.57314]}, - {"t":0.59968, "x":6.94776, "y":5.61341, "heading":-2.02859, "vx":-2.62577, "vy":2.71735, "omega":-0.51492, "ax":-0.01618, "ay":0.09252, "alpha":0.09239, "fx":[0.04605,-0.38427,-0.59634,-0.166], "fy":[1.68296,1.89485,1.46468,1.25274]}, - {"t":0.63496, "x":6.85512, "y":5.70933, "heading":-2.04675, "vx":-2.62634, "vy":2.72061, "omega":-0.51166, "ax":3.80731, "ay":-3.35795, "alpha":-13.42152, "fx":[-3.25342,58.38795,101.74157,102.16887], "fy":[-105.97819,-90.53055,-34.4909,2.52864]}, - {"t":0.67023, "x":6.76484, "y":5.80321, "heading":-2.0648, "vx":-2.49203, "vy":2.60216, "omega":-0.98511, "ax":4.33216, "ay":-4.43784, "alpha":-4.88212, "fx":[47.3847,66.40692,91.99519,88.96844], "fy":[-97.27079,-86.05501,-57.6973,-60.92258]}, - {"t":0.70551, "x":6.67963, "y":5.89224, "heading":-2.09955, "vx":-2.33922, "vy":2.44561, "omega":-1.15733, "ax":4.43799, "ay":-4.60622, "alpha":-1.2117, "fx":[69.64503,72.7109,80.77542,78.82434], "fy":[-83.77828,-81.25516,-73.20905,-75.15954]}, - {"t":0.74078, "x":6.59988, "y":5.97564, "heading":-2.14038, "vx":-2.18266, "vy":2.28313, "omega":-1.20007, "ax":4.44799, "ay":-4.63147, "alpha":0.28652, "fx":[76.93405,76.45554,74.35225,74.89429], "fy":[-77.55831,-78.00692,-80.01979,-79.53497]}, - {"t":0.77606, "x":6.52565, "y":6.0533, "heading":-2.18271, "vx":-2.02576, "vy":2.11975, "omega":-1.18996, "ax":4.44394, "ay":-4.63531, "alpha":1.11384, "fx":[80.24185,79.07386,70.46076,72.58411], "fy":[-74.3591,-75.5261,-83.63396,-81.86213]}, - {"t":0.81133, "x":6.45696, "y":6.12519, "heading":-2.22469, "vx":-1.869, "vy":1.95624, "omega":-1.15067, "ax":4.43784, "ay":-4.6339, "alpha":1.64399, "fx":[81.98643,81.07025,67.96273,70.92617], "fy":[-72.57339,-73.50343,-85.78312,-83.42518]}, - {"t":0.84661, "x":6.39379, "y":6.19132, "heading":-2.26528, "vx":-1.71245, "vy":1.79278, "omega":-1.09268, "ax":4.43195, "ay":-4.63111, "alpha":2.01519, "fx":[82.97093,82.66658,66.29937,69.6082], "fy":[-71.54248,-71.79684,-87.14916,-84.60713]}, - {"t":0.88188, "x":6.33614, "y":6.25168, "heading":-2.30382, "vx":-1.55611, "vy":1.62941, "omega":-1.02159, "ax":4.42669, "ay":-4.62814, "alpha":2.29047, "fx":[83.53682,83.97764,65.17043,68.50235], "fy":[-70.95061,-70.33175,-88.05102,-85.56018]}, - {"t":0.91716, "x":6.284, "y":6.30627, "heading":-2.33986, "vx":-1.39996, "vy":1.46615, "omega":-0.9408, "ax":4.42207, "ay":-4.62538, "alpha":2.50279, "fx":[83.85477,85.07096,64.39929,67.54782], "fy":[-70.62697,-69.06377,-88.65837,-86.35645]}, - {"t":0.95244, "x":6.23737, "y":6.35511, "heading":-2.37304, "vx":-1.24397, "vy":1.30299, "omega":-0.85251, "ax":4.41802, "ay":-4.62294, "alpha":2.67119, "fx":[84.02053,85.99062,63.87353,66.71237], "fy":[-70.47041,-67.96319,-89.07107,-87.0347]}, - {"t":0.98771, "x":6.19623, "y":6.3982, "heading":-2.40312, "vx":-1.08812, "vy":1.13991, "omega":-0.75828, "ax":4.41446, "ay":-4.62082, "alpha":2.8076, "fx":[84.09269,86.76783,63.5167,65.97744], "fy":[-70.41674,-67.008,-89.35293,-87.61784]}, - {"t":1.02299, "x":6.1606, "y":6.43554, "heading":-2.42987, "vx":-0.9324, "vy":0.97691, "omega":-0.65924, "ax":4.41132, "ay":-4.619, "alpha":2.92001, "fx":[84.10958,87.426,63.27392,65.33154], "fy":[-70.42299,-66.18065,-89.54757,-88.12057]}, - {"t":1.05826, "x":6.13045, "y":6.46713, "heading":-2.45312, "vx":-0.77679, "vy":0.81397, "omega":-0.55624, "ax":4.40854, "ay":-4.61744, "alpha":3.01405, "fx":[84.09764,87.9834,63.10413,64.7671], "fy":[-70.45914,-65.46653,-89.68644,-88.55289]}, - {"t":1.09354, "x":6.10579, "y":6.49297, "heading":-2.47274, "vx":-0.62128, "vy":0.65109, "omega":-0.44992, "ax":4.40609, "ay":-4.61607, "alpha":3.09384, "fx":[84.07583,88.45461,62.97567,64.27889], "fy":[-70.50355,-64.85318,-89.7932,-88.92195]}, - {"t":1.12881, "x":6.08662, "y":6.51306, "heading":-2.48861, "vx":-0.46585, "vy":0.48826, "omega":-0.34078, "ax":4.4039, "ay":-4.61485, "alpha":3.16251, "fx":[84.05823,88.85133,62.86359,63.86317], "fy":[-70.54019,-64.33002,-89.8861,-89.23302]}, - {"t":1.16409, "x":6.07292, "y":6.52741, "heading":-2.50063, "vx":-0.3105, "vy":0.32547, "omega":-0.22922, "ax":4.40195, "ay":-4.61376, "alpha":3.22246, "fx":[84.05549,89.18294,62.74806,63.51726], "fy":[-70.55695,-63.8882,-89.97951,-89.49003]}, - {"t":1.19936, "x":6.06471, "y":6.53602, "heading":-2.50872, "vx":-0.15522, "vy":0.16272, "omega":-0.11555, "ax":4.40021, "ay":-4.61274, "alpha":3.27558, "fx":[84.07578,89.45683,62.61327,63.23929], "fy":[-70.54449,-63.52053,-90.0847,-89.69585]}, - {"t":1.23464, "x":6.06197, "y":6.53889, "heading":-2.5128, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":7.74039, "y":4.78461, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-4.39436, "ay":4.60526, "alpha":-3.42343, "fx":[-55.71731,-76.12844,-91.98002,-75.16139], "fy":[94.53786,79.06205,59.84323,79.89339]}, + {"t":0.03528, "x":7.73766, "y":4.78748, "heading":1.5708, "vx":-0.15505, "vy":0.16249, "omega":-0.12079, "ax":-4.39612, "ay":4.60655, "alpha":-3.37085, "fx":[-56.05497,-76.12234,-91.75752,-75.17216], "fy":[94.32835,79.05791,60.16853,79.86927]}, + {"t":0.07057, "x":7.72945, "y":4.79608, "heading":1.56653, "vx":-0.31015, "vy":0.32502, "omega":-0.23972, "ax":-4.39816, "ay":4.60792, "alpha":-3.3106, "fx":[-56.41835,-76.05305,-91.49063,-75.28401], "fy":[94.10021,79.1131,60.55647,79.74805]}, + {"t":0.10585, "x":7.71577, "y":4.81041, "heading":1.55808, "vx":-0.46533, "vy":0.4876, "omega":-0.35653, "ax":-4.40051, "ay":4.60943, "alpha":-3.24109, "fx":[-56.82181,-75.92451,-91.1724,-75.48689], "fy":[93.84399,79.22319,61.01522,79.53804]}, + {"t":0.14113, "x":7.69661, "y":4.83049, "heading":1.5455, "vx":-0.6206, "vy":0.65024, "omega":-0.47089, "ax":-4.40318, "ay":4.61111, "alpha":-3.16021, "fx":[-57.28453,-75.74174,-90.79304,-75.76812], "fy":[93.54674,79.38241,61.55622,79.24949]}, + {"t":0.17641, "x":7.67198, "y":4.8563, "heading":1.52888, "vx":-0.77596, "vy":0.81293, "omega":-0.58239, "ax":-4.40622, "ay":4.61302, "alpha":-3.06507, "fx":[-57.83202,-75.51133,-90.33897,-76.11159], "fy":[93.19076,79.58319,62.19515,78.89565]}, + {"t":0.2117, "x":7.64186, "y":4.88785, "heading":1.50833, "vx":-0.93142, "vy":0.97569, "omega":-0.69053, "ax":-4.40966, "ay":4.61522, "alpha":-2.95149, "fx":[-58.49842,-75.24233,-89.79114,-76.49663], "fy":[92.75153,79.81537,62.95345,78.49413]}, + {"t":0.24698, "x":7.60625, "y":4.92515, "heading":1.48397, "vx":-1.08701, "vy":1.13853, "omega":-0.79467, "ax":-4.4136, "ay":4.61779, "alpha":-2.81327, "fx":[-59.33004,-74.94762,-89.12227,-76.89628], "fy":[92.19428,80.06487,63.86092,78.06901]}, + {"t":0.28226, "x":7.56515, "y":4.96819, "heading":1.45593, "vx":-1.24273, "vy":1.30146, "omega":-0.89393, "ax":-4.41812, "ay":4.6208, "alpha":-2.64099, "fx":[-60.39127,-74.64637,-88.29184,-77.27463], "fy":[91.46818,80.31141,64.9603,77.65381]}, + {"t":0.31755, "x":7.51855, "y":5.01699, "heading":1.42439, "vx":-1.39862, "vy":1.4645, "omega":-0.98711, "ax":-4.42338, "ay":4.62429, "alpha":-2.41981, "fx":[-61.77444,-74.36845,-87.23639,-77.58226], "fy":[90.49546,80.52413,66.31583,77.29622]}, + {"t":0.35283, "x":7.46645, "y":5.07154, "heading":1.38956, "vx":-1.55469, "vy":1.62765, "omega":-1.07249, "ax":-4.42951, "ay":4.62822, "alpha":-2.1254, "fx":[-63.61763,-74.16335,-85.84972,-77.74814], "fy":[89.1505,80.65253,68.02992,77.06587]}, + {"t":0.38811, "x":7.40884, "y":5.13185, "heading":1.35172, "vx":-1.71097, "vy":1.79095, "omega":-1.14748, "ax":-4.43657, "ay":4.63218, "alpha":-1.71555, "fx":[-66.1382,-74.11971,-83.93771,-77.66382], "fy":[87.21537,80.60588,70.27871,77.06822]}, + {"t":0.4234, "x":7.34571, "y":5.19792, "heading":1.31124, "vx":-1.86751, "vy":1.95439, "omega":-1.20801, "ax":-4.44402, "ay":4.63472, "alpha":-1.11064, "fx":[-69.69996,-74.41512,-81.10155,-77.14944], "fy":[84.2761,80.19826,73.39488,77.47153]}, + {"t":0.45868, "x":7.27705, "y":5.26976, "heading":1.26861, "vx":-2.02431, "vy":2.11792, "omega":-1.2472, "ax":-4.4485, "ay":4.63065, "alpha":-0.14034, "fx":[-74.9538,-75.46924,-76.37523,-75.8727], "fy":[79.44675,78.96737,78.08588,78.56393]}, + {"t":0.49396, "x":7.20286, "y":5.34737, "heading":1.22461, "vx":-2.18126, "vy":2.2813, "omega":-1.25215, "ax":-4.43236, "ay":4.59732, "alpha":1.6436, "fx":[-83.10988,-78.58171,-66.75598,-73.1254], "fy":[70.51082,75.32368,86.07536,80.88666]}, + {"t":0.52924, "x":7.12314, "y":5.43073, "heading":1.18043, "vx":-2.33765, "vy":2.44351, "omega":-1.19416, "ax":-4.28828, "ay":4.34634, "alpha":6.04079, "fx":[-95.90217,-90.34065,-38.42755,-67.09952], "fy":[50.87151,58.17748,101.12466,85.54624]}, + {"t":0.56453, "x":7.03799, "y":5.51965, "heading":1.1383, "vx":-2.48895, "vy":2.59686, "omega":-0.98102, "ax":-3.85423, "ay":3.37475, "alpha":13.02512, "fx":[-102.19801,-101.64729,1.64888,-60.04128], "fy":[32.96363,1.08571,106.12302,89.44177]}, + {"t":0.59981, "x":6.94777, "y":5.61337, "heading":1.10368, "vx":-2.62494, "vy":2.71593, "omega":-0.52146, "ax":-0.01946, "ay":0.10541, "alpha":0.11891, "fx":[-0.74568,-0.19432,0.08378,-0.46753], "fy":[1.65635,1.37842,1.92958,2.2074]}, + {"t":0.63509, "x":6.85515, "y":5.70926, "heading":1.08528, "vx":-2.62563, "vy":2.71965, "omega":-0.51726, "ax":3.79616, "ay":-3.35493, "alpha":-13.49959, "fx":[101.62329,102.21895,-3.57781,58.02182], "fy":[-34.82108,3.2231,-105.91808,-90.74948]}, + {"t":0.67038, "x":6.76487, "y":5.80313, "heading":1.06703, "vx":-2.49169, "vy":2.60128, "omega":-0.99357, "ax":4.32416, "ay":-4.41793, "alpha":-5.15384, "fx":[92.49726,90.01853,45.81125,65.88397], "fy":[-56.88603,-59.26422,-97.98721,-86.45343]}, + {"t":0.70566, "x":6.67965, "y":5.89216, "heading":1.03198, "vx":-2.33912, "vy":2.4454, "omega":-1.17541, "ax":4.43852, "ay":-4.6032, "alpha":-1.29214, "fx":[81.07797,79.13318,69.28387,72.49686], "fy":[-72.86955,-74.81877,-84.06524,-81.44303]}, + {"t":0.74094, "x":6.59988, "y":5.97558, "heading":0.99051, "vx":-2.18252, "vy":2.28298, "omega":-1.221, "ax":4.44899, "ay":-4.63041, "alpha":0.26193, "fx":[74.4908,74.96305,76.83477,76.41564], "fy":[-79.88742,-79.465,-77.65201,-78.04324]}, + {"t":0.77623, "x":6.52564, "y":6.05325, "heading":0.94742, "vx":-2.02554, "vy":2.11961, "omega":-1.21176, "ax":4.44451, "ay":-4.63457, "alpha":1.11675, "fx":[70.49572,72.53089,80.22464,79.148], "fy":[-83.60169,-81.90706,-74.37587,-75.44616]}, + {"t":0.81151, "x":6.45694, "y":6.12515, "heading":0.90467, "vx":-1.86873, "vy":1.95609, "omega":-1.17236, "ax":4.4379, "ay":-4.63311, "alpha":1.66372, "fx":[67.93448,70.79361,81.99696,81.22492], "fy":[-85.80306,-83.5366,-72.56099,-73.33074]}, + {"t":0.84679, "x":6.39377, "y":6.19128, "heading":0.86331, "vx":-1.71214, "vy":1.79262, "omega":-1.11365, "ax":4.43156, "ay":-4.63018, "alpha":2.0464, "fx":[66.23404,69.41661,82.98764,82.88027], "fy":[-87.19664,-84.76381,-71.52326,-71.54876]}, + {"t":0.88207, "x":6.33612, "y":6.25165, "heading":0.82401, "vx":-1.55578, "vy":1.62925, "omega":-1.04145, "ax":4.42591, "ay":-4.62707, "alpha":2.32998, "fx":[65.08539,68.26346,83.54973,84.23534], "fy":[-88.11188,-85.75058,-70.93591,-70.02198]}, + {"t":0.91736, "x":6.28398, "y":6.30625, "heading":0.78727, "vx":-1.39963, "vy":1.46599, "omega":-0.95924, "ax":4.42095, "ay":-4.62417, "alpha":2.54848, "fx":[64.30633,67.26939,83.85897,85.36168], "fy":[-88.72393,-86.57333,-70.62266,-68.70351]}, + {"t":0.95264, "x":6.23735, "y":6.3551, "heading":0.75342, "vx":-1.24364, "vy":1.30284, "omega":-0.86933, "ax":4.4166, "ay":-4.62162, "alpha":2.72156, "fx":[63.7806,66.40013,84.0137,86.30616], "fy":[-89.13585,-87.27302,-70.47934,-67.56167]}, + {"t":0.98792, "x":6.19622, "y":6.39819, "heading":0.72275, "vx":-1.08781, "vy":1.13977, "omega":-0.7733, "ax":4.41279, "ay":-4.61942, "alpha":2.86156, "fx":[63.42894,65.63597,84.07397,87.10202], "fy":[-89.41355,-87.87386,-70.43992,-66.57285]}, + {"t":1.02321, "x":6.16058, "y":6.43553, "heading":0.69547, "vx":-0.93211, "vy":0.97679, "omega":-0.67234, "ax":4.40943, "ay":-4.61754, "alpha":2.97676, "fx":[63.19434,64.96466,84.07905,87.77425], "fy":[-89.60212,-88.39135,-70.46028,-65.71808]}, + {"t":1.05849, "x":6.13044, "y":6.46712, "heading":0.67174, "vx":-0.77654, "vy":0.81387, "omega":-0.56731, "ax":4.40646, "ay":-4.61591, "alpha":3.07299, "fx":[63.03402,64.37814,84.05599,88.34234], "fy":[-89.73417,-88.83604,-70.50964,-64.98149]}, + {"t":1.09377, "x":6.10578, "y":6.49296, "heading":0.65173, "vx":-0.62106, "vy":0.651, "omega":-0.45888, "ax":4.40383, "ay":-4.6145, "alpha":3.15457, "fx":[62.91494,63.87083,84.02424,88.82183], "fy":[-89.83425,-89.21549,-70.56584,-64.34956]}, + {"t":1.12906, "x":6.08661, "y":6.51306, "heading":0.63554, "vx":-0.46568, "vy":0.48819, "omega":-0.34758, "ax":4.4015, "ay":-4.61325, "alpha":3.22475, "fx":[62.81103,63.43871,83.99818,89.2252], "fy":[-89.9214,-89.53527,-70.61249,-63.81076]}, + {"t":1.16434, "x":6.07292, "y":6.52741, "heading":0.62327, "vx":-0.31038, "vy":0.32542, "omega":-0.2338, "ax":4.39942, "ay":-4.61211, "alpha":3.28605, "fx":[62.70151,63.07891,83.98871,89.56244], "fy":[-90.01057,-89.79954,-70.6372,-63.35545]}, + {"t":1.19962, "x":6.06471, "y":6.53602, "heading":0.61502, "vx":-0.15516, "vy":0.16269, "omega":-0.11786, "ax":4.39756, "ay":-4.61106, "alpha":3.34042, "fx":[62.56982,62.7894,84.00422,89.8414], "fy":[-90.11357,-90.01136,-70.63044,-62.97581]}, + {"t":1.2349, "x":6.06197, "y":6.53889, "heading":0.61087, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] From d3d8f2a390d876c72598790c179adb39541233ac Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Fri, 24 Oct 2025 02:07:43 -0400 Subject: [PATCH 144/180] Refactor drive and composite commands for improved algae intake and scoring automation --- .../deploy/choreo/E_RIGHT_PATH_1_BACK.traj | 196 +++++++++-------- .../deploy/choreo/E_RIGHT_PATH_2_BACK.traj | 198 ++++++++++-------- .../deploy/choreo/E_RIGHT_PATH_3_BACK.traj | 120 ++++++----- .../deploy/choreo/E_RIGHT_PATH_4_BACK.traj | 196 +++++++++-------- src/main/deploy/choreo/F_PATH_1.traj | 47 +++-- src/main/deploy/choreo/F_PATH_2.traj | 74 +++++-- src/main/deploy/choreo/F_PATH_3.traj | 113 +++++----- src/main/deploy/choreo/F_PATH_4.traj | 164 ++++++++++----- src/main/deploy/choreo/F_PATH_5.traj | 125 ++++++----- src/main/deploy/choreo/F_PATH_6.traj | 85 -------- src/main/deploy/choreo/F_PATH_7.traj | 79 ------- src/main/deploy/choreo/F_PATH_8.traj | 70 ------- .../robot/commands/AutonomousCommands.java | 30 +-- .../frc/robot/commands/CompositeCommands.java | 32 ++- .../robot/subsystems/shared/drive/Drive.java | 2 +- 15 files changed, 767 insertions(+), 764 deletions(-) delete mode 100644 src/main/deploy/choreo/F_PATH_6.traj delete mode 100644 src/main/deploy/choreo/F_PATH_7.traj delete mode 100644 src/main/deploy/choreo/F_PATH_8.traj diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_1_BACK.traj b/src/main/deploy/choreo/E_RIGHT_PATH_1_BACK.traj index 3699ba1d..15ba82ac 100644 --- a/src/main/deploy/choreo/E_RIGHT_PATH_1_BACK.traj +++ b/src/main/deploy/choreo/E_RIGHT_PATH_1_BACK.traj @@ -3,8 +3,8 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":7.152472496032715, "y":0.4605357348918915, "heading":3.141592653589793, "intervals":53, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":2.838493585586548, "y":1.8093056678771973, "heading":0.0, "intervals":20, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":7.152472496032715, "y":0.4605357348918915, "heading":3.141592653589793, "intervals":52, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":3.198220729827881, "y":2.1674070358276367, "heading":0.0, "intervals":19, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, {"x":2.3785881996154785, "y":3.3401336669921875, "heading":0.0, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, {"x":2.937044858932495, "y":3.872309923171997, "heading":1.5707963267948966, "intervals":34, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ @@ -15,8 +15,8 @@ }, "params":{ "waypoints":[ - {"x":{"exp":"7.152472496032715 m", "val":7.152472496032715}, "y":{"exp":"0.4605357348918915 m", "val":0.4605357348918915}, "heading":{"exp":"pi rad", "val":3.141592653589793}, "intervals":53, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"2.838493585586548 m", "val":2.838493585586548}, "y":{"exp":"1.8093056678771973 m", "val":1.8093056678771973}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":20, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, + {"x":{"exp":"7.152472496032715 m", "val":7.152472496032715}, "y":{"exp":"0.4605357348918915 m", "val":0.4605357348918915}, "heading":{"exp":"pi rad", "val":3.141592653589793}, "intervals":52, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"3.198220729827881 m", "val":3.198220729827881}, "y":{"exp":"2.1674070358276367 m", "val":2.1674070358276367}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":19, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, {"x":{"exp":"2.3785881996154785 m", "val":2.3785881996154785}, "y":{"exp":"3.3401336669921875 m", "val":3.3401336669921875}, "heading":{"exp":"0 deg", "val":0.0}, "intervals":27, "split":false, "fixTranslation":true, "fixHeading":false, "overrideIntervals":false}, {"x":{"exp":"2.937044858932495 m", "val":2.937044858932495}, "y":{"exp":"3.872309923171997 m", "val":3.872309923171997}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":34, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ @@ -30,102 +30,100 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,1.47444,2.01312,2.55519], + "waypoints":[0.0,1.39551,1.9336,2.52308], "samples":[ - {"t":0.0, "x":7.15247, "y":0.46054, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.30985, "ay":1.13451, "alpha":-2.36127, "fx":[-106.15131,-109.53492,-109.38886,-104.24005], "fy":[27.85125,6.71386,8.39245,34.23341]}, - {"t":0.03429, "x":7.14876, "y":0.4612, "heading":3.14159, "vx":-0.21636, "vy":0.0389, "omega":-0.08097, "ax":-6.31061, "ay":1.13479, "alpha":-2.3233, "fx":[-106.17408,-109.51598,-109.36459,-104.31184], "fy":[27.73526,6.89733,8.59089,33.98641]}, - {"t":0.06858, "x":7.13763, "y":0.4632, "heading":3.13882, "vx":-0.43275, "vy":0.07781, "omega":-0.16063, "ax":-6.31143, "ay":1.1351, "alpha":-2.28075, "fx":[-106.19086,-109.4924,-109.34011,-104.39879], "fy":[27.6378,7.13249,8.7742,33.68674]}, - {"t":0.10287, "x":7.11909, "y":0.46654, "heading":3.13331, "vx":-0.64916, "vy":0.11674, "omega":-0.23884, "ax":-6.31232, "ay":1.13546, "alpha":-2.23259, "fx":[-106.20301,-109.46343,-109.31461,-104.50191], "fy":[27.55293,7.42251,8.9508,33.32898]}, - {"t":0.13716, "x":7.09311, "y":0.47121, "heading":3.12512, "vx":-0.86561, "vy":0.15567, "omega":-0.31539, "ax":-6.3133, "ay":1.13585, "alpha":-2.17745, "fx":[-106.21228,-109.42805,-109.28693,-104.62253], "fy":[27.47295,7.77177,9.13148,32.90592]}, - {"t":0.17145, "x":7.05972, "y":0.47722, "heading":3.1143, "vx":-1.08209, "vy":0.19462, "omega":-0.39005, "ax":-6.31439, "ay":1.1363, "alpha":-2.11357, "fx":[-106.22087,-109.38487,-109.25551,-104.76233], "fy":[27.38778,8.18626,9.33014,32.40804]}, - {"t":0.20574, "x":7.01891, "y":0.48456, "heading":3.10093, "vx":-1.2986, "vy":0.23358, "omega":-0.46253, "ax":-6.31559, "ay":1.13679, "alpha":-2.03859, "fx":[-106.23173,-109.33197,-109.21818,-104.92344], "fy":[27.28393,8.67427,9.56484,31.82288]}, - {"t":0.24003, "x":6.97066, "y":0.49323, "heading":3.08507, "vx":-1.51516, "vy":0.27256, "omega":-0.53243, "ax":-6.31692, "ay":1.13734, "alpha":-1.9493, "fx":[-106.24876,-109.26668,-109.1719,-105.10849], "fy":[27.14294,9.2474,9.85945,31.13386]}, - {"t":0.27432, "x":6.915, "y":0.50325, "heading":3.06681, "vx":-1.73177, "vy":0.31156, "omega":-0.59927, "ax":-6.31838, "ay":1.13797, "alpha":-1.84119, "fx":[-106.27735,-109.18509,-109.1122,-105.32082], "fy":[26.93882,9.92235,10.24631,30.31849]}, - {"t":0.3086, "x":6.8519, "y":0.5146, "heading":3.04626, "vx":-1.94842, "vy":0.35058, "omega":-0.6624, "ax":-6.31997, "ay":1.13867, "alpha":-1.7077, "fx":[-106.32507,-109.0813,-109.03228,-105.56466], "fy":[26.63348,10.72411,10.77058,29.34538]}, - {"t":0.34289, "x":6.78138, "y":0.52729, "heading":3.02355, "vx":-2.16513, "vy":0.38962, "omega":-0.72096, "ax":-6.32161, "ay":1.13945, "alpha":-1.5389, "fx":[-106.40294,-108.94585,-108.92116,-105.84549], "fy":[26.16844,11.69179,11.49798,28.16888]}, - {"t":0.37718, "x":6.70342, "y":0.54132, "heading":2.99883, "vx":-2.38189, "vy":0.42869, "omega":-0.77373, "ax":-6.32316, "ay":1.14034, "alpha":-1.31888, "fx":[-106.5275,-108.76246,-108.75992,-106.17059], "fy":[25.44839,12.89057,12.52902,26.71925]}, - {"t":0.41147, "x":6.61803, "y":0.55669, "heading":2.9723, "vx":-2.59871, "vy":0.4678, "omega":-0.81895, "ax":-6.32415, "ay":1.14131, "alpha":-1.02033, "fx":[-106.72448,-108.50045,-108.51326,-106.54963], "fy":[24.30538,14.43765,14.02739,24.88305]}, - {"t":0.44576, "x":6.5252, "y":0.5734, "heading":2.94422, "vx":-2.81556, "vy":0.50693, "omega":-0.85394, "ax":-6.32333, "ay":1.1423, "alpha":-0.59171, "fx":[-107.03479,-108.09421,-108.10836,-106.99481], "fy":[22.41125,16.56689,16.28154,22.46082]}, - {"t":0.48005, "x":6.42494, "y":0.59146, "heading":2.91494, "vx":-3.03238, "vy":0.5461, "omega":-0.87423, "ax":-6.31677, "ay":1.14289, "alpha":0.07813, "fx":[-107.51937,-107.37535,-107.37375,-107.517], "fy":[19.02322,19.81867,19.85443,19.06483]}, - {"t":0.51434, "x":6.31725, "y":0.61085, "heading":2.88496, "vx":-3.24898, "vy":0.58529, "omega":-0.87155, "ax":-6.2888, "ay":1.14108, "alpha":1.28669, "fx":[-108.19958,-105.7639,-105.82265,-108.09677], "fy":[12.03662,25.76334,26.00465,13.83311]}, - {"t":0.54863, "x":6.20215, "y":0.63159, "heading":2.85508, "vx":-3.46462, "vy":0.62442, "omega":-0.82743, "ax":-6.13751, "ay":1.125, "alpha":4.23689, "fx":[-107.77566,-99.70393,-101.63272,-108.477], "fy":[-7.28619,41.28126,38.08086,4.46805]}, - {"t":0.58292, "x":6.07974, "y":0.65367, "heading":2.8267, "vx":-3.67507, "vy":0.66299, "omega":-0.68215, "ax":-4.85939, "ay":1.06, "alpha":14.2065, "fx":[-82.3114,-51.32747,-90.0828,-106.90578], "fy":[-65.09645,89.6783,58.32113,-10.78204]}, - {"t":0.61721, "x":5.95086, "y":0.67702, "heading":2.80331, "vx":-3.8417, "vy":0.69934, "omega":-0.19501, "ax":-1.83896, "ay":0.16468, "alpha":5.61042, "fx":[-23.91618,-13.53294,-39.64858,-48.02298], "fy":[-18.08314,13.78057,21.68104,-6.17386]}, - {"t":0.6515, "x":5.81805, "y":0.7011, "heading":2.79663, "vx":-3.90476, "vy":0.70498, "omega":-0.00264, "ax":-0.01384, "ay":-0.06338, "alpha":0.00576, "fx":[-0.22636,-0.21624,-0.24439,-0.25451], "fy":[-1.0972,-1.06905,-1.05896,-1.0871]}, - {"t":0.68579, "x":5.68415, "y":0.72524, "heading":2.79654, "vx":-3.90523, "vy":0.70281, "omega":-0.00244, "ax":-0.00382, "ay":-0.02121, "alpha":0.00001, "fx":[-0.06492,-0.06491,-0.06494,-0.06495], "fy":[-0.36076,-0.36074,-0.36073,-0.36075]}, - {"t":0.72008, "x":5.55024, "y":0.74932, "heading":2.79645, "vx":-3.90536, "vy":0.70208, "omega":-0.00244, "ax":-0.00123, "ay":-0.00686, "alpha":0.0, "fx":[-0.02099,-0.02099,-0.02099,-0.02099], "fy":[-0.11677,-0.11677,-0.11677,-0.11677]}, - {"t":0.75437, "x":5.41633, "y":0.77339, "heading":2.79637, "vx":-3.9054, "vy":0.70185, "omega":-0.00244, "ax":-0.0003, "ay":-0.00167, "alpha":0.0, "fx":[-0.0051,-0.0051,-0.0051,-0.0051], "fy":[-0.02836,-0.02836,-0.02836,-0.02836]}, - {"t":0.78866, "x":5.28242, "y":0.79746, "heading":2.79628, "vx":-3.90541, "vy":0.70179, "omega":-0.00244, "ax":0.00024, "ay":0.00131, "alpha":0.0, "fx":[0.004,0.004,0.004,0.004], "fy":[0.02225,0.02225,0.02225,0.02225]}, - {"t":0.82295, "x":5.1485, "y":0.82152, "heading":2.7962, "vx":-3.90541, "vy":0.70184, "omega":-0.00244, "ax":0.00108, "ay":0.00603, "alpha":0.0, "fx":[0.01843,0.01843,0.01843,0.01843], "fy":[0.10251,0.10251,0.10251,0.10251]}, - {"t":0.85724, "x":5.01459, "y":0.84559, "heading":2.79612, "vx":-3.90537, "vy":0.70204, "omega":-0.00244, "ax":0.00338, "ay":0.01877, "alpha":0.0, "fx":[0.05744,0.05744,0.05744,0.05744], "fy":[0.31935,0.31935,0.31935,0.31935]}, - {"t":0.89152, "x":4.88068, "y":0.86967, "heading":2.79603, "vx":-3.90525, "vy":0.70269, "omega":-0.00244, "ax":0.01019, "ay":0.05653, "alpha":0.0, "fx":[0.17327,0.17327,0.17327,0.17327], "fy":[0.96158,0.96158,0.96158,0.96158]}, - {"t":0.92581, "x":4.74678, "y":0.8938, "heading":2.79595, "vx":-3.9049, "vy":0.70463, "omega":-0.00244, "ax":0.03071, "ay":0.16947, "alpha":0.0, "fx":[0.52239,0.52239,0.52241,0.52241], "fy":[2.88263,2.88261,2.88261,2.88263]}, - {"t":0.9601, "x":4.6129, "y":0.91806, "heading":2.79587, "vx":-3.90385, "vy":0.71044, "omega":-0.00244, "ax":0.09307, "ay":0.50497, "alpha":-0.00002, "fx":[1.583,1.58297,1.58307,1.5831], "fy":[8.58945,8.58935,8.58932,8.58942]}, - {"t":0.99439, "x":4.47909, "y":0.94272, "heading":2.79578, "vx":-3.90066, "vy":0.72775, "omega":-0.00244, "ax":0.27803, "ay":1.43912, "alpha":-0.00011, "fx":[4.72898,4.72879,4.72935,4.72954], "fy":[24.47929,24.47879,24.4786,24.4791]}, - {"t":1.02868, "x":4.3455, "y":0.96852, "heading":2.7957, "vx":-3.89113, "vy":0.7771, "omega":-0.00244, "ax":0.69862, "ay":3.25214, "alpha":-0.00043, "fx":[11.88232,11.88161,11.88427,11.88498], "fy":[55.31903,55.31754,55.31675,55.31824]}, - {"t":1.06297, "x":4.21249, "y":0.99708, "heading":2.79562, "vx":-3.86717, "vy":0.88861, "omega":-0.00246, "ax":1.21082, "ay":4.79339, "alpha":-0.00106, "fx":[20.59218,20.5908,20.59913,20.60052], "fy":[81.53635,81.53437,81.53203,81.53401]}, - {"t":1.09726, "x":4.0806, "y":1.03037, "heading":2.79553, "vx":-3.82565, "vy":1.05297, "omega":-0.00249, "ax":1.65056, "ay":5.46017, "alpha":-0.0019, "fx":[28.06788,28.06637,28.0831,28.08461], "fy":[92.87938,92.87758,92.8724,92.87421]}, - {"t":1.13155, "x":3.95039, "y":1.06968, "heading":2.79545, "vx":-3.76906, "vy":1.2402, "omega":-0.00256, "ax":2.0375, "ay":5.67987, "alpha":-0.0029, "fx":[34.64437,34.64368,34.67018,34.67087], "fy":[96.61861,96.61683,96.60732,96.6091]}, - {"t":1.16584, "x":3.82235, "y":1.11555, "heading":2.79536, "vx":-3.69919, "vy":1.43496, "omega":-0.00266, "ax":2.39714, "ay":5.71062, "alpha":-0.00409, "fx":[40.75525,40.75651,40.79404,40.79277], "fy":[97.14498,97.1426,97.12694,97.12932]}, - {"t":1.20013, "x":3.69691, "y":1.16811, "heading":2.79527, "vx":-3.61699, "vy":1.63077, "omega":-0.0028, "ax":2.73984, "ay":5.64981, "alpha":-0.00557, "fx":[46.57629,46.58091,46.63136,46.62672], "fy":[96.11583,96.11184,96.08756,96.09156]}, - {"t":1.23442, "x":3.5745, "y":1.22735, "heading":2.79517, "vx":-3.52305, "vy":1.8245, "omega":-0.00299, "ax":3.06952, "ay":5.53568, "alpha":-0.00812, "fx":[52.17051,52.18119,52.25273,52.24199], "fy":[94.18384,94.17603,94.13666,94.1445]}, - {"t":1.26871, "x":3.4555, "y":1.29316, "heading":2.79507, "vx":-3.41779, "vy":2.01432, "omega":-0.00327, "ax":3.39007, "ay":5.38335, "alpha":-0.02261, "fx":[57.54848,57.58834,57.78004,57.73987], "fy":[91.64368,91.61461,91.49471,91.5241]}, - {"t":1.303, "x":3.3403, "y":1.3654, "heading":2.79496, "vx":-3.30155, "vy":2.19891, "omega":-0.00404, "ax":3.73287, "ay":5.1779, "alpha":-0.16974, "fx":[62.62962,62.99836,64.36788,63.98427], "fy":[88.70501,88.41922,87.4344,87.73968]}, - {"t":1.33729, "x":3.22929, "y":1.44384, "heading":2.79482, "vx":-3.17355, "vy":2.37646, "omega":-0.00986, "ax":4.25578, "ay":4.7678, "alpha":-1.03725, "fx":[67.33029,70.04566,77.61074,74.57153], "fy":[85.55052,83.21438,76.2683,79.36248]}, - {"t":1.37158, "x":3.12297, "y":1.52813, "heading":2.79448, "vx":-3.02763, "vy":2.53994, "omega":-0.04543, "ax":4.87355, "ay":4.09887, "alpha":-2.41545, "fx":[72.12253,79.77089,93.66886,86.02847], "fy":[81.83135,74.11168,55.76467,67.17456]}, - {"t":1.40587, "x":3.02202, "y":1.61763, "heading":2.79292, "vx":-2.86051, "vy":2.68049, "omega":-0.12826, "ax":5.30466, "ay":3.46822, "alpha":-3.33991, "fx":[76.5997,88.69811,102.56937,93.05607], "fy":[77.8594,63.3398,37.42115,57.35314]}, - {"t":1.44016, "x":2.92705, "y":1.71159, "heading":2.78852, "vx":-2.67862, "vy":2.79941, "omega":-0.24278, "ax":5.59557, "ay":2.94295, "alpha":-3.75835, "fx":[81.18369,95.64878,106.49575,97.38764], "fy":[73.21985,52.49123,24.65011,49.87365]}, - {"t":1.47444, "x":2.83849, "y":1.80931, "heading":2.7802, "vx":-2.48675, "vy":2.90032, "omega":-0.37165, "ax":5.75508, "ay":2.51639, "alpha":-4.10958, "fx":[83.98647,99.69565,107.99334,99.89331], "fy":[69.45514,43.049,14.70893,43.99888]}, - {"t":1.49368, "x":2.79172, "y":1.86557, "heading":2.77305, "vx":-2.37603, "vy":2.94873, "omega":-0.45071, "ax":5.86468, "ay":2.1742, "alpha":-4.53218, "fx":[85.60221,102.78906,108.85901,101.77595], "fy":[67.46975,34.92275,6.00975,39.52804]}, - {"t":1.51292, "x":2.74709, "y":1.9227, "heading":2.76438, "vx":-2.26321, "vy":2.99056, "omega":-0.5379, "ax":5.96152, "ay":1.82071, "alpha":-4.85539, "fx":[87.72481,105.38842,109.04614,103.45531], "fy":[64.70424,26.00185,-1.80544,34.97842]}, - {"t":1.53216, "x":2.70465, "y":1.98057, "heading":2.75403, "vx":-2.14851, "vy":3.02559, "omega":-0.63132, "ax":6.04564, "ay":1.45945, "alpha":-5.07095, "fx":[90.36368,107.27273,108.75224,104.94956], "fy":[60.9863,16.69959,-8.67119,30.2848]}, - {"t":1.5514, "x":2.66444, "y":2.03905, "heading":2.74188, "vx":-2.03221, "vy":3.05367, "omega":-0.72887, "ax":6.12053, "ay":1.08953, "alpha":-5.13841, "fx":[93.63048,108.35407,108.16285,106.28617], "fy":[55.868,7.4931,-14.51266,25.28181]}, - {"t":1.57064, "x":2.62647, "y":2.098, "heading":2.72786, "vx":-1.91446, "vy":3.07463, "omega":-0.82773, "ax":6.18594, "ay":0.71481, "alpha":-5.03935, "fx":[97.33258,108.68263,107.42745,107.44135], "fy":[49.17148,-1.03788,-19.39631,19.89763]}, - {"t":1.58988, "x":2.59079, "y":2.15728, "heading":2.71194, "vx":-1.79545, "vy":3.08838, "omega":-0.92468, "ax":6.23751, "ay":0.34502, "alpha":-4.80217, "fx":[100.96845,108.44293,106.63067,108.35129], "fy":[41.24683,-8.48973,-23.52204,14.23973]}, - {"t":1.60911, "x":2.5574, "y":2.21676, "heading":2.69415, "vx":-1.67545, "vy":3.09502, "omega":-1.01706, "ax":6.27164, "ay":-0.0105, "alpha":-4.47557, "fx":[104.08546,107.85302,105.80969,108.96702], "fy":[32.67427,-14.78702,-27.08749,8.48593]}, - {"t":1.62835, "x":2.52633, "y":2.2763, "heading":2.67458, "vx":-1.55479, "vy":3.09482, "omega":-1.10317, "ax":6.28754, "ay":-0.34577, "alpha":-4.10262, "fx":[106.45769,107.08116,104.98286,109.27528], "fy":[23.96792,-20.05529,-30.22663,2.78822]}, - {"t":1.64759, "x":2.49758, "y":2.33578, "heading":2.65336, "vx":-1.43383, "vy":3.08817, "omega":-1.1821, "ax":6.28663, "ay":-0.65772, "alpha":-3.71397, "fx":[108.04887,106.23282,104.16274,109.29044], "fy":[15.4929,-24.47572,-33.02187,-2.74599]}, - {"t":1.66683, "x":2.47116, "y":2.39507, "heading":2.63062, "vx":-1.31288, "vy":3.07551, "omega":-1.25355, "ax":6.27142, "ay":-0.94526, "alpha":-3.32924, "fx":[108.9306,105.36744,103.35948,109.04281], "fy":[7.47578,-28.2183,-35.52592,-8.04575]}, - {"t":1.68607, "x":2.44706, "y":2.45406, "heading":2.6065, "vx":-1.19223, "vy":3.05733, "omega":-1.3176, "ax":6.24478, "ay":-1.20857, "alpha":-2.95988, "fx":[109.21982,104.51604,102.58141,108.57014], "fy":[0.03603,-31.4234,-37.77558,-13.06692]}, - {"t":1.70531, "x":2.42528, "y":2.51266, "heading":2.58115, "vx":-1.07209, "vy":3.03408, "omega":-1.37454, "ax":6.20942, "ay":-1.4487, "alpha":-2.6118, "fx":[109.0414,103.69329,101.8351,107.91231], "fy":[-6.78209,-34.20174,-39.79898,-17.7849]}, - {"t":1.72454, "x":2.4058, "y":2.57076, "heading":2.55471, "vx":-0.95263, "vy":3.0062, "omega":-1.42479, "ax":6.16776, "ay":-1.66714, "alpha":-2.28736, "fx":[108.50917,102.90484,101.12545,107.10799], "fy":[-12.98279,-36.63927,-41.61919,-22.18938]}, - {"t":1.74378, "x":2.38862, "y":2.62829, "heading":2.5273, "vx":-0.83397, "vy":2.97413, "omega":-1.46879, "ax":6.12177, "ay":-1.86566, "alpha":-1.98684, "fx":[107.71858,102.15144,100.45581,106.19272], "fy":[-18.59855,-38.80261,-43.25607,-26.28038]}, - {"t":1.76302, "x":2.37371, "y":2.68516, "heading":2.49904, "vx":-0.7162, "vy":2.93824, "omega":-1.50702, "ax":6.07305, "ay":-2.04607, "alpha":-1.70935, "fx":[106.74571,101.43135,99.82821,105.19804], "fy":[-23.67616,-40.74358,-44.72726,-30.06517]}, - {"t":1.78226, "x":2.36105, "y":2.74131, "heading":2.47005, "vx":-0.59936, "vy":2.89888, "omega":-1.5399, "ax":6.02281, "ay":-2.21013, "alpha":-1.45339, "fx":[105.64913,100.74168,99.2435,104.15107], "fy":[-28.26769,-42.50273,-46.04867,-33.55583]}, - {"t":1.8015, "x":2.35064, "y":2.79667, "heading":2.44042, "vx":-0.48349, "vy":2.85636, "omega":-1.56786, "ax":5.972, "ay":-2.35953, "alpha":-1.21726, "fx":[104.47297,100.07908,98.70158,103.07467], "fy":[-32.42513,-44.11205,-47.23483,-36.76747]}, - {"t":1.82074, "x":2.34244, "y":2.85118, "heading":2.41026, "vx":-0.3686, "vy":2.81096, "omega":-1.59128, "ax":5.92131, "ay":-2.49578, "alpha":-0.99921, "fx":[103.24986,99.44018,98.20158,101.9877], "fy":[-36.19749,-45.59694,-48.29902,-39.71685]}, - {"t":1.83998, "x":2.33644, "y":2.9048, "heading":2.37964, "vx":-0.25468, "vy":2.76295, "omega":-1.6105, "ax":5.87125, "ay":-2.6203, "alpha":-0.79756, "fx":[102.00363,98.82176,97.74201,100.90549], "fy":[-39.62933,-46.9777,-49.25349,-42.42142]}, - {"t":1.85921, "x":2.33263, "y":2.95747, "heading":2.34866, "vx":-0.14173, "vy":2.71254, "omega":-1.62585, "ax":5.82217, "ay":-2.73431, "alpha":-0.61076, "fx":[100.75151,98.22091,97.32096,99.84024], "fy":[-42.7604,-48.27066,-50.10947,-44.89859]}, - {"t":1.87845, "x":2.33098, "y":3.00915, "heading":2.31738, "vx":-0.02972, "vy":2.65993, "omega":-1.6376, "ax":5.77433, "ay":-2.83893, "alpha":-0.4374, "fx":[99.50579,97.63501,96.93615,98.80154], "fy":[-45.62561,-49.48906,-50.87729,-47.16528]}, - {"t":1.89769, "x":2.33148, "y":3.0598, "heading":2.28588, "vx":0.08137, "vy":2.60532, "omega":-1.64601, "ax":5.72789, "ay":-2.93513, "alpha":-0.27621, "fx":[98.27516,97.06177,96.58509,97.79673], "fy":[-48.25541,-50.64362,-51.56646,-49.23767]}, - {"t":1.91693, "x":2.3341, "y":3.10938, "heading":2.25421, "vx":0.19157, "vy":2.54885, "omega":-1.65133, "ax":5.68295, "ay":-3.0238, "alpha":-0.12607, "fx":[97.06566,96.49923,96.26515,96.83134], "fy":[-50.67623,-51.7431,-52.1857,-51.13097]}, - {"t":1.93617, "x":2.33884, "y":3.15785, "heading":2.22244, "vx":0.3009, "vy":2.49067, "omega":-1.65375, "ax":5.63957, "ay":-3.1057, "alpha":0.01404, "fx":[95.88141,95.9457,95.97364,95.90935], "fy":[-52.91094,-52.79466,-52.74297,-52.8594]}, - {"t":1.95541, "x":2.34567, "y":3.20519, "heading":2.19062, "vx":0.40939, "vy":2.43093, "omega":-1.65348, "ax":5.59778, "ay":-3.18149, "alpha":0.14499, "fx":[94.72517,95.39976,95.70789,95.03351], "fy":[-54.97934,-53.80418,-53.24559,-54.43612]}, - {"t":1.97465, "x":2.35459, "y":3.25137, "heading":2.15881, "vx":0.51709, "vy":2.36972, "omega":-1.65069, "ax":5.55756, "ay":-3.2518, "alpha":0.26758, "fx":[93.59868,94.86023,95.46525,94.20555], "fy":[-56.89858,-54.77647,-53.70021,-55.87327]}, - {"t":1.99388, "x":2.36556, "y":3.29636, "heading":2.12706, "vx":0.62401, "vy":2.30716, "omega":-1.64554, "ax":5.51889, "ay":-3.31713, "alpha":0.3825, "fx":[92.50297,94.32616,95.24318,93.42636], "fy":[-58.68352,-55.71551,-54.11289,-57.18205]}, - {"t":2.01312, "x":2.37859, "y":3.34013, "heading":2.0954, "vx":0.73018, "vy":2.24334, "omega":-1.63819, "ax":5.42265, "ay":-3.47679, "alpha":0.55721, "fx":[90.14165,92.91941,94.32952,91.56027], "fy":[-62.3597,-58.15056,-55.81156,-60.23507]}, - {"t":2.03776, "x":2.39823, "y":3.39435, "heading":2.05504, "vx":0.86379, "vy":2.15768, "omega":-1.62446, "ax":5.22553, "ay":-3.76015, "alpha":0.79173, "fx":[85.68758,89.96927,92.09088,87.79141], "fy":[-68.3142,-62.58251,-59.38364,-65.55574]}, - {"t":2.0624, "x":2.4211, "y":3.44638, "heading":2.01501, "vx":0.99255, "vy":2.06503, "omega":-1.60495, "ax":4.96569, "ay":-4.08851, "alpha":1.07364, "fx":[79.82255,86.16187,89.17089,82.70441], "fy":[-75.04539,-67.69132,-63.62956,-71.81097]}, - {"t":2.08704, "x":2.44706, "y":3.49602, "heading":1.97547, "vx":1.1149, "vy":1.96429, "omega":-1.57849, "ax":4.61769, "ay":-4.46615, "alpha":1.41463, "fx":[72.04943,81.20213,85.26828,75.66247], "fy":[-82.49816,-73.52894,-68.71014,-79.13467]}, - {"t":2.11168, "x":2.47593, "y":3.54306, "heading":1.93657, "vx":1.22867, "vy":1.85425, "omega":-1.54364, "ax":4.14603, "ay":-4.8915, "alpha":1.82829, "fx":[61.76765,74.70247,79.91666,65.70437], "fy":[-90.41577,-80.08451,-74.79913,-87.51261]}, - {"t":2.13632, "x":2.50746, "y":3.58726, "heading":1.89854, "vx":1.33083, "vy":1.73372, "omega":-1.49859, "ax":3.50499, "ay":-5.34874, "alpha":2.32783, "fx":[48.39053,66.1873,72.393,51.50456], "fy":[-98.1931,-87.21504,-82.02767,-96.48656]}, - {"t":2.16096, "x":2.54132, "y":3.62836, "heading":1.86161, "vx":1.41719, "vy":1.60193, "omega":-1.44123, "ax":2.64703, "ay":-5.79455, "alpha":2.91523, "fx":[31.64471,55.15324,61.6133,31.68957], "fy":[-104.76839,-94.54354,-90.32466,-104.61781]}, - {"t":2.1856, "x":2.57704, "y":3.66607, "heading":1.8261, "vx":1.48241, "vy":1.45916, "omega":-1.3694, "ax":1.55009, "ay":-6.14744, "alpha":3.54581, "fx":[12.02789,41.23792,46.13848,6.06217], "fy":[-108.76396,-101.35836,-99.04452,-109.09769]}, - {"t":2.21024, "x":2.61404, "y":3.70015, "heading":1.79236, "vx":1.52061, "vy":1.30769, "omega":-1.28204, "ax":0.26043, "ay":-6.3044, "alpha":4.07897, "fx":[-8.92067,24.51866,24.69206,-22.57094], "fy":[-109.06113,-106.62175,-106.36464,-106.89672]}, - {"t":2.23488, "x":2.65158, "y":3.73046, "heading":1.76077, "vx":1.52702, "vy":1.15235, "omega":-1.18153, "ax":-1.09361, "ay":-6.19646, "alpha":4.3451, "fx":[-29.04602,5.81006,-2.25654,-48.91554], "fy":[-105.51394,-109.2403,-109.12372,-97.72235]}, - {"t":2.25952, "x":2.68887, "y":3.75697, "heading":1.73166, "vx":1.50008, "vy":0.99968, "omega":-1.07447, "ax":-2.35046, "ay":-5.83543, "alpha":4.3476, "fx":[-46.56094,-13.36282,-30.85192,-69.14705], "fy":[-99.06771,-108.57986,-104.6957,-84.69269]}, - {"t":2.28416, "x":2.72512, "y":3.77983, "heading":1.70519, "vx":1.44216, "vy":0.85589, "omega":-0.96735, "ax":-3.38915, "ay":-5.30938, "alpha":4.23769, "fx":[-60.69408,-31.29826,-55.64728,-82.95419], "fy":[-91.13362,-104.84463,-93.94852,-71.31737]}, - {"t":2.3088, "x":2.75963, "y":3.79931, "heading":1.68135, "vx":1.35866, "vy":0.72507, "omega":-0.86294, "ax":-4.17547, "ay":-4.73023, "alpha":4.10788, "fx":[-71.57288,-46.79462,-73.82668,-91.90005], "fy":[-82.90647,-98.93465,-80.54678,-59.45133]}, - {"t":2.33343, "x":2.79184, "y":3.81574, "heading":1.66009, "vx":1.25577, "vy":0.60852, "omega":-0.76172, "ax":-4.74378, "ay":-4.17718, "alpha":3.9708, "fx":[-79.75771,-59.4268,-85.93056,-97.64657], "fy":[-75.11035,-91.94043,-67.60191,-49.55798]}, - {"t":2.35807, "x":2.82134, "y":3.82947, "heading":1.64132, "vx":1.13889, "vy":0.5056, "omega":-0.66388, "ax":-5.14925, "ay":-3.68504, "alpha":3.82583, "fx":[-85.87945,-69.36517,-93.71911,-101.38507], "fy":[-68.07084,-84.73481,-56.4369,-41.48364]}, - {"t":2.38271, "x":2.84784, "y":3.84081, "heading":1.62496, "vx":1.01202, "vy":0.4148, "omega":-0.56962, "ax":-5.44017, "ay":-3.26077, "alpha":3.67848, "fx":[-90.47794,-77.05404,-98.74262,-103.868], "fy":[-61.87094,-77.85091,-47.22712,-34.90983]}, - {"t":2.40735, "x":2.87112, "y":3.85004, "heading":1.61093, "vx":0.87797, "vy":0.33446, "omega":-0.47898, "ax":-5.65184, "ay":-2.89925, "alpha":3.53567, "fx":[-93.9662,-82.98052,-102.04376,-105.55392], "fy":[-56.47385,-71.54239,-39.71913,-29.52626]}, - {"t":2.43199, "x":2.89104, "y":3.8574, "heading":1.59912, "vx":0.73872, "vy":0.26302, "omega":-0.39186, "ax":-5.80847, "ay":-2.59173, "alpha":3.40209, "fx":[-96.64498,-87.56877,-104.26554,-106.72263], "fy":[-51.7953,-65.88727,-33.57869,-25.07736]}, - {"t":2.45663, "x":2.90748, "y":3.86309, "heading":1.58947, "vx":0.5956, "vy":0.19916, "omega":-0.30804, "ax":-5.92642, "ay":-2.3293, "alpha":3.27991, "fx":[-98.72917,-91.15307,-105.79709,-107.54773], "fy":[-47.73984,-60.87079,-28.50784,-21.36448]}, - {"t":2.48127, "x":2.92035, "y":3.86729, "heading":1.58188, "vx":0.44957, "vy":0.14177, "omega":-0.22722, "ax":-6.01674, "ay":-2.10408, "alpha":3.16957, "fx":[-100.37177,-93.98484,-106.8761,-108.13935], "fy":[-44.21693,-56.43693,-24.26924,-18.23615]}, - {"t":2.50591, "x":2.9296, "y":3.87015, "heading":1.57628, "vx":0.30133, "vy":0.08993, "omega":-0.14913, "ax":-6.08698, "ay":-1.90952, "alpha":3.07054, "fx":[-101.68224,-96.2495,-107.65073,-108.56902], "fy":[-41.14679,-52.51618,-20.68115,-15.57716]}, - {"t":2.53055, "x":2.93518, "y":3.87178, "heading":1.57261, "vx":0.15135, "vy":0.04288, "omega":-0.07347, "ax":-6.14241, "ay":-1.74027, "alpha":2.98185, "fx":[-102.73965,-98.08303,-108.21553,-108.88428], "fy":[-38.4615,-49.03917,-17.60593,-13.29951]}, - {"t":2.55519, "x":2.93704, "y":3.87231, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":7.15247, "y":0.46054, "heading":3.14159, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.95962, "ay":2.4391, "alpha":-1.77481, "fx":[-100.26693,-104.36205,-102.92747,-97.92916], "fy":[44.58879,33.89753,37.98584,49.48174]}, + {"t":0.03323, "x":7.14918, "y":0.46188, "heading":3.14159, "vx":-0.19802, "vy":0.08104, "omega":-0.05897, "ax":-5.9595, "ay":2.43902, "alpha":-1.74842, "fx":[-100.27856,-104.31851,-102.89834,-97.98193], "fy":[44.54375,34.00581,38.03992,49.35875]}, + {"t":0.06645, "x":7.13931, "y":0.46592, "heading":3.13963, "vx":-0.39603, "vy":0.16208, "omega":-0.11706, "ax":-5.95935, "ay":2.43892, "alpha":-1.71881, "fx":[-100.28551,-104.267,-102.87156,-98.04352], "fy":[44.50675,34.13486,38.08457,49.21546]}, + {"t":0.09968, "x":7.12287, "y":0.47265, "heading":3.13574, "vx":-0.59404, "vy":0.24312, "omega":-0.17417, "ax":-5.95918, "ay":2.43881, "alpha":-1.68531, "fx":[-100.28852,-104.20648,-102.84596,-98.11503], "fy":[44.47565,34.28691,38.12235,49.049]}, + {"t":0.13291, "x":7.09984, "y":0.48208, "heading":3.12996, "vx":-0.79204, "vy":0.32415, "omega":-0.23017, "ax":-5.95898, "ay":2.43868, "alpha":-1.64705, "fx":[-100.28854,-104.13559,-102.82006,-98.19786], "fy":[44.44768,34.46494,38.1565,48.85566]}, + {"t":0.16613, "x":7.07023, "y":0.49419, "heading":3.12231, "vx":-0.99004, "vy":0.40518, "omega":-0.2849, "ax":-5.95873, "ay":2.43852, "alpha":-1.60291, "fx":[-100.28676,-104.0525,-102.79197,-98.29385], "fy":[44.41926,34.67284,38.19118,48.63054]}, + {"t":0.19936, "x":7.03405, "y":0.509, "heading":3.11284, "vx":-1.18802, "vy":0.4862, "omega":-0.33816, "ax":-5.95842, "ay":2.43832, "alpha":-1.55139, "fx":[-100.28477,-103.95475,-102.7592,-98.40542], "fy":[44.38569,34.91588,38.23176,48.36718]}, + {"t":0.23259, "x":6.99128, "y":0.5265, "heading":3.10161, "vx":-1.386, "vy":0.56722, "omega":-0.3897, "ax":-5.95803, "ay":2.43808, "alpha":-1.49046, "fx":[-100.28465,-103.83895,-102.71842,-98.53573], "fy":[44.34062,35.20123,38.28531,48.05686]}, + {"t":0.26581, "x":6.94194, "y":0.5467, "heading":3.08866, "vx":-1.58396, "vy":0.64823, "omega":-0.43923, "ax":-5.95753, "ay":2.43777, "alpha":-1.41727, "fx":[-100.28928,-103.70031,-102.66511,-98.68909], "fy":[44.27527,35.5389,38.36143,47.68758]}, + {"t":0.29904, "x":6.88603, "y":0.56958, "heading":3.07406, "vx":-1.78191, "vy":0.72923, "omega":-0.48632, "ax":-5.95687, "ay":2.43737, "alpha":-1.32771, "fx":[-100.3027,-103.5318,-102.59286,-98.87148], "fy":[44.17702,35.94339,38.47344,47.24228]}, + {"t":0.33226, "x":6.82353, "y":0.59515, "heading":3.05791, "vx":-1.97984, "vy":0.81021, "omega":-0.53043, "ax":-5.95597, "ay":2.43684, "alpha":-1.21563, "fx":[-100.33084,-103.32268,-102.4923,-99.09147], "fy":[44.02708,36.43647,38.64061,46.69578]}, + {"t":0.36549, "x":6.75446, "y":0.62342, "heading":3.04028, "vx":-2.17773, "vy":0.89118, "omega":-0.57082, "ax":-5.95468, "ay":2.4361, "alpha":-1.07139, "fx":[-100.38281,-103.0557,-102.34897,-99.36191], "fy":[43.79583,37.05252,38.89195,46.00917]}, + {"t":0.39872, "x":6.67882, "y":0.65438, "heading":3.02132, "vx":-2.37559, "vy":0.97212, "omega":-0.60642, "ax":-5.95273, "ay":2.43501, "alpha":-0.87892, "fx":[-100.47343,-102.70109,-102.1392,-99.70297], "fy":[43.43354,37.84939,39.27379,45.11868]}, + {"t":0.43194, "x":6.5966, "y":0.68802, "heading":3.00117, "vx":-2.57337, "vy":1.05303, "omega":-0.63562, "ax":-5.94956, "ay":2.4333, "alpha":-0.60936, "fx":[-100.62873,-102.20279,-101.82111,-100.14844], "fy":[42.8491,38.93263,39.8655,43.91172]}, + {"t":0.46517, "x":6.50781, "y":0.72435, "heading":2.98005, "vx":-2.77106, "vy":1.13388, "omega":-0.65587, "ax":-5.94384, "ay":2.43033, "alpha":-0.2049, "fx":[-100.89912,-101.44136,-101.31237,-100.75921], "fy":[41.85436,40.51739,40.81641,42.16854]}, + {"t":0.4984, "x":6.41246, "y":0.76337, "heading":2.95825, "vx":-2.96855, "vy":1.21463, "omega":-0.66268, "ax":-5.93174, "ay":2.42431, "alpha":0.46992, "fx":[-101.39692,-100.11079,-100.42536,-101.6556], "fy":[39.98557,43.11887,42.44698,39.39567]}, + {"t":0.53162, "x":6.31055, "y":0.80506, "heading":2.93624, "vx":-3.16564, "vy":1.29518, "omega":-0.64707, "ax":-5.89785, "ay":2.4082, "alpha":1.82835, "fx":[-102.42406,-97.14036,-98.62137,-103.09704], "fy":[35.70318,48.33731,45.59377,34.21717]}, + {"t":0.56485, "x":6.20211, "y":0.84943, "heading":2.91474, "vx":-3.3616, "vy":1.3752, "omega":-0.58632, "ax":-5.71592, "ay":2.32082, "alpha":6.09969, "fx":[-104.69071,-85.1836,-93.54629,-105.48402], "fy":[19.2743,64.31934,53.27962,21.03273]}, + {"t":0.59808, "x":6.08726, "y":0.8964, "heading":2.89525, "vx":-3.55152, "vy":1.45231, "omega":-0.38365, "ax":-3.63431, "ay":1.5017, "alpha":11.50753, "fx":[-59.73238,-36.98712,-68.1641,-82.39082], "fy":[-8.99128,56.55541,48.85774,5.75224]}, + {"t":0.6313, "x":5.96725, "y":0.94549, "heading":2.88251, "vx":-3.67228, "vy":1.50221, "omega":-0.00129, "ax":0.00046, "ay":0.02394, "alpha":0.01216, "fx":[0.02351,0.03502,-0.00762,-0.01927], "fy":[0.37998,0.42323,0.43448,0.39129]}, + {"t":0.66453, "x":5.84523, "y":0.99541, "heading":2.88246, "vx":-3.67226, "vy":1.503, "omega":-0.00089, "ax":0.00294, "ay":0.0072, "alpha":0.00001, "fx":[0.04999,0.05,0.04998,0.04997], "fy":[0.12248,0.1225,0.12252,0.1225]}, + {"t":0.69776, "x":5.72322, "y":1.04536, "heading":2.88244, "vx":-3.67217, "vy":1.50324, "omega":-0.00089, "ax":0.00103, "ay":0.00251, "alpha":0.0, "fx":[0.01746,0.01746,0.01746,0.01746], "fy":[0.04264,0.04264,0.04265,0.04265]}, + {"t":0.73098, "x":5.60121, "y":1.0953, "heading":2.88241, "vx":-3.67213, "vy":1.50333, "omega":-0.00089, "ax":0.00036, "ay":0.00087, "alpha":0.0, "fx":[0.00608,0.00608,0.00608,0.00608], "fy":[0.01486,0.01486,0.01486,0.01486]}, + {"t":0.76421, "x":5.47919, "y":1.14526, "heading":2.88238, "vx":-3.67212, "vy":1.50335, "omega":-0.00089, "ax":0.00013, "ay":0.00031, "alpha":0.0, "fx":[0.00213,0.00213,0.00213,0.00213], "fy":[0.0052,0.0052,0.0052,0.0052]}, + {"t":0.79743, "x":5.35718, "y":1.19521, "heading":2.88235, "vx":-3.67212, "vy":1.50336, "omega":-0.00089, "ax":0.00005, "ay":0.00011, "alpha":0.0, "fx":[0.00077,0.00077,0.00077,0.00077], "fy":[0.00189,0.00189,0.00189,0.00189]}, + {"t":0.83066, "x":5.23517, "y":1.24516, "heading":2.88232, "vx":-3.67211, "vy":1.50337, "omega":-0.00089, "ax":0.00002, "ay":0.00005, "alpha":0.0, "fx":[0.00036,0.00036,0.00036,0.00036], "fy":[0.00088,0.00088,0.00088,0.00088]}, + {"t":0.86389, "x":5.11316, "y":1.29511, "heading":2.88229, "vx":-3.67211, "vy":1.50337, "omega":-0.00089, "ax":0.00002, "ay":0.00005, "alpha":0.0, "fx":[0.00038,0.00038,0.00038,0.00038], "fy":[0.00093,0.00093,0.00093,0.00093]}, + {"t":0.89711, "x":4.99115, "y":1.34506, "heading":2.88226, "vx":-3.67211, "vy":1.50337, "omega":-0.00089, "ax":0.00005, "ay":0.00012, "alpha":0.0, "fx":[0.00087,0.00087,0.00087,0.00087], "fy":[0.00213,0.00213,0.00213,0.00213]}, + {"t":0.93034, "x":4.86914, "y":1.39501, "heading":2.88223, "vx":-3.67211, "vy":1.50338, "omega":-0.00089, "ax":0.00014, "ay":0.00035, "alpha":0.0, "fx":[0.00242,0.00242,0.00242,0.00242], "fy":[0.00591,0.00591,0.00591,0.00591]}, + {"t":0.96357, "x":4.74713, "y":1.44496, "heading":2.8822, "vx":-3.67211, "vy":1.50339, "omega":-0.00089, "ax":0.00041, "ay":0.00099, "alpha":0.0, "fx":[0.00692,0.00692,0.00692,0.00692], "fy":[0.0169,0.0169,0.0169,0.0169]}, + {"t":0.99679, "x":4.62512, "y":1.49492, "heading":2.88217, "vx":-3.67209, "vy":1.50342, "omega":-0.00089, "ax":0.00117, "ay":0.00285, "alpha":0.0, "fx":[0.01986,0.01986,0.01986,0.01986], "fy":[0.04851,0.04851,0.04851,0.04851]}, + {"t":1.03002, "x":4.50311, "y":1.54487, "heading":2.88214, "vx":-3.67205, "vy":1.50352, "omega":-0.00089, "ax":0.00335, "ay":0.00819, "alpha":0.0, "fx":[0.05703,0.05703,0.05703,0.05703], "fy":[0.13927,0.13927,0.13927,0.13927]}, + {"t":1.06325, "x":4.3811, "y":1.59483, "heading":2.88211, "vx":-3.67194, "vy":1.50379, "omega":-0.00089, "ax":0.00963, "ay":0.02351, "alpha":0.0, "fx":[0.1638,0.1638,0.1638,0.1638], "fy":[0.39985,0.39985,0.39985,0.39985]}, + {"t":1.09647, "x":4.2591, "y":1.64481, "heading":2.88208, "vx":-3.67162, "vy":1.50457, "omega":-0.00089, "ax":0.02768, "ay":0.06748, "alpha":0.0, "fx":[0.47075,0.47075,0.47075,0.47075], "fy":[1.14777,1.14777,1.14777,1.14777]}, + {"t":1.1297, "x":4.13712, "y":1.69484, "heading":2.88205, "vx":-3.6707, "vy":1.50681, "omega":-0.00089, "ax":0.07962, "ay":0.19347, "alpha":0.0, "fx":[1.35426,1.35426,1.35427,1.35427], "fy":[3.2908,3.2908,3.2908,3.2908]}, + {"t":1.16293, "x":4.0152, "y":1.74501, "heading":2.88202, "vx":-3.66806, "vy":1.51324, "omega":-0.00089, "ax":0.22866, "ay":0.55033, "alpha":-0.00001, "fx":[3.88947,3.88946,3.88948,3.88949], "fy":[9.36101,9.361,9.36099,9.36101]}, + {"t":1.19615, "x":3.89345, "y":1.7956, "heading":2.88199, "vx":-3.66046, "vy":1.53152, "omega":-0.00089, "ax":0.63245, "ay":1.48316, "alpha":-0.00003, "fx":[10.75775,10.75772,10.75785,10.75788], "fy":[25.22814,25.22803,25.22799,25.22811]}, + {"t":1.22938, "x":3.77217, "y":1.8473, "heading":2.88196, "vx":-3.63945, "vy":1.5808, "omega":-0.00089, "ax":1.41654, "ay":3.13585, "alpha":-0.00014, "fx":[24.0946,24.09455,24.09517,24.09523], "fy":[53.34023,53.33985,53.33964,53.34002]}, + {"t":1.2626, "x":3.65203, "y":1.90156, "heading":2.88193, "vx":-3.59238, "vy":1.685, "omega":-0.00089, "ax":2.19972, "ay":4.44497, "alpha":-0.00036, "fx":[37.41566,37.4158,37.41768,37.41754], "fy":[75.60836,75.6077,75.60689,75.60755]}, + {"t":1.29583, "x":3.53388, "y":1.96, "heading":2.8819, "vx":-3.51929, "vy":1.83269, "omega":-0.00091, "ax":2.749, "ay":4.98144, "alpha":-0.00077, "fx":[46.75715,46.75792,46.76225,46.76148], "fy":[84.73455,84.73343,84.73121,84.73234]}, + {"t":1.32906, "x":3.41847, "y":2.02364, "heading":2.88187, "vx":-3.42795, "vy":1.9982, "omega":-0.00093, "ax":3.1731, "ay":5.11309, "alpha":-0.0219, "fx":[53.89606,53.92771,54.05096,54.0192], "fy":[87.02438,86.99288,86.91999,86.95162]}, + {"t":1.36228, "x":3.30632, "y":2.09286, "heading":2.88184, "vx":-3.32252, "vy":2.16809, "omega":-0.00166, "ax":4.16293, "ay":4.55065, "alpha":-2.08872, "fx":[63.73579,68.12214,78.0509,73.33188], "fy":[83.84918,79.50983,70.31928,75.94253]}, + {"t":1.39551, "x":3.19822, "y":2.16741, "heading":2.88179, "vx":-3.1842, "vy":2.31929, "omega":-0.07106, "ax":5.6711, "ay":1.65715, "alpha":-9.01765, "fx":[78.29136,101.83908,105.88003,99.84487], "fy":[70.74095,12.13437,-8.08864,37.9637]}, + {"t":1.41544, "x":3.13589, "y":2.21396, "heading":2.88037, "vx":-3.07118, "vy":2.35232, "omega":-0.25077, "ax":5.84735, "ay":0.76908, "alpha":-10.50223, "fx":[85.38776,103.45353,105.01485,103.9907], "fy":[64.03797,-17.1633,-23.10917,28.56184]}, + {"t":1.43537, "x":3.07584, "y":2.26099, "heading":2.87537, "vx":-2.95465, "vy":2.36765, "omega":-0.46007, "ax":5.94017, "ay":0.2869, "alpha":-10.53765, "fx":[91.73482,102.21689,104.15544,106.05532], "fy":[55.94792,-29.42495,-29.16339,22.16105]}, + {"t":1.4553, "x":3.01814, "y":2.30823, "heading":2.86621, "vx":-2.83626, "vy":2.37337, "omega":-0.67008, "ax":6.06192, "ay":-0.0401, "alpha":-9.27711, "fx":[98.47117,102.51781,103.99953,107.45779], "fy":[44.20584,-31.8813,-30.96693,15.91392]}, + {"t":1.47523, "x":2.96282, "y":2.35552, "heading":2.85285, "vx":-2.71546, "vy":2.37257, "omega":-0.85497, "ax":6.17235, "ay":-0.30348, "alpha":-7.55508, "fx":[103.72983,103.58265,104.26346,108.38381], "fy":[31.14002,-30.57449,-30.85263,9.63853]}, + {"t":1.49516, "x":2.90993, "y":2.40275, "heading":2.83581, "vx":-2.59245, "vy":2.36652, "omega":-1.00553, "ax":6.24043, "ay":-0.51169, "alpha":-6.09671, "fx":[106.66719,104.47295,104.58637,108.86514], "fy":[20.26299,-28.9227,-30.30187,4.14697]}, + {"t":1.51509, "x":2.8595, "y":2.44981, "heading":2.81577, "vx":-2.46808, "vy":2.35632, "omega":-1.12704, "ax":6.27815, "ay":-0.67313, "alpha":-4.97236, "fx":[108.12183,105.11432,104.87612,109.04615], "fy":[11.91594,-27.56385,-29.71395,-0.43729]}, + {"t":1.53501, "x":2.81156, "y":2.49663, "heading":2.79331, "vx":-2.34296, "vy":2.34291, "omega":-1.22613, "ax":6.29839, "ay":-0.79915, "alpha":-4.1066, "fx":[108.78741,105.57634,105.12373,109.04745], "fy":[5.54202,-26.51312,-29.16912,-4.23336]}, + {"t":1.55494, "x":2.76612, "y":2.54317, "heading":2.76888, "vx":-2.21744, "vy":2.32698, "omega":-1.30797, "ax":6.3088, "ay":-0.89917, "alpha":-3.4271, "fx":[109.04395,105.91691,105.33578,108.94703], "fy":[0.5913,-25.70607,-28.67559,-7.38826]}, + {"t":1.57487, "x":2.72318, "y":2.58936, "heading":2.74281, "vx":-2.09171, "vy":2.30906, "omega":-1.37627, "ax":6.31364, "ay":-0.98002, "alpha":-2.88198, "fx":[109.08663,106.17368,105.51995,108.79242], "fy":[-3.33992,-25.08464,-28.22639,-10.02866]}, + {"t":1.5948, "x":2.68275, "y":2.63519, "heading":2.71538, "vx":-1.96588, "vy":2.28953, "omega":-1.43371, "ax":6.31524, "ay":-1.04652, "alpha":-2.43577, "fx":[109.01643,106.37066,105.68248,108.61214], "fy":[-6.53045,-24.60584,-27.81287,-12.2551]}, + {"t":1.61473, "x":2.64482, "y":2.68061, "heading":2.68681, "vx":-1.84003, "vy":2.26867, "omega":-1.48225, "ax":6.31495, "ay":-1.10208, "alpha":-2.06404, "fx":[108.8869,106.52357,105.82802,108.42325], "fy":[-9.17192,-24.23879,-27.42779,-14.14561]}, + {"t":1.63466, "x":2.60941, "y":2.7256, "heading":2.65727, "vx":-1.71417, "vy":2.24671, "omega":-1.52338, "ax":6.31354, "ay":-1.14913, "alpha":-1.74963, "fx":[108.72719,106.64297,105.95998,108.23591], "fy":[-11.39773,-23.96112,-27.06568,-15.76062]}, + {"t":1.65459, "x":2.5765, "y":2.77015, "heading":2.62691, "vx":-1.58835, "vy":2.22381, "omega":-1.55825, "ax":6.31149, "ay":-1.18945, "alpha":-1.48022, "fx":[108.55349,106.73621,106.08081,108.05605], "fy":[-13.30245,-23.75637,-26.72261,-17.14722]}, + {"t":1.67452, "x":2.5461, "y":2.81423, "heading":2.59585, "vx":-1.46257, "vy":2.2001, "omega":-1.58775, "ax":6.30908, "ay":-1.22437, "alpha":-1.24678, "fx":[108.37494,106.80854,106.19231,107.88703], "fy":[-14.95438,-23.61213,-26.39585,-18.3424]}, + {"t":1.69445, "x":2.5182, "y":2.85783, "heading":2.56421, "vx":-1.33683, "vy":2.1757, "omega":-1.6126, "ax":6.3065, "ay":-1.2549, "alpha":-1.04251, "fx":[108.19674,106.86382,106.29582,107.73063], "fy":[-16.40381,-23.51887,-26.08353,-19.37556]}, + {"t":1.71438, "x":2.49281, "y":2.90094, "heading":2.53207, "vx":-1.21115, "vy":2.15069, "omega":-1.63338, "ax":6.30385, "ay":-1.2818, "alpha":-0.86225, "fx":[108.02181,106.90493,106.39232,107.58763], "fy":[-17.6884,-23.46909,-25.78444,-20.27028]}, + {"t":1.73431, "x":2.46993, "y":2.94355, "heading":2.49952, "vx":-1.08552, "vy":2.12515, "omega":-1.65056, "ax":6.3012, "ay":-1.30568, "alpha":-0.70198, "fx":[107.85181,106.93409,106.48253,107.45819], "fy":[-18.8368,-23.45678,-25.49783,-21.0457]}, + {"t":1.75424, "x":2.44955, "y":2.98564, "heading":2.46663, "vx":-0.95994, "vy":2.09913, "omega":-1.66455, "ax":6.2986, "ay":-1.32702, "alpha":-0.55853, "fx":[107.68759,106.95303,106.56703,107.3421], "fy":[-19.87111,-23.47705,-25.22328,-21.71749]}, + {"t":1.77416, "x":2.43167, "y":3.02721, "heading":2.43345, "vx":-0.83442, "vy":2.07268, "omega":-1.67568, "ax":6.29608, "ay":-1.3462, "alpha":-0.42939, "fx":[107.5296,106.96313,106.64625,107.23891], "fy":[-20.80863,-23.52582,-24.96058,-22.29867]}, + {"t":1.79409, "x":2.41629, "y":3.06825, "heading":2.40006, "vx":-0.70894, "vy":2.04585, "omega":-1.68424, "ax":6.29364, "ay":-1.36352, "alpha":-0.31252, "fx":[107.37797,106.96552,106.72052,107.14805], "fy":[-21.66304,-23.59967,-24.70968,-22.80011]}, + {"t":1.81402, "x":2.40341, "y":3.10876, "heading":2.36649, "vx":-0.58351, "vy":2.01868, "omega":-1.69047, "ax":6.2913, "ay":-1.37925, "alpha":-0.20626, "fx":[107.23275,106.96109,106.79012,107.06885], "fy":[-22.44527,-23.69568,-24.47062,-23.23098]}, + {"t":1.83395, "x":2.39303, "y":3.14871, "heading":2.3328, "vx":-0.45813, "vy":1.99119, "omega":-1.69458, "ax":6.28906, "ay":-1.39359, "alpha":-0.10922, "fx":[107.09385,106.95062,106.85528,107.00063], "fy":[-23.1642,-23.81129,-24.24351,-23.59913]}, + {"t":1.85388, "x":2.38515, "y":3.18812, "heading":2.29903, "vx":-0.3328, "vy":1.96342, "omega":-1.69675, "ax":6.28692, "ay":-1.40671, "alpha":-0.02028, "fx":[106.96116,106.93475,106.91618,106.94267], "fy":[-23.82703,-23.9443,-24.02847,-23.91129]}, + {"t":1.87381, "x":2.37976, "y":3.22697, "heading":2.26522, "vx":-0.2075, "vy":1.93538, "omega":-1.69716, "ax":6.28488, "ay":-1.41877, "alpha":0.06154, "fx":[106.83456,106.91403,106.97298,106.89427], "fy":[-24.43973,-24.09272,-23.82564,-24.17331]}, + {"t":1.89374, "x":2.37688, "y":3.26526, "heading":2.2314, "vx":-0.08225, "vy":1.90711, "omega":-1.69593, "ax":6.28293, "ay":-1.42988, "alpha":0.13704, "fx":[106.71392,106.88895,107.02584,106.85474], "fy":[-25.00722,-24.25479,-23.63513,-24.3903]}, + {"t":1.91367, "x":2.37648, "y":3.30298, "heading":2.1976, "vx":0.04296, "vy":1.87861, "omega":-1.6932, "ax":6.28108, "ay":-1.44015, "alpha":0.20691, "fx":[106.59909,106.85993,107.07488,106.8234], "fy":[-25.53366,-24.42892,-23.45706,-24.56677]}, + {"t":1.9336, "x":2.37859, "y":3.34013, "heading":2.16385, "vx":0.16814, "vy":1.84991, "omega":-1.68908, "ax":6.2666, "ay":-1.51557, "alpha":0.31738, "fx":[106.20287,106.61882,106.97212,106.57872], "fy":[-27.36787,-25.71095,-24.18592,-25.8528]}, + {"t":1.96039, "x":2.38534, "y":3.38916, "heading":2.11859, "vx":0.33605, "vy":1.8093, "omega":-1.68057, "ax":6.22395, "ay":-1.67613, "alpha":0.46607, "fx":[105.23012,105.90028,106.48053,105.85958], "fy":[-30.82796,-28.45725,-26.18372,-28.57324]}, + {"t":1.98719, "x":2.39658, "y":3.43704, "heading":2.07356, "vx":0.50282, "vy":1.76439, "omega":-1.66808, "ax":6.16557, "ay":-1.87221, "alpha":0.64871, "fx":[103.87813,104.91712,105.82307,104.87982], "fy":[-35.04018,-31.81735,-28.63423,-31.89133]}, + {"t":2.01398, "x":2.41227, "y":3.48364, "heading":2.02887, "vx":0.66803, "vy":1.71422, "omega":-1.6507, "ax":6.08298, "ay":-2.11612, "alpha":0.87757, "fx":[101.93904,103.53454,104.91372,103.49181], "fy":[-40.25397,-35.9828,-31.70212,-36.03957]}, + {"t":2.04078, "x":2.43235, "y":3.52881, "heading":1.98464, "vx":0.83102, "vy":1.65752, "omega":-1.62719, "ax":5.96148, "ay":-2.42588, "alpha":1.1709, "fx":[99.05325,101.52713,103.60374,101.42821], "fy":[-46.82048,-41.22172,-35.6351,-41.37668]}, + {"t":2.06757, "x":2.45676, "y":3.57236, "heading":1.94104, "vx":0.99076, "vy":1.59252, "omega":-1.59581, "ax":5.77415, "ay":-2.82799, "alpha":1.55638, "fx":[94.57323,98.50298,101.61984,98.17017], "fy":[-55.21823,-47.90734,-40.81798,-48.46938]}, + {"t":2.09437, "x":2.48538, "y":3.61401, "heading":1.89828, "vx":1.14547, "vy":1.51675, "omega":-1.55411, "ax":5.46905, "ay":-3.36023, "alpha":2.07595, "fx":[87.29973,93.75562,98.42239,92.62989], "fy":[-66.01775,-56.53597,-47.86426,-58.20852]}, + {"t":2.12116, "x":2.51803, "y":3.65345, "heading":1.85663, "vx":1.29202, "vy":1.42671, "omega":-1.49849, "ax":4.94206, "ay":-4.06833, "alpha":2.79114, "fx":[75.04691,85.98701,92.85683,82.36144], "fy":[-79.56515,-67.66104,-57.74892,-71.82914]}, + {"t":2.14796, "x":2.55443, "y":3.69021, "heading":1.81648, "vx":1.42444, "vy":1.3177, "omega":-1.4237, "ax":3.9899, "ay":-4.96735, "alpha":3.78381, "fx":[54.40719,72.8973,82.26866,61.89498], "fy":[-94.78255,-81.48551,-71.83176,-89.87298]}, + {"t":2.17475, "x":2.59403, "y":3.72374, "heading":1.77834, "vx":1.53135, "vy":1.1846, "omega":-1.32231, "ax":2.31559, "ay":-5.88607, "alpha":5.0694, "fx":[22.82832,51.17987,60.63871,22.90348], "fy":[-106.81068,-96.51781,-90.61682,-106.53607]}, + {"t":2.20155, "x":2.63589, "y":3.75337, "heading":1.7429, "vx":1.59339, "vy":1.02688, "omega":-1.18648, "ax":-0.08218, "ay":-6.28824, "alpha":5.94264, "fx":[-14.98003,19.15247,19.31265,-29.07625], "fy":[-108.18994,-107.49744,-107.14333,-105.01391]}, + {"t":2.22834, "x":2.67856, "y":3.77862, "heading":1.71111, "vx":1.59119, "vy":0.85839, "omega":-1.02725, "ax":-2.4374, "ay":-5.81359, "alpha":5.58264, "fx":[-47.53312,-17.4276,-33.29351,-67.5834], "fy":[-98.40791,-107.80099,-103.67549,-85.66555]}, + {"t":2.25514, "x":2.72032, "y":3.79954, "heading":1.68359, "vx":1.52588, "vy":0.70262, "omega":-0.87766, "ax":-4.03424, "ay":-4.88434, "alpha":4.93177, "fx":[-69.35715,-48.04634,-69.91561,-87.16588], "fy":[-84.56933,-98.14085,-83.71165,-65.90303]}, + {"t":2.28193, "x":2.75975, "y":3.81661, "heading":1.66007, "vx":1.41778, "vy":0.57174, "omega":-0.74551, "ax":-4.93632, "ay":-4.01227, "alpha":4.35838, "fx":[-82.58825,-68.63531,-88.06681,-96.5715], "fy":[-71.82388,-85.13726,-64.63704,-51.39215]}, + {"t":2.30873, "x":2.79597, "y":3.83049, "heading":1.6401, "vx":1.28552, "vy":0.46423, "omega":-0.62873, "ax":-5.44116, "ay":-3.33334, "alpha":3.87119, "fx":[-90.59388,-81.37837,-96.82264,-101.41544], "fy":[-61.53007,-73.16977,-50.85916,-41.23767]}, + {"t":2.33552, "x":2.82846, "y":3.84173, "heading":1.62325, "vx":1.13972, "vy":0.37492, "omega":-0.525, "ax":-5.73834, "ay":-2.82325, "alpha":3.47772, "fx":[-95.61759,-89.28023,-101.39812,-104.13389], "fy":[-53.48969,-63.39606,-41.21949,-33.98547]}, + {"t":2.36232, "x":2.85694, "y":3.85077, "heading":1.60918, "vx":0.98596, "vy":0.29927, "omega":-0.43182, "ax":-5.92391, "ay":-2.43678, "alpha":3.16658, "fx":[-98.91503,-94.35399,-104.0098,-105.77745], "fy":[-47.20189,-55.66092,-34.30001,-28.63278]}, + {"t":2.38911, "x":2.88123, "y":3.85791, "heading":1.59761, "vx":0.82723, "vy":0.23398, "omega":-0.34697, "ax":-6.04619, "ay":-2.13802, "alpha":2.92003, "fx":[-101.17374,-97.75276,-105.6162,-106.83282], "fy":[-42.22167,-49.53483,-29.15612,-24.55559]}, + {"t":2.41591, "x":2.90123, "y":3.86341, "heading":1.58831, "vx":0.66523, "vy":0.17669, "omega":-0.26873, "ax":-6.13051, "ay":-1.90198, "alpha":2.72231, "fx":[-102.78,-100.12346,-106.66547,-107.54399], "fy":[-38.21486,-44.62464,-25.20439,-21.36436]}, + {"t":2.4427, "x":2.91685, "y":3.86746, "heading":1.58111, "vx":0.50096, "vy":0.12573, "omega":-0.19579, "ax":-6.19093, "ay":-1.71166, "alpha":2.56138, "fx":[-103.95947,-101.83745,-107.3847,-108.04227], "fy":[-34.94106,-40.62848,-22.08069,-18.80903]}, + {"t":2.46949, "x":2.92805, "y":3.87022, "heading":1.57587, "vx":0.33508, "vy":0.07986, "omega":-0.12715, "ax":-6.23563, "ay":-1.55541, "alpha":2.42843, "fx":[-104.84945,-103.11574,-107.89734,-108.40268], "fy":[-32.22818,-37.32538,-19.55076,-16.72377]}, + {"t":2.49629, "x":2.93479, "y":3.8718, "heading":1.57246, "vx":0.16799, "vy":0.03818, "omega":-0.06209, "ax":-6.2696, "ay":-1.42508, "alpha":2.31705, "fx":[-105.5367,-104.09491,-108.27467,-108.67034], "fy":[-29.9518,-34.55494,-17.45881,-14.99505]}, + {"t":2.52308, "x":2.93704, "y":3.87231, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_2_BACK.traj b/src/main/deploy/choreo/E_RIGHT_PATH_2_BACK.traj index c7171a1b..02ccab3d 100644 --- a/src/main/deploy/choreo/E_RIGHT_PATH_2_BACK.traj +++ b/src/main/deploy/choreo/E_RIGHT_PATH_2_BACK.traj @@ -3,8 +3,8 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":3.173567533493042, "y":3.878880023956299, "heading":1.5707963267948966, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.6164592504501345, "y":2.643705368041992, "heading":2.400500524589353, "intervals":13, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":3.173567533493042, "y":3.878880023956299, "heading":1.5707963267948966, "intervals":53, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.6164592504501345, "y":2.643705368041992, "heading":2.400500524589353, "intervals":16, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":1.2163537740707395, "y":2.1863720417022705, "heading":2.400500524589353, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":2.937044858932495, "y":3.56351637840271, "heading":1.5707963267948966, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ @@ -12,13 +12,14 @@ {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":0, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":2, "data":{"type":"MaxVelocity", "props":{"max":1.0}}, "enabled":true}], "targetDt":0.05 }, "params":{ "waypoints":[ - {"x":{"exp":"3.173567533493042 m", "val":3.173567533493042}, "y":{"exp":"3.878880023956299 m", "val":3.878880023956299}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.6164592504501343 m", "val":1.6164592504501345}, "y":{"exp":"2.643705368041992 m", "val":2.643705368041992}, "heading":{"exp":"2.400500524589353 rad", "val":2.400500524589353}, "intervals":13, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"3.173567533493042 m", "val":3.173567533493042}, "y":{"exp":"3.878880023956299 m", "val":3.878880023956299}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":53, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.6164592504501343 m", "val":1.6164592504501345}, "y":{"exp":"2.643705368041992 m", "val":2.643705368041992}, "heading":{"exp":"2.400500524589353 rad", "val":2.400500524589353}, "intervals":16, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":{"exp":"1.2163537740707397 m", "val":1.2163537740707395}, "y":{"exp":"2.1863720417022705 m", "val":2.1863720417022705}, "heading":{"exp":"2.400500524589353 rad", "val":2.400500524589353}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":{"exp":"2.937044858932495 m", "val":2.937044858932495}, "y":{"exp":"3.56351637840271 m", "val":3.56351637840271}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ @@ -26,7 +27,8 @@ {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":0, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":2, "data":{"type":"MaxVelocity", "props":{"max":{"exp":"1 m / s", "val":1.0}}}, "enabled":true}], "targetDt":{ "exp":"0.05 s", "val":0.05 @@ -34,87 +36,111 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,0.84777,1.28242,2.45689], + "waypoints":[0.0,2.06576,2.75258,3.9249], "samples":[ - {"t":0.0, "x":3.17357, "y":3.87888, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.11215, "ay":-3.62513, "alpha":4.96579, "fx":[-86.54827,-62.34738,-94.37979,-104.54929], "fy":[-67.45617,-90.24474,-55.71509,-33.23338]}, - {"t":0.02649, "x":3.17177, "y":3.87761, "heading":1.5708, "vx":-0.13543, "vy":-0.09604, "omega":0.13156, "ax":-5.11305, "ay":-3.63058, "alpha":4.90647, "fx":[-86.54616,-62.69263,-94.23791,-104.40966], "fy":[-67.44805,-89.99497,-55.93352,-33.64395]}, - {"t":0.05299, "x":3.16639, "y":3.87379, "heading":1.57428, "vx":-0.27089, "vy":-0.19222, "omega":0.26154, "ax":-5.11402, "ay":-3.63617, "alpha":4.84467, "fx":[-86.48463,-63.04933,-94.17934,-104.23869], "fy":[-67.51493,-89.73382,-56.00927,-34.14275]}, - {"t":0.07948, "x":3.15742, "y":3.86742, "heading":1.58121, "vx":-0.40638, "vy":-0.28856, "omega":0.38989, "ax":-5.11503, "ay":-3.64202, "alpha":4.77915, "fx":[-86.36626,-63.42593,-94.19489,-104.03383], "fy":[-67.65293,-89.45487,-55.95844,-34.73277]}, - {"t":0.10597, "x":3.14486, "y":3.8585, "heading":1.59154, "vx":-0.54189, "vy":-0.38504, "omega":0.5165, "ax":-5.11607, "ay":-3.64829, "alpha":4.70848, "fx":[-86.19395,-63.83309,-94.27312,-103.79165], "fy":[-67.85737,-89.14982,-55.7997,-35.41849]}, - {"t":0.13246, "x":3.12871, "y":3.84702, "heading":1.60522, "vx":-0.67743, "vy":-0.4817, "omega":0.64124, "ax":-5.11712, "ay":-3.65514, "alpha":4.63098, "fx":[-85.97114,-64.28395,-94.40029,-103.50765], "fy":[-68.1226,-88.80818,-55.55485,-36.20597]}, - {"t":0.15896, "x":3.10896, "y":3.83297, "heading":1.62221, "vx":-0.81299, "vy":-0.57853, "omega":0.76393, "ax":-5.11815, "ay":-3.66278, "alpha":4.54447, "fx":[-85.70204,-64.79455,-94.56028,-103.17606], "fy":[-68.44175,-88.41675,-55.24965,-37.10316]}, - {"t":0.18545, "x":3.08563, "y":3.81636, "heading":1.64245, "vx":-0.94859, "vy":-0.67557, "omega":0.88433, "ax":-5.11913, "ay":-3.67144, "alpha":4.44611, "fx":[-85.39203,-65.38425,-94.73432,-102.7894], "fy":[-68.80634,-87.95895,-54.9147,-38.12035]}, - {"t":0.21194, "x":3.0587, "y":3.79717, "heading":1.66588, "vx":-1.08421, "vy":-0.77283, "omega":1.00212, "ax":-5.12006, "ay":-3.68138, "alpha":4.33215, "fx":[-85.04817,-66.07636,-94.90063,-102.33799], "fy":[-69.20574,-87.41396,-54.58659,-39.27069]}, - {"t":0.23843, "x":3.02818, "y":3.77541, "heading":1.69243, "vx":-1.21985, "vy":-0.87036, "omega":1.11689, "ax":-5.12092, "ay":-3.69292, "alpha":4.19754, "fx":[-84.67995,-66.89885,-95.03372,-101.80907], "fy":[-69.62643,-86.75539,-54.3093,-40.57126]}, - {"t":0.26493, "x":2.99407, "y":3.75105, "heading":1.72202, "vx":-1.35552, "vy":-0.9682, "omega":1.22809, "ax":-5.1217, "ay":-3.70642, "alpha":4.03556, "fx":[-84.30041,-67.88514,-95.10332,-101.1855], "fy":[-70.0507,-85.94954,-54.13603,-42.04455]}, - {"t":0.29142, "x":2.95636, "y":3.7241, "heading":1.75455, "vx":-1.49121, "vy":-1.06639, "omega":1.335, "ax":-5.12235, "ay":-3.72229, "alpha":3.83722, "fx":[-83.92792,-69.07515,-95.07241,-100.44353], "fy":[-70.45474,-84.95284,-54.13163,-43.72098]}, - {"t":0.31791, "x":2.91506, "y":3.69455, "heading":1.78992, "vx":-1.62691, "vy":-1.16501, "omega":1.43666, "ax":-5.12278, "ay":-3.74099, "alpha":3.59039, "fx":[-83.58889,-70.51637,-94.89402,-99.54906], "fy":[-70.80536,-83.70814,-54.37606,-45.64317]}, - {"t":0.34441, "x":2.87016, "y":3.66237, "heading":1.82798, "vx":-1.76263, "vy":-1.26411, "omega":1.53178, "ax":-5.12272, "ay":-3.76309, "alpha":3.27853, "fx":[-83.32247,-72.26513,-94.50555,-98.45081], "fy":[-71.05423,-82.13918,-54.96961,-47.87337]}, - {"t":0.3709, "x":2.82166, "y":3.62756, "heading":1.86856, "vx":-1.89834, "vy":-1.36381, "omega":1.61864, "ax":-5.12152, "ay":-3.78926, "alpha":2.87848, "fx":[-83.18884,-74.38776,-93.81884,-97.06702], "fy":[-71.12703,-80.1422,-56.04088,-50.50703]}, - {"t":0.39739, "x":2.76957, "y":3.5901, "heading":1.91144, "vx":-2.03402, "vy":-1.4642, "omega":1.6949, "ax":-5.11776, "ay":-3.82035, "alpha":2.35624, "fx":[-83.28506,-76.96145,-92.70208,-95.25782], "fy":[-70.90138,-77.57257,-57.75931,-53.69924]}, - {"t":0.42388, "x":2.71389, "y":3.54997, "heading":1.95635, "vx":-2.16961, "vy":-1.56541, "omega":1.75732, "ax":-5.10824, "ay":-3.85742, "alpha":1.65825, "fx":[-83.77776,-80.07373,-90.94576,-92.76134], "fy":[-70.15703,-74.22325,-60.35473,-57.71952]}, - {"t":0.45038, "x":2.65462, "y":3.50714, "heading":2.0029, "vx":-2.30494, "vy":-1.6676, "omega":1.80125, "ax":-5.0856, "ay":-3.90155, "alpha":0.69006, "fx":[-84.97806,-83.81769,-88.19597,-89.02664], "fy":[-68.44755,-69.78877,-64.14586,-63.07454]}, - {"t":0.47687, "x":2.59177, "y":3.46159, "heading":2.05062, "vx":-2.43967, "vy":-1.77096, "omega":1.81953, "ax":-5.03127, "ay":-3.95193, "alpha":-0.74553, "fx":[-87.53255,-88.27337,-83.8195,-82.6965], "fy":[-64.70466,-63.80637,-69.57152,-70.80225]}, - {"t":0.50336, "x":2.52537, "y":3.41329, "heading":2.09883, "vx":-2.57296, "vy":-1.87566, "omega":1.79978, "ax":-4.88897, "ay":-3.99061, "alpha":-3.17977, "fx":[-92.93579,-93.4403,-76.63947,-69.62444], "fy":[-55.65826,-55.58163,-77.16948,-83.10727]}, - {"t":0.52985, "x":2.45549, "y":3.3622, "heading":2.14651, "vx":-2.70248, "vy":-1.98138, "omega":1.71554, "ax":-4.43199, "ay":-3.83203, "alpha":-8.54048, "fx":[-103.45448,-98.94094,-64.65491,-34.49699], "fy":[-27.34485,-44.40861,-87.16042,-101.81274]}, - {"t":0.55635, "x":2.38234, "y":3.30836, "heading":2.19196, "vx":-2.8199, "vy":-2.0829, "omega":1.48928, "ax":-3.59004, "ay":-3.34267, "alpha":-14.93866, "fx":[-103.86068,-100.37882,-51.87447,11.85144], "fy":[12.9563,-39.80619,-94.85978,-105.72187]}, - {"t":0.58284, "x":2.30637, "y":3.252, "heading":2.23141, "vx":-2.91501, "vy":-2.17146, "omega":1.09352, "ax":-3.1972, "ay":-3.48301, "alpha":-15.32982, "fx":[-100.76443,-96.77586,-43.89344,23.89957], "fy":[8.41372,-45.5227,-97.82504,-102.04602]}, - {"t":0.60933, "x":2.22802, "y":3.19325, "heading":2.26038, "vx":-2.99971, "vy":-2.26373, "omega":0.68739, "ax":-1.98735, "ay":-4.21354, "alpha":-13.34435, "fx":[-73.74359,-83.19161,-23.50188,45.2201], "fy":[-31.69826,-61.59158,-102.11627,-91.27833]}, - {"t":0.63582, "x":2.14786, "y":3.1318, "heading":2.27859, "vx":-3.05236, "vy":-2.37536, "omega":0.33386, "ax":4.09202, "ay":-3.83991, "alpha":2.81522, "fx":[62.08599,77.95675,78.89252,59.48108], "fy":[-75.59115,-59.49971,-52.83343,-73.33867]}, - {"t":0.66232, "x":2.06843, "y":3.06753, "heading":2.28744, "vx":-2.94395, "vy":-2.47709, "omega":0.40844, "ax":5.00872, "ay":0.11652, "alpha":11.33623, "fx":[77.73036,105.90698,82.91057,74.23957], "fy":[-69.55939,-4.20447,63.74941,17.94206]}, - {"t":0.68881, "x":1.99219, "y":3.00194, "heading":2.29826, "vx":-2.81126, "vy":-2.47401, "omega":0.70877, "ax":5.85579, "ay":2.1648, "alpha":2.50944, "fx":[104.85081,102.68058,94.23854,96.65127], "fy":[20.3109,31.31039,51.0354,44.63365]}, - {"t":0.7153, "x":1.91977, "y":2.93716, "heading":2.31704, "vx":-2.65612, "vy":-2.41665, "omega":0.77525, "ax":5.68021, "ay":2.82975, "alpha":-1.40175, "fx":[92.83528,94.23696,100.53541,98.86748], "fy":[55.69676,52.83755,39.76317,44.23546]}, - {"t":0.7418, "x":1.85139, "y":2.87413, "heading":2.33757, "vx":-2.50564, "vy":-2.34169, "omega":0.73811, "ax":5.52776, "ay":3.06933, "alpha":-3.06491, "fx":[85.73118,87.75734,103.23995,99.3742], "fy":[67.00542,63.72665,33.64139,44.45994]}, - {"t":0.76829, "x":1.78695, "y":2.81317, "heading":2.35713, "vx":-2.35919, "vy":-2.26037, "omega":0.65692, "ax":5.42437, "ay":3.18893, "alpha":-3.99907, "fx":[81.58196,83.31383,104.68573,99.48633], "fy":[72.40955,69.84944,29.85702,44.85501]}, - {"t":0.79478, "x":1.72635, "y":2.7544, "heading":2.37453, "vx":-2.21549, "vy":-2.17589, "omega":0.55097, "ax":5.35158, "ay":3.26027, "alpha":-4.59632, "fx":[78.85467,80.2286,105.56848,99.46386], "fy":[75.60253,73.64152,27.30271,45.278]}, - {"t":0.82127, "x":1.66954, "y":2.6979, "heading":2.38913, "vx":-2.07371, "vy":-2.08952, "omega":0.4292, "ax":5.29798, "ay":3.30768, "alpha":-5.00961, "fx":[76.91525,78.00147,106.15559,99.3965], "fy":[77.72363,76.18517,25.47441,45.66757]}, - {"t":0.84777, "x":1.61646, "y":2.64371, "heading":2.4005, "vx":-1.93335, "vy":-2.00189, "omega":0.29648, "ax":5.22535, "ay":3.58659, "alpha":-3.68598, "fx":[77.89238,79.39135,101.9207,96.32267], "fy":[76.96045,75.1934,39.75517,52.11856]}, - {"t":0.8812, "x":1.55474, "y":2.57878, "heading":2.41041, "vx":-1.75864, "vy":-1.88197, "omega":0.17324, "ax":5.01898, "ay":3.94838, "alpha":-2.69491, "fx":[76.55356,77.45133,95.7165,91.76444], "fy":[78.3499,77.33136,53.12276,59.83952]}, - {"t":0.91464, "x":1.49874, "y":2.51806, "heading":2.41621, "vx":-1.59083, "vy":-1.74995, "omega":0.08314, "ax":4.83916, "ay":4.2083, "alpha":-1.95358, "fx":[75.52364,76.04551,90.07927,87.60229], "fy":[79.38876,78.80829,62.30166,65.82903]}, - {"t":0.94807, "x":1.44826, "y":2.4619, "heading":2.41899, "vx":-1.42903, "vy":-1.60925, "omega":0.01782, "ax":4.6861, "ay":4.40101, "alpha":-1.3839, "fx":[74.70427,74.98514,85.27193,83.87557], "fy":[80.19716,79.88485,68.80374,70.55361]}, - {"t":0.98151, "x":1.4031, "y":2.41056, "heading":2.41958, "vx":-1.27235, "vy":-1.4621, "omega":-0.02845, "ax":4.55632, "ay":4.5482, "alpha":-0.93386, "fx":[74.03268,74.1625,81.24821,80.56352], "fy":[80.84797,80.69914,73.56294,74.34393]}, - {"t":1.01494, "x":1.3631, "y":2.36421, "heading":2.41863, "vx":-1.12001, "vy":-1.31003, "omega":-0.05967, "ax":4.44584, "ay":4.66358, "alpha":-0.56962, "fx":[73.46785,73.51077,77.88694,77.62411], "fy":[81.38705,81.33198,77.15218,77.43364]}, - {"t":1.04838, "x":1.32814, "y":2.32302, "heading":2.41663, "vx":-0.97137, "vy":-1.1541, "omega":-0.07872, "ax":4.35112, "ay":4.75608, "alpha":-0.26873, "fx":[72.98243,72.98583,75.06585,75.01117], "fy":[81.84424,81.83422,79.93064,79.9891]}, - {"t":1.08181, "x":1.2981, "y":2.28709, "heading":2.414, "vx":-0.82589, "vy":-0.99508, "omega":-0.0877, "ax":4.26928, "ay":4.83165, "alpha":-0.01591, "fx":[72.55785,72.55709,72.68075,72.68133], "fy":[82.23944,82.23973,82.13046,82.13033]}, - {"t":1.11525, "x":1.27287, "y":2.25652, "heading":2.41107, "vx":-0.68314, "vy":-0.83354, "omega":-0.08824, "ax":4.19801, "ay":4.89441, "alpha":0.19958, "fx":[72.18139,72.20247,70.64756,70.5964], "fy":[82.58616,82.57212,83.90642,83.94517]}, - {"t":1.14868, "x":1.25237, "y":2.23139, "heading":2.40812, "vx":-0.54278, "vy":-0.66989, "omega":-0.08156, "ax":4.13548, "ay":4.94726, "alpha":0.38549, "fx":[71.84425,71.90555,68.89957,68.7237], "fy":[82.89372,82.84842,85.36488,85.49895]}, - {"t":1.18212, "x":1.23654, "y":2.21175, "heading":2.40539, "vx":-0.40451, "vy":-0.50448, "omega":-0.06867, "ax":4.08022, "ay":4.99232, "alpha":0.54754, "fx":[71.54035,71.65377,67.38397,67.03567], "fy":[83.1686,83.08133,86.5809,86.84095]}, - {"t":1.21555, "x":1.22529, "y":2.19768, "heading":2.4031, "vx":-0.26809, "vy":-0.33756, "omega":-0.05037, "ax":4.03109, "ay":5.03115, "alpha":0.69005, "fx":[71.26551,71.4373,66.05871,65.50919], "fy":[83.41531,83.28055,87.6088,88.00894]}, - {"t":1.24899, "x":1.21858, "y":2.1892, "heading":2.40141, "vx":-0.13331, "vy":-0.16935, "omega":-0.0273, "ax":3.98714, "ay":5.06492, "alpha":0.81637, "fx":[71.01692,71.24833,64.89012,64.12488], "fy":[83.63698,83.45366,88.48875,89.03221]}, - {"t":1.28242, "x":1.21635, "y":2.18637, "heading":2.4005, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.99082, "ay":4.00267, "alpha":-2.73922, "fx":[75.98676,76.51398,95.47907,91.58983], "fy":[79.18484,78.6284,54.05686,60.4672]}, - {"t":1.31801, "x":1.21951, "y":2.18891, "heading":2.4005, "vx":0.17762, "vy":0.14245, "omega":-0.09749, "ax":4.99148, "ay":4.0027, "alpha":-2.71212, "fx":[76.07288,76.61853,95.38308,91.53999], "fy":[79.09109,78.51271,54.20687,60.52862]}, - {"t":1.3536, "x":1.229, "y":2.19651, "heading":2.39703, "vx":0.35527, "vy":0.28491, "omega":-0.19401, "ax":4.99222, "ay":4.0027, "alpha":-2.68161, "fx":[76.20113,76.69703,95.25654,91.51045], "fy":[78.95493,78.42037,54.40686,60.55711]}, - {"t":1.38919, "x":1.2448, "y":2.20919, "heading":2.39013, "vx":0.53294, "vy":0.42737, "omega":-0.28945, "ax":4.99307, "ay":4.00267, "alpha":-2.64672, "fx":[76.37312,76.75537,95.09622,91.49811], "fy":[78.77401,78.34529,54.66104,60.55695]}, - {"t":1.42478, "x":1.26693, "y":2.22693, "heading":2.37982, "vx":0.71064, "vy":0.56982, "omega":-0.38365, "ax":4.99404, "ay":4.00262, "alpha":-2.60615, "fx":[76.59118,76.80154,94.89752,91.49872], "fy":[78.54492,78.27919,54.97543,60.53384]}, - {"t":1.46037, "x":1.29539, "y":2.24975, "heading":2.36617, "vx":0.88838, "vy":0.71227, "omega":-0.4764, "ax":4.99517, "ay":4.00253, "alpha":-2.55811, "fx":[76.8587,76.84621,94.65409,91.50652], "fy":[78.26282,78.21082,55.35823,60.49553]}, - {"t":1.49596, "x":1.33017, "y":2.27763, "heading":2.34922, "vx":1.06616, "vy":0.85472, "omega":-0.56744, "ax":4.99648, "ay":4.0024, "alpha":-2.50014, "fx":[77.18046,76.9038,94.35725,91.51347], "fy":[77.92086,78.12489,55.82051,60.45278]}, - {"t":1.53155, "x":1.37128, "y":2.31059, "heading":2.32902, "vx":1.24398, "vy":0.99717, "omega":-0.65642, "ax":4.99803, "ay":4.00224, "alpha":-2.42871, "fx":[77.56337,76.99418,93.99491,91.50807], "fy":[77.50914,78.00011,56.3773,60.42096]}, - {"t":1.56714, "x":1.41872, "y":2.34861, "heading":2.30566, "vx":1.42186, "vy":1.13961, "omega":-0.74286, "ax":4.99988, "ay":4.00199, "alpha":-2.33861, "fx":[78.0178,77.14557,93.54977,91.47322], "fy":[77.01276,77.80579,57.0495,60.42293]}, - {"t":1.60273, "x":1.47249, "y":2.3917, "heading":2.27922, "vx":1.59981, "vy":1.28204, "omega":-0.82609, "ax":5.00211, "ay":4.00162, "alpha":-2.22168, "fx":[78.56015,77.39985,92.99594,91.38197], "fy":[76.40811,77.4954,57.86752,60.49436]}, - {"t":1.63832, "x":1.53259, "y":2.43986, "heading":2.24982, "vx":1.77783, "vy":1.42446, "omega":-0.90516, "ax":5.00482, "ay":4.00097, "alpha":-2.06441, "fx":[79.21824,77.82299,92.29212,91.18875], "fy":[75.65484,76.99347,58.87841,60.69472]}, - {"t":1.67391, "x":1.59903, "y":2.49309, "heading":2.2176, "vx":1.95595, "vy":1.56685, "omega":-0.97863, "ax":5.00811, "ay":3.99972, "alpha":-1.8423, "fx":[80.0439,78.52726,91.3666,90.80853], "fy":[74.67698,76.16605,60.16129,61.13224]}, - {"t":1.7095, "x":1.67182, "y":2.55139, "heading":2.18278, "vx":2.13419, "vy":1.7092, "omega":-1.0442, "ax":5.012, "ay":3.99697, "alpha":-1.5055, "fx":[81.1466,79.72461,90.07964,90.05966], "fy":[73.3106,74.74497,61.86454,62.02939]}, - {"t":1.74509, "x":1.75095, "y":2.61475, "heading":2.14561, "vx":2.31257, "vy":1.85145, "omega":-1.09778, "ax":5.01562, "ay":3.98978, "alpha":-0.93309, "fx":[82.80431,81.87585,88.11136,88.46584], "fy":[71.12235,72.09295,64.31076,63.93381]}, - {"t":1.78068, "x":1.83643, "y":2.68317, "heading":2.10654, "vx":2.49107, "vy":1.99345, "omega":-1.13099, "ax":5.01107, "ay":3.96442, "alpha":0.27107, "fx":[85.97708,86.20579,84.52129,84.24321], "fy":[66.4745,66.22623,68.36909,68.66508]}, - {"t":1.81627, "x":1.92826, "y":2.75663, "heading":2.06629, "vx":2.66942, "vy":2.13454, "omega":-1.12134, "ax":4.85347, "ay":3.75102, "alpha":4.84072, "fx":[96.85671,96.84854,74.89676,61.62274], "fy":[43.88088,46.86151,77.38325,87.08931]}, - {"t":1.85186, "x":2.02634, "y":2.83497, "heading":2.02638, "vx":2.84215, "vy":2.26804, "omega":-0.94906, "ax":-0.07962, "ay":-0.11478, "alpha":0.08581, "fx":[-1.45624,-1.05623,-1.25244,-1.65246], "fy":[-2.25027,-2.05451,-1.65441,-1.85025]}, - {"t":1.88745, "x":2.12744, "y":2.91562, "heading":1.99261, "vx":2.83932, "vy":2.26395, "omega":-0.94601, "ax":-4.80123, "ay":-3.68671, "alpha":-5.86513, "fx":[-98.18136,-99.06413,-74.70621,-54.71847], "fy":[-39.75872,-41.93816,-77.63152,-91.51144]}, - {"t":1.92304, "x":2.22545, "y":2.99386, "heading":1.95894, "vx":2.66844, "vy":2.13274, "omega":-1.15475, "ax":-5.00971, "ay":-3.9628, "alpha":-0.48454, "fx":[-86.28338,-87.09872,-84.22619,-83.24657], "fy":[-66.02264,-65.0313,-68.73314,-69.83754]}, - {"t":1.95863, "x":2.31725, "y":3.06725, "heading":1.91784, "vx":2.49015, "vy":1.99171, "omega":-1.17199, "ax":-5.01583, "ay":-3.98973, "alpha":0.89473, "fx":[-83.68547,-81.52302,-87.23184,-88.83119], "fy":[-70.07944,-72.49771,-65.47975,-63.3997]}, - {"t":1.99422, "x":2.40269, "y":3.13561, "heading":1.87613, "vx":2.31164, "vy":1.84971, "omega":-1.14015, "ax":-5.01138, "ay":-3.99617, "alpha":1.53951, "fx":[-82.8479,-78.401,-88.46044,-91.25889], "fy":[-71.39017,-76.14963,-64.12989,-60.22523]}, - {"t":2.02981, "x":2.48179, "y":3.19891, "heading":1.83555, "vx":2.13328, "vy":1.70749, "omega":-1.08536, "ax":-5.00679, "ay":-3.99801, "alpha":1.91108, "fx":[-82.60951,-76.40736,-88.96727,-92.67203], "fy":[-71.84061,-78.31637,-63.62205,-58.24131]}, - {"t":2.0654, "x":2.55454, "y":3.25715, "heading":1.79692, "vx":1.95509, "vy":1.5652, "omega":-1.01734, "ax":-5.00307, "ay":-3.99848, "alpha":2.15056, "fx":[-82.6318,-75.02918,-89.11759,-93.62467], "fy":[-71.92463,-79.7461,-63.54469,-56.8367]}, - {"t":2.10099, "x":2.62096, "y":3.31032, "heading":1.76072, "vx":1.77703, "vy":1.4229, "omega":-0.9408, "ax":-5.00014, "ay":-3.9985, "alpha":2.3164, "fx":[-82.77891,-74.02776,-89.0738,-94.32316], "fy":[-71.83059,-80.75255,-63.70211,-55.7682]}, - {"t":2.13658, "x":2.68103, "y":3.35843, "heading":1.72723, "vx":1.59908, "vy":1.28059, "omega":-0.85836, "ax":-4.99779, "ay":-3.99839, "alpha":2.43732, "fx":[-82.98515,-73.27567,-88.92105,-94.86233], "fy":[-71.64718,-81.49169,-63.98755,-54.91933]}, - {"t":2.17217, "x":2.73478, "y":3.40147, "heading":1.69668, "vx":1.42121, "vy":1.13829, "omega":-0.77162, "ax":-4.99588, "ay":-3.99825, "alpha":2.52912, "fx":[-83.21469,-72.69745,-88.70963,-95.29237], "fy":[-71.42234,-82.05091,-64.3368,-54.22655]}, - {"t":2.20776, "x":2.7822, "y":3.43945, "heading":1.66922, "vx":1.2434, "vy":0.99599, "omega":-0.68161, "ax":-4.99429, "ay":-3.99813, "alpha":2.60115, "fx":[-83.44625,-72.24469,-88.47199,-95.64277], "fy":[-71.18467,-82.48375,-64.70847,-53.65159]}, - {"t":2.24335, "x":2.82329, "y":3.47237, "heading":1.64496, "vx":1.06566, "vy":0.8537, "omega":-0.58903, "ax":-4.99293, "ay":-3.99804, "alpha":2.65929, "fx":[-83.66637,-71.88442,-88.23045,-95.93225], "fy":[-70.95249,-82.82531,-65.07451,-53.16952]}, - {"t":2.27894, "x":2.85805, "y":3.50022, "heading":1.624, "vx":0.88796, "vy":0.71141, "omega":-0.49439, "ax":-4.99176, "ay":-3.99796, "alpha":2.70736, "fx":[-83.86617,-71.59306,-88.00116,-96.1735], "fy":[-70.73823,-83.09981,-65.4152,-52.7631]}, - {"t":2.31453, "x":2.88649, "y":3.52301, "heading":1.60641, "vx":0.7103, "vy":0.56912, "omega":-0.39803, "ax":-4.99074, "ay":-3.99788, "alpha":2.74792, "fx":[-84.03951,-71.35321,-87.79618,-96.37547], "fy":[-70.55069,-83.32467,-65.71629,-52.4198]}, - {"t":2.35012, "x":2.90861, "y":3.54073, "heading":1.59224, "vx":0.53268, "vy":0.42684, "omega":-0.30024, "ax":-4.98984, "ay":-3.99781, "alpha":2.78277, "fx":[-84.18203,-71.15172,-87.62472,-96.54473], "fy":[-70.3963,-83.51272,-65.96724,-52.1303]}, - {"t":2.38571, "x":2.92441, "y":3.55339, "heading":1.58155, "vx":0.35509, "vy":0.28455, "omega":-0.2012, "ax":-4.98905, "ay":-3.99773, "alpha":2.81317, "fx":[-84.29053,-70.97853,-87.49395,-96.68616], "fy":[-70.27988,-83.67359,-66.16013,-51.88751]}, - {"t":2.4213, "x":2.93389, "y":3.56098, "heading":1.57439, "vx":0.17753, "vy":0.14228, "omega":-0.10108, "ax":-4.98835, "ay":-3.99764, "alpha":2.84003, "fx":[-84.36258,-70.82592,-87.40946,-96.80343], "fy":[-70.20515,-83.81455,-66.28886,-51.68605]}, - {"t":2.45689, "x":2.93704, "y":3.56352, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":3.17357, "y":3.87888, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.05765, "ay":-4.00362, "alpha":0.00539, "fx":[-86.02726,-86.01206,-86.0312,-86.04639], "fy":[-68.10304,-68.12218,-68.09795,-68.07882]}, + {"t":0.03898, "x":3.16973, "y":3.87584, "heading":1.5708, "vx":-0.19713, "vy":-0.15605, "omega":0.00021, "ax":-5.05469, "ay":-4.00128, "alpha":0.0071, "fx":[-85.97631,-85.95629,-85.98148,-86.00149], "fy":[-68.06401,-68.08919,-68.05729,-68.03211]}, + {"t":0.07795, "x":3.1582, "y":3.86672, "heading":1.5708, "vx":-0.39415, "vy":-0.312, "omega":0.00049, "ax":-5.04672, "ay":-3.99497, "alpha":0.01179, "fx":[-85.83913,-85.80584,-85.84757,-85.88083], "fy":[-67.95897,-68.00068,-67.94773,-67.90602]}, + {"t":0.11693, "x":3.13901, "y":3.85152, "heading":1.57082, "vx":-0.59085, "vy":-0.46772, "omega":0.00095, "ax":-4.95112, "ay":-3.91929, "alpha":0.06982, "fx":[-84.19754,-83.99827,-84.23678,-84.43563], "fy":[-66.70253,-66.94101,-66.62927,-66.3911]}, + {"t":0.15591, "x":3.11222, "y":3.83031, "heading":1.57086, "vx":-0.78383, "vy":-0.62048, "omega":0.00367, "ax":-0.00112, "ay":-0.00089, "alpha":2.58338, "fx":[-4.7421,4.70437,4.70402,-4.74269], "fy":[-4.73871,-4.73802,4.70863,4.70762]}, + {"t":0.19488, "x":3.08166, "y":3.80613, "heading":1.571, "vx":-0.78387, "vy":-0.62051, "omega":0.10436, "ax":0.0, "ay":0.0, "alpha":2.14367, "fx":[-3.91849,3.92019,3.91849,-3.92019], "fy":[-3.92019,-3.91849,3.92019,3.91849]}, + {"t":0.23386, "x":3.05111, "y":3.78194, "heading":1.57507, "vx":-0.78387, "vy":-0.62051, "omega":0.18791, "ax":0.0, "ay":0.0, "alpha":1.73467, "fx":[-3.15803,3.18502,3.15803,-3.18502], "fy":[-3.18502,-3.15803,3.18502,3.15803]}, + {"t":0.27284, "x":3.02056, "y":3.75776, "heading":1.5824, "vx":-0.78387, "vy":-0.62051, "omega":0.25552, "ax":0.0, "ay":0.0, "alpha":1.50054, "fx":[-2.7121,2.77451,2.7121,-2.77451], "fy":[-2.77451,-2.7121,2.77451,2.7121]}, + {"t":0.31181, "x":2.99001, "y":3.73357, "heading":1.59235, "vx":-0.78387, "vy":-0.62051, "omega":0.31401, "ax":0.0, "ay":0.0, "alpha":1.09541, "fx":[-1.95889,2.04569,1.95889,-2.04569], "fy":[-2.04569,-1.95889,2.04569,1.95889]}, + {"t":0.35079, "x":2.95945, "y":3.70939, "heading":1.60459, "vx":-0.78387, "vy":-0.62051, "omega":0.35671, "ax":0.0, "ay":0.0, "alpha":1.05051, "fx":[-1.85609,1.98316,1.85609,-1.98316], "fy":[-1.98316,-1.85609,1.98316,1.85609]}, + {"t":0.38977, "x":2.9289, "y":3.6852, "heading":1.6185, "vx":-0.78387, "vy":-0.62051, "omega":0.39765, "ax":0.0, "ay":0.0, "alpha":0.64528, "fx":[-1.12065,1.23609,1.12065,-1.23609], "fy":[-1.23609,-1.12065,1.23609,1.12065]}, + {"t":0.42874, "x":2.89835, "y":3.66102, "heading":1.634, "vx":-0.78387, "vy":-0.62051, "omega":0.4228, "ax":0.0, "ay":0.0, "alpha":0.70939, "fx":[-1.21398,1.37501,1.21398,-1.37501], "fy":[-1.37501,-1.21398,1.37501,1.21398]}, + {"t":0.46772, "x":2.8678, "y":3.63683, "heading":1.65048, "vx":-0.78387, "vy":-0.62051, "omega":0.45045, "ax":0.0, "ay":0.0, "alpha":0.35911, "fx":[-0.59917,0.70935,0.59917,-0.70935], "fy":[-0.70935,-0.59917,0.70935,0.59917]}, + {"t":0.5067, "x":2.83724, "y":3.61265, "heading":1.66803, "vx":-0.78387, "vy":-0.62051, "omega":0.46445, "ax":0.0, "ay":0.0, "alpha":0.44397, "fx":[-0.72952,0.88634,0.72952,-0.88634], "fy":[-0.88634,-0.72952,0.88634,0.72952]}, + {"t":0.54567, "x":2.80669, "y":3.58846, "heading":1.68614, "vx":-0.78387, "vy":-0.62051, "omega":0.48175, "ax":0.0, "ay":0.0, "alpha":0.19878, "fx":[-0.3154,0.40586,0.3154,-0.40586], "fy":[-0.40586,-0.3154,0.40586,0.3154]}, + {"t":0.58465, "x":2.77614, "y":3.56428, "heading":1.70491, "vx":-0.78387, "vy":-0.62051, "omega":0.4895, "ax":0.0, "ay":0.0, "alpha":0.24522, "fx":[-0.38295,0.50535,0.38295,-0.50535], "fy":[-0.50535,-0.38295,0.50535,0.38295]}, + {"t":0.62363, "x":2.74558, "y":3.54009, "heading":1.72399, "vx":-0.78387, "vy":-0.62051, "omega":0.49906, "ax":0.0, "ay":0.0, "alpha":0.12424, "fx":[-0.18651,0.26159,0.18651,-0.26159], "fy":[-0.26159,-0.18651,0.26159,0.18651]}, + {"t":0.6626, "x":2.71503, "y":3.5159, "heading":1.74344, "vx":-0.78387, "vy":-0.62051, "omega":0.5039, "ax":0.0, "ay":0.0, "alpha":0.10341, "fx":[-0.15036,0.22113,0.15036,-0.22113], "fy":[-0.22113,-0.15036,0.22113,0.15036]}, + {"t":0.70158, "x":2.68448, "y":3.49172, "heading":1.76308, "vx":-0.78387, "vy":-0.62051, "omega":0.50793, "ax":0.0, "ay":0.0, "alpha":0.10046, "fx":[-0.14334,0.21665,0.14334,-0.21665], "fy":[-0.21665,-0.14334,0.21665,0.14334]}, + {"t":0.74056, "x":2.65393, "y":3.46753, "heading":1.78288, "vx":-0.78387, "vy":-0.62051, "omega":0.51185, "ax":0.0, "ay":0.0, "alpha":0.0087, "fx":[-0.00724,0.0221,0.00724,-0.0221], "fy":[-0.0221,-0.00724,0.0221,0.00724]}, + {"t":0.77953, "x":2.62337, "y":3.44335, "heading":1.80283, "vx":-0.78387, "vy":-0.62051, "omega":0.51219, "ax":0.0, "ay":0.0, "alpha":0.10123, "fx":[-0.13758,0.22267,0.13758,-0.22267], "fy":[-0.22267,-0.13758,0.22267,0.13758]}, + {"t":0.81851, "x":2.59282, "y":3.41916, "heading":1.82279, "vx":-0.78387, "vy":-0.62051, "omega":0.51613, "ax":0.0, "ay":0.0, "alpha":-0.05119, "fx":[0.07314,-0.11052,-0.07314,0.11052], "fy":[0.11052,0.07314,-0.11052,-0.07314]}, + {"t":0.85749, "x":2.56227, "y":3.39498, "heading":1.84291, "vx":-0.78387, "vy":-0.62051, "omega":0.51414, "ax":0.0, "ay":0.0, "alpha":0.109, "fx":[-0.1401,0.24455,0.1401,-0.24455], "fy":[-0.24455,-0.1401,0.24455,0.1401]}, + {"t":0.89646, "x":2.53172, "y":3.37079, "heading":1.86295, "vx":-0.78387, "vy":-0.62051, "omega":0.51839, "ax":0.0, "ay":0.0, "alpha":-0.08785, "fx":[0.11367,-0.19678,-0.11367,0.19678], "fy":[0.19678,0.11367,-0.19678,-0.11367]}, + {"t":0.93544, "x":2.50116, "y":3.34661, "heading":1.88316, "vx":-0.78387, "vy":-0.62051, "omega":0.51496, "ax":0.0, "ay":0.0, "alpha":0.11412, "fx":[-0.13732,0.26119,0.13732,-0.26119], "fy":[-0.26119,-0.13732,0.26119,0.13732]}, + {"t":0.97442, "x":2.47061, "y":3.32242, "heading":1.90323, "vx":-0.78387, "vy":-0.62051, "omega":0.51941, "ax":0.0, "ay":0.0, "alpha":-0.10874, "fx":[0.12894,-0.24994,-0.12894,0.24994], "fy":[0.24994,0.12894,-0.24994,-0.12894]}, + {"t":1.01339, "x":2.44006, "y":3.29824, "heading":1.92347, "vx":-0.78387, "vy":-0.62051, "omega":0.51517, "ax":0.0, "ay":0.0, "alpha":0.11237, "fx":[-0.12533,0.26215,0.12533,-0.26215], "fy":[-0.26215,-0.12533,0.26215,0.12533]}, + {"t":1.05237, "x":2.4095, "y":3.27405, "heading":1.94355, "vx":-0.78387, "vy":-0.62051, "omega":0.51955, "ax":0.0, "ay":0.0, "alpha":-0.11852, "fx":[0.1282,-0.27842,-0.1282,0.27842], "fy":[0.27842,0.1282,-0.27842,-0.1282]}, + {"t":1.09135, "x":2.37895, "y":3.24986, "heading":1.9638, "vx":-0.78387, "vy":-0.62051, "omega":0.51493, "ax":0.0, "ay":0.0, "alpha":0.10139, "fx":[-0.10379,0.24078,0.10379,-0.24078], "fy":[-0.24078,-0.10379,0.24078,0.10379]}, + {"t":1.13032, "x":2.3484, "y":3.22568, "heading":1.98387, "vx":-0.78387, "vy":-0.62051, "omega":0.51888, "ax":0.0, "ay":0.0, "alpha":-0.12241, "fx":[0.11964,-0.29308,-0.11964,0.29308], "fy":[0.29308,0.11964,-0.29308,-0.11964]}, + {"t":1.1693, "x":2.31785, "y":3.20149, "heading":2.0041, "vx":-0.78387, "vy":-0.62051, "omega":0.51411, "ax":0.0, "ay":0.0, "alpha":0.08179, "fx":[-0.07613,0.19732,0.07613,-0.19732], "fy":[-0.19732,-0.07613,0.19732,0.07613]}, + {"t":1.20828, "x":2.28729, "y":3.17731, "heading":2.02414, "vx":-0.78387, "vy":-0.62051, "omega":0.5173, "ax":0.0, "ay":0.0, "alpha":-0.12415, "fx":[0.10826,-0.30221,-0.10826,0.30221], "fy":[0.30221,0.10826,-0.30221,-0.10826]}, + {"t":1.24725, "x":2.25674, "y":3.15312, "heading":2.0443, "vx":-0.78387, "vy":-0.62051, "omega":0.51246, "ax":0.0, "ay":0.0, "alpha":0.05322, "fx":[-0.04484,0.13012,0.04484,-0.13012], "fy":[-0.13012,-0.04484,0.13012,0.04484]}, + {"t":1.28623, "x":2.22619, "y":3.12894, "heading":2.06427, "vx":-0.78387, "vy":-0.62051, "omega":0.51454, "ax":0.0, "ay":0.0, "alpha":-0.12775, "fx":[0.09784,-0.3155,-0.09784,0.3155], "fy":[0.3155,0.09784,-0.3155,-0.09784]}, + {"t":1.32521, "x":2.19563, "y":3.10475, "heading":2.08433, "vx":-0.78387, "vy":-0.62051, "omega":0.50956, "ax":0.0, "ay":0.0, "alpha":0.01723, "fx":[-0.01394,0.04235,0.01394,-0.04235], "fy":[-0.04235,-0.01394,0.04235,0.01394]}, + {"t":1.36418, "x":2.16508, "y":3.08057, "heading":2.10419, "vx":-0.78387, "vy":-0.62051, "omega":0.51023, "ax":0.0, "ay":0.0, "alpha":-0.13562, "fx":[0.08942,-0.33907,-0.08942,0.33907], "fy":[0.33907,0.08942,-0.33907,-0.08942]}, + {"t":1.40316, "x":2.13453, "y":3.05638, "heading":2.12408, "vx":-0.78387, "vy":-0.62051, "omega":0.50494, "ax":0.0, "ay":0.0, "alpha":-0.02759, "fx":[0.01503,-0.06974,-0.01503,0.06974], "fy":[0.06974,0.01503,-0.06974,-0.01503]}, + {"t":1.44214, "x":2.10398, "y":3.03219, "heading":2.14376, "vx":-0.78387, "vy":-0.62051, "omega":0.50387, "ax":0.0, "ay":0.0, "alpha":-0.15319, "fx":[0.08484,-0.38692,-0.08484,0.38692], "fy":[0.38692,0.08484,-0.38692,-0.08484]}, + {"t":1.48111, "x":2.07342, "y":3.00801, "heading":2.1634, "vx":-0.78387, "vy":-0.62051, "omega":0.4979, "ax":0.0, "ay":0.0, "alpha":-0.08226, "fx":[0.03988,-0.20893,-0.03988,0.20893], "fy":[0.20893,0.03988,-0.20893,-0.03988]}, + {"t":1.52009, "x":2.04287, "y":2.98382, "heading":2.1828, "vx":-0.78387, "vy":-0.62051, "omega":0.49469, "ax":0.0, "ay":0.0, "alpha":-0.18502, "fx":[0.08333,-0.47109,-0.08333,0.47109], "fy":[0.47109,0.08333,-0.47109,-0.08333]}, + {"t":1.55907, "x":2.01232, "y":2.95964, "heading":2.20208, "vx":-0.78387, "vy":-0.62051, "omega":0.48748, "ax":0.0, "ay":0.0, "alpha":-0.15183, "fx":[0.05976,-0.38799,-0.05976,0.38799], "fy":[0.38799,0.05976,-0.38799,-0.05976]}, + {"t":1.59804, "x":1.98177, "y":2.93545, "heading":2.22108, "vx":-0.78387, "vy":-0.62051, "omega":0.48156, "ax":0.0, "ay":0.0, "alpha":-0.24002, "fx":[0.08403,-0.61489,-0.08403,0.61489], "fy":[0.61489,0.08403,-0.61489,-0.08403]}, + {"t":1.63702, "x":1.95121, "y":2.91127, "heading":2.23985, "vx":-0.78387, "vy":-0.62051, "omega":0.4722, "ax":0.0, "ay":0.0, "alpha":-0.24339, "fx":[0.0728,-0.6251,-0.0728,0.6251], "fy":[0.6251,0.0728,-0.6251,-0.0728]}, + {"t":1.676, "x":1.92066, "y":2.88708, "heading":2.25826, "vx":-0.78387, "vy":-0.62051, "omega":0.46272, "ax":0.0, "ay":0.0, "alpha":-0.32667, "fx":[0.0828,-0.84059,-0.0828,0.84059], "fy":[0.84059,0.0828,-0.84059,-0.0828]}, + {"t":1.71497, "x":1.89011, "y":2.8629, "heading":2.27629, "vx":-0.78387, "vy":-0.62051, "omega":0.44999, "ax":0.0, "ay":0.0, "alpha":-0.36691, "fx":[0.07562,-0.94567,-0.07562,0.94567], "fy":[0.94567,0.07562,-0.94567,-0.07562]}, + {"t":1.75395, "x":1.85955, "y":2.83871, "heading":2.29383, "vx":-0.78387, "vy":-0.62051, "omega":0.43568, "ax":0.0, "ay":0.0, "alpha":-0.45789, "fx":[0.07386,-1.18164,-0.07386,1.18164], "fy":[1.18164,0.07386,-1.18164,-0.07386]}, + {"t":1.79293, "x":1.829, "y":2.81453, "heading":2.31081, "vx":-0.78387, "vy":-0.62051, "omega":0.41784, "ax":0.0, "ay":0.0, "alpha":-0.53783, "fx":[0.06306,-1.3892,-0.06305,1.3892], "fy":[1.3892,0.06305,-1.3892,-0.06306]}, + {"t":1.8319, "x":1.79845, "y":2.79034, "heading":2.3271, "vx":-0.78387, "vy":-0.62051, "omega":0.39687, "ax":0.0, "ay":0.0, "alpha":-0.65251, "fx":[0.0491,-1.68644,-0.0491,1.68645], "fy":[1.68644,0.0491,-1.68645,-0.0491]}, + {"t":1.87088, "x":1.7679, "y":2.76615, "heading":2.34257, "vx":-0.78387, "vy":-0.62051, "omega":0.37144, "ax":0.0, "ay":0.0, "alpha":-0.77888, "fx":[0.02746,-2.01371,-0.02741,2.01376], "fy":[2.0137,0.0274,-2.01377,-0.02747]}, + {"t":1.90986, "x":1.73734, "y":2.74197, "heading":2.35705, "vx":-0.78387, "vy":-0.62051, "omega":0.34108, "ax":0.00005, "ay":-0.00006, "alpha":-0.93628, "fx":[-0.00124,-2.42007,0.00288,2.4217], "fy":[2.41986,-0.00309,-2.42192,0.00103]}, + {"t":1.94883, "x":1.70679, "y":2.71778, "heading":2.37034, "vx":-0.78387, "vy":-0.62051, "omega":0.30459, "ax":0.00158, "ay":-0.002, "alpha":-1.12247, "fx":[-0.01414,-2.87514,0.06796,2.9289], "fy":[2.86807,-0.07506,-2.93596,0.00706]}, + {"t":1.98781, "x":1.67624, "y":2.6936, "heading":2.38221, "vx":-0.78381, "vy":-0.62059, "omega":0.26084, "ax":0.05225, "ay":-0.06577, "alpha":-1.34594, "fx":[0.79971,-2.59117,0.9795,4.36703], "fy":[2.36123,-1.21107,-4.59632,-1.02871]}, + {"t":2.02679, "x":1.64573, "y":2.66936, "heading":2.39238, "vx":-0.78177, "vy":-0.62315, "omega":0.20838, "ax":1.58171, "ay":-1.79572, "alpha":-1.22491, "fx":[27.24521,23.64343,26.61486,30.11433], "fy":[-27.42182,-31.11682,-33.61133,-30.02854]}, + {"t":2.06576, "x":1.61646, "y":2.64371, "heading":2.4005, "vx":-0.72012, "vy":-0.69315, "omega":0.16064, "ax":1.4587, "ay":-1.39769, "alpha":-1.18392, "fx":[24.99607,21.73381,24.66729,27.85109], "fy":[-20.69479,-24.23163,-26.81034,-23.36052]}, + {"t":2.10869, "x":1.58689, "y":2.61266, "heading":2.4074, "vx":-0.65751, "vy":-0.75314, "omega":0.10982, "ax":0.03867, "ay":-0.03368, "alpha":-1.15058, "fx":[0.50611,-2.31383,0.81015,3.62833], "fy":[2.39867,-0.72588,-3.54356,-0.42089]}, + {"t":2.15162, "x":1.5587, "y":2.5803, "heading":2.41211, "vx":-0.65585, "vy":-0.75459, "omega":0.06043, "ax":0.00089, "ay":-0.00077, "alpha":-0.90665, "fx":[-0.11592,-2.32554,0.1461,2.3557], "fy":[2.32752,-0.14413,-2.35373,0.11789]}, + {"t":2.19454, "x":1.53055, "y":2.54791, "heading":2.4147, "vx":-0.65581, "vy":-0.75462, "omega":0.02151, "ax":0.00002, "ay":-0.00002, "alpha":-0.69877, "fx":[-0.10531,-1.80333,0.106,1.80402], "fy":[1.80337,-0.10595,-1.80397,0.10535]}, + {"t":2.23747, "x":1.5024, "y":2.51552, "heading":2.41563, "vx":-0.65581, "vy":-0.75462, "omega":-0.00849, "ax":0.0, "ay":0.0, "alpha":-0.51885, "fx":[-0.07968,-1.3392,0.07969,1.33921], "fy":[1.3392,-0.07969,-1.33921,0.07968]}, + {"t":2.28039, "x":1.47425, "y":2.48313, "heading":2.41526, "vx":-0.65581, "vy":-0.75462, "omega":-0.03076, "ax":0.0, "ay":0.0, "alpha":-0.35972, "fx":[-0.05491,-0.92849,0.05491,0.92849], "fy":[0.92849,-0.05491,-0.92849,0.05491]}, + {"t":2.32332, "x":1.4461, "y":2.45073, "heading":2.41394, "vx":-0.65581, "vy":-0.75462, "omega":-0.0462, "ax":0.0, "ay":0.0, "alpha":-0.215, "fx":[-0.03208,-0.55498,0.03208,0.55498], "fy":[0.55498,-0.03208,-0.55498,0.03208]}, + {"t":2.36625, "x":1.41795, "y":2.41834, "heading":2.41196, "vx":-0.65581, "vy":-0.75462, "omega":-0.05543, "ax":0.0, "ay":0.0, "alpha":-0.0789, "fx":[-0.01137,-0.2037,0.01137,0.2037], "fy":[0.2037,-0.01137,-0.2037,0.01137]}, + {"t":2.40917, "x":1.3898, "y":2.38595, "heading":2.40958, "vx":-0.65581, "vy":-0.75462, "omega":-0.05882, "ax":0.0, "ay":0.0, "alpha":0.054, "fx":[0.00745,0.13944,-0.00745,-0.13944], "fy":[-0.13944,0.00745,0.13944,-0.00745]}, + {"t":2.4521, "x":1.36164, "y":2.35355, "heading":2.40706, "vx":-0.65581, "vy":-0.75462, "omega":-0.0565, "ax":0.0, "ay":0.0, "alpha":0.18907, "fx":[0.02485,0.48824,-0.02485,-0.48824], "fy":[-0.48824,0.02485,0.48824,-0.02485]}, + {"t":2.49502, "x":1.33349, "y":2.32116, "heading":2.40463, "vx":-0.65581, "vy":-0.75462, "omega":-0.04838, "ax":0.0, "ay":0.0, "alpha":0.33172, "fx":[0.04153,0.85671,-0.04153,-0.85671], "fy":[-0.85671,0.04153,0.85671,-0.04153]}, + {"t":2.53795, "x":1.30534, "y":2.28877, "heading":2.40255, "vx":-0.65581, "vy":-0.75462, "omega":-0.03414, "ax":0.00002, "ay":0.00003, "alpha":0.48767, "fx":[0.05883,1.25999,-0.05804,-1.2592], "fy":[-1.25914,0.05888,1.26005,-0.05798]}, + {"t":2.58087, "x":1.27719, "y":2.25638, "heading":2.40109, "vx":-0.65581, "vy":-0.75462, "omega":-0.01321, "ax":2.59339, "ay":2.98416, "alpha":0.30156, "fx":[44.44219,44.91605,43.7906,43.30274], "fy":[50.00538,50.50693,51.50786,51.01855]}, + {"t":2.6238, "x":1.25143, "y":2.22673, "heading":2.40052, "vx":-0.54448, "vy":-0.62652, "omega":-0.00026, "ax":4.22267, "ay":4.85893, "alpha":0.00291, "fx":[71.83419,71.83465,71.81866,71.8182], "fy":[82.6422,82.6419,82.65579,82.65609]}, + {"t":2.66673, "x":1.23195, "y":2.20432, "heading":2.40051, "vx":-0.36322, "vy":-0.41795, "omega":-0.00014, "ax":4.22964, "ay":4.86695, "alpha":0.00181, "fx":[71.94979,71.95005,71.94009,71.93982], "fy":[82.78114,82.78093,82.78959,82.7898]}, + {"t":2.70965, "x":1.22025, "y":2.19086, "heading":2.4005, "vx":-0.18166, "vy":-0.20903, "omega":-0.00006, "ax":4.23197, "ay":4.86963, "alpha":0.00144, "fx":[71.9885,71.98871,71.98078,71.98057], "fy":[82.82769,82.82752,82.83441,82.83458]}, + {"t":2.75258, "x":1.21635, "y":2.18637, "heading":2.4005, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.01301, "ay":4.01602, "alpha":-2.80111, "fx":[78.56655,79.43799,92.86166,90.21305], "fy":[76.62122,75.6823,58.44621,62.4958]}, + {"t":2.7881, "x":1.21952, "y":2.18891, "heading":2.4005, "vx":0.17809, "vy":0.14267, "omega":-0.09951, "ax":5.01324, "ay":4.01595, "alpha":-2.76846, "fx":[78.64148,79.51587,92.77422,90.16333], "fy":[76.53273,75.58681,58.56775,62.55362]}, + {"t":2.82363, "x":1.22901, "y":2.19651, "heading":2.39697, "vx":0.35618, "vy":0.28534, "omega":-0.19786, "ax":5.01349, "ay":4.01586, "alpha":-2.73145, "fx":[78.7482,79.57594,92.66019,90.1279], "fy":[76.40966,75.50804,58.72831,62.58867]}, + {"t":2.85915, "x":1.24482, "y":2.20918, "heading":2.38994, "vx":0.53429, "vy":0.428, "omega":-0.29489, "ax":5.01378, "ay":4.01574, "alpha":-2.68898, "fx":[78.8881,79.62268,92.51697,90.10378], "fy":[76.2499,75.44091,58.93093,62.60482]}, + {"t":2.89468, "x":1.26697, "y":2.22692, "heading":2.37946, "vx":0.7124, "vy":0.57066, "omega":-0.39042, "ax":5.01409, "ay":4.01559, "alpha":-2.63954, "fx":[79.06314,79.6621,92.34089,90.08692], "fy":[76.05044,75.37859,59.17992,62.60725]}, + {"t":2.9302, "x":1.29544, "y":2.24972, "heading":2.36559, "vx":0.89053, "vy":0.71331, "omega":-0.48419, "ax":5.01445, "ay":4.0154, "alpha":-2.58115, "fx":[79.27616,79.70217,92.12697,90.07184], "fy":[75.80704,75.31185,59.4811,62.60293]}, + {"t":2.96573, "x":1.33024, "y":2.2776, "heading":2.34839, "vx":1.06866, "vy":0.85596, "omega":-0.57588, "ax":5.01484, "ay":4.01514, "alpha":-2.51099, "fx":[79.53114,79.75363,91.86835,90.05097], "fy":[75.5137,75.22822,59.84237,62.60145]}, + {"t":3.00125, "x":1.37137, "y":2.31054, "heading":2.32793, "vx":1.24682, "vy":0.9986, "omega":-0.66509, "ax":5.01528, "ay":4.01481, "alpha":-2.42507, "fx":[79.83375,79.83126,91.55556,90.01353], "fy":[75.16183,75.11034,60.27444,62.61639]}, + {"t":3.03678, "x":1.41883, "y":2.34855, "heading":2.3043, "vx":1.42498, "vy":1.14122, "omega":-0.75124, "ax":5.01577, "ay":4.01435, "alpha":-2.31743, "fx":[80.19245,79.95598,91.17508,89.94359], "fy":[74.73859,74.93329,60.79225,62.6677]}, + {"t":3.0723, "x":1.47261, "y":2.39162, "heading":2.27762, "vx":1.60317, "vy":1.28383, "omega":-0.83356, "ax":5.01628, "ay":4.01369, "alpha":-2.17883, "fx":[80.6204,80.15872,90.70667,89.8163], "fy":[74.2238,74.65947,61.41764,62.7861]}, + {"t":3.10783, "x":1.53273, "y":2.43976, "heading":2.248, "vx":1.78137, "vy":1.42642, "omega":-0.91097, "ax":5.01678, "ay":4.01268, "alpha":-1.99388, "fx":[81.1396,80.48798,90.11819,89.59024], "fy":[73.58343,74.22839,62.1845,63.02196]}, + {"t":3.14335, "x":1.59918, "y":2.49297, "heading":2.21564, "vx":1.95959, "vy":1.56897, "omega":-0.9818, "ax":5.01713, "ay":4.011, "alpha":-1.735, "fx":[81.79025,81.02559,89.35407,89.18961], "fy":[72.75452,73.53423,63.14991,63.46508]}, + {"t":3.17888, "x":1.67196, "y":2.55124, "heading":2.18076, "vx":2.13783, "vy":1.71146, "omega":-1.04344, "ax":5.01689, "ay":4.00786, "alpha":-1.34681, "fx":[82.65502,81.92418,88.30713,88.45731], "fy":[71.60482,72.36961,64.42073,64.29486]}, + {"t":3.2144, "x":1.75107, "y":2.61457, "heading":2.1437, "vx":2.31605, "vy":1.85384, "omega":-1.09128, "ax":5.01452, "ay":4.00094, "alpha":-0.69856, "fx":[83.93546,83.51007,86.73633,87.00064], "fy":[69.79981,70.25754,66.22755,65.93474]}, + {"t":3.24993, "x":1.83652, "y":2.68295, "heading":2.10493, "vx":2.49419, "vy":1.99597, "omega":-1.1161, "ax":5.00221, "ay":3.98071, "alpha":0.61505, "fx":[86.27981,86.6334,83.95577,83.47534], "fy":[66.1786,65.7889,69.18247,69.69291]}, + {"t":3.28545, "x":1.92828, "y":2.75637, "heading":2.06528, "vx":2.6719, "vy":2.13739, "omega":-1.09425, "ax":4.8964, "ay":3.85955, "alpha":4.90177, "fx":[93.31014,94.24242,76.94917,68.64388], "fy":[52.36214,52.30602,75.59013,82.34093]}, + {"t":3.32098, "x":2.02629, "y":2.83473, "heading":2.02641, "vx":2.84584, "vy":2.2745, "omega":-0.92011, "ax":-0.04487, "ay":-0.05809, "alpha":0.20237, "fx":[-0.93258,-0.26807,-0.59378,-1.25829], "fy":[-1.48304,-1.15758,-0.49298,-0.81856]}, + {"t":3.3565, "x":2.12736, "y":2.9155, "heading":1.99372, "vx":2.84425, "vy":2.27243, "omega":-0.91292, "ax":-4.86754, "ay":-3.82724, "alpha":-5.96025, "fx":[-94.3506,-96.29119,-76.66913,-63.87092], "fy":[-49.99059,-48.42901,-75.94026,-86.04143]}, + {"t":3.39203, "x":2.22533, "y":2.99381, "heading":1.96129, "vx":2.67133, "vy":2.13647, "omega":-1.12466, "ax":-5.00104, "ay":-3.97843, "alpha":-0.93531, "fx":[-86.54769,-87.6189,-83.73715,-82.36151], "fy":[-65.78224,-64.46258,-69.45772,-70.98531]}, + {"t":3.42755, "x":2.31707, "y":3.0672, "heading":1.92133, "vx":2.49367, "vy":1.99514, "omega":-1.15789, "ax":-5.01516, "ay":-4.0006, "alpha":0.58467, "fx":[-84.51434,-83.59338,-86.1586,-86.95971], "fy":[-69.09057,-70.16179,-66.97157,-65.97247]}, + {"t":3.46308, "x":2.40249, "y":3.13555, "heading":1.8802, "vx":2.3155, "vy":1.85302, "omega":-1.13712, "ax":-5.01724, "ay":-4.00749, "alpha":1.32861, "fx":[-83.77495,-81.28256,-87.21533,-89.0942], "fy":[-70.2947,-73.10019,-65.87761,-63.39237]}, + {"t":3.4986, "x":2.48158, "y":3.19885, "heading":1.8398, "vx":2.13726, "vy":1.71065, "omega":-1.08992, "ax":-5.01699, "ay":-4.0103, "alpha":1.76959, "fx":[-83.51542,-79.77247,-87.69534,-90.36727], "fy":[-70.77521,-74.90703,-65.41585,-61.75832]}, + {"t":3.53413, "x":2.55435, "y":3.25709, "heading":1.80108, "vx":1.95904, "vy":1.56818, "omega":-1.02705, "ax":-5.01625, "ay":-4.01164, "alpha":2.06033, "fx":[-83.47707,-78.70606,-87.88324,-91.23343], "fy":[-70.93033,-76.13333,-65.28452,-60.59924]}, + {"t":3.56965, "x":2.62077, "y":3.31027, "heading":1.7646, "vx":1.78083, "vy":1.42567, "omega":-0.95386, "ax":-5.01544, "ay":-4.01234, "alpha":2.26568, "fx":[-83.55071,-77.9153,-87.90876,-91.87033], "fy":[-70.91978,-77.01773,-65.33786,-59.71989]}, + {"t":3.60518, "x":2.68087, "y":3.35839, "heading":1.73071, "vx":1.60266, "vy":1.28313, "omega":-0.87337, "ax":-5.0147, "ay":-4.01274, "alpha":2.41802, "fx":[-83.68167,-77.30972,-87.84082,-92.36205], "fy":[-70.82118,-77.68157,-65.49548,-59.02427]}, + {"t":3.6407, "x":2.73464, "y":3.40144, "heading":1.69969, "vx":1.42451, "vy":1.14058, "omega":-0.78747, "ax":-5.01403, "ay":-4.01299, "alpha":2.53534, "fx":[-83.83925,-76.83533,-87.72031,-92.75397], "fy":[-70.67744,-78.19396,-65.70864,-58.45908]}, + {"t":3.67623, "x":2.78209, "y":3.43942, "heading":1.67171, "vx":1.24639, "vy":0.99802, "omega":-0.6974, "ax":-5.01344, "ay":-4.01315, "alpha":2.62844, "fx":[-84.00477,-76.4573,-87.57357,-93.07308], "fy":[-70.51453,-78.59786,-65.94575,-57.9918]}, + {"t":3.71175, "x":2.8232, "y":3.47235, "heading":1.64694, "vx":1.06829, "vy":0.85545, "omega":-0.60403, "ax":-5.01292, "ay":-4.01326, "alpha":2.70416, "fx":[-84.16614,-76.15168,-87.41863,-93.33674], "fy":[-70.34931,-78.92177,-66.1852,-57.60103]}, + {"t":3.74728, "x":2.85799, "y":3.5002, "heading":1.62548, "vx":0.8902, "vy":0.71288, "omega":-0.50796, "ax":-5.01245, "ay":-4.01333, "alpha":2.76705, "fx":[-84.3152,-75.90124,-87.26842,-93.55674], "fy":[-70.19332,-79.1856,-66.41171,-57.27188]}, + {"t":3.7828, "x":2.88645, "y":3.523, "heading":1.60743, "vx":0.71214, "vy":0.57031, "omega":-0.40966, "ax":-5.01204, "ay":-4.01339, "alpha":2.8202, "fx":[-84.44622,-75.69313,-87.13253,-93.74153], "fy":[-70.05475,-79.40378,-66.61414,-56.99347]}, + {"t":3.81833, "x":2.90859, "y":3.54072, "heading":1.59288, "vx":0.53408, "vy":0.42773, "omega":-0.30948, "ax":-5.01167, "ay":-4.01342, "alpha":2.8658, "fx":[-84.55504,-75.51757,-87.01825,-93.89729], "fy":[-69.93965,-79.58711,-66.78418,-56.75764]}, + {"t":3.85385, "x":2.9244, "y":3.55339, "heading":1.58188, "vx":0.35604, "vy":0.28516, "omega":-0.20767, "ax":-5.01133, "ay":-4.01344, "alpha":2.90544, "fx":[-84.63857,-75.367,-86.93123,-94.02867], "fy":[-69.85258,-79.74373,-66.91551,-56.55817]}, + {"t":3.88938, "x":2.93388, "y":3.56098, "heading":1.57451, "vx":0.17802, "vy":0.14258, "omega":-0.10445, "ax":-5.01104, "ay":-4.01345, "alpha":2.9403, "fx":[-84.69446,-75.2356,-86.87588,-94.13917], "fy":[-69.79705,-79.87986,-67.00323,-56.39031]}, + {"t":3.9249, "x":2.93704, "y":3.56352, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_3_BACK.traj b/src/main/deploy/choreo/E_RIGHT_PATH_3_BACK.traj index df62627d..69b0191a 100644 --- a/src/main/deploy/choreo/E_RIGHT_PATH_3_BACK.traj +++ b/src/main/deploy/choreo/E_RIGHT_PATH_3_BACK.traj @@ -3,26 +3,28 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":3.199847936630249, "y":3.813179254531861, "heading":1.5707963267948966, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":3.199847936630249, "y":3.813179254531861, "heading":1.5707963267948966, "intervals":43, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":1.2258362770080566, "y":4.026000022888184, "heading":1.5707963267948966, "intervals":20, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":2.785933017730713, "y":4.141683101654053, "heading":1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":1, "data":{"type":"MaxVelocity", "props":{"max":1.0}}, "enabled":true}], "targetDt":0.05 }, "params":{ "waypoints":[ - {"x":{"exp":"3.199847936630249 m", "val":3.199847936630249}, "y":{"exp":"3.8131792545318604 m", "val":3.813179254531861}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":23, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"3.199847936630249 m", "val":3.199847936630249}, "y":{"exp":"3.8131792545318604 m", "val":3.813179254531861}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":43, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":{"exp":"1.2258362770080566 m", "val":1.2258362770080566}, "y":{"exp":"4.026000022888184 m", "val":4.026000022888184}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":20, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":{"exp":"2.785933017730713 m", "val":2.785933017730713}, "y":{"exp":"4.141683101654053 m", "val":4.141683101654053}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, {"from":1, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":1, "data":{"type":"MaxVelocity", "props":{"max":{"exp":"1 m / s", "val":1.0}}}, "enabled":true}], "targetDt":{ "exp":"0.05 s", "val":0.05 @@ -30,52 +32,72 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,1.11081,2.09591], + "waypoints":[0.0,2.14243,3.12753], "samples":[ - {"t":0.0, "x":3.19985, "y":3.81318, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.41597, "ay":0.69171, "alpha":0.0, "fx":[-109.13382,-109.13382,-109.13382,-109.13382], "fy":[11.76586,11.76586,11.76586,11.76586]}, - {"t":0.0483, "x":3.19237, "y":3.81399, "heading":1.5708, "vx":-0.30987, "vy":0.03341, "omega":0.0, "ax":-6.41542, "ay":0.69165, "alpha":0.0, "fx":[-109.12438,-109.12438,-109.12438,-109.12438], "fy":[11.76484,11.76484,11.76484,11.76484]}, - {"t":0.09659, "x":3.16992, "y":3.81641, "heading":1.5708, "vx":-0.61971, "vy":0.06681, "omega":0.0, "ax":-6.41474, "ay":0.69158, "alpha":0.0, "fx":[-109.11285,-109.11285,-109.11285,-109.11285], "fy":[11.7636,11.7636,11.7636,11.7636]}, - {"t":0.14489, "x":3.13251, "y":3.82044, "heading":1.5708, "vx":-0.92952, "vy":0.10021, "omega":0.0, "ax":-6.41389, "ay":0.69149, "alpha":0.0, "fx":[-109.09844,-109.09844,-109.09844,-109.09844], "fy":[11.76204,11.76204,11.76204,11.76204]}, - {"t":0.19318, "x":3.08013, "y":3.82609, "heading":1.5708, "vx":-1.23928, "vy":0.13361, "omega":0.0, "ax":-6.4128, "ay":0.69137, "alpha":0.0, "fx":[-109.07991,-109.07991,-109.07991,-109.07991], "fy":[11.76005,11.76005,11.76005,11.76005]}, - {"t":0.24148, "x":3.0128, "y":3.83334, "heading":1.5708, "vx":-1.549, "vy":0.167, "omega":0.0, "ax":-6.41135, "ay":0.69122, "alpha":0.0, "fx":[-109.05519,-109.05519,-109.05519,-109.05519], "fy":[11.75738,11.75738,11.75738,11.75738]}, - {"t":0.28978, "x":2.93052, "y":3.84222, "heading":1.5708, "vx":-1.85864, "vy":0.20038, "omega":0.0, "ax":-6.40931, "ay":0.691, "alpha":0.0, "fx":[-109.02059,-109.02059,-109.02059,-109.02059], "fy":[11.75365,11.75365,11.75365,11.75365]}, - {"t":0.33807, "x":2.83327, "y":3.8527, "heading":1.5708, "vx":-2.16819, "vy":0.23375, "omega":0.0, "ax":-6.40626, "ay":0.69067, "alpha":0.0, "fx":[-108.9687,-108.9687,-108.9687,-108.9687], "fy":[11.74806,11.74806,11.74806,11.74806]}, - {"t":0.38637, "x":2.72109, "y":3.86479, "heading":1.5708, "vx":-2.47758, "vy":0.26711, "omega":0.0, "ax":-6.40118, "ay":0.69012, "alpha":0.0, "fx":[-108.88222,-108.88222,-108.88222,-108.88222], "fy":[11.73873,11.73873,11.73873,11.73873]}, - {"t":0.43467, "x":2.59396, "y":3.8785, "heading":1.5708, "vx":-2.78674, "vy":0.30044, "omega":0.0, "ax":-6.39102, "ay":0.68902, "alpha":0.0, "fx":[-108.70939,-108.70939,-108.70939,-108.70939], "fy":[11.7201,11.7201,11.7201,11.7201]}, - {"t":0.48296, "x":2.45192, "y":3.89381, "heading":1.5708, "vx":-3.0954, "vy":0.33372, "omega":0.0, "ax":-6.36061, "ay":0.68575, "alpha":0.0, "fx":[-108.19218,-108.19218,-108.19218,-108.19218], "fy":[11.66434,11.66434,11.66434,11.66434]}, - {"t":0.53126, "x":2.29501, "y":3.91073, "heading":1.5708, "vx":-3.40259, "vy":0.36684, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, - {"t":0.57955, "x":2.13068, "y":3.92845, "heading":1.5708, "vx":-3.40259, "vy":0.36684, "omega":0.0, "ax":6.36061, "ay":-0.68575, "alpha":0.0, "fx":[108.19218,108.19218,108.19218,108.19218], "fy":[-11.66434,-11.66434,-11.66434,-11.66434]}, - {"t":0.62785, "x":1.97376, "y":3.94537, "heading":1.5708, "vx":-3.0954, "vy":0.33372, "omega":0.0, "ax":6.39102, "ay":-0.68902, "alpha":0.0, "fx":[108.70939,108.70939,108.70939,108.70939], "fy":[-11.7201,-11.7201,-11.7201,-11.7201]}, - {"t":0.67615, "x":1.83172, "y":3.96068, "heading":1.5708, "vx":-2.78674, "vy":0.30044, "omega":0.0, "ax":6.40118, "ay":-0.69012, "alpha":0.0, "fx":[108.88222,108.88222,108.88222,108.88222], "fy":[-11.73873,-11.73873,-11.73873,-11.73873]}, - {"t":0.72444, "x":1.7046, "y":3.97438, "heading":1.5708, "vx":-2.47758, "vy":0.26711, "omega":0.0, "ax":6.40626, "ay":-0.69067, "alpha":0.0, "fx":[108.9687,108.9687,108.9687,108.9687], "fy":[-11.74806,-11.74806,-11.74806,-11.74806]}, - {"t":0.77274, "x":1.59241, "y":3.98648, "heading":1.5708, "vx":-2.16819, "vy":0.23375, "omega":0.0, "ax":6.40931, "ay":-0.691, "alpha":0.0, "fx":[109.02059,109.02059,109.02059,109.02059], "fy":[-11.75365,-11.75365,-11.75365,-11.75365]}, - {"t":0.82104, "x":1.49517, "y":3.99696, "heading":1.5708, "vx":-1.85864, "vy":0.20038, "omega":0.0, "ax":6.41135, "ay":-0.69122, "alpha":0.0, "fx":[109.05519,109.05519,109.05519,109.05519], "fy":[-11.75738,-11.75738,-11.75738,-11.75738]}, - {"t":0.86933, "x":1.41288, "y":4.00583, "heading":1.5708, "vx":-1.549, "vy":0.167, "omega":0.0, "ax":6.4128, "ay":-0.69137, "alpha":0.0, "fx":[109.07991,109.07991,109.07991,109.07991], "fy":[-11.76005,-11.76005,-11.76005,-11.76005]}, - {"t":0.91763, "x":1.34555, "y":4.01309, "heading":1.5708, "vx":-1.23928, "vy":0.13361, "omega":0.0, "ax":6.41389, "ay":-0.69149, "alpha":0.0, "fx":[109.09844,109.09844,109.09844,109.09844], "fy":[-11.76204,-11.76204,-11.76204,-11.76204]}, - {"t":0.96592, "x":1.29318, "y":4.01874, "heading":1.5708, "vx":-0.92952, "vy":0.10021, "omega":0.0, "ax":6.41474, "ay":-0.69158, "alpha":0.0, "fx":[109.11285,109.11285,109.11285,109.11285], "fy":[-11.7636,-11.7636,-11.7636,-11.7636]}, - {"t":1.01422, "x":1.25577, "y":4.02277, "heading":1.5708, "vx":-0.61971, "vy":0.06681, "omega":0.0, "ax":6.41542, "ay":-0.69165, "alpha":0.0, "fx":[109.12438,109.12438,109.12438,109.12438], "fy":[-11.76484,-11.76484,-11.76484,-11.76484]}, - {"t":1.06252, "x":1.23332, "y":4.02519, "heading":1.5708, "vx":-0.30987, "vy":0.03341, "omega":0.0, "ax":6.41597, "ay":-0.69171, "alpha":0.0, "fx":[109.13382,109.13382,109.13382,109.13382], "fy":[-11.76586,-11.76586,-11.76586,-11.76586]}, - {"t":1.11081, "x":1.22584, "y":4.026, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.43554, "ay":0.4772, "alpha":0.0, "fx":[109.46674,109.46674,109.46674,109.46674], "fy":[8.11709,8.11709,8.11709,8.11709]}, - {"t":1.16007, "x":1.23364, "y":4.02658, "heading":1.5708, "vx":0.31698, "vy":0.0235, "omega":0.0, "ax":6.4349, "ay":0.47716, "alpha":0.0, "fx":[109.45574,109.45574,109.45574,109.45574], "fy":[8.11628,8.11628,8.11628,8.11628]}, - {"t":1.20932, "x":1.25706, "y":4.02832, "heading":1.5708, "vx":0.63393, "vy":0.04701, "omega":0.0, "ax":6.43408, "ay":0.47709, "alpha":0.0, "fx":[109.4418,109.4418,109.4418,109.4418], "fy":[8.11524,8.11524,8.11524,8.11524]}, - {"t":1.25858, "x":1.29609, "y":4.03121, "heading":1.5708, "vx":0.95084, "vy":0.07051, "omega":0.0, "ax":6.43301, "ay":0.47702, "alpha":0.0, "fx":[109.42358,109.42358,109.42358,109.42358], "fy":[8.11389,8.11389,8.11389,8.11389]}, - {"t":1.30783, "x":1.35073, "y":4.03526, "heading":1.5708, "vx":1.2677, "vy":0.094, "omega":0.0, "ax":6.43154, "ay":0.47691, "alpha":0.0, "fx":[109.39873,109.39873,109.39873,109.39873], "fy":[8.11205,8.11205,8.11205,8.11205]}, - {"t":1.35709, "x":1.42097, "y":4.04047, "heading":1.5708, "vx":1.58449, "vy":0.11749, "omega":0.0, "ax":6.42943, "ay":0.47675, "alpha":0.0, "fx":[109.36284,109.36284,109.36284,109.36284], "fy":[8.10939,8.10939,8.10939,8.10939]}, - {"t":1.40634, "x":1.50681, "y":4.04683, "heading":1.5708, "vx":1.90117, "vy":0.14097, "omega":0.0, "ax":6.42612, "ay":0.4765, "alpha":0.0, "fx":[109.30646,109.30646,109.30646,109.30646], "fy":[8.10521,8.10521,8.10521,8.10521]}, - {"t":1.4556, "x":1.60825, "y":4.05436, "heading":1.5708, "vx":2.21769, "vy":0.16444, "omega":0.0, "ax":6.42016, "ay":0.47606, "alpha":0.0, "fx":[109.20503,109.20503,109.20503,109.20503], "fy":[8.09769,8.09769,8.09769,8.09769]}, - {"t":1.50485, "x":1.72527, "y":4.06303, "heading":1.5708, "vx":2.53391, "vy":0.18789, "omega":0.0, "ax":6.40626, "ay":0.47503, "alpha":0.0, "fx":[108.96867,108.96867,108.96867,108.96867], "fy":[8.08016,8.08016,8.08016,8.08016]}, - {"t":1.55411, "x":1.85785, "y":4.07286, "heading":1.5708, "vx":2.84945, "vy":0.21129, "omega":0.0, "ax":6.33721, "ay":0.46991, "alpha":0.0, "fx":[107.79411,107.79411,107.79411,107.79411], "fy":[7.99307,7.99307,7.99307,7.99307]}, - {"t":1.60336, "x":2.00588, "y":4.08384, "heading":1.5708, "vx":3.16159, "vy":0.23444, "omega":0.0, "ax":-6.33721, "ay":-0.46991, "alpha":0.0, "fx":[-107.79411,-107.79411,-107.79411,-107.79411], "fy":[-7.99307,-7.99307,-7.99307,-7.99307]}, - {"t":1.65262, "x":2.15392, "y":4.09482, "heading":1.5708, "vx":2.84945, "vy":0.21129, "omega":0.0, "ax":-6.40626, "ay":-0.47503, "alpha":0.0, "fx":[-108.96867,-108.96867,-108.96867,-108.96867], "fy":[-8.08016,-8.08016,-8.08016,-8.08016]}, - {"t":1.70187, "x":2.2865, "y":4.10465, "heading":1.5708, "vx":2.53391, "vy":0.18789, "omega":0.0, "ax":-6.42016, "ay":-0.47606, "alpha":0.0, "fx":[-109.20503,-109.20503,-109.20503,-109.20503], "fy":[-8.09769,-8.09769,-8.09769,-8.09769]}, - {"t":1.75113, "x":2.40352, "y":4.11333, "heading":1.5708, "vx":2.21769, "vy":0.16444, "omega":0.0, "ax":-6.42612, "ay":-0.4765, "alpha":0.0, "fx":[-109.30646,-109.30646,-109.30646,-109.30646], "fy":[-8.10521,-8.10521,-8.10521,-8.10521]}, - {"t":1.80038, "x":2.50496, "y":4.12085, "heading":1.5708, "vx":1.90117, "vy":0.14097, "omega":0.0, "ax":-6.42943, "ay":-0.47675, "alpha":0.0, "fx":[-109.36284,-109.36284,-109.36284,-109.36284], "fy":[-8.10939,-8.10939,-8.10939,-8.10939]}, - {"t":1.84964, "x":2.5908, "y":4.12721, "heading":1.5708, "vx":1.58449, "vy":0.11749, "omega":0.0, "ax":-6.43154, "ay":-0.47691, "alpha":0.0, "fx":[-109.39873,-109.39873,-109.39873,-109.39873], "fy":[-8.11205,-8.11205,-8.11205,-8.11205]}, - {"t":1.89889, "x":2.66104, "y":4.13242, "heading":1.5708, "vx":1.2677, "vy":0.094, "omega":0.0, "ax":-6.43301, "ay":-0.47702, "alpha":0.0, "fx":[-109.42358,-109.42358,-109.42358,-109.42358], "fy":[-8.11389,-8.11389,-8.11389,-8.11389]}, - {"t":1.94815, "x":2.71568, "y":4.13647, "heading":1.5708, "vx":0.95084, "vy":0.07051, "omega":0.0, "ax":-6.43408, "ay":-0.47709, "alpha":0.0, "fx":[-109.4418,-109.4418,-109.4418,-109.4418], "fy":[-8.11524,-8.11524,-8.11524,-8.11524]}, - {"t":1.9974, "x":2.75471, "y":4.13937, "heading":1.5708, "vx":0.63393, "vy":0.04701, "omega":0.0, "ax":-6.4349, "ay":-0.47716, "alpha":0.0, "fx":[-109.45574,-109.45574,-109.45574,-109.45574], "fy":[-8.11628,-8.11628,-8.11628,-8.11628]}, - {"t":2.04666, "x":2.77813, "y":4.1411, "heading":1.5708, "vx":0.31698, "vy":0.0235, "omega":0.0, "ax":-6.43554, "ay":-0.4772, "alpha":0.0, "fx":[-109.46674,-109.46674,-109.46674,-109.46674], "fy":[-8.11709,-8.11709,-8.11709,-8.11709]}, - {"t":2.09591, "x":2.78593, "y":4.14168, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":3.19985, "y":3.81318, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.41608, "ay":0.69173, "alpha":0.0, "fx":[-109.13562,-109.13562,-109.13562,-109.13562], "fy":[11.76605,11.76605,11.76605,11.76605]}, + {"t":0.04982, "x":3.19188, "y":3.81404, "heading":1.5708, "vx":-0.31967, "vy":0.03446, "omega":0.0, "ax":-6.41335, "ay":0.69143, "alpha":0.0, "fx":[-109.08931,-109.08931,-109.08931,-109.08931], "fy":[11.76106,11.76106,11.76106,11.76106]}, + {"t":0.09965, "x":3.168, "y":3.81661, "heading":1.5708, "vx":-0.63921, "vy":0.06891, "omega":0.0, "ax":-6.40517, "ay":0.69055, "alpha":0.0, "fx":[-108.95009,-108.95009,-108.95009,-108.95009], "fy":[11.74605,11.74605,11.74605,11.74605]}, + {"t":0.14947, "x":3.1282, "y":3.8209, "heading":1.5708, "vx":-0.95834, "vy":0.10332, "omega":0.0, "ax":-0.71637, "ay":0.07723, "alpha":0.0, "fx":[-12.18522,-12.18522,-12.18522,-12.18522], "fy":[1.3137,1.3137,1.3137,1.3137]}, + {"t":0.1993, "x":3.07956, "y":3.82615, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[-0.00004,-0.00004,-0.00004,-0.00004], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.24912, "x":3.03003, "y":3.83149, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.29894, "x":2.98051, "y":3.83683, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.34877, "x":2.93098, "y":3.84217, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.39859, "x":2.88145, "y":3.84751, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.44842, "x":2.83193, "y":3.85285, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.49824, "x":2.7824, "y":3.85818, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.54806, "x":2.73287, "y":3.86352, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.59789, "x":2.68335, "y":3.86886, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.64771, "x":2.63382, "y":3.8742, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.69754, "x":2.58429, "y":3.87954, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.74736, "x":2.53477, "y":3.88488, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.79718, "x":2.48524, "y":3.89022, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.84701, "x":2.43571, "y":3.89556, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.89683, "x":2.38619, "y":3.9009, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.94665, "x":2.33666, "y":3.90624, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":0.99648, "x":2.28713, "y":3.91158, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.0463, "x":2.23761, "y":3.91692, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.09613, "x":2.18808, "y":3.92226, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.14595, "x":2.13855, "y":3.9276, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.19577, "x":2.08903, "y":3.93294, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.2456, "x":2.0395, "y":3.93828, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.29542, "x":1.98997, "y":3.94362, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.34525, "x":1.94044, "y":3.94896, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.39507, "x":1.89092, "y":3.9543, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.44489, "x":1.84139, "y":3.95964, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.49472, "x":1.79186, "y":3.96498, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.54454, "x":1.74234, "y":3.97032, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.59437, "x":1.69281, "y":3.97565, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.64419, "x":1.64328, "y":3.98099, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.69401, "x":1.59376, "y":3.98633, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.74384, "x":1.54423, "y":3.99167, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.79366, "x":1.4947, "y":3.99701, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.84349, "x":1.44518, "y":4.00235, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.89331, "x":1.39565, "y":4.00769, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.00004,0.00004,0.00004,0.00004], "fy":[0.0,0.0,0.0,0.0]}, + {"t":1.94313, "x":1.34612, "y":4.01303, "heading":1.5708, "vx":-0.99404, "vy":0.10717, "omega":0.0, "ax":0.71637, "ay":-0.07723, "alpha":0.0, "fx":[12.18522,12.18522,12.18522,12.18522], "fy":[-1.3137,-1.3137,-1.3137,-1.3137]}, + {"t":1.99296, "x":1.29749, "y":4.01828, "heading":1.5708, "vx":-0.95834, "vy":0.10332, "omega":0.0, "ax":6.40517, "ay":-0.69055, "alpha":0.0, "fx":[108.95009,108.95009,108.95009,108.95009], "fy":[-11.74605,-11.74605,-11.74605,-11.74605]}, + {"t":2.04278, "x":1.25769, "y":4.02257, "heading":1.5708, "vx":-0.63921, "vy":0.06891, "omega":0.0, "ax":6.41335, "ay":-0.69143, "alpha":0.0, "fx":[109.08931,109.08931,109.08931,109.08931], "fy":[-11.76106,-11.76106,-11.76106,-11.76106]}, + {"t":2.09261, "x":1.2338, "y":4.02514, "heading":1.5708, "vx":-0.31967, "vy":0.03446, "omega":0.0, "ax":6.41608, "ay":-0.69173, "alpha":0.0, "fx":[109.13562,109.13562,109.13562,109.13562], "fy":[-11.76605,-11.76605,-11.76605,-11.76605]}, + {"t":2.14243, "x":1.22584, "y":4.026, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.43554, "ay":0.4772, "alpha":0.0, "fx":[109.46674,109.46674,109.46674,109.46674], "fy":[8.11709,8.11709,8.11709,8.11709]}, + {"t":2.19168, "x":1.23364, "y":4.02658, "heading":1.5708, "vx":0.31698, "vy":0.0235, "omega":0.0, "ax":6.4349, "ay":0.47716, "alpha":0.0, "fx":[109.45574,109.45574,109.45574,109.45574], "fy":[8.11628,8.11628,8.11628,8.11628]}, + {"t":2.24094, "x":1.25706, "y":4.02832, "heading":1.5708, "vx":0.63393, "vy":0.04701, "omega":0.0, "ax":6.43408, "ay":0.47709, "alpha":0.0, "fx":[109.4418,109.4418,109.4418,109.4418], "fy":[8.11524,8.11524,8.11524,8.11524]}, + {"t":2.29019, "x":1.29609, "y":4.03121, "heading":1.5708, "vx":0.95084, "vy":0.07051, "omega":0.0, "ax":6.43301, "ay":0.47702, "alpha":0.0, "fx":[109.42358,109.42358,109.42358,109.42358], "fy":[8.11389,8.11389,8.11389,8.11389]}, + {"t":2.33945, "x":1.35073, "y":4.03526, "heading":1.5708, "vx":1.2677, "vy":0.094, "omega":0.0, "ax":6.43154, "ay":0.47691, "alpha":0.0, "fx":[109.39873,109.39873,109.39873,109.39873], "fy":[8.11205,8.11205,8.11205,8.11205]}, + {"t":2.3887, "x":1.42097, "y":4.04047, "heading":1.5708, "vx":1.58449, "vy":0.11749, "omega":0.0, "ax":6.42943, "ay":0.47675, "alpha":0.0, "fx":[109.36284,109.36284,109.36284,109.36284], "fy":[8.10939,8.10939,8.10939,8.10939]}, + {"t":2.43796, "x":1.50681, "y":4.04683, "heading":1.5708, "vx":1.90117, "vy":0.14097, "omega":0.0, "ax":6.42612, "ay":0.4765, "alpha":0.0, "fx":[109.30646,109.30646,109.30646,109.30646], "fy":[8.10521,8.10521,8.10521,8.10521]}, + {"t":2.48721, "x":1.60825, "y":4.05436, "heading":1.5708, "vx":2.21769, "vy":0.16444, "omega":0.0, "ax":6.42016, "ay":0.47606, "alpha":0.0, "fx":[109.20503,109.20503,109.20503,109.20503], "fy":[8.09769,8.09769,8.09769,8.09769]}, + {"t":2.53647, "x":1.72527, "y":4.06303, "heading":1.5708, "vx":2.53391, "vy":0.18789, "omega":0.0, "ax":6.40626, "ay":0.47503, "alpha":0.0, "fx":[108.96867,108.96867,108.96867,108.96867], "fy":[8.08016,8.08016,8.08016,8.08016]}, + {"t":2.58572, "x":1.85785, "y":4.07286, "heading":1.5708, "vx":2.84945, "vy":0.21129, "omega":0.0, "ax":6.33721, "ay":0.46991, "alpha":0.0, "fx":[107.79411,107.79411,107.79411,107.79411], "fy":[7.99307,7.99307,7.99307,7.99307]}, + {"t":2.63498, "x":2.00588, "y":4.08384, "heading":1.5708, "vx":3.16159, "vy":0.23444, "omega":0.0, "ax":-6.33721, "ay":-0.46991, "alpha":0.0, "fx":[-107.79411,-107.79411,-107.79411,-107.79411], "fy":[-7.99307,-7.99307,-7.99307,-7.99307]}, + {"t":2.68423, "x":2.15392, "y":4.09482, "heading":1.5708, "vx":2.84945, "vy":0.21129, "omega":0.0, "ax":-6.40626, "ay":-0.47503, "alpha":0.0, "fx":[-108.96867,-108.96867,-108.96867,-108.96867], "fy":[-8.08016,-8.08016,-8.08016,-8.08016]}, + {"t":2.73349, "x":2.2865, "y":4.10465, "heading":1.5708, "vx":2.53391, "vy":0.18789, "omega":0.0, "ax":-6.42016, "ay":-0.47606, "alpha":0.0, "fx":[-109.20503,-109.20503,-109.20503,-109.20503], "fy":[-8.09769,-8.09769,-8.09769,-8.09769]}, + {"t":2.78274, "x":2.40352, "y":4.11333, "heading":1.5708, "vx":2.21769, "vy":0.16444, "omega":0.0, "ax":-6.42612, "ay":-0.4765, "alpha":0.0, "fx":[-109.30646,-109.30646,-109.30646,-109.30646], "fy":[-8.10521,-8.10521,-8.10521,-8.10521]}, + {"t":2.832, "x":2.50496, "y":4.12085, "heading":1.5708, "vx":1.90117, "vy":0.14097, "omega":0.0, "ax":-6.42943, "ay":-0.47675, "alpha":0.0, "fx":[-109.36284,-109.36284,-109.36284,-109.36284], "fy":[-8.10939,-8.10939,-8.10939,-8.10939]}, + {"t":2.88125, "x":2.5908, "y":4.12721, "heading":1.5708, "vx":1.58449, "vy":0.11749, "omega":0.0, "ax":-6.43154, "ay":-0.47691, "alpha":0.0, "fx":[-109.39873,-109.39873,-109.39873,-109.39873], "fy":[-8.11205,-8.11205,-8.11205,-8.11205]}, + {"t":2.93051, "x":2.66104, "y":4.13242, "heading":1.5708, "vx":1.2677, "vy":0.094, "omega":0.0, "ax":-6.43301, "ay":-0.47702, "alpha":0.0, "fx":[-109.42358,-109.42358,-109.42358,-109.42358], "fy":[-8.11389,-8.11389,-8.11389,-8.11389]}, + {"t":2.97976, "x":2.71568, "y":4.13647, "heading":1.5708, "vx":0.95084, "vy":0.07051, "omega":0.0, "ax":-6.43408, "ay":-0.47709, "alpha":0.0, "fx":[-109.4418,-109.4418,-109.4418,-109.4418], "fy":[-8.11524,-8.11524,-8.11524,-8.11524]}, + {"t":3.02902, "x":2.75471, "y":4.13937, "heading":1.5708, "vx":0.63393, "vy":0.04701, "omega":0.0, "ax":-6.4349, "ay":-0.47716, "alpha":0.0, "fx":[-109.45574,-109.45574,-109.45574,-109.45574], "fy":[-8.11628,-8.11628,-8.11628,-8.11628]}, + {"t":3.07827, "x":2.77813, "y":4.1411, "heading":1.5708, "vx":0.31698, "vy":0.0235, "omega":0.0, "ax":-6.43554, "ay":-0.4772, "alpha":0.0, "fx":[-109.46674,-109.46674,-109.46674,-109.46674], "fy":[-8.11709,-8.11709,-8.11709,-8.11709]}, + {"t":3.12753, "x":2.78593, "y":4.14168, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/E_RIGHT_PATH_4_BACK.traj b/src/main/deploy/choreo/E_RIGHT_PATH_4_BACK.traj index 7cedf691..8c1b69d1 100644 --- a/src/main/deploy/choreo/E_RIGHT_PATH_4_BACK.traj +++ b/src/main/deploy/choreo/E_RIGHT_PATH_4_BACK.traj @@ -3,28 +3,30 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":3.1932778358459473, "y":4.194243907928467, "heading":1.5707963267948966, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":1.9559978246688845, "y":5.059605598449707, "heading":0.7626747895755805, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":3.1932778358459473, "y":4.194243907928467, "heading":1.5707963267948966, "intervals":43, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":1.9559978246688845, "y":5.059605598449707, "heading":0.7626747895755805, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":1.2163536548614502, "y":5.85614538192749, "heading":0.7626747895755805, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":2.812213182449341, "y":4.470187187194824, "heading":1.5707963267948966, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":2, "data":{"type":"MaxVelocity", "props":{"max":1.0}}, "enabled":true}], "targetDt":0.05 }, "params":{ "waypoints":[ - {"x":{"exp":"3.1932778358459473 m", "val":3.1932778358459473}, "y":{"exp":"4.194243907928467 m", "val":4.194243907928467}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":29, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"1.9559978246688843 m", "val":1.9559978246688845}, "y":{"exp":"5.059605598449707 m", "val":5.059605598449707}, "heading":{"exp":"0.7626747895755805 rad", "val":0.7626747895755805}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"3.1932778358459473 m", "val":3.1932778358459473}, "y":{"exp":"4.194243907928467 m", "val":4.194243907928467}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":43, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"1.9559978246688843 m", "val":1.9559978246688845}, "y":{"exp":"5.059605598449707 m", "val":5.059605598449707}, "heading":{"exp":"0.7626747895755805 rad", "val":0.7626747895755805}, "intervals":25, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":{"exp":"1.2163536548614502 m", "val":1.2163536548614502}, "y":{"exp":"5.85614538192749 m", "val":5.85614538192749}, "heading":{"exp":"0.7626747895755805 rad", "val":0.7626747895755805}, "intervals":32, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":{"exp":"2.812213182449341 m", "val":2.812213182449341}, "y":{"exp":"4.470187187194824 m", "val":4.470187187194824}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, {"from":2, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}], + {"from":3, "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, + {"from":"first", "to":2, "data":{"type":"MaxVelocity", "props":{"max":{"exp":"1 m / s", "val":1.0}}}, "enabled":true}], "targetDt":{ "exp":"0.05 s", "val":0.05 @@ -32,87 +34,109 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,0.70227,1.28366,2.43338], + "waypoints":[0.0,1.58865,2.75503,3.90263], "samples":[ - {"t":0.0, "x":3.19328, "y":4.19424, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.27912, "ay":3.28254, "alpha":-5.61057, "fx":[-63.41662,-89.03718,-106.88978,-99.84165], "fy":[89.47213,64.11986,24.64636,45.1016]}, - {"t":0.02422, "x":3.19173, "y":4.19521, "heading":1.5708, "vx":-0.12784, "vy":0.07949, "omega":-0.13587, "ax":-5.27867, "ay":3.29337, "alpha":-5.53983, "fx":[-63.75912,-89.01306,-106.76459,-99.61766], "fy":[89.21791,64.14212,25.14945,45.56776]}, - {"t":0.04843, "x":3.18709, "y":4.1981, "heading":1.56751, "vx":-0.25567, "vy":0.15924, "omega":-0.27002, "ax":-5.27798, "ay":3.30458, "alpha":-5.46873, "fx":[-64.10657,-88.92846,-106.6117,-99.46079], "fy":[88.9568,64.247,25.75455,45.88138]}, - {"t":0.07265, "x":3.17935, "y":4.20292, "heading":1.56097, "vx":-0.38348, "vy":0.23927, "omega":-0.40245, "ax":-5.27704, "ay":3.31635, "alpha":-5.39575, "fx":[-64.46636,-88.78541,-106.42854,-99.36334], "fy":[88.68313,64.43092,26.46416,46.06266]}, - {"t":0.09686, "x":3.16851, "y":4.20969, "heading":1.55122, "vx":-0.51127, "vy":0.31958, "omega":-0.53312, "ax":-5.27582, "ay":3.32892, "alpha":-5.31926, "fx":[-64.8477,-88.58603,-106.21177,-99.31537], "fy":[88.3897,64.6897,27.28201,46.13468]}, - {"t":0.12108, "x":3.15459, "y":4.2184, "heading":1.53831, "vx":-0.63903, "vy":0.40019, "omega":-0.66193, "ax":-5.27429, "ay":3.34255, "alpha":-5.23738, "fx":[-65.26171,-88.33268,-105.95715,-99.30483], "fy":[88.06753,65.01846,28.21332,46.1238]}, - {"t":0.1453, "x":3.13756, "y":4.22907, "heading":1.52228, "vx":-0.76675, "vy":0.48113, "omega":-0.78876, "ax":-5.27238, "ay":3.35752, "alpha":-5.14785, "fx":[-65.72166,-88.02814,-105.65931,-99.31757], "fy":[87.70561,65.41142,29.26491,46.06015]}, - {"t":0.16951, "x":3.11745, "y":4.24171, "heading":1.50318, "vx":-0.89443, "vy":0.56244, "omega":-0.91342, "ax":-5.27005, "ay":3.37419, "alpha":-5.04788, "fx":[-66.2432,-87.67589,-105.31151,-99.3373], "fy":[87.29049,65.86172,30.44557,45.9783]}, - {"t":0.19373, "x":3.09425, "y":4.25632, "heading":1.48106, "vx":-1.02205, "vy":0.64415, "omega":-1.03566, "ax":-5.26722, "ay":3.39293, "alpha":-4.93394, "fx":[-66.84456,-87.28034,-104.90521,-99.34537], "fy":[86.80583,66.36108,31.76648,45.91802]}, - {"t":0.21795, "x":3.06795, "y":4.27291, "heading":1.45598, "vx":-1.1496, "vy":0.72631, "omega":-1.15514, "ax":-5.26382, "ay":3.4142, "alpha":-4.80157, "fx":[-67.54685,-86.84735,-104.42946,-99.32034], "fy":[86.23172,66.89937,33.24186,45.92514]}, - {"t":0.24216, "x":3.03857, "y":4.2915, "heading":1.42801, "vx":-1.27707, "vy":0.80899, "omega":-1.27141, "ax":-5.25973, "ay":3.43849, "alpha":-4.64513, "fx":[-68.37417,-86.3848,-103.87005,-99.23718], "fy":[85.54398,67.46399,34.89001,46.05274]}, - {"t":0.26638, "x":3.0061, "y":4.3121, "heading":1.39722, "vx":-1.40444, "vy":0.89226, "omega":-1.3839, "ax":-5.25481, "ay":3.46639, "alpha":-4.45747, "fx":[-69.35371,-85.90345,-103.2081,-99.06591], "fy":[84.71313,68.03893,36.73484,46.36253]}, - {"t":0.29059, "x":2.97055, "y":4.33473, "heading":1.36371, "vx":-1.53169, "vy":0.9762, "omega":-1.49184, "ax":-5.24878, "ay":3.49862, "alpha":-4.22959, "fx":[-70.51554,-85.41824,-102.41788,-98.76935], "fy":[83.70321,68.60333,38.80836,46.92689]}, - {"t":0.31481, "x":2.93192, "y":4.35939, "heading":1.32758, "vx":-1.6588, "vy":1.06092, "omega":-1.59427, "ax":-5.24119, "ay":3.53601, "alpha":-3.95009, "fx":[-71.89217,-84.95026,-101.46304,-98.29943], "fy":[82.47039,69.12925,41.15471,47.8316]}, - {"t":0.33903, "x":2.89021, "y":4.38612, "heading":1.28897, "vx":-1.78572, "vy":1.14655, "omega":-1.68992, "ax":-5.23125, "ay":3.57966, "alpha":-3.60433, "fx":[-73.51746,-84.5299,-100.2901,-97.59107], "fy":[80.9612,69.57778,43.8369,49.17984]}, - {"t":0.36324, "x":2.84544, "y":4.41493, "heading":1.24805, "vx":-1.9124, "vy":1.23324, "omega":-1.77721, "ax":-5.21754, "ay":3.631, "alpha":-3.17303, "fx":[-75.42483,-84.20212,-98.81631,-96.5522], "fy":[79.11066,69.89228,46.94856,51.09784]}, - {"t":0.38746, "x":2.7976, "y":4.44586, "heading":1.20501, "vx":-2.03875, "vy":1.32117, "omega":-1.85405, "ax":-5.19751, "ay":3.69206, "alpha":-2.62962, "fx":[-77.64437,-84.03583,-96.90548,-95.04672], "fy":[76.84009,69.98547,50.63521,53.74263]}, - {"t":0.41167, "x":2.7467, "y":4.47894, "heading":1.16012, "vx":-2.16461, "vy":1.41057, "omega":-1.91772, "ax":-5.16649, "ay":3.7657, "alpha":-1.93478, "fx":[-80.19863,-84.14191,-94.31626,-92.8655], "fy":[74.05496,69.71272,55.13468,57.3116]}, - {"t":0.43589, "x":2.69277, "y":4.5142, "heading":1.11368, "vx":-2.28972, "vy":1.50177, "omega":-1.96458, "ax":-5.11564, "ay":3.85605, "alpha":-1.024, "fx":[-83.09674,-84.7104,-90.57928,-89.6757], "fy":[70.64276,68.81103,60.8571,62.05048]}, - {"t":0.46011, "x":2.63582, "y":4.5517, "heading":1.0661, "vx":-2.41361, "vy":1.59514, "omega":-1.98938, "ax":-5.02689, "ay":3.96836, "alpha":0.22429, "fx":[-86.32606,-86.09521,-84.66858,-84.93393], "fy":[66.47177,66.73921,68.54522,68.24646]}, - {"t":0.48432, "x":2.5759, "y":4.59149, "heading":1.01793, "vx":-2.53534, "vy":1.69124, "omega":-1.98394, "ax":-4.85902, "ay":4.10456, "alpha":2.08493, "fx":[-89.8387,-89.02401,-73.98932,-77.74992], "fy":[61.3953,62.17547,79.53672,76.1621]}, - {"t":0.50854, "x":2.51308, "y":4.63365, "heading":0.96988, "vx":-2.653, "vy":1.79064, "omega":-1.93345, "ax":-4.50248, "ay":4.2237, "alpha":5.32203, "fx":[-93.51547,-95.07917,-50.99151,-66.75721], "fy":[55.29486,50.98694,95.31456,85.77901]}, - {"t":0.53275, "x":2.44751, "y":4.67825, "heading":0.92306, "vx":-2.76204, "vy":1.89292, "omega":-1.80458, "ax":-3.6959, "ay":3.94587, "alpha":12.00321, "fx":[-96.93369,-104.85756,0.99175,-50.66499], "fy":[48.55606,16.59681,107.34336,95.97614]}, - {"t":0.55697, "x":2.37954, "y":4.72525, "heading":0.87936, "vx":-2.85154, "vy":1.98847, "omega":-1.5139, "ax":-3.10245, "ay":3.79241, "alpha":14.8783, "fx":[-94.98715,-104.10939,27.73879,-39.7293], "fy":[51.46523,2.75604,103.13796,100.67202]}, - {"t":0.58119, "x":2.30958, "y":4.77451, "heading":0.8427, "vx":-2.92667, "vy":2.08031, "omega":-1.15361, "ax":-2.55577, "ay":4.23901, "alpha":13.96139, "fx":[-88.06742,-97.34294,39.96174,-28.44285], "fy":[61.36816,24.75565,98.38878,103.90455]}, - {"t":0.6054, "x":2.23796, "y":4.82613, "heading":0.81477, "vx":-2.98856, "vy":2.18296, "omega":-0.81552, "ax":-0.72216, "ay":5.15449, "alpha":10.85612, "fx":[-72.35098,-30.87829,61.02861,-6.93421], "fy":[77.41295,80.21664,86.31444,106.76142]}, - {"t":0.62962, "x":2.16537, "y":4.88051, "heading":0.79502, "vx":-3.00604, "vy":2.30779, "omega":-0.55263, "ax":1.9802, "ay":5.54963, "alpha":5.63734, "fx":[-4.80531,51.35441,62.72135,25.45982], "fy":[103.64924,87.28615,84.17369,102.48162]}, - {"t":0.65384, "x":2.09316, "y":4.93802, "heading":0.78163, "vx":-2.95809, "vy":2.44218, "omega":-0.41611, "ax":4.92382, "ay":3.66235, "alpha":2.03505, "fx":[77.75064,90.54149,88.90168,77.81727], "fy":[69.55454,52.16645,56.56361,70.89771]}, - {"t":0.67805, "x":2.02297, "y":4.99823, "heading":0.77156, "vx":-2.83886, "vy":2.53086, "omega":-0.36683, "ax":6.0527, "ay":0.28805, "alpha":5.50721, "fx":[104.70939,101.13859,107.6909,98.27996], "fy":[8.83663,-35.11592,3.13793,42.74008]}, - {"t":0.70227, "x":1.956, "y":5.05961, "heading":0.76267, "vx":-2.69228, "vy":2.53784, "omega":-0.23347, "ax":6.0301, "ay":-1.85772, "alpha":3.16684, "fx":[100.86798,95.88802,105.39485,108.13044], "fy":[-39.24527,-51.10159,-26.93801,-9.11245]}, - {"t":0.73647, "x":1.86745, "y":5.14531, "heading":0.75469, "vx":-2.48606, "vy":2.47431, "omega":-0.12516, "ax":5.53491, "ay":-3.17708, "alpha":1.8848, "fx":[90.64275,88.42937,97.35053,100.16599], "fy":[-60.32867,-63.79999,-49.20001,-42.83652]}, - {"t":0.77067, "x":1.78567, "y":5.22807, "heading":0.75041, "vx":-2.29677, "vy":2.36565, "omega":-0.0607, "ax":5.17799, "ay":-3.77937, "alpha":1.19873, "fx":[84.99928,84.00033,90.87655,92.42818], "fy":[-68.51186,-69.84777,-60.6527,-58.1318]}, - {"t":0.80487, "x":1.71015, "y":5.30677, "heading":0.74833, "vx":-2.11968, "vy":2.2364, "omega":-0.01971, "ax":4.93828, "ay":-4.10925, "alpha":0.79489, "fx":[81.63101,81.1585,86.20677,86.99859], "fy":[-72.73188,-73.31566,-67.31442,-66.22674]}, - {"t":0.83907, "x":1.64054, "y":5.38085, "heading":0.74766, "vx":-1.9508, "vy":2.09587, "omega":0.00748, "ax":4.77084, "ay":-4.31412, "alpha":0.53249, "fx":[79.42296,79.1993,82.79617,83.18406], "fy":[-75.28227,-75.54794,-71.59043,-71.10748]}, - {"t":0.87326, "x":1.57662, "y":5.45, "heading":0.74792, "vx":-1.78764, "vy":1.94833, "omega":0.02569, "ax":4.64849, "ay":-4.45274, "alpha":0.34915, "fx":[77.87187,77.77205,80.22891,80.40529], "fy":[-76.983,-77.10042,-74.54148,-74.3341]}, - {"t":0.90746, "x":1.5182, "y":5.51403, "heading":0.74879, "vx":-1.62866, "vy":1.79605, "omega":0.03763, "ax":4.5556, "ay":-4.55239, "alpha":0.21409, "fx":[76.72568,76.68754,78.23819,78.30669], "fy":[-78.19506,-78.24117,-76.6909,-76.61209]}, - {"t":0.94166, "x":1.46516, "y":5.57279, "heading":0.75008, "vx":-1.47287, "vy":1.64036, "omega":0.04495, "ax":4.48285, "ay":-4.62733, "alpha":0.11056, "fx":[75.84573,75.83593,76.65408,76.67229], "fy":[-79.10111,-79.11444,-78.32207,-78.30028]}, - {"t":0.97586, "x":1.41741, "y":5.62618, "heading":0.75162, "vx":-1.31956, "vy":1.48211, "omega":0.04873, "ax":4.4244, "ay":-4.68565, "alpha":0.02873, "fx":[75.14982,75.14946,75.36561,75.36655], "fy":[-79.80318,-79.80443,-79.60034,-79.59854]}, - {"t":1.01006, "x":1.37487, "y":5.67413, "heading":0.75328, "vx":-1.16824, "vy":1.32186, "omega":0.04971, "ax":4.37646, "ay":-4.7323, "alpha":-0.03755, "fx":[74.58623,74.58423,74.29806,74.30108], "fy":[-80.36266,-80.36345,-80.6281,-80.62638]}, - {"t":1.04426, "x":1.33748, "y":5.71657, "heading":0.75498, "vx":-1.01857, "vy":1.16002, "omega":0.04843, "ax":4.33645, "ay":-4.77044, "alpha":-0.09232, "fx":[74.12086,74.11062,73.39963,73.41613], "fy":[-80.81864,-80.82566,-81.47191,-81.4594]}, - {"t":1.07846, "x":1.30518, "y":5.75345, "heading":0.75664, "vx":-0.87027, "vy":0.99687, "omega":0.04527, "ax":4.30256, "ay":-4.8022, "alpha":-0.13832, "fx":[73.73031,73.70795,72.63337,72.66997], "fy":[-81.19722,-81.21426,-82.17679,-82.14765]}, - {"t":1.11266, "x":1.27793, "y":5.78474, "heading":0.75819, "vx":-0.72312, "vy":0.83264, "omega":0.04054, "ax":4.2735, "ay":-4.82903, "alpha":-0.17751, "fx":[73.39797,73.36136,71.97233,72.03265], "fy":[-81.51646,-81.54556,-82.77422,-82.72553]}, - {"t":1.14686, "x":1.2557, "y":5.81039, "heading":0.75958, "vx":-0.57697, "vy":0.66749, "omega":0.03447, "ax":4.24831, "ay":-4.85201, "alpha":-0.21128, "fx":[73.11177,73.05992,71.3964,71.48216], "fy":[-81.78928,-81.83134,-83.28687,-83.21745]}, - {"t":1.18106, "x":1.23846, "y":5.83038, "heading":0.76075, "vx":-0.43168, "vy":0.50156, "omega":0.02724, "ax":4.22627, "ay":-4.87189, "alpha":-0.24069, "fx":[72.8627,72.79541,70.89031,71.00192], "fy":[-82.02512,-82.08031,-83.73142,-83.64122]}, - {"t":1.21526, "x":1.22616, "y":5.84468, "heading":0.76169, "vx":-0.28715, "vy":0.33494, "omega":0.01901, "ax":4.20682, "ay":-4.88928, "alpha":-0.26653, "fx":[72.64389,72.56156,70.44224,70.57928], "fy":[-82.23111,-82.29906,-84.12044,-84.01008]}, - {"t":1.24946, "x":1.2188, "y":5.85328, "heading":0.76234, "vx":-0.14328, "vy":0.16773, "omega":0.0099, "ax":4.18953, "ay":-4.90459, "alpha":-0.28941, "fx":[72.45003,72.35348,70.04294,70.20435], "fy":[-82.41266,-82.49265,-84.46357,-84.33413]}, - {"t":1.28366, "x":1.21635, "y":5.85615, "heading":0.76267, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.82875, "ay":-4.1988, "alpha":2.70745, "fx":[72.75349,73.46399,89.5518,92.77341], "fy":[-82.1239,-81.53275,-63.44657,-58.57843]}, - {"t":1.31958, "x":1.21947, "y":5.85344, "heading":0.76267, "vx":0.17349, "vy":-0.15086, "omega":0.09728, "ax":4.82904, "ay":-4.19876, "alpha":2.68863, "fx":[72.83116,73.51974,89.51037,92.70107], "fy":[-82.04156,-81.47167,-63.49137,-58.6745]}, - {"t":1.35551, "x":1.22882, "y":5.84531, "heading":0.76617, "vx":0.34699, "vy":-0.30171, "omega":0.19387, "ax":4.82938, "ay":-4.19869, "alpha":2.66734, "fx":[72.88099,73.61596,89.49085,92.59736], "fy":[-81.98195,-81.37234,-63.5031,-58.81685]}, - {"t":1.39144, "x":1.2444, "y":5.83175, "heading":0.77314, "vx":0.52051, "vy":-0.45257, "omega":0.28971, "ax":4.82976, "ay":-4.19859, "alpha":2.64283, "fx":[72.90758,73.7537,89.49066,92.45968], "fy":[-81.94062,-81.23311,-63.48491,-59.00835]}, - {"t":1.42737, "x":1.26622, "y":5.81278, "heading":0.78354, "vx":0.69403, "vy":-0.60342, "omega":0.38466, "ax":4.83022, "ay":-4.19844, "alpha":2.61415, "fx":[72.91736,73.93462,89.50622,92.28422], "fy":[-81.91128,-81.05154,-63.4411,-59.25333]}, - {"t":1.4633, "x":1.29428, "y":5.78839, "heading":0.79736, "vx":0.86758, "vy":-0.75426, "omega":0.47859, "ax":4.83075, "ay":-4.19826, "alpha":2.57994, "fx":[72.91908,74.16105,89.53259,92.06565], "fy":[-81.8853,-80.82412,-63.37759,-59.55776]}, - {"t":1.49923, "x":1.32857, "y":5.75859, "heading":0.81456, "vx":1.04114, "vy":-0.9051, "omega":0.57128, "ax":4.83137, "ay":-4.19803, "alpha":2.5383, "fx":[72.92477,74.43638,89.56281,91.79661], "fy":[-81.85077,-80.54591,-63.30269,-59.92978]}, - {"t":1.53516, "x":1.36909, "y":5.72336, "heading":0.83509, "vx":1.21472, "vy":-1.05593, "omega":0.66248, "ax":4.8321, "ay":-4.19774, "alpha":2.4865, "fx":[72.9512,74.76544,89.58688,91.46682], "fy":[-81.79095,-80.2097,-63.2284,-60.38045]}, - {"t":1.57109, "x":1.41585, "y":5.68271, "heading":0.85889, "vx":1.38834, "vy":-1.20675, "omega":0.75181, "ax":4.83296, "ay":-4.19737, "alpha":2.42042, "fx":[73.0226,75.15552,89.58971,91.06149], "fy":[-81.68135,-79.80469,-63.17274,-60.92527]}, - {"t":1.60701, "x":1.46885, "y":5.63664, "heading":0.8859, "vx":1.56198, "vy":-1.35756, "omega":0.83878, "ax":4.83399, "ay":-4.19685, "alpha":2.33347, "fx":[73.17574,75.6182,89.54729,90.55825], "fy":[-81.48419,-79.31363,-63.16429,-61.58698]}, - {"t":1.64294, "x":1.52809, "y":5.58516, "heading":0.91604, "vx":1.73566, "vy":-1.50834, "omega":0.92262, "ax":4.83522, "ay":-4.19608, "alpha":2.21443, "fx":[73.4704,76.17346,89.41824,89.92073], "fy":[-81.13649,-78.70666,-63.25174,-62.40148]}, - {"t":1.67887, "x":1.59357, "y":5.52826, "heading":0.94918, "vx":1.90938, "vy":-1.6591, "omega":1.00218, "ax":4.83665, "ay":-4.19475, "alpha":2.04208, "fx":[74.01337,76.85971,89.12323,89.08356], "fy":[-80.52181,-77.9261,-63.52658,-63.43145]}, - {"t":1.7148, "x":1.6653, "y":5.46594, "heading":0.98519, "vx":2.08316, "vy":-1.80982, "omega":1.07555, "ax":4.83814, "ay":-4.19205, "alpha":1.77054, "fx":[75.02185,77.76245,88.48517,87.91194], "fy":[-79.39165,-76.84185,-64.18653,-64.80221]}, - {"t":1.75073, "x":1.74327, "y":5.39821, "heading":1.02383, "vx":2.25698, "vy":-1.96043, "omega":1.13916, "ax":4.83866, "ay":-4.18509, "alpha":1.27736, "fx":[77.02888,79.1196,87.00265,86.06557], "fy":[-77.08872,-75.08142,-65.76185,-66.8169]}, - {"t":1.78666, "x":1.82748, "y":5.32507, "heading":1.06476, "vx":2.43083, "vy":-2.1108, "omega":1.18505, "ax":4.82847, "ay":-4.15752, "alpha":0.08128, "fx":[81.80523,81.92647,82.45431,82.33778], "fy":[-71.08926,-70.96634,-70.34886,-70.46819]}, - {"t":1.82259, "x":1.91793, "y":5.24655, "heading":1.10734, "vx":2.60431, "vy":-2.26017, "omega":1.18797, "ax":4.35986, "ay":-3.53315, "alpha":-8.6212, "fx":[98.67691,97.69503,33.09915,67.16874], "fy":[-37.25267,-23.82837,-97.53123,-81.7789]}, - {"t":1.85852, "x":2.01432, "y":5.16307, "heading":1.15002, "vx":2.76096, "vy":-2.38711, "omega":0.87823, "ax":-4.3683, "ay":3.54187, "alpha":8.67554, "fx":[-99.46426,-97.61552,-31.96945,-68.16497], "fy":[35.88831,25.17527,98.56491,81.35641]}, - {"t":1.89444, "x":2.11069, "y":5.07959, "heading":1.18158, "vx":2.60401, "vy":-2.25986, "omega":1.18993, "ax":-4.82711, "ay":4.16134, "alpha":0.03306, "fx":[-82.24859,-82.17568,-81.96656,-82.04024], "fy":[70.6219,70.70014,70.94468,70.866]}, - {"t":1.93037, "x":2.20114, "y":5.00108, "heading":1.22433, "vx":2.43058, "vy":-2.11035, "omega":1.19111, "ax":-4.83805, "ay":4.18719, "alpha":-1.25176, "fx":[-76.54239,-80.1913,-87.4916,-84.95001], "fy":[77.60343,73.95346,65.10348,68.23103]}, - {"t":1.9663, "x":2.28534, "y":4.92796, "heading":1.26712, "vx":2.25675, "vy":-1.95991, "omega":1.14614, "ax":-4.83734, "ay":4.19289, "alpha":-1.77806, "fx":[-73.79937,-79.75049,-89.66857,-85.90831], "fy":[80.56116,74.79293,62.50511,67.42017]}, - {"t":2.00223, "x":2.3633, "y":4.86025, "heading":1.3083, "vx":2.08295, "vy":-1.80926, "omega":1.08226, "ax":-4.83578, "ay":4.19476, "alpha":-2.06177, "fx":[-72.18118,-79.75552,-90.89376,-86.19034], "fy":[82.20111,74.97524,60.9436,67.28683]}, - {"t":2.03816, "x":2.43502, "y":4.79795, "heading":1.34719, "vx":1.90921, "vy":-1.65855, "omega":1.00818, "ax":-4.83441, "ay":4.19554, "alpha":-2.23732, "fx":[-71.11775,-79.93431,-91.70716,-86.16851], "fy":[83.23978,74.89914,59.8593,67.46138]}, - {"t":2.07409, "x":2.5005, "y":4.74107, "heading":1.38341, "vx":1.73551, "vy":-1.50781, "omega":0.9278, "ax":-4.8333, "ay":4.19594, "alpha":-2.35568, "fx":[-70.37377,-80.18581,-92.29826,-85.9943], "fy":[83.94952,74.70708,59.04466,67.78543]}, - {"t":2.11002, "x":2.55973, "y":4.6896, "heading":1.41674, "vx":1.56186, "vy":-1.35705, "omega":0.84316, "ax":-4.83239, "ay":4.19619, "alpha":-2.44047, "fx":[-69.8326,-80.46338,-92.75142,-85.74295], "fy":[84.45806,74.4637,58.40398,68.17824]}, - {"t":2.14595, "x":2.61273, "y":4.64355, "heading":1.44704, "vx":1.38824, "vy":-1.20629, "omega":0.75548, "ax":-4.83163, "ay":4.19638, "alpha":-2.50412, "fx":[-69.42846,-80.74237,-93.11058,-85.45723], "fy":[84.83434,74.20312,57.88608,68.59362]}, - {"t":2.18187, "x":2.65949, "y":4.60292, "heading":1.47418, "vx":1.21464, "vy":-1.05552, "omega":0.66551, "ax":-4.83098, "ay":4.19655, "alpha":-2.55375, "fx":[-69.12059,-81.00851,-93.40132,-85.16394], "fy":[85.11956,73.94537,57.4604,69.00293]}, - {"t":2.2178, "x":2.70001, "y":4.56771, "heading":1.49809, "vx":1.04107, "vy":-0.90474, "omega":0.57375, "ax":-4.83041, "ay":4.19669, "alpha":-2.59366, "fx":[-68.88183,-81.25293,-93.63987,-84.88111], "fy":[85.34028,73.70314,57.10706,69.38742]}, - {"t":2.25373, "x":2.7343, "y":4.53791, "heading":1.51871, "vx":0.86752, "vy":-0.75396, "omega":0.48057, "ax":-4.82991, "ay":4.19681, "alpha":-2.62661, "fx":[-68.69311,-81.46988,-93.83723,-84.62144], "fy":[85.51466,73.48496,56.81227,69.73433]}, - {"t":2.28966, "x":2.76235, "y":4.51353, "heading":1.53597, "vx":0.69399, "vy":-0.60317, "omega":0.38619, "ax":-4.82947, "ay":4.19691, "alpha":-2.65439, "fx":[-68.54055,-81.65546,-94.0012,-84.39426], "fy":[85.65562,73.29684,56.56595,70.03472]}, - {"t":2.32559, "x":2.78416, "y":4.49457, "heading":1.54985, "vx":0.52047, "vy":-0.45238, "omega":0.29083, "ax":-4.82907, "ay":4.19699, "alpha":-2.67824, "fx":[-68.41373,-81.80694,-94.13753,-84.20653], "fy":[85.77264,73.14312,56.36058,70.28216]}, - {"t":2.36152, "x":2.79975, "y":4.48102, "heading":1.5603, "vx":0.34697, "vy":-0.30159, "omega":0.1946, "ax":-4.82873, "ay":4.19705, "alpha":-2.69899, "fx":[-68.30479,-81.92234,-94.25049,-84.06356], "fy":[85.87281,73.02707,56.19041,70.47195]}, - {"t":2.39745, "x":2.8091, "y":4.4729, "heading":1.56729, "vx":0.17348, "vy":-0.1508, "omega":0.09763, "ax":-4.82843, "ay":4.19708, "alpha":-2.71728, "fx":[-68.20778,-82.00016,-94.34328,-83.9694], "fy":[85.96141,72.95116,56.05111,70.60054]}, - {"t":2.43338, "x":2.81221, "y":4.47019, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":3.19328, "y":4.19424, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.29244, "ay":3.68917, "alpha":-0.00642, "fx":[-90.00419,-90.01958,-90.04156,-90.02618], "fy":[62.77854,62.75655,62.72496,62.74695]}, + {"t":0.03695, "x":3.18967, "y":4.19676, "heading":1.5708, "vx":-0.19553, "vy":0.1363, "omega":-0.00024, "ax":-5.29042, "ay":3.68776, "alpha":-0.00765, "fx":[-89.9663,-89.98464,-90.0108,-89.99248], "fy":[62.75973,62.73355,62.69592,62.72209]}, + {"t":0.07389, "x":3.17883, "y":4.20431, "heading":1.57079, "vx":-0.39099, "vy":0.27254, "omega":-0.00052, "ax":-5.28638, "ay":3.68495, "alpha":-0.01011, "fx":[-89.89049,-89.91475,-89.94927,-89.92504], "fy":[62.72209,62.68755,62.63783,62.67237]}, + {"t":0.11084, "x":3.16078, "y":4.2169, "heading":1.57077, "vx":-0.58629, "vy":0.40868, "omega":-0.00089, "ax":-5.27427, "ay":3.67651, "alpha":-0.01751, "fx":[-89.66306,-89.70517,-89.76465,-89.72262], "fy":[62.6091,62.54958,62.46361,62.52313]}, + {"t":0.14778, "x":3.13552, "y":4.23451, "heading":1.57074, "vx":-0.78115, "vy":0.54451, "omega":-0.00154, "ax":-1.05522, "ay":0.73555, "alpha":-2.9612, "fx":[-12.46081,-23.03856,-23.53808,-12.7582], "fy":[18.28038,17.72011,6.90636,7.13933]}, + {"t":0.18473, "x":3.10594, "y":4.25513, "heading":1.57068, "vx":-0.82014, "vy":0.57169, "omega":-0.11094, "ax":-0.00001, "ay":0.00001, "alpha":-2.70066, "fx":[4.93808,-4.93731,-4.93848,4.93692], "fy":[4.93726,4.93842,-4.93698,-4.93814]}, + {"t":0.22167, "x":3.07564, "y":4.27625, "heading":1.56658, "vx":-0.82014, "vy":0.57169, "omega":-0.21072, "ax":0.0, "ay":0.0, "alpha":-2.27414, "fx":[4.17538,-4.14032,-4.17538,4.14032], "fy":[4.14032,4.17538,-4.14032,-4.17538]}, + {"t":0.25862, "x":3.04534, "y":4.29737, "heading":1.55879, "vx":-0.82014, "vy":0.57169, "omega":-0.29474, "ax":0.0, "ay":0.0, "alpha":-1.9136, "fx":[3.54042,-3.45644,-3.54042,3.45644], "fy":[3.45644,3.54042,-3.45644,-3.54042]}, + {"t":0.29556, "x":3.01504, "y":4.31849, "heading":1.54791, "vx":-0.82014, "vy":0.57169, "omega":-0.36544, "ax":0.0, "ay":0.0, "alpha":-1.60909, "fx":[3.00852,-2.87384,-3.00852,2.87384], "fy":[2.87384,3.00852,-2.87384,-3.00852]}, + {"t":0.33251, "x":2.98474, "y":4.33961, "heading":1.5344, "vx":-0.82014, "vy":0.57169, "omega":-0.42488, "ax":0.0, "ay":0.0, "alpha":-1.35206, "fx":[2.56032,-2.38044,-2.56032,2.38044], "fy":[2.38044,2.56032,-2.38044,-2.56032]}, + {"t":0.36945, "x":2.95444, "y":4.36073, "heading":1.51871, "vx":-0.82014, "vy":0.57169, "omega":-0.47484, "ax":0.0, "ay":0.0, "alpha":-1.13516, "fx":[2.18069,-1.96457,-2.18069,1.96457], "fy":[1.96457,2.18069,-1.96457,-2.18069]}, + {"t":0.4064, "x":2.92414, "y":4.38185, "heading":1.50116, "vx":-0.82014, "vy":0.57169, "omega":-0.51678, "ax":0.0, "ay":0.0, "alpha":-0.9521, "fx":[1.85764,-1.61541,-1.85764,1.61541], "fy":[1.61541,1.85764,-1.61541,-1.85764]}, + {"t":0.44334, "x":2.89384, "y":4.40297, "heading":1.48207, "vx":-0.82014, "vy":0.57169, "omega":-0.55195, "ax":0.0, "ay":0.0, "alpha":-0.79752, "fx":[1.58159,-1.32318,-1.58159,1.32318], "fy":[1.32318,1.58159,-1.32318,-1.58159]}, + {"t":0.48029, "x":2.86354, "y":4.4241, "heading":1.46168, "vx":-0.82014, "vy":0.57169, "omega":-0.58142, "ax":0.0, "ay":0.0, "alpha":-0.66686, "fx":[1.34477,-1.07922,-1.34477,1.07922], "fy":[1.07922,1.34477,-1.07922,-1.34477]}, + {"t":0.51723, "x":2.83324, "y":4.44522, "heading":1.4402, "vx":-0.82014, "vy":0.57169, "omega":-0.60605, "ax":0.0, "ay":0.0, "alpha":-0.55626, "fx":[1.14082,-0.87593,-1.14082,0.87593], "fy":[0.87593,1.14082,-0.87593,-1.14082]}, + {"t":0.55418, "x":2.80294, "y":4.46634, "heading":1.41781, "vx":-0.82014, "vy":0.57169, "omega":-0.6266, "ax":0.0, "ay":0.0, "alpha":-0.46242, "fx":[0.96443,-0.70674,-0.96443,0.70674], "fy":[0.70674,0.96443,-0.70674,-0.96443]}, + {"t":0.59112, "x":2.77264, "y":4.48746, "heading":1.39466, "vx":-0.82014, "vy":0.57169, "omega":-0.64369, "ax":0.0, "ay":0.0, "alpha":-0.38253, "fx":[0.81112,-0.56601,-0.81112,0.56601], "fy":[0.56601,0.81112,-0.56601,-0.81112]}, + {"t":0.62807, "x":2.74234, "y":4.50858, "heading":1.37088, "vx":-0.82014, "vy":0.57169, "omega":-0.65782, "ax":0.0, "ay":0.0, "alpha":-0.31419, "fx":[0.67708,-0.44892,-0.67708,0.44892], "fy":[0.44892,0.67708,-0.44892,-0.67708]}, + {"t":0.66501, "x":2.71204, "y":4.5297, "heading":1.34657, "vx":-0.82014, "vy":0.57169, "omega":-0.66943, "ax":0.0, "ay":0.0, "alpha":-0.25535, "fx":[0.55898,-0.35137,-0.55898,0.35137], "fy":[0.35137,0.55898,-0.35137,-0.55898]}, + {"t":0.70196, "x":2.68173, "y":4.55082, "heading":1.32184, "vx":-0.82014, "vy":0.57169, "omega":-0.67886, "ax":0.0, "ay":0.0, "alpha":-0.20423, "fx":[0.45389,-0.26988,-0.45389,0.26988], "fy":[0.26988,0.45389,-0.26988,-0.45389]}, + {"t":0.73891, "x":2.65143, "y":4.57194, "heading":1.29676, "vx":-0.82014, "vy":0.57169, "omega":-0.68641, "ax":0.0, "ay":0.0, "alpha":-0.15929, "fx":[0.35918,-0.20156,-0.35918,0.20156], "fy":[0.20156,0.35918,-0.20156,-0.35918]}, + {"t":0.77585, "x":2.62113, "y":4.59306, "heading":1.2714, "vx":-0.82014, "vy":0.57169, "omega":-0.69229, "ax":0.0, "ay":0.0, "alpha":-0.11918, "fx":[0.27247,-0.14394,-0.27247,0.14394], "fy":[0.14394,0.27247,-0.14394,-0.27247]}, + {"t":0.8128, "x":2.59083, "y":4.61419, "heading":1.24582, "vx":-0.82014, "vy":0.57169, "omega":-0.6967, "ax":0.0, "ay":0.0, "alpha":-0.08267, "fx":[0.1915,-0.09498,-0.1915,0.09498], "fy":[0.09498,0.1915,-0.09498,-0.1915]}, + {"t":0.84974, "x":2.56053, "y":4.63531, "heading":1.22008, "vx":-0.82014, "vy":0.57169, "omega":-0.69975, "ax":0.0, "ay":0.0, "alpha":-0.04867, "fx":[0.11415,-0.053,-0.11415,0.053], "fy":[0.053,0.11415,-0.053,-0.11415]}, + {"t":0.88669, "x":2.53023, "y":4.65643, "heading":1.19423, "vx":-0.82014, "vy":0.57169, "omega":-0.70155, "ax":0.0, "ay":0.0, "alpha":-0.01615, "fx":[0.03831,-0.0166,-0.03831,0.0166], "fy":[0.0166,0.03831,-0.0166,-0.03831]}, + {"t":0.92363, "x":2.49993, "y":4.67755, "heading":1.16831, "vx":-0.82014, "vy":0.57169, "omega":-0.70215, "ax":0.0, "ay":0.0, "alpha":0.01589, "fx":[-0.03811,0.01535,0.03811,-0.01535], "fy":[-0.01535,-0.03811,0.01535,0.03811]}, + {"t":0.96058, "x":2.46963, "y":4.69867, "heading":1.14237, "vx":-0.82014, "vy":0.57169, "omega":-0.70156, "ax":0.0, "ay":0.0, "alpha":0.04841, "fx":[-0.11727,0.04374,0.11727,-0.04374], "fy":[-0.04374,-0.11727,0.04374,0.11727]}, + {"t":0.99752, "x":2.43933, "y":4.71979, "heading":1.11645, "vx":-0.82014, "vy":0.57169, "omega":-0.69977, "ax":0.0, "ay":0.0, "alpha":0.08239, "fx":[-0.20147,0.06925,0.20147,-0.06925], "fy":[-0.06925,-0.20147,0.06925,0.20147]}, + {"t":1.03447, "x":2.40903, "y":4.74091, "heading":1.0906, "vx":-0.82014, "vy":0.57169, "omega":-0.69673, "ax":0.0, "ay":0.0, "alpha":0.11888, "fx":[-0.29317,0.09236,0.29317,-0.09236], "fy":[-0.09236,-0.29317,0.09236,0.29317]}, + {"t":1.07141, "x":2.37873, "y":4.76203, "heading":1.06486, "vx":-0.82014, "vy":0.57169, "omega":-0.69233, "ax":0.0, "ay":0.0, "alpha":0.15896, "fx":[-0.39508,0.11338,0.39508,-0.11338], "fy":[-0.11338,-0.39508,0.11338,0.39508]}, + {"t":1.10836, "x":2.34843, "y":4.78316, "heading":1.03928, "vx":-0.82014, "vy":0.57169, "omega":-0.68646, "ax":0.0, "ay":0.0, "alpha":0.20386, "fx":[-0.51022,0.13239,0.51022,-0.13239], "fy":[-0.13239,-0.51022,0.13239,0.51022]}, + {"t":1.1453, "x":2.31813, "y":4.80428, "heading":1.01392, "vx":-0.82014, "vy":0.57169, "omega":-0.67893, "ax":0.0, "ay":0.0, "alpha":0.25494, "fx":[-0.64204,0.14933,0.64204,-0.14933], "fy":[-0.14933,-0.64204,0.14933,0.64204]}, + {"t":1.18225, "x":2.28783, "y":4.8254, "heading":0.98884, "vx":-0.82014, "vy":0.57169, "omega":-0.66951, "ax":0.0, "ay":0.0, "alpha":0.31372, "fx":[-0.79444,0.16389,0.79444,-0.16389], "fy":[-0.16389,-0.79444,0.16389,0.79444]}, + {"t":1.21919, "x":2.25753, "y":4.84652, "heading":0.9641, "vx":-0.82014, "vy":0.57169, "omega":-0.65792, "ax":0.0, "ay":0.0, "alpha":0.38199, "fx":[-0.97196,0.17556,0.97196,-0.17556], "fy":[-0.17556,-0.97196,0.17556,0.97196]}, + {"t":1.25614, "x":2.22723, "y":4.86764, "heading":0.93979, "vx":-0.82014, "vy":0.57169, "omega":-0.64381, "ax":0.0, "ay":0.0, "alpha":0.46179, "fx":[-1.17983,0.18362,1.17983,-0.18362], "fy":[-0.18362,-1.17983,0.18362,1.17983]}, + {"t":1.29308, "x":2.19693, "y":4.88876, "heading":0.91601, "vx":-0.82014, "vy":0.57169, "omega":-0.62675, "ax":0.0, "ay":0.0, "alpha":0.55553, "fx":[-1.42416,0.18707,1.42416,-0.18707], "fy":[-0.18707,-1.42416,0.18707,1.42416]}, + {"t":1.33003, "x":2.16663, "y":4.90988, "heading":0.89285, "vx":-0.82014, "vy":0.57169, "omega":-0.60622, "ax":0.0, "ay":0.0, "alpha":0.666, "fx":[-1.7121,0.18468,1.7121,-0.18468], "fy":[-0.18468,-1.7121,0.18468,1.7121]}, + {"t":1.36697, "x":2.13633, "y":4.931, "heading":0.87046, "vx":-0.82014, "vy":0.57169, "omega":-0.58162, "ax":0.0, "ay":0.0, "alpha":0.79649, "fx":[-2.052,0.17496,2.052,-0.17496], "fy":[-0.17496,-2.052,0.17496,2.052]}, + {"t":1.40392, "x":2.10603, "y":4.95213, "heading":0.84897, "vx":-0.82014, "vy":0.57169, "omega":-0.55219, "ax":0.0, "ay":0.00001, "alpha":0.95088, "fx":[-2.45362,0.15625,2.45374,-0.15613], "fy":[-0.1561,-2.45359,0.15628,2.45377]}, + {"t":1.44087, "x":2.07573, "y":4.97325, "heading":0.82857, "vx":-0.82014, "vy":0.57169, "omega":-0.51706, "ax":0.0001, "ay":0.00015, "alpha":1.13372, "fx":[-2.92695,0.12823,2.93039,-0.12478], "fy":[-0.12403,-2.9262,0.12898,2.93114]}, + {"t":1.47781, "x":2.04543, "y":4.99437, "heading":0.80946, "vx":-0.82013, "vy":0.57169, "omega":-0.47517, "ax":0.00284, "ay":0.00408, "alpha":1.35035, "fx":[-3.44223,0.13242,3.53882,-0.03562], "fy":[-0.0146,-3.42124,0.15343,3.5598]}, + {"t":1.51476, "x":2.01513, "y":5.01549, "heading":0.79191, "vx":-0.82003, "vy":0.57185, "omega":-0.42529, "ax":0.07997, "ay":0.11405, "alpha":1.60557, "fx":[-2.79363,1.39117,5.51035,1.33347], "fy":[1.91754,-2.21345,1.96794,6.08795]}, + {"t":1.5517, "x":1.98489, "y":5.0367, "heading":0.7762, "vx":-0.81707, "vy":0.57606, "omega":-0.36597, "ax":1.89652, "ay":2.38269, "alpha":1.21694, "fx":[28.91325,32.9479,35.53191,31.64428], "fy":[41.27276,37.51055,39.85426,43.47765]}, + {"t":1.58865, "x":1.956, "y":5.05961, "heading":0.76267, "vx":-0.74701, "vy":0.66409, "omega":-0.32101, "ax":1.43275, "ay":1.47208, "alpha":1.59531, "fx":[20.1892,24.73117,28.4782,24.08413], "fy":[25.59005,20.89687,24.56827,29.10325]}, + {"t":1.6353, "x":1.92271, "y":5.09219, "heading":0.7477, "vx":-0.68016, "vy":0.73277, "omega":-0.24658, "ax":0.03069, "ay":0.02843, "alpha":1.57059, "fx":[-3.53679,0.36974,4.57941,0.67553], "fy":[0.63751,-3.57526,0.33104,4.54096]}, + {"t":1.68196, "x":1.89101, "y":5.12641, "heading":0.73619, "vx":-0.67873, "vy":0.73409, "omega":-0.1733, "ax":0.00056, "ay":0.00052, "alpha":1.26149, "fx":[-3.24825,-0.15085,3.26738,0.17001], "fy":[0.16929,-3.24897,-0.15157,3.26666]}, + {"t":1.72861, "x":1.85934, "y":5.16066, "heading":0.72811, "vx":-0.6787, "vy":0.73412, "omega":-0.11445, "ax":0.00001, "ay":0.00001, "alpha":1.01158, "fx":[-2.61112,-0.14959,2.61147,0.14994], "fy":[0.14993,-2.61113,-0.1496,2.61146]}, + {"t":1.77527, "x":1.82767, "y":5.19491, "heading":0.72277, "vx":-0.6787, "vy":0.73412, "omega":-0.06725, "ax":0.0, "ay":0.0, "alpha":0.80936, "fx":[-2.08861,-0.13098,2.08862,0.13098], "fy":[0.13098,-2.08861,-0.13098,2.08862]}, + {"t":1.82192, "x":1.79601, "y":5.22916, "heading":0.71963, "vx":-0.6787, "vy":0.73412, "omega":-0.02949, "ax":0.0, "ay":0.0, "alpha":0.64535, "fx":[-1.66505,-0.10966,1.66505,0.10966], "fy":[0.10966,-1.66505,-0.10966,1.66505]}, + {"t":1.86858, "x":1.76434, "y":5.26341, "heading":0.71826, "vx":-0.6787, "vy":0.73412, "omega":0.00062, "ax":0.0, "ay":0.0, "alpha":0.51186, "fx":[-1.32051,-0.0888,1.32051,0.0888], "fy":[0.0888,-1.32051,-0.0888,1.32051]}, + {"t":1.91523, "x":1.73268, "y":5.29766, "heading":0.71828, "vx":-0.6787, "vy":0.73412, "omega":0.0245, "ax":0.0, "ay":0.0, "alpha":0.40258, "fx":[-1.03859,-0.06981,1.03859,0.06981], "fy":[0.06981,-1.03859,-0.06981,1.03859]}, + {"t":1.96189, "x":1.70101, "y":5.33191, "heading":0.71943, "vx":-0.6787, "vy":0.73412, "omega":0.04328, "ax":0.0, "ay":0.0, "alpha":0.31236, "fx":[-0.80589,-0.05324,0.80589,0.05324], "fy":[0.05324,-0.80589,-0.05324,0.80589]}, + {"t":2.00854, "x":1.66935, "y":5.36616, "heading":0.72145, "vx":-0.6787, "vy":0.73412, "omega":0.05786, "ax":0.0, "ay":0.0, "alpha":0.23693, "fx":[-0.61136,-0.03915,0.61136,0.03915], "fy":[0.03915,-0.61136,-0.03915,0.61136]}, + {"t":2.0552, "x":1.63768, "y":5.40041, "heading":0.72415, "vx":-0.6787, "vy":0.73412, "omega":0.06891, "ax":0.0, "ay":0.0, "alpha":0.17272, "fx":[-0.44576,-0.02734,0.44576,0.02734], "fy":[0.02734,-0.44576,-0.02734,0.44576]}, + {"t":2.10185, "x":1.60602, "y":5.43466, "heading":0.72736, "vx":-0.6787, "vy":0.73412, "omega":0.07697, "ax":0.0, "ay":0.0, "alpha":0.1167, "fx":[-0.30123,-0.0175,0.30123,0.0175], "fy":[0.0175,-0.30123,-0.0175,0.30123]}, + {"t":2.14851, "x":1.57435, "y":5.46891, "heading":0.73095, "vx":-0.6787, "vy":0.73412, "omega":0.08241, "ax":0.0, "ay":0.0, "alpha":0.0662, "fx":[-0.17092,-0.00932,0.17092,0.00932], "fy":[0.00932,-0.17092,-0.00932,0.17092]}, + {"t":2.19517, "x":1.54269, "y":5.50317, "heading":0.7348, "vx":-0.6787, "vy":0.73412, "omega":0.0855, "ax":0.0, "ay":0.0, "alpha":0.01884, "fx":[-0.04866,-0.00246,0.04866,0.00246], "fy":[0.00246,-0.04866,-0.00246,0.04866]}, + {"t":2.24182, "x":1.51102, "y":5.53742, "heading":0.73879, "vx":-0.6787, "vy":0.73412, "omega":0.08638, "ax":0.0, "ay":0.0, "alpha":-0.02762, "fx":[0.07134,0.00333,-0.07134,-0.00333], "fy":[-0.00333,0.07134,0.00333,-0.07134]}, + {"t":2.28848, "x":1.47936, "y":5.57167, "heading":0.74282, "vx":-0.6787, "vy":0.73412, "omega":0.08509, "ax":0.0, "ay":0.0, "alpha":-0.0754, "fx":[0.19477,0.0083,-0.19477,-0.0083], "fy":[-0.0083,0.19477,0.0083,-0.19477]}, + {"t":2.33513, "x":1.44769, "y":5.60592, "heading":0.74679, "vx":-0.6787, "vy":0.73412, "omega":0.08157, "ax":0.0, "ay":0.0, "alpha":-0.12674, "fx":[0.32747,0.01265,-0.32747,-0.01265], "fy":[-0.01265,0.32747,0.01265,-0.32747]}, + {"t":2.38179, "x":1.41603, "y":5.64017, "heading":0.75059, "vx":-0.6787, "vy":0.73412, "omega":0.07566, "ax":0.0, "ay":0.0, "alpha":-0.1841, "fx":[0.47572,0.01656,-0.47572,-0.01656], "fy":[-0.01656,0.47572,0.01656,-0.47572]}, + {"t":2.42844, "x":1.38436, "y":5.67442, "heading":0.75412, "vx":-0.6787, "vy":0.73412, "omega":0.06707, "ax":0.0, "ay":0.0, "alpha":-0.25017, "fx":[0.64653,0.02023,-0.64653,-0.02023], "fy":[-0.02023,0.64653,0.02023,-0.64653]}, + {"t":2.4751, "x":1.3527, "y":5.70867, "heading":0.75725, "vx":-0.6787, "vy":0.73412, "omega":0.0554, "ax":0.0, "ay":0.0, "alpha":-0.32809, "fx":[0.84799,0.02387,-0.84799,-0.02387], "fy":[-0.02387,0.84799,0.02387,-0.84799]}, + {"t":2.52175, "x":1.32103, "y":5.74292, "heading":0.75984, "vx":-0.6787, "vy":0.73412, "omega":0.04009, "ax":0.00001, "ay":-0.00001, "alpha":-0.42155, "fx":[1.08974,0.02797,-1.08952,-0.02775], "fy":[-0.02798,1.08951,0.02774,-1.08975]}, + {"t":2.56841, "x":1.28937, "y":5.77717, "heading":0.76171, "vx":-0.6787, "vy":0.73412, "omega":0.02043, "ax":1.41661, "ay":-1.53228, "alpha":-0.43384, "fx":[25.22113,24.24267,22.96541,23.95565], "fy":[-25.97614,-24.94579,-26.15687,-27.17589]}, + {"t":2.61506, "x":1.25924, "y":5.80975, "heading":0.76266, "vx":-0.61261, "vy":0.66263, "omega":0.00018, "ax":4.37199, "ay":-4.72896, "alpha":-0.00191, "fx":[74.37151,74.37132,74.36108,74.36128], "fy":[-80.43351,-80.43364,-80.4431,-80.44297]}, + {"t":2.66172, "x":1.23542, "y":5.83552, "heading":0.76267, "vx":-0.40863, "vy":0.442, "omega":0.0001, "ax":4.37824, "ay":-4.73572, "alpha":-0.00115, "fx":[74.47573,74.47562,74.46947,74.46958], "fy":[-80.5504,-80.55049,-80.55618,-80.55609]}, + {"t":2.70837, "x":1.22112, "y":5.85099, "heading":0.76267, "vx":-0.20437, "vy":0.22105, "omega":0.00004, "ax":4.38033, "ay":-4.73798, "alpha":-0.00089, "fx":[74.51052,74.51044,74.50565,74.50573], "fy":[-80.58942,-80.58949,-80.59392,-80.59385]}, + {"t":2.75503, "x":1.21635, "y":5.85615, "heading":0.76267, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.84902, "ay":-4.21373, "alpha":2.76554, "fx":[75.9427,75.93531,87.97747,90.06626], "fy":[-79.19187,-79.23148,-65.60581,-62.66841]}, + {"t":2.79089, "x":1.21947, "y":5.85344, "heading":0.76267, "vx":0.1739, "vy":-0.15111, "omega":0.09918, "ax":4.84906, "ay":-4.21361, "alpha":2.74115, "fx":[76.006,75.98818,87.93369,89.99689], "fy":[-79.11776,-79.16937,-65.6509,-62.75143]}, + {"t":2.82675, "x":1.22883, "y":5.84531, "heading":0.76623, "vx":0.3478, "vy":-0.30223, "omega":0.19748, "ax":4.84911, "ay":-4.21347, "alpha":2.71337, "fx":[76.05056,76.07191,87.90519,89.90038], "fy":[-79.05965,-79.07584,-65.67337,-62.87052]}, + {"t":2.86262, "x":1.24442, "y":5.83176, "heading":0.77331, "vx":0.5217, "vy":-0.45333, "omega":0.29479, "ax":4.84916, "ay":-4.21328, "alpha":2.6813, "fx":[76.08015,76.18748,87.88934,89.77455], "fy":[-79.01355,-78.9493,-65.67627,-63.02786]}, + {"t":2.89848, "x":1.26625, "y":5.81279, "heading":0.78389, "vx":0.6956, "vy":-0.60443, "omega":0.39095, "ax":4.84922, "ay":-4.21306, "alpha":2.64376, "fx":[76.09991,76.33639,87.88253,89.61627], "fy":[-78.97392,-78.78745,-65.66376,-63.22662]}, + {"t":2.93434, "x":1.29431, "y":5.78841, "heading":0.79791, "vx":0.86951, "vy":-0.75552, "omega":0.48576, "ax":4.84927, "ay":-4.21278, "alpha":2.59911, "fx":[76.11681,76.52076,87.87977,89.42119], "fy":[-78.93319,-78.58701,-65.64149,-63.47121]}, + {"t":2.9702, "x":1.32861, "y":5.7586, "heading":0.81533, "vx":1.04341, "vy":-0.9066, "omega":0.57897, "ax":4.84931, "ay":-4.21244, "alpha":2.54504, "fx":[76.14041,76.74363,87.87414,89.18328], "fy":[-78.88097,-78.34334,-65.61738,-63.7676]}, + {"t":3.00607, "x":1.36915, "y":5.72338, "heading":0.83609, "vx":1.21732, "vy":-1.05767, "omega":0.67024, "ax":4.84933, "ay":-4.21199, "alpha":2.4782, "fx":[76.18402,77.00936,87.85561,88.89414], "fy":[-78.80255,-78.04971,-65.60273,-64.12399]}, + {"t":3.04193, "x":1.41592, "y":5.68274, "heading":0.86013, "vx":1.39123, "vy":-1.20872, "omega":0.75912, "ax":4.84932, "ay":-4.2114, "alpha":2.39352, "fx":[76.26687,77.32444,87.80918,88.54163], "fy":[-78.67647,-77.69599,-65.61441,-64.55193]}, + {"t":3.07779, "x":1.46893, "y":5.63669, "heading":0.88735, "vx":1.56514, "vy":-1.35975, "omega":0.84496, "ax":4.84922, "ay":-4.21058, "alpha":2.28288, "fx":[76.41819,77.69913,87.71103,88.10726], "fy":[-78.4695,-77.26606,-65.67891,-65.06853]}, + {"t":3.11365, "x":1.52818, "y":5.58521, "heading":0.91765, "vx":1.73904, "vy":-1.51075, "omega":0.92683, "ax":4.84896, "ay":-4.20937, "alpha":2.13238, "fx":[76.68532,78.15099,87.52038,87.56086], "fy":[-78.12648,-76.73208,-65.84081,-65.70106]}, + {"t":3.14952, "x":1.59367, "y":5.52833, "heading":0.95089, "vx":1.91294, "vy":-1.66171, "omega":1.0033, "ax":4.84831, "ay":-4.2074, "alpha":1.91593, "fx":[77.15239,78.7133,87.15998,86.84808], "fy":[-77.54622,-76.04072,-66.18264,-66.49741]}, + {"t":3.18538, "x":1.66539, "y":5.46603, "heading":0.98687, "vx":2.08681, "vy":-1.8126, "omega":1.07201, "ax":4.84671, "ay":-4.20381, "alpha":1.57766, "fx":[77.98836,79.45867,86.46061,85.8572], "fy":[-76.51622,-75.07359,-66.8791,-67.55332]}, + {"t":3.22124, "x":1.74334, "y":5.39832, "heading":1.02532, "vx":2.26063, "vy":-1.96336, "omega":1.12859, "ax":4.84209, "ay":-4.19574, "alpha":0.97154, "fx":[79.59931,80.58275,84.95874,84.3097], "fy":[-74.49017,-73.50127,-68.38327,-69.09836]}, + {"t":3.2571, "x":1.82753, "y":5.32521, "heading":1.06579, "vx":2.43428, "vy":-2.11383, "omega":1.16343, "ax":4.82263, "ay":-4.16901, "alpha":-0.45123, "fx":[83.288,82.85306,80.73917,81.24623], "fy":[-69.47852,-69.93201,-72.37592,-71.86803]}, + {"t":3.29297, "x":1.91793, "y":5.24672, "heading":1.10751, "vx":2.60723, "vy":-2.26334, "omega":1.14725, "ax":4.51007, "ay":-3.80741, "alpha":-8.75857, "fx":[95.96788,94.12463,47.1588,69.6089], "fy":[-44.68141,-41.35847,-92.86252,-80.14937]}, + {"t":3.32883, "x":2.01433, "y":5.16311, "heading":1.14866, "vx":2.76897, "vy":-2.39988, "omega":0.83314, "ax":-4.51628, "ay":3.8128, "alpha":8.95423, "fx":[-96.8748,-94.16898,-45.8514,-70.38728], "fy":[43.38282,42.06747,94.0808,79.88766]}, + {"t":3.36469, "x":2.11073, "y":5.07949, "heading":1.17854, "vx":2.60701, "vy":-2.26315, "omega":1.15426, "ax":-4.82259, "ay":4.17052, "alpha":0.65468, "fx":[-83.96236,-83.01994,-80.02382,-81.11759], "fy":[68.71408,69.75957,73.20694,72.077]}, + {"t":3.40055, "x":2.20112, "y":5.00101, "heading":1.21993, "vx":2.43406, "vy":-2.11358, "omega":1.17774, "ax":-4.84258, "ay":4.19691, "alpha":-0.89096, "fx":[-79.55805,-81.23673,-85.04356,-83.64505], "fy":[74.56095,72.79341,68.28219,69.9163]}, + {"t":3.43642, "x":2.2853, "y":4.92791, "heading":1.26217, "vx":2.26039, "vy":-1.96307, "omega":1.14579, "ax":-4.8469, "ay":4.20443, "alpha":-1.55404, "fx":[-77.35734,-80.73954,-87.11283,-84.56796], "fy":[77.1777,73.70783,66.02003,69.15875]}, + {"t":3.47228, "x":2.36324, "y":4.86022, "heading":1.30326, "vx":2.08657, "vy":-1.81229, "omega":1.09006, "ax":-4.84823, "ay":4.20759, "alpha":-1.92202, "fx":[-76.02232,-80.64695,-88.28751,-84.9113], "fy":[78.67777,73.99946,64.65799,68.94411]}, + {"t":3.50814, "x":2.43496, "y":4.79793, "heading":1.34235, "vx":1.9127, "vy":-1.66139, "omega":1.02113, "ax":-4.84869, "ay":4.20922, "alpha":-2.15512, "fx":[-75.12345,-80.72308,-89.06572,-84.9869], "fy":[79.65301,74.03356,63.71888,68.98515]}, + {"t":3.544, "x":2.50043, "y":4.74105, "heading":1.37897, "vx":1.73881, "vy":-1.51044, "omega":0.94384, "ax":-4.84883, "ay":4.21019, "alpha":-2.31547, "fx":[-74.4798,-80.87662,-89.62815,-84.92416], "fy":[80.33523,73.94522,63.01988,69.15628]}, + {"t":3.57987, "x":2.55967, "y":4.68959, "heading":1.41282, "vx":1.56492, "vy":-1.35945, "omega":0.8608, "ax":-4.84884, "ay":4.21083, "alpha":-2.43227, "fx":[-74.00062,-81.06417,-90.05675,-84.78785], "fy":[80.83515,73.79697,62.47514,69.39267]}, + {"t":3.61573, "x":2.61268, "y":4.64355, "heading":1.44369, "vx":1.39103, "vy":-1.20844, "omega":0.77358, "ax":-4.84879, "ay":4.21128, "alpha":-2.52108, "fx":[-73.63433,-81.26224,-90.39465,-84.61482], "fy":[81.21323,73.62226,62.03824,69.65682]}, + {"t":3.65159, "x":2.65944, "y":4.60292, "heading":1.47143, "vx":1.21714, "vy":-1.05742, "omega":0.68316, "ax":-4.84871, "ay":4.21161, "alpha":-2.59091, "fx":[-73.34881,-81.4569,-90.6671,-84.42801], "fy":[81.50593,73.44087,61.68131,69.92532]}, + {"t":3.68745, "x":2.69997, "y":4.56771, "heading":1.49593, "vx":1.04325, "vy":-0.90638, "omega":0.59025, "ax":-4.84862, "ay":4.21188, "alpha":-2.64734, "fx":[-73.12252,-81.63931,-90.89015,-84.24274], "fy":[81.73693,73.26543,61.3862,70.18265]}, + {"t":3.72332, "x":2.73427, "y":4.53791, "heading":1.5171, "vx":0.86937, "vy":-0.75533, "omega":0.49531, "ax":-4.84853, "ay":4.21208, "alpha":-2.69398, "fx":[-72.94029,-81.80361,-91.0747,-84.06973], "fy":[81.92249,73.10446,61.14029,70.41814]}, + {"t":3.75918, "x":2.76233, "y":4.51353, "heading":1.53486, "vx":0.69549, "vy":-0.60427, "omega":0.39869, "ax":-4.84843, "ay":4.21225, "alpha":-2.73324, "fx":[-72.79098,-81.94575,-91.22848,-83.91676], "fy":[82.07429,72.96393,60.93442,70.62422]}, + {"t":3.79504, "x":2.78415, "y":4.49457, "heading":1.54916, "vx":0.52161, "vy":-0.45321, "omega":0.30067, "ax":-4.84835, "ay":4.21239, "alpha":-2.76681, "fx":[-72.66621,-82.06284,-91.35718,-83.78962], "fy":[82.20092,72.84821,60.76169,70.79536]}, + {"t":3.8309, "x":2.79974, "y":4.48102, "heading":1.55994, "vx":0.34774, "vy":-0.30214, "omega":0.20145, "ax":-4.84826, "ay":4.2125, "alpha":-2.79589, "fx":[-72.5596,-82.15274,-91.46506,-83.69273], "fy":[82.30885,72.76056,60.61688,70.92744]}, + {"t":3.86677, "x":2.8091, "y":4.4729, "heading":1.56717, "vx":0.17387, "vy":-0.15107, "omega":0.10118, "ax":-4.84818, "ay":4.21259, "alpha":-2.82137, "fx":[-72.46628,-82.21383,-91.5553,-83.62948], "fy":[82.40295,72.70346,60.49602,71.01734]}, + {"t":3.90263, "x":2.81221, "y":4.47019, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/F_PATH_1.traj b/src/main/deploy/choreo/F_PATH_1.traj index a541a42c..30ab8e58 100644 --- a/src/main/deploy/choreo/F_PATH_1.traj +++ b/src/main/deploy/choreo/F_PATH_1.traj @@ -3,8 +3,8 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":7.152472496032715, "y":4.007034778594971, "heading":4.71238898038469, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":6.099902153015137, "y":4.149273872375488, "heading":4.71238898038469, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":7.152472496032715, "y":4.007034778594971, "heading":4.71238898038469, "intervals":18, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":5.881801605224609, "y":4.026000022888184, "heading":4.71238898038469, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -13,8 +13,8 @@ }, "params":{ "waypoints":[ - {"x":{"exp":"7.152472496032715 m", "val":7.152472496032715}, "y":{"exp":"4.007034778594971 m", "val":4.007034778594971}, "heading":{"exp":"270 deg", "val":4.71238898038469}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"6.099902153015137 m", "val":6.099902153015137}, "y":{"exp":"4.149273872375488 m", "val":4.149273872375488}, "heading":{"exp":"270 deg", "val":4.71238898038469}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"7.152472496032715 m", "val":7.152472496032715}, "y":{"exp":"4.007034778594971 m", "val":4.007034778594971}, "heading":{"exp":"270 deg", "val":4.71238898038469}, "intervals":18, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"5.881801605224609 m", "val":5.881801605224609}, "y":{"exp":"4.026000022888184 m", "val":4.026000022888184}, "heading":{"exp":"270 deg", "val":4.71238898038469}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -26,26 +26,27 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,0.81309], + "waypoints":[0.0,0.88787], "samples":[ - {"t":0.0, "x":7.15247, "y":4.00703, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.39489, "ay":0.86417, "alpha":0.0, "fx":[-108.77521,-108.77521,-108.77521,-108.77521], "fy":[14.69934,14.69934,14.69934,14.69934]}, - {"t":0.04783, "x":7.14516, "y":4.00802, "heading":-1.5708, "vx":-0.30586, "vy":0.04133, "omega":0.0, "ax":-6.39408, "ay":0.86406, "alpha":0.0, "fx":[-108.76147,-108.76147,-108.76147,-108.76147], "fy":[14.69748,14.69748,14.69748,14.69748]}, - {"t":0.09566, "x":7.12322, "y":4.01099, "heading":-1.5708, "vx":-0.61168, "vy":0.08266, "omega":0.0, "ax":-6.393, "ay":0.86392, "alpha":0.0, "fx":[-108.74314,-108.74314,-108.74314,-108.74314], "fy":[14.695,14.695,14.695,14.695]}, - {"t":0.14349, "x":7.08665, "y":4.01593, "heading":-1.5708, "vx":-0.91746, "vy":0.12398, "omega":0.0, "ax":-6.39149, "ay":0.86371, "alpha":0.0, "fx":[-108.71749,-108.71749,-108.71749,-108.71749], "fy":[14.69154,14.69154,14.69154,14.69154]}, - {"t":0.19132, "x":7.03545, "y":4.02285, "heading":-1.5708, "vx":-1.22316, "vy":0.16529, "omega":0.0, "ax":-6.38923, "ay":0.86341, "alpha":0.0, "fx":[-108.67902,-108.67902,-108.67902,-108.67902], "fy":[14.68634,14.68634,14.68634,14.68634]}, - {"t":0.23915, "x":6.96964, "y":4.03174, "heading":-1.5708, "vx":-1.52875, "vy":0.20659, "omega":0.0, "ax":-6.38546, "ay":0.8629, "alpha":0.0, "fx":[-108.61493,-108.61493,-108.61493,-108.61493], "fy":[14.67768,14.67768,14.67768,14.67768]}, - {"t":0.28697, "x":6.88922, "y":4.04261, "heading":-1.5708, "vx":-1.83416, "vy":0.24786, "omega":0.0, "ax":-6.37794, "ay":0.86188, "alpha":0.0, "fx":[-108.48685,-108.48685,-108.48685,-108.48685], "fy":[14.66037,14.66037,14.66037,14.66037]}, - {"t":0.3348, "x":6.7942, "y":4.05545, "heading":-1.5708, "vx":-2.13921, "vy":0.28908, "omega":0.0, "ax":-6.3554, "ay":0.85884, "alpha":0.0, "fx":[-108.10353,-108.10353,-108.10353,-108.10353], "fy":[14.60857,14.60857,14.60857,14.60857]}, - {"t":0.38263, "x":6.68461, "y":4.07026, "heading":-1.5708, "vx":-2.44318, "vy":0.33016, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}, - {"t":0.43046, "x":6.56776, "y":4.08605, "heading":-1.5708, "vx":-2.44318, "vy":0.33016, "omega":0.0, "ax":6.3554, "ay":-0.85884, "alpha":0.0, "fx":[108.10353,108.10353,108.10353,108.10353], "fy":[-14.60857,-14.60857,-14.60857,-14.60857]}, - {"t":0.47829, "x":6.45817, "y":4.10086, "heading":-1.5708, "vx":-2.13921, "vy":0.28908, "omega":0.0, "ax":6.37794, "ay":-0.86188, "alpha":0.0, "fx":[108.48685,108.48685,108.48685,108.48685], "fy":[-14.66037,-14.66037,-14.66037,-14.66037]}, - {"t":0.52612, "x":6.36315, "y":4.1137, "heading":-1.5708, "vx":-1.83416, "vy":0.24786, "omega":0.0, "ax":6.38546, "ay":-0.8629, "alpha":0.0, "fx":[108.61493,108.61493,108.61493,108.61493], "fy":[-14.67768,-14.67768,-14.67768,-14.67768]}, - {"t":0.57395, "x":6.28273, "y":4.12457, "heading":-1.5708, "vx":-1.52875, "vy":0.20659, "omega":0.0, "ax":6.38923, "ay":-0.86341, "alpha":0.0, "fx":[108.67902,108.67902,108.67902,108.67902], "fy":[-14.68634,-14.68634,-14.68634,-14.68634]}, - {"t":0.62178, "x":6.21692, "y":4.13346, "heading":-1.5708, "vx":-1.22316, "vy":0.16529, "omega":0.0, "ax":6.39149, "ay":-0.86371, "alpha":0.0, "fx":[108.71749,108.71749,108.71749,108.71749], "fy":[-14.69154,-14.69154,-14.69154,-14.69154]}, - {"t":0.66961, "x":6.16573, "y":4.14038, "heading":-1.5708, "vx":-0.91746, "vy":0.12398, "omega":0.0, "ax":6.393, "ay":-0.86392, "alpha":0.0, "fx":[108.74314,108.74314,108.74314,108.74314], "fy":[-14.695,-14.695,-14.695,-14.695]}, - {"t":0.71744, "x":6.12916, "y":4.14532, "heading":-1.5708, "vx":-0.61168, "vy":0.08266, "omega":0.0, "ax":6.39408, "ay":-0.86406, "alpha":0.0, "fx":[108.76147,108.76147,108.76147,108.76147], "fy":[-14.69748,-14.69748,-14.69748,-14.69748]}, - {"t":0.76527, "x":6.10722, "y":4.14829, "heading":-1.5708, "vx":-0.30586, "vy":0.04133, "omega":0.0, "ax":6.39489, "ay":-0.86417, "alpha":0.0, "fx":[108.77521,108.77521,108.77521,108.77521], "fy":[-14.69934,-14.69934,-14.69934,-14.69934]}, - {"t":0.81309, "x":6.0999, "y":4.14927, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":7.15247, "y":4.00703, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-6.45247, "ay":0.09631, "alpha":0.0, "fx":[-109.75464,-109.75464,-109.75464,-109.75464], "fy":[1.63813,1.63813,1.63813,1.63813]}, + {"t":0.04933, "x":7.14462, "y":4.00715, "heading":-1.5708, "vx":-0.31827, "vy":0.00475, "omega":0.0, "ax":-6.45173, "ay":0.09629, "alpha":0.0, "fx":[-109.74209,-109.74209,-109.74209,-109.74209], "fy":[1.63794,1.63794,1.63794,1.63794]}, + {"t":0.09865, "x":7.12107, "y":4.0075, "heading":-1.5708, "vx":-0.63651, "vy":0.0095, "omega":0.0, "ax":-6.45077, "ay":0.09628, "alpha":0.0, "fx":[-109.72567,-109.72567,-109.72567,-109.72567], "fy":[1.6377,1.6377,1.6377,1.6377]}, + {"t":0.14798, "x":7.08183, "y":4.00809, "heading":-1.5708, "vx":-0.9547, "vy":0.01425, "omega":0.0, "ax":-6.44945, "ay":0.09626, "alpha":0.0, "fx":[-109.70329,-109.70329,-109.70329,-109.70329], "fy":[1.63736,1.63736,1.63736,1.63736]}, + {"t":0.1973, "x":7.02689, "y":4.00891, "heading":-1.5708, "vx":-1.27283, "vy":0.019, "omega":0.0, "ax":-6.44755, "ay":0.09623, "alpha":0.0, "fx":[-109.67096,-109.67096,-109.67096,-109.67096], "fy":[1.63688,1.63688,1.63688,1.63688]}, + {"t":0.24663, "x":6.95627, "y":4.00996, "heading":-1.5708, "vx":-1.59086, "vy":0.02374, "omega":0.0, "ax":-6.44456, "ay":0.09619, "alpha":0.0, "fx":[-109.62018,-109.62018,-109.62018,-109.62018], "fy":[1.63612,1.63612,1.63612,1.63612]}, + {"t":0.29596, "x":6.86995, "y":4.01125, "heading":-1.5708, "vx":-1.90875, "vy":0.02849, "omega":0.0, "ax":-6.43919, "ay":0.09611, "alpha":0.0, "fx":[-109.52883,-109.52883,-109.52883,-109.52883], "fy":[1.63476,1.63476,1.63476,1.63476]}, + {"t":0.34528, "x":6.76797, "y":4.01277, "heading":-1.5708, "vx":-2.22637, "vy":0.03323, "omega":0.0, "ax":-6.42668, "ay":0.09592, "alpha":0.0, "fx":[-109.31594,-109.31594,-109.31594,-109.31594], "fy":[1.63158,1.63158,1.63158,1.63158]}, + {"t":0.39461, "x":6.65033, "y":4.01453, "heading":-1.5708, "vx":-2.54337, "vy":0.03796, "omega":0.0, "ax":-6.36445, "ay":0.09499, "alpha":0.0, "fx":[-108.25753,-108.25753,-108.25753,-108.25753], "fy":[1.61578,1.61578,1.61578,1.61578]}, + {"t":0.44393, "x":6.51714, "y":4.01652, "heading":-1.5708, "vx":-2.8573, "vy":0.04265, "omega":0.0, "ax":6.36445, "ay":-0.09499, "alpha":0.0, "fx":[108.25753,108.25753,108.25753,108.25753], "fy":[-1.61578,-1.61578,-1.61578,-1.61578]}, + {"t":0.49326, "x":6.38394, "y":4.01851, "heading":-1.5708, "vx":-2.54337, "vy":0.03796, "omega":0.0, "ax":6.42668, "ay":-0.09592, "alpha":0.0, "fx":[109.31594,109.31594,109.31594,109.31594], "fy":[-1.63158,-1.63158,-1.63158,-1.63158]}, + {"t":0.54259, "x":6.2663, "y":4.02026, "heading":-1.5708, "vx":-2.22637, "vy":0.03323, "omega":0.0, "ax":6.43919, "ay":-0.09611, "alpha":0.0, "fx":[109.52883,109.52883,109.52883,109.52883], "fy":[-1.63476,-1.63476,-1.63476,-1.63476]}, + {"t":0.59191, "x":6.16432, "y":4.02178, "heading":-1.5708, "vx":-1.90875, "vy":0.02849, "omega":0.0, "ax":6.44456, "ay":-0.09619, "alpha":0.0, "fx":[109.62018,109.62018,109.62018,109.62018], "fy":[-1.63612,-1.63612,-1.63612,-1.63612]}, + {"t":0.64124, "x":6.07801, "y":4.02307, "heading":-1.5708, "vx":-1.59086, "vy":0.02374, "omega":0.0, "ax":6.44755, "ay":-0.09623, "alpha":0.0, "fx":[109.67096,109.67096,109.67096,109.67096], "fy":[-1.63688,-1.63688,-1.63688,-1.63688]}, + {"t":0.69056, "x":6.00738, "y":4.02413, "heading":-1.5708, "vx":-1.27283, "vy":0.019, "omega":0.0, "ax":6.44945, "ay":-0.09626, "alpha":0.0, "fx":[109.70329,109.70329,109.70329,109.70329], "fy":[-1.63736,-1.63736,-1.63736,-1.63736]}, + {"t":0.73989, "x":5.95244, "y":4.02495, "heading":-1.5708, "vx":-0.9547, "vy":0.01425, "omega":0.0, "ax":6.45077, "ay":-0.09628, "alpha":0.0, "fx":[109.72567,109.72567,109.72567,109.72567], "fy":[-1.6377,-1.6377,-1.6377,-1.6377]}, + {"t":0.78922, "x":5.9132, "y":4.02553, "heading":-1.5708, "vx":-0.63651, "vy":0.0095, "omega":0.0, "ax":6.45173, "ay":-0.09629, "alpha":0.0, "fx":[109.74209,109.74209,109.74209,109.74209], "fy":[-1.63794,-1.63794,-1.63794,-1.63794]}, + {"t":0.83854, "x":5.88965, "y":4.02588, "heading":-1.5708, "vx":-0.31827, "vy":0.00475, "omega":0.0, "ax":6.45247, "ay":-0.09631, "alpha":0.0, "fx":[109.75464,109.75464,109.75464,109.75464], "fy":[-1.63813,-1.63813,-1.63813,-1.63813]}, + {"t":0.88787, "x":5.8818, "y":4.026, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/F_PATH_2.traj b/src/main/deploy/choreo/F_PATH_2.traj index c38c49f0..2f8246b0 100644 --- a/src/main/deploy/choreo/F_PATH_2.traj +++ b/src/main/deploy/choreo/F_PATH_2.traj @@ -3,8 +3,9 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":6.099902153015137, "y":4.149273872375488, "heading":4.71238898038469, "intervals":12, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":6.555067539215088, "y":3.969104051589966, "heading":4.71238898038469, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":5.976627826690674, "y":4.168239593505859, "heading":4.71238898038469, "intervals":15, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":6.811098575592041, "y":4.139791488647461, "heading":4.71238898038469, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":5.63525390625, "y":5.694940567016602, "heading":-0.5176488456806968, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -13,8 +14,9 @@ }, "params":{ "waypoints":[ - {"x":{"exp":"6.099902153015137 m", "val":6.099902153015137}, "y":{"exp":"4.149273872375488 m", "val":4.149273872375488}, "heading":{"exp":"270 deg", "val":4.71238898038469}, "intervals":12, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"6.555067539215088 m", "val":6.555067539215088}, "y":{"exp":"3.969104051589966 m", "val":3.969104051589966}, "heading":{"exp":"270 deg", "val":4.71238898038469}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"5.976627826690674 m", "val":5.976627826690674}, "y":{"exp":"4.168239593505859 m", "val":4.168239593505859}, "heading":{"exp":"270 deg", "val":4.71238898038469}, "intervals":15, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"6.811098575592041 m", "val":6.811098575592041}, "y":{"exp":"4.139791488647461 m", "val":4.139791488647461}, "heading":{"exp":"270 deg", "val":4.71238898038469}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"5.63525390625 m", "val":5.63525390625}, "y":{"exp":"5.694940567016602 m", "val":5.694940567016602}, "heading":{"exp":"-0.5176488456806968 rad", "val":-0.5176488456806968}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -26,21 +28,57 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,0.55109], + "waypoints":[0.0,0.67787,1.7466], "samples":[ - {"t":0.0, "x":6.0999, "y":4.14927, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.99967, "ay":-2.37487, "alpha":0.0, "fx":[102.05264,102.05264,102.05264,102.05264], "fy":[-40.39588,-40.39588,-40.39588,-40.39588]}, - {"t":0.04592, "x":6.10623, "y":4.14677, "heading":-1.5708, "vx":0.27553, "vy":-0.10906, "omega":0.0, "ax":5.9984, "ay":-2.37437, "alpha":0.0, "fx":[102.03112,102.03112,102.03112,102.03112], "fy":[-40.38736,-40.38736,-40.38736,-40.38736]}, - {"t":0.09185, "x":6.12521, "y":4.13926, "heading":-1.5708, "vx":0.551, "vy":-0.2181, "omega":0.0, "ax":5.99642, "ay":-2.37358, "alpha":0.0, "fx":[101.99732,101.99732,101.99732,101.99732], "fy":[-40.37398,-40.37398,-40.37398,-40.37398]}, - {"t":0.13777, "x":6.15684, "y":4.12674, "heading":-1.5708, "vx":0.82638, "vy":-0.32711, "omega":0.0, "ax":5.99284, "ay":-2.37217, "alpha":0.0, "fx":[101.93651,101.93651,101.93651,101.93651], "fy":[-40.34991,-40.34991,-40.34991,-40.34991]}, - {"t":0.1837, "x":6.20111, "y":4.10921, "heading":-1.5708, "vx":1.1016, "vy":-0.43605, "omega":0.0, "ax":5.98451, "ay":-2.36887, "alpha":0.0, "fx":[101.79475,101.79475,101.79475,101.79475], "fy":[-40.2938,-40.2938,-40.2938,-40.2938]}, - {"t":0.22962, "x":6.25801, "y":4.08669, "heading":-1.5708, "vx":1.37643, "vy":-0.54484, "omega":0.0, "ax":5.94301, "ay":-2.35244, "alpha":0.0, "fx":[101.08891,101.08891,101.08891,101.08891], "fy":[-40.0144,-40.0144,-40.0144,-40.0144]}, - {"t":0.27554, "x":6.32748, "y":4.05919, "heading":-1.5708, "vx":1.64936, "vy":-0.65287, "omega":0.0, "ax":-5.94301, "ay":2.35244, "alpha":0.0, "fx":[-101.08891,-101.08891,-101.08891,-101.08891], "fy":[40.0144,40.0144,40.0144,40.0144]}, - {"t":0.32147, "x":6.39696, "y":4.03169, "heading":-1.5708, "vx":1.37643, "vy":-0.54484, "omega":0.0, "ax":-5.98451, "ay":2.36887, "alpha":0.0, "fx":[-101.79475,-101.79475,-101.79475,-101.79475], "fy":[40.2938,40.2938,40.2938,40.2938]}, - {"t":0.36739, "x":6.45386, "y":4.00916, "heading":-1.5708, "vx":1.1016, "vy":-0.43605, "omega":0.0, "ax":-5.99284, "ay":2.37217, "alpha":0.0, "fx":[-101.93651,-101.93651,-101.93651,-101.93651], "fy":[40.34991,40.34991,40.34991,40.34991]}, - {"t":0.41332, "x":6.49813, "y":3.99164, "heading":-1.5708, "vx":0.82638, "vy":-0.32711, "omega":0.0, "ax":-5.99642, "ay":2.37358, "alpha":0.0, "fx":[-101.99732,-101.99732,-101.99732,-101.99732], "fy":[40.37398,40.37398,40.37398,40.37398]}, - {"t":0.45924, "x":6.52976, "y":3.97912, "heading":-1.5708, "vx":0.551, "vy":-0.2181, "omega":0.0, "ax":-5.9984, "ay":2.37437, "alpha":0.0, "fx":[-102.03112,-102.03112,-102.03112,-102.03112], "fy":[40.38736,40.38736,40.38736,40.38736]}, - {"t":0.50517, "x":6.54874, "y":3.97161, "heading":-1.5708, "vx":0.27553, "vy":-0.10906, "omega":0.0, "ax":-5.99967, "ay":2.37487, "alpha":0.0, "fx":[-102.05264,-102.05264,-102.05264,-102.05264], "fy":[40.39588,40.39588,40.39588,40.39588]}, - {"t":0.55109, "x":6.55507, "y":3.9691, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":5.97663, "y":4.16824, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.89821, "ay":-2.59191, "alpha":-1.67418, "fx":[96.8673,99.27787,103.37371,101.78863], "fy":[-51.60162,-46.81964,-36.89407,-41.03517]}, + {"t":0.04519, "x":5.98265, "y":4.16559, "heading":-1.5708, "vx":0.26655, "vy":-0.11713, "omega":-0.07566, "ax":5.93226, "ay":-2.5123, "alpha":-1.61318, "fx":[97.6942,99.88424,103.73929,102.30614], "fy":[-49.98027,-45.47286,-35.80287,-39.67809]}, + {"t":0.09038, "x":6.00075, "y":4.15773, "heading":-1.57422, "vx":0.53463, "vy":-0.23067, "omega":-0.14856, "ax":5.97772, "ay":-2.401, "alpha":-1.52803, "fx":[98.80148,100.69206,104.22472,102.99867], "fy":[-47.69861,-43.5984,-34.29123,-37.77292]}, + {"t":0.13557, "x":6.03102, "y":4.14486, "heading":-1.58093, "vx":0.80477, "vy":-0.33917, "omega":-0.21761, "ax":6.04113, "ay":-2.23463, "alpha":-1.40085, "fx":[100.34488,101.83289,104.90313,103.95067], "fy":[-44.27173,-40.77281,-32.04078,-34.95618]}, + {"t":0.18076, "x":6.07356, "y":4.12725, "heading":-1.59076, "vx":1.07778, "vy":-0.44015, "omega":-0.28092, "ax":6.13434, "ay":-1.95991, "alpha":-1.19103, "fx":[102.60042,103.55493,105.91024,105.30788], "fy":[-38.59592,-36.00893,-28.32402,-30.421]}, + {"t":0.22596, "x":6.12853, "y":4.10536, "heading":-1.60346, "vx":1.355, "vy":-0.52872, "omega":-0.33474, "ax":6.27654, "ay":-1.42602, "alpha":-0.78452, "fx":[105.983,106.30046,107.48407,107.2813], "fy":[-27.58253,-26.40386,-21.05809,-21.97994]}, + {"t":0.27115, "x":6.19617, "y":4.08001, "heading":-1.61859, "vx":1.63864, "vy":-0.59317, "omega":-0.3702, "ax":6.42333, "ay":-0.02356, "alpha":0.27329, "fx":[109.26849,109.25711,109.25007,109.26001], "fy":[0.53935,0.64495,-1.35867,-1.42845]}, + {"t":0.31634, "x":6.27678, "y":4.05318, "heading":-1.63532, "vx":1.92892, "vy":-0.59423, "omega":-0.35785, "ax":3.8236, "ay":5.04328, "alpha":3.97289, "fx":[68.48663,49.45604,61.41742,80.79333], "fy":[84.55505,96.77669,89.24822,72.55881]}, + {"t":0.36153, "x":6.36785, "y":4.03147, "heading":-1.65149, "vx":2.10171, "vy":-0.36632, "omega":-0.17831, "ax":-3.06227, "ay":5.57414, "alpha":4.03952, "fx":[-34.69919,-55.72923,-69.9958,-47.92926], "fy":[103.55582,94.01011,83.77077,97.92156]}, + {"t":0.40672, "x":6.45971, "y":4.02061, "heading":-1.65954, "vx":1.96332, "vy":-0.11442, "omega":0.00424, "ax":-4.48701, "ay":4.56383, "alpha":3.20003, "fx":[-64.01259,-75.96049,-87.49225,-77.82558], "fy":[88.82921,78.92375,65.84264,76.92216]}, + {"t":0.45191, "x":6.54385, "y":4.0201, "heading":-1.65935, "vx":1.76055, "vy":0.09183, "omega":0.14886, "ax":-4.92702, "ay":4.1081, "alpha":2.84734, "fx":[-73.95455,-82.69896,-92.51323,-86.06198], "fy":[80.89908,71.98649,58.80298,67.82171]}, + {"t":0.4971, "x":6.61838, "y":4.02844, "heading":-1.65263, "vx":1.53789, "vy":0.27747, "omega":0.27753, "ax":-5.13168, "ay":3.86177, "alpha":2.65682, "fx":[-78.69491,-85.99346,-94.82416,-89.64127], "fy":[76.38488,68.10275,55.1193,63.14363]}, + {"t":0.54229, "x":6.68264, "y":4.04493, "heading":-1.64008, "vx":1.30599, "vy":0.45199, "omega":0.3976, "ax":-5.24858, "ay":3.70901, "alpha":2.53802, "fx":[-81.42008,-87.96594,-96.15372,-91.56768], "fy":[73.52991,65.5898,52.84097,60.3958]}, + {"t":0.58748, "x":6.7363, "y":4.06914, "heading":-1.62212, "vx":1.0688, "vy":0.61961, "omega":0.51229, "ax":-5.32386, "ay":3.60535, "alpha":2.45679, "fx":[-83.17199,-89.30785,-97.02576,-92.72357], "fy":[71.58155,63.7885,51.27366,58.65985]}, + {"t":0.63268, "x":6.77916, "y":4.10082, "heading":-1.59896, "vx":0.8282, "vy":0.78254, "omega":0.62332, "ax":-5.37627, "ay":3.5305, "alpha":2.39759, "fx":[-84.38419,-90.30756,-97.64967,-93.45381], "fy":[70.17727,62.39302,50.1127,57.52838]}, + {"t":0.67787, "x":6.8111, "y":4.13979, "heading":-1.5708, "vx":0.58524, "vy":0.94208, "omega":0.73167, "ax":-5.40239, "ay":3.49372, "alpha":2.15547, "fx":[-85.62842,-90.9663,-97.47567,-93.50196], "fy":[68.59477,61.36751,50.37146,57.37519]}, + {"t":0.71025, "x":6.82722, "y":4.17213, "heading":-1.5471, "vx":0.41028, "vy":1.05523, "omega":0.80147, "ax":-5.41247, "ay":3.47754, "alpha":2.13757, "fx":[-85.86557,-91.26338,-97.60822,-93.52112], "fy":[68.28245,60.90889,50.09279,57.32355]}, + {"t":0.74264, "x":6.83767, "y":4.20813, "heading":-1.52114, "vx":0.235, "vy":1.16785, "omega":0.8707, "ax":-5.42395, "ay":3.45897, "alpha":2.11728, "fx":[-86.13974,-91.59262,-97.75442,-93.55232], "fy":[67.91876,60.39424,49.78224,57.24927]}, + {"t":0.77502, "x":6.84243, "y":4.24777, "heading":-1.49295, "vx":0.05934, "vy":1.27988, "omega":0.93927, "ax":-5.43713, "ay":3.43746, "alpha":2.09408, "fx":[-86.45935,-91.95775,-97.91649,-93.60224], "fy":[67.49114,59.81529,49.43396,57.14069]}, + {"t":0.80741, "x":6.8415, "y":4.29102, "heading":-1.46253, "vx":-0.11675, "vy":1.3912, "omega":1.00709, "ax":-5.45242, "ay":3.41225, "alpha":2.06726, "fx":[-86.8351,-92.36376,-98.09761,-93.6797], "fy":[66.98314,59.16092,49.03965,56.98214]}, + {"t":0.8398, "x":6.83486, "y":4.33787, "heading":-1.42991, "vx":-0.29333, "vy":1.50171, "omega":1.07404, "ax":-5.47037, "ay":3.3823, "alpha":2.03586, "fx":[-87.28095,-92.81746,-98.30237,-93.79663], "fy":[66.37264,58.41587,48.5873,56.75221]}, + {"t":0.87218, "x":6.8225, "y":4.38827, "heading":-1.39513, "vx":-0.47049, "vy":1.61125, "omega":1.13997, "ax":-5.49173, "ay":3.34614, "alpha":1.99849, "fx":[-87.81562,-93.32839,-98.53751,-93.96939], "fy":[65.62896,57.55852,48.05926,56.42085]}, + {"t":0.90457, "x":6.80438, "y":4.44221, "heading":-1.35821, "vx":-0.64835, "vy":1.71962, "omega":1.2047, "ax":-5.51757, "ay":3.30162, "alpha":1.95313, "fx":[-88.46499,-93.91025,-98.81303,-94.22096], "fy":[64.70791,56.5572,47.42886,55.94464]}, + {"t":0.93695, "x":6.78049, "y":4.49963, "heading":-1.31919, "vx":-0.82704, "vy":1.82654, "omega":1.26795, "ax":-5.54945, "ay":3.24549, "alpha":1.89677, "fx":[-89.26621,-94.58349,-99.14417,-94.58441], "fy":[63.54301,55.36351,46.65463,55.25846]}, + {"t":0.96934, "x":6.75079, "y":4.56049, "heading":-1.27813, "vx":-1.00676, "vy":1.93165, "omega":1.32938, "ax":-5.58972, "ay":3.17257, "alpha":1.82462, "fx":[-90.27488,-95.37974,-99.55479,-95.10904], "fy":[62.0288,53.89965,45.66925,54.26]}, + {"t":1.00173, "x":6.71526, "y":4.62471, "heading":-1.23508, "vx":-1.18779, "vy":2.0344, "omega":1.38847, "ax":-5.64212, "ay":3.07405, "alpha":1.72874, "fx":[-91.5784,-96.35038,-100.08362,-95.87103], "fy":[59.98652,52.03237,44.35742,52.77872]}, + {"t":1.03411, "x":6.67383, "y":4.69221, "heading":-1.19011, "vx":-1.37052, "vy":2.13395, "omega":1.44446, "ax":-5.71285, "ay":2.93383, "alpha":1.59499, "fx":[-93.32193,-97.58362,-100.79672,-96.99356], "fy":[57.08656,49.51371,42.50669,50.50762]}, + {"t":1.0665, "x":6.62645, "y":4.76286, "heading":-1.14333, "vx":-1.55553, "vy":2.22897, "omega":1.49611, "ax":-5.81283, "ay":2.71894, "alpha":1.39547, "fx":[-95.76039,-99.241,-101.81289,-98.68431], "fy":[52.6489,45.82702,39.68333,46.83446]}, + {"t":1.09888, "x":6.57302, "y":4.83647, "heading":-1.09488, "vx":-1.74379, "vy":2.31702, "omega":1.54131, "ax":-5.96184, "ay":2.35079, "alpha":1.0669, "fx":[-99.35211,-101.63457,-103.35547,-101.29492], "fy":[45.03098,39.70406,34.85901,40.35098]}, + {"t":1.13127, "x":6.51342, "y":4.91274, "heading":-1.04496, "vx":-1.93687, "vy":2.39316, "omega":1.57586, "ax":-6.1876, "ay":1.59303, "alpha":0.43229, "fx":[-104.68701,-105.27865,-105.79029,-105.24119], "fy":[29.23658,27.12159,24.95277,27.07731]}, + {"t":1.16366, "x":6.44745, "y":4.99108, "heading":-0.99392, "vx":-2.13726, "vy":2.44475, "omega":1.58986, "ax":-6.30643, "ay":-0.54535, "alpha":-1.15221, "fx":[-106.77206,-107.06855,-107.66061,-107.58129], "fy":[-14.7558,-11.05477,-3.6138,-7.6806]}, + {"t":1.19604, "x":6.37493, "y":5.06997, "heading":-0.94244, "vx":-2.3415, "vy":2.42709, "omega":1.55254, "ax":-2.28771, "ay":-5.78216, "alpha":-3.90146, "fx":[-35.98145,-20.17216,-43.778,-55.72169], "fy":[-100.96023,-104.70099,-96.56082,-91.18917]}, + {"t":1.22843, "x":6.29789, "y":5.14554, "heading":-0.89215, "vx":-2.41559, "vy":2.23983, "omega":1.42619, "ax":2.56951, "ay":-5.76678, "alpha":-3.64636, "fx":[36.64969,56.93236,53.46812,27.77661], "fy":[-102.02496,-92.17011,-93.74045,-104.42985]}, + {"t":1.26081, "x":6.22101, "y":5.21506, "heading":-0.84597, "vx":-2.33237, "vy":2.05306, "omega":1.3081, "ax":3.82519, "ay":-5.08582, "alpha":-3.19847, "fx":[57.75645,74.0653,74.34447,54.09508], "fy":[-92.40218,-79.91023,-79.36079,-94.36044]}, + {"t":1.2932, "x":6.14748, "y":5.27888, "heading":-0.8036, "vx":-2.20849, "vy":1.88836, "omega":1.20451, "ax":4.29943, "ay":-4.7221, "alpha":-2.97246, "fx":[66.33437,80.59741,81.48565,64.11054], "fy":[-86.7771,-73.71523,-72.52682,-88.26679]}, + {"t":1.32559, "x":6.07821, "y":5.33756, "heading":-0.76459, "vx":-2.06925, "vy":1.73543, "omega":1.10825, "ax":4.54034, "ay":-4.50824, "alpha":-2.84592, "fx":[70.89517,84.00561,84.92127,69.09729], "fy":[-83.28331,-70.03574,-68.76338,-84.65275]}, + {"t":1.35797, "x":6.01358, "y":5.3914, "heading":-0.7287, "vx":-1.92221, "vy":1.58942, "omega":1.01608, "ax":4.68465, "ay":-4.36919, "alpha":-2.76649, "fx":[73.72942,86.10872,86.89201,72.00815], "fy":[-80.90941,-67.58224,-66.4419,-82.34117]}, + {"t":1.39036, "x":5.95378, "y":5.44058, "heading":-0.69579, "vx":-1.77049, "vy":1.44792, "omega":0.92649, "ax":4.78037, "ay":-4.27198, "alpha":-2.71232, "fx":[75.67222,87.54502,88.14648,73.88705], "fy":[-79.18288,-65.81578,-64.89774,-80.76414]}, + {"t":1.42274, "x":5.89895, "y":5.48524, "heading":-0.66579, "vx":-1.61567, "vy":1.30957, "omega":0.83865, "ax":4.84836, "ay":-4.20033, "alpha":-2.67309, "fx":[77.09463,88.59328,89.0019,75.18718], "fy":[-77.86354,-64.47552,-63.81459,-79.6322]}, + {"t":1.45513, "x":5.84917, "y":5.52544, "heading":-0.63863, "vx":-1.45865, "vy":1.17354, "omega":0.75207, "ax":4.8991, "ay":-4.1454, "alpha":-2.64336, "fx":[78.18511,89.39412,89.61511,76.13465], "fy":[-76.81847,-63.42052,-63.02336,-78.78575]}, + {"t":1.48751, "x":5.8045, "y":5.56128, "heading":-0.61427, "vx":-1.29999, "vy":1.03929, "omega":0.66647, "ax":4.93838, "ay":-4.10196, "alpha":-2.62006, "fx":[79.04907,90.02608,90.07252,76.85405], "fy":[-75.9688,-62.56797,-62.42543,-78.13065]}, + {"t":1.5199, "x":5.76499, "y":5.59278, "heading":-0.59269, "vx":-1.14006, "vy":0.90644, "omega":0.58161, "ax":4.96968, "ay":-4.06677, "alpha":-2.6013, "fx":[79.74986,90.53653,90.42575,77.41923], "fy":[-75.26505,-61.866,-61.95933,-77.60824]}, + {"t":1.55229, "x":5.73067, "y":5.62001, "heading":-0.57385, "vx":-0.97911, "vy":0.77473, "omega":0.49737, "ax":4.9952, "ay":-4.03769, "alpha":-2.5859, "fx":[80.32776,90.95576,90.70756,77.8766], "fy":[-74.67469,-61.28039,-61.58465,-77.18028]}, + {"t":1.58467, "x":5.70158, "y":5.64298, "heading":-0.55774, "vx":-0.81734, "vy":0.64397, "omega":0.41362, "ax":5.0164, "ay":-4.01326, "alpha":-2.57305, "fx":[80.80956,91.30406,90.9398,78.25663], "fy":[-74.17553,-60.78762,-61.2737,-76.82091]}, + {"t":1.61706, "x":5.67774, "y":5.66173, "heading":-0.54435, "vx":-0.65488, "vy":0.514, "omega":0.33029, "ax":5.03429, "ay":-3.99245, "alpha":-2.56221, "fx":[81.21378,91.59557,91.1376,78.58013], "fy":[-73.75192,-60.37095,-61.00686,-76.51203]}, + {"t":1.64944, "x":5.65917, "y":5.67628, "heading":-0.53365, "vx":-0.49184, "vy":0.3847, "omega":0.24731, "ax":5.04958, "ay":-3.97451, "alpha":-2.55299, "fx":[81.5536,91.84041,91.31175,78.86178], "fy":[-73.39253,-60.01817,-60.76988,-76.24066]}, + {"t":1.68183, "x":5.64589, "y":5.68666, "heading":-0.52564, "vx":-0.3283, "vy":0.25598, "omega":0.16463, "ax":5.0628, "ay":-3.95889, "alpha":-2.5451, "fx":[81.83869,92.04602,91.47015,79.11227], "fy":[-73.08891,-59.72017,-60.55215,-75.99718]}, + {"t":1.71422, "x":5.63792, "y":5.69287, "heading":-0.52031, "vx":-0.16434, "vy":0.12777, "omega":0.08221, "ax":5.07434, "ay":-3.94517, "alpha":-2.53832, "fx":[82.07631,92.21797,91.61867,79.33957], "fy":[-72.83463,-59.47005,-60.34569,-75.77426]}, + {"t":1.7466, "x":5.63525, "y":5.69494, "heading":-0.51765, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/F_PATH_3.traj b/src/main/deploy/choreo/F_PATH_3.traj index 54a99f41..a3f411f8 100644 --- a/src/main/deploy/choreo/F_PATH_3.traj +++ b/src/main/deploy/choreo/F_PATH_3.traj @@ -3,22 +3,24 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":5.948180198669434, "y":4.026000022888184, "heading":4.71238898038469, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":7.664534091949463, "y":4.822539806365967, "heading":1.5707963267948966, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":5.312845230102539, "y":5.400979518890381, "heading":-0.5179875110397575, "intervals":55, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":7.010232925415039, "y":6.064763069152832, "heading":1.5707963267948966, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":1.0}}, "enabled":true}], "targetDt":0.05 }, "params":{ "waypoints":[ - {"x":{"exp":"5.948180198669434 m", "val":5.948180198669434}, "y":{"exp":"4.026000022888184 m", "val":4.026000022888184}, "heading":{"exp":"270 deg", "val":4.71238898038469}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"7.664534091949463 m", "val":7.664534091949463}, "y":{"exp":"4.822539806365967 m", "val":4.822539806365967}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"5.312845230102539 m", "val":5.312845230102539}, "y":{"exp":"5.400979518890381 m", "val":5.400979518890381}, "heading":{"exp":"-0.5179875110397575 rad", "val":-0.5179875110397575}, "intervals":55, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"7.010232925415039 m", "val":7.010232925415039}, "y":{"exp":"6.064763069152832 m", "val":6.064763069152832}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"1 m / s", "val":1.0}}}, "enabled":true}], "targetDt":{ "exp":"0.05 s", "val":0.05 @@ -26,49 +28,64 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,1.17692], + "waypoints":[0.0,1.97994], "samples":[ - {"t":0.0, "x":5.94818, "y":4.026, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.38951, "ay":1.33028, "alpha":16.96732, "fx":[87.69216,19.09249,82.84233,109.02999], "fy":[66.01385,108.02505,-71.08104,-12.44686]}, - {"t":0.02942, "x":5.95008, "y":4.02658, "heading":-1.5708, "vx":0.12915, "vy":0.03914, "omega":0.49923, "ax":4.51582, "ay":1.46105, "alpha":16.09449, "fx":[87.80683,21.06865,89.22912,109.14678], "fy":[65.84723,107.64321,-62.80586,-11.27622]}, - {"t":0.05885, "x":5.95583, "y":4.02836, "heading":-1.55611, "vx":0.26202, "vy":0.08213, "omega":0.97278, "ax":4.60583, "ay":1.60375, "alpha":15.39677, "fx":[87.46923,22.46084,94.1257,109.31991], "fy":[66.27865,107.34342,-55.18521,-9.31949]}, - {"t":0.08827, "x":5.96554, "y":4.03147, "heading":-1.52749, "vx":0.39754, "vy":0.12932, "omega":1.4258, "ax":4.66414, "ay":1.74846, "alpha":14.87121, "fx":[86.72221,23.48188,97.6349,109.50366], "fy":[67.23387,107.10152,-48.74606,-6.6258]}, - {"t":0.11769, "x":5.97925, "y":4.03603, "heading":-1.48553, "vx":0.53477, "vy":0.18076, "omega":1.86335, "ax":4.70114, "ay":1.89625, "alpha":14.45588, "fx":[85.60281,24.39654,100.21839,109.6423], "fy":[68.63049,106.86669,-43.25454,-3.22404]}, - {"t":0.14712, "x":5.99702, "y":4.04217, "heading":-1.43071, "vx":0.67309, "vy":0.23656, "omega":2.28869, "ax":4.72832, "ay":2.05319, "alpha":14.06171, "fx":[84.15346,25.56924,102.31759,109.66941], "fy":[70.37223,106.55229,-38.10315,0.87532]}, - {"t":0.17654, "x":6.01887, "y":4.05002, "heading":-1.36337, "vx":0.81222, "vy":0.29697, "omega":2.70243, "ax":4.75772, "ay":2.22532, "alpha":13.58351, "fx":[82.44088,27.54165,104.22179,109.50528], "fy":[72.33616,106.0058,-32.6095,5.67608]}, - {"t":0.20596, "x":6.04483, "y":4.05972, "heading":-1.28385, "vx":0.9522, "vy":0.36244, "omega":3.1021, "ax":4.80365, "ay":2.41559, "alpha":12.89211, "fx":[80.58811,31.14622,106.04771,109.05296], "fy":[74.34975,104.92931,-26.11699,11.19218]}, - {"t":0.23538, "x":6.07493, "y":4.07143, "heading":-1.19258, "vx":1.09354, "vy":0.43352, "omega":3.48142, "ax":4.88504, "ay":2.62073, "alpha":11.81762, "fx":[78.83371,37.61967,107.72715,108.19221], "fy":[76.14661,102.68319,-17.9649,17.44668]}, - {"t":0.26481, "x":6.10922, "y":4.08532, "heading":-1.09015, "vx":1.23727, "vy":0.51063, "omega":3.82913, "ax":5.02396, "ay":2.82571, "alpha":10.14703, "fx":[77.65051,48.46135,108.94535,106.76712], "fy":[77.26511,97.89187,-7.38028,24.48133]}, - {"t":0.29423, "x":6.1478, "y":4.10157, "heading":-0.97748, "vx":1.38509, "vy":0.59377, "omega":4.12769, "ax":5.2276, "ay":2.99962, "alpha":7.70494, "fx":[78.00809,64.17847,108.94361,104.54988], "fy":[76.7656,88.20951,6.71316,32.40238]}, - {"t":0.32365, "x":6.19081, "y":4.12034, "heading":-0.85603, "vx":1.5389, "vy":0.68202, "omega":4.35439, "ax":5.4451, "ay":3.11848, "alpha":4.50916, "fx":[81.98452,81.46744,105.92949,101.09663], "fy":[72.25057,72.37485,25.9863,41.56586]}, - {"t":0.35308, "x":6.23845, "y":4.14175, "heading":-0.72791, "vx":1.69912, "vy":0.77378, "omega":4.48706, "ax":5.55572, "ay":3.18687, "alpha":0.27233, "fx":[93.62772,94.04472,95.37966,94.95251], "fy":[55.73508,54.98432,52.65044,53.46135]}, - {"t":0.3825, "x":6.29085, "y":4.1659, "heading":-0.59589, "vx":1.86258, "vy":0.86755, "omega":4.49508, "ax":5.1287, "ay":3.08416, "alpha":-7.43128, "fx":[108.47036,99.74418,67.21356,73.5228], "fy":[1.95592,43.87131,85.56545,78.45019]}, - {"t":0.41192, "x":6.34787, "y":4.19276, "heading":-0.46363, "vx":2.01348, "vy":0.95829, "omega":4.27643, "ax":4.1242, "ay":3.06737, "alpha":-12.87839, "fx":[103.96803,99.64234,46.27866,30.71685], "fy":[-30.6386,43.95,98.26907,97.12019]}, - {"t":0.44135, "x":6.4089, "y":4.22229, "heading":-0.33781, "vx":2.13483, "vy":1.04854, "omega":3.8975, "ax":4.46879, "ay":2.46007, "alpha":-12.05426, "fx":[103.52197,97.68479,38.50997,64.33457], "fy":[-31.6994,47.76727,101.20956,50.10263]}, - {"t":0.47077, "x":6.47365, "y":4.2542, "heading":-0.22313, "vx":2.26632, "vy":1.12093, "omega":3.54283, "ax":4.96916, "ay":1.76007, "alpha":-11.55187, "fx":[105.69848,95.35094,40.24201,96.80457], "fy":[-22.06087,51.64744,99.94176,-9.77529]}, - {"t":0.50019, "x":6.54248, "y":4.28794, "heading":-0.11889, "vx":2.41252, "vy":1.17271, "omega":3.20294, "ax":5.0149, "ay":1.82273, "alpha":-11.27773, "fx":[106.59227,93.02218,42.91973,98.674], "fy":[-13.53973,54.7482,97.8384,-15.03019]}, - {"t":0.52961, "x":6.61563, "y":4.32324, "heading":-0.02465, "vx":2.56008, "vy":1.22634, "omega":2.87112, "ax":4.95904, "ay":1.88058, "alpha":-11.15589, "fx":[106.1148,90.39347,44.07311,96.82572], "fy":[-7.3113,57.14792,95.3896,-17.27347]}, - {"t":0.55904, "x":6.6931, "y":4.36013, "heading":0.05983, "vx":2.70599, "vy":1.28168, "omega":2.54288, "ax":4.73772, "ay":1.88333, "alpha":-10.92382, "fx":[103.09949,86.35722,43.39629,89.49588], "fy":[-2.50958,57.97353,90.07624,-17.40041]}, - {"t":0.58846, "x":6.77477, "y":4.39866, "heading":0.13465, "vx":2.84538, "vy":1.33709, "omega":2.22146, "ax":0.32243, "ay":-0.24496, "alpha":1.73007, "fx":[0.4328,1.64007,10.49976,9.36483], "fy":[-0.32036,-9.25336,-7.98541,0.89239]}, - {"t":0.61788, "x":6.85863, "y":4.4379, "heading":0.20001, "vx":2.85487, "vy":1.32988, "omega":2.27237, "ax":-4.26991, "ay":-1.57292, "alpha":14.65754, "fx":[-103.58428,-81.8474,-26.31445,-78.77393], "fy":[3.75176,-64.39656,-95.26431,48.88947]}, - {"t":0.64731, "x":6.94078, "y":4.47634, "heading":0.26687, "vx":2.72924, "vy":1.2836, "omega":2.70364, "ax":-4.37459, "ay":-1.46586, "alpha":16.0532, "fx":[-106.78895,-83.68512,-25.9507,-81.21749], "fy":[4.98073,-66.68455,-100.38374,62.35241]}, - {"t":0.67673, "x":7.01919, "y":4.51348, "heading":0.34642, "vx":2.60052, "vy":1.24047, "omega":3.17597, "ax":-4.27291, "ay":-1.38806, "alpha":17.25537, "fx":[-107.86904,-83.31289,-21.63972,-77.90235], "fy":[5.70991,-68.69188,-102.91678,71.45681]}, - {"t":0.70615, "x":7.09386, "y":4.54937, "heading":0.43986, "vx":2.4748, "vy":1.19963, "omega":3.68368, "ax":-5.75094, "ay":-2.14927, "alpha":5.48442, "fx":[-106.56363,-91.41597,-85.80187,-107.50598], "fy":[-19.77202,-58.15275,-64.63161,-3.67734]}, - {"t":0.73558, "x":7.16419, "y":4.58374, "heading":0.54825, "vx":2.30559, "vy":1.13639, "omega":3.84504, "ax":-5.81323, "ay":-2.58747, "alpha":-1.96586, "fx":[-94.92696,-103.5253,-102.33008,-94.74322], "fy":[-52.70815,-32.85663,-37.00489,-53.47897]}, - {"t":0.765, "x":7.22951, "y":4.61606, "heading":0.66138, "vx":2.13455, "vy":1.06026, "omega":3.7872, "ax":-5.58991, "ay":-2.69021, "alpha":-5.43432, "fx":[-83.18418,-108.30658,-104.25233,-84.5878], "fy":[-70.02825,-11.39636,-32.58079,-69.0333]}, - {"t":0.79442, "x":7.28989, "y":4.64609, "heading":0.77281, "vx":1.97008, "vy":0.98111, "omega":3.62731, "ax":-5.37709, "ay":-2.75171, "alpha":-7.39669, "fx":[-75.49464,-109.11406,-104.12764,-77.11458], "fy":[-78.38967,2.2898,-33.58413,-77.53927]}, - {"t":0.82384, "x":7.34553, "y":4.67377, "heading":0.87954, "vx":1.81187, "vy":0.90014, "omega":3.40968, "ax":-5.21858, "ay":-2.81605, "alpha":-8.39439, "fx":[-72.03154,-108.86225,-103.29914,-70.87302], "fy":[-81.64707,9.82292,-36.36496,-83.41147]}, - {"t":0.85327, "x":7.39658, "y":4.69903, "heading":0.97986, "vx":1.65832, "vy":0.81729, "omega":3.16269, "ax":-5.12203, "ay":-2.87246, "alpha":-8.7781, "fx":[-72.45039,-108.58523,-102.11373,-65.34791], "fy":[-81.29557,13.49412,-39.75271,-87.88467]}, - {"t":0.88269, "x":7.44316, "y":4.72183, "heading":1.07292, "vx":1.50761, "vy":0.73277, "omega":2.90441, "ax":-5.08458, "ay":-2.90157, "alpha":-8.7994, "fx":[-76.39848,-108.4863,-100.72435,-60.33971], "fy":[-77.58988,14.88327,-43.26612,-91.44688]}, - {"t":0.91211, "x":7.48531, "y":4.74214, "heading":1.15837, "vx":1.35801, "vy":0.6474, "omega":2.6455, "ax":-5.09708, "ay":-2.88421, "alpha":-8.66893, "fx":[-83.26858,-108.53941,-99.22317,-55.7686], "fy":[-70.14919,14.93344,-46.68258,-94.3402]}, - {"t":0.94154, "x":7.52307, "y":4.75994, "heading":1.23621, "vx":1.20804, "vy":0.56254, "omega":2.39044, "ax":-5.14027, "ay":-2.80724, "alpha":-8.59488, "fx":[-91.76779,-108.68338,-97.67564,-51.6112], "fy":[-58.59644,14.19264,-49.89354,-96.70396]}, - {"t":0.97096, "x":7.55638, "y":4.77528, "heading":1.30655, "vx":1.0568, "vy":0.47994, "omega":2.13755, "ax":-5.18402, "ay":-2.67502, "alpha":-8.75718, "fx":[-99.83746,-108.86811,-96.1336,-47.87568], "fy":[-43.52068,12.98597,-52.84342,-98.6273]}, - {"t":1.00038, "x":7.58523, "y":4.78824, "heading":1.36944, "vx":0.90427, "vy":0.40123, "omega":1.87989, "ax":-5.20072, "ay":-2.51641, "alpha":-9.21409, "fx":[-105.56203,-109.05912,-94.64293,-44.5867], "fy":[-27.06276,11.522,-55.49915,-100.17349]}, - {"t":1.02981, "x":7.60959, "y":4.79896, "heading":1.42475, "vx":0.75125, "vy":0.32719, "omega":1.60878, "ax":-5.18322, "ay":-2.37001, "alpha":-9.86121, "fx":[-108.40287,-109.23419,-93.24894,-41.77416], "fy":[-11.98019,9.95399,-57.8342,-101.39207]}, - {"t":1.05923, "x":7.62945, "y":4.80756, "heading":1.47209, "vx":0.59874, "vy":0.25746, "omega":1.31863, "ax":-5.14409, "ay":-2.26022, "alpha":-10.52767, "fx":[-109.15318,-109.38065,-91.99826,-39.46588], "fy":[-0.04467,8.40842,-59.82249,-102.32413]}, - {"t":1.08865, "x":7.64484, "y":4.81415, "heading":1.51089, "vx":0.44739, "vy":0.19096, "omega":1.00888, "ax":-5.10039, "ay":-2.19105, "alpha":-11.08792, "fx":[-108.91232,-109.49374,-90.9367,-37.68214], "fy":[8.37548,6.99242,-61.43956,-103.00455]}, - {"t":1.11808, "x":7.6558, "y":4.81882, "heading":1.54057, "vx":0.29732, "vy":0.12649, "omega":0.68264, "ax":-5.06402, "ay":-2.15527, "alpha":-11.48688, "fx":[-108.43876,-109.57474,-90.10484,-36.43199], "fy":[13.6941,5.79244,-62.66608,-103.46273]}, - {"t":1.1475, "x":7.66235, "y":4.82161, "heading":1.56066, "vx":0.14832, "vy":0.06307, "omega":0.34466, "ax":-5.04089, "ay":-2.14368, "alpha":-11.71394, "fx":[-108.10169,-109.62848,-89.53421,-35.71214], "fy":[16.48554,4.8727,-63.48973,-103.72237]}, - {"t":1.17692, "x":7.66453, "y":4.82254, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":5.31285, "y":5.40098, "heading":-0.51799, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.00791, "ay":2.34946, "alpha":0.01123, "fx":[102.16304,102.18963,102.22267,102.19612], "fy":[40.03998,39.97176,39.88743,39.9557]}, + {"t":0.036, "x":5.31674, "y":5.4025, "heading":-0.51799, "vx":0.21628, "vy":0.08458, "omega":0.0004, "ax":6.00551, "ay":2.34852, "alpha":0.01373, "fx":[102.11548,102.14795,102.18836,102.15596], "fy":[40.04092,39.95752,39.85446,39.93792]}, + {"t":0.072, "x":5.32842, "y":5.40707, "heading":-0.51797, "vx":0.43247, "vy":0.16912, "omega":0.0009, "ax":6.0007, "ay":2.34664, "alpha":0.01873, "fx":[102.02043,102.0646,102.11976,102.07572], "fy":[40.04277,39.92905,39.78858,39.90242]}, + {"t":0.108, "x":5.34787, "y":5.41468, "heading":-0.51794, "vx":0.64849, "vy":0.2536, "omega":0.00157, "ax":5.9863, "ay":2.34101, "alpha":0.03373, "fx":[101.73596,101.81478,101.91426,101.83585], "fy":[40.04811,39.8437,39.59149,39.7963]}, + {"t":0.144, "x":5.3751, "y":5.42532, "heading":-0.51788, "vx":0.86399, "vy":0.33787, "omega":0.00279, "ax":1.86315, "ay":0.72863, "alpha":4.97225, "fx":[26.80398,14.81433,38.00528,47.14304], "fy":[31.49045,8.3125,-6.60643,16.37844]}, + {"t":0.17999, "x":5.40741, "y":5.43796, "heading":-0.51778, "vx":0.93106, "vy":0.3641, "omega":0.18178, "ax":0.00003, "ay":0.0, "alpha":5.36195, "fx":[-5.20456,-18.98286,5.2056,18.98385], "fy":[18.98334,-5.20511,-18.98337,5.20505]}, + {"t":0.21599, "x":5.44092, "y":5.45107, "heading":-0.51124, "vx":0.93106, "vy":0.3641, "omega":0.37481, "ax":0.0, "ay":0.0, "alpha":4.78389, "fx":[-4.75466,-16.90604,4.75466,16.90605], "fy":[16.90604,-4.75467,-16.90605,4.75465]}, + {"t":0.25199, "x":5.47444, "y":5.46417, "heading":-0.49775, "vx":0.93106, "vy":0.3641, "omega":0.54702, "ax":0.0, "ay":0.0, "alpha":4.25842, "fx":[-4.43506,-14.99058,4.43506,14.99058], "fy":[14.99058,-4.43506,-14.99058,4.43506]}, + {"t":0.28799, "x":5.50796, "y":5.47728, "heading":-0.47805, "vx":0.93106, "vy":0.3641, "omega":0.70032, "ax":0.0, "ay":0.0, "alpha":3.78265, "fx":[-4.20099,-13.23562,4.20099,13.23562], "fy":[13.23562,-4.20099,-13.23562,4.20099]}, + {"t":0.32399, "x":5.54147, "y":5.49039, "heading":-0.45284, "vx":0.93106, "vy":0.3641, "omega":0.83649, "ax":0.0, "ay":0.0, "alpha":3.3533, "fx":[-4.01875,-11.63571,4.01875,11.63571], "fy":[11.63571,-4.01875,-11.63571,4.01875]}, + {"t":0.35999, "x":5.57499, "y":5.50349, "heading":-0.42273, "vx":0.93106, "vy":0.3641, "omega":0.9572, "ax":0.0, "ay":0.0, "alpha":2.96687, "fx":[-3.86397,-10.18309,3.86397,10.18309], "fy":[10.18309,-3.86397,-10.18309,3.86397]}, + {"t":0.39599, "x":5.60851, "y":5.5166, "heading":-0.38827, "vx":0.93106, "vy":0.3641, "omega":1.06401, "ax":0.0, "ay":0.0, "alpha":2.61976, "fx":[-3.71966,-8.86884,3.71966,8.86884], "fy":[8.86884,-3.71967,-8.86884,3.71966]}, + {"t":0.43199, "x":5.64202, "y":5.52971, "heading":-0.34997, "vx":0.93106, "vy":0.3641, "omega":1.15832, "ax":0.0, "ay":0.0, "alpha":2.30842, "fx":[-3.57447,-7.6836,3.57447,7.6836], "fy":[7.6836,-3.57447,-7.6836,3.57447]}, + {"t":0.46798, "x":5.67554, "y":5.54282, "heading":-0.30827, "vx":0.93106, "vy":0.3641, "omega":1.24142, "ax":0.0, "ay":0.0, "alpha":2.02939, "fx":[-3.42125,-6.61797,3.42125,6.61797], "fy":[6.61797,-3.42125,-6.61797,3.42125]}, + {"t":0.50398, "x":5.70906, "y":5.55592, "heading":-0.26358, "vx":0.93106, "vy":0.3641, "omega":1.31447, "ax":0.0, "ay":0.0, "alpha":1.77935, "fx":[-3.25595,-5.66276,3.25595,5.66276], "fy":[5.66276,-3.25595,-5.66276,3.25595]}, + {"t":0.53998, "x":5.74258, "y":5.56903, "heading":-0.21626, "vx":0.93106, "vy":0.3641, "omega":1.37853, "ax":0.0, "ay":0.0, "alpha":1.55517, "fx":[-3.07667,-4.80918,3.07667,4.80918], "fy":[4.80918,-3.07667,-4.80918,3.07667]}, + {"t":0.57598, "x":5.77609, "y":5.58214, "heading":-0.16664, "vx":0.93106, "vy":0.3641, "omega":1.43451, "ax":0.0, "ay":0.0, "alpha":1.35394, "fx":[-2.88295,-4.04886,2.88295,4.04886], "fy":[4.04886,-2.88295,-4.04886,2.88295]}, + {"t":0.61198, "x":5.80961, "y":5.59525, "heading":-0.115, "vx":0.93106, "vy":0.3641, "omega":1.48325, "ax":0.0, "ay":0.0, "alpha":1.17292, "fx":[-2.67522,-3.37394,2.67522,3.37394], "fy":[3.37394,-2.67522,-3.37394,2.67522]}, + {"t":0.64798, "x":5.84313, "y":5.60835, "heading":-0.0616, "vx":0.93106, "vy":0.3641, "omega":1.52548, "ax":0.0, "ay":0.0, "alpha":1.00958, "fx":[-2.4544,-2.77707,2.4544,2.77707], "fy":[2.77707,-2.4544,-2.77707,2.4544]}, + {"t":0.68398, "x":5.87664, "y":5.62146, "heading":-0.00669, "vx":0.93106, "vy":0.3641, "omega":1.56182, "ax":0.0, "ay":0.0, "alpha":0.8616, "fx":[-2.22157,-2.25148,2.22157,2.25148], "fy":[2.25148,-2.22157,-2.25148,2.22157]}, + {"t":0.71998, "x":5.91016, "y":5.63457, "heading":0.04954, "vx":0.93106, "vy":0.3641, "omega":1.59284, "ax":0.0, "ay":0.0, "alpha":0.72682, "fx":[-1.97781,-1.79096,1.97781,1.79096], "fy":[1.79096,-1.97781,-1.79096,1.97781]}, + {"t":0.75598, "x":5.94368, "y":5.64767, "heading":0.10688, "vx":0.93106, "vy":0.3641, "omega":1.619, "ax":0.0, "ay":0.0, "alpha":0.60323, "fx":[-1.72398,-1.3899,1.72398,1.3899], "fy":[1.3899,-1.72398,-1.3899,1.72398]}, + {"t":0.79197, "x":5.9772, "y":5.66078, "heading":0.16516, "vx":0.93106, "vy":0.3641, "omega":1.64072, "ax":0.0, "ay":0.0, "alpha":0.48897, "fx":[-1.46069,-1.04333,1.46069,1.04333], "fy":[1.04333,-1.46069,-1.04333,1.46069]}, + {"t":0.82797, "x":6.01071, "y":5.67389, "heading":0.22422, "vx":0.93106, "vy":0.3641, "omega":1.65832, "ax":0.0, "ay":0.0, "alpha":0.38231, "fx":[-1.18822,-0.7469,1.18822,0.7469], "fy":[0.7469,-1.18822,-0.7469,1.18822]}, + {"t":0.86397, "x":6.04423, "y":5.687, "heading":0.28392, "vx":0.93106, "vy":0.3641, "omega":1.67208, "ax":0.0, "ay":0.0, "alpha":0.2816, "fx":[-0.90648,-0.49695,0.90648,0.49695], "fy":[0.49695,-0.90647,-0.49695,0.90648]}, + {"t":0.89997, "x":6.07775, "y":5.7001, "heading":0.34411, "vx":0.93106, "vy":0.3641, "omega":1.68222, "ax":0.0, "ay":0.0, "alpha":0.18529, "fx":[-0.61504,-0.29051,0.61504,0.29051], "fy":[0.29052,-0.61504,-0.29051,0.61504]}, + {"t":0.93597, "x":6.11126, "y":5.71321, "heading":0.40467, "vx":0.93106, "vy":0.3641, "omega":1.68889, "ax":0.0, "ay":0.0, "alpha":0.09188, "fx":[-0.31314,-0.12534,0.31314,0.12534], "fy":[0.12534,-0.31314,-0.12534,0.31314]}, + {"t":0.97197, "x":6.14478, "y":5.72632, "heading":0.46547, "vx":0.93106, "vy":0.3641, "omega":1.6922, "ax":0.0, "ay":0.0, "alpha":-0.00008, "fx":[0.00029,0.0001,-0.00029,-0.0001], "fy":[-0.00009,0.00029,0.0001,-0.00029]}, + {"t":1.00797, "x":6.1783, "y":5.73942, "heading":0.52639, "vx":0.93106, "vy":0.3641, "omega":1.69219, "ax":0.0, "ay":0.0, "alpha":-0.09204, "fx":[0.32661,0.08654,-0.32661,-0.08654], "fy":[-0.08654,0.32661,0.08654,-0.32661]}, + {"t":1.04397, "x":6.21181, "y":5.75253, "heading":0.5873, "vx":0.93106, "vy":0.3641, "omega":1.68888, "ax":0.0, "ay":0.0, "alpha":-0.18542, "fx":[0.66738,0.13396,-0.66739,-0.13396], "fy":[-0.13396,0.66739,0.13396,-0.66738]}, + {"t":1.07997, "x":6.24533, "y":5.76564, "heading":0.6481, "vx":0.93106, "vy":0.3641, "omega":1.6822, "ax":0.0, "ay":0.0, "alpha":-0.2817, "fx":[1.02439,0.14154,-1.02439,-0.14154], "fy":[-0.14153,1.02439,0.14154,-1.02439]}, + {"t":1.11596, "x":6.27885, "y":5.77875, "heading":0.70866, "vx":0.93106, "vy":0.3641, "omega":1.67206, "ax":0.0, "ay":0.0, "alpha":-0.38236, "fx":[1.39953,0.10761,-1.39953,-0.10761], "fy":[-0.10761,1.39953,0.10761,-1.39953]}, + {"t":1.15196, "x":6.31237, "y":5.79185, "heading":0.76885, "vx":0.93106, "vy":0.3641, "omega":1.6583, "ax":0.0, "ay":0.0, "alpha":-0.48897, "fx":[1.79478,0.0297,-1.79478,-0.0297], "fy":[-0.0297,1.79478,0.0297,-1.79478]}, + {"t":1.18796, "x":6.34588, "y":5.80496, "heading":0.82855, "vx":0.93106, "vy":0.3641, "omega":1.6407, "ax":0.0, "ay":0.0, "alpha":-0.60317, "fx":[2.21221,-0.09552,-2.21221,0.09552], "fy":[0.09552,2.21221,-0.09552,-2.21221]}, + {"t":1.22396, "x":6.3794, "y":5.81807, "heading":0.88761, "vx":0.93106, "vy":0.3641, "omega":1.61898, "ax":0.0, "ay":0.0, "alpha":-0.7267, "fx":[2.65385,-0.27221,-2.65385,0.27221], "fy":[0.27221,2.65385,-0.27221,-2.65385]}, + {"t":1.25996, "x":6.41292, "y":5.83118, "heading":0.94589, "vx":0.93106, "vy":0.3641, "omega":1.59282, "ax":0.0, "ay":0.0, "alpha":-0.86144, "fx":[3.12174,-0.50537,-3.12174,0.50537], "fy":[0.50537,3.12174,-0.50537,-3.12174]}, + {"t":1.29596, "x":6.44643, "y":5.84428, "heading":1.00323, "vx":0.93106, "vy":0.3641, "omega":1.56181, "ax":0.0, "ay":0.0, "alpha":-1.00937, "fx":[3.61789,-0.80081,-3.61789,0.80081], "fy":[0.80081,3.61789,-0.80081,-3.61789]}, + {"t":1.33196, "x":6.47995, "y":5.85739, "heading":1.05946, "vx":0.93106, "vy":0.3641, "omega":1.52548, "ax":0.0, "ay":0.0, "alpha":-1.17267, "fx":[4.14427,-1.16509,-4.14427,1.16509], "fy":[1.16509,4.14426,-1.16509,-4.14427]}, + {"t":1.36796, "x":6.51347, "y":5.8705, "heading":1.11437, "vx":0.93106, "vy":0.3641, "omega":1.48326, "ax":0.0, "ay":0.0, "alpha":-1.35366, "fx":[4.70287,-1.60546,-4.70287,1.60546], "fy":[1.60546,4.70287,-1.60546,-4.70287]}, + {"t":1.40395, "x":6.54699, "y":5.8836, "heading":1.16777, "vx":0.93106, "vy":0.3641, "omega":1.43453, "ax":0.0, "ay":0.0, "alpha":-1.55487, "fx":[5.29581,-2.12978,-5.29581,2.12978], "fy":[2.12978,5.29581,-2.12978,-5.29581]}, + {"t":1.43995, "x":6.5805, "y":5.89671, "heading":1.21941, "vx":0.93106, "vy":0.3641, "omega":1.37856, "ax":0.0, "ay":0.0, "alpha":-1.77903, "fx":[5.92543,-2.74634,-5.92543,2.74634], "fy":[2.74634,5.92543,-2.74634,-5.92543]}, + {"t":1.47595, "x":6.61402, "y":5.90982, "heading":1.26904, "vx":0.93106, "vy":0.3641, "omega":1.31451, "ax":0.0, "ay":0.0, "alpha":-2.02906, "fx":[6.5945,-3.46372,-6.5945,3.46372], "fy":[3.46372,6.5945,-3.46372,-6.5945]}, + {"t":1.51195, "x":6.64754, "y":5.92293, "heading":1.31636, "vx":0.93106, "vy":0.3641, "omega":1.24147, "ax":0.0, "ay":0.0, "alpha":-2.30809, "fx":[7.30657,-4.29045,-7.30657,4.29046], "fy":[4.29046,7.30657,-4.29045,-7.30657]}, + {"t":1.54795, "x":6.68105, "y":5.93603, "heading":1.36105, "vx":0.93106, "vy":0.3641, "omega":1.15838, "ax":0.0, "ay":0.0, "alpha":-2.61942, "fx":[8.0663,-5.23478,-8.0663,5.23478], "fy":[5.23478,8.0663,-5.23478,-8.0663]}, + {"t":1.58395, "x":6.71457, "y":5.94914, "heading":1.40275, "vx":0.93106, "vy":0.3641, "omega":1.06409, "ax":0.0, "ay":0.0, "alpha":-2.96651, "fx":[8.88006,-6.3041,-8.88006,6.3041], "fy":[6.3041,8.88006,-6.3041,-8.88006]}, + {"t":1.61995, "x":6.74809, "y":5.96225, "heading":1.44105, "vx":0.93106, "vy":0.3641, "omega":0.9573, "ax":0.0, "ay":0.0, "alpha":-3.35293, "fx":[9.75653,-7.50442,-9.75653,7.50442], "fy":[7.50442,9.75653,-7.50442,-9.75653]}, + {"t":1.65595, "x":6.7816, "y":5.97536, "heading":1.47552, "vx":0.93106, "vy":0.3641, "omega":0.83659, "ax":0.0, "ay":0.0, "alpha":-3.78225, "fx":[10.7076,-8.83949,-10.7076,8.83949], "fy":[8.83949,10.7076,-8.83949,-10.7076]}, + {"t":1.69195, "x":6.81512, "y":5.98846, "heading":1.50563, "vx":0.93106, "vy":0.3641, "omega":0.70044, "ax":0.0, "ay":0.0, "alpha":-4.25799, "fx":[11.7493,-10.30981,-11.7493,10.30981], "fy":[10.30981,11.7493,-10.30981,-11.7493]}, + {"t":1.72794, "x":6.84864, "y":6.00157, "heading":1.53085, "vx":0.93106, "vy":0.3641, "omega":0.54715, "ax":0.0, "ay":0.0, "alpha":-4.78342, "fx":[12.90296,-11.91112,-12.90294,11.91114], "fy":[11.91111,12.90293,-11.91115,-12.90297]}, + {"t":1.76394, "x":6.88216, "y":6.01468, "heading":1.55054, "vx":0.93106, "vy":0.3641, "omega":0.37496, "ax":-0.00001, "ay":-0.00004, "alpha":-5.36144, "fx":[14.19614,-13.63297,-14.1966,13.63243], "fy":[13.63208,14.19573,-13.63333,-14.19701]}, + {"t":1.79994, "x":6.91567, "y":6.02778, "heading":1.56404, "vx":0.93106, "vy":0.3641, "omega":0.18195, "ax":-1.86317, "ay":-0.72857, "alpha":-4.97695, "fx":[-20.23919,-44.57749,-42.79449,-19.15708], "fy":[1.45883,1.44431,-24.50694,-27.96708]}, + {"t":1.83594, "x":6.94798, "y":6.04042, "heading":1.57059, "vx":0.86399, "vy":0.33787, "omega":0.00279, "ax":-5.98629, "ay":-2.34102, "alpha":-0.03373, "fx":[-101.86028,-101.90766,-101.79034,-101.74232], "fy":[-39.72752,-39.61012,-39.9123,-40.03032]}, + {"t":1.87194, "x":6.97521, "y":6.05107, "heading":1.57069, "vx":0.64849, "vy":0.2536, "omega":0.00157, "ax":-6.00069, "ay":-2.34665, "alpha":-0.01873, "fx":[-102.0899,-102.11594,-102.05039,-102.02414], "fy":[-39.8644,-39.79882,-39.96708,-40.03285]}, + {"t":1.90794, "x":6.99466, "y":6.05867, "heading":1.57075, "vx":0.43247, "vy":0.16912, "omega":0.0009, "ax":-6.0055, "ay":-2.34853, "alpha":-0.01373, "fx":[-102.1665,-102.18553,-102.13738,-102.11825], "fy":[-39.9101,-39.86194,-39.98537,-40.03363]}, + {"t":1.94394, "x":7.00634, "y":6.06324, "heading":1.57078, "vx":0.21628, "vy":0.08458, "omega":0.0004, "ax":-6.00791, "ay":-2.34947, "alpha":-0.01123, "fx":[-102.20481,-102.22034,-102.18093,-102.16532], "fy":[-39.93295,-39.89353,-39.99453,-40.03401]}, + {"t":1.97994, "x":7.01023, "y":6.06476, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/F_PATH_4.traj b/src/main/deploy/choreo/F_PATH_4.traj index 66d94b7e..ae77c880 100644 --- a/src/main/deploy/choreo/F_PATH_4.traj +++ b/src/main/deploy/choreo/F_PATH_4.traj @@ -3,22 +3,24 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":7.664534091949463, "y":4.822539806365967, "heading":1.5707963267948966, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":5.63525390625, "y":5.723388195037842, "heading":5.759586531581287, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":7.010232925415039, "y":6.064763069152832, "heading":1.5707963267948966, "intervals":107, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":6.25162410736084, "y":4.035482883453369, "heading":-1.5707963267948966, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":0.5}}, "enabled":true}], "targetDt":0.05 }, "params":{ "waypoints":[ - {"x":{"exp":"7.664534091949463 m", "val":7.664534091949463}, "y":{"exp":"4.822539806365967 m", "val":4.822539806365967}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"5.63525390625 m", "val":5.63525390625}, "y":{"exp":"5.723388195037842 m", "val":5.723388195037842}, "heading":{"exp":"330 deg", "val":5.759586531581287}, "intervals":38, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"7.010232925415039 m", "val":7.010232925415039}, "y":{"exp":"6.064763069152832 m", "val":6.064763069152832}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":107, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"6.25162410736084 m", "val":6.25162410736084}, "y":{"exp":"4.035482883453369 m", "val":4.035482883453369}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"0.5 m / s", "val":0.5}}}, "enabled":true}], "targetDt":{ "exp":"0.05 s", "val":0.05 @@ -26,48 +28,116 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,1.21167], + "waypoints":[0.0,4.41378], "samples":[ - {"t":0.0, "x":7.66453, "y":4.82254, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-5.55385, "ay":2.3377, "alpha":-7.72046, "fx":[-64.94315,-94.13923,-109.65289,-109.14212], "fy":[88.40789,56.43005,4.36042,9.8564]}, - {"t":0.03107, "x":7.66185, "y":4.82367, "heading":1.5708, "vx":-0.17255, "vy":0.07263, "omega":-0.23986, "ax":-5.56459, "ay":2.35307, "alpha":-7.56577, "fx":[-65.7665,-94.20808,-109.61865,-109.01485], "fy":[87.78412,56.30105,4.97179,11.04324]}, - {"t":0.06214, "x":7.65381, "y":4.82706, "heading":1.56334, "vx":-0.34543, "vy":0.14573, "omega":-0.47492, "ax":-5.57401, "ay":2.36831, "alpha":-7.42658, "fx":[-66.60996,-94.14827,-109.56604,-108.92494], "fy":[87.13013,56.38493,5.85298,11.76921]}, - {"t":0.09321, "x":7.64039, "y":4.83273, "heading":1.54859, "vx":-0.51861, "vy":0.21931, "omega":-0.70565, "ax":-5.58275, "ay":2.38407, "alpha":-7.29361, "fx":[-67.51441,-93.9707,-109.48829,-108.87072], "fy":[86.41217,56.66175,7.00441,12.13089]}, - {"t":0.12427, "x":7.62158, "y":4.8407, "heading":1.52667, "vx":-0.69206, "vy":0.29338, "omega":-0.93225, "ax":-5.59149, "ay":2.40115, "alpha":-7.15569, "fx":[-68.53319,-93.68756,-109.37608,-108.84201], "fy":[85.58336,57.10693,8.43139,12.24951]}, - {"t":0.15534, "x":7.59738, "y":4.85097, "heading":1.4977, "vx":-0.86577, "vy":0.36798, "omega":-1.15457, "ax":-5.60104, "ay":2.42042, "alpha":-6.99883, "fx":[-69.73403,-93.31435,-109.2171,-108.82309], "fy":[84.57962,57.68905,10.14444,12.26941]}, - {"t":0.18641, "x":7.56778, "y":4.86357, "heading":1.46183, "vx":-1.03979, "vy":0.44318, "omega":-1.37201, "ax":-5.61243, "ay":2.44269, "alpha":-6.80505, "fx":[-71.20076,-92.87282,-108.99525,-108.79463], "fy":[83.31405,58.36642,12.15975,12.3579]}, - {"t":0.21748, "x":7.53276, "y":4.87852, "heading":1.41921, "vx":-1.21416, "vy":0.51907, "omega":-1.58343, "ax":-5.62696, "ay":2.46856, "alpha":-6.55134, "fx":[-73.03343,-92.3955,-108.68934,-108.73344], "fy":[81.66929,59.08151,14.50048,12.70679]}, - {"t":0.24855, "x":7.49233, "y":4.89584, "heading":1.37001, "vx":-1.38898, "vy":0.59577, "omega":-1.78697, "ax":-5.64614, "ay":2.49823, "alpha":-6.20875, "fx":[-75.34437,-91.93303,-108.27097,-108.60855], "fy":[79.48835,59.75157,17.19951,13.53716]}, - {"t":0.27962, "x":7.44645, "y":4.91555, "heading":1.31449, "vx":-1.5644, "vy":0.67338, "omega":-1.97987, "ax":-5.67151, "ay":2.53139, "alpha":-5.74163, "fx":[-78.24557,-91.56629,-107.70055,-108.37093], "fy":[76.56566,60.25142,20.3056,15.11027]}, - {"t":0.31068, "x":7.39511, "y":4.93769, "heading":1.25298, "vx":-1.7406, "vy":0.75203, "omega":-2.15825, "ax":-5.70409, "ay":2.56725, "alpha":-5.10682, "fx":[-81.82063,-91.42814,-106.91894,-107.93195], "fy":[72.64456,60.37934,23.89734,17.75123]}, - {"t":0.34175, "x":7.33828, "y":4.9623, "heading":1.18593, "vx":-1.91782, "vy":0.83179, "omega":-2.31691, "ax":-5.74326, "ay":2.60483, "alpha":-4.25035, "fx":[-86.07448,-91.7444,-105.82773,-107.11814], "fy":[67.43533,59.78176,28.11646,21.8964]}, - {"t":0.37282, "x":7.27592, "y":4.9894, "heading":1.11394, "vx":-2.09625, "vy":0.91272, "omega":-2.44896, "ax":-5.78468, "ay":2.64381, "alpha":-3.09312, "fx":[-90.86283,-92.91602,-104.23467,-105.56941], "fy":[60.67824,57.76449,33.25438,28.18479]}, - {"t":0.40389, "x":7.208, "y":5.01903, "heading":1.03786, "vx":-2.27597, "vy":0.99486, "omega":-2.54506, "ax":-5.81538, "ay":2.68444, "alpha":-1.47473, "fx":[-95.83185,-95.68208,-101.67014,-102.48773], "fy":[52.27618,52.73754,40.01356,37.61928]}, - {"t":0.43496, "x":7.13448, "y":5.05123, "heading":0.95879, "vx":-2.45665, "vy":1.07826, "omega":-2.59088, "ax":-5.79404, "ay":2.71875, "alpha":1.06712, "fx":[-100.43824,-101.2724,-96.53598,-95.97335], "fy":[42.48072,40.22977,50.5134,51.75701]}, - {"t":0.46603, "x":7.05536, "y":5.08605, "heading":0.87829, "vx":-2.63666, "vy":1.16273, "omega":-2.55773, "ax":-5.47753, "ay":2.69168, "alpha":6.365, "fx":[-104.111,-108.28634,-78.85908,-81.42841], "fy":[32.0376,5.01301,73.8508,72.23766]}, - {"t":0.49709, "x":6.9708, "y":5.12347, "heading":0.79883, "vx":-2.80684, "vy":1.24635, "omega":-2.35998, "ax":-4.33895, "ay":2.60646, "alpha":14.13383, "fx":[-105.35271,-100.32436,-24.98242,-64.55795], "fy":[26.82559,-39.38171,102.62335,87.2735]}, - {"t":0.52816, "x":6.88151, "y":5.16345, "heading":0.72551, "vx":-2.94164, "vy":1.32733, "omega":-1.92086, "ax":-4.33193, "ay":2.60199, "alpha":13.61148, "fx":[-104.17777,-99.74191,-28.81674,-62.00335], "fy":[29.04454,-38.52676,98.2847,88.23426]}, - {"t":0.55923, "x":6.78802, "y":5.20594, "heading":0.66583, "vx":-3.07623, "vy":1.40817, "omega":-1.49797, "ax":-4.28619, "ay":2.48702, "alpha":12.90751, "fx":[-101.93853,-97.71249,-32.7662,-59.21056], "fy":[30.62596,-36.35785,87.38319,87.56289]}, - {"t":0.5903, "x":6.69038, "y":5.25089, "heading":0.61929, "vx":-3.20939, "vy":1.48544, "omega":-1.09696, "ax":1.35485, "ay":-0.34783, "alpha":-3.1858, "fx":[33.84381,25.39316,11.77765,21.16788], "fy":[-7.65958,6.10815,-4.15166,-17.96308]}, - {"t":0.62137, "x":6.59132, "y":5.29688, "heading":0.58521, "vx":-3.1673, "vy":1.47463, "omega":-1.19594, "ax":4.39407, "ay":-2.46566, "alpha":-12.16784, "fx":[101.20072,98.75159,42.32281,56.69212], "fy":[-33.5277,35.07948,-80.04837,-89.26414]}, - {"t":0.65244, "x":6.49504, "y":5.3415, "heading":0.54805, "vx":-3.03078, "vy":1.39803, "omega":-1.57397, "ax":4.4401, "ay":-2.64914, "alpha":-12.27491, "fx":[102.0754,101.10022,44.0765,54.84702], "fy":[-35.93443,36.01606,-87.58828,-92.73791]}, - {"t":0.68351, "x":6.40302, "y":5.38366, "heading":0.49915, "vx":-2.89284, "vy":1.31572, "omega":-1.95533, "ax":4.42228, "ay":-2.73679, "alpha":-12.26899, "fx":[101.7464,101.94343,45.61323,51.58405], "fy":[-38.4384,36.27649,-88.68625,-95.35971]}, - {"t":0.71457, "x":6.31528, "y":5.42321, "heading":0.4384, "vx":-2.75544, "vy":1.2307, "omega":-2.33651, "ax":4.77427, "ay":-2.6278, "alpha":-10.7276, "fx":[100.85525,103.65377,70.12552,50.2011], "fy":[-41.43441,32.57619,-73.47362,-96.46077]}, - {"t":0.74564, "x":6.23198, "y":5.46018, "heading":0.36581, "vx":-2.60712, "vy":1.14905, "omega":-2.6698, "ax":5.71849, "ay":-2.56166, "alpha":-4.28735, "fx":[99.59205,107.99489,98.96689,82.52586], "fy":[-44.56876,-14.21721,-44.41015,-71.09627]}, - {"t":0.77671, "x":6.15374, "y":5.49464, "heading":0.28287, "vx":-2.42945, "vy":1.06947, "omega":-2.803, "ax":5.86084, "ay":-2.60976, "alpha":-0.40668, "fx":[99.6285,100.87488,99.79505,98.46659], "fy":[-44.62745,-41.68959,-44.15866,-47.08918]}, - {"t":0.80778, "x":6.08109, "y":5.52661, "heading":0.19578, "vx":-2.24736, "vy":0.98839, "omega":-2.81564, "ax":5.84867, "ay":-2.59507, "alpha":1.93862, "fx":[100.92955,93.274,99.06662,104.66635], "fy":[-41.7335,-56.96195,-46.32698,-31.54342]}, - {"t":0.83885, "x":6.01409, "y":5.55607, "heading":0.1083, "vx":-2.06565, "vy":0.90776, "omega":-2.75541, "ax":5.80386, "ay":-2.56449, "alpha":3.45135, "fx":[103.02259,86.95906,97.82334,107.08287], "fy":[-36.40592,-66.35207,-49.16534,-22.56137]}, - {"t":0.86992, "x":5.95271, "y":5.58303, "heading":0.0227, "vx":-1.88534, "vy":0.82809, "omega":-2.64818, "ax":5.75491, "ay":-2.52639, "alpha":4.57121, "fx":[105.29052,81.86093,96.3258,108.08009], "fy":[-29.38897,-72.63958,-52.19036,-17.67386]}, - {"t":0.90098, "x":5.89692, "y":5.60754, "heading":-0.05958, "vx":-1.70654, "vy":0.7496, "omega":-2.50616, "ax":5.70499, "ay":-2.48566, "alpha":5.50752, "fx":[107.21697,77.74699,94.69201,108.50522], "fy":[-21.57158,-77.087,-55.19498,-15.26769]}, - {"t":0.93205, "x":5.84665, "y":5.62963, "heading":-0.13744, "vx":-1.5293, "vy":0.67237, "omega":-2.33505, "ax":5.65329, "ay":-2.44837, "alpha":6.33432, "fx":[108.54029,74.43547,92.99678,108.67092], "fy":[-13.81045,-80.3313,-58.07053,-14.3723]}, - {"t":0.96312, "x":5.80186, "y":5.64934, "heading":-0.20999, "vx":-1.35366, "vy":0.5963, "omega":-2.13825, "ax":5.60043, "ay":-2.41944, "alpha":7.06192, "fx":[109.25492,71.79295,91.29759,108.70143], "fy":[-6.73968,-82.73222,-60.75329,-14.39066]}, - {"t":0.99419, "x":5.76251, "y":5.66669, "heading":-0.27642, "vx":-1.17966, "vy":0.52114, "omega":-1.91885, "ax":5.54844, "ay":-2.40082, "alpha":7.68338, "fx":[109.50326,69.71067,89.64263,108.65307], "fy":[-0.68864,-84.51772,-63.20421,-14.9386]}, - {"t":1.02526, "x":5.72854, "y":5.68173, "heading":-0.33603, "vx":-1.00728, "vy":0.44655, "omega":-1.68014, "ax":5.49947, "ay":-2.39176, "alpha":8.19709, "fx":[109.45947,68.08737,88.0733,108.55758], "fy":[4.27534,-85.84964,-65.4,-15.75804]}, - {"t":1.05633, "x":5.6999, "y":5.69445, "heading":-0.38823, "vx":-0.83642, "vy":0.37224, "omega":-1.42547, "ax":5.45493, "ay":-2.38989, "alpha":8.6121, "fx":[109.26416,66.82056,86.62485,108.43774], "fy":[8.24795,-86.85505,-67.32811,-16.66985]}, - {"t":1.08739, "x":5.67655, "y":5.70486, "heading":-0.43252, "vx":-0.66694, "vy":0.29799, "omega":-1.1579, "ax":5.41532, "ay":-2.39238, "alpha":8.94543, "fx":[109.00788,65.80448,85.32677,108.3128], "fy":[11.39685,-87.64129,-68.98334,-17.54685]}, - {"t":1.11846, "x":5.65844, "y":5.71296, "heading":-0.46849, "vx":-0.4987, "vy":0.22366, "omega":-0.87998, "ax":5.38039, "ay":-2.3966, "alpha":9.2176, "fx":[108.73943,64.93254,84.20349,108.19984], "fy":[13.90248,-88.30214,-70.36486,-18.29722]}, - {"t":1.14953, "x":5.64554, "y":5.71875, "heading":-0.49583, "vx":-0.33154, "vy":0.1492, "omega":-0.59361, "ax":5.34947, "ay":-2.40037, "alpha":9.44897, "fx":[108.4801,64.10283,83.27525,108.11378], "fy":[15.92787,-88.91879,-71.47379,-18.85364]}, - {"t":1.1806, "x":5.63782, "y":5.72223, "heading":-0.51428, "vx":-0.16534, "vy":0.07463, "omega":-0.30004, "ax":5.32177, "ay":-2.40198, "alpha":9.65743, "fx":[108.23586,63.22515,82.55916,108.06697], "fy":[17.60652,-89.55749,-72.31104,-19.16585]}, - {"t":1.21167, "x":5.63525, "y":5.72339, "heading":-0.5236, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":7.01023, "y":6.06476, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-2.25759, "ay":-6.03905, "alpha":0.00573, "fx":[-38.41721,-38.36512,-38.38455,-38.43666], "fy":[-102.71641,-102.73584,-102.72848,-102.70903]}, + {"t":0.04125, "x":7.00831, "y":6.05963, "heading":1.5708, "vx":-0.09313, "vy":-0.24911, "omega":0.00024, "ax":-1.98576, "ay":-5.3119, "alpha":0.36993, "fx":[-34.79463,-31.78904,-32.72713,-35.79784], "fy":[-90.28237,-91.22856,-90.45099,-89.45396]}, + {"t":0.0825, "x":7.00278, "y":6.04483, "heading":1.57081, "vx":-0.17504, "vy":-0.46823, "omega":0.0155, "ax":-0.00001, "ay":-0.00004, "alpha":2.49947, "fx":[-6.48838,6.48802,6.48789,-6.48851], "fy":[-6.48893,-6.48879,6.48762,6.48748]}, + {"t":0.12375, "x":6.99556, "y":6.02552, "heading":1.57145, "vx":-0.17504, "vy":-0.46823, "omega":0.1186, "ax":0.0, "ay":0.0, "alpha":2.20025, "fx":[-5.70776,5.71518,5.70776,-5.71518], "fy":[-5.71519,-5.70776,5.71519,5.70776]}, + {"t":0.165, "x":6.98834, "y":6.0062, "heading":1.57634, "vx":-0.17504, "vy":-0.46823, "omega":0.20936, "ax":0.0, "ay":0.0, "alpha":1.9359, "fx":[-4.99735,5.05305,4.99735,-5.05305], "fy":[-5.05305,-4.99735,5.05305,4.99735]}, + {"t":0.20625, "x":6.98112, "y":5.98689, "heading":1.58497, "vx":-0.17504, "vy":-0.46823, "omega":0.28922, "ax":0.0, "ay":0.0, "alpha":1.70263, "fx":[-4.35662,4.48195,4.35662,-4.48195], "fy":[-4.48195,-4.35662,4.48195,4.35662]}, + {"t":0.2475, "x":6.9739, "y":5.96757, "heading":1.5969, "vx":-0.17504, "vy":-0.46823, "omega":0.35945, "ax":0.0, "ay":0.0, "alpha":1.49696, "fx":[-3.78308,3.98597,3.78308,-3.98597], "fy":[-3.98597,-3.78308,3.98597,3.78308]}, + {"t":0.28875, "x":6.96668, "y":5.94826, "heading":1.61173, "vx":-0.17504, "vy":-0.46823, "omega":0.4212, "ax":0.0, "ay":0.0, "alpha":1.31577, "fx":[-3.27287,3.55242,3.27287,-3.55242], "fy":[-3.55242,-3.27287,3.55242,3.27287]}, + {"t":0.33, "x":6.95946, "y":5.92894, "heading":1.62911, "vx":-0.17504, "vy":-0.46823, "omega":0.47548, "ax":0.0, "ay":0.0, "alpha":1.15624, "fx":[-2.82138,3.17121,2.82138,-3.17121], "fy":[-3.17121,-2.82138,3.17121,2.82138]}, + {"t":0.37125, "x":6.95224, "y":5.90963, "heading":1.64872, "vx":-0.17504, "vy":-0.46823, "omega":0.52317, "ax":0.0, "ay":0.0, "alpha":1.01585, "fx":[-2.42369,2.83425,2.42369,-2.83425], "fy":[-2.83425,-2.42369,2.83425,2.42369]}, + {"t":0.4125, "x":6.94502, "y":5.89031, "heading":1.6703, "vx":-0.17504, "vy":-0.46823, "omega":0.56508, "ax":0.0, "ay":0.0, "alpha":0.89236, "fx":[-2.07484,2.53508,2.07484,-2.53508], "fy":[-2.53508,-2.07484,2.53508,2.07484]}, + {"t":0.45375, "x":6.9378, "y":5.871, "heading":1.69361, "vx":-0.17504, "vy":-0.46823, "omega":0.60189, "ax":0.0, "ay":0.0, "alpha":0.78378, "fx":[-1.76998,2.26847,1.76998,-2.26847], "fy":[-2.26847,-1.76998,2.26847,1.76998]}, + {"t":0.495, "x":6.93058, "y":5.85168, "heading":1.71844, "vx":-0.17504, "vy":-0.46823, "omega":0.63422, "ax":0.0, "ay":0.0, "alpha":0.68832, "fx":[-1.50448,2.03018,1.50448,-2.03018], "fy":[-2.03018,-1.50448,2.03018,1.50448]}, + {"t":0.53625, "x":6.92336, "y":5.83237, "heading":1.7446, "vx":-0.17504, "vy":-0.46823, "omega":0.66261, "ax":0.0, "ay":0.0, "alpha":0.60443, "fx":[-1.27404,1.8167,1.27404,-1.8167], "fy":[-1.8167,-1.27404,1.8167,1.27404]}, + {"t":0.5775, "x":6.91614, "y":5.81305, "heading":1.77193, "vx":-0.17504, "vy":-0.46823, "omega":0.68754, "ax":0.0, "ay":0.0, "alpha":0.53072, "fx":[-1.07466,1.62513,1.07466,-1.62513], "fy":[-1.62513,-1.07466,1.62513,1.07466]}, + {"t":0.61875, "x":6.90892, "y":5.79374, "heading":1.80029, "vx":-0.17504, "vy":-0.46823, "omega":0.70944, "ax":0.0, "ay":0.0, "alpha":0.46597, "fx":[-0.90269,1.45302,0.90269,-1.45302], "fy":[-1.45302,-0.90269,1.45302,0.90269]}, + {"t":0.66, "x":6.9017, "y":5.77442, "heading":1.82956, "vx":-0.17504, "vy":-0.46823, "omega":0.72866, "ax":0.0, "ay":0.0, "alpha":0.40909, "fx":[-0.75483,1.29829,0.75483,-1.29829], "fy":[-1.29829,-0.75483,1.29829,0.75483]}, + {"t":0.70126, "x":6.89447, "y":5.75511, "heading":1.85962, "vx":-0.17504, "vy":-0.46823, "omega":0.74553, "ax":0.0, "ay":0.0, "alpha":0.35913, "fx":[-0.6281,1.15914,0.6281,-1.15914], "fy":[-1.15914,-0.6281,1.15914,0.6281]}, + {"t":0.74251, "x":6.88725, "y":5.73579, "heading":1.89037, "vx":-0.17504, "vy":-0.46823, "omega":0.76035, "ax":0.0, "ay":0.0, "alpha":0.31526, "fx":[-0.51982,1.03401,0.51982,-1.03401], "fy":[-1.03401,-0.51982,1.03401,0.51982]}, + {"t":0.78376, "x":6.88003, "y":5.71648, "heading":1.92173, "vx":-0.17504, "vy":-0.46823, "omega":0.77335, "ax":0.0, "ay":0.0, "alpha":0.27673, "fx":[-0.42761,0.92151,0.42761,-0.92151], "fy":[-0.92151,-0.42761,0.92151,0.42761]}, + {"t":0.82501, "x":6.87281, "y":5.69717, "heading":1.95364, "vx":-0.17504, "vy":-0.46823, "omega":0.78477, "ax":0.0, "ay":0.0, "alpha":0.2429, "fx":[-0.34935,0.82042,0.34935,-0.82042], "fy":[-0.82042,-0.34935,0.82042,0.34935]}, + {"t":0.86626, "x":6.86559, "y":5.67785, "heading":1.98601, "vx":-0.17504, "vy":-0.46823, "omega":0.79479, "ax":0.0, "ay":0.0, "alpha":0.2132, "fx":[-0.28316,0.72965,0.28316,-0.72965], "fy":[-0.72965,-0.28316,0.72965,0.28316]}, + {"t":0.90751, "x":6.85837, "y":5.65854, "heading":2.01879, "vx":-0.17504, "vy":-0.46823, "omega":0.80358, "ax":0.0, "ay":0.0, "alpha":0.18712, "fx":[-0.2274,0.6482,0.2274,-0.6482], "fy":[-0.6482,-0.2274,0.6482,0.2274]}, + {"t":0.94876, "x":6.85115, "y":5.63922, "heading":2.05194, "vx":-0.17504, "vy":-0.46823, "omega":0.8113, "ax":0.0, "ay":0.0, "alpha":0.16423, "fx":[-0.18061,0.5752,0.18061,-0.5752], "fy":[-0.5752,-0.18061,0.5752,0.18061]}, + {"t":0.99001, "x":6.84393, "y":5.61991, "heading":2.08541, "vx":-0.17504, "vy":-0.46823, "omega":0.81807, "ax":0.0, "ay":0.0, "alpha":0.14413, "fx":[-0.14153,0.50982,0.14153,-0.50982], "fy":[-0.50982,-0.14153,0.50982,0.14153]}, + {"t":1.03126, "x":6.83671, "y":5.60059, "heading":2.11915, "vx":-0.17504, "vy":-0.46823, "omega":0.82402, "ax":0.0, "ay":0.0, "alpha":0.12648, "fx":[-0.10903,0.45133,0.10903,-0.45133], "fy":[-0.45133,-0.10903,0.45133,0.10903]}, + {"t":1.07251, "x":6.82949, "y":5.58128, "heading":2.15314, "vx":-0.17504, "vy":-0.46823, "omega":0.82924, "ax":0.0, "ay":0.0, "alpha":0.11099, "fx":[-0.08216,0.39907,0.08216,-0.39907], "fy":[-0.39907,-0.08216,0.39907,0.08216]}, + {"t":1.11376, "x":6.82227, "y":5.56196, "heading":2.18735, "vx":-0.17504, "vy":-0.46823, "omega":0.83382, "ax":0.0, "ay":0.0, "alpha":0.09739, "fx":[-0.06008,0.35243,0.06008,-0.35243], "fy":[-0.35243,-0.06008,0.35243,0.06008]}, + {"t":1.15501, "x":6.81505, "y":5.54265, "heading":2.22175, "vx":-0.17504, "vy":-0.46823, "omega":0.83783, "ax":0.0, "ay":0.0, "alpha":0.08544, "fx":[-0.04205,0.31084,0.04205,-0.31084], "fy":[-0.31084,-0.04205,0.31084,0.04205]}, + {"t":1.19626, "x":6.80783, "y":5.52333, "heading":2.25631, "vx":-0.17504, "vy":-0.46823, "omega":0.84136, "ax":0.0, "ay":0.0, "alpha":0.07496, "fx":[-0.02744,0.2738,0.02744,-0.2738], "fy":[-0.2738,-0.02744,0.2738,0.02744]}, + {"t":1.23751, "x":6.80061, "y":5.50402, "heading":2.29101, "vx":-0.17504, "vy":-0.46823, "omega":0.84445, "ax":0.0, "ay":0.0, "alpha":0.06575, "fx":[-0.01572,0.24086,0.01572,-0.24086], "fy":[-0.24086,-0.01572,0.24086,0.01572]}, + {"t":1.27876, "x":6.79339, "y":5.4847, "heading":2.32585, "vx":-0.17504, "vy":-0.46823, "omega":0.84716, "ax":0.0, "ay":0.0, "alpha":0.05766, "fx":[-0.00642,0.21158,0.00642,-0.21158], "fy":[-0.21158,-0.00642,0.21158,0.00642]}, + {"t":1.32001, "x":6.78617, "y":5.46539, "heading":2.36079, "vx":-0.17504, "vy":-0.46823, "omega":0.84954, "ax":0.0, "ay":0.0, "alpha":0.05056, "fx":[0.00085,0.1856,-0.00085,-0.1856], "fy":[-0.1856,0.00085,0.1856,-0.00085]}, + {"t":1.36126, "x":6.77895, "y":5.44607, "heading":2.39584, "vx":-0.17504, "vy":-0.46823, "omega":0.85163, "ax":0.0, "ay":0.0, "alpha":0.04432, "fx":[0.00645,0.16256,-0.00645,-0.16256], "fy":[-0.16256,0.00645,0.16256,-0.00645]}, + {"t":1.40251, "x":6.77173, "y":5.42676, "heading":2.43097, "vx":-0.17504, "vy":-0.46823, "omega":0.85345, "ax":0.0, "ay":0.0, "alpha":0.03883, "fx":[0.01065,0.14215,-0.01065,-0.14215], "fy":[-0.14215,0.01065,0.14215,-0.01065]}, + {"t":1.44376, "x":6.76451, "y":5.40744, "heading":2.46617, "vx":-0.17504, "vy":-0.46823, "omega":0.85506, "ax":0.0, "ay":0.0, "alpha":0.03401, "fx":[0.0137,0.12409,-0.0137,-0.12409], "fy":[-0.12409,0.0137,0.12409,-0.0137]}, + {"t":1.48501, "x":6.75729, "y":5.38813, "heading":2.50144, "vx":-0.17504, "vy":-0.46823, "omega":0.85646, "ax":0.0, "ay":0.0, "alpha":0.02976, "fx":[0.01581,0.10811,-0.01581,-0.10811], "fy":[-0.10811,0.01581,0.10811,-0.01581]}, + {"t":1.52626, "x":6.75007, "y":5.36882, "heading":2.53677, "vx":-0.17504, "vy":-0.46823, "omega":0.85769, "ax":0.0, "ay":0.0, "alpha":0.02603, "fx":[0.01716,0.094,-0.01716,-0.094], "fy":[-0.094,0.01716,0.094,-0.01716]}, + {"t":1.56751, "x":6.74285, "y":5.3495, "heading":2.57215, "vx":-0.17504, "vy":-0.46823, "omega":0.85876, "ax":0.0, "ay":0.0, "alpha":0.02274, "fx":[0.01789,0.08153,-0.01789,-0.08153], "fy":[-0.08153,0.01789,0.08153,-0.01789]}, + {"t":1.60876, "x":6.73562, "y":5.33019, "heading":2.60757, "vx":-0.17504, "vy":-0.46823, "omega":0.8597, "ax":0.0, "ay":0.0, "alpha":0.01983, "fx":[0.01811,0.07052,-0.01811,-0.07052], "fy":[-0.07052,0.01811,0.07052,-0.01811]}, + {"t":1.65001, "x":6.7284, "y":5.31087, "heading":2.64304, "vx":-0.17504, "vy":-0.46823, "omega":0.86052, "ax":0.0, "ay":0.0, "alpha":0.01727, "fx":[0.01793,0.0608,-0.01793,-0.0608], "fy":[-0.0608,0.01793,0.0608,-0.01793]}, + {"t":1.69126, "x":6.72118, "y":5.29156, "heading":2.67853, "vx":-0.17504, "vy":-0.46823, "omega":0.86123, "ax":0.0, "ay":0.0, "alpha":0.015, "fx":[0.01744,0.05222,-0.01744,-0.05222], "fy":[-0.05222,0.01744,0.05222,-0.01744]}, + {"t":1.73251, "x":6.71396, "y":5.27224, "heading":2.71406, "vx":-0.17504, "vy":-0.46823, "omega":0.86185, "ax":0.0, "ay":0.0, "alpha":0.01298, "fx":[0.01669,0.04464,-0.01669,-0.04464], "fy":[-0.04464,0.01669,0.04464,-0.01669]}, + {"t":1.77376, "x":6.70674, "y":5.25293, "heading":2.74961, "vx":-0.17504, "vy":-0.46823, "omega":0.86238, "ax":0.0, "ay":0.0, "alpha":0.01119, "fx":[0.01575,0.03794,-0.01575,-0.03794], "fy":[-0.03794,0.01575,0.03794,-0.01575]}, + {"t":1.81501, "x":6.69952, "y":5.23361, "heading":2.78518, "vx":-0.17504, "vy":-0.46823, "omega":0.86284, "ax":0.0, "ay":0.0, "alpha":0.00959, "fx":[0.01464,0.03201,-0.01464,-0.03201], "fy":[-0.03201,0.01464,0.03201,-0.01464]}, + {"t":1.85626, "x":6.6923, "y":5.2143, "heading":2.82078, "vx":-0.17504, "vy":-0.46823, "omega":0.86324, "ax":0.0, "ay":0.0, "alpha":0.00815, "fx":[0.0134,0.02674,-0.0134,-0.02674], "fy":[-0.02674,0.0134,0.02674,-0.0134]}, + {"t":1.89751, "x":6.68508, "y":5.19498, "heading":2.85639, "vx":-0.17504, "vy":-0.46823, "omega":0.86358, "ax":0.0, "ay":0.0, "alpha":0.00685, "fx":[0.01206,0.02206,-0.01206,-0.02206], "fy":[-0.02206,0.01206,0.02206,-0.01206]}, + {"t":1.93876, "x":6.67786, "y":5.17567, "heading":2.89201, "vx":-0.17504, "vy":-0.46823, "omega":0.86386, "ax":0.0, "ay":0.0, "alpha":0.00567, "fx":[0.01062,0.01789,-0.01062,-0.01789], "fy":[-0.01789,0.01062,0.01789,-0.01062]}, + {"t":1.98001, "x":6.67064, "y":5.15635, "heading":2.92764, "vx":-0.17504, "vy":-0.46823, "omega":0.86409, "ax":0.0, "ay":0.0, "alpha":0.00458, "fx":[0.0091,0.01415,-0.0091,-0.01415], "fy":[-0.01415,0.0091,0.01415,-0.0091]}, + {"t":2.02126, "x":6.66342, "y":5.13704, "heading":2.96329, "vx":-0.17504, "vy":-0.46823, "omega":0.86428, "ax":0.0, "ay":0.0, "alpha":0.00357, "fx":[0.00749,0.01078,-0.00749,-0.01078], "fy":[-0.01078,0.00749,0.01078,-0.00749]}, + {"t":2.06251, "x":6.6562, "y":5.11772, "heading":2.99894, "vx":-0.17504, "vy":-0.46823, "omega":0.86443, "ax":0.0, "ay":0.0, "alpha":0.00263, "fx":[0.00578,0.00772,-0.00578,-0.00772], "fy":[-0.00772,0.00578,0.00772,-0.00578]}, + {"t":2.10377, "x":6.64898, "y":5.09841, "heading":3.0346, "vx":-0.17504, "vy":-0.46823, "omega":0.86454, "ax":0.0, "ay":0.0, "alpha":0.00173, "fx":[0.00398,0.00494,-0.00398,-0.00494], "fy":[-0.00494,0.00398,0.00494,-0.00398]}, + {"t":2.14502, "x":6.64176, "y":5.0791, "heading":3.07026, "vx":-0.17504, "vy":-0.46823, "omega":0.86461, "ax":0.0, "ay":0.0, "alpha":0.00086, "fx":[0.00206,0.00237,-0.00206,-0.00237], "fy":[-0.00237,0.00206,0.00237,-0.00206]}, + {"t":2.18627, "x":6.63454, "y":5.05978, "heading":3.10593, "vx":-0.17504, "vy":-0.46823, "omega":0.86464, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,-0.00001,0.0,0.00001], "fy":[0.00001,0.0,-0.00001,0.0]}, + {"t":2.22752, "x":6.62732, "y":5.04047, "heading":3.14159, "vx":-0.17504, "vy":-0.46823, "omega":0.86464, "ax":0.0, "ay":0.0, "alpha":-0.00086, "fx":[-0.00223,-0.00223,0.00223,0.00223], "fy":[0.00223,-0.00223,-0.00223,0.00223]}, + {"t":2.26877, "x":6.6201, "y":5.02115, "heading":-3.10593, "vx":-0.17504, "vy":-0.46823, "omega":0.86461, "ax":0.0, "ay":0.0, "alpha":-0.00173, "fx":[-0.00465,-0.00433,0.00465,0.00433], "fy":[0.00433,-0.00465,-0.00433,0.00465]}, + {"t":2.31002, "x":6.61288, "y":5.00184, "heading":-3.07026, "vx":-0.17504, "vy":-0.46823, "omega":0.86454, "ax":0.0, "ay":0.0, "alpha":-0.00263, "fx":[-0.0073,-0.00633,0.0073,0.00633], "fy":[0.00633,-0.0073,-0.00633,0.0073]}, + {"t":2.35127, "x":6.60566, "y":4.98252, "heading":-3.0346, "vx":-0.17504, "vy":-0.46823, "omega":0.86443, "ax":0.0, "ay":0.0, "alpha":-0.00358, "fx":[-0.01023,-0.00824,0.01023,0.00824], "fy":[0.00824,-0.01023,-0.00824,0.01023]}, + {"t":2.39252, "x":6.59844, "y":4.96321, "heading":-2.99894, "vx":-0.17504, "vy":-0.46823, "omega":0.86428, "ax":0.0, "ay":0.0, "alpha":-0.00458, "fx":[-0.01347,-0.01009,0.01347,0.01009], "fy":[0.01009,-0.01347,-0.01009,0.01347]}, + {"t":2.43377, "x":6.59122, "y":4.94389, "heading":-2.96329, "vx":-0.17504, "vy":-0.46823, "omega":0.86409, "ax":0.0, "ay":0.0, "alpha":-0.00567, "fx":[-0.01709,-0.01187,0.01709,0.01187], "fy":[0.01187,-0.01709,-0.01187,0.01709]}, + {"t":2.47502, "x":6.584, "y":4.92458, "heading":-2.92765, "vx":-0.17504, "vy":-0.46823, "omega":0.86386, "ax":0.0, "ay":0.0, "alpha":-0.00685, "fx":[-0.02116,-0.0136,0.02116,0.0136], "fy":[0.0136,-0.02116,-0.0136,0.02116]}, + {"t":2.51627, "x":6.57678, "y":4.90526, "heading":-2.89201, "vx":-0.17504, "vy":-0.46823, "omega":0.86357, "ax":0.0, "ay":0.0, "alpha":-0.00815, "fx":[-0.02573,-0.01528,0.02573,0.01528], "fy":[0.01528,-0.02573,-0.01528,0.02573]}, + {"t":2.55752, "x":6.56955, "y":4.88595, "heading":-2.85639, "vx":-0.17504, "vy":-0.46823, "omega":0.86324, "ax":0.0, "ay":0.0, "alpha":-0.00959, "fx":[-0.03089,-0.01688,0.03089,0.01688], "fy":[0.01688,-0.03089,-0.01688,0.03089]}, + {"t":2.59877, "x":6.56233, "y":4.86663, "heading":-2.82078, "vx":-0.17504, "vy":-0.46823, "omega":0.86284, "ax":0.0, "ay":0.0, "alpha":-0.01119, "fx":[-0.03672,-0.0184,0.03672,0.0184], "fy":[0.0184,-0.03672,-0.0184,0.03672]}, + {"t":2.64002, "x":6.55511, "y":4.84732, "heading":-2.78519, "vx":-0.17504, "vy":-0.46823, "omega":0.86238, "ax":0.0, "ay":0.0, "alpha":-0.01298, "fx":[-0.04334,-0.01982,0.04334,0.01982], "fy":[0.01982,-0.04334,-0.01982,0.04334]}, + {"t":2.68127, "x":6.54789, "y":4.828, "heading":-2.74961, "vx":-0.17504, "vy":-0.46823, "omega":0.86185, "ax":0.0, "ay":0.0, "alpha":-0.015, "fx":[-0.05085,-0.0211,0.05085,0.0211], "fy":[0.0211,-0.05085,-0.0211,0.05085]}, + {"t":2.72252, "x":6.54067, "y":4.80869, "heading":-2.71406, "vx":-0.17504, "vy":-0.46823, "omega":0.86123, "ax":0.0, "ay":0.0, "alpha":-0.01727, "fx":[-0.05937,-0.0222,0.05937,0.0222], "fy":[0.0222,-0.05937,-0.0222,0.05937]}, + {"t":2.76377, "x":6.53345, "y":4.78937, "heading":-2.67854, "vx":-0.17504, "vy":-0.46823, "omega":0.86051, "ax":0.0, "ay":0.0, "alpha":-0.01983, "fx":[-0.06905,-0.02306,0.06905,0.02306], "fy":[0.02306,-0.06905,-0.02306,0.06905]}, + {"t":2.80502, "x":6.52623, "y":4.77006, "heading":-2.64304, "vx":-0.17504, "vy":-0.46823, "omega":0.8597, "ax":0.0, "ay":0.0, "alpha":-0.02273, "fx":[-0.08005,-0.02361,0.08005,0.02361], "fy":[0.02361,-0.08005,-0.02361,0.08005]}, + {"t":2.84627, "x":6.51901, "y":4.75075, "heading":-2.60758, "vx":-0.17504, "vy":-0.46823, "omega":0.85876, "ax":0.0, "ay":0.0, "alpha":-0.02602, "fx":[-0.09253,-0.02376,0.09253,0.02376], "fy":[0.02376,-0.09253,-0.02376,0.09253]}, + {"t":2.88752, "x":6.51179, "y":4.73143, "heading":-2.57215, "vx":-0.17504, "vy":-0.46823, "omega":0.85769, "ax":0.0, "ay":0.0, "alpha":-0.02976, "fx":[-0.10671,-0.02341,0.10671,0.02341], "fy":[0.02341,-0.10671,-0.02341,0.10671]}, + {"t":2.92877, "x":6.50457, "y":4.71212, "heading":-2.53677, "vx":-0.17504, "vy":-0.46823, "omega":0.85646, "ax":0.0, "ay":0.0, "alpha":-0.034, "fx":[-0.12279,-0.02242,0.12279,0.02242], "fy":[0.02242,-0.12279,-0.02242,0.12279]}, + {"t":2.97002, "x":6.49735, "y":4.6928, "heading":-2.50144, "vx":-0.17504, "vy":-0.46823, "omega":0.85506, "ax":0.0, "ay":0.0, "alpha":-0.03883, "fx":[-0.14103,-0.02063,0.14103,0.02063], "fy":[0.02063,-0.14103,-0.02063,0.14103]}, + {"t":3.01127, "x":6.49013, "y":4.67349, "heading":-2.46617, "vx":-0.17504, "vy":-0.46823, "omega":0.85345, "ax":0.0, "ay":0.0, "alpha":-0.04431, "fx":[-0.16169,-0.01785,0.16169,0.01785], "fy":[0.01785,-0.16169,-0.01785,0.16169]}, + {"t":3.05252, "x":6.48291, "y":4.65417, "heading":-2.43097, "vx":-0.17504, "vy":-0.46823, "omega":0.85163, "ax":0.0, "ay":0.0, "alpha":-0.05055, "fx":[-0.18506,-0.01386,0.18506,0.01386], "fy":[0.01386,-0.18506,-0.01386,0.18506]}, + {"t":3.09377, "x":6.47569, "y":4.63486, "heading":-2.39584, "vx":-0.17504, "vy":-0.46823, "omega":0.84954, "ax":0.0, "ay":0.0, "alpha":-0.05766, "fx":[-0.21149,-0.00839,0.21149,0.00839], "fy":[0.00839,-0.21149,-0.00839,0.21149]}, + {"t":3.13502, "x":6.46847, "y":4.61554, "heading":-2.36079, "vx":-0.17504, "vy":-0.46823, "omega":0.84716, "ax":0.0, "ay":0.0, "alpha":-0.06574, "fx":[-0.24135,-0.00111,0.24135,0.00111], "fy":[0.00111,-0.24135,-0.00111,0.24135]}, + {"t":3.17627, "x":6.46125, "y":4.59623, "heading":-2.32585, "vx":-0.17504, "vy":-0.46823, "omega":0.84445, "ax":0.0, "ay":0.0, "alpha":-0.07495, "fx":[-0.27503,0.00835,0.27503,-0.00835], "fy":[-0.00835,-0.27503,0.00835,0.27503]}, + {"t":3.21752, "x":6.45403, "y":4.57691, "heading":-2.29101, "vx":-0.17504, "vy":-0.46823, "omega":0.84136, "ax":0.0, "ay":0.0, "alpha":-0.08544, "fx":[-0.31298,0.02043,0.31298,-0.02043], "fy":[-0.02043,-0.31298,0.02043,0.31298]}, + {"t":3.25877, "x":6.44681, "y":4.5576, "heading":-2.25631, "vx":-0.17504, "vy":-0.46823, "omega":0.83783, "ax":0.0, "ay":0.0, "alpha":-0.09738, "fx":[-0.35571,0.03565,0.35571,-0.03565], "fy":[-0.03565,-0.35571,0.03565,0.35571]}, + {"t":3.30002, "x":6.43959, "y":4.53828, "heading":-2.22175, "vx":-0.17504, "vy":-0.46823, "omega":0.83382, "ax":0.0, "ay":0.0, "alpha":-0.11098, "fx":[-0.40375,0.05461,0.40375,-0.05461], "fy":[-0.05461,-0.40375,0.05461,0.40375]}, + {"t":3.34127, "x":6.43237, "y":4.51897, "heading":-2.18735, "vx":-0.17504, "vy":-0.46823, "omega":0.82924, "ax":0.0, "ay":0.0, "alpha":-0.12648, "fx":[-0.4577,0.07802,0.4577,-0.07802], "fy":[-0.07802,-0.4577,0.07802,0.4577]}, + {"t":3.38252, "x":6.42515, "y":4.49965, "heading":-2.15315, "vx":-0.17504, "vy":-0.46823, "omega":0.82402, "ax":0.0, "ay":0.0, "alpha":-0.14412, "fx":[-0.51821,0.10669,0.51821,-0.10669], "fy":[-0.10669,-0.51821,0.10669,0.51821]}, + {"t":3.42377, "x":6.41793, "y":4.48034, "heading":-2.11915, "vx":-0.17504, "vy":-0.46823, "omega":0.81808, "ax":0.0, "ay":0.0, "alpha":-0.16422, "fx":[-0.58602,0.14157,0.58602,-0.14157], "fy":[-0.14157,-0.58602,0.14157,0.58602]}, + {"t":3.46503, "x":6.41071, "y":4.46102, "heading":-2.08541, "vx":-0.17504, "vy":-0.46823, "omega":0.8113, "ax":0.0, "ay":0.0, "alpha":-0.18712, "fx":[-0.66189,0.18374,0.66189,-0.18374], "fy":[-0.18374,-0.66189,0.18374,0.66189]}, + {"t":3.50628, "x":6.40348, "y":4.44171, "heading":-2.05194, "vx":-0.17504, "vy":-0.46823, "omega":0.80358, "ax":0.0, "ay":0.0, "alpha":-0.2132, "fx":[-0.74671,0.23447,0.74671,-0.23447], "fy":[-0.23447,-0.74671,0.23447,0.74671]}, + {"t":3.54753, "x":6.39626, "y":4.4224, "heading":-2.01879, "vx":-0.17504, "vy":-0.46823, "omega":0.79479, "ax":0.0, "ay":0.0, "alpha":-0.2429, "fx":[-0.84142,0.29518,0.84142,-0.29518], "fy":[-0.29518,-0.84142,0.29518,0.84142]}, + {"t":3.58878, "x":6.38904, "y":4.40308, "heading":-1.98601, "vx":-0.17504, "vy":-0.46823, "omega":0.78477, "ax":0.0, "ay":0.0, "alpha":-0.27673, "fx":[-0.94707,0.36754,0.94707,-0.36754], "fy":[-0.36754,-0.94707,0.36754,0.94707]}, + {"t":3.63003, "x":6.38182, "y":4.38377, "heading":-1.95364, "vx":-0.17504, "vy":-0.46823, "omega":0.77335, "ax":0.0, "ay":0.0, "alpha":-0.31525, "fx":[-1.06481,0.45341,1.06481,-0.45341], "fy":[-0.45341,-1.06481,0.45341,1.06481]}, + {"t":3.67128, "x":6.3746, "y":4.36445, "heading":-1.92174, "vx":-0.17504, "vy":-0.46823, "omega":0.76035, "ax":0.0, "ay":0.0, "alpha":-0.35913, "fx":[-1.1959,0.55493,1.1959,-0.55493], "fy":[-0.55493,-1.1959,0.55493,1.1959]}, + {"t":3.71253, "x":6.36738, "y":4.34514, "heading":-1.89037, "vx":-0.17504, "vy":-0.46823, "omega":0.74554, "ax":0.0, "ay":0.0, "alpha":-0.40909, "fx":[-1.34177,0.67454,1.34177,-0.67454], "fy":[-0.67454,-1.34177,0.67454,1.34177]}, + {"t":3.75378, "x":6.36016, "y":4.32582, "heading":-1.85962, "vx":-0.17504, "vy":-0.46823, "omega":0.72866, "ax":0.0, "ay":0.0, "alpha":-0.46597, "fx":[-1.50399,0.81496,1.50399,-0.81496], "fy":[-0.81496,-1.50399,0.81496,1.50399]}, + {"t":3.79503, "x":6.35294, "y":4.30651, "heading":-1.82956, "vx":-0.17504, "vy":-0.46823, "omega":0.70944, "ax":0.0, "ay":0.0, "alpha":-0.53073, "fx":[-1.68433,0.97928,1.68433,-0.97928], "fy":[-0.97928,-1.68433,0.97928,1.68433]}, + {"t":3.83628, "x":6.34572, "y":4.28719, "heading":-1.8003, "vx":-0.17504, "vy":-0.46823, "omega":0.68755, "ax":0.0, "ay":0.0, "alpha":-0.60444, "fx":[-1.88481,1.17094,1.88481,-1.17094], "fy":[-1.17094,-1.88481,1.17094,1.88481]}, + {"t":3.87753, "x":6.3385, "y":4.26788, "heading":-1.77193, "vx":-0.17504, "vy":-0.46823, "omega":0.66261, "ax":0.0, "ay":0.0, "alpha":-0.68833, "fx":[-2.10773,1.39378,2.10773,-1.39378], "fy":[-1.39378,-2.10773,1.39378,2.10773]}, + {"t":3.91878, "x":6.33128, "y":4.24856, "heading":-1.7446, "vx":-0.17504, "vy":-0.46823, "omega":0.63422, "ax":0.0, "ay":0.0, "alpha":-0.78378, "fx":[-2.35575,1.65207,2.35575,-1.65207], "fy":[-1.65207,-2.35575,1.65207,2.35575]}, + {"t":3.96003, "x":6.32406, "y":4.22925, "heading":-1.71844, "vx":-0.17504, "vy":-0.46823, "omega":0.60189, "ax":0.0, "ay":0.0, "alpha":-0.89237, "fx":[-2.63199,1.95046,2.63199,-1.95046], "fy":[-1.95046,-2.63199,1.95046,2.63199]}, + {"t":4.00128, "x":6.31684, "y":4.20993, "heading":-1.69361, "vx":-0.17504, "vy":-0.46823, "omega":0.56508, "ax":0.0, "ay":0.0, "alpha":-1.01585, "fx":[-2.94017,2.29407,2.94017,-2.29407], "fy":[-2.29407,-2.94017,2.29407,2.94017]}, + {"t":4.04253, "x":6.30962, "y":4.19062, "heading":-1.6703, "vx":-0.17504, "vy":-0.46823, "omega":0.52317, "ax":0.0, "ay":0.0, "alpha":-1.15624, "fx":[-3.28472,2.68839,3.28472,-2.68839], "fy":[-2.68839,-3.28472,2.68839,3.28472]}, + {"t":4.08378, "x":6.3024, "y":4.1713, "heading":-1.64872, "vx":-0.17504, "vy":-0.46823, "omega":0.47548, "ax":0.0, "ay":0.0, "alpha":-1.31577, "fx":[-3.67104,3.13927,3.67104,-3.13927], "fy":[-3.13927,-3.67104,3.13927,3.67104]}, + {"t":4.12503, "x":6.29518, "y":4.15199, "heading":-1.62911, "vx":-0.17504, "vy":-0.46823, "omega":0.4212, "ax":0.0, "ay":0.0, "alpha":-1.49696, "fx":[-4.10572,3.6528,4.10572,-3.6528], "fy":[-3.6528,-4.10572,3.6528,4.10572]}, + {"t":4.16628, "x":6.28796, "y":4.13267, "heading":-1.61173, "vx":-0.17504, "vy":-0.46823, "omega":0.35945, "ax":0.0, "ay":0.0, "alpha":-1.70263, "fx":[-4.59692,4.23516,4.59692,-4.23516], "fy":[-4.23516,-4.59692,4.23516,4.59692]}, + {"t":4.20753, "x":6.28074, "y":4.11336, "heading":-1.5969, "vx":-0.17504, "vy":-0.46823, "omega":0.28922, "ax":0.0, "ay":0.0, "alpha":-1.93591, "fx":[-5.15477,4.89239,5.15477,-4.89239], "fy":[-4.89239,-5.15477,4.89239,5.15477]}, + {"t":4.24878, "x":6.27352, "y":4.09405, "heading":-1.58497, "vx":-0.17504, "vy":-0.46823, "omega":0.20936, "ax":0.0, "ay":0.0, "alpha":-2.20026, "fx":[-5.7919,5.62994,5.7919,-5.62994], "fy":[-5.62994,-5.7919,5.62994,5.7919]}, + {"t":4.29003, "x":6.2663, "y":4.07473, "heading":-1.57634, "vx":-0.17504, "vy":-0.46823, "omega":0.1186, "ax":0.00001, "ay":0.00004, "alpha":-2.49948, "fx":[-6.52384,6.45241,6.52433,-6.45192], "fy":[-6.45152,-6.52343,6.45282,6.52473]}, + {"t":4.33128, "x":6.25908, "y":4.05542, "heading":-1.57145, "vx":-0.17504, "vy":-0.46823, "omega":0.0155, "ax":1.98576, "ay":5.3119, "alpha":-0.36994, "fx":[32.7258,35.7972,34.79591,31.78972], "fy":[90.45156,89.45402,90.28179,91.22851]}, + {"t":4.37253, "x":6.25354, "y":4.04062, "heading":-1.57081, "vx":-0.09313, "vy":-0.24911, "omega":0.00024, "ax":2.25759, "ay":6.03905, "alpha":-0.00573, "fx":[38.38454,38.43666,38.41721,38.36512], "fy":[102.72848,102.70903,102.71641,102.73584]}, + {"t":4.41378, "x":6.25162, "y":4.03548, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/F_PATH_5.traj b/src/main/deploy/choreo/F_PATH_5.traj index 0ae9f4a8..53ac82e0 100644 --- a/src/main/deploy/choreo/F_PATH_5.traj +++ b/src/main/deploy/choreo/F_PATH_5.traj @@ -3,22 +3,24 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":5.218018531799316, "y":5.192361831665039, "heading":5.759586531581287, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":7.749877452850342, "y":6.150105953216553, "heading":1.5707963267948966, "intervals":37, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":6.090419769287109, "y":4.054448127746582, "heading":-1.5707963267948966, "intervals":66, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":7.010232925415039, "y":6.064763069152832, "heading":1.5707963267948966, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":1.0}}, "enabled":true}], "targetDt":0.05 }, "params":{ "waypoints":[ - {"x":{"exp":"5.218018531799316 m", "val":5.218018531799316}, "y":{"exp":"5.192361831665039 m", "val":5.192361831665039}, "heading":{"exp":"330 deg", "val":5.759586531581287}, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"7.749877452850342 m", "val":7.749877452850342}, "y":{"exp":"6.150105953216553 m", "val":6.150105953216553}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":37, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"6.090419769287109 m", "val":6.090419769287109}, "y":{"exp":"4.054448127746582 m", "val":4.054448127746582}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":66, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"7.010232925415039 m", "val":7.010232925415039}, "y":{"exp":"6.064763069152832 m", "val":6.064763069152832}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], + {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, + {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"1 m / s", "val":1.0}}}, "enabled":true}], "targetDt":{ "exp":"0.05 s", "val":0.05 @@ -26,50 +28,75 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,1.33553], + "waypoints":[0.0,2.36827], "samples":[ - {"t":0.0, "x":5.21802, "y":5.19236, "heading":-0.5236, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.68659, "ay":2.16829, "alpha":6.92679, "fx":[75.70755,98.44791,108.70287,104.05053], "fy":[79.43627,48.08191,-14.94123,34.95091]}, - {"t":0.03257, "x":5.22104, "y":5.19351, "heading":-0.5236, "vx":0.18523, "vy":0.07063, "omega":0.22563, "ax":5.69716, "ay":2.1681, "alpha":6.83238, "fx":[76.19772,98.59826,108.79826,104.03389], "fy":[78.95468,47.74257,-14.16168,34.97974]}, - {"t":0.06515, "x":5.23009, "y":5.19696, "heading":-0.51625, "vx":0.37081, "vy":0.14125, "omega":0.44819, "ax":5.71119, "ay":2.1654, "alpha":6.71072, "fx":[76.6391,99.09488,108.9196,103.92911], "fy":[78.51254,46.66857,-13.11618,35.26636]}, - {"t":0.09772, "x":5.2452, "y":5.20271, "heading":-0.50165, "vx":0.55685, "vy":0.21179, "omega":0.66679, "ax":5.72813, "ay":2.1608, "alpha":6.56423, "fx":[77.06326,99.87335,109.0599,103.73866], "fy":[78.07974,44.93888,-11.79595,35.796]}, - {"t":0.1303, "x":5.26638, "y":5.21076, "heading":-0.47993, "vx":0.74344, "vy":0.28217, "omega":0.88061, "ax":5.74731, "ay":2.15504, "alpha":6.3963, "fx":[77.51231,100.85297,109.21022,103.46499], "fy":[77.61403,42.64939,-10.18604,36.54884]}, - {"t":0.16287, "x":5.29364, "y":5.22109, "heading":-0.45125, "vx":0.93065, "vy":0.35237, "omega":1.08896, "ax":5.76808, "ay":2.14904, "alpha":6.20952, "fx":[78.04214,101.94114,109.35906,103.11156], "fy":[77.05699,39.92577,-8.26359,37.49887]}, - {"t":0.19544, "x":5.32702, "y":5.23371, "heading":-0.41577, "vx":1.11854, "vy":0.42238, "omega":1.29123, "ax":5.78996, "ay":2.14407, "alpha":6.00309, "fx":[78.72678,103.04013,109.49121,102.6843], "fy":[76.32749,36.9356,-5.99516,38.6119]}, - {"t":0.22802, "x":5.36653, "y":5.24861, "heading":-0.37371, "vx":1.30714, "vy":0.49222, "omega":1.48677, "ax":5.81285, "ay":2.14168, "alpha":5.76936, "fx":[79.66425,104.05576,109.58592,102.19395], "fy":[75.31117,33.89691,-3.33226,39.84193]}, - {"t":0.26059, "x":5.41219, "y":5.26578, "heading":-0.32528, "vx":1.49649, "vy":0.56198, "omega":1.6747, "ax":5.83729, "ay":2.14356, "alpha":5.48958, "fx":[80.98372,104.90566,109.61342,101.66002], "fy":[73.84294,31.08187,-0.2036,41.12447]}, - {"t":0.29317, "x":5.46403, "y":5.28522, "heading":-0.27073, "vx":1.68663, "vy":0.6318, "omega":1.85352, "ax":5.8646, "ay":2.15109, "alpha":5.12882, "fx":[82.85219,105.52253,109.52851,101.11773], "fy":[71.67834,28.81637,3.49907,42.36364]}, - {"t":0.32574, "x":5.52208, "y":5.30694, "heading":-0.21035, "vx":1.87766, "vy":0.70187, "omega":2.02059, "ax":5.89677, "ay":2.16467, "alpha":4.62995, "fx":[85.47487,105.84663,109.2569,100.63107], "fy":[68.44685,27.47997,7.94882,43.40577]}, - {"t":0.35831, "x":5.58637, "y":5.33095, "heading":-0.14454, "vx":2.06974, "vy":0.77238, "omega":2.1714, "ax":5.93564, "ay":2.18285, "alpha":3.90575, "fx":[89.07238,105.79986,108.66334,100.31875], "fy":[63.57996,27.51446,13.4436,43.98077]}, - {"t":0.39089, "x":5.65694, "y":5.35727, "heading":-0.07381, "vx":2.26309, "vy":0.84349, "omega":2.29863, "ax":5.98036, "ay":2.20128, "alpha":2.82619, "fx":[93.7921,105.22994,107.46459,100.41019], "fy":[56.21852,29.45133,20.54965,43.55297]}, - {"t":0.42346, "x":5.73383, "y":5.38591, "heading":0.00107, "vx":2.4579, "vy":0.91519, "omega":2.39069, "ax":6.01987, "ay":2.21171, "alpha":1.18567, "fx":[99.46852,103.79897,104.94216,101.37535], "fy":[45.16422,33.96588,30.48919,40.86302]}, - {"t":0.45603, "x":5.81709, "y":5.4169, "heading":0.07894, "vx":2.65399, "vy":0.98724, "omega":2.42931, "ax":6.0083, "ay":2.19698, "alpha":-1.45284, "fx":[105.15092,100.75878,98.71007,104.1778], "fy":[29.13917,41.93593,46.32535,32.07929]}, - {"t":0.48861, "x":5.90673, "y":5.45022, "heading":0.15808, "vx":2.8497, "vy":1.0588, "omega":2.38198, "ax":5.71802, "ay":2.0351, "alpha":-6.86002, "fx":[108.68129,94.56623,77.56378,108.2365], "fy":[8.06108,54.27401,75.89434,0.23663]}, - {"t":0.52118, "x":6.00259, "y":5.48579, "heading":0.23567, "vx":3.03596, "vy":1.12509, "omega":2.15853, "ax":5.04762, "ay":1.80487, "alpha":-12.59735, "fx":[108.78357,87.78405,46.92441,99.94238], "fy":[0.22831,64.34287,97.07954,-38.84971]}, - {"t":0.55376, "x":6.10416, "y":5.5234, "heading":0.30598, "vx":3.20038, "vy":1.18388, "omega":1.74818, "ax":4.69417, "ay":1.96558, "alpha":-14.12077, "fx":[108.29833,82.1571,32.20349,96.72716], "fy":[4.61032,70.81818,102.02499,-43.71752]}, - {"t":0.58633, "x":6.2109, "y":5.563, "heading":0.36292, "vx":3.35329, "vy":1.24791, "omega":1.28821, "ax":4.33368, "ay":1.88663, "alpha":-15.83756, "fx":[107.53569,78.26056,19.73888,89.32329], "fy":[5.0197,74.01286,103.29642,-53.96478]}, - {"t":0.6189, "x":6.32243, "y":5.60465, "heading":0.40489, "vx":3.49445, "vy":1.30937, "omega":0.77232, "ax":4.2312, "ay":1.91464, "alpha":-15.02764, "fx":[105.03051,75.57147,20.57547,86.70861], "fy":[7.39097,73.38713,97.66379,-48.17169]}, - {"t":0.65148, "x":6.4385, "y":5.64832, "heading":0.43004, "vx":3.63228, "vy":1.37173, "omega":0.28281, "ax":-2.10553, "ay":1.40638, "alpha":4.72168, "fx":[-49.61013,-44.52574,-20.45323,-28.66841], "fy":[28.13527,5.82958,19.99998,41.72354]}, - {"t":0.68405, "x":6.5557, "y":5.69375, "heading":0.43926, "vx":3.56369, "vy":1.41754, "omega":0.43662, "ax":-4.46689, "ay":-1.59583, "alpha":14.61465, "fx":[-105.7764,-80.02552,-33.09454,-85.0259], "fy":[-2.05956,-68.86578,-93.18081,55.52776]}, - {"t":0.71663, "x":6.66942, "y":5.73908, "heading":0.45348, "vx":3.41819, "vy":1.36556, "omega":0.91267, "ax":-4.63823, "ay":-1.87754, "alpha":14.26732, "fx":[-107.57885,-79.80322,-35.19989,-92.99791], "fy":[-6.76594,-72.3425,-98.45922,49.8221]}, - {"t":0.7492, "x":6.7783, "y":5.78256, "heading":0.48321, "vx":3.2671, "vy":1.3044, "omega":1.37742, "ax":-4.75875, "ay":-2.08758, "alpha":13.48651, "fx":[-107.90296,-78.94263,-38.78634,-98.14816], "fy":[-11.19279,-74.33274,-99.08733,42.57643]}, - {"t":0.78177, "x":6.8822, "y":5.82395, "heading":0.52808, "vx":3.11209, "vy":1.2364, "omega":1.81672, "ax":-4.84913, "ay":-2.27341, "alpha":12.64609, "fx":[-107.69482,-77.69709,-42.78531,-101.75215], "fy":[-15.69654,-76.14192,-98.38165,35.54]}, - {"t":0.81435, "x":6.981, "y":5.86301, "heading":0.58725, "vx":2.95414, "vy":1.16235, "omega":2.22866, "ax":-4.94052, "ay":-2.43962, "alpha":11.67527, "fx":[-107.12433,-76.35768,-48.21531,-104.44996], "fy":[-20.37301,-77.77639,-96.39485,28.55507]}, - {"t":0.84692, "x":7.0746, "y":5.89958, "heading":0.65985, "vx":2.79321, "vy":1.08288, "omega":2.60897, "ax":-5.70656, "ay":-2.55347, "alpha":4.66557, "fx":[-104.4003,-87.69918,-88.1737,-107.9949], "fy":[-31.82925,-64.88837,-63.5183,-13.49922]}, - {"t":0.8795, "x":7.16256, "y":5.9335, "heading":0.74483, "vx":2.60732, "vy":0.9997, "omega":2.76094, "ax":-5.90487, "ay":-2.51604, "alpha":0.33412, "fx":[-100.8623,-99.58362,-100.01694,-101.29743], "fy":[-41.86252,-44.80291,-43.77677,-40.74602]}, - {"t":0.91207, "x":7.24436, "y":5.96473, "heading":0.83477, "vx":2.41498, "vy":0.91775, "omega":2.77183, "ax":-5.9064, "ay":-2.45158, "alpha":-2.12547, "fx":[-98.44363,-105.80838,-102.72051,-94.89205], "fy":[-47.37596,-27.44471,-37.62302,-54.35928]}, - {"t":0.94464, "x":7.31989, "y":5.99332, "heading":0.92506, "vx":2.22258, "vy":0.83789, "omega":2.70259, "ax":-5.86278, "ay":-2.39678, "alpha":-3.69628, "fx":[-97.54483,-108.42428,-103.31928,-89.60825], "fy":[-49.27558,-14.64443,-36.29347,-62.86056]}, - {"t":0.97722, "x":7.38918, "y":6.01935, "heading":1.01309, "vx":2.03161, "vy":0.75982, "omega":2.58219, "ax":-5.81531, "ay":-2.35456, "alpha":-4.7069, "fx":[-98.09569,-109.32207,-103.1374,-85.11177], "fy":[-48.23009,-6.03047,-37.01511,-68.92593]}, - {"t":1.00979, "x":7.45227, "y":6.04285, "heading":1.0972, "vx":1.84218, "vy":0.68312, "omega":2.42887, "ax":-5.77714, "ay":-2.31552, "alpha":-5.38134, "fx":[-99.77282,-109.54829,-102.57232,-81.17643], "fy":[-44.71437,-0.56077,-38.68638,-73.58355]}, - {"t":1.04237, "x":7.50921, "y":6.06387, "heading":1.17632, "vx":1.654, "vy":0.60769, "omega":2.25357, "ax":-5.74876, "ay":-2.27135, "alpha":-5.88854, "fx":[-102.09942,-109.56303,-101.79229,-77.68428], "fy":[-39.17605,2.72532,-40.78441,-77.3049]}, - {"t":1.07494, "x":7.56004, "y":6.08246, "heading":1.24973, "vx":1.46674, "vy":0.53371, "omega":2.06176, "ax":-5.72546, "ay":-2.21918, "alpha":-6.34332, "fx":[-104.54672,-109.53931,-100.89091,-74.57688], "fy":[-32.16468,4.54158,-43.02929,-80.33841]}, - {"t":1.10751, "x":7.60478, "y":6.09867, "heading":1.31689, "vx":1.28024, "vy":0.46142, "omega":1.85514, "ax":-5.70193, "ay":-2.16143, "alpha":-6.80626, "fx":[-106.66431,-109.52957,-99.93257,-71.8263], "fy":[-24.36113,5.38756,-45.25693,-82.83065]}, - {"t":1.14009, "x":7.64346, "y":6.11255, "heading":1.37732, "vx":1.0945, "vy":0.39101, "omega":1.63343, "ax":-5.675, "ay":-2.10346, "alpha":-7.29038, "fx":[-108.19184,-109.54095,-98.96865,-69.41878], "fy":[-16.48924,5.61272,-47.36308,-84.87738]}, - {"t":1.17266, "x":7.6761, "y":6.12417, "heading":1.43052, "vx":0.90964, "vy":0.3225, "omega":1.39595, "ax":-5.64446, "ay":-2.05068, "alpha":-7.77719, "fx":[-109.08731,-109.56651,-98.04382,-67.34513], "fy":[-9.16992,5.46764,-49.27659,-86.54737]}, - {"t":1.20524, "x":7.70273, "y":6.13359, "heading":1.476, "vx":0.72578, "vy":0.2557, "omega":1.14262, "ax":-5.61233, "ay":-2.00649, "alpha":-8.23648, "fx":[-109.46552,-109.59728,-97.19833,-65.59521], "fy":[-2.81658,5.13759,-50.9462,-87.89427]}, - {"t":1.23781, "x":7.7234, "y":6.14085, "heading":1.51322, "vx":0.54297, "vy":0.19034, "omega":0.87432, "ax":-5.58142, "ay":-1.97176, "alpha":-8.64127, "fx":[-109.50314,-109.62637,-96.46818,-64.15552], "fy":[2.37694,4.76259,-52.3338,-88.96229]}, - {"t":1.27038, "x":7.73812, "y":6.14601, "heading":1.5417, "vx":0.36116, "vy":0.12611, "omega":0.59284, "ax":-5.55433, "ay":-1.94552, "alpha":-8.97397, "fx":[-109.36694,-109.64959,-95.88455,-63.00944], "fy":[6.37887,4.4493,-53.41093,-89.78849]}, - {"t":1.30296, "x":7.74694, "y":6.14908, "heading":1.56101, "vx":0.18023, "vy":0.06274, "omega":0.30053, "ax":-5.53301, "ay":-1.92595, "alpha":-9.226, "fx":[-109.1826,-109.66479,-95.47298,-62.13938], "fy":[9.24197,4.27813,-54.15638,-90.40309]}, - {"t":1.33553, "x":7.74988, "y":6.15011, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":6.09042, "y":4.05445, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":2.684, "ay":5.86606, "alpha":0.01271, "fx":[45.68364,45.57468,45.62444,45.73347], "fy":[99.76655,99.8163,99.79341,99.74356]}, + {"t":0.03588, "x":6.09215, "y":4.05822, "heading":-1.5708, "vx":0.09631, "vy":0.21049, "omega":0.00046, "ax":2.68292, "ay":5.8637, "alpha":0.01555, "fx":[45.67188,45.53863,45.59945,45.73281], "fy":[99.72344,99.78424,99.7562,99.69525]}, + {"t":0.07177, "x":6.09733, "y":4.06955, "heading":-1.57078, "vx":0.19258, "vy":0.4209, "omega":0.00101, "ax":2.68076, "ay":5.85898, "alpha":0.02122, "fx":[45.6484,45.46663,45.5495,45.73147], "fy":[99.63732,99.72016,99.6818,99.59869]}, + {"t":0.10765, "x":6.10597, "y":4.08843, "heading":-1.57074, "vx":0.28877, "vy":0.63113, "omega":0.00178, "ax":2.67431, "ay":5.84485, "alpha":0.03824, "fx":[45.57814,45.25141,45.39988,45.72723], "fy":[99.38002,99.52835,99.4588,99.3096]}, + {"t":0.14353, "x":6.11805, "y":4.11484, "heading":-1.57068, "vx":0.38474, "vy":0.84086, "omega":0.00315, "ax":0.86977, "ay":1.90112, "alpha":5.47495, "fx":[27.94398,-0.38502,-0.45072,32.06958], "fy":[44.25745,46.84103,19.94891,18.30252]}, + {"t":0.17941, "x":6.13242, "y":4.14623, "heading":-1.57057, "vx":0.41595, "vy":0.90908, "omega":0.1996, "ax":0.00006, "ay":0.00001, "alpha":6.00985, "fx":[15.59793,-15.60314,-15.59599,15.6051], "fy":[15.60419,15.5971,-15.60406,-15.59682]}, + {"t":0.2153, "x":6.14734, "y":4.17885, "heading":-1.5634, "vx":0.41595, "vy":0.90908, "omega":0.41525, "ax":0.0, "ay":0.0, "alpha":5.37587, "fx":[13.85135,-14.05759,-13.85128,14.05765], "fy":[14.0576,13.8513,-14.05763,-13.85133]}, + {"t":0.25118, "x":6.16227, "y":4.21147, "heading":-1.5485, "vx":0.41595, "vy":0.90908, "omega":0.60816, "ax":0.0, "ay":0.0, "alpha":4.79692, "fx":[12.17133,-12.72645,-12.17133,12.72645], "fy":[12.72645,12.17133,-12.72645,-12.17133]}, + {"t":0.28706, "x":6.17719, "y":4.2441, "heading":-1.52668, "vx":0.41595, "vy":0.90908, "omega":0.78028, "ax":0.0, "ay":0.0, "alpha":4.27093, "fx":[10.58691,-11.56476,-10.58691,11.56475], "fy":[11.56475,10.58691,-11.56476,-10.58691]}, + {"t":0.32295, "x":6.19212, "y":4.27672, "heading":-1.49868, "vx":0.41595, "vy":0.90908, "omega":0.93354, "ax":0.0, "ay":0.0, "alpha":3.79521, "fx":[9.11629,-10.53594,-9.11629,10.53594], "fy":[10.53594,9.11629,-10.53594,-9.11629]}, + {"t":0.35883, "x":6.20704, "y":4.30934, "heading":-1.46518, "vx":0.41595, "vy":0.90908, "omega":1.06972, "ax":0.0, "ay":0.0, "alpha":3.3666, "fx":[7.76919,-9.61165,-7.76919,9.61165], "fy":[9.61165,7.76919,-9.61165,-7.76919]}, + {"t":0.39471, "x":6.22197, "y":4.34196, "heading":-1.4268, "vx":0.41595, "vy":0.90908, "omega":1.19052, "ax":0.0, "ay":0.0, "alpha":2.98169, "fx":[6.54918,-8.77053,-6.54918,8.77053], "fy":[8.77053,6.54918,-8.77053,-6.54918]}, + {"t":0.43059, "x":6.23689, "y":4.37458, "heading":-1.38408, "vx":0.41595, "vy":0.90908, "omega":1.29751, "ax":0.0, "ay":0.0, "alpha":2.63698, "fx":[5.4555,-7.99686,-5.4555,7.99686], "fy":[7.99686,5.4555,-7.99686,-5.4555]}, + {"t":0.46648, "x":6.25182, "y":4.4072, "heading":-1.33752, "vx":0.41595, "vy":0.90908, "omega":1.39214, "ax":0.0, "ay":0.0, "alpha":2.32896, "fx":[4.48431,-7.27935,-4.48431,7.27935], "fy":[7.27935,4.48431,-7.27935,-4.48431]}, + {"t":0.50236, "x":6.26674, "y":4.43982, "heading":-1.28757, "vx":0.41595, "vy":0.90908, "omega":1.47571, "ax":0.0, "ay":0.0, "alpha":2.05422, "fx":[3.62977,-6.61011,-3.62977,6.61011], "fy":[6.61011,3.62977,-6.61011,-3.62977]}, + {"t":0.53824, "x":6.28167, "y":4.47244, "heading":-1.23462, "vx":0.41595, "vy":0.90908, "omega":1.54942, "ax":0.0, "ay":0.0, "alpha":1.80949, "fx":[2.88469,-5.98369,-2.88468,5.9837], "fy":[5.98369,2.88468,-5.9837,-2.88469]}, + {"t":0.57413, "x":6.2966, "y":4.50506, "heading":-1.17902, "vx":0.41595, "vy":0.90908, "omega":1.61435, "ax":0.0, "ay":0.0, "alpha":1.59171, "fx":[2.24109,-5.3964,-2.24109,5.3964], "fy":[5.3964,2.24109,-5.3964,-2.24109]}, + {"t":0.61001, "x":6.31152, "y":4.53768, "heading":-1.12109, "vx":0.41595, "vy":0.90908, "omega":1.67146, "ax":0.0, "ay":0.0, "alpha":1.39801, "fx":[1.69066,-4.84571,-1.69066,4.84571], "fy":[4.84571,1.69066,-4.84571,-1.69066]}, + {"t":0.64589, "x":6.32645, "y":4.5703, "heading":-1.06111, "vx":0.41595, "vy":0.90908, "omega":1.72163, "ax":0.0, "ay":0.0, "alpha":1.22574, "fx":[1.225,-4.32981,-1.225,4.32982], "fy":[4.32982,1.225,-4.32982,-1.225]}, + {"t":0.68177, "x":6.34137, "y":4.60292, "heading":-0.99934, "vx":0.41595, "vy":0.90908, "omega":1.76561, "ax":0.0, "ay":0.0, "alpha":1.07248, "fx":[0.8359,-3.84736,-0.83589,3.84736], "fy":[3.84736,0.83589,-3.84736,-0.8359]}, + {"t":0.71766, "x":6.3563, "y":4.63554, "heading":-0.93598, "vx":0.41595, "vy":0.90908, "omega":1.80409, "ax":0.0, "ay":0.0, "alpha":0.93599, "fx":[0.51547,-3.39718,-0.51546,3.39718], "fy":[3.39718,0.51546,-3.39718,-0.51547]}, + {"t":0.75354, "x":6.37122, "y":4.66816, "heading":-0.87125, "vx":0.41595, "vy":0.90908, "omega":1.83768, "ax":0.0, "ay":0.0, "alpha":0.81426, "fx":[0.2563,-2.97817,-0.2563,2.97817], "fy":[2.97817,0.2563,-2.97817,-0.2563]}, + {"t":0.78942, "x":6.38615, "y":4.70078, "heading":-0.80531, "vx":0.41595, "vy":0.90908, "omega":1.8669, "ax":0.0, "ay":0.0, "alpha":0.70544, "fx":[0.05155,-2.5892,-0.05155,2.5892], "fy":[2.5892,0.05155,-2.5892,-0.05155]}, + {"t":0.82531, "x":6.40107, "y":4.7334, "heading":-0.73832, "vx":0.41595, "vy":0.90908, "omega":1.89221, "ax":0.0, "ay":0.0, "alpha":0.60788, "fx":[-0.10503,-2.22909,0.10503,2.22908], "fy":[2.22908,-0.10503,-2.22908,0.10503]}, + {"t":0.86119, "x":6.416, "y":4.76602, "heading":-0.67042, "vx":0.41595, "vy":0.90908, "omega":1.91402, "ax":0.0, "ay":0.0, "alpha":0.52005, "fx":[-0.21903,-1.89654,0.21903,1.89654], "fy":[1.89654,-0.21903,-1.89654,0.21903]}, + {"t":0.89707, "x":6.43092, "y":4.79864, "heading":-0.60174, "vx":0.41595, "vy":0.90908, "omega":1.93268, "ax":0.0, "ay":0.0, "alpha":0.4406, "fx":[-0.2954,-1.59025,0.29539,1.59024], "fy":[1.59025,-0.29539,-1.59025,0.2954]}, + {"t":0.93295, "x":6.44585, "y":4.83126, "heading":-0.53239, "vx":0.41595, "vy":0.90908, "omega":1.94849, "ax":0.0, "ay":0.0, "alpha":0.36825, "fx":[-0.3384,-1.30883,0.3384,1.30883], "fy":[1.30883,-0.3384,-1.30883,0.3384]}, + {"t":0.96884, "x":6.46077, "y":4.86388, "heading":-0.46247, "vx":0.41595, "vy":0.90908, "omega":1.96171, "ax":0.0, "ay":0.0, "alpha":0.30187, "fx":[-0.35168,-1.05092,0.35168,1.05091], "fy":[1.05092,-0.35168,-1.05091,0.35168]}, + {"t":1.00472, "x":6.4757, "y":4.8965, "heading":-0.39208, "vx":0.41595, "vy":0.90908, "omega":1.97254, "ax":0.0, "ay":0.0, "alpha":0.24041, "fx":[-0.33825,-0.81518,0.33825,0.81517], "fy":[0.81518,-0.33825,-0.81517,0.33825]}, + {"t":1.0406, "x":6.49062, "y":4.92912, "heading":-0.3213, "vx":0.41595, "vy":0.90908, "omega":1.98117, "ax":0.0, "ay":0.0, "alpha":0.18288, "fx":[-0.30052,-0.60036,0.30051,0.60035], "fy":[0.60036,-0.30052,-0.60035,0.30052]}, + {"t":1.07649, "x":6.50555, "y":4.96174, "heading":-0.25021, "vx":0.41595, "vy":0.90908, "omega":1.98773, "ax":0.0, "ay":0.0, "alpha":0.12836, "fx":[-0.24033,-0.40534,0.24032,0.40533], "fy":[0.40533,-0.24033,-0.40533,0.24033]}, + {"t":1.11237, "x":6.52048, "y":4.99436, "heading":-0.17888, "vx":0.41595, "vy":0.90908, "omega":1.99233, "ax":0.0, "ay":0.0, "alpha":0.07597, "fx":[-0.15898,-0.22916,0.15898,0.22916], "fy":[0.22916,-0.15898,-0.22916,0.15898]}, + {"t":1.14825, "x":6.5354, "y":5.02699, "heading":-0.10739, "vx":0.41595, "vy":0.90908, "omega":1.99506, "ax":0.0, "ay":0.0, "alpha":0.02487, "fx":[-0.05727,-0.0711,0.05726,0.0711], "fy":[0.0711,-0.05726,-0.0711,0.05726]}, + {"t":1.18413, "x":6.55033, "y":5.05961, "heading":-0.0358, "vx":0.41595, "vy":0.90908, "omega":1.99595, "ax":0.0, "ay":0.0, "alpha":-0.02578, "fx":[0.06449,0.06929,-0.06449,-0.06928], "fy":[-0.06929,0.06449,0.06929,-0.06449]}, + {"t":1.22002, "x":6.56525, "y":5.09223, "heading":0.03582, "vx":0.41595, "vy":0.90908, "omega":1.99503, "ax":0.0, "ay":0.0, "alpha":-0.07682, "fx":[0.20642,0.19214,-0.20641,-0.19213], "fy":[-0.19214,0.20642,0.19213,-0.20642]}, + {"t":1.2559, "x":6.58018, "y":5.12485, "heading":0.1074, "vx":0.41595, "vy":0.90908, "omega":1.99227, "ax":0.0, "ay":0.0, "alpha":-0.12907, "fx":[0.36902,0.29719,-0.36902,-0.29719], "fy":[-0.29719,0.36902,0.29719,-0.36902]}, + {"t":1.29178, "x":6.5951, "y":5.15747, "heading":0.17889, "vx":0.41595, "vy":0.90908, "omega":1.98764, "ax":0.0, "ay":0.0, "alpha":-0.1834, "fx":[0.55318,0.38376,-0.55318,-0.38376], "fy":[-0.38376,0.55318,0.38376,-0.55318]}, + {"t":1.32767, "x":6.61003, "y":5.19009, "heading":0.25022, "vx":0.41595, "vy":0.90908, "omega":1.98106, "ax":0.0, "ay":0.0, "alpha":-0.2407, "fx":[0.76008,0.45066,-0.76008,-0.45065], "fy":[-0.45065,0.76008,0.45065,-0.76008]}, + {"t":1.36355, "x":6.62495, "y":5.22271, "heading":0.3213, "vx":0.41595, "vy":0.90908, "omega":1.97242, "ax":0.0, "ay":0.0, "alpha":-0.30193, "fx":[0.99116,0.49614,-0.99115,-0.49613], "fy":[-0.49614,0.99115,0.49613,-0.99116]}, + {"t":1.39943, "x":6.63988, "y":5.25533, "heading":0.39208, "vx":0.41595, "vy":0.90908, "omega":1.96159, "ax":0.0, "ay":0.0, "alpha":-0.36807, "fx":[1.24805,0.51787,-1.24804,-0.51786], "fy":[-0.51787,1.24804,0.51787,-1.24805]}, + {"t":1.43531, "x":6.6548, "y":5.28795, "heading":0.46246, "vx":0.41595, "vy":0.90908, "omega":1.94838, "ax":0.0, "ay":0.0, "alpha":-0.44022, "fx":[1.53253,0.51286,-1.53253,-0.51286], "fy":[-0.51286,1.53253,0.51286,-1.53253]}, + {"t":1.4712, "x":6.66973, "y":5.32057, "heading":0.53238, "vx":0.41595, "vy":0.90908, "omega":1.93258, "ax":0.0, "ay":0.0, "alpha":-0.51952, "fx":[1.84646,0.47742,-1.84646,-0.47742], "fy":[-0.47742,1.84646,0.47742,-1.84646]}, + {"t":1.50708, "x":6.68465, "y":5.35319, "heading":0.60172, "vx":0.41595, "vy":0.90908, "omega":1.91394, "ax":0.0, "ay":0.0, "alpha":-0.60724, "fx":[2.19172,0.40715,-2.19172,-0.40715], "fy":[-0.40715,2.19172,0.40715,-2.19172]}, + {"t":1.54296, "x":6.69958, "y":5.38581, "heading":0.6704, "vx":0.41595, "vy":0.90908, "omega":1.89215, "ax":0.0, "ay":0.0, "alpha":-0.70476, "fx":[2.57013,0.29686,-2.57013,-0.29686], "fy":[-0.29686,2.57013,0.29686,-2.57013]}, + {"t":1.57885, "x":6.71451, "y":5.41843, "heading":0.7383, "vx":0.41595, "vy":0.90908, "omega":1.86686, "ax":0.0, "ay":0.0, "alpha":-0.81359, "fx":[2.98342,0.14062,-2.98342,-0.14062], "fy":[-0.14062,2.98342,0.14062,-2.98342]}, + {"t":1.61473, "x":6.72943, "y":5.45105, "heading":0.80529, "vx":0.41595, "vy":0.90908, "omega":1.83767, "ax":0.0, "ay":0.0, "alpha":-0.93538, "fx":[3.43317,-0.06829,-3.43317,0.06829], "fy":[0.06829,3.43317,-0.06829,-3.43317]}, + {"t":1.65061, "x":6.74436, "y":5.48367, "heading":0.87123, "vx":0.41595, "vy":0.90908, "omega":1.80411, "ax":0.0, "ay":0.0, "alpha":-1.07198, "fx":[3.9208,-0.33735,-3.9208,0.33735], "fy":[0.33735,3.9208,-0.33735,-3.9208]}, + {"t":1.68649, "x":6.75928, "y":5.51629, "heading":0.93596, "vx":0.41595, "vy":0.90908, "omega":1.76564, "ax":0.0, "ay":0.0, "alpha":-1.22537, "fx":[4.4475,-0.67475,-4.44751,0.67475], "fy":[0.67475,4.44751,-0.67475,-4.4475]}, + {"t":1.72238, "x":6.77421, "y":5.54891, "heading":0.99932, "vx":0.41595, "vy":0.90908, "omega":1.72167, "ax":0.0, "ay":0.0, "alpha":-1.39777, "fx":[5.01434,-1.08935,-5.01434,1.08935], "fy":[1.08935,5.01434,-1.08935,-5.01434]}, + {"t":1.75826, "x":6.78913, "y":5.58153, "heading":1.0611, "vx":0.41595, "vy":0.90908, "omega":1.67151, "ax":0.0, "ay":0.0, "alpha":-1.5916, "fx":[5.62221,-1.59055,-5.62221,1.59055], "fy":[1.59055,5.62221,-1.59055,-5.62221]}, + {"t":1.79414, "x":6.80406, "y":5.61415, "heading":1.12108, "vx":0.41595, "vy":0.90908, "omega":1.6144, "ax":0.0, "ay":0.0, "alpha":-1.8095, "fx":[6.27201,-2.1882,-6.27202,2.1882], "fy":[2.1882,6.27202,-2.1882,-6.27201]}, + {"t":1.83003, "x":6.81898, "y":5.64677, "heading":1.17901, "vx":0.41595, "vy":0.90908, "omega":1.54947, "ax":0.0, "ay":0.0, "alpha":-2.05431, "fx":[6.96481,-2.89234,-6.96481,2.89234], "fy":[2.89234,6.96481,-2.89234,-6.96481]}, + {"t":1.86591, "x":6.83391, "y":5.67939, "heading":1.23461, "vx":0.41595, "vy":0.90908, "omega":1.47576, "ax":0.0, "ay":0.0, "alpha":-2.32912, "fx":[7.70205,-3.713,-7.70205,3.713], "fy":[3.713,7.70205,-3.713,-7.70205]}, + {"t":1.90179, "x":6.84883, "y":5.71201, "heading":1.28756, "vx":0.41595, "vy":0.90908, "omega":1.39218, "ax":0.0, "ay":0.0, "alpha":-2.63717, "fx":[8.486,-4.65978,-8.486,4.65978], "fy":[4.65978,8.486,-4.65978,-8.486]}, + {"t":1.93767, "x":6.86376, "y":5.74463, "heading":1.33752, "vx":0.41595, "vy":0.90908, "omega":1.29755, "ax":0.0, "ay":0.0, "alpha":-2.98189, "fx":[9.32018,-5.74145,-9.32018,5.74145], "fy":[5.74145,9.32018,-5.74145,-9.32018]}, + {"t":1.97356, "x":6.87868, "y":5.77725, "heading":1.38408, "vx":0.41595, "vy":0.90908, "omega":1.19056, "ax":0.0, "ay":0.0, "alpha":-3.36678, "fx":[10.21008,-6.9653,-10.21008,6.9653], "fy":[6.9653,10.21008,-6.9653,-10.21008]}, + {"t":2.00944, "x":6.89361, "y":5.80988, "heading":1.4268, "vx":0.41595, "vy":0.90908, "omega":1.06975, "ax":0.0, "ay":0.0, "alpha":-3.79537, "fx":[11.16397,-8.33636,-11.16397,8.33636], "fy":[8.33636,11.16397,-8.33636,-11.16397]}, + {"t":2.04532, "x":6.90854, "y":5.8425, "heading":1.46518, "vx":0.41595, "vy":0.90908, "omega":0.93356, "ax":0.0, "ay":0.0, "alpha":-4.27106, "fx":[12.19393,-9.85641,-12.19393,9.85641], "fy":[9.85641,12.19393,-9.85641,-12.19393]}, + {"t":2.08121, "x":6.92346, "y":5.87512, "heading":1.49868, "vx":0.41595, "vy":0.90908, "omega":0.7803, "ax":0.0, "ay":0.0, "alpha":-4.79701, "fx":[13.31706,-11.52263,-13.31707,11.52263], "fy":[11.52263,13.31707,-11.52263,-13.31706]}, + {"t":2.11709, "x":6.93839, "y":5.90774, "heading":1.52668, "vx":0.41595, "vy":0.90908, "omega":0.60817, "ax":0.0, "ay":0.0, "alpha":-5.37592, "fx":[14.55681,-13.326,-14.55687,13.32593], "fy":[13.32598,14.55685,-13.32595,-14.55682]}, + {"t":2.15297, "x":6.95331, "y":5.94036, "heading":1.5485, "vx":0.41595, "vy":0.90908, "omega":0.41527, "ax":-0.00006, "ay":-0.00001, "alpha":-6.00986, "fx":[15.94348,-15.24993,-15.94543,15.24796], "fy":[15.24888,15.94431,-15.24901,-15.9446]}, + {"t":2.18885, "x":6.96824, "y":5.97298, "heading":1.5634, "vx":0.41595, "vy":0.90908, "omega":0.19961, "ax":-0.86976, "ay":-1.90112, "alpha":-5.47524, "fx":[0.58313,-31.97651,-28.05656,0.27214], "fy":[-20.07299,-18.19721,-44.16108,-46.91863]}, + {"t":2.22474, "x":6.9826, "y":6.00437, "heading":1.57057, "vx":0.38474, "vy":0.84086, "omega":0.00315, "ax":-2.67431, "ay":-5.84485, "alpha":-0.03824, "fx":[-45.39982,-45.72721,-45.57821,-45.25144], "fy":[-99.45883,-99.30961,-99.37999,-99.52834]}, + {"t":2.26062, "x":6.99469, "y":6.03078, "heading":1.57068, "vx":0.28877, "vy":0.63113, "omega":0.00178, "ax":-2.68076, "ay":-5.85898, "alpha":-0.02122, "fx":[-45.54949,-45.73146,-45.64842,-45.46663], "fy":[-99.68181,-99.5987,-99.63732,-99.72016]}, + {"t":2.2965, "x":7.00332, "y":6.04966, "heading":1.57074, "vx":0.19258, "vy":0.4209, "omega":0.00101, "ax":-2.68292, "ay":-5.8637, "alpha":-0.01555, "fx":[-45.59945,-45.73281,-45.67189,-45.53863], "fy":[-99.7562,-99.69525,-99.72343,-99.78424]}, + {"t":2.33239, "x":7.0085, "y":6.06099, "heading":1.57078, "vx":0.09631, "vy":0.21049, "omega":0.00046, "ax":-2.684, "ay":-5.86606, "alpha":-0.01271, "fx":[-45.62444,-45.73348,-45.68364,-45.57467], "fy":[-99.79341,-99.74356,-99.76655,-99.8163]}, + {"t":2.36827, "x":7.01023, "y":6.06476, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/F_PATH_6.traj b/src/main/deploy/choreo/F_PATH_6.traj deleted file mode 100644 index 91304e23..00000000 --- a/src/main/deploy/choreo/F_PATH_6.traj +++ /dev/null @@ -1,85 +0,0 @@ -{ - "name":"F_PATH_6", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":7.749877452850342, "y":6.150105953216553, "heading":1.5707963267948966, "intervals":50, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":5.483531951904297, "y":2.3855068683624268, "heading":3.7000980142279785, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"7.749877452850342 m", "val":7.749877452850342}, "y":{"exp":"6.150105953216553 m", "val":6.150105953216553}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":50, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"5.483531951904297 m", "val":5.483531951904297}, "y":{"exp":"2.3855068683624268 m", "val":2.3855068683624268}, "heading":{"exp":"212 deg", "val":3.7000980142279785}, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.76157], - "samples":[ - {"t":0.0, "x":7.74988, "y":6.15011, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-3.00145, "ay":-5.17869, "alpha":7.93235, "fx":[-65.00331,-11.39395,-29.78674,-98.03113], "fy":[-88.45565,-109.15778,-105.44631,-49.29264]}, - {"t":0.03523, "x":7.74801, "y":6.14689, "heading":1.5708, "vx":-0.10575, "vy":-0.18245, "omega":0.27947, "ax":-3.02123, "ay":-5.18552, "alpha":7.79174, "fx":[-64.94125,-12.10486,-30.92944,-97.58557], "fy":[-88.493,-109.07314,-105.10216,-50.14821]}, - {"t":0.07046, "x":7.74241, "y":6.13725, "heading":1.58064, "vx":-0.21219, "vy":-0.36515, "omega":0.55398, "ax":-3.04882, "ay":-5.19523, "alpha":7.58032, "fx":[-64.5611,-12.68975,-33.23583,-96.95167], "fy":[-88.76122,-108.9968,-104.37834,-51.34128]}, - {"t":0.10569, "x":7.73305, "y":6.12116, "heading":1.60016, "vx":-0.3196, "vy":-0.54818, "omega":0.82105, "ax":-3.08331, "ay":-5.20694, "alpha":7.30784, "fx":[-63.87851,-13.21673,-36.57862,-96.11084], "fy":[-89.24261,-108.92213,-103.23419,-52.87552]}, - {"t":0.14093, "x":7.71987, "y":6.09861, "heading":1.62909, "vx":-0.42823, "vy":-0.73163, "omega":1.07851, "ax":-3.12343, "ay":-5.21957, "alpha":6.98779, "fx":[-62.91554,-13.78354,-40.78029,-95.03509], "fy":[-89.91093,-108.83706,-101.62503,-54.76054]}, - {"t":0.17616, "x":7.70285, "y":6.0696, "heading":1.66708, "vx":-0.53827, "vy":-0.91552, "omega":1.3247, "ax":-3.16728, "ay":-5.23238, "alpha":6.63467, "fx":[-61.70332,-14.52762,-45.58332,-93.684], "fy":[-90.73127,-108.72183,-99.53843,-57.0136]}, - {"t":0.21139, "x":7.68192, "y":6.03409, "heading":1.71375, "vx":-0.64986, "vy":-1.09986, "omega":1.55845, "ax":-3.21235, "ay":-5.2456, "alpha":6.25813, "fx":[-60.2867,-15.64255,-50.63595,-91.99918], "fy":[-91.65912,-108.54383,-97.03923,-59.66279]}, - {"t":0.24662, "x":7.65703, "y":5.99209, "heading":1.76866, "vx":-0.76304, "vy":-1.28467, "omega":1.77893, "ax":-3.25604, "ay":-5.26092, "alpha":5.853, "fx":[-58.73276,-17.40466,-55.50579,-89.89393], "fy":[-92.63778,-108.24556,-94.31071,-62.75314]}, - {"t":0.28185, "x":7.62812, "y":5.94356, "heading":1.83134, "vx":-0.87775, "vy":-1.47002, "omega":1.98514, "ax":-3.29686, "ay":-5.28137, "alpha":5.38639, "fx":[-57.14786,-20.21466,-59.71922,-87.233], "fy":[-93.59136,-107.7175,-91.67186,-66.35759]}, - {"t":0.31708, "x":7.59515, "y":5.88849, "heading":1.90127, "vx":-0.9939, "vy":-1.65609, "omega":2.17491, "ax":-3.3358, "ay":-5.31018, "alpha":4.78347, "fx":[-55.71365,-24.65706,-62.80252,-83.79082], "fy":[-94.4076,-106.73691,-89.55679,-70.59751]}, - {"t":0.35231, "x":7.55807, "y":5.82685, "heading":1.9779, "vx":-1.11143, "vy":-1.84318, "omega":2.34344, "ax":-3.37709, "ay":-5.34801, "alpha":3.91272, "fx":[-54.77029,-31.56156,-64.28703,-79.15477], "fy":[-94.89275,-104.83363,-88.46227,-75.68355]}, - {"t":0.38754, "x":7.51681, "y":5.7586, "heading":2.06046, "vx":-1.23041, "vy":-2.0316, "omega":2.48129, "ax":-3.42628, "ay":-5.38725, "alpha":2.5678, "fx":[-55.03444,-41.97272,-63.64561,-72.46712], "fy":[-94.63481,-101.02214,-88.88302,-82.00268]}, - {"t":0.42278, "x":7.47134, "y":5.68368, "heading":2.14788, "vx":-1.35112, "vy":-2.2214, "omega":2.57176, "ax":-3.47935, "ay":-5.40014, "alpha":0.42655, "fx":[-58.29152,-56.69898,-60.14102,-61.59941], "fy":[-92.46686,-93.42804,-91.23853,-90.28621]}, - {"t":0.45801, "x":7.42158, "y":5.60206, "heading":2.23849, "vx":-1.4737, "vy":-2.41165, "omega":2.58678, "ax":-3.49091, "ay":-5.2908, "alpha":-3.23529, "fx":[-70.19163,-74.80988,-52.59927,-39.91705], "fy":[-83.28841,-79.5104,-95.71884,-101.46223]}, - {"t":0.49324, "x":7.36749, "y":5.51381, "heading":2.32962, "vx":-1.59669, "vy":-2.59805, "omega":2.4728, "ax":-3.28718, "ay":-4.52051, "alpha":-11.09388, "fx":[-101.47982,-90.22117,-40.39226,8.43733], "fy":[-36.70332,-61.29212,-101.38449,-108.19069]}, - {"t":0.52847, "x":7.3092, "y":5.41947, "heading":2.41674, "vx":-1.7125, "vy":-2.75732, "omega":2.08195, "ax":-3.04742, "ay":-4.39402, "alpha":-12.72622, "fx":[-104.16682,-88.68168,-34.02355,19.52906], "fy":[-26.10932,-63.1505,-103.47564,-106.22893]}, - {"t":0.5637, "x":7.24697, "y":5.3196, "heading":2.49009, "vx":-1.81987, "vy":-2.91212, "omega":1.63359, "ax":-2.77272, "ay":-4.33545, "alpha":-13.8355, "fx":[-104.39267,-86.17872,-27.56499,29.48371], "fy":[-21.01747,-65.92491,-105.00332,-103.03342]}, - {"t":0.59893, "x":7.18113, "y":5.21431, "heading":2.54765, "vx":-1.91755, "vy":-3.06487, "omega":1.14614, "ax":-2.43277, "ay":-4.22411, "alpha":-15.02823, "fx":[-103.18919,-83.21948,-20.43435,41.32042], "fy":[-16.08373,-68.39268,-105.84884,-97.07853]}, - {"t":0.63416, "x":7.11207, "y":5.10371, "heading":2.58803, "vx":-2.00326, "vy":-3.21369, "omega":0.61668, "ax":-2.21023, "ay":-3.99987, "alpha":-15.38664, "fx":[-97.82992,-80.42513,-16.79244,44.66622], "fy":[-10.90378,-67.78276,-103.9601,-89.50026]}, - {"t":0.6694, "x":7.04012, "y":4.98801, "heading":2.60975, "vx":-2.08113, "vy":-3.35461, "omega":0.07459, "ax":0.53416, "ay":-0.96553, "alpha":-1.84387, "fx":[7.52672,2.38835,10.65163,15.77683], "fy":[-9.94537,-18.32386,-22.76707,-14.65696]}, - {"t":0.70463, "x":6.96713, "y":4.86922, "heading":2.61238, "vx":-2.06231, "vy":-3.38863, "omega":0.00962, "ax":0.27123, "ay":-0.16606, "alpha":-0.00415, "fx":[4.60966,4.59879,4.61733,4.62822], "fy":[-2.80991,-2.82853,-2.83938,-2.82076]}, - {"t":0.73986, "x":6.89464, "y":4.74973, "heading":2.61272, "vx":-2.05276, "vy":-3.39448, "omega":0.00948, "ax":0.08736, "ay":-0.05278, "alpha":0.0, "fx":[1.48602,1.48601,1.48602,1.48603], "fy":[-0.89777,-0.89778,-0.89779,-0.89778]}, - {"t":0.77509, "x":6.82237, "y":4.63011, "heading":2.61305, "vx":-2.04968, "vy":-3.39634, "omega":0.00948, "ax":0.02808, "ay":-0.01694, "alpha":0.0, "fx":[0.4777,0.4777,0.4777,0.4777], "fy":[-0.28819,-0.28819,-0.28819,-0.28819]}, - {"t":0.81032, "x":6.75018, "y":4.51044, "heading":2.61339, "vx":-2.04869, "vy":-3.39693, "omega":0.00948, "ax":0.0093, "ay":-0.00561, "alpha":0.0, "fx":[0.15826,0.15826,0.15827,0.15827], "fy":[-0.09544,-0.09544,-0.09545,-0.09544]}, - {"t":0.84555, "x":6.678, "y":4.39076, "heading":2.61372, "vx":-2.04836, "vy":-3.39713, "omega":0.00948, "ax":0.00395, "ay":-0.00238, "alpha":0.0, "fx":[0.0672,0.0672,0.06721,0.06721], "fy":[-0.04052,-0.04053,-0.04053,-0.04052]}, - {"t":0.88078, "x":6.60584, "y":4.27107, "heading":2.61406, "vx":-2.04822, "vy":-3.39721, "omega":0.00948, "ax":0.0043, "ay":-0.00259, "alpha":0.0, "fx":[0.07306,0.07305,0.07306,0.07307], "fy":[-0.04404,-0.04405,-0.04406,-0.04405]}, - {"t":0.91601, "x":6.53368, "y":4.15138, "heading":2.61439, "vx":-2.04807, "vy":-3.39731, "omega":0.00948, "ax":0.01083, "ay":-0.00653, "alpha":0.0, "fx":[0.18429,0.18429,0.18429,0.1843], "fy":[-0.11108,-0.11109,-0.11109,-0.11109]}, - {"t":0.95125, "x":6.46153, "y":4.03169, "heading":2.61472, "vx":-2.04769, "vy":-3.39754, "omega":0.00948, "ax":0.03302, "ay":-0.01989, "alpha":0.0, "fx":[0.56161,0.56162,0.56161,0.5616], "fy":[-0.33835,-0.33834,-0.33834,-0.33834]}, - {"t":0.98648, "x":6.38941, "y":3.91197, "heading":2.61506, "vx":-2.04653, "vy":-3.39824, "omega":0.00948, "ax":0.10289, "ay":-0.06188, "alpha":0.00003, "fx":[1.75013,1.75021,1.75007,1.75], "fy":[-1.05265,-1.05251,-1.05244,-1.05257]}, - {"t":1.02171, "x":6.31737, "y":3.79221, "heading":2.61539, "vx":-2.0429, "vy":-3.40042, "omega":0.00948, "ax":0.32194, "ay":-0.18996, "alpha":0.00757, "fx":[5.48323,5.50302,5.46915,5.44934], "fy":[-3.25805,-3.22398,-3.20431,-3.23838]}, - {"t":1.05694, "x":6.2456, "y":3.67229, "heading":2.61572, "vx":-2.03156, "vy":-3.40711, "omega":0.00974, "ax":1.41152, "ay":0.24638, "alpha":3.17589, "fx":[27.26657,34.50207,21.19378,13.07611], "fy":[-7.54394,7.05038,16.10335,1.15346]}, - {"t":1.09217, "x":6.1749, "y":3.55241, "heading":2.61607, "vx":-1.98183, "vy":-3.39843, "omega":0.12164, "ax":2.5145, "ay":3.85102, "alpha":15.42282, "fx":[100.83295,84.21921,22.25285,-36.22155], "fy":[2.57861,63.8437,103.18193,92.41451]}, - {"t":1.1274, "x":6.10663, "y":3.43507, "heading":2.62035, "vx":-1.89324, "vy":-3.26275, "omega":0.665, "ax":2.58238, "ay":4.12287, "alpha":15.15327, "fx":[105.06806,84.41975,21.97504,-35.76083], "fy":[9.1853,67.1421,105.55678,98.63108]}, - {"t":1.16263, "x":6.04154, "y":3.32267, "heading":2.64378, "vx":-1.80226, "vy":-3.1175, "omega":1.19887, "ax":2.5518, "ay":4.41373, "alpha":14.17555, "fx":[104.9829,81.71461,19.95888,-33.03506], "fy":[20.62238,71.46634,106.68777,101.52874]}, - {"t":1.19787, "x":5.97962, "y":3.21558, "heading":2.68602, "vx":-1.71236, "vy":-2.962, "omega":1.6983, "ax":2.49368, "ay":4.68133, "alpha":13.07129, "fx":[103.0455,78.20075,17.56897,-29.14839], "fy":[31.66942,75.78806,107.45652,103.59845]}, - {"t":1.2331, "x":5.92084, "y":3.11413, "heading":2.74585, "vx":-1.6245, "vy":-2.79707, "omega":2.15882, "ax":2.46849, "ay":4.95772, "alpha":11.56657, "fx":[99.35033,73.98895,15.79161,-21.17743], "fy":[43.19335,80.18166,107.93033,106.01237]}, - {"t":1.26833, "x":5.86514, "y":3.01866, "heading":2.82191, "vx":-1.53753, "vy":-2.6224, "omega":2.56632, "ax":2.98843, "ay":5.5801, "alpha":3.40721, "fx":[69.93286,61.61747,35.6752,36.10379], "fy":[83.57991,90.15242,103.17762,102.75351]}, - {"t":1.30356, "x":5.81283, "y":2.92974, "heading":2.91233, "vx":-1.43225, "vy":-2.42581, "omega":2.68636, "ax":3.10934, "ay":5.62022, "alpha":-0.47353, "fx":[50.28697,51.37128,55.55826,54.33922], "fy":[97.03332,96.43492,94.09371,94.83112]}, - {"t":1.33879, "x":5.7643, "y":2.84776, "heading":3.00697, "vx":-1.3227, "vy":-2.2278, "omega":2.66968, "ax":3.12942, "ay":5.55819, "alpha":-2.71763, "fx":[38.49998,45.33087,69.61671,59.47465], "fy":[102.44199,99.47086,84.35816,91.9022]}, - {"t":1.37402, "x":5.71964, "y":2.77272, "heading":3.10103, "vx":-1.21245, "vy":-2.03197, "omega":2.57393, "ax":3.11706, "ay":5.48878, "alpha":-4.14583, "fx":[30.07399,42.97298,78.55293,60.48134], "fy":[105.31109,100.55024,76.23385,91.35526]}, - {"t":1.40925, "x":5.67886, "y":2.70454, "heading":-3.09148, "vx":-1.10263, "vy":-1.8386, "omega":2.42787, "ax":3.09849, "ay":5.43152, "alpha":-5.04638, "fx":[23.41177,43.67132,83.95907,59.77576], "fy":[107.04353,100.27776,70.34505,91.88794]}, - {"t":1.44449, "x":5.64193, "y":2.64313, "heading":-3.00594, "vx":-0.99347, "vy":-1.64724, "omega":2.25008, "ax":3.08788, "ay":5.38449, "alpha":-5.62324, "fx":[17.86773,46.80605,87.15297,58.26892], "fy":[108.14382,98.87772,66.43608,92.89725]}, - {"t":1.47972, "x":5.60885, "y":2.58844, "heading":-2.92667, "vx":-0.88468, "vy":-1.45753, "omega":2.05196, "ax":3.08997, "ay":5.34072, "alpha":-6.03349, "fx":[13.14301,51.71211,88.99176,56.39081], "fy":[108.8455,96.42601,64.02289,94.08205]}, - {"t":1.51495, "x":5.5796, "y":2.5404, "heading":-2.85437, "vx":-0.77581, "vy":-1.26937, "omega":1.8394, "ax":3.10288, "ay":5.29462, "alpha":-6.38629, "fx":[9.08342,57.65845,89.99619,54.37854], "fy":[109.27914,93.01782,62.65901,95.28363]}, - {"t":1.55018, "x":5.55419, "y":2.49897, "heading":-2.78957, "vx":-0.66649, "vy":-1.08284, "omega":1.6144, "ax":3.12133, "ay":5.24422, "alpha":-6.74215, "fx":[5.60192,63.90561,90.4843,52.37964], "fy":[109.52852,88.87045,61.9962,96.4156]}, - {"t":1.58541, "x":5.53265, "y":2.46407, "heading":-2.73269, "vx":-0.55652, "vy":-0.89808, "omega":1.37686, "ax":3.13964, "ay":5.19108, "alpha":-7.11814, "fx":[2.64445,69.81848,90.65874,50.49609], "fy":[109.65263,84.33652,61.77591,97.43001]}, - {"t":1.62064, "x":5.51499, "y":2.43565, "heading":-2.68418, "vx":-0.44591, "vy":-0.71519, "omega":1.12608, "ax":3.15404, "ay":5.13876, "alpha":-7.50078, "fx":[0.17296,74.96301,90.65669,48.80474], "fy":[109.69525,79.83283,61.80702,98.30004]}, - {"t":1.65587, "x":5.50123, "y":2.41365, "heading":-2.64451, "vx":-0.33479, "vy":-0.53414, "omega":0.86182, "ax":3.16332, "ay":5.09103, "alpha":-7.86277, "fx":[-1.84333,79.12842,90.57677,47.3669], "fy":[109.68944,75.74092,61.94679,99.01071]}, - {"t":1.6911, "x":5.4914, "y":2.39799, "heading":-2.61414, "vx":-0.22334, "vy":-0.35478, "omega":0.5848, "ax":3.16834, "ay":5.05069, "alpha":-8.17677, "fx":[-3.43186,82.27663,90.49294,46.2324], "fy":[109.65991,72.34203,62.08772,99.55378]}, - {"t":1.72634, "x":5.4855, "y":2.38862, "heading":-2.59354, "vx":-0.11172, "vy":-0.17684, "omega":0.29672, "ax":3.17094, "ay":5.01928, "alpha":-8.42218, "fx":[-4.61739,84.46237,90.46127,45.44104], "fy":[109.6245,69.80796,62.1491,99.92455]}, - {"t":1.76157, "x":5.48353, "y":2.38551, "heading":-2.58309, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/F_PATH_7.traj b/src/main/deploy/choreo/F_PATH_7.traj deleted file mode 100644 index 7ce234bf..00000000 --- a/src/main/deploy/choreo/F_PATH_7.traj +++ /dev/null @@ -1,79 +0,0 @@ -{ - "name":"F_PATH_7", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":5.483531951904297, "y":2.3855068683624268, "heading":3.7000980142279785, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":7.740394592285156, "y":4.784609317779541, "heading":1.5707963267948966, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"5.483531951904297 m", "val":5.483531951904297}, "y":{"exp":"2.3855068683624268 m", "val":2.3855068683624268}, "heading":{"exp":"212 deg", "val":3.7000980142279785}, "intervals":44, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"7.740394592285156 m", "val":7.740394592285156}, "y":{"exp":"4.784609317779541 m", "val":4.784609317779541}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":45, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.48526], - "samples":[ - {"t":0.0, "x":5.48353, "y":2.38551, "heading":-2.58309, "vx":0.0, "vy":0.0, "omega":0.0, "ax":4.0691, "ay":4.07779, "alpha":-10.17511, "fx":[13.52822,105.7504,99.29536,58.28315], "fy":[108.85541,28.81407,46.76423,93.01452]}, - {"t":0.03376, "x":5.48585, "y":2.38783, "heading":-2.58309, "vx":0.13736, "vy":0.13765, "omega":-0.34347, "ax":4.08039, "ay":4.1105, "alpha":-9.92156, "fx":[14.95102,105.17135,99.02134,58.48162], "fy":[108.65779,30.81017,47.32394,92.88163]}, - {"t":0.06751, "x":5.49281, "y":2.39482, "heading":-2.59468, "vx":0.27509, "vy":0.2764, "omega":-0.67838, "ax":4.09982, "ay":4.14849, "alpha":-9.57092, "fx":[16.7377,104.24325,98.85999,59.10607], "fy":[108.38545,33.75799,47.63874,92.47605]}, - {"t":0.10127, "x":5.50443, "y":2.40651, "heading":-2.61758, "vx":0.41349, "vy":0.41644, "omega":-1.00146, "ax":4.12523, "ay":4.19337, "alpha":-9.12064, "fx":[18.9131,102.85426,98.77876,60.12972], "fy":[108.01517,37.71349,47.781,91.80268]}, - {"t":0.13502, "x":5.52074, "y":2.42296, "heading":-2.65139, "vx":0.55274, "vy":0.55799, "omega":-1.30933, "ax":4.15372, "ay":4.24691, "alpha":-8.56987, "fx":[21.52336,100.84781,98.7285,61.51452], "fy":[107.5127,42.72211,47.85285,90.86735]}, - {"t":0.16878, "x":5.54177, "y":2.44421, "heading":-2.69558, "vx":0.69295, "vy":0.70135, "omega":-1.59862, "ax":4.18183, "ay":4.31003, "alpha":-7.92522, "fx":[24.63224,98.04574,98.63918,63.20958], "fy":[106.82897,48.74328,47.99707,89.68026]}, - {"t":0.20254, "x":5.56754, "y":2.47034, "heading":-2.74955, "vx":0.83411, "vy":0.84684, "omega":-1.86614, "ax":4.20632, "ay":4.38174, "alpha":-7.20467, "fx":[28.3201,94.31343,98.41086,65.14913], "fy":[105.89418,55.55938,48.41387,88.26086]}, - {"t":0.23629, "x":5.59809, "y":2.50143, "heading":-2.81254, "vx":0.9761, "vy":0.99475, "omega":-2.10934, "ax":4.2257, "ay":4.45849, "alpha":-6.43318, "fx":[32.68985,89.67801,97.8946,67.24906], "fy":[104.6069,62.71176,49.38701,86.64489]}, - {"t":0.27005, "x":5.63345, "y":2.53754, "heading":-2.88374, "vx":1.11874, "vy":1.14525, "omega":-2.3265, "ax":4.24165, "ay":4.53513, "alpha":-5.62253, "fx":[37.88472,84.46105,96.85165,69.3996], "fy":[102.81227,69.53292,51.32378,84.89609]}, - {"t":0.3038, "x":5.67363, "y":2.57879, "heading":-2.96227, "vx":1.26192, "vy":1.29833, "omega":-2.51629, "ax":4.25879, "ay":4.60761, "alpha":-4.73544, "fx":[44.12461,79.32583,94.86566,71.44701], "fy":[100.25513,75.30164,54.81043,83.12928]}, - {"t":0.33756, "x":5.71865, "y":2.62524, "heading":-3.04721, "vx":1.40568, "vy":1.45387, "omega":-2.67614, "ax":4.28046, "ay":4.67561, "alpha":-3.64559, "fx":[51.77434,75.16174,91.15809,73.14373], "fy":[96.47203,79.42814,60.65927,81.56344]}, - {"t":0.37131, "x":5.76854, "y":2.67698, "heading":-3.13755, "vx":1.55017, "vy":1.6117, "omega":-2.7992, "ax":4.30007, "ay":4.74003, "alpha":-2.10699, "fx":[61.4706,72.86244,84.24019,73.99887], "fy":[90.51487,81.51485,69.81368,80.66276]}, - {"t":0.40507, "x":5.82332, "y":2.73408, "heading":3.05115, "vx":1.69533, "vy":1.7717, "omega":-2.87032, "ax":4.28733, "ay":4.78573, "alpha":0.25893, "fx":[74.31747,73.13839,71.53163,72.71741], "fy":[80.14524,81.23711,82.64493,81.58851]}, - {"t":0.43883, "x":5.88299, "y":2.79662, "heading":2.95426, "vx":1.84005, "vy":1.93325, "omega":-2.86158, "ax":4.14879, "ay":4.73898, "alpha":4.01783, "fx":[91.5806,76.40598,50.28036,64.01176], "fy":[59.30462,78.13296,96.9307,88.06679]}, - {"t":0.47258, "x":5.94747, "y":2.86457, "heading":2.85766, "vx":1.98009, "vy":2.09322, "omega":-2.72596, "ax":3.353, "ay":4.45633, "alpha":10.89508, "fx":[107.25402,82.22066,25.29354,13.36613], "fy":[18.42043,71.92322,106.1527,106.70729]}, - {"t":0.50634, "x":6.01622, "y":2.93777, "heading":2.76564, "vx":2.09328, "vy":2.24364, "omega":-2.35818, "ax":3.30319, "ay":4.30238, "alpha":12.02434, "fx":[107.80105,85.4709,28.45723,3.0158], "fy":[12.53331,67.80788,105.20922,107.17874]}, - {"t":0.54009, "x":6.08876, "y":3.01596, "heading":2.68604, "vx":2.20478, "vy":2.38888, "omega":-1.95229, "ax":3.34209, "ay":4.14884, "alpha":12.64743, "fx":[107.79121,88.26137,32.24544,-0.90621], "fy":[7.90864,63.76914,103.88263,106.72191]}, - {"t":0.57385, "x":6.16509, "y":3.09896, "heading":2.62014, "vx":2.31759, "vy":2.52892, "omega":-1.52536, "ax":3.35632, "ay":3.95568, "alpha":13.39279, "fx":[107.32358,90.76015,35.272,-4.99527], "fy":[1.5418,59.501,102.49207,105.60539]}, - {"t":0.60761, "x":6.24523, "y":3.18658, "heading":2.56865, "vx":2.43089, "vy":2.66245, "omega":-1.07328, "ax":3.3556, "ay":3.71584, "alpha":14.08685, "fx":[105.68424,92.75183,37.90231,-8.02703], "fy":[-5.93269,54.89636,100.69176,103.16596]}, - {"t":0.64136, "x":6.3292, "y":3.27857, "heading":2.53242, "vx":2.54416, "vy":2.78788, "omega":-0.59776, "ax":3.34076, "ay":3.34833, "alpha":14.30544, "fx":[100.51336,93.34354,40.52994,-7.08546], "fy":[-13.72765,48.99995,96.84654,95.69791]}, - {"t":0.67512, "x":6.41698, "y":3.37459, "heading":2.51224, "vx":2.65693, "vy":2.90091, "omega":-0.11487, "ax":1.81717, "ay":-0.37382, "alpha":3.06543, "fx":[32.39433,41.02199,29.89525,20.32632], "fy":[-18.05089,-4.29512,5.71771,-8.80603]}, - {"t":0.70887, "x":6.50771, "y":3.4723, "heading":2.50836, "vx":2.71827, "vy":2.88829, "omega":-0.0114, "ax":0.37858, "ay":-0.35319, "alpha":0.01104, "fx":[6.44544,6.47963,6.43368,6.3995], "fy":[-6.04775,-6.00133,-5.9677,-6.01413]}, - {"t":0.74263, "x":6.59968, "y":3.56959, "heading":2.50798, "vx":2.73105, "vy":2.87637, "omega":-0.01102, "ax":-0.04307, "ay":0.04071, "alpha":-0.00042, "fx":[-0.73289,-0.73419,-0.73241,-0.73111], "fy":[0.69409,0.69231,0.69101,0.69278]}, - {"t":0.77639, "x":6.69184, "y":3.66671, "heading":2.50761, "vx":2.7296, "vy":2.87774, "omega":-0.01104, "ax":-0.53965, "ay":0.45784, "alpha":-0.11946, "fx":[-9.24025,-9.61259,-9.11845,-8.74569], "fy":[8.22121,7.71649,7.35399,7.85935]}, - {"t":0.81014, "x":6.78368, "y":3.76411, "heading":2.50723, "vx":2.71138, "vy":2.8932, "omega":-0.01507, "ax":-3.11176, "ay":-2.21957, "alpha":-11.67971, "fx":[-77.22549,-84.09319,-42.20817,-8.19368], "fy":[17.29431,-35.29756,-77.96533,-55.04871]}, - {"t":0.8439, "x":6.87343, "y":3.86051, "heading":2.50673, "vx":2.60634, "vy":2.81827, "omega":-0.40933, "ax":-3.25195, "ay":-3.50798, "alpha":-14.76257, "fx":[-102.55712,-93.41407,-39.06809,13.78026], "fy":[10.88714,-51.19999,-98.87043,-99.49579]}, - {"t":0.87765, "x":6.95956, "y":3.95364, "heading":2.49291, "vx":2.49657, "vy":2.69986, "omega":-0.90765, "ax":-3.18858, "ay":-3.65719, "alpha":-15.31538, "fx":[-105.6712,-93.91015,-37.55856,20.19268], "fy":[9.11117,-53.4948,-101.26418,-103.1833]}, - {"t":0.91141, "x":7.04201, "y":4.0427, "heading":2.46227, "vx":2.38894, "vy":2.57641, "omega":-1.42464, "ax":-3.10468, "ay":-3.67425, "alpha":-15.91351, "fx":[-106.68227,-94.35433,-36.62514,26.42291], "fy":[9.77417,-53.88568,-102.28104,-103.59918]}, - {"t":0.94517, "x":7.12088, "y":4.12757, "heading":2.41418, "vx":2.28413, "vy":2.45238, "omega":-1.96181, "ax":-3.70643, "ay":-4.3204, "alpha":-10.30505, "fx":[-104.15854,-91.39059,-45.62704,-11.00485], "fy":[-28.32828,-59.26797,-98.91761,-107.44101]}, - {"t":0.97892, "x":7.19588, "y":4.20789, "heading":2.34796, "vx":2.15902, "vy":2.30654, "omega":-2.30967, "ax":-4.23323, "ay":-4.75289, "alpha":-2.44156, "fx":[-81.58591,-80.94453,-64.58497,-60.9085], "fy":[-72.09369,-73.11179,-87.90997,-90.2656]}, - {"t":1.01268, "x":7.26634, "y":4.28304, "heading":2.26999, "vx":2.01612, "vy":2.1461, "omega":-2.39209, "ax":-4.31471, "ay":-4.75129, "alpha":0.64937, "fx":[-71.36446,-70.50862,-75.58302,-76.11184], "fy":[-82.71052,-83.39118,-78.81313,-78.35725]}, - {"t":1.04643, "x":7.33194, "y":4.35278, "heading":2.18925, "vx":1.87048, "vy":1.98572, "omega":-2.37016, "ax":-4.32004, "ay":-4.70275, "alpha":2.45783, "fx":[-67.54639,-61.26459,-81.70896,-83.41054], "fy":[-86.08026,-90.53277,-72.56631,-70.79018]}, - {"t":1.08019, "x":7.39262, "y":4.41713, "heading":2.10924, "vx":1.72465, "vy":1.82697, "omega":-2.2872, "ax":-4.30854, "ay":-4.64923, "alpha":3.6607, "fx":[-66.45012,-53.72557,-85.01272,-87.95949], "fy":[-87.05576,-95.30346,-68.76075,-65.20801]}, - {"t":1.11394, "x":7.44838, "y":4.47615, "heading":2.03203, "vx":1.57921, "vy":1.67003, "omega":-2.16363, "ax":-4.29646, "ay":-4.60018, "alpha":4.47897, "fx":[-66.64,-47.92162,-86.56445,-91.20035], "fy":[-86.99155,-98.42989,-66.86915,-60.70034]}, - {"t":1.1477, "x":7.49924, "y":4.52991, "heading":1.959, "vx":1.43418, "vy":1.51475, "omega":-2.01244, "ax":-4.28735, "ay":-4.55919, "alpha":5.03244, "fx":[-67.46416,-43.62752,-86.93593,-93.67872], "fy":[-86.41033,-100.4691,-66.44207,-56.88059]}, - {"t":1.18146, "x":7.54521, "y":4.57844, "heading":1.89107, "vx":1.28946, "vy":1.36085, "omega":-1.84256, "ax":-4.28043, "ay":-4.52734, "alpha":5.40535, "fx":[-68.58705,-40.53873,-86.46071,-95.64888], "fy":[-85.56327,-101.80323,-67.10474,-53.56353]}, - {"t":1.21521, "x":7.5863, "y":4.6218, "heading":1.82887, "vx":1.14497, "vy":1.20803, "omega":-1.6601, "ax":-4.27396, "ay":-4.50414, "alpha":5.66086, "fx":[-69.82098,-38.36297,-85.36227,-97.24935], "fy":[-84.5912,-102.68127,-68.53426,-50.65005]}, - {"t":1.24897, "x":7.62251, "y":4.66001, "heading":1.77283, "vx":1.0007, "vy":1.05598, "omega":-1.46901, "ax":-4.26656, "ay":-4.48823, "alpha":5.84532, "fx":[-71.0552,-36.85375,-83.81765,-98.56517], "fy":[-83.58238,-103.26318,-70.44723,-48.08143]}, - {"t":1.28272, "x":7.65386, "y":4.6931, "heading":1.72324, "vx":0.85667, "vy":0.90448, "omega":-1.2717, "ax":-4.25754, "ay":-4.47783, "alpha":5.99061, "fx":[-72.22189,-35.81508,-81.98763,-99.65338], "fy":[-82.59685,-103.65274,-72.59728,-45.81965]}, - {"t":1.31648, "x":7.68035, "y":4.72108, "heading":1.68031, "vx":0.71296, "vy":0.75333, "omega":-1.06948, "ax":-4.24693, "ay":-4.47116, "alpha":6.11644, "fx":[-73.27825,-35.09519,-80.02816,-100.55465], "fy":[-81.67812,-103.91889,-74.77731,-43.83824]}, - {"t":1.35024, "x":7.702, "y":4.74396, "heading":1.64421, "vx":0.5696, "vy":0.6024, "omega":-0.86301, "ax":-4.23529, "ay":-4.46667, "alpha":6.23298, "fx":[-74.19645,-34.57753,-78.09088,-101.29917], "fy":[-80.85927,-104.10893,-76.82138,-42.11782]}, - {"t":1.38399, "x":7.71882, "y":4.76175, "heading":1.61508, "vx":0.42663, "vy":0.45162, "omega":-0.65261, "ax":-4.22345, "ay":-4.46318, "alpha":6.34359, "fx":[-74.95764,-34.17254,-76.31878,-101.90992], "fy":[-80.16639,-104.2564,-78.60327,-40.64375]}, - {"t":1.41775, "x":7.73081, "y":4.77445, "heading":1.59305, "vx":0.28407, "vy":0.30096, "omega":-0.43848, "ax":-4.21237, "ay":-4.45984, "alpha":6.44754, "fx":[-75.54842,-33.81107,-74.84094,-102.40453], "fy":[-79.62047,-104.38577,-80.03092,-39.40499]}, - {"t":1.4515, "x":7.738, "y":4.78207, "heading":1.57825, "vx":0.14187, "vy":0.15042, "omega":-0.22084, "ax":-4.20294, "ay":-4.45605, "alpha":6.54221, "fx":[-75.95866,-33.43949,-73.76884,-102.79646], "fy":[-79.23844,-104.51515,-81.03776,-38.39344]}, - {"t":1.48526, "x":7.74039, "y":4.78461, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/deploy/choreo/F_PATH_8.traj b/src/main/deploy/choreo/F_PATH_8.traj deleted file mode 100644 index cef87d7d..00000000 --- a/src/main/deploy/choreo/F_PATH_8.traj +++ /dev/null @@ -1,70 +0,0 @@ -{ - "name":"F_PATH_8", - "version":1, - "snapshot":{ - "waypoints":[ - {"x":7.740394592285156, "y":4.784609317779541, "heading":1.5707963267948966, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":6.061971664428711, "y":6.538893699645996, "heading":0.6108652381980153, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}], - "targetDt":0.05 - }, - "params":{ - "waypoints":[ - {"x":{"exp":"7.740394592285156 m", "val":7.740394592285156}, "y":{"exp":"4.784609317779541 m", "val":4.784609317779541}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":35, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"6.061971664428711 m", "val":6.061971664428711}, "y":{"exp":"6.538893699645996 m", "val":6.538893699645996}, "heading":{"exp":"35 deg", "val":0.6108652381980153}, "intervals":39, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], - "constraints":[ - {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, - {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}], - "targetDt":{ - "exp":"0.05 s", - "val":0.05 - } - }, - "trajectory":{ - "sampleType":"Swerve", - "waypoints":[0.0,1.2349], - "samples":[ - {"t":0.0, "x":7.74039, "y":4.78461, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-4.39436, "ay":4.60526, "alpha":-3.42343, "fx":[-55.71731,-76.12844,-91.98002,-75.16139], "fy":[94.53786,79.06205,59.84323,79.89339]}, - {"t":0.03528, "x":7.73766, "y":4.78748, "heading":1.5708, "vx":-0.15505, "vy":0.16249, "omega":-0.12079, "ax":-4.39612, "ay":4.60655, "alpha":-3.37085, "fx":[-56.05497,-76.12234,-91.75752,-75.17216], "fy":[94.32835,79.05791,60.16853,79.86927]}, - {"t":0.07057, "x":7.72945, "y":4.79608, "heading":1.56653, "vx":-0.31015, "vy":0.32502, "omega":-0.23972, "ax":-4.39816, "ay":4.60792, "alpha":-3.3106, "fx":[-56.41835,-76.05305,-91.49063,-75.28401], "fy":[94.10021,79.1131,60.55647,79.74805]}, - {"t":0.10585, "x":7.71577, "y":4.81041, "heading":1.55808, "vx":-0.46533, "vy":0.4876, "omega":-0.35653, "ax":-4.40051, "ay":4.60943, "alpha":-3.24109, "fx":[-56.82181,-75.92451,-91.1724,-75.48689], "fy":[93.84399,79.22319,61.01522,79.53804]}, - {"t":0.14113, "x":7.69661, "y":4.83049, "heading":1.5455, "vx":-0.6206, "vy":0.65024, "omega":-0.47089, "ax":-4.40318, "ay":4.61111, "alpha":-3.16021, "fx":[-57.28453,-75.74174,-90.79304,-75.76812], "fy":[93.54674,79.38241,61.55622,79.24949]}, - {"t":0.17641, "x":7.67198, "y":4.8563, "heading":1.52888, "vx":-0.77596, "vy":0.81293, "omega":-0.58239, "ax":-4.40622, "ay":4.61302, "alpha":-3.06507, "fx":[-57.83202,-75.51133,-90.33897,-76.11159], "fy":[93.19076,79.58319,62.19515,78.89565]}, - {"t":0.2117, "x":7.64186, "y":4.88785, "heading":1.50833, "vx":-0.93142, "vy":0.97569, "omega":-0.69053, "ax":-4.40966, "ay":4.61522, "alpha":-2.95149, "fx":[-58.49842,-75.24233,-89.79114,-76.49663], "fy":[92.75153,79.81537,62.95345,78.49413]}, - {"t":0.24698, "x":7.60625, "y":4.92515, "heading":1.48397, "vx":-1.08701, "vy":1.13853, "omega":-0.79467, "ax":-4.4136, "ay":4.61779, "alpha":-2.81327, "fx":[-59.33004,-74.94762,-89.12227,-76.89628], "fy":[92.19428,80.06487,63.86092,78.06901]}, - {"t":0.28226, "x":7.56515, "y":4.96819, "heading":1.45593, "vx":-1.24273, "vy":1.30146, "omega":-0.89393, "ax":-4.41812, "ay":4.6208, "alpha":-2.64099, "fx":[-60.39127,-74.64637,-88.29184,-77.27463], "fy":[91.46818,80.31141,64.9603,77.65381]}, - {"t":0.31755, "x":7.51855, "y":5.01699, "heading":1.42439, "vx":-1.39862, "vy":1.4645, "omega":-0.98711, "ax":-4.42338, "ay":4.62429, "alpha":-2.41981, "fx":[-61.77444,-74.36845,-87.23639,-77.58226], "fy":[90.49546,80.52413,66.31583,77.29622]}, - {"t":0.35283, "x":7.46645, "y":5.07154, "heading":1.38956, "vx":-1.55469, "vy":1.62765, "omega":-1.07249, "ax":-4.42951, "ay":4.62822, "alpha":-2.1254, "fx":[-63.61763,-74.16335,-85.84972,-77.74814], "fy":[89.1505,80.65253,68.02992,77.06587]}, - {"t":0.38811, "x":7.40884, "y":5.13185, "heading":1.35172, "vx":-1.71097, "vy":1.79095, "omega":-1.14748, "ax":-4.43657, "ay":4.63218, "alpha":-1.71555, "fx":[-66.1382,-74.11971,-83.93771,-77.66382], "fy":[87.21537,80.60588,70.27871,77.06822]}, - {"t":0.4234, "x":7.34571, "y":5.19792, "heading":1.31124, "vx":-1.86751, "vy":1.95439, "omega":-1.20801, "ax":-4.44402, "ay":4.63472, "alpha":-1.11064, "fx":[-69.69996,-74.41512,-81.10155,-77.14944], "fy":[84.2761,80.19826,73.39488,77.47153]}, - {"t":0.45868, "x":7.27705, "y":5.26976, "heading":1.26861, "vx":-2.02431, "vy":2.11792, "omega":-1.2472, "ax":-4.4485, "ay":4.63065, "alpha":-0.14034, "fx":[-74.9538,-75.46924,-76.37523,-75.8727], "fy":[79.44675,78.96737,78.08588,78.56393]}, - {"t":0.49396, "x":7.20286, "y":5.34737, "heading":1.22461, "vx":-2.18126, "vy":2.2813, "omega":-1.25215, "ax":-4.43236, "ay":4.59732, "alpha":1.6436, "fx":[-83.10988,-78.58171,-66.75598,-73.1254], "fy":[70.51082,75.32368,86.07536,80.88666]}, - {"t":0.52924, "x":7.12314, "y":5.43073, "heading":1.18043, "vx":-2.33765, "vy":2.44351, "omega":-1.19416, "ax":-4.28828, "ay":4.34634, "alpha":6.04079, "fx":[-95.90217,-90.34065,-38.42755,-67.09952], "fy":[50.87151,58.17748,101.12466,85.54624]}, - {"t":0.56453, "x":7.03799, "y":5.51965, "heading":1.1383, "vx":-2.48895, "vy":2.59686, "omega":-0.98102, "ax":-3.85423, "ay":3.37475, "alpha":13.02512, "fx":[-102.19801,-101.64729,1.64888,-60.04128], "fy":[32.96363,1.08571,106.12302,89.44177]}, - {"t":0.59981, "x":6.94777, "y":5.61337, "heading":1.10368, "vx":-2.62494, "vy":2.71593, "omega":-0.52146, "ax":-0.01946, "ay":0.10541, "alpha":0.11891, "fx":[-0.74568,-0.19432,0.08378,-0.46753], "fy":[1.65635,1.37842,1.92958,2.2074]}, - {"t":0.63509, "x":6.85515, "y":5.70926, "heading":1.08528, "vx":-2.62563, "vy":2.71965, "omega":-0.51726, "ax":3.79616, "ay":-3.35493, "alpha":-13.49959, "fx":[101.62329,102.21895,-3.57781,58.02182], "fy":[-34.82108,3.2231,-105.91808,-90.74948]}, - {"t":0.67038, "x":6.76487, "y":5.80313, "heading":1.06703, "vx":-2.49169, "vy":2.60128, "omega":-0.99357, "ax":4.32416, "ay":-4.41793, "alpha":-5.15384, "fx":[92.49726,90.01853,45.81125,65.88397], "fy":[-56.88603,-59.26422,-97.98721,-86.45343]}, - {"t":0.70566, "x":6.67965, "y":5.89216, "heading":1.03198, "vx":-2.33912, "vy":2.4454, "omega":-1.17541, "ax":4.43852, "ay":-4.6032, "alpha":-1.29214, "fx":[81.07797,79.13318,69.28387,72.49686], "fy":[-72.86955,-74.81877,-84.06524,-81.44303]}, - {"t":0.74094, "x":6.59988, "y":5.97558, "heading":0.99051, "vx":-2.18252, "vy":2.28298, "omega":-1.221, "ax":4.44899, "ay":-4.63041, "alpha":0.26193, "fx":[74.4908,74.96305,76.83477,76.41564], "fy":[-79.88742,-79.465,-77.65201,-78.04324]}, - {"t":0.77623, "x":6.52564, "y":6.05325, "heading":0.94742, "vx":-2.02554, "vy":2.11961, "omega":-1.21176, "ax":4.44451, "ay":-4.63457, "alpha":1.11675, "fx":[70.49572,72.53089,80.22464,79.148], "fy":[-83.60169,-81.90706,-74.37587,-75.44616]}, - {"t":0.81151, "x":6.45694, "y":6.12515, "heading":0.90467, "vx":-1.86873, "vy":1.95609, "omega":-1.17236, "ax":4.4379, "ay":-4.63311, "alpha":1.66372, "fx":[67.93448,70.79361,81.99696,81.22492], "fy":[-85.80306,-83.5366,-72.56099,-73.33074]}, - {"t":0.84679, "x":6.39377, "y":6.19128, "heading":0.86331, "vx":-1.71214, "vy":1.79262, "omega":-1.11365, "ax":4.43156, "ay":-4.63018, "alpha":2.0464, "fx":[66.23404,69.41661,82.98764,82.88027], "fy":[-87.19664,-84.76381,-71.52326,-71.54876]}, - {"t":0.88207, "x":6.33612, "y":6.25165, "heading":0.82401, "vx":-1.55578, "vy":1.62925, "omega":-1.04145, "ax":4.42591, "ay":-4.62707, "alpha":2.32998, "fx":[65.08539,68.26346,83.54973,84.23534], "fy":[-88.11188,-85.75058,-70.93591,-70.02198]}, - {"t":0.91736, "x":6.28398, "y":6.30625, "heading":0.78727, "vx":-1.39963, "vy":1.46599, "omega":-0.95924, "ax":4.42095, "ay":-4.62417, "alpha":2.54848, "fx":[64.30633,67.26939,83.85897,85.36168], "fy":[-88.72393,-86.57333,-70.62266,-68.70351]}, - {"t":0.95264, "x":6.23735, "y":6.3551, "heading":0.75342, "vx":-1.24364, "vy":1.30284, "omega":-0.86933, "ax":4.4166, "ay":-4.62162, "alpha":2.72156, "fx":[63.7806,66.40013,84.0137,86.30616], "fy":[-89.13585,-87.27302,-70.47934,-67.56167]}, - {"t":0.98792, "x":6.19622, "y":6.39819, "heading":0.72275, "vx":-1.08781, "vy":1.13977, "omega":-0.7733, "ax":4.41279, "ay":-4.61942, "alpha":2.86156, "fx":[63.42894,65.63597,84.07397,87.10202], "fy":[-89.41355,-87.87386,-70.43992,-66.57285]}, - {"t":1.02321, "x":6.16058, "y":6.43553, "heading":0.69547, "vx":-0.93211, "vy":0.97679, "omega":-0.67234, "ax":4.40943, "ay":-4.61754, "alpha":2.97676, "fx":[63.19434,64.96466,84.07905,87.77425], "fy":[-89.60212,-88.39135,-70.46028,-65.71808]}, - {"t":1.05849, "x":6.13044, "y":6.46712, "heading":0.67174, "vx":-0.77654, "vy":0.81387, "omega":-0.56731, "ax":4.40646, "ay":-4.61591, "alpha":3.07299, "fx":[63.03402,64.37814,84.05599,88.34234], "fy":[-89.73417,-88.83604,-70.50964,-64.98149]}, - {"t":1.09377, "x":6.10578, "y":6.49296, "heading":0.65173, "vx":-0.62106, "vy":0.651, "omega":-0.45888, "ax":4.40383, "ay":-4.6145, "alpha":3.15457, "fx":[62.91494,63.87083,84.02424,88.82183], "fy":[-89.83425,-89.21549,-70.56584,-64.34956]}, - {"t":1.12906, "x":6.08661, "y":6.51306, "heading":0.63554, "vx":-0.46568, "vy":0.48819, "omega":-0.34758, "ax":4.4015, "ay":-4.61325, "alpha":3.22475, "fx":[62.81103,63.43871,83.99818,89.2252], "fy":[-89.9214,-89.53527,-70.61249,-63.81076]}, - {"t":1.16434, "x":6.07292, "y":6.52741, "heading":0.62327, "vx":-0.31038, "vy":0.32542, "omega":-0.2338, "ax":4.39942, "ay":-4.61211, "alpha":3.28605, "fx":[62.70151,63.07891,83.98871,89.56244], "fy":[-90.01057,-89.79954,-70.6372,-63.35545]}, - {"t":1.19962, "x":6.06471, "y":6.53602, "heading":0.61502, "vx":-0.15516, "vy":0.16269, "omega":-0.11786, "ax":4.39756, "ay":-4.61106, "alpha":3.34042, "fx":[62.56982,62.7894,84.00422,89.8414], "fy":[-90.11357,-90.01136,-70.63044,-62.97581]}, - {"t":1.2349, "x":6.06197, "y":6.53889, "heading":0.61087, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], - "splits":[0] - }, - "events":[] -} diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index fa0fb1b0..4c684128 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -2114,9 +2114,6 @@ public static final LoggedAutoRoutine autoFLeft( LoggedAutoTrajectory path3 = (routine.trajectory("F_PATH_3")); LoggedAutoTrajectory path4 = (routine.trajectory("F_PATH_4")); LoggedAutoTrajectory path5 = (routine.trajectory("F_PATH_5")); - LoggedAutoTrajectory path6 = (routine.trajectory("F_PATH_6")); - LoggedAutoTrajectory path7 = (routine.trajectory("F_PATH_7")); - LoggedAutoTrajectory path8 = (routine.trajectory("F_PATH_8")); routine .active() @@ -2124,39 +2121,26 @@ public static final LoggedAutoRoutine autoFLeft( Commands.sequence( path1.resetOdometry(), Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - path1.cmd(), CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), superstructure.waitUntilAtGoal(), - path2.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.intakeAlgaeFromReef( - drive, superstructure, cameras) - .withTimeout(1), + Commands.parallel( + path2.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_ALGAE)), + CompositeCommands.V3_EpsilonCompositeCommands.intakeAlgaeFromReefAuto( + drive, superstructure, cameras), Commands.parallel( path3.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), Commands.runOnce(() -> drive.stop()), CompositeCommands.V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure), Commands.parallel( path4.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), - CompositeCommands.V3_EpsilonCompositeCommands.intakeAlgaeFromReef( - drive, superstructure, cameras) - .withTimeout(1), + CompositeCommands.V3_EpsilonCompositeCommands.intakeAlgaeFromReefAuto( + drive, superstructure, cameras), Commands.parallel( path5.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), Commands.runOnce(() -> drive.stop()), - CompositeCommands.V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure), - Commands.parallel( - path6.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), - CompositeCommands.V3_EpsilonCompositeCommands.intakeAlgaeFromReef( - drive, superstructure, cameras) - .withTimeout(1), - Commands.parallel( - path7.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), - Commands.runOnce(() -> drive.stop()), - CompositeCommands.V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure), - Commands.parallel( - path8.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)))); + CompositeCommands.V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure))); return routine; } diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 4f0500bf..d57a2d3f 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -800,7 +800,7 @@ public static final Command optimalScoreBarge(V3_EpsilonSuperstructure superstru Commands.runOnce(() -> RobotState.setScoreSide(optimalSideBarge())), superstructure .runGoalUntil(V3_EpsilonSuperstructureStates.BARGE_SCORE, () -> false) - .withTimeout(0.5)); + .withTimeout(2)); } /** @@ -907,6 +907,30 @@ public static final Command intakeAlgaeFromReef( postIntakeAlgaeFromReef(drive, superstructure, cameras)); } + public static final Command intakeAlgaeFromReefAuto( + Drive drive, + V3_EpsilonSuperstructure superstructure, + Supplier level, + Camera... cameras) { + + return Commands.sequence( + Commands.parallel( + superstructure.runGoalUntil( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }, + () -> RobotState.isHasAlgae()), + DriveCommands.autoAlignReefAlgae(drive, cameras)), + postIntakeAlgaeFromReef(drive, superstructure, cameras)); + } + public static final Command postIntakeAlgaeFromReef( Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { return superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP); @@ -918,6 +942,12 @@ public static final Command intakeAlgaeFromReef( drive, superstructure, () -> RobotState.getReefAlignData().algaeIntakeHeight(), cameras); } + public static final Command intakeAlgaeFromReefAuto( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + return intakeAlgaeFromReefAuto( + drive, superstructure, () -> RobotState.getReefAlignData().algaeIntakeHeight(), cameras); + } + public static final Command emergencyEject( V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { return Commands.sequence( diff --git a/src/main/java/frc/robot/subsystems/shared/drive/Drive.java b/src/main/java/frc/robot/subsystems/shared/drive/Drive.java index c66f44ca..6f336e79 100644 --- a/src/main/java/frc/robot/subsystems/shared/drive/Drive.java +++ b/src/main/java/frc/robot/subsystems/shared/drive/Drive.java @@ -356,7 +356,7 @@ public void setFFGains(double kS, double kV) { /** Runs a choreo path from swerve samples */ public void choreoDrive(SwerveSample sample) { - Pose2d pose = RobotState.getRobotPoseField(); + Pose2d pose = RobotState.getRobotPoseReef(); double xFF = sample.vx; double yFF = sample.vy; double rotationFF = sample.omega; From 5f61e46a2cbb0d6f199c09d3995c6a3b79fb721f Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Fri, 24 Oct 2025 14:26:19 -0400 Subject: [PATCH 145/180] Update robot constants for simulation mode and enhance climber functionality --- src/main/deploy/choreo/F_PATH_2.traj | 125 ++++++----- src/main/deploy/choreo/F_PATH_3.traj | 120 +++++----- src/main/deploy/choreo/F_PATH_4.traj | 209 ++++++++---------- src/main/deploy/choreo/F_PATH_5.traj | 142 ++++++------ src/main/java/frc/robot/Constants.java | 2 +- .../robot/commands/AutonomousCommands.java | 10 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 12 +- .../climber/V3_EpsilonClimberConstants.java | 12 +- .../climber/V3_EpsilonClimberIOTalonFX.java | 7 + 9 files changed, 326 insertions(+), 313 deletions(-) diff --git a/src/main/deploy/choreo/F_PATH_2.traj b/src/main/deploy/choreo/F_PATH_2.traj index 2f8246b0..e45795d3 100644 --- a/src/main/deploy/choreo/F_PATH_2.traj +++ b/src/main/deploy/choreo/F_PATH_2.traj @@ -5,7 +5,8 @@ "waypoints":[ {"x":5.976627826690674, "y":4.168239593505859, "heading":4.71238898038469, "intervals":15, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":6.811098575592041, "y":4.139791488647461, "heading":4.71238898038469, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":5.63525390625, "y":5.694940567016602, "heading":-0.5176488456806968, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":6.111105918884277, "y":6.0616984367370605, "heading":-0.5317242496599526, "intervals":19, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":5.21057653427124, "y":5.295576572418213, "heading":-0.5176488456806968, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -16,7 +17,8 @@ "waypoints":[ {"x":{"exp":"5.976627826690674 m", "val":5.976627826690674}, "y":{"exp":"4.168239593505859 m", "val":4.168239593505859}, "heading":{"exp":"270 deg", "val":4.71238898038469}, "intervals":15, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":{"exp":"6.811098575592041 m", "val":6.811098575592041}, "y":{"exp":"4.139791488647461 m", "val":4.139791488647461}, "heading":{"exp":"270 deg", "val":4.71238898038469}, "intervals":33, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"5.63525390625 m", "val":5.63525390625}, "y":{"exp":"5.694940567016602 m", "val":5.694940567016602}, "heading":{"exp":"-0.5176488456806968 rad", "val":-0.5176488456806968}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"6.111105918884277 m", "val":6.111105918884277}, "y":{"exp":"6.0616984367370605 m", "val":6.0616984367370605}, "heading":{"exp":"-0.5317242496599526 rad", "val":-0.5317242496599526}, "intervals":19, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"5.21057653427124 m", "val":5.21057653427124}, "y":{"exp":"5.295576572418213 m", "val":5.295576572418213}, "heading":{"exp":"-0.5176488456806968 rad", "val":-0.5176488456806968}, "intervals":40, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -28,57 +30,76 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,0.67787,1.7466], + "waypoints":[0.0,0.60216,1.60646,2.33334], "samples":[ - {"t":0.0, "x":5.97663, "y":4.16824, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.89821, "ay":-2.59191, "alpha":-1.67418, "fx":[96.8673,99.27787,103.37371,101.78863], "fy":[-51.60162,-46.81964,-36.89407,-41.03517]}, - {"t":0.04519, "x":5.98265, "y":4.16559, "heading":-1.5708, "vx":0.26655, "vy":-0.11713, "omega":-0.07566, "ax":5.93226, "ay":-2.5123, "alpha":-1.61318, "fx":[97.6942,99.88424,103.73929,102.30614], "fy":[-49.98027,-45.47286,-35.80287,-39.67809]}, - {"t":0.09038, "x":6.00075, "y":4.15773, "heading":-1.57422, "vx":0.53463, "vy":-0.23067, "omega":-0.14856, "ax":5.97772, "ay":-2.401, "alpha":-1.52803, "fx":[98.80148,100.69206,104.22472,102.99867], "fy":[-47.69861,-43.5984,-34.29123,-37.77292]}, - {"t":0.13557, "x":6.03102, "y":4.14486, "heading":-1.58093, "vx":0.80477, "vy":-0.33917, "omega":-0.21761, "ax":6.04113, "ay":-2.23463, "alpha":-1.40085, "fx":[100.34488,101.83289,104.90313,103.95067], "fy":[-44.27173,-40.77281,-32.04078,-34.95618]}, - {"t":0.18076, "x":6.07356, "y":4.12725, "heading":-1.59076, "vx":1.07778, "vy":-0.44015, "omega":-0.28092, "ax":6.13434, "ay":-1.95991, "alpha":-1.19103, "fx":[102.60042,103.55493,105.91024,105.30788], "fy":[-38.59592,-36.00893,-28.32402,-30.421]}, - {"t":0.22596, "x":6.12853, "y":4.10536, "heading":-1.60346, "vx":1.355, "vy":-0.52872, "omega":-0.33474, "ax":6.27654, "ay":-1.42602, "alpha":-0.78452, "fx":[105.983,106.30046,107.48407,107.2813], "fy":[-27.58253,-26.40386,-21.05809,-21.97994]}, - {"t":0.27115, "x":6.19617, "y":4.08001, "heading":-1.61859, "vx":1.63864, "vy":-0.59317, "omega":-0.3702, "ax":6.42333, "ay":-0.02356, "alpha":0.27329, "fx":[109.26849,109.25711,109.25007,109.26001], "fy":[0.53935,0.64495,-1.35867,-1.42845]}, - {"t":0.31634, "x":6.27678, "y":4.05318, "heading":-1.63532, "vx":1.92892, "vy":-0.59423, "omega":-0.35785, "ax":3.8236, "ay":5.04328, "alpha":3.97289, "fx":[68.48663,49.45604,61.41742,80.79333], "fy":[84.55505,96.77669,89.24822,72.55881]}, - {"t":0.36153, "x":6.36785, "y":4.03147, "heading":-1.65149, "vx":2.10171, "vy":-0.36632, "omega":-0.17831, "ax":-3.06227, "ay":5.57414, "alpha":4.03952, "fx":[-34.69919,-55.72923,-69.9958,-47.92926], "fy":[103.55582,94.01011,83.77077,97.92156]}, - {"t":0.40672, "x":6.45971, "y":4.02061, "heading":-1.65954, "vx":1.96332, "vy":-0.11442, "omega":0.00424, "ax":-4.48701, "ay":4.56383, "alpha":3.20003, "fx":[-64.01259,-75.96049,-87.49225,-77.82558], "fy":[88.82921,78.92375,65.84264,76.92216]}, - {"t":0.45191, "x":6.54385, "y":4.0201, "heading":-1.65935, "vx":1.76055, "vy":0.09183, "omega":0.14886, "ax":-4.92702, "ay":4.1081, "alpha":2.84734, "fx":[-73.95455,-82.69896,-92.51323,-86.06198], "fy":[80.89908,71.98649,58.80298,67.82171]}, - {"t":0.4971, "x":6.61838, "y":4.02844, "heading":-1.65263, "vx":1.53789, "vy":0.27747, "omega":0.27753, "ax":-5.13168, "ay":3.86177, "alpha":2.65682, "fx":[-78.69491,-85.99346,-94.82416,-89.64127], "fy":[76.38488,68.10275,55.1193,63.14363]}, - {"t":0.54229, "x":6.68264, "y":4.04493, "heading":-1.64008, "vx":1.30599, "vy":0.45199, "omega":0.3976, "ax":-5.24858, "ay":3.70901, "alpha":2.53802, "fx":[-81.42008,-87.96594,-96.15372,-91.56768], "fy":[73.52991,65.5898,52.84097,60.3958]}, - {"t":0.58748, "x":6.7363, "y":4.06914, "heading":-1.62212, "vx":1.0688, "vy":0.61961, "omega":0.51229, "ax":-5.32386, "ay":3.60535, "alpha":2.45679, "fx":[-83.17199,-89.30785,-97.02576,-92.72357], "fy":[71.58155,63.7885,51.27366,58.65985]}, - {"t":0.63268, "x":6.77916, "y":4.10082, "heading":-1.59896, "vx":0.8282, "vy":0.78254, "omega":0.62332, "ax":-5.37627, "ay":3.5305, "alpha":2.39759, "fx":[-84.38419,-90.30756,-97.64967,-93.45381], "fy":[70.17727,62.39302,50.1127,57.52838]}, - {"t":0.67787, "x":6.8111, "y":4.13979, "heading":-1.5708, "vx":0.58524, "vy":0.94208, "omega":0.73167, "ax":-5.40239, "ay":3.49372, "alpha":2.15547, "fx":[-85.62842,-90.9663,-97.47567,-93.50196], "fy":[68.59477,61.36751,50.37146,57.37519]}, - {"t":0.71025, "x":6.82722, "y":4.17213, "heading":-1.5471, "vx":0.41028, "vy":1.05523, "omega":0.80147, "ax":-5.41247, "ay":3.47754, "alpha":2.13757, "fx":[-85.86557,-91.26338,-97.60822,-93.52112], "fy":[68.28245,60.90889,50.09279,57.32355]}, - {"t":0.74264, "x":6.83767, "y":4.20813, "heading":-1.52114, "vx":0.235, "vy":1.16785, "omega":0.8707, "ax":-5.42395, "ay":3.45897, "alpha":2.11728, "fx":[-86.13974,-91.59262,-97.75442,-93.55232], "fy":[67.91876,60.39424,49.78224,57.24927]}, - {"t":0.77502, "x":6.84243, "y":4.24777, "heading":-1.49295, "vx":0.05934, "vy":1.27988, "omega":0.93927, "ax":-5.43713, "ay":3.43746, "alpha":2.09408, "fx":[-86.45935,-91.95775,-97.91649,-93.60224], "fy":[67.49114,59.81529,49.43396,57.14069]}, - {"t":0.80741, "x":6.8415, "y":4.29102, "heading":-1.46253, "vx":-0.11675, "vy":1.3912, "omega":1.00709, "ax":-5.45242, "ay":3.41225, "alpha":2.06726, "fx":[-86.8351,-92.36376,-98.09761,-93.6797], "fy":[66.98314,59.16092,49.03965,56.98214]}, - {"t":0.8398, "x":6.83486, "y":4.33787, "heading":-1.42991, "vx":-0.29333, "vy":1.50171, "omega":1.07404, "ax":-5.47037, "ay":3.3823, "alpha":2.03586, "fx":[-87.28095,-92.81746,-98.30237,-93.79663], "fy":[66.37264,58.41587,48.5873,56.75221]}, - {"t":0.87218, "x":6.8225, "y":4.38827, "heading":-1.39513, "vx":-0.47049, "vy":1.61125, "omega":1.13997, "ax":-5.49173, "ay":3.34614, "alpha":1.99849, "fx":[-87.81562,-93.32839,-98.53751,-93.96939], "fy":[65.62896,57.55852,48.05926,56.42085]}, - {"t":0.90457, "x":6.80438, "y":4.44221, "heading":-1.35821, "vx":-0.64835, "vy":1.71962, "omega":1.2047, "ax":-5.51757, "ay":3.30162, "alpha":1.95313, "fx":[-88.46499,-93.91025,-98.81303,-94.22096], "fy":[64.70791,56.5572,47.42886,55.94464]}, - {"t":0.93695, "x":6.78049, "y":4.49963, "heading":-1.31919, "vx":-0.82704, "vy":1.82654, "omega":1.26795, "ax":-5.54945, "ay":3.24549, "alpha":1.89677, "fx":[-89.26621,-94.58349,-99.14417,-94.58441], "fy":[63.54301,55.36351,46.65463,55.25846]}, - {"t":0.96934, "x":6.75079, "y":4.56049, "heading":-1.27813, "vx":-1.00676, "vy":1.93165, "omega":1.32938, "ax":-5.58972, "ay":3.17257, "alpha":1.82462, "fx":[-90.27488,-95.37974,-99.55479,-95.10904], "fy":[62.0288,53.89965,45.66925,54.26]}, - {"t":1.00173, "x":6.71526, "y":4.62471, "heading":-1.23508, "vx":-1.18779, "vy":2.0344, "omega":1.38847, "ax":-5.64212, "ay":3.07405, "alpha":1.72874, "fx":[-91.5784,-96.35038,-100.08362,-95.87103], "fy":[59.98652,52.03237,44.35742,52.77872]}, - {"t":1.03411, "x":6.67383, "y":4.69221, "heading":-1.19011, "vx":-1.37052, "vy":2.13395, "omega":1.44446, "ax":-5.71285, "ay":2.93383, "alpha":1.59499, "fx":[-93.32193,-97.58362,-100.79672,-96.99356], "fy":[57.08656,49.51371,42.50669,50.50762]}, - {"t":1.0665, "x":6.62645, "y":4.76286, "heading":-1.14333, "vx":-1.55553, "vy":2.22897, "omega":1.49611, "ax":-5.81283, "ay":2.71894, "alpha":1.39547, "fx":[-95.76039,-99.241,-101.81289,-98.68431], "fy":[52.6489,45.82702,39.68333,46.83446]}, - {"t":1.09888, "x":6.57302, "y":4.83647, "heading":-1.09488, "vx":-1.74379, "vy":2.31702, "omega":1.54131, "ax":-5.96184, "ay":2.35079, "alpha":1.0669, "fx":[-99.35211,-101.63457,-103.35547,-101.29492], "fy":[45.03098,39.70406,34.85901,40.35098]}, - {"t":1.13127, "x":6.51342, "y":4.91274, "heading":-1.04496, "vx":-1.93687, "vy":2.39316, "omega":1.57586, "ax":-6.1876, "ay":1.59303, "alpha":0.43229, "fx":[-104.68701,-105.27865,-105.79029,-105.24119], "fy":[29.23658,27.12159,24.95277,27.07731]}, - {"t":1.16366, "x":6.44745, "y":4.99108, "heading":-0.99392, "vx":-2.13726, "vy":2.44475, "omega":1.58986, "ax":-6.30643, "ay":-0.54535, "alpha":-1.15221, "fx":[-106.77206,-107.06855,-107.66061,-107.58129], "fy":[-14.7558,-11.05477,-3.6138,-7.6806]}, - {"t":1.19604, "x":6.37493, "y":5.06997, "heading":-0.94244, "vx":-2.3415, "vy":2.42709, "omega":1.55254, "ax":-2.28771, "ay":-5.78216, "alpha":-3.90146, "fx":[-35.98145,-20.17216,-43.778,-55.72169], "fy":[-100.96023,-104.70099,-96.56082,-91.18917]}, - {"t":1.22843, "x":6.29789, "y":5.14554, "heading":-0.89215, "vx":-2.41559, "vy":2.23983, "omega":1.42619, "ax":2.56951, "ay":-5.76678, "alpha":-3.64636, "fx":[36.64969,56.93236,53.46812,27.77661], "fy":[-102.02496,-92.17011,-93.74045,-104.42985]}, - {"t":1.26081, "x":6.22101, "y":5.21506, "heading":-0.84597, "vx":-2.33237, "vy":2.05306, "omega":1.3081, "ax":3.82519, "ay":-5.08582, "alpha":-3.19847, "fx":[57.75645,74.0653,74.34447,54.09508], "fy":[-92.40218,-79.91023,-79.36079,-94.36044]}, - {"t":1.2932, "x":6.14748, "y":5.27888, "heading":-0.8036, "vx":-2.20849, "vy":1.88836, "omega":1.20451, "ax":4.29943, "ay":-4.7221, "alpha":-2.97246, "fx":[66.33437,80.59741,81.48565,64.11054], "fy":[-86.7771,-73.71523,-72.52682,-88.26679]}, - {"t":1.32559, "x":6.07821, "y":5.33756, "heading":-0.76459, "vx":-2.06925, "vy":1.73543, "omega":1.10825, "ax":4.54034, "ay":-4.50824, "alpha":-2.84592, "fx":[70.89517,84.00561,84.92127,69.09729], "fy":[-83.28331,-70.03574,-68.76338,-84.65275]}, - {"t":1.35797, "x":6.01358, "y":5.3914, "heading":-0.7287, "vx":-1.92221, "vy":1.58942, "omega":1.01608, "ax":4.68465, "ay":-4.36919, "alpha":-2.76649, "fx":[73.72942,86.10872,86.89201,72.00815], "fy":[-80.90941,-67.58224,-66.4419,-82.34117]}, - {"t":1.39036, "x":5.95378, "y":5.44058, "heading":-0.69579, "vx":-1.77049, "vy":1.44792, "omega":0.92649, "ax":4.78037, "ay":-4.27198, "alpha":-2.71232, "fx":[75.67222,87.54502,88.14648,73.88705], "fy":[-79.18288,-65.81578,-64.89774,-80.76414]}, - {"t":1.42274, "x":5.89895, "y":5.48524, "heading":-0.66579, "vx":-1.61567, "vy":1.30957, "omega":0.83865, "ax":4.84836, "ay":-4.20033, "alpha":-2.67309, "fx":[77.09463,88.59328,89.0019,75.18718], "fy":[-77.86354,-64.47552,-63.81459,-79.6322]}, - {"t":1.45513, "x":5.84917, "y":5.52544, "heading":-0.63863, "vx":-1.45865, "vy":1.17354, "omega":0.75207, "ax":4.8991, "ay":-4.1454, "alpha":-2.64336, "fx":[78.18511,89.39412,89.61511,76.13465], "fy":[-76.81847,-63.42052,-63.02336,-78.78575]}, - {"t":1.48751, "x":5.8045, "y":5.56128, "heading":-0.61427, "vx":-1.29999, "vy":1.03929, "omega":0.66647, "ax":4.93838, "ay":-4.10196, "alpha":-2.62006, "fx":[79.04907,90.02608,90.07252,76.85405], "fy":[-75.9688,-62.56797,-62.42543,-78.13065]}, - {"t":1.5199, "x":5.76499, "y":5.59278, "heading":-0.59269, "vx":-1.14006, "vy":0.90644, "omega":0.58161, "ax":4.96968, "ay":-4.06677, "alpha":-2.6013, "fx":[79.74986,90.53653,90.42575,77.41923], "fy":[-75.26505,-61.866,-61.95933,-77.60824]}, - {"t":1.55229, "x":5.73067, "y":5.62001, "heading":-0.57385, "vx":-0.97911, "vy":0.77473, "omega":0.49737, "ax":4.9952, "ay":-4.03769, "alpha":-2.5859, "fx":[80.32776,90.95576,90.70756,77.8766], "fy":[-74.67469,-61.28039,-61.58465,-77.18028]}, - {"t":1.58467, "x":5.70158, "y":5.64298, "heading":-0.55774, "vx":-0.81734, "vy":0.64397, "omega":0.41362, "ax":5.0164, "ay":-4.01326, "alpha":-2.57305, "fx":[80.80956,91.30406,90.9398,78.25663], "fy":[-74.17553,-60.78762,-61.2737,-76.82091]}, - {"t":1.61706, "x":5.67774, "y":5.66173, "heading":-0.54435, "vx":-0.65488, "vy":0.514, "omega":0.33029, "ax":5.03429, "ay":-3.99245, "alpha":-2.56221, "fx":[81.21378,91.59557,91.1376,78.58013], "fy":[-73.75192,-60.37095,-61.00686,-76.51203]}, - {"t":1.64944, "x":5.65917, "y":5.67628, "heading":-0.53365, "vx":-0.49184, "vy":0.3847, "omega":0.24731, "ax":5.04958, "ay":-3.97451, "alpha":-2.55299, "fx":[81.5536,91.84041,91.31175,78.86178], "fy":[-73.39253,-60.01817,-60.76988,-76.24066]}, - {"t":1.68183, "x":5.64589, "y":5.68666, "heading":-0.52564, "vx":-0.3283, "vy":0.25598, "omega":0.16463, "ax":5.0628, "ay":-3.95889, "alpha":-2.5451, "fx":[81.83869,92.04602,91.47015,79.11227], "fy":[-73.08891,-59.72017,-60.55215,-75.99718]}, - {"t":1.71422, "x":5.63792, "y":5.69287, "heading":-0.52031, "vx":-0.16434, "vy":0.12777, "omega":0.08221, "ax":5.07434, "ay":-3.94517, "alpha":-2.53832, "fx":[82.07631,92.21797,91.61867,79.33957], "fy":[-72.83463,-59.47005,-60.34569,-75.77426]}, - {"t":1.7466, "x":5.63525, "y":5.69494, "heading":-0.51765, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":5.97663, "y":4.16824, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.58714, "ay":-3.20259, "alpha":-1.28759, "fx":[90.24007,94.06194,99.32466,96.51581], "fy":[-62.45144,-56.55315,-46.68191,-52.21439]}, + {"t":0.04014, "x":5.98113, "y":4.16566, "heading":-1.5708, "vx":0.22429, "vy":-0.12856, "omega":-0.05169, "ax":5.68126, "ay":-3.03343, "alpha":-1.20977, "fx":[92.40474,95.65173,100.4199,98.07034], "fy":[-59.17022,-53.78846,-44.23741,-49.19491]}, + {"t":0.08029, "x":5.99471, "y":4.15805, "heading":-1.57287, "vx":0.45236, "vy":-0.25034, "omega":-0.10025, "ax":5.7981, "ay":-2.80478, "alpha":-1.10462, "fx":[95.10111,97.65195,101.77648,99.96684], "fy":[-54.68696,-50.01944,-40.96425,-45.16367]}, + {"t":0.12043, "x":6.01754, "y":4.14574, "heading":-1.5769, "vx":0.68512, "vy":-0.36293, "omega":-0.1446, "ax":5.94446, "ay":-2.48084, "alpha":-0.95568, "fx":[98.48296,100.21632,103.47819,102.27655], "fy":[-48.26359,-44.58857,-36.36622,-39.57544]}, + {"t":0.16058, "x":6.04984, "y":4.12918, "heading":-1.5827, "vx":0.92375, "vy":-0.46252, "omega":-0.18296, "ax":6.12555, "ay":-1.99301, "alpha":-0.73175, "fx":[102.64886,103.5032,105.60231,105.02134], "fy":[-38.4985,-36.18238,-29.48402,-31.43755]}, + {"t":0.20072, "x":6.09185, "y":4.109, "heading":-1.59005, "vx":1.16965, "vy":-0.54253, "omega":-0.21234, "ax":6.32815, "ay":-1.19934, "alpha":-0.36946, "fx":[107.21359,107.36584,108.0442,107.9368], "fy":[-22.59615,-21.91039,-18.26448,-18.83082]}, + {"t":0.24086, "x":6.14391, "y":4.08626, "heading":-1.59857, "vx":1.42369, "vy":-0.59068, "omega":-0.22717, "ax":6.43246, "ay":0.20158, "alpha":0.26295, "fx":[109.38101,109.36303,109.45057,109.46251], "fy":[4.68924,4.88282,2.13514,2.00828]}, + {"t":0.28101, "x":6.20624, "y":4.06271, "heading":-1.60769, "vx":1.68192, "vy":-0.58259, "omega":-0.21661, "ax":5.84317, "ay":2.64899, "alpha":1.35097, "fx":[98.40392,95.23129,100.91557,103.01202], "fy":[47.78278,53.72036,41.99294,36.73838]}, + {"t":0.32115, "x":6.27847, "y":4.04145, "heading":-1.61638, "vx":1.91648, "vy":-0.47625, "omega":-0.16238, "ax":3.40939, "ay":5.39305, "alpha":2.52473, "fx":[61.98209,43.45446,53.36349,73.17091], "fy":[90.13451,100.33598,95.27983,81.18681]}, + {"t":0.3613, "x":6.35815, "y":4.02668, "heading":-1.6229, "vx":2.05335, "vy":-0.25975, "omega":-0.06103, "ax":0.4474, "ay":6.3541, "alpha":2.97688, "fx":[20.43438,-5.68444,-9.24168,24.93255], "fy":[107.55338,109.32823,108.96475,106.47916]}, + {"t":0.40144, "x":6.44094, "y":4.02137, "heading":-1.62535, "vx":2.07131, "vy":-0.00467, "omega":0.05848, "ax":-1.35851, "ay":6.23593, "alpha":2.83009, "fx":[-7.37873,-31.73641,-41.79255,-11.52408], "fy":[109.31663,104.88472,101.21869,108.8657]}, + {"t":0.44158, "x":6.523, "y":4.02621, "heading":-1.62301, "vx":2.01677, "vy":0.24567, "omega":0.17209, "ax":-2.34159, "ay":5.94988, "alpha":2.63267, "fx":[-24.07606,-45.51333,-57.17701,-32.55259], "fy":[106.95183,99.75423,93.50208,104.61496]}, + {"t":0.48173, "x":6.60207, "y":4.04087, "heading":-1.6161, "vx":1.92277, "vy":0.48452, "omega":0.27777, "ax":-2.91692, "ay":5.6992, "alpha":2.48595, "fx":[-34.5241,-53.65815,-65.49644,-44.78498], "fy":[104.09583,95.66833,87.94516,100.05739]}, + {"t":0.52187, "x":6.67691, "y":4.06491, "heading":-1.60495, "vx":1.80568, "vy":0.71331, "omega":0.37757, "ax":-3.28396, "ay":5.5025, "alpha":2.38031, "fx":[-41.49446,-58.97646,-70.57441,-52.39162], "fy":[101.55204,92.51884,83.9731,96.34013]}, + {"t":0.56202, "x":6.74675, "y":4.09798, "heading":-1.58979, "vx":1.67385, "vy":0.9342, "omega":0.47312, "ax":-3.53516, "ay":5.34948, "alpha":2.30208, "fx":[-46.41892,-62.72816,-73.96007,-57.42091], "fy":[99.42268,90.04277,81.04202,93.46493]}, + {"t":0.60216, "x":6.8111, "y":4.13979, "heading":-1.5708, "vx":1.53193, "vy":1.14895, "omega":0.56554, "ax":-3.68243, "ay":5.25537, "alpha":2.07425, "fx":[-50.44338,-64.85532,-74.85927,-60.39059], "fy":[97.40131,88.48055,80.16109,91.52625]}, + {"t":0.63259, "x":6.85601, "y":4.17719, "heading":-1.55359, "vx":1.41986, "vy":1.30889, "omega":0.62866, "ax":-3.78506, "ay":5.18171, "alpha":2.05951, "fx":[-52.42446,-66.54083,-76.33651,-62.22935], "fy":[96.3376,87.20807,78.74063,90.27138]}, + {"t":0.66303, "x":6.89747, "y":4.21942, "heading":-1.53445, "vx":1.30467, "vy":1.46658, "omega":0.69134, "ax":-3.89896, "ay":5.09633, "alpha":2.04202, "fx":[-54.63476,-68.40739,-77.96446,-64.27447], "fy":[95.08802,85.73806,77.11196,88.81012]}, + {"t":0.69346, "x":6.93537, "y":4.26642, "heading":-1.51341, "vx":1.18601, "vy":1.62168, "omega":0.75349, "ax":-4.02586, "ay":4.99647, "alpha":2.02104, "fx":[-57.11061,-70.47843,-79.76343,-66.56212], "fy":[93.60647,84.02817,75.22998,87.08964]}, + {"t":0.72389, "x":6.9696, "y":4.31808, "heading":-1.49048, "vx":1.06349, "vy":1.77374, "omega":0.81499, "ax":-4.16771, "ay":4.87858, "alpha":1.99558, "fx":[-59.89527,-72.78124,-81.75594,-69.13365], "fy":[91.83171,82.0234,73.03693,85.04072]}, + {"t":0.75433, "x":7.00004, "y":4.37432, "heading":-1.46568, "vx":0.93666, "vy":1.92221, "omega":0.87573, "ax":-4.32676, "ay":4.73792, "alpha":1.96432, "fx":[-63.03977,-75.34705,-83.96605,-72.03513], "fy":[89.68133,79.65144,70.45827,82.57185]}, + {"t":0.78476, "x":7.02654, "y":4.43502, "heading":-1.43903, "vx":0.80498, "vy":2.0664, "omega":0.93551, "ax":-4.50547, "ay":4.56823, "alpha":1.92549, "fx":[-66.60309,-78.21054,-86.41772,-75.31552], "fy":[87.04293,76.81614,67.39719,79.56111]}, + {"t":0.81519, "x":7.04895, "y":4.50002, "heading":-1.41056, "vx":0.66786, "vy":2.20543, "omega":0.99411, "ax":-4.70631, "ay":4.36107, "alpha":1.87664, "fx":[-70.65063,-81.40799,-89.13127,-79.02185], "fy":[83.76128,73.38818,63.72737,75.84548]}, + {"t":0.84563, "x":7.0671, "y":4.56916, "heading":-1.3803, "vx":0.52464, "vy":2.33815, "omega":1.05122, "ax":-4.93139, "ay":4.10506, "alpha":1.81442, "fx":[-75.24846,-84.97231,-92.1165,-83.18887], "fy":[79.62007,69.19212,59.28412,71.20731]}, + {"t":0.87606, "x":7.08078, "y":4.64222, "heading":-1.34831, "vx":0.37456, "vy":2.46308, "omega":1.10644, "ax":-5.18158, "ay":3.7849, "alpha":1.73414, "fx":[-80.4486,-88.92217,-95.35989,-87.81841], "fy":[74.31689,63.98902,53.85443,65.35985]}, + {"t":0.90649, "x":7.08978, "y":4.71893, "heading":-1.31464, "vx":0.21687, "vy":2.57826, "omega":1.15921, "ax":-5.45481, "ay":3.38034, "alpha":1.62935, "fx":[-86.25559,-93.23935,-98.80211,-92.84166], "fy":[67.43293,57.45513,47.16901,57.93771]}, + {"t":0.93692, "x":7.09385, "y":4.79896, "heading":-1.27936, "vx":0.05086, "vy":2.68114, "omega":1.2088, "ax":-5.74289, "ay":2.86574, "alpha":1.49124, "fx":[-92.55764,-97.82437,-102.30089,-98.05654], "fy":[58.40798,49.16197,38.90366,48.50824]}, + {"t":0.96736, "x":7.09274, "y":4.88188, "heading":-1.24257, "vx":-0.12392, "vy":2.76835, "omega":1.25418, "ax":-6.0265, "ay":2.21162, "alpha":1.30852, "fx":[-99.0012,-102.41664,-105.57685,-103.04128], "fy":[46.55637,38.57614,28.70686,36.63662]}, + {"t":0.99779, "x":7.08618, "y":4.96716, "heading":-1.2044, "vx":-0.30732, "vy":2.83566, "omega":1.294, "ax":-6.26861, "ay":1.39139, "alpha":1.06863, "fx":[-104.80862,-106.47078,-108.15196,-107.07803], "fy":[31.20936,25.1252,16.28201,22.05172]}, + {"t":1.02822, "x":7.07392, "y":5.0541, "heading":-1.16502, "vx":-0.4981, "vy":2.878, "omega":1.32653, "ax":-6.41073, "ay":0.39702, "alpha":0.76264, "fx":[-108.64398,-109.02537,-109.32292,-109.18665], "fy":[12.11168,8.41649,1.55527,4.92959]}, + {"t":1.05866, "x":7.0558, "y":5.14187, "heading":-1.12465, "vx":-0.6932, "vy":2.89009, "omega":1.34974, "ax":-6.38205, "ay":-0.7375, "alpha":0.39466, "fx":[-108.83899,-108.7237,-108.25877,-108.40605], "fy":[-9.94047,-11.32004,-15.08694,-13.8311]}, + {"t":1.08909, "x":7.03174, "y":5.22948, "heading":-1.08358, "vx":-0.88742, "vy":2.86764, "omega":1.36175, "ax":-6.13084, "ay":-1.92221, "alpha":-0.01071, "fx":[-104.26482,-104.2703,-104.30294,-104.29744], "fy":[-32.7577,-32.73834,-32.63456,-32.65403]}, + {"t":1.11952, "x":7.0019, "y":5.31586, "heading":-1.04213, "vx":-1.074, "vy":2.80914, "omega":1.36142, "ax":-5.66299, "ay":-3.03402, "alpha":-0.41416, "fx":[-95.30775,-95.3248,-97.38036,-97.29028], "fy":[-53.5288,-53.45368,-49.61214,-49.8364]}, + {"t":1.14996, "x":6.96659, "y":5.39995, "heading":-1.0007, "vx":-1.24635, "vy":2.71681, "omega":1.34882, "ax":-5.04736, "ay":-3.9724, "alpha":-0.77838, "fx":[-83.74086,-83.02459,-88.16714,-88.48382], "fy":[-70.31911,-71.1044,-64.61081,-64.24316]}, + {"t":1.18039, "x":6.92632, "y":5.48079, "heading":-0.95965, "vx":-1.39995, "vy":2.59592, "omega":1.32513, "ax":-4.37702, "ay":-4.69833, "alpha":-1.08131, "fx":[-71.55776,-69.365,-77.80071,-79.08385], "fy":[-82.74573,-84.53088,-76.82037,-75.57211]}, + {"t":1.21082, "x":6.88169, "y":5.55762, "heading":-0.91932, "vx":-1.53316, "vy":2.45293, "omega":1.29222, "ax":-3.72636, "ay":-5.22739, "alpha":-1.31898, "fx":[-60.09073,-56.08927,-67.37873,-69.97846], "fy":[-91.46902,-93.91695,-86.15204,-84.12761]}, + {"t":1.24126, "x":6.83331, "y":5.62985, "heading":-0.88, "vx":-1.64657, "vy":2.29384, "omega":1.25208, "ax":-3.13604, "ay":-5.60002, "alpha":-1.49957, "fx":[-49.92073,-44.16131,-57.64417,-61.64611], "fy":[-97.44078,-100.12794,-92.99129,-90.45866]}, + {"t":1.27169, "x":6.78174, "y":5.69706, "heading":-0.84189, "vx":-1.74201, "vy":2.12342, "omega":1.20644, "ax":-2.61977, "ay":-5.85836, "alpha":-1.63537, "fx":[-41.15226,-33.88225,-48.95438,-54.25748], "fy":[-101.49621,-104.09864,-97.88578,-95.11536]}, + {"t":1.30212, "x":6.72752, "y":5.75897, "heading":-0.80518, "vx":-1.82173, "vy":1.94513, "omega":1.15667, "ax":-2.17617, "ay":-6.03662, "alpha":-1.73785, "fx":[-33.67203,-25.18996,-41.39457,-47.80778], "fy":[-104.25103,-106.57266,-101.35084,-98.5502]}, + {"t":1.33256, "x":6.67107, "y":5.81537, "heading":-0.76998, "vx":-1.88796, "vy":1.76141, "omega":1.10378, "ax":-1.79742, "ay":-6.1597, "alpha":-1.81605, "fx":[-27.29788,-17.88134,-34.90255,-42.21237], "fy":[-106.12725,-108.07066,-103.79765,-101.10352]}, + {"t":1.36299, "x":6.61278, "y":5.86613, "heading":-0.73638, "vx":-1.94266, "vy":1.57395, "omega":1.04852, "ax":-1.47399, "ay":-6.24487, "alpha":-1.87659, "fx":[-21.84598,-11.72708,-29.35466,-37.36092], "fy":[-107.40644,-108.93726,-105.52897,-103.02081]}, + {"t":1.39342, "x":6.55297, "y":5.91114, "heading":-0.70447, "vx":-1.98752, "vy":1.3839, "omega":0.99141, "ax":-1.19681, "ay":-6.30385, "alpha":-1.92418, "fx":[-17.155,-6.51809,-24.61307,-33.14362], "fy":[-108.27555,-109.39571,-106.75909,-104.47622]}, + {"t":1.42386, "x":6.49193, "y":5.95033, "heading":-0.6743, "vx":-2.02394, "vy":1.19206, "omega":0.93285, "ax":-0.95798, "ay":-6.3446, "alpha":-1.96215, "fx":[-13.09132,-2.07882,-20.54788,-29.46187], "fy":[-108.85953,-109.59006,-107.63706,-105.59288]}, + {"t":1.45429, "x":6.42989, "y":5.98367, "heading":-0.64591, "vx":-2.0531, "vy":0.99897, "omega":0.87313, "ax":-0.75091, "ay":-6.37255, "alpha":-1.99288, "fx":[-9.54705,1.73293,-17.04525,-26.23138], "fy":[-109.24295,-109.61357,-108.26602,-106.45825]}, + {"t":1.48472, "x":6.36706, "y":6.01112, "heading":-0.61934, "vx":-2.07595, "vy":0.80503, "omega":0.81248, "ax":-0.5702, "ay":-6.3914, "alpha":-2.01807, "fx":[-6.43586,5.03067,-14.00896,-23.38174], "fy":[-109.48387,-109.52716,-108.71743,-107.135]}, + {"t":1.51516, "x":6.30362, "y":6.03266, "heading":-0.59461, "vx":-2.0933, "vy":0.61052, "omega":0.75107, "ax":-0.4115, "ay":-6.40374, "alpha":-2.03896, "fx":[-3.68882,7.90473,-11.35911,-20.85489], "fy":[-109.62275,-109.37091,-109.04111,-107.66846]}, + {"t":1.54559, "x":6.23972, "y":6.04828, "heading":-0.57176, "vx":-2.10583, "vy":0.41564, "omega":0.68901, "ax":-0.27127, "ay":-6.41139, "alpha":-2.05645, "fx":[-1.2507,10.42706,-9.02992,-18.60313], "fy":[-109.68825,-109.17143,-109.27201,-108.09186]}, + {"t":1.57602, "x":6.17551, "y":6.05796, "heading":-0.55079, "vx":-2.11408, "vy":0.22052, "omega":0.62643, "ax":-0.14663, "ay":-6.41563, "alpha":-2.07123, "fx":[0.92293,12.65534,-6.96732,-16.58729], "fy":[-109.70093,-108.94646,-109.43487,-108.42983]}, + {"t":1.60646, "x":6.11111, "y":6.0617, "heading":-0.53172, "vx":-2.11855, "vy":0.02527, "omega":0.5634, "ax":-0.01125, "ay":-6.42277, "alpha":-1.94784, "fx":[3.02898,14.03522,-4.32291,-13.50645], "fy":[-109.69032,-108.81066,-109.60971,-108.88699]}, + {"t":1.64471, "x":6.03005, "y":6.05796, "heading":-0.51017, "vx":-2.11898, "vy":-0.22045, "omega":0.48888, "ax":0.17595, "ay":-6.41788, "alpha":-1.99504, "fx":[6.19925,17.56809,-1.1188,-10.67715], "fy":[-109.5402,-108.2765,-109.66647,-109.18218]}, + {"t":1.68297, "x":5.94911, "y":6.04483, "heading":-0.49147, "vx":-2.11224, "vy":-0.46598, "omega":0.41255, "ax":0.41967, "ay":-6.40338, "alpha":-2.05319, "fx":[10.19207,22.13943,3.23298,-7.01065], "fy":[-109.2196,-107.40943,-109.59477,-109.45462]}, + {"t":1.72123, "x":5.86861, "y":6.02232, "heading":-0.47568, "vx":-2.09619, "vy":-0.71096, "omega":0.334, "ax":0.74832, "ay":-6.36912, "alpha":-2.12617, "fx":[15.41762,28.22482,9.32687,-2.05475], "fy":[-108.57666,-105.93903,-109.20465,-109.62706]}, + {"t":1.75948, "x":5.78896, "y":5.99046, "heading":-0.46291, "vx":-2.06756, "vy":-0.95462, "omega":0.25266, "ax":1.21094, "ay":-6.29176, "alpha":-2.21926, "fx":[22.57461,36.59078,18.21401,5.01184], "fy":[-107.27745,-103.30081,-108.02071,-109.4855]}, + {"t":1.79774, "x":5.71075, "y":5.94934, "heading":-0.45324, "vx":-2.02123, "vy":-1.19533, "omega":0.16776, "ax":1.89548, "ay":-6.11214, "alpha":-2.3386, "fx":[32.90645,48.46001,31.80775,15.79229], "fy":[-104.51309,-98.22406,-104.73909,-108.38655]}, + {"t":1.836, "x":5.63481, "y":5.89913, "heading":-0.44682, "vx":-1.94872, "vy":-1.42916, "omega":0.07829, "ax":2.95336, "ay":-5.66468, "alpha":-2.48512, "fx":[48.61696,65.48288,53.27488,33.56842], "fy":[-98.10169,-87.68906,-95.48227,-104.14511]}, + {"t":1.87426, "x":5.56242, "y":5.84031, "heading":-0.44383, "vx":-1.83573, "vy":-1.64588, "omega":-0.01679, "ax":4.53378, "ay":-4.48422, "alpha":-2.59223, "fx":[72.61436,87.88898,84.06431,63.90546], "fy":[-81.78069,-65.03336,-69.6768,-88.61053]}, + {"t":1.91251, "x":5.49551, "y":5.77406, "heading":-0.44447, "vx":-1.66228, "vy":-1.81743, "omega":-0.11596, "ax":6.1239, "ay":-1.80543, "alpha":-2.19601, "fx":[100.86019,106.84401,107.75082,101.20786], "fy":[-41.96563,-22.84197,-17.29122,-40.74072]}, + {"t":1.95077, "x":5.43639, "y":5.70321, "heading":-0.44891, "vx":-1.428, "vy":-1.8865, "omega":-0.19997, "ax":6.22965, "ay":1.52321, "alpha":-1.16836, "fx":[107.81867,105.98524,103.76762,106.28669], "fy":[17.68942,26.70391,34.17719,25.06723]}, + {"t":1.98903, "x":5.38632, "y":5.63215, "heading":-0.45656, "vx":-1.18967, "vy":-1.82823, "omega":-0.24467, "ax":5.32981, "ay":3.59813, "alpha":-0.30191, "fx":[91.84654,90.99123,89.46731,90.32896], "fy":[59.42164,60.74356,62.95549,61.69196]}, + {"t":2.02729, "x":5.34471, "y":5.56484, "heading":-0.46592, "vx":-0.98576, "vy":-1.69057, "omega":-0.25622, "ax":4.49134, "ay":4.6117, "alpha":0.22561, "fx":[75.35357,75.84295,77.44896,76.94039], "fy":[79.45815,78.98105,77.41016,77.92575]}, + {"t":2.06554, "x":5.31028, "y":5.50354, "heading":-0.47572, "vx":-0.81394, "vy":-1.51414, "omega":-0.24759, "ax":3.88986, "ay":5.13247, "alpha":0.54139, "fx":[63.63334,64.29673,68.79015,67.94165], "fy":[89.21574,88.72103,85.28771,85.98307]}, + {"t":2.1038, "x":5.28199, "y":5.44937, "heading":-0.48519, "vx":-0.66512, "vy":-1.31779, "omega":-0.22688, "ax":3.4654, "ay":5.4294, "alpha":0.74336, "fx":[55.55921,55.86879,62.54341,61.81048], "fy":[94.5156,94.31392,90.02825,90.5525]}, + {"t":2.14206, "x":5.25908, "y":5.40293, "heading":-0.49387, "vx":-0.53254, "vy":-1.11007, "omega":-0.19844, "ax":3.15713, "ay":5.61484, "alpha":0.88122, "fx":[49.82663,49.6307,57.90247,57.44766], "fy":[97.70012,97.78147,93.12251,93.42286]}, + {"t":2.18031, "x":5.24102, "y":5.36457, "heading":-0.50146, "vx":-0.41176, "vy":-0.89526, "omega":-0.16472, "ax":2.92554, "ay":5.73918, "alpha":0.98038, "fx":[45.60045,44.89244,54.34599,54.21126], "fy":[99.77199,100.07546,95.27237,95.36719]}, + {"t":2.21857, "x":5.2274, "y":5.33452, "heading":-0.50776, "vx":-0.29984, "vy":-0.6757, "omega":-0.12722, "ax":2.74615, "ay":5.82727, "alpha":1.05473, "fx":[42.37574,41.19923,51.54612,51.72407], "fy":[101.20568,101.67449,96.83915,96.76116]}, + {"t":2.25683, "x":5.21794, "y":5.31293, "heading":-0.51263, "vx":-0.19478, "vy":-0.45276, "omega":-0.08687, "ax":2.60355, "ay":5.89242, "alpha":1.11235, "fx":[39.84085,38.25413,49.29251,49.75534], "fy":[102.24712,102.83671,98.02383,97.80553]}, + {"t":2.29509, "x":5.2124, "y":5.29993, "heading":-0.51595, "vx":-0.09517, "vy":-0.22734, "omega":-0.04431, "ax":2.48769, "ay":5.94228, "alpha":1.15822, "fx":[37.79648,35.85962,47.44601,48.15762], "fy":[103.03389,103.7104,98.9456,98.61596]}, + {"t":2.33334, "x":5.21058, "y":5.29558, "heading":-0.51765, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/F_PATH_3.traj b/src/main/deploy/choreo/F_PATH_3.traj index a3f411f8..e38300bb 100644 --- a/src/main/deploy/choreo/F_PATH_3.traj +++ b/src/main/deploy/choreo/F_PATH_3.traj @@ -3,7 +3,7 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":5.312845230102539, "y":5.400979518890381, "heading":-0.5179875110397575, "intervals":55, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":5.21057653427124, "y":5.295576572418213, "heading":-0.5176488456806968, "intervals":57, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":7.010232925415039, "y":6.064763069152832, "heading":1.5707963267948966, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -14,7 +14,7 @@ }, "params":{ "waypoints":[ - {"x":{"exp":"5.312845230102539 m", "val":5.312845230102539}, "y":{"exp":"5.400979518890381 m", "val":5.400979518890381}, "heading":{"exp":"-0.5179875110397575 rad", "val":-0.5179875110397575}, "intervals":55, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"5.21057653427124 m", "val":5.21057653427124}, "y":{"exp":"5.295576572418213 m", "val":5.295576572418213}, "heading":{"exp":"-0.5176488456806968 rad", "val":-0.5176488456806968}, "intervals":57, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":{"exp":"7.010232925415039 m", "val":7.010232925415039}, "y":{"exp":"6.064763069152832 m", "val":6.064763069152832}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -28,64 +28,66 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,1.97994], + "waypoints":[0.0,2.11406], "samples":[ - {"t":0.0, "x":5.31285, "y":5.40098, "heading":-0.51799, "vx":0.0, "vy":0.0, "omega":0.0, "ax":6.00791, "ay":2.34946, "alpha":0.01123, "fx":[102.16304,102.18963,102.22267,102.19612], "fy":[40.03998,39.97176,39.88743,39.9557]}, - {"t":0.036, "x":5.31674, "y":5.4025, "heading":-0.51799, "vx":0.21628, "vy":0.08458, "omega":0.0004, "ax":6.00551, "ay":2.34852, "alpha":0.01373, "fx":[102.11548,102.14795,102.18836,102.15596], "fy":[40.04092,39.95752,39.85446,39.93792]}, - {"t":0.072, "x":5.32842, "y":5.40707, "heading":-0.51797, "vx":0.43247, "vy":0.16912, "omega":0.0009, "ax":6.0007, "ay":2.34664, "alpha":0.01873, "fx":[102.02043,102.0646,102.11976,102.07572], "fy":[40.04277,39.92905,39.78858,39.90242]}, - {"t":0.108, "x":5.34787, "y":5.41468, "heading":-0.51794, "vx":0.64849, "vy":0.2536, "omega":0.00157, "ax":5.9863, "ay":2.34101, "alpha":0.03373, "fx":[101.73596,101.81478,101.91426,101.83585], "fy":[40.04811,39.8437,39.59149,39.7963]}, - {"t":0.144, "x":5.3751, "y":5.42532, "heading":-0.51788, "vx":0.86399, "vy":0.33787, "omega":0.00279, "ax":1.86315, "ay":0.72863, "alpha":4.97225, "fx":[26.80398,14.81433,38.00528,47.14304], "fy":[31.49045,8.3125,-6.60643,16.37844]}, - {"t":0.17999, "x":5.40741, "y":5.43796, "heading":-0.51778, "vx":0.93106, "vy":0.3641, "omega":0.18178, "ax":0.00003, "ay":0.0, "alpha":5.36195, "fx":[-5.20456,-18.98286,5.2056,18.98385], "fy":[18.98334,-5.20511,-18.98337,5.20505]}, - {"t":0.21599, "x":5.44092, "y":5.45107, "heading":-0.51124, "vx":0.93106, "vy":0.3641, "omega":0.37481, "ax":0.0, "ay":0.0, "alpha":4.78389, "fx":[-4.75466,-16.90604,4.75466,16.90605], "fy":[16.90604,-4.75467,-16.90605,4.75465]}, - {"t":0.25199, "x":5.47444, "y":5.46417, "heading":-0.49775, "vx":0.93106, "vy":0.3641, "omega":0.54702, "ax":0.0, "ay":0.0, "alpha":4.25842, "fx":[-4.43506,-14.99058,4.43506,14.99058], "fy":[14.99058,-4.43506,-14.99058,4.43506]}, - {"t":0.28799, "x":5.50796, "y":5.47728, "heading":-0.47805, "vx":0.93106, "vy":0.3641, "omega":0.70032, "ax":0.0, "ay":0.0, "alpha":3.78265, "fx":[-4.20099,-13.23562,4.20099,13.23562], "fy":[13.23562,-4.20099,-13.23562,4.20099]}, - {"t":0.32399, "x":5.54147, "y":5.49039, "heading":-0.45284, "vx":0.93106, "vy":0.3641, "omega":0.83649, "ax":0.0, "ay":0.0, "alpha":3.3533, "fx":[-4.01875,-11.63571,4.01875,11.63571], "fy":[11.63571,-4.01875,-11.63571,4.01875]}, - {"t":0.35999, "x":5.57499, "y":5.50349, "heading":-0.42273, "vx":0.93106, "vy":0.3641, "omega":0.9572, "ax":0.0, "ay":0.0, "alpha":2.96687, "fx":[-3.86397,-10.18309,3.86397,10.18309], "fy":[10.18309,-3.86397,-10.18309,3.86397]}, - {"t":0.39599, "x":5.60851, "y":5.5166, "heading":-0.38827, "vx":0.93106, "vy":0.3641, "omega":1.06401, "ax":0.0, "ay":0.0, "alpha":2.61976, "fx":[-3.71966,-8.86884,3.71966,8.86884], "fy":[8.86884,-3.71967,-8.86884,3.71966]}, - {"t":0.43199, "x":5.64202, "y":5.52971, "heading":-0.34997, "vx":0.93106, "vy":0.3641, "omega":1.15832, "ax":0.0, "ay":0.0, "alpha":2.30842, "fx":[-3.57447,-7.6836,3.57447,7.6836], "fy":[7.6836,-3.57447,-7.6836,3.57447]}, - {"t":0.46798, "x":5.67554, "y":5.54282, "heading":-0.30827, "vx":0.93106, "vy":0.3641, "omega":1.24142, "ax":0.0, "ay":0.0, "alpha":2.02939, "fx":[-3.42125,-6.61797,3.42125,6.61797], "fy":[6.61797,-3.42125,-6.61797,3.42125]}, - {"t":0.50398, "x":5.70906, "y":5.55592, "heading":-0.26358, "vx":0.93106, "vy":0.3641, "omega":1.31447, "ax":0.0, "ay":0.0, "alpha":1.77935, "fx":[-3.25595,-5.66276,3.25595,5.66276], "fy":[5.66276,-3.25595,-5.66276,3.25595]}, - {"t":0.53998, "x":5.74258, "y":5.56903, "heading":-0.21626, "vx":0.93106, "vy":0.3641, "omega":1.37853, "ax":0.0, "ay":0.0, "alpha":1.55517, "fx":[-3.07667,-4.80918,3.07667,4.80918], "fy":[4.80918,-3.07667,-4.80918,3.07667]}, - {"t":0.57598, "x":5.77609, "y":5.58214, "heading":-0.16664, "vx":0.93106, "vy":0.3641, "omega":1.43451, "ax":0.0, "ay":0.0, "alpha":1.35394, "fx":[-2.88295,-4.04886,2.88295,4.04886], "fy":[4.04886,-2.88295,-4.04886,2.88295]}, - {"t":0.61198, "x":5.80961, "y":5.59525, "heading":-0.115, "vx":0.93106, "vy":0.3641, "omega":1.48325, "ax":0.0, "ay":0.0, "alpha":1.17292, "fx":[-2.67522,-3.37394,2.67522,3.37394], "fy":[3.37394,-2.67522,-3.37394,2.67522]}, - {"t":0.64798, "x":5.84313, "y":5.60835, "heading":-0.0616, "vx":0.93106, "vy":0.3641, "omega":1.52548, "ax":0.0, "ay":0.0, "alpha":1.00958, "fx":[-2.4544,-2.77707,2.4544,2.77707], "fy":[2.77707,-2.4544,-2.77707,2.4544]}, - {"t":0.68398, "x":5.87664, "y":5.62146, "heading":-0.00669, "vx":0.93106, "vy":0.3641, "omega":1.56182, "ax":0.0, "ay":0.0, "alpha":0.8616, "fx":[-2.22157,-2.25148,2.22157,2.25148], "fy":[2.25148,-2.22157,-2.25148,2.22157]}, - {"t":0.71998, "x":5.91016, "y":5.63457, "heading":0.04954, "vx":0.93106, "vy":0.3641, "omega":1.59284, "ax":0.0, "ay":0.0, "alpha":0.72682, "fx":[-1.97781,-1.79096,1.97781,1.79096], "fy":[1.79096,-1.97781,-1.79096,1.97781]}, - {"t":0.75598, "x":5.94368, "y":5.64767, "heading":0.10688, "vx":0.93106, "vy":0.3641, "omega":1.619, "ax":0.0, "ay":0.0, "alpha":0.60323, "fx":[-1.72398,-1.3899,1.72398,1.3899], "fy":[1.3899,-1.72398,-1.3899,1.72398]}, - {"t":0.79197, "x":5.9772, "y":5.66078, "heading":0.16516, "vx":0.93106, "vy":0.3641, "omega":1.64072, "ax":0.0, "ay":0.0, "alpha":0.48897, "fx":[-1.46069,-1.04333,1.46069,1.04333], "fy":[1.04333,-1.46069,-1.04333,1.46069]}, - {"t":0.82797, "x":6.01071, "y":5.67389, "heading":0.22422, "vx":0.93106, "vy":0.3641, "omega":1.65832, "ax":0.0, "ay":0.0, "alpha":0.38231, "fx":[-1.18822,-0.7469,1.18822,0.7469], "fy":[0.7469,-1.18822,-0.7469,1.18822]}, - {"t":0.86397, "x":6.04423, "y":5.687, "heading":0.28392, "vx":0.93106, "vy":0.3641, "omega":1.67208, "ax":0.0, "ay":0.0, "alpha":0.2816, "fx":[-0.90648,-0.49695,0.90648,0.49695], "fy":[0.49695,-0.90647,-0.49695,0.90648]}, - {"t":0.89997, "x":6.07775, "y":5.7001, "heading":0.34411, "vx":0.93106, "vy":0.3641, "omega":1.68222, "ax":0.0, "ay":0.0, "alpha":0.18529, "fx":[-0.61504,-0.29051,0.61504,0.29051], "fy":[0.29052,-0.61504,-0.29051,0.61504]}, - {"t":0.93597, "x":6.11126, "y":5.71321, "heading":0.40467, "vx":0.93106, "vy":0.3641, "omega":1.68889, "ax":0.0, "ay":0.0, "alpha":0.09188, "fx":[-0.31314,-0.12534,0.31314,0.12534], "fy":[0.12534,-0.31314,-0.12534,0.31314]}, - {"t":0.97197, "x":6.14478, "y":5.72632, "heading":0.46547, "vx":0.93106, "vy":0.3641, "omega":1.6922, "ax":0.0, "ay":0.0, "alpha":-0.00008, "fx":[0.00029,0.0001,-0.00029,-0.0001], "fy":[-0.00009,0.00029,0.0001,-0.00029]}, - {"t":1.00797, "x":6.1783, "y":5.73942, "heading":0.52639, "vx":0.93106, "vy":0.3641, "omega":1.69219, "ax":0.0, "ay":0.0, "alpha":-0.09204, "fx":[0.32661,0.08654,-0.32661,-0.08654], "fy":[-0.08654,0.32661,0.08654,-0.32661]}, - {"t":1.04397, "x":6.21181, "y":5.75253, "heading":0.5873, "vx":0.93106, "vy":0.3641, "omega":1.68888, "ax":0.0, "ay":0.0, "alpha":-0.18542, "fx":[0.66738,0.13396,-0.66739,-0.13396], "fy":[-0.13396,0.66739,0.13396,-0.66738]}, - {"t":1.07997, "x":6.24533, "y":5.76564, "heading":0.6481, "vx":0.93106, "vy":0.3641, "omega":1.6822, "ax":0.0, "ay":0.0, "alpha":-0.2817, "fx":[1.02439,0.14154,-1.02439,-0.14154], "fy":[-0.14153,1.02439,0.14154,-1.02439]}, - {"t":1.11596, "x":6.27885, "y":5.77875, "heading":0.70866, "vx":0.93106, "vy":0.3641, "omega":1.67206, "ax":0.0, "ay":0.0, "alpha":-0.38236, "fx":[1.39953,0.10761,-1.39953,-0.10761], "fy":[-0.10761,1.39953,0.10761,-1.39953]}, - {"t":1.15196, "x":6.31237, "y":5.79185, "heading":0.76885, "vx":0.93106, "vy":0.3641, "omega":1.6583, "ax":0.0, "ay":0.0, "alpha":-0.48897, "fx":[1.79478,0.0297,-1.79478,-0.0297], "fy":[-0.0297,1.79478,0.0297,-1.79478]}, - {"t":1.18796, "x":6.34588, "y":5.80496, "heading":0.82855, "vx":0.93106, "vy":0.3641, "omega":1.6407, "ax":0.0, "ay":0.0, "alpha":-0.60317, "fx":[2.21221,-0.09552,-2.21221,0.09552], "fy":[0.09552,2.21221,-0.09552,-2.21221]}, - {"t":1.22396, "x":6.3794, "y":5.81807, "heading":0.88761, "vx":0.93106, "vy":0.3641, "omega":1.61898, "ax":0.0, "ay":0.0, "alpha":-0.7267, "fx":[2.65385,-0.27221,-2.65385,0.27221], "fy":[0.27221,2.65385,-0.27221,-2.65385]}, - {"t":1.25996, "x":6.41292, "y":5.83118, "heading":0.94589, "vx":0.93106, "vy":0.3641, "omega":1.59282, "ax":0.0, "ay":0.0, "alpha":-0.86144, "fx":[3.12174,-0.50537,-3.12174,0.50537], "fy":[0.50537,3.12174,-0.50537,-3.12174]}, - {"t":1.29596, "x":6.44643, "y":5.84428, "heading":1.00323, "vx":0.93106, "vy":0.3641, "omega":1.56181, "ax":0.0, "ay":0.0, "alpha":-1.00937, "fx":[3.61789,-0.80081,-3.61789,0.80081], "fy":[0.80081,3.61789,-0.80081,-3.61789]}, - {"t":1.33196, "x":6.47995, "y":5.85739, "heading":1.05946, "vx":0.93106, "vy":0.3641, "omega":1.52548, "ax":0.0, "ay":0.0, "alpha":-1.17267, "fx":[4.14427,-1.16509,-4.14427,1.16509], "fy":[1.16509,4.14426,-1.16509,-4.14427]}, - {"t":1.36796, "x":6.51347, "y":5.8705, "heading":1.11437, "vx":0.93106, "vy":0.3641, "omega":1.48326, "ax":0.0, "ay":0.0, "alpha":-1.35366, "fx":[4.70287,-1.60546,-4.70287,1.60546], "fy":[1.60546,4.70287,-1.60546,-4.70287]}, - {"t":1.40395, "x":6.54699, "y":5.8836, "heading":1.16777, "vx":0.93106, "vy":0.3641, "omega":1.43453, "ax":0.0, "ay":0.0, "alpha":-1.55487, "fx":[5.29581,-2.12978,-5.29581,2.12978], "fy":[2.12978,5.29581,-2.12978,-5.29581]}, - {"t":1.43995, "x":6.5805, "y":5.89671, "heading":1.21941, "vx":0.93106, "vy":0.3641, "omega":1.37856, "ax":0.0, "ay":0.0, "alpha":-1.77903, "fx":[5.92543,-2.74634,-5.92543,2.74634], "fy":[2.74634,5.92543,-2.74634,-5.92543]}, - {"t":1.47595, "x":6.61402, "y":5.90982, "heading":1.26904, "vx":0.93106, "vy":0.3641, "omega":1.31451, "ax":0.0, "ay":0.0, "alpha":-2.02906, "fx":[6.5945,-3.46372,-6.5945,3.46372], "fy":[3.46372,6.5945,-3.46372,-6.5945]}, - {"t":1.51195, "x":6.64754, "y":5.92293, "heading":1.31636, "vx":0.93106, "vy":0.3641, "omega":1.24147, "ax":0.0, "ay":0.0, "alpha":-2.30809, "fx":[7.30657,-4.29045,-7.30657,4.29046], "fy":[4.29046,7.30657,-4.29045,-7.30657]}, - {"t":1.54795, "x":6.68105, "y":5.93603, "heading":1.36105, "vx":0.93106, "vy":0.3641, "omega":1.15838, "ax":0.0, "ay":0.0, "alpha":-2.61942, "fx":[8.0663,-5.23478,-8.0663,5.23478], "fy":[5.23478,8.0663,-5.23478,-8.0663]}, - {"t":1.58395, "x":6.71457, "y":5.94914, "heading":1.40275, "vx":0.93106, "vy":0.3641, "omega":1.06409, "ax":0.0, "ay":0.0, "alpha":-2.96651, "fx":[8.88006,-6.3041,-8.88006,6.3041], "fy":[6.3041,8.88006,-6.3041,-8.88006]}, - {"t":1.61995, "x":6.74809, "y":5.96225, "heading":1.44105, "vx":0.93106, "vy":0.3641, "omega":0.9573, "ax":0.0, "ay":0.0, "alpha":-3.35293, "fx":[9.75653,-7.50442,-9.75653,7.50442], "fy":[7.50442,9.75653,-7.50442,-9.75653]}, - {"t":1.65595, "x":6.7816, "y":5.97536, "heading":1.47552, "vx":0.93106, "vy":0.3641, "omega":0.83659, "ax":0.0, "ay":0.0, "alpha":-3.78225, "fx":[10.7076,-8.83949,-10.7076,8.83949], "fy":[8.83949,10.7076,-8.83949,-10.7076]}, - {"t":1.69195, "x":6.81512, "y":5.98846, "heading":1.50563, "vx":0.93106, "vy":0.3641, "omega":0.70044, "ax":0.0, "ay":0.0, "alpha":-4.25799, "fx":[11.7493,-10.30981,-11.7493,10.30981], "fy":[10.30981,11.7493,-10.30981,-11.7493]}, - {"t":1.72794, "x":6.84864, "y":6.00157, "heading":1.53085, "vx":0.93106, "vy":0.3641, "omega":0.54715, "ax":0.0, "ay":0.0, "alpha":-4.78342, "fx":[12.90296,-11.91112,-12.90294,11.91114], "fy":[11.91111,12.90293,-11.91115,-12.90297]}, - {"t":1.76394, "x":6.88216, "y":6.01468, "heading":1.55054, "vx":0.93106, "vy":0.3641, "omega":0.37496, "ax":-0.00001, "ay":-0.00004, "alpha":-5.36144, "fx":[14.19614,-13.63297,-14.1966,13.63243], "fy":[13.63208,14.19573,-13.63333,-14.19701]}, - {"t":1.79994, "x":6.91567, "y":6.02778, "heading":1.56404, "vx":0.93106, "vy":0.3641, "omega":0.18195, "ax":-1.86317, "ay":-0.72857, "alpha":-4.97695, "fx":[-20.23919,-44.57749,-42.79449,-19.15708], "fy":[1.45883,1.44431,-24.50694,-27.96708]}, - {"t":1.83594, "x":6.94798, "y":6.04042, "heading":1.57059, "vx":0.86399, "vy":0.33787, "omega":0.00279, "ax":-5.98629, "ay":-2.34102, "alpha":-0.03373, "fx":[-101.86028,-101.90766,-101.79034,-101.74232], "fy":[-39.72752,-39.61012,-39.9123,-40.03032]}, - {"t":1.87194, "x":6.97521, "y":6.05107, "heading":1.57069, "vx":0.64849, "vy":0.2536, "omega":0.00157, "ax":-6.00069, "ay":-2.34665, "alpha":-0.01873, "fx":[-102.0899,-102.11594,-102.05039,-102.02414], "fy":[-39.8644,-39.79882,-39.96708,-40.03285]}, - {"t":1.90794, "x":6.99466, "y":6.05867, "heading":1.57075, "vx":0.43247, "vy":0.16912, "omega":0.0009, "ax":-6.0055, "ay":-2.34853, "alpha":-0.01373, "fx":[-102.1665,-102.18553,-102.13738,-102.11825], "fy":[-39.9101,-39.86194,-39.98537,-40.03363]}, - {"t":1.94394, "x":7.00634, "y":6.06324, "heading":1.57078, "vx":0.21628, "vy":0.08458, "omega":0.0004, "ax":-6.00791, "ay":-2.34947, "alpha":-0.01123, "fx":[-102.20481,-102.22034,-102.18093,-102.16532], "fy":[-39.93295,-39.89353,-39.99453,-40.03401]}, - {"t":1.97994, "x":7.01023, "y":6.06476, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":5.21058, "y":5.29558, "heading":-0.51765, "vx":0.0, "vy":0.0, "omega":0.0, "ax":5.93225, "ay":2.53549, "alpha":0.00947, "fx":[100.8788,100.90207,100.93285,100.90962], "fy":[43.19115,43.13655,43.06463,43.11927]}, + {"t":0.03709, "x":5.21466, "y":5.29732, "heading":-0.51765, "vx":0.22002, "vy":0.09404, "omega":0.00035, "ax":5.92999, "ay":2.53452, "alpha":0.01155, "fx":[100.83453,100.86287,100.90044,100.87214], "fy":[43.18865,43.12205,43.03434,43.10101]}, + {"t":0.07418, "x":5.2269, "y":5.30255, "heading":-0.51764, "vx":0.43996, "vy":0.18804, "omega":0.00078, "ax":5.92548, "ay":2.5326, "alpha":0.01572, "fx":[100.74595,100.78443,100.83558,100.79719], "fy":[43.18364,43.09302,42.97376,43.06448]}, + {"t":0.11127, "x":5.24729, "y":5.31127, "heading":-0.51761, "vx":0.65973, "vy":0.28197, "omega":0.00136, "ax":5.91195, "ay":2.52681, "alpha":0.02826, "fx":[100.48016,100.54872,100.64078,100.57247], "fy":[43.16844,43.00579,42.792,42.95498]}, + {"t":0.14836, "x":5.27582, "y":5.32346, "heading":-0.51756, "vx":0.87899, "vy":0.37569, "omega":0.00241, "ax":1.08629, "ay":0.46429, "alpha":4.97423, "fx":[13.84618,0.84061,24.12154,35.1013], "fy":[26.03606,3.32343,-10.14314,12.3735]}, + {"t":0.18544, "x":5.30917, "y":5.33772, "heading":-0.51747, "vx":0.91928, "vy":0.39291, "omega":0.1869, "ax":0.00001, "ay":0.0, "alpha":4.72555, "fx":[-4.59236,-16.72858,4.59283,16.72903], "fy":[16.72885,-4.59255,-16.72876,4.59264]}, + {"t":0.22253, "x":5.34327, "y":5.35229, "heading":-0.51054, "vx":0.91928, "vy":0.39291, "omega":0.36216, "ax":0.0, "ay":0.0, "alpha":4.19747, "fx":[-4.18228,-14.83074,4.18228,14.83074], "fy":[14.83074,-4.18228,-14.83074,4.18228]}, + {"t":0.25962, "x":5.37736, "y":5.36686, "heading":-0.4971, "vx":0.91928, "vy":0.39291, "omega":0.51784, "ax":0.0, "ay":0.0, "alpha":3.72142, "fx":[-3.88423,-13.09774,3.88423,13.09774], "fy":[13.09774,-3.88423,-13.09774,3.88423]}, + {"t":0.29671, "x":5.41146, "y":5.38143, "heading":-0.4779, "vx":0.91928, "vy":0.39291, "omega":0.65587, "ax":0.0, "ay":0.0, "alpha":3.29372, "fx":[-3.65981,-11.52425,3.65981,11.52425], "fy":[11.52425,-3.65981,-11.52425,3.65981]}, + {"t":0.3338, "x":5.44555, "y":5.39601, "heading":-0.45357, "vx":0.91928, "vy":0.39291, "omega":0.77803, "ax":0.0, "ay":0.0, "alpha":2.91051, "fx":[-3.48075,-10.1018,3.48075,10.1018], "fy":[10.1018,-3.48075,-10.1018,3.48075]}, + {"t":0.37089, "x":5.47965, "y":5.41058, "heading":-0.42472, "vx":0.91928, "vy":0.39291, "omega":0.88597, "ax":0.0, "ay":0.0, "alpha":2.56794, "fx":[-3.32693,-8.82048,3.32693,8.82048], "fy":[8.82048,-3.32693,-8.82048,3.32693]}, + {"t":0.40798, "x":5.51374, "y":5.42515, "heading":-0.39186, "vx":0.91928, "vy":0.39291, "omega":0.98122, "ax":0.0, "ay":0.0, "alpha":2.2622, "fx":[-3.18453,-7.66984,3.18453,7.66984], "fy":[7.66984,-3.18453,-7.66984,3.18453]}, + {"t":0.44507, "x":5.54784, "y":5.43972, "heading":-0.35546, "vx":0.91928, "vy":0.39291, "omega":1.06512, "ax":0.0, "ay":0.0, "alpha":1.98967, "fx":[-3.04447,-6.63945,3.04447,6.63945], "fy":[6.63945,-3.04447,-6.63946,3.04447]}, + {"t":0.48215, "x":5.58193, "y":5.4543, "heading":-0.31596, "vx":0.91928, "vy":0.39291, "omega":1.13891, "ax":0.0, "ay":0.0, "alpha":1.7469, "fx":[-2.90113,-5.71922,2.90113,5.71922], "fy":[5.71922,-2.90113,-5.71922,2.90113]}, + {"t":0.51924, "x":5.61603, "y":5.46887, "heading":-0.27372, "vx":0.91928, "vy":0.39291, "omega":1.2037, "ax":0.0, "ay":0.0, "alpha":1.53068, "fx":[-2.7514,-4.89951,2.7514,4.89951], "fy":[4.89951,-2.7514,-4.89951,2.7514]}, + {"t":0.55633, "x":5.65012, "y":5.48344, "heading":-0.22907, "vx":0.91928, "vy":0.39291, "omega":1.26047, "ax":0.0, "ay":0.0, "alpha":1.33803, "fx":[-2.59387,-4.17128,2.59387,4.17128], "fy":[4.17128,-2.59387,-4.17128,2.59387]}, + {"t":0.59342, "x":5.68422, "y":5.49801, "heading":-0.18233, "vx":0.91928, "vy":0.39291, "omega":1.3101, "ax":0.0, "ay":0.0, "alpha":1.16623, "fx":[-2.42826,-3.52607,2.42826,3.52607], "fy":[3.52607,-2.42826,-3.52607,2.42826]}, + {"t":0.63051, "x":5.71831, "y":5.51259, "heading":-0.13374, "vx":0.91928, "vy":0.39291, "omega":1.35335, "ax":0.0, "ay":0.0, "alpha":1.01277, "fx":[-2.25496,-2.95605,2.25496,2.95605], "fy":[2.95605,-2.25496,-2.95605,2.25496]}, + {"t":0.6676, "x":5.75241, "y":5.52716, "heading":-0.08354, "vx":0.91928, "vy":0.39291, "omega":1.39092, "ax":0.0, "ay":0.0, "alpha":0.87536, "fx":[-2.07474,-2.45396,2.07474,2.45396], "fy":[2.45396,-2.07474,-2.45396,2.07474]}, + {"t":0.70469, "x":5.7865, "y":5.54173, "heading":-0.03195, "vx":0.91928, "vy":0.39291, "omega":1.42338, "ax":0.0, "ay":0.0, "alpha":0.7519, "fx":[-1.88845,-2.01317,1.88845,2.01317], "fy":[2.01317,-1.88845,-2.01317,1.88845]}, + {"t":0.74178, "x":5.8206, "y":5.5563, "heading":0.02084, "vx":0.91928, "vy":0.39291, "omega":1.45127, "ax":0.0, "ay":0.0, "alpha":0.6405, "fx":[-1.69692,-1.62763,1.69692,1.62763], "fy":[1.62763,-1.69692,-1.62763,1.69692]}, + {"t":0.77886, "x":5.85469, "y":5.57088, "heading":0.07466, "vx":0.91928, "vy":0.39291, "omega":1.47502, "ax":0.0, "ay":0.0, "alpha":0.53942, "fx":[-1.50079,-1.29189,1.50079,1.29189], "fy":[1.29189,-1.50079,-1.29189,1.50079]}, + {"t":0.81595, "x":5.88879, "y":5.58545, "heading":0.12937, "vx":0.91928, "vy":0.39291, "omega":1.49503, "ax":0.0, "ay":0.0, "alpha":0.44706, "fx":[-1.3005,-1.00107,1.3005,1.00107], "fy":[1.00107,-1.3005,-1.00107,1.3005]}, + {"t":0.85304, "x":5.92288, "y":5.60002, "heading":0.18482, "vx":0.91928, "vy":0.39291, "omega":1.51161, "ax":0.0, "ay":0.0, "alpha":0.36194, "fx":[-1.09619,-0.75087,1.09619,0.75087], "fy":[0.75087,-1.09619,-0.75087,1.09619]}, + {"t":0.89013, "x":5.95698, "y":5.61459, "heading":0.24088, "vx":0.91928, "vy":0.39291, "omega":1.52504, "ax":0.0, "ay":0.0, "alpha":0.2827, "fx":[-0.88773,-0.53759,0.88773,0.53759], "fy":[0.53759,-0.88773,-0.53759,0.88773]}, + {"t":0.92722, "x":5.99107, "y":5.62917, "heading":0.29745, "vx":0.91928, "vy":0.39291, "omega":1.53552, "ax":0.0, "ay":0.0, "alpha":0.20807, "fx":[-0.67469,-0.3581,0.67469,0.3581], "fy":[0.3581,-0.67469,-0.3581,0.67469]}, + {"t":0.96431, "x":6.02517, "y":5.64374, "heading":0.3544, "vx":0.91928, "vy":0.39291, "omega":1.54324, "ax":0.0, "ay":0.0, "alpha":0.13683, "fx":[-0.45637,-0.20986,0.45637,0.20985], "fy":[0.20986,-0.45637,-0.20985,0.45637]}, + {"t":1.0014, "x":6.05926, "y":5.65831, "heading":0.41163, "vx":0.91928, "vy":0.39291, "omega":1.54831, "ax":0.0, "ay":0.0, "alpha":0.06782, "fx":[-0.2318,-0.09091,0.2318,0.09091], "fy":[0.09091,-0.2318,-0.09091,0.2318]}, + {"t":1.03849, "x":6.09336, "y":5.67288, "heading":0.46906, "vx":0.91928, "vy":0.39291, "omega":1.55083, "ax":0.0, "ay":0.0, "alpha":-0.00007, "fx":[0.00024,0.00008,-0.00024,-0.00008], "fy":[-0.00008,0.00024,0.00008,-0.00024]}, + {"t":1.07558, "x":6.12745, "y":5.68746, "heading":0.52658, "vx":0.91928, "vy":0.39291, "omega":1.55083, "ax":0.0, "ay":0.0, "alpha":-0.06796, "fx":[0.24117,0.06385,-0.24117,-0.06385], "fy":[-0.06385,0.24117,0.06385,-0.24117]}, + {"t":1.11266, "x":6.16155, "y":5.70203, "heading":0.58409, "vx":0.91928, "vy":0.39291, "omega":1.54831, "ax":0.0, "ay":0.0, "alpha":-0.13695, "fx":[0.4926,0.10052,-0.4926,-0.10052], "fy":[-0.10052,0.4926,0.10053,-0.4926]}, + {"t":1.14975, "x":6.19564, "y":5.7166, "heading":0.64152, "vx":0.91928, "vy":0.39291, "omega":1.54323, "ax":0.0, "ay":0.0, "alpha":-0.20817, "fx":[0.75632,0.10958,-0.75632,-0.10958], "fy":[-0.10958,0.75632,0.10958,-0.75632]}, + {"t":1.18684, "x":6.22974, "y":5.73117, "heading":0.69876, "vx":0.91928, "vy":0.39291, "omega":1.53551, "ax":0.0, "ay":0.0, "alpha":-0.28278, "fx":[1.03422,0.08983,-1.03422,-0.08983], "fy":[-0.08983,1.03422,0.08983,-1.03422]}, + {"t":1.22393, "x":6.26383, "y":5.74575, "heading":0.75571, "vx":0.91928, "vy":0.39291, "omega":1.52502, "ax":0.0, "ay":0.0, "alpha":-0.36199, "fx":[1.32831,0.03945,-1.32831,-0.03945], "fy":[-0.03945,1.32831,0.03945,-1.32831]}, + {"t":1.26102, "x":6.29793, "y":5.76032, "heading":0.81227, "vx":0.91928, "vy":0.39291, "omega":1.51159, "ax":0.0, "ay":0.0, "alpha":-0.44708, "fx":[1.64067,-0.04409,-1.64067,0.04409], "fy":[0.04409,1.64067,-0.04409,-1.64067]}, + {"t":1.29811, "x":6.33202, "y":5.77489, "heading":0.86833, "vx":0.91928, "vy":0.39291, "omega":1.49501, "ax":0.0, "ay":0.0, "alpha":-0.53942, "fx":[1.97342,-0.16403,-1.97342,0.16404], "fy":[0.16403,1.97342,-0.16404,-1.97342]}, + {"t":1.3352, "x":6.36612, "y":5.78946, "heading":0.92378, "vx":0.91928, "vy":0.39291, "omega":1.475, "ax":0.0, "ay":0.0, "alpha":-0.64047, "fx":[2.32874,-0.32432,-2.32874,0.32432], "fy":[0.32432,2.32874,-0.32432,-2.32874]}, + {"t":1.37229, "x":6.40021, "y":5.80404, "heading":0.97848, "vx":0.91928, "vy":0.39291, "omega":1.45125, "ax":0.0, "ay":0.0, "alpha":-0.75185, "fx":[2.70879,-0.52963,-2.70879,0.52963], "fy":[0.52963,2.70879,-0.52963,-2.70879]}, + {"t":1.40937, "x":6.43431, "y":5.81861, "heading":1.03231, "vx":0.91928, "vy":0.39291, "omega":1.42336, "ax":0.0, "ay":0.0, "alpha":-0.87528, "fx":[3.11577,-0.78534,-3.11577,0.78534], "fy":[0.78534,3.11577,-0.78534,-3.11577]}, + {"t":1.44646, "x":6.4684, "y":5.83318, "heading":1.0851, "vx":0.91928, "vy":0.39291, "omega":1.3909, "ax":0.0, "ay":0.0, "alpha":-1.01269, "fx":[3.55192,-1.09758,-3.55192,1.09758], "fy":[1.09758,3.55192,-1.09758,-3.55192]}, + {"t":1.48355, "x":6.5025, "y":5.84775, "heading":1.13669, "vx":0.91928, "vy":0.39291, "omega":1.35334, "ax":0.0, "ay":0.0, "alpha":-1.16614, "fx":[4.01954,-1.47312,-4.01954,1.47312], "fy":[1.47312,4.01954,-1.47312,-4.01954]}, + {"t":1.52064, "x":6.53659, "y":5.86233, "heading":1.18688, "vx":0.91928, "vy":0.39291, "omega":1.31009, "ax":0.0, "ay":0.0, "alpha":-1.33794, "fx":[4.5211,-1.91939,-4.5211,1.91939], "fy":[1.91939,4.5211,-1.91939,-4.5211]}, + {"t":1.55773, "x":6.57069, "y":5.8769, "heading":1.23547, "vx":0.91928, "vy":0.39291, "omega":1.26047, "ax":0.0, "ay":0.0, "alpha":-1.53059, "fx":[5.05932,-2.44438,-5.05932,2.44438], "fy":[2.44438,5.05932,-2.44438,-5.05932]}, + {"t":1.59482, "x":6.60478, "y":5.89147, "heading":1.28222, "vx":0.91928, "vy":0.39291, "omega":1.2037, "ax":0.0, "ay":0.0, "alpha":-1.74681, "fx":[5.63737,-3.05648,-5.63737,3.05648], "fy":[3.05648,5.63737,-3.05648,-5.63737]}, + {"t":1.63191, "x":6.63888, "y":5.90604, "heading":1.32686, "vx":0.91928, "vy":0.39291, "omega":1.13891, "ax":0.0, "ay":0.0, "alpha":-1.98959, "fx":[6.25912,-3.76437,-6.25912,3.76437], "fy":[3.76437,6.25912,-3.76437,-6.25912]}, + {"t":1.669, "x":6.67297, "y":5.92062, "heading":1.3691, "vx":0.91928, "vy":0.39291, "omega":1.06512, "ax":0.0, "ay":0.0, "alpha":-2.26213, "fx":[6.92943,-4.57673,-6.92943,4.57673], "fy":[4.57673,6.92943,-4.57673,-6.92943]}, + {"t":1.70608, "x":6.70707, "y":5.93519, "heading":1.40861, "vx":0.91928, "vy":0.39291, "omega":0.98122, "ax":0.0, "ay":0.0, "alpha":-2.56788, "fx":[7.65467,-5.50191,-7.65467,5.50191], "fy":[5.50191,7.65467,-5.50191,-7.65467]}, + {"t":1.74317, "x":6.74116, "y":5.94976, "heading":1.445, "vx":0.91928, "vy":0.39291, "omega":0.88598, "ax":0.0, "ay":0.0, "alpha":-2.91046, "fx":[8.44324,-6.54746,-8.44324,6.54746], "fy":[6.54746,8.44324,-6.54746,-8.44324]}, + {"t":1.78026, "x":6.77526, "y":5.96433, "heading":1.47786, "vx":0.91928, "vy":0.39291, "omega":0.77804, "ax":0.0, "ay":0.0, "alpha":-3.29366, "fx":[9.30633,-7.71945,-9.30633,7.71945], "fy":[7.71945,9.30633,-7.71945,-9.30633]}, + {"t":1.81735, "x":6.80935, "y":5.97891, "heading":1.50672, "vx":0.91928, "vy":0.39291, "omega":0.65588, "ax":0.0, "ay":0.0, "alpha":-3.72137, "fx":[10.2588,-9.02162,-10.2588,9.02162], "fy":[9.02162,10.2588,-9.02162,-10.2588]}, + {"t":1.85444, "x":6.84345, "y":5.99348, "heading":1.53104, "vx":0.91928, "vy":0.39291, "omega":0.51786, "ax":0.0, "ay":0.0, "alpha":-4.19742, "fx":[11.32021,-10.45414,-11.32021,10.45414], "fy":[10.45414,11.32021,-10.45414,-11.32021]}, + {"t":1.89153, "x":6.87754, "y":6.00805, "heading":1.55025, "vx":0.91928, "vy":0.39291, "omega":0.36218, "ax":-0.00001, "ay":-0.00001, "alpha":-4.72549, "fx":[12.51584,-12.01214,-12.51618,12.01178], "fy":[12.01179,12.51583,-12.01213,-12.51619]}, + {"t":1.92862, "x":6.91164, "y":6.02262, "heading":1.56368, "vx":0.91928, "vy":0.39291, "omega":0.18692, "ax":-1.08629, "ay":-0.46428, "alpha":-4.97472, "fx":[-5.88236,-31.47303,-30.70089,-5.85369], "fy":[5.44312,5.19629,-20.23056,-21.99792]}, + {"t":1.96571, "x":6.94499, "y":6.03688, "heading":1.57061, "vx":0.87899, "vy":0.37569, "omega":0.00241, "ax":-5.91195, "ay":-2.52681, "alpha":-0.02826, "fx":[-100.59004,-100.63607,-100.53123,-100.48473], "fy":[-42.90922,-42.80429,-43.05126,-43.15658]}, + {"t":2.00279, "x":6.97352, "y":6.04907, "heading":1.5707, "vx":0.65973, "vy":0.28197, "omega":0.00136, "ax":-5.92548, "ay":-2.5326, "alpha":-0.01572, "fx":[-100.80744,-100.83285,-100.77419,-100.74864], "fy":[-43.03919,-42.98051,-43.11823,-43.17703]}, + {"t":2.03988, "x":6.99391, "y":6.05779, "heading":1.57075, "vx":0.43996, "vy":0.18804, "omega":0.00078, "ax":-5.92999, "ay":-2.53452, "alpha":-0.01155, "fx":[-100.87979,-100.89841,-100.85523,-100.83654], "fy":[-43.08247,-43.03929,-43.14054,-43.18379]}, + {"t":2.07697, "x":7.00615, "y":6.06302, "heading":1.57078, "vx":0.22002, "vy":0.09404, "omega":0.00035, "ax":-5.93225, "ay":-2.53549, "alpha":-0.00947, "fx":[-100.91594,-100.93117,-100.89575,-100.88047], "fy":[-43.1041,-43.06868,-43.15169,-43.18716]}, + {"t":2.11406, "x":7.01023, "y":6.06476, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/F_PATH_4.traj b/src/main/deploy/choreo/F_PATH_4.traj index ae77c880..885c0670 100644 --- a/src/main/deploy/choreo/F_PATH_4.traj +++ b/src/main/deploy/choreo/F_PATH_4.traj @@ -3,24 +3,26 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":7.010232925415039, "y":6.064763069152832, "heading":1.5707963267948966, "intervals":107, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":6.25162410736084, "y":4.035482883453369, "heading":-1.5707963267948966, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":7.010232925415039, "y":6.064763069152832, "heading":1.5707963267948966, "intervals":62, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":6.7965826988220215, "y":4.032148838043213, "heading":-1.5604875077843534, "intervals":22, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":5.9229350090026855, "y":4.018707752227783, "heading":-1.5707963267948966, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":0.0, "y":0.0, "w":17.548, "h":8.052}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":0.5}}, "enabled":true}], + {"from":"first", "to":2, "data":{"type":"MaxVelocity", "props":{"max":1.0}}, "enabled":true}], "targetDt":0.05 }, "params":{ "waypoints":[ - {"x":{"exp":"7.010232925415039 m", "val":7.010232925415039}, "y":{"exp":"6.064763069152832 m", "val":6.064763069152832}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":107, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, - {"x":{"exp":"6.25162410736084 m", "val":6.25162410736084}, "y":{"exp":"4.035482883453369 m", "val":4.035482883453369}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], + {"x":{"exp":"7.010232925415039 m", "val":7.010232925415039}, "y":{"exp":"6.064763069152832 m", "val":6.064763069152832}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":62, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"6.7965826988220215 m", "val":6.7965826988220215}, "y":{"exp":"4.032148838043213 m", "val":4.032148838043213}, "heading":{"exp":"-1.5604875077843534 rad", "val":-1.5604875077843534}, "intervals":22, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"5.9229350090026855 m", "val":5.9229350090026855}, "y":{"exp":"4.018707752227783 m", "val":4.018707752227783}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":41, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"last", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, {"from":"first", "to":"last", "data":{"type":"KeepInRectangle", "props":{"x":{"exp":"0 m", "val":0.0}, "y":{"exp":"0 m", "val":0.0}, "w":{"exp":"17.548 m", "val":17.548}, "h":{"exp":"8.052 m", "val":8.052}}}, "enabled":false}, - {"from":"first", "to":"last", "data":{"type":"MaxVelocity", "props":{"max":{"exp":"0.5 m / s", "val":0.5}}}, "enabled":true}], + {"from":"first", "to":2, "data":{"type":"MaxVelocity", "props":{"max":{"exp":"1 m / s", "val":1.0}}}, "enabled":true}], "targetDt":{ "exp":"0.05 s", "val":0.05 @@ -28,116 +30,93 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,4.41378], + "waypoints":[0.0,2.13409,3.09778], "samples":[ - {"t":0.0, "x":7.01023, "y":6.06476, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-2.25759, "ay":-6.03905, "alpha":0.00573, "fx":[-38.41721,-38.36512,-38.38455,-38.43666], "fy":[-102.71641,-102.73584,-102.72848,-102.70903]}, - {"t":0.04125, "x":7.00831, "y":6.05963, "heading":1.5708, "vx":-0.09313, "vy":-0.24911, "omega":0.00024, "ax":-1.98576, "ay":-5.3119, "alpha":0.36993, "fx":[-34.79463,-31.78904,-32.72713,-35.79784], "fy":[-90.28237,-91.22856,-90.45099,-89.45396]}, - {"t":0.0825, "x":7.00278, "y":6.04483, "heading":1.57081, "vx":-0.17504, "vy":-0.46823, "omega":0.0155, "ax":-0.00001, "ay":-0.00004, "alpha":2.49947, "fx":[-6.48838,6.48802,6.48789,-6.48851], "fy":[-6.48893,-6.48879,6.48762,6.48748]}, - {"t":0.12375, "x":6.99556, "y":6.02552, "heading":1.57145, "vx":-0.17504, "vy":-0.46823, "omega":0.1186, "ax":0.0, "ay":0.0, "alpha":2.20025, "fx":[-5.70776,5.71518,5.70776,-5.71518], "fy":[-5.71519,-5.70776,5.71519,5.70776]}, - {"t":0.165, "x":6.98834, "y":6.0062, "heading":1.57634, "vx":-0.17504, "vy":-0.46823, "omega":0.20936, "ax":0.0, "ay":0.0, "alpha":1.9359, "fx":[-4.99735,5.05305,4.99735,-5.05305], "fy":[-5.05305,-4.99735,5.05305,4.99735]}, - {"t":0.20625, "x":6.98112, "y":5.98689, "heading":1.58497, "vx":-0.17504, "vy":-0.46823, "omega":0.28922, "ax":0.0, "ay":0.0, "alpha":1.70263, "fx":[-4.35662,4.48195,4.35662,-4.48195], "fy":[-4.48195,-4.35662,4.48195,4.35662]}, - {"t":0.2475, "x":6.9739, "y":5.96757, "heading":1.5969, "vx":-0.17504, "vy":-0.46823, "omega":0.35945, "ax":0.0, "ay":0.0, "alpha":1.49696, "fx":[-3.78308,3.98597,3.78308,-3.98597], "fy":[-3.98597,-3.78308,3.98597,3.78308]}, - {"t":0.28875, "x":6.96668, "y":5.94826, "heading":1.61173, "vx":-0.17504, "vy":-0.46823, "omega":0.4212, "ax":0.0, "ay":0.0, "alpha":1.31577, "fx":[-3.27287,3.55242,3.27287,-3.55242], "fy":[-3.55242,-3.27287,3.55242,3.27287]}, - {"t":0.33, "x":6.95946, "y":5.92894, "heading":1.62911, "vx":-0.17504, "vy":-0.46823, "omega":0.47548, "ax":0.0, "ay":0.0, "alpha":1.15624, "fx":[-2.82138,3.17121,2.82138,-3.17121], "fy":[-3.17121,-2.82138,3.17121,2.82138]}, - {"t":0.37125, "x":6.95224, "y":5.90963, "heading":1.64872, "vx":-0.17504, "vy":-0.46823, "omega":0.52317, "ax":0.0, "ay":0.0, "alpha":1.01585, "fx":[-2.42369,2.83425,2.42369,-2.83425], "fy":[-2.83425,-2.42369,2.83425,2.42369]}, - {"t":0.4125, "x":6.94502, "y":5.89031, "heading":1.6703, "vx":-0.17504, "vy":-0.46823, "omega":0.56508, "ax":0.0, "ay":0.0, "alpha":0.89236, "fx":[-2.07484,2.53508,2.07484,-2.53508], "fy":[-2.53508,-2.07484,2.53508,2.07484]}, - {"t":0.45375, "x":6.9378, "y":5.871, "heading":1.69361, "vx":-0.17504, "vy":-0.46823, "omega":0.60189, "ax":0.0, "ay":0.0, "alpha":0.78378, "fx":[-1.76998,2.26847,1.76998,-2.26847], "fy":[-2.26847,-1.76998,2.26847,1.76998]}, - {"t":0.495, "x":6.93058, "y":5.85168, "heading":1.71844, "vx":-0.17504, "vy":-0.46823, "omega":0.63422, "ax":0.0, "ay":0.0, "alpha":0.68832, "fx":[-1.50448,2.03018,1.50448,-2.03018], "fy":[-2.03018,-1.50448,2.03018,1.50448]}, - {"t":0.53625, "x":6.92336, "y":5.83237, "heading":1.7446, "vx":-0.17504, "vy":-0.46823, "omega":0.66261, "ax":0.0, "ay":0.0, "alpha":0.60443, "fx":[-1.27404,1.8167,1.27404,-1.8167], "fy":[-1.8167,-1.27404,1.8167,1.27404]}, - {"t":0.5775, "x":6.91614, "y":5.81305, "heading":1.77193, "vx":-0.17504, "vy":-0.46823, "omega":0.68754, "ax":0.0, "ay":0.0, "alpha":0.53072, "fx":[-1.07466,1.62513,1.07466,-1.62513], "fy":[-1.62513,-1.07466,1.62513,1.07466]}, - {"t":0.61875, "x":6.90892, "y":5.79374, "heading":1.80029, "vx":-0.17504, "vy":-0.46823, "omega":0.70944, "ax":0.0, "ay":0.0, "alpha":0.46597, "fx":[-0.90269,1.45302,0.90269,-1.45302], "fy":[-1.45302,-0.90269,1.45302,0.90269]}, - {"t":0.66, "x":6.9017, "y":5.77442, "heading":1.82956, "vx":-0.17504, "vy":-0.46823, "omega":0.72866, "ax":0.0, "ay":0.0, "alpha":0.40909, "fx":[-0.75483,1.29829,0.75483,-1.29829], "fy":[-1.29829,-0.75483,1.29829,0.75483]}, - {"t":0.70126, "x":6.89447, "y":5.75511, "heading":1.85962, "vx":-0.17504, "vy":-0.46823, "omega":0.74553, "ax":0.0, "ay":0.0, "alpha":0.35913, "fx":[-0.6281,1.15914,0.6281,-1.15914], "fy":[-1.15914,-0.6281,1.15914,0.6281]}, - {"t":0.74251, "x":6.88725, "y":5.73579, "heading":1.89037, "vx":-0.17504, "vy":-0.46823, "omega":0.76035, "ax":0.0, "ay":0.0, "alpha":0.31526, "fx":[-0.51982,1.03401,0.51982,-1.03401], "fy":[-1.03401,-0.51982,1.03401,0.51982]}, - {"t":0.78376, "x":6.88003, "y":5.71648, "heading":1.92173, "vx":-0.17504, "vy":-0.46823, "omega":0.77335, "ax":0.0, "ay":0.0, "alpha":0.27673, "fx":[-0.42761,0.92151,0.42761,-0.92151], "fy":[-0.92151,-0.42761,0.92151,0.42761]}, - {"t":0.82501, "x":6.87281, "y":5.69717, "heading":1.95364, "vx":-0.17504, "vy":-0.46823, "omega":0.78477, "ax":0.0, "ay":0.0, "alpha":0.2429, "fx":[-0.34935,0.82042,0.34935,-0.82042], "fy":[-0.82042,-0.34935,0.82042,0.34935]}, - {"t":0.86626, "x":6.86559, "y":5.67785, "heading":1.98601, "vx":-0.17504, "vy":-0.46823, "omega":0.79479, "ax":0.0, "ay":0.0, "alpha":0.2132, "fx":[-0.28316,0.72965,0.28316,-0.72965], "fy":[-0.72965,-0.28316,0.72965,0.28316]}, - {"t":0.90751, "x":6.85837, "y":5.65854, "heading":2.01879, "vx":-0.17504, "vy":-0.46823, "omega":0.80358, "ax":0.0, "ay":0.0, "alpha":0.18712, "fx":[-0.2274,0.6482,0.2274,-0.6482], "fy":[-0.6482,-0.2274,0.6482,0.2274]}, - {"t":0.94876, "x":6.85115, "y":5.63922, "heading":2.05194, "vx":-0.17504, "vy":-0.46823, "omega":0.8113, "ax":0.0, "ay":0.0, "alpha":0.16423, "fx":[-0.18061,0.5752,0.18061,-0.5752], "fy":[-0.5752,-0.18061,0.5752,0.18061]}, - {"t":0.99001, "x":6.84393, "y":5.61991, "heading":2.08541, "vx":-0.17504, "vy":-0.46823, "omega":0.81807, "ax":0.0, "ay":0.0, "alpha":0.14413, "fx":[-0.14153,0.50982,0.14153,-0.50982], "fy":[-0.50982,-0.14153,0.50982,0.14153]}, - {"t":1.03126, "x":6.83671, "y":5.60059, "heading":2.11915, "vx":-0.17504, "vy":-0.46823, "omega":0.82402, "ax":0.0, "ay":0.0, "alpha":0.12648, "fx":[-0.10903,0.45133,0.10903,-0.45133], "fy":[-0.45133,-0.10903,0.45133,0.10903]}, - {"t":1.07251, "x":6.82949, "y":5.58128, "heading":2.15314, "vx":-0.17504, "vy":-0.46823, "omega":0.82924, "ax":0.0, "ay":0.0, "alpha":0.11099, "fx":[-0.08216,0.39907,0.08216,-0.39907], "fy":[-0.39907,-0.08216,0.39907,0.08216]}, - {"t":1.11376, "x":6.82227, "y":5.56196, "heading":2.18735, "vx":-0.17504, "vy":-0.46823, "omega":0.83382, "ax":0.0, "ay":0.0, "alpha":0.09739, "fx":[-0.06008,0.35243,0.06008,-0.35243], "fy":[-0.35243,-0.06008,0.35243,0.06008]}, - {"t":1.15501, "x":6.81505, "y":5.54265, "heading":2.22175, "vx":-0.17504, "vy":-0.46823, "omega":0.83783, "ax":0.0, "ay":0.0, "alpha":0.08544, "fx":[-0.04205,0.31084,0.04205,-0.31084], "fy":[-0.31084,-0.04205,0.31084,0.04205]}, - {"t":1.19626, "x":6.80783, "y":5.52333, "heading":2.25631, "vx":-0.17504, "vy":-0.46823, "omega":0.84136, "ax":0.0, "ay":0.0, "alpha":0.07496, "fx":[-0.02744,0.2738,0.02744,-0.2738], "fy":[-0.2738,-0.02744,0.2738,0.02744]}, - {"t":1.23751, "x":6.80061, "y":5.50402, "heading":2.29101, "vx":-0.17504, "vy":-0.46823, "omega":0.84445, "ax":0.0, "ay":0.0, "alpha":0.06575, "fx":[-0.01572,0.24086,0.01572,-0.24086], "fy":[-0.24086,-0.01572,0.24086,0.01572]}, - {"t":1.27876, "x":6.79339, "y":5.4847, "heading":2.32585, "vx":-0.17504, "vy":-0.46823, "omega":0.84716, "ax":0.0, "ay":0.0, "alpha":0.05766, "fx":[-0.00642,0.21158,0.00642,-0.21158], "fy":[-0.21158,-0.00642,0.21158,0.00642]}, - {"t":1.32001, "x":6.78617, "y":5.46539, "heading":2.36079, "vx":-0.17504, "vy":-0.46823, "omega":0.84954, "ax":0.0, "ay":0.0, "alpha":0.05056, "fx":[0.00085,0.1856,-0.00085,-0.1856], "fy":[-0.1856,0.00085,0.1856,-0.00085]}, - {"t":1.36126, "x":6.77895, "y":5.44607, "heading":2.39584, "vx":-0.17504, "vy":-0.46823, "omega":0.85163, "ax":0.0, "ay":0.0, "alpha":0.04432, "fx":[0.00645,0.16256,-0.00645,-0.16256], "fy":[-0.16256,0.00645,0.16256,-0.00645]}, - {"t":1.40251, "x":6.77173, "y":5.42676, "heading":2.43097, "vx":-0.17504, "vy":-0.46823, "omega":0.85345, "ax":0.0, "ay":0.0, "alpha":0.03883, "fx":[0.01065,0.14215,-0.01065,-0.14215], "fy":[-0.14215,0.01065,0.14215,-0.01065]}, - {"t":1.44376, "x":6.76451, "y":5.40744, "heading":2.46617, "vx":-0.17504, "vy":-0.46823, "omega":0.85506, "ax":0.0, "ay":0.0, "alpha":0.03401, "fx":[0.0137,0.12409,-0.0137,-0.12409], "fy":[-0.12409,0.0137,0.12409,-0.0137]}, - {"t":1.48501, "x":6.75729, "y":5.38813, "heading":2.50144, "vx":-0.17504, "vy":-0.46823, "omega":0.85646, "ax":0.0, "ay":0.0, "alpha":0.02976, "fx":[0.01581,0.10811,-0.01581,-0.10811], "fy":[-0.10811,0.01581,0.10811,-0.01581]}, - {"t":1.52626, "x":6.75007, "y":5.36882, "heading":2.53677, "vx":-0.17504, "vy":-0.46823, "omega":0.85769, "ax":0.0, "ay":0.0, "alpha":0.02603, "fx":[0.01716,0.094,-0.01716,-0.094], "fy":[-0.094,0.01716,0.094,-0.01716]}, - {"t":1.56751, "x":6.74285, "y":5.3495, "heading":2.57215, "vx":-0.17504, "vy":-0.46823, "omega":0.85876, "ax":0.0, "ay":0.0, "alpha":0.02274, "fx":[0.01789,0.08153,-0.01789,-0.08153], "fy":[-0.08153,0.01789,0.08153,-0.01789]}, - {"t":1.60876, "x":6.73562, "y":5.33019, "heading":2.60757, "vx":-0.17504, "vy":-0.46823, "omega":0.8597, "ax":0.0, "ay":0.0, "alpha":0.01983, "fx":[0.01811,0.07052,-0.01811,-0.07052], "fy":[-0.07052,0.01811,0.07052,-0.01811]}, - {"t":1.65001, "x":6.7284, "y":5.31087, "heading":2.64304, "vx":-0.17504, "vy":-0.46823, "omega":0.86052, "ax":0.0, "ay":0.0, "alpha":0.01727, "fx":[0.01793,0.0608,-0.01793,-0.0608], "fy":[-0.0608,0.01793,0.0608,-0.01793]}, - {"t":1.69126, "x":6.72118, "y":5.29156, "heading":2.67853, "vx":-0.17504, "vy":-0.46823, "omega":0.86123, "ax":0.0, "ay":0.0, "alpha":0.015, "fx":[0.01744,0.05222,-0.01744,-0.05222], "fy":[-0.05222,0.01744,0.05222,-0.01744]}, - {"t":1.73251, "x":6.71396, "y":5.27224, "heading":2.71406, "vx":-0.17504, "vy":-0.46823, "omega":0.86185, "ax":0.0, "ay":0.0, "alpha":0.01298, "fx":[0.01669,0.04464,-0.01669,-0.04464], "fy":[-0.04464,0.01669,0.04464,-0.01669]}, - {"t":1.77376, "x":6.70674, "y":5.25293, "heading":2.74961, "vx":-0.17504, "vy":-0.46823, "omega":0.86238, "ax":0.0, "ay":0.0, "alpha":0.01119, "fx":[0.01575,0.03794,-0.01575,-0.03794], "fy":[-0.03794,0.01575,0.03794,-0.01575]}, - {"t":1.81501, "x":6.69952, "y":5.23361, "heading":2.78518, "vx":-0.17504, "vy":-0.46823, "omega":0.86284, "ax":0.0, "ay":0.0, "alpha":0.00959, "fx":[0.01464,0.03201,-0.01464,-0.03201], "fy":[-0.03201,0.01464,0.03201,-0.01464]}, - {"t":1.85626, "x":6.6923, "y":5.2143, "heading":2.82078, "vx":-0.17504, "vy":-0.46823, "omega":0.86324, "ax":0.0, "ay":0.0, "alpha":0.00815, "fx":[0.0134,0.02674,-0.0134,-0.02674], "fy":[-0.02674,0.0134,0.02674,-0.0134]}, - {"t":1.89751, "x":6.68508, "y":5.19498, "heading":2.85639, "vx":-0.17504, "vy":-0.46823, "omega":0.86358, "ax":0.0, "ay":0.0, "alpha":0.00685, "fx":[0.01206,0.02206,-0.01206,-0.02206], "fy":[-0.02206,0.01206,0.02206,-0.01206]}, - {"t":1.93876, "x":6.67786, "y":5.17567, "heading":2.89201, "vx":-0.17504, "vy":-0.46823, "omega":0.86386, "ax":0.0, "ay":0.0, "alpha":0.00567, "fx":[0.01062,0.01789,-0.01062,-0.01789], "fy":[-0.01789,0.01062,0.01789,-0.01062]}, - {"t":1.98001, "x":6.67064, "y":5.15635, "heading":2.92764, "vx":-0.17504, "vy":-0.46823, "omega":0.86409, "ax":0.0, "ay":0.0, "alpha":0.00458, "fx":[0.0091,0.01415,-0.0091,-0.01415], "fy":[-0.01415,0.0091,0.01415,-0.0091]}, - {"t":2.02126, "x":6.66342, "y":5.13704, "heading":2.96329, "vx":-0.17504, "vy":-0.46823, "omega":0.86428, "ax":0.0, "ay":0.0, "alpha":0.00357, "fx":[0.00749,0.01078,-0.00749,-0.01078], "fy":[-0.01078,0.00749,0.01078,-0.00749]}, - {"t":2.06251, "x":6.6562, "y":5.11772, "heading":2.99894, "vx":-0.17504, "vy":-0.46823, "omega":0.86443, "ax":0.0, "ay":0.0, "alpha":0.00263, "fx":[0.00578,0.00772,-0.00578,-0.00772], "fy":[-0.00772,0.00578,0.00772,-0.00578]}, - {"t":2.10377, "x":6.64898, "y":5.09841, "heading":3.0346, "vx":-0.17504, "vy":-0.46823, "omega":0.86454, "ax":0.0, "ay":0.0, "alpha":0.00173, "fx":[0.00398,0.00494,-0.00398,-0.00494], "fy":[-0.00494,0.00398,0.00494,-0.00398]}, - {"t":2.14502, "x":6.64176, "y":5.0791, "heading":3.07026, "vx":-0.17504, "vy":-0.46823, "omega":0.86461, "ax":0.0, "ay":0.0, "alpha":0.00086, "fx":[0.00206,0.00237,-0.00206,-0.00237], "fy":[-0.00237,0.00206,0.00237,-0.00206]}, - {"t":2.18627, "x":6.63454, "y":5.05978, "heading":3.10593, "vx":-0.17504, "vy":-0.46823, "omega":0.86464, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,-0.00001,0.0,0.00001], "fy":[0.00001,0.0,-0.00001,0.0]}, - {"t":2.22752, "x":6.62732, "y":5.04047, "heading":3.14159, "vx":-0.17504, "vy":-0.46823, "omega":0.86464, "ax":0.0, "ay":0.0, "alpha":-0.00086, "fx":[-0.00223,-0.00223,0.00223,0.00223], "fy":[0.00223,-0.00223,-0.00223,0.00223]}, - {"t":2.26877, "x":6.6201, "y":5.02115, "heading":-3.10593, "vx":-0.17504, "vy":-0.46823, "omega":0.86461, "ax":0.0, "ay":0.0, "alpha":-0.00173, "fx":[-0.00465,-0.00433,0.00465,0.00433], "fy":[0.00433,-0.00465,-0.00433,0.00465]}, - {"t":2.31002, "x":6.61288, "y":5.00184, "heading":-3.07026, "vx":-0.17504, "vy":-0.46823, "omega":0.86454, "ax":0.0, "ay":0.0, "alpha":-0.00263, "fx":[-0.0073,-0.00633,0.0073,0.00633], "fy":[0.00633,-0.0073,-0.00633,0.0073]}, - {"t":2.35127, "x":6.60566, "y":4.98252, "heading":-3.0346, "vx":-0.17504, "vy":-0.46823, "omega":0.86443, "ax":0.0, "ay":0.0, "alpha":-0.00358, "fx":[-0.01023,-0.00824,0.01023,0.00824], "fy":[0.00824,-0.01023,-0.00824,0.01023]}, - {"t":2.39252, "x":6.59844, "y":4.96321, "heading":-2.99894, "vx":-0.17504, "vy":-0.46823, "omega":0.86428, "ax":0.0, "ay":0.0, "alpha":-0.00458, "fx":[-0.01347,-0.01009,0.01347,0.01009], "fy":[0.01009,-0.01347,-0.01009,0.01347]}, - {"t":2.43377, "x":6.59122, "y":4.94389, "heading":-2.96329, "vx":-0.17504, "vy":-0.46823, "omega":0.86409, "ax":0.0, "ay":0.0, "alpha":-0.00567, "fx":[-0.01709,-0.01187,0.01709,0.01187], "fy":[0.01187,-0.01709,-0.01187,0.01709]}, - {"t":2.47502, "x":6.584, "y":4.92458, "heading":-2.92765, "vx":-0.17504, "vy":-0.46823, "omega":0.86386, "ax":0.0, "ay":0.0, "alpha":-0.00685, "fx":[-0.02116,-0.0136,0.02116,0.0136], "fy":[0.0136,-0.02116,-0.0136,0.02116]}, - {"t":2.51627, "x":6.57678, "y":4.90526, "heading":-2.89201, "vx":-0.17504, "vy":-0.46823, "omega":0.86357, "ax":0.0, "ay":0.0, "alpha":-0.00815, "fx":[-0.02573,-0.01528,0.02573,0.01528], "fy":[0.01528,-0.02573,-0.01528,0.02573]}, - {"t":2.55752, "x":6.56955, "y":4.88595, "heading":-2.85639, "vx":-0.17504, "vy":-0.46823, "omega":0.86324, "ax":0.0, "ay":0.0, "alpha":-0.00959, "fx":[-0.03089,-0.01688,0.03089,0.01688], "fy":[0.01688,-0.03089,-0.01688,0.03089]}, - {"t":2.59877, "x":6.56233, "y":4.86663, "heading":-2.82078, "vx":-0.17504, "vy":-0.46823, "omega":0.86284, "ax":0.0, "ay":0.0, "alpha":-0.01119, "fx":[-0.03672,-0.0184,0.03672,0.0184], "fy":[0.0184,-0.03672,-0.0184,0.03672]}, - {"t":2.64002, "x":6.55511, "y":4.84732, "heading":-2.78519, "vx":-0.17504, "vy":-0.46823, "omega":0.86238, "ax":0.0, "ay":0.0, "alpha":-0.01298, "fx":[-0.04334,-0.01982,0.04334,0.01982], "fy":[0.01982,-0.04334,-0.01982,0.04334]}, - {"t":2.68127, "x":6.54789, "y":4.828, "heading":-2.74961, "vx":-0.17504, "vy":-0.46823, "omega":0.86185, "ax":0.0, "ay":0.0, "alpha":-0.015, "fx":[-0.05085,-0.0211,0.05085,0.0211], "fy":[0.0211,-0.05085,-0.0211,0.05085]}, - {"t":2.72252, "x":6.54067, "y":4.80869, "heading":-2.71406, "vx":-0.17504, "vy":-0.46823, "omega":0.86123, "ax":0.0, "ay":0.0, "alpha":-0.01727, "fx":[-0.05937,-0.0222,0.05937,0.0222], "fy":[0.0222,-0.05937,-0.0222,0.05937]}, - {"t":2.76377, "x":6.53345, "y":4.78937, "heading":-2.67854, "vx":-0.17504, "vy":-0.46823, "omega":0.86051, "ax":0.0, "ay":0.0, "alpha":-0.01983, "fx":[-0.06905,-0.02306,0.06905,0.02306], "fy":[0.02306,-0.06905,-0.02306,0.06905]}, - {"t":2.80502, "x":6.52623, "y":4.77006, "heading":-2.64304, "vx":-0.17504, "vy":-0.46823, "omega":0.8597, "ax":0.0, "ay":0.0, "alpha":-0.02273, "fx":[-0.08005,-0.02361,0.08005,0.02361], "fy":[0.02361,-0.08005,-0.02361,0.08005]}, - {"t":2.84627, "x":6.51901, "y":4.75075, "heading":-2.60758, "vx":-0.17504, "vy":-0.46823, "omega":0.85876, "ax":0.0, "ay":0.0, "alpha":-0.02602, "fx":[-0.09253,-0.02376,0.09253,0.02376], "fy":[0.02376,-0.09253,-0.02376,0.09253]}, - {"t":2.88752, "x":6.51179, "y":4.73143, "heading":-2.57215, "vx":-0.17504, "vy":-0.46823, "omega":0.85769, "ax":0.0, "ay":0.0, "alpha":-0.02976, "fx":[-0.10671,-0.02341,0.10671,0.02341], "fy":[0.02341,-0.10671,-0.02341,0.10671]}, - {"t":2.92877, "x":6.50457, "y":4.71212, "heading":-2.53677, "vx":-0.17504, "vy":-0.46823, "omega":0.85646, "ax":0.0, "ay":0.0, "alpha":-0.034, "fx":[-0.12279,-0.02242,0.12279,0.02242], "fy":[0.02242,-0.12279,-0.02242,0.12279]}, - {"t":2.97002, "x":6.49735, "y":4.6928, "heading":-2.50144, "vx":-0.17504, "vy":-0.46823, "omega":0.85506, "ax":0.0, "ay":0.0, "alpha":-0.03883, "fx":[-0.14103,-0.02063,0.14103,0.02063], "fy":[0.02063,-0.14103,-0.02063,0.14103]}, - {"t":3.01127, "x":6.49013, "y":4.67349, "heading":-2.46617, "vx":-0.17504, "vy":-0.46823, "omega":0.85345, "ax":0.0, "ay":0.0, "alpha":-0.04431, "fx":[-0.16169,-0.01785,0.16169,0.01785], "fy":[0.01785,-0.16169,-0.01785,0.16169]}, - {"t":3.05252, "x":6.48291, "y":4.65417, "heading":-2.43097, "vx":-0.17504, "vy":-0.46823, "omega":0.85163, "ax":0.0, "ay":0.0, "alpha":-0.05055, "fx":[-0.18506,-0.01386,0.18506,0.01386], "fy":[0.01386,-0.18506,-0.01386,0.18506]}, - {"t":3.09377, "x":6.47569, "y":4.63486, "heading":-2.39584, "vx":-0.17504, "vy":-0.46823, "omega":0.84954, "ax":0.0, "ay":0.0, "alpha":-0.05766, "fx":[-0.21149,-0.00839,0.21149,0.00839], "fy":[0.00839,-0.21149,-0.00839,0.21149]}, - {"t":3.13502, "x":6.46847, "y":4.61554, "heading":-2.36079, "vx":-0.17504, "vy":-0.46823, "omega":0.84716, "ax":0.0, "ay":0.0, "alpha":-0.06574, "fx":[-0.24135,-0.00111,0.24135,0.00111], "fy":[0.00111,-0.24135,-0.00111,0.24135]}, - {"t":3.17627, "x":6.46125, "y":4.59623, "heading":-2.32585, "vx":-0.17504, "vy":-0.46823, "omega":0.84445, "ax":0.0, "ay":0.0, "alpha":-0.07495, "fx":[-0.27503,0.00835,0.27503,-0.00835], "fy":[-0.00835,-0.27503,0.00835,0.27503]}, - {"t":3.21752, "x":6.45403, "y":4.57691, "heading":-2.29101, "vx":-0.17504, "vy":-0.46823, "omega":0.84136, "ax":0.0, "ay":0.0, "alpha":-0.08544, "fx":[-0.31298,0.02043,0.31298,-0.02043], "fy":[-0.02043,-0.31298,0.02043,0.31298]}, - {"t":3.25877, "x":6.44681, "y":4.5576, "heading":-2.25631, "vx":-0.17504, "vy":-0.46823, "omega":0.83783, "ax":0.0, "ay":0.0, "alpha":-0.09738, "fx":[-0.35571,0.03565,0.35571,-0.03565], "fy":[-0.03565,-0.35571,0.03565,0.35571]}, - {"t":3.30002, "x":6.43959, "y":4.53828, "heading":-2.22175, "vx":-0.17504, "vy":-0.46823, "omega":0.83382, "ax":0.0, "ay":0.0, "alpha":-0.11098, "fx":[-0.40375,0.05461,0.40375,-0.05461], "fy":[-0.05461,-0.40375,0.05461,0.40375]}, - {"t":3.34127, "x":6.43237, "y":4.51897, "heading":-2.18735, "vx":-0.17504, "vy":-0.46823, "omega":0.82924, "ax":0.0, "ay":0.0, "alpha":-0.12648, "fx":[-0.4577,0.07802,0.4577,-0.07802], "fy":[-0.07802,-0.4577,0.07802,0.4577]}, - {"t":3.38252, "x":6.42515, "y":4.49965, "heading":-2.15315, "vx":-0.17504, "vy":-0.46823, "omega":0.82402, "ax":0.0, "ay":0.0, "alpha":-0.14412, "fx":[-0.51821,0.10669,0.51821,-0.10669], "fy":[-0.10669,-0.51821,0.10669,0.51821]}, - {"t":3.42377, "x":6.41793, "y":4.48034, "heading":-2.11915, "vx":-0.17504, "vy":-0.46823, "omega":0.81808, "ax":0.0, "ay":0.0, "alpha":-0.16422, "fx":[-0.58602,0.14157,0.58602,-0.14157], "fy":[-0.14157,-0.58602,0.14157,0.58602]}, - {"t":3.46503, "x":6.41071, "y":4.46102, "heading":-2.08541, "vx":-0.17504, "vy":-0.46823, "omega":0.8113, "ax":0.0, "ay":0.0, "alpha":-0.18712, "fx":[-0.66189,0.18374,0.66189,-0.18374], "fy":[-0.18374,-0.66189,0.18374,0.66189]}, - {"t":3.50628, "x":6.40348, "y":4.44171, "heading":-2.05194, "vx":-0.17504, "vy":-0.46823, "omega":0.80358, "ax":0.0, "ay":0.0, "alpha":-0.2132, "fx":[-0.74671,0.23447,0.74671,-0.23447], "fy":[-0.23447,-0.74671,0.23447,0.74671]}, - {"t":3.54753, "x":6.39626, "y":4.4224, "heading":-2.01879, "vx":-0.17504, "vy":-0.46823, "omega":0.79479, "ax":0.0, "ay":0.0, "alpha":-0.2429, "fx":[-0.84142,0.29518,0.84142,-0.29518], "fy":[-0.29518,-0.84142,0.29518,0.84142]}, - {"t":3.58878, "x":6.38904, "y":4.40308, "heading":-1.98601, "vx":-0.17504, "vy":-0.46823, "omega":0.78477, "ax":0.0, "ay":0.0, "alpha":-0.27673, "fx":[-0.94707,0.36754,0.94707,-0.36754], "fy":[-0.36754,-0.94707,0.36754,0.94707]}, - {"t":3.63003, "x":6.38182, "y":4.38377, "heading":-1.95364, "vx":-0.17504, "vy":-0.46823, "omega":0.77335, "ax":0.0, "ay":0.0, "alpha":-0.31525, "fx":[-1.06481,0.45341,1.06481,-0.45341], "fy":[-0.45341,-1.06481,0.45341,1.06481]}, - {"t":3.67128, "x":6.3746, "y":4.36445, "heading":-1.92174, "vx":-0.17504, "vy":-0.46823, "omega":0.76035, "ax":0.0, "ay":0.0, "alpha":-0.35913, "fx":[-1.1959,0.55493,1.1959,-0.55493], "fy":[-0.55493,-1.1959,0.55493,1.1959]}, - {"t":3.71253, "x":6.36738, "y":4.34514, "heading":-1.89037, "vx":-0.17504, "vy":-0.46823, "omega":0.74554, "ax":0.0, "ay":0.0, "alpha":-0.40909, "fx":[-1.34177,0.67454,1.34177,-0.67454], "fy":[-0.67454,-1.34177,0.67454,1.34177]}, - {"t":3.75378, "x":6.36016, "y":4.32582, "heading":-1.85962, "vx":-0.17504, "vy":-0.46823, "omega":0.72866, "ax":0.0, "ay":0.0, "alpha":-0.46597, "fx":[-1.50399,0.81496,1.50399,-0.81496], "fy":[-0.81496,-1.50399,0.81496,1.50399]}, - {"t":3.79503, "x":6.35294, "y":4.30651, "heading":-1.82956, "vx":-0.17504, "vy":-0.46823, "omega":0.70944, "ax":0.0, "ay":0.0, "alpha":-0.53073, "fx":[-1.68433,0.97928,1.68433,-0.97928], "fy":[-0.97928,-1.68433,0.97928,1.68433]}, - {"t":3.83628, "x":6.34572, "y":4.28719, "heading":-1.8003, "vx":-0.17504, "vy":-0.46823, "omega":0.68755, "ax":0.0, "ay":0.0, "alpha":-0.60444, "fx":[-1.88481,1.17094,1.88481,-1.17094], "fy":[-1.17094,-1.88481,1.17094,1.88481]}, - {"t":3.87753, "x":6.3385, "y":4.26788, "heading":-1.77193, "vx":-0.17504, "vy":-0.46823, "omega":0.66261, "ax":0.0, "ay":0.0, "alpha":-0.68833, "fx":[-2.10773,1.39378,2.10773,-1.39378], "fy":[-1.39378,-2.10773,1.39378,2.10773]}, - {"t":3.91878, "x":6.33128, "y":4.24856, "heading":-1.7446, "vx":-0.17504, "vy":-0.46823, "omega":0.63422, "ax":0.0, "ay":0.0, "alpha":-0.78378, "fx":[-2.35575,1.65207,2.35575,-1.65207], "fy":[-1.65207,-2.35575,1.65207,2.35575]}, - {"t":3.96003, "x":6.32406, "y":4.22925, "heading":-1.71844, "vx":-0.17504, "vy":-0.46823, "omega":0.60189, "ax":0.0, "ay":0.0, "alpha":-0.89237, "fx":[-2.63199,1.95046,2.63199,-1.95046], "fy":[-1.95046,-2.63199,1.95046,2.63199]}, - {"t":4.00128, "x":6.31684, "y":4.20993, "heading":-1.69361, "vx":-0.17504, "vy":-0.46823, "omega":0.56508, "ax":0.0, "ay":0.0, "alpha":-1.01585, "fx":[-2.94017,2.29407,2.94017,-2.29407], "fy":[-2.29407,-2.94017,2.29407,2.94017]}, - {"t":4.04253, "x":6.30962, "y":4.19062, "heading":-1.6703, "vx":-0.17504, "vy":-0.46823, "omega":0.52317, "ax":0.0, "ay":0.0, "alpha":-1.15624, "fx":[-3.28472,2.68839,3.28472,-2.68839], "fy":[-2.68839,-3.28472,2.68839,3.28472]}, - {"t":4.08378, "x":6.3024, "y":4.1713, "heading":-1.64872, "vx":-0.17504, "vy":-0.46823, "omega":0.47548, "ax":0.0, "ay":0.0, "alpha":-1.31577, "fx":[-3.67104,3.13927,3.67104,-3.13927], "fy":[-3.13927,-3.67104,3.13927,3.67104]}, - {"t":4.12503, "x":6.29518, "y":4.15199, "heading":-1.62911, "vx":-0.17504, "vy":-0.46823, "omega":0.4212, "ax":0.0, "ay":0.0, "alpha":-1.49696, "fx":[-4.10572,3.6528,4.10572,-3.6528], "fy":[-3.6528,-4.10572,3.6528,4.10572]}, - {"t":4.16628, "x":6.28796, "y":4.13267, "heading":-1.61173, "vx":-0.17504, "vy":-0.46823, "omega":0.35945, "ax":0.0, "ay":0.0, "alpha":-1.70263, "fx":[-4.59692,4.23516,4.59692,-4.23516], "fy":[-4.23516,-4.59692,4.23516,4.59692]}, - {"t":4.20753, "x":6.28074, "y":4.11336, "heading":-1.5969, "vx":-0.17504, "vy":-0.46823, "omega":0.28922, "ax":0.0, "ay":0.0, "alpha":-1.93591, "fx":[-5.15477,4.89239,5.15477,-4.89239], "fy":[-4.89239,-5.15477,4.89239,5.15477]}, - {"t":4.24878, "x":6.27352, "y":4.09405, "heading":-1.58497, "vx":-0.17504, "vy":-0.46823, "omega":0.20936, "ax":0.0, "ay":0.0, "alpha":-2.20026, "fx":[-5.7919,5.62994,5.7919,-5.62994], "fy":[-5.62994,-5.7919,5.62994,5.7919]}, - {"t":4.29003, "x":6.2663, "y":4.07473, "heading":-1.57634, "vx":-0.17504, "vy":-0.46823, "omega":0.1186, "ax":0.00001, "ay":0.00004, "alpha":-2.49948, "fx":[-6.52384,6.45241,6.52433,-6.45192], "fy":[-6.45152,-6.52343,6.45282,6.52473]}, - {"t":4.33128, "x":6.25908, "y":4.05542, "heading":-1.57145, "vx":-0.17504, "vy":-0.46823, "omega":0.0155, "ax":1.98576, "ay":5.3119, "alpha":-0.36994, "fx":[32.7258,35.7972,34.79591,31.78972], "fy":[90.45156,89.45402,90.28179,91.22851]}, - {"t":4.37253, "x":6.25354, "y":4.04062, "heading":-1.57081, "vx":-0.09313, "vy":-0.24911, "omega":0.00024, "ax":2.25759, "ay":6.03905, "alpha":-0.00573, "fx":[38.38454,38.43666,38.41721,38.36512], "fy":[102.72848,102.70903,102.71641,102.73584]}, - {"t":4.41378, "x":6.25162, "y":4.03548, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":7.01023, "y":6.06476, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":-0.53484, "ay":-6.42809, "alpha":-0.01447, "fx":[-9.02906,-9.17816,-9.16568,-9.01678], "fy":[-109.3456,-109.33321,-109.33445,-109.34681]}, + {"t":0.03442, "x":7.00992, "y":6.06096, "heading":1.5708, "vx":-0.01841, "vy":-0.22126, "omega":-0.0005, "ax":-0.53461, "ay":-6.4253, "alpha":-0.01776, "fx":[-9.00957,-9.19257,-9.17723,-8.99454], "fy":[-109.29937,-109.28416,-109.28577,-109.30093]}, + {"t":0.06884, "x":7.00897, "y":6.04953, "heading":1.57078, "vx":-0.03681, "vy":-0.44242, "omega":-0.00111, "ax":-0.53414, "ay":-6.41973, "alpha":-0.02434, "fx":[-8.97068,-9.22132,-9.20027,-8.95019], "fy":[-109.20704,-109.18622,-109.18865,-109.20938]}, + {"t":0.10326, "x":7.00738, "y":6.0305, "heading":1.57074, "vx":-0.0552, "vy":-0.6634, "omega":-0.00195, "ax":-0.53276, "ay":-6.40312, "alpha":-0.044, "fx":[-8.85469,-9.30698,-9.26873,-8.81828], "fy":[-108.93123,-108.89372,-108.89934,-108.93655]}, + {"t":0.13768, "x":7.00517, "y":6.00387, "heading":1.57067, "vx":-0.07353, "vy":-0.8838, "omega":-0.00346, "ax":-0.27181, "ay":-3.26747, "alpha":-4.33748, "fx":[10.51711,-20.63955,-16.89956,8.52813], "fy":[-47.73807,-46.67425,-63.52471,-64.37812]}, + {"t":0.1721, "x":7.00247, "y":5.97152, "heading":1.57055, "vx":-0.08289, "vy":-0.99627, "omega":-0.15276, "ax":-0.00004, "ay":-0.00006, "alpha":-6.46077, "fx":[16.77452,-16.76767,-16.77568,16.76632], "fy":[16.76598,16.77403,-16.76801,-16.77617]}, + {"t":0.20652, "x":6.99962, "y":5.93722, "heading":1.5653, "vx":-0.08289, "vy":-0.99627, "omega":-0.37515, "ax":0.0, "ay":0.0, "alpha":-5.8129, "fx":[15.17202,-15.0061,-15.17207,15.00605], "fy":[15.00608,15.17205,-15.00607,-15.17205]}, + {"t":0.24095, "x":6.99677, "y":5.90293, "heading":1.55238, "vx":-0.08289, "vy":-0.99627, "omega":-0.57523, "ax":0.0, "ay":0.0, "alpha":-5.2166, "fx":[13.78843,-13.28979,-13.78843,13.28979], "fy":[13.28979,13.78843,-13.28979,-13.78843]}, + {"t":0.27537, "x":6.99391, "y":5.86864, "heading":1.53258, "vx":-0.08289, "vy":-0.99627, "omega":-0.75479, "ax":0.0, "ay":0.0, "alpha":-4.67069, "fx":[12.57865,-11.65226,-12.57865,11.65226], "fy":[11.65226,12.57865,-11.65226,-12.57865]}, + {"t":0.30979, "x":6.99106, "y":5.83435, "heading":1.5066, "vx":-0.08289, "vy":-0.99627, "omega":-0.91556, "ax":0.0, "ay":0.0, "alpha":-4.17324, "fx":[11.50565,-10.11578,-11.50565,10.11578], "fy":[10.11578,11.50565,-10.11578,-11.50565]}, + {"t":0.34421, "x":6.98821, "y":5.80006, "heading":1.47509, "vx":-0.08289, "vy":-0.99627, "omega":-1.0592, "ax":0.0, "ay":0.0, "alpha":-3.72181, "fx":[10.5402,-8.69372,-10.5402,8.69372], "fy":[8.69372,10.5402,-8.69372,-10.5402]}, + {"t":0.37863, "x":6.98536, "y":5.76576, "heading":1.43863, "vx":-0.08289, "vy":-0.99627, "omega":-1.18731, "ax":0.0, "ay":0.0, "alpha":-3.31355, "fx":[9.65991,-7.39288,-9.65992,7.39288], "fy":[7.39288,9.65992,-7.39288,-9.65991]}, + {"t":0.41305, "x":6.9825, "y":5.73147, "heading":1.39776, "vx":-0.08289, "vy":-0.99627, "omega":-1.30137, "ax":0.0, "ay":0.0, "alpha":-2.94544, "fx":[8.8481,-6.21527,-8.8481,6.21527], "fy":[6.21527,8.8481,-6.21527,-8.8481]}, + {"t":0.44747, "x":6.97965, "y":5.69718, "heading":1.35297, "vx":-0.08289, "vy":-0.99627, "omega":-1.40275, "ax":0.0, "ay":0.0, "alpha":-2.61433, "fx":[8.0926,-5.15937,-8.0926,5.15937], "fy":[5.15937,8.0926,-5.15937,-8.0926]}, + {"t":0.48189, "x":6.9768, "y":5.66289, "heading":1.30468, "vx":-0.08289, "vy":-0.99627, "omega":-1.49274, "ax":0.0, "ay":0.0, "alpha":-2.31712, "fx":[7.38492,-4.2213,-7.38493,4.2213], "fy":[4.2213,7.38492,-4.2213,-7.38492]}, + {"t":0.51631, "x":6.97394, "y":5.62859, "heading":1.2533, "vx":-0.08289, "vy":-0.99627, "omega":-1.5725, "ax":0.0, "ay":0.0, "alpha":-2.0507, "fx":[6.71909,-3.39535,-6.71909,3.39535], "fy":[3.39535,6.71909,-3.39535,-6.71909]}, + {"t":0.55073, "x":6.97109, "y":5.5943, "heading":1.19918, "vx":-0.08289, "vy":-0.99627, "omega":-1.64308, "ax":0.0, "ay":0.0, "alpha":-1.81222, "fx":[6.09134,-2.67487,-6.09135,2.67487], "fy":[2.67487,6.09135,-2.67487,-6.09135]}, + {"t":0.58515, "x":6.96824, "y":5.56001, "heading":1.14262, "vx":-0.08289, "vy":-0.99627, "omega":-1.70546, "ax":0.0, "ay":0.0, "alpha":-1.59883, "fx":[5.49889,-2.05235,-5.49889,2.05235], "fy":[2.05235,5.49889,-2.05235,-5.49889]}, + {"t":0.61957, "x":6.96538, "y":5.52572, "heading":1.08392, "vx":-0.08289, "vy":-0.99627, "omega":-1.76049, "ax":0.0, "ay":0.0, "alpha":-1.40803, "fx":[4.94036,-1.52019,-4.94036,1.52019], "fy":[1.52019,4.94036,-1.52019,-4.94036]}, + {"t":0.65399, "x":6.96253, "y":5.49142, "heading":1.02332, "vx":-0.08289, "vy":-0.99627, "omega":-1.80896, "ax":0.0, "ay":0.0, "alpha":-1.23729, "fx":[4.41423,-1.07049,-4.41423,1.07049], "fy":[1.07049,4.41423,-1.07049,-4.41423]}, + {"t":0.68842, "x":6.95968, "y":5.45713, "heading":0.96105, "vx":-0.08289, "vy":-0.99627, "omega":-1.85155, "ax":0.0, "ay":0.0, "alpha":-1.08453, "fx":[3.92012,-0.69573,-3.92012,0.69574], "fy":[0.69574,3.92012,-0.69574,-3.92012]}, + {"t":0.72284, "x":6.95682, "y":5.42284, "heading":0.89732, "vx":-0.08289, "vy":-0.99627, "omega":-1.88888, "ax":0.0, "ay":0.0, "alpha":-0.94754, "fx":[3.45671,-0.38849,-3.4567,0.38849], "fy":[0.38849,3.45671,-0.38849,-3.45671]}, + {"t":0.75726, "x":6.95397, "y":5.38855, "heading":0.83231, "vx":-0.08289, "vy":-0.99627, "omega":-1.92149, "ax":0.0, "ay":0.0, "alpha":-0.8246, "fx":[3.02384,-0.14192,-3.02383,0.14192], "fy":[0.14192,3.02384,-0.14192,-3.02384]}, + {"t":0.79168, "x":6.95112, "y":5.35426, "heading":0.76617, "vx":-0.08289, "vy":-0.99627, "omega":-1.94988, "ax":0.0, "ay":0.0, "alpha":-0.71381, "fx":[2.61997,0.05042,-2.61996,-0.05041], "fy":[-0.05042,2.61997,0.05042,-2.61997]}, + {"t":0.8261, "x":6.94826, "y":5.31996, "heading":0.69905, "vx":-0.08289, "vy":-0.99627, "omega":-1.97445, "ax":0.0, "ay":0.0, "alpha":-0.61378, "fx":[2.24483,0.19434,-2.24482,-0.19434], "fy":[-0.19434,2.24482,0.19434,-2.24482]}, + {"t":0.86052, "x":6.94541, "y":5.28567, "heading":0.63109, "vx":-0.08289, "vy":-0.99627, "omega":-1.99557, "ax":0.0, "ay":0.0, "alpha":-0.52285, "fx":[1.8966,0.29503,-1.89659,-0.29502], "fy":[-0.29503,1.8966,0.29503,-1.8966]}, + {"t":0.89494, "x":6.94256, "y":5.25138, "heading":0.5624, "vx":-0.08289, "vy":-0.99627, "omega":-2.01357, "ax":0.0, "ay":0.0, "alpha":-0.43987, "fx":[1.57482,0.35714,-1.57481,-0.35714], "fy":[-0.35714,1.57481,0.35714,-1.57481]}, + {"t":0.92936, "x":6.9397, "y":5.21709, "heading":0.49309, "vx":-0.08289, "vy":-0.99627, "omega":-2.02871, "ax":0.0, "ay":0.0, "alpha":-0.36344, "fx":[1.27761,0.38448,-1.2776,-0.38448], "fy":[-0.38448,1.2776,0.38448,-1.2776]}, + {"t":0.96378, "x":6.93685, "y":5.18279, "heading":0.42326, "vx":-0.08289, "vy":-0.99627, "omega":-2.04122, "ax":0.0, "ay":0.0, "alpha":-0.29255, "fx":[1.00431,0.38049,-1.00431,-0.38049], "fy":[-0.38049,1.00431,0.38049,-1.00431]}, + {"t":0.9982, "x":6.934, "y":5.1485, "heading":0.353, "vx":-0.08289, "vy":-0.99627, "omega":-2.05129, "ax":0.0, "ay":0.0, "alpha":-0.22601, "fx":[0.75333,0.34769,-0.75333,-0.34769], "fy":[-0.34769,0.75333,0.34769,-0.75333]}, + {"t":1.03262, "x":6.93114, "y":5.11421, "heading":0.28239, "vx":-0.08289, "vy":-0.99627, "omega":-2.05907, "ax":0.0, "ay":0.0, "alpha":-0.1629, "fx":[0.52393,0.28828,-0.52393,-0.28828], "fy":[-0.28828,0.52393,0.28828,-0.52393]}, + {"t":1.06704, "x":6.92829, "y":5.07992, "heading":0.21152, "vx":-0.08289, "vy":-0.99627, "omega":-2.06468, "ax":0.0, "ay":0.0, "alpha":-0.10222, "fx":[0.31512,0.20372,-0.31513,-0.20372], "fy":[-0.20372,0.31513,0.20372,-0.31513]}, + {"t":1.10146, "x":6.92544, "y":5.04563, "heading":0.14045, "vx":-0.08289, "vy":-0.99627, "omega":-2.0682, "ax":0.0, "ay":0.0, "alpha":-0.04303, "fx":[0.12624,0.09497,-0.12624,-0.09497], "fy":[-0.09497,0.12624,0.09497,-0.12624]}, + {"t":1.13589, "x":6.92258, "y":5.01133, "heading":0.06926, "vx":-0.08289, "vy":-0.99627, "omega":-2.06968, "ax":0.0, "ay":0.0, "alpha":0.01547, "fx":[-0.04285,-0.0373,0.04285,0.03729], "fy":[0.03729,-0.04285,-0.03729,0.04285]}, + {"t":1.17031, "x":6.91973, "y":4.97704, "heading":-0.00198, "vx":-0.08289, "vy":-0.99627, "omega":-2.06914, "ax":0.0, "ay":0.0, "alpha":0.07433, "fx":[-0.19256,-0.19332,0.19255,0.19332], "fy":[0.19332,-0.19255,-0.19332,0.19255]}, + {"t":1.20473, "x":6.91688, "y":4.94275, "heading":-0.0732, "vx":-0.08289, "vy":-0.99627, "omega":-2.06659, "ax":0.0, "ay":0.0, "alpha":0.1342, "fx":[-0.32194,-0.37291,0.32194,0.3729], "fy":[0.3729,-0.32194,-0.3729,0.32194]}, + {"t":1.23915, "x":6.91403, "y":4.90846, "heading":-0.14433, "vx":-0.08289, "vy":-0.99627, "omega":-2.06197, "ax":0.0, "ay":0.0, "alpha":0.19627, "fx":[-0.4309,-0.57746,0.43089,0.57745], "fy":[0.57746,-0.43089,-0.57746,0.43089]}, + {"t":1.27357, "x":6.91117, "y":4.87416, "heading":-0.21531, "vx":-0.08289, "vy":-0.99627, "omega":-2.05521, "ax":0.0, "ay":0.0, "alpha":0.26112, "fx":[-0.51734,-0.80698,0.51734,0.80698], "fy":[0.80698,-0.51734,-0.80698,0.51734]}, + {"t":1.30799, "x":6.90832, "y":4.83987, "heading":-0.28605, "vx":-0.08289, "vy":-0.99627, "omega":-2.04622, "ax":0.0, "ay":0.0, "alpha":0.33012, "fx":[-0.58031,-1.06391,0.5803,1.06391], "fy":[1.06391,-0.5803,-1.06391,0.5803]}, + {"t":1.34241, "x":6.90547, "y":4.80558, "heading":-0.35648, "vx":-0.08289, "vy":-0.99627, "omega":-2.03486, "ax":0.0, "ay":0.0, "alpha":0.40385, "fx":[-0.61657,-1.34828,0.61656,1.34828], "fy":[1.34828,-0.61657,-1.34828,0.61657]}, + {"t":1.37683, "x":6.90261, "y":4.77129, "heading":-0.42652, "vx":-0.08289, "vy":-0.99627, "omega":-2.02096, "ax":0.0, "ay":0.0, "alpha":0.48391, "fx":[-0.62391,-1.66328,0.62391,1.66328], "fy":[1.66328,-0.62391,-1.66328,0.62391]}, + {"t":1.41125, "x":6.89976, "y":4.73699, "heading":-0.49609, "vx":-0.08289, "vy":-0.99627, "omega":-2.0043, "ax":0.0, "ay":0.0, "alpha":0.57096, "fx":[-0.59796,-2.00891,0.59796,2.00892], "fy":[2.00892,-0.59796,-2.00892,0.59796]}, + {"t":1.44567, "x":6.89691, "y":4.7027, "heading":-0.56508, "vx":-0.08289, "vy":-0.99627, "omega":-1.98465, "ax":0.0, "ay":0.0, "alpha":0.6668, "fx":[-0.53494,-2.38869,0.53495,2.38869], "fy":[2.38869,-0.53494,-2.38869,0.53494]}, + {"t":1.48009, "x":6.89405, "y":4.66841, "heading":-0.63339, "vx":-0.08289, "vy":-0.99627, "omega":-1.9617, "ax":0.0, "ay":0.0, "alpha":0.77233, "fx":[-0.4293,-2.80259,0.42931,2.8026], "fy":[2.80259,-0.42931,-2.80259,0.42931]}, + {"t":1.51451, "x":6.8912, "y":4.63412, "heading":-0.70091, "vx":-0.08289, "vy":-0.99627, "omega":-1.93511, "ax":0.0, "ay":0.0, "alpha":0.88955, "fx":[-0.27554,-3.25395,0.27555,3.25396], "fy":[3.25396,-0.27554,-3.25396,0.27554]}, + {"t":1.54893, "x":6.88835, "y":4.59983, "heading":-0.76752, "vx":-0.08289, "vy":-0.99627, "omega":-1.90449, "ax":0.0, "ay":0.0, "alpha":1.0197, "fx":[-0.06689,-3.74276,0.06689,3.74277], "fy":[3.74276,-0.06689,-3.74276,0.06689]}, + {"t":1.58336, "x":6.88549, "y":4.56553, "heading":-0.83307, "vx":-0.08289, "vy":-0.99627, "omega":-1.8694, "ax":0.0, "ay":0.0, "alpha":1.16495, "fx":[0.20385,-4.27172,-0.20384,4.27173], "fy":[4.27173,0.20384,-4.27173,-0.20384]}, + {"t":1.61778, "x":6.88264, "y":4.53124, "heading":-0.89742, "vx":-0.08289, "vy":-0.99627, "omega":-1.8293, "ax":0.0, "ay":0.0, "alpha":1.32698, "fx":[0.5446,-4.84089,-0.5446,4.84089], "fy":[4.84089,0.5446,-4.84089,-0.5446]}, + {"t":1.6522, "x":6.87979, "y":4.49695, "heading":-0.96039, "vx":-0.08289, "vy":-0.99627, "omega":-1.78362, "ax":0.0, "ay":0.0, "alpha":1.50819, "fx":[0.96394,-5.45208,-0.96394,5.45208], "fy":[5.45208,0.96394,-5.45208,-0.96394]}, + {"t":1.68662, "x":6.87693, "y":4.46266, "heading":-1.02178, "vx":-0.08289, "vy":-0.99627, "omega":-1.73171, "ax":0.0, "ay":0.0, "alpha":1.71073, "fx":[1.47077,-6.10555,-1.47077,6.10555], "fy":[6.10555,1.47077,-6.10555,-1.47077]}, + {"t":1.72104, "x":6.87408, "y":4.42836, "heading":-1.08139, "vx":-0.08289, "vy":-0.99627, "omega":-1.67282, "ax":0.0, "ay":0.0, "alpha":1.93722, "fx":[2.0744,-6.80239,-2.0744,6.80239], "fy":[6.80239,2.0744,-6.80239,-2.0744]}, + {"t":1.75546, "x":6.87123, "y":4.39407, "heading":-1.13897, "vx":-0.08289, "vy":-0.99627, "omega":-1.60614, "ax":0.0, "ay":0.0, "alpha":2.19034, "fx":[2.78416,-7.54347,-2.78416,7.54347], "fy":[7.54347,2.78416,-7.54347,-2.78416]}, + {"t":1.78988, "x":6.86837, "y":4.35978, "heading":-1.19425, "vx":-0.08289, "vy":-0.99627, "omega":-1.53075, "ax":0.0, "ay":0.0, "alpha":2.47288, "fx":[3.60909,-8.32985,-3.6091,8.32984], "fy":[8.32984,3.6091,-8.32984,-3.6091]}, + {"t":1.8243, "x":6.86552, "y":4.32549, "heading":-1.24694, "vx":-0.08289, "vy":-0.99627, "omega":-1.44563, "ax":0.0, "ay":0.0, "alpha":2.78797, "fx":[4.55787,-9.16388,-4.5579,9.16386], "fy":[9.16387,4.55789,-9.16387,-4.55788]}, + {"t":1.85872, "x":6.86267, "y":4.29119, "heading":-1.2967, "vx":-0.08289, "vy":-0.99627, "omega":-1.34967, "ax":-0.00001, "ay":0.0, "alpha":3.13854, "fx":[5.63753,-10.04844,-5.63803,10.04795], "fy":[10.04822,5.6378,-10.04817,-5.63776]}, + {"t":1.89314, "x":6.85981, "y":4.2569, "heading":-1.34316, "vx":-0.08289, "vy":-0.99627, "omega":-1.24164, "ax":-0.00033, "ay":0.00003, "alpha":3.52791, "fx":[6.84926,-10.99384,-6.86051,10.98275], "fy":[10.98883,6.85529,-10.98776,-6.85449]}, + {"t":1.92756, "x":6.85696, "y":4.22261, "heading":-1.3859, "vx":-0.0829, "vy":-0.99627, "omega":-1.1202, "ax":-0.00739, "ay":0.00062, "alpha":3.95898, "fx":[8.08559,-12.11577,-8.33898,11.86626], "fy":[12.00352,8.2208,-11.97859,-8.20382]}, + {"t":1.96198, "x":6.8541, "y":4.18832, "heading":-1.42445, "vx":-0.08316, "vy":-0.99625, "omega":-0.98393, "ax":-0.16485, "ay":0.01424, "alpha":4.42918, "fx":[6.86607,-15.82283,-12.51952,10.26039], "fy":[13.35998,9.88796,-12.76103,-9.51834]}, + {"t":1.9964, "x":6.85114, "y":4.15403, "heading":-1.45832, "vx":-0.08883, "vy":-0.99576, "omega":-0.83148, "ax":-2.93358, "ay":0.41356, "alpha":3.26623, "fx":[-43.44704,-56.90501,-56.43289,-42.81215], "fy":[19.35933,14.87719,-4.00084,-2.09748]}, + {"t":2.03083, "x":6.84635, "y":4.12001, "heading":-1.48694, "vx":-0.18981, "vy":-0.98152, "omega":-0.71905, "ax":-5.89967, "ay":1.80952, "alpha":0.25939, "fx":[-99.82159,-100.22233,-100.86639,-100.4965], "fy":[32.38006,31.47735,29.19683,30.06339]}, + {"t":2.06525, "x":6.83632, "y":4.08729, "heading":-1.51169, "vx":-0.39288, "vy":-0.91924, "omega":-0.71012, "ax":-5.55539, "ay":3.13946, "alpha":0.07628, "fx":[-94.22743,-94.44489,-94.76223,-94.54805], "fy":[53.87187,53.50573,52.93125,53.29662]}, + {"t":2.09967, "x":6.8195, "y":4.05751, "heading":-1.53613, "vx":-0.5841, "vy":-0.81117, "omega":-0.7075, "ax":-4.75473, "ay":4.31877, "alpha":0.03803, "fx":[-80.68982,-80.87543,-81.06322,-80.87815], "fy":[73.66649,73.46496,73.25545,73.45742]}, + {"t":2.13409, "x":6.79658, "y":4.03215, "heading":-1.56049, "vx":-0.74776, "vy":-0.66252, "omega":-0.70619, "ax":-3.55495, "ay":5.3554, "alpha":0.03759, "fx":[-60.24513,-60.51706,-60.69244,-60.42038], "fy":[91.24249,91.06357,90.94491,91.12466]}, + {"t":2.17789, "x":6.76042, "y":4.00827, "heading":-1.59142, "vx":-0.90348, "vy":-0.42793, "omega":-0.70454, "ax":-1.89612, "ay":6.06989, "alpha":0.10732, "fx":[-31.593,-32.58398,-32.91568,-31.91731], "fy":[103.45796,103.15574,103.03351,103.34139]}, + {"t":2.2217, "x":6.71902, "y":3.99534, "heading":-1.62228, "vx":-0.98654, "vy":-0.16204, "omega":-0.69984, "ax":-0.29347, "ay":4.32466, "alpha":2.23305, "fx":[3.55723,-12.00628,-14.68538,3.16713], "fy":[76.93112,76.64097,70.10045,70.57214]}, + {"t":2.2655, "x":6.67553, "y":3.9924, "heading":-1.65294, "vx":-0.9994, "vy":0.0274, "omega":-0.60202, "ax":0.00541, "ay":0.17337, "alpha":4.92359, "fx":[13.80871,-11.52724,-13.7832,11.86969], "fy":[14.63924,16.71521,-8.72007,-10.83838]}, + {"t":2.3093, "x":6.63175, "y":3.99376, "heading":-1.67931, "vx":-0.99916, "vy":0.03499, "omega":-0.38635, "ax":0.00014, "ay":0.00397, "alpha":4.18805, "fx":[11.98598,-9.62648,-11.98384,9.63383], "fy":[9.69787,12.05215,-9.56242,-11.91766]}, + {"t":2.35311, "x":6.58799, "y":3.9953, "heading":-1.69623, "vx":-0.99915, "vy":0.03517, "omega":-0.20289, "ax":0.0, "ay":0.00009, "alpha":3.51333, "fx":[10.18935,-7.90729,-10.18929,7.90744], "fy":[7.90889,10.19084,-7.90584,-10.1878]}, + {"t":2.39691, "x":6.54422, "y":3.99684, "heading":-1.70512, "vx":-0.99915, "vy":0.03517, "omega":-0.049, "ax":0.0, "ay":0.0, "alpha":2.89853, "fx":[8.46395,-6.4487,-8.46395,6.4487], "fy":[6.44873,8.46399,-6.44866,-8.46392]}, + {"t":2.44072, "x":6.50045, "y":3.99838, "heading":-1.70727, "vx":-0.99915, "vy":0.03517, "omega":0.07797, "ax":0.0, "ay":0.0, "alpha":2.3353, "fx":[6.83038,-5.18095,-6.83038,5.18095], "fy":[5.18095,6.83039,-5.18095,-6.83038]}, + {"t":2.48452, "x":6.45668, "y":3.99992, "heading":-1.70385, "vx":-0.99915, "vy":0.03517, "omega":0.18027, "ax":0.0, "ay":0.0, "alpha":1.81495, "fx":[5.29466,-4.04464,-5.29466,4.04464], "fy":[4.04464,5.29466,-4.04464,-5.29466]}, + {"t":2.52833, "x":6.41292, "y":4.00146, "heading":-1.69596, "vx":-0.99915, "vy":0.03517, "omega":0.25977, "ax":0.0, "ay":0.0, "alpha":1.32874, "fx":[3.85278,-2.99164,-3.85278,2.99164], "fy":[2.99164,3.85278,-2.99164,-3.85278]}, + {"t":2.57213, "x":6.36915, "y":4.003, "heading":-1.68458, "vx":-0.99915, "vy":0.03517, "omega":0.31797, "ax":0.0, "ay":0.0, "alpha":0.86798, "fx":[2.49438,-1.98276,-2.49438,1.98276], "fy":[1.98276,2.49438,-1.98276,-2.49438]}, + {"t":2.61593, "x":6.32538, "y":4.00454, "heading":-1.67065, "vx":-0.99915, "vy":0.03517, "omega":0.356, "ax":0.0, "ay":0.0, "alpha":0.42405, "fx":[1.20499,-0.98554,-1.20499,0.98554], "fy":[0.98554,1.20499,-0.98554,-1.20499]}, + {"t":2.65974, "x":6.28161, "y":4.00608, "heading":-1.65505, "vx":-0.99915, "vy":0.03517, "omega":0.37457, "ax":0.0, "ay":0.0, "alpha":-0.01162, "fx":[-0.03259,0.02752,0.03259,-0.02752], "fy":[-0.02752,-0.03259,0.02752,0.03259]}, + {"t":2.70354, "x":6.23785, "y":4.00762, "heading":-1.63865, "vx":-0.99915, "vy":0.03517, "omega":0.37406, "ax":0.0, "ay":0.0, "alpha":-0.44751, "fx":[-1.23775,1.08023,1.23775,-1.08023], "fy":[-1.08023,-1.23775,1.08023,1.23775]}, + {"t":2.74735, "x":6.19408, "y":4.00916, "heading":-1.62226, "vx":-0.99915, "vy":0.03517, "omega":0.35446, "ax":0.0, "ay":0.0, "alpha":-0.89213, "fx":[-2.43189,2.19363,2.43189,-2.19363], "fy":[-2.19363,-2.43189,2.19363,2.43189]}, + {"t":2.79115, "x":6.15031, "y":4.0107, "heading":-1.60673, "vx":-0.99915, "vy":0.03517, "omega":0.31538, "ax":0.0, "ay":0.0, "alpha":-1.35403, "fx":[-3.63886,3.38629,3.63886,-3.38629], "fy":[-3.38629,-3.63886,3.38629,3.63886]}, + {"t":2.83496, "x":6.10655, "y":4.01224, "heading":-1.59292, "vx":-0.99915, "vy":0.03517, "omega":0.25607, "ax":0.0, "ay":0.0, "alpha":-1.84184, "fx":[-4.8857,4.67418,4.8857,-4.67418], "fy":[-4.67418,-4.8857,4.67418,4.8857]}, + {"t":2.87876, "x":6.06278, "y":4.01379, "heading":-1.5817, "vx":-0.99915, "vy":0.03517, "omega":0.17539, "ax":0.00003, "ay":0.0, "alpha":-2.36427, "fx":[-6.20336,6.07037,6.20423,-6.0695], "fy":[-6.06996,-6.20381,6.06991,6.20378]}, + {"t":2.92256, "x":6.01901, "y":4.01533, "heading":-1.57402, "vx":-0.99915, "vy":0.03517, "omega":0.07182, "ax":3.48318, "ay":-0.12261, "alpha":-1.61638, "fx":[56.17178,62.13278,62.31394,56.37276], "fy":[-7.79132,-7.21183,3.17584,3.48534]}, + {"t":2.96637, "x":5.97859, "y":4.01675, "heading":-1.57087, "vx":-0.84658, "vy":0.0298, "omega":0.00102, "ax":6.43412, "ay":-0.22648, "alpha":-0.01142, "fx":[109.44021,109.44074,109.44488,109.44436], "fy":[-3.91344,-3.90925,-3.79128,-3.79535]}, + {"t":3.01017, "x":5.94768, "y":4.01784, "heading":-1.57083, "vx":-0.56473, "vy":0.01988, "omega":0.00052, "ax":6.44439, "ay":-0.22684, "alpha":-0.0067, "fx":[109.61599,109.61619,109.61862,109.61843], "fy":[-3.89441,-3.89195,-3.82258,-3.82499]}, + {"t":3.05398, "x":5.92912, "y":4.01849, "heading":-1.57081, "vx":-0.28244, "vy":0.00994, "omega":0.00022, "ax":6.44783, "ay":-0.22696, "alpha":-0.00513, "fx":[109.67479,109.67491,109.67678,109.67666], "fy":[-3.88803,-3.88615,-3.83306,-3.83492]}, + {"t":3.09778, "x":5.92294, "y":4.01871, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/deploy/choreo/F_PATH_5.traj b/src/main/deploy/choreo/F_PATH_5.traj index 53ac82e0..b5360132 100644 --- a/src/main/deploy/choreo/F_PATH_5.traj +++ b/src/main/deploy/choreo/F_PATH_5.traj @@ -3,7 +3,7 @@ "version":1, "snapshot":{ "waypoints":[ - {"x":6.090419769287109, "y":4.054448127746582, "heading":-1.5707963267948966, "intervals":66, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":5.9229350090026855, "y":4.018707752227783, "heading":-1.5707963267948966, "intervals":68, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":7.010232925415039, "y":6.064763069152832, "heading":1.5707963267948966, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -14,7 +14,7 @@ }, "params":{ "waypoints":[ - {"x":{"exp":"6.090419769287109 m", "val":6.090419769287109}, "y":{"exp":"4.054448127746582 m", "val":4.054448127746582}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":66, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, + {"x":{"exp":"5.9229350090026855 m", "val":5.9229350090026855}, "y":{"exp":"4.018707752227783 m", "val":4.018707752227783}, "heading":{"exp":"-90 deg", "val":-1.5707963267948966}, "intervals":68, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}, {"x":{"exp":"7.010232925415039 m", "val":7.010232925415039}, "y":{"exp":"6.064763069152832 m", "val":6.064763069152832}, "heading":{"exp":"90 deg", "val":1.5707963267948966}, "intervals":17, "split":false, "fixTranslation":true, "fixHeading":true, "overrideIntervals":false}], "constraints":[ {"from":"first", "to":null, "data":{"type":"StopPoint", "props":{}}, "enabled":true}, @@ -28,75 +28,77 @@ }, "trajectory":{ "sampleType":"Swerve", - "waypoints":[0.0,2.36827], + "waypoints":[0.0,2.47438], "samples":[ - {"t":0.0, "x":6.09042, "y":4.05445, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":2.684, "ay":5.86606, "alpha":0.01271, "fx":[45.68364,45.57468,45.62444,45.73347], "fy":[99.76655,99.8163,99.79341,99.74356]}, - {"t":0.03588, "x":6.09215, "y":4.05822, "heading":-1.5708, "vx":0.09631, "vy":0.21049, "omega":0.00046, "ax":2.68292, "ay":5.8637, "alpha":0.01555, "fx":[45.67188,45.53863,45.59945,45.73281], "fy":[99.72344,99.78424,99.7562,99.69525]}, - {"t":0.07177, "x":6.09733, "y":4.06955, "heading":-1.57078, "vx":0.19258, "vy":0.4209, "omega":0.00101, "ax":2.68076, "ay":5.85898, "alpha":0.02122, "fx":[45.6484,45.46663,45.5495,45.73147], "fy":[99.63732,99.72016,99.6818,99.59869]}, - {"t":0.10765, "x":6.10597, "y":4.08843, "heading":-1.57074, "vx":0.28877, "vy":0.63113, "omega":0.00178, "ax":2.67431, "ay":5.84485, "alpha":0.03824, "fx":[45.57814,45.25141,45.39988,45.72723], "fy":[99.38002,99.52835,99.4588,99.3096]}, - {"t":0.14353, "x":6.11805, "y":4.11484, "heading":-1.57068, "vx":0.38474, "vy":0.84086, "omega":0.00315, "ax":0.86977, "ay":1.90112, "alpha":5.47495, "fx":[27.94398,-0.38502,-0.45072,32.06958], "fy":[44.25745,46.84103,19.94891,18.30252]}, - {"t":0.17941, "x":6.13242, "y":4.14623, "heading":-1.57057, "vx":0.41595, "vy":0.90908, "omega":0.1996, "ax":0.00006, "ay":0.00001, "alpha":6.00985, "fx":[15.59793,-15.60314,-15.59599,15.6051], "fy":[15.60419,15.5971,-15.60406,-15.59682]}, - {"t":0.2153, "x":6.14734, "y":4.17885, "heading":-1.5634, "vx":0.41595, "vy":0.90908, "omega":0.41525, "ax":0.0, "ay":0.0, "alpha":5.37587, "fx":[13.85135,-14.05759,-13.85128,14.05765], "fy":[14.0576,13.8513,-14.05763,-13.85133]}, - {"t":0.25118, "x":6.16227, "y":4.21147, "heading":-1.5485, "vx":0.41595, "vy":0.90908, "omega":0.60816, "ax":0.0, "ay":0.0, "alpha":4.79692, "fx":[12.17133,-12.72645,-12.17133,12.72645], "fy":[12.72645,12.17133,-12.72645,-12.17133]}, - {"t":0.28706, "x":6.17719, "y":4.2441, "heading":-1.52668, "vx":0.41595, "vy":0.90908, "omega":0.78028, "ax":0.0, "ay":0.0, "alpha":4.27093, "fx":[10.58691,-11.56476,-10.58691,11.56475], "fy":[11.56475,10.58691,-11.56476,-10.58691]}, - {"t":0.32295, "x":6.19212, "y":4.27672, "heading":-1.49868, "vx":0.41595, "vy":0.90908, "omega":0.93354, "ax":0.0, "ay":0.0, "alpha":3.79521, "fx":[9.11629,-10.53594,-9.11629,10.53594], "fy":[10.53594,9.11629,-10.53594,-9.11629]}, - {"t":0.35883, "x":6.20704, "y":4.30934, "heading":-1.46518, "vx":0.41595, "vy":0.90908, "omega":1.06972, "ax":0.0, "ay":0.0, "alpha":3.3666, "fx":[7.76919,-9.61165,-7.76919,9.61165], "fy":[9.61165,7.76919,-9.61165,-7.76919]}, - {"t":0.39471, "x":6.22197, "y":4.34196, "heading":-1.4268, "vx":0.41595, "vy":0.90908, "omega":1.19052, "ax":0.0, "ay":0.0, "alpha":2.98169, "fx":[6.54918,-8.77053,-6.54918,8.77053], "fy":[8.77053,6.54918,-8.77053,-6.54918]}, - {"t":0.43059, "x":6.23689, "y":4.37458, "heading":-1.38408, "vx":0.41595, "vy":0.90908, "omega":1.29751, "ax":0.0, "ay":0.0, "alpha":2.63698, "fx":[5.4555,-7.99686,-5.4555,7.99686], "fy":[7.99686,5.4555,-7.99686,-5.4555]}, - {"t":0.46648, "x":6.25182, "y":4.4072, "heading":-1.33752, "vx":0.41595, "vy":0.90908, "omega":1.39214, "ax":0.0, "ay":0.0, "alpha":2.32896, "fx":[4.48431,-7.27935,-4.48431,7.27935], "fy":[7.27935,4.48431,-7.27935,-4.48431]}, - {"t":0.50236, "x":6.26674, "y":4.43982, "heading":-1.28757, "vx":0.41595, "vy":0.90908, "omega":1.47571, "ax":0.0, "ay":0.0, "alpha":2.05422, "fx":[3.62977,-6.61011,-3.62977,6.61011], "fy":[6.61011,3.62977,-6.61011,-3.62977]}, - {"t":0.53824, "x":6.28167, "y":4.47244, "heading":-1.23462, "vx":0.41595, "vy":0.90908, "omega":1.54942, "ax":0.0, "ay":0.0, "alpha":1.80949, "fx":[2.88469,-5.98369,-2.88468,5.9837], "fy":[5.98369,2.88468,-5.9837,-2.88469]}, - {"t":0.57413, "x":6.2966, "y":4.50506, "heading":-1.17902, "vx":0.41595, "vy":0.90908, "omega":1.61435, "ax":0.0, "ay":0.0, "alpha":1.59171, "fx":[2.24109,-5.3964,-2.24109,5.3964], "fy":[5.3964,2.24109,-5.3964,-2.24109]}, - {"t":0.61001, "x":6.31152, "y":4.53768, "heading":-1.12109, "vx":0.41595, "vy":0.90908, "omega":1.67146, "ax":0.0, "ay":0.0, "alpha":1.39801, "fx":[1.69066,-4.84571,-1.69066,4.84571], "fy":[4.84571,1.69066,-4.84571,-1.69066]}, - {"t":0.64589, "x":6.32645, "y":4.5703, "heading":-1.06111, "vx":0.41595, "vy":0.90908, "omega":1.72163, "ax":0.0, "ay":0.0, "alpha":1.22574, "fx":[1.225,-4.32981,-1.225,4.32982], "fy":[4.32982,1.225,-4.32982,-1.225]}, - {"t":0.68177, "x":6.34137, "y":4.60292, "heading":-0.99934, "vx":0.41595, "vy":0.90908, "omega":1.76561, "ax":0.0, "ay":0.0, "alpha":1.07248, "fx":[0.8359,-3.84736,-0.83589,3.84736], "fy":[3.84736,0.83589,-3.84736,-0.8359]}, - {"t":0.71766, "x":6.3563, "y":4.63554, "heading":-0.93598, "vx":0.41595, "vy":0.90908, "omega":1.80409, "ax":0.0, "ay":0.0, "alpha":0.93599, "fx":[0.51547,-3.39718,-0.51546,3.39718], "fy":[3.39718,0.51546,-3.39718,-0.51547]}, - {"t":0.75354, "x":6.37122, "y":4.66816, "heading":-0.87125, "vx":0.41595, "vy":0.90908, "omega":1.83768, "ax":0.0, "ay":0.0, "alpha":0.81426, "fx":[0.2563,-2.97817,-0.2563,2.97817], "fy":[2.97817,0.2563,-2.97817,-0.2563]}, - {"t":0.78942, "x":6.38615, "y":4.70078, "heading":-0.80531, "vx":0.41595, "vy":0.90908, "omega":1.8669, "ax":0.0, "ay":0.0, "alpha":0.70544, "fx":[0.05155,-2.5892,-0.05155,2.5892], "fy":[2.5892,0.05155,-2.5892,-0.05155]}, - {"t":0.82531, "x":6.40107, "y":4.7334, "heading":-0.73832, "vx":0.41595, "vy":0.90908, "omega":1.89221, "ax":0.0, "ay":0.0, "alpha":0.60788, "fx":[-0.10503,-2.22909,0.10503,2.22908], "fy":[2.22908,-0.10503,-2.22908,0.10503]}, - {"t":0.86119, "x":6.416, "y":4.76602, "heading":-0.67042, "vx":0.41595, "vy":0.90908, "omega":1.91402, "ax":0.0, "ay":0.0, "alpha":0.52005, "fx":[-0.21903,-1.89654,0.21903,1.89654], "fy":[1.89654,-0.21903,-1.89654,0.21903]}, - {"t":0.89707, "x":6.43092, "y":4.79864, "heading":-0.60174, "vx":0.41595, "vy":0.90908, "omega":1.93268, "ax":0.0, "ay":0.0, "alpha":0.4406, "fx":[-0.2954,-1.59025,0.29539,1.59024], "fy":[1.59025,-0.29539,-1.59025,0.2954]}, - {"t":0.93295, "x":6.44585, "y":4.83126, "heading":-0.53239, "vx":0.41595, "vy":0.90908, "omega":1.94849, "ax":0.0, "ay":0.0, "alpha":0.36825, "fx":[-0.3384,-1.30883,0.3384,1.30883], "fy":[1.30883,-0.3384,-1.30883,0.3384]}, - {"t":0.96884, "x":6.46077, "y":4.86388, "heading":-0.46247, "vx":0.41595, "vy":0.90908, "omega":1.96171, "ax":0.0, "ay":0.0, "alpha":0.30187, "fx":[-0.35168,-1.05092,0.35168,1.05091], "fy":[1.05092,-0.35168,-1.05091,0.35168]}, - {"t":1.00472, "x":6.4757, "y":4.8965, "heading":-0.39208, "vx":0.41595, "vy":0.90908, "omega":1.97254, "ax":0.0, "ay":0.0, "alpha":0.24041, "fx":[-0.33825,-0.81518,0.33825,0.81517], "fy":[0.81518,-0.33825,-0.81517,0.33825]}, - {"t":1.0406, "x":6.49062, "y":4.92912, "heading":-0.3213, "vx":0.41595, "vy":0.90908, "omega":1.98117, "ax":0.0, "ay":0.0, "alpha":0.18288, "fx":[-0.30052,-0.60036,0.30051,0.60035], "fy":[0.60036,-0.30052,-0.60035,0.30052]}, - {"t":1.07649, "x":6.50555, "y":4.96174, "heading":-0.25021, "vx":0.41595, "vy":0.90908, "omega":1.98773, "ax":0.0, "ay":0.0, "alpha":0.12836, "fx":[-0.24033,-0.40534,0.24032,0.40533], "fy":[0.40533,-0.24033,-0.40533,0.24033]}, - {"t":1.11237, "x":6.52048, "y":4.99436, "heading":-0.17888, "vx":0.41595, "vy":0.90908, "omega":1.99233, "ax":0.0, "ay":0.0, "alpha":0.07597, "fx":[-0.15898,-0.22916,0.15898,0.22916], "fy":[0.22916,-0.15898,-0.22916,0.15898]}, - {"t":1.14825, "x":6.5354, "y":5.02699, "heading":-0.10739, "vx":0.41595, "vy":0.90908, "omega":1.99506, "ax":0.0, "ay":0.0, "alpha":0.02487, "fx":[-0.05727,-0.0711,0.05726,0.0711], "fy":[0.0711,-0.05726,-0.0711,0.05726]}, - {"t":1.18413, "x":6.55033, "y":5.05961, "heading":-0.0358, "vx":0.41595, "vy":0.90908, "omega":1.99595, "ax":0.0, "ay":0.0, "alpha":-0.02578, "fx":[0.06449,0.06929,-0.06449,-0.06928], "fy":[-0.06929,0.06449,0.06929,-0.06449]}, - {"t":1.22002, "x":6.56525, "y":5.09223, "heading":0.03582, "vx":0.41595, "vy":0.90908, "omega":1.99503, "ax":0.0, "ay":0.0, "alpha":-0.07682, "fx":[0.20642,0.19214,-0.20641,-0.19213], "fy":[-0.19214,0.20642,0.19213,-0.20642]}, - {"t":1.2559, "x":6.58018, "y":5.12485, "heading":0.1074, "vx":0.41595, "vy":0.90908, "omega":1.99227, "ax":0.0, "ay":0.0, "alpha":-0.12907, "fx":[0.36902,0.29719,-0.36902,-0.29719], "fy":[-0.29719,0.36902,0.29719,-0.36902]}, - {"t":1.29178, "x":6.5951, "y":5.15747, "heading":0.17889, "vx":0.41595, "vy":0.90908, "omega":1.98764, "ax":0.0, "ay":0.0, "alpha":-0.1834, "fx":[0.55318,0.38376,-0.55318,-0.38376], "fy":[-0.38376,0.55318,0.38376,-0.55318]}, - {"t":1.32767, "x":6.61003, "y":5.19009, "heading":0.25022, "vx":0.41595, "vy":0.90908, "omega":1.98106, "ax":0.0, "ay":0.0, "alpha":-0.2407, "fx":[0.76008,0.45066,-0.76008,-0.45065], "fy":[-0.45065,0.76008,0.45065,-0.76008]}, - {"t":1.36355, "x":6.62495, "y":5.22271, "heading":0.3213, "vx":0.41595, "vy":0.90908, "omega":1.97242, "ax":0.0, "ay":0.0, "alpha":-0.30193, "fx":[0.99116,0.49614,-0.99115,-0.49613], "fy":[-0.49614,0.99115,0.49613,-0.99116]}, - {"t":1.39943, "x":6.63988, "y":5.25533, "heading":0.39208, "vx":0.41595, "vy":0.90908, "omega":1.96159, "ax":0.0, "ay":0.0, "alpha":-0.36807, "fx":[1.24805,0.51787,-1.24804,-0.51786], "fy":[-0.51787,1.24804,0.51787,-1.24805]}, - {"t":1.43531, "x":6.6548, "y":5.28795, "heading":0.46246, "vx":0.41595, "vy":0.90908, "omega":1.94838, "ax":0.0, "ay":0.0, "alpha":-0.44022, "fx":[1.53253,0.51286,-1.53253,-0.51286], "fy":[-0.51286,1.53253,0.51286,-1.53253]}, - {"t":1.4712, "x":6.66973, "y":5.32057, "heading":0.53238, "vx":0.41595, "vy":0.90908, "omega":1.93258, "ax":0.0, "ay":0.0, "alpha":-0.51952, "fx":[1.84646,0.47742,-1.84646,-0.47742], "fy":[-0.47742,1.84646,0.47742,-1.84646]}, - {"t":1.50708, "x":6.68465, "y":5.35319, "heading":0.60172, "vx":0.41595, "vy":0.90908, "omega":1.91394, "ax":0.0, "ay":0.0, "alpha":-0.60724, "fx":[2.19172,0.40715,-2.19172,-0.40715], "fy":[-0.40715,2.19172,0.40715,-2.19172]}, - {"t":1.54296, "x":6.69958, "y":5.38581, "heading":0.6704, "vx":0.41595, "vy":0.90908, "omega":1.89215, "ax":0.0, "ay":0.0, "alpha":-0.70476, "fx":[2.57013,0.29686,-2.57013,-0.29686], "fy":[-0.29686,2.57013,0.29686,-2.57013]}, - {"t":1.57885, "x":6.71451, "y":5.41843, "heading":0.7383, "vx":0.41595, "vy":0.90908, "omega":1.86686, "ax":0.0, "ay":0.0, "alpha":-0.81359, "fx":[2.98342,0.14062,-2.98342,-0.14062], "fy":[-0.14062,2.98342,0.14062,-2.98342]}, - {"t":1.61473, "x":6.72943, "y":5.45105, "heading":0.80529, "vx":0.41595, "vy":0.90908, "omega":1.83767, "ax":0.0, "ay":0.0, "alpha":-0.93538, "fx":[3.43317,-0.06829,-3.43317,0.06829], "fy":[0.06829,3.43317,-0.06829,-3.43317]}, - {"t":1.65061, "x":6.74436, "y":5.48367, "heading":0.87123, "vx":0.41595, "vy":0.90908, "omega":1.80411, "ax":0.0, "ay":0.0, "alpha":-1.07198, "fx":[3.9208,-0.33735,-3.9208,0.33735], "fy":[0.33735,3.9208,-0.33735,-3.9208]}, - {"t":1.68649, "x":6.75928, "y":5.51629, "heading":0.93596, "vx":0.41595, "vy":0.90908, "omega":1.76564, "ax":0.0, "ay":0.0, "alpha":-1.22537, "fx":[4.4475,-0.67475,-4.44751,0.67475], "fy":[0.67475,4.44751,-0.67475,-4.4475]}, - {"t":1.72238, "x":6.77421, "y":5.54891, "heading":0.99932, "vx":0.41595, "vy":0.90908, "omega":1.72167, "ax":0.0, "ay":0.0, "alpha":-1.39777, "fx":[5.01434,-1.08935,-5.01434,1.08935], "fy":[1.08935,5.01434,-1.08935,-5.01434]}, - {"t":1.75826, "x":6.78913, "y":5.58153, "heading":1.0611, "vx":0.41595, "vy":0.90908, "omega":1.67151, "ax":0.0, "ay":0.0, "alpha":-1.5916, "fx":[5.62221,-1.59055,-5.62221,1.59055], "fy":[1.59055,5.62221,-1.59055,-5.62221]}, - {"t":1.79414, "x":6.80406, "y":5.61415, "heading":1.12108, "vx":0.41595, "vy":0.90908, "omega":1.6144, "ax":0.0, "ay":0.0, "alpha":-1.8095, "fx":[6.27201,-2.1882,-6.27202,2.1882], "fy":[2.1882,6.27202,-2.1882,-6.27201]}, - {"t":1.83003, "x":6.81898, "y":5.64677, "heading":1.17901, "vx":0.41595, "vy":0.90908, "omega":1.54947, "ax":0.0, "ay":0.0, "alpha":-2.05431, "fx":[6.96481,-2.89234,-6.96481,2.89234], "fy":[2.89234,6.96481,-2.89234,-6.96481]}, - {"t":1.86591, "x":6.83391, "y":5.67939, "heading":1.23461, "vx":0.41595, "vy":0.90908, "omega":1.47576, "ax":0.0, "ay":0.0, "alpha":-2.32912, "fx":[7.70205,-3.713,-7.70205,3.713], "fy":[3.713,7.70205,-3.713,-7.70205]}, - {"t":1.90179, "x":6.84883, "y":5.71201, "heading":1.28756, "vx":0.41595, "vy":0.90908, "omega":1.39218, "ax":0.0, "ay":0.0, "alpha":-2.63717, "fx":[8.486,-4.65978,-8.486,4.65978], "fy":[4.65978,8.486,-4.65978,-8.486]}, - {"t":1.93767, "x":6.86376, "y":5.74463, "heading":1.33752, "vx":0.41595, "vy":0.90908, "omega":1.29755, "ax":0.0, "ay":0.0, "alpha":-2.98189, "fx":[9.32018,-5.74145,-9.32018,5.74145], "fy":[5.74145,9.32018,-5.74145,-9.32018]}, - {"t":1.97356, "x":6.87868, "y":5.77725, "heading":1.38408, "vx":0.41595, "vy":0.90908, "omega":1.19056, "ax":0.0, "ay":0.0, "alpha":-3.36678, "fx":[10.21008,-6.9653,-10.21008,6.9653], "fy":[6.9653,10.21008,-6.9653,-10.21008]}, - {"t":2.00944, "x":6.89361, "y":5.80988, "heading":1.4268, "vx":0.41595, "vy":0.90908, "omega":1.06975, "ax":0.0, "ay":0.0, "alpha":-3.79537, "fx":[11.16397,-8.33636,-11.16397,8.33636], "fy":[8.33636,11.16397,-8.33636,-11.16397]}, - {"t":2.04532, "x":6.90854, "y":5.8425, "heading":1.46518, "vx":0.41595, "vy":0.90908, "omega":0.93356, "ax":0.0, "ay":0.0, "alpha":-4.27106, "fx":[12.19393,-9.85641,-12.19393,9.85641], "fy":[9.85641,12.19393,-9.85641,-12.19393]}, - {"t":2.08121, "x":6.92346, "y":5.87512, "heading":1.49868, "vx":0.41595, "vy":0.90908, "omega":0.7803, "ax":0.0, "ay":0.0, "alpha":-4.79701, "fx":[13.31706,-11.52263,-13.31707,11.52263], "fy":[11.52263,13.31707,-11.52263,-13.31706]}, - {"t":2.11709, "x":6.93839, "y":5.90774, "heading":1.52668, "vx":0.41595, "vy":0.90908, "omega":0.60817, "ax":0.0, "ay":0.0, "alpha":-5.37592, "fx":[14.55681,-13.326,-14.55687,13.32593], "fy":[13.32598,14.55685,-13.32595,-14.55682]}, - {"t":2.15297, "x":6.95331, "y":5.94036, "heading":1.5485, "vx":0.41595, "vy":0.90908, "omega":0.41527, "ax":-0.00006, "ay":-0.00001, "alpha":-6.00986, "fx":[15.94348,-15.24993,-15.94543,15.24796], "fy":[15.24888,15.94431,-15.24901,-15.9446]}, - {"t":2.18885, "x":6.96824, "y":5.97298, "heading":1.5634, "vx":0.41595, "vy":0.90908, "omega":0.19961, "ax":-0.86976, "ay":-1.90112, "alpha":-5.47524, "fx":[0.58313,-31.97651,-28.05656,0.27214], "fy":[-20.07299,-18.19721,-44.16108,-46.91863]}, - {"t":2.22474, "x":6.9826, "y":6.00437, "heading":1.57057, "vx":0.38474, "vy":0.84086, "omega":0.00315, "ax":-2.67431, "ay":-5.84485, "alpha":-0.03824, "fx":[-45.39982,-45.72721,-45.57821,-45.25144], "fy":[-99.45883,-99.30961,-99.37999,-99.52834]}, - {"t":2.26062, "x":6.99469, "y":6.03078, "heading":1.57068, "vx":0.28877, "vy":0.63113, "omega":0.00178, "ax":-2.68076, "ay":-5.85898, "alpha":-0.02122, "fx":[-45.54949,-45.73146,-45.64842,-45.46663], "fy":[-99.68181,-99.5987,-99.63732,-99.72016]}, - {"t":2.2965, "x":7.00332, "y":6.04966, "heading":1.57074, "vx":0.19258, "vy":0.4209, "omega":0.00101, "ax":-2.68292, "ay":-5.8637, "alpha":-0.01555, "fx":[-45.59945,-45.73281,-45.67189,-45.53863], "fy":[-99.7562,-99.69525,-99.72343,-99.78424]}, - {"t":2.33239, "x":7.0085, "y":6.06099, "heading":1.57078, "vx":0.09631, "vy":0.21049, "omega":0.00046, "ax":-2.684, "ay":-5.86606, "alpha":-0.01271, "fx":[-45.62444,-45.73348,-45.68364,-45.57467], "fy":[-99.79341,-99.74356,-99.76655,-99.8163]}, - {"t":2.36827, "x":7.01023, "y":6.06476, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], + {"t":0.0, "x":5.92294, "y":4.01871, "heading":-1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":3.0273, "ay":5.69671, "alpha":0.0115, "fx":[51.51534,51.4223,51.47166,51.56474], "fy":[96.88791,96.93725,96.91091,96.86149]}, + {"t":0.03639, "x":5.92494, "y":4.02248, "heading":-1.5708, "vx":0.11016, "vy":0.20729, "omega":0.00042, "ax":3.02611, "ay":5.69447, "alpha":0.01406, "fx":[51.49999,51.38632,51.44659,51.56032], "fy":[96.84737,96.90761,96.8754,96.81504]}, + {"t":0.07278, "x":5.93095, "y":4.03379, "heading":-1.57078, "vx":0.22027, "vy":0.4145, "omega":0.00093, "ax":3.02374, "ay":5.69, "alpha":0.01917, "fx":[51.46931,51.31442,51.39646,51.55145], "fy":[96.76637,96.84834,96.80436,96.72216]}, + {"t":0.10916, "x":5.94097, "y":4.05264, "heading":-1.57075, "vx":0.3303, "vy":0.62155, "omega":0.00163, "ax":3.01662, "ay":5.67661, "alpha":0.0345, "fx":[51.37746,51.09924,51.24613,51.52469], "fy":[96.52402,96.67071,96.59124,96.44383]}, + {"t":0.14555, "x":5.95498, "y":4.07902, "heading":-1.57069, "vx":0.44007, "vy":0.82811, "omega":0.00288, "ax":0.79883, "ay":1.50329, "alpha":5.44405, "fx":[26.7412,-1.03873,-1.17995,29.82866], "fy":[38.08307,40.19109,12.45553,11.55248]}, + {"t":0.18194, "x":5.97153, "y":4.11015, "heading":-1.57058, "vx":0.46914, "vy":0.88281, "omega":0.20098, "ax":0.00003, "ay":0.00001, "alpha":5.56926, "fx":[14.45428,-14.45942,-14.45326,14.46046], "fy":[14.46007,14.45393,-14.45981,-14.45361]}, + {"t":0.21833, "x":5.9886, "y":4.14227, "heading":-1.56327, "vx":0.46914, "vy":0.88281, "omega":0.40364, "ax":0.0, "ay":0.0, "alpha":4.96921, "fx":[12.80178,-12.99592,-12.80175,12.99595], "fy":[12.99593,12.80176,-12.99594,-12.80177]}, + {"t":0.25472, "x":6.00567, "y":4.17439, "heading":-1.54858, "vx":0.46914, "vy":0.88281, "omega":0.58446, "ax":0.0, "ay":0.0, "alpha":4.42407, "fx":[11.22621,-11.73639,-11.22621,11.73639], "fy":[11.73639,11.22621,-11.73639,-11.22621]}, + {"t":0.2911, "x":6.02274, "y":4.20652, "heading":-1.52732, "vx":0.46914, "vy":0.88281, "omega":0.74544, "ax":0.0, "ay":0.0, "alpha":3.93112, "fx":[9.7513,-10.63843,-9.75131,10.63843], "fy":[10.63843,9.7513,-10.63843,-9.7513]}, + {"t":0.32749, "x":6.03981, "y":4.23864, "heading":-1.50019, "vx":0.46914, "vy":0.88281, "omega":0.88848, "ax":0.0, "ay":0.0, "alpha":3.48714, "fx":[8.39087,-9.66806,-8.39087,9.66806], "fy":[9.66806,8.39087,-9.66806,-8.39087]}, + {"t":0.36388, "x":6.05688, "y":4.27076, "heading":-1.46786, "vx":0.46914, "vy":0.88281, "omega":1.01537, "ax":0.0, "ay":0.0, "alpha":3.08863, "fx":[7.15129,-8.79897,-7.15129,8.79897], "fy":[8.79897,7.15129,-8.79897,-7.15129]}, + {"t":0.40027, "x":6.07395, "y":4.30289, "heading":-1.43091, "vx":0.46914, "vy":0.88281, "omega":1.12776, "ax":0.0, "ay":0.0, "alpha":2.73198, "fx":[6.03369,-8.01126,-6.03369,8.01126], "fy":[8.01126,6.03369,-8.01126,-6.03369]}, + {"t":0.43666, "x":6.09102, "y":4.33501, "heading":-1.38988, "vx":0.46914, "vy":0.88281, "omega":1.22717, "ax":0.0, "ay":0.0, "alpha":2.41354, "fx":[5.03556,-7.2902,-5.03556,7.2902], "fy":[7.2902,5.03556,-7.2902,-5.03556]}, + {"t":0.47304, "x":6.10809, "y":4.36714, "heading":-1.34522, "vx":0.46914, "vy":0.88281, "omega":1.315, "ax":0.0, "ay":0.0, "alpha":2.12979, "fx":[4.15195,-6.62507,-4.15195,6.62507], "fy":[6.62507,4.15195,-6.62507,-4.15195]}, + {"t":0.50943, "x":6.12516, "y":4.39926, "heading":-1.29737, "vx":0.46914, "vy":0.88281, "omega":1.3925, "ax":0.0, "ay":0.0, "alpha":1.87736, "fx":[3.37632,-6.0082,-3.37632,6.0082], "fy":[6.0082,3.37632,-6.0082,-3.37632]}, + {"t":0.54582, "x":6.14224, "y":4.43138, "heading":-1.2467, "vx":0.46914, "vy":0.88281, "omega":1.46081, "ax":0.0, "ay":0.0, "alpha":1.65305, "fx":[2.70116,-5.43413,-2.70115,5.43413], "fy":[5.43413,2.70115,-5.43413,-2.70115]}, + {"t":0.58221, "x":6.15931, "y":4.46351, "heading":-1.19354, "vx":0.46914, "vy":0.88281, "omega":1.52096, "ax":0.0, "ay":0.0, "alpha":1.45391, "fx":[2.11846,-4.89898,-2.11846,4.89898], "fy":[4.89898,2.11846,-4.89898,-2.11846]}, + {"t":0.6186, "x":6.17638, "y":4.49563, "heading":-1.1382, "vx":0.46914, "vy":0.88281, "omega":1.57387, "ax":0.0, "ay":0.0, "alpha":1.27722, "fx":[1.62009,-4.39994,-1.62009,4.39995], "fy":[4.39994,1.62009,-4.39995,-1.62009]}, + {"t":0.65498, "x":6.19345, "y":4.52775, "heading":-1.08093, "vx":0.46914, "vy":0.88281, "omega":1.62034, "ax":0.0, "ay":0.0, "alpha":1.12045, "fx":[1.19798,-3.93492,-1.19798,3.93492], "fy":[3.93492,1.19798,-3.93492,-1.19798]}, + {"t":0.69137, "x":6.21052, "y":4.55988, "heading":-1.02197, "vx":0.46914, "vy":0.88281, "omega":1.66111, "ax":0.0, "ay":0.0, "alpha":0.98134, "fx":[0.84433,-3.50222,-0.84433,3.50222], "fy":[3.50222,0.84433,-3.50222,-0.84433]}, + {"t":0.72776, "x":6.22759, "y":4.592, "heading":-0.96152, "vx":0.46914, "vy":0.88281, "omega":1.69682, "ax":0.0, "ay":0.0, "alpha":0.85781, "fx":[0.55177,-3.10036,-0.55177,3.10036], "fy":[3.10036,0.55177,-3.10036,-0.55177]}, + {"t":0.76415, "x":6.24466, "y":4.62413, "heading":-0.89978, "vx":0.46914, "vy":0.88281, "omega":1.72804, "ax":0.0, "ay":0.0, "alpha":0.748, "fx":[0.3134,-2.728,-0.3134,2.728], "fy":[2.728,0.3134,-2.728,-0.3134]}, + {"t":0.80054, "x":6.26173, "y":4.65625, "heading":-0.8369, "vx":0.46914, "vy":0.88281, "omega":1.75525, "ax":0.0, "ay":0.0, "alpha":0.6502, "fx":[0.12288,-2.38377,-0.12288,2.38377], "fy":[2.38377,0.12288,-2.38377,-0.12288]}, + {"t":0.83692, "x":6.2788, "y":4.68837, "heading":-0.77303, "vx":0.46914, "vy":0.88281, "omega":1.77891, "ax":0.0, "ay":0.0, "alpha":0.56291, "fx":[-0.02556,-2.06631,0.02556,2.06631], "fy":[2.06631,-0.02556,-2.06631,0.02556]}, + {"t":0.87331, "x":6.29587, "y":4.7205, "heading":-0.7083, "vx":0.46914, "vy":0.88281, "omega":1.7994, "ax":0.0, "ay":0.0, "alpha":0.48474, "fx":[-0.13706,-1.77422,0.13706,1.77422], "fy":[1.77422,-0.13706,-1.77422,0.13706]}, + {"t":0.9097, "x":6.31295, "y":4.75262, "heading":-0.64282, "vx":0.46914, "vy":0.88281, "omega":1.81704, "ax":0.0, "ay":0.0, "alpha":0.41446, "fx":[-0.21619,-1.50606,0.21619,1.50605], "fy":[1.50606,-0.21619,-1.50605,0.21619]}, + {"t":0.94609, "x":6.33002, "y":4.78475, "heading":-0.57671, "vx":0.46914, "vy":0.88281, "omega":1.83212, "ax":0.0, "ay":0.0, "alpha":0.35094, "fx":[-0.26692,-1.26037,0.26691,1.26037], "fy":[1.26037,-0.26692,-1.26037,0.26692]}, + {"t":0.98248, "x":6.34709, "y":4.81687, "heading":-0.51004, "vx":0.46914, "vy":0.88281, "omega":1.84489, "ax":0.0, "ay":0.0, "alpha":0.29317, "fx":[-0.29263,-1.03571,0.29263,1.03571], "fy":[1.03571,-0.29263,-1.03571,0.29263]}, + {"t":1.01886, "x":6.36416, "y":4.84899, "heading":-0.44291, "vx":0.46914, "vy":0.88281, "omega":1.85555, "ax":0.0, "ay":0.0, "alpha":0.24023, "fx":[-0.29617,-0.83067,0.29617,0.83067], "fy":[0.83067,-0.29617,-0.83067,0.29617]}, + {"t":1.05525, "x":6.38123, "y":4.88112, "heading":-0.37539, "vx":0.46914, "vy":0.88281, "omega":1.8643, "ax":0.0, "ay":0.0, "alpha":0.19125, "fx":[-0.27986,-0.64389,0.27986,0.64388], "fy":[0.64388,-0.27986,-0.64388,0.27986]}, + {"t":1.09164, "x":6.3983, "y":4.91324, "heading":-0.30755, "vx":0.46914, "vy":0.88281, "omega":1.87125, "ax":0.0, "ay":0.0, "alpha":0.14544, "fx":[-0.24553,-0.4741,0.24553,0.4741], "fy":[0.4741,-0.24553,-0.4741,0.24553]}, + {"t":1.12803, "x":6.41537, "y":4.94536, "heading":-0.23946, "vx":0.46914, "vy":0.88281, "omega":1.87655, "ax":0.0, "ay":0.0, "alpha":0.10205, "fx":[-0.19453,-0.32019,0.19452,0.32019], "fy":[0.32019,-0.19452,-0.32019,0.19453]}, + {"t":1.16442, "x":6.43244, "y":4.97749, "heading":-0.17117, "vx":0.46914, "vy":0.88281, "omega":1.88026, "ax":0.0, "ay":0.0, "alpha":0.06039, "fx":[-0.12777,-0.18117,0.12777,0.18117], "fy":[0.18117,-0.12777,-0.18117,0.12777]}, + {"t":1.2008, "x":6.44951, "y":5.00961, "heading":-0.10275, "vx":0.46914, "vy":0.88281, "omega":1.88246, "ax":0.0, "ay":0.0, "alpha":0.01976, "fx":[-0.04575,-0.05628,0.04575,0.05628], "fy":[0.05628,-0.04575,-0.05628,0.04575]}, + {"t":1.23719, "x":6.46658, "y":5.04174, "heading":-0.03426, "vx":0.46914, "vy":0.88281, "omega":1.88318, "ax":0.0, "ay":0.0, "alpha":-0.02051, "fx":[0.0514,0.05504,-0.05139,-0.05504], "fy":[-0.05504,0.05139,0.05504,-0.0514]}, + {"t":1.27358, "x":6.48365, "y":5.07386, "heading":0.03427, "vx":0.46914, "vy":0.88281, "omega":1.88243, "ax":0.0, "ay":0.0, "alpha":-0.06109, "fx":[0.16392,0.15306,-0.16392,-0.15305], "fy":[-0.15306,0.16392,0.15305,-0.16392]}, + {"t":1.30997, "x":6.50073, "y":5.10598, "heading":0.10277, "vx":0.46914, "vy":0.88281, "omega":1.88021, "ax":0.0, "ay":0.0, "alpha":-0.10265, "fx":[0.2924,0.23772,-0.29239,-0.23772], "fy":[-0.23772,0.29239,0.23772,-0.29239]}, + {"t":1.34636, "x":6.5178, "y":5.13811, "heading":0.17118, "vx":0.46914, "vy":0.88281, "omega":1.87647, "ax":0.0, "ay":0.0, "alpha":-0.14589, "fx":[0.43768,0.30866,-0.43767,-0.30865], "fy":[-0.30865,0.43767,0.30865,-0.43768]}, + {"t":1.38274, "x":6.53487, "y":5.17023, "heading":0.23947, "vx":0.46914, "vy":0.88281, "omega":1.87116, "ax":0.0, "ay":0.0, "alpha":-0.19152, "fx":[0.60089,0.36506,-0.60089,-0.36505], "fy":[-0.36506,0.60089,0.36506,-0.60089]}, + {"t":1.41913, "x":6.55194, "y":5.20235, "heading":0.30755, "vx":0.46914, "vy":0.88281, "omega":1.86419, "ax":0.0, "ay":0.0, "alpha":-0.24032, "fx":[0.7834,0.4057,-0.7834,-0.4057], "fy":[-0.4057,0.7834,0.4057,-0.7834]}, + {"t":1.45552, "x":6.56901, "y":5.23448, "heading":0.37539, "vx":0.46914, "vy":0.88281, "omega":1.85545, "ax":0.0, "ay":0.0, "alpha":-0.29308, "fx":[0.98673,0.42888,-0.98673,-0.42888], "fy":[-0.42888,0.98673,0.42888,-0.98673]}, + {"t":1.49191, "x":6.58608, "y":5.2666, "heading":0.4429, "vx":0.46914, "vy":0.88281, "omega":1.84479, "ax":0.0, "ay":0.0, "alpha":-0.35068, "fx":[1.21258,0.43234,-1.21258,-0.43234], "fy":[-0.43234,1.21258,0.43234,-1.21258]}, + {"t":1.5283, "x":6.60315, "y":5.29873, "heading":0.51003, "vx":0.46914, "vy":0.88281, "omega":1.83202, "ax":0.0, "ay":0.0, "alpha":-0.41405, "fx":[1.46275,0.41329,-1.46275,-0.41329], "fy":[-0.41329,1.46275,0.41329,-1.46275]}, + {"t":1.56468, "x":6.62022, "y":5.33085, "heading":0.5767, "vx":0.46914, "vy":0.88281, "omega":1.81696, "ax":0.0, "ay":0.0, "alpha":-0.48424, "fx":[1.73908,0.36831,-1.73908,-0.36831], "fy":[-0.36831,1.73908,0.36831,-1.73908]}, + {"t":1.60107, "x":6.63729, "y":5.36297, "heading":0.64281, "vx":0.46914, "vy":0.88281, "omega":1.79934, "ax":0.0, "ay":0.0, "alpha":-0.56235, "fx":[2.04347,0.29336,-2.04347,-0.29336], "fy":[-0.29336,2.04347,0.29336,-2.04347]}, + {"t":1.63746, "x":6.65436, "y":5.3951, "heading":0.70829, "vx":0.46914, "vy":0.88281, "omega":1.77888, "ax":0.0, "ay":0.0, "alpha":-0.64963, "fx":[2.37776,0.18372,-2.37776,-0.18372], "fy":[-0.18372,2.37776,0.18372,-2.37776]}, + {"t":1.67385, "x":6.67144, "y":5.42722, "heading":0.77302, "vx":0.46914, "vy":0.88281, "omega":1.75524, "ax":0.0, "ay":0.0, "alpha":-0.74746, "fx":[2.74376,0.03398,-2.74376,-0.03398], "fy":[-0.03398,2.74376,0.03398,-2.74376]}, + {"t":1.71024, "x":6.68851, "y":5.45934, "heading":0.83688, "vx":0.46914, "vy":0.88281, "omega":1.72804, "ax":0.0, "ay":0.0, "alpha":-0.85734, "fx":[3.14319,-0.16198,-3.14319,0.16197], "fy":[0.16198,3.14319,-0.16197,-3.14319]}, + {"t":1.74662, "x":6.70558, "y":5.49147, "heading":0.89976, "vx":0.46914, "vy":0.88281, "omega":1.69684, "ax":0.0, "ay":0.0, "alpha":-0.98097, "fx":[3.57765,-0.41096,-3.57766,0.41096], "fy":[0.41096,3.57765,-0.41096,-3.57765]}, + {"t":1.78301, "x":6.72265, "y":5.52359, "heading":0.96151, "vx":0.46914, "vy":0.88281, "omega":1.66115, "ax":0.0, "ay":0.0, "alpha":-1.12018, "fx":[4.04865,-0.72048,-4.04865,0.72048], "fy":[0.72048,4.04865,-0.72048,-4.04865]}, + {"t":1.8194, "x":6.73972, "y":5.55572, "heading":1.02195, "vx":0.46914, "vy":0.88281, "omega":1.62038, "ax":0.0, "ay":0.0, "alpha":-1.27706, "fx":[4.55759,-1.0987,-4.5576,1.0987], "fy":[1.0987,4.5576,-1.0987,-4.55759]}, + {"t":1.85579, "x":6.75679, "y":5.58784, "heading":1.08092, "vx":0.46914, "vy":0.88281, "omega":1.57391, "ax":0.0, "ay":0.0, "alpha":-1.45386, "fx":[5.10585,-1.55439,-5.10585,1.55439], "fy":[1.55439,5.10585,-1.55439,-5.10585]}, + {"t":1.89218, "x":6.77386, "y":5.61996, "heading":1.13819, "vx":0.46914, "vy":0.88281, "omega":1.52101, "ax":0.0, "ay":0.0, "alpha":-1.65309, "fx":[5.69482,-2.0968,-5.69482,2.0968], "fy":[2.0968,5.69482,-2.0968,-5.69482]}, + {"t":1.92856, "x":6.79093, "y":5.65209, "heading":1.19354, "vx":0.46914, "vy":0.88281, "omega":1.46086, "ax":0.0, "ay":0.0, "alpha":-1.87746, "fx":[6.32614,-2.73554,-6.32614,2.73554], "fy":[2.73554,6.32614,-2.73554,-6.32614]}, + {"t":1.96495, "x":6.808, "y":5.68421, "heading":1.24669, "vx":0.46914, "vy":0.88281, "omega":1.39254, "ax":0.0, "ay":0.0, "alpha":-2.12994, "fx":[7.00186,-3.48036,-7.00186,3.48036], "fy":[3.48036,7.00186,-3.48036,-7.00186]}, + {"t":2.00134, "x":6.82507, "y":5.71633, "heading":1.29737, "vx":0.46914, "vy":0.88281, "omega":1.31504, "ax":0.0, "ay":0.0, "alpha":-2.41371, "fx":[7.72476,-4.34088,-7.72476,4.34088], "fy":[4.34088,7.72476,-4.34088,-7.72476]}, + {"t":2.03773, "x":6.84215, "y":5.74846, "heading":1.34522, "vx":0.46914, "vy":0.88281, "omega":1.22721, "ax":0.0, "ay":0.0, "alpha":-2.73215, "fx":[8.49885,-5.3262,-8.49885,5.3262], "fy":[5.3262,8.49885,-5.3262,-8.49885]}, + {"t":2.07412, "x":6.85922, "y":5.78058, "heading":1.38987, "vx":0.46914, "vy":0.88281, "omega":1.12779, "ax":0.0, "ay":0.0, "alpha":-3.0888, "fx":[9.32988,-6.44438,-9.32988,6.44438], "fy":[6.44438,9.32988,-6.44438,-9.32988]}, + {"t":2.1105, "x":6.87629, "y":5.81271, "heading":1.43091, "vx":0.46914, "vy":0.88281, "omega":1.01539, "ax":0.0, "ay":0.0, "alpha":-3.48729, "fx":[10.22615,-7.7018,-10.22615,7.7018], "fy":[7.7018,10.22615,-7.7018,-10.22615]}, + {"t":2.14689, "x":6.89336, "y":5.84483, "heading":1.46786, "vx":0.46914, "vy":0.88281, "omega":0.8885, "ax":0.0, "ay":0.0, "alpha":-3.93124, "fx":[11.19941,-9.10219,-11.19941,9.10219], "fy":[9.10219,11.19941,-9.10219,-11.19941]}, + {"t":2.18328, "x":6.91043, "y":5.87695, "heading":1.50019, "vx":0.46914, "vy":0.88281, "omega":0.74545, "ax":0.0, "ay":0.0, "alpha":-4.42416, "fx":[12.26595,-10.64554,-12.26595,10.64554], "fy":[10.64554,12.26595,-10.64554,-12.26595]}, + {"t":2.21967, "x":6.9275, "y":5.90908, "heading":1.52731, "vx":0.46914, "vy":0.88281, "omega":0.58446, "ax":0.0, "ay":0.0, "alpha":-4.96926, "fx":[13.44787,-12.32647,-13.44789,12.32644], "fy":[12.32647,13.44789,-12.32645,-13.44787]}, + {"t":2.25606, "x":6.94457, "y":5.9412, "heading":1.54858, "vx":0.46914, "vy":0.88281, "omega":0.40364, "ax":-0.00003, "ay":-0.00001, "alpha":-5.56929, "fx":[14.77396,-14.13275,-14.775,14.1317], "fy":[14.1321,14.77432,-14.13235,-14.77464]}, + {"t":2.29244, "x":6.96164, "y":5.97333, "heading":1.56327, "vx":0.46914, "vy":0.88281, "omega":0.20099, "ax":-0.79883, "ay":-1.50329, "alpha":-5.44418, "fx":[1.30648,-29.73243,-26.8513,0.9261], "fy":[-12.57935,-11.4431,-37.98319,-40.27654]}, + {"t":2.32883, "x":6.97818, "y":6.00445, "heading":1.57058, "vx":0.44007, "vy":0.82811, "omega":0.00288, "ax":-3.01662, "ay":-5.67661, "alpha":-0.0345, "fx":[-51.24607,-51.52468,-51.37751,-51.09926], "fy":[-96.59127,-96.44384,-96.52399,-96.6707]}, + {"t":2.36522, "x":6.9922, "y":6.03083, "heading":1.57069, "vx":0.3303, "vy":0.62155, "omega":0.00163, "ax":-3.02374, "ay":-5.69, "alpha":-0.01917, "fx":[-51.39644,-51.55145,-51.46932,-51.31443], "fy":[-96.80437,-96.72216,-96.76636,-96.84834]}, + {"t":2.40161, "x":7.00222, "y":6.04968, "heading":1.57075, "vx":0.22027, "vy":0.4145, "omega":0.00093, "ax":-3.02611, "ay":-5.69447, "alpha":-0.01406, "fx":[-51.44659,-51.56032,-51.49999,-51.38632], "fy":[-96.8754,-96.81504,-96.84737,-96.90761]}, + {"t":2.438, "x":7.00823, "y":6.06099, "heading":1.57078, "vx":0.11016, "vy":0.20729, "omega":0.00042, "ax":-3.0273, "ay":-5.69671, "alpha":-0.0115, "fx":[-51.47166,-51.56474,-51.51534,-51.4223], "fy":[-96.91091,-96.86149,-96.88791,-96.93725]}, + {"t":2.47438, "x":7.01023, "y":6.06476, "heading":1.5708, "vx":0.0, "vy":0.0, "omega":0.0, "ax":0.0, "ay":0.0, "alpha":0.0, "fx":[0.0,0.0,0.0,0.0], "fy":[0.0,0.0,0.0,0.0]}], "splits":[0] }, "events":[] diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 4b343dc0..0b2ef474 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -5,7 +5,7 @@ public final class Constants { public static final boolean TUNING_MODE = true; public static final double LOOP_PERIOD_SECONDS = 0.02; - public static final RobotType ROBOT = RobotType.V3_EPSILON; + public static final RobotType ROBOT = RobotType.V3_EPSILON_SIM; public static Mode getMode() { switch (ROBOT) { diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index 4c684128..35548f4d 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -2126,17 +2126,15 @@ public static final LoggedAutoRoutine autoFLeft( superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), superstructure.waitUntilAtGoal(), Commands.parallel( - path2.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_ALGAE)), - CompositeCommands.V3_EpsilonCompositeCommands.intakeAlgaeFromReefAuto( - drive, superstructure, cameras), + path2.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE)), Commands.parallel( path3.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), Commands.runOnce(() -> drive.stop()), CompositeCommands.V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure), Commands.parallel( - path4.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), - CompositeCommands.V3_EpsilonCompositeCommands.intakeAlgaeFromReefAuto( - drive, superstructure, cameras), + path4.cmd(), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE)), Commands.parallel( path5.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), Commands.runOnce(() -> drive.stop()), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index dafff28f..41464c0b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -2,6 +2,7 @@ import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.apriltag.AprilTagFields; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command; @@ -87,7 +88,7 @@ public V3_EpsilonRobotContainer() { elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); - // climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); + // climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); leds = new V3_EpsilonLEDs(); vision = @@ -288,7 +289,14 @@ private void configureButtonBindings() { operator.leftBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))); operator.rightBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))); - operator.povUp().onTrue(climber.releaseClimber()).onFalse(climber.winchClimber()); + operator + .povUp() + .onTrue( + Commands.sequence( + Commands.runOnce(() -> manipulator.setArmGoal(Rotation2d.fromDegrees(90))), + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.HANDOFF)), + climber.releaseClimber())) + .onFalse(climber.winchClimber()); operator.povDown().whileTrue(climber.winchClimberManual()); operator .povLeft() diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java index 32793a70..dbfe468f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java @@ -8,16 +8,14 @@ public class V3_EpsilonClimberConstants { public static final int ROLLER_CAN_ID; - public static final int MOTOR_ID; public static final MotorParameters MOTOR_PARAMETERS; public static final double CLIMBER_CLIMBED_RADIANS; static { - DEPLOYMENT_CAN_ID = 42; - ROLLER_CAN_ID = 42; + DEPLOYMENT_CAN_ID = 50; + ROLLER_CAN_ID = 51; - MOTOR_ID = 50; MOTOR_PARAMETERS = new MotorParameters(DCMotor.getKrakenX60Foc(1), 24.0, 0.81, Units.inchesToMeters(1.78)); @@ -27,10 +25,8 @@ public class V3_EpsilonClimberConstants { public static record MotorParameters( DCMotor MOTOR_CONFIG, double GEAR_RATIO, double GEARBOX_EFFICIENCY, double SPOOL_DIAMETER) {} - public static final double CLIMBER_CLIMBED_ZERO_RADIANS = - 41; // TODO: None of these four lines are valid numbers i - // just made up stuff - public static final double CLIMBER_CLIMBED_DEPLOYED_RADIANS = 67; + public static final double CLIMBER_CLIMBED_ZERO_RADIANS = 41; + public static final double CLIMBER_CLIMBED_DEPLOYED_RADIANS = Units.rotationsToRadians(-2); public static final ClimberTimingConfig CLIMBER_TIMING_CONFIG = new ClimberTimingConfig(1.1, 0.25, 0.5); public static final CurrentLimits CURRENT_LIMITS = new CurrentLimits(40.0, 80.0); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java index 8c4e4663..131bb6f8 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java @@ -8,6 +8,7 @@ import com.ctre.phoenix6.controls.VoltageOut; import com.ctre.phoenix6.hardware.TalonFX; import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.util.Units; import edu.wpi.first.units.measure.Angle; import edu.wpi.first.units.measure.AngularVelocity; import edu.wpi.first.units.measure.Current; @@ -108,4 +109,10 @@ public void setdeploymentVoltage(double volts) { public void setRollerVoltage(double volts) { rollerTalonFX.setControl(rollerVoltageRequest.withOutput(volts).withEnableFOC(true)); } + + @Override + public boolean isClimbed() { + return Units.rotationsToRadians(deploymentPositionRotations.getValueAsDouble()) + >= V3_EpsilonClimberConstants.CLIMBER_CLIMBED_RADIANS; + } } From 58fd66480b8beaa003cb1e7e562cd6299595acdc Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Fri, 24 Oct 2025 18:10:20 -0400 Subject: [PATCH 146/180] Refactor climber commands and constants for improved functionality and performance --- src/main/java/frc/robot/Constants.java | 2 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 11 +++++++---- .../v3_Epsilon/climber/V3_EpsilonClimber.java | 14 +++++++++----- .../climber/V3_EpsilonClimberConstants.java | 2 +- .../climber/V3_EpsilonClimberIOTalonFX.java | 4 ++-- 5 files changed, 20 insertions(+), 13 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 0b2ef474..4b343dc0 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -5,7 +5,7 @@ public final class Constants { public static final boolean TUNING_MODE = true; public static final double LOOP_PERIOD_SECONDS = 0.02; - public static final RobotType ROBOT = RobotType.V3_EPSILON_SIM; + public static final RobotType ROBOT = RobotType.V3_EPSILON; public static Mode getMode() { switch (ROBOT) { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 41464c0b..0605423c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -37,6 +37,7 @@ import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimber; import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIO; import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIOSim; +import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIOTalonFX; import frc.robot.subsystems.v3_Epsilon.leds.V3_EpsilonLEDs; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; @@ -88,7 +89,7 @@ public V3_EpsilonRobotContainer() { elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); - // climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); + climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); leds = new V3_EpsilonLEDs(); vision = @@ -294,10 +295,12 @@ private void configureButtonBindings() { .onTrue( Commands.sequence( Commands.runOnce(() -> manipulator.setArmGoal(Rotation2d.fromDegrees(90))), - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.HANDOFF)), - climber.releaseClimber())) - .onFalse(climber.winchClimber()); + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.HANDOFF)))); operator.povDown().whileTrue(climber.winchClimberManual()); + Trigger isClimberReady = new Trigger(() -> RobotState.isClimberReady()); + isClimberReady + .and(operator.povDown()) + .onTrue(Commands.runOnce(() -> elevator.setPosition(() -> ReefState.STOW))); operator .povLeft() .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR)) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java index 132a35cb..098d459d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java @@ -75,11 +75,11 @@ public Command setRollerVoltage(double volts) { * @return A command to release the climber. */ public Command releaseClimber() { - return this.runEnd(() -> io.setDeploymentVoltage(1), () -> io.setDeploymentVoltage(0)) + return this.runEnd(() -> io.setDeploymentVoltage(-1), () -> io.setDeploymentVoltage(0)) .until( () -> inputs.deploymentPosition.getRadians() - >= V3_EpsilonClimberConstants.CLIMBER_CLIMBED_DEPLOYED_RADIANS + <= V3_EpsilonClimberConstants.CLIMBER_CLIMBED_DEPLOYED_RADIANS || override) .finallyDo(() -> RobotState.setClimberReady(true)); } @@ -91,8 +91,10 @@ public Command releaseClimber() { * @return A command to winch the climber. */ public Command winchClimber() { - return Commands.runEnd(() -> io.setRollerVoltage(12), () -> io.setRollerVoltage(0)) - .until(() -> isClimbed); + return Commands.parallel( + Commands.runOnce(() -> io.setRollerVoltage(0)), + Commands.runEnd(() -> io.setDeploymentVoltage(-12), () -> io.setDeploymentVoltage(0)) + .until(() -> isClimbed)); } /** @@ -101,7 +103,9 @@ public Command winchClimber() { * @return A command to manually winch the climber. */ public Command winchClimberManual() { - return this.runEnd(() -> io.setRollerVoltage(4), () -> io.setRollerVoltage(0)); + return Commands.parallel( + Commands.runOnce(() -> io.setRollerVoltage(0)), + this.runEnd(() -> io.setDeploymentVoltage(-12.0), () -> io.setDeploymentVoltage(0))); } /** diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java index dbfe468f..e8010d9c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java @@ -26,7 +26,7 @@ public static record MotorParameters( DCMotor MOTOR_CONFIG, double GEAR_RATIO, double GEARBOX_EFFICIENCY, double SPOOL_DIAMETER) {} public static final double CLIMBER_CLIMBED_ZERO_RADIANS = 41; - public static final double CLIMBER_CLIMBED_DEPLOYED_RADIANS = Units.rotationsToRadians(-2); + public static final double CLIMBER_CLIMBED_DEPLOYED_RADIANS = -10; public static final ClimberTimingConfig CLIMBER_TIMING_CONFIG = new ClimberTimingConfig(1.1, 0.25, 0.5); public static final CurrentLimits CURRENT_LIMITS = new CurrentLimits(40.0, 80.0); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java index 131bb6f8..3059657a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java @@ -49,7 +49,7 @@ public V3_EpsilonClimberIOTalonFX() { rollerConfig = new TalonFXConfiguration(); rollerPositionRotations = rollerTalonFX.getPosition(); rollerVelocityRotationsPerSecond = rollerTalonFX.getVelocity(); - rollerAppliedVoltage = rollerTalonFX.getSupplyVoltage(); + rollerAppliedVoltage = rollerTalonFX.getMotorVoltage(); rollerSupplyCurrentAmps = rollerTalonFX.getSupplyCurrent(); rollerTorqueCurrentAmps = rollerTalonFX.getTorqueCurrent(); rollerTemperatureCelsius = rollerTalonFX.getDeviceTemp(); @@ -58,7 +58,7 @@ public V3_EpsilonClimberIOTalonFX() { deploymentConfig = new TalonFXConfiguration(); deploymentPositionRotations = deploymentTalonFX.getPosition(); deploymentVelocityRotationsPerSecond = deploymentTalonFX.getVelocity(); - deploymentAppliedVoltage = deploymentTalonFX.getSupplyVoltage(); + deploymentAppliedVoltage = deploymentTalonFX.getMotorVoltage(); deploymentSupplyCurrentAmps = deploymentTalonFX.getSupplyCurrent(); deploymentTorqueCurrentAmps = deploymentTalonFX.getTorqueCurrent(); deploymentTemperatureCelsius = deploymentTalonFX.getDeviceTemp(); From cb00716d312036d45b11e9eb9ef3bfa58d4bf2f0 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Sat, 25 Oct 2025 18:29:00 -0400 Subject: [PATCH 147/180] 9991 --- .wpilib/wpilib_preferences.json | 2 +- build.gradle | 2 +- .../frc/robot/commands/CompositeCommands.java | 2 +- .../shared/elevator/ElevatorConstants.java | 2 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 17 +++++++++++------ .../v3_Epsilon/climber/V3_EpsilonClimber.java | 18 ++++++++++-------- .../climber/V3_EpsilonClimberConstants.java | 4 ++-- .../climber/V3_EpsilonClimberIOTalonFX.java | 5 +++-- 8 files changed, 30 insertions(+), 22 deletions(-) diff --git a/.wpilib/wpilib_preferences.json b/.wpilib/wpilib_preferences.json index b78bd1bd..74b5b54b 100644 --- a/.wpilib/wpilib_preferences.json +++ b/.wpilib/wpilib_preferences.json @@ -2,5 +2,5 @@ "enableCppIntellisense": false, "currentLanguage": "java", "projectYear": "2025", - "teamNumber": 190 + "teamNumber": 9991 } diff --git a/build.gradle b/build.gradle index 17f28036..e7d54a27 100755 --- a/build.gradle +++ b/build.gradle @@ -69,7 +69,7 @@ import com.jcraft.jsch.* ext { // RoboRIO SSH details - roboRIOHost = 'roboRIO-190-FRC.local' // Replace with your team number + roboRIOHost = 'roboRIO-9991-FRC.local' // Replace with your team number roboRIOUser = 'admin' // Default user roboRIOPassword = '' // Default password machineInfoFile = '/etc/machine-info' // Path to the file to read diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index d57a2d3f..c05eb193 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -670,7 +670,7 @@ public static final Command intakeCoralDriverSequence( superstructure.runGoalUntil( V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoralLoose()), superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.HANDOFF_SPIN, () -> intake.hasCoralLocked()), + V3_EpsilonSuperstructureStates.HANDOFF, () -> intake.hasCoralLocked()), postIntakeCoralSequence(superstructure, intake, manipulator)); } diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index 748dc24d..b0e06318 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -332,7 +332,7 @@ public static enum ElevatorPositions { new PositionConstants( 1.3864590139769697 + Units.inchesToMeters(0.5), 1.3864590139769697 + Units.inchesToMeters(0.5), - Units.inchesToMeters(48))), + Units.inchesToMeters(50))), L4_PLUS( new PositionConstants( 0.0, diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 0605423c..81444889 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -42,6 +42,7 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakePivotState; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIO; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOSim; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOTalonFX; @@ -295,12 +296,16 @@ private void configureButtonBindings() { .onTrue( Commands.sequence( Commands.runOnce(() -> manipulator.setArmGoal(Rotation2d.fromDegrees(90))), - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.HANDOFF)))); - operator.povDown().whileTrue(climber.winchClimberManual()); - Trigger isClimberReady = new Trigger(() -> RobotState.isClimberReady()); - isClimberReady - .and(operator.povDown()) - .onTrue(Commands.runOnce(() -> elevator.setPosition(() -> ReefState.STOW))); + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.HANDOFF)), + Commands.runOnce(() -> intake.setPivotGoal(IntakePivotState.L1)), + climber.releaseClimber())); + operator + .povDown() + .whileTrue( + Commands.sequence( + Commands.runOnce(() -> RobotState.setClimberReady(false)), + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.STOW)), + climber.winchClimber())); operator .povLeft() .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR)) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java index 098d459d..a7b52179 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java @@ -42,7 +42,7 @@ public void periodic() { isClimbed = io.isClimbed(); if (RobotState.isClimberReady()) { - io.setRollerVoltage(12); + io.setRollerVoltage(-12); } ExternalLoggedTracer.record("Climber Total", "Climber/Periodic"); @@ -75,13 +75,15 @@ public Command setRollerVoltage(double volts) { * @return A command to release the climber. */ public Command releaseClimber() { - return this.runEnd(() -> io.setDeploymentVoltage(-1), () -> io.setDeploymentVoltage(0)) - .until( - () -> - inputs.deploymentPosition.getRadians() - <= V3_EpsilonClimberConstants.CLIMBER_CLIMBED_DEPLOYED_RADIANS - || override) - .finallyDo(() -> RobotState.setClimberReady(true)); + return Commands.sequence( + Commands.runOnce(() -> io.setRollerVoltage(12)), + this.runEnd(() -> io.setDeploymentVoltage(-1), () -> io.setDeploymentVoltage(0)) + .until( + () -> + inputs.deploymentPosition.getRadians() + <= V3_EpsilonClimberConstants.CLIMBER_CLIMBED_DEPLOYED_RADIANS + || override) + .finallyDo(() -> RobotState.setClimberReady(true))); } /** diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java index e8010d9c..a87b4aa0 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java @@ -17,9 +17,9 @@ public class V3_EpsilonClimberConstants { ROLLER_CAN_ID = 51; MOTOR_PARAMETERS = - new MotorParameters(DCMotor.getKrakenX60Foc(1), 24.0, 0.81, Units.inchesToMeters(1.78)); + new MotorParameters(DCMotor.getKrakenX60Foc(1), 16.0, 0.81, Units.inchesToMeters(1.78)); - CLIMBER_CLIMBED_RADIANS = 410; + CLIMBER_CLIMBED_RADIANS = -350; } public static record MotorParameters( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java index 3059657a..081e69a9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java @@ -102,7 +102,8 @@ public void updateInputs(V3_EpsilonClimberIOInputs inputs) { inputs.rollerTemperatureCelsius = rollerTemperatureCelsius.getValueAsDouble(); } - public void setdeploymentVoltage(double volts) { + @Override + public void setDeploymentVoltage(double volts) { deploymentTalonFX.setControl(deploymentVoltageRequest.withOutput(volts).withEnableFOC(true)); } @@ -113,6 +114,6 @@ public void setRollerVoltage(double volts) { @Override public boolean isClimbed() { return Units.rotationsToRadians(deploymentPositionRotations.getValueAsDouble()) - >= V3_EpsilonClimberConstants.CLIMBER_CLIMBED_RADIANS; + <= V3_EpsilonClimberConstants.CLIMBER_CLIMBED_RADIANS; } } From 3d9e419ec35a791d44374372e570c710bfa4d019 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sun, 26 Oct 2025 19:16:48 -0400 Subject: [PATCH 148/180] format --- build.gradle | 21 +++++++++++---------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/build.gradle b/build.gradle index c3f50906..0ca0d637 100755 --- a/build.gradle +++ b/build.gradle @@ -75,10 +75,10 @@ deploy { // The options below may improve performance, but should only be enabled on the RIO 2 - // final MAX_JAVA_HEAP_SIZE_MB = 100; - // jvmArgs.add("-Xmx" + MAX_JAVA_HEAP_SIZE_MB + "M") - // jvmArgs.add("-Xms" + MAX_JAVA_HEAP_SIZE_MB + "M") - // jvmArgs.add("-XX:+AlwaysPreTouch") + final MAX_JAVA_HEAP_SIZE_MB = 100; + jvmArgs.add("-Xmx" + MAX_JAVA_HEAP_SIZE_MB + "M") + jvmArgs.add("-Xms" + MAX_JAVA_HEAP_SIZE_MB + "M") + jvmArgs.add("-XX:+AlwaysPreTouch") // Enable VisualVM connection // jvmArgs.add("-Dcom.sun.management.jmxremote=true") @@ -103,7 +103,8 @@ deploy { } // Grab the roboRIO comment via SSH -import com.jcraft.jsch.* + +import com.jcraft.jsch.JSch ext { // RoboRIO SSH details @@ -320,12 +321,12 @@ tasks.withType(JavaCompile) { // Create version file project.compileJava.dependsOn(createVersionFile) gversion { - srcDir = "src/main/java/" + srcDir = "src/main/java/" classPackage = "frc.robot" - className = "BuildConstants" - dateFormat = "yyyy-MM-dd HH:mm:ss z" - timeZone = "America/New_York" - indent = " " + className = "BuildConstants" + dateFormat = "yyyy-MM-dd HH:mm:ss z" + timeZone = "America/New_York" + indent = " " } // Create commit with working changes on event branches From a93e1266360e3ada555f4bd97ed4e0c26d606d39 Mon Sep 17 00:00:00 2001 From: iamabhiveni Date: Mon, 27 Oct 2025 18:49:54 -0400 Subject: [PATCH 149/180] Co-authored-by: jasminepalit Co-authored-by: Prabhudesai, Arnav --- src/main/java/frc/robot/Constants.java | 2 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 2 +- .../V3_EpsilonSuperstructurePose.java | 37 +++++++++++++------ 3 files changed, 28 insertions(+), 13 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 4b343dc0..0b2ef474 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -5,7 +5,7 @@ public final class Constants { public static final boolean TUNING_MODE = true; public static final double LOOP_PERIOD_SECONDS = 0.02; - public static final RobotType ROBOT = RobotType.V3_EPSILON; + public static final RobotType ROBOT = RobotType.V3_EPSILON_SIM; public static Mode getMode() { switch (ROBOT) { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 81444889..a32f344c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -388,6 +388,6 @@ public void robotPeriodic() { */ @Override public Command getAutonomousCommand() { - return autoChooser.selectedCommand(); + return AutonomousCommands.autoELeft(drive, superstructure, intake, manipulator, null).cmd(); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java index ab7c2ef0..348a7f9b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java @@ -90,21 +90,36 @@ public Command wait( V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator, Optional condition) { - return Commands.sequence( + + return Commands.either( + Commands.either( + elevator.waitUntilAtGoal(), + manipulator.waitUntilArmAtGoal(), + () -> + condition + .get() + .equals(V3_EpsilonSuperstructureTransitionCondition.ELEVATOR_AT_GOAL)), Commands.parallel( elevator.waitUntilAtGoal(), manipulator.waitUntilArmAtGoal(), intake.waitUntilPivotAtGoal()), - Commands.either( - Commands.either( - elevator.waitUntilAtGoal(), - manipulator.waitUntilArmAtGoal(), - () -> - condition - .get() - .equals(V3_EpsilonSuperstructureTransitionCondition.ELEVATOR_AT_GOAL)), - Commands.none(), - () -> condition.isPresent())); + () -> condition.isPresent()); + + // return Commands.sequence( + // Commands.parallel( + // elevator.waitUntilAtGoal(), + // manipulator.waitUntilArmAtGoal(), + // intake.waitUntilPivotAtGoal()), + // Commands.either( + // Commands.either( + // elevator.waitUntilAtGoal(), + // manipulator.waitUntilArmAtGoal(), + // () -> + // condition + // .get() + // .equals(V3_EpsilonSuperstructureTransitionCondition.ELEVATOR_AT_GOAL)), + // Commands.none(), + // () -> condition.isPresent())); } /** From 665a6279dfa4e9f4d9d0abe2775260d3cba16719 Mon Sep 17 00:00:00 2001 From: ArnavPrabhudesai Date: Mon, 27 Oct 2025 19:30:25 -0400 Subject: [PATCH 150/180] Tested code --- src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java index b9d37eb2..0b434bc4 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java @@ -338,6 +338,7 @@ public BooleanSupplier inFastScoringTolerance() { } } + //FSM for the Elevator public class ElevatorFSM { @AutoLogOutput(key = "Elevator/Past Barge Threshold") public boolean pastBargeThresholdgetPositionMeters() { From 3acafff62ae3e1e41af016be3522efe482b982fe Mon Sep 17 00:00:00 2001 From: Elliot Scher <44726531+ElliotScher@users.noreply.github.com> Date: Fri, 31 Oct 2025 15:36:21 -0400 Subject: [PATCH 151/180] before BOTB and GBTG (#150) * Altered the direction the arm goes when scoring. Co-authored-by: SeptimusHeap7 * initial * add flyby * Worked on windmill states. Co-authored-by: SeptimusHeap7 Co-authored-by: Elliot Scher Co-authored-by: Kevin Reas Co-authored-by: Sriaditya Vaddadi Co-authored-by: adembele2 * add flyby * Update constants and FSM logic for V3 Epsilon to barge score * barge * barge * barge * barge * barge * barge * barge * barge * make stuff work --------- Co-authored-by: jasminepalit Co-authored-by: SeptimusHeap7 Co-authored-by: Elliot Scher Co-authored-by: Kevin Reas Co-authored-by: Sriaditya Vaddadi Co-authored-by: adembele2 Co-authored-by: Anshu Adiga --- src/main/deploy/Superstructure.dot | 11 +- src/main/java/frc/robot/Constants.java | 2 +- src/main/java/frc/robot/RobotState.java | 101 +++++++++--- .../frc/robot/commands/CompositeCommands.java | 93 ++--------- .../shared/drive/DriveConstants.java | 4 +- .../subsystems/shared/elevator/Elevator.java | 14 +- .../shared/elevator/ElevatorConstants.java | 2 +- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 27 +-- .../superstructure/Superstructure.dot | 133 +++++++-------- .../V3_EpsilonSuperstructure.java | 156 +++++------------- .../V3_EpsilonSuperstructureEdges.java | 8 +- .../V3_EpsilonSuperstructurePose.java | 83 +++++----- .../V3_EpsilonSuperstructureStates.java | 100 ++++------- ...ilonSuperstructureTransitionCondition.java | 6 - .../manipulator/V3_EpsilonManipulator.java | 62 +++---- .../V3_EpsilonManipulatorConstants.java | 33 ++-- 16 files changed, 339 insertions(+), 496 deletions(-) delete mode 100644 src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureTransitionCondition.java diff --git a/src/main/deploy/Superstructure.dot b/src/main/deploy/Superstructure.dot index 3e83e71a..b2aea297 100644 --- a/src/main/deploy/Superstructure.dot +++ b/src/main/deploy/Superstructure.dot @@ -91,7 +91,7 @@ digraph Superstructure { L3_SCORE -> FLIP_DOWN [type=UNCONSTRAINED] L3_SCORE -> L2 [type=UNCONSTRAINED] L3_SCORE -> L4 [type=UNCONSTRAINED] - L3_SCORE -> L3_SCORE [type=UNCONSTRAINED] + L3_SCORE -> L3 [type=UNCONSTRAINED] L3_SCORE -> HANDOFF [type=UNCONSTRAINED] L3_SCORE -> STOW_UP [type=UNCONSTRAINED] L3_SCORE -> L2_ALGAE [type=UNCONSTRAINED] @@ -223,12 +223,7 @@ digraph Superstructure { HANDOFF_SPIN -> HANDOFF HANDOFF -> HANDOFF_SPIN - INVERSE_FLIP_DOWN -> GROUND_INTAKE_CORAL - GROUND_INTAKE_CORAL -> INVERSE_FLIP_UP + HANDOFF -> INVERSE_FLIP_UP - L4_SCORE -> INVERSE_FLIP_DOWN - L2_SCORE -> INVERSE_FLIP_DOWN - - INVERSE_FLIP_UP -> L2 - INVERSE_FLIP_UP -> L4 + INVERSE_FLIP_UP -> STOW_UP } \ No newline at end of file diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 0b2ef474..4b343dc0 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -5,7 +5,7 @@ public final class Constants { public static final boolean TUNING_MODE = true; public static final double LOOP_PERIOD_SECONDS = 0.02; - public static final RobotType ROBOT = RobotType.V3_EPSILON_SIM; + public static final RobotType ROBOT = RobotType.V3_EPSILON; public static Mode getMode() { switch (ROBOT) { diff --git a/src/main/java/frc/robot/RobotState.java b/src/main/java/frc/robot/RobotState.java index 2ae14697..39255259 100644 --- a/src/main/java/frc/robot/RobotState.java +++ b/src/main/java/frc/robot/RobotState.java @@ -1,5 +1,6 @@ package frc.robot; +import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.Matrix; import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator; import edu.wpi.first.math.geometry.Pose2d; @@ -17,11 +18,7 @@ import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.subsystems.shared.drive.DriveConstants; import frc.robot.subsystems.shared.vision.Camera; -import frc.robot.util.AllianceFlipUtil; -import frc.robot.util.ExternalLoggedTracer; -import frc.robot.util.GeometryUtil; -import frc.robot.util.InternalLoggedTracer; -import frc.robot.util.NTPrefixes; +import frc.robot.util.*; import java.util.Optional; import lombok.Getter; import lombok.Setter; @@ -42,7 +39,7 @@ public class RobotState { @Getter @Setter private static RobotMode mode; @Getter @Setter private static boolean hasAlgae; - @Getter @Setter private static ScoreSide scoreSide; + @Getter private static ScoreSide scoreSide; @Getter @Setter private static boolean isIntakingCoral; @Getter @Setter private static boolean isIntakingAlgae; @@ -152,22 +149,87 @@ public static void periodic( // auto // alignment to the reef to score coral - Pose2d autoAlignCoralSetpoint = + // --- 1. Get the BASE setpoint (the target location on the field) --- + + Pose2d baseCoralSetpoint = OIData.currentReefHeight().equals(ReefState.L1) ? Reef.reefMap.get(closestReefTag).getPostSetpoint(ReefPose.CENTER) : Reef.reefMap.get(closestReefTag).getPostSetpoint(OIData.currentReefPost()); - if (scoreSide == ScoreSide.RIGHT) { - autoAlignCoralSetpoint = - new Pose2d( - autoAlignCoralSetpoint.getX(), - autoAlignCoralSetpoint.getY(), - autoAlignCoralSetpoint.getRotation().rotateBy(new Rotation2d(-Math.PI / 2))); - } else if (scoreSide == ScoreSide.LEFT) { - autoAlignCoralSetpoint = - new Pose2d( - autoAlignCoralSetpoint.getX(), - autoAlignCoralSetpoint.getY(), - autoAlignCoralSetpoint.getRotation().rotateBy(new Rotation2d(Math.PI / 2))); + + Pose2d autoAlignCoralSetpoint = baseCoralSetpoint; + + if (OIData.currentReefHeight().equals(ReefState.L1)) { + scoreSide = ScoreSide.CENTER; + } else { + + // --- 2. Automatically determine the closest side of the ROBOT --- + Pose2d robotPose = getRobotPoseReef(); + // Translation2d targetTranslation = baseCoralSetpoint.getTranslation(); + // + // + // // Define "left" and "right" points on the robot, relative to its center. + // // We'll use the Y-trackwidth from DriveConstants. + // // In WPILib, +Y is "left" and -Y is "right" in robot-local coordinates. + // // + // double robotHalfWidth = DriveConstants.DRIVE_CONFIG.bumperLength() / 2.0; + // + // // Transform these robot-local points into field-global coordinates + // Translation2d leftSideField = + // robotPose + // .transformBy(new Transform2d(new Translation2d(0, + // robotHalfWidth), new Rotation2d())) + // .getTranslation(); + // Translation2d rightSideField = + // robotPose + // .transformBy(new Transform2d(new Translation2d(0, + // -robotHalfWidth), new Rotation2d())) + // .getTranslation(); + // + // // Calculate distance from each robot side to the target + // double distToLeft = leftSideField.getDistance(targetTranslation); + // double distToRight = rightSideField.getDistance(targetTranslation); + // + // // Set the static scoreSide variable based on which side is closer + // // (This variable is now updated every loop) + // if (distToLeft < distToRight) { + // scoreSide = ScoreSide.LEFT; + // } else { + // scoreSide = ScoreSide.RIGHT; + // } + + if (Math.abs( + MathUtil.angleModulus( + baseCoralSetpoint + .getRotation() + .rotateBy(Rotation2d.fromDegrees(-90)) + .minus(RobotState.getRobotPoseField().getRotation()) + .getRadians())) + <= Math.abs( + MathUtil.angleModulus( + baseCoralSetpoint + .getRotation() + .rotateBy(Rotation2d.fromDegrees(90)) + .minus(RobotState.getRobotPoseField().getRotation()) + .getRadians()))) { + scoreSide = ScoreSide.RIGHT; + } else { + scoreSide = ScoreSide.LEFT; + } + + // --- 3. Now, create the FINAL setpoint using the newly-set scoreSide --- + if (scoreSide == ScoreSide.RIGHT) { + autoAlignCoralSetpoint = + new Pose2d( + baseCoralSetpoint.getX(), + baseCoralSetpoint.getY(), + baseCoralSetpoint.getRotation().rotateBy(new Rotation2d(-Math.PI / 2))); + } else { + autoAlignCoralSetpoint = + new Pose2d( + baseCoralSetpoint.getX(), + baseCoralSetpoint.getY(), + baseCoralSetpoint.getRotation().rotateBy(new Rotation2d(Math.PI / 2))); + } } // @Author: Abhiraam Venigalla, Ananth Krishna Gomattam, Atharv Joshi, Chris Xu, @@ -288,6 +350,7 @@ public static void periodic( Logger.recordOutput(NTPrefixes.ALGAE_DATA + "Algae Setpoint Error", distanceToAlgaeSetpoint); Logger.recordOutput(NTPrefixes.ALGAE_DATA + "At Algae Setpoint", atAlgaeSetpoint); Logger.recordOutput(NTPrefixes.ALGAE_DATA + "Algae Height", algaeHeight); + Logger.recordOutput(NTPrefixes.REEF_DATA + "Score Side", scoreSide); ExternalLoggedTracer.record("Robot State Total", "RobotState/Periodic"); } diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index c05eb193..3b115c96 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -1,17 +1,13 @@ package frc.robot.commands; -import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.kinematics.ChassisSpeeds; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; -import frc.robot.FieldConstants; -import frc.robot.FieldConstants.Reef; import frc.robot.FieldConstants.Reef.ReefPose; import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotState; -import frc.robot.RobotState.ScoreSide; import frc.robot.subsystems.shared.climber.Climber; import frc.robot.subsystems.shared.climber.ClimberConstants; import frc.robot.subsystems.shared.drive.Drive; @@ -679,10 +675,17 @@ public static final Command postIntakeCoralSequence( V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { return Commands.either( - Commands.sequence( - superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.HANDOFF_SPIN, () -> manipulator.hasCoral()), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), + Commands.either( + Commands.sequence( + superstructure.runGoalUntil( + V3_EpsilonSuperstructureStates.HANDOFF_SPIN, () -> manipulator.hasCoral()), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), + Commands.none(), + () -> + !superstructure.getTargetState().equals(V3_EpsilonSuperstructureStates.STOW_UP) + && !superstructure + .getCurrentState() + .equals(V3_EpsilonSuperstructureStates.STOW_UP)), superstructure.runGoal(V3_EpsilonSuperstructureStates.L1), () -> !RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); } @@ -700,16 +703,6 @@ public static final Command optimalAutoScoreCoralSequence( Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { return Commands.either( Commands.sequence( - // Commands.runOnce( - // () -> { - // if (RobotState.getOIData().currentReefHeight().equals(ReefState.L1)) { - // RobotState.setScoreSide(ScoreSide.CENTER); - // } else { - // RobotState.setScoreSide( - // optimalSideReef(RobotState.getReefAlignData().coralSetpoint())); - // } - // }) - // .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), superstructure.setPosition(), DriveCommands.autoAlignReefCoral(drive, cameras) .until(() -> RobotState.getReefAlignData().atCoralSetpoint()), @@ -721,16 +714,6 @@ public static final Command optimalAutoScoreCoralSequence( public static final Command optimalAutoScoreCoralSequence( Drive drive, V3_EpsilonSuperstructure superstructure, ReefState height, Camera... cameras) { return Commands.sequence( - Commands.runOnce( - () -> { - if (RobotState.getOIData().currentReefHeight().equals(ReefState.L1)) { - RobotState.setScoreSide(ScoreSide.CENTER); - } else { - RobotState.setScoreSide( - optimalSideReef(RobotState.getReefAlignData().coralSetpoint())); - } - }) - .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), superstructure.runReefGoal(() -> height), DriveCommands.autoAlignReefCoral(drive, cameras), Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), @@ -746,61 +729,15 @@ public static final Command optimalAutoScoreCoralSequence( public static final Command optimalAutoAlignReefAlgae( Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { return Commands.sequence( - Commands.runOnce( - () -> { - int closestReefTag = RobotState.getReefAlignData().closestReefTag(); - if (closestReefTag != -1) { - Pose2d baseAlgaeSetpoint = - Reef.reefMap.get(closestReefTag).getAlgaeSetpoint(); - RobotState.setScoreSide(optimalSideReef(baseAlgaeSetpoint)); - } - }) - .beforeStarting(() -> RobotState.setScoreSide(ScoreSide.CENTER)), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), DriveCommands.autoAlignReefAlgae(drive, cameras)); } - private static final ScoreSide optimalSideReef(Pose2d baseSetpoint) { - if (Math.abs( - MathUtil.angleModulus( - baseSetpoint - .getRotation() - .rotateBy(Rotation2d.fromDegrees(-90)) - .minus(RobotState.getRobotPoseField().getRotation()) - .getRadians())) - <= Math.abs( - MathUtil.angleModulus( - baseSetpoint - .getRotation() - .rotateBy(Rotation2d.fromDegrees(90)) - .minus(RobotState.getRobotPoseField().getRotation()) - .getRadians()))) { - return ScoreSide.RIGHT; - } else { - return ScoreSide.LEFT; - } - } - - private static final ScoreSide optimalSideBarge() { - boolean facingPositive = - MathUtil.inputModulus( - RobotState.getRobotPoseField().getRotation().getRadians(), 0, 2 * Math.PI) - >= 0 - && MathUtil.inputModulus( - RobotState.getRobotPoseField().getRotation().getRadians(), 0, 2 * Math.PI) - < Math.PI; - - if (RobotState.getRobotPoseField().getX() < FieldConstants.fieldLength / 2) - return facingPositive ? ScoreSide.RIGHT : ScoreSide.LEFT; - else return facingPositive ? ScoreSide.LEFT : ScoreSide.RIGHT; - } - public static final Command optimalScoreBarge(V3_EpsilonSuperstructure superstructure) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setScoreSide(optimalSideBarge())), - superstructure - .runGoalUntil(V3_EpsilonSuperstructureStates.BARGE_SCORE, () -> false) - .withTimeout(2)); + return superstructure + .runGoal(V3_EpsilonSuperstructureStates.BARGE_SCORE) + .andThen( + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.BARGE_SCORE, 1)); } /** diff --git a/src/main/java/frc/robot/subsystems/shared/drive/DriveConstants.java b/src/main/java/frc/robot/subsystems/shared/drive/DriveConstants.java index 7db9c82c..a5fef6b9 100644 --- a/src/main/java/frc/robot/subsystems/shared/drive/DriveConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/drive/DriveConstants.java @@ -253,8 +253,8 @@ public class DriveConstants { FRONT_RIGHT, BACK_LEFT, BACK_RIGHT, - Units.inchesToMeters(34.5), - Units.inchesToMeters(34.5)); + Units.inchesToMeters(33.5), + Units.inchesToMeters(33.5)); GAINS = new Gains( diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java index 0b434bc4..e0588912 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java @@ -1,8 +1,6 @@ package frc.robot.subsystems.shared.elevator; -import static edu.wpi.first.units.Units.Second; -import static edu.wpi.first.units.Units.Seconds; -import static edu.wpi.first.units.Units.Volts; +import static edu.wpi.first.units.Units.*; import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj2.command.Command; @@ -338,13 +336,11 @@ public BooleanSupplier inFastScoringTolerance() { } } - //FSM for the Elevator + // FSM for the Elevator public class ElevatorFSM { @AutoLogOutput(key = "Elevator/Past Barge Threshold") public boolean pastBargeThresholdgetPositionMeters() { - if (Constants.getMode() == Mode.REAL) - return inputs.accelerationMetersPerSecondSquared < -1.0 - && inputs.velocityMetersPerSecond > 4; + if (Constants.getMode() == Mode.REAL) return inputs.velocityMetersPerSecond > 2.75; else { return inputs.positionMeters > .95; } @@ -431,6 +427,10 @@ public boolean atGoal(ReefState position) { return Elevator.this.atGoal(Elevator.this.getPosition(position)); } + public boolean inTolerance(double toleranceMeters) { + return Math.abs(positionGoalMeters - inputs.positionMeters) <= toleranceMeters; + } + public Command waitUntilAtGoal() { return Elevator.this.waitUntilAtGoal(); } diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index b0e06318..bcdc1cf3 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -303,7 +303,7 @@ public static enum ElevatorPositions { new PositionConstants( 0.2161583093038944 + Units.inchesToMeters(1), 0.2161583093038944 + Units.inchesToMeters(1), - 0)), + 0.1819)), ALGAE_MID( new PositionConstants( 0.7073684509805078, 0.7073684509805078, 1.2)), // USED AS PRE-HANDOFF FOR V3 diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index a32f344c..d8e605e4 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -19,13 +19,7 @@ import frc.robot.commands.CompositeCommands.SharedCommands; import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; import frc.robot.commands.DriveCommands; -import frc.robot.subsystems.shared.drive.Drive; -import frc.robot.subsystems.shared.drive.DriveConstants; -import frc.robot.subsystems.shared.drive.GyroIO; -import frc.robot.subsystems.shared.drive.GyroIOPigeon2; -import frc.robot.subsystems.shared.drive.ModuleIO; -import frc.robot.subsystems.shared.drive.ModuleIOSim; -import frc.robot.subsystems.shared.drive.ModuleIOTalonFX; +import frc.robot.subsystems.shared.drive.*; import frc.robot.subsystems.shared.elevator.Elevator; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions; @@ -313,21 +307,10 @@ private void configureButtonBindings() { superstructure .runActionWithTimeout(V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, 1) .finallyDo(() -> RobotState.setHasAlgae(false))); - operator - .povRight() - .whileTrue( - superstructure - .override(() -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_ALGAE)) - .finallyDo(() -> RobotState.setHasAlgae(false))); + operator.start().whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)); - operator - .back() - .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)) - .onFalse( - superstructure - .runActionWithTimeout(V3_EpsilonSuperstructureStates.BARGE_SCORE, 0.1) - .finallyDo(() -> RobotState.setHasAlgae(false))); + operator.back().onTrue(V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure)); } private void configureAutos() { @@ -388,6 +371,8 @@ public void robotPeriodic() { */ @Override public Command getAutonomousCommand() { - return AutonomousCommands.autoELeft(drive, superstructure, intake, manipulator, null).cmd(); + return AutonomousCommands.autoELeft( + drive, superstructure, intake, manipulator, RobotCameras.V3_EPSILON_CAMS) + .cmd(); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot index 772e288a..254bcf50 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot @@ -10,64 +10,45 @@ digraph Superstructure { STOW_DOWN -> L3_ALGAE [type=UNCONSTRAINED] STOW_DOWN -> PROCESSOR [type=UNCONSTRAINED] STOW_DOWN -> BARGE [type=UNCONSTRAINED] - STOW_DOWN -> CLIMB [type=NO_ALGAE] + STOW_DOWN -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] - GROUND_ACQUISITION -> STOW_DOWN [type=UNCONSTRAINED] + GROUND_ACQUISITION -> FLIP_UP [type=UNCONSTRAINED] GROUND_ACQUISITION -> GROUND_INTAKE [type=UNCONSTRAINED] GROUND_ACQUISITION -> L1 [type=UNCONSTRAINED] - GROUND_ACQUISITION -> L2 [type=UNCONSTRAINED] - GROUND_ACQUISITION -> L3 [type=UNCONSTRAINED] GROUND_ACQUISITION -> L4 [type=UNCONSTRAINED] GROUND_ACQUISITION -> HANDOFF [type=UNCONSTRAINED] - GROUND_ACQUISITION -> STOW_UP [type=UNCONSTRAINED] - GROUND_ACQUISITION -> L2_ALGAE [type=UNCONSTRAINED] GROUND_ACQUISITION -> L3_ALGAE [type=UNCONSTRAINED] - GROUND_ACQUISITION -> PROCESSOR [type=UNCONSTRAINED] GROUND_ACQUISITION -> BARGE [type=UNCONSTRAINED] - GROUND_INTAKE -> STOW_DOWN [type=UNCONSTRAINED] + GROUND_INTAKE -> FLIP_UP [type=UNCONSTRAINED] GROUND_INTAKE -> GROUND_ACQUISITION [type=UNCONSTRAINED] GROUND_INTAKE -> L1 [type=UNCONSTRAINED] - GROUND_INTAKE -> L2 [type=UNCONSTRAINED] - GROUND_INTAKE -> L3 [type=UNCONSTRAINED] GROUND_INTAKE -> L4 [type=UNCONSTRAINED] GROUND_INTAKE -> HANDOFF [type=UNCONSTRAINED] - GROUND_INTAKE -> STOW_UP [type=UNCONSTRAINED] - GROUND_INTAKE -> L2_ALGAE [type=UNCONSTRAINED] GROUND_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] - GROUND_INTAKE -> PROCESSOR [type=UNCONSTRAINED] GROUND_INTAKE -> BARGE [type=UNCONSTRAINED] - L1 -> STOW_DOWN [type=UNCONSTRAINED] + L1 -> FLIP_UP [type=UNCONSTRAINED] L1 -> GROUND_ACQUISITION [type=UNCONSTRAINED] - L1 -> L2 [type=UNCONSTRAINED] - L1 -> L3 [type=UNCONSTRAINED] L1 -> L4 [type=UNCONSTRAINED] L1 -> L1_SCORE [type=UNCONSTRAINED] L1 -> HANDOFF [type=UNCONSTRAINED] - L1 -> STOW_UP [type=UNCONSTRAINED] - L1 -> L2_ALGAE [type=UNCONSTRAINED] L1 -> L3_ALGAE [type=UNCONSTRAINED] - L1 -> PROCESSOR [type=UNCONSTRAINED] L1 -> BARGE [type=UNCONSTRAINED] L2 -> STOW_DOWN [type=UNCONSTRAINED] - L2 -> GROUND_ACQUISITION [type=UNCONSTRAINED] - L2 -> L1 [type=UNCONSTRAINED] + L2 -> FLIP_DOWN [type=UNCONSTRAINED] L2 -> L3 [type=UNCONSTRAINED] L2 -> L4 [type=UNCONSTRAINED] L2 -> L2_SCORE [type=UNCONSTRAINED] - L2 -> HANDOFF [type=UNCONSTRAINED] L2 -> STOW_UP [type=UNCONSTRAINED] L2 -> L2_ALGAE [type=UNCONSTRAINED] L2 -> L3_ALGAE [type=UNCONSTRAINED] L2 -> PROCESSOR [type=UNCONSTRAINED] L2 -> BARGE [type=UNCONSTRAINED] - L2 -> CLIMB [type=NO_ALGAE] L3 -> STOW_DOWN [type=UNCONSTRAINED] - L3 -> GROUND_ACQUISITION [type=UNCONSTRAINED] - L3 -> L1 [type=UNCONSTRAINED] + L3 -> FLIP_DOWN [type=UNCONSTRAINED] L3 -> L2 [type=UNCONSTRAINED] L3 -> L4 [type=UNCONSTRAINED] L3 -> L3_SCORE [type=UNCONSTRAINED] @@ -77,7 +58,7 @@ digraph Superstructure { L3 -> L3_ALGAE [type=UNCONSTRAINED] L3 -> PROCESSOR [type=UNCONSTRAINED] L3 -> BARGE [type=UNCONSTRAINED] - L3 -> CLIMB [type=NO_ALGAE] + L3 -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] L4 -> STOW_DOWN [type=UNCONSTRAINED] L4 -> GROUND_ACQUISITION [type=UNCONSTRAINED] @@ -91,16 +72,15 @@ digraph Superstructure { L4 -> L3_ALGAE [type=UNCONSTRAINED] L4 -> PROCESSOR [type=UNCONSTRAINED] L4 -> BARGE [type=UNCONSTRAINED] + L4 -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] - L1_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] + L1_SCORE -> L1 [type=UNCONSTRAINED] L2_SCORE -> STOW_DOWN [type=UNCONSTRAINED] - L2_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] - L2_SCORE -> L1 [type=UNCONSTRAINED] + L2_SCORE -> FLIP_DOWN [type=UNCONSTRAINED] L2_SCORE -> L2 [type=UNCONSTRAINED] L2_SCORE -> L3 [type=UNCONSTRAINED] L2_SCORE -> L4 [type=UNCONSTRAINED] - L2_SCORE -> HANDOFF [type=UNCONSTRAINED] L2_SCORE -> STOW_UP [type=UNCONSTRAINED] L2_SCORE -> L2_ALGAE [type=UNCONSTRAINED] L2_SCORE -> L3_ALGAE [type=UNCONSTRAINED] @@ -108,60 +88,46 @@ digraph Superstructure { L2_SCORE -> BARGE [type=UNCONSTRAINED] L3_SCORE -> STOW_DOWN [type=UNCONSTRAINED] - L3_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] - L3_SCORE -> L1 [type=UNCONSTRAINED] + L3_SCORE -> FLIP_DOWN [type=UNCONSTRAINED] L3_SCORE -> L2 [type=UNCONSTRAINED] - L3_SCORE -> L3 [type=UNCONSTRAINED] L3_SCORE -> L4 [type=UNCONSTRAINED] + L3_SCORE -> L3 [type=UNCONSTRAINED] L3_SCORE -> HANDOFF [type=UNCONSTRAINED] L3_SCORE -> STOW_UP [type=UNCONSTRAINED] L3_SCORE -> L2_ALGAE [type=UNCONSTRAINED] L3_SCORE -> L3_ALGAE [type=UNCONSTRAINED] L3_SCORE -> PROCESSOR [type=UNCONSTRAINED] L3_SCORE -> BARGE [type=UNCONSTRAINED] + L3_SCORE -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] - L4_SCORE -> STOW_DOWN [type=UNCONSTRAINED] + L4_SCORE -> FLIP_UP [type=UNCONSTRAINED] L4_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] L4_SCORE -> L1 [type=UNCONSTRAINED] - L4_SCORE -> L2 [type=UNCONSTRAINED] L4_SCORE -> L3 [type=UNCONSTRAINED] L4_SCORE -> L4 [type=UNCONSTRAINED] L4_SCORE -> HANDOFF [type=UNCONSTRAINED] - L4_SCORE -> STOW_UP [type=UNCONSTRAINED] - L4_SCORE -> L2_ALGAE [type=UNCONSTRAINED] - L4_SCORE -> L3_ALGAE [type=UNCONSTRAINED] - L4_SCORE -> PROCESSOR [type=UNCONSTRAINED] L4_SCORE -> BARGE [type=UNCONSTRAINED] - HANDOFF -> STOW_DOWN [type=UNCONSTRAINED, requires=ARM] + HANDOFF -> FLIP_UP [type=UNCONSTRAINED] HANDOFF -> GROUND_ACQUISITION [type=UNCONSTRAINED] HANDOFF -> L1 [type=UNCONSTRAINED] - HANDOFF -> L2 [type=UNCONSTRAINED, requires=ARM] - HANDOFF -> L3 [type=UNCONSTRAINED] HANDOFF -> L4 [type=UNCONSTRAINED] - HANDOFF -> STOW_UP [type=UNCONSTRAINED] - HANDOFF -> L2_ALGAE [type=UNCONSTRAINED] HANDOFF -> L3_ALGAE [type=UNCONSTRAINED] - HANDOFF -> PROCESSOR [type=UNCONSTRAINED] HANDOFF -> BARGE [type=UNCONSTRAINED] - HANDOFF -> CLIMB [type=NO_ALGAE] STOW_UP -> STOW_DOWN [type=UNCONSTRAINED] - STOW_UP -> GROUND_ACQUISITION [type=UNCONSTRAINED] - STOW_UP -> L1 [type=UNCONSTRAINED] + STOW_UP -> FLIP_DOWN [type=UNCONSTRAINED] STOW_UP -> L2 [type=UNCONSTRAINED] STOW_UP -> L3 [type=UNCONSTRAINED] STOW_UP -> L4 [type=UNCONSTRAINED] - STOW_UP -> HANDOFF [type=UNCONSTRAINED] STOW_UP -> L2_ALGAE [type=UNCONSTRAINED] STOW_UP -> L3_ALGAE [type=UNCONSTRAINED] STOW_UP -> PROCESSOR [type=UNCONSTRAINED] STOW_UP -> BARGE [type=UNCONSTRAINED] - STOW_UP -> CLIMB [type=NO_ALGAE] + STOW_UP -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] L2_ALGAE -> STOW_DOWN [type = NO_ALGAE] - L2_ALGAE -> GROUND_ACQUISITION [type = NO_ALGAE] - L2_ALGAE -> L1 [type = NO_ALGAE] + L2_ALGAE -> FLIP_DOWN [type = NO_ALGAE] L2_ALGAE -> L2 [type=UNCONSTRAINED] L2_ALGAE -> L3 [type=UNCONSTRAINED] L2_ALGAE -> L4 [type=UNCONSTRAINED] @@ -172,12 +138,14 @@ digraph Superstructure { L2_ALGAE -> PROCESSOR [type=UNCONSTRAINED] L2_ALGAE -> BARGE [type=UNCONSTRAINED] L2_ALGAE -> L2_ALGAE_DROP - L2_ALGAE -> CLIMB [type=NO_ALGAE] + L2_ALGAE -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] L2_ALGAE_DROP -> L2_ALGAE - L2_ALGAE_INTAKE -> STOW_UP [type=UNCONSTRAINED] + L2_ALGAE_INTAKE -> FLIP_DOWN [type=UNCONSTRAINED] L2_ALGAE_INTAKE -> L2_ALGAE [type=UNCONSTRAINED] + L2_ALGAE_INTAKE -> L2_ALGAE_DROP [type=UNCONSTRAINED] + L3_ALGAE -> STOW_DOWN [type = NO_ALGAE] L3_ALGAE -> GROUND_ACQUISITION [type = NO_ALGAE] @@ -192,25 +160,18 @@ digraph Superstructure { L3_ALGAE -> PROCESSOR [type=UNCONSTRAINED] L3_ALGAE -> BARGE [type=UNCONSTRAINED] L3_ALGAE -> L3_ALGAE_DROP - L3_ALGAE -> CLIMB [type=NO_ALGAE] + L3_ALGAE -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] L3_ALGAE_DROP -> L3_ALGAE L3_ALGAE_INTAKE -> STOW_UP [type=UNCONSTRAINED] L3_ALGAE_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] + L3_ALGAE_INTAKE -> L3_ALGAE_DROP [type=UNCONSTRAINED] - PROCESSOR -> STOW_DOWN [type = NO_ALGAE] - PROCESSOR -> GROUND_ACQUISITION [type = NO_ALGAE] - PROCESSOR -> L1 [type = NO_ALGAE] - PROCESSOR -> L2 [type=UNCONSTRAINED] - PROCESSOR -> L3 [type=UNCONSTRAINED] - PROCESSOR -> L4 [type=UNCONSTRAINED] - PROCESSOR -> HANDOFF [type = NO_ALGAE] - PROCESSOR -> STOW_UP [type=UNCONSTRAINED] - PROCESSOR -> L2_ALGAE [type=UNCONSTRAINED] - PROCESSOR -> L3_ALGAE [type=UNCONSTRAINED] + + PROCESSOR -> POST_PROCESSOR [type = NO_ALGAE] PROCESSOR -> PROCESSOR_SCORE [type=UNCONSTRAINED] - PROCESSOR -> BARGE [type=UNCONSTRAINED] + PROCESSOR -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] PROCESSOR_SCORE -> PROCESSOR [type=UNCONSTRAINED] @@ -226,21 +187,49 @@ digraph Superstructure { BARGE -> L3_ALGAE [type=UNCONSTRAINED] BARGE -> PROCESSOR [type=UNCONSTRAINED] BARGE -> BARGE_SCORE [type=UNCONSTRAINED] + BARGE -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] BARGE_SCORE -> BARGE [type=UNCONSTRAINED] L4_SCORE -> GROUND_AQUISITION_ALGAE L2_SCORE -> GROUND_AQUISITION_ALGAE - GROUND_AQUISITION_ALGAE -> STOW_UP GROUND_AQUISITION_ALGAE -> PROCESSOR + GROUND_AQUISITION_ALGAE -> POST_PROCESSOR GROUND_AQUISITION_ALGAE -> GROUND_INTAKE_ALGAE GROUND_INTAKE_ALGAE -> GROUND_AQUISITION_ALGAE - FLIP_DOWN -> GROUND_ACQUISITION - FLIP_DOWN -> L1 - FLIP_DOWN -> HANDOFF - - FLIP_UP -> STOW_DOWN + FLIP_DOWN -> GROUND_ACQUISITION [type=UNCONSTRAINED] + FLIP_DOWN -> L1 [type=UNCONSTRAINED] + FLIP_DOWN -> HANDOFF [type=UNCONSTRAINED] + + FLIP_UP -> STOW_DOWN [type=UNCONSTRAINED] + FLIP_UP -> STOW_UP [type=UNCONSTRAINED] + FLIP_UP -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] + FLIP_UP -> L2 [type=UNCONSTRAINED] + FLIP_UP -> L3 [type=UNCONSTRAINED] + FLIP_UP -> PROCESSOR [type=UNCONSTRAINED] + + POST_PROCESSOR -> FLIP_DOWN [type = NO_ALGAE] + POST_PROCESSOR -> STOW_UP [type = UNCONSTRAINED] + POST_PROCESSOR -> L2_ALGAE [type = UNCONSTRAINED] + POST_PROCESSOR -> L3_ALGAE [type = UNCONSTRAINED] + POST_PROCESSOR -> L2 [type = UNCONSTRAINED] + POST_PROCESSOR -> L3 [type = UNCONSTRAINED] + POST_PROCESSOR -> L4 [type = UNCONSTRAINED] + POST_PROCESSOR -> BARGE [type = UNCONSTRAINED] + + HANDOFF_SPIN -> HANDOFF + HANDOFF -> HANDOFF_SPIN + HANDOFF -> L4_WINDMILL + + INVERSE_FLIP_UP -> L2_WINDMILL + INVERSE_FLIP_UP -> L3_WINDMILL + + L2_WINDMILL -> L2 + L3_WINDMILL -> L3 + L4_WINDMILL -> L4 + + HANDOFF -> INVERSE_FLIP_UP } \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index ec31a351..89f035da 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -1,20 +1,9 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; -import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.geometry.Translation2d; -import edu.wpi.first.math.geometry.Translation3d; -import edu.wpi.first.math.kinematics.ChassisSpeeds; -import edu.wpi.first.units.Units; -import edu.wpi.first.units.measure.Angle; -import edu.wpi.first.units.measure.Distance; -import edu.wpi.first.units.measure.LinearVelocity; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import edu.wpi.first.wpilibj2.command.button.Trigger; -import frc.robot.Constants; -import frc.robot.FieldConstants; import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotState; import frc.robot.RobotState.RobotMode; @@ -25,9 +14,6 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.Side; -import frc.robot.util.AllianceFlipUtil; import frc.robot.util.NTPrefixes; import java.util.HashMap; import java.util.LinkedList; @@ -40,8 +26,6 @@ import java.util.function.Supplier; import java.util.stream.Collectors; import lombok.Getter; -import org.ironmaple.simulation.SimulatedArena; -import org.ironmaple.simulation.seasonspecific.reefscape2025.ReefscapeAlgaeOnFly; import org.jgrapht.Graph; import org.jgrapht.graph.DefaultDirectedGraph; import org.littletonrobotics.junction.AutoLogOutput; @@ -112,94 +96,6 @@ public V3_EpsilonSuperstructure( // Add edges between states V3_EpsilonSuperstructureEdges.addEdges(graph, elevator, intake, manipulator); - - // trigger to run - new Trigger( - () -> - targetState == V3_EpsilonSuperstructureStates.BARGE_SCORE - && manipulator.getRollerGoal() == ManipulatorRollerState.SCORE_ALGAE - && !Constants.getMode().equals(Constants.Mode.REAL)) - .onTrue( - Commands.runOnce( - () -> { - Translation2d shooterPositionOnRobot = - new Translation2d( - V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() - * manipulator.getArmAngle().getSin() - - 0.05, - 0); - Distance initialHeight = - Distance.ofBaseUnits( - V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() - * manipulator.getArmAngle().getCos() - + elevator.getPositionMeters(), - Units.Meters); - - double v_x = - manipulator.getArmVelocity() - * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() - * manipulator.getArmAngle().getSin() - + -manipulator.getRollerVelocity() - * edu.wpi.first.math.util.Units.inchesToMeters(1.5) - * manipulator.getArmAngle().getSin(); - double v_y = - manipulator.getArmVelocity() - * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() - * manipulator.getArmAngle().getCos() - + -manipulator.getRollerVelocity() - * edu.wpi.first.math.util.Units.inchesToMeters(1.5) - * manipulator.getArmAngle().getCos() - + elevator.getVelocityMetersPerSecond(); - Logger.recordOutput("AlgaeCalculations/velocity/v_x", v_x); - Logger.recordOutput("AlgaeCalculations/velocity/v_y", v_y); - Angle shooterAngle = - manipulator - .getArmAngle() - .plus(Rotation2d.kCW_90deg) - .unaryMinus() - .getMeasure(); - Logger.recordOutput( - "AlgaeCalculations/shooterPositionOnRobot", shooterPositionOnRobot); - Logger.recordOutput("AlgaeCalculations/initialHeight", initialHeight); - Logger.recordOutput("AlgaeCalculations/shooterAngle", shooterAngle); - ReefscapeAlgaeOnFly algae = - new ReefscapeAlgaeOnFly( - RobotState.getRobotPoseField().getTranslation(), - shooterPositionOnRobot, // shooter position relative to bot - new ChassisSpeeds(), // maybe fix this eventually - RobotState.getRobotPoseField() - .getRotation() - .plus(Rotation2d.kCW_Pi_2), // good - initialHeight, // initial height of the ball, in meters | - // (length from arm joint to - // ball * cos (arm angle)) + elevator height - LinearVelocity.ofRelativeUnits( - Math.hypot(v_x, v_y) * .85, - Units.MetersPerSecond), // initial velocity, in m/s - shooterAngle // shooter angle - ); - algae - .withTargetPosition( - () -> { - double x = FieldConstants.Barge.middleCage.getX(); - double y = - AllianceFlipUtil.applyY(FieldConstants.Barge.middleCage.getY()); - double z = 2.018538; - return new Translation3d(x, y, z); - }) - .withTargetTolerance( - new Translation3d( - edu.wpi.first.math.util.Units.inchesToMeters(23), 1.86055, .242062)); - SimulatedArena.getInstance() - .addGamePieceProjectile( - algae.withProjectileTrajectoryDisplayCallBack( - (poses) -> - Logger.recordOutput( - "successfulShotsTrajectory", poses.toArray(Pose3d[]::new)), - (poses) -> - Logger.recordOutput( - "missedShotsTrajectory", poses.toArray(Pose3d[]::new)))); - })); } /** @@ -208,14 +104,15 @@ public V3_EpsilonSuperstructure( */ @Override public void periodic() { - manipulator.setArmSide( - RobotState.getScoreSide().equals(ScoreSide.LEFT) ? Side.NEGATIVE : Side.POSITIVE); - manipulator.setClearsElevator( - elevator.getPositionMeters() - > V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() * 1.1); - - if (currentState != null && !currentState.equals(V3_EpsilonSuperstructureStates.OVERRIDE)) - currentState.getAction().get(intake, manipulator); + if (currentState != null && !currentState.equals(V3_EpsilonSuperstructureStates.OVERRIDE)) { + if (nextState != null) { + // If we are in a transition, run the actions for the destination state + nextState.getAction().get(intake, manipulator); + } else { + // Otherwise, just run the actions for the state we are in + currentState.getAction().get(intake, manipulator); + } + } if (RobotMode.disabled()) { nextState = null; } else if (edgeCommand == null || !edgeCommand.getCommand().isScheduled()) { @@ -372,8 +269,39 @@ private Optional bfs( * @return true if the transition is allowed */ private boolean isEdgeAllowed(EdgeCommand edge, V3_EpsilonSuperstructureStates goal) { - return edge.getGamePieceEdge() == GamePieceEdge.UNCONSTRAINED - || RobotState.isHasAlgae() == (edge.getGamePieceEdge() != GamePieceEdge.NO_ALGAE); + // --- 1. Algae Check (Original Logic) --- + boolean gamePieceAllowed = + edge.getGamePieceEdge() == GamePieceEdge.UNCONSTRAINED + || RobotState.isHasAlgae() == (edge.getGamePieceEdge() != GamePieceEdge.NO_ALGAE); + + if (!gamePieceAllowed) { + return false; // Fail fast if game piece logic disallows it + } + + // Condition is TRUE, so we must apply the path forcing logic. + if (!manipulator.hasAlgae()) { + V3_EpsilonSuperstructureStates from = graph.getEdgeSource(edge); + V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(edge); + + boolean needsFlip = RobotState.getScoreSide().equals(ScoreSide.RIGHT); + + if (goal == V3_EpsilonSuperstructureStates.STOW_UP && needsFlip) { + if (to == V3_EpsilonSuperstructureStates.STOW_UP + && from != V3_EpsilonSuperstructureStates.INVERSE_FLIP_UP) { + return false; + } + } + + if (goal == V3_EpsilonSuperstructureStates.STOW_UP && !needsFlip) { + if (to == V3_EpsilonSuperstructureStates.STOW_UP + && from != V3_EpsilonSuperstructureStates.INVERSE_FLIP_UP) { + return false; + } + } + } + + // --- 3. If all checks pass, the edge is allowed --- + return true; } /** Resets the superstructure to initial auto state. */ diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index e44a78a8..f860c478 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -122,9 +122,15 @@ private static Command getEdgeCommand( V3_EpsilonSuperstructurePose pose = to.getPose(); + if (to.equals(V3_EpsilonSuperstructureStates.BARGE_SCORE)) { + return Commands.sequence( + pose.asConfigurationSpaceCommand(elevator, intake, manipulator), + Commands.waitUntil(() -> elevator.pastBargeThresholdgetPositionMeters())); + } + return Commands.sequence( pose.asConfigurationSpaceCommand(elevator, intake, manipulator), - pose.wait(elevator, intake, manipulator, to.getTransitionCondition())); + pose.wait(elevator, intake, manipulator)); } /** diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java index 348a7f9b..2cfafcad 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java @@ -1,5 +1,6 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.FieldConstants.Reef.ReefState; @@ -23,18 +24,41 @@ public class V3_EpsilonSuperstructurePose { @Getter private final ManipulatorArmState armState; @Getter private final IntakePivotState intakeState; - /** - * Constructs a new V3_EpsilonSuperstructurePose with the given subsystem poses. - * - * @param key A unique identifier for this pose. - * @param poses The combined poses for all relevant subsystems. - */ + @Getter private final Optional flyByElevatorTolerance; + @Getter private final Optional flyByArmTolerance; + public V3_EpsilonSuperstructurePose(String key, SubsystemPoses poses) { this.key = key; this.elevatorHeight = poses.elevatorHeight(); this.armState = poses.manipulatorArmState(); this.intakeState = poses.intakePivotState(); + + this.flyByElevatorTolerance = Optional.empty(); + this.flyByArmTolerance = Optional.empty(); + } + + public V3_EpsilonSuperstructurePose(String key, SubsystemPoses poses, double elevatorTolerance) { + this.key = key; + + this.elevatorHeight = poses.elevatorHeight(); + this.armState = poses.manipulatorArmState(); + this.intakeState = poses.intakePivotState(); + + this.flyByElevatorTolerance = Optional.of(elevatorTolerance); + this.flyByArmTolerance = Optional.empty(); + } + + public V3_EpsilonSuperstructurePose( + String key, SubsystemPoses poses, Rotation2d flyByArmTolerance) { + this.key = key; + + this.elevatorHeight = poses.elevatorHeight(); + this.armState = poses.manipulatorArmState(); + this.intakeState = poses.intakePivotState(); + + this.flyByElevatorTolerance = Optional.empty(); + this.flyByArmTolerance = Optional.of(flyByArmTolerance); } /** @@ -72,7 +96,6 @@ public Command setManipulatorState(V3_EpsilonManipulator manipulator) { * states defined by this pose. * * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. * @param intake The intake subsystem. * @param manipulator The manipulator subsystem. * @return A Command that sets all subsystems to their respective states in parallel. @@ -86,40 +109,18 @@ public Command asConfigurationSpaceCommand( } public Command wait( - ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator, - Optional condition) { - - return Commands.either( - Commands.either( - elevator.waitUntilAtGoal(), - manipulator.waitUntilArmAtGoal(), - () -> - condition - .get() - .equals(V3_EpsilonSuperstructureTransitionCondition.ELEVATOR_AT_GOAL)), - Commands.parallel( - elevator.waitUntilAtGoal(), - manipulator.waitUntilArmAtGoal(), - intake.waitUntilPivotAtGoal()), - () -> condition.isPresent()); - - // return Commands.sequence( - // Commands.parallel( - // elevator.waitUntilAtGoal(), - // manipulator.waitUntilArmAtGoal(), - // intake.waitUntilPivotAtGoal()), - // Commands.either( - // Commands.either( - // elevator.waitUntilAtGoal(), - // manipulator.waitUntilArmAtGoal(), - // () -> - // condition - // .get() - // .equals(V3_EpsilonSuperstructureTransitionCondition.ELEVATOR_AT_GOAL)), - // Commands.none(), - // () -> condition.isPresent())); + ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { + + if (flyByElevatorTolerance.isPresent()) { + return Commands.waitUntil(() -> elevator.inTolerance(flyByElevatorTolerance.get())); + } else if (flyByArmTolerance.isPresent()) { + return Commands.waitUntil(() -> manipulator.armInTolerance(flyByArmTolerance.get())); + } else { + return Commands.parallel( + elevator.waitUntilAtGoal(), + manipulator.waitUntilArmAtGoal(), + intake.waitUntilPivotAtGoal()); + } } /** diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 113dde68..c6af70a9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -1,5 +1,6 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; +import edu.wpi.first.math.geometry.Rotation2d; import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureAction.SubsystemActions; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructurePose.SubsystemPoses; @@ -7,7 +8,7 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakeRollerState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; -import java.util.Optional; +import lombok.Getter; public enum V3_EpsilonSuperstructureStates { START("START", new SubsystemPoses(), SubsystemActions.empty()), @@ -29,12 +30,16 @@ public enum V3_EpsilonSuperstructureStates { GROUND_INTAKE_ALGAE( "GROUND_INTAKE_ALGAE", new SubsystemPoses( - ReefState.STOW, ManipulatorArmState.ALGAE_INTAKE_FLOOR, IntakePivotState.INTAKE_ALGAE), + ReefState.ALGAE_FLOOR_INTAKE, + ManipulatorArmState.ALGAE_INTAKE_FLOOR, + IntakePivotState.INTAKE_ALGAE), new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), GROUND_AQUISITION_ALGAE( "GROUND_AQUISITION_ALGAE", new SubsystemPoses( - ReefState.STOW, ManipulatorArmState.ALGAE_INTAKE_FLOOR, IntakePivotState.INTAKE_ALGAE), + ReefState.ALGAE_FLOOR_INTAKE, + ManipulatorArmState.ALGAE_INTAKE_FLOOR, + IntakePivotState.INTAKE_ALGAE), SubsystemActions.empty()), GROUND_INTAKE_CORAL( @@ -64,7 +69,7 @@ public enum V3_EpsilonSuperstructureStates { SubsystemActions.empty()), L2_SCORE( "L2_SCORE", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), + new SubsystemPoses(ReefState.L2, ManipulatorArmState.FLIPPED_SCORE, IntakePivotState.HANDOFF), new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), L3( @@ -144,46 +149,30 @@ public enum V3_EpsilonSuperstructureStates { BARGE( "BARGE", new SubsystemPoses( - ReefState.ALGAE_SCORE, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), + ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.HANDOFF), SubsystemActions.empty()), BARGE_SCORE( "BARGE_SCORE", new SubsystemPoses( - ReefState.ALGAE_SCORE, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + ReefState.ALGAE_SCORE, ManipulatorArmState.ALGAE_SCORE, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP), + Rotation2d.fromDegrees(15)), FLIP_DOWN( "FLIP_DOWN", new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty(), - V3_EpsilonSuperstructureTransitionCondition.ELEVATOR_AT_GOAL), + SubsystemActions.empty()), FLIP_UP( "FLIP_UP", new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty(), - V3_EpsilonSuperstructureTransitionCondition.MANIPULATOR_AT_GOAL), - INVERSE_FLIP_DOWN( - "INVERSE_FLIP_DOWN", - new SubsystemPoses( - ReefState.HANDOFF, ManipulatorArmState.INVERSE_FLIP_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty(), - V3_EpsilonSuperstructureTransitionCondition.ELEVATOR_AT_GOAL), + SubsystemActions.empty()), INVERSE_FLIP_UP( - "FLIP_UP", + "INVERSE_FLIP_UP", new SubsystemPoses( ReefState.HANDOFF, ManipulatorArmState.INVERSE_FLIP_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty(), - V3_EpsilonSuperstructureTransitionCondition.MANIPULATOR_AT_GOAL); - - // Readable name for state - private final String name; + SubsystemActions.empty()); - // Target positions for all subsystems in this state - private final SubsystemPoses subsystemPoses; - - // Actions to perform for all subsystems in this state - private final SubsystemActions subsystemActions; - - private final Optional transitionCondition; + @Getter private final V3_EpsilonSuperstructurePose pose; + @Getter private final V3_EpsilonSuperstructureAction action; /** * Constructor for V3_SuperstructureStates. @@ -193,52 +182,19 @@ public enum V3_EpsilonSuperstructureStates { * @param action The subsystem actions for this state. */ V3_EpsilonSuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { - this.name = name; - this.subsystemPoses = pose; - this.subsystemActions = action; - this.transitionCondition = Optional.empty(); + this.pose = new V3_EpsilonSuperstructurePose(name, pose); + this.action = new V3_EpsilonSuperstructureAction(name, action); } V3_EpsilonSuperstructureStates( - String name, - SubsystemPoses pose, - SubsystemActions action, - V3_EpsilonSuperstructureTransitionCondition condition) { - this.name = name; - this.subsystemPoses = pose; - this.subsystemActions = action; - this.transitionCondition = Optional.of(condition); + String name, SubsystemPoses pose, SubsystemActions action, Double elevatorTolerance) { + this.pose = new V3_EpsilonSuperstructurePose(name, pose, elevatorTolerance); + this.action = new V3_EpsilonSuperstructureAction(name, action); } - /** - * Constructor for V3_SuperstructureStates with empty actions. - * - * @param name The name of the state. - * @param pose The subsystem poses for this state. - */ - public V3_EpsilonSuperstructurePose getPose() { - return new V3_EpsilonSuperstructurePose(name, subsystemPoses); - } - - /** - * Returns the actions associated with this superstructure state. - * - * @return The actions for this state. - */ - public V3_EpsilonSuperstructureAction getAction() { - return new V3_EpsilonSuperstructureAction(name, subsystemActions); - } - - public Optional getTransitionCondition() { - return transitionCondition; - } - - /** - * Returns the name of the superstructure state. - * - * @return The name of the state. - */ - public String getName() { - return name; + V3_EpsilonSuperstructureStates( + String name, SubsystemPoses pose, SubsystemActions action, Rotation2d armTolerance) { + this.pose = new V3_EpsilonSuperstructurePose(name, pose, armTolerance); + this.action = new V3_EpsilonSuperstructureAction(name, action); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureTransitionCondition.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureTransitionCondition.java deleted file mode 100644 index 6c67c30d..00000000 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureTransitionCondition.java +++ /dev/null @@ -1,6 +0,0 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure; - -public enum V3_EpsilonSuperstructureTransitionCondition { - ELEVATOR_AT_GOAL, - MANIPULATOR_AT_GOAL, -} diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index b26bd643..24151b0d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -1,8 +1,6 @@ package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; -import static edu.wpi.first.units.Units.Second; -import static edu.wpi.first.units.Units.Seconds; -import static edu.wpi.first.units.Units.Volts; +import static edu.wpi.first.units.Units.*; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; @@ -11,15 +9,14 @@ import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.RobotState; +import frc.robot.RobotState.ScoreSide; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.Side; import java.util.Set; import lombok.Getter; -import lombok.Setter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; @@ -31,29 +28,27 @@ public class V3_EpsilonManipulator { @Getter private Rotation2d armGoal; - @Setter - @Getter - @AutoLogOutput(key = "Manipulator/Arm Side") - private Side armSide; - @AutoLogOutput(key = "Manipulator/Roller Goal") @Getter private ManipulatorRollerState rollerGoal; private boolean isClosedLoop; - @Setter @Getter private boolean clearsElevator; + Set algaeStates; public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { this.io = io; inputs = new ManipulatorIOInputsAutoLogged(); isClosedLoop = true; - armGoal = ManipulatorArmState.VERTICAL_UP.getAngle(armSide); - armSide = Side.POSITIVE; + armGoal = ManipulatorArmState.VERTICAL_UP.getAngle(RobotState.getScoreSide()); rollerGoal = ManipulatorRollerState.STOP; - clearsElevator = false; + algaeStates = + Set.of( + ManipulatorArmState.ALGAE_INTAKE_FLOOR, + ManipulatorArmState.REEF_INTAKE, + ManipulatorArmState.ALGAE_SCORE); } public void periodic() { @@ -61,17 +56,7 @@ public void periodic() { Logger.processInputs("Manipulator", inputs); if (isClosedLoop) { - Rotation2d goal = armGoal; - - if (!isSafePosition() || clearsElevator) { - if (armSide == Side.POSITIVE) { - goal = Rotation2d.fromRotations(goal.getRotations() - 1.0); - } else { - goal = Rotation2d.fromRotations(goal.getRotations() + 1.0); - } - } - - io.setArmGoal(goal); + io.setArmGoal(armGoal); } if (rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { @@ -139,7 +124,11 @@ public Command runArm(double volts) { */ public void setArmGoal(ManipulatorArmState goal) { isClosedLoop = true; - armGoal = goal.getAngle(armSide); + if (!algaeStates.contains(goal)) { + armGoal = goal.getAngle(RobotState.getScoreSide()); + } else { + armGoal = goal.getAngle(ScoreSide.CENTER); + } } public void setArmGoal(Rotation2d goal) { @@ -222,6 +211,10 @@ public boolean armAtGoal(Rotation2d state) { <= V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); } + public boolean armInTolerance(Rotation2d tolerance) { + return Math.abs(inputs.armPosition.minus(armGoal).getRadians()) <= tolerance.getRadians(); + } + /** * Waits until the arm is at the goal position. * @@ -290,6 +283,7 @@ public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure, ElevatorFSM Commands.waitSeconds(.25), algaeCharacterizationRoutine.dynamic(Direction.kReverse)); } + /** * Sets the manipulator arm to the specified state. * @@ -330,22 +324,6 @@ public Rotation2d getArmAngle() { return inputs.armPosition; } - /** - * Checks if the manipulator arm is currently in a safe position. A safe position is when the arm - * is pointing away from the robot's body. The safe position threshold is determined by the angle - * between the arm and the robot's body. If the angle is greater than the threshold, it is - * considered safe. - * - * @return true if the arm is in a safe position, false otherwise. - */ - @AutoLogOutput(key = "Manipulator/Safe Position") - public boolean isSafePosition() { - double cosThresh = - Math.cos(Math.PI - ManipulatorArmState.SAFE_ANGLE.getAngle(armSide).getRadians()); - // unsafe if -cos(theta) >= cosThresh - return (-inputs.armPosition.getCos()) < cosThresh; - } - public double getArmVelocity() { return inputs.armVelocityRadiansPerSecond; } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java index ec8ac59f..83367342 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java @@ -6,6 +6,8 @@ import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.util.Units; import frc.robot.Constants; +import frc.robot.RobotState; +import frc.robot.RobotState.ScoreSide; import frc.robot.util.LoggedTunableNumber; import lombok.RequiredArgsConstructor; @@ -86,7 +88,7 @@ public final class V3_EpsilonManipulatorConstants { new LoggedTunableNumber("Manipulator/Arm/MaxAcceleration", 8), new LoggedTunableNumber("Manipulator/Arm/CruisingVelocity", 5), new LoggedTunableNumber( - "Manipulator/Arm/GoalTolerance", Units.degreesToRadians(1))); + "Manipulator/Arm/GoalTolerance", Units.degreesToRadians(3))); CURRENT_LIMITS = new ManipulatorCurrentLimits(40, 20, 40, 20); break; case V3_EPSILON_SIM: @@ -203,11 +205,11 @@ public static record ArmParameters( @RequiredArgsConstructor public static enum ManipulatorArmState { - PRE_SCORE(Rotation2d.fromDegrees(50.0)), + PRE_SCORE(Rotation2d.fromDegrees(25.0).unaryMinus()), SCORE(Rotation2d.fromDegrees(90.0)), // Placeholder value. Make sure to test SCORE_L4(Rotation2d.kPi), PROCESSOR(Rotation2d.fromDegrees(90)), - ALGAE_INTAKE_FLOOR(Rotation2d.fromDegrees(90)), + ALGAE_INTAKE_FLOOR(Rotation2d.fromDegrees(113.378906)), CORAL_INTAKE_FLOOR(Rotation2d.fromDegrees(-99)), REEF_INTAKE(Rotation2d.fromDegrees(90)), INTAKE_OUT_LINE(Rotation2d.fromDegrees(61)), @@ -217,19 +219,33 @@ public static enum ManipulatorArmState { TRANSITION(Rotation2d.fromDegrees(25.0)), // Placeholder value. Make sure to test VERTICAL_UP(Rotation2d.fromDegrees(0)), HANDOFF(Rotation2d.kPi), + FLIPPED_SCORE(Rotation2d.fromDegrees(-270)), + WINDMILL_ANGLE(Rotation2d.fromDegrees(-90)), SAFE_ANGLE(Rotation2d.fromDegrees(150)), FLIP_ANGLE(Rotation2d.fromDegrees(135)), + ALGAE_SCORE(Rotation2d.fromDegrees(25)), INVERSE_FLIP_ANGLE(Rotation2d.fromDegrees(135).unaryMinus()), EMERGENCY_EJECT_ANGLE( Rotation2d.fromDegrees(90)); // Idk if tested. Looks fine but double check. private final Rotation2d angle; - public Rotation2d getAngle(Side side) { - if (side == Side.NEGATIVE) { + public Rotation2d setRotationDirection(boolean direction) { + if (direction == true) { + return angle; + } else { + return angle.minus(Rotation2d.kPi).minus(Rotation2d.kPi); + } + } + + public Rotation2d getAngle(RobotState.ScoreSide scoreSide) { + if (scoreSide.equals(ScoreSide.RIGHT)) { + return angle; + } else if (scoreSide.equals(ScoreSide.LEFT)) { return angle.unaryMinus(); + } else { + return angle; } - return angle; } } @@ -258,9 +274,4 @@ public double getVoltage() { return voltage; } } - - public enum Side { - POSITIVE, - NEGATIVE - } } From e0cb01c823e1ae5615ee74a8b839c09e250e72a1 Mon Sep 17 00:00:00 2001 From: Luke Maxwell <24lbmaxwell@protonmail.com> Date: Fri, 31 Oct 2025 16:56:02 -0400 Subject: [PATCH 152/180] minimal auto --- .../robot/commands/AutonomousCommands.java | 27 ++++++++++++++++++- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 7 ++--- 2 files changed, 30 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index 35548f4d..b89977ad 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -2108,7 +2108,7 @@ public static final LoggedAutoRoutine autoFLeft( V3_EpsilonManipulator manipulator, Camera... cameras) { - LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoELeftBack"); + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoFLeft"); LoggedAutoTrajectory path1 = (routine.trajectory("F_PATH_1")); LoggedAutoTrajectory path2 = (routine.trajectory("F_PATH_2")); LoggedAutoTrajectory path3 = (routine.trajectory("F_PATH_3")); @@ -2142,4 +2142,29 @@ public static final LoggedAutoRoutine autoFLeft( return routine; } + + public static final LoggedAutoRoutine autoFLeftMinimal( + Drive drive, + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator, + Camera... cameras) { + + LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoFLeftMinimal"); + LoggedAutoTrajectory path1 = (routine.trajectory("F_PATH_1")); + + routine + .active() + .onTrue( + Commands.sequence( + path1.resetOdometry(), + Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), + CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + drive, superstructure, ReefState.L4, cameras), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.waitUntilAtGoal(), + Commands.runOnce(() -> drive.stop()))); + + return routine; + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index d8e605e4..ab51d69b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -332,6 +332,9 @@ private void configureAutos() { () -> AutonomousCommands.autoELeftBack(drive, superstructure, intake, manipulator)); autoChooser.addRoutine( "Algae", () -> AutonomousCommands.autoFLeft(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "1 piece do nothing", + () -> AutonomousCommands.autoFLeftMinimal(drive, superstructure, intake, manipulator)); SmartDashboard.putData("Autonomous Modes", autoChooser); } @@ -371,8 +374,6 @@ public void robotPeriodic() { */ @Override public Command getAutonomousCommand() { - return AutonomousCommands.autoELeft( - drive, superstructure, intake, manipulator, RobotCameras.V3_EPSILON_CAMS) - .cmd(); + return autoChooser.selectedCommand(); } } From e48efc9e44730255b215b7cd540994832336901d Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 1 Nov 2025 11:58:07 -0400 Subject: [PATCH 153/180] Update at 'Sat Nov 01 11:58:07 EDT 2025' --- src/main/java/frc/robot/Constants.java | 104 +++++++++--------- .../climber/V3_EpsilonClimberConstants.java | 49 +++++---- 2 files changed, 78 insertions(+), 75 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 4b343dc0..3f310627 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -3,58 +3,58 @@ import edu.wpi.first.wpilibj.RobotBase; public final class Constants { - public static final boolean TUNING_MODE = true; - public static final double LOOP_PERIOD_SECONDS = 0.02; - public static final RobotType ROBOT = RobotType.V3_EPSILON; - - public static Mode getMode() { - switch (ROBOT) { - case V0_FUNKY: - case V0_WHIPLASH: - case V0_GOMPEIVISION_TEST: - case V1_STACKUP: - case V2_REDUNDANCY: - case V3_EPSILON: - return RobotBase.isReal() ? Mode.REAL : Mode.REPLAY; - - case V0_FUNKY_SIM: - case V0_WHIPLASH_SIM: - case V0_GOMPEIVISION_TEST_SIM: - case V1_STACKUP_SIM: - case V2_REDUNDANCY_SIM: - case V3_EPSILON_SIM: - return Mode.SIM; - - default: - return Mode.REAL; + public static final boolean TUNING_MODE = false; + public static final double LOOP_PERIOD_SECONDS = 0.02; + public static final RobotType ROBOT = RobotType.V3_EPSILON; + + public static Mode getMode() { + switch (ROBOT) { + case V0_FUNKY: + case V0_WHIPLASH: + case V0_GOMPEIVISION_TEST: + case V1_STACKUP: + case V2_REDUNDANCY: + case V3_EPSILON: + return RobotBase.isReal() ? Mode.REAL : Mode.REPLAY; + + case V0_FUNKY_SIM: + case V0_WHIPLASH_SIM: + case V0_GOMPEIVISION_TEST_SIM: + case V1_STACKUP_SIM: + case V2_REDUNDANCY_SIM: + case V3_EPSILON_SIM: + return Mode.SIM; + + default: + return Mode.REAL; + } } - } - - public static enum Mode { - REAL, - SIM, - REPLAY - } - - public static enum RobotType { - V0_FUNKY, - V0_FUNKY_SIM, - V0_WHIPLASH, - V0_WHIPLASH_SIM, - V0_GOMPEIVISION_TEST, - V0_GOMPEIVISION_TEST_SIM, - V1_STACKUP, - V1_STACKUP_SIM, - V2_REDUNDANCY, - V2_REDUNDANCY_SIM, - V3_EPSILON_SIM, - V3_EPSILON, - } - - public static void main(String... args) { - if (ROBOT == RobotType.V1_STACKUP_SIM) { - System.err.println("Cannot deploy, invalid mode selected: " + ROBOT.toString()); - System.exit(1); + + public static enum Mode { + REAL, + SIM, + REPLAY + } + + public static enum RobotType { + V0_FUNKY, + V0_FUNKY_SIM, + V0_WHIPLASH, + V0_WHIPLASH_SIM, + V0_GOMPEIVISION_TEST, + V0_GOMPEIVISION_TEST_SIM, + V1_STACKUP, + V1_STACKUP_SIM, + V2_REDUNDANCY, + V2_REDUNDANCY_SIM, + V3_EPSILON_SIM, + V3_EPSILON, + } + + public static void main(String... args) { + if (ROBOT == RobotType.V1_STACKUP_SIM) { + System.err.println("Cannot deploy, invalid mode selected: " + ROBOT.toString()); + System.exit(1); + } } - } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java index a87b4aa0..16ab25f7 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java @@ -4,37 +4,40 @@ import edu.wpi.first.math.util.Units; public class V3_EpsilonClimberConstants { - public static final int DEPLOYMENT_CAN_ID; + public static final int DEPLOYMENT_CAN_ID; - public static final int ROLLER_CAN_ID; + public static final int ROLLER_CAN_ID; - public static final MotorParameters MOTOR_PARAMETERS; + public static final MotorParameters MOTOR_PARAMETERS; - public static final double CLIMBER_CLIMBED_RADIANS; + public static final double CLIMBER_CLIMBED_RADIANS; - static { - DEPLOYMENT_CAN_ID = 50; - ROLLER_CAN_ID = 51; + static { + DEPLOYMENT_CAN_ID = 50; + ROLLER_CAN_ID = 51; - MOTOR_PARAMETERS = - new MotorParameters(DCMotor.getKrakenX60Foc(1), 16.0, 0.81, Units.inchesToMeters(1.78)); + MOTOR_PARAMETERS = + new MotorParameters(DCMotor.getKrakenX60Foc(1), 16.0, 0.81, Units.inchesToMeters(1.78)); - CLIMBER_CLIMBED_RADIANS = -350; - } + CLIMBER_CLIMBED_RADIANS = -400; + } - public static record MotorParameters( - DCMotor MOTOR_CONFIG, double GEAR_RATIO, double GEARBOX_EFFICIENCY, double SPOOL_DIAMETER) {} + public static record MotorParameters( + DCMotor MOTOR_CONFIG, double GEAR_RATIO, double GEARBOX_EFFICIENCY, double SPOOL_DIAMETER) { + } - public static final double CLIMBER_CLIMBED_ZERO_RADIANS = 41; - public static final double CLIMBER_CLIMBED_DEPLOYED_RADIANS = -10; - public static final ClimberTimingConfig CLIMBER_TIMING_CONFIG = - new ClimberTimingConfig(1.1, 0.25, 0.5); - public static final CurrentLimits CURRENT_LIMITS = new CurrentLimits(40.0, 80.0); + public static final double CLIMBER_CLIMBED_ZERO_RADIANS = 41; + public static final double CLIMBER_CLIMBED_DEPLOYED_RADIANS = -10; + public static final ClimberTimingConfig CLIMBER_TIMING_CONFIG = + new ClimberTimingConfig(1.1, 0.25, 0.5); + public static final CurrentLimits CURRENT_LIMITS = new CurrentLimits(40.0, 80.0); - public static record CurrentLimits(double SUPPLY_CURRENT_LIMIT, double STATOR_CURRENT_LIMIT) {} + public static record CurrentLimits(double SUPPLY_CURRENT_LIMIT, double STATOR_CURRENT_LIMIT) { + } - public static record ClimberTimingConfig( - double WAIT_AFTER_RELEASE_SECONDS, - double REDUNDANCY_DELAY_SECONDS, - double REDUNDANCY_TRUSTING_TIMEOUT_SECONDS) {} + public static record ClimberTimingConfig( + double WAIT_AFTER_RELEASE_SECONDS, + double REDUNDANCY_DELAY_SECONDS, + double REDUNDANCY_TRUSTING_TIMEOUT_SECONDS) { + } } From 00c0672ec6d259df93f68426d2883bf51874a032 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 1 Nov 2025 12:29:57 -0400 Subject: [PATCH 154/180] climber --- src/main/java/frc/robot/Constants.java | 104 +++++++++--------- .../climber/V3_EpsilonClimberConstants.java | 49 ++++----- 2 files changed, 75 insertions(+), 78 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 3f310627..deb3a07e 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -3,58 +3,58 @@ import edu.wpi.first.wpilibj.RobotBase; public final class Constants { - public static final boolean TUNING_MODE = false; - public static final double LOOP_PERIOD_SECONDS = 0.02; - public static final RobotType ROBOT = RobotType.V3_EPSILON; - - public static Mode getMode() { - switch (ROBOT) { - case V0_FUNKY: - case V0_WHIPLASH: - case V0_GOMPEIVISION_TEST: - case V1_STACKUP: - case V2_REDUNDANCY: - case V3_EPSILON: - return RobotBase.isReal() ? Mode.REAL : Mode.REPLAY; - - case V0_FUNKY_SIM: - case V0_WHIPLASH_SIM: - case V0_GOMPEIVISION_TEST_SIM: - case V1_STACKUP_SIM: - case V2_REDUNDANCY_SIM: - case V3_EPSILON_SIM: - return Mode.SIM; - - default: - return Mode.REAL; - } + public static final boolean TUNING_MODE = false; + public static final double LOOP_PERIOD_SECONDS = 0.02; + public static final RobotType ROBOT = RobotType.V3_EPSILON; + + public static Mode getMode() { + switch (ROBOT) { + case V0_FUNKY: + case V0_WHIPLASH: + case V0_GOMPEIVISION_TEST: + case V1_STACKUP: + case V2_REDUNDANCY: + case V3_EPSILON: + return RobotBase.isReal() ? Mode.REAL : Mode.REPLAY; + + case V0_FUNKY_SIM: + case V0_WHIPLASH_SIM: + case V0_GOMPEIVISION_TEST_SIM: + case V1_STACKUP_SIM: + case V2_REDUNDANCY_SIM: + case V3_EPSILON_SIM: + return Mode.SIM; + + default: + return Mode.REAL; } - - public static enum Mode { - REAL, - SIM, - REPLAY - } - - public static enum RobotType { - V0_FUNKY, - V0_FUNKY_SIM, - V0_WHIPLASH, - V0_WHIPLASH_SIM, - V0_GOMPEIVISION_TEST, - V0_GOMPEIVISION_TEST_SIM, - V1_STACKUP, - V1_STACKUP_SIM, - V2_REDUNDANCY, - V2_REDUNDANCY_SIM, - V3_EPSILON_SIM, - V3_EPSILON, - } - - public static void main(String... args) { - if (ROBOT == RobotType.V1_STACKUP_SIM) { - System.err.println("Cannot deploy, invalid mode selected: " + ROBOT.toString()); - System.exit(1); - } + } + + public static enum Mode { + REAL, + SIM, + REPLAY + } + + public static enum RobotType { + V0_FUNKY, + V0_FUNKY_SIM, + V0_WHIPLASH, + V0_WHIPLASH_SIM, + V0_GOMPEIVISION_TEST, + V0_GOMPEIVISION_TEST_SIM, + V1_STACKUP, + V1_STACKUP_SIM, + V2_REDUNDANCY, + V2_REDUNDANCY_SIM, + V3_EPSILON_SIM, + V3_EPSILON, + } + + public static void main(String... args) { + if (ROBOT == RobotType.V1_STACKUP_SIM) { + System.err.println("Cannot deploy, invalid mode selected: " + ROBOT.toString()); + System.exit(1); } + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java index 16ab25f7..58a9b82b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java @@ -4,40 +4,37 @@ import edu.wpi.first.math.util.Units; public class V3_EpsilonClimberConstants { - public static final int DEPLOYMENT_CAN_ID; + public static final int DEPLOYMENT_CAN_ID; - public static final int ROLLER_CAN_ID; + public static final int ROLLER_CAN_ID; - public static final MotorParameters MOTOR_PARAMETERS; + public static final MotorParameters MOTOR_PARAMETERS; - public static final double CLIMBER_CLIMBED_RADIANS; + public static final double CLIMBER_CLIMBED_RADIANS; - static { - DEPLOYMENT_CAN_ID = 50; - ROLLER_CAN_ID = 51; + static { + DEPLOYMENT_CAN_ID = 50; + ROLLER_CAN_ID = 51; - MOTOR_PARAMETERS = - new MotorParameters(DCMotor.getKrakenX60Foc(1), 16.0, 0.81, Units.inchesToMeters(1.78)); + MOTOR_PARAMETERS = + new MotorParameters(DCMotor.getKrakenX60Foc(1), 16.0, 0.81, Units.inchesToMeters(1.78)); - CLIMBER_CLIMBED_RADIANS = -400; - } + CLIMBER_CLIMBED_RADIANS = -400; + } - public static record MotorParameters( - DCMotor MOTOR_CONFIG, double GEAR_RATIO, double GEARBOX_EFFICIENCY, double SPOOL_DIAMETER) { - } + public static record MotorParameters( + DCMotor MOTOR_CONFIG, double GEAR_RATIO, double GEARBOX_EFFICIENCY, double SPOOL_DIAMETER) {} - public static final double CLIMBER_CLIMBED_ZERO_RADIANS = 41; - public static final double CLIMBER_CLIMBED_DEPLOYED_RADIANS = -10; - public static final ClimberTimingConfig CLIMBER_TIMING_CONFIG = - new ClimberTimingConfig(1.1, 0.25, 0.5); - public static final CurrentLimits CURRENT_LIMITS = new CurrentLimits(40.0, 80.0); + public static final double CLIMBER_CLIMBED_ZERO_RADIANS = 41; + public static final double CLIMBER_CLIMBED_DEPLOYED_RADIANS = -10; + public static final ClimberTimingConfig CLIMBER_TIMING_CONFIG = + new ClimberTimingConfig(1.1, 0.25, 0.5); + public static final CurrentLimits CURRENT_LIMITS = new CurrentLimits(40.0, 80.0); - public static record CurrentLimits(double SUPPLY_CURRENT_LIMIT, double STATOR_CURRENT_LIMIT) { - } + public static record CurrentLimits(double SUPPLY_CURRENT_LIMIT, double STATOR_CURRENT_LIMIT) {} - public static record ClimberTimingConfig( - double WAIT_AFTER_RELEASE_SECONDS, - double REDUNDANCY_DELAY_SECONDS, - double REDUNDANCY_TRUSTING_TIMEOUT_SECONDS) { - } + public static record ClimberTimingConfig( + double WAIT_AFTER_RELEASE_SECONDS, + double REDUNDANCY_DELAY_SECONDS, + double REDUNDANCY_TRUSTING_TIMEOUT_SECONDS) {} } From a4678db9931fe2200f6289398b02329c3a4da6dc Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 1 Nov 2025 12:33:52 -0400 Subject: [PATCH 155/180] Update at 'Sat Nov 01 12:33:52 EDT 2025' --- .../V3_EpsilonSuperstructure.java | 1324 +++++++++-------- 1 file changed, 664 insertions(+), 660 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 89f035da..1475890e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -15,705 +15,709 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; import frc.robot.util.NTPrefixes; -import java.util.HashMap; -import java.util.LinkedList; -import java.util.Map; -import java.util.Optional; -import java.util.Queue; -import java.util.Set; -import java.util.function.BooleanSupplier; -import java.util.function.DoubleSupplier; -import java.util.function.Supplier; -import java.util.stream.Collectors; import lombok.Getter; import org.jgrapht.Graph; import org.jgrapht.graph.DefaultDirectedGraph; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; +import java.util.*; +import java.util.function.BooleanSupplier; +import java.util.function.DoubleSupplier; +import java.util.function.Supplier; +import java.util.stream.Collectors; + /** * The V3_EpsilonSuperstructure class manages the coordinated movement and state transitions of the * robot's major subsystems including elevator, manipulator, and intake. */ public class V3_EpsilonSuperstructure extends SubsystemBase { - private final Graph graph; - private final ElevatorFSM elevator; - private final V3_EpsilonIntake intake; - private final V3_EpsilonManipulator manipulator; - - /** - * The previous, current, and next states of the superstructure. These are used to track the state - * transitions and manage the command scheduling. - */ - @Getter private V3_EpsilonSuperstructureStates previousState; - - /** - * The current state of the superstructure, which is updated periodically based on the command - * scheduling and state transitions. - */ - @Getter private V3_EpsilonSuperstructureStates currentState; - - /** - * The next state that the superstructure is transitioning to. This is determined by the command - * scheduling and the current target state. - */ - @Getter private V3_EpsilonSuperstructureStates nextState; - - /** - * The target state that the superstructure is trying to achieve. This is set by the robot and - * determines the next action to be taken. - */ - @Getter private V3_EpsilonSuperstructureStates targetState; - - /** The command that is currently being executed to transition between states. */ - private EdgeCommand edgeCommand; - - /** - * Constructs a V2_RedundancySuperstructure. - * - * @param elevator The elevator subsystem. - * @param intake The intake subsystem. - * @param manipulator The manipulator subsystem. - */ - public V3_EpsilonSuperstructure( - ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { - this.elevator = elevator; - this.intake = intake; - this.manipulator = manipulator; - - previousState = null; - currentState = V3_EpsilonSuperstructureStates.START; - nextState = null; - - targetState = V3_EpsilonSuperstructureStates.START; - - // Initialize the graph - graph = new DefaultDirectedGraph<>(EdgeCommand.class); - - for (V3_EpsilonSuperstructureStates vertex : V3_EpsilonSuperstructureStates.values()) { - graph.addVertex(vertex); - } + private final Graph graph; + private final ElevatorFSM elevator; + private final V3_EpsilonIntake intake; + private final V3_EpsilonManipulator manipulator; + + /** + * The previous, current, and next states of the superstructure. These are used to track the state + * transitions and manage the command scheduling. + */ + @Getter + private V3_EpsilonSuperstructureStates previousState; + + /** + * The current state of the superstructure, which is updated periodically based on the command + * scheduling and state transitions. + */ + @Getter + private V3_EpsilonSuperstructureStates currentState; + + /** + * The next state that the superstructure is transitioning to. This is determined by the command + * scheduling and the current target state. + */ + @Getter + private V3_EpsilonSuperstructureStates nextState; + + /** + * The target state that the superstructure is trying to achieve. This is set by the robot and + * determines the next action to be taken. + */ + @Getter + private V3_EpsilonSuperstructureStates targetState; + + /** + * The command that is currently being executed to transition between states. + */ + private EdgeCommand edgeCommand; + + /** + * Constructs a V2_RedundancySuperstructure. + * + * @param elevator The elevator subsystem. + * @param intake The intake subsystem. + * @param manipulator The manipulator subsystem. + */ + public V3_EpsilonSuperstructure( + ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { + this.elevator = elevator; + this.intake = intake; + this.manipulator = manipulator; + + previousState = null; + currentState = V3_EpsilonSuperstructureStates.START; + nextState = null; + + targetState = V3_EpsilonSuperstructureStates.START; + + // Initialize the graph + graph = new DefaultDirectedGraph<>(EdgeCommand.class); + + for (V3_EpsilonSuperstructureStates vertex : V3_EpsilonSuperstructureStates.values()) { + graph.addVertex(vertex); + } - // Add edges between states - V3_EpsilonSuperstructureEdges.addEdges(graph, elevator, intake, manipulator); - } - - /** - * Periodic method that handles state transitions and subsystem updates. Updates robot state - * variables and manages command scheduling based on current state. - */ - @Override - public void periodic() { - if (currentState != null && !currentState.equals(V3_EpsilonSuperstructureStates.OVERRIDE)) { - if (nextState != null) { - // If we are in a transition, run the actions for the destination state - nextState.getAction().get(intake, manipulator); - } else { - // Otherwise, just run the actions for the state we are in - currentState.getAction().get(intake, manipulator); - } + // Add edges between states + V3_EpsilonSuperstructureEdges.addEdges(graph, elevator, intake, manipulator); } - if (RobotMode.disabled()) { - nextState = null; - } else if (edgeCommand == null || !edgeCommand.getCommand().isScheduled()) { - // Update edge to new state - if (nextState != null) { - previousState = currentState; - currentState = nextState; - nextState = null; - } - - // Schedule next command in sequence - if (currentState != targetState) { - bfs(currentState, targetState) - .ifPresent( - next -> { - this.nextState = next; - edgeCommand = graph.getEdge(currentState, next); - edgeCommand.getCommand().schedule(); - }); - } + + /** + * Periodic method that handles state transitions and subsystem updates. Updates robot state + * variables and manages command scheduling based on current state. + */ + @Override + public void periodic() { + if (currentState != null && !currentState.equals(V3_EpsilonSuperstructureStates.OVERRIDE)) { + if (nextState != null) { + // If we are in a transition, run the actions for the destination state + nextState.getAction().get(intake, manipulator); + } else { + // Otherwise, just run the actions for the state we are in + currentState.getAction().get(intake, manipulator); + } + } + if (RobotMode.disabled()) { + nextState = null; + } else if (edgeCommand == null || !edgeCommand.getCommand().isScheduled()) { + // Update edge to new state + if (nextState != null) { + previousState = currentState; + currentState = nextState; + nextState = null; + } + + // Schedule next command in sequence + if (currentState != targetState) { + bfs(currentState, targetState) + .ifPresent( + next -> { + this.nextState = next; + edgeCommand = graph.getEdge(currentState, next); + edgeCommand.getCommand().schedule(); + }); + } + } + + // Log the current state of the superstructure and edge command + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "Goal", targetState == null ? "NULL" : targetState.toString()); + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "Previous State", + previousState == null ? "NULL" : previousState.toString()); + Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Current State", currentState.toString()); + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "Next State", + nextState == null ? "NULL" : nextState.toString()); + if (edgeCommand != null) { + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "EdgeCommand", + graph.getEdgeSource(edgeCommand) + " --> " + graph.getEdgeTarget(edgeCommand)); + } else { + Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "EdgeCommand", "NO EDGES SCHEDULED"); + } + + elevator.periodic(); + intake.periodic(); + manipulator.periodic(); + + double armHeight = + -manipulator.getArmAngle().rotateBy(new Rotation2d(-Math.PI / 2)).getSin() + * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() + + elevator.getPositionMeters(); + Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Arm Height", armHeight); + Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Clears Base", 0.075 < armHeight); + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "Clears Intake", + intake.getPivotAngle().getDegrees() > 15 + || armHeight > 0.37 + || Math.abs( + manipulator.getArmAngle().rotateBy(new Rotation2d(-Math.PI / 2)).getCos() + * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS()) + > 0.35); } - // Log the current state of the superstructure and edge command - Logger.recordOutput( - NTPrefixes.SUPERSTRUCTURE + "Goal", targetState == null ? "NULL" : targetState.toString()); - Logger.recordOutput( - NTPrefixes.SUPERSTRUCTURE + "Previous State", - previousState == null ? "NULL" : previousState.toString()); - Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Current State", currentState.toString()); - Logger.recordOutput( - NTPrefixes.SUPERSTRUCTURE + "Next State", - nextState == null ? "NULL" : nextState.toString()); - if (edgeCommand != null) { - Logger.recordOutput( - NTPrefixes.SUPERSTRUCTURE + "EdgeCommand", - graph.getEdgeSource(edgeCommand) + " --> " + graph.getEdgeTarget(edgeCommand)); - } else { - Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "EdgeCommand", "NO EDGES SCHEDULED"); + /** + * Updates the target state and handles command rescheduling for optimal path. + * + * @param goal New target state to achieve + */ + private void setGoal(V3_EpsilonSuperstructureStates goal) { + // Don't do anything if goal is the same + if (this.targetState == goal) return; + else { + this.targetState = goal; + } + + if (nextState == null) return; + + var edgeToCurrentState = graph.getEdge(nextState, currentState); + // Figure out if we should schedule a different command to get to goal faster + if (edgeCommand.getCommand().isScheduled() + && edgeToCurrentState != null + && isEdgeAllowed(edgeToCurrentState, goal)) { + // Figure out where we would have gone from the previous state + bfs(currentState, goal) + .ifPresent( + newNext -> { + if (newNext == nextState) { + // We are already on track + return; + } + + if (newNext != currentState && graph.getEdge(nextState, newNext) != null) { + // We can skip directly to the newNext edge + edgeCommand.getCommand().cancel(); + edgeCommand = graph.getEdge(currentState, newNext); + edgeCommand.getCommand().schedule(); + nextState = newNext; + } else { + // Follow the reverse edge from next back to the current edge + edgeCommand.getCommand().cancel(); + edgeCommand = graph.getEdge(nextState, currentState); + edgeCommand.getCommand().schedule(); + var temp = currentState; + previousState = currentState; + currentState = nextState; + nextState = temp; + } + }); + } } - elevator.periodic(); - intake.periodic(); - manipulator.periodic(); - - double armHeight = - -manipulator.getArmAngle().rotateBy(new Rotation2d(-Math.PI / 2)).getSin() - * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() - + elevator.getPositionMeters(); - Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Arm Height", armHeight); - Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Clears Base", 0.075 < armHeight); - Logger.recordOutput( - NTPrefixes.SUPERSTRUCTURE + "Clears Intake", - intake.getPivotAngle().getDegrees() > 15 - || armHeight > 0.37 - || Math.abs( - manipulator.getArmAngle().rotateBy(new Rotation2d(-Math.PI / 2)).getCos() - * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS()) - > 0.35); - } - - /** - * Updates the target state and handles command rescheduling for optimal path. - * - * @param goal New target state to achieve - */ - private void setGoal(V3_EpsilonSuperstructureStates goal) { - // Don't do anything if goal is the same - if (this.targetState == goal) return; - else { - this.targetState = goal; + /** + * Performs breadth-first search to find the next state in the path to the goal. + * + * @param start Starting state + * @param goal Target state + * @return Optional containing the next state in the path, empty if no path exists + */ + private Optional bfs( + V3_EpsilonSuperstructureStates start, V3_EpsilonSuperstructureStates goal) { + Map parents = new HashMap<>(); + Queue queue = new LinkedList<>(); + queue.add(start); + parents.put(start, null); + while (!queue.isEmpty()) { + V3_EpsilonSuperstructureStates current = queue.poll(); + if (current == goal) break; + for (EdgeCommand edge : + graph.outgoingEdgesOf(current).stream() + .filter(edge -> isEdgeAllowed(edge, goal)) + .toList()) { + V3_EpsilonSuperstructureStates neighbor = graph.getEdgeTarget(edge); + if (!parents.containsKey(neighbor)) { + parents.put(neighbor, current); + queue.add(neighbor); + } + } + } + + if (!parents.containsKey(goal)) return Optional.empty(); + + V3_EpsilonSuperstructureStates nextState = goal; + while (!nextState.equals(start)) { + V3_EpsilonSuperstructureStates parent = parents.get(nextState); + if (parent == null) return Optional.empty(); + else if (parent.equals(start)) return Optional.of(nextState); + nextState = parent; + } + return Optional.of(nextState); } - if (nextState == null) return; - - var edgeToCurrentState = graph.getEdge(nextState, currentState); - // Figure out if we should schedule a different command to get to goal faster - if (edgeCommand.getCommand().isScheduled() - && edgeToCurrentState != null - && isEdgeAllowed(edgeToCurrentState, goal)) { - // Figure out where we would have gone from the previous state - bfs(currentState, goal) - .ifPresent( - newNext -> { - if (newNext == nextState) { - // We are already on track - return; + /** + * Checks if a state transition is allowed based on algae presence. + * + * @param edge The transition edge to check + * @param goal The target state + * @return true if the transition is allowed + */ + private boolean isEdgeAllowed(EdgeCommand edge, V3_EpsilonSuperstructureStates goal) { + // --- 1. Algae Check (Original Logic) --- + boolean gamePieceAllowed = + edge.getGamePieceEdge() == GamePieceEdge.UNCONSTRAINED + || RobotState.isHasAlgae() == (edge.getGamePieceEdge() != GamePieceEdge.NO_ALGAE); + + if (!gamePieceAllowed) { + return false; // Fail fast if game piece logic disallows it + } + + // Condition is TRUE, so we must apply the path forcing logic. + if (!RobotState.isHasAlgae()) { + V3_EpsilonSuperstructureStates from = graph.getEdgeSource(edge); + V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(edge); + + boolean needsFlip = RobotState.getScoreSide().equals(ScoreSide.RIGHT); + + if (goal == V3_EpsilonSuperstructureStates.STOW_UP && needsFlip) { + if (to == V3_EpsilonSuperstructureStates.STOW_UP + && from != V3_EpsilonSuperstructureStates.INVERSE_FLIP_UP) { + return false; } + } - if (newNext != currentState && graph.getEdge(nextState, newNext) != null) { - // We can skip directly to the newNext edge - edgeCommand.getCommand().cancel(); - edgeCommand = graph.getEdge(currentState, newNext); - edgeCommand.getCommand().schedule(); - nextState = newNext; - } else { - // Follow the reverse edge from next back to the current edge - edgeCommand.getCommand().cancel(); - edgeCommand = graph.getEdge(nextState, currentState); - edgeCommand.getCommand().schedule(); - var temp = currentState; - previousState = currentState; - currentState = nextState; - nextState = temp; + if (goal == V3_EpsilonSuperstructureStates.STOW_UP && !needsFlip) { + if (to == V3_EpsilonSuperstructureStates.STOW_UP + && from != V3_EpsilonSuperstructureStates.INVERSE_FLIP_UP) { + return false; } - }); + } + } + + // --- 3. If all checks pass, the edge is allowed --- + return true; } - } - - /** - * Performs breadth-first search to find the next state in the path to the goal. - * - * @param start Starting state - * @param goal Target state - * @return Optional containing the next state in the path, empty if no path exists - */ - private Optional bfs( - V3_EpsilonSuperstructureStates start, V3_EpsilonSuperstructureStates goal) { - Map parents = new HashMap<>(); - Queue queue = new LinkedList<>(); - queue.add(start); - parents.put(start, null); - while (!queue.isEmpty()) { - V3_EpsilonSuperstructureStates current = queue.poll(); - if (current == goal) break; - for (EdgeCommand edge : - graph.outgoingEdgesOf(current).stream() - .filter(edge -> isEdgeAllowed(edge, goal)) - .toList()) { - V3_EpsilonSuperstructureStates neighbor = graph.getEdgeTarget(edge); - if (!parents.containsKey(neighbor)) { - parents.put(neighbor, current); - queue.add(neighbor); + + /** + * Resets the superstructure to initial auto state. + */ + public void setAutoStart() { + currentState = V3_EpsilonSuperstructureStates.START; + nextState = null; + targetState = V3_EpsilonSuperstructureStates.STOW_DOWN; + if (edgeCommand != null) { + edgeCommand.getCommand().cancel(); } - } } - if (!parents.containsKey(goal)) return Optional.empty(); + /** + * Maps current OI reef height to corresponding elevator position state. + * + * @return Appropriate superstructure state for current reef height + */ + private V3_EpsilonSuperstructureStates getElevatorPosition() { + switch (RobotState.getOIData().currentReefHeight()) { + case STOW, CORAL_INTAKE -> { + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + case L1 -> { + return V3_EpsilonSuperstructureStates.L1; + } + case L2 -> { + return V3_EpsilonSuperstructureStates.L2; + } + case L3 -> { + return V3_EpsilonSuperstructureStates.L3; + } + case L4 -> { + return V3_EpsilonSuperstructureStates.L4; + } + case ALGAE_INTAKE_BOTTOM -> { + return V3_EpsilonSuperstructureStates.L2_ALGAE; + } + case ALGAE_INTAKE_TOP -> { + return V3_EpsilonSuperstructureStates.L3_ALGAE; + } + case ALGAE_SCORE -> { + return V3_EpsilonSuperstructureStates.BARGE; + } + default -> { + return V3_EpsilonSuperstructureStates.START; + } + } + } + + // --- Control Commands --- - V3_EpsilonSuperstructureStates nextState = goal; - while (!nextState.equals(start)) { - V3_EpsilonSuperstructureStates parent = parents.get(nextState); - if (parent == null) return Optional.empty(); - else if (parent.equals(start)) return Optional.of(nextState); - nextState = parent; + /** + * Returns a command that sets the superstructure to the given goal state. + * + * @param goal The desired superstructure state + * @return Command to run the goal + */ + public Command runGoal(V3_EpsilonSuperstructureStates goal) { + return runOnce(() -> setGoal(goal)); } - return Optional.of(nextState); - } - - /** - * Checks if a state transition is allowed based on algae presence. - * - * @param edge The transition edge to check - * @param goal The target state - * @return true if the transition is allowed - */ - private boolean isEdgeAllowed(EdgeCommand edge, V3_EpsilonSuperstructureStates goal) { - // --- 1. Algae Check (Original Logic) --- - boolean gamePieceAllowed = - edge.getGamePieceEdge() == GamePieceEdge.UNCONSTRAINED - || RobotState.isHasAlgae() == (edge.getGamePieceEdge() != GamePieceEdge.NO_ALGAE); - - if (!gamePieceAllowed) { - return false; // Fail fast if game piece logic disallows it + + /** + * Returns a command that sets the superstructure to the goal provided by a supplier. + * + * @param goal Supplier providing the desired superstructure state + * @return Command to run the goal + */ + public Command runGoal(Supplier goal) { + return runOnce(() -> setGoal(goal.get())); } - // Condition is TRUE, so we must apply the path forcing logic. - if (!manipulator.hasAlgae()) { - V3_EpsilonSuperstructureStates from = graph.getEdgeSource(edge); - V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(edge); + /** + * Checks whether the superstructure has reached its target state. + * + * @return true if current state matches the target state + */ + @AutoLogOutput(key = NTPrefixes.SUPERSTRUCTURE + "At Goal") + public boolean atGoal() { + return currentState == targetState + && elevator.atGoal() + && intake.pivotAtGoal() + && manipulator.armAtGoal(); + } - boolean needsFlip = RobotState.getScoreSide().equals(ScoreSide.RIGHT); + public Command waitUntilAtGoal() { + return Commands.sequence(Commands.waitSeconds(.02), Commands.waitUntil(() -> atGoal())); + } - if (goal == V3_EpsilonSuperstructureStates.STOW_UP && needsFlip) { - if (to == V3_EpsilonSuperstructureStates.STOW_UP - && from != V3_EpsilonSuperstructureStates.INVERSE_FLIP_UP) { - return false; - } - } + /** + * Runs a temporary override action, returning to a previous goal after. + * + * @param action The override action to perform + * @param oldGoal The goal to return to after override + * @return Command that runs the override and resumes the old goal + */ + public Command override(Runnable action) { + return Commands.sequence(runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), Commands.run(action)) + .finallyDo(() -> setGoal(currentState)); + } - if (goal == V3_EpsilonSuperstructureStates.STOW_UP && !needsFlip) { - if (to == V3_EpsilonSuperstructureStates.STOW_UP - && from != V3_EpsilonSuperstructureStates.INVERSE_FLIP_UP) { - return false; - } - } + /** + * Runs a temporary override action, returning to a previous goal after. + * + * @param action The override action to perform + * @param oldGoal The goal to return to after override + * @return Command that runs the override and resumes the old goal + */ + public Command override(Runnable action, double timeSeconds) { + return override(action).withTimeout(timeSeconds); } - // --- 3. If all checks pass, the edge is allowed --- - return true; - } - - /** Resets the superstructure to initial auto state. */ - public void setAutoStart() { - currentState = V3_EpsilonSuperstructureStates.START; - nextState = null; - targetState = V3_EpsilonSuperstructureStates.STOW_DOWN; - if (edgeCommand != null) { - edgeCommand.getCommand().cancel(); + /** + * Runs the goal state and waits until a given condition becomes true. + * + * @param goal The desired superstructure state + * @param condition The condition to wait for after running the goal + * @return Combined command for running and waiting + */ + public Command runGoalUntil(V3_EpsilonSuperstructureStates goal, BooleanSupplier condition) { + return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); } - } - - /** - * Maps current OI reef height to corresponding elevator position state. - * - * @return Appropriate superstructure state for current reef height - */ - private V3_EpsilonSuperstructureStates getElevatorPosition() { - switch (RobotState.getOIData().currentReefHeight()) { - case STOW, CORAL_INTAKE -> { - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - case L1 -> { - return V3_EpsilonSuperstructureStates.L1; - } - case L2 -> { - return V3_EpsilonSuperstructureStates.L2; - } - case L3 -> { - return V3_EpsilonSuperstructureStates.L3; - } - case L4 -> { - return V3_EpsilonSuperstructureStates.L4; - } - case ALGAE_INTAKE_BOTTOM -> { - return V3_EpsilonSuperstructureStates.L2_ALGAE; - } - case ALGAE_INTAKE_TOP -> { - return V3_EpsilonSuperstructureStates.L3_ALGAE; - } - case ALGAE_SCORE -> { - return V3_EpsilonSuperstructureStates.BARGE; - } - default -> { - return V3_EpsilonSuperstructureStates.START; - } + + public Command runGoalUntil( + Supplier goal, BooleanSupplier condition) { + return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); } - } - - // --- Control Commands --- - - /** - * Returns a command that sets the superstructure to the given goal state. - * - * @param goal The desired superstructure state - * @return Command to run the goal - */ - public Command runGoal(V3_EpsilonSuperstructureStates goal) { - return runOnce(() -> setGoal(goal)); - } - - /** - * Returns a command that sets the superstructure to the goal provided by a supplier. - * - * @param goal Supplier providing the desired superstructure state - * @return Command to run the goal - */ - public Command runGoal(Supplier goal) { - return runOnce(() -> setGoal(goal.get())); - } - - /** - * Checks whether the superstructure has reached its target state. - * - * @return true if current state matches the target state - */ - @AutoLogOutput(key = NTPrefixes.SUPERSTRUCTURE + "At Goal") - public boolean atGoal() { - return currentState == targetState - && elevator.atGoal() - && intake.pivotAtGoal() - && manipulator.armAtGoal(); - } - - public Command waitUntilAtGoal() { - return Commands.sequence(Commands.waitSeconds(.02), Commands.waitUntil(() -> atGoal())); - } - - /** - * Runs a temporary override action, returning to a previous goal after. - * - * @param action The override action to perform - * @param oldGoal The goal to return to after override - * @return Command that runs the override and resumes the old goal - */ - public Command override(Runnable action) { - return Commands.sequence(runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), Commands.run(action)) - .finallyDo(() -> setGoal(currentState)); - } - - /** - * Runs a temporary override action, returning to a previous goal after. - * - * @param action The override action to perform - * @param oldGoal The goal to return to after override - * @return Command that runs the override and resumes the old goal - */ - public Command override(Runnable action, double timeSeconds) { - return override(action).withTimeout(timeSeconds); - } - - /** - * Runs the goal state and waits until a given condition becomes true. - * - * @param goal The desired superstructure state - * @param condition The condition to wait for after running the goal - * @return Combined command for running and waiting - */ - public Command runGoalUntil(V3_EpsilonSuperstructureStates goal, BooleanSupplier condition) { - return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); - } - - public Command runGoalUntil( - Supplier goal, BooleanSupplier condition) { - return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); - } - - /** - * Returns a short command to run the previous state, useful for temporary state restoration. - * - * @return Command to go back to the previous state - */ - public Command runPreviousState() { - return runGoal(() -> previousState); - } - - /** - * Converts a ReefState (field-level enum) into a corresponding elevator goal and runs it. - * - * @param goal Supplier of ReefState - * @return Command to move to the elevator position for the reef level - */ - public Command runReefGoal(Supplier goal) { - return runGoal( - () -> { - // Translate ReefState to superstructure state - switch (goal.get()) { - case L1: - return V3_EpsilonSuperstructureStates.L1; - case L2: - return V3_EpsilonSuperstructureStates.L2; - case L3: - return V3_EpsilonSuperstructureStates.L3; - case L4: - return V3_EpsilonSuperstructureStates.L4; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }); - } - - /** - * Moves to a scoring position, executes the score action for a fixed time, then returns to pose. - * - * @param goal Supplier of the ReefState (target height/level) - * @return Command to run the score cycle (pose → action → timeout → pose) - */ - public Command runReefScoreGoal(Supplier goal) { - // Run appropriate action sequence depending on reef level - return this.runGoal( - () -> { - switch (goal.get()) { - case L1: - return V3_EpsilonSuperstructureStates.L1_SCORE; - case L2: - return V3_EpsilonSuperstructureStates.L2_SCORE; - case L3: - return V3_EpsilonSuperstructureStates.L3_SCORE; - case L4: - return V3_EpsilonSuperstructureStates.L4_SCORE; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }); - - // return runActionWithTimeout( - // () -> - // switch (goal.get()) { - // case L1 -> V3_EpsilonSuperstructureStates.L1; - // case L2 -> V3_EpsilonSuperstructureStates.L2; - // case L3 -> V3_EpsilonSuperstructureStates.L3; - // case L4 -> V3_EpsilonSuperstructureStates.L4; - // default -> V3_EpsilonSuperstructureStates.STOW_DOWN; - // }, - // () -> - // switch (goal.get()) { - // case L1 -> 0.8; - // case L2 -> 0.15; - // case L3 -> 0.15; - // case L4 -> 0.1; - // default -> 0; - // }); - } - - /** - * Runs an action by going to a pose, performing the action, waiting, and returning. - * - * @param pose The pose to return to after action - * @param action The action to perform - * @param timeout How long to wait during the action phase (in seconds) - * @return Full command sequence - */ - public Command runActionWithTimeout( - Supplier pose, - Supplier action, - DoubleSupplier timeout) { - return Commands.sequence( - runGoal(action), // Run the action - waitUntilAtGoal(), - Commands.defer(() -> Commands.waitSeconds(timeout.getAsDouble()), Set.of())) - .finallyDo(() -> setGoal(pose.get())); // Return to original pose - } - - /** - * Runs an action by going to a pose, performing the action, waiting, and returning. - * - * @param pose The pose to return to after action - * @param action The action to perform - * @param timeout How long to wait during the action phase (in seconds) - * @return Full command sequence - */ - public Command runActionWithTimeout( - V3_EpsilonSuperstructureStates pose, V3_EpsilonSuperstructureStates action, double timeout) { - return Commands.sequence( - runGoal(action), // Run the action - waitUntilAtGoal(), - Commands.waitSeconds(timeout), - runGoal(pose)) - .finallyDo(() -> setGoal(pose)); // Return to original pose - } - - /** - * Smart overload that runs an action using a cached pose–action mapping, determining the pose - * from the action. - * - * @param action The scoring or action state - * @param timeout Timeout for the action duration - * @return Command sequence to perform and recover from the action - */ - public Command runActionWithTimeout( - Supplier action, DoubleSupplier timeout) { - // Maps each action state to its corresponding pose state - Map actionPoseMap = - new HashMap<>() { - { - put(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.L1); - put(V3_EpsilonSuperstructureStates.L2_SCORE, V3_EpsilonSuperstructureStates.L2); - put(V3_EpsilonSuperstructureStates.L3_SCORE, V3_EpsilonSuperstructureStates.L3); - put(V3_EpsilonSuperstructureStates.L4_SCORE, V3_EpsilonSuperstructureStates.L4); - put(V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.BARGE); - put( - V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, - V3_EpsilonSuperstructureStates.PROCESSOR); - } - }; - - // Reverse the map so we can look up the pose from action if needed - Map poseActionMap = - actionPoseMap.entrySet().stream() - .collect(Collectors.toMap(Map.Entry::getValue, Map.Entry::getKey)); - - // Try to look up pose from action (either direction works) - if (actionPoseMap.containsKey(action.get())) { - return runActionWithTimeout(() -> actionPoseMap.get(action.get()), action, timeout); - } else if (actionPoseMap.containsValue(action.get())) { - return runActionWithTimeout(action, () -> poseActionMap.get(action.get()), timeout); - } else return Commands.none(); // If action is not recognized, do nothing - } - - /** - * Smart overload that runs an action using a cached pose–action mapping, determining the pose - * from the action. - * - * @param action The scoring or action state - * @param timeout Timeout for the action duration - * @return Command sequence to perform and recover from the action - */ - public Command runActionWithTimeout(V3_EpsilonSuperstructureStates action, double timeout) { - // Maps each action state to its corresponding pose state - Map actionPoseMap = - new HashMap<>() { - { - put(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.L1); - put(V3_EpsilonSuperstructureStates.L2_SCORE, V3_EpsilonSuperstructureStates.L2); - put(V3_EpsilonSuperstructureStates.L3_SCORE, V3_EpsilonSuperstructureStates.L3); - put(V3_EpsilonSuperstructureStates.L4_SCORE, V3_EpsilonSuperstructureStates.L4); - put(V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.BARGE); - put( - V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, - V3_EpsilonSuperstructureStates.PROCESSOR); - } - }; - - // Reverse the map so we can look up the pose from action if needed - Map poseActionMap = - actionPoseMap.entrySet().stream() - .collect(Collectors.toMap(Map.Entry::getValue, Map.Entry::getKey)); - - // Try to look up pose from action (either direction works) - if (actionPoseMap.containsKey(action)) { - return runActionWithTimeout(actionPoseMap.get(action), action, timeout); - } else if (actionPoseMap.containsValue(action)) { - return runActionWithTimeout(action, poseActionMap.get(action), timeout); - } else return Commands.none(); // If action is not recognized, do nothing - } - - /** - * Updates the superstructure to match the current OI-defined reef height. - * - * @return Command to move to elevator position state - */ - public Command setPosition() { - return runGoal(() -> getElevatorPosition()).withTimeout(0.02); - } - - /** - * Checks if the elevator is at its goal position. - * - * @return True if the elevator is at its goal, false otherwise. - */ - public boolean elevatorAtGoal() { - return elevator.atGoal(); - } - - @AutoLogOutput(key = NTPrefixes.SUPERSTRUCTURE + "IsTransitioning") - public boolean isTransitioning() { - return edgeCommand != null && edgeCommand.getCommand().isScheduled(); - } - - public Command allTransition() { - Command all = runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN); - for (var source : V3_EpsilonSuperstructureStates.values()) { - for (var sink : V3_EpsilonSuperstructureStates.values()) { - if (source == sink) continue; - if (sink == V3_EpsilonSuperstructureStates.FLIP_DOWN) continue; - if (sink == V3_EpsilonSuperstructureStates.FLIP_UP) continue; - if (sink == V3_EpsilonSuperstructureStates.STOW_DOWN) continue; - if (sink == V3_EpsilonSuperstructureStates.STOW_UP) continue; - if (sink == V3_EpsilonSuperstructureStates.GROUND_ACQUISITION) continue; - if (sink == V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) continue; - if (sink == V3_EpsilonSuperstructureStates.GROUND_AQUISITION_ALGAE) continue; - if (sink == V3_EpsilonSuperstructureStates.GROUND_INTAKE) continue; - if (sink == V3_EpsilonSuperstructureStates.L1) continue; - if (sink == V3_EpsilonSuperstructureStates.L1_SCORE) continue; - if (sink == V3_EpsilonSuperstructureStates.L2) continue; - if (sink == V3_EpsilonSuperstructureStates.L2_SCORE) continue; - if (sink == V3_EpsilonSuperstructureStates.L3) continue; - if (sink == V3_EpsilonSuperstructureStates.L3_SCORE) continue; - - if (source != V3_EpsilonSuperstructureStates.START - && sink != V3_EpsilonSuperstructureStates.START - && source != V3_EpsilonSuperstructureStates.OVERRIDE - && sink != V3_EpsilonSuperstructureStates.OVERRIDE) { - all = - all.andThen( - runGoal(sink), - runOnce( - () -> - Logger.recordOutput( - "Superstructure/Current Objective", - source.toString() + " -> " + sink.toString())), - Commands.waitUntil(() -> atGoal())); - all = - all.andThen( - runGoal(source), - runOnce( - () -> - Logger.recordOutput( - "Superstructure/Current Objective", - sink.toString() + " -> " + source.toString())), - Commands.waitUntil(() -> atGoal())); - } - } + + /** + * Returns a short command to run the previous state, useful for temporary state restoration. + * + * @return Command to go back to the previous state + */ + public Command runPreviousState() { + return runGoal(() -> previousState); + } + + /** + * Converts a ReefState (field-level enum) into a corresponding elevator goal and runs it. + * + * @param goal Supplier of ReefState + * @return Command to move to the elevator position for the reef level + */ + public Command runReefGoal(Supplier goal) { + return runGoal( + () -> { + // Translate ReefState to superstructure state + switch (goal.get()) { + case L1: + return V3_EpsilonSuperstructureStates.L1; + case L2: + return V3_EpsilonSuperstructureStates.L2; + case L3: + return V3_EpsilonSuperstructureStates.L3; + case L4: + return V3_EpsilonSuperstructureStates.L4; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }); + } + + /** + * Moves to a scoring position, executes the score action for a fixed time, then returns to pose. + * + * @param goal Supplier of the ReefState (target height/level) + * @return Command to run the score cycle (pose → action → timeout → pose) + */ + public Command runReefScoreGoal(Supplier goal) { + // Run appropriate action sequence depending on reef level + return this.runGoal( + () -> { + switch (goal.get()) { + case L1: + return V3_EpsilonSuperstructureStates.L1_SCORE; + case L2: + return V3_EpsilonSuperstructureStates.L2_SCORE; + case L3: + return V3_EpsilonSuperstructureStates.L3_SCORE; + case L4: + return V3_EpsilonSuperstructureStates.L4_SCORE; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }); + + // return runActionWithTimeout( + // () -> + // switch (goal.get()) { + // case L1 -> V3_EpsilonSuperstructureStates.L1; + // case L2 -> V3_EpsilonSuperstructureStates.L2; + // case L3 -> V3_EpsilonSuperstructureStates.L3; + // case L4 -> V3_EpsilonSuperstructureStates.L4; + // default -> V3_EpsilonSuperstructureStates.STOW_DOWN; + // }, + // () -> + // switch (goal.get()) { + // case L1 -> 0.8; + // case L2 -> 0.15; + // case L3 -> 0.15; + // case L4 -> 0.1; + // default -> 0; + // }); } - return all; - } - - public Command stateTransitions(V3_EpsilonSuperstructureStates source) { - Command all = Commands.none(); - - for (var sink : V3_EpsilonSuperstructureStates.values()) { - if (sink == source - || sink == V3_EpsilonSuperstructureStates.START - || sink == V3_EpsilonSuperstructureStates.OVERRIDE) continue; - - all = - all.andThen( - Commands.sequence( - runOnce(() -> System.out.println("→ " + source + " to " + sink)), - runGoal(sink), - Commands.waitUntil(this::atGoal), - Commands.waitSeconds(1.0), - runOnce(() -> System.out.println("← " + sink + " back to " + source)), - runGoal(source), - Commands.waitUntil(this::atGoal), - Commands.waitSeconds(1.0))); + + /** + * Runs an action by going to a pose, performing the action, waiting, and returning. + * + * @param pose The pose to return to after action + * @param action The action to perform + * @param timeout How long to wait during the action phase (in seconds) + * @return Full command sequence + */ + public Command runActionWithTimeout( + Supplier pose, + Supplier action, + DoubleSupplier timeout) { + return Commands.sequence( + runGoal(action), // Run the action + waitUntilAtGoal(), + Commands.defer(() -> Commands.waitSeconds(timeout.getAsDouble()), Set.of())) + .finallyDo(() -> setGoal(pose.get())); // Return to original pose } - return all; - } + /** + * Runs an action by going to a pose, performing the action, waiting, and returning. + * + * @param pose The pose to return to after action + * @param action The action to perform + * @param timeout How long to wait during the action phase (in seconds) + * @return Full command sequence + */ + public Command runActionWithTimeout( + V3_EpsilonSuperstructureStates pose, V3_EpsilonSuperstructureStates action, double timeout) { + return Commands.sequence( + runGoal(action), // Run the action + waitUntilAtGoal(), + Commands.waitSeconds(timeout), + runGoal(pose)) + .finallyDo(() -> setGoal(pose)); // Return to original pose + } - public boolean armBelowThreshold() { - return manipulator.getArmAngle().getDegrees() >= 90; - } + /** + * Smart overload that runs an action using a cached pose–action mapping, determining the pose + * from the action. + * + * @param action The scoring or action state + * @param timeout Timeout for the action duration + * @return Command sequence to perform and recover from the action + */ + public Command runActionWithTimeout( + Supplier action, DoubleSupplier timeout) { + // Maps each action state to its corresponding pose state + Map actionPoseMap = + new HashMap<>() { + { + put(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.L1); + put(V3_EpsilonSuperstructureStates.L2_SCORE, V3_EpsilonSuperstructureStates.L2); + put(V3_EpsilonSuperstructureStates.L3_SCORE, V3_EpsilonSuperstructureStates.L3); + put(V3_EpsilonSuperstructureStates.L4_SCORE, V3_EpsilonSuperstructureStates.L4); + put(V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.BARGE); + put( + V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, + V3_EpsilonSuperstructureStates.PROCESSOR); + } + }; + + // Reverse the map so we can look up the pose from action if needed + Map poseActionMap = + actionPoseMap.entrySet().stream() + .collect(Collectors.toMap(Map.Entry::getValue, Map.Entry::getKey)); + + // Try to look up pose from action (either direction works) + if (actionPoseMap.containsKey(action.get())) { + return runActionWithTimeout(() -> actionPoseMap.get(action.get()), action, timeout); + } else if (actionPoseMap.containsValue(action.get())) { + return runActionWithTimeout(action, () -> poseActionMap.get(action.get()), timeout); + } else return Commands.none(); // If action is not recognized, do nothing + } + + /** + * Smart overload that runs an action using a cached pose–action mapping, determining the pose + * from the action. + * + * @param action The scoring or action state + * @param timeout Timeout for the action duration + * @return Command sequence to perform and recover from the action + */ + public Command runActionWithTimeout(V3_EpsilonSuperstructureStates action, double timeout) { + // Maps each action state to its corresponding pose state + Map actionPoseMap = + new HashMap<>() { + { + put(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.L1); + put(V3_EpsilonSuperstructureStates.L2_SCORE, V3_EpsilonSuperstructureStates.L2); + put(V3_EpsilonSuperstructureStates.L3_SCORE, V3_EpsilonSuperstructureStates.L3); + put(V3_EpsilonSuperstructureStates.L4_SCORE, V3_EpsilonSuperstructureStates.L4); + put(V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.BARGE); + put( + V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, + V3_EpsilonSuperstructureStates.PROCESSOR); + } + }; + + // Reverse the map so we can look up the pose from action if needed + Map poseActionMap = + actionPoseMap.entrySet().stream() + .collect(Collectors.toMap(Map.Entry::getValue, Map.Entry::getKey)); + + // Try to look up pose from action (either direction works) + if (actionPoseMap.containsKey(action)) { + return runActionWithTimeout(actionPoseMap.get(action), action, timeout); + } else if (actionPoseMap.containsValue(action)) { + return runActionWithTimeout(action, poseActionMap.get(action), timeout); + } else return Commands.none(); // If action is not recognized, do nothing + } + + /** + * Updates the superstructure to match the current OI-defined reef height. + * + * @return Command to move to elevator position state + */ + public Command setPosition() { + return runGoal(() -> getElevatorPosition()).withTimeout(0.02); + } + + /** + * Checks if the elevator is at its goal position. + * + * @return True if the elevator is at its goal, false otherwise. + */ + public boolean elevatorAtGoal() { + return elevator.atGoal(); + } + + @AutoLogOutput(key = NTPrefixes.SUPERSTRUCTURE + "IsTransitioning") + public boolean isTransitioning() { + return edgeCommand != null && edgeCommand.getCommand().isScheduled(); + } + + public Command allTransition() { + Command all = runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN); + for (var source : V3_EpsilonSuperstructureStates.values()) { + for (var sink : V3_EpsilonSuperstructureStates.values()) { + if (source == sink) continue; + if (sink == V3_EpsilonSuperstructureStates.FLIP_DOWN) continue; + if (sink == V3_EpsilonSuperstructureStates.FLIP_UP) continue; + if (sink == V3_EpsilonSuperstructureStates.STOW_DOWN) continue; + if (sink == V3_EpsilonSuperstructureStates.STOW_UP) continue; + if (sink == V3_EpsilonSuperstructureStates.GROUND_ACQUISITION) continue; + if (sink == V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) continue; + if (sink == V3_EpsilonSuperstructureStates.GROUND_AQUISITION_ALGAE) continue; + if (sink == V3_EpsilonSuperstructureStates.GROUND_INTAKE) continue; + if (sink == V3_EpsilonSuperstructureStates.L1) continue; + if (sink == V3_EpsilonSuperstructureStates.L1_SCORE) continue; + if (sink == V3_EpsilonSuperstructureStates.L2) continue; + if (sink == V3_EpsilonSuperstructureStates.L2_SCORE) continue; + if (sink == V3_EpsilonSuperstructureStates.L3) continue; + if (sink == V3_EpsilonSuperstructureStates.L3_SCORE) continue; + + if (source != V3_EpsilonSuperstructureStates.START + && sink != V3_EpsilonSuperstructureStates.START + && source != V3_EpsilonSuperstructureStates.OVERRIDE + && sink != V3_EpsilonSuperstructureStates.OVERRIDE) { + all = + all.andThen( + runGoal(sink), + runOnce( + () -> + Logger.recordOutput( + "Superstructure/Current Objective", + source.toString() + " -> " + sink.toString())), + Commands.waitUntil(() -> atGoal())); + all = + all.andThen( + runGoal(source), + runOnce( + () -> + Logger.recordOutput( + "Superstructure/Current Objective", + sink.toString() + " -> " + source.toString())), + Commands.waitUntil(() -> atGoal())); + } + } + } + return all; + } + + public Command stateTransitions(V3_EpsilonSuperstructureStates source) { + Command all = Commands.none(); + + for (var sink : V3_EpsilonSuperstructureStates.values()) { + if (sink == source + || sink == V3_EpsilonSuperstructureStates.START + || sink == V3_EpsilonSuperstructureStates.OVERRIDE) continue; + + all = + all.andThen( + Commands.sequence( + runOnce(() -> System.out.println("→ " + source + " to " + sink)), + runGoal(sink), + Commands.waitUntil(this::atGoal), + Commands.waitSeconds(1.0), + runOnce(() -> System.out.println("← " + sink + " back to " + source)), + runGoal(source), + Commands.waitUntil(this::atGoal), + Commands.waitSeconds(1.0))); + } + + return all; + } + + public boolean armBelowThreshold() { + return manipulator.getArmAngle().getDegrees() >= 90; + } } From 0e90e98b8334c40fc212efaf9317b5cbaa02cc38 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 1 Nov 2025 12:51:42 -0400 Subject: [PATCH 156/180] Update at 'Sat Nov 01 12:51:42 EDT 2025' --- .../frc/robot/commands/CompositeCommands.java | 1809 +++++++++-------- .../subsystems/shared/elevator/Elevator.java | 777 +++---- .../V3_EpsilonSuperstructure.java | 1319 ++++++------ .../manipulator/V3_EpsilonManipulator.java | 597 +++--- 4 files changed, 2254 insertions(+), 2248 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 3b115c96..9369fa0c 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -28,6 +28,7 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; import frc.robot.util.AllianceFlipUtil; + import java.util.Set; import java.util.function.BooleanSupplier; import java.util.function.Supplier; @@ -36,919 +37,923 @@ * A class that holds composite commands, which are sequences of commands for complex robot actions. */ public class CompositeCommands { - /** A class that holds composite commands that are shared across different robot versions. */ - public static final class SharedCommands { - /** - * Creates a command to reset the robot's heading to the alliance-specific zero. - * - * @param drive The drive subsystem. - * @return A command to reset the heading. - */ - public static final Command resetHeading(Drive drive) { - return Commands.runOnce( - () -> { - RobotState.resetRobotPose( - new Pose2d( - RobotState.getRobotPoseField().getTranslation(), - AllianceFlipUtil.apply(new Rotation2d()))); - }) - .ignoringDisable(true); - } - - /** - * Creates a command to set a static reef height in the robot state. This does not move any - * mechanisms. - * - * @param height The reef height to set. - * @return A command to set the reef height. - */ - public static final Command setStaticReefHeight(ReefState height) { - return Commands.runOnce(() -> RobotState.setReefHeight(height)); - } - } - - /** A class that holds composite commands for the V1_StackUp robot. */ - public static final class V1_StackUpCompositeCommands { - /** - * Creates a command to intake coral from the station. - * - * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. - * @param manipulator The manipulator subsystem. - * @return A command to intake coral. - */ - public static final Command intakeCoral( - ElevatorCSB elevator, FunnelCSB funnel, V1_StackUpManipulator manipulator) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setIntakingCoral(true)), - elevator.setPosition(() -> ReefState.CORAL_INTAKE), - Commands.waitUntil(elevator::atGoal), - Commands.race( - manipulator.intakeCoral(), funnel.intakeCoral(() -> manipulator.hasCoral()))) - .finallyDo(() -> RobotState.setIntakingCoral(false)); - } - - /** - * Creates a command to intake coral from the station with an override. - * - * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. - * @param manipulator The manipulator subsystem. - * @return A command to intake coral with an override. - */ - public static final Command intakeCoralOverride( - ElevatorCSB elevator, FunnelCSB funnel, V1_StackUpManipulator manipulator) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setIntakingCoral(true)), - elevator.setPosition(() -> ReefState.CORAL_INTAKE), - Commands.waitUntil(elevator::atGoal), - Commands.parallel(manipulator.intakeCoral(), funnel.intakeCoral(() -> false))) - .finallyDo(() -> RobotState.setIntakingCoral(false)); - } - - /** - * Creates a command to score coral. - * - * @param manipulator The manipulator subsystem. - * @return A command to score coral. - */ - public static final Command scoreCoral(V1_StackUpManipulator manipulator) { - return manipulator.scoreCoral().withTimeout(0.4); - } - - /** - * Creates a command sequence to score coral, waiting for auto-alignment. - * - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param autoAligned A supplier that returns true when the robot is aligned. - * @return A command sequence to score coral. - */ - public static final Command scoreCoralSequence( - ElevatorCSB elevator, V1_StackUpManipulator manipulator, BooleanSupplier autoAligned) { - return Commands.sequence( - Commands.either( - elevator.setPosition(() -> ReefState.L3), - elevator.setPosition(), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L4) - && !elevator.getPosition().equals(ElevatorPositions.L4)), - Commands.waitUntil(() -> autoAligned.getAsBoolean()), - elevator.setPosition(), - Commands.waitSeconds(0.05), - Commands.waitUntil(elevator::atGoal), - Commands.either( - manipulator.scoreL4Coral().withTimeout(0.4), - manipulator.scoreCoral().withTimeout(0.15), - () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L4))); - } - - /** - * Creates a command sequence to automatically score coral. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. - * @return A command sequence to auto-score coral. - */ - public static final Command autoScoreCoralSequence( - Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { - return Commands.either( - autoScoreL1CoralSequence(drive, elevator, manipulator, cameras), - Commands.sequence( - Commands.either( - elevator.setPosition(() -> ReefState.L2), - Commands.none(), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L1) - || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) - || RobotState.getOIData() - .currentReefHeight() - .equals(ReefState.CORAL_INTAKE)), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - scoreCoralSequence( - elevator, - manipulator, - () -> RobotState.getReefAlignData().atCoralSetpoint())), - elevator - .setPosition(() -> ReefState.STOW) - .onlyIf( - () -> - elevator.getPosition().equals(ElevatorPositions.L3) - || elevator.getPosition().equals(ElevatorPositions.L2))), - () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); - } - - /** - * Creates a command sequence to automatically score coral at L1. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. - * @return A command sequence to auto-score coral at L1. - */ - public static final Command autoScoreL1CoralSequence( - Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefCoral(drive, cameras), - scoreL1Coral(drive, elevator, manipulator)); - } - - /** - * Creates a command to score coral at L1. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @return A command to score coral at L1. - */ - public static final Command scoreL1Coral( - Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator) { - return Commands.sequence( - elevator.setPosition(), - Commands.waitSeconds(0.02), - Commands.waitUntil(elevator::atGoal), - Commands.parallel( - manipulator.scoreL1Coral().withTimeout(0.8), - Commands.sequence( - Commands.waitSeconds(0.05), - Commands.either( - DriveCommands.inchMovement(drive, -1, 0.1), - DriveCommands.inchMovement(drive, 1, 0.1), - () -> RobotState.getOIData().currentReefPost() == ReefPose.LEFT)))); - } - - /** - * Creates a command for an emergency eject of coral. - * - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @return A command to eject coral. - */ - public static final Command emergencyEject( - ElevatorCSB elevator, V1_StackUpManipulator manipulator) { - return Commands.sequence( - elevator.setPosition(() -> ReefState.L1), - Commands.waitSeconds(0.125), - Commands.waitUntil(elevator::atGoal), - manipulator.scoreCoral().withTimeout(0.4), - elevator.setPosition(() -> ReefState.STOW)); - } - - /** - * Creates a command to remove algae from the reef. This uses the closest reef tag to - * automatically pick the reef height. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. - * @return A command to remove algae. - */ - public static final Command twerk( - Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { - return Commands.deferredProxy( - () -> - twerk( - drive, - elevator, - manipulator, - switch (RobotState.getReefAlignData().closestReefTag()) { - case 10, 6, 8, 21, 17, 19 -> ReefState.ASS_BOT; - case 9, 11, 7, 22, 20, 18 -> ReefState.ASS_TOP; - default -> ReefState.ASS_BOT; - }, - cameras)); - } - - /** - * Creates a command to remove algae from the reef. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. - * @return A command to remove algae. - */ - public static final Command twerk( - Drive drive, - ElevatorCSB elevator, - V1_StackUpManipulator manipulator, - ReefState level, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefAlgae(drive, cameras), - elevator.setPosition(() -> ReefState.L4), - Commands.waitUntil(elevator::atGoal), - manipulator.toggleAlgaeArm(), - Commands.waitSeconds(0.1), - elevator.setPosition(() -> level), - manipulator.removeAlgae().until(elevator::atGoal), - manipulator.removeAlgae().withTimeout(0.35), - manipulator.toggleAlgaeArm()); - } - - /** - * Creates a command to set the dynamic reef height in the robot state. This sets the height and - * then moves the elevator to that position. - * - * @param height The reef height to set. - * @param elevator The elevator subsystem. - * @return A command to set the dynamic reef height. - */ - public static final Command setDynamicReefHeight(ReefState height, ElevatorCSB elevator) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setReefHeight(height)), elevator.setPosition()); - } - - /** - * Creates a command to climb the robot. - * - * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. - * @param climber The climber subsystem. - * @param drive The drive subsystem. - * @return A command to climb. - */ - public static final Command climb( - ElevatorCSB elevator, FunnelCSB funnel, Climber climber, Drive drive) { - return Commands.sequence( - elevator.setPosition(() -> ReefState.STOW), - Commands.waitSeconds(0.02), - Commands.waitUntil(elevator::atGoal), - funnel.setClapDaddyGoal(FunnelState.CLIMB), - Commands.parallel( - climber.releaseClimber(), - Commands.waitSeconds( - ClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), - Commands.waitUntil(climber::climberReady), - Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); - } - } - - public static final class V2_RedundancyCompositeCommands { - /** - * Creates a command to intake coral from the station. - * - * @param superstructure The superstructure subsystem. - * @param intake The intake subsystem. - * @return A command to intake coral. - */ - public static final Command intakeCoralDriverSequence( - V2_RedundancySuperstructure superstructure, V2_RedundancyIntake intake) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoalUntil( - V2_RedundancySuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); - } - - /** - * Creates a command to intake coral from the station using the operator sequence. - * - * @param superstructure The superstructure subsystem. - * @param intake The intake subsystem. - * @return A command to intake coral using the operator sequence. - */ - public static final Command intakeCoralOperatorSequence( - V2_RedundancySuperstructure superstructure, V2_RedundancyIntake intake) { - return Commands.sequence( - superstructure.runGoalUntil( - V2_RedundancySuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); - } - - /** - * Creates a command to score coral at L1. - * - * @param drive The drive subsystem. - * @param superstructure The superstructure subsystem. - * @return A command to score coral at L1. - */ - public static final Command scoreL1Coral( - Drive drive, V2_RedundancySuperstructure superstructure) { - return Commands.sequence( - superstructure.runGoal(V2_RedundancySuperstructureStates.L1), - Commands.parallel( - superstructure.runReefScoreGoal(() -> ReefState.L1), - Commands.sequence( - Commands.waitSeconds(0.05), - Commands.either( - DriveCommands.inchMovement(drive, -1, 0.1), - DriveCommands.inchMovement(drive, 1, 0.1), - () -> RobotState.getOIData().currentReefPost() == ReefPose.LEFT)))); - } - - /** - * Creates a command sequence to score coral at L1, waiting for auto-alignment. - * - * @param drive The drive subsystem. - * @param superstructure The superstructure subsystem. - * @return A command sequence to score coral at L1. - */ - public static final Command autoScoreL1CoralSequence( - Drive drive, - ElevatorFSM elevator, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefCoral(drive, cameras), scoreL1Coral(drive, superstructure)); - } - /** - * Creates a command sequence to score coral, waiting for auto-alignment. - * - * @param elevator The elevator subsystem. - * @param superstructure The superstructure subsystem. - * @param autoAligned A supplier that returns true when the robot is aligned. - * @return A command sequence to score coral. + * A class that holds composite commands that are shared across different robot versions. */ - public static final Command scoreCoralSequence( - ElevatorFSM elevator, - V2_RedundancySuperstructure superstructure, - BooleanSupplier autoAligned) { - return Commands.sequence( - Commands.either( - superstructure.runGoal(V2_RedundancySuperstructureStates.L3), - superstructure.runReefGoal(() -> RobotState.getOIData().currentReefHeight()), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L4) - && !superstructure - .getCurrentState() - .equals(V2_RedundancySuperstructureStates.L4)), - Commands.waitUntil(() -> autoAligned.getAsBoolean()), - superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight()), - superstructure - .runGoal(V2_RedundancySuperstructureStates.STOW_DOWN) - .onlyIf( - () -> - elevator.getPosition().equals(ElevatorPositions.L3) - || elevator.getPosition().equals(ElevatorPositions.L2))); + public static final class SharedCommands { + /** + * Creates a command to reset the robot's heading to the alliance-specific zero. + * + * @param drive The drive subsystem. + * @return A command to reset the heading. + */ + public static final Command resetHeading(Drive drive) { + return Commands.runOnce( + () -> { + RobotState.resetRobotPose( + new Pose2d( + RobotState.getRobotPoseField().getTranslation(), + AllianceFlipUtil.apply(new Rotation2d()))); + }) + .ignoringDisable(true); + } + + /** + * Creates a command to set a static reef height in the robot state. This does not move any + * mechanisms. + * + * @param height The reef height to set. + * @return A command to set the reef height. + */ + public static final Command setStaticReefHeight(ReefState height) { + return Commands.runOnce(() -> RobotState.setReefHeight(height)); + } } /** - * Creates a command sequence to automatically score coral. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param superstructure The superstructure subsystem. - * @param cameras The vision cameras. - * @return A command sequence to auto-score coral. + * A class that holds composite commands for the V1_StackUp robot. */ - public static final Command autoScoreCoralSequence( - Drive drive, - ElevatorFSM elevator, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - return Commands.either( - Commands.sequence( - autoScoreL1CoralSequence(drive, elevator, superstructure, cameras), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)), - Commands.sequence( - Commands.either( - superstructure.runGoal(V2_RedundancySuperstructureStates.L2), - Commands.none(), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L1) - || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) - || RobotState.getOIData() - .currentReefHeight() - .equals(ReefState.CORAL_INTAKE)), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - scoreCoralSequence( - elevator, - superstructure, - () -> RobotState.getReefAlignData().atCoralSetpoint())), - superstructure - .l4PlusSequence() - .onlyIf(() -> RobotState.getOIData().currentReefHeight() == ReefState.L4)), - () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); + public static final class V1_StackUpCompositeCommands { + /** + * Creates a command to intake coral from the station. + * + * @param elevator The elevator subsystem. + * @param funnel The funnel subsystem. + * @param manipulator The manipulator subsystem. + * @return A command to intake coral. + */ + public static final Command intakeCoral( + ElevatorCSB elevator, FunnelCSB funnel, V1_StackUpManipulator manipulator) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setIntakingCoral(true)), + elevator.setPosition(() -> ReefState.CORAL_INTAKE), + Commands.waitUntil(elevator::atGoal), + Commands.race( + manipulator.intakeCoral(), funnel.intakeCoral(() -> manipulator.hasCoral()))) + .finallyDo(() -> RobotState.setIntakingCoral(false)); + } + + /** + * Creates a command to intake coral from the station with an override. + * + * @param elevator The elevator subsystem. + * @param funnel The funnel subsystem. + * @param manipulator The manipulator subsystem. + * @return A command to intake coral with an override. + */ + public static final Command intakeCoralOverride( + ElevatorCSB elevator, FunnelCSB funnel, V1_StackUpManipulator manipulator) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setIntakingCoral(true)), + elevator.setPosition(() -> ReefState.CORAL_INTAKE), + Commands.waitUntil(elevator::atGoal), + Commands.parallel(manipulator.intakeCoral(), funnel.intakeCoral(() -> false))) + .finallyDo(() -> RobotState.setIntakingCoral(false)); + } + + /** + * Creates a command to score coral. + * + * @param manipulator The manipulator subsystem. + * @return A command to score coral. + */ + public static final Command scoreCoral(V1_StackUpManipulator manipulator) { + return manipulator.scoreCoral().withTimeout(0.4); + } + + /** + * Creates a command sequence to score coral, waiting for auto-alignment. + * + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param autoAligned A supplier that returns true when the robot is aligned. + * @return A command sequence to score coral. + */ + public static final Command scoreCoralSequence( + ElevatorCSB elevator, V1_StackUpManipulator manipulator, BooleanSupplier autoAligned) { + return Commands.sequence( + Commands.either( + elevator.setPosition(() -> ReefState.L3), + elevator.setPosition(), + () -> + RobotState.getOIData().currentReefHeight().equals(ReefState.L4) + && !elevator.getPosition().equals(ElevatorPositions.L4)), + Commands.waitUntil(() -> autoAligned.getAsBoolean()), + elevator.setPosition(), + Commands.waitSeconds(0.05), + Commands.waitUntil(elevator::atGoal), + Commands.either( + manipulator.scoreL4Coral().withTimeout(0.4), + manipulator.scoreCoral().withTimeout(0.15), + () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L4))); + } + + /** + * Creates a command sequence to automatically score coral. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param cameras The vision cameras. + * @return A command sequence to auto-score coral. + */ + public static final Command autoScoreCoralSequence( + Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { + return Commands.either( + autoScoreL1CoralSequence(drive, elevator, manipulator, cameras), + Commands.sequence( + Commands.either( + elevator.setPosition(() -> ReefState.L2), + Commands.none(), + () -> + RobotState.getOIData().currentReefHeight().equals(ReefState.L1) + || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) + || RobotState.getOIData() + .currentReefHeight() + .equals(ReefState.CORAL_INTAKE)), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + scoreCoralSequence( + elevator, + manipulator, + () -> RobotState.getReefAlignData().atCoralSetpoint())), + elevator + .setPosition(() -> ReefState.STOW) + .onlyIf( + () -> + elevator.getPosition().equals(ElevatorPositions.L3) + || elevator.getPosition().equals(ElevatorPositions.L2))), + () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); + } + + /** + * Creates a command sequence to automatically score coral at L1. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param cameras The vision cameras. + * @return A command sequence to auto-score coral at L1. + */ + public static final Command autoScoreL1CoralSequence( + Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { + return Commands.sequence( + DriveCommands.autoAlignReefCoral(drive, cameras), + scoreL1Coral(drive, elevator, manipulator)); + } + + /** + * Creates a command to score coral at L1. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @return A command to score coral at L1. + */ + public static final Command scoreL1Coral( + Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator) { + return Commands.sequence( + elevator.setPosition(), + Commands.waitSeconds(0.02), + Commands.waitUntil(elevator::atGoal), + Commands.parallel( + manipulator.scoreL1Coral().withTimeout(0.8), + Commands.sequence( + Commands.waitSeconds(0.05), + Commands.either( + DriveCommands.inchMovement(drive, -1, 0.1), + DriveCommands.inchMovement(drive, 1, 0.1), + () -> RobotState.getOIData().currentReefPost() == ReefPose.LEFT)))); + } + + /** + * Creates a command for an emergency eject of coral. + * + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @return A command to eject coral. + */ + public static final Command emergencyEject( + ElevatorCSB elevator, V1_StackUpManipulator manipulator) { + return Commands.sequence( + elevator.setPosition(() -> ReefState.L1), + Commands.waitSeconds(0.125), + Commands.waitUntil(elevator::atGoal), + manipulator.scoreCoral().withTimeout(0.4), + elevator.setPosition(() -> ReefState.STOW)); + } + + /** + * Creates a command to remove algae from the reef. This uses the closest reef tag to + * automatically pick the reef height. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param cameras The vision cameras. + * @return A command to remove algae. + */ + public static final Command twerk( + Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { + return Commands.deferredProxy( + () -> + twerk( + drive, + elevator, + manipulator, + switch (RobotState.getReefAlignData().closestReefTag()) { + case 10, 6, 8, 21, 17, 19 -> ReefState.ASS_BOT; + case 9, 11, 7, 22, 20, 18 -> ReefState.ASS_TOP; + default -> ReefState.ASS_BOT; + }, + cameras)); + } + + /** + * Creates a command to remove algae from the reef. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param cameras The vision cameras. + * @return A command to remove algae. + */ + public static final Command twerk( + Drive drive, + ElevatorCSB elevator, + V1_StackUpManipulator manipulator, + ReefState level, + Camera... cameras) { + return Commands.sequence( + DriveCommands.autoAlignReefAlgae(drive, cameras), + elevator.setPosition(() -> ReefState.L4), + Commands.waitUntil(elevator::atGoal), + manipulator.toggleAlgaeArm(), + Commands.waitSeconds(0.1), + elevator.setPosition(() -> level), + manipulator.removeAlgae().until(elevator::atGoal), + manipulator.removeAlgae().withTimeout(0.35), + manipulator.toggleAlgaeArm()); + } + + /** + * Creates a command to set the dynamic reef height in the robot state. This sets the height and + * then moves the elevator to that position. + * + * @param height The reef height to set. + * @param elevator The elevator subsystem. + * @return A command to set the dynamic reef height. + */ + public static final Command setDynamicReefHeight(ReefState height, ElevatorCSB elevator) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setReefHeight(height)), elevator.setPosition()); + } + + /** + * Creates a command to climb the robot. + * + * @param elevator The elevator subsystem. + * @param funnel The funnel subsystem. + * @param climber The climber subsystem. + * @param drive The drive subsystem. + * @return A command to climb. + */ + public static final Command climb( + ElevatorCSB elevator, FunnelCSB funnel, Climber climber, Drive drive) { + return Commands.sequence( + elevator.setPosition(() -> ReefState.STOW), + Commands.waitSeconds(0.02), + Commands.waitUntil(elevator::atGoal), + funnel.setClapDaddyGoal(FunnelState.CLIMB), + Commands.parallel( + climber.releaseClimber(), + Commands.waitSeconds( + ClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), + Commands.waitUntil(climber::climberReady), + Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); + } + } + + public static final class V2_RedundancyCompositeCommands { + /** + * Creates a command to intake coral from the station. + * + * @param superstructure The superstructure subsystem. + * @param intake The intake subsystem. + * @return A command to intake coral. + */ + public static final Command intakeCoralDriverSequence( + V2_RedundancySuperstructure superstructure, V2_RedundancyIntake intake) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoalUntil( + V2_RedundancySuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); + } + + /** + * Creates a command to intake coral from the station using the operator sequence. + * + * @param superstructure The superstructure subsystem. + * @param intake The intake subsystem. + * @return A command to intake coral using the operator sequence. + */ + public static final Command intakeCoralOperatorSequence( + V2_RedundancySuperstructure superstructure, V2_RedundancyIntake intake) { + return Commands.sequence( + superstructure.runGoalUntil( + V2_RedundancySuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); + } + + /** + * Creates a command to score coral at L1. + * + * @param drive The drive subsystem. + * @param superstructure The superstructure subsystem. + * @return A command to score coral at L1. + */ + public static final Command scoreL1Coral( + Drive drive, V2_RedundancySuperstructure superstructure) { + return Commands.sequence( + superstructure.runGoal(V2_RedundancySuperstructureStates.L1), + Commands.parallel( + superstructure.runReefScoreGoal(() -> ReefState.L1), + Commands.sequence( + Commands.waitSeconds(0.05), + Commands.either( + DriveCommands.inchMovement(drive, -1, 0.1), + DriveCommands.inchMovement(drive, 1, 0.1), + () -> RobotState.getOIData().currentReefPost() == ReefPose.LEFT)))); + } + + /** + * Creates a command sequence to score coral at L1, waiting for auto-alignment. + * + * @param drive The drive subsystem. + * @param superstructure The superstructure subsystem. + * @return A command sequence to score coral at L1. + */ + public static final Command autoScoreL1CoralSequence( + Drive drive, + ElevatorFSM elevator, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + return Commands.sequence( + DriveCommands.autoAlignReefCoral(drive, cameras), scoreL1Coral(drive, superstructure)); + } + + /** + * Creates a command sequence to score coral, waiting for auto-alignment. + * + * @param elevator The elevator subsystem. + * @param superstructure The superstructure subsystem. + * @param autoAligned A supplier that returns true when the robot is aligned. + * @return A command sequence to score coral. + */ + public static final Command scoreCoralSequence( + ElevatorFSM elevator, + V2_RedundancySuperstructure superstructure, + BooleanSupplier autoAligned) { + return Commands.sequence( + Commands.either( + superstructure.runGoal(V2_RedundancySuperstructureStates.L3), + superstructure.runReefGoal(() -> RobotState.getOIData().currentReefHeight()), + () -> + RobotState.getOIData().currentReefHeight().equals(ReefState.L4) + && !superstructure + .getCurrentState() + .equals(V2_RedundancySuperstructureStates.L4)), + Commands.waitUntil(() -> autoAligned.getAsBoolean()), + superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight()), + superstructure + .runGoal(V2_RedundancySuperstructureStates.STOW_DOWN) + .onlyIf( + () -> + elevator.getPosition().equals(ElevatorPositions.L3) + || elevator.getPosition().equals(ElevatorPositions.L2))); + } + + /** + * Creates a command sequence to automatically score coral. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param superstructure The superstructure subsystem. + * @param cameras The vision cameras. + * @return A command sequence to auto-score coral. + */ + public static final Command autoScoreCoralSequence( + Drive drive, + ElevatorFSM elevator, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + return Commands.either( + Commands.sequence( + autoScoreL1CoralSequence(drive, elevator, superstructure, cameras), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)), + Commands.sequence( + Commands.either( + superstructure.runGoal(V2_RedundancySuperstructureStates.L2), + Commands.none(), + () -> + RobotState.getOIData().currentReefHeight().equals(ReefState.L1) + || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) + || RobotState.getOIData() + .currentReefHeight() + .equals(ReefState.CORAL_INTAKE)), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + scoreCoralSequence( + elevator, + superstructure, + () -> RobotState.getReefAlignData().atCoralSetpoint())), + superstructure + .l4PlusSequence() + .onlyIf(() -> RobotState.getOIData().currentReefHeight() == ReefState.L4)), + () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); + } + + /** + * Creates a command to intake algae from the reef. This uses the closest reef tag to + * automatically pick the reef height and reef face. + * + * @param drive The drive subsystem. + * @param superstructure The superstructure subsystem. + * @param cameras The vision cameras. + * @return A command to remove algae. + */ + public static final Command intakeAlgaeFromReefSequence( + Drive drive, + V2_RedundancySuperstructure superstructure, + Supplier level, + Camera... cameras) { + return Commands.sequence( + DriveCommands.autoAlignReefAlgae(drive, cameras), + superstructure.runGoalUntil( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V2_RedundancySuperstructureStates.INTAKE_REEF_L3; + case ALGAE_INTAKE_BOTTOM: + return V2_RedundancySuperstructureStates.INTAKE_REEF_L2; + default: + return V2_RedundancySuperstructureStates.STOW_DOWN; + } + }, + () -> RobotState.isHasAlgae()), + Commands.parallel( + Commands.sequence( + Commands.waitSeconds(0.25), + Commands.either( + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_UP), + superstructure.runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V2_RedundancySuperstructureStates.REEF_ACQUISITION_L3; + default: + return V2_RedundancySuperstructureStates.REEF_ACQUISITION_L2; + } + }), + () -> RobotState.isHasAlgae())), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) + .withTimeout(0.5))); + } + + /** + * Creates a command to drop algae from the reef. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param intake The intake subsystem. + * @param superstructure The superstructure subsystem. + * @param level A supplier that provides the current reef level. + * @param cameras The vision cameras. + * @return A command to drop algae from the reef. + */ + public static final Command dropAlgae( + Drive drive, + ElevatorFSM elevator, + V2_RedundancyManipulator manipulator, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Supplier level, + Camera... cameras) { + return Commands.sequence( + DriveCommands.autoAlignReefAlgae(drive, cameras), + Commands.sequence( + superstructure + .runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V2_RedundancySuperstructureStates.INTAKE_REEF_L3; + case ALGAE_INTAKE_BOTTOM: + return V2_RedundancySuperstructureStates.INTAKE_REEF_L2; + default: + return V2_RedundancySuperstructureStates.STOW_DOWN; + } + }) + .until(() -> RobotState.isHasAlgae()), + Commands.waitSeconds(2.0), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) + .withTimeout(0.5)), + superstructure.runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V2_RedundancySuperstructureStates.DROP_REEF_L3; + case ALGAE_INTAKE_BOTTOM: + return V2_RedundancySuperstructureStates.DROP_REEF_L2; + default: + return V2_RedundancySuperstructureStates.STOW_DOWN; + } + }), + Commands.waitSeconds(1.0), + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); + } + + /** + * Creates a command sequence for the floor intake of algae. + * + * @param superstructure The superstructure subsystem. + * @return A command sequence for the floor intake. + */ + public static final Command floorIntakeSequence(V2_RedundancySuperstructure superstructure) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoalUntil( + V2_RedundancySuperstructureStates.INTAKE_FLOOR, () -> RobotState.isHasAlgae())); + } + + /** + * Creates a command that posts the floor intake sequence, which can either go up or down based + * on whether the robot has algae. + * + * @param superstructure The superstructure subsystem. + * @return A command that posts the floor intake sequence. + */ + public static final Command postFloorIntakeSequence( + V2_RedundancySuperstructure superstructure) { + return Commands.either( + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_UP), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN), + RobotState::isHasAlgae); + } + + /** + * Creates a command to set the dynamic reef height in the robot state. This sets the height and + * then moves the superstructure to that position. + * + * @param height The reef height to set. + * @param superstructure The superstructure subsystem. + * @return A command to set the dynamic reef height. + */ + public static final Command setDynamicReefHeight( + ReefState height, V2_RedundancySuperstructure superstructure) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setReefHeight(height)), superstructure.setPosition()); + } + + /** + * Creates a command to climb the robot. + * + * @param superstructure The superstructure subsystem. + * @param climber The climber subsystem. + * @param drive The drive subsystem. + * @return A command to climb. + */ + public static final Command climb( + V2_RedundancySuperstructure superstructure, Climber climber, Drive drive) { + return Commands.sequence( + superstructure.runGoal(V2_RedundancySuperstructureStates.CLIMB), + Commands.parallel( + climber.releaseClimber(), + Commands.waitSeconds( + ClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), + Commands.waitUntil(climber::climberReady), + Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); + } } /** - * Creates a command to intake algae from the reef. This uses the closest reef tag to - * automatically pick the reef height and reef face. + * Creates a command sequence for homing all subsystems in the V2_Redundancy robot. * - * @param drive The drive subsystem. - * @param superstructure The superstructure subsystem. - * @param cameras The vision cameras. - * @return A command to remove algae. - */ - public static final Command intakeAlgaeFromReefSequence( - Drive drive, - V2_RedundancySuperstructure superstructure, - Supplier level, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefAlgae(drive, cameras), - superstructure.runGoalUntil( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V2_RedundancySuperstructureStates.INTAKE_REEF_L3; - case ALGAE_INTAKE_BOTTOM: - return V2_RedundancySuperstructureStates.INTAKE_REEF_L2; - default: - return V2_RedundancySuperstructureStates.STOW_DOWN; - } - }, - () -> RobotState.isHasAlgae()), - Commands.parallel( - Commands.sequence( - Commands.waitSeconds(0.25), - Commands.either( - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_UP), - superstructure.runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V2_RedundancySuperstructureStates.REEF_ACQUISITION_L3; - default: - return V2_RedundancySuperstructureStates.REEF_ACQUISITION_L2; - } - }), - () -> RobotState.isHasAlgae())), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) - .withTimeout(0.5))); - } - - /** - * Creates a command to drop algae from the reef. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. - * @param superstructure The superstructure subsystem. - * @param level A supplier that provides the current reef level. - * @param cameras The vision cameras. - * @return A command to drop algae from the reef. - */ - public static final Command dropAlgae( - Drive drive, - ElevatorFSM elevator, - V2_RedundancyManipulator manipulator, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Supplier level, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefAlgae(drive, cameras), - Commands.sequence( - superstructure - .runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V2_RedundancySuperstructureStates.INTAKE_REEF_L3; - case ALGAE_INTAKE_BOTTOM: - return V2_RedundancySuperstructureStates.INTAKE_REEF_L2; - default: - return V2_RedundancySuperstructureStates.STOW_DOWN; - } - }) - .until(() -> RobotState.isHasAlgae()), - Commands.waitSeconds(2.0), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) - .withTimeout(0.5)), - superstructure.runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V2_RedundancySuperstructureStates.DROP_REEF_L3; - case ALGAE_INTAKE_BOTTOM: - return V2_RedundancySuperstructureStates.DROP_REEF_L2; - default: - return V2_RedundancySuperstructureStates.STOW_DOWN; - } - }), - Commands.waitSeconds(1.0), - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); - } - - /** - * Creates a command sequence for the floor intake of algae. - * - * @param superstructure The superstructure subsystem. - * @return A command sequence for the floor intake. - */ - public static final Command floorIntakeSequence(V2_RedundancySuperstructure superstructure) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoalUntil( - V2_RedundancySuperstructureStates.INTAKE_FLOOR, () -> RobotState.isHasAlgae())); - } - - /** - * Creates a command that posts the floor intake sequence, which can either go up or down based - * on whether the robot has algae. - * - * @param superstructure The superstructure subsystem. - * @return A command that posts the floor intake sequence. - */ - public static final Command postFloorIntakeSequence( - V2_RedundancySuperstructure superstructure) { - return Commands.either( - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_UP), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN), - RobotState::isHasAlgae); - } - - /** - * Creates a command to set the dynamic reef height in the robot state. This sets the height and - * then moves the superstructure to that position. - * - * @param height The reef height to set. - * @param superstructure The superstructure subsystem. - * @return A command to set the dynamic reef height. + * @param intake The intake subsystem. + * @param elevator The elevator subsystem. + * @return A command sequence to home all subsystems. */ - public static final Command setDynamicReefHeight( - ReefState height, V2_RedundancySuperstructure superstructure) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setReefHeight(height)), superstructure.setPosition()); - } - - /** - * Creates a command to climb the robot. - * - * @param superstructure The superstructure subsystem. - * @param climber The climber subsystem. - * @param drive The drive subsystem. - * @return A command to climb. - */ - public static final Command climb( - V2_RedundancySuperstructure superstructure, Climber climber, Drive drive) { - return Commands.sequence( - superstructure.runGoal(V2_RedundancySuperstructureStates.CLIMB), - Commands.parallel( - climber.releaseClimber(), - Commands.waitSeconds( - ClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), - Commands.waitUntil(climber::climberReady), - Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); - } - } - - /** - * Creates a command sequence for homing all subsystems in the V2_Redundancy robot. - * - * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. - * @param elevator The elevator subsystem. - * @return A command sequence to home all subsystems. - */ - public static final Command homingSequences( - V2_RedundancyManipulator manipulator, V2_RedundancyIntake intake, ElevatorFSM elevator) { - return Commands.sequence( - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.ALGAE_MID)), - elevator.waitUntilAtGoal(), - manipulator.homingSequence(), - intake.homingSequence(), - Commands.runOnce(() -> elevator.setPosition())); - } - - public static final class V3_EpsilonCompositeCommands { - - public static final Command intakeCoralDriverSequence( - V3_EpsilonSuperstructure superstructure, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoralLoose()), - superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.HANDOFF, () -> intake.hasCoralLocked()), - postIntakeCoralSequence(superstructure, intake, manipulator)); - } - - public static final Command postIntakeCoralSequence( - V3_EpsilonSuperstructure superstructure, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - return Commands.either( - Commands.either( - Commands.sequence( - superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.HANDOFF_SPIN, () -> manipulator.hasCoral()), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), - Commands.none(), - () -> - !superstructure.getTargetState().equals(V3_EpsilonSuperstructureStates.STOW_UP) - && !superstructure - .getCurrentState() - .equals(V3_EpsilonSuperstructureStates.STOW_UP)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L1), - () -> !RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); - } - - /** - * Creates a command to automatically align the robot to the optimal side of the coral based on - * the current reef height and the robot's orientation. This command sets the score side in the - * RobotState and then runs the auto-alignment command. After the command ends, it resets the - * score side to center. - * - * @param drive The drive subsystem. - * @return A command to auto-align to the optimal side of the coral. - */ - public static final Command optimalAutoScoreCoralSequence( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { - return Commands.either( - Commands.sequence( - superstructure.setPosition(), - DriveCommands.autoAlignReefCoral(drive, cameras) - .until(() -> RobotState.getReefAlignData().atCoralSetpoint()), - superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight())), - superstructure.runGoalUntil(V3_EpsilonSuperstructureStates.L1_SCORE, () -> false), - () -> !RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); - } - - public static final Command optimalAutoScoreCoralSequence( - Drive drive, V3_EpsilonSuperstructure superstructure, ReefState height, Camera... cameras) { - return Commands.sequence( - superstructure.runReefGoal(() -> height), - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), - superstructure - .runReefScoreGoal(() -> height) - .until( - () -> { - if (height.equals(ReefState.L4)) return superstructure.armBelowThreshold(); - else return false; - })); - } - - public static final Command optimalAutoAlignReefAlgae( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { - return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), - DriveCommands.autoAlignReefAlgae(drive, cameras)); - } - - public static final Command optimalScoreBarge(V3_EpsilonSuperstructure superstructure) { - return superstructure - .runGoal(V3_EpsilonSuperstructureStates.BARGE_SCORE) - .andThen( - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.BARGE_SCORE, 1)); - } - - /** - * Creates a command to score coral. - * - * @param superstructure The superstructure subsystem. - * @param goal This is the goal. - * @return A command to score coral. - */ - public static final Command scoreCoral( - V3_EpsilonSuperstructure superstructure, Supplier goal) { - return superstructure.runReefScoreGoal(goal); - } - - /** - * public static final Command intakeAlgaeReef(V3_EpsilonSuperstructure superstructure, - * V3_EpsilonSuperstructureStates goal, V3_EpsilonSuperstructureAction action, V3_EpsilonIntake - * intake, V3_EpsilonSuperstructure hasalgae) { return Commands.sequence( - * superstructure.runGoal(), Commands.run(() -> action.runIntake(intake)), - * superstructure.isHasAlgae() == (edge.getGamePieceEdge() != (GamePieceEdge.NO_ALGAE) ); ); } - */ - - /** - * drive to reef go to algae level (L2 or L3) turn intake on go until it has algae then stow up - */ - public static final Command dropAlgae( - Drive drive, - ElevatorFSM elevator, - V3_EpsilonManipulator manipulator, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Supplier level, - Camera... cameras) { - return Commands.sequence( - Commands.parallel( - superstructure.runGoalUntil( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }, - () -> RobotState.isHasAlgae()), - DriveCommands.autoAlignReefAlgae(drive, cameras)), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, 2.0, 0.0)), () -> drive.stop()) - .withTimeout(0.5), - superstructure.runActionWithTimeout( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE_DROP; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; - default: - return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; - } - }, - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE_DROP; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; - default: - return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; - } - }, - () -> 2)) - .finallyDo( - () -> { - RobotState.setHasAlgae(false); - }); - } - - public static final Command intakeAlgaeFromReef( - Drive drive, - V3_EpsilonSuperstructure superstructure, - Supplier level, - Camera... cameras) { - - return Commands.sequence( - Commands.parallel( - superstructure.runGoalUntil( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }, - () -> RobotState.isHasAlgae()), - DriveCommands.autoAlignReefAlgae(drive, cameras)), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, 2.0, 0.0)), () -> drive.stop()) - .withTimeout(0.5), - postIntakeAlgaeFromReef(drive, superstructure, cameras)); - } - - public static final Command intakeAlgaeFromReefAuto( - Drive drive, - V3_EpsilonSuperstructure superstructure, - Supplier level, - Camera... cameras) { - - return Commands.sequence( - Commands.parallel( - superstructure.runGoalUntil( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }, - () -> RobotState.isHasAlgae()), - DriveCommands.autoAlignReefAlgae(drive, cameras)), - postIntakeAlgaeFromReef(drive, superstructure, cameras)); - } - - public static final Command postIntakeAlgaeFromReef( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { - return superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP); - } - - public static final Command intakeAlgaeFromReef( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { - return intakeAlgaeFromReef( - drive, superstructure, () -> RobotState.getReefAlignData().algaeIntakeHeight(), cameras); - } - - public static final Command intakeAlgaeFromReefAuto( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { - return intakeAlgaeFromReefAuto( - drive, superstructure, () -> RobotState.getReefAlignData().algaeIntakeHeight(), cameras); - } - - public static final Command emergencyEject( - V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { - return Commands.sequence( - superstructure.override( - () -> { - manipulator.setArmGoal( - frc.robot - .subsystems - .v3_Epsilon - .superstructure - .manipulator - .V3_EpsilonManipulatorConstants - .ManipulatorArmState - .EMERGENCY_EJECT_ANGLE); - manipulator.setRollerGoal( - frc.robot - .subsystems - .v3_Epsilon - .superstructure - .manipulator - .V3_EpsilonManipulatorConstants - .ManipulatorRollerState - .L4_SCORE); - })); - } - - public static final Command intakeAlgaeFloor( - V3_EpsilonSuperstructure superstructure, V3_EpsilonManipulator manipulator) { - return superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) - .until(() -> manipulator.hasAlgae()); // add intake for algae after - } - - public static final Command handoffCoral( - V3_EpsilonSuperstructure superstructure, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF), - Commands.waitUntil(() -> manipulator.hasCoral()), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)); - } - - public static final Command manipulatorGroundIntake( - V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { - return Commands.sequence( - Commands.runOnce( - () -> superstructure.runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE)), - Commands.runOnce(() -> manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE))); - } - - public static final Command setDynamicReefHeight( - ReefState height, V3_EpsilonSuperstructure superstructure) { - return Commands.either( - Commands.sequence( - Commands.runOnce(() -> RobotState.setReefHeight(height)), - superstructure.setPosition()), - Commands.none(), - () -> - Set.of( - V3_EpsilonSuperstructureStates.L2, - V3_EpsilonSuperstructureStates.L3, - V3_EpsilonSuperstructureStates.L4) - .contains(superstructure.getCurrentState())); + public static final Command homingSequences( + V2_RedundancyManipulator manipulator, V2_RedundancyIntake intake, ElevatorFSM elevator) { + return Commands.sequence( + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.ALGAE_MID)), + elevator.waitUntilAtGoal(), + manipulator.homingSequence(), + intake.homingSequence(), + Commands.runOnce(() -> elevator.setPosition())); + } + + public static final class V3_EpsilonCompositeCommands { + + public static final Command intakeCoralDriverSequence( + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoalUntil( + V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoralLoose()), + superstructure.runGoalUntil( + V3_EpsilonSuperstructureStates.HANDOFF, () -> intake.hasCoralLocked()), + postIntakeCoralSequence(superstructure, intake, manipulator)); + } + + public static final Command postIntakeCoralSequence( + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + return Commands.either( + Commands.either( + Commands.sequence( + superstructure.runGoalUntil( + V3_EpsilonSuperstructureStates.HANDOFF_SPIN, () -> manipulator.hasCoral()), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), + Commands.none(), + () -> + !superstructure.getTargetState().equals(V3_EpsilonSuperstructureStates.STOW_UP) + && !superstructure + .getCurrentState() + .equals(V3_EpsilonSuperstructureStates.STOW_UP)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L1), + () -> !RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); + } + + /** + * Creates a command to automatically align the robot to the optimal side of the coral based on + * the current reef height and the robot's orientation. This command sets the score side in the + * RobotState and then runs the auto-alignment command. After the command ends, it resets the + * score side to center. + * + * @param drive The drive subsystem. + * @return A command to auto-align to the optimal side of the coral. + */ + public static final Command optimalAutoScoreCoralSequence( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + return Commands.either( + Commands.sequence( + superstructure.setPosition(), + DriveCommands.autoAlignReefCoral(drive, cameras) + .until(() -> RobotState.getReefAlignData().atCoralSetpoint()), + superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight())), + superstructure.runGoalUntil(V3_EpsilonSuperstructureStates.L1_SCORE, () -> false), + () -> !RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); + } + + public static final Command optimalAutoScoreCoralSequence( + Drive drive, V3_EpsilonSuperstructure superstructure, ReefState height, Camera... cameras) { + return Commands.sequence( + superstructure.runReefGoal(() -> height), + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), + superstructure + .runReefScoreGoal(() -> height) + .until( + () -> { + if (height.equals(ReefState.L4)) return superstructure.armBelowThreshold(); + else return false; + })); + } + + public static final Command optimalAutoAlignReefAlgae( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), + DriveCommands.autoAlignReefAlgae(drive, cameras)); + } + + public static final Command optimalScoreBarge(V3_EpsilonSuperstructure superstructure) { + return superstructure + .runGoal(V3_EpsilonSuperstructureStates.BARGE_SCORE) + .andThen( + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.BARGE_SCORE, 1)); + } + + /** + * Creates a command to score coral. + * + * @param superstructure The superstructure subsystem. + * @param goal This is the goal. + * @return A command to score coral. + */ + public static final Command scoreCoral( + V3_EpsilonSuperstructure superstructure, Supplier goal) { + return superstructure.runReefScoreGoal(goal); + } + + /** + * public static final Command intakeAlgaeReef(V3_EpsilonSuperstructure superstructure, + * V3_EpsilonSuperstructureStates goal, V3_EpsilonSuperstructureAction action, V3_EpsilonIntake + * intake, V3_EpsilonSuperstructure hasalgae) { return Commands.sequence( + * superstructure.runGoal(), Commands.run(() -> action.runIntake(intake)), + * superstructure.isHasAlgae() == (edge.getGamePieceEdge() != (GamePieceEdge.NO_ALGAE) ); ); } + */ + + /** + * drive to reef go to algae level (L2 or L3) turn intake on go until it has algae then stow up + */ + public static final Command dropAlgae( + Drive drive, + ElevatorFSM elevator, + V3_EpsilonManipulator manipulator, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Supplier level, + Camera... cameras) { + return Commands.sequence( + Commands.parallel( + superstructure.runGoalUntil( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }, + () -> RobotState.isHasAlgae()), + DriveCommands.autoAlignReefAlgae(drive, cameras)), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, 2.0, 0.0)), () -> drive.stop()) + .withTimeout(0.5), + superstructure.runActionWithTimeout( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE_DROP; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + default: + return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + } + }, + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE_DROP; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + default: + return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + } + }, + () -> 2)) + .finallyDo( + () -> { + RobotState.setHasAlgae(false); + }); + } + + public static final Command intakeAlgaeFromReef( + Drive drive, + V3_EpsilonSuperstructure superstructure, + Supplier level, + Camera... cameras) { + + return Commands.sequence( + Commands.sequence( + superstructure.runGoalUntil( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }, + () -> RobotState.isHasAlgae()), + DriveCommands.autoAlignReefAlgae(drive, cameras)), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, 2.0, 0.0)), () -> drive.stop()) + .withTimeout(0.5), + postIntakeAlgaeFromReef(drive, superstructure, cameras)); + } + + public static final Command intakeAlgaeFromReefAuto( + Drive drive, + V3_EpsilonSuperstructure superstructure, + Supplier level, + Camera... cameras) { + + return Commands.sequence( + Commands.parallel( + superstructure.runGoalUntil( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }, + () -> RobotState.isHasAlgae()), + DriveCommands.autoAlignReefAlgae(drive, cameras)), + postIntakeAlgaeFromReef(drive, superstructure, cameras)); + } + + public static final Command postIntakeAlgaeFromReef( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + return superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP); + } + + public static final Command intakeAlgaeFromReef( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + return intakeAlgaeFromReef( + drive, superstructure, () -> RobotState.getReefAlignData().algaeIntakeHeight(), cameras); + } + + public static final Command intakeAlgaeFromReefAuto( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + return intakeAlgaeFromReefAuto( + drive, superstructure, () -> RobotState.getReefAlignData().algaeIntakeHeight(), cameras); + } + + public static final Command emergencyEject( + V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { + return Commands.sequence( + superstructure.override( + () -> { + manipulator.setArmGoal( + frc.robot + .subsystems + .v3_Epsilon + .superstructure + .manipulator + .V3_EpsilonManipulatorConstants + .ManipulatorArmState + .EMERGENCY_EJECT_ANGLE); + manipulator.setRollerGoal( + frc.robot + .subsystems + .v3_Epsilon + .superstructure + .manipulator + .V3_EpsilonManipulatorConstants + .ManipulatorRollerState + .L4_SCORE); + })); + } + + public static final Command intakeAlgaeFloor( + V3_EpsilonSuperstructure superstructure, V3_EpsilonManipulator manipulator) { + return superstructure + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .until(() -> manipulator.hasAlgae()); // add intake for algae after + } + + public static final Command handoffCoral( + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF), + Commands.waitUntil(() -> manipulator.hasCoral()), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)); + } + + public static final Command manipulatorGroundIntake( + V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { + return Commands.sequence( + Commands.runOnce( + () -> superstructure.runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE)), + Commands.runOnce(() -> manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE))); + } + + public static final Command setDynamicReefHeight( + ReefState height, V3_EpsilonSuperstructure superstructure) { + return Commands.either( + Commands.sequence( + Commands.runOnce(() -> RobotState.setReefHeight(height)), + superstructure.setPosition()), + Commands.none(), + () -> + Set.of( + V3_EpsilonSuperstructureStates.L2, + V3_EpsilonSuperstructureStates.L3, + V3_EpsilonSuperstructureStates.L4) + .contains(superstructure.getCurrentState())); + } } - } } diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java index e0588912..684752c0 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java @@ -1,7 +1,5 @@ package frc.robot.subsystems.shared.elevator; -import static edu.wpi.first.units.Units.*; - import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; @@ -21,434 +19,445 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.util.ExternalLoggedTracer; import frc.robot.util.InternalLoggedTracer; -import java.util.function.BooleanSupplier; -import java.util.function.Supplier; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; -public class Elevator { - private final ElevatorIO io; - private final ElevatorIOInputsAutoLogged inputs; - - // --- MODIFIED: Store the goal primarily as a double for flexibility --- - private double positionGoalMeters; - private ElevatorPositions lastKnownPositionEnum; // Keep track of the last named position - private boolean isClosedLoop; - - public Elevator(ElevatorIO io) { - this.io = io; - this.inputs = new ElevatorIOInputsAutoLogged(); - - // Initialize to STOW position - this.lastKnownPositionEnum = ElevatorPositions.STOW; - this.positionGoalMeters = lastKnownPositionEnum.getPosition(); - isClosedLoop = true; - } - - private void periodic() { - InternalLoggedTracer.reset(); - io.updateInputs(inputs); - InternalLoggedTracer.record("Update Inputs", "Elevator/Periodic"); - - InternalLoggedTracer.reset(); - Logger.processInputs("Elevator", inputs); - InternalLoggedTracer.record("Process Inputs", "Elevator/Periodic"); - - Logger.recordOutput( - "Elevator/Position", - lastKnownPositionEnum != null ? lastKnownPositionEnum.name() : "CUSTOM"); - - InternalLoggedTracer.reset(); - if (isClosedLoop) { - // Always use the double goal for the IO layer - io.setPositionGoal(positionGoalMeters); - } - InternalLoggedTracer.record("Set Position Goal", "Elevator/Periodic"); - } - - /** - * Gets the elevator position enum for a given reef state. - * - * @param newPosition The reef state. - * @return The corresponding elevator position. - */ - private ElevatorPositions getPosition(ReefState newPosition) { - return ElevatorConstants.REEF_STATE_ELEVATOR_POSITION_MAP.get(newPosition); - } - - /** - * Gets the current position of the elevator. - * - * @return The current elevator position. - */ - private double getPositionMeters(ElevatorIOInputs inputs) { - return inputs.positionMeters; - } - - /** - * Gets the feedforward characterization velocity. - * - * @return The feedforward characterization velocity. - */ - private double getFFCharacterizationVelocity(ElevatorIOInputs inputs) { - return inputs.velocityMetersPerSecond - * ElevatorConstants.ELEVATOR_GEAR_RATIO - / (2 * Math.PI * ElevatorConstants.DRUM_RADIUS); - } - - /** - * Sets the control gains for the elevator. - * - * @param kP The proportional gain. - * @param kD The derivative gain. - * @param kS The static gain. - * @param kV The velocity gain. - * @param kA The acceleration gain. - * @param kG The gravity gain. - */ - private void setGains(double kP, double kD, double kS, double kV, double kA, double kG) { - io.updateGains(kP, kD, kS, kV, kA, kG); - } - - /** - * Sets the motion constraints for the elevator. - * - * @param maxAcceleration The maximum acceleration. - * @param cruisingVelocity The cruising velocity. - */ - private void setConstraints(double maxAcceleration, double cruisingVelocity) { - io.updateConstraints(maxAcceleration, cruisingVelocity); - } - - /** - * Checks if the elevator is at the goal position within a specified tolerance. - * - * @param position The target position in meters. - * @return true if the current position is within the goal tolerance of the target position, false - * otherwise. - */ - private boolean atGoal(double position) { - return Math.abs(position - inputs.positionMeters) - <= ElevatorConstants.CONSTRAINTS.goalToleranceMeters().get(); - } - - /** - * Checks if the elevator is at the goal position. - * - * @return True if the elevator is at the goal position, false otherwise. - */ - @AutoLogOutput(key = "Elevator/At Goal") - private boolean atGoal() { - return Math.abs(positionGoalMeters - inputs.positionMeters) - <= ElevatorConstants.CONSTRAINTS.goalToleranceMeters().get(); - } - - /** - * Checks if the elevator is at the goal position. - * - * @return True if the elevator is at the goal position, false otherwise. - */ - @AutoLogOutput(key = "Elevator/At Goal") - private boolean atGoal(ElevatorPositions position) { - return Math.abs(position.getPosition() - inputs.positionMeters) - <= ElevatorConstants.CONSTRAINTS.goalToleranceMeters().get(); - } - - /** - * Waits until the elevator is at the goal position. - * - * @return A command that waits until the elevator is at the goal position. - */ - private Command waitUntilAtGoal() { - return Commands.waitSeconds(0.02).andThen(Commands.waitUntil(() -> atGoal())); - } - - /** - * Checks if the elevator is within a fast scoring tolerance of the goal position. - * - * @return A BooleanSupplier that returns true if the elevator is within the fast scoring - * tolerance, false otherwise. - */ - private BooleanSupplier inFastScoringTolerance() { - return () -> Math.abs(inputs.positionMeters - positionGoalMeters) <= 0.03; - } - - /** - * Runs the SysId routine for the elevator subsystem. - * - * @param subsystem The subsystem to run the SysId routine on. - * @return A command that runs the SysId routine. - */ - private Command sysIdRoutine(Subsystem subsystem) { - - SysIdRoutine characterizationRoutine = - new SysIdRoutine( - new SysIdRoutine.Config( - Volts.of(1).per(Second), - Volts.of(3), - Seconds.of(3), - (state) -> Logger.recordOutput("Elevator/SysID State", state.toString())), - new SysIdRoutine.Mechanism((volts) -> io.setVoltage(volts.in(Volts)), null, subsystem)); - - return Commands.sequence( - Commands.runOnce( - () -> { - isClosedLoop = false; - }), - characterizationRoutine - .quasistatic(Direction.kForward) - .until( - () -> - Elevator.this.atGoal( - ElevatorPositions.L4.getPosition() - Units.inchesToMeters(12.0))), - characterizationRoutine - .quasistatic(Direction.kReverse) - .until( - () -> - Elevator.this.atGoal( - ElevatorPositions.STOW.getPosition() + Units.inchesToMeters(12.0))), - characterizationRoutine - .dynamic(Direction.kForward) - .until( - () -> - Elevator.this.atGoal( - ElevatorPositions.L4.getPosition() - Units.inchesToMeters(12.0))), - characterizationRoutine - .dynamic(Direction.kReverse) - .until( - () -> - Elevator.this.atGoal( - ElevatorPositions.STOW.getPosition() + Units.inchesToMeters(12.0))), - subsystem.runOnce(() -> setPositionFromReef(() -> ReefState.STOW))); - } - - /** Private method to set position based on ReefState. */ - private void setPositionFromReef(Supplier newPosition) { - isClosedLoop = true; - this.lastKnownPositionEnum = getPosition(newPosition.get()); - this.positionGoalMeters = this.lastKnownPositionEnum.getPosition(); - } - - /** Private method to set position based on ElevatorPositions enum. */ - private void setPositionFromEnum(ElevatorPositions newPosition) { - isClosedLoop = true; - this.lastKnownPositionEnum = newPosition; - this.positionGoalMeters = this.lastKnownPositionEnum.getPosition(); - } - - /** Private method to set position based on a double value. */ - private void setPositionFromDouble(double newPositionMeters) { - isClosedLoop = true; - this.positionGoalMeters = newPositionMeters; - // When a raw double is commanded, there's no corresponding enum state. - this.lastKnownPositionEnum = null; - } - - public class ElevatorCSB extends SubsystemBase { - - @Override - public void periodic() { - ExternalLoggedTracer.reset(); - Elevator.this.periodic(); - ExternalLoggedTracer.record("Elevator Total", "Elevator/Periodic"); - } - - public ElevatorPositions getPosition() { - return Elevator.this.lastKnownPositionEnum; - } - - /** - * Creates a command to set the elevator to a pre-defined position. - * - * @param newPosition The target ElevatorPositions enum. - * @return A command that sets the elevator position. - */ - public Command setPosition(ElevatorPositions newPosition) { - return this.runOnce(() -> Elevator.this.setPositionFromEnum(newPosition)); - } - - /** - * Creates a command to set the elevator to a specific height in meters. - * - * @param newPositionMeters The target height in meters. - * @return A command that sets the elevator position. - */ - public Command setPosition(double newPositionMeters) { - return this.runOnce(() -> Elevator.this.setPositionFromDouble(newPositionMeters)); - } - - public Command setPosition(Supplier newPosition) { - return this.runOnce(() -> Elevator.this.setPositionFromReef(newPosition)); - } - - public Command setPosition() { - return Commands.runOnce( - () -> - Elevator.this.setPositionFromReef(() -> RobotState.getOIData().currentReefHeight())); - } - - public Command setVoltage(double volts) { - return this.runEnd( - () -> { - isClosedLoop = false; - io.setVoltage(volts); - }, - () -> io.setVoltage(0.0)); - } - - public Command resetPosition() { - return runOnce(() -> Elevator.this.lastKnownPositionEnum = ElevatorPositions.STOW) - .andThen( - runOnce( - () -> io.setPosition(ElevatorConstants.ELEVATOR_PARAMETERS.MIN_HEIGHT_METERS()))); - } - - public Command sysIdRoutine() { - return Elevator.this.sysIdRoutine(this); - } +import java.util.function.BooleanSupplier; +import java.util.function.Supplier; - public double getPositionMeters() { - return Elevator.this.getPositionMeters(inputs); - } +import static edu.wpi.first.units.Units.*; +import static frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions.L4; - public double getFFCharacterizationVelocity() { - return Elevator.this.getFFCharacterizationVelocity(inputs); - } +public class Elevator { + private final ElevatorIO io; + private final ElevatorIOInputsAutoLogged inputs; - public void setGains(double kP, double kD, double kS, double kV, double kA, double kG) { - Elevator.this.setGains(kP, kD, kS, kV, kA, kG); - } + // --- MODIFIED: Store the goal primarily as a double for flexibility --- + private double positionGoalMeters; + private ElevatorPositions lastKnownPositionEnum; // Keep track of the last named position + private boolean isClosedLoop; - public void setConstraints(double maxAcceleration, double cruisingVelocity) { - Elevator.this.setConstraints(maxAcceleration, cruisingVelocity); - } + public Elevator(ElevatorIO io) { + this.io = io; + this.inputs = new ElevatorIOInputsAutoLogged(); - public boolean atGoal() { - return Elevator.this.atGoal(); + // Initialize to STOW position + this.lastKnownPositionEnum = ElevatorPositions.STOW; + this.positionGoalMeters = lastKnownPositionEnum.getPosition(); + isClosedLoop = true; } - public Command waitUntilAtGoal() { - return Elevator.this.waitUntilAtGoal(); - } + private void periodic() { + InternalLoggedTracer.reset(); + io.updateInputs(inputs); + InternalLoggedTracer.record("Update Inputs", "Elevator/Periodic"); - public BooleanSupplier inFastScoringTolerance() { - return Elevator.this.inFastScoringTolerance(); - } - } - - // FSM for the Elevator - public class ElevatorFSM { - @AutoLogOutput(key = "Elevator/Past Barge Threshold") - public boolean pastBargeThresholdgetPositionMeters() { - if (Constants.getMode() == Mode.REAL) return inputs.velocityMetersPerSecond > 2.75; - else { - return inputs.positionMeters > .95; - } - } + InternalLoggedTracer.reset(); + Logger.processInputs("Elevator", inputs); + InternalLoggedTracer.record("Process Inputs", "Elevator/Periodic"); - public void periodic() { - ExternalLoggedTracer.reset(); - Elevator.this.periodic(); - ExternalLoggedTracer.record("Elevator Total", "Elevator/Periodic"); - } + Logger.recordOutput( + "Elevator/Position", + lastKnownPositionEnum != null ? lastKnownPositionEnum.name() : "CUSTOM"); - public ElevatorPositions getPosition() { - return Elevator.this.lastKnownPositionEnum; + InternalLoggedTracer.reset(); + if (isClosedLoop) { + // Always use the double goal for the IO layer + io.setPositionGoal(positionGoalMeters); + } + InternalLoggedTracer.record("Set Position Goal", "Elevator/Periodic"); } /** - * Sets the elevator to a pre-defined position. + * Gets the elevator position enum for a given reef state. * - * @param newPosition The target ElevatorPositions enum. + * @param newPosition The reef state. + * @return The corresponding elevator position. */ - public void setPosition(ElevatorPositions newPosition) { - Elevator.this.setPositionFromEnum(newPosition); + private ElevatorPositions getPosition(ReefState newPosition) { + return ElevatorConstants.REEF_STATE_ELEVATOR_POSITION_MAP.get(newPosition); } /** - * Sets the elevator to a specific height in meters. + * Gets the current position of the elevator. * - * @param newPositionMeters The target height in meters. + * @return The current elevator position. */ - public void setPosition(double newPositionMeters) { - Elevator.this.setPositionFromDouble(newPositionMeters); - } - - public void setPosition(Supplier newPosition) { - Elevator.this.setPositionFromReef(newPosition); - } - - public void setPosition() { - Elevator.this.setPositionFromReef(() -> RobotState.getOIData().currentReefHeight()); + private double getPositionMeters(ElevatorIOInputs inputs) { + return inputs.positionMeters; } - public Command resetPosition() { - return Commands.runOnce(() -> Elevator.this.lastKnownPositionEnum = ElevatorPositions.STOW) - .andThen( - Commands.runOnce( - () -> io.setPosition(ElevatorConstants.ELEVATOR_PARAMETERS.MIN_HEIGHT_METERS()))); - } - - public Command sysIdRoutine(V2_RedundancySuperstructure superstructure) { - - return Commands.sequence( - superstructure.runGoal(V2_RedundancySuperstructureStates.OVERRIDE), - Elevator.this.sysIdRoutine(superstructure)); + /** + * Gets the feedforward characterization velocity. + * + * @return The feedforward characterization velocity. + */ + private double getFFCharacterizationVelocity(ElevatorIOInputs inputs) { + return inputs.velocityMetersPerSecond + * ElevatorConstants.ELEVATOR_GEAR_RATIO + / (2 * Math.PI * ElevatorConstants.DRUM_RADIUS); } - public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { - - return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), - Elevator.this.sysIdRoutine(superstructure)); + /** + * Sets the control gains for the elevator. + * + * @param kP The proportional gain. + * @param kD The derivative gain. + * @param kS The static gain. + * @param kV The velocity gain. + * @param kA The acceleration gain. + * @param kG The gravity gain. + */ + private void setGains(double kP, double kD, double kS, double kV, double kA, double kG) { + io.updateGains(kP, kD, kS, kV, kA, kG); } - public double getPositionMeters() { - return Elevator.this.getPositionMeters(inputs); + /** + * Sets the motion constraints for the elevator. + * + * @param maxAcceleration The maximum acceleration. + * @param cruisingVelocity The cruising velocity. + */ + private void setConstraints(double maxAcceleration, double cruisingVelocity) { + io.updateConstraints(maxAcceleration, cruisingVelocity); } - public double getFFCharacterizationVelocity() { - return Elevator.this.getFFCharacterizationVelocity(inputs); + /** + * Checks if the elevator is at the goal position within a specified tolerance. + * + * @param position The target position in meters. + * @return true if the current position is within the goal tolerance of the target position, false + * otherwise. + */ + private boolean atGoal(double position) { + return Math.abs(position - inputs.positionMeters) + <= ElevatorConstants.CONSTRAINTS.goalToleranceMeters().get(); } - public void setGains(double kP, double kD, double kS, double kV, double kA, double kG) { - Elevator.this.setGains(kP, kD, kS, kV, kA, kG); + /** + * Checks if the elevator is at the goal position. + * + * @return True if the elevator is at the goal position, false otherwise. + */ + @AutoLogOutput(key = "Elevator/At Goal") + private boolean atGoal() { + return Math.abs(positionGoalMeters - inputs.positionMeters) + <= ElevatorConstants.CONSTRAINTS.goalToleranceMeters().get(); } - public void setConstraints(double maxAcceleration, double cruisingVelocity) { - Elevator.this.setConstraints(maxAcceleration, cruisingVelocity); + /** + * Checks if the elevator is at the goal position. + * + * @return True if the elevator is at the goal position, false otherwise. + */ + @AutoLogOutput(key = "Elevator/At Goal") + private boolean atGoal(ElevatorPositions position) { + return Math.abs(position.getPosition() - inputs.positionMeters) + <= ElevatorConstants.CONSTRAINTS.goalToleranceMeters().get(); } - public boolean atGoal() { - return Elevator.this.atGoal(); + /** + * Waits until the elevator is at the goal position. + * + * @return A command that waits until the elevator is at the goal position. + */ + private Command waitUntilAtGoal() { + return Commands.waitSeconds(0.02).andThen(Commands.waitUntil(() -> atGoal())); } - public boolean atGoal(ReefState position) { - return Elevator.this.atGoal(Elevator.this.getPosition(position)); + /** + * Checks if the elevator is within a fast scoring tolerance of the goal position. + * + * @return A BooleanSupplier that returns true if the elevator is within the fast scoring + * tolerance, false otherwise. + */ + private BooleanSupplier inFastScoringTolerance() { + return () -> Math.abs(inputs.positionMeters - positionGoalMeters) <= 0.03; } - public boolean inTolerance(double toleranceMeters) { - return Math.abs(positionGoalMeters - inputs.positionMeters) <= toleranceMeters; + /** + * Runs the SysId routine for the elevator subsystem. + * + * @param subsystem The subsystem to run the SysId routine on. + * @return A command that runs the SysId routine. + */ + private Command sysIdRoutine(Subsystem subsystem) { + + SysIdRoutine characterizationRoutine = + new SysIdRoutine( + new SysIdRoutine.Config( + Volts.of(1).per(Second), + Volts.of(3), + Seconds.of(3), + (state) -> Logger.recordOutput("Elevator/SysID State", state.toString())), + new SysIdRoutine.Mechanism((volts) -> io.setVoltage(volts.in(Volts)), null, subsystem)); + + return Commands.sequence( + Commands.runOnce( + () -> { + isClosedLoop = false; + }), + characterizationRoutine + .quasistatic(Direction.kForward) + .until( + () -> + Elevator.this.atGoal( + L4.getPosition() - Units.inchesToMeters(12.0))), + characterizationRoutine + .quasistatic(Direction.kReverse) + .until( + () -> + Elevator.this.atGoal( + ElevatorPositions.STOW.getPosition() + Units.inchesToMeters(12.0))), + characterizationRoutine + .dynamic(Direction.kForward) + .until( + () -> + Elevator.this.atGoal( + L4.getPosition() - Units.inchesToMeters(12.0))), + characterizationRoutine + .dynamic(Direction.kReverse) + .until( + () -> + Elevator.this.atGoal( + ElevatorPositions.STOW.getPosition() + Units.inchesToMeters(12.0))), + subsystem.runOnce(() -> setPositionFromReef(() -> ReefState.STOW))); } - public Command waitUntilAtGoal() { - return Elevator.this.waitUntilAtGoal(); + /** + * Private method to set position based on ReefState. + */ + private void setPositionFromReef(Supplier newPosition) { + isClosedLoop = true; + this.lastKnownPositionEnum = getPosition(newPosition.get()); + this.positionGoalMeters = this.lastKnownPositionEnum.getPosition(); } - public BooleanSupplier inFastScoringTolerance() { - return Elevator.this.inFastScoringTolerance(); + /** + * Private method to set position based on ElevatorPositions enum. + */ + private void setPositionFromEnum(ElevatorPositions newPosition) { + isClosedLoop = true; + this.lastKnownPositionEnum = newPosition; + this.positionGoalMeters = this.lastKnownPositionEnum.getPosition(); } - public double getVelocityMetersPerSecond() { - return inputs.velocityMetersPerSecond; + /** + * Private method to set position based on a double value. + */ + private void setPositionFromDouble(double newPositionMeters) { + isClosedLoop = true; + this.positionGoalMeters = newPositionMeters; + // When a raw double is commanded, there's no corresponding enum state. + this.lastKnownPositionEnum = null; + } + + public class ElevatorCSB extends SubsystemBase { + + @Override + public void periodic() { + ExternalLoggedTracer.reset(); + Elevator.this.periodic(); + ExternalLoggedTracer.record("Elevator Total", "Elevator/Periodic"); + } + + public ElevatorPositions getPosition() { + return Elevator.this.lastKnownPositionEnum; + } + + /** + * Creates a command to set the elevator to a pre-defined position. + * + * @param newPosition The target ElevatorPositions enum. + * @return A command that sets the elevator position. + */ + public Command setPosition(ElevatorPositions newPosition) { + return this.runOnce(() -> Elevator.this.setPositionFromEnum(newPosition)); + } + + /** + * Creates a command to set the elevator to a specific height in meters. + * + * @param newPositionMeters The target height in meters. + * @return A command that sets the elevator position. + */ + public Command setPosition(double newPositionMeters) { + return this.runOnce(() -> Elevator.this.setPositionFromDouble(newPositionMeters)); + } + + public Command setPosition(Supplier newPosition) { + return this.runOnce(() -> Elevator.this.setPositionFromReef(newPosition)); + } + + public Command setPosition() { + return Commands.runOnce( + () -> + Elevator.this.setPositionFromReef(() -> RobotState.getOIData().currentReefHeight())); + } + + public Command setVoltage(double volts) { + return this.runEnd( + () -> { + isClosedLoop = false; + io.setVoltage(volts); + }, + () -> io.setVoltage(0.0)); + } + + public Command resetPosition() { + return runOnce(() -> Elevator.this.lastKnownPositionEnum = ElevatorPositions.STOW) + .andThen( + runOnce( + () -> io.setPosition(ElevatorConstants.ELEVATOR_PARAMETERS.MIN_HEIGHT_METERS()))); + } + + public Command sysIdRoutine() { + return Elevator.this.sysIdRoutine(this); + } + + public double getPositionMeters() { + return Elevator.this.getPositionMeters(inputs); + } + + public double getFFCharacterizationVelocity() { + return Elevator.this.getFFCharacterizationVelocity(inputs); + } + + public void setGains(double kP, double kD, double kS, double kV, double kA, double kG) { + Elevator.this.setGains(kP, kD, kS, kV, kA, kG); + } + + public void setConstraints(double maxAcceleration, double cruisingVelocity) { + Elevator.this.setConstraints(maxAcceleration, cruisingVelocity); + } + + public boolean atGoal() { + return Elevator.this.atGoal(); + } + + public Command waitUntilAtGoal() { + return Elevator.this.waitUntilAtGoal(); + } + + public BooleanSupplier inFastScoringTolerance() { + return Elevator.this.inFastScoringTolerance(); + } + } + + // FSM for the Elevator + public class ElevatorFSM { + @AutoLogOutput(key = "Elevator/Past Barge Threshold") + public boolean pastBargeThresholdgetPositionMeters() { + if (Constants.getMode() == Mode.REAL) + return inputs.positionMeters >= L4.getPosition(); + else { + return inputs.positionMeters > .95; + } + } + + public void periodic() { + ExternalLoggedTracer.reset(); + Elevator.this.periodic(); + ExternalLoggedTracer.record("Elevator Total", "Elevator/Periodic"); + } + + public ElevatorPositions getPosition() { + return Elevator.this.lastKnownPositionEnum; + } + + /** + * Sets the elevator to a pre-defined position. + * + * @param newPosition The target ElevatorPositions enum. + */ + public void setPosition(ElevatorPositions newPosition) { + Elevator.this.setPositionFromEnum(newPosition); + } + + /** + * Sets the elevator to a specific height in meters. + * + * @param newPositionMeters The target height in meters. + */ + public void setPosition(double newPositionMeters) { + Elevator.this.setPositionFromDouble(newPositionMeters); + } + + public void setPosition(Supplier newPosition) { + Elevator.this.setPositionFromReef(newPosition); + } + + public void setPosition() { + Elevator.this.setPositionFromReef(() -> RobotState.getOIData().currentReefHeight()); + } + + public Command resetPosition() { + return Commands.runOnce(() -> Elevator.this.lastKnownPositionEnum = ElevatorPositions.STOW) + .andThen( + Commands.runOnce( + () -> io.setPosition(ElevatorConstants.ELEVATOR_PARAMETERS.MIN_HEIGHT_METERS()))); + } + + public Command sysIdRoutine(V2_RedundancySuperstructure superstructure) { + + return Commands.sequence( + superstructure.runGoal(V2_RedundancySuperstructureStates.OVERRIDE), + Elevator.this.sysIdRoutine(superstructure)); + } + + public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { + + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), + Elevator.this.sysIdRoutine(superstructure)); + } + + public double getPositionMeters() { + return Elevator.this.getPositionMeters(inputs); + } + + public double getFFCharacterizationVelocity() { + return Elevator.this.getFFCharacterizationVelocity(inputs); + } + + public void setGains(double kP, double kD, double kS, double kV, double kA, double kG) { + Elevator.this.setGains(kP, kD, kS, kV, kA, kG); + } + + public void setConstraints(double maxAcceleration, double cruisingVelocity) { + Elevator.this.setConstraints(maxAcceleration, cruisingVelocity); + } + + public boolean atGoal() { + return Elevator.this.atGoal(); + } + + public boolean atGoal(ReefState position) { + return Elevator.this.atGoal(Elevator.this.getPosition(position)); + } + + public boolean inTolerance(double toleranceMeters) { + return Math.abs(positionGoalMeters - inputs.positionMeters) <= toleranceMeters; + } + + public Command waitUntilAtGoal() { + return Elevator.this.waitUntilAtGoal(); + } + + public BooleanSupplier inFastScoringTolerance() { + return Elevator.this.inFastScoringTolerance(); + } + + public double getVelocityMetersPerSecond() { + return inputs.velocityMetersPerSecond; + } + } + + public ElevatorFSM getFSM() { + return new ElevatorFSM(); + } + + public ElevatorCSB getCSB() { + return new ElevatorCSB(); } - } - - public ElevatorFSM getFSM() { - return new ElevatorFSM(); - } - - public ElevatorCSB getCSB() { - return new ElevatorCSB(); - } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 1475890e..6ed0ff02 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -15,709 +15,700 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; import frc.robot.util.NTPrefixes; -import lombok.Getter; -import org.jgrapht.Graph; -import org.jgrapht.graph.DefaultDirectedGraph; -import org.littletonrobotics.junction.AutoLogOutput; -import org.littletonrobotics.junction.Logger; - import java.util.*; import java.util.function.BooleanSupplier; import java.util.function.DoubleSupplier; import java.util.function.Supplier; import java.util.stream.Collectors; +import lombok.Getter; +import org.jgrapht.Graph; +import org.jgrapht.graph.DefaultDirectedGraph; +import org.littletonrobotics.junction.AutoLogOutput; +import org.littletonrobotics.junction.Logger; /** * The V3_EpsilonSuperstructure class manages the coordinated movement and state transitions of the * robot's major subsystems including elevator, manipulator, and intake. */ public class V3_EpsilonSuperstructure extends SubsystemBase { - private final Graph graph; - private final ElevatorFSM elevator; - private final V3_EpsilonIntake intake; - private final V3_EpsilonManipulator manipulator; - - /** - * The previous, current, and next states of the superstructure. These are used to track the state - * transitions and manage the command scheduling. - */ - @Getter - private V3_EpsilonSuperstructureStates previousState; - - /** - * The current state of the superstructure, which is updated periodically based on the command - * scheduling and state transitions. - */ - @Getter - private V3_EpsilonSuperstructureStates currentState; - - /** - * The next state that the superstructure is transitioning to. This is determined by the command - * scheduling and the current target state. - */ - @Getter - private V3_EpsilonSuperstructureStates nextState; - - /** - * The target state that the superstructure is trying to achieve. This is set by the robot and - * determines the next action to be taken. - */ - @Getter - private V3_EpsilonSuperstructureStates targetState; - - /** - * The command that is currently being executed to transition between states. - */ - private EdgeCommand edgeCommand; - - /** - * Constructs a V2_RedundancySuperstructure. - * - * @param elevator The elevator subsystem. - * @param intake The intake subsystem. - * @param manipulator The manipulator subsystem. - */ - public V3_EpsilonSuperstructure( - ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { - this.elevator = elevator; - this.intake = intake; - this.manipulator = manipulator; - - previousState = null; - currentState = V3_EpsilonSuperstructureStates.START; - nextState = null; - - targetState = V3_EpsilonSuperstructureStates.START; - - // Initialize the graph - graph = new DefaultDirectedGraph<>(EdgeCommand.class); - - for (V3_EpsilonSuperstructureStates vertex : V3_EpsilonSuperstructureStates.values()) { - graph.addVertex(vertex); - } - - // Add edges between states - V3_EpsilonSuperstructureEdges.addEdges(graph, elevator, intake, manipulator); + private final Graph graph; + private final ElevatorFSM elevator; + private final V3_EpsilonIntake intake; + private final V3_EpsilonManipulator manipulator; + + /** + * The previous, current, and next states of the superstructure. These are used to track the state + * transitions and manage the command scheduling. + */ + @Getter private V3_EpsilonSuperstructureStates previousState; + + /** + * The current state of the superstructure, which is updated periodically based on the command + * scheduling and state transitions. + */ + @Getter private V3_EpsilonSuperstructureStates currentState; + + /** + * The next state that the superstructure is transitioning to. This is determined by the command + * scheduling and the current target state. + */ + @Getter private V3_EpsilonSuperstructureStates nextState; + + /** + * The target state that the superstructure is trying to achieve. This is set by the robot and + * determines the next action to be taken. + */ + @Getter private V3_EpsilonSuperstructureStates targetState; + + /** The command that is currently being executed to transition between states. */ + private EdgeCommand edgeCommand; + + /** + * Constructs a V2_RedundancySuperstructure. + * + * @param elevator The elevator subsystem. + * @param intake The intake subsystem. + * @param manipulator The manipulator subsystem. + */ + public V3_EpsilonSuperstructure( + ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { + this.elevator = elevator; + this.intake = intake; + this.manipulator = manipulator; + + previousState = null; + currentState = V3_EpsilonSuperstructureStates.START; + nextState = null; + + targetState = V3_EpsilonSuperstructureStates.START; + + // Initialize the graph + graph = new DefaultDirectedGraph<>(EdgeCommand.class); + + for (V3_EpsilonSuperstructureStates vertex : V3_EpsilonSuperstructureStates.values()) { + graph.addVertex(vertex); } - /** - * Periodic method that handles state transitions and subsystem updates. Updates robot state - * variables and manages command scheduling based on current state. - */ - @Override - public void periodic() { - if (currentState != null && !currentState.equals(V3_EpsilonSuperstructureStates.OVERRIDE)) { - if (nextState != null) { - // If we are in a transition, run the actions for the destination state - nextState.getAction().get(intake, manipulator); - } else { - // Otherwise, just run the actions for the state we are in - currentState.getAction().get(intake, manipulator); - } - } - if (RobotMode.disabled()) { - nextState = null; - } else if (edgeCommand == null || !edgeCommand.getCommand().isScheduled()) { - // Update edge to new state - if (nextState != null) { - previousState = currentState; - currentState = nextState; - nextState = null; - } - - // Schedule next command in sequence - if (currentState != targetState) { - bfs(currentState, targetState) - .ifPresent( - next -> { - this.nextState = next; - edgeCommand = graph.getEdge(currentState, next); - edgeCommand.getCommand().schedule(); - }); - } - } - - // Log the current state of the superstructure and edge command - Logger.recordOutput( - NTPrefixes.SUPERSTRUCTURE + "Goal", targetState == null ? "NULL" : targetState.toString()); - Logger.recordOutput( - NTPrefixes.SUPERSTRUCTURE + "Previous State", - previousState == null ? "NULL" : previousState.toString()); - Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Current State", currentState.toString()); - Logger.recordOutput( - NTPrefixes.SUPERSTRUCTURE + "Next State", - nextState == null ? "NULL" : nextState.toString()); - if (edgeCommand != null) { - Logger.recordOutput( - NTPrefixes.SUPERSTRUCTURE + "EdgeCommand", - graph.getEdgeSource(edgeCommand) + " --> " + graph.getEdgeTarget(edgeCommand)); - } else { - Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "EdgeCommand", "NO EDGES SCHEDULED"); - } - - elevator.periodic(); - intake.periodic(); - manipulator.periodic(); - - double armHeight = - -manipulator.getArmAngle().rotateBy(new Rotation2d(-Math.PI / 2)).getSin() - * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() - + elevator.getPositionMeters(); - Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Arm Height", armHeight); - Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Clears Base", 0.075 < armHeight); - Logger.recordOutput( - NTPrefixes.SUPERSTRUCTURE + "Clears Intake", - intake.getPivotAngle().getDegrees() > 15 - || armHeight > 0.37 - || Math.abs( - manipulator.getArmAngle().rotateBy(new Rotation2d(-Math.PI / 2)).getCos() - * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS()) - > 0.35); + // Add edges between states + V3_EpsilonSuperstructureEdges.addEdges(graph, elevator, intake, manipulator); + } + + /** + * Periodic method that handles state transitions and subsystem updates. Updates robot state + * variables and manages command scheduling based on current state. + */ + @Override + public void periodic() { + if (currentState != null && !currentState.equals(V3_EpsilonSuperstructureStates.OVERRIDE)) { + if (nextState != null) { + // If we are in a transition, run the actions for the destination state + nextState.getAction().get(intake, manipulator); + } else { + // Otherwise, just run the actions for the state we are in + currentState.getAction().get(intake, manipulator); + } } - - /** - * Updates the target state and handles command rescheduling for optimal path. - * - * @param goal New target state to achieve - */ - private void setGoal(V3_EpsilonSuperstructureStates goal) { - // Don't do anything if goal is the same - if (this.targetState == goal) return; - else { - this.targetState = goal; - } - - if (nextState == null) return; - - var edgeToCurrentState = graph.getEdge(nextState, currentState); - // Figure out if we should schedule a different command to get to goal faster - if (edgeCommand.getCommand().isScheduled() - && edgeToCurrentState != null - && isEdgeAllowed(edgeToCurrentState, goal)) { - // Figure out where we would have gone from the previous state - bfs(currentState, goal) - .ifPresent( - newNext -> { - if (newNext == nextState) { - // We are already on track - return; - } - - if (newNext != currentState && graph.getEdge(nextState, newNext) != null) { - // We can skip directly to the newNext edge - edgeCommand.getCommand().cancel(); - edgeCommand = graph.getEdge(currentState, newNext); - edgeCommand.getCommand().schedule(); - nextState = newNext; - } else { - // Follow the reverse edge from next back to the current edge - edgeCommand.getCommand().cancel(); - edgeCommand = graph.getEdge(nextState, currentState); - edgeCommand.getCommand().schedule(); - var temp = currentState; - previousState = currentState; - currentState = nextState; - nextState = temp; - } - }); - } + if (RobotMode.disabled()) { + nextState = null; + } else if (edgeCommand == null || !edgeCommand.getCommand().isScheduled()) { + // Update edge to new state + if (nextState != null) { + previousState = currentState; + currentState = nextState; + nextState = null; + } + + // Schedule next command in sequence + if (currentState != targetState) { + bfs(currentState, targetState) + .ifPresent( + next -> { + this.nextState = next; + edgeCommand = graph.getEdge(currentState, next); + edgeCommand.getCommand().schedule(); + }); + } } - /** - * Performs breadth-first search to find the next state in the path to the goal. - * - * @param start Starting state - * @param goal Target state - * @return Optional containing the next state in the path, empty if no path exists - */ - private Optional bfs( - V3_EpsilonSuperstructureStates start, V3_EpsilonSuperstructureStates goal) { - Map parents = new HashMap<>(); - Queue queue = new LinkedList<>(); - queue.add(start); - parents.put(start, null); - while (!queue.isEmpty()) { - V3_EpsilonSuperstructureStates current = queue.poll(); - if (current == goal) break; - for (EdgeCommand edge : - graph.outgoingEdgesOf(current).stream() - .filter(edge -> isEdgeAllowed(edge, goal)) - .toList()) { - V3_EpsilonSuperstructureStates neighbor = graph.getEdgeTarget(edge); - if (!parents.containsKey(neighbor)) { - parents.put(neighbor, current); - queue.add(neighbor); - } - } - } - - if (!parents.containsKey(goal)) return Optional.empty(); - - V3_EpsilonSuperstructureStates nextState = goal; - while (!nextState.equals(start)) { - V3_EpsilonSuperstructureStates parent = parents.get(nextState); - if (parent == null) return Optional.empty(); - else if (parent.equals(start)) return Optional.of(nextState); - nextState = parent; - } - return Optional.of(nextState); + // Log the current state of the superstructure and edge command + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "Goal", targetState == null ? "NULL" : targetState.toString()); + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "Previous State", + previousState == null ? "NULL" : previousState.toString()); + Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Current State", currentState.toString()); + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "Next State", + nextState == null ? "NULL" : nextState.toString()); + if (edgeCommand != null) { + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "EdgeCommand", + graph.getEdgeSource(edgeCommand) + " --> " + graph.getEdgeTarget(edgeCommand)); + } else { + Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "EdgeCommand", "NO EDGES SCHEDULED"); } - /** - * Checks if a state transition is allowed based on algae presence. - * - * @param edge The transition edge to check - * @param goal The target state - * @return true if the transition is allowed - */ - private boolean isEdgeAllowed(EdgeCommand edge, V3_EpsilonSuperstructureStates goal) { - // --- 1. Algae Check (Original Logic) --- - boolean gamePieceAllowed = - edge.getGamePieceEdge() == GamePieceEdge.UNCONSTRAINED - || RobotState.isHasAlgae() == (edge.getGamePieceEdge() != GamePieceEdge.NO_ALGAE); - - if (!gamePieceAllowed) { - return false; // Fail fast if game piece logic disallows it - } - - // Condition is TRUE, so we must apply the path forcing logic. - if (!RobotState.isHasAlgae()) { - V3_EpsilonSuperstructureStates from = graph.getEdgeSource(edge); - V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(edge); - - boolean needsFlip = RobotState.getScoreSide().equals(ScoreSide.RIGHT); + elevator.periodic(); + intake.periodic(); + manipulator.periodic(); + + double armHeight = + -manipulator.getArmAngle().rotateBy(new Rotation2d(-Math.PI / 2)).getSin() + * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() + + elevator.getPositionMeters(); + Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Arm Height", armHeight); + Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Clears Base", 0.075 < armHeight); + Logger.recordOutput( + NTPrefixes.SUPERSTRUCTURE + "Clears Intake", + intake.getPivotAngle().getDegrees() > 15 + || armHeight > 0.37 + || Math.abs( + manipulator.getArmAngle().rotateBy(new Rotation2d(-Math.PI / 2)).getCos() + * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS()) + > 0.35); + } + + /** + * Updates the target state and handles command rescheduling for optimal path. + * + * @param goal New target state to achieve + */ + private void setGoal(V3_EpsilonSuperstructureStates goal) { + // Don't do anything if goal is the same + if (this.targetState == goal) return; + else { + this.targetState = goal; + } - if (goal == V3_EpsilonSuperstructureStates.STOW_UP && needsFlip) { - if (to == V3_EpsilonSuperstructureStates.STOW_UP - && from != V3_EpsilonSuperstructureStates.INVERSE_FLIP_UP) { - return false; + if (nextState == null) return; + + var edgeToCurrentState = graph.getEdge(nextState, currentState); + // Figure out if we should schedule a different command to get to goal faster + if (edgeCommand.getCommand().isScheduled() + && edgeToCurrentState != null + && isEdgeAllowed(edgeToCurrentState, goal)) { + // Figure out where we would have gone from the previous state + bfs(currentState, goal) + .ifPresent( + newNext -> { + if (newNext == nextState) { + // We are already on track + return; } - } - if (goal == V3_EpsilonSuperstructureStates.STOW_UP && !needsFlip) { - if (to == V3_EpsilonSuperstructureStates.STOW_UP - && from != V3_EpsilonSuperstructureStates.INVERSE_FLIP_UP) { - return false; + if (newNext != currentState && graph.getEdge(nextState, newNext) != null) { + // We can skip directly to the newNext edge + edgeCommand.getCommand().cancel(); + edgeCommand = graph.getEdge(currentState, newNext); + edgeCommand.getCommand().schedule(); + nextState = newNext; + } else { + // Follow the reverse edge from next back to the current edge + edgeCommand.getCommand().cancel(); + edgeCommand = graph.getEdge(nextState, currentState); + edgeCommand.getCommand().schedule(); + var temp = currentState; + previousState = currentState; + currentState = nextState; + nextState = temp; } - } - } - - // --- 3. If all checks pass, the edge is allowed --- - return true; + }); } - - /** - * Resets the superstructure to initial auto state. - */ - public void setAutoStart() { - currentState = V3_EpsilonSuperstructureStates.START; - nextState = null; - targetState = V3_EpsilonSuperstructureStates.STOW_DOWN; - if (edgeCommand != null) { - edgeCommand.getCommand().cancel(); + } + + /** + * Performs breadth-first search to find the next state in the path to the goal. + * + * @param start Starting state + * @param goal Target state + * @return Optional containing the next state in the path, empty if no path exists + */ + private Optional bfs( + V3_EpsilonSuperstructureStates start, V3_EpsilonSuperstructureStates goal) { + Map parents = new HashMap<>(); + Queue queue = new LinkedList<>(); + queue.add(start); + parents.put(start, null); + while (!queue.isEmpty()) { + V3_EpsilonSuperstructureStates current = queue.poll(); + if (current == goal) break; + for (EdgeCommand edge : + graph.outgoingEdgesOf(current).stream() + .filter(edge -> isEdgeAllowed(edge, goal)) + .toList()) { + V3_EpsilonSuperstructureStates neighbor = graph.getEdgeTarget(edge); + if (!parents.containsKey(neighbor)) { + parents.put(neighbor, current); + queue.add(neighbor); } + } } - /** - * Maps current OI reef height to corresponding elevator position state. - * - * @return Appropriate superstructure state for current reef height - */ - private V3_EpsilonSuperstructureStates getElevatorPosition() { - switch (RobotState.getOIData().currentReefHeight()) { - case STOW, CORAL_INTAKE -> { - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - case L1 -> { - return V3_EpsilonSuperstructureStates.L1; - } - case L2 -> { - return V3_EpsilonSuperstructureStates.L2; - } - case L3 -> { - return V3_EpsilonSuperstructureStates.L3; - } - case L4 -> { - return V3_EpsilonSuperstructureStates.L4; - } - case ALGAE_INTAKE_BOTTOM -> { - return V3_EpsilonSuperstructureStates.L2_ALGAE; - } - case ALGAE_INTAKE_TOP -> { - return V3_EpsilonSuperstructureStates.L3_ALGAE; - } - case ALGAE_SCORE -> { - return V3_EpsilonSuperstructureStates.BARGE; - } - default -> { - return V3_EpsilonSuperstructureStates.START; - } - } - } - - // --- Control Commands --- - - /** - * Returns a command that sets the superstructure to the given goal state. - * - * @param goal The desired superstructure state - * @return Command to run the goal - */ - public Command runGoal(V3_EpsilonSuperstructureStates goal) { - return runOnce(() -> setGoal(goal)); - } - - /** - * Returns a command that sets the superstructure to the goal provided by a supplier. - * - * @param goal Supplier providing the desired superstructure state - * @return Command to run the goal - */ - public Command runGoal(Supplier goal) { - return runOnce(() -> setGoal(goal.get())); - } - - /** - * Checks whether the superstructure has reached its target state. - * - * @return true if current state matches the target state - */ - @AutoLogOutput(key = NTPrefixes.SUPERSTRUCTURE + "At Goal") - public boolean atGoal() { - return currentState == targetState - && elevator.atGoal() - && intake.pivotAtGoal() - && manipulator.armAtGoal(); - } - - public Command waitUntilAtGoal() { - return Commands.sequence(Commands.waitSeconds(.02), Commands.waitUntil(() -> atGoal())); - } - - /** - * Runs a temporary override action, returning to a previous goal after. - * - * @param action The override action to perform - * @param oldGoal The goal to return to after override - * @return Command that runs the override and resumes the old goal - */ - public Command override(Runnable action) { - return Commands.sequence(runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), Commands.run(action)) - .finallyDo(() -> setGoal(currentState)); - } - - /** - * Runs a temporary override action, returning to a previous goal after. - * - * @param action The override action to perform - * @param oldGoal The goal to return to after override - * @return Command that runs the override and resumes the old goal - */ - public Command override(Runnable action, double timeSeconds) { - return override(action).withTimeout(timeSeconds); - } - - /** - * Runs the goal state and waits until a given condition becomes true. - * - * @param goal The desired superstructure state - * @param condition The condition to wait for after running the goal - * @return Combined command for running and waiting - */ - public Command runGoalUntil(V3_EpsilonSuperstructureStates goal, BooleanSupplier condition) { - return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); - } - - public Command runGoalUntil( - Supplier goal, BooleanSupplier condition) { - return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); - } - - /** - * Returns a short command to run the previous state, useful for temporary state restoration. - * - * @return Command to go back to the previous state - */ - public Command runPreviousState() { - return runGoal(() -> previousState); - } - - /** - * Converts a ReefState (field-level enum) into a corresponding elevator goal and runs it. - * - * @param goal Supplier of ReefState - * @return Command to move to the elevator position for the reef level - */ - public Command runReefGoal(Supplier goal) { - return runGoal( - () -> { - // Translate ReefState to superstructure state - switch (goal.get()) { - case L1: - return V3_EpsilonSuperstructureStates.L1; - case L2: - return V3_EpsilonSuperstructureStates.L2; - case L3: - return V3_EpsilonSuperstructureStates.L3; - case L4: - return V3_EpsilonSuperstructureStates.L4; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }); - } - - /** - * Moves to a scoring position, executes the score action for a fixed time, then returns to pose. - * - * @param goal Supplier of the ReefState (target height/level) - * @return Command to run the score cycle (pose → action → timeout → pose) - */ - public Command runReefScoreGoal(Supplier goal) { - // Run appropriate action sequence depending on reef level - return this.runGoal( - () -> { - switch (goal.get()) { - case L1: - return V3_EpsilonSuperstructureStates.L1_SCORE; - case L2: - return V3_EpsilonSuperstructureStates.L2_SCORE; - case L3: - return V3_EpsilonSuperstructureStates.L3_SCORE; - case L4: - return V3_EpsilonSuperstructureStates.L4_SCORE; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }); + if (!parents.containsKey(goal)) return Optional.empty(); - // return runActionWithTimeout( - // () -> - // switch (goal.get()) { - // case L1 -> V3_EpsilonSuperstructureStates.L1; - // case L2 -> V3_EpsilonSuperstructureStates.L2; - // case L3 -> V3_EpsilonSuperstructureStates.L3; - // case L4 -> V3_EpsilonSuperstructureStates.L4; - // default -> V3_EpsilonSuperstructureStates.STOW_DOWN; - // }, - // () -> - // switch (goal.get()) { - // case L1 -> 0.8; - // case L2 -> 0.15; - // case L3 -> 0.15; - // case L4 -> 0.1; - // default -> 0; - // }); + V3_EpsilonSuperstructureStates nextState = goal; + while (!nextState.equals(start)) { + V3_EpsilonSuperstructureStates parent = parents.get(nextState); + if (parent == null) return Optional.empty(); + else if (parent.equals(start)) return Optional.of(nextState); + nextState = parent; } - - /** - * Runs an action by going to a pose, performing the action, waiting, and returning. - * - * @param pose The pose to return to after action - * @param action The action to perform - * @param timeout How long to wait during the action phase (in seconds) - * @return Full command sequence - */ - public Command runActionWithTimeout( - Supplier pose, - Supplier action, - DoubleSupplier timeout) { - return Commands.sequence( - runGoal(action), // Run the action - waitUntilAtGoal(), - Commands.defer(() -> Commands.waitSeconds(timeout.getAsDouble()), Set.of())) - .finallyDo(() -> setGoal(pose.get())); // Return to original pose + return Optional.of(nextState); + } + + /** + * Checks if a state transition is allowed based on algae presence. + * + * @param edge The transition edge to check + * @param goal The target state + * @return true if the transition is allowed + */ + private boolean isEdgeAllowed(EdgeCommand edge, V3_EpsilonSuperstructureStates goal) { + // --- 1. Algae Check (Original Logic) --- + boolean gamePieceAllowed = + edge.getGamePieceEdge() == GamePieceEdge.UNCONSTRAINED + || RobotState.isHasAlgae() == (edge.getGamePieceEdge() != GamePieceEdge.NO_ALGAE); + + if (!gamePieceAllowed) { + return false; // Fail fast if game piece logic disallows it } - /** - * Runs an action by going to a pose, performing the action, waiting, and returning. - * - * @param pose The pose to return to after action - * @param action The action to perform - * @param timeout How long to wait during the action phase (in seconds) - * @return Full command sequence - */ - public Command runActionWithTimeout( - V3_EpsilonSuperstructureStates pose, V3_EpsilonSuperstructureStates action, double timeout) { - return Commands.sequence( - runGoal(action), // Run the action - waitUntilAtGoal(), - Commands.waitSeconds(timeout), - runGoal(pose)) - .finallyDo(() -> setGoal(pose)); // Return to original pose - } + // Condition is TRUE, so we must apply the path forcing logic. + if (!RobotState.isHasAlgae()) { + V3_EpsilonSuperstructureStates from = graph.getEdgeSource(edge); + V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(edge); - /** - * Smart overload that runs an action using a cached pose–action mapping, determining the pose - * from the action. - * - * @param action The scoring or action state - * @param timeout Timeout for the action duration - * @return Command sequence to perform and recover from the action - */ - public Command runActionWithTimeout( - Supplier action, DoubleSupplier timeout) { - // Maps each action state to its corresponding pose state - Map actionPoseMap = - new HashMap<>() { - { - put(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.L1); - put(V3_EpsilonSuperstructureStates.L2_SCORE, V3_EpsilonSuperstructureStates.L2); - put(V3_EpsilonSuperstructureStates.L3_SCORE, V3_EpsilonSuperstructureStates.L3); - put(V3_EpsilonSuperstructureStates.L4_SCORE, V3_EpsilonSuperstructureStates.L4); - put(V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.BARGE); - put( - V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, - V3_EpsilonSuperstructureStates.PROCESSOR); - } - }; - - // Reverse the map so we can look up the pose from action if needed - Map poseActionMap = - actionPoseMap.entrySet().stream() - .collect(Collectors.toMap(Map.Entry::getValue, Map.Entry::getKey)); - - // Try to look up pose from action (either direction works) - if (actionPoseMap.containsKey(action.get())) { - return runActionWithTimeout(() -> actionPoseMap.get(action.get()), action, timeout); - } else if (actionPoseMap.containsValue(action.get())) { - return runActionWithTimeout(action, () -> poseActionMap.get(action.get()), timeout); - } else return Commands.none(); // If action is not recognized, do nothing - } + boolean needsFlip = RobotState.getScoreSide().equals(ScoreSide.RIGHT); - /** - * Smart overload that runs an action using a cached pose–action mapping, determining the pose - * from the action. - * - * @param action The scoring or action state - * @param timeout Timeout for the action duration - * @return Command sequence to perform and recover from the action - */ - public Command runActionWithTimeout(V3_EpsilonSuperstructureStates action, double timeout) { - // Maps each action state to its corresponding pose state - Map actionPoseMap = - new HashMap<>() { - { - put(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.L1); - put(V3_EpsilonSuperstructureStates.L2_SCORE, V3_EpsilonSuperstructureStates.L2); - put(V3_EpsilonSuperstructureStates.L3_SCORE, V3_EpsilonSuperstructureStates.L3); - put(V3_EpsilonSuperstructureStates.L4_SCORE, V3_EpsilonSuperstructureStates.L4); - put(V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.BARGE); - put( - V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, - V3_EpsilonSuperstructureStates.PROCESSOR); - } - }; - - // Reverse the map so we can look up the pose from action if needed - Map poseActionMap = - actionPoseMap.entrySet().stream() - .collect(Collectors.toMap(Map.Entry::getValue, Map.Entry::getKey)); - - // Try to look up pose from action (either direction works) - if (actionPoseMap.containsKey(action)) { - return runActionWithTimeout(actionPoseMap.get(action), action, timeout); - } else if (actionPoseMap.containsValue(action)) { - return runActionWithTimeout(action, poseActionMap.get(action), timeout); - } else return Commands.none(); // If action is not recognized, do nothing - } + if (goal == V3_EpsilonSuperstructureStates.STOW_UP && needsFlip) { + if (to == V3_EpsilonSuperstructureStates.STOW_UP + && from != V3_EpsilonSuperstructureStates.INVERSE_FLIP_UP) { + return false; + } + } - /** - * Updates the superstructure to match the current OI-defined reef height. - * - * @return Command to move to elevator position state - */ - public Command setPosition() { - return runGoal(() -> getElevatorPosition()).withTimeout(0.02); + if (goal == V3_EpsilonSuperstructureStates.STOW_UP && !needsFlip) { + if (to == V3_EpsilonSuperstructureStates.STOW_UP + && from != V3_EpsilonSuperstructureStates.INVERSE_FLIP_UP) { + return false; + } + } } - /** - * Checks if the elevator is at its goal position. - * - * @return True if the elevator is at its goal, false otherwise. - */ - public boolean elevatorAtGoal() { - return elevator.atGoal(); + // --- 3. If all checks pass, the edge is allowed --- + return true; + } + + /** Resets the superstructure to initial auto state. */ + public void setAutoStart() { + currentState = V3_EpsilonSuperstructureStates.START; + nextState = null; + targetState = V3_EpsilonSuperstructureStates.STOW_DOWN; + if (edgeCommand != null) { + edgeCommand.getCommand().cancel(); } - - @AutoLogOutput(key = NTPrefixes.SUPERSTRUCTURE + "IsTransitioning") - public boolean isTransitioning() { - return edgeCommand != null && edgeCommand.getCommand().isScheduled(); + } + + /** + * Maps current OI reef height to corresponding elevator position state. + * + * @return Appropriate superstructure state for current reef height + */ + private V3_EpsilonSuperstructureStates getElevatorPosition() { + switch (RobotState.getOIData().currentReefHeight()) { + case STOW, CORAL_INTAKE -> { + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + case L1 -> { + return V3_EpsilonSuperstructureStates.L1; + } + case L2 -> { + return V3_EpsilonSuperstructureStates.L2; + } + case L3 -> { + return V3_EpsilonSuperstructureStates.L3; + } + case L4 -> { + return V3_EpsilonSuperstructureStates.L4; + } + case ALGAE_INTAKE_BOTTOM -> { + return V3_EpsilonSuperstructureStates.L2_ALGAE; + } + case ALGAE_INTAKE_TOP -> { + return V3_EpsilonSuperstructureStates.L3_ALGAE; + } + case ALGAE_SCORE -> { + return V3_EpsilonSuperstructureStates.BARGE; + } + default -> { + return V3_EpsilonSuperstructureStates.START; + } } - - public Command allTransition() { - Command all = runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN); - for (var source : V3_EpsilonSuperstructureStates.values()) { - for (var sink : V3_EpsilonSuperstructureStates.values()) { - if (source == sink) continue; - if (sink == V3_EpsilonSuperstructureStates.FLIP_DOWN) continue; - if (sink == V3_EpsilonSuperstructureStates.FLIP_UP) continue; - if (sink == V3_EpsilonSuperstructureStates.STOW_DOWN) continue; - if (sink == V3_EpsilonSuperstructureStates.STOW_UP) continue; - if (sink == V3_EpsilonSuperstructureStates.GROUND_ACQUISITION) continue; - if (sink == V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) continue; - if (sink == V3_EpsilonSuperstructureStates.GROUND_AQUISITION_ALGAE) continue; - if (sink == V3_EpsilonSuperstructureStates.GROUND_INTAKE) continue; - if (sink == V3_EpsilonSuperstructureStates.L1) continue; - if (sink == V3_EpsilonSuperstructureStates.L1_SCORE) continue; - if (sink == V3_EpsilonSuperstructureStates.L2) continue; - if (sink == V3_EpsilonSuperstructureStates.L2_SCORE) continue; - if (sink == V3_EpsilonSuperstructureStates.L3) continue; - if (sink == V3_EpsilonSuperstructureStates.L3_SCORE) continue; - - if (source != V3_EpsilonSuperstructureStates.START - && sink != V3_EpsilonSuperstructureStates.START - && source != V3_EpsilonSuperstructureStates.OVERRIDE - && sink != V3_EpsilonSuperstructureStates.OVERRIDE) { - all = - all.andThen( - runGoal(sink), - runOnce( - () -> - Logger.recordOutput( - "Superstructure/Current Objective", - source.toString() + " -> " + sink.toString())), - Commands.waitUntil(() -> atGoal())); - all = - all.andThen( - runGoal(source), - runOnce( - () -> - Logger.recordOutput( - "Superstructure/Current Objective", - sink.toString() + " -> " + source.toString())), - Commands.waitUntil(() -> atGoal())); - } - } + } + + // --- Control Commands --- + + /** + * Returns a command that sets the superstructure to the given goal state. + * + * @param goal The desired superstructure state + * @return Command to run the goal + */ + public Command runGoal(V3_EpsilonSuperstructureStates goal) { + return runOnce(() -> setGoal(goal)); + } + + /** + * Returns a command that sets the superstructure to the goal provided by a supplier. + * + * @param goal Supplier providing the desired superstructure state + * @return Command to run the goal + */ + public Command runGoal(Supplier goal) { + return runOnce(() -> setGoal(goal.get())); + } + + /** + * Checks whether the superstructure has reached its target state. + * + * @return true if current state matches the target state + */ + @AutoLogOutput(key = NTPrefixes.SUPERSTRUCTURE + "At Goal") + public boolean atGoal() { + return currentState == targetState + && elevator.atGoal() + && intake.pivotAtGoal() + && manipulator.armAtGoal(); + } + + public Command waitUntilAtGoal() { + return Commands.sequence(Commands.waitSeconds(.02), Commands.waitUntil(() -> atGoal())); + } + + /** + * Runs a temporary override action, returning to a previous goal after. + * + * @param action The override action to perform + * @param oldGoal The goal to return to after override + * @return Command that runs the override and resumes the old goal + */ + public Command override(Runnable action) { + return Commands.sequence(runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), Commands.run(action)) + .finallyDo(() -> setGoal(currentState)); + } + + /** + * Runs a temporary override action, returning to a previous goal after. + * + * @param action The override action to perform + * @param oldGoal The goal to return to after override + * @return Command that runs the override and resumes the old goal + */ + public Command override(Runnable action, double timeSeconds) { + return override(action).withTimeout(timeSeconds); + } + + /** + * Runs the goal state and waits until a given condition becomes true. + * + * @param goal The desired superstructure state + * @param condition The condition to wait for after running the goal + * @return Combined command for running and waiting + */ + public Command runGoalUntil(V3_EpsilonSuperstructureStates goal, BooleanSupplier condition) { + return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); + } + + public Command runGoalUntil( + Supplier goal, BooleanSupplier condition) { + return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); + } + + /** + * Returns a short command to run the previous state, useful for temporary state restoration. + * + * @return Command to go back to the previous state + */ + public Command runPreviousState() { + return runGoal(() -> previousState); + } + + /** + * Converts a ReefState (field-level enum) into a corresponding elevator goal and runs it. + * + * @param goal Supplier of ReefState + * @return Command to move to the elevator position for the reef level + */ + public Command runReefGoal(Supplier goal) { + return runGoal( + () -> { + // Translate ReefState to superstructure state + switch (goal.get()) { + case L1: + return V3_EpsilonSuperstructureStates.L1; + case L2: + return V3_EpsilonSuperstructureStates.L2; + case L3: + return V3_EpsilonSuperstructureStates.L3; + case L4: + return V3_EpsilonSuperstructureStates.L4; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }); + } + + /** + * Moves to a scoring position, executes the score action for a fixed time, then returns to pose. + * + * @param goal Supplier of the ReefState (target height/level) + * @return Command to run the score cycle (pose → action → timeout → pose) + */ + public Command runReefScoreGoal(Supplier goal) { + // Run appropriate action sequence depending on reef level + return this.runGoal( + () -> { + switch (goal.get()) { + case L1: + return V3_EpsilonSuperstructureStates.L1_SCORE; + case L2: + return V3_EpsilonSuperstructureStates.L2_SCORE; + case L3: + return V3_EpsilonSuperstructureStates.L3_SCORE; + case L4: + return V3_EpsilonSuperstructureStates.L4_SCORE; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }); + + // return runActionWithTimeout( + // () -> + // switch (goal.get()) { + // case L1 -> V3_EpsilonSuperstructureStates.L1; + // case L2 -> V3_EpsilonSuperstructureStates.L2; + // case L3 -> V3_EpsilonSuperstructureStates.L3; + // case L4 -> V3_EpsilonSuperstructureStates.L4; + // default -> V3_EpsilonSuperstructureStates.STOW_DOWN; + // }, + // () -> + // switch (goal.get()) { + // case L1 -> 0.8; + // case L2 -> 0.15; + // case L3 -> 0.15; + // case L4 -> 0.1; + // default -> 0; + // }); + } + + /** + * Runs an action by going to a pose, performing the action, waiting, and returning. + * + * @param pose The pose to return to after action + * @param action The action to perform + * @param timeout How long to wait during the action phase (in seconds) + * @return Full command sequence + */ + public Command runActionWithTimeout( + Supplier pose, + Supplier action, + DoubleSupplier timeout) { + return Commands.sequence( + runGoal(action), // Run the action + waitUntilAtGoal(), + Commands.defer(() -> Commands.waitSeconds(timeout.getAsDouble()), Set.of())) + .finallyDo(() -> setGoal(pose.get())); // Return to original pose + } + + /** + * Runs an action by going to a pose, performing the action, waiting, and returning. + * + * @param pose The pose to return to after action + * @param action The action to perform + * @param timeout How long to wait during the action phase (in seconds) + * @return Full command sequence + */ + public Command runActionWithTimeout( + V3_EpsilonSuperstructureStates pose, V3_EpsilonSuperstructureStates action, double timeout) { + return Commands.sequence( + runGoal(action), // Run the action + waitUntilAtGoal(), + Commands.waitSeconds(timeout), + runGoal(pose)) + .finallyDo(() -> setGoal(pose)); // Return to original pose + } + + /** + * Smart overload that runs an action using a cached pose–action mapping, determining the pose + * from the action. + * + * @param action The scoring or action state + * @param timeout Timeout for the action duration + * @return Command sequence to perform and recover from the action + */ + public Command runActionWithTimeout( + Supplier action, DoubleSupplier timeout) { + // Maps each action state to its corresponding pose state + Map actionPoseMap = + new HashMap<>() { + { + put(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.L1); + put(V3_EpsilonSuperstructureStates.L2_SCORE, V3_EpsilonSuperstructureStates.L2); + put(V3_EpsilonSuperstructureStates.L3_SCORE, V3_EpsilonSuperstructureStates.L3); + put(V3_EpsilonSuperstructureStates.L4_SCORE, V3_EpsilonSuperstructureStates.L4); + put(V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.BARGE); + put( + V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, + V3_EpsilonSuperstructureStates.PROCESSOR); + } + }; + + // Reverse the map so we can look up the pose from action if needed + Map poseActionMap = + actionPoseMap.entrySet().stream() + .collect(Collectors.toMap(Map.Entry::getValue, Map.Entry::getKey)); + + // Try to look up pose from action (either direction works) + if (actionPoseMap.containsKey(action.get())) { + return runActionWithTimeout(() -> actionPoseMap.get(action.get()), action, timeout); + } else if (actionPoseMap.containsValue(action.get())) { + return runActionWithTimeout(action, () -> poseActionMap.get(action.get()), timeout); + } else return Commands.none(); // If action is not recognized, do nothing + } + + /** + * Smart overload that runs an action using a cached pose–action mapping, determining the pose + * from the action. + * + * @param action The scoring or action state + * @param timeout Timeout for the action duration + * @return Command sequence to perform and recover from the action + */ + public Command runActionWithTimeout(V3_EpsilonSuperstructureStates action, double timeout) { + // Maps each action state to its corresponding pose state + Map actionPoseMap = + new HashMap<>() { + { + put(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.L1); + put(V3_EpsilonSuperstructureStates.L2_SCORE, V3_EpsilonSuperstructureStates.L2); + put(V3_EpsilonSuperstructureStates.L3_SCORE, V3_EpsilonSuperstructureStates.L3); + put(V3_EpsilonSuperstructureStates.L4_SCORE, V3_EpsilonSuperstructureStates.L4); + put(V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.BARGE); + put( + V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, + V3_EpsilonSuperstructureStates.PROCESSOR); + } + }; + + // Reverse the map so we can look up the pose from action if needed + Map poseActionMap = + actionPoseMap.entrySet().stream() + .collect(Collectors.toMap(Map.Entry::getValue, Map.Entry::getKey)); + + // Try to look up pose from action (either direction works) + if (actionPoseMap.containsKey(action)) { + return runActionWithTimeout(actionPoseMap.get(action), action, timeout); + } else if (actionPoseMap.containsValue(action)) { + return runActionWithTimeout(action, poseActionMap.get(action), timeout); + } else return Commands.none(); // If action is not recognized, do nothing + } + + /** + * Updates the superstructure to match the current OI-defined reef height. + * + * @return Command to move to elevator position state + */ + public Command setPosition() { + return runGoal(() -> getElevatorPosition()).withTimeout(0.02); + } + + /** + * Checks if the elevator is at its goal position. + * + * @return True if the elevator is at its goal, false otherwise. + */ + public boolean elevatorAtGoal() { + return elevator.atGoal(); + } + + @AutoLogOutput(key = NTPrefixes.SUPERSTRUCTURE + "IsTransitioning") + public boolean isTransitioning() { + return edgeCommand != null && edgeCommand.getCommand().isScheduled(); + } + + public Command allTransition() { + Command all = runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN); + for (var source : V3_EpsilonSuperstructureStates.values()) { + for (var sink : V3_EpsilonSuperstructureStates.values()) { + if (source == sink) continue; + if (sink == V3_EpsilonSuperstructureStates.FLIP_DOWN) continue; + if (sink == V3_EpsilonSuperstructureStates.FLIP_UP) continue; + if (sink == V3_EpsilonSuperstructureStates.STOW_DOWN) continue; + if (sink == V3_EpsilonSuperstructureStates.STOW_UP) continue; + if (sink == V3_EpsilonSuperstructureStates.GROUND_ACQUISITION) continue; + if (sink == V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) continue; + if (sink == V3_EpsilonSuperstructureStates.GROUND_AQUISITION_ALGAE) continue; + if (sink == V3_EpsilonSuperstructureStates.GROUND_INTAKE) continue; + if (sink == V3_EpsilonSuperstructureStates.L1) continue; + if (sink == V3_EpsilonSuperstructureStates.L1_SCORE) continue; + if (sink == V3_EpsilonSuperstructureStates.L2) continue; + if (sink == V3_EpsilonSuperstructureStates.L2_SCORE) continue; + if (sink == V3_EpsilonSuperstructureStates.L3) continue; + if (sink == V3_EpsilonSuperstructureStates.L3_SCORE) continue; + + if (source != V3_EpsilonSuperstructureStates.START + && sink != V3_EpsilonSuperstructureStates.START + && source != V3_EpsilonSuperstructureStates.OVERRIDE + && sink != V3_EpsilonSuperstructureStates.OVERRIDE) { + all = + all.andThen( + runGoal(sink), + runOnce( + () -> + Logger.recordOutput( + "Superstructure/Current Objective", + source.toString() + " -> " + sink.toString())), + Commands.waitUntil(() -> atGoal())); + all = + all.andThen( + runGoal(source), + runOnce( + () -> + Logger.recordOutput( + "Superstructure/Current Objective", + sink.toString() + " -> " + source.toString())), + Commands.waitUntil(() -> atGoal())); } - return all; + } } - - public Command stateTransitions(V3_EpsilonSuperstructureStates source) { - Command all = Commands.none(); - - for (var sink : V3_EpsilonSuperstructureStates.values()) { - if (sink == source - || sink == V3_EpsilonSuperstructureStates.START - || sink == V3_EpsilonSuperstructureStates.OVERRIDE) continue; - - all = - all.andThen( - Commands.sequence( - runOnce(() -> System.out.println("→ " + source + " to " + sink)), - runGoal(sink), - Commands.waitUntil(this::atGoal), - Commands.waitSeconds(1.0), - runOnce(() -> System.out.println("← " + sink + " back to " + source)), - runGoal(source), - Commands.waitUntil(this::atGoal), - Commands.waitSeconds(1.0))); - } - - return all; + return all; + } + + public Command stateTransitions(V3_EpsilonSuperstructureStates source) { + Command all = Commands.none(); + + for (var sink : V3_EpsilonSuperstructureStates.values()) { + if (sink == source + || sink == V3_EpsilonSuperstructureStates.START + || sink == V3_EpsilonSuperstructureStates.OVERRIDE) continue; + + all = + all.andThen( + Commands.sequence( + runOnce(() -> System.out.println("→ " + source + " to " + sink)), + runGoal(sink), + Commands.waitUntil(this::atGoal), + Commands.waitSeconds(1.0), + runOnce(() -> System.out.println("← " + sink + " back to " + source)), + runGoal(source), + Commands.waitUntil(this::atGoal), + Commands.waitSeconds(1.0))); } - public boolean armBelowThreshold() { - return manipulator.getArmAngle().getDegrees() >= 90; - } + return all; + } + + public boolean armBelowThreshold() { + return manipulator.getArmAngle().getDegrees() >= 90; + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 24151b0d..92b74efe 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -1,7 +1,5 @@ package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; -import static edu.wpi.first.units.Units.*; - import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; @@ -15,320 +13,323 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; -import java.util.Set; import lombok.Getter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; +import java.util.Set; + +import static edu.wpi.first.units.Units.*; + public class V3_EpsilonManipulator { - private final V3_EpsilonManipulatorIO io; - private final ManipulatorIOInputsAutoLogged inputs; + private final V3_EpsilonManipulatorIO io; + private final ManipulatorIOInputsAutoLogged inputs; + + @AutoLogOutput(key = "Manipulator/Arm Goal") + @Getter + private Rotation2d armGoal; + + @AutoLogOutput(key = "Manipulator/Roller Goal") + @Getter + private ManipulatorRollerState rollerGoal; + + private boolean isClosedLoop; + + Set algaeStates; + + public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { + this.io = io; + inputs = new ManipulatorIOInputsAutoLogged(); + + isClosedLoop = true; + armGoal = ManipulatorArmState.VERTICAL_UP.getAngle(RobotState.getScoreSide()); + rollerGoal = ManipulatorRollerState.STOP; + + algaeStates = + Set.of( + ManipulatorArmState.ALGAE_INTAKE_FLOOR, + ManipulatorArmState.REEF_INTAKE, + ManipulatorArmState.ALGAE_SCORE); + } + + public void periodic() { + io.updateInputs(inputs); + Logger.processInputs("Manipulator", inputs); + + if (isClosedLoop) { + io.setArmGoal(armGoal); + } + + if (rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { + io.setRollerVoltage(ManipulatorRollerState.SCORE_ALGAE.getVoltage()); + } else if (hasAlgae() + && Set.of( + ManipulatorRollerState.CORAL_INTAKE, + ManipulatorRollerState.STOP, + ManipulatorRollerState.ALGAE_INTAKE) + .contains(rollerGoal) + && !rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { + RobotState.setHasAlgae(true); + io.setRollerVoltage(holdVoltage()); + } else if (hasCoral()) { + io.setRollerVoltage(holdVoltage()); + } else { + io.setRollerVoltage(rollerGoal.getVoltage()); + } + } + + /** + * Checks if the manipulator is currently detecting coral. This is done by checking if the CAN + * range sensor is detecting a distance less than the coral detection threshold and greater than + * 0. + * + * @return True if the manipulator is detecting coral, false otherwise. + */ + @AutoLogOutput(key = "Manipulator/Has Coral") + public boolean hasCoral() { + return inputs.canRangeGot; + } + + /** + * Checks if the manipulator is currently detecting algae. This is done by checking if the CAN + * range sensor is detecting a distance less than the algae detection threshold and greater than + * 0. + * + * @return True if the manipulator is detecting algae, false otherwise. + */ + @AutoLogOutput(key = "Manipulator/Has Algae") + public boolean hasAlgae() { + boolean hasAlgae = rollerGoal.equals(ManipulatorRollerState.ALGAE_INTAKE) && inputs.canRangeGot; + return hasAlgae; + } + + /** + * Creates a command to run the manipulator arm at a specified voltage. + * + * @param volts The voltage to set the arm to. + * @return A command to run the arm. + */ + public Command runArm(double volts) { + return Commands.runEnd( + () -> { + isClosedLoop = false; + io.setArmVoltage(volts); + }, + () -> io.setArmVoltage(0)); + } + + /** + * Sets the goal for the manipulator arm to reach. + * + * @param goal The goal state to set the arm to. + */ + public void setArmGoal(ManipulatorArmState goal) { + isClosedLoop = true; + if (!algaeStates.contains(goal)) { + armGoal = goal.getAngle(RobotState.getScoreSide()); + } else { + armGoal = goal.getAngle(ScoreSide.CENTER); + } + } - @AutoLogOutput(key = "Manipulator/Arm Goal") - @Getter - private Rotation2d armGoal; + public void setArmGoal(Rotation2d goal) { + isClosedLoop = true; + armGoal = goal; + } + + /** + * Updates the gains for the manipulator arm. This function sets the PID gains for the three slots + * of the arm. The gains are used to control the arm's movement. + * + * @param kP0 The proportional gain for slot 0. + * @param kD0 The derivative gain for slot 0. + * @param kS0 The static gain for slot 0. + * @param kV0 The velocity gain for slot 0. + * @param kA0 The acceleration gain for slot 0. + * @param kG0 The gravity gain for slot 0. + * @param kP1 The proportional gain for slot 1. + * @param kD1 The derivative gain for slot 1. + * @param kS1 The static gain for slot 1. + * @param kV1 The velocity gain for slot 1. + * @param kA1 The acceleration gain for slot 1. + * @param kG1 The gravity gain for slot 1. + * @param kP2 The proportional gain for slot 2. + * @param kD2 The derivative gain for slot 2. + * @param kS2 The static gain for slot 2. + * @param kV2 The velocity gain for slot 2. + * @param kA2 The acceleration gain for slot 2. + * @param kG2 The gravity gain for slot 2. + */ + public void updateArmGains( + double kP0, + double kD0, + double kS0, + double kV0, + double kA0, + double kG0, + double kP1, + double kD1, + double kS1, + double kV1, + double kA1, + double kG1, + double kP2, + double kD2, + double kS2, + double kV2, + double kA2, + double kG2) { + io.updateSlot0ArmGains(kP0, kD0, kS0, kV0, kA0, kG0); + io.updateSlot1ArmGains(kP1, kD1, kS1, kV1, kA1, kG1); + io.updateSlot2ArmGains(kP2, kD2, kS2, kV2, kA2, kG2); + } + + /** + * Updates the constraints for the arm. + * + * @param maxAcceleration The maximum acceleration. + * @param maxVelocity The maximum velocity. + */ + public void updateArmConstraints(double maxAcceleration, double maxVelocity) { + io.updateArmConstraints(maxAcceleration, maxVelocity); + } - @AutoLogOutput(key = "Manipulator/Roller Goal") - @Getter - private ManipulatorRollerState rollerGoal; + /** + * Checks if the arm is at the goal position. + * + *

This function checks if the arm is within the goal tolerance of the currently set arm goal + * position. If the arm is within the tolerance, it returns true. Otherwise, it returns false. + * + * @return If the arm is at the goal position. + */ + @AutoLogOutput(key = "Manipulator/Arm At Goal") + public boolean armAtGoal() { + return armAtGoal(armGoal); + } - private boolean isClosedLoop; + public boolean armAtGoal(Rotation2d state) { + return Math.abs(inputs.armPosition.minus(state).getRadians()) + <= V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); + } - Set algaeStates; + public boolean armInTolerance(Rotation2d tolerance) { + return Math.abs(inputs.armPosition.minus(armGoal).getRadians()) <= tolerance.getRadians(); + } - public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { - this.io = io; - inputs = new ManipulatorIOInputsAutoLogged(); + /** + * Waits until the arm is at the goal position. + * + *

This command waits for 0.02 seconds and then checks if the arm is at the goal position. If + * the arm is not at the goal position, it waits for 0.02 seconds and checks again. This process + * repeats until the arm is at the goal position. + * + * @return A command that waits until the arm is at the goal position. + */ + public Command waitUntilArmAtGoal() { + return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::armAtGoal)); + } - isClosedLoop = true; - armGoal = ManipulatorArmState.VERTICAL_UP.getAngle(RobotState.getScoreSide()); - rollerGoal = ManipulatorRollerState.STOP; + /** + * Returns a voltage to hold the roller at the current position. The voltage is calculated based + * on the current torque current of the roller. The calculation is done using a piecewise + * polynomial function. The function first checks if the current torque current is less than or + * equal to 20. If it is, it uses one set of coefficients to calculate the voltage. Otherwise, it + * uses another set of coefficients. + */ + private double holdVoltage() { + return RobotState.isHasAlgae() ? -12.0 : -1; + } - algaeStates = - Set.of( - ManipulatorArmState.ALGAE_INTAKE_FLOOR, - ManipulatorArmState.REEF_INTAKE, - ManipulatorArmState.ALGAE_SCORE); - } + /** + * Sets the current slot of the manipulator arm based on the current state of the subsystem. If + * the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to + * 1. Otherwise, it sets the slot to 0. + */ + public void setSlot() { + if (RobotState.isHasAlgae()) { + io.setSlot(2); + } else if (hasCoral()) { + io.setSlot(1); + } else { + io.setSlot(0); + } + } - public void periodic() { - io.updateInputs(inputs); - Logger.processInputs("Manipulator", inputs); + /** + * Creates a command to run the SysId routine for the manipulator arm, generating the constants + * and gains for a PID. + * + * @param superstructure The V3 Epsiolon Superstructure. + * @return A command to run the SysId routine for the manipulator arm. + */ + public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure, ElevatorFSM elevator) { + SysIdRoutine algaeCharacterizationRoutine = + new SysIdRoutine( + new SysIdRoutine.Config( + Volts.of(0.5).per(Second), + Volts.of(8), + Seconds.of(10), + (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), + new SysIdRoutine.Mechanism( + (volts) -> io.setArmVoltage(volts.in(Volts)), null, superstructure)); + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.L4)), + Commands.runOnce(() -> isClosedLoop = false), + algaeCharacterizationRoutine.quasistatic(Direction.kForward), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.quasistatic(Direction.kReverse), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.dynamic(Direction.kForward), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.dynamic(Direction.kReverse)); + } - if (isClosedLoop) { - io.setArmGoal(armGoal); + /** + * Sets the manipulator arm to the specified state. + * + * @param state The state to set the arm to. + */ + public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmState state) { + io.setManipulatorState(state); } - if (rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { - io.setRollerVoltage(ManipulatorRollerState.SCORE_ALGAE.getVoltage()); - } else if (hasAlgae() - && Set.of( - ManipulatorRollerState.CORAL_INTAKE, - ManipulatorRollerState.STOP, - ManipulatorRollerState.ALGAE_INTAKE) - .contains(rollerGoal) - && !rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { - RobotState.setHasAlgae(true); - io.setRollerVoltage(holdVoltage()); - } else if (hasCoral()) { - io.setRollerVoltage(holdVoltage()); - } else { - io.setRollerVoltage(rollerGoal.getVoltage()); + /** + * Sets the roller goal state of the manipulator. If the subsystem has algae or coral and the goal + * is one of the intake states, it sets the roller voltage to the hold voltage. Otherwise, it sets + * the roller voltage to the goal voltage. + * + * @param rollerGoal The desired state of the roller. + */ + public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState rollerGoal) { + this.rollerGoal = rollerGoal; + if ((hasAlgae() || hasCoral()) + && Set.of( + V3_EpsilonManipulatorConstants.ManipulatorRollerState.ALGAE_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerState.CORAL_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerState.STOP) + .contains(rollerGoal)) { + + io.setRollerVoltage(holdVoltage()); + } else { + io.setRollerVoltage(rollerGoal.getVoltage()); + } } - } - - /** - * Checks if the manipulator is currently detecting coral. This is done by checking if the CAN - * range sensor is detecting a distance less than the coral detection threshold and greater than - * 0. - * - * @return True if the manipulator is detecting coral, false otherwise. - */ - @AutoLogOutput(key = "Manipulator/Has Coral") - public boolean hasCoral() { - return inputs.canRangeGot; - } - - /** - * Checks if the manipulator is currently detecting algae. This is done by checking if the CAN - * range sensor is detecting a distance less than the algae detection threshold and greater than - * 0. - * - * @return True if the manipulator is detecting algae, false otherwise. - */ - @AutoLogOutput(key = "Manipulator/Has Algae") - public boolean hasAlgae() { - boolean hasAlgae = rollerGoal.equals(ManipulatorRollerState.ALGAE_INTAKE) && inputs.canRangeGot; - return hasAlgae; - } - - /** - * Creates a command to run the manipulator arm at a specified voltage. - * - * @param volts The voltage to set the arm to. - * @return A command to run the arm. - */ - public Command runArm(double volts) { - return Commands.runEnd( - () -> { - isClosedLoop = false; - io.setArmVoltage(volts); - }, - () -> io.setArmVoltage(0)); - } - - /** - * Sets the goal for the manipulator arm to reach. - * - * @param goal The goal state to set the arm to. - */ - public void setArmGoal(ManipulatorArmState goal) { - isClosedLoop = true; - if (!algaeStates.contains(goal)) { - armGoal = goal.getAngle(RobotState.getScoreSide()); - } else { - armGoal = goal.getAngle(ScoreSide.CENTER); + + /** + * Gets the current angle of the manipulator arm. + * + * @return The current angle of the manipulator arm, in radians. + */ + public Rotation2d getArmAngle() { + return inputs.armPosition; } - } - - public void setArmGoal(Rotation2d goal) { - isClosedLoop = true; - armGoal = goal; - } - - /** - * Updates the gains for the manipulator arm. This function sets the PID gains for the three slots - * of the arm. The gains are used to control the arm's movement. - * - * @param kP0 The proportional gain for slot 0. - * @param kD0 The derivative gain for slot 0. - * @param kS0 The static gain for slot 0. - * @param kV0 The velocity gain for slot 0. - * @param kA0 The acceleration gain for slot 0. - * @param kG0 The gravity gain for slot 0. - * @param kP1 The proportional gain for slot 1. - * @param kD1 The derivative gain for slot 1. - * @param kS1 The static gain for slot 1. - * @param kV1 The velocity gain for slot 1. - * @param kA1 The acceleration gain for slot 1. - * @param kG1 The gravity gain for slot 1. - * @param kP2 The proportional gain for slot 2. - * @param kD2 The derivative gain for slot 2. - * @param kS2 The static gain for slot 2. - * @param kV2 The velocity gain for slot 2. - * @param kA2 The acceleration gain for slot 2. - * @param kG2 The gravity gain for slot 2. - */ - public void updateArmGains( - double kP0, - double kD0, - double kS0, - double kV0, - double kA0, - double kG0, - double kP1, - double kD1, - double kS1, - double kV1, - double kA1, - double kG1, - double kP2, - double kD2, - double kS2, - double kV2, - double kA2, - double kG2) { - io.updateSlot0ArmGains(kP0, kD0, kS0, kV0, kA0, kG0); - io.updateSlot1ArmGains(kP1, kD1, kS1, kV1, kA1, kG1); - io.updateSlot2ArmGains(kP2, kD2, kS2, kV2, kA2, kG2); - } - - /** - * Updates the constraints for the arm. - * - * @param maxAcceleration The maximum acceleration. - * @param maxVelocity The maximum velocity. - */ - public void updateArmConstraints(double maxAcceleration, double maxVelocity) { - io.updateArmConstraints(maxAcceleration, maxVelocity); - } - - /** - * Checks if the arm is at the goal position. - * - *

This function checks if the arm is within the goal tolerance of the currently set arm goal - * position. If the arm is within the tolerance, it returns true. Otherwise, it returns false. - * - * @return If the arm is at the goal position. - */ - @AutoLogOutput(key = "Manipulator/Arm At Goal") - public boolean armAtGoal() { - return armAtGoal(armGoal); - } - - public boolean armAtGoal(Rotation2d state) { - return Math.abs(inputs.armPosition.minus(state).getRadians()) - <= V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); - } - - public boolean armInTolerance(Rotation2d tolerance) { - return Math.abs(inputs.armPosition.minus(armGoal).getRadians()) <= tolerance.getRadians(); - } - - /** - * Waits until the arm is at the goal position. - * - *

This command waits for 0.02 seconds and then checks if the arm is at the goal position. If - * the arm is not at the goal position, it waits for 0.02 seconds and checks again. This process - * repeats until the arm is at the goal position. - * - * @return A command that waits until the arm is at the goal position. - */ - public Command waitUntilArmAtGoal() { - return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::armAtGoal)); - } - - /** - * Returns a voltage to hold the roller at the current position. The voltage is calculated based - * on the current torque current of the roller. The calculation is done using a piecewise - * polynomial function. The function first checks if the current torque current is less than or - * equal to 20. If it is, it uses one set of coefficients to calculate the voltage. Otherwise, it - * uses another set of coefficients. - */ - private double holdVoltage() { - return hasAlgae() ? -12.0 : -1; - } - - /** - * Sets the current slot of the manipulator arm based on the current state of the subsystem. If - * the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to - * 1. Otherwise, it sets the slot to 0. - */ - public void setSlot() { - if (hasAlgae()) { - io.setSlot(2); - } else if (hasCoral()) { - io.setSlot(1); - } else { - io.setSlot(0); + + public double getArmVelocity() { + return inputs.armVelocityRadiansPerSecond; } - } - - /** - * Creates a command to run the SysId routine for the manipulator arm, generating the constants - * and gains for a PID. - * - * @param superstructure The V3 Epsiolon Superstructure. - * @return A command to run the SysId routine for the manipulator arm. - */ - public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure, ElevatorFSM elevator) { - SysIdRoutine algaeCharacterizationRoutine = - new SysIdRoutine( - new SysIdRoutine.Config( - Volts.of(0.5).per(Second), - Volts.of(8), - Seconds.of(10), - (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), - new SysIdRoutine.Mechanism( - (volts) -> io.setArmVoltage(volts.in(Volts)), null, superstructure)); - return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.L4)), - Commands.runOnce(() -> isClosedLoop = false), - algaeCharacterizationRoutine.quasistatic(Direction.kForward), - Commands.waitSeconds(.25), - algaeCharacterizationRoutine.quasistatic(Direction.kReverse), - Commands.waitSeconds(.25), - algaeCharacterizationRoutine.dynamic(Direction.kForward), - Commands.waitSeconds(.25), - algaeCharacterizationRoutine.dynamic(Direction.kReverse)); - } - - /** - * Sets the manipulator arm to the specified state. - * - * @param state The state to set the arm to. - */ - public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmState state) { - io.setManipulatorState(state); - } - - /** - * Sets the roller goal state of the manipulator. If the subsystem has algae or coral and the goal - * is one of the intake states, it sets the roller voltage to the hold voltage. Otherwise, it sets - * the roller voltage to the goal voltage. - * - * @param rollerGoal The desired state of the roller. - */ - public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState rollerGoal) { - this.rollerGoal = rollerGoal; - if ((hasAlgae() || hasCoral()) - && Set.of( - V3_EpsilonManipulatorConstants.ManipulatorRollerState.ALGAE_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerState.CORAL_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerState.STOP) - .contains(rollerGoal)) { - - io.setRollerVoltage(holdVoltage()); - } else { - io.setRollerVoltage(rollerGoal.getVoltage()); + + public double getRollerVelocity() { + return inputs.rollerVelocityRadiansPerSecond; } - } - - /** - * Gets the current angle of the manipulator arm. - * - * @return The current angle of the manipulator arm, in radians. - */ - public Rotation2d getArmAngle() { - return inputs.armPosition; - } - - public double getArmVelocity() { - return inputs.armVelocityRadiansPerSecond; - } - - public double getRollerVelocity() { - return inputs.rollerVelocityRadiansPerSecond; - } } From 892b777835e100d571e161c1cd591dc7b0fbfc49 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 1 Nov 2025 12:52:00 -0400 Subject: [PATCH 157/180] algae & barge --- .../frc/robot/commands/CompositeCommands.java | 1809 ++++++++--------- .../subsystems/shared/elevator/Elevator.java | 772 ++++--- .../manipulator/V3_EpsilonManipulator.java | 597 +++--- 3 files changed, 1579 insertions(+), 1599 deletions(-) diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 9369fa0c..bed60a98 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -28,7 +28,6 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; import frc.robot.util.AllianceFlipUtil; - import java.util.Set; import java.util.function.BooleanSupplier; import java.util.function.Supplier; @@ -37,923 +36,919 @@ * A class that holds composite commands, which are sequences of commands for complex robot actions. */ public class CompositeCommands { + /** A class that holds composite commands that are shared across different robot versions. */ + public static final class SharedCommands { + /** + * Creates a command to reset the robot's heading to the alliance-specific zero. + * + * @param drive The drive subsystem. + * @return A command to reset the heading. + */ + public static final Command resetHeading(Drive drive) { + return Commands.runOnce( + () -> { + RobotState.resetRobotPose( + new Pose2d( + RobotState.getRobotPoseField().getTranslation(), + AllianceFlipUtil.apply(new Rotation2d()))); + }) + .ignoringDisable(true); + } + + /** + * Creates a command to set a static reef height in the robot state. This does not move any + * mechanisms. + * + * @param height The reef height to set. + * @return A command to set the reef height. + */ + public static final Command setStaticReefHeight(ReefState height) { + return Commands.runOnce(() -> RobotState.setReefHeight(height)); + } + } + + /** A class that holds composite commands for the V1_StackUp robot. */ + public static final class V1_StackUpCompositeCommands { + /** + * Creates a command to intake coral from the station. + * + * @param elevator The elevator subsystem. + * @param funnel The funnel subsystem. + * @param manipulator The manipulator subsystem. + * @return A command to intake coral. + */ + public static final Command intakeCoral( + ElevatorCSB elevator, FunnelCSB funnel, V1_StackUpManipulator manipulator) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setIntakingCoral(true)), + elevator.setPosition(() -> ReefState.CORAL_INTAKE), + Commands.waitUntil(elevator::atGoal), + Commands.race( + manipulator.intakeCoral(), funnel.intakeCoral(() -> manipulator.hasCoral()))) + .finallyDo(() -> RobotState.setIntakingCoral(false)); + } + + /** + * Creates a command to intake coral from the station with an override. + * + * @param elevator The elevator subsystem. + * @param funnel The funnel subsystem. + * @param manipulator The manipulator subsystem. + * @return A command to intake coral with an override. + */ + public static final Command intakeCoralOverride( + ElevatorCSB elevator, FunnelCSB funnel, V1_StackUpManipulator manipulator) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setIntakingCoral(true)), + elevator.setPosition(() -> ReefState.CORAL_INTAKE), + Commands.waitUntil(elevator::atGoal), + Commands.parallel(manipulator.intakeCoral(), funnel.intakeCoral(() -> false))) + .finallyDo(() -> RobotState.setIntakingCoral(false)); + } + + /** + * Creates a command to score coral. + * + * @param manipulator The manipulator subsystem. + * @return A command to score coral. + */ + public static final Command scoreCoral(V1_StackUpManipulator manipulator) { + return manipulator.scoreCoral().withTimeout(0.4); + } + + /** + * Creates a command sequence to score coral, waiting for auto-alignment. + * + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param autoAligned A supplier that returns true when the robot is aligned. + * @return A command sequence to score coral. + */ + public static final Command scoreCoralSequence( + ElevatorCSB elevator, V1_StackUpManipulator manipulator, BooleanSupplier autoAligned) { + return Commands.sequence( + Commands.either( + elevator.setPosition(() -> ReefState.L3), + elevator.setPosition(), + () -> + RobotState.getOIData().currentReefHeight().equals(ReefState.L4) + && !elevator.getPosition().equals(ElevatorPositions.L4)), + Commands.waitUntil(() -> autoAligned.getAsBoolean()), + elevator.setPosition(), + Commands.waitSeconds(0.05), + Commands.waitUntil(elevator::atGoal), + Commands.either( + manipulator.scoreL4Coral().withTimeout(0.4), + manipulator.scoreCoral().withTimeout(0.15), + () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L4))); + } + + /** + * Creates a command sequence to automatically score coral. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param cameras The vision cameras. + * @return A command sequence to auto-score coral. + */ + public static final Command autoScoreCoralSequence( + Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { + return Commands.either( + autoScoreL1CoralSequence(drive, elevator, manipulator, cameras), + Commands.sequence( + Commands.either( + elevator.setPosition(() -> ReefState.L2), + Commands.none(), + () -> + RobotState.getOIData().currentReefHeight().equals(ReefState.L1) + || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) + || RobotState.getOIData() + .currentReefHeight() + .equals(ReefState.CORAL_INTAKE)), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + scoreCoralSequence( + elevator, + manipulator, + () -> RobotState.getReefAlignData().atCoralSetpoint())), + elevator + .setPosition(() -> ReefState.STOW) + .onlyIf( + () -> + elevator.getPosition().equals(ElevatorPositions.L3) + || elevator.getPosition().equals(ElevatorPositions.L2))), + () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); + } + + /** + * Creates a command sequence to automatically score coral at L1. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param cameras The vision cameras. + * @return A command sequence to auto-score coral at L1. + */ + public static final Command autoScoreL1CoralSequence( + Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { + return Commands.sequence( + DriveCommands.autoAlignReefCoral(drive, cameras), + scoreL1Coral(drive, elevator, manipulator)); + } + + /** + * Creates a command to score coral at L1. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @return A command to score coral at L1. + */ + public static final Command scoreL1Coral( + Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator) { + return Commands.sequence( + elevator.setPosition(), + Commands.waitSeconds(0.02), + Commands.waitUntil(elevator::atGoal), + Commands.parallel( + manipulator.scoreL1Coral().withTimeout(0.8), + Commands.sequence( + Commands.waitSeconds(0.05), + Commands.either( + DriveCommands.inchMovement(drive, -1, 0.1), + DriveCommands.inchMovement(drive, 1, 0.1), + () -> RobotState.getOIData().currentReefPost() == ReefPose.LEFT)))); + } + + /** + * Creates a command for an emergency eject of coral. + * + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @return A command to eject coral. + */ + public static final Command emergencyEject( + ElevatorCSB elevator, V1_StackUpManipulator manipulator) { + return Commands.sequence( + elevator.setPosition(() -> ReefState.L1), + Commands.waitSeconds(0.125), + Commands.waitUntil(elevator::atGoal), + manipulator.scoreCoral().withTimeout(0.4), + elevator.setPosition(() -> ReefState.STOW)); + } + + /** + * Creates a command to remove algae from the reef. This uses the closest reef tag to + * automatically pick the reef height. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param cameras The vision cameras. + * @return A command to remove algae. + */ + public static final Command twerk( + Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { + return Commands.deferredProxy( + () -> + twerk( + drive, + elevator, + manipulator, + switch (RobotState.getReefAlignData().closestReefTag()) { + case 10, 6, 8, 21, 17, 19 -> ReefState.ASS_BOT; + case 9, 11, 7, 22, 20, 18 -> ReefState.ASS_TOP; + default -> ReefState.ASS_BOT; + }, + cameras)); + } + + /** + * Creates a command to remove algae from the reef. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param cameras The vision cameras. + * @return A command to remove algae. + */ + public static final Command twerk( + Drive drive, + ElevatorCSB elevator, + V1_StackUpManipulator manipulator, + ReefState level, + Camera... cameras) { + return Commands.sequence( + DriveCommands.autoAlignReefAlgae(drive, cameras), + elevator.setPosition(() -> ReefState.L4), + Commands.waitUntil(elevator::atGoal), + manipulator.toggleAlgaeArm(), + Commands.waitSeconds(0.1), + elevator.setPosition(() -> level), + manipulator.removeAlgae().until(elevator::atGoal), + manipulator.removeAlgae().withTimeout(0.35), + manipulator.toggleAlgaeArm()); + } + + /** + * Creates a command to set the dynamic reef height in the robot state. This sets the height and + * then moves the elevator to that position. + * + * @param height The reef height to set. + * @param elevator The elevator subsystem. + * @return A command to set the dynamic reef height. + */ + public static final Command setDynamicReefHeight(ReefState height, ElevatorCSB elevator) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setReefHeight(height)), elevator.setPosition()); + } + + /** + * Creates a command to climb the robot. + * + * @param elevator The elevator subsystem. + * @param funnel The funnel subsystem. + * @param climber The climber subsystem. + * @param drive The drive subsystem. + * @return A command to climb. + */ + public static final Command climb( + ElevatorCSB elevator, FunnelCSB funnel, Climber climber, Drive drive) { + return Commands.sequence( + elevator.setPosition(() -> ReefState.STOW), + Commands.waitSeconds(0.02), + Commands.waitUntil(elevator::atGoal), + funnel.setClapDaddyGoal(FunnelState.CLIMB), + Commands.parallel( + climber.releaseClimber(), + Commands.waitSeconds( + ClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), + Commands.waitUntil(climber::climberReady), + Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); + } + } + + public static final class V2_RedundancyCompositeCommands { + /** + * Creates a command to intake coral from the station. + * + * @param superstructure The superstructure subsystem. + * @param intake The intake subsystem. + * @return A command to intake coral. + */ + public static final Command intakeCoralDriverSequence( + V2_RedundancySuperstructure superstructure, V2_RedundancyIntake intake) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoalUntil( + V2_RedundancySuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); + } + + /** + * Creates a command to intake coral from the station using the operator sequence. + * + * @param superstructure The superstructure subsystem. + * @param intake The intake subsystem. + * @return A command to intake coral using the operator sequence. + */ + public static final Command intakeCoralOperatorSequence( + V2_RedundancySuperstructure superstructure, V2_RedundancyIntake intake) { + return Commands.sequence( + superstructure.runGoalUntil( + V2_RedundancySuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); + } + + /** + * Creates a command to score coral at L1. + * + * @param drive The drive subsystem. + * @param superstructure The superstructure subsystem. + * @return A command to score coral at L1. + */ + public static final Command scoreL1Coral( + Drive drive, V2_RedundancySuperstructure superstructure) { + return Commands.sequence( + superstructure.runGoal(V2_RedundancySuperstructureStates.L1), + Commands.parallel( + superstructure.runReefScoreGoal(() -> ReefState.L1), + Commands.sequence( + Commands.waitSeconds(0.05), + Commands.either( + DriveCommands.inchMovement(drive, -1, 0.1), + DriveCommands.inchMovement(drive, 1, 0.1), + () -> RobotState.getOIData().currentReefPost() == ReefPose.LEFT)))); + } + + /** + * Creates a command sequence to score coral at L1, waiting for auto-alignment. + * + * @param drive The drive subsystem. + * @param superstructure The superstructure subsystem. + * @return A command sequence to score coral at L1. + */ + public static final Command autoScoreL1CoralSequence( + Drive drive, + ElevatorFSM elevator, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + return Commands.sequence( + DriveCommands.autoAlignReefCoral(drive, cameras), scoreL1Coral(drive, superstructure)); + } + /** - * A class that holds composite commands that are shared across different robot versions. + * Creates a command sequence to score coral, waiting for auto-alignment. + * + * @param elevator The elevator subsystem. + * @param superstructure The superstructure subsystem. + * @param autoAligned A supplier that returns true when the robot is aligned. + * @return A command sequence to score coral. */ - public static final class SharedCommands { - /** - * Creates a command to reset the robot's heading to the alliance-specific zero. - * - * @param drive The drive subsystem. - * @return A command to reset the heading. - */ - public static final Command resetHeading(Drive drive) { - return Commands.runOnce( - () -> { - RobotState.resetRobotPose( - new Pose2d( - RobotState.getRobotPoseField().getTranslation(), - AllianceFlipUtil.apply(new Rotation2d()))); - }) - .ignoringDisable(true); - } - - /** - * Creates a command to set a static reef height in the robot state. This does not move any - * mechanisms. - * - * @param height The reef height to set. - * @return A command to set the reef height. - */ - public static final Command setStaticReefHeight(ReefState height) { - return Commands.runOnce(() -> RobotState.setReefHeight(height)); - } + public static final Command scoreCoralSequence( + ElevatorFSM elevator, + V2_RedundancySuperstructure superstructure, + BooleanSupplier autoAligned) { + return Commands.sequence( + Commands.either( + superstructure.runGoal(V2_RedundancySuperstructureStates.L3), + superstructure.runReefGoal(() -> RobotState.getOIData().currentReefHeight()), + () -> + RobotState.getOIData().currentReefHeight().equals(ReefState.L4) + && !superstructure + .getCurrentState() + .equals(V2_RedundancySuperstructureStates.L4)), + Commands.waitUntil(() -> autoAligned.getAsBoolean()), + superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight()), + superstructure + .runGoal(V2_RedundancySuperstructureStates.STOW_DOWN) + .onlyIf( + () -> + elevator.getPosition().equals(ElevatorPositions.L3) + || elevator.getPosition().equals(ElevatorPositions.L2))); } /** - * A class that holds composite commands for the V1_StackUp robot. + * Creates a command sequence to automatically score coral. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. + * @param superstructure The superstructure subsystem. + * @param cameras The vision cameras. + * @return A command sequence to auto-score coral. */ - public static final class V1_StackUpCompositeCommands { - /** - * Creates a command to intake coral from the station. - * - * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. - * @param manipulator The manipulator subsystem. - * @return A command to intake coral. - */ - public static final Command intakeCoral( - ElevatorCSB elevator, FunnelCSB funnel, V1_StackUpManipulator manipulator) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setIntakingCoral(true)), - elevator.setPosition(() -> ReefState.CORAL_INTAKE), - Commands.waitUntil(elevator::atGoal), - Commands.race( - manipulator.intakeCoral(), funnel.intakeCoral(() -> manipulator.hasCoral()))) - .finallyDo(() -> RobotState.setIntakingCoral(false)); - } - - /** - * Creates a command to intake coral from the station with an override. - * - * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. - * @param manipulator The manipulator subsystem. - * @return A command to intake coral with an override. - */ - public static final Command intakeCoralOverride( - ElevatorCSB elevator, FunnelCSB funnel, V1_StackUpManipulator manipulator) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setIntakingCoral(true)), - elevator.setPosition(() -> ReefState.CORAL_INTAKE), - Commands.waitUntil(elevator::atGoal), - Commands.parallel(manipulator.intakeCoral(), funnel.intakeCoral(() -> false))) - .finallyDo(() -> RobotState.setIntakingCoral(false)); - } - - /** - * Creates a command to score coral. - * - * @param manipulator The manipulator subsystem. - * @return A command to score coral. - */ - public static final Command scoreCoral(V1_StackUpManipulator manipulator) { - return manipulator.scoreCoral().withTimeout(0.4); - } - - /** - * Creates a command sequence to score coral, waiting for auto-alignment. - * - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param autoAligned A supplier that returns true when the robot is aligned. - * @return A command sequence to score coral. - */ - public static final Command scoreCoralSequence( - ElevatorCSB elevator, V1_StackUpManipulator manipulator, BooleanSupplier autoAligned) { - return Commands.sequence( - Commands.either( - elevator.setPosition(() -> ReefState.L3), - elevator.setPosition(), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L4) - && !elevator.getPosition().equals(ElevatorPositions.L4)), - Commands.waitUntil(() -> autoAligned.getAsBoolean()), - elevator.setPosition(), - Commands.waitSeconds(0.05), - Commands.waitUntil(elevator::atGoal), - Commands.either( - manipulator.scoreL4Coral().withTimeout(0.4), - manipulator.scoreCoral().withTimeout(0.15), - () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L4))); - } - - /** - * Creates a command sequence to automatically score coral. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. - * @return A command sequence to auto-score coral. - */ - public static final Command autoScoreCoralSequence( - Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { - return Commands.either( - autoScoreL1CoralSequence(drive, elevator, manipulator, cameras), - Commands.sequence( - Commands.either( - elevator.setPosition(() -> ReefState.L2), - Commands.none(), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L1) - || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) - || RobotState.getOIData() - .currentReefHeight() - .equals(ReefState.CORAL_INTAKE)), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - scoreCoralSequence( - elevator, - manipulator, - () -> RobotState.getReefAlignData().atCoralSetpoint())), - elevator - .setPosition(() -> ReefState.STOW) - .onlyIf( - () -> - elevator.getPosition().equals(ElevatorPositions.L3) - || elevator.getPosition().equals(ElevatorPositions.L2))), - () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); - } - - /** - * Creates a command sequence to automatically score coral at L1. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. - * @return A command sequence to auto-score coral at L1. - */ - public static final Command autoScoreL1CoralSequence( - Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefCoral(drive, cameras), - scoreL1Coral(drive, elevator, manipulator)); - } - - /** - * Creates a command to score coral at L1. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @return A command to score coral at L1. - */ - public static final Command scoreL1Coral( - Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator) { - return Commands.sequence( - elevator.setPosition(), - Commands.waitSeconds(0.02), - Commands.waitUntil(elevator::atGoal), - Commands.parallel( - manipulator.scoreL1Coral().withTimeout(0.8), - Commands.sequence( - Commands.waitSeconds(0.05), - Commands.either( - DriveCommands.inchMovement(drive, -1, 0.1), - DriveCommands.inchMovement(drive, 1, 0.1), - () -> RobotState.getOIData().currentReefPost() == ReefPose.LEFT)))); - } - - /** - * Creates a command for an emergency eject of coral. - * - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @return A command to eject coral. - */ - public static final Command emergencyEject( - ElevatorCSB elevator, V1_StackUpManipulator manipulator) { - return Commands.sequence( - elevator.setPosition(() -> ReefState.L1), - Commands.waitSeconds(0.125), - Commands.waitUntil(elevator::atGoal), - manipulator.scoreCoral().withTimeout(0.4), - elevator.setPosition(() -> ReefState.STOW)); - } - - /** - * Creates a command to remove algae from the reef. This uses the closest reef tag to - * automatically pick the reef height. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. - * @return A command to remove algae. - */ - public static final Command twerk( - Drive drive, ElevatorCSB elevator, V1_StackUpManipulator manipulator, Camera... cameras) { - return Commands.deferredProxy( - () -> - twerk( - drive, - elevator, - manipulator, - switch (RobotState.getReefAlignData().closestReefTag()) { - case 10, 6, 8, 21, 17, 19 -> ReefState.ASS_BOT; - case 9, 11, 7, 22, 20, 18 -> ReefState.ASS_TOP; - default -> ReefState.ASS_BOT; - }, - cameras)); - } - - /** - * Creates a command to remove algae from the reef. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param cameras The vision cameras. - * @return A command to remove algae. - */ - public static final Command twerk( - Drive drive, - ElevatorCSB elevator, - V1_StackUpManipulator manipulator, - ReefState level, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefAlgae(drive, cameras), - elevator.setPosition(() -> ReefState.L4), - Commands.waitUntil(elevator::atGoal), - manipulator.toggleAlgaeArm(), - Commands.waitSeconds(0.1), - elevator.setPosition(() -> level), - manipulator.removeAlgae().until(elevator::atGoal), - manipulator.removeAlgae().withTimeout(0.35), - manipulator.toggleAlgaeArm()); - } - - /** - * Creates a command to set the dynamic reef height in the robot state. This sets the height and - * then moves the elevator to that position. - * - * @param height The reef height to set. - * @param elevator The elevator subsystem. - * @return A command to set the dynamic reef height. - */ - public static final Command setDynamicReefHeight(ReefState height, ElevatorCSB elevator) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setReefHeight(height)), elevator.setPosition()); - } - - /** - * Creates a command to climb the robot. - * - * @param elevator The elevator subsystem. - * @param funnel The funnel subsystem. - * @param climber The climber subsystem. - * @param drive The drive subsystem. - * @return A command to climb. - */ - public static final Command climb( - ElevatorCSB elevator, FunnelCSB funnel, Climber climber, Drive drive) { - return Commands.sequence( - elevator.setPosition(() -> ReefState.STOW), - Commands.waitSeconds(0.02), - Commands.waitUntil(elevator::atGoal), - funnel.setClapDaddyGoal(FunnelState.CLIMB), - Commands.parallel( - climber.releaseClimber(), - Commands.waitSeconds( - ClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), - Commands.waitUntil(climber::climberReady), - Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); - } - } - - public static final class V2_RedundancyCompositeCommands { - /** - * Creates a command to intake coral from the station. - * - * @param superstructure The superstructure subsystem. - * @param intake The intake subsystem. - * @return A command to intake coral. - */ - public static final Command intakeCoralDriverSequence( - V2_RedundancySuperstructure superstructure, V2_RedundancyIntake intake) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoalUntil( - V2_RedundancySuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); - } - - /** - * Creates a command to intake coral from the station using the operator sequence. - * - * @param superstructure The superstructure subsystem. - * @param intake The intake subsystem. - * @return A command to intake coral using the operator sequence. - */ - public static final Command intakeCoralOperatorSequence( - V2_RedundancySuperstructure superstructure, V2_RedundancyIntake intake) { - return Commands.sequence( - superstructure.runGoalUntil( - V2_RedundancySuperstructureStates.INTAKE_STATION, () -> intake.hasCoral()), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); - } - - /** - * Creates a command to score coral at L1. - * - * @param drive The drive subsystem. - * @param superstructure The superstructure subsystem. - * @return A command to score coral at L1. - */ - public static final Command scoreL1Coral( - Drive drive, V2_RedundancySuperstructure superstructure) { - return Commands.sequence( - superstructure.runGoal(V2_RedundancySuperstructureStates.L1), - Commands.parallel( - superstructure.runReefScoreGoal(() -> ReefState.L1), - Commands.sequence( - Commands.waitSeconds(0.05), - Commands.either( - DriveCommands.inchMovement(drive, -1, 0.1), - DriveCommands.inchMovement(drive, 1, 0.1), - () -> RobotState.getOIData().currentReefPost() == ReefPose.LEFT)))); - } - - /** - * Creates a command sequence to score coral at L1, waiting for auto-alignment. - * - * @param drive The drive subsystem. - * @param superstructure The superstructure subsystem. - * @return A command sequence to score coral at L1. - */ - public static final Command autoScoreL1CoralSequence( - Drive drive, - ElevatorFSM elevator, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefCoral(drive, cameras), scoreL1Coral(drive, superstructure)); - } - - /** - * Creates a command sequence to score coral, waiting for auto-alignment. - * - * @param elevator The elevator subsystem. - * @param superstructure The superstructure subsystem. - * @param autoAligned A supplier that returns true when the robot is aligned. - * @return A command sequence to score coral. - */ - public static final Command scoreCoralSequence( - ElevatorFSM elevator, - V2_RedundancySuperstructure superstructure, - BooleanSupplier autoAligned) { - return Commands.sequence( - Commands.either( - superstructure.runGoal(V2_RedundancySuperstructureStates.L3), - superstructure.runReefGoal(() -> RobotState.getOIData().currentReefHeight()), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L4) - && !superstructure - .getCurrentState() - .equals(V2_RedundancySuperstructureStates.L4)), - Commands.waitUntil(() -> autoAligned.getAsBoolean()), - superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight()), - superstructure - .runGoal(V2_RedundancySuperstructureStates.STOW_DOWN) - .onlyIf( - () -> - elevator.getPosition().equals(ElevatorPositions.L3) - || elevator.getPosition().equals(ElevatorPositions.L2))); - } - - /** - * Creates a command sequence to automatically score coral. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param superstructure The superstructure subsystem. - * @param cameras The vision cameras. - * @return A command sequence to auto-score coral. - */ - public static final Command autoScoreCoralSequence( - Drive drive, - ElevatorFSM elevator, - V2_RedundancySuperstructure superstructure, - Camera... cameras) { - - return Commands.either( - Commands.sequence( - autoScoreL1CoralSequence(drive, elevator, superstructure, cameras), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)), - Commands.sequence( - Commands.either( - superstructure.runGoal(V2_RedundancySuperstructureStates.L2), - Commands.none(), - () -> - RobotState.getOIData().currentReefHeight().equals(ReefState.L1) - || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) - || RobotState.getOIData() - .currentReefHeight() - .equals(ReefState.CORAL_INTAKE)), - Commands.parallel( - DriveCommands.autoAlignReefCoral(drive, cameras), - scoreCoralSequence( - elevator, - superstructure, - () -> RobotState.getReefAlignData().atCoralSetpoint())), - superstructure - .l4PlusSequence() - .onlyIf(() -> RobotState.getOIData().currentReefHeight() == ReefState.L4)), - () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); - } - - /** - * Creates a command to intake algae from the reef. This uses the closest reef tag to - * automatically pick the reef height and reef face. - * - * @param drive The drive subsystem. - * @param superstructure The superstructure subsystem. - * @param cameras The vision cameras. - * @return A command to remove algae. - */ - public static final Command intakeAlgaeFromReefSequence( - Drive drive, - V2_RedundancySuperstructure superstructure, - Supplier level, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefAlgae(drive, cameras), - superstructure.runGoalUntil( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V2_RedundancySuperstructureStates.INTAKE_REEF_L3; - case ALGAE_INTAKE_BOTTOM: - return V2_RedundancySuperstructureStates.INTAKE_REEF_L2; - default: - return V2_RedundancySuperstructureStates.STOW_DOWN; - } - }, - () -> RobotState.isHasAlgae()), - Commands.parallel( - Commands.sequence( - Commands.waitSeconds(0.25), - Commands.either( - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_UP), - superstructure.runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V2_RedundancySuperstructureStates.REEF_ACQUISITION_L3; - default: - return V2_RedundancySuperstructureStates.REEF_ACQUISITION_L2; - } - }), - () -> RobotState.isHasAlgae())), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) - .withTimeout(0.5))); - } - - /** - * Creates a command to drop algae from the reef. - * - * @param drive The drive subsystem. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. - * @param superstructure The superstructure subsystem. - * @param level A supplier that provides the current reef level. - * @param cameras The vision cameras. - * @return A command to drop algae from the reef. - */ - public static final Command dropAlgae( - Drive drive, - ElevatorFSM elevator, - V2_RedundancyManipulator manipulator, - V2_RedundancyIntake intake, - V2_RedundancySuperstructure superstructure, - Supplier level, - Camera... cameras) { - return Commands.sequence( - DriveCommands.autoAlignReefAlgae(drive, cameras), - Commands.sequence( - superstructure - .runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V2_RedundancySuperstructureStates.INTAKE_REEF_L3; - case ALGAE_INTAKE_BOTTOM: - return V2_RedundancySuperstructureStates.INTAKE_REEF_L2; - default: - return V2_RedundancySuperstructureStates.STOW_DOWN; - } - }) - .until(() -> RobotState.isHasAlgae()), - Commands.waitSeconds(2.0), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) - .withTimeout(0.5)), - superstructure.runGoal( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V2_RedundancySuperstructureStates.DROP_REEF_L3; - case ALGAE_INTAKE_BOTTOM: - return V2_RedundancySuperstructureStates.DROP_REEF_L2; - default: - return V2_RedundancySuperstructureStates.STOW_DOWN; - } - }), - Commands.waitSeconds(1.0), - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); - } - - /** - * Creates a command sequence for the floor intake of algae. - * - * @param superstructure The superstructure subsystem. - * @return A command sequence for the floor intake. - */ - public static final Command floorIntakeSequence(V2_RedundancySuperstructure superstructure) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoalUntil( - V2_RedundancySuperstructureStates.INTAKE_FLOOR, () -> RobotState.isHasAlgae())); - } - - /** - * Creates a command that posts the floor intake sequence, which can either go up or down based - * on whether the robot has algae. - * - * @param superstructure The superstructure subsystem. - * @return A command that posts the floor intake sequence. - */ - public static final Command postFloorIntakeSequence( - V2_RedundancySuperstructure superstructure) { - return Commands.either( - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_UP), - superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN), - RobotState::isHasAlgae); - } - - /** - * Creates a command to set the dynamic reef height in the robot state. This sets the height and - * then moves the superstructure to that position. - * - * @param height The reef height to set. - * @param superstructure The superstructure subsystem. - * @return A command to set the dynamic reef height. - */ - public static final Command setDynamicReefHeight( - ReefState height, V2_RedundancySuperstructure superstructure) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setReefHeight(height)), superstructure.setPosition()); - } - - /** - * Creates a command to climb the robot. - * - * @param superstructure The superstructure subsystem. - * @param climber The climber subsystem. - * @param drive The drive subsystem. - * @return A command to climb. - */ - public static final Command climb( - V2_RedundancySuperstructure superstructure, Climber climber, Drive drive) { - return Commands.sequence( - superstructure.runGoal(V2_RedundancySuperstructureStates.CLIMB), - Commands.parallel( - climber.releaseClimber(), - Commands.waitSeconds( - ClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), - Commands.waitUntil(climber::climberReady), - Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); - } + public static final Command autoScoreCoralSequence( + Drive drive, + ElevatorFSM elevator, + V2_RedundancySuperstructure superstructure, + Camera... cameras) { + + return Commands.either( + Commands.sequence( + autoScoreL1CoralSequence(drive, elevator, superstructure, cameras), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)), + Commands.sequence( + Commands.either( + superstructure.runGoal(V2_RedundancySuperstructureStates.L2), + Commands.none(), + () -> + RobotState.getOIData().currentReefHeight().equals(ReefState.L1) + || RobotState.getOIData().currentReefHeight().equals(ReefState.STOW) + || RobotState.getOIData() + .currentReefHeight() + .equals(ReefState.CORAL_INTAKE)), + Commands.parallel( + DriveCommands.autoAlignReefCoral(drive, cameras), + scoreCoralSequence( + elevator, + superstructure, + () -> RobotState.getReefAlignData().atCoralSetpoint())), + superstructure + .l4PlusSequence() + .onlyIf(() -> RobotState.getOIData().currentReefHeight() == ReefState.L4)), + () -> RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); } /** - * Creates a command sequence for homing all subsystems in the V2_Redundancy robot. + * Creates a command to intake algae from the reef. This uses the closest reef tag to + * automatically pick the reef height and reef face. * + * @param drive The drive subsystem. + * @param superstructure The superstructure subsystem. + * @param cameras The vision cameras. + * @return A command to remove algae. + */ + public static final Command intakeAlgaeFromReefSequence( + Drive drive, + V2_RedundancySuperstructure superstructure, + Supplier level, + Camera... cameras) { + return Commands.sequence( + DriveCommands.autoAlignReefAlgae(drive, cameras), + superstructure.runGoalUntil( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V2_RedundancySuperstructureStates.INTAKE_REEF_L3; + case ALGAE_INTAKE_BOTTOM: + return V2_RedundancySuperstructureStates.INTAKE_REEF_L2; + default: + return V2_RedundancySuperstructureStates.STOW_DOWN; + } + }, + () -> RobotState.isHasAlgae()), + Commands.parallel( + Commands.sequence( + Commands.waitSeconds(0.25), + Commands.either( + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_UP), + superstructure.runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V2_RedundancySuperstructureStates.REEF_ACQUISITION_L3; + default: + return V2_RedundancySuperstructureStates.REEF_ACQUISITION_L2; + } + }), + () -> RobotState.isHasAlgae())), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) + .withTimeout(0.5))); + } + + /** + * Creates a command to drop algae from the reef. + * + * @param drive The drive subsystem. + * @param elevator The elevator subsystem. * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. - * @param elevator The elevator subsystem. - * @return A command sequence to home all subsystems. + * @param intake The intake subsystem. + * @param superstructure The superstructure subsystem. + * @param level A supplier that provides the current reef level. + * @param cameras The vision cameras. + * @return A command to drop algae from the reef. + */ + public static final Command dropAlgae( + Drive drive, + ElevatorFSM elevator, + V2_RedundancyManipulator manipulator, + V2_RedundancyIntake intake, + V2_RedundancySuperstructure superstructure, + Supplier level, + Camera... cameras) { + return Commands.sequence( + DriveCommands.autoAlignReefAlgae(drive, cameras), + Commands.sequence( + superstructure + .runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V2_RedundancySuperstructureStates.INTAKE_REEF_L3; + case ALGAE_INTAKE_BOTTOM: + return V2_RedundancySuperstructureStates.INTAKE_REEF_L2; + default: + return V2_RedundancySuperstructureStates.STOW_DOWN; + } + }) + .until(() -> RobotState.isHasAlgae()), + Commands.waitSeconds(2.0), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(1.0, 0.0, 0.0)), () -> drive.stop()) + .withTimeout(0.5)), + superstructure.runGoal( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V2_RedundancySuperstructureStates.DROP_REEF_L3; + case ALGAE_INTAKE_BOTTOM: + return V2_RedundancySuperstructureStates.DROP_REEF_L2; + default: + return V2_RedundancySuperstructureStates.STOW_DOWN; + } + }), + Commands.waitSeconds(1.0), + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN)); + } + + /** + * Creates a command sequence for the floor intake of algae. + * + * @param superstructure The superstructure subsystem. + * @return A command sequence for the floor intake. + */ + public static final Command floorIntakeSequence(V2_RedundancySuperstructure superstructure) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoalUntil( + V2_RedundancySuperstructureStates.INTAKE_FLOOR, () -> RobotState.isHasAlgae())); + } + + /** + * Creates a command that posts the floor intake sequence, which can either go up or down based + * on whether the robot has algae. + * + * @param superstructure The superstructure subsystem. + * @return A command that posts the floor intake sequence. + */ + public static final Command postFloorIntakeSequence( + V2_RedundancySuperstructure superstructure) { + return Commands.either( + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_UP), + superstructure.runGoal(V2_RedundancySuperstructureStates.STOW_DOWN), + RobotState::isHasAlgae); + } + + /** + * Creates a command to set the dynamic reef height in the robot state. This sets the height and + * then moves the superstructure to that position. + * + * @param height The reef height to set. + * @param superstructure The superstructure subsystem. + * @return A command to set the dynamic reef height. */ - public static final Command homingSequences( - V2_RedundancyManipulator manipulator, V2_RedundancyIntake intake, ElevatorFSM elevator) { - return Commands.sequence( - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.ALGAE_MID)), - elevator.waitUntilAtGoal(), - manipulator.homingSequence(), - intake.homingSequence(), - Commands.runOnce(() -> elevator.setPosition())); - } - - public static final class V3_EpsilonCompositeCommands { - - public static final Command intakeCoralDriverSequence( - V3_EpsilonSuperstructure superstructure, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - return Commands.sequence( - Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoralLoose()), - superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.HANDOFF, () -> intake.hasCoralLocked()), - postIntakeCoralSequence(superstructure, intake, manipulator)); - } - - public static final Command postIntakeCoralSequence( - V3_EpsilonSuperstructure superstructure, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - return Commands.either( - Commands.either( - Commands.sequence( - superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.HANDOFF_SPIN, () -> manipulator.hasCoral()), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), - Commands.none(), - () -> - !superstructure.getTargetState().equals(V3_EpsilonSuperstructureStates.STOW_UP) - && !superstructure - .getCurrentState() - .equals(V3_EpsilonSuperstructureStates.STOW_UP)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L1), - () -> !RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); - } - - /** - * Creates a command to automatically align the robot to the optimal side of the coral based on - * the current reef height and the robot's orientation. This command sets the score side in the - * RobotState and then runs the auto-alignment command. After the command ends, it resets the - * score side to center. - * - * @param drive The drive subsystem. - * @return A command to auto-align to the optimal side of the coral. - */ - public static final Command optimalAutoScoreCoralSequence( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { - return Commands.either( - Commands.sequence( - superstructure.setPosition(), - DriveCommands.autoAlignReefCoral(drive, cameras) - .until(() -> RobotState.getReefAlignData().atCoralSetpoint()), - superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight())), - superstructure.runGoalUntil(V3_EpsilonSuperstructureStates.L1_SCORE, () -> false), - () -> !RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); - } - - public static final Command optimalAutoScoreCoralSequence( - Drive drive, V3_EpsilonSuperstructure superstructure, ReefState height, Camera... cameras) { - return Commands.sequence( - superstructure.runReefGoal(() -> height), - DriveCommands.autoAlignReefCoral(drive, cameras), - Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), - superstructure - .runReefScoreGoal(() -> height) - .until( - () -> { - if (height.equals(ReefState.L4)) return superstructure.armBelowThreshold(); - else return false; - })); - } - - public static final Command optimalAutoAlignReefAlgae( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { - return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), - DriveCommands.autoAlignReefAlgae(drive, cameras)); - } - - public static final Command optimalScoreBarge(V3_EpsilonSuperstructure superstructure) { - return superstructure - .runGoal(V3_EpsilonSuperstructureStates.BARGE_SCORE) - .andThen( - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.BARGE_SCORE, 1)); - } - - /** - * Creates a command to score coral. - * - * @param superstructure The superstructure subsystem. - * @param goal This is the goal. - * @return A command to score coral. - */ - public static final Command scoreCoral( - V3_EpsilonSuperstructure superstructure, Supplier goal) { - return superstructure.runReefScoreGoal(goal); - } - - /** - * public static final Command intakeAlgaeReef(V3_EpsilonSuperstructure superstructure, - * V3_EpsilonSuperstructureStates goal, V3_EpsilonSuperstructureAction action, V3_EpsilonIntake - * intake, V3_EpsilonSuperstructure hasalgae) { return Commands.sequence( - * superstructure.runGoal(), Commands.run(() -> action.runIntake(intake)), - * superstructure.isHasAlgae() == (edge.getGamePieceEdge() != (GamePieceEdge.NO_ALGAE) ); ); } - */ - - /** - * drive to reef go to algae level (L2 or L3) turn intake on go until it has algae then stow up - */ - public static final Command dropAlgae( - Drive drive, - ElevatorFSM elevator, - V3_EpsilonManipulator manipulator, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, - Supplier level, - Camera... cameras) { - return Commands.sequence( - Commands.parallel( - superstructure.runGoalUntil( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }, - () -> RobotState.isHasAlgae()), - DriveCommands.autoAlignReefAlgae(drive, cameras)), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, 2.0, 0.0)), () -> drive.stop()) - .withTimeout(0.5), - superstructure.runActionWithTimeout( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE_DROP; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; - default: - return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; - } - }, - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE_DROP; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; - default: - return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; - } - }, - () -> 2)) - .finallyDo( - () -> { - RobotState.setHasAlgae(false); - }); - } - - public static final Command intakeAlgaeFromReef( - Drive drive, - V3_EpsilonSuperstructure superstructure, - Supplier level, - Camera... cameras) { - - return Commands.sequence( - Commands.sequence( - superstructure.runGoalUntil( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }, - () -> RobotState.isHasAlgae()), - DriveCommands.autoAlignReefAlgae(drive, cameras)), - Commands.runEnd( - () -> drive.runVelocity(new ChassisSpeeds(0.0, 2.0, 0.0)), () -> drive.stop()) - .withTimeout(0.5), - postIntakeAlgaeFromReef(drive, superstructure, cameras)); - } - - public static final Command intakeAlgaeFromReefAuto( - Drive drive, - V3_EpsilonSuperstructure superstructure, - Supplier level, - Camera... cameras) { - - return Commands.sequence( - Commands.parallel( - superstructure.runGoalUntil( - () -> { - switch (level.get()) { - case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; - case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; - default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; - } - }, - () -> RobotState.isHasAlgae()), - DriveCommands.autoAlignReefAlgae(drive, cameras)), - postIntakeAlgaeFromReef(drive, superstructure, cameras)); - } - - public static final Command postIntakeAlgaeFromReef( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { - return superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP); - } - - public static final Command intakeAlgaeFromReef( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { - return intakeAlgaeFromReef( - drive, superstructure, () -> RobotState.getReefAlignData().algaeIntakeHeight(), cameras); - } - - public static final Command intakeAlgaeFromReefAuto( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { - return intakeAlgaeFromReefAuto( - drive, superstructure, () -> RobotState.getReefAlignData().algaeIntakeHeight(), cameras); - } - - public static final Command emergencyEject( - V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { - return Commands.sequence( - superstructure.override( - () -> { - manipulator.setArmGoal( - frc.robot - .subsystems - .v3_Epsilon - .superstructure - .manipulator - .V3_EpsilonManipulatorConstants - .ManipulatorArmState - .EMERGENCY_EJECT_ANGLE); - manipulator.setRollerGoal( - frc.robot - .subsystems - .v3_Epsilon - .superstructure - .manipulator - .V3_EpsilonManipulatorConstants - .ManipulatorRollerState - .L4_SCORE); - })); - } - - public static final Command intakeAlgaeFloor( - V3_EpsilonSuperstructure superstructure, V3_EpsilonManipulator manipulator) { - return superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) - .until(() -> manipulator.hasAlgae()); // add intake for algae after - } - - public static final Command handoffCoral( - V3_EpsilonSuperstructure superstructure, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF), - Commands.waitUntil(() -> manipulator.hasCoral()), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)); - } - - public static final Command manipulatorGroundIntake( - V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { - return Commands.sequence( - Commands.runOnce( - () -> superstructure.runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE)), - Commands.runOnce(() -> manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE))); - } - - public static final Command setDynamicReefHeight( - ReefState height, V3_EpsilonSuperstructure superstructure) { - return Commands.either( - Commands.sequence( - Commands.runOnce(() -> RobotState.setReefHeight(height)), - superstructure.setPosition()), - Commands.none(), - () -> - Set.of( - V3_EpsilonSuperstructureStates.L2, - V3_EpsilonSuperstructureStates.L3, - V3_EpsilonSuperstructureStates.L4) - .contains(superstructure.getCurrentState())); - } + public static final Command setDynamicReefHeight( + ReefState height, V2_RedundancySuperstructure superstructure) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setReefHeight(height)), superstructure.setPosition()); + } + + /** + * Creates a command to climb the robot. + * + * @param superstructure The superstructure subsystem. + * @param climber The climber subsystem. + * @param drive The drive subsystem. + * @return A command to climb. + */ + public static final Command climb( + V2_RedundancySuperstructure superstructure, Climber climber, Drive drive) { + return Commands.sequence( + superstructure.runGoal(V2_RedundancySuperstructureStates.CLIMB), + Commands.parallel( + climber.releaseClimber(), + Commands.waitSeconds( + ClimberConstants.CLIMBER_TIMING_CONFIG.WAIT_AFTER_RELEASE_SECONDS())), + Commands.waitUntil(climber::climberReady), + Commands.deadline(climber.winchClimber(), Commands.run(drive::stop))); + } + } + + /** + * Creates a command sequence for homing all subsystems in the V2_Redundancy robot. + * + * @param manipulator The manipulator subsystem. + * @param intake The intake subsystem. + * @param elevator The elevator subsystem. + * @return A command sequence to home all subsystems. + */ + public static final Command homingSequences( + V2_RedundancyManipulator manipulator, V2_RedundancyIntake intake, ElevatorFSM elevator) { + return Commands.sequence( + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.ALGAE_MID)), + elevator.waitUntilAtGoal(), + manipulator.homingSequence(), + intake.homingSequence(), + Commands.runOnce(() -> elevator.setPosition())); + } + + public static final class V3_EpsilonCompositeCommands { + + public static final Command intakeCoralDriverSequence( + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + return Commands.sequence( + Commands.runOnce(() -> RobotState.setHasAlgae(false)), + superstructure.runGoalUntil( + V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoralLoose()), + superstructure.runGoalUntil( + V3_EpsilonSuperstructureStates.HANDOFF, () -> intake.hasCoralLocked()), + postIntakeCoralSequence(superstructure, intake, manipulator)); + } + + public static final Command postIntakeCoralSequence( + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + return Commands.either( + Commands.either( + Commands.sequence( + superstructure.runGoalUntil( + V3_EpsilonSuperstructureStates.HANDOFF_SPIN, () -> manipulator.hasCoral()), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), + Commands.none(), + () -> + !superstructure.getTargetState().equals(V3_EpsilonSuperstructureStates.STOW_UP) + && !superstructure + .getCurrentState() + .equals(V3_EpsilonSuperstructureStates.STOW_UP)), + superstructure.runGoal(V3_EpsilonSuperstructureStates.L1), + () -> !RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); + } + + /** + * Creates a command to automatically align the robot to the optimal side of the coral based on + * the current reef height and the robot's orientation. This command sets the score side in the + * RobotState and then runs the auto-alignment command. After the command ends, it resets the + * score side to center. + * + * @param drive The drive subsystem. + * @return A command to auto-align to the optimal side of the coral. + */ + public static final Command optimalAutoScoreCoralSequence( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + return Commands.either( + Commands.sequence( + superstructure.setPosition(), + DriveCommands.autoAlignReefCoral(drive, cameras) + .until(() -> RobotState.getReefAlignData().atCoralSetpoint()), + superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight())), + superstructure.runGoalUntil(V3_EpsilonSuperstructureStates.L1_SCORE, () -> false), + () -> !RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); + } + + public static final Command optimalAutoScoreCoralSequence( + Drive drive, V3_EpsilonSuperstructure superstructure, ReefState height, Camera... cameras) { + return Commands.sequence( + superstructure.runReefGoal(() -> height), + DriveCommands.autoAlignReefCoral(drive, cameras), + Commands.waitUntil(() -> RobotState.getReefAlignData().atCoralSetpoint()), + superstructure + .runReefScoreGoal(() -> height) + .until( + () -> { + if (height.equals(ReefState.L4)) return superstructure.armBelowThreshold(); + else return false; + })); + } + + public static final Command optimalAutoAlignReefAlgae( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), + DriveCommands.autoAlignReefAlgae(drive, cameras)); + } + + public static final Command optimalScoreBarge(V3_EpsilonSuperstructure superstructure) { + return superstructure + .runGoal(V3_EpsilonSuperstructureStates.BARGE_SCORE) + .andThen( + superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.BARGE_SCORE, 1)); + } + + /** + * Creates a command to score coral. + * + * @param superstructure The superstructure subsystem. + * @param goal This is the goal. + * @return A command to score coral. + */ + public static final Command scoreCoral( + V3_EpsilonSuperstructure superstructure, Supplier goal) { + return superstructure.runReefScoreGoal(goal); + } + + /** + * public static final Command intakeAlgaeReef(V3_EpsilonSuperstructure superstructure, + * V3_EpsilonSuperstructureStates goal, V3_EpsilonSuperstructureAction action, V3_EpsilonIntake + * intake, V3_EpsilonSuperstructure hasalgae) { return Commands.sequence( + * superstructure.runGoal(), Commands.run(() -> action.runIntake(intake)), + * superstructure.isHasAlgae() == (edge.getGamePieceEdge() != (GamePieceEdge.NO_ALGAE) ); ); } + */ + + /** + * drive to reef go to algae level (L2 or L3) turn intake on go until it has algae then stow up + */ + public static final Command dropAlgae( + Drive drive, + ElevatorFSM elevator, + V3_EpsilonManipulator manipulator, + V3_EpsilonIntake intake, + V3_EpsilonSuperstructure superstructure, + Supplier level, + Camera... cameras) { + return Commands.sequence( + Commands.parallel( + superstructure.runGoalUntil( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }, + () -> RobotState.isHasAlgae()), + DriveCommands.autoAlignReefAlgae(drive, cameras)), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, 2.0, 0.0)), () -> drive.stop()) + .withTimeout(0.5), + superstructure.runActionWithTimeout( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE_DROP; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + default: + return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + } + }, + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE_DROP; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + default: + return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + } + }, + () -> 2)) + .finallyDo( + () -> { + RobotState.setHasAlgae(false); + }); + } + + public static final Command intakeAlgaeFromReef( + Drive drive, + V3_EpsilonSuperstructure superstructure, + Supplier level, + Camera... cameras) { + + return Commands.sequence( + Commands.sequence( + superstructure.runGoalUntil( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }, + () -> RobotState.isHasAlgae()), + DriveCommands.autoAlignReefAlgae(drive, cameras)), + Commands.runEnd( + () -> drive.runVelocity(new ChassisSpeeds(0.0, 2.0, 0.0)), () -> drive.stop()) + .withTimeout(0.5), + postIntakeAlgaeFromReef(drive, superstructure, cameras)); + } + + public static final Command intakeAlgaeFromReefAuto( + Drive drive, + V3_EpsilonSuperstructure superstructure, + Supplier level, + Camera... cameras) { + + return Commands.sequence( + Commands.parallel( + superstructure.runGoalUntil( + () -> { + switch (level.get()) { + case ALGAE_INTAKE_TOP: + return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; + case ALGAE_INTAKE_BOTTOM: + return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; + default: + return V3_EpsilonSuperstructureStates.STOW_DOWN; + } + }, + () -> RobotState.isHasAlgae()), + DriveCommands.autoAlignReefAlgae(drive, cameras)), + postIntakeAlgaeFromReef(drive, superstructure, cameras)); + } + + public static final Command postIntakeAlgaeFromReef( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + return superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP); + } + + public static final Command intakeAlgaeFromReef( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + return intakeAlgaeFromReef( + drive, superstructure, () -> RobotState.getReefAlignData().algaeIntakeHeight(), cameras); + } + + public static final Command intakeAlgaeFromReefAuto( + Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + return intakeAlgaeFromReefAuto( + drive, superstructure, () -> RobotState.getReefAlignData().algaeIntakeHeight(), cameras); + } + + public static final Command emergencyEject( + V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { + return Commands.sequence( + superstructure.override( + () -> { + manipulator.setArmGoal( + frc.robot + .subsystems + .v3_Epsilon + .superstructure + .manipulator + .V3_EpsilonManipulatorConstants + .ManipulatorArmState + .EMERGENCY_EJECT_ANGLE); + manipulator.setRollerGoal( + frc.robot + .subsystems + .v3_Epsilon + .superstructure + .manipulator + .V3_EpsilonManipulatorConstants + .ManipulatorRollerState + .L4_SCORE); + })); + } + + public static final Command intakeAlgaeFloor( + V3_EpsilonSuperstructure superstructure, V3_EpsilonManipulator manipulator) { + return superstructure + .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .until(() -> manipulator.hasAlgae()); // add intake for algae after + } + + public static final Command handoffCoral( + V3_EpsilonSuperstructure superstructure, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF), + Commands.waitUntil(() -> manipulator.hasCoral()), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)); + } + + public static final Command manipulatorGroundIntake( + V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { + return Commands.sequence( + Commands.runOnce( + () -> superstructure.runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE)), + Commands.runOnce(() -> manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE))); + } + + public static final Command setDynamicReefHeight( + ReefState height, V3_EpsilonSuperstructure superstructure) { + return Commands.either( + Commands.sequence( + Commands.runOnce(() -> RobotState.setReefHeight(height)), + superstructure.setPosition()), + Commands.none(), + () -> + Set.of( + V3_EpsilonSuperstructureStates.L2, + V3_EpsilonSuperstructureStates.L3, + V3_EpsilonSuperstructureStates.L4) + .contains(superstructure.getCurrentState())); } + } } diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java index 684752c0..47f7e374 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java @@ -1,5 +1,8 @@ package frc.robot.subsystems.shared.elevator; +import static edu.wpi.first.units.Units.*; +import static frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions.L4; + import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; @@ -19,445 +22,428 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.util.ExternalLoggedTracer; import frc.robot.util.InternalLoggedTracer; +import java.util.function.BooleanSupplier; +import java.util.function.Supplier; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; -import java.util.function.BooleanSupplier; -import java.util.function.Supplier; +public class Elevator { + private final ElevatorIO io; + private final ElevatorIOInputsAutoLogged inputs; + + // --- MODIFIED: Store the goal primarily as a double for flexibility --- + private double positionGoalMeters; + private ElevatorPositions lastKnownPositionEnum; // Keep track of the last named position + private boolean isClosedLoop; + + public Elevator(ElevatorIO io) { + this.io = io; + this.inputs = new ElevatorIOInputsAutoLogged(); + + // Initialize to STOW position + this.lastKnownPositionEnum = ElevatorPositions.STOW; + this.positionGoalMeters = lastKnownPositionEnum.getPosition(); + isClosedLoop = true; + } + + private void periodic() { + InternalLoggedTracer.reset(); + io.updateInputs(inputs); + InternalLoggedTracer.record("Update Inputs", "Elevator/Periodic"); + + InternalLoggedTracer.reset(); + Logger.processInputs("Elevator", inputs); + InternalLoggedTracer.record("Process Inputs", "Elevator/Periodic"); + + Logger.recordOutput( + "Elevator/Position", + lastKnownPositionEnum != null ? lastKnownPositionEnum.name() : "CUSTOM"); + + InternalLoggedTracer.reset(); + if (isClosedLoop) { + // Always use the double goal for the IO layer + io.setPositionGoal(positionGoalMeters); + } + InternalLoggedTracer.record("Set Position Goal", "Elevator/Periodic"); + } + + /** + * Gets the elevator position enum for a given reef state. + * + * @param newPosition The reef state. + * @return The corresponding elevator position. + */ + private ElevatorPositions getPosition(ReefState newPosition) { + return ElevatorConstants.REEF_STATE_ELEVATOR_POSITION_MAP.get(newPosition); + } + + /** + * Gets the current position of the elevator. + * + * @return The current elevator position. + */ + private double getPositionMeters(ElevatorIOInputs inputs) { + return inputs.positionMeters; + } + + /** + * Gets the feedforward characterization velocity. + * + * @return The feedforward characterization velocity. + */ + private double getFFCharacterizationVelocity(ElevatorIOInputs inputs) { + return inputs.velocityMetersPerSecond + * ElevatorConstants.ELEVATOR_GEAR_RATIO + / (2 * Math.PI * ElevatorConstants.DRUM_RADIUS); + } + + /** + * Sets the control gains for the elevator. + * + * @param kP The proportional gain. + * @param kD The derivative gain. + * @param kS The static gain. + * @param kV The velocity gain. + * @param kA The acceleration gain. + * @param kG The gravity gain. + */ + private void setGains(double kP, double kD, double kS, double kV, double kA, double kG) { + io.updateGains(kP, kD, kS, kV, kA, kG); + } + + /** + * Sets the motion constraints for the elevator. + * + * @param maxAcceleration The maximum acceleration. + * @param cruisingVelocity The cruising velocity. + */ + private void setConstraints(double maxAcceleration, double cruisingVelocity) { + io.updateConstraints(maxAcceleration, cruisingVelocity); + } + + /** + * Checks if the elevator is at the goal position within a specified tolerance. + * + * @param position The target position in meters. + * @return true if the current position is within the goal tolerance of the target position, false + * otherwise. + */ + private boolean atGoal(double position) { + return Math.abs(position - inputs.positionMeters) + <= ElevatorConstants.CONSTRAINTS.goalToleranceMeters().get(); + } + + /** + * Checks if the elevator is at the goal position. + * + * @return True if the elevator is at the goal position, false otherwise. + */ + @AutoLogOutput(key = "Elevator/At Goal") + private boolean atGoal() { + return Math.abs(positionGoalMeters - inputs.positionMeters) + <= ElevatorConstants.CONSTRAINTS.goalToleranceMeters().get(); + } + + /** + * Checks if the elevator is at the goal position. + * + * @return True if the elevator is at the goal position, false otherwise. + */ + @AutoLogOutput(key = "Elevator/At Goal") + private boolean atGoal(ElevatorPositions position) { + return Math.abs(position.getPosition() - inputs.positionMeters) + <= ElevatorConstants.CONSTRAINTS.goalToleranceMeters().get(); + } + + /** + * Waits until the elevator is at the goal position. + * + * @return A command that waits until the elevator is at the goal position. + */ + private Command waitUntilAtGoal() { + return Commands.waitSeconds(0.02).andThen(Commands.waitUntil(() -> atGoal())); + } + + /** + * Checks if the elevator is within a fast scoring tolerance of the goal position. + * + * @return A BooleanSupplier that returns true if the elevator is within the fast scoring + * tolerance, false otherwise. + */ + private BooleanSupplier inFastScoringTolerance() { + return () -> Math.abs(inputs.positionMeters - positionGoalMeters) <= 0.03; + } + + /** + * Runs the SysId routine for the elevator subsystem. + * + * @param subsystem The subsystem to run the SysId routine on. + * @return A command that runs the SysId routine. + */ + private Command sysIdRoutine(Subsystem subsystem) { + + SysIdRoutine characterizationRoutine = + new SysIdRoutine( + new SysIdRoutine.Config( + Volts.of(1).per(Second), + Volts.of(3), + Seconds.of(3), + (state) -> Logger.recordOutput("Elevator/SysID State", state.toString())), + new SysIdRoutine.Mechanism((volts) -> io.setVoltage(volts.in(Volts)), null, subsystem)); + + return Commands.sequence( + Commands.runOnce( + () -> { + isClosedLoop = false; + }), + characterizationRoutine + .quasistatic(Direction.kForward) + .until(() -> Elevator.this.atGoal(L4.getPosition() - Units.inchesToMeters(12.0))), + characterizationRoutine + .quasistatic(Direction.kReverse) + .until( + () -> + Elevator.this.atGoal( + ElevatorPositions.STOW.getPosition() + Units.inchesToMeters(12.0))), + characterizationRoutine + .dynamic(Direction.kForward) + .until(() -> Elevator.this.atGoal(L4.getPosition() - Units.inchesToMeters(12.0))), + characterizationRoutine + .dynamic(Direction.kReverse) + .until( + () -> + Elevator.this.atGoal( + ElevatorPositions.STOW.getPosition() + Units.inchesToMeters(12.0))), + subsystem.runOnce(() -> setPositionFromReef(() -> ReefState.STOW))); + } + + /** Private method to set position based on ReefState. */ + private void setPositionFromReef(Supplier newPosition) { + isClosedLoop = true; + this.lastKnownPositionEnum = getPosition(newPosition.get()); + this.positionGoalMeters = this.lastKnownPositionEnum.getPosition(); + } + + /** Private method to set position based on ElevatorPositions enum. */ + private void setPositionFromEnum(ElevatorPositions newPosition) { + isClosedLoop = true; + this.lastKnownPositionEnum = newPosition; + this.positionGoalMeters = this.lastKnownPositionEnum.getPosition(); + } + + /** Private method to set position based on a double value. */ + private void setPositionFromDouble(double newPositionMeters) { + isClosedLoop = true; + this.positionGoalMeters = newPositionMeters; + // When a raw double is commanded, there's no corresponding enum state. + this.lastKnownPositionEnum = null; + } + + public class ElevatorCSB extends SubsystemBase { + + @Override + public void periodic() { + ExternalLoggedTracer.reset(); + Elevator.this.periodic(); + ExternalLoggedTracer.record("Elevator Total", "Elevator/Periodic"); + } -import static edu.wpi.first.units.Units.*; -import static frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions.L4; + public ElevatorPositions getPosition() { + return Elevator.this.lastKnownPositionEnum; + } -public class Elevator { - private final ElevatorIO io; - private final ElevatorIOInputsAutoLogged inputs; + /** + * Creates a command to set the elevator to a pre-defined position. + * + * @param newPosition The target ElevatorPositions enum. + * @return A command that sets the elevator position. + */ + public Command setPosition(ElevatorPositions newPosition) { + return this.runOnce(() -> Elevator.this.setPositionFromEnum(newPosition)); + } - // --- MODIFIED: Store the goal primarily as a double for flexibility --- - private double positionGoalMeters; - private ElevatorPositions lastKnownPositionEnum; // Keep track of the last named position - private boolean isClosedLoop; + /** + * Creates a command to set the elevator to a specific height in meters. + * + * @param newPositionMeters The target height in meters. + * @return A command that sets the elevator position. + */ + public Command setPosition(double newPositionMeters) { + return this.runOnce(() -> Elevator.this.setPositionFromDouble(newPositionMeters)); + } - public Elevator(ElevatorIO io) { - this.io = io; - this.inputs = new ElevatorIOInputsAutoLogged(); + public Command setPosition(Supplier newPosition) { + return this.runOnce(() -> Elevator.this.setPositionFromReef(newPosition)); + } - // Initialize to STOW position - this.lastKnownPositionEnum = ElevatorPositions.STOW; - this.positionGoalMeters = lastKnownPositionEnum.getPosition(); - isClosedLoop = true; + public Command setPosition() { + return Commands.runOnce( + () -> + Elevator.this.setPositionFromReef(() -> RobotState.getOIData().currentReefHeight())); } - private void periodic() { - InternalLoggedTracer.reset(); - io.updateInputs(inputs); - InternalLoggedTracer.record("Update Inputs", "Elevator/Periodic"); + public Command setVoltage(double volts) { + return this.runEnd( + () -> { + isClosedLoop = false; + io.setVoltage(volts); + }, + () -> io.setVoltage(0.0)); + } - InternalLoggedTracer.reset(); - Logger.processInputs("Elevator", inputs); - InternalLoggedTracer.record("Process Inputs", "Elevator/Periodic"); + public Command resetPosition() { + return runOnce(() -> Elevator.this.lastKnownPositionEnum = ElevatorPositions.STOW) + .andThen( + runOnce( + () -> io.setPosition(ElevatorConstants.ELEVATOR_PARAMETERS.MIN_HEIGHT_METERS()))); + } - Logger.recordOutput( - "Elevator/Position", - lastKnownPositionEnum != null ? lastKnownPositionEnum.name() : "CUSTOM"); + public Command sysIdRoutine() { + return Elevator.this.sysIdRoutine(this); + } - InternalLoggedTracer.reset(); - if (isClosedLoop) { - // Always use the double goal for the IO layer - io.setPositionGoal(positionGoalMeters); - } - InternalLoggedTracer.record("Set Position Goal", "Elevator/Periodic"); + public double getPositionMeters() { + return Elevator.this.getPositionMeters(inputs); } - /** - * Gets the elevator position enum for a given reef state. - * - * @param newPosition The reef state. - * @return The corresponding elevator position. - */ - private ElevatorPositions getPosition(ReefState newPosition) { - return ElevatorConstants.REEF_STATE_ELEVATOR_POSITION_MAP.get(newPosition); + public double getFFCharacterizationVelocity() { + return Elevator.this.getFFCharacterizationVelocity(inputs); } - /** - * Gets the current position of the elevator. - * - * @return The current elevator position. - */ - private double getPositionMeters(ElevatorIOInputs inputs) { - return inputs.positionMeters; + public void setGains(double kP, double kD, double kS, double kV, double kA, double kG) { + Elevator.this.setGains(kP, kD, kS, kV, kA, kG); } - /** - * Gets the feedforward characterization velocity. - * - * @return The feedforward characterization velocity. - */ - private double getFFCharacterizationVelocity(ElevatorIOInputs inputs) { - return inputs.velocityMetersPerSecond - * ElevatorConstants.ELEVATOR_GEAR_RATIO - / (2 * Math.PI * ElevatorConstants.DRUM_RADIUS); + public void setConstraints(double maxAcceleration, double cruisingVelocity) { + Elevator.this.setConstraints(maxAcceleration, cruisingVelocity); } - /** - * Sets the control gains for the elevator. - * - * @param kP The proportional gain. - * @param kD The derivative gain. - * @param kS The static gain. - * @param kV The velocity gain. - * @param kA The acceleration gain. - * @param kG The gravity gain. - */ - private void setGains(double kP, double kD, double kS, double kV, double kA, double kG) { - io.updateGains(kP, kD, kS, kV, kA, kG); + public boolean atGoal() { + return Elevator.this.atGoal(); } - /** - * Sets the motion constraints for the elevator. - * - * @param maxAcceleration The maximum acceleration. - * @param cruisingVelocity The cruising velocity. - */ - private void setConstraints(double maxAcceleration, double cruisingVelocity) { - io.updateConstraints(maxAcceleration, cruisingVelocity); + public Command waitUntilAtGoal() { + return Elevator.this.waitUntilAtGoal(); } - /** - * Checks if the elevator is at the goal position within a specified tolerance. - * - * @param position The target position in meters. - * @return true if the current position is within the goal tolerance of the target position, false - * otherwise. - */ - private boolean atGoal(double position) { - return Math.abs(position - inputs.positionMeters) - <= ElevatorConstants.CONSTRAINTS.goalToleranceMeters().get(); + public BooleanSupplier inFastScoringTolerance() { + return Elevator.this.inFastScoringTolerance(); + } + } + + // FSM for the Elevator + public class ElevatorFSM { + @AutoLogOutput(key = "Elevator/Past Barge Threshold") + public boolean pastBargeThresholdgetPositionMeters() { + if (Constants.getMode() == Mode.REAL) return inputs.positionMeters >= L4.getPosition(); + else { + return inputs.positionMeters > .95; + } } - /** - * Checks if the elevator is at the goal position. - * - * @return True if the elevator is at the goal position, false otherwise. - */ - @AutoLogOutput(key = "Elevator/At Goal") - private boolean atGoal() { - return Math.abs(positionGoalMeters - inputs.positionMeters) - <= ElevatorConstants.CONSTRAINTS.goalToleranceMeters().get(); + public void periodic() { + ExternalLoggedTracer.reset(); + Elevator.this.periodic(); + ExternalLoggedTracer.record("Elevator Total", "Elevator/Periodic"); } - /** - * Checks if the elevator is at the goal position. - * - * @return True if the elevator is at the goal position, false otherwise. - */ - @AutoLogOutput(key = "Elevator/At Goal") - private boolean atGoal(ElevatorPositions position) { - return Math.abs(position.getPosition() - inputs.positionMeters) - <= ElevatorConstants.CONSTRAINTS.goalToleranceMeters().get(); + public ElevatorPositions getPosition() { + return Elevator.this.lastKnownPositionEnum; } /** - * Waits until the elevator is at the goal position. + * Sets the elevator to a pre-defined position. * - * @return A command that waits until the elevator is at the goal position. + * @param newPosition The target ElevatorPositions enum. */ - private Command waitUntilAtGoal() { - return Commands.waitSeconds(0.02).andThen(Commands.waitUntil(() -> atGoal())); + public void setPosition(ElevatorPositions newPosition) { + Elevator.this.setPositionFromEnum(newPosition); } /** - * Checks if the elevator is within a fast scoring tolerance of the goal position. + * Sets the elevator to a specific height in meters. * - * @return A BooleanSupplier that returns true if the elevator is within the fast scoring - * tolerance, false otherwise. + * @param newPositionMeters The target height in meters. */ - private BooleanSupplier inFastScoringTolerance() { - return () -> Math.abs(inputs.positionMeters - positionGoalMeters) <= 0.03; + public void setPosition(double newPositionMeters) { + Elevator.this.setPositionFromDouble(newPositionMeters); } - /** - * Runs the SysId routine for the elevator subsystem. - * - * @param subsystem The subsystem to run the SysId routine on. - * @return A command that runs the SysId routine. - */ - private Command sysIdRoutine(Subsystem subsystem) { - - SysIdRoutine characterizationRoutine = - new SysIdRoutine( - new SysIdRoutine.Config( - Volts.of(1).per(Second), - Volts.of(3), - Seconds.of(3), - (state) -> Logger.recordOutput("Elevator/SysID State", state.toString())), - new SysIdRoutine.Mechanism((volts) -> io.setVoltage(volts.in(Volts)), null, subsystem)); - - return Commands.sequence( - Commands.runOnce( - () -> { - isClosedLoop = false; - }), - characterizationRoutine - .quasistatic(Direction.kForward) - .until( - () -> - Elevator.this.atGoal( - L4.getPosition() - Units.inchesToMeters(12.0))), - characterizationRoutine - .quasistatic(Direction.kReverse) - .until( - () -> - Elevator.this.atGoal( - ElevatorPositions.STOW.getPosition() + Units.inchesToMeters(12.0))), - characterizationRoutine - .dynamic(Direction.kForward) - .until( - () -> - Elevator.this.atGoal( - L4.getPosition() - Units.inchesToMeters(12.0))), - characterizationRoutine - .dynamic(Direction.kReverse) - .until( - () -> - Elevator.this.atGoal( - ElevatorPositions.STOW.getPosition() + Units.inchesToMeters(12.0))), - subsystem.runOnce(() -> setPositionFromReef(() -> ReefState.STOW))); + public void setPosition(Supplier newPosition) { + Elevator.this.setPositionFromReef(newPosition); } - /** - * Private method to set position based on ReefState. - */ - private void setPositionFromReef(Supplier newPosition) { - isClosedLoop = true; - this.lastKnownPositionEnum = getPosition(newPosition.get()); - this.positionGoalMeters = this.lastKnownPositionEnum.getPosition(); + public void setPosition() { + Elevator.this.setPositionFromReef(() -> RobotState.getOIData().currentReefHeight()); } - /** - * Private method to set position based on ElevatorPositions enum. - */ - private void setPositionFromEnum(ElevatorPositions newPosition) { - isClosedLoop = true; - this.lastKnownPositionEnum = newPosition; - this.positionGoalMeters = this.lastKnownPositionEnum.getPosition(); + public Command resetPosition() { + return Commands.runOnce(() -> Elevator.this.lastKnownPositionEnum = ElevatorPositions.STOW) + .andThen( + Commands.runOnce( + () -> io.setPosition(ElevatorConstants.ELEVATOR_PARAMETERS.MIN_HEIGHT_METERS()))); } - /** - * Private method to set position based on a double value. - */ - private void setPositionFromDouble(double newPositionMeters) { - isClosedLoop = true; - this.positionGoalMeters = newPositionMeters; - // When a raw double is commanded, there's no corresponding enum state. - this.lastKnownPositionEnum = null; - } - - public class ElevatorCSB extends SubsystemBase { - - @Override - public void periodic() { - ExternalLoggedTracer.reset(); - Elevator.this.periodic(); - ExternalLoggedTracer.record("Elevator Total", "Elevator/Periodic"); - } - - public ElevatorPositions getPosition() { - return Elevator.this.lastKnownPositionEnum; - } - - /** - * Creates a command to set the elevator to a pre-defined position. - * - * @param newPosition The target ElevatorPositions enum. - * @return A command that sets the elevator position. - */ - public Command setPosition(ElevatorPositions newPosition) { - return this.runOnce(() -> Elevator.this.setPositionFromEnum(newPosition)); - } - - /** - * Creates a command to set the elevator to a specific height in meters. - * - * @param newPositionMeters The target height in meters. - * @return A command that sets the elevator position. - */ - public Command setPosition(double newPositionMeters) { - return this.runOnce(() -> Elevator.this.setPositionFromDouble(newPositionMeters)); - } - - public Command setPosition(Supplier newPosition) { - return this.runOnce(() -> Elevator.this.setPositionFromReef(newPosition)); - } - - public Command setPosition() { - return Commands.runOnce( - () -> - Elevator.this.setPositionFromReef(() -> RobotState.getOIData().currentReefHeight())); - } - - public Command setVoltage(double volts) { - return this.runEnd( - () -> { - isClosedLoop = false; - io.setVoltage(volts); - }, - () -> io.setVoltage(0.0)); - } - - public Command resetPosition() { - return runOnce(() -> Elevator.this.lastKnownPositionEnum = ElevatorPositions.STOW) - .andThen( - runOnce( - () -> io.setPosition(ElevatorConstants.ELEVATOR_PARAMETERS.MIN_HEIGHT_METERS()))); - } - - public Command sysIdRoutine() { - return Elevator.this.sysIdRoutine(this); - } - - public double getPositionMeters() { - return Elevator.this.getPositionMeters(inputs); - } - - public double getFFCharacterizationVelocity() { - return Elevator.this.getFFCharacterizationVelocity(inputs); - } - - public void setGains(double kP, double kD, double kS, double kV, double kA, double kG) { - Elevator.this.setGains(kP, kD, kS, kV, kA, kG); - } - - public void setConstraints(double maxAcceleration, double cruisingVelocity) { - Elevator.this.setConstraints(maxAcceleration, cruisingVelocity); - } - - public boolean atGoal() { - return Elevator.this.atGoal(); - } - - public Command waitUntilAtGoal() { - return Elevator.this.waitUntilAtGoal(); - } - - public BooleanSupplier inFastScoringTolerance() { - return Elevator.this.inFastScoringTolerance(); - } - } - - // FSM for the Elevator - public class ElevatorFSM { - @AutoLogOutput(key = "Elevator/Past Barge Threshold") - public boolean pastBargeThresholdgetPositionMeters() { - if (Constants.getMode() == Mode.REAL) - return inputs.positionMeters >= L4.getPosition(); - else { - return inputs.positionMeters > .95; - } - } - - public void periodic() { - ExternalLoggedTracer.reset(); - Elevator.this.periodic(); - ExternalLoggedTracer.record("Elevator Total", "Elevator/Periodic"); - } - - public ElevatorPositions getPosition() { - return Elevator.this.lastKnownPositionEnum; - } - - /** - * Sets the elevator to a pre-defined position. - * - * @param newPosition The target ElevatorPositions enum. - */ - public void setPosition(ElevatorPositions newPosition) { - Elevator.this.setPositionFromEnum(newPosition); - } - - /** - * Sets the elevator to a specific height in meters. - * - * @param newPositionMeters The target height in meters. - */ - public void setPosition(double newPositionMeters) { - Elevator.this.setPositionFromDouble(newPositionMeters); - } - - public void setPosition(Supplier newPosition) { - Elevator.this.setPositionFromReef(newPosition); - } - - public void setPosition() { - Elevator.this.setPositionFromReef(() -> RobotState.getOIData().currentReefHeight()); - } - - public Command resetPosition() { - return Commands.runOnce(() -> Elevator.this.lastKnownPositionEnum = ElevatorPositions.STOW) - .andThen( - Commands.runOnce( - () -> io.setPosition(ElevatorConstants.ELEVATOR_PARAMETERS.MIN_HEIGHT_METERS()))); - } - - public Command sysIdRoutine(V2_RedundancySuperstructure superstructure) { - - return Commands.sequence( - superstructure.runGoal(V2_RedundancySuperstructureStates.OVERRIDE), - Elevator.this.sysIdRoutine(superstructure)); - } - - public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { - - return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), - Elevator.this.sysIdRoutine(superstructure)); - } - - public double getPositionMeters() { - return Elevator.this.getPositionMeters(inputs); - } - - public double getFFCharacterizationVelocity() { - return Elevator.this.getFFCharacterizationVelocity(inputs); - } - - public void setGains(double kP, double kD, double kS, double kV, double kA, double kG) { - Elevator.this.setGains(kP, kD, kS, kV, kA, kG); - } - - public void setConstraints(double maxAcceleration, double cruisingVelocity) { - Elevator.this.setConstraints(maxAcceleration, cruisingVelocity); - } - - public boolean atGoal() { - return Elevator.this.atGoal(); - } - - public boolean atGoal(ReefState position) { - return Elevator.this.atGoal(Elevator.this.getPosition(position)); - } - - public boolean inTolerance(double toleranceMeters) { - return Math.abs(positionGoalMeters - inputs.positionMeters) <= toleranceMeters; - } - - public Command waitUntilAtGoal() { - return Elevator.this.waitUntilAtGoal(); - } - - public BooleanSupplier inFastScoringTolerance() { - return Elevator.this.inFastScoringTolerance(); - } - - public double getVelocityMetersPerSecond() { - return inputs.velocityMetersPerSecond; - } - } - - public ElevatorFSM getFSM() { - return new ElevatorFSM(); - } - - public ElevatorCSB getCSB() { - return new ElevatorCSB(); + public Command sysIdRoutine(V2_RedundancySuperstructure superstructure) { + + return Commands.sequence( + superstructure.runGoal(V2_RedundancySuperstructureStates.OVERRIDE), + Elevator.this.sysIdRoutine(superstructure)); } + + public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { + + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), + Elevator.this.sysIdRoutine(superstructure)); + } + + public double getPositionMeters() { + return Elevator.this.getPositionMeters(inputs); + } + + public double getFFCharacterizationVelocity() { + return Elevator.this.getFFCharacterizationVelocity(inputs); + } + + public void setGains(double kP, double kD, double kS, double kV, double kA, double kG) { + Elevator.this.setGains(kP, kD, kS, kV, kA, kG); + } + + public void setConstraints(double maxAcceleration, double cruisingVelocity) { + Elevator.this.setConstraints(maxAcceleration, cruisingVelocity); + } + + public boolean atGoal() { + return Elevator.this.atGoal(); + } + + public boolean atGoal(ReefState position) { + return Elevator.this.atGoal(Elevator.this.getPosition(position)); + } + + public boolean inTolerance(double toleranceMeters) { + return Math.abs(positionGoalMeters - inputs.positionMeters) <= toleranceMeters; + } + + public Command waitUntilAtGoal() { + return Elevator.this.waitUntilAtGoal(); + } + + public BooleanSupplier inFastScoringTolerance() { + return Elevator.this.inFastScoringTolerance(); + } + + public double getVelocityMetersPerSecond() { + return inputs.velocityMetersPerSecond; + } + } + + public ElevatorFSM getFSM() { + return new ElevatorFSM(); + } + + public ElevatorCSB getCSB() { + return new ElevatorCSB(); + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 92b74efe..68d4fab6 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -1,5 +1,7 @@ package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; +import static edu.wpi.first.units.Units.*; + import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; @@ -13,323 +15,320 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; +import java.util.Set; import lombok.Getter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; -import java.util.Set; - -import static edu.wpi.first.units.Units.*; - public class V3_EpsilonManipulator { - private final V3_EpsilonManipulatorIO io; - private final ManipulatorIOInputsAutoLogged inputs; - - @AutoLogOutput(key = "Manipulator/Arm Goal") - @Getter - private Rotation2d armGoal; - - @AutoLogOutput(key = "Manipulator/Roller Goal") - @Getter - private ManipulatorRollerState rollerGoal; - - private boolean isClosedLoop; - - Set algaeStates; - - public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { - this.io = io; - inputs = new ManipulatorIOInputsAutoLogged(); - - isClosedLoop = true; - armGoal = ManipulatorArmState.VERTICAL_UP.getAngle(RobotState.getScoreSide()); - rollerGoal = ManipulatorRollerState.STOP; - - algaeStates = - Set.of( - ManipulatorArmState.ALGAE_INTAKE_FLOOR, - ManipulatorArmState.REEF_INTAKE, - ManipulatorArmState.ALGAE_SCORE); - } - - public void periodic() { - io.updateInputs(inputs); - Logger.processInputs("Manipulator", inputs); - - if (isClosedLoop) { - io.setArmGoal(armGoal); - } - - if (rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { - io.setRollerVoltage(ManipulatorRollerState.SCORE_ALGAE.getVoltage()); - } else if (hasAlgae() - && Set.of( - ManipulatorRollerState.CORAL_INTAKE, - ManipulatorRollerState.STOP, - ManipulatorRollerState.ALGAE_INTAKE) - .contains(rollerGoal) - && !rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { - RobotState.setHasAlgae(true); - io.setRollerVoltage(holdVoltage()); - } else if (hasCoral()) { - io.setRollerVoltage(holdVoltage()); - } else { - io.setRollerVoltage(rollerGoal.getVoltage()); - } - } - - /** - * Checks if the manipulator is currently detecting coral. This is done by checking if the CAN - * range sensor is detecting a distance less than the coral detection threshold and greater than - * 0. - * - * @return True if the manipulator is detecting coral, false otherwise. - */ - @AutoLogOutput(key = "Manipulator/Has Coral") - public boolean hasCoral() { - return inputs.canRangeGot; - } - - /** - * Checks if the manipulator is currently detecting algae. This is done by checking if the CAN - * range sensor is detecting a distance less than the algae detection threshold and greater than - * 0. - * - * @return True if the manipulator is detecting algae, false otherwise. - */ - @AutoLogOutput(key = "Manipulator/Has Algae") - public boolean hasAlgae() { - boolean hasAlgae = rollerGoal.equals(ManipulatorRollerState.ALGAE_INTAKE) && inputs.canRangeGot; - return hasAlgae; - } - - /** - * Creates a command to run the manipulator arm at a specified voltage. - * - * @param volts The voltage to set the arm to. - * @return A command to run the arm. - */ - public Command runArm(double volts) { - return Commands.runEnd( - () -> { - isClosedLoop = false; - io.setArmVoltage(volts); - }, - () -> io.setArmVoltage(0)); - } - - /** - * Sets the goal for the manipulator arm to reach. - * - * @param goal The goal state to set the arm to. - */ - public void setArmGoal(ManipulatorArmState goal) { - isClosedLoop = true; - if (!algaeStates.contains(goal)) { - armGoal = goal.getAngle(RobotState.getScoreSide()); - } else { - armGoal = goal.getAngle(ScoreSide.CENTER); - } - } + private final V3_EpsilonManipulatorIO io; + private final ManipulatorIOInputsAutoLogged inputs; - public void setArmGoal(Rotation2d goal) { - isClosedLoop = true; - armGoal = goal; - } - - /** - * Updates the gains for the manipulator arm. This function sets the PID gains for the three slots - * of the arm. The gains are used to control the arm's movement. - * - * @param kP0 The proportional gain for slot 0. - * @param kD0 The derivative gain for slot 0. - * @param kS0 The static gain for slot 0. - * @param kV0 The velocity gain for slot 0. - * @param kA0 The acceleration gain for slot 0. - * @param kG0 The gravity gain for slot 0. - * @param kP1 The proportional gain for slot 1. - * @param kD1 The derivative gain for slot 1. - * @param kS1 The static gain for slot 1. - * @param kV1 The velocity gain for slot 1. - * @param kA1 The acceleration gain for slot 1. - * @param kG1 The gravity gain for slot 1. - * @param kP2 The proportional gain for slot 2. - * @param kD2 The derivative gain for slot 2. - * @param kS2 The static gain for slot 2. - * @param kV2 The velocity gain for slot 2. - * @param kA2 The acceleration gain for slot 2. - * @param kG2 The gravity gain for slot 2. - */ - public void updateArmGains( - double kP0, - double kD0, - double kS0, - double kV0, - double kA0, - double kG0, - double kP1, - double kD1, - double kS1, - double kV1, - double kA1, - double kG1, - double kP2, - double kD2, - double kS2, - double kV2, - double kA2, - double kG2) { - io.updateSlot0ArmGains(kP0, kD0, kS0, kV0, kA0, kG0); - io.updateSlot1ArmGains(kP1, kD1, kS1, kV1, kA1, kG1); - io.updateSlot2ArmGains(kP2, kD2, kS2, kV2, kA2, kG2); - } - - /** - * Updates the constraints for the arm. - * - * @param maxAcceleration The maximum acceleration. - * @param maxVelocity The maximum velocity. - */ - public void updateArmConstraints(double maxAcceleration, double maxVelocity) { - io.updateArmConstraints(maxAcceleration, maxVelocity); - } + @AutoLogOutput(key = "Manipulator/Arm Goal") + @Getter + private Rotation2d armGoal; - /** - * Checks if the arm is at the goal position. - * - *

This function checks if the arm is within the goal tolerance of the currently set arm goal - * position. If the arm is within the tolerance, it returns true. Otherwise, it returns false. - * - * @return If the arm is at the goal position. - */ - @AutoLogOutput(key = "Manipulator/Arm At Goal") - public boolean armAtGoal() { - return armAtGoal(armGoal); - } + @AutoLogOutput(key = "Manipulator/Roller Goal") + @Getter + private ManipulatorRollerState rollerGoal; - public boolean armAtGoal(Rotation2d state) { - return Math.abs(inputs.armPosition.minus(state).getRadians()) - <= V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); - } + private boolean isClosedLoop; - public boolean armInTolerance(Rotation2d tolerance) { - return Math.abs(inputs.armPosition.minus(armGoal).getRadians()) <= tolerance.getRadians(); - } + Set algaeStates; - /** - * Waits until the arm is at the goal position. - * - *

This command waits for 0.02 seconds and then checks if the arm is at the goal position. If - * the arm is not at the goal position, it waits for 0.02 seconds and checks again. This process - * repeats until the arm is at the goal position. - * - * @return A command that waits until the arm is at the goal position. - */ - public Command waitUntilArmAtGoal() { - return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::armAtGoal)); - } + public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { + this.io = io; + inputs = new ManipulatorIOInputsAutoLogged(); - /** - * Returns a voltage to hold the roller at the current position. The voltage is calculated based - * on the current torque current of the roller. The calculation is done using a piecewise - * polynomial function. The function first checks if the current torque current is less than or - * equal to 20. If it is, it uses one set of coefficients to calculate the voltage. Otherwise, it - * uses another set of coefficients. - */ - private double holdVoltage() { - return RobotState.isHasAlgae() ? -12.0 : -1; - } + isClosedLoop = true; + armGoal = ManipulatorArmState.VERTICAL_UP.getAngle(RobotState.getScoreSide()); + rollerGoal = ManipulatorRollerState.STOP; - /** - * Sets the current slot of the manipulator arm based on the current state of the subsystem. If - * the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to - * 1. Otherwise, it sets the slot to 0. - */ - public void setSlot() { - if (RobotState.isHasAlgae()) { - io.setSlot(2); - } else if (hasCoral()) { - io.setSlot(1); - } else { - io.setSlot(0); - } - } + algaeStates = + Set.of( + ManipulatorArmState.ALGAE_INTAKE_FLOOR, + ManipulatorArmState.REEF_INTAKE, + ManipulatorArmState.ALGAE_SCORE); + } - /** - * Creates a command to run the SysId routine for the manipulator arm, generating the constants - * and gains for a PID. - * - * @param superstructure The V3 Epsiolon Superstructure. - * @return A command to run the SysId routine for the manipulator arm. - */ - public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure, ElevatorFSM elevator) { - SysIdRoutine algaeCharacterizationRoutine = - new SysIdRoutine( - new SysIdRoutine.Config( - Volts.of(0.5).per(Second), - Volts.of(8), - Seconds.of(10), - (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), - new SysIdRoutine.Mechanism( - (volts) -> io.setArmVoltage(volts.in(Volts)), null, superstructure)); - return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.L4)), - Commands.runOnce(() -> isClosedLoop = false), - algaeCharacterizationRoutine.quasistatic(Direction.kForward), - Commands.waitSeconds(.25), - algaeCharacterizationRoutine.quasistatic(Direction.kReverse), - Commands.waitSeconds(.25), - algaeCharacterizationRoutine.dynamic(Direction.kForward), - Commands.waitSeconds(.25), - algaeCharacterizationRoutine.dynamic(Direction.kReverse)); - } + public void periodic() { + io.updateInputs(inputs); + Logger.processInputs("Manipulator", inputs); - /** - * Sets the manipulator arm to the specified state. - * - * @param state The state to set the arm to. - */ - public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmState state) { - io.setManipulatorState(state); + if (isClosedLoop) { + io.setArmGoal(armGoal); } - /** - * Sets the roller goal state of the manipulator. If the subsystem has algae or coral and the goal - * is one of the intake states, it sets the roller voltage to the hold voltage. Otherwise, it sets - * the roller voltage to the goal voltage. - * - * @param rollerGoal The desired state of the roller. - */ - public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState rollerGoal) { - this.rollerGoal = rollerGoal; - if ((hasAlgae() || hasCoral()) - && Set.of( - V3_EpsilonManipulatorConstants.ManipulatorRollerState.ALGAE_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerState.CORAL_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerState.STOP) - .contains(rollerGoal)) { - - io.setRollerVoltage(holdVoltage()); - } else { - io.setRollerVoltage(rollerGoal.getVoltage()); - } + if (rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { + io.setRollerVoltage(ManipulatorRollerState.SCORE_ALGAE.getVoltage()); + } else if (hasAlgae() + && Set.of( + ManipulatorRollerState.CORAL_INTAKE, + ManipulatorRollerState.STOP, + ManipulatorRollerState.ALGAE_INTAKE) + .contains(rollerGoal) + && !rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { + RobotState.setHasAlgae(true); + io.setRollerVoltage(holdVoltage()); + } else if (hasCoral()) { + io.setRollerVoltage(holdVoltage()); + } else { + io.setRollerVoltage(rollerGoal.getVoltage()); } - - /** - * Gets the current angle of the manipulator arm. - * - * @return The current angle of the manipulator arm, in radians. - */ - public Rotation2d getArmAngle() { - return inputs.armPosition; + } + + /** + * Checks if the manipulator is currently detecting coral. This is done by checking if the CAN + * range sensor is detecting a distance less than the coral detection threshold and greater than + * 0. + * + * @return True if the manipulator is detecting coral, false otherwise. + */ + @AutoLogOutput(key = "Manipulator/Has Coral") + public boolean hasCoral() { + return inputs.canRangeGot; + } + + /** + * Checks if the manipulator is currently detecting algae. This is done by checking if the CAN + * range sensor is detecting a distance less than the algae detection threshold and greater than + * 0. + * + * @return True if the manipulator is detecting algae, false otherwise. + */ + @AutoLogOutput(key = "Manipulator/Has Algae") + public boolean hasAlgae() { + boolean hasAlgae = rollerGoal.equals(ManipulatorRollerState.ALGAE_INTAKE) && inputs.canRangeGot; + return hasAlgae; + } + + /** + * Creates a command to run the manipulator arm at a specified voltage. + * + * @param volts The voltage to set the arm to. + * @return A command to run the arm. + */ + public Command runArm(double volts) { + return Commands.runEnd( + () -> { + isClosedLoop = false; + io.setArmVoltage(volts); + }, + () -> io.setArmVoltage(0)); + } + + /** + * Sets the goal for the manipulator arm to reach. + * + * @param goal The goal state to set the arm to. + */ + public void setArmGoal(ManipulatorArmState goal) { + isClosedLoop = true; + if (!algaeStates.contains(goal)) { + armGoal = goal.getAngle(RobotState.getScoreSide()); + } else { + armGoal = goal.getAngle(ScoreSide.CENTER); } - - public double getArmVelocity() { - return inputs.armVelocityRadiansPerSecond; + } + + public void setArmGoal(Rotation2d goal) { + isClosedLoop = true; + armGoal = goal; + } + + /** + * Updates the gains for the manipulator arm. This function sets the PID gains for the three slots + * of the arm. The gains are used to control the arm's movement. + * + * @param kP0 The proportional gain for slot 0. + * @param kD0 The derivative gain for slot 0. + * @param kS0 The static gain for slot 0. + * @param kV0 The velocity gain for slot 0. + * @param kA0 The acceleration gain for slot 0. + * @param kG0 The gravity gain for slot 0. + * @param kP1 The proportional gain for slot 1. + * @param kD1 The derivative gain for slot 1. + * @param kS1 The static gain for slot 1. + * @param kV1 The velocity gain for slot 1. + * @param kA1 The acceleration gain for slot 1. + * @param kG1 The gravity gain for slot 1. + * @param kP2 The proportional gain for slot 2. + * @param kD2 The derivative gain for slot 2. + * @param kS2 The static gain for slot 2. + * @param kV2 The velocity gain for slot 2. + * @param kA2 The acceleration gain for slot 2. + * @param kG2 The gravity gain for slot 2. + */ + public void updateArmGains( + double kP0, + double kD0, + double kS0, + double kV0, + double kA0, + double kG0, + double kP1, + double kD1, + double kS1, + double kV1, + double kA1, + double kG1, + double kP2, + double kD2, + double kS2, + double kV2, + double kA2, + double kG2) { + io.updateSlot0ArmGains(kP0, kD0, kS0, kV0, kA0, kG0); + io.updateSlot1ArmGains(kP1, kD1, kS1, kV1, kA1, kG1); + io.updateSlot2ArmGains(kP2, kD2, kS2, kV2, kA2, kG2); + } + + /** + * Updates the constraints for the arm. + * + * @param maxAcceleration The maximum acceleration. + * @param maxVelocity The maximum velocity. + */ + public void updateArmConstraints(double maxAcceleration, double maxVelocity) { + io.updateArmConstraints(maxAcceleration, maxVelocity); + } + + /** + * Checks if the arm is at the goal position. + * + *

This function checks if the arm is within the goal tolerance of the currently set arm goal + * position. If the arm is within the tolerance, it returns true. Otherwise, it returns false. + * + * @return If the arm is at the goal position. + */ + @AutoLogOutput(key = "Manipulator/Arm At Goal") + public boolean armAtGoal() { + return armAtGoal(armGoal); + } + + public boolean armAtGoal(Rotation2d state) { + return Math.abs(inputs.armPosition.minus(state).getRadians()) + <= V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); + } + + public boolean armInTolerance(Rotation2d tolerance) { + return Math.abs(inputs.armPosition.minus(armGoal).getRadians()) <= tolerance.getRadians(); + } + + /** + * Waits until the arm is at the goal position. + * + *

This command waits for 0.02 seconds and then checks if the arm is at the goal position. If + * the arm is not at the goal position, it waits for 0.02 seconds and checks again. This process + * repeats until the arm is at the goal position. + * + * @return A command that waits until the arm is at the goal position. + */ + public Command waitUntilArmAtGoal() { + return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::armAtGoal)); + } + + /** + * Returns a voltage to hold the roller at the current position. The voltage is calculated based + * on the current torque current of the roller. The calculation is done using a piecewise + * polynomial function. The function first checks if the current torque current is less than or + * equal to 20. If it is, it uses one set of coefficients to calculate the voltage. Otherwise, it + * uses another set of coefficients. + */ + private double holdVoltage() { + return RobotState.isHasAlgae() ? -12.0 : -1; + } + + /** + * Sets the current slot of the manipulator arm based on the current state of the subsystem. If + * the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to + * 1. Otherwise, it sets the slot to 0. + */ + public void setSlot() { + if (RobotState.isHasAlgae()) { + io.setSlot(2); + } else if (hasCoral()) { + io.setSlot(1); + } else { + io.setSlot(0); } - - public double getRollerVelocity() { - return inputs.rollerVelocityRadiansPerSecond; + } + + /** + * Creates a command to run the SysId routine for the manipulator arm, generating the constants + * and gains for a PID. + * + * @param superstructure The V3 Epsiolon Superstructure. + * @return A command to run the SysId routine for the manipulator arm. + */ + public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure, ElevatorFSM elevator) { + SysIdRoutine algaeCharacterizationRoutine = + new SysIdRoutine( + new SysIdRoutine.Config( + Volts.of(0.5).per(Second), + Volts.of(8), + Seconds.of(10), + (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), + new SysIdRoutine.Mechanism( + (volts) -> io.setArmVoltage(volts.in(Volts)), null, superstructure)); + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.L4)), + Commands.runOnce(() -> isClosedLoop = false), + algaeCharacterizationRoutine.quasistatic(Direction.kForward), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.quasistatic(Direction.kReverse), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.dynamic(Direction.kForward), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.dynamic(Direction.kReverse)); + } + + /** + * Sets the manipulator arm to the specified state. + * + * @param state The state to set the arm to. + */ + public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmState state) { + io.setManipulatorState(state); + } + + /** + * Sets the roller goal state of the manipulator. If the subsystem has algae or coral and the goal + * is one of the intake states, it sets the roller voltage to the hold voltage. Otherwise, it sets + * the roller voltage to the goal voltage. + * + * @param rollerGoal The desired state of the roller. + */ + public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState rollerGoal) { + this.rollerGoal = rollerGoal; + if ((hasAlgae() || hasCoral()) + && Set.of( + V3_EpsilonManipulatorConstants.ManipulatorRollerState.ALGAE_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerState.CORAL_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerState.STOP) + .contains(rollerGoal)) { + + io.setRollerVoltage(holdVoltage()); + } else { + io.setRollerVoltage(rollerGoal.getVoltage()); } + } + + /** + * Gets the current angle of the manipulator arm. + * + * @return The current angle of the manipulator arm, in radians. + */ + public Rotation2d getArmAngle() { + return inputs.armPosition; + } + + public double getArmVelocity() { + return inputs.armVelocityRadiansPerSecond; + } + + public double getRollerVelocity() { + return inputs.rollerVelocityRadiansPerSecond; + } } From b4cda5152a52008a339694c6567ebd0be8b8681b Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 1 Nov 2025 12:58:12 -0400 Subject: [PATCH 158/180] Update at 'Sat Nov 01 12:58:12 EDT 2025' --- .../V3_EpsilonSuperstructureStates.java | 374 +++++++++--------- 1 file changed, 188 insertions(+), 186 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index c6af70a9..7abc351d 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -11,190 +11,192 @@ import lombok.Getter; public enum V3_EpsilonSuperstructureStates { - START("START", new SubsystemPoses(), SubsystemActions.empty()), - STOW_DOWN( - "STOW_DOWN", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), - SubsystemActions.empty()), - STOW_UP( - "STOW_UP", - new SubsystemPoses( - ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), - SubsystemActions.empty()), - OVERRIDE("OVERRIDE", new SubsystemPoses(), SubsystemActions.empty()), - GROUND_ACQUISITION( - "GROUND_ACQUISITION", - new SubsystemPoses( - ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), - SubsystemActions.empty()), - GROUND_INTAKE_ALGAE( - "GROUND_INTAKE_ALGAE", - new SubsystemPoses( - ReefState.ALGAE_FLOOR_INTAKE, - ManipulatorArmState.ALGAE_INTAKE_FLOOR, - IntakePivotState.INTAKE_ALGAE), - new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), - GROUND_AQUISITION_ALGAE( - "GROUND_AQUISITION_ALGAE", - new SubsystemPoses( - ReefState.ALGAE_FLOOR_INTAKE, - ManipulatorArmState.ALGAE_INTAKE_FLOOR, - IntakePivotState.INTAKE_ALGAE), - SubsystemActions.empty()), - - GROUND_INTAKE_CORAL( - "GROUND_INTAKE_CORAL", - new SubsystemPoses( - ReefState.STOW, ManipulatorArmState.CORAL_INTAKE_FLOOR, IntakePivotState.INTAKE_CORAL), - new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.STOP)), - - GROUND_INTAKE( - "GROUND_INTAKE", - new SubsystemPoses( - ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), - new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.CORAL_INTAKE)), - - L1( - "L1", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), - new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.STOP)), - L1_SCORE( - "L1_SCORE", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), - new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.SCORE_CORAL)), - - L2( - "L2", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), - SubsystemActions.empty()), - L2_SCORE( - "L2_SCORE", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.FLIPPED_SCORE, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), - - L3( - "L3", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), - SubsystemActions.empty()), - L3_SCORE( - "L3_SCORE", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), - - L4( - "L4", - new SubsystemPoses(ReefState.L4, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), - SubsystemActions.empty()), - L4_SCORE( - "L4_SCORE", - new SubsystemPoses(ReefState.L4, ManipulatorArmState.SCORE_L4, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.L4_SCORE, IntakeRollerState.STOP)), - - HANDOFF( - "HANDOFF", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.CENTERING)), - - HANDOFF_SPIN( - "HANDOFF", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.OUTTAKE)), - - L2_ALGAE( - "L2_ALGAE", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - SubsystemActions.empty()), - L2_ALGAE_DROP( - "L2_ALGAE_DROP", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), - L2_ALGAE_INTAKE( - "L2_ALGAE_INTAKE", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), - - L3_ALGAE( - "L3_ALGAE", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - SubsystemActions.empty()), - L3_ALGAE_DROP( - "L3_ALGAE_DROP", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), - L3_ALGAE_INTAKE( - "L3_ALGAE_INTAKE", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), - - PROCESSOR( - "PROCESSOR", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), - SubsystemActions.empty()), - POST_PROCESSOR( - "POST_PROCESSOR", - new SubsystemPoses( - ReefState.POST_PROCESSOR, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), - SubsystemActions.empty()), - PROCESSOR_SCORE( - "PROCESSOR_SCORE", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), - - BARGE( - "BARGE", - new SubsystemPoses( - ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.HANDOFF), - SubsystemActions.empty()), - BARGE_SCORE( - "BARGE_SCORE", - new SubsystemPoses( - ReefState.ALGAE_SCORE, ManipulatorArmState.ALGAE_SCORE, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP), - Rotation2d.fromDegrees(15)), - FLIP_DOWN( - "FLIP_DOWN", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty()), - FLIP_UP( - "FLIP_UP", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty()), - INVERSE_FLIP_UP( - "INVERSE_FLIP_UP", - new SubsystemPoses( - ReefState.HANDOFF, ManipulatorArmState.INVERSE_FLIP_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty()); - - @Getter private final V3_EpsilonSuperstructurePose pose; - @Getter private final V3_EpsilonSuperstructureAction action; - - /** - * Constructor for V3_SuperstructureStates. - * - * @param name The name of the state. - * @param pose The subsystem poses for this state. - * @param action The subsystem actions for this state. - */ - V3_EpsilonSuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { - this.pose = new V3_EpsilonSuperstructurePose(name, pose); - this.action = new V3_EpsilonSuperstructureAction(name, action); - } - - V3_EpsilonSuperstructureStates( - String name, SubsystemPoses pose, SubsystemActions action, Double elevatorTolerance) { - this.pose = new V3_EpsilonSuperstructurePose(name, pose, elevatorTolerance); - this.action = new V3_EpsilonSuperstructureAction(name, action); - } - - V3_EpsilonSuperstructureStates( - String name, SubsystemPoses pose, SubsystemActions action, Rotation2d armTolerance) { - this.pose = new V3_EpsilonSuperstructurePose(name, pose, armTolerance); - this.action = new V3_EpsilonSuperstructureAction(name, action); - } + START("START", new SubsystemPoses(), SubsystemActions.empty()), + STOW_DOWN( + "STOW_DOWN", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), + SubsystemActions.empty()), + STOW_UP( + "STOW_UP", + new SubsystemPoses( + ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), + SubsystemActions.empty()), + OVERRIDE("OVERRIDE", new SubsystemPoses(), SubsystemActions.empty()), + GROUND_ACQUISITION( + "GROUND_ACQUISITION", + new SubsystemPoses( + ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), + SubsystemActions.empty()), + GROUND_INTAKE_ALGAE( + "GROUND_INTAKE_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_FLOOR_INTAKE, + ManipulatorArmState.ALGAE_INTAKE_FLOOR, + IntakePivotState.INTAKE_ALGAE), + new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), + GROUND_AQUISITION_ALGAE( + "GROUND_AQUISITION_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_FLOOR_INTAKE, + ManipulatorArmState.ALGAE_INTAKE_FLOOR, + IntakePivotState.INTAKE_ALGAE), + SubsystemActions.empty()), + + GROUND_INTAKE_CORAL( + "GROUND_INTAKE_CORAL", + new SubsystemPoses( + ReefState.STOW, ManipulatorArmState.CORAL_INTAKE_FLOOR, IntakePivotState.INTAKE_CORAL), + new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.STOP)), + + GROUND_INTAKE( + "GROUND_INTAKE", + new SubsystemPoses( + ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), + new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.CORAL_INTAKE)), + + L1( + "L1", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.STOP)), + L1_SCORE( + "L1_SCORE", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.SCORE_CORAL)), + + L2( + "L2", + new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + L2_SCORE( + "L2_SCORE", + new SubsystemPoses(ReefState.L2, ManipulatorArmState.FLIPPED_SCORE, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), + + L3( + "L3", + new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + L3_SCORE( + "L3_SCORE", + new SubsystemPoses(ReefState.L3, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), + + L4( + "L4", + new SubsystemPoses(ReefState.L4, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + L4_SCORE( + "L4_SCORE", + new SubsystemPoses(ReefState.L4, ManipulatorArmState.SCORE_L4, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.L4_SCORE, IntakeRollerState.STOP)), + + HANDOFF( + "HANDOFF", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.CENTERING)), + + HANDOFF_SPIN( + "HANDOFF", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.OUTTAKE)), + + L2_ALGAE( + "L2_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + SubsystemActions.empty()), + L2_ALGAE_DROP( + "L2_ALGAE_DROP", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + L2_ALGAE_INTAKE( + "L2_ALGAE_INTAKE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), + + L3_ALGAE( + "L3_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + SubsystemActions.empty()), + L3_ALGAE_DROP( + "L3_ALGAE_DROP", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + L3_ALGAE_INTAKE( + "L3_ALGAE_INTAKE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), + + PROCESSOR( + "PROCESSOR", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + SubsystemActions.empty()), + POST_PROCESSOR( + "POST_PROCESSOR", + new SubsystemPoses( + ReefState.POST_PROCESSOR, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + SubsystemActions.empty()), + PROCESSOR_SCORE( + "PROCESSOR_SCORE", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + + BARGE( + "BARGE", + new SubsystemPoses( + ReefState.HIGH_STOW, ManipulatorArmState.PRE_SCORE, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + BARGE_SCORE( + "BARGE_SCORE", + new SubsystemPoses( + ReefState.ALGAE_SCORE, ManipulatorArmState.ALGAE_SCORE, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP), + Rotation2d.fromDegrees(15)), + FLIP_DOWN( + "FLIP_DOWN", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), + SubsystemActions.empty()), + FLIP_UP( + "FLIP_UP", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), + SubsystemActions.empty()), + INVERSE_FLIP_UP( + "INVERSE_FLIP_UP", + new SubsystemPoses( + ReefState.HANDOFF, ManipulatorArmState.INVERSE_FLIP_ANGLE, IntakePivotState.STOW), + SubsystemActions.empty()); + + @Getter + private final V3_EpsilonSuperstructurePose pose; + @Getter + private final V3_EpsilonSuperstructureAction action; + + /** + * Constructor for V3_SuperstructureStates. + * + * @param name The name of the state. + * @param pose The subsystem poses for this state. + * @param action The subsystem actions for this state. + */ + V3_EpsilonSuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { + this.pose = new V3_EpsilonSuperstructurePose(name, pose); + this.action = new V3_EpsilonSuperstructureAction(name, action); + } + + V3_EpsilonSuperstructureStates( + String name, SubsystemPoses pose, SubsystemActions action, Double elevatorTolerance) { + this.pose = new V3_EpsilonSuperstructurePose(name, pose, elevatorTolerance); + this.action = new V3_EpsilonSuperstructureAction(name, action); + } + + V3_EpsilonSuperstructureStates( + String name, SubsystemPoses pose, SubsystemActions action, Rotation2d armTolerance) { + this.pose = new V3_EpsilonSuperstructurePose(name, pose, armTolerance); + this.action = new V3_EpsilonSuperstructureAction(name, action); + } } From 3b8e9d31e4371c60ca265fac9d54eeedf881303e Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 1 Nov 2025 12:58:25 -0400 Subject: [PATCH 159/180] Update at 'Sat Nov 01 12:58:24 EDT 2025' --- .../V3_EpsilonSuperstructureStates.java | 374 +++++++++--------- 1 file changed, 186 insertions(+), 188 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 7abc351d..2580533c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -11,192 +11,190 @@ import lombok.Getter; public enum V3_EpsilonSuperstructureStates { - START("START", new SubsystemPoses(), SubsystemActions.empty()), - STOW_DOWN( - "STOW_DOWN", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), - SubsystemActions.empty()), - STOW_UP( - "STOW_UP", - new SubsystemPoses( - ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), - SubsystemActions.empty()), - OVERRIDE("OVERRIDE", new SubsystemPoses(), SubsystemActions.empty()), - GROUND_ACQUISITION( - "GROUND_ACQUISITION", - new SubsystemPoses( - ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), - SubsystemActions.empty()), - GROUND_INTAKE_ALGAE( - "GROUND_INTAKE_ALGAE", - new SubsystemPoses( - ReefState.ALGAE_FLOOR_INTAKE, - ManipulatorArmState.ALGAE_INTAKE_FLOOR, - IntakePivotState.INTAKE_ALGAE), - new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), - GROUND_AQUISITION_ALGAE( - "GROUND_AQUISITION_ALGAE", - new SubsystemPoses( - ReefState.ALGAE_FLOOR_INTAKE, - ManipulatorArmState.ALGAE_INTAKE_FLOOR, - IntakePivotState.INTAKE_ALGAE), - SubsystemActions.empty()), - - GROUND_INTAKE_CORAL( - "GROUND_INTAKE_CORAL", - new SubsystemPoses( - ReefState.STOW, ManipulatorArmState.CORAL_INTAKE_FLOOR, IntakePivotState.INTAKE_CORAL), - new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.STOP)), - - GROUND_INTAKE( - "GROUND_INTAKE", - new SubsystemPoses( - ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), - new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.CORAL_INTAKE)), - - L1( - "L1", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), - new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.STOP)), - L1_SCORE( - "L1_SCORE", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), - new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.SCORE_CORAL)), - - L2( - "L2", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), - SubsystemActions.empty()), - L2_SCORE( - "L2_SCORE", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.FLIPPED_SCORE, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), - - L3( - "L3", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), - SubsystemActions.empty()), - L3_SCORE( - "L3_SCORE", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), - - L4( - "L4", - new SubsystemPoses(ReefState.L4, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), - SubsystemActions.empty()), - L4_SCORE( - "L4_SCORE", - new SubsystemPoses(ReefState.L4, ManipulatorArmState.SCORE_L4, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.L4_SCORE, IntakeRollerState.STOP)), - - HANDOFF( - "HANDOFF", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.CENTERING)), - - HANDOFF_SPIN( - "HANDOFF", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.OUTTAKE)), - - L2_ALGAE( - "L2_ALGAE", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - SubsystemActions.empty()), - L2_ALGAE_DROP( - "L2_ALGAE_DROP", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), - L2_ALGAE_INTAKE( - "L2_ALGAE_INTAKE", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), - - L3_ALGAE( - "L3_ALGAE", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - SubsystemActions.empty()), - L3_ALGAE_DROP( - "L3_ALGAE_DROP", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), - L3_ALGAE_INTAKE( - "L3_ALGAE_INTAKE", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), - - PROCESSOR( - "PROCESSOR", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), - SubsystemActions.empty()), - POST_PROCESSOR( - "POST_PROCESSOR", - new SubsystemPoses( - ReefState.POST_PROCESSOR, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), - SubsystemActions.empty()), - PROCESSOR_SCORE( - "PROCESSOR_SCORE", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), - - BARGE( - "BARGE", - new SubsystemPoses( - ReefState.HIGH_STOW, ManipulatorArmState.PRE_SCORE, IntakePivotState.HANDOFF), - SubsystemActions.empty()), - BARGE_SCORE( - "BARGE_SCORE", - new SubsystemPoses( - ReefState.ALGAE_SCORE, ManipulatorArmState.ALGAE_SCORE, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP), - Rotation2d.fromDegrees(15)), - FLIP_DOWN( - "FLIP_DOWN", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty()), - FLIP_UP( - "FLIP_UP", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty()), - INVERSE_FLIP_UP( - "INVERSE_FLIP_UP", - new SubsystemPoses( - ReefState.HANDOFF, ManipulatorArmState.INVERSE_FLIP_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty()); - - @Getter - private final V3_EpsilonSuperstructurePose pose; - @Getter - private final V3_EpsilonSuperstructureAction action; - - /** - * Constructor for V3_SuperstructureStates. - * - * @param name The name of the state. - * @param pose The subsystem poses for this state. - * @param action The subsystem actions for this state. - */ - V3_EpsilonSuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { - this.pose = new V3_EpsilonSuperstructurePose(name, pose); - this.action = new V3_EpsilonSuperstructureAction(name, action); - } - - V3_EpsilonSuperstructureStates( - String name, SubsystemPoses pose, SubsystemActions action, Double elevatorTolerance) { - this.pose = new V3_EpsilonSuperstructurePose(name, pose, elevatorTolerance); - this.action = new V3_EpsilonSuperstructureAction(name, action); - } - - V3_EpsilonSuperstructureStates( - String name, SubsystemPoses pose, SubsystemActions action, Rotation2d armTolerance) { - this.pose = new V3_EpsilonSuperstructurePose(name, pose, armTolerance); - this.action = new V3_EpsilonSuperstructureAction(name, action); - } + START("START", new SubsystemPoses(), SubsystemActions.empty()), + STOW_DOWN( + "STOW_DOWN", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), + SubsystemActions.empty()), + STOW_UP( + "STOW_UP", + new SubsystemPoses( + ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), + SubsystemActions.empty()), + OVERRIDE("OVERRIDE", new SubsystemPoses(), SubsystemActions.empty()), + GROUND_ACQUISITION( + "GROUND_ACQUISITION", + new SubsystemPoses( + ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), + SubsystemActions.empty()), + GROUND_INTAKE_ALGAE( + "GROUND_INTAKE_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_FLOOR_INTAKE, + ManipulatorArmState.ALGAE_INTAKE_FLOOR, + IntakePivotState.INTAKE_ALGAE), + new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), + GROUND_AQUISITION_ALGAE( + "GROUND_AQUISITION_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_FLOOR_INTAKE, + ManipulatorArmState.ALGAE_INTAKE_FLOOR, + IntakePivotState.INTAKE_ALGAE), + SubsystemActions.empty()), + + GROUND_INTAKE_CORAL( + "GROUND_INTAKE_CORAL", + new SubsystemPoses( + ReefState.STOW, ManipulatorArmState.CORAL_INTAKE_FLOOR, IntakePivotState.INTAKE_CORAL), + new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.STOP)), + + GROUND_INTAKE( + "GROUND_INTAKE", + new SubsystemPoses( + ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), + new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.CORAL_INTAKE)), + + L1( + "L1", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.STOP)), + L1_SCORE( + "L1_SCORE", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.SCORE_CORAL)), + + L2( + "L2", + new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + L2_SCORE( + "L2_SCORE", + new SubsystemPoses(ReefState.L2, ManipulatorArmState.FLIPPED_SCORE, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), + + L3( + "L3", + new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + L3_SCORE( + "L3_SCORE", + new SubsystemPoses(ReefState.L3, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), + + L4( + "L4", + new SubsystemPoses(ReefState.L4, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + L4_SCORE( + "L4_SCORE", + new SubsystemPoses(ReefState.L4, ManipulatorArmState.SCORE_L4, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.L4_SCORE, IntakeRollerState.STOP)), + + HANDOFF( + "HANDOFF", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.CENTERING)), + + HANDOFF_SPIN( + "HANDOFF", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.OUTTAKE)), + + L2_ALGAE( + "L2_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + SubsystemActions.empty()), + L2_ALGAE_DROP( + "L2_ALGAE_DROP", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + L2_ALGAE_INTAKE( + "L2_ALGAE_INTAKE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), + + L3_ALGAE( + "L3_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + SubsystemActions.empty()), + L3_ALGAE_DROP( + "L3_ALGAE_DROP", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + L3_ALGAE_INTAKE( + "L3_ALGAE_INTAKE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), + + PROCESSOR( + "PROCESSOR", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + SubsystemActions.empty()), + POST_PROCESSOR( + "POST_PROCESSOR", + new SubsystemPoses( + ReefState.POST_PROCESSOR, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + SubsystemActions.empty()), + PROCESSOR_SCORE( + "PROCESSOR_SCORE", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + + BARGE( + "BARGE", + new SubsystemPoses( + ReefState.HIGH_STOW, ManipulatorArmState.PRE_SCORE, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + BARGE_SCORE( + "BARGE_SCORE", + new SubsystemPoses( + ReefState.ALGAE_SCORE, ManipulatorArmState.ALGAE_SCORE, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP), + Rotation2d.fromDegrees(15)), + FLIP_DOWN( + "FLIP_DOWN", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), + SubsystemActions.empty()), + FLIP_UP( + "FLIP_UP", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), + SubsystemActions.empty()), + INVERSE_FLIP_UP( + "INVERSE_FLIP_UP", + new SubsystemPoses( + ReefState.HANDOFF, ManipulatorArmState.INVERSE_FLIP_ANGLE, IntakePivotState.STOW), + SubsystemActions.empty()); + + @Getter private final V3_EpsilonSuperstructurePose pose; + @Getter private final V3_EpsilonSuperstructureAction action; + + /** + * Constructor for V3_SuperstructureStates. + * + * @param name The name of the state. + * @param pose The subsystem poses for this state. + * @param action The subsystem actions for this state. + */ + V3_EpsilonSuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { + this.pose = new V3_EpsilonSuperstructurePose(name, pose); + this.action = new V3_EpsilonSuperstructureAction(name, action); + } + + V3_EpsilonSuperstructureStates( + String name, SubsystemPoses pose, SubsystemActions action, Double elevatorTolerance) { + this.pose = new V3_EpsilonSuperstructurePose(name, pose, elevatorTolerance); + this.action = new V3_EpsilonSuperstructureAction(name, action); + } + + V3_EpsilonSuperstructureStates( + String name, SubsystemPoses pose, SubsystemActions action, Rotation2d armTolerance) { + this.pose = new V3_EpsilonSuperstructurePose(name, pose, armTolerance); + this.action = new V3_EpsilonSuperstructureAction(name, action); + } } From cf908bfb14e98ddb61bd7239519e313957886cbd Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 1 Nov 2025 13:00:41 -0400 Subject: [PATCH 160/180] Update at 'Sat Nov 01 13:00:41 EDT 2025' --- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 636 +++++++++--------- .../manipulator/V3_EpsilonManipulator.java | 598 ++++++++-------- 2 files changed, 619 insertions(+), 615 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index ab51d69b..d8582af8 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -52,328 +52,330 @@ import org.littletonrobotics.junction.Logger; public class V3_EpsilonRobotContainer implements RobotContainer { - // Subsystems - private Drive drive; - private ElevatorFSM elevator; - private V3_EpsilonIntake intake; - private V3_EpsilonManipulator manipulator; - private V3_EpsilonSuperstructure superstructure; - private V3_EpsilonClimber climber; - private V3_EpsilonLEDs leds; - private Vision vision; - - // Controller - private static final CommandXboxController driver = new CommandXboxController(0); - private static final CommandXboxController operator = new CommandXboxController(1); - - // Auto chooser - private final ChoreoChooser autoChooser = new ChoreoChooser(); - - public V3_EpsilonRobotContainer() { - - if (Constants.getMode() != Mode.REPLAY) { - switch (Constants.ROBOT) { - case V3_EPSILON: - drive = - new Drive( - new GyroIOPigeon2(), - new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), - new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), - new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), - new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); - elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); - climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); - superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); - leds = new V3_EpsilonLEDs(); - vision = - new Vision( - () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), - RobotCameras.V3_EPSILON_CAMS); - break; - case V3_EPSILON_SIM: - drive = - new Drive( - new GyroIO() {}, - new ModuleIOSim(DriveConstants.FRONT_LEFT), - new ModuleIOSim(DriveConstants.FRONT_RIGHT), - new ModuleIOSim(DriveConstants.BACK_LEFT), - new ModuleIOSim(DriveConstants.BACK_RIGHT)); - elevator = new Elevator(new ElevatorIOSim()).getFSM(); - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); - climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOSim()); - superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); - leds = new V3_EpsilonLEDs(); - vision = - new Vision( - () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), - RobotCameras.V3_EPSILON_CAMS); - break; - default: - break; - } + // Subsystems + private Drive drive; + private ElevatorFSM elevator; + private V3_EpsilonIntake intake; + private V3_EpsilonManipulator manipulator; + private V3_EpsilonSuperstructure superstructure; + private V3_EpsilonClimber climber; + private V3_EpsilonLEDs leds; + private Vision vision; + + // Controller + private static final CommandXboxController driver = new CommandXboxController(0); + private static final CommandXboxController operator = new CommandXboxController(1); + + // Auto chooser + private final ChoreoChooser autoChooser = new ChoreoChooser(); + + public V3_EpsilonRobotContainer() { + + if (Constants.getMode() != Mode.REPLAY) { + switch (Constants.ROBOT) { + case V3_EPSILON: + drive = + new Drive( + new GyroIOPigeon2(), + new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), + new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), + new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), + new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); + elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); + climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + leds = new V3_EpsilonLEDs(); + vision = + new Vision( + () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), + RobotCameras.V3_EPSILON_CAMS); + break; + case V3_EPSILON_SIM: + drive = + new Drive( + new GyroIO() { + }, + new ModuleIOSim(DriveConstants.FRONT_LEFT), + new ModuleIOSim(DriveConstants.FRONT_RIGHT), + new ModuleIOSim(DriveConstants.BACK_LEFT), + new ModuleIOSim(DriveConstants.BACK_RIGHT)); + elevator = new Elevator(new ElevatorIOSim()).getFSM(); + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); + climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOSim()); + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + leds = new V3_EpsilonLEDs(); + vision = + new Vision( + () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), + RobotCameras.V3_EPSILON_CAMS); + break; + default: + break; + } + } + + if (drive == null) { + drive = + new Drive( + new GyroIO() { + }, + new ModuleIO() { + }, + new ModuleIO() { + }, + new ModuleIO() { + }, + new ModuleIO() { + }); + } + if (elevator == null) { + elevator = new Elevator(new ElevatorIO() { + }).getFSM(); + } + if (intake == null) { + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() { + }); + } + if (manipulator == null) { + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() { + }); + } + if (climber == null) { + climber = new V3_EpsilonClimber(new V3_EpsilonClimberIO() { + }); + } + if (leds == null) { + leds = new V3_EpsilonLEDs(); + } + if (superstructure == null) { + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + } + + LTNUpdater.registerAll(drive, elevator, intake, manipulator); + + configureButtonBindings(); + configureAutos(); } - if (drive == null) { - drive = - new Drive( - new GyroIO() {}, - new ModuleIO() {}, - new ModuleIO() {}, - new ModuleIO() {}, - new ModuleIO() {}); + /** + * Configure the button bindings for the robot. This method is called in the constructor and is + * responsible for setting up the default commands for each button on the controllers. + */ + private void configureButtonBindings() { + Trigger elevatorStow = + new Trigger( + () -> + elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) + || elevator.getPosition().equals(ElevatorPositions.STOW)); + Trigger elevatorNotStow = + new Trigger( + () -> + !elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) + && !elevator.getPosition().equals(ElevatorPositions.STOW)); + drive.setDefaultCommand( + DriveCommands.joystickDrive( + drive, + () -> -driver.getLeftY(), + () -> -driver.getLeftX(), + () -> -driver.getRightX(), + () -> false, + () -> false, + driver.povRight())); + + driver.povDown().onTrue(SharedCommands.resetHeading(drive)); + + driver.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); + driver.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); + driver.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); + driver.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); + + driver + .y() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); + driver + .x() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); + driver + .b() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); + driver + .a() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); + + driver + .rightTrigger(0.5) + .whileTrue( + V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence(drive, superstructure)); + driver + .leftTrigger(0.5) + .whileTrue( + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake, manipulator)) + .onFalse( + V3_EpsilonCompositeCommands.postIntakeCoralSequence( + superstructure, intake, manipulator)); + + driver + .leftBumper() + .whileTrue(V3_EpsilonCompositeCommands.intakeAlgaeFloor(superstructure, manipulator)) + .onFalse( + Commands.either( + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), + () -> RobotState.isHasAlgae())); + driver.rightBumper().onTrue(Commands.runOnce(() -> RobotState.toggleReefPost())); + + driver.povUp().onTrue(superstructure.setPosition()); + driver.povDown().onTrue(SharedCommands.resetHeading(drive)); + driver.povLeft().onTrue(DriveCommands.inchMovement(drive, -0.5, .07)); + + driver + .leftStick() + .onTrue(V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence(drive, superstructure)); + + driver + .back() + .whileTrue(V3_EpsilonCompositeCommands.intakeAlgaeFromReef(drive, superstructure)) + .whileFalse(V3_EpsilonCompositeCommands.postIntakeAlgaeFromReef(drive, superstructure)); + + driver + .start() + .whileTrue( + V3_EpsilonCompositeCommands.dropAlgae( + drive, + elevator, + manipulator, + intake, + superstructure, + () -> RobotState.getReefAlignData().algaeIntakeHeight())); + + operator.y().onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); + operator.x().onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); + operator.b().onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); + operator.a().onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); + + operator + .y() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); + operator + .x() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); + operator + .b() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); + operator + .a() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); + + operator + .rightTrigger(0.5) + .whileTrue( + superstructure.override( + () -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_CORAL), 0.4)); + + operator.leftBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))); + operator.rightBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))); + + operator + .povUp() + .onTrue( + Commands.sequence( + Commands.runOnce(() -> manipulator.setArmGoal(Rotation2d.fromDegrees(90))), + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.HANDOFF)), + Commands.runOnce(() -> intake.setPivotGoal(IntakePivotState.L1)), + climber.releaseClimber())); + operator + .povDown() + .whileTrue( + Commands.sequence( + Commands.runOnce(() -> RobotState.setClimberReady(false)), + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.STOW)), + climber.winchClimber())); + operator + .povLeft() + .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR)) + .onFalse( + superstructure + .runActionWithTimeout(V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, 1) + .finallyDo(() -> RobotState.setHasAlgae(false))); + + operator.start().whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)); + + operator.back().onTrue(V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure)); } - if (elevator == null) { - elevator = new Elevator(new ElevatorIO() {}).getFSM(); - } - if (intake == null) { - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); - } - if (manipulator == null) { - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); - } - if (climber == null) { - climber = new V3_EpsilonClimber(new V3_EpsilonClimberIO() {}); - } - if (leds == null) { - leds = new V3_EpsilonLEDs(); + + private void configureAutos() { + autoChooser.addCmd( + "Drive FF Characterization", () -> DriveCommands.feedforwardCharacterization(drive)); + autoChooser.addCmd( + "Wheel Radius Characterization", () -> DriveCommands.wheelRadiusCharacterization(drive)); + autoChooser.addRoutine( + "4 Piece Right Early Madtown", + () -> AutonomousCommands.autoERight(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "4 Piece Right Late Madtown", + () -> AutonomousCommands.autoERightBack(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "4 Piece Left Early Madtown", + () -> AutonomousCommands.autoELeft(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "4 Piece Left Late Madtown", + () -> AutonomousCommands.autoELeftBack(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "Algae", () -> AutonomousCommands.autoFLeft(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "1 piece do nothing", + () -> AutonomousCommands.autoFLeftMinimal(drive, superstructure, intake, manipulator)); + SmartDashboard.putData("Autonomous Modes", autoChooser); } - if (superstructure == null) { - superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + + /** + * Periodic function for the robot. This function is called every 20ms, and is responsible for + * updating the robot's state and logging relevant data. + */ + @Override + public void robotPeriodic() { + RobotState.periodic( + drive.getRawGyroRotation(), + NetworkTablesJNI.now(), + drive.getYawVelocity(), + drive.getModulePositions(), + vision.getCameras()); + + LoggedTunableNumber.updateAll(); + + Logger.recordOutput( + "Component Poses", + V3_EpsilonMechanism3d.getPoses( + elevator.getPositionMeters(), intake.getPivotAngle(), manipulator.getArmAngle())); + + if (!Constants.getMode().equals(Constants.Mode.REAL)) { + Logger.recordOutput( + "FieldSimulation/Algae", SimulatedArena.getInstance().getGamePiecesArrayByType("Algae")); + Logger.recordOutput( + "FieldSimulation/Coral", SimulatedArena.getInstance().getGamePiecesArrayByType("Coral")); + } } - LTNUpdater.registerAll(drive, elevator, intake, manipulator); - - configureButtonBindings(); - configureAutos(); - } - - /** - * Configure the button bindings for the robot. This method is called in the constructor and is - * responsible for setting up the default commands for each button on the controllers. - */ - private void configureButtonBindings() { - Trigger elevatorStow = - new Trigger( - () -> - elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) - || elevator.getPosition().equals(ElevatorPositions.STOW)); - Trigger elevatorNotStow = - new Trigger( - () -> - !elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) - && !elevator.getPosition().equals(ElevatorPositions.STOW)); - drive.setDefaultCommand( - DriveCommands.joystickDrive( - drive, - () -> -driver.getLeftY(), - () -> -driver.getLeftX(), - () -> -driver.getRightX(), - () -> false, - () -> false, - driver.povRight())); - - driver.povDown().onTrue(SharedCommands.resetHeading(drive)); - - driver.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); - driver.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); - driver.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); - driver.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); - - driver - .y() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); - driver - .x() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); - driver - .b() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); - driver - .a() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); - - driver - .rightTrigger(0.5) - .whileTrue( - V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence(drive, superstructure)); - driver - .leftTrigger(0.5) - .whileTrue( - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake, manipulator)) - .onFalse( - V3_EpsilonCompositeCommands.postIntakeCoralSequence( - superstructure, intake, manipulator)); - - driver - .leftBumper() - .whileTrue(V3_EpsilonCompositeCommands.intakeAlgaeFloor(superstructure, manipulator)) - .onFalse( - Commands.either( - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), - () -> RobotState.isHasAlgae())); - driver.rightBumper().onTrue(Commands.runOnce(() -> RobotState.toggleReefPost())); - - driver.povUp().onTrue(superstructure.setPosition()); - driver.povDown().onTrue(SharedCommands.resetHeading(drive)); - driver.povLeft().onTrue(DriveCommands.inchMovement(drive, -0.5, .07)); - - driver - .leftStick() - .onTrue(V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence(drive, superstructure)); - - driver - .back() - .whileTrue(V3_EpsilonCompositeCommands.intakeAlgaeFromReef(drive, superstructure)) - .whileFalse(V3_EpsilonCompositeCommands.postIntakeAlgaeFromReef(drive, superstructure)); - - driver - .start() - .whileTrue( - V3_EpsilonCompositeCommands.dropAlgae( - drive, - elevator, - manipulator, - intake, - superstructure, - () -> RobotState.getReefAlignData().algaeIntakeHeight())); - - operator.y().onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); - operator.x().onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); - operator.b().onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); - operator.a().onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); - - operator - .y() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); - operator - .x() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); - operator - .b() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); - operator - .a() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); - - operator - .leftTrigger(0.5) - .whileTrue( - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake, manipulator)) - .whileFalse( - V3_EpsilonCompositeCommands.postIntakeCoralSequence( - superstructure, intake, manipulator)); - operator - .rightTrigger(0.5) - .whileTrue( - superstructure.override( - () -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_CORAL), 0.4)); - - operator.leftBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))); - operator.rightBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))); - - operator - .povUp() - .onTrue( - Commands.sequence( - Commands.runOnce(() -> manipulator.setArmGoal(Rotation2d.fromDegrees(90))), - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.HANDOFF)), - Commands.runOnce(() -> intake.setPivotGoal(IntakePivotState.L1)), - climber.releaseClimber())); - operator - .povDown() - .whileTrue( - Commands.sequence( - Commands.runOnce(() -> RobotState.setClimberReady(false)), - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.STOW)), - climber.winchClimber())); - operator - .povLeft() - .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR)) - .onFalse( - superstructure - .runActionWithTimeout(V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, 1) - .finallyDo(() -> RobotState.setHasAlgae(false))); - - operator.start().whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)); - - operator.back().onTrue(V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure)); - } - - private void configureAutos() { - autoChooser.addCmd( - "Drive FF Characterization", () -> DriveCommands.feedforwardCharacterization(drive)); - autoChooser.addCmd( - "Wheel Radius Characterization", () -> DriveCommands.wheelRadiusCharacterization(drive)); - autoChooser.addRoutine( - "4 Piece Right Early Madtown", - () -> AutonomousCommands.autoERight(drive, superstructure, intake, manipulator)); - autoChooser.addRoutine( - "4 Piece Right Late Madtown", - () -> AutonomousCommands.autoERightBack(drive, superstructure, intake, manipulator)); - autoChooser.addRoutine( - "4 Piece Left Early Madtown", - () -> AutonomousCommands.autoELeft(drive, superstructure, intake, manipulator)); - autoChooser.addRoutine( - "4 Piece Left Late Madtown", - () -> AutonomousCommands.autoELeftBack(drive, superstructure, intake, manipulator)); - autoChooser.addRoutine( - "Algae", () -> AutonomousCommands.autoFLeft(drive, superstructure, intake, manipulator)); - autoChooser.addRoutine( - "1 piece do nothing", - () -> AutonomousCommands.autoFLeftMinimal(drive, superstructure, intake, manipulator)); - SmartDashboard.putData("Autonomous Modes", autoChooser); - } - - /** - * Periodic function for the robot. This function is called every 20ms, and is responsible for - * updating the robot's state and logging relevant data. - */ - @Override - public void robotPeriodic() { - RobotState.periodic( - drive.getRawGyroRotation(), - NetworkTablesJNI.now(), - drive.getYawVelocity(), - drive.getModulePositions(), - vision.getCameras()); - - LoggedTunableNumber.updateAll(); - - Logger.recordOutput( - "Component Poses", - V3_EpsilonMechanism3d.getPoses( - elevator.getPositionMeters(), intake.getPivotAngle(), manipulator.getArmAngle())); - - if (!Constants.getMode().equals(Constants.Mode.REAL)) { - Logger.recordOutput( - "FieldSimulation/Algae", SimulatedArena.getInstance().getGamePiecesArrayByType("Algae")); - Logger.recordOutput( - "FieldSimulation/Coral", SimulatedArena.getInstance().getGamePiecesArrayByType("Coral")); + /** + * Returns the autonomous command for the robot. This command will be scheduled for the entire + * autonomous period. + * + * @return the autonomous command for the robot + */ + @Override + public Command getAutonomousCommand() { + return autoChooser.selectedCommand(); } - } - - /** - * Returns the autonomous command for the robot. This command will be scheduled for the entire - * autonomous period. - * - * @return the autonomous command for the robot - */ - @Override - public Command getAutonomousCommand() { - return autoChooser.selectedCommand(); - } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 68d4fab6..00ac3ac4 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -1,7 +1,5 @@ package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; -import static edu.wpi.first.units.Units.*; - import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; @@ -15,320 +13,324 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; -import java.util.Set; import lombok.Getter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; +import java.util.Set; + +import static edu.wpi.first.units.Units.*; + public class V3_EpsilonManipulator { - private final V3_EpsilonManipulatorIO io; - private final ManipulatorIOInputsAutoLogged inputs; + private final V3_EpsilonManipulatorIO io; + private final ManipulatorIOInputsAutoLogged inputs; + + @AutoLogOutput(key = "Manipulator/Arm Goal") + @Getter + private Rotation2d armGoal; + + @AutoLogOutput(key = "Manipulator/Roller Goal") + @Getter + private ManipulatorRollerState rollerGoal; + + private boolean isClosedLoop; + + Set algaeStates; + + public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { + this.io = io; + inputs = new ManipulatorIOInputsAutoLogged(); + + isClosedLoop = true; + armGoal = ManipulatorArmState.VERTICAL_UP.getAngle(RobotState.getScoreSide()); + rollerGoal = ManipulatorRollerState.STOP; + + algaeStates = + Set.of( + ManipulatorArmState.ALGAE_INTAKE_FLOOR, + ManipulatorArmState.REEF_INTAKE, + ManipulatorArmState.ALGAE_SCORE, + ManipulatorArmState.PRE_SCORE); + } + + public void periodic() { + io.updateInputs(inputs); + Logger.processInputs("Manipulator", inputs); + + if (isClosedLoop) { + io.setArmGoal(armGoal); + } + + if (rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { + io.setRollerVoltage(ManipulatorRollerState.SCORE_ALGAE.getVoltage()); + } else if (hasAlgae() + && Set.of( + ManipulatorRollerState.CORAL_INTAKE, + ManipulatorRollerState.STOP, + ManipulatorRollerState.ALGAE_INTAKE) + .contains(rollerGoal) + && !rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { + RobotState.setHasAlgae(true); + io.setRollerVoltage(holdVoltage()); + } else if (hasCoral()) { + io.setRollerVoltage(holdVoltage()); + } else { + io.setRollerVoltage(rollerGoal.getVoltage()); + } + } + + /** + * Checks if the manipulator is currently detecting coral. This is done by checking if the CAN + * range sensor is detecting a distance less than the coral detection threshold and greater than + * 0. + * + * @return True if the manipulator is detecting coral, false otherwise. + */ + @AutoLogOutput(key = "Manipulator/Has Coral") + public boolean hasCoral() { + return inputs.canRangeGot; + } + + /** + * Checks if the manipulator is currently detecting algae. This is done by checking if the CAN + * range sensor is detecting a distance less than the algae detection threshold and greater than + * 0. + * + * @return True if the manipulator is detecting algae, false otherwise. + */ + @AutoLogOutput(key = "Manipulator/Has Algae") + public boolean hasAlgae() { + boolean hasAlgae = rollerGoal.equals(ManipulatorRollerState.ALGAE_INTAKE) && inputs.canRangeGot; + return hasAlgae; + } + + /** + * Creates a command to run the manipulator arm at a specified voltage. + * + * @param volts The voltage to set the arm to. + * @return A command to run the arm. + */ + public Command runArm(double volts) { + return Commands.runEnd( + () -> { + isClosedLoop = false; + io.setArmVoltage(volts); + }, + () -> io.setArmVoltage(0)); + } + + /** + * Sets the goal for the manipulator arm to reach. + * + * @param goal The goal state to set the arm to. + */ + public void setArmGoal(ManipulatorArmState goal) { + isClosedLoop = true; + if (!algaeStates.contains(goal)) { + armGoal = goal.getAngle(RobotState.getScoreSide()); + } else { + armGoal = goal.getAngle(ScoreSide.CENTER); + } + } - @AutoLogOutput(key = "Manipulator/Arm Goal") - @Getter - private Rotation2d armGoal; + public void setArmGoal(Rotation2d goal) { + isClosedLoop = true; + armGoal = goal; + } + + /** + * Updates the gains for the manipulator arm. This function sets the PID gains for the three slots + * of the arm. The gains are used to control the arm's movement. + * + * @param kP0 The proportional gain for slot 0. + * @param kD0 The derivative gain for slot 0. + * @param kS0 The static gain for slot 0. + * @param kV0 The velocity gain for slot 0. + * @param kA0 The acceleration gain for slot 0. + * @param kG0 The gravity gain for slot 0. + * @param kP1 The proportional gain for slot 1. + * @param kD1 The derivative gain for slot 1. + * @param kS1 The static gain for slot 1. + * @param kV1 The velocity gain for slot 1. + * @param kA1 The acceleration gain for slot 1. + * @param kG1 The gravity gain for slot 1. + * @param kP2 The proportional gain for slot 2. + * @param kD2 The derivative gain for slot 2. + * @param kS2 The static gain for slot 2. + * @param kV2 The velocity gain for slot 2. + * @param kA2 The acceleration gain for slot 2. + * @param kG2 The gravity gain for slot 2. + */ + public void updateArmGains( + double kP0, + double kD0, + double kS0, + double kV0, + double kA0, + double kG0, + double kP1, + double kD1, + double kS1, + double kV1, + double kA1, + double kG1, + double kP2, + double kD2, + double kS2, + double kV2, + double kA2, + double kG2) { + io.updateSlot0ArmGains(kP0, kD0, kS0, kV0, kA0, kG0); + io.updateSlot1ArmGains(kP1, kD1, kS1, kV1, kA1, kG1); + io.updateSlot2ArmGains(kP2, kD2, kS2, kV2, kA2, kG2); + } + + /** + * Updates the constraints for the arm. + * + * @param maxAcceleration The maximum acceleration. + * @param maxVelocity The maximum velocity. + */ + public void updateArmConstraints(double maxAcceleration, double maxVelocity) { + io.updateArmConstraints(maxAcceleration, maxVelocity); + } - @AutoLogOutput(key = "Manipulator/Roller Goal") - @Getter - private ManipulatorRollerState rollerGoal; + /** + * Checks if the arm is at the goal position. + * + *

This function checks if the arm is within the goal tolerance of the currently set arm goal + * position. If the arm is within the tolerance, it returns true. Otherwise, it returns false. + * + * @return If the arm is at the goal position. + */ + @AutoLogOutput(key = "Manipulator/Arm At Goal") + public boolean armAtGoal() { + return armAtGoal(armGoal); + } - private boolean isClosedLoop; + public boolean armAtGoal(Rotation2d state) { + return Math.abs(inputs.armPosition.minus(state).getRadians()) + <= V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); + } - Set algaeStates; + public boolean armInTolerance(Rotation2d tolerance) { + return Math.abs(inputs.armPosition.minus(armGoal).getRadians()) <= tolerance.getRadians(); + } - public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { - this.io = io; - inputs = new ManipulatorIOInputsAutoLogged(); + /** + * Waits until the arm is at the goal position. + * + *

This command waits for 0.02 seconds and then checks if the arm is at the goal position. If + * the arm is not at the goal position, it waits for 0.02 seconds and checks again. This process + * repeats until the arm is at the goal position. + * + * @return A command that waits until the arm is at the goal position. + */ + public Command waitUntilArmAtGoal() { + return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::armAtGoal)); + } - isClosedLoop = true; - armGoal = ManipulatorArmState.VERTICAL_UP.getAngle(RobotState.getScoreSide()); - rollerGoal = ManipulatorRollerState.STOP; + /** + * Returns a voltage to hold the roller at the current position. The voltage is calculated based + * on the current torque current of the roller. The calculation is done using a piecewise + * polynomial function. The function first checks if the current torque current is less than or + * equal to 20. If it is, it uses one set of coefficients to calculate the voltage. Otherwise, it + * uses another set of coefficients. + */ + private double holdVoltage() { + return RobotState.isHasAlgae() ? -12.0 : -1; + } - algaeStates = - Set.of( - ManipulatorArmState.ALGAE_INTAKE_FLOOR, - ManipulatorArmState.REEF_INTAKE, - ManipulatorArmState.ALGAE_SCORE); - } + /** + * Sets the current slot of the manipulator arm based on the current state of the subsystem. If + * the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to + * 1. Otherwise, it sets the slot to 0. + */ + public void setSlot() { + if (RobotState.isHasAlgae()) { + io.setSlot(2); + } else if (hasCoral()) { + io.setSlot(1); + } else { + io.setSlot(0); + } + } - public void periodic() { - io.updateInputs(inputs); - Logger.processInputs("Manipulator", inputs); + /** + * Creates a command to run the SysId routine for the manipulator arm, generating the constants + * and gains for a PID. + * + * @param superstructure The V3 Epsiolon Superstructure. + * @return A command to run the SysId routine for the manipulator arm. + */ + public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure, ElevatorFSM elevator) { + SysIdRoutine algaeCharacterizationRoutine = + new SysIdRoutine( + new SysIdRoutine.Config( + Volts.of(0.5).per(Second), + Volts.of(8), + Seconds.of(10), + (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), + new SysIdRoutine.Mechanism( + (volts) -> io.setArmVoltage(volts.in(Volts)), null, superstructure)); + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.L4)), + Commands.runOnce(() -> isClosedLoop = false), + algaeCharacterizationRoutine.quasistatic(Direction.kForward), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.quasistatic(Direction.kReverse), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.dynamic(Direction.kForward), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.dynamic(Direction.kReverse)); + } - if (isClosedLoop) { - io.setArmGoal(armGoal); + /** + * Sets the manipulator arm to the specified state. + * + * @param state The state to set the arm to. + */ + public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmState state) { + io.setManipulatorState(state); } - if (rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { - io.setRollerVoltage(ManipulatorRollerState.SCORE_ALGAE.getVoltage()); - } else if (hasAlgae() - && Set.of( - ManipulatorRollerState.CORAL_INTAKE, - ManipulatorRollerState.STOP, - ManipulatorRollerState.ALGAE_INTAKE) - .contains(rollerGoal) - && !rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { - RobotState.setHasAlgae(true); - io.setRollerVoltage(holdVoltage()); - } else if (hasCoral()) { - io.setRollerVoltage(holdVoltage()); - } else { - io.setRollerVoltage(rollerGoal.getVoltage()); + /** + * Sets the roller goal state of the manipulator. If the subsystem has algae or coral and the goal + * is one of the intake states, it sets the roller voltage to the hold voltage. Otherwise, it sets + * the roller voltage to the goal voltage. + * + * @param rollerGoal The desired state of the roller. + */ + public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState rollerGoal) { + this.rollerGoal = rollerGoal; + if ((hasAlgae() || hasCoral()) + && Set.of( + V3_EpsilonManipulatorConstants.ManipulatorRollerState.ALGAE_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerState.CORAL_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerState.STOP) + .contains(rollerGoal)) { + + io.setRollerVoltage(holdVoltage()); + } else { + io.setRollerVoltage(rollerGoal.getVoltage()); + } } - } - - /** - * Checks if the manipulator is currently detecting coral. This is done by checking if the CAN - * range sensor is detecting a distance less than the coral detection threshold and greater than - * 0. - * - * @return True if the manipulator is detecting coral, false otherwise. - */ - @AutoLogOutput(key = "Manipulator/Has Coral") - public boolean hasCoral() { - return inputs.canRangeGot; - } - - /** - * Checks if the manipulator is currently detecting algae. This is done by checking if the CAN - * range sensor is detecting a distance less than the algae detection threshold and greater than - * 0. - * - * @return True if the manipulator is detecting algae, false otherwise. - */ - @AutoLogOutput(key = "Manipulator/Has Algae") - public boolean hasAlgae() { - boolean hasAlgae = rollerGoal.equals(ManipulatorRollerState.ALGAE_INTAKE) && inputs.canRangeGot; - return hasAlgae; - } - - /** - * Creates a command to run the manipulator arm at a specified voltage. - * - * @param volts The voltage to set the arm to. - * @return A command to run the arm. - */ - public Command runArm(double volts) { - return Commands.runEnd( - () -> { - isClosedLoop = false; - io.setArmVoltage(volts); - }, - () -> io.setArmVoltage(0)); - } - - /** - * Sets the goal for the manipulator arm to reach. - * - * @param goal The goal state to set the arm to. - */ - public void setArmGoal(ManipulatorArmState goal) { - isClosedLoop = true; - if (!algaeStates.contains(goal)) { - armGoal = goal.getAngle(RobotState.getScoreSide()); - } else { - armGoal = goal.getAngle(ScoreSide.CENTER); + + /** + * Gets the current angle of the manipulator arm. + * + * @return The current angle of the manipulator arm, in radians. + */ + public Rotation2d getArmAngle() { + return inputs.armPosition; } - } - - public void setArmGoal(Rotation2d goal) { - isClosedLoop = true; - armGoal = goal; - } - - /** - * Updates the gains for the manipulator arm. This function sets the PID gains for the three slots - * of the arm. The gains are used to control the arm's movement. - * - * @param kP0 The proportional gain for slot 0. - * @param kD0 The derivative gain for slot 0. - * @param kS0 The static gain for slot 0. - * @param kV0 The velocity gain for slot 0. - * @param kA0 The acceleration gain for slot 0. - * @param kG0 The gravity gain for slot 0. - * @param kP1 The proportional gain for slot 1. - * @param kD1 The derivative gain for slot 1. - * @param kS1 The static gain for slot 1. - * @param kV1 The velocity gain for slot 1. - * @param kA1 The acceleration gain for slot 1. - * @param kG1 The gravity gain for slot 1. - * @param kP2 The proportional gain for slot 2. - * @param kD2 The derivative gain for slot 2. - * @param kS2 The static gain for slot 2. - * @param kV2 The velocity gain for slot 2. - * @param kA2 The acceleration gain for slot 2. - * @param kG2 The gravity gain for slot 2. - */ - public void updateArmGains( - double kP0, - double kD0, - double kS0, - double kV0, - double kA0, - double kG0, - double kP1, - double kD1, - double kS1, - double kV1, - double kA1, - double kG1, - double kP2, - double kD2, - double kS2, - double kV2, - double kA2, - double kG2) { - io.updateSlot0ArmGains(kP0, kD0, kS0, kV0, kA0, kG0); - io.updateSlot1ArmGains(kP1, kD1, kS1, kV1, kA1, kG1); - io.updateSlot2ArmGains(kP2, kD2, kS2, kV2, kA2, kG2); - } - - /** - * Updates the constraints for the arm. - * - * @param maxAcceleration The maximum acceleration. - * @param maxVelocity The maximum velocity. - */ - public void updateArmConstraints(double maxAcceleration, double maxVelocity) { - io.updateArmConstraints(maxAcceleration, maxVelocity); - } - - /** - * Checks if the arm is at the goal position. - * - *

This function checks if the arm is within the goal tolerance of the currently set arm goal - * position. If the arm is within the tolerance, it returns true. Otherwise, it returns false. - * - * @return If the arm is at the goal position. - */ - @AutoLogOutput(key = "Manipulator/Arm At Goal") - public boolean armAtGoal() { - return armAtGoal(armGoal); - } - - public boolean armAtGoal(Rotation2d state) { - return Math.abs(inputs.armPosition.minus(state).getRadians()) - <= V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); - } - - public boolean armInTolerance(Rotation2d tolerance) { - return Math.abs(inputs.armPosition.minus(armGoal).getRadians()) <= tolerance.getRadians(); - } - - /** - * Waits until the arm is at the goal position. - * - *

This command waits for 0.02 seconds and then checks if the arm is at the goal position. If - * the arm is not at the goal position, it waits for 0.02 seconds and checks again. This process - * repeats until the arm is at the goal position. - * - * @return A command that waits until the arm is at the goal position. - */ - public Command waitUntilArmAtGoal() { - return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::armAtGoal)); - } - - /** - * Returns a voltage to hold the roller at the current position. The voltage is calculated based - * on the current torque current of the roller. The calculation is done using a piecewise - * polynomial function. The function first checks if the current torque current is less than or - * equal to 20. If it is, it uses one set of coefficients to calculate the voltage. Otherwise, it - * uses another set of coefficients. - */ - private double holdVoltage() { - return RobotState.isHasAlgae() ? -12.0 : -1; - } - - /** - * Sets the current slot of the manipulator arm based on the current state of the subsystem. If - * the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to - * 1. Otherwise, it sets the slot to 0. - */ - public void setSlot() { - if (RobotState.isHasAlgae()) { - io.setSlot(2); - } else if (hasCoral()) { - io.setSlot(1); - } else { - io.setSlot(0); + + public double getArmVelocity() { + return inputs.armVelocityRadiansPerSecond; } - } - - /** - * Creates a command to run the SysId routine for the manipulator arm, generating the constants - * and gains for a PID. - * - * @param superstructure The V3 Epsiolon Superstructure. - * @return A command to run the SysId routine for the manipulator arm. - */ - public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure, ElevatorFSM elevator) { - SysIdRoutine algaeCharacterizationRoutine = - new SysIdRoutine( - new SysIdRoutine.Config( - Volts.of(0.5).per(Second), - Volts.of(8), - Seconds.of(10), - (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), - new SysIdRoutine.Mechanism( - (volts) -> io.setArmVoltage(volts.in(Volts)), null, superstructure)); - return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.L4)), - Commands.runOnce(() -> isClosedLoop = false), - algaeCharacterizationRoutine.quasistatic(Direction.kForward), - Commands.waitSeconds(.25), - algaeCharacterizationRoutine.quasistatic(Direction.kReverse), - Commands.waitSeconds(.25), - algaeCharacterizationRoutine.dynamic(Direction.kForward), - Commands.waitSeconds(.25), - algaeCharacterizationRoutine.dynamic(Direction.kReverse)); - } - - /** - * Sets the manipulator arm to the specified state. - * - * @param state The state to set the arm to. - */ - public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmState state) { - io.setManipulatorState(state); - } - - /** - * Sets the roller goal state of the manipulator. If the subsystem has algae or coral and the goal - * is one of the intake states, it sets the roller voltage to the hold voltage. Otherwise, it sets - * the roller voltage to the goal voltage. - * - * @param rollerGoal The desired state of the roller. - */ - public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState rollerGoal) { - this.rollerGoal = rollerGoal; - if ((hasAlgae() || hasCoral()) - && Set.of( - V3_EpsilonManipulatorConstants.ManipulatorRollerState.ALGAE_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerState.CORAL_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerState.STOP) - .contains(rollerGoal)) { - - io.setRollerVoltage(holdVoltage()); - } else { - io.setRollerVoltage(rollerGoal.getVoltage()); + + public double getRollerVelocity() { + return inputs.rollerVelocityRadiansPerSecond; } - } - - /** - * Gets the current angle of the manipulator arm. - * - * @return The current angle of the manipulator arm, in radians. - */ - public Rotation2d getArmAngle() { - return inputs.armPosition; - } - - public double getArmVelocity() { - return inputs.armVelocityRadiansPerSecond; - } - - public double getRollerVelocity() { - return inputs.rollerVelocityRadiansPerSecond; - } } From 2846809be0224dbf61e3ddc708222613d430a0fe Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 1 Nov 2025 13:01:00 -0400 Subject: [PATCH 161/180] Update at 'Sat Nov 01 13:01:00 EDT 2025' --- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 628 +++++++++--------- .../manipulator/V3_EpsilonManipulator.java | 599 +++++++++-------- 2 files changed, 608 insertions(+), 619 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index d8582af8..86705e5b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -52,330 +52,320 @@ import org.littletonrobotics.junction.Logger; public class V3_EpsilonRobotContainer implements RobotContainer { - // Subsystems - private Drive drive; - private ElevatorFSM elevator; - private V3_EpsilonIntake intake; - private V3_EpsilonManipulator manipulator; - private V3_EpsilonSuperstructure superstructure; - private V3_EpsilonClimber climber; - private V3_EpsilonLEDs leds; - private Vision vision; - - // Controller - private static final CommandXboxController driver = new CommandXboxController(0); - private static final CommandXboxController operator = new CommandXboxController(1); - - // Auto chooser - private final ChoreoChooser autoChooser = new ChoreoChooser(); - - public V3_EpsilonRobotContainer() { - - if (Constants.getMode() != Mode.REPLAY) { - switch (Constants.ROBOT) { - case V3_EPSILON: - drive = - new Drive( - new GyroIOPigeon2(), - new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), - new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), - new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), - new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); - elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); - climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); - superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); - leds = new V3_EpsilonLEDs(); - vision = - new Vision( - () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), - RobotCameras.V3_EPSILON_CAMS); - break; - case V3_EPSILON_SIM: - drive = - new Drive( - new GyroIO() { - }, - new ModuleIOSim(DriveConstants.FRONT_LEFT), - new ModuleIOSim(DriveConstants.FRONT_RIGHT), - new ModuleIOSim(DriveConstants.BACK_LEFT), - new ModuleIOSim(DriveConstants.BACK_RIGHT)); - elevator = new Elevator(new ElevatorIOSim()).getFSM(); - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); - climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOSim()); - superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); - leds = new V3_EpsilonLEDs(); - vision = - new Vision( - () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), - RobotCameras.V3_EPSILON_CAMS); - break; - default: - break; - } - } - - if (drive == null) { - drive = - new Drive( - new GyroIO() { - }, - new ModuleIO() { - }, - new ModuleIO() { - }, - new ModuleIO() { - }, - new ModuleIO() { - }); - } - if (elevator == null) { - elevator = new Elevator(new ElevatorIO() { - }).getFSM(); - } - if (intake == null) { - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() { - }); - } - if (manipulator == null) { - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() { - }); - } - if (climber == null) { - climber = new V3_EpsilonClimber(new V3_EpsilonClimberIO() { - }); - } - if (leds == null) { - leds = new V3_EpsilonLEDs(); - } - if (superstructure == null) { - superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); - } - - LTNUpdater.registerAll(drive, elevator, intake, manipulator); - - configureButtonBindings(); - configureAutos(); + // Subsystems + private Drive drive; + private ElevatorFSM elevator; + private V3_EpsilonIntake intake; + private V3_EpsilonManipulator manipulator; + private V3_EpsilonSuperstructure superstructure; + private V3_EpsilonClimber climber; + private V3_EpsilonLEDs leds; + private Vision vision; + + // Controller + private static final CommandXboxController driver = new CommandXboxController(0); + private static final CommandXboxController operator = new CommandXboxController(1); + + // Auto chooser + private final ChoreoChooser autoChooser = new ChoreoChooser(); + + public V3_EpsilonRobotContainer() { + + if (Constants.getMode() != Mode.REPLAY) { + switch (Constants.ROBOT) { + case V3_EPSILON: + drive = + new Drive( + new GyroIOPigeon2(), + new ModuleIOTalonFX(0, DriveConstants.FRONT_LEFT), + new ModuleIOTalonFX(1, DriveConstants.FRONT_RIGHT), + new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), + new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); + elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); + climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + leds = new V3_EpsilonLEDs(); + vision = + new Vision( + () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), + RobotCameras.V3_EPSILON_CAMS); + break; + case V3_EPSILON_SIM: + drive = + new Drive( + new GyroIO() {}, + new ModuleIOSim(DriveConstants.FRONT_LEFT), + new ModuleIOSim(DriveConstants.FRONT_RIGHT), + new ModuleIOSim(DriveConstants.BACK_LEFT), + new ModuleIOSim(DriveConstants.BACK_RIGHT)); + elevator = new Elevator(new ElevatorIOSim()).getFSM(); + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); + climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOSim()); + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + leds = new V3_EpsilonLEDs(); + vision = + new Vision( + () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), + RobotCameras.V3_EPSILON_CAMS); + break; + default: + break; + } } - /** - * Configure the button bindings for the robot. This method is called in the constructor and is - * responsible for setting up the default commands for each button on the controllers. - */ - private void configureButtonBindings() { - Trigger elevatorStow = - new Trigger( - () -> - elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) - || elevator.getPosition().equals(ElevatorPositions.STOW)); - Trigger elevatorNotStow = - new Trigger( - () -> - !elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) - && !elevator.getPosition().equals(ElevatorPositions.STOW)); - drive.setDefaultCommand( - DriveCommands.joystickDrive( - drive, - () -> -driver.getLeftY(), - () -> -driver.getLeftX(), - () -> -driver.getRightX(), - () -> false, - () -> false, - driver.povRight())); - - driver.povDown().onTrue(SharedCommands.resetHeading(drive)); - - driver.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); - driver.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); - driver.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); - driver.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); - - driver - .y() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); - driver - .x() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); - driver - .b() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); - driver - .a() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); - - driver - .rightTrigger(0.5) - .whileTrue( - V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence(drive, superstructure)); - driver - .leftTrigger(0.5) - .whileTrue( - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake, manipulator)) - .onFalse( - V3_EpsilonCompositeCommands.postIntakeCoralSequence( - superstructure, intake, manipulator)); - - driver - .leftBumper() - .whileTrue(V3_EpsilonCompositeCommands.intakeAlgaeFloor(superstructure, manipulator)) - .onFalse( - Commands.either( - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), - () -> RobotState.isHasAlgae())); - driver.rightBumper().onTrue(Commands.runOnce(() -> RobotState.toggleReefPost())); - - driver.povUp().onTrue(superstructure.setPosition()); - driver.povDown().onTrue(SharedCommands.resetHeading(drive)); - driver.povLeft().onTrue(DriveCommands.inchMovement(drive, -0.5, .07)); - - driver - .leftStick() - .onTrue(V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence(drive, superstructure)); - - driver - .back() - .whileTrue(V3_EpsilonCompositeCommands.intakeAlgaeFromReef(drive, superstructure)) - .whileFalse(V3_EpsilonCompositeCommands.postIntakeAlgaeFromReef(drive, superstructure)); - - driver - .start() - .whileTrue( - V3_EpsilonCompositeCommands.dropAlgae( - drive, - elevator, - manipulator, - intake, - superstructure, - () -> RobotState.getReefAlignData().algaeIntakeHeight())); - - operator.y().onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); - operator.x().onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); - operator.b().onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); - operator.a().onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); - - operator - .y() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); - operator - .x() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); - operator - .b() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); - operator - .a() - .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); - - operator - .rightTrigger(0.5) - .whileTrue( - superstructure.override( - () -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_CORAL), 0.4)); - - operator.leftBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))); - operator.rightBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))); - - operator - .povUp() - .onTrue( - Commands.sequence( - Commands.runOnce(() -> manipulator.setArmGoal(Rotation2d.fromDegrees(90))), - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.HANDOFF)), - Commands.runOnce(() -> intake.setPivotGoal(IntakePivotState.L1)), - climber.releaseClimber())); - operator - .povDown() - .whileTrue( - Commands.sequence( - Commands.runOnce(() -> RobotState.setClimberReady(false)), - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.STOW)), - climber.winchClimber())); - operator - .povLeft() - .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR)) - .onFalse( - superstructure - .runActionWithTimeout(V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, 1) - .finallyDo(() -> RobotState.setHasAlgae(false))); - - operator.start().whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)); - - operator.back().onTrue(V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure)); + if (drive == null) { + drive = + new Drive( + new GyroIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}, + new ModuleIO() {}); } - - private void configureAutos() { - autoChooser.addCmd( - "Drive FF Characterization", () -> DriveCommands.feedforwardCharacterization(drive)); - autoChooser.addCmd( - "Wheel Radius Characterization", () -> DriveCommands.wheelRadiusCharacterization(drive)); - autoChooser.addRoutine( - "4 Piece Right Early Madtown", - () -> AutonomousCommands.autoERight(drive, superstructure, intake, manipulator)); - autoChooser.addRoutine( - "4 Piece Right Late Madtown", - () -> AutonomousCommands.autoERightBack(drive, superstructure, intake, manipulator)); - autoChooser.addRoutine( - "4 Piece Left Early Madtown", - () -> AutonomousCommands.autoELeft(drive, superstructure, intake, manipulator)); - autoChooser.addRoutine( - "4 Piece Left Late Madtown", - () -> AutonomousCommands.autoELeftBack(drive, superstructure, intake, manipulator)); - autoChooser.addRoutine( - "Algae", () -> AutonomousCommands.autoFLeft(drive, superstructure, intake, manipulator)); - autoChooser.addRoutine( - "1 piece do nothing", - () -> AutonomousCommands.autoFLeftMinimal(drive, superstructure, intake, manipulator)); - SmartDashboard.putData("Autonomous Modes", autoChooser); + if (elevator == null) { + elevator = new Elevator(new ElevatorIO() {}).getFSM(); } - - /** - * Periodic function for the robot. This function is called every 20ms, and is responsible for - * updating the robot's state and logging relevant data. - */ - @Override - public void robotPeriodic() { - RobotState.periodic( - drive.getRawGyroRotation(), - NetworkTablesJNI.now(), - drive.getYawVelocity(), - drive.getModulePositions(), - vision.getCameras()); - - LoggedTunableNumber.updateAll(); - - Logger.recordOutput( - "Component Poses", - V3_EpsilonMechanism3d.getPoses( - elevator.getPositionMeters(), intake.getPivotAngle(), manipulator.getArmAngle())); - - if (!Constants.getMode().equals(Constants.Mode.REAL)) { - Logger.recordOutput( - "FieldSimulation/Algae", SimulatedArena.getInstance().getGamePiecesArrayByType("Algae")); - Logger.recordOutput( - "FieldSimulation/Coral", SimulatedArena.getInstance().getGamePiecesArrayByType("Coral")); - } + if (intake == null) { + intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); + } + if (manipulator == null) { + manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); + } + if (climber == null) { + climber = new V3_EpsilonClimber(new V3_EpsilonClimberIO() {}); + } + if (leds == null) { + leds = new V3_EpsilonLEDs(); + } + if (superstructure == null) { + superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); } - /** - * Returns the autonomous command for the robot. This command will be scheduled for the entire - * autonomous period. - * - * @return the autonomous command for the robot - */ - @Override - public Command getAutonomousCommand() { - return autoChooser.selectedCommand(); + LTNUpdater.registerAll(drive, elevator, intake, manipulator); + + configureButtonBindings(); + configureAutos(); + } + + /** + * Configure the button bindings for the robot. This method is called in the constructor and is + * responsible for setting up the default commands for each button on the controllers. + */ + private void configureButtonBindings() { + Trigger elevatorStow = + new Trigger( + () -> + elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) + || elevator.getPosition().equals(ElevatorPositions.STOW)); + Trigger elevatorNotStow = + new Trigger( + () -> + !elevator.getPosition().equals(ElevatorPositions.CORAL_INTAKE) + && !elevator.getPosition().equals(ElevatorPositions.STOW)); + drive.setDefaultCommand( + DriveCommands.joystickDrive( + drive, + () -> -driver.getLeftY(), + () -> -driver.getLeftX(), + () -> -driver.getRightX(), + () -> false, + () -> false, + driver.povRight())); + + driver.povDown().onTrue(SharedCommands.resetHeading(drive)); + + driver.y().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); + driver.x().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); + driver.b().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); + driver.a().and(elevatorStow).onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); + + driver + .y() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); + driver + .x() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); + driver + .b() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); + driver + .a() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); + + driver + .rightTrigger(0.5) + .whileTrue( + V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence(drive, superstructure)); + driver + .leftTrigger(0.5) + .whileTrue( + V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + superstructure, intake, manipulator)) + .onFalse( + V3_EpsilonCompositeCommands.postIntakeCoralSequence( + superstructure, intake, manipulator)); + + driver + .leftBumper() + .whileTrue(V3_EpsilonCompositeCommands.intakeAlgaeFloor(superstructure, manipulator)) + .onFalse( + Commands.either( + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), + superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), + () -> RobotState.isHasAlgae())); + driver.rightBumper().onTrue(Commands.runOnce(() -> RobotState.toggleReefPost())); + + driver.povUp().onTrue(superstructure.setPosition()); + driver.povDown().onTrue(SharedCommands.resetHeading(drive)); + driver.povLeft().onTrue(DriveCommands.inchMovement(drive, -0.5, .07)); + + driver + .leftStick() + .onTrue(V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence(drive, superstructure)); + + driver + .back() + .whileTrue(V3_EpsilonCompositeCommands.intakeAlgaeFromReef(drive, superstructure)) + .whileFalse(V3_EpsilonCompositeCommands.postIntakeAlgaeFromReef(drive, superstructure)); + + driver + .start() + .whileTrue( + V3_EpsilonCompositeCommands.dropAlgae( + drive, + elevator, + manipulator, + intake, + superstructure, + () -> RobotState.getReefAlignData().algaeIntakeHeight())); + + operator.y().onTrue(SharedCommands.setStaticReefHeight(ReefState.L4)); + operator.x().onTrue(SharedCommands.setStaticReefHeight(ReefState.L3)); + operator.b().onTrue(SharedCommands.setStaticReefHeight(ReefState.L2)); + operator.a().onTrue(SharedCommands.setStaticReefHeight(ReefState.L1)); + + operator + .y() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); + operator + .x() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); + operator + .b() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); + operator + .a() + .and(elevatorNotStow) + .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); + + operator + .rightTrigger(0.5) + .whileTrue( + superstructure.override( + () -> manipulator.setRollerGoal(ManipulatorRollerState.SCORE_CORAL), 0.4)); + + operator.leftBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))); + operator.rightBumper().onTrue(Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))); + + operator + .povUp() + .onTrue( + Commands.sequence( + Commands.runOnce(() -> manipulator.setArmGoal(Rotation2d.fromDegrees(90))), + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.HANDOFF)), + Commands.runOnce(() -> intake.setPivotGoal(IntakePivotState.L1)), + climber.releaseClimber())); + operator + .povDown() + .whileTrue( + Commands.sequence( + Commands.runOnce(() -> RobotState.setClimberReady(false)), + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.STOW)), + climber.winchClimber())); + operator + .povLeft() + .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR)) + .onFalse( + superstructure + .runActionWithTimeout(V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, 1) + .finallyDo(() -> RobotState.setHasAlgae(false))); + + operator.start().whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)); + + operator.back().onTrue(V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure)); + } + + private void configureAutos() { + autoChooser.addCmd( + "Drive FF Characterization", () -> DriveCommands.feedforwardCharacterization(drive)); + autoChooser.addCmd( + "Wheel Radius Characterization", () -> DriveCommands.wheelRadiusCharacterization(drive)); + autoChooser.addRoutine( + "4 Piece Right Early Madtown", + () -> AutonomousCommands.autoERight(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "4 Piece Right Late Madtown", + () -> AutonomousCommands.autoERightBack(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "4 Piece Left Early Madtown", + () -> AutonomousCommands.autoELeft(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "4 Piece Left Late Madtown", + () -> AutonomousCommands.autoELeftBack(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "Algae", () -> AutonomousCommands.autoFLeft(drive, superstructure, intake, manipulator)); + autoChooser.addRoutine( + "1 piece do nothing", + () -> AutonomousCommands.autoFLeftMinimal(drive, superstructure, intake, manipulator)); + SmartDashboard.putData("Autonomous Modes", autoChooser); + } + + /** + * Periodic function for the robot. This function is called every 20ms, and is responsible for + * updating the robot's state and logging relevant data. + */ + @Override + public void robotPeriodic() { + RobotState.periodic( + drive.getRawGyroRotation(), + NetworkTablesJNI.now(), + drive.getYawVelocity(), + drive.getModulePositions(), + vision.getCameras()); + + LoggedTunableNumber.updateAll(); + + Logger.recordOutput( + "Component Poses", + V3_EpsilonMechanism3d.getPoses( + elevator.getPositionMeters(), intake.getPivotAngle(), manipulator.getArmAngle())); + + if (!Constants.getMode().equals(Constants.Mode.REAL)) { + Logger.recordOutput( + "FieldSimulation/Algae", SimulatedArena.getInstance().getGamePiecesArrayByType("Algae")); + Logger.recordOutput( + "FieldSimulation/Coral", SimulatedArena.getInstance().getGamePiecesArrayByType("Coral")); } + } + + /** + * Returns the autonomous command for the robot. This command will be scheduled for the entire + * autonomous period. + * + * @return the autonomous command for the robot + */ + @Override + public Command getAutonomousCommand() { + return autoChooser.selectedCommand(); + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 00ac3ac4..1f9f98b2 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -1,5 +1,7 @@ package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; +import static edu.wpi.first.units.Units.*; + import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; @@ -13,324 +15,321 @@ import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; +import java.util.Set; import lombok.Getter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; -import java.util.Set; - -import static edu.wpi.first.units.Units.*; - public class V3_EpsilonManipulator { - private final V3_EpsilonManipulatorIO io; - private final ManipulatorIOInputsAutoLogged inputs; - - @AutoLogOutput(key = "Manipulator/Arm Goal") - @Getter - private Rotation2d armGoal; - - @AutoLogOutput(key = "Manipulator/Roller Goal") - @Getter - private ManipulatorRollerState rollerGoal; - - private boolean isClosedLoop; - - Set algaeStates; - - public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { - this.io = io; - inputs = new ManipulatorIOInputsAutoLogged(); - - isClosedLoop = true; - armGoal = ManipulatorArmState.VERTICAL_UP.getAngle(RobotState.getScoreSide()); - rollerGoal = ManipulatorRollerState.STOP; - - algaeStates = - Set.of( - ManipulatorArmState.ALGAE_INTAKE_FLOOR, - ManipulatorArmState.REEF_INTAKE, - ManipulatorArmState.ALGAE_SCORE, - ManipulatorArmState.PRE_SCORE); - } - - public void periodic() { - io.updateInputs(inputs); - Logger.processInputs("Manipulator", inputs); - - if (isClosedLoop) { - io.setArmGoal(armGoal); - } - - if (rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { - io.setRollerVoltage(ManipulatorRollerState.SCORE_ALGAE.getVoltage()); - } else if (hasAlgae() - && Set.of( - ManipulatorRollerState.CORAL_INTAKE, - ManipulatorRollerState.STOP, - ManipulatorRollerState.ALGAE_INTAKE) - .contains(rollerGoal) - && !rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { - RobotState.setHasAlgae(true); - io.setRollerVoltage(holdVoltage()); - } else if (hasCoral()) { - io.setRollerVoltage(holdVoltage()); - } else { - io.setRollerVoltage(rollerGoal.getVoltage()); - } - } - - /** - * Checks if the manipulator is currently detecting coral. This is done by checking if the CAN - * range sensor is detecting a distance less than the coral detection threshold and greater than - * 0. - * - * @return True if the manipulator is detecting coral, false otherwise. - */ - @AutoLogOutput(key = "Manipulator/Has Coral") - public boolean hasCoral() { - return inputs.canRangeGot; - } - - /** - * Checks if the manipulator is currently detecting algae. This is done by checking if the CAN - * range sensor is detecting a distance less than the algae detection threshold and greater than - * 0. - * - * @return True if the manipulator is detecting algae, false otherwise. - */ - @AutoLogOutput(key = "Manipulator/Has Algae") - public boolean hasAlgae() { - boolean hasAlgae = rollerGoal.equals(ManipulatorRollerState.ALGAE_INTAKE) && inputs.canRangeGot; - return hasAlgae; - } - - /** - * Creates a command to run the manipulator arm at a specified voltage. - * - * @param volts The voltage to set the arm to. - * @return A command to run the arm. - */ - public Command runArm(double volts) { - return Commands.runEnd( - () -> { - isClosedLoop = false; - io.setArmVoltage(volts); - }, - () -> io.setArmVoltage(0)); - } - - /** - * Sets the goal for the manipulator arm to reach. - * - * @param goal The goal state to set the arm to. - */ - public void setArmGoal(ManipulatorArmState goal) { - isClosedLoop = true; - if (!algaeStates.contains(goal)) { - armGoal = goal.getAngle(RobotState.getScoreSide()); - } else { - armGoal = goal.getAngle(ScoreSide.CENTER); - } - } + private final V3_EpsilonManipulatorIO io; + private final ManipulatorIOInputsAutoLogged inputs; - public void setArmGoal(Rotation2d goal) { - isClosedLoop = true; - armGoal = goal; - } - - /** - * Updates the gains for the manipulator arm. This function sets the PID gains for the three slots - * of the arm. The gains are used to control the arm's movement. - * - * @param kP0 The proportional gain for slot 0. - * @param kD0 The derivative gain for slot 0. - * @param kS0 The static gain for slot 0. - * @param kV0 The velocity gain for slot 0. - * @param kA0 The acceleration gain for slot 0. - * @param kG0 The gravity gain for slot 0. - * @param kP1 The proportional gain for slot 1. - * @param kD1 The derivative gain for slot 1. - * @param kS1 The static gain for slot 1. - * @param kV1 The velocity gain for slot 1. - * @param kA1 The acceleration gain for slot 1. - * @param kG1 The gravity gain for slot 1. - * @param kP2 The proportional gain for slot 2. - * @param kD2 The derivative gain for slot 2. - * @param kS2 The static gain for slot 2. - * @param kV2 The velocity gain for slot 2. - * @param kA2 The acceleration gain for slot 2. - * @param kG2 The gravity gain for slot 2. - */ - public void updateArmGains( - double kP0, - double kD0, - double kS0, - double kV0, - double kA0, - double kG0, - double kP1, - double kD1, - double kS1, - double kV1, - double kA1, - double kG1, - double kP2, - double kD2, - double kS2, - double kV2, - double kA2, - double kG2) { - io.updateSlot0ArmGains(kP0, kD0, kS0, kV0, kA0, kG0); - io.updateSlot1ArmGains(kP1, kD1, kS1, kV1, kA1, kG1); - io.updateSlot2ArmGains(kP2, kD2, kS2, kV2, kA2, kG2); - } - - /** - * Updates the constraints for the arm. - * - * @param maxAcceleration The maximum acceleration. - * @param maxVelocity The maximum velocity. - */ - public void updateArmConstraints(double maxAcceleration, double maxVelocity) { - io.updateArmConstraints(maxAcceleration, maxVelocity); - } + @AutoLogOutput(key = "Manipulator/Arm Goal") + @Getter + private Rotation2d armGoal; - /** - * Checks if the arm is at the goal position. - * - *

This function checks if the arm is within the goal tolerance of the currently set arm goal - * position. If the arm is within the tolerance, it returns true. Otherwise, it returns false. - * - * @return If the arm is at the goal position. - */ - @AutoLogOutput(key = "Manipulator/Arm At Goal") - public boolean armAtGoal() { - return armAtGoal(armGoal); - } + @AutoLogOutput(key = "Manipulator/Roller Goal") + @Getter + private ManipulatorRollerState rollerGoal; - public boolean armAtGoal(Rotation2d state) { - return Math.abs(inputs.armPosition.minus(state).getRadians()) - <= V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); - } + private boolean isClosedLoop; - public boolean armInTolerance(Rotation2d tolerance) { - return Math.abs(inputs.armPosition.minus(armGoal).getRadians()) <= tolerance.getRadians(); - } + Set algaeStates; - /** - * Waits until the arm is at the goal position. - * - *

This command waits for 0.02 seconds and then checks if the arm is at the goal position. If - * the arm is not at the goal position, it waits for 0.02 seconds and checks again. This process - * repeats until the arm is at the goal position. - * - * @return A command that waits until the arm is at the goal position. - */ - public Command waitUntilArmAtGoal() { - return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::armAtGoal)); - } + public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { + this.io = io; + inputs = new ManipulatorIOInputsAutoLogged(); - /** - * Returns a voltage to hold the roller at the current position. The voltage is calculated based - * on the current torque current of the roller. The calculation is done using a piecewise - * polynomial function. The function first checks if the current torque current is less than or - * equal to 20. If it is, it uses one set of coefficients to calculate the voltage. Otherwise, it - * uses another set of coefficients. - */ - private double holdVoltage() { - return RobotState.isHasAlgae() ? -12.0 : -1; - } + isClosedLoop = true; + armGoal = ManipulatorArmState.VERTICAL_UP.getAngle(RobotState.getScoreSide()); + rollerGoal = ManipulatorRollerState.STOP; - /** - * Sets the current slot of the manipulator arm based on the current state of the subsystem. If - * the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to - * 1. Otherwise, it sets the slot to 0. - */ - public void setSlot() { - if (RobotState.isHasAlgae()) { - io.setSlot(2); - } else if (hasCoral()) { - io.setSlot(1); - } else { - io.setSlot(0); - } - } + algaeStates = + Set.of( + ManipulatorArmState.ALGAE_INTAKE_FLOOR, + ManipulatorArmState.REEF_INTAKE, + ManipulatorArmState.ALGAE_SCORE, + ManipulatorArmState.PRE_SCORE); + } - /** - * Creates a command to run the SysId routine for the manipulator arm, generating the constants - * and gains for a PID. - * - * @param superstructure The V3 Epsiolon Superstructure. - * @return A command to run the SysId routine for the manipulator arm. - */ - public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure, ElevatorFSM elevator) { - SysIdRoutine algaeCharacterizationRoutine = - new SysIdRoutine( - new SysIdRoutine.Config( - Volts.of(0.5).per(Second), - Volts.of(8), - Seconds.of(10), - (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), - new SysIdRoutine.Mechanism( - (volts) -> io.setArmVoltage(volts.in(Volts)), null, superstructure)); - return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), - Commands.runOnce(() -> elevator.setPosition(() -> ReefState.L4)), - Commands.runOnce(() -> isClosedLoop = false), - algaeCharacterizationRoutine.quasistatic(Direction.kForward), - Commands.waitSeconds(.25), - algaeCharacterizationRoutine.quasistatic(Direction.kReverse), - Commands.waitSeconds(.25), - algaeCharacterizationRoutine.dynamic(Direction.kForward), - Commands.waitSeconds(.25), - algaeCharacterizationRoutine.dynamic(Direction.kReverse)); - } + public void periodic() { + io.updateInputs(inputs); + Logger.processInputs("Manipulator", inputs); - /** - * Sets the manipulator arm to the specified state. - * - * @param state The state to set the arm to. - */ - public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmState state) { - io.setManipulatorState(state); + if (isClosedLoop) { + io.setArmGoal(armGoal); } - /** - * Sets the roller goal state of the manipulator. If the subsystem has algae or coral and the goal - * is one of the intake states, it sets the roller voltage to the hold voltage. Otherwise, it sets - * the roller voltage to the goal voltage. - * - * @param rollerGoal The desired state of the roller. - */ - public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState rollerGoal) { - this.rollerGoal = rollerGoal; - if ((hasAlgae() || hasCoral()) - && Set.of( - V3_EpsilonManipulatorConstants.ManipulatorRollerState.ALGAE_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerState.CORAL_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerState.STOP) - .contains(rollerGoal)) { - - io.setRollerVoltage(holdVoltage()); - } else { - io.setRollerVoltage(rollerGoal.getVoltage()); - } + if (rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { + io.setRollerVoltage(ManipulatorRollerState.SCORE_ALGAE.getVoltage()); + } else if (hasAlgae() + && Set.of( + ManipulatorRollerState.CORAL_INTAKE, + ManipulatorRollerState.STOP, + ManipulatorRollerState.ALGAE_INTAKE) + .contains(rollerGoal) + && !rollerGoal.equals(ManipulatorRollerState.SCORE_ALGAE)) { + RobotState.setHasAlgae(true); + io.setRollerVoltage(holdVoltage()); + } else if (hasCoral()) { + io.setRollerVoltage(holdVoltage()); + } else { + io.setRollerVoltage(rollerGoal.getVoltage()); } - - /** - * Gets the current angle of the manipulator arm. - * - * @return The current angle of the manipulator arm, in radians. - */ - public Rotation2d getArmAngle() { - return inputs.armPosition; + } + + /** + * Checks if the manipulator is currently detecting coral. This is done by checking if the CAN + * range sensor is detecting a distance less than the coral detection threshold and greater than + * 0. + * + * @return True if the manipulator is detecting coral, false otherwise. + */ + @AutoLogOutput(key = "Manipulator/Has Coral") + public boolean hasCoral() { + return inputs.canRangeGot; + } + + /** + * Checks if the manipulator is currently detecting algae. This is done by checking if the CAN + * range sensor is detecting a distance less than the algae detection threshold and greater than + * 0. + * + * @return True if the manipulator is detecting algae, false otherwise. + */ + @AutoLogOutput(key = "Manipulator/Has Algae") + public boolean hasAlgae() { + boolean hasAlgae = rollerGoal.equals(ManipulatorRollerState.ALGAE_INTAKE) && inputs.canRangeGot; + return hasAlgae; + } + + /** + * Creates a command to run the manipulator arm at a specified voltage. + * + * @param volts The voltage to set the arm to. + * @return A command to run the arm. + */ + public Command runArm(double volts) { + return Commands.runEnd( + () -> { + isClosedLoop = false; + io.setArmVoltage(volts); + }, + () -> io.setArmVoltage(0)); + } + + /** + * Sets the goal for the manipulator arm to reach. + * + * @param goal The goal state to set the arm to. + */ + public void setArmGoal(ManipulatorArmState goal) { + isClosedLoop = true; + if (!algaeStates.contains(goal)) { + armGoal = goal.getAngle(RobotState.getScoreSide()); + } else { + armGoal = goal.getAngle(ScoreSide.CENTER); } - - public double getArmVelocity() { - return inputs.armVelocityRadiansPerSecond; + } + + public void setArmGoal(Rotation2d goal) { + isClosedLoop = true; + armGoal = goal; + } + + /** + * Updates the gains for the manipulator arm. This function sets the PID gains for the three slots + * of the arm. The gains are used to control the arm's movement. + * + * @param kP0 The proportional gain for slot 0. + * @param kD0 The derivative gain for slot 0. + * @param kS0 The static gain for slot 0. + * @param kV0 The velocity gain for slot 0. + * @param kA0 The acceleration gain for slot 0. + * @param kG0 The gravity gain for slot 0. + * @param kP1 The proportional gain for slot 1. + * @param kD1 The derivative gain for slot 1. + * @param kS1 The static gain for slot 1. + * @param kV1 The velocity gain for slot 1. + * @param kA1 The acceleration gain for slot 1. + * @param kG1 The gravity gain for slot 1. + * @param kP2 The proportional gain for slot 2. + * @param kD2 The derivative gain for slot 2. + * @param kS2 The static gain for slot 2. + * @param kV2 The velocity gain for slot 2. + * @param kA2 The acceleration gain for slot 2. + * @param kG2 The gravity gain for slot 2. + */ + public void updateArmGains( + double kP0, + double kD0, + double kS0, + double kV0, + double kA0, + double kG0, + double kP1, + double kD1, + double kS1, + double kV1, + double kA1, + double kG1, + double kP2, + double kD2, + double kS2, + double kV2, + double kA2, + double kG2) { + io.updateSlot0ArmGains(kP0, kD0, kS0, kV0, kA0, kG0); + io.updateSlot1ArmGains(kP1, kD1, kS1, kV1, kA1, kG1); + io.updateSlot2ArmGains(kP2, kD2, kS2, kV2, kA2, kG2); + } + + /** + * Updates the constraints for the arm. + * + * @param maxAcceleration The maximum acceleration. + * @param maxVelocity The maximum velocity. + */ + public void updateArmConstraints(double maxAcceleration, double maxVelocity) { + io.updateArmConstraints(maxAcceleration, maxVelocity); + } + + /** + * Checks if the arm is at the goal position. + * + *

This function checks if the arm is within the goal tolerance of the currently set arm goal + * position. If the arm is within the tolerance, it returns true. Otherwise, it returns false. + * + * @return If the arm is at the goal position. + */ + @AutoLogOutput(key = "Manipulator/Arm At Goal") + public boolean armAtGoal() { + return armAtGoal(armGoal); + } + + public boolean armAtGoal(Rotation2d state) { + return Math.abs(inputs.armPosition.minus(state).getRadians()) + <= V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); + } + + public boolean armInTolerance(Rotation2d tolerance) { + return Math.abs(inputs.armPosition.minus(armGoal).getRadians()) <= tolerance.getRadians(); + } + + /** + * Waits until the arm is at the goal position. + * + *

This command waits for 0.02 seconds and then checks if the arm is at the goal position. If + * the arm is not at the goal position, it waits for 0.02 seconds and checks again. This process + * repeats until the arm is at the goal position. + * + * @return A command that waits until the arm is at the goal position. + */ + public Command waitUntilArmAtGoal() { + return Commands.sequence(Commands.waitSeconds(0.02), Commands.waitUntil(this::armAtGoal)); + } + + /** + * Returns a voltage to hold the roller at the current position. The voltage is calculated based + * on the current torque current of the roller. The calculation is done using a piecewise + * polynomial function. The function first checks if the current torque current is less than or + * equal to 20. If it is, it uses one set of coefficients to calculate the voltage. Otherwise, it + * uses another set of coefficients. + */ + private double holdVoltage() { + return RobotState.isHasAlgae() ? -12.0 : -1; + } + + /** + * Sets the current slot of the manipulator arm based on the current state of the subsystem. If + * the subsystem has algae, it sets the slot to 2. If the subsystem has coral, it sets the slot to + * 1. Otherwise, it sets the slot to 0. + */ + public void setSlot() { + if (RobotState.isHasAlgae()) { + io.setSlot(2); + } else if (hasCoral()) { + io.setSlot(1); + } else { + io.setSlot(0); } - - public double getRollerVelocity() { - return inputs.rollerVelocityRadiansPerSecond; + } + + /** + * Creates a command to run the SysId routine for the manipulator arm, generating the constants + * and gains for a PID. + * + * @param superstructure The V3 Epsiolon Superstructure. + * @return A command to run the SysId routine for the manipulator arm. + */ + public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure, ElevatorFSM elevator) { + SysIdRoutine algaeCharacterizationRoutine = + new SysIdRoutine( + new SysIdRoutine.Config( + Volts.of(0.5).per(Second), + Volts.of(8), + Seconds.of(10), + (state) -> Logger.recordOutput("Manipulator/SysID State", state.toString())), + new SysIdRoutine.Mechanism( + (volts) -> io.setArmVoltage(volts.in(Volts)), null, superstructure)); + return Commands.sequence( + superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), + Commands.runOnce(() -> elevator.setPosition(() -> ReefState.L4)), + Commands.runOnce(() -> isClosedLoop = false), + algaeCharacterizationRoutine.quasistatic(Direction.kForward), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.quasistatic(Direction.kReverse), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.dynamic(Direction.kForward), + Commands.waitSeconds(.25), + algaeCharacterizationRoutine.dynamic(Direction.kReverse)); + } + + /** + * Sets the manipulator arm to the specified state. + * + * @param state The state to set the arm to. + */ + public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmState state) { + io.setManipulatorState(state); + } + + /** + * Sets the roller goal state of the manipulator. If the subsystem has algae or coral and the goal + * is one of the intake states, it sets the roller voltage to the hold voltage. Otherwise, it sets + * the roller voltage to the goal voltage. + * + * @param rollerGoal The desired state of the roller. + */ + public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState rollerGoal) { + this.rollerGoal = rollerGoal; + if ((hasAlgae() || hasCoral()) + && Set.of( + V3_EpsilonManipulatorConstants.ManipulatorRollerState.ALGAE_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerState.CORAL_INTAKE, + V3_EpsilonManipulatorConstants.ManipulatorRollerState.STOP) + .contains(rollerGoal)) { + + io.setRollerVoltage(holdVoltage()); + } else { + io.setRollerVoltage(rollerGoal.getVoltage()); } + } + + /** + * Gets the current angle of the manipulator arm. + * + * @return The current angle of the manipulator arm, in radians. + */ + public Rotation2d getArmAngle() { + return inputs.armPosition; + } + + public double getArmVelocity() { + return inputs.armVelocityRadiansPerSecond; + } + + public double getRollerVelocity() { + return inputs.rollerVelocityRadiansPerSecond; + } } From 2919895725150e6b6d73c3a9473d717c1d3c7598 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 1 Nov 2025 13:06:50 -0400 Subject: [PATCH 162/180] Update at 'Sat Nov 01 13:06:50 EDT 2025' --- .../V3_EpsilonSuperstructureEdges.java | 264 +++++++------ .../V3_EpsilonSuperstructureStates.java | 374 +++++++++--------- 2 files changed, 322 insertions(+), 316 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index f860c478..c3c7a988 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -1,14 +1,12 @@ package frc.robot.subsystems.v3_Epsilon.superstructure; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj.Filesystem; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; -import java.io.FileReader; -import java.io.Reader; -import java.util.ArrayList; import lombok.Builder; import lombok.Getter; import lombok.Setter; @@ -16,141 +14,147 @@ import org.jgrapht.graph.DefaultEdge; import org.jgrapht.nio.dot.DOTImporter; -public class V3_EpsilonSuperstructureEdges { - public static final ArrayList UNCONSTRAINED = new ArrayList<>(); - public static final ArrayList NO_ALGAE_EDGES = new ArrayList<>(); +import java.io.FileReader; +import java.io.Reader; +import java.util.ArrayList; - public record Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { - public Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { - this.from = from; - this.to = to; +public class V3_EpsilonSuperstructureEdges { + public static final ArrayList UNCONSTRAINED = new ArrayList<>(); + public static final ArrayList NO_ALGAE_EDGES = new ArrayList<>(); + + public record Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { + public Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { + this.from = from; + this.to = to; + } + + @Override + public String toString() { + return from + " -> " + to; + } } - @Override - public String toString() { - return from + " -> " + to; + public enum GamePieceEdge { + UNCONSTRAINED, + NO_ALGAE } - } - - public enum GamePieceEdge { - UNCONSTRAINED, - NO_ALGAE - } - - public static void loadEdgesFromDot( - String path, - Graph graph, - ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - - DOTImporter importer = new DOTImporter<>(); - - // --- Fix 1: safer vertex factory --- - importer.setVertexFactory( - id -> { - try { - return V3_EpsilonSuperstructureStates.valueOf(id); - } catch (IllegalArgumentException e) { - System.err.println("[DOT Import] Unknown vertex in DOT: " + id); - return null; - } - }); - - // --- Fix 2: ensure edge objects are valid --- - importer.setEdgeWithAttributesFactory( - attributes -> { - GamePieceEdge type = GamePieceEdge.UNCONSTRAINED; - - if (attributes.containsKey("type")) { - try { - type = GamePieceEdge.valueOf(attributes.get("type").getValue().toUpperCase()); - } catch (Exception e) { - System.err.println("[DOT Import] Invalid edge type, defaulting to UNCONSTRAINED"); - } - } - - // Create a proper EdgeCommand with no command yet - return EdgeCommand.builder().gamePieceEdge(type).command(null).build(); - }); - - // --- Fix 3: actually import the file and verify success --- - try (Reader r = new FileReader(path)) { - importer.importGraph(graph, r); - } catch (Exception ex) { - throw new RuntimeException("Failed to parse DOT file: " + path, ex); + + public static void loadEdgesFromDot( + String path, + Graph graph, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + + DOTImporter importer = new DOTImporter<>(); + + // --- Fix 1: safer vertex factory --- + importer.setVertexFactory( + id -> { + try { + return V3_EpsilonSuperstructureStates.valueOf(id); + } catch (IllegalArgumentException e) { + System.err.println("[DOT Import] Unknown vertex in DOT: " + id); + return null; + } + }); + + // --- Fix 2: ensure edge objects are valid --- + importer.setEdgeWithAttributesFactory( + attributes -> { + GamePieceEdge type = GamePieceEdge.UNCONSTRAINED; + + if (attributes.containsKey("type")) { + try { + type = GamePieceEdge.valueOf(attributes.get("type").getValue().toUpperCase()); + } catch (Exception e) { + System.err.println("[DOT Import] Invalid edge type, defaulting to UNCONSTRAINED"); + } + } + + // Create a proper EdgeCommand with no command yet + return EdgeCommand.builder().gamePieceEdge(type).command(null).build(); + }); + + // --- Fix 3: actually import the file and verify success --- + try (Reader r = new FileReader(path)) { + importer.importGraph(graph, r); + } catch (Exception ex) { + throw new RuntimeException("Failed to parse DOT file: " + path, ex); + } + + // --- Fix 4: assign the edge commands after load --- + for (EdgeCommand e : graph.edgeSet()) { + V3_EpsilonSuperstructureStates from = graph.getEdgeSource(e); + V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(e); + e.setCommand(getEdgeCommand(from, to, elevator, intake, manipulator)); + } + + System.out.printf( + "[DOT Import] Loaded %d vertices, %d edges%n", + graph.vertexSet().size(), graph.edgeSet().size()); } - // --- Fix 4: assign the edge commands after load --- - for (EdgeCommand e : graph.edgeSet()) { - V3_EpsilonSuperstructureStates from = graph.getEdgeSource(e); - V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(e); - e.setCommand(getEdgeCommand(from, to, elevator, intake, manipulator)); + @Builder(toBuilder = true) + @Getter + public static class EdgeCommand extends DefaultEdge { + @Setter + private Command command; + @Builder.Default + private GamePieceEdge gamePieceEdge = GamePieceEdge.UNCONSTRAINED; } - System.out.printf( - "[DOT Import] Loaded %d vertices, %d edges%n", - graph.vertexSet().size(), graph.edgeSet().size()); - } - - @Builder(toBuilder = true) - @Getter - public static class EdgeCommand extends DefaultEdge { - @Setter private Command command; - @Builder.Default private GamePieceEdge gamePieceEdge = GamePieceEdge.UNCONSTRAINED; - } - - /** - * Gets the command to execute for a given edge in the superstructure state graph. This command - * typically involves coordinating the elevator, funnel, intake, and manipulator subsystems to - * move from one state to another. - * - * @param from The starting state of the superstructure. - * @param to The target state of the superstructure. - * @param elevator The elevator subsystem. - * @param intake The intake subsystem. - * @param manipulator The manipulator subsystem. - * @return A {@link Command} that, when executed, transitions the superstructure from the 'from' - * state to the 'to' state. - */ - private static Command getEdgeCommand( - V3_EpsilonSuperstructureStates from, - V3_EpsilonSuperstructureStates to, - ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - - V3_EpsilonSuperstructurePose pose = to.getPose(); - - if (to.equals(V3_EpsilonSuperstructureStates.BARGE_SCORE)) { - return Commands.sequence( - pose.asConfigurationSpaceCommand(elevator, intake, manipulator), - Commands.waitUntil(() -> elevator.pastBargeThresholdgetPositionMeters())); + /** + * Gets the command to execute for a given edge in the superstructure state graph. This command + * typically involves coordinating the elevator, funnel, intake, and manipulator subsystems to + * move from one state to another. + * + * @param from The starting state of the superstructure. + * @param to The target state of the superstructure. + * @param elevator The elevator subsystem. + * @param intake The intake subsystem. + * @param manipulator The manipulator subsystem. + * @return A {@link Command} that, when executed, transitions the superstructure from the 'from' + * state to the 'to' state. + */ + private static Command getEdgeCommand( + V3_EpsilonSuperstructureStates from, + V3_EpsilonSuperstructureStates to, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + + V3_EpsilonSuperstructurePose pose = to.getPose(); + + if (to.equals(V3_EpsilonSuperstructureStates.BARGE_SCORE)) { + return Commands.sequence( + pose.asConfigurationSpaceCommand(elevator, intake, manipulator), + Commands.waitUntil(() -> manipulator.armInTolerance(Rotation2d.fromDegrees(15)))); + } + + return Commands.sequence( + pose.asConfigurationSpaceCommand(elevator, intake, manipulator), + pose.wait(elevator, intake, manipulator)); } - return Commands.sequence( - pose.asConfigurationSpaceCommand(elevator, intake, manipulator), - pose.wait(elevator, intake, manipulator)); - } - - /** - * Adds all predefined edges to the superstructure state graph, categorized by algae condition. - * - * @param graph The graph to which edges are added. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. - */ - public static void addEdges( - Graph graph, - ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - loadEdgesFromDot( - Filesystem.getDeployDirectory().toPath().resolve("Superstructure.dot").toString(), - graph, - elevator, - intake, - manipulator); - } + /** + * Adds all predefined edges to the superstructure state graph, categorized by algae condition. + * + * @param graph The graph to which edges are added. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param intake The intake subsystem. + */ + public static void addEdges( + Graph graph, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + loadEdgesFromDot( + Filesystem.getDeployDirectory().toPath().resolve("Superstructure.dot").toString(), + graph, + elevator, + intake, + manipulator); + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index 2580533c..fe64c6b3 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -11,190 +11,192 @@ import lombok.Getter; public enum V3_EpsilonSuperstructureStates { - START("START", new SubsystemPoses(), SubsystemActions.empty()), - STOW_DOWN( - "STOW_DOWN", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), - SubsystemActions.empty()), - STOW_UP( - "STOW_UP", - new SubsystemPoses( - ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), - SubsystemActions.empty()), - OVERRIDE("OVERRIDE", new SubsystemPoses(), SubsystemActions.empty()), - GROUND_ACQUISITION( - "GROUND_ACQUISITION", - new SubsystemPoses( - ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), - SubsystemActions.empty()), - GROUND_INTAKE_ALGAE( - "GROUND_INTAKE_ALGAE", - new SubsystemPoses( - ReefState.ALGAE_FLOOR_INTAKE, - ManipulatorArmState.ALGAE_INTAKE_FLOOR, - IntakePivotState.INTAKE_ALGAE), - new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), - GROUND_AQUISITION_ALGAE( - "GROUND_AQUISITION_ALGAE", - new SubsystemPoses( - ReefState.ALGAE_FLOOR_INTAKE, - ManipulatorArmState.ALGAE_INTAKE_FLOOR, - IntakePivotState.INTAKE_ALGAE), - SubsystemActions.empty()), - - GROUND_INTAKE_CORAL( - "GROUND_INTAKE_CORAL", - new SubsystemPoses( - ReefState.STOW, ManipulatorArmState.CORAL_INTAKE_FLOOR, IntakePivotState.INTAKE_CORAL), - new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.STOP)), - - GROUND_INTAKE( - "GROUND_INTAKE", - new SubsystemPoses( - ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), - new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.CORAL_INTAKE)), - - L1( - "L1", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), - new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.STOP)), - L1_SCORE( - "L1_SCORE", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), - new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.SCORE_CORAL)), - - L2( - "L2", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), - SubsystemActions.empty()), - L2_SCORE( - "L2_SCORE", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.FLIPPED_SCORE, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), - - L3( - "L3", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), - SubsystemActions.empty()), - L3_SCORE( - "L3_SCORE", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), - - L4( - "L4", - new SubsystemPoses(ReefState.L4, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), - SubsystemActions.empty()), - L4_SCORE( - "L4_SCORE", - new SubsystemPoses(ReefState.L4, ManipulatorArmState.SCORE_L4, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.L4_SCORE, IntakeRollerState.STOP)), - - HANDOFF( - "HANDOFF", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.CENTERING)), - - HANDOFF_SPIN( - "HANDOFF", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.OUTTAKE)), - - L2_ALGAE( - "L2_ALGAE", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - SubsystemActions.empty()), - L2_ALGAE_DROP( - "L2_ALGAE_DROP", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), - L2_ALGAE_INTAKE( - "L2_ALGAE_INTAKE", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), - - L3_ALGAE( - "L3_ALGAE", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - SubsystemActions.empty()), - L3_ALGAE_DROP( - "L3_ALGAE_DROP", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), - L3_ALGAE_INTAKE( - "L3_ALGAE_INTAKE", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), - - PROCESSOR( - "PROCESSOR", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), - SubsystemActions.empty()), - POST_PROCESSOR( - "POST_PROCESSOR", - new SubsystemPoses( - ReefState.POST_PROCESSOR, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), - SubsystemActions.empty()), - PROCESSOR_SCORE( - "PROCESSOR_SCORE", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), - - BARGE( - "BARGE", - new SubsystemPoses( - ReefState.HIGH_STOW, ManipulatorArmState.PRE_SCORE, IntakePivotState.HANDOFF), - SubsystemActions.empty()), - BARGE_SCORE( - "BARGE_SCORE", - new SubsystemPoses( - ReefState.ALGAE_SCORE, ManipulatorArmState.ALGAE_SCORE, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP), - Rotation2d.fromDegrees(15)), - FLIP_DOWN( - "FLIP_DOWN", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty()), - FLIP_UP( - "FLIP_UP", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty()), - INVERSE_FLIP_UP( - "INVERSE_FLIP_UP", - new SubsystemPoses( - ReefState.HANDOFF, ManipulatorArmState.INVERSE_FLIP_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty()); - - @Getter private final V3_EpsilonSuperstructurePose pose; - @Getter private final V3_EpsilonSuperstructureAction action; - - /** - * Constructor for V3_SuperstructureStates. - * - * @param name The name of the state. - * @param pose The subsystem poses for this state. - * @param action The subsystem actions for this state. - */ - V3_EpsilonSuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { - this.pose = new V3_EpsilonSuperstructurePose(name, pose); - this.action = new V3_EpsilonSuperstructureAction(name, action); - } - - V3_EpsilonSuperstructureStates( - String name, SubsystemPoses pose, SubsystemActions action, Double elevatorTolerance) { - this.pose = new V3_EpsilonSuperstructurePose(name, pose, elevatorTolerance); - this.action = new V3_EpsilonSuperstructureAction(name, action); - } - - V3_EpsilonSuperstructureStates( - String name, SubsystemPoses pose, SubsystemActions action, Rotation2d armTolerance) { - this.pose = new V3_EpsilonSuperstructurePose(name, pose, armTolerance); - this.action = new V3_EpsilonSuperstructureAction(name, action); - } + START("START", new SubsystemPoses(), SubsystemActions.empty()), + STOW_DOWN( + "STOW_DOWN", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), + SubsystemActions.empty()), + STOW_UP( + "STOW_UP", + new SubsystemPoses( + ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), + SubsystemActions.empty()), + OVERRIDE("OVERRIDE", new SubsystemPoses(), SubsystemActions.empty()), + GROUND_ACQUISITION( + "GROUND_ACQUISITION", + new SubsystemPoses( + ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), + SubsystemActions.empty()), + GROUND_INTAKE_ALGAE( + "GROUND_INTAKE_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_FLOOR_INTAKE, + ManipulatorArmState.ALGAE_INTAKE_FLOOR, + IntakePivotState.INTAKE_ALGAE), + new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), + GROUND_AQUISITION_ALGAE( + "GROUND_AQUISITION_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_FLOOR_INTAKE, + ManipulatorArmState.ALGAE_INTAKE_FLOOR, + IntakePivotState.INTAKE_ALGAE), + SubsystemActions.empty()), + + GROUND_INTAKE_CORAL( + "GROUND_INTAKE_CORAL", + new SubsystemPoses( + ReefState.STOW, ManipulatorArmState.CORAL_INTAKE_FLOOR, IntakePivotState.INTAKE_CORAL), + new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.STOP)), + + GROUND_INTAKE( + "GROUND_INTAKE", + new SubsystemPoses( + ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), + new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.CORAL_INTAKE)), + + L1( + "L1", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.STOP)), + L1_SCORE( + "L1_SCORE", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.SCORE_CORAL)), + + L2( + "L2", + new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + L2_SCORE( + "L2_SCORE", + new SubsystemPoses(ReefState.L2, ManipulatorArmState.FLIPPED_SCORE, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), + + L3( + "L3", + new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + L3_SCORE( + "L3_SCORE", + new SubsystemPoses(ReefState.L3, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), + + L4( + "L4", + new SubsystemPoses(ReefState.L4, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + L4_SCORE( + "L4_SCORE", + new SubsystemPoses(ReefState.L4, ManipulatorArmState.SCORE_L4, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.L4_SCORE, IntakeRollerState.STOP)), + + HANDOFF( + "HANDOFF", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.CENTERING)), + + HANDOFF_SPIN( + "HANDOFF", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.OUTTAKE)), + + L2_ALGAE( + "L2_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + SubsystemActions.empty()), + L2_ALGAE_DROP( + "L2_ALGAE_DROP", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + L2_ALGAE_INTAKE( + "L2_ALGAE_INTAKE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), + + L3_ALGAE( + "L3_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + SubsystemActions.empty()), + L3_ALGAE_DROP( + "L3_ALGAE_DROP", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + L3_ALGAE_INTAKE( + "L3_ALGAE_INTAKE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), + + PROCESSOR( + "PROCESSOR", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + SubsystemActions.empty()), + POST_PROCESSOR( + "POST_PROCESSOR", + new SubsystemPoses( + ReefState.POST_PROCESSOR, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + SubsystemActions.empty()), + PROCESSOR_SCORE( + "PROCESSOR_SCORE", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + + BARGE( + "BARGE", + new SubsystemPoses( + ReefState.ALGAE_SCORE, ManipulatorArmState.PRE_SCORE, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + BARGE_SCORE( + "BARGE_SCORE", + new SubsystemPoses( + ReefState.ALGAE_SCORE, ManipulatorArmState.ALGAE_SCORE, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP), + Rotation2d.fromDegrees(15)), + FLIP_DOWN( + "FLIP_DOWN", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), + SubsystemActions.empty()), + FLIP_UP( + "FLIP_UP", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), + SubsystemActions.empty()), + INVERSE_FLIP_UP( + "INVERSE_FLIP_UP", + new SubsystemPoses( + ReefState.HANDOFF, ManipulatorArmState.INVERSE_FLIP_ANGLE, IntakePivotState.STOW), + SubsystemActions.empty()); + + @Getter + private final V3_EpsilonSuperstructurePose pose; + @Getter + private final V3_EpsilonSuperstructureAction action; + + /** + * Constructor for V3_SuperstructureStates. + * + * @param name The name of the state. + * @param pose The subsystem poses for this state. + * @param action The subsystem actions for this state. + */ + V3_EpsilonSuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { + this.pose = new V3_EpsilonSuperstructurePose(name, pose); + this.action = new V3_EpsilonSuperstructureAction(name, action); + } + + V3_EpsilonSuperstructureStates( + String name, SubsystemPoses pose, SubsystemActions action, Double elevatorTolerance) { + this.pose = new V3_EpsilonSuperstructurePose(name, pose, elevatorTolerance); + this.action = new V3_EpsilonSuperstructureAction(name, action); + } + + V3_EpsilonSuperstructureStates( + String name, SubsystemPoses pose, SubsystemActions action, Rotation2d armTolerance) { + this.pose = new V3_EpsilonSuperstructurePose(name, pose, armTolerance); + this.action = new V3_EpsilonSuperstructureAction(name, action); + } } From 74469a542e41164113534ec37f77c24a7af2b99f Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 1 Nov 2025 13:07:02 -0400 Subject: [PATCH 163/180] Update at 'Sat Nov 01 13:07:02 EDT 2025' --- .../V3_EpsilonSuperstructureStates.java | 374 +++++++++--------- 1 file changed, 186 insertions(+), 188 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java index fe64c6b3..db2b6d02 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java @@ -11,192 +11,190 @@ import lombok.Getter; public enum V3_EpsilonSuperstructureStates { - START("START", new SubsystemPoses(), SubsystemActions.empty()), - STOW_DOWN( - "STOW_DOWN", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), - SubsystemActions.empty()), - STOW_UP( - "STOW_UP", - new SubsystemPoses( - ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), - SubsystemActions.empty()), - OVERRIDE("OVERRIDE", new SubsystemPoses(), SubsystemActions.empty()), - GROUND_ACQUISITION( - "GROUND_ACQUISITION", - new SubsystemPoses( - ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), - SubsystemActions.empty()), - GROUND_INTAKE_ALGAE( - "GROUND_INTAKE_ALGAE", - new SubsystemPoses( - ReefState.ALGAE_FLOOR_INTAKE, - ManipulatorArmState.ALGAE_INTAKE_FLOOR, - IntakePivotState.INTAKE_ALGAE), - new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), - GROUND_AQUISITION_ALGAE( - "GROUND_AQUISITION_ALGAE", - new SubsystemPoses( - ReefState.ALGAE_FLOOR_INTAKE, - ManipulatorArmState.ALGAE_INTAKE_FLOOR, - IntakePivotState.INTAKE_ALGAE), - SubsystemActions.empty()), - - GROUND_INTAKE_CORAL( - "GROUND_INTAKE_CORAL", - new SubsystemPoses( - ReefState.STOW, ManipulatorArmState.CORAL_INTAKE_FLOOR, IntakePivotState.INTAKE_CORAL), - new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.STOP)), - - GROUND_INTAKE( - "GROUND_INTAKE", - new SubsystemPoses( - ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), - new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.CORAL_INTAKE)), - - L1( - "L1", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), - new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.STOP)), - L1_SCORE( - "L1_SCORE", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), - new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.SCORE_CORAL)), - - L2( - "L2", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), - SubsystemActions.empty()), - L2_SCORE( - "L2_SCORE", - new SubsystemPoses(ReefState.L2, ManipulatorArmState.FLIPPED_SCORE, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), - - L3( - "L3", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), - SubsystemActions.empty()), - L3_SCORE( - "L3_SCORE", - new SubsystemPoses(ReefState.L3, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), - - L4( - "L4", - new SubsystemPoses(ReefState.L4, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), - SubsystemActions.empty()), - L4_SCORE( - "L4_SCORE", - new SubsystemPoses(ReefState.L4, ManipulatorArmState.SCORE_L4, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.L4_SCORE, IntakeRollerState.STOP)), - - HANDOFF( - "HANDOFF", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.CENTERING)), - - HANDOFF_SPIN( - "HANDOFF", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.OUTTAKE)), - - L2_ALGAE( - "L2_ALGAE", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - SubsystemActions.empty()), - L2_ALGAE_DROP( - "L2_ALGAE_DROP", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), - L2_ALGAE_INTAKE( - "L2_ALGAE_INTAKE", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), - - L3_ALGAE( - "L3_ALGAE", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - SubsystemActions.empty()), - L3_ALGAE_DROP( - "L3_ALGAE_DROP", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), - L3_ALGAE_INTAKE( - "L3_ALGAE_INTAKE", - new SubsystemPoses( - ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), - - PROCESSOR( - "PROCESSOR", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), - SubsystemActions.empty()), - POST_PROCESSOR( - "POST_PROCESSOR", - new SubsystemPoses( - ReefState.POST_PROCESSOR, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), - SubsystemActions.empty()), - PROCESSOR_SCORE( - "PROCESSOR_SCORE", - new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), - - BARGE( - "BARGE", - new SubsystemPoses( - ReefState.ALGAE_SCORE, ManipulatorArmState.PRE_SCORE, IntakePivotState.HANDOFF), - SubsystemActions.empty()), - BARGE_SCORE( - "BARGE_SCORE", - new SubsystemPoses( - ReefState.ALGAE_SCORE, ManipulatorArmState.ALGAE_SCORE, IntakePivotState.HANDOFF), - new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP), - Rotation2d.fromDegrees(15)), - FLIP_DOWN( - "FLIP_DOWN", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty()), - FLIP_UP( - "FLIP_UP", - new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty()), - INVERSE_FLIP_UP( - "INVERSE_FLIP_UP", - new SubsystemPoses( - ReefState.HANDOFF, ManipulatorArmState.INVERSE_FLIP_ANGLE, IntakePivotState.STOW), - SubsystemActions.empty()); - - @Getter - private final V3_EpsilonSuperstructurePose pose; - @Getter - private final V3_EpsilonSuperstructureAction action; - - /** - * Constructor for V3_SuperstructureStates. - * - * @param name The name of the state. - * @param pose The subsystem poses for this state. - * @param action The subsystem actions for this state. - */ - V3_EpsilonSuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { - this.pose = new V3_EpsilonSuperstructurePose(name, pose); - this.action = new V3_EpsilonSuperstructureAction(name, action); - } - - V3_EpsilonSuperstructureStates( - String name, SubsystemPoses pose, SubsystemActions action, Double elevatorTolerance) { - this.pose = new V3_EpsilonSuperstructurePose(name, pose, elevatorTolerance); - this.action = new V3_EpsilonSuperstructureAction(name, action); - } - - V3_EpsilonSuperstructureStates( - String name, SubsystemPoses pose, SubsystemActions action, Rotation2d armTolerance) { - this.pose = new V3_EpsilonSuperstructurePose(name, pose, armTolerance); - this.action = new V3_EpsilonSuperstructureAction(name, action); - } + START("START", new SubsystemPoses(), SubsystemActions.empty()), + STOW_DOWN( + "STOW_DOWN", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), + SubsystemActions.empty()), + STOW_UP( + "STOW_UP", + new SubsystemPoses( + ReefState.HIGH_STOW, ManipulatorArmState.VERTICAL_UP, IntakePivotState.STOW), + SubsystemActions.empty()), + OVERRIDE("OVERRIDE", new SubsystemPoses(), SubsystemActions.empty()), + GROUND_ACQUISITION( + "GROUND_ACQUISITION", + new SubsystemPoses( + ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), + SubsystemActions.empty()), + GROUND_INTAKE_ALGAE( + "GROUND_INTAKE_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_FLOOR_INTAKE, + ManipulatorArmState.ALGAE_INTAKE_FLOOR, + IntakePivotState.INTAKE_ALGAE), + new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), + GROUND_AQUISITION_ALGAE( + "GROUND_AQUISITION_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_FLOOR_INTAKE, + ManipulatorArmState.ALGAE_INTAKE_FLOOR, + IntakePivotState.INTAKE_ALGAE), + SubsystemActions.empty()), + + GROUND_INTAKE_CORAL( + "GROUND_INTAKE_CORAL", + new SubsystemPoses( + ReefState.STOW, ManipulatorArmState.CORAL_INTAKE_FLOOR, IntakePivotState.INTAKE_CORAL), + new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.STOP)), + + GROUND_INTAKE( + "GROUND_INTAKE", + new SubsystemPoses( + ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.INTAKE_CORAL), + new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.CORAL_INTAKE)), + + L1( + "L1", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.STOP)), + L1_SCORE( + "L1_SCORE", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.L1), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.SCORE_CORAL)), + + L2( + "L2", + new SubsystemPoses(ReefState.L2, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + L2_SCORE( + "L2_SCORE", + new SubsystemPoses(ReefState.L2, ManipulatorArmState.FLIPPED_SCORE, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), + + L3( + "L3", + new SubsystemPoses(ReefState.L3, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + L3_SCORE( + "L3_SCORE", + new SubsystemPoses(ReefState.L3, ManipulatorArmState.SCORE, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.SCORE_CORAL, IntakeRollerState.STOP)), + + L4( + "L4", + new SubsystemPoses(ReefState.L4, ManipulatorArmState.TRANSITION, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + L4_SCORE( + "L4_SCORE", + new SubsystemPoses(ReefState.L4, ManipulatorArmState.SCORE_L4, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.L4_SCORE, IntakeRollerState.STOP)), + + HANDOFF( + "HANDOFF", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.STOP, IntakeRollerState.CENTERING)), + + HANDOFF_SPIN( + "HANDOFF", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.HANDOFF, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.CORAL_INTAKE, IntakeRollerState.OUTTAKE)), + + L2_ALGAE( + "L2_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + SubsystemActions.empty()), + L2_ALGAE_DROP( + "L2_ALGAE_DROP", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + L2_ALGAE_INTAKE( + "L2_ALGAE_INTAKE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_BOTTOM, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), + + L3_ALGAE( + "L3_ALGAE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + SubsystemActions.empty()), + L3_ALGAE_DROP( + "L3_ALGAE_DROP", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + L3_ALGAE_INTAKE( + "L3_ALGAE_INTAKE", + new SubsystemPoses( + ReefState.ALGAE_INTAKE_TOP, ManipulatorArmState.REEF_INTAKE, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.ALGAE_INTAKE, IntakeRollerState.STOP)), + + PROCESSOR( + "PROCESSOR", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + SubsystemActions.empty()), + POST_PROCESSOR( + "POST_PROCESSOR", + new SubsystemPoses( + ReefState.POST_PROCESSOR, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + SubsystemActions.empty()), + PROCESSOR_SCORE( + "PROCESSOR_SCORE", + new SubsystemPoses(ReefState.STOW, ManipulatorArmState.PROCESSOR, IntakePivotState.STOW), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP)), + + BARGE( + "BARGE", + new SubsystemPoses( + ReefState.ALGAE_SCORE, ManipulatorArmState.PRE_SCORE, IntakePivotState.HANDOFF), + SubsystemActions.empty()), + BARGE_SCORE( + "BARGE_SCORE", + new SubsystemPoses( + ReefState.ALGAE_SCORE, ManipulatorArmState.ALGAE_SCORE, IntakePivotState.HANDOFF), + new SubsystemActions(ManipulatorRollerState.SCORE_ALGAE, IntakeRollerState.STOP), + Rotation2d.fromDegrees(15)), + FLIP_DOWN( + "FLIP_DOWN", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), + SubsystemActions.empty()), + FLIP_UP( + "FLIP_UP", + new SubsystemPoses(ReefState.HANDOFF, ManipulatorArmState.FLIP_ANGLE, IntakePivotState.STOW), + SubsystemActions.empty()), + INVERSE_FLIP_UP( + "INVERSE_FLIP_UP", + new SubsystemPoses( + ReefState.HANDOFF, ManipulatorArmState.INVERSE_FLIP_ANGLE, IntakePivotState.STOW), + SubsystemActions.empty()); + + @Getter private final V3_EpsilonSuperstructurePose pose; + @Getter private final V3_EpsilonSuperstructureAction action; + + /** + * Constructor for V3_SuperstructureStates. + * + * @param name The name of the state. + * @param pose The subsystem poses for this state. + * @param action The subsystem actions for this state. + */ + V3_EpsilonSuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { + this.pose = new V3_EpsilonSuperstructurePose(name, pose); + this.action = new V3_EpsilonSuperstructureAction(name, action); + } + + V3_EpsilonSuperstructureStates( + String name, SubsystemPoses pose, SubsystemActions action, Double elevatorTolerance) { + this.pose = new V3_EpsilonSuperstructurePose(name, pose, elevatorTolerance); + this.action = new V3_EpsilonSuperstructureAction(name, action); + } + + V3_EpsilonSuperstructureStates( + String name, SubsystemPoses pose, SubsystemActions action, Rotation2d armTolerance) { + this.pose = new V3_EpsilonSuperstructurePose(name, pose, armTolerance); + this.action = new V3_EpsilonSuperstructureAction(name, action); + } } From a80073fe9b6f25a9733c7384ef9fe60838702c09 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 1 Nov 2025 13:10:33 -0400 Subject: [PATCH 164/180] Update at 'Sat Nov 01 13:10:33 EDT 2025' --- .../superstructure/V3_EpsilonSuperstructureEdges.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index c3c7a988..65315652 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -129,7 +129,7 @@ private static Command getEdgeCommand( if (to.equals(V3_EpsilonSuperstructureStates.BARGE_SCORE)) { return Commands.sequence( pose.asConfigurationSpaceCommand(elevator, intake, manipulator), - Commands.waitUntil(() -> manipulator.armInTolerance(Rotation2d.fromDegrees(15)))); + Commands.waitUntil(() -> manipulator.armInTolerance(Rotation2d.fromDegrees(10)))); } return Commands.sequence( From 3e12fbd653078dbb482c96ea51e2bb3491bf599b Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 1 Nov 2025 13:10:56 -0400 Subject: [PATCH 165/180] Update at 'Sat Nov 01 13:10:56 EDT 2025' --- .../V3_EpsilonSuperstructureEdges.java | 263 +++++++++--------- 1 file changed, 130 insertions(+), 133 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index 65315652..1dc64a6e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -7,6 +7,9 @@ import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import java.io.FileReader; +import java.io.Reader; +import java.util.ArrayList; import lombok.Builder; import lombok.Getter; import lombok.Setter; @@ -14,147 +17,141 @@ import org.jgrapht.graph.DefaultEdge; import org.jgrapht.nio.dot.DOTImporter; -import java.io.FileReader; -import java.io.Reader; -import java.util.ArrayList; - public class V3_EpsilonSuperstructureEdges { - public static final ArrayList UNCONSTRAINED = new ArrayList<>(); - public static final ArrayList NO_ALGAE_EDGES = new ArrayList<>(); - - public record Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { - public Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { - this.from = from; - this.to = to; - } - - @Override - public String toString() { - return from + " -> " + to; - } - } + public static final ArrayList UNCONSTRAINED = new ArrayList<>(); + public static final ArrayList NO_ALGAE_EDGES = new ArrayList<>(); - public enum GamePieceEdge { - UNCONSTRAINED, - NO_ALGAE + public record Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { + public Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { + this.from = from; + this.to = to; } - public static void loadEdgesFromDot( - String path, - Graph graph, - ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - - DOTImporter importer = new DOTImporter<>(); - - // --- Fix 1: safer vertex factory --- - importer.setVertexFactory( - id -> { - try { - return V3_EpsilonSuperstructureStates.valueOf(id); - } catch (IllegalArgumentException e) { - System.err.println("[DOT Import] Unknown vertex in DOT: " + id); - return null; - } - }); - - // --- Fix 2: ensure edge objects are valid --- - importer.setEdgeWithAttributesFactory( - attributes -> { - GamePieceEdge type = GamePieceEdge.UNCONSTRAINED; - - if (attributes.containsKey("type")) { - try { - type = GamePieceEdge.valueOf(attributes.get("type").getValue().toUpperCase()); - } catch (Exception e) { - System.err.println("[DOT Import] Invalid edge type, defaulting to UNCONSTRAINED"); - } - } - - // Create a proper EdgeCommand with no command yet - return EdgeCommand.builder().gamePieceEdge(type).command(null).build(); - }); - - // --- Fix 3: actually import the file and verify success --- - try (Reader r = new FileReader(path)) { - importer.importGraph(graph, r); - } catch (Exception ex) { - throw new RuntimeException("Failed to parse DOT file: " + path, ex); - } - - // --- Fix 4: assign the edge commands after load --- - for (EdgeCommand e : graph.edgeSet()) { - V3_EpsilonSuperstructureStates from = graph.getEdgeSource(e); - V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(e); - e.setCommand(getEdgeCommand(from, to, elevator, intake, manipulator)); - } - - System.out.printf( - "[DOT Import] Loaded %d vertices, %d edges%n", - graph.vertexSet().size(), graph.edgeSet().size()); + @Override + public String toString() { + return from + " -> " + to; } - - @Builder(toBuilder = true) - @Getter - public static class EdgeCommand extends DefaultEdge { - @Setter - private Command command; - @Builder.Default - private GamePieceEdge gamePieceEdge = GamePieceEdge.UNCONSTRAINED; + } + + public enum GamePieceEdge { + UNCONSTRAINED, + NO_ALGAE + } + + public static void loadEdgesFromDot( + String path, + Graph graph, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + + DOTImporter importer = new DOTImporter<>(); + + // --- Fix 1: safer vertex factory --- + importer.setVertexFactory( + id -> { + try { + return V3_EpsilonSuperstructureStates.valueOf(id); + } catch (IllegalArgumentException e) { + System.err.println("[DOT Import] Unknown vertex in DOT: " + id); + return null; + } + }); + + // --- Fix 2: ensure edge objects are valid --- + importer.setEdgeWithAttributesFactory( + attributes -> { + GamePieceEdge type = GamePieceEdge.UNCONSTRAINED; + + if (attributes.containsKey("type")) { + try { + type = GamePieceEdge.valueOf(attributes.get("type").getValue().toUpperCase()); + } catch (Exception e) { + System.err.println("[DOT Import] Invalid edge type, defaulting to UNCONSTRAINED"); + } + } + + // Create a proper EdgeCommand with no command yet + return EdgeCommand.builder().gamePieceEdge(type).command(null).build(); + }); + + // --- Fix 3: actually import the file and verify success --- + try (Reader r = new FileReader(path)) { + importer.importGraph(graph, r); + } catch (Exception ex) { + throw new RuntimeException("Failed to parse DOT file: " + path, ex); } - /** - * Gets the command to execute for a given edge in the superstructure state graph. This command - * typically involves coordinating the elevator, funnel, intake, and manipulator subsystems to - * move from one state to another. - * - * @param from The starting state of the superstructure. - * @param to The target state of the superstructure. - * @param elevator The elevator subsystem. - * @param intake The intake subsystem. - * @param manipulator The manipulator subsystem. - * @return A {@link Command} that, when executed, transitions the superstructure from the 'from' - * state to the 'to' state. - */ - private static Command getEdgeCommand( - V3_EpsilonSuperstructureStates from, - V3_EpsilonSuperstructureStates to, - ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - - V3_EpsilonSuperstructurePose pose = to.getPose(); - - if (to.equals(V3_EpsilonSuperstructureStates.BARGE_SCORE)) { - return Commands.sequence( - pose.asConfigurationSpaceCommand(elevator, intake, manipulator), - Commands.waitUntil(() -> manipulator.armInTolerance(Rotation2d.fromDegrees(10)))); - } - - return Commands.sequence( - pose.asConfigurationSpaceCommand(elevator, intake, manipulator), - pose.wait(elevator, intake, manipulator)); + // --- Fix 4: assign the edge commands after load --- + for (EdgeCommand e : graph.edgeSet()) { + V3_EpsilonSuperstructureStates from = graph.getEdgeSource(e); + V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(e); + e.setCommand(getEdgeCommand(from, to, elevator, intake, manipulator)); } - /** - * Adds all predefined edges to the superstructure state graph, categorized by algae condition. - * - * @param graph The graph to which edges are added. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. - */ - public static void addEdges( - Graph graph, - ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - loadEdgesFromDot( - Filesystem.getDeployDirectory().toPath().resolve("Superstructure.dot").toString(), - graph, - elevator, - intake, - manipulator); + System.out.printf( + "[DOT Import] Loaded %d vertices, %d edges%n", + graph.vertexSet().size(), graph.edgeSet().size()); + } + + @Builder(toBuilder = true) + @Getter + public static class EdgeCommand extends DefaultEdge { + @Setter private Command command; + @Builder.Default private GamePieceEdge gamePieceEdge = GamePieceEdge.UNCONSTRAINED; + } + + /** + * Gets the command to execute for a given edge in the superstructure state graph. This command + * typically involves coordinating the elevator, funnel, intake, and manipulator subsystems to + * move from one state to another. + * + * @param from The starting state of the superstructure. + * @param to The target state of the superstructure. + * @param elevator The elevator subsystem. + * @param intake The intake subsystem. + * @param manipulator The manipulator subsystem. + * @return A {@link Command} that, when executed, transitions the superstructure from the 'from' + * state to the 'to' state. + */ + private static Command getEdgeCommand( + V3_EpsilonSuperstructureStates from, + V3_EpsilonSuperstructureStates to, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + + V3_EpsilonSuperstructurePose pose = to.getPose(); + + if (to.equals(V3_EpsilonSuperstructureStates.BARGE_SCORE)) { + return Commands.sequence( + pose.asConfigurationSpaceCommand(elevator, intake, manipulator), + Commands.waitUntil(() -> manipulator.armInTolerance(Rotation2d.fromDegrees(10)))); } + + return Commands.sequence( + pose.asConfigurationSpaceCommand(elevator, intake, manipulator), + pose.wait(elevator, intake, manipulator)); + } + + /** + * Adds all predefined edges to the superstructure state graph, categorized by algae condition. + * + * @param graph The graph to which edges are added. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param intake The intake subsystem. + */ + public static void addEdges( + Graph graph, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + loadEdgesFromDot( + Filesystem.getDeployDirectory().toPath().resolve("Superstructure.dot").toString(), + graph, + elevator, + intake, + manipulator); + } } From 46409ad477210ea818b27e1c3542492ebb371e35 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 1 Nov 2025 13:13:40 -0400 Subject: [PATCH 166/180] Update at 'Sat Nov 01 13:13:40 EDT 2025' --- .../V3_EpsilonSuperstructureEdges.java | 263 +++++++++--------- 1 file changed, 133 insertions(+), 130 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index 1dc64a6e..b8344e08 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -7,9 +7,6 @@ import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; -import java.io.FileReader; -import java.io.Reader; -import java.util.ArrayList; import lombok.Builder; import lombok.Getter; import lombok.Setter; @@ -17,141 +14,147 @@ import org.jgrapht.graph.DefaultEdge; import org.jgrapht.nio.dot.DOTImporter; -public class V3_EpsilonSuperstructureEdges { - public static final ArrayList UNCONSTRAINED = new ArrayList<>(); - public static final ArrayList NO_ALGAE_EDGES = new ArrayList<>(); +import java.io.FileReader; +import java.io.Reader; +import java.util.ArrayList; - public record Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { - public Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { - this.from = from; - this.to = to; +public class V3_EpsilonSuperstructureEdges { + public static final ArrayList UNCONSTRAINED = new ArrayList<>(); + public static final ArrayList NO_ALGAE_EDGES = new ArrayList<>(); + + public record Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { + public Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { + this.from = from; + this.to = to; + } + + @Override + public String toString() { + return from + " -> " + to; + } } - @Override - public String toString() { - return from + " -> " + to; + public enum GamePieceEdge { + UNCONSTRAINED, + NO_ALGAE } - } - - public enum GamePieceEdge { - UNCONSTRAINED, - NO_ALGAE - } - - public static void loadEdgesFromDot( - String path, - Graph graph, - ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - - DOTImporter importer = new DOTImporter<>(); - - // --- Fix 1: safer vertex factory --- - importer.setVertexFactory( - id -> { - try { - return V3_EpsilonSuperstructureStates.valueOf(id); - } catch (IllegalArgumentException e) { - System.err.println("[DOT Import] Unknown vertex in DOT: " + id); - return null; - } - }); - - // --- Fix 2: ensure edge objects are valid --- - importer.setEdgeWithAttributesFactory( - attributes -> { - GamePieceEdge type = GamePieceEdge.UNCONSTRAINED; - - if (attributes.containsKey("type")) { - try { - type = GamePieceEdge.valueOf(attributes.get("type").getValue().toUpperCase()); - } catch (Exception e) { - System.err.println("[DOT Import] Invalid edge type, defaulting to UNCONSTRAINED"); - } - } - - // Create a proper EdgeCommand with no command yet - return EdgeCommand.builder().gamePieceEdge(type).command(null).build(); - }); - - // --- Fix 3: actually import the file and verify success --- - try (Reader r = new FileReader(path)) { - importer.importGraph(graph, r); - } catch (Exception ex) { - throw new RuntimeException("Failed to parse DOT file: " + path, ex); + + public static void loadEdgesFromDot( + String path, + Graph graph, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + + DOTImporter importer = new DOTImporter<>(); + + // --- Fix 1: safer vertex factory --- + importer.setVertexFactory( + id -> { + try { + return V3_EpsilonSuperstructureStates.valueOf(id); + } catch (IllegalArgumentException e) { + System.err.println("[DOT Import] Unknown vertex in DOT: " + id); + return null; + } + }); + + // --- Fix 2: ensure edge objects are valid --- + importer.setEdgeWithAttributesFactory( + attributes -> { + GamePieceEdge type = GamePieceEdge.UNCONSTRAINED; + + if (attributes.containsKey("type")) { + try { + type = GamePieceEdge.valueOf(attributes.get("type").getValue().toUpperCase()); + } catch (Exception e) { + System.err.println("[DOT Import] Invalid edge type, defaulting to UNCONSTRAINED"); + } + } + + // Create a proper EdgeCommand with no command yet + return EdgeCommand.builder().gamePieceEdge(type).command(null).build(); + }); + + // --- Fix 3: actually import the file and verify success --- + try (Reader r = new FileReader(path)) { + importer.importGraph(graph, r); + } catch (Exception ex) { + throw new RuntimeException("Failed to parse DOT file: " + path, ex); + } + + // --- Fix 4: assign the edge commands after load --- + for (EdgeCommand e : graph.edgeSet()) { + V3_EpsilonSuperstructureStates from = graph.getEdgeSource(e); + V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(e); + e.setCommand(getEdgeCommand(from, to, elevator, intake, manipulator)); + } + + System.out.printf( + "[DOT Import] Loaded %d vertices, %d edges%n", + graph.vertexSet().size(), graph.edgeSet().size()); } - // --- Fix 4: assign the edge commands after load --- - for (EdgeCommand e : graph.edgeSet()) { - V3_EpsilonSuperstructureStates from = graph.getEdgeSource(e); - V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(e); - e.setCommand(getEdgeCommand(from, to, elevator, intake, manipulator)); + @Builder(toBuilder = true) + @Getter + public static class EdgeCommand extends DefaultEdge { + @Setter + private Command command; + @Builder.Default + private GamePieceEdge gamePieceEdge = GamePieceEdge.UNCONSTRAINED; } - System.out.printf( - "[DOT Import] Loaded %d vertices, %d edges%n", - graph.vertexSet().size(), graph.edgeSet().size()); - } - - @Builder(toBuilder = true) - @Getter - public static class EdgeCommand extends DefaultEdge { - @Setter private Command command; - @Builder.Default private GamePieceEdge gamePieceEdge = GamePieceEdge.UNCONSTRAINED; - } - - /** - * Gets the command to execute for a given edge in the superstructure state graph. This command - * typically involves coordinating the elevator, funnel, intake, and manipulator subsystems to - * move from one state to another. - * - * @param from The starting state of the superstructure. - * @param to The target state of the superstructure. - * @param elevator The elevator subsystem. - * @param intake The intake subsystem. - * @param manipulator The manipulator subsystem. - * @return A {@link Command} that, when executed, transitions the superstructure from the 'from' - * state to the 'to' state. - */ - private static Command getEdgeCommand( - V3_EpsilonSuperstructureStates from, - V3_EpsilonSuperstructureStates to, - ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - - V3_EpsilonSuperstructurePose pose = to.getPose(); - - if (to.equals(V3_EpsilonSuperstructureStates.BARGE_SCORE)) { - return Commands.sequence( - pose.asConfigurationSpaceCommand(elevator, intake, manipulator), - Commands.waitUntil(() -> manipulator.armInTolerance(Rotation2d.fromDegrees(10)))); + /** + * Gets the command to execute for a given edge in the superstructure state graph. This command + * typically involves coordinating the elevator, funnel, intake, and manipulator subsystems to + * move from one state to another. + * + * @param from The starting state of the superstructure. + * @param to The target state of the superstructure. + * @param elevator The elevator subsystem. + * @param intake The intake subsystem. + * @param manipulator The manipulator subsystem. + * @return A {@link Command} that, when executed, transitions the superstructure from the 'from' + * state to the 'to' state. + */ + private static Command getEdgeCommand( + V3_EpsilonSuperstructureStates from, + V3_EpsilonSuperstructureStates to, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + + V3_EpsilonSuperstructurePose pose = to.getPose(); + + if (to.equals(V3_EpsilonSuperstructureStates.BARGE_SCORE)) { + return Commands.sequence( + pose.asConfigurationSpaceCommand(elevator, intake, manipulator), + Commands.waitUntil(() -> manipulator.armInTolerance(Rotation2d.fromDegrees(6)))); + } + + return Commands.sequence( + pose.asConfigurationSpaceCommand(elevator, intake, manipulator), + pose.wait(elevator, intake, manipulator)); } - return Commands.sequence( - pose.asConfigurationSpaceCommand(elevator, intake, manipulator), - pose.wait(elevator, intake, manipulator)); - } - - /** - * Adds all predefined edges to the superstructure state graph, categorized by algae condition. - * - * @param graph The graph to which edges are added. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. - */ - public static void addEdges( - Graph graph, - ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - loadEdgesFromDot( - Filesystem.getDeployDirectory().toPath().resolve("Superstructure.dot").toString(), - graph, - elevator, - intake, - manipulator); - } + /** + * Adds all predefined edges to the superstructure state graph, categorized by algae condition. + * + * @param graph The graph to which edges are added. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param intake The intake subsystem. + */ + public static void addEdges( + Graph graph, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + loadEdgesFromDot( + Filesystem.getDeployDirectory().toPath().resolve("Superstructure.dot").toString(), + graph, + elevator, + intake, + manipulator); + } } From b4f7ebcc6a90fabbe6024cc5a8c25d3f5e6a3e0b Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sat, 1 Nov 2025 13:13:49 -0400 Subject: [PATCH 167/180] Update at 'Sat Nov 01 13:13:49 EDT 2025' --- .../V3_EpsilonSuperstructureEdges.java | 263 +++++++++--------- 1 file changed, 130 insertions(+), 133 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index b8344e08..499b0e9e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -7,6 +7,9 @@ import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import java.io.FileReader; +import java.io.Reader; +import java.util.ArrayList; import lombok.Builder; import lombok.Getter; import lombok.Setter; @@ -14,147 +17,141 @@ import org.jgrapht.graph.DefaultEdge; import org.jgrapht.nio.dot.DOTImporter; -import java.io.FileReader; -import java.io.Reader; -import java.util.ArrayList; - public class V3_EpsilonSuperstructureEdges { - public static final ArrayList UNCONSTRAINED = new ArrayList<>(); - public static final ArrayList NO_ALGAE_EDGES = new ArrayList<>(); - - public record Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { - public Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { - this.from = from; - this.to = to; - } - - @Override - public String toString() { - return from + " -> " + to; - } - } + public static final ArrayList UNCONSTRAINED = new ArrayList<>(); + public static final ArrayList NO_ALGAE_EDGES = new ArrayList<>(); - public enum GamePieceEdge { - UNCONSTRAINED, - NO_ALGAE + public record Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { + public Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { + this.from = from; + this.to = to; } - public static void loadEdgesFromDot( - String path, - Graph graph, - ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - - DOTImporter importer = new DOTImporter<>(); - - // --- Fix 1: safer vertex factory --- - importer.setVertexFactory( - id -> { - try { - return V3_EpsilonSuperstructureStates.valueOf(id); - } catch (IllegalArgumentException e) { - System.err.println("[DOT Import] Unknown vertex in DOT: " + id); - return null; - } - }); - - // --- Fix 2: ensure edge objects are valid --- - importer.setEdgeWithAttributesFactory( - attributes -> { - GamePieceEdge type = GamePieceEdge.UNCONSTRAINED; - - if (attributes.containsKey("type")) { - try { - type = GamePieceEdge.valueOf(attributes.get("type").getValue().toUpperCase()); - } catch (Exception e) { - System.err.println("[DOT Import] Invalid edge type, defaulting to UNCONSTRAINED"); - } - } - - // Create a proper EdgeCommand with no command yet - return EdgeCommand.builder().gamePieceEdge(type).command(null).build(); - }); - - // --- Fix 3: actually import the file and verify success --- - try (Reader r = new FileReader(path)) { - importer.importGraph(graph, r); - } catch (Exception ex) { - throw new RuntimeException("Failed to parse DOT file: " + path, ex); - } - - // --- Fix 4: assign the edge commands after load --- - for (EdgeCommand e : graph.edgeSet()) { - V3_EpsilonSuperstructureStates from = graph.getEdgeSource(e); - V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(e); - e.setCommand(getEdgeCommand(from, to, elevator, intake, manipulator)); - } - - System.out.printf( - "[DOT Import] Loaded %d vertices, %d edges%n", - graph.vertexSet().size(), graph.edgeSet().size()); + @Override + public String toString() { + return from + " -> " + to; } - - @Builder(toBuilder = true) - @Getter - public static class EdgeCommand extends DefaultEdge { - @Setter - private Command command; - @Builder.Default - private GamePieceEdge gamePieceEdge = GamePieceEdge.UNCONSTRAINED; + } + + public enum GamePieceEdge { + UNCONSTRAINED, + NO_ALGAE + } + + public static void loadEdgesFromDot( + String path, + Graph graph, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + + DOTImporter importer = new DOTImporter<>(); + + // --- Fix 1: safer vertex factory --- + importer.setVertexFactory( + id -> { + try { + return V3_EpsilonSuperstructureStates.valueOf(id); + } catch (IllegalArgumentException e) { + System.err.println("[DOT Import] Unknown vertex in DOT: " + id); + return null; + } + }); + + // --- Fix 2: ensure edge objects are valid --- + importer.setEdgeWithAttributesFactory( + attributes -> { + GamePieceEdge type = GamePieceEdge.UNCONSTRAINED; + + if (attributes.containsKey("type")) { + try { + type = GamePieceEdge.valueOf(attributes.get("type").getValue().toUpperCase()); + } catch (Exception e) { + System.err.println("[DOT Import] Invalid edge type, defaulting to UNCONSTRAINED"); + } + } + + // Create a proper EdgeCommand with no command yet + return EdgeCommand.builder().gamePieceEdge(type).command(null).build(); + }); + + // --- Fix 3: actually import the file and verify success --- + try (Reader r = new FileReader(path)) { + importer.importGraph(graph, r); + } catch (Exception ex) { + throw new RuntimeException("Failed to parse DOT file: " + path, ex); } - /** - * Gets the command to execute for a given edge in the superstructure state graph. This command - * typically involves coordinating the elevator, funnel, intake, and manipulator subsystems to - * move from one state to another. - * - * @param from The starting state of the superstructure. - * @param to The target state of the superstructure. - * @param elevator The elevator subsystem. - * @param intake The intake subsystem. - * @param manipulator The manipulator subsystem. - * @return A {@link Command} that, when executed, transitions the superstructure from the 'from' - * state to the 'to' state. - */ - private static Command getEdgeCommand( - V3_EpsilonSuperstructureStates from, - V3_EpsilonSuperstructureStates to, - ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - - V3_EpsilonSuperstructurePose pose = to.getPose(); - - if (to.equals(V3_EpsilonSuperstructureStates.BARGE_SCORE)) { - return Commands.sequence( - pose.asConfigurationSpaceCommand(elevator, intake, manipulator), - Commands.waitUntil(() -> manipulator.armInTolerance(Rotation2d.fromDegrees(6)))); - } - - return Commands.sequence( - pose.asConfigurationSpaceCommand(elevator, intake, manipulator), - pose.wait(elevator, intake, manipulator)); + // --- Fix 4: assign the edge commands after load --- + for (EdgeCommand e : graph.edgeSet()) { + V3_EpsilonSuperstructureStates from = graph.getEdgeSource(e); + V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(e); + e.setCommand(getEdgeCommand(from, to, elevator, intake, manipulator)); } - /** - * Adds all predefined edges to the superstructure state graph, categorized by algae condition. - * - * @param graph The graph to which edges are added. - * @param elevator The elevator subsystem. - * @param manipulator The manipulator subsystem. - * @param intake The intake subsystem. - */ - public static void addEdges( - Graph graph, - ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { - loadEdgesFromDot( - Filesystem.getDeployDirectory().toPath().resolve("Superstructure.dot").toString(), - graph, - elevator, - intake, - manipulator); + System.out.printf( + "[DOT Import] Loaded %d vertices, %d edges%n", + graph.vertexSet().size(), graph.edgeSet().size()); + } + + @Builder(toBuilder = true) + @Getter + public static class EdgeCommand extends DefaultEdge { + @Setter private Command command; + @Builder.Default private GamePieceEdge gamePieceEdge = GamePieceEdge.UNCONSTRAINED; + } + + /** + * Gets the command to execute for a given edge in the superstructure state graph. This command + * typically involves coordinating the elevator, funnel, intake, and manipulator subsystems to + * move from one state to another. + * + * @param from The starting state of the superstructure. + * @param to The target state of the superstructure. + * @param elevator The elevator subsystem. + * @param intake The intake subsystem. + * @param manipulator The manipulator subsystem. + * @return A {@link Command} that, when executed, transitions the superstructure from the 'from' + * state to the 'to' state. + */ + private static Command getEdgeCommand( + V3_EpsilonSuperstructureStates from, + V3_EpsilonSuperstructureStates to, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + + V3_EpsilonSuperstructurePose pose = to.getPose(); + + if (to.equals(V3_EpsilonSuperstructureStates.BARGE_SCORE)) { + return Commands.sequence( + pose.asConfigurationSpaceCommand(elevator, intake, manipulator), + Commands.waitUntil(() -> manipulator.armInTolerance(Rotation2d.fromDegrees(6)))); } + + return Commands.sequence( + pose.asConfigurationSpaceCommand(elevator, intake, manipulator), + pose.wait(elevator, intake, manipulator)); + } + + /** + * Adds all predefined edges to the superstructure state graph, categorized by algae condition. + * + * @param graph The graph to which edges are added. + * @param elevator The elevator subsystem. + * @param manipulator The manipulator subsystem. + * @param intake The intake subsystem. + */ + public static void addEdges( + Graph graph, + ElevatorFSM elevator, + V3_EpsilonIntake intake, + V3_EpsilonManipulator manipulator) { + loadEdgesFromDot( + Filesystem.getDeployDirectory().toPath().resolve("Superstructure.dot").toString(), + graph, + elevator, + intake, + manipulator); + } } From 6a013a05ae9575f8d144bee268275d2e7ac4b4ca Mon Sep 17 00:00:00 2001 From: Elliot Scher <44726531+ElliotScher@users.noreply.github.com> Date: Mon, 3 Nov 2025 21:29:05 -0500 Subject: [PATCH 168/180] Event nhalt1 (#152) * Update at 'Sun Nov 02 11:38:54 EST 2025' * Update at 'Sun Nov 02 11:39:13 EST 2025' * Update at 'Sun Nov 02 11:44:41 EST 2025' * Update at 'Sun Nov 02 11:53:33 EST 2025' * Update at 'Sun Nov 02 15:24:48 EST 2025' --- build.gradle | 8 ++--- .../frc/robot/commands/CompositeCommands.java | 7 ++-- .../v3_Epsilon/V3_EpsilonRobotContainer.java | 7 +++- .../V3_EpsilonSuperstructure.java | 35 +++++++++++++++++-- .../manipulator/V3_EpsilonManipulator.java | 2 ++ 5 files changed, 46 insertions(+), 13 deletions(-) diff --git a/build.gradle b/build.gradle index e7d54a27..5fe35d63 100755 --- a/build.gradle +++ b/build.gradle @@ -37,10 +37,10 @@ deploy { // The options below may improve performance, but should only be enabled on the RIO 2 - // final MAX_JAVA_HEAP_SIZE_MB = 100; - // jvmArgs.add("-Xmx" + MAX_JAVA_HEAP_SIZE_MB + "M") - // jvmArgs.add("-Xms" + MAX_JAVA_HEAP_SIZE_MB + "M") - // jvmArgs.add("-XX:+AlwaysPreTouch") + final MAX_JAVA_HEAP_SIZE_MB = 100; + jvmArgs.add("-Xmx" + MAX_JAVA_HEAP_SIZE_MB + "M") + jvmArgs.add("-Xms" + MAX_JAVA_HEAP_SIZE_MB + "M") + jvmArgs.add("-XX:+AlwaysPreTouch") // Enable VisualVM connection // jvmArgs.add("-Dcom.sun.management.jmxremote=true") diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index bed60a98..9fc19067 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -663,11 +663,8 @@ public static final Command intakeCoralDriverSequence( V3_EpsilonManipulator manipulator) { return Commands.sequence( Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> intake.hasCoralLoose()), - superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.HANDOFF, () -> intake.hasCoralLocked()), - postIntakeCoralSequence(superstructure, intake, manipulator)); + superstructure.runGoalUntil(V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> false), + superstructure.runGoalUntil(V3_EpsilonSuperstructureStates.HANDOFF, () -> false)); } public static final Command postIntakeCoralSequence( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java index 86705e5b..b11411c1 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java @@ -224,7 +224,7 @@ private void configureButtonBindings() { driver.povUp().onTrue(superstructure.setPosition()); driver.povDown().onTrue(SharedCommands.resetHeading(drive)); - driver.povLeft().onTrue(DriveCommands.inchMovement(drive, -0.5, .07)); + // driver.povLeft().onTrue(DriveCommands.inchMovement(drive, -0.5, .07)); driver .leftStick() @@ -303,6 +303,11 @@ private void configureButtonBindings() { operator.start().whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)); operator.back().onTrue(V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure)); + + Trigger trigger = driver.povLeft(); + Trigger trigger2 = driver.povRight(); + + trigger.onTrue(superstructure.everythingsFucked(trigger2)); } private void configureAutos() { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java index 6ed0ff02..f06faee5 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java @@ -9,11 +9,14 @@ import frc.robot.RobotState.RobotMode; import frc.robot.RobotState.ScoreSide; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; +import frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.EdgeCommand; import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.GamePieceEdge; import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; +import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakePivotState; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; +import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; import frc.robot.util.NTPrefixes; import java.util.*; import java.util.function.BooleanSupplier; @@ -100,12 +103,16 @@ public V3_EpsilonSuperstructure( @Override public void periodic() { if (currentState != null && !currentState.equals(V3_EpsilonSuperstructureStates.OVERRIDE)) { + if (nextState != null) { // If we are in a transition, run the actions for the destination state - nextState.getAction().get(intake, manipulator); + if (atIntermediateGoal()) { + nextState.getAction().get(intake, manipulator); + } } else { - // Otherwise, just run the actions for the state we are in - currentState.getAction().get(intake, manipulator); + if (atIntermediateGoal()) { + currentState.getAction().get(intake, manipulator); + } } } if (RobotMode.disabled()) { @@ -381,6 +388,17 @@ public boolean atGoal() { && manipulator.armAtGoal(); } + public boolean atIntermediateGoal() { + var tolerance = + Optional.of( + Rotation2d.fromRadians( + V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get())); + if ((currentState.getPose().getFlyByArmTolerance()).isPresent()) { + tolerance = currentState.getPose().getFlyByArmTolerance(); + } + return elevator.atGoal() && intake.pivotAtGoal() && manipulator.armInTolerance(tolerance.get()); + } + public Command waitUntilAtGoal() { return Commands.sequence(Commands.waitSeconds(.02), Commands.waitUntil(() -> atGoal())); } @@ -711,4 +729,15 @@ public Command stateTransitions(V3_EpsilonSuperstructureStates source) { public boolean armBelowThreshold() { return manipulator.getArmAngle().getDegrees() >= 90; } + + public Command everythingsFucked(BooleanSupplier condition) { + return Commands.parallel( + override( + () -> { + elevator.setPosition(ElevatorPositions.L4); + manipulator.setArmGoal(ManipulatorArmState.HANDOFF); + intake.setPivotGoal(IntakePivotState.INTAKE_CORAL); + })) + .until(condition); + } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java index 1f9f98b2..756951b9 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java @@ -76,6 +76,8 @@ public void periodic() { } else { io.setRollerVoltage(rollerGoal.getVoltage()); } + + Logger.recordOutput("Manipulator/Arm In Tolerance", armInTolerance(Rotation2d.fromDegrees(15))); } /** From 104eb42bdb2111e0cdfff7d079ea40a0b92a1eeb Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sun, 9 Nov 2025 22:38:40 -0500 Subject: [PATCH 169/180] had to do reflection to get Choreo to work --- build.gradle | 6 ++++-- src/main/java/frc/robot/Robot.java | 20 ++++++++++++++----- .../V3_EpsilonSuperstructureEdges.java | 3 +-- 3 files changed, 20 insertions(+), 9 deletions(-) diff --git a/build.gradle b/build.gradle index d11307ba..dc0db600 100755 --- a/build.gradle +++ b/build.gradle @@ -8,6 +8,7 @@ plugins { ext { deploySrcDir = "src/main/deploy" + deployRobotDir = "/home/lvuser/deploy" } java { @@ -39,6 +40,7 @@ gradle.projectsEvaluated { if (file(candidateDir).exists()) { project.ext.deploySrcDir = candidateDir + project.ext.deployRobotDir = "/home/lvuser/deploy/${baseName}" } else { println "Folder '${candidateDir}' does not exist. Using default deploy folder." } @@ -75,7 +77,7 @@ deploy { // The options below may improve performance, but should only be enabled on the RIO 2 - final MAX_JAVA_HEAP_SIZE_MB = 100; + final MAX_JAVA_HEAP_SIZE_MB = 100 jvmArgs.add("-Xmx" + MAX_JAVA_HEAP_SIZE_MB + "M") jvmArgs.add("-Xms" + MAX_JAVA_HEAP_SIZE_MB + "M") jvmArgs.add("-XX:+AlwaysPreTouch") @@ -92,7 +94,7 @@ deploy { // Static files artifact frcStaticFileDeploy(getArtifactTypeClass('FileTreeArtifact')) { files = project.fileTree(project.ext.deploySrcDir) - directory = '/home/lvuser/deploy' + directory = deployRobotDir // Change to true to delete files on roboRIO that no // longer exist in deploy directory on roboRIO deleteOldFiles = false diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index c1bb9243..77f6bd09 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -1,14 +1,11 @@ package frc.robot; +import choreo.Choreo; import com.ctre.phoenix6.SignalLogger; import edu.wpi.first.math.MathShared; import edu.wpi.first.math.MathSharedStore; import edu.wpi.first.math.MathUsageId; -import edu.wpi.first.wpilibj.DriverStation; -import edu.wpi.first.wpilibj.IterativeRobotBase; -import edu.wpi.first.wpilibj.RobotController; -import edu.wpi.first.wpilibj.Timer; -import edu.wpi.first.wpilibj.Watchdog; +import edu.wpi.first.wpilibj.*; import edu.wpi.first.wpilibj.livewindow.LiveWindow; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj2.command.Command; @@ -27,7 +24,9 @@ import frc.robot.util.InternalLoggedTracer; import frc.robot.util.PhoenixUtil; import frc.robot.util.VirtualSubsystem; +import java.io.File; import java.lang.reflect.Field; +import java.lang.reflect.InvocationTargetException; import java.util.HashMap; import java.util.Map; import java.util.function.BiConsumer; @@ -200,6 +199,17 @@ public double getTimestamp() { } }); + try { + var m = Choreo.class.getDeclaredMethod("setChoreoDir", File.class); + m.setAccessible(true); + m.invoke( + null, + new File( + Filesystem.getDeployDirectory(), + Constants.ROBOT.name().toLowerCase().replaceFirst("_sim", "") + "/choreo")); + } catch (NoSuchMethodException | InvocationTargetException | IllegalAccessException e) { + throw new RuntimeException(e); + } // Log active commands Map commandCounts = new HashMap<>(); BiConsumer logCommandFunction = diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java index 1cfbcbe7..e6a80e62 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java @@ -2,7 +2,6 @@ import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj.Filesystem; -import edu.wpi.first.wpilibj.RobotBase; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; @@ -151,7 +150,7 @@ public static void addEdges( loadEdgesFromDot( Filesystem.getDeployDirectory() .toPath() - .resolve(!RobotBase.isSimulation() ? "" : "v3_epsilon/" + "Superstructure.dot") + .resolve("v3_epsilon/" + "Superstructure.dot") .toString(), graph, elevator, From bb1e427a14ae7a42224c69a5e3fa5de53f1a55d5 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Sun, 9 Nov 2025 22:48:34 -0500 Subject: [PATCH 170/180] V2 seems to be rotating in auto when it shouldn't --- src/main/java/frc/robot/Constants.java | 8 +- src/main/java/frc/robot/RobotState.java | 135 ++++++------------------ 2 files changed, 36 insertions(+), 107 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 77e7e874..ea7257f0 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -5,7 +5,7 @@ public final class Constants { public static final boolean TUNING_MODE = false; public static final double LOOP_PERIOD_SECONDS = 0.02; - public static final RobotType ROBOT = RobotType.V3_EPSILON_SIM; + public static final RobotType ROBOT = RobotType.V3_EPSILON; public static Mode getMode() { switch (ROBOT) { @@ -30,13 +30,13 @@ public static Mode getMode() { } } - public static enum Mode { + public enum Mode { REAL, SIM, REPLAY } - public static enum RobotType { + public enum RobotType { V0_FUNKY, V0_FUNKY_SIM, V0_WHIPLASH, @@ -53,7 +53,7 @@ public static enum RobotType { public static void main(String... args) { if (ROBOT == RobotType.V1_STACKUP_SIM) { - System.err.println("Cannot deploy, invalid mode selected: " + ROBOT.toString()); + System.err.println("Cannot deploy, invalid mode selected: " + ROBOT); System.exit(1); } } diff --git a/src/main/java/frc/robot/RobotState.java b/src/main/java/frc/robot/RobotState.java index 39255259..a3bed29a 100644 --- a/src/main/java/frc/robot/RobotState.java +++ b/src/main/java/frc/robot/RobotState.java @@ -158,45 +158,13 @@ public static void periodic( Pose2d autoAlignCoralSetpoint = baseCoralSetpoint; - if (OIData.currentReefHeight().equals(ReefState.L1)) { + if (OIData.currentReefHeight().equals(ReefState.L1) + || !Constants.RobotType.V3_EPSILON.equals(Constants.ROBOT) + || !Constants.RobotType.V3_EPSILON_SIM.equals(Constants.ROBOT)) { scoreSide = ScoreSide.CENTER; } else { // --- 2. Automatically determine the closest side of the ROBOT --- - Pose2d robotPose = getRobotPoseReef(); - // Translation2d targetTranslation = baseCoralSetpoint.getTranslation(); - // - // - // // Define "left" and "right" points on the robot, relative to its center. - // // We'll use the Y-trackwidth from DriveConstants. - // // In WPILib, +Y is "left" and -Y is "right" in robot-local coordinates. - // // - // double robotHalfWidth = DriveConstants.DRIVE_CONFIG.bumperLength() / 2.0; - // - // // Transform these robot-local points into field-global coordinates - // Translation2d leftSideField = - // robotPose - // .transformBy(new Transform2d(new Translation2d(0, - // robotHalfWidth), new Rotation2d())) - // .getTranslation(); - // Translation2d rightSideField = - // robotPose - // .transformBy(new Transform2d(new Translation2d(0, - // -robotHalfWidth), new Rotation2d())) - // .getTranslation(); - // - // // Calculate distance from each robot side to the target - // double distToLeft = leftSideField.getDistance(targetTranslation); - // double distToRight = rightSideField.getDistance(targetTranslation); - // - // // Set the static scoreSide variable based on which side is closer - // // (This variable is now updated every loop) - // if (distToLeft < distToRight) { - // scoreSide = ScoreSide.LEFT; - // } else { - // scoreSide = ScoreSide.RIGHT; - // } - if (Math.abs( MathUtil.angleModulus( baseCoralSetpoint @@ -287,28 +255,11 @@ public static void periodic( .tolerance() .get(); - ReefState algaeHeight; - switch (closestReefTag) { - case 10: - case 6: - case 8: - case 21: - case 17: - case 19: - algaeHeight = ReefState.ALGAE_INTAKE_BOTTOM; - break; - case 9: - case 11: - case 7: - case 22: - case 20: - case 18: - algaeHeight = ReefState.ALGAE_INTAKE_TOP; - break; - default: - algaeHeight = ReefState.ALGAE_INTAKE_BOTTOM; - break; - } + ReefState algaeHeight = + switch (closestReefTag) { + case 9, 11, 7, 22, 20, 18 -> ReefState.ALGAE_INTAKE_TOP; + default -> ReefState.ALGAE_INTAKE_BOTTOM; + }; InternalLoggedTracer.record("Generate Setpoints", "RobotState/Periodic"); InternalLoggedTracer.reset(); @@ -396,47 +347,27 @@ private static int getMinDistanceReefTag() { } if (AllianceFlipUtil.shouldFlip()) { - switch (minDistanceTag) { - case 0: - minDistanceTag = 7; - break; - case 1: - minDistanceTag = 6; - break; - case 2: - minDistanceTag = 11; - break; - case 3: - minDistanceTag = 10; - break; - case 4: - minDistanceTag = 9; - break; - case 5: - minDistanceTag = 8; - break; - } + minDistanceTag = + switch (minDistanceTag) { + case 0 -> 7; + case 1 -> 6; + case 2 -> 11; + case 3 -> 10; + case 4 -> 9; + case 5 -> 8; + default -> minDistanceTag; + }; } else { - switch (minDistanceTag) { - case 0: - minDistanceTag = 18; - break; - case 1: - minDistanceTag = 19; - break; - case 2: - minDistanceTag = 20; - break; - case 3: - minDistanceTag = 21; - break; - case 4: - minDistanceTag = 22; - break; - case 5: - minDistanceTag = 17; - break; - } + minDistanceTag = + switch (minDistanceTag) { + case 0 -> 18; + case 1 -> 19; + case 2 -> 20; + case 3 -> 21; + case 4 -> 22; + case 5 -> 17; + default -> minDistanceTag; + }; } return minDistanceTag; } @@ -472,7 +403,7 @@ public static Optional getBufferedPose(double timestamp) { return poseBuffer.getSample(timestamp); } - public static final record ReefAlignData( + public record ReefAlignData( int closestReefTag, Pose2d coralSetpoint, Pose2d algaeSetpoint, @@ -483,14 +414,12 @@ public static final record ReefAlignData( ReefState algaeIntakeHeight, Camera... cameras) {} - public static final record OperatorInputData( - ReefPose currentReefPost, ReefState currentReefHeight) {} + public record OperatorInputData(ReefPose currentReefPost, ReefState currentReefHeight) {} - public static final record HeadingData( + public record HeadingData( Rotation2d robotHeading, long latestRobotHeadingTimestamp, double robotYawVelocity) {} - public static final record VisionObservation( - Pose2d pose, double timestamp, Matrix stddevs) {} + public record VisionObservation(Pose2d pose, double timestamp, Matrix stddevs) {} public enum RobotMode { DISABLED, From 99874a9c2492ce67e5883a366368616f002d258d Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Fri, 21 Nov 2025 23:45:11 -0500 Subject: [PATCH 171/180] return to 190 from 9991 --- .wpilib/wpilib_preferences.json | 2 +- build.gradle | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.wpilib/wpilib_preferences.json b/.wpilib/wpilib_preferences.json index 74b5b54b..b78bd1bd 100644 --- a/.wpilib/wpilib_preferences.json +++ b/.wpilib/wpilib_preferences.json @@ -2,5 +2,5 @@ "enableCppIntellisense": false, "currentLanguage": "java", "projectYear": "2025", - "teamNumber": 9991 + "teamNumber": 190 } diff --git a/build.gradle b/build.gradle index 5fe35d63..f791edcf 100755 --- a/build.gradle +++ b/build.gradle @@ -69,7 +69,7 @@ import com.jcraft.jsch.* ext { // RoboRIO SSH details - roboRIOHost = 'roboRIO-9991-FRC.local' // Replace with your team number + roboRIOHost = 'roboRIO-190-FRC.local' // Replace with your team number roboRIOUser = 'admin' // Default user roboRIOPassword = '' // Default password machineInfoFile = '/etc/machine-info' // Path to the file to read From a75ba7a76c17a11b671da1f637f64f3699fe7840 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Fri, 21 Nov 2025 23:49:54 -0500 Subject: [PATCH 172/180] Epsilon -> Poot --- Superstructure.py | 2 +- .../{Robot_Epsilon => Robot_Poot}/config.json | 2 +- .../{Robot_Epsilon => Robot_Poot}/model.glb | Bin .../{Robot_Epsilon => Robot_Poot}/model_0.glb | Bin .../{Robot_Epsilon => Robot_Poot}/model_1.glb | Bin .../{Robot_Epsilon => Robot_Poot}/model_2.glb | Bin .../{Robot_Epsilon => Robot_Poot}/model_3.glb | Bin src/main/java/frc/robot/Constants.java | 10 +- src/main/java/frc/robot/FieldConstants.java | 8 +- src/main/java/frc/robot/Robot.java | 4 +- src/main/java/frc/robot/RobotState.java | 4 +- .../robot/commands/AutonomousCommands.java | 486 +++++++++--------- .../frc/robot/commands/CompositeCommands.java | 151 +++--- .../shared/drive/DriveConstants.java | 32 +- ...psilon.java => TunerConstantsV3_Poot.java} | 2 +- .../subsystems/shared/elevator/Elevator.java | 8 +- .../shared/elevator/ElevatorConstants.java | 6 +- .../shared/vision/VisionConstants.java | 2 +- .../v0_GompeivisionTestRobotContainer.java | 4 +- .../V3_PootMechanism3d.java} | 4 +- .../V3_PootRobotContainer.java} | 139 +++-- .../climber/V3_PootClimber.java} | 14 +- .../climber/V3_PootClimberConstants.java} | 4 +- .../climber/V3_PootClimberIO.java} | 8 +- .../climber/V3_PootClimberIOSim.java} | 18 +- .../climber/V3_PootClimberIOTalonFX.java} | 14 +- .../leds/V3_PootLEDs.java} | 8 +- .../superstructure/Superstructure.dot | 0 .../V3_PootSuperstructure.java} | 252 +++++---- .../V3_PootSuperstructureAction.java} | 20 +- .../V3_PootSuperstructureEdges.java} | 44 +- .../V3_PootSuperstructurePose.java} | 28 +- .../V3_PootSuperstructureStates.java} | 38 +- .../superstructure/intake/V3_PootIntake.java} | 26 +- .../intake/V3_PootIntakeConstants.java} | 8 +- .../intake/V3_PootIntakeIO.java} | 8 +- .../intake/V3_PootIntakeIOSim.java} | 50 +- .../intake/V3_PootIntakeIOTalonFX.java} | 58 +-- .../manipulator/V3_PootManipulator.java} | 32 +- .../V3_PootManipulatorConstants.java} | 8 +- .../manipulator/V3_PootManipulatorIO.java} | 7 +- .../manipulator/V3_PootManipulatorIOSim.java} | 70 ++- .../V3_PootManipulatorIOTalonFX.java} | 30 +- src/main/java/frc/robot/util/LTNUpdater.java | 133 +++-- 44 files changed, 862 insertions(+), 880 deletions(-) rename advantagescopeassets/{Robot_Epsilon => Robot_Poot}/config.json (98%) rename advantagescopeassets/{Robot_Epsilon => Robot_Poot}/model.glb (100%) rename advantagescopeassets/{Robot_Epsilon => Robot_Poot}/model_0.glb (100%) rename advantagescopeassets/{Robot_Epsilon => Robot_Poot}/model_1.glb (100%) rename advantagescopeassets/{Robot_Epsilon => Robot_Poot}/model_2.glb (100%) rename advantagescopeassets/{Robot_Epsilon => Robot_Poot}/model_3.glb (100%) rename src/main/java/frc/robot/subsystems/shared/drive/{TunerConstantsV3_Epsilon.java => TunerConstantsV3_Poot.java} (99%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/V3_EpsilonMechanism3d.java => v3_Poot/V3_PootMechanism3d.java} (97%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/V3_EpsilonRobotContainer.java => v3_Poot/V3_PootRobotContainer.java} (67%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/climber/V3_EpsilonClimber.java => v3_Poot/climber/V3_PootClimber.java} (89%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/climber/V3_EpsilonClimberConstants.java => v3_Poot/climber/V3_PootClimberConstants.java} (93%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/climber/V3_EpsilonClimberIO.java => v3_Poot/climber/V3_PootClimberIO.java} (86%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/climber/V3_EpsilonClimberIOSim.java => v3_Poot/climber/V3_PootClimberIOSim.java} (73%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java => v3_Poot/climber/V3_PootClimberIOTalonFX.java} (91%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/leds/V3_EpsilonLEDs.java => v3_Poot/leds/V3_PootLEDs.java} (95%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon => v3_Poot}/superstructure/Superstructure.dot (100%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java => v3_Poot/superstructure/V3_PootSuperstructure.java} (68%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/superstructure/V3_EpsilonSuperstructureAction.java => v3_Poot/superstructure/V3_PootSuperstructureAction.java} (71%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java => v3_Poot/superstructure/V3_PootSuperstructureEdges.java} (76%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java => v3_Poot/superstructure/V3_PootSuperstructurePose.java} (80%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java => v3_Poot/superstructure/V3_PootSuperstructureStates.java} (83%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java => v3_Poot/superstructure/intake/V3_PootIntake.java} (89%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java => v3_Poot/superstructure/intake/V3_PootIntakeConstants.java} (97%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java => v3_Poot/superstructure/intake/V3_PootIntakeIO.java} (93%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java => v3_Poot/superstructure/intake/V3_PootIntakeIOSim.java} (74%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java => v3_Poot/superstructure/intake/V3_PootIntakeIOTalonFX.java} (87%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java => v3_Poot/superstructure/manipulator/V3_PootManipulator.java} (89%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java => v3_Poot/superstructure/manipulator/V3_PootManipulatorConstants.java} (98%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java => v3_Poot/superstructure/manipulator/V3_PootManipulatorIO.java} (91%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java => v3_Poot/superstructure/manipulator/V3_PootManipulatorIOSim.java} (70%) rename src/main/java/frc/robot/subsystems/{v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java => v3_Poot/superstructure/manipulator/V3_PootManipulatorIOTalonFX.java} (91%) diff --git a/Superstructure.py b/Superstructure.py index 99038af3..2c562c83 100644 --- a/Superstructure.py +++ b/Superstructure.py @@ -2,7 +2,7 @@ from networkx.drawing.nx_pydot import read_dot # Load the graph from the DOT file -G = read_dot("/home/elliotscher/Documents/FRC/FRC_190/2k25-Robot-Code/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot") +G = read_dot("/home/elliotscher/Documents/FRC/FRC_190/2k25-Robot-Code/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/Superstructure.dot") # Specify your start and end nodes start = input("Enter the start node: ") diff --git a/advantagescopeassets/Robot_Epsilon/config.json b/advantagescopeassets/Robot_Poot/config.json similarity index 98% rename from advantagescopeassets/Robot_Epsilon/config.json rename to advantagescopeassets/Robot_Poot/config.json index 7ef79ac3..406fc2e2 100644 --- a/advantagescopeassets/Robot_Epsilon/config.json +++ b/advantagescopeassets/Robot_Poot/config.json @@ -1,5 +1,5 @@ { - "name": "Epsilon", + "name": "Poot", "sourceUrl": "https://frc190.onshape.com/documents/fffbf0683934212b94752d43/w/aa43f9bee049f3b1d51e0915/e/de81482fe4fd1694f19df80a", "disableSimplification": true, "rotations": [ diff --git a/advantagescopeassets/Robot_Epsilon/model.glb b/advantagescopeassets/Robot_Poot/model.glb similarity index 100% rename from advantagescopeassets/Robot_Epsilon/model.glb rename to advantagescopeassets/Robot_Poot/model.glb diff --git a/advantagescopeassets/Robot_Epsilon/model_0.glb b/advantagescopeassets/Robot_Poot/model_0.glb similarity index 100% rename from advantagescopeassets/Robot_Epsilon/model_0.glb rename to advantagescopeassets/Robot_Poot/model_0.glb diff --git a/advantagescopeassets/Robot_Epsilon/model_1.glb b/advantagescopeassets/Robot_Poot/model_1.glb similarity index 100% rename from advantagescopeassets/Robot_Epsilon/model_1.glb rename to advantagescopeassets/Robot_Poot/model_1.glb diff --git a/advantagescopeassets/Robot_Epsilon/model_2.glb b/advantagescopeassets/Robot_Poot/model_2.glb similarity index 100% rename from advantagescopeassets/Robot_Epsilon/model_2.glb rename to advantagescopeassets/Robot_Poot/model_2.glb diff --git a/advantagescopeassets/Robot_Epsilon/model_3.glb b/advantagescopeassets/Robot_Poot/model_3.glb similarity index 100% rename from advantagescopeassets/Robot_Epsilon/model_3.glb rename to advantagescopeassets/Robot_Poot/model_3.glb diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index deb3a07e..12a739af 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -5,7 +5,7 @@ public final class Constants { public static final boolean TUNING_MODE = false; public static final double LOOP_PERIOD_SECONDS = 0.02; - public static final RobotType ROBOT = RobotType.V3_EPSILON; + public static final RobotType ROBOT = RobotType.V3_POOT; public static Mode getMode() { switch (ROBOT) { @@ -14,7 +14,7 @@ public static Mode getMode() { case V0_GOMPEIVISION_TEST: case V1_STACKUP: case V2_REDUNDANCY: - case V3_EPSILON: + case V3_POOT: return RobotBase.isReal() ? Mode.REAL : Mode.REPLAY; case V0_FUNKY_SIM: @@ -22,7 +22,7 @@ public static Mode getMode() { case V0_GOMPEIVISION_TEST_SIM: case V1_STACKUP_SIM: case V2_REDUNDANCY_SIM: - case V3_EPSILON_SIM: + case V3_POOT_SIM: return Mode.SIM; default: @@ -47,8 +47,8 @@ public static enum RobotType { V1_STACKUP_SIM, V2_REDUNDANCY, V2_REDUNDANCY_SIM, - V3_EPSILON_SIM, - V3_EPSILON, + V3_POOT_SIM, + V3_POOT, } public static void main(String... args) { diff --git a/src/main/java/frc/robot/FieldConstants.java b/src/main/java/frc/robot/FieldConstants.java index 6c93cf90..37c2d658 100644 --- a/src/main/java/frc/robot/FieldConstants.java +++ b/src/main/java/frc/robot/FieldConstants.java @@ -135,8 +135,8 @@ public Pose2d getAlgaeSetpoint() { double adjustYBranch = Units.inchesToMeters(6.469); // Offset Y setpoint by center of tag to reef branch double adjustXBranch = - Constants.ROBOT.equals(Constants.RobotType.V3_EPSILON) - || Constants.ROBOT.equals(Constants.RobotType.V3_EPSILON_SIM) + Constants.ROBOT.equals(Constants.RobotType.V3_POOT) + || Constants.ROBOT.equals(Constants.RobotType.V3_POOT_SIM) ? (DriveConstants.DRIVE_CONFIG.bumperWidth() / 2.0) + FieldConstants.Reef .coralWidth // Offset X setpoint by center of robot to bumper + coral width @@ -150,8 +150,8 @@ public Pose2d getAlgaeSetpoint() { DriveConstants.DRIVE_CONFIG.bumperWidth() / 2.0 + Units.inchesToMeters(2); // Offset X setpoint by center of robot to bumper - // if (Constants.ROBOT.equals(Constants.RobotType.V3_EPSILON) - // || Constants.ROBOT.equals(Constants.RobotType.V3_EPSILON_SIM)) { + // if (Constants.ROBOT.equals(Constants.RobotType.V3_POOT) + // || Constants.ROBOT.equals(Constants.RobotType.V3_POOT_SIM)) { // adjustXAlgae += Units.inchesToMeters(5); // } diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index c1bb9243..b8900552 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -20,7 +20,7 @@ import frc.robot.subsystems.v0_Whiplash.V0_WhiplashRobotContainer; import frc.robot.subsystems.v1_StackUp.V1_StackUpRobotContainer; import frc.robot.subsystems.v2_Redundancy.V2_RedundancyRobotContainer; -import frc.robot.subsystems.v3_Epsilon.V3_EpsilonRobotContainer; +import frc.robot.subsystems.v3_Poot.V3_PootRobotContainer; import frc.robot.util.Alert; import frc.robot.util.Alert.AlertType; import frc.robot.util.CanivoreReader; @@ -160,7 +160,7 @@ public void robotInit() { V0_GOMPEIVISION_TEST_SIM -> new v0_GompeivisionTestRobotContainer(); case V1_STACKUP, V1_STACKUP_SIM -> new V1_StackUpRobotContainer(); case V2_REDUNDANCY, V2_REDUNDANCY_SIM -> new V2_RedundancyRobotContainer(); - case V3_EPSILON, V3_EPSILON_SIM -> new V3_EpsilonRobotContainer(); + case V3_POOT, V3_POOT_SIM -> new V3_PootRobotContainer(); default -> new RobotContainer() {}; }; diff --git a/src/main/java/frc/robot/RobotState.java b/src/main/java/frc/robot/RobotState.java index 39255259..0f56e314 100644 --- a/src/main/java/frc/robot/RobotState.java +++ b/src/main/java/frc/robot/RobotState.java @@ -66,8 +66,8 @@ public class RobotState { case V2_REDUNDANCY: case V2_REDUNDANCY_SIM: break; - case V3_EPSILON: - case V3_EPSILON_SIM: + case V3_POOT: + case V3_POOT_SIM: break; } diff --git a/src/main/java/frc/robot/commands/AutonomousCommands.java b/src/main/java/frc/robot/commands/AutonomousCommands.java index b89977ad..a4f5cd34 100644 --- a/src/main/java/frc/robot/commands/AutonomousCommands.java +++ b/src/main/java/frc/robot/commands/AutonomousCommands.java @@ -19,10 +19,10 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructure; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Poot.superstructure.V3_PootSuperstructure; +import frc.robot.subsystems.v3_Poot.superstructure.V3_PootSuperstructureStates; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntake; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulator; import frc.robot.util.AllianceFlipUtil; import frc.robot.util.GeometryUtil; import frc.robot.util.LoggedChoreo.LoggedAutoRoutine; @@ -1095,9 +1095,9 @@ public static final LoggedAutoRoutine autoDCenter( // public static final LoggedAutoRoutine autoALeft( // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // V3_EpsilonManipulator manipulator, + // V3_PootIntake intake, + // V3_PootSuperstructure superstructure, + // V3_PootManipulator manipulator, // Camera... cameras) { // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeft"); @@ -1125,55 +1125,55 @@ public static final LoggedAutoRoutine autoDCenter( // path1.resetOdometry(), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), // path1.cmd(), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // superstructure.runGoal(V3_PootSuperstructureStates.L4), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.25), // Commands.deadline( // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // superstructure.runGoal(V3_PootSuperstructureStates.L4), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.25), // Commands.deadline( // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // superstructure.runGoal(V3_PootSuperstructureStates.L4), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.25), // Commands.deadline( // path4.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // superstructure.runGoal(V3_PootSuperstructureStates.L4), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5))); // return routine; @@ -1181,9 +1181,9 @@ public static final LoggedAutoRoutine autoDCenter( // public static final LoggedAutoRoutine autoALeftNashoba( // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // V3_EpsilonManipulator manipulator, + // V3_PootIntake intake, + // V3_PootSuperstructure superstructure, + // V3_PootManipulator manipulator, // Camera... cameras) { // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftNashoba"); @@ -1211,55 +1211,55 @@ public static final LoggedAutoRoutine autoDCenter( // path1.resetOdometry(), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), // path1.cmd(), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // superstructure.runGoal(V3_PootSuperstructureStates.L4), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.25), // Commands.deadline( // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // superstructure.runGoal(V3_PootSuperstructureStates.L4), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.25), // Commands.deadline( // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // superstructure.runGoal(V3_PootSuperstructureStates.L4), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.25), // Commands.deadline( // path4.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // superstructure.runGoal(V3_PootSuperstructureStates.L4), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5))); // return routine; @@ -1267,9 +1267,9 @@ public static final LoggedAutoRoutine autoDCenter( // public static final LoggedAutoRoutine autoALeftDAVE( // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // V3_EpsilonManipulator manipulator, + // V3_PootIntake intake, + // V3_PootSuperstructure superstructure, + // V3_PootManipulator manipulator, // Camera... cameras) { // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoALeftD.A.V.E."); @@ -1297,55 +1297,55 @@ public static final LoggedAutoRoutine autoDCenter( // path1.resetOdometry(), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), // path1.cmd(), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // superstructure.runGoal(V3_PootSuperstructureStates.L4), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.25), // Commands.deadline( // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // superstructure.runGoal(V3_PootSuperstructureStates.L4), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.25), // Commands.deadline( // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // superstructure.runGoal(V3_PootSuperstructureStates.L4), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.25), // Commands.deadline( // path4.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // superstructure.runGoal(V3_PootSuperstructureStates.L4), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5))); // return routine; @@ -1353,9 +1353,9 @@ public static final LoggedAutoRoutine autoDCenter( // public static final LoggedAutoRoutine autoARight( // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // V3_EpsilonManipulator manipulator, + // V3_PootIntake intake, + // V3_PootSuperstructure superstructure, + // V3_PootManipulator manipulator, // Camera... cameras) { // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoARight"); @@ -1384,55 +1384,55 @@ public static final LoggedAutoRoutine autoDCenter( // path1.resetOdometry(), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), // path1.cmd(), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // superstructure.runGoal(V3_PootSuperstructureStates.L4), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.25), // Commands.deadline( // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4), + // superstructure.runGoal(V3_PootSuperstructureStates.L4), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.25), // Commands.deadline( // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.25), // Commands.deadline( // path4.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5))); // return routine; @@ -1440,9 +1440,9 @@ public static final LoggedAutoRoutine autoDCenter( // public static final LoggedAutoRoutine autoBLeft( // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // V3_EpsilonManipulator manipulator, + // V3_PootIntake intake, + // V3_PootSuperstructure superstructure, + // V3_PootManipulator manipulator, // Camera... cameras) { // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBLeft"); @@ -1466,33 +1466,33 @@ public static final LoggedAutoRoutine autoDCenter( // path1.cmd(), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE)), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5), // Commands.deadline( // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)), + // superstructure.runGoal(V3_PootSuperstructureStates.L4)), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); + // superstructure.runGoal(V3_PootSuperstructureStates.STOW_DOWN))); // return routine; // } // public static final LoggedAutoRoutine autoCLeft( // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // V3_EpsilonManipulator manipulator, + // V3_PootIntake intake, + // V3_PootSuperstructure superstructure, + // V3_PootManipulator manipulator, // Camera... cameras) { // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); @@ -1519,41 +1519,41 @@ public static final LoggedAutoRoutine autoDCenter( // path1.resetOdometry(), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), // path1.cmd(), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5), // Commands.deadline( // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5), // Commands.deadline( // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5))); // return routine; @@ -1561,9 +1561,9 @@ public static final LoggedAutoRoutine autoDCenter( // public static final LoggedAutoRoutine autoCLeftPush( // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // V3_EpsilonManipulator manipulator, + // V3_PootIntake intake, + // V3_PootSuperstructure superstructure, + // V3_PootManipulator manipulator, // Camera... cameras) { // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCLeft"); @@ -1594,41 +1594,41 @@ public static final LoggedAutoRoutine autoDCenter( // .withTimeout(0.5), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), // path1.cmd(), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5), // Commands.deadline( // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5), // Commands.deadline( // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5))); // return routine; @@ -1636,9 +1636,9 @@ public static final LoggedAutoRoutine autoDCenter( // public static final LoggedAutoRoutine autoCRight( // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // V3_EpsilonManipulator manipulator, + // V3_PootIntake intake, + // V3_PootSuperstructure superstructure, + // V3_PootManipulator manipulator, // Camera... cameras) { // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); @@ -1664,50 +1664,50 @@ public static final LoggedAutoRoutine autoDCenter( // path1.resetOdometry(), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), // path1.cmd(), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5), // Commands.deadline( // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5), // Commands.deadline( // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5))); // return routine; // } // public static final LoggedAutoRoutine autoCRightPush( // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // V3_EpsilonManipulator manipulator, + // V3_PootIntake intake, + // V3_PootSuperstructure superstructure, + // V3_PootManipulator manipulator, // Camera... cameras) { // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoCRight"); @@ -1737,50 +1737,50 @@ public static final LoggedAutoRoutine autoDCenter( // () -> drive.stop()) // .withTimeout(0.5), // path1.cmd(), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5), // Commands.deadline( // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5), // Commands.deadline( // path3.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), // Commands.runOnce(() -> RobotState.setAutoClapOverride(false)), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), // Commands.waitUntil(() -> superstructure.atGoal())), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5))); // return routine; // } // public static final LoggedAutoRoutine autoBRight( // Drive drive, - // V3_EpsilonIntake intake, - // V3_EpsilonSuperstructure superstructure, - // V3_EpsilonManipulator manipulator, + // V3_PootIntake intake, + // V3_PootSuperstructure superstructure, + // V3_PootManipulator manipulator, // Camera... cameras) { // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoBRight"); @@ -1804,30 +1804,30 @@ public static final LoggedAutoRoutine autoDCenter( // path1.cmd(), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4)), + // superstructure.runGoal(V3_PootSuperstructureStates.L4)), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5), // Commands.deadline( // path2.cmd(), - // CompositeCommands.V3_EpsilonCompositeCommands.intakeCoralDriverSequence( + // CompositeCommands.V3_PootCompositeCommands.intakeCoralDriverSequence( // superstructure, intake, manipulator), // Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT))), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE)), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN))); + // superstructure.runGoal(V3_PootSuperstructureStates.STOW_DOWN))); // return routine; // } // public static final LoggedAutoRoutine autoDCenter( - // Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + // Drive drive, V3_PootSuperstructure superstructure, Camera... cameras) { // LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoDCenter"); // LoggedAutoTrajectory path1 = // routine @@ -1844,19 +1844,19 @@ public static final LoggedAutoRoutine autoDCenter( // path1.cmd(), // Commands.parallel( // DriveCommands.autoAlignReefCoral(drive, cameras), - // superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE)), + // superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE)), // superstructure.runActionWithTimeout( - // V3_EpsilonSuperstructureStates.STOW_DOWN, - // V3_EpsilonSuperstructureStates.L4_SCORE, + // V3_PootSuperstructureStates.STOW_DOWN, + // V3_PootSuperstructureStates.L4_SCORE, // 0.5))); // return routine; // } public static final LoggedAutoRoutine autoERight( Drive drive, - V3_EpsilonSuperstructure superstructure, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator, + V3_PootSuperstructure superstructure, + V3_PootIntake intake, + V3_PootManipulator manipulator, Camera... cameras) { LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoERight"); @@ -1872,52 +1872,52 @@ public static final LoggedAutoRoutine autoERight( path1.resetOdometry(), Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), Commands.parallel( - path1.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + path1.cmd(), superstructure.runGoal(V3_PootSuperstructureStates.STOW_UP)), + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), superstructure.waitUntilAtGoal(), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), path2.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) + .runGoal(V3_PootSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.5))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4))), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + .andThen(superstructure.runGoal(V3_PootSuperstructureStates.L4))), + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), superstructure.waitUntilAtGoal(), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), path3.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) + .runGoal(V3_PootSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.5))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4))), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + .andThen(superstructure.runGoal(V3_PootSuperstructureStates.L4))), + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), superstructure.waitUntilAtGoal(), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), path4.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) + .runGoal(V3_PootSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.5))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4))), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + .andThen(superstructure.runGoal(V3_PootSuperstructureStates.L4))), + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE))); + superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE))); return routine; } public static final LoggedAutoRoutine autoELeft( Drive drive, - V3_EpsilonSuperstructure superstructure, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator, + V3_PootSuperstructure superstructure, + V3_PootIntake intake, + V3_PootManipulator manipulator, Camera... cameras) { LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoELeft"); @@ -1937,51 +1937,51 @@ public static final LoggedAutoRoutine autoELeft( path1.resetOdometry(), Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), path1.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), superstructure.waitUntilAtGoal(), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), path2.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) + .runGoal(V3_PootSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((2.0))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + .andThen(superstructure.runGoal(V3_PootSuperstructureStates.STOW_UP))), + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), superstructure.waitUntilAtGoal(), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), path3.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) + .runGoal(V3_PootSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.5))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + .andThen(superstructure.runGoal(V3_PootSuperstructureStates.STOW_UP))), + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), superstructure.waitUntilAtGoal(), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), path4.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) + .runGoal(V3_PootSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.5))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP))), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + .andThen(superstructure.runGoal(V3_PootSuperstructureStates.STOW_UP))), + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE))); + superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE))); return routine; } public static final LoggedAutoRoutine autoERightBack( Drive drive, - V3_EpsilonSuperstructure superstructure, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator, + V3_PootSuperstructure superstructure, + V3_PootIntake intake, + V3_PootManipulator manipulator, Camera... cameras) { LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoERightBack"); @@ -1997,49 +1997,49 @@ public static final LoggedAutoRoutine autoERightBack( path1.resetOdometry(), Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), path1.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), superstructure.waitUntilAtGoal(), Commands.parallel( path2.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) + .runGoal(V3_PootSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.0))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L2))), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + .andThen(superstructure.runGoal(V3_PootSuperstructureStates.L2))), + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L2, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_SCORE), + superstructure.runGoal(V3_PootSuperstructureStates.L2_SCORE), superstructure.waitUntilAtGoal(), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), path3.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) + .runGoal(V3_PootSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.0))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L2))), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + .andThen(superstructure.runGoal(V3_PootSuperstructureStates.L2))), + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L2, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_SCORE), + superstructure.runGoal(V3_PootSuperstructureStates.L2_SCORE), superstructure.waitUntilAtGoal(), Commands.parallel( path4.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) + .runGoal(V3_PootSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.0))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4))), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + .andThen(superstructure.runGoal(V3_PootSuperstructureStates.L4))), + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE))); + superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE))); return routine; } public static final LoggedAutoRoutine autoELeftBack( Drive drive, - V3_EpsilonSuperstructure superstructure, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator, + V3_PootSuperstructure superstructure, + V3_PootIntake intake, + V3_PootManipulator manipulator, Camera... cameras) { LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoELeftBack"); @@ -2063,49 +2063,49 @@ public static final LoggedAutoRoutine autoELeftBack( path1.resetOdometry(), Commands.runOnce(() -> RobotState.setReefPost(ReefPose.LEFT)), path1.cmd(), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), superstructure.waitUntilAtGoal(), Commands.parallel( path2.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) + .runGoal(V3_PootSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.0))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L2))), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + .andThen(superstructure.runGoal(V3_PootSuperstructureStates.L2))), + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L2, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_SCORE), + superstructure.runGoal(V3_PootSuperstructureStates.L2_SCORE), superstructure.waitUntilAtGoal(), Commands.parallel( Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), path3.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) + .runGoal(V3_PootSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.0))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L2))), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + .andThen(superstructure.runGoal(V3_PootSuperstructureStates.L2))), + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L2, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_SCORE), + superstructure.runGoal(V3_PootSuperstructureStates.L2_SCORE), superstructure.waitUntilAtGoal(), Commands.parallel( path4.cmd(), superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_CORAL) + .runGoal(V3_PootSuperstructureStates.GROUND_INTAKE_CORAL) .andThen(Commands.waitSeconds((1.0))) - .andThen(superstructure.runGoal(V3_EpsilonSuperstructureStates.L4))), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + .andThen(superstructure.runGoal(V3_PootSuperstructureStates.L4))), + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE))); + superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE))); return routine; } public static final LoggedAutoRoutine autoFLeft( Drive drive, - V3_EpsilonSuperstructure superstructure, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator, + V3_PootSuperstructure superstructure, + V3_PootIntake intake, + V3_PootManipulator manipulator, Camera... cameras) { LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoFLeft"); @@ -2121,33 +2121,33 @@ public static final LoggedAutoRoutine autoFLeft( Commands.sequence( path1.resetOdometry(), Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), superstructure.waitUntilAtGoal(), Commands.parallel( path2.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE)), + superstructure.runGoal(V3_PootSuperstructureStates.L3_ALGAE_INTAKE)), Commands.parallel( - path3.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), + path3.cmd(), superstructure.runGoal(V3_PootSuperstructureStates.STOW_UP)), Commands.runOnce(() -> drive.stop()), - CompositeCommands.V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure), + CompositeCommands.V3_PootCompositeCommands.optimalScoreBarge(superstructure), Commands.parallel( path4.cmd(), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE)), + superstructure.runGoal(V3_PootSuperstructureStates.L2_ALGAE_INTAKE)), Commands.parallel( - path5.cmd(), superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), + path5.cmd(), superstructure.runGoal(V3_PootSuperstructureStates.STOW_UP)), Commands.runOnce(() -> drive.stop()), - CompositeCommands.V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure))); + CompositeCommands.V3_PootCompositeCommands.optimalScoreBarge(superstructure))); return routine; } public static final LoggedAutoRoutine autoFLeftMinimal( Drive drive, - V3_EpsilonSuperstructure superstructure, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator, + V3_PootSuperstructure superstructure, + V3_PootIntake intake, + V3_PootManipulator manipulator, Camera... cameras) { LoggedAutoRoutine routine = drive.getAutoFactory().newRoutine("autoFLeftMinimal"); @@ -2159,9 +2159,9 @@ public static final LoggedAutoRoutine autoFLeftMinimal( Commands.sequence( path1.resetOdometry(), Commands.runOnce(() -> RobotState.setReefPost(ReefPose.RIGHT)), - CompositeCommands.V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence( + CompositeCommands.V3_PootCompositeCommands.optimalAutoScoreCoralSequence( drive, superstructure, ReefState.L4, cameras), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L4_SCORE), + superstructure.runGoal(V3_PootSuperstructureStates.L4_SCORE), superstructure.waitUntilAtGoal(), Commands.runOnce(() -> drive.stop()))); diff --git a/src/main/java/frc/robot/commands/CompositeCommands.java b/src/main/java/frc/robot/commands/CompositeCommands.java index 9fc19067..86b15524 100644 --- a/src/main/java/frc/robot/commands/CompositeCommands.java +++ b/src/main/java/frc/robot/commands/CompositeCommands.java @@ -22,11 +22,11 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntake; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; +import frc.robot.subsystems.v3_Poot.superstructure.V3_PootSuperstructure; +import frc.robot.subsystems.v3_Poot.superstructure.V3_PootSuperstructureStates; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntake; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulator; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulatorConstants.ManipulatorRollerState; import frc.robot.util.AllianceFlipUtil; import java.util.Set; import java.util.function.BooleanSupplier; @@ -655,35 +655,35 @@ public static final Command homingSequences( Commands.runOnce(() -> elevator.setPosition())); } - public static final class V3_EpsilonCompositeCommands { + public static final class V3_PootCompositeCommands { public static final Command intakeCoralDriverSequence( - V3_EpsilonSuperstructure superstructure, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { + V3_PootSuperstructure superstructure, + V3_PootIntake intake, + V3_PootManipulator manipulator) { return Commands.sequence( Commands.runOnce(() -> RobotState.setHasAlgae(false)), - superstructure.runGoalUntil(V3_EpsilonSuperstructureStates.GROUND_INTAKE, () -> false), - superstructure.runGoalUntil(V3_EpsilonSuperstructureStates.HANDOFF, () -> false)); + superstructure.runGoalUntil(V3_PootSuperstructureStates.GROUND_INTAKE, () -> false), + superstructure.runGoalUntil(V3_PootSuperstructureStates.HANDOFF, () -> false)); } public static final Command postIntakeCoralSequence( - V3_EpsilonSuperstructure superstructure, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { + V3_PootSuperstructure superstructure, + V3_PootIntake intake, + V3_PootManipulator manipulator) { return Commands.either( Commands.either( Commands.sequence( superstructure.runGoalUntil( - V3_EpsilonSuperstructureStates.HANDOFF_SPIN, () -> manipulator.hasCoral()), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)), + V3_PootSuperstructureStates.HANDOFF_SPIN, () -> manipulator.hasCoral()), + superstructure.runGoal(V3_PootSuperstructureStates.STOW_UP)), Commands.none(), () -> - !superstructure.getTargetState().equals(V3_EpsilonSuperstructureStates.STOW_UP) + !superstructure.getTargetState().equals(V3_PootSuperstructureStates.STOW_UP) && !superstructure .getCurrentState() - .equals(V3_EpsilonSuperstructureStates.STOW_UP)), - superstructure.runGoal(V3_EpsilonSuperstructureStates.L1), + .equals(V3_PootSuperstructureStates.STOW_UP)), + superstructure.runGoal(V3_PootSuperstructureStates.L1), () -> !RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); } @@ -697,19 +697,19 @@ public static final Command postIntakeCoralSequence( * @return A command to auto-align to the optimal side of the coral. */ public static final Command optimalAutoScoreCoralSequence( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + Drive drive, V3_PootSuperstructure superstructure, Camera... cameras) { return Commands.either( Commands.sequence( superstructure.setPosition(), DriveCommands.autoAlignReefCoral(drive, cameras) .until(() -> RobotState.getReefAlignData().atCoralSetpoint()), superstructure.runReefScoreGoal(() -> RobotState.getOIData().currentReefHeight())), - superstructure.runGoalUntil(V3_EpsilonSuperstructureStates.L1_SCORE, () -> false), + superstructure.runGoalUntil(V3_PootSuperstructureStates.L1_SCORE, () -> false), () -> !RobotState.getOIData().currentReefHeight().equals(ReefState.L1)); } public static final Command optimalAutoScoreCoralSequence( - Drive drive, V3_EpsilonSuperstructure superstructure, ReefState height, Camera... cameras) { + Drive drive, V3_PootSuperstructure superstructure, ReefState height, Camera... cameras) { return Commands.sequence( superstructure.runReefGoal(() -> height), DriveCommands.autoAlignReefCoral(drive, cameras), @@ -724,17 +724,16 @@ public static final Command optimalAutoScoreCoralSequence( } public static final Command optimalAutoAlignReefAlgae( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + Drive drive, V3_PootSuperstructure superstructure, Camera... cameras) { return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), + superstructure.runGoal(V3_PootSuperstructureStates.STOW_DOWN), DriveCommands.autoAlignReefAlgae(drive, cameras)); } - public static final Command optimalScoreBarge(V3_EpsilonSuperstructure superstructure) { + public static final Command optimalScoreBarge(V3_PootSuperstructure superstructure) { return superstructure - .runGoal(V3_EpsilonSuperstructureStates.BARGE_SCORE) - .andThen( - superstructure.runActionWithTimeout(V3_EpsilonSuperstructureStates.BARGE_SCORE, 1)); + .runGoal(V3_PootSuperstructureStates.BARGE_SCORE) + .andThen(superstructure.runActionWithTimeout(V3_PootSuperstructureStates.BARGE_SCORE, 1)); } /** @@ -745,16 +744,16 @@ public static final Command optimalScoreBarge(V3_EpsilonSuperstructure superstru * @return A command to score coral. */ public static final Command scoreCoral( - V3_EpsilonSuperstructure superstructure, Supplier goal) { + V3_PootSuperstructure superstructure, Supplier goal) { return superstructure.runReefScoreGoal(goal); } /** - * public static final Command intakeAlgaeReef(V3_EpsilonSuperstructure superstructure, - * V3_EpsilonSuperstructureStates goal, V3_EpsilonSuperstructureAction action, V3_EpsilonIntake - * intake, V3_EpsilonSuperstructure hasalgae) { return Commands.sequence( - * superstructure.runGoal(), Commands.run(() -> action.runIntake(intake)), - * superstructure.isHasAlgae() == (edge.getGamePieceEdge() != (GamePieceEdge.NO_ALGAE) ); ); } + * public static final Command intakeAlgaeReef(V3_PootSuperstructure superstructure, + * V3_PootSuperstructureStates goal, V3_PootSuperstructureAction action, V3_PootIntake intake, + * V3_PootSuperstructure hasalgae) { return Commands.sequence( superstructure.runGoal(), + * Commands.run(() -> action.runIntake(intake)), superstructure.isHasAlgae() == + * (edge.getGamePieceEdge() != (GamePieceEdge.NO_ALGAE) ); ); } */ /** @@ -763,9 +762,9 @@ public static final Command scoreCoral( public static final Command dropAlgae( Drive drive, ElevatorFSM elevator, - V3_EpsilonManipulator manipulator, - V3_EpsilonIntake intake, - V3_EpsilonSuperstructure superstructure, + V3_PootManipulator manipulator, + V3_PootIntake intake, + V3_PootSuperstructure superstructure, Supplier level, Camera... cameras) { return Commands.sequence( @@ -774,11 +773,11 @@ public static final Command dropAlgae( () -> { switch (level.get()) { case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; + return V3_PootSuperstructureStates.L3_ALGAE_INTAKE; case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; + return V3_PootSuperstructureStates.L2_ALGAE_INTAKE; default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; + return V3_PootSuperstructureStates.STOW_DOWN; } }, () -> RobotState.isHasAlgae()), @@ -790,21 +789,21 @@ public static final Command dropAlgae( () -> { switch (level.get()) { case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE_DROP; + return V3_PootSuperstructureStates.L3_ALGAE_DROP; case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + return V3_PootSuperstructureStates.L2_ALGAE_DROP; default: - return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + return V3_PootSuperstructureStates.L2_ALGAE_DROP; } }, () -> { switch (level.get()) { case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE_DROP; + return V3_PootSuperstructureStates.L3_ALGAE_DROP; case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + return V3_PootSuperstructureStates.L2_ALGAE_DROP; default: - return V3_EpsilonSuperstructureStates.L2_ALGAE_DROP; + return V3_PootSuperstructureStates.L2_ALGAE_DROP; } }, () -> 2)) @@ -816,7 +815,7 @@ public static final Command dropAlgae( public static final Command intakeAlgaeFromReef( Drive drive, - V3_EpsilonSuperstructure superstructure, + V3_PootSuperstructure superstructure, Supplier level, Camera... cameras) { @@ -826,11 +825,11 @@ public static final Command intakeAlgaeFromReef( () -> { switch (level.get()) { case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; + return V3_PootSuperstructureStates.L3_ALGAE_INTAKE; case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; + return V3_PootSuperstructureStates.L2_ALGAE_INTAKE; default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; + return V3_PootSuperstructureStates.STOW_DOWN; } }, () -> RobotState.isHasAlgae()), @@ -843,7 +842,7 @@ public static final Command intakeAlgaeFromReef( public static final Command intakeAlgaeFromReefAuto( Drive drive, - V3_EpsilonSuperstructure superstructure, + V3_PootSuperstructure superstructure, Supplier level, Camera... cameras) { @@ -853,11 +852,11 @@ public static final Command intakeAlgaeFromReefAuto( () -> { switch (level.get()) { case ALGAE_INTAKE_TOP: - return V3_EpsilonSuperstructureStates.L3_ALGAE_INTAKE; + return V3_PootSuperstructureStates.L3_ALGAE_INTAKE; case ALGAE_INTAKE_BOTTOM: - return V3_EpsilonSuperstructureStates.L2_ALGAE_INTAKE; + return V3_PootSuperstructureStates.L2_ALGAE_INTAKE; default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; + return V3_PootSuperstructureStates.STOW_DOWN; } }, () -> RobotState.isHasAlgae()), @@ -866,75 +865,75 @@ public static final Command intakeAlgaeFromReefAuto( } public static final Command postIntakeAlgaeFromReef( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { - return superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP); + Drive drive, V3_PootSuperstructure superstructure, Camera... cameras) { + return superstructure.runGoal(V3_PootSuperstructureStates.STOW_UP); } public static final Command intakeAlgaeFromReef( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + Drive drive, V3_PootSuperstructure superstructure, Camera... cameras) { return intakeAlgaeFromReef( drive, superstructure, () -> RobotState.getReefAlignData().algaeIntakeHeight(), cameras); } public static final Command intakeAlgaeFromReefAuto( - Drive drive, V3_EpsilonSuperstructure superstructure, Camera... cameras) { + Drive drive, V3_PootSuperstructure superstructure, Camera... cameras) { return intakeAlgaeFromReefAuto( drive, superstructure, () -> RobotState.getReefAlignData().algaeIntakeHeight(), cameras); } public static final Command emergencyEject( - V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { + V3_PootManipulator manipulator, V3_PootSuperstructure superstructure) { return Commands.sequence( superstructure.override( () -> { manipulator.setArmGoal( frc.robot .subsystems - .v3_Epsilon + .v3_Poot .superstructure .manipulator - .V3_EpsilonManipulatorConstants + .V3_PootManipulatorConstants .ManipulatorArmState .EMERGENCY_EJECT_ANGLE); manipulator.setRollerGoal( frc.robot .subsystems - .v3_Epsilon + .v3_Poot .superstructure .manipulator - .V3_EpsilonManipulatorConstants + .V3_PootManipulatorConstants .ManipulatorRollerState .L4_SCORE); })); } public static final Command intakeAlgaeFloor( - V3_EpsilonSuperstructure superstructure, V3_EpsilonManipulator manipulator) { + V3_PootSuperstructure superstructure, V3_PootManipulator manipulator) { return superstructure - .runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) + .runGoal(V3_PootSuperstructureStates.GROUND_INTAKE_ALGAE) .until(() -> manipulator.hasAlgae()); // add intake for algae after } public static final Command handoffCoral( - V3_EpsilonSuperstructure superstructure, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { + V3_PootSuperstructure superstructure, + V3_PootIntake intake, + V3_PootManipulator manipulator) { return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.HANDOFF), + superstructure.runGoal(V3_PootSuperstructureStates.HANDOFF), Commands.waitUntil(() -> manipulator.hasCoral()), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP)); + superstructure.runGoal(V3_PootSuperstructureStates.STOW_UP)); } public static final Command manipulatorGroundIntake( - V3_EpsilonManipulator manipulator, V3_EpsilonSuperstructure superstructure) { + V3_PootManipulator manipulator, V3_PootSuperstructure superstructure) { return Commands.sequence( Commands.runOnce( - () -> superstructure.runGoal(V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE)), + () -> superstructure.runGoal(V3_PootSuperstructureStates.GROUND_INTAKE_ALGAE)), Commands.runOnce(() -> manipulator.setRollerGoal(ManipulatorRollerState.CORAL_INTAKE))); } public static final Command setDynamicReefHeight( - ReefState height, V3_EpsilonSuperstructure superstructure) { + ReefState height, V3_PootSuperstructure superstructure) { return Commands.either( Commands.sequence( Commands.runOnce(() -> RobotState.setReefHeight(height)), @@ -942,9 +941,9 @@ public static final Command setDynamicReefHeight( Commands.none(), () -> Set.of( - V3_EpsilonSuperstructureStates.L2, - V3_EpsilonSuperstructureStates.L3, - V3_EpsilonSuperstructureStates.L4) + V3_PootSuperstructureStates.L2, + V3_PootSuperstructureStates.L3, + V3_PootSuperstructureStates.L4) .contains(superstructure.getCurrentState())); } } diff --git a/src/main/java/frc/robot/subsystems/shared/drive/DriveConstants.java b/src/main/java/frc/robot/subsystems/shared/drive/DriveConstants.java index a5fef6b9..213f4374 100644 --- a/src/main/java/frc/robot/subsystems/shared/drive/DriveConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/drive/DriveConstants.java @@ -234,19 +234,19 @@ public class DriveConstants { DRIVER_DEADBAND = 0.025; OPERATOR_DEADBAND = 0.25; break; - case V3_EPSILON: - case V3_EPSILON_SIM: - FRONT_LEFT = TunerConstantsV3_Epsilon.FrontLeft; - FRONT_RIGHT = TunerConstantsV3_Epsilon.FrontRight; - BACK_LEFT = TunerConstantsV3_Epsilon.BackLeft; - BACK_RIGHT = TunerConstantsV3_Epsilon.BackRight; + case V3_POOT: + case V3_POOT_SIM: + FRONT_LEFT = TunerConstantsV3_Poot.FrontLeft; + FRONT_RIGHT = TunerConstantsV3_Poot.FrontRight; + BACK_LEFT = TunerConstantsV3_Poot.BackLeft; + BACK_RIGHT = TunerConstantsV3_Poot.BackRight; DRIVE_CONFIG = new DriveConfig( - TunerConstantsV3_Epsilon.DrivetrainConstants.CANBusName, - TunerConstantsV3_Epsilon.DrivetrainConstants.Pigeon2Id, - TunerConstantsV3_Epsilon.kSpeedAt12Volts.in(MetersPerSecond), - TunerConstantsV3_Epsilon.kWheelRadius.in(Meters), + TunerConstantsV3_Poot.DrivetrainConstants.CANBusName, + TunerConstantsV3_Poot.DrivetrainConstants.Pigeon2Id, + TunerConstantsV3_Poot.kSpeedAt12Volts.in(MetersPerSecond), + TunerConstantsV3_Poot.kWheelRadius.in(Meters), DCMotor.getKrakenX60Foc(1), DCMotor.getKrakenX60Foc(1), FRONT_LEFT, @@ -258,12 +258,12 @@ public class DriveConstants { GAINS = new Gains( - new LoggedTunableNumber("Drive/Drive KS", TunerConstantsV3_Epsilon.driveGains.kS), - new LoggedTunableNumber("Drive/Drive KV", TunerConstantsV3_Epsilon.driveGains.kV), - new LoggedTunableNumber("Drive/Drive KP", TunerConstantsV3_Epsilon.driveGains.kP), - new LoggedTunableNumber("Drive/Drive KD", TunerConstantsV3_Epsilon.driveGains.kD), - new LoggedTunableNumber("Drive/Turn KP", TunerConstantsV3_Epsilon.steerGains.kP), - new LoggedTunableNumber("Drive/Turn KD", TunerConstantsV3_Epsilon.steerGains.kD)); + new LoggedTunableNumber("Drive/Drive KS", TunerConstantsV3_Poot.driveGains.kS), + new LoggedTunableNumber("Drive/Drive KV", TunerConstantsV3_Poot.driveGains.kV), + new LoggedTunableNumber("Drive/Drive KP", TunerConstantsV3_Poot.driveGains.kP), + new LoggedTunableNumber("Drive/Drive KD", TunerConstantsV3_Poot.driveGains.kD), + new LoggedTunableNumber("Drive/Turn KP", TunerConstantsV3_Poot.steerGains.kP), + new LoggedTunableNumber("Drive/Turn KD", TunerConstantsV3_Poot.steerGains.kD)); AUTO_ALIGN_GAINS = new AutoAlignGains( new LoggedTunableNumber("Drive/Translation KP", 4.0), diff --git a/src/main/java/frc/robot/subsystems/shared/drive/TunerConstantsV3_Epsilon.java b/src/main/java/frc/robot/subsystems/shared/drive/TunerConstantsV3_Poot.java similarity index 99% rename from src/main/java/frc/robot/subsystems/shared/drive/TunerConstantsV3_Epsilon.java rename to src/main/java/frc/robot/subsystems/shared/drive/TunerConstantsV3_Poot.java index e83723de..84fdca1d 100644 --- a/src/main/java/frc/robot/subsystems/shared/drive/TunerConstantsV3_Epsilon.java +++ b/src/main/java/frc/robot/subsystems/shared/drive/TunerConstantsV3_Poot.java @@ -11,7 +11,7 @@ // Generated by the Tuner X Swerve Project Generator // https://v6.docs.ctr-electronics.com/en/stable/docs/tuner/tuner-swerve/index.html -public class TunerConstantsV3_Epsilon { +public class TunerConstantsV3_Poot { // Both sets of gains need to be tuned to your individual robot. // The steer motor uses any SwerveModule.SteerRequestType control request with the diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java index 47f7e374..371752c6 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/Elevator.java @@ -18,8 +18,8 @@ import frc.robot.subsystems.shared.elevator.ElevatorIO.ElevatorIOInputs; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructure; import frc.robot.subsystems.v2_Redundancy.superstructure.V2_RedundancySuperstructureStates; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; +import frc.robot.subsystems.v3_Poot.superstructure.V3_PootSuperstructure; +import frc.robot.subsystems.v3_Poot.superstructure.V3_PootSuperstructureStates; import frc.robot.util.ExternalLoggedTracer; import frc.robot.util.InternalLoggedTracer; import java.util.function.BooleanSupplier; @@ -391,10 +391,10 @@ public Command sysIdRoutine(V2_RedundancySuperstructure superstructure) { Elevator.this.sysIdRoutine(superstructure)); } - public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure) { + public Command sysIdRoutine(V3_PootSuperstructure superstructure) { return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), + superstructure.runGoal(V3_PootSuperstructureStates.OVERRIDE), Elevator.this.sysIdRoutine(superstructure)); } diff --git a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java index bcdc1cf3..8e612432 100644 --- a/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/elevator/ElevatorConstants.java @@ -119,8 +119,8 @@ public class ElevatorConstants { } break; - case V3_EPSILON: - case V3_EPSILON_SIM: + case V3_POOT: + case V3_POOT_SIM: ELEVATOR_CAN_ID = 20; ELEVATOR_GEAR_RATIO = 4.0; DRUM_RADIUS = Units.inchesToMeters(2.211 / 2.0); @@ -356,7 +356,7 @@ public double getPosition() { return position.V1(); case V2_REDUNDANCY, V2_REDUNDANCY_SIM: return position.V2(); - case V3_EPSILON, V3_EPSILON_SIM: + case V3_POOT, V3_POOT_SIM: return position.V3(); default: return position.V3(); diff --git a/src/main/java/frc/robot/subsystems/shared/vision/VisionConstants.java b/src/main/java/frc/robot/subsystems/shared/vision/VisionConstants.java index fb0f3ec8..d3e57687 100644 --- a/src/main/java/frc/robot/subsystems/shared/vision/VisionConstants.java +++ b/src/main/java/frc/robot/subsystems/shared/vision/VisionConstants.java @@ -389,7 +389,7 @@ public static class RobotCameras { new Camera(new CameraIOLimelight(V2_REDUNDANCY_LEFT)), new Camera(new CameraIOLimelight(V2_REDUNDANCY_RIGHT)) }; - public static final Camera[] V3_EPSILON_CAMS = { + public static final Camera[] V3_POOT_CAMS = { new Camera( new CameraIOGompeiVision( BACK_BOTTOM_LEFT, diff --git a/src/main/java/frc/robot/subsystems/v0_GompeivisionTest/v0_GompeivisionTestRobotContainer.java b/src/main/java/frc/robot/subsystems/v0_GompeivisionTest/v0_GompeivisionTestRobotContainer.java index 7a176299..7586fc1d 100644 --- a/src/main/java/frc/robot/subsystems/v0_GompeivisionTest/v0_GompeivisionTestRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v0_GompeivisionTest/v0_GompeivisionTestRobotContainer.java @@ -27,7 +27,7 @@ public v0_GompeivisionTestRobotContainer() { vision = new Vision( () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), - RobotCameras.V3_EPSILON_CAMS); + RobotCameras.V3_POOT_CAMS); break; default: break; @@ -38,7 +38,7 @@ public v0_GompeivisionTestRobotContainer() { vision = new Vision( () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), - RobotCameras.V3_EPSILON_CAMS); + RobotCameras.V3_POOT_CAMS); } configureButtonBindings(); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonMechanism3d.java b/src/main/java/frc/robot/subsystems/v3_Poot/V3_PootMechanism3d.java similarity index 97% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonMechanism3d.java rename to src/main/java/frc/robot/subsystems/v3_Poot/V3_PootMechanism3d.java index 2705c29f..b52f73d4 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonMechanism3d.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/V3_PootMechanism3d.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon; +package frc.robot.subsystems.v3_Poot; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Pose3d; @@ -7,7 +7,7 @@ import edu.wpi.first.math.geometry.Transform3d; import org.littletonrobotics.junction.Logger; -public class V3_EpsilonMechanism3d { +public class V3_PootMechanism3d { private static final double ELEVATOR_STAGE_1_MIN_HEIGHT = 0.095250; // Meters off the ground private static final double ELEVATOR_STAGE_1_MAX_HEIGHT = 0.7809; private static final double ELEVATOR_CARRIAGE_MANIPULATOR_MIN_HEIGHT = 0.120650; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java b/src/main/java/frc/robot/subsystems/v3_Poot/V3_PootRobotContainer.java similarity index 67% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java rename to src/main/java/frc/robot/subsystems/v3_Poot/V3_PootRobotContainer.java index b11411c1..890407aa 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/V3_EpsilonRobotContainer.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/V3_PootRobotContainer.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon; +package frc.robot.subsystems.v3_Poot; import edu.wpi.first.apriltag.AprilTagFieldLayout; import edu.wpi.first.apriltag.AprilTagFields; @@ -17,7 +17,7 @@ import frc.robot.RobotState; import frc.robot.commands.AutonomousCommands; import frc.robot.commands.CompositeCommands.SharedCommands; -import frc.robot.commands.CompositeCommands.V3_EpsilonCompositeCommands; +import frc.robot.commands.CompositeCommands.V3_PootCompositeCommands; import frc.robot.commands.DriveCommands; import frc.robot.subsystems.shared.drive.*; import frc.robot.subsystems.shared.elevator.Elevator; @@ -28,38 +28,38 @@ import frc.robot.subsystems.shared.elevator.ElevatorIOTalonFX; import frc.robot.subsystems.shared.vision.Vision; import frc.robot.subsystems.shared.vision.VisionConstants.RobotCameras; -import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimber; -import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIO; -import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIOSim; -import frc.robot.subsystems.v3_Epsilon.climber.V3_EpsilonClimberIOTalonFX; -import frc.robot.subsystems.v3_Epsilon.leds.V3_EpsilonLEDs; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakePivotState; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIO; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOSim; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeIOTalonFX; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIO; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOSim; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorIOTalonFX; +import frc.robot.subsystems.v3_Poot.climber.V3_PootClimber; +import frc.robot.subsystems.v3_Poot.climber.V3_PootClimberIO; +import frc.robot.subsystems.v3_Poot.climber.V3_PootClimberIOSim; +import frc.robot.subsystems.v3_Poot.climber.V3_PootClimberIOTalonFX; +import frc.robot.subsystems.v3_Poot.leds.V3_PootLEDs; +import frc.robot.subsystems.v3_Poot.superstructure.V3_PootSuperstructure; +import frc.robot.subsystems.v3_Poot.superstructure.V3_PootSuperstructureStates; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntake; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntakeConstants.IntakePivotState; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntakeIO; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntakeIOSim; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntakeIOTalonFX; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulator; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulatorConstants.ManipulatorRollerState; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulatorIO; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulatorIOSim; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulatorIOTalonFX; import frc.robot.util.LTNUpdater; import frc.robot.util.LoggedChoreo.ChoreoChooser; import frc.robot.util.LoggedTunableNumber; import org.ironmaple.simulation.SimulatedArena; import org.littletonrobotics.junction.Logger; -public class V3_EpsilonRobotContainer implements RobotContainer { +public class V3_PootRobotContainer implements RobotContainer { // Subsystems private Drive drive; private ElevatorFSM elevator; - private V3_EpsilonIntake intake; - private V3_EpsilonManipulator manipulator; - private V3_EpsilonSuperstructure superstructure; - private V3_EpsilonClimber climber; - private V3_EpsilonLEDs leds; + private V3_PootIntake intake; + private V3_PootManipulator manipulator; + private V3_PootSuperstructure superstructure; + private V3_PootClimber climber; + private V3_PootLEDs leds; private Vision vision; // Controller @@ -69,11 +69,11 @@ public class V3_EpsilonRobotContainer implements RobotContainer { // Auto chooser private final ChoreoChooser autoChooser = new ChoreoChooser(); - public V3_EpsilonRobotContainer() { + public V3_PootRobotContainer() { if (Constants.getMode() != Mode.REPLAY) { switch (Constants.ROBOT) { - case V3_EPSILON: + case V3_POOT: drive = new Drive( new GyroIOPigeon2(), @@ -82,17 +82,17 @@ public V3_EpsilonRobotContainer() { new ModuleIOTalonFX(2, DriveConstants.BACK_LEFT), new ModuleIOTalonFX(3, DriveConstants.BACK_RIGHT)); elevator = new Elevator(new ElevatorIOTalonFX()).getFSM(); - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOTalonFX()); - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOTalonFX()); - climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOTalonFX()); - superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); - leds = new V3_EpsilonLEDs(); + intake = new V3_PootIntake(new V3_PootIntakeIOTalonFX()); + manipulator = new V3_PootManipulator(new V3_PootManipulatorIOTalonFX()); + climber = new V3_PootClimber(new V3_PootClimberIOTalonFX()); + superstructure = new V3_PootSuperstructure(elevator, intake, manipulator); + leds = new V3_PootLEDs(); vision = new Vision( () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), - RobotCameras.V3_EPSILON_CAMS); + RobotCameras.V3_POOT_CAMS); break; - case V3_EPSILON_SIM: + case V3_POOT_SIM: drive = new Drive( new GyroIO() {}, @@ -101,15 +101,15 @@ public V3_EpsilonRobotContainer() { new ModuleIOSim(DriveConstants.BACK_LEFT), new ModuleIOSim(DriveConstants.BACK_RIGHT)); elevator = new Elevator(new ElevatorIOSim()).getFSM(); - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIOSim()); - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIOSim()); - climber = new V3_EpsilonClimber(new V3_EpsilonClimberIOSim()); - superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); - leds = new V3_EpsilonLEDs(); + intake = new V3_PootIntake(new V3_PootIntakeIOSim()); + manipulator = new V3_PootManipulator(new V3_PootManipulatorIOSim()); + climber = new V3_PootClimber(new V3_PootClimberIOSim()); + superstructure = new V3_PootSuperstructure(elevator, intake, manipulator); + leds = new V3_PootLEDs(); vision = new Vision( () -> AprilTagFieldLayout.loadField(AprilTagFields.k2025ReefscapeWelded), - RobotCameras.V3_EPSILON_CAMS); + RobotCameras.V3_POOT_CAMS); break; default: break; @@ -129,19 +129,19 @@ public V3_EpsilonRobotContainer() { elevator = new Elevator(new ElevatorIO() {}).getFSM(); } if (intake == null) { - intake = new V3_EpsilonIntake(new V3_EpsilonIntakeIO() {}); + intake = new V3_PootIntake(new V3_PootIntakeIO() {}); } if (manipulator == null) { - manipulator = new V3_EpsilonManipulator(new V3_EpsilonManipulatorIO() {}); + manipulator = new V3_PootManipulator(new V3_PootManipulatorIO() {}); } if (climber == null) { - climber = new V3_EpsilonClimber(new V3_EpsilonClimberIO() {}); + climber = new V3_PootClimber(new V3_PootClimberIO() {}); } if (leds == null) { - leds = new V3_EpsilonLEDs(); + leds = new V3_PootLEDs(); } if (superstructure == null) { - superstructure = new V3_EpsilonSuperstructure(elevator, intake, manipulator); + superstructure = new V3_PootSuperstructure(elevator, intake, manipulator); } LTNUpdater.registerAll(drive, elevator, intake, manipulator); @@ -185,40 +185,37 @@ private void configureButtonBindings() { driver .y() .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); + .onTrue(V3_PootCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); driver .x() .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); + .onTrue(V3_PootCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); driver .b() .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); + .onTrue(V3_PootCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); driver .a() .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); + .onTrue(V3_PootCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); driver .rightTrigger(0.5) - .whileTrue( - V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence(drive, superstructure)); + .whileTrue(V3_PootCompositeCommands.optimalAutoScoreCoralSequence(drive, superstructure)); driver .leftTrigger(0.5) .whileTrue( - V3_EpsilonCompositeCommands.intakeCoralDriverSequence( - superstructure, intake, manipulator)) + V3_PootCompositeCommands.intakeCoralDriverSequence(superstructure, intake, manipulator)) .onFalse( - V3_EpsilonCompositeCommands.postIntakeCoralSequence( - superstructure, intake, manipulator)); + V3_PootCompositeCommands.postIntakeCoralSequence(superstructure, intake, manipulator)); driver .leftBumper() - .whileTrue(V3_EpsilonCompositeCommands.intakeAlgaeFloor(superstructure, manipulator)) + .whileTrue(V3_PootCompositeCommands.intakeAlgaeFloor(superstructure, manipulator)) .onFalse( Commands.either( - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_UP), - superstructure.runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN), + superstructure.runGoal(V3_PootSuperstructureStates.STOW_UP), + superstructure.runGoal(V3_PootSuperstructureStates.STOW_DOWN), () -> RobotState.isHasAlgae())); driver.rightBumper().onTrue(Commands.runOnce(() -> RobotState.toggleReefPost())); @@ -228,17 +225,17 @@ private void configureButtonBindings() { driver .leftStick() - .onTrue(V3_EpsilonCompositeCommands.optimalAutoScoreCoralSequence(drive, superstructure)); + .onTrue(V3_PootCompositeCommands.optimalAutoScoreCoralSequence(drive, superstructure)); driver .back() - .whileTrue(V3_EpsilonCompositeCommands.intakeAlgaeFromReef(drive, superstructure)) - .whileFalse(V3_EpsilonCompositeCommands.postIntakeAlgaeFromReef(drive, superstructure)); + .whileTrue(V3_PootCompositeCommands.intakeAlgaeFromReef(drive, superstructure)) + .whileFalse(V3_PootCompositeCommands.postIntakeAlgaeFromReef(drive, superstructure)); driver .start() .whileTrue( - V3_EpsilonCompositeCommands.dropAlgae( + V3_PootCompositeCommands.dropAlgae( drive, elevator, manipulator, @@ -254,19 +251,19 @@ private void configureButtonBindings() { operator .y() .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); + .onTrue(V3_PootCompositeCommands.setDynamicReefHeight(ReefState.L4, superstructure)); operator .x() .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); + .onTrue(V3_PootCompositeCommands.setDynamicReefHeight(ReefState.L3, superstructure)); operator .b() .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); + .onTrue(V3_PootCompositeCommands.setDynamicReefHeight(ReefState.L2, superstructure)); operator .a() .and(elevatorNotStow) - .onTrue(V3_EpsilonCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); + .onTrue(V3_PootCompositeCommands.setDynamicReefHeight(ReefState.L1, superstructure)); operator .rightTrigger(0.5) @@ -294,15 +291,15 @@ private void configureButtonBindings() { climber.winchClimber())); operator .povLeft() - .whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.PROCESSOR)) + .whileTrue(superstructure.runGoal(V3_PootSuperstructureStates.PROCESSOR)) .onFalse( superstructure - .runActionWithTimeout(V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, 1) + .runActionWithTimeout(V3_PootSuperstructureStates.PROCESSOR_SCORE, 1) .finallyDo(() -> RobotState.setHasAlgae(false))); - operator.start().whileTrue(superstructure.runGoal(V3_EpsilonSuperstructureStates.BARGE)); + operator.start().whileTrue(superstructure.runGoal(V3_PootSuperstructureStates.BARGE)); - operator.back().onTrue(V3_EpsilonCompositeCommands.optimalScoreBarge(superstructure)); + operator.back().onTrue(V3_PootCompositeCommands.optimalScoreBarge(superstructure)); Trigger trigger = driver.povLeft(); Trigger trigger2 = driver.povRight(); @@ -352,7 +349,7 @@ public void robotPeriodic() { Logger.recordOutput( "Component Poses", - V3_EpsilonMechanism3d.getPoses( + V3_PootMechanism3d.getPoses( elevator.getPositionMeters(), intake.getPivotAngle(), manipulator.getArmAngle())); if (!Constants.getMode().equals(Constants.Mode.REAL)) { diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java b/src/main/java/frc/robot/subsystems/v3_Poot/climber/V3_PootClimber.java similarity index 89% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java rename to src/main/java/frc/robot/subsystems/v3_Poot/climber/V3_PootClimber.java index a7b52179..29ac5d4f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimber.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/climber/V3_PootClimber.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.climber; +package frc.robot.subsystems.v3_Poot.climber; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; @@ -9,9 +9,9 @@ import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; -public class V3_EpsilonClimber extends SubsystemBase { - private final V3_EpsilonClimberIO io; - private final V3_EpsilonClimberIOInputsAutoLogged inputs; +public class V3_PootClimber extends SubsystemBase { + private final V3_PootClimberIO io; + private final V3_PootClimberIOInputsAutoLogged inputs; @AutoLogOutput(key = "Climber/override") private boolean override; @@ -19,9 +19,9 @@ public class V3_EpsilonClimber extends SubsystemBase { @AutoLogOutput(key = "Climber/isClimbed") private boolean isClimbed; - public V3_EpsilonClimber(V3_EpsilonClimberIO io) { + public V3_PootClimber(V3_PootClimberIO io) { this.io = io; - inputs = new V3_EpsilonClimberIOInputsAutoLogged(); + inputs = new V3_PootClimberIOInputsAutoLogged(); isClimbed = false; @@ -81,7 +81,7 @@ public Command releaseClimber() { .until( () -> inputs.deploymentPosition.getRadians() - <= V3_EpsilonClimberConstants.CLIMBER_CLIMBED_DEPLOYED_RADIANS + <= V3_PootClimberConstants.CLIMBER_CLIMBED_DEPLOYED_RADIANS || override) .finallyDo(() -> RobotState.setClimberReady(true))); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java b/src/main/java/frc/robot/subsystems/v3_Poot/climber/V3_PootClimberConstants.java similarity index 93% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java rename to src/main/java/frc/robot/subsystems/v3_Poot/climber/V3_PootClimberConstants.java index 58a9b82b..e2d3f50a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/climber/V3_PootClimberConstants.java @@ -1,9 +1,9 @@ -package frc.robot.subsystems.v3_Epsilon.climber; +package frc.robot.subsystems.v3_Poot.climber; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.util.Units; -public class V3_EpsilonClimberConstants { +public class V3_PootClimberConstants { public static final int DEPLOYMENT_CAN_ID; public static final int ROLLER_CAN_ID; diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIO.java b/src/main/java/frc/robot/subsystems/v3_Poot/climber/V3_PootClimberIO.java similarity index 86% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIO.java rename to src/main/java/frc/robot/subsystems/v3_Poot/climber/V3_PootClimberIO.java index d7f5dddd..ab6ede0c 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/climber/V3_PootClimberIO.java @@ -1,11 +1,11 @@ -package frc.robot.subsystems.v3_Epsilon.climber; +package frc.robot.subsystems.v3_Poot.climber; import edu.wpi.first.math.geometry.Rotation2d; import org.littletonrobotics.junction.AutoLog; -public interface V3_EpsilonClimberIO { +public interface V3_PootClimberIO { @AutoLog - public static class V3_EpsilonClimberIOInputs { + public static class V3_PootClimberIOInputs { public Rotation2d deploymentPosition = new Rotation2d(); public double deploymentVelocityRadiansPerSecond = 0.0; public double deploymentAppliedVolts = 0.0; @@ -25,7 +25,7 @@ public static class V3_EpsilonClimberIOInputs { * * @param inputs The inputs to update. */ - public default void updateInputs(V3_EpsilonClimberIOInputs inputs) {} + public default void updateInputs(V3_PootClimberIOInputs inputs) {} /** * Sets the voltage for the intake. diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOSim.java b/src/main/java/frc/robot/subsystems/v3_Poot/climber/V3_PootClimberIOSim.java similarity index 73% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOSim.java rename to src/main/java/frc/robot/subsystems/v3_Poot/climber/V3_PootClimberIOSim.java index 1510df00..9770a41f 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/climber/V3_PootClimberIOSim.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.climber; +package frc.robot.subsystems.v3_Poot.climber; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Rotation2d; @@ -6,27 +6,27 @@ import edu.wpi.first.wpilibj.simulation.DCMotorSim; import frc.robot.Constants; -public class V3_EpsilonClimberIOSim implements V3_EpsilonClimberIO { +public class V3_PootClimberIOSim implements V3_PootClimberIO { private final DCMotorSim sim; private double deploymentAppliedVolts; private double rollerAppliedVolts; - public V3_EpsilonClimberIOSim() { + public V3_PootClimberIOSim() { sim = new DCMotorSim( LinearSystemId.createDCMotorSystem( - V3_EpsilonClimberConstants.MOTOR_PARAMETERS.MOTOR_CONFIG(), + V3_PootClimberConstants.MOTOR_PARAMETERS.MOTOR_CONFIG(), 0.004, - V3_EpsilonClimberConstants.MOTOR_PARAMETERS.GEAR_RATIO()), - V3_EpsilonClimberConstants.MOTOR_PARAMETERS.MOTOR_CONFIG()); + V3_PootClimberConstants.MOTOR_PARAMETERS.GEAR_RATIO()), + V3_PootClimberConstants.MOTOR_PARAMETERS.MOTOR_CONFIG()); deploymentAppliedVolts = 0.0; rollerAppliedVolts = 0.0; } @Override - public void updateInputs(V3_EpsilonClimberIOInputs inputs) { + public void updateInputs(V3_PootClimberIOInputs inputs) { deploymentAppliedVolts = MathUtil.clamp(deploymentAppliedVolts, -12.0, 12.0); sim.setInputVoltage(deploymentAppliedVolts); rollerAppliedVolts = MathUtil.clamp(rollerAppliedVolts, -12.0, 12.0); @@ -38,14 +38,14 @@ public void updateInputs(V3_EpsilonClimberIOInputs inputs) { inputs.deploymentVelocityRadiansPerSecond = sim.getAngularVelocityRadPerSec(); inputs.deploymentAppliedVolts = deploymentAppliedVolts; inputs.deploymentSupplyCurrentAmps = - sim.getCurrentDrawAmps() / V3_EpsilonClimberConstants.MOTOR_PARAMETERS.GEARBOX_EFFICIENCY(); + sim.getCurrentDrawAmps() / V3_PootClimberConstants.MOTOR_PARAMETERS.GEARBOX_EFFICIENCY(); inputs.deploymentTorqueCurrentAmps = sim.getCurrentDrawAmps(); inputs.rollerPosition = Rotation2d.fromRadians(sim.getAngularPositionRad()); inputs.rollerVelocityRadiansPerSecond = sim.getAngularVelocityRadPerSec(); inputs.rollerAppliedVolts = rollerAppliedVolts; inputs.rollerSupplyCurrentAmps = - sim.getCurrentDrawAmps() / V3_EpsilonClimberConstants.MOTOR_PARAMETERS.GEARBOX_EFFICIENCY(); + sim.getCurrentDrawAmps() / V3_PootClimberConstants.MOTOR_PARAMETERS.GEARBOX_EFFICIENCY(); inputs.rollerTorqueCurrentAmps = sim.getCurrentDrawAmps(); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Poot/climber/V3_PootClimberIOTalonFX.java similarity index 91% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java rename to src/main/java/frc/robot/subsystems/v3_Poot/climber/V3_PootClimberIOTalonFX.java index 081e69a9..715ba716 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/climber/V3_EpsilonClimberIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/climber/V3_PootClimberIOTalonFX.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.climber; +package frc.robot.subsystems.v3_Poot.climber; import static edu.wpi.first.units.Units.*; import static frc.robot.util.PhoenixUtil.*; @@ -16,7 +16,7 @@ import edu.wpi.first.units.measure.Voltage; import frc.robot.util.PhoenixUtil; -public class V3_EpsilonClimberIOTalonFX implements V3_EpsilonClimberIO { +public class V3_PootClimberIOTalonFX implements V3_PootClimberIO { private final TalonFX rollerTalonFX; private final TalonFX deploymentTalonFX; @@ -42,9 +42,9 @@ public class V3_EpsilonClimberIOTalonFX implements V3_EpsilonClimberIO { private final StatusSignal deploymentTorqueCurrentAmps; private final StatusSignal deploymentTemperatureCelsius; - public V3_EpsilonClimberIOTalonFX() { - rollerTalonFX = new TalonFX(V3_EpsilonClimberConstants.ROLLER_CAN_ID); - deploymentTalonFX = new TalonFX(V3_EpsilonClimberConstants.DEPLOYMENT_CAN_ID); + public V3_PootClimberIOTalonFX() { + rollerTalonFX = new TalonFX(V3_PootClimberConstants.ROLLER_CAN_ID); + deploymentTalonFX = new TalonFX(V3_PootClimberConstants.DEPLOYMENT_CAN_ID); rollerConfig = new TalonFXConfiguration(); rollerPositionRotations = rollerTalonFX.getPosition(); @@ -84,7 +84,7 @@ public V3_EpsilonClimberIOTalonFX() { } @Override - public void updateInputs(V3_EpsilonClimberIOInputs inputs) { + public void updateInputs(V3_PootClimberIOInputs inputs) { inputs.deploymentPosition = new Rotation2d(deploymentPositionRotations.getValue()); inputs.deploymentVelocityRadiansPerSecond = deploymentVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); @@ -114,6 +114,6 @@ public void setRollerVoltage(double volts) { @Override public boolean isClimbed() { return Units.rotationsToRadians(deploymentPositionRotations.getValueAsDouble()) - <= V3_EpsilonClimberConstants.CLIMBER_CLIMBED_RADIANS; + <= V3_PootClimberConstants.CLIMBER_CLIMBED_RADIANS; } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/leds/V3_EpsilonLEDs.java b/src/main/java/frc/robot/subsystems/v3_Poot/leds/V3_PootLEDs.java similarity index 95% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/leds/V3_EpsilonLEDs.java rename to src/main/java/frc/robot/subsystems/v3_Poot/leds/V3_PootLEDs.java index d0d8e51a..328ba24e 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/leds/V3_EpsilonLEDs.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/leds/V3_PootLEDs.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.leds; +package frc.robot.subsystems.v3_Poot.leds; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.RobotController; @@ -10,7 +10,7 @@ import frc.robot.RobotState.RobotMode; import frc.robot.subsystems.shared.leds.Leds; -public class V3_EpsilonLEDs extends Leds { +public class V3_PootLEDs extends Leds { private static Leds instance; // Robot state tracking @@ -29,13 +29,13 @@ public class V3_EpsilonLEDs extends Leds { private static final int RIGHT_LENGTH_START = 34; private static final int RIGHT_LENGTH_END = 68; - public V3_EpsilonLEDs() { + public V3_PootLEDs() { super(LENGTH, PORT); } public static Leds getInstance() { if (instance == null) { - instance = new V3_EpsilonLEDs(); + instance = new V3_PootLEDs(); } return instance; } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/Superstructure.dot similarity index 100% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/Superstructure.dot rename to src/main/java/frc/robot/subsystems/v3_Poot/superstructure/Superstructure.dot diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructure.java similarity index 68% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java rename to src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructure.java index f06faee5..9c0fdec8 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructure.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructure.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure; +package frc.robot.subsystems.v3_Poot.superstructure; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; @@ -10,13 +10,13 @@ import frc.robot.RobotState.ScoreSide; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; import frc.robot.subsystems.shared.elevator.ElevatorConstants.ElevatorPositions; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.EdgeCommand; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureEdges.GamePieceEdge; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakePivotState; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; +import frc.robot.subsystems.v3_Poot.superstructure.V3_PootSuperstructureEdges.EdgeCommand; +import frc.robot.subsystems.v3_Poot.superstructure.V3_PootSuperstructureEdges.GamePieceEdge; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntake; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntakeConstants.IntakePivotState; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulator; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulatorConstants; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulatorConstants.ManipulatorArmState; import frc.robot.util.NTPrefixes; import java.util.*; import java.util.function.BooleanSupplier; @@ -30,38 +30,38 @@ import org.littletonrobotics.junction.Logger; /** - * The V3_EpsilonSuperstructure class manages the coordinated movement and state transitions of the + * The V3_PootSuperstructure class manages the coordinated movement and state transitions of the * robot's major subsystems including elevator, manipulator, and intake. */ -public class V3_EpsilonSuperstructure extends SubsystemBase { - private final Graph graph; +public class V3_PootSuperstructure extends SubsystemBase { + private final Graph graph; private final ElevatorFSM elevator; - private final V3_EpsilonIntake intake; - private final V3_EpsilonManipulator manipulator; + private final V3_PootIntake intake; + private final V3_PootManipulator manipulator; /** * The previous, current, and next states of the superstructure. These are used to track the state * transitions and manage the command scheduling. */ - @Getter private V3_EpsilonSuperstructureStates previousState; + @Getter private V3_PootSuperstructureStates previousState; /** * The current state of the superstructure, which is updated periodically based on the command * scheduling and state transitions. */ - @Getter private V3_EpsilonSuperstructureStates currentState; + @Getter private V3_PootSuperstructureStates currentState; /** * The next state that the superstructure is transitioning to. This is determined by the command * scheduling and the current target state. */ - @Getter private V3_EpsilonSuperstructureStates nextState; + @Getter private V3_PootSuperstructureStates nextState; /** * The target state that the superstructure is trying to achieve. This is set by the robot and * determines the next action to be taken. */ - @Getter private V3_EpsilonSuperstructureStates targetState; + @Getter private V3_PootSuperstructureStates targetState; /** The command that is currently being executed to transition between states. */ private EdgeCommand edgeCommand; @@ -73,27 +73,27 @@ public class V3_EpsilonSuperstructure extends SubsystemBase { * @param intake The intake subsystem. * @param manipulator The manipulator subsystem. */ - public V3_EpsilonSuperstructure( - ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { + public V3_PootSuperstructure( + ElevatorFSM elevator, V3_PootIntake intake, V3_PootManipulator manipulator) { this.elevator = elevator; this.intake = intake; this.manipulator = manipulator; previousState = null; - currentState = V3_EpsilonSuperstructureStates.START; + currentState = V3_PootSuperstructureStates.START; nextState = null; - targetState = V3_EpsilonSuperstructureStates.START; + targetState = V3_PootSuperstructureStates.START; // Initialize the graph graph = new DefaultDirectedGraph<>(EdgeCommand.class); - for (V3_EpsilonSuperstructureStates vertex : V3_EpsilonSuperstructureStates.values()) { + for (V3_PootSuperstructureStates vertex : V3_PootSuperstructureStates.values()) { graph.addVertex(vertex); } // Add edges between states - V3_EpsilonSuperstructureEdges.addEdges(graph, elevator, intake, manipulator); + V3_PootSuperstructureEdges.addEdges(graph, elevator, intake, manipulator); } /** @@ -102,7 +102,7 @@ public V3_EpsilonSuperstructure( */ @Override public void periodic() { - if (currentState != null && !currentState.equals(V3_EpsilonSuperstructureStates.OVERRIDE)) { + if (currentState != null && !currentState.equals(V3_PootSuperstructureStates.OVERRIDE)) { if (nextState != null) { // If we are in a transition, run the actions for the destination state @@ -161,7 +161,7 @@ public void periodic() { double armHeight = -manipulator.getArmAngle().rotateBy(new Rotation2d(-Math.PI / 2)).getSin() - * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() + * V3_PootManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS() + elevator.getPositionMeters(); Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Arm Height", armHeight); Logger.recordOutput(NTPrefixes.SUPERSTRUCTURE + "Clears Base", 0.075 < armHeight); @@ -171,7 +171,7 @@ public void periodic() { || armHeight > 0.37 || Math.abs( manipulator.getArmAngle().rotateBy(new Rotation2d(-Math.PI / 2)).getCos() - * V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS()) + * V3_PootManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS()) > 0.35); } @@ -180,7 +180,7 @@ public void periodic() { * * @param goal New target state to achieve */ - private void setGoal(V3_EpsilonSuperstructureStates goal) { + private void setGoal(V3_PootSuperstructureStates goal) { // Don't do anything if goal is the same if (this.targetState == goal) return; else { @@ -230,20 +230,20 @@ && isEdgeAllowed(edgeToCurrentState, goal)) { * @param goal Target state * @return Optional containing the next state in the path, empty if no path exists */ - private Optional bfs( - V3_EpsilonSuperstructureStates start, V3_EpsilonSuperstructureStates goal) { - Map parents = new HashMap<>(); - Queue queue = new LinkedList<>(); + private Optional bfs( + V3_PootSuperstructureStates start, V3_PootSuperstructureStates goal) { + Map parents = new HashMap<>(); + Queue queue = new LinkedList<>(); queue.add(start); parents.put(start, null); while (!queue.isEmpty()) { - V3_EpsilonSuperstructureStates current = queue.poll(); + V3_PootSuperstructureStates current = queue.poll(); if (current == goal) break; for (EdgeCommand edge : graph.outgoingEdgesOf(current).stream() .filter(edge -> isEdgeAllowed(edge, goal)) .toList()) { - V3_EpsilonSuperstructureStates neighbor = graph.getEdgeTarget(edge); + V3_PootSuperstructureStates neighbor = graph.getEdgeTarget(edge); if (!parents.containsKey(neighbor)) { parents.put(neighbor, current); queue.add(neighbor); @@ -253,9 +253,9 @@ private Optional bfs( if (!parents.containsKey(goal)) return Optional.empty(); - V3_EpsilonSuperstructureStates nextState = goal; + V3_PootSuperstructureStates nextState = goal; while (!nextState.equals(start)) { - V3_EpsilonSuperstructureStates parent = parents.get(nextState); + V3_PootSuperstructureStates parent = parents.get(nextState); if (parent == null) return Optional.empty(); else if (parent.equals(start)) return Optional.of(nextState); nextState = parent; @@ -270,7 +270,7 @@ private Optional bfs( * @param goal The target state * @return true if the transition is allowed */ - private boolean isEdgeAllowed(EdgeCommand edge, V3_EpsilonSuperstructureStates goal) { + private boolean isEdgeAllowed(EdgeCommand edge, V3_PootSuperstructureStates goal) { // --- 1. Algae Check (Original Logic) --- boolean gamePieceAllowed = edge.getGamePieceEdge() == GamePieceEdge.UNCONSTRAINED @@ -282,21 +282,21 @@ private boolean isEdgeAllowed(EdgeCommand edge, V3_EpsilonSuperstructureStates g // Condition is TRUE, so we must apply the path forcing logic. if (!RobotState.isHasAlgae()) { - V3_EpsilonSuperstructureStates from = graph.getEdgeSource(edge); - V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(edge); + V3_PootSuperstructureStates from = graph.getEdgeSource(edge); + V3_PootSuperstructureStates to = graph.getEdgeTarget(edge); boolean needsFlip = RobotState.getScoreSide().equals(ScoreSide.RIGHT); - if (goal == V3_EpsilonSuperstructureStates.STOW_UP && needsFlip) { - if (to == V3_EpsilonSuperstructureStates.STOW_UP - && from != V3_EpsilonSuperstructureStates.INVERSE_FLIP_UP) { + if (goal == V3_PootSuperstructureStates.STOW_UP && needsFlip) { + if (to == V3_PootSuperstructureStates.STOW_UP + && from != V3_PootSuperstructureStates.INVERSE_FLIP_UP) { return false; } } - if (goal == V3_EpsilonSuperstructureStates.STOW_UP && !needsFlip) { - if (to == V3_EpsilonSuperstructureStates.STOW_UP - && from != V3_EpsilonSuperstructureStates.INVERSE_FLIP_UP) { + if (goal == V3_PootSuperstructureStates.STOW_UP && !needsFlip) { + if (to == V3_PootSuperstructureStates.STOW_UP + && from != V3_PootSuperstructureStates.INVERSE_FLIP_UP) { return false; } } @@ -308,9 +308,9 @@ private boolean isEdgeAllowed(EdgeCommand edge, V3_EpsilonSuperstructureStates g /** Resets the superstructure to initial auto state. */ public void setAutoStart() { - currentState = V3_EpsilonSuperstructureStates.START; + currentState = V3_PootSuperstructureStates.START; nextState = null; - targetState = V3_EpsilonSuperstructureStates.STOW_DOWN; + targetState = V3_PootSuperstructureStates.STOW_DOWN; if (edgeCommand != null) { edgeCommand.getCommand().cancel(); } @@ -321,34 +321,34 @@ public void setAutoStart() { * * @return Appropriate superstructure state for current reef height */ - private V3_EpsilonSuperstructureStates getElevatorPosition() { + private V3_PootSuperstructureStates getElevatorPosition() { switch (RobotState.getOIData().currentReefHeight()) { case STOW, CORAL_INTAKE -> { - return V3_EpsilonSuperstructureStates.STOW_DOWN; + return V3_PootSuperstructureStates.STOW_DOWN; } case L1 -> { - return V3_EpsilonSuperstructureStates.L1; + return V3_PootSuperstructureStates.L1; } case L2 -> { - return V3_EpsilonSuperstructureStates.L2; + return V3_PootSuperstructureStates.L2; } case L3 -> { - return V3_EpsilonSuperstructureStates.L3; + return V3_PootSuperstructureStates.L3; } case L4 -> { - return V3_EpsilonSuperstructureStates.L4; + return V3_PootSuperstructureStates.L4; } case ALGAE_INTAKE_BOTTOM -> { - return V3_EpsilonSuperstructureStates.L2_ALGAE; + return V3_PootSuperstructureStates.L2_ALGAE; } case ALGAE_INTAKE_TOP -> { - return V3_EpsilonSuperstructureStates.L3_ALGAE; + return V3_PootSuperstructureStates.L3_ALGAE; } case ALGAE_SCORE -> { - return V3_EpsilonSuperstructureStates.BARGE; + return V3_PootSuperstructureStates.BARGE; } default -> { - return V3_EpsilonSuperstructureStates.START; + return V3_PootSuperstructureStates.START; } } } @@ -361,7 +361,7 @@ private V3_EpsilonSuperstructureStates getElevatorPosition() { * @param goal The desired superstructure state * @return Command to run the goal */ - public Command runGoal(V3_EpsilonSuperstructureStates goal) { + public Command runGoal(V3_PootSuperstructureStates goal) { return runOnce(() -> setGoal(goal)); } @@ -371,7 +371,7 @@ public Command runGoal(V3_EpsilonSuperstructureStates goal) { * @param goal Supplier providing the desired superstructure state * @return Command to run the goal */ - public Command runGoal(Supplier goal) { + public Command runGoal(Supplier goal) { return runOnce(() -> setGoal(goal.get())); } @@ -392,7 +392,7 @@ public boolean atIntermediateGoal() { var tolerance = Optional.of( Rotation2d.fromRadians( - V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get())); + V3_PootManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get())); if ((currentState.getPose().getFlyByArmTolerance()).isPresent()) { tolerance = currentState.getPose().getFlyByArmTolerance(); } @@ -411,7 +411,7 @@ public Command waitUntilAtGoal() { * @return Command that runs the override and resumes the old goal */ public Command override(Runnable action) { - return Commands.sequence(runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), Commands.run(action)) + return Commands.sequence(runGoal(V3_PootSuperstructureStates.OVERRIDE), Commands.run(action)) .finallyDo(() -> setGoal(currentState)); } @@ -433,12 +433,12 @@ public Command override(Runnable action, double timeSeconds) { * @param condition The condition to wait for after running the goal * @return Combined command for running and waiting */ - public Command runGoalUntil(V3_EpsilonSuperstructureStates goal, BooleanSupplier condition) { + public Command runGoalUntil(V3_PootSuperstructureStates goal, BooleanSupplier condition) { return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); } public Command runGoalUntil( - Supplier goal, BooleanSupplier condition) { + Supplier goal, BooleanSupplier condition) { return Commands.sequence(runGoal(goal), Commands.waitUntil(condition)); } @@ -463,15 +463,15 @@ public Command runReefGoal(Supplier goal) { // Translate ReefState to superstructure state switch (goal.get()) { case L1: - return V3_EpsilonSuperstructureStates.L1; + return V3_PootSuperstructureStates.L1; case L2: - return V3_EpsilonSuperstructureStates.L2; + return V3_PootSuperstructureStates.L2; case L3: - return V3_EpsilonSuperstructureStates.L3; + return V3_PootSuperstructureStates.L3; case L4: - return V3_EpsilonSuperstructureStates.L4; + return V3_PootSuperstructureStates.L4; default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; + return V3_PootSuperstructureStates.STOW_DOWN; } }); } @@ -488,26 +488,26 @@ public Command runReefScoreGoal(Supplier goal) { () -> { switch (goal.get()) { case L1: - return V3_EpsilonSuperstructureStates.L1_SCORE; + return V3_PootSuperstructureStates.L1_SCORE; case L2: - return V3_EpsilonSuperstructureStates.L2_SCORE; + return V3_PootSuperstructureStates.L2_SCORE; case L3: - return V3_EpsilonSuperstructureStates.L3_SCORE; + return V3_PootSuperstructureStates.L3_SCORE; case L4: - return V3_EpsilonSuperstructureStates.L4_SCORE; + return V3_PootSuperstructureStates.L4_SCORE; default: - return V3_EpsilonSuperstructureStates.STOW_DOWN; + return V3_PootSuperstructureStates.STOW_DOWN; } }); // return runActionWithTimeout( // () -> // switch (goal.get()) { - // case L1 -> V3_EpsilonSuperstructureStates.L1; - // case L2 -> V3_EpsilonSuperstructureStates.L2; - // case L3 -> V3_EpsilonSuperstructureStates.L3; - // case L4 -> V3_EpsilonSuperstructureStates.L4; - // default -> V3_EpsilonSuperstructureStates.STOW_DOWN; + // case L1 -> V3_PootSuperstructureStates.L1; + // case L2 -> V3_PootSuperstructureStates.L2; + // case L3 -> V3_PootSuperstructureStates.L3; + // case L4 -> V3_PootSuperstructureStates.L4; + // default -> V3_PootSuperstructureStates.STOW_DOWN; // }, // () -> // switch (goal.get()) { @@ -528,8 +528,8 @@ public Command runReefScoreGoal(Supplier goal) { * @return Full command sequence */ public Command runActionWithTimeout( - Supplier pose, - Supplier action, + Supplier pose, + Supplier action, DoubleSupplier timeout) { return Commands.sequence( runGoal(action), // Run the action @@ -547,7 +547,7 @@ public Command runActionWithTimeout( * @return Full command sequence */ public Command runActionWithTimeout( - V3_EpsilonSuperstructureStates pose, V3_EpsilonSuperstructureStates action, double timeout) { + V3_PootSuperstructureStates pose, V3_PootSuperstructureStates action, double timeout) { return Commands.sequence( runGoal(action), // Run the action waitUntilAtGoal(), @@ -565,24 +565,22 @@ public Command runActionWithTimeout( * @return Command sequence to perform and recover from the action */ public Command runActionWithTimeout( - Supplier action, DoubleSupplier timeout) { + Supplier action, DoubleSupplier timeout) { // Maps each action state to its corresponding pose state - Map actionPoseMap = + Map actionPoseMap = new HashMap<>() { { - put(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.L1); - put(V3_EpsilonSuperstructureStates.L2_SCORE, V3_EpsilonSuperstructureStates.L2); - put(V3_EpsilonSuperstructureStates.L3_SCORE, V3_EpsilonSuperstructureStates.L3); - put(V3_EpsilonSuperstructureStates.L4_SCORE, V3_EpsilonSuperstructureStates.L4); - put(V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.BARGE); - put( - V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, - V3_EpsilonSuperstructureStates.PROCESSOR); + put(V3_PootSuperstructureStates.L1_SCORE, V3_PootSuperstructureStates.L1); + put(V3_PootSuperstructureStates.L2_SCORE, V3_PootSuperstructureStates.L2); + put(V3_PootSuperstructureStates.L3_SCORE, V3_PootSuperstructureStates.L3); + put(V3_PootSuperstructureStates.L4_SCORE, V3_PootSuperstructureStates.L4); + put(V3_PootSuperstructureStates.BARGE_SCORE, V3_PootSuperstructureStates.BARGE); + put(V3_PootSuperstructureStates.PROCESSOR_SCORE, V3_PootSuperstructureStates.PROCESSOR); } }; // Reverse the map so we can look up the pose from action if needed - Map poseActionMap = + Map poseActionMap = actionPoseMap.entrySet().stream() .collect(Collectors.toMap(Map.Entry::getValue, Map.Entry::getKey)); @@ -602,24 +600,22 @@ public Command runActionWithTimeout( * @param timeout Timeout for the action duration * @return Command sequence to perform and recover from the action */ - public Command runActionWithTimeout(V3_EpsilonSuperstructureStates action, double timeout) { + public Command runActionWithTimeout(V3_PootSuperstructureStates action, double timeout) { // Maps each action state to its corresponding pose state - Map actionPoseMap = + Map actionPoseMap = new HashMap<>() { { - put(V3_EpsilonSuperstructureStates.L1_SCORE, V3_EpsilonSuperstructureStates.L1); - put(V3_EpsilonSuperstructureStates.L2_SCORE, V3_EpsilonSuperstructureStates.L2); - put(V3_EpsilonSuperstructureStates.L3_SCORE, V3_EpsilonSuperstructureStates.L3); - put(V3_EpsilonSuperstructureStates.L4_SCORE, V3_EpsilonSuperstructureStates.L4); - put(V3_EpsilonSuperstructureStates.BARGE_SCORE, V3_EpsilonSuperstructureStates.BARGE); - put( - V3_EpsilonSuperstructureStates.PROCESSOR_SCORE, - V3_EpsilonSuperstructureStates.PROCESSOR); + put(V3_PootSuperstructureStates.L1_SCORE, V3_PootSuperstructureStates.L1); + put(V3_PootSuperstructureStates.L2_SCORE, V3_PootSuperstructureStates.L2); + put(V3_PootSuperstructureStates.L3_SCORE, V3_PootSuperstructureStates.L3); + put(V3_PootSuperstructureStates.L4_SCORE, V3_PootSuperstructureStates.L4); + put(V3_PootSuperstructureStates.BARGE_SCORE, V3_PootSuperstructureStates.BARGE); + put(V3_PootSuperstructureStates.PROCESSOR_SCORE, V3_PootSuperstructureStates.PROCESSOR); } }; // Reverse the map so we can look up the pose from action if needed - Map poseActionMap = + Map poseActionMap = actionPoseMap.entrySet().stream() .collect(Collectors.toMap(Map.Entry::getValue, Map.Entry::getKey)); @@ -655,29 +651,29 @@ public boolean isTransitioning() { } public Command allTransition() { - Command all = runGoal(V3_EpsilonSuperstructureStates.STOW_DOWN); - for (var source : V3_EpsilonSuperstructureStates.values()) { - for (var sink : V3_EpsilonSuperstructureStates.values()) { + Command all = runGoal(V3_PootSuperstructureStates.STOW_DOWN); + for (var source : V3_PootSuperstructureStates.values()) { + for (var sink : V3_PootSuperstructureStates.values()) { if (source == sink) continue; - if (sink == V3_EpsilonSuperstructureStates.FLIP_DOWN) continue; - if (sink == V3_EpsilonSuperstructureStates.FLIP_UP) continue; - if (sink == V3_EpsilonSuperstructureStates.STOW_DOWN) continue; - if (sink == V3_EpsilonSuperstructureStates.STOW_UP) continue; - if (sink == V3_EpsilonSuperstructureStates.GROUND_ACQUISITION) continue; - if (sink == V3_EpsilonSuperstructureStates.GROUND_INTAKE_ALGAE) continue; - if (sink == V3_EpsilonSuperstructureStates.GROUND_AQUISITION_ALGAE) continue; - if (sink == V3_EpsilonSuperstructureStates.GROUND_INTAKE) continue; - if (sink == V3_EpsilonSuperstructureStates.L1) continue; - if (sink == V3_EpsilonSuperstructureStates.L1_SCORE) continue; - if (sink == V3_EpsilonSuperstructureStates.L2) continue; - if (sink == V3_EpsilonSuperstructureStates.L2_SCORE) continue; - if (sink == V3_EpsilonSuperstructureStates.L3) continue; - if (sink == V3_EpsilonSuperstructureStates.L3_SCORE) continue; - - if (source != V3_EpsilonSuperstructureStates.START - && sink != V3_EpsilonSuperstructureStates.START - && source != V3_EpsilonSuperstructureStates.OVERRIDE - && sink != V3_EpsilonSuperstructureStates.OVERRIDE) { + if (sink == V3_PootSuperstructureStates.FLIP_DOWN) continue; + if (sink == V3_PootSuperstructureStates.FLIP_UP) continue; + if (sink == V3_PootSuperstructureStates.STOW_DOWN) continue; + if (sink == V3_PootSuperstructureStates.STOW_UP) continue; + if (sink == V3_PootSuperstructureStates.GROUND_ACQUISITION) continue; + if (sink == V3_PootSuperstructureStates.GROUND_INTAKE_ALGAE) continue; + if (sink == V3_PootSuperstructureStates.GROUND_AQUISITION_ALGAE) continue; + if (sink == V3_PootSuperstructureStates.GROUND_INTAKE) continue; + if (sink == V3_PootSuperstructureStates.L1) continue; + if (sink == V3_PootSuperstructureStates.L1_SCORE) continue; + if (sink == V3_PootSuperstructureStates.L2) continue; + if (sink == V3_PootSuperstructureStates.L2_SCORE) continue; + if (sink == V3_PootSuperstructureStates.L3) continue; + if (sink == V3_PootSuperstructureStates.L3_SCORE) continue; + + if (source != V3_PootSuperstructureStates.START + && sink != V3_PootSuperstructureStates.START + && source != V3_PootSuperstructureStates.OVERRIDE + && sink != V3_PootSuperstructureStates.OVERRIDE) { all = all.andThen( runGoal(sink), @@ -702,13 +698,13 @@ public Command allTransition() { return all; } - public Command stateTransitions(V3_EpsilonSuperstructureStates source) { + public Command stateTransitions(V3_PootSuperstructureStates source) { Command all = Commands.none(); - for (var sink : V3_EpsilonSuperstructureStates.values()) { + for (var sink : V3_PootSuperstructureStates.values()) { if (sink == source - || sink == V3_EpsilonSuperstructureStates.START - || sink == V3_EpsilonSuperstructureStates.OVERRIDE) continue; + || sink == V3_PootSuperstructureStates.START + || sink == V3_PootSuperstructureStates.OVERRIDE) continue; all = all.andThen( diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureAction.java b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructureAction.java similarity index 71% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureAction.java rename to src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructureAction.java index 4f6606c8..a34a6bde 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureAction.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructureAction.java @@ -1,9 +1,9 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure; +package frc.robot.subsystems.v3_Poot.superstructure; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakeRollerState; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntake; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntakeConstants.IntakeRollerState; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulator; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulatorConstants.ManipulatorRollerState; import lombok.Getter; /** @@ -11,7 +11,7 @@ * of manipulator, funnel, and intake rollers and provides methods to control them in a coordinated * manner. */ -public class V3_EpsilonSuperstructureAction { +public class V3_PootSuperstructureAction { @Getter private final IntakeRollerState intakeRollerState; @Getter private final ManipulatorRollerState manipulatorRollerState; @@ -21,7 +21,7 @@ public class V3_EpsilonSuperstructureAction { * @param key Identifier for the action set * @param rollerStates Combined states for all subsystem rollers */ - public V3_EpsilonSuperstructureAction(String key, SubsystemActions rollerStates) { + public V3_PootSuperstructureAction(String key, SubsystemActions rollerStates) { this.intakeRollerState = rollerStates.intakeRollerState(); this.manipulatorRollerState = rollerStates.manipulatorRollerState(); } @@ -31,7 +31,7 @@ public V3_EpsilonSuperstructureAction(String key, SubsystemActions rollerStates) * * @param manipulator The manipulator subsystem to control */ - public void runManipulator(V3_EpsilonManipulator manipulator) { + public void runManipulator(V3_PootManipulator manipulator) { manipulator.setRollerGoal(manipulatorRollerState); } @@ -40,7 +40,7 @@ public void runManipulator(V3_EpsilonManipulator manipulator) { * * @param intake The intake subsystem to control */ - public void runIntake(V3_EpsilonIntake intake) { + public void runIntake(V3_PootIntake intake) { intake.setRollerGoal(intakeRollerState); } @@ -51,7 +51,7 @@ public void runIntake(V3_EpsilonIntake intake) { * @param intake The intake subsystem * @param manipulator The manipulator subsystem */ - public void get(V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { + public void get(V3_PootIntake intake, V3_PootManipulator manipulator) { runIntake(intake); runManipulator(manipulator); } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructureEdges.java similarity index 76% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java rename to src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructureEdges.java index 499b0e9e..dfd76bc4 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructureEdges.java @@ -1,12 +1,12 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure; +package frc.robot.subsystems.v3_Poot.superstructure; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj.Filesystem; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntake; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulator; import java.io.FileReader; import java.io.Reader; import java.util.ArrayList; @@ -17,12 +17,12 @@ import org.jgrapht.graph.DefaultEdge; import org.jgrapht.nio.dot.DOTImporter; -public class V3_EpsilonSuperstructureEdges { +public class V3_PootSuperstructureEdges { public static final ArrayList UNCONSTRAINED = new ArrayList<>(); public static final ArrayList NO_ALGAE_EDGES = new ArrayList<>(); - public record Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { - public Edge(V3_EpsilonSuperstructureStates from, V3_EpsilonSuperstructureStates to) { + public record Edge(V3_PootSuperstructureStates from, V3_PootSuperstructureStates to) { + public Edge(V3_PootSuperstructureStates from, V3_PootSuperstructureStates to) { this.from = from; this.to = to; } @@ -40,18 +40,18 @@ public enum GamePieceEdge { public static void loadEdgesFromDot( String path, - Graph graph, + Graph graph, ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { + V3_PootIntake intake, + V3_PootManipulator manipulator) { - DOTImporter importer = new DOTImporter<>(); + DOTImporter importer = new DOTImporter<>(); // --- Fix 1: safer vertex factory --- importer.setVertexFactory( id -> { try { - return V3_EpsilonSuperstructureStates.valueOf(id); + return V3_PootSuperstructureStates.valueOf(id); } catch (IllegalArgumentException e) { System.err.println("[DOT Import] Unknown vertex in DOT: " + id); return null; @@ -84,8 +84,8 @@ public static void loadEdgesFromDot( // --- Fix 4: assign the edge commands after load --- for (EdgeCommand e : graph.edgeSet()) { - V3_EpsilonSuperstructureStates from = graph.getEdgeSource(e); - V3_EpsilonSuperstructureStates to = graph.getEdgeTarget(e); + V3_PootSuperstructureStates from = graph.getEdgeSource(e); + V3_PootSuperstructureStates to = graph.getEdgeTarget(e); e.setCommand(getEdgeCommand(from, to, elevator, intake, manipulator)); } @@ -115,15 +115,15 @@ public static class EdgeCommand extends DefaultEdge { * state to the 'to' state. */ private static Command getEdgeCommand( - V3_EpsilonSuperstructureStates from, - V3_EpsilonSuperstructureStates to, + V3_PootSuperstructureStates from, + V3_PootSuperstructureStates to, ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { + V3_PootIntake intake, + V3_PootManipulator manipulator) { - V3_EpsilonSuperstructurePose pose = to.getPose(); + V3_PootSuperstructurePose pose = to.getPose(); - if (to.equals(V3_EpsilonSuperstructureStates.BARGE_SCORE)) { + if (to.equals(V3_PootSuperstructureStates.BARGE_SCORE)) { return Commands.sequence( pose.asConfigurationSpaceCommand(elevator, intake, manipulator), Commands.waitUntil(() -> manipulator.armInTolerance(Rotation2d.fromDegrees(6)))); @@ -143,10 +143,10 @@ private static Command getEdgeCommand( * @param intake The intake subsystem. */ public static void addEdges( - Graph graph, + Graph graph, ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { + V3_PootIntake intake, + V3_PootManipulator manipulator) { loadEdgesFromDot( Filesystem.getDeployDirectory().toPath().resolve("Superstructure.dot").toString(), graph, diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructurePose.java similarity index 80% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java rename to src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructurePose.java index 2cfafcad..a01b096b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructurePose.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructurePose.java @@ -1,14 +1,14 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure; +package frc.robot.subsystems.v3_Poot.superstructure; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import frc.robot.FieldConstants.Reef.ReefState; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakePivotState; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntake; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntakeConstants.IntakePivotState; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulator; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulatorConstants.ManipulatorArmState; import java.util.Optional; import lombok.Getter; @@ -17,7 +17,7 @@ * elevator, manipulator arm, intake, and funnel. This class allows for coordinated control of these * subsystems to achieve a desired configuration. */ -public class V3_EpsilonSuperstructurePose { +public class V3_PootSuperstructurePose { private final String key; @Getter private final ReefState elevatorHeight; @@ -27,7 +27,7 @@ public class V3_EpsilonSuperstructurePose { @Getter private final Optional flyByElevatorTolerance; @Getter private final Optional flyByArmTolerance; - public V3_EpsilonSuperstructurePose(String key, SubsystemPoses poses) { + public V3_PootSuperstructurePose(String key, SubsystemPoses poses) { this.key = key; this.elevatorHeight = poses.elevatorHeight(); @@ -38,7 +38,7 @@ public V3_EpsilonSuperstructurePose(String key, SubsystemPoses poses) { this.flyByArmTolerance = Optional.empty(); } - public V3_EpsilonSuperstructurePose(String key, SubsystemPoses poses, double elevatorTolerance) { + public V3_PootSuperstructurePose(String key, SubsystemPoses poses, double elevatorTolerance) { this.key = key; this.elevatorHeight = poses.elevatorHeight(); @@ -49,8 +49,7 @@ public V3_EpsilonSuperstructurePose(String key, SubsystemPoses poses, double ele this.flyByArmTolerance = Optional.empty(); } - public V3_EpsilonSuperstructurePose( - String key, SubsystemPoses poses, Rotation2d flyByArmTolerance) { + public V3_PootSuperstructurePose(String key, SubsystemPoses poses, Rotation2d flyByArmTolerance) { this.key = key; this.elevatorHeight = poses.elevatorHeight(); @@ -77,7 +76,7 @@ public Command setElevatorHeight(ElevatorFSM elevator) { * @param intake The intake subsystem to control. * @return A Command that sets the intake extension state and waits until it reaches the goal. */ - public Command setIntakeState(V3_EpsilonIntake intake) { + public Command setIntakeState(V3_PootIntake intake) { return Commands.parallel(Commands.runOnce(() -> intake.setPivotGoal(intakeState))); } @@ -87,7 +86,7 @@ public Command setIntakeState(V3_EpsilonIntake intake) { * @param manipulator The manipulator subsystem to control. * @return A Command that sets the arm state and waits until it reaches the goal. */ - public Command setManipulatorState(V3_EpsilonManipulator manipulator) { + public Command setManipulatorState(V3_PootManipulator manipulator) { return Commands.parallel(Commands.runOnce(() -> manipulator.setArmGoal(armState))); } @@ -101,15 +100,14 @@ public Command setManipulatorState(V3_EpsilonManipulator manipulator) { * @return A Command that sets all subsystems to their respective states in parallel. */ public Command asConfigurationSpaceCommand( - ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { + ElevatorFSM elevator, V3_PootIntake intake, V3_PootManipulator manipulator) { return Commands.parallel( Commands.runOnce(() -> elevator.setPosition(() -> elevatorHeight)), Commands.runOnce(() -> manipulator.setArmGoal(armState)), Commands.runOnce(() -> intake.setPivotGoal(intakeState))); } - public Command wait( - ElevatorFSM elevator, V3_EpsilonIntake intake, V3_EpsilonManipulator manipulator) { + public Command wait(ElevatorFSM elevator, V3_PootIntake intake, V3_PootManipulator manipulator) { if (flyByElevatorTolerance.isPresent()) { return Commands.waitUntil(() -> elevator.inTolerance(flyByElevatorTolerance.get())); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructureStates.java similarity index 83% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java rename to src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructureStates.java index db2b6d02..4b0e0247 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/V3_EpsilonSuperstructureStates.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructureStates.java @@ -1,16 +1,16 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure; +package frc.robot.subsystems.v3_Poot.superstructure; import edu.wpi.first.math.geometry.Rotation2d; import frc.robot.FieldConstants.Reef.ReefState; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureAction.SubsystemActions; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructurePose.SubsystemPoses; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakePivotState; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakeRollerState; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; +import frc.robot.subsystems.v3_Poot.superstructure.V3_PootSuperstructureAction.SubsystemActions; +import frc.robot.subsystems.v3_Poot.superstructure.V3_PootSuperstructurePose.SubsystemPoses; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntakeConstants.IntakePivotState; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntakeConstants.IntakeRollerState; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulatorConstants.ManipulatorArmState; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulatorConstants.ManipulatorRollerState; import lombok.Getter; -public enum V3_EpsilonSuperstructureStates { +public enum V3_PootSuperstructureStates { START("START", new SubsystemPoses(), SubsystemActions.empty()), STOW_DOWN( "STOW_DOWN", @@ -171,8 +171,8 @@ public enum V3_EpsilonSuperstructureStates { ReefState.HANDOFF, ManipulatorArmState.INVERSE_FLIP_ANGLE, IntakePivotState.STOW), SubsystemActions.empty()); - @Getter private final V3_EpsilonSuperstructurePose pose; - @Getter private final V3_EpsilonSuperstructureAction action; + @Getter private final V3_PootSuperstructurePose pose; + @Getter private final V3_PootSuperstructureAction action; /** * Constructor for V3_SuperstructureStates. @@ -181,20 +181,20 @@ public enum V3_EpsilonSuperstructureStates { * @param pose The subsystem poses for this state. * @param action The subsystem actions for this state. */ - V3_EpsilonSuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { - this.pose = new V3_EpsilonSuperstructurePose(name, pose); - this.action = new V3_EpsilonSuperstructureAction(name, action); + V3_PootSuperstructureStates(String name, SubsystemPoses pose, SubsystemActions action) { + this.pose = new V3_PootSuperstructurePose(name, pose); + this.action = new V3_PootSuperstructureAction(name, action); } - V3_EpsilonSuperstructureStates( + V3_PootSuperstructureStates( String name, SubsystemPoses pose, SubsystemActions action, Double elevatorTolerance) { - this.pose = new V3_EpsilonSuperstructurePose(name, pose, elevatorTolerance); - this.action = new V3_EpsilonSuperstructureAction(name, action); + this.pose = new V3_PootSuperstructurePose(name, pose, elevatorTolerance); + this.action = new V3_PootSuperstructureAction(name, action); } - V3_EpsilonSuperstructureStates( + V3_PootSuperstructureStates( String name, SubsystemPoses pose, SubsystemActions action, Rotation2d armTolerance) { - this.pose = new V3_EpsilonSuperstructurePose(name, pose, armTolerance); - this.action = new V3_EpsilonSuperstructureAction(name, action); + this.pose = new V3_PootSuperstructurePose(name, pose, armTolerance); + this.action = new V3_PootSuperstructureAction(name, action); } } diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/intake/V3_PootIntake.java similarity index 89% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java rename to src/main/java/frc/robot/subsystems/v3_Poot/superstructure/intake/V3_PootIntake.java index 0538ad00..f9b7555b 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntake.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/intake/V3_PootIntake.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure.intake; +package frc.robot.subsystems.v3_Poot.superstructure.intake; import static edu.wpi.first.units.Units.*; @@ -8,16 +8,16 @@ import edu.wpi.first.wpilibj2.command.Subsystem; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakePivotState; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants.IntakeRollerState; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntakeConstants.IntakePivotState; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntakeConstants.IntakeRollerState; import java.util.Set; import lombok.Getter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; -public class V3_EpsilonIntake { - private final V3_EpsilonIntakeIO io; - private final V3_EpsilonIntakeIOInputsAutoLogged inputs; +public class V3_PootIntake { + private final V3_PootIntakeIO io; + private final V3_PootIntakeIOInputsAutoLogged inputs; // private final double INTAKE_CORAL_THRESHOLD = 1.0; @Getter @@ -30,9 +30,9 @@ public class V3_EpsilonIntake { private boolean isClosedLoop; - public V3_EpsilonIntake(V3_EpsilonIntakeIO io) { + public V3_PootIntake(V3_PootIntakeIO io) { this.io = io; - inputs = new V3_EpsilonIntakeIOInputsAutoLogged(); + inputs = new V3_PootIntakeIOInputsAutoLogged(); pivotGoal = IntakePivotState.STOW; rollerGoal = IntakeRollerState.STOP; @@ -94,7 +94,7 @@ public boolean hasCoralLoose() { @AutoLogOutput(key = "Intake/At Goal") public boolean pivotAtGoal() { return Math.abs(inputs.pivotPosition.getRadians() - pivotGoal.getAngle().getRadians()) - < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); + < V3_PootIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); } /** @@ -107,7 +107,7 @@ public boolean pivotAtGoal() { */ public boolean pivotAtGoal(IntakePivotState goal) { return Math.abs(inputs.pivotPosition.getRadians() - goal.getAngle().getRadians()) - < V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); + < V3_PootIntakeConstants.PIVOT_CONSTRAINTS.GOAL_TOLERANCE().getRadians(); } /** @@ -153,9 +153,9 @@ public void setRollerGoal(IntakeRollerState rollerGoal) { if (hasCoralLocked() || hasCoralLoose() && Set.of( - V3_EpsilonIntakeConstants.IntakeRollerState.ALGAE_INTAKE, - V3_EpsilonIntakeConstants.IntakeRollerState.CORAL_INTAKE, - V3_EpsilonIntakeConstants.IntakeRollerState.STOP) + V3_PootIntakeConstants.IntakeRollerState.ALGAE_INTAKE, + V3_PootIntakeConstants.IntakeRollerState.CORAL_INTAKE, + V3_PootIntakeConstants.IntakeRollerState.STOP) .contains(rollerGoal)) { io.setInnerRollerVoltage(0); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/intake/V3_PootIntakeConstants.java similarity index 97% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java rename to src/main/java/frc/robot/subsystems/v3_Poot/superstructure/intake/V3_PootIntakeConstants.java index 894ac580..09fe1799 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/intake/V3_PootIntakeConstants.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure.intake; +package frc.robot.subsystems.v3_Poot.superstructure.intake; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.system.plant.DCMotor; @@ -7,7 +7,7 @@ import lombok.Getter; import lombok.RequiredArgsConstructor; -public class V3_EpsilonIntakeConstants { +public class V3_PootIntakeConstants { public static final int PIVOT_CAN_ID; public static final int ROLLER_CAN_ID_OUTER; @@ -46,7 +46,7 @@ public class V3_EpsilonIntakeConstants { 1, DCMotor.getKrakenX60Foc(1), 0, new Rotation2d(), Rotation2d.fromDegrees(0)); switch (Constants.ROBOT) { - case V3_EPSILON: + case V3_POOT: PIVOT_CONSTRAINTS = new Constraints( new LoggedTunableNumber("Intake/Max Acceleration", 160), @@ -64,7 +64,7 @@ public class V3_EpsilonIntakeConstants { break; - case V3_EPSILON_SIM: + case V3_POOT_SIM: PIVOT_CONSTRAINTS = new Constraints( new LoggedTunableNumber("Intake/Max Acceleration", 100.0), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/intake/V3_PootIntakeIO.java similarity index 93% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java rename to src/main/java/frc/robot/subsystems/v3_Poot/superstructure/intake/V3_PootIntakeIO.java index 9d5e7364..c13e2fad 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/intake/V3_PootIntakeIO.java @@ -1,11 +1,11 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure.intake; +package frc.robot.subsystems.v3_Poot.superstructure.intake; import edu.wpi.first.math.geometry.Rotation2d; import org.littletonrobotics.junction.AutoLog; -public interface V3_EpsilonIntakeIO { +public interface V3_PootIntakeIO { @AutoLog - public class V3_EpsilonIntakeIOInputs { + public class V3_PootIntakeIOInputs { public Rotation2d pivotPosition = new Rotation2d(); public double pivotVelocityRadiansPerSecond = 0.0; public double pivotAppliedVolts = 0.0; @@ -41,7 +41,7 @@ public class V3_EpsilonIntakeIOInputs { * * @param inputs The inputs to update. */ - public default void updateInputs(V3_EpsilonIntakeIOInputs inputs) {} + public default void updateInputs(V3_PootIntakeIOInputs inputs) {} /** * Sets the voltage for the intake. diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/intake/V3_PootIntakeIOSim.java similarity index 74% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java rename to src/main/java/frc/robot/subsystems/v3_Poot/superstructure/intake/V3_PootIntakeIOSim.java index 8de107a9..e103c26a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/intake/V3_PootIntakeIOSim.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure.intake; +package frc.robot.subsystems.v3_Poot.superstructure.intake; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.ArmFeedforward; @@ -10,7 +10,7 @@ import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim; import frc.robot.Constants; -public class V3_EpsilonIntakeIOSim implements V3_EpsilonIntakeIO { +public class V3_PootIntakeIOSim implements V3_PootIntakeIO { private SingleJointedArmSim pivotMotorSim; private DCMotorSim rollerInnerMotorSim; private DCMotorSim rollerOuterMotorSim; @@ -24,51 +24,51 @@ public class V3_EpsilonIntakeIOSim implements V3_EpsilonIntakeIO { private boolean isClosedLoop; - public V3_EpsilonIntakeIOSim() { + public V3_PootIntakeIOSim() { pivotMotorSim = new SingleJointedArmSim( LinearSystemId.createSingleJointedArmSystem( - V3_EpsilonIntakeConstants.PIVOT_PARAMS.MOTOR(), - V3_EpsilonIntakeConstants.PIVOT_PARAMS.MASS_KG(), - V3_EpsilonIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO()), - V3_EpsilonIntakeConstants.PIVOT_PARAMS.MOTOR(), - V3_EpsilonIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO(), + V3_PootIntakeConstants.PIVOT_PARAMS.MOTOR(), + V3_PootIntakeConstants.PIVOT_PARAMS.MASS_KG(), + V3_PootIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO()), + V3_PootIntakeConstants.PIVOT_PARAMS.MOTOR(), + V3_PootIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO(), 1, - V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getRadians(), - V3_EpsilonIntakeConstants.PIVOT_PARAMS.MAX_ANGLE().getRadians(), + V3_PootIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getRadians(), + V3_PootIntakeConstants.PIVOT_PARAMS.MAX_ANGLE().getRadians(), true, - V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getRadians()); + V3_PootIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getRadians()); rollerInnerMotorSim = new DCMotorSim( LinearSystemId.createDCMotorSystem( - V3_EpsilonIntakeConstants.ROLLER_PARAMS.MOTOR(), + V3_PootIntakeConstants.ROLLER_PARAMS.MOTOR(), 0.04, - V3_EpsilonIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO()), - V3_EpsilonIntakeConstants.ROLLER_PARAMS.MOTOR()); + V3_PootIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO()), + V3_PootIntakeConstants.ROLLER_PARAMS.MOTOR()); rollerOuterMotorSim = new DCMotorSim( LinearSystemId.createDCMotorSystem( - V3_EpsilonIntakeConstants.ROLLER_PARAMS.MOTOR(), + V3_PootIntakeConstants.ROLLER_PARAMS.MOTOR(), 0.04, - V3_EpsilonIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO()), - V3_EpsilonIntakeConstants.ROLLER_PARAMS.MOTOR()); + V3_PootIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO()), + V3_PootIntakeConstants.ROLLER_PARAMS.MOTOR()); armFeedbackController = new ProfiledPIDController( - V3_EpsilonIntakeConstants.PIVOT_GAINS.kP().get(), + V3_PootIntakeConstants.PIVOT_GAINS.kP().get(), 0.0, - V3_EpsilonIntakeConstants.PIVOT_GAINS.kD().get(), - V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.getTrapezoidConstraints()); + V3_PootIntakeConstants.PIVOT_GAINS.kD().get(), + V3_PootIntakeConstants.PIVOT_CONSTRAINTS.getTrapezoidConstraints()); armFeedbackController.disableContinuousInput(); armFeedforwardController = new ArmFeedforward( - V3_EpsilonIntakeConstants.PIVOT_GAINS.kS().get(), - V3_EpsilonIntakeConstants.PIVOT_GAINS.kA().get(), - V3_EpsilonIntakeConstants.PIVOT_GAINS.kV().get(), - V3_EpsilonIntakeConstants.PIVOT_GAINS.kA().get()); + V3_PootIntakeConstants.PIVOT_GAINS.kS().get(), + V3_PootIntakeConstants.PIVOT_GAINS.kA().get(), + V3_PootIntakeConstants.PIVOT_GAINS.kV().get(), + V3_PootIntakeConstants.PIVOT_GAINS.kA().get()); pivotAppliedVoltage = 0.0; rollerInnerAppliedVoltage = 0.0; @@ -77,7 +77,7 @@ public V3_EpsilonIntakeIOSim() { } @Override - public void updateInputs(V3_EpsilonIntakeIOInputs inputs) { + public void updateInputs(V3_PootIntakeIOInputs inputs) { if (isClosedLoop) { pivotAppliedVoltage = armFeedbackController.calculate(pivotMotorSim.getAngleRads()) diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/intake/V3_PootIntakeIOTalonFX.java similarity index 87% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java rename to src/main/java/frc/robot/subsystems/v3_Poot/superstructure/intake/V3_PootIntakeIOTalonFX.java index 46cf0c99..3cd0e034 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/intake/V3_EpsilonIntakeIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/intake/V3_PootIntakeIOTalonFX.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure.intake; +package frc.robot.subsystems.v3_Poot.superstructure.intake; import static edu.wpi.first.units.Units.RadiansPerSecond; import static edu.wpi.first.units.Units.RadiansPerSecondPerSecond; @@ -29,7 +29,7 @@ import frc.robot.util.PhoenixUtil; import java.util.ArrayList; -public class V3_EpsilonIntakeIOTalonFX implements V3_EpsilonIntakeIO { +public class V3_PootIntakeIOTalonFX implements V3_PootIntakeIO { private final TalonFX pivotTalonFX; private final StatusSignal pivotPositionRotations; @@ -78,51 +78,51 @@ public class V3_EpsilonIntakeIOTalonFX implements V3_EpsilonIntakeIO { private StatusSignal[] statusSignals; - public V3_EpsilonIntakeIOTalonFX() { - pivotTalonFX = new TalonFX(V3_EpsilonIntakeConstants.PIVOT_CAN_ID); - rollerTalonFXOuter = new TalonFX(V3_EpsilonIntakeConstants.ROLLER_CAN_ID_OUTER); - rollerTalonFXInner = new TalonFX(V3_EpsilonIntakeConstants.ROLLER_CAN_ID_INNER); + public V3_PootIntakeIOTalonFX() { + pivotTalonFX = new TalonFX(V3_PootIntakeConstants.PIVOT_CAN_ID); + rollerTalonFXOuter = new TalonFX(V3_PootIntakeConstants.ROLLER_CAN_ID_OUTER); + rollerTalonFXInner = new TalonFX(V3_PootIntakeConstants.ROLLER_CAN_ID_INNER); - leftCANrange = new CANrange(V3_EpsilonIntakeConstants.LEFT_SENSOR_CAN_ID); - rightCANrange = new CANrange(V3_EpsilonIntakeConstants.RIGHT_SENSOR_CAN_ID); + leftCANrange = new CANrange(V3_PootIntakeConstants.LEFT_SENSOR_CAN_ID); + rightCANrange = new CANrange(V3_PootIntakeConstants.RIGHT_SENSOR_CAN_ID); pivotConfig = new TalonFXConfiguration(); pivotConfig.CurrentLimits.SupplyCurrentLimitEnable = true; pivotConfig.CurrentLimits.SupplyCurrentLimit = - V3_EpsilonIntakeConstants.CURRENT_LIMITS.PIVOT_SUPPLY_CURRENT_LIMIT(); + V3_PootIntakeConstants.CURRENT_LIMITS.PIVOT_SUPPLY_CURRENT_LIMIT(); pivotConfig.CurrentLimits.StatorCurrentLimitEnable = true; pivotConfig.CurrentLimits.StatorCurrentLimit = - V3_EpsilonIntakeConstants.CURRENT_LIMITS.PIVOT_STATOR_CURRENT_LIMIT(); + V3_PootIntakeConstants.CURRENT_LIMITS.PIVOT_STATOR_CURRENT_LIMIT(); pivotConfig.Feedback.SensorToMechanismRatio = - V3_EpsilonIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO(); + V3_PootIntakeConstants.PIVOT_PARAMS.PIVOT_GEAR_RATIO(); pivotConfig.SoftwareLimitSwitch.ForwardSoftLimitEnable = true; pivotConfig.SoftwareLimitSwitch.ForwardSoftLimitThreshold = - V3_EpsilonIntakeConstants.PIVOT_PARAMS.MAX_ANGLE().getRotations(); + V3_PootIntakeConstants.PIVOT_PARAMS.MAX_ANGLE().getRotations(); pivotConfig.SoftwareLimitSwitch.ReverseSoftLimitEnable = true; pivotConfig.SoftwareLimitSwitch.ReverseSoftLimitThreshold = - V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getRotations(); + V3_PootIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getRotations(); pivotConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; pivotConfig.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive; pivotConfig.Slot0 = new Slot0Configs() .withGravityType(GravityTypeValue.Arm_Cosine) - .withKP(V3_EpsilonIntakeConstants.PIVOT_GAINS.kP().get()) - .withKD(V3_EpsilonIntakeConstants.PIVOT_GAINS.kD().get()) - .withKA(V3_EpsilonIntakeConstants.PIVOT_GAINS.kA().get()) - .withKV(V3_EpsilonIntakeConstants.PIVOT_GAINS.kV().get()) - .withKS(V3_EpsilonIntakeConstants.PIVOT_GAINS.kS().get()) - .withKG(V3_EpsilonIntakeConstants.PIVOT_GAINS.kG().get()); + .withKP(V3_PootIntakeConstants.PIVOT_GAINS.kP().get()) + .withKD(V3_PootIntakeConstants.PIVOT_GAINS.kD().get()) + .withKA(V3_PootIntakeConstants.PIVOT_GAINS.kA().get()) + .withKV(V3_PootIntakeConstants.PIVOT_GAINS.kV().get()) + .withKS(V3_PootIntakeConstants.PIVOT_GAINS.kS().get()) + .withKG(V3_PootIntakeConstants.PIVOT_GAINS.kG().get()); pivotConfig.MotionMagic = new MotionMagicConfigs() .withMotionMagicCruiseVelocity( AngularVelocity.ofRelativeUnits( - V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS + V3_PootIntakeConstants.PIVOT_CONSTRAINTS .CRUISING_VELOCITY_RADIANS_PER_SECOND() .get(), RadiansPerSecond)) .withMotionMagicAcceleration( AngularAcceleration.ofRelativeUnits( - V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS + V3_PootIntakeConstants.PIVOT_CONSTRAINTS .MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED() .get(), RadiansPerSecondPerSecond)); @@ -145,24 +145,24 @@ public V3_EpsilonIntakeIOTalonFX() { rollerInnerConfig = new TalonFXConfiguration(); rollerInnerConfig.CurrentLimits.SupplyCurrentLimitEnable = true; rollerInnerConfig.CurrentLimits.SupplyCurrentLimit = - V3_EpsilonIntakeConstants.CURRENT_LIMITS.INNER_ROLLER_SUPPLY_CURRENT_LIMIT(); + V3_PootIntakeConstants.CURRENT_LIMITS.INNER_ROLLER_SUPPLY_CURRENT_LIMIT(); rollerInnerConfig.CurrentLimits.StatorCurrentLimitEnable = true; rollerInnerConfig.CurrentLimits.StatorCurrentLimit = - V3_EpsilonIntakeConstants.CURRENT_LIMITS.INNER_ROLLER_STATOR_CURRENT_LIMIT(); + V3_PootIntakeConstants.CURRENT_LIMITS.INNER_ROLLER_STATOR_CURRENT_LIMIT(); rollerInnerConfig.Feedback.SensorToMechanismRatio = - V3_EpsilonIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO(); + V3_PootIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO(); rollerInnerConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; rollerInnerConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; rollerOuterConfig = new TalonFXConfiguration(); rollerOuterConfig.CurrentLimits.SupplyCurrentLimitEnable = true; rollerOuterConfig.CurrentLimits.SupplyCurrentLimit = - V3_EpsilonIntakeConstants.CURRENT_LIMITS.OUTER_ROLLER_SUPPLY_CURRENT_LIMIT(); + V3_PootIntakeConstants.CURRENT_LIMITS.OUTER_ROLLER_SUPPLY_CURRENT_LIMIT(); rollerOuterConfig.CurrentLimits.StatorCurrentLimitEnable = true; rollerOuterConfig.CurrentLimits.StatorCurrentLimit = - V3_EpsilonIntakeConstants.CURRENT_LIMITS.OUTER_ROLLER_STATOR_CURRENT_LIMIT(); + V3_PootIntakeConstants.CURRENT_LIMITS.OUTER_ROLLER_STATOR_CURRENT_LIMIT(); rollerOuterConfig.Feedback.SensorToMechanismRatio = - V3_EpsilonIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO(); + V3_PootIntakeConstants.ROLLER_PARAMS.PIVOT_GEAR_RATIO(); rollerOuterConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; rollerOuterConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; @@ -185,7 +185,7 @@ public V3_EpsilonIntakeIOTalonFX() { pivotVoltageRequest = new VoltageOut(0); pivotMotionMagicRequest = - new MotionMagicVoltage(V3_EpsilonIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getMeasure()); + new MotionMagicVoltage(V3_PootIntakeConstants.PIVOT_PARAMS.MIN_ANGLE().getMeasure()); rollerInnerVoltageRequest = new VoltageOut(0); rollerOuterVoltageRequest = new VoltageOut(0); @@ -241,7 +241,7 @@ public V3_EpsilonIntakeIOTalonFX() { * @param inputs The inputs of the subsystem. */ @Override - public void updateInputs(V3_EpsilonIntakeIOInputs inputs) { + public void updateInputs(V3_PootIntakeIOInputs inputs) { inputs.pivotPosition = new Rotation2d(pivotPositionRotations.getValue()); inputs.pivotVelocityRadiansPerSecond = pivotVelocityRotationsPerSecond.getValue().in(RadiansPerSecond); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/manipulator/V3_PootManipulator.java similarity index 89% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java rename to src/main/java/frc/robot/subsystems/v3_Poot/superstructure/manipulator/V3_PootManipulator.java index 756951b9..c7d4c339 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulator.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/manipulator/V3_PootManipulator.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; +package frc.robot.subsystems.v3_Poot.superstructure.manipulator; import static edu.wpi.first.units.Units.*; @@ -11,17 +11,17 @@ import frc.robot.RobotState; import frc.robot.RobotState.ScoreSide; import frc.robot.subsystems.shared.elevator.Elevator.ElevatorFSM; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructure; -import frc.robot.subsystems.v3_Epsilon.superstructure.V3_EpsilonSuperstructureStates; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorArmState; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants.ManipulatorRollerState; +import frc.robot.subsystems.v3_Poot.superstructure.V3_PootSuperstructure; +import frc.robot.subsystems.v3_Poot.superstructure.V3_PootSuperstructureStates; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulatorConstants.ManipulatorArmState; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulatorConstants.ManipulatorRollerState; import java.util.Set; import lombok.Getter; import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; -public class V3_EpsilonManipulator { - private final V3_EpsilonManipulatorIO io; +public class V3_PootManipulator { + private final V3_PootManipulatorIO io; private final ManipulatorIOInputsAutoLogged inputs; @AutoLogOutput(key = "Manipulator/Arm Goal") @@ -36,7 +36,7 @@ public class V3_EpsilonManipulator { Set algaeStates; - public V3_EpsilonManipulator(V3_EpsilonManipulatorIO io) { + public V3_PootManipulator(V3_PootManipulatorIO io) { this.io = io; inputs = new ManipulatorIOInputsAutoLogged(); @@ -211,7 +211,7 @@ public boolean armAtGoal() { public boolean armAtGoal(Rotation2d state) { return Math.abs(inputs.armPosition.minus(state).getRadians()) - <= V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); + <= V3_PootManipulatorConstants.CONSTRAINTS.goalToleranceRadians().get(); } public boolean armInTolerance(Rotation2d tolerance) { @@ -264,7 +264,7 @@ public void setSlot() { * @param superstructure The V3 Epsiolon Superstructure. * @return A command to run the SysId routine for the manipulator arm. */ - public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure, ElevatorFSM elevator) { + public Command sysIdRoutine(V3_PootSuperstructure superstructure, ElevatorFSM elevator) { SysIdRoutine algaeCharacterizationRoutine = new SysIdRoutine( new SysIdRoutine.Config( @@ -275,7 +275,7 @@ public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure, ElevatorFSM new SysIdRoutine.Mechanism( (volts) -> io.setArmVoltage(volts.in(Volts)), null, superstructure)); return Commands.sequence( - superstructure.runGoal(V3_EpsilonSuperstructureStates.OVERRIDE), + superstructure.runGoal(V3_PootSuperstructureStates.OVERRIDE), Commands.runOnce(() -> elevator.setPosition(() -> ReefState.L4)), Commands.runOnce(() -> isClosedLoop = false), algaeCharacterizationRoutine.quasistatic(Direction.kForward), @@ -292,7 +292,7 @@ public Command sysIdRoutine(V3_EpsilonSuperstructure superstructure, ElevatorFSM * * @param state The state to set the arm to. */ - public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmState state) { + public void setManipulatorState(V3_PootManipulatorConstants.ManipulatorArmState state) { io.setManipulatorState(state); } @@ -303,13 +303,13 @@ public void setManipulatorState(V3_EpsilonManipulatorConstants.ManipulatorArmSta * * @param rollerGoal The desired state of the roller. */ - public void setRollerGoal(V3_EpsilonManipulatorConstants.ManipulatorRollerState rollerGoal) { + public void setRollerGoal(V3_PootManipulatorConstants.ManipulatorRollerState rollerGoal) { this.rollerGoal = rollerGoal; if ((hasAlgae() || hasCoral()) && Set.of( - V3_EpsilonManipulatorConstants.ManipulatorRollerState.ALGAE_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerState.CORAL_INTAKE, - V3_EpsilonManipulatorConstants.ManipulatorRollerState.STOP) + V3_PootManipulatorConstants.ManipulatorRollerState.ALGAE_INTAKE, + V3_PootManipulatorConstants.ManipulatorRollerState.CORAL_INTAKE, + V3_PootManipulatorConstants.ManipulatorRollerState.STOP) .contains(rollerGoal)) { io.setRollerVoltage(holdVoltage()); diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/manipulator/V3_PootManipulatorConstants.java similarity index 98% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java rename to src/main/java/frc/robot/subsystems/v3_Poot/superstructure/manipulator/V3_PootManipulatorConstants.java index 83367342..db0f938a 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorConstants.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/manipulator/V3_PootManipulatorConstants.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; +package frc.robot.subsystems.v3_Poot.superstructure.manipulator; import com.ctre.phoenix6.configs.SlotConfigs; import com.ctre.phoenix6.signals.GravityTypeValue; @@ -11,7 +11,7 @@ import frc.robot.util.LoggedTunableNumber; import lombok.RequiredArgsConstructor; -public final class V3_EpsilonManipulatorConstants { +public final class V3_PootManipulatorConstants { public static final ArmParameters ARM_PARAMETERS; public static final Gains EMPTY_GAINS; @@ -58,7 +58,7 @@ public final class V3_EpsilonManipulatorConstants { new LoggedTunableNumber("Manipulator/L1 Volts", 3.5 * 1.56)); switch (Constants.ROBOT) { - case V3_EPSILON: + case V3_POOT: EMPTY_GAINS = new Gains( new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 100), @@ -91,7 +91,7 @@ public final class V3_EpsilonManipulatorConstants { "Manipulator/Arm/GoalTolerance", Units.degreesToRadians(3))); CURRENT_LIMITS = new ManipulatorCurrentLimits(40, 20, 40, 20); break; - case V3_EPSILON_SIM: + case V3_POOT_SIM: EMPTY_GAINS = new Gains( new LoggedTunableNumber("Manipulator/Arm/Empty/kP", 100), diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/manipulator/V3_PootManipulatorIO.java similarity index 91% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java rename to src/main/java/frc/robot/subsystems/v3_Poot/superstructure/manipulator/V3_PootManipulatorIO.java index c61a5357..6fdf83eb 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIO.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/manipulator/V3_PootManipulatorIO.java @@ -1,9 +1,9 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; +package frc.robot.subsystems.v3_Poot.superstructure.manipulator; import edu.wpi.first.math.geometry.Rotation2d; import org.littletonrobotics.junction.AutoLog; -public interface V3_EpsilonManipulatorIO { +public interface V3_PootManipulatorIO { @AutoLog public static class ManipulatorIOInputs { @@ -48,8 +48,7 @@ public default void setRollerVoltage(double volts) {} public default void setArmGoal(Rotation2d rotation) {} - public default void setManipulatorState( - V3_EpsilonManipulatorConstants.ManipulatorArmState state) {} + public default void setManipulatorState(V3_PootManipulatorConstants.ManipulatorArmState state) {} /** * Sets the gains for the arm. diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/manipulator/V3_PootManipulatorIOSim.java similarity index 70% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java rename to src/main/java/frc/robot/subsystems/v3_Poot/superstructure/manipulator/V3_PootManipulatorIOSim.java index 4d5c572a..fca303bf 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOSim.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/manipulator/V3_PootManipulatorIOSim.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; +package frc.robot.subsystems.v3_Poot.superstructure.manipulator; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.ArmFeedforward; @@ -11,7 +11,7 @@ import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim; import frc.robot.Constants; -public class V3_EpsilonManipulatorIOSim implements V3_EpsilonManipulatorIO { +public class V3_PootManipulatorIOSim implements V3_PootManipulatorIO { private final SingleJointedArmSim armMotorSim; private final DCMotorSim rollerMotorSim; @@ -27,16 +27,16 @@ public class V3_EpsilonManipulatorIOSim implements V3_EpsilonManipulatorIO { private boolean isClosedLoop; - public V3_EpsilonManipulatorIOSim() { + public V3_PootManipulatorIOSim() { armMotorSim = new SingleJointedArmSim( LinearSystemId.createSingleJointedArmSystem( - V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MOTOR_CONFIG(), + V3_PootManipulatorConstants.ARM_PARAMETERS.MOTOR_CONFIG(), 0.4389150229, - V3_EpsilonManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO()), - V3_EpsilonManipulatorConstants.ARM_PARAMETERS.MOTOR_CONFIG(), - V3_EpsilonManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO(), - V3_EpsilonManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS(), + V3_PootManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO()), + V3_PootManipulatorConstants.ARM_PARAMETERS.MOTOR_CONFIG(), + V3_PootManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO(), + V3_PootManipulatorConstants.ARM_PARAMETERS.LENGTH_METERS(), Double.NEGATIVE_INFINITY, Double.POSITIVE_INFINITY, true, @@ -48,49 +48,47 @@ public V3_EpsilonManipulatorIOSim() { slot0 = new double[] { - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kP().get(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kD().get(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kS().get(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kV().get(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kA().get(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kG().get() + V3_PootManipulatorConstants.EMPTY_GAINS.kP().get(), + V3_PootManipulatorConstants.EMPTY_GAINS.kD().get(), + V3_PootManipulatorConstants.EMPTY_GAINS.kS().get(), + V3_PootManipulatorConstants.EMPTY_GAINS.kV().get(), + V3_PootManipulatorConstants.EMPTY_GAINS.kA().get(), + V3_PootManipulatorConstants.EMPTY_GAINS.kG().get() }; slot1 = new double[] { - V3_EpsilonManipulatorConstants.CORAL_GAINS.kP().get(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kD().get(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kS().get(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kV().get(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kA().get(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kG().get() + V3_PootManipulatorConstants.CORAL_GAINS.kP().get(), + V3_PootManipulatorConstants.CORAL_GAINS.kD().get(), + V3_PootManipulatorConstants.CORAL_GAINS.kS().get(), + V3_PootManipulatorConstants.CORAL_GAINS.kV().get(), + V3_PootManipulatorConstants.CORAL_GAINS.kA().get(), + V3_PootManipulatorConstants.CORAL_GAINS.kG().get() }; slot2 = new double[] { - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kP().get(), - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kD().get(), - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kS().get(), - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kV().get(), - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kA().get(), - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kG().get() + V3_PootManipulatorConstants.ALGAE_GAINS.kP().get(), + V3_PootManipulatorConstants.ALGAE_GAINS.kD().get(), + V3_PootManipulatorConstants.ALGAE_GAINS.kS().get(), + V3_PootManipulatorConstants.ALGAE_GAINS.kV().get(), + V3_PootManipulatorConstants.ALGAE_GAINS.kA().get(), + V3_PootManipulatorConstants.ALGAE_GAINS.kG().get() }; armFeedbackController = new ProfiledPIDController( - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kP().get(), + V3_PootManipulatorConstants.EMPTY_GAINS.kP().get(), 0.0, - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kD().get(), + V3_PootManipulatorConstants.EMPTY_GAINS.kD().get(), new Constraints( - V3_EpsilonManipulatorConstants.CONSTRAINTS - .cruisingVelocityRotationsPerSecond() - .get(), - V3_EpsilonManipulatorConstants.CONSTRAINTS + V3_PootManipulatorConstants.CONSTRAINTS.cruisingVelocityRotationsPerSecond().get(), + V3_PootManipulatorConstants.CONSTRAINTS .maxAccelerationRotationsPerSecondSquared() .get())); armFeedforwardController = new ArmFeedforward( - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kS().get(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kG().get(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kV().get(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kA().get()); + V3_PootManipulatorConstants.EMPTY_GAINS.kS().get(), + V3_PootManipulatorConstants.EMPTY_GAINS.kG().get(), + V3_PootManipulatorConstants.EMPTY_GAINS.kV().get(), + V3_PootManipulatorConstants.EMPTY_GAINS.kA().get()); armFeedbackController.enableContinuousInput( -Math.PI, Math.PI); // Wrap around at -180 and 180 degrees diff --git a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/manipulator/V3_PootManipulatorIOTalonFX.java similarity index 91% rename from src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java rename to src/main/java/frc/robot/subsystems/v3_Poot/superstructure/manipulator/V3_PootManipulatorIOTalonFX.java index c49bc314..7d803533 100644 --- a/src/main/java/frc/robot/subsystems/v3_Epsilon/superstructure/manipulator/V3_EpsilonManipulatorIOTalonFX.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/manipulator/V3_PootManipulatorIOTalonFX.java @@ -1,4 +1,4 @@ -package frc.robot.subsystems.v3_Epsilon.superstructure.manipulator; +package frc.robot.subsystems.v3_Poot.superstructure.manipulator; import static edu.wpi.first.units.Units.RadiansPerSecond; import static edu.wpi.first.units.Units.RotationsPerSecond; @@ -30,7 +30,7 @@ import frc.robot.util.PhoenixUtil; import java.util.ArrayList; -public class V3_EpsilonManipulatorIOTalonFX implements V3_EpsilonManipulatorIO { +public class V3_PootManipulatorIOTalonFX implements V3_PootManipulatorIO { private final TalonFX armTalonFX; private final StatusSignal armPositionRotations; @@ -63,41 +63,41 @@ public class V3_EpsilonManipulatorIOTalonFX implements V3_EpsilonManipulatorIO { private final CANrange canRange; private final StatusSignal isDetected; - public V3_EpsilonManipulatorIOTalonFX() { - armTalonFX = new TalonFX(V3_EpsilonManipulatorConstants.ARM_CAN_ID); - rollerTalonFX = new TalonFX(V3_EpsilonManipulatorConstants.ROLLER_CAN_ID); - canRange = new CANrange(V3_EpsilonManipulatorConstants.CAN_RANGE_ID); + public V3_PootManipulatorIOTalonFX() { + armTalonFX = new TalonFX(V3_PootManipulatorConstants.ARM_CAN_ID); + rollerTalonFX = new TalonFX(V3_PootManipulatorConstants.ROLLER_CAN_ID); + canRange = new CANrange(V3_PootManipulatorConstants.CAN_RANGE_ID); armConfig = new TalonFXConfiguration(); armConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; armConfig.CurrentLimits.SupplyCurrentLimit = - V3_EpsilonManipulatorConstants.CURRENT_LIMITS.MANIPULATOR_SUPPLY_CURRENT_LIMIT(); + V3_PootManipulatorConstants.CURRENT_LIMITS.MANIPULATOR_SUPPLY_CURRENT_LIMIT(); armConfig.CurrentLimits.SupplyCurrentLimitEnable = true; armConfig.CurrentLimits.StatorCurrentLimit = - V3_EpsilonManipulatorConstants.CURRENT_LIMITS.MANIPULATOR_STATOR_CURRENT_LIMIT(); + V3_PootManipulatorConstants.CURRENT_LIMITS.MANIPULATOR_STATOR_CURRENT_LIMIT(); armConfig.CurrentLimits.StatorCurrentLimitEnable = true; armConfig.Feedback.SensorToMechanismRatio = - V3_EpsilonManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO(); + V3_PootManipulatorConstants.ARM_PARAMETERS.GEAR_RATIO(); armConfig.Slot0 = - Slot0Configs.from(V3_EpsilonManipulatorConstants.EMPTY_GAINS.toTalonFXSlotConfigs()); + Slot0Configs.from(V3_PootManipulatorConstants.EMPTY_GAINS.toTalonFXSlotConfigs()); armConfig.Slot1 = - Slot1Configs.from(V3_EpsilonManipulatorConstants.CORAL_GAINS.toTalonFXSlotConfigs()); + Slot1Configs.from(V3_PootManipulatorConstants.CORAL_GAINS.toTalonFXSlotConfigs()); armConfig.Slot2 = - Slot2Configs.from(V3_EpsilonManipulatorConstants.ALGAE_GAINS.toTalonFXSlotConfigs()); + Slot2Configs.from(V3_PootManipulatorConstants.ALGAE_GAINS.toTalonFXSlotConfigs()); armConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; armConfig.ClosedLoopGeneral.ContinuousWrap = true; armConfig.MotionMagic = new MotionMagicConfigs() .withMotionMagicAcceleration( AngularAcceleration.ofRelativeUnits( - V3_EpsilonManipulatorConstants.CONSTRAINTS + V3_PootManipulatorConstants.CONSTRAINTS .maxAccelerationRotationsPerSecondSquared() .get(), RotationsPerSecondPerSecond)) .withMotionMagicCruiseVelocity( AngularVelocity.ofRelativeUnits( - V3_EpsilonManipulatorConstants.CONSTRAINTS + V3_PootManipulatorConstants.CONSTRAINTS .cruisingVelocityRotationsPerSecond() .get(), RotationsPerSecond)); @@ -117,7 +117,7 @@ public V3_EpsilonManipulatorIOTalonFX() { rollerConfig = new TalonFXConfiguration(); rollerConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake; rollerConfig.CurrentLimits.SupplyCurrentLimit = - V3_EpsilonManipulatorConstants.CURRENT_LIMITS.ROLLER_SUPPLY_CURRENT_LIMIT(); + V3_PootManipulatorConstants.CURRENT_LIMITS.ROLLER_SUPPLY_CURRENT_LIMIT(); rollerConfig.CurrentLimits.SupplyCurrentLimitEnable = true; tryUntilOk(5, () -> rollerTalonFX.getConfigurator().apply(rollerConfig, 0.25)); diff --git a/src/main/java/frc/robot/util/LTNUpdater.java b/src/main/java/frc/robot/util/LTNUpdater.java index d7c24b50..5aaaabc1 100644 --- a/src/main/java/frc/robot/util/LTNUpdater.java +++ b/src/main/java/frc/robot/util/LTNUpdater.java @@ -13,10 +13,10 @@ import frc.robot.subsystems.v2_Redundancy.superstructure.intake.V2_RedundancyIntakeConstants; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulator; import frc.robot.subsystems.v2_Redundancy.superstructure.manipulator.V2_RedundancyManipulatorConstants; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntake; -import frc.robot.subsystems.v3_Epsilon.superstructure.intake.V3_EpsilonIntakeConstants; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulator; -import frc.robot.subsystems.v3_Epsilon.superstructure.manipulator.V3_EpsilonManipulatorConstants; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntake; +import frc.robot.subsystems.v3_Poot.superstructure.intake.V3_PootIntakeConstants; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulator; +import frc.robot.subsystems.v3_Poot.superstructure.manipulator.V3_PootManipulatorConstants; public class LTNUpdater { @@ -209,85 +209,83 @@ public static void registerIntake(V2_RedundancyIntake intake) { V2_RedundancyIntakeConstants.EXTENSION_MOTOR_CONSTRAINTS.MAX_VELOCITY()); } - public static void registerIntake(V3_EpsilonIntake intake) { + public static void registerIntake(V3_PootIntake intake) { LoggedTunableNumber.createGroup( () -> { intake.updateIntakeGains( - V3_EpsilonIntakeConstants.PIVOT_GAINS.kP().get(), - V3_EpsilonIntakeConstants.PIVOT_GAINS.kD().get(), - V3_EpsilonIntakeConstants.PIVOT_GAINS.kS().get(), - V3_EpsilonIntakeConstants.PIVOT_GAINS.kV().get(), - V3_EpsilonIntakeConstants.PIVOT_GAINS.kA().get(), - V3_EpsilonIntakeConstants.PIVOT_GAINS.kG().get()); + V3_PootIntakeConstants.PIVOT_GAINS.kP().get(), + V3_PootIntakeConstants.PIVOT_GAINS.kD().get(), + V3_PootIntakeConstants.PIVOT_GAINS.kS().get(), + V3_PootIntakeConstants.PIVOT_GAINS.kV().get(), + V3_PootIntakeConstants.PIVOT_GAINS.kA().get(), + V3_PootIntakeConstants.PIVOT_GAINS.kG().get()); intake.updateIntakeConstraints( - V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS + V3_PootIntakeConstants.PIVOT_CONSTRAINTS .MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED() .get(), - V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS + V3_PootIntakeConstants.PIVOT_CONSTRAINTS .CRUISING_VELOCITY_RADIANS_PER_SECOND() .get()); }, - V3_EpsilonIntakeConstants.PIVOT_GAINS.kP(), - V3_EpsilonIntakeConstants.PIVOT_GAINS.kD(), - V3_EpsilonIntakeConstants.PIVOT_GAINS.kS(), - V3_EpsilonIntakeConstants.PIVOT_GAINS.kV(), - V3_EpsilonIntakeConstants.PIVOT_GAINS.kA(), - V3_EpsilonIntakeConstants.PIVOT_GAINS.kG(), - V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED(), - V3_EpsilonIntakeConstants.PIVOT_CONSTRAINTS.CRUISING_VELOCITY_RADIANS_PER_SECOND()); + V3_PootIntakeConstants.PIVOT_GAINS.kP(), + V3_PootIntakeConstants.PIVOT_GAINS.kD(), + V3_PootIntakeConstants.PIVOT_GAINS.kS(), + V3_PootIntakeConstants.PIVOT_GAINS.kV(), + V3_PootIntakeConstants.PIVOT_GAINS.kA(), + V3_PootIntakeConstants.PIVOT_GAINS.kG(), + V3_PootIntakeConstants.PIVOT_CONSTRAINTS.MAX_ACCELERATION_RADIANS_PER_SECOND_SQUARED(), + V3_PootIntakeConstants.PIVOT_CONSTRAINTS.CRUISING_VELOCITY_RADIANS_PER_SECOND()); } - public static void registerManipulatorArm(V3_EpsilonManipulator manipulator) { + public static void registerManipulatorArm(V3_PootManipulator manipulator) { LoggedTunableNumber.createGroup( () -> { manipulator.updateArmGains( - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kP().get(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kD().get(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kS().get(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kV().get(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kA().get(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kG().get(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kP().get(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kD().get(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kS().get(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kV().get(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kA().get(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kG().get(), - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kP().get(), - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kD().get(), - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kS().get(), - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kV().get(), - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kA().get(), - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kG().get()); + V3_PootManipulatorConstants.EMPTY_GAINS.kP().get(), + V3_PootManipulatorConstants.EMPTY_GAINS.kD().get(), + V3_PootManipulatorConstants.EMPTY_GAINS.kS().get(), + V3_PootManipulatorConstants.EMPTY_GAINS.kV().get(), + V3_PootManipulatorConstants.EMPTY_GAINS.kA().get(), + V3_PootManipulatorConstants.EMPTY_GAINS.kG().get(), + V3_PootManipulatorConstants.CORAL_GAINS.kP().get(), + V3_PootManipulatorConstants.CORAL_GAINS.kD().get(), + V3_PootManipulatorConstants.CORAL_GAINS.kS().get(), + V3_PootManipulatorConstants.CORAL_GAINS.kV().get(), + V3_PootManipulatorConstants.CORAL_GAINS.kA().get(), + V3_PootManipulatorConstants.CORAL_GAINS.kG().get(), + V3_PootManipulatorConstants.ALGAE_GAINS.kP().get(), + V3_PootManipulatorConstants.ALGAE_GAINS.kD().get(), + V3_PootManipulatorConstants.ALGAE_GAINS.kS().get(), + V3_PootManipulatorConstants.ALGAE_GAINS.kV().get(), + V3_PootManipulatorConstants.ALGAE_GAINS.kA().get(), + V3_PootManipulatorConstants.ALGAE_GAINS.kG().get()); manipulator.updateArmConstraints( - V3_EpsilonManipulatorConstants.CONSTRAINTS + V3_PootManipulatorConstants.CONSTRAINTS .maxAccelerationRotationsPerSecondSquared() .get(), - V3_EpsilonManipulatorConstants.CONSTRAINTS - .cruisingVelocityRotationsPerSecond() - .get()); + V3_PootManipulatorConstants.CONSTRAINTS.cruisingVelocityRotationsPerSecond().get()); }, - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kP(), - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kD(), - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kS(), - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kV(), - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kA(), - V3_EpsilonManipulatorConstants.ALGAE_GAINS.kG(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kP(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kD(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kS(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kV(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kA(), - V3_EpsilonManipulatorConstants.EMPTY_GAINS.kG(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kP(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kD(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kS(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kV(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kA(), - V3_EpsilonManipulatorConstants.CORAL_GAINS.kG(), - V3_EpsilonManipulatorConstants.CONSTRAINTS.maxAccelerationRotationsPerSecondSquared(), - V3_EpsilonManipulatorConstants.CONSTRAINTS.cruisingVelocityRotationsPerSecond(), - V3_EpsilonManipulatorConstants.CONSTRAINTS.goalToleranceRadians()); + V3_PootManipulatorConstants.ALGAE_GAINS.kP(), + V3_PootManipulatorConstants.ALGAE_GAINS.kD(), + V3_PootManipulatorConstants.ALGAE_GAINS.kS(), + V3_PootManipulatorConstants.ALGAE_GAINS.kV(), + V3_PootManipulatorConstants.ALGAE_GAINS.kA(), + V3_PootManipulatorConstants.ALGAE_GAINS.kG(), + V3_PootManipulatorConstants.EMPTY_GAINS.kP(), + V3_PootManipulatorConstants.EMPTY_GAINS.kD(), + V3_PootManipulatorConstants.EMPTY_GAINS.kS(), + V3_PootManipulatorConstants.EMPTY_GAINS.kV(), + V3_PootManipulatorConstants.EMPTY_GAINS.kA(), + V3_PootManipulatorConstants.EMPTY_GAINS.kG(), + V3_PootManipulatorConstants.CORAL_GAINS.kP(), + V3_PootManipulatorConstants.CORAL_GAINS.kD(), + V3_PootManipulatorConstants.CORAL_GAINS.kS(), + V3_PootManipulatorConstants.CORAL_GAINS.kV(), + V3_PootManipulatorConstants.CORAL_GAINS.kA(), + V3_PootManipulatorConstants.CORAL_GAINS.kG(), + V3_PootManipulatorConstants.CONSTRAINTS.maxAccelerationRotationsPerSecondSquared(), + V3_PootManipulatorConstants.CONSTRAINTS.cruisingVelocityRotationsPerSecond(), + V3_PootManipulatorConstants.CONSTRAINTS.goalToleranceRadians()); } /** @@ -314,10 +312,7 @@ public static void registerAll( } public static void registerAll( - Drive drive, - ElevatorFSM elevator, - V3_EpsilonIntake intake, - V3_EpsilonManipulator manipulator) { + Drive drive, ElevatorFSM elevator, V3_PootIntake intake, V3_PootManipulator manipulator) { registerDrive(drive); registerElevator(elevator); registerIntake(intake); From ae45e84082d7ccb6d559b6afde5c1379f2be7cf2 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Mon, 24 Nov 2025 14:19:51 -0500 Subject: [PATCH 173/180] update to poot --- src/main/deploy/{v3_epsilon => v3_poot}/Superstructure.dot | 0 src/main/deploy/{v3_epsilon => v3_poot}/choreo/Choreo.chor | 0 .../deploy/{v3_epsilon => v3_poot}/choreo/E_RIGHT_PATH_1.traj | 0 .../{v3_epsilon => v3_poot}/choreo/E_RIGHT_PATH_1_BACK.traj | 0 .../deploy/{v3_epsilon => v3_poot}/choreo/E_RIGHT_PATH_2.traj | 0 .../{v3_epsilon => v3_poot}/choreo/E_RIGHT_PATH_2_BACK.traj | 0 .../deploy/{v3_epsilon => v3_poot}/choreo/E_RIGHT_PATH_3.traj | 0 .../{v3_epsilon => v3_poot}/choreo/E_RIGHT_PATH_3_BACK.traj | 0 .../deploy/{v3_epsilon => v3_poot}/choreo/E_RIGHT_PATH_4.traj | 0 .../{v3_epsilon => v3_poot}/choreo/E_RIGHT_PATH_4_BACK.traj | 0 src/main/deploy/{v3_epsilon => v3_poot}/choreo/F_PATH_1.traj | 0 src/main/deploy/{v3_epsilon => v3_poot}/choreo/F_PATH_2.traj | 0 src/main/deploy/{v3_epsilon => v3_poot}/choreo/F_PATH_3.traj | 0 src/main/deploy/{v3_epsilon => v3_poot}/choreo/F_PATH_4.traj | 0 src/main/deploy/{v3_epsilon => v3_poot}/choreo/F_PATH_5.traj | 0 src/main/java/frc/robot/RobotState.java | 4 ++-- .../v3_Poot/superstructure/V3_PootSuperstructureEdges.java | 2 +- 17 files changed, 3 insertions(+), 3 deletions(-) rename src/main/deploy/{v3_epsilon => v3_poot}/Superstructure.dot (100%) rename src/main/deploy/{v3_epsilon => v3_poot}/choreo/Choreo.chor (100%) rename src/main/deploy/{v3_epsilon => v3_poot}/choreo/E_RIGHT_PATH_1.traj (100%) rename src/main/deploy/{v3_epsilon => v3_poot}/choreo/E_RIGHT_PATH_1_BACK.traj (100%) rename src/main/deploy/{v3_epsilon => v3_poot}/choreo/E_RIGHT_PATH_2.traj (100%) rename src/main/deploy/{v3_epsilon => v3_poot}/choreo/E_RIGHT_PATH_2_BACK.traj (100%) rename src/main/deploy/{v3_epsilon => v3_poot}/choreo/E_RIGHT_PATH_3.traj (100%) rename src/main/deploy/{v3_epsilon => v3_poot}/choreo/E_RIGHT_PATH_3_BACK.traj (100%) rename src/main/deploy/{v3_epsilon => v3_poot}/choreo/E_RIGHT_PATH_4.traj (100%) rename src/main/deploy/{v3_epsilon => v3_poot}/choreo/E_RIGHT_PATH_4_BACK.traj (100%) rename src/main/deploy/{v3_epsilon => v3_poot}/choreo/F_PATH_1.traj (100%) rename src/main/deploy/{v3_epsilon => v3_poot}/choreo/F_PATH_2.traj (100%) rename src/main/deploy/{v3_epsilon => v3_poot}/choreo/F_PATH_3.traj (100%) rename src/main/deploy/{v3_epsilon => v3_poot}/choreo/F_PATH_4.traj (100%) rename src/main/deploy/{v3_epsilon => v3_poot}/choreo/F_PATH_5.traj (100%) diff --git a/src/main/deploy/v3_epsilon/Superstructure.dot b/src/main/deploy/v3_poot/Superstructure.dot similarity index 100% rename from src/main/deploy/v3_epsilon/Superstructure.dot rename to src/main/deploy/v3_poot/Superstructure.dot diff --git a/src/main/deploy/v3_epsilon/choreo/Choreo.chor b/src/main/deploy/v3_poot/choreo/Choreo.chor similarity index 100% rename from src/main/deploy/v3_epsilon/choreo/Choreo.chor rename to src/main/deploy/v3_poot/choreo/Choreo.chor diff --git a/src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_1.traj b/src/main/deploy/v3_poot/choreo/E_RIGHT_PATH_1.traj similarity index 100% rename from src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_1.traj rename to src/main/deploy/v3_poot/choreo/E_RIGHT_PATH_1.traj diff --git a/src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_1_BACK.traj b/src/main/deploy/v3_poot/choreo/E_RIGHT_PATH_1_BACK.traj similarity index 100% rename from src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_1_BACK.traj rename to src/main/deploy/v3_poot/choreo/E_RIGHT_PATH_1_BACK.traj diff --git a/src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_2.traj b/src/main/deploy/v3_poot/choreo/E_RIGHT_PATH_2.traj similarity index 100% rename from src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_2.traj rename to src/main/deploy/v3_poot/choreo/E_RIGHT_PATH_2.traj diff --git a/src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_2_BACK.traj b/src/main/deploy/v3_poot/choreo/E_RIGHT_PATH_2_BACK.traj similarity index 100% rename from src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_2_BACK.traj rename to src/main/deploy/v3_poot/choreo/E_RIGHT_PATH_2_BACK.traj diff --git a/src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_3.traj b/src/main/deploy/v3_poot/choreo/E_RIGHT_PATH_3.traj similarity index 100% rename from src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_3.traj rename to src/main/deploy/v3_poot/choreo/E_RIGHT_PATH_3.traj diff --git a/src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_3_BACK.traj b/src/main/deploy/v3_poot/choreo/E_RIGHT_PATH_3_BACK.traj similarity index 100% rename from src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_3_BACK.traj rename to src/main/deploy/v3_poot/choreo/E_RIGHT_PATH_3_BACK.traj diff --git a/src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_4.traj b/src/main/deploy/v3_poot/choreo/E_RIGHT_PATH_4.traj similarity index 100% rename from src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_4.traj rename to src/main/deploy/v3_poot/choreo/E_RIGHT_PATH_4.traj diff --git a/src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_4_BACK.traj b/src/main/deploy/v3_poot/choreo/E_RIGHT_PATH_4_BACK.traj similarity index 100% rename from src/main/deploy/v3_epsilon/choreo/E_RIGHT_PATH_4_BACK.traj rename to src/main/deploy/v3_poot/choreo/E_RIGHT_PATH_4_BACK.traj diff --git a/src/main/deploy/v3_epsilon/choreo/F_PATH_1.traj b/src/main/deploy/v3_poot/choreo/F_PATH_1.traj similarity index 100% rename from src/main/deploy/v3_epsilon/choreo/F_PATH_1.traj rename to src/main/deploy/v3_poot/choreo/F_PATH_1.traj diff --git a/src/main/deploy/v3_epsilon/choreo/F_PATH_2.traj b/src/main/deploy/v3_poot/choreo/F_PATH_2.traj similarity index 100% rename from src/main/deploy/v3_epsilon/choreo/F_PATH_2.traj rename to src/main/deploy/v3_poot/choreo/F_PATH_2.traj diff --git a/src/main/deploy/v3_epsilon/choreo/F_PATH_3.traj b/src/main/deploy/v3_poot/choreo/F_PATH_3.traj similarity index 100% rename from src/main/deploy/v3_epsilon/choreo/F_PATH_3.traj rename to src/main/deploy/v3_poot/choreo/F_PATH_3.traj diff --git a/src/main/deploy/v3_epsilon/choreo/F_PATH_4.traj b/src/main/deploy/v3_poot/choreo/F_PATH_4.traj similarity index 100% rename from src/main/deploy/v3_epsilon/choreo/F_PATH_4.traj rename to src/main/deploy/v3_poot/choreo/F_PATH_4.traj diff --git a/src/main/deploy/v3_epsilon/choreo/F_PATH_5.traj b/src/main/deploy/v3_poot/choreo/F_PATH_5.traj similarity index 100% rename from src/main/deploy/v3_epsilon/choreo/F_PATH_5.traj rename to src/main/deploy/v3_poot/choreo/F_PATH_5.traj diff --git a/src/main/java/frc/robot/RobotState.java b/src/main/java/frc/robot/RobotState.java index 6e90bdc6..f2c1fc25 100644 --- a/src/main/java/frc/robot/RobotState.java +++ b/src/main/java/frc/robot/RobotState.java @@ -159,8 +159,8 @@ public static void periodic( Pose2d autoAlignCoralSetpoint = baseCoralSetpoint; if (OIData.currentReefHeight().equals(ReefState.L1) - || !Constants.RobotType.V3_EPSILON.equals(Constants.ROBOT) - || !Constants.RobotType.V3_EPSILON_SIM.equals(Constants.ROBOT)) { + || !Constants.RobotType.V3_POOT.equals(Constants.ROBOT) + || !Constants.RobotType.V3_POOT_SIM.equals(Constants.ROBOT)) { scoreSide = ScoreSide.CENTER; } else { diff --git a/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructureEdges.java b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructureEdges.java index 5fff4a1a..350371b7 100644 --- a/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructureEdges.java +++ b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/V3_PootSuperstructureEdges.java @@ -150,7 +150,7 @@ public static void addEdges( loadEdgesFromDot( Filesystem.getDeployDirectory() .toPath() - .resolve("v3_epsilon/" + "Superstructure.dot") + .resolve("v3_poot/" + "Superstructure.dot") .toString(), graph, elevator, From cf99b6456f7199f155a7b5ee01fe8e38b39c9a60 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Mon, 24 Nov 2025 14:23:30 -0500 Subject: [PATCH 174/180] gv stuff --- .../shared/vision/CameraIOGompeiVision.java | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shared/vision/CameraIOGompeiVision.java b/src/main/java/frc/robot/subsystems/shared/vision/CameraIOGompeiVision.java index 4079f509..adbd502e 100644 --- a/src/main/java/frc/robot/subsystems/shared/vision/CameraIOGompeiVision.java +++ b/src/main/java/frc/robot/subsystems/shared/vision/CameraIOGompeiVision.java @@ -7,12 +7,7 @@ import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Rotation3d; import edu.wpi.first.math.geometry.Transform2d; -import edu.wpi.first.networktables.BooleanSubscriber; -import edu.wpi.first.networktables.ConnectionInfo; -import edu.wpi.first.networktables.DoubleArraySubscriber; -import edu.wpi.first.networktables.NetworkTable; -import edu.wpi.first.networktables.NetworkTableInstance; -import edu.wpi.first.networktables.PubSubOption; +import edu.wpi.first.networktables.*; import edu.wpi.first.wpilibj.Timer; import frc.robot.FieldConstants; import frc.robot.RobotState; @@ -43,6 +38,7 @@ public class CameraIOGompeiVision implements CameraIO { private final DoubleArraySubscriber observationSubscriber; // private final IntegerSubscriber fpsAprilTagSubscriber; private final BooleanSubscriber cameraConnectedSubscriber; + private final DoubleSubscriber cameraUSBSpeedSubscriber; private final Map lastTagDetectionTimes; @@ -98,6 +94,7 @@ public CameraIOGompeiVision( PubSubOption.periodic(0.01)); // this.fpsAprilTagSubscriber = outputTable.getIntegerTopic("fps_apriltags").subscribe(0); this.cameraConnectedSubscriber = outputTable.getBooleanTopic("connected").subscribe(false); + this.cameraUSBSpeedSubscriber = outputTable.getDoubleTopic("usb_speed").subscribe(0.0); lastTagDetectionTimes = new HashMap<>(); @@ -236,9 +233,9 @@ public void updateInputs(CameraIOInputs inputs) { // --- Parse tag angle + distance data --- int tagEstimationDataEndIndex = switch ((int) values[0]) { - default -> 0; case 1 -> 8; case 2 -> 16; + default -> 0; }; int indexCounter = 0; @@ -344,11 +341,13 @@ public void updateInputs(CameraIOInputs inputs) { Logger.recordOutput( "Vision/Cameras/" + config.key() + "/Camera Connected", cameraConnectedSubscriber.get()); + Logger.recordOutput( + "Vision/Cameras/" + config.key() + "/USB Speed", cameraUSBSpeedSubscriber.get()); } @Override public boolean getIsConnected(CameraIOInputs inputs) { - return true; + return inputs.isConnected; } @Override From c5019778c213b9d068eb1345ab19a04bd7099680 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Mon, 24 Nov 2025 14:36:30 -0500 Subject: [PATCH 175/180] rm TrajectoryGenerator.java --- .../frc/robot/util/TrajectoryGenerator.java | 96 ------------------- 1 file changed, 96 deletions(-) delete mode 100644 src/main/java/frc/robot/util/TrajectoryGenerator.java diff --git a/src/main/java/frc/robot/util/TrajectoryGenerator.java b/src/main/java/frc/robot/util/TrajectoryGenerator.java deleted file mode 100644 index 0aa52f16..00000000 --- a/src/main/java/frc/robot/util/TrajectoryGenerator.java +++ /dev/null @@ -1,96 +0,0 @@ -package frc.robot.util; - -import edu.wpi.first.math.Matrix; -import edu.wpi.first.math.Nat; -import edu.wpi.first.math.numbers.N1; -import edu.wpi.first.math.numbers.N6; - -public class TrajectoryGenerator { - /** - * Generates the 6 coefficients for a quintic polynomial trajectory. - * - * @param x_i Initial position - * @param v_i Initial velocity - * @param a_i Initial acceleration - * @param x_f Final position - * @param v_f Final velocity - * @param a_f Final acceleration - * @param t_i Initial time - * @param t_f Final time - * @return A 6x1 column vector of the polynomial coefficients (c₀ to c₅). - */ - public static final Matrix generateQuinticTrajectory( - double x_i, - double v_i, - double a_i, - double x_f, - double v_f, - double a_f, - double t_i, - double t_f) { - Matrix A = - new Matrix<>( - Nat.N6(), - Nat.N6(), - new double[] { - 1, - t_i, - Math.pow(t_i, 2), - Math.pow(t_i, 3), - Math.pow(t_i, 4), - Math.pow(t_i, 5), - 0, - 1, - 2 * t_i, - 3 * Math.pow(t_i, 2), - 4 * Math.pow(t_i, 3), - 5 * Math.pow(t_i, 4), - 0, - 0, - 2, - 6 * t_i, - 12 * Math.pow(t_i, 2), - 20 * Math.pow(t_i, 3), - 1, - t_f, - Math.pow(t_f, 2), - Math.pow(t_f, 3), - Math.pow(t_f, 4), - Math.pow(t_f, 5), - 0, - 1, - 2 * t_f, - 3 * Math.pow(t_f, 2), - 4 * Math.pow(t_f, 3), - 5 * Math.pow(t_f, 4), - 0, - 0, - 2, - 6 * t_f, - 12 * Math.pow(t_f, 2), - 20 * Math.pow(t_f, 3) - }); - - // The vector of boundary conditions - Matrix B = - new Matrix<>(Nat.N6(), Nat.N1(), new double[] {x_i, v_i, a_i, x_f, v_f, a_f}); - - return A.solve(B); - } - - /** - * Evaluates the position at a given time using the calculated trajectory coefficients. - * - * @param coeffs The 6x1 coefficient vector from generateQuinticTrajectory. - * @param t The time at which to evaluate the position. - * @return The position at time t. - */ - public static final double evaluateQuinticTrajectory(Matrix coeffs, double t) { - return coeffs.get(0, 0) - + coeffs.get(1, 0) * t - + coeffs.get(2, 0) * Math.pow(t, 2) - + coeffs.get(3, 0) * Math.pow(t, 3) - + coeffs.get(4, 0) * Math.pow(t, 4) - + coeffs.get(5, 0) * Math.pow(t, 5); - } -} From 953f6ae838e0b95b3906c7abbcbf35601d67b2e0 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Mon, 24 Nov 2025 20:40:41 -0500 Subject: [PATCH 176/180] wrongly placed parenthesis --- src/main/java/frc/robot/FieldConstants.java | 7 +++---- src/main/java/frc/robot/RobotState.java | 4 ++-- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/src/main/java/frc/robot/FieldConstants.java b/src/main/java/frc/robot/FieldConstants.java index 37c2d658..8078fe81 100644 --- a/src/main/java/frc/robot/FieldConstants.java +++ b/src/main/java/frc/robot/FieldConstants.java @@ -50,14 +50,14 @@ public static class CoralStation { public static class Reef { public static final double coralWidth = Units.inchesToMeters(2.0); // ffudge - public static enum ReefPose { + public enum ReefPose { RIGHT, LEFT, ALGAE, CENTER } - public static enum ReefState { + public enum ReefState { STOW, POST_PROCESSOR, HIGH_STOW, @@ -79,7 +79,7 @@ public static enum ReefState { STOW_DOWN } - public static record FaceSetpoints(Pose2d right, Pose2d left, Pose2d algae, Pose2d center) { + public record FaceSetpoints(Pose2d right, Pose2d left, Pose2d algae, Pose2d center) { public Pose2d getPostSetpoint(ReefPose post) { return post == ReefPose.LEFT ? left : post == ReefPose.RIGHT ? right : center; } @@ -140,7 +140,6 @@ public Pose2d getAlgaeSetpoint() { ? (DriveConstants.DRIVE_CONFIG.bumperWidth() / 2.0) + FieldConstants.Reef .coralWidth // Offset X setpoint by center of robot to bumper + coral width - // sigma : DriveConstants.DRIVE_CONFIG.bumperWidth() / 2.0; // Offset X setpoint by center of robot to bumper diff --git a/src/main/java/frc/robot/RobotState.java b/src/main/java/frc/robot/RobotState.java index f2c1fc25..7c211b2d 100644 --- a/src/main/java/frc/robot/RobotState.java +++ b/src/main/java/frc/robot/RobotState.java @@ -159,8 +159,8 @@ public static void periodic( Pose2d autoAlignCoralSetpoint = baseCoralSetpoint; if (OIData.currentReefHeight().equals(ReefState.L1) - || !Constants.RobotType.V3_POOT.equals(Constants.ROBOT) - || !Constants.RobotType.V3_POOT_SIM.equals(Constants.ROBOT)) { + || !(Constants.ROBOT.equals(Constants.RobotType.V3_POOT) + || Constants.ROBOT.equals(Constants.RobotType.V3_POOT_SIM))) { scoreSide = ScoreSide.CENTER; } else { From e7b5aa36c9d0745fa5cb674384dc9743f90a7a07 Mon Sep 17 00:00:00 2001 From: Anshu Adiga Date: Mon, 15 Dec 2025 18:24:45 -0500 Subject: [PATCH 177/180] remove thetaStdev override --- src/main/java/frc/robot/subsystems/shared/vision/Camera.java | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/shared/vision/Camera.java b/src/main/java/frc/robot/subsystems/shared/vision/Camera.java index 0760ca52..976303a1 100644 --- a/src/main/java/frc/robot/subsystems/shared/vision/Camera.java +++ b/src/main/java/frc/robot/subsystems/shared/vision/Camera.java @@ -73,8 +73,6 @@ public void periodic() { thetaStdev = Double.POSITIVE_INFINITY; } - thetaStdev = Double.POSITIVE_INFINITY; - // Add observation to list double xyStdDev = xyStdevCoeff From ee6ddd617b07807986b51a8ecaaa2887b0e0703a Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Tue, 16 Dec 2025 19:13:08 -0500 Subject: [PATCH 178/180] remove secific absolute aths --- Superstructure.py | 2 +- dh2fk.py | 6 ------ 2 files changed, 1 insertion(+), 7 deletions(-) diff --git a/Superstructure.py b/Superstructure.py index 2c562c83..aef1a904 100644 --- a/Superstructure.py +++ b/Superstructure.py @@ -2,7 +2,7 @@ from networkx.drawing.nx_pydot import read_dot # Load the graph from the DOT file -G = read_dot("/home/elliotscher/Documents/FRC/FRC_190/2k25-Robot-Code/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/Superstructure.dot") +G = read_dot("src/main/java/frc/robot/subsystems/v3_Poot/superstructure/Superstructure.dot") # Specify your start and end nodes start = input("Enter the start node: ") diff --git a/dh2fk.py b/dh2fk.py index be161999..fd495ab4 100644 --- a/dh2fk.py +++ b/dh2fk.py @@ -2,13 +2,8 @@ from numpy import disp import sympy as sp -# Use this in a Jupyter Notebook or similar for nicely formatted math output sp.init_printing(use_unicode=True) -# ------------------------------------------------------------------- -# Part 1: Symbolic Derivation -# ------------------------------------------------------------------- - # 1. Define the symbolic variables l1, l3, d3, l5, theta5, l7 = sp.symbols('l1 l3 d3 l5 theta5 l7') @@ -25,7 +20,6 @@ ] def create_symbolic_transform(dh_row): - """Creates a 4x4 symbolic transformation matrix from a DH table row.""" theta, d, a, alpha = dh_row return sp.Matrix([ From 4b8d63294c11c29c8b92f07d2176d13d32f5e145 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Wed, 17 Dec 2025 18:09:35 -0500 Subject: [PATCH 179/180] remove unused files and scripts related to superstructure and DH parameters --- .SysId/sysid.json | 1 - Superstructure.py => debug/Superstructure.py | 4 +- dh2fk.py => debug/dh2fk.py | 0 src/main/java/frc/robot/Robot.java | 41 -------------------- 4 files changed, 3 insertions(+), 43 deletions(-) delete mode 100644 .SysId/sysid.json rename Superstructure.py => debug/Superstructure.py (68%) rename dh2fk.py => debug/dh2fk.py (100%) diff --git a/.SysId/sysid.json b/.SysId/sysid.json deleted file mode 100644 index 0967ef42..00000000 --- a/.SysId/sysid.json +++ /dev/null @@ -1 +0,0 @@ -{} diff --git a/Superstructure.py b/debug/Superstructure.py similarity index 68% rename from Superstructure.py rename to debug/Superstructure.py index aef1a904..af497177 100644 --- a/Superstructure.py +++ b/debug/Superstructure.py @@ -1,8 +1,10 @@ import networkx as nx from networkx.drawing.nx_pydot import read_dot +import os # Load the graph from the DOT file -G = read_dot("src/main/java/frc/robot/subsystems/v3_Poot/superstructure/Superstructure.dot") +dot_file_path = os.path.abspath(os.path.join(os.path.dirname(__file__), "../src/main/java/frc/robot/subsystems/v3_Poot/superstructure/Superstructure.dot")) +G = read_dot(dot_file_path) # Specify your start and end nodes start = input("Enter the start node: ") diff --git a/dh2fk.py b/debug/dh2fk.py similarity index 100% rename from dh2fk.py rename to debug/dh2fk.py diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index deb5abcf..3b4fd577 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -271,47 +271,6 @@ public void robotPeriodic() { lowBatteryAlert.set(true); } InternalLoggedTracer.record("Check Battery Alert", "Robot"); - - // Check CAN status - // LoggedTracer.reset(); - // var canStatus = RobotController.getCANStatus(); - // if (canStatus.transmitErrorCount > 0 || canStatus.receiveErrorCount > 0) { - // canErrorTimer.restart(); - // } - // canErrorAlert.set( - // !canErrorTimer.hasElapsed(canErrorTimeThreshold) - // && !canErrorTimerInitial.hasElapsed(canErrorTimeThreshold)); - - // // Log CANivore status - // if (Constants.getMode() == Constants.Mode.REAL) { - // var canivoreStatus = canivoreReader.getStatus(); - // if (canivoreStatus.isPresent()) { - // Logger.recordOutput( - // NTPrefixes.CANIVORE_STATUS + "Status", - // canivoreStatus.get().Status.getName()); - // Logger.recordOutput( - // NTPrefixes.CANIVORE_STATUS + "Utilization", - // canivoreStatus.get().BusUtilization); - // Logger.recordOutput( - // NTPrefixes.CANIVORE_STATUS + "OffCount", canivoreStatus.get().BusOffCount); - // Logger.recordOutput( - // NTPrefixes.CANIVORE_STATUS + "TxFullCount", - // canivoreStatus.get().TxFullCount); - // Logger.recordOutput( - // NTPrefixes.CANIVORE_STATUS + "ReceiveErrorCount", canivoreStatus.get().REC); - // Logger.recordOutput( - // NTPrefixes.CANIVORE_STATUS + "TransmitErrorCount", canivoreStatus.get().TEC); - // if (!canivoreStatus.get().Status.isOK() - // || canStatus.transmitErrorCount > 0 - // || canStatus.receiveErrorCount > 0) { - // canivoreErrorTimer.restart(); - // } - // } - // canivoreErrorAlert.set( - // !canivoreErrorTimer.hasElapsed(canivoreErrorTimeThreshold) - // && !canErrorTimerInitial.hasElapsed(canErrorTimeThreshold)); - // } - // LoggedTracer.record("Check CANivore Status", "Robot"); } /** This function is called once when the robot is disabled. */ From fc2826277aa70c94a44f2491594c1925c3d142a9 Mon Sep 17 00:00:00 2001 From: ElliotScher Date: Thu, 18 Dec 2025 17:04:42 -0500 Subject: [PATCH 180/180] remove Superstructure.dot Graphviz DOT files redundancy --- .../superstructure/Superstructure.dot | 242 ------------------ .../v3_Poot/superstructure/Superstructure.dot | 235 ----------------- 2 files changed, 477 deletions(-) delete mode 100644 src/main/java/frc/robot/subsystems/v2_Redundancy/superstructure/Superstructure.dot delete mode 100644 src/main/java/frc/robot/subsystems/v3_Poot/superstructure/Superstructure.dot diff --git a/src/main/java/frc/robot/subsystems/v2_Redundancy/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v2_Redundancy/superstructure/Superstructure.dot deleted file mode 100644 index 38b57b57..00000000 --- a/src/main/java/frc/robot/subsystems/v2_Redundancy/superstructure/Superstructure.dot +++ /dev/null @@ -1,242 +0,0 @@ -digraph Superstructure { - /* - * Graphviz DOT file for the superstructure state machine. - * States are represented as nodes, and transitions are represented as edges. - */ - - // Node definitions - start [color = red] - stow_down [color = green] - - intake_coral [color = green] - - L1 [color = green] - L2 [color = green] - L3 [color = green] - L4 [color = green] - L4_plus [color = green] - - score_L1 [color = green] - score_L2 [color = green] - score_L3 [color = green] - score_L4 [color = green] - score_L4_plus [color = green] - - intermediate_wait_for_elevator [color = blue] - intermediate_wait_for_arm [color = blue] - - stow_up [color = blue] - - floor_acquisition [color = blue] - reef_acquisition_L2 [color = blue] - reef_acquisition_L3 [color = blue] - - barge [color = blue] - processor [color = blue] - - floor_intake [color = blue] - reef_intake_L2 [color = blue] - reef_intake_L3 [color = blue] - reef_drop_L2 [color = blue] - reef_drop_L3 [color = blue] - - score_barge [color = blue] - score_processor [color = blue] - - - - // start - start -> stow_down - - // stow down - stow_down -> intake_coral - stow_down -> L1 - stow_down -> L2 - stow_down -> L3 - stow_down -> L4 - - stow_down -> intermediate_wait_for_elevator - - stow_down -> floor_acquisition - - // intake coral - intake_coral -> stow_down - - // L1 - L1 -> stow_down - - L1 -> L2 - L1 -> L3 - L1 -> L4 - - L1 -> score_L1 - - L1 -> intermediate_wait_for_elevator - - L1 -> floor_acquisition - - // L2 - L2 -> stow_down - - L2 -> L1 - L2 -> L3 - L2 -> L4 - - L2 -> score_L2 - - L2 -> intermediate_wait_for_elevator - - L2 -> floor_acquisition - - // L3 - L3 -> stow_down - - L3 -> L1 - L3 -> L2 - L3 -> L4 - - L3 -> score_L3 - - L3 -> intermediate_wait_for_arm - - L3 -> reef_acquisition_L2 - L3 -> reef_acquisition_L3 - - // L4 - L4 -> stow_down - - L4 -> L1 - L4 -> L2 - L4 -> L3 - L4 -> L4_plus - - L4 -> score_L4 - - L4 -> intermediate_wait_for_arm - - L4 -> reef_acquisition_L2 - L4 -> reef_acquisition_L3 - - // L4_plus - L4_plus -> stow_down - - L4_plus -> score_L4_plus - - L4_plus -> intermediate_wait_for_arm - - // score_L1 - score_L1 -> L1 - - // score_L2 - score_L2 -> L2 - - // score_L3 - score_L3 -> L3 - - // score_L4 - score_L4 -> L4 - - // score_L4_plus - score_L4_plus -> L4_plus - - // intermediate_wait_for_elevator - intermediate_wait_for_elevator -> stow_up - - intermediate_wait_for_elevator -> reef_acquisition_L2 - intermediate_wait_for_elevator -> reef_acquisition_L3 - - intermediate_wait_for_elevator -> barge - intermediate_wait_for_elevator -> processor - - // intermediate_wait_for_arm - intermediate_wait_for_arm -> stow_down - - intermediate_wait_for_arm -> L1 - intermediate_wait_for_arm -> L2 - - intermediate_wait_for_arm -> floor_acquisition - - // stow_up - stow_up -> intermediate_wait_for_arm - - stow_up -> barge - stow_up -> processor - - intermediate_wait_for_arm -> stow_up - - barge -> stow_up - processor -> stow_up - // floor_acquisition - floor_acquisition -> stow_down - - floor_acquisition -> intermediate_wait_for_elevator - - floor_acquisition -> floor_intake - - // reef_acquisition_L2 - reef_acquisition_L2 -> intermediate_wait_for_arm - - reef_acquisition_L2 -> stow_up - - reef_acquisition_L2 -> reef_acquisition_L3 - - reef_acquisition_L2 -> barge - reef_acquisition_L2 -> processor - - reef_acquisition_L2 -> reef_intake_L2 - reef_acquisition_L2 -> reef_drop_L2 - - // reef_acquisition_L3 - reef_acquisition_L3 -> intermediate_wait_for_arm - - reef_acquisition_L3 -> stow_up - - reef_acquisition_L3 -> reef_acquisition_L2 - - reef_acquisition_L3 -> barge - reef_acquisition_L3 -> processor - - reef_acquisition_L3 -> reef_intake_L3 - reef_acquisition_L3 -> reef_drop_L3 - - // barge - barge -> intermediate_wait_for_arm - - barge -> reef_acquisition_L2 - barge -> reef_acquisition_L3 - - barge -> processor - - barge -> score_barge - - // processor - processor -> intermediate_wait_for_arm - - processor -> reef_acquisition_L2 - processor -> reef_acquisition_L3 - - processor -> barge - - processor -> score_processor - - // floor_intake - floor_intake -> floor_acquisition - - // reef_intake_L2 - reef_intake_L2 -> reef_acquisition_L2 - - // reef_intake_L3 - reef_intake_L3 -> reef_acquisition_L3 - - // reef_drop_L2 - reef_drop_L2 -> reef_acquisition_L2 - - // reef_drop_L3 - reef_drop_L3 -> reef_acquisition_L3 - - // score_barge - score_barge -> barge - - // score_processor - score_processor -> processor -} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/Superstructure.dot b/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/Superstructure.dot deleted file mode 100644 index 254bcf50..00000000 --- a/src/main/java/frc/robot/subsystems/v3_Poot/superstructure/Superstructure.dot +++ /dev/null @@ -1,235 +0,0 @@ -digraph Superstructure { - START -> STOW_DOWN [type=UNCONSTRAINED] - - STOW_DOWN -> FLIP_DOWN [type=UNCONSTRAINED] - STOW_DOWN -> L2 [type=UNCONSTRAINED] - STOW_DOWN -> L3 [type=UNCONSTRAINED] - STOW_DOWN -> L4 [type=UNCONSTRAINED] - STOW_DOWN -> STOW_UP [type=UNCONSTRAINED] - STOW_DOWN -> L2_ALGAE [type=UNCONSTRAINED] - STOW_DOWN -> L3_ALGAE [type=UNCONSTRAINED] - STOW_DOWN -> PROCESSOR [type=UNCONSTRAINED] - STOW_DOWN -> BARGE [type=UNCONSTRAINED] - STOW_DOWN -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] - - GROUND_ACQUISITION -> FLIP_UP [type=UNCONSTRAINED] - GROUND_ACQUISITION -> GROUND_INTAKE [type=UNCONSTRAINED] - GROUND_ACQUISITION -> L1 [type=UNCONSTRAINED] - GROUND_ACQUISITION -> L4 [type=UNCONSTRAINED] - GROUND_ACQUISITION -> HANDOFF [type=UNCONSTRAINED] - GROUND_ACQUISITION -> L3_ALGAE [type=UNCONSTRAINED] - GROUND_ACQUISITION -> BARGE [type=UNCONSTRAINED] - - GROUND_INTAKE -> FLIP_UP [type=UNCONSTRAINED] - GROUND_INTAKE -> GROUND_ACQUISITION [type=UNCONSTRAINED] - GROUND_INTAKE -> L1 [type=UNCONSTRAINED] - GROUND_INTAKE -> L4 [type=UNCONSTRAINED] - GROUND_INTAKE -> HANDOFF [type=UNCONSTRAINED] - GROUND_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] - GROUND_INTAKE -> BARGE [type=UNCONSTRAINED] - - L1 -> FLIP_UP [type=UNCONSTRAINED] - L1 -> GROUND_ACQUISITION [type=UNCONSTRAINED] - L1 -> L4 [type=UNCONSTRAINED] - L1 -> L1_SCORE [type=UNCONSTRAINED] - L1 -> HANDOFF [type=UNCONSTRAINED] - L1 -> L3_ALGAE [type=UNCONSTRAINED] - L1 -> BARGE [type=UNCONSTRAINED] - - L2 -> STOW_DOWN [type=UNCONSTRAINED] - L2 -> FLIP_DOWN [type=UNCONSTRAINED] - L2 -> L3 [type=UNCONSTRAINED] - L2 -> L4 [type=UNCONSTRAINED] - L2 -> L2_SCORE [type=UNCONSTRAINED] - L2 -> STOW_UP [type=UNCONSTRAINED] - L2 -> L2_ALGAE [type=UNCONSTRAINED] - L2 -> L3_ALGAE [type=UNCONSTRAINED] - L2 -> PROCESSOR [type=UNCONSTRAINED] - L2 -> BARGE [type=UNCONSTRAINED] - - L3 -> STOW_DOWN [type=UNCONSTRAINED] - L3 -> FLIP_DOWN [type=UNCONSTRAINED] - L3 -> L2 [type=UNCONSTRAINED] - L3 -> L4 [type=UNCONSTRAINED] - L3 -> L3_SCORE [type=UNCONSTRAINED] - L3 -> HANDOFF [type=UNCONSTRAINED] - L3 -> STOW_UP [type=UNCONSTRAINED] - L3 -> L2_ALGAE [type=UNCONSTRAINED] - L3 -> L3_ALGAE [type=UNCONSTRAINED] - L3 -> PROCESSOR [type=UNCONSTRAINED] - L3 -> BARGE [type=UNCONSTRAINED] - L3 -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] - - L4 -> STOW_DOWN [type=UNCONSTRAINED] - L4 -> GROUND_ACQUISITION [type=UNCONSTRAINED] - L4 -> L1 [type=UNCONSTRAINED] - L4 -> L2 [type=UNCONSTRAINED] - L4 -> L3 [type=UNCONSTRAINED] - L4 -> L4_SCORE [type=UNCONSTRAINED] - L4 -> HANDOFF [type=UNCONSTRAINED] - L4 -> STOW_UP [type=UNCONSTRAINED] - L4 -> L2_ALGAE [type=UNCONSTRAINED] - L4 -> L3_ALGAE [type=UNCONSTRAINED] - L4 -> PROCESSOR [type=UNCONSTRAINED] - L4 -> BARGE [type=UNCONSTRAINED] - L4 -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] - - L1_SCORE -> L1 [type=UNCONSTRAINED] - - L2_SCORE -> STOW_DOWN [type=UNCONSTRAINED] - L2_SCORE -> FLIP_DOWN [type=UNCONSTRAINED] - L2_SCORE -> L2 [type=UNCONSTRAINED] - L2_SCORE -> L3 [type=UNCONSTRAINED] - L2_SCORE -> L4 [type=UNCONSTRAINED] - L2_SCORE -> STOW_UP [type=UNCONSTRAINED] - L2_SCORE -> L2_ALGAE [type=UNCONSTRAINED] - L2_SCORE -> L3_ALGAE [type=UNCONSTRAINED] - L2_SCORE -> PROCESSOR [type=UNCONSTRAINED] - L2_SCORE -> BARGE [type=UNCONSTRAINED] - - L3_SCORE -> STOW_DOWN [type=UNCONSTRAINED] - L3_SCORE -> FLIP_DOWN [type=UNCONSTRAINED] - L3_SCORE -> L2 [type=UNCONSTRAINED] - L3_SCORE -> L4 [type=UNCONSTRAINED] - L3_SCORE -> L3 [type=UNCONSTRAINED] - L3_SCORE -> HANDOFF [type=UNCONSTRAINED] - L3_SCORE -> STOW_UP [type=UNCONSTRAINED] - L3_SCORE -> L2_ALGAE [type=UNCONSTRAINED] - L3_SCORE -> L3_ALGAE [type=UNCONSTRAINED] - L3_SCORE -> PROCESSOR [type=UNCONSTRAINED] - L3_SCORE -> BARGE [type=UNCONSTRAINED] - L3_SCORE -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] - - L4_SCORE -> FLIP_UP [type=UNCONSTRAINED] - L4_SCORE -> GROUND_ACQUISITION [type=UNCONSTRAINED] - L4_SCORE -> L1 [type=UNCONSTRAINED] - L4_SCORE -> L3 [type=UNCONSTRAINED] - L4_SCORE -> L4 [type=UNCONSTRAINED] - L4_SCORE -> HANDOFF [type=UNCONSTRAINED] - L4_SCORE -> BARGE [type=UNCONSTRAINED] - - HANDOFF -> FLIP_UP [type=UNCONSTRAINED] - HANDOFF -> GROUND_ACQUISITION [type=UNCONSTRAINED] - HANDOFF -> L1 [type=UNCONSTRAINED] - HANDOFF -> L4 [type=UNCONSTRAINED] - HANDOFF -> L3_ALGAE [type=UNCONSTRAINED] - HANDOFF -> BARGE [type=UNCONSTRAINED] - - STOW_UP -> STOW_DOWN [type=UNCONSTRAINED] - STOW_UP -> FLIP_DOWN [type=UNCONSTRAINED] - STOW_UP -> L2 [type=UNCONSTRAINED] - STOW_UP -> L3 [type=UNCONSTRAINED] - STOW_UP -> L4 [type=UNCONSTRAINED] - STOW_UP -> L2_ALGAE [type=UNCONSTRAINED] - STOW_UP -> L3_ALGAE [type=UNCONSTRAINED] - STOW_UP -> PROCESSOR [type=UNCONSTRAINED] - STOW_UP -> BARGE [type=UNCONSTRAINED] - STOW_UP -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] - - L2_ALGAE -> STOW_DOWN [type = NO_ALGAE] - L2_ALGAE -> FLIP_DOWN [type = NO_ALGAE] - L2_ALGAE -> L2 [type=UNCONSTRAINED] - L2_ALGAE -> L3 [type=UNCONSTRAINED] - L2_ALGAE -> L4 [type=UNCONSTRAINED] - L2_ALGAE -> HANDOFF [type = NO_ALGAE] - L2_ALGAE -> STOW_UP [type=UNCONSTRAINED] - L2_ALGAE -> L2_ALGAE_INTAKE [type=UNCONSTRAINED] - L2_ALGAE -> L3_ALGAE [type = NO_ALGAE] - L2_ALGAE -> PROCESSOR [type=UNCONSTRAINED] - L2_ALGAE -> BARGE [type=UNCONSTRAINED] - L2_ALGAE -> L2_ALGAE_DROP - L2_ALGAE -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] - - L2_ALGAE_DROP -> L2_ALGAE - - L2_ALGAE_INTAKE -> FLIP_DOWN [type=UNCONSTRAINED] - L2_ALGAE_INTAKE -> L2_ALGAE [type=UNCONSTRAINED] - L2_ALGAE_INTAKE -> L2_ALGAE_DROP [type=UNCONSTRAINED] - - - L3_ALGAE -> STOW_DOWN [type = NO_ALGAE] - L3_ALGAE -> GROUND_ACQUISITION [type = NO_ALGAE] - L3_ALGAE -> L1 [type = NO_ALGAE] - L3_ALGAE -> L2 [type=UNCONSTRAINED] - L3_ALGAE -> L3 [type=UNCONSTRAINED] - L3_ALGAE -> L4 [type=UNCONSTRAINED] - L3_ALGAE -> HANDOFF [type = NO_ALGAE] - L3_ALGAE -> STOW_UP [type=UNCONSTRAINED] - L3_ALGAE -> L2_ALGAE [type = NO_ALGAE] - L3_ALGAE -> L3_ALGAE_INTAKE [type=UNCONSTRAINED] - L3_ALGAE -> PROCESSOR [type=UNCONSTRAINED] - L3_ALGAE -> BARGE [type=UNCONSTRAINED] - L3_ALGAE -> L3_ALGAE_DROP - L3_ALGAE -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] - - L3_ALGAE_DROP -> L3_ALGAE - - L3_ALGAE_INTAKE -> STOW_UP [type=UNCONSTRAINED] - L3_ALGAE_INTAKE -> L3_ALGAE [type=UNCONSTRAINED] - L3_ALGAE_INTAKE -> L3_ALGAE_DROP [type=UNCONSTRAINED] - - - PROCESSOR -> POST_PROCESSOR [type = NO_ALGAE] - PROCESSOR -> PROCESSOR_SCORE [type=UNCONSTRAINED] - PROCESSOR -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] - - PROCESSOR_SCORE -> PROCESSOR [type=UNCONSTRAINED] - - BARGE -> STOW_DOWN [type=UNCONSTRAINED] - BARGE -> GROUND_ACQUISITION [type=UNCONSTRAINED] - BARGE -> L1 [type=UNCONSTRAINED] - BARGE -> L2 [type=UNCONSTRAINED] - BARGE -> L3 [type=UNCONSTRAINED] - BARGE -> L4 [type=UNCONSTRAINED] - BARGE -> HANDOFF [type=UNCONSTRAINED] - BARGE -> STOW_UP [type=UNCONSTRAINED] - BARGE -> L2_ALGAE [type=UNCONSTRAINED] - BARGE -> L3_ALGAE [type=UNCONSTRAINED] - BARGE -> PROCESSOR [type=UNCONSTRAINED] - BARGE -> BARGE_SCORE [type=UNCONSTRAINED] - BARGE -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] - - BARGE_SCORE -> BARGE [type=UNCONSTRAINED] - - L4_SCORE -> GROUND_AQUISITION_ALGAE - L2_SCORE -> GROUND_AQUISITION_ALGAE - - GROUND_AQUISITION_ALGAE -> PROCESSOR - GROUND_AQUISITION_ALGAE -> POST_PROCESSOR - - GROUND_AQUISITION_ALGAE -> GROUND_INTAKE_ALGAE - GROUND_INTAKE_ALGAE -> GROUND_AQUISITION_ALGAE - - FLIP_DOWN -> GROUND_ACQUISITION [type=UNCONSTRAINED] - FLIP_DOWN -> L1 [type=UNCONSTRAINED] - FLIP_DOWN -> HANDOFF [type=UNCONSTRAINED] - - FLIP_UP -> STOW_DOWN [type=UNCONSTRAINED] - FLIP_UP -> STOW_UP [type=UNCONSTRAINED] - FLIP_UP -> GROUND_AQUISITION_ALGAE [type=UNCONSTRAINED] - FLIP_UP -> L2 [type=UNCONSTRAINED] - FLIP_UP -> L3 [type=UNCONSTRAINED] - FLIP_UP -> PROCESSOR [type=UNCONSTRAINED] - - POST_PROCESSOR -> FLIP_DOWN [type = NO_ALGAE] - POST_PROCESSOR -> STOW_UP [type = UNCONSTRAINED] - POST_PROCESSOR -> L2_ALGAE [type = UNCONSTRAINED] - POST_PROCESSOR -> L3_ALGAE [type = UNCONSTRAINED] - POST_PROCESSOR -> L2 [type = UNCONSTRAINED] - POST_PROCESSOR -> L3 [type = UNCONSTRAINED] - POST_PROCESSOR -> L4 [type = UNCONSTRAINED] - POST_PROCESSOR -> BARGE [type = UNCONSTRAINED] - - HANDOFF_SPIN -> HANDOFF - HANDOFF -> HANDOFF_SPIN - HANDOFF -> L4_WINDMILL - - INVERSE_FLIP_UP -> L2_WINDMILL - INVERSE_FLIP_UP -> L3_WINDMILL - - L2_WINDMILL -> L2 - L3_WINDMILL -> L3 - L4_WINDMILL -> L4 - - HANDOFF -> INVERSE_FLIP_UP -} \ No newline at end of file

50yVseanZdGS`T%7aN1F6kSI)0$oA6zHA8E*IjeE@|5$E zk8uoiZR$EzJ)^ErUAsD_$WI9v`=Db_PH%=jLya@kXOi|;#~fQ)Y0TB!eTQw#x4nOb zo7T3DLVmStTU%Uih3h{xjlDVT%J}C^DG5tN{Vw_seJ)O%f!zA{;49yMw9Ow%{{CrN zU;7qyQ{?J8@n_OH*A;UbbENt#J7*tLIBw?7u3Af`HxJ9>!0kj1n!91Cg{X1EGCp`a zu~i(nwb)KzwaNqWk8_+5TlB#=A=NF! z9%5hlN83rRg?t!?c4vaXG5-*&j~7?P`ZTh5`3SGn}5t=Ui0 z4QYv|VGiz*nOl;w+js7h6JR;Ii%`HfsaM(k+j_KvVz3y$dI?IvlGw)F$&g!Q8*{fq zPJm;P`y$q#W089&H8GAw?m6XSY+dfJrVy-**-^ufp)%{+e{&f`piixkb?q7HCud4XhR0@avCEC9#<6n94uR!=$ZVGc% z!N2kj^PEdSpH|7xCpHOs#O;a_*i!Lu|9#uP zj+B9G4gQsew7ft3YYqNyMgCQ!bX;@ruQd4A9ejm<|7wx{&Ak73;tj9{A+uu z_}jk!_dWmWkKfJSf4%){Ln-+Cy#F5XuOj)K?)~>dQp~@ijlaJi{{8*%@9*<}|Nr&(|6hOqzx?)|9<%Q@4bKjKL7Xc^Zs2xf3K(fy`JLhRQ$hv{i~!|!Ypn!G#i_Z z%pztnv#8n3Y-%~;SYfjT*$u!3W_>dmjFezXGLw;!${a%WKyUz= zLl_M((-BW*mZ3r+vkrOn&HT&?nJpRDF_W^M%p3~44>$xr+nj68F(a7a&2VM`nEAo- z_%>wJ0qdA`%~|F=ShKL%W<Fsxh*{7q$DReT0%mLWtP9pP>zRqoOw>+{B{D}+t(RGWm3n4I z;)%`P#Cn;Fs5;XW)RbT(d}gyO^)h1x%~tR$n30JKGl`jj%p_Q1a|F4)%`9eZxLL5w zW)FB3!B+SW#(U$PvBTVD?liN)$pY5GcW1pKSkbHmRx&G_4z-23*qmlg2WR3JbE27M zH`Xhg(b+MHIh@^kgT2kR=5}iC0C(d*8Xwr@BlgyKjlD7UntND@VdgdSf%(Xefkii` zlGzSyXSN52GjrM30i&AHz-Y{tvGa5@Cb==pDX`j`uc-ajcokNCpShRH`>^e%N0tjl z!7n9e2Dl9W68BAMSQ@Keo;MZbX6o-AG8r64;}_rT8C2z8jmEjWRc3qs;^6 zW^)U;4S#^_ZRRtoy)>Q~pYhL(Z}^{N{Qwh~3C)eTnyG4b|<}K_Jc%9iT^Cteb@rCT$*bCzznJdhL)L3rbF>LdT zafj90#yO%Z&2y}*FmIE0$vkUZqv~1goN?E%OxwH*|Bi7M)=KjXwhBCpzeC0)@Vt2e zyo5hR?pfoMaUFlkxP`yZ$_4W@<5R{5^OO0}++l1twi)jke=v6%I~ec8wi@@~T{Q2R z_wi?pn`E59P8*w9+hTk*znGuR{l*Pe_8U*}`x%`v?viuZyi49i^8oSv#w+GW%vZz? zo14hpY;0nOt;RR=z4^}kMwL(CCuZNwugne_Pslrn9WXY++yw5ze`o!j`NRAkhVRVR z<~rgVjdjLu{5oSF{;A4pW;36vY-V;ayO{&5Y*qoQm{q~5W;L*ySskoy)&OgmHNl#E z7N4qGd?uf&ZhXp~s;+$AezV(a@U{5{d}F>f*R#tyUqYi{6#>x~V@Ui?gBwlT|y zWJRP#cN6^YfK<}Y%8nh(r};9LA6Dr_(o87GZB;2vfY z)3?ZTtcM@U@aqz8)R~gQfu* zrU^b#@xXXyeDl8Az^D5@Cw#2#tF`7j#_P=W;CepuQ`m8;5uF{vS-a$M^Mtueo-j|E zyBY72yX7(SxcNp|e8%3WyT(1xG%X^b_&xHdc?>)Td#BtbPntWiQ|4acd*ojEiud_m zdBi*lzT_Rh1J)_=fIpT=g6n#Gjp=BfQ-r5BqJ8w5bKqCU_3NlsfWfR@HMk7 za;scpZo$@?bIF<`=gKGMQ`3|G8ix!|9x@Iat~_iU0X@7Uj~GWm7cby=QpkhGzs6AZ znhegz$7H8JW=ty`zu7V;(1&E9c2j^NBf(%0rD|#u{TSxRzNm_6S(XteE)pWTm#0d}KT}lzeQ2f}!kT z$>Y3FE%rHXyi~8$BV#xfh8a)AOU6&dBX}mP6NZT`F?t%kjb27ZD}$BZdIsmIFj!w= z7}!#9sjgT)Y5-(vZuHAhz7-4zmY10H4`P zWhJ*V!%hWe^0VMS=WAL)xty=5FE>^gU5tTnyI|doEU=PWe^_5({1GdRmBw@RLcI{6 zcqzIXgN-3ZS8O0SkeuvR7Wmn*6qczR%e5@fRF<+W$9hHHOJOU^vMrm4r3@vkN2Z}% z%d-sS@i{k?$;?swvjm!!1;STBxR1;r_85F@hMG6jM!8AeP@CjtaI@S3Zjoz=ujP~3 zjk9$%vT>FaRyHi9<*J}%fCd$jkW`_36+hIR#~0Y<$@%gR-pBcJfqcZR20`nQOlAeZ zq`cCPWRT2f>Xmpco~h^f7S!)%v@izYvr;{dm6d%`T5n;!7LR2TE2;IE+(+^^RTqE@ zLS}!-qn`(pH2yW!uEveJOXlYEq7p7KRt1$KASnt(4`0uedqQ244Xke7K zN?9eXMvUtlC9Kkn3&D*G#u$Ot-P()%5~s6PWhY)&*XDi zkjM30#P=F)uL8qteEvm=C$&H`Pk#5 z`lQ~AkJtxsN4GLs8+UYTqYc=`XbZMA+JWti_TYHlNq6*UV+=UP7z>Uy#)0E_f8Eh{ zS$V9#iSObu=Xs=~hkRpH+GxrtN@F#_&de%VIjo#kCC-rptc;HaGkQp*kgwvKh{QNr zNEw)=jRvgewC<{va+SQRR>{@iY93ozR?8S=jZXObRs%Tov0PSUDnts29P(Lw5s^c_ zh_9lY(GgZTtgKNFRxYa^mfLD!HM5$6&GChdB1U1OkWmz0m$f`rT`VtHk6BAtO|62g z7BcD(%WKuaUdcMxYZ)cvqxdAEgnSa8!O!e^PpyzE8jRx7IHqe4L= zAC})}!@Q~0#%hg^8uC$n5K%)uh>ze$s^o>4&&X>O!?%Uk#A*w-sg;XJUL%)L9N*4r zXf?9hvDOf5i;o!cL48yasTMUPw^0gKZY-D4k@ZGa9wNDoJVptlBv_JJ2cnIw4p>#N zBeVASs#ZEUd5rX6IcyxgSktNn_GUKJ8f*;$hv1VM$&F-2QX>VvC+oGWVXO?Yp6d2S2ji*kz^nIE zcjWbZs_zhcs;d|o!Hh;GFq4rP%xq)<%Ngat@9ByXjB3#8I{4xoNI(Noa%{; zBt~LmB%?vrNNWT>A-g9v5@JcfBt{}*6f1+QQP@B$0jmj(1V&2yKVSkd6@D~p{jAZj z23qlm{A0v3(&EPv>t~I_`h)$g0akn?4J+}nc*a;_1FT3!YGRSF_{JD(ERiu-Cu^Hp zE?3BH>I+hwvao`n$CC{*4^5r-pTiJ7tEbX7|M`_Ff@LVwZNKhEwUEk zH>u5Jty6WZ*K(bzW!1LUsoH#&)~Oy=Pw*Z2>(p!chSfLnE%;Wx1AFqWa176IjiuHS zYq7OaZK96N4xVANivT^tF_y8tqAV;L)m&9)52LBlX2;#V`DW39GU;7udE5y3FAh+sq*t5}aamYpuk_Tc3%13Vsg8C3`#b3D$O2##>KxR3n=4L`O5CgVBu`U<@NB7}JOa#xi1q z*?A?N=qyH7FsqRb%*N~UL_a0=B^bwu3&u4*2e(mmg0&5sXnhSn(XoxM!PrI|Fb<5Z ztW31FVw0?ItbPq{VK&Lyf=#x*6Zsb0%xH?Wnb>6OW$<R9w9cE>Z^@#YB z;G^I>{1Ku%tRt-KwjL9C6nq@~h(Atjhjkp=3GTFZS)s%q2SbA&@W+VlvW{VEtZPI< zgV%!Z@kfcRv5sPEt?R)*+zfCXdmp^c>b2lyR@PcKh+hw0vMw{egsrnK;(c6at+&nw z&j-&1&jv5xZ(BF58`f>>7XA+YhIJ}7Q7O?3SMOv%F0#ijSkg!f^V?9 z;N9T8;Bh#|f{$6dW<9n-@wwV+)@krGYqwb0Xx+j#SvTco z-pMzK`QuHzr}xW~)+z8kC*LpMar*t_K9sNYYrQx43fl+n3+@k|Q|tK@ACPaYch&)z z`{fOJQ%40)+v>HWcfz zzTr0pHwQNbHwL%hH-H<1hvZA^m30XIzw$8SL*NVRr6s88h5WL9T0g9HaMuTSbDneR zhYgKS38LP0B!9!{{Cpm+)k4+X>H+rPXZk{QRbG<|)irq?yw0<^P))I>vO1N2ITrG7 zNOx;)a66UeVylBe+ps@bLF|b&kGS7$;|M;y{lt1|g|~xv#W`h&3i+-6sDC-pdGNft z0A5fR)%@ULGUj9Rg5m7&_ERgIeMBCW;p}HTcj1^nvr@_Z!2`im@+GfYDw!I;h;uGf zi_{f)RfgE%?4vTJJPOes_0)4)hA)5sV4rA`Z`k!j^~{X(aJbugF$`!}e`IVQCo zf=|b4TA5t_8$1+DE)Q{{_&6!n*4*8{iD-9=|)bg2ru9Lw%988AI4<6)kTvP|K zOKLIaSp;5^m*rx0SzeJL@HO~WKhq)doqh|x*Y9*vIiHRpNo6v861gC_5L`%qkR&oG zvv6=iWH|X*_a}1LJp!i3lfxOemMoMvz{qS&$RSny+G(e3HH9>?W0IXw)I%M)@cb`qS1pTTQ&3_QmA z45@5wkEh?v47%jZpkf?qM6u&wk?omM@~4TJaAwFU8yoBazq{-q9ow~gNZ0o4iR7J;6S1>$0KFJz2M5p{ zWfnM_oPVfc+5cd+-IJ^yvZu6d$DTmOSvdhaCkMhG5KJA$NDbGv2LD# zrm$1mz2(s0KQbN|k7ys6+)iQlktv8Lvy(IGi|-?o+R5y`a+U}m5+P)kn2qlzlh{e^ zeysGBb40k1@F8=E&K5I8gb+7mrkI7FOMH%)LCg)Ajyd2A{5%m75)KRpqrXgSC$ale zt)Fb8qsnMtG#OpC)lpwD!U?fMritnJ-r}eFrFv6gp6D%psgRJ?x{Z!5TVpX~ zI~`d@0YBo~QK79KK>hx*gKn*3$d0-L*hzN`!x%EA>_fHQqL28YeyXX$4zWU}ifQ=v zRA{H$>ks&zx|5D6dt$M`STeTEY-hAH*qQB2`0l};!5+cx^z7;xoFb+QD`X00hV-Ro zAJId{mT_bc9Y@9mdot?=vwJWL*%|D9;=B5x`oZigCW|S;44I65)!lVm`H$?b|KU~X zu6r<>#QIm=g-&Z-gW2q?b{6}ao zql3j+Ph=Ov5`&5D0kW7~oLLv$RgVmI(WBsXA)^^Ml8mCT2FRk=K>1UT7GuOuJw}WL z$5Oe7UDO^Zi(rFfY&}|z0msO(G7jU|I*uMCN6T1xET5}bdYoLYV(Hk-3fo2OK{Bo$ zAxDBER23M;!;2O17b=J-39N1Ymr)OYi z-GV-WopnpP0(RD2SfL}dZWa88UE=D0^l&*se&Jo(Ubi9MI+$KuRo7H{aZLqvIuX!c zRXP#W0mkX^@!6pbJ zE1r&_3-cIb=s|KYI9Lt=hsdF_f?duoYge$#<7?41uQt8z{O)-fsh>e)6noV^l~L^D zU!aU)KmP`$5&cAekp>$84iE#uw8W~@E3ZbdvR%opXjh{~P5S87q$6}Ss?qD&u1vfN zRspQQj#cUXSC`(;bzxK`Mg%Kk(@~jdrJ&z|xf-!Db~UV|U71KF`T{n>*CbZbu8Ebh zGjYOymoagpIw|tv0zhX`Rt}xew*&f^xZ2F^m~doA(r26f)%h!5-CBq zy*Bugys~YAjaeyRmttHp7(pCShgAg5nMtJLWJAHBVi-6~3WcR%E>dOn)@8y>(*pbtD33qON1twUg>(`h-e~omAQB z)mW7Nd_~FW3a^FTm5k>0TuwMg&*f*yZ=I6fjz#D}R|H-c)?3(Juv+#YtTtHNt^;;q zmWsZag@dWEl)*^677;}xaYmh0DR>P=ixlD)6;m+!1*Rl6kj#jBAlY^7)I6IN>AlxS zR{$$gC5cX|PpSd-KsafLr>5&(A4dJ{0Yv6eW3Em|ByF&t-JeK$#_586?S70iFlKJ| zW!&5D16CGEs8(5=RHsxWQCXZ)$vM$HU4?jMQBhPPQV~0?suHOps*1!qiLSuPX;lF` zqpFESIW;Q&S=($+wqAf2xcRmRb&$hbV6O4^~mC%V0`-VjkU+vqwVa( zvx&GcI6Ewh{I}Jdgvv=kGF@}gYEG!hJoYoF^R{amt9i) z1Y(2j93mxIlkEwNCu2jvA@)!^7Mz&$xJ!YbL~N)Xn{g~U@+J4X7K+lGEs7{9N`a-A zm0%o2OoZ3no@h_Phro(`Kv_-^62<{UL z^g_K)?8hGv^R=O%hBsdX+sdY|~OQhDR@Oy|Z(tB86s1L$FAP$P;yiX2d z^L1qSk%IpcIVg6+U8JKBi5#3Sk`bGa{VR46ovwGWzDP%9HA-*+tMkQ9R;KHn*fgC+ z=MuR^8l4&+Nzbrn+L823dluN6_i7|P%bv}6wmk=&!()!5=kll{X&$*9jhaz|)9o3| zr`glNh16dlcCf=Vy#t%7w=?r`s-B`3vAR&C)wx9;FbzJcC@PA9#YAziIIme$EQ&}9 zbCFn#UnI7P?P7|atha$nh%6RciA~lybRLmc5J9@%8NpTdN_z$3D<-||0#vX-i`i(R!2EEJo|iVhgxMjM9JTm*)om1Oy%Q{sdey*Vv2g1@;A|_? zQn3tNCYFQC#R~D83cmvD$y;cz#}?UdiTtMfqNHEpI(v#e)m}$*3b-Esj=0}pI|iK( z_Yj+EkI@^%MlnWj6q~?JJi_;^`n|QI)2DJbjA{06dk=m$qe%J#alb!gZyhc8A*=`G zE>NjnP@)78Y5sXkr}kv3i_dE7mby zC)SJTtV9!ud2B1eB>2o^L>IlZ-*K{+{zOm4Uivc~9ee37bcgJvztW+xm-f3f_R_s! zJ)t+`Q_$}bdD#BfK4>4d58)&0&Gr^>i@g=xYHtI#+1tVG_6~3d=X?~_8S|KZ)IMTA zq{0(ANFs!HKLq?AR$EkPFK5id_bDYru@CdO7a2^IuFgsx14eKd+mp+#-=_>hx zo|7ku?zKh4?X&$pm9GQ$u{YqGz`ejJ);8LwSl@47 zWR)KE%s1ILh;6hl(QEP*{WV|FE%Q3j&GvOxHi4UYRF}iLRbJ+~`A&DuAMmcR5?Nmf z4A8y6UNElO*N9vtawTxZzRLI-%G~7-0rG}S|wJC<3vsbdNS^z zdaA^{b9$*{XXuUjf|Z;03+$HtFFi)j(h>74YtM<@vY%tO?L&0% zyg&!d3#|3xR6SKMm5BHBGuCh0&+N1IIq)`qE1f{k(~tfOtnLcDw?DA@&VCPe6Wv7&(Sy&ok1?2a1!IEU@NeyRaJn#y zDSC?K)aof#P^~BY9^#Gtmen_y(w#*YIKANX6tC?!w$jxZ_Y$3m#sWLzm+9q1Yv8Mk zj>KY#4)|DNsa~dQfHg!-Q43#Fv?m%H?0{dO5{g7%BGFs*Q6u#r-G}$%NZpS0*kXyU zC2E69@grCtq}z&i#On~NE!v2-jN4#w#Beo&)irduT}$`g_4q&bFZ-wc$Nr6fBu40g z`k{Cv2I|L*ABhLzA>+k*iLN6SV|7Kq`2+txD+Bd?YnRRbJ2e zR=`;auEDRM5Agbc>HM^R*rsEUWnw?=C4nvU54N4J_BZ~N_rv~bFQ-HDM*1voAZIzF z4FL=8558*k1BU0=&Nq80SxW*gqwls$?3=xe$kM!Yu zIp-m9SPa#}^h_dtH|qU?1K{Zh>Rm(A^Ir%BjT30E#?L`==Hju*nrg+^8&Ys zgm)r1A^Ilk^8&|U9u>#LU_C_758NaYj9=7Zit&=L13fa zpzDi`SOc*zaD&KoRuPG#9vwv(1_i`jZ6yUb8krE;`W6=oILhIL!-)_Zglu^Vd& zHWkgpESNLZ_`pPZtdFOM`ousSCzcb_iQ~k^?;@j_*o8F*n~N6W2Gt#X16!wW>NeE8 zN#q9DnmtC)O?^sWcwhvW(243qa}qi+@Cg|uamLV@erzC~^N$nP83}U)ec=86>xo&7 z?j(j0%^5}Zl)xx#av%Y@37yfLYCJvX$I)?qG^26gWMZRXO%B9&;!!O==Zy)*BqKia zIA9DXfzzA%BLltZ`#vp@h&_aph<&0v85l`05xx(v`QktyIK9Ee`1Cwy)ns}Y%1IAP zf{IvQn0*3$16Rd0u~YBTEx;C{rAX&glhtK9Sk+`dR{I8S>6WsUyro;o)?jOSQ>S&( zIn`x#A`SBzGL4fKKY&R8z<|JIaYdwdYRH;0wUY)vkjQ|*z`!MOS=^@P zEqz-zmo4ON-9omMshreKO|Yh{B?rM77#I||C@zVVPAaFC9L#u7Acd2XaSE)qY^dXi zxT2wMgl~*B(v5W+ei|otYRft@xsw8ao%*-+b=^!hmj(1cBAzG+7SJtqLmgLKBYs^s zA*(UiO0*VDbZdU5w_@!d@E_Q%;KmjCbpahuv{R?W8PQ&y5~sn_%&$`6n(jcPz3QM& zic_MkYNyVCXT(`?j@7IBoNg+c$u_F3IxE^>=R`-C9aKkkLYx%&s2d-Q&wDqYo~34k z`H3~vEk!G^6=&)Mv!m*y2C6~eAZD#q8+8smC(euV#5<{0sVT45JNUY$?RR?YNI zYBbY3@XZ)C)fLnLxD~MSs-?Op1_xS_cR{qoE{gM<^PE1f8_Op0ylx_!%8IH#85OY# zs)ZUH7!qiqh6IL!Et%!fdD$foHb*sQmu9-T-j1(CRz=mEjG=)GR6DOP=ti=!%&q6B zxhl7wtLA}um{nH&;8w;esTO)0*)6clvN}1O?D$TBE`iR0PJyoY zoW!y^xpZzlPgR9qMP1YlWJ7sTH87Sanaxy!u8TF!5Y_CA~u%59! z0|ki}aO%Nn6Ufgfvy&f7>iGR;y9e^ITF}YoWW<+cB`KKHN#@iK3?rjHR*!zN-8f5I z*xkTZ_`LA*IeDEd_`IAii_<>PG0-89+sWnRbQ&_jBkRgCPI7!1&XSBsGG+~UJ%-Uca~Nl85NOVGUX5p?s%pr% zL7+6Oy0Q`DhIH9%#;a0_c|BRmDUGiVvzls5yb--Oo2q82q*KbNCre`WWlo)o=Qbxc zO*IKLQBA?7uuC}gWdm8lDT!}NoM@o2YNCoe4S3#*I~VmOumrPa#G3|+ImMkzx;f)! z^Z;(88mppCF(Q|BQLqIOzf*8S)kqa_iaM8dOU5neiRyQFu1Z(a>Vc|GWv7x;)v1E7 z64vLm8na4Hd3u=AciE}n6mse~b@2s>lt=N@@6B9@j>5IU+RO`4lm5c63OTK?!cIM> zJp6iCU9cRpa%9#;Ked5ss0za;-znms2X+ysC3%INvh;1OOSf3RFKTVF>N!Q=7e;%v zzG|Raz`Csc-mst^E$k zIZ%Gh2r~ngH_!uqZ>NXT8lQqJzpGm10iFraL2@QQ#=%*O&spU3XTL>^`a6D~JHHF0-`R1zGu9d7jCaQ2XHa3f6BTveL}>W>s{3ozYQPPY{?&)(mH=GXg)=8I2DK^i|areb-fL)O%BtL!Wk4LoIL? zk~M+d#yGLrJq{|u2~aGKj&5**z!Y+)I^oC-3CwpEz>L9KJnoZ^hdQyZ=^Q^W8O{`E zGWnyy33y-MId)(Y~iQSlO;HS5l)q~DvXF2`{5j*h1`-$HVceb9lS%H_rM7LN93q4~gT>NhG&hiD~wY!Da8AFv?`=Wt1;jhH5MGJ#)0G1cyPR$ z0Oo{s*V*puaPDGvoV(sV&lYzvN8Bc|)45G_2e^}(_le*0?t7N7#d&8NdFP$O`16eJ zI(NLgo+IvfU%hYM9Y$ZhTjZV958&VT9(aZ@#RHEU`ov4tzj+s&Lu6mT&O0}qTQDDb zBb6Z@!hGPBl`8PEOyR$MWxT)8P<@>M&oHwxEd2hWp;3*=foziNG znyN}+Bf--6lK7FT4Dr&c1hbKcu z7%PvxG-@KVG+1i&!@2BSaeiP|oqxS2-c#>8v#ZW`?5sZIg%Uf2{p){?2@_@wxWDk<-vwBSU1 z3Yf`N5@u<^v?`rSNhAeWT$j+9sGm`0k|*>@U0l}GmB3oMCRkh70!!c%lb22<#?q@) zs+caWQ<0led5lx3M69F-)2j?BGj%e_VzRib#E-XP+EYRm)x~r|)-$MtSVmP@7h^RG z%*?VV+{#+2BDyG8l$-=GGJy&4MOd$_mw6|=lio63sT1B({7El{`+;XWhI>Rucb9vG zRAIH8)n#5ZH#)H;Fiv?(;GXniy6<^yV#1H%Dt3`7KD9G}nN()Ag52fa3a_9lq@udf z$W`t;=e?uIis>$<#wl+xw%1$f6;K7$N|-CWC~j1kQLv-BiY_dR$SS%B=hW^W=bfXe zpxlk*?DIBa`@zM`R#9Okm|qo8k=-cnQLR;BT?8zmm5Rq{vVigNA=J@si2K|5<7^;% zzqgvKRbC`FGFg$ZW4e$m%&u#^d@8?M!|G};q8rIQrltGK`RzzIfR|JVao3Z-$6N1h zz=yD-R{yY5RxloZt(RBj1M^WOf*X+vn_%zuHj%N%|3}l6ZdF}S7Lrxjvx?sC?eund z+r3?Q%Qf7fYq=(V9d*`v;iw;?;!-=S+Dwhz-ezo<=fMlO9wyvv#CCbxu7hjqpZ#dDI9jugU@^ zvzx_@fY0cj;2o9`-U-H;@T0w4Dz_R<)+ledx6WGtj^Nb8v2|Wnva+~Y-SGGfZbmnY z%z$N;W4xRyml{LvXm1!93%ulR95V13Y6=+( zyeZg1F9li2-E?rX$#htDIS$TPZ=9E1Y`7`06mD8Fvdi&s#(8O& zWtVBN9C8AY@!ljd7J>7^GB+04$=ta3WQ6>)zJOsEUAxnvtwvZ-=zd1B?T+_D|awq83g4)2wUa4NVJ-860v zSrN-ATYGKbx5l!A+0_KEtXs~_Ez4qgWP2~Rilf?-+s>=xrgBrem9R8m8mhGNT6+_` zR@g+Zj9b>tBgoimf`3+ukceRwcJ3tchMrZ?HE6oQN;&mT~jSjxalT9le+; zmMZGzfLjzR;&z8M#Op-7qgTo;4YL%MPj>UV6Yqu%^@_RK$tZ>ubxXRX+SUC9^<4)q3kh23oA6~>CWJ%|nRdUyl90pK8fAvY)Mh1^{DLW~N# zJy{vx6(mx~?d$dT`gwhs_xJL;xrya<^WgI`D(Lp{dU-v)KCJcyd*bu4QqawZ6>uwf zQB^cm5v<^~b_>XYvNfOeYPz*skWYJSw+*rKUNjY5mG>&(+cIzCwsrH%0*x!VF?3tn@t7S;kR!>kefhHfLbD!!T9+^wN&veLq9>{fQGxQ(%@ zU{x3m+-k%cV2#}xFq(Qbyqfs>Zgp1bV-4KeUK6jeSDUpaU=4g0equ#XnY{=qBA5j~ z(k-t?xLLhYy0Fgb71rTZRybL_;qC}lGI8>%UM4RyeiZYO?kLVwUT1@!)f?sxCzjEx z>Q(bH!m8?xW_6T1nzPr?qur+X>@c%=L)~F8Gr+6vWq@1F8^h{ow+`oO?A7DU_1zpW zvwK6_p)k|KE9s?&TixpibBx>1ZGx`_vmRIjU(2nDZ{RiZ8hQ<=(#We#te#sNtLxVH z>Uwp&`otT6b^Kk3Fk-!~o0saPyu9pC((6y@HztIhi=?z1*Cs1egck*X_WG`eFmz zI9_R8M#rH-Y;U2vhzcv+fz()ut#G4wQOS*h9j8UHW&2i+g;Pq(x_z_=oK5dVw$Pxla`f8Fn_m)3LK z@$4`Mo9!l`c3N-0d%&%ze`BS=(&T)DTUs9`>yVqD-HLg=*`<%$+wFqi=kAC5CoJbH zytv+1GD_jiy_Z{%+(OOXWJxqI+8s2%j;aiVl!Ixn?1%N@&kXJK>Q-EbbcJKZ(Z*op0M zEh6%oE z=$Tj~?+GCK?RO!qkPt8OTaPv8^$HDXuY?bO@_uEHDC zi{u$tcrTfk!b=XO#7}W2QDcfb8K2ZkL@cS77@w3;GH)ttGu)}zbZ`o@$L#SQ48>n& zmuuiLd=j#fdedM{=f;-sUO3NYxA5LJcP;yG!?ttbI-D2cIjn^9wz}(B*@|s*FHzw# zcoP4V>hHkE__z3X?nUC4z*G2VMBcg^-SuQ|bT{C+(CR6VTl?^m+9BR1*0#EvSYHQj zb+_=x9)~sIx%kb*wz&KP%KWT*nyP2rGx)QNF1oMWH|}fjE&d#_i{M4~g8R~a&fYJH zzXG4(&$DvDeL?)CTL$&K(qXE6%}}yyj{0436!}V`^;QaXyQZu(3sdwf36>;Q0xOI9 zTT|k#;I{;u;nSOGQMU7y^#+^1`d%7z=!T$j*9c}S)Y;O)@b&u!qX<|Q&AFmfDvRn| zBUV$xP8+88mj+A=dpNnnz(MebV?$7*OHI5#k>Tjy6{SK$a$BPvSd@7iX06Q>a5ADI z*B_3r#J2#ww}@!kWnv{GdV&2}D-635SOni5wZMj8L-M1*j0{G=&nI&sI1j&=(V{T* zy$EJ<>SRI@uOD@mpawV}oX`3aY%$7!5yb|Qa$#lA*AVN7T3;Qo4&07d2ebw?J1Q(1YIn2P zZyB}}^{?76lCW!LFe!c%JB|i>q1ZPH>x16gN0jS)ZN9yxuh#d$IDkIhelsyS*}x?D zv0;jbW62tY5}{%jiAGoqFdBX(nt-#wS?rpKoa|s?{5Z14n(wLqB}{YBS04Pp>>%|I zpewhB9S@>HxCh)zOi(Wd7z0(n6=?9y1ZPtB4S8Qs5cDR~d|j)?h63%~q4ODoi5} zg*-Iwt{FBfu~E76b+n$`MA}&CBTfT}2u2D#~@2$-9Db-3{{YVt33Jc;Z&}_Si7T`ndvbhc2y&c96l=Qx% z>30_X16CiR2Y4H;v(wmp@C>uZ#2=vE`hdPl;0|{B$*$kfi2H*7$>;|fgQv;b z!ulT2SBm?Es^AwC<-Wl9&Dd9_`+(of`d;+^d~LeT*g@k%nD*TVwD0nnA5=a*X&+Q= zK0hDA^!h%8>GgdG)9d>Xrq}l&Ot0@lm|oup^!jSU%+F`@LzvoL(0b24LF)tiZDNOm zXqWj4b+5P^yffI7&&I1TMZQ;IihQraRQ_I}_}86yca%6^sUCcK-gBxCXe9aif$zgq z``(AC_Pq~N?Ry`l+V?(8i|>7y7T^0Y-MRNF5ud^LXx1eF6PO9XgnTAnhbiy94pZKH zjkef$Ghn?#?J&S;gVsj$4G*GXco4P2Iq1U8Lqjhz3V3hA^!?t1>HEDwfo-BWpY?f0 z6jr06WcH5yKPdIRL-B7vx@sG!aR5BP%&^{?e@w&jbqfvaKi$F&aNdUL7QRKdaH{zh z9l6P-ufaDPCAw&+(3$WJYaP5pXdJG`&tk{<;D0)Tvzf(&83QG?D4ZcC7R`Fc^Wf`V z{Xv)SU6?N4yD(k8cVW7G@50pc-l3;wvug8+eix=>_)_^gaxcTw`Cf*p^SwlCYbuec zeA=h8=X}%z=c5r9i@kh>xQO^i!q>cf2tMNbf2UE#dnkP6%kSzbpRw=i8K1K6VLE}| zInO)wm~RZ8GaqB;%?IKXDtr&fddRl{AB*#5sJOuUJCxA{kdb*G&I7&?coI#&XTQfl=Q-*kr*3`2u9>I_u$;;dx0lV4tzqrP#;mBdm^5oiT6!~qFnb)Jwe0r8)y5j z?!vsscj$a|(z{|4pZ`OA1Mw;N6#c!aDDN#nm2evVANGoE-4VVz=^glY`Ci{4@ytAo zJx9H8D$FU^Vk0ihf6x&NhyTis-_%#M>K+?k)ng;nxGmPBc6ggQcld7JVe#BNg1s=O zg=y$b=RWJ>26tbhdN&yxO1&fxCrlW6r#VXw*9A|nnuec{kK z3&*bgQJfoy0-mp^H&dSCC%{a3AAQ1^WS=sopa6ITJc0(`6e>@ZzEWOBYY?h-1C67c z=!JO{dx=)zWGYX>mV!&s&5IYNSQwAJ;#mFQ4?;ID1G%&012hR|$%kkX&XO~kO_qmH z9h}TwQ{)#O`&TuQ8q17HavksCNvuxh-tAea{dLE_C|{4SA1Zm7(8-$!XA<{U`#OOW zY&(ebMRjl?eN>Z&sLDP3n?ipQ)n%O7r!|sLR zSuZ#}U<^kKuqQqj%MQ%mZtO7>#lE5Fvvp&)VMY$r`ck1u zmWutjFIs-&zU&j!n~F{2PVL?zzSRdyVEttE2YQ{4)eRA zHHF=$a&PuYd|&oYVD-fkf(cRKYe;TWBQMN6=#eGEPlh>#yR}c@`;n2z>W3w^o^aA@ z;t6&Y&A@s_L)7icqi+|~{bfHHL28ORV zSP8Aaa_F*^N29J1qw>}OkpykS0o+lW#F_|y5_fK&!Ph0H8R~!y@RiA`gw|Ur{8N-v zuZpMY3g0k%%IFGrZl57%0^i0v!+owvc{Bq>UKHvEa(`}8Fd2_9z&V3Dpa;qUvJQ2d zqZ(KjUxk{!wp|I75369MtY>;Ts+G@lm^vjIedEyDc!qz@ozi0%kK=yo@$5B$`@PTM z2eD^9YY>(n<+0^tK1Jzn0=i)n&^UdnC-QlJs+Xah`9eSEZtNG>XfzC)qlQJrMH7x|Xsb4C}@ zRBUauLEX?-6s%50YojJiUm312I)^pGG!O5h@HQNU!(rUheV5TNSq*MmqZS<4Xxo)lX#o}ii!f_XydC;?&DpIzd$s{v;qRlwI9T4- zf6#Kd&u9?iLA)vj$SZ;7pRco5;Q!OvYfesnW~I>LYaXVx*A&&kj#zW+fxfSQt9)nz zmO}Hd6e@*XQ2Og=;CLAk97E1j_}sQKk(H4j!AEbZ$X!s%@J3V-E{ zu4wr+M$@e^N^!YR{VRtGps$bDEle}88>?NdoXjhrE0+u39bLo*DDgC4y*t(o{hs=a ze098`ps$;k0?oTrXyBzniLNKQi1pEIs}Ju@m_Fp2Fn!23x*D(78{Unfs6qKkWp8v& zc6o!2Sq{+GvU?Mz&i5uvo$pPUI^UZxb-p(!`&DJNDvE;thrROv&!SlO_yRKt)tQkzNF(id4k{HmukcyI^m}qu$?t*6%TL^$Hw8 zJl7}Byi;~|zRm3JJ2UUh{PueIdvjp}7WkPCC`Mpme!CE^IK;d;F!ttgU2~AL@bi;e z0;*pj{P}PNXTj8)#j!NfO2nk$N+L@_CR_m1Zw3s$8RS}kn-Bdjjr5yHUl5lU(q9<} ze`O#X-bl(#@YJT`rxGs(t1mD94Uqb#!*83;vHh&e3 zIb29NH^)6l{(Ww4;^m>frQk0jeIcZ)tML!HbL~0yA@_QAQXhitbG^OT@D~>wF5_bI zEQ;Gp2@gVCx(fc%VRw!_+dd3yXpYSmd`Nd5E-^;byt`rNiL>_r`S-dmM~>>G%>=724u1or zzPn(?-9?TVQj=i&#o})^e80^c-4J)$F#1j#M&D_}=sRr~eWzjV<%&7&iN$x?uqaO( zUf*fM>pRU`@ClT$+}yPQr6wW8{ksnm<5CD`OZkQSL=TL!-~gWXERH9~Sh%b)TgY=? z+)n|E^sR)qz&2Zg|08U;)8011Vw>HD{|Owu&!Fsm2IWo+zWtE+4&t9C?Q_HCI~{l! z^4>#nry%-$ZrFaOVdWhn?Fcy!ArHgb`;a4_L-_j~lHMZ_{|-XaJIJvQNc#fX-xrYg z9)$zA5BlCdj=fLXm$3c5fp7Rep>G05q4@2EwYHaBM{$qB0DPaLk3;Hv0Q%Ykq`nLL z?`w#CUkAPlJVyHCaR1&V{0{Ehz%f!DgX^{%|0MD63=#0#z!Rh#g9f(?|4HN%$esAl zz`uJI>fW=k>BQZ8HO{B=y$Pf5jX1ISo({Yn_h#H%aiaQ(?e{dfpTa#CI7yy2<4)q< zjyp!$bFlryzIzAW-z#zN;9f_*PL5L$68{AwPSn0rhT3<^Q2S09Uf(J2B-eS$Q14C| z>fI?gcyE*PHdlWNn%`;fDCNEYFYp-tyOjS<+~dSvfDU*98sX!FP6R%H4fryAvX|rD zjr*F?PQly~ukUNa>wAn`F9qHw&j)eu!{vJk`4X{5;Q+n_x9=qghwmAh-+LT=9}?iB zq&$LqIq)Ir@5LP<_A+!pu>`-Oq`yRA+at|IP&pvj@@8E76v_(=pXp60QkTZ_Q?Iry|_Qs1qdB}ba zLg68H%Rd+Q04aOf6)z6uGW!MScFSzh3zxBH{(0nwknZ-_xAA=MA z7u_!?=S%j&i|Kbac~2Ws-oKC{@7)g{ZwF+(9dPHi;qMIG!yfog;_ktH8n=?&?~)<} zW`I2PqPqqD-Zpr8KgRtO_mKMv*K@Be#^Am7=TP67Zkv4_*)?WZi969 zW1I!g?gz+xf#ARS?adt71yAqa#AAZraV?vO?}qKS8>ZqWXn?x{v7}?X41Nn)FeAVH z0`$QQ_!~LCHxME{7N*xXPzR5>uW~KNa1Xf~AOP-#`L`EZW00dE$X;JV2wd-81%+?D zJBc=7y}Oe={p$_Yb-lZb9sldyThT7--QDm5I7+Vd@M3q{>nZ60SbYz`gp8w{AWX5Z zUI9L;TY!&cD;=;JiRgS^uF*mxI177Y=B<0gC)JI$UTnTb6>C@ z?h6=qqYaU7H2KFkSFl^|bN0Q7k~fO<(d>LX0NKysEE_i4YIf~kNv_Y>6L%mmiv4f< z;6RQvguu-4&%+DK443+OcZ9Q+>m0$+k?feelKky(pL&nGZ}8tdjynoJX@k4n-ss*B zmtZ5I`|aVJHG*AmYxob_bKa+3d)zn3Z@h1j-+JG99h~-#`l0>b|;Sg+v~(GvLDz3wh{{8 z5ONN6M8wMq7f&R;TcO)6ftj}iF5F;4{~K&5e}llXAW}W*zR9mWihB(DP%Y`bK9$8h`{&U1r7XFWU3gX9l6_wj$+XWvBbJ0Jz#jGqeGFDaOc zOGYM(jYs|!4Gj6g8^qVG=>2AW1RWqTMh+q0e*gt9W; zK8|lUB*%YZ7lj4*iG3PBNIWS%$oC(T<73=}_^imR@v(e;A%RfH4MH!sAnPR{6XFAI zn0S`>Fh`Q&KedZNAN-UrA3z`Uy0d?9qSwRe?o9H!vD0u8jJs}pSpmdl{7+6i=bz;5 zc@7zNv&5fto`XO+!RyJsstKGm5hg`f_Ap-Mb>UgP3g$vr!ry!U@;>7m2E~Ju$vJ@? z^F5u(P!oDOVkh)+dh!JY5j=n7SAKHd;kyvey6@nQyW=V2U+hlq?euc4V_#cuWG`om zCoW!j=y>AhO@e|q86w_f$a3#;_Hp+I$AM(}17-f`T+3P4vH!TQ(}!?Br!U`5_zBqO zzsd6hUtV~Z{O{qOVJ~q%a?D^SU_WODOu7DiFX1Qe-_Cegd=p{lRfeKx#sB1e?@Zv= zt~QK7kpd?Yn?QUD)VqpYQ#D*=WMwFN|8lJO@0}|+J_XL7XnWOR3|54TSCJgo@GCRe zc|Qw=-Zh4yH;x?FK>oV|zXmMAauD~*k^4K!`Ij@6BiBIwy9Q!pZD@XFAd8hDS8ZI4 zU?AR#|Bmk&1dwCMH9b&^Jhg+<4G(a-;Q>zPx2}QaHytA7Xvl!m12u!C$W;?pEBFoP ze(Q|l$TVnw(;!aP36_8eSjSKS>yWc%Fa}cCH}KKnj5#6*&VVC0BXDh?F3(U2$YdqR zU5~K%WS?=zr+FheI*n_X4qamexu<#82CfU#=V(3XWuNm^i&!{iU-JpLuVA6a68Z{K z-xqv2q5((iL-+cD?=KYM+Ymq4h50VS_sBx{1^IHskH{Z6R?yqx{$w}gtOmg%aKOH| zi}0<4?~vc~-2~AazjO+CTcMH{@U}rZFW}t|H@$$j9p-ugZwJ)&0#N&QAh);$;d~5% z$~P7I-Z11ah;387;qct1a{bc`xo;}$r0?u+AvzVo{}Jxuzq~^;~P}udYiqnPjTLGp2}yCPZJx? z)A_WU-}{npN#yswvcE)r&G!-V!&CYi`33)Zcer>xq2~33P$#BdYsh+H?v19@H`#Cd z2;8>Ov_Fp^-^3s0zR%M?%>95bhz#Rv9v>jzbB4Pj^mT)<*B-{6n13Swb)(#_II-{A z!`SOY+3k^S@jDwbUT2Q?f}Yow)XoqCFGF6Y80^2^(EfVE*1Mea&M*M`KyK_vTAx5S z$bPLLleL1nH-_sv!d~7ZQ0B(qo?uV!M|@vosQWQr0U7F^;)@+axz1s32hQ#f3$Q<| z$gVH|Tf#?cNh$3~>j$f^ADqc9q<4jv)(nPU7hDTCf$d3ehZ_*+PI?zOZB6mT4jceM zZ~%nHwzxro9;Ayl*95-}X@g*;4dTxBB&A1C47I7=Wn3e4GTf8wB0j~H4RKF9r<@_~ zC(dc)r||Yuz5HIoU@EQ=vJv#kRIf2*qgUX-Ye(b11EYUAOw+GN8r~YM|}u_^`YX4BUl?U-bl_EhZ`HLPHIE= zf3@(hAYIhFVffWZYY3Nbn4#g3j~oyjh#W|)61kcN+HhA^vpc*s{vhgqFftCkG>Gp(e1RP0#l>I6wG4njHh?oL za!xZSgUtf7y^7ESn+D2og=M`8q|Npwlk=)zc{p#gy{idN4vK|4$Q7w=wl{^8tAk>< z&Gx1eo)Q$zZMHX!@Kktzxd}CQSGr}q=Fp>8y3O5Y_ygV1l+e^&MYt)hncIRRWxOU_ z_bT>2ts=E0X=S{YxYAxLVv?nyvoz*ETg`5$)#Pi$p7u7#HpGjwORALDkd#L3Ybj2+ z1g@kfj^12odh_t}2MPoV2J+(y1=tD1?xB+8E$J=b==@-PQW~(2MPxN3e%?T8APuVC z0=RmmIa0#Q$JvDfV*aHe(}?9GUN~?QB`kn{w*cy1MXxkD^KhgvoV__5xfyp8#J$1 z)V|8m*POSUH=!-RWr)jfL0=x|CIyno{|b3tb>8OqKsQSuiIn}s2Dum@I2|0%R7Yb~mgmsYY)^TJLZe#FP?^)-#bF23pY%jbTVB&3t54Z{z-YU-9jN1e|?_NRyj=Qh`MdWk5s_bWRylU)!akvK8vpC|x z`AdWhX%R{cY~!r^Agry#@4$YZ>QEMH;&-5)YQjG_;ymp1b02YzARmSP-j6!y@BU<2 zl(3bvwn1pS2meRwCo2JBUjkgpAA!zh2y7vJD_pm`@qe&>v@!(lH)Oy2N!bF`_8Bv8ydj|JZ+bjnZwKd_E+^ifE8k3!vhht$*7I~+M>9V1;#y~FrV!0|hTJVfjX z+_B(E!{0ke-qY68F#8U|N;}B0w;}R<4(IPA{!^qs4fpSDQr?29_$l&p{3qe`9f0e0 z08ZPRq9DNe*-=|O%-@tu|e3RI5@`$gN$9oWd;2WgBj+^N{OUm)! zYs6-Hui@rFLn+wnHB_rp;*_#e0cqv4t+r1~8Yhc1Cyc7=dG}5QTe7O@gFI*}231^0T zj4uq#Aau-`O8PX2Eq6iLo$4<3?(*I-3_YK@cMMkElMwfwgk5*7dz5b(Tnq8(sB@IG zr>yIEX8Jcf>wU<3?*$(x^py2DT)(5%2c*0Y`R*jFz7HS)ozhpb()lqpn|;y=kGM`4S0ah!9si(I^T21 zBlxE{dK&uQ!=%sTy86QZ>I;YDW71DSDSH+FFvpHV>3ax&3v8%3NLX8pjDw4Hh-1$~ z`#X&P3Hd*UPxlJ`edH9wD}=v|d@;za_y@`T0@T1m_@9#V6F7Gw3LYT!MR;c~T64Su z9Dl+3jC3*bPT+5b(iMU-7NW#8loaFbC+{3@3fJ4mO*Xu}WC-Xl!Gu1+Imv`h1Vu)h z<9$Kw^WY{**bL*UBk$^iFwo{8=fLRvlA~Wh`%5NN$nC^V+# ze@&jRf&~Z{WC!jhn1Myfu?blO{~Nf^$=)~Q`8t@NJO$WqTh!g?eM|Z`!3eR9UK(7C z&Tbkmzq`SUkYckFcY~LY^fWgwGM~Giv<*-W9roY4u0uSP^t^5=^o`458%*KD*IkHQ2<37od3N#bTk-vF;!19IH$dXs z1Z^)i6c<{`cXV&|c5rkjU%K66Jpfa16Tc<0;3nvK0dj?K!O&X6(~E?DfHJs_@LI@! zTk+SCcdHc+{Yax3CVvPSA?CvM`vLhwFcMlr?)xG6?SvJ%hR{ySf#dh@phF%vw3@UX zmTfqGHk`ii!7_Z$u~m@&c0lag0hjU)zSeuQcL(k!?_Scj!};3|YtrK^J9Iz0#S+~6 zsjIc#N{;M;3%JYLZN-PO@=U}Vu3$Vlz0hRtWiNL!ceS^BkF|sE^xi|>-H^+6TYHdu zNK4?Xc*t08aa__db^F7wP$-CW2Bu_$U1)RM5oeYE%A@OC0 z?|&EH`@PZI=ByxnyO+UDbhmSb_e0)WVQq6Vk|#rG8Q5BYnBE%(=na;@m}ehnJDvb2}(`JG8*NtSx+V^-km+7JNWw zrJq>CHaC-PQDqGNW2IfzeFfpnb}vk%ge$J#9jRQ zPH!B)(G%9{So~7t&cQc=O5ztLe-XYGlmi~3$M=PDc!fwQ%=dmWLIRx6)h>YHv4a2h zpqIoh$b*!*%PYvyLVN)z6SVhuYAACk-pLGqF`kk#g|6Utdb$Zt7Fc-+d{Zb(r~o+& z!c<6R$K?SpEBiMOP})HVu~(4uX2^GoVBjr+Rww>lE+}}S>h1Tkv5RxRmz`ai`#I}? zcMtDVCgd9Ym4pg7D~V+yT!60$6^59X1MXg7+uW0&dUZxD;wt(!W9n9H*CH6hT}J%66RU?DJv(Gy_{T8e#*`f5?N4u!JD|^8_7Q( zc{6?*Ir6~Z%fs)a;qoE#lQxInyA5vNT>OIkVj(zUA_NvOM8P723x;NsV<`l|rPgMs zgL8-#rRI{L-6isMrK0345}L)aP0lQGZH5YwgPpnisG0pFdU zCX~g=jLb}GRj;dC4f0DjbZ~XTxslcI%Z8GiEKXT+mIQ_h|b38x&P z`Fug5oITGiX0PR2oW;ml+-^!a&ER2-cdvx|w-0hlE$-|-WKH~xb_Vii#9hz#Cf4!o z*P@(T%q|KWah>x#1ho`oZob9yJfYl9Ci{AKF5e2sh+o7I7>gL*ViEEewVQYo-0=`J z#zWhv%`fdm*1|7L&LZ&jGud`j8O+?aElcv;9X$IU|C zxo#cKe*h|CZTuvA4g}mJ*zR*&vFfTotP}6<3b=UVq1laxme+`K8pHWcvS+(5^1Y$# za1(PnIgl^l4~IiJ8TQ>I{1Ld}Rs(2j72vK_fPpuR_+%)3lVMs8!%ea3kzOB;TRDh* z^>7tn^)(=8U0fw(C3t}&DQ$#d{Y|kNlCxfD6xT5k8s9{YjKYnC4Oo|)b#T=}V(^WF z`&R?zUR`*YyS=*nhkKB9@W=9hOn^Q(4qpsHkq9SHN^Q=p4j-@v+`rnCR1I03*buIA zDontsR$+SxS1|<+UOD)7jY7$M0jiPV3O3@&FB{4V6@9kobmVNz(MF*`gbLY%;MWzl zn}o7D$D`YnfWplE^>&r@xhTc{1rW;bvjl2O?LA!uG z0N!3fyICkZ-;ioX&ZeRM)&Q%3-5;0VZXSA(uRk^CXftSlFL^I|{UG_}w_6Zy9_mXd z&F*XU!*5ASi_i%;nk_?ptTa2H-3MM^n%#=DmZ9E|1@qa^>>%EC#&v~UCqAFgue%(I zUFT41=!8As-}S=pX~=s$A@8*b^~CjpGk4_mgLTBwqyKkr!dHZrbt&o?6`asg_1xv3jq`qEO4{-xw_4USYVdb?` z?G~J!*X~FDzM*#HX=}AJEJ3jV+lM;xe{_XD*p1YV@CQ31yAtchu}+3G*dEylE?<;V z*q&TniFbkX*A2fpG`v*1f9PfJ1Vp|QUcXQ?;(6?5u4V|eJ>v}t zRfla?6K-8iD12hmje$@nPTgdfdm{{6uP)TQx{wN|hK7+g6*oClo|JNs@#^81hkaPj zx|-Axp)%xa2s^JKY(dfX8d%f#m7x&qhH~~a+*Bxe^*Lt>xko~m8wne53Y5ALq0*eu z2s&LOu5dbMO$$}yx@tl8n?jz7Q2Xjb%&QMMuM|0Q+9KKIvaccM^iU;^R)nQj3u<7c zpUHt&an>ZY#S1e>rL{zU%ED`5&wB7Gw6ije4dIqj0T9QF*#ye1SS8CK?u z3FNvG{@;}l|4LXnAcu=;m&3l6oHIh=+-0|~BYZ6s%V)gnkk`Q-JZ=bui`}buyOQ7$ z7O|EX=H3#Rd)GsZyMtIVOv3^Y^a^l18J7gxE{U9X!Zw@@fo?W=?!?^zd2R`3WhH+y z{JA2q1v8Vk2+X?U-Ykf9v&feR=3QR+cX?p|ig9-XWIOTgmU8y>$m=2CEyc|bWuu&| zu<#1uXM@^T2rgY_%FKi-W-X)4yI|$z=U8?__PdSq=7%!!e`d2YlA}0`x=i>P31ufG z8yaRgXDth*@ca3!9GsOM(%^hZfw#i@n;#O@ZnnFEJj+A5AqnP#DVUF3xp6tHTe!}f z4V7>Kasjbhh%fw^J-C?ILKuK4FaQ@p{aXmHF9W6BO=&CO6&{CFxDt5}+_zOw_1OLl zfp8Du-O%M$!m`_gTNMi1;u4CF=UO{Bwi+7TYN&NK`6KoNKd5HZ+yRSt!Z#!;%h;3zX{9_v{!Lc8lEooV5=E-zG}ghP)5C9)BBb!S#j^ zC}Lj>zm-S{@%C1Z+!soK9GGYy;N1OC{kD>VNzzKN50Y{q)Y7{J3S3L?Rw%D6z1!Sd zkxSruw}eH!1i93`9l4k%|3wIihv3Z}f^zo){^8I^k)NQ}eFP2hr^ri`b`YxFL5_St z>Q6A+L^J#V7qCAjkC=Mj<3G!p4?%Hz2(sO?lyn$g-m~6IAu-?r_9?iF-^024p4`uo z;|Q#`XYpSq&xz1`kr?XXJ@Uoa;>rc=_FQ30?{wq`&O41e6?vXBj==SM)_XZ5(%d5V z6T|WQ1XAA*u<(8$-*Iw00;}(N{8!2OO6VP^af{rqpz3`CSMM8Wg2xPh?^x(4{%hoU z6$;=Z(EFa@yhlQxQsyV{`i?@?`+_sRh4c3vti3NF{e6WLjqqu5AB8e_6c*ppocAcS z!e_nLLIder9D;LP7yl`aJQ4CafuC{i=aDC&0X`9GXD@e`xo!Dxmm`6rWqdbkk=uqZLcPQFUq-mK-I4D~-Q{+~-3eFu5WKHJ{MsR}JV)+yTaoiJ zz8iHX+~x{=SL#mpD?_FGnrnL0ZTun$S~`FDU6GyuLxyLkse^blQ;bFkHRX`2V8J??R76TG}ma zarj!=&v5S3Q2tKB$NLlt+erw8kCX36NU-+Cr;+^`Cd8`9t>{OY^# z1wY0AgwO|}7oqZ0@S{*!ay$i5uMB<@X8_#uCggAGTxs6{ zll)41soUNg&zCzS+k5T2D@ebRuXj}BNxA}ehdY5Ue6-_>9uw1p?riC7zN z4C!O}wnr8G@{s?YgvZyNGdpvvHDCDXgg=^ZdR5`eA63ZL13qITNPInz6`b7UwTHQ1n+b0+%-+bc z=5`j+Gl%bkQ~3~-x`!aoiDma=s0-g3xy&0$$)os=NOk-Tk!F0aY(r!teiCP8fx`A9 zl)MDUbw7r-z^FV7FYhp=tdBJ18(Hfk8}O6EN4>|rWb!A4dqV1~@AQNM*}zGJvu8nY zOTga>8}k6fxQM@kAHgj=Mj?;tEReaIxWD zkoxL6z2H~YbN0aB+Y4)NF9brd_2S^_iLSRQvO3a`@1=C(SB6pkaC;Y}ZHMhAZs9J@ zcrb#Ao6=ldD7>4LU6BZ}km2)%!#)X+g?q$V>WSO|6L4pw2c@?1Zi+PEn^vX6Pk6_? zGRV?l5!ve7H!?-KSc{$+viSbu1T#@H;L8KmE3R@7l0e=z1#Z@r%R&h=-!_zAUPcJtdx01xl z!{4jul;^B+;rWreb{$(BzPk2e&RPT)ZzcX>=#eWU#W^E4T);}?t`M#a^9PGjofA!fJI16ga20)e<>-q!RHf2urO(9;X9%EErZ0jj5JaB@`m%1 znlF3@@ue{Q?!+$uZ7|L7`SSnF_bWt7fpEcaA>n}&-5g3@Ri`=sS0yNTRiP1H!T(mvzJjyHL9d%j z>@rAwt>FFDfb};TX5LVHG;WC9%#iMy8A@I=&aM=`lKf)f&B1R?{>xwn)`apW0^bmO z6mGEH7?NHU_rZOGX=JTfvWGT0u88)Q%5==ewz$Zl02$5nxt*OokO zkhNd{j);tm46-MZX96s|+4xP#Q4PXe6a04MX^X54(@$)|LH2OmKwI>}f%YWwPlS1Q z9eyLusSc~JDgIT4`*#)TlOhdCtpWM3Mz}Vz5wR(TE;xleS3w%}Hu*Y6`rG|%k>L8-V)WI4*Vh|T@lf7) zvHR*cL&BZNBLdt2yT3gcwq6})Fs`;UnX<2jC0L)b+H-ziyFDzqe)cd*7z*8PfZYjt z-9WzlG6=$6ZD){Zec^VI_L07JJ6s=oI5~$w|LemSKQ1SySa`$m2g2EF2S-ozyn%+E z*EZ5F(#LL#>urx9|L|}Za*DDy7{4F6I)vLq+D3ZYZE(Hpk>nWx!>=!2An6K~aWKTX z!Q}1_Ev^GZx(<-`Msai`EW4o`?}qCd89-_$=y(0``x5Gm9Dv^)Lf=q0bVJG4hqTU+ z{5r$2>tRTMJq!u32YI@~hU>}qkE$X?iR)$ev}Zx&>jELK3RJ1Q;qrCyX5#w7-m4tx0F$o^`Km)oYy;n|4f(F)nn%If8wE-3I_P|T;rUe} z=k?^A3kOeB#TvNkhR8P>8r^6(c)hva%aNCdyM=pm%{^cUR^+UCoOL}^y%wBT6IUZL zoioP3fExqPtvk%UE=aNW`obdY4~?(CXorT}*N0GV!hKa9dAh^z>y6(7f?;nsetksn zBitig3#MWVXmKt0jcX`-EbO>eq}7It*9zH^V>4jijfJ2$7T#K}$mL#V*m$`jo#F6x zh19nac3)R-C9Vrpxyzy9<=|K+2z)v5SChU95?>eopL@vL#Y^G;>wxS4b2x?kxg#R{ zb@JAbb2Y@hdGONiChxp(9&)C@RufgR4%br~e&9Grano>DB4-d=%UNq+31+8+Y`Biz z3PW;RK^gPm&XqTmH_;YF6zu4&BmY{MZer8j1;K9tJiT&}RQPnI@#`9fVO>KktjjOf zfn+$1-#P@1uPaQujbez$I93T(tH;U-=Qx9$k}A2w{jZe9%6 z-Vv#D_LF-ZEWZQzZ-n0@*IT$ZVfMX&|F(%gf;<)#if_R~Ek!#KI=XCS2Vl!`qu=hu@gF1CqmcU^fU&n1w~=j2 zSt$J_(jSAG_cdp~hkF;6T`A5l5D}-b0IpQz4oX=Fr|?ev2RU;SaxZ>}5}5Rb`j{p1 zK6Jsa;nRIhDJP)zJ%)S?W?f;*DF6X-VfYs4jCbH4<;deuB91V0PAk-qs5iytx}3^&+z!X`az(!->O zur9@t8jsy70jpRBd=H2H3QJuEWCr36R=$kLjKpm$gqe_;h)1wJW=3Wv9yV6XFewpA zO(qt?h55~_#DX~emcGalhYRwn`U*!ZPBt!!SPU-KT&pZ!L33px{1{3JAwxeO)phIt zkR?jex040UaRxW!iZl7C1anOJl}|OG|2T;6r>We4`F)+EGW8phDuvJel2gCWHcHZb zOPtD39@VW%Q=VVfZM0UEU)TP3uUplP?w4N&svFg~{&Ur^>Q?pm=hW>VJ-27pt;bUv zZ=To$^QijFp4DWe zo?tzzS&@2z^{i$?>Iv2pkR7Qf_)>mu|EO;DRHxSofA_jQ-{)3$F{&A)2hK((oNL`) z$~wXS@1^1NrmF_@gi8ymW_nHqwd~Tz4d!hRY z7ou+eF3;`R*6sP~+Y8aZJyYLaYHiuMKDW`j)p_UAPq+|ud**Zd-%__1!wz=7<1*j6 zC`;q-+iH9pW7J}EZnhfV#u&BO{CT#T^y9L>dhBqi>x8rE-=-h)UQC_vM}4sW*1EkI zI^kUF_U}06O+R)>uM_@h%l_{F3b>+4DblF7jfG%l@cte@`cz&DbG2YPgW|ywSGoZ0!l@+p>T931`<&INQ2C zU!8Cv`Uw|WC;X@DYA)n+D?J@uT@%%}S_5;T=Fl%zA1rD~_%qgiq;Jd4Mki>kl5}CT zZvB-{(HZ&+SGSj1KjA_?xBuySuyeJ8rGIYy6?cE$T04K0oxf%&{n#P>TD#~fyXcyw zbFJH`zSVirwk*2V&VN$>ytQ`cTDOw`bdy zMeFu#`(S6&mi@Cv^nb4rjke@xuC+`5-2PLy|E#~gkoxxbbi$eX_F}bV|LEI4UL$%b z^%E}inD_VWVE!%=^%kP`1b=1znR`jjwJkf}y1fw3?eEp?@7clpeLB%y4}ZMh!M7(w zcRlF2```N={INrH*Tb*(J6x=~joK5mTj$TRC!E;_i;f+BuWqBYdgfjde-Bi2N6Go` zCHYVF?b-AbE|xvv%(}f;V~5{s%c7%(=$Q9h+p@E%+u!QnUWn)R_jJPFeea%hNz|Tj zHtWVOgucC)&u#iSo%C&4RMY+$`^(PvxxE;5d%pTMs%f=%PrLSh*}?b6d-pDdw(Mfo z?O&x6&a^S6*SG(Sd4G9g|B5}Q>2<<|UY~HTHpZwg8x6wJBzj|NfrKS_ow`D&2K)qIfT>NLwJ6wq8_G0#L&xfCIuFviH zwq@s2x97WN=|Z<<>DPm$pXdF(w(M-@%g(oMFGm0NQnn}j-TSu}OW$6o=k`*z-(G6Z zZB*Z$k52fjZ8c}w!7jDBJ)3^QxvmHMEgR$c=-YE`%hK2FpS@phNBZ_moseGN{uOIK z&YUm%J3qH)*6rU>-==TNE@gdtsnu=txxLW++w;*0|KId&dV9iOJ$5+L4)*``xjmn; z!yi4jm%6@<>V&iHgPpIwy%0L#zpZZ5>x930F7nK}z0~?(>HD{5V`Gdyw|d?$w7&hj z_ixkJ?S-7vIUjv{u628wS(g!=+enR@TEUIs#bLe{S zwGZvL?6?2atv@ln{me|xSvAv$)r)c2wP6?2jQY298-efvkx z?U`fVf5r}H{~f48^yw_C5U!wAnBH9g86aMSwSY0m7~)0QuNI4pC0-1Me;hK7cyW4y zL1d743BtvZ>SvbZTSQ@Gn0P6^Q4~Q&h?nNuMK;nVUIuQigLH_O zDP^tl=DSGcNhxPlfYgwHOdz$Q;Wkt>Uq`A)dIhTz;fhve^Npm+gezH9%r}y%kW$&I zYQB+Fm6R%0HM85I8Yxw+>gF3s)k&#l)i8SoYmidis%gHFRFjk%RxR_5q*|oZv}#*9 zh}Fi`vg%kliPgc?w(45Bh}Ff_vFcg5iPgi^wdz|b#OmYfSq%u+N9MtAh-`pN#czac zh|G)M7}*G!55EbrF)|ImiIpF}0I~^p=AZlZ&;9!6{kl-^m;bIcHt(JP{`qfYL-SVZ zP0h!2vUN|V&Ymz0L7 zVRTLnV%gC~S~*aiv}|ap>V&HqO;y$CuByb6(Q4X3Rt1fggtk-ft1_`HXh9LkD-p|# zc2sYzBC$;9OMO?a0pkR^Op3XEbd&(h||Z(#K_tPA)?%9&IgMU79ox zEiN5iikORbmu@df%t7l*=a(R6(|{e(4_l`mU*6`p@o{+QjIc(!JCDO1MDxOZVv4cTN3*f9}`0ykCFE`=z((x85@K zQ~aLGuivb**N4)9zi7prMjPfZTJg`+hth$+e#@i@b=NW(eVEbcKJ_BgYen5DX~jhI zMoBBGHyYK4(t*F$iqeGAimuUzj?sPU^QPB|(uC5A5u*X4{blLH(Eoa~fVY7Uyqnn z5B~Ra)e}wSKBsc09HaT8U(r>q>ieV~|C6+R*!-v36Y7}j)0oXd1MABblDhslqnY*n z+$@B1;>S^TPPD$-g&?V!O-qmkseRGvv8&CihOhp7Rb(do8l%S5~;vCPQKoUOL4 zGS5#(-5DrzaKbuV%i|3fBHGvdl}|1u(1lbRKol`C9H zo0^PFCUQWqAi1ZLBe!)8er{_9er{_TDbuZMiRHGY5}t-!kAEF$ zxveRLr&=?K<+iRSJjI%fyqf1`CMhY_Ed1HX6l()Vu0pQIU&a$%1X&D!8UIf)WD%}l z8UIspYYu0mSd++ml{J@GiZzk&B^TtofXu$6A1&htvhgd6c%v8f%R~j>F$Xx#N%<@$clVPDCbB)@Eyz zH4-@*e>1s9BRAovS|cbsm1852!znS9BO`fh?zHYeCgA5KB^7xezDMd(WITR8Qt~3V z;Jc(PMJ}~&=S|o`YMQkbKh3%U-{HvZ$lI+YR(If3ejQf3ek#l_v*5#yju{t9!xB8N{$m)k% zi0q5siS*7^e_{)*0r(58f%ps2F*i_3z`7AXLY_`Y8$V)ov^pR=;fJj@R%>Ki{IJyy zKWw$f50j%kGJ+pN39^3Pgdbzwj32U^Tg{Ly@IzKh{E*cOKV)5oAELy|kYW5-@@pn! zA%2`Sh%1Y;2II$(B5Tw@{Gc_2v>@%(5aeJ|^~J$v$R?x(t)}=v;!V*d(kjv;)zBio zZ9qCr+N3&KM4CogMZIw8CBMCpHmPY^jZEg9uZ2dDrcp~FEg~Hw-63ru9V4xx)<*4y z`p+4SR#|1VMpmO$q%EX})OJWiNXJM!WHTCOH5wv|(Io0U-a}q#7>yyMVd^3^&QPyA zqtOo8jfPo+CXm*VhLKj$=tLT(p?UYDRn!Ve!(=p?B8Sm1YmFw6R#DGd`lJ!E5!z)1 zXE)@nR(mZCv(9J|X%)3X(lC0nrIVynav7a6-Ds0*&?VA0(jzm_BGNR{FzbyrxfWd_ zO(Q*W9U4WNX0p*SYNuxM*3Lw)NK?!*nqo3ix<{HsT1BG=X_(?jX*lVb3`U#GMwdtv zNt?_;TS(JLr_43F;Cl1sORHRIw90s+RVI*68fF8UKw3%~Cei2+X_aB-y`N{a%6y|$ z78so)Z6zHctuoeVm2qelX_$>ht4KFUOG#fytBf*QWi)3S(Jtz-Nvmu@t4PD#V6=*QC`&jl zopOuODcy}8>48R(zUgXoj5J73qgA9Qq;I4(78?!I%jgsJXl_NTNW&~KZTt;JkMu^P zNGEkRI!4;0kI^H(hUtrrkk*k->1T9GfAhu;Kp#jyNyFS|G>No|G?(;6M`TCN)cY^3 z(#B|&wnnS8Gg_rRxujtt=mzO0X_%XkH=!l;=1Z$IH(I5I(JC#CR%vCl%4L))4I>tp zw2?H-LZeBfRR$UTA$=naGZ4Ko*l3j@Mw3YQNRz1FqS2=`OjBf2(ljR5I9;PXjo7mx zHEP#5U8D76j%Yluk-oYZxjp2RWrXR;&JPmnbrCz{9a+i0w)zD-Uvj`WfAPG)q0 z><6+V^q$OXAGvNHHq1dUS*5mqlqErKi!vM|U3QN+}KGE#RI3uAJvP_ z$baGQNlL?4&spu7dhzNrry$cvizAd~{tJ-+KdL>ABV7I~ z)wJvp9{->2hTg(>{(s#UjU^H&Q8lUmSf#2Al^ro9soYrNDoN$W5%)(Rs!^9Slwaq^ z{;HhF&*kVURHk3rFXiYeeksl6I`nLYaETnzh*I|>k>8W8Mt3NIQsVh9bf4q-O=)o5 zLC@S5-J=+DJ<_?l91Xie&E&P)wu z;tr{%vfxW*AT^0_7HUbgrqu^Y=x`5N4JkXVYF&Cg2`%rDDvd6!?-7^&PDYP=#B&i# zMoR1C`dRC!P0$^vjI4}~*PEiZNAFHW(kk&D>Ak8zxT3jwX%XEgjpcKq$6b!;xpT~a z>!6|XkY0}T@}@@he7eL{gAQ+_M)rA;Ine5Hq^nPn0}UQWJb<3bhm?giKq$wrG_Z86 z-Vo{USfk@(O*;^4+5z38GTaI2*BGOxV~j?RF&bTWss#5)TG=vMS#ywjvNh-E`?`;@ z)T8cWHKgjcI^n96EZac%=eiA1mvN?U^{lFfL)2ZIso@}ZHJ7=wxlApo&V$rq96400 z4z(EfbFDhmTpaOu>c^wj^bV+29qzG9s%lcZ*!(BL#m_`c8eFMaIPN0#7G^Oun#I&* z7E&{rddy<#F$@1w9KRIH{V0c2yBuTcEymPajA>nCI9AsD|K+HS7-~0QYA;}FFJS6C zVCp={+><2JDkhnBFUizulBv}sep4-)o=Men5>j`>GIvB8rI^vhdhU|Qr~Zb8w20-v zX_bJl2c-{X@sq7RjZ$S1Y(h(|R$g-=jcM6sdv8EJs8^7exMoAtbI@FgdJ(d8sDI)2 zH2j{3`XTC#sCCt>NFAj5GJdZ{v#+uU>ble?s>L(l_nXv5()_LFM*JRDHjb(1Rh?%+ z|F3#q8r!K|QqQX@_gwczy{#(TbKNQRttxZRbr*e$k>)|vThd&KWgo?^ zu0(wx^@L=5*F16gKan`aha0DPZoGdPoKTxnKVU z_bd8lsV}WJP4iZIpVGf&dZ+ZR=`GVLgXsIEcPjdpX}&c2e(7zBzGYg!;J;cxv^p^c!@0Z@GGvBgGyh*?Je(9b1^;@PlOYfThmi?LUm)9%YGRL{W3yIrd`X*JFHPr9y2mh-y=7+qddHK zvLPj7mCA#^jCVf|mgPH1Sx$Hv7N0u^uOPhK*ng6-q~#?x1&xsxsb1U^;wyM#ZzpGx zu>(ydeTuQ+Bw?3J!xAT}P7?OIG~%}qOX5k@6PjqA%|!E5CenIlCPnthYsfj>Sd-Kz zR_+91Nm%;QI3}x60+y3SNZC~qj7=tie!~pxf%$RQA=8K*GIqX$#@2U`*evTXN3KI& z$C1OhL)HQ7AeO)bxH;BC96fC9CpHH;2dm!0q&#HpBQ_T~7hB(hxOvEZ_;+*kVJxEg z3GF3q9&hGeBW2Hv$1OlEzycL-tWfdBh7`~BCSY;R&zTR9KOQ@6e&TzG#be#gPkcAA zcxxAaJT~3@r0ygZZ|%U3H$Ah}$ko_#3*gow*J3>_fLo7TkFBu)ZX;S_2l+ihn~Fg^xLt6?k;OUQ1$Q;J zQ_cEaL9S|O(98Hmo0hLJQkFK`SlVo3X|s)m&o&l58!KN+j>^Jk<1WK`S(FmTQC1D) z75Lpq>583JR()A(YtSB5r1#aGbXh@5;E&;0Eo0HGNnfu5X|n5=z+$R=qd8U^IR;-= z{SwBaTN^2>ysY?T>E&rnqsB!&kY({@p;t-|Y^x=4y|Aa2MD{`Urezq4eK}%m%n>ZW zBM8eL95FWI2>-j<6WRMCxOzz0^&_|jNZIuxxJJlP|7ls^_tp}s(LY@~6uLo5SYPJIelfz;2C?M*Yo>NjUYdh}AVA+r&W zHzR;}QannHP_D)WviNA!um2^6cQrdHY8y3X(G|;vrmM@&u|#~e%d&^bY9OnS>{-5b zK>wpwm+Sgf+Ar7dGclFl-}RyL95kSw$;_l_K0GsFeNRCa7ID2Z5DFtR;`{a}jU!~8 zQakTkt8_)assX=T^?>}} zRo(bCr0aCe6>8ogLQY+?>|0?<(630}>A&#nMD{#c#$u5P_)(jXt}FUmDoJ--WoV=o zOV0S8&rmMq4VzN+)aeFYj)P+UDlJMIa-VNS!MSk7ROtycT6*~LA0dio2#JDu0U!&y9#=7 zJW})7RVaBP*WH`^nxobGtM{}r=Zr;G!S{HZ`y%_2uGv`+y{!4^O5_-Wtc>q+MD?qA z+tQ?sMrtOz3~nT{G=5n^BamhA%MlumEQ?>B&@f~<{0fAIBFp0!GxMnxi4Q?f4k2EV zBSX>Entv^h&KQI&hF^mC0Hp4bZ1w|@1Bgir`eR?M`qn$5*#H|ot2N>A_z~KyqJ#?K zGMQE^p4LUZVYOnJXg|~kQ7e{_Hc7pg%en8#v{(s*I+^FC6XDM2di6@WkeY;+S3jjI zu`INCiR9}*DT&BL;@vo+^(5Vl%#4O;&r!`&7shXg)XcS7HqGK_6=pSLTTn$tVfOtx(6&9InghC3JWCdl0QvZ6FbHl}6B z!7s?VqgkFDv>Wx1T5*ztcB27O>qs;zY{avuCtMmQhEj6ztGT(7RHSA#v|h+U=El#7 z@7sz3=3MDnjZUPQ1N`UG!?M-H@XLDlq~l|`Z+b_h@#DBldPmd-Xa+-iSGJlE_e5{G zY&E{!+U6;cZCg54YmTJJqM9}%VSU5VpNElE&bQ1a;@9ChEWv-Q{zYA!R_ANxxE`(; zvKXoLxyMD2MTj>btTt7%+6|FvSv42l5Lbx0DL_c`;RUEu%~Yiydqvml>mD{W_o^v% zl$Ws9^80tJ8R<>Af4X0~dnw#c-K!S3=G{o8t$32M z5o%*0bJddi;wzxLDSE|ucxVF6Ws?pLo?YK~lmcglaq8crW(~b+ZR9XS06%3h3 z{l)I3eHUt}v<^=DF0=!qqN!ooNfXdAs`*Md?Y@wGy0W=PmCZe>!acLmUpA>#&Ha_t zHbOW;YBh8BtC6mq7`*oSQUs@^D zn)gHZs})b6Mgb9ywdBckkZK)U^4xkzhhr^xg5#0uakL=RlDAN8M009C12U1+X1oy@ zk+R4%Bh;KXSS?FaTr=KmwKz?1P5J-SHZ{h{F0M5|jc~Gys}*R7ll4w3dm7+m9oN06 zkCWX__d;4();rw`?Ix0J1tHT}By{LtT$%9NGwI*S;I(hMHAk`Xa z^j{sRwn{dDYDl$Y8g*Agi{Rs=d|tuL@G_U?rqxq%?a_ zi8rPw&uKA26?sF7p%v8TSHQ_?t~S3s?@CEz2~x|UaY`Xe5m(l}8Cu<)AWr>t-JLj``gyuXu{h0~Tf|~;QOj9+T^*gf z_}_N2^j1~1xAk$qJ$G@owpFd+@OuN%RUPUjXzn7tZB_PE?M#bWSpUejD((GO%w0%( zpE-k}xeK-9XUID_a~IO&nn_GQgYnyQ7ysO^bDeAY=YILKg8#fm+1G{Br0ZS-r~Rm&IxBMInv*v`SSvsx+<)`bT|EwE*gEs+XzuAuC!x z1F@1g&30;)soIdNrfu<8#rbzbyK8+d=#QMV12@sMJBg;nNi=OuB6_7L>1t&XDX%zE z>sJfn7y4PVYE+etRsHIEbi~>lFq!MW9)%I(gl|cWX6*51* zdb%2gCXgo{-Cqx>QBpjubpxbEN%6GkjgT5`#nb9HL248h&pFL#!{Ry1*2eE zaw0u^hmh7BxcD}q+(-vsz2w}+?w5ygc^<~&{%X@vghw*k*80=YwDOX97{#ZOmWOeF z3h^*!rXVBuvfZU(2?&!i7B|M&^ir`Ogo$5)9A|8OsaPPw#PbqUizn+~UfdwGc$i}$ z+<2s{w;|j_q}I^NmY5fdNQm%c0WAh`6kdnr#RXmyJ;)p*}{++L;g62g^t= zLP2s(MQS~85T~A8h%{M8^I=u#fmDC5wXw=m)*J=Kao*(PK^mMv53ASKlo4NwoVfvW!*pbj%2 z)#nUQhnbKX3+SF?L8|{B;2tF-)#sPxHk*~2>RY~($nRUir9(54S8E})zDsk0n&s2{ zpYFF-Y{~K>4Wa*8Z+S0P}VG2_L`}Gc#s;XaO|#uR*&}mH9o5z7KM| zn3+S{O)t3;#}4tkRgkjf9O8I!Gq<)2onMI@wUM=$4Ln4i!??=mf3-t(a2m@hUY8@4 zkq_bPY21n2Vdl?v;@2a+F7tyA5z@@sb~OIOgf-W8KYIUR;ti}L_*+TYMjLR1cth(E ze9g^mHLLQs7!7kdI;9i(rK`~~(mY+!lG2^hr4x~wCA%7@eGcRC+oPYl8V%Obyf4}% zq@7+avxDo9+D)Yyz70t2SaO*c+=SFVBh8SFM~`gWg8} z_r&jyhVE&-L*C}rYu01rdX2fz$B>V5&H#?8?dXpGF1eZ`)mpyF%;+lQD)J5F=m6^# zQeL&*<9IXceSAr^t}m1R3R3&+J|L|rvMFu&hxn43`TGc8QuBX~^^)}>@&vxac_)x- z@THg5BDDkW1^gGSk2ymYgJ-O#k;n0E>sfr;dJf;Vp2xSz`#jRYpKhtuvXIl6E!Qlg zc34SjR&)uj4KwGhNV}D?TQT3hgp}J&tEGKkZJDia%Y9jj)2@q;$#;u&3jYq%0^dRE zK*CG$7h9(}vKV&@v;EqSp#5fpm{EV6Ba3j0Sr4FH33qX1FmvojIkM0?hQE-|BIezX z5n5(?2FpxOLVM+$C?Cm$vhW9A}a=+%rNtX(rPIJLCe zeHdcC|5~K>8irT}FcYbrg(2qnXCt*!P%Z0R^r~hyV(BT3MvkHs^&n;-wWBe}JpT%$ zc2@?OvA+j-FMg0?_tJ8xcNJ&)TXFoC!w9dySN~!Kas(x&rfT2PaC5IUA3K$>jT~We zh0Oo2Hcjn)bgt2F^YuUb>)HJoMYTF3cyct~7*9yM1|59qp^-d|9x?-N6w<|)_8x^k zO+=2Sbx1%a5LQbuns!31xcUv+o1peVE9_H{Y9rK&q$1T$q>(Q(G6%jia9*^uX05gU zVT@VNFa|9>n%F+d9&J`Nj6pxE720oFq5Y)qLmMX(KR|1hY*ssrq2-WXKS*1agiPX? z)<2A)r76O%$WmSeZLA)~A)MB8q!H7)h%vN1YX9@&@}i5?V>^sHL|dcYVmXfFr5(yg zs^-@7ArGUM$8xrw6|Hs{i`!{htB26YWjLyp5Myb{$`IGuh_R+!dl>mJ8d_^6#+nxG z2=WNpOS_`Rnmtov(c_x6Z(!Pp2DAd21JK<1K%?0P8m%>mu=>X8->MJW*R(7RkZJ|S zQIg&bt?L+P)^&_C>pI4nbsgi-*xGZd6&>TuijH2CB#qn`U;W~~v`kI7ipn@qi<%IU zR%vAPSR=Hbb}zkY+TOR2Z=#>o626Um3#m5q4gND}=Qr_BlJYiE);VeG$B@$R(%+Aw ze|z!kO)0w(vKb{yi?&23SL7UNZt3FJ@jG**5mIf%yBvK7Dck?69QSqhYSZF1MlVZ` zzsJ#c(aaSHy>EIAFB@$x&AkRKU7pkrXsOGirE3xTkhZ%Py0<2wk7(s<(x$wKw!Q*) z0(k;$eFe3uwnlpY3fx-s?~8;!CjUpYeNUsUuf!ck9!FbWiF*$D9NPLy+zZGT$gdHU zwB%6aZKl7m#Pm~^&{wIBey(n`bq%A7Z=>wnxery5RXHXNE&VHPzSOjeOF61tc1`f_ zAVsUMI^o}8MjF!A(#xmOzuISa3eDV+V|Owl>1Z_fQRHHd-bISmb!qgXRZ>UMx9y29 zGcETr)0S)9)KT>BQ8e;++!M&B`LD(kdJ_30I(t0sX{2<$cD;>9m$jvoDg3v+kiEF; zQ~2)(Belk50@`>!QmdXOm{m^`%&MmeX4TUK${26fPE9cDs3w@cMR%k|O;>Y%4`dHw z6VbKTBDIcdB5o#9`!y%xW+SyyYob}5HIb4gm>y3Tq{dy7ajoeU%^=4lwDJt3c9~AX z-GkIl*Gag0k@s?3{iW8(6~wRNzgv#fj?=45dwZ2>T~kwKXu%(s zX|=~6=kfKs#(*0C{dPIh{Tc&CkLq{zEB>w${i1f!XvX2<*th-b(b!H_Z(X@Yd$RE8 zsxsoVTS3>A0hf{XMfIY6N!rn%ITWoRNu*WM_{rZ(rQK>;xgmSJMoik-BRjoDJidKh zVCe7t(H+~Dp~7TRGLcGo-BWriOTtP$r=-;FY`iN=h>C1|M%B5 z;9spq-O*J;{?%&rkpG-SR~G3x@z*s)@3sHD`prP| z`aI}~({t#LlVuT5{cGiv_8R)n)y4QN-@=%F-FkEfiFV%ldqn*GBCBL3bH zfA@*zaB|Q#t6$^qAn{kw%l4=}y1&fG)Uo_^_UfJadrJKMCH|gUe?5NsRq*L|-u^Q4 zUV&bS_ROST5wH0ut@5u=56|CyqOo{c`b-T-k&QAhb*mXR^)A(q(w-dc8feJVtT{MQ zYy4d*W$1Tl-;U;G8*yJWTc^=cDf(dk4j-*@kX0x@cS|dHWF^wR64`9D7uWCQ`t#z& zc~Ug%ryVHLiay~+He2maDTI`5M?GZCwfl2H(Y?5uJ^E!Yu4dzlTB)h}4`e;ne5rcL z*|`SURCJBm%oSzjS7dRCkg9!-Hh!46R*h)yV~9{@^PAcst5qd&IL!`fmA!Og2Bd5` zvU5p;$x;@z^u!R>dbMQn#8rbLD!|-X(41y{^MGN(yw%g;knW^);8B$n|iVc$C0lN zxwX?nD_-gmm*v?bUZ3N&khO@bkDHt4K)u~YoLd`Nn`4bhX-HqD4xy$wX+zJbC7}*TSxj0I>cp8Xku8aL=FC>e zR;Ev?l~$K?rmVf1F}NJp7O9m3UCh1fLW#KuYh6JXN^FPJ>aQ-8)q%c=cqUyrU-p}h zq;?}LEA-{~-I3ks0d?Vy_oV#Gk(ZO&ixk;gx)ADvRNuY}p?;j%1=)qT>?B>0vV`;} zBoaai&L4o2{iC}Xap+ANNLe|Ndb$QuVh^NN6Aq-5K1i(;)W}5Rh`z)Jb7nteKjK3u zsXwwm@u9qz1CRrV4A!gVAO@RT8Nl zq()Lhky;NpmiQR@=ffy-94HMIDh{VjkzrKwd-Ye9E~FDT~K^ociR_ z%?l_i8&bM%0VU2v$_BE4vSuS?1G$0o=OX74zmc%W8Db{gNE!3!zt1OhGo{T(&L_T* zd|4S`EFiQPxrlMe0z$VUZ(-~syUlI5TN&@jdb0#~8)F=`B)4<^jmR>Tbvy1Rt*>bnxwqlu(MfZM2z~zwTDC>UQdgMBCY&R{}c1lbl zEKBcpO5B8$rFT1J-G}8vw5T2A-iq8p>Q2tyhTKMc7vY^)V#?$1#_htUvz<2Z0puR+ zKHCXBh}?@+XS=cc$OgWjGiBwGCHw$xKNg#vgbp&2FOS?s>>#1t$lb&ak^4cUW&mX0 z$&B2Ce~8leAot=Q=KTFg%>x|99l}a;fY8H~aR7OM_z}uKh&)LA5prb4I&p~5W5`Dt z9UmfelyeRt4-r2`_$Z@Z+3=sh9b@cUf%Bi_{QqI^J;3a$st4YCre>0jgL7Ma?Ac|5|5d2F~X%@PO4Me140I|^&6)`jg1XRlV{r2KGlSl+? z&-cE3^X+x^-uK)y_w2IzTKg8D`uQJGQ!dt4y(ZE6H9WB&b+y)Oc;fBAJGrjmS$85e zt0}#gvIZ@}-PG>m`*)*DP%nBv7HSh^P0X~3UVGXsP0e_0dVhy!l z@clKwHMAe(oA(0mrTq}x;Z&fy<%g*K7^sH%A=(e3JCOrHA`8l;mc-GI+&8W?Ol=29Aod>D?k|#Zg?&qPT0h-43G48HI3-mCx-vED&_U2(~ zj{|>;e&$iW`#b8710Uh~1UD<_dMyBz()J1-Re41Brp7oPDa;Gby!m1n*Pe3AAm+*eb0 z75GZwHQ=j-*MYCW7`{X;%U-6HQ7>dg*`Ik%5j|N}OuY!GPhD~L7oJ(1b@9aF?5{kt zBr9aE1LZJFvR8P1N%ktwFUelx`6YbzTA?({xT};>l9lo744Ba_=cz@&BHF!pelf6^ zb_MrU7kUFLvOd7xStYPfRt2ogs)1F&Qm!?8vlLiLyOt;P0+!QP%ah81`UKX}uF2|n zVpXAzCsqS{bFJfvy@8cn>v&>i)|dOLfz`D7QtGmP^z_a8^Q0PJ4ebFuvlduOyWZ~= z>N7d$`b-;dJ?*waL)HTC-@vE!Sp$X4JJcJpftg;11F4NF49b)n2GKVXSjV-I|5OJY zl#M7fQX7;t(bJd>=D+p@_NCoSeK4>;*Jggn0N?;xEqrHqp@q9g6k0PSn^yXU1Doh; ziYe&-vq}9QH zZ|0t6TCS^dN;?r1?iP-8J0uD%b@d?T}ID@`b=D@XJO zhD;ICL@(NNkwkg{)p00O^oHY~#na{kwT+suWC2B~A>;)mhsD(O?X66bLM63j@XwXN zN_hU|d_yTgiC{U;Y6j|=ssu3)&R!W|1w}bRNp%y7KJSaEtxR%(62uZXd*#kesVO^* zp{2Z_&--$oxj9g|V0n@VmQ!0zUC$4tiLH3n3g8ObTl4)*fSb^MH{V|gTuFNyc<3>} zF-bnq-)9?&QiBr8wmfljpcxC5BbtFBL2OCQSja8m=~q+Rp69NHci)OyND5kO)nO_x zC>^{TUS4ToC;sC$aPZsm{9S-%SKF4_Za{6M+fv(|CvFSxt{kxkC1eCMF>X)$%_N1f zf0GpUg!eY4##p1hc$QLwa_C;PLv|Pp*S;I=kQDae>Dn!n6yC>w*aN7%@IGqF2uch4 z0@aHvJ18ma3Fp2S&-@@z8DXy^Bkc8tjIbB{`(8;>P&x>C;eaG9C@Jg%?;bKj$OUQ? z4oZ^3LDcr8uFP;SPj3V&BOILMg@co%a4_vAxOJt4LwNdr@b1bBN(UbXDmfgQq=mzH z$^r1}2hcv8x*Fv1JY9L=KzR9sdH#_=<%NTjyr5e}jNWa6OSH9t}L2_DMX^ys5{~ zRz^4$cr5LZ6i((pC@Uxzd>p?2qri{S{si9~1TTLAHRS~*1*L;idCCburG?XY%89@e zX`h~CgwyFc4c=Ty;S7rW{{)_>6fgm(>~JPUSwN}hES^3HsJw6%|Kk%tC5TVcqb)*v z?x%U8Qo?D}KFbqN11bxAmYTAIvcTCCB?zU1b0|s>XYu@VfgvND3wN$;@P9z9AW8~f z0BZSAUN|2p|F6_=ev%q40GM4;4gA)Nh%w3Qbc;MbK6E(a*E@VvV#)AwG<_VkPE&}`y14?icU__fs(@Ye6t=t z{VHlV0F?ri8oouj0p48M;oB4?f@`RK7pP5GIYQ~+TKILPgByXy(<`mqNKrCSUeF#K zHeaQL>uKGTn3s~SQQ}lEPEep6A(50jF_&f$#T)gMTJT3eQk`iTaCh z<{4JxBdHK6^FEYp?R$7pT8L z>(wMRC>^}`hIH^6&s8!|7I>Yaq#*xa$mIMB$OTFbf2CFg%z)E*dQtXDk`7))u2L2# zhC5dhCy;@ZR3II^4pdU8pwJAOz+pgn{^2~O8Q4sF1oh!SWr&f$5kMuWkvzYh zdOLlic*+ohWcpWaGpGdGAtWQeM~lv&#DXKdHV2d zJY{S)foG2Z&g4H$pf*06$UWn-Nx+HOWZ0GvSIbjmc~NTir9o?8u^$aMy=3pk1EOyCUQWUe!L;^b@=_f-{UC8=sw zlCx$Z<&B`Hi%(|r|2nhTl$qHa#_%8TFUS@r$!>9y>=yH!h4i%ZCX1;JDJ|>Dk1hyoI`*5 zwa_UWDyhx~-%Ex2QTij5YM)X@od+J3(s@FIxivysRciI54(+E}QbWqsZZ;c?rB=#_ zS@Z5H6)O|Z0yj*jwprT*yJH+$MG z&9`UPJ!dbhm&Uc};So8+oIOwTi0pmldo_yKNV(iDYSgfqHjE|CZLQ9LR$0A7a+~Y~ zeqV0A^?VV>*sN&g6%I?V{Fpfj^%Ha?jTeq=g=Q-aOS2>9Nf;3!sMmSet)&9yLDagf zZQE!=E#TU}*Nw^1UT)-61M9=lHfGrTaN5p|XVhywEZq*(b_*GNarW_e%22nTSLd&voIY#N24b@Xl^sRK3^1PvD5N&4m@;I9o z=Gq9Gvh+S>yh9s%pbV%5SJ=i|6;nEZC0vbY7y>jhLkn&P>&xf|ceATcpGeoB88!8v zTu#dfNKgA)N*Mvv=Tcw1;f&Ez>We9(fcnzwhiDFi#njDeFb24Yt2qzMf3T42d}`x> z3%JgsHXf+||2+D}F{AoVn%QUq^E{Wj9(h9J0`$-q>XWI*oY3e1ef@p{~_gF$<13UkdQ% z=ieDGE!~LhuF@E(Nxt@^H2L~;CAxa0Qm$54bzqGwX+n+95Pz&pm}Dh)6{wpFc2jzb zfWv8T%Cm<9SJJnN-eTaUTvySr53n?DGkQyatGI5)?->akNo#X@OMz0l&3UKMNn2V1 z9K{{#QX?OO`4`5}+LHJ3v<4}lI@U7a7_MkNqCS@1)r`_uw5$5>sA=s5luy}; zqIOqIyfq^{9=H{)t*NQ$oj~o~d}f9_xs`V_I}?Fh(-)C6YG(UTpTu=rW~&M)J>8c1 zoebQDzHMpiJtBSBj(&B&+tM<_Pz_KDtFG2eL!DfAphrEh6lMoX9dLVEJFtqTpaY&t zZAW(TRNxMLs<($wO0^TEA8;CdJF)kt0j0=01NF-_7tt=1{z;!}y^G#mSmRyjdZl-2 ze)|KZ+Pks~W&&r>w;T0cfzrXqiz_n>zma1L#?!wqPK zjW2i)cybO<%C5e6AaD*>wZ?;hQq1@AseUZd$~_aU+>;)2&CTbk9=Q=6u{^+D6r+Cj z1Y_@=Xz1SH`~}qIB+V9O{{pW2B-*+U{pzdtrlmHy1t`bxKKhM)k!N@xcxW+tY-wsthR=I!Dma+FE68JZmSNo&&#NNklnK!D0TiIWhn3i z=~Fq457OR*l|G)8E6y)tl@(a46M>PzVl1o2T|SwfiL4KMJJV{MLXVMj?jSw!&6Z*Q zzdW{XJblyBccyXQL{>q8_0z?-Cjs53U1>i`Nk>vQHg5)Z8YgEyjhWm(o%vK+n8n@F zFEe+{;*L&WC#~7sF$Fk<@66%;narxVeJW1|GUmD&C?~LtJLUoB@y%tFR%U4t-`2*o1gnp-%_gk9Mxb25CiE@@n*VAO zYRkZJi@19w_vxEvB!iexzcZ=4nU)3tH{q(^nqF#4Xz7`z4_e0ETd*tYfl~i1_}nZ@ zE4f#jl>TT&PHaip3@nxLovqk){ee=Yt+=ZmxEbHrin0Y*X>-1@HDyb%QO0++;nS^v zTk)-J5=GyJz2BF*J{8+=pT2CH^Bpsntp={9wH@DmHyCGI`nTtvZGh6U?ZGg$z^&=q zo?h{iSZ_z}-ww8! z(I;*<%FbX7Y2WVL*9W*O*WKyW>um>G;-8(t9P(Ft@YEfFJJPoY?Onhh@-^?_`xU_5 zxxR%~I7fO~N7dnx9^lkax74`Iz20o%%oGFo~FSFyto z-dN19UwbtxOKR9cF^X79=b0*{z*asnlbC0-h})GZYgir9sW*$ZG6vk3t5Vj5lq)<^ z#i7RZHquw0FuAA7C|mWT9lom#Ji9M-X@OX{H_&Wm?g#1mF!o~+WhyY^T1?H;0*bhL zZh)sacxpf?waLH|uJRC*fl|OSYLobNWz-!(q13Y%HBVkQ|DNM6l+Fg<7Neil=4+rHt)dg;G`VolrU}))PvF#hyZ`wreP3^wkuUrka@pTo*<&I-3!5P+n+j zv+mulI6o==FZKOvyu4!+a+|W6XGS@KA(=&9DrLvFKFd1v2F{!rKSIV*qH?B#mp6~R zl9U;cl$zd*msg*meB`O0>V(vFsQc;3#mm!&?6WQ}uO20&8>Jpsw!Hj?&$5o)As4R{ z=AH>zY{R^~J5VVvq`#b_f2X{>vSf^d+8D=6Nyi-f?vRi&l~2{oIF8DXN|BCPjIy$= z8XI>)$e2o${aE*&pAnLyr-#Mpd3so!LM{~zNhoGC=2xjm*~tAIv#(S>pV7=^$=Wwo zhO&GMV=8t~TB>1}D)qa=%%2i+l%uZXRK@;M2jCfEdYh>Aa?hy&3JrjAW-ixyo<`^a zLZ(vA4eVv!hFtbHM{+JV8*8Fw#l1F^*&D-Wk$EC?0?K3JMkR73tB|uiF-$pKsmv$^ zrGI5GXHi+-8FrqP)STf_{3`#;5OA6j@-VJaqGh~^n5;eFHmTDx-c}8l6iFyoRr6mqvAHHiYE@a+wzl$JQc-V zrlwB}Csp#yOHU;4K3CT>FU4)S&Q%#jYNbY1y+aK}Ia!^frz5+oq)5t2Qd9 zR7lF}$wTfpPe*pvq(Vw<6PXj~Pv}FXq2m~PDUW%o#{!KgQHqrNR=ZkCab6-{qqInT zDwGz9VTIBn&k!2H?5o?69}vnTkK|qY0e$Z{_01D;>Zvj#Pqex$d)9d)C7aUGoP2lh}O0H)md&g>68Xt9Bp{rIq;8+aF}4bJo9S!?e*^%4y?U(b4~A+*rgwb!Q4x zAMM@_4Yk@ZvpKr2jk zHzM2q*?fVn;GVH)YQB^&V=ud}#pQA0k#ef*R{Sj2pEH$bIy3(adH9*(9GL)-+5RaC6Pvo_BCmF6Gi))9Gz#P%}F>zxn^#n zL-WBPW`EVbCdbf9F-Nz20~T-E@>mOj@?ss-GQef8E5Cw6S9<6l@@-VGL}}AW`4JPq&AenyqTQnOxlgWSzP7s2PH06C>JZ| zDwNZeTNTOy%h?O%dZ$qO1E+G;W~}9S3fIZh`U0JaNz6(uP{}~j5+$qBc4jH@ckTpKe?5Vo@vM|~>gHgYfTpL7`b1h2 zST$|5wKGgaKh#Qn60M1>pjO&iCngnkqqQsZx01Tt@NVejR?;?8$z=3H&GdA#I+p>p zP<2vP09Wv-)KqQuV4!#N$>GMy>6FsHNI|2@|vB3H}2Bp zi+eIX$5Jo^-=U4&6@utb-iq7 z;4i!+c?~P!%%pDyyKphRv#7g6^toM_yo;5(k7O5}O0Tl_5$rB~apxp2+&Re$cMk2@ z_)nifuQK@&$&1=}VSStDC9mdr$)9;%@?@UJ9fzmAd<2>^IgR&F_Q3O0%y?PCiI-B> zFI60RX~LeDP}dJuEO|MlCi$v*`cXxSgp+^x3Z*W2uh!uCTES;uO<2;{wmQ6GE9lje zwJ-j%6}0ta?VEg9`{K1K4%Kh9FaD`lQupK?&)Ct&dv5aRo{Q)9LDco!*1~&8@@MUr zJX!mp2@I=5Bk!XRtLFsh{o4!w-Y)w3Tz@MOL&*$Vmrl@_!u7+0B*^<;fdaiRJU`_;T)%gFc&GUYek> zkQsi@=F!ssIZK|;S@L<#=v5Q|U^v62VK=0n*#s;h+ za)8=K1_0~nl@fjtsIPJ_%7v_sxvY%+fcx_|m$7YYE9O5c1r(+KEWWXxU*j`*@;B@E zJMrC&9j&F%b1F6kdR9d%J<<$gDLUv~32f)uLXR2(ErrVRD}lysG}EJ2NgJWk&n7@) zI|kDuUC~~swPFR($d4v)+G^lxK9h6MUqb1-k$x$SHbQxcWk5BHp6ekUijzI`rWi|H-WOVqh_! znddD7&lk}?hE@i?FQRR(IwLU5WBN&oaTtB5O=ItV7HCGOX_Rw-=YR>OQO*UP%R8LP zoknT&p{CV0?7)4&-hJpTq==OQ*!T$QW;QBNjsjyJMr~*At_5l{-jn;adc2qGd-(Pl zz%#)4@1cD=!$#@g>gIRt2~sC_7h0uSZ+#_${cWAy&M;8%`RJ!Vd6TJ6K%&r)R48T%6Yi zMiPgM&sxDaW2lc!*jpK^nVA%0D`N?j1eCFaVrFG5q1ad%OQ;MmnbH89#I=)}*~cey zokC6S-#p~<{{4Z<0-?_ic}t5x?&qlPvJTv(ePBk~Lt1R=z*eqPHJ`QMDc7b_R}J{c zwW+*S4aRXTC~sAPF&%Futx9mZt495*nTqC7pAW16x4YJqw<^H!u21DHSKmVF%3Ebn zi$w{#GMA(^siaj3)p356v`U~*&aZT;7%JxcO3S+adzRDVI=9!)yu-Wwj^FetKFcTi z^pZFJlmEMvw*NbR%_4r6zfSMm_{IKu-@!MDx0;`Jjc@Ba`{s^36L6 zu^H)IF|Hv!l*5BrZ{=89uDM2fbARYY+GEpd)H6EPsB5>G-qC6G>RauZ+pcXrvtz}( z`rQNibGs|t5o&AQE$$Tkw&gVBX0!pwjl|B{xWC@+{&I!&N&Cy4CC+vw_I_hk{{8-n zRqTq^@*n%ll^#1QcG>@5_m?|Mk9Bw1+u2`YMzLi0ly>hgcb2~S>Qpwgzw#IWcUjN< z<<1(!ell*L=l&AcO9KW2^N5AP|6qR^9TEFW{ZzicJk$QI_g4l!G>4p0SrKJG!ir|I zR~8a04ge1-9f=h^Sxz}ho}eM&!+}60K=Gka=}}*fri8~mm!TK+3QA;*7phwj9}3k= zh!2J8F2sjI^&8cccA&WooUL}C8WQueo1MLetC@MV7MY*DFSTL7I<8&RJa?%tSI=Ye zd|gjunn}%52-N_IU-j`)`y}2S2@Y1%BR(DlZdSV^o*vDb1Oiz8kioA%c@ z_Luzn0?GuS{@+rD3G66&{Y8{XiEd0tRBTe(UqYpYB@}fqOMucMp&Axxlu%vCa*F!A zLZPSu=NooRqU>_BUygv!({ez2vN! z+0B`Arkpitn{#Kr24~Kha@M4U&Yig%oH=JoEt6c8^E5fllX)CMdnQ-qOsPYY?mADN z-#3j~ZZXx;7&cVjC*uv2nS84v-bcC0w<_k>tL2bCEJ^R9mDV{Mn`X>2*~%?a+LV1C?at1YZ&J-~51VvYskKo1K5>Fx z@Q2Qqnx>pT49j;HJz)#a&)%BB`ka-phx;q6=MBt>IK-XRz?_IZ+*t#enXtr*J=|Y| z(*BCG+ronH8E#?G*Don-{L-)Hw6nDPi$kPeLUD*YODHCBe+k7QaekTS=ouxF`x|Is z&X_4@?OkbZ)EaB?c5bwTYY}&Dw30i2W?L*tvoVvq2^Sd_3w ze&V6N8qSlED*A3XPpxUD)C9NF3eOK`%2^YKEKk@YPCpcPxWAl1r7-79x}X&1d^yWX zVa}JcuN3BdxhmvIoi8OZ8HHOFAoW?o7FNWvwEhvemFevGliC&Y#pv`O8nd zD}RFDQ~vT9J}>`|{vWwg|EK?7ZN9RXzfG;6&|jXvk#C@lO$pPtQ~vUeeS5XH#x^=8 z`G_f#DStU;j-UFt;0%?z9A_D+V9rxr~4L1$U|t&Ppu zm#!;+xh|BvbY_By?x>^q~_AI6B%}-<}Vh_#r&$ zay^4_TKZ?`mC?v&F=8RTMl9A_`Ot~w9LYM~GyEsbz|_-+PMqS((1!bVeCQT48d`FV zqtpjOzYM)HB7#orW4>SK!AK>uHW@)DJ~GpSbW$B*_|Q44;X@be%2njbng~?hSIT$I`EIT< z<$GloH36>3SYxiWL5ys^dOP1(X%Q3c9J!iZ?Y^5UQ5`_H?`YqIL0y$bTZflhP@h=UN*V68m^JxteO2|IalYi!r8@2`eOBFH${@Z|Py|=2R3lcO zYf|bEYg~yG;IU{hj4J$pJW%8{S{@|F*Nj2RuA~JJ;J~dIxT3f4Q$>f2kpHXT>gCcV{W{ zxgsZ~ebvrvxu@J^fe**O#r~3J#D8LjUdV$T#tdI8}KeXtKCO|E!z~(64*_D0jWS#q6%eh-p_gksBPG zu!D5iw+tVDX+l%N2>J&5#v6`r7wblpyA;`VC+6rG-yYd5#1#?cp2xTQ-r^eHSif;) zFEK|R*)A4}I0Pd%w1GQ%5r3d0X?%M~4C4FTPhb4z`pc$NHc5K9>8<@ym{i_gUpYUG4s{U*k?k?dUJQcuqjx-KqHv-uUE zx!y)$Y4=2@k=WNq(biT!lI&ovh)iRZWWyhcwRjZmi}}uo zWY1TQI|b{pYfDS=XzKSREB<}Sx_=+{nSJPd^$v%HYvd>?U?DKc>+*b0TxvTF?80${{PYd1y+QY9*_V6o{ zJ^adK55F>5`>*6_SCCV!ga3U;!i9J6?RKoia_F9@H4q#39SIt9tRGhcR_#0JH7-z( zmpf=1<7~dX&nBORG1!Z*Vy%n;YB|0tS>`?QYA<%)?Lg0yHFoTF+D1|vRdzdVz114n zVYky>1~m3;Cwl6W-&=k1a?>-eKKaen!JdM%z9?uBd9UbvR;T|-X1 zTlrr<lZOkaB&(lR{64lN0?Wo*Cc9U*ltB z68tu}Z$3RIQ~wwq9w*VGC&;()()bp=p8%RW^8|W6O8HL0mfr+=E}fnr-@$L;Timw~ z&DTPF^P^ z$?K$q`<2RyX_fG+znd`H7;u|&{Ue~~Ldqju&Pp>or7KRazR6(2NwoFqn+$H8MBCiw z6M(L?d)Sj>f$~xJP<{k1{2F(fXY*3<-`A;MoL1w-^jyMPKZTx7aH6>JlhnkDVmR|@ znn`^ka3Za{`Hf?MV%@u`-2+Da6!+^L*$JLI4QN)yF9G#_6DwW>G+*ake9J73V*9%i z{x_RxXTpgWCaiZs!cC*uqi4`R1*~`mP`|w?V3@POVd7A+qWH|S2gHj12h`W_&O{yV zOgR5e@cc-6hV!4qiefB%2gQo#0QDUdE1nA!*NPQK1EmjlQ0@c+$`9^AiF38Zh3}!Y zJN zH&>~~69V)r;>oFjgz~ z&EqclOfjNff48yguBJT)I2UYmHMMIfv%yOG42l)Ska`!26~&Nx4vIN%W0zdRot}X# zcGQPYA3Z(x>ZvzSwg$6Y!+lbht$}(4ss$G6Q8Dq*g^dFrGzH6jk ztmv5ndM2v<`60Bl33v;%budsa?iOl41UFp^ZkwMl-+XZ2wFz&w09&|2Jo*DLnz>UK zP|SelsRm-$AAtSh1mbV-nex-kKy#b+qF+Cah2W)f>S7X4VkiTag9XKbV#sf?gTG0y zd4Io^aNvg`8PZr^@BjqkLeBe+Ycyytl{qOCHi(FRK?uTeegv4Fi>CN zKH$Rxf%*#f0s9>c+@Ehs8$GAmoU@hS!$W|c6H}RdqbrkdbR`(@aC#2mJ5~I~BNC1E zr0XN-t>T+U@~+C7$^jL;jq{=3SubEQSLMfY-a{LTGGjShn>fnYP_z1}Io295gdME^ zy7qw%_ElIBlt{Jtw6ms_Ta_W&SUtwjHUnL2N*LNDTzyIv+ACa<(njqT3s|FJ*-%!{ zLS-g`uzpD8w1>DKln=CPh0SC()LYAmwv<_{NM%lKDl=J&+QPJ$&0qy6TdLU)EwVZQ zZ8chN@*I5HbF}J+XSDHX=}}^o^VTLLey^fbGote3T82DTP~D~cy|yK3hc+d>t>pb9 z?%Fs|t%h2nj1bk&O8uNMp;{TWTxo$UV}`=IrQEH(D>RQ*%?#TIKu&X5P^=K??5qsGjq>?z{JVYyYS3 zUIBDO90A|m_w{tto+BXbd+T@4`3iZ7oV(EHT^_=yc{vS#o2SZ~S!Tn(ZQWn>&gR9D zSbugZ)2#fXGdP_QN2mKF&I)?gJ%h8H`SHBXzCdTnk?Nnu#gk&4BS*l~H~)TKVn&=D z-@RtNcmL0>Nx4$3F~%6_7ofFYe}H0YTKn||(1Sp0zy1WJNq&;EUcwuO_qEcMvnW&- z?py{}pL>w&OP+hahIe^*oQGGeJ3~(h_4jHug-S``xvt+t?$KUDE%$WS&m#AL*9#;3 zu7&Dm)a9s!m7CL#L*EXyvjeC_tgUgk`c=8drZBhRkFPg?-uhbmwbABY{CWfA-u-$5 zZHYdb32Nf!;281VTh4=nE6^33|5s~{zsz5y-N#?-uhl9f zzwKLSIZ`In(x-JvNm6T|b||rz77guFj+9nKE!plBM=#yxoe5_l zwBq5voBOW?zb)sjMS42B!I{LH9pNvd2aQqX`q4x@ zL)gYg@cU|*C$pvur)J);5nM+l+%t;bJ(8JJUX(|#Wlp3OqbZ}?hX^mS9 zoXC5cUCn%uN^9Ed7A2^RCdQu#RK^*|80poZye5{L1XLOtM2{9crM4p4oxozQN^tXm z^Z87i-w9Nb3j2?;o)$?ZtO8{kFrzh?88sV#mY^Z@P6rmaHZ$*YfOGh)gWfLS5Uwrs zYadW&*-kHK6YxnFd%?58^kSIBo@l4Pjk?+&<-xEM_4KaEGbX>8cg^~_se1a=1m1D2 zZ^*AE&-Ltk`?h9WkWxfes>o0kS*aYIIz}dsK5Jlmb8O23-0&xMbT`{`fH{TA7~a=)a1KKGm0 z&{e4AF>;oP6MN=<``7X~iw#{NTBx0O*F)s((C1XUU~c`349-$f=Y7Mu-}K#Zw$wkw zY{mS&z1(lof9GcXJkFtUa1O<9F|W>W#wu~X)kj$W_xkaQ>-6JQs$18OSN%$O^Qvw6 zM}EAy2d}ytwK#9)$D4cbdK!Z|p?BiP8y>v!8j+zaG*jw#-`bB?EmvfH6l?xx{dmp& zBxj*M&;2cB^(+aw(}>E^%S(SQsjpO7+ANjU%S+!G{ceJO>s8amuF&H~YTTP~6Tj(^ zp|^%BP&(Z^;lAM3)Srtxq}dhBf}DalR1YX;c|M=$S0gtePobZNyr;ChoOuh5L*Kce z-_mt6hRT)5o5-QatCaA$t62IT)ZHB`FC$kIUar#nV)nE=k2`z<>spF0y)R-WdPX$J;>rxkuuYEMjkVt_W@yPd0A$&4 zTKLZ$^iJWbhhgxraN8O1~jj$G@udaIB`BK zpL9|5Gjv4NU=CvKC|hv8E1!u~%vIoQh~L9QV+M02b*`sR&-YU5a%b)(G0gyq+Fs8J zm6j+qdyZ&-TIP)OtWa0a99EKe$ULq3yLx)4e3afAo*-(>OPtH1S8|-oA`fMBjOVh* zw}j+Uo9JLIGb>&0Lw^mcWeIQztKOa9xubGK?iQh3Q#JRvld4i(u1c=`pZAlOj|p%2 zf6Y%m_irAQc1c7l8_^)o_wV+Tm;3GZkXNG9Z+?9bc_l!(`wjWYD~~%Hdf>_F%46mp z^4gR1m|xdVUT$_VWf3zZM=u8-amsQu@~z6g%DwLJ4f)9%&yY)A?qahWZb<%$9U4-Y zGM9T+DJ+)*-SxSAC}zmz#)#l`p9O|7%0W3(EM$~}vlWrR?jf<6IL#dsl2>3l<=Gq? zD(42q>?waK56gAta&q8hwLO0?e<^u&OJT}iK^de25h<;~)D1#|~iJJox=XwgUtaI2?{*uGf|J9u$ zpX{CsZ&#%OpV-F#lY91w9sCYu2EEr7uru{&^M4HC7wd7P5AJ;CT*)K6UX@6~b9XTR zU5qc?%oq!~dOdxcm@mD7<$mOC<%S~H;qbKH#P6PnoO?QYE{m(tRaMOBDp@I&7!R5I zyGG=v_|SO?Z)Evoxnuoe!$(<8Tc28aXg$`#hq8;2mg2~tmxJwc@8s#shTNZ=ydG<@ zHe4eisq3SroGG`cL^_4}bbXq8t~YDO^(L1phpJy&oExH#nmNhjR)ZT=2AKd3RC+Nd zU3g3?m$-W67M1tpKOz!Et(3mp+7sQK#!*JbSIZmjH7gR-R0)di`_5Q6(1=3 zijCDo<@iEPRE|f)?Ml^J71cy3e=Bc_ht%52-K&Z6*UICIw|obsNb#9(D1}lJ<@@LM zL`O=Q)Nu~~Z)ZWNHqWCcWgS3~mx*X3wI%LlF|Rl{B2mQ3X3&$WtCb3GVAqz~n23N< zD`g%%`Fgcdo>L`XuU5)@u2N~WQs&W@zK`B>D zZNrWzCN!Uh>r?70y*9h7^m`Cc8ZITS2THeHi-Y)%dIzcUaDJ)O-?iAtY^$djMtK*% zTAm@aQPN%Y8q)3XOm;+v@;-7RQs1F(yq%*SXTLSG8l=oEj6idmnK%c|I7I1lE2Gqs zX3ulr(5i+>~piLf3%~Vz zXNke{ofZD?v9o-Sd}pm6=OsmOXDLlYgqNcpaU|}n@aGTtLP)lzj=9f zX@~pD2pTDlJE|q^i9FiNy_Cm!xtHYc-DB=4p?gdYRVZheF&J0sEY~y z&^!;pn~VQLFW}m31$Tz!M5+-Q1SxV0*i>o~dYsTZgg!zYjS_*_HY`M;zsNa5F>hFl zq{W`AklS;nfHlR9N*u}^${cD*v?8f75g#j?xNZW=%FAe1axbeRbJa+5bL&#K-sXQ{ zf5{oD>2ikhC^M;;oS|diGfr75md960zw+oysaQlNMXXuR{gp?0O2zVMP))Nn#(igA6lE*-+J8Hbjr3VPrrB&f_2;ef z*hB^!Ib->=k*pi}0(rYp?0)$LGonNuo6%qnId-|j_4C+71{-yCa-ZYDRq`ovsFA^D zB3Mi5Kpd6lu@Nts7sXYhZSu|X*qFgaZMN9`t@QKa#_ntz8_u&4XMpOnIEJ@z#@=ZG9s1Y#VQ$XQQWnUQE`lrSIf-i@mxtY`k6lyco!HLCoG@yjOULuB)F{tJ1Bd z@6NNK7ADWOp>{@_WoYTU_48^_yR&Vmk5aSy_jxwdNSGHzKUqCw<-*&!E(6M)i~04d zm1~ze^wiI*zcA~0XgRd&Nx9njzw)ALHjK7c_tAZ#gL(}kd?SiD^czcga)Gz#spU{} zo$EK;YuYi5&Qn&AC)I{0EsJ<&Gq}5^<(Z{r>*_Rm>N+;0-{=|7EBBD=H>6*o)A0NU z>6f|={cO5*8o91R+7%j)&~EkAZ>aYuXUA$&2rWlwJdCy0zAF9dspSYgMo-N~PmM?D zG}L0~<(tPy8?Pr7Q_CSm2+LfzmLrd=jZ<{=w~^yt&TP0ll?0Zh72uk1W}MxnX?DBM z(s72J-B?M^v^c<-bG5~qQx0{`!p@#&@G&b)p4lfd{pdR#d4F8x`C516#Z}UqJadp< z)7@w3IP%>m>L`Z=x1da>ZA|;5a;;-HjZsiDq~~q-DLRgu*0#ub)X8Y+Lv4N?ZFTPV z$eHw3XX(g&C?k7{jvR`z=~z~W+)bRNqvSdUuFkklCF6H;md?66D>R3pGjvbI{)*ky zbAN^YFm#FQ?l1L+vCG0TwBh~Ly|dQU9Cq)ro_oqDkcfMo4LyEm`oq{?c|@?I=Dg>7 z&7Jk;`a?%M*CIOCJ@;B3t*jrr`%3Q6edqql^@sWXa#gIqvm(~j%t~^GvA=SiVXT~p zrjBUq*m16$x1wJ~jLw_oiIV>}$CufM90@({rOERCIsKB?=%!+CohM4mPj|Mc$Po39 z?91}n-BhgGz8qd`?xWBnM#Mrl<#K2KuiKY5M8CQ<^J?jXe)ZgCITh=sUqQLVb~*hL zgSyK)($3OSu1-Gm^P#Jka?Sf2<%*rvt)G8;`|F?A&#$kU@42(yOg|qvL)O*Ot1a$H zvvMg+Dklb1+ZH>ko0jE!${mzz>D_Cw@7!5^5@yc#T2K9aWH5-`)pOtF`uU*nVY_hr z%zdN1LY$;;h?WZRP-G9#Z%6&SxFzsRV3o)L5_H)pnC^@rzEiwWWE$~Z)S?D9@RtXj zb%#k^rNQ~H6+eV^K~EX2624*BCbUfW{(+J7sL4k%>>%nAjqz8@5!{9RhFpjGLn&Zj z#yFWOcocnq#J^@}Gp~|7kX}G>!j<@1{k)XdHK%?)Xn=7{(rnkUw8Ryymfq+msf)au zl-*q+e<$6SJB*XKJm)58PEKLm2XYaf4<(-=cM-MxyeRn#v$wckyw~r0zE?aw_FaC; z*JA#2{Quw~{awal<(X&vtqb1RalT1-=J}R#fWD_^`^Y8dc|07Ob4*Mc0!`saJas&YL^ zQ6{p^+)J)Dv%e~p1b-2kY}{#Pwvop$3d_|j$065gc4euE+^RHHj$;J-!Mza_*`47I z(S{-yons#TrR1wU(ZQM9IA0s*YvcafxW6{y!;ScGBmD|p)<%5zpTLLhiSKHM?`nV- z)J`{utGsJ_;#%7izuKPoJN1ywaF6n+9f?Qnpr%H$6(|omCTRr60@cHffs+|WeJtG2 zXzJsskAnkJCQ}T)YPwnbDT=gl$4D~IeXKjml{s5S&GyjuLMr#o@r$6 zSV_B@tG)-r>Gfnj?P@E4W8MWSA`@mfrDN(^y`(6P) zI7`~nUi7F-(8FRbefp;^rmfG?Vz@)?h4Z-1g=;LLR!lK>WklIU^i456C6op5m|?xt zyGdK788$X!49vCEFXdY5mogtI(F|Y)hcT9V8_ednm}P%9P@9!G`Sj(}2SZt^i8oNQ zEoW@bc{Seh%8mSX{SM`l2l1=bkn68v?s`3})x~)Rfp$DOW6vf~(=M;s9-|``e1sZ*;!GwyT_M3~NvSCG+d|Wv%PK zWZwNcpc(hudBa+unfSHe)&R}ZAK3)W->=uGZ{I>OSB7)aOle^+Iwx@sfOfFnX|4t{ zOU{XNrT?Mx;CTYQ(u|og!_x+wC1=l>i4!C|oxs_0PU3tC&oL-Yb2WfD@CvMx`eh7KVds4X6={I8`^}~)aS4c!ymGQm8nj_ z?CwfYN>oLK!I^7(aHhU-aHh;YI8#m^oGGUd&XmvxXL>pf&PrI-O_`d#CcZT|Yt9B| zWL3@77B*+<4Vp7`1EFm8D@Hs+o*!J`DA*L^QeOM zGFrXJdsLCK!&Ok*jr#6|U4gq5S~Ew#m0wg;7?>^N&ViXS{=m#L0|#d2A{xklAC#GW zXkfMr-`W-IwvxJ;h6ZM0qg_}dW;g0h{-d3Mo^7@RSMwe9ruIsj=U4bYS)qaN4a^!c zGZZysW+-aN%uv*jnJ=gzGs{pzW|pB>SsO!uuW+sB|7;K3iqGmZvl7*3W-F@CQWm4k zEJpQNI%P2PG(quYefApP?g@?Je7arl-UU-yid*O9H{R8mn!c)L!xV~O^mh0>EK3nLYRr0@{r1ex`E$~V9 zXC=LDg|5*BUY|9S<}gleF{%a8(h{KZ=(5k!q;b zX67}j&CF|5o0-?BHZ!kLZDwAh+RQ9QwfvvDtTyE`s!h3!YEv$w+LX(vHf1rYCC^bU z_tem8=D%oVEzXLvlB_suF8r8mW+mAJTuZY13Z?YkN9}&Ht(8*yN#OxnYpCB__$jTD z>>92m*^lTk`(-ILsZnhP%xbd1e5PI399n}ZC7GG9%wSoX-IKCk4JH>_X?AzYcr}>p zQ`hrpS#~EG$;z_3$aq$km2$nE>m6kID$8ys|5jOc8yU9BvRk1IZeh91Fz_NoRv%4+;P3LOQ~O$^2GJdE}?#DqTJP4 zze06Zl{NCq%_df!l~KQm-_)4$Xf>uBUyUgbSYyf$W`40-Ql`1ynVIH#XP+U5TklMs zpbBUfyZ$MQUH_CBuYbyn*PqWS`ScQ6{rT^gNXz(7a35KDCU0>O)XFS#15(bq0V!wQ zfRwXtK*5}K0}2;#9YChM3xH$#s?9a%46@2rB|qBhmMheOyQ9bC2D z0jGL)>?){Z2T(n*C*BSL%Pye388mhQ^kFZ0_M{92?=GZwbLj3uXvLoNY(d>@nreo( zfZ8rjS@ed2m6y;q)pc_l+Uq)FCmDr6QX~}A6$npf`wWTOR zvu;XLwk{MX?*^Kyvq0Gv=xN*q%Jx9>i54h30#|bHX{?_StRi{&GbpEncTVGaCOv0> zk4~k27WFg9hxjS#`%^y)EcQw2AEv%PcInF=r^zCNHEh0z)@hXV}YKKI*M{U&}^EcDEhaU z?Q%5b7~nDVwu1wjfMS8Rtesujmeyh$wZ=k6!af~*+Mcy$ZLG1@v~F6d4J-`d(~fKi zc(4U-!PV5lT@8hy^bE;{X8M5)g?6>UhqSORo73uUPAfE{e<&PGGdrP(dX_cOf{UhJ zlr_>K-w5^MY!EH@ZR#c2KwABw!vlf!Q1bqTjG5UH=((vGGLRMz%uqA+4tEIct5fu@J0on;PVas;Y<^DZa>xq5Tcub>K4d*Io~T_tl zM*pjDORq2@uTy^wsBHKb`jBa|S+xI5s|em`7VVd56~Q6RqWu!JV&KbMAEoCJ__CMi z`6cy7;medJ{zP9f+?n#l3$)A}(TDe(NclX_6Ot!VCcwG>5`JkWUs9lwFiR0{;kiYP`cU zg-$qyJAh`A?xfrWG~;zAd%yVLb(fH*w!oYTpH#m3J!T zM&ONn($*%$(VtnIE&bBECEm`@w$W=|i=#7Ac$$)>5}6)JCbMOQ`pgx-X%YTdj~nExPJUgi4cYPlU>s zo`k38r~XgIqv-u))*3hEM?4$Q8(f_?|Rax+3>V?J!#Z4lu?Xyt)lk-_W5mME_oy4BE)EUbcC2rK4Sg2 z2r;9y_Fp}}ElzF|YfAy&Ixa$bkVp3!EBj{Ww;3yIJigKS(i{2B!Qf3}Wh0_5kM5I7 zDM1K>h8ZzyR76hWqK$M)l^I=OS~5TFJLQpFYnY zVBQC%TWOFdkQr%g^l?2@O6gdd^`APQ-j$r^`U~vp3W}&GvjRpgH&3ZI!Y!h!*4?fD z7_W*^1G@%Bm5X@i=hMqq&48A>X61@zK+EMq<%DK3KCW?jp;?TSYhNyFHsk1?aAnS6 zWG7RfM41OIpOoM{-pAD_)RtpxhfrIN9KKL{kCKZ}`;e<~aaxT+ZAhajOVi2}YJqZ1 z3bjnhaS5gKO5rP5bJBQMru7vG7s&z0t(n6>&cJnA#CnxiaMc#Gisd2Hc9gKb&4oXgK;l;f^k?ZJhxaIlh!5e7md`afK6Q8rDjPL zd&sp3<)7r*gkq2S#A(U9)v`k6z{CP|iEGn`PyVc}Z6JLOsjr^@;?w2N%yHr8wG{K$ zyVqO!bTClsroSYtU^UeJZ)kOSQYE$ijF)d-NMn&vHy^t1>M6~=fxcgPdNcEIJDQG2 zaT=py?#~!C$JH@3(}izXn%=pT|KVBCjeJ9VuT`d;YbkA`zI_*S(+vc6arHc`dY~uL znImEla0b^!>5Uih>2y})O#00)(a2izeHT&|u{vkbW7LM+azA<_H~%F1npmIC%KS7| z^BJoJtlmlVOs1Fz!z^|47!5O$VLM^Wu${2B9V;YcJ`-oOuabax1Q#SBYh zxuZAxV^o@t#mtg8u|P5UUTc!GHHz67PjAM~legB^7Lf1~Ma!<0fXRVWcCw zfIGwYF_VGgY~~?(NLQDmPzQ7+8~tk*0db?AgIX6|+i_B2M4sl^70jccwb_gUW*YF9 zDdm`z!TbSc5isk3@1yKvMgj9TM7CjLPR->olXudO)3Gw^Ls$)G@~*M^99wfZc}kt@ z)U`f?^`|sqW(d!xQ)+T&bg}-N-^c~wZZU6^a+Gn3=94lPgjuHY90_K(kRBVwm}gpW zWewpj&rEcdBi}`ypTSHF=Dsr5l^G%Od=6%Ah+Gh@%;to&*39wHodu$;O^&R<2+M8D zmC32ev&ogosmZ6wmC32er^%JMbLG?I?kfxHKO?^FlX|D8`Mt;x?YDiBnWN2&;FGG- z(|l4D|MlPfTmBvI^Upn_ly{e>b#1u&ihxD5&HY>sbd5Svj<%y;c;im@Q-M+jEPLa# z{J!{(y?*9X;=cG!{-562^WW+3`A^?3h0+VBopq`Px}7!M#{0_uwXq{wsKFnpR?0UKBE{dF#+{z5fXy9miXM$5k0!Pvo=Y)64 z2yjvOtH`I!rVIyD#Yup2D|5kna$9mJb16f?i5=ADF-9HWM(NCaigAza^mfNa#%btz z2GvE3n>wY?F6o)Sn9*wjHYH5$SbD0av6_zMQi|uRIhNSsX)kB=8h{P7SER9ALC;QX%4S%0q#|2THphBX zO>N6G!drqPs-K0je!{uSqivnviD_m-yEG}y{v_sGk1O}hWQvhX z?w(GHnK9kDQz%B>y1J%PJTcvUY)-(biO#-tEb-fo#mZxe^{dDuij|j*%ZiMjZyk%J zj@U>;^=mz2iT@XJeQqe0SUZ!^Oc7BWt5hwgaTj?ku`*yDQEarv5>~j{QqR^=m-=S0 z#QN06DLu*udgIBnEXSsoF^5|Bw!v~I#oL*J5&JGY^{SQP46b`g<7Ci@=d6%WGCrEwt}(=Z=fA{Ib{VqPrL9k%5ug*8Fnefh!>^WB^2Xc zlzA6ZmN0V4!k)2f+>0}^kmAXvTJ_W>FJvzA8Ck%bh<)cJylXt?d@zl3F_+?rU#-;S zZ(G4sZPaFibK1aW?bJLA+gu*b!c3qXy0b6?Cg0A@#>xvWkizr+z6%hW0NAn zOG;=ov~riHNB#R^lf>cOQ7*==nE}tJabw4gXp1PfJSs`rDn5^>BxB=@Qu^0olf>#q z>P1wN(R;=!<@y0}yS{kcu}K@}D~}@EIA7wxh-BQjzcv*6_s;g0oS$b7$r-9=8UR$E zWi}-BiRxe@lXaZ6A$G3^ABdyOn=}y$Af}QI)Poxa&?|jt09U9Z8%Ggi)KZg@h||;} zNptdeR;iPmtQ5<*R&{MsoSH;&Jh5UVb*W5EqB1o+Zw&QXuJ7VHJkhkEP3jbB~P8Q}7q}HrU$GL(yP+l0i(>BW0G6a4{l}9M6_XmF1sqKEt(hl@DDq|MX{1wtDhmJT- z$nbx+vfhmeC{8=uQ@P@FD0w1xy`J`Z-|K5H6&{v$mUP+JVD~~XtGXKKdk*Kl3)Fo7 zGN5{q&`EkqXV??fow%aaHhC7AYrlw61+3yZYWtO^L)%|OTVAt>8FS>_`9-{m?Y2}? zi>)rYh-(X1qY;X!`M+cA{Y~=!{xZ*=)OTO*zrd&#bGI@;fzd6dtt6nnqL{YwfclDJ z+VY?UM%nE9$^!*PS#BjrbHC#O*XgC;L3y@s7(yCUXsnjO}wFXV4rpzrZ z=%QyTP|J`OsTug+xH9w!uEIyBimT_rj!6E&+F-R)d9v&Xp!$^?DWmY|@$Q>wjRLBJ zxq+T<;Txoe#?x>|@6G(LF5vg+znP-1T@|01zjhW-3)no$9H4p_Pyg)#N@?aN zIy9d?0vjcnKf?4!5pkqLtynK0;)34X}t0-19~oaAN=>e0`xraK6v`!U5!s5-qzfA1-McSt#7*?qaWd_hvm@; zAMOa;5nL*U+y#8Q6IgW*;BG*@aeu{cUz*|sgj(>777!|-|C0Aw0$jp<#t$q9E{C=~ zO22Uiw{z9Y^=N#8#rS*jWY5ml|JN9Um3ZXc!Cj9~9)(`)#Akbf(|5vq?zepUc%qXJ z<4<@8-h6j(-`;$>7k+S$Lq8v)-?#|9uZ>UG1SoZVkRGEZF6C;(!V2IDXt{9T&bbG#|_ivApBOW--Q&Zgg!$)DotspMM%rCNH83s*BQ=TUaX zbJJLl&*FRcH1H|D^Z7)FJq>+l>O0f=44>*Peka#Y13!c3qW;~UmA()Dm->BsV*2~= zW!C5aEXt<~=O=F9{NydJSNi+$diJFDGbv|*74MSocig>bmY-2ad@RU9QcoNq#ysA$EdJ1_ls`_kmwUz&XTOOtPZDW83r{xa?=Nqm+1#tW&-Zzka|* zuHxQyu(dwz-=!GQ@g1(;qeoB5fn0Bdsx$zlNHK5;Ui zoB6zhUOgB(fclCa$TQ?^-CM>)sa8I5nE|wQIM#7Ak^MKMeV|}M547NFV zQcb)O!>ho>(%#2_dMZl~e+|@MS<3lKJ`+3titBIa(Sup-+@ti}mN5723IFd3&Roee z^}JM@xjESXx7_)ggssKJcYt>vNmzb6K3@uDl0H1nJ$gdxbMi2sUz}*xGVt>hdd1md zXL0%y^yvL8*YIG%<6`bh!P1@d{vJx*36`EqZEd34PXhIgmXaTwyr~ZcbN_<+FZlk! zjIFdrfAfQBi?e5Qx8By$JAIrFNj}bpBp>HPz}OGaqo4F4l%E2B%ALwiV#$4h=Oo_Y zbHH=J%zD^-jxr0(dk)V&oAMM`dIr7cG8;3%!(G(QOSJJkW~VFRX|c8V{qu~(GN9D{ z^VH5u-uX`h_3svQ-w9^khR^;l@dV=UyTHz3^Doe&553aMS@hinzTKMk`H6C$pJ=(* zT3jq<{|L2vfO=tngt7*xulGmz{BGdAyzK>i_k3{fnY54QZFd72^LaG2oq$GH9GaqE z4o&eeho%UbLsR6;pa;6?m9*7qR{=x6t-kwT*KaF-gw8ty z zlXai$(|mFX&-7_Nxi~!~q(RS6b_7Bu^qGbAp822no&TO^#=4braco@S%DGDEG1p;_ zi8bKN=W8R@tG~gwcD=@0as}mU%$1d|Jy)C-n2?aw2smP%bDsTI|5s=j!>Z!>MoNzI zQtBS{Y?Hf*%tv9JQ5Wgyaq=~h6;9h)o?|X@!$qFB$gvl;9#1Mz`zg;gzYw}=xwFU_ z7y08NvyA%5W~igmdt{MQR~h~Qtx!jE$tl5i!ePkesfBEX7t$6GR-CZiwDU<=tF*&v zvx+Q=%H?uU+O^~{kn{ zPOWcSo4@^^IVZgr^QKQp_><^iqHadcpNK`~$F-`?M*d$-n6^YUT-~SGt1rv-J#kuk zHJrBlq?&osDys%c{Y*>Zy|vlOkvFlT%8=z=kec*s4I2MOTTv>qgbGBMvM8}ZKlLZY71$rdG>^$ zMSMONIG6U~wC0Ob%}sVjlw-8EJS0was{qL0Zc zp0JwdZwlO$-mU1_63%E9wRZ!}z_W_lwtRCHa24(C_~vH7&1i2=T}_Oua(kY!1<*Va z+tXeR_u&lgz!L`p%@MH!&)pJe?g%wETf>`}H9~#Pw!m%Z-HG~+@IKom4$3?dyU^PN z4?mXY?n>Di4r>Q`cL&Pd??CN6K;?-YxxSb39(aGVVeHA>>P2>>SKWwG#;#oVO8aat zp1CU$$1Xg7Z%QL@cb>U7-`@kc2d%wn?}8lhUi$W->;1s@!Sjye zx-aGZaKU@?v=0J5fCRcXHKW5ngmh`Xko_t9Aqnn7?Et>H4^ZCm0BRpb($Su;B(*Pa zUp_gIVjT1bc;-QrK|nJ%97Op5(EJSt@vQye!1t$iFi+VZ9@RVyhfofN&ompuM<|ED zAC9MWDCHyYdk68f!+~;s2T?l`cm#asLDY^0%9EPC;TWLW2y-|b%eOxQJcRbK3AY_f z`w;5m`Q$jBav1OkuE+8HBY}Eh97pX4;9<0m=bJ|ZkD`4%wWHuYkD+z~&o~Bn4DAzn z^0B~UX`jS>1L1a$qjoazV{p62QTqhnISzOn?Ng|K0&ZIE#3%XAM}f!F`zfAtB2bOT zrzl3G>ltw>&l(8STjW%pcoI+@$f-Q*WS}~bQ~CZU;Mq^1b~@iY1*jh8bZV!;zkiC_ znLO=Nz)#UWi~AaoFixfR8Q`apUQVTUHt@5^J?d@Fp`4A>b2_chQO-f?(O2VKzJEG! zBF{RPat82p?l_NUH2~FfpT`r=O0v(Vf$FNx<5{0Y>N%U*=XuuINIK^vDM$_37kI|! zfS;rHeCohvEmrzqC)rl39Z&o^P<^iv=U1ZnFpI`FDA%C_xrWyDly9J4 zF+<2VDc7T;>7;c7<(p`5u7m1*8~82sJ=anDE>KchvQKi|fs_zYY90tsn5L?*YF@`xffzaBkxIL!NOH z@Fve5UC6%b@b97AjRb7m@Q?WZ zEkO12Kcc2|tgU)YqVj8aVn6C?t=I6x+ks|BS;MpLL}FGWdM{-ST7`Z48x^a^X>9DV|P0KLK*YCi-16ph6iYQNz7Yk+HLKgc)l1>Q^hA^5_n zKy}LxQTs7a4f8{^A4F>+Px3HN`3dj=S`Slu0QfWd9!`4fM}X>G%qR3H-}wblZTO?q z9zn0FEzR2}2z(13Tpo{BYDSshP!Am^zRp2Y+DtL+7>%iAw316a?W#*2`s29is zWCp1sdNT3>k+lGrq7pLmNEK&YJh3=4k5mcan6Cqsrb@C`cz#J{Myry{tW+g@_8K`a zGVUtnsTr`4m5>9Yh+6so!`@kd+fkg4duLDF-Q~tT#6yfY5Zoal!L3+vinLg9cPlOh zN?ROCp?HBpylzmcRA@`RMgH$Q!~V{>@f(tG`9HbOGvCb4?%gvx^7(wjTXSH}bpzgC z0+zUL$P>+og;9r6V_+lVVbr126xf9L7Ii2!&;4$|mgF6R(m)4diLjG{n)XB(=@14Gbxi4@ zBQ+g}Khl!g&ir0WU`wvM@O!O*t+*zF30GbD^|rvaTy^ET3lUG0OShRL5Zh|JAHv&s3ZCcS3QEhlRdcV1MJEjqP1|;+#jP>Ldn%# zjGngX&Kji&bs|cx$`nbOaMz9daol;M_C%S&ojVhG+f<;oQBM?`Mp9}>@`94XOv=iX zO`@dGgwmF9&hCbCkI*dsLn%RtU>5J{3e+=I31SL-y|TboB;^QwXSOD(b=G%g8)}p$ zlvkA|)Nm_HC@E|K98A7F|JfC8eHNu1fl36kDDA{sQmmkz;L}sApsnENccolJ4BCx% zZ372yETG-tq6Y&9NBKZs-`z<`YUm1Iubi?6Z`~27bg&0W31TNovw81M@bo)Vn#0?7 z1}5oXS4vuL)nO({K?!0W?>2hP5c0kF|1R+6dr;a3s0DTpO8WuT_bXHE&s$~#XLGHj zFb594Qc_SxDCC79QBs)4^+E97L*V1J8!9z)0q)D252n-^xDR)f3$#`wc|l3xGyHWQOQaVs-P)0Zicp$Y$@c*6R;17;6!og8SI5^4(MixApq>P}nprmjJ zyt~ptk{6T+4uykPW;i~|3&->3!zn8-98b~Gy zN(X21md^o|9L}OF=YKM}nrAiKn~@$K zLEOP_bf8AN`W?JiDM5+gPLfiCGQwRXWe25$yGhCpw{i7ll2U^bfl|Zmz}u)*UT6=$ zu59oXp#1+Gl)ehox~J6eHQsV3@J_D3PFYKz62t@i|J^`khX*Jr7mVQQ!6=D5NJ$w% ziAhPJJy1#EA>Mu;Q0d^|C=onNS=m9~k4H$#4oU=%l9UvZT<~?SAE&HUbYzqcloX!e zKik2lKSb$Cpi;m?l%C=(4*?&FvVgL~(*u2sP)GzxQh18m7kRr9ffB?^q!;1Yl@z{>e4%vk z47D%w|83#cpQH3DP>JBVC=n<-yhciL!SitK&#zKCNV32v-do5BdbKW!a+Y$z%amW{ zYI*5kG4E9(P)1lnS{!8oVhpYr#)dLv2-Zy+1|kg_tun^8je1yG4V zdEqUfmSd#`rGuZszbENHDIm!R+Khh=7ykwl({F%E3U5$SMo>CPazT;>loXT*egRZw z_yc8mex-vyM(N;>l;rt;#r2>b|TnzB;EJG}ijK;?x$^RC|kf5)|Q z!P~&Mx&CXE1^&vr{y;fN3V)>ZH{SY3;8^m%QBrDn2N~)gKqZBDqC}vy@NeGo4)7g# z_5VbP;6K#-8%|sq;lEKj_%9_n|92zLKbAMX7bT$gD7{PhUGBXf<+b;Ddn?LH4e#^z ze*phQ{sC`PGEfRAB!&M_%7XlVhD4yeApakzQC|2Tr95oP+jFDsH@5ktON(T+X2bnSOlo1*t7kmi(klIF3UT8#({J&B|W8Rztm5&;8og{)1JiAgr zlgR%!3CeLzkRVzT1+N~pO`|N(EXo4Scvl0s`TEp0kNkggWdZp3MqDcq7@aOj1mpOP zR{TGa4uJCi#N&hKCY~m|yplpYQd_uq<%RYnIeg`X4kUSd<%N!<#MQTeA0LO*(TVzw zKqaZpyuCS44xcE5$MZ`A`Tt%(<-URZ243!5_oSvLSA%$OZ(v{YL6ioD!ITGuA-t;}upd`LNQ1*r z?lsFcp?*jh2HXTVfP5IgI3Nt??$9s-I6REx{|5pGay^Rj$S|7!9|Ro4^%(wtFmN!} zWBKn*fSXV^mNX`8%G-tkhjG0rG8cQ2crS5uc<<0Ko;MB$4iDqP1j^%qBgrT71ZPAe zLG=YHXH7)D>kk~qok{%a$S{dCA#8?Z#Evy;CQ+Wm)n>F~RG1uPtI0@Q?6u{6eSzc1 zr_iR+z|lNCg;bSIjS|*W{-ZbL3AAAPcPcysoqh(4B!= z7(L%h>!T-qdG42|U}>q;wkeONPmQrSw0COjbnk_{hu$vk#*mKd|6)83?PYqq7{f!I zo)Ks~1x`zu5okP3Q9YFrXj(y;T!UIKwN`4~)ZfP)W{$hIN_UreI+kZ(xdYbSuzDD$ zbKpGfN=a6qEl*oiKGhdl`=a}YwJEy$R_Rs0Cr?gQ{?+fv)2}==QSV`)GO}l2xv$I< zv9u|=uS{E_c1P`!o`|JwGR2|M2R&rkH?>u6LrLh>HY6j-x(97rYI9&euD9h4{eat0 zw;i=5;I`!3QLpr>E@FFX>j1YS-=3BX01n`42WsmAomWbjb$|oOl{wQMR(Gxr;%Y~} zYY=khU`jjjUG;&=u*#_QkU_Po?o4V3+=;85xvN*HQlTOHBS%N!en)H|2* zJW?y5cJ+DGD`jhEpU3>%6d8CP^?OmChwQ7z;ohXSQ9^DF9LK%AnbqTf;$bD^w!jJG z`%-Eb<>$6Qcg5~YQcl+oQu(b-eT)R`Op!$|W zzz@@bO8kd#t#6_pp`W4ND9?v*rQObbKkgYglvD+rLEWKXm>EEIFNXp3hdY$Jhk=nc zM?S9t7b&H?t7r@I!=p~d`0PE9$@R`Wf||pT+w~$ilGHoO@J62Al6yyj@wNo2r8zR{ zXO85Ft(noAFo#{A^_XiJb9Fc{?EoIa>~VdMq-Hqt!`e}CPL8I=od~X@VxRE{o-Fnz zY{GlT#{U`1bHkYn8FOqL|80y@SL?XAD#!6311P(P{f#(PljH<>3V0*%u(nNlCdZ&RM0!gKC9$oQXW zT#pBe`KR%pJ%L7xm`1HO`OSECI!QZx#{bOZ`Du|7xTC%YV=ks6+uqxXCrA@o=Y&+og{Kqb&9l=m)1C1Q8GgwD@ zawD!;D{$3<){!*5`Npry;^LTQfNcHxi)Rgib)a}D_ z>i_g9*q5ZYz}{T#2cB&Nlp5~GQ%!)Lkf9fWyEdd>`?GdRKylXoT<;AQkun~@f2OlL z8d2Vt|2u%R9~eYhc_2^J2OdCvAaBqQK@Y_PDeVi~mpf9p6fdj?bHp`nEK9vyq>1jh zssogMbtBaSN|m~i+-)cx@I)r{)B2E!ae6Wu(hJTMpjY)c6n{76DtW8xtKKc*#LkSc zSiNn;+wCZ~Wv;Yh#M22s#J%VHhsEnmuQXl(q3|}HWvNuQbJyJ38(kQ;l*dz5wBVykPrHu8tHdaY}%J#TWdYbr^ zoe0I=#+pcRCyIy@Mw*yG&xq~i{ERpu?MQJaQnX^DOc-mz=o8`s`O2x_ z7%_rAYErSpaT;l2GkV&XYuzbL0vc^i&eez$(nqnCP)aJk6H0T%dP1qN*i$I&cIE|o z->@7dgXE_#OW%6NHC_x6mkvCJ?}0oN083?;n}^)r;eug=9ggXQ9z zu^yb+^78rw%fHLTy9$gTQE>6D5PA7Vtc6N0-nAqbpH6bu6Hw0Hb8HhwFE1|_pE&wT zUf%dUdJ($Ab7j1|JInRvOn#oudnFy?Xh=`&6XR_s*~s2BqM^N{{F5Z7&EiT(J+9oN z4CJa)#xka$tI>XI&DbUR%hh73XkI|BB)a^j5G=S^8hLc+sirb_)!l`kzv|Gx1PhkcanZ?th9cl5Ll*JV$Zj;U!iLiZy;x;7( zq4>;5g%g+)%Faq0Lh+gL*;AbM6ro+Hq#^|rN|B7op1gaCc#S19oNX+v9_mdmrC5?uNcSk)5AIlYoUz0+=FX>X%z%EB?H|vz zGp2u^*f)KslfD=M*kf>6D{47&j{lW&aLsoHa`s*9 zqt2AN@>ECWNNY-B*{;lywm>noyZFVM?!-5ufP3`=FsCoYo9@8x3N$i;v3YH$v!W9T zO>Z1oqiJ|%r0c>czDgwPw_(Q}TtN2qRm%DqKt z#QpL$Df?XFgM>xdTny|lo7*mb$@iyU*XzFWcUScMs@hr8=WSalwkQ9;_N?jqZM{3T z+(EUneyeOxIaXG&ha>Iw5JR^I8<+QRRPOmmyEmlm<0Af7YbsYzxrakts`Op1AnoCh zN)(a3)O;p-KPJ)^`DW>k^gPjfV-L#%NOQVHdM-yLht-`r`NC|1*H`qow*rB$iG{@5{S7 z)M-fj-PIwraHUA&)sQ5Osq4k_Jfs9_Sk+*fYf`WOQSX{j*}dXI{(V?Qg+&dXC|j6*WDi|Hy}P77*|o^r{#YVKP`@2 zF;~4}ep=Zj@z9B%E^HNvpLWe9u3CDaJ);Y-IzKH%NL+Q|q?J$HzvybK&Q)u1NSt)y zsw?^FWLZhJmP&rQM_g^Luf$2G^<~5-M=#lID*0(S=*EnfBbj*XB>z|P(21)~9Cju5 zT=3S8ZL(t|emX_P5p(v5Ybx0-`o=LxE6X@SiJwlKwBuIr({ffxZZaynmYwQSP|f6@ z6_1xzpt2OC^r$V!c;LmTB`K)p@=vmLX)ki@#EwbMOyi}*O*lk}GZ`+(QRod+wx(W3|Nn*cF5#KqEL%41gzfC&UnR}c#O+GlTH^00U^r;KA zo05->-|TsV>KDdQqb5WBf?wMLDEB^|8Z{q|l+pCmJF0(lyv767mNcbKnZU1}NZo|k z7fHXMuW>)_xxS1gtM;iebfq7#ANQ1&528@W-?-FTx9G$6*!{%|+)O4s>m=07+;)z!B*L7l9 zeC|kfh@;jX=;%0Jj*KVIRK_xNygD&5j-+E_>_Q_NDx-UDj}ourWn3&r(ou7KlqDRM z)^Y5HGA5i9&UncmI%-3r4xkHA{?JiL<7GT@$IwyJ=Uq<2@iHp8W9X=LkE5c7*hq-# z9^?!s0Obq^#8LC~p9$0^y=xOj&@pi&lTNm89KD`grPC|q8XP@GC5@NTvbKY=fBv^~jPPx!i&++FJ~T32|k=YVl`~w4Nz1OK0?lcZC@L(fzZoqb*4K z#=FY4B3%ei42U6o{u_nbM~vN# zYtN%_MTiMT0gbj^MQJp1#j{d+P#VLE@4>9@Nog!|q9=2u7bRzm)*m(5N;*n2uFyoy zlh#r?EwxsU=^G2`oUnbO*9pVR_ZGT#ccRaV@1I3KsTtJrq5dgpqSW0K8mfNGjzV*# zUbxU`4PbVt<5JTlr>h1`-IqGBA#o1MD|?2ab2e$qJdY*m)sme@t(t2h>DZF~O`A~C z#-+&aNpI)Limu3{y-Q~=Cf%MIKlSUb`lR_2Kd2WJKd2q_L`SiQ*uaw>lSXkIdD1bm zYlZpX+D|7#s=uB{P0~*$ZRKXn3eT5Rf0;Cyu2uD#;xw%cLh+UTm3q<{==!oJoq?_| zd(wI6`m!gTfvzum(s}60vL~H^g)feM==w^!N41fj5ow>=d*#^wt}joSbOySpX&*(=nhj*0zcPf9WEPh%(Pw`5PLi*2m-jH@DEv`D= z)Q92?*Oz_h9(-4svZT6UwZZnCc*FIj_Bchy_Y5OfR?;m`r(BMapU!YlAFbWpb41ls ztGo7m(G|zYSNrX(FV#b|tr@*)24_#mpD)R_ca}nP1HLLYJ&= zIgOOI9mg=86Y8ibHMtIwj=IoTtHE&QCw+DrDaXgrE41Ivc4vM%v((c|S3T#`Y)@Ku zN3YPvC(XPg>8Po(SFhvDFJ^n1`AN_3s3nVLvUjG_3>+V6t{RwhnrpHl2$M}gDw}K$ zg~dT$HCZIKq~us>`_^8OY!^ap83hhoJKsNN%kuU@ajRI?`BrH!bS@^@YgymFWW91G zJExV_o$rt%w zLNQL^`?n_c!b;yiah#eg@t<0g!uRjv(G;;`T3@T9DXu9kHt9^=6|b+fvRq}Ztku($ zHCbO$lY+9S4J~NOnyjz1vRq|}vJ_S`ab&T+#EylP&DB;|-&VE0Tv_SNkiw=XR;<3h zk|j{ASbcqcJo@FVNmNYhm?sxIr&dnC3ZGO@MNaff%2iM?XSL%bA0=kgmZt@;pj_fZ z*TmY=FL?rSpQ9$_a_kZnlkZ(S`Xy&rreZ5T<7HjaFa7<}S$F#PsgabX1bR!^Kx&fH zdr~pyyl4DK#iS<5Q>QL{DCahYR6o*`de9MhHmON{sJ-+{KB_^S=M90bweh6Jz;Wag zC^Z3&Cs&rmFP$s*&&spOO?hUoR7`5pjM*;F=A3U1hLv-ZrnI2nq+(OKYRR0Jekt3u zV$QqDq$aJQ`AUvTGHsaU(l2G6wontT$@=DWh?K?iU^b`h2~Hh>p6xV?QYWB%n)AOS z_)7XE_bcbtm$J4~EvWs-2Sh41Akr*(0Hyu`tSnD!tpW}tm*cGhy1u0TLg|;M6&5EK z_F)AS^lOKR8+TyT^xV@c&&WJ_>!~x)581L2eDt&%fPb7kWZ}7|m)$NT{q*$R+m-(r z1k{^Z@4A6_%gJZ%M$&)J_{4e|>ut9yPwv6B-g>T5y^D9jPflKRHc8JtJ?`d^jK`xc zM31_`K)v>is3isg&{qct3WmiA?<4MI1 zWM=A#r^m2fzWd|7djQWIOd1YU)2YX=_4*JW!t=)R(I;5XUSsjIRbciEK7%vpmZpHx#F=Sqj&F-ln#sgZx3hRtr0ShB8`lDajnri z*Ag~q`?g>(}8 zZ%^X+Q%RcwPvPqGtlQ?m=KRkWNT>7f@@2p!3<+dm(q-<$EDeUCE`9vKSkv9p$z>WlW)qfkqfI zvXGI4F5yY{{Tg3Lo!%8Ze<^!?FQv{MzeW|hjC)s+CIheJ>MBZ8fO4!?gWZfi)ShRr zAzcYHqN%%ouVAO|RXpP!;H%i(E7y7*IIttI1NW~dT@&~HUd>)#dEpy)b}G=_$i@=7 zhP}U?c-n|V*TD__wl?DiteNA&S9aEcJC)`0aT-MKWP^Ghr9FCSD^yk z-7D%z)RTIuMBxe5n=7pgax&>O3$<`+;H27~5jzlUE=?asQZJ{LS*kDh-yW!auTK1C zPr~%9oOEul=djgf1-7H69=JlTN1jDnf_mq+lA0%HW&oLb6t_gV`&&iZ;k}nwr zJs1}`BhPGTN$m(=EAmEQQcuooNljz$YV|=#era;F@>5Mno~4<*(?(O*lqB~g zU)w*~qO2m4-0q8Y1KEo-rt(B7-Qqfj5onQ<(N z-6Co#lIAIC610ZP(K|-s#PVLkBnuQ;g``Ok+QY?OLVLK_QK-g6yMNgeKnYP=r6wV1 z+mus^9fiu6+9OxImry#Z{dn0Og-T2E94p>SxV%2Wey!9h6#mDKjNYteFJ$GsVi#dq ztDtqgkPGEjlO0{?e5v$5PBz0ztwJ$llUBi*tKU-cztUUFwW=3W&K=jYURVJr?(kWy zBpdR1+puh_K3;qDF>`(TrFxweUXuPw`s(WM--tI>gg3+(345$7yz&1F9h3qlYFInz z;F|fbE9)1Y>*@p4eyIaf%PfzwdjEAb4RRR5sqobD96~h{Nkf;k;Bp#TGSp;zJpc8= zPNl^~`%1E46?%PleOLEiPqr`Vn3l0*Ef@)HtMpt?JExLWK|Na1iYEJ;RwFUAIydz@ z>gJM-PP;{6%}`&Lta@wazpmD#;NA54)&p0JTqojU@o@6f)~{RdWigo=jfA6pa@{|l zFn^)}>*M_^Z@-*p`AgGz2vViwfh27KF%aYqi+xkcdr?m2zpYQFv{|Vr`8H_*adsrmy3!8Po4#lZuW6t3j(ycT z_FixBjC(6PQCr=gLB6hUaDGWn&i_G*S+~xceW^ZCa)W1O|RF* zIxQrNwU1Sj?39(OHQ6hZ)x$YiL@d!BQuA0PmFqNl7gVm+WUW-%Qm#w>^-`xwt7Vch zv;wVMzEGx6_Duf1$s=CLLTOTswmyi?xU!U??cOz8tWf7{b@^ghd*!;0Riee9h*+}f zSS891MZ}VFtdbogjV@x9IQvqp662Qah+cmuYN|&makd((qybQhUz1oRu8b8$EHO%n zb_Ao5xQ437Dybf&WF+uw`)_=b7Qhs%#C5-- zSS95sC3{7Tu^0T4=Pqf9)%ws1Yk@eVh)j~AlON?e>tdbO;#8{*1(6m-qmODL|bP%=&@t#pgx&e((Qp7DWV##OFKWLrMKBh&( zC?%D#O3G164g*UXnZ)=dhrufwt3;l;h)*IneK<8nDUrJ_;*+SsDtP-P+tUO|g^t{kMO=DbUGJmEqCgmt4 zn=|558Hd2{Y(ZLatP&+6BbH17PT?&^ELl~o5~Gx)h$Tgo5+jzZNt6=flWYOrGybp^ z&y__fG3u}p>l#>IwHcCl~Te2}$$;x7tC|Q>ymZT^pLZ$2m z+)EKl);?B=9t6%Ip?rd~P$S3Rx! zWz$}Sq>EqqzT>3DS4)_*{3)(h(kG^!5Xp}rX&e*hQr;O|aQ=zYNt#Q&O|(7eahmj- z>N`_xF`*jJ#7U){9EDAz9P2qniYvS}q#bf=X&07d`8RC?YH1T+Cx2JOkkC8CohVvh z(ykPByM_KYagX|*BwcV}(MeIR-G^1|fJr=m+8L9)THNPTwixN}lKfwa9f*a7Lj6P$ zi978>OxCHi1F`V6ac_^7vBHm`ew?}54fWX2N~k8+TAy)N>)Y|^eqNt8zrwFcR?y;m zwURFXy&LwtXlHu$UvwQfhdrm<_Nm9O$LzJG&SB3rcf6DmJl)st(h}e~=&n2^R?kOo zMS0zwO`U$l-}SfBdBgsStH1hb*sZCl{zZPHU$lPC+)m$`&g8BW*QneSf6?-e zwA3#t+MimkUctCxspVa0sb5mGKegPiXdb`BHg~6`eu*uw0{SJXfxx`~K0ZWp#1yPK~=O_C`0oSKN`|t_@Fl-j5nj&vxgHduozK*@)Lh$@Y}IxpA+@ zNkI2{X!F~HT@#+ymQK$*AX@PbK>NKXdqqy<8P9$5oM=yoJ|XVRNTG8$6Hvk&))z$)~5RJ|km*`T~!NoYW|unTW6d9qa^{MBT)=2jS+p z1HqG#-AUkSYMzzs8E0y}Cb37rQ<1gPX{|eu-7}ME(E;q@&`Ng^=>*^jv`p*X@$7o= z6oDH_7r{BXOGk~v@$8h)GIs;%M)pf+pSzxPL$rGjk9!U7WuJwXx$8*RM_t(_Kx0j~ z|G?AI+*@#MwAEe9lh?uT58>`L)La{_-}>MWrp8zU!jZIJ8~8w=+-U#EhZ@0TGjmJ02d4yB{9pcif%eu7_feg8LF4Bt4KV4O97|r9oTZ(xClsY4Bw7rNJ}F zmj+K7TpHZPv^2PLX=(6W!KFbx%+jE~d1+8rvoxrySsK(&FAeH>mIig$OM_aVrQvYC z%7~}>MsJ3t=pkDBV5E=6$@h$q=csuI=&qaR*eP>K#C_Xl&r*I4OxKBLI+M1^mV~9@ z8lZb`mIU|PED4^ow)vYT%{3Wl8Y-H1Xy(Ku^W<PKxR$CID z0c&=l=4r~`0*B6`#bVN}D0@o7Q`A4rd2LIAXS2P)X>6X*_7e0}>$GPzzXa}YMfpjd z`6ef(rL&s9&8ca6yXfy@T+MHA_eoA=dxcZl^lUMPyxuWQN$nz@Zo?UBp5yi!Z+HdV z&e^XYo!+KDKqJmd^VDYbKMf+SYsC3#i#T;nuY*RMdbWfU(H7G7rD0(Z|1S*E+l4`F zzcA<*zc9$hFAVy{EDZX*EDY`@`CdG!t&ErIg74iMnvt3SwVBI@wFB1Wj-GCHIa}>@ zPI~(RX#wzioU--0W_X9X zKXIO#=e~Jvo2NMcp6kcL<2>;g>6;;)-u6g%l5@=UYvCGNcjd@Xz@T+cH% z0KY~4Ay567v(`KfuL(~!4L9-BcYxmsuX0-1V$LDEnX6ZUuhK`2sA(K-;p!FOEA-gc z!vo<#PC8r6y|0F^as5@&gPeu7nA&?NJp_CxJPiC6zj_bf@GaoOE zNN)rG&KYqZkp7u{CEU-u{>M3S|K_|m&z}At>A%^1{P(@#KJGmTe2}aA!dJNR^y&X` zKHNXa-{bVR4}c$VRiBnL;JmiQoXxf%+)BF_gxkm$gxkp%ggeL=ggeO>aBpF_i}HeS zH~E5aBI$FS+f|Qq;6{)O>vAI83Gv=Z+*`nzUyFG6Fj75WJ)RoLQ+0rKI4kbta1zfP z&-;W6_|Hvvepo!)s{|}@{@m5!nsBYBvvES)apB86dmQQba0>sufb+u^@js*EId!A? zk31a9)7Js7%yIQ6Xsb!|y) zIM-|u_b#XQYT(tp^>UuNiu2%F@Wepw4hol2cP;QT@=M6C{{oK1cvzjrL~B7XZ!(zWr-xeVyJczx)F7QjxN zN_Qd8oEbcmu5;Lq_iPV5gM3fkGyph&bK$nA~JZV$lrkv1rICqW)9zi~lx(Q(}Z`c-iH2K#2{}|vl zm>2d6 z2T?m0crf`??oJ7thb_XEz%BXD1GzJov){Jn-v0c@KEQp#zQBFMe!zLu&EUMZ&4IIc zY6hiQ;Q;<;9&jE{9Kbu~avIzW?oKC7gICatNj`H|pd9GVq;26%JcU`#b6a>5&r$j; zHAj5JXUbdZO`;FVjA)y6_q}`a_bRL1B+9cJ)`+h?zqSK^T5x;5pB*J z^r}%S=5FZY;9~UE*^;zH+(Ugbe8DuX<)71zYfo(UwB@P%<~Bf2{q`iGt$RWpWrE7tnN~{lYU${$oD)-Ot4&08`45zdmeE%Wv<6odHhXCcwN5BKSXWpIm z7gIMIsMp^}>PNr@UrhO;C_7vjWsM8D+B0(7H^6b|@79gfHSVXL3sg?&PJOq?-`@_r z9X{DT*Yki%H&xv2j@)oQ<(^#W(c7846L~LSZ>~D=9eP<0<7>3{^#pqQ+>LzIX^{uN z4(L8-_bJ~5yb0d_#<>63-OIO9zLono(i4|ti-I0{i^4&C)uNzeuqY^DEDA~)i-JC>Y6LQSbz`ML`*CQ7|&WqM($aCRu&Y z6!JUy{nOxLl(Qb;>NGg2DUriccl&UZyxh-wI-K9+$p5M3Z3fSrVsLB*PjnvdT^QUS zzc47%Ee!67Ul`mUzc6^3_QK%a_l4nMq^pI&z3&UdL%iL+#tTDpZtwB$D?z_U)ER%u~jcoZ)9Y51+D;h5d&yf7%gmf(t?qE=mjIvIIF<&A|Q zX@8%9*LpJUo?aLl!ZQZASoNo#k0D3vUbx42$D=?`VRmox6Tl~_dp%@4k1E2Vz!}N$dwR3yKtE5q3#feI z$;;0I%QC`)L0inR5F+VJXbDtlSEar#B@bB}3lEwV66d7ZF_%8hX zeBQJWzDrK*EqLEw!3F;cp85XBi`^f2vNz$6--1*2Oy!@$H@^vdlk(kgEcd|Q$lcvd z`WjHa@osAGhx7g!&v~x%PqMorFZ64!eiFI+pJW#y5j+dmx_}mBLAfKN%^zk`_Gh8} z&qOZZTjbL0XMxYcpUPp*4}Xo)%3pcc>+sa``Oiz>MCDiH`7eolsa)fHxSXfBzLZ{h z3a;{fYA&OEX^^{|4>x=xJo10xHRr=G-UKgv1MR#EcxU9m@|S2Tv{l_T;G^q5j=l*odA!}m9YkL$+U>QM^7`sDI<3*g;O zryb`+o-J{Aow>6BPV;nXPa~ZRl(Wm>((3^0!29QxzQzK8f74@^= zyr#l~ZOv~k04|7JTSu;r<#)dTJb?UIN}osC^91W=B+rj-!qsuy`FuQAx*43^6y7tL zbPVtqc(85Y;u1;PJ>TZIB1r0X?1iB&3p4kRO`y+~+7A z3p|!*KgXR@fXDGat$D5)unl=@O06Qlxj+17M}BWolpN;5b?=E}GYqbE9_6{nE}Kx^ zi}F19$T^huA?=M6G8p+~TiQAYxEc8<-r)Jj{m2J$e+az$zzB!%mf4XDogKN*+5FEw zaM%N=?@#K7?6Dhf8N+{%Mxs!L7*6ddpnUl5+?xZO!#yRwQE=b#;X5Lq>ZV>_Yf-YisL#@Jq{XEUP#a8&1);So zSzbK%Ma!2K3#~BPV6+i60O~EM<-${Cv>a)%Xav-@uI0j5t6GkEX_FW)Q*@lF3mMSdu}ZUSO-IS`DbKj> z%puprr*~W`XPjg7|HE8c-8ZFqR*c-I7bn>Agtwi6>B>?~aCTZp33IP(9Th8RO>wr^ zx{SHYI9qI8#@y9$b}<^uwOr_{q92J~5cZnXO`PlR=@;Qj*V`re zzO)3_BwrYPV(LXIlze6EwWeShsaAtXsl-7|BaPEK;;;C2yzBu9&V#eE+)tt`+~*y8bSIrFu^mUP_JE@VhEU%CVDLv|wx;HAkvB z@0WM*SDGy|Qsq8e-FH=vROK(GS+Q<^%lEHtZs@I*e4VO)UFyA>eplreef&O5vwdaj zYu*0Vx>{eA^RT9UxU%u8#2A$`WL0=WT(SDKT+=>WF^*b4zqMk#vGKQ(N25NKYm1|b zK1_2yQ8B50b^2A)xv}E$S{*)I*_>Y)t*l&MX*SkQJiji#%X3XVnKd8-c4l1%V2HA; z^0|H_Ir2zGZFjEg0K1WULTU!gxTlXs9b_5x(Rwm=!~&wPT@UWm!P3!#vJpM>0ar@Z zgQG4`uMc+wPQWsvPl!Gp^{`gxJ+8IHSSIS(_3vm9tw0TssPs2?|Db0Ly01ySc=Aq9 z=RpdM=b-Lf=#D16*^QRjkM}gh!elHNBgQns7ij>{cq@&uR1E|U_Q#GN~ znDyWeD5L(202*ski$jX>I1DQ1J}9jco(I{Ca#Q|S{}<1kY0C9bdQneLDW?9`(s|cf zefqjy?DfL_;4|JWp7gFy8q=>1<>Eab_nEr!7m^3K9Ek05?fPDSsXk@f;B&Uz_Surk zmfIe8ItV>0D3AVaIb}IrZBZqXwiT^Y#(MW%?mnnX8U-8`-#a4y!U%q$K7BfZQ8Egu zdz_6PmQKA+5n0kX*zVj+r^Pj+WXfwN_PkH@gDdchDhP zUft>JYH){wJDrvB-Nn#}q$b9g$?gF3WCeFVyX!$sjJ7m)IxCxKKkG(PpQN8$cargi zCQ+)2HZV^F)8?r4t0z$FqjtVtK<$rO{(1wAE~G8cx!H{Vb5^D~>J0T9pEQ4+$M&GU zd})pkBXuBw5IZn5@Ufho3(y0T#sSU?@q!ql9!Z=b?x@SxifIydsYjkLh1f)#Vtf^`k2pwd3ZdfJ;k93gXUbhQUlO6^l{2< z88zqIEb?}72DXc{uzj3??c*%;v;of+a29rqGq7Wvg`FrH@kKv?&Oj~C&PMm3YUxgU zYTRA#eDmxXXJfZG|GER+&+2Tf0y^KEjXi+QH)mryZ!Vn`*elLIXPtA;+1Q)1(W{() zeHi6&Kxd=tN~^x}!PTZOfb+*y=owYcx)gyRtym)y7~9!-JBXxLsVjUi$up{)nQ8Tl z6+BZ{tdKB;yQ7@j;(a3}=)dX=N)Z$i#u-7)@Q9O)vrv!uEmjgYiKWC@VlHu*xJ-;D zZWG6e>BM>N@lc8u3vL{*PuF;rm@ST~{9YYqR1;tmuG3DVy3|Pdl4Rs=qx#HFrFD6* z`jp(Wq0XcM$vqFPD9QD<0=D8>9FTM@N!Q|)vXl3G!dm~kA<+N!tqp*_&$s&<{-(dJ zZoszKCR=73ZL2M|?deMz$FFhEjdyKrllVW4d1DKnX~DI>+!AQq>V~nk{&pjN)x9eX zNcuRq_oF^ZZ{1?YknuC!yW(yZc^GkM9g=*47_~&wx1u8@zr7={W9(tqNP!J4+v^#v zu_eu88=A-OZx-9oj2gexHt1*Ux7dazB)`-)G$#2iwxJQpZ%MnBI>c`gtE(6ETg2`4 zNq&nMyB^7J5pUNe`7L7gIwZd(Vf$|JTciRxDSc5DZLi|Gs!F_WUH*UH(c+`;uowL% z$IUPBoBSHTz;E(v`~ttpukj1~Ccnln@SFUaVh4>Q;}*nTxow#3y`$hUrlx;I;*4z-X`{R*|8wnWXVZAfc4r{>c&cZ*r8H7Hph z?Y-1@2}d-IBioek6*D-RO-Rm4`=K$(5qC7jRgSo$*^uOjJEI$r?B{l|haJ;;aWusm z_I8KZ!_MnEaYl zo^CuD9>*CqDXsxeL*5LorYYAG;=1rWWq0>DyT->p98bwp*jsRI#0}3uv_FljJPzK# z{xr(Xrtl2*XX1HB$Nn5mjXQ)qL3(8D)sd7(!Hw9To8K!ZV2>29t)sJEe0n#1jJ}hVWd6LGW5tTpPn(8My~} zKcG^x9Cp9RVS8eR{)?WZAt&C8{<5zc#=deTIycf9)Y?#e4T?$1D>1D;Eg7!HVht9n zPy2_fF;uL{O<9)$xN;q!it;mNH1^TszH4QU=$K^g+ttC`%ut434t& z!8Pcrkv`a?jmUUl)-+kqzR5Pl;ER&?m=(&;5tb# z_OdI_5lH3r`CaLY60J+$l_;KbxcEBfu-}*{p7UpAv@U&D7Qd$Wy6WGxw(~a84sAGT z_jf@-67A4Nw><5r?8n+hTOHX%Ust@Q64&Tge-dWOvVj;ztfg#_sJv(ANcGFR*b|jk3eXp+ zPQ+SeDz7ZiF|LS2>(#WBDSm2Y!Z5Xu=d8_ZHgUp!tnO%krT~ck)T| zQ_Jd3DsfEZ8mS3x-q?p_`nE3Ca-kuUwk6&wanO~#)tczZmgSu*dHi+J&PsjW$Ke5& z#W@AWQHM~h>rcuyA>Ufo*>nOcN&(Y8hC;Vg+ty9xny$^`T-narI?kVTyO!r^iq%p2 zXl>L^x>8A-Yv1}PQCH3Y}H|cm6-V)j#^p;RJ>ApL?CDcv2M^bMI z`78I`=`EpNLr*WgCDcvo|E0HtI#WHRlyKEe>X|1$Q1*Y#KhjV(V;l>guEZHAL#4S` zqK&rJmP?UsZIX+%hbt4SDc2ruOSO<|54WZ2JhX?~QZ3}}6||*V$koBv(zLtN*4lns zZfkA7Ew>G}zXN^dnr%w*ONx0$aDk8RbR_q=#PNv1^?CD6`eo{|=r8E+q9>!jtiOvM zXSPUx7d;bt}gx$-G6+bmo8M z_L7y^5!F9V?T0O~mz)u{#9nfy*faK$Gsu?MOU^7?VlO%4>>2yW-bgz0WFOZP$gfMD zK+a|R#P4#BCp)_ytM-vp!8WAXWi-~1>1U@U&UWg5r-jaE^ve_5*iKKF(96Si>c^*z z&vxqHr&oyW^n3Ldv7LUeUL>~G?@ha$^`1#yC-$S?t2c_R)yt-OoIkx*^v+3MEw;Wj z*Ut20zgTMXkG6HgZ2V~&9s#x*In5yQAv)Ba>vbv>@#3t!%!Y)`u8 z#gk$fae>&zJ`_jTxAvYmCt;h8{BFY4j=lI<{f9H!nXbQxGu?HdJ;}MB{CHgx{<1HDSmhBHFSBHnPOxQ4_V&LHuUc+#0AUJ_3_;}T^NBZ(`Pr7Sh4DdiPn zt83T#EhtW+KlYXDC-s{%vZnnezI6px_MZ4$`r?YW_oOM(W$BJoMhqc7mwJjh5=GWa z)c#6xi0dYec{A#z6s{`oN-11zj;1Yl6*`)>+|}u5I^wQcTjhwmniDllUSYP%mTOJ6 zRgSw@!B*LFvBk=1qO#K`*>6RU6+BEOjV|U}F{W#?7S`pMR<^A=&$Iq`iRxTL@<(!% zJvTu9A$cw(E+Tm}$xAp-^mLMo5HsijmAHuH8C9K^sQi`<%R?5}rS|dCm1AAZ!`i~P z)VB6i;yPuy^~L|YmY0RRy59)xUDwL%|b#g%cg}SV!mP4ka~u) z^t@($Tb<|HFzqZP{>s)${VLb`vi(_ouGTKT_0zGwYgeDu=JBk=F$G6sdkfxL>Ap5# z@ak*#(5d4c6>BI{P- zkYvqF>nCT;G-pk?a*9Z%MwG0}EOjrwegIl4TLD|eHR5g&ZAPw&154Lai~jTYX^JU&1yQb`aa#D7M=cme+Ez^VfFT=BBaT_Ly>-?XKRo=Ja0q z?BleDdPDbNvK1D6*bG0~JoZ*yFg9btQJ**+5o)_gqE>?=mqdAIy{rrGCg ztUmkFyi4Pm+U9I5+GcAURq00U9M42$QyXn%!qe`fc2#_G<6K_J_NB4AoQ27cySB7( zRdcbxfnt&Z6N*U+4=6E-_%PYc#eA(JCM@>KiD3$V{lqPZ`HaF*j)~)3bmloDYCe-RLK1`U);+g7w{Szcg$(T>V7t;EY~JHD0eOnsQV8Y}y7O*pJ& zab8W@wkG47MmEvk)VAbZvcAW6U9~N7rb&9M!4t_wY6Jqt#9;7EDah`gTt zppRAZ$0_^mI#Pu{j=$(h2~r8EK_OF04U8xwm5>@VCP^iXyyEFLQVAokG$lzT^mA`U zQl>QKN^_F_8pe`oLDCyqzkqH<*}Va@pcwTlO+f3n_K zM(%T-7{kxrcDxENY5kt$RE!s?MYG^hTpyKueQo9os<-o#<^Pt&GnH-IQ1h*rX*H2A z*EZ(l+RU-)eX@4+Yklz~m2!pq0K{*u9Wk3&&V2!5Ho0E$oqphDFGw+e;e9WzlNWZy ziR;vy$pwoI3V$^5fV{ByO$nr_#0 zEw4+Nsi1Z1Lys>dFSPlIuTMIxHRtQgYq@%Vep+OyfE-npr6^U^WS+`Jm8}x1w?`z| ze%1Qx_|-?Jh4+Dh3e>C%%Ab<@a)xf?@%&M3j^GL=`260G$`e$L3iDfY8b+wG%z zT)UG-%Z<_9mDP&9x+%J}F%gxxcUDmUoq(m7A4!m7kTH zm3Nh&^%skszuL9rU6s_0ODqrTUOequ&UyJ+qwLDVx*JYCuDq-KtlX^9m|rS4oBGE# zC3#b5o#)BsKzHA|BdY}Tlv#JQmUjZ$&SJ;3?KCotZLqakru}u>>0VOXU~7#(>nSF- zvkS?yOl)mel4qIN&Tb^nGO?ZANuFh5tBX@HJu$ZjJy=C=$vqoAw?}NZ>(_oaFGgTp zjJsb{jJ{t~?449*U)i`9=RK_N{`B|Dy}J7Tv?t5GntHN1{pYE@mHnCeFrDA$><#pQ zGr>7*pF0zr!)XtxvsEjEy1?=t(ll?=UVHmZ`ODdx=B-u;HCxWpG<(y$)e51_!P)BU zEzelak*cyK@?5sBvYezYc^l6QaQ@nAbxo<&wzu5&wQsfUb^WEbJKs~QZLjOEL!7tn zf-7cVMk_3Tytdhw#ok=|ve+G~jd4wSG)3q$;-~vC%6(XS##!5vSV?P>W8QhS{k9=y zVr9S8WK2I!+gu;TT1oRw4#%~!X7jBkG)F96raWbu<0`fd<-OO=x-zvwtj2cwza{CmGf|Y z_S@RDtrA*L_#%JFo4l zKMt)}w%^K}l$4@OH)_((4bz8f-nQDz3#`fbrU)Ht&s|mGlA4TT<$RORD|o&%-}Guz zE?hltQXBAY>xwwh%D$>x3pJs!E0gQigvJ)sRk^N^=xRb^S2w;jT?>_TwVrfh4?JACF4Brvex0st?yYKFRL(syowzvJ!lW1Ks)7G!duAjNKer0xj0<`rjZQ4%dc_n%E z3flUW+4Tv~*00R2Pk^?5rA>VTl+=~R^a-d59jWR3tSO(c>>Q|^pBqwlP}wKz6Sp{; zWiCE(?yJHrj%HbNq|Ru=)7kZbTWUJ5R)$;Fv~8=y!yB6JSI+a*wQWQ9RVA)lUE4Nv zzg4!aaxHAAHJfDaLfe}(ysP5}YWG;LIXq?m-(Oma{Xn~djEYFK3nwvP5#1AB{ zFVWnjSy@&Gus+AM(Auj<`M5mZhH7V;d#SbdTUqO~X8NABZKvZ~wur1=FICx}shtJq zyk_l8I?-go*^oRyQk5??{@$+TV;)d!Tk~&r5Fy z)W$lIye&{WyyvBRI{ide!FWoofqJ}oQo3iRYs1}?yd@`xdZwr+ingFE&pn2`Ip>9r z0gmCi8E1r!0*<1t8A(gvNJ>pOGjs%S1XoQ+p3*d&QX@_Z9S$7MwP&MyLi#YS8*ozS zCP2?nug^)LLxDrNuE)utLx4lLuFFZGgMov&uETkugMfp$E>TuG89<%`m0J3f2cYBB zk30iP8T!W4L^qDt#_^iYO53=;Hm86;y0mTxHTM zDOVThl{8HHHTD1KSE5|fFzMIi)zYs-xujvzuL)~Gzr=pkso1EGDAy<`mGrDS<&tJe zzeWJ1YErRf>6bKXSt?dD`X$XOs91kWHK$)2$18Cf8^>$o`dXep+_=70#?ODc@nPcZ z`$g_Pas2%w*PkST0Z|%A62icUUzHh@9F!rHC6p+XEtE5qHk1~XKN3c-A7v6H6Xir@ zl%Y{#*(A~gB^jxKR6*Jxl@JFh^GHLaB~lcnB595?l9mglrBP9W8vT)EH5MsLiAxzv ziEHdflGwP9WHV(l<+O28dTRre`Xz~OVwC5Sq&Mj!*-x2IIdD>x4m$vq6(>g;tK2yG zBT76qQsX3HCMumc|C_;=aJ6M&d$yu{~~$F&X2WcaTT%);`N2GbY^xI`5D=nz|+Y?b{cue zzCa$b&y$Dj+u1SMvA|=qyv;dWhVo_!`0vOE4cHw{POGy;1yi|BfpZT z|B?Tl{9Wq*mcN@{mR+9xGk-pN4)_o9zvh=_mjN&1iGSt)%%98tl|P$31AH!fHv3C{ zNp>mlQl9uX_n*oBOwC{NKj#-`mt_B;?it`S*|)O)=1*r&0l$?!4g3%J|MLIlPvK#t z1*9{5WArl5Sm=_S%2gMVezV4H_XLs*9qg&pcFj&9_vDid+vdq!b>sU^2A;yb?v%S> zQ)#rv~yw3kt0jsc$zE0{1 z?1`W7>!jYz5IXl63QAwmdhh^m_hUK8t5x&!dDe&+{KLqCd}nM*c?r^ZW22WK`S0=_OFNW=zsrA{ z?^N2cB>Zjun|$ZeP9@=Q@?Ynhl_r(;EKMxUjc`w{CYLs&Jef47G=chwzELwloGfo_y16OldT59QoL6bZHcDQ}Qv{sM1K_Sn|=?$kGVl81hlsh|+N2 zX!7>-!JJYD@;N2_>4yV{mxh%(Qa7j6iCj3RG`rN9TsXV5N2v?BaF5dNrLN?{-AlWb zx{-DTb|vplzAJFo(k`Vca^Wteoq;=-ex3Iq{R&t`-m~q2Z0~GPX<%t@-a4o>DL;~@ zCXqJF56H9?&CTYK@0s;4^#jf&pOfvG^#k@R^)1cL=48UYr9P!Sve}uiPpNll z_iT?$_*VXleD|zZ=`CRIQm@i(+3wjd@;mcm@}u)RfOqD1Q925EC;46c{&?U~i?)ZCtbnbJ7m-Q>42ddC5e^~k;fYOwUnakW z`dfiY?)Or+X?`zhY(6dDH{S=iANjO=fAVSh0p!#21Ief52a!+94z zIRcL`PTVX`L@7qv+c5N^6j$i zfm@Srn{ShE58OW6A=@tBHW%)Y?U?n;x66e)W;SqiE6Syno&=-zn=)+8MZW zwo7(D^`r8y=J!W9Dj%7DjWh!IRr0S>8V>v#`2&=O0l!ZEAf-)!50F1ZX(;eP@|*G} z^P7R+B)=(tiu^>bp9DUce&pF-VZz{m1O^Ha%%kLHi$pC=bSl0Te( zfn4}7eRmo?I0X2GSbm7B)43iDJdOMeN`ru>lb=axAn*+GvnUM!o=N^iO8tRnk)KUz zm+Wk=`sZ``($V1x+I3|}|@sg}1Zc zk-weo#?xz`0>h;2fU* zCEkd0!!M!6Gbqoc_K(>gvd@M;Wk-f1fS(OV0{=*U65p{saQm=bcqjW)c0@Rt(zd{p z$WNiP4e(_0KXdPJ;5+1}QoA+q6!Ong+6s6o`4`By0&W#%h0{nE<)?8qE1b^NMfvHZ z3-dF$5?+{Jke?aO2*L~U^YgR9nL&7deqR2?a8?kWm!F%@3ttSvbMtfZzhr;T4iA4J z9TxtY9TpA+{)PPA?629Oz(d1l!r!uYGvOiOVBlxMA>r@Y-?D?lKeE3^cu+Wy^1wGEIeAZDFJOth zN2o*IgVZxrQSK3b6zYY#;fKH<0qc|hm{MI}UGD#YnjZoikpG11D&UXFzfa8%fDOri zN?jGODs&Iuqvrd-M&v)Et~;=M=oY?9&G*93x#|Y&7P^Kv$c0@)m(ZWKzn={t7rvjp zm%YiIF5%74IdlScAs-k9g!i(6r2l2VpsrIG6#kd}HygyA|7C;2f3yDp2ayj6|H=Lh z985km{44t>@ZZ_LfJ4ZK(w7H>O~O!mbr@-X;3nk5DeVUwMm~blzQEz+Bf~ynZ{WV< zBdOarjN*DP;7Ibup;!Y^pgTcnQRm*m2Zp+oo;xv)cMAAU_PY#-W%-;fL2hBm-< zQb>-?YLAHaW5dw%#&_;;=T$en)y zTj#Cv3&TIjFXZ~4;oR^)o;sIwUbrZ<%3J0a@l>n);?Od00lbL(obVn`okKb|ToNu0 zE%Hl9&GWOv``kI3bWXT5G|!vmmvX;(-YM^x|2cFby%R3uPP6D}_q!JtJ%pnp18WT7=$tue^EallP9WS!hbRd1w~;=6&*} z;RAAE)6gVb5t`(U^DAgqll;oiIBx{Jg8Zs*WoQI!lsC+;4p#+XgS?#Y2Xv&Pi9Ytr-0ue ze}y*Q99|7Kg)aebCV!Q>o5MG=Z-ys{^TN;+|TT4The;Afh%JMIB=br3-u09NRQ~q*x7x3=vs_bgM{TlKo z!?oEpz&okGE4u@DXZ8*1o($gz*JamIzCODSctdtQ@W$*0;Fq!+fj4De0^Xe6lsy6b zMtCCJlHH7F-B-i?sBOL$z6$($_!{tm@O9vW;Q`?Nw4{_h6dnXV93BEb5*`NL!dpt& zqu~+YW8qQYQ2uIR^h&2|IshPEuD zW|w%~gsT$V&@R-!nKz+)4jj^M$Ruy(rEFd}2e?<5$FDR7qn5HJ;MP+10c)+4eaNai zhhI1sU8@>bb*$&0WmWU~#dv)|)VZo%{UVaRI@dEvXCdvYc~#STX4JHv5jCx+M@{Q# z=-`e;pSlq3>al3$jwfG0T8Iwr81$*?=#D{ucRaQ8(WoAeKJI9=sp{yCM#py|b+41= zM@`*Pz@yNhs#!e|cp~@I+Fglu^`xkMJ(*lh>uc!Ku0+e4m##pYnwJ83R$9uFSxMbq z#@$dVl`coKS}Nt_ALi=$KFq(%y*j1K(5b3Rx(waj_o%H~x)g1ynx;$9?5X*CpZX8b zqF#bl@ITzY1nr-?!1tmC={=r#AD!TD>n&F8`s=SVO;1nv zsj9tqRl~7H2cwa_496M+j6wSn9BWK4Chd!Gtg*mYv@gJ`#s*{4e&D9_4tu~WJsr+n zCrNKm}0q;fZ{vFbteYJfQkc81SW>v6n~x&6yLcM z7Ciwdu2ighd@unFq`3A|;AwbCG3zHO;wWSKS8$Q1={@7b+@B$O0T+3O_#EXKc$T_> zf8rhooSsmOe0~4aJprH4*T_F|51rVhN3eq8{p--uv%W?inS z2S+8ou?gJcG$Y>XZ-&|09_NpYVwL2<9*KE-*~ zgj>E0Ug7sT38NX4=zhSs{soH56chVbz&zgr#b}Cu{u30JDPH<6C@xbh^c_%K<}O~x z+n~72-Dn)QK=EhNOKyVV&-R)<<_35Z=4_wY%YAAe?dwiz%r#K=t+@Q9uW~Po3yOzr z>b1gc>b16Q3J<#%+zl7rl;5K!yykwl&$TDt6sGfcx8JoR(;h}soO2|Zc5s;oh$6fg z>2NQOI-EEHmh=!&TQ43vIjnUG7{(OTDJj+9!K(+1cr)r$w5tXTWHs1E@#W$ktHL&l zQx^kS1-7xWuM{wll>_dvl6Y2exG>}8#JmQ)t2o_q>@F({?^*#Sy)?aCVZ{EHhnFn_ z?^+Rdy%fD%!Qa+`rTI%&;HuK_u9bX6u%fP`$HK0r< zcCj~c9~WuFinoJhE#%vqc3^}NXC6U55>`}PdN`Q~(*Z`dkgwp%!vt5LG+}NnelIhn z8Q7Gb%tTG$>?+V(G2os%8Zn|B`RPKwBc-=%Yl^|ux8;$;1AebDT%I`WN-))pTpJ@T zp$*rxHJyyO)=s7)wHUvK@Tp>GJJZt>_7(jB_OGF90P9zox{K*-dbn1m1bRd(dRv>8 zrX&hQOERtCSW6PMFw!%cgDqfM3!-i`gLf?m79`u$9CKM=T%~n2CEtvU7}_Reni?^3 z_2HB1yL#|+^#is}O!`Lt{{{i;R1XwCzJZK*J@JuZrs{%qVG!4o5%(u05Mx|8p~-)1d8D|S-cX90NCE~WszVZ>c{-SWezb~X9Q7l3Ik$5m@6YvCii z!^GyJH$Qx257^hdWb(nN^@M%RLnbebS})kw++^~=sMUgf%|#|Rj9P8j*PLW>!KlHm znjB0D$_~p~2iCM6>}xjS>~N{|h{UqiGg-i_E(^?Ree*f5L?u&*XSD_nwE=wv z;aVG*g3Li1nr$$xYhVToQ||(|!D|*K+8OZ1zkxg9JBw2P7Vy=-g1^Cx7K0J}CE&Mr z1Wfo2;$L7V#fXcg{KgFonD2pP2Ej`XCNqSx0xt4v_Z29{U5w?5fS>#d{K_qdksJn! zrCJ6qb4y|NhLfpIET(F?Tjs=PEd|A=SEE!tz!nBYsf4W>qULvyK(p zTgQqK7HhTyMsXB<73}A{J{4flK8J4{6|jwBI-}rGSAnbeO)A;Z^i{HBU_ECBT)MFF?pWe+ zu*wzST>GO?RD?I|54MC~?eAK`y3PjsySng^bKM-*f=o;J%eh3&t$5>RU~?GIc|=XE z*ybjnxKFXuL#=pdagXI}E4W-?IarF_5L~ zYa>=&TvZ8JDzWJ=%}9D*(iUGOR`QK0Zi|7hssADK685W@EehlHhWZ5=F@s_*-hDZZTLgSd{hYk`#4&K0kGUgMgoPC2{uq9(Fs$R4fO8bP*&2?xJXoIJ>_nCj@17&eC$ z$DG}YMb1u~16ENyw3x=fS)D#28`r*vwUkWB@T z`~iM78$H)4H{dHRxs;StFqMv03fN-@TC&NBQ@~V;RZd1p4reLeI4RmdAFv;FQljW! zG_FWOCMi5zf9k}PB(QD+XeC0E7y$Msn~*pWtlJ>!1eAm@Ze3}`rzC(0&c-u)NPQi) zF)h*CfFFJXil-Ex{2COmDW3TiDArRf^s9iQehG^E459u9dVv0Z0j05dr8fZ{U6g`I&3I|D1VAYe2XkY5;ZYNx@|FiG>ti%$%3 z8R130ATyhC63$WV<~;KA;kq92O#h|4gO>~q*vU*T6t+@~aU9s!f8iw`6UBC7nCHNQ zipNalGQn0p2{=n}&avQ@pTbr?BZ>*P{LIDxW5QfMCyMUGGe-l(%!TqgdQd!ECTS0# zhk=tCVL=BcC&j{m7H%w1Gf*zXmIVq1D845Rbv*d(IdF&KewWai17jzacnz5)Fq8?1 zR>LMIaI3)8aGVK=RtC)TN?7Sc?i+9=d}m^!6>!#x-F`d6ilY<{EoM?E4*LMnbhyBo z^sR+wo@vETP763mp*Ziu)Iu@kOUz{WaB*$INp>Pk++p%xkQW;#mR(HQL~tVP_viGA zs}q;G4DM_KEZ&iT!xM}7sW}?3dg3w{8*!P7%`vizjJV82WER8Oi5dQu=e8F7lKKZS z-@+1}2spxhaGc-66)y$F8-Gvq1MK2HuGj`Yyc{NPIoYiNW4x8jHh8|TX>Z}R`5OG1 z_7+~H6)=KQ0X7qFfg?=jlDbV~Hd|w6^ByzYeICQ@iN7>xH8;U!{6;3=0}a{bWKMEF zGF(@Y_&csOaLeC;;+TyQmu$>AMY=Koa@RIxZ{WpVO!O!l4&HkDm1H<|?xE(Hi6DW3f zyA`{;-HP4aZpH3yw_}IjM#DqOa3dk zg8#*to$%_;?1GJVW;e{dGkf6bo!JX}?_g~Ag5Ly;@K083^GaIci&uglS?IWK9XDaa zEBTROZ44XMgnzK4WE#V;HX*tSzum};g;TwXFV7Lp0%tK^I+)e2U{~&;&cx@lLCMKTnumN|MibANEX_wFET^cN@n%z0n(e@p9sX{wT`hSR_i zRR*gt_jjf;{sd<#F{4J|V3z1uH4I>$Ss3h3-H#cmP&3nhMEx1H3p0Drm|mC}Kryl! z%?p8=aSRS-D1(E!i5vy(xW|Rp;k#B>g`>^E7Fvy_koj1XFND zPh!pIG;iqv_T+P@IsDJe^;__1{F!(MB@=VO)LhY>cYbOL+0Ve8wP-}BJkFHoo{C0=0)$@0Xs8v4Mnj=iCP|&vD!S(n zXY?EyjGbD4By+=9>FEAHjImYgjD$|>iG*$x*CpWIGKNuj4DIAjDpnhZ{sUI=>j|AKB^OiB)n}=ki2WwsMFjy%(WYy4tSZj)htS>q- zGw4k8Ay|nl;{LstS=3%$jm4C%;38TJ$!jJht#n~9)@$a~)qYCp!py1*Kd(7g7v@&K zbH(Sud_!}t56q`DCzwxJz?|wm^CRh)@0nG7L(e?QeC8w4w54qR%dATJ>Rie^=1rP= z%%RL>be0}2#r7Seu;!&2yWcXxNpYRcJZ3eximPW4&t|mNd{txj8)hDB$j)SxUju$i zthm6(M2cyJeS!GdzXvrbDIlJv!M&*FQQLGF*o{yjI;`^iO+*lHRS#| z2TBFeEaogIZAEjLGoUmV&HGM+Qe-qkJO#=_u9@RWP>PM_i6_95=meTqR^vCfaJI#$ zx4GRsr{Zu`xnOL!x#FNaZk0iCe?P#*R075K{Rksd5v;^4VLL2L1+XHlyV#fVUYHT&>$Z$sJ+mA> zsxBxtZV)PHZBV?O)K6h8IP3xR*8ywOKfs9P8o<@H13k1RC=R>75i8c8-T|nvUla8+ z0YgTA4U|Oj);Y@!Gm{&O{*TNir3yM)(1Fi*kQHL9GXyH7EUa;mf;4|8i z3CA-m_g@>ZEgoQIaNulabFGZHt5(Efspk;2Gy#JJilr8JRoq9wT$hBwj(`u32$=Ck z_?}CVi$Il$fPXCwgB^i>BVM))YEBO{o-)3>xn{-hUbEtKuUj$Z*RA;R>&)c4m>X8C z`VH3Ioy=7$e)pJirm#n{*N^IQv1OkQ0w_539(W$cnIiZXVI$GL3lcyW7mxTY@3 zc_B`CRoxPZ&PV9^L6U>cba>3@N{9!wg>FDp-_9&0{Xtf9b zq&`poA2yO!JO7uB@Zn%2`lC3iNPo`e;Ze@nyy#=+xbl3!RE7KdwhfxtecKit?7j_0 z4?An6tev&_QP|Gf0zN;Om!CO9EI(jDv^X(XtwHH*4~Sa%)8xf*6hceMhB7<^RV`b9 zL;PTLw(J28_JdH>n$Ux$LX;)g8Yt=ptobKn-f5a}JK4PbmndYZ@xsj%TQ~g4}fc!$r zVH=%i8^cHU;`O5YgK&8%!070_@`vQ>TsetY98wZ`lKKfKcZI-0WE1<($R(yE@#9hP3WJ5| z8;`PF1aHFU^e3Vu_T$Km$D!~!?Y~hGL(%;+5j}7z(GTSl2n9pYY44MH5UBSly?g~B zUe8-Bs2+38lRAo8cfaKH>Qz4A|}1DOd^xe^z(@*eSHig$3zTz zW13ekCeQwri{<63kk{aqi^DFrS57X2S1um@g6KwGjOhFn-(`Wv;FXKU9=CYjgL3I4 zp!U2@34Ap3mwV}=aeZ`LKVR_5IZ8q>Ay-&Gl$@pTktSvW?T1l+aKnh+yWzCn6Mta8 z-UvV3|4Zh*d*?>_5&j(+IeJFQT`2?x9&CZ8*q#t?KASb_Vt%>PDC^J zT$CTXGhU*X3Z}PaXFOx_2Eibx}Q~a@QxX9Yyu1rG#c<$5Dd-vze@> zk&|1e5z1^;mOECw1@sIcrW&m-)}ORP%ty~Zu0VQNE6=8{-wt5 zcX~qc;)I$IbAVbHVlv|SXu=gci2C{+qcW9bGcKOC7nU1!`$>+)N$FbY%Z(^I%_VZ4~$RE(Knv_Vji@T~CSo zsU4a2sPn0CMMaWn=OTFJQke)ck;FG?h2uxLi67u5?Y8(-Zh`Wvv?U5>m(d-f)}Y)3 z^0c&aa=Emkv}T9YpF}O4JTT=@hkt>?DhIANeg}VdoQynpx%jCwS70P#-0K49tV#EEn7+bHwCDi9SN+C@#IcM2FF)^SZ+(Kgu&6c3rqsNRRT@~|mGrmQhn9w4IMCq> z6Bj|Zu0^X5r7((TEus`IGtcI{5i@$;q#(X!xq&NAdd4*}^2$lixJu@l8RQu+--I>44^#_MSC!r zA(V$k`nFI?+A!2^p)@oxXI?R0zN*7;B`%fb_ z{T|NO;ZFY75$N8_$o&cPENyME8RU+8EK8DOhBIwp*4;&9=db~cOk>?aL0&8 zzY9*sS7>OT182}Ocs^%<@_xd>QyUzlv%zTr2S1;mGdxNk9_JkIa6{Pv102f#GnO*W z$#H5-l*>deiZa&Clj9VBteE*J{JsnD(DrvzaMkvAlks#;B|n_nm`*Ori~+}*C~%w^ z3y#NW+sRG9i`&Uf#Esj@O~RYo$@Qm}w`2@B#*8-B$YWwnSJwsX=DLF2T{mzzk8JUf zbSLiVdVq57*ueW^O&`~rSi2Ri>F4@_Blrn)eFSPX9}k>&G>j_}!p2 z%ve9xJ2Q@1iZfHKr5!~)m6bME`g?AiKfwyjG6uFJ-o<*%;-soYyat8Ynp*M@FrTlE zr>!8bnRxC#elF_=)D6l!d;@c-7Xc!!@T@klI^7CxWwpDOE0%!Y zQm-*uy|3Y(y@b2+8rJZuDNFeT4rPr#gtDB^&}!E3!-$9K^F%$Ep5@?jR^P+v9R{xA z{yqqIiU9|cA4K_@Pt__ub0fHSt>kmH5@li_J^I@j*3g!+8eAQ`hHF^cTC|YvsupynlXws^)IZmH-Vd2f&aqVdkeUQ z75ixJz+dy}{hCMlm7n^B@z>&R`jxVd(b&@N&o!eNw=E<0E^sF^0ZX(8+|8`P672)` zGAGbE8^4458T&2K4)6eXf&o0wjojt?yG>+v@P6J%+=(%6Bk!}HX?JFH`crK+DC(+2P|4eR|G54cbGfcbVjfv)F+tFzMbG{L3F&PUqpeI&ZaJhO@W3%tjO)sQ*oU(7!nyZgj{q3xV! zOnFBw{DYC@E#)Hkj`}^l|Dx@1+5`BO`ZdvI@D24VqATEQ>XeMb*T8Fx(>mAWDl_dX z0luP6O{BB)Q_`D;pU{aYFR7E$z5(7~)Ylm&jPa;SFTs~wq4Q2|GOK?np68tbRqPq~jQ$Li^dS#EH@8?lTKWN+t<$1LpooZ9`tiWVSvl zgJfiqqRG``t&p5dGPIw%tR7O3Nsbm&2bW|@GAU4jYO~%*MJ6RWVl8IA@yN*8@|0&2 z&3pi(gF0^|F4-8MPF;zE0vQw3sVlKjCOKt=b}ZD&*p_cGM7?AkNj46OWlS4~Ol;Pu zF^Gz?nh1rf4IwJVDk20HyC|6=luR(UiOChGaDD{2OrTDPDMSea3sV;)$^sUmEOnmb3SYH<4r()5Q1JoH03CP4}#i=tG zVzO$@X%Z4AV4bNG8WMV)(2$5YA!~P?;*c0j#F{=g{^Dw^5EFxmdEV7o7bgM}(N02d zVqb%GbV5^uQk~UqZnDw5PLHU`8ax4*fWBI+%HxCaY1ig;iU-D{U58jZ=VREocsFBM z?Vpd1->M#{o%7Lf3DpO+bKc_?Y5;2Iyu(-2&{#C!hQtj_RpN#qmF*5kkk0q;-2+Sq zo6(aJ1METFjb8C=X{g1s#Q<}%g6l;TlQ<@=t}p^=d{>H?w_g4e(*^z~H9T8tvYi8` zeP?|3sfbgN?L?+Cn4G#JD7Gybb#z{bXq;4%jCOml158^oq7pd0ql3|5HcG%+d;)#~ z`%wZXdk7c;b5aH7S{Mp*qEi%vnc$)-o6PW3IyoWCCvxJi5;^f#iJUmJ#7-PqV&X(7 zd1B;};8AY_ijhm=B4G29kWb7$Oz~q0op`W>xMG_7r1U01)l0^+OzOn=C3WrCiICK# z=UFFkO<~#+@N-Q;@p8$?Cq<=8;D-44PK+EHAMD%{n+qQ1iRGtIkm9>RKAscv7LRD4 ze`<5U&^@&|VcMQ@Yu1y-(rNvcl}mqGX3<%MPnIoAM0qZ5AytZ_nV^ zveKFfyO%X!-k#aHWS_&dWg$C*S11e&qa_yZIjmbHBNk3O%cp_U{WM zro5Tz%cG7=B|i-gZa(=1loxPu3;YW>wsQ1M3HCvVd3yo7rW5)nlbPcGfsK1%#k~Ck zm!`96Ceb??{!Ay)Oe8ZY;N1SPV$=Sy6Ua}5MbmjS<3aIhRna3}TJdQwx#}M)KIo+# zM}EA2Me8MMl^CH{RxHqKEB@!T74!3&%q!d6#6pj2W@4k!>HLq_PA7lFaV^LbE@F8(Z2t=Ur)fOTh#e;(skjY0G&!1#$EjpoDXZP5~bd3+}isAN+E- z$x9v1c`SLs+%VMPrnY~NhFjZzu*TK)+$=!L^>xVC=8U6%QF7}N*FhKfm#98i&o}Vz zP;wg(*GF-9i(=c5jCMi2C29nZ_SQCnI~(OAcy0Rn#>8k9aA%|0w={;RELaN^pN4~- zXVS}*fjRGGYND(3HZ|DO)SI{$T2*y4gFa+>qhwWsL+wkZ51LmsqJE|-yLbAVDyS0u ziTk0NRrXc<05bhqW3@v`nF#9KxkzfAIoBR+kJ>T`%^(ttq;DMUj^KFeu|%D~an!8d zP;;WRelw3I9^ZXh_2_7}W{17H>^`O1C?@fYw27158rB(nqtp#qB1QZiq%hA!_b_+@04 zn&qaPFYlL=S!NaxF9*w_VJ%?&Sk`NO{1;s5Wbg`j8Jy4h`6_q?u2jyrYfdNXU1Q}v z51dEebu!mLow0WVybimk6ZLKq-#{DO2}}DM!ajU}y-DxhQ>UTd`ZN^hQ}a>tU>fQS{N#JMi5=7# zh|>&CCU2_Lq(MwqSR9yZNOii5;{rG1%i=Vk7gg7I(ojMc@0e_@U4u*n1P=605 zciX6wyAwSBUEn?Hli&&PPwG=JmVbhO(mqXm3cN#o2A=aac$?N4%4xLqTSVu0&2E9S zc-77koptAl&w)CL@DHaG2mc^G&wfIkig&^3ticQ9|8N({aNe5JNnn?VFS_IK9aC`^ zOr`y`%?3lc0{j}yKdZ~;zOh+cRxm5suWWWW%dc<-WXDO6!{r3OqF%{0-{9m3b6MOf z;+1$ca=Kh@89sxYcmguJFffe1r8bw#yd2kHmae2YKE+3fB4G5G?2lfrVUQa2r2yjJmLEh5O}myh@)^x2Ckhm-8u6OR`^pt*BcNEdg6nx5ZKO zDflVZh1*56aO=}l%@EV7ShiNKwQy`+)`Xh3&?TC581NBWx)B=oZCaq z={~f7w?$l0cL4ky&&@HO;Q?D1&Xe%O%IaLRm3X06>x|15BposBo=cXt3E z=K=bDBR3nI&HuUH?#FSnp5Ar1v-aV{*+6DJeyzQ@bvBaOfP-rfj-5?pHrma^oAAap z!YfxCCt*XdA*~X`#qr-2BQ8p5j1RA9fQ@kimc)rzAFR(+B`GEFmenIljcc$TSdVrZ ze1vtuy0p{cFRTsLCYP3y2De!)q6awQego(5dOaYTgG%`exxXo#$$>Yq7Fdg`?{h^( zup$n^`}9@7xAhCx{Y9%1KCd0L9#I}zZ}J5$zx=oYy(xej(3@twPrNCJThNv@D6MFAY^xY*}6|9O&@-A0ZvAMa*n>)0sp#yK{ zx?}c7>Rj}AbDa1Xs_zffw^8V;fz{Zzm6LvtL;DB%7V0yU)9e}8OzSM=434~8JlbeV1~3CI#4%(> zgEw$SjG^4ZyEmHrC`v|rOgG4mq?HjL({);7DN*>Ct`m*J?{OW6U`87Pj-(z=6bg=@ zj=<}24ZOy6k;D<;W%flxQm*1647HiSOg1w(oYqk4%y{}Pb47cw9e9a)2tAp>%r*=R zvsv)^U81i8yDcu^_#8r}BXI}t0`(wrS->ndE0`6BZYS~`!9S=6lFNqQG&`^409uN( z(dtZZC-6MAGn;w6oHo#}!rP|oOXU^o1n&UD8q>P!#Zq|WrjU+PRRyr$0d z#*gaES@v)^(+8ibGv|0zXZqr9b*3M#S7-Y3zdHVZ4|_P)yMT9g%osM4p0@$`0%VTwkp?5VH~n19KWY@*jdUl{{Ydww#=$+Qad2O% zPxj+Is05!~-JkRc*5_DvDt)q>a3?Am+?#Z_(x<#>aEB@dmJ04xse}7en&7UayVb`# z)W^G(?ojD?m+1YW_e$2_ev}SO#~ncLkgTBIIeKsD9j15P(BS>2_hMM^PSyKW?_S+6 z(u2Bp3=iJZ|NRu`9j;HpaQ>>cjpgBBIAiw$ipFw{-x|?N z2P3z}?*(K&j^#IldywuxQUAF^>8^B>k+vLTuEz3m!5u1!dtwc)_;}CM{jo-HSBe6o zxFdbMpZ>r1lh+^;nj=&pVDKX<6B+^s&|xyA(}#h=05>c4j` z-J9A4BS&RWW66Ia zCO3&W=$CFX9@IHpxdiP>GtXI0GtXI0GtXI0GtXJU%oB$q^O{*GPgAUPu35nh;O}5g zpqatPnSy3GALlwBXF(t53YrIKHt_I&^MH@@q+NO>W>hm!%ytv+3P$lq;3LLsjn+bq z+Vaeiz?n%690U%8W0NL07#sxCCLM4HI2bl= zF=}92zfgN*!M5;x3veg4f%RJiE<$OH@bmF5MvxDO7hKFwwuTv83}ZM1HYw82!|NEy zH4!j~Lt&O$(LWR}Pzq-|dL!W%Taj-`8Sa~sZwK$#lDGwB1YAg8KL&Tv7?ht;J_-$M zl$W+O%1hfC<)vYb^3ttFdFfW8y!5H&{PYOloH7y@+$cZUP4x%xwoN5E0Oxkl9s;LQ zH{+_2u$3bj%O=Ca9fE(;e0`E%ZP$Q@nW;~r=P-V@Nq!Bu#;%2Do9KnwA2;5A%ba^W ztlPJ+YU`M1kArnvXUF>W%(KU$2CrwF-M~CMicxuk9pg7L&mO~=ywQ$^$JqpK;_p|J z-@PgPjr893jK9<2bTtmQ=h^jvFP;wb*o)S5_~jX}kv(b6fPJ0`W7&h&Oc>}{u$bLx z&4Oc=r?4BX*|5uVU@N=Qn&V@c#xSliO%oU)DGyC>vNa|f+lXnBE>YdbF=C_QkdgY( zkSH!b*M@lH>iY&@1AKAuiQ}O()br9C>cVpsBBSpuFHEiwrM@ppUMfW$7_nlYl#AMM zWco&@1c4F}KTskPfC*swi_@#quxr9`6*skT$4Xa7h=w3_0Pde`KBB}Rx&m_&aa>8! zRjQ*g=p=oq4vCqu)bJgcyCkK~K&u1T0k%9(pvp*xNP?P_!F2TLDV@ADC}Ah~_H?*h zyLg>N)y3<30EAt5?b5*C&-JOzT$o*HUvqsbGY>Xb-w80!r-boc0H&f&VHUvSra&oM z;FFt$aJSOM7W!mn5$v!Ou|=@)+S6776(l+=d^8gRmY}Xo6bgo#OkfpSm8dhpC|3$l znob2;!p!J66)0KYm@5P*?WP>9tcFu|0+hbfA9sB}^yaEW(n@vywa&rrL#wLkLn(<0 zuWWB}CGp!-r7e}Tr0Gdr5~od7vO_^B{nACGm6kM8n@ghSH^6^0%t=9!7F{w>r%MKU zbxE{qanYUeWRyhH7Hi!JWxJH==sLO5a_ynbNMjS$MVlc;m8nm@9x7aIRGd1fZuP-o z_y+1wMu7G8ztSt!t|p3416K>hr#5{fU2XbDpzPIDmexpcByNCOl+kFdtxo&8CLQ4d#LesfH#cUZx=oNHwzJYZ`)5 zW~&FvadjRk9A;#WtLgJ{jhK?$=reg~=LU13bBP0L1ozVjB{v^eibwHy?ZpQ*hU3W^ zU}KbDF+NRPH5cI`!ARE*tWK*byiFJwMsFtKrfA4w$C^+5voE{~r2oWbM!K-iv6TDM8w47ottxpawlomxTIo@0`MV!0j zK0zT%!P-GuS_;SMOJqa5*re3KIs?}<9AWB!SxgPrn3gz=dc1h2R9qQ?qA4aSE}2w5 zCJunIXcT489b%)umjTPrmJU%CO`{aKIF#7v3}tZ|NJS`%j!}wiG}`6C=+yDZNL3Oi zBh{h2i|y07R$y9w@7Sn#X~9--K@gtwI!XnUs*?OnEFaq!2gL{_AQK-H=VQ650$2gR zL`?M45}>X~NS(kLdMdgYsD}yB(qe$p8!Cd8Tv_wMmgUp^!ODXnH6j~(Y^C8w_lZ#H zqN6+}a{pSXw^Adrn`r2BNnAAa!^G~Lm3k{RB8TyTKIhR_lQ?M-Iq?jm*YQhuY73K_ zEMU@8_z@-r`s653EPHZv$>C;%NeRZm*~_<~pcs!PFP>gXd#nHgfh+)_R=4u`;0TC z=q<^flX%q9ea4$YlnEvunNp}Y`FT&|W>tT$!55D4Yw{ne6kTAKG}%< zo@~T;Pd4JN3wWIgDV=B{jJvpQvGDI<+r@WVOLwbhrGc=BhUOIT!L=Yfm-+_ zx>0*-;Zk%XDRaVQ=thy$LMcYu+#1&iY{Wjh-L4_Jpjh{YW*0lYdV{;Ece>u_f;-(V z>fhM6))(AK{j2MXA}9^0uldFGW2c;SpMFNVPk(b7Ui%no$uSrtX(q?eM#OcWq3Be| zQ{>OWTpt0C1iFcM>~j<;CgQ8lQ_iug@gPyGfSryVaM7`eW8rfVj~x^5%K;ZB;HBfx z8ymmIL4GC%{Rds#fTNB}ZydZEf1tQTr~eOFt5xvT@#u|7nS0biDN|CIgwn14r0hUh+QF+Q&1na!Qh#(psZIUOZ8re5P-@cvbIT1x zQI!5P5S2;VqBN&LXmnB@Z=gU8M!Oq=MtPk*4?_Y?uctZAvpC`6!`~fusW`hpc-%d7 zDXlcslvXNhN<2yrT?$-Fk3ngx$#FA1!PE4F9V^LjIX%Ja^pqVdNjZ_=DbBuk_{5G< z-h=P)>m4H_*ZOB`O@1Zi zEVzpLJkRebc$iww(X-%L*h=}yo`O&DiQS|m1aDEVpzjdQ&~K=3;6h7iZ%`81>w#nJ zIyuFOIpN_NZnh*=t~g;*`^;S>N^0ebdxkUn8T)$VpA$YuZc3iA&KC9mFmABlsh3 z(u0(rz@PA)9;EC5ci^2pNck1~m7l$X8}bM62ilhS4tSgY+Y;RcId2M-XA#dcZbeJE z56X9EDSv}<RSwoBKUO?+DJKsj*rjDfb)+WPsgX^2tTbt1&3z#ACnNFS>@b3r<~7Zj zF&5XwW(E_RIwmC+^Mp9mF@kpVAksc8%S?(hN|+tRqmCc6QwLEhFg5cfPo0+9@}AMz zx;h&~sJ&U7L*;dPNMdF^F>N-+w3s#xV_Hm`fLUxzK8p!_VtRGjh|cRxB;?(xb9@tm zI!`1SbEv&8xz~>S6wI@<+g_+sOZF2bBTmNEd+62v`;^SowDUdz_gkHHvYXd8mETQ% z592~A=5*SNAD{cLPDR;8?{4S#4VY{i?TvFrd*htZPB>?@b56VV<8fcsi7Gp}eiwIm z-K7sv;@CGPrp@Z#m=K>44D}&kCT0Y0OlF@6)Q-qECJUqVo8bIP?bDBg?x_>hbPh>I z|CaxSzcA4!{vEYrq&m!)@EawT)fpz7D8s$V@o9Pw>O>UXnhoy=Zrz~g{>}L^-0wMW zh7o}CVHg=4ccB>I5uP(12wILA#BYp3-%*l-$zjj6b6Xe!Z@!KBgfJuAxpu@0KY>Zt zj(A}PSo=7c z)Q+(0+~qIhl|LT%>Bs|2FEOF%oQgxg(Od(NaqfjQ3|JB|H=`?^pktY|llFcst6 z1)@||J8M!}?WPgx9G9bvJC2d;l2M$(zUE$Zk-N8M3-`G{-)AiPhZzO6BLcZ+a~J)G z(dHF*?|;l|_kuh3Ywou%%p3Qd`?q#EJ~wZjPVRZjs^J;)t^3RddV;-}mHowRpq;tL zn81!}TJkE%r*xkyx)Wjq4s-4QVX@;t1-3k0W*}|JeT&YEQh-*)1DN5h z*%I7RN?f{h6icBo;on#%U+qp$B1nuZ;5BE3*cH-l{u`W*gy0mL- zw25?;{337>*HytkIMP&svm6CGu#n%kDlWniU=?cZnj8UYmzZ`<4ma8_Ih@@bH9+l@ z91i19E5O?DjJx0sCNiU&OuY-WeKI(edKYW=so+E&pWQJ;M_AcUV;-x0c!yd2&j6>B zJw$xiOo8jHkG9bOy=XFAV*^mTmnVUfLG4AJ1QXa8g=q>`P7Tg_o=Q|NI1#rlSO-3I zT5#6$M6R5KYNEZ!)5+BaYr6?%0vVlt+l+bwj9)W$9Zg^+)s=qs;E|bt?xOEW)DF7^ zFun_5J;sq4k1ErWdK{csOBgNf11t|#fCtkKz;bRrJV-g>@^Dxc+#FMpGMl|T+ND>P z-g00!>Pk-g4l8lhY*X1CVy3Bm!LvZ^O010M?hw0s^qq>K>=Zg+Lg63}veTyrxzZHv zi`6$JW}^Rq$wc|xWTqw5KJAjQ*D%+VQZCG8cKb~jWuGYl+uajh4sIL9HO%cZStxr= zaq=bLW3#xuCM#u+DMqF^40$h@&TLLQ!L=iKk10y77`$#ax0}7lyIErtAyX87IJ^4> z&RDy3wcoG^OnVXdPVG7r7J|9#OH>GczAte?C1AIrY`u`Vjui9gnjATR%PYyJ*ne3Tm#?8lFC!@YKJ4<|nYt*tFQ_b?w0>phJ8 za5;)$!$Iny>zoy7p;ACUM++V7b*lAXzXZK>u-CaogS}2E8tj+3rQmY6 z%*{hLT@32Hmib;MxM&B!B8L*B{{@|Bp_1@V6LlP;{Rui*;|o+q?OMLf<{_>-U* z=62E01ar9tKA8zY-)u|W&^PcQUBkbYp`6@>Hg{qLRiqfZjL6yl=LGSBL zRLMvI<_ts>{fbt*C@SLp=9@L`>!B@DBf@l<4`=QK{LtavT55uL)Uih!g9Y)_RmU$^5ahAZ zCJWu{n&Zdj|0|d@D!5Bjl#yRXGYCr9F%O zL*OBN6SJv>2XUlK;hL%7aq21juE+6?%_iTIf}4fRl;Et)-@)H;y!56P?#C6=hq4#! zP5l}#UXkE5LSYfSw{Ixyd!c_Xu1B3g`3g5*QLrdizoows%#9fCm-zjPp??&k?;Sl2 z(Xtwv252J1$^L`;uXu2FVgs}K@au1%L3-r`SNh!%yFDU=mi{$E?i!vD03 z(*t+Wch%~=x~ufpHafqo7N}F}uHz~b>U6pr_{)Sf@C4k%sg}odwO#O7b;V6K7Szdq z-KfXf&ct273Dljy&frAq?(~lZqwv6WCyK&d+MT!twQvl6xSG_$(RLKx>6!tK#9>&A zXe16teSc|s*N^9(9={X2?NF>9+YBhZ!pFFy>Ttzyur_r%*Pqukog087H61^tT^$+R zBb$~?I`raCh%-_iLhYU4oncI*jR4!(NN^(0+nDw^-i+yh*UgxYwgad$IE~RMhQ{dp zLSu6Bo=W2e;&@Htbh>LA9zU%Mar)NA5dNQscs7UQrL4>I8g9e+i3ppTE7PEh{*6EE zJy-pW!_b&;bkg@^K2Yx4R8D8YrgA#x_MzoUq z3)GoqDY!$A&L~ZR&OHpzXG?lp;dL~oC1R>`e}Z>$6ndh& zHX2&-9UC1zS$GFuVhk7E32)<4)EStrrnaO71q>WbCZmOq2}VM7HlK$Emaq7i|Nu0qr?> z&Jw#hltgYWEnz}*>A6G+-M6^@8{&LwO#LmOmdCxXiY z$0`0s;#jx=y!i^Zqc^c}2Y7=!k{Gun_zkW}&XsmIK|{-%#WuEsb~F(#!dVmPBEd?i zqSh2c%Z33*_p$J3m%t-j8R5dga90KwYq%?mZ#CS7Gn)!`6PQH8 zE00nMW(}20F;I8xDn@tFDqLBaIfd@?6--6ys>~Kjfu-mxPfrnM6-D?vR^xXs4VI>_ z96ik$ugdaDRX62$rK;0gjj>(thfLH$y+gvdwmB%bQy5WZM*2*qsSTwxv02E6nGkYK zYzU>X&B|=04D$$iRpgP%Vlo=Nhcj|jW1EdROlf9trRnB)`Ock3?8OkpLg34@CfY&!F#U(nflC~kJIA3Te5PzMTZU2>ZL%i zo+-fWKLdP_Rwem^l}vv4qja!G$+;q5uoB4^tW)rAP#5PhVu11~7N^7lJ``?YDVgI@Q;xu0;ac!*Z05` z^X)-7B8qx_51iaY;q>d<*}_e6P~IWAJB0EMwKj4G$qiD{%NbJ2N3(KmM7QN&zNHhD z^D%6B*zOppMdcCl%5sIba(u+J72vsJ;yb9|9T|_pBwjw2t;8!9%gPfI%jV`iAWuU@ zZ*3`fddoEqT`LyvpV*Z8V14eR#rH(X=w2iR`|%GL57l%~}}e7Tr&usQWR@L#YQ z^;=M?nA|m-yifFoJAYGndhy;JSV^_?9au@V0$Z^P>%fYusP9N#t`d2pUo%EDK^JMl zPj+IR+T3>{-_dj?mLsJpYt}BHJSt6C#dZbdUCHR1_->$_EuZi==?-=?JwW+kk!rq`fDDwQhb7J`a1?8-g3h*A3zv`os^3FX*4-oVJfs9;MAJrBy|8Lww zRC&3x9-%o%kum-`*U7b&*mANYDyj8SZLF7$WBn_X9m|!*Ye#b;`-+m#N;elu34KYF zz)GW!4@&)X{1j6&ULmwW-%#VJZ_F#@iJgxIdLJE(=3{_z*=aqJ%?>qcjMjvW zOjbL@3`r56}RmA04MCen9THOYHBXz{%4g zzs*CJi${s!bMbhMOfD;5V3?I>B#cMSVh?lOx1%ou0x%A25Y#UdILK0K~SEQ4Mb1C zrvbaTj%&W9JcltnKvq7i=b(HRn^3C{fCuPXL;D{v9!m5YqIlq1a+}e__k-H=x|y;G zrg4pnYgbd^*e&#KMrBRxkAqVEPq;W}`zM^dfhU~&gE(x^>rXg&4^KF`6i>KBDDvN- zy6;0F-iIgcq|{_7oLu`tA}ABViChs$CIVfe71y++tOQrWJGX;F9}kY_3OSosfvb3}P?5;ChgBa7 zYR8FAP1jx^al#$Qw}+wLMQbKy2CVchqFMOqcDasl?onVA*UcuQ^ZMkjn@!mXL;Wk! zTu?hb(mP=3t*bB(ON`V2xEPf z)?&&ccx#;t@hN37`oR^Ve*BfMpxCtF_ZrP}llOi!*ctYIwA3%!XkA2IoE-FBD5G3g z;x4Wm*cBX3-5r#}UrziUp#1-G{^vtisvG#%>!MNAp`9Pys}7uNUh;V;_269d1SnU3 zE?Ppl_u*X8u;j3B82FwWfpWylAuW{uJrV1ioM0o?o{5MWg7VtOqrVB*1g$DD*Cb+% zn}a9``b%~&J1sf3n}YJj$E7r9HA!Km7&nOJIZ4X(NmxV6bDxZo4a~;Mx&XgLeo!i2 za(a`Y%G9P^5RIlbT8;Kg6rxDKk!q8IYm$Ru)P>Q8dV_qMElN)>qM}Z_DT-2xpb=>Y zMKOxJ@4aQU^O6(txQsmqWW0(t>F~?I=hGrUkWIAU&84)DD5G za3&w%s@_pwqln4+V2#r*><{o(@5o-JZJl;!8+XZCcnKJC4W;eMjTbib0-N9}pM`@7aiQ=pq4ez~qy2x{dv}}sEij`Cfwj>Ni95u%VRSOUd)*~-2OcOrd>DH} zc^%m&%4_*2y?pN?u}%Zf-U-eSfHC^Z%Eix4P}-blfbz*+PudS`d6d$>!3Qu|=TJ2QW$1~Ah!&B7zVL?xUr)d8UTlxl+FYb5Bewf+UL z=nx#}OZeb_h^E8i=v!Xa!2->IozeHcd`nxqGS|Zhuc58)e%S!(n_#98Z3L%MPbS&~ zPND7r`?SS&r+f$YpzcZEW^gmDo?NxbcB5}A*qyo;8SO!yMBO#m@z|A~tuV!t$o7T} zoCNEsvkJP1el-m*aCZ^)^txPwgf79+dl2yH0+Od zN6HU4EXI(XYDU{Jc02hWaafGD+Bcz7DyDci&&6;%f_Mac_)Ov%I1aw% z^_peaAq{>_cD7j#H#nQjEIbZN?J_&ZEQ2|mLw+_+howXg7BLR&+z;G^oY83d#By*LnH`|qzQY2y@36ot zJk0!Nc9PkNJ7pMUHz-%~GHRi`$(~wxfXDIt&kMi>xMnCYJHO&NS6-jwA|s&4{&1U?Fw;V)o@#q5gl72CU# zqVtv%>2L4NYRW49&fqClP2p zKi9S-uT{S8N6n1xDO%glv#rR837E;9s;QaJT}A8s`L;C~aTc4ok2Nv6*J#bZz_uaN znsus9OlWL$f6>~0p-pLYzfEOyPfkTFHfu9iYiH_an*t7`E&9Li-l@4J6`WZLGHHzN z?PeNZaPPt}u86&<{ zB^hLIERr`c5nXtPoLLFB|kU=Iw3p;IGo;k(6)U@Z(^!Wf1ZiI6Ex;9WCF4S?dD zW;pRoGn}}kdE6HiwH%LU!<@s~4r8=9tq$q>(LS9H(;N~NF^3i-!gbkM@wC9uL6SoEq;(YL2 z0qS}t?^Mja2)nU0)QVcHf$o;Wy5)3IGvFCqokpoSP%`+_NG*V;Q@1)u^jEusCwIF)o5Fo!Eq{T$W^$t#FAj|Afs>JDR#lVsy$(qiB#T%AN|3Gig{?txPE z0LoIKI~1!YWl3R0$0U2b7)kAgT=xp}txKS3lEYq%?DjX*_72o97uXxQX&0zn=Rol; zBfpe2^(6k+iKL}K$%rne{xVkC6DglSilP%psYoktD(VBJU514Ea`HYrc{yI;eW=-m zv>Z5`d>Hw1H0344Lb~Lj6y@8U)%5Qrg;NGdfp|c(ZCEd-5FCB?C;Y*+> z>#k@Y#J7$Dj*^Z6epYaIvFCti3D;2!82 zzMRn%x^e5n-*v-{Uy~my?E2aHH7Ef}P5oP(Z zXs1vkrM*KZ$~Dj)h`((Fc1EKGsF`}7^84(m8iB3-(LXezzCHQqpko*v^a_Hb(JVag z<#GA~@OgF~!zn%I<&XLt`;!r=XZ@~dE);uj*VIegebGPcdSeCsuZm)7DLuZR(f+cy&H?4CULsFP3cqfY+7 z+Dq*Q+zma+dY*q7&b~D|jmLQAQTGaEas4@|)+y}*N2MNj(pEjr-N)Rk)W5>6QL!tu zcN~>^!YhJ>cAUGX)_KLf&`xxZ)Z>0nG$W6*FWocsnBN7Rh4!+$q#pJC&{k-_+Yi`3 zwaPsbIPORMqvT&j(q(-Wbwv;MbtJ76l3K36jJoj!lKghV`oA-^k{3Vjz96l`Lrq$# zZ>j$#$eP#Tbs%2uyGYs}WU2JxcRV9Gt9C1rNv^-b3R;iqnJSLxVpOK!1msKpB zTU<`+Rp6E6Yn=96;&fm0pCSW)8sCYh;aBkyWJeo(1U-I%>~qB#zwX5)zX8-v9A7~8 z>A@G!U`Ox{YsH3+Ig$y}y;Dv%4jY_#Wvf+<5By0L7Cdrbr2DPvcVB@wk*H{~t`n zoj~o7q|*@8zUW8v9)j|9lRo4gcw5PwpLf;qA$x)H^XOWuQF_ryA}!uGm3qlZM*R{s zFQRRg)cR#=UP9X{Ire&LUUn};(hlHNi~RqEXor;iyCmm-4oUTTC+YbPsTXT}=Y$99UkbACSKZUmtLXmLfuE0&XnxF{b)=V( zFTV!w{S;5VhWWAn(uKo^`X66ax z&(FF)IcaSEgzo$w(YsC>o_C!zKkstqpOJhn{~gKOQt&_E?T?iH6UpcD9`xkeL&`H! zP)JWan3o~H60{sgVy_gFN1OZprruTy#5 zeul@50zgVKe}}y|gL4DfhyfW-YpvKGgKa;$|(SC1_$EL{j`fkQv`kE*bHIzz5OA9EHwC zQsn!{kBs_apChU9TFPs=I+}XP?C&L)1i7DIMp+X53&{`Xy1$n+xt~9jnq}w?`eVtX z{d0f6C>ntE&Z1~XY;_iKX8>BJy8Z?p#1zBkqaso zKtpmt#S3UaE~uCS^-2G6^|{)?=kWi#`Q>~|jz5*u8n~QX8mQL5*1nBDIcnqE0^6d? zJsE9O8-G&N4vns~QSH3+N$tIKOM>mu>z)vGKp#8VOG7i+Uw|%V5?8;8rcg5(3#Lhw zi9n3LYkz7aSCd}n0H7pl(f}RcrTdvm`2asA=#a()jnP=jV}kDFY;+`wRJRw2$Vfap z&F_g0=^V=Ea3$@_*=R(hT^kp4RO5J__(+i?Z;FRB&5!5qIP@3?BB@hUqyzm3v=65t z-9HUY%BVg2II3$PPf>!Dl;=Ax+{LN3@DJ?vmoSKtuxL6lkn2b1r~7ftjN z__{s)G}36`Xzbmlp~0%!7sWZ{FNLrH_NzMVm>q~?R8`9V`4$@-9J zUeF*&>OM3&Bxn{SV;>eB95fEueA(WStaA@U>y}Nq6KS7F^7dVTyP#?6NZmd_Y0c&! zZ|{#Lts~_QL4zi}+J0!)q)}{7nuNBjJ+Lj>)$zV9S1L=_DvjEB--a~7w~i)Yl_%ZU z1nggiN7Ezkrbjb?GiXVCCfkMR$2_~ei-59h_D()E-YMR#cSj&K#VQd^ibsNa5@qQH zypz_zJ82$t!rO=_C)ykPKq6vcF({4L-hMTAPDQ(u6Yc9yqrBP^CkxBNmJyM%{OQ!3 z=37MjVJRtn&wl<4YEDO&;N2NW+2??P6Uh5V(kt|j7E^yBQg-ha`_9z$N4qJBapy>q z~%blZRkU4jbj`ha@k3)XnIg-Yq3r|WjDmk-5mbnDDj9TY%qZYs}=uZ{tp&L-z zN9VeuTXe1mnndS%qDgeF7dk}edZRsbP8vk#`l2gzt{<9J=UPO2@XjU3{GD5h%-^}A zkoG%wG;(a`9!Byey<5coB88;O!RzSyc%%)o9ejvqJ|K6jjUNF2L++rU{{gmwo;oZQ zTLJfAcBSYk@3OPo2RTi9m+j;&BgsuCQhOvzlIV0KbwbvpsCpepO@U3RZNt+ofi02a zwBhL%t}P`8Y(w6Tk_WaW&ms3fNq$r05%PkD$SQM5je(7MBbIQ~btMsDjWSkoz%Iy4 z>H}NzyK=xBa!EiHd9O7!{ek6?b7JX-%u4o&71;atN6u518c9IAA;lUHV6+_9!fZdVnM-X2%KZbj2hdBo)Yc)d3oeCwVY@Hb z>`HBIaM%?*SEQyEI1-+FP%B@tzCfLJC7jj*b|aVHSTC^Ijq56udIKwy*Pw3{MY0?B z6tz-#RzFmyz6QAMLoQFUKER&T3L~w7l5|G@kC8T^RqZxnrW|-Asv1}AXpbi|@5s6~Pu!IoMf*ohYF`vrxwN&$=d@-E?P1tm|^7Ya(|sBaTg8|CXJC~U~TO|VC3 zhh&mjTnQ&x0SW^(LwkjxK47j-z-_Himc&aqR==o+)DQjWA4$LJan+yRlMJjrX&|s3 zSL*G7^t>cq4M{tP(J(NKlAReHl6YyX?9Aws%u!=;5MyvKvdE@EE~#-jIE>e!VFU|G zcG*10F*Uw-3FBK(@=c9h!Qn_NHG&04AT?}78W~3QNU$tgQGvd4U|A!#V(6KQlr-AP zg<3tMd+rzceB4rb3*f6j%4_ckxUF5`yJXuhAD|I%Yombj_!$9TF7ByY;GVh#o~s+Y zRxUN-u;e{3B6tjpfS+&Sv*E`^z&#BojRlV8swdBO2Wp?wlQ(n&iaWL_?ydM;Hr#hB zU~BShR%P*1`;sOA#TV>L+Q-WyFB|^54R9hn*f`)g?oA}^2QNLG|2T=X7jQ3XoAY0K z0^9O@b2#?4z-;Pz^W-G<(Ar;Xr%(Z?ok6*uf%j0E>X~ zYMKwfaX3(3NArO5u@K(u0?To=m^<^?la%9nGXHZD)}`9P)!-|7vd6ALISamZ z7_b-lAv`k~D1V59*~|3-_TgHVtHaoJ4~28BMQJFoCb{f-|LJ7)H-wd2EBP|g(X7P( zrhYj!%h!4jZ2i{rRH7Ac;*Kwe|d*bgYbkk{BD4gku} z<2CjT1A*E6TY+>ywp6tU=_QmDZnXQed-j6=TldmeWQFFs{3=;U+oXvpC{z+&=fuERO-&w zz6;&zR7z*DlbVX;QJxSR_%D(|e#Vmg?v@}bxO7df4)Ge~E8MJ(9>r#YSL)A>)+gS=#eKiA7w>0B>g zC0Rai@E37)F&-q6Eqy@x5UuXH)V@#YBV=Vn=|M8~K4n=`Z}76C-r(P*?js~)lA1|E z_7S>dd0U-_ruYJ&e5mB1b)mluc%GO1>?1VQ=W=}&`sypaqVjBT*Kl>Ue-p{vhTvQB z22gQ%bTW}N<5!VOetSAleuuBZfu97FuimS0;HLo1KlC*6S9$InADwfJFNV^85Ls6OsAKd-8tL176V^en74* z%klfTd%stNhwqV7%f|d(YVPxj0`VQPKUt|iL+M+05B2wY$pgP}cT>IxUHhxZp6>+S zg--odO6!mzKjEcgcnq1fyk}nb@}7C!%Wvj&FOQkmz5KMW+~Pg2`)}yS*S%s?yzUjX z;&re17LTGIc+9WGI^!{9;?jV~lH-vew_F<}nSyI|7fxQD#quOxi{9W7;5vRS&*OE# z$ElMP^syipeat;c{aP=1>0{_7<*9Qi>2)uC{un2QGqz+jD4Up7pn(A6VmVLn?cVd!G8|uqV2W8byw|4Y~bQ zJnw1KQ$T5GJkt6nfsXuUq{5G(J9vyQmOkMg%Dlo^wS5+ zwC?0f&`4Z|=Jz@@5Q;l=9bDad-yIIF2f1PsU5gf&aY6Z7^2I!_Xhb)Vcjbw0aCSY( zdy&ea6+Q~h)REW?-GD~>2A;bh=%pLN?=^z+6Mri2`Eu}->wQ^K(){WoqP2QO&yP!W_#@)lwdf$Zh{3d=QUH%2|e>LF(6%Pk{IO;CIR^S3O;`OMn zkEU}4^~aFE;%f(vvUcDlYXR|>;+cBErr>O#>=n)=$=2Xp-f%3s(O0~D7+>+S6u1!H zQFbKbxt@Tn%X;4#C=d00uyA?Bk0Xu8HfA5bm}s-E6RD?(K#tZyb#GsYdq{~p6LV}Zw#i|elm->)63?T6ZM-Po-H8;1jB3$TiJ zU+9hpu7a~|!;_=2E;tT&9B-M-d)otva|^HAChWqrn;?b`zd03~h1I}SZx=9#{J^MGcZgp5hywOzC*wDxT0z&UVf@l-uyjJ@`-UfRoAh!C11)XHPJYYgw|) zXZJ9WYwc7AV!N`CU(ca-A#g6a>{%887xCV~Jku9D8O0Bq!SyU`S`H$|A2jR+b|)7f zKN1_E8CV4kr?gw(@<(EuG@B=fay<$t+kv5^Az?qT8~cRa!j54V@&kBo25<&%QM9lr zz-ibj9l-T8c1Bvhids69wQp1gMWp4w0c$FD1q*CN#p|D_VJ64zP$-yMMZ zU;4HRKv~n&AZ785`nGC(ZFyjMuGP8}Q1Xqcq-uPR+9n;(+*MpOFK%UfrkI39hKg#y`-l_IulDhsNVG9 zo$5V}1dSZ^o<@lNyZ&cIuJd|R{iq&{dsBU<7A1SLsD4y0*5toA;O6$D^`LrFJ=XxJ zzEwXq;OmR;NA+Obn^h>6v>%I_kJgXztjwE_){pV5%$tw#OqAqJSdHhSMqJ*kEX(;A z_h8DD&=+DDq@z+O7&(;X+=@h zr$%E%U9C^8H*Hp`H#IjKhdvc`Em@yxwXl^!ux$HOD??0mZJvr&>T7Fn{9pO$ZA@un zS=LWSZwvS7&vl*_MSEka`&05l@fvCzQF8T6azt7^^K(H-s+-3P<>!J@j4^QtS~2tJ zm1b&w+Pf{!Q&HWR0@t9NY)e`6X}a~aAb(pFU$iaH(`~s=3$CY0+PfwDG!q_4yhc)Q z64PGeax>YpWHL`Ty=N(EJx$VHaYr$yl%i}}+&mtsF7!exsrX27O7VJXdls#vT2-|& zH7s&HwUu<+=aCBbX(sbD-iIb>uj1&GWdCCO(0J#Pq``rBCUY~hHFR6)$8_?9co!q7g6Qq$uAAxhq2kB4j9e(5 ziAm{DLAg*S{g?@jEn9hlNfJyhWV=z54kanA?O9ANv?b&T+X7Epw)1h*{iv~Ba6ZOT z1xfi#o*<4$t9#M%y`)?y*^lYud+`obQa)QN3(NQ79jK&yCQm3@zIPd3MUkQ|d)lAZ{LF&8$D4!}$2msC^ zKOQL0x>=+Xf%3SCqf>z-m{1nfmJe#Yt z$j?OfEl`#jNL-M1`WY{N{5o*jC$fT-3+2<+# za3#k1ILhP6YXD{0H=a}zC`p21g;i(%ji)?;ybf?Yd0p~4NcHezMzbYZ(B6S}-8*ot z(umcASKS*$d$!ZGxsO2MyqUl%*GI3zV<$L{fX8Y}=$KlNFnEXwsTVcP2}=Nul-Qz;Jz?t)%O zwq(Q14X;!-7D?iQP7i z)aGz%4g+2dlz#g#sLS=htH}@JT4%)^23!QZ2`K&ZBB;w6p!E5RxV{y7vWOaK74HB_ ztG|%a?La&Ev=xw;EFvoO#eol+wTbRX1a0cGht?*Tplr8yMp@&NE2@) zgwk_Rn?oocjHSo(z-P!04y&*9sLxQwe-A2iFmz`wxdR?dJ{M|J4k%7@F14aGbE%mF zwW$cyE@2KdrV4N_S97SX3jLWw%|U^?J&3Csl;@CFBd^Y?BpcA#(3zURYUH!It_wVf zt2*R$S=VI!ISWct4=BsdSzI>&&gKrMMNmHzdeRUmo6ecgn5Mvn`8$o$)L>&Vl~NBV&s6A+Vpntn%4Xt#U#0ghEda2vkQ}ZBZIg9qGXL=XytIi)hdk;Lbp4(x*_`2{;5=GllCRP#)>K z6`f-cQ0F#GrnC!mXEJ3)^B4*o0gagiy%_=Ij0NCusLXEUqoAm}L3<`r-VLaD@e`pr zdjLn0k0sw7%B<+~`*Ae}sI_E2uEzr>QnwfRI4HeV3(@$!fqRkfOZ{HZt@dGsNLuR4 z;=U!Am%TxIl5C#EwYMfU0*b?H9eTNSSZP{^m8LcCQEzE2l~sNO)H3AF{~No?3HI+FaA{mJjXF zEKK)|c3nI0OYJBtP%=HU^zf2KONT2ByksGgI!pE}9UzfN_*&tp3ja&;8evU)1Wugf zm-bG3o8D|Xe`!8V&u?}Lrr}px>}`6#?F{0#>CJj)W&U)xQuv-qlq>VCdfN`9O8h_l zmx?5{MH)S|s3QMYG(+|e!jC9NIg+f2Ww|3;fpYvu>Akg|FzgAl`k%s@;ZnBO`YvIa zvogtr3q6zG4nr8vv&Jae4kJ@JwSAZNJi?25SYM+)R-LfTiICxr@T~EmXVh!z4dGT8 zs}gWk6<9T3OxUX!Fc|l~FeqGU39MVSdSW9)Vr)#oh3QF>l5CoPj@O+ex04)!#^ER5x%KHu zaeVByHcqs%7qs6s%U$Us@;HClVT*suv&P=E-Dg2Nm2~`nQFFhf*co#Y7F zd>U2O>rQdwq%8Q8ZEe4ksb041#z}JS+XzW=Dak#4a^119XPilLwEP!5abk|#*RTf96Wx$bN!dJ?Y@#jiW*_}HSyNm1`KZZyGx}CZCiHP@G6CncO^j z5__Z+^b;$soUL?y`tzkH#mP^8YCg84^d!0NY^iawCDw>|>?Qe=lCC=iWxScticFsQ zDb}5m%GnBzlX$-)nNLxEr}}0;$ND8t9=o}Gtm)ZJYn;@xC-*yBdSARPj1$`(o5Uj%{Z5jelysaFq*0mB zicFr#gr02YV+-qx)6*06tVKra#7_pKOc#Njy%HeVSY& zHb-Zd8I4LO<1Km*l?koL6&xpJK~IwV;-vp%98p3%nIgfY z)9=LNBy)PQ=`|uACne=ik`|%K(ITBuCSxFzXX0^^v_B~;KK7>?CrLTmmeTLUeVWdu zXmjXE`mvX850&J3k|RXxn#p7`83UO-lgT*wsreI0>|^P@zPBXulalUtgyCd7sdV%t z|2Po^i0!uv_v!Zi&gR*lC-=pf=mEFIagu-T8)s5@v=~*%)CM3PdnH|WY(=xxXLIBy znee(XJt#RH5 zrkrg{@F&TAadB~q(~Xn-{7I5CNjFZ6i%9NJ3ij!ipeLEoicFq~`IF-I#k=Bn8lN*0 zpFX3LXW~<7M&LUepH?#*Z`xr_=hx^w?rc1Kb*7D-aWjOx8Ggd@pSF{522+Yp$QeW_ zJ~>Bc=rjsZ4Fu(TtHK6`vpRclJ}Ty8_&nfq;kIyJ0w@KWx~d)iZ0!caS|NQ z313}+hSyHqQ(S4`y%X3~WD#M%6W2N^suR7GMXsJP59qG+qOP;Eb7{3&EPwmlfT!Gm zr`&+2+<+&YrIr&gk{%xs|3!AVDRRS#rzD@+a^#L=)^_UG3S711oh?E;gs)t#)dFEE zm+MC4!e1`A;zl(JZ4!=jc9@+PCY}8ut)@s9#wc0Ratv1Y9s|_>OIvXwa{e~I){^BvCSUj3VI$f@)(PE<`Z*C>= zps}moRa=v7Ot#K?GabgPrG>|jwc0Ratv1Y9s|_>OYQv1R+Aw3SHq2P-6m>`~P<#Z@ z2aDDikEOaB=Z9vBaG=?vQKQ+VIVS3)8Kya>IoOITMbgL{4@o>E$9Q2pSbME?)-D@G zqO_V_d1J|1S{O6dYQv1R+Aw3SHq0bjZTJyo%#VR|tu|_G?KS#hShZFgR&AsS6Pe+m zQ=s7SEZ2xAj0bD4wa(gQ*igI-Q5Rvyuw*SQj2UaSVJ2OVr)zayd*dEAtXiuLtJYq_ zr=ovoRnsb`SW%mchfV<#$?;Ga57ypfpB5g;)-J7?@jSLMT(~z4lUn6Pt%X^`uu&?* zu(jGKm9^TiYOOZRSgQ>)!htZMl|PetQFuIb+PHRUT-dzW(s-~oTI;M`h7DWc3>$_e zYpG$waAoZ^oEXLwn@`-2;X~Ze=HkKHZ8)%TA)F-VMM=hkD0-5P8LtpiIE|OWc(C?b z8?9Z24dZ?c57tt{fTF>s;|w-`UKkCqb{CD4lHwtr3wbe)~{vqD! zYcHZ5jHDgf$HePbX?mydR~7yiedpGvMaIi+dw3|kt1Fu|$l5DOkfNYzA8GO;lb>vR zcqq$O+xhO2c_}iS*7?%mA-Rv=I{W)9)nbEh!!(pNQpM`RT*f z$Ad{4GRKB6AStBub=n1%1`p}!UyazHlYkt712n4Ibj%Nha%craKsueWjB; zCuPpb5omHl$(JR8OLFOXZLh{1N!&ZJ%iX$o$h7TAsaILxA+PNwZ#OCPPl1O_F<|nY zP2s_0rQ(0%@t`%$WXtJvH6~w9hX-2=OdDcj!{o`fI>htEXojdq@#|*(d68+`bA!}B zmUJbxTc+2NjwZ8FQ8H{;8;#qrb{QUQv>0z-*f0*k#*ax>Z8jz4iiSPoA{4(~`kFRG zOl}pTC+pPY-H>UHB(}14{v&CVqAg1nuq)C%#b4G=cm(p0;pk|!4;+rPt2yOnq+vn! zB{&Ryt>}*6Q1rH1eFYWqSy7P%2NU60`&>btt*q5cP_d!4mI*3av|=C&>O5tgq${ZC z(u#R3sCd(o=?nHpQ(KGFH}J>(SWOg@S}~9NGA?RT&LZ`O!stwI$=7;Aa}?WJ(xqO| z9-SgCc~eiQk?=Z^3;Zne z5#?4q-*RIs^cB)RJ76Q~B`=efT{6Z-K&`&o%hV0K1@)cUZMzilH_}5&r(Tm%9iY|; zX}NRhi(Iay56`79bS=w>T>3)S)j~;{b4je*@Xq2fki-3s0Z-}ipdN@@Y8bGdG7MPT z4Ohulx8Tj$e6iZnl5&fU-)~s5?=LB43gg7uZaA@48%|_P662&W9yAKtg;CI+)@v*z z@u1OXQt8HF^yP+em%FjYt-Ur{lI^vTW9_x^WBp~AvGy8H?3)cI_RWS9`{vT)L^d_? zIFX%2JQCE0+A*kg)~D8+njdY#{AjzejfNj( zA8WN?##(Kdu~r*qtks4Y`*OpKeYs&qRwSASvLn%~&^XY{s824axuZFx`J`E8IMf`| zOp{%U=3J+ZGs5r?_o`t+SV@lOWY1dbjE;zkv<+0G-Nx~3_(@{MT5XuIRvTul)rJ{s zwPD6uZJ4oE8)o8G8x6>7d*N0a_Tsh|Y_;K2HV~piqER*@Vmw$|t+x#aHZJloV|{IS zu>Q3+TI;M`MqzE_7_JIq##(Kdu~r*qtks5@%v){POV?_{r?uMfskK^kNOVbSb;0ql zX*?K3FCGup#&`~D_Svdq*f1>FXfZ4q<;kSghPV9V+}4x49yfeis|}ylYQvSa+At#= z2oqZ4N;)3ml`Rhwg~vl-Jj89x8_CI8EH2n)vAAHH#RXeu?XvaTaA>%-HX0@k!-gxv zu(jGSW34vKh%eJRuN7b1+2)Ri+>P`vZ)POt#g@ZEJf1a@tzE{`Si1}xhAYE{;mTTS z*igIGdT~C6H^W%T$AfWio2C;b$A+kTl9C($6jOQ|5gI#%u@U#Lde&MhUR(T*a3fw@ zQ0tfB&2VK{DheB!(ucz1A$KE>W|T4y2S)ccH7|q#tzov7#T;ae0UO=c`aEpdcu0o< zYrFBshK=6L?Ox7+qzwl8cRYXpGEDlwbM4)Nkzs^-Y6(*Jd_jz zW!YZi+9m(;K_VvW=7JbV@{`*J9`bngbiA1)DB8Uh-OJW$Nj(%FK|GG+ee#+7dEvo! zV43gUlA~R7M-oY$`nKipp#Km^;wGL--u1v5!&X5+!QFL~Wa4y#BorNu+Z+n8zV zGLa}IDN>AwbQCYI?UFKA3)1JRTNw|Twmp`8N$O>INYWqMOC{y-Md2Yy2lCpUl(%nP zJY?E-lkJ$4r!XGkb=k(gR_9IOA+PNwZ;vJId3uM!crdCMuQ!?_CNs*MP8KyU31oxrx^# zQ5cgHn7ld_a49b;2fv}WZeIBTFKzKwjXMoT6XZ=zB0)Ia6 zeDB={)IIBursgRB9?!h*ms0ZX&;A4I|4e!g_?&;u!z55II zpZClCh1_3GTILs1>)c}Qd-twaZ@%ze-vUT<>4; zf93Ay{!s3>a;NYg&h)4FQ~he-YJVE=H0q9_)hmH#lK+7=zT{u$*RKIz^BaIKarH*1 zeS`ZiQGT2JB!4o$U*(VW$N9JX@2NYU>ob98@~-2#e+uvz?jKKD1w6r@2t1KHZ}N+` z{qIO`0N)JdH~eq?Y=4lS<7Ela+RgN{xSmOx7cBx2G)aYL1h3RnpZR z-535#zmH$!_XZwDE-QsEfnWNs`~dFCQsHm@3qOG;76BLf1;9n*J+Wx`3iy@(8u+!( zar^Ryef++DF8O$#THyQh+W~GIxNHT~Y2f3yv%rrd9qRi*Q~wGSMd`vrQKsG`PW1K% z@S8pS7~cX5iK^6gq4l{y`F-!l*Y4~0ZvhT?`Tji7k2J*h@qH;x z;LbQs5g*6d;`@;A?RxrNzPHyo;uAPcd;+!mVO_Hu(9Rd%jXT|a58u;wC-nyQ=3U)+ z*AQSIa-CzopXUZ~}fJ4a-KY{>;l|{t6XY#^|{<1=?|cODrdb{ zC+|cpd>Dzy-N0BdeS-z&P<+Dh& zeGO85U{)yC=grl*YV50#H}*B$EH{(A?wTr=O) zH*;-$8(=%%7TDCc1Ge$){R;l`(QXB48E~0f4qQTARsK(7zmhLp;#QJYxGKIXHOII^ zsXK#BpPq-(6 zPr9doPf_UPo{ z?lyN0SGSRFckglUKfw3N|3vBE!1u^+<(b=nXSuV1XLEH6XWb#IXW);$1x!@W-ahPxm5I`W`Z?l|D_deb~gdnkk_Gh4bsU!xIY5_=-vUo!!H_=B=f$>-3Y8hUf12_ z?gZXVUYFXtfp@xl*gL-JUIG5zy#;)myaCs51K;AU4M+{yKh@>QdZc@S_qzLl_kq*; z?lpd0-)$hT4}LcQ?b&tx!FDNBH~DT zQ>$1yX1^&5P1$%>4ZKWj#o3FxY9v{2%D%H57;X-1LEe#)aNCZ&10`Wqm~Ib-8v`}U zr3q+Co5c$$f>BFg3x3fW+_nPBQdaSD98j@y+ENy`7?EqYBg-?{XK8P%eRzBFE?f(* zoya?r%b%(fm6jG5@yW;Q!$IWab1Ob!gJ+-;hxmhAjuk2 zk&cWnlzpshGW(E=`|1Of4egeU_oUv*i~3Y_yeDBej`}40D(aKsJq@HhfLu`XuYbT@ z{-{s=!CU@#Poir1qdv)&Sa_1Hu;`*NRg;!$Eas2&BtA=cuMX~nA>rDh3RR(JEYg#3 zEH1eUBS3pDjS5L!)k_)`l^84P!%kckjQ6CmpmD26PZ}v2vE><|8b#7(m17*)NGvYi zlcE93;#aY}6m>}F`zhY2<6RYi6}Yx|iIPcZY;XE`qcs+5(IUd={pHH+{iXSyOuj$) zepz-)1}@9*9Z1!HmB=enst#0421V?%IFgDWDVuWPPA4#nZpqeA9tomnqNFv!u4ta< zaV>Bnx+sj*2G63JqTQOm%5~qK_ThK-mMFZ>-ku8o$NsD0GwVO=YZL`ny{WIP5Wd&G zz9KDA3#>iXwk)2h#yh0}tU{?O|5syMYq4M!brt!IMxsWk-cdQspW4i%x;!C$pvIu+ zkY-&yU~PUS$*WqbG1(;0L(SnvP*07jR^0JG$=O?xDgreYTTvQ8AMGXO#W0NjF(mwd?J-4%)SkhiH9NCEl^4TczG7!e@?g;S8tvJM zE72k0LR3ip3j@L0j+ErTup_-aAYijUxjY!u`=a~uV^AL``kd%cU!bVDd=|`)p(cGM z3M6j^^`hvIRy$E<(H?m&h(3!l%X2}P79El|gXFQIL-JCH2j8>=5YSIJh%j%(btB3xs9!5a*Fea)qKI(H<<3{th zA^%67fa+ECvSZw~1h%5Ak#7{D7B#iQyBtqB-mfv`_?7URMXDLz?)a7GTK~iGM$fhI zrcogbRsm`}cuJLk8Us2(Aqw9Uh4x0Fy-{dy6xti{KCKGkpi-gLsnF^a*P8R$)Rqev z&}?o&@3!Q+JZ)$R)GQSznFCZznevQ=HbC`WdH#C^{RiirQsY@8Tly90VB{et z9zxM1Md>?}#NnHVlDG}?S?UIED>BNpnsp;dYFB|$kI-8^0`7ZI(;Yfej@n+KUwcvR z3Ek1$>`m$gP14-#L+Z__)ZElb)4KLt={e=12zFhEH)u|1{isWl#$Ivi>xJtqU@Bmt z9DS%-VIf5y>RMRP85Y%nYPsk`RiN4_njy-ecFJBwyPNW%*UQt>jVY_A%ZEPJs-;m} zo?dpLr(Nh{7kXFUna$U#cYWwreS1qH_g;TssVa@2AIMO7wtGAJu=^rUu+#)H>qZipjS+*PfZipeT2 zy&-c+aa*-+He!y6r&s*e#>_oMc-1=FggL3muYyJ|)0<*zT=Uk|8gomvy>0L4{ltC#gXRmX__B4HpO#^yHo68(R__ntpr*R zDu-5T&*w;5D|BMWrdCVQp5*$a)vp#cwti|Y6%LIKXpImyMe{Yw^&fV>b?m)g5!!KAg!(JoOF%_;R-MUvK(a^%|Oh;J=V zo}F#qEkE>zyhW?AW=KQcqP0^qrvdL07bhB1pSNhm)l93$TeKh7T(8Uf^mUqyhz3{D?H^Pzl zlX!Qp)msu3?eoR&X}79t@q3!Zx)#5uxvXpLaK&Fn-=fuB zJWO+-cpPM#P#R>Fv~MSV*%>@!XWMu(3ZULrj1I*JuRzk<70XilJng*necFpv18M}T zx7E+(s8MUhy=v_e&!tw1pVgSH4Ai{K|9-tQ|9`Q)W%A8>XDa+h{g>+D{o?G3e!sq4 zoV{A1Z!P-$W%d2(@RR(0{jd1T_09RQBwjy>pZwon`u7{9v;SheZ?b<2<40evUKTwq zPdPv43x9v{?=R{1C&!PyIoZpFzrUpKFZ}(P(gWp1<~Aj0%ZsPDdZo<3C;hCh=36@sk`mN&1iuKgp3V zTopw>llV#Z{Uv*UjDNj3rlMMzHbwsnF;r=TDORAKM3sQ%k|!YW_*yD@nGvDedr6KuNc4hhL9b zA}(M2nCQ!Nspj7B5ave7xE# z3BLGy$u1BpY+n&y;dnfgv6P_xWNo%%{WWwT5pF#p&~_EA~4rKIzyv~Af`zZgx3duP-A68DJ4 znzcnVA~TwhY>Ux^xOdX`OH!7wCHo~g#zfijMw;f4c%H_LCAFY(pmG{rO-Q2TM%iqP z8GVaKT6+4nwc3)LFSZ_8TdWmHD!2LbWm97;9$lhmC7t_QV!mhvO1JJL`=u!Q{7c{s zehxIPU>`}&s#Qg+hMn`Kv!~QsS}#mKmdP{HnwV9Gel7W_-uBbIXG?suoy1jqyE1tu z9iGbyhncj!L7=(~>8EPYQGjevJ*B>R51_gO9*i;5cyI0w|r(IIi&w;kqrbE&c`*!V~6uus6TR!TTU5_#jLO z-U$1-eepS%h%dn;dSxPTBG;3^W*cC4^2t0m1vmw)?hpRE0cCBtKlPJ=vLM-?GzmDF zI|l?k6PEw%-@#(w(qQes zl#=`amI9ZNAH_&p29#&Qa#B-ZQ%1pZ(mlL9n8E11gpoWQ*o*uUO4IPzm_g}M(lmTGW&{t8ODSK@h@1tS zLG9(i^W<`_XHq_xJD2ms!NAMNuOKx8&I#pajMXa`<#T`w$gkjffxD8l5IC3oD#mdi z;6n1Np@e;bS5b2{sW*NT{Ta*GkdDCfLN+MZLKpi1`v>2O!x+!kaqlp^8|0C5J*g>h zF=PIE(o*2kaJMOSH()C-IFvDa17mL}a3%Q-)UE^`!~L5m3*N}p&5Yp1z+)NNHrQ z{7y=D0MBC7-bv{!JO##3x{K@DKv_E6MKVubwU zP`(Eb@}7HvS27A7BwYo(in<4>y%JxL`*`PC-g6)D8hU#z*Vh1#pl&;#u$@nke_}yC z!8iot7Pd`3LHs~EZb6)Z_=IWX2UAMVA&85Z1MMs;KA|v&V4Q>T3C1B9x3G2i1mh5l zTiDJgY&kw5$sriekU5_q4#BvE{Jeqj3`q{b_=o&_g1CaY32tFQ;1-g6!kn$nClt*a zB>4y95R6-hIRWDqj6+EB48|=K<`cvlB)Ns351%k+BcCvbwf~pFCzvF`qzYS3o?wy$ z?Jgx-kR+iUytkwZifAtDGub>BEl)5>f=Lz9$rB_=FsVW;PcTV>Nfjhz`1#8dOnOjQ zs*p~eAW4Er6*A)!BuOx-LM%ftd4kCnGLa{k3_t&JA2QcF6wfDQB2SPcp{(@|+vN!*)jO1i zPmpHeJW`(CVc&$_VPeoNnBHMxA-%)Igx(?6HB3ayFfnK!@-z;nl}N`S#CnIMJVBBK z;~X;6I}|TZFkOR56_WA<>C~=(yOqYlbPy(0*gScHG!8MJU>XP0K4hYI$kRBO4kDed zp)BMHrg1Rs!`751lr5i-i98{xaWEZ3>GclMFQn5xluqxk?aLF4H%M{|k}7QH6Sky% zf=LgO+=5vqn5{z6K0%fVW~C6@B>YtJgu;>plQ5Wl!mm@FP}nlTEEdYvKA~vK1hZS% zHtZA38o}%nj6*QaL6!+IpJ0{=NvT4fl|p{YgmiiblP#D$A)S3f=JEvN5KNw6e1b_5 z@~jj#WuG9+1hZ1eFHaC}5Zfn+TQJLn>##qN9YQ+$1X(7Sl|sq+1nCrFD}};(2eVI* z_950XB&`&Z_6cT_khD@L-af%B6U<6sTeD9vK0&-eY@Z-*Av61gq$I&43}&BDJfC2e z31+2`CrL0Xh4l6brfZNjV>4_j8UmY>%Z`yqpWBcfW0FHiCr?nctL=7-o3dj}$`eeI zkhEhgJ9$Erpm&glp-Ip?lt!M=G-1tHyxt+^6PhAJX!`#ajArGSXP?jn?L!krdQoYw6*LQf7$j4+m1Y;tn3&w=M#)WFs`7CV?&zjLVgo1XA&EN_O+c7qyuH<}zaRR>{`-F6Mj7>M%F*b!aXd3JolYD|Whb_-1 zBsC7kGyF324w?8nY}Y%;BVtp0!gha$f>MPoW1nD_30udG(JUCZWq*g#=pBBk{tm`1 zn3iGd_&X%^4tX5H=K4FxqoF8nA2go4@!^K?jW zpCGwG?DbGks$hN%>GcjKPxv+S3ETZ5OUfr~`~D8wre9?7@`UYvk-t>G$fSKjI=#a$ z)i3g=vQPMV`9;bjQs*q4v(bWabNwQVw__}xPbl6mvasGEbHB*#_6fh9_zA`99g^`A z(%C1-G9kYm{ zL6H+;e~04j7}NPh#`Xz$evwHl1z9u3_6h0yBDb73<1SivIt9xwxrmLn~t;8fEYiDZeNl(OFFqg5tbSN z%`Z~tOqRqiGQS;TL;M{YZl)b$BfKNGWSpf&#H?xbi-@z7j!!7wj!~8_dC`{4JF-Ek z{URG;Yhclqj9X|J{35qLpRgD!FP-shah7z#a{f3=OR-5<$}C#W7*K>I#W0KGEG7LS z_1sFH{I$ec+7|QtX&H+1h_o0B`8^%X_rd%f%$hM1J|P)rDXDiT z?C+omOR`c>RHedpj7x(BW7A;exP<%pH4aPvKem$m9hP!e@t0z~!&2%jhLY?Umr_n= z$G9|M$C&hbD2*Ls=5dzFR_{=@e8Q5Aah8^#aVXv|vUoejUv`|O{Ct99Gj8{HD1AJ} z;`I)h@Cg=)QKx^!@fgi7Qruwd`(W`C3ddtqBu0y(kUk#cmh+2LBu0y+P;&c(;`I(& zKhBcbCn&;_MP-yHgW@p`A&=uRS|mo3EyVE{PbA)Ax_FEyawm?*sOMJm#?6n%_;cYC zEc#;MsEihmF`eEaPuGz2kxUenMt;jK#%cv^Yx^ zkFj7RM)Qu0`2UtlP8!*q)8PNSyWLO>nmg5uhA~9Mlg*XPINfOK>(jqh}D&v;7V>E6dX{C^f9pkp9chI@AircJn zWV^DDj3YMZkF(SjzevUSjpH_Nw__|j`-CoN7P=%NHWw9VsSCV8%ps^Oo*~H_D0*`o zZD~_+mK1|q5t|jaxhwfBpyD=n%@>ccD>ZrAhs@$JCgUfRUhj~(JfZkFOIuT(P+0FE zKEn8i^n60u#%C!~`kNQMw|5f+cp_=N59gk;?2q&%T;gr(B>MP_cFuyxLNC>)Pbkr++;u&H>A z#vvr73Wenf+wB-j$|n>)-=Xw=k@5KsF^6EBLoyPh@eG?Ak1_9*hx~kk@dL$0Z_e|J z%paAp8dof1`g-^ndu>u6D! z%$_0LSy5%Hn<$O%WF}`t74({n&x$Ik4TH22v8|)59MhjExvlXDh0l~s#$wuj21MZq z&s*XQh-9=zvuDUVO)|evMDk3@U&9#?#oI6>Pl?)o285j{SsFf}tYR$0yg@-*N8=yt zOvz-l#)2nH=8xH!jP0D1HvF__KomYxGM!IEVOz)IWe&dv-^sG&6Ov~@6t-bV+AS1} zw6G}~hAn05sFRds>!cHub(Zo-&T!QUvtvo4fjakCr!J2K4kI7O-LXKO^g0-8lA*w% z+#MWFyd50QT^=9Ks~sQCs~ykt<2aRQFm;`R=DJhxc`%KGoduPPKSZZ+w%=T!offQ9 zg1Zpgy=~B!%O0UEdUKs3co6U)?#?331J1*SXBJ5^xmm!&IaO1q1uLFjHr^I3fi3aV zID-1aiN=>rxj88ZOWq@}VAsjo&9U}f$kh_kVqz9`<9jEN#)tTQIlwl2K@)z{8Ynx! zCc#H!DgSW+mb^OSbt!2HHWl6Yr;}#j6`^yntMQI5z^vHiEk|+g!rq)(U5)zcq@A%Q+lSgy!nuz%sN0#-taU#2$<&+z)QON;)a``+ zc|WdKhqHgnb5?IfPO7fRxxM8{m4KBv{kuG=3a6y%Ox3eUIu}@$YG+e(7H~Cric_u2 z1IzQ|Iov(lHHoHTi_j#RrbvsC&T?uR^`cEpqn@;?DK$-^rjfJ?jiV;f0l@vy;WnnU zzv~e7!%C+^)SolCIz$7A78~*IDx4pDDsOKeiC(pj`f>_x`=|qXv#2+A3(a_c)2LCT z6R#UZjmg_Z?YYyA)GX>4?a2A79eG=asBP3PY8IWx+s<{(xoQ@5;%>*N4dv!h4k;Vh zCX}d}5+vwEcXRMq*#MAwohTSZxX z(PWoJszJFSS9kfly>m6A23*x7WkuC^(+RFxbUdf#R-<%0J5!x=TsNu{)sO0u8blXS zb0KFB=|to{QBC@VC%?;$dXl@l-n<=#~Hc(_-)^)2ld^euH@aKTWF_uw|Gzg-QsWcxA|L0w*znYcL4A3 zcLMM9cLDF>*;{->FJDF*F9IG-|6CSMXt*q#&3qX;|4XRR8O)b)?>yI^|JyIB7*&WW z0V_q7qaDaAM-kt<%0;B(T#D-|QHnd2fmOKYBc03bBb~_YxjxR7<8CUt)K|f~>r%d@ z3a2j}&HpG*eYwc-i({ONbh5Xjge_h)Alfk+L>d@f=5@mRW&Tp~TZ322t^D?Kce!tj z56k8LGV)u{9xVgvwD4Of-RiFJ(&1j=FDD=X^Aei!P80UK}%{Vq{MEVysx4Qt%+=nCHuc%{F> z52t>Y=qi6DrJJ}b?}GpO|M{!^Rn%Nf8WG({%}wqa>PAG@kamr(_1E}aqksB;_<#F< zlK$iWMgAYZXEZX}E!vYbD*D0yo!alI{So*t^6&i*=Wq^QZfdDSZL_g#2SlU;0z1JrlT^{1ksG`Qz?k_lSF(^eFIA_n140J7@Zn z{Mr2Xll;kCoy7H7z_X}ZOzkDWlgQWc+sEBH{_jJ;EBMlNAu7{4O7~NKfII8B_pp0{ zyX$~gk}u)+Yy1-4afyG8nkU>xeBGD+BhpuXDfey$E+K!FyRW%dv6j8k9YyU;{wVI; z47>>(y+Z$7?Oq9y!e8N;SKX9oQZz9-n)~B{-^{<=49p`5)`uSN?0i zKiHcb?a%X5fRo9W`J?@W=w+T+@0R;zl$VqCjt=0-{egRvzr@{_-AnE-{zE^N`+G-I z!xJm~a;{&b{v|gpT0wcGU*V@kFHrNMd&mFL|H;2Yde0w2?SauTekJ+y+^`3u@n&;hf?gRg4e;juXjOIo&qglXN(d_71>YsC~sGT0I;{Jir+x`#! zU4Oh^<)=r#_it1FJ?TB*d;WcYa5N`6D0<6(;GcDGQTM)oi}Zm%g!j#f4j~;3oXORj z+m`Pe}w<7d)>X^mPU)CBcm6&x52+idL8%@R||RS2>&~`fv0{)`mI|)-4XsM-nS$= zinJKGI9eJ#>DT$k{R{l=b>Qp%4gVIu`ki}=^rm~tKf(Q{NKg9XqE*oe(R{yv_ssW) zlJ5;xrbpk>rf1v)%6t0>{si)UsGSk*<7Y(kfqQfHjr*N{(|^O0-@5PIw_xBq_q2No z_zd~c(IURU(-RqB!?(y^Z zmLvSzeDCkw+kE+3?%3!!zH=OJ81Kh%??~X0T!Zei9EX?`jTh9a$maN`rrBc_+R$|kLAtx`4gh!qeuLseCH$J=4s#)o0*_|5z71NUcs{{iVe*VC_vdimbI z7kO{e%BZ$~*4Od1Y5z08hskSGde+yaR`6N>obSPZT@m%*`JTQHzg`*D@(=NBEmCb? zkEfpV-TeVP)t%JC_vMLWqP{%45_nAXfUn8(wS0Y^`^?qn7ti@_Jl`ESmAoIncmVi- zf6!<7wLF_es_7f>^rx-?zx&K}_0xE^tKW;fE2VC}Kfid;*Wmdq-;ifNbqz_MxGp@? z)eqp_T3~Xd2#2as3xpSX`*Wq$FAtLAs4t{SPjuj&VKRh3lDSMi;>szR#j|KWac ze|LNMJ^g6E2WgD|7d8KI|04a3 z^5N9(4BXid0*>IyQ|tU-t_Jz?z9LuUeFgGi)C~dd!kuBH!9K;aksr#{5MPexJkV2H zj$c&rjc9unU@mzR^2WY{@8~=E_T++{xYLX~O@WQbTlnTa+qdy;eLLTpT(CXQw5HVF zx8#{-z~(&Hl2UWuikg-_hx@s}MqKAmYUKOFe@k|}in{ejwfX~#8{-K=62wBU&*K%GP|nJ1>OkJ+D6EABM{N><#8)R++ zF4}8k!2ve_iWAPFR2$fet9krp25<)dS2B^A?4C#RhW&tT*tu$tFTG$JcDa%V$WExO zbNn_7D6c)oJ~M|M{yg3=KS&tnQ`(KaNKfv0_S8M$#OEVnSRNz~5jC*d?7Mrwo$rnW zVi|XKXV2N4TIpK$fa}+;VI@0?W7(x0M`;E5N_Q)JncLXg+(CXTdzm|ccadusx5};I z>K3@6yQy14y49aZ?F#mbCn%33=~xksXYaovn!ql8WhCwS%4i?jwKCe9wylI(?d_IF zlAkP(_ChwYoL{Yo*7{D!H`e-Gtn}A<$vbZ5zpU}vi>`1Fa(6A%LZ@aw=sO}UIR^UJ z9;o;c%Xr&zsQVbCGFl5d06Xy9L(r5i?jcfFr#0mPc(uFX*`zaD!P=))<6)la>a<$j z&sudH>&^+R-C7m3`Yenj1zH$M3UoZzT1U02Er=wiSP&frHWx%kgU(Kkm(ZSTZK7%&$S>z_=qHC$e=YVP!*K+h3;4PeKdpRE~%ZF%} zOGqaGwd`Dieda>oMdX)Yow*3^{#f2QQ&N0ek{ORhT2yj8ymAVbtHb$1CB@^C9I0G+ zM3NE@tDKBw>#&OUuEV(VaO79z%!~6L*)8Z2x9}a8@`e+#qquSmasc|K3B1!7(0 za*owRzfXPz@bdfs^bIwcgV1F{NBLKzdS&{T$kqAwM;AGSyVOk71Jwf6MbuK%SN5%Z ziYM<=(blm~MO(){l(KIV`YHK?*-D=KAlFv`mtwtnkfW6qEe%=?v^)Ho^eZ%~ zpYqQK(Abw$-ia>#Q*^eUQu-UNtHJ*}W%r}!FR9#5+O_gq&fkgVt!{rJ`8)Ibuovu# zb>+95pM)NMVy?wu*UCJsPji6_$xo(SJ@R+tS|xU^+(TMic^4%o=UTbuRkT?w1}?^W zbqeM0!b={@PcnDq0S!uz^m-3i@cKe%-m!0V|_6(D6X6pyMjj$kkSkOxlW?%h6~p zS_mG^x+Lpl7yhFSQcGiVrKvJBSz*Tkr}OXOlxb5QS{a7rwNIsY@|5==wJ#%Ifqn4Lz(4aWwY(XXU+{#VXZ4j@ z?8@u;wnMSIJPKyM!*@NJ^-R{|CH(&wr1_=fyCYov1^5@9q7FEt@*+?81-h(pz`G@@ z>>k{+d#-jjqw-_YPRU}emAsDU^-XqgZSxISurX>?^@zF{4fh$Yl_Uo^mjfog*La(;CF0=BIu zu^(s)dx84C2z(M;y+FDxJ0NM{2k@VR@@LSOpT_R;J@RKbdLdg&`2pzJ)x1^xd30re zo_a7AgoCjG?2pxA-(-1MlRw8lUcjpIEV=fT=YcPftG9HojLv&7!!VkoQD{+}@==wJ z`AG25k)x47XFxi0tTr~9Ig=6GSq&UXK8F8}M*A9E8B|dR8(itaJ)O~xs$^`+i_MQO+ZW4 zBJpQZHJafBv}qcUd=mLYw9K5NzhslpY%w5Q}p!^bx z&98y;D4UPIsy;dwI1lZ5G5OAzCQ@GVMFR%l?ym4p(=^I`uosCsUur`DD@@ z;84!~MCnUt(l7CqvniXCze>rUutU8CSb8S<9%BJO0v0}`mWES>|DdgHf zrsV&Nru|>&@qa*n|6lI=1Mt7dXK=^NWb2p=oQ!?q_gDec`~RCex>N5aYz9q9`)x%3 ztx5KULFl)Gv2)aLtrzx-8novjXvzaf1A*$wby!S#0kygGqhtVZ0Q#?1lwQDI{I@UV z{jhrU;kce-Eg;>=J0O2o(u||Ch86TL<>?9%dXA2!gsn&W_PNK|!>aV`jy$y^&xHVx zXB@Rp8exa+_O9*q&2Qy%+Jc|uNbud!z@2AahA!P5&DlBR-AK#P?Uzx$l++Eqxh84V z>iK#JbOY*JxO>w5ch7oq$F7`rNuC5c_P}=QY)y>wwN~szdhyY6nsCt_SudAD?U=2(7rPz8%9Ypa2C0? zo~gj8SX73PrepJ%#kHYWie@ES&~%{j7@8;<3Y5rqw*77dX?B)r&ege>#aYnYYcLd?F>2 zfNEP4k}tsoj*Tmz<~yEbYy)-SaisBJRBd`JX&jjDz>zdz3@zC{!7;Q&JJP5$o=4N3 z#zC_8jsllrGUIF{EjN?5Yk{k!rHjw0gq+0U^kp|M6qEC&W6$U3e-(ao|qCIm;hLd)u zy%uwANV4(`N!Gq*uIx_R?#{SqV7x2=F5wP+M^*q=Fq#@EZvbjV(-UPk;BJh&CQ2HC zL(}nc&g|o2pRa}P=F}U8(zf;++kPl5 z+Q{3xaoz~5ChyAmkksA{w5a{jHXf4Ncrb0Ly|ELegMgjMZR3HorG4Kv9++Bo0ML

cc{n9e z9ZI6QS?&;ZwwxmFB@KBviR9s=ArB{!Je)M-;UtoWlZHH;MDlRbkcX4JyzfhC$iqn_ z4<`+IIEm!pq#+L{kvyC<x zCy_iHAM$V#$;0s>4=0g493S#<63N5yArB{!JRBeLa1zPG@gWZx zCy_iHAB_>qVPouAZX09Da^4tgKIGvfl856%9!?^8I6mazB$9{YLmo~dc{o1g;UtoW z<3k=!B6&DIT931MAOn#UpN3{#f$2JJ&B(K5n}r_uyF>@6>gQyY`JK zYOgwJy4&yRG0HE0HPcP{Q1cCvI=fAB1&=w|BW@kbB_W60PU6%SQVV?{?F+p7`Eqf7=xcbUkuFy$Sx<`?9sh z&o4~(m)+J(eOk_(?B{phQLkN4Yo4F|`0i>S(SD9U>*uk0zfbj@=G)zz%}GxEX{O(% zSo2bn3zp3GvrgMdeO~T8*S|GxPvxEirui+8si|dF-D#G;+4s>pbUc5$zoN%3YTwwb z$alPPsQRCF*l0ia@Qi<1Fx>y6QTGDk`Q7s2_Wo1PWQgBCYnJ|D-K{TQAR>^0l>*Z)U;U3uki%DbzX z{8f2(qF;H&i|Es)GY2FNf99D3A+|c_jpHoO8)B|=F7jGn=4JByP-b2heDch*f=@p3 z$(Qws%iNSFsd)l_NuFfXE}PCsk@50po{{EBy3%)2y~Z~1@C!7P86xtZk~>-k#I{H@%4 z*f=?pp{mWazxsacPdnpR zVydxa-V~VkWA;6T&cS3JrapX65w}HPoxepn&%gTqqP+4qeV3u{$NrMIn-JSL&hjiL<_U8&c}^%ZN0VoaGIO-xqw}obqw})hqw})ZCoXf- zcQk+9cQjGVH~kF-(GAWr|FiyvLNrGBc3#H<^QNfJ+xJR37mM2>>i@ZD9GQQ@ysW(P zH+}c?*M0XCJ<~V+%@-Lj@_y`3`u18eMEGgs(s&)|E;s*q8!)X^_@s`{+NB|lK-tU--5q>{}RqO`_1oV{^%KK zQJKH%`=;M>c3BidJL^op+lpdUZa#2yexT(u=YQ)g*{Dr_S6*~-K8qk;Yy79qMu^r&e~a_9qnPBPSQY%I&SZ$zcYlj>(W5ctqOtZLI}0LO zpZ+b*w~sXWZ*c}iw7&jZ{GEbm{r zvp(W)@eTI|H`M#H}dAgxAQRH&d1-;m;Jupe6YiOcOUzd{Wjlx zu)}<_AN!R3uHSsH!+h@_`;JXP7pM_QSj4bNR8Clq2&d!Q`%AT)fKG@ep`#6D%upfDfo zFlST5K4s6ZFdytN=UUXOeqU~nZ)zm(ACmFwk7a!M+ud^QH>;T(Uu&9!d(Nt%yvO_Z z=5AY6BXMJ=xmDGB<_?=*Be{Ng#!vl_@qN>J=iZu9BYC#QbO-OeRZZo79lPcF6xB#J z{xsFW*KRB4Mhf>lw|DNH2{n>^|1n+pA6059pL~9|+_qw$@%2;(en|ioNBRQvx#0JYMYZ0nNMRjuZRhFQzKb7CRir zt?YRq7B}oL=Y$NII9Ovi^Da4uP?#9PMQcZB3>(RLBdeYqu5s&o{8Y6QPwY>9I7DMr zxydwTVg+CG{VBnb;p6 zuH|eQd|=L^xp`t+ZQpw)&nWkdnzHBE*tMKv19OfIJ}_t9#QyQwII$0Q{5dlx_K9^b z_9;*IVoi(nD%PS{XJQR0uTB4GTa*{u^5Rq8eZ}Ww#%En(Csv%Fi5=z)%-E;wIhp2z z9p?PZ*r)6no92TZ=IqVbr|kKh=7SyP+|Jmi?Ae~?gB|9~&)BEzxuE8Q9p=2y*e5<; zH1@%cKj)6dK5=YgpYmcG$1RRYe82I%lvjti{P+x|_}nDy)S0uDu*00E6#JAtbIE+L z!<@ww`^0BA#Xi{a=S-*AC$3xUQ(oQ5D>L?w&(4j{kHt7Ha^2P zE{AI=)6S=b?R;98^J%#j=KR~ZoZoX6ZrO8mtsJg}?HpaWS~y1+<{VwFg*k&aE+;Ub#AVMkwsN=@wlj@k zJJT5EOk=KvIS)B5Cq6$p_Q8%n=PJiO@fpkUnar_2K3vN=%=o~Z+r0L&dsF6$b)3vC z%Q?@v?3vGYEoVN%ocW9o%(>8YTV1VXe!f`dmeG09@tM-GKX$I=tm)V%K6g4kvpV+2 zhif^T8XuT*tzGU+t-~u%j8r?h%D;8qb$l&nVpEQti48M;uRN-wmbvo95$>k5vbbIJ z$*5nA>pwak|L8dSf9czQv`_w?{!?Bb_&se@UYz5z^5Qe@u+tWtp@$vj?7P^f?D=@+ zgB|AFyx1o`e=qjIjz8z}#Xi61jJ~qx`&l_$3)}gAu$}J*bG{$f!ki5lmlK~i82ezy zpK}OfpFesgVO$Q^Ql_0}2-|svu$^ZJmu-vkV)#ez{r{ytU4DE_>womDA@0ij66I^& z80`AAeN*|O+z>acXua|ar;T*~zTscW$*57T<)NP|U$SPL+bn%s`N7MIT*oCVly7J< zN$u!~*@a`VAoeNy zw-3w*JIvoih<(cb-30T&4)gaEVxO{qbHRMD!~89V*r)8@YcL<|Fn`A(_KE-QL+pbc zfBqgs>=VZ-_9-t`aU9}%jO$&x}-%T z-q8&{YNj&pm*5Mo`Da7k(N*bNtjzl*xaL34Ys5Rc;sa+Y^L`2b^1RLsc}G{Fcd;_> zm*D9;pWldgbVt^ksm%K&cetw2Baf2)FxpY3UdbdllGO>a;{IEj_@wsE+3}xa5cewS{`NXPL z=VE1I1#eet#}eXmO@4+lafAQ;@~iWS)uFc(D-$cY#{oN*5UUA(hBC2&9M$K}Uo2*=m1 zle2}ncDS4^{KXmP7SN6z)))V(%=U1d9G8QgGC3zX z_K9^Y_9;)tVvUOR=l5tud2RYf+aiu<+%DzCu)O@a`lJ@zU4x8ThOJIvpRkA2Gi9eMM?4)gcr zW1q5rgWi0w!~AXf*eCwG_OTCk{P}zLvCp=9=v*|v?vTkoZkN~}AFeeYm^QlYrga*_ zvnNdP_Y{1td{Dz8EysLlJD7GXugtifaU9|p#_^BaG;Zs&>i5&%I(X4I|IEbal>4tM z^!q$8T=|?kr}<%(mMfQxpX9HpzD9YwQzrQ7=e(}`(eq>VTIsiWuEh?UoqI7mjQ!;U zUQXpXmG3jBP+6W+$^+)FRQtXqV?2xsI>`MR}*%JfNi{LM>Kd4A=ODJk^TI;=?L z8JEBQ=**w;@mX@_E2%uo@=InH`Y#8)n#vwie&~`yzi8z0RQC1q+if?-pI>`rD$l6>7keyAn{HP#fA-sjzRKDasXRmTXI?hOfBxvQ^k(sY z=z~K4(6m=ld2Z&vk>7gnUn^31p60i_a*RK9$g=b<@o)KVq4)D%N#z-uuPNm(ow+Ps zDSZ3;h5oL>W$9jW?IrIO`Ys=>NadNEKd{{xzi8^Rw1@b7BeB|d)+?zzXY*UhwTG== zk;?NozuOgK{E%_W(tnD5om|^t&MT=rfAc$t&m)tUr56hq%e4)TI@T%v_|`3GH;^4tmPW*pIe+z>Ex?VtXN zBLCK+HQFaXT{Y4F^3p2p!yUGo7VYEY3sx&JEd&ntJB%*e5QMm z|53`PPu~90M1R=iRoaJtsyfM+ytG>TZBZ}zdk0cJee(Pl#b@Pe?YE2WE%F6RS8M;A z*|W&Eov=##@YrgT{5Q*2YyV6nwhiQ3`s62a?a4)}v=28IpU$tY)_!}WTpMdw+)rYy zi~Grj6{l%mdgJAh@;9XP@A~BrTs+iaN9)WEV~>5@>PdR-!*vF!-F&da*khkJ=1x`r z&j$}xyZK;;vBy5QRO+w(b+;I&cJsjwW6$;Nt-QR?WLF@}xOi1KzBcy1Zpkq9pWAtw zyHFVadBX9vahbce9H?XG<*TQ;>cWhdmxRB*{eB%6CtW<%Z4^esPZn<8<3W8Ue*EfG zcS`jEIu=GWpXQnfqv6Aax7zZ4?c4V>p6V(Jqr-O#@3yGF_U&g+oaU+sqsdEz+kVnl z`|9pTO?4LuqpQ0LA2_YQ_SMHvnCA8rMpqXJH(T3R``*6~pX!blrceGTT)(Kl_Pr+J zQ%4w`OoZ=#x3Bi4o5kl=VfxsO!f~vg{eHa0?V1~k98BEcIEE*lR;aPM@#(1!CRXrH z=Zx1_ReEi*>sxc2#^(8K-KHuND|p%i<26DL% z6wReEn2qVg+AZI9_9Q-{8s0#0p-vc#OvCoolBm z6D#=8G2=B>PY#-_OswEICc}>{(fIUkH&N~MRbqu5#vc0=x6S-7TrKfgKS!@UXS3<< zq}L`Z|Kqfo?xkl&DtGKt{Ht=fmNM;H*sg``T9|9&ayGuzP0KuNC;6M3t*=$yY^SN} zWB&NS<^$t1f5}bSj!P=e_|>%!?RveIbH(Qq-Gkff-}lTfcx9~m*tPh;<^$ss``0)! z8~dyK3|G7PV282CKCzC)KCzC)jE+$bnil(02m38z0&~A{orxiK;u*&$Zr|V2F7cR( z$6BmEv3A8e8Efo0$2Q<^=;T-4JH_pGOg-h<3nn=1)YI%R_SmQPssq)(<@saX?Apzh z^KXxG!~6A9p0>*f_wI#DmFIsjOs}%*f6VGm8HdQz{k64InUlV$Nh5A^BSN1yUcaBchtX&ly}b;Yy7QU z;_@kz-?B1cD-*UdVJj21GGW@Zb*&M+2g_fbliZJT+WOD>U1G@Z{@=94@98HWuh~w^ zzxs!9?#0(uYQMVj>rrm|W42d&(Zy5TeqVf{_KrP^-LcJQC|@yTiaT`n1m&Mwj#nn; zFg|cupZMDNx5_JL$JbYCIn<|b_4y^NvsP_Y=$5U@m+*{RFn6>vb6^-Bo?rNEcl=W& zti|?gK3bXQ7ktMylhi)-_Ob4bHzx6JGe5~?%rgu7h%Sx@qAGoQ2^?H*}gT(VN^*S}Qg9yn{d_Pw``8>3}XzLiOxDf7xM zlS^2~Jy>n5t6O_Y3D3|UJ{aQ$yf(jtIdGqiqusxUm6Y%dJ$n6U_s`Gfl(7C9bYaEo5}mh z-?J8`9j6L!zvL5bmzDdDc1?w`zb4%CaVcNgrDF3!S8eSN+D4x)8}0gw9iPf#KS=Df z<7Z-jXvHVI$Ic(J-)Of`n07o=m@!KmF=pfTipO%?c8qKM8Q1Z(@pzA~J$Y7jZR@K~ zn(n&)yQ;QtD>uVor`@sNH+pNGZ=czHrn~L+Ep#qAa&^YEJB$xw8J}K7RdlU-e(?-t z-m$G?g_b%T?=ln-sF;kf_3*$pM z_|(6?qPFS6Ba4-3M|j*e+iRP)|8ANx?GATozm3j&AGv&{Tf2J|z4oftW~iNZH#_BE zZ+KHhoe#H=GGY1veE+uFtG&~PY0B8)Sd-&+k2N`N_q`W9qS|=s=;;ooec=(e69vnSS$8wD} z)0Jr>cx1mdI^M5qU#v_YfUkORvHBl$^h{;^;dc&xR>yvue8%(vc$*97=@>t@`E+I4 z6ka@Vwd%kRR~IYOcJPNkJg)Y_`ZJZW!-HR5qGNpGBN@}~@UAD%)3JQYsneBdQ+WBg zt987;cvZ17Z3myT@^Q5{IAo?faQ+esdjwKPP=1&`}lb}-cLVex-xAF@6l|v z+V7DvVeIftm)u;yxNi2~aQDiaxkuq0ejcuN<`QOyvBy4bCvVQ*i_G_|Fi-8~gB`{m z`|Nl5L;733-(0nu4|W)P?6a}So9aKY?Ht$Yt!;DsRxg>)-#6$b69br{}dto!`4O3GCyjdGt< zT%z@VwV~vpMRAVH;abYHYhk+F0$x43Pw<>?Z>!D=kBN6 z;qlS#$Hpfp_nK6!<#=Kro+^3 zKG_TtIz`AQkr*n6U0Yvph)Y}dkeEo|4qTpO3O-Bxq7{B}=2?5h4$q=icKsirY8t8{dC0 zSns9brPJKhG2N7px_Y`Bv~-;E^9_q!gSBIoHy=F3J#fo|$|Fu2?~c3pR^_FqPta?L z71v^i%}yN54rAwc@v+~vYk#Xg_*i{l>Jyh!UY+AIdmlbNhqhGyW|CXE*C^#Fk5AS6 zqD=0Ka_qO_`;E)*eEHZMbENyHPH-@DX86^shvitSUUbZOW#(h>7rjR6Z#~*~ylb*y zRE{~=Nl#|X+zg(5^_U!Ut##*2P-dM4pF4DDjyY8e`8F129tH3H;m90&k(Uk2n7v4N zQk^k5=2SN{ouJG*3og2BXpTA6_eYFZX1)Y(++j?PIns4*f->tP_?GkJcg23C_`uA0 z;2u@S)Af3rhh*@ zzr!hWJa+nz*D2dmwDu)`z79{Y5Z{zLsI zw3(!K^T7^dk9}Uaa)$a3>oP#?=7Sx^9{cQ?_v+tkN`JMR4|W)P?9=|}jq2Za&SbTl z4|W)P?9=YhkJSIH$EK*=e6YjVW1r&9GwuEIoS|wrAM7yp*k{VO+5J{Kc81!`2Rn>C z_USqxi)V{wkN{k!m*|>@fD&C+l5Eg z9EUiDas1=9i`zZ!GjV^5`|4%GtEBX|+G`*7>uYCx`OAeKJM}a>j6L=l)Uu*p`^$I3 z{rxvRT0%M9o*kw>=8q3-J}^GlZ@z7cPF{2DC_kdoJGz#v{q?Y4m2=$Sr*#eT$u3#> zb}e=od+gKoiQ9E9wAt+={3AQ{Q{KDH81*rKd|>l|@oCfXNS%)@Y(3n6`oIIq-CrK{ zt8&)$?5kzovC|B-+qKwX?6J>2TU@XH%Rij$4;?&C@1@P|bJfTE@qx_;#^-`2y|fPb zF~z>ksrxAJ`T3k*mDB&oMJ2@i`{y&eU5g#Y9{Wrjy{)!a`)lPqjmQT({@8aP_hkv~ zGVFpmzVb(vbU*Qyhi5DEJc8qLo~uwz%UoJzs@km_>@fD&=l#yFYn>~fJ4Nm0gB`{m z`#f>p8|q)r6|3ERu*2A6pT*0z)0n%FncaM_!`Ne=w%6~b{;L;{QoH$Jhq1>#UvIr! z>+|fTncaM_!`NfK_L%HldWCn#d6@Qs<8oqqJRaj~v+QyBK zZ+*S;5f3Mg@2_#4a@T`h;~_g=t6Z;NLF4ARjP z)V^TI;idkU|9DtwIdgg(T3Y^3#~)JqyIV9pxU@cx-E~lDJ^#J+L8bLS_q_x4zV^QO z(b9V?%iQm=#Wyd&&i$rW-lEL??pXO&W$yRM&bKLZzg^NU%G__qg|{nnza@9wq0If> z_HD-8Z>>Gg{nPH3zG`uREk3Zt4Yqi~ z7H8Pv4_mvy)?To+BW&#pTf4*7A7JYzu=O9<`W0;b4Q}>!^~A>AweX?iH*By=WLnSxO?UFiiwT8oi}{%Y}}o_xS`f7mU#{4)^IgM#ngOMeQ*<#^Lpag*wLJ>c5QEF%Ca^ z{AeBH@O_;|=@^G!8a`6TIDFXr5&GPL`>hyWYG1x_SgHS{1BaECb7se(rRCrB%8=6E z-FW(t()z6U*Wl86elvS;Y5i*z4lcbf>}VRli$7WiQw|ykQ$E@V^Sfv!OnuN&n0lhI zF!e`!VeX4(4b1(Toj903@v(A4$b-+7IPf!|&pc*1?p62Evq&Hp2Wanh8@Mv=pYEXe>6HohH;%xOH{#H-zhoSy)dl}P?cE8rX!~wSWz!o>y;t5-vVT(U( z?E+hS!PbtjwJ&V#4qJbKt)IZwe_-oZu=O|C`XLsId9*0Zp!b75Qm!nQ7kZM_WJIvTe1 zHEio{m^py0?`)lp-PZ50t?OZ1@5A;U0H$47ui4nQaf&{`*vpPb?52~j=_hQu3Y*@- zro*u5Gi%VKg zW8=}Dt!2lf*==m{T*k-j#`e56JO1#d`CF0B<^HG4->je0cGmx48yB#R7ud!TY~u^I zaR=LYgl(L{Hhy6n*RYLu*mM9keSl3jVAB)WbOtv4fq9OgOJ-;Mn*aagb*_y^n=h`-GPVS7&n+xsin-fO}3z6-YZV6eR(gYCT;%skNEe{Om&dabTyZ2nAqY+eo9 zd>giTIBfHC*ye$-z0Zg3JwI&k|6$t~fNj43wtWQH_7`B=cYtj_0%nX@J2FP>JvPrc zdymaC&fa75jI;OHJmc&=HqSVFk8SgF%C~ttZ1Y3d=8dq;Ct;gs!Z!beZC(o7d=<8N zENt^z*yg>k&4*!|C&M;>hHYLA+k6|gc{m);&l!U@?u?lOGX~9W-07W>`3m8`bMG9k ze9mVV_&cr{puBMOO8?{Pp30rxshMwgK?mhir=OhXAD3d||H1fj4NMu71ylBURi}@I z`AxAqvx~nn{!&hYopPjnWy+U-%KWDMKV^PXu2JSU_5jC;7{`g@M~pqgx)5WJaUKzy>jl-0IaGhlf!JKHz!)E2 zXgAj@F#2K+v||j+ff&b+IS^xw8au8})gRZVz&LhIe6fD;TE!;T6=LjxW}IRjq8)pN z^N1Mxs;L+K)jnVxlNv|UH_R*SXu}+T_r66+e{w_o5t>&J1| zC))(>pZSfqow!QiGk3yFNztVf0Sn)L}*9aadF-%GnM2z_{7h=qXFT`lW_Yk8mUV|88U@XKK8|MzO zxkj-L(XRLljQ-dwHI5QrU~`QEn`;ypb1K&eY_3sYbBzKka~GuKQ0=%TRexNQ0%J}k zhrpOqlh>pfk4ZC5vG&Y$nQ-pRb)j9Y7ySjsoH$ljB8TZF{fr; z1lQ32?;QU-cmGLqr`_W;`uXp^rmW}xjr&^su?s>ok!xSKpA~rGwK+U;dYZsz_c)qT z7Vj1~{@6dJvdvZqys*U-lkyT+v6+LyW$74PuOeu@GZy%z+s9HH{rK{!|l(YT{E(UaA=n z)r^yB#!vs5vrg=5*h@{l=udGBN=}R;u#yww3#{bCyaJ;Q-$Q@&#cL2_3}yTRV{Gld zhMI{!iXQ)a4pI7m`wVI&_QbqLtLG)$qXovE{ZF1l@H||*%M-x?JP#wr^CX^!5#u=% z&%=n-^DtsOm*SZlv8o%0)$=f7C5AW;BSx)N&iO?VtLI_WjyY6+%z+r=U=G9>A76;o z^Dtuc#TbFb86ck1xb% z!}k!QFXljuF)#;Wb?y+Wb7!`TF`4~E4#YTiO?)wTXjg1v?hs=SG~*O=hjw-D{>J$` zcdA{}2QhbQ98KTE+@T$9nB#Apzn?u3V+_oJSg8wpCotB9I*Id(7&(s^&#idoM2zQF z)Ck0QZbj`tjOSK-AvWuYz-B!W>kVUIEcC(Hc;^2bM|`f~svXa@h|wQ)2{FdOb1-6z zue=1toXUFw<9L*71jcbHIRwU>N?ii0XMT)>+NSXrXMVI}PECAq<~QdRXMV((Q!`F+ z=0`i`M4kK_M|=)d>lJ5yv|~;js~ShsH*w}iJJyOd|BWL)hYE~2HS@x?^Mx4aRGmi^ zqd#JG9uZ@IFg{`&3-%N-js;(c(T49KMqj)JG0qFdLX5F-9uZ@H?5S$Uv8w*qQ^Xht zYeS6jvCoJxr}Cb_m=k-1cFc)AMT|Ld9uceaXts-aH2ZT+95Ih*$DEqHVjj_szM650 zc|<$r#Cb%FIW_f)c|^N9k7^vO0WsEuwIRlwSTkbm0rn0t=G4p!*Up{BE_!YD7risb z`FFmQ9%BDB>+OGZzO*dXxvQPoX7pCt?IeS3rnU#P=q!}k!QFJ6NfV_+=A7`tG( zD{B#BPQ@1#eM^JPb)j9Y7yV7DjyX{e5#xNJ9wJ5!M*T#L`vU4JV%#rKZxN#g;|np`@IA!ni`O8=7#IsN#{Tyl z^7lNW>6_TUus`blg;?Fc5UcwaV$|R=9g0-r5%3T8JM zEpV9*uJrl(_5xpyilE9%V8uq2_XJjasd5d+m`V()#1dGEO>2a$UW;}mC))8WU_d+O zQ2j9nVvK`15Mz9NAx0a%hZub^2V#tYu@GZy%z@Zkmulx4f3AsR(!@7u@|rZ`F=@tW z(v06!KDTGk-|-}&U9A`W1;$=#`h)RJ=&$6&yaJ<58IQo|i`SqJ#?Z{m|1n>~`y`9c z{#c_H=T%A)_O1DmeAfB|ft}u*;p=b32|T<{Aye72odmx2hM4e$G0=wZAx2-k1~JCK zScoyUdwhzxPl`DeyWl$76@P)zUx`D}ALA(T1;+TwOJK~YyeBZ`RIU*ib1Ja}#+*tH zfz7#9J81kt6NhTzQ%zo~84uNrlWN9KUzF@C?vr9pO}*%^_5tIV%ynUWfiWl6hIY(} zH6zBH*bBs%Q!_8PK1~7Tb49;!ei7r^!FflF^N#BQF|G$(Cx~&K;0rO@@IA!ni`O8= z7#IsN#zx*D#+w)X(oQ(gmZ}h zDQ8)M&EIheY(D=BjNd8YcR}cj-!*>}xn*c(z17;C_b~_gLHq5#v6H`y*o9A93GAjQb|;r--pu+-DKv-j4e(V%+m_ zUq*~)1U!czHt*Nsa{<~hhw6_x5Mvz7ff(cC3$b~>7TCOB3vAx61;+7X4)izIrP}d) zrTTNsfj&5PO?;CkuQ(T>5B5MaPH~PxJN69EA%EkD^OagJ`U{M`)bt1Ao6uj$iFpM^ z8|L^MN1U$&#u%D;;oAAaeNDT^saUfQ{(C+#pCA6Wolo$4Eu3pypZFaOV)MQxu=>3g z+Rgi#u$%WafzA7xz~+5T@W{Nc32ffi{=M&}+@HbwG}uqPH-s<5Xv6Oh&3*oVz3-;w zoraJ9>ZH;`)G&>1|F6)=f1exq`<%vq%5x*y`O3`5pz7zffA*Xgcw5ax_&n^Gz5dM21n6nN2wc#1E)7H#+*V)Vsp5MvCCg&1QWzwn?aV$7-7#rHpGSNu(? zzY<4ajHARC7~?B1fib7@p1_z>$ssW2RALE?Ih7m&D{+G~cCPU^Y2uhP@lBe%%KaBP z9+PIACe8RwMJsIBV6F@8YQ5-B&2?cMfib71Z}e}ub~fO^ucQp<9IP9VypvmA;w%d2E){FiW?bu7qff(ax`i6Oh9c}pD-#B7T3XCx{^MY$q*m1u8 z`#j?Os`F@`>wh_@^aSS?=Mj5?>k8))v3Y%}8uCBNLDbJpD^3aC;q!Qi@p(LaP7g6Y zr-#q)A;#zT@VP$3_*@^p5Tgy>LyW$74PuOeu@GZyd`=Rv`FTRF+7*A3>aWBR*!(=9 zz!)F*BlIypPbjeYc|w8B&l3uaIh7m&EBy_^=Opo3#g5N^s{Z16OSEH7O?>fuCfd=a z8IO3L6YUrSVoS0W&wBdW`kG^;fVvM1TUto;= z@AD-1d`tEJnCD5f^Mz|t{Z10sBx0OXT$6}#u5nEw#x;Oz5;3j~T$6}#z2KTejOzv0 zBw}1IxF!+fdQrG0?wP7@m(G zVs#!7<2?Sm7l{7+U+o3BCb6G5U;k}=inWcr(X8$NNNvH|PJJvVv;{F~8VnCMy*DBb z8C4vdehy@aH*EBVQy+H<99_#6-lp6WSoukme{=Lv-Y1Hmz{+(*xn5u;oBox`z$bChkeA@7!UiX%`+f; zVMM9Z#YBv;w&M*0iWio+yD0#E?z(M2`}bv@u&7NNf_TSA2N+O%wZK&xejwwb(gnt! z`0u}QRul9?jMw4yh%p|W_KU zIG9I`k3ZGC_`W(GyiOe_##6_Sc|=eD)`fP1xi0i4=DIMBz~=Y@oAU~69uJu7!f^_W zd9Yt-H`k@wv0l|5`yepp!9JqDxo>J-?5Du^zB(SfP8}!4!|`Jt)8ZkbF2oLR2k&u)D7{0#yJwU6ee#qR{J);NNn+~_Z^!JqhV^vCzn4>4Yc*CWPw7#A`Ar{+`a zM71maMDDPY#xum=5Y#a9>2imx>P&XtNLRf1UC0aU~}ID#`-WH#=yEUA7bnW=0l8qQpd0M zZ${-ussA`n;rM>-H7Q2KpU*n;!||JpN8V22`42of+An>LCdCceo<}rgZX3)e0O)i1WV-P;dm~m|4T4l@?l`*S!tVQ+5 z8r3*hyBZ&RBCb`&%#|^luN6H6ZEv@F;GFzjONiAqhFD#Dh}AWTSY4}#&1;DxHm@at z)isZH^I8&ioKKu%vt4ipF|Ki36XrOAYlzKjN!ZP6NnrC@V(4RDO9GqMlECU(LLYUF zY5WOdbxk5x*D7Ll4I@_9He&NQ0kKk--~wWEU8)_qFR-}}0-O6Iu(@vnoBJuSxzA#3 z=Kc$8o)>}D`EvQukmK6J+{g1lU|f@x>Ht?bg6oZ=UEzpW!`1pX;0i~?+D5Fd`M=kS z^(L-0uQze6${n-6;FLLz;F>wU;2`ETuQ&6xe>sc($Y11$1{3p`k=I}zGx8cVF+r0{ zU^B0Uk9ln3S~IUzyWkF9t8&U52Wwa3V^74jW?q}G6}$#*Z?}468QSj4W)r$RCC;<1 z8^$#K&QhMFkvfHL8$ORJz}vo@PqNnCH|&_;&O5)VPqs!pH7pq8!;_kxF`T;c%FwZ) zFCV$7%HfV9-y2Rp_2hSdTr!>v`f3=|%!O}@j$|hv{W1*MYRT7sO=iJuEy>)ik6Feh z#tJpGAtk09Ws^tbGWx-ev}~}9)j#=#mFrl5>{!>EZSb_=`!bwJr(|Dt$ir6%6<~G_{svIWnQK1(-@sH~dH|Pjt^dlOG4& zN!r*-B=Oo~Qu}O2GO=11$$6MbO44Lf>wGvVUF`sATxch`)Pj)TvlkP7^^~&avkWEQ z|6-Nz9T7O~wli;fB1zzeUw`KkMm#qH$w7v2{;L{t+lE)jL3rrRaBE>4_ z5be2IbKd^!|JKhzxE{3YP}N4X|I5>CcUyOSQ>U3fFgxvbAVAF?vmg1>8($~=GT$gh6)S;fnDSyqE$B-ep4 z!}NSMV}2=8{#_zl^FsOTmm8wom#)dC%<<+cOI0F6-H#Z{bkOmuL&Hh<*(2etJPY%5 zPRXw=*9mxO>wE#G%JRGI5a;@3%CHG<}dp8ioF1>mM{DkGnl4 zeU{u}Z_BnOVTG)qOyB)1VMGVAQ!IE-u`UjUZWTFHi% z8%Q38ej?AU&a<}{dXp7jE|PPl-?EiOyAeCxdNO^SJugtB1NoEEowSWp8EiUS-HTS9hK`WEgv2wKz#{ z<xN{vjZ5r(GTF(@?}l^UT*?HkJH_7TQD zz4ZTwZvS`A{!i^4+PQXEJ%k*(9spUFE*dfljv{Xoyx^&_&cY|gk%bMM;N`YOWN7Rp zvU%_iQcHK7JPC~_e9%pDx4|<~?CCVJdCxAww_8JtRSD#L$I0Y4xWT5Dvx#N3qNMsu zUjXMs@-T3qp=T#O{5Uy}j9*>RIAM_q*ogPu@JV z9hp6T6UmPZ;ImAx4gJEllH50XUjNUqh@N@d$@;!J?)_ztvD(I6Wcpceu0K|d?d!0Y zoc40z?}MzxbW7g2s)?+QOJIKM z3-S)H)5zxz6svTyK&3qx>Orn=Ko2)ejMlEt0WDqG%L38I_1N5=EoP^$D}FMo=`0>_|$$ z8bQ%0(miDw)(DD5k^brNSR*JJWzg!dc7AU(zfUSW3jo9VEW@wBhh$ZlFLWIoObX{c zB6i!{q3@spr2OP3HdE5@%sx>a>O$--v1_f+xj)B7iDwMYdQ^PN;LbEfZMJF3@uyf#fQESPzxwhc!?9Lw^8cKqW*ufNE zKR)Pm0NMW99t_@kJ~n!qAw*XItlsJQq_;;>lNvd~j(GumpXVdv>9J0b{K|`0dDxI$ z->Q6$4RPT~u8HhQwhLq|wB+w^9$*>vuF&+-Q?}PKo874D21PHPW^n2Yv*=X_Qg)`W z`Q;pV<3;YUxYZE$s)Re=b;<+EcJ*hQ%K34xPo8jL=M-bZ(t19sxHn9gayFvvcRfGe z+y~;qpBQ#c4d5Rq`@+`8kz{td7x&xi2d(BO5*Hg6Uh}>`wC`|`WcRh?qg{3Ia6&fG z4SmWkR@XzX(qGAj)~8vcL4~1GQwP{wD1|**6$rI!xr58=L2PTnvK?7P z!RwX|w!BeD-wXch@ok%x_9sW>I3TDJ%5Hb zsC)PEa$cbB-51VyfVy{wHFXDd?@qqy2I}7JmFEiT-aXaD6>AiG_xGJHSfkjxM;n~6 zMzMDX9&^MR#olddUI1$pdw0MOd#q7#|4fn{)+o4N%*PgM6x@H5VvRKl?)R)_g*6K9 zw|iiLH45(E%l#v{Kj!66$$jGZU2=bE%ooZ1Z3!PG_a`lTC%GTKEl+a4=Ji*S`&tdx z&Tn*Z5NuP{&88LUhV4^IK+H`qIQX(5xt~)KHl{g&-|z(_zd~sUEB%Y?*_=jv63W1c zs9R*yt;ZznURfBkWFNUb%nCYI4S`ZY)5&e6mx*)BLAenjB;LXo&OHtV|Eco~?k;+8 zq!r-Wr@Yi>pY_mUK}C3xZ^cHg@rTVXE5Y5bJy=#v53s9U1*RvauqeF)3||%o*26Eb z@$Wv6x9_UL#^-OCcjzTDreOrQ#M^OQ&PGx&#Q-e8otNn{glzdrpv)IPKKf-rQl}|} zkPCX=KcBuS{aycGiNTO&u6>_Bs3Ne}ma}s0(w-oMacaePdPk*Mk8Amomp5j=Ys)0|;K+g1vk0$$NHf z2>O=~jH?#}@ByijkUgtv>Q3*%ysv8`0LO!d-`#b*W3MQvTe&*V-)iIns*xU;04%ETC2}Wb!{TRVh(})EdAA5F`oNaTkz2t0m&32Nr6VA4goDFE# zT5>kdGDdQ?vy%(Akesc(rJ3aH>AKO9v&QF5BxjqBYAiXs@>e6t*>Q9Jk(}LL zDN=IwKzako*&;3LOU}mKsVg~~|Gtjo>|pmglCzKY)smd;UcIK|Y=P6tT$?$&sdY8U zS-X6YoZY*SNX|Oz43e{%8^a}Mqia`{oUQw`isbCA;gzvQv0s<^Q4wnt`?dY73Rt7q zud7xlk2Q+@y2kl(Sfkjlw>1mF8pVEXcdIPcDE8}FZ_8kfV!zgEuXcW0KpPl(D*y&W zUo<2xZVPRay})r>Bf{RdgHvstph<^C$~mC}Tt4)JxSc*m)@|+x>u%m8XI?xdy{$S! zF~e^1G0qx_cI*O6?52>Kh1}r5;jWN;qZny<(HHi+cZWzm!thUPJJQOt zKe6+!=g8+d17M_W0X{up6&e3*AQbcU>`@5^T6h!(@4gwBTtMHpD`T_eD4oeQtNa}LuN7zMj)TkvYvQ`v^@u~6df zUFK8pK66hS4ep%|v+4&ec%1K8IO92+&HLlRzYdFo??F{r$Uq-HKXV*(DY?$Lz^LQ@ zl%4=x{_Krt@KDe7@e|?PpYMiMul%{q;7MTFx(j)p7Y__qVfLVX_B+g<|IhY7R{X@Is2g449VFly{1df#_ygcIa|qkn&hlQlc|!k zhmzwZXBXd?A~~BKG(~du%Babbv#X9wlAJwhF-dZ^ck%?u*~Q`GC1=-U#YxUOwjC=u z+w;L_$=R1*VkKwW`ov1kW*#0XIor6-2+7%x=Z8to&g(E#a`v6|5XspU%LYl#ekn3g za`y1H{*tq#K|jga&{usVXHSjpEje2#zo+Evhr}L|vqi$XOU{`t4 zNzRV^)KPL)tG(L!T^u+au00HZFK4n04KGcHBg*IErs<7ILgWmnzOo>cO-La1GiN}L zKQ?fKZ6g-V65z=04`f@L3*_*%1bEMGl3y>Mk^yaI!nYYlQu1d$(chT~Jtr+CHD@|P zX6IQjs8~O;{=PemeKZR;E8k7TzVd|vWL$ayE<~HZ6STA3Y2kGzWO= zg~n&!bl~}64zy|F!}PQKVE@Ru@Xfj#yS~!{qQB3DjFk)7%Lz{KZd@W%`f-r`46%eI z7D-^S>Kb#;dO;daO#&MS<-Yl`Ok(da5A5$*^Rlyck(;yU!4ie1!Sm*j!>-9tF~p14 z-llvfwjdd<5Ax@m^K8f*pZQR{lb#P>-N7(w#e7K3({sNVo*EOl0Ky9C_)*_ru!D{mDvDCq%JKlEfdLsx@kF+a$%4Pf;1Y6#2JLA$_} z#zmvoNZsg=v`*^A;(KeQZp4&WD|KUQpA@MZ-}bJNy0OJ}jns|t(W|9y1TS1Ab;BuV zrPPharB+JaXfS4l)D8Dz%cX8aSTC2lQKr!{sT(y{FO|A+>g5ut8$UvqNZlwseDQzj z#_vT^H;N@LlDg61?n0>>x}b$pHwO1!Aa&!&p7~NY2HMP*x>2WTveb=t^XEz3xO_87 z>V|vCB&i$DqZ6fW+)SG*b>olaT&WvxBIiimuw6A<>c*@Wv!reuD>qB(M&8hwQa5)0 zN|3st)qm~$W(B3d#DY2)S2e@%Dk}w+UG##q*hunb+*-)l=marW7LbRf*TJ=npQM%F zQF7_pI{0)dhlI3!LXJ*a4^fZyl4kp@V1LL4*h{C8*m|z8BYOiJBxOmLQogWl>PD#6 zaJJ!qUJpAfY=Xuot&GL;^sxWVCfHuijvXE84`~UTVOPCA>`tCLWK`J#cH!&TftB`< zdw&c3bje`W3*M8DbGE|89`D$=F`2~Cunj&0+4BV#*OOvTwn6*F?%ZW-e?pSCLzP>htkj*O9+XMCL9AhiuAC1)?+-z7PlTymG>?Bl*WC1)$` z-yu2s&~At1Y-+RZlCwP*ZIhg>e`~Ac?2OV|C1)p(-6A;~b$qkr>~NdSlC#~THc8IL zt=T9!oBwKq(@^6IgU&0wz`ArJ z(tIL^;6Y9hWxI%U4lzNp%}?^P`!Uij#{^{>Ws~cZpOP-qkHD8pyGgSK*3hAH8hkr8 zh3Fo-Li_t^&|zs1A-jB`+uWm2-)+3|cNdlK%E&QTI4aPXwp$P5o*jerb_LnMcYZKq z;c>_xJcJdi;0`luoq#@NHnCobb};$P2`D-D5?ej~4H>=SB!rCo$d-&hPvRP$f;Lkf z_#(p^vgGqA7=GA;zhBvvTwiw@-aq%}KYRZ+L`0u~WsmgSf5-8NUBA!3mqR)p>%ZDq zYWrCz6zjt$R;$7mv^fXw!VB`cwP&$Mw&%gh$C8hkcZm7#KM$)v-)E^mb6K4(7obwM zkyTrj&-%Hf!_H@OS&arRd^t-8?*Wu0eNyg+_0E76yLKCE$Ln~oS0+@k9v=Uxe?i+LBJ=J$a1&68spjf~?$EfSv$>ykW0M zAAW@$DsdSSI@to*wv~~qm!Z+{LNK!CXm)1O708(B2YWhrv!WJPL6@roGG>V}ZsJwJ z)7o8nZmhrXhUDzz$JZriYnHt(IlFM+HObkBhptM_&Ud^jIorF{70FqzWtSyqzvN~~ z&W49%NzPWBa7l9Z*Qtw=v&9@PO3r#jXG+eNU7sO2yZddr5{YVqc2F#UbDI& zIqSUOyyR^CN9QDG?aG{!oNYVctmN#LgJ&dXTNgMZIa{vfY025!OHN77@;fIbXMdGF zDLMOf+zH9q<0p?x&OWz0E;*asC%HztR>TnAFNAiU{2i)>Kl-D!vo>>Ia(%<6Lk zUbTNuuDwqu{a)XIvz2d{1H|_;eGpH!UXH3OK>r*lbuG-is8g z=K;rlW<#UV0c2=zDvm@$PlyJ6*@y z@N7~5%dO`JDT%k?gI6!s;~x*`;C=_l?8R)$Pe<@sd9=3KK$*Z zs%%uvhfsW$8}IXbA}fFDA+#A{&;2f}WA_^{N*Nyrul@+lY$HX`>G>-03MqIi5F$ ze-7Z6A3TLI%l4&)z1H(FJ)gm@q%MY4WA(hyi)YYuvn>fu_UFq7Jcsel&B)D4UflQH zb11WJ4yiNEg(nYx0Ug%vBH#8}bC<6#;L`6*^7YhPHgD`ph^_dNY@c+E75(!PDz>+T zaxV|EQV&mHB zc|t3c-^bjjJP#;!~pCbOC6s}-AHKuOzOs(jZdX+1buiSb)#L?CsH?NjD0M1 zBhvP<)Q!oD9!cHcPaaC$hzouwb>rfo2U0imsrRLBWIElKy0I?ip45%#<#(lSRJfNb zbz@k$T&WuaCf<>{5q{>j)Qye>ZcE*0-0YUrjh-8Fq;9-;mo0T8Ff3c@M&mIzrEa*| z+?2YZ)qm~$+Eji67oBymIwQkS>)snEdq&X>i+@O$*>6FYsGQG37m|VD@8HUapCn=W zQ8N6|J2+4)hXh`ELdGV&hp@1{q|$pUNPrKJ*l{YkG}aYXJ^KJ9y-SnYQNED6;3HJ4 zKHYF4L=V|DKEV#Zg2ow-^zi4^C&(fNm{((eD7*ACqzvlMa#p!RySiT>Dt$eBS;QU^ z-+ckLAd{W0{f?Yj`4xI(yk{;q(uqanHyD4!o-fK-OX%lsaL2)eS1i$+j9U90j!pCD zp{s1j?#4f0<$FEP+w(c%;rAcl>aOSTGRatI(@*gI<--#$gfM9S3%a~7$XhR+&N~13 z1#VTWxO0R3Z2Y$0u-^GG+ZA-1Es6O9d&V7MI~{+somTnK@?kRbF5%2i?aGI~7WLSj z65f1pISZQE{eEro}$@s61Jnyz8wcK%>ymR=$0xDV2ij$rZ>vlI;^8_pUWSKSGd9aHuxNAiRI=ex+ z?8)q26>ECwm@lNiD8`(|TGLt?I+)*OgR$mOYl`>0@O-{B%2r^!=XLOt4OQ=XEm~qj z)q7qw3^r7~=k+w#nyUA_(q>pw^`2Lma@JHmpIcnAqUt@bAw#XGde1A_*NUq5yb_OF zQuUtK#~zkcz2`OE&XTJ4ye4k5pz1v@$CegUz2~*;Q@-TvrHFjV*J*$U5pNzT42_e*lN&d{Hdv-8;x$=TWke@M>ywEZqQdwS(J$=Qt$zDmwMEB{q; z_QB*YlCwL`eU_ZP;`CW^_GF7slC!rqeUzN-^znn_?85L5lCvk`-b>C-wRdL)ZWtI(d^9kQM(B;|Uu&VX70jY+6Wa`q@%_+n;3Lx1;3jU|SlO zo=t|jJ|#`h*wSfZ_K+qn){w2Uqm35ClchUdq3duvnwDIWc+B*L*XQkMhjQ@-?>c%I zQ^cO;z4kQvrRl*Y)}9V5?Zle;`$J-;JsmfEAe%DQ9Xx{^=%n2nSe&IjEFSAX$Ctdw z>Y3gW-^&hkMDPbz(>a~2E>(brezE7H3#}#PClsJ78hLQ9>pjWEYXxXiWxq}sU`-|j zJJOh2%ID~{FC(f>air|Nj_W!tFuu!nr1zBPN)~5^vUTO1Xvv!e`KuK(SpDfvwAv3# z9^rX_-MQmL3s-%_9v-^Q`c!tN52l(}=DOeP!%Syt{4|dRjC1A_?mN>emFuuQ{k^$c zxC?C_on~xUN5{9!b)kNS_u<9A>3N;UF7#;V9mB>&0sI~*NZTH4Mk<%`;<3pE>5q&h zq*wZ@<4-6UtPHg=bsefPPLJEqW9b+ zXTK-7NzQf;b(5SWS+0_^+lRSI&Zhe*fA`+}jM=#p1tn)gdli(NJ#Jr6a@M%rMRK-Y zD;LSx89$w=dY^jTDrc(Rr#9Abrs{oae_Lm&-lwjb>4Y_k`_wH)I$@3CK6PbZC#+H2 zr@mu!#2UqY>iABMSfjX4-QK|wYy5kkdS?NwQQW6q)wBTCDDG3cd~m=T#eM3~We!-Q zxKABi+W~77_o?SSvBw(4J+Gh{_E@91=cNm_#~Q^wuPxW?utssu>*ZKGtWn(avenyR zjpCkHz)@SQQQY$yKh+j%6!*Ne+N+&k$6|%(>zn|1{aJZNd#p0Qlf7WzpT`vJ-Hprh+8G|YUe12IN3M+n1gS`pV8c zKgGVk^QG(W++q6)KV+LL`O!7xC`-NdleHS*N58LH%^qKL;8utHXsh?5*u3~ceCJm` zdhB!vd;Hypw=($CeNT=W%LM88_p$!eFn@09mQQ-V#Nu5>6GmLFJpB-}4(@PGXaPnja)-g&?KOORe&;fiJ)Q#Y;g{5vdEiWu};{X(vy3zi=Ug}2WS$e4( ztIO-9Zj8LFle+O_xK8SZU4TyNhV`icsT+NI2T0xcc zAfRf&^F;8;&Hw(wTN{B@0kmU zdte|TkW9OxMH-g{UsLs=MCw3r5N=q_L0TZx2%JcHrH=tRa>Yi__>4 z9{l9_Zluli;&k;Xe?DwdzF}W*5H;lM`JaR75w25$=Y!9yQmC} zerN-8KW<|`UX`KowuQj$%2@Wec3IlHvmbn?eyrqF1%FbWO&YS?IN)?y$=Qa{A(FE_ zzXeOq)>{!QIs29dOU^ESP*!qw(Co63vpE&YO3v=SQbuyN$jCC1vo&>PBxkFgE-g8` zzE5e%*{Y7EC1*o-m6DugtxHMH{`y@~a@HrMq~vU9?UItSN%kcrXSZJ}Avt?4wuI#D z7XK2Gv&~FFlC$5t1WC?bb_|l7g+0Y3XWg3@mzb~C#>gPw2Qs;x|xK&Qj0Tz;@fg$wnp`XNS;!)CiR0y@~m_s@zJ|S;1Lg)m# zmt?0~!PMgA==$kX$(5n5;4`)yot9IY^y%meTe8a0Pm>c2dCHk1tW+qi`_#c$C{qtd z$A{7vPwbgzq(9WT7D`(w`}mzqcQ{eDJe_N`o<&Wz2RgYteLpXQjShTI_T4N`ryqXD zZk^8{r9&&w*jDyDyy$wec4`G0n&r+9&F)8v-L60<_wwhZ_c)Lp6)RGkOg&EubvA@2 zRHUU{^n7pI8O9@bE7D!He0k8m(yVe=B^oo$mCsr|l`WiIiPryQ#ede_%kDg=M4KFZ z!mLZ?F!zYcGRwJ=84eqdzB`t8`eI8e)Z%_Qg&Rne+u9y z=T)IwpTr+3^-Hh(eVZyY<@g0diMIjVr&<`TSU8gCa+POW7lhHUg9}K+bthi$MHtP$ zokp^4ezC?is?t9No{-^(b6B%QRq4R3R^V}AFKhLxDlOd86_V;sV;yRR)6lxU@VQG_ zHfd%!jh(B5SjQd44VS|OPaSU--x%M_AUT`zJwkGJ(#irp9Oa`xp_Wo+i(0ckg?s^n~(zN+Nx=rduGv$=i4Bxi>@g-Oo#-Cad;_H&ymlC$CY zl_h7JudOUO+ow)t$=M4Il_h7NWL1)!wH{MRa`s_BCCS-2M=DCrR_<0&a@NVYqU7wT zy%i*98@H$+IeX-DdCA$kE6YpH-mX_(a<=A+P|4Y=vqB|jGeScpXIp2Nlbl^Xp`7IG zfgbW^?cyxm~OpjoN6-`L8XccaLf`+{cw$rc5VaHddpN zb-a0IrMe{HSvA_DZ~#wre`oM7Q=J}6(ephHr42j!Ri}MU=(%&UyOHjwPPfMe@TW0P zjOX*J)3j6G{P(r$ta%GEZCFiens|gADfXM)995IHJ+_jCwk^P0rPicntcJ6ccZK+s?=|VwJ*Amr zeP7-LYSE5!4;$Mx*739BYSFc~Tc=L`p*+))R*U-GpKKUVOV4-b*P@#n79@_|{#;+H zHf_+MEvX*s$!ATeO|ui{5$~DK{QJq;bbOtCWJ;_RA7ERD21Z^c&+fct&+FHr>AE~} zu<~U#D4`BLv&ssZHrmH5FVvx@mpa3Q>GRkcr@C}xPfv(@-Gc*kMb);_WKU-VshHwAcQa83c*Ot1meorl_8|B;8lDaX}qL$Q+ zIqQ_aZ)pDAvGsLpO5Lz=tSNP)$dwvWH>!=TA$3EquOW5gY?`uW%%AHAb+0aUqrOXZ zsT+ItRg=0gqh&Rz8{fWAsT;nlsniXx22|=s+)I$UQE(1O-LR_wQa9%35UCs2CK9O| zZ;KMC8+NA*Qa5_fG)Udh>c4h=clp<&>+E&#iY-U0g%j^Q&^NJl_w_Ty9AHn-68J z9F%A0N=MSy2R5-i#16>BNZO-)7W2E3M;vZM(o=0dvCjN z+pc-=nDkC$|E+)MuAlzA56Dn$0TBjiPLv1>amu`F+pFQPlnLJ=P%k9{Wxj(}m4aSA>N^+a33*NE=HH(T zEgS=QY~7~x%)O4J`5O=3cSTeBmaig~UmSSn4^3(RrsoJr`^4HtMpM^rd8Ff=EEbaz zO=~;Z!QsfwEaq!8b$DC|mMytGVRt=he+6XIIy3E;(EONi)gW!b!~}XA`P4lbr2*BU*Cy(&%W(*>{1_ zlCyc|no7>L7|>L5_Nhx#$=SPmn@G;~Yu`k2c88_XH}mg%o?YKqa`tY$#*(u&oEl5c zw!a!BIXgNoN^-VM;V8*j%VUisXSeidBsn{&U?a)dSNs2woITO%AIaHD-y$VvTdawc zoQ-Z6DLH%aRYS?y$hi$AXKPh#C^?&PtAXUK>*NNKvt^1mkesb~y1wM>+FA7_XSLd^ zonO1a=5+pt0BH0f-B4y^bK2mj7p&E&s6jY;bQc)@AymCrj~sn?agIQv$6YL#jqgH5EG0qdRMo9W%Un$LSqt z=j}K!=r8Slx*V?y7^+s}32jr*{%O#lIU|sZ|%r+34S$C1=a0be5dWsnuC> zcGA;MlCy2*b&{Mt8P-X1cKOYYlCzFuJ4((57wsrHTlzu=$=SIBJ4ntJaqS>E>$ktX z;7hP*BIlFIMTgln^fo&yc>G3v_vyXbV zk(}kOZ6s$)9&9Z+`zxlk6|BdDe1Y}}a^lCyVaw~(CGYOi*Frxx!_t6m9!E2x{7uwsvbz!rFL(ab8ziG0&A4Uiv}PD+;!qW^fPG!!wU= zv_gd%sil>I@V)MIaKq26Q_NX%sYnkxHNcKHAHSKz zcI!b)#k%s40@FzG4LxZ4S>D{~NlkL)Ne}u^`JL_;OTJ1ZV! z-;eGde1$x}@`_z+*pDs zIQqu0{HFbBS-n3jjCW*%X7#64t@U8tWVSK)RDZK>SZ^2@Gf?WrtUm*!ZuDC_KrNizEU^ZyY-d2 z(c(ZKsT=n?_K~_#)TWQr4Z5kf)QuJmdrRFo;L=;_M%MLSQaAF(_maAiS)`ZLjZr6h zO5M=+?kRQSvs+K88(j|dkh&4xriavx%|E(J-8i>aS1o2|`LNBKjf&Y2X~??>THaMxKotNP{2VB*R>v5mV+s8rFR` z>9EimRtF8D%^jzZCiZSHJ8lr&*tr#{8r{lGI7>WTBevM51iVbEO;=KzEl22$jQjJhV>D{=&FK+xy!L> z5!;f6(c5cve2@E1VQlHP22DWZJ7o|pPOk{+CFK}H_&=l)TnXs3+sxw#X`yZod zp}Y&^)%*|4rdccB1*f9$|Hd;_!3kEJ&+6G)++rf6EL$Noc%U$u;lE!DuX3w$K4$yIh!_hkmPJm$w88{ z@6HXBoNbmkP;yqQz1sO*8#snu`5FKlJEt2ujT}R}Uho3_?S{lBeGJV@cY-TJ7m&;% zW9f+QzsRJ;X=K8vvGnthTZAopOv+}ArIrWxk@TikaJgt4b?!Qy)Xpym!(-#<_r~SO z7CT>X%Z#J99?m!PETr7CFE))4LcyUz$kI+4}KYFLdmp z`y@K$yc@S#Kc20sHi=$7W5ZjdZ)ZLFOrpj6zGU_#uCbB}Cef0`PP4K3U)a+llW5P& z%bC;J0({f+Nwi#GTUK<6C-3JmnLf|XQ~sW90IyViG7a57JJnOUm;I~HWco$F)lh%7 zj-OsInf~q!)K*UrepTaCY^F!`2R!NT?R(61d9U3f=h%5kl^l4wx)17xVu9L z?hqho+>N-qdx-7S#N7h~f&?c7LJXo1><#B}`f`8YU-a2Cncbb9ueP_hx_V``E@~Z5 z1S;qtbnUN)!j>2C)awEZHGeYj7@t!SRT9$qX|;`DXq5uc=o z1v6B+FR#;h^>=!I%T|C~^jK&P<%P9>p#BLuV$oorYPJN*v-rQe81D7_yE)7F8*R7$YvG+m8&=9o_ zbrL3uF(oj_5GOtDEvRQ%Lvg+#wpI2QT!hWgT4RX+oD@F;mvn_8eT{I>aW!Fw%2vsW zsYdAeL`_h<`$~F#qY+++8zktRdCI$AG{VI#N<#c;q-;kc?CIH0m^0mg>ZL~5Ssas} zY!4!(3L{Js*JlsymQQnk7@^~N?`@Xwz$r@nlJ|Bz~Q$ zu)ePePCPUjMs-pVPE9qzvDH_hVxXL0w$TJThWJ2_ylz79MH3vjAQQB%exZCv6Z96p zv$yYhP7P8MT)*Qx2yQ7fu)+k(_x9j6`MA@nA0~KJBF{y=Izu``Oz}#H3g>uoI3+AJ z#igFAoQaJ;|8t`$jt)}es$P!dmmM@0+q%anR3{#fo?> zQx+?HR+_R{u}#gC#fnAsCM;H5O*LV$qNkk+ixs9vOjxWyi3y7pGCfULtmyd6n8k|R zXk!*DKIj{>Skb!Kn8k{Yqm5atxYJ$ii$C?&(rS%ZtSCt{VzFYLtr3eA3K~W%RvejS z#A3y!o<=NIbboHhVntJgA&V6gZW*#zk+jk9e`3WLLl!IQz8J7rk(h75VnwW*0gDyd zXAM}aa9wP`VntAY0~RY{-|4ehp^>N0V#VJv|L^|2XD!|X9aXu6{1VA#!4#z-iroDN ztKfc>DK1~oi-W@sutwet=dWvrx~4S9n`?&3hL6DKz`}aFT5HGeKJ+J${I8Day>4YyH$-lqil|w)MoN0rD|N;B6BQ0s6d@F#5}jt z<_INPG~H2->*Q*VS1W_b#zKZO%{E7^WB1AVTMa0FHpi~BTWO?W4g{)NptExiLB+%k zV7UcK4)+%hIcx1N=mjyP;4Hjlj-K5@7V1cvsRE0Ii;`mFg7C6UG zNmxB@K7AQxi9^zR3py6obY+bte%khvym^7zu2`b$k!O@w_J%I`TVlFK9PKRYD72PZ z;>`=jgeiT6%ik<9sC*Jl|DY^<9c_hLw`}-^zG}j?jaF#r|5e@ilbBC)!wQ!@mw`g9 zfr5UB71qlg1HUKoLXU@5D6i-T3-)&tZg;T8lzGJv?e>XOCt9NyeTJa&LJHnyjk;ys zIE9NoG)LbWt7j;1mAaag6KRdAF$1{?%AM$+0&7%WuEu>X)Z_EtSu?ZY5jM;$>Dn-} z<2Ttbv%f~zFteLlt(n<*h1Se$vxhY^`|`9kGpoG7nwbq&ux4gQf3RX^pYT@9te=?` zGwZe6ika1%X2r}Jb+KY*?H-DK@#l9guRu#?cAcpuGrQ-MB{O?+p(Qh0A#cgdM!&US zX1gROD?a3C*Z2m8EW_CxJIWzk>$efuq(>7;jH?K5jX4k8lGqXyc z&6wFaS!T@a5(hJ8cKu;9X12o$GiLVh*!y??8pztf30XBH@fOJ z7ERkvZlu7K%G%Hu*0$-8DUnB5IS9DhyHQ3l;nAjRORf^qbipMXE#$GXOEA6 zdC>Ex-Gz&X?QzMh{nRf0#y0%6JvuM_!9S=QC_E7CakxUU^yYgt!KBI_FRpNwRNqw< zI5`K*={OZEGn9oI&H>wfjN#>jzJlXn2MqC!g+(Je33%H9?|gU)79A?-wcvo6Uf+R# znM}r24p`9Ii#yz4OVi~XvHrUv_gZT?RdJ5ksk2zubVnh-Y=a}tyQRhna;y2E!;Z}C zipfr_y{(fI^P5}d$o#tdJ2JnYE;%y4&sI4yzqbcFGQT$(9GKtuGzaE)sl5a9n|0KI z`Mm@V%W=Uu`=( z=6CHOJLcDCwjJ|p*~^akUHn44-~QyEPmZ!>eh=%|GQX{x#QW{fJeby4TjqCc`)%g; zbHQ!qx6b`G^Ba5aHuL*n$!+HMjpA+Qw@x(mU;epgzG(1I{`uc=`0xHTw{^s3u|{`& z(Ot=@6i2kUq{t;!uK}MbM;zR}H`hbVQ@Pa32^U@Nz^TlY!qTZuIP+d5q<(t>a$B5G zaZeVkb#H@b+D=$M+Z)W5cIN^;ov>fG^Du3oJa;bB2~{2shA!O)aC1L6;rnJAiP2Y8 zu6G}2yu4RSTHK(o3{9wgrev0mUcXH@8COw+#idn4O`Qdf&t=bt^Ng8OwLP^g3WJ~-F1Y`CKcPp90o>f~ zf?kV7Hzjjm%MBMyR8bYK%4SI>__|;~tC}Ee7^U7Z*9DJ1Ru$5f-1tW|F4%=v5r#e; zLE*Bl*vUaofTx$})+|@-Xw^;FsOw7`ce-L)c?-GT%At|BTv4O;5y_@jQH!4|$~MH) zkyRaq>^xVjJ!?Z>BYO)Db*^}H^m?*cBIdixi~H*Ow(_m51BGdG-0<2tS^gQR2|sqZ zVPgAQNt=P1kgwy0y^MN7`-*{rU4R>==rl?J10Fa6@(FB&ezT zL2U}|sA={b7N2=d`ReXCKfN91hNO|t9(P=5*n?X!)SYhWx#RtMd2W2wQ92Ohj)evT zxRsy#)6*Px?D0gEo7v>Ri}hQW_o_$_)^5@BVD>dPdocTwQ69{`Wt%&*uU+KM>`(S` zXZ8o4b!YZBE_7%1-}D#vXaBSIv)^BEWA>k$yD|Gu_K5HOPkm#r>2Az^nv5H> zUsCSM>^})|W%kX?T$z36)2_^Z;38LMU#Y(g3g+bj$cikl|9ktwGMPxE6cSm^2B#$LqPS33TJoP6F=-e zB=Ov>#!Yec#F+y*9wXJboNQ0@ny)C{g9EsopFJ@r`Z6VI%5in7UT9VlLM4l2INjx5 zcz#J4Y0s>IK^MJn<@Z*aZk-KDUS612(?du)>Os!e_`9NEzrHq3o}j(5@f!= zk%SNT#$yVDg-dgWsjph=ja7$K1^+tY-)MW|ii1kR%`=NgE5I8^?C33MjJQoQ_q>sl z{Gg~g$z=cC8*_d=rC*aOY1CLBbf!D>{75Guagz^5SQ^s$Y5jziw|wxc&p28*Lq&KQ z>Vy3+81w0q#2TmNK6pRApQMjiTd8j+U;N_V6Hd(#YeG%(#YZ=97o)AabNI!RGP?O;rJ%s&weF+CGyKr+ z=RofI^e?>k8b1_vs&NkvYx7Tz`2FkjcaDnw6n|#cwzEGo+v%YnGy5pOkC`2R#gCa) z63_YH8qcC3e#~s*Ctqf^A>Egm)p77;W`7>@WoBbIUuO1dZ(nBi@(Ukk7Gr&w*}XDdNQ;1=RKL(e#<z{PEo6ILI#R$SK(Rqt`qW(6Z>u1tj_7sr+f68KKP0 ze(#U3mU~D-Kd5p!aslYOAx?ThTo<+l1MrJ>D?hJoAXj-f0LQ=CP0PgfNat<`;P(se z^irJP`6&e8fxS6Yvbhz^s{(LK?;7$rR0b+?fw=5N7a{F?C`p^8)FuW)RM3uP05}Qo3vtgh_z~B&XL%J%k{9G2Vx+R(BIz-v!~srAKJ? zFa=?vY%peT>PmIS1BFxw#=%@SzTknHut_r*)ead;#>uG(Ro20nXfy^6Y*!I3Q7}5{ z>qB04KcU0BV06t9bMv%13r77y(E0cyP}u&SdO!$nb@~bh57Wu&PzbI|?#bDmaUvD# z5L6qc$W7ARNFjU(n%fQHs`yv@+Iu1RN>h!?jXS`%dd*X?64^Sd@FnE6$)3}$}& z?+a#rpUwzoe!q1MW`4Ur4q|@$hXgUdS>{2^@BK4D%PLCo(4#USQ)l-Te8<%MdC z`wsuN-c!?3+%Nghde4FT1DW5h(*l{_d7T28-;##`%{#y z`899yXMV$T{Fz^J@@IatkNPvemsa^RzkkQ!zx%hOe<;2$8pI6}Ym)mf2t_qdRrK--BB&!c8YWEx5Q%_TTtWxLdGC^w;kfT^11V=0 z!zuf4{Ln5VT*(Q7zDePz+(S;NA9Nj}--csBii$Ah$#B@zD*}gh6X%tK%_VKqBXH*n zH9>bqj?{H$1STyQBy6&+ytMI+nvhu)iOyTCB^!FG3A_77;oyTKAt6>pXqgp-*{g4W#WPvKa!(Yx zuMURKsWQSi!zeUgQ39%m8YnkB3VUZZ!0f&ybmBo2UT=`$0>yool)gt{=?7WPD)~BP zkBG)}PZe(X_7SviSu`&9Q00_k{rRs)qnYcJsWHrTahDk8dTx0%b1fGX&0K40M>E$O z)zJ33%=P8CNaotvIFh*z z+#bnX$Bc_)t`GJWuk)X|>ocFkzWcL|`({=Ib6xKc!CYq^j$p2pBoWMYr@j%)we(du zbL|%s&RkdMg)`SDw}vyvGVqdk?LrWAK?=B#iFfg$r2jQXYLye6YEsC z9*r^RQoC0&^Pn2XtKGqri3|Bee>LvViaR*-g%V|158!%f-N8PawP^t-$3=VJK^vD) z8qrD2Cn>svqdPsIIKz+7<;xvZ4{js>#4Jc05sPbP_7pB3cY(9(VzEbgf8k{ECYW$7 z7QKxI2|JpeOWp>?{yUZq*jh8k@qR3BTd69Td8F|Re#YXvu}Z>|l}o8|TpXVK(M$MX zXiJ7$;&26iCmDkj8l@YDmKjf|ZRb1636H}E;(D*K)t!W6kK?e{TYVbp&`;>wB_1_D zjUxREDni_pc=Y;plP_5&I^7kIi`Ng8Sl?358W;tQc zi+I#p9t6emU4@=K6R?-+Jvf4OB%PIj4TD=CEH{^q97sUN89lfW+3uulnSgau`*X^2 zyC_GRfH&t45^FBk@z3ui;MZen+__wW8atC)y=d#G|L&iRs>`H9%tAm)<{`3DXiPsG9f zdvjya7Aou$u~g#+tecn&>rxZZvd=TvGW;#1RVU)U`Z!o>-;tZ#Uy5_5nL_0Taqp;k zQcUYR6E@va=DHq}VkZ+{$?JQn+*vy*y5+e`yL27QJxP|L=YUVV+pt00q7PE+Y_)@& zw)E#h#U)gs`L1-itOqAQm&f@0EIRMf2HHn>yyaF+`(z%%o7+70n%hNK&=3x*lXyI} zM^^Z7T?hCo9$lWO2pfZkfjCsgxZPsC@kduA9voq*peFQxGKlYgm{2ONe>%Ce7n$1- zezunvt_?a#9RiDrSG8jUZsiCV%SE)Ky41 zBw*0S)Aa1HyfEHc!0b+aDRjU)x2I4QZYN=-P~Hwj(84Ti%X zRD?41By@?n3H_sGh1nWOIP`fKM5c8S94(XZ*t0TN8Ss&s6O*v*dMmum%%;t6l5nwh z5AMQ8H{yFI;}LanpX=4TY0R8tyrn#d>#f|%%Wp`=sugNn`oYV5hZD)n?AK{2tlh0^ z3iEsUQ8M$pIyjm6^}d?S{F<*zW_}kAPiB56HYG8?hq98G-xjAN=J&$MB<6SYyd>uL zlXxBet9MlUN??BP#0$)CnTf#szS|L)&n$7FO8$I@d@-Icgzi2W#zr58G{f%Lj$air6W z8`$Uoi&aw4;H{W_shI|8i&D_--eXwx@g2aa6zsS>25y#h;^LiBaKI`Wq5OvPJ5N3sna$gMk>iaDJ$sLWA; zd*+ymsl&YJzIS)-M0zR?3e2Ojan10(CKUq)*U`JDcfndI4d;}|2$rjYVdTOzT;ePz zv{zn&q!VdqY&byh2~>iuj%nC*O-(puw?gtMEe+pms|iwJHE&vzhUqs32bbNOqkFM`(rh{qeIHt*yp2u_- zK7CBbXMP81xQBvpQ!xX-?e9oV;RA(U3o`JgLY1`leX+L5@eCX^__jo|qna?nAp>(i zP5^_+Dnevx1{Uu$go)ex36hT)cxFcogyeM+a{6at$M=tcfAEgB&dcZ!TyJ45jZMwOciw}zgviJIw}+XyPaN0mJGX-`uFYg-9q(kZ zw!cvp^V@%W7V}#@HjDY4`z@3C9d|dA`F-J=$@~^v$Yg#yEzM+pZB;UvU%9#r<~K7X zgZZ_z&R~8`4`eXE>t<&#zh`@7FuymRrZc~$Vd>1T#44Tn{pWl-^SgCfI`f;OoX-5Z zeMn<|>nV--eQKS?{MsB$V}7sANMn9uyQDF{iyx;lzZv1F%&*qXROWZyx>V*DhNUvU z9a>YE-(mSF%IK`||$@V2#nCPm=4a*Ye zpU-At?*Y9yoi2`W*DVW!6TZUg&~z}%&BCv)=u!?)3oY0j=Hil3H;{+**~$+phI zo;`V}rlm(()%^q+(>$D>J)C@kRfMp(JUp}I9N%%Lny}_o9v<_aEV-MZCe-xG$0Jwe z;a=td!F*0Wj=Zb|jZR{`(8$MA--5xyLPn^y%Euld_uUiS-&Q`PMB3sB>10bCuWR@1837*Xi&1s~Iy2 znb}3%3YpnEj|-StqmTk-_UW|(W;SPi0W*7TL;*8WH68qT@Q ztopHBX4ag`Wo9qS<}$OB-sUi~Dsef??0Ul-X7=^=9AZsZnSJb& z&CGg=_y2$O%2HQkGqXhlvzggPHCfE8Nl6wn`*-a9-KYAmtKj+A$MCz|VVjt*F(CHe z_UDy-x!FI(TukxtqurD_WfSh-_QM^jTtj%W0{ZSP!&~zZCC9i zLDYeJytV|#&sK#w%YH)tPsMod`AIll(F}v_ig8knJ7inDgKKk&vCSt9hTXXf51$ob zhoo0vADaLd^oy`4^*am!XULjRgubJCavgu3fZ64RIR2&rS9NI^%+@c&bLs=RyT1Pa z>ze#uuI;aNg}6wp?PMbJ6(*l3#1q=~U~AWdQ!^^Wm=UXBzz=z@w@)E*+V>>iuZcAx zk_vJ7N1ZwOB?GvUM}_$7V;Zkjt;9t%72?*0g|zltKdzu(5h{zdl4!OJr!cVyf326& zBKJD6j(QPJpY@FNx)wku%_1yu{7P$zydhGz2qP-G35vH4gRy53POI%JtUDwFLDC}J zZzU(}o;p#o{%#SzDHO;1?t^&M4@LNWd>_GBuYvE?p&0k&brocuE+sXUV$|0CMu)SE zY2(ylv^-ErrnVszy1W>VUd*H3X1O%#Krv3<9!yULy{2^SVw_PS=Egp0Azj;IJnuZ0 zR)%#FG{TBe_Cp2V+qRo+TWp|=qo=iy#zPdbl_ZstGrox3C4Es$o;OlD(+*8+Vkt- zuQvVHe&zj5{Zh<59!|g8<2RR(_WaZTwkPW)kj+S!f7`$R{r%tn|D31k z_i?}5zyI#{-~Vp^KHu;2{%-$%9`U*VdtCD0%Yf;zu*6k|9u_)ZU26~zn|~-^ZvPR|F(a>zu(XI=k@%)&i}T5 zUyuJ@r+B{K{UZ6hAC*6s;KA-cz+5I!64kpD^;JGY_o*Y`%GgpIlK29eEl-2)l2TlI zItM=9c7bR6OL0P8FkHEw2oukg;vzL?NV%Eyzv9x?b*0#MejqGNNCX^Jik(};{kQkH zf!_BLY~EK6+NZC;*oP&kv$F~m!)L=3F?Jc%eS%RBsw9qPB^YMV3ZwfjlK#Ho^owy}vn%|wE}eeuFUBuHI&iL`jJhl;#trdnV55at zb4{%nb0d4hNUJ(3Z7)JoZ)Zv6-DWC#R3z44>aD&ovyCd^ig3K$89uY6g-)3j;nyjB zXqIUm$!ip0e!^xle(;iv=M`by5K~&WqlBabig4uQ0E!Bh(&sOQShYl;Ys-D9sG<-* zZYUzTg%)I;Qi#%=r*!_qQJO8rx+Q0;$Z6kfN*Cj8x>^HmH0Vf^4;SK)q-NUR*^$4s zT#S=z+Gx%Zcj=w+g*f&>D{0xvN(y=x;-igC^qLYR+2UtVdtoh&J}L)+cMDK{(OcSR zy%bK~DZn!+DdpreI3 zEw?QK=K%#c)A9(}cdLNV_I$h}KZ_QJRe^g&K59V+%3aw2SCaBE@T498@Od*V^TC2${#~XOl zF&}R)z5*({%3D633k@yCpp8iAH zdvdY(=Rt4#|R#?rOdR)X3cb^Q4{6&naaCdqZ*{K$T+}nsYM%)|W@ZbV8jy)4GOMHk z)@`t~Jp;!iPLO=L*9zk+GBB+sQ=(ek2qTg*@T*iAG|FmVx<>{+b6N$@=rwG=nSs?U z*P-<81904zfeYOnz+_oA)Qj^E`Y%FZ-I`c9Fgyc~w}}zEjDD3kr_(+A9qw_KJl~Yr-g3FAdKGd%~vODHN}nhBt?sKv(hi>5}E* z-`?E^lWU*RvWaQ9NoEr0h;=mnkxj$Ld7mYb;+|49O{u6BW+2(+-9qonQ*r7YCG~ir zjcz2T;)uS(d9&J9vawG^?Y{N=ecMkIbvPC8A6ZFR)8Eh{aSrOPp8+k~F6J1IO2tKI zTq!9jonC)ULFrs6DVz(S9z`j5W%7M8`l3h1-YNL1xRR6x&7=AoDfn(m0|nW3B&D4x z*cRGCpPuOOPba2ekK1jus z4b)wd@uge|&2lk?pXZZtlCzYocLYGfs$~2e<4H+dQ((`CWYh@Oq1!oSknuGMyXns* z%}Gra<#wim=k<^imW12&*YMM|T4CnRBz)h!v!sPcx5KLa#!&kZ%F@ zCk4#$dIsgQ4}ih~0rgJRg3ZPLuvJmOp*vcjOxZ%xt(veUqYbWTY>~#KigV-UP4L(u zp5N_4ICthp*cmmHW}O%3PD3j|!TS(hT}c?;Ee{qix23kBgdg`t0{1P7lG}Ma{mm8@ zIOWo_XFO&`UILAG<#aNI$LNg3us-rFb@b-Z-Ka0bZmy%vx;(CrjFiZKY@#a%c?=u+ zMcsRS8<{NTF|bRq^nzBKI7Z|BK9wDrBkVDlDbQYxaC8mcnwk{x3(u@%9|S6x?KqdKq9t0eN7FERzcFBMD(nB zKwECzfTKSWu$yW&tsmPxVl@o3k4KFk+d%ir3z%^!UYv(9 z0Ox=1!KUr;xYET9nljSh8pNZcSSPp5&N{*St;UeEwxZpoq^5%FPzBFiq1=f?K zTi3+lMr?t3#zuVdlsL?N&;T)UEqovOI6SuVJ=njRO7ogy@!*pR$ZxB?&%E@}XZYu{hB>80y{PDOLPE_gaZ93<$}kLwjPyG2|ss8Ssd5=EY+1 zoyAa}^p;YF#A3>?K5+VQ9T|0q#pzMulJw6_wD`>(v_1D-J#AYXHK*J`pG}?ki(DIh zbGn1v`C`7$CgOAkPs8Y8|{a|}EI+rw2w-sTMMbDz~%ceTYxYiqr zQlinaXC)ORE`Xmt(fD!3V>(Ue;E`c8`pFeg)_H5#dLSBij*g@JNuiJ~iAJSG&eZ=_ zCK#$k;{+u=TG@CX(mF=t`b}FXAoV50J&(e?tNkhBcrDCIjKa-IPJCW6pzpaTob7&D@+-3iCaj1;D~+BouS-3I4U59l%QiyvhF6gEH4@{K&0zYRVvv6l ziLMcTpw*q=9!28g9a1Rt4}fd#k@!rj0NTD-LC>3!I41oGq(qzq?R}B>@%uYa7_JU^ z3nEdjTLUz8?+7i!BC&IMGu+s1Bk9~Z66^Q3L3EX-dehqo?CjMFYmZLmv&GzuGscZz z_dK7!8W4dRay78HOqKc@Mc}f~8tq%|!>MpRs$CX=Wftj>x!skXqRnKbo%IJ$=EKx=v#eai{Q+VN|l&xY6J7Z{EM)tuC^1iOnLUj$ z&Vg{75UiMVh1OguhyCY6aOcV;G*aU&Ox_%V3nKcE>YO@Io*jY@mWA>L&zfM6N(lNE zS4czVwgI#Uql!wi`jaJXp!F;mQ+h>94vNPVq=@Z*WMR_JTA1P!jD78wL1_6KaMcgS zUy`eE)BPcII2?@ompH&Wqioo^JQ!1tgh6J(9k3lAjPa9GLC4zzLV5>d@}j%oJ>Li% z>w~b zKQxM9=3aA(<^wUVkRb7}FHLX_#EsHGm?}vmhpT~jWWNoR-^i!OI|K31*E2Asl8!TO zqeTt@Xk&Gs$5D+`d@KNGx6h)!I#qONegN(bzD_oiAJW<30a%)APd_K+(9X^Q*r_Iz zj+}|5A#eOKrh6J?I=fR^ia(ZfWi-W1mzKDQ`GgnV(%P6M6m`yD+;^aX*64lby;k^( zzbUj51+U|04)w={H`-|Ri&FL4RxvkwXCs|$DweFd>xa9>eV~WmCPI9$AD(i3OxkMa zVCyY0XS+6o3RGMmVUr&wWCv2W`H7%2%?~}aEou41LMZI*hxfMbqvMk2VEfh=d#qQc zbM-Z_oP057tP?*~oafx-?2B7l=S!pcHn^(R`bOxYc|8ocQ4`aPaj;hT_0i;?}PBtN6a^H1sS7s7@qEf13E^-=?jtI z?CXQ;UT1*PU>E3T;Dg;qmO)H`E?m*{!GX4~An^JIxWCK?$Nc;V?M|w&Vyq87+}$XC z9VwJ3_VmF?p{;QC1V|RtdSm;OHb^7`B39c6#IG)_XA8SDzM%dEhsaQ{d|aPa31-jjvKdV4^`BofX#(9C-?O<3uLQ=Siy zdZe~d@Gvh-YmDXt%9=>-izlWp8%-ZCS5uclPh9)@B559ZM4XqH6JFs?*7s6rqn0OT zhHbo8|cN*$WXw8)b$ zArIs}v{8*&d*TyY54@Y%LYf)+5@T`g#x31CvOeA$p3U>XZuei%Xql~0A@6~!oAYVf zKr66(=Z@oMM$xuekb6rWbe8ykjq5{~>q0JV2TJhS$P#&K)bz zgMaz38J5etV@u`8#7?iqLQP|0r0h;D&uNa=|y&7O2J*&E+dVa5@5uvt4oB`f9inFdE)^ zxuTX&BhdLgiQ6@C{nVT`*pl8&a&o&X8mwvqwS*Sw*4eJuZ*dbu+~fIeimrIvwg#T| zQK8c+=hQ>hE?8k7mUyqsyGy9?HAiGc@0Bgp5n3$|K1 zL7j3IHLrKUjRoi6)!N7OW}*wKU7P`hJ>OGnPZwM?=A*=}^b?J%aYp^R{SvEjt+cjS zT+1`FUt(Eq8zuWX)^cBhf-NfETz|q>npQT>0+BZZ7Fra@C|oqglm6(BL5kcyybQ$G|FuuX~z@%ZE(T>?KX;*AD?(d)d?;7x02)CEs{k) z9Z}W!Grf#^B58c-i0WNF(y+V3!6@Ak({{Wh6SuAK%hwUlCf=j0B7N9p;D`tJrqfMt zS8&mE#M`$cN!c(8_+^gx)y{uhaQEHEx&pp5` zDh2$a?Qy#H9XMhaCgxGwqhDDTeAwU!D=yfh5bywoZn+7$o9*#_@N1~&SHu3<_BbY@ z1~wd40VNfCYz}UOZ^N=AAHLe5jAJW!l#Y{>SBPsuPqzV`*(H6IY=?sSJG`Zy1a%XA zNWZronu>G6!pV5r(O`=nlkGrrS1v8OZ;R76UWT6HJmdU$TP*Fg6#m)$mJFS3G4G}< zRQ0N(rfar%<8++lMN|_#*lUaZKFLUiKpTx&X^Z=My-94!636EwY;k#<2VddcOw(F! zV@|)3)Zu+KMHSvg2gMV#p#M|a?0Fj%db!ZX!VG$Qc=mMYrQ8o z(wvHWlDnJ5HU4(hB(rxE%$i|?_qgY@cKkkYm9xRVJBsOktQoYwx5nve@f0^E1oq@u zU2EL^b{+i?e{Z|C*BV=I%F`in?7f4tMvs{RywIx| zW~o@?+ZZ$H*c)vi+hT=YF$*N6uC4I#o)r#qdo9_w`(g)vS? z`BxJxaoylgV7kABkL+%VZ(hFx|A7+vS!IEvRzHT6yXPn+#{vzy=fN{|Te=l!flnXD z!8DB!T4-c}L7lx|Ri6}+Ic$O410(RRETx>K7HG422keV}K{rQPV13Lmm^}9*O_j00 zs*RwWOI~1|4y2+xsB@V&GEpcyL`@$MhZG=j@85GP`}w# zglLYty>%%2Q5nU^nxoNWA6niqiEvkbf@~spQiYr zTQjY$3YI*4Y>JWoHFU*V1zBFXM0Cz{3V$vlOiYYFE!p^36|LG2TZT|xHy)nThtA>)c7>mr)O|bLj0$#&R zoKx~KL1U-UytJwn!gWn>@KbYj2eHq54w~TVD~=Ki@jKn*B_;><^^20Q`deR8z&v^!hvovVmawAkN zEPx;jD{>ufgyx2E(CKXmJ^E#cZtm_dx_=rCcx8xrs|{eX@jcp;X^1K(c0hB~3rg}a zM4@>w+>HN7>+}rqj!B_ps$nBF9yCP#2NNU>&s%BE5<^TMY#`P4ZKKIU3~^p~41Xh| ziLzP^uweKoIvQ3@n~M$brPFDOoce^WhZ^8PKRcS(IhPu4iM3@G+@S?^VYG9*0iIo5 zK$9Y^$U&^*^eOQdMPW^>Lk;yM7_6JmHG9 zKI-N)Q;DmcB=oR8eq2{emVOElG*=(zo_j$Sy>`N>{`z=eTOrANTEef7dKkSumbTps zg+1wd7&zLAmdj^>sgoWi{5VZE6_3GCtQ%H5cRW1{`T*+}>){i*Ony>hBebaKp@BoJ z)aytanAGdy{coEki_}_SSe7n&-1;Svoz)=jeWr_{i~oV{_ufF}8C^X1%K-Eh?m^R1 zT~wXy2T5xP4yo$m3YTPvpXdehO*(k|P8ld3)qyYhI@qPA5_+AP3kp6uI5_?jtX)+j z*?UC?`|+)i*JGljVx0~;bZ&!FMV)xFF*>+1{4?-7AMwwA-onCyDu@_7lX^$p!nK#n zp%+}C;C;97*^e~Po#{qVvbV6eOc2bW1R9xf6K&BH4l0*W_lq}iW$=2K8~=)SjlPMx zZ9U-Lk2>n}0clNi$OpjQwq|mQCBf#UkgnvHjwOjpp8$Q z>nPx4Z#b)`jcca9qTRhWf$CIkyn3XV-flL7-OsO}=Hqx8{Ur#-n_a=M5w5f~FCBDd zU%~P+ExN1r2)4huj7`qd$aLd-$g;eQ3&-5&-*sq&X7$Txb>@@QQKb!(D=*Chx?CY{@>E*2#aB6fTe7DWz$9BDd>sNgcf1{g7a}&;E`L@T<^XpkkIeZ@D_h*7Z z7jaKM<@30?B?S5^#nHI@b2u=-0&Lq0X~Z?L#$(6rFy*H>j+}H37Z}LF(L1%Y;?-H) zG|gIK-PlY6?ZmpHcq7rmqm3RdJ&SrVp8QhVX4?4W47%s3kX&pHoew>OyL|T2+Ud_} z#_ls{6>Cl3Z1c&wk66pJG@OEV#gJagX*BzgO)umfsQa1ISh4siMd}@=VM9*i$TQVq zm6lO-x8xM+a!s^(w3Ju5c?vVc`)jv@k@V-pQz-2!eiv>(E-|P$iJmd_RPnS61eu=1 z>d@D8=-DdRJLe?Iohl_?HDmCoJb@dvq_kK)0CtOYcRw!hAeXDDaC`0v?CyP?mX3M| z>#L9BuW)tRnEnn@?2qH8d$0H$#m~@n!Ev0qTZs>rs?h=K)6+rGno-M^P_Q3ei&o;7Ril zJndB~#&%=S^F4xR0$)Q=`J%!nOkJFV?ny4bphSzEibak*M&b%KE z?KUyg;qD;}D6)nNsrmF>_Ygh~+Y86WJ*PD@#kP$KOc3kVJ*?6|haVo2PFI`hqKgJb z^g1zz6Th?cTCIV42d#Odkzy{*&x3eR+*fc#bS<0P!U>Zv!KvzUc<-|dzn^i1oZNIUS-T76WfNddhhT{Owi7jv6~iov8LSW4 zi34R{L5bc*II?XgS~}Okxzb+nQD!F&c4~nwwfd5KaXWBzWE=FeSCXn8+JPmtP2ja4 zgwI#lf&1+~LiGQm>Ab_S{NK2rq`hftY0##{b$-s$E|DUow70&}PD9G7kjPF}ksXzh z`#NQ0?~)K@MMn0z@3!Z9e$VmzcO4FYIJoZ9=kq?_@7Me1R4Py1g9B?n!=U72wC(a9 zOqS1rf76_4&YV4%{on;mtB<5hCHh!f?hJ!mGs)3SA3Iyl!##&jG;5zeCRMG1i%oUp zJVPJPi3h=nb!`+_zgy69pK?=g_E7Hg-6&r7R!!DiLLV;gMx$=A=*D&l^_#I9=dP{h z7a!^*+k#yP>wrE4d?N*`UASf44cb##OmUlbVL`4dt(lQQPY3S8n-SsU|1yedQuJ`} z^tbfVz>9X6>fyZAA1QylIlW$@hgNcRWL&nE{#NZox9E0yKH&#ndTS?+Y!uU3)ls~; z(oWnboGBK_F6K5B>!Ngg2Q4gY<=k)RqVMurnyS4Kv{ZCarmKi93OSdd-8#a#F_liV zc)*7!9sITVB^9bfLgXbK{OkXiGQ!_Nx6rR~`Ku-A9QXjr;vLxMs!K=ItHC^Ohv1Qu zr-q5m(C_*V%rnm7M+mbu8Frw%&V0V2Mhv1q+tFA3hMH5j1S%7^?C~r6a^SBnS7G~A7&`Lgbt`=G- zH9_P_MN)6n#N^Bhcp!U#JVG@wcjY_SmvxU4|I@@~Q37Zv_)*jXO&sDI3LA7{=wi!O z9KF&7q()`ZpXXcg!_zCUd|WB*Fy4wkZ?1)hQ-#0fqOIuVI~2@oTWNo*2D)1YaGy8z z(9#GEEJ#jJGu$d68DkBM3>eDq?GjVNLJd4Sh3CuHbyIuG7Gw(JXzH34Qi<4tM$VeF zy{(24jJIIQ_}k=o=p%V7-h%6GJ?MUMDkZdU#xd6;XrlK^QhBu*`;B=^L;D_6*Tv1a zVbBLs-D*XB%QvI!SV1du-bs5Un{eXy@3hQiD*fa)33uc!lJU*qi*IhidT%jpJF%Gm zsxEYbT#`_RzmeK_=}j2e*+Y+CIB_R4He#z>J5@JJL8k3SRQU3Z;uSbh-nJ1}>X%Vn ztTA|w-iXUGvdPE75q=kKz&#h@$WS#1ws~y8+9&?BFOtC4U<1nf+$YONc@R8x18VI* zL3P2O;c4}H{KJ$<+PML)1PIS_J9*s|9WeXkdTjZ0lmBVg3$K*cqqCG>oU^^4Z8fjM zA}ztMxJ(RZBG%#I7Zu!?8=c^LZXNo(oeLU!n;=$Yo#6Z34~wfS;8pipp%3UDL~FeR zr`WZqTjUGMwF#hibuHFRih+KOq3}y>EpBScfE#`;VDW1WZtEz4b}tk79=`^Ueys(M z%j;md*&5XJX@x?oVQ_f$8oWKO2TZv@?tGs*hNw#*&@D~vSh6}^94&!_DT8=sp^i2; zyCH;&<0Wg=vGiICWK5AG&;IK8ckEXfc6%#LOI?j|cRqrF{4KJwT8&Pl(_or#{?1sx z8YgzY1fOLQR4=_6Kb`S{j<3m7ow^DSCRl+%bs;j2KUgXdWH&y6Dg*; znI?HNJbh80=uj1%+R3oS%7*6j7SP{eLO;}Xe>yTQo^;az$6w%SJ3OPSw*mQS`E<0^ zjywU-dT|ALTscHv#hk!kX`*udxwJQi!)wnwX>nr--*=J2{4HX7k-nP$u$03>;hz2F z;TpBVZZ-7n?V)QS54c~kYN)lNorXB~aaz~a@UmS!DfV9pDXY}5qr993el`RhX*K-$ zK#f|HXfR_KJ1X-^C+Hc-XARO>;@|{mS@Q(GPFRkGH3hI?whcW0vjtee=Dz%`OOk) zV2g3TtFxf#W>V|lMfjvFgeDw{C6D+;*v2K2-#ejy`tl-FO(+yRiq@1rZxK%3@s-{; zX^>9&Lfl%>CiGfM(~Y|e@vE?Zbhpvx_bgtBcMnR)Gps>v|K|mGdT1B@`1z5mwON2m zBI{{x&vHm+3$UcJgt{J^KwZmxTqd1DDoY>3Z_oL-j|J1j;@8l=dp`bWG`c`=%|j_QV2bLZg~H!IP+FySuzNlECfKE{dX zis7D}63#E~2j!dFVa8@9T=@*aXVy1J9Tl*ReRD)soY(R!ynr{BK9-%*>P{K{NZ z)@^~#$8s3o&z^<$SBAsfC&J#PQ30o14&$PS^^i@30_Lvx zu2y(lLb3-G@ZG$PyoH6BqDLrT)yH4FLv1@n$IZmRYnn9UdksCmFcV|9SyB1O4-__j zChn;Zq_y%Q>Z+W9B@QCmcR7$);0#Rn%BFsb59#XZ8JHdXiGmNDrwQX{;K#N`x@M$A zhm)scf1hrm>#_XNl=zoGx@0_mcSv7j9_mG*nyIOwFGsLG+$!xKvz5 z3Rewb=g+BVob{G=&+&wwCsWZ?Gl&)riUY&#Q_*vRE$L$c{P``9Hv+fQy74t&8zhf% z%`(*QZ5zaB%VTY}0k8L;7-sZLK}(shY8%!|K+|IiHaJ&vEx$S-pPPb$L#?}y6KXNj<>E=L_tRtMuo`i3k%VFDG zVK&~Kgweqba5{4deA_Sy_de}_u&piJY?(=z)zb@JCoXWqGAClH;OY7^dY`Jh-9&u8 zRSY(hcJLY7C*tByokG^Bi1!*l5r4h@4*TE8Q+wV7{CB?s#yajNTeArmV3PwAogJu1 zWdceMiGid&VN~8U9={Cr0u6(=M1kXRyq!7pmKV{D6XQ|8cq?q0^OfS2#-qEY9O#+1 z(8Ts}*lG2KdnL?=nPKBF?Z;=eryde&&>e>xEDU+w>RuW(U>x3Vks&_1jpioGq36I& z)Hl19+^)*u@NE_(x4ejCl;!ZsIUg!!Nwl*~7SSe#9%qG;W|S=E_hrz%92ZhDk;OCd zCDh;lDt+K&vHngi4cxbZRR4~}DwS6HXgHGeg`V;LQQfp>LIl6UYAjBdl8~Nui>PSh zSR680LcTGTYRdw6@!E-oh+mFGQEwxm5ejNaGxP^xs9Z;q_3JZ;|@)Mu-g2UKRcZ2LO#wNmX{94c?BOKzTOOK9t}s)?;6OQ zsR`Kz!*STy7TDr24qD`gAWuwMcvZu*Pjj}ODx zkRCWz_?XXA9ESD5ZSdiW3{7etilYyHgQ2e(1w;--vmc)Xuk|@Pb8#ph3D1U`eU4?7c316RJ2-`c#DSyiltP=|!?XQAv zKXM4}+xnYpif^ZdMT3#bY`Ol2dnxPDU{pWC)Yg-PrkV}LN24x^R=+P^z>Vh^sP% z&K7eUlA1pd^XtD-*vie+QYC{&9NTD1hYb1Mk--VK#B@_ui&tJMgNkQ`9Kf$qwJ#+D zQ2Bf(Egw|HXId5bTy?S-ZZ{jqSt0MY3P37CJ8LXjSF7b3(k;i;4`S97_Xt6lK?gcSDd zoC0GMn_@S&|ACdin>)Y>9A9^DUh{<(wJ<}~QO+7H#oJcp&~LXRx= zLvc$YSc!dLlvF>g-1-g<3EbWl_xo7!;0ky&{Sau#^|1}Z8)3zgg|Oe}AM=0?I0J3m znYsTMcfA)b&$r-iy!gvpg`aWIVmYQLr{KoSY>; zne=vFco~#P_soB?(!clMhSEFQG~_4qC_My*BP-~l^A9$6(jv%M)=0zTf3WVf4leUj z2W<+FutT#gx$SPfbY_u+?Qoc_Hoji)(i{@A@%~}_jTt@E`Mj5XN|{5KEt}}o;9mA9 z%7`xXFDG`Yhvk~N(W=07Dr)OyGpfUA>*Z+Dyw=TjWhRi5wjX`#-_4Yk7SP1gwiM;i z#ae%Trkn-GDRD{{3y^7`2|Je2z_3nsa!Wh0rhc?Vu9GRX^it#d3;fZu9n9EPLPt&R zs4dHFXAL^t^!cHPdo#bCwS+YZd6C)h&%TXa_*G8Nr48X%XDhp#o=L?H&hTn)E8Cg) zlFZ#B1f9Qy-FfUzClb3jH8Pza2uZH?nD@28TPo zf!Ch~mb2a%r0$o&Cd&qa<)mBOYd!xY4`gw_Q5KOK2(HLgM1n5uF9j)#`kH0 z?I*Tlb|oEnzK?!(l`_YT%_P>FLM6LO*-6 z9@ub^dc|zhtrnUhB?l{gKe7VR7g`TTpk(4l7Ot32H5GR7+PR1&og@-%2!LZFi`cEc zXJpVJf~@-=*u^yu$ks6z`VINO0)tP|ef7_vez%aRZd*cJVguAl7qaq@@BDwM!aHO6 zo|)c0$twx|%poopEbWV0;AqC;mncGrr0||MqxHsN#!$n*76ueAAylx8f zNs8c|^Sa42|1B&3K8Ebl1xW&%YLVus5uwN-X5XCU652;@O3FU6i>pjeEX2p1I34 z)4wxkvny{A;MHH=T=*|?vHw9?WCayRm8oBb1C<6?8>j->^pZs?cR=)(c5ajEOJ*9}3$yp1<78uAu$T8FVCk#(I#Kxr z1L56QO1Z-8MMSb8S{<-$Y8PKTFOt2T*#Psim(r}D2qte*4tAeTlbk{XQ@@)7qZ1v- z+~+ydaTMm{^&nE8_?(#(JcX#lc$)7V&Wg=#g}&(b)>4Kx8%K;L)tP{dwUBmhCwr+a(GMLS{ zDNljg&6GPXm~ApWK=-;UX!Y$N*1g4^E*;II;_rcM&-);fD8x~|ejpn#F_B(n_>y17 zGxnS>r1nND`l$Mhb!gYnx~;-*Cp>_eJ#V3-lgH9Lg#dw-+)azTL->VW{!CMtkq^vX zh(gBuv+>DdYAKt}J#c->ZaH-k#AI>Va!=WjvhSpzG7a=Rp0L^ZRkXoh57gzKFi}<^ z#rRo)XMi7Du;?ure0&U77WpxILBO1q^a8%|zN{(6lV&NWz^^U7Oy{u`ot6|rSh){# z%icrQ?Uhir)rb9EIgvEJHN)fzK~Ni?&42Ulf)}T~nflwM{MB?ZtQUJR8n9N)FV4d@vc#Ew*)IsrMzo{zZ#+j&Ng-ZuSWG0zba{ zp)30|x()2c52g`vuB`WB9oV?9CU18ab|k+P5?n5l&qNpYaBCLSggDXg$Ih%r?lnvr z8bXbeo!MLcr!Z~w8&dOfVllhyK*J=T#!hi!bIXrHjocSIu^`n?EB(i3hdJnk#3|EGm4+^+zIgxZY>Mf1^mj zAe?rNzt86Srcd*)6mye>AP1Y0Kz! zH7drOej1lwr1KTepI5C z06z{`Gno(@+I6J>66>v){-#4@)b#~w&snjaP4g+wyb%n3TC$L_^}JGN2gq7kG7s6) zyt14a`i5Jw?MIfrKKxb!(jFEp_SG@Yx1W&xnPI^m1k`fHZ5@ysX3m;a=fPk>Bi+8- zoQ>Xl5J0N}a&Fva392@5rndmT+`q+Y4E&(tZ30AinXy&tV_<%5C~OV8$+l7ke2R2| z^f*&?#J&U;{V{>XX*bxXJGHPtZ#{UvyUqq(YK4IlN5Hu9Yi!Gm9>AVZF1q$AyKzX^ z?_a7=yVzpF=BWtYLd_15R?ii-A)*`fb0T@w-xUX1P+|@C(f5N;H@!hEe;-^K62qFSs2`r0!AYm|fppkTHKp zlSZFqql@;z_s$u`^cI04?V)R-YKP? z_)8Qz>M)z7Uq=gnsZ-;)L+tU;Hj)Y&LPMq=WRp+z(4sO^f!k zf&au5H*F9XrMizD(d#DP4X?SA>kOFhxfb$UFDvL3dztvaS2}V?1N;s4u)sydbTsrP zEH%_;HGk6R-7t4;Ti zdUhq8CtWsn(=1xp(*%k6I?VrZDgUFS6LM;HurEtA`LX-OutvO{+0U$0ontQ%JjB~s zgqj8CcfJ?orfaidgGU7_Lk*= z^Qo=OY`Q;;nI|wG<*}^``WP{S(hp@wWGxK!*1X>5q!$aRqOlQG2 z7=H!fTj)ln;?M>gI%Hs1%m#MSw+C8>dT~_=>lq5~;l@!<)T}bru`$Jh-&JJ-zp7v@ zTQ{H^ek@MpM;5PPi#nTO@0bbHQ?AaGpVUBKvlg{ht!CN^AEBh~Hg(pnVngCm!TFU3 zN$Qa~g}j7%qX-hNIBeotFDNe)IABe{@^h@9Cc2RF1Uzxt^j%;qoOK)<)!63O)8U-s zcREzB%EpX)&vnf0BB$DwY;_RhN=?LMR=t9Kt6wBCyCoshisj7YpAElyRWH?+FJo(W z{o+lc+G%9jQg(Xma=KknPwPLau(1~mDJ!d-96l*CuE?G?MCMXM*%GGg5J3JPdD{GC zG21syBC`aw?-Q(~W6+(*mYn{f&%%sgYg#d{+LWjm*^g z(<|{jCiSt0w6$FLlz&Q$J0l@YJ9E*SK}xJSUQFWZxt#YHMP{AQMbit@xg+v(nXyqb z<-eK?!A!k6BV=_6G>Jn$9LA>Cj^HYN&Oe#&pKY(+=5Y_!c&mSzO8DhnaMN zL6SU+9Ji3q^btc_(G-?2^o&~jZ3$>KPG$q$9&+Eu^uqK%lh}mZelSa;9j1($#75sx zg=MqqVcyJ%%rMLdBJ;~&%hCz#&VC2*xR(Q$){SQur2^rXqXhJL9~a9(z4bJlzdn{3U#|x;TLCH7V;Fz19j?m#p3g<`j8P!biND5OXc&)FNO=TEuEuy4{HM~sUhX$0nFcQBE&g1Q%Zs~a~b=VJDS%;3i18f!xdA74kj^$ zi=Hl3Z}R(6dobYNx5oJh6IB47C^!kQ!X{H7j7NTgF#0- zIXV3f__{j>It`Y=paBhFs+^d7*QWu?`cB2e{ovni z5hs7Un?}g{K;Ii_&QCbITlqbPl=I7ZRR^(<2Y&=_j+XEPhj!6kA*-OHsZ8ab4Rm6m zD>yWtA$K8*^x~fry#M1&6AoumYL_FtT^UZ_=R}j)5C^!Tl0-{6(ke5_RH8y)FUc&~G`AA*Q{-v2E@Gm9w zMnOSs)_rpr!g`7SXTxnpv^ksk$@b#^_iT}&c1g$%{NL}1k51?Ie(3t&b9&%>s0(cT-!r(J1%+j0 z|Ks-je-_!O9q%y9x4-CAnxO9q+@8sXPTXsOJ-z5>0sdGr2|UA^;a+Y5D%YKWE%!dd zH{SxB{mu=1kEKKVWr5q%5eg zzK8g&cPXYJ50!Ss!I?PW{+W=6Cks5`%+?fgcgn-UjCB4$qNx1rQDVPJdVC z;moUnT%~RgnGMgw2Jh;X-gy#I_?n9)`+a!@-yXu)T+}g}PUn2Tljpr$v`jK0ec_#$ zu`d^ApL|3XCsIjQB^UK)y`~*9AvA4ZF5cMqj>-$}QL(@STs5ec~8hTDSdvuu=|8%t}(hr)^**_g;Ys8A~nLbnM#z$vHcRYW-q5I8wLf$~%>c)%8S zXW?P1N4!f}542}xVPll5s+yp=>G)=$+xBqo@Yo*MdLavkq|JeS_nIJLeHQ+6xBxE? zeS*UivQVY>F+4r=7GAUpJizTDaP<#_H7S{RWmF;f4Y>m~u9-MPzYhLduYq%?GSO{i zC*%*RSVm~pI&t1z8tIt3cXa|3kA`?*tE*?<>iD$Rd&iffS z+9yx&AKs_yhcnQuBMSBjyXmtlGjQosS2(aagJ?(wo@B>hx!MxB^ zLJ0*HrQy7rKD1CbNzmBSkiSf{K{bF5-Acn7??2GJRYEp=hrpll{zk2bfE;F}VPsb) zwJMhIvwx&w;S~uf7rYZ)C=l2(f*qexG_6}*j7 zP)6B|H&5?{g)fbPMQ$ zCF`;|ieX>Zxiaq*Zw4{pE^pembUH4*piwV=%X zMWn8kh=(uu6U>Yk@|=mN7M4i6H~W&CH~|N%mQb<6bsCVJfQJV)(yKp2{#pg5%qoD7b$C9o4|5;xlWq=yW3!@ zzzoke(BRtzmf1Cm$Kr9_YT>&i(BKd+?DQ+S{g*ny^hiABxU7b4Np&!8c|3Y3TEi3H zLLqw?k4LMX!PI{u_+CjkjFJUjhZlrL5pMcY3KqvM!I(P&|9oK+97$4yetQVBYP;dJ z;R{ZC5#gFl3G5FoR-GwL*eE5iLkwMc{SqGkGj4{PL6hlK2#+roe1?QIr)c6$9>=w% zfz@eu;j_Wxbb}2?+BklsfRL6 z{Q1PD*Vr##Le~e}kKLK{8sFUNp}hy5awnW$W8A^-w7Y8tq#l2brjN_WV3INDsl7&} zwiMyq@dzA7zQ()Pf~n})YtX6{cqt3+k7a$6nGnGb!5Q8OCp_?1P__T>dC?Gu+j>NZ< z9pUP>9GLSf0wrrAL2=1TD0&xxo1bTa)e$G?_Ky%4Yn2ezwhy*ni9pp|tzdk2B)s1e zfxQ*IP`&6X_h(uJUiOuMYL$nmu=_cVi|T^#d0D)@z!kCVtcSSpWi-h1Ic|&i2y+c? zk)rW)Oig|R`466ul`#CYzKu-h4W>~t zVHmVVOg8Hd@CKhl@rsbqt~`^g)*~=L6#92j#i(NLk!2|Q$9YNoFqst3c==rt7PdZ=#N1mIOG08($i{$f!9OOcn{A{ zINJ>h+Co1U&xyR^B`|Gv2%flX$BjSK3+E+5S6A*hXkXC+IoZLe6n_*}?fn9>KEb%w z&=vYFWPtRgU|frJ?eHK|3UfRE;?z4e3{Y@YmFZ2SPWpAm(F%V;hUjzsIL~t|^r)bTE1wxKUd4<61FnrGS z$@I{Jp@A4VB}nyNwuE+8Kf|Ka9{laP9x{)9hN1GpUS>%%eZKPypL-jU^=uF%pj-mY;p|pFzGgQ(Nx}LV!(&W+rOx6BMdUYD~Ff;%Q`UFo+ikSB{ z6L=bR0=MSMJbr*)0G5rEP~eeCoU&2?hM0HI@9Z}2#V>zUnq5m#@|)mzzCT8tc}LC8 z_h5m)KNje|rh>v?ICRY)NBTaZPh2W|*YwBLtIyD&k}}vl%^!ct%%J)AzQe)Jr-E%HZ}*rjpQd-JNZ3y-n|QRU7n!&vsze~zaGMc&P3V#4q;#4 z#5HqI@aSA23+q0L+cEkHPR|xY__}4hMx7tdd(jRPynplYul+C~r$*=m)*@S5KMZ`F z4UPtB6S5fv%AAyV2Ni@2G zR~LI@{{zB)_I9)Ak}+vYO;U7os+LV|!9A z=?{4T;>q4PxA7JE-+B%oI=s;7vJ3tnP)5p@-G(3wyD0IWN4uDv=9R5j^w_k1?u#F&zHf0F&u4HvYU0`+gL| zSck{BEzlQ6?@xql$Av!P3-PdZoIi-v9;3Za5oolV!>VDAF>y&fJelqV+GNWi`>POaR=6W!zmf3@r>-ekWgW_@pkPUoRiyx0>5{;Y&NZVy!neYK)5 z+3Kf;9%41hmXN!N8Bq27oQVD+Gt2F!hg znF}s(A9{O9?T-hlyblnSx=X0f^T{+5q) zNa(AD8Bgis`Zts@!vlxfCy=j?9~Jeu<0746s#|)KG&0@M^+W^xr>jCE9=l^sr!X@& zrt-hey5qA@;WK#1S~PK^JHCt+-lN;*oXtdclt@~rrgb#bes{wz^9t%%d{Ed8yWxV) zOgeki8A@E-FyL4O{T=)YmYsIPUE>`nWo9hq(^~eRq$Y>8!EpTNG{g}4gISt zR<6rT+x0rg9FCjV8>EdoE>Zl;~hW1 ztAVbV;T!;0XA_LBaKVp$LUwSf4>Z4YLDSzQpm)Orc3HV#^utC_oU{N|>~=vd=Wdw4 z_ceETfeU6QNnl0eOtl?SE<)D07YwgF;2(c<#%aHrL3RBE>JD=A`4a@rKYj z{x=;wrQK-l4rd%bE*yTWkER22oCUV_eMtVAN2)&r&cl6eL4OfAT|(#h0B*gxH^m8cjn>kIxpj1|?IEtZc!v`5 z-qVoOhgke4kd*$#k)G#6T=M)aU2}U(QpOKa*ZUK#jy+FD)gR)JS50*B(`-6C_91#H z_E4c=D4!>=ATU?pPtG%rvrceCGa=vYBxrY`4;@jX^E=&ko(eL@9I@$Qxxk`04YyZ1 zVuDl}{qy#Kpy7@foDf1j*J8oC#sTjI+K`H<0M^GiV5aF7D)s#eZ|*wax$JKKu;4lP zXyAbES7!15dc=S#4j6oRIv3U_hW#=Qcs8|@o1oJHrKJyW(%sDK&ZA{Q$Qe41tM-vEZ`n0k*wNh1D{TKyKaxbXZmneYO9=`QP?vneiRy;WT(yV2}K( z9^kKdbE}`(<5*#SpTE5@F6O#D&RX3A(g%b2I4yg;SJ4EUKhL6x)9rD2#V3%@Jx2*$ z_i^RFw_v*Xv2aJbj}Hz60Us1c!9Mr#%-1_mZT+6K&)-LrqwAotvzAKN-AC81dT!M3 z4w^mTK88IS!pSTbW?ZWsj#9eQ@# z(UC>@l*{aJY+M*!^NFT{F?RShBAvz?yV2Zlwm9nTXZkVl1ewR#;+Vo_y0C5{rP|qI zsB$l5m^<>}hiy?SMMBeJ#;8@Vu*FAV-Bhj}!=(?l#m2-&nm%I;keL0YjzJ^B4i-nrwux`-@~82J3&^q8onyrLz~bC z5V<24R{Xdt^wdYd^<%GKK*3$C_Rj=`d}mns^e#qkr~tcZhrsF5T?~HT0)yMe!0%0W z@xrrSsIar-WT)Q6vIq%ySzZ$j?z)4YhjoLHDB%m!?x3l_7jf5Dri~tVaD-bi#Aun4 zhS41~s!kBHqJH#p?Hzn#^%UIN;;C-j9eldk9Q36>(#b|^95HSsSYE5A3GvqGr<~7K z3mLXzM{6|e3|G^0lF-PL*7!%xnCE50^n|lU>*2%cW^^n48)l7bz4ubGe5#0poYw^EnOFjAAY z!to=-lsM0bzg#A85*#FSCgp|NqDV_@IwI_|<`i%h=9Z{;MDQBht%O56E%EEuB2qIm z2M&}bfUkG^t1q-w^x8l}#_d-;!IW9dp7UUCKU__QV);S!4JxUd@&dVHU z_c_DpTbVHKf;rYccm=kfpTn_D=D0y%o}D&%0J@XRv13s+j99c2&XwNA*vK{rSS|xy zw{D~Ve`46DuEY5(xQ$PbOJKG^t;qZ1Eld}<3Q2=M^M%)M;XQ?K5D{2DmHnmkC;2931H+kCrA?TnK~kG z;9XxK=WUZte+_P+QD!uKvkRk1GBfq~#sL)o*pk*7 zH3xct&CMfsMlb+2^f!(eqIOD)Ma{m1Z#&afk`uHr;>1u+RRafwt zVG!@Lr3WV3UBUkIM#dcyW}MNAE2w7V!_@@$z_ZVn@%NzVpda-e4wzrY5M3ik7*`G_ z6ffhXm5-pqE)~*>F5$ypv2a5r1df|s!jxI>U~PXJC{Yl22yI_MG^*@}fSVL3(X+y!i z|1dZykH)**hcQe4!|#)#Y3$l?kg7Z_u;5&YSI7WA>(lsO=rPKf@&$C~oyKFi<4I#g z3pBqo#GKpqyqT83L^d_VLss+Dtc0D*^tpz(MmvtnyW0)rxu@`;;{s^C(Fm{3pAs}5 z6M@lJ0%s?lLal8+@cLR3EJ{C#?OFs8#{;0z_#}>b`2pH5Sb~h~Nt}D<8%>yd@W=^#dQsTDJSOE> zMYH=I$6wVspr_$LjbX>|TIEZSa*QCO-N#Tv*%?a5Wl_?fqj)m$0L=8Mpes+0qTiL# zpgXjc4s1D!jiXEoxmb^o;?Q{7{9X6YF8Z z5d%z}Z2@gJi{Qx+0~D?IhYwrg;q>dhc-<-yBv%B!`N6#?nNR}u53a*<>AmRM*#Oz+ z7ejH#9`sn%4NhAUxCY%lxJvMrFB`sB?ax1bRJH5{H;cQxC{Q0mtXg1sr7WG9_Ub-|%VVQx&gR`Xp~M~z)#j48Wf%6((h+)Qswv%R z7Z&l-u)4O54syG2;A&0o%`JgJRDZINx+e~#ac7nj! zTdqV(Gj*}yQ#Xw^c**m*I%t$3p$MP4xYJj4aNw|B(!A=zl}**b*XGTXtvneXr0hW3 zEuRUCPQvcfJ5W|Ood$94aBbWU+|)0O?re<#lcep~KGjaxv*g356Wj58f+mI4)j-dX z?RYHo7e6wo9a>*$W4}Erd}x87rySJAF!M27qu^gu8KjMN)!(`Gi5Ta$K3;z7?O_^gz1N6JFxB72jR_4)SI*=oM_m zVWKjKetw4XYcxGP9{qcC*@3-6SN+*Zd;BHp~E?B3V7QdQ_ z{Fj4S=fKQ}MO5f~L9c0s9qGF-Gk!1*{Ttz!j$= zO^T=CiJ2guGDYOAc+$3|WnjH{3WoVlBtQQeSod=>y8M36bBkMHchzVi1le99yoHU1RrpZ^#F8Yf~z(N$0g zzYQBBCSsqn1rRVk6xyssfBio3JF;63@t>^mt4$-wEYgE{e%6>N`b+K~_2ulxTjN0L zhHHx_XC8e&0XMF1hdpzMALcFk>&Mr_c$wj(G;{(=++IQuJ3z0WA^!Z61Mo45E{Z;S zjq=N|u9#@@AVibm6VSupxu^$a*w2Xrd{Rp>dl-hBlym+X;yv7iq1O3_R%Z^2Ie?D< zZx3I?^PD)l-3d79vN8pZ{ze|UfW0;?p|e}wktcCT^`}KIVG(U|;?PZB)E+NSp%P6F zSNl97<&ZO^m0^X7oz-;JVHFjwv_hw;P4wlrI_1k+;o_H_v_w zFSA6~oHnYmddN-tJ081~K9h;n7~o>Zi|=zeaVcR~;l%n;_=Y7~HdF6@+zE!>7?>@Oj7?C_4EFX1yJaPnM@Zv7V?g z@g0rpcNam^=hHBJ!vn4KkeLJo1H3HklPqrE^`UKbU z!!g#~mk-+{?p14tW8GpsineK_T>0TBKWDwj5P3s(SBK#e%TV$UFQ9%)hvCie+w{5c zDtXEbLwQllv~JufvPm3@@5|ql^ZI#YGJ7bFFleTHYgsC6AA;7wT~v$HdCwTpdp@U| zPTT#mnrAx%dn|6H**!jRd%g|Ef&MkLEnp&C4;hR#OUg(h>XdSDF#059(w@oju>Q*+ zEM9qD%&@%+uYv}l-+?`})U*OFjvFNAP7k1^E55+V*8_3VitGH`U+to{b0B`}m6q{d zoE1H`7>NDEtiRHx4j5W70JRfMp!d`Ucz<{RI*i;5p^a6L)pr0&pNGSwsC;OB(jRA* zq{7I3$xwc>bSO92 zs2?8F>4ss)40zwWeerN$3wT#G@xB}TVk3TnUstA6i)vq-clrtJTyv84r*(% zPoz)l%u%*90v71rr+>=k*m-3;cxF}-UGIbJP;cnt@|9{9_QASMF(q@VWemtQt@}>i4O)Rp$ZpJ7I!{$~MwJo7Yg$-vsMM7?Z*YF|+!yF>Z4S;fJYq!gp6=RD4}y zxk=QO`I;N!H-{8XsAz``kBsosxIwVS;0ug&Ho`YgU0`eWD`eht&YK3p4xn3nMiUut55m*{Ir5Hc&= zH8H+#7x|5J;`E1TqU!G^8YNMI7o{4gtox287cGU_y&5>aM-kDg)ty1)^79dF*sYGMey^alv)_VLUmfc`deMhNO)xCG7uspK@aw;ILg1EO*h|zP z&py`;19f^~$@n7fU3eRWWs3gm#Idkc^tc5%sA0>bV_?3y9NsIap>rWD^xMh;suyQ9fq8LD(GPU8O9b^z|?pZF~hSB3Prz_w!I2oNECB5&3vpD z{pyK<*_~i-a*W5zJyBVu2|QgjsclA2@w`+G!}1(xMw2p5)q4cG7Qs{~dZ-tiz7GA~ zrBJ|BW%L%kO@1GW=-3w}JSMXklyl$F^wUb%cYqS)iaEL0#wj88Th7_ri{7-4iik1K zGeh@u(>8z6LoIp5_pNQEYoiqLMmbP{XDt=JP{4vc?sV$rGx9vDfSa9S$!<2$)S(Kv z=wL3LnjJ+wp37tQo0oL3c0avzmB;Ca>ghzlP&y-($6wxJ{hpP^L~H zz(o$1&+epTk5k-gV>$e-)<`o-^g%0E78jemq2X6IK#G$rnwuBUlV_n2qa}-LCtamb z<2&$Ckii+D{xmM{F`Qc`gL8h*C9i=WV7Hw*5iK5>?VTETn%KW6x25=2|qfX0QtY_+u)ylHw0PT&48{ipG8ctEDe zS^2}5m>K^gKN6OO|7O#VR)B4v-SFYvFXnjR3oMw^AD#^T#Z06k8*RlEZrh2U?7pbg zdgAG2xw_&9`}3p&z8pBm|LXUHb;vh>oK#AicYJ4tK~?b9Zwt-H>SjF#=EKA7XX%A* zH@o;H2~zCSXx-*6R#4#sHsPhT;Z7$T-ed#h^^vCi>0p;KJGfze#Ju-89n5xFf9^+f z7mZ15XPQT){Bikiy4T&tjLTbi$=Vi5o7~3ybZ1g$(?>dYs+H-=`H)p#QS0`ug^e7Y zL|=Z0c`sHi%+LQmEgBa=iQdg@oPHI3nYWFMo_=G=x4)8+q8a&1zOkN3qBdhw6hGRf ziLDmvw_B{brCDJkbFt|lkL?NEIK4*pr}YcjZtM$bs~ecXuL`POy%Vgje`P)U-J^=X z=U{>2S2oZufozUuK=ZOMY=piyUD)sxf@ABMU-=X|UHJ)8nm)4yA3yU~8(ZMH^=J0V zO_hH`P#C z*(Vm^FS1h#?tuH?PfW}A0pvu5!MFV%nRA?&>%P|s7Uz9n@;MDKGt&^3_4>ey26n=U zJ)#EP@jY83@={{0R5G9P?--xf4#5t0_^k@>*r4)yNJtt?D)w*LzE!WFaKJvA6rSmIh=^8+( zF2$sN|0UzzTqCQ1TeQ;nC5t=yQ1n0r)5uLPSka(rG7DHk5h>+tQ%)nzanvTuzt7pa z3!QZNum|t6#a*P;GqCD+!MC;@Nshb^c=owlmQ>h#A`*~onM zLbe>-Y>v~V?_HWi92nc&YrhD%)Veu$<5%!rT z<>s+PR(ClywRSSp$zzop4p@D--c9?q<+7~P?)<#CPBPzOp%NUhg$D zd0I6sw9jUZCBbBOSs0kiVAk`+3r<6?MASkWdxn@+ z^f$VCRe^@R=b43L7hN}B$RFl-roLIs@;Up?%HKbeEu&WQGOXf$yvSfusHKL<2-A9J zFf*HHG{MLNns%qN10_5Kb;iQ#;xsla;{qkM=fXAPG`1~hA30dR0(-|)HpOI!crL1k z_c!mbKeJN#f-CKiDu0JLhiPTb7xQZtue!|=JOeqeQJt_M`4(F=%@FQCZGghI6h_KU za4zpP44IU|s-45Y?)n3;jJV0nqwm1l^eb?p@dj%iUILHW{Gi{RFcd zr%=A;6}HUtDNO$4Me{Z!Go6GCn6^5Bwr3@=%;Awx_V+HyswT0ug*)M9bp?4YN@SZW z`@-w$FBBA$!1}L9LYt7CM*P%DddV$a4OPKG|hvytd>b`_j=x3y$>Vc5jbn=A&9@T1h*%Bt44l zivCCuM{HoeOcYDVD5d2IK2W^q0_${5qm?;Hu<`nN#$7l|OJwuG{#PVpU0Z0KOBG~K zi)2wjQi^Q-3iHmKW4AX(@^J+nU{N2zKE*m)LUA{Im=M8kZcpZR4eWpl-?MCfRX<2g z`2uU6hqE8)yWrLN3eYkSXDmDtLayG035UX1>E8@6{T&Z+C82D3$y3;}+Y81RhO+Vj zHE?vxWLUpGgiSDRg}~1>T*jSXrZhpkUmQ{3CiDtspRS0W{k0SL@>OS;?TTj5o!f&> zCIqqXlRm)KfVtGz8puX}d<+ij{b}`#KsI;k9kC~WmF7gBW@WNrpz`+tg*61Q)dr5R z@ZW3tH8y}PoNNHwel}1a_fyPwcK}y9RrFz1`m?W!=9&4q;{9!eKT~o@=S_p#NzKiV zDVPkURYCQXe&3g=9o|oWe!e7g9bdM=G>XQHy!)u_KFp-QXd4ZVCG(ty%HjZ0A}^o6e|ufj8@Z)hgzKSMXZ#UTnk8Zt`3BDs#bKPxfMQ7hSMf$_<|*`bH0m z_4}402;m;gs`4Ez30VZ;AKh6$c`^UkK;&mxxwHAow`hUmbubS+!D811Q*P@+D1UvN z4H>?g98Xlkr2fa*?*>hp{JjyB>W;F2L&y22BCn`B{0LLp>1lN#xf_;QA7*5GpNnX1 zgG1$RZ2BS#;G90g@XZHV#Mr}declTQQa->|MPG!i{@G9@>}UI@Wx)}%OEAb`AFHw{ zhmNFUVAkrww64^_GNW-&7wp~8(3F+M&@nN-*muiJ$r8< z?#R>Is4{gei}kXkwIl0D&UOv!({h}Yqn?vug9B64zf5a)2{bBt6}!1Ahfc>uQ`dx* z?Dh8-H2V8NI##xv(d*CjvStKzZd%4(ShQ0tm%|%sE@i=Yy6LIk+DwnU#mv>Olb!~8 zai>-;Vn*SOq`X-NR()H*Y#ZLtn`3KXtj~P*X@t1vZVdrF%XzHz$TfOee+w)=%w;~x z0dzF47<>-QVfI!FXzQl;kgYnKwTzOd;%DDL;mRy#+h-1c=zy4;v&xorpKh>fU)2pq zdf2cK-D7l=w41ZZo`x=Y$&lie+DRXehi54z!UaJwbD%$UAz zCxm(h^I}34YY%Avb-{?59Za9UwJo_!vA1(x+mrGxjz zvd{BGPTcttYFaji?H@541{8lF*G3CAHR2by^=30oIyH)YgE8E=!YDpkdPqE3~e?1AVLUt#=|+)@U!UkwQ~w|@p5SwD#V z-G7gi!_U!@e*;)3R*F5k9b_NepJkhVC8?7+#SZDm>Q;Bq`{i+b`Ac&q>d{0Ueq{O+ zk3Q^Fu;|ZqyU6)Sdb0}euT-Vf8+P9`Wv5?M((j4e;gOw`S#$U4d2|G9|6{_8$`Wbc z!gPp>HD-pvCkdUOz--Qly)&Lcr~7?^=_LlNf5A7t_IL{fP|Zj~;6{ zJebR>5k0o|bXbpqE-vt2Gqf(&X8r1HVddP9px3C$CfNEylwB#fg=jF%S;>&pDe8)+ zsk4j&`EX12EHu4SV~S6!pfPeY+~1?hI!89ZLt_aHRa0T{H676Ibe3}vzDd=_IdRe*9Ke4PipJ z=$+-Ph6YrLbGvq$wTkBidIi7i>gms^Vc_$j9OTcvq{~lTp~>tSME1+2eRrZj(fbJm z%f!;PSb_z`k0Jcu3A)|&3{*P`VPFMEGMTktYx)r6)L!t*WZR%|Q$Fl*D9$`_up7=j zz6&#FIdFbrp4)1rTv$I;8A7Ihg9F2}U`F?1SnK%?mOJo}oPHX5hZaHa)O2WVxDNUr zVs5NPDr|8Sb;bE-pl0$daH*_@=*O!dYSRtyv}l6WE*dc7;#Ei}71ZtSS@PaYw26N6^I!gkTd={IiEcNqZTfNZEZxDcp1XX z=E7LbXlj0yBlbFNAU*DYnCJfz)ElP2NtfZI+NU0x1FXS(*L&X4p%u#9p5TY>9hsw3 zy8rh)B4r2X{;%_Y&o>+8AuIFS|DHn!*}*WykMPvF2)Fk&WjnP!;wYjBU;i^0E4bmCq-@gV z2e@+43|?|UD%SW1s9|kLD-Id4q#qCPRE8VL7-+Gj{R?o(^s7`@B+r!Q7vP@D<#f0C z3kZh`u#EdoO@Hr$Yf^#8`%@7zLLz`GFF+evJt5`UeE9vZ09!AZ2rsWya>CGuxI)`h z(3x<_(q-vG{4iP~Y;%3Un|nM&=Wab=qcD>SZ#={eH&lfKsUhTC^$@$){i5mOnMzaf zk;tyCAj_3?lxFb=fN4OWrxb+7(}mbG z`5An#ZXkgQQP|rh=4uvDSY075%IwLwXOXl{y9i@_b=j0#OGwVT2urq^u!@N_e3$6& zJHAWGBDJ0P9^112Tho&8Y&`qegbi{Q^{e-?@#=m(HaTJr+-=Ino2bf++rnU~VGeqJ z`U%6F@*rnNiQSe zQi47#3D3j!LsG#x#FlHx6Fp)Fr9!4KoA+(V!@Ea}1p5sJ)LZ{98hVTW$0uDWb<$mo zOjQulgOX_aw!8SMzLCD@mr;4xU95F^M2A;)(E7Z)IIumMs&6R^Enn~Ao7nYa9;G83 z)w_qk*2>V?YsP}A$W=e8QBe!y||BS)=Sx%-OKs*uj&7-?=HOzF{V<&av}=3hKU*2 z)vU*)W;4NYYX+L?s~k|PpqJ=HH~$2AUovpbw^W!OD#J$T zX5s`3U#OX{&dytBiX5e}u<)1xQ{0k?vObr&4`mXzDxPHDh-7NNqu0j7GdftsnGW702jqbE5jPgf=XAdxK|sx2Hc*-kP7;Xel@0d~aF-de)(Tr1_eJ*FBB0iUifq1WSEXaNYA zyfBXB+ZBZzM*$NT?4UOrwS^%f-~55BI$bd`7Q%S}Q#uFoQ^bEyR`k%-zTVCqv6Bkh z)w3}2mnm$lHx!;*W#PG7M?p75Qy9M?3wu{zg&TSDLU=$HZh7+@X2pM{j*KkqKHLSL z?mwVKAG2`k!Jf?J>v`hUvT>7@E(@EziUwL{<1qshre@H^YtPTdI$J5byWW-mu{q_x z+I~GW1xNohVSNri;a29Q;NXjTO!w$)kZVlAuzsp+?8`7nGPs4)Ykt7weRpBb)LUr# z;U#!9eTJ?bA~jO$1`JS^XYrA@u-5T7JlL+umK5B=v1?3WSd$^^*>(%hHLm8yitiRL zy^T4;Ci59_Qs!uT8^^xYr~E)8rn>Jo_F8n1CNV9R5_21a&RwCtvI=bJ9 z9aABGNrPqhvpcwSmPGK2%Ht>fy@R!b^o7b<)2U`~DsKOyD%5)glh@)@w8h_~;F&}H zMPFOMy-Mm{QA-7)->rPwEgJMiR@hRJimIPHsCSr#pe~<=PA&b(!^KcY9hrs~{~hH^ zXGn!rE7Nf5yxv@3nN(0bnTA#s>M*<8NJtUc<(f6S!K6b=aCn=B`)m@SL|ai%QAtNt zNf~UyCdwR_j?JPU{p!Pqv}s*BhL7pV`aZZo1_9~VG)k8lXsx7z%yc|D(S&JUZsM!U z((%U@DI0us2j5wr{NI|E>R!RmVof%Qeagj6x`I-%CYKb<0sF02aQ|gh_HAD%)StP6 zQ9u8HmR%OO@mFxopSRGvfQGSde``dXHC#4>t zpf{TAtn?aQKaxbd?kcd+B1<}bV=1kh-VCMNui=`f&1CSP1e`;!Vf{}9;XpwmsApY6 zgPvN#HUHd`Bo%a${JHMY*Kx&Lsc>RUL1yHN>zFmkL|7Qy z#7}U)j;Ds`2^vZZ=xy?KER9nYG{=O}(X#8fz2y(R)XO5tkLwsGEA}6%-x1&Y2CflL z(dxoqT4HkpGv|cR#1>VdZRZVf_BxM#+Ug0X&)z`O)n9mTTN7bW?hVwhNy}{eC>8G4 z-N1+?f!ur*@f}dViKgrOLHZp-p>y0#d@%b6oO+`v1UTHp3$v4;HCI6x>~$0UZA(Go z*h~+v-9)wf;(SJ3^fHy-#KX-BEMY(r>HofoPwF+<>FmSwpl=G^jW%TF%lguq87XKJ zC1D14;`quQZHczTJd;!erl%6Zz)@h@%a5<7jNBd%xX5q67lVjOXT)NNr_EQpudw9U3 z2O2_;+9ZrDxCt)%bXREM~ooC4~Fd3!d z-FUdu0!rqS(Lcn5)$#B7xn;@t-buo9tYu_u%Yi6QYec-#{Hq2me~~gI|d8>RnfoUHPnC5C5)ikRJ}=7$XIv@ zuLp=dZwn1!*0D?Y|bMcc=UHZW=^cgACa>1jR*O}jp6^Tsef=dc9fW~ zZ;zjH&N<bvS)Ah9gBec96#aW=aco%)Dzt;J_i z&mkY?UJ%(E2hZZS@iE{xU700BpB23ld%(h2o9(`T77Z&*L0;L2O{hPMpF4s$Z?QhB z^@>2()%!9_nx*WuMFgJaOL&7u6Lw8xAOCbfy45^~HrHv_ zD0w#EK?J&we@cbdnndnH1ln=UG~cxp%GA$c`73$h>dLE-IOZI#J**-0?DT}A%g*7& zsRlwrsU<8vat<>LC4!q~J~#C8IgIa;3c~#URx%II;noU?a9964|El2}%JYUo@2b9Z zO;hyHg=q;;wV#fSi$s~zO2UE@mubO@NX!#;Ws%23Ez_|`+|c-nG;`~yGd2=6o6~5M zos96{Q6x6*3Zfr3)P%4mkx4yZ9tBO)6EvTU}1S45AD|E-;h-Jv+_J< z{G7{mdrF1Es&x5ziODeQ`GlcUBHQVf5L?1Ji6p?0VjL)WVXF8&@uN5`0SfD8&bDf{FW|Yv8NH6 z)v8NX1sAYqrG$-b5914K1OIOymy7e%48q0Y_dcwsh?~fQ(Bh>Y>ov;;emDi8{wGyt z(klc~f<%UI#&4L>CkLE_Ak_X*1yN=-U|1J~XLsEJTWwiZsCfpD&OHfJ3)I;Gb_SJv zM~Ye|u~)b83;yP8DyJNHzxJaJNS4yjuqOLBZI0L_z4+GZ}UW!MJm^mXNJ> z0Hk%nSmACY$O#5erWt~rAyVPOr8%5G3&HtErGinMEpM|i1gCB=68zK*NbXDsdO2wc zw&kvrC4}JfLO`6wP%?GLL?i3O;qAqTVJ#%nFkTOe+ivWJZZvVDTMg zVfa(beScT3E`)Ck!{nGdFr}}ofM>$+c6}9`>QO@5=J7xOdbhoki|DHF72^D`WM|6AWOk&`=JM#9nyOSwgY zFJ>m|v1jFW@T|@kZ6>KQ*cb+LwEb|R{ZD9W&x1!3{LsMb6#Ik;lIx}pfyL1 zm4=FczvBdq7^caV<@uq@``*y&z9Fk=@WYFdTe%5Kq->|?FIy-b%WuyV`yrz5tYp0o z$=x$zM|SullUJ$n9;_QwU_-3_U< z;<=2_^&|j~x`;jJ9Cg9e$kNQBKs2zCvesgE-m2F9|JKwa z&QQw(bDxOk;;&D+PV~TfS3OqQV=g3a@W2vhHAW)4`jM9hHj2IGzg#NRCVJqAgeV2oy5+AnY75Mhu|~$B%)k6eYR8;u5UPr<2u*TzyuxP zsn@A~l{3lIEPA1;|4#An?mEPhQfw|d_}TvsIaUS8XPLGeLsDpqCBc85So zZ#Ue#;Wr!)&w-=+-LP|470|gF81mQ+WyG~AwwGmPeGZ}8I&YZrPo25A9>O1UhC`B~ zA=4~5gjFAdIVUYCOEy1@O`4xFFV%@Np96>S#~B&gamkpKmK?_0hc?jl?K*6E-y^s+ z=ORsZQD*NB9KrdA3MuJcJFF``f}S-^G{W>L)bs33`ASOt%V|K!aU5X&fZRl_Kwb86bSjG^)rUQWg!YTv(iYDG`UH-+bj$__$^djd{24S?l>pxAB2dOuOnOB(WZYd z*0S|9S%TcBRN1ipVIb}8jAo~P!sMhp_`Kg4hkkqodo(^nR*5r?+i(+Bh03w$emii1 ziaX3z(q#UJc3}J(b9i^fkR5%t1AkuL%~i~mvb}?MqS$ri|J{?at;cubEL$zw_Rff{ zeI@dLue;E?$69Rph+WwAI+3*BiTxHYktw{pjFwk5g2S6#cy@6oJ&t$?+s5q1BCc=H&W-iuh4@Rk*3cd2YtgZy^!Pl20LW=fvKDllW z4sFmEJ|AEdGrTByw+X!HVzI^xf_Q?U}L{hfGYTSwm%n z_2>5Dnh;;w$kc^}Eql@N)M!dOV<1eMxet9VMe-NFNQ80G`|#DGCsrf>Nri!(`^0RD z9F0jbYAS+;;5L$WJ5yBW3Ci6up@iQl=g4%fBdI{a?-Z?7IfX zKQm!#e?8@f9$JIyZh9xaMFJREnG< zN58drH@^(VEp3Ef#cMI{%WbfoEz1IXtwY5XXJCf7XY{jQhf6hA!nkF+j1O9e7EKz! zeKlhC&%|d1FHYM`%0BC?$5EpuW)AF>vSW+ad6{bZonZ?S)_dW5BNoGzwv0I$P{*P1$7}}e!yW)hC7nle^3XOb3qZ2l}>kHGgrjX5ujTksvLwN7uMcq3$ z;(oFIceW)`{H=}XnB75NDj(8<_Kg@T>M--OYUuCSO_<*=i-OGlQu6*ySZjBlhTiWf zEXv%3#+^H>RBtRCsJbgN`#$I9yFQ^k56F^}hrA6=j8f zN?Y;f&Sy~ntbxjHwql6cH#n~Jlmh*>;uAGFmLh+PmOS2y_uAFi*kOS*P<z&J5iH~M)9Z0xfTJv4tqzBrFP=DHAHe655i%~}X4S%@*eZ$Y0^vg~r- zMVRU81rsba*wurJP);%wPFWbT8&4MD{RaWun7&eWwf|z=ZSXVmQk9g&99oQ)De|;p zzcD*qCO*?fYBtqj`vxvS{gs!fqBrJy)?DW<0@ z3cLHo!>6N5v3ilV;MIR8JSty`J*38hQ&}(Ihb+UlSyG|bVRP>G@ns0(rNVeiS3ddW zGQ5#sDA=Z()45^G@zqdGq5S#@a&upf7e2`eUyj`nxgpEZPf|~tqF<8gh!r?=%{@vP z_JayMR^a@Evn08uBDhzsz;)USX#7AuVfx6GSmyPX54>z5sC%u%k>MWtrmoi7M#yJ$@vzH)i3br^>=Uh=xZVv+#;|uUb;P8tzoh!W+Mg1&4E8+(ipJtX4J^4$X_V z^6|05^!pMax+0EuerJc~Wj@BY+%H zw{1HQHP$zYd)-r75;G5{s4B7y+eBK@Jr9*@v{+>59$GecK2G{##Ewqaq$vOS_*q}d zil?064;2nG zX3MbyvMCT}$Kj$Y-{5thCt?mXhq`9Zp`UpJRF-o1dQ&RAE0kf*nt(6F-jBbW8v8RJ z@TBu<_^znSPK5v-cGQ9LJ4Vd-1)zrJDK1b!$`bS$2Bs@!+We5RQOg)U-E*BcJ0)S6 z=NS6L_oXp{A+vtX@JqWhsd#F$`x5c$FeQ?Ve)MEEs}U{73Y2yBFFd}8Sh~29Zmg|^ zg&z<Z1X?# zYX2l$o_B#pEbl2S&YXmUWnCzyMN4@0V-h}38AK{G428LDGCBlg@GIs>golSGLDRZXb>NX?hy|WkP`%J@eKP5~$<21kh!I1xI#cz|LV!bk9g{L2L zL3@Ux_8mPoNAVU^ z6w5NtzM?nK+Y_Gc)?fy1!_lj95NviZWJynlW5)>}u4#;vjT<-ur`0L*T4JrpJu(8n z)GCp#tudQgJ^~kOZlyOR+U(wtkr*HwOS4ZXF+4F6TZ2U2u~{qJel-%kGg_#s@G%S; zF$!H5D+!i;V&RhKC>-%rTS)ic3g)jz;famL!k`poxMpF2@+DFsaD*CX>0^O|dP#*_ z%TMyzZ!Pe~WJ96f?LjnV+-O|lr6Kr5ds3+XXq?d@EBq4YaBn`0#<^*=BsZXvw5`VA zykohv$nh6VJUs@7t_r2V5LIDw%@}OHH%ruY=n0`P7TMKO{$Gc9P7NB1$+aHo1I2q^ zOWjzExm(2bZ#EGOCX7Q1Q(KT!>j`5+#^JcM5U_foDop<}4*$K*feQKGG-u*?{M)k@ zTrw(Ye%N?)PL^dlMYm{i!+11x(qMtpylB;AOB^xHkaeydLdShYe`|n*xvE^_9~Vgf zThlIy=*3f!FyD10oSKU%zRT8Q%Y9~nPN6CGa8+gczM-IPW`;4QzuL|JZ(uaf{Lu8v6Ge zI6X5*BlC7zGPwwD4iY_&bCiV*T^B*-nCN-jt0UYmTo21$^u_3WV`0znf86b%{g4yS z;D6JKtu#bFum4wxaJ({--%-&IXGa(am9t0F^AY{geU7@&F6Q-Fd-cbW^JIh(&(i4j z>;4$`_=9-fsHRb)2jGknqMIuJi1!(QcORdore-z4?%e>4>2FP`xAcX&aRc$eg**J- z6B5Dq)IfaoaE{d?15;t#r-As`y^gC~XCi#%2H{J72^s_&4_yc6=Tr za&;fT$+;qD*LpCzhkgZ@f6vJ3lVh0^Z@|CF+BjRj1rq&ApkCy<)+CEsz3eYg{6HIbNYi2MXc=}@Ne4R~ zhr*YWs?5h$2iM!L2ggJmw%%U{-M1LPVizL@B|3OudMM{xCt;czx)^8dn~^Eb<37&Q z#laBIhu@O0Tfw?m8)Zh-J;YvLxh~EVzh$$}+H9u29;!M=Q0hSyrm;*9Ke+Q0^86pX zI;V&APhOEmc^zDOt%qx>+Gy~KBG@h!{gS#0!kFSKfNS*eL5#W}8{h*Pm-JDtLF}n> zHt^}AKA!n(ECj6j&Sms7K$QTgpz_9w^WA8GJw-i>eWnb*B*_4WUN;f!6{>mZR|A}{ zC+_EufZhx>#65bN!Xhp#=hKfCLyUd%hHjgFq{Pui zcoA|bv+5Tu-fM(EqC_rtsj?uOZiI_l_fwFEmT2=g8cqnaNE!eY)CZ`bDXgZoK@ zA8sPQI5;3PN$dlh%`!&p>B3!gkP5^88l#I4$<)&@ zOh!Dr+%v&_0VzUK^Rn{vZ6ebxdpmg~!xcxmB9`01YL&X)aTcZx_3lz}n zU<%CbCC4fxif9+&0TI_V*g6+Q%sDdvbbJk2W1%9h8t%dAPnEKRy_K-3QI|K$kurH# zC3GI7O7_O$`M*R754$*%yPG!C?Wc^#Z^qFf86_6(ri@1hl+yI9W-(h$8TX2r)|1qV zA$nj>9MPpD9MHN1BaimP^L9Fd-U}xvE$@l;*Np|A?Q(E*s0uEr66d*>zFLiUS3!C& z5hSZa_?8M4eD}&g2rn5ymq)7NfLH25!}*gm!&?<6{FD)_bW`cg8&xzN|A{`PzoyM& z)bN967L{E7Lv6ll$ae&h$ze6&=zBFBJ7y}SY||GsEqmdDc{#kzREdxj&9t~C5;W!Kra({w%q+X6*g#K>2XaqX3ue2KSdLby9}9bsTqy**2Gtt5@t2%5`W3N ziT$6JGG2bnH&&`9VbPBtbCchFV?zq`SZI$~u-3nsNluG1+!3MRY}vw|?fnHl-nroN zsfDFZt^~7Zwcr-m%Epbm1*2PKnGb7YryV@u|M7I5@m#)P|0nIzAfjleCGEJ5^Jr;D zDJ_-8uc^J$j>wK|GD4YUWW;q`h!jaEN=1Z7X4$3nKkxhX`rpsK55DQad0prCJdfjZ zyx;j32Qt5!7N(&*5p?xcSdwcin>XJ|c%rG!b9-&~8-miW*l!o}2!%n9C^?+4m1c zcKgRRR63LL`2Nz6Tqq{H{#T{L`VH=JQs19Ds6k)cgD ztoD{;A1k8BwX7Q+?LUZ3eQ!>mX3JrInhMLQ9Yg&t%Hg7yYRqNVJ@L}D!v9@U-Cg^F zEvCI;yUT{N^vYMl^-piuz#Du`zpjSFU2hpo9>AIo+QGf5x2)fZ?kx851F$nG;x(6M zc+;E%hZ>4l)~q6^-|!WdoOs7B6(&NKmkb-;_Kv*|@qmav{n$6t_sm~=Ka5$b$kKkj zXL{#{!^!EY%<rr_=?oO`Cmw#XGTFXfncv%l(Wq;)YnSmG;|y;WnCeM?x4*>KL@ zRAm8+vn+OtH`vXf!&R7=_Fc}3jk`xSisN?E`2 z&E(SiB^()D#=c+fF3AQzfEB@I%x&BN>7KP6OrP|Lb=*{ve(utTk&&O6EPuzRUzCA? zGs@YkbL!I6J*$LY@#XANxw>>`a(PmjP6ZqOX}ENI$r~{?xq_WA87h4NXQj9`UMY_M(p^)^!sLu+U>)o*A-vb1@G9T zISuO4g?%+F%4wJ2cTrs$TwB8oLVLgz=V8+ABVXB-{_Eh~OeIO>`&Tw8$N?7Lke8fK z*D~Y4DERSEPLl7eW%++{q4ViCx^=ORna-$#`(|%w^xrx*W1B3S%IgD9&FfjCQ$M!M z#Enk$XkgR)6d(i12jy*5_?{oD(=ZdN0iS;fY z&Squi3JVH|?etM%ay*}Hcuitcj`d^uJ=|fZW-@c`{tJHXNrT-VlG!A^_wd&I3+%E= zVIBF=ux_~=GoF>oexzLowaS5PTX`xo_8JEerNVaKe9V>&x+2)~TJbSRV{Yg8RAw~q z|JJ0jyFGcW;JYfbc1vgfj-Q}0(-oNQq9@E`QV8vL?8(fVo-mD@`Q(3v=l^{&nC975 z^1PA_msULG^M<`8ci|3rwm)U36BVUq-~Zrk&@ntS$|EkggN; zCzEwNQj<)F`HK_oXR*PiL#1o;W|OPYbM{?(fV4!{jy`jDZMUJa(uG@(Xjoh}^KUPw zq+g}9c-IRy^Swy({Ql7)`5YEmbCVVNj=C`bjP;i>nvP77Ujfj_0wT8@IrYD?_AB>iMkeh!6P2_K`AQP{!}?? z@xHxSX?Ym?CI6D-T$`cQA)Mvy{Z5xJN)_1_ zw68IWy;hf#-ulLnp?5UP*#3pa#=obTOJms5#cAZ**hM{?V_4=8clxE@Pb&0%$d-=O zrz?(1lJ|;OR`v9?sM9!H+SV4!OhQUP;0^-=#t(n5ZL26QoUOcnOT?X|X{QI5p zY-p$p?2+p)ZMw_nd3&USb-`~MV(^IRFQ|fTImPs@>k+$w-PpgzSPBYBWRqkDvgpHB zbjdJ@ogJ*g{OUDnMRgLpbVrR@#6*eZ$8Y@KntF`1Vs9#kvyRMH!isz=mSUsC402Y3 z%}Q%F-**6;Y-0nCF`?B1fcI?=gLvXj8*XuspvCx|%!L(k5jXz+|Mt0p3%!AZeZk;{5 za_WY5B;Wr}9dlsPW;e0shZ-Bw;=qj73?+3tRTg*lCi@|`o8Cq$vb8^NvX{PYRCl!> z-`5@4%&r8^7m;P2GEPj!?+q!us)ZGnPON)x&ZbSvg=;${s>g7`c7HY} zSB-5Q=_`&b-}Haa)p};cP8JVmN7m*EjviZ>k+Tx(8=(i(yp=uO(vPh%c83goWA^${ z7Yurq20@|QSNTS?1~AKzZOaZ z#`R=#-XCO@1+OU7s1clJ9%gF;+bDbBb7*%s!p`>SBU#z_!Ihe$Y>dhfDNWiAOLUL3 z*J{HhlY};5vEKJs}o zZZ2sa9V)rxUS_*Af<#wQO2)SQt%>t1@@c_%3s!92lc@{~q3Qw)roB>u zl`cF%E@qZ&c%NZxZiqbT{IFz^ztz}GXGif#;h6tj)4uQS2CtnmjztXQH3Xj=;r{jU zY|}d>mQc3>%0FnZ;M9Ih^|UMen?8}vnfM!GLQ`R=%_Me4zZgP_t6ER>w; z#ta&n!0p&(*&U;WFC8GtS&9t zc~U(5cRstHr6L{fGn&3_T*y`|9V8_d@VipvBDQl-cd1WyB&Bs<%r0borOshR)WdiQ zbC{GtFCu=>+_2%*mpUb;<28-e;p$2`)>tPud5LKU586YlDJ>hZf;Vf z@(AhRKt0C#CJ2A_s7c%R>$4@Z=0kg!va}*)HLJbm2>MF$(&Qlq>>y{lpL+O@?!N`1~z2PQ0BK?n<_##vL#2=*sZIg zILW;f{^w3-B*X_78J5HJn&C{~dHdfZE5UD$3j6Q)6d2L?8G1%2u!F~rz%=t}XxPx7 z$=f(Xy-y89eU)X&<#EvZvlcYY)WDTt@8BEn0nfOU35uN4@iCzZm}MYzw)SG8Vl$un zKLsoMC@_nYt?)WT4F;;HGM3*C>knEBRSN3tljaYeN`Oc~ax9tqzoxIt zzU#u^)5hHKN&-E9h-_e>PK7UUC}fNCofZ*-JNBsrg+z zz3erR8Sq@sL)rIKG4rnuCGBb<%5u2WYOcbSxqzh|Sj{|R`+dqc1C z^MscJ&OsAD8+;k158Br*f!p$atS-VGPMVrQ=y9I+P)mnuEenv2y@RslH8AGO4G4{i z0_naSTkmHB+1t$_oeg3k8|*=L-e{O#r@~l&N2nZmRM@veopoj0f-C+r#H;S=j4ru? z<4*Y~7%k^M)iZ%UQ1#?}GlZA(EliR?cY;fq%TeZk;)_Qx4vcwmegXn_MJGk3jkvZ3xQ2xMTSjPL_xe-0+LO}^M3{_{{j#-J}im!w% zvG3{Xt}pO8pja3f*Tu65Y0ztKwQzZGKgof40KEDpr06P1ddSa0N4kVRQNtzg>QZ5v zWj9!_GD32HFjeRCt6ng1znb)RPn_tdCJzZ2{EjjiDf)l{?A;?Tt&_b;Cb2`o*HlLO zzLEDv|ER(5L*+DspLt#_9|NVmi3F>EWbHBmrhRv$JGK3#38k74;IWXdJ19%O6K29m zg%oj;v6@tPQX90hQnWV?86o9J2*1PL2=7vdOSV090r@ky)=EiIFjx+~_qxF~_kPkL zFMTkmNCiEu-*mTP9aQbE0u#?-`Zjqp%o*H`O*$AyHfM~%Gl9?WrCL*1>VL5C=}_jm zZwAGj-4B1PdERw%oY>#)t#HAB*UYL@Ve#M+q5WJRX-l08yb3B89$ZzBcGfS0aGfuL z>xH3`lR>8Nw4h$tzCuMh8!|g_``KpU*_R%L14Tfgcd6WT3|v&Jhj}lr z(JjUCpwRXcwnfjRruYf)d#Nl_zMdiOFrEyi`?|3sohOqP^_>b=SIe+u4J)B5bsDJE zv_n^d0;FD?365{7KsReUT$?usK2+v{20Fu{Y;Bl0FCJD8j{ING>Hl}6{?B}O;vOrw zH{%s-GRVgP3qoMgqeMXNIhAYY&*^p_xc)m2+jbVgg=6Po;@dnl+xi8R9?XSl(Rpaq z_#MW-`677OanC7t`e_VUBy2yB$9cJ(uS0@kgi`ocvZu-F0(uUBYTGbl`m;^<2z~>JQ@_8!5l*CE5mf300isUij`M@6Gks zS;U$ACGjtDvg>g%qn-O>>|Wx}Y4SA3wviOL7d89Q2C{zhiLB?p#Kw`fWUwWVl2l*f zIIUoc4ojluA36ACiA0xH1kuZq9IRW%JMjPJAKHopUMO zA_vpezmcJ(ENSh}!I8;rv`fxIytX0-53lC)`v-iJVkhU|MD7VZ>oQ1q(LV>@8Maad zJrbVr8Tqc92GTGY3?Z*xpn~paGIUxBM`B;#@zf$3G1e56-Cm&1nJns-!`;beU*NeA zUN@Q*21=V>Ab17RZF>p!>%2e@2YXuK@)EpMU*PPU2gt2g2}E>dW30j)T73Tt_?Bej zS&*SD&iXr_oQ)wzT*bGgoWbXpjmmA#N&0&`LE&mPjx1CX`j&M-)sAe8+9V1Mt6Cvz zK{j?gP=Hqv4e*qES7XzcLG7PPsFck{=f&qiWm^%9`urS!Zg7Rwe>36A)8}|9F$~Hz z65wa>bDZBZ88n9kf{XQY-1qk-*!8gI8TIGbY+M4tXZFJ|z31F3@dcJt&w}1lpQF)% zZ?L`Xk1%-PbF{2)gEen&33HmWaGgmfl%BKJIbE2AzutF%V)x-a>FA2T5Gy zm4!vu8(`H(MasXJg@+R>A-Z@uUD%$5xqsh+=b8(&Xkivsxn+WEkt=D8%|bCD9xP{t zlV;B>+~^koWfziZLv1Ez@cO0to?OnP&P1i%`#>+egydr~u`YflTpCnEp01e~ckq`m zCx4Zb3ZV zILn=|?a4H7WB~0ldWOGqa>?kgEsbE$@IZSBjhMQZ9;-jYHA`x!c-IVCEb|Nxhkv6^ zuOH%r%BQG2w4J)IwikaseTpHRFOj%ucamo4Q#|vwgC@&r2up0AVo~2#(w&$tEI!P? zqtrl)|5JtutGORmp^_#pT?I{A{O`+ z@Ycyd$DKCfgxT$IR5b(hdgvtuJ9Wa+t|vGlaf4E3ye*Ef>=s+D4e_A z>s07eXBtj(u7IBp^=W2t8oGqNfo)w^NG>G}t5u%CX+;mJxRZvO{o-K#>id*+Jq?eC zaehB%GbQXx!>eO#pl1j7C9mNB_SH_%YWPUYG}CZ>kEvkBGjPiXrQ!SM%|aBf)77^= zM)mua!nS~RswsMm(_@u&5+u$}OnHoB2aFNz8an8f+he>iph+xn`A*UMA7jCRRrGXb zCFydO!mGQMw9JUl)Qo?Oy2o!*a&kIV{7l89c}b*rGMM_jOvUqB1!VQ(I#~y#VtH;A zDG#4dO;=K}dK%~4xX6<7)>Q0_Xs7QV%*0~NRP4hYI9tkZ>n!YDn?c7r1wReWqdDHT@b^>-PW4J6r!B$oNG}DOANo`Brc~HI zHU;;DnUQm5Aw2n+jJ+)8(Z26hu<3m=s%Od3i_#{@yq}Cl7OTaXXFFi_)nu&cEhn@y z?up)#jLkov3pPg*rzO z*6oM__A8oFxDJ$KAMB7ICMpxeOgGNW}As z?exdPMXZYBZd~r2`{QDhwAVcmhZJ?t(Z}jS4Dyp7p?B9& z@z4+M81DB7r&TOT6hb`DQ!Fex+YG(=jK5O+Sm;Wug<)<9 zxaZGiF#k~ov(6=O#)~EA=DvpYMhUpen|leKq`@UfKo8!dZ-|M6NVNpqqLKlHJH4Rp zZ#<62LTFbvhuIbJXn(&PbWg7Zhm3d}HMJh}x~V~1a6GQDX@PG{kn8Z*3)}OpC{?H{al4e7h*G5RV79)_`02beiAB-Mb%3 zAk%vXG$FzhpGSM;n@C0vXY6znb8k~^yXGtTp5clCx7dtZSJJD z)L0B$-%UKjI_Z~ZEV5I%qP%GfHJyybn$45wX2n-Js~?N~3J;K(Yzg^Jh(&LUTeMa` zo6gF`VquR6%HqG3zdt?1qG@SVbikLUr98y-PYY<_y6e>6=OOlTs~~&D)#P&FAujiB zAjKt$lwtG``xdp*rw1`&kj_IKx2}^W53NtqRDFo=bhua6{EN=+t{C*nYo%T*?+dyg zWAMlNMtX9oKfFwh!JB=n=tbf}_!}65b+g{nF**tFZp7f-!7u3PDJR(UUkq;5h^OqS zoUtp!pt7zP4Y`&9H`HTrit=?@)lvXyvN5=J{YDCY{0ZVqqw)F0AryJ20p=t|;|66< z@p)|}g>pr0aK-qRASV}vO}jcF=F2{v*3XeBcc%l^ zm}rU5o<`zv>lSb=%@!{PN8+Br^{}{5jfPl7;{m@88TWBx`3c%?#P9ZZ@8h~Jx9DoZb2@2pAM=ld z(xTmu=*ph^I4VXWcfUZoxA;CjG0r6u{*F|Sy^pg;f252Hdq}rC=VRp6kiroy600I` z-umy9R?#TxJ&Qo_=X1(iOvN9;5tzamWATX>6CYbeVEy6_YLhn-0uMysx694+RliK| zTM>aPR@9R3BMpd~6oFnvrSzT^Y~>r^;yUA2V9?fDE^8^Up6q&%rK@bQ8BkntiGTqbi5vesiT3-E*R z{$ZG+`w9XUSb;}VD0Vwq2Gg3iz_wSR*mA2D2J9LKoex7X-K7~KG(QMOTthKz6ZcGA zSS^TWLb)e`^C0i!Cw|%(ite2Exnz%-SUxute@x=8$kt{tb!aF$tgL}?qo&iIWc&0x|$XY3&E#<Cd$0;S!2Id5`Dc zzR~LIzr{N%?{QvP2j?Ukh_grC!$ns*Nxv*#r=jC6R&H&f6Ro+z>Q{Gh+oZ4b_Ln9k zgx$rXx8KtR^^>sa+FkT%ctS5!yy4OMyZGo?2=!W!2xc?xqThv^w1T_(a{6*gqagP#pxw&u+1w7H+3vXiV-`(^gS0wNRZV1#-Qo?pEIW>Y$7=(ol0oe7S6H<@#N!pqlfd6i{!!B71u`n_KcPf2{ z^NZTWOtSzyd#Vy-Mz5rYTLaLv<27gmS#TG70A5K+g`ZRWX@YV9mZye;re!>x;9QFX zH9SB3CX?nD+(9e1qmXyu16_=~gVws!VE6MHn&Ef{C%ZHWWX*Z?NA6(cs6E05jSiZ! z>JCmTRZa5aY~HZZcQCCbMhq@&rNKY^F@2c^)tPd~RgOQdsW?OX4!k3F#~({ee97tc zV=_GJk571pbHtW=G_ohmZ69xRb7oGhp!}082#Rw7s=tl)3Y=r_c>oqayNw2GYaupR z13urmjb{T}fKELZd@gYogf?e&r}q+$7~Muoy-rYn)Sk3y?rj{nxD_H_i{fUb+jz*O z9*X5v=vccq{*Ek%!kY$kyT}`-^eu!vCgxO}5b}VWg8ZPiU5rOZYa@bn`^@ z5&W6znm|Xm-+9g7?{sfgm3Y(06Ron^DM|LQ=nUNZe4&$K6ecI0SMx-NAsyuLYNMe0 z*8|nOn(0&g2chMY2kLaMqtUO%fK|E&rfvB|Ha?r+Uyui$NPJCCUs}L6OAp+=gF6)i zZiDwe4|H~pqM-fSlLg?`+XM5*Z6NpNPhe2%j)yfz zk%?&?G-kVF$oMy6cwIAGjBv+l!&Typ6&>)`&K<9hiq-CWvlFZiyW=pcbHbuW?Vzgf zj^&SQg^INAkfG_0yPYOOXZTlekax#*zqZ4si=}Y3$qjXuTf^W3`EVuQ4fmD$flqWQ z+>LR=nHOT=fa`tE%W}iJg-_w@IuBTR+6|@PH!y1BRmj@lh6Q02&?M@^uDNbFA+jFU z?N)I+I?2$e8AulW zUD5V=7)VDFXv;Sj^wV;MecQ4~x4;Ew8k$01UT0j8;DY(xmcnx5&ve7f1)pCX1Yi0! zQtKrbymBmFD2r~TH#=N#;P)QFNa&;qt6Xqrzskhcr~G_A)&*C@`-vq1Z8W3Z88Zit zBbl07iq3IHccsI$a7Zz2;2vtle%@r5^MpR1cgD71aiqEJK9#KC-s;}@)G*10szx~D zsFn(1H}tp@`W9N4@ZZl7y=Z6dE$q*q{lU-nh&Kaoq5WmlIIdqP*O|)7_yX3X- zYQrt`cCDozJI2GDS-0>tE2TA)cf#$#w{XCgTq=mOgD&o*o~fQd@e{&fd!`f4UgS>$ z#Z-8F&k5HTTGHMLufgBk35`D+(4XXTxU|CwJFY6wUVir8!ko}=cCaY*YlAr|PWbtu zUDCuWoiM1~5$`-)DCFPnfV$U?INYZ~*tw(`o<=$1f{W8YiTi_n?HzI7QV5y1%pkkuChmG%3EN*S z1K*^ZIH0f*5@q_pF?Y_#c-IE~gPny1r*7iC;7<7Rs6l&>!A(q1;jRx)6R~{CO*9zs z9c*{Ci&4FAVr4}&+#4p)-!Be0UjIF$zB);%nGR^#`#F5naiMD=4p{s?9%k$br$tr{ z7%F!M^yE{i$9@N7Z>%7oDxWf!I^Zq+EwD4DjING%z@~?zL2F(eP4D4=UkvkwxJ@l2 zS8b1Wdu9moSshfEVvh=^s*_STbW)?6J@@3k5;M27P^gJL){fDpfpfnQqCFZ1n9;L$ zh4gTcJzALt(hAvR%4)I0zfKACEGUdh3+%8L=VX@MbEai+cBsDoJ-OaLNeeve@CvIU zOZi3g_>>(s4*o`}m%7n^dUn{Z&_TnW929-V+2Qy=?#<5Ms&nM8Exzg1M*3gEgtzZ) zG3s7Dop(}!qBvXJ{kDwuMH|5h&Rx;y%B614Y$52dE!Mh-WH{j-99?0H$ORI- z8gGlq=WOUw*eYy?GnZ6MBa2C8lpbc7kYKTc+ zI^co14UQTh7Z@`tEyYlZ!w25x?xK^Ko$;R5ZCaAVFM+PT6C)pA}yr~~iejGcLRNVeL-VL8mX4wz~}mwpk@71LM^**pv9Xh!ne{6(q3`{(??h)T?pzVEzTjC|KOo`pP8Mj+{q=dbU4@AK7FcJ{ zKsWCyLg+jToOiN}9QtjAqeCpX*D{9`{BOd)y6YHY6i1t1N5J-U?%me#q!kKJ!PfIS zKKgTvZk4=;8%M8W?!3wLG4v~}U3?us49*azwzNRI3ioci$0gl4&p|K>^N_R14Yi%@1rS{7?`2E zTqhiT*-f;YV1}!>M_b(bPW<@y8s@y?YxE`|D=KWY#)jq zbPfCW2nB6=MB|=ZMHjS%-9z)J_nE7>Dr_yxODLyp8duT0vk$!f(@63kuArXC9lmbu z^v(VX@(5AV8NR>g&%c7Iy`se6v{t&(d>OUZjH0X~b@co$|D3#!*4`{3*NvBPXt4{~ znq*OB&&%j<8cl=lL{W0$B`j2aPR1XcX`;y`EE)Qda7sVbMS`^P%c=~Sn@tc%zt z+eS5W!^Qrl7xDM?PU>@1G3m?ri>wPF&}1?&;-Z+Ia92eY~7v8eDYy;6S%MwO=6>NSIG z4Qt@(O;cPnp+KybX@NE!Q*=E3J;_6*6NXlu!%snT1r4VT*y(f*JI%ifqqlyC-*67| z8y3L76IIZ+<}9jMn}h72La=r{i+4u{fPZ!}oLYDmdk&Q#ZB7t8Z#;vT^coBrEWq05 z3~n*vF4_J|A#&vz)W6Al7Js?~ogb%h3wFT7GCg5JDEDz2@U<>{mSno=G)|9cf!{7! z;>4b(ajo80-lNl`d5=zE(dPHi_vZ;p-G2%bc4dHNcRm|7^b~Gr4~GHD@iZy>Bn}I9 z0GBTA=eTqd|H>M{w7>iuIrStiv>Xg3u?@7c`~z#X(^W+}}wK8}uYPV~zqo1El1pCtbQ=b1mG z>#4`k?&~uuQ*fu=$B$vj;$n)reuzeo>Y5KmX3c5YikeTzXv*Gm|hL3Zin#u>vAzusTq1M zJcP52mBrBd4p>`%5CfG}gsy&_@YLfVuG?H8tY6B{tDGre9H#@2Rt?vhOi;t_GAK8_ zfwJ2s*u%gN4(L9HyUR`RdQ=j`Ob><+Z3pn!oqWExTf_CB19&{70z#|wzBK`+jse+6w#jC5cu2_v5bPwUDGSp4yW4 zVKmRU%-wN_&L7=}DoM|vLfxG%j^Hluf(Oub>mkX!+Ka(2o#6E2Z2E1!7vJCC0S70Q z((2j#^DPya!kJKSzwANxKYl{Di*0nqdk;qTJFLz4ou!}t9=yKWNwgZ*PUe4i<7+ty8NU|h`6;A?MHp4A|ky9Rvb2{9P+Lk!hy|O@upWJoXqbBbv?G?2+wxd z*kB>Nj^Bd%QJpZ*O*u(z?-tB!XoWiq!^LdHEx60I4q|?)Q*nk7_WWD|z0&s3>N7@| zruH2Ej&PyznNIaQo)%`c(}DA>7qd=$&A{B8jH$B zt)0zeo3{}`7pUNFHI1>@h%0n2l2O@PN?f)P^K#s1;iyas?70yyN8YEPm{_WKvH^RK zOsANwKD74I2Anki4dp7E(W7Y_&|*jx9sRI~{(M@G?s4Df!O$P#yQ}MQz}F5srae$J zo46jg@iWB~MJ-|3TSJtSzLVzbM#1BvA^Ok$OzLZvg8mFc?9oz4r#KJ1Z|gdKZp@&4 z4W3XCyAHdS$I$B;Q4n={9sUWrO_|*5)H-_|o~gV}>$Vrb^p3Uo&&`njTTl*WiEHuj z1vRQssRx-0Yw_jL=b}8{Thm}IdaRo)mR58?(r*LwUvN>!`F7;t2(L2(Ull=x39RRrGsiTSK_hZqFAikO5Yk*ARD7Z>I)laM&t@S z?4m~oO%;@KbOk<9zD7i_`eX}US5V@d^>3M zJ}t3w!7|J_&1aK?4(lk(EyLjEHo6_{EbPx*ij70QQF*;AWZ5poF(0c*8Y95;)k|^i z<_}bra1^`;EyY=x+2m*L1iuQGpwY=hGSLo!)t*c6b3hPniz2Yyx&#&d?CHAKO9)k8 zg8Ih$s4BDs0?QZUZ#JFeTx#I#UH)04Su~vU9mefnj1BKEi$Cq!;o-!^=puV3(Zzw+ zw(51UP=BK!&FX+7k-E4mx>Oi^u^If2>!M$}2CUpt3kfrHQA5udw8~52Ve2B!kg3T!Z4gcYjsAoDdGx^x!dvf50zc*hmYyB6Z=??v#<=N!~Y3vqYl zXYf3u3$w2*L_NPocx}-ScFkXi*Oc1ek`OGM__qMV7IbpA-BX=CX$$bwpiW2`-b-ZW z3()3rD})J&V&|d-`0jiIWDXxf-rcxAU7-^CU0X#XGUj9AjW@7W?J8MV%tz-zPhkW< ze`hY9k1DO)GczlazR1nT_k4!ydu1AxXK;UdiUn*fe@$@~^U!tO2DrfUdnXpp!wC~d zfJI6jO_iI6%U|ROJ||l!?+IdXj~N2-J*D?G#3d!xN$Vnbe|i?8zihbJ)w_+}e_=Sr zM1|tZ>q*s@;lWdziFSUX1M3-9SlH0`_B{I2kD9BEx5Z$|prKfO}+m4Nx4B zOS>EG$QuAHwMxnJ>`toe5I7&WmWnrP(3W@s&p&7;t*=Gmzf%I{uIQlXXY<8^nF7A% z_w0|i7V5li)j|LEHaZ`6Q|L<2LH)JgsE^A(LH~jdp0WEv6S~cXC-ZdhdvP)KEHQy~ zayt0)Cg*khvxjfl+BmFPq9IO!;Owl8rR&1!Qd>M|ZPmuyKW>!YD-$vYYonXRaXM4~ z9_~Mxi;?Y&rvIx$V6|GDqrwQ(*QC|QY${5R>R+FX3;ASBIA=!9)$b1y~x&c^P2oZ-U1=V0tU z8xI?X!M~0Kc(!RaruI&OhJ^u8IdnF@uE>KW<80u;`&rm0x)lD&8N)>HS@>JO7FOAh zgKb-8;YzP&=yv$6utIef-a6U=vIph~9q(u23GRaXD6f}f;x!ZBPi}{oE=NwvGx4W(HE8WYn)`MJu2JO7rJJY7!*vGsNY4VbTP~EgZU(NhjR(EhaC$ay z2Chu-hf>2-^3I)(={Kz)am*{~VLu&h5{#g_x{Pv`PsfSbqqr-mj`nn)j*Exo3bF@U z=yUosY}_(Uu=vnHQD)O{fzF$ zJegfCq8g@!#%?aWrkh2Lf2Lx(w%(HK{zuNwNqa6jG`swPMV6t z)>hK1+Lg4fSQA&3HgUd!99^{1#7f?O^sw118fj^w)s9Z`j;PTwE}4P{`?k=JpKpZE zHdAm~)ECldo6V;~r(jW85w+Yt2UQJ|ahBW@nlbY>{PLcR+gK>6ynO`UHciGu7LN2z zd;#(b+!6oZK5`E(0qu-Q*uURsnz5669L`Qcy;E_bWo#=v)R=@H-7S(PMew`u`-z;N zut(_7=m2ZGi8%SK3=}W_2BVfw#JTqn{Ki&8TK|dY(0CL=w|s!p1rzY#NJnV=@dD;~ zO~5mjcj5L70`(me(Dw5q*s2{0{l`r}wLZ@wZ@CNns?|VzS_H96Ora`T0|Too;m^S3 zP<&PcryDjv^X(zf2Q_ff?-mF$Oc%VnY2e>1ygqfy;lkPf>NAD-? z5IXg;IA`v76jnCE#8(68-G^~_*trw}dh8%K&Ob@?ehxY(oawMI4qa+uVabvEbh~{l z-h1H#ZHZ}gE^#dOUvCMfmal2a(Xm*Sr3WG0x!y5uEIOR+4;lfy@A7pF4nGqi#Pw?< zo5(SkGpA1H^{=u0pyQcI$ivQb#%m_*yo1QQD$h0lDlNoK+=GCep7vqRrg==KvdRCyG> zY5Gd%4^O0BX(O?lUn|jt1abG?kvPAVb5nS*c*TH`oTJiCW^-JHz6m2xN3)*lOH?7w zXavse_&{S!Og4hPD88bkhqV&0dLMVxW%RLv3j@=E3h@YIrf&fOM5B zz&1n;ht&5Vne--zU!#Vfv$u*H4t2n&w&8faN2Sh^#hsw%IUH+T%7uom?~p4D$EiMx zpse~coc}TmjqYBDb$1G&+?Vq`n*88U@5hk2VHnP;O@NiF!eH@$Vd!r70%{eV;CQww zrq>t4Y7M?OTB%}OXbl|9ng-QNRB=n-cZgWkAdKswiqG5H!Drt|p|r2OlNj)1$60br9J-Pg7J&NXz$iY1>XH(jl*D!Y52^2g}Tsp&0t(Q z{2jFfodx@WgK_QdEb8}?``KP``(n=odiya9UO98#j$QycBqhU5!$G*_oGn!==D|OO zL3qpKKXSkO5hfH4#O~v!5*zy!hPV#IueTdSxcD7D7!JhOM@>bQz;LK;xFqi3 zXWtbC1Mpgfp%AvP1BSZ{z$WKn!8D>7)C~tslhIM2DC&vW0`^?tqHSYc)b))w!;(`_KGj`oI4{_)_veITAJeFl2?7?Oq$ z#BbrrynD+N78MP^894Op_*vy#G*>j9FO!~OB)qYgNfcTdbx>5o+*P4NDr9F3~)heP&P zLcdpx0wepO$&ZgbYkitdoa=`M;puSwp9@`5>xV}kM}yfm4om#%i}&IGJP(m-d|%A- za)jrc_s+NAKUXq@O)bTgt=$(Zx_CzWJD=MR>Wh2U{T6CtnrU`^AEZxqLeB%8l;+h3 zml-e(Et1k$lRoG*_?%?v6DhHoebCrM6thn7nO@b~9#`3jPV$vI>qc6~~m?F+@ z^~SF5`vm3* zKPx#@y3s|~6?8<^1#+lzigN(JiZs3y_CnP&t+c3jsj$(!7n++?((ht`MQXixUG)cA z{p1?_ZIi{uxygK9cnAEVW$}!B6j>a944T(vIoIGr2O%CxHD&RDh7ApL<9k3kS?s5} zpVqG_fl(Pf(RkJ@GF(yvFP(d0`?vgcMA_ z$e?693TGp_Kh@7B~S-!ij0!Ot{(!7iO9X*Pi@k?)-o3Jy%h~TH`NU z5zA-75)JXzn?G#6e;dr4m?7R-$Dc0F)Pwi)(R3&OH+!+}8_!5?B-g#aS@xy^IBa~A z94mjZFOkV$5a~(wr+%?=?FFXy7BOBA7tmv-|T$`RttNZ?BcZ&4E za8L=IbN#`ljhX`~3u~yq@(w}T-fB%Nhjt=*=FY{8Y8NBmPWse zjR*)6uTAKn*2kUfW8zf0U|vhl`gAg{C?h)CvzXYi4wh-+K}&+(QhrlAn@|=;>n=Q} z^;g>2j?`H0Gx4L!p6zVWB0+gRhT&y+FiFvX2&V}Wwjq_lY<$%nPFquR~H zYI~5jVk?{8&`CA#&WZ<5wXlc{gx52hSwmPY=S8MKw__7K z`>U89%NoM3)<$OiHkCd&yTY^Gjci-oQ!@38;B)>4W_8b#j>IOzy7>)k!}tr7@Tdr8 zKd5KtJ=DoSr3z9N>e0&ZZkZ(TEoVX1{`Rqg!_N0S%%h0ka73~tIey~GR{2iFwcPSe%0*M zgon_yP=s`kDyGNh3c-Jaz<+WTYx$W9dzRdWV3$hfZOG?@e#b!CRKd=^uZ2L*Nnp6W zf=#e&2aRu{@GHKY-RJlF%jPF*M9eQ|W_;c$KAI+)hJI()7PLXH!+GKbmG5kJQ7tqF zOeVYVZ){ocSGeW8o8lIKW81azU}T9UX#|w9y3em6#m%4A^etojfgf&-B${}ml(mQ2 z!Ib_v^tMMS`(|u(u)&ewssv|s3~C|jnf3H$Tk{%q=Y>>I9fQ>pJylX zzOamVS~}^K**X_#2jFaVU>uwiUD0{9Jlx zn?O6?ePZt|qUe1|I8`fuV(q0_G~}cMDcOBwo2PuGeUJCh&$c4wvZ|iCwvVC09YyS@ zLI)XDhl=^n3Ypz&DP{B?FX`R8kU5_1q}NWiLge-jZ1s%>8Y80!YQ6<5NAiWVzyJzI z7O-%YZ2DGW53gMFS^QBV$;v=DG$^0l`1g?XS|pI>@SdI1bRs(!?qcfuo&|**C5L67 zVVQLvQ{OO;gt%%bm(63vkLtw#lK3@a{*D>nJStA-`Q-OK-m!nTn0jP}6dG^lGVNRw zVHwYn?)#U+wkmZA#RFSl;msV@mc9r&6RN=CUpA|MV+2N>pZGmTHXGyU0x5avU?G#u zlodi?bnq*vFwbJ4Dz9N@hCi(DmBlU@=fE*fTX3|>WD62XI2*JVuFGe#+aa~!(SIs* zSZA=Ijjgc${0E^)K7+Yf@UHU|5KdaBvo&X>ur1I)a)~=$uD|X8i_;$BK+80C#;6Ih z7Ri%Z&op+_vH~XhEu;3EsjOyb5rp@-M60+V4LF|6W*LqGRquKVC{JQP=EVw0%I)-L zUlO~ws;_YUXBYPjCotMAp7EjCRLAhwZ5nW-8}KDce%PTU){+)z8!D$|7(}k7hYRNN&oN zuy9>8_s+|b^}8mp$auwuuXGU;J3GK`-7BVNow}UwEY;a%ooYf8sfHBizpgJjv z?JtamKCMB}x;%>QF3Nzx+RhLe|BT&=E{5=WLm0p08Pl6z4awQD=l z`GZ;Xp)QE+dKXMm?kmXF4Pw1U#?iABU-C*-MHOG@FGn} zSA4(>KGo5r`Qu>w9e*|@yOdT2Y=>pa{!EgVM=$&=;BKHFn>FVR=@s0Ai*x*#BOhQ+ zj(-A`qA#m`ahE2mCc-amU$*6*1s#{>L0GX59s-K?h_mTz}yh;&H-SlLqx3}=o2N6IxoEo>v89WghC8!9wV%ab=UVB7yAxA6F_nzA*U|(rdk93s3 zQjMD<)8oDKbuGCxP0^8=mH3eRk2q>^cVHoZqiB*|IBgr@z^3`WrGHyJXpNUWo9g<3 zqD-#Q+tKzcEAl(Fcde!rA3L@>y@7UQ4E4K0d3tDm_6#PF}vW4drmR+d2K3=G(oKs@*^u4)0dz_r_-q**Z#rkCAThHrkjOI2OX3KbK%`@-_C+svKr* z*MhsbS6T1#jUYdAAPg_Q!n7xJ0Ct25&&w~fYx;b@f4)THT*D8#ge-$qC>#C~15sN;cC!{RzqAh*@W4-%nMPCY*lB@i2w(adX@$&Od>XbEP z@}uiT`Rgr|CUcB^DVR+M6>4Z#kE6^n&VbS#zfi}&!>l&mj_iMDQ+AKTY=4wLUEto& zuRRa3+)FQM-^E9yAb*fe%S+|GQm(YOp8;EERYV;z=P7jX0XA8;f@c3(Mm59r*}Z;E zBoo}1`i|YtMjz{-Ie7t`XWz$m^7-eA9to1#IeVFWcNayE>n%j7?_mbp+sSw3E8*x0 zJ?4A5f&8=-_`G5_>)Q974D{DRfZi?^H0J{y480Bu40YMJKgpEKeH-GXoowmwC`#({ z7}TwIFppGkGIWcFaL?^5@vs&7xV-~~N88v^<6X2Y{VSZIt!&up$uzs87UHtEuz-6- z;*Y{s$oRIIeVMmj9JaR$G`lu2$BAFnr#eb`hIkW;&@dDH&UAv}_>HW8UYpP`jC(s5 zY+&lPs$hJ*8XQ;Yu)cGTfcWY&Ox0b_?rm^@-Ji0+_1HRQGClx?&)_|;m$*MC?G@Z; z4~EfJ+N?k>9j05~g3YdL*j?9;ptJ7`-11$`w#=%85f>3ELszl+&P}kgMGkhnSjmq1 zc0gml`$B1~7DIj=t{UvGVUeri9qQnqnY0Tfo;q}K8!tZ#G@xIVi>(kf)PA3cRCqX^=UIBewd`%wIe z_gU8h%g(TXZ_o26t5#si<9EPGey`(Fqruj^8V{#k>PWvzoedrSPH36dMz_n=*wSDo z6kX~fld{FEvTBaRUm9fJJd+jwXd)Ahp7gA129qi1pp80iVq*7nCY+Gc zdV5pJ>)z8@eM}d1l}!`8hpI5k*ftuU_f{}ap2kiZ)l>Gf(J)~8RQ52vj68HUL-3+0 zZ0vx1lCd*`Wh*AL)QgD}zThsu|Cq$w);^)Sf=CEFFp-_hxJw5nCW7PH32Zwvr^xj8 z5NoEEcOC4P=rtZ7@P6TTFN|fa8XB&@g%&J>xwpJ!(r~m&-N^p?=J;I}dh`wjjs2 zzAQoe4Rk!cM>=o%FlE_DXj6Mi9};^r4?{1=)J>wHN%HLE3sb=Od{W>(9r3_MfO+3Y zHK7*^Fc}HaF7=ccE6d!5y%7#(wb7)Qp6u4*vAlDzi^3%`EbpM3FhEX3+kzv_K@;~zvdVX`ENjK6d?vfN5 z41>wi+PT;>`p6eAN83`8;_D=NHgz%t)dY+3&>t< zgi#NgskeETD9Pc>`r=OdFwIJQURBF`DWnt`JVfFwQvmf?A0}lMLMtwz#9ozPu2KNHeab|MK`YGood-t6 zAeu#WftA`jIPG7o9-JbD;N3Y8d(l`(%Ibt0hqIvf!B#<0w*|iM%z#$Ch0wcKH5jX= z!D921AXt9lPP4ag^*eWL*r&qOpNU}l_BrGn34_6N6X1k@HcZg4ha|sPa5_;2_9UyC+Q9{tABb`EiHB9(9@M=kU*@1Fo3d7Ke^_1}1|V zAU9fphFCHJAD38wGaHbl;Q+$~W6-pt2AAdo3&Y@q2d* zzk85)W|64w+{JltFL-^hP?Yc2M!Pwyuw}g}72mC0 zq*79w3%pSar@E=n$)v9{T$~?I^L%_LX}lv0KlzSQzgW?l#rBXD|CPSk?xL8rwvh0z zmU53xqP)GezFrJQn=itUAD>93rx6tFJqv##GU(EEXXtbEBm|pEXvTj* zFz&>07#tKx^E*TsbovNHUUH<+icH8pWdNRGM@hTyXV`4C4-PJ$Pl@yRXW!x7;Qzf% z%%0i;7xZ?(`|6wGc(D_DY}f*g7SE%j;70J}QCSpd}zb!2-(F-h+K%4nFTA!+P*9rPdrg*yk@e$OQ{e z2IQi}NX~+*PKGPfb8&q1SLkp$1!gOAapS2JsJnd^z8uKKS)A9nay=SmpU%YSM!8F#=OtvbtX=# zGgVK|8O3snGVxzsf_SlZ1dC|T#GTE{Y2)v~EMssMDrGqnsmU>g*;)8+vxHW7H-fQt z7A{!)h0NtMpy!b+%<=q58?yW%(ku%jKKG6pe)A~U_-5h!hCwl#4$DD^BnuBX4~^NY zI$PNME(^bB4vA6o9wRE(WZ|Eg17mE=o5lV;vQa-xK1Qy16^$L4jaSWn)6rxb+Nzq3 zP6icZ=Nd|3+SzD$A&myur_xk|Y@EC65q%o-jow_%#)Y4G_v0s?8+6Uab6!hmU3kx! zL*dytq~^0Yz_oYGvE*#@T3jwM`mb+{b4fP#xXm*yihW`}cV*)lZ#js5A{(=LNDgi= z+6w*Ce^Bd;9Gvvm5$;PWC|)ZE4+{}sWSU8F`*QGc&vcNx96=42bFfKL3bon}w9+*P zle$~rSH*fte$4;Q)jyDt^;4YjCI`3N>cQ^DToeEASu!+?5`QGL!{E)inC9D4ax9t8 zW4UK(wBc>x)i|E-`k8}2=8b~8VfA2>nS-hoM?l-=GgSKK;FMes@ICYvnlEtAQp

qx95;p_~K9}q!wVtGGAa)ev$}(#gg_4pTSdD|aw{>$U9N!<7(7pBm*XvBpEf$X)j9U#;7U5Xu8FhIt+>waV#~@{xq!~ju|c5f z7?#ezVPsvLg9G0aJNkx^J#n0*7$v)<^^3xWVfwsVY&{MJ-O|}5b>9I~=IHE}c?7`l z?>f8ox58k4JDpwsM{#iQgw8IV*iAd5vkN13K0c)s`u>z-K|HIrfKTAkgP z{V{OCQD^7bG!(R|I=gRu{oxY$@$XOB@O@k0bS|CU(oIHKR!C=;Z-_NieX7qp?MfGA z1+k;=Puctv)@mNf?#9Uk_3dqa-W{6ch!rHe*00uKohLfG^hc+0g}2VGSk++s`buZl zuX;2__nW}KKV`<;ztA>RXZL~Foy}Mv*35>)uIP%h4)pyg`{0m<;pKI9hu(d`(!+Ij zNlpBKJZsLsx~Fa`P^)7iZxc4Kzx?4A?5iWlru`u>ywvGexS*`41P13tZV zc3w?FA%At9-P1n)5Xy9RdG~IC!&W*wcTXcIg>`nX23W%u$?ns+F3Ks%E;7JcO|#eM z-2lG?bs@2%Z-<#W)e)!l)#shp>vgDv>+EVhK8+K+bapn?f^oyko&4KjR=!3wKJ2Zt zdqwO%gy`(bHqOHC-*tA?iCysnI=hv`?m{)4UGm#6^zEw7E)TK$u|Q|H^)+I)_By+5 zhW!{&MQ6AE>n!Y7QfD`>NoDL`P@i{;D+a2WlHL2REg)a<@8X@L^pC~R;QLD$MSIPt z-G|`9uv;*a#@M?$S3vVS3eL3VH2C%m?j?CZHX8rhq0i87Kxf!M^SAc%6j*dOL0Ld$ zht{NT62qz}U#M&>$%E2Lsl%!7DVZq%CBLg3$ZqxCeg@~}ov;;^?XfxnI@I>SgH-lS z?yC^~;t10B{;Zn67kuu16MGR~zr#zQ!nBvTna1bTId<^!)i+F~{CD4wufRVI!$>ap z^oBzPieITlc{&yxpf28;h4EDO(V0Bh?Nt(fraJq+b;1vmWAQ5G4{hR!eZPfa5z?XM zyHmJ-#bta%W$!Pzix<1^#dOly_G}cDbH*N2*7tEdW=*Jto2cyRE*UuS!x?ojl`XT< zpat#E6}X)GwQ^G?KK!^=;qNf-W+!5ZZE3hncBpzG8gq9L-z72Y3J-B~!EJDw%GP-6 zhkeiZL3^_28Mkd1cK88QCp)jLJr1YSHx-Sk?C|ELvCrZ}FjBiqQ_re9AcKBJ2E7&R zI~(|L3HiDE)7!|t#>&3J1~!TGFYow4DYQEkrc>G8GkPm?$tOy2t?a044ruA0%;Q?= zcfC5oi|L!nI@ zt*nvTH^^7TfycG7C)r;?gNjRdTq|?gbQ`jbKFH%*S@@t6a6C)pajh&@_&R728;%s$ z%2xDsg34!Od0Z>|YMmcE_KUbyRxHLvc{4JL$F;J%qX!4xTTeVFzYCmK`?Sd5ajon& ztBI>>B=ERa7Lz<3Q_8>Najoq5fStG~DwxN$vb_!$@a2m0NO7&K_>%`%b^bP_xK{Qd zUo_quF%c=Qm5uTIi5+YzBE_|`@$nhBu7r{qCa?CD|?6`>ZRi8Jg$|w^s`)fR|mF;bD9STl33>4SO z5;i@Defw7c#kI0ewZDMRfsR0Nt?c!^6o~1Sq)=Qd+fu>6?%LWZwW;i`5eC-%-RD4x zYh|fB(qPBeaFya(Sy#L7;60`Vk85RPvb~0e6Ww@RD;sn74)lA!pU1T_yGtkG5eD+O zR<>cGC#((%LyBuoRy;E894uDhA(A;Bl>N^{lBlKL2|j*UHWXZO7vI9`LwUc0JAy;gug! zTq}$84#5#6b|A&IvOg-k#~$%h@Gh10`j&t#qpKjrwX#L~Gw^uO36_|^ z9@ok|jR){>Q+hwAd0Miq8&)J6QCusl8Q2_~Qp`NXwX$r}o~X8`(s*1eyX^igu!nm-91wvM|!40ajh&lkAbaP z-btajR@UfG1N+eJL7+l*?w&0j3Ka`cDXx{B{Q4b=csJp3t?W+vYuGnxA&;?PZ!&}6 z;)s1bu9an#JPiRZmw8+(J62^Q9QApO6xYgDZygFQX&-r9D=T)SD9mvG#bYd)A$*OJ z@h+3cwX$NvZ(m-v)1XmYD;qQ0OTGIhgU7Wp--8vg)zqInu9e;WG!Ym7de7rpSxob7 znA`Rtk85QCTh3#U?FFQ`R_w_v2_5177=UmP? zd+)W++G}{d-|yiyf@=ktzU6pC?{h?5E8I=7!Q=UFf@=l)@h>FA>5t%A;fTyY$rc*h zKwT^7otq%C)1&cM^q772eG|z{>=s-rJS}!Y>bF}3*9tRxSEA5UO@eEMiPY5FR$mib zE9BH)LcXTuh`LsoAM+UH%H$*JTETlu3%c4f4N=z$i|_qHsxxGSy+Zi-P4f~4}Ev`$bYX#qZ?P%d^W5KmTXU8j~|20jpbMVTz78yRPQkUpl~r3r*Nb}v*9u{q z#$B|hd!p2}!nO@Xk^x4&f@_6wcgNzF3Y~&$g$wf{u+8&#f@=kz(yesw{hr`jVTI^4 zPFh)kscVHG+uOL^sfg~G(c`y%gSF(6F?FqwRPr4s#7)H1wZh-FzxcM1L_%FFjHdAu zGf(GNQP&DD*7o7Hl?z4GwSw8;U)XD@oZwoaCj2vIXZZ@Q6&@Hp!iMVW1=k903kZ(; zc35z&kYvi?%^#};*9!M5a`5J#&k%L3AY%l0%EzyQYlYzYcaq?T-GXa{2KSMY@m^9u zT`TwwRu#>#l>+Ko!KnU&X#U=A!L`DmPj;wi{a3-Y!rQ62NU`FX;99}clS765t_!Xe z6t@xNxa}~at`*e%9-(C?*CFa!VfNL}D4}cyqOKJ@r~N`2>_B0!5XK$pL%%E{MAWr{ z(@MJk{$XR(hBfF;zmg7viT==>N1!L`D>Pp{F)q!hum!tCJNNHViXaILWV z&MEZlV};;aAv|&`iVe7jscQvM?Lwqv{vK1;3iBP*(9yt7!L@?6RgvhlU$5X=!QYIt zwxoNa)U`tHfh`h;v|hor!r(uu_yFH2xK>zP7m5omy%$_7bSP}Wjj8tq*9w|%PGZxC z7ch0Lz{u2M)5m)-b*-T6_!_&eUy7+~1-Y(voMU2yscVIh&3|#in`;v4T4CKvDUz>P zUPWCiMBqN`xY}PtT`MGP`h_F5_ZM6%oV94dS5A2gt`$NY9^=x~e8IJXW!WXXHK$x~ zt&mj2V-3kQ!L>r#l9jluwFyzz3gyiXI7R2H;99{jt5q^0jK+DHAmDE|$Jt}%$ z@`3WAs;N>yT`Th*&^%GK^=8vdr1yu7B^>qyrJQau&`%u@G6cKf;aDm28 zIGRLPQP&Cq8a*gA<(%XlZR?<4-_bZ9J;AlYrlvP2u`@w%t>Cu44n^PCCAd~F)j5OI zcApnqD|8Onj-SQe<1kjVkI| z!RA{Z&hO_YqOKLLDE-C-XQTwz3L|8{;Qew_1=k8aK2NZ?ey!kIq5Jb?d{Ft2;95bg ze;E$ja8+=v@RePS171Bv)V0Fl?JoFJNUPvlAycnY@}%{*;94Q%?G(vwRtl(Vg<+RKU*#!rOC z8&^@+3a3(f5ZZi95=4*Tc<~Q(GM5!xD}1~87WpT{39c22&fh_H);k5)3L~@6A{~!& zf@_7ZB|A{{pF5bkR`}E&jYfntW9nLANTU{VR__p8D-76sSoH0DkKkJ2v)K^a+w^%& zT`SCekSn>+uTOBTaKc>?@2=|-Tq{Ht&%vKFKMJmuj`KI--KQD^*9vW#$MN;}D#5kF z@6|W(imrXwiuS_`-CyF}`C?36E9}_RhQ}N?$JDh#{Ov!u&$&TDT`RQ5N|E}u_f^!j zLexGlW@WJ{gh`Ls2bM?RlyS@mn6-GDwm7GlcEx1+~YwjdjHB1VqYX$w1 zN49x%oHmbMX9bVDqW#T(1lI~jPMe|rRc(T6h1S{GXx_P(|JtkW&R#V0;7!4`0(y86 z;j_mPb*<3&>j7eqZbHOnJ)9gtAh3TE~lX!Ti5!L`EgGtH>}^J2lZ!nBw5$nMZ~!L@?UgL6o_ z>x|%9!OeCTntQVjQ`ZXB;w9){!dpyTD;(K90i93#A-GmBm~mQU9oi$fR;WDhZW~6& z;ncN)_q{Yp7xW3P6}H9RGAbqco>kI6?VmZD-U*G=Z8;*;z#?-ZfYUm%lrmIOJ^baqCrHFflw1m1= z*sd)_vK#b8)U`r^d^f&#zg<0A?Ai?l>1-7wZgMD6I2n~F1S{>`5_%89)I<(A6D@wMgy8|39c0y3M!GW z63v%K|NYSi_t8?H&4{{Iun+oxz8Wq-)U`t1m@afVY~;WGpF7oymdq&>QP&FPG=3t> zG~^<6tq?W37k#KHmQdFUpI&yLinr>5YlQWtq?S!0v#_t zEx1_ySuK|O+N1zG(Z+esT~ z+zM@%58aC-rs;ixYXzSIc`Wn(r{G#)!F)eFYvO0YwZhEJ>#@R{hk|Pb2friONR|k$ z6~Oj7F0CuY)V0D*`{%gAHV0GJ3YXNsVSjCescVIX&Tibpzm-te3hmxfWNeS3gt}JH zpmC-L4aSP7YXv!RH{K@wSwvkctPS{z`3`%*wE~HKhVRwn3a%Au4_0IDEGM{D$e(-| z@Aygt*9w;`*Wqd0BSc**eAw%Q*YtiCTq|5w9Duha{t{d()VvFk%)QtrxK?=JQe?ZC zuD4Lv3d#kSLfZ&|3Q}>YXd3^|VnOniB4nv>TX3yl;&K65$DBgc zwZgo^_mIbrEr_~SASv%r-iQyB1T|3S&2>BGt98F?FrbU)vD1PxvmlR_Hl@MKtc%U%|CPUG9EcZMwEaT`PF* z4w8&KLHAQ>Km7NYEDnnPCAd}?R_TLXdp--U6>`7kb`hPT`N4We1`va-PpqDjflEd2p{KN&!L>ryTY1d2{aIIh)qK}^6_%66s;Mx<>yY2ssC49Hojb2#R39c0aexFARub)QLwZeDt zU9_oi8=|fiw$U81hv!8i>RN&Q)PXMlQU5nzs~bn-Brfk4QP&E0Y5c^`K(P&Vt)O+J z7kU5OAfc`msujD?D$9|AYlZp+AJA&+1%hjZDJ~Dt%6El=YlXkpE7AJ*Cj{3D(|#2r zI~sdPT`NQ>WuU$duP}A3u>P$HlBBi^t`*#(Zi&uJ{VTXu*xEvDU9zPJb*)gV>Ls~H zO`5RxdhB*TT>bTz;98-3_%wW=wncEQFvc|xKbL*-Z@z4vc?gf*cv*0*@Zs%Mtg!b0 zrmhuICN<&VhgV_hT4C3&R-Crp8B^B^Im5bftJDvPFi%gXai(rtj3v~y(%b=3M6|re zmbzAYZ~Va@0-uVgYlSWMzTt*t)`Dw=)d@6LYVbcx3>9iO@Sdvuf@_7t9Y^tvM2X;9 z;roUH+_<)pwSxPhbLf`(SwvkcEb*yF z&PF>Bb*)g#H6!cx#fZ9A*yhoJE?m?6w+^FJ--AMv4vDC1g>y81VqfGh8|qpi`&%zs zHDtAfx>oqWb)gyal?2xcw(t>Yl*|=eEBpy*KuPYK1lI}y%2lX(<#EBa!n0NTko=n) zf@_7d8?#a9rk9wyR(QVO3>~@FCb(AkqIO@j;L{($wZetDFKi1FqzHAb(3U5X=*vkF z>RO@q?jMO=%x}T9f_az+Ub5|r;95a_&l)^)#6L3+stO0O^ZhG=YlZu#uHe(M2QhW6 zaAE9I+%j(srmhuy9?;lBeedN6De|`Sr7d-> zz}L|IDe-*~b*(ULZ5x)mVlKE=I1@*6JkIoqn6Tf)br_h-N(;ZGm-iY<@I>$$%oi8 zo{ohgj^WGOtFRn>eN${L9#dC@rIP6}jBm!R8=|p)G#x)r?7$m0jmInLdcK8K57s_& zLPB#>fGUlh>@f|iV(I>Zj&UEJIWa-BWHIe?mj1-~$qMKpU576^{0X~!^+!YLIZ6$C zh@X~iK+^P>=RK6*sT+^}dlo!D*oJp{nxdT4xv+QnODsDe3(DL=4*I1ZR_(ItI?!c zPchAB0$sXO(YW{)O!JvQs*xOeRPs~EX9ApZj>!H@uaM6K+*Gw}eP+}69eOTjzhx6$ zai!?MsIly=cv{Qg@hXYQuR!+Tp){fw7lK#WtzoZRj3EKvBv`q8AM5dBHfi}QOx%KBRk`WbXPreyQ9QEX&u|*ln({P@i-*BgiP!;Ps7%lJeKSaP7Ar|4sS@4mcJLmsN84HLknytoB4m-@1zr z_^XdUM`VIz&@nzQ>{ZpG4`SFj0`nhVy%$-{%Ldc=xA+mh%h0HXRJeHjK7V}CHPpT+ z8r+*6@}qsE!C}@Mcyaq7ul8I6+P}NPrQG|xqLVdT*kc4as<(Lgem+RVJ9S$ zmB;Y~NogQ6JRD#7c7u!Wh=u*9&tvf_ZLaUqe3*3Q7nW5n(ypH11^rUSkgIZgne;VN zVAOIm($Fc-4xKw1bi2LC+7tFHAJm2VqJl}&?qqhm)>(8eK8{S9RmfgC6O2l(q>)&e zGB#)A8&OEpaj3b(&Nd#8*e97pGxRu{Zc$AAVIqk;x|5BM|A_jH z4kH7Mma(d7BSE4zolI7A6>4+~`P9jZ=W=Y3!aO2V--{=hoo3s#61xWlsr_QO;gGsNk3dsru-Y`$ zwrCDSG)3`oNmp@IQ8c_=y`CR@ARAkErb5t@68_@lHpScD!EKI^aG8OC{A&K_uvt)BF%Z;uo#(ATFM>e%yJ+g*1AK#i3M^f_4o$P(#Mf-j zf-CuS4SaMWf2~gppKFaS4*QAt?IBs<^;Z$+Dh=eLZYINcg95x>VJEjDXc4I9-^U4( zoYHjPK!|)JN9OWIO!hlh_|mFD65pO>yu4%%Og0(vuO89={QW=I;eYOd|8L#{LOq;! z%{S@q)b79Ph+$e+>;IK{VUtZ-h5mpDwKM;3)C)T?OzZzjy|6vDo9Xxb->dJYkUx>u zG5X)NasR9BgzHL>+=2gAAMIb=wEtdD?LYOHgxb48Enp(l@%m3~Tq68Gt<_8GS^cYz zMtrr^`Tt(W?Z3Cz|Dzqz99pL>=i+doo|;h4?q8iap{|keeYDORL%#=v&ll>-(fa$`>%RKTf3$IkNb^&9thtj+=s$-{jc-=&+Gr{-2M0ZcmMeuq2}*@)w2_7{{A0z z^!{@^K+lW)&vE{%yGOrAIR1b2_|^|O{jWY0y+4IIeOP#%o)`1q>%{%%`uwXO_n$gw z|LV&9=X(CDH}{|G{I3q(f3E+(`gHX3gnD-W>ej`oYvRiKO!z!-92cMW=b}=tnC^Mz zad#JwKpuWsFtXoO?nKBo5qOgaO0UIoM(@m*#Uuy+kc1DMf%8!Bw!#X^?cmyy0764hx<%xLs zFK+u9J1DNuB{lde=Qo4}?Guh9ZUA=U?zUdh=_Rj^pJSUcTZc7|0Cy@sMBKA(FFX>erO6R36Y^OscIp*^S z7rgOg*QuruZ~67OqQ4ib^gD|j+bu<75?tB+pT*>X(LLJ?EySMd%OEoTQ;^&yW7b1G zfvET$KvxfpV*_S~kf}P~P}40r_R-v_Wa%SSIDhFS^Q_a9q$-)i{*{NA?7Wdgb=Y)p zvYOAVAN?7p9SMaavNyENU+%+yBEwS)4Di&Stgw88^w7iMpb$I7Q?M$tGQ-6 zznr%x3-(UB#0}h3h!(mhgRfa9H?i~?DwB?YJ@HEXk&NNM`ObtFr4#rW#|`0vwhh!5 zoAVdnxWR(s<6wKV13&5NJm~WHi|#kM^RXM_piz7V?JV%(1Gl9^Z;}sMy1;`kpyPbG z?m42E)sDQ(t!&uSd0leL#*z;ivJ}=&%EDK->hd3EE{5)cn|R_GW!|PY5RNqrBx;+x zxkq*Ou-8F{d`Y^_JzY8h95Nh;Y{CZ4cJx3PpE!$5k7KzREj1|r=wi~!X_PADq@hZ; zrDR3=QSFnbvB>dlHfiB}m_q+3$-ymRqV~0fvAX7qD;A}bukW5Pubt1~80$E4W5xh> zkyJ0f;xdo)<&R|-&e0&-X1Ni|YD2bppAC7UYe>q7Eo;#w&^gowr2QlrwjKP=Sq*-Inwuh^#aEG6dp8tB0Nvh@sz_Oi|@u zM}GP5Y|tBbUNWV{k{7L73cJgav3jx|zj{t9xyJ>ysO()78T#F_)MVE()UP&`Xg2NB zw(Y7DT{@jjHk|ilq%U|$MjaEAxn}#Ab)%=^zxChma z`J{1`8r%C;ok&)=lV^Vo*l&K;A+#F6K=(^#CU7qZX z-X!vM*%tiU(u>AIe>4lNY#vhSLO@TE#Go8#ipaQM^-!Xxw%t_u%Q&3=zGaB1QlSTDjFzHbgb8A>T zE_<>7D5}x^5podEx)M+8i7hBem|}^)+|Pj8y$am=k}p+d&0@$Nw1OLXiv@&qK??QsDKNHZCEq5ow-^gehjj`GGD&U}lyd3~pff_O^-e-HJ>Pj_4y@SR4?JeL^O-E2gFn59dRKVy($~}A+|poVcE^Jc3l+m7@p_TjVkf?v z5ks$MnPl;HEB@TyrSMcf7Ki%k^O=vLq0gVL^)-&GVF%F4zfp8;1P) zQ_J-&&;$MlkWW*#aGF7bpgk;rM5dTOLaB6iw= z>!x|Jw~Vq#ZP+MWJJXG=>l2ehhMG1J4}g9DGn4dasH6MMlUd!)M6%OpHyT^0$*K%m zNLHO~MqAKec1fc*IjyJ+9a}#zYNIWQ?pqU>D}RbHXVl1w5>J>@w}knb(Sgsm27`x9 zt2U>41b-V75A`j-_y6tzd@DHvS{BH1RaPpJ>;^FuT4ZwpZ$F8wXJ&)HMg^BSaW#7P zIR%y!v~qjy-b0zWi=b@8F#gP51xPORhsw9wyut>3u>FMSzReUq6`aA#NE_blk((C?Zj{>tVmSY;KVn1is2L9E~yt; z^Bb0=L4sd6wlkf`f8P=V<|i@cn@90Ma&uty6KQg@O^Uy~*BMGGwaCWfcesjI`e3&g z5sBe;Ztx!k_~h?T2Ig3BMpgGw?DRz>;crx_zu6iz=Xwe`aci~q-@sN;giAL0lm^TS z=iw6nM`Gf(e;2cFFv8*MGe}3j`^;h0!#Kq)p1eIJ&5kbmfg|-7kf4OoY|x`INmgXXQe(LD^b9lO+*ool#shpGr!a{he&Vv8`7pcSxAw~G z$8p1wC9pQRW?$1uS6ro%0i#2DORsfIk;q)4Ya#|qxzp#LicHsL!+ukJ(zq4dCZ6c+x8*6ai=^S-~-^|H!c3{cs&?kU zTk{WIrNQK#^YHIslX%8E7OwWYh&6wx@(umzdZ_qfMZ1x$hz zFA*6#b{BVQ?+|!x??(zsL|l>AL*yZjBqzF;m)`zCJ(OJviMW%ZJx#GkB$3Z1FMX^S zWcIqs=7X3FJhh$iU1^T<-e-`I;CeBi>%&11ht1wVM8^O$%EaSX>LJnR#F{KHt&Cq z^i~dKrDSH3JKu-H=fW?{r7PCt&qyP8y=*9%xaSLwYxZD0wx15PEAd36P7YdpgS?28~>@=wvHvSFXtLepML*_w>jXa~Hc^>BvkAneE zjkNSH`{ROX=}vzp zmy03cumZ1KG64Qm&4K~4ntUxY0Y+VQ06Cw@yxw+uc(+^!Bq6|$sSE@+dpY38x$&Ok z7Q?=^x6pe>FaCUMD*PHFM*JF2-uH4gjH$ROQj&Gy%MXZQL#?0W*brMjnBIfVF4J*9 zl>y&U6$d{GPh({TH9q6dJUE{72lE^H^N;l0!NhMIiCX-Sv)42N^$XTS;oM#>;=^!g z7&MbiYH{cElb@r7cf(1S{_fJiC7V&JPBOVN)LHw?$suUN+AMNnp#k&S(z(ix{>DDm zZDLl)>)^r57C|*!`ZXOekA|G z5ZGVb&OCAzk-KvyL2gqOv)xmZRM)z|53gM2rCL8CHH^Bj%wbG^LnZDvD;5F{yKk~Of%qFyt9zLEQwx0n<1-fRj#)QvsvxD+}dQfl=@sCdiz_>T^5K-&OtN2I3 zR?RzT`y?+O#ioMn+#Iz2xF=t@J{#2HpNRS*U3gWR(R=Cv3yC9V%MYN>7Trs(cy68{ z&%`W&V^5FcbxLFTT|ef-C52yj;#FDxQlJOSzBiT}ANYhTPBVs^iB?1=wuCEOp#)RD z`Vg*bI@c`!8cqMckSISWD;;jR9ffU4B592iwbxHjL8F|r$eI;8OnJrji(d5E`RnHf z=8w4s?s=0*Yz=FeAloABa4V7Il>A{T&e2>YH^azaTNQTEDrF*G;Z16qb=hXS$s`C{ z5H!bD_@zn2=1M^hn$qW z_<%1d@NxWVH1L5ZzuPYxLPVcLakpIf)%V5VzCl%T!&bz{CuD${lO0~=Ys81E#>1lt zNANKfb$;E4U??x7W6chlO(V|}CON8+)yJB+WA{v;N6(V<)8)B6%E~bRfj7C-?8lky zYDVveFC;$6XG%Xy@1}W>5{X)}lJ>pxW6`%indEJ*CNpFBB%ABBt$!P?V-%7{VIw+L zUK4kXIh(ixhlD1PjPbvji$-s-N%=zJr=!ezbSsghT|T5)PM58DW=yPAtjM|J7OXDu zATPbfk_~!}tjHmlw0`Zv?II6$e#sJ&dyeLY-sr{33uFAX&RAW>gUziLll}b+B$@RN z?7sADa_#dA(Zfj=th{R~QOLSk$H^Qxt=pWzt}K+ojTA z$pJ~+1TloP1aV@u^&*EbF(i4HaTaHT(e5j0pxyrkH+NtaIyg2K)=ZM)Z@6r>)+Idm`8 z=ivhI9NUhiwd8npi5ILmHk!!Jdcm0*nLQrKPWf@vLLYF=HI*MqN)S@UAW%k*kK(g(U94wjqo9P&DPc#SV!bX{D zCT2fNnkGBK-ka-~Rm=dgcu){{e%54e(c14BYSD0Hm7;dmjAWdhzZ6RR&y)`AI4gPd zHyirN`*BA%XNuhD8i)NZj(a$07W!kD4*i3hxN|-gsNcg_SoLQBAOE2beXXP(e5^We zVK*MumAb-fkrAI0YzsNF48UZhi0@AHg{KdO!r)35-t>J0=)QW4zR}10M^wU)>PEs2V4q) z9S2*nmZv;Fy=5wttE!R-y{|a0ty921$&5(dF6R#EjsnTBQ8EePB~$+5V) z(kJUn(Dcg*fV&yvG&bZx6)IAMC9Zp2Y} z$)tRE2je=h32zLGAiCcb*{OGik!!bRk|>7>>;u-2oG!H?-9hGTt)CmwU!Xxgn>w&7 zXUrp(k9zPgi90Lj7)Oq%p2ID)4?hx}PByIb#W!i+-n>~%8YeE6Y^ZW%eP3sjwm>3E z+-S+>+b<o_|{4Yd4CCTyBq!%eT=gF5pP!RNqVE`7j9WHluWByB4E zYPXTlgQkP-b3Oj)UQ_UiFozfYt@sL)sc=kbG;nH8yl6@Ys9*es%+Gr8F;WRo^Y;Ma zS9$S%?HLfc%?v$CbLRs;iecBtXSQ_@?0MDx+3+L1R}v{P<139)Kr3P$e&WjV8^R;u z-uZ|4*2&>K&-#JEts&$^ZaX*DPy~b1CXpb%ikmb-6S9B15Ve;%+_Y|*D@lviW$HJK ziz}jewL@dc(6ZGf290yk`IaAlDAAi@l`xxOEh`AV-Tx9L6)c;2qM9{p8{k)-c8VZCSAk@PNI^0*PP znU?~{lv;T*{H`l|Ffxh^s;k4#4ZYYa8L33}=L)>+T zA?o66*DXq5@yGAC4v=az%ujcOytd1c!YE~G<`jwy-a#LE-y*~KO2M6ksFn9u}2o9 z|JLD@w1~}Hy06h4Q^18a(YAh;3Eq)4+~|ZN#9dAVrR#qu;_r^bMN1XCchDQ08Zk9|2hG10%-i z^6eu`AnBDQthr^uJKy(!;Zw%KU=v6F&GcaKmvkY2dk_BQ@g*=k`WPzT=*1tf&49f{ zPAL12JKuJl?qN0Si>zuKc#ZUIC>!=tVl>f$22Q5JvIn{N=vW<|=^q8$mU`UsR*B!_ z7y$Ac1`%<37x%0YpfX2~9CEnAHK{RhKi!EexV@Guo7Nv{bZ3+LNow5AkC)MyuhArC z?3a=a<}t`eK8>hvyR41cc~Pz|9phThW|nvtNCM~6xy|`9#y?^K-dvGJ!tGx$#`aa% zRxy?+f*iYv^dlpV&mpQ4$Fck0X_D}1F66nIF+1gvh&;m+$xn%hJ-FMCu&P5yqPi

N(2(mi!debH)*m_6?T2FV%D0iAT>3N4Wpw$AZ;# zecYIQggcb~uIHTmb%d`w;Vm>K9Tk+V__k+bv7C5}$+qGxRL?Ob9{W%%>Co@TPsF2v z$x&V!T8z=eUNA;OHf>WN>{1Ndug?>LOzP9E{#G?xRe#}{I!|jPjOZxp7MX|Jvem`mwkApkt zb^87IkbXZJD%f&k`u%7?Jm#OVahK%ohX<7)$!UaL+-c#ci$?@#gI1! z6binRjst28dF>Ec(4fB6e%QzRQs1hP>f{;W`}h;;TXo)625HUv__qaAU!}g)wT(vn zIQ6aMsc%)7XvCirk4n_Hl91ZZe-V$Pmlp{%H1~`9R?buJ%3R6Y&-ajyBdKpSv%fK4 zKs-Kmmd5TT#{4|>t%9jrvmzg!)z!rWJDwzJ~f%Td8j~FY6%xWn6=OsBd+orx}l@zSS1$Tg^8# z zp}y4z>RX-mHRlG@x7tO0t4XiT`4Z||t);$|<@}Hc;!!J9mwSa23hGG5;t#s~`Y>6LA{|F=(c`~JM@`akPnsSt zNKJ!v)PGd#qR&gI|2Xkl8d$08b2;L1$^}_J!By6 zcSv5TlsQ~xz?YJaN!0JCo?s~McPylS2ih6(3gYn=^*hE=EG?maM;-M$?#b@scZtW> z)bAMKw~uPq-r!69j@9-1_yFp6j3XYmtT*Bpr#}`9(Xto{i(h>)7Y2~BOX<$-|^~_G54nW z>RGC7r=eKlQFU!_?3Mm*+Hef4460ltyytDA{O>1_x3Y^tyR zqWY?R`ayofYy@s29*4Id{HL8Lm;TjJG$Z79^LO9sn6o+`NPVkEq~qgib^dg?EZm{I zx=^s2n^50sJn3i|www2*yedgL9{RkS{~{fqQC1azjE-Bl~_mGa~ zNym3nH2HvYnUG03&a=_v?@31$(oyw+CT}AhKNFAIi?nzh^{qybj*|kl_{+Dy`&KsZ zwD=zCTX~U=GgoQza_U>{CLNE&X!8K-TWzDh)tm3y{2}$N#!=sDg{lrWroL5wyBzGu z)Zs1EM-HRD)ruavT#0n-HBS-0>g)1);?b4*R^3ZhoWuqc-)e4*TfyDb%+LqQ2GpSNc4U`d0GPw_45& zxC`~I0cd1b6>YMT$8CG9w&#W@FD(%f^Kx5JG}Q3(l+Z zHqy5a z((!}54&S4tfp(ipAAluK1wr{^CS=sa08zXZBd^Xo4(i07Ri zT^XC-cd7x3UbovmFkhuLRcwDVk;pe*TqU+e{}%nX=slwUFM6NI7X6**??txg^F*I3 zvUdq`CW?;t=XJr~*XjN6_xV++Tm_@8tgaNuMY8*MB;W z-2eGrqSwXqT7TXzp1Jz-Ib!?I=Zoz>$CVTL`Ntoz{l`zSE&4ps@qT}=MUzCw`}4g- z-}mqPMdv|m|2aQm`_Fk3+oJC$I-clnMc-R=JdrIrAEM)lY|(l8>;M0q8T&ddS`YceOBfOOQ!b_+qFUS&~#Q;v3+Wg6Dqa+5`U(Z&MCa4-zc`4`+zh-p>`=wKPxLW*Q>4N80tvuSni2wzqs4mhYL{S8U5#kI4@()EA%I|9_aN zdoidPuk9*B(Rs_iP=Q}I)rswf)O7qlRz+RB#Cmyk2;DkJ!!v6WqO=_Dt-K3e#4>Q**1nsR1Ei%|QcJhNU? z4`CNKqDHPfllQy}{rx=grkyw`9f}2?;yS{#8{>i63 z;a*rKOOGCtKgm&EaD`{G`LD+0D;(`Btaz5mK8zlf-+g_XP_Oe@wn}zL{%{jT^qhH? zsmk}xpYkpM$19#?gAzLBN4DmoamH)P1Hrp6^ z7sC3zLz6|>?DmsSu<+&$v{T7u7r%6o``I-Wt!=WIkwbsEr`8U5`(!pNnKWE3Fklv{ zUe9I$XGhD8tx6Mq`jE|5P8usWNKn7TYv4JS<~LgIB4i7eE;+|$z8EIwv0xs&Q9sAF zjp;8pb%_(0JDp?lN4v;1N1uX=spptuWE+Hcy9%AIo@0v=pMmI~*Duboo)0HYOgq|Bdb^q!GQ1LU$M&Jo*rx`X6Cd>kwgy}tYc z^__Fyi|s-3{p7q>tpm~PIZJ!UeJ%48+gd5K53hfQ*gkpw6U4kM72DS788EX)7FHi28(?x1q&B%V|g<_g0o?F80x-_4J~~EokJC1ZZ)k9)$2AqzUB#za}?N( zE4g40lmgT26j(=i6! zGOfq;LQ-&vp5vG?cssk8Jxw^Oq8+&Ac9!(GUg(zp34*e=v)8?rq1^q~pxI>y+oIrz z9tZEiJk=d6b!HsiS#=Tmr|n>K9w4?&Nra>}S}!iL0uMZPh1zvW>}1|6e9*EUjzlOi z8umw<_@4sv4@yi%u^mq*D+-=1-^uQqci`no*?FgYb~3rw%~&0ONw|jAKm6ucj|%gp zF<`DT^Kz&{tHow`+F6-3+g`y<7U39rUzw%qp2nOdIaoSTg@w&Kjyb(e_y}tGone;CZYCA<5{8bH2Y9rbIS#u6(-wL_Dy?Uz)maFe7bJtP zwFbN2I|lA|DFVSY4chn97P`K?4~8T5u#&s7(B<_T*kQ7Vy=!?Y=%e`=B#QSixzYgw z&+Z-IGGH%Dy*^xcs-57ta*9^s)tR(=vg|fpYda4 zPfW1TL5FoqEWs`9G!I&-!%8t7Yd>V;(($@%T7e&qZY{&trn+p+MGb6?d5ZbPy39*` zC{7;Ghz&#Zm}Ehi@Jv}Nni=Y`mp_hP@TNTDd_j+yT?-NjKDDB0XMI*_JQ%v~ZN%rw z`fOUGI?NmR4ExYpy9V!$Ls!om*#1MGz3-9^Wl`tw@)lZOw|fb+7Soze5e6*hV-?&y zc>w#oH()Jy>OsO`21>6mWbOl6Ky^Z)&?v}|S=e@frF3Fm-AhCEOST=t({~Aq=I&!2 zb7}2|-V(6daUXM0e+3^RHp1Hb``E7W6)-;14Q@?0VtFeOc9kc>M=K-t-8L3d?p_41 z5+gRv#{mx3-2<1Q``Iil20v%L0S%-5ta8sAL6=XoZvVyoYFkuTfL}QnfBFIWK zVVdfBc(ySaj6RvLo?f@$W+;=uu?e6s<&ew&1+W*lUDm8!9yy%AQ}9%Oc< zSMj`M2oAY(kahIQK&hlGyfDU$Engpih1J(_xUm@vpP_{>FV$e#MKdPZX(TFGzsD~F z53!|-Vuge3TQNoN5R2Rul3R1O10`|}F?R(Y!7Q0JJSAby_LlUAP4t}Aryb@@-DVfe zsegteQ_Y#ThA+)n-NdQi%-O1pG_ZY@gG)9YW)ojrhJa-!a9h}6W-nO<^B5I1}sY^$_nY-%Ok?&JzhQ;x7wn|ug1NC0`uBTWB&9Q2JXfTx#^u-I8n zP+or*;s;sLMwH9ph}ml}FtB3AR~rSJ?LNV>d@E*tVy<9Geml(XeUx4P(VAB)=ztr$ zjx*ng)r-pi~|L;WGxE6_Uam62$6zZibRA7e2ib8(}5 zDpYpnZSB0v{iUOmC8d^=`xatv0#c!%Bl+q3etWMRqN zR@&duo*lc@B`+&F{({u+mxcg41w_z7;+e;>BL@^Im6`oO3?IhqBVzC z!{O{&5YXNVzS6CNXWeLR&?ipJ*>#y;b<+}W9>$vw&o-`N2}rJdP@nKy+xhRx7> zhcg>-V=mrKehVcw&aC?}3mm!i5!^_2W*^idP+j6OB;0mpryrij&S|G$T$?isGrol{ z=J`O;7#9}e@f?UDyuQ5BR-vU(hondtV#QJLe`i8sWk`(mSwD@F90eu?xGs zx)rVNBnoZcy09(X-_shdqw(bcSGI9f4LyUdgJ0xanOWEC_{by>*XX&j^QX_EM6XO# z^KoVGb_C$B@T#yJFMf4n z%iB`G$|x5-Cc3j=uVQ#KHwr&)aA%QYA3{UqQB0wIe=_OW(nG5jVREE9tAG0$UYp$) znwGdTiv@IVru`$&tI?fBl+Ye$ucZYK26?dYk)NRT<2%7d=E2nCUc>92%VB}O2OBWs z9vGE4!Z3di_V!%?qzA--eVzwT5VZ03)Q#R z!=`VZtaZvE%vws%zfAFBTc3v`pLqq=ZuMgRfjL+sbs8QX_F`eGv_DCaFQ`O$u~9kC zP*+72s%Rgp+cz5V?wJAb;iDIuI<*bANFNsr8{y5WvpR5<)WO{5<=$+5U@Hn$qlLo^ z==Hewcxw0v+~@Dj9(<|65Cu(iL~r(VLK()s_Qz+hyxG|HEbM}3aCk2tcIZI}YS>@J z7xR7Cs-64s`^akispi8jJ)evt6B}@Vs}EZna$eZitp%eqeAt|gHhF159XS7i4;yr6 zzu?X1Ha!2`hbdp_0^_|tV(1iKrZZ$Kd{KRgvDMa>*0yR0 z=_3>vA7^tK+rjqRXn{lEan{uPGnBa33LfEc)>-`x#M#S1ZtZdQc?#WgO?IF)l>FG+ zafJ{(F&1XX__3c;lVD=A5RPj2vD8lPQ2q1{IJx>UhohUI&&*e_I@6C;w@E-tzb05$ z<;NPdb_-rgw?iLEe{`S^k=&^pTlysbO>nnXV+HWz&rAO@Nr}S+xX-uDwOVqy=wwk z5;Wp1r6FKx8o)L@YsK*iA%dK+04Dk!W|ez1=N#>k`us^Ns=o{oo_ig@t}SlFEb}4w zsc#?~cK<1=*Y3vdftc@LaA@U2o1+xvXCVBE}hRJ9Ib zy@yHy_G-cji9u{)*d{nM=@m{c4`Q?Wy2H2!ckp$45WBu02~yt*v2k25>ocM>y*?3xG zaKPZcg4qK?Sa0jkuzgI8z(5efqzBf4`zIM-Iw9=JxCdY?X^rj<%v@k7b7*NetC`e>o<_%o3cBHJKxreE-W-6(e8X9nGtbcX zuqyiHhOC&aTqhFf03=M!)VS7{42i?u)MAgt;eJPLD(AzqSeo>^i|} zhRnitm3kcGbb|G=z9MwF)r_U5Pq082Vcr4L4vfBgf_Z$B7o^j^CqKWOV6Hd63sO9r z@XW*rc7Diuu&IBAX-n7s<@$(>?i~pR!MA z-}%F@KSSBs`+|<#NOr5F4l*?tLGg=7<}majROcRrqFzz#ghMgNuqZgPD2gREq`+{C zTzIM$#bCAR0@e$M?M6t@1#{^Q?20MO5vGVp+ zdB@{Apm9nxJG(bS*jm*BTJq6skJbcqTmBAeXn*oo&m((o8|j@E)!kJ16tm9(dPpZEA6YBad+k6{+;T5)4Q zqM#u-hFziS^=gF%nRz^h%`j-g1E1Z5A6~|=9HkG~X>wnb>K)6X9G~NI31u9zB$j#U z+`>uAd@y-$ENiCyV;#?*!u9U4%zSGE%JsU8SI)$;1`P`wto#V09>lVu^ttGj{uUED z#j%U;ZU{5?HzTb_$I6#K%rjT+K!xpbtX68dAi%dBldR&{c%xQ9t<)!k_&7E%U^NU* zuf@4H;+Xd%XNY)SiQQV`Sa;o%P^`gm^O$&6S;#^1b36vFj%R7}?}C@IGd|lN&wSt3 zg096X#E^IvFoX7=9o8&NFN|l;BHO`yI|v1Dr378^wT;ZH8FvG zuTK^ZncWIsZX~do#bYq<$ve<#O<=k=eJj;M#7q4)vfU);+NU zEmh{pzJnxIlH7)-Eq21=T1hP9=?6S?v?uy_C9(V4U!b$sc8ttPVmHjoabmg`vZqO` zqhBsQ-Ia70Ik**gU~)VLQsV)BC%85FDVrKdy~SVW)bmfJOUXW6s7DrVdV^ z@!~FqnWr$TjySj-T!8J7DQt#&KBTE9;POi;tZGgrENFJY0}Uyx_q1B5`MMTY3{GXX zXPaQpv9ChG|HIyUKvl7{>He5=4w&OH=VPLaVw-b3ii$aB3Fd$avw{gxP%xroP(+kn zs9+Yvte68P5EUh3{?}8RcMtQe`_1~#x_9o}Gas|oS@ZkKqWbN6s&~KD)lZkshu5~w zWL_P5>EovO@E%jMnAx-QX1dKjyur~_*67YkC zRhpTkePXtEeR;1kPTDLjgE{~3al1g{C; zZ_W3L(!p|1PyYa(_SIe-lixcyaW{Zpy3&_n*NgacD$ws%C>*jUBWO@)co$y+IC!?3Rg3Vn_Mxl4)$}xCrfd>!aNI+IzNQUn4eX z^iiG=|A^I#uw~=dAC>!)USzH}T-mr|NBN#_{_LQ42+RNADDU}v3**k$*vwx?dHGu- z*@((7SX_f+{C&Uj?CHc$EK@$uZ?|!W=9ZeyTG$`sc|4p>t_sOwe;hi-&40M+`PFpR zJnER-bEl%v75^lCi^q8PC-NIRuFu(~YQdaEZxxR|M6l z68jQ&vF|&ACF?xoka~;<@jK^mt2}?`$cHSN+0K+<#V$c3wD@| zGCR)Gs$>eY^5gY)#vJE|;y+8jZ9Z{m{c&F9!z)o?M<3x8e4P6^-V%i!){BWxj`QhT z#Sp%8t%u%kPrCAtB)S(48(saEI1=2C`|Vkx6^}Ft_Zr^+-|Zif z?H>%scfbFI_Eu2mo73a-f9iYb|6N|8oVp)w{XW!F&J*Av`WUuHiCOCvbE=8 z6hCd*h&9(gSG;jVi01n9z2bnlr1n4BCn?T(zEL|(#k=Qms=R5jaU!+r9mP$WZx^%U zPb*Fv86^6TI;6PS`OD(Q=+%n%g+3B*H+53nEBKxGZJMOwFF)dwxLm)U;?556@l{mk zd#+x*DER4};^y-ni553b?Vz~+-lHPWZaOW}&2_nj!BC*4+D zsA5&&+C5HjgvDO{y6*;!a*ly)KOp>We6{omdfqH4z&9OAg_k@tR&o8myv0W=9J<=bFK^ByL*Zsy84R!JwGXa)@PMy`dE4Qc+Who#L_wi!_j79o=|<8KZ+>+ zcE9(jkGGYlk0;$fq75rnK$U0vB~?4*S+))I=W`vah-H8LWb^L$^OJ+dibMyJSKkg0aSN`p`<()KVw=mN?bM^J(WC%AwbxVOddiuV-VngI%})~U z$0oCRfdTxT=?~GZb8XgB-X9N4%^Ut)cS2i`6~OPxy&DE(Ih$ox4dl1w9z+|eS?X1oGaMGQ{V*oyGDEfqZG}cOu$jmCywR@~6e_h<-&5ilTP|<$Yg> zPRZfoReB&#Xt!VJZ0?Gem4f(K*Oj8|(0FmdB8dAg*NFnj8Di7KAo<+*i+=A*lkl1w zgLvf6PWp%|`NHQ02Jy7Kr_6S?%OC#eW)OeV_l(xHP2TXOsgkqzC68@-gioq%Dth_+ zWcddk;VJj6M4q|H?AP2Q{OSNlQKDEJJMVgg_gLyJUVe#Tlf@BUdt9V^juOh+JUPN0 zJH-lZlHBw6#}R(WOaCdxi#PE3DSFp26-~c*@tbp!#r0S#QNO%5 zzfm+!G#}_F65D(8U0-6vAsN%=5#GGhl~7?PV;W`e%^y#67q?_gdG>nqd{6AfPZ?9k zNN?V^7Ee@e#mtB?=B^JK7IlQA7^?8Chu*qR-YG1>L;;cXqfwEZ%s z^431QMO{-?K*nUb4Rx&8J{eQL6Fz*$K=~ac8B^JZKK$oWZ`N1F6#C7FM~;hRA1}+j zqN@7xik)NG5*brN3t!$YCV{njY%ivb^X0WBXR?8{xER02mtVXs*O3>d=rzS@}OqnSDz?ZapWNt$Jw1 z=3Dylzlz4OEE$uw$dBidT3IdgX3zHcaktB%tn~Ou77*^ot4wrfBV|kjpZW2zkL;O^ zjA^ThKewyNS#KHB#y|Xd!hE?uvy7=6yfM^96vl@ zANQ$lDjv%5Gx_E|KH-j)xGu-fnACl|PJc&Hws;(?Yr3CbU*at)q{Ohx+I}88CQ_tc zmHXhX_smTe-S1k7bvq95 z+r{F9lZ>g)sRR6Ka*Swd?=6xZ9pLU)Lq(&pk>bp^1AO9ScM&3E8ei=opZMHfl#}D< zV26YJ${$>Gmoe>`c#x;BOwq59F^yS&kY7w3tgkI&%IkNKkM^)N3y?A0jy}jE7JF%z zWK8ov9^~t5nzC&&rW2(O@h11I*i;!)Q0qfHqrV(KGNw7h4sl0&Z?;6nRB_26zI1FP z>mp-%yGPD9JI1o#libC|(}#HfYYA-qGkbCM#UVa-l3dfP%f^s`QE!{kjI8 zyn)mz?cHE~5ld_pMm$ zT~FR$UhCrqII=yNp1fId3`>+T>8c#&ALO-uQ^r)>{4jTy*Lv4Zu`GDhVIJ_*o^6sb zeOYmsr^;)6zlHDia{K$qBeK#3XL_v41`!-l#SjIH5kvmTrV`~;7WBRkVJI_DIOZzBe zik<1sPggZ%wPj2d6l37 z9Th6NSMlJn9b(xI8B?OU2Okriz<$59mt)<7M@-CQTN-dtceMu}EVT+*m!gmN^57+< zR)aGJ>m8#!c(BxJm5r_0@I(*(N{*jzbG@`*#rE$ z^1byr`y^xPQ+FRfwSD#OY4Y3tOPu-Vt8$OZclM0!bLIgPGDW*)oV7Xc%)iS$y{9^-XjyNad4jyB zzbRpK?BE^dCyO*0Q%~m| zJh4QaXxPV56hFCxcTI~CbryMxV-I)8xoW6bA!AzcbqC)y&0UO_G1aZ=!e_p<7ft1u zo}hE#U7K>b&Y3AjO>p6Jwx#Hc%JEZcoeNJZVyXWuW4h?$!nf73H4`$X9Z@d4(F`xG zyo{;+2Nxb^YRXQ?m==`W$zR4;v7$02+dp^mU40yxmyD^+(4BnEB5#%^$Ml0mJNf-l zk*utY$!qsc9-xb5Eo4l6!gul+Q3-6r8+)mB*rTVCt=`pUhbGj?%Ld9A;bG5xOO%1_B_y~*fEc0+UJSLL;yA!C|5(v=^1Z7;`p z0z1Ckm5*!8Svwh%{~=et$tgu^AY-z-?8+ZZdp^Y)$b=;-_Maxx?&}|El6f7XFKxZy&Q#EsW{ecr=xs_NA8!K9>dtlMtp4(TysuZ*d*)nc&{wAK;%=5LB*SZ`(r{gyBHf|~UTQVkx0$cdb%9i?A8PgvPw{ZJcHfHB!OsPG$ z@L>~Vt|4P`o3Vu#D{soW%a~#}Z{h8ttk_dIer^SC;jeo+vJe@Q%l$3<*8*?$r;N!g zYYSf?*V>lKm4oaCiN6y3(_NUeU$n0__e#(m_q zUNhQ?W&O2{+sSKvKyOEOdj2;4T3+j87kaaCZnAz%D7z#?)ow zcH{Vo^wD3!s$jRt8BHF-!PZg`Yd;LX7O5HT8I4)-~D(tF$S*FJo$7VguiQ$%^^Qm|C^kz*$d6CS*+MmK*rW`QB`XjA{46 z4ZP)uNcQ}CsF>!qfsf{~Y_yE2xY)qgT}fbTKggJ#ZQy&yXR=Fwa?vf%Mt($U^C(qa{M@t^3rN;+Q^T~@zbu1DH|KOkuQ?h zy2E8FHe9ZuFOk>!AsJKk^o_hmMhtr{V>)NLiLaN}`YIXIHnUCqo4nSK$e7xU*u(=8 z?OCLZY3{O3{CO+RqGU|g2RHHJ9w}OgjH#7ePajg-Qj3x?-H+eIgD%*FU6L^!F6?L= zKZ^$~R5;%1x$tX$3qNv)pyq-brg zF6RfNR!z(;wPht%@LN)=f}?H1st#DeouyW5|MJpLbY8(7{C|q5Vy5Ed!xjAC!elY{ zoRyeSdL_>&9Vd8qN71~^N*Hc&F&c%9uLmci_(LE%iraOz-MD@cuJx%x=h-LVGyy zL4&=t4Kk+T(;c{9ajBJz$<4`uH#u*`X3LnIkI8pzx;wHk8Pm{v4!qPnZ{{jv`j+9q zKUqbxHZrCt(^b5Sc`SQ1%UxK@cWm}uPGC=y>_xz+Rs74iOg5w)7e`jE;?`2DzDH8@ zGY+rf{!*)Ntu6H>udL$NrB*u^+n7CzU&U9*@l#`nm*!ApHP=b4oJyFo$fm1#C#hB5 z3v%D*fvfovd9CN`;mDTHTh05+Ykj(msgCPv9w)DL^Wl*!`P6E@T3+iLWK26Bt>z_? z>{+ag>E4gkd{JA@s>tzkz1AAO+A~F4B4cvyx`vN$X{iOvnA%NU!=J6U3A-j^DzIUV zar|IEdbdKRqPE=Yd9bT3A9Th_tY4JOy1%gHVntqC`JC&E9UpNiL2OF3XG_}8=0D{g-Gj|Jvsp2l*OXd$9!=3Q zFVE(iq*ix&T527N&*8CBtF!fO!k+b;!%s-90(*Pu>usOI^91}9GYgxFLl5Tg5sQ*V zwX;@YXU)0%Rhc+(R>o9g>RkRcD@Kf!F--}W%P-#w6|-eb1(N1+KO1+EC1dK_Y97Cu zVlTGHn4%ZX<7*fff5`E3CSo4X3{25Cl`(ZMG+#a&x72TyF>UEPpI2#PV|HK0)NIRq zKB}*m79eAqcY8kXP{fqIlH(`EbOC>N)`~TgF})qTfLHD2$b4i>Hr@+($Q+qJ%a~4n zT)@MJMY2UQCd=jvxfzRPgJet|vlsFUml9Y(8B^u3g}jd(KcN~IB}^7^GmM`A`J32d z5qFVVnRd3+KX+Qh?@Fx}bdtY6Hx_YEIev=v_tGwwS_DeENP%`=f&9gVPJ zZ4NBvw(?qEEMqzoznI&}YrW81Z&sk$65jY$D9bO$^kJJN{F}Vi7s;4D1TW#;lI`XG z2nlR@mVAFtUh8vZOrtv5^8-HI5(b z8}6LnRJh3TQ(@NxZX>KjbGcV|;pY>0kuHuRS&pCW^(OLIxyQRE_X>YBV1Vi`B`3`Jj>Qy6qMtqRLiN{C*59L zkufo1K<1E&4E> z?;k3)k};V!o54G3vCK!tG{$ZQ&y;(-XQtVUCnsm{5cxjWL(av`Uo&_isa4GJ6unjV znS2GV^#PXp1CBHKBdJxF5;kVK>ofT!IezB#@Y2?mp2c-itNSvhe8Xn(U^#wVPg}8! zeY5x=sa27#j%>xdS$w&?)=$frt~9acqvf^!O2#zB+L{lO*SfuoDe#yz@0MoI8p!d} zB-5H#l^&}HGNu|GYSgspM>VDIcW zxv%>-8PfxoA^gcHD{)SapKJ2H{ReVi_aN!Zx!3&fHp6&=+}GWt6K5$)hw;l&tLbvDdHajQ_(ZAI zu5p&y#UfTbPHNTgs&&|eK2|(gYIR2ErT5z+%cWLMc}+!w`&N9f96u|2=&aQ^yRj3^|>^atPJJoQefm>^@?^kF!!C-<6fD#!Hg<|DW+%U+b13n7cFDX*=w`EM%@{i<3Ql2`5Mr6tOk zzTOzg&GMPDD>9}96-M#8dMma_#x#BODEZ#IBO54VN;y1=_p$S4{xT->#8G_TkVtky z#`H+O=ReLYmOZm`7qx9i^A2+S9LTg6`$9+ahEl6z9pp2GpQHH`xv%^2uoQijZe#c? zsa1`Umih^s#_;D-s~69#&GN*I;jiWRS=`A>>se|n50YBFkuhBwGL{dPT3wMb>GzK1 zwWU_!GN#UN$MU)ITHh*T+SGU)pD(ZV$1+M1G1(m*$Ma^|vl%j`PwC@$ z;SMsLlQF%t7|(~DO3~iRn5M5C&nH+}YIZWFJT;L6g!@!yh0m(Z_yUk$WUIP6BWv`m*Jn3SI9y?oDKANp}ay@K5k}jSd4&I zs9a-zW@RJSr=(YCSD%Zl`bjqduTUkcN37)F6iME zYG9Ye&bB@k2Cq=m@Ju$f>HrO1p|2~x$bFW7YVZm*d;FT68`(p7g_c~s%~ra|eR`x< z=s~e?b~C|Kd4)<%Kfv0TJgdAy=B^H`SGRl0D>T?k$2x=>yh5(kKWNF`$;vC#&!Vx` zEILzpg*scA=u5T8QeL6VuCe+)&r+0EDABu(NIE6I>ngoM{$Cf13Hcr{c!h=y_YkG0 zpJVU})!cGQ^t|cK;1zoCOupM&ViSW`D9_(^_=CuAtEP#NozET&hI@(Q)-K9n_{{Ze^_Mvr!4ZTepq@Ct3dhahz$^4*+C%15b-sXCsE|ltd~yo`uh8tdsch`9YkGKv=2&Gho1}YT z@Cs#a%w*opI%@C=t@!qZZTy+8!7EgB?;E!GK^Nr}S{QSOiLBMiD>Sp)Y1U!oA>|bc zy?>CIK0K|wLcQCqW+%JdRbHWdEjqJhnQxR==-}!U?ctxv$}4obp{9-ApQ*e;EkC{r zE7>F9Z|HkVRx9gzDLNUu=UdoM-k5laTIP!Go>@j0Y8gI8$l$_!CG{~8Tmp$ooQ;@gX$}8k}Z4(O`b3?!@RCk^adzo=kz$^45;~eYf z>n`9GTDaf=D?e+IfLCZxu>^MU>z@K%p;jeR+1kr@^zaJRvygj#98C#>S7`Z3d0lsE zrNJv?IXjsJyCrGx3fYc&%bE@BsJuc8uHR*+Myyg^A@8MUSbX_|$}8m3!IOFH4_98H zns?W*T3zlauaN#kH`b}$8|4+M82?o(DZVJL(47iBwRpQs0t@mT_3W?M5e%NX= zgI6fl#frfzRQ~rTF>`cj2CvXbU54nn)KP<1Xt?zH)L(e$6ud(77Nm<2g%9ZA z6`DWeqnI?cit-9|^m`^YY#Oh;LRP1v#Dh88l~<_S%3v|Ob&&E3J?*no1jS!gULmdK z43S~|M0tgJxYQLLpC>A>kaPTTz2}iMqn*v^;C*{3aT>CHquh6Nhk?d`ay#ijL)RnPpSeU&S zDZN7FhRZ#69oq?bg)EMwusf|E>){o$sFB4En-|u@D>Uv!Ci^zDjs~yLqBqHGWUF`$ zUZLTY-m#QRTzQ3TuiazI#Y*KBS`&O$dO`LpuaJ+|VRmDZP+p;6>ve3a#ckyk8r!}X z+cx{P@(R86G+{0l@_X;nE5z~-)1q{l$}2Q+p?6qk`z+-Z%1VpS*DsW&yh4NDH4+og zzE@tM#5{Il{ryMED>U?@t4NH$$lw)fcrHYIc;V0B75eCXO^k}z!r&EZ-}r^t;y9AQ zE2PtTY80@M+*JszG=!UG_wBous$2Jlvk*QZh{t4F;jVkVy5L|JD+`4UZL9$`>?rB zUMa88%>(P1$--L#ULpPQBg}7sUcf6<*)4)aZQm#06&kkTJ{x1QLclB3&+{F7RD}t6 zg?5^yu&Vpx^zaIu`Y!#Ubxif}3LVIw#ZK6i)8G|)KRAVjTzR3vD|F%3JNDR2Q(mD_ zm+!L{Ete~=Q0D6hmeO{g@(O({>cvhq&?~Rd*8&?@@wT^=S19geUuNg~N_mB@4$9AF zp82f2LWfc(Yk7)fDz8w}s~f|XZO&3&p$`sW`T`Tvlvl{1Pkm8#Qljz-b@rYm-bFlC zUZH8$yF|$nml?c5dlnrRKidQ{c!eytMT??+wlR2xx(s|S{`@+I!7HSH@=@IOGiC4! zeUW?7#LV2I!7KD#=11!WmunBN(AA>d)E4CxnpyUQxV*_Wtu?Ti~ue?INZ=BO# z_?)V|LK_|gg*97{rMyDF`w!Nf`(!GwP`SCkwfm#KD6i03tDa1M=(X|+r59SqqL$wl z@Cu#pcbK&d5dvPJ;*-y^^gIUyyh1)s_vABX2LZ28{=~P;!rMZ?E2LdbW^D?;*TXBc z?S3ZvRJ6VxUZIZlv)H>0`89ZjjzpwLZ~a3JULn7=@$9EhTjdpMb2e7KC%8m;g|f<> zW8=?zD6i1)S>9}X!YSny`s}`u?QL{Zd4-y`9?0H2i&I{qnkI#ri}qQ0g+gA>(>CAC zP+p-Govp$ec*uRIrB~=ciC}$;@HFKWvI?pr8WsGYyh1@er;C!_Pn1{a%?B6Z+~Nv@ zSLkQ6U{QO05QA6f`}`;3RwoZAYyh3+otzmoRK7jBF{djwb&HNND z;1zOfafXezJt*K6O4@vv>Cdea@Cxx}Z&_r^P6A$`CYH(Uv&|Phyh2y}Gg)kU8$G;2 zUAjtNSDz1N@CpSrNM$vXZfWoe6>guvtSkPhyh16*AFyk?7b>sN@=oVj&A#r+EA%1S zhu!l!sk}mtEgV_zsyCEZs7b(JmLk_h;1#;-UyPMKo@DR}B|2!coHLYHXi>rHVcop5 zlvk*Wo3H+GsdVKP`c$%}@IL%Od4)Q?n=HO=daArax2En8HUq9Qc!fsB9TkIOk1}|L z;;pWV&m(p)c!lOWKNTCJCNp@2?)!ca?Z4Du@CuDBn=UF1_toGPa`Be^U8brTyh6ja zNv~O>ReE@Z)&(Ysm(j(PSEyKF`Hp(jVC5C+SN4W@%pH|isG-M6u`t$0d4-O5a2K=s zoL63@AL4<*E0onrJm3k+E7bDnEq$pbsmd!9Js>fxRktkV6>2`Otv19jQ+b89 z1%A=G4op^FA+P?OSW^AB$}41ha}}Gn_O5_eXr}!^_E)_#0$!m@nc=L+<3j>op_Wc} zSc|c11iV7uX1!tkPjwaW3e9}_h1I>AsfSm{YPs~0z3QTeSIB=%7Bg|WZU(PVUZ+&% zxI9XOSLn%`1lGx+x$+8aIsA|f>p4$(g;vhGz*^nit-M0}>iexyvm&z-2b4V%nu6~m83U!#UQS#AZyhmXoDRBGh}ad74{U$o0DPkWQGdhgYa!+s}g4 zEUdgjRUX8Ng98UDuTWSm>EZL;sJuc~o}Cgu<@!CmLd8yci0{?UDX&o5YfHrN%dyHU zbahi(vCA=Dd4&p9f2gl_Aw_wGZWPV0@7F;3jHFkn?Z*0=#l1}B6?)(Oy*B4!vhoV? zOBU?z>$l1)bgzX2>#^pZfLEwu$ph@sh_eD-p?zlri|=$;z$-L={cSe++gbsyP$%El z><;TG;1&8dPI~#<{MN%O)VW_K+j?t|9$ulP^RrmFyGPC76*~Aam06ZJufZ!+bL)Gy z<$Yu270R>Y5xbdU$KVx8ce%*+4s%mpp;;^ZnR)dS$}8kDU<<31aZP!JGIoq$DN|l3 zuh7q*Wm#FbPs%IQ{qZ)fT8Rwh6{=Xb>Zyd|a_?&C70TzoM?W_(U3rE4qD)0p>__Dl zYFu%w_}%ll@(NY3+9ryuk7n=+nRN^lA=bwkyh5QBFN=_IyBNGeyRSSJ(VJ#5c!ict zPZVF8)@Sev{hFL6?sN{*;1w#gB}-(+Y%qgYsBxi8QFYD~J-kBI^`AxZ?EK0rbpFsQ zG3Q=izIw?TP@T25dp8z;y<%E;9|5n>wN#X@(QIs*~)sph*n-9kGx~pr_IlmSE$F~ip;IRC*>8& z{L4-Ia4}tZg+i|$Y&T!}5#SYC(0YgdW=6X53jM5GUQC_wNqL11`-~K&>b_83p`|ff zWG-}#!7J3^gTEMjGK9e^AvSw_m5c zLL)~AvF!L^#fLEya*w1WQWbNr@<@K zFo3I3VB8_M`F&)sNb*6}&6E zEK7NX)`dIj7x4_`6`H)Xv>5;Glky5Vx3?14zP?aiAv@h>u{R`!!7DU!ho5-z;{=0O z$RzrLs6J{pgI6f-^FuM7&t>omU9Iw7{57r_gI6fpFIDVma7BYxh)u~7TmHOg2Cq;* z+f2b+dg|d7`W^a3?5_7s53kVm7H`DzJKdC5Xf3-VPQP5Eyh40uxLDc8Q+b7A3m+5- z>&_^z(2u^W#QXbql~<_apB+W$gty8oRBS|&zO{VM1YV)?7h3A$Ph~2v&`bYRv*tWY zd4+5X+|{lYm3v7_uTYUnt(kp+1mzVfyI~QVZ1X^Qg+fBzS^URy0$!o@c}}tI(|iQH zLPw_FVC~Ot67UMG?G?vH9Umm%6>@%<#9Ta!3V4NnduFh#{VVkF3avbx#TFfHW(KcN z$E-B@y)u6dUZGiwKCr6gYbmc#lRi(G-Qy|BD|F)575N>P9m*@zZ_!cKpu;ic73%cK znN9M&s=Pu4?oVP_x1TDn(8I*)EaLtL^T?kJF2q6_Nfyc!frFS)-r5 zJVSYfvhEZYA?uQqSE%3xOVRZDOXU^H3Um~~m##B-g|?gdiY}c_GI)ie_n#MW_xCV( zg*yL!AZl)1z~B`sXOkfMWVB@P3LWf`Do(lH(BKtH>zgGyeu*=KSLoH=Oi{^O)59zD zzIn1RKcAw9SExbq8}YhtXXO=YV{un}@3LBXg^nMU$2zx1d4*!192NKv-_CmP)xl?$ z{B{_4mGfo&s`$!^BR+Q$PlL-SKL6ZFoH$!Rad+JbvBv$Q`leRR@At*IEr#!F-T3-N zbQ!f*l|Sl}Cp^Gss^VH53x=0JSxNDtzJc85 z2ak@*5@!4V5a3G1-ij_3GZmM;93w^_b5Wdrs8aa+DfI-t5$B*Q9UgtiLEsy4T@Dur zx31_b@QparGRdOAnHYg@#BC0~BU;Gsli(Y1es_;km%^Q7F|N3{;aC{?fMTSFI*@`v7@r}5Ikj+}aAJxP0jkwdTYOwFsDywhA z>CNY|JKxHvZ^TVMdXRa%FQmQ^XI=j?3tyEX@QpaT`tMktFAoL25x48NiTU~DlLFs} zTi{yU{6x$)fp5f3v94e~t(g3Mli!HDU|!XH=-6aEz7Z!rR5xD`m|u@?#BJGD-TeOG zVH&;>*X55Y<~;|NVE9JdzCGp4wY(D zaXnu$d?Rjt{27*-_(QG>%kQTxcVizm6*b2<;%pX;W$(X~GsidL79J_W1`V%bj&H=3 znX*w!Z(ZFS--yFrTPE`V-~qv2TiJVl@$9|5l-DDBZ!g6;_73CNYYTgB;cv6|_EMZ< z4>F#;x0fn!G^!N#_EL=FU@tEGE%qG49$ne(2<+VjmhID?XgqswFN%luP(z%ww;JNd z-d@TtgX82lFWU2q>NB*D<7Dp}w4j;cS|-Ah#%%FkE($bPr9Rh;|%%-rv1{{Q)Y=Ks#M zmV1x;@4d(6%!>*nT+;His;2UvE{nRbf>SCgZoX?P`}MB4;u`UKw&lfdmFLj?5jhO~ z4uk3U8JvB8RQ2ii9Od*o52oLLFx?lx+4o0v+_ayT>OPWPj{Bo3r~6KJJGeipa=K5U zJp2BrVxapP%Cql}s$90G?t_MQ4EINHcDc&g=zfaw>~;j0?!VydN zPWN||w<;WP2=`-f_W3H#?gwgz;drQ%-EWGs`%}e$^TzQ|C%gX@XX~Qk|DW`o+nnF; z&6(#XHg^_Un<#beg>R1+{oS4^zIvjva9aOSaku^M`kS8VigS+tzstPfKYN|#d>1J9 zouAxyesbUW$$jT1_nn{IcYbo;`N@6fC-4ts(aY%t_|LvGpSy?J-**qST+fcdBlCCh?Bvvo7(PvShW;mdcypd3 zd6#g$C@^`Wz}cR%a4>nPz~r$4|KIdnxBVQ(mzS<(vCjMJS@2v3Q;UaJ zzbWpts)R-FliwB38JE{0VA>DGr`~+zE{_ddywN?rz3@*}9@;OQTO=FG?aO)cemf1^ zy`2-^lxb+^-VGamrka6Ww)N&~iy4mfCb}ta9FwKm37k}s51*E)*r!-w{wOhBakUnC zxi&UU@yZ|h`NG>NiYt#P&G+_8R=odvU2gN@v*HxqftxrdDGuyEp4-@dQryR74PUqN zqvEY03oLAxJy+}yzs=&k=MzJnd)^isw>?sv85Ci$rQbuv;dvffw2phA*sX5?9dR*- z!n&t{hVrmEg>-*K8`xu9LEWM!25!^0zV44Vch%qCj%lhpw$4y~;zdzi^znD9e0t<~ zi(mZ>@ju?Y(&Ep?A5{7IC(ag5=i?Q(mmkP8`}3{hEfvmKd~|xP_|fUR76V?qQk=0S z(ZaR4p?tzv6WxSGZ&bNY{!+RlCk=JZek-Z#``N(#pOw^^*EiJXfhBd9ha33U%#ym% z8w|XyYDwLWV+NjdwuJ7_+Xn7Gtc1?|y@BoC7uTg`8o1V?;<|(%2EJYJ-^x?niW%!a zYgNqH&arz%jqP_?Q`C6e0$qw4<4G-B)EMXL^diRicYi2iJTH|0TxK{g)Gyh?z-VW6 zIRm5pPjBK>pWwJBPa7EVn0go(ah61Y9IYc z$3;I=Jm`Ol6S`3RE>r918Wwx3;`AF`M|Z1>fmz2ox`-tPZdkgGu6K}u6K~Yky?kom zrORvUObZys^T67*btmf?n2B1t2nz#`>RU^#|WWBhCTS2vy)%2(boTx+Pm-QB=wr{FXL zqkTKgz&Nf}#=wZj{fpt+M4ZkK4UG67MHv|9_4cBHalTZJexUm3A8H5vM(v|N>A2`; ziU<8qaY7f0Kl;!77T%Q%zfs*T<+G?0YTzO(^IAOVYxo`eI?KeO{SyP*n0@E3MrJ5| z2lYtfY0(DW&p-0w^)gj?+|bwDW~zbvKY7F}Y%{QLxm*15UIXXvd)Zh%`_^e={gA{E zV>>4Dn?}_B+oZ$B(%v!)mr@eJ>7V8l7Fxq%VCTTKJwygaKI80Smn=m)Bg{-JizZ`3~e zla7mirg+f*6en~+{52{ja=KrG>3$9FlYPGi)BPGu_iHfSufcS`2Gji-O!sRr-LJuP zzXsF&8cg?VFx{`gbiW4E{TfX7YcSof!F0a{)BPGuxfz&pGce_5V9L$Fl$(JmHv>~{ z2BzE$Ot~4Dax*aHW?;(Az?7STDK`UCZU&~@3{1Hhm~t~P(iOk)^KV;f9k9!%E)n642pT{~d9roeQqf$16q)3r(E z_|2jE_{{;+H4dh0A56aqVEU~9({Bivep|rwn**lbA~5|%f$6skOuuPh`mF=gZy=a{ z8^QFO38s4=nC^XGy7z(U-Up_8ADHfaV7m8#>D~vXdmotYePFuxf$81{rh6Zl?tNgo z_kro&2c~-;nC^XGy7y5z?j2Mg_Y^SQ`@nSX1Jk_^O!q!8-TT0F?*r4l4@~zyFx~sW zbngSxy$?+HJ}}+;z;y2e)4dN&a{(~roM6gD!IYzdDR%`^P79`77fd-Ym~vw<<;-Bp zrNNYAgDLk0Q%(-1Tpdg~JeYEOFy;JUnhQ`l<~URza~v?uDZn(>0Mi@ z0Mi@-(l(#@@x=z74#{-QMl+*YD)3^fDcmvZo1k?Bg)3^oGcm~rr2h;cm({%x+>jg~L z5tyzo@W0xeo%F(3{b!u}du#X|rtyQmqHzVL@dl=G2&VA~rg00V@eHPM4yN%Brt1Ps z*9(}gBXG{^i}D$aVY+XE>3#~P`z)C5zhJsAgXw+^ru#UU?(bl_?}I5H08^d-ru+d+ zc?FpA4KU>);D5Deo1_cub8n<8?&tMwoU>g5m zx-P(Uy@2UD0_VKGXx@i0O!Gc4&HKPK?*r4k4@~nuFwOhGH17k`ybnzCJ}}Muz%=gz z)4UH%^FA=m`@l5s1Jk?@O!Gc4&HJdFo*Dk#pLvpA&@m^Ib|@$9z@#0Rv;&iNVA2ju z+JQ+sFlh%S?ZBiRn6v|vc3{#DOxl4-J1}VnChe&Ff6APl^um~==VM@c4g;p=Ghljd z1E%LWV0z92rsqFkdM*T}=S5(8js&LXOJI8L1g7UvV0umkrsr2+daecjS9*4h^Ci77 zCjS}dKIeR)=KC~$&{s6Bz%<^#G!DTuKEX6@!8D%1G|s^^{=sxzfa!Vx({%*Sd41)a z+Y+nsoV|9B`Z?DHa`J!08Ud|GAcmYw$3;0E7ffptU|O31)7k`>)+WHTHUXx!2{0WC z=bMvhtps)cSB&~puKG5|dl9teg1;sH$2vLJZvGknvo#%B148>bnc6`){VkZ*gL2kK zJURb1=Nc0+>eE^knAWPmv{nVCwJI?EE!wBQ1=HVx>2JaGw_y5Pw3G91b26>1s2H-} zfw8PMPwgd(-U*ZK zsQLz;m-BD`U7PrK*}l1qhw4bq`L{XSG#(4}&9meAhrcz(jCOLIOU`rrcYmwuAclyN z)i~n8x!*WiS@Eyvhho-|vWg$97!p3Jej&vXB|X9`Rr;*{_SpWb;qpJlvMgNwn_^k_ zwEP>zvW?TSEr#}G+o!XSQ%4>XNaZWe}SeD8D@lY)5avVdJAChfw90SLtJ_DmK zaSSTQF~F#gV}Q{PjsZsd_z#RS{2RrCzdR1B^Cs3^3xyF~IVe7|&F$bkDA@bO%F|9PKOJQ7+4r z?qKvmjyTmZP>w!B-x=C5=uYLbzBw3uiDQ7#PL6(4x}zLr_%|@>=IDQ=JIW2Z|1Ym) zr7!CI$G<1W-x;Y_?)6T(<61-iV{Cy*cQENL`M>pgy}T4UVhWQ@h^aguxe%Kjl8 z(I=!M7}pklBf$T+uirH#wpwhS*F^rVRO4XM5NumEpC|q|)gdPBQQm&yD|Md$qnz47 zIoPbx?Cf#jVeaH(r?}ttZRWEZ+bU+(Yt2`SS&GM{%r_64IbHFO;uFoIhfS8hm-*^; zJ~POC_P%k7E3E2fK5NoQ#beH!n@_kiMAc7;YHRLWZlL1MS6Z8YvFvRuk3Zj4G3vkC zAm2@v|A%%q-ehRU6YcK_Z>P#}+?%snD@HtVKU%6fi1YID7K#ynm0!(O9bB_i-pa|_ zSikGBvuDQhdZs-$o-fL&A5fqA z2klV5p?&I49GChT@lgLGPSOSO=hO>q(9}bf6Qe$ubOe)*VA2sxI)X_@FzE;;9l@ld zs-LYRm7{;CK6C_=j;emPj$qOeOge%|M= z{cIhn96C~c=m;hqRsC!o!K5RYbOe)*V8lOr-%I28tUAWPINuWcU#N2QL&d4jjpIBx z;;CZvn?Cfhy1t-SiQx}bIr_Qi>HDf2dKFB)qsk3>-7?gddi85_-B{jpX0&3|?{?#g zv7OzsFRAMY?H`(YL6zgUJo20>hhE(_M5=PcX%-cs$`Svo4H2pwdQmyfm+GS*s2%hV zwU2(I<3cZr2mMTOLNAKnpqJsiaNW`QqMZ5x^{Ic*4)q(_r~brosh<%K^*`byUH(xo zXa^l}jyW0iQBFF7Nk=gH4aWtOj$qOeOge%|M=Syan<>()(kA4HA9rUNFpRFU9 zbOe)*VA2sxI)X_@FzE;;9l@j{m~;e_j$qOeOge%|M^!&tM=FPoR3AEmNk>&bTSqYI z2qqoDq$3#d*R}j3`yT3Hp4HmGIN#a#>Z)?|!+bLXqkk?;s-y0+=(j6lYpXiycd}J2 z#pvhHuWF!9UFc=Kyt*ofUhPnsx3J2_`XxS^8rwN_rlMlBA0AdgF^*gK zZF$9rr$jFUBhGd2%clbX@2~@t~h6PUuDPLoYfn zTz7Q7D5riv{n^?5gLbIj&_4Aij!XTFc&PsoC+YH!dO!a9#(BLmGq5_} zN5fP(`eB@ffzdyK(}$|DjeZNBG(^>bUL)ICDn>s)jvu5LdJS9sm#T00ogApHFI;!u zJ^QOVC|}&6pDIWF%rAY6?HoMcTQS-{a;BGJ95?lSPsNBQv!8(xr(IGHRgU<(-RPl? zi}Rv#oG;Z!KTtd9A8H@{M#qI-6c75D;)Grlzu|Y%a9+6X=zLL*e!%Y!>Qn!q9qKo< zPyLDGQa>Y}k=gx^I7yd()T@Nl4m#o-b293qoOA?}j$qOeOge%|M={cIhbNLxb!err{;TvA ziqVeamF33vx1C?67{`5Z9Mlq@$`Y#|iowOge%| zM=bZ@V(`Jhq^`0w^d+cOUF7u({ zHq6N)E9tgkhog=bF{ZOOg z4D~Dv{Ly2kvCb1yYvbQev9~d{8F|{)c&vJN?2Iuq3Yl$;EzN3<1;xDd>>T5{1iqYO zJV%t%xuZVy3EH8)Li^N*I4<=q;-NlAoTLTfCyj7kq}{-+(~RX4%1<@ce{gKFv7KeM zlZ@?~j+kgXZu!L%jPdlkJKh*)r1f}X{9F5sH=Y;DNjuc1en2~<9oi@Da9q+3@sM_i zle9zpq+Odb?TmWmb!%@dPcEw&>n~lvjP1mpGB>twew`bS+abup7*7#PoiR>lz0Mf_ zg(o`Wd7+&2LVeN;?T}t*pY+0UNiW1hdLd5I3-Oa)I4{y`%BD8P@{#`8is>4o~F7uq4c&_48{ z<3cYm;(=aZ#0kB?h@bT8T|BQ*uSz@e8OsZnEMU}Y`|N^7y*?Z-WYp`gtA&kvS^5?+ z##3`ZQDdAwCyE;5e-vBPcwQ(cy-=U@LOY}v+9$nmT+$2ikY0$B^g{fk7tV|HTDsQ6 zSYD;VFHZII_y5kRoq^Y~IJLj_KnADdE`OfJDW3Pvshr|`a3zIP{PS0*sCyB9qfkzI zp+4z_c1SO@PuCZYOV=0Tq3a8A()ES-NiX>u%<*g=#~N8}Kc{lDvWJZI`#(BtY$xw1 zZ)5w{*ZCTcd#|UzF`gMN0meA(#|9eXf94rzJTH{f`Jz7c1KOefLHpEiI4<=k;-P*< zoYen_pY+0ckzRH4>^7EnFSg5Azh&1Q#&(vT+h%M(c-I!=asBQ&8RIFx(a{)ZzO$Q* z@gH2g$#`BUC%sUg^g=tN7uqMia9q+0@sM7Klk`ITq>FF4Tjr!!)!t9dseE(o1aqqY z)*{uM+Bw<1f>unDM+&PI{p}>4kPkFSJj3 z;kcw1;vu~dC+UUwNiUoi>1Fopg0cKkfiPoz>-Pc1c08URGPZBmdXG6BcSw^R<`mDb zADhi7&ahjX%qjj>5gX<6BSY?ia?%U+NiVcRdZB&N3&*AYL_E~bh?Dvs@slo;dm#4$ z;~c@1j}hbgqdGa6*4-!{LmkS;z?6@HDIWtG#~7gc z7#m>9!N8P*fhh+AQw|2E91Ki37?^S}Fy&xi%E7>tgMldr15*wLrW_1RIT)C7Ffip{ zR8D$P4u*2d!N8P*fhh+AQw|2E91Ki37?^S}Fy&xi%E7>tgMldr15*wLrW_1RIT)C7 zFfip{R8D$P4u*2d!N8P*fhh+AQw|2E91Ki37?^S}Fy&xi%E7>tgMldr15*wLrW_1R zIT)C7Ffip{R8D$P4u*2d!N8P*fpJ{?=71>&15*wLrW_1RIT)C7Ffip{V9LS3l!JjO z2Ln?M2BsVgOgR{saxf|tgMldr15*wLrW_1RIT)C7Ffip{V9LS3 zl!JjO2Ln?M2BsVgOgR{saxf|tgMldr15*wLrW_1RIT)C7Ffip{ zV9LS3l!JjO2Ln?M2BsVgOgR{saxf|tgMldr15*wLrW_1RIT)C7 zFfip{V9LS3l!JjO2Ln?M2BsVgOgR{saxf|tgMldr15*wLrW_1R zIT)C7Ffip{V9LS3l!JjO2Ln?M2BsVgOgR{saxf|tgMldr15*wL zrW_1RIT)C7Ffip{V9LS3l!JjO2Ln?M2BsVgOgR{saxf|tgMldr z15*wLrW_1RIT-RPVw6)3hH_$*=RW8Bdp+mOT@Nzog>^lQUpybCb*TRr*MoA`%?*0t z{Rh&E*6X1ct>feQKdtX$9Rcq@pgz_S|uaf5p0a?)yasz3`qG=|%4~K`(mW z33}0cP|yqSiIFby-l`aS6_oGAQTczx`$ak5$;^EZ)9`zU_ju9gYMn0oy-?^y?~6h& zybnye;5}hgU+RVThpGI(;yp~tCy|FxJ_)9L5={9dnDR+5<&$8_C&83Yf+?Q_Q$9)M z$S1*+Pl73*1XDfwp9E7r38s7!O!*|3@<}k|lVHjx z!IV!@Ir2#`<&$8_C&83Yf+?Q_Q$7i%d=gCgBsiyD#26nrnRG-s=?Eqr!K5RYbOe)* zVA2sxI)X_@D$ku4{O9KdH1CF{H17t}ycY2FQ{c{iBm-C&w`gK6Fkrg=A*=G|bLcY|r(4W@ZF znC9J7PS+jHyHQT_ZZOTe!8Gp%)4Ur@^KLNByTLj2BF6a7$)qF7Nk=g02qqoDq$8Mg z1e1|LFg>3H z)ALC%J)Z>A^GPbF>yDmJqMV*jg6a7rn4V99>G>p>o=<}5`6QU0PlDG>p>o=<}5`6QU0PlDn z;+#5yNk=g02qqoDq$8Mg1e1b`c9S2P7IAB`G0n<7TnAUNqoUS`s$3Z!*e~A z)^WhJjsvE395Aip(7P*Gg9g(&4w%+)z_gBozom5?FsAItJ9F)^K4w%+) z=(t$N0n<7TnAUN?w2p(n&8Zi0P94FdBbamqla6505llLQNk=g02qqoDq$8Enbw@g) zoOA?}j$qOeOge%|M=L9r!(@?|9(%kiPGM-$VND2YwIfdm#8d#P=oO z<;3qHeLn>LtlaOY82qi&KUhDae#5#F^(WTfsh=@^sQ=;5B3=F?f7UD^#3y&DXscZ0$7ZZMeM4F=P@!C-nfn96C+i~97wG`$;)I`nQZ znBENr)4Rc7dN&wM?*@Z$Ui5xDG0vUN5lrU@rgH?-IfCgN!E}ybI!7>_Bbd&S%IP@_ zog>QW9Km#sU^+)Iog_xvH7I|)#j{u9I-z?Jm8F<106J3zEf!*Cr zbVEZ8Jbkl?&gHy;Ef$#Q=x?Kjn&`|Q8_M&wG|_!}ZQ#oJOmxv741E32Z;PGD27Y1o z+oE>5f%jkgWidFzz+=b!GM3Ly`)RCSeEUxeYNvhspBB`<|N9>nbX>$7P}b1S@)3D- zu5snmc^%jC=)@}n*RGOBr@b}su^%S7yzdR%`jv_9>n8)xx@MyLo@!tdy@~G0Hv`Y} zH_=VcYiPfzr-^P>Q3LjWNvmmDd=1WV*5c1=|5CH8ourd+WAQUrt}hbG{=pWpmF$8{O{nR{R5 z8~Mif-!tZzd(XA@-fQhu=A7%GY9B=Up@5``M0+2+M$0+->x0^xnx3@j{86NSeFjF zyWQBOqdaR|(52&BnsaKGj&E$eDc!T*;YHJW@=lu3xdgQCt55Dlu9{H7ZgHOJs zM?SdD*B;p;AGlt~NAJ)hKfXcm>H{jBO@en`x<~%b=D{m;>XBF9I(WN18}fDE4W9Q% zLq2l%;4{A3nAbQk_{Q9rH$5zP?kiTOo@9DM3^Ejhmt-0%FB{NbCyCl77O zkB$l6zB=>w(VoCvPJM4tM$y=Zxnpgpw^D^KiSYLe`iL> zH>l2!?manplj@w}Z;TCI=Ka?E@_z+y{6=eD>-FG)kF@4tuLR$9Q)?dceDJB~wC2;F z4L)N3)_la%!SkDYly;$}s=rVCw#dQ-XPqGVk}u)_%3Jt+Q&+{LAjahkx9Z-nv zZ=N3f;_d8UG%>!n0C?q{9xL}<7WiZF3vwG zn09f^(ZRHfZygd$yEyU3!L*CphXm6eXWku5JH7G6VETtA-V3IG*ltQN{lmL$!SoM9 zW(CtfTsJqE{^5do!SoOP<_FV1Y*v@kKQz|$_pkb;vuB15eQcMJ!SuaHExky9^3(Nu?p5`B%TEh^@J5K#|l#_qf=Kl!hpY_ex zg866lemR(bR{v*%`DYD#G?;(Z&w*>Rgnmat0f8|FLgZYQPG&`7o z_dVU0tvy5j-LEzV^Y6a8XE6Wn&dtI6ySvuq{JU>!2s!`m&fS9fcdyI(uhwdEA81ksW!Hgj<-YS?eWamwT8AC2uudY*#UElp-Fk@Pov9x7iENvMW zOIrrU(w2d-v}Ir{Z5bF#TL#9`mVvRfWnc_%-C^Gy^Az6^V}73%a{-?ra|E9)a|fR} za|+)Da}D1Sa}edsP1I-3;(eIQcz@||Rw;G)^d zw$SUP*~zvrp!b|)TbQ=foMc-#^wK%Ww($B3l}^1aoY8r1vMo$pYi_bFTsCZ0vJHOw z&Y8)!`Lzk{$v$Ds-R;RfVZgcV$v$DXAGas_gk832PxcApH*8P#31_U^p6nAg-=sa+ zC(In&p6nA=JfuC@7p*>ORux_a`EPpr*r~~X(?cVsCjU(bzBx7dZ`yv@50d|;JNNn^`EPpS+7FWdrW;3p zko-3twfwZ?zv;&>O-cR}U)p_2@?Uw~gvrT&^qntHPX410eQa{_A3b2yB>&OBICDyJY%ux!>B+Ipo;yxUj(M(ncv^BS zaqicrC&w7*JN9^N?DXWAWblBtL`%NY#$BONHO-hax?>KW(a;*5s zU6Yby#V00CN{$uRT=o6rSaG`p-cODdzqNFwQy-(kj$J8(V`j?Wn3*y-W~K~|nJI%~ zX3F50nKC$LrVNgmDT8BX>h4^FcPI0XoR6IJ*7W4qe#q)=$ua-%1KN^vfvc}*OU@B` z-P@L&JFNO-TXIfu!sBhpxkl?9ZOJ*vAs4kJ=O!oY-IkoQoZr7KIhWb<<>|>e&Xg0U zC+9v_EIU0pCwlF^>f5W&mH0lLThT6@)6p)R)6p)R)6p)R)6p)R)6p)R)6p)R)6p)R z)6p)R)6pKCOVUoAW70o3x21n@ZcG2*+?M{qxh?&Jb6ffc=eG0@&TZ)*oZHerIJc!= za!yUZ>iPivp6dqmV+XDmb5HuW5nBY)?+xDR6M6f-!RW7ZSTOe)equ2F>Oam3roX+Q zK98m!)-L_?I@g2_{r02vbqV_O>Gib;`g!H_|LXIn;2rUFYGy>G}`axf>j;*s&$-*b;VZ2|Ko|>HmLdoa~sttQY)Q z^MX?DJOzE3cfF|QEM+-i?ZVELVCPD(b0yfh66{oReBk=D)DEVCTQE^IzEcFYNpmcK!=H|An3Z!qyQk*A0|YcjcuH z?AikC+5+s_0_@rX?AikC+5+s_0_@rX?An5I))v%fZ2@*|0d{Qxc5MNsJpayXBbL9c z3ryesY3o0woPQAOQRvIO(?zv5RhARhF6^2Z?3x(tni%Yw80?xD?3x%{u8A==U=0wt zOnpCZy$*e!53D|1uJ5_th+O9WrL8Y>?Gd}$g0%&^&I!BD3A@e-yUq!_&I!BD3A@e- zTSvHDA68D?m6tlOYsj!`$gpe3uxrS$Ysj!`$gpe3uxrRLa}(B(VdgljA;YdA!>%DK zXAN0>){tTD^Y6R{Zu!f)z|0LlZJocAGlym00ezWwx~TRb%5uWmh28sr-TQ#u`+(j1 zfZh9m-TQ#cy${wF*y}+qQ{T_qmqFj>1FH|0`#A0^A(y#-X^XX&FKdqpyV`=a1-qXG zyPpNSp9Q<01-qXGyPpNSp9Nb-xZDR+PTiH4I#`aU06eYn)ue*n46{YzV4rY`|@ zwFPSn)^7pUZvobC0oHE;)^7pUZvobC0k)2^J_E|BJB+;4f%OT2^$CIX34!$qf%OT2 z^$CIX34!$qf%OT2^$CIX34!$qf%OT2^$CIh-F;dte_0p!v;1~Sxqd|G%e>P?AQtoroNx&XNA7c2UZ_0{j&5ELoRdw($<&h zGlpGl!PuD>YyGVgRz z`Hq(5gtZInvkL383hT29>$3{$vkL383YR{s`sgB;sqg3c)1vS5fz^jg|6Bcmk;~k_ zwDo2B24h!Su(n|RkYW9hVf~O{{g7e(kYW9hVf~O{>j;f;9m>*EdU;|=TM4eR3#>*EdU;|>42`>0#~vM%sv`Qevx;{wo^ zd8dmiMxZPwtXjGOB*t)>h1-34*b%Cu5Y+YdM0$Uf@x|H>T>D%=iR0sW1&OZo$LiA;H z7FE1hSx#8HuyJazacZz}YOrx?uyJazacXcGr^eU--$mpy_5HjUI`n-$u=;QrbH|ts ze?{an_b+XInel+w)fTKR*w{nZ*hARZL)h3u*w{nZ*hARZL)bdPW&Eac>aM)hfsOHm zjq!wy@q~@>gpKipjq!wy@q~@>gpKj6>DOaCVPiaDV?1GFJYi!zVPiaD<~#bGTCZAr z`8SMLwJv47VCIbasj5RAOF45}{8!PJ(OFcn!(};P?ZU<^!^SMb#w^3eEW^eu!^SMb zWy~^b4*1FaM)hfsOHpjq!(#@rRA^hmG-vjq!(#@rRA^hmG-v zjq!(#@rRA^hmG-vjq!(BkNtPfQDFJYy2$3BP>1&gD`#z-+!W}`=q#!n5oI}H?ZW1! zfXz(-o0|eQHwA2N3fSBfaG9HeJqznAQ{T_ao56j2KCt?5nP-E&B%UpDnfsTvzRVmT z*wq%SE!cb`u=z${^Nqmf8-dL?0-J9HHs1(r9c9~*a_SBvFLhvZxxnUffz9Oto67|@ zmkVqz7uZ}bFngoq34z%&B~J)!E*F?RR`QC#=5m3}26C z%^u^@x(@_jzSOw%mnVXMxazoc(96NcJvT1>c8z{D{TuImFI|3C@OytBpN9TD_%~f9 zq>sh~@AT~n>A0!EAMZIKjh-ERz;BA(v-Dk&(-%m3x58m^qQ_?s88N9?JQ_>Y< zg0EO?Y8v-`@SB6CrmxHh9)A3^G|}Y>p1nW#%$eh{e4sRnGAZfXZBfrZDw=!8UA_cmh7`_ z+OQ@2%*XH9l6@DGcWlkRqi4U_EBo#)f4^7uogTVa@9evNYN_7YZ{YfG^v-@8Pdw5) z`_1gRPM_?z^y72-WWTX(FY1&1_C{RZC;LqvcTJznx4O}HZXVS-eDQq8y}^$Se>dH` zV(=|XjY;Rc8r*#1*mS^Y{c8Fv|LMJS!OF|j_{|q4rX%hTKKSY>Y08Gn*5r@%XiEp( z9DH>9%=G4*;Nv%&m*%bAzov7|JDu{ngM$a%-X%Y?ZSWxnch66(5qxn&V{Vxm*Di5< z&%Dd8f*-iPCHGi0xZg>=@}TRZ4E@@A=f@j@H(zY=d{33XV&OXO@$}+(-T6z^eR2!3SK`C%=7p-uX z$n)0-KKkaa`Njo{*L1diYO(y-^x$J(n4cc%8ag}V*{SpT!ACTGnEIX@eB>Te(`9YJ zeYc;KzI%Mw9oThz+O{>y_RLjd(~|cEue-vSbn8J&)!LEol>TSns6P3G9ipFsXH5S@ z=Wmw>^F6Hh^I*P{tA85I_tRx)FyGbFO9k`2z4370nk~M=IR^&weI7L=nD2Jx_k;PK zFZ^yW-}&;hm#kgO_kY63VA{o|2L#hzULO)nJ343AVA|LBs{Cfui*|QWuVC8aul}|~ zO-?%Bfk?&e{$Sr!Spl3b1?nS z`oRyeIvkw&*7<1O2CEqhGbm^taZ9e%LzFKU;VDZJ!DK zxzCDz-e*Yv@3ZB<;4|lc;k)2J;ydF1;=AL&<2&Vl^BMft-^lWu-`W9w+-7CVA}|6+ktIsux$;tt--cU*ftB>mSNjIY}=flY###K zx4`yAuzeA1Uj*BC!S-peeI0Dy2-`Qp_KmQ8DQq7L+xNos=Y0RLeKl-f4X<%$pS=AO zp<_Rf{1=b+$^6G(TW#d1yPsXWgRebz@qGUQOV#8%J>4h&;I6(kzU%znd9}vi-A1?O z4USr}Cg1#}<~(5X5;Y!nNK@{AM(~KIdgOrvg14N}HNUf1Ffq>8RR25d{^q+2lJe0b zW+(O6*yqF4ai7blChvdpv6GT^AMZatS)Ox#J2qL)4^|qJEWcwFY$3nrA5mZQn=kHH zD+Bl0VuNLB%>CE-OYn%w?uNTATa#0s9Ul#*oa^`M-%{uOkY!5r;hn)++ z&K+Rq4zP0v*trJm90Yc50y~$1oy)+^Wnkw%uyZ2Vxf1N$3U+P>PH(_7S6OkFf0#wmrhON7(iV+a6)t zBW!zw=}%~Pu>$Z?<3)U8_Em&Kyw%~LB-8*n7g-f-M7V*g|!Q77uGJUU0AztY1cX;FS%^jGCJk=j6UBU zbyp56ujyCcyz@}U;m93_!~fH9d#S&{fA-4X|3j?hmi&*adgXVjoTA+SlmmL@?XL~~ z(MG-U>(%%c`3*}|{c4rd6<%RpYySDr;4`Xxxrgl+ywRo`cuI-V@dqY#Ct723uy>y1>I`S9yci3cC}k9KSbzJ9zN?*8I{pgMa^V zYo1wO8!y>wsjt_<<+ZQ=qjx@SY_xG1yO;gCcOLg{yz7;B>zyZz30}2t?|kO?;Ek&9 z{MsqOW3Q|7AK{C$Q?ER(nzl_fBX7$RCS2=89zc-$ba=4V2^Mbwut7rS4QQwC3 zd*_X++`s65zmk9Wba20K_RjMj4Ssz2-g)?g!SkAX=da!$tgVI1qb=mxg0%%}3)U8_ zEx5F0-6`kv{(bVT^=IcOLG|xp`Vaf$5pUJMfusB6+10!folS@J z$;ZDI>^uuwC2I@0wqR|++N$Z)ZNX#fw&2oM`Tdt%eq$?js>WLNZ*P3ncAl%4GOGit z1D86see9N8wzVy*Hv7A(&7#v%@$2>Ws}A>62UZ9D^7%L?MedvwW{l(*Mt$z1KCC`m z>W`_`jlVlG_OMERqNOFjTID+C{_`d_=jSdB9{O@~KKIPv7e+PbL#v#_=p6e%bN-l&UmxRjUcA=@3?lE3kK-1G0pwB#dS3GQ)HOa9Jt!Iz)dlG~mL z{#liG{Vxv(uYO=l{&tn$yR@}%d9+olOWhW%Em&KywqR|+r7i1@-CtDy!Po2W?yR$V z<>z}udG5NlSKhtOf4iqwKCN5GA9=3I=ifPa@SDBz67_Gu^`%-FihWOQA=ehHEm&Ky zwqR|+rLFS&FS-22Rs4)bLe*x`d9La= zTI>CWI^0toSRM4sXXRQPa@XQu|C?N^KCC{hK3wV#J+Cnze{k%}m;CnOjd|c+As;ZL zG56ax_|@I2J@IOv7rW#4s?JPVEqM2X8}onk3x4*D#=K6IHy)kgH#O$Bs(kNo_m>)T z&#A%FK5op7W8yiNtPbV$TG)HS+JY?uY}sJT3|klY4~sSB``-<_vwAe;%ijr3txfr; zw}Ve#vMF!>R+O`3uca)Ka(=9T{zwl4c+&wTn{ zf>*43_;-6Tcy#Zc`O)Wtk9es%C*pfgh{B ztC^QCTf65wmo?^{F9|++cw_$i`N4m=xiP}Z8531S)@=dO4&d+`ne9B$Td0d^>uEri$ z)pb^Sw>i(OU+cO$wo29(a&5udg0%%}3)U7~+A6>QlFM&wWZ$N|RK2|{Rq@&tQ!jO3 zb>LFRwvXMC%eJ;m)n;F<+AKO}cWTO0>g`t@?x_x}4*KQuaSsBydl0byO|DfRRv%U$ zF7=P>-!1R)*Z7`G?$Nhfe)frwFR@Iw{EfSVPyKpzhS!b3<2LPJE7jLpY4%1J}h`dbuP(vKMuZf=N|d?dU;k^qDMZfI%|Xby!}e| z{K0O)Lx0gd&)z-wl)>HeRrNBLtX;~fUHJLB-I}~^7uGJUU0AztY1cX;FZq<}+?iio zQ!iVc(K&79Zh7a?@qGN=sF!lMl$ZNogWu|!*O?#p{C<1ayxiR2riO0$t@hxvm+F@9 zo)+AF#cuf@mH!_1T?qA>UT{A5zZEM>OOIeiyt?b#B`Jw+A2jMnk@}E_Xi>TP14?xwc?!!Plfp{Px}R&Gm1uf5rDyOkLE0)qzVL+dg(nF5B9*m5~k2>WO-i@-A{I#Px<@H|;`OnVl zlplONc!%G0%KP6FeA{2EvuSP#{(1Ms^7+>W-<=oB*VOyfCr?={&%ZF_8$GmGe&f90 zVG9<^Tb>)wxny-Hr`N*X6V?`N8DPr>TV~k0z_)hloCnqI9^BBmqYP{G{)FFOI&^rp zC3`J$uZ7ENU%szP$Mcl2d*rQMYR?mHxui?&dBTH^=u&&0@T4uO^Me5lR3r2V8DDypS)w!khx{PY<+EK^TSMHjvyM7edDp^~|wFPSn))uTSSX*#u ztNi{;F2AuM%Y4#ae%tSp_N5MWR|hV2Z2Q0;OYqvi`Y178q6{UggWPLj?+I%QezRT%*s|5+ z^)kcO1>WiEj}l``xb?P=l4H)7?*Aw`7QN)@j}l{4%2~44BKKOjy!N|u=O@SWGPaiO zu^=&?hdX^dKQW$%*L=4+*SH$b!~5JhKQW$%A3l73VmuGe>o-3+_Z)EVyu^4O`D=sb zCC2mc$mc#vjOQs&$=XG(U0A!Yc46(p+J&_Xmv*fq@{(7ZJU=ncq--)eYo9(VF)oGu z-q2AFm-5oz>APpnOpd{hyk}-|Z1&stW+umM`zdx38545tv}Zm_j1{S`I$v~ai>D>l>)@_U(-Z4;@PsOVIO}!rVZGWC>viz9mse+{RqJ)| zMoWE|Sg(V7T=rpNy$-&i>x{&D9px!m9pqjMdrw$fuw{TP8*G_j>jJOZFe9kb8?H1Xxfc4|w`L^PNGWH@UW?po;quxoR%}nMC(GD6VAuAMJsIBXlx0C)DD3x!j&it^mwuk( z4x5@>1AOZ0smZm$0WVZBef2fNI~Gh$t|i{L<_F0&#+Uc`Ai4Iat%b{@E#%sQwFPSn z))uTSxU^;6sn;drXLS4r$G$Zqxi)*wm>J16+d*wJ(%;XI=eB>(_T(Dxi0T_~?N`59 zY?Z7nDnERjh;-tiWG2Hq4?ra_KV?dx1N&NFNP=l z$CSi=F+985)Wm)<UkY?)!}0{^^WYGQA_Chs#fx##}yvXw7x zeJ}pqRjRWFR*rI(?6s7Cc>P+qy!J;APf7YS$k@8E@6?1p1H9&tsR@4uc#F%XCj1%T zi|?MA@MnNGdvt2Tp8@Xvz|@341KjtTsR@4uc$Gt{Yu64wXw|6+e+J4^vUZVc7uGJU zU0A!Yc46(prCsZYyyR|YO-bytQ%)J31?Nvp?90P`Z|Eq8OL^(ve$nw0l6%m%T{9uM zH+{l06Owz@Pt2N-+{<2Rjfu%U?wh;(C zrX+m;`d8;#>Km|N(3d+j0Jcij7IJOD+JdzOYYWyE zT-qwX|B}mZ?6R*_XKU8Ky$8QKHL+Jtebs^0flD3RK6Xnk+u9vHrY83E(Rr==)Wlvt z_fZE{2UZ9D^7$BBf!x>%*#9Qist>CVs}Gm@XP)w2(qFOUE}h0F{1v(Xn6t+x{1xGU zcAt>&SA_3Ab3(#j5#G0bLc(7W?ooZK_$$Jz+%qxZuL%F_qlpQBMfixdCMEn8DNo7j zAop6>d&1g+Edy-XV9N|!7x?+LCnbD4;fvOrl=S)BW8+ClU(j!CR-Kbu_ctrqYbn3i z!sWFOoIfGyPb*{VnE4YD{ic-87W zU;Js|rw^Ev@TY}O-FH&LpB6r4^GOMRTFO(hc9Clr)-J4FSi7)xVeP`DUF(RvZSk(g*T~gU2O(Bey(qT+(N9#IMICeJKxr zrpj?q_pux_XI#?vQd|5zt}R$wu(n`r!TsvC;L=w4{g+&RV=dLU zhfgNgURSjpd^M@BIci^8rT+O%?^XE_BEF#Hb1r-@8F%oLhVhAb2W%~U%J@XQ1N_`O;}h`? zaNC9x67df3PtKT-h+z*dM)fdVQs;d0k&*4 z{d$>U>jHnJvP*0T+_z$5Mqpz}&@oPAVK%PBYpF|lEzi(+9N97uj|1~OiN}E{Gx0bu zbs-)HrjEqp)by+8NjwhBGa()a=2;Ps1M>`xBP*G@8waFa%B)>jyRdd)p1E;A+C^U4 zwT{S3&VL%0h=HPPGCDBvV(Rnlsbd@&_fcNv7Wl8(W0Nsrk9HoHj2%04>2b-JvRBs~ zmy9(#YM&|}LOlj;m!DTU_1Lts3?*xevS|y}7OX8;Td=m^g>Cs9kQ*b0zOiH6$Cxti zZ>$-1jX|S4#->qDCSjRX-^ksBxYcTPK+@Jdxhp3MCG$v6U^vmaCjtk`GxPbj{av$|!^w^}IJF zdo9o0YvJ-*#!i#>i8{*IWeohYedGR&jn5hq%$RxNp23WzU*0*GG4|fu1vB=3VzXez z=afy6vL) z9{k>TKFZ-z&Uk=)GRPShO+GxB@zUDI1~ZO2@#J8}S4W;6%(&}?bAlOQwiYgr zwvcNJ))uTSSX;2R;L?_Lr~HgdpV%v&3FFmg>d%L9?APnx2IJeOeiS;4dylE&&AFDb zcl)7rd67SdwrnmPZBYho!PLFR zwvXMC%eKaN^|7kWqQf}$ihBE1hkL36t5d62@qEnZgWP;RFny-ER(zh^M}1g*xYTFO zYLzP@CsoO;n_YE7$XPeL;Sa&An~fP2%(_{pmxEb1yY#JK*3G^-Etqw)Lpnu!Vcl$O zuVB_j)?Yrp=aSW-oL&oiPgq;9Wq>UkY?)!}0<(s5YuzsEmK&}ZWnew?xs`%hSJ`Kk zC}+uD%QN>{xV)CNyW2O9Yh~=R2D@XGPYh;l_LS{|S+iZ@d%>*bwhj(vjd$oa!L0r6 zwnZ>&!f$UB%v$kQYX!4*^g_MNC2N;*Y8TcntX){Uuy$eX!lhm7h`eOh7$T9n&MefA(!p>le(v?Wom)*|*(bgJAY;FWf4a zecK=I9L(O_e*4DvT(UZp(`#Yx32O_s46tQ`Ei-IgVD=F2soQ1W{EZ((8Q4$%=!e1V z>#eX~l(S^7<(YdeTwcrG@ecLei86Na0oc8Me|!VBIXG-H#4Az6#?H31;u|sCt=8)-L7LF05TxyRdd)?ZVoHOS{$)dCBZ?cl}rVOEmtU|=JQMcoSKT_8ef*oY3}%1-XLV-Z z|JADPa4r4-$JMW8|H6EdC2NZ^XbaXBtSwkuu(sgRR{8yxTz+Hhckf#N_SgsCsA9^j zPOa{B9k|r7?PIs(vaPXSe^u3H(P1BdSiSwK!#&l3)j_{}KIU&kZvIBt|0dU}533KW z510D*>@9J4e9tB0H+a)eLyq6zroRZrZ*bUeg7F)i^B=+Z4en5Vx0DCJLB3TOzrnBn zH5k9aCEpCjH|)+a@jaKU4(0S(*n7g-f-M7V*)aCt4hi*tV;*UH$%2X&{1e&1 zdfD)OoiHKf_{5$%DHvbbVG{FQq^YB!H@LOdizy}d#VGggMRsZ@Im^2%7M(a z>ci^8Wu9CAv&e}bnXzw_tz_a>1|Au5;#Te$7EIhq_ltswTluf6f{9ys=eNPct-Mn2 zSBYCW;+~Kbw{rOd!Nex4`loo#C96{_Tm4$td&1g+Edy-XV9N|!7nm4|uh;DoH)I)z zCz6S4K!@jFvezQ_TDZKH*cqRvj9p@&c%Cq^Q9MtWm?@qoOe_`86DG!r=Lr*g#q)%T z$>Mp!#A@+8VPZEZKjkS|yU4W*YZulotX){Uuy*0nu63;G6m=)Y=lxxxY%)5;$RLOP z-YCCvxRetQLN0OS#KnxNGx0JXrH~Uxb4it}93A3ohSd95;%?U7CgjB9y!5?bZ7p0L zZ6VhdtSwkuu(n`r!KE$hPT7b{vJAv4SvKOBEHm*<)`hqy>qzXCb;p0({OToZi!x{n z))uTSSX;2R;L=w4{g+&RW5oOT?GXoL`%;Ixs{@xhwteiDT(&jhm28hgs#qu6sXE+K z9atUiSw0{0bt5-lH|&3tYt@Ij74-?DJ zcpfIkpYc3Q?7wqQasn`(M^3H)#`7?-!;I%CPs!Rvu3cEWuy$eX!rFzk3zv4SBl41o zF=w1f*<^Hx(Pmr<`@Nx~94_U=BQw@QPF%KQFygfxn-RzDn2q>u$8yAdJH{g(+_9gw z7A}vrYIUjGg0%%}3)U8_Ex5F0-6=nD@s5Fsmv?MT9KB;^;_Dqt6L;?zn|OT3-oy`j z_C(3rq72%CwFPSn))uTSxU^M%|0S2-81d$e3AvUybjFI*R~=X#xYV)jb8X3GTO(ec zF)cd8(KFWNKI*{g!0Mo1J|E91K<+sOu>Vc2RUcL#Rv#|)$(iGNUCHF_VZDy~ledTU zI+(mYtk=Qh?P0wRCT|bxbuf8*Sg(W0+rxStOx_;W>tJ%TuwF-bN>&HC*TUWt))s6T zV9N$uX4tyG-V$&Y;=YgkXFJSA%vxprag!rFzk z3u_nFE?nBRj>t|d_128x#zRM{x`W+eOP^1eYn&o zXQTVYC6hOj{bKG<-bnU~Ve&?@UksBslKoTlMc_Y~`hRF@c zelg`KSsmnF3wuvkTd-w-EgNi^Ve0~u!;rmon7p0txs%V+y?F8pvPVxjOZHmiUJIAk zlDkrW1{quAAjO{nCO0Ym3@|xM@n?X^W!kCoXMo9Zia!HP?o<33U~;13&j6Dv6@Lbp z+==)zP@a;ti(I>~c46(p+J&_XYZorlFE_H1CTw8M4*2ovio<2I{5oNER`=|q}1FM66`FzMh z=Xq_OONEaAO|DfRRv%U$F7?S7uD@c*y1?Yn#AS#uhp7@u!8!jgLPqOwN4#X<>5d<4+5dV;_H7 z_>3x_KmN2ZIr;IYg~`>AKP^n|Zv1H}Ps!Rvu3cEWuy$eX!rFzk3zv4SBl42T@s6J- zWs}h%M>>9?u-_Xx%HdK@K5)kmO6(He%+Vw&b#{k*^+~ zQgp~;kFP2BQ3qBBRtNp^`FI{5a?j&~{cm!u`mp-2`f#aV=A!pZ9CW^j^LMz9XOY1F zZ=F-a88pU3lxH(}1`TB^&!F+l8p~{)l;<=dN5^;v&uu~Oc`>l(#lW5y1AAT!?0GS; z=f%LD7Xz2)#dsDBa?fCbIiJW_8_!@u?ioz5XE4DFpTVU6@aLV$$hDt!mY@9(I`%)X z{SR#a1Ka<=_CGb9qW`h4Ltgf)wl(C7@}K)@?UXY3KZVQxseKOef2BY1AB4XDKG=UB z?7t88-v|5egZ=lx{`=ta-)Db|-2N7}zlH5@Vf$Oy{uVC#+p_=ptaC!k{>O1X_i>yL zJI;q4=fjTk;c}esoC0|{e{oEUd{NGAKW#ir8JxGm<-FCgJ@S8L-0oZtedn04b4=Jd zChQy&c8&=<$Aq0@!sQ&(c@1*sHL&v<*m(`?yask&1DErfa-9EJ=hBwreAm;skLzi$ z>uIp-X|U^QaJio5+8y$8ozS%-q zUCV`C%Y|LbgqUCV{bwOrQ^k-L5fyM73}eh9mM2)lj=m+Ob+dfI25gIunsebIYl zl&9Q}bB_l3qTH+fwEZ2*;65x|?!&rQh5TRHhjQ-{efLaZ_e^2;Okwv-VfRd7_e^2; zOyP3R)O|YS?$g2U)4}f3!S2(+?$g2LK3%zQ^;zd`m-|-whj1VLLtyz7WV4rBBqS`B6{?{hi>_-$|bkzf4Yn*{5d1nZjw>zf4Y zn*{5d1ed-^`okdC9|qPR2G$=2)*lAe9|kV{VM_my&pPM5^bgSwll$n03G0UmulPUk z`9#0;FV*J|`J(ha{xp9@%Aj8{T>2I3dx`vC@vGDq7kzzzVSRvMeSmB7{~O=q!q->7 zQ|_tXDXiZqtlufD-zi-BotA!>oPYhsF|ilPx!7%WpWf0B(|8B&W4r@wyaQ~!18lql zT*f;XTY}U}J4yV{Kq#ZD3<< zU}J4yV{PCv*2ee_Zv#&^KRcfiJXz{YpLWqd~&@4)%y7xjug7tTHZ)!*WqDdQc! z=om)IQ^rdgLx+4(#?pRT{2gU5P8KfXWQ`?6{;$Ld8e3Ys&zBraYaAuEjH85&qlAs4 zgpH$wjiZFiILb1vkn`)8pB>)`=h~kzGPsN@G=87^7{3o2zYiO~4;#M^m+|}N3P4`w zB`{VU`J&8O@o91Hl)-!yaG8(7n0@5`N<6+f9MCs+1Z?gI*xV7Yxg%h6N5JNefXy8N zm$@U%SAg7n1+e)FVDlBg<|}~BR{)p!3d;EX5YeDKcbA^H%|`t zF;5O`o*dXbIk0(h;Dz(#d|Lh=bHbp%D04%Za|XNSlY!0qBrlvZ3i-d1_r_dF=$oSn zHb)a|jwaX~O|UtdYWn{|ZYc8tp>JLw_>0Iv#C=BHGd7*DL*#mbXH1X%g)&dh7oGbK zyRU9E_iqw~g|cUlA_zE0S}=^SkK-JwyDn^2^a@l8=%5mOeJr5rLrqQ!QZr)e!W8PQTysxl%Ut#mU!e!o9{-K^f%fFi(%jod0H}CPH%ys-} z`B5p4d5qyQk1@FgJg1m3m1iY?RvuTzVB|gKKIR;T%{dI4a~L+~Fl^3Y*qp<#Ifvmg z=dgKhk(=ihHqR|=o?F;Fx3GC`;WE!HW7Kc{Gs@4HWX9#ej8z726UH%_1AmdZ z+$j%p0nRdjnLBvCz@j`;fY@r!e>4v{qhmgK*nIM^`Q%~q$-`wndFH(5 z{W{9e9Ot!zf|>h_UOSk%^9A+u?7rwTQz#E>3!E7QvlihwK8y0~o=-dPgYtMT4_uzh zL#(LhPO|3X*_WSnE(vQyoa4iNJVOWe3?0}rbYRcWfjvV9_6!}^Gj!nc3?0vHsp)^g zXT)$%)=W;C6m?-OR`{RgFUMb_N+SCv+7{as)Nh3>R9Xc zOghg;L&x*cV9!T`Js%DBd^ET`AB{D6zkwZ}>73VUiF4>!o0VDHpSK|1qvvvRAJ654 zJ(m;qTu#_?IpOkLPWB)?ABw#X+ZuZ%w#`L(7VW2e>_KwJt_OZ z&pKz5JuLf7&xGavo(T(kCTvaqe{&XX731dFubxB7Jw1mM_8d~!b4X#&A%)9xNZI4_ zpYp_&J+gfWdp-6o>=pWN^89P=B~e+_&7HC&7P+JQ1(*&ceD5EzkX4k z`A+PE=d*ZDG-dWYcep&yofrqtOJa}PG1X_CXU(3tV=&KN=boOu4tw@G?AhzEXRpJa zy$*Z!I$WN;&R)D{tb5)!I-d6pd)_z9UccuAdEPhj^1N?+1{|Xfdb4MCOv2u=V-(o^OJ0hUcE(v*CFt_;Pqo3O*j5pMvj)=c?dC;+zE^Z_lB?_nY%6cvkqFc+LyH zD4zdTp&LjBk%~Nql}h#{^#>&o{wG$a7Ed9r8RBe2P3L1z#i2 zPr(PtIq$RI?3JD4;EUqi2VW-V&iFW)KOf&G^XlUh)sb(%@`E)GKR#6E=f}6oy#4rG zImgG>%e4i3!(5BNN6T{=@ZI`n{k#Tzx;)1LUoX#hzz588AMg$HJP3ToJSPHQGS82| zC(Shwd|A!6kB=*P_<82|uz8*ZzHOd!fzPVvU*Lo1nh!p!=GDhXj(q#v2cJFHi11_Q zOc3Pww{s>4jNdzFg24F0b0!FkpFC%R!1&K|CJ2mQJ!gWz`2KMw2#l{FXG6gFOM6}e zzJ;FSfX|`lJK&4xxexd#dL9J6i=GpKPvb!^$36F4r@BwQUih}Lmh#$aBS+o+?Be;} z6_>8@wdXFL@2_&+BH!uhKKTcC^{w$;=l9O5H3siCx;1Z5<*r0$^Ou_QfXPeLc-SFL zx&Il#BcAG!2M!3{az@wu&SJsaHdkjEPhY&I|C{eFNXkc#n4Q#LW1kOG$9*oZ&ULEa z|KwvQCG9@me|)k$=lphTvYa2RG$vX8$A-U~tQYco{t~6U0vNbv7+40d}%DH~8{vG8%f74*<^~w&x)K@vrL4BT&_u;vDf1amydCr!H z=WjWAFP7i;_4;w2ygS%;2m9_|-yQ6`gMD|f?+*6e!M;1#cL)3KVBa0=yMuX#ygS%; z2m9_|-yQ6`gMD|(sk{0-6WDhL`|e=h9qhYagqTujGOW)Atj`9lj|W`l zSk~tRxxOf{dDmg{vBTzRht1y(o7WvS-#cs`cvznnxXk0Nj}3BtY~cTG?ryHtHv`sZ z1J;iS){h9*j|kR}2-c4X){h9*j|kR}2-YVG)+Y+qCkoal3f3nI)+Y+qCkoal3f3nI z)<+Bev^=!P_347m84K$J2I~U`>oW$Ixn%WWL#}TdY<_9jywkAxsA2O|!{)Ds&1(&t z?;6%e4%Vj*)@KjaXAjnA57uW7)@KjaXAjnA57yTU)&~s!qVr*LPyG^MeJo*pEMa{t zVSOxX^8aO?Rj$?N6E>G7Y%Wb$A5qxcn6N&jus)@*KB#b+GgF^f{us++cKHIQ9+ps>{us++cKHIQ91ZX7uXmXxXgiO%nov6d0_J*!e2^`$7&zMTz|$WVapgL_3^t|=Hl_?VrVKWw3^t|=Hl_?VrVKWw3^v9M zHU|`J4k*}|IM|#{urYM7F?6socW{~O$rwQ7#s51Z2iHm3({%sy<64%irf*cgA$jw~u^9aG_7lO@!0Gl%bHYWpYP6pVV46r#FU~@9S=47bp)N?Yx?1SK!4jbbS zo0|eQHwA2N3fSBfu(>H)x00b&HEvHMk;dGX3Z;tj(J7YcP-aEB*@K+0-G-drjDK+OdUD17&&$1 z%wm{2a%M419XYcYrjDK+OdUD17&&$1%wm}L#o4$uuAZ}J+L{Ljxp`n<-WO-%!n{Y% zvE}`GzAf*aGj`E2Pl$|PI_y3j>^>drJ{{~nT}`LHPY1hC2fI%PyH5wZ=Loy!2)pM9 zyXOeI=Loy!2)pM9yXOeI=Low83cCjiy9WxpX9~Ob3cJS&yT=NsR))xiVR|M9F1lG3%*5?G)7X{Ww z1=e>3)~5y52L{&12G++0*2f0c#|GBN2G++0*2f0cHv`sZ1J;iS){h9*j|kR}2-c4X z){h9*j|kR}2-YVG)+Y+qC#t4X%>_=c_P$|#qF{ZZV11%seWGA}qF{ZrV12Y;<}CQ7 z!}@f=%zf}bhxGx2^#OzR8H4p1gY{v9^=*Th(+%8f+1fps)Aidnm^s~f8wN9{o4i^u zbGrZN7tEY)oyK71bZ^a#vgsqo{q?DX_1S~<*@N}jgZ0^i_1S~<*@N}jgZ1@-^#Oy) zdyiittY0FmUm~nuBCKB`tY0FmUm~nuBCL-ktdAwEk0q>+Wldi9v4lC(;r4x^Y@GFQ z)*iu}0rA0Z!Q>m6y?d}epS62dIpJ^KJLIf^+*4-ze{BG*?IW{v3CC*q#05q;zCVAhDH+!)Ln(b2yQW{qgMbAnkT+WN#`)`$ij9<0wT z_t!@k)(05Y2N>1|7}f_E)(05Y2N>1|xF)arj>7ts!umPG`Z>e;Im7xn!}>YH`Z>e; zIoITMKWA8aafTFl)T(>tl~x-+P!f=k;F=yR11s_;@gD&imgJ%$oDXw*<51eEzk;tT|s( z|9)6=o_}G;_2K9Kte@kT4jWTYlUHZ%jI81dVAjcx>JrTQ`9C`av##DcKdxoHeWTgI ztixZ|7OXEi_t8fkHf{pu%(dZTL!b5ke^l`f$XBfP1@4{}%znXJ?ZNCLEH^ip{e^Yv zWnkX{Uw5uG1_U++1U3c)HU8&dOu(c3v%{) z@IQx*d4Y|2fsK)Y*)y__GG+(4u{W?$3Ul{l76v$c<5g$p^Ck?Qwtdggo%OVDg9DR>d@-Ltc?xMg)^@ z1YMEZ8_K*f=cMI4syWEZ8_K*f=cMI4szhGT4|h*qAcdm@?RyGT4|h z*qAcdm@?RyGT0b5*cdmMJzxCNVPoQ8_KxvChmE0wjiG~$xr2?lgN*@%jSYm^6JPS3 zxF>t!EB`H+J#oii?1}I8V#wJOfAsla_QaogA(%b!{a*<-#*q87zmH!!Y|JCfemyad zF#Gsd)yFpM@8g$_oPGai>x@6Zpt=rz0*BYHHC7INW9VSxI$`5FVdFYs<2qsEI$`5F zVdFYs<2qquRAFOOVPjNbV^m>dRAFOOVPjNbV^m>dRAFOgVPj@td`R$1hmEm?@kPP^ z95yBwHYOJ~h8M=C1;2FIm}1yiV;CPB{LhfFg|JcrNhST!}zx0e-0bt4;$lO<4Onra~K~v{L*1_6u{;#fbrSGFCE5b55II6 zpFRB2VSM)RONa5)qJY%zYX8A)R=V6t4luuH=j5*9dKH| z8n67P_tFJbdqn=`3lq~3_Xi(*^^`QFn(Ni>)1xgNbaU|0?K9JxbApfGY+jnTcK@2r zHScuF>kbYcbbFWl%(lUY99+eztr2{2Lt}248rLpye9yeguYw=Az9siqHMrkNz4D;z zqYVApdgsR*f;V5R^56b(l(}{I;`xqyqb_?qy?9=C{!+CvY<|Sz`OjMhA8=Kl{PyL2 zYx3p3*E^5;V96S9_N&&s-QL0DhBfC8|G7j>K6mM+eEM<0&mGev&tD_>=$pId8y75I z)7ko|#qwj7?>*1t*caxfhq{K&4taL!yngTzO&_Md=LR3S$JBILTX5g1FZ%BBVRvBH z@oC%EDBCkvjZI757rgEYW74e$MfrVq8@7+=c#jLSKKaP?$%pmphV|=)_3MW9>xT8~ zhV|=)_3MW9>xT8~hV|=)_3MW9>xT8~hV|=)_3MW9>sC$-g8IZJ!203C`r*U+;lujj z!}{UF`r*U+;lujj!}{UF`r*U+;lujj!}{UF`r*U+;lr&nXQrlaFZIZ|>)zJE$SK1Q zHtt)K%j*AViGCgWu=3BkPjmHe;{MzRR{zuPbK!LjS-EU^KJ7l}XjewxYq2YPpHHio z*Q(DwOMia-{CV&2{~v#`Z0$MNPI)G_Q`mM2^WKS_fo-R-?G(11!nRY`b_&~0VcRKe zJB9bVzEl4FElbvHU2{#RyxYCO2Vc}FU;cP-I=)k0tU5;t{Xg&4DR2Cb;4W)*%2UP! zFVm${e(wF?7jOJHT`@iQtqnd-E42p?e||yQd1mkr_Fd2+KYGUe4*lj!=O^#8{`&Ki z_rHDOyrkVHe>X2#o#i!BMuB9cQQeHwr%BqS@)H^@Dr8G&{YrZt#HKbJD?e zp0?ARbl`d+KlIW$>GA4JJ?``R3zg0$!Dn=yo4&Jo@Wi#|rq#C&{@R50w8nwK-@bEZ zI&$~m%ZANL*L^p5%-!v2)5C%XoZFuE9vZyckK5CZCk5}aO?#SrdhqxS+tZx$g3nmD zJ#Bnx@aCJerxUIUo;kQZ9bKJ!MLAbIq&f?wKwN;EsE)ldE~|M+2hIJn60JY5R?WhpgU~HrXP0_yKL{;=#dJU(uEp>=E4S-nO*y{=ut0 z*_PUl4nE=Ww)DcV;MP0Z($EWn54orCW=J$JsV!2_!G zjVpr(9^IBY-xPe&@V0csAA+Yn*p@~<6g=#ywzSK0pUCIE@rnLM)m(#na-W;02Xp^- z<^^N-m)#?lkn$Ya8qD`OeUD(;%hOi{(=Pg77EHV7ett0R;_)+rX&2|86imCg=ICJB z#kUR#rd^y^%>`;@tJ=lwLxSlCo_H^q_ITrq!L-wvcL&oyY&RvC{^8xWVETt4)!d(Z z(mz}`H<{p#EGy3pTV`fyxJKm5Y8!Sv@FycSGFA2MS_jHf(5C6xPW`~^r=0_8Q`Cq?U?KASe_+MY$GnoH%=jLGk z*Iny!{@1rPgq;6%=WfCLuUGFB%>R1xYQ2toGEO+YS_6a`KO8bNm~q8g2L?0V7&auB zamWq31~Wc+eTQJiE!%D%%y_2XcEOBulr#QOpK+1*VZ7x18AoZC@s;Ia-1Ww=xF_SW zz83~FPJ8&OPxz5ZWcTb_YDst)o2aP3fNfCNG-S zBilya{!5Q+Te$Gf9@(~Va<#u~Te$Yf9@(}qdWRm_wy^quN~hiyc3!$iwk@pCsYkXg zoblDhY}=prNJF*_ZntMcwr$>+8?$}F++7;8eZqtT8nb=Eq+=SheZuvpG-msR|NLoV zwof?b2D@av-+vwgzZKW@zSMW=1pknN*(Ub&&FSA6FyE!mLm)As7sknQV`+Xtd= z-^hLJGe4|+1MEv5IISVu$KEuuA=~%vI=Z^H-iHrfqA}Z7PuZq1+lOCt`X}#7S+<*?-n5qnoq;rhA`i&i{y{ zp4qX);U70;#~5?oYRZm1UVOGX$GJWxx%N*@*|ExB?`_JCVURnvLEkYC_i-%5{T(A= z*Rd1jaZL5f**&vkt!Mt&Gdl)5a9Ypo*zBl5tsVSiL$B-@a)Yi_&YAjHag!>KietrP zD*t51iW|StnjI?+e55+Bvp!b5>!#N1Sn^GgAh~%#^_~Gi7khOx+!~^GxK`AFiHHeQdwY1wFH4{;%xQ zGdmX;zgExe9O0#=p4qv>-zGI>=MaN=eG0@&TZ)*oZHerIJc#LaBfTg z;M|t}!MQE{gL7N@CFj)iSI)H`e4sjOzB>Dr@xXTHHs&MibN2PCetvv?&i>|#jd{yD zUpuuSUwm!oKR>D=zjkHtotHJ_jV=xT>7fmI;(5UvZrhNTJFTw2W<&0KZ18)_HRP2J z3hudh)j#hYd`{K3|EWH&|3B=#cbry5w*HHt2q-N%HBD;CS)z3J5*3vopa`Opnj|1e zK-vbgs3>AWM=^m}P*K#ufb{#Cv!Y_oIXmVYxb>~-r>2HG=YGz)zcc5K=eGawSf91m zTJ=0td#|otyWXkwtJ(K^hV~`-)$HP40dsHH`UcMqt$Xk+(>e^#EUmZj%+h)b&n&IC z@XXSB3(qXAxA4r;dJE4it+(*Z(s~QeXss{ttkgOW&rq%Z@a)#Q6VGm~JMrw+x)aZC ztvm7T*18kVZmm1b zx$)hAsUdg&AYf|9%AW*G4f*pI0aHW%`fb3}kgxp`Fg4_i%E3Q1tzGo+3)z-Z?&zsuU5wz{B^@7HZt_q6pzjk0SWsamA=?zMI(lKsmI zsuamj+pXJ0|3{WpDpK6mRNLL`4EG)c z4iBxen>9bGf!FS(7rWb=r!?@K54^g&?X$9h*RJr0?zU-N1FzBC&fV>D_xwe>jeqNA zz1;d3+ErcO&7S%;*zdleo84R^XxF)4H*4+AE@Nz5UbUMo?-9mK?yFsGi2G)Qv9#SC zUG1F%!x)=(X;*uHOc;Aj&+KYDxbIEq*A=IBwfb%yjJ~TKPGk>P@&kwR54Va7=gJ2y zlqVV~f3#D-Xjgx+7Z3OmKlm4K#1)_9Bc91q{FA?QN%aDsv3ED?@?K-FT}|s|_CaH> z-Tj@rS@CC$Jy-4OcC$&}H}=})eA(50s@%kLyZrvHc4yrtUc2AU?rP22Hu2hhHL9!q zrLc+DD8F%6D{+5oqutzByI9W5(7y4~E_VIN!TyW!U2N&a!OuIbyV%y7gZ~lVbhfE( zUnOJanTI-C>n%-uJ{zv=Y#ZNh;`7X1+S$t7zC`XD&z5wyH{HHO`ZaQ1XZzCab)@fV zhZEVumHfb={KKu{!nyK63+0JM${+32FWS{#?8O6q#1H<(8*#-a`G{xo6#wKeT~fWk zN4M^17gP`0{o1^vUE}^{8J*!cF1y>^SP>0o*N z8hh_*KZEvqHYV5TeyQ#e$bzW#+b6k7dd2O(Nt$%y_ zA{+c{-m$$+acgMIyFH$7XHR?_;+9?C&X)Zg^0|6RJ8Q9H(60K7c9vf|XqP#poegLh zwA<^Tb~dtc&`#}eB73-!A2^hMxK&&@S3YQ=Jkdz`qn-LiyZVd0c)*YN!M}JTuJ|M$ z@l2lLAMK<|su#Fp?e;c%Wm7+HZ`rB69e+tvuicbi+u7bdQ5Zae$&(WYLzRb$)PxYwI{?N;Qsv**8V>a~05!?w1eTAtUg_L{afv_+n8 zA3LM1eb^_@+n?L1tvx&}&-+>OZ5y*GdEWnb**12~(Rn`Z{PWw`l+*KkKBMQhv0wg@ z=kqKZ*~Wfbo#*pkFrba)U6<$Q-4E8rx~$3b^G@w>B73-!A2^hMxK&&@S3YQ=Jkdz` zqn-LiyZVd0c)*YN!M}JTuJ|M$@l2lLAMK<|su#HNxB0dulk59_`4{>2-o3e=lM!#^ z+YXQ9damxeKi_tIHrI2wYE`~n{${S{Hg|r$jr}s$bH3d2?SaZcyAyZFw|eIAID+z@3@U|9p{^rkJDn4@^l()QvOc6 zP3jlz>M!=<0YBmg|Kg3f;*)&DGkJ=Cr(M(~)eEe7hmG{*TIr5YjR#_BoREXY54mYv zk+a4debG3ikIDGlq;ZSA#xs62&hfADPh8Cl^3i-DPt7Cp*ZiVins;cbcC?l~V?cfw z8}iSXQC!B7@?nfAPsX0|XH2SJw5z|^iwFFOAN-3q;)+l55zpi){>fjuqAU})^`De^1E@MggFvgT8V^aAuCe<(6)nDwz1AfF0{>2+{ z#V7fQXYv&Pj7jN|>IGJviH+(Ru2r3bPt`xfQe8w2s+Y)3brd@tH z#-8$LOsZeBtH0Qb2mFX1{EIi@icj(p&*Ulo$zQspdV!O5l`{SP&b9ix9-sPqpIBN4 zAP21vkek*G$XV+N^hN6o^ik^%v};`gd#zXCN9!2)*ZKx=lXaCct%s1O)=B82)=%hH zvaS-_(OUM50r_EU$UkF7aT!a>hcTu+8I#JNF{yshuKr>#9`GZ6@GstoD?Z6bJd>yR zXG}_$R4=gBRj|?D?_8_D>+z|-_lc!-0CLd!0J&-1fSk3SKwq@ZKp&I!hfP|Sz+USW z_|ZBB{ZirUs{j95y~FB%Ix07_4pg1 z?D!RC@4CH?_cEzT8{JmCo z)5aoe_*^~yjw^fXxFY-M<9hs!P}XseB0INIecxVEsmR(js_*UBK2T`YyVm!9E?-t? zC%S!r_|F+#XdjKP@8d4-P-xe?_YveXuWF$cmeluozVumv?Qvp#pa1gL3at3F`uvSh zR_nzAo9EtfpsCu?TK0?q`C)9xKVwF58B5BCF{V5jlgghlseaL}{$ej4@FRZkFW!hN zKFLQslc)G6f9aCy1@5tIcWbb^uJ7X=r|fQRuB@Bo+F3{KZu?zdH;d2b4&B`b-&!|I ztUG({Zf|GmX33#f_1$gt=DJyOyY7X)R`tEQS#rMQvc7iQPj$2O<*5mMZM-|Xj6ODM z+1Gw(Q_r_gdAE<9ZS}nUMc4MRxufcNKWEPBV;>$-&-?$iZyy_ad_5m`(awF`ZvoWv z`Aqn@w_SBvJ)h@8PxZEIudClip5mYUrAw;Uzyof|Z2xsH z+wgO}>{qAXlv(;&FMIgcdfB(KH)V=m>t!EpS3i5iw>M?3zPFcsvQzzRrB>@Qr(f2~ zPH0>|+h_2)Ow}WM*&ZF-JMJUaWsWZFW!Dzf&%Sl?y3EWfy)5sb`q_)lTbEh&a8LVv zM*Zya3)f{nS=!SsJSnvI8r0LeTpaAD@7&XJ)(1ahxAd^n9t!@ST;0Pye>ub*yr75O z^hwC4+wdN?*N^U6m*<5&d)R>O8uP8#D5A?(sKf;L7v4HSflZ^87i+{dQG({@d4Zzj<2TFWS{# z?8O6q#1H<(8*#-a`G{xo6#wKeT~fWk4R$H8;alqazF$(^J?mcxoDBcDpPlqt;A+F0 z{p^$v0*9Aw>}QR?4cs<9yPv&M#qBwF+MRJ&KkMJHf!FT1mi_F`P7S)+qqR=R!r zX!qN-yIZ$0p?$w;yW6AlgZ<(TyW83`f}c5G_q7(Q8~CyDR#{(LdRqfOX2zY@*Y{S=uZ+{n}cYqGkE^;!Vx6XMR&RbIXUVY~rT@U;b#GJyNTg zw?A=nGkbkqp11EftCN>M|-D5^y4&& z{+)I)uG2K;x-k&*cVi>=i+1%Fd+~rD@q>TyMqKepKH`}?#lIUHQI}LNu;z7& z-Tm1#mf%NY4Bj;M;8SA~o;6nCUt<_uG`7)8V;&tf7iiZU!CrF*Kblkc*IXm6<{ee9AvOD=z#iA9PWk=%xJ8QT?J_{l#89;79!6U%U}l ze3FlNCQtE?j?#sGU6<)%-`(7hd$M)7yNm5`YeVjJ_STv%*5=NJ+yiZ&v%6UP`x+w8`tP!?|~%cp%X3)Yi%_aNmPCp6_|7jqU2rR$|`WvZ{?;TGqtt^6tboc8vQCbmm>>{5Dqa^U%KN z{nmDqJIf3Eo33wdXEkx(K07~G%xP`gcgywuYZbJ%nS1B@xM%0Iwhkk6eLhEhx~ttg z(Ov8GdUf-zcK^&=pZ_`8UG4pOxn8fj8+Wzu7UX)p)D91_hadTYH~EK8#f4|(1OLhs zU6en1sb93Kzu1ch{D>d?i#OtmPx2AZcC?!x3hifB?r8hI5$rP$b+ESI1wXef?_jH{H}yK^AKJlo$ZP6# zys}dVd$4m;uj6UeI@nIY-F(UDe(vT`M)!I5yvykR@8(@b&js4`yue=1 z5&Y=+f`2`Ch^yxj`RF-Co_c<{@s`nZjeaH1yV&k{i1v=3=*RIE{X0HmT*q_F$MGNY zbh^a+onEnDw5z|^iwFFOAN-3q;)+l55zpi){+(V?msBrs@{G&qUJ56=$HJBFy>O^| zGTiE34d=RtqlND6Xry~S+UZ$9yPgr)>)C-HJyY~r&h9(R)cMMan0<)`IYRJ zUk6$K+?v@|vnttbTLxLT<3syjZyaQWX9fGeoifO_TpIi=FCJv4tPTEe*kh2rw;{yc zFMp7&xHsg}f9F9~@L0%m(60k+)#i}@2VV`erCVxd>DS?3478V@ubDk-WMxzP>Psq{ z?8m)c+2rT3hE+`d>kp}7io5=(Dy|4mbyZCH&%3Eg>=*6oFZSXAKjH`f z;*GfClYGQ8d5VAXmoBMZ;94&aw^rNbcLqymt3DcGnKf@!CE3^)P#U zbZCG0v0?V&;laMr)x&J|!r*7s@x!dylHh;SxM6nOIU(+$dk(WsmxO!{>fo-uD&#q~ z@i6PVHst?P&M<4aF2`$Ey3;V5e{+u4PVI0ad$^JxIFx_5Ra`h%K4_sl(Mb8Do%%() z`is4Iz>oOBzj!0A_#_|kOrGK&?W9Ypm&2K4-esh(n|B%M?&e)aAG~V32%V-?Bd6!A%T}I;;dyQxOXq@9;FQlW6a_ihdl2(ZAz1#&w*>e4G|BPp47L-)R^7MZ5Zoy?DTn_`$z;Bd+))AMs3{ z;@@c(bxHLCYu=?89;7w=Xbixc#s++9%)qn868vk7p^L^II%-U!qsA)j8pGIYY~x2` z9{-vP#MK-jAI%-|)SM!J%{BU!%)!_WKeC56`GHUQhiAowf8~QN$`iemKRT*kw5z|^ ziwFFOAN-3q;)+l55zpi){?SpoWOJIvc~@n0)2MH~%bP~sx4hXjjt6U!7stu6p?Puq zv_3j7j;p8sk{8F@1#9x+IQ;PDyf{8-*Sy1C^A10nclg)5Bd+Eh`Doser{*2`Yu?c> z&AVeB&W-IyoR}N!Z?xR#XOAkm(f@awo5Z+>Ue_e%vwmrlnCGWQHHrDJoYN%si+0UB z>^1N3qj`sa%{$_1-jR>y9eHZrk-zSTsa{~sJNhn7;Y3=)mBs)ZYHYx*#tfWmETM(Q z7#eBpp`FGg?Ha4tYYgK@V;lb(^TgF$ARo;U^3>cRf6X=erMX7m)ea}Jhb#GkL-~hW z#f5X_gBHpYjg&vysb93Kzu1ch{D>d?i#OtmPx2AZcowKj(TRU@5uc21jcjxSup>;APU+-^~M(mtjQcyQD_AmR}nxl5k z-cqez=DGa+ZPMzUvw64F%M7|=h`s&H&RO?^BbobihS*g**37wBOTXkQHyN>FuvvInc_!tLgnT*>Rwq&@spRKX1u?_Q%*9A9u$(``MjKb9_Eu zY}nT(+>qn*tTlgM`}lzzpZ`e%_q8*(CBW z@^ji-H8S#lXq_4v#r=*6oFZSXAKjH`f;*GfC zlYGQ8d5VAXmoBMZ;BS|WunxZm?Y=v9gw3g3({nQQpb=K5PEF6%8M}ygPCJcHw0ru%VfO3! zIbOTJ-Z9ihKb_;X>(qLvHQ8Yo@Bf-B_qUb3ckyu>ciZ0%oVbh6XX}TyMqKepKH`}?#Xs6fmsBr@Etz*Fecik>>F(y8X*{@jXBsDN-kHXa zn|G#h<>sAfyg7|b|HpX?F$9$X?F;Aya%-?Aj`$fC@i@kWjkNCmAcq6X(Bp>lip5otW z7j;SX0&Cu-7#^fG{Adioo5luwYRtg1#uEH%jG?2(9(rj^qNBzt?Ha?_Yi#33V;=vS z3&hnNAs@{h^3g*oz1J zh#&lmH{yy<@)6JEDgMz>y0~XwTvu_=dQ&~)Y5-H6<7xv_{o`r|Q(fe02~)k~Y7A2y zP$=OOiSuaOX^HZ>P$=OOiSv_xUS-!^|9U60MXvn z2GNhJ8KQqzOT@UY#)$d2+9T%aYLb}0t5ssZXjgx+7Z3OmKlm4K#1)_9Bc91q{FA?Q zN%aD&&P*{nseCv;Rzg^sGV&`UKKI%<53b(jUu#9`GZ6@GstoD?Z6b zJd>yR=e>_~N%aD++NYWAzb5oonD=+B`Zu$&Hw1oO>e|eXTOW8Us^82`+!*-G|2oea zJQ{eu^1(cN;pM=8?ep@i@bjR{4u|B~?c25VI`+-YvkMxv^g5pMx|`44Li=VnXCB2>_zkzCtrWlOK)<5%a}%h$SVosQkk z$hFsQY3X(Rur$|x+tAYMIAcMs?R-~DucO-GNA~b0KkzC4@T|D-uYAx&d7_u{M@RLG zcJ&u~@qi!kgMaZxT=7Xh;+Z_fKRQYmwEOhX7B;_ep6~CRku7XVZl32Me?SYnre&Vz z=Zy9(?D~#*p0~L>w6Mb6^E{uQzueq@8@~4>)wMOIIFq6IzP|rbxPOf zcF!4kUN7x)bMJsG_qJyC*Y)9XImRI^LZY7d7f?8vYF4n`&oIG-?o|8Ys1n!>(RcM*Guj2Aba?cA9$00_*7hY zRzC2rJkdq@qnG+cyZVd0c)*YN!M}JTuJ|M$@l2lLAHAeYsu%dTqgz|eZ^M2+VdmY5 z^IKcq_d&;AlUkeo8g#sLzt*tMke@ws7<~N zcrL`<`!4lxJ+Rk45d3I= z2>!Kigt*#ILO$AOLY~@x!n;@POQB!MewEnnc!>6npXkT&7X3RuV_e5`%*XK`^K`nz z{GDF0U$m>g*oz1Jh#&lmH{yy<@)6JEDgK>aQI}LNaI!}wqrDJtqCFCDrM(kys67>M ztGyO*u00rNp}iSsq&*vGr@b7sYmW!^+WUbY?FqrZ_KFZ!dq~JfdrQbudrr_!dr|0D zvPUJh!-?$SN`Bx_{^3?};avHkh4Mrr<&Spi7wzgV_Tm9Q;s^iYjkw~Ie8e+(ihs0| zE~#GWUTcTreS4ez*zrE#_FY@D@7lEQnrn5haC^2b*|Tlhvz_|KCfTQL+NV8XOCMW0 zvxyy&+bRoQIJCZ%?b(w3-v2c2w>9>%y;|3^?zgtgUVoO^ihb+Z+G|>7Pij$MAFZut z15arA4}MbrTsvy-#`fg0R{q*+rZl#_k8kC#{rQo`_U<9AvPv%u1 zx%KJ3cE%h1?f0weW*3g^Yd?S9-@2@-o6Ww}#}2Bxr(JVF-E7ANeXL6RJ?$d*TS%>I z_pyCP?r8@cT{rvYJ-w~f(mk!ylz+?(pGRj4Z1UrEyw8uGF0cz8tmA$5|G24Rlj`vw>Mxm`(RwtV?yt&=|)o3gDzJ|xwKR3dz%&p=3^3VG9 z!$rRr$%boFEI-%?UpQoQk^F$gPim9;yn5ARMdA%C{!>4rGEWzYlSk@4T_mpV8U9p} zI9yTkWRbXSd)5<0;(Yze$BU#znh!q32|mRYKE)wE#VtO?IX)l(UOlroOm*%G5`fXPNr$@-Gu7u3u&1D$NI<${C;P3qI9He5&vG z6esu;SLCmposMN14{5(>*LX;6-1y1JKDD7;_Nk4VUm3+pZD<#VZvJM(8(93OHf~O3 z#EF}08FA(2U`8CextS5SZq8=Jxtn(xX_4mB^s(NVCdGyJ^;vbYCwJ?Ud9O{OExNi+ zcF>wWnMFSp*jIn8lil2@Z)RWjjq}s@)ydY}*f%rkz5=`DF@LX!dAfU4#A#n>SHHlz zPl9z1+}1{YclX0+4^Hj>nV;0g-NQ4kt>;E%#1@(!>)qkeWp}x}J$b93L)Iu56Lg`p_YyK5y zM!7TJ+&9aAnlqy+&KmOPo&IUg8mc&>#-AW7dN7Ju+)V$@kasTmtNq@2}%I2KZ0DzmDe~kWcdcbtd`#I-Z|Ezmo5- zV>@dvvS&?3epsu~_uZ`FC@yO|`W~D$ALYqfkiH*hjY$2XUH!#gJm5$C;9tBESA3F> zcqUKr&l-`wi>F@|>#@06c++|>d}fQaY z;`<}_-LBi$_ow*&DE;n_@8h&zwBkF>@Ll%5;dh#G-?h^#?(cPa#eKi-`^UH+*nJln z_X)f2CFA~K_Z?;2SM0v8jQfo%zGn~L^*h}oKkj?X$ea5fGxF)a$BaC??=d6)>G$mX zyo=r0V_d%>#Tnz`jd3DAIb&QrbH=#%=Ztab!u-;H0QAyt z+@P0!`v$%An>gsD-^xKR{e})_x$C!eIOAQvxx<<8`Yj&Lgin5>r%1ougS~#!2S56) zAN=b#fQYN#1|lE*W)OMmw}i-FzcEC=^xH%9SMBg1d-#zbc$0tlR9tvgKJc$R(M9>A zm-oOBzj!0A_#_|kOrGMO{G|*1(tZH?tKUX}2mNLW{OGq-;7z}=0-yTr z6?oQfvcSK7s|CIE8!qUT{I*NQZvngCP)0BDiC*Fvy~ICyNtgepy?okp_#f>RWdELQ z(mjpoe#n2te$I4HX}TXZ-OKtf+Ls&mJhPWids*4br+upbC;Ob)%a`n@jr+aX%coe5 zThsp1|E~S&?B$bBury^apD=s*lKrBV>=%vS9k7>A-#GjyziWtR*Z)W7)w}yi#qV{x z-`jQb`cLzFofW?~*U0PjXZXE2*5C9S0er)y^XJ)Lq;u)n&!h9|**z3G~{OBBh{Of#v;_BRf^3i$zn-xQbiH|4|noAP9xP5HC_rhd_`{$ej4@RR&5K;(_M z;*)&DGkJ=C_7_PP^s4w~uqo>Uf0l0sPukV!cqwkmTukV_PtM8r3N8dq{r@oISe|_>NoB>Rh!bLakT&wgZok?1J?wSP z9)5KG9{zPMA8~bFANlAUKl0T1e&nz70O^;`17v@W+S#`wd-n6l5Bq%NpZ!0I%f2Ax zzq!EQ%N4&()7byL{3rQsn)n-D{QaV{clf(TXY%m(j?U`g?;xGw z!{0|b+lRlKbmk9#Pw6Zm{?5`FLHzxtvx8{YnL^m>tRej93?lsNY$D?7%p&s9Sw`fk zGmgkVITOi}Gm&CD`&DGm{t)?L|AYLqpG0xlucCa|f1*6um!kaHucCg@uKr>#9`GZ6 z@GstoD?Z6bJd>yRXTOSc;qS_1e#PI>g9rWg5d7#jiQrAYRRo{<4I_BgZyUkCe)9-j z^jk>irQb-RUB8`#y?#>(Kl-gD{OdQEh^z5WKKjij^3-oRp;z+TPnP`lQ*4I^*~5?g zz?=NTr{co1@_~Qli7v_?z0@z-)nDwz1AfF0{>2+{#V7fQXYv&P=#~8TQ~XU>`m1$C zc+h$y{Ae8#-n2dmpZYyhc-DF*{A-;PU9|p*URoEWUF)UTYaJCoT3^M#)?JC4toO#> zZzWHy-;#f_-uu7ucVKy+zRw!7^`-T)yib4ZDzkeR*UR!g{rDAT@19sM%lq{Ak2ZUM zSv}5qD0=)Lv&AdxWqF@Iu&vqdYwKlspMKZ3MRvuedRgA5-?XvF8b0U0UoLv-+qdzvg~h{IvR6`c=!Fu`}=V`dQvbtDX1M zvgiG^{P12|{@I_Pxa?a{KI~^up6qi_{_KBHzi3x~u@?{c5kL4BZ^RX!#9`GZ6 z@GstoD?Z6bJd>yRcjK*0y3nsguh{N*i1v=3=!f@}^6&VJaUIW_l#ku zyIJvPjTz5n?do>3N#8g2=cwd-+0}lk+=TI8w*3CCc4yrt%!{($&hBc>+BRXnlzla- ztNo?0i9a78zj0S9Ij9Nqt8DJ8T`Xs2Xy15g7rXxCVE@JVF1GaI;OCvzU2N;k!T*SF zI@{Fy!+9XjJk;4*Z)xK5*>GiN+xT`9pJ(pU&Q|tm6QBRHC7tcfubMEw%0|xXY+ruU zg!xsbc6g9I{KyZy$v=E5E<7tA_*b6jqWsZI{i0p{#a=w%NBrPlyb)J?l8<;MPw`Lw z(#7?wsAKK+HhX1Le?PfpC-=Lkmo)YFnJK@vv(;BL_4l90-)?7D-r&!@DO$g&o%Ok^ zslQ)!Ik%nt_-IpqA6qrHosE0FslUIi$Zu!Qf8EsI_a6GNt!=25=kJHL*R-{vE%JQ( z*col@!#;W5{@hM&?crg0-p`V6+n7zs^Zvifwy|rD&hz)f`RBK>DW~W8d`8c0W52lf z_}sV4Mz*ovR_FQr7Yt})dDrFn`{57P#=5M@^Y=rwJ07CF|Nq4MW`sD9C|{$ej4@FRZkFW!hNKFLQslc)ISekfhgE16$K(h(k{FV8RO z&hty-f#;XT3C}N$AD&+tS3IXQ-gtg#9MZ1wiM_@xel(u(uW?RXjeqjdydY1_7oNYG zNAxS1U$Gq?WDh^`18?#VpNb35$_M_HC%Pzq^iscQSAVe=5BL#3_!n=)6`$lIp2<`E zqnC7{U&;QBqM1kbv8`Pj`f=N$xR15$-O!Kc)As3O`ThO5H$}5r_OZK%HuU5F)9-p) z>G+0zUL1B`Z+mNALqA`Jo!;9HUfR&lqmzd8wmz#G`uX+L&b@8(hS1*V>0UPdsbD|k zyk0i&{orShLwZ^E=iq<+uDz^H%|?EHX@3QJ)qTFF9n-Oq&vVh;J?;2jjr{!TvbLwK zE@nyoO?ZULbvHP3RKE+%wpWwdj z=M`e_+6tDhInv{y=bc+HuftrA`^`SJV9CZ=9v6SJu;8wlGd%un=g9?+kDluBUS%T+ z=B+CBxc&sUo2gml0?jPVW_V1p) zhrbp-XKd~l?4AEh?&<9@aW~KE;W7EV^IJEM$@AgkyLwFiP5$WOG5u0|_vP1ndvY7F z{`~`<%x?uV?UiHTR97J)es017|)S?e}^55s&e6@w|tEz4L$7v_Rjx3ch&cpxYa(W=P~)z9278lp7u#y-%kEx9;@r~q+e>M zzp{r1`GFt#hd0GVFXaQz$`ifFpSgox>KF4){iR(zU@v~~Bi`^2pUf}fif8f>|KurM zw$%&m(2+i-7<<~KBUn0ur6X86g8lQ(=?IpNVCe{!j^4gpN43L`?BNY89ld?Ij$r8s zmX2WQ2$qgu=?IpNVCe{!j$r8smX2WQ2$qgu>FDjtbyPb#${roT($U+O>j;*PVCe{! zj$ohvp@(?g>DRk`1NQxWWwdXHhvK4u;b+~9gMB-^-8yBI$LKYt_ehW7`PGj`c#K}7 zmmKJExKADs?44e}UOgq5jBQ8?`y~qc9cqUKU(M$P<`{V&WPv#x{ z)qI2phx4%)Klp(++VL+wi7TGTXG}T&%(TJ#c`Ye<*6RSL+dL~ z^*~ByygfWmDp}&&(W~WyCwq)ugLgjJ+fZjN7KuWnlcreA8Ozp{r1 z`GFt#hd0GVFXaQzKF5l{xUadhX>75@q-_DqaFX^leprUeBhtCNuJVW zTfNW@9qD6=v8Np#@B@~PVCe{!j$r8smX2WQ2$qiCzFbGO!;kFY4U8Z7^!DXCf~6x^ zI)bGmSUQ5GBUn0ur6X86f~6x^I)bGmSUQ5Gqqi^DQSIm`dvpX#M{i%QBUn0ur6X86 zg2}&S$#wl01N;Z}*E;O_>BolC{vXzDPN{iL(OE}zEWrM=XU-|Q?4r&dPd@wHqIO^P z@VH(7^NL>F-#mWd?emIu8n?g4r_WqbH0Abj9@lt%MN!qq<`v-o%P!{^y;kWIk8huN ze$mjE&+#@-&OhJv@iLET@3zkxkFmeH>0iA)etzwn^%(z8?){j@#Qo`S&w5Ngb$@)> zWAZ$r^_w1(|M~;p@jmHSpULlfoHzJv-%f7VEk7&Tzw_$y=%;7D<V4{(bg_yOZzyb)J?l8<;MPw`Lw=z{-d4UX`7 zfj_@&W^8}0;p}LC_%U;$pL;jWjs9CdcVvv){`Pq>pYINtAM-pmGe73P?(O+eFWRLS z_UJ`l@Pl4p{G%6`xab8YAM^r~CwhU&UwY9m>2<(4(_{Ojdefr)OY5gbKgZ3T68$$k zY;ufSZ_%Wv*PtyEqh9yUo*4ByXUN2;7wzZ;pV({M;z#2d|I&-N(u;hg7kNrA@|Rvc zYxjmxO?1O6!oe;(xP4~?zX7c1Fu=s zi+1USz4XG5^uoXNBCh5a`DlKTr{)*=OE3B*y$)a2Gq#uR(j)5i#f{ygpA|=Ri~c*0 z>Kf-)hoibgy(T=}IqLP|^v+SQYxnIO^`c#RVK2S#BfapCUT{cU^a7I)dV$GPdXc~G zdv3pC)T`0?RbqS9oE@V5dGo49-9Ni+$2cAie6(8BYvkJMF`wqcYs5U){Iy2R|CJYO z#D39^UgUz3_kRsqVdlyHA3f)c>PU`ffk$ z*FyO@;EA6K<^R+xekfGjwbv6?uYo% z{Sg0}U&Ph?A|K5!@|0fWFTLFJq>$$qvBorAU8s52x6W1Gp7vp{Toe6N9(#TC|I}$~ zW8CKl-Wc;a;)0uEp2tjB7xRDP>UF+f+`DL3f3X)2_|g2rzvdTlbw4B@-4DrAdXc~M zqFY7vG<)D^}6-Kv!h-&Jik2VQ}2v3W1dwq%VPdlE?O4* zMZ4w~_L^V#(fq={<`;1_zsN^=k*D+`f9bWh?lT3dH*yERULd{BYWZ;i_UQFN(YFPf zr*{ney+HoI{<(6DyY;xLF`o|gt4F4kskMO^VoKH`}?#XtE=FBiw%qo|X8t?X+^ zuxd+T<^)*vBv|z%SoI`W^(0vJBv|z%SoI`W^(0vJBv|#N+Tlm`@CH^r306G`Ry_$; zJqcDl306G`Ry_$;JqcDl306G`Ry_$;JqcDl306G`Ry_$;J*jr|l|A}`RZoIdPl8oX zf>lp~RZoIdPl8oXf>lp~RZoIdPl8oXf>lp~RZoIdPl8oXf>lqdU3#gWq+RtSSoI`W z^(0vJBv|z%SoI`W^(0vJBv|z%SoI`W^(0vJBv|z%SoI`W^(0vJq}rvI>PgyFPl8oX zf>lp~RZoIdPl8oXf>lp~RZoIdPl8oXf>lp~RZoIdPl8oXf>lp~RZps2da0hIUG*eb z^(0vJBv|z%SoI`W^(0vJBv|z%SoI`W^(0vJBv|z%SoI`W^(0vJBv|#N+NGE3N!nFU zf>lp~RZoIdPl8oXf>lp~RZoIdPl8oXf>lp~RZoIdPl8oXf>lp~RZoIdPpVydsh*@= z^(0vJBv|z%SoI`W^(0vJBv|z%SoI`W^(0vJBv|z%SoI`W^(0vJBv|z%SoNgZrI+eS z+Eq`2RZoIdPl8oXf>lp~RZoIdPl8oXf>lp~RZoIdPl8oXf>lp~RZoIdPl8oXs$F`i zo}^v%Bv|z%SoI`W^(0vJBv|z%SoI`W^(0vJBv|z%SoI`W^(0vJBv|z%SoI`W^`zRR zm+DE{RZoIdPl8oXf>lp~RZoIdPl8oXf>lp~RZoIdPl8oXf>lp~RZoIdPl8oXf>lqd zU3#gWq+RtSSoI`W^(0vJBv|z%SoI`W^(0vJBv|z%SoI`W^(0vJBv|z%SoI`W^(0vJ zq}rvI>PgyFPl8oXf>lp~RZoIdPl8oXf>lpa0}HcmuX>U?QaH6wG3((UAAG5=OIbI* z{+dfXWvSw~M^ZP`AEa^YegR zj(eI)bGmSUQ5GBUn0u zr6X86f~BL{EB^NRfAzOd#k(pup0&2XeAn6nSZfQ6d95vgwYC7(+Jf5oTa|0Iwje)x z_o1}~+O@U-*4hGow6*}&+5(t06TMp$X8fnPVvXoo|2{%G!jE(WOGmJD1WQM?Yt2DA z(*EDIMx-@Zbk`az`f3dptTkA$)?mR}g9U317C%~p1#1l!tTkA*bDxww@1($5g9U31 z7OXW`u-0I~T7xAAt-*q|28)f>V8L301#1l!tTkA$)?mR}g9U317XMm<1#1l!n}78? z{Zubu#zTswBkj@=EFHnp5iA|S(h)2j!O{^d9o4SqUBz1Z{(ipyXV%j7u8J|EcU54$ zs{-p?6s=Ms>RlCB@2bFhR|VF)DzM&Ff%UFR?RwtnT@~$mR|VF)DzM&F zf%UEmtanx9sdrW2R4-x1e~P6e?a~n}9l_EOEFHnp5iA|S(h)2j)vkFb9ch=2VCe{! zj^O`4zjM?(eYDm)eX!o?d)+Jci27%--s!`S-syw&PG9YscY3E!yWZ)8^-dpd^-dqG zcluzx(+BIFKG&vt2{VRMEFEc=j^K*D8Cm~4l8$g99l_F3?W!}SBkj@=EFHnp5iA|S z(h)2j!P@(TzS{c)*4`(u_CA5N_X(`MPhjnRVr*#d6Igqnu+iQpaK&Ew@C}0YKEa9h zK7qCO39P+O@R{l*oazXcj$r8smX2WQ2$qgu=?IpNVCe{!j%wHQPTxe(Ua^PG{2Z5# za3USSye~%E6o>y0-@MT7{$>x~M!EG>Vct9Q9@dS8tMwk4>+~KOtoO)Zy+_7g?~!TO zdt|WQBZG&QzefhUnEpL7SnrX+dXEg&du06UJu>ZjkL=p>SwrSMGMF`F^2a8;qxt(c zJ{8~J1wQ{Q-{0|0866oX`W}|?qwi!HSNeXI@uu%;8HW|$DTndz-l6z;@jvmMa>aQL zVSfEt&U2_Z_vX)a?oE2$l+K~zeyH=QxF71=D(;6m&x-q@&bi`w&ACb3S9y+CoDUZ6 zlmCkI!Bm66wf64`^RH^NP>cP&9{b-~gYgWa&ZNI7R)1+%%?Vb`30BPsR?P`k%?Vb` z30BPsR?P`k%?Vb`30BPsR?P`k%?Vb`30BPsR?P`6uQ@XxJvzoVE#4vP;$`mIJjTYK z7I58{#@H|C1^n}yV{FCc0dL=ZtUdixz?WPz*2)g7>aX3@cbr{%eZVV+jzm{k8MzPO!Ym0hiP$woz*XKB!}{Wo`}lg8hqamyH4U zol|W4-XCz|r4wz(O4Yod4I3ueAH4&f`{QK0_3(h}x13^aX9fJ*;3;<8yntIRoML}1 z3HahCr&`&i0gvuB&91sD;QcP2ZmpjR`06L7Tl38UH~3|`eg90rtJ}@6wa*1y^YSC? z(ANTPTz6K)OP9`$HoM$0J6?P8`?I6ZH|xxau{NJDH|DVXy(438RSM?EoZC;GANx}4 zocXbjciuHW_I=(j3nC{q+b@h<{cX>Z$l;2~C6U`Lr<6p_*I!!_wb*dk(NUxGN=u`5 z6&PUkz+<tPmQ&sUJrQP$}wiAggmFbc9=cedwV}; zr78EH->V;ESLB6z3pnrIzuQ!v95Cadcyz#wlLv+b%=qclKVZhySMOKx{uytTmIur@ z%wTshoZ-1xs@alp)r={*BxzHIFnF!Sh^{D7HX zN9P92yu0I#?Ytl6WA?g$nWsA+9We9v!g&ERulvsmnE76PTEN@~D(w|8_lMlp0dwD2 zSu0@fC#!P;=05Z2&H;1(skc+W+?S?Q4w(CuF!wRpaDUUa-1p>@`=MfSpHvRqKb0Hz zRpre6R(;_Zh0<60ETb*4PGXY=bqn!I}$T%@MHX4p?&ythol(Tmx%v zf;DHsn#*9#eX!;}SaTn&dj(kc5U}noVBL$rx)*_UF9P%IW?q1GPXp^-2iCn2ta~F^ z_eQYprC{A-!MgW?xt}xs!Maz2b*~10``cn$cwVs4eV+EwImh_tc-e^SGRM|CHsYyU zj=&v8w|n?xg%`zMXs)ogFZF z7QYcN`QKi%y0@WUKj#HZf7K2TvWFk}fj9YwPsN32zOXy2ksy4 zfqL%KuG$Z*+7GPS53E`dtQr!m+7hf<6s%eltXdST+7+yt7OYwqtlAi?+8C_b7_3?v ztQs4v+8eA|9jsa%tXdtc+8(T$AFRIx!1~((tiK(=`r84lzcs-68w9MsO~CqF2CTnj z!1`MTtiOH0`kM%>zm>rH+X}3|t-$)*3ar1y!1@~vtiRpB`dbgIzxBZSTMw+i4Z-@G z5v;!@!TQ@1tiL_M`r8w%zg5Bd8}>%KG{YPzJ*`SMv--M!z?UC=xZT*#-J_h%Kf~Co zUAWHGZfuv^Z;MkK#oA|dRc}uY+v3y)d`90RO+Nn_PHlvhKla<=)CMdbw&g_g8XMh* z!MYEFbsq-nJ`C1<7_9p+SodMD?!#bm;64o2eHg6!Fj)6tuivMHs$wWurQ96C1^njV)bl zFPpR@K!SMkvcxh0xK3+vB2BLVm+3A(LU>_fUz%}6EJ=jO%E9Vb0-H(-0>3vCZ9!P z1BR224-4xm|A3u;t^F#NawC>O(x*iJk&*r&KjGnd1t(BARwMYef( zz|UT{$j0p#aOr|Y_DEsCllNO>!@C81WBwu=&??|=)fZW%x&dGOQ>ndMIbe-djT6Q& zST_1dcer}Htz^qsim zskmUp1uHICalwiUR$OozSAC>C#p%2j#wH!l*faLvN9|y>dwVzLwLYW2PifcRr{MqU z-?ORxcFh;rF~@~>94Wr~gHo%pFtiW2t<)AC5pajoN^PsFH;8-0BzIpO9`MKemD+9n z10LL`)c(>f;Gesd+V(91Zq}>RX6zF1>b*;?+g44L_Bkd_(I?O!_{u*)< z#%96Zi|n(L!Whtag9o*P)Asc5{EWURzthiYQWS;s$pc0AK8Ot4^HiGI<>^+Ee`K?Q@s4p68mj- zXn&|ziG4dE;DX!|yY+y8|5BsGF6bX{(e@>_eYb!QtLEO1|`;Emw<@L6L@ z?C~!GZd6=ieLoL*rdZd)xvmAL*Va3x)INDCTq{hhnpSE9+`D-2<-Z?ojUNbj>^(=@ zN%sZ(dFj!1+Wi54)8}Yw^>Dz|e#iCuY zz={P{EU;pM6$_lkQs3#ua(rc_MYeWJXg|HdB0J@o zfE%=5WQFBpK+MZHelI+Qya~F;-)yAYg^sDqK>;)U~|61eai0}vcacpz_P(UX1*0Wkb8J1R}7);+q2=RJ_0zt_yjlSl7b2t_7#pjy-Lm z?Nh$*NSL@wM=rFY@>o-wF0>)ng;-h0xK3cjg^l76sKcs;lu^DNBP)$%gvp`9HuX_0m}xQ+Gy?*H^u2(dw2f@ z_N$w-*bH^JLHT_{Hu#hcST@+F{OH{r?Rqx{)^n3=XtMV7|$t|4SDKXuzZ3Q3#=T#$_=cX!RiaR-br)quJX7gr_Z(K z<@m*O=Gti;LOwk&a(mm_hdfiPYw4G+1*g}ZvSOZHQXH-oChq-5&a=JC=k=U@=h@7C z%I9^xc{ZhAz;j+d(vIpLaPjIR?fLS2J|BOi-P9(uuWfpyHEJDj!K-tvReAe>i|5+? z9y90h}?i_pU zwty9D+k6y@cEtiK7Fe;siUn3Ia2iW}C(kEtoo74E4LNLlV4fYfAmEO#%(Lg*zFcf- zd_B+JDGj)Fjrn%=qJVeLpKs5Wx9dGSu~Mv9v?~@^vA~K2RxGe$fzw#&_)l><#x7Vn z*EW}rz4zVRdBb7)A{(%5z^RSqK5{^uwsFg16a9%l`~j<0ngiirp+#oyW7aW=kV>AzvI774mNO`VqHtSt_7#puB<#e z@+nN*zTeIAe1czmZIY*u-(wqIIKw7C9NMqH za)v!}Z@`MRZ9a-cyJCSA3#?dR#R4l9IE|&gliTq*vttgsG?^W98`)uY%=tK*9s9C$ z)a=;DL33uuzH5IGu~Mv9v?~@^vA~K2RxGe$fzw#&_)l><#@ZxfZ}ybG&o9}~ciDhb z8_j*gy$PxNF8#UoU}ITsqa)OW-@VO!f5=_@P>d`+5o7@4&--y#zk?{KI{{1pe%W!+pI3 zey71SUoVkEie*E)t_8~{Sh2v$0j%7>${DP_fWK}u&DWOT16oXrHRt-a(_$@JyX!Px zqmpNebuI0>7Mx!D#lY#Yo);$8!NaHfdLBGz$aG)NgWoBf?(2E*(YsFf^*ne@<>|hj z2k-atwD`B@r0b^ndY<+kbEf%v9^Ab9G+)n?Pl^?ncEtrNE?9BFiVId;u;PN#xauSA zDSl(m>Aub+H(_kv-D#??OTij%*r*+xwx|05zgRvc)?nLRHzn3)x!EbPX8YyEDY2HD z`MLY{s=UTK?2jq2_EW5F^HD6{m-1L(#R4l9Sh2v01x{nB@APZG{?lU(JbJ+NSR21G zbb73r4;ni?*3vcRx-n2*W7j%$daS**uaa0PRxICM9t*5kV8sF}7Fe;sX{>bor#KyB zN4oDas0q3DJ~wx$73r^Rz_J0SHk$ifo8ok??d9eyH7zzP8cy@IE`DSKmJL`o*r)tx z4=U~2g9_GjlWS!UmOWVZ;MD%{_7mfJU5ZzandsN+@PF_56a9J}_=#sG`t>?+QSC{7 zy$*cBL6iJ?9r$m5ndH~&z#qOi$*&Pd?vY}nqg5?veSYYJ< zR&HSB3|3#juMeN>*EYe;51t&?Jg1JG9M?i`o;2C7k&7Mx!D*=v*Ida^LF zj{RY>Urz>i*l~(qPX?b^bBbS22A5Qy;@6YGJN!D?uP1{qcz3d2PX=f1o$S|>!J{vn z?AMdQv!+b;>&fJkV#TFhalwiUR$Q>+f)y96xZpId`bc|<-*|MgU*{w@VQj9gInl3+ zf;HZ-Q9C$oPxn6;oLn5&06Se=9M=Zly|p;58Mb_)IIbmL^ImaWW9;@zaa?;;tZnmA zEZP+dtXN>h0xK3+vA}68^__m5mz^A+gZJFy=0f?}?3rbg`Ij-?u z=Ei{5ezl*RSSeO4+7%0|SYX8hD;8L>z-g>>{HHh_V=qsh?AIi@c5jDStE9iO0m}xQ z+Gy@`ZHm*mwx64`tf^vitGjQo)`}n5fMo-g4fZKN+IvsC_TGc_+~iu>gJlnvJvgV!xjO{OJY7 zem?{F+-r;deg^O-Hx~Q-4B#iPci%j^{S4rP+zgC6o|{}Nd$8=mvInR3%gz`Z_baCOi6_ST{fhW6 z$QkGND}s9uALsWgg7eQB=l3guOCKKR_bY;*bYqqMis08;kN5i(!OI7Y_xlyWm8OjM z`xVJ2#j>GY*Mj8}tXN>>09I~bI(}M3AI^OT61>5xTem^bv z_0sWvKP|Y^3FG~KTJVm?jQ9I#!Aob2_xowdC&h|OyW)Zs7p%Bo#RV%aSaHE=T=kLm z6yG*$oZsh3Zo=5Cn&`e2b$cMe8gJOB9h|nO-<3D}a7^3-x#*iQac|_zDr4iG$=pU` z<6g=WySlSq%J*2#95^=ay;Q7i^HD6?6$`9bV8sF}7Fe;oO%h9er(Y9CkBfUyFWqNc z+?%?O`<7pOR%>({7x%J`>O3y)aUJN|wf9xu4-zZIibcC(ffWm^SYX8hD;7A7m5%=u zr(^5@H}=?*$+e9fX0Imwl?_-n;MC^-V(&emt|+obZBPLLF@TvIL=Z$lL6AOWKrw+L z5)32-6Xw7OidiuSFpD~lI%bT6;eB5ZW-*|GsG|~9q7hUSb@cYrb)GXlF8x36{pa)E z@sqV!JgeBJs=BJHt9I4iyBz!cHqZI7HYy#n*pwpEJ!Nc7$wwJj8CV(Q^X;RrCF%NF z!p@ugR(V)?Sa~=vzvkY9%Ki>{USq>$+I$~`&-yNVatN818m)3>kRuW z@ZZyN@eP6BNLil|SYHxk^b`3h>sR7$d6xWdX+!;SWb1%G4ouzf$APIc{x~qtfPMDmo?Sm6%cahi3tKL1xv=HJmJ8?0^%+Ue^WrvX zxv38nb(4{S@fTAbUmIogBO@Qv^D#HJNn?HJBi44>0cGE@)6&==`jkDCeq;4DtNv{o zCqy5#wFi}b)ADu5vt>~?%YrQnwk+7PV9SC}_(@r|1L^vRA+PTk`RG$d{`#6xu0Ckg zN8dE+sUKOM^X+U|){U~PGiAY+1zQ%JFYBl8zvCkRj=i0}d-x>sTjcdaREGXl2L7px zeu&7+$T-$u{0+&UeDp(9#ys^&R0jEc`xyI$bYs83&YR?;JghvdJe-$j&9LLJ7{4gb ztXm#FET*$=+4Y3TtXqnwM`qnJ^^(Y}Tk75znRQE>Ns(E%JpM#v)-C;Cjm+FMVNU8l zo7N}K%8>4FVe^D73$_lhb%U)l?6bhkq3h3$<+5)4bY5iElh3~&nR)G|Qaq?U`&-)F z-@^IdvUXapUF>U_a#;i4-#&gTSR3D)%8<^Qxqh3-tfjwc9+@@vIU7Z0?fvnZky(=; zze;4*>W6+A>&)EUVnJ-%JX!`o%8kzOgb$do;-SyQzky(!&w{K+2 z`e}VEi*(C^Eep0R*s@^Dg7anh?9~5=bY1#!sjpeDeqL%H*0Fs`?*{AJ&$fu|#=7@L z{LRzfvL0?ie2J79zs8lyvt>~S%YrQnwyaF1R2FPmaK5bk`=96hJH~o%MQOaS4tyzP z>ZuH@44jv7>{D)@^J9(m>eBREfeh=|V(Gh~40$R8D}#K#eT;KOx^b>xzL~}#Ql5O2 zhn0u(^6Xjl8Xn`e<(Yl6r;my0?3=xGYGn4!>Rl3jxn0@tPJ(^x3GD_mIYe}*t)^i8TMIV_Hd?`%4Og3pig5R*w6gp zv&ihLoVzU6Gtd5(Hutx1{X$d>if`dC)>ETytw%YrQnwk+7P;Cxv=JN0K@w77a~6ZT7AtQDDk z)Iuqp{nhpA#B}yuyVZ-#e(ag0cL4p-__|Cd|u9NC$AfsbK47=N9JtqqV}OzMPz)zl;oL#O-g4?}_gl&u%)LPv<<8xTBhE%Y+2O7vS7=CEep0R*s|b! zS^4)r&-r(Z^X}71?;hviBT}Z$%D~FNc^St(<>om*);OCgTvOP2liw;2D-SCV=jE~4OS;GRInUS)PTM1fvCpvc$_-dTzjjNM?% zu`wOH!O`h^OMS2#?47==Fm{7`-x3+S!NNU}u?>6o!T3JsSsCi-Z(;L)(aGg7AhdG@!Y`&&5wTWl9wo*I8EQ!X~Br(6{C z$2PU^wUMz|-S5`O*s|_+Z)9v-mz3&;?dv*^#&m3A|N2;DY-MjKrDHqyeW}iQwp{9I zxv=HJmJ3@hY`L)I!ufK2M$+?)jb*J9V?AYLuuQ^IG>I^9`T<^$1d@} z`jN3$9KBv->=-9+6dC)*`As5Y_gK*?GPajrZ5G+Gep(;PBHglJ%YrQnwk+7P;Cxv= zJN3sd^r53;9k3VOVPs_NNIyCxGWMmjM?}W%bc+&W`}%Q-v7a&Cb)GGYI#?ELS+Hfn zmIYfDoG&Z?{^vRWj$v>4Y3bd=4s%{<94W)ID+A|c9Q%};=lod1Ui9nqTY(IAq)STQ z4Q0qv8CV(Q^X+3iXVQ)53_EY~TjgQpVddexJpLn%H;;A8Gkz@o-n=})Svp~*>Xv@T-b79%Y`i$wp`e9;e5G1 zV9Fq`^*0^Pr{fPojD6Dai& z#+AOY_}%QkK}^RV=j%q1E$gTCu`JRp3$`rSvS7=CEep<<<+D>a{F1B#{z}#jKPKyp zf0NIG-;>XXKa|go{kHcG%1zQ$uS+Hfn`Lgowf1dO282&zv7yN)6U&`?8 z%D{OU$3EreIX~9$S2BP6n9N@p@>B*^CVQ@2TN%fmbmQ2=&YS$!_Joy(m51~4_$<3# z$}@h`te40iziHM>Fn-glm$LNKZ<_TIjNdftB^bYH)=Myc)2x?Z{H9qi!T83qUZOsE zR)%zc3!5iwSuj51uGy?xmR_ne?6bi5@Upgq@mqJzi9fq*QT%FIqf*a2`&-ieEu8-? zzT2+nWy-<_pY=S9Z$9gJ7@vLC^Dw^rtmk2T{8`V#`2Mq=hlvTmdLCY$#uH#Y592$` zdY<~^*>Xv@T-b79%Y`i$wp`e9;e5G1Bk6g@$DDO0b(4|7N1Jsi?E8j{>2N+Be`MBL zq~n+E8VrAJ*Jk)}yJo|`+qE2i->&iS2Y2mfSwF3hWsz=Kuw}uP1zQ$uS#Z8ApPl;S z7w;Mve|gu&_|dy&#=qXRG=BH4vGK=u?T!DSce3Q!vZ#Y)!IlME7HnCtWx@Hf^6!71 z^Y0k`=Bx?%Eq>^%6?tA|U}fOEjANhQ<~cvs@Rw&ziwu7BtaZsp8CV%u8RYZrtN#cuwMrgw}<^Yn7BRc z*TKZ?VZRP0ZV&r)FtJ(KucJPBR)%zc3!5iwS+I40ts88eVV?yih75a~FmaRI^CX^< zd!fX2VULu0=Gotp?r-7zZ;2h`ezHti#DHQy874Lq`^hjdqu5V|i6zB;GE9sq_LE^^ zPqCj26O)SlWSCf0>?gy-u3ka$7v4H8GlJwxIPxtB=XA@>-GN95k4W&N~1 zmPNW{!IlME7HnCtWx@Hfe0J(jTqgHmiPz-bEODINvn9Thd%47Ya*vmIQ11N_zrwqy z@@!eu!Lne>f-MWSEZDN(d|CPTKhODhjCe=vN%C9bAhB1;^C|-?1LtKN`}{V~`LRa4 zCiYa3A&wJ!t>mK&tPHFS^7;1h-XhYyw+MFL{IL+U}BL)s}#`quLk{k5t=j|+mSe976Pp@)Me37hWk~n8uzA9k1zQK$y1~{N_E}(JXk*(66E|L)PvXgI3rbvT zY(%MNp8YN9{ua*vme}dq)5?@Z41DZqVPfNBPYV+>AA4GuSo+x0!o=9eo)#wdKK8UQ zG5N8lg^AUVJuOV^ZtQ8PPo6E8bjyV;7q(p3a$(DbEf>z0>oby`XJWi#=SkgUWQdWD zT`27PhK%WOKAm{r-cw0jbZsDsm#%FjG26A7B)+<~l*C=v#*%pK+Fn}LPwQh@q+1qj zS+HfnmIYf@CX*}6XXm+yORo(o@#?irC62u|tHih0mX)~o+PD%AU)xvW_j>neo-Kk4-5u z#IeWLlzfzdm4TH(KHomxQ%Sn_RKm`i{8o8bd02TkFQ1P^@0~cv{5$U7As_D|f%A9P za0iOMGymQ9)NlulJ`wr5nY@FBy5;Yn@y;6S{9oO{3{ocZUZ(+Z;u-{wQ?=77F-sZnQzjS|Y{`=!PpL|^B!>;pT*ZHvP zd^o?(SEnF7ufMpaCH=S5ZGUb(OdZr);k@4J+Me`Zvu;<{LtY&dR>y?ZF=2H~SRE5q z$Ar}};k=HiUPHQi4Xj=RtJlElHL!XOoY!me>-=B3uQ|WYcR!7M+)snuPlMf0gWXSq z^ZRM;-I1Q(Cv@+K^xtw1`RDeXsDt~%aDIQ-Jv7pP&Hk8ss>r*S3%i#KyO#^QmkYa> z3%i#KyO#^+_j27oB;EZ(*!@G;{X^LOL)iU8IKO|G-%tCc`@!@3X`Wk=kLOmf=T@-i zR=Jp;OkvMVVb4rq z&rD&@OkvMVVb4tA{F$lebea6W`Am>Jf9XE@{JE9(A;@bV0&5=vYaaq@9|Gs?L$pO9 zJ#Y7-Ed=SmrA^e&*-=mj?VaGfy^}T}r2iUw5AB7J*ER{(HVM`?3D!0V);0;&HVM`? z3C`OlX%9oX_As#aFtGM8u=X&p_AqeX9wu)e!oA@mR*7d!+$S#Q?L)M~Bp>ZCVeK$s z?J!~OFyXu%rZ%6X=j}_iIVAnJv_1YgdqwJ?T``=uE7tas^j~9FsVy$@+5p4a0K?h< z!`cAD+5p4a0K?hhC~4`a8h-JHYxo!1_DDd4C6eE3)5~e2ZXh`{Ccx$LHt#0;q%jJ8<5AM;`~$ ze~tfwJ}=1YYXj?R1M6!8>uUq+YXj?R1M6!8=Y4JT?;u_O4p{#VSpN=K{|;FH4mj`M zk@t7l=)42NBeUbXF?sSqVan~1^ZpM1ZXZVKllPa@hmQ2$(wFw<{O_oPezI`hPgY+- z(tnMgpuVNZ>(dJB(+ca;3hUDf>(dJB(+ca;3g>-V^`j(RKT23XN?1QiSU*ZwKT0_7 zN1694ylR^vVVCFQ8Om`DhK8F@j-2-^)PJ9R^xuc|--q?zhxOlw^ZxtB3Lrfnmq1^2 z(tpdC6+h?aP92O#0q5gU=(A7yukpt>h6D1(j)09F0UJ94Hg*JT>Ba?u{~a-i$fwQi2ZWm&$5>Br<0tpJUZBTbeT*p9v$zz_cAlqxT_i&#wPbi!@p$=#-EGZMjec=2qa%EUWjo_s@|*gG=cmRC#t#oWXlru^2puds1nVdK8S#(jm2`wHjd zzA}e;|15Jick&{`T+cnZFmtZ==l*xcI{vx%sMNtY#&AB4F|h@_r#vF!?ISdf~d5b=dgou<_Ml{CxrVPlFpfw z-@sqGXOlB5znR_%%Wu6C7WPiqEWLCmEbN`Iuy?}3-U$nH7FNECHh1@{_mCpvJ*2Sr zkiyRkU@-ueD>_e4`??{kOq_qpTaFzSEfK5NdzU4wb|I(d5cI_%x+ zuy?P+-n|Zc_d4v|>o8~Q-ucd1ylX%2`$oq5zG3hChQ03__P%d8f8RGY1Fli)wH;Mn zlW=zIS_Rt!*Sgpw^ef##kFCPBrMu~|VelRbY#SO*h-*=79=^ROGPV!{$3@0Q;^Z?U zW1FEafGvl*12z>8{1|l~Y%RRU1RD(RH^DYzwJl>l*lb+6ePnDo9_$kt8;>uBM#lEz z`=cUbL!!=tjkotuVEfJe6topKC*JddEy_!u#B^-AyQX(cAcM_}IvTdz-Zz0w3-?eU zgN=W0|% zs7qq=^J7T{TcEGrjPlqBol#~3t~F9RlU!RjLnrgKDJ)&EnpkwUIaE; z?g?PKwOX_ITWq?n+A=b>UJq>_85^*#_KJ*c*pGuFV>32tWMpi~>WqqvO`3Zk*s>aL z9~)QV@YBE8u)X$uWNh2M{x&i;tKNTs4W4^G*sQ)#+E2hnj(GdzgUz0MMA)&f`Cv@P zzI~n2-Vt{1_e_rI*uy_p85ukIZqG)>ex5r)$P>HzJ>H9q?cabUk+BtYZwhjkY4}Rm6FfWaH3vXQilyLqTt7d%4TVulBZ?BSZ)6GVQ15+PZWa@03j>n4X z8SnDQ31O$bA|JiZaba+^$ZKwYbg1)swM?eLzDI;-r$pZH*u%={kKJ@|S$@vSgUb0d zygI$tsg!@saYM@G-u+G*-?&ttx;GtAuIE#;_Al4}?uq-CpNsU_ch<=2fPCll9i#r_ zb7ak08I%8@KS!qAgIcbhrBk0Vmqw{=g>W4W8!FF9X{=c#JN%u@d=1fHSpT_Mc-7_87yB=Wg>4160PcMo2 z@QlN*j?6QDeRE`<@#smBdB!o7k$J`^UW)9Q5qZ*IoH4p3}je(`7RMMO<-YjI#}U<_LS{2z%xTd*%px<_LS{2z%xT zd*%px<_LQR3LBFgHYPdjnJH|H@l2+4UjXbGE9{vpoR2;388PXe9mC#70DDgX?EM9> z_Zq<7cK~}20_^<=uxHS)XV$Q1;;?7puxH}1XW}sDBlsf0o{7VriNl_y!k)3hp8La| z`@^35!=C%Yp8La|`@^35!=C%Y+AzS{Fu>X{z}hgt+AzS{Fu>X{z}hgt+AzS{RKUhw zhK;=pYl8tBOBvQ?1J-5(*2V+Q$5__pgmi6DVB@aC#$$(#(+(TI9X75zY`k~aIPkDG zEpR@Lw>CDUYhwfdpT_Ryx7udF+HAnu5y9FK!P*hQ+7ZFp5y9FK!P*hQ+7ZFpM8Vob z!P-Q@+C;(HM8Vob!P-Q@+C;(HM8VomLW(>~9lGTQd zbYm35#+QbTI}IC;8a7TfZ2W52xYn@ou3>HDU~TGPZT4Vo_F!%HU~TqbZT4Vo_F!%H zU~Ro%ZNOmd5@GEUVeJxO?Gj<_5@GEUVeJxO?Gj;aEMaXdVQnm7Z7gAJEMaXdVQnm7 zZ7gAJEMaXvVPk2+#?pkf5rvJ732RddYf}nqg9_(kW@-~ly0)^gadcth>%yFa{5xU- zYokk^+5p4a0K?h3SfN-vh-4X zOIV)*Sf2t|p8{B)0$5vgSQ~X%zX|x?5#Nk_jQ0iW0|M&<0_y_;>jMJo0|M&<0_y_; z>jMJo0|M)l0vj6*HZ~fp4-0IpGgzM&Sf3YI9~n3w15KYD()Hzmjf)8Xx5RkN#ro4n ziL&%jg7r~?^-+TLQG)eRf?qDh@q;-B!7d%v=LOae3)T+{)(;ET4-3{03)T+{)(;ET z4-3|(4A!R%)~5{CrwrDo4A!R%)~5{CrwrDo4A#dDHU<=I3@BKiIM|p@us(FKK6J1? zcW^$|lRki?>l+9g{|z=S9BjNe*f?^q@#SFS&cVi`gY_|l^+|;Fd4%|xv)ODus*zSKBkR6#iZ+N3>)VP zHvScCTrAjlS+H@mVB>4SoP+#a%r1SLk5YZ6!y#%_Usk*j1~5b z74}RP_DmM`j2QOp81`%z_RJUdEEx8T820QK_DmV}tQqzU8urW@_Dmf1OdR%19QI5c z_Dmf1OdR%19OfH>T{`R;E6jYyxj*c=KkT_b?72Vexj*c=KkT_b?72Uz4FjwV1FQ`L ztPKOK4FjwV1FQ`LtPKOK4FjxA1p+Y(rt6IfdmSQ`~s+Z9-w7FZh?SQ{Hy8yi>~8(13~SQ{Hy8yi>~8(7;6 zSep%4J0e&+B3L^jSUVzEJ0e&+B3L^jSUVzEnmLW(-D$TK~Z)uMHdN+P1;ybc5Th zp5=*7x5I{!(dizn6&amwy{}_F=yY!_jEqh<=*QO5EW)Ie857uT6 z)@BdZW)Ie857uT6*47Kw1`H;q$D@bG`lCnJJtnetiO6V|2y2%JYnKRXmk4W@2y0^r zYhwv(V+m_xnWdL(EMaXdVQnm7Z7gAJEMaXvVQoHP_CRK*cA>B~qA+_Y*q_7Nl)~DS z!rGw1?8&@YlGi4dbZuo}_K22^k9o33)c?%L>=9v?jtqN56Az5c9?{PGL}rf&e*|Q- zt%bF@g|*RzwE>2;0fw~!hP45PwE>2;0fw~!&eBV^qp&umuy)R{cFwSN&aigQuy)R{ zcFwSN&RKfN&KcHb8`fqU)@B>lW*gRK8`fqU)@B>lW*gRK8`g##)`lErPZc|JSetX0 zy;;+>Q72s+by%Brm_1%>)M0JxVQueW_MC^^9A(&ZUT}G2_M9(0D>8e|kBy4Vp7X;a zBeUoHT`dir()0iw>QahtP$Hr<_zn^j*&UTnz>nI&am!n9hoz%4L6Cb zPZ0TY9_RO8A0^WDQGz*lyL3$aE$4CbM@QzIZbs_Ugbe3*r=Ad*b3Nw~eOr*x=LOae z3)T+{)(;EjoN;C8**Sk)Wxtp|=aOTGMCQD*>F~&$V`A&hZ}lmI^(lk(Da-Ot?;UpT z)~Aegeac{c%3yuUV13G9ecWJu++fapzbman^ob*#vt#VfVSVUeedu6)?qJTKUGwMz zNV>j(FlXY0`(vJ*iSKcHWX{CzO6?Dk;Y|GWiIF)IUvgb!&cr{zJ~C(Gm!|gK$m?SW z>yrrU^9bwn2+=Zf^9bwn2njKALkH{E3G3Gh>(>eE*9q&_3G3Gh>(>eE z*9q&R3hSc^>!S+mqYCSz3hSc^>!S+mqYCSz3hOfq>oW^uLxNp8tdA{>EeiJMus*r4 zKDn?yyf8K`>QMR=ldi8ZjExO;=`c1n*rmhR*kG3qV`GC|I*g4CcIhxSHrS=ZM}Ian zvrC8dS%&p-hV`L_^`VCKp@#LLhV`L_^`VCKp@#Lnh4smW^%IBn6NmK^hp~gg79G}4 z9M(@9)=wPPPaM|g9oFX^*5@78=N;DP9oFX^*5@78=N;DP9o7dQ)(0QPCJnoESf70u z+cxaaVSW5zef%>{Ww1Yov5~_r9X3V*Z0rIUn?3B(Gx;?KXLji@Hhb8m!`SR$mkwjI zhg~|1%^r5?FgAPGrNhQRfQ^{|V>gIBIc!V@*q98kF&SWEGQh@U$Ye?}8DM?+VSW7X zy=Y=l`)#=K+xv(6Z>})~e(k&i!ezZ{X8i7*gTmiFkKDD>kZ{epwX*adHXIh#Uw!qA z@7n92F#g2IXFfk7)J)ec!O5Za@Kv+)1=o!Ui=J2|vpD@1XA=x%%i~q4LSdGmje*j@v1g`@yt9;lx>yCtZ6$2lBUA1bT_aPU&Ay$I$#hHW+2NJQ)PJ=HO6loyU2uD3 zp4W8RL3!H8d}ufGr#&r~cD6pWzxAYFtp7vn^({Zw4Nd!oBle1Yv__$C*neE)CP(!R z3m%U==)S&T?Bd8T{?Io(w07*T6$k7S_U;&Yjc4`=`|lQc>6ZOM{e2_TU$q8DzMw(> za{8fX_Akqyy10KipSyM*P|kmYs|S?J?f>?Ga(xc1HLzUIw_6P?*Z-*w1Iy1vdZRh9 zkC5N|j>zP5%L$Rme~q0ZQ|_CMB2%9(-^aeAo|}Idnfi}80@n zJHBAY7wq_g9bd5H3wC_Lj;~Ckazxm-vtG~|9OI|=)pH2wFm4&hns zFW#kJV*3#p`w_MuVfzubA7T3uwjW{p5w;&;`w_MuVfzubA7T3uwjW{p5w;&;`_c5@ z!+h7j*X7~l0sDtH9-Lpir}p^J{+Rv4)Z6D5w|i=QIODPX!#~cQUp)P&2_f0?fN)%& z`Na;kuLw`fI3PS*YkqOUWmkj-69M0lju?5x~RFFrUlxo=ihpJTQ-BpiS6tgN2x?>HnZ++tQ%|1&;6Bs5%W zR*~oGSo_eh_G+_=)h@d%n11Bjmj>nAx4Sf$ MP63l<2+Lr{&UH^uQgY|iKkBfu# zykg^vgY{pv&c)^DBHiaj-gY1#+lTyZH_Ej=sgLbUJ#ByLZ@=(dJ#QHtMt7Z89CpX$ zVUzm?hc;WyE8g+r<>9dDgTsiH^NJ_;9Us1{GbG$rdtPzijpIYp{f2~x7S1iMm_0s> zdVEN@v2t$l!1@!ynr(-M$rsEmR_`_;jJs`UIJIxuM|~!QCT)g=TQ`_n{PVsO%Fjjm zCEFYrw!djkCcjDLf#HzhbFzGH>T*!%(0)#q|2DTD6ncI;J1h6%n!`iK*Jfw+d7xi< z#&PfLte!nC9Ue}fFgvUNxCe)ainC^C{dGus9(2U1vx|EyyDXT#+I5!&;2MwcqeiFPWRkZ+FCqaQ9PlvV3YBd2o1h&pFxn+PL2#q3)tMzK(5lXgJ}L*;##- z6%P$B>@+*8=cF!&h3;$3&g#F)8Ha^qK8@q+;cE{IBR+`Z%XHpb<$0gYhxgq4dH*e! zabbNJFV>TBWc?XmJ{RdeFY>kn`Pe?>Z@W>h?MZ!XXX`fF;(p<&tv^RxH! zjzT&v>d(*K+oi*XhR0T!pS{ngUOzOfTpY*OUltDywVt1sz5ieDIxH-|eqJ^%E`MxT zsD1dnY`m<#^?_kV$Fz^qadh*e2ZnD}#PQ{Gk-pXo2Zbw7jpOl--G_(D9pgA{_Wba0 zcHKCBAL~3KT>s9TY<#VG^@uR;zByTaI(;}ITzS!)te(%Mu_9+4Hz%wA>N^}9);efT zHog}3IygL;es6g{P3OH;p7+^&c+btB_uq0E7uJXIVm%p0)}Qg^bCK@zB5ym8kL^SL zwj1Tzp47*7rk=Jx^|xQ>uRrFmS;haP`OE(Li3^ zV~&e+<$ux~=b9wdyTiT59$a{}{wJItg&&UDs!(^-vf|cf-19H|Yh-S!*rYJy!{ym; zH|@A_q0jYSX8h4+>lCg!e?^vmo|U0oe+%z$)C2baa-G*tPTqJVKG#W&k4=`{7VG(O#mHor zo4&~8SD7&~*>hs7bFG7pO-5Y#RZQRhlw`HDR>V9nIyYH$@Yfl?_~>QHvrWFq_~n@s zlVhHWeC)Y*B@MSi}Cf*gC^L3+yw( zK09oiz(1DS3SOnuhOlj$rI*?qwl84&2)6HF`xLgXVc!ARcLVmFfp;IjUZHb~kF)pi z=?!WY4&5QX^TTginvARUX_lUU-}3Bl85jN*&j0r7@w*gOPFa-Ylb6qPUdAy+K6!re ziNgx-RD7JhKbKx~MB#6JBOm(wQH3tEKg!ad9&$|K%E6IO+3ncEu5T~R(%YSJY~dfh zBloL*Y~lFlmSpKiynb|H=nj#e`Rd5R(B~Fs>Ag=IS(w=`@=m85TA03kQI>vR^$~?? zw?v-ac39z>5s}YYb5Nm268V@{1{NA^7P;S<`xI{N5V`#xdleqpE%MM^_9$F`a^(E8 z=UEy0$lt=|30oFy9boGQTW8p3fqh2UXNPSQ*tUXgL)f;3ZFAVZfbApLzJv4Q@t3}J zes7WgW6Z`em>;u_LE6W01Um-dUmAnI*Z0bA1Kw;V0kyrm=zrwc@BVX2Y-@-$8 zN8bC)0fjs6kGyVGzjFG-)%GdN_c(0taz5j~*sGlXdk^keF89NGdzb5Tk_AKPH!}F2J|DJ0iQ|^h!M5aD(?HQSRPU{kx`mft2 zGSAhlWn`Y$blO3A+Q)ooH}jvGwx{LN&en(ax1RKi_1}GsRSH|K{3@&et23$>I`xg~ zqQ7riy|D1k$ZxJyt+2*-k?XYjM{;h@uQU1Uk6oDzx*+oW#$P3GJr()FT|ZC8ej53f zwLeNWUGtkv{>f_>B&#-yylIVj$qniHfp=#5$?qnA-!Ss%CT}Lysztu5!RyIm@5Fql zXVb3BGkMal8Tfg|$nVuLGWnd8uC>UM{2#6tnR0ur6Pfz7X&IS%&e$+jll;i1bHmSL zTT#~JJ0nwvcSgo_rel`5-Z=tx?tqZ8w)$9!_I54YkSyv5O#iq{m#RF|6$j1uxmWnwIA%75O%EyyM}~a zTf+Z|>wM=v>hIhKJNLoP1+a4g>|6jl7i2P}xd3)9fSn6q=K|Qd0Cp~boeN;+0@%3# zb}oRO3t;C0*tsB+Da{42bAjo6OO@vv3p*ENGNriyb}oRO3t;C0*tr09E`Xg2VCMqZ zxd3)9fSn6q=K|QdAd@N01+d@SOuqE(f}JB^=Lpz20(Opoog-l92-rCSc8-9ZBVgwU z*f|1rj)0vbVCMzcc|jTG1=x83c3yy;7hvZF*m(hVUVxn!VCMzcc>#7_fSng$=LOig z0Cp~boeN;+0@%3#b}o>a3zT6lfSn6q=K|Qd0M5?^){S{nM#lL|dFC(kVg7>uZ`9d( z{=Yc4Qa8VQu-`q{?_O5_Ki0t68piJ)ZQ^$i_PYoB-Glw^!G8B(zk9IXJ=pIa>~}Ad z$*qCyFW%>0V*3#p`w{+Q{)+RR{YabGkFfm++mEpQ2-}aa{RrESu>A{>f$vFEg%|{^{4~%kKQk zpH!xje@pU}|CG=FHlOF0mE@oPZI$Me$(v8^xBrr7DgW-2Rgy_L|J!_?<+6~^>YUc? zC%-M%nS653l7Gg3`K@izeaf1R(tU{d=hgc+N_dtZUiy2*k$66Rwk3S zY2}6+ewO|Afj>{JO#fzOrD>Jv|7D!YR;9nmWYRpU(!91M_cZS+{w4pkOwub%rwkZ* z%0PyEC<7*c{=%g3e=(mMD)|je9+pAgltH>>@Go`A$#>7?)1Ca0;hA#frtNb>mY&Kc zxq2p)LH@KEzl-&0MEbU-(+>P!T4s`KpM)|E1&-xvv?z#N4ekVOm z%laLr4RZC&${^i7iTT8SH$B%5SsCV&YqzZ5NhggmVm`6oVe-iJOWN;0JC@Tv{g-i_ zwUzG!`Oprz?@ZcXe~fqgowlLb zcW)EU{_6%|%z2B7GmBlrGmmZ*23)_ecexhs9+Z zbqjaz-7H*l`v=9{x9b|7JibMk@zDFl?LX@ht~jn$82ak`;y*fd4qdiy9ZvpnUh(Gj zw+gGz*fc!9$GqZ#JGTt$HfkH%KQ_1c?6;eT{ny(pJhbcFV(&vo$yxowwSRlLIIiY}$raD`4~I>8x!7*#!AZNl`iCW7yj)!G zi>}ENr}qn!`n*!C_TyT~vee(U{Tr_oU)+V-$Ia&H;->`l4 zX~h;FUy`ht-#0v7ds=bU_9rEup4&IP-)UO$priXG`+Tr>xc-!B#p?aGPOko;PgpR2 zT5-Yj4U#Ws?-jm1=+$D6AwPESb-|vY?{}{j&uH^b_ocOahZk;tt=PX_vHK1q_Xu|n zd%alurTewNwB__-#~1JEUiX__!qy*6FFxONa`#IMJ;MeM&L~c}_@(YUPuMAJ ze(W2?Z^wMp{jKUf!VWEG7HgeZH|cQA4&k`xW)??&yGhb%(Dq@^zHb(L9=lU=@_yTe zRi1yd`10lL!?>ZFhVM_CS3LXTR-ykk4Z?$GEh+9dr**i$T7%GH;*w(Pt=ooM8#D-a zPDtO|Q`?1mj%g51KYU5?*}FFnJ?pO|Dz4V^oy4ucAsCo{q7E-=?$&J(6{Cl8Nah;)d{oKS(Nqr zJ5`;-_6y!9_FCF9yt8$k@Z+FG#fEh^4X1rkJ8YZUU3}YNv+%;kb;6y8Eh>&JY#z?K zt4?^M&7$HvO|}dNOspI3sajaPr>av}v3QLzX48emYgXwTI-S2}c;To8#n0w+3CA9} zcG%{s4~yM;bPeB*s~?8l_CfL1R^7r0FRUBJ-|~L3@7Qi(V51GfU#^*7ym6Oq;p`JO z3in<#uh``LuHmVQhT*MobBnk4*d`n>uW_h1eok?nb2^6`-e?+LcyM-c<$$fie&;q1 z(>|M3++*67;o!wBLXEv=W#jj&Wi7*w@4lCf-{sTy41b+8H5`wrSO6yBejjo*v9_6}7eUd+btz^QwL zLuXXE$SjeCZPSG za^b7l_`Tqa?ZW=&y_SvN6NeT;(^Fp0#_!F;x`zovr)T5$hwy%uEe?RH7e3+cxiR5Q;m_&)(a=Ub#_tZ|uD6 zz5Q&vhT+*K=4S8h;MW_42kOkt-rE}8n}jnDo0Gk_)&JBq-1^?^?7giR-7I`|=raukiYW7qjou z<;7lMw}~%i-=*^p>J^TE_QmYG^y!p6!e;ee%Dzh--`hQmI^m`4yL4H_ZsEc&U&_8q ziw@p3ynpe_*>~xjg+0T-uCHX@rCB|94%;q&CHpSzG@(a0dGfUEyL9`^9m2C?U(LQt zZ8zRN+_B?p*>`E~(IGrh{q^j-bljXIy&L!S?7Q^h3Ee~Wfzz|^(zLGIhB+Th&%R6R zcIg%-44m;V-=+L_nD3QsLb~nnKW)xp{_;DCi-@Cpp!mn($TexNDl8i^*vsdV_$|o6jJFa(V zvvQRw$UJpe_N!aHvjWZtA z;JZSL6B}lH)R?adjXOuas^{m0-tTOjrBD3xM}_XgBlrL7qQa(cZIq?IdBTT<6`dpB z*8KfK{qr`=(pyZKSLprf1{tqEU|wO$+K~@gGOzHLeb&#?tBrcU(C&uyGXC+C4+|qd zTQ}oRc3fO&**Eg;gFY_YGqpjM-n#L!!pj39FJHE1IN{B;vh*)bZXYgd_K&Ph4tRC* zaOA<&V?LX19{PpVGQRub%|gQ(u}vnf-8ziCEw)M5x0;3xS6?HO8D4M0FtzcT8IPX5 zRhY6@Z2!yN*eYzWLF6WnY!%wfTalHu#<;D*jrT@=ZKth5t_GBWiXa8_jMzvlSJJlCpMN9K7=ryZ21eawe;Gk@CCa%pGlL;G7#`o;QpnN~MU zZWiCMUGAtG8eS6l<}P(Z=M|CfKP}aN_l@soopWo4uO5uN%igPpg+D}o^5dFeuR?sE zcRQ#?*yD)E^PX5Wj5;rJdd3<)zdZ8a_ODh>zv{?;6qLVn;I{?yx%Sep3+7*c)2|Aa zJ9Vos3f5=gGs_Cr^ZNHcFIfMot3NOJT%`B;TO2#cciAH{`CPj=jwAB_(`At<_uL&L zQ=dkwMW&w3-iqUk`mcDrG}hARI{AUfJg@1rgYvYG`Ot3WPkUM}?QDH$f9pxVSpNyD zZ53wEjAh;VZKu$2S>&#>JB2&fi1lnesZ%(*b>ziIbPA6bBA?Q*Q<%AT}$6u%fHZZi*h~_XLcy(zxg>G%H@8x zV~28mX4mgfuIEu-ZCz0yme%rtFmKcp4W8RL3!H8d}ufGr#&r~cD6pWzxAYFtpCC+YmO7Ja}fCa{B3qv?9 zUh8r_*LtRPx&E6x-n#r;q)$C6)*1OeeIt|4MO`D4|MtxzQ*Ntzk*Uv{-^cMtJ*R&j znfjl&Br?zS?ZU`Buj#ad^0bfn&~D~Wds;5-Y<*~d>q);@|F{0!Djcv~oUcE=s#UoE zfXHJBDr|FSvvRpx&1qV$PmBASmh1W8 zqH@^g`1t7R+~`O9iWCZCr+iQi}PKfSb8q1@q5$8_qm?n9BO=i0YNrv4A# z6q)Dhc0**I*L2!JdD_Q(XgBkxJuR1Zwm!7K^`u{{|A_5(2|aH6G@EBn>9R}sXjbGp z8|@O_ZSYx^{>|c^;ow~&SKiSxd^aj`?}0r-r<)=-|90o_dNFd{D|Qa=ycN0qCOd}- z3nI^cc&9LKY2-_G+^L*?|I8j``Rk7AQO@V6wR@EF|8dHW<#L}sZO3wb9@uloay_@} zxMR8g12)~U{9L3@JR&|9^7n2XnS7d8k4*j-&4}w;%I$Y|Wa=~dg2>eK-s2)u|1S@U z%ya!XI5N*`I_;o5?PET)oB7k8mP7sJi;S;4 zv=FX6Jn~uF6hg}zBk#N-36H-V`R%_Z;qxyd-?M8HE?f7@?6+6V?;fsgANkRAU$Ia3 z$cL`dJ?y-Fp8ax|W}d^!=WS&xriU3nP=y+yRlvf44S~DYt&L$kgYA)K3T9gnEvAAu{!U=&{H= z*Aov%=6Ox09h9ei%!hU}f7;V>X=m$0`&&=?h5C2??6I;w1*>I?8EC4B)_Ux3vY zVD$x9eF0VQk`#6s$f4t53n| zQ?U9JtUd*+Pr>R_u=*6NK4m)ki1O$uu=*6NJ_V~!!Rk}6`V_1_1@m0!Q?U9JtUd*+ zPr>R_u=*6NJ_V~!W%4C`3Ra(j)u&+fDOi09R-b~^r(pFdSbYjspMuq=VD%|jeF|2e zg4L&B^(k0=3Ra(j)u&+fDbvwMlt)j2)u&+fDOi09R-b~^r(pFdSbYjspMuq=VD%|j zeF|2eg4L&B^(k0=3Ra(j)u&+fDOi09R-b~^r(pFdSbYjspMuq=VD%|jeF|2eg4L&B z^(k0=3Ra(j)u&+fDbvwMlt)j2)u&+fDOi09R-b~^r(pFdSbYjspMuq=VD%|jeF|2e zg4L&B^(k0=3Ra(j)u&+fDOi09R-b~^r(pFdSbYjspMuq=VD%|jeF|2eg4L&B^(k0= z3Ra(j)u&+fDbvwMlt)j2)u&+fDOi09R-b~^r(pFdSbYjspMuq=VD%|jeF|2eg4L&B z^(k0=3Ra(j)u&+fDOi09R-b~^r(pFdSbYjspMuq=VD%|jeF|2eg4L&B^(k0=3Ra(j z)u&+fDbvwMlt)j2)u&+fDOi09R-b~^r(pFdSbYjspMuq=VD%|jeF|2eg4L&B^(k0= z3Ra(j)u&+fDOi09R-b~^r(pFdSbYjspMuq=VD%|jeF|2eg4L&B^(k0=3Ra(j)u&+f zDbv+Q)Tc;SpMuq=VD%|jeF|2eg4L&B^(k0=3Ra(j)u&+fDOi09R-b~^r(pFdbUN4b zu_gVb}Ap>v`DqJnVWNc0CWfo`+q}!>;FH*YmLJdD!*5 z>7FnAr=O45U-V<1?K{%#JJ`O1?K{}MgY7%mzJu*M*uI19JJ`O1?K{}MgY7%mzJu*M z*uI19JJWwJx|sdNJLx_HoY${S=h;n1#_uZZcNO-#3j1A!{jS1(S7E=au-{eK?<(wf z752Ld`(1_ouEKs-VZW=e-&NS}D(rU^_Pc8O?_r;cXR*KN$6sRm5gGdtwjW{p5w;&; z`w_MuVfzubA7T3uwjW{p5w;&;`w_MuVfzubA7T5^^xw<;==zgBb^Qsu{)AnB!mdAI z*PpQKPuTS*?D`XS{RzANgk68au0LVdpRnss*!3su`V)5j3A_F@-Tm9Be_tey_5r^D*$uzEVIo(`+0!|Lgglk0I;@@!tEa>2>9Bgb z>7E<@r=NS;U%ZFE#P%aH_9JXR!uBI)hy51bN%u2h_cLMlGhz2LVfQm(_cLMlGhz2LVfQm(_cLMlGhz2LVfQm( z_cLMlGhz2LVfQm(_cLMlGfmgN;y>L!#Qx$v{3W&@k+C0P`w_MuVfzubA7T3uwjW{p z5w;&;`w_MuVfzubA7T3uwjW{p5w;&q|2^zW^G5*z>U34?HqUqw0(lL zeS)=pg0+2uwS9uMeS)=pg0+2uwS9uMeS)=pg0+2uwS9uMeS+PC<=x1$^(Wo>!`2_R z{;>6jtv_u2Ve1cDf7trN)*rV1u=R(nKdikO&mxm<{YlTWGNk{K-J0on8TglM-b_bE z+c{XnIEf8~?+=aP~4w?ECt{e048 zd&55mVbBth;lxQ#`Z4f-*S&`<#KOX z(xzOWSKn?_uIGg(tXHmo{}uJi&qex^V>@T%BLCRJjWQ;m%U7$GG5IIkP47-SQ0~L; z-I+1SM&aAm+a|pqYgffP`S5F7 zC2y_YHsk%i+dP?c=_VNuc&bgZW%uS8uivdz^5iy+GG6uMW=X}L*U$LEiH(!fFI_w1 zogZwNJl(8L#^a}KoLoJ6)r`M=e&gi1<5yNvR=ueWlg9Nv&UoN6jg!@C&CU3}_t&$nnu3L3Z$~&LdJn2$@t*UENe(0&DN$W1PtIke&y~RzE z$*oqc+BxOfpEpV7{;;xgZko^N_nIazzxGMxfRy{+(LCAx$N80ar{xYiqgk^4YVTI= zc5Yh#t6L=d*PK<`#`1q#DIj6hbi+b2c-G*yr*$8@rWgrgHxHtw=_x4-}aNr zhf|qWuQf|fy!XS(lTw*Ac4?fveEr9j2c|O9mNiOtfBmz{5h?et+a!7WPhV6{OXV+G z*fcr!&r2)+mdc-bUejc~+diqBo^qcP8zpmhTTwYOm4D*C#>o!PtgQSXmA|t~)8yv+ zKCk>Zm1)?kQ8MkKm6b=OGGBITlsxj<_m#({Jm%uY$wPIkRehbx-#n#BGJg7s%En*S zD2%zTNwRd&%F3-$p1*mcq#|)UG-um08xL zX)=3Ct*V>T^y80cnrypM?W#LdetnOoN#FC%&jew#eFu&%3VCERkFuN8&s{E{`QUOEtB(JShwn~G|x9qY?XXa zbK~q;I$h8@dFl$Tkb-)#El2HpA zWof+= z>Zr61bKhv2JlVck6@9n!>g|%}cWqupU$4=2^W=%1&8v7fs`cG0dGqkbRlB9~+aB32 z>2zk3s;yJL{IboHTQ+0 z`c3O9-v3!GIw!ZC-nxo0^4{qklf(MAteTw4ym;2u$>`#yRg9Mw?Y2%T2cXaaCQC+g{A@j%vhjh>Q`G|*EzkJWXtVpgMzisyI<+rpA3Uj?{z&W5N!tgusoElaMr6j{mSntIMMXLN z*F5{ePx~Yjiz_Pzr{BqQ#`aGZPkN)GD&=n<*+2Q=iH9q`N%`Wj!;&e_Uth7-l{E@A z?l~l>e$fRL)l(kb_^4#ifHNvyO=W7{cS7>vm8Vsll=2ymoRoa`)L9iBQ{Lv`Q5Y44y!_jvlKaOe86S1TsHFPLLdNgCF*@mR)8LBT)Ayt> zbxiVHld~(n_@YMPvl+dTCJm}rj!M&8-@9kh;EtM=ZPWMmvR%d`Z~tXf#qMc)K7H<= zk`3=Tx?*_BOIMCcK4>?vV((PG?g=L*z4kt$Vr-iJ_M#J$dFS@8;9Y%n{gaYYA3m+3 zdHU|X-{^$oj7RpV*f&kDx%Q~!q9rF+?2)F|U*p8&g&W3H3`=?HxMPyzuG*)9Z}_7t zk4>H(dU(a9X`Wx~dwjBBpV1Y^r!qIbcvNzIhyE3ewZ_$tOfLI&V8y{H&%6GpWa#rp zR6LlcxUs$$;6{>sQ3c;6+@Dt$K6=LcWM63`z1TpySajSA!)X6 zGU3NNDo#py)$R6A`fhM{#j5GI_o3AXB}adESH+-I{*s&aPwxKofr{ZNKeW|;$>A41 zR&hYeFK^dBxv2N!S>0M3G%#siv!deLw5&^(?vvCV^mN6TG|wiN4@eeWJGJ7#RQ{Q3 z`X-Mzd?hREwrBb!(>uRhv07SI-97s!4{tj?lj*Z&zvQm7->vAI%6HtTPqOIkc@@W} z`E0*K-(=-Qb1J?}^FLw5p2;_-e3X@2Sfx+WbmsDkZ_@PI&+eUkfA1$1z0%+Id$3P( z!PKuSdZs-0^WMq)LsqN&l;1vbe9~d+;T7km{MK&ABq!7zS#fj9b><(DG{5KQibqra z(;0^)AKiRX#VaYF(f;71#|dXu%uf08B?l%mx4o!hY09TQF(lco+0|KJeDUA`$yv2- zt@tiY@AvY)$)|5TSn*@ZW9kh^o<02OjJFxPPZB20toS}nKe*xE$<=2qu3)Yoc$qyR-Yb5zFlp1H zcDCO8r0&9GmnLz&*SG4!G&DMLz)%+m&__2+$_1?o@%}ZwN+@y;2-ngsgBzJUd zQN?<1pJneQZw%k0iuGRpoBT`P?McTjEU&REK3bIQQzx!tS6#9=d1<}4zFl$HlH{H< ze?^>V#_Bv~x^PHS{&3?c4oQ6X+V6G?lGjvcbG_@4G>d3a6>=3+qjD63| ztBoG=s##Gj-2E>2_HgGK2&aNqT`$$Z^%0uLtEQW4z*$4Ev1f2Kw9*o6{O)=wJbNg{ z&>Z(N7#k$U;)@Yw&?`%fzgv2j!+@V+yq1eAhsrNvd{ioEpnBhH%Bl=rCTKo7$%scty%?qo4|O3 zwO@I<0u)wvNaeiRvTqewjuZ^DcUBcRyP2hOUfnwEDg3?JJeBk6kcuj}(pfN1&*jfx zowi`4m;TS7=Uc&4ZUL1rW|vti=hc~dRge~8n#y@~Z`5;eKlq!$LY_lFh+wuI@m0{^ zWs=HyH9_|Ue4Hwn?ZD<2;L}nt-YV}G@cxrN@@nrB&p_MS2zhmm^>fJjAeim`%4!%s zS#aZ>0o4%KU$Eu<{m@t?RE-w4ckx)ok9cy8+NOMS;cC|s|C|o4yT*o+ zn47rYtc9{oVlLyosTSl7eo1^>NDr(9d%5ot=T-Z$bx=|x=058FweV~BYl-vf(|>9~ zv;MQhdG&yO9W{e_g{#ol?PR zcmT34tjmCG&GpE-AJeZv{EIMTU7cswp?}Za$huX) z+3y@BMh3ZKm9WFVBvo$gws%uik_M-7luhVQqq2+yrNrQz=tf zyyrt6q&x3T>BHKX<>Y{ChtL#97T;0GhPr=Or`%)LDxGFSzuR+C_}tlb@-@V0tP z%1pMs_vB0%SG*>rh~1-|h3POZ@UN8VZ2QyL3|QD=QOa@FzC0oWuCTcS?@!9kq{Hcj zt5S}zxU*s!%yJ!*GMTkEeahk;3sUy7_U}5T!i8>QQ^v6E{hU(a#QMc4-fa6V)xg*NVMQU)1fYPK}sTv*RcPc z6Sy!XjKwA&_eozLG!Z@@OjxyFY8uu=_#7~<-65%qX(Q&zPj8QtKDJc`&XA6y;-v8d zG=Vc@Q=fg(=E-`%88TvhwDhZMJK#A(hj!Z~^&}JEIm2NcA|;cw4uCnst3i^DgEjD+ z;a_In(%66PfaeTvWlxr-{B#7)kdF8JNuR+5I73!kca$C`x&mj&9@=fB%O;(GA19A% z`ga9BZ{@M}JU8ISyrAl^lvv&Zw_k}qEOj`eiE+SR2c?9mtuVgs5HDF52u&e~#7OCn z%y9dq=xx%{$(9)VO^cA86FZFGY+oY{o#BLWt;K9)9E2uEx2rixlwH4fuSyuN;wb`*nh7 z)@Iu$N9opQSKxV@#WB4lYvKl+6{qwaARYB`1fV1N5wce7Bx)bnut45`dq%Q9O{2j@8I8#~>>j<0`{eG;JZd*G7 z&ux~BTPG=cH~^o+UNBoPow2e5p4;5FZ;52l+5vcOv$DurN~ZR}c}b}_SZe6X@_MX& z!JH5&&%_3JZZn~JrQ|)y4tQ=;v45CkY+(z$@3p%ZAocLE0iN3&V;w9NEwu)o+no72 zLONb=2|Tx{QN30AC~uB&@_?Pv!?C8g&w`V?r6vtC;C<}tzI&v{@h14cHT|NcuA7Yj zbDQV4OXn&~;5ggoZp(dA$$3LOmq#Tr(z6ro@Z2|c*(q%bHO6CDw>Va6;c9^AJ}Ej* z`s;)~UMoZSSgGh-8@#p&Z+A;q(hcxjW?Sx&zK?2$=YBCdUYf9}HQozIj+6d9s0W-C zclL~t&OB|))*xVW{KW~9{#QM`cLo**q^7AY@m}9<+An!T=-{&&6-c_vEZI%?yy^!MF(DQ<=)a8?Y7i>za~oacdFp?zpZ706s)L>?}(en zeyJv19eCefQIaU7ylH{&%dYYJrLqJS;H(%&*zvbi#&=|@U%d3{o&vsWw~JhftdHWc ztY6}B^Zu%NENj!ef15bpjvPL79(A0sww;LIywj*RMTT`DL)V=|y{UP>eMsI*3OE{$ zeRyo=7Sg*BojrL!si&#s(QA%5w*Rlb-F$QKRhue%{I8AsTS*I)TY2(+bzuJhY4hn2 z?Em{8T_K&%4kMgJ9|fyP9Vgp)^4Mq5e)o&v77~xMt~!KME#?-nd|VYT8zEu)zW2dCT^Z5$~-r z*2*|UhFf&N_^{?FQgh4*?SkH450(tUh8&<;My39Na6O{PU|l1hV!8edEc^F=oK?rIw50NYaJ& zu!O~?1NRY|JWJrrlcBqh#AS7aO|1RqdHYDRZU^vVZ9-n{A^ml&aUAJ5dpFrJ)&}2G z*X_H>=l)i(i?!e37)@sFwSXwre$30Aq(h-4>|k-O!Zz|ivcvZ25!=YOGd2*z+Q+Wl zP8#K`A%?Yi(PJ}dDz?Wq1*0N~S(O9ECwfJZ?f2|pA8Q}IW)nH#YzzBY`<;(Bl7XG= zAfCl5+(XH;J5G3PDr>{Y(Et z`05NB*>6pi7m^V^onRchhSqV5N!WE~@M7)T*vukVes#ioXYy#4?*wyM{B%(% zNwJT{K5f*IGSX_r9_$+*CRCAzF^or9-xV?A9oOu1cI&xA#9u(%+;?oL6Vej3<%TG9=EcW88L-9%-2p=hfhEVdPqMhQxU_ z_0Un(gWpE=-81|PhLTKv_4-AU_jXHkp4Eya)-H?B*ZSG~F= z5N`z$hu(-M`Teg+oLAqBk0JByvLw!{jr)&~4Qbif{=&L=Qu0rx#Cdi8mc!(YXNJUi zb;yb*q;zpS{@1F+N2FhIEdE!e8jxE{&Z8DzwX8pRU~*aF_q}9VA9BPi3AOlx{|+R< zF3G6H4;nv;ESPgu;=EemJCH~_FQOLTaoHF$baEzGAlY6wRna7i^-$e zS*XRg{l|xxUCux)e*3FgWcb4r)Z#PCyvgxt*HDYkxA!Br9FBYUqP7lDR!o;=CI4VGD_Bx-M~E zEpgsK*7wPlIIkAhZXk<4W=fn_le_L9SJiVR&Z}ozZ6)1iWJ#P?``Paxj}~P~oL3hI z#E@WxY>D&gvmb|vv1%5^Yg(Qn6Gvy@KHt`yB9FdiNt{=!f1M?^uQKs}FDqUk8y(Xm z&a3|hpCq%lrb(Pv+iG4RifhyHT%v9z5#_xpc<$T1&XCL7Qt=qp$S0FS25ETiPwFL- zzfZzzRXa6}XvZeuwM})pMD%*6;JIx0d4<@#zl!JnY)ck-G2$xTi_^*1NL9B>nA>bj zOD1j+NfPJPOG9!-7bUln12a#n=xmz$e@cC zFt<5hKcD!Aox^9T)scKsHS84THh*=^A(Ly)VQy1C@(wvU?hHPAyV6`JLcRbzdoM8+@|jQ2c)p~QGEX2k9|Po8WZsyQ9N8g<`x{o z+~&=YN90+`A$(t=YKlpG_d}T5tgE?4RzE&~@5o5&65?0NIhf4{PwGJItoP2Vy)S7UTcoz1+30$h7Ea+`spw9Ade? z3}d}dx#a4ma^%VR;cv(a#Tbl-o-$ybfwE-&zv|BV?E8LalKH&8xMf=a!@bFzY5$l0 z|9?5J*y>hrXjgl}nXr9-eR%Rkjc_JBDj9%w`{$mV2|IQ%g1g_&dU7UoJ7feyy;gd1 zCfulI1X+eUo}3Bo7a2g9jim=?!h+ZOFm(T(tDFg&AM<~mSKs;itlrrcui-~mBeJvoaO?=XU>78ahIMLYL3g(*W8dh(ox;viG-2o3h+bH+tg#_*;5A5YGr zQjHPF?;G#QS#^8DUxub2H!K0$N8U4rydgV0Ig7shYy^Kd9I3(=1~+*Q*BG=sYljkdGhme0M4u!DZ_go}5K9HW`B9 z_=ldHMML!sVY0z{s!uqJF6q#g)h${P&Y~~Bw1zvKI}*;Kcg)&AVWtt`Ec(r*HEbZ} zgtO?G3O$H#=R`P*&U|eMqtga^a2B<=YXs{p3q3fC#(A@AJIlnAvuKMu#w`E;mnUb@ zt>smzEdj3zg8Q;c%w(2oJFs!G=$dk|Mlc78raDI z8vI%i&Z6f|>%)WmmV`4&OhX$OwAX}i79F6iOJ(!%0sVBTY@TkHsY_+^cayu?bg=G4 zWYJ%~TJ)nzGO}ok7MgUz*feC((IM(I{B;JhsKPH*x;Y~gS=4Q%3SE;fShVyzy9X~) zkwr&uQKAh)t|E)(6GggA{{ph8pNayFT5tkcH1eAq&7XY$S+ui(9F;M%?VLuCaq_K$ zO(5fE?^!xDS5+{fWwjRdjuEVAGF+3c{LPSEkE+vywt_7OeN&}*+JZS3(U|kfG^=w4vgl2FRXR9V@anbYDl}`M zV9~$aRp}y|EM(EbCpvWAF~PkH0(I!CUxIsk^^&9Y_r&=4AVrRzeJ{q@mMi3_+gUNT zF1;#8hj$TUv3^f^+V+|lyPwp_(Rl@8oXs2{Pc!6CA&XiT$PZUAJYYI_@9%fB>fn&X!o!3w0-pnWYP7Z3Uqa(;FDHb zigcUxC1lY>y%p#`pHCr+rk5(v*4~0=^gAiiy*&i~I9*kwKcWOL#gr>hy@%(JMQ1rF z(!UN~Ko*UwQKTlD1YdDYp< z>yU;l+TB5k4qTmtEc$nd5_PE-JeD(yz2{Ye2`5*zpl1gOZv0xVM6J3Ce%q1Tf>yuH zLKgMg)q-kA2o5x3<5qom8nWougUU2tUhwBAH&wb;PH^c=_8z_c&9@7Gs#1H6Tx8Mv zv(@Mr`CMetEqQA6p1y?_gP^UI*{>3@`VUY%1)?dsEUKnfA z6YL%5xznVV>eSFE6IryXizW?TAm$OTVl?UWrDEQ(vs{y2OB3^yJ*PBi$NY3;(Mg(` z^yK$6WYM)#wdgzxF|U~(qea&YlaNL27qNY6r6G%Eq-#;N`(hrn)HHET_6!--ya`q^}!0Qd#cQBFm1-a;j_BzW&48!9j2SaQN*nZ~pLk z^Xssic|~NrcWZp@9}di`uld7=>zH3c#*I0pwSRbWPUreRoJkED{_y92UH^zltS*J7_~VCr1~)f`e-Xm)cvsfyOJ&g!Ah4oAsbF3Xo%SOJBmvl?ut6 zSKn@b4VN`t2Kv9S%HU2j1+ug3Iy z4P}2>6V9uDn>2v=Yg59X&x^-jK}KGC!g*Di_6pJ#n-I>c4PDvVi6MH(Jm>5hpl4BQ z!g*EeWdrQGpielj=HIP{2}3jq=T&W=df1ZF0-5Uite5cpfhys=3Pug^*+G+VUTsK! z370^ba9(vSs)I9`?~vcRvFoOz{}p+)aNbKet|&)1ubOYFg8^R8k@udBtOJ$p50EFL zo$En$Sq1WH#)Eo@hFauR-#zTQ?I=ZF4g63G$0sCXd)3@JaGjEkyqY?r9%^S4Ag?aE zR||ueoy0bIQY|ddio$@79YbFIpi>X=qb?$^`hBQ_$HqsHS1pd$LQmX=f6!NO^(>j>HY7g>i>gifgo;w@coMHPdAsSIF|6!o%3oh z_j(wwyWWHIYDl|!cyr=NH_odkv+7}xW`B3it4m+jgTg=79-LPnxxR$(cH!=vS1Xph z1mCyqk~y!QXU|?{o+079>XrQxyq{?k&Z|?@UP6Pv0^z(mo4r$uCN?0idVj8ii{Fco zS69T>K}O?cWYmyFb>P2!FUG->m`6*?A9=O$AJ(Sj0OZw0hwET!pspw9)$WaTux`?2 z56-JESJlH`@%kQ|S9c^?Q2*Z=`nA4RbOzJbxu&0(YfT3b7u59Sy4up3ua2ncAB(i3 zX$^L$>Ceuzr^76)QPWo_aG=Pe(DyrRb)v2XLic|>%$fGf5qkrR!pepx;H{fHr1N~7iwEo~p4m6KiqSl`l zX-OLrgs5B=pBq^PTC5pDi$FekseD9<3GHW$1Nhsv9M=&c7Br z)0cKa8-3&GOheU$j_J+Xx4y5A8pns}&a`-}CTjiLT%GC1Ju0a6A4qnlhkb?KD$mY+ ztG>`@AM|&oGfWksPzX#I@8Ich5p;e)S3E5>!H>^j$OC9 zd@a=a&-*yj&J98@CKH|M$N-@)N7Opej)#OEef+x<4Jp$_tzVms=?c^JQ0wyO#uM2E9^ zEYF=zTNW{zgA18goJD z&4tfl{Wd%LTv7NUCTZBwb%%wIBB$1l`i&93g^j!I=!kB@=aBuxmg*c7zKe_FY^l7d zGiv>P`qT3yK$C@}BsytKpK$N0w>7{5#)cX5$x21;$ zIic1cFv*72^$@<1edX3Pe5osH{dLc6XxbYm)cS9Hv8JE0h0o-{c5AxC!wogQZ|$sU za9`nFDYCPnOIo_1);}zt?Ps$KYW-KQThZ-bgx6)=NGtlOLik}47F*MTUoNQi-)AV(gYEzlk-~507>l&KfW4c170qXTj6IAGcKr__q>kq2Zf6iKQ2`&=D5aBe5yzR=fysnZYnjqX%i`1lX=Rj?cx_lXVO ztwYZYa06af;`>6IUYBI}T5=KOSRI{IuU!1|PV+H{SHIOcSH9oo;a z6Le?$xB09^>#w_E`#HO{sdlw1a9^m)SZx}U=R1=-x(0;J(mz-8AR~4@a2F;&fki`metOa9^mRff^k@#0I!8bl-ASdRDT8d+b{2 zd8pEFx2({2r2I;SD*IRh_l2(7qe_1?SpfHiDvea7jaNH@9E-2AoYL9E4#0h(^PZ{D zv^E`q`$E?nt5B`Z=D>ZSjrl5ciHSLIU#MdRd-u;VF9h5Ec_w=o#;Gu6ToW7e;5Myh5i%8uH!^Q;J(l# z*5=wGBjCQ!6PZl^e$DdoEKYG}?}Y=)>9aOlK4?*6c3-$J^eVglH7i_!`$D^p(xmN~ zH-P&>TWw(1{IwH~1^sPRX}~`gP{@A!nY~kABy-@t(0f)YRH`%u?hD;1DbtQD@63In zyszjNvjn+|$0mNu(9gr;)7QMv&%>E5V*YmY-jp*&>MOqm<0A$xR4FDBW3yt$06ilx z9yrvQ2C0Q&+ zFHS7QxaSfp_I=lXFy=fN{e7D_Ha7R)WxO4axrKo<-S=WMvhD-Mq6_jPk#(IJqu$Ai zK-Ntd%YJ)56j}H3aYwqfbuhB-w_6T0d|LqeS983M|$f*AhP0E z#%8zTw&H(9GQJA)-HQL!HpG(J99)K8qwB-1XuO;kvZBIdD|$bEDf);Kv#scf+NJ0@ zxzyI0&e`jQUJlj%Y`#$Mg`T(mTdk?$;bq8*pGw*I`;RxWVvl21bgrW}vZCfE*2d5a zy?Ke_ZRnObFZA-o?zN$cYnG$;&uyVKO{w%oR=jf4nr<1f99i+2ku4oq=#5^%)G@a7 zb(#;dqJfPKb;@6ktf;fbmj1hTIlki;9^2B6?mp;6oTq9>2X*m9@1k0j4Sn$12U&44 zv86M%uRvB@yV;H!JzRla$8(qLsQJ^C_>LIww53^ne32FB)!5N#SAEeN=?M1J`shmR z15b{(r)!h_kQEp7w4*BdE0Gn`cGyv`#8v2xEUL7pJ&*gLKXbtcdpi5t8uW0gRol_z z5I^)%E^~IE+NrCt?`;!kPa77kK~Lu1+xB$QvbD&HlS3S6;OBM7ilc%ZsnOCvjE}x` zq$hHMaG$o|MB6S5!ajD`QYUKLJ{bRZ@dzjS-6jNC@nxzbO_K{oR-DOr*fu%@&*kL- zCwgdaD4zR_*N$|=>0msD9v_|Pj&Y%Q?)%ug^U5#`uhqR8Cwf{x9Ix%czD_hnHx$oh z@**eNE-w_%{m2CNejN|Td-2G`nVRg6KvulQ-uLbSVc6&QVw|t;6M^@x6Pp+8?zsW) z^>H?j_-4NmpN(bgIA47WM^-%a!ij!MjzCs?ciNdQtk{Up(swpb8ITc)tT>&`3m&f7 zfUJ0o%~M>?M&h%#iOp-u0-}%=*Rr{f_SjAMJojhsg_cqzvf@-WPieRriL98+=1NtT zoALRtV)LmnZ#LsQ@{rAI61PTS-`>FXdG+gNd|$4y`O#6c&B%%!ot&v(E&DC&tDmrW znOWFYeAhT{gt9)9^BCuilRnFkwRqgTk8K|RU;QoDmC`3QVqeE|k{<^B!v2ltGv^on z#D1@NAINi#kz&tZBluEqc2xy@(e3NYq5&kH%{ zFy=W-+aBk@nT;1bx7j%^A7h^L)C^>GjBNY=a_&5hg0h{+g=@reYm~43Uw%FV=>#O zuAT~Qbv_t)%{#GU>|`H^@7j;WDsn)mPPROr@zL2#P2w@+sA z?m*x*@4J4f(2MQ-f!DlyDXCI*od8Hkqu<-LtAABzZzYkwFX;m{>wF2lkQ#Ug}j{8wSas+Qq@O|R3W-7a|puX)dt)1ot? zmSY>e1zJ>7b2;#u_pPn8=_|!$;LVQn5Yv77r+ERdc~1z`rn4@H=TL2jHZ9cg!a0R; zH*H$e+Z%Yz`|5aYdiApx@S1m@B|7x$p=CHX`NigFGvb5MtLfKUg_c+Z0k3(F&QPHX z(gGlf#g_)F(#!|`z-!(eo~u&hscWH}#Zx2HXrTUTc*$cAb-G=772b<3AJu7tt1tXu z+qWcX&~5vCfY-dc1!+>Fe#EZ!tsb}KuXdVe8;)2JyGi` zzSmqc8hQOIzMKBv<*3=v@5q5pY6|r7=AX!cZM!Sd1*;p81J$=HQ7=U~%6*~bzu5W_ zyW}YMh0a>7LMOkIWAhT`g_BdG7j)z)&v~v7SEtz@<=FZqtS?c~q>B&8QC`Q?&rgeP z)|aC^=egpZHr2e)h#c6wul}$8yq&!q{T%ZHk9ok~Oh;}j`g}O9KttJiat&SAOo*|CZ@9hX5gi&aq!Guv15Mg= zW49(8H!ry8(DnIEI9Bd@q)m-X*)?I$q5UZKTq(&>?#<})RGapF(1_#aX)|rQGgyvt zf6j${T6EHMIeL+`Dc-0}?R&6&vVOxdi)oSPdm1!(nmpw-M~fzD(2Dl*^b2cWyF`<&*&|1J%~2N}P1@xO^9QhagNg>V zh>~aPXDHKlJJqSg_QO4#k!Llie~}#JHAjCXsMEYydCEPU``y)1SJ-b^e7dVDeKJm-c3|y2m=5mBt^@aW4v<%)VV3fgdppPH zsnB*uMMW9`KL z4NFvL&sOr3=SGy6kL6Gcd3u$_WsYne7WPc@;|X}dYGt3XYsmH=)`qob?-6f*_ht)f z)lIbdFqidTZN&L{Sh2A!PL6W#sQllo-Y=K=Ggy09<}KDgAxF87)bX$qjm(q7>p69a z5*;!`4zK^ZJuPUjjdFOt0sWO|k9~4@{e9{cX~-fuykB=y6sf_ZChSihS1QqAJ>~Fv znuaUUk!|Jh`d{p@BHU&yybPZj7X z+eYNu5xeB6T-Yz<+j)cJY3RqF$hYfz$y4_iKag+7^i`nOTz?_o{`w|Q$DIC&e0w@s zj^51tfy_`W$dRE`AlTjsJHddIz1cNwV+cyta_J=?Aq@~9Yl7% zh3vX_U_JC$S%B<%Q=ffP?{E>a>#B!LBaXO>?ArX8|LeTCj&CZZ;`wrYKjTdX#$5L| znwyO=_XDJ>eFy{V&hu(KE=Dq@J<+~W4zfliu=iNhg4eHPUYs2ngO_N6P zE9jIV;dYbM*U+#$6>FMCZ+i*3i|%1fQ|7OFm}PYrpAEIH_3*0oU94%^8&?mBj>TBh z^jWDMhVCo|uFGGKdI>Ir?_y1pVoDvnPAS4?@3`Gdup3{DHBF|C^{~IZ2y2>@dep&5 zxk7w~mok0UIJ6LJnr5XiotmxJ$#wa`x^-~c>JBn+r}|pB*tY=dZhWuSL7U0~tZ6bB zQ4dKg?jR4xSu*YZNCDO~ZMed8?X|ZtUl+Bi4uWm+v8KtFc^>Ku^RcF>-^p4?iMxgT zTz;$;t|i^XckuY+IsZrt#ikzC+U8eD_)#|_fCE5O9)+?i8W2SO-w^SoQX9}d9xbe z)AJ1Ax_or^1~^-phI5}6vl}4gV>;F}*`_wYbn7&%X<9hy6|C97-a$4lucEKu$I5i9 zX?k|)6&$*ehBZy9Q(uF;V=C4(of%sX`z97)P1CR!b+G>89js~6W$T%IQ!2okrYUpl zp!2BPSkn~EH1{ccZ(_gN(TA<0@+=SYx6{tCwMravF|K4DiRu11Skn};ja|2rYgp4{ z+W93s?wN(09R8VoGvZ1H_P5&~H9$V3V@(sU6_U;0dA+A>UeD`>Wb=KSL4%0RrAA~| zs~=N|8sk7-gMY%%mpn|Aqg5<^trt$DPl8<+58FY0GDhX>TC*mel)e@0dTi=R60=hd z+4W`06%rvY*wu7g7WsEYBjzx#e7i+fZTyKjOsfU=$iPA0kzKj>UdGtG-b%*Rybepo z+vRRONypy|dAi+r;_;g;EjD-&zu(MR@FSG;_|2kS7VRL<4Fscpxt&0=J_{C=9-k)8 zznRu*bPDl*FSvBv_v_?mI}tD4QA9qp5p2BqX$cAY&CJ{Vo{+sa1*3)?c|>k^5R9sP z#+^8q3Z`8&raRgCRxs@f`x2rvM~r2UramB9r^J}}E{fGt7>RLE-unSrkS4~>?9Rnx zU!@pl6W`n;OJ|8OaqX8P68i2ZzEfi_<&%J>pO_c@`nH&C{K@vop6Aq3Zea{MReMZ?wd$VWZF5|#Pa$hU8em>0F^ zz-mSue_>uUd|D3K8ztBy`%o77$rzZktBy|^8FNpt&BcMNjb$U|MQ2^hA}{weVqSE& zTq-%UK(Nr*sw8r7kYFcAhYT`Exe4>4iU!GKLyTaju@+az*Xx3{ii|FhiLr9Xt`YZ= z$_0gCr?Lu;`YmcrxQRyDm6#jI3wJ z$yu>*R047R&93roPhSl4#+4zi4~H$UbI?X9HCRdK#5-=fGI#`c_D6DRK`y1!YvU%wq> zhowBSYhdIC()om#3k01BBa8cqxkH@eRxtGTwv{UG@(0xx>CGex!sQGk+eg#QKm*)+cb^Y2MRd^3M-B%4?u% zG?x>?{+F|Bm;A-#3p+MGSGuxoKFK~S=2oi@tRY*9@mhPC_QdP-Wtvp;exBFn%W|;1W?z<@<+c2>ob7*&1-v$2mV@Or`?B0DujQBJ zY!)Nq-~2l8IwKh$^7YpH+8R8S(vWX6v)aIeXQ{}yx0kTB z>&w!RZ$oFag%6|CkZ&V(TEX5HX~?&&rt5>3UOGOX;|H_`lSgUDw}YOv2LIma$hWl) z2Cy<-Fw)e1`k*y71Nrt~ZX3w{mX3UD`N;rI%*{l;O}t7PI%X?t=-m^bmaO($N%pnBBnrEABCd*YgD5K4!H!KT>j$Z*N~Tf`OX_->w*F z3MsE{;yC-P%owIv-9)|(Ei-~G^KT&E_U~Z|)%k+YXR!UtT@*Y&imgYT@|bZrJN_T6 zw(Cku#_H^NCcQEO!x}axV)5HMMxc{<8~IlAk_il4E9MR!n~h=Ru6*R%HM2~>XZ#)H z+ugI+an3G4zD;g422&3)H+d>&49>moAm5H@V+6kJ8Rovz7Z(k|hOObn`F4Jj5v=%7 zgnSEjM)2w1Lgd@atUhjGZZY!hJXXV{vx&V6?3gRB8-T}wBIH}0ZU*pcelhZ`LPk6I zXnqg*b~1bROrq0~Z_8S>gS=Lm$hV3S2H>8Mg?#&&y;Dm)vypF0PqY83%t5}rKZ(`x zZ52#=C7a!g{x^_sud-UIBTYAvZ?jU3Aw20e@@?%1V^CjQfPC9~zY!cYEJVJoKV}Gz zGK-LJ`PwGFzdZvyHva7;;4#;{c;3>k%2B$>v~uo8b#3Y=JwLP@bF;diCQJQlS72^7 zY=pP8)Fc>xZ;LvDE_em&f^cVZ>lU!~@ zAm6HtjFTQ0MdwUK&tI8wBUr)IBDXc2;^JB&hda+B=W8HvIJ?(YM~uZ zij9|EpA}kju5zrTWGb}jqWD4g+pq8UNv$&@kZ)J)kCT?03oZM7Rg6@hAhhp= zcKaklxd`OjGM`vUbE?q3J)QSSo8p94zG7swq~jcdy8nm)G15O_VaT_CIqs22fzZBn zN9~bDSPA|8z?hwq-z}lhXMf!--E1qg^7hHQr8digQ1_ptyh|!b3qeoZ-0!-env?C^8UDghxkp>CH+A3t%Y8VloqcE0G^wDksKjCe!d2e zr@}8pGQ2H(3;HP=q`JKI*j}0#CTU$?jcvBo1WU>1h0o#L;PsMimLK{JmaGny&P1%k zWd9233^I%=L|M1>E8=uVStulZnZw%5%iQf2W< z%+3Dtogs}16uyzfz)4c8d%t}qi~o`={e>@ONQ+sL??7M7&Gzt{B8BZ7N18!DY<5!usT(d*h@f|N3BVc0+vmgAUy^CxyiQ-Hck{Y_nGW8Z19@G)EFa73 z{bhMtzCOVJ#fQAEUzU&M_5QLvEwAgB-4Uc1!%nE&g%`1({bKLB61O6C*b>siVC1ALt; znXiDae;bO(mLU(Tbr?v#R|;R*v*aNpe9uzkVa=%{iJKdH z7uY*8>e~onld}|gxZ!nQQgg`*dDui{9Jyk&40+f}aTsa*>4iM}xAG`5(~hmH&c+nW zhS}sb^Qv*(u=?#3((02J^6>Pt<4CIzZ{*<#QH#j04PMB@dZpo{gU+qZ2#@&uP6R{mSg_&LGntH3O>lg3zfad`%oX`Va>uI z@^zLEj(tC029g441v0Rty^a(;TY(I`&nJ+4KI)4M9OEBO-pyEve%Dirx06o0)?jSJ z*2A#3^hf^uyeNhwv{{Gy9C?2q*}T{vk0E5)ZgRPjaRNIwvrBu(!&U*vqGyIDkk|VI z@Vxf7k0oJq0+2;-jZ7qtV*`;z1M_1^eSZD&t$qPajZM<=mxE&8h7PZPeNXGXJMi#v_;y8(6z7bvnwYc~QDYzDbENY%{ zkPPq)K^8sle3(rA7J@7~Vd-&lazYrg=uPKwWLBgXvgpahv&qcG-pHae$9R#qTb3h> z4tltbM1Ax@7QIp*Lq>bAN4A{nu%ArO3q-cO^y>h5u|5dd^4++@B%vu7*^;ky{Bfuv z<@G_DY|Zw!#}p~op7=V+=64k-Uo(WSId59i3U%<%>N3crBEC@g6s}Ct!|j(AKZ8g8 zTVj0w+za^8LKovHY#r%u%mcw0b#GHGoG@a#K8sU7)&U97z&LtIJ-9qn!}!?(u6?i? ze%59@Tf6>@A6pBJ#TOfDq2aL-#(X{e?{#{3Z2a3LJ-W5RV-EQE1SXHvqnv@K?X3X! z;Fg%N*9=yXD55dzg5G>ZY-C~{@0nUnZLq=(xlysCzw)08N$!Q9H$t`9b3erFbM>s$*}-;^lN z!?ayj3wtLst(V31t=RTbme*%()Xi%^-Gyyu`%h)-jr&`&+Bnu`p*_HD(1>M zsMNui@2aT#Z&^|c^sWl({)qv#pxQ+hb^m|ZTI(*en6HTaR++8MKKDAS6JTt%BdQj3 znD3nH{?pjn?6J4iDA)Zn_cA@mO&xXWy~VX~X|p=!PFt|G)<;fNL)|}+t<64=-8-JU z%VYJDI~6og_rJNZ7ViJ8fx3CIPc3}ysE)b5`R;YlVu1$g{!3Ns;J_UX%tHoQF|Eo# z6LtR@S_=ww>ZpSs(XR!AK^mAlJ+iG93U_N#&X(uc_X{SLXrk`#`mzS*9@oI!Y4PA% zF#aamc>k<{uM@Pe{f!niuy}_S?ti~u4YZ%9iMi9YU29-)jwb5S zSGKHPon4<#+h0JopAKHn+=%Cp%<3rk_4ix<0@T-Q%o&bnyC5-S!;3O?B~p zoezEn$6R&s{=Q9o4!#|A@Ooage-697b@2L+T=fhhl6CQU*fqZj>aXcy?lkud+n%9= zxznZ3tAHrB#ODVFRRIiciO*Y!dnKd{YKhP1v_n-8Fj|-L+-Yz9Dj2s%7jvi4Eh-_e zuq8gvFFsYk`0Fh(cWMw?2?w6&V(v6>@>4L?*2Cxj?wJahK1dI9r)CGrLB5L~zEgjX zehLl~TVn3C<%J69v8yHKPN(-ThwfMO@E!b@l)=YnJ$z5Sv?^duK}*b?evd4J}I-p1Ly9mf0{PqOX*%elY$`wlck zRv~|y=;XskyQj#X&%AEJC;M{bPlGMF5E%Oe`LldwHe8P=MgBb4o#kvkl^}mk{+tS_ zFG`R<&EBU#7voaoPrk1Hw6Ie2Gw}8N-v>R$+yehjfkJHwdLHi5%ohTh1bD+}Rk&NKANM%$)!Ia$4}nbZAA`wPMdkbwV0kx=?~%*{yXMurcN_`gV%)GvVdg z$LN)P+mrzVhnJvNHeo;plqHp*S9YplCOpe6L9cApwrkMu>tpoFUb&hD0ih-6m7VoI z6BM78pjWnXQ8sM1DM7ES#`J73Dlb8Q?9c7jAjhf{{jo+fvf;znQuN1eev<>&MwEgJ z&nFn&fXt&$pdX9NPv3-%+se?J`sU|NsDJka{j0swZh`i)GW3+T^S=plO=aj)4RgB% zsjJG-r|RdJ4{t)s@m>r!z6~q4mZML#-Q#?C*roz~sv|>h!y&&4^q{T_EP&$k6}Zn$ zi}JzyUup-fdVBANi0O~!TqVM!n zk2}y~RVDhw_%}dhoH_E4Ijr+wYY8xp+QiqDzr;9nC*!NvEdNYYk>BcSOd&i+4f(Bi zwi(Y&9Q-qfr6_ue>uW|$%3~Z z7rB8}cfsNOo2oKyR}Sw6qk0O?oHyScCjREkApiET%tLVLpq(Ayw4dP83T=1D{yiRb zwe124d&IalenV%N#2B0NXM7tsFlPJV{Fyer6DV{QW97N+T|jxZ7}tjOcY&RQ^^iX& zUv-94xh;`Dr?NE$rn0e>^QTvX6Rgt_<8MNYBaA2(_oFHLROXN?R3R`e*A^4&DB^x*)3Ep@a zYXeW*1fPuC>j2Zsb&)^6t*{5ry}H788fXP2?FG-MZnpya7{Nb#*gEu~V|0-}*ZEn( zjY7dcYt~u7{I!CY3NBl)zF8aj)3d(~+{w~G{`@e+8h-c){%L!%1DF;H9_ygd5iSf8 z{MKfQ6@0N2yyX4B9OkWH^{DJRkJmDX90S2}?{=EQ;@yG|6%JZJ8uOiV-)Yd}j&Q|6 z8~L;MQ8Q>iMewBg*!JLCCit_&up^W|5WJ_XZU&=%3jTbu#uRk-ig?8+Gk9ez_;z`o zIkf30cydW6a~P8+_|tTg34AFQJbWSC6!a$uem;A$J#<+pcy*(L3Cvn7+E_5H^IHqS z+c&U$iAbhSSa|vv!gL=n=9rE5c&TY`|7AFx95EYq#Hp|5v0>D&YmsCRWEiYcDG&w zFab%yKrvBFP!YS}ya%ug8x&C#L2SwZB$VImIp1>^YyH+;>+|2Nz2@w*-+E@|nVG$< zpabqdCF+XLoNWmmos|CkIXp)-5V1n||JLnVfcJJ~JmQ~Z1yQ)ymB`&2uWkv!Q*_Ax zyy@KnF1st^m&he8VA2g`yfa9#dm-eNXPn)s4@*Zt3@K(i4_-?gSIk)(?T158sj>lI}Sea@HvQ6O+)vQ0Z0xq6dHUtRcW2=aK$^+e4ssLO%82H(oRp z?5p2W5B{Pr!(c=B8_EYgd_4@(Li4BxzchLnl#hN(J@|f|Mu7c~*W{-?-98ffPJT_k z*22*vq0JOLdk_7(=3hrZY-^=Y72!MztkBmI{rKAcV_@o#T*}v|nT&zDfv<^&?7DI^ zv~Tu?av~08W1(~QD_UpF+i}o)VlMUIZ+967b#|{o^x!9N9uG~==TZ;;#`6=vWZNt1 z!4EK<4qbb`q#k_R?X%zr`p=n&8$GRO!J?KqR0BW0U^b+byr3TZ^5R)Auk%al!8h15 z2Ttg|q#pdlCG+7$;tLQx_{Y@d!J*|j)Pujj%|htC^9A+bdlt-x0}pek2Y*M+BCtW9 zT=d}AO@tyhw|F5hb@Q9 zgD*hz;CJe_9Lz?bKacBo*|-$+#N1oIW{|%~bQud~GFD&EI&um!$gN`M58>YCVOv4Hc?&>h-ixsMh~xqLo5* zU1GdhTr`Mv3jG?b6q3a}&D4aUWFr;{K@S5%*0szqp^O{}uOHwH|T*RqGVbMYaC=&uhkF<+F>z zJynb^^q}V`{ObDh$1*P-+asFdYuk%5o-s6;ePu2g5`>a}zxc{nkiszzQfBok;DX}|OUmp$PnKqxv`2MHK zByYOko;SVtn&ka9PCQhvj%4%HrhLF>11|L6m}qm@Zb@>l9$(>3Yg>|!e!C6^OPxp- z*JbMILh_=^GyWa#(zMCH`Wq7VFx5O8XS&K%^Z$rrlInjeTT7B^J>zQXB-J|84b2s* z^*?iLLC;I9O^iFdY(Q%k`WL?b&BVBv$6<&#Te^on*0oog#md#dR441&}PRS2Zr~gGyiAAJshKzNzLH_fz%1;y$a^BksRyo#MHu z*8joxA-ta4LHeWh8_zm;2v((SrMrzQnL}^nCym^s+~q%+)r|Yl;6ih$>{~5MdUY3K z$7)Gmf7Y_~CAUE9K(TyVMJ>Cec?0^j&z2XWyr|n%81>Ixc?XnpebV4U`BnLT)bF%J zf~L7w-YDvdeHXH(mZn zx03zj58=pKGf9kx-phcz_}`@CT5|`C-oGTd&D)!h7>4?&GiJjz7~!2nasz{O@CiOh z^4!%DJX*Y;pm<^u#m>RsbXVd9)Qd_Bs8#@vE=J6_APepIlpn~|^6 zc`6@)*VxFTDyUUf-7AeO1L~zP<+QuFB<;aGp*_ zufS^coAO8;-)eOQtTh$#qRI-^w&gV#H2Jc;1L~abdlkH`FUZ|dmUT>rGHdh!URJTM z2hzYeJz3rm^{4r#LD`*j`MR7c7Qa0m-n2d~w?uujrgElut$3V?qiTm!FaY z%H5YH!?bLLJQ?r#=>_+p+nvVJZhS_^I%UBA^SaU%l<%&-1GhVWmn%?ib3YZH9=R-k zfY;(Sd+op9X@_%b|NS=iPG0x#H(USvRlj@$SaLRfU*j#d{wvr2uIqpMdyArB!^dBQ z1J~ak`B&cdD;gF}FO^&1nlrMF{44)2*cD})4}O#GNiPu-(%$4j&;Ac2fhV0u=E2+W zhteg)oMpxXfg{!l+%VcT7&1S!C7sg5A+Uc+2T9;k{cC(M*blV54$yVYY`X+1x+&#( zZgb(r_hU5vZq77l>MAGsz1ajT0uB$-hV9g z4b_nZ4li>b31v;2Ndkx4-y8<>hd4?ChrbrCghuIC<+Bl&%;Q$UtVj6%<2$o|@lXh{ zb(c;&tz!SI9}Kg;I!Xes26bKqFYd_Y&+)l*z2pnG6EDlxcR>6Xq3mva4(b7Y4RobEjVD!h|P;jazp$U z?k!jhc{%CwPdILTVKHQnPL^-N@fI)tfgSfx$o=rQCQlZ^$^}>Dz45!#n7aThb0ql( z)amg0@`4G&{d zP{4)M_cd`$xi>#KX;doEi@sPE%n(mK#0KSvXZ{_DvXR3h@ zxWs>yC!w4+X&ls!(U4lB{=}zaAn}2Qv=i^=ITU{_NKr4%xq3NW)RT27g=bZYWK|IrD6W z!~MCoQVG7RpEHL-^C@=HH+&C=4j2x*?wCr$QK$RHVX%FxgA|53XZH?+Vs#7YZyaAc zU?{ve(L!p2^4v2+;9{M%WQ+2Blw%sZN+ALp^>Gi9x=Zp5{NL{z{((PzF3X4EI)nGj zgT_f|as#~Q-?xp130^wVG#vk5aAwDwOgLHOq!2jMxkWZ4%y%H!*zzTesB1-X)4RFQ zIn9dX9yWP!|5{U$*O=zRHb*m(uWTy-J#_<;ckX@%j>|PkuCXqJZiDLxL)O_B!l3AH zBrl172l0&xNp5+h01g*EC)uP=CN#yvmIc18Uz!OWY;Zk@jr}@4hb1RkDMlk!-1_nY zPDQpc3gj__y%cPfy{m z@td`a&WGKb8!7JN_)YBs82#dpbO-f!=@r1{Dc_}aIL|-3^TDa^y`)xM%bJ{f3-iiz zq-prS{U2w+f!214Uic2=%AP^YI0uEmqEEJO!FsWwVl4Uz_irMfv{g^B66L9F^1*(E zk>ZO*IlIt5A0EbOE5_lt&#Qc}S*))p!SVC$^C9)Ko+1#RuY7g^JQ}J)`dS^{!kdqo z(%<-BOT6+yDtsa}!~ZI%%7UF*_KE@c4m4l>9QLQ%Di-6j4(#77%{A{@I)k?7%-;MLvo=# zIS`+0qbNkV^z}I&wRoeLd(n=7WG&g?y}A##L;V({B4R))FF^-awcH&K4@z6d9;9xFQd}V?33P<2`4*g@g&FiaRLJihK*rpBpOr;k`X9&j2QJfJHW%H0Mam z0tookK#_sh@@9Vl9H{&wbwiy=4c|dfkOr;6-@O3jPya}xQKx6u0(g41M#{u{we(B@ zL`DCSF5$g3?(q&r0w`F9rY-H9{;?TR^UB3()%6EJys%hMx6*nKAg#ZFP+7AZ`#Iu zh`d!GrQ^H$>}Eb3>zF46;`>~o{SJ!EKS^q+|MN`&49zT*KH$4o)ifXKl5?dC`2OeP zw_|LPBQ3*k#PwtWY~PVD-9er6nQ!56T8^|AzZYm<06HCBNy08S`HX8bd?8Io`F8AE zc-Asg8ie0ktFqQ`41F_!OFdqD{OhyDk8}fH^yLJ8{x3e;*4MrN#oNp0`}~VE(aN zkGZUcDdXBHgdZz(wER1f9GQIi-|_$D+Vhw@jL6TC1U@%kTm#MXZtZHMz=arG|As+QhXwxc~G+ zrLByg?FlRNZApLMWH0!(SZP}?bn$?M+)PQ>5j|@+c=zIoBW?-A*Ae|8UD* zuwsmZLSTOHnRphiS*9c~zoCsAC>rKS0`q(Pa)Y$Q97$ll_d+)~craHIn6GW_3b!ot zB!T(q4_shcRW|u2r6I0x_jrLMFn?ul7kEDGy(BQ-1YBTJvsaS9{2flN@GbehBryL` zwhNd%{3Hp?UvbtMypMd91m<7H{4(>)mjvdUzjK1u=L#i(`P$Q6Kuxn$5}4n7tTXsF z`Ys8~&)Vb!Pkwxq1m+uccYzCz-=)u}lkDmOcHZUEF2tEga0bPKUy{K5h{jIPCb&cr zm>*i=2$PNnn0uwj<26DVGH1AMNP^{m%T61m-uG z?E+CB8xZFAx$F%7yVMBtd*nDmPbonc0zmf{hv!9~{{ey`V43__i;@$O(y zp-=ilaKGftTZRfJ)IZeU1++4C71^lYe3G{-_A>`vBU570?g+P>9e+e6&n77Af^`i<`ZKUOtS2)o16 zJHVG-mI`5a=7!)|!HX=&?hK1)3vsDU6vFO|2`fRtjNvKE`*4laj4M*qtp$ z8R+h5r4V*!q)rcb`MH%s*qz&v-QZC#JB6@26Lh=7J9T@7usaV9^nwkI>=nZ9gmyK6 zWj_@u!tTuMZwQ(99;XO@SS`~Sg2L)jh#%-<4E_Id=qh4x$=(!Jo%-%6V(|9&O`&D* zJelA^e+|XnXLejBxX^S>6X3_6%LEsC^rs;dyEJ4X24Cf*4}+7;nTWwtKIuT3k1Z21 z_=ibaaNDjm6KhDGt_xbbJem04)_t@gXk$Aj*7F(9;@tPo^<**bUStjrjvx0Fa#5ZI zcr5QN6Y>Db0^Tl;B{_YiIkfMaN%Bi4Gq4KMpgA8sHiB&_RwN(mYXHX1?j(CU8bOYF z#}vT>ylr9vzjp+u2+Z^;)P^Z7U04$G08wXjp_gVGCU}6PLL;ykH#$Y|01bPYz(IrZ zOM(a3;cpBs*A!g@4=_#51YX?(MG)DTmMebYZ#@BsHL&0yu#VO<3eaG}}+hRjIv zBpzUpDSTYf(^K#OSz}G%<(EQF!2@)3H-psjOwWxto^0G0>krp^3LfA_oGI8?=*t8T zPUVP2_C>_O=DQ(neHi`d-Q|GknK|LDR_XgKc+A0!2`UDH-mN`4$1@%;C|8+B8SD(_?5rS;YsZlnc(^i=b1v1 z*EyNs0le{^g!WO$1P@S+=R7t~jgtu;;O_gzuyjch$t=SJ!n)s;2_C?2swuoZkSP;9 zfc9(?c(FT6CU}6oyfK{Icv~iT0Nt;~;BA^O6Fk7}aVB8is95$9@6Vf8W)QbCQzm$T zjg!p4C+n?D@BpXY8NsTil`_Et9P4TfV-GfDf(Lj%&dg6Ffli8$I|QV95jz;AW~1AyP{wcz{YTBbd6*oQc@#UaBta%eQ8N z2bh+x3mfbmnBW2Aiw$Az-DXVi0IeK#Va#t^CU}6+xdz}qswERV!0N;LaKD!W6Ffko zx<0Ioa%O@D_`XXAB4@iX!2_&&Yyu4qrF0cMfXQuBxHe>ur{Dpayfy=;M@%Mo0N)@Z zczaxn2_9f(`9Ai!vjK?jS7X!xW*uz+;+y?i8qbc;Fa+^!*8i@9KfY%H7kAKi*D2u& z+Y8ww*Z3Zv5<2T%! zXqG9SQHuY&DQPzg;mt|zc5@3`f6IpCb>5+P9=8L@u6fH?)e;wywQ9z($5U{A{Oy@F zUaaMS)+G1VZOv|DY#_$}>pnj}x{Fog_bKpsoJ%x2XwnP>KAT<)VXSZ zn{6vJ1A&dBpYLR!Mw#P26c}@5?_;ss8iT;bU*3D!gccScuyK}k40B)H6a+TjuHMNC z4V!?##xAB?+2kTi5ZD;^Ya5GqY6gNMEqb<#{V}ryfsM^uZecN9n}fi{!9|&=LeTj*19nzbD&(z{XZhL)rMdt#I%C3ij~UM)t9p4G3(!Jvx#N9oh;6HkL&M zvd=4RL13dhVYY7YV%4;){?WT_4y zun|_SXN^zTgTTg&lL0L8lmp4%d=|1ppBzA7<5AD~?5)fR1U8m>%wfCsID){&+DpsX zsR$=fWXFEmBU!yDrXSbs1Z4V&G2^xfsK=|4q)H>T|i*tB*kdv(8vu0Hg@eW zl*yvqKw#t589i8%3}ZQb2V{}JLgu)Ez{cL){${?Zt{|{6J)W^f;jSRC@#5JoEbyW$ z2yEQFv?Hsz;syd64LOYurI#Y;8ZT_)mZ|vMbVB^!+-Rw)O zIS6drrn`fEJkS*D(ks~C0UMbHo-Hk~G3w|bwzID**2Y(`ft%del&EclIfopb*_W}~ z35%+2Y}kO^y9uKX+Iq2=g|QUdYCRgkVlEt{*w#gFKD$3KfnwWnPC+ceQN4-xmc-6xeD{}oHzV`;nFObcR& zd$f4`h{??(iF>S%jsJz8yRUR&t%o0?HQQ|)$fkQ8C)w0^7CSxg6v>OT1K6VlXGsoT zx`~BuK1Z^8)4golA?5h{HOHBJzf#{~_$8KpSUFE>&ueUUmU8~&y8CR!s6F)CJL8|T zP5rizJbPqEw$Wx6#kTkTTeHN}Sc+{w8)dPKQK7_VzW$KS^eV%N&veso&$dVGrr5Ui z9AMtl_EBv6#lIVid>>1(ZL{=VY{J2P6x*5)>dU%i9-!FPrL`xUo4lW5Tg&)Ctna-8 z6x+Hc4r5)i4^wPwm)4E_iaJQKZDx-VEVJ_=ifs>9j%72$4^wP=dHzIJIX{77+k$TW zSZ%=(ifu=@4PmdRB~WZTE@1`>&55VjRx4yK>#_A1#kPIhk79l99HrRSC3YSQdyyas zJ~RKo61GCZGlemhnO=bV`~8(jv8{gCR2C#lq}Vp<@oaXr?+J=+Ut#~OhWl}fZT01W zY*o++ifuo+En*Y9BvEV|+%Sk)q#UQ%wxW3mt94G41fO}iaX2gcJ4q6JW{lBl7Opr+ zvF%;&Ko&6c6vei=V*jVZ+lb{ zJnAr)MCQ^ZK@vQw-IbHf=ShMjc+~vy@$A{gBwA0qh+|AU{sgUm;Gfg%SLtC%aH@*9 z^K4k}BgCm%pFF|t?n|WW{hWP{*&jYcoND9vi!6{GBu+J?Uka1=KS-Ra*|W2(N#|pd z;8Z=cFR;tc6NppYU?H)mR&m6s$`olV`O`k)RN4K@OlN#NajJ$XsqF6Ty~L@;^uNL? z_v|4~bx+ZCw$Nq|ajNE#sqCZiA>vdGhF@VJy$%qkYQb-^KbLk8r#d<74*OHFoj6q+ z-RrDsd>nDA{rB8vuMWl#r~32VT~@w)D{-p*=RaVPi=&BC&FOK6g?HaWoNC;ad+egY zF5*;8Js+}9uW-*1v@cChK4D#=qli;YcYVNeuWctz^-9mj?8d@K;#3ExK4D%Tw-BeA z_b!t~jow6@YVhV~%zi=`ajNZW3*;(4O~@+$P002Ay85z8r@oKZ;!(6@b)c9DAFR$g zN;*|lLNV#&OA*res8aGp>*M_N;uz2SW(^4QM>ffk8}wQr6Tb1%?t`W9==G%kU$)@s z<%v?*TEtNNuXbO{<)KymDTdwn>TK6bGjs_9C!QWIeLs!gD%zt9QyD;8fe6A1rC^w*$ecPIR0m zIbF2|VRtS!Tqb?)+#H16Sx^)pwQpg#c@g>IHQrX^i|J;{9%)IJtV&%SCYf+$4Upx zoJiikdZF~`u`S8(LIb4i3@ef+cLkj;Wz%Q827lp6cWVf>V7j|1DqQ??FEBptX_sEXtYSR6{JbNH5BNGQp`% z&a0I#GI9sOsW$7WC(StJ27*%^bxBuxbH^0~r+T5tSUQO77o4iqhbGcaBR3G7>eUwd z(tL9d@@FdASV@oWBBzNQ(YgWll36EL5S*&-2~%k_`ZI!4wf3}=q|q)QIMp?6T%?F> zU+bXDyA_b_c+N&CDb2u^i;$VlnkJqHk+YFoESQnE%X5O&9G$V^H1 zunh>iWB7HPRQb#vgx$HCJx$85vIb#yoW{?V%HFjEVR!ENERqZ+w*+B#p7)v|<=nCb zVRx$A&y`xAY=zuCa>99wrCU2&fUrA_&-qGszBLD7caBvol`vygaA{|*F$hjIMkh@2dT&nG>wGg*$_zIK z!Ko%@he?G-Mj$v<|A-CJxMv0+IMtK65z@R*rXcLjq~?**z{w^cI8~eD5zhzWV&qdIyTxJKO5d#?|yhbASiKl zFP^ue5$#BLn6+DnYy4?Na{eN1uC~7g$z$<+pPk$A{lx1E(bVF*wwaRLG})NPyvpjd0&vR}l533-C;nF`w1+i=BpiuCEJ-`qGbvMmz-1ycYGPBXMtu#~+<(d@1%R4$XG~QD1s-k0G9^D?ty>SHL+i%#U z&wFY)f~YUuAFa>dm^*=}FI|K>hyHN^QD0gas?Qt6I%EAoIeS;2#~lJ3K-8Dsc&p2e zW?_FLUgLz3x;%BhHHiAsz12EA#@iZ1eQ7H*T|R6|OAz&?*`~VOC!rOH`cfY}pLC0d z71pF;{pUO#uJ)(}i2Bm~xHpMcv<-;*(q-%Ld?oCw6!oP^BXl_X+zdp0>HTtTZo9Y{ zi2Bl#Ep)iPWC^0aG^I?NYoBcamZ-loAJ1u>inaSVe)oblk6P9oKH+z?X1O*Wt=9}h zeQEMKZ9eU-If(kwttc-#-ULK_sYxqsepufe`?Ik2c(^v-xxF!n`cgYQyW|J*;G({C z&__JKvZEP@`qHR|*uQAigm{&ACPvUw`93-MrXcD|b*E@yKcoqW`qC?*THIol5s3QIeJhN3jkg{8r~G9`%30 zuIRP4gkz$6f7mB4DuRS8`E zult$*x(p@+HDLm8)g4P=b$G2zaHJdSis3%LMLDd3mBmofe;ehnrvFn6_H(@{hvo95 z7$7XiQ*flWVoG4AcT88okp>Mch0_@=QUu;=wJU=r-xMhV^L>w(LQweQ6oL8nPrkv= zPj+k!zDv(Ezrp1Xu1s*JVS7r!VcCY1t@u42*;E1%e-cw><9DGM@(pHRab%tGoqXqC z2LH@z&U)fI+~GkP1mA4R-0|JM>Qe^V-exQf<(A({A+fVHTZVJq@hb(RWtL={Io3A8iKk)1%S@GdQe zM5hed1X0HxT@0+p6WId9ncKV=PI`WnY2h^%rxk<4sx(a=Nx^3cn&Xw-=)FM^v# zU&y>rr(tRlG?|y5J7ieh+m{fI0WaqRTBB6$6Nugn|2qazcF!TH)wSs9MsnqCC^ zXPl7f{;dAR5dVCTY(I|MH!p%ucm9$6gTFmIwiw#n=qQ_v<3B5kAkxKJ zwg~mJtcu|C_p!2VsPopj2%634CW}IOQ&=%%S!&9*p}r$tuhWz~PYLxsjupfC53fD< z;kf^pA~4^oB@_1XRVJ=KGtsjxj#u~SNr)u4~1jcr;@iayq zt%fBq;jB;Bg*d0@mSTvI7J3dq`O@MN_;Y7t*Kc?qdhIQNmugO3Vo=`aQv!43VadWz zn`K@M`Q8;>=i;2bt4iQ9&rBBfLi1_~I1cwrF-M)7!-^q#$cHY0sFUed3d%?6ahQJcavXnDSPaFMtx|kYHf&Y`E!Iv*nS=7LcBSA}u_GlHpD)uagKm$_StP!P z*Ii2CuU$H931Z-otYWOs$&(f1J9f^e7$(`D@C?KM{a_K<_aK0|Z+P7J3V*jeut5V zLo9Nc^R4GS;WPmMjkwR zTsaeQ@h~S3-swgS6LGPBu{-zvQo}@CJpP9}pJQCdL|nX}jR*f^*^uJmM}Z#vcz6xv zKvPj?^(i%qi(BF|4H=?Aaj|x|2jB4O4-;|mpb~d}y1NF&#jfw&dGwP;6c?W~@!;13 zwJ0uLj`~?w)F>`i1bOgDb2KO}{&L%$`xI+aTs)=7oi97COL4KKzXuOD)}*-j&3Sju zeRV^BceQ$Y%>ocIWf28&F)_ZJY<+I7Wx!;wHU4_=sP+6c_tWb?4{)7*bq3 zY6V_PhB3v(9`1O5V)Q949^c)aoBJ74T>PY&J2x&ep}5$|(VhFIno(Tbw$z>XxMD^=eCjlq^6>PzD$x$@|dEkV?mzIf=ur|z<$SheR-7rvy_n&Q($ z9~b_v+6DwKTGGLV4>)a0@o6gqSMGX98B=>+apqe~Z7C*QwAq=L?69YpbXuAV_f;rk z@SO{td4JsdL&T)dn>q913-%O~_9$@T?gJeuCgqkc{KtKJib+kcJM*2_94IE8vA~HJ z{_RLHX+IAq{^gMq#iU2)I&j^u9_n>q1|b&eF1-b!}lvyMAaO#06fN3Lh(LNV!< z^G-Z#q%*~&Ek`=>TNYTeg_!pGw*#M+bC#PuPi*V~A|~xW7{5E@ zphQeMD69ehm=Hj{KlOc;h@K6&DnH&E&%qFRbK%$3_o?dpGY6)da8=%_ccC#?<+CzQ z8soX5$~;$n47@zfnX5R@xovE@iVJ-P&A5sqt&fxS@%)-WbFSh%bu8?-iVO7^=E7AR zX|i84uHrmHme_I?7aD)inX5R``q%C{56_KJi=$=D(aL;W5$;K|%vU+?jr%pa_$c*9 zZ87A21C;Yj&@<)>#wq8o|DNQ&Yruc@52YO3_t_12?ALJ0!8zmJLXBK@Q4a3O8e_iu z7Vepj?_uHj2HbR580FwrwrR+H)<#hd?txE3KG-Lca&Q;%yqc6-8z~1@i|6Ou9V2)a z!F?V}vr z`tfSq#9LV@Qlm6!<2)| zO~i96uO(0pZq6JHKD&23<=`rAYw$`O7hLESD^32FYXarq4CZU{;J3#p2j}LD`{LLi zqa57V)!3WuaFlXz9bRklFY3oA2lo&;lXKyTl!G%VZp7U&UnaQF(4m@q#cpK|>-YgJ zo-j+9Q)^$N#a%Bcb8ya=HF=j{WzH*3U7LUYs?5RJ&eGMmKjNugIgV< z#jn?#q#WG0Vl6&3Oqqi-ZKK1-VNOtRq06`F@CQ4SCJw9PrBIV%zeyq#yJ~~A?xTc21HNQk0_ETm7U^@fzDbmWTl7qyKO1v`a&WQN4fwY`hbada)76l}m&25Uvy~a} zD+3ZK2j`Aw<1X<&L^-%F{)Rjv_W%E3*ajC%w7CQuHp zi?b15bao%*;7axx@$@D8Cq&wskk<;DoJt`7VpNP+>>9w0}lisIV^`N}drHIwY|KChvPfT<9NpG4ykI zNL*;2S;g>S8=k|0oagi-#W2k0HgTb9{Yr3en;XQ18V)aor}wTB7kW6Q48mpU#D%Ko ze1p|TQi%%{oWNc;1=VW_UZQcTocKw>x6DYx-gvB4n~P_3hM#{*&@C3{NLrCAqS&1m1N`BRSHg49w;!NH$`naB*}d zaiJZ1mVl937IC3Q1B&6-kh{c%_P`jkMdn@NLQgI&2Cp->i3@G=qX;_wzD-={Ue6*( zZ+3^c(2FaJa8Juy#D)6wD25ETTf~LR#(#&Q_Z7s2S}y+v1C12Kg}UXIfGjSPxX^O< z68QB8&(_2^YeIAhY`yY?xX|hWC6G|_n7Gh(k;RZU@+onl9ytH<&?n?OU42{(1G_yU z&U4<;Vt6$7F>#^J2aBPH&qEsLU5i2Iz(e9frJF@?`|Ts*LeH%&hF+T=5EnWQW9Rj? z_lXM~w7Ccjemtc4JI*SCq0Ju>7aBIG7_ME zvRU_u3)QnJf(6SmhzoVfDuUqXyTpYK+Eom0_iqswYX7MiY<+GL7rJjR#^aZ65EpvE zvII6I+#oKr@)WMY_aRQfz&lxX{$RA~=n|6l$&P83Cnm!2Bw4p*xU|ii)~Q zT)8lSjAuhDEV;StuNGC4z?ZQ&n!>xway)|)cW zy^=;;=+YZyaJ6X~aiK9DrO>;3I&qEXvY}rnm4<8y#vi2Yyo)r~H za=<=a-hcR7l2e=N^L7hYl3aHQ&pKc0OLEpiBd#B_oMgRFV?M2P8Ob8YbnNmn!qxw} zpBIK|^X9+82ycUW=Vr7wV1ggJN|A2re{LO`B)sg@NEg^+22F{tg4dh5neQ z&CmT627(K{c0!AfOb7$Pg|2z6#mn+l9UfE2!abOKZ)}c1cKl~pVjE_Q+)$LaG~2f>2Zzo0U)?gwf?vdWy1gv zTxe{B9?$I*0D=oWgJ;Jtu?rxcp)OC4>#th}f(!ktR*$>cuLZ${Zm87dPdlvx!G&53 z)#E+duO(SMP@l*AS_6U$?Ryw~kA&4AxX>S&=(qG)1A+_n(L+CH^lA`XXl6SDerMBa z5M1c*X$D-g%PJ6DsL51)?uF-B2rjfQ?(hCRV1#2=0I2f>9N`f9{Sy8DCRLc^_%`Knfa#19NX z|L59lUl3gAj9JEf$a_Ds7d~;ud}X082rhJDgb^QQ;R}Kb-5hVs*WB|1!G$)tZ^Vzk zUjc#(9f5nd2kcw{f(tF%X3W2@Tmga$-D+*ZKc)GC;6nT1-ke=*!$5GME915K-TfgT zxX>q;ba-J-5C|@G+-mgA_V|O~LjM<>5wYa#QNIWW5_It_h~R3H*KEW*qgO4-r^@wt z;QHSrU&Z$)qCe(=5WBo~;d{PKDW86)#pPp^@{i6K|L#)i58SK48;w=YGp40FZxgSa zKlxTeem+F`znxtwaWh3>()_1BtO;zBiawfQ6OTH->-hT)!5u{FenGV?|}VP!RO zp;nSQ_bT~CTcf2$R~eOeU8z0EpEH*H`ViK=i`3fKWeC+r)-fXS9hx=jx;7hi*H@5)K3o3gI9E`Chl|+NB*H#HF2i~?syLF?;7Gx?__B3 z>+vGQts-o6UZBCV`_vHLZaS^b`|4H^cgiQI^UNK;h&yfZ zS&g^z`$gR8z>Dg9@Um*+P6zp@^NI%5#GM+XtMO<1Dv3L_8-VhHO5#rEHA2oLtctkP znM>7pRMSf0PTRSv@vR#xh&y$}Gn2axs37ii*+ezoCEyovr+W?6c+ihZ;!Zd2Z-_My z<;0!pw`<6!H7+Oabj;O;{Ql%h;!a0TME)n^Cvm5ZkdJ!rQbB$~$1e@|uaI)$PSY>o znZvh#5O*r_P^S5QfDHxIH7+o!i{mOt}3P^JP&*TM4)8->d(+pY@+b7Ut&UJ(Pa3{znJiJ!=JB`+>Di z{M-b8l7C^2FY^9slKltaI>Q1;j`DTmuDa_rCO!gzY6E?z*%V(}2yW@|!Im_S}vO58oo7;ab zhU`w_Kszoy_9eUXq?tXx+0KvbjydM_1~x$-2L0Yu%k6mtUW>?=nY_2>+aBXthv-YJ za<=Db_g0YIIqm7d$6Kr`Qj1#~ug1ID949ougF_{Gj$K zvOC5L9C`2bm1K8#JHe68ykn1bWOtgKcH%sE71^C@nBP%r5I}Zki^7>}EejyKGqtS?S8NL) zyR&4bGq?3vLw2W8x-;)owFG(d`ny)*`3MeF1&;8I`t>$uDneW#(ija=3T&fyn@N@*ne~7H{S%4e*8E$Zrn43>`oEpTlWImP*OT4Rnc~I=x`mS6nRLsIw~PxVyE9>q8$Z=LnDlL9-1wpFP_jEeuH$%E7}b%U zvBzAePB__}m3eOb;zoSWaXoX)-TD4rp|t)TmhSx9w{WsM{g%7)dw6!Ls3R@t>&{pF z4yEfI;pNVgPDGI1iJ#)m?PhNvyYuFptC!)yiJjeX(y2TsG?p(oquFP>0*_{+O z4?cHqB-x#3e|hj#bEC-aOv3zc+Mi8ica~tjcv1RhvO6xApPen+NOosG{#W?z&184% ze&Y8Sy@l*fA?Bc;kB=t1GZgc`_ugzGyJNE6gG=W&lihia`RLsaTgmR+$GrBEs;y*q z@-e@>E^G_goifaE>y>RKyAy%qE81@*yE6du&JNn!$nLzv{CJNYF=Tf{4?+&c(V}-i z$SPYSWMONB-#*jcllcevQ!Ib*%Lu0Fvx;K*jBg9sOdmW$5V_MNyCC-Uk203`Ikkb^ zstTf5KFD}0I|3mT%RjN-#YRbC6w9BS9?ST;2#V!J)&5xuS|9!B)}s`#08ue-9G zzm*tU89jp8d{<)Z^H&R*?hz%%?%J}RISyV!YkoCz6Epj!#Mpl>?PM_rlo)%y-+tCF z0pCx&uE7ltGw%c?#=iRO$}Fz>QU7U^cCPH!EG1_CHEG|9Is^Xu(L{ilW7yRzBs{i*-7L2Wly5a3V!r`qvd*|_W#)PK5Yju%_% z=u7>lSE>iFzcKa{{ijFP_GS~l`%(Ytl|3Ou_O z@$huEWEstY`Ro5WV@+bD|g=4W$0lYqHI( zvQH58pVn>J!n{`nQ~zn#@NMkTOXBWWj|}NE}Z&Lr+XY=uYQG7|7l`f z91Cr~f%;G1sClu1ZGO~$IzMgzt6Jbs{iie1XR&wx zOHyH%kX4u_iO3%j2I9UYJvyL_zO?A;|A_e}ftmHMal<=9XcLl3 z`rVhBLh7C?ByZI)2fr`ZNoL^|&|=DMlK=W<0bXD4k(}#g0V#NPl=!d5evQHE^AnP5 zUzkE+c_zvKb)V~SKZpBuxW_Kmohk<5-Xl)e2%nGPei1#RZW2D%9x;V!(jDSj%P*Qj z=8+7-=jp#pKzGAK!e{#>#*jDu3E}h6IzzbXl1ca+`%4EtlJ?Mt#nTh(+ zVY3Xur&$*D=2xvX2H(9|gpJR)=t6aqRKmtS*l%I5K8>(3x`93n&rTz3^v&0YccJNo zjTe#)psh|CVdLcEh7f!;jj%EKkRdc_ewDCsAO2TeQ95Dcnb}70;w$Da5HsV#4Kk59b-_MfbJmh~LO_RO-sR)37&x*c)Gwq2WdHjl~^&#c!i7l5gzLJ-xWn z<^uV~Kjc0er+SyjH_qDSD-u6mqWUS?DZQAK<0ARS^!3t<&tESp-#E)h^bU_8-`KB` zuQ)yUGWo{q^?k&qk(bFg#y(3YR_u=;-#GZaw@9vWg?yv$wsayuo`;UT`IVcd6Kfh@ zA>Wu-+*>@~eU*IUgXP{Lci=VhjbeLag{Z_Gc)SA0*pO1|;(R!?!@*<~{;xkZgbSEQP6hE!MM(_0?F=C^OEPqkN@W)69*#|q_ z?BGK3MK>mY4Ot_{yjTmm?e({imvYRDbwLMe%{B)uTS#MDe}`bx`Nw=3+cqgT%MAK3 zpT@SGy3aDd6rN9G+dpdtn>oAAqp@xB-MQv-_XX6h`t+J*-dQ@A#P zC)3U|OIMsvW7{`kmKkW|`u_G`1}&_jYZcGndA;ogdCM zdzf=*YYN?Z&C+jX z(wu5=@C>t~$4naA4qiFOyi$EOjcqHx3pSq*nMGq;J$kAcI&cP!ZOf0HX11C!oyNA$ z3kRDKn`YA3wnM}e(^bxsV2`Bxy2++{@-!OT9{V!cY~wwR#x&@hIH%+0jt?%RM=734^Z{=98SinT{ZuAry+ipHR-mFk+ z3XN^Abs2BotuvX%ww*FeHG4QrrLkUx$&*dJz8V`gzckV;_(+Xa)7&3n27XgxTm4Ru znR<~LOI}Vr%rt7Mv279OL1wXSYAoD&`T+CK)3UE9_eg#&Fv0vy_S3LOGO+0wbJZ+0 zwp}#6m$@=1kjA#N0(+PV8z$1&wnFxi=Bp=aEL_l~o7w)e97oGJ;T;`2ni~gCq&d~s zH`<#6mQJ9t?Y8^_%x`5fW7{9WdCWsQN72}}TYLqxp`7!< zdepK3xlOy70W`Kf_*+)9lYan>Z5QY8H}hN{Nn_hd!9~oo_eav$_DPj|W_;6;G`7u~ z!`ocfVHAyR+YE3u153#}bY)+?MRa!a&Akycwp|mK)^w0#8LUS=8S7&vryoIae0+U3 zbHc^pG`9WCSAP3)E(_~Xao$Lj{Cyn#G@Q}IznkOik%IE~bo90UN*@pBsPJ!I*i+BH zF=0PG|Mq0{^VoyWbEnvw&vUBSv(Iy_KZ^y}gU@rP*qhIDs@Sv7bFJ8e&vU2Po6mEq z*t5@bt$*d+i$q@04(xePamTCHS?$NCj}&*d4LhnmO8iW5XU3L&+Dtjej=lMn{kLd- zOTSRuX=N|ZT&kmfBkQ#_SPLHimEunNx`A37L;j8+^ZPXDr=6Sjh2qX#hZfqRF3A*k zuGXlmjk@xg;*PZre^$@so8Q*Dr}{{G*^ z#pZ6+$}E<@Ye;?lE3MQtI=J&lFYuO23<$PtZGxJAb~sqkS#(p5o4sUS+hF$)70hJeplh3yu9uai{&_TiWtd z?sb|+&O!PNKLo;`l-B zc18JHlHBXvEOfuN{%bPDopD=^%6>^Q#hvK)`?Qh^lPT_mX5OR4JWi&#vnqP0ws!3o ziaVvA9nuC=mA_$0KXc*30qurN$9mLJwYO=T1HMq)@xHZ1D_7tv#htwG_iBZcaVMevM$PNZ7m7P>Th?jS=6|KQ^X}4iErrrnm3)Yx}yCa&@ji?PRB~6nDP+kJCQtUn%Y^$~!{aDc=Qq^NszJ zG^dTt|-%X{1%ipG@O5|CdhNW2DMM3xRY^~JRht<62+ZtL+fdqi+-WFvH53;JGkGZZu=(`cRc02C$HU}(7XZ8*8cX( zWAaPAuQnH(dOV^rdxQ8kqWOb38ndrG+EHYccS&PTRm|=#jIJ>>X1|=Zuh6GP)0jQ! z;XpCSGn&Ti4G#~O_c%n+nEmVG0I{cVG>zGD*GXx4pCe))?pUc87)j5?{W1?@dPXAo%#Cx#h-M|CX-+ln^%yZPZ4}KL zBv1WCjG326^9FT)ZzeJndPMUERYx@!9$g;MyusJ$Ekx^62{dmIKd`CTaz26P4PMV~ zCgO7@(7ZuA@75w?Ks?PG#7DOf^h^D!MMk~9Cd$OJ2e7}#idyD?7qG{eBF>@dB z$~l_m4SWvt5lerIrg?*XF+IhF6;U*AP@q9S@xHSBTRE@Nr{izp%kC(eQ!Uk@w}|K- zMe_!wUHgjAl2J5oP@>cTaVb?a%^TckJy7f#9Yym7kGBjI-Cjh|yg}Om{l$T}NSZg8 zRcEj$6B$MG2JMmth>REH{e#lZvwH@K(|<(Lyg|DP!$gf6Q8aJhv2(bn+%1ac4X*7N zA{NR!NpYrMl|947g1b>_PIb=+@hK*X<_*#v87Z<2kD_^l=DCK6v0LT+^0NFl>qm(k zpQ32q;N*b-F?B%{%^PIjJzOl^6-o03?kfU>ms2#&8@S6gRvywGoas0E{wT5YawN?g z^n4f~TE;}uyg{`CW5oEQQ8aI`^k{R@W?BNx8$2!AN}Q7S1mH}+oNL>QGx81+%o{XK zJy@je6Gig|xW9?NU)<}&-z@Hd;&0jdUE?08Wqs8*i~FINt>3%VC*U5a;Bo4Af7}nn zjC-KkCqAU#<#9h0GwujTuAW+lAHdxKL)J-_bD=m_KgaphI{eIE@q1SLM{Wucj_;M< zC{i{|IHd5_L&rtc@ydt%=6_lony>s%zv|~i!$RsE_52q_q^A5;XF2EOZ^o1VdE|XX z%pCTJ7)CaeJuImv-vNG>p9}d4`(QUN#rU0i2U%8J`ut@B$50u?$RnLV*&Q;;~u~y_b0SY z^+nqwB8yuzty69O{jhL*8A-meYP!qf;n2slPW5@(E8=5>^q(@uX{C;ckd;xiPPOLS z5b;{J6RcC6?`?{5QBkx`^;WDYR?6=J>s0+BLd1+ik+e=V?srp++a5{2tH_?CqQ-+L zfpw}ESA>c)zedqI)q!#?_9qz^uuiqX5IL7TOy18c=QkR6Ix4>Ih$P>2v0Jz(A=^LJ zsn+*DCerMRqIIeVn}vxLp^>ys^+VBc5pW}t)~PxdJ}%C;i>7s|)m%@AkcH8-PBrw= zaWTb5-uWxnD0;>m69Y3z|1aOsCA5JT%!?Ojic0)=B}oobaVr^V^LF|^*7ty9fj^nzIQK91I@_AGQkbQ~b>T#@xt{@evI zXF@!!Q$2q2g6RJ;me#3$>UB{}8ZYlMk$D|wT9uaHrfdVwXH8K_`faRJjh%W_T$KJC>r_+Q$-4z*Tg5un{i!bs(?6cp zsp5_d@Auy1b8!DihAKYfi*R2?xp$J~_g=76Rq?osw~oE=B~NSO<8m(@=gz&1DJK@M zmuo2Hd2x%DmlD|~c<310c5yE*5-YmvICn0%NfA-=wyTc4@a;y*yCmAB)p71z+35vE z`WwzV#?gg4ng+qsNbD%S_&T}0dB;;39V3_dliu-JXvo!A&sKtxnVwRM#riU7bj+zHZ>}!q3FIDKIma?}PZjZYi?@#b^`X91#mFJv zI@Sw4*;ZK;tL3d@y-?h3U3{d765FxQ%I>xpcvufh@eJ>qz zsza9=!nokAV}JeN)tU(3=B4A@xtT30iNgcEu#!JJ%+CIq~Iz+|MAt-+Z4ch)++vbeubPe{VVQ%U(|% z`|D$Z%LGfE8b=E(s2gJ^j@V!!aWZi zW80&9ONt45J#?HqH{eBSarc&|j&tW;buT4~%C*s$Q;q6hQWQ2kbeubv`*d+})m^UB zmH9_(DJkY@o;t?1!xxtjOP_h@7~9_4SX^ve=B{IZeR$epBB-;wj&tWW&MPiT$+My` zw%vTam}p!>u4R{b#=6VQT{1r+U5;Z!=b}Q|_DDMFgUtM(U>;L6&0nux{i;i>WCdvKrVTm%2Ec5%T z{373kv}C`pyc?xZITsyc+tl)$zaO`qb*vY%Tbf^N_fJdjd$DRk(dD{4?@8vVB=2ge z+22{mxpQ|b77#+N^TybAmAo5eacvjxnZ%5`A!{$5aICn0hS7A|T zj=hdO{@*f5?K0Wxm{aXjrGSVkG42xk$V6TUv9s> zD_Sh`qWH4C;%)J*v-F=bzF6z(XZ2~-!cpFXmgSc6`ES?8i#(%MENGlPLDVm*VnoKQ z3F5Nc%Y@j`czL{dG+)J(SBv9BL>U!p8l{gFJHk~ADw0!XMAF; zDE}!9#hsorVnvOH4itCR7m5?z*E>+$X({i6Yt_!4;?BY&v7+E^2Z}o*Vq-;ww_GbP zztfFFt zlRr98+-W86jEfcW{6y(1(#X5*im#Jr8cIKtad(_J;owYhCv)|9G4Grs#holI<3+hr zP84@KmX8z9dOK6x`Ay!Pw@mss#GS74Zo3RCv;)^_E5pgG?dA#`Jo-@Ur_ffH;&}SElJ0J7Li4Hx}QryWT@7l{+ zUH+}iU-DqAsM|Iz#U1y_v0|Pn&v2A}-Yqm%NzJP}!xU7m(<%1uJ@U3nXcY^cB ziAy_F9BC$P{^qIT&Z-MBV#!mvpG4X-=~9gF=-^Iqr|-;Iv1yQsQzLuDh?iAl8n`Y){;j78GFY7ikIZ6!O z=bJ0aQS_~woW#hqhvoaa#2lj6=cIhXTlfd|E%Kjd89 z;Kv>mcgng)is8LIDeknp@IVCI^Q5@5&Q97^!IR?7o6!$M%q~xgJM$mi7pvcRQryWj z|Gx0<=tXhoW^|;;B=-d&?gZ3~6u)NiqPSCj+dXlzzZb=w-nH%t`+Hs#caCm;Ag*=s zqPVlr;hy*;_gf^)s+2n8F%^y$oo1sdsEz5l5|(h?%+*v=Rlp?V&Y(LiaVpH-jQdBc~jgeaqhNA zBm0(!J4s(}ir*w7?sy%js;7Vb3ytd^zpku*XrGEW*TG79qqhy{tiNFeOX)E)_JqI} zwVj(!Z@g)b33jUCufGfO4h0{OXDxPmQki(*v1h_JLl@#Idrpdijw6WS|08_H5m&C% z!j?erA&TqQNKS-wr9bRWRvZDSimQg?GGxOF_hm6 z=_{(v6R;EcFaC0v80DP&tmZ>de(#LxcPl*Csg3f(uqXFhfAYhy^UBzq#IS$Sk$l8> zudp!%i1EIhj(Xtys2?r|^~U9+KKZ$*XSN6R&vrr=w%@8(_kq<&yVytaEVwYmlg@qp zA6)8F6+P4Hc>?LZc5C_Ig(9PV~XJPglIjCW5rwIFfjiQR4K<97Pl@=xr)OyhETL}jhS<)>>` z+2rT;tAEsFdlGV`3S~Q8tNDep{m~t=lBTc?=^r=PkE@xGjndf@!1A1(*=#^s|v`MIcP zwg>gkc0w1n->PHBZB_I%LGuJO&D=xN*IYkL9DJ#i?td_fcukJ{`V`k6#OaUv>kZ@> z1o@-AoprG&BXRYr&&9c7xrn#Ck?W_1Yh2Fk z9)&7#`R`V1CO`L6G1Fvw+J5Q{_Hh$qilOMe1&zdaXqcdirAtqH;F*eMuG`iDGG}o4!=?loyF&VNF*(NOJQw zk41&!E_zMLubV#>iRGR37+KDSm_%W}&rxqF`C!r`@xHu+zD+*2)rJI-^LiSx=kMH? z?pOAzSW`7YRA20%zi1)nuVlaBS80D%&r9OHoPQ3L95?8^_)s`Xe3qPX&KWUrBdX_rwUv+2#Cg*(~=(Ny#VQ9Tpv@+!xTu zI!FEQoR{`&p2wz3lZ`pW*oqF+PG;Z9E`krpeWB3tWj0}_Ia51%l9)|QJ>^2}q}s{s z;$|IrhLLOo34uAq%5c?AGUm!7Ugq$ib`m)|zo^;6liEqE-G#;Y>0Z=M_6;Z@hEDRP zc9P+6S@A=*PqdR=gEU*awT=P*ZgYB%iZ`^i6YFmu|IXib%kLj;Yd_BAhKbMb?@?Q= zwYI+){p23C)!SKmiH;raQ(IkgyR*pDT(#9NAKM9+Gm+F*=dW%lT5XG_w)*MWFCxu{ zhtyV!c5f_J%#5S9`gh)^S^7~ieM#~>`i>kj7S~rK1Pl1OTVBQW-j`+ywBh1cis_e+ zPZRKUYg@|vHzy1Dx`SJb>T}Zt3AEuPxnFFmT#pA|cjjneJ+=G|558{Gv_kr=S0e>{ z-HTEM^@#Xk0>19;$^3fR4MPNcoqP3sdJBE9KpS3gD38AL#2~U~NnI~}vSj#^4x2pm zzV!!_MsHl*^_vfdkVYM*y6VYYhm%GJa;DXD-yB8$WPF0N9+hbvY1HSolRh+fB5CCR z%~3!1>m<_1W1*wIw89k9Xh1bb{rCLS=(*OjS^k~pv6RVZr`wyK$cAyrc6#;($)rUw zm(=>fV7bmj)|H=;M(-W)owP_h-(DY-#*X|+)Hmr{7uk_N=_=1cZ~xkk;!aIF7k!^+ zD)J}er>50UzPBTPlHlZ~_giO2{-ow8cRe_R9r=@CH#~H=ecwro+8$nduPa~49_!xc zzrz_3)-!ypX94{?&nvt5>6JLq(xm#CC(kJB9Cei1XX8T8MW(&SsC~}*^QlM|c9Pm> zM5(7@kSMhCwAou>WQC=l0W%r2{Yzu~CI9m`0*Wq|xWr1r$@ z!yOkrq(DLPEm~<;{p+P7_>(-7@{7pb z8AH)d7G%mJt}m72Zpk&rk@!Ry_%jHDJb(uo(+ky8%O%$4(Efl{^_sm~aoZpf&6u%vyU+w=o zcPQ5FpdVXrmXC>clK85LSP_;K0v|GIObhX3=Zz5fkmNtwitk7Fhrox-8q-OHpIIIP zAL6jRhe$PZdI)^T$gIDK_AMubz=t^Q8X^)FjthYgnefL5@#T162z&_os~fvb4}nHl zk92F|`4HGpzuE}V@awS<>|t!|J5WsQdm;pPXH;?PEiSH&2*G;DqjC+~g6APwnCBWtac604qR5o+lH$&!mXF2G49OICp38CWo04g$orFD46a}igP&;|)nkZ^# zQ|+W_Xo8rzAsw}oL5}g_#o>(9PWH=w^!1wALg7!QEQ%IeO6Ceh+-dgafw<8%Zz%i; z#_8N{@tY3oQm@QyF=%_vP^@7%^X#tJH8Wc%eq-wW>jP1ATc%K~VMsqAN;J&j7m76u zyK2RVeoo%hPW(4L6i-L0c2ZLQ_Oxt{1GSUW^7pA$cfZp)(o0?A#GKA==^W|7a@|V) zACKr9=?weinwJmv=p1Q`(;v!qi{JY&F1EE3xvnXyQ)v_HnzDAkBR^dnhZ#orbw)npuykxU=tY zpjn_ueu_KIvJW;}z9~d;=fcVM=C5CiQrszev!?k`l%Tj1eY&W5TgE%Ilgb|H&4Vd% z5PS6a-pRk)9g7#QmeknJ9_bp$`)o>*&u_84yVk|N1o`|;@5gGD#}p->zc2p`ErVMj z^7-Ao7i#TK=Ov$?EpVmQ=wuG^`G*>8(AMS2Og`Uj(Pr&O{|w~wQ{~#KaeTp^alVi2 zUwvOW_K9=-$Mn6galdg|=NnqVf$PYhxW2fcjSbjF{^Vkf<65JF`^cXZ+4P52vfW|o z$Ih>{T?=~^O8wZ*UDjwbPpE!u^U@2n%14h;KQ<_7igw~rIQ3&gUkuaS<=ip+$)?*K zvO=Pg{R--U2~VsEUqW*roLRNiIG)L~65>wbz8S@o0(mPU z?nJ!IAR4S*dKlmGHE%y#KN$jNbLOB79e=OFkmo zq`q`#)8}7&#CUBh-PsiG=q>cEx9QHNE$=TW zd>8iYb3Yln@Hn(U-MU(V1K-J?OVw^3rFjW`0oP;(iSm z$hA1~Y(d%gNF2RJyZ@&e7ysU2yS8kh9gT~hh5VsSOQpue*;*af-VFOr{^XCO3);vT zU&){3>wQD3Q#YCX3EC}>)2;i({%-ripdF7Hcg6dQ-W{%yKe=RP68XzsCV#SZL1y9m z_5%5nQ{6I)soTzyKgnJ=lju9-6#0`hZ!!pfd4@LHiFrDmNIgD`{7LW5K4R;GQ1T~e zlROr-p11I?K4ZaprUd-_@RYfuLa{~7^KwoJ{n(N}YMSvIhfv({`q192`FI$`ohgk6 zo4>suNpWXOM4%aMj-j}-u+&U*)?zi6RU!9$b3&#diaSA*mzZ7;CR5zmUvq_7;@mW9 zCr(XPnRlhy^_NHE!ibZN2AYY9}8`u9kQF z1X4Tk_gk#(E-{|k$+9uCw9bbDsGam(F;UCmJA&FtV4uF)uPujCJ6V~lskT3OFtwA^ ze$_OWkAtY4AjYvqhy{F>$iMTfB#wZok8YO_U07n1z#1^_2U`1z);_ki-}tlsKlUKZc>I~h z0@$0t{IkB_sn(ms(tP1Gj#xf)o{eGin>;r|3KYI8z=u1>g}_em_|>mNQuXU5tmB=Z zjnS;*1#3TWW2!;sge_BP?7y;%gZa8~nMxST__(=OtlB*%jrFYY7vBrt)n$#vf93w} z+Q;66j62_?672t3{DR-kv1Ni9S6ccZKkFCa{2acYF+`rL!}m5?P`goma8WNBwM0>}Pjk zTJO!Y&W+@}np)?&ExPNA;5zqwWT$gI@2j0k=X!3rEtSso{ImJMpUr1le=9+KmUY}C z(1uaZiyK}dM*Sbnl1OZwKewKZX`M^|E9Z!!p3nEbD9}!}P(QMY>99rRwP^9EO!6QiEXr{5^|klYoh=WJ6qlAWk$`=pHm?b-S}j`jB) z>+fRLvs{;8LKI@0T zuMCxmww*Ar0x|Z>a60xaj*x$gHOYHh77#O@s50-h&L_`oR?o`OKCf`xrfitiDX+-b zQrVWHM?TTFud+F|UjgCr&W*~?Ik2#pluf;3_twQlmGkP|$GMadO)slD*(CQu4tL8% z`B!zSEZz)Mb%--GbkD+M5B9$|%e|G>dq*@LDV!^>CGJsTkoagQ?pwHzIQ8~-N{{c| zRrnVQA%5ihs|eU|gSbY6R-#Afd*Uypn~IFBJ*fQm!yAj8g|iT2-#R}F`|GvCcPKyh z-7{malaRJyzxjLpve-Dzm;QFjg^MC)(>Kar=*v0b`RG1z@rS3ywyEL7t!JDN&Fk(U zwsQ{`?I*1x?lZ;|R|c*jE>Z7@IJ;myG0sZjJ5rY&E2|Z2rtZ+py`Z7it+KjX)5oi) zw!5Lab93OG3EGw4)LopDh6HO<=BPV5)A+B{7OYq4kH&7*Le{AKe$D>S!Z)aLj#fLN z^}4CbKm6m8HoT>}8}wYe+gflvb!RBf)WW^4XeT(^knhXJxmA3RD$cXw`&Dty72msx zzGz^9;sSqLrRxY*PuU)vTf4Qp2jzKlajn+VCp~fSj%C_pJu|U!daf39CI|8Ox>K~6S$T;I#SGPw z1{EZB`qEar+PMhvp0Sm+Yz@>q)=XPWJ1c)1hMhP|)@f-)4UBVfCmdW%jPr6=iaW$O zuPkutk0Z$QRL+^N8hr9FxX6q2B4X>-ir^P9exm5Gnw7u}Oh55(;0ogKfb^nN?Hk1R z^ZSadf%a79m8yb2T{w%(KbcewW)<1FZceTCLLZU4$0zJIs7ZmoA8 zz^e*iJ9S)*%zA&ETFmZqK;Sj@uRPx#RYR`$SOB@MCxGdg{L{ zQSEbXR(Y4!E7gYIj&##=2=zU#d@uKY&6E3DW&WGXTy*>IIf-NC-m=tdvJkf!EAI$i z;72^!QSNnH;6rS^Pvq}#pOp0uEbHALf90+dv`@aD)ovX z>U&YGXYKwS&ag$iv<#Az2SdlFZ|za&$#srfq&=uQGexpE$f+n|LXJf$~Ju|c(3Sk-xs1!*Zvek zM|OT9j(k;jyau zwrjVF4;zmVV>~!FK7`nz=xkehs#D`^`R~Vevz7CBOha4wx$9T7J$L<6c}7i&J(urf zvDrCeNP3(7E#%qk{9Z^uHl{2+7x@n-W+X;AbM5VjQNE~rjrv7+?*0eA6T_Z8{?mwI zr_ZyF#IQegn`*>(uOi(l5aWG09reKZQ9oP`>W#}see!cr&ukCspY4P$Y(LN21TS^e zd2cM3_soKMFD;n&*n)ZQEtvP@f_bklnD_94@m|>53+6q)VBQN1<~_n--a8EDJ;h+& zYYgT+$Y9=^4CXz{oQ}QBoF99f!Myhw%zL82yjL2`d#J&@w;IfQuEBUO?8OH29&Ir1 z-3IfXZZPll2J;?pFz*cqqyE`Wo=-!1+>v{t;o-vcto`pp#L{_{h+#vWIhBc9?HyrD zPtI5AANjA87PtKhQl2(nii(}Vd5K#dFCa>2If?x$<`KurXCY1#kVAy5@gttGBC8l5 z>_uF2Z)R~KM_S@};hDtZk!gsN&t#H!E+m<-)BRj#k=6YLajTPAg}qY@aknEmM7=H7 z&DkCjTaO&lAMI^&KWs-PDN#!pDgD?V1vYubU^#FRO^x7T#pz^}ijq<@r5BsO@hP zuY}vmEFsT%<7aJlJZrO|b@K~0+g>$}u-RPU(G}afgr>f3d&ivv6K(Gv^8B%AmR8kC znx{|1h4iYfKK6Plwog=bXxHzl_#CL}Hu&umQKzV?bI)&&#pxAFi_5bU#mDVRqnW!B z#ImYNyT^Uv#HXrC)A5&MM4S0a>vsu}!r5Q7fwsL0X`6QKC0%j`2OTaDTbOvpYG1Rr zqi-c>QK!}fGkE7D4ZO;KqggiFcjDf$o6Pl54g%?aEZJn{+T}((q1gs=Z3kcC(?!;p z`6DtC2WrdAFznTo`423aXAY3_ao|xMrvo_N1F{g7bAY0r<)lNQj)mOt9oX& zvSoeUw#fSo4JH_T+%W3}ha<+@(U;gR>Wz%84JtIoWt zZCSpDc**nA+BMfB#NR}SHtKFT@y@WFTE^&8#PPe=Y6X(d5+^oUpyl>CPh2!{vNpf) zIpX1c25CQ3tw+BPNy3?dnif2c6qn=0|cpWlB4|eA!Xw_PPGElg{lnq^*n2?fLNYv^uwQ`*m(Q zw|~z8@{G5X?_z`8cZ2T*ei-Wnm{-X=E_a5hZ)cFaYci;m`tCYyE2tMZsJ_R;IScD; z+ohvXfu`iJtjt5ifa`?j5fCK)E;8Ay=lGX6GzE%YNVP& zyg6eD-G13j;_TOo>!+(sBd*h+xE|;-nK(yqF}<99pvu3js2&6<0sAp!>e`INu2fEnV z4W#_gYw83_d)%aLXeXJMPbEhCaeuXp813rv zy=}y3Z*dQg5ThMtGee2dKEq#y6QkW`?s1YB?K#ZlEHT=-%kc}uX#cn6ol1BvzKi^h z*NO4HTrTT|SMpDbmt~+`i%98b$O;yL083hr9VkqQI(09 z#cczzjN1%i9JeLJK5k=(iQM+0N>|Zxr}9ouA}9{PB;<9`o)_t$50N; zexBUsy-P9o84|h;>Jt;`V^}#q9)fjoT069k(mQL2hq| zkK7IsH@STxo^rcIoaOe6_{;4aahcmc;x&I4h~xNP&^8d?neX;5VUEqIzMX7e>zP}2 zs_)KG>t?1dtiGM;dq$gAr>O7r^1x~4FT2$DyK?J1^GvY%t{2o_W{!1H-+Q%+Ys`1< z$`7n>x50F*q5Q-46`RcD<;rigirZv*rdIw0ed%n8zSIuU#~!pY12OvEQ4jo8yOn)% zPDfvz^G|*hDURvtZ}(l1=cc#wq5KE>#fdxetSY?k%{>X?i-Q;OuX7Vc(i#uq0a3x;y+fz~EwhM7w@28?`KDpmm=4mbaleCKOc-%jDGdoK$Qpm?Q2(5Ip~KoqkqnM&~N9zMSq^lL_eROh5kR=fN=rahVcU1 zjBy0N3&t1xju?0FyVsTDkrwwU` zs?OJ}%__cTQ(EL2pF=orP#SH~^N2ytO1n3w3W#ZSl%~hN6&35+E3NNdEiK#))dqN; z1a;2yBw(H=0rNZwnCD5rJWm4Vc@i+slYn`i1dR5Hc@i+slYn`i1kCd!V4f!d^E?Td z=SjdkPXgw75-`t`a60B0I6vkez&uX^=6Mn@&y#?8o&?PEBw(H=0pqN*I6;kP&ukRIy zy%Yyr*(ol@f290%#Zr+l`#o`|D@(+!%KzYiH}7nD`fN~)zYS{mhSE{yk{pWhtlmkl zDIGS{x~mwrF~9bEX3Mjq`77Js-fQ*NR_5dnX>@*8Qek_YZ2+@v$ip_{Z~0wNCch(| z#qZv3Z@9e6M!i?MH{l}JbM-Ebb{!Kx!cyKb{5x)-&6K`e!?#ON#wrmi8HD zX}4jP_8ewy=T^4lF)V*;Sj)70FJYE;5@u;XVb*qKWlJ8z^0(G+FwD|E!z}HVIHf&P z9&YFVWSb}3Qocd5IprIqcS-pM!>r$(mH)yw7-sbeR{jhAf&Mn-y~2>6-`DcDq+NofmZANbGuoWJD9EWYtC#jO8+v(zv8kNIXT zamU&o4Cv0W+nUD`XRYnc_(^}*+6S<JN zx7IQboA^6CLzYANxg5*i{*N;8|7H1_w1>-=Z2ennnHA(bk1aph{Qv#i3S@&yx4w(@ z9c}jGxwbOvxuq5;AMZTT$Bww*)&n6fz28%wY0pZUe^!nquICnLh8t&z!-{V)<-f!- z&6NL-Smrh5-%x$ZGE7-kC6q7A4#j`*k9=k*o&iQWo&iRFJOj3%96SSz^6@ViY50H0 zkG%LBFv{R(plmz?>G;QzUdfVQvy`KueB{MDS)Qxm8Az9TH9SMwkVlrGS?m|E3wcnN zmiHB?2c#pvrG8L8rORjHxx`4rGf)=t;%~qxL)uTzK-pI9(0)*Uitfa)59#<@nNDpU zX^Q{RHef5-C;lGggYiyyE*S3$d%&mz*a=46z*aEo47P$%m#`Hq%OKssT=!tsozw9Q z&W~q+Q4XE~M)~*`j5Pc|F!JIVV3dJpfMGwL0Zw@@PAA<{^3yZGu-#HVJp<`7jh+EU z9a!w7XCPf^l4heSN9oS#mU^IPa5kh`d!X7Z{8Fc|h{liu;>I`)Uh9Z&41O0Y>@w7mPIgKjcSV{0$go@H1F73%>-j2rd&x)h_Iv94j{ONC< zci0ipcrslMoJ&n7KdXFL0yNYdH<<;#-fZ@0=$q<2m9BRi4*)=tGJ=gdgODF0d=#dvO? z?22K}?QiMnZ(*nZBgL@)%`L@vuiIA@<9#_D^}zX2KU@y#jmt-U@^ewoY!B+6?Sw9D zKkIe;!fu;(VAc-I+JRX+Flz^9?ZB)Zn6(45c3{>H%-T`@6z#yQ9hkKPvvy$C4$Rt7 z{uJ%NtR1K0-8nz%1kBojSv$&~q8*sE1G9Eu)(*_tfmu7spQ0U@wF9$uVAc-I+JRX+ zFlz_4YIn7{qfuvyKfOzzn+`_UO2zvdI2bMVDBcrhZzLX5e0KkLo%zI)Z#w5`Htnm< ze>-jJ7oE#AbA8mC%WoOao#^yYZ&2nRoZVe9@?=P#qhD`HYl#VHkRHQAf5XXVD4jpx$gnyJ_(rp zIhg%Cr>FFDD1S=-hssIm7g6~s{Uv&CN;2e$ObY}z5+ z(to3RKpz|FtR0xO1G9Eu)(*_tQT~)M0@$jZr4M6R`Zk88&tq8nLWZS}WLWx6hNVws zSo&Iqr4MGHpO(@uB2MWSQJ$235&dmSACJmR>HE>MQu>5sLrPzfY-6_cE$LnOZ!LXM z!_o&cEPXR#w$0L)`yX}n-?mNtw7+fJmi{X2zj0s1>;I6rZ`I4NXlGdZIfkYGV_5n{ zhNZt`So%?hrGI5u`dx;lKW13^Y2Mi z%dzwisXqC+mi{Ewe@g$2bV2_OF~u@A|0{kw%#uIsFO2>FSwA0Uom;T@|FECTMf|gI zA=go7v}BeJTEy`~Oz9`g1E=Vh8ys9t&9Gi}o}>j-8Y z!K@>gb>wu^1LsHmfLTW{>j-8Y!K@>gbp*4HVAc`LI)Yh8FzX0r9l@+4m~{lRj$o^f zLB+r84?j+%_BN>ccl}!NK;qTozU$6C6<3M*uHRX%xOE9~e-O7{ct&`H!dIb$}o}>j-8Y!K@>gbp*4HVAc`LI&wPd zf%Bt&z^o&fbp*4HVAc`LI)Yh8FzX0r9l@+4m~{lRj$qai%sPTuN3d1L+`fGc=MHPB zjb+T**GO8dcu%FiMv2RcQ}yj@d{4EG@+{oZ*SJGtTbo?2!j>yA0f>}o} z>j-8Y!K@>gbp*4HVAc`LI)Yh8FzX0r9l@+4m~{lRj$qai%sO&9>Vfm4e!#3Fm~{lR zj$qai%sPTuM=isO59Hm=TBJpEK>W7&Sid5d&0PFz&HV0jl~_I<^} z-MSjnVidO>*VUGO_C;4){%*~?*~&?~ubZv>*wo!^&mCH$yUm`{L%ZATY&XBV&Hkn< zyW8Fi>03Lf_d@=``4yv_jqhgBJEHt+rxfG4-B&7xJu62mhMhyZDu(^PH&=}J+Syn! z-j~x+51b$M!{wmfxO~(nKNt1P_MraRPUyn+vtH2gXUsYx59}o}>j-8Y!B!o86I;k}(=cj#Xgkc0w1npY?){KV#Mrd00m<>j-8Y!K@>gbp*4HVAc`LI)Yh8 zFzX0r9l@+4m~{lRj$qai%sPTuM@~mQaDLPem~{lRj$qai%sPTuM=Vk+lieHWuw8O0StT#VAy6=x}u)+k;_vEAylw)FmPuD1MX zhq~Iz*>la+R{qpnZno!U>gHy%r|&{Ho1Lllx!LUhY`WRr3+au|E+pHK-+!)RlvA(0 zVw69ksA4?V%|S8jsg|&S{uXv-x}+HPH#({q@73(EV!SV>qaHXv>W9lgy>a=dPkt`y zne9RSvz^d|?PtB9|@=%sPTuM=}o}>j-8Y!K@>gbp*4HVAc`L zI)be_9?RintatgH+SQ>#UdF;|iW}AOGA@o%yn3XUv23T}k|AD3zevT-uHMES`>pi1 zyLx#W>+&kDf7RPKuPZ)m_!tWtC|}qfRY%NAA8BY( zyTUx@_9==n{~32wG3G`0yitt#(x4onlpph`uj(kq{OaM}iZSo{aH3+&$L^S`81uAS z7AeO3EvI8%m-A!3m&?ICFqe<{VSX;=joBW|KeL^fe`fnJ|IF`&^t0)d{m4HrDunDu zIVZL%M)`jRD8_RqHB}6ILP{!zo%1s)hW%&LD#m+VbWn`<<#f~o=STf;IjA=-AN9%4 zMLn}UsDHK-y0HDM7j*m?vyRBaI)Yh8FzX0r9l@+4m~{lRj$qai%sPTuM=}qfRmW{xhZ#fj?5B3PZvQZ&$FGVjTpMPrTBvw>s^Lc8bBZ%pA8r_*6u(_C+}M`= z0R8RKH^Yq~RTP(PGs0NWTJeUnBaEIs6;G)+(&*Apai8rYZRvM1jS-%lQD?dm%mO`987}`5PQijB>_JP>k}o|DqVr ztz1ws>>2K?7?{eiKH@m^CS72|z59reKZQ9oP`>W#}see!cr&ukCspY4P$ zY(MJ-9e>8GBl570VAc`LI)Yh8FzX0r9l@+4m~{lRj$qai%sPTuM=XY4`t2}!f>6taf^WHVqn|4)Pz1J`Ln;^w2 z?3?MyD-@>-ZLaUzrudhME%hzC70;>F+LrG8y^Sq@r{(Qz<#>DkYAgR-lMc4$hPUWw zv&Ye|lg-X^GdtPrAF#iZ?Y)p5T0*@G@?T1NO7DVls-97d^0zNhjOPv=pcwYtZloA? zMwC+w`_mOrjQ7fsTQT03(@_tcAN9lKpx(Ir2eLl-xu|Eh2ldZ(LKn85^@5H+W7ZLQ zSVu7H2*z`vBbaprvyNca5zIP*Sw}GI2xc9@tRt9p1hbA{))CA)Ql1nY!K@>vqaHXv z>Icj^Ql1nY!K@>gbp*4HVAc`LI)Yh8FzX0r9l@+4m~{lRj$qc2@>q17u_VwqbJZan zYgc0K1{%$GC{FDWWK;@Lys>PM5ztcc#YRC!vHXhfwGJ}If3&B+t^emFW7wy2)SjC@ znq-U_aF)3J0h#{nH1VVMlMKDzDb?n?H!ubylp?-8tgg{CQ(@xYMNQ+(%iP2-?o~E+ zEX+#mH@u>;*YGFKQ?-=w#5Wyr*+GSj)up|OKUB$O^xN-AocJ=Mv1GO48Gm>ip&z^` zed%2n0q!d;9jV-%N*a5ajjR=ntUcjI`w+m!#$ zYM#cz;9JBO=Xe^1xE|c_E~VGMxkaBo z_a5=Y$8+_k8y*nP**{z#Fg9A{SvW~dnec+xb7vQ^xBE-tHj}H0bfaGp`>o9TVV$gwP;xA!=qRQ$o#AV(r5zl}5N<8w=F466R;(NcH5%ui9QTmSF(IWYq zN^kuAgV=CLv3*rX-6*ZN`&KV~@=#S~rC8ucCZI9kxC(I+*fUo2bD=(6kw*|z9; zKI7dO^{n-O<}&VYRCQ9LV^-rt8C8cvy80Qd8Y&x>7WXh(xT^S)!Op=5nev#*$y)NG z?s5GQ@y(!EJvJ$Uc;?(odT)D`KK{)iz3rP6Ha5z;R@C1vaQ;8+ooBdJ#o51YAa(~0KWO0ki z1y7#2rlkI>!Dp=btmLQ(Rf_f<>aQv}rdid3*9`i!WRHIZ&zkjVN%#5t7VQ_mv8v?Z zv#S;S!Ec|J{9LVi!8P|;TeAPs;KP1gS2C+>jiPz$E~_{w`4sJEZsd>XU(JbNY+1a^d7}?pv;T*Bj-d$^uObvV8)sGNMy?R zH=Y>Gao_$va;Kgh?hU5S0p|x(|I}W=%JLNHVYdVyK4^HV^ki_QQ%9zHF9iRq$LQQXwEdXe|JDlU=5en1 z+j)8X+xI#@ANP}%<8nP0>@q&rx%#T{x&8)=#^-s_K5T5vk^V3Jd&gofjPqn^FysHd zMli?S_;h^EP*0N!f~j-*(ZSSz@BYEe>*lJ#%-43-!Tzj|+jTUYC7$vxPCa|)y7Fv)3kQMx7;!{RUaPw)^k%+_iKZP zeLppQ^HA^)^-I&wF9m-#pfo-BUhow+l%{(=3U2ZG|F+jHH!b&{f7rA<&e21sNb zQ_tHM1ykqCX9iP$#oocpt9FlI=4(6aV1L%faacFUXFWYG>uf!&zjcy}^=wM@xXG#CjNr8sC#N-wg6l7toG$t@_@#1F(!#x;EBnW*6i{SM` zr=)(z1+Tn)N~(Bj@YHvwq@4!_H`;q@Zm-sPYVLnmSnVTrq+I9t z1(S09Lmr!y=SBNvHKTs|&szOtQ9tAC@lY`1k1q}8xE=ZhQ_r1;2UF*){e!9h(~7~& zYyBR<%-43-!Tzj|)-d*VX485@!R*49+q0!!K`tVd`^Kbk8J{z7Mc`(|?9ycN_eKEM(<0I0zcY|+l zI5Lg+F!-C+vchSJnxt>@4G&C z=XudSd0@)H}}u4!{vAP&#%um&-Tx++b-Yt&#&hhtp?=R z`47_uwdDur{&PnU&f~oO^58uF zQ8kC;<4zthB-eB8RYP)}+uu7R*T4SZA$eZ3`}(B6uUp3P_00Ib&N;5Hf9mmlL7l!| zsNeSy^YZ=0d~IhP?9ci*4(sOltf$9iovnxUw@z}g{)JU~=FjM# zM)%C;ivjod%;%ApHucQsm!JCg%IBTkpX-&+N9ztbIiIHvpL23Pe_dYbl-xda>M6PZ z#b2J1$C-C*?>zp#H}=lQJ>}irxt^gr_sMm>dtjej|1)LxO?h6X-OqpedtP81&limE zd4%J7exV-EJJjjz^~bYrc-U z@~*D=`fB6TUGsI6WkSe(lsfU+=yDNcVhw*r-8| ze0_MqO+9jZ?{YnJ|Iwp*=5c1f)H9F2bB$j4xE;&p?)7T#D|_WSm;bF-uK&S>z4E+h z_xg(dUUxB$*JF(DbsER@`i*+LuA@$`_o(0NK<4H3A@jAJb+A9{<2bCF8&o zKA-phcQBvZjrWM(A^AN2tY$Eu^Y7LT=JVfn&I|VEeBn5pM;xE?i^t`>V?CUYtdsMU z^>hAmUbL^jGv-MDjU$2?=iIizjQ>G}V2*qDr|}yp^^|`)m^y!(8%+HjX9qK{Zr2Ah zU)xy+`?Efd!@4;>>*;Y>XX|18t&?1=pXI7!7(rTmunQvIFmNN#u)$eEb+KI`dmS!e5E{jHN+te@{+z7Dz0_w~v3zpq=q7x;SS z`+~1?zDM}_=lg~43%+;we&PFw?<2ma`2OPii|u@`u|MB;9Ea~gj?ecakIVNa>*4#9 zb@DyS`uYClylD6JNq=9rjN|K>@qL|hTwnjxG~5 z&GA`JkIOn+59@E8dz|4d+F>pa1mt zyudh~FBsqR2*>sOLOq^$sMGTi^?ROTUY@_0ukEaZ{aGK!Vci^`_4K%`v-Pn4)=4hb zKcwt^_n$j973b6AUmKS0d_Q>cx?$;>z2pBWuhtlzYIY3Xb-?hn@Vwv&3x=mJZw|hD zml5f*CBciwmVHlrJ9yT|BT|>og4cE{dv0-UaNB1_=JqPh%f5$h?tk!&qw+X?ei)U< zUv|vseB2$UkIwZ}Df`^B&gpNB&h?M^kmny`F0}U?7EJ#$S_CuBd%yiw%$@O%{zov! z-ED3#^^BSkOr2+(6HNW{2M05+$NB{`U)xy+`?Efd!@4;>>*;Y>XX|18t&?1=zw)t@ z^Y7T3x=v0lcZ=WT$Bdes?rjh}<<`k*Y=_{dKAN1C^a-xI@07G+WblGxr=V{*+V z;5FlVr_xh{f4--8>U>^s>$Sbpb(aUvY1=2=e_QbD*Y`=k-50$2*FI_c#lg=GKQ#?{ zCb;4Ur>6Iw3qI|{vge65w;#EiF|9*L#(o6c~@i)BQFCVw*-u-huM|S9+>wI8f z|6KpIPYsXY|;88`N`%dVXo?IM!>8%~p%-xPI+8h6;W2%2r@C&CMo5o)p-1?1U(;l}3 zS39~>+UcI)Umxz2+lL>}IrlGrMdv)ug0-FV_@#$+$;YiSsY|Zs?0dW9I)8hiORoQi zH@oC{(cbZ{Ba1re|8DDG#%cFjD%u(U`Z2*AcWIqq>N)tMlA;fFu3QjI{l{D#%)CyV z9?X1gXC3U%`Zx~j=J>3q$7P+ZhxNBka+aX42uQYP;Y~Uml+B>l3`H zU%PboX~ECG+Ag=ZJmQGl{~vRX$m5LLu6-W=#2)SQaX-GUeXghZbM14T%RgtDLA zeV!NXYX-+0=|ADS{zaXPv-0v_#&6vunBxxmpkL94dS00wOr4X42UGv&Cj>LEe;pOf zd~IhP?9ci*4(sOltf$9iovnxUw@z}g{!nQ_7!t$rkR6+@B5`@8u37IuimxN#tp$6mexuq?LV^UKd?#dv^oVJb$jjf zL6_hI_pX!Mue+p9?%({2I(eLTj@d7dKmYpu@^RCO{c=55m#>@aY;a)RTz{=*b@RMv zuh}`~NdNoa8(P%HIQyI%%=jZK1#{f%pFO+iLp?i84W`bAx(8E#jaI?Tt6rmE=4(6a zV1L%faacFUXFWYG>uf!&zjcy}^CnC{_520w-Vo9qgMP@ z;`^)m1)EBIf1TCp_Y&V<-M8N^zh9P)*)G42?p(E9et%usYx~^({WII={(o+?Lwkl$aoSKl$ezrHm(QJ=l%7^Q|lG)eR3T6axnS6f7pRVJGqa)Bbe7itxdtaPQLG2zv#p3XZkh4 zyslO}9n9-(^vA)x4$t^9nAfN6yl(B!>)CO5ojX3Se~-)i!g_eWSSRlz>*xLDylB7s zivx-}>EHH(V8*$5?_kFNapC?&AC6o5^kC|_qHZvCw%bs*=tKQ?y%o&77Q7hDd~IhP z?9ci*4(sOltf$9iovnxUw@z}ge$HP#&fT}DfzQd-p9k~#Ij2Y5XUpg6k&A-)yj@eZ zdeNWH;Uzuf!&zjcy}^>cmb>yYaZU!Po`_`2n~ z#n&^}GrrEb&hhon^^flhu8VxXaJ}UFi0dfdUtC|=&UKglxgK*IuG1W!>o)-x% zZm+t>ySe`h$F9udG;01)9{;9=pXB3CdvaB-r&7u1xy~CKuFmzZp0GO4i}vk4{h_Fn z{`<@eW}F%0f*JqYPQe^^QJrAwsj=z%;%}*QpD%)`zwf)j%RIbF4n*B(iW*?Qrz2o>z`YsYi|tReL;(~%fjF~AGS!ZzY;v4cFR=# z^Wc|9w@ior9Q@PEEz_kt$33pQw``RzuN1uQFRjv=8o}-MX`Kew4!*p!b#5QJp>^(m zai2r;IQKqsXdZvxa&7W)PwCVq*E4i{n_TC+Gu!0)pSi6~o)_(34U9VJf8No-jI*F& zFyo)LPcX;r^jpQ^Hy`Tx>0iOr`TeKC)PLjq!OW}XyTQ!YcGkiEtdHZcZjR4-dR*4o zdRTw!Bp2&Hxo6{aQS-PzISpu>-Z)|NeajOYr!GT-pPtt^?J+fY)4Im#)LFr!jyO1- zzaV(ltb@~YWqa9h|MUI7ADmu%G5D&{P11pH1b_H(lXUxA!3TG5n%j4Is%h@OU;Soz zoD)l%N#{yFm<-LF_`+_`ExMy>UUKz^R=CIus`eLIINrFvz{K8b+(=d%GTdH z$;JAA+OJ+(vO4aE|FluPwAc1=e|wM4_0navf={1NFP+#X_>L#)rJGI)-gB1&)5E6) zw>$g5w8MG9-CsK}?R-gavm@%KGo}Y$vY>wY=(6C~YB$L3^RH}>`#*edvoZNBVDAu=)P~vT+*E3}*aKE)3?l z&kqfzo^gGGsdMZJ!PH;5V=(iYeN-^>wVidaKkMT-tefMro*tKVwjS2sI?2WQhjuzG z-?)5WM>5x~8_GxX; zPMbasZvVp2)S`Xd&(PuA;i==eVEzw#(I101eljYzZ+FExx&NZ-WAivWOglG^|LNlM z@^RmP{13UFbl&;7&NEk^pX+~T*Kv7Xv@cu|_e<0N!7r8ee41D}< z*5lIM%N}Qs-y5%6zfanD*pQ;n8~5#-c6k1@g1PS9`MA>yUijyFxqU%Mhl{=Jv>#}8~*9GCtRPj6i?;~e&D zvw|7_w`z?G=D5pN#rH(&={r8YqfzI{-|biQq5iIC*D08J9k;4>!OYio*1`U)kK?dz zj?a2}T-MooSbysz7wez(b4y zu|ut*|AQ-PrSGc-f7q&aI_jX{?{BW1I<*RZqe7iDr(JN}Np(`KlHf7x|F`|5zWe3= zXFR=M9_O0cb@TYYjjo%Id&C2Eb3G@0Qa9JRbYtCI|J?HX=XudS_u{CZ{>@JhW}M+& zf*HR~i(rnsW9?w-d1Uus>U?0kVCwJnKk@t*^LqcMVCHK(>tKJ@$8lIU$7ek~F6(SP ztiN@Vi}kl#QaK&otxmE22QI6e{xmZ9hR-Uea+d|qtym?!d`Ix=UR6?+CxUz4T_v@6 zHTaV4tEMR*246p{YMTCK@Odk$rd8htKihfV)c^b7eHQJT+rMp4E%z_?=W2PJmg}qK z@$WdIdOq$)7gf*oe7m4}u5<9q)pPyF{j++W7wuoPjN{V(oPC2CXWnnMi@7uYz%PP1 z?$K`rQ_m021XJfXj|Nl!b@vA|uWAc|nXm1vgZ)__$6?(ZpY`;(th4p7{?x%dC$$xKI=5Gmp{==5(?el_H?A|JMIWo9%*H&fs+y+m*y;ZvK%dd*Rz5mx% z>BAR-pFh2Idi#OkId7C*>)sjs-BE|82Db(u_3)v&eZT$NdbAM>%98;wz>X^ueZ(fqJ5v5>x(++zg^E@#<^;GFykNaNHE9k`(ZHk z{Jb%kI=8D5&+tH+Cf3Q{!pB7_&ba$6@?}p%}RgcT~`j5V_Z#wtN_lr6Y zp58aT)HC?jIepX0n!)$K)i-tfGM*)0U#VYOv?#dmnf+4fwZYS$>6bnq8+=Q{{%Pf@ z!4q%npAI-a_@$i(q^8FPSDQE>xBvXbfZTtNt^@NphtD6F$DjM_zZVl8g1f`ck*leAP!q&5yp_EnW7v z;0E7yOS8@mK5YN)X^#{5jmi`({oy#kIQjA0WmmCnx zy#8=dF!QyYb+A9{<2bCFf^%0+FjtZkBJ zwGaMi-=?YF*x(v{o2Es#2mf(i)3jlE@FV4$rK{HlzdX8Gn)Q3|ybqeC?t8{uemSvu zI(GAXyFArAw>M~VNbcW$<{^2UVH*y~X^UJ>{e>-Zoj3lYMXrDH`z`Xk zXzzD@%#r>h2L?0FCyjy`|F~b{wZw5Nz8y?G=PwMV&XJp6Z`A+rmC??;o|+NNd~IhP z?9ci*4(sOltf$9iovnxUw@z}g{$Ka3m!3W#KEu~kEBhYZKlqe3^-}Naf`^`6FRfY@ zeD~aX>4G1FEB;b1-Crv{x6>&Hrjts7PkHjd)ccg+R*mbYJB zO8-U=2Q$v?lY<$*LXTjM`)0#n>SG~5 z&GA`JkIOn+59@E85iIfi$2YM zs-D^$AAD=48fo--!7traBkeXb_>*00rpoh!mtIgay}H?6xdZeL(+OxxL*> zwQ~RNht$sFT=b{fdHi)BmHi)W^KlQ_uTHL~?7K*=^WIT)a{bqjuaoCR`-&rDF7#hp zA((LnytAg57vnGgYcR*X`jTMk*)TAeI@cZ>O#RK<1~adAErXe_?W}|SSs%w?-5j6w z^ti0E^|1cdNiNp^S;6~}%7lViNZbaUP0O0*dglGRX|A(+rDnPQ9cwqs^P>HYu`x&b|9x&S;~f7% zFynu^%Z8#(j=OKmVCs3SXE1d>H6ob$Crk`xUZXAvX1=zw4)$k#9EWvteAd(Bvd-4S z`dcTtSpTPIm)!$)RlMF_9@{?cbaHUJKeta+Y6qYARQq(rSMmC}{P(i|>n#rcxm!tE zdR=h6`$|%s^Mcz|PN_=2;IdoS)4&sghyIY#uuj2`pLt|%zoG26Bm2)kyh9%6-5WdP z@sC~GAs@H2;ZeDs>rXu@*I91-QMvwaCm)sPMSHJhF&FwDy)l?^UTYrjcg8uoFg{GWfXcn|7rV@>q7!FtPthWu;+Xm}xEBb8VZPRs0 zyM9Ypza^~S64q}C>$imUTf+J+Vf~h{eoI)tC9K~P)^7>xw}kau!ul;?{g$wPOIW|9 z?Rq}{+dZW^fti;cU|0_@tOpp@0}Sf{hV=l$dVpa)z_1=*SPw9)2N>1^4C?`g^#H?q zfMGqrupVGo53ud}kpJ6#&brf?m%emZUplNW9oCl)>r03ArNjEtVSVYazI0e$I;<}p z)|U?JONaHP!}`);ed(~ibXZ@y?Rw+?+r9VhF~PjtR|0ll3D|ulVE2`P-B$v3UkTWK zC1CfJfZbODc3%nDeI;P`m4Mw>0(M^s*nK5n_mzO%R|0ll3ESOY5clF?UhcmG zyZ;XC{yVVy@4)WA1H1nY?EX8j`|rT+zXQLu_W$-#VjbLn2X_A**!_3lE%)DX&obKG zrwn$VGT42}VD~A5-KPw8pEB5e%3${?gWabLcAqlXeac|>DTCdo40fL~*nP@i_bG$j zrwn$VGTYs+?Z17$IrnyCUhd}zyPqTMevYvFIl}Je2)myn?0$~0`#Hj!=KSBjoUDWU zIl}Je2)myn?0$~$misxn2QKaIdkeeoE$qIxu>0P^?t2Tn?=9@Ux3K%(!tQ$uyYDUR zzPGUZ-ooyC3%l=Q*tN9RB-e=Q*tN9M*Xb>pX{bp2IrNVV&o& z&U0AjIjr*>)_D%=Jco6j!#dAlo#(L5b6Dp&tn(b!c@FD5hjpIAI?rL9=k~#Q4(mLJ zb)LgI&taYCu+DQ>=Q*tN9M*Xb>pX{bp2IrNVV&o&&U0AjdC_OH^BmTB4(mLJb)LgI z&taYCu+DQ>=Q*tN9M*Xb|7o-H9M*Xb>pX{bp2IrNVV&o&&U0AjIjr*>)_D%=Jco6j z!#dAlo#(L5^P*2_IL~37=djLmSm!yc^BmTB4(mLJb)LgI&taYCu+DQ>=Q*tN9M*YW z@Mh;Ztn(Z$zu9>X>pU;|Z+4!;I?rL9=djLmSm!yc^Bn$Qv-2F*c@FD5hjpIAI?rL9 z=djLmSm!yc^BmTB4(mLJb)Lg|&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2w zIjrX#)^iT)IfwO}!+OqPJ?F5VbKCKR+aG^8tmhooa}Mh{hxMGpdd^`z=dhl0SkF1E z=N#5^4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT) zIfwO}!+OqPJ?F5Vb6C$gtmhoob8b7HaQovAhxMGpdd^`z=dhl0SkF1E=N#5^4(mCG z^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqP zJ?F5Vb6C$gtmhooa}Mh{hxMGpdd_Xf18IN!kg%R}SkF1E=N#5^4(mCG^_;_c&S5?0 zu%2^R&pE8;9M*FV>p6$@oWpv~VLj(Cz9~HCu%2^R&pE8;9M*FV>p6$@oWpv~VLj)t zo^x2wIjrX#)^iT)IfwO}!+OqPd|%eD=iGKYtMX6h4q}n zdd^`z=dhl0SkF1E=N#5^4(mCG^_;`xV*Pr~Y1eZO>p6$@oWpv~VLj)to^x2wIjrX# z)^iTysl$H`>p6$@oWpv~VLj)to^x2wIjrX#)^lz<9%K9CH-`0`!+OqPJ?F5Vb6C$g zO#S$lVLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gj7JgAIjrX#)^iT)IfwO} z!+OqPJ?Ajbiaa}Mh{hxMGpdd^`z=dhl0SkF1k`dg=-bK3Qs!+OqPJ?F5V zb6C$gtmhooa}Mh{hxMGp_*B_P0LHWG`%BL`?Q=(m=N#5^4(mCG^_;_c&S5?0u%2_< zeShgWr(MrEtmhooa}HAvesWmPIZXY&znB-EbK3Qs!+OqPJ?F5Vb6C$gtmhooa}Mh{ zhxMGpdd^`y!0gij;|FG63|P-Otmhooa}Mh{hxMGpdd^`z=dhl0SkF0(51D;HU_Ixs zo^x2wIjrX#)^l#VpZ|K!Y1eZO>p6!xE*^4N&pE8;9M*FV>p6$@oWpv~VLj)to^x2w zIm|laIfq$)&$D{YY1eZO>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5V zb6C$gtmhooa}Mh{hxMG>?)9ObbK3Qs!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z z=dhl0SkF1E=N#5^4(mCG^_;`xi+>d+cf72yo^x2wIjrX#)^iT)IfwO}!+OqPJ?F5V zbC}mTo>*AVIjrX#)^iT)IfwO}+m2_|{`gm6J?F5VbC~1eafS7q!_p6$@ zoWpv~VLj)to^x2wIm|laiG^8z>(p~jyPk7c&pE8;9M*FV>p6$@oWpv~VLj)to^zPb zc|6Q8pZ|E6VLj(C=Lp6$@oZF7a*#7v9VLj)to^x2wIZQqH zlVLsQF!keGhM5;0W?0WTtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#tx1b;ZJ=N#5^ z4(mCG^_;_c&S5?0FxOFd&S5?0u%2^R&pE8;9On8B&pE8;9M*FV>p6$@oZF5k-2V8( zVLj(Cp6$@ zoWo}|3C}sK=N#5^4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^zPr zH}IUpdd_Y4{H5odc0K2?o^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{ zhsnkI^_p6$@oWpv~VLj)to^x2w zIjrX#)^lzp6$@oWpv~VLj)to^x2wIjrX#)^iT) zIfwO}!+Oqb#}jUU{Nb>kb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG z^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqP zJ?F5Vb6C&0?RdiNk3SsNa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0 zu%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$g ztmhooa}Mh{w;j)_{qe8Ddd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&pE8; z9M*FV>p6$@oWpv~VLj)to^u%QA|7T~&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX# z)^iT)IfwO}!+Oqb$75`N{Kl}Jb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=Nx7| z@i4=B&S5?0u%2^R&pC{b6wf)V=N#5^4(mCG^_;_c&S5?0Fy2%==P>>yJm;{Ua~S_B zUUXQ`IjrX#)^iT)IfwO}!+OqPJ?FOL3AaD~a9Gbdtmhooa}Mh{hp7{9IjrX#W?p#C zVdjhH9M*FV>p6$@oWpv~VLj)to^zO7tY6PL?Rw5(J?F5Vb6C$gTz#|W9M*FV>p6$@ zoWpv~VLj)to^x2wIjrX#)^iTyPsY0r>p6$@oWpv~ZTJ19=bU!N!7C2yIfwO}!+OqP zJ?F5Vb6C$gtmhooa}Mh{hgml~=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&pE8; z9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+Oqb_xz>joOV6uu%2^R&pE8; z9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmho&b%G}u z)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}M*qz{3pdIfwO}!+Oqb$75`N{Khcj;5~-* zoWpv~VLj)to^x2wIjrX#)^iT)IfwO}!>k(~W?0WTtmhooa}Mh{hxMGpd`{vChxMGp zdd^`z=dhl0SkF1E=N#tq9G^MN=RBTsSkF1kc>&Kktmhooa}Mh{hxMGpdd^`z=dhl0 z+wp|kAAdNk=N#5^4(mCG^_;`hiMJfqa}F~vJm)a;#d8kpIfwO}!+OqPJ?F5Vb6C$g zOfJ^1=bUyu=dhl0SkF1k^$fmoSkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV z>p6$@oWpv~ZTJ19=bUyu=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&pFI`;yH)) zoWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z z=dhl0SkF1E=iGKY;r7QL4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)t zo^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E z=N#5^4(mCG^_<&|C*1z{!(lz=u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX# z)^iT)IfwO}!+OqPJ?Aikk?9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT) zIfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c z&f)%>J?F5Vb6C$gtmhoob8b7HaQovAhZzU2IL!F?#$i3@u%2^R&pE8;9M*FV>p6$@ zoWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxtD&o^x2w zIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C&0?RdiNk3SsNa}Mh{hxMGpdd^`z=dhl0n0etj zhxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWorA z;yH))oWpv~VLj)to^x2wIjrX#)^iT)IfwO}+m0vP{`kXTJ?F5Vb6C$gtmhooa}Mh{ zhnW|ib6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2^R z&pE8;9M*FV>p6$@oWs{__MF3d&S5?0u%2^R&pE8;+;%+S_QxL%>p6$@oWmR!4>_#o z9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{ zhxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&f&qEJ?F5VbKCKR+aG^8tmhooa}Mh{ zhxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~ zVLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhoob8b7HaQovAhxMGpdd^`z z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2w zIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd_Xf6K;R};jo@_SkF1E z=N#5^4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT) zIfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkJlbc*5p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqP zJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mC$9Z$IZ@rT2D&S5?0 zu%2^R&pE8;9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$g ztmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0w&Mx6KmKr7&pE8; z9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{ zhxMGpdd}ffHha!tJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkJlbc*5p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$g ztmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&$;b*!tIYg z9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{ zhxMGpdd^`z=dhl0SkF1E=N#5^4(mCG^_;_c&S5?0u%2^R&pE8;9M*FV>p8a_Pq_W@ zhr@c#VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z z=dhmhqR(c}IgGEn=Na+c6OZ?I(}MAP|L2xqyx$A&4aNsP_kmzM;kH-U)HnAZa&!MY z&OUn$%;UeAMG)uR5gUKkuz8*8jyThm`C#CwR=mLrTsV{=e-{ z9uiFdSO4d$qCevtwLF;d=id~}anBzUOg$^Q22p6$@oWpv~VLj)to^x2wIjrX#)^iT) zIfwO}!+OqPJ?F5Vb6C&0?Rd`Zf8ry-jC0A9V8)-{BbehJ*(jKL##acY&XYDgRE$IY zrK^IO*JU3DGhf?T2m7-=j>Eb+KI`dmS!e5E{jHN+tY6PLbJ24S>p6$@oWpv~VLj)t zo^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{w;j*9{jdFKalwr9?7U#c z|8`O^$Gx;?F!d~M5lo%eRS%~A7j_M1Uayo3X1=zw4)$k#9EWvteAd(Bvd-4S`dcTt zSihcg=A!2u)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E z=N#5^ZabcH`%j!5%sBJU3TFKG+5~gl(R&6{&s|^twfI}=yzrf1>VI%~F!OrknPBE? zJL_P7*2i&JH^*l^Jud5PJ*>ZVl8g20IcF|<&S5?0u%2^R&pE8;9M*FV>p6$@oWpv~ zVLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?FOLIk$hcYl0c)_yNI;KcQ(b$KAbLF!db0 zdS<*Ici%15cr}>%yDkl8UcH_OX1=zw4)$k#9EWvteAd(Bvd-4S`dcTtSihcg=A!2u z)^iSjSJFEjw{Cn^_;_c&S5?0u%2^R&pG_o+VGsi9eVdo^LD+U82`hieN*3+ z6ACV^*)J`h72J1Jzw~YA;D6oMFV|D@alf>nG-~_jul>@Im4ja{*FW{2Gp-ni_6rUP zrvI+bo?o;x&N=;p8UMwNf5^xEZhkQJ3>pzkoqMzkrvCA@f|=Kpiowj+cGkiEtdHZc zZjP_#oONKGtw+x}?Rw5(J?F5Vb6C$gtmhooa}Mh{hxMGpdd^`z=dhl0SkF1E=N#5^ z4(mCG^_;_c&S5?0u%2^R&$;b*&h3BRLBWi3_YYSU?Tr8C^T8bVtXqSr=hh2@sq_3Z zf~o&+CkHdH`?>`)U)xy+`?Efd!@4;>>*;Y>XX|18t&?1=U(Y#n(Q^*#IfwO}!+OqP zJ?F5Vb6C$gtmhooa}Ix2`JD8hJMJvjs@t@4QuFJA|F!O%RDM$MbzR1!lD@&iXOBs5 z9umB9<(RZ-``{CI8=DS!{f=Us&l`?S|8ryT%9dkOg+c$@UbTKO{XhBoFGYXG*=KPu z$u=2fF=F!QyYb+A9{<2ZWGSqDAmu%2^R&pE8; z9M*FV>p6$@oWpv~VLj)to^x2wIjrX#)^iT)IfwO}!+OqPJ?F5Vb6C$gtmhooa}Mh{ zhxMG>{>{> zV6ID-zZ}f<>NV?wxsH8e$MDi{eLJmUFxS14_YLNH*mkay?a%eI<8WQ=_*`#$T&}~d zhwFLk*;Y>XX|18t&?1+AK$+IURZxGtiKo5-wW&Sh4uHs z`g>vhy|DgXSbs09zZcfu3+wNN_4mU1dtv>(u>M|He=n@R*LM89_Q&4~>+gm2_rm&n zVg0?Z{$5yrFRZ^8*53>3?}hdE!uoq*{k^dMURZxGtiKmFFS6bmnYTVRMAd(e`b@!%U8PxnaHBuwHIhFE^~08`jGW z>*a>^a>HBhU$7;6T-MX$!X6j)xUk2CJud8V;VqBr@7vVi@7u7yZ^Qn+4g32x?C;yK zzi-3-z76~PHtg@)u)lA^{=NS{y{XZb={{dnD4+#5zK-m8S!u}r+_Wyve{|AKqKOpS?0b&0S z2>X9P*#85<{vXhG_Y3}S-|yJGcuj7}W=Ff(!Da`W9c*^6*}-N9n;mR+u-U<82b&#i zcCgvOW(S)cY<95O*}kp(57)eSO?tls?EMn3_e;RuF9CbM1nm71u=h*A-Y)@rzXa_4 z60rA6z}_zbd%pzi{SvVEOTgYQ0eim$?EMn3_eYTZQmB|d*Lu!w!sZB@BW#YaIl|^>`?hd@ zAUS&fE$scbu=n4>-hT^w|1IqOx3Kr$!rp%id;cx${kO39-@@L13w!@9?ESZ}_usW{#)4lZ(;Ahg}wh4HZNX>TVr#ik2%8T2%95pj<7kx<_Mc3Y>u!w!sZB@BW#Ya zIl|@$n~jjR&ndt@rvUq$0_<}N zu+J&LKBoZtoC54~3b4;9z&@t{`o(uMQ zF4*U}V4vrLeVz;Uc`n%JxnQ5?f_a;1o`}o`|?LPMk``jz+bFZ+^y}~~C3j5qE>~pWM&%MGv_X_*mE9`Tx@RC`_ zr$f(*+I;SncAtBNeeMj!}K1Hk$LVEq8F zegIfM0IVMX)(-&d2Y~eh!1@7T{Q$6j09Zc&tRKL3`~ddH4*=^2fb|2w`T=150I+@l zSU&))9{|=50P6>U^#j2A0bursLAsK9zuU_C0Z9u-)RitTt*?2ktU)}sRJQGxZSzYTVRMAd z5jIEI9AR^W%@H<7*c@SVgv}8)N7x);bF_V1@Zpf7zA0GW6s&Iw);9&~n}YRC!TP3P zeN(W$DOleWtZxd|HwEjPg0I=^n}YRC!TP3PeN(W$DOlf>?f9nbk8cXrHwEjPf;ld} zDOleWtZxd|HwEjPg7ru{X3*Int)XN9!<%9L|!Fu^%y?n4< zK3Fdwtd|eg%LnV_gZ1*kdih|ze6U_VST7%}mk-v<2kYg7_43({m(Tuq`Cz?#uwFh` zFCVOz57x^E>*a&>^1*ufV7+{>UOreaAFP)T*2@R$<%9L|!RE#5aBFOi^f5=+9AR^W z%@H<7*c@SVgv}8)N7x);bA-(iHb>YTVRMAd5jIELw*|iOJV(`u>Mk5 ze<`fL6xLq~>o0}%m%{o>Vg04>qUvMIj{R!!zR+Jv`=^V~OEaH;rD)e*O1u72Sbr(3 zztnd8rS`{P3hOV08Nd06W%;-rUVpw|>UpkPu>Ml|>o0}%m%{o>Vg04B{!&YTVRMAd z5jIELw*?O^IqG?a^*qCRo?$)D@EuRoOE;ZVy|@O`^Gv&*XIRfOjQ9AA>Cs=$Gwphw zVLi{Vo@ZFkGpy$s*7FSOd4}~o!+M@=$MbA|JkPM6XIRfOtmhfl^9<{GhV?wddY)nC zTe)M5ujiR|Ju!w!sZB@qwU**ubUk8;lujyVSV_pK73doKCBNP)`t)4!-w_Z z!}{=HefY3Gd{`eotPda7hY#z+hxOsZ`tV_W__pK2w?967SRX#D4%)ij;lujyVSV_pdGR{j8k-}1%n>$6*c@SVgv}8)N7x); zbA-(iHb>YTVRMAd5jIEI9AR^W&C&L4VP6Asbl(uzeM4aP4T0S^1a{vL*nLA__YHyF zHw1Ry5ZHY~VD}Ay-8Tew-w@b+Ltys}f!#L*cHa=#eM4aP4Y8elL+sDKA+Y;~!0sCY zyKe~Wz9F#thQRI{0=sVr?7kte`-Z^o8v?s;2<*Ngu=|FYTVRMAd5jIEI9AR^W%@H<7*c@SVw0&FH|AidSd0E5YusWIOvS*`NKDVE0#o-CqfIeu!w!sZB@ zBW#YaIl|^>`?j!87CE{P9qc}Iu=~)#?n4K=4;}12bg=u-!R|u`yAK`gK6J4A(82CQ z2fGg)>^^j``_RE3U)R3a=Mi=vI@o>aVE3W3oqg!+&pwYZ^^j``_RGeLkGJL z9qc}Iu=~)#?n4K=4;}12bg=u-!R|u`yAK`gK6J4A(81=#>u_sqj`T6d;x&B0VR?T{ zbEMrIVRMAd5jIEI9AR^W%@H<7*c@SVgv}8)N7x);bF_V1*iVog-LDgNzfRcwI$`(g zgx#+bcE3*8{W@Xy>xA8}6Xy44_UnY*uM>8^PT2iAVfX8V-LDgNzfRcwI$`(ggx#;x zcJ{lpKl^pU?$-&sUnlH-ov{0L!tU1zyI&{Fyx6Z3cE3*8{W@Xy>xA8}6L!B&*!?u!w z+U~xk^#5<&caTVr#ik2%8T2%95pj<7kx<_Mc3Y>u!w z!sZB@BW#YaIl|@$nkVfTNB-TxhS|99B^-(mNEhu!}jcK>(S{oi5te}~=w9d`eB z*!|yO_kV}o{~dP!ci8>kZD;>?`@h>d*!|yWcmH?T{oi5te}~=w9d`eB*!|yO_kV}o z{~dP!ci8>kVfTNB-TxhS|99B^-(mA2$E~qB(#ITObA-(iHb>YTVRMAd5jIEI9AR^W z%@H<7*c@SVgv}8)N7x)~CrA5}BW#YaIl|@$nu!w z!dvFZXXcA<4k%ueydM`FGq7OZr_~n*^ZtFT`kvavVOd9G}lIkIUzq_3*i8oqSGOKcAD%i}p2x zV~+Hn@Lm6+PR3bzc`)O*ZW7FK2Yt}5=tDiP%nqi`NyCGw|ML@qnb*IL3TD2xvkvxW zeH@2%b9~m*k>l3b9O+|@usOo!2%95pj<7kx<_Mc3Y>u!w!sZB@ zBW#YaIl|@$nYTVRMAd5jIEI9AR^W%@N)* zN4_Kc{=~52HOBXX&l(RenC}JMX9x4W;Op&16zzO3m^mnz?*$_s25=X-(kqP=G4 zm?Qn~e{X0}8{_PAZZPAItQ5>~uYdOJq7U`#Fg2JuAL<@V{WV$zGp~A$f|;-Ftb_eo zAID+c9G~^{xU94Fu>RIbF4k{eu!w!sZB@BW#YaIl|@$nA8TFYr5<=L>!Z^E|@uY@T2E9nA9%zk_)`;&(95Q~VC*`HSDdJg@OPnCClw2eX~u z!R*iPV2;D@V2;o4U>=v>!K{bh!K{i4|Hygc7AU)xy+`?Efd!@4;>>*;Y>XX|18t&?1=-@M3iYiy46F-O=OVRMAd z5jIEI9AR^W%@H<7*c@SVgv}8)N7x);bA-(iHb>h%-u!w!sZB@BW#Ya zIl|@$n&Ow|erJwA*FDFTa0Gn)vVF8oPE(RR$f6Ck4N7+OcW;#lfxLI5zEZOK`QLJEfiO3I6rr zPPu*f0iARI@>g`u<1AR)Igej@SeJa`7rNy7e|WP?o)_(YzoWn3 z?--}uYpJN8@vk2f%yF0238tQdKPoBuQ0K}8!PI}u)xpf`#OcAz*LK#y{;ZGVux^ge zdU{;e*?L%i>m(QJH!pJB8k-}1%n>$6*c@SVgv}8)N7x);bA-(iHb>YTVRMAd5jIEI z9AR^W&Czzh-u!w!sZB@BW#YaIl|@$n2^``JUdX^LfFo*Y-}=T^>BAZJ%`iZNaZ!-zWWcU-0T* z`=sp`2R}Rf)HLXs;EErdn%;XZ__Pzt_OsaBe&pi5xqt8d`{i*;FX@-Z-|%|BeB7pc z_s{hl*`a@~^MQf=bN#c2_RsU8{q&vUxb$ED<<7-?8K?d~f*F71Mb&`wqn-@85jm?oh<_Mc3 zY>u!w!sZB@BW#YaIl|@$nYTVRMAd5jIEI z9AR^W%@H<7*c@SVgv}8)N7x+UEpx1V?Bw*xH#-%t!%bZ$rW(s8?Kz1$C-XH)ZW2kcmy>p8P#X|A(&TlaMn0YNdA(;8v&N|qi^>G~5&GA`J zkIOn+59@E8u!w+Ri%IpY?&w5jIEI9AR^W%@H<7*c@SVgv}8)N7x);bA-(iHb;2N9EUtNtZYA; zO~rN8@vjX_cfKFIc-^pc&ECHk?XT7to@#as-gUt6wD7#(2@8g&FK-UMdzTUEvL(Tb z$BszXyd6C2;}NOLXTfW`jZ7tLgWEncGPhT0J}UP=_{LFroIXE{%HuCPW^_L8j?+iy zda67+I@dYYTVRMAd5jIEI9AR^W%@H<7*c@SVgv}8)N7x)~XC3U%`oQK0nu!w!sZB@BfMpf7alM@&y9cj0ZgRTevf#B7C#Skg zg6l7toF4ls_@#1F(%1XEQT*+Y)>G0|ErZt&osw=iK6vHrQ_7x04xak%lyvl<;6{5- z&F$4XPtE=Bnlv?!bNIZedHk_&PR+;N>-(v>o@%?6<~rXf6Z%{Kvf8D2UbOfAB=(n~ z|Ioh$GtP(S2Qz-BPQe^^uR6ihGxoRFiaAo}urtKJ@$8lIU z$7ek~F6(SPtiN@Vi}jlqIc|;3kv`@Knu!w!sZB@ zBW#YaIl|^>JL_P7)(196*c@SVgv}8)N7x);bA-(iHb>YTVRMAd5jIEI9N{f<>~Y(; zG;`(K#p~*bx#Q9imHt`q{O8A|#>WRQ{c&7+^y1)O4;`OQSP(pX#`skF&)^$AAD{OB zckuk*F}Ao8z;d9+!2t9@gJF$;JB3iyXJc=13oN zgv}8)N7x);bA-(iHb>YTVRMAd5jIEI9AR^W%@H<7*c@SVw4HUZKkEaVBW#YaIl|@$ znx1jIqrMwuyo6;crR@K*J0_HH-pbDyZ&rhVMX!U zoA$%7wDgGJr&|wCy+#B#n?5{Uab0k~&xWT)4+oDuZbWMNN^rNwN2GP{2lJfrCm#oY zGkauie|6_kx&LS9jLPHe`Rb@V{zbJ$=i@FKI6Bw!%AZE(I@`}5o$Ie(c0K95X#a6= z%!~fz8U-`Xq|KidjQ{!a_}t*Q_uU>$J$qgfOr7P<4yOK-`UEqtQ+oz8U)xy+`?Efd z!@4;>>*;Y>XX|18t&?1=-@M3iYiy46F-O=OVRMAd5jIEI9AR^W%@H<7*c@SVgv}8) zN7x);bA-(iHb>i82m7-=usOo!2%95pj<7kx<_Mc3Y>u!w!sZB@BW#YaIl|@$Z<*tV zH}}uyh2?km&*zIa&-TyfkuKl&&*zsJtp?=t&JWWDwdDur{&PnU&f~oO^58uFQ8kC;<4zthB-eB8RYP)}+uu7R*T4SZ zA$eZ3d%mE*=Ml#7{KEL2cQ~%+BkJ)yMV+3%sNeG%^YVPhd~IhP?9ci*4(sOltf$9i zovnxUw@z}ge)A&7t+6@M#~fjEgv}8)N7x);bA-(iHb>YTVRMAd5jIEI9AR^W%@H<7 z*c@&5d}ofdnu!w!sZB@BW#ZFmN_o0(ldV#x^=&v z`TNoCB|Y=^raGg0=I>Jj?(dnuXT7wkXa4^6Q~zH1d)e;K^~&GZ)*W(k{vLPuoRjnS zyUQz`lG}$)Jtg=`=e#d-mXC3U%`Zx~j=J>3q z$7P+ZhxNBkaYTZD$?q@Ao@%q}?20bA-*Y_}k4n!sZB@BW#YaIl|@$n1>7I{*FSw~kZtq>LXYN0GRL?xl?3a4x@prD#D<8LG z*=yK(dSBTq*SY*}y>k5zF6@=(Mf;*bF)#YRd{8js9QkATju?O5vS5yT-fh9u^Y%r- z)cNw6!PH-|cQEs+-6NR!+Ri%IpY?GZ*3I!*PmjwwTMz4Ro#bNu=0%QMV{@dBIl|@$ znu!w!sZB@BW#YaIoi%T*q`-*%@H<7*c@SVgv}8) zN7x);bA-(iHb>YTVRMAd5jID7%N+U4e7@?l#ruo*GNj>x;e& z=Ka2K@8^oY<#V7%i(oz<`W+X{=SIa-gZVt!d0;S~Gq&?NX@5SK9EZ;<$LDj*IX>&@aam{UVg0R>T&&-`$Z>0Ij`T4{*c@SVgv}8) zN7x);bA-(iHb>YTVRMAd5jIEI9AR^W%@H<7+gS(uvp%pn!sZB@BW#W^b&?Bgj<7kx z<_Mc3Y>u!w!sZB@BW#ZFmO1hrq1nkxi`Ny`pDV5k=DKv*bHQA%cK)0>qKUMVS z`nGo0V6JuTG%-nKv2;f}-gx#M%)?s2)Ew;rzZ zt&{Hs*3b6>=SBNvHKTs|&szOtQ9tAC@lY`1k1q}8xE=ZhQ_r1;2UF*){e!9h(~7~& zYyBR<%-43-!Tzj|o+fQ+!~uBeasOyN7x+U|Hs~WKwDKM z>sloU1{6e4%z~H&#K75m?PZ(VoFgJC5>;$KL_kpq0w&BkXKl0HAfCO~K^g<*)aESa zfQo_{ef8Cv|8mNeH^zIn@4MW7I>s6Ob)8x@YgWx!v-VsYP#$6B5mp{y-qHKJk$q;wJmVQ{xh6`9u8WCwYj6^Azvp^*M|8_4@q9dwhK^xJpsx2{($uPUV-fJeFNF& zdk7kr?X8vg5Z z9P`rWJLW4nagaXoksabD`@~b@5@-2C{N*Qkk^jmUd0ZGPkLW0mu<{5ikFfFxE03`9 z2rG}U@(3%Bu<{5ikFfFxE03`92rG}U@(3%BlI!!G@`zk{gq25Fd4!cmSb2n%M_74; zl}A{4gq25Fd4!cmSb2n%M>x*opZ6G3-20XH9aG!~etr0u;-2s)TYI`cy!`Sp#l7Nl z4~!}98wc1L)_vyJ>x?b#Cubczwz#)E{lc-ueP)-ZewDA;WL%+tTeoqAoo)J$E9{Rr zdt5PY+q=gV{;c`PxWdnuUmREX|Kw}qig_W|eIWX}C&Z5K53#R%MaI>ABmU?f5r3IE03`92rG}U z@(3%Bu<{5ikFfFxE03`92rG}U@(3%Bu<{5ikFfG6x$ZNSN94*QtUSWXBdk2a$|I~i z!pbA8Ji^K&tUSWXBdk2a$|I~i!f_rK`}WY{d;43rKP=tv=={$M+D&)<-r>Yv z>Eb<_`kzync+KJI&ogqqXvse5j8*eL|8m;Rebe*$<~(g^|FqlXIoBO>M7lzj^9lzZ zmA0Rm^JjYnB2>#{aE zGhfMxgY=1y><~BEC!QLYILja6FF(nP{8zrn!_@%q_*wh+#wLHd>PMGvHs|8x)4hIj9x?UKq|akHzjE}$ z$UJHn$naBxc2dSSb#$;s7fS zu;KtK4zS_?D-N*Y04ol#;s7fSu;KtK4zS_?D-N*Y04ol#;sD2S(0o}BXaD`U%Agb9 z^gSgx`jVqlTm0op*LPm>n16fc{gtzJd)axH=Wni@c2559$dCE(oXW@7zvgm18{2_p z2bLXJc3|0oFWI$8s&U20WheFx`9F7Sm0oz*v+jd9wgcaL){^PRGhg!gZgYS0^yyJK zZ}H^PX{RM}zVMc1(|`1M(RIGqX1Vl&v%>d9&t5)#@0#abzRdWR=_i-w-`U=3l~(Bu zWAg9J%TIjMSg^)|H5RO~V2uSo9>#(-795YIIUU>gel{TAnuiM$7X{&Uv%cd0Z#13Og2aa`Q6Zt!bzFs;1o}Jx}KKb~oY6F+AzQvoB?|ZnAF9vJ=~cWfPW7STMukSefH@u)7+0 zSF9iV(01xxCE1L5v(Z}?^M&OnI+`ymKgIYN+Y#drEIYEvd|}xUV+WRRV(h@Ov!G4Q zH`b4R81+@>nrz0r`RFaHdKQ*_bTnUBev0ukwj;(*SaxKS`NFaz#ttms#MpslXF;2> z&*IpJL)U-2m~YJMUUQnuu@B2WI+`ymKgIYN+Yw_2mL1t-zOd|wu>)(q;)VGmx#k$_ zGw#;QUy~fU^8rcv(JN&b`!Vmh=O~w>BbE-n#T?uDJw{)0v24cn#S7{%7Wx`j&;FiV zI@+`7#JpgAkbXROG5(YX?_R_w=FLV=ty2uejD?PDieo#!$LLEgmQCaf@`5^yi;l*X z{_n}9qdksJ%+vwt#2n9EjBlHdo?5T<6SL_QYfQ{o=*Ye}w)1<8zT{%rM7|&|sKdDE zXk6+4o?JSr3FySUVEvJPJa;j^*;@5DU?*ldaajYYjP4pM!1$7t~ z9pqx=bV0dvRL9VddBJ)m{dn%07td-x#^-qO!PjB%zhHaT8J(Efx5vp#K{k>`NZ|jQ%10UiNrKTtg?wV|L%Od zVxMDno3TH#xy@nkSLZ+8p?uTj+tng28<&DS=HKY_e0lZSV)oy=4-78DgIYCeZyf8u zg&or=o6hyp*Ru(7k3&)B?9+jLy^;~Arq=?ybW@3fqdH5z?yJwb0E`C~eR*%uynA*(J9$hA6d)zuMYy6LyrSrRw z%bw{vA?s~^)*UiBYrOZV*{bH}_p2PAUDWLK><06*>yO7|oqL#nCck*xQQ3QEo|*ml zq|I^LUfK7XPRh#W=Sq|I_cfsPu)O7uoF09`LD^W#ANZb z0vu3$2D{O^z7kyx;th*#RFP>HNw;qq2?H>}TAl{S8~5 zl0>)4rfZR^;Xb#3d|?X#|J9XqqGZ5=zau5BGVv#xC&JF~8B z9lIUYbu`Ds)`_oY*0rq@U(c*-TgSehS=Y9XeLb_TZ5{i1W?kDl_VvuVwsq|5nRRXJ z*w-`b+SakJXV$f?V_(m#Yg@;@o>|w#U9o}{!#L)wz#*0Zhagmuh%wsoDbj#)F+qzCz$E;^t*9q&G^=#{!JZ4%m ztYiGNb)B$|VO!S;>lhtd*9q(Rrpq5}Z|gc?9mBS+6V@?o>pEc_!?vyy)-mhf)^)-< zhHYIZtYhrkx=vWfu&rxfWAK9OZDH|5{^M2?ef=6IF)x*!@AE@P%sN2_8Dk)a<7c01 z-z#ZqI_I2yW_IC)mg7H7Oin!TjBMITNHejn$ljDt-+57lx$`7X{(~Wy|9h!Zz*BQxZ0Ylh?i=}OW%Hj5az4iD;z{NoI{mCJUTglrC98{To-@?>Wvh!HnSaP{vAWpZ{DbEX z7?eG4{=s`#UA)}Y={Gb4ZG(ejy*Kk{h#%*Y>k zw0vgdk33pFGxA3sEuR_rBafEPjQo*D%V$RZ$fM;mBY))4@|lr8@@V;t*BCKM@H51) zSclP?^mQC!8}o1CALRmDZU-AM_8BL(X>suN%(}KX_b^#lhDz>)PVr>zQ?Jaq#uby0$p@dS+c)9DF^quA{lLj@?hzwXI`k*0rr; zXV$f?V`tX2tz&1_wXI`k*0rr;XX=ctV`tX2tz&1_wXI`k*0rq@XVx`2P^{okH}KQt z#FBN44(A%{7`Aoo>ln6m?duq}b)B$|VO!U}j$vEZzK&sA*S?NnTi3phVO!U}j$vEZ zzK&u1jrN+a<4~7;9f!K)>p0XUU&o;?`8p1D$=7kHOTLanUGjAt>XNVHP?vlihq~nJ zIMk&D*IN;{1>%|DKRLI0f5QethbC(s*D;x$epnCx*mm9IoLcWHeARdB+3#+0{!8uD5&*{r9&kC!Gea>ip$PTPO9Ow|D;AD?2iV^Iuok zvyflA+X03C;d>lX*g1MupThpt|2(o7w_)y}!k_n6JGSt1$|l1L{|{VlWWpJRKV9w_ ziM$R*Zu2U^=-a%Uv19Xc#=gzVnQ?7iW%TjK=H-l^HZN!Vw|O~-c{wv*=@SRpAwIHC z+%zunlt08-eiDEAPhOO-H=1sq?6${6p0AdJH&3QEZC%CB6K>hUK6f7IeC18ulEYU% z!}*(o%E^@v-ROMc-D%QyK+SpEN!uiYyFc!n{`1etv{m!`cIveYpI=?hyd>}N@V@0U#&%*u-$Mq`4?fFEX!k>Fb_b>c>>7*kH|F@pX=c;@i4qNjm&WvmGa>gHwWByx6=tu-CM|VC^qh`wQ0og0;V3?JrpS3)cREwZCBPFIf8v*8YOEzhLbzSo;gs z{(`l?VC^qh`%7}xt@K&Xu=W?M{RL}(!P;N2_7|-E1#5r7+F!8t7p(mSYk$GoU$FKU zto;Rt{Z-^kYf`ym9V&OQatAASuyO}0cd&8?D|fJR2P=25atAASuyO}0cd&8?D|fJR z2P=25awoZJ&j0k0GlIW;)j_wwcZ~i+QGV&2o|H zT(caRo#I?8Yip+P$JSEer>(KVe_MP0ISl`8OypiCkt=uT zN9PFky}n^TI(P8L&nf(g&MExY`Nh0+t`&0TD}CZ1JH$u!iJQhHp7Mt{%THTlh5zJ5 z`Lg<->0Gn=pXpq)`k(1sv-+RuT(kP0>0Eo^xL%pgHLL%b&NZw5S#*Axo#I?8x6{I~jF%*)PesI=# zXBa!Ib6EQeW?c3Kto;S!C;JP=fA$v~=H;yYgghOfPPpfE)VO(Ijj@6AJ&O;SSQY5oj8Ye;{I!$ zU_Y!ApKmxrtH{GTaSnUjIqY%gu*YlYhdu5b_P8_tv)9lG_20(|_22DqUU06V6Y9S+ z=L_c=@=*VsIgdEkkcay39O}O_G32~MC)9uEQ2(7n{dayLum8@W{yT^I?;PsC`>*IX;$y-w1XSD zeADZX$R?ifPL*fxyXP<2;I{WV5BcPn?8(}A=UJVO%Pu>%eU-cVu1Af?rhnO^9{W$7 zITEfDn@$Nk=-9K)JZmd~?P(^Vu1nZ7$Bt#pdYD9RH{%`TnJM zWsNQB^(4+$yjJNeSTm}btR>Y<f}iCi@kR?UR*Kbm90=PdGK@`TS{u<0j!E`!ZZ!soS+yM)hiu#KD0f5PTZ zVrQ1K`I+!}5V`s9_cO4KiQMY|a-DJL)9=X+{T__{XwBeH89Dy&`3S~O@&e<(jp1zj zu8`Z=SLoZBSlF?%vaoMwDD(1h?QAXlu`{>u)6U|;e>=O2dD+=r%on-hfWG2`9mNg% ziYMbL&iJGFFMSy1TPS&;A<5c}co&e_g_V%%_d=W;s>3O~c$o%?TRK@r1n z*XnBnIiHEJk3OH3VC?W23dTO4tzgF08HYc7c0-Pze0GEJKRV+IId_%PCl0bhd}N=v zXsGMV=VH*{vv0@kTVYMSlTJ!jANe;KWCeSGY)x&?UO`j+?uCsk?4%O zY*?2>XWTo<#tCN}&kp%^{e&})XV=WuO*rG=Q!eWW*NHjf&_{Bu(VoI*-|xhAVe&=cJ5lDJ*EC`bhxMHCJ-`3% z@2~1z-oN4dW&i#LJu2r6eGYSsnfEE`{r>357tNl0f%W-s^Sut%A@}hAj_<#i7x$mq zYs@ib?Ylqjd-Ko2_E~k2yYF3Kefqu&_t;hP8}6~4!#%chxW{%5^KuUN*v{b|+d150 zJKN{bjJpf$hkI=2aF6XA?y;T2J+^bW$94|)*v{b|TXiFgzR$Txd_S4Kh4+tqf0O<| zyeNDpIr>g1adY4BcTxC$X%wp@is2&h9o=Y+dB36e%iOQR_Sre(z7e+1&KdWOuzhys zy}7e}cFwqOL>}H1)?oYWoN?a>+h^yD`$pJ4JDZ)3&g>(}xi^;nm-e2W&*12XdvCWN z?!BGEy|;6?_jV5V-tIs5+tdf_*q9mj!*ICwF2Uj6+d15OJBNF3=Wy>`mOtDN!}!Ua z28{nUhI5#gGxL=`ap0aAed5FYGfdpLABKr1_th|Q<{ld+{_>x^Siezx&rSIX_uf_X z!@ajN_vgx2xc7Fs&CBnH(GU0DHQ46m_rq|w_jbAN-;jqp9G8bX9OrO{n&b~ejmy9r zD{3ln3~}Sn#W?>r|9MaH>wk`QQTTI<{8?S%qd(hA9{IDt3;Q#<)MWJ8${pVmsIdBtrChr7=Eq;kN!IltHJ z!%B;xtzAC;!*?qqS6tC~&Q0%BHh4JaclUq0vd8E)E}yX2+m(N&ZF4&}y zi|hPUd2nLR|7^N=y3KVtzp;4Zbf+tG?)F8~^v4l7A6spn?!QIOE%sa{-SDN{=1Z3k zOZU66ncHmFY()A@hn#P3d3?Ih8B4l+$}K0P6W(Z=k2`%-de53UPulCm^xT7*xP0jT zC#D;n+t|7H)1%UB9&6-0eEJFL++}k9w9E17=RKEj`Kz5qq;Jev-1*%{hovL_l=EG! zhNkzvx|qukUSn{2=LI>x+4Sgi^x&L#eCLRChe0{Fo!QTFmh+L%^iCgsKIc7J_eziG zmfL)0vALC-x6E_bW!K*6Gfi?I=Jg($&VDJM<3>9VOFIqCc}e>>gWmWdpX17Fk4UdM zCg*$Rk4P_jGoSBTgGQ#iY@73U$Baw|-k8sQCHuFE9%-I){bnQ5cEj?y@BWkh`%Rzb zYeg37*pmg~7oFDw_z;u-(a^7LnBhz&T6EECZ?w`<>4VMl{Lbn9W##;f^10u>=j=*($$YJjdi|5iqzO5XTj}FU zi^2-Q+e*OoSRqXRW5Fy`}0Hp?<@QD&-t7;=2yC2kn_Gkv#|CotUU{B&%)ZXu=XshJqv5k!Y_tB3v189+Ox3s zEUY~XYtO>kv#|CotUU{B&%)ZXu=XshJqv5k!rG^>)-9}c3v1oNTDP#)Ev$75Yu&bTkTEcsztDB5v*DSs}{kkMX+iStXc%C z7Qw1Tuxb&kS_G>W!Ky{DY7wkj1gjRosztDBk?Sv{7X4<9p+=!EIcKicHmtP`Yi+|? z+pyL)thEhmZNpmIu+}!LwGC@+!&=+0);6rQ4Qp+~THCPJHmtP`$2BTu&6hZ6zOd#C zYre4N3v0fx<_l}Su;vSEzOd#CYre4N3v0fx<_l}Su;vSEzOd>Qa~C7me38fe|5M); z#|PHj;eW^Ti(G4t3+@HUnR~o1R2$J3qoY~@|2x%5&5QYJUa;yvtojeD{==&Oua$V>OZXd53Byes{gR+Kdkx>tNy!wsQ=_hXF75*a^)1c*mD~7uJKtJKl|_4 z8^rN}HAh(e53K$NR{sO5|AE#2!0LZs^*^xsA6Welto{d9{{yT4fz|)O>VIJMKd|~A zSpCnws~&52S>x9Js{cQ0@T6lmOmd#<%y&%oU3ISOaQ|gGerFr>YrpEp&&D?A+TGx| zwSyhkm!0U@-`EWPlo>1N7|)HKjcpcVpQi^E?ELd%FINZN*vk2(llQ9~+;K_g`&(R5TWO^){GRacs~@S^kF&{Y_B*#}x|u!W zY&J5p<#)MeJ0mX4-Nr;-g^@D`zeArfVC*mkI@sq2M#k@QJ6F_r27PQ`3putK1Gb+V zB6$gYf?Tz{)#}E@SYl@(yD=&KFD`^JjkLXr27Ae=R=BBe7B*VdW84 z9%1EC^8bqcYyYOqw9`)St$#ms+N@i8rx$JS|HjR<#T)fWZ@V<-^)Bj@p7T-8Z}se( zzS+tDUDRnS?%OXNcy!LY59yzFzdGl)Zy%7he=z6G<{y#X_G-@jyOUeb%6ZP;1{U(| z8~vrwe>ojg*lBt2;KKe6dk-nb{dwhM3V+tQKc_lhR?Zp!TQ$m=d5!wf|6SB+%vW;a zAbsK^JH$=)iKoUT&hm%&%TMwm{|~y?^gqx2-(uo`w9&eGJmKoSxj$d5_m_g7_nth~d@JFL9J$~&yQ!^%6Xyu->nth~d@JFL9J z%Dd#mP5Q(WR^DOd9ai39;NZ9GfvOtcFOAe#~(#l3e!V^GF=eF@9F^x_LKFyXD@c#^*fkr>`nMe3)~)edkshZ?}@`tkUtD%H|j6d`X}0Dox(XdG()vsBFLT z%C0l?&H0ti+vR-4@Ws-RhvdBTGE1cU^w0UbYZ?{ugVt}7N`L&NO;g#~;e#bp*`Ls) zd8%<~BEC!QLYILja6FF(nP{Qqf% zc}2cnth~d@JFL9J$~&yQ z!^%6Xyu->nth~d@JFL9J$~&yQ!^$-r=TYlHI^7vwP(qx_9Hry!;;53FggqFWj(7pFCFxC7Q{NR@%Z$ZzdhvKa<`G` zrAI#KeA`XK(<$3L;C$UR!_sTFo#A}!&O_7r$Ns~)$-RTqZ(pD8yu!Cfr>l<6`KGmx zN;~(;x!>+~XEG+|pU&=^{`_XnNB(qpI(K+(=g6B6ONZ=`+kgJLL(;8x$j4pn=Y!K} zgK~dfd8kL){Jz}JLmKr+_imH>e^Pc(y2j{yUNd&?p0=5le>ZQBvE9?puFb!{cX+ph z(kBkizvK61{~qbYW%KU=p53fxT6b5@lUp2`_N(OIjchcqSGxM-oTn_;CvCHQbN{|# zs}K97Gj`AU%Qucl`~D^8o!=Umt`Ye07Y3zY?Uu`j+9tGc{NV|s(mT87KEKxK#PrUq^10OYJu!Xi&3ulZ-7!2} zX-q!%Nhgg=cL;MI-lb>y%6qv^qn-dVr`I4M>So5%SiMIK; z$K2a19X287Ip_3F$G@BNmDlx6uiP;A`O(+=rws?^d`qVz)6<9LJni&>={|w?ed8}_ zyPz|t&5-oG4RW2w*BzR+o0Z!vFFq`td`ix1U36UfZR?!>{MzvJ#|v}cZk{;K6*2ebi$}`dY`F5AI{R`&+&a`|o;m+HqjcEjt{Qp1*I-Z~QnQ{XEF` ze6L@6(&Suz^z1(AYU}5Aw(8hB-E(Hny{_n$_BcHs_wpWxrAH3T{TYAsq3M17az87U zi^qq|oW}cc?NeB}hP7v5?O9lR7S^7HwP#`NSy+1()}Dp6XJPGGSbG-Mo^=j;7S^7H zwP#`NSy+1()}Dp6XJPGGSbG-Mo`tn%VeMI1dluH7g|%m4?O9lR7S^7HwP#`NSy+1( z)}Dp6XJPGGSbG-MK83YbVXakIYZca7g|${;tyNfS71mmXwN_!RRak2k)>?(NR$;AG zSZfv5T7~1asy&EY^#@k{fmMHC)gSntP=8?6A6WGVR{eohe_+)gSoH^1{ee|~VAUU3 z^#@k{fmMHC)gM^(2VPkHiRT-~L~_ntt#erG9M(FAwa#I!b6D#f);fo^&S9-{SnC|t zI)}B+VXbpm>m1fPhqcaOt#erG9M(FA<9Zdd=1vSXcUW_WHFsEZhc$OtbB8r|SaXLp zcUW_WHFsEZhc$OtbB8r|SaXLpcUW_WRnv%r7`f(-JZ9B-->LtmJut>3y#;k-Wa+rq#KXqldS>A0G6Vd6lt`=iG3?H6P=v%l}Z> z=IWf6+U2K8=Vx=?WX8{xALiwJ)IE!(W0zUkpY?l{);X`&zfmC{HMMan{T5%_oqw>i z!#(hBl<6${tr}4Tu zWB=Z_R&*W4UH`hA@uxgEXZ#$pOV0TJ@n$(QuYESonfXdi9HdWtWQVxPKJnDJ#996j zfB8vXnth~d@JFL9J$~&yQ z!^%6Xyu->nth~d@JFL9J$~CNeGg#|EI;;Wdh~qWz$A15xwcnL5a=I}7WB=xBeo@`O zaqW$3vi7NJa=cGtRy{{way|QdHDCAnu?{RbKE%AR8X`IRF~_w?a@l7tvM-M7Rs5{v zZ#Ql4|3(epS$+P@HJy(iIjeqdmzAAwZ+2+)xK7JDzuolu>S+&sU*hlj+WW$1tM=n; zva0>g*>r36jI-IOnXNkX&3273U>g&8z2uAmqt6&Hb{GT3K0h!reg~t=GcYz71I9LE z!1g`e_L00U(l14JN|F6iG;S&KryTiNj{NuU3+Mi{N3QvzUqWtUmZSKTqqs4y>mW0K z%DJ8EOFRQ(Bg#u%oG<%*dH6HiWg)ILnE4L)WLM{XCoW$qP2ASGwBK2!j$Jo%{_6_Q zl=}8v!};<1o0RRx*TdDZw`m=}IJW5fJ+#&(mJ#+2@Qs9Wv!ci%4c`siBcYnnb@dbP(i=SkPx zUCPdS(fP<7&nw;d&Bx9s9MG$DMThU4Pg-&1(nGx$D`RKfXD+L2^3vkYtO2uMmHk_; z?czMU@!Zk|hfc0X-ZuM%zuV~snCDDhC%Ngnee~^jHRRZ|XWS0D_B&^EZ4S=NY3{KKB)o9%MC~nm~r&UV$c58J`wQ2hg-Tz%ToL}8> zt5uv^AHR6b*yjtIjx##;toz2ZaonPK)< zKXlzK^-DK9%jKQ>zG6DNy8M=t*Qj1F|L1Nz`$Fx<`sFsi&wW^T?oX!Q!gV_L?OvTc zX~X-_IjQgB)!z49>N+QGHOQVlsSf{NsGU%K}~g< zb5h?i)q~!?%XLOAdw+eW^!_^L`_>bgJ^M^OI?q0JboHKI@3~I9&co|>xOK65bSf*& zuxC3}(HXVuR@J*&E>>l%$=}|3-@C(Ct)jD9kH6WoeO#wq=WpvHoo?HGG%nZK`D}Z3 zwCha%c7yt8th()Yy3KV~=u;Q#)I~nmO=vgWb!OI$wr7j6>Y};FI`(Ygb18~pDH^L3 z&Ak-mqAv2;o-JZnit<<&&E1|Ya#4!bKwT6=d$!1FDOxjiQ7-J+Vr`V7Jeq#7mg=H4 zP>R-!)tvw8I+oY8)n;EvE%LM0*!L`ZMsn(aQN*V2(bbuZ@?%fHq6buOxntIb}q zynw#%V{FDcQGLTtubE-oLLYhX0snua6ZtH;>qtNHfqEV3{90Edf2c2-qu2M?P9Ccj zOqN8N~?3+>ZB1&Wsu5g&xV}7RwID z-LhA$?X_b(cNcZtzt-XE6MVigkNawGm-l<5b@kF6cXFOS{=90VF?G%tb$zjVa+?m$ z*WcB=#t(Lo@jDn@o`JD}Eg0LZHJC9?UXtAOozXWt&e$>gWpuD_KhBJ4zjJ0xd&ZeD zZ476|v@x6+Gm@7g{ZeG76xlCFnUXPg<+#&Bj# z8^f7B7|BbKekrn3itLx8am$fE<;c%+le>bLf$WtrxXXe|ty6-{f9`~PKZ8D|i+;Dxf+K2ORcb+?ahuS7hE_LqO zZ*+|xo<+v*V03u~#s;=vY_ry3#x!|Ja?>wM-|RSJ$Lu>}-+r7K(|+g7m^OwpW7-(b zjA>&yGiD?&Mf&B)PC2q)j>auV{*)s>%aQ-SzrwtbYrg2$!o0BK%$QN!7}w>D$((aL zJCvjNm!rJ=CSP%F+~lXzYS)~znaB9tH*cwJ+4wcfX`>FYPP9+|sGoV=UgYZM!t&T{ z>{!q5cU%0uwB>zQdww6<=e5$PncZE!#+dcXKW{VMYf)aRQC_^pQF~NZVQK^W8m2a|-(hM4bpWO|@B<^`cQCp<17ibQ zu<9zTx+*#K3Pztg24ja>17qKQoEg)8=ggS)j5A|WKhbAQ>MG2Ck=*MlGRBPTcwI%# zn9;aiSCOL|`RR2PIku@^Fk?pZ^}322AEWqqT}95Em>bNP%o!#I!~$ka#m;PdT}4j5 zh$D4)K}H`rzF-F?KG+X++w%w$Pkvy0!A}@no`JD}Em*$5%A@4?Dt+bvV~4rH*k{f# zW7_YW8Iu?xXG~%WGbS;GnR6ufJO+KwBg~kQea|CuWRX9fN92r2Okr%3$J|byN6Di& zcpj1CdlWa%BXZ`-oO3%1KOf_J=IH+UkM{z0C(oVzqV`@O{tOs>HvHo=yM2!4bNr(G znVsD6zJNMO?)2`1yAPPp``iPBcM5;JyCEj|J(9m;(mhfhAHPTXFMW3t=ZiB&=bg?T zoomRc&D2|%bA&SnrZ)2fBja~4x;z8xT!UpB*10CR>6c;jIY(gZQ0rmrbH>1oX}@!3 zOwJhOjL8`T>s*8RFOvJYhKw;IJASSqXUu3^Ki80>8~OR))}O?8u-tp#o89sHoodec zy>5_~P2Xd(z#X#PmlpS~rT^Ufwc-wTf&1it`FpogbZ=~2`2U}LANQ-Dk$vLh@8)=? z_pf_T_p8t3?$>+lU*CKFtKQ$m{<8*jH~wwYCCWQ5GuCQ#qYm3FyO{HX*G{fq^3b^@ zK+kbZqsaEoM5uzuwJN`*Ai|)qdw}x>b9|*=$tJRvmWCc8xU%+n6=R zkeo4K^ce%j4r9RB=Lbf{?_hL!2F3{KKB z)o9#m!X<0N4dby5;kqV`0s4M7liRud zZ`PPtzw4E~UH(CrJ58s9%e!CxOa1h{p6G@@cTIV;ewEA4cOSmG>oL=Rw+`Pv=(0(5 z#Bt5H0Cd9p^gZCT~@pzSpjwKV<{gIr_%2_Uvi* zVW--2kLqT#&vcz#+FV+{XXVm5=DY2V7u&Np*Q3*JQd%AR%e}6%dCNc7Pww*6edz2m z;c|O+nJPNFv{|{je&tEm`SZ`G-nZuTAL`M0{^PUk*)3dW^Og_SM>^e}?!8YHox#`k zwP$y8oj?EFtUem6?z*i`bDfXQY#r;=MLyTPHTzQ6Ir7Ba?AcY_DJiq;I@6ZAFzUsu!ey}9XjgQ-g;_KC6Y*}yJmKT59JrG34?vt9%9XTOY}HU4!j zs*{^;_vM26zPGU%>qPYpo7LctbL6L^o!Mew@SkTh8rV#rf;ZnDh_G8I!&OCXSJueo6Y?p9DLl z$Ugm&#-(49Kjp~Ja^ye#Vf);U_e+{D`c>qN8O4Ww$>og6+|XgnD9-dtHROyL<%NF9 z<;<(@KKtIqUw8I7cHg!`ZU3g*{s%tk!L?kzMwj>M59ra(`MUbUs;6z;!nymlH&pxI z`eT)6H`?f*ReoS({0>H!XJBk#3&u8nz>IJ5I>}AHBz?2vj2*M@jD7oYW=#8CIk$5| z)y8mUOdG?QF>MTIK1)UNx=6ni*(pW#OVPNc$e(iLXF2lUa~kG_T=PZ08s=4w;!}>| z#<;G-n9MoMs}#k*6y>EZ&f`+MtmZl0`<*xH4{p=O`S7s^RV#Zh6aoqrO19M8n+brQ;z&BNB)o6vB z4)ZES@h?SrsoSLAg|*L{ujTc<{aWWcH$P*K>dn2+bbhV(6V(k4ALG19zZGj|zSqb3 zz~%o`$zBBgi$C)whcg~Dy&p0!t zjp59gHik1}M)FdmUyAIMBm3oO+;ZekIr6g{`S1HH%nP~Zi@q~sM)ARZ4SmLBZZKmq z=iJVUWnuv{W|WswoUgb}zBaLc?b#ha^*qM%Xm9>eGp)8$M;Eo48Rzc6pAPaow(fCJ z>A5LeI8WTXMS0up=U2(^5zlX39^bvU^SZ|zR$gY_C3P-u=vN-TM70E8xa7X&?CDj@ z@O=ktP+sbqU7XMB^LlCcp?#cpAGA`;)kvorJzI-x)}pa$kq@=Vw_4?Ig|_BD(h_8yFV`*CJW z`<*jm+B43KNj*WIF{v{!|3z}IGsqY-vg36IIb%lSdYwUzZse!e8RXceH-i~7ny=Rx z;? zRps{aKN^d;`Ms;%pZ_P{Vg2eedHnT`H^0{nar3e4UEY7{-B#=~>meVDJNZ46=4Vbx zOjbT*=kCdtU*|la?(pR5b*8#}=gW^w=B!-r{PZTrB;QZ3IXAB#k+f-gzjM1KPfA{S zdWQ2`-;PcmTWqHD4jYV3_89TF^RRQr^1p?=@mgCbPe|%K!bcn9uIeD_QEUt6e_j?jgzf zA6)DF_sd5oJCDE7`SYtMCQS$3>OA7kNy#}U-tFA=lJkJ={+`kiLI?Tnp?H-6-d{TYA#!kKY*y>Ff~{xrMp2WR}e z|4%vBt%?FU_7;mOnoo z^I=(jzIef#W%=LhlGpeir~80h^F?2Az>eaBeZ`G&6;J$8obglf$A9I8dHr5aTXyZ2 zbb0MA&-E{Dk4g@%-r~9b$7dsx^SVrN`M`_EBuj2}m&<3IbxKkl(%|xM-Z(uuZtr@R zf4kgi$s_m9bos7_oRh5k#zQV&YW``-i|;RNy;5RbotpgPDtkc=`)wFJ!WunX7kToe)k>2lU}#Zb@}+6dn8lunB(#r zAL^MrwCeXRf9mz^3i%zqwkhOYZt7Inxo+fog`Ew*Uac5+v)5Y{<4(V`W#MO&cN!Ib zrW-F)%&X@fKa@4E-b=P9;xP1upUaBF)6Lr!aqEB7QbpX(Ep;s7e8P9D7IEHsZe5X= zeU{t2$P4GM>grxctx(eb{chuPOWN0sE6=&P<`M|BnZs;i8vx{5!ltN5w9ivOys%u99En-|}C@w$p!^F?2Az>eaBeZ`G&6;J$8 zobglf$A9G|&KImb$oK73SCOl(#=OzQQ%l;vosMl<*1n!|)^=s>_ebv@RaPB1^Sq17 zst=>;ZY}D@0h8}5>dC0{{!!GKIcGgs)F0%kOX#a!VMlcg`>LyqtGbFms;l^^x{Cj* ztISt*)#O#lO}{36vs05DvtN^a8@Hx$&7Ye5F+XdCpXdFfCjV_-o?q&@&8w!mioWV9 zc2rlfuedR;;)y?sGkz-m_^-SyET>!jcy~#4^`5m~E~%~_)@R+a>T3PKUCXMg1J>x(k&U+b4L?Q84nGVOQkuQJsE>$@`52kXZ&)eY;@GSw67-!j!1>+3SrALOb_=&N2~ zM|BMQs&9;|x`#iihxn;FiT|pf%u99E`q)Bl{cWLdeQ#mM`r%*g*N-U1wf?#A$NK8R zPwT@A|E&)%=7n7IMPG5ij^bl|co8?oRXp)WamG)@AODq?IA5^pDy+H+tFFdueNm?U zYyDEDeQkYIru}aHRi-*%eOIRXVEtH8H>^)9>WTGlMV+y}uBboARhQ6Ly~2*_81_}) z7*}-@R>Z?>}Jt9as%;*6h)KmIE(%W}q-nd+7Gftl)+^^KY8oAr&E z>YMeMnd+hSnVIUL^`)8Wr}d?o>ZkRwh1~ksLT-I;VaNL3!jARH#kkfd7voxAUHEBz zb>XM=;l;eH56@Irt#2>lV10Y0x@vuX5jX4ei@4e6f+EiLxuA%%eU2#dVxJ?5ypTt$ zKdhT_s7ubFUO9(4<{avqbEtdHp&mMiI_Vthr*o*Qh1}{-p>OraIn-z8P`8~!J$DXu z-Z|8N=Ws4KGcP+YoI_o54)w}8)G_B!-<(6;a}M>;In+t#P(PhRT`lBxUKILvUO0#P z?2LUoFPuX?cMf&lIn;mWa4tB<`GRlh@KqM>0kS3U{5}i!0Mwj@@Oio5P?uaD>Q#nL zsAJBdzBz}w=N#&xbEuQfp?*4tx?0Gs{uKIFf1E>ob`EvhIn;CKQ0JXP{dW%Mf-`fs zv%@*mCFfADoI@RR4)x7B)IH}=51m7ubf&J#|4>&8xz*c3-|Db)sL#%!Zaas1?i}j8 zbEyB$;an*4^?Ny`uCBG~m!50t>Nf+w^;}a||1s|qms3}F{pd@VQ&%sUGRx)E)z_c@ zz~$7{(+9uoa_Z_vJHP63>gtKxKIw9=t2aF1a_Z{weP+0vx;m`q{Vu1jwq3m5<+SLG*lRrB(?8sZ9j@wX_#Ex~ zH+;T!4xhW7!{>45@HyQ%e13NhpX;5&=Y8jJ4^YTeSJ78p#g6rLu7iE+hn*SM`nq7p z?mQkfI_ai zioWV9cB~I~9qg;FGOqRE!H(ZcIEVWRXZ*K5+&Rt{tUU;;uG(kG>s41{4xgia|Ax=k zzOTdQZs+iM+&O$scMhN5ox|t)T%Ld4cMkUeg+77u{f6Xxj+Q>3ubso^Zs+iM+&O$scMhN5ox|t)T%Ld4cMkUegI3%xst?=)sGe{SpnAeRfa;Im1BCj+J%H*J_W-I_+ykh-aSx#S#yx=QA@=~Phuj0G zesT|>`pG>&B(F-&JwRlqCOg~%MB~;pF82VDpEdc(JwPL9|P|m!!Qk@C!tqQs7D*CFc*il`@zUnIDs;=UXeO`7u_^CRH|EjCZOLf)y*g|go zZJ}>{Z(+y!;ljT4$;G(VKNtRl_fS4=ct4f5^Y>_O z2R{{m{8wJ$e8H-#u<9zTx*D_fMZDkf{cHUa?{|D(TOY;y9cSyWc)#OpeHZU{oUI?@ zeUmfqtyE9K`ze=)_g2oxRaenhUB!;-D)v=Z8CP``f9&(J+rdxON&Hv+WM1l5t&c6_ z*54NT*7p{6tRF7yTc2EvYyERk=fis_A2+<8at`mU3c2bk`icW~6d&v>Zj7sV;*a8t zpNc>JD=*CJ_j1a6EA3z2TWSCD-b(wO_g32Pyth();JuaV1MjU=Pk3*oy2^Vi)gOOv z73vS~tyHggZ>4(0dn?s9-dm}@@!m@HkoQ)qhrG8^{p7us>L>55BmDQ>*CQk;2jr8x86 zN_pYEmGVMA^Vwc2Rk#QE>t*lO-9IwtVe1@LYV>8!OTBb`Y0Z09cAYP-d9KuLYCGrQ zjejid_rogA4eu^nzG3ic&gafsx%_a8HJo4QzE*kNN7i&+>ZSJOgU?>Oke|DMheH3W zJgiVyY`H^x;w@kepSPsQKn zRj<6n`Qp!0C6iiLxCdaqlO9>V!aV@|W}{^*e8!Kt$KXMwzaEgw*L?ER(n))^aGiNQ zHYz{)!E(;GUeL3=Rf|^6A2&Ot-0I%e&cnC6uzcmCZFBu^t}TDvc@^g?8~$3p{MprW zd5_yYzl@7~_1!ua`VY-s-x)ir?6 zb4zFD^;)}bl2;`+{i^hBUNzY<`!(6Oacdga{He*GdEZ=Hlb_~)t?<9c?VjH-uUau* z(^nj@qxfK7absM?6MqzE{8apHURC8~VL9Dm(z&HG_E^z#z3Z*b%l*f+b-rcteWf+; zZ|Qme^15>Q%lF&4{D!}6QeOMi)-K=b&)v&S)>y;k=dAjd^6oFLQ{clop3Unp(+ z&L%D|Z?jkV^h-B!`Ji)FD4l;;XP37>bjk7^T{e}xD*4E5%B6NIZ6-Ta*)e%lavQg% zam`LmcFfP3{Iqdv8rSAk)4a^jn*6jl)D#DsS55P>xYZOli$hIuusGKgXNy}+akE@h zl?#h=O>wqdRF#V*-hV$^^T=lt>gvV&&&p=j=ltTkZ)SVm^qkAjz4^85^!4)ZM15U- zIje5=qRZ`nGyDI}_WR8Aob5TgD}K}2>}6)x*~ZCiyh1*3X#V{u^f&(CGnZrMn6BmDeTxdg?$^R z7}v%r{IPKgKW&^${@XakypU_Y=qnD`QGBqkxG}Eci9d=nek%U>ue`+hf@i$_XhL0u zdmk_(p{~MBo~kC)ftXJ|;?3-`VKtX`Uhk!B`~D5iz((a%kOCMOg8DoM_pdZ9?SM={FciHuk}dw z{xQ$FeCzKY&34-SBbUE_^aI&F8@%E2SCc2QmL2o&M2$RdMt0@%AGv&s9iPo^c=J2g zpTFNjS(}aX?@;wU`{nGJQ-5}OHG4ceOq(?b5_m>-I9KX~Sw!p{1WekuICvFTzB8n@R+i#2Fo zjY^FgfR?(>VdEw@SI2E}2QcHb6p-ud~(8x*$}=6_z~V*lEY zMVxmXJg3No^;r${ThvwSvl{5bVC%CQ=(k|&vl{5PVC%CQ=(k|&vl{5PVC%EY&h^gL zXEo4oA-6uOfqo0NzPN$=qe#x*v&B{&+4@}Og^K$>KFD~X4^p~X zor6El!B6MlzjK(Ev-OqC%h~!(=H+aCDD!f*{*-w+Ti?pOoUNZ_Ue4C%GB5Yj`d{Yd zY<+P9-|NEXAg{tf-#OT+ArJPQ!?@1DALrnwbMW7pdHr5azglAThLz{<xMU0JlN&u-?2i&$LFl# z@==$zZup?(1$F2@wNJ~2Wo|s9%KF){wqnD)j(7Q0 zZ*(Z+dtbLk!<_BUboqv*^$R=wMy*rGXS}gdG4Ae7HZ1H6?%k>IbM*C{ig7FBI~VhM z>%~nAKc~0vT*Tp;KW|pd>x`W?DdP6&V_l0lEWW{pMV!|e(xr&o!>g=Ym2%FXU66KqmMu6!T8DZF!mS^W?qa3hknmF^nuQyKXeX#qjTsdokO4L9Qse^(3d)g zezlNmzM;Q$dFXqcLqF^s`ef(OKRbuM+8KL{r+Fz~%<zdMx&M z%%R_NdFTV3Lx1QT`bOu_PdbM_Gs7nRD*YB5`cmi6uNHE~lRo3Yq3?AL{jf9R^8eAn zAM{|JV>}ppj0ZC>#)Ct@=N$S#=g=QIhrZD{^pnn^&vXv`r*r5_okPD`$Qh4uLx1ZW z`d;VI4}07~pX?m^XJ`E6dHK(Hn%D2;lzw&ZP4isSuYS7NPZ@cqUu~Gt$n#FW`r4NB zTu#4Q`+hN()34t1&}S~EUtQyX{CgwxtJMqMbvga&-dBH~v3}@RzqJXUzMNqs~VSnRr8`>m7nyhiUa+s=0(4%xY4gF4)m*vGySUK zM!%|D(61`a^sCAR{UiMrdp6upI@6cYZy~2&qu+w*9^o;zgo!YFQrf431f$T6vjS%D$Ka_uQ2}5*TVQozYF8P_s7P}i~cysxu29i_mSCtXfoM!$s){TlriOdm(T1=HWrZ^86^^jofP z{UH4oOrJ=<BluLeY*Uif0v*1^@acW{i@qRUd%VYk99eA6d&v>Zj7sV;*a7? zzpwby@6!h}FY@(!IpuzJlczg*uDM^`>&lItxnI5H(5{|$?pGh}wt>sJU%mLE&MxPE zb@DIkxSaddqjucL<=n4!>%W%ExnCXsSx1+1zxw>=tGb-~)wA2K<#O&<&uF!>%ei0O z`>0i1&i(4JN*kARzq-lzHZJFWb)9LgUC#aL(z9DhUX`5t)vKDel%1;VaK9=!_p2J0 z`&HTDepP;Qzp8P$U)8+0UzMNSuPP4QuWDZ0uPScbuPP4QuPV;muPScbuPPVZuPV;m zuPPUI?kDPhtS?H`7g@iQ&~H(ftdC0Qw_xk968bIJ{x_lDg6;PS{T6J`CG=ac*-O;F z**M;3NUnYrefmz>p&x~@PoD}iuKHE{QNN0x>R0hU>Q@u>t2Ry{=e|?=+;_?j_noqD z|67b}zfa_kJy-b2eW(1laf*2%*L=}e9I&JKU|(@#T*VWA6leTY{PACTiSq?Vy-gDJ zt4Y+a7R-I2`XcL>yx(FkbH7Nx1#|C6zXjX>R_M22`+bFe3${M1qJGuvRn))Pm=*d+ zbdalGMPL0YcIZcCpFS04T=lE?qka`X)vw}z)UPJ$S8bd^ZsQdC+;_?j_noqD|C?xB z`@Q$a_`rRq{N%n<{@Xa7Uv!XbzUV6s*in42uedR;;)y?sGk&UH#ed~xVL7!PDN&DP zeN>`8%6gI1E>tEjKD zzA;hXXnkNseW3N3iTX_I8!PG?tuIZ~ms+2hsL!-Mwvbz2ny4?ezPGSreQY7OKDijz z`rg8h_0@%+)+Z+#*ZS~8^Rm7=k)PJLCyImh;fdyDeSQ%)>)R8>!9ExKFZSL%V9TNX z|8KwTQbJ_St}KbV&pEG)Buhlu2}LDK#A8cjDV41xiB?357VXP@&RkdBrF~x%?OMnZ zBC^GA-tTLU`*YOq@%=pCkN9|=Z-03;=9)QX<~WY?m}BNV@1lA3aegfG=JyUoYvK0= zMf2?U4n=F>^EoNWulhJECHYk!XQdEt!Ke8+D}{Iq?BlEy;w`X`vr>q+z&_6M?d0;S zKF&%Z-ahT0<5P@_?fbYD<0AWb7ULrOI2Yq0^L#$!S8<<0#udt$Uk&vW^cC76hxW;# zUviMgqJEH*9ONhK^#ZG0TuS9vQ!2kHeSA>M+2z`3{NSACq7LcE1?A7`ZyZ-ITB zl|sA)_HmYPCzoIKaaIcP7RqrBk9Z4=^LfmJDv!XSJ~^~wP#)SRhknUH9&(VA9ONfs z?0$@7A6H^rWFK#0Tx1`IVq9b&pJH5OAGcy$WSq|)AEO+1D`Z@u zJW=(@p&g6z&^|fzOAhjogPi0bKl%68)aUe4l3(?Czm()xeNHbW`Bk4MOi6y#=lxQW zU-fy#l;l@^o-if(RiB4UNq*Jm6;qO5^?A#bQ zSACu{CHYmKM@>n7)#pW1l3(?C*P?QtM@>n7)#qu8+VOeUqH>?tE$Y|jX^YzNdEg>B zeO|YyU!ONF8kf%l7s=`K%tiCy^TtKv@_Ff^dGmSZqIvLn?4o)0dFi5g^SSP#weWfD zqIn)avr^Go;Q5Gn3$`5MJ#vTx$ss-@hq#d(;z=^%Rm59pC&Zs*#H)z6P#)sdqH^>n z_0bKJ@g00xX>Rs#Czlr2a-d4NDgr$ImDCX5NDD@ z{7DXRDLKTeMddQy5Z|&q#J%JY50gWjOolwD2bn`$O-6g@PsSzdg)yqL<5=AXKr9!- z#!*K&#Ct3caUeOwhvX19k`b>W-aB z@v4jq@v6)l;#HXk#H%vTh*xFa5UkTmty7y-~OpYe9xGCa=iV? zxKp(=$O~U`@eP+%CckmlH}Qu1%aZ+nQ~uu$_U`|G%GV?N-=+NT$-cdmZ{iaYq$U_ctl7sx@0lm&Y7X6_<`bU3Y$c6qwI}ZJUF%I+x#`w@5 z7~@8NV9W>l17n`h9~krJ&x?;!`UIe+5J9a?tRI>^ZSf=FGJRA_j^*g_4+%%C*{vscE5k&{b4w#OW`>Z&hNi`^d;kA-{wA;e4>D9QhHHqdxK`V6=mLinNbB3mE+({{jx@m1N|rkgq{G&Ig&t z@$BQ_-S@ivJm4Ha_KE(#f7^TAK7ZoxL+-vWit}*EXW~3u@|oeDX9PXRdAQ^=|F`ao z!oGYyfw86Ek2^U(^80kWU%+y|f5-a;WWTS69+LfjA9_gk`+K}!K=%0oyk9`}`}^JZ z(EM6s{$zfF{c?VSU6b+uWu7sAGXFRylyyOTDEB3H-*3s?pTYC%?|Q!l`5dvYkjLX% zhy0$bd(nAr$Op0<{$A`0c|p-1=}%9V9#K*4|@iq zU)VF)_fvG<4LM=YD2M#8XE4U)^L6Bq$0LXQ9y#Rw$RQs{4tYXy$RCnJUXhHvpvWKc zkVWM(UeuR)Ksz!&XkX?H{ffVWJYrvvQ|t@!i+v&gFVC;t=W&1k^SGdgvC>a+&|7lQ zXL8VUa?pQrunTgq7jm#8aLk{21A&2kkki++O$l*IYWPGe2 z`0fxH@jT80a7Gr+Bgo;Lf-L7Ls1wdLSRT$h9LjMnf%6owoTq^0JOwQ0DXN@jb8?=7 z^3V>;L;K{=Zz|Ug&v(c{PI8c+EaxexAI>ABKF?D^J3LPThjR_qk@FOkhjS2-ljkWY zm-CcdJGt`|Rqnvy{DmCaAd1LYuASU@3Ruolz;d1fhJDGml*4z2C|md*5jlLP zh#bCOL=N9IB8TrCk;8Y8$l?1)xh041-;(hiUHLBe?(dW5{;m+dqr0oVPcGk-!+Od0%CKJY9W$(#eBTV~CEq>6 zddc_DuwL?=wB6r5{`0C} z-jHv>h4=dy(}wr{$hhx}`^u0X_n>iK8I1eUxUUSxy=mN62ID?8?kj_F&l>lYS-$)G zZ=46*mzR0NeR-Kr+?SVm#(jC*FUP#$zC7-cgMFS2@3S*b@b?v++*ic=J-7#nI{tnm z-is&udyl)nE9K_|?;*)OSbtyjFZ-?(&X?ug3cSxM?^EDCS9zZT@4w3X6kacOf3L=` z*ZjVN z-pe3|_ch3P4?_GN&X?u+wflX*zyJGyurG-ZVP6s-!oDOvgndbT2>X)vVqjm;57-Xu z3;F?ueL+9KurKI`vah0Y^e6SvA2`@4IoNLs<-xAW!QRQi50Ha@AP2ue4*E$BdP@%a zOb&WZ4*E~VxX~YEzu$-rW zgs&eYHtRu>09l^4WU|C17tRq;~5iIKnmURr}T*pxV z-}+o^*h0Ju*xQsJ^^hHN9DH7Hb4B}m?dbF7lSk~?#I7&4guMTt%WNZqzg^$k{P63U zw$8#86Nv2u>> z?YBn#?_a|@7nYh5-TTQ(a=-iY%w=6aBzL^0!%=|Ia$eSBIXimSfknG20PWlb+GICtzr||Z@s$B!$y;LzM}{kW2Mk66X}eq6Tobsv)bxNND7 zOUQm)cJs&c$$ngR&-Sy(eq6S4@?Kn_;^A@Cad+4MH+|mNafQRkV{bmnw(c>Q+~bO3w&!Vs$ipX1NLF+oKtB2LYm#?X^e3OX z{K|qcC3EEm-LNu$>b?V6zUb!;(X=hO-<~jiQB>m1AuNBa!anA;GQ-J}+n;O>+ha7j z-}Kt1X@~LTfd^e{+T85OeOERy$(@B{KQ6PZ-88Zvm#NZrHrbEMe3V{5_Tw@~yt0Js z$7N1v@&Vb8%QSg@1=)|w)c$T2*^etK(RmHok1MKv@mjJUSN=&y=h%;{;E;oJb^N%J zgU`(U){iS$(QY~G`*GPiM=T@zaoNe07L)zBZ0o-B$bMY5@wAy_Kdv3t3%1tkwS!`@ zJ7KIZ80(952V>o#4`Ap6^aKn&f&PG@KhP^M^a}b0hQ2`$!O%nKCm8w(y#+&Wq0eCG zGxQt`J%|2-q5rT8@OEz(uop1w1$G369l^f9urJsh>wCL{J%VA6uv0MX6!r^-{lc!n zuxr>m81@c70EQoce*nWjz;A%zH{ege@F(yyVE7sMA29q6{1O;`3H}NUe+54V_T!>| z1H-?;?}6d>;19v@hi~6FmuuSow4amwO|x?R;2!q33uchNxS*^p@yt~6d20@|-zJmE zwT?Z=F8?ZLr~UUk&<;C0!}1#j?`KQAp0n8+2bHmNZ0bZMSEfoZojGf7`of+vKJETwh&lzLlg; z%E_>KZ8kCf`3sp}a7&V#rf11_9K9jg*r1R+{nam$eLtH*_Tx$hJvxo-$CcP`W{~~3 zl0)LzWIwLthdOg}^*aqq+7z2l_Tx%w+`NG7$Cb3dY9ZN=EBSmyj{Ud_F8w;keq1&8 zd@09%T={v0x!?M6MLjy?+Vta!F8w^$mmgR3`p-ET{J5fi{`nim6+L;=bg~~;^uwa} z$bMXrUax9f3*(FGS8=`99d0zQX*QMR)%H5vJUDd*xmJsV&DbAilOLB~CpA7h`E|k)*1x@J=Oo#*h`jv#Omab=1>^&peVjbDX)d|Pd8KUgHM7Vc)jPlr z=rNtV`OAuS$m#Eq{TS`9*-2zSE_+9#4B3y%o>(Oz`*GQ$)8om0T*=`>$B_NFlEa=G zMfT%LMr|5F_Tx%kS~8sM$CVs*O^*Gz3QoK)$9`P-A0L~m@5dFbxoafr`*B5; zJO3YZS)S@q#y(v>w+Gx-?aSnj>ld;7urV`|H>&6Ms@C>Ns=b!mGtU3~#^mnSOIhdB zQC}Av`+kmJ|E}GHRsD0^s_*dp4V!cIe;c2QQloP1{FMJ<^z_fU_U8__(TMlM-ZO7~ zRCxJ3wt4SCCCoLC=JugKR@&d3(P9S6kBtv8!)r_>*Q%b=$uP#<`swZT-$_5UKLN`+ zLWj9G_c{#S21B=@^I+&aYyk{gfQ^7*Bd{GXYzH<4hE2iNz_2ygAQ(0X+XTZlVY6V^ zENmGJTZWB;VdJoUFl-+_0gO3^uK>eWz=we0L$oj5{p|BGz~B7Yw>yV$c>M2_L(u!g zSxa;Ilm30bPQGcD%k$JIoSQt;D&GX6@^~89tJ^wei>2&p*53Xy(>>4%j!kz1bM%*0vUJ998W)mbtaY7rzqS z=EgC%w*K5CT0d<(b8EL z%lny{zf6<7pE>Q4nUeQ2+Gp-6U#HuAp~_s!dF<--(LEdHQO-JF6hxo3T0l7)-SBc$ z`ICi|^Q2Xcqgq!irkoY~92VK`ODN~(57~VEjQAtIUAOc3150Fm3kL4JSk^araH5yT z&!J!6WJFglr=LT=zRAP4&zJR0e!6L%tZ$;9iGSqzrJvUgewZNhmfU;pc$v54+aX@x zylj5n5}WdR=wDY=6Q$t z*Se}@*p;>r<~h+iqjg)$u&d55bYEIOwJvEHc9nhIv95Tk?BE6by8x31l}Ob-bV<@< z#C-Egqmrp6CoE4^y*|%eQn^%W^H=MWW<%$g`#&p{`t^e?Nit!kiIdW)D$`2Xy0=U< z)jE|)J@;l=+vl)}=J6_dsR2ulw67jK!Mr>uFV*X^<)N zah|^iRNp>v%$w$*jd`gKovyU~?t9%_wk|K#ru4P8-lRU}-Bo$1y&t{7V!y4}sybHv z)~Ysb>q&X33kvh?ert!=J8#HKJzVK{+vUWuw$tP?sZ5Ouc1E#`T~)eF>Xu*1*imh! z*t`o%r$(OoW3uAN8FtCDrBc1Of0}f?eYQQOuw<&>%GJrC3+CF(x0gt5X|pu>yzYEE z`o0pWBNs19Dy^Mw)g0P8nia?WCd{X;^kVVUEyw0~=7i#@4%g&Z)iJ8vsQRX5xhe4@ zM^AL-no{=J3De@vS6g>x#p3pdvuDLUI*)g!kN7gVtkvB3i%&+oP9M%q3b)OR4?A^~ zd*;{)NfnVQewu!c>k5}x-MVemz>sbQT*GIVeZ~LswGp-Tpa&Yd6?^! z-Bj>PyT$Qmg+txx)tVQq@3lBCe0!*CytUkfV$Uv)tGc1?=dLyKuQ_*dd|ZWLuH++2 z^1F>+6klV9xzRVB938uHVZ3?5yKdQIcSVCHEr^F!7~uw7@Jh5_i}~>@14g>q7mbL_ zcXQ)UuN&Ge_H491I@{;cf7vp@&AoeDv{y7OerbhuAAeHZ9Ow5V zFU-ig#aEOvPdqm%o;tM99lfrEx$E6by!4UxT5~vvhm4ZPILA4+m!54H4}fl?L9aAl5NS+ z7fp;?elgj7JFl3%?$pA#$6kf*g9l4mtq)-67oAKN8zW&q6L)rN(FLm_bhW(T~aY11x#(0iPrXPo6-o{N=o4u8%G8+qyT6NU~+e zlKU)pAt^CyG`Vxvy2+9)qsW`PeO}O@bB<5`$L0wa^~>?I@hso(1RJe?qJZ3f#jzp;OBFXIo6jUK=&&_vwI(-LdmXkms(r{jmLGV-)Tlx6 z1>}cI_mAekkel-gc~3@Nhv(L!!uzL2x7?CjqxRQ~%=hc)Fem;yT;@anw=2Q;`!PMs z&m!aR$E>-0E*XD6=J9v|8Q)tRH<{lmOYptLkLN96IsSgk(G8Z8`Mt%|GBUoOSHDw^ zp(pSBS9yV|pQv^c)qbM-O_V%V$!V4R(32ofWn1d$iDZ0Nwe|u04tj#`r~bNR0?YCJ z)W(~}lJR}J6K)+%#`jaVT|JVF@26%K4=3aMsntJumyGYHc6v3(7?&!~SM?*+PNdq8 zRKJmu$0#|Ck{>=f$Wxi@pGy{NhjL-e16bA(Eb9oCbp*>gf@K}SvW{R`N3g6TSk^I= za~(r{t|J)phIIsEKCzBq%rn*zjQPhpg0U`2ey$_R@tru#16bBk>SNx(vW{R`N3g6T zSk@6N>j;*01j{;xa;{^j&vgW2ez1;U%p2AbjQLdZa2-*O`B(CDz3^=P?dIof|BW-< zC7Z^(xkEeJ{A(7t_g^02j(hnD+waPyZgZ`7T)%bA>~E7+xJQrc=ME};o_)I48rOMN zZ&&*9O1AQ6AGvM+=;12#{VCblf4zHkRd=_kW|AD!VuQf_8(pijySa`% z_lZ{iw83qAznd%9q+yi0bA#(V`W1I`%a@~D$E|n6-s|qpzhr#WxyL&9V9VFsor~8; z+2cNPox1jPl?(SUr*B#9o_BrRr=M3gy{fEq>tBA;wYV#7t~>Grckp)uT)p89&4|j2 zUC$cB+_(cDG%xyRTDLBvUFYuY%;d5&Ty|rD+xv@W%$tWycAJlwyM0bw6}x4cgDNzWOa!d+l=fQ|A>?;iNa+#JyL#d(Z0@ z{W$#%*Qao$i}o%T{nF+Qcf$`W-2t~OsWD{C8}8bLE8SOfzbyFZx;I^&>sPwzcix}e z*Q}rG+jWJj_wd*xS@M>v^yG4P_w>!lhrRl{wkLe(7X4Dz-Z^xjd$G$hck-$e?JwKj zar;eq-?@fqTjk!NZql^Hu1fs|_OZ>w-Hde$T)A$y*%$U6<9@qtuDj*(M{K+OCwO^g zx{9Z?v*S+9xZdBr=Q>>djD7jINp9)^ligJR_b1^8M6bjrK*t7@#ow3iZI_+@jP0Hp zPfp6TwJ%N^Nxpk6@^yY(X0P{Vu-`S0K4Ui2n@4_k zO$QP= z<(iJsSI=+E@#1m$iVIYoMEy2VZCcfrRWev5n^iJfHI^d3hqc@MOgUSAZ72AB&8EZl z6YSgdSZ>mH#RWe&O7TaP^_Q`&a zxU-czu-{_xzAruG-an8rgn8|S``w`pmb1L(11;Tz)GG4y=6AX+Q`V55>)g~Gz2GBq zv4d`Q4X;>Fe*E-n-G=lAGQNTHT<07w`TnA!@+%HFuc-cv*Gy46&rdw7sQp7npI+2& z(z8mDJaxLCR3vBh%n3#Ee{%Q<=#%}T{G9f4$f)0@+)Ogs$zM8^jP`qeI+=`qZ*4M( z40)SKPS9n71wkNK2-G0!3o=3nH* zx`_OGy%bxuc2=#ORcmL}+F7-BR;`^?YiHHk`M(iZw02glomFdR)!JFLc2=#ORcmL} z+F7-BR;?Y&!`N9r%n92GbH(<<9J1dqx0EN$Ipqv%LHWZPaa>{TI9@4NYsdMKcGTK& zKBZr^cAS5aQ>~r0HHnfhI$1O>l#AY?zUVXB z5j{uyqW|bu>;m$Ly+BT}BgilI<#jR^yTf>;9P=RcF+b7{=1tnid`iEVXORc3ZlRwt=g?1C3+Sh;5%g2m4*FSCuGS9vS=5eN zJLqRoziREEpG9)2wS#`j+QFa5*jZonS*;!07yVajM|s3v)Y?&gu`jiD9IuqCwd4Fq zJ8JDXpVF^dJI=qzsn$;08uvD0ci7vA-C-{zc89%<*d6vZVt3fvh}~gtBX)Sz_`{bHU)9?ZYUiFFbA zu@{wbDdxU3jGg<~FeluXhPmRtG|VCQrD1NlFAa0feQ8(=?n}cO`IxX><*;_#hfBFy zJMK%R9kq7cmrB2C?YJ)$In~-hCuQxJN08^8T079yC;*6c%YX%_qp6&;_j_YU4?JAvHana_i-2hgumO~ z+tzt6wx{idZ?lk%u&)zK9sk={e(T$erA^;gEPZ(yVv)hi7K?0N=9I{+&nXleRmZ5` z8r7yzeHkT#QL-5&v+?7Sv4CZas3T*?Z)HxZhV z-DgaGP7uqev!TDm8IxbrIIJVqTG*&N1Nx2upUbF^v*6ulvR=>s;F;`Sd7kd?jb!BR z&4X*VyDrDCgHJQZ6@KkL`5@GZE{OX(ss<>iJa(}n(g>T-qHL4YZU+{WT^4PljlpynwYRiq!#P6NCFS$b5ji8R?i3%pI$ zFXHg5!Sf;x&l)^O;_$37{#g@;XN@`Jt|sxy9#uL2x88kUyt;iw@?k^T#1*e7Mc$BY z6!#u_2D$x%4deR`Ig6YcdQDt>S`BhRy9RNoxAMtVkGwRV(k~+4`PK#To!K0(KC4!I z&Ud*w-G4T5pG$Mktn&`35q~g0*XD0)&WLB7ekOlA{K6`6lXkg&-)?<;{Q8p9Sw5}* zQSr2sa^>;&hsGB?S&ij;y;dQ9Z*Fz6dJY=(j5F#PXVf#!)OzVH6K!pnYv=5q=B4`^ zk?Wk*)hr*=g#788=gl#%-cIg%YDd#+>)qrMk3Ve+-nyUc&p3>narko$BWEA}T*Jtj zh(Fgba#rHcHH@60_;U>-XDj|(!^oM7Ki4pF7URz~jGWQZbH5f=)9MEAT-I?+k5t4?&)>#!3Y_PXsvx4q6g(RptR zPHe&3h!Y#}w&TQhyiGZ=DQ|;LY*594#@nD18}zp6#5Vtxm=N)y_yq4OocIdwL!9^! z?^}FcA?I7X&vD{&yf1R%i@c9=;-kFpa^kzZPjlkaRLq8FdQr^g@BU@NT|xNFOt>p( z)R~U)IoP7}EOn-{`#kP%bRMV90*pEfFzPJ8sIvg0&H{`&3oz;|z^JnTqs{`1ItwuB zEWoI<0He+Vj5-T2>MQ{IBWDvvodrPOMVfcm2!0!!1gZ(#er7EhgQXnR>hN6#hF&cpL+jg(XZqsR7_}9tcZMt z#E@3SidMynR>g`|#d21~cvi)JR>g!?#fnzNkXFT(R>hoF#iGbRNZ!M$*w3n%(5hI` zsu%7!r48B(}s|8i_e^$3|jNedoujSP?9-qE&Zw{`C7fD#pW{NbHBX zl9&*4D6t~uR$@rZxx|)O3yC>(Zt8dQPAbNO4oK_=-H@0NIwP?nbV*`J=$OQo&^?Jc zVIvaDL02WlgAPmV2i=yK5IQfhB5XloNZ5$PmarX(Ibl;0i&_;c!UiQ)gl$T!2pj)z zbB`)k)VVnL4T z`z8`Y?(j~E+M8RoXZQCHi}vzX?eVSJ`&*S0uqszzRSviVpmKNE{?_-PRLs2l{!Cae6*K?s z?$4;0dH21GuwH-XdlxF-rQ;c$``RI%(eagHT^}s*kIswgxYzt%+^gef#kxN7IYl{D z{p?n(b3Qvf$8}txSl35i^4#Ac$E)P|-Pm651r+~o4q5L76dM(v8x^-370(+L=NlFO z8?`SmYQJFAKEkN|h2}qfuc38D@t+>6>%E3zqvCm^;(Vjxf1~yVM(r1HpI`P7$OFs% z0{8!A-vRxXI9BtY9@FZWTrqS&;$G;6#KX`TiIbsA5?K}RAJ(S)9s`ia4H)_vi)LzV} zJ(^K_H>37+ICGJ`-VSFpYF~`{vR_6!|Kqb5FTdP{z}{BQXm;8D{m;lncs-GGF`ets zeh>P#OU}#mK2b66naDW;$^-9^JJQb!u&$$iTU7p6=eR_Mzw%60or(PE`)Iu`s^1;f zPVKvm+K(HxPd94+Zq&ZssQtcCc>tsG1GuxnJF5S$yhEqnAN-Gb|55H!;Z8B`ZmV~w z`OZGdao1bDbIo`5QI5R=-n9qwzQ2EGAB;QNcsC!6{5sy*2jhOdD&PICx1STdukf$D z>#cKTPrY3tbJS0ZlbgrRx7%8j%*^SsJSlvBo;|Zhsm%BZ81qD&UzEwr=(LCJK4Y@2^=g^SnQafSFOSLEJr2#w46Sg49rf`9 zds6$n%!Wl(?Dk@#>>e}nGM{{J>^+MH+Zh}3GC!YtiM{xdx2(GNuGuI#jgr$SIgOIj zC^?Oi(?&qs-AN}t4l=Qu< zzw%p8Du4TLf48lyxA*#WtJs3P31)1oGMVQdJH`GyCTre$v2>>Xl_%Rp4^B0s3QA=j zJMSbrY1T~B;IopM($R@_S>YUW%+QjVcV797^*@_lB2(_SO{{WoAbuGdGtn@9NGUY<_6=n|t=D^>)DM`KHz}{?RU;ylyi?d-?@74+)3HqZNJq;-`qjj-oE8qw`lq8>}#Ig;-U+iv#(cc ze(k0#X~w?JE&S3Ay1Oa+x~{}V_h`S)tbgZ&>s{?3omjuzp6lE-GhSf*jRV)Zo4$CS z^N0=tJ4A8nePZ z*S$CUdZxy5SGi*^_O<=P4_t}PJ=xbu9hbTGy?d~)MpI_GuPTjZ{lU# zPInze0!y2V%dcg+3zX78Bj#_c_svTgV(>rU%Z zNZG!;A?vFCIEk{o@^HqDE;osNopG9Tv!`a+S7CAM&hD0BUtLxexZmz_?5o+-L9Tt9 zMXbN}je%}N*@disbGHF*Ug3P!Ke$VOcSf6etUqMfTkh$~b12)i#=YF-_pGICR~+BV zt*yA0vUQr$)1CeN8p^hyZcn#hsqh*ob|u0(AEvS;4{|mR_7_#Wd0`Bf9=sH-5X6lVf~hSJ??HR z+(6mBTGrG>OSVzAWluGA+aKCS*&2V{#69@o_mu7VbQ8Dsknbtmv8UbYwtlmfeN`IR z*xgpw>z}uU^Ui7HM!vU&ecik6Cihj{ui00f_0`;@XMbh=8pFu~$Y_r)@>&FMp9TkFR> z$~LE2Y%5O7qim}-8#|Zu{4?+xwSd zU)#Sr+uEfi*%#u}k2dD&gUkJrtBjG8y2=FO;iGcs>}O=GpDv0Bqut!b>*G*)XGt2K?)n#QuG zUf*J+Z?V$1Sm|4=^eq;B^R^HxTZok{#L5<8Wec≫?1_tZX3`Tkv)oD?5#qoyN*e zV`ZnY*s1p+vGO6Y@*%PEA+hoyvGO6Y@*%PEA+h)n@84qO-(uz8V&&gr<=)4`%J;^~_r}Wi#^QVZb0JpGg;+foV)a~z)pH@1=YoHJ#q#{}&#YKI zvtsqkiq$hKR?ntlJ=`#2<4aY(G zsZ_xpS2I@ZIizH2rM;4|;*1_lIHOeR%HoH!{zX5QOqJND z66?EGB~tb49Lg9{?LDp9d;Tr<$ZF4mdm!?T$-n(Q7PVjdOTSgC_PoFQ9bNU_w^i?h zTlJo}Rqu~m^< zkG#w?XI8O8*H5swl_{1v?w}2JpUdal3)00i(`tQepX)HkZoIri=A4r@v7II5OJ*8$ z_>}FaeVl!}W~t0CFMiH;297M1>DK%U*s{H*OzF)1zkUH5w-3}ToylIi8MbdrUS2$N z))!?R8#rKS+yUuZoxOM&NCM{$ecdvJNL<57dgm$#tGY8 zjRWgCjD23uAKbp@U&6lB{?48>?I(BCUiH}5upvLYnN#Z_X0~-N{ly)2@nwjm?R7(b zaZ9>ih8Wu(dC@nn_1xxcNA2D04b8T?OBdh4cGOf|1M>2 zv)43NX8v%>JbBo37u6m~nYVv9!%eC;ihZg5pdHe4mMgn*H2bP})oeHH$uX39rT=c? z>TkzT=0V5Iar@Nt-#_*9e0Oi>I#!>^cGOkon`auetpftzX z+uOOVqc>CLD;hlQ243Jymwn52)ZWlOc~ld3%@5zP9krLV zYL98v-qTL_vZ~8Gwv95k=zf}eW7&_C`NX}>a9uY2Oqs7gu$sHF$#(Xo_LcU;erLLy zd;G?}x?E7*4X9NN`!Cz4pt^hVE*)iLz`|sWPe2t&y@*nK!`pznzf!|PjMq6y3 zy%Y5x(8vw6>yW?#`q<7}!#8Or?i)#L4yYs*mPlD)>;#?O_Z%+ue>w{>Th zW;<#xX-JKVdF%G8`d50YG-W=o zakKs(TwI2Ifx|x3f|oq#bM$_Gy4QZb|GX{S=km^Kmy7nG%qai#(LF?FqhyvnCS*2B zX4#WMX4$JkX4%7Ho{gGkqvqMDc{XaEWq*o!Hfo-YnrEZt*~mP5-H4TL$lepW5i8x0 zy()A=_OQ?m+1o;&W2Mir(&t#|bFB1P_N~z8Sm|@D^f^}g?7wxE(`Rpkv9dwglfnjL zWrMPZg$>Hy7B(n*Uighz`Hfiljad1OSosav&%$rS%5TKVZ^X)P#Ns!+uZxwhlf5c@ zU95ba>}}!eWX}sqXW8e%KgY^H$I3s)%0I{ApZzl>R?igK z!{V6|t7nSrdGSn({mAB(0`EGm0p#G)w`i^|>^adJxHWFMEx{u*(q?7I;^r&Ro$Qt@+2#m};j zM*N&o@pDSW&nXo@rzC#Xsm8soW_;eEPwCVPE3aXEe&UBEQk&M5 zWjwF;(YE-EGN}&kI>zdo4lb2iQM(-5QG0Ov;%TK*Z67JmHq}1eF4$H&b8l0`}eZ%uXwKUVr4!gKX;l)#T-qHY8U(o%=r75of=W+&tnVmOoXeL{j_9 z99O>Kg#4r8z{9SJ8oj=Tb&?J)diK~=wGVB1kF zU(}_(IWm5iytv8PX2`39$$nhsjgbS%eq7P>Z{)sB?Z*{8@xa?G_v4Cso}FVqu7b>_ zz{9Reo@hUSb^N%JtBSot_T#c!>*T(D?Z;(5k4LcFkIUXNZ4B9u%kDd|fb7R*YZuFX zi{6jRR=(vumiuwp55~_V`*GRj%X8nO_T#c=`)?Ry9{jj$c2n+7g&)@r>y@``rSpG- z-o`zTu$rGJ{vpfjZa>F1d};~#hvypFK99^Nf79Y#+w_20pR#w% z%#xRW`lP+BRss3Dtq){t>zKQ8k~c}Mo+GKY^UB>Qoh2OCZ&`*E3v*UusQ zahW5JTtxQcGUGNbCHrxiL&~in`*E3h?N*chxXivseMI)-ik?}tj_k)3?cI4j*^euK z!=*X)<4X2DAXmqaD>-Vz8rJdSN^Y*b+*PP}xGS06&;B}pDfz}(RczTQi^xN}*RhAh z^T_+&dY!%G=9%RBJ)7G0m%m4DzV;4Vsm4Tdy}fU@W8#Ed`=my;WXG}O#!p;s-;G9+ zAM2QJD?c)f-0F+NZI4ES$%pOrb5ga;Ao43cMll{2NRR6aNFm^vK z({-97`*E4;-Y+Ekahbx+)5v~Y=HyMY$$ngBd7lMjKQ43HXG_R_TqYUv0ojksoIiC1 z*^et4al~q}A6Hb+e+}7>D|+m*wPZi8{13|K*pI8=)or=@eq2ez602Cpk86kZf~~cB z?I0(1Cyez4V|}siV5~dz0StYBo`9hz&>t}L2YLmDUP0f$&^PEI7_O{sDdi48H+?0){_F1N5zFA0aQF(lF ziJMOzH)2(CXyv)&9#3sgUN^JI_2%zo2P|9cX0$ofEqw8?KFrm+?8ijw)oxw- z`|FZkuiekze)iw#`K#CKj5_08^#jh1`(OA{bpM*MUL(W^Xe^hXJj@Q?C zG=JS0IbM3>n-ivV%<;=*=N1%Rmiz5J)6Ys4JUNcP?fc{t$y*0bAXl?*BwM!^kUw1P zl258S@`TeCCl9@xC2u%tee&C3h2$Gg`68J;dJ1{&9$zLSFPKIiH+WMrc+w2=(r9J! zz<#sIpI4lj9CO56@}!l+lc8(ok^Q)mJL@bU`*9_0&RT#;U{G0jK2i|SX2 z8?2lZX@10wW%;uYej5GQY67|WqovIk9W8ls)pDle!YsLb%R^0mJegeix5G_~VN=Ow zawXGnubJfSg$J3{HRq5IuDXw@e$;&OyF-48roXe0d_$x6qm_k=$ydJmPISU`@007+ zzb|Ugcqw^(r9Gl67v=b?vzFEzH#o;PPaIJ2?q|9BuWnB#2fVg~^}o5TYjRR%5!sJ1 zX?pttvL9EnVaQyvAD7+IdluP`%U*Nkbh00p?Z0UX*^kTK_wXdLAD3-=Xol>^WqkG#EV%@=5cjyBc`T#uvLr&>}b%A`KCqGvwK<(-nf-i)qmk=qv^dVI6!jOMxh^3~@S zj~-Z@<92tH?IAJ2btuUwvLeBKGswWUX~yxob9MlXikQTwHDN9_*I<+YBvb4GOg;ko%4)b5jL zc=H0*?>nKGssC)QPP+paBnu|y@=gs~4@w}Ue+4f>ihUKHD z7rb9D$KPFk!i3$q@!s~|DL4L~`n>*6jgz&1+rRZV=Fnb!tT5Sf;aKL-Mj!QZ^1!KM zm_uvvTm9s<(?&CgcJ92A$;N7+85mzJDGIa~DI7VUl69Ljlo_M1pQFaC(1*X_(3 zJYUv2`eNk*S?lP|?-$BiM|HkiBx@c0xMi`db^eUSOJuDl=x5>|d6wzt^@Zn5mwB@v zR(?J#CMvSK5NCwbmJ}+ggTQb!MUa(mJMfNz1US?5kk@5$2evb-Z!GsBATJw5j_+OY#Zx zPd2Rznvq-9GNyEu8_DC#U12soawYkyuJ@SxKfZ*#XiG)ZA;BYr-2XHKiW z(yFht>MO1KN~^xos;{)_D_#4^V(~4_DzmSXs_z-k9DO)>$wBpEz=7)_tW_Uuo4>TJ@DyeWg`j zY1LQy>rO4=kq?eFnE&3Zn#8^G29ujydSkrblwRcJ2VN6Db&2}`eG#Ee#k#Mw>MO1KN~^xos;{)_E3NuUhxQZn70N9* z)F+2_$f135=$9PiA%{8HnRQPvKw<-yj#*|W^f5=`=>;2Ep4F4m2K?dmy{zv+P%+eS9kMxBxN?#be^aY>by#HZeUI(1_ zKV-jN&ify-*BR&i581D;^ZtkIbFZdtn3pOr&!Sev+hf5 z5Ou^h$*M20WtOYH#P(Spd>uHeI9>7DBg}X2J<9TauU0a1&TT_3-M^yQ())4pBX3kN zWoJD>u06i2dGMwu$rFy++uS!Q$MX*>ZO&c$|6|>LTD6~6?Wa}yY1MvOwJ*;U_8Xor z;Pmuvm&G5AWGs|k^mM&=#KI$3J~w@7++tKt2g)t18&|7)6w3=Pxj4R}YmPTgyfA*F zV~$Inb3xqwuoDThxLw#~+haB1`hknUH9&(rmvT8G{+RUmpv#QOkYE$MA?POJ( z*`PBH<%-i`jaVMmjvUsM9M+l~bbuUmgB)~bXV&efRr_hxepD}a zEDv@^4)#J0c0>;LMGkgH4)#b6et@jn%&IoCs?DrwGppLnsy4H#P52y%Ni@ShSnq$( zFMeyi{~`M}{n_N>WZ#$d{)g;ku-^ZWy=>O|AF`L(djGRC>-OP)q<#1wX&?Sa+K2y< z_Thh|eR-y^{qTGN!~Zz%f5=`RocBLuzmCrPAF^Lx=lu`aue{zuw}|B?3Lf24i*AINW@CyL>J z&@alRJ~^~Q4(*dezvLhfIm`oDwF&Rh#fX@GUI=z4>W% zSwpw%fxTJhfV*#VQ=5Lx_0l?^IIZfZRejMz3pqo5u+(9B_^m@7ZR3h{ed!DJWuEz4 zSl`QomnKK>Qa`Qg?~qf{xvVYyE{_LYa0K_Tfw{*Fb#~^osxOQ>m=oke-A;`8fy^k+2HD7A zj61W)%yv}$9dZI;Zlz7kIXTQNIjq;tEOU->^o6w}tNpd!|7QJoou41hL*N8s3H5ho z%!$+&MxAuKWy6d)`ucb$&YI@!OtIFFu)NkmPn*iU?GJ~f#B&#;Fs?DrwGppLnsy4H#&8%uOJN3*OagDdm zLi?K2*L5o!S6^0x{nmb>Lfqx`>g4w~9vZj4tQz^8zDLFDzdM~=+RUmpvxh#}JU-&Y((p5B#n~pGw2He9 z>&Wspzuq4oQ}ZeE;_)rxTkHRW{ABeO@zt#wk;lDwM_i(HUGnBt&Es#kok>2wO7r;6 zH!6`;n_1OnR<)T`ZDv)QS=DA%wJCC1%ztPfEMp;u`sC0KIkZm>{gQ(`@Y8bcy9*y~tr5$zgrTVcp3=AIL#Z$U#@Zq61{rrsxdI zRhyz?ELUxcow7XG7g+3?9PEW0?1&ufiyZ8Z9PE)C?35gQ1z2p5tlAWtWw~loY@Fq) z&8%-`Vew{N}wA^Wjd?|;Z%9_#%N*^k|N|3g-7 z!v9E{kWJcz|B*H^7HJdyN7}^LrA_FG^Zp0zYlbd4?|;~@UoYqV583O6^ZtkI*VlRf zL-xAly#FD4eQ@6YkiG6X?|;auP52*a6S^U7!v9E{&?RXT{zuw`?n#^QKhFCf*ad7> z7`E)Z|6#ee7w7#C+1sY`{)g=C%X$Ap_O|T2{~>#Obl(4vz3n^if5@s$_#bH#wkd7G z|45s#WoZ-sN7{t#OPeC6!Tg8z!7>(ds80^vI< zrr0UVgMER;mdU|h$ia@t!M@1B?#RI&$-z#^!9Re-2Fa>Tv00X@HpRwSuG$p;iSl&8 z;m94tNP8VezU6Itm-$b`pv3- zvn^^hiT7z;mHmF(vr&9+2gW(sI@dLfzx;wRQud+l*TnU^Qzx^(KG-0>>)w3UUtRIi zxaU0)dGLS>;)9;c@oTke#m7y~)p=z9I6kyeZr|~Hv6+$~tz<|m8PZCIw2~pMWJoI+ z(n^N3k|7;p64+h(>POndOZ#>re>3sPxZe-m$g^9vji*1;hdgppyLj<|1IdHlc{=Xd za3uNBW825u4q`4Py}oMuc;NPFEPs9K({b&o3(2j%Y!_EQb|qQ$n^pa0Rlix)Z&vl2 zRsCjFzgg99R`r`z{R&&?Rj5M_za@t@$)PWDkbxXzBL|tuVJze@#+^AGjTgbuZkb^HG z2OqUFrzwpn}FZ{Fg3;!(r!aqyD z@XyjO{Im26|1AB&KTE$@Yv=tlWXO6QaNa+Yy-qsspUGZlocGUUufxv!XR_BZ=lwI; z>z?!ene27adH+oIy6U`tCWm-nXHF{_;GabX_-By;{#j&ze-;_wpG5}vXORK+C^EoK zMF#liqBzt07U%sl?b_SB^ZuFa{ebiSne6?8^ZuFa{f6`Yne6?E^ZuFaeVz0Ene6?K z^ZuFa{gU(knXLMSf0lmXpQT^;XXzLIS^9;4mVV)%rC<1G=@-6N`h`!HeuWLzH`F1A z-;zU{lcAvx$LIp{4}^$Y(DeM33?GxU(G`h|an z-m+Zvi&zMH&T`eS*e1(WzhcWQ4>nE?woeW|fgF4VIrtEA@Ga!vbI8FLk%N!gnc<(| zPf!m33_n9wGQdB>FR@(70RId>#&RVC{4@L>%ash`D_DMPt^1t2qaykB$J)3L^GlJn zzUjGA^|Pw}4mP4}CmrfIj4S+>to@a$FKwbuR@L9Z$12~OE*M`snZ2+x+w>d>`#Ol* zS+445ReiA3hYm=6^o4kvzx6W2etyV)EU}*-vX>cgqs6#XeaI~JF&3$h`H}j8pkyU*e3(Lb8g)vv;Fef`R^bqraa?CB}M_7KF)^@7)xstD7 zn`)mc`3;t`t-iGX-kI3hc{qqrd z9U9R^UzEZ7 zSe%iOy^qCt7TM?haLz^cJ{IR+WS{rLxft2|Se%!Ueclh}Xk_nKk>?@%m=}QCC$A-QP#ua2B`y8^I3Ch_P%YDvS&IIKwjO9K@EoXvqcE<8BMsgTC zIm`(;%oRDzAvw$~Im|gZtOfc1Hr@z25M#VSH^@O}$U&FLLC45J_sBsf$w61i!4}BD zM#w?8$wBAI!4}BDM##Z-$ib$_!3N2}Hp#*E$-yU(eJ)zg*5!UXX|pN#&VzQ zma}#7AuJC*ha7wnIru1Y@LlBK)5yWsk%JE;2j56mv7E%ZEDt_b>d3xB@*6By`wq#6 zuw3msB!9wkweOI83(M8MV~2BxKjT~=JQLY(cvh0<=k9Zochwy*b#E=}+y8Ix{P_At z?!1M&tdz&!G5a6ilMnA7u^oR`f0w*__^;d-^6xV2@^=Q+y{uh!PhQ;(%ZB@7IscZs zhsJsH_dko?B@B1GS;ybK{2$++5AWr%9sdr?u6!qv&l+`a3U`Wd=ZeprKjU4(Fozbt zeOKL|S9b!lzjr54-K)plW4uq{AcMbmiuWwY{@y9xzaaa2r+6=e?C+i8eGRg|cZ&Bo z$bZJWit4V~@7_=QGu|-_K8NG-J`L~Ako~<@yi-GdB=@cj+23o$J2>RvbI8FLk%ONk zhx>}ca<^08x0gGytP}3alGS~9-0he9@N(ytb%GxztM>}C>b=6Odap36-Yd+i_X_3x zDYm2U>HRDB`qcY?S@k|(R=p3HRqq34)%$?*-WmHi@U4t+p9ak@ME}FOndaU zgZsvmLEXcbyW*^)?#avDa+a%m@^TklY+UZi|C#SL(qF0jjdC}V{_W3rCo#;S34Uys z+{5>N4DV~iXfvz@Ijj-;Qup)a9SYV__vhuE3zn<<^YV@c%hmmP(LI){_Yg%_S+3qg z6y0XIdJi!hY=q^(cF5r_D_Pwu7F%QaA9+_%#ihTSV^sOcKRq9=a`J!59T*jtrd3?3 z?+)plYFgz~)9Rj2TIE#J>Yh(p><I=Si+i;RUY+EKVJ^#3+z|rQAM{|9(0}@Y=InXgdA*#9BhglY>*sm zldSTn>EIJsuI`QC65ZfDtT1sp5#&CS0#^%I}(ydmAh?}LFG~9E*#5M9#!tnv0UX*^?4#} zP|g$KSLHkrepSvB|MdG>Dvt_ZCwWx(D7>dYzY%hkWR*vSuS0H=|Es%&VeR7JSO4ibugar}Zm_<} zqlzxET;)+k_gJp-sG_SZS9w =rTqn_z?NE7&Gkks(l>-*jJI#sR@?~=>6GXBuFEL5&HuOa#gNRzRScqD%U69abmg3^~raiSgvw?@MFmTuw3Q(jw}F*t`D{&xjy-Rh1i;WbK?(v6Jr;DTMT(T{q8e-*FSxi zS>^iv&^N(C{?njemFwGO-|=E58*c-};bm;IJ?C{SEnM4$IZ|H^k4d-1{#1{>BbD zx_>3Nrq7yH{jAEx>390TMX~X}64R>sXcPB&Aahp5z*!XoXZ0THU)lSp`dL+981aC# z2|bj)9P~5DKn}8z^&UCMhH{aatm@00u-yL^??18~Uq|kwp)a|UCTqkxs=mxQ+fnr) zvz2>Re!O_6l{V$aD|Z)vH|M76V@{;LFnkf_r|3P|JJuD?lpVYvdZ+vXGkH*nOzlIL zL_J2#H?K4*nQ3yu@@UoT^UNicOJz2HwLWS#bdI_Ivr?H~KiCo_6K0w?DV?b@t%Rw2 z%T!aXQ<=cJDt%Y*VVjW0aY)ZhB9IdfTF=IhsMneLSa znKB>eW!@=Y-#l^5o93X6d6^EKt~CAbd)-{NE-%xj^tGnmq(0`|Re71cAHBi&zn7!g zsybHv)~Ysb>q&W;3kvhiert!=J8#I#JY4B`)8)jmw$tP?nM{oeW=64$T~)eF=9XW| zm{Dz}*t`o%XGWg-W3=MP8FtCDr82#@e;ReYeYQQOuw0fQU#IMGz%O zkeq`cDj-=TEE&nd&b-qk$$1eZ3c`{kDoG`LRkhRa)!w=1@}0~7^xl1*m7l#mUDef< zI!sUbYzgf9m3BE($A2x#thgTWQt!Ra)r+gexMO=GHr?CjP;E5fWhd!5U#t`;At?P2ea z-tDB!vQ8v#buO&ZPdl6kx7LfjUG9aY2;1g-a>5oDE+()Fy}iZxXoo8zUku2gRs{!t#(4o>=Px=B?)_G(JE)xxP9VM z-CkLajAiKy}7I;Z1nyT#B#3nNPO{Mva?f0szn+li=< zcY`y3`wr1}NMyw1oVHW^`ZiHN&83KBrTor?dt1d;rc{;m~}G!%lWMNZ4vREG%;7A;LvcRSY}xdL-dON58IGX=XI;nto_OR=$DNk6`UY zu=XPu-3Z1{1miP;@z48ZzukNz@la}1Lc8N?e>9&>evPXjN8_G9C5Xs9c@>q{IbM1L!&O`WA6CAB z)sJB9M6mWF7~KfQkIneB8UHwT9zO-_&|#V|^vkZ1&LIr_vL78@PZ;`Tx4yKNF!U>; zNZZwfpCHB4dXtK#@H`bUX|4kW9@{o_QM$6FvgF? z__P@RF~$q~h;a$Wj$@PqmYZ=zY{n6>8Arrs91)vwL~OULKGHZMHsfgOqudaiaYSs!5wRIZ z#AX~3n{h;J#u2d@N3Wd5(W_76h#2LAhTWXDdXZ&j#9a8XpnYo?9g5{LsOEyzzwiu+SWlIdOG+ z*!1tk_+2wZ;sH7B0$0w8d)=mrOtXHCh?;*+e12-OxKt$~B7f)e!oOmYnD_Y8h)D&a z#Pgp|6k=eth^vF6#F)er#qJjmZI~AxC64a-OuYHkhV{3nM~Qb&eI}Ow+PP}uwo#&Y zrHNwXv{Ydye?2emeLGR4Z`UHs*Xg_%zj~5*qw8m3ZP%R>%eGDyHDCNXZ2Z(8M9;2M zM5oAeVQ!(bV%(?GM1f7otTMMwi?Pm3arwsr*7TAm#ktSE6rJCZ)~k8G6It$ri~3)+ zuvQd^6w@j%6YDbev_6KIHgUpgF@Ew;YjfHi!j0M>QeGWpeVKK$xR!gPuwNcyefhI3 z5*64cK74DW)qc}jvF_X5B30Lc)~kD0iYzbg7rl0OwT}FM@7#BC9OJL=Zh6}kBN#4(^!3*%oR1x92dWiKM}TR?sW8%<*w05VZ3&h70j*8-^irNqE zErPR%-wLONv`fCXRBYT9DM~hMWcR!FmDusa0g-;rxjzzZilkR>0;VAppBVQ9< z{{0Yp!t_;y%e3om=Z;)P`2BXT*{Qx*MEI+BEqhhYaKf2dX0bnOKbLUgCZ{8oj0RbO zJ~#e;WW@C;v!ik3x(y6hWp%>Xvtg`Fi_x+e4;JIiVmw={FJwo^1N70VoN*`daJ1$q ztIoxJgd>s+v0i%PFyStXyIOl*I!3tE~&hY=SFzrAitzT1oy4sz-xD4)zP-qI z;4I;g%x{PmFP|ekpiDDyUY;im^FJ|Wd^A3M_xV8i%jv2I>hG9h1=<;_D+b!nzPe0+ zZp5^b0e)&tE*9Xkg1<})o6HXA#e zjh)TL&Sqmrh5Bh^i27+{i~4C~j{0fF0`=335$dNIJJioWIU76F z&p`*@gblKRUeg^ntV~6@_#t!|7={wao`pm|T+Bf>o#*X+g_QJ-F_&4^&#*X@H z%GubFd`vrR>`0!5E*m?Nzu}XO9k(?b=WoXDaBg7i4(ANU?r_d#><;G`#_n+LVeF3P zY+k&>Ih(ONoU<9b!?}&IJDl^Fa-0j9`Zz~2_KR~T(>~6r3|*XS8GdliX86Rpnc*Mj zY^-0lu{*49^cmYRdXDWI{YSdSE|4E%FUY5{Bjn%M7vy9GjNM^>O*zWJ)JOT4c2I7n zeUzu6i*h#np!^M=I4*{NK3)vlZ0u|{b~YP3n~j~##tw7<)=i?v&Sqn0v$2DmaA*N< z?6BO79o9EvhwYfL!}iVCAzd?e$d4I28{byrG z{1|&-V@LcO`$C;G@s5oh$-x^tl8sY|VzXeIHxfH`t!m zFOe@#%M6(J+b3SXD-y4Lhj6_Pr^Tefvj|7*)FQOYX2Q99Oc&M0oFUxhc6*WO=X->E z6;CBz_%)Fa+o`oxSkIL)v=}Xm@nA9DEXK11{W5()Z2E|GOyBWYBNJ@X$O>s086poxw#b{2 zxy8l;=X$~Yh~Rz%-;W5cp#|5_{`57p)GrSg*Sl`UIAQNCIb3Y3zMJqW|1i<_dL-e+ zNrs6}>z({(Y_U2Pd)8uYTAS9SbvlJqp?NyPcE3l<>`RTBQ~ACTN9-@tHY7Yh*F*cn z)tZD^9h=p$SsiT0GVL&I11(|bLVe4$3GG;h7OR78nmS0!)Uls${3-H6`}GXtzO&Di zGfZn)SdOum?a>7Hm_R0&E3v(y|B5{(7*od^M;vQ|Ep}#rpE01gjP-FZnC&h8-S$aI z4$#NH)gCvT8}XU5H$Bfh6cY;nfIiJCwCSd}_+7Nm`FPt&v3zj!8gh#vn?<{&OVR$V z6l>;)(pPDp*m^XgpBUagdVO_IkCGy!-5sj)(ND{*%H=}PFVMbP-Bbw)L%D6rp}u44 zLpzRX2ikW``#{$*bb%ko@B@50hEL$%G5oXhFjj2mTbMpuT+fTAo8bH?BFVqaIy276 zI{PHy#fQc^rEdR7_{DppoqMfANLIIAALVQ`-Tvq{AAeug*;S@IJ^NLil1{s!(RAnaE$n=8 zxD1tVo1fR&RxG+)+|BOP9#oFXQ%uR^Y~5RdFpGm0i*Xi`WO*RaiA3G8dwW)B7SHEgrD0{a@a*>iz?4cqL+z`llU_Gn-q$M*JdEVid( z%{oyd?6)7s6F-0>3}$;G@xH$UGO>(IKvtHK70A#sG6dOLMz$#`O|y*5VJs{&7A)Vu zJm(Md4bTB$bO3Zi7~KG!5k_Y~mxR$J&@o|j40KNz-2YH_1 zwiiI{n{{2b7eM@&bzrs^K>V9^W40GS{WaxmFM#A@+F^SEBu_(^?FEqh4WDc;z+!8X zbT-JWpR+Y&Jlhmp|A!osts&EyEi*1pbN!#?Z#K*8Y?klYEDy9wE7~lVvssR3v)s>SIibyRMVsZ2Hp?w- zmUG%H7sd4lv+iND+|On?q0Mqdo8^!;%Pnn|bMiHlSl2^Xj%Tyn&t^HH&2mMX<&ZYy zIVQKXS)a7-?TXID&)hi6($?uTbxOiqYrU`(!vXJbqbiDza^Zi#1UOwNgCY)mf7 z&-~adS43=bMVp<~iTCq4EXPBcnA{I#WpYB4p~)3dwkC%}nVZ}a$HL^Cd~GV$btjhN zp$?eb4|T)jgs3wnS43ShIV9?s$t_X$OwNfmVsbguRg>eP4x8K$b=%~GsPiUQL|ZU9 zB-)6{Ezx#N&WScKEq2Dk$9{LlL`=OsPIU)KV zlPjWMGC3srE0bHIA2T^8`Ztq{^7TD@-^8pN*eqAX_f1R=8RMN4HaEA~oZV(~d7I7g zZ8rC}*_wdO)(UL4hJbsc^SreMEH`ToSl_HgU^`}w0^2uh7f9EvX&^sltpoWqYaljT z8{unTvA$o!a^~PUsOU3n|JCQ9Sk4?gKjV!T%bEY{&d;!%Ie6~E8?XQ7a~EvAi{~?Z z?JGt;!}BYKd40qt|KaPRJnyw)%X@kL%rLKy>p6inRUW$;=4(DN;yBMM80PhnmWlf@ z)_55|vF7%CF2HcCYsh>qz_7*gbBpEe7R%=?mgie6|F_t@z+&?Si_Ie}HoxFF-sc)z zXBdw6T%FG~7`9kGZ?QbzV)?(t<^>j;FW`B8GmpS^U^BnK^Z#bvf%9u$??v4(`7r8?$&*o+O#X~IX7Xy(J(F*vPMSO%b=BnOG1it@K5wx+-(vZ{#pVST zn=e>w9)bE9SVLxO*EmNu<$v0|BR=L(d=ALkw^+Hw=3Ew=i&<=rX0f@O#pZOl=VIo1 zG4^QKycp}7`7*Zi|GgIj{F}27IJY%>G=JLsJwDbVKu^rR7+>q)eh>BSPuVZy^F)T} zoQc^-z;X}ASUckJ0x_?{o(+^g?KLjL!_(Z8WqTs=K9A<(!sx~rJ2vmO*nHe#^K^^N z-z_$;x7d8&V(S1FTOYtP8+b85w~u^iS{g712Ja(mKuz4=<%;CTssd4G)zdt>c> z`(EcnzC9C;hiw|W&n{m%)c5uJ^I^q@?y=Wi5A~HAek*MH?w$7C35k7mtq?2Mux)m& z+(~>p#wD{R@7QcV_jwXu`6217&(^qhvg}EHOEcxRR$W+c7aN|`cm7aG>tV<$JK2t; zzKeG)>)k_(?H%Wn`hKhSqV+2ZjSn(bfzyLCvjR{3AiFD8HM?{q$&-F+16eM3VBz?dbqThCog=yTVm7bkyPY2_Q7(Dy=(^a6RS8I`~{ zbz(Y!yyXo|;Hy0)tw7#-RfO|^E1nU^+w;dCiNXic2;^<4{fqFGsYmrAQ`{F#_SL2O zL;BwpeMY}P^;8J?~0Y5zeBu@EccW6F-dKK{ER<)N2F2j5TD6v-4XQ{ zbt2xD55FzKetMgDo7d)Nap?G4L~EaYON7o9OeI>aw(Jx)a;~QOi#zNP{V%Mf`b!FK7bAAAp!!3veIx3v{fg@ESh__t zTDy$+Iki%Y$XDPUa~NOuZ7tTN+)TWkzu}5!Cu}0#uD|ArQon2@-X`_(i`D5j60Ne& zI%4-XF45YQz!sGz`ia(rQyawNcO0VC;hTkGc>hCG|IF+KVny16RR4{M;bPyW{Zv28 zg!!Uu|9w<{$+Ed(Sb;sn+qTxzMT2+G5N|IRo-WR0J43vU+cHg58v8x*cA)Mwap2@> z;%)S&Q^mYPr-;_;qo#-wFP|h@Nhf|Ts^2ry zY$tjiyGy){mF>ittapjGg3q=Uw|}}#v~n(JE#9mP`Ukd9U9}P`x85RJ@BPqH+^Bn# zXw^DbPHY_gi0W5fR#tp=-~rX2F`8?T|aAIP)-}5A9U;P9ffHlhB8DDn}(3-3KP{ zA#b;qBom=4LVRea9gZXw=l4D)T6=r1wetNMO7&~XHP-wLp;UiduGLoNYKf@+io~m| zgxwSR(5~-3`pUX^H^hgwxqYdyp8F*!@wTUfu(EASO1z!AW?4(RCMDjgwXm!NNs(VF;773<;rP@?tlMkUKWl89*GIgqna(e)9he-K?CarZ)r zsXo4M*r`cqp#H(ggoZbp@n$pLY{r|-c(WOAHsj4^yxE2~kekiqW;40jOl~%ln{DI< zW9qOmb=a6XY)lM%QXjGclHahMNrm=AH74{?|eahMNrm=AH7 z4{?kS0srPO|K>3N<}m-}F#qNl{|3I-VZPU4zSm*C*I~ZbVZPU4zSm*C*D<~q;)28C zg2Up1!{UO&;(}x10>m%J#4m_h4vSe1i&+kfSq_U?4vSe1i&>6|SrAVh7Ec`(PaPId z9TQI>hB_vOLfm&u+=p22uvqV~Snse{@32_!uvqV~Snrrv4|#~g@(_pRAr8w!9FvDY z?%|l+1M($5%a{BnUxFOT&vGO`%aQynNAj~A$rh!+;V%BB>sv= zno+J;pkZQv&elySSDex})W0EF6Ur5*ElK1*X*Z@^@!rTJ{+#LaQ2kxA68qnLl#A+b z+7aq+oFEs~fBu(5{)DM=Qhld)LVv?r*(rx)b5EPiJ^w4_$ZXDn=RnLmCV%;JENs5^ zRPU-~bKY3*(Pi&_|0UnSPnRjNFTvNvtZ}(_*u_sJ_LW{&+#j9xr^26q6 z_L;5;eLp>$ULZegPG_@upUvijwsYVoQEOCffjrB+cf`eao)^e-*&_Eu<&1R&_I=;9 z`yzGC7l{^|-`T~s{VMXNs86((E%{CC{H8wU%y!*+4@8a^Ucy}3es#$Mad`4em}A>{ zp8rYo-P@7cVRJY8wGOvMy~wwz9X8jq*&NVj^F+Jl;?pA0S7V6hojcBm;~^gr&r9e1 zAgUD`M?81?<(wG!a2(NM^FI6QyHR3A*vCYx%+3p9oBw0tx%cZA#gJ?hi065$FN!@4 zCJ@i%)*Tm}&Q7Ox*qqMZHtVFA7UmS&kOVK z5vi)c{ih)3E;Af4vVx{|*j&%v@*LbZ_Wed`hs_ObHfOZiT+*JLb)Go25ZVRZcxB;y z(Runl;yFdq1>$hS1H^NwgbPK=F$akjn_#q6WM5YI(Zlob;${YE@D&sa`0ZugLAv3aFkbWVBk#?;3|YeMY`BK)}! zoPXIfH&hUVJ`2HlnZ4#=1-S1H)@wk{8NN#{X6;JgL%+f1jCM$>lw$nVgg*2eY>sKO zxu?zMr1sVKS6GE!OyEP^*qCRPm2*TwANq|GQ&wB=O-tlMzi~c%jn%MqDA8i`O}ksz zIxFd@#6&CX>^jSrFbVN|v&q-imS#za=S0)Lwpx!#LOgGuTh*$&GcmQp=8|^b>XudH zb`olb%{^^4C$-sJmCl#eE|!RR4xhet-mbSoiD$$)2PY<;5r6kW5~79Jn}^b~hkL>r zJ;!^AAZqYm!@3fgW;rV35GuFTSVKT$B&3HC*Oyt>SJexTw@@(d+$g`QlqMU6e zXPe2{W^%TfoXz|cV}!yqCPuJ zpB<*p4%26c>9d))qCPuJpB<*p4%272>nvKI!3G^>gJw>OHs~-LG;>(AK{K~S8#HrX z^cxQI8xHdu4)Yrh^BZP9i+;mle#2pY!(o2IF@6Jlox^;cnX96&bC|C)b6fOvX3mSg z&di0;KRe7nJIp^j%s)HKKbv_j`e%pvXNUP`hxup6_-BYI4vQ&f4vR6xVKK$bc`>G# zxiH2QGe^ca=&(5GusG276%;@2O)MlEOwi@Eyiw##cnef z#@KD<$QZlL+!^x?hvgd%%QqaBZ#XR9F!N%}HyoC4I4s|ASia$yd;@YMhvi6S&Wkyc z!*V1uN5&k<%$+fpb4)JB=GU0lIV`VpSYGF_yw1#*F|Tu2Ugxm9&S80-WAZx4Mg1%n zHFIIiMg1%nHFIaoll>-7hP>3wuQ4w*^KQ(a{Vad>v;5i5@@F%T#{AjO@@GHGpZzR< z_M80qtP6AA*6z5j%{FDh_UTDQ~DG_jK5IsGv!cUB95lHmN2#h?GwiK;a6cDqzQi`jQqeegpnrD zAneg3{PHt1!dbbG)t9Ut$=a8UF0>KgM=?GX<6l+S|DZ7P2ESNt`iu3A9Ize2NR!D; zMaz!*h5TR}@Viz<%c3I6QnGO&nPHtI%eK$+X#Q=-F3GYwh2nec?0R$lPsT1JWRSvr z1^jtEXFtM+50rIRef%Ebnz_DmkFIWM>gfJCY7(}`71Z!c7|Jv}P8jNHct&D-(1wP# z2t(Ug$NL$C*AX6u#Ri35cKvU!2(B{z&5#JuXh|0_5>{=+P`z2x3_s2pZX(thG zm8WFk!N-RZ-ch?{VfZBsWrg8ygrRO>cxFDf4{a2Nwg^Mpg^>o91AQzngc!?-hF2eH z5O2^9(m;&u<1b<=gTEohx<~^twh>KZkjA!=29_g5Rz9EApO3tH?S!-T!x`Oh#!ooo zGo0}se&*rmG|}xW#d6bMtZ(Fi?SvCQAWJ4Uq)X*g_76FSGx^U4{;3YO9oyJ3KZCK4 z#uWWGixC+6s2u$_ixK3nQ3ud}vltO0#-SXIzh*H4>zf#X?U)!raSrQad|)vG`GI;A zBQW+6#x_`tp!kDzkR~g~*k|g;h&8NzjD5sIbYBDfD8^@u7#Eo*-2$&)F=8TvTPljL5`G9=u;R7rEt3JL-xMr?r z;onn)LC@U&IkpnE$IWx`7wKXd{tYqKjee#j_>7w_wuR-`_PEr$=X-pDzg_7wVQeSq%r6M%EWE?5yT~TIH_vjn?XXC~Zp8_1)cgyC6Bd5MeP{MO3(qncN+w&$WDax!V*#-vFh<~$17r8Q`hbc7KmVd9 zSeP;2PsBq)RaoXqyo+#3-%QENcZYsNr6eBql%lkOi zXOk?c4}EK?^1OFNa$5Y^#%-5TosO?MlGEkSmMwIa>a_ltlYgcRsWk}cvq1AMcw%NTPXHaEe)Qyr|!<|Z-bR{u1P5c2|aF2Wv7h2_`| zo0}kADo2_aE3gjy;GByv(&Tz*`iT8ye?t79^gG1R!hfF>Ym_>UFY9ldFy#A~+beIqkuc7O zyg3)mGrTz${EgNdsScZSd2430E~nU>OX2*+TbENf?}7Ek`5rwi$9WNzdvh78@6EZW z9dGVK?R#?~TC4NsT*Qwzhax_`xm933gzbCljT$lX!s?qj7q)}zjZ_EcLyRubz-Lhg zj88)Y`N#FfaI9l!;J;Yz&AG5&M8mX$G!Wx_%bRmyzmOklgUz|94Qz|Ijo4dnr1Id{ z{q@EU?G^ka*=-O9>>5j=3Mt`Pp1mJ>796J0N>Q^ykb4g6)tf z=|9o75&i!`9F)WVtqyqeWE_SVYY4HGM~@f&H*S1;b6R`=+c$nCE?BervEn<{2w0QC zpFuhhW|Y|7=1PsKIEXN>Hi5|j-8D557B*onm8mReV&wV^V$7r3|A%y^S5^f z8tgL|>PS=PpYR_(3w??;FaG`9d63?Crb1w?>yL5ld2uYcvts3Oz=PDrGiyx#9tZsY zHHR=Z6l;!ec>XYX7yW75O|%Ew?1grE_S7EcH)c@UQ zfgjWvsuLFseOEAE)OV1Hg7G2@vQjW!)DFl&!Fc@(j?1&?J9e~57SPW>!X7ORyyJKw z4}?A5TrBtK{tJ%Fv+#HvY%03W3ky>c?e9Nos=r!RityF+Lf6<J&9mLMS)+Yc%0t=Q>35=i*4*=-h?NsQq&f$-`Q+H-(Ps>n-&=`iA)=oJ z{y1G;&g=7bc>A0#=ZEvj`RDy&v^1mTGFrSZ4x=R*Ey-v}MoTeTypMc5H0yhe`n(<9 zKBvq1VKQ+z|GZzI3nX*w_fKsL5MG(Fmfl&QI^l0m7uGe~wIDp{S|XjJ)4PPr_K$E& zF7Hct|KbMjyGNqOciri9{&)S+<6d@aQu$W59#qH5FhxdIX-~M#?Tct%gpn>U=k<9z zynRlW^TYY%{PTV>S}vpIGFrSZK1NG2T9VOHjFw`w6ziknba^?i&)ebcbGn=#CKDg$ zpZAODGuJWX4S(s3Q|{N+kiQ%Cc~`ypn>vKuj34T5p-J#8Z^-471NFj%iOJVA+23E6 zojs9o%3piv#od1(++%77T|HMO8q@We8)`V4Kp6kU|HpRl?^q8pK8MdE#`dsX#7GC} zAx8Sh2V&$4`9tjSs}N)V{-XR-Ux0t?M*tsNk#iyT3uAoxeT7N33n%u|Uw<}_aH3A# z^p)3c5uWl*8@=mj4tlmiwik7)@4^UQdR$tUJ@E?R<5kn>R;Ax2-1MbL_e$+vgs%@B z=62aSfN&-M4*yr(qh+4qr{TVkhJC1f`G~jV8$&x2&U9moY}lbW;U3Q>RiE{)M)=&W zqH1c#{Dc#ouf_M6Vw}5Uds0}J>f_k4J**h#`k3D0`8ukPZLo7_AcH|v-mzoV!mRv> z&q-RlPZc4NL!9QA^U3H92iDt5LnG9VfTR)SzkBx<7VUjFm4L+bq6twEn;CX)S=t}>pW?FFaHYxIU&yy+XOjbUld{(6XcmN$O-#G zb>dndpTTyp4QvZBwv99pBTZ}zF}D4r^|8$4~iobyKi8^l351a%;&13?`K>OfEjf;te? zfuIfqbs(q%K^+L{Ku`yQIuO)>pbi9eAgBXD9r%mufM)y$F$p7je>z$&K^&ArPzQoK z5Y&O74g_@|r~^SA2OfEjf;#ZusRQghHlD+$v%PqB zo}J&ubNJ?*HlEL?I&e-oPW55jY0dbb--r4)<sT|%x#CH)9KGY`6uZ>u0KtNj5mBgop=Ucj_)871|N^_CKCqVkMAr~UmzynyUc_k zRw#%Wgdv6~h$Vy}wn&IEgdyfgh&_ZM7Wp715r!D$hgd}zVwVdsj4;GB7h)S>h;{gm zHerZ?8e$<~h>aTjRY3l6!OYfT#M#)&K|UIO%{$8h%>1EZe)9iBA3m7;+k&{n1>Q$^ zf7!);!TZYiUNd2M-x}X{raS@eY{2)RY24v`YkWVNFuZS#?@bei_pR}LY8nf8-=)Uv$LcMwg3iEFRvAY`Z zIgQVvY-7`HYxhhu7eJjSo>A}O!`H<&7XPN4`VL))kyBxRuwU>Kquk`B(SI65eMb!a zA&mX=avl8kZj8H({u3FFc{|kPCx4m@c^~7O{|u3r;2W>_^PhbS_#g6*eNGg!&Oc%( z5T`Nq`u)3@=?VIIGrqCnxWo=#2Y8@1y|$kOBfqBpzrjzIbFx07o>TiMr`Rx)A=X7c z%v#6qVqEvZIP=Z)QNH5#rk%Oh==}@-q#%? zOAy}qMn4U6<9Wy%>N}^)%Xxj?4!a{F23^h%=aci#`^DzhiqTSxR*d^7SRWOmr5G*6 zXh}v(vOfAaU0%-X^LBXqoG#~w$s`8KE!1>Ks0cI)%E3*t@rrFzOWQE|#NCp-v-4okG8i7glg!a)MEhm1W$=anlw;7dNSBxM`n(<9KBvq1;e2xbdB6TCmm@wg zCNNqt_Ffq+%q>mdHKU~&Etk=9nQZ->E-&Zxc{{v)PM7n;WDA0#=ZEP$-pfjD zV$Q<*1++BkB-#=46`J`9ockDGgmWU&0h|*tUx9NID#tk#^A$MfBDy%|Vm=CK2I%r~ zUZ1za+vjvSKb%j_KkpZd1)9YUyhob&1e$n{G-05L_ec{4ns|>iVW7!l7TzOG9wa~GU0%ROS$=k4(JIbF^V=aci#`(<)h>@)f){1@!oWw|TfO-JS6 z4_ubJYL>fdmb+?}yK0uZ#<-7;(*++*`5Vp)d41jvZ=ciU{BS-w|GZypZi2E!-w^`# zjblU@>>kI?%zbc7$xgvf;8+s|{}JPC49HetJK%3nX9$BI!Zj$u@FyH=Y9IVojB;L| zw}XBV+w^oSK$r8w`Q-fbez9B~WlQZqOu#WB3^4)6j%Yzlz%eBZF+sCj9q-tra?}Bq ztGgI?kx$f_Smp?tm-G6(9o{~t%lYAaa{hV0ke4Nki>vVc66gkTP!2&I_%F}_4Lp#a z0NV`WXulMcLr@O?Cpv)s0PPUt;~!y|SI$S<#h8lcAI4s`)TQ)AY43P@{qky0tGsB} z`XyCJh3(Bi-?r{kBE5R#B*e2%`jz^3bsaHLpv_C<9hA8(7ua%+(1_Y zUF;X~qk$idd)&aM20pdNzXtwcFD7*%)AyM8@7Z5(tZ5wMg1Jm^j~vFGFBkm$IZ@CnCw=hhlb(3(kp6h> zlU{jrN#8tvNDn?NfFB44KM)?@`ha^m z#t;0R`W2g=|3Ue`=n0%93V)jZzr?%U=cluq&-da&y!rpXYril);uynEjQy2| ze+OY4_kLo>=!d;Z*#48?80#MF*%;+<`Gz~M!}^8on7+q~qj?`>>cRg8@&AxajK1Qy z2Qdx&-(3#T{R@5vye9cP%$ISlghP*cH2gyt{V~p!upIMl$b|@F{?%?vxj+3ZE7Cw( zn5QER#F&2>yTsh{_i%6=|1#r9dWGW}jIq&D_#cr2*>ZG`qkV4>|1Zb^M|lvuzZ(gD zJNo?!6GOn)(>ffMdpSD!23)^0u?YXg|HnG;6Ug5&CgJl~i0$FL5b=QiE8soh=-eIS zhAGE*V(LRRW#$AJ_e}d3_Y7T(dr*(s#F%7aAjTxaKhRNYR-dHzA-r;kQ_*n}=^^&o z!L}%_B0a<&UBd9c$PZzUPr@Gmgdx_#yEoDL;`P_mM>!CNc2GWqu^-qUq=o%6bm8wB z>0vp_!|;i6LV8$^@{5kM|B8d-_}3XnKGsiwQ9okXqxbB;lw&<(YjMHQ4(gq0C$1Rl z#jqoE4g_@|r~^SA2OfEj zf;te?fuIfqbs(q%e_tIq2zQZ;Ik!~aoHI>w+!5YcuDiOeY__$o#CLwjwA~J6tkkta~ZEw_6L|SzfkytK0SBS1!J5+-K8$ z_x%B?*a#VVqw;jDF8aN{jYt;c9-*nHyy$Y|EIUrY8jF23AJWJr2?g_~swO*!Z zJwJv_xO`%(4}HNi_H@>oV@~Tjyvw|;dje&BdQmQd`y6H!$fAyvPO5%`cb{vGDXPlp z%qkS_Pv}^zqN=r&5=<{3@S=ciwN_ zx+E*Vc0lficiyM{xJo`qI$Iuqciwl->nfAH+En7Z=dag~@@2`o*N5+J4K-5y_DZHK!~ro+9MJ98INrQr^g0&B{uw{GP|-n8Kj-)&F6Cao&lB>~;% zbN%C=WsPIUdMkwbnoc2$f~Mo#lm#&Xxffa<$?FM@!rv{=Y8sh?~2jAqZJ!eQMZm2qs}C-wrh7*V)l8`d=KV$Dy`%XWU6So~?U#7(sES%G>s*{o_l{O;+EdQz z+Jf#K?Z5E8FY8;U@m(!-Z_@0A-+%e>Lf+rMYG2IzN7%1nm*&o!J?&GttM89-Vz^)C z)@Z33buO+rj)HgXr{)b)<@**^qv2iqwC|NsWB2D$@4>tF%iMgb`jWJ&1dLhsUTM^T zV~^zLaL3K`y4Pj<{NKii%l+Vvo5&&kWc}l9@Gde{Cw+)Kn=OjuKmJ6nLipYi^4Tu; znxbv9e_1rX=|Ug{5Y3v!|t}^GtEUSHtEkY@7X) zh4?K7V~_Za24koA?FM7N_)Q06*Z8dmWAFG42;&Fv+YrV-;5Q?T-@tE47=MD_m@s|@ zzdd364}O!v_$B;Sh4EMT4GZJPz$Yl<-@sP{auw`5=F4i~i;RfB5?WX6rKnjCVSjcnxb28rEBA?IJe$#8%(aNxBn&V@?;=WHeg~(rhhA zv$Y`2)`B!!3qsz^T99UILE5YZJxyA?k57s{Tc*1dJR3Lf@&|nEzq7$wpOju)uRzYl z@$EzS-4wi!_zf*RFoS*-=7{(Wt%tLIbBColi{Ba1diYMawp!!1f^TTGO7W@N?u#KV zenab%hNavdp*dXqhSrx$>-e)zDd)#;XjT7WlCMwXa36j{YyX&9^3qpjBz{9{%)puQ z{OOM*enV?o=waD=j$gueQuNub301`=mnD8ft6Q5as=%8`@w+PSjygqE#L&$6y%o3N zR~1yk8Tk}`L#tv9p>ni?wJ>(i#?6Z@0`J|&1>?PG6;l@QEkB&j$8mkQ=c`%zqVjs< z%(5Ze^Yz0^pU9Q>2FoAdo-e!SF8O1owK6x{^L6O-LpeU(Ik_9|Gw+=ulj`tNV#QTDCGGc_XCu=_hJd-&*Ph}*GE6}*UvGmw*+FehXt&? z2rd(jW2+w$@*b{hdGEsKC~h#P<@M18*}9%=U68Ho$<_tgx}I!Zkge;1vp?1{J>dvVZ(JrTUe72}{E_C)-! zCxUTMz@CVJJrRt9681#!9#@Qm681zSkI{G^BE&%ndm<9=Lxeb}U{555{5fy&P1nmA zT-XzFIrey_*zM&HF6@cKkO`MhZ1tfpf&CqhIV~@b(y%Au!k!4`ZyNSQH0+6B{-$A1 zM8lp4=5HGIL^SM)VE(3IPegm`DjN1gw3okW*b~vPCxZE#hCLDeG->fZJ}Jick<2|p z_&$=kU#Q;PbOC?s?Uk5&hj0&t?r{QIxc5Z4+<%&@ocM71;_!51rJ#yzl zcl*7`E__!@Ul`xgy;i)o3*Xh!&#LYIN|jdm;k#No(T?q6%8FG2zN@7VUdSj1mrg9< zyIQ(bml3jP@AqQd!R5`TXwN7v*qhsG*dNgxdvj_H`y(#wkKmlzh5Zp1_D66|?ZWg~1n&gKIkg}5NBlfS!~O`)sU_@>_+Wno=hPDRM`GnUzUg}F4;uDIG{-!4 zdutII_D5pKgv%$k`XF;$2Q%vx0nBN6Ycd-4M>On@;98J|{SgiOBe)i%VShx!{s^uG zY1kjpus?!pK^pc)H1LLNLByN47NlW+gzl$>wICPvN8G1LE4Kc|rQBOTbYXwQ_0|V0|A^=fY|UBmu}=Ga@q*RVgLVSfbI@HOm@XxJaYHGB>GBO3Nc za1CF>{)h|vBe;g|!v2WMW3;!1@525F-bIXS_%7^^ko;j!XCB-shx<7C^9*x}R=hU> z_eXH=Al~RgA8|j(^f!Qc?DqCPD2{WPa2#8G=!@z-qY;o_&$QJjWjBIi5$;ej0dJE-0-rkduE$%&$Y@a4A?C+E8$6$!Pc(Mw?QfF(di$Pa*Z3VqWAFHVM&k$YyN$*_;P)Jj-|+TZ$)Di&AB~^E??M{? zgWroZehI%LY5bM9&r5#H+cPEq2EHP&#`1US3-4E4FvKQ2pJ3u|0DET!OiaWx112Wo znE?|M@yvjUiFjtf#6&zZU}7Sk889(Xo0u3IZ}CkRat1tqV)Cm1=5ZWy2|SxY>jtsO zC${>~FU&Daz8AopF62~r*2UyCk=_D9Sb zejpaZ8oq@65wnIbVSj|y@cG@s`@7u;_`~?7>-Ev>2Vvg{!+J{~MthjfrgE8Z99w-n zdj!5+;rkMiqh4KNFsJMF(d<2;Y|Y*i%GT^Xp={0G6Ux@?Jq6C7da^ZpPbgd3dwQC* zK$o6qKMrgS@6{*ycx#*SdagThlLRFyx42mR&+;cvoB#KcHz~e#to$?i|J`+X&j*?_ z0D(GXJMZ-EzWS2C^t%J}dV=-i+G<{Of+hJVS{ z{`%AYO4do0#Xst$4|Vv+f$~D)RgV8iFP&)lEO|CpR{LK2?z&2!IdWa9@2YOv+D&U2 zE^9V_+1i@7o9^*wk!*Eqo0YWB`+CFA+vJyH9*K|jJ9=!HA7qDGJ$+{ichJ*&|0XA2 zb$pZjE%oMsk7O118(+yyuWPtbNo`oX&$oF~3q7l9LbZM6QD1BQnjYUQwfcTkI+^(8 zm-R%EMKvuDCbjPcz4K5W)$XMZa^Ym9JM7D=l1Futo0>}9dTTz_V%U4~az>wCxhB6V zT=D~1>Y$~Yw<@OY=KWOW8d_GT_^h;A3cPMTQdp~+2+xl^gY?i+x-+r;-{P`h|;qZ*4buY)eF3NCSho)-moAq3j?UWJCRKk|eyD0Ob^IlcWTh(-NEM9k;t2JG!xj05s zleSf3cI0<)?51^mTkY?V%*8QHwXdr>_V@=sj`ifx@2OjxPWe#>u2p+qrJD1dA9W-3 z?e|sl*^z$KncP=DP^HqZ@S`rR-qTkdZamSCI#zjHf91>>Ht%!+EA}Z@u&R)w0phmg3E=U3KBb7v%VU!+rH{w$tx@o?L~6 zhRW}nHPQDrvbmeudq}@dkxz&R)RaNSPQ{94{QmYP^>Zu#e-*ubp zydhg`h3|DIE9bs2!!P^IdPgno6XL4f!{zg-KTr$nt@D5WD1)rOsh>L7WQ0HILoEi5 z9H>g)Z;$c`^u1E^*W8IO_fg%VX8Fh6o#zhP@t)fB_=JCK$?x3am)k3UpR8`1l?nBg zWS|49>boIJGwJs}sj0GN9pTm+SWq8&R7SPPvBskF|0GKXq(WuKd_L zzUx+)2zkm!r{!}^pV8fZeO9l|y-JR&P(b$`P*^YOHd0=Hp^{$KF00PY9dG*O z?OOgl*ZOPTFVF|S(Ff2IztI!WAHUHb&@0#I73iC5^bPdTHF^m8=^Fh6y>*S=f{J^&1^d;;e!;G_ zv1_n*ZR{QVfHr;r{DU_B0sMwGegpi8HvRXM0fsADD$qVAdah&pNF zChDq*r|6f?e%i+WOrL=o{guH`2mP1^Kj!oNn+E^p^ZcF$zvuJ(p$32G^L(8KUxyfd z9bwNds2xxLslI0y)Q)E_)V^mI8vL!#vkMJ=*yq`W2LJ5y^k0KN_jz`q!Jqp)d(q&} zeV$!t@c+`Y3k`8WdUl~9UPw>>HN+R`*@cGqB0YP7cw19?cA+62NzX1c#3||7g@*Vg zJ^j}Z@1$oJ8seSw>_tPolb&5@h>y~<3k`8odUl~9o=Q*uHN;=(*@cGqD?NMB5Pzj- z7cRtW<=KS`aa?(J;X-^@p8mU#4=B$rT*wEMXD=?~1In`t7xD*)qhuE@|i*`HAxE!iD@qdG_K$exf|Pa3P;jo?W<*=P1uE{E+`BPyhXpFDcJ1{E#mx&tCkH zFDcJ1{E%NM&n_IuyOd`aHsoW<(|-%{H|5#I2FTx(XD>G7Z_2X^0r{Tt?7|0mpz`d( z2l=7$^xp^hr1I>-2l=G(?8OK9q^dGvg#W>(uldep9H=}S@qvw~B+Kf|hZyaH7##zb z?ERa6e$E=cJm2(JMZ$ZzYrAd{O&j-CKZmY$w^i%u^y=DGZC`iE^?f$RzwnKADr`v# zoos(nck6&x)cad=>Jz75ar@V(p{ivsu8*XhCELDN9U}*nX+E8t4aab&yDRWb)R!)8%3k`MElx zi+;V{&pza{ORrwKO{t|m|nBTYNdzBKIv zU1jJ3Kg#d}d@92y^h+83pox3C-P(DjC>mTBmZVx zaNcCbj$_a7(fGo+`^>nb4+K9+dV;qakiCOlA zX)w*HQe!v4*^k;uPutOr0s(cgjtCQ=O`KIQPs(k9= zs(qI;6iq@e{o_ze%hn`?Ljp0(i_`l3x=ppV-05&Eu8-+@nUWWq7@ z>#5QD`bZCb_tG1(N9#KBcD6TlRP_b2-Ly%v{_;jz-#9M6JhVlApRtNAJS|kMuW(I{ zxRFgK_#mqq*fN>&|8m1UGp?xWyg9SVQ6$_=*sp@h^KL$Mq*LyZENd`xr<3ySfd}{%$$9<>a-qyV>Um_1o7)Rh?{w z-ObMnmHw@wYTbphZsa9P)r4=_K56}pMc&javo4TxdrXoXx7^rBzp(ST3|p~9ZY*9! z*Bl+HhGo7cze<)}pX-=aoo<*+wJv+pJw2qTnz%l*THZF?ZQG-Qs^2l6x_YCGd*!C3 z24yR%E}t6iN4^+1zUlHl#sza7iwiFI))~2ba0xZ~&1~x2^0(xPgH_cx z1VXD)F!m44SlkUbBORADNva71AbL%_nGpP@*BvuXI zt)oM0-;mW49f_gmoQL?J#br`_#X!|9JhShto5WZCgAY`%H(!#)W>k^=PPbO++pm+0 z^3RnmA1Rgp-3M~__Omiizf9`fh3x9>k5Z_QAZJc;@LBcZbGgvorLlL8S8=JszBxWLIgQO`&#f&!lR&*;R(OV&b?w zTlZcY)%vy7Zn}47yBzmO(oOxkp||Vwdc$p+qn{c(E!6E?@tVKv-GS* z0Pd|y{;hBISl3r~YY#PcMk|>y!Sk}wqYkRh=L_VCs7bQGm`3VLaYA;;vQ=idTvGD3t1#=yX3odZ5th!M%xe6VBM;?1URLyT(K=sL# zUTqyUTlOeZQ4M=0zp7eflkdknKK0|pV(Q@LP`6cipSn`DnELhWmF~o!%Biq4dDZ!J zskHbyk6L&v;lVn%UmgF(?Ft$3e`2lWg3y*+3uFI}|Y@I@F9h^~h z>zqTKP6T_{%$8%T!{t*n$B(ki;9@G(j4W!^H&L?Bu;S|O(5#Bb%_prtZT3w!vU5>& za$aV|@!n(MZjKHW)ZFIzRJu!L-5rqMR)zewmVcbn4E$tX@RQpvrI9mk36=G6QMEs0 zvaI@EB{i~C0k!kHGqORK5~|WG+0;krGN}HgbE+;YQ>p_Q%c)`+ldG+j?#OJb>Z!`5 zqojDSCkEzq__MrCPK)!vdE-3uzT}+IK#i&My-c-syPQ(HfjV^Wd%6DQ9rEDKm(-yJ zXJmn!JLI-$FR9VZ&dU1ZcE-SQdA4dqS=FgYay@X#9hc+gZ`M<_wnn+#hU|4SC26a! zms#yTt~J|Tm$sWK*QU4oO3^pmy?Oho^fJ^9nQ+w~0e;o#T;JL4RCauQ`>TdqzV#(8 zr+sPc9;(sZR!UoPRK1)x5mKnO_%pEE|}|BT(AOJ z^)0hneqL*~%slluSl4y8ES~*Y<<88hP7bu>-bt29 zu%n1-pSO_z)&i*tk1Vb(JR0s6C{{(C|GHodJ?A{c2Q4m>2X&gNU3(9>BQ{64%`&~G zR(~+eed$hT_xmIL)%Z)__%|n7=|6j7fZB2IW8cB8gM78KbXV^;=qgvFY$_|}ZJ|DD z_>J8C;R-plcoo$h=7YyzKFD!=(2C6#xW4Tj-cXHgb4s>IxJ|bHq=8!3@_Tt^$MzU{ z7+am#`~bJLY4cxFy`DQOC-m7VuP?2yl2tt??^(NLT*sA>&RuohQlF+NsyM#6^b_YA+&#M)?w(E3IgLCE>w$?A7E=?q zPLf%BRZ>gK7f@wppOG_ql~C`t%%-;7ORw%*a8AjeQk8yGR`oBKT-|ScN0$Dgp4!+r zO773KSGFtHR*hV%H!&jBQn)q^sQ@ z^Uii}XYZyuChP59{;s84t#Cgz`D`M0!j&KW)$R>cpNy~LRPJBSIn=YidanNw-z(o~ z-@cVSRECDF<$^DtmmJ48UEasIV6J0v!5tu1A2l^p&Mbe;ckApsDu3OHvgMp%a^|51 zN*_5bi#6OXziU!V4bT3JI{5Ihe7O3y95KC!T6j5=%F}a5_VS^$ACKKoJ9~FK^=3BW6o*J8FN-p*}IlHX2tB79dphJ9n)Q_sNT2z z&&T1N7UMnpl>9EwjeSUqwv2Pq zb7V2TVpTpU|26|`{i`M)JoBkoHt(F+=N-wPd|n}LZkQpKTpGY1H!C439LXoDd>h8S z)^!QBcdj40rtSbfA=-~saV^Xe3q|nORadhU$R``)v}h}(d%>7vynJt7O~EH!0}^YiLp zI4@jvJ?mF`9&_m0iC;BsW(Um+nen~(Ps>+(k&}6RF!2`|e7G@gHf}b1JEQ_X6Ce78l?lZ%q5nnvZ_ib82soc$ zj8z{1=Mz-l0Ou1_p8@9+)K~!LQ>ZZtoKK;~E^t1DniGNZDb!pEoKK6ILo?2&*%+sF zyT&p8gZN+aO`ZEM$3Kl6!lN6Uw*)+}SWY+&<1T|oXr9X=wZKci^5D*0SgUJ4vtQe{ z=4%4?Grn~rv%eC|y@S*9YL>^Wsa-Dq=8vL0XS!UxZO%B>y;&LFdz9;Ud2Vbs4cn6W zp!xvV2T*+j>>H>)1NK>{u?QTCP-7H0Mxn-T!LeIZKQ){a%@`Z!|3B5%f06(4zA)xk z-Y>)W!#ocXKCC~PuodsAkReV9*>+}3_y=YFrc}l_ zKOY>2@X){SX>r>UHRpwc`KS3wTDE@IHRF5ppO#neERJ}I8)JoAIN~L)@DfM7#1vj) zh?khcOAPT6Q+SCXUSbL_F~m!n!b>K^OD2VvEQpsZ>is1UF9~C8EMq*^Sf{ZqV;_ut zGxpgy7WF{37pLZ2g=YZqJQ!nzfdTP6C~ORf=Rsj+ zKs*l$O9SG0P#7B!&x69=fOuXgOfC@53x(AM;(4Lo;{x&gcX3*`YaC;0Vq=b_CRTVr zAl4EJg9*f7IyOr{Y?h!f8$-;-6qaL%<(R^F3^5*4*pDOj`!3IoeMpP8jB}zeFdzm7 zg^dBRF(}Loh?zlQX+SJ36vh^av4z6k0E<-_nN}A0x_*nI94Fm6{#s>oFDbfwBR$-qMoG|e3t6(Bl(X0r{xuA z!jZ3I##r%Y4EZ{y_&SDs9aDTAL%xnFzK$VZrzyV9gnXSz@pTsD>nw_|6Uf&I#n%bs z>xAM@1oCy?#l|wmbB%Qx+cNgS*f(RJjbl-KjzDfxD9%$L=P48yDv%2midPZHk$xAa z=3K?60rJUUj1>n9$R~s1W&!zRP@F9wpA3r21>}=KalC+hGAQmBkWU812?O%Uptxc{ zK3OOpNg$v6U7XhK8poKL*qCFfi4`9O$n^=u0Se>*h2jPUa)Ux~h8E-uEs9IjkW17Q z$HQ5-BF2Mdau1>|NyakhY*EhsJ*kjn+d@d9$ZptxUw z+^7m>FZWZp(1Jn5p$*hU>+eS}!)?da+5Z z7h7<>*rL{p1+EthwO%Z6y;!LAVu9<$Lai4At``fneh0W-493`4#(1u=PGeifJ{bFE z?6Yw!YCREfZ5`B_JK&l-sI_>&wRlkLdVp*6-^HmpSFP;=>KTMFRvG|6Jp(9h0HB@$ zlx6@>&j3nG0H|jGr7-~1Gl0?_0O}b)X%YbS44||MfO-Z{>zIIghVSCEZr3=*)WpUd zOHHiSLjl*CL9Iapu0exZn-;h>E!3K|z%^^3*0KezWn0u5w+Yv{O=|6%;oA3id2Z}O zTC`=H6QuzF)Bu3e1^{XUKxqa5H3Oiu1b|usP#Ob3jR7d_0igB()OrV?CP5hEv}h}( zd%>7*YE2w)O&ruZIN)0OcX^mn8RNZgjE(o2TGIzy(+9PV54hG3sVQTeAGKx#xMn2O zS`y$|k}$qE|7m%p8Dpqd)Qqvx4VqA|Xi|Db3+fduO0OtTuPBsWQJ`K?D7~UUy`oTh zML@lxPRBA{Lolzt3QulQYTEMq*^Sf{ZqV;_utGxpgy7Nutc)OLc>d;)4d zL1{q&wV3aFF5CUwBN;P-L7$rsfmp_mYP`U@c^~Wpfr$x8c0yu zNI-2QD9xlm&7@FTN`YERp){5PHI_nYFD0N~;N|)%-3G zQ!10vbHI47DNQM$rWBNp6i{mlsVQTeE2UWi)GUG0G68Ct!1&($r{$IA--7-fi!oNd z1A+b#fnE&qI|%fT2=r)>-$9^%M4)$r{0@Nr5rLi#@;dl1Nm|E`6NG%KA+^r(dU!=IQo2&A4i{0VVF(l^+Dq3kJ#~2Ivt3#&rimZimNf^IM@;rXdB<}z#)zq`We{sw&qWMotrM}CwJpSK z);=JXv-S-!p0&@$vEchup#Ml>OT?T4{YMgWA{G_sKayA!-)jQ>M-rnNv}B=K=jkI-UpgAL)1=(0`=kc|iY>j^_dWM>?Jt=s(i&yg>hv zj_0j$TDP0hcvCu_Qof~h9Pxla|B=L6h`|K5sNsNuyTcH0)VsE_P$!{nzxiLv}%goqUd`i~@5OidZY zvDSOv7#r_3#IyqaM-tN_juq%Xl2|u2WsLKqJe%^Fsl1%>S&Gk0fgWo4KKiHSku%}w zKhpU+YmB@ZNB@z|*D>@T>3khS|B=quG4vnle4PpXM>=08(0`=!bpriII$tNyf28wu zfc_($ud~L;=~>Gl*JnK!IY4Wj$PHTCLe9|I2jmj1eM64X+Gpcfkk0}1A4zT#IZr_U zk>os)3kCEaNiGz56+r)yE^T~kz zBb`qM^dISbGNAuR=aT{bM>?Mj=s(i=WI+Fs&L>;rv~D-0@uqY>?U|B>VXksB1~Ka$)aa)uW4A4$#-xkQHkBgrKq$H>rsBsoUp9y$7tB=`6u+cM4r za83+O+RTrP6Ffc_)N@gnyN=s%L&FMe+d^dCu1 z*chipTgLo1#>iD#a|}62K>v~CB$2BG^dCvCGBst8N44Jj#@KkTA*TxHKa!j(@~D9R zBgwU6)X?a|;W9UE9*Nd$&uG=#7AL;AG4E;y? zda()pNBVlPK>v}xUM$dmq^}nX^dIT##en`JeZ3gaf26M$1Nx8j^iBzwJlt;w)O$nvaNl?HEwI4jbp*}L_q(MTwBLAcR>G~ z{YSc<0nmS>>lpz3N4lN?(0`=s8LV+yx0}*v}{ z0H8Ji(0?Sg0jL=O^dCvh0BQ*U{YO$ufEoip|B=)fp!NXJe0`worH6vV00`worwIt&^`k$6Z%@{-fk*-&?#;6-Kq5nwND+=@fc_(??L^Hdp#Ml}K2Zw_=s%KLP}G$H`j4bW z)EKAcT+|Z^^dISZT5F6NR6zfcuBQd`AL)8pK>v}hr-cETx9fUZK>v}hrv>yM>3Ui~ z|B61A5W^dCv><&SL3I1i{n1@s?D4Jv9=0sTi( zn~IuMK>v}{tfH0`(0?SgtW~}Z1N0wBjVo$j0sTi(`-*xSK>v}{#2VwYXv>)Y#u&Al z)*M4kCZPXFYBEu)3FtqPTFumyK^>{}-Z#d^dkrv~S?4Xwi(0?SoJm~QO^dCu&5BhNg z`j4dd=l_MaWDcl4NDq|ioAgGhK1yo?nF*7p-2Y|Pbu0)(0M{R9Y0>-z~1 z#@6=}AndL0Cjf^11PH6^`w7r{T;ET?8mD!;DUCO!<0<7^O2-u*kX~G4dg>L{m0tVQ zlrheadS*(`rh1l2FQtw8WGkw1x;_LMNf{3rv_X{GvPTwzx z_&R;RAmZyZwOUpB-b9KslzSE_E>Z4fq&P;o$C2V5<=#g>vMu90C=OQc0j0QE zxi^&JY~`L&ip!OINhyw3?lGmfU%B^``red#QW@j4Xv>)Y##nKcGT#&@DfdKDT&3JA zDK%vjNBS?%0pq=ewDOdtnXJz>&5zhm9&1R?^kJ! z(SKwugZ?Ayx#&N#)`|WjYg_0)vi1S}N7lZf|H#^B<5<)hBB#AQ)tbB9^HZ(G%e_F= zx}Mx4)EKAcT(!2V@25(71{o_2fWDt9X#@2AR7o?S@25&y0)0PK(irIbsgm|U-%ph^ z3HpAjq*dT*KUG@C)b~@h#%bMdO5;uGcuM(}(s8vOD)+inYtV8JOtm&G_r_Ff)^g8G zwU#aS(o}2Qa*s{5_AU3`{E=-L=Rs)z4Rhj|0XQ|Q>$h}OJ#z5|IsB~Ju)mp#Y zYcw@wjPs+`jO3nmYAs3bWoLXx|I_kHGp6sCPI^TdE8U>JUpna(_5IRGuc+^rPI^Us zzjV?o>ieaWUQypKo%D+Oe(9uF)b~p#{g}RAx-~}sk+lr^kF4jS|HxV=`j4z_q5sI* z2lO9V`-c7_YoCo{Q5rT*d&?`$r`&U1X+h;)^h#GI_oz3w$MpR}y{e*UC!)%Wu!?W?|@KWSq1{rpKQtMBJeIy!wne`}o9?WQ!| zl#ZvAZz&yDdOS{lTR~|co;%Dvo`#!~L_uC$kO@An_smT?}? ze?%Hoxd*<|rgFJAezIm&?wPN&ta2}XrE!&e>?`f7+qkO}STmYRV{$=)XJ%jQ5(-l*&ErmDW`5b)T9t#`#g2CAnv^(lW`tl#TD` ze_G!5cdu-J^UIb4wj8kKfGr1XIbh2HTMpQAz?K8H9I)kpEeC8lV9Nnp4%l+QmIJmN zu;qX)2W&ZD%K=*s*mA&@1GXHn<$x^*Y&l@d0b35(a=?}Ywj8kKfGr1XIbh2HTMpQA z;QwzqP$qEls@PMEuU}V^pFbTaCO!(~4^i)3&1JJVT(>Mg(XJTBIe~iIlZPZa@`TAA zFrbtJ|7y19Lkd@e#&zGZ6_Hoj#qDh%_LN}j*R5mQruKk8#*Abw2S>5iMFvCg_zbK^ z{%4w<-Ef$4)n!$gz?`epae>Dzs=UDRLe(R%9--ZC3BeR=W7N*WA23IG3Ve=1q zLi6hR;1B2Gd>{VJ_@oKxq3`S}{P?FNu`KbrsQXiEKJnN6!td!uu`DWv_jDgCx|w^5 zZQTd)=-+dTu`zby+xuZ$MASBq&Qjj|<@R8HrP(vBYOV8H;aa`;Z+-i+K0RBr0t4Ig z{C(q@D6o=E`BH=L4Smj>oi4D?lYRJ%ce(iPgm0{*V^6&weo2z6N{xEs$M5J{0_~%+yS5v^Kf@F!*+%v1MNyW_fd?KRDhfBkp{16*c>G zgLj8#i(5%!#Kn=#;P8h;kt<}EXgpg3uV6dq*6yBo8(tJX-gkl}j+tQg;&?MAz|#2~h{E*ABJ*p89n(Ueh0;$*(hMl;@WQ-8|D; zlfPs8wGz4}UwIJH)I*VhW%Rnz;(3X*_D~o-3#p0enWN7`YGSO@>KXY5vGii7^8Yqg zeUKiI)Wm9xdYx9^M@q-3PMe0`=3lVofGr1XIbh2HTMpQAz?K8H9I)kpEeC8lV9Nnp z4%l+QmIJmNu;qX)2W&ZD%K=*s{JR_&F89G9PM!9NO8#k!ZS!Eu0b35(a=?}Y|DVqR zZn#FaSWd=p+dSCj!IlHI9I)kpEeC8lV9Nnp4%l+QmIJmNNQ)c*IjzZaYm063V9SC3 zXbwlZpY3eDU zzu!QACxK$}PLNlFV)`2q^mi51ar!$FdU^W$5;Df$alIaDN3WlL>g}rE%kp%d-cPDe z??1J($duEI+ET{_#j3oFRXsq*RsAwn?aCN`Mg5U6wS(u&nA*X5Wn3b*0k)I8zM;me zm#2A+xc~ zU^_oG9nWQ1O?g9esIIS!)peIK{^~!LpExcLYAfxpSI!@Lz3{%nd9>y&qgds$ zj8&e?`BeEYV|8EX^Gx@PjOjkW^JT2=FB#+fS)V7ynA-cFcpXc`o+1S+duMNuwBRhGmNCJ zm;MY-bL@xL>xaBs|EE5aasF)YR!mxjJ>>fW|M?%o@IUC?3ZJ9mJr$0Ez^{ea?@e0L zJqR^d&t=)0)R*za?bi{PRg&@B5xMxV3qCTYpY(4kPrpwtX9sj1olnQ9KB`yE4R3hq zcg!2>aY3;vFJo1Yj8*+uw;iZc5QZPk!s6UoYFW`)_;g@Uqf>KMs%C-gp0}+?4HoM;ZIy{C!75 z!2gB={lD$|t{S~lbZ%3|>fIt^;#7#+qB4quk}*BEY~Ocj!&&`L{Z6MGvc2!DYa;Ub z^Z$g~|3TjcxE7Pr`))YkIs##MeceGm6Viger8a(K&N!Ysg8ZrVStlq~&p;XLxSNju zpR5Nto~w!6*pGMzCF9G`6%)76JdXQRd2@-;<7HeRD{Sskag>ZhS7hIk@mfzA?;BNi z%ZnFHWK2Kl-*hhhp2|^7=h68TQ+-q~#mVi^>{yTc8_LUA)e}I+RsAwn?aEm7N5-n3 zGFJVUF|~s2>Bs%CA9{Iz?4OLWo&ao5##nySqA9C;LhDVS6&B zb|&3xSCGo6}7FS~*Dt8aX|N7Ce5p4!22(OC6wVHvA$WEuY_zvV|* z0@M6kUR@^|8eJp$AC2+5>r4MWe|oFdy2xjG#&Z3dQV!_rk5s0bi$AVAzm#Q&Zy?@) z$`E#==T~xD!x_$zER+1RlHQj5J(WqAypjzmd_a~_e2Xlj*1Kgn`aPAS{wRJ%mQl|` zRTs50T$WLM4x|1g_ak|Il=@5krh2Hq)Nd-IV@@hd`c3uVb(j1e)uZr?yzVq^oJT!>3xm&v0&@hts^WBn4b*uQ))voKN;pH;(_7tqxSbUUh7oG)_c%+ zKc*bZ?^66V{g;|p-s5r(@dRq?e-~4(>Sa<9C-W?_JBoApcX6F7%v{ z93R@TU_O(;_->;ep*<&LHXXot#qrCb5&K_;9>sW7^}j<~O-l?-#5nVXY^M7&R)wCz z_*$ZqsrvMup=U7OGr+|Z=IkJkA0Fsty7;^Q;vi` zFz(Q=pb55gO`vwK=FMfwmu+PN^{0LM$?V39KK#(@T-ssxYAk)WQv7tTAny6+MHcuV zk~gjHt^K?_C$IjrG5?%L({_(8#Sbpf_$%Lf+UfDt`IAcS{N4OkTA6XJcq@RGwkHR*%V+_aEzOHDLg^ zJZmMMUo>ew+OS~{Sdu!FEx8eCNeG}9-R=}CRezsMd!M+X87t4aRqGIZUXrA4x zF)!(TOzg~eoIRerfu$>SSzA6NhL4=kmY@GTkxe*%mUS|(W;eCWtog7Q?&;&sU0@_D z@->7vYSEm(irK`RpPprpJ}+a1J{Mz`@!W=w>+@SnPchd&&$68#?O3at8`ynpD^{#z z>+-kez6Fo7{B4Ty!>4~2Zq0&t`bnNVVx#+$h&AhZp%g%)$o}m z@actWDpN~ zxQ)dRT4Y(DGlqXl^yTx47ZmpP!QAnEN1khTH*s%JB0J!|gJnEA(vrb3hOd1X&L57c zB|h9sWHrV`@GTKuVrbY&2A6g+&-u=l5SJLf<4tLvx4==0Q(!Rf)+CNi%6H7{>K?-v zdIsQ{@u!#x>lu9{#`MKMhQEji;J))&sNa}i?v3pZ?Rv*lqg)JM67SDPE^ehgTN})M zS4Z)SV+v_5jZd>zg?F+ZqrJ4|K{5Q9V-zp9WxAGY!D$xm--WN+@uxQa+G*D2&NlXZ z$#`uZkKs-8mF6XGUeK}}3+AlzR<>)#N^NzO7#`QR6mOT^mA$zW%x`q>%@8*tY>^SnEb!{KfEwY+c_F{gYIufed8V^W2U@dB z!7+SHrab(}#$#+xVlcn*WD>hDG?Hbi5W_q8W#JLK|6<;ogL%Z)VBTVUPG0%`X?Atq zIM()dPxd-6hF@7#j%V+bkGG0F&9XWA^AqU{^E2&FGwu3NcKXan=H?T_kJS9eynDT2 zQzr)V#ijbNUc<+-?jA8b$MvVI$Wwd1t5Yy9Q@J=lINyu^a_AJBSF9U*Y(I&Oca7oq z>|OZLX@1wVt(GCZdu-<&?)x%OB2>~#4P6H6vG`0U1r&OXXmdg2J`3lYO};a zzq6IOWB9gDf3Pui9Jy1LVBYIZ7CyfK<84}=WH*21tZwYx}AO-!?9hEgs>;l4`GDJ-$S9&rus$_Go85E5=Lwc6`v7*SbqQXtc@TFJUfe09vxwRr z#BaAL#lvm~3j0SvJocL(FA)FPV&@#pudegw+q=xRG^!EItA_{h1ry`Voq7iIA$|e8 zOScE6T)zkNlNtQ^urtfFm3xADgL}Tb?&l2b_C*}yW=CFs4Y0jef_ZR24xY2^1y&q_ z`I4{cdG5WB*t12!{H^w$tvL0WdGrtFt|jiUb=5QTM)iXE=A9?m{Jy#Q6vlh!3&#gFOu7AFwqa`PmHA^*7<#kEE8q47GT+s9UFg`Pl&-Qc?x!ALo zL*(%aKEHbByEIJ3cwFemu^y(^<2z#R=IpBepsxk}x$`*LR%Bd*d1HDc^U7tv7Tg@F zj%R*%P^;n`Ao~!O!N=SELZFQCxJ5r+T|Lj|zsjYxajnjqW-AVtD!OPf@4fh}N0ne! z1264!nM{11xdki^^V7zC0QS(KJ9Ow+S{q!Z9V@eV05~)(sa5|Lu9c4%1{?3WX_I36 zSRS?-27N~r()!FSCnC=e0(xKkRQdd#mFe@DwJ*bXR_{+1J2!v0ktc|U1lya&wVRVb z$1hHO6uPIoIiV89kBc7*ZQ*l0p(@6es>g=rJ@X-<8pe&r4GLYgDYLmc#_3LahE9dt zGH&>7UdW)|@|mgphnekmSNP;)u8i>jCuhFp$yRX*+wyU6w0!s}USzu#&8u|2VVOQG z3fv=)u^FM?wCb7Hiwb@*Jj;ketlffD;v>fHugkD{u1mxT-xz+^;|43)s~$|*naDQG z*~4zgT*@H#(#pJ8eJpa2&d}*UhaADRlHpyXurBi$W zOeq({_ilJ<-ZwN5UNs8hlRq)@wzu)Z`%W}Zv|GAo@7H+o>RvSO&@IH&U~C{9>lVbz z=H`~`30-0DqhsvRh!y7AFT29qBFCBMkqf4+?c+t?r_nrP?onEY%>i)Ww;*1#P!{d# z{;tq<;BmIChr8BgQ=F*tBAQofJyA0Ub%ohmkF%OiZMDFaJ4N=_(frldi`vVoQLyB} zarRUEDy`G=ZK5hZ2MU#Zua#a?8oDnI;-gpkv%>pIL7B}#yujYQT81)P#fzk9p7&Wr z24y0kYn2mh?AGgAnXH>d=a2Xd=@ZGyj`o7cgdpy-ut%DDeu* z_r1u%uH=9x%MlNB=*t>Jj}z;jNAvaNp0c|gGr)-{L40@reEiLo@=&wn33g)Ba8{=I zC~^KtG;hTV^J-oJFvbq+Y~aqlcKN{WlgHWRMiW^7mAypa`_X*&R69QL)LYTKPY|DT zcM7YYv5QE$9nI@a&B`x`o1$3DAl`3_Kd=3%Ff49;oTVFAo?C*P;7PILta3RA9$Mj; z_!tz#9~?JpTTc5!y_rG0#pW)nd)TWPH0MmpgQ>GD_mx zSLK^Se%H+s-!6*TAXbmRqFuprhljU?K*T71h;K7F#EKfcsCbBNRr72NIem|bs)%pj zI1Uia+LYjh5#M^Oo-ORo7319y-^Tv!EW*advO{<;T#fM(YnrZLL5OchI2{rnt~KWA z5#M^|{Zq`nSf95*d^^1+7yj)QGH1lM6FY4ba|S!}(}-_xZKy4R7yQmvBfg!s@vRu2 zr6%8sn6`d=6R~2=EM|w8cIw_g#EnQt{x)4Ok6WD%K2@p8_anaD2U*}=CB}b3d|P{8 zS78a6#3~@Z4fx}dn7=qX&xH6k=lPs zF2f2pI>T;f+9@WaFQr{YeB0-nAH1%4Sv!FEmL1wDer1nMSrFg;T%-#`SG=lqMNB*B zr#Rtzd$8#pV%pVf{h>=}N39&<-oQ*z;F*7pHXiZqqQy}V^U6)L?{J!#C&Y=hb;_7M z5#O$D7XU--r-m*PD2}-I;mdINb!SZx z@HUav{L&HHf9NXiBfdSpX`?7m@R{XT#J5v6`@k+9Cgvl)jqSQ#^tqH?Y{&On-HD!% zv}LI1j?d47PHn+!-ds^0@vXOOD=<%9BmP2sTf9{<@HzLpXoC25z}97=#an&?-iXgZ$LG(2?aj^FC*#K9PR=k-VLW5~ z)heG4S*|c=!@-S%SK8+{6SllFb^e~PsmWMz{~6DO6$f*h30uw_J2>Inv}9~qN{dZ6 zcKAaA;mm!0#}ZoECu7lg%cF$G#motWE%mvj_t$c-Pnx~Lw0)<#n+Bd32Bm{sw4@G2 z#Dl|w;RRypd7GDr%3pfHNyO48$2}JxD|du2#L`<1IzxpOVX(hJNp0KfU}%E(Y8}MV z&vVp;ukQ7XED*P5I2YESCMiz$dXgWGS?VheVK zTZlQoPI82hMu)@%#GGHFa=^FP%i<+s&N9){M9EU&5_7J>_wR|0zlfKJIe$5p5!U_s zNE}AYIXZtRLxg{`F(M2xXY_tASliwMCL!j$e7dK|)^>u#oSQBegIoDZ!Cb_gB3o;* zI?qf|1@FzzmG20%PZsEgn6toNiK29qJP?4GGj4r-QM<@oi8%*Vb%4AJD?&%aoXxXV z6HWL6i8%-OW(VhV8gxgTxv^$?C^^0gR6(5CdRr+`z4CHV=uJ)Ph>CtqAZ*VG=Cc2(B}?K)Q44Wz?Vyoj!dVZ95<$FW(iuzjkDDc4t$DY;$Q$kh zzKCP{4P7EGZ*2{kViD`!++i_g+9sCbyL(i`6me})JJ^gkcIM`OB5S9PP#kfrPw63+ zdl`319NTJnL9xKs51t{8-QD*mi&ybDu^w^k;4gvom*2l*XZ0y}EQg1g`gXA4hMlLL z1p@UseZ0FVet+i>;(>ScbvK1&^xQ-Ew$t{arm_RFBoMy+WmW;xxF?+w2;a^slGF6d z#zhIlKR=HA8v48A;RNEJ!!6fBuY^36$D1{a54|)lqnYsS^9fTzH{Q!@CVV^aNVU*= zL50nPZ)dkX9#XZvo0;0Z(&(XSbEkO8-*#y*OFLSvE9^jgn^0p6t2nQ>ApSPjol<8F66`ca17~JYqeu` zO8z$B%499xX@?;G)}^!q^L-o%#NP%tE6;jWiU8tokF@_o8?a%EApUkt&f=^^XI~)x z)-(FLwt2}WLHup|D^1v@_1-}I?T7mV*a*9hK>TeH`y_2kiw%PK+Zn4Svxw++K>Y3M z?2B2?b&wu*f7u4g7{nSuA^8&J`W)Nwp^cLY(UUTLHzCOZ}VBY)kT5$+fQ#T zEIwURApZ76Jzusk-!eh`ZPo#aY+AjBK>Y2%ZP(c0#`S>s+XFvWWfQ#T3*v9{Y~9KR zbuI|R-wx?pk7a5@wc6S&cL6E zN3EI(*(oa!f7^adf3`W-7(x8)r^YYY=!JGb z{O$Uu1^M`80YLoi#DT7S-KLU2{O#YSbo@xbGeP`q$Knorx&3}Y{O#`5_&1F=tQW-J z-g&>6Oz(&MhN0>GiBYumh>5FA^x`QnQ*@JU^PMf?bgW=JoJIPApW+0;W&1? znxlpI+oRmn{{&q{w zv&_CvP9XmF`M~?^ZsCkT{B4;FMR?T@O9b(^UW46vS+{Y5_}eoTkT)LMP7r_lICCjp zZ>ygm{&xEdKVI|jI}7o*bD#M0Kg&iBb%vSv+dne}@&#{mXvE(-x;I}# z&sd2?L-Mado>OAZnn7LW4d|JSV}F^teR|;J^J@rCJ~Natp4;Rd+Y-C0y2Qi1@+Gm^ z=f5$+$#&*I{!8W{$;}$yJ0TUi^IKbiQM-x+Bwv2r)mPTjq}7-$ zvonv8I%2y;&9{^c@sVwv%o)AqV2`XaetvD}meKDLWtnZaJa}t1MxOf=IcN6^TVc7E6vV0ST-yU0uh=Np>8>5UwS88*{E~N#Tey2q z9+ppH;EGSnC0sg_OY)^_nvYJHUN)1&zy*qJNN7Iqt;D_M$DT?Ens`yh@9dr@+`hh3 z^0A$kr#A;ZpDHo%w4h9K{^?!3bf#muO-}+PuUm9tNwGV0u;i2Pmx>j?J?<&_ttI*7ML(I~m7AaBlQ(2)3Z)C?kbLsXv*Dl}xGRWH_I|ut42UTp z`P(5b&B43HZbAI5UEF;#n7l2CDwo8($gO)3t38hA^twRY8xV#(BL5(9_Ud?>Ep z$SAqlzjK}wu~-^0C*-))sXt%##@SRkmF4_CN^a zMGXAVH50raTS;QzDpvzV=(44vCSu?t&Gv}4kRQ4r2L2r5DeAsiAu;g1*~`U-(Jqq9 z&2jUwaPSEOd&IzfE)@`?E3KAX?w)*CMYoAROD^}!v7=)C!$y+Jeckr6rQEy?5(DoF z9VZ&?E-ty;J|VX)FYj-XT<*E>wxYxUZ^`AJ9vLgXj%X#h+{{Z4S|VJwN(}ts>TJ>J zx3-eYbz3z`RFCc;x!iz7Q!N{N?~q*XmHQ>cPZNBBxZF>rx>&OB+bOx+T6OPQay9S= z;&O|=Gl?!95t7R_T`eT)osE=S?u*8emNumV;WJ|3r+sq3l`WS9ak=L_-iVA}>?D_) zbpMbDT<-uEaL#i~+$4%tafTv@fu{_cE&Tr|COO{4v-^qp6-!8t_soSV;xj&ziQ~Py zHHYYsqcj*eUWtKQBF8)L*;a{xPvp&I?vZPy#K70@{RI7xCnS#dXhUD<^V-CTWj<@KEnIe31Z%!QV_TD+gNVg%JINnn?e=~iXHcWE7Z`=B? zn}r5Tj<+!^Vu#B8DmmUir`}=hGIo|6Z^;J^JUYCAJ=l>@`&cFuVPN-r6B5?caxf7F4t^ez zkl*5LA`D#g=(as&lUz-NfqP6X8Qgfen>@aF@t+}O&8{ZGz%H$7hMw!~Y$6OCd3Rc9 z(z(2n<9)X>AvDRHQEES$Jc?qEzfG1LZ|*23zPVF*$?-m!GFO}#U7tNbyt;N#We6;t zkyl2%`uNr@_MvcA$;WQnbDYIh$Se6+_PQbasofmO$NC4>U{6cUmwfD#vzd7Fa+M?> z>$LSN>*P{h^0E8N`m_1zmq|W0{PqsEu3AtsXa!eC)i#ds)sYO(Y*XC;ca_%7OKgkL}WH4BNWC zxa4DV4Zo#*xVlmDv1NBGWxF1?l6>s*-G{YN@tY+do8wjsR^y$Q3=+Hs(vFRdaYEAcSW5mbqzU;*cG%Ll4kA=-WwW_zaOFs7KBNNM#rL*K?C+9S2 zVaIn!K6cZBN1DeOKTdq?$;Zy@uPK;^$j2rYf2B=494Yx&r(TOq$L{TveC)}-BQ%%x z{+#$&&w6`9Tjq8B7=qc8rP_}Bw>{Y*!u zMseb4i&S22o;o6m-&lNx9qE$C(mDT5)(5`@i*E6;d|d3$$Gr>Yhq~9Y#0KwRPw+U@ z-fc-}+l4!xIK!&_HQaKm@OCy9k7wMq-y(ua^WvX_d3`ONaH}54tDHT`(i41;oQMrFiK3VE$;%S&L`=O^mqTf>*nV(qB9956jN5r#GKk zI#=4jhzFiBGfZ?D?9GWQUg9)Xj9S=^6DNHB>0I&fd23Fba5K9+qG{jNj5y(i4~K|` z)jT+H!dto)5l1a68F9h|V|R)7aZNdK!rkY1i|!|vG2(=a`OX#bWn4LN!c)c`5z+pQ zIB~+e@?R2jJN(Rv6K)b%Nt~>+0N3GSc-0=8#L&8hIB~)kmV}8%d*(9Yg!^dk#iVyX zapHt)oNOxIy`IU46OM)hV#-_xPMol3S9`E)UWF4UJY!;37~MzX#0eLR{6z%poydq2 z{>$l#sF*i9Cr&uwWM6Tv@mNNj@U6N9;MvVGoH*g1`wtiGwvA-O3IEdVxwyQ`o)ag0 z{izGMmiFVs38!!C0eQ=NapHuB_)ZYVC--E;3IBb`4rUj4!-x}}abk*qzatoN!j6x# z!qr@VG2(;;uA`1YT?BE$?2Fnmr5+(A3mHo;gP*_v5H%LIdQ_Tj_uT1#+63x z5w3SsDx?ic^ykD0o7?m@*ME+A`z)BBnl;g~C8s}+_#5%I??+2U4?n&X0Zs;0||1k8hbcamc#@KM3D}pBZt;i+X2-I<+1#;*c+mt_l`=Pl>V5-p>pT!|w^g z#$)p|+!9_ZP-54-^_Q<1SMf1=s)qB#eSNk}sQO;w*x{o(Z^=@vfGl&gh8HaE*i)XX zV^qS=Ul%uldB<|d`s-T4Ayt}@CJgoT<2NCphGVg3vsz8EJMKUFFQtD?u$Zw;BA)~ zjJVtq-?~C{;4wyAuHH{-w{3{M`E=Vkp`?H4hCKGsCtDd|_^p-f%t!YxkXnd54YHZb z1V%{gebJQH9QQJ})IzlWkk1?>8tfsC`f*Js^Tb6(LMWcg9Lzg>(}j{2qTjvj=2g3! zhZ0|X+b32u_*j&Y{voz}Ls)t6EGvrm*=gl$G5bIy~+sO~&PBi%yIIpOdqYcob1a{G31;?!q9jX31e=F;%n+}9d$$lLn{ zfam$K8ga-Yv&4%!=bxIMqkf>bM;EyBYj#E)vO^!#Hb!j-3YtZ2v=E2fy2uVua@rINamb6pP!|(; z+Cm(1!pd!8WRZ0i(mXsl=?e{Rx(MQs1MDK9a&b>V9P+dyTSQ3YVGD7{-zs;8HFIhT z;*bYr=mf*7M+@SRJ$~OHqPu>!lt3*+pPW8$&Zns$4tZDcb;7q)cF7^{T;Kt9n~fI4 zArJ4>2FBfAAc#YLQE|06`KF-6&v`qxgaxBF2;z`$?r93+{DmM6Ie(sIqTT&K$szAM zP!#$fTP%n}KDua;xK)5j4tYe!g3x+woFERlN%MLzV%<$a9CA`pEtt<<3gVFK?8*Zr zdz=)+A-jkB!Gg<9tj^3J{_0Zzt>_8 zAP(8{qF|9q_q?C|h>0)ZDrph%h&rIZSG9 zSLMph3Of$r#365dKa2T|?9GWo4r+CcjaVPSi9^0|F&A%=voR+QxzP|`e(ku46Neo0 zeU>KUWOiyth|BY2{9No8Q|Px9$+$Xb@x;)K-VPE!J4Ejc zy}3S<#Lwl{Tn(KZ{W6p|WS0V8Lp{1AG z&e+0;Lq4;pHY>Wj6DJP&`meRM7Y^H{2AJ>uL#ycO$B9F(JTX?BvXeLw-1GI15-Yk`age z=&>Dt_w6+!4taE;er#{0v5Yw6lbfEi!^`bCamY;udvL9=7bgyR;DKLQ^y-O>IOM;a zit?v9{5WyQy+;<{`*)S$#38S5(2ND2oymwpt~BHdyZkB}Ck}ae`8q6M?p#J3@=sw0 z*)KgEIC01`FJa<7;(t;{;=m|i&f#oA!p5;#9r_Di4%vsv!xF^ z8M}-Thn!esGjsAN#EC;b7wp0|&RNNbLvHnIE_;;Kl@o`&G|OeS((`9d9CF~rJZxG0 z)r>ggJmZhDw{IJA;*iU1-_05fYs!g3{xave_R@6&BM!OFq+#r;s|P0zIjGust##Q= zj5y@m0d-lccHW#g9jYCiPYpA&~XZS2Z~o(^$R13abPT=S{>JEaDAZFnQ|vuRPBIOG;3t5}}?9L0%4 zu01@+^5V=6sR7RYZIGpMgg++^Iky&VssDJp)BraRyKf1&?#GEk?y~r)oS!#f9)jMQ)c3`vA0JlP&f@@?cP8{-vpqrNU zk2XpTu=l#=VqGS0sR7PVV5n&2-$81CAKd(Vb30hwD% z4e;ln{Nl}{Sg8RPUq*|03B{!bIMZ5p(XG%*sR0fyzDQ`Jib@S|r#gFuZ)_8(0gilI zS~SSEOlp8VN}U!TzBZ5=;6a!E67w?GlN#V0`D%y*e)FXUIAZq>;n<>})Byi>yPOewE16=FQEpe<+R;dBbKRhFE9{Pw8 zhde3#1FPNqGb0XpQrulOsAhy+Nb?FamX?4wpo?}esdwdJ#sULm<+z0IApPc z3(xaDoH*pky?Tn7Up=J;c$nLC(O7en8emhpwIY5}VW|NwQfseR{2-rE11xc)k!!tC zX_No$^0oX4XQCc>wXO#?mN9a_i&~BexSlDQ<3;WlbnX{6;@Vnxu?_3=ku<>m&SL~KEI-rB%kk>D49`GpGY=ytR`! z^KCsRQ_n3$LP$qZ>~%iV0@tPzmlm#=*L31RZpk5cu9VGGvTZVsb@Z?^mCv$Ja>)7| zQd_-Hue(iQV2}MV{9wmzj5Ns|atz`}(pO_M5qno#hdMw0#6+58yLvtD2)^n2JdbxoUVc;DHy6~)-o>_=Po^>LM*DJb2 zV&F?N;+a#WbD_i`=PVw`3puSb6Ng-(c|5DqZIy{I@VeZAyvMGL8tH)p)^_D~?Z50M z4!Q2hIQH~gE{*iS%|>?R??>m-NDtgDDT-%WFiRsnaQloqS=diQG{V3yF8T9nAL2C9 z15bqQZ1C-Q8tH*2Z1>|CTjXJ+2X@;N$paSVXQT%{nSUEQoiAP^J#a(62tI6ZFe5$i zrQ+dy;H9>V^uV5>o7jQzPc_m5$J8px(@&_$h(mUIyq+B%oSu;$IH_O>KK0NbMjSFc zYs*6$&SInoKK->7cQ3n&ksf&R+G2cEvELbS$WggH_?VZ!Ne;QvP+#ujQ(TZ9c$x^{ zQJd>nh(j(P637>~ITT79a-(?xyjAmo8tH`l-z&|7vOU#EC!D3YFCR6sjfyKTnpNN_S@^ejY)_2EYrB#S(=qm259Sp=F*LyWz?A!S(5Qkig z-x52=bq3;)*Zby$U0oUiamY2^mWGPWLV!5rlH+SZmOvLE4mmic9XM3`AV??t^RO7W zzkiz`oiNKi5T^S#5u_6y95M{H%@}4Oop6U^L!o)O9UAF`_2(x&AKv=9nzJa4hu2D9 za8%llk)x0AS=cgJ&rqmF^@P2}3!8~U&Xay>LjOH^&BP&>cpjfHx>iOramWp8UQd|5 z>50@!bldecVfcnaQb%#}=bYx)49WV6c~HPSaeT)F;*jBFQL`x`a{_V5<3_ogGaPZ> zLm0S0g1gz-Jwoa?()Zpe+J^PgNGF{BcqCLm?#xIhd?E0mIeW)=sp-9Jnq{eo>r!5in-3n;=bZVUMk%Y`<+5()8Zg;tLf*90h55Esw*Y zo?lf#nqJHOj<9ZexFAh$sqz~|?vwW{#33JO;{!i8s4j>@K7D(gs8;x!g*3f6-?xE3 zLS_om^tNoYMl{WrLy)GoqnjuEHn6WC4tY(MR#1503PBulqZ7@b;*9NrG`+hAE*GbT zhagSwybrE0xcN*$9CCqxB_iX^0707GvmNWhz#8WSamYhfEf7xEOoBM%zpfWTUTU2n z4!L~UIxzI+Z9yFJjm6~rOm+?fr$I$RROArEp30Q zS3Q~?veXX+;*iI`uPRzUm?wxs_VYR-(&f$z#36Uxp8?kXQVEDd9#!Jg|3%n)2Ul5j z|JyX_z4zX0LJQ=adu=*`APCZ>cStBwln&BFdQo~2483=fbFW1eq@yT;AR-8Y^p3Rm zvllzhIKMyM?=$nv+><#u2@zKIeVyy9i^tTcEtVk{y;hnlUS7tQA*XA!m4}qeE|wv` ze4U>^Pw^dFhJ0}NB|et(L$M4w;zDMA_G%?thWyXOg*eVQ#j{?8$>o~UL)I%E^sJn;+c?FyUU81ZWo72tN51unyB01bpLZ_J zmLdQCNijK;xE))Dd~R()>Ck#2TZa5siaau;@=~@8dES7m(rofhwhVdXA892+ofB*s z^7D2{Wop)|Y#H)_VgGXah-YjW@}N97_`@?v#4_Z>yMN@B<dGfL8T)SBTu?+cc&AyzZOHr{5`AII1%g!w+mLcaTmV)K4GGZArc(1We zf<51Y1DkjbJm~!~VY#NoDl1;rVQKNoUrbO>qs`c^VfSmkWxJ zMzzlgZfxSYF?h0x=gHv4CY~FEC!2Vl9PfVE-zo9e)l?uempK9Ws>T9 z+7eJhg`q$Uhi7s zFtH3ddc((Fr+hp0{Cwo(NbjGB9qJ)pJeZtTMV1xIkb5+_<8>|GQ$6H_+cQx2Vm;JD zE}3GdH@)yyJwN|a(WABRl@iO4|Lnr@dZ*&FUeaz21|O4e6{N@|Mwe zyoJ{`==qsHpGa-abx;pE(f0II{WM%(oS!*rAgv!>R6XQIX=l^cMg`PEZrC*sO}`nV z4#uN>>nO#L*6JZ2|Dz;L|6;j17%#&@v@=-?^^k|IIYCpNHc=0Gc)6O?XUIZzFwQ00 zK*KiVR1bM$#eb|&?ZH@x|frs4ev_WXQp{XME6_0&TyxvUMn&IU&sA7AtQ4b^^A zOFiTbbCa3Wqm4QkYtHqj*Tuh55BWj6i}c~~lQ%DAXi6a$VnHaGN0YQpbR-lpu9P9BD;FXcYpbs78h%#4EgtK5$5)r4C*28 z-{qMPdZknk`STfz>CYsj40%f7%x22`1Imz}=lzx*JPKEad@M4T8MS`BGUN>d-#4W* zJW+<+C2>PDf9qe$kTdNqU+5u8?0{3skgp%fW=b^Jtql1E&Z21# z<<-3n@OVSJ_jiqT9&f1LdqpCh#~Ug?B)RU9fX5q}@K0ymBLR;$)O*8XeLosJ-nhA$ z4(t2Wy80L6&PU$XkGE{GD-Is7GT3`xO^buas|%^c-3K8)b3a;JYIDe2Fx0? zol_Ooy%z4wtPU6)X@Min);ES1E%2g!=S2&=XwP}k0xz1J7cKCj$$8NNFPfYeE%2h1 zX~T;ac+twV;YAC)Xl2^)q8VPaGHrO#3@=)lHoRzt7p+WNZeA*m*{JNj=Ev*peTT94 z9e*_aJG7zmE@jB@ko_aIdKtS%0v<9~oPe-`|RK$ z3p`|H$ncOE9>i2ZmoED7kd0-? zB@T7*;UOzSu5e+h4-Z)xa=x+|86L7ShA>z(ZDse7spIiCY~|hU^XN!|;%mAy4RZk>MdLL+-fxbKaO1-XqTBuRgxd@Q{@u z!$TH$$jXr6AqzZYWytW51s<~Qk${IR@Q`(n1UzJchpc-f;34zmCE?1D;UP0TWM#x=ja{@c*qP7Ss5}sWO*YGGF^{zSjrmVR*;_51E{Y zEbx%YdC0tY&`8gD$g=cMEpi^Rz(XeIA@h}5nLOtq%h2F{&w0rF%lSP)=ON4F-W5FO zAPf2)SR&h71px;UOzSF1S6!@Q{@u!$W3x$jXrK4ZY4+bG@ew86L90L)JYK@Q?)_ zvhI<9hb-`r$$7}qa7!88BLNRt>K=aLIS*NWt~AYa9=Jn-`Vb1v7W0PL)L4@mi6(DMeFl40HdCgbi6X{SzyIytCrBObvbpPut2{Q zdfg9fx$)x@`WVNG^>ZCV)@#R>^?KKfpEucgZudyQ`z3h4#xh%YzXb2sSY`|Fm*D*x z%WUEO8hF3PGFy1R2Hvl+%og6Sf%j`HvxWC-;Qf;Ie%<+2Ujv2n9E9_%z66|S1Ls+N ziJ?cXRQSGK)}Zw$;5kRaa}HWY4bM3M&pBva2zbr`c+Nq~sNp#W;5i4ZF9FXv0MA*k z;W-E3IV;nK=NyFRtnS3{X_>a;Y;Ww@9v(8mLspLh9x_|#S&sr9vVn(eEJKEe zOz@C#tJTNALpJb`$$7{G51E{YOz@D&GGutjaP)H;%aGwA6Fg+H3>hA>fro4?LxzWJ z;2|5!kl`T{JY=#A86GmhLpGKn!$T%`$i{id1P__)85kb2fro4?LxzV;@Q}%#f#D$= zc*w?i$Oay=u^t6HWP*oG&O;`6$i{id1P_@kLxzV;@Q{sV$ncN}9m3=f&$Asfq(;UN<|WMdgJ zJY)|ZGFgTU51HU08_SU4Arm}gV;M3$WDg!PS%wS`ncyKC=OKIWkd-0BL-yby8|NVt zJY-`TGCX90hioiEe)Ms7uS2PDV|PlxLpJb`$$7{G57}6T3=f&$Asgo*6Fg+&JY<50 zY%D{DhfMI0jb+I2kO>~LaUL?kLpIJsHu1YA;2|4$$a>C%ha7~5tY>3*$Oay=GGutj z1|G69WO&F19h9W!9!Mt3=cU34_PcjhKJ1Xki{}&c*qP7 zSu8__hs^Mh#WG}g$N~>pEJKc;pY|RZ9&#K!Wc}XYAu~K={hr|=2jC&=PBwVR0eHx| zYXTl}03Nb3WO&E{c*x3-;UNd$A%~oY90?COh9W!$W4vkl`USJY=>E86GmYdNr{O86GmjLl(=B;UP0TWVQ?$9x|_Ol3grA zhKJ1Xkl8Y1c*qP7Su8__hs^Mh*)n8!$P5ozEJKEe%LxzX!!$W4v zkl`USJY=y986L6^51B1PhKJ1Xki{}&c*s6HWVQ?$9x}s27R!*~A#=W%c48TF@!v)< zJY=y986L6^51E~Z%hA>4-Z+Kha7;1tPB|*atI!>I1f1l4_Tat z9E67~&O`R#AuB_MhwQ;a7Uv;*@Q{@u!$bDqAuB_MhwQ;aR)!1@*@K5H&O;`6$jXr6 zArm}gWytW5J$T5kl!)nzef-}WM#~LGGutj1P@smGCX90hpY@49x}m0R)!1@ zncyKSLxzV;@Q{@u!$T%`$jXr6Arm}gWytW52_CXCWO&E~4_O&9JY<50tPB|*GQmSu zh71qcz(ZDs3=i4BLso_i51HU0D?^5dOz@DEA;Uu^c*x3-;UOD%$jXr6Arm}gWytW5 z2_CXCWO&F19hA>frre_LuPo$Vi__#WQK<LY{%mQV({W>c ze#eu^e%x_meZ1qzdOfJnim-Yef}8Dm-Z>#`zaQr_#GlFk_xtg`k4eyJMcA0t?>;yF z&t-o%!9zCiko8Op581jIde()9Y~Udq%W~l%8+gd%JY)k8nVg4g;30d?LpJb`*?GtY z9x^)**}y|)=OO>^dxM8;9gjHYAscwe>O#Xq4#GoL-vb_U5FWCgjo~2&;UNd?SsEU4 z5FWC+$MBGY@Q~I0fQKA}hpc=X9&!*KvictIkO>~LIvDVf4LoFa9x}m0RtEzfvVn(e zEJKEeY~UfY^N=OG(-$hyk{9*r=OG(- z$iDNC2_ACDdB_GHGCL2M;30>chiu>>`_4l)@Q{7yArn00p!1LoJmiq`kPSR!&w0oM z4>{;OWCIU5=saYChwM2I*}y~goQG`SA$!h4CV0r6^N=Vy4x1|Bjw z581#&Cg&j&JY>&#$OaxVIS<*uLnh}T6Fg*fFyJ8@c*x{DWP*oGc9#V_WCIVGoQG`S zA(Qiv2_CYZpWz`Jc*x{DWCIVGoQF*Ckjd_{fQM}0A(Qiv2_7=pT^8_=4LoFW9>lk<@6`-|1Hf`?4-ko7DI4>@JYT^8_=eR#;?JY

?V2UweI}Ups!~zxEw|?LPea!|>}T!>|7gzkW6R`rGj9hr_Rb4!?do{QC3o>*vF- z{|~=$G5p5Mu=a|-c%yf+%xk@$WxnfOE%RXSZJ8f?hs(U#`&{PJ-t98a_MVsdw|BnG z%e_Z$zAoK7UVig?cFg)iftM|Xuw{$v`pFY{4TlVQ$xpa;X{o|=!;%|KYl|S`sD_1-I zvw!fx+V@94{b23>kN@i5S|0u3U;Xw6>nDHyPyFqr>p#Ex%O9*?{pi;}SbzKJKl)(( z@ZbEC57s|R*Kf5V|KItCAFN(K`Hc@&-_q$&e)?pGZrP`2 z<nt$ zy6f;;j~#yNw8L-xcKEI94r{O5xBPAGb^CsY<-h&F!|dEX;bHb~|M0MKZ(s2+KDXa^ z7|+{>JiPXL@6M~&?OR^@+Uup$q5Sm84&Ab^y(*W^@zGxKw5}U}?Nz;`-#+b?EC21^ z9%kqEbq}+D`@M&id;7qL@wxrs!+74l@nQULKl!kF^&Y+YmQIKA(}BU{Q1Lv*E8;lhmFVLWaG5>+4wE4Hm-}ejrZbkexUfAe<*I}H;U)^lhXN_^7B90 z;g_<{UsWzY79ajCp8Q_?`NQfZy?9vu;$(J;pV=?2R&Mb&KE>g97N6r^+^$~5^XgkV z9m-Fi?9eUy^sHPu$A|v$)GqPYUhPYf-hLJN+sDFA`&-y=--~kF4}(wpWbkbN4F2t_ zQLpyfsBh_XC_jC&L$~bHvvTPiANt2ryTo66RWIr7SCPMcEbO$uh5h!uD7XDE__R+3 z&-TyY-@Y34YQK&8mQIKA(}BI{NMbwIN!KyzoqfmK1}1Z{h7vZ z`!8;Pp-#$!s+MmgO`!WA$Y)jvzuZ_BSg zXGcHJzW!gi#zlOLmv|aS@qgc6tC#flTgu-)Om^Cz$$tAbmD_$!eA?%UXZt_#Z(pc- zwO>?yOQ%Em>60D0WuKmvOXv8|Kc3np{%?HUx8)~3?DxLczDs}YKK%N_@areTum23c zel`61+wkj$!>@l1zkWOX`t$JX=fki655I9S{Km^C&u1JBzwz~z-tT>HJTCo>(@&ny z_#J-Zdiag^;pYd2pMMyBeq;Fgli}xQhM)f#etv2A`K#gQ$A+JO8-9LoSbMcEMSA;H z7=k8T{KQ-1y@JN#1i`K!w1$Ku1k#gpHQ|BDY-uJqR5KYg-8x9roia_Jl&`o~kd#Q%MNeV;$~}6zxt&+Vr*o`$cD@z=&b_Kv=V8^ibUKuuKG~sL z_UT!dX%HO$Qb~-Q2 ze&>jl+xcRAI(Lj`=aKR6oU(d#ep!7>r$hPalO4KcpPrRV=lIY+p4uh;pWjnH^^)HC zU->&1%ueTp+3y^&ayws)Pv?&D>^w65ol{n?&M&KP>2xSReX>Kh?9;Py=^P*W$5Xq+ z|IJ^Ed-=)stMH%gW8qiZ-@@Ov?}Z<3KMeoeJ{f+y{WJV|`)c_4_S^9PrJEPZZ@$Qm zc_jPhm&!Ho#K(LTPxDm#-~6?DNpHW3{Ox05r~NJLx9>%{?T5jqeKL5qe+K{d)u>nd zZPd4PI+UM2*`ZtZ=~=mSjt~9gsa@j##@FV}*N(%leTQGW55N8}{QAl8>p#Peqi|dhvDZphMzwfetu^7`JdtEmxiCe8h(Ck`1!Zt=l6!i8@(%SUhBOx^Ih+t znFo6x&HUKAY39w|Q!}6T&YF3)_t(t7Kl9$pHZS*HoB6tQ^LY8q@7Xc$XJ0%}x#EQQ zh#%r9u86;Qqk2j2y)*fH2aTQHM`OQt)0EqLYWVcd8lJtshJWv}saNl{sc-3YC_jC& zL$~bHvvTPiANt2ryTqSAymL2eJL9hVIgQ8e?KDoi&(rwro=@Yt`#+8M?gixsx-XP} z=pIpiqx(hqlhXN_^7B90;g_<{UsWzY79ajCp8Q_?`NQfZ{fF;KYg-8x9roia_Jl&`o~kd#9w>ey$6eXrQf{) z!}8yK0>kXwJp;q+-~9u_%DsCDhVi-k3Wo8#dklv0zxxe_)$8s(7*^lX=}><9WQT6q zr)TBTIX?7{r*?_I_Nrde@1BR1EC1d9FwD-~3o*?8-4`*e+`C6&7@xaeVi?c6cVZa- zyN_a6z3!fhVf8JY4&|p$cIcLUdR8u-<3s;=YM1z%zpfwt()r-+kLtZn{@*{j(H^e=9kJf@5IOa6;Jb5 z{LNq0OM35h%HKPl?DW3p?7w$EmD_uu`1DRFp1m)RfA5N_SMQCgZ|QU>KYg-8x9m^P zS1z67L;rZ1zv6FvwNFnwwtr9iwy#gSx8F~HXdj?{(*8jGr+tI^Rr?9`xAqz8hwVSq zKTFqd%dbCYM?cTL{$IJqMSP5xcp69XH@>Qu^!D$`-@ZO}+V97H`v8^O{y==%H;8BZ z3Gr{Ap?bCdP<>0ML;2~G9lB+oo|Q}I_|QL|+9m#<_WHalD*fJ7*|?Vf-dh=F=iXr% zX1{mtlzZ>CEFGVF&t(|TUw-e6;(zbIEM2{NZ&ZCtr$hPalO4KcpPrRV=lIY+p4uh; zpZ5Cjm)`qy^7n2XJH2Pe{%^haMwQ$9clh)!9-h6Ihkx(rsaNmosc-3YC_jC&L$~bH zvvTPiANt2ryTqSA%+DKl`G4cFdBHeszA%29M~v&{7vsHohaYG@;vbr)_>JZ-{-kt% zru_U*cKD_2^H-J2kHv?7izmMqfBvv~Nzebw-@L$1^9B3OBg$=l!KZl#&*mfio2S&P z`AdCEr$hPalO4KcpPrRV=lIY+p4uh;+Uxqq`oHwM*LPU{yYF|Hox2BknEksScv!i2 zZ}2cacc1Vuo_EjiF#dP{@UVLIK9TyCPKWZ-Cp&b@K0Pa!&heptJhe;wwO93$-upiC z-~G(v!_M8?Jk0*x=RB<3yXScrpS%Bg@iU%xFZ3|}y+fp4y-%dRrPHDO^vMq0vQN*- zrE`4fA5ZNPf8Ss2(-Y^ne^31XqqqOicR~C8d@r;Q(04@p1ASk#Z_sx~`w4xIw9n9Y zO8XCezm)E~ru@Elvg11_`@WAV*LPEVd{4#GcUJs;e^oE(?cbBXeSPe--;e$F0V=os zf%vp<5YP4#;@>_)^=kj2`j$?I^3x|fbjvn_nu|yb~YuQ9R94@i%`}FX`1+ z{&Zj`eb`So<)$Y->5OOk<6pa|SM8;~rPHDO^vMq0vQN*-rE`4fA5ZNPf8(q7iL_(y z`)J?Z{n75d2ej|;_dcwC()&UBPwxupSG_l+zx580e%Sj&`e*6-ZTa=*?C9s&-}=KV z*SLs}@e)ttDE`J*?-RZBz3=n#@7a>uLvZg-8jg9 z<8hds8>hqU-}oI??v3kVd~UoC<9U8y82|GR!|HW@V_1Dlr$hPalO4KcpPrRV=lIY+ zp60LkzxiurJwG}8{O9oVtHaOV4nIFU{QUFq^V`GEpASDjKm7dv@S7Kg-+VFr=8@qy zzYM>5XZX!WpFE#=YWU4xU+L9X{&Zj`eb`So<)$Y->5OOk<6pa|SM8;~rPHDO^vMq0 zvQN*-rE`4fA5ZNP|2KcFUe8YsKmR%W{Oa)Yx5Lj54?q7r{QUOt^XJ3Q&ksNUKm6u} z;Wu9lzj)|(#55M_+_|5ynFCG|val-J6ABJCC@$H=l`2K(SFaGaue)_-v-S7Vsy!5-P z_?IsIKgG-QiIe~Sck=Ty-lc;18ShoW{ET<3V1CB?Rxm&Fr~mt3ALeJghb5h#@lF=Z z&v-uz=4ZUC1@kkd^E2h=XR^c3WS^g@Tz)1#{7gLgnfQOcYd-ao?j14Z%I|$Km>utq z!R+6=Lc_}SPMLIkyk7?6>0L7zfA5{a>g63YSba;UL;2~G9lB+oo|Q}I_|QL|+9m$_ z?cGE2yUNm^og;wtTjvO1{r1im59_yg?s!`pKOS8rFaA+|aOob?1qO^|w1`G^`)Ghu{CzKTFqd z%dbCYM?cTL{$IJqMSP5xcp69XH@>Qu^gF+^a^=5sJ;UtWd7okS?;Oyua_@Z5Fg|x~ zXc*5sPc)4GoiiF%FYhL(m-?1Yhw{@WJ9NuFJu8>a@u7b_jj#A?ulk|%`ltN$TXyQt z?AOngTmQ$Wae-&!1^>p8dNsb(w{$v`pFY{4TlVQ$xpa;X{o|=!;;+4`m-PCl{PkOQ z>d&+P`nhuJ|M)a6@NB%`-#AjQ#+Uk*PKWZ-Cp&b@{`7q1(m6i#kEeEtzqsqpeQYlC zU32>-hQ(dCk78Kdb^9wmc`oj{eHX*xuG^0>Ebh8}8pGnQ+rKd^?z(*)!{RRYKZQJ=)1mzI$qwDJFOIETI>(3p@zgHy*IwQkRF-t_ z^uh9bzYk`|yMD`a_HTY1R<3sdrQ_p$Kp0Q&2EzDzPY_lw?+n7~TRI)ePoM12E&KGW zTsp^x{_)f<@z-9}OS*Rzl`FsZ7GZY0!w9qQeMVTh7v~J)<2^^|czWj%#^3vouzGnH z5?0^R=}><9WQT6q*It!N=lIY+p4uh;pLpYc{8m}!HTPb^<~#Rc!sbEuWWwf0_h-W9 zP4{ZT=2Q1=!sc1`aKh$a_jAJLW%qW%=IheUd)-g&y`#M$ER_DXX6F`#*un8zSOsLI+UM2 z*`ZtZ=~=mSjt~9gsa@i)y{eb=`ltN$TXyQt?AOngTmQ$Wae-&!1^>p8dNsb(w{$v` zpFY{4TlVQ$xpa;X{o|=!;{WEa^^NBzhoAo(etz|n=i_gOpC2B6{(1QM?cwLoho7Gx ze*S;>%?rbCz8HS<$ncwAhTpt1{N|(KH%|?}`Rgm)K1Tgte)}6?cI_cURd|-_q$&e)?pGZrP`2 z<^sFfxv=k-(tX#I-}g>-d&Le#M1HfPBDzX_lsfm@~$zgzNOQl{Pf8V z-Lg;5%B6FB=pRq*5`XcAdlHmoUUSa?Y`$~<0Bjy~F9B?R{LQ;30XA>C#{f2;y59gc z&${;jHvhU00X8qYCjmBJmu?;}zxh2o=Kbu82P#*b5FhbFJjE697jINA>F$M4uKezc zfZ1`61kAqsC1B;ccLK)8eH1XB?x}$BzjH>z>g8Sw>FQfL9m-Fi?9eUy^sHPu$A|v$ z)GqP=tVey?MLSks?VAqTJ$>|tbkk4LQ~yb4{VM(Sx7tNNtiANl()HW&>(ANI&$F-p zSFUjpALAvS#!>t~>rtP2Nw2>0rvp3b!+yFcH$Cx5XFSt?>l?4V)T{Q|`o>GAL;2~G z9lB+oo|Q}I_|QL|+9m$lt91bBtq;iGx&b?_C$Qf-gK}Gcz^8QyJX^28zjX}tYJEd} zOQ%Em>60D0WuKmvOXv8|Kc3np{@Sa0NpF2X{?-lHX+44c))|!B`U5_#OW@gh1^%sL zs8{P7>RUP;%1@u{&@KD)tXw+BhyL-@F7X#{xYxp1Hm|uC0yf{dF9J3Xx<_JpZhriu zdq)N~Z@PB^HlMnW0yfXOrveslxW586FT2+QHeZ)+9xuQ7Jv-+8?288~SDX+Z@k2bt z74a8uR4?i7@ldY(?)QM%aqkDrzWYF6<+>*X#>f33FrMxef$?|W2&`W2A%WGmbUKuu zKG~sL_Qe~OOXv8|Kc3np{%?I_W$}}DzF?UDymJS`{OX-Y80K&9oWd|aeCHR2`R6;= zFwAe?d52;C{LVoP^YeE;VwnFg-MmnK^F?;dBiT2<9WQT6q zr)TBTIX?7{r*?_I@pb#szt=akQu^joJ|x$@uo z)i67^t~Jd5t#=J8_twFN@wxS}VLWf$Y#9GrPa9URTW1?q-_q$&e)?pGZrL}!Dwodj zp?^HJOZ;DZeOG&3I}Xe5{EKvUoQqkWv+ukNtX$`4V0@gff$?|W%Vtc4&|p$cIcLUdR8u- z<3s;=YM1!G@%4?q@!E0tweRq2_fMW1U(F-0pDg|LpW)Z9hF^ahe*JLx_0QqgZ--xh z9)A6N`1SwcH!gH-?`- z8Ge3d`1zmV=a+_!uja4k$Cm#5+b7SBulO5Z-u=;D+R;7yu=e$y4y@h1vjgi7-rs@s z6YuiC`p?~CGpt{E$49#U=6xSnKlJVotbdlS-v;%|Ia zFX`SnQm*{oKZ4ouE)vYX_mW`cdPfPy$NNe!p59%8@%J7RtX|$}g4MTlI+UM2*`ZtZ z=~=mSjt~9gsa@i4d|f$T?b!YY?c2Tx?cRO~{h@sn`bqmM^q=-!=vVE>(BImpp&zz? zL;oyYzb(K1oE`l<`}%+78W-^~UgBwd#ozdSJV z@|=D5?ZC?Y%XiNYjF04I>2xSReX>Kh?9;Py=^P*W$5Xq+ zUwc(A>FzaBuKeyhg4uBo63o8)kznPzHwnhaeM&H%?pcEIcmEQsUhZXr)wgsyl%GD? zp)S1Y%8 z8=vBEJd4lqFK$<_;(7Hgoet%vPj={*eR@_do#R9QcxspUo4?$Xpl|S#?iqmjPxlYN z{Hl8iVE)#91u#GC9s`(vcE174Z@c#Z=Fi=S0Q2+iNr3tP(#;FyH(zAOJd%C$OXZq( z;$uFFr+F&==CA4{-MtXXmEV04Fgxy%fZ2Dy1gu>5PQduMj{?TiJrywiKXdn5!0P2* z3s`+ir$hPalO4KcpPrRV=lIY+p4uh;+Uve6zfqR-)(7No-GH6e6WA|4RBr1J__Qv8 zXX_RCw~nD+t#7Dr>2xSReX>Kh?9;Py=^P*W$5Xq+Uwc(A>BU#_w{E~r>j~@^rzyAf z2YgzWz_axV{9DIRuhuuzw{$v`pFY{4TlVQ$xpa;X{o|=!;{Tbye!TYLC*5nL?f6gk z9l`vndyruM*8NB@KkVKln16Pk63lPAX9?!d-M<9$^X_GW`Tx?*3*|RoWXC*`ee+A@ zns?%3K8mM#D*m7O>r)r$?x9ky{O+fM*>P_b%)a}qVCA~!3dYC%S1_LL#e(s7Uly!h z?$LtPw{$v`pFY{4TlVQ$xpa;X{o|=!;&1-C^1f9TKY8c7hxyMt_dU$7-g)q0{`Ss^ z5A(x!etejJzH{Zn{PvwUALh^R9QrUnf9KPO`Tx?*3*|RoWXC*`ee+A@ns?%3K8mM# zD*ooL>LvZocduOe@7(t=J9i#@nEl`SUq4v6cYb{7_}sbjVLb1=`7r)>4t-d??tJ>N z`j$?I^3x|fbjvQ-1y@JN#1i`K!w1$Ku1k#gpHQ|NH)0S<>B8 zs$BWqUkbD1UQ?KT_npGZbq^|x&wURLG-=(6;?0ztitMBIvvVSpX|^r`}C|_ zI>(3p@zgHy=MS%ce6K9y&N*nTPtX5aaD zSh>!{!}vHa598?^J&eEe^{{$5cMq#?>2xSReX>Kh?DL0}OXv8|Kc3np{`_HalyO&l zWjq#l8K=c##&2<&ab5goycgH;1I2s%LvbL#QGCdsl+MqTpa01Yzm$Fcs&e_U`0#J> z>@fcBhmo#c?u~)fw{$v`pFY{4TlVQ$xpa;X{o|=!;%|K2KG^vv z?Rfi0hqdqRFCEtIx9@aVf4Kdq!}`hXQytcSZvX1Aes%j=hxNDH?>ej>c3w~aEM31X zzy6#Z{XF~nf8`n%@iAWFX&lAh_^MvgZ{P1Y$bb8RhuOJ(!o%$UnRi}Kxwo%)>G<4! z<6%5+AM!B%w?BDUy*jU_zNOQl{Pf8V-Lg;5%B6FB=pRq*693Qm`VT8tJG$3MKheJK zJA$>ldyruL!Tm_Ee&XIFSpRXK60BdjX9?Ed+`k0thwf#9_0Q7v+w$wr+0oClum4xB zaSpO{vZ9ye;ih>d#aG=5%0xQ92kG`VfB)pKaoE_!%qH( z{rr-0^H=!f$MDR*;h*1Aul%9}BI{I!?+I`j?cci+Wd zgyp|`F#ZzE&fSkO%>MuPfBs}xxp$w&Fg|zB#xKf0p8vytHH`n=%Q388cVEY_`j$Q& zUVi#yhi=)YXXVm4KJ<^Lc8S0Cs$MVs|HAF%|84l$8GiPMU%A7N&+o|pcn&}Q!>?Y$ zufD@ihvBEs@Y8MfpPs`{=i#US@N1Xx*Iw;&kluQ!{H>$1)A}m=t-C6>^;mpbr^U1N zTl`zsRj<~2)wgsyl%GD?pNUJ#V7Z!)3CVZ-g_Dr&)hpu!{VHKA8J_qbMHnC zi;M0(sbTTby)!i|j=J}!hQ(KLvfZ>om;Hz4tWC{=EY=tlWDaY8an;H)I-aI&L{NDUHY+T>GIc&V&d^$Y8{niip zhns(w&Tlln_>jF?DJQZ%a6r}e~Tx-7ylP;tX%2!Px2xSReX>Kh?9;Py=^P*W$5Xq+|MUIzS)b94t>p%KK>q7cT>qYuc>qz=l>r47u>rVP%>rwh=>H2N?_2=y9=h@f)E7!P)kMR;u<0$^0 z@2^k2q_>_Uf9pK#wEn|>>q5$Hy$GMyk??GN3IEoe)T{L<^(~za<)=?}=$3tYRxX|6 zL;rYcm-riB=O@17E41V76ByRMw|`(*yWhToVg2Fu8w~3ww+~@h|GE7M!}`_jTNu{g zZa>4Ye(0TCW$B-#>$m0CpR=Q%XJ7xXT;n1>#!Ebnqxc(N)l2&A>sYz+-+qr_c5WZY zF#ESZWLUYkZ)6ys+fOo#=j}5Y#{c%846B!SjnzwiOQ%Em>60D0WuKmvOXv8|Kc3np z{@Ux-+2%K--#XQ>{I`BJ%+9TA4YPmiUBk+~b+BQ4ZhdSR&s#Se#{bsShSlrV*@o4( zbUKuuKG~sL_UT!_lxn^ca3q{ z_m1(~caU-2_mT15cN0Hw_aFYE{>DG_oyBkT{l%Y@&d-#e|H%%&lzslHa{00N@Ne9D9CySbTf_ zd|2Gu`AYF{>Eh(_i=VS2uFk%AyK=?h@e$9*Q#>F4_j}69m45Tuu>3dQ4YPCe;4u3) zKMpJR=FMSzZa)1+-^26f*2xSReX>Kh?2G3sm(KB_e>}BI{6FpW zSqqikda3-aqq5WbD*LUwD!27md|Ic)v-Mm2Th~>u)_c{rbUKuuKG~sL_UT!Z>ok!rGJEy>JcYc9C?_2{v z-+2fAzjX6L`OO#EF^^>5{8G8*o%ooK;%T0W|6AW!y`*p4Vu+#Yh_B-#O+|DE5 z(>Vn^JHLQ`=Ni(3p@zgHy*IwN#BK_KNV_g1g-(hyH z-G|w~{xGcE>nFqbT>lxy^ZL~={@34z)vNnb)VFjxl%GD?pKBXS+|s z{M$Vn=H>3+FkhE$9xuQ7Jv-+8?288~SDX+Z@k2bt74a8uR4?h>Um<_@TCmf77wmTr zhH|?f1E22Az_a@_@b8`t_3Hi&^(~za<)=?}=$3tYRxX|6L;rYcm-xT$<;|_qo3G_> z9%rZdo&Dy0a@u7b_wM+cP z8~4t|>SbQL_b-OcclR#FuzB#_%lPEE`SIS-7&dR-`x?XM(|dPg*gSjhaSWS(@12fe z^YXplF>Jmr-8^1?^Luv8``H%{RIWH7KH`UXiYwwT-l$&E@BNFFEC0QVG0e`rmod!# zy`wR#+`=o$7lHQ9De+VU%iH3eTSb8!%v^#r`zz;bNJ~z{PZ7w z?K1q@>nr`*@hiXgS=9Hn`|#@z!>^wVzy34)`ql93Z^N%24!{06{QB+i>(9flpATy< z@5tcu#>Ma(FP}W0aWu>y)(?%l`ls<&zco(l&&F^4+_}q~E<9!}8yK9mDM0Js!jC-~ArL z%Ke}I^atZ}_kk=O&$}mN7=Q0g>p$w{9coy8OQ%Em>60D0WuKmvOXv8|Kc3np{@Sa0 zNxyqkR<8VazsfK>ckjwD`*$D9uyXI7mSKGE{+3}p?_QT-{O`V(VfFHExO%B?>2xSR zeX>Kh?9;Py=^P*W$5Xq+|I=RoVsWYT&b!IqIXHGYAIE;@=9JrcI(%+Db9V5&b#1+)bSOW4vO~A*)3b8v93T3}Q@h09_gDQ;oL~PG|JQGQ z7u279FVxR{N7Vm)Uoar!>BNzm)E~ru@Elvg11_`@WAV*LPEVd{4#G zcUJsA>+_#+B)$GAfBlx7`ZN3WbLH0m@o8M(*?7Ufaim_2FZC^*4&|p$cIcLUdR8u- z<3s;=YM1yMU-zA|KBFBw-=Tdw_o3Z8528PGPDDTH{D}V3xf1=V^CtRR=TP*+&Zp>~ zrR%rl*PpYapJ!kHuUz9IKE_KtjidM*U)4)`=R4%@+y^_I2VuW+BFgRj2tJ)F!L#!w z_;(IPy*i(wzNOQl{Pf8V-Lg;5%B6FB=pRq*5`XdG?YH@s?-d{3zK&t>$?f+T7Ps6! zkWZeAXKsJUusG-TjSP!_Za>Mexajto42zd;|H-g8s{4DzSEY-)$}b+vjyNs*;m{ARot z*YN|zd;CLjAiq(3$e)zX&y=74$qv7ieg3L)`LX!$Z}H^!;?EyeFX_cs@)vipQ#{6g zahh_A-|#7}!?Sn~|KdRPDn3--(&R&ANS&zDV z>4%NSyRUxOIK6x9hmGH#|AjvoHm>j9`(fk#?!zDE2kxHyVgBLn&mZPD?q2<2{-kt% zru_U*cKD_2^H-J2kHv?7izmMqfBvv~NxydlR<8W_zQ8a$_wK;(?Em5K4J-HFDHz7* z-Y*!&^WHTW#{b?s7*?-)2Vq!!OQ%Em>60D0Wq*3Ua_Jl&`p1($jQ?w|?`p5xhchhy z?avuz=l1Okvw!<}hLwB!e1`G4{XfHa-oBt={BOU|uzKA-qG9zdoet%vPj={*eR@_d zo#R9QcxspUzxG;L(r@3?u>7~5YM7ndXEn_J?Y|mU?(NGO#^?5H4dZ$HxQ6k+{awTA zb^E@C)wgsyl%GD?p}dbI8wk{~`Zh zx_P1e=8No@N3w5zsa*3;e9TAjG*89f{8hcAcYmP#-7CmW_YJb&J%q~benNb@w-C?n zGsM4p4%Mss57oDHI+UM2*)e}*pPrRV=lIY+p4uh;pLqVi{yu-${hY>Q_jVem-REii zcF(7A{cqpHJLj`Je3YOWEhIDwiLN5C0ZVelPx? zc>Yr_>D|vMfA@B>(|w-och9GCyZ;lP?ghoO`$F;W9#Qq`eo^%;oet%vPj={*eR@_d zo#R9Qc=CtwH@=E{wPW$H_AO40q#pn84al3w4Jgl?(La><0tRln_>R*?!y`8SMQ#jPoDF)cYn?> zKYaJ<4D-)--_9_gMeH-0;(Z(MhN-+1p_ zKR?iUfBvC+0QimW2jEXi=V!{#|73?>%07Qpx%^ms__uiSd-3NFtC#f7*UR6zdv-dH z&wl6hmD~A!eE!TKgVZSzdD}7`rGjz)(^W+PyZ}kzb(K1oE`l< z`-|URxyD6&jF)&CNAWkls+aU@$8nJV+IN_pYxiOHuRjbc_xi~&KG%PS@w|RDjQ{nw zVfE@hJ@qY}4&|p$cIcLUdR8u-<3s;=YM1zb)}ub(%hLPal)vv#cKSYL|L5QLvU2;L z#i#FFJp2B|zwcu8>U&vzOQ%Em>60D0WuKmvOXv8|Kc3np{-5=zPran~y(xd+q3ra1 zI{WXtRk?l7;?s97o_+t~-*>Tk^}VdVrPHDO^vMq0vOhgvxpa;X{o|=!;{S;^KId-C zYn{h2-*ryMJlOdi^JC|F%$uF}F`sr0$UNKmAoFkMhRn;ICo*4`ZXPec`8_-4{p^be zDp#BkAMryx#TD`Y#2cS_N$)(4{GHQbr}I1Pcdkddo%g|~b3k}@J_!HL4XIb>iPX1r zI+UM2*`ZtZ=~=mSjt~9gsa@j#+Uq;<{7WBx`G=pK;b(vNl{@_S3_qU3kN@zi*YKQP{|~cs-vz_$-}l0> za_>807@zyT7{>FyJBIPU?~!5ky6==>^(~za<)=?}=$3tYRxX|6L;rYculQ@P>LvZY z%T})Z_q{gE&V9!Xvwz=r!^*wyzF~asdvF-f`%WCj|GpoG)vNcv)VFjxl%GD?p-8-8)%@QV+>(wnbeJh}82XAZykbNI!j!!KSPesS#Zi*JWt z+&lc@;o%o255M?%_{G)3FWw%0arp3y&xc>!KK%UQ)|Rzn^R@PE9@p;8@A|{fzj#AG zDIU;&iWBs!;s^b$xI#ZH-q1fw*Kf6ZD z%TIRSi2U6{!cO;-u;0BU%I!WAe7ffZ&+b3Lzk5;CtNT*aw{$v`pFY{4TlVQ$xpa;X z{o|=!;;+4`m-Ox%k-vLL*y(-}_Pe)4x!q@iPxqYQ+5IQ@cQ1;1bzh45mQIKA(}BU{NMcbP4idl1M;_Sz)tH4?6=OK+}0oPX<9WQT6qr)TBTIX?7{r*?_|o4-~s>8%gQ-?{-ittYVGI)idsf54}82|Qb`z`u12 z^=f@XeM_f9`RS7#x@Di9l}qRN&_ABqEB>#&zQ)(355N4w&(83(Km5uaetd=>&*8^^ z_|ghH`r^1E1c}z_a%?@bBFX_3Awi^(~za<)=?}=$3tY zRxX|6L;rYcm-riBf8|g8+F}pw_{ab0-yGJyfA%kYuy+5GKlvL=*B}1;IK&T*Sxtil^}v zf8(oqN&jd6;8REWfArH2X6GOO)xR~)?EkCZ{$S<)`9JZumyXY`{_+Ro`J-R|VEljj zk3Lwv{>?x6VD&AX4&|p$cIcLUdR8u-<3s;=YM1yMUpIGc+-b*tpVhwoZmZq!6SPva>5##i-{ z-tV*W_q#1S{hrHyzw;`$-+%GxcVRsHy%_&~M^>+XUsm7J=}><9WQT6qr)TBTIX?7{ zr*?_|TR;3=@y1)H8h-0n!*5;dlgIkuAO7C(TL&9{>tn-j-E8=+rwzY#w&Az_HvHD* zhTnSK@LR_le(QU~Z{2VBtp^Ujb;9Ade)yGsasF5Si~on;I^^(MpB#Scmcws7bNH=u z4!`x!;kPb2{MJi{-#Y5>TVEZ1>#oCZJ$Cr5(+K#?>b^A!a)pqjV z{?cJ~Zr|xJ`?nu;Sh=@Pbr_%9zdDTP?Q0#z|Mt5Mt5@%hs&DCZC_jC&L$~bHvvTPi zAMF)S?G=CRRlTI&zTa_>|Mmk9vvd1|huOdV!^6tGeZ|B0+JZ~TJ@Y?IWE2>_- zH@fzE>2xSReX>Kh?9;Py=^P*W$5Xq+pFiw(J>#x;*mx{XHcpG5jo;#GRps(y@!{X%$?wIVKdfHTi-+YePG+b0nf>Bw z zzlHtwy(qW+F!;1j2G91-;NQL)^=iM3`j$?I^3x|fbjvH0^^)Fx z75Ur8!cO~J*l*v9a@!AsPy1x>Z2t`Y?W<9*_S>j$>2xSReX>Kh?9;Py=^P*W$5Xq+ z|IJ^EH;lXX?-`Hn>oZQwNtu-stzEmw)Nc&L_{u{_rbz`0*KjJcl3u z;a9KWSKr~M!|>B*_~|zM^c;RV4?q2fU%L#y_WDZi_oLUoOMmS?{QAT2>nFpn{|vu= zHT?S9@au=euYV4|emng7^YH8E!>|7jzi~1A#>*$qXB-V{ul6};$M!$S-@XWT+AqO= z`zVy#{tA5BcY$a7G4OAnhI+MsLw!r9L;2~G9lB+oo|Q}I_|QL|+AIFrt9nUq|AYMP zi(sey6708+Lb>g)z^8o|c(xw{|MqF9SNk{Aw{$v`pFY{4TlVQ$xpa;X{o|=!;{W1} z?~JcEuMNNXZurfE!*6~Ze)Hz=n@@+|JUjg6-{Che55M_(_|4renOT+5bdu{4l zIvvVSpX|^r`}C|_I>(3p@zgHyfAReH`NPh;Y2VJlY4^^@=?|To(@!og-T&2pI%lU} zb^cC&>s+3G*m*tuvvmEo{Q7ft^z-cN|CMW8#K(Avr*Rbj7tfEI^v=7<-#IvTIv>aW zeJ?D(ayw6lPv`9L?ED@6oy$|N&g-df>2xSReX>Kh?9;Py=^P*W$J6+VzxAkFXZu!r zS@*bgs$uIPw|+Hjo#fWFhOM96de^XZm0JfJw%&5AZryCy`pm7T4O_Rlb+%#a zIi*|YDZllf>{u7dzV)KYwT=`Y>r3&p?i7FPQPoTOtt+lv`ER{(n4MdP9A^L4Cx?}L z>z2d#+)A>2xSReX>Kh?9;Py=^P*W$5Xq+|Fb^-IbSKg z^NI3zZjqhNGqT?~N9A_@5ueUQ;@Npg{5wafUY)O0-_q$&e)?pGZrP`2<$+_3C`3`j$?I^3x|fbjv9Deho>{0_fyJ^aS|@bd%1&p!-5zcKv$$?)?t!_WT=Kfg5m{MGRDW5dtC4L`p(EZ*qd zCG%SEF`4grr^!6n`%UJ@-gPo>_TH2Ew0EG)v%L>x{_Wi;^K$P=nXgMXkC)&4o*nak z_QeC0D^7@y_#vL+iuj8+s+aWMW0Jpjn%L?6CiZ*RNx8lEgir54;o198`2Wm%Z&bZ{ zPfC4Dr$hPalO4KcpPrRV=lIY+p4uh;{NbJBSlbzQKYaHe8jsy8Xq0ML;2~G9lB+oo|Q}I_|QL|+9m#< z^~2A5SkmvF^Y6uq^56aE!|dF>=)>&))_ea;xp$BH(($?b)raxCd)J5Yzx&vS)vNbz z)VFjxl%GD?p)Km627dhf-^-#aqw^u7%Hy*s1a-lM^%cWUtb z<@f#<{=I9XUcGmtzNOQl{Pf8V-Lg;5%B6FB=pRq*5`X@%-(iirexEfS``y+!?e|>c zx8He<>wf<=-uqpcAL#dD{-NKI`Hg;G=1)rJXUfn2WQSkMK7UoY{8)VWw|Me<@#hb# zm-K$0mH$WY_hokaJ(vA{=T&aM|Kii{!g%(3G5-CItX}=TtiGkwq5Sm84&Aa(&&s89 zeCQuf?Gk_Et9oh2>Z^UzLA$5V{NdXVpr53t{*%u7Rr>31wTpgOd+DF0>$m0CpR=Q% zXJ7xXy^M?a7%%ZOj^b~8RWIq)SN?QhCwu=p# zt{--vx&B$Yep`P1IXn7!_7`uwa*d1l7%%ZOj^b~8Rj-%6`@moR-4p)o3_ttBuiW9s zXZMglp2Ls-@T=GGtMBmBVfg7Y{B)cBr|0m~dHCu7$@6KKulJ;`AAZ~V#qy?!z*UcLS^ERMZ?H7vfp{x&S`y?!_>9xh#+Tz>I$cEr`$7jIXt zI6OY$`FM)w=sP{d$U;t+?3_ufn<+GG-!RU||sx7TYu=Y8&DRr=qqYX17YYyb9l?a%tGbM_gYbM_H`_TOdW&VId2&+PBZ zbk01mO#jRe%kr9eV_Ckn^P&FyDGuL?&(Fr?b9(rnPUrLKKaO8J)-g{mAM@w(F|S_w zT;|*5V;){U=I7;O-d;ZD^W|fnUq0sl<>R=pd>k*9kK@SlaeP@mjyuc8@o4!tPAwnD zud}^;_0I=!@<;r9Gj4v;lh1VKKmFB3Ue!y!wez9={3#CKihrCBtWG|shyUq3&MUUh zar|07=E>z_{#-uh)#YQpT|VaFR=sd>oIKkK@$xar`>ltJiV7+xFu)xO^NRmyhG-@^L&}K8~}?$MJXhI4&d{!;PkA3OiU;f}9{VO-#>o=acJij&F_?EZ%hUIVm!~gEa^I!Fx zOZ&6#apUtI{J$;BYt~F#zV}=F*)6sI?nnO7E%l$@@NX&3x4!V#Zz=vwAMmnU8uusu z(l7b;>&E#v@Bi;_N#~!w{AX`TzqN?UOZz{6!&}e(pZFE;xh&4)zbyWbKH$xljr*TJ zkh}S=l$vr-1wvSyR0SqcOUWtv$pdmZ~J>b^80W6&5!+*kJ4}dDlhGC@bj1N5$pd&&%b9ilE-~Lrz+Gn0zo%+xGxh&4itIOig ze7kJinTMC@nfZB{&Y8ED>7V(0Sza^VvV3djL;d+v9KIEwpN-4s^zc8O_OJBYznVAH zvH4Jan-A5!`Ox;zd}upqKD7NbAKI>(4{dMFhqlA!L;F|lw%hvKzlvi!FTU-+aqSoB zvA?9#ew2RuS9xh~KGDB7+k8b&^BA4YZ}d0s$*cKLzP0nA{`@Hp--^%A z#^rN*_@7R7Nx%JT#@jhr9Upc7H(FNTfBYeLUsm_$JnW5^Z4VE*=^o3rlP`LcH(9p* z{Kj`(*mm`m@A0PFZhQOYFTAkr@VEZKg>9d;+ivS`doGUcy!f{N#_1-?|Jk?w*|KqOyz8GX)AOmn@Y-cM-}ygX=5zXg z@1Yl#SM$7lYv)7#`BNOe6`!At%jfj)Kb`85{$oD8t@*I?t7CuM_G3R?KK9?`W4~TL z_V?vu9#}r+hvj45SU%>H%KIWh0V_sT5=Bwpn9$P-@&I9Gu`JsGk=R^JZQyjh(pP!A(=k)MDo$8f-^I_i& zwBLQoA6~u#Xn*{xzx;u>s-yk%oqz5FmhHcv|H@mJ?bjdtwimX)|H9|r*mm>4`@QCt zW%I*3yy(K_jhBASh0Q0mn`i28{wa=msrcrr#x;+n$NZK~^IrPRhvlXHi4S=2>e2sS zf5hdRjN;t>F(10^;{V+b{IF%?e$$&jWSO2f{r(Hn`NH>l=%s!1|En*(u)Oa1br+Uz z?R=;|e~QDm;`6g{`J5j9r&C?hKgT!6<=w`9@Ry%_UVlCHgP(j}e|^xypX4~WeSY!{ zzv8_9db^+gvh(_D?rELZUyu8<$DP+-kN&35J+Hsq2bk@CM_|F&Ck+MdO4J2!6I zKRxXibhf|H-+m;o_AmL?&WHN*r#O5oK0h0m&*|ZRI@Klp>eY6rz3o%~wp(%9p2crF zH*VWMJ?$5Cw!hHdezf;(j{Qr%wez9={3#CKiqFr+<#T%YpH6j2zj~FI_O?&`+it~a zdltX#+_-K3^t4~l+5SR*`;olbzvNpxAL`Ga;_$8b{A^r4r-%RPRG0K0``0bzy`zrH zM}3!%x-TEw!}776EFas?o~s|*)$*~uEg#$A^09p`AKUGv{jxnTAKUrHKeqqnW4~BF z_Lt>jKUzNaud}`LVf{N#7H9I`KH_&?ZQRbckNti7(AoJp{hhbVtMhsJ*3O6e^QZH9 zz7?OJjmzis@IRgEl77dp$!+zRCuhG~Hh<3kxNKgXe#_?D*?*VK!?Ry6o1bTYU!Tp} zGY>4A&u4yEHqXzzvF!L&yW>Lr9WRRGI8uDam&SG6Nsr@EIvuCd@Ay?-+RIn}d=Mvp z#LqY5<|jS*OlSVnUtQ!?z2sXvAL`Ga;_$8b{A^r4r-%RPRG0M6|DVrQs^hDE|Gs-X zRo@r<;=3=a`-^_&KFhX;Kl`DK z^UMp|K5Mt#*5CGA9NT&EZU2pHzetb$C7t%K^xMCBUR3*=zVGE3SN$LU(91Kc;ymOL z?|IQY@n3u6{>#R_&tH14WqQ8udoN7q1K#t!FYTlMBOiZZc|H4C7nX1Be5gNvio>_! z^RsdJoF4wCQ(e+;|0*waEMN7_2X)UM+e5zDPV&?Clh3xR{I|VT7u#X=vVGQWyRE&BL{<&_r!+!jlXFu@{$FKheU-!B7kstoz?K9iT9S`}a3;Uh= zZjZgN->={7i!bbV?H7LIh5g?BiaRdscknOzy$kz&{BG~^-5b;I=6~?<7xsJlT(4}q z-`Q{dKkjOOue*KE+5d+haA9#i>eDVP{?ngvVdK8ri!Myh{r~la>HN)?UYP!0`Na#% ztM>W*8vjFSFhRs&vwu4)Zg8xJ#SFf4V&-VFV$=QFtV{*os@0*B)aOs|)?rOJ23l z_e#$G^Bt2j&V1kGj6dH!Imeyvp`3c=J1M8m`F_f&f4-}7<~842IrG(Cz4WhM;#4p3 ztCw-B7d_RB&gw;f^_pY(**@!spZ#ZD@iWe>H-5&Sb;!?gXMOTh&#YU1>YVk=PyMsb z`I*P1iWqO*F@U%lo!^lbN> zaQ!_$TpZ687vJ;7jq5q&^mslwot|56e(*eV^M>b~n@_Y?Fa4{RIMqx1>Sf&OMNjpj zv%1hT<@u+$NOvP^j=%~z3*0D-h(S& z?fIa8{)m%r;^(Jv^O>Ifr?a}yU%lj2yZ8R;?|s1Hcu%nS-XCmS?-i!U`-bWC9%A~v zpIBbrTP$Dg`JjLPh?8&P=cjS=nV$Tov%1h9@XFd0F?Ye6{C;{`n(LzKNfo#?5DX@}JJ?MSu00Yqqm} z-nTmY&wE&BoOwU%j6d&fo#W2?T&JFS&+F7V?|G8v*2S&A_3eve-TUHO55IA(lb;^z z=cm)U`sugce%qmS_^X%p>ZO165~q5JU%iZ5z38c4bXFJotCzfLw~lfBeUG3x51Q{L z6o209Kgac5gYIfr?Yy|U%lpf z{%rq8Pkh6(|KnfvhG(3A_%UyE#(&9oztK7FeeZVnQ_rVA=2vOWSH9Dp5BleiIMqx1{4{Pp)06*nRu}rKm%M8K({Fl%v;SYa{~Mff?(uK$cErroY=k3+&X?MQv_Ufg*dg))i#Hn85S1;pM zFM6sMoz;u}>NWRhZm-?Cvh}y#Y;mkZTYT%&Hm-GR(_=l`bXw;&{no!NFYDr#ul9V< zzj}#Ny~M9x#;soTR4+QK3;oqgUbR~Xxc=4$E{=7Bi*G&Q#$rR{ncyk&7JMm$*I5fbBbeKo#I<>r*W;rlOF5y zq|>@R>9?Lwd0FSDe6{C;{`n(LzKNfo#?5DX@}JJ?LVxv=SMAm{s{h01yO71P4pQ;0 zkJPx(^`gIe&ArC6-8zc( zx4vR=th-oz>oGR2bsE!S{l;`!*D?Lpdn_;OK$free9%9C#K|}D^V7KbOi%vPSzYL_ zUh=Blx|j909%gZ@lUaQ0XEv^NHPd6g&2(CaGyT@*EHCSJmaq1F&_92~$v5%y)42Ie zPyW+cz38uAb6@yu_a1lsy~kagS#RNtKkG1@U z>YVi)PW`ja!ZO16 z5~q5JU%iZ5z38c4bXFJotCzfLf6@J(eD?o?k9^V@=V^C-#TozSpYgP2VuqQ830eYUgR zd(idwespoXH(h-1Q#Y>ntkdKD>vVcAyZOQU+RYo@<8D6DUcL0MUgA_Q@vE0{s~0`h zi_YpofAx}A?cQ6jzxUaT<30D{d;h(0y%(Pz@5`std-Un|etmg)@4kGs=Y#(FBTl}F zpP$CfXL|CV&gw;f^_uI-v)wvW^|wA%ajaWaeCt^?u63@`WBsdiS{Ez**2^j{>u8m) z_I%Jkf5gc*@$=KT`Akp#(^*~UuU_)1-8%gBpLIUZIJ5re8GqIVJ;!~>2fX#EXVwut zbw^c9g)l2{CB~JAczj_(B zdeM{rbXFJotCzfLpYN5N{pUL-XPo)I$zAbh-RZ`i@1dM}<~u2;&iQ`Iseit!a^^MP zTRHR9o)7xxk2v`z{^{q8o6q#*Kb_Tu{=4e+h_n4$-{a%Y{!h8bW6wCReEi=&81*zx(F9;=ki^l_zVDgW13u!uXTI92m;TjDoa!Zh_4>{kw|dc2z38l7^jEK&U-1F=seRt>{^9!1 zd*3f9&b$x)lH%X_LoaP1iWqO*F@U%h_g1vlU4s{Mgi{cpO8bJJD)o36&a=}OPdS2}OL(tq<+ zUN>Lmd-IhKH(&X4^ObKmUHN&_mCrX_`G3<@T^?Ay=D2)I?Ni5F>Ob|pr8rafTZ%v1 z!!3dKIor6;^dq7`DxsIrYHaDtX}k2FL~8I=Z$Co zIiEb^%z5S+f6hP8ap%1B)HCO+r_MQ#J@wD|?U|Q#_{&#&KIor6;^dq7`DxsIrYHaD ztS$`K@x$Zml%=O@@bFLFl z{d4_z<~7%qXTI92m;TjDoa!Zh^)hbtqNjS%S-t45UY-fAeXgU={&RhO#+mExGyYtU zpX1JT`l)BG-%p)$U4QDI>-{sYxesvWtG#;ZU%kYsUgB3T<5n+vsu!Krh5qU#uiEFn z$Ju}Ghn#WdKFJw>?w_3F&V7|r&)jc0bz5YCx~9dq-f81n2Q@v`M@^@7Q=1>Gr`mjIoz><; z?bS>F>LpI~62E#Gw|dc2z38ki^j9x=)oxwc`de?dIM$&pzV&Gv*SfXonfsZiPV3yJ z-}<-ZWnJ9z)t(Rf=Z`q~CVqYzH=pUre>$rd{ncykW1sDFANcG)_lM6obKm%kKlhW* zapykssb}s#pE~Eh^r?UDSD$&!ee5$|?bS>F{1GSL#LrLT<}*F{PiJ+Zzk125_PK9= z_MiLtXPmjuf5xBt|L3^#yTGYuelIw6&hH4P{`r03%xivkIP=wBz4WhM;#4p3tCw-B z7d_RB&gw;f^_u$tXS?qv)c@fh`_pHf`CaCWKfl+U8xJ#SFd}&&F`G;zQa;~ z-)AX~@3s`*_gos+cV5!t`!DJAU6}OyUQF|b@5ody?bS>F>LpI~62E#Gw|dc&|8!Ot z`m2|`YWLlo`umxW3Di9^dOpr|p#yA+*+J@uHe?<&+`ViHtsx!aBF(z`GiyFJhyP_ zpXV9QyyiKFGhglbpnv{|lW*eZr*ZR{p8Th?y3k*}7T*Kzir=RM9i^Bl+-f1VGy zwQ=XUkz3O<&y(Dm&Uwz{*6Q_JUw!vmtJgf2a%=U{UcL0sA938qd4>2&KckLK^oV0L(((P|C~B~XXMoXjC-DW`7X(s@3iNG{`n(L zzKLJGj9b0vsa|we7y7H0ylVFymiqfXOL2U+rTD(*(zw3!k{;iGNvH3^q~G^qs+aG` zl&|*crGNg2lW*czFXQGjJ^4>(^`gIe&2{D3Ze8^HTQ9vh)=@9M_0=2Ky6fq&9(y{i z)1H3ox0jc7-OE>dKIor6;^dq7`DxsIrYHaDtS$rR{nblewa;_)Xa9NL{){uv;h*v6`TTR-d2avI zGtcv%I_Ek6Q~x~wf9B;op4Cfx_0qq3iBrAAuU^KjUi4HiI;#u))yp~wwa_6|boN?womoxsn|8kBy@5P*Y=6#t{=e$RA>c8hVe8`#Cymxcv ztG#;ZU%kYsUgB3T<5n+vsu!Krh5qU__u0<&dC%zVKkpx%apt|GGyc4aKjJy?W_iy~L?r;#V)@Rxf(07oF9G{^}*K+ULEnv;Vv= zcE*|a$jP1iW zqO*F@U%lo%#It?g<2(D$`+aAedGGIxKkoyc7R7=pZ77(IP;$78Gqj2Jjb2)I!`_G zzUQfP-UB`LKl$08eC9Rpjh^{xuU`6BFLA1u_|?m})r+3$MQ8P*zk1DkzGwTqCwumv z_h-*I^Iq*4|HY5{jC0(15BJnF@8_O6=e^y#^ncyoIrEzLeDBJ4+N+oT)k~b}C4TiX zZuO$4deK>3=&xS#s(s#TKKsx6&S#u?5BiKh??<2G&U@3Ro_U}8)cLS4|D03*ynlV> zHScAg`D(9T`d2S;s+aiH%ed8xp6W$s^`gIe&3p7`yLF7~Z$0PYSm(L;)}3x#>q4i; zdeP~$j&#Rg>q~bYW!>q{H?&tT{i~Na)l2;9W!&mTPxYd+y3k*}dKIor6;^dq7`DxsIrYHaDtX{3_{`$J^ zbnAq_`4@cu9oO92)Y@CK8n>1;ZjEc)+Sj->v2kl<9{r3aciyP)?ml2&5m2M9k-S{u3mG${x5KSwD-5Tn7FZU8gSZhnsK?{a>V71^91J= z&O@BHIM4C_+j{S>uj}*oJq2~V=GO4n-rD}SHUDwn0>FJE0Qcb3p zf%`TDmRI{--;&VYHzsi3p1^&R0`t?c0QU_G+_x>Z&*j@d+oyWjZm;?E>AM)Ouir6w z)A_Eh^Ak0_=Du~Jy>Fo4zKw$WW(w|GD!6Z~;J&?r`z8yv_N;R-+&5fs-*&-$^9A=U z7~D5vaNmx>eNzVatr=YHYHz>mn>E_|mJRM3H@I)#;J%52`&JI_8#-8C?RR~1M|-V0_lfGl6rq^uF^enM<^Q~u$v3c0D$GC4xVe__Um9hEUGtAgL z@7ZQ-{`br?c3ki*GaXB9KX`pH@WmtyL;XLDVyWb z{y^1mXB+M<>MM*xo;QBtJ>k?y6^07tv~I@b>i}I{kVKwS1updo6E;_=<;!W zx_n%>E+5yk%g1%@@^SsUd|VeVAJ@yv$944baecjfTz4;5FWcue*GGGQi;IaH3#S36 z4W}8G3ob`o?l@0yUg12%d5iNLAJ^u)er7e&eq1ALyZv#F^~=XK!t!yAaQWN+pL{>m zJZYUw+uk)F*9hBwTwg37*B#5p^~myZow9sfzbqfuHOt5K&hl{`w0vA2Eg#oS%g6Q9 z@^PKDd|ZDm=Q;h=0#_qk?P|A{X8qgm#Ig3KcJZyriH&QmPE3zAJTaZt_QdpC^ApR< zTA*0Iwez9={3#CKiqFr+<#T%YpH6j2fAz9`UUPl4_qVv1xUp~=aN2O1ak=1f#O03j z1m_jbL!7rb&#~Ic5v!dXu{m?byX;f1N8edCPs+=7a?R#UYocm5XId*2n=`GUip`nU zR>kJb|2k`~VsoaoSg|>CehXMOXIi^eyE)UEuGpMeyE(J|=FH-lGmCG|Y+Q3@dd!*W zG-sy2+8Il`HBqtt)=I_VSVI+yKfk#w8`qkv+Uc{uUP#Hx^Co#A+u;taft5Y9~jmc5=jOCr4b4xZH7`;Jm_li1QZbIaa%L zRwM1z4r~AHS?i$w)9qC&rr(+jSYFm@!1Aq~5B29y zarjnzel{+j)5HICs!RH-mu=>n>!ZED#l^&ph0}o3hSQA81(zc(cbq3UuW%mXyv2Er z)lQDM8e!)u)_ui}gVuw^j*r%f#g3cSkHwCs)|JJMv(}r%j=$ES#g5C?r^Sxf^Zd-R zDNR|Fqr|c3*Vfw_0|; z)cRD~-AA=<6?T8sdREwdSL+gPVaoh(kzWc+C>%MV% z+)qxY`^@Qg|5;wPlWVSz_Wl+Z6E_x415O)GGcFfgj=0=$p5VN~d5H5C=Q*wxxEkSV zSG%>d>TgXgERMCdu=v*C!p5~W7pBLWU6@X5d13mk@rC7O?Jq3f+WAm_{uGCA#ph?^ z@;N>HPp7)1zk1nDuDL$i`&(R0+*mjbIBhu1xLj~K;&R7%g7XUJAapXX=k2lMqv!Ck;o{9OntecmB}0&MVU6d?TICL(=d3L|(R&Yp##>{uUP#Hx^C)`A~oU6o+rc=V#;cIX(POr@ExSdf85{xjx$aTU<=sSU3$hZ8*)iTyQz! za>sds^9tu7&Rd-4SncG9)lQE1m@{wSV}D#e_S5BK|6M-z>*ZsAUq0r6+c!Fh%A5a%scJ2_&tlOwK1xZ2h3oviwMR||{d9WE@s zce}80z4L|X@h%vq(>r3Ae(#Q9d3mP{%eQtu)So}a;ala85C7AtF6pmcwv%hF zkM{l+7ZW!YP6JLGPBShST#mThah~A3!g+}E7UwxuJ2_&tlOuL*?)xm*b)WCHVAq4b z=Ym})`pye>{W$M=ExWGtT^Q}IH+?S#yAJgo8SMJh_hqo_R^Oe$u4ij^om+p`zr}G~ zTzuEdjq5r(J+80Q>AE}puE*tNJGtiiXzy=vF>zzzG~l%1G~;r?<%r82=Lya$oQF7X zah~I9fvXX&cD4I9P5phd28-icHduV$xWUHt?Hf#wZ{lD&eJcmk?;AQ;UcRk^d&9z@U8g#Y+OF4hyUqRm-JUJ+sQT8M|*#Zi-{Wxrvax8rx}+EE=OGMI8Sh1;XK57 zi}M_-ogA^+$q^sd2)ASBpVp_v&P%OZi=D4p&lWq6wazVeerx?(?7Y{yxY+ry^>VTE zWb5c+=g-#H#m=j1cfMVJ=i$Y1eqMa%?TzbvK0VI!)9L&_{l|5|?Y5I^u8;Qq78esY z7ES|B8%{GW7hI0G+;N`Zyux{i^A_hht`@i&;c8dAHF)c9ZC)&nHG8r6*7C*1owezf z>9O{&b~>#IjOn*lFqW4!gt2^U=R^JZQyjh(pP!A(=k)MDo$8YQ>Sa5*=K5&wZ*ehk zW8pO5wBa=4a>3<@%N^$l&MTaUIB#*DW3`hbRy#RjbEfqru>H}x6WD%gJqm39wN3@L zUt7Nd+uyBgfz1P-IqO|u^MiFTuz6#?v$JeIv2KQT^GxmLpZc4ZietVizIm*1&2Q;3 z@1@gxn11u5ylf}eTp#WIEiNW*ESv_MHk@W$F1Q?Vx#K*+d4=;3=Pk~2TrF@l!qu*J zYircsnj2UgYjI%ltZzS+Q|{CogA^+ zS?8*D>tEIX;j=Cl7RP#7SbXbfVdGj~3)5rWElj8NxG??J>B91|eixQ+?R=;|e~QDm z;`6g{`J5j9r&C?huU_)9om_K$wD-5Tn7FZU8gSZhnsK?{a>V71^91J=&O@BHIM1=# z$q}oa9C5X)-5Ou@xAqqn$C_YRd~1ba<61)u(_?KhOs6%+F#Xmd!}7958J2JDe5gNv zio>_!^RsdJoF4wCQ(e+uy=*7fTp#WIEiNW*ESv_MHk@W$F1Q?Vx#K*+d4=;3=Pk~2 ztaft5Y9~j0)b94H_T{7h@)2kGh`)S{yL{+bK6EZ0`j?NqmXCaw4F>zzzG~l%1G~;r?<%r82=Lya$oQF7Xah~I9 zfsfj){%TkI?2p@i?5E4(%pA2W{>)v=#+^BBnVy;Jmg$^1aGCy@8<*wf+gQeuZ|!`j zKYxnDx8n1&arvAc{?B}}F^~Chxq8_quem|(=~#10{3s{{L}h@*mkVS(vDP8P&Tp+xh@JOZw-7rY zww@t&o@|{%?EKmKhuC>_?asIB?>xLX&d-bQyuERq&!@+Eemb51r{8sfylf}eTp#WI zEiNW*ESv_MHk@W$F1Q?Vx#K*+d4=;3=Pk~2TrIF`1UcerSGzS5>u>EuERHo5vG}i> zwHC2)t-*-tu{I;7)0&N#erq{md0FET%eQtu)So}a;ala85C7AtF6pmcwv%hF zkM{l+7ZW!YP6JLGPBShST#mThah~A3!g+}E7UwxuJ2_&tlOsN^&Cho0y4T-&?^qn` zz+>^P508yI*UroISWjL%oz|Jh^jm)(%geg-SiZIMq5k|S4&RE;&&K6*dibACbxFT^ z&F|*Bom_K$Y(M=iE+%d)oCcgWoMv1uxEyi0<2=E6h4T>SEzWa%T$^t$$F=!#wbMtt zwd?C|P5a_l>mG}54SZ}|YvW^jteKDLw3a@m-x~W^Ue?~n@~xc@_2*A<_*Q&=HZGsj z!~b-uOZuyq?c|#4qrJby#l($;(}2^4(~Qdnmm@BBoF_Q1a312k#cC%@p8rOM6dYo^h(|JhxouA0dc5==2(ca(UV&cZaX~1d2X~yM(%Mq75 z&J&zhI1h2&;ylOI0#_qk?P|A1U;VA!hsCj`9~OUpi&-|VH2}5KV{Jf8r!@mH{nir1 z^0LMtmT&ERs6T&-!?)t|vvK*H9{#6OUD98@Y$w-TAMO1uE+%d)oCcgWoMv1uxEyi0 z<2=E6h4T>SEzWbSc5=jOCr5l-BivTI@21t?_tdaBzO#nKzu$a+4I9^Y*)To6*M{lz z9XGt&-hAH;%gcA)@NTO|J0I%LpW^VX`21{KKBtHO=~S2WtJmCDxy^QR&GpgV-{NB8 z#=>d9X~Sv8<$}u*mpjfAoL4vxao*xQ$7&}>taft5)vk8mhO57C#$j=MOAc@R`NkYJ zu5Zs_dVG@()9G7vn10`|!}9WNJ1pPY`A~oU6o+rcUq6p=`J5j9r&C?hU%hN6*IXa% z{VgsgZY-PzoHm?hTrRjAak=9>!Fh%A5a%t|AC3y&XFa`aUvteDvL9 z?6~QB%GmMLcb2i^tnV*l$KUxr!m{J?d^cg)@!EHs^>G~ceP`_WUc2Ld{hbdK$9Y2W zoj)|L^NRF1-$V71^91J=&O@BH zIL~plz|{y>yV`vNy8gZmjm7cJXe_>ONn_*s#x$m9zS*%%=X}d!ng034$FjV9!&-m& z*3O6e^QSm`D?UFPm(S_pe>&AA{ng8Ma?SP8-rwS4;>N;hz-hy2#^r*`5tlp86P#B# z4{_e&JjZG$N33>o#GW`#$rmQF=TtlupkP zrQh>Ky>EWa^|Af*x44+Nv2Yr2+Hjh2x!`id<&N_N=M~OFoVPg7akaqJ2v@t>dtY1s z-s2Xh_q)aKy>H|8J~%zSCr)SYkJI0KEVAm)g}Ga z%Qkt<_0itn;$q^)!fC*1!)eClg3A$?JI)iFS2z!G-r_vR)dH*C_50@Y9OLc__Q!dC zY}tM~&y_9Pf9ILHW&8C!YqxBFpJ(uv%>(mn-m>{&p4nSAZ_KlN%jT1L#&6j?Q@i=6 z{^q6Pn6HX&9&23lTYAiU=`!qiKHB?R zTuj_pI1M;$IL)|Ra5>^~$9aPD3g;otTb$>(THtDgt6l9qXQhA7Uy0LmS>pG+mT`NI zi=LkEqO<3|=zzz zG~l%1G~;r?<%r82=Lya$oQF7Xah~I9fz?iq_^92DtM=ui|MC%M`G~)KjJtg3Sw3_w zANrS%yq1rAmk%G74}X>q-3<@%N^$l&MTaUIB#*D<7$DA+HGFduJ-Q3>)-u(ak_6We)sc@+kJj|y8lmSzYEac z?*;PecLe#?&WHN*r#O5oK0h0m&*|ZRI@Klp)yp<{&GpgV-{NB8#=>d9X~Sv8<$}u* zmpjfAoL4vxao*xQ$JGKKbLMWJYB#?x-(LItuD7iJ{NA@L&ivN7EdJ{r^Lxw2o!>^6 z>6zb5m+73}QkUtU-&mLBHNU+s%eQtu)So}a;ala85C7AtF6mbsds^9tu7&Rd-4xLRPflOwKnwa@SA+phmSORy}?JY%pd z{yclIY}|P!VVRzJR$-aWd4^$`{&}`xSzhzZ!?Jv9=R^JZQyjh(pP!A(=k)MDo$8YQ z>Sdd}=K5&wZ*ehkW8pO5wBa=4a>3<@%N^$l&MTaUIB#*D<7$D`PL5dZ=6<_-n%nOC z_4W5%dn}Ic-DC0Z_u7B8Y}~n5yiCvBLtdtH?kz9VKlhxM!Fh%A5a%t&AA{ng9%cFpzC-rwS4;>N;hz-hy2#^r*`5tlp8 z6P#B#4{_e&Jjc}ntDPLNYx8+-fA4j;?wjYOmt7CebJWYO6XzN7W!I1MZ27Y5%6aB| z+4bf;i@xkSbe>UPc6~a}t}nZ8ooCvYUC-9;I=B9=e~aU~xcIJ@8`pJodR$+p({*?H zU60GlHhInU(ca(UV&cZaX~1d2X~yM(%Mq75&J&zhI1h2&;ylOI0#_qk?P{NQF*aZQ z=N*k@apv8PW%1{oj%DM{yB^E*%sU{&!6J(t@!+G zTt26V|LIhh^j9z2=QY3<@%N^$l&MTaU zIB#*D<7$Dc5w3Q%w?2vfty>~a>zRn(Iw!_${S$gx7lqE&OQFAYROHqAD)OzJ5B29y zarjnzel{+j)5HICs!RH-mu>Qz>!ZED#l^&ph0}o3hSQA81(zc(cbq3UuW%mXyv2Er zs|8lO>-AOUd~DA-wa^~ z$9aPD3g;otTb$>(THtDgkJ{b1YF|G3FCTH1kNC^SxXXv0T z-170f-16}p-SY8#-SY9=-SY7~-tzIB-lfmw8NcP@xxT#*aLvave%s#P+HQ-98w;la zrwykWmkTaOT<$nea9-g&#CePJ99Iimjc~QAz55c!^PHQbINitC_{aSX<96SJp6-Xx z*?kiFyMH3D?yJbRc0SafKgHo&@z>8|Tt26V|J_$Po}2v(^|Gy2J6s>!-{N9!pUZQ+ zyA7m4d)jcCak=1f#O03j1m_jbL!7rb&vCWD$FsGoP3^j`qP_bP`ggxVobF?Y-~A2a zcHe`Z?uXFXeG>Y+eZynwZLlEeU;;$*xpw;?zb!-_hFWg`!mbOeVgUue$Mi7 zpJ(~F|FeAD7g|2<7cC$6k(Q79OUuW7r{&{*)beqkYWcW-wS3&yT0ZV~Eg$#6_P)wB z*T=Tn-{NB8#=>d9X~Sv8<$}u*mpjfAoL4vxao*xQ$JGK?BV6rjpE+mq)qm!qWpQSX zS{8riu4UuSoVHBQ%yr9j&K$T*|ICfc@@jn*`PR;d`tzqad@DXb8<)@N;eR^SCH>XQ zwtCI=(ca(UV&cZaX~1d2X~yM(%Mq75&J&zhI1h2&;ylOI0w4FHcl$JF&V9c<=d?fe z-l+Yw_et%)y=Q8_?)_8yd+(*12YO%C{Lp)>=8fKOHJ|j}t9hn&^H2TFOT{r?72iD8 zxaPO?nD^3YK1{!PQeL*nYp##>{uUP#Hx^Ct`A~oU6o+rc=V#;c zIX(POr@ExSdf8U5xjx$aTU<=sSU3$hZ8*)iTyQz!a>sds^9tu7&Rd-4xLRPflOw)d zn?GXrLDzks@NFNp?0WDC|Ko*SCw}_Bd-%4yeth8PU)Xi!PrlQIU2lH%uYTnAaUJ@E z7hl-*={>*Z!meB2^{X!IdbW1gx%GGbTO8NL#dp2jxUQqq+jX*9Y<6{)aAX+^>3*kJ)y5e)J(1rt=rS^L~TFDyGg&TlKrj+^tF%d+F?{1&t9IQz|Sc<*J$-}&uk*>QP((^+=B zp5JGR+8y`n?|h&*&J&97{GoB3SER@JMmn8`q~H08ylj)#Tp#WIEiNW* zESv_MHk@W$F1Q?Vx#K*+d4=;3=Pk~2TrF@l!qu+!`R#J^)qj4|Toz}3>s%Ipegj=L z?))~oOwasgx=iQ%mby&;{KmR0ulenDS-!RNq5k|S4&RE;&&K6*dibACbxD8qvQ1ud zeYE$txR|)Ha2jyhaGG(s;Bv&}j`IZP70yGPw>ZynwZLj8M{Le)T_gLWHFLDvPg^g@ z{@Xf2_UqOcvcI?Pka?i>h|CYIQ)J#~{UY;8>l&G7YB&GX-@H^D^HuT9V~uNmOOJUk zo#w;zn=$h+eTkUUgF>zzzG~l%1G~;r?<%r82=Lya$oQF7Xah~I9fvXX&cC}kG zr~a)MBu?uHiT}D|T_fYR?hrk#M?`1q6w%-MMe=H0Bl*_Ohx+rUID9KUKO2|N>EVAm z)g}Ga%XWCp_0itn;$q^)!fC*1!)eClg3A$?JI)iFS2z!G-r_vRY9~jmc5=k75$509 zvGdQ~*LGgod)&@fd%xRxZ0~(LzwLc+=e@lr?tHlS$DJqlUb*w<-Zyt%UAyz``a2IV zj`Q>4J8y4X=kw`to}W(V|LJ#KATQhDHP=Ube~XKW8w;larwykWmkTaOT<$nea9-g& z#CePJ99Iimjc~QAz4x{C?>%mDdcRxz-upIg?}O9Rd*XEV{y6=;S1zyKH_!^RsdJoF4wCQ(e+uy=;@$Tp#WIEiNW*ESv_MHk@W$F1Q?Vx#K*+d4=;3=Pk~2 zTrIHL^}e}tm7Z5|9PD`y$H$%naop_r5XaM=8*!ZNc@oFpo-=V=?)ekP>z+$-9PfD* z$M@PD_v`O`pg7JGitqfPah+GB$N5G&ork2~`AN^KTyuSFtNkr5CT=X82AnpWW?U|~ z9C5khJi&Q|^AP7P&U0KXa5ci!uJ)ey(7)$E#Oe7E@q2E>xIIroPtTdq+4Cp#_gsp+ zdR|4owez9={3#CKiqFr+<#T%YpH6j2fAzAhUUPl4_qVv1xUp~=aN2O1ak=1f#O03j z1m_jbL!7rb&vCWDY9~j0)NX&v)86y^`uCi_I6eO_e(wbsxAz6;={*8Ed%uAG-aC+2 z?<2^!c0SafKgHo&@%h=fd`=Jl)2S}$KkBu=!(MZJY^(h(E+%d)oCcgWoMv1uxEyi0 z<2=E6h4T>SEzWaXEpRo$)voq_H`l-4qs8fW>WzQ=er?=-*QTf6yXowAaQgdwTweWd zF5lYuP=Eduhi}DSKaX+woF4wCQ(e+uy=y$d_9uHE@|{hfyw$N72jowqlx z^ZE2R&rhfG|Ma^qke6-pn(L#zzs1GGjfK;I(}vTG%LSJsE_a+KIInOX;=ILqj;jT( zM!4G5{(z@n^40$>UwvV5?)!<4T_42%pZ?i}jr%X(^pm%po;x3UVLIRP%Pvg+lb?NI zd42Y`URb`h^P&FyDGuL?&(Fr?b9(rnPIXCt^|DP~bA7b;x44+Nv2Yr2+Hjh2x!`id z<&N_N=M~OFoVPg7akao|Cr9iW;XB{za&Oc5XZPWqmv(>N`D*v=oyT@R-}!C#`JMN6 z|KIs=zY91|?)L)c&;5?zyt;Ph+x2%IUL5D=#dqG`xX$O(<2*l|&i~WzxSg=9=K5&wZ*ehk zW8pO5wBa=4a>3<@%N^$l&MTaUIB#*D<7$D`?l1n1@LcyG_Bc4-UtV^6obNI(J8sT5 zsh1s3=Udgwjt)B^`L^}4F>L)^6Go9@~xc@ z_2*A<_*Q&=HZGsj!~b-uOZuyqZStDyqrJby#l($;(}2^4(~Qdnmm@BBoF_Q1a312k z#d(ga1+GTexk}%ibR6uvjgF6f&(U$S?>su5&f33s_*=)>z6ZynwZPQ~SG(GM)3E-1&rzJd^C*7be>CpL9p9a#r|(75 z*>@!A@B5PS>bsNjt(_0`=TC9?R(yUoE}zrG|8%NL`m2|1?3(MNy}!l9#Epg1fYXN4 zjLQX=BQAHGCpfQg9^$;kd5+aij#%yFh|QVv?;eBfk8_`M*?v0rc$e+JbMJTAem(bu zm+kL!uXx!!F!zv`%@1>LdD*-%_neo_Cvz`)**sIb`KSKorQ(>cif_! z^RsdJoF4wCQ(e+uy=_cln;O_Kp|&cN`I?sds^9tu7&Rd-4xLV+9 zgsWZc9WV6nI3iBR7x6pp7`NjQJsqd$?D$20$2EC%ypwP3e5gNvio>_!^RsdJoF4wC zQ(e+uy=at{XqS@ zPbg0J55@1kqH(+5NKf}6>FoX_{oS{eSNAjJTRR`>&!6J(t@!+GTt26V|LIhh^j9z2 z>NVF#dw+|Ii5m;20jCY88J7z#M_leWPjFu0Jj8j6^Bh+TT#c}MVpF?4=XAeia$j~I zW;|JTe`dT|cHd?^Ty{Tayj^ymXFOka|7U8k?7q;{XxaUusok>sNVU7aRDbuKisOD% z@!h9tT=%ciV71^91J=&O@BH zIL~plz|{y>yV_^Y*?je%xoBCOnWL7)pSf$!Fh%A z5a%t=A(Ao-rwp|Ox##F4LEH$&A41}IpT81d4lr_=ONBp zoaeY&;G=e{zuMK_@k0NOBjR*?5x?V(aXTK-({YNEVAmkNNN~)XO$m?Qnf?e~XK`eU7nk8gSZhnsK?{a>V71^91J=&O@BHIL~pl zz{i}q+oyAtIleAC4*uyky}`2M<6pb~g&jBV@o(?8?T)9v@);L)oc)})yRhT$C%yR2 zy=HV=e&E9|?0EgCx4N+7_|xuu-FaW7cE|ntJ0B>H^Mv9%e`s9i73p!lkxu6!>34o2 zFWclb*GGGQi;IaH3#S364W}79SCI=YM_leWPjFu0Jj8j6^Bh+TT#azGtNkB6@sh9p zkAKyL#rcOH^G54~_%HeH3mf;ocf0$x)AQ*Mx-gxO|AGtC|65;uVR^muITx01?R=;| ze~QDm;`6g{`J5j9r&C?hU%hOr*IXa%{VgsgZY-PzoHm?hTrRjAak=9>!Fh%A5a%t< zb6hR3+Q|{C-TVf0d+qZZ%Ci3R+sd*y^P9`E`14!LvT^4(nq_+Cx0_`;=Qo{Y`scTv zWqHkSK+E#2oe%ZrPjUEGe10}ApVPztbgE1G)k|Ks$!o5U_Wl+Z6E_x415O)GGcFfg zj=0=$p5VN~d5H5C=Q*wxSncG9t6lB$yWY0zKfh@%i!;A1*yWdml?{}8s`2D5$ewS%nzt^P4?>Oo7`%e1(?jtYToe%ZrPjUEGe10}ApVPztbgE1G ztCwx^n(L#zzs1GGjfK;I(}vTG%LSJsE_a+KIInOX;=ILqj;jS$J2_&to9C%+ul=|F z!$&Xc|H;pK^(nrS^UrZ){k2@?mPd+$1l_KHviY7mg#)#3m?5q|2y6L6PD%m zV;^#1`PR;d`tzqad@DXb8<)@N;eR^SCH?9pFWclb*GGGQi;IaH3#S364W}8G3ob`o z?l@0yUg12%d5iNLR|~9ma>UiH_RoI!!?#`kKmNvtEsOI_fBNCe;{W#39=dGYzxm*Y zEYow#2YlEvov;3i4_&7J0dIC;dHsW5`;cvyZ|!`jKYxnDx8n1&arvAc{-;x2(qFx7 zlh<4y?foq-CT=X82AnpWW?U|~9C5khJi&Q|^AP7P&U0KXu-eHHyEdQW!m{hW*&ml( z56)b)>^gDgsAboWGj}b!uADh-+4bhkb<3_pXAWF;eL8dFvg_8FGnZY@*6upD{;q$E zd9X~Sv8<$}u*mpjfAoL4vx zao*xQ$JGK?BV6rjpJV;ztN)w>EQ>Se2Fv2lIm5DX=Uif$o;k-@rgP3cmg%2!l4W_# zxyrJ9Yv)7#`BNOe6`!At%jfj)Kb`85{_17>yyp67?{9H2abw{$;I!d1<8r~}h|3-4 z3C=5=hd6I>p5tnP)lQE1QoGBwp7!ob=->Scak`Hoe)l(w+kFpux*tMk_etpQ{)xQ0 zuOi>t`A~oU6o+rc=V#;cIX(POr@Ey7Qm@Osg=?;lZMDC}#l($;(}2^4(~Qdnmm@BB zoF_Q1a312k#d(ga1+GT8+ST5D3H`fYAx`%(#P9xwal7w9PxnLU>^=$o-9M36_f_Ou zJ0I%LpW^VX`21{KKBtHO=~S2WS1;S=HP=Ube~XKW8w;larwykWmkTaOT<$nea9-g& z#CePJ99IjhcGve+KJ6`@^n(4{x$gVpZ~65f#;ymy_Wqyz66`whm*3_2%dQ{q{GpdF zyRLlM@Bf!&*PB20p>O^p`nwK&*hjqmvg^~o{ZHO`*>&qLzsp}=c0F6W>)iUg{w2ZCXPS@S(cRemI+vGLZM|*#Zi-{Wxrvax8rx}+EE=OGMI8Sh1;XK57 zi}M^;3+&olj@W&bd)@yjo8!^`z^nc@;UmuS5r6p@clpqBv;K$9i_Ul588I;v3Gv%g`MAi z&Al(|y!VkW|G@3zeE31%bz$epFMZ~Poj?E9(=P11x_0N=^>-d#9Ovi7ci!H(&gawP zJU^Yz|I_cfKwh?`Yp##>{uUP#Hx^CownU zVfoh1hx+rUID9KUKO2|N>EVAm)g}Ga%l3KA_0itn;$q^)!fC*1!)eClg3A$?JI)iF zS2z!G-r_vR)dH)X9I@KXzkAN9z4b}-Z`~4cTF*rM);Te5>z~jw&%|yVI_Fv0W%^r3 zMP9A1BH!BiP=Eduhi}E_XXElYJ^W9nx};yd3<@ z%N^$l&MTaUIB#*D<7$Dc5w3Q%w?2vfty>~a>zRn(Iw!_${S$iTS@iXa&Ur?Cnf`fp zeOX?uuOi>t`A~oU6o+rc=V#;cIX(POr@ExSdf7g&xjx$aTU<=sSU3$hZ8*)iTyQz! za>sds^9tu7&Rd-4xLRPflOsNUd%XiY4$k@Kvg6~NdoMd~&N=zAd9X~Sv8<$}u*mpjfAoL4vxao*xQ$JGK?BV6rjpKIIASO2-@ zT^47qg_p&jYvg6)&b9M0J#$UH`xl*at-VbDT!SymYp%_gd&9z@U8g#Y+OF4 zhyUqRm-JUJ+vGLZM|*#Zi-{Wxrvax8rx}+EE=OGMI8Sh1;XK57i}M^;3#@i>#OBPo zp1c*?AAjcCKXciB`iJj-Vf*iY{F%?#cKh{x1}T z{lgbF?tgu=&)If*Zu*D|)A_J3zcBr`J?Fym`i^hAuzYLhL;d+v9KIEwpN-4s^zc8O z>XQEIWt+U_`e^TOaWQdY;WXg1;WXoN!R3g{9p?$oE1ZWoZ*iXEYJt^Gj@XuxzG z+x>CYJ6g7%&RS2)_TO0pYT150YeOyD-)GIJW%IzSCADmRm^G%B%^S1!)Ux?x)}&fC z&(v=IslR!tIOeP3o5vd0{FWZ`UOLT(={HZx%Qkt<_0itn;$q^)!fC*1!)eClg3A$? zJI)iFS2z!G-r_vR)dHI{<%p|Y?S02e|GsY}PT#!}zwcogx9?=p)AzIJ?7Ld@_q{E7 z^&Kwx*3O6e^QSm`D?UFPm(S_pe>&AA{ng7hdCm3F-rwS4;>N;hz-hy2#^r*`5tlp8 z6P#B#4{_e&Jjc}ntDPLNd(j>5+~@3g;r?gG5%)zqzPMl7amRhsjz{jVcARqGwd0rj zu^rdkr|o#>{%!5<>(<}>-r~3qTzvP38`pi~^thj#PWPG9@BVYgyKAnGZMDC}#l($; z(}2^4(~Qdnmm@BBoF_Q1a312k#d(ga1+GT8+ST6iLjR5<;&glwzvGT^J08)~af;54 zU-WlelUK((`PR;d`tzqad@DXb8<)@N;eR^SCH>XQ_Ib_q(ca(UV&cZaX~1d2X~yM( z%Mq75&J&zhI1h2&;ylOI0;^reJLf9%T*n>S9S3LKm1W1rS#xIDadXz9S#~^~HENa} zXJ_r2WyjxH(`MOmdDgmFcD$Z7aF!j%XKkEi$M@PD_v`O`pg7JGitqfPah+GB$N5G& zork2~`H8%2lh<4y?foq-CT=X82AnpWW?U|~9C5khJi&Q|^AP7P&U0KXa5ci!uJ&2e zY4g>8)_PhNXV!pP7Jt@;S~l*i8MRE$tR=Nf=d3ZcO#iGswJfh$lWJMMwez9={3#CK ziqFr+<#T%YpH6j2fAz9WUUPl4_qVv1xUp~=aN2O1ak=1f#O03j1m_jbL!7rb&vCWD zY9~jmcKv>*z2Cp|?{_hA`n^p2en&HIzpv5L?{0MVdmR1!PA9K^zmsq6e5gNvio>_! z^RsdJoF4wCQ(e-pUj2S|&GoUZ_P4m0xUp~=aN2O1ak=1f#O03j1m_jbL!7rb&vCWD z)d;Iyzuz70`}^0?|E8-r%SZg>W8CFK&;IUq=v+SZFCTd=ANejHJ}e*pEFZpY{KL=X z!{_D0|K+1DtG{~LKCihx+WT8vOx##F4LEH$&A41}IpT81d4lr_=ONBpeAI4#v#S=` zs}WYaIlk^bsC|xu%lgkbz_K`VZm=x=oHHyNcg`i2>6vqk<<=Nxtm&KWL@@4VoTz%QNa}K{u&z##Y(>dq-%k6~xGEYm;Vj#-x1d{bswzP0nA z{`@Hp--^%A#^rN*_@7R7Nq_aSOV71^91J=&O@BH zIL~plz-lK)eEALN@+`FbEj?H4K1|OWyFb%&$nM+pe6ssFJ-6&WPtP;E|I>5M?hEz& zv-?Fo7wtY$?d~tt-+iazxF1z~_o*7!{j2o2ua!>syVCDISkFaYbA4>9{VgsgZY-Pz zoHm?hTrRjAak=9>!Fh%A5a%tp5tnPs}Vl#XYRS5_RiDv@BB@i&g;bQ ze9yR@2h!8|A)TE!(%<={ygJX6Z|!`jKYxnDx8n1&arvAc{-;x2(qFx7tJho~?foq- zCT=X82AnpWW?U|~9C5khJi&Q|^AP7P&U0KXa5ci_%z2J+_YwQ!JU_NdimhHdu zOx?2mdY-jgw!hCac+2L2c{Xp^{4me#Et@yyS-xfS$voq?Y@Vsz{8NAPQgO^z#W#;N zuK6uJ=Dl>957Td+l$Y)En(L#zzs1GGjfK;I(}vTG%LSJsE_a+KIInOX;=ILqj;jT( zM!4G5KF_9ZzWUEItIOidv#iVF&oi#e#+_$hm+6^jVwdThXJwb^pJ!;7V71^91J=&O@BHIL~plz|{y>yV`rsO8=g}5~t^~#P4}6Nzp_*3O6e^QSm`D?UFPm(S_pe>&AA{ng9%dCm3F-rwS4;>N;hz-hy2#^r*`5tlp8 z6P#B#4{_e&Jjc}ntKIc;Vqf{@fB9DJ?zg<(bMLk6KFr6z*M;4mdC-r&`L?@n^VXkr zVfS?BkY?IeqAMO1uE+%d)oCcgWoMv1uxEyi0<2=E6h4T>SEzWaX zEpRo$?q`;x_MiWXOTPMl-|t>noF9MWTdWV_zxsPFY}`+KgSXsvdY<<|7pC)jA9rE; z-}PA+me)PM>B91@oe%ZrPjUEGe10}ApVPztbgE1GtCwx^n(L#zzs1GGjfK;I(}vTG z%LSJsE_a+KIInOX;=ILqj;jT(M%cN^?B~0`I1bJ^_Oj#SoO>@jZq7ORvg7HTt1mmw z&N=+Ddkh!7BHpdljXoL_WoNeR*fACNIQNu~_6 zl~AaXknrFX0!E<9G?9`j&jnkdEikkLNODdD?FbSh0fB)DL?rEuj8UhR3|Jd_y{>z| z*SY)0Z_fLyS>J1YuIqE}z1MzPyFS|cTU<=sSU3$hZ8*)iTyQz!a>vyKS1Vi%aka(O z9OnhjBb;}&dlsVpbI!Xg&YTM`i$CYc%f_8^=Vf~4oO+qgIoDpMf6l>|<<;{l@~vGR z>aRY%RNrINtYw9N%kq+^@g+Kyl0yif{hVxaJkN;h zz-hy2#^r*`5tlozCb(MRYKW^XuI4x|a30~jtG(~(=-+pC#OeDx;`d!1nis)eu)(T+MM_;5@>4 zSNp7YwE5~kYdtNCGiyLCi$7~aEgN^%j9R8=){QfwbE53R*t~#ej{nN>p^yin~=RMa)dw+|Ii5m;20jCY88J7z#M_lf>n&4`Mt0Ato zxSHd&r|XB}cU{rAU2mkP>yUJIeUkpJTgt2Jnewe&9qO+>#ZkB7 zt7qe?b9&T2oqS1ue))agbA7b;x44+Nv2Yr2+Hjh2x!`id<&LWfu2#4j;%bYlInE2r zyRK(CN9eg|^Ut0uHZSdYWAoLXLpG1?`DF9ko?ABW?RjSN;hu9gPwx3=^XHz6Hm|PT ze7pYU;l(jOFTQzu$2>os=Ktw;UeI&V_go*p)&3S26E_x415O)GGcFfgj=0=$ zHNn*iS3_KFaW%(zf%6FGUF|(rtbflNi_>$+;`e;AaeHo=o}Oo>v*(=Y@A+qW^<1=k zYgdQ*t50#%t@!HMxayo9^-m{X(w|>`tM^V%fa+<9_Y;Et?O&{JTDK**y8#Px+{2^XIqy;TxM**KWRDfAjF-n4cHlyuESF z=hI`JpHB1t^xw`4p8A;In&4`Mt0AtoxSHd< zzQI06DUP}oUp*UFoztWK>EuiL^UH7Yp6jE%zs1GGjfK;I z(}vTG%LSJsE_Yl_aJ9nK5La7V&2e5}-pLX3ZvN}vw)fpe{rjGyIDO|){J#Ha+`bD* z&#bMnap;^iH7l74>4%Wv|Y>!ZED z#l^&ph0}o3hSQA81(zc(cU(vIGi%yxOgd++n`Qd@zNEbR?xcKcSBLtmPjS?(`0ClX>YN_+PbXi}pI?5H_go+C z{VgsgZY-PzoHm?hTrRjAak=Aaf~ys-hPc||YL4>)^G=S~Il|lndK{a7&OMZ6^U}Gu zvTVLO_gt3EW9MGXvia@YqggiZoqIRS=EHMOXW2Y??)5C2KhHg&W%KIV&A01s9$p;t z^WvMgH?H}7dd&0FY5t#n=LPceo4n`xXzy=vF>zzzG~l%1G~;r?<%r82R});Va5co$ z7FTne7dVe_-qk+$E;nEO=bq-WICHOaS^T*Nx@_FJH@ZyE+%sLKbMB=s(?9oEm*qA0 zUYF%tyE@cgeTt)Q#aGY9Rp<1me>(Y+{`~TryyyC8?{9H2abw{$;I!d1<8r~}h|3*U z6I`uuHN@2xS96>fn0Io-_L*JJv^~D;x}Iq}?K+|Dx9f+t>#i%>-n-stKhSkZ`-iSi z+HZ8-(*C6Dnf5ca+yB(xeyKS2SH-sV71s|l`FxEkVWi>o=#3!Fzd?`rRQp#EJa6sPNl;&)xqxLt3gr|Xb( zc72lmu3O5h>zVScT^;JLKE+YD;;U!ls&jhOKb?F@e}4IW-gAAl_qVv1xUp~=aN2O1 zak=1f#O02w39eSS8sch;t2xdK%)9&RnZNaKeavoyw#Vmv)s1bZ&-mvzw*5Z%Q@?-v z*slM~|9WHF`!Brb$8Nj*zz2QmjqM+v@roPUZ@m6>H?}|ds&Bcm{Y>rlKlQg?DvteC z@$JVN*ZwU%_Iv5HKTN;t^VR>&pKxPwe&{EkvF+l2-51>0xKDlRjp_N7U;3!+L+6{n z_r~-;`j>AkuRr(IHQI06DUP}oUp*UFoztWK>EuiL^UH7bp6jE%zs1GGjfK;I z(}vTG%LSJsE_Yl_aJ9nK5La7V&2e7fJi^yL^D%sFkIUC~x_oWF%hz_jd~NT`*M4C6 z+CMB``;Fymf3ke-XO^%1&+@fjTE6yI%h!Hv`P#oNU;DjVpW8lj`PxrD=J$Ee*FJOG z`&)gAi5m;20jCY88J7z#M_lf>n&4`Mt0AtoxSHdQ;R9Y+Q9tkNT(cnuqLI z`Qd9X~Sv8<$}u*mpiT|xLV*`@w=XH+^+M})AfHkyDvb0_Y36JeFXW|t`7BApW>)n@zt|&)j2)tpH9A{ z|MF}1;rCo0zt#R07ZW!YP6JLGPBShST#mThaW%o!3Rgp1ZE-cnd4cl?=Uwexhu6RB z^Wt>fUi_}-8@KEH^mP57&h87)-~9r4bss^#wW~w@)u%Y>R($nrTy;*5`lpjG>CZ2} z)qAdw_Wl+Z6E_x415O)GGcFfgj=0=$HNn*iS3_KFaW%(zfqB<`gzFyAgZjq zFVnd0*QCdNoOHUslm6?z&jY{7d#;c6{uUP#Hx^C^LtJff zHOF~@-2;*%&b!(>KhnSRCUH8S62J2-<97ZQHcD_b`=W+7t{7$~Lt3&^LtJffHOF~@ zdDr=!eddRL@UQQ-W_z6X(3fqe^A7&9?RVbIU$$M(JNwJF_j#9p*?wT&@n5!on0Nn| z?KfskfMxrWSu0@Kex`Q&pZeP`703Rn`1WIsYyXxW`@MA9AEw`aQeJ+O_go+C{Vgsg zZY-PzoHm?hTrRjAak=Aaf~ys-hPc||YL4>)=Mm1k+GmZ6%~$_f`(jy~SrcPf{C7Y4 z&Sm4y8XC*=%-R~ubk3R^%k7lK%Yi zTfOJ{Xzy=vF>zzzG~l%1G~;r?<%r82R});Va5co$7FTne7npZ)#Lms%^rWYr>nczB z${RZ${HO1{vGc_D{H&*)>nhLu!5cfT{MO&`q362FFZ~BMb{_gqzxc*`e)`%QJ8ymN zH{W>AXRmhWx%GGcTO8-b#dp5kxXz=~V>dcOM?pR#@EeBJllnEt2#r5nrZlV5#f`PQxu^;e(bs9W*XvvJiq zJ?fuMzNA0D{66owKHB?RTuj_pI1M;$IL)|Ra5>^~$JGQ^D_jk6wZ+vO=LP1S95L@c z>B)cKIko>E-~Q}n{oniFzp*&~;_rRZwu}FF{)-zM_fI|T#`HYpZO__1bpFo&`Ns5r z(>L5$UjNJ2+*rP~t3&YN_+PbXi} zpI?5H_go+C{VgsgZY-PzoHm?hTrRjAak=Aaf~ys-hPc||YL4>)^G=S~IYQf=`Dedd z^U{9L=BxeA&13uho8PuwnD@55m=CudnJ2e>nLoGPnOE0tzFmLw@Zy-C7vH?San0w` zW1gQ*^Z)caFKD~F=lb}q_P4m0xUp~=aN2O1ak=1f#O02w39eSS8sch;t2xdKoJTnC zYVUWef4^sO`kjm4@87s>7xc8f(AjoGf7_S5+V13AyE@cgeTt)Q#aGY9Rp<1me>(Y+ z{`~U$yyyC8?{9H2abw{$;I!d1<8r~}h|3*U6I`uuHN@2xS96>fn0IY=_L(!@ZiBYR zc@KTrb~^9iFWY|S-TYQfwbE53R*t~#ej{nN>p^yin~>OI#-dw+|Ii5m;20jCY8 z8J7z#M_lf>n&4`Mt0AtoxSHd32TfJ>`3@ zkKby4i;IaH3#S364W}8G3ob`o?zo!ZYK5yIuC}{b+HzPc44; zuZ`P%ZF;)jO=tJP>F@ryyt;2L-`dro{_0a4bt}GlHm*9SNBz^um-OeC-{(EoM|*#Z zi-{Wxrvax8rx}+EE=OGMxSHT@~vGR>aRYd9X~Sv8<$}u*mpiT|xLVnis)eu)(T+MM_ zVBX0Q-@JS39{aS<^_FG*=UUUUICBkZS^T*+wQStEX0=SuT+3RfbFOhM(?8d~mgP0q z#Fph-yE@cgeTt)Q#aGY9Rp<1me>(Y+{+nM<-8s@d*T-+Qzs1GGjfK;I(}vTG%LSJs zE_Yl_aJ9nK5La7V&2e7fJi>Wb`&{STeD$AeyvyRuwclm&=X&X~apzj`GCgyBb(zk& zw!BRLqp!WOyyjZ;w#&D6b*R7k6i3~Pubz#o&goJAbn+$r`Q`U{&-KyX-{NB8#=>d9 zX~Sv8<$}u*mpiT|xLV`bk-1Fc78f*3okowoi&G-ozK?pJh%SNe~aV1xcJVO z8`pVsdYoUU(|LFLosY}QZ}Oh&qrJby#l($;(}2^4(~Qdnmm@BBTupGb!qpI0TU^a? zUf?{!c~|?amA(1uKWk_&i!*C$FN^>C|HNNdHtwv&y-d%n(Y;LPtlhm#|E%e~EU#JX zds)7^LtJffHOF~@c_&BAyLoPZw?Xam9Luu)^9;|jIP+}JviS4N&$4mnS)gTl<{6=7 zI_KG;W%}otqGfr_vqsDEtz8}JuRg_5x8kd3;k>JTo{`&p^`B?wmc^N8>XyZyXYH1a zJI~-P(=*TJEz>#A>@Cwj&+;wHYo762mT&FqP=EC)j=B|JJsVe@)1&_B!ZED#l^&ph0}o3hSQA81(zc(cU(mpgtrUUyt`9PfDN_+Go?e*Mh{iesKoeDjCKHLpmI`9?a; zL(*@4((&$|>*KfD-{NB8#=>d9X~Sv8<$}u*mpiT|xLVQ;R9Y+Q9tkNT&RFX`u3 z&#T;Xef(DYTU<=sSU3$hZ8*)iTyQz!a>vyKS1Vi%aka(O9P>_&_&P^e&b!)s-b4SM z0}-d^L&Wd75##ne2|Yb$LTAsP(BE?@^6GgN`PQxu^;e(bs9W*XvvJiqJ?fuMzNA0D z{0{HAKHB?RTuj_pI1M;$IL)|Ra5>^~$JGQ^D_jk6wZ+vO=LP1S9I<;q^BwRvV)qw5 z^4orP*?or({@uT@?0&@G{nTGtcAw&7p83nm?q9tA2j9NzzQ$L-@mH7K@A!ZRzqaf? z$TxlTJC@xadB-bn?7m6u?x)n>eU{?5|5AMSWg7Pr<{nUb+{a0$`#b4(-$!14llNR7 z?foq-CT=X82AnpWW?U|~9C5khYJ#g3u7)yQi>i^(FesWoy zzx1pB`|`&B%^zPj?i*hIx0dPo2cQ4=GM#_;*Wb8I|6}id!?L`-@cVBp-`dro{_0a4 zbu0eX^BPy3)1&_B!ZED#l^&ph0}o3hSQA81(zc(cU(!r}&Ix6yNeHHoEt`7BA zpW>)n@zt|&)j2)tpH9A{pI`Fwo4n`xXzy=vF>zzzG~l%1G~;r?<%r82R});Va5co$ z7FTne7dVe_-qqgvB>J~*i8!riB7W_Dw{~@?zxotM z-HNZCjjPV-QU7%ECH?v3_j%9t(ca(UV&cZaX~1d2X~yM(%Mq75t|quz;cAGhEw1J` zFEH;~U*&dgemmYd@9TKse6Zt)^TduX&L2DOIIrw@)=Mm1k+B;t8-*H5ojxQVkI_?;^;}Ja_r|9hXMSsUNd3C&# zZ|&+(fAuMjx)p!xd5x>i=~4f5@+JNG<+pmz_0itn;$q^)!fC*1!)eClg3A$?JFX_U zTH$Jlt1YhPI4>~o?vHnK{oyg~w#PZ|Teh9fIq$OVcg}^EZP#;-yli`)bLVCIfjOsM zwttv&?PdFoIR{_1Kk2)Z_A|BH|J2`psW|pm#kU`8T>H25*zcv&{xJRalk)PLyyyC8 z?{9H2abw{$;I!d1<8r~}h|3*U6I`uuHN@2xS96>fIFGR7T{&u>Yf781{&THqS)92B zwJiQzn_4#RT(erHXRc)}(>d3;mg%2sU(539yOZ**T^;JLKE+YD;;U!ls&jhOKb?F@ ze}4H*-gAAl_qVv1xUp~=aN2O1ak=1f#O02w39eSS8sch;t2xdKoJTXx<8OM>w>HI(6dSm*3>E~}OuiD@DfB2Hq z|6~8)mz+2s^ww9L`2XaKUvb9$@{f4MHN4KeEHG;hHrfN$?L6O|MHWs z_UfR2^%1AKiC;a9Tb=2t{&eOG{rNT5BTl>Te%9ajK#Su$p~d(8(8m4O@B0NukME79 zbG~(Q^!q+(e)(=`erc}``d1%u@=N^uGH!m+lV5b^3;p>euiAYRv;Mx7SsdTcEdKY+ zx8obvH#gJcTb$|ijn4G@c4v9{rf0uT?bSj5{1T_SiC;a9Tb=2t{&eOS{rUBd4}9@y zf7WYWeEL86U%vRndB%%ga^nBVA9=|c_s8DnrANP%1dr!!yZ&o6n^{*B-D=;{AM&wlj8`Hr`|=)`~dpMB98 z_r0I~qNC?0-u}X)^M}9xg-8E$U-!b3*P~zi!jrG|{L(+a#K|x5^UJvTMNfXwnP2qh z*W3?1?bg$%zjZc>WBrZdTbHA8t=Ewr>v*Ko`X2q>tozaL(0U;KKDFnU{`nTeB-;#ixa_|~jwTx(gR#~K&uwDv{%t%*@y*2*Yf?bSj5 z>LX5d6Tf;Iw>r~P{prjv`t!?o3TpTLg8KWeL2-QVp!mLn(73*jkRIPnNT=^99R2e> z+4A!Jg_G~JR|oy8k2uv${OW1k>P%1dr!!yZ&o6n^Zr%I(Tl2p-z6DTx-w0@2-wsHR zZwjQ-w+7Ph8wBO$+XUsSy*lV$eZ;A5;#W`OR%d#uKb`qPe}2vTQ>T62TRHvbot+bB z-sL&*=N+Fj?!5bR^vpX!N9VjNbo9?VL?^F#x9H@ny*lV$eZ;A5;#W`OR%d#uKb`qP ze}2iU_IY3I^q=?0PMmqa?8Kk<&d#{=KHAYU@2MS~^Zwe=Kkv1jyyktkldtyt(m%h% z$uIHq%eeVPPkzyvU-ajf=l^T>UO@f5FHjus5ftD11&!;ygYJ-_tNFLClq{QNR*e$kU(bmj~F`6aK~Jx^YL&(asiGxo*z?0w^UCOy=a;-{cfYLu?iCit zJ;dU>x7fJuIi|!%ga5@^3`4)^sheRR5$Ufr*W$@J=LGie4#(TtixQp z^_lB$-R9z0&$;;4d2U?mKc~mK(CM^Zbo#9$U0&9gE?@1{LI3I_PIVK%dK$Mn(^LKF z%oqCeOJ22G*SG%GG%k*{j*D*%qwhT9&YCty&#ZNGbj}($NB^vibMl%sb56e6tAqa4N1W;=e)TkNb*88K)0r>y z=a;-{pLLK<|5+dD#F=%IPW)L<>5Mz;EFC?w{?gGo>oOhvvtHB5Yu0f(`D)KE{qswl z{1U%<8n-&rQ~l}87y9#So)b9jpZ2bwKKNhe{nW|pul=jP zck{&P?B#F=}YC;r?6J>$;3(W7VX znI4^UFZJl3d#op~x%YbV)t+Da=a)G7C4PPxH^1n~FFNyu{``_x?Q=i<^q>3eC(hh| zKk?_j{26!d*B?D|AOGl_`};@#-1k3u&GP^!U+wv&e}0LRU*hMNar29w{Gv0z=+CdY z?tI$4i&uZ|Ar{B`iN*KcV&i(BF+JXMOsDrB+n;+cvi-dGCENdN&oBM+OPu@?KfjEd zU-aY`o%uq4e#xtL@2S<_J9@?O?q2b|)7QA(^-GU;0MqH+!1Q}(u)MrWSiah;gZ|Y= zoa!ci^)zmErlfwI z`D(8Y`d1%us+;)L)40`{p6X9$zR;gv@~YiEp!&NvR2=t=itk=h<34TfVWr2tr*yg} zm45fC%F8{h^3`4)^sheRR5$Ufr*W$@J=LGie4#(T<~rMHpLG{c|5wA=tj;fMS?8BEuJcQKe(9fI;^de3`DNVvq9?!T z%rE-$YtAcAyYIo(-*@7Q9)kmD_ zCVuraZgr-o`qP;&^yinnYWE$n`um1jaeP~?_`bQ;xW2`f9^Yt7r*F5V-#6XL%eUUj zS9^8Pzxs$%-Ndh+#;wluRDU}2i~jub9BJ*Ix2eD9aEjykoZ@?Kr*S>clOE6cq|@_1 z>Gxbvd3j!_e6?2x{i}~S)lK~BY24~ePxYrWU+B*-dDZSYjrw~=r8u5lIq~P2md5q0 zOL{y5lTOdZq~9|$<>gtL^3`4)^sheRR5$TYJ!jnNOi%TvGhgU`!mrOf?ce#)pMCnj z`n_Lr;=JRPpL^ne&!>O>8TT*zu`fD$Uh;Wgd~|-rfBGdy|EnLo>g4rdZ+q3rS9^8P zzxs$%-Ndh+#;wluRDU}2h5je}`pnb*gYW*d)BmSG{EwVCU-x-( z==qHw`?#a?=l|Bn9Q{B2Po8n|de$F(#>rQEe(9fI;^de3`Sm?BZhp~|Uv%ad{rUCq z+yBr<*8YEg+duxB^?%*Rzw}3o^NUaat{*M_Z~yRHf3$Jm_RoInN7M5&&;8wRNatt# z(Wktj-`nT@k01VqeuuyK^pAK$zfbM?rGI{jlV9TJmvQrpp8TRSzv$1eU;FD1f8<^J zr`+{_=q}Dfckv&(8~33*JrCdMeE3fP!*_W-e3$RTcXfF9u09Xn)$O6XdOmbl=ZEg< z|InQ;pORm5Tz;hX@$r%RkH3!;XMBI8`15;sq;cnW@<@8-_wz_P=Xdo;`serdNO{fg z@R9P>ULEwWKH^k2@vEnCt1~^-pU!-tKfmNv`)qfo|7?#Z&TOYo#Q*fqKjY4Jee}%s zess=$;OL+I!^vy*8z*1w)j|L2BTjV_|I~BFt(Gp{wMtU>C-;@$U&hTZdh(0Te4+md zzkd3(&vEVapX1$$GsnRv;y?43&$x5kJbLDMdUVcl_UNDE@5yV9%O_v$`K5n;iIZRA z=hqyUPo3$>FFNy!{`{JG)Pve*9`d06Ge3Ed?=x?CQ2d$CJZRjR=R8Qy%zqxFbLK@4 z+P-GK^q}o)=1~vYzO?6;{`nCrRu)uVIfu}A;RZ%+fyuMYZGA91Ri_|?<6)tR2^PiMZ+pI@`zIPEjf zKmC2Lp*X(dP<-EaXk6cYNRRJ9q|K6@=JSu>7QTX- z7y9!{UbS1#zy7{uP#oVlD86qWG_G$Vq{p`s(&-xt>Gy4g^774v^3`4)^sheRR5$Uf zr*W$@J^4jve$k&_a~BtEX|RGdT=zKr=X%JAGuKH@{JDN|#+~abN6%bu zIXdS$%+WvBXHH(;ea(2{4#ES(UV_v<_rD# zC9m4&y5i|S*Beiqxej^a&-KYO?p(J#dgglO(K**SkN&y-dGea;q97QTX-7y9!{UbTClsQ%uiDvo!oitpX4#`R8Cdggw?(K+`K zj(+cUm6vzE+P<{sm;Tj9oa!ci^)zmErlZsJ!@<5p*Ssz06iLVteEa}Lj`-TKn?x9)UttVdmZ>r^+c z^{dlkUF&pO?>ha~!7eZBW0$Y?>Y#u15huUIub#%O&h%7&I`f78{E}Dg)+MgLHJOWJ zt>)re!?|&-?VKKKKBv=K(CN2Eba`1jx_q@)2mPy$IMq%3>S^5SOi%TvGhgV>uX&E> zw9j)mr~f>kbK=Z%J171;&vV9|=X{QydH(09)kmD_ zCVuraZgr-o`qP;&^yinnYMcpAntWNxS{_2c7&t)Aw^Ssv4InQw&{qua+ z$!nhbI{9kPFa7gNoct0$zl@t-^yC+v`9*(z&3WZ%pXc08|9SrH#F^*fPW*XZ?u2%t ziYLxI$9Uq;^NnZRZ~Yw~di2cmkVoe{CwcT+8?)_eo~u0hYR@nI^Glrk5euiEFi-_w7d2R?D;IpGt3o*zEr&U3{_&pdB@ zbk1|gNB=yZeDa#-mQTLg^GpBy5+}dJ&oATV7d`n!XMWM2U%o$5yYG_J-}g$2<2xqB z_kEMb_1%;7_#R3+eJ7>;x$md+JM>+ZwlD4ZrGI{jlV9TJmvQrpp8TRSU+B*-dDZTF z7WMZnkK*{oNAc(R{4=g^f~3c{Lel9QBI);Sk@E7*k@D4E9rUk0;#4>BtEX|RGdbM(ynGDqjU zM|1SQ-+%k5C$D+$=H#nAzx2;9aq>(2{4#ES(UV_v<`@0>HP_iryLB?_Z~e^TSXZ<7 z*4u1c>u{#W`kd*sZfCzY>v{G&w9aS0Pwn}oe}0LRU*hMNar29w{Gu~o=+7^C)oy*o z`deGFIM$pjzO^VD*BX`Sv36xTt!bHlYh9L?H89Ipdv(yi`iN8A#IK<(Gv z{`{Kv5KsHO$9MYA`+X(Gp{``_x?azA6i%FL~8I>js?uuX)!iPn=n2;KZNx z2hO;&F2T_=>lGZGv+lvsKkFWxyk^~lldtyt(m%h%$uIHq%eeVPPkzyvU-aLv?J(Cy z&pHoyu5DX8V%L9&@79#qbtA8JBp$cE#68d7pTD){kGdJldNS&Xtuv#}*!nZ-kF86? z7i_&6eqrm_@DW?zhQHXlH+;u)J>!Aj1GY|1?bgq!zjbwrW4)c?TZgA{t-MD6 zdOqp5&QE!1ub%p=GY#UXKNg=a*tq<{^zaeW$zM!A-?6;>9YN_+PbXi}pIB%d57~3=N-;FoOd|yaNgm(!+D4E4(A=tJDhj5 z%f0?;g7XgN9nL$PcR25G-r>B%d57~3=N-;FoOd|yaNgm(!};ZRVole6pVkZQcWWKd ze$Uny?RRe7(SHBdBW=5|PHEeV^-J51tZUl#HOH~D-B|~ z#ZkB7t7qe?b9&T2oqS1ue(~|1^GB%d57~3=N-;F zoOj#j@($-+?QM5?r#pt~6w;oi#f9piGU06S=?ZvuMZAaFdYWte;&UR;gs@knvRe$SQ z6~{VP#kc-d<60LhJ=V)gr**W_|30%$T6t;jcdLKDXL0(Si{J0xxNR5ow7t;Tc0_;M zm%Q5UB%d57~3=N-;FoOd|yaNgm( z!+D4EYsTDd@N@p{ul(!Sw&^)uY@79bFSadv?ibs}Jr9g+`<@fV_6eRJ#`YDSE5`OA zo;Sw!EuKTh_BplN7uDZBsyOyt#kbFFT>HB8*axQ5aV`D!nNRxoS8rZd`==Q9>i-bF z;w)eBm#=Y`FFga%>+ZR20{T)yhOeAR#X@@4hgXYz}W z_nddy^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>C4K9_em@9x?^<*xrjIPbR4 z?YFV*d8a+^aNgm(!+D4E4(A=tJDhho?{MDXyu*2i^UH7PnseIjn~N@AbJXQ)?z()< zX_v3L?(#JUUcTnW%h#NF`I<{FUvuo`Ywo>#&B>Rqx%%=ohhM(t_RH7#+VXWCw|t!= zoc1{mp8j)uT)xgVmalV=)dDgIwxAb&Xtz0bExI(+-mtc z=UTqb#g?ygwB_sEZ8^XAc+b~)#GcFNoj!So^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$P zcR25G-r>Bfop<%;9nL$PcR25G-r>B%d57~3=N-;FoOd|yaNgm(!+D4E4(FF`?V5A0 zr?$;GrZ3xOXP&ccTb}vPvTc0kMa#DRnJ+EdC(Jx**}h`tSIhPxGw)iqZ<+bnvVBhN z_C@u#k1CFRSMlvL8`r)rJ=dInV_xTR%hx%=X>YsJzwJ((nXlgZO#GS0E*p2|x6Aa* zymy(-nGY}1Kl9{ed0B^3J>^@wI@Di%ilc7DSI@>(=k%z5I{A|R{Nm$1=biSv!+D4E z4(A=tJDhho?{MDXyu*2i^A6`7&O4lUIPbR4?Hqi!sl2Pb?Jn<%qgLDJ@($-6&O4lU zIPY-Y;k?6nhw~2S9nL$PcR25G-r@Z6J2B^+ZGL|<=Azca(Qb}vog8fLYW*B+PHSBq zY_4m)9c&J49Ug3MY<(VV&OFaYEzkeY`qei!$FAMnyZ+|n#W7bezBzp3n%k$xoIjn; z5z_A*p}e$P4~HK8t&@Yrv3?E~-?}>3xYpaj^jL=n(`kJkOuuz|@cf&#o!`AI-`dro z{_0a4bt}GlHm*9SNBz^um-OcsAMZKuwC5epJDhho?{MDXyu*2i<;XjncR25G-r>B% zd57~3=N-;FoOiX$z5Z%~^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%`QZ4+QqaEEjE_*X)z7ft;Mui&lb~com(uIxsSO#|Np?cxZ34jyPDKr zt%{?D#aG+LRrB=lE}gtfKkv#*yLDxatH1STu{hSD#o}9^78}>PwU{33* z{wB%d57~3=N-;FoOd|yaNgm( z!+D4E4(A=tJDhiZC+3`Utli&?xv2HGwVR__mm8bATCW?M(^|(Ho9q7TS>GF*16%hS zn;Xx4=Vfzd>x64Jm$rU5Hpi~r+`Infi>w#nXtrL#rW&Ln0-`dro{_0a4bt}GlHm*9S zNBz^um-OcsAMZKuwC5epJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2SUF~wO zznb8@!+D4E4(A=tJDhho?{MDXyu*2i^A6`7&O4lUIPY+N`JLSO*LRMjk9GXC`&;Y# zVKJ@yhmG~_N8h%)ujGvRU9=ezS=gfnx}_% z>EvDdZ{FQ<(QX|-k4A}tv86}WgS8+-`dro z{_0a4bt}GlHm*9SNBz^um-Oe?6F&a>WBDt0oOd|yaNgm(!+D4E4(A=tJDhho?{MDX zyu*2i^A6`7&O4lUwadN!YJ&3)=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{MDXyu*3t zcjDML&pkeZ9TTlDfgLNYJAoZTtw(_!Tdh-p9doT;fgOvjYk?i3t#^SPyRCzP=idYC zV_?Vn+RXv#Z*EW=bB5xZOEj)IMtaOu(rK=eesh)b(r$eTp^ye2J?>X^#V}+4+%ew(}<2a_3XF@y@es`<;K; zCv;wBU(xxReMskV_AQ;?+2_=5UsQklsN&dn72iIsaqa8UW1pE$`^@y)XO@@t&X4r( zyh)tSr^N3(%eb9?(bIVuot>}I-+7$8I=_=|?dni}^(l_J6<<9YSDn+N{^{gP`tysA z_nddy^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d580^_RjC}PJ7BW+TGtVaX}w2mEbBmG z8mteAX|rx5rrCOuST5F?#B#L$B$j*aYEpl-DvlZ!Uu_##&C|n+bn-6!yelv5FPrrn zjjO+P9kDppd&J^f2NE0C`jD6&>qcTattW};x6UM%m-Q#Hd}~*S`m0ZI)UEjH*|_SQ z9`#QrU((MzdF5lAcloX+IPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d57~3=N-;FoOiX$ zz5Z%~^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%dFOZHo`Uc7VD}n)#|OIy z;rl+=y$Rp_!R}f39uRgf!*_zPdmO$Wgx&k_T_NnA$h`No>|TlQ5NUT0rFQpL>hGRQ zaome3zI#B8>mE>g+|x;?`*-Pg52(Df`;L!s_4j=rEROH~;C-fIz6XSj>pMZ19^Vhb zbo#Ckrr-C5u)KVS2+Oy2b*R7k6i3~Pub#d`B% zd57~3=N-;FoOd|yaNgm(!+D4E4(A=tyX|v%hx4v>xz}G!aNcd7`E95n&O4lUIPY-Y z;k?6nhw~2S9nL$PcR25G-r>B%`NeB<&Uv3<_toa2)&tjWj%uB7Z0X=Go;fzhuHD?b{(Fva#W7bezBzp3n%k$xIYK&} zBc$IsLV0Po9=LJ!w@x?~$NJ$|eCvv1<63VV(_^yyv{ro_9F!aNgm(!+D4E4(A<~BkyqD;k?6nhw~2S z9nL$PcR25G-qkMm`l|`fJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2Sm*0tF zpY;&1W1@8uuw$k56R=~bbrrBIuF>f zzIJnf`kNaR$DE<~<`Ru-j*%X7m2{e`q~BbnytG>B%c~`sK>#rs_?{MDXyu*2i^A6`7&O4lU zIPY-Y;k?6nhw~2S9nL$PUw$XoHuwNv+vf7M%`RWt^76HfFJIgK^0iM`zV;Q%*FI!< z#&BF%zVy3{pSFDM>z1$M*Yb5-TfX+0r``H>a=iAj%h$el`PwHh zU;FCiYahOR?c0~Heg3k%tiLDzb&OcPjvdR_F=hEW)+}Ggpylh>w0s@2mak*ka(?mg zp7Tz7-r>B%d57~3=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{MDL&b#_slMv?}&O4lU zIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d581M?*v;<2J2&;8SHQ0JnPS3F|A93jb*(W zOoMf7Fm2Yi!8BX<2Fqo>3%NZ1|G+vq+T~umn$%ydilc_bSKG!_^Yrj8oxDpw@5)QN zb!LpKzx8LZIM$`X;#;o<8`nBEm>%ofU^=aPgXy;(4xWDxtdoP~Te~{cUww+BZpBy6 z##QI^sDC>7lK%Y4M>*!N+;QIFyu*2i^A6`7&O4lUSdP5Id57~3=N-;FoOd|yaNgm( z!+BS`-0QCB%d57~3=N-;FoOgaF&h>m(7dr>^ zyL7jGe>!UNClUTf1}K z`a2gcj&tPVJ2!7!=hW$OZk|rpPtxz)yu7sg-mY==_Z?m=j_>ng@qM=!8`t-IF+INX zi|O?JUrfL60%LjkUNDw#?dni}^(l_J6<<9YSDn+N{^{gP`tysA_nddy^A6`7&O4lU zIPY-Y;k?6nhw~2S9nL$PcR25G-r>C4K9_em?`oHO{nZ5L-S)Y>!+D4E4(A=tJDhho z?{MDXyu*2i^A6`7&O4lUIKTW(t~uvp*j&_ig|IoQ?+sydSKlGR=Cr;~gw1t*w+Nd9 z`<@XtH};()Y|iZaN7!82cag9;cJ1cg^*1Lkj=6gA&EXr@+&(?d5z^@#A^q1m!j7fg zcZH0rzwZrUaeRjei|_kH*tou1gz51;BTT379AWx>{|L*=cagAsYgdQ*t50#%t@!HM zxayo9^-m{X(w|>^yyv{ro_9F!aNgm(!+D4E4(A=tJDhho?{MDXyu*2i^A6`7&O4lU zwadN!YJ&3)=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{MDXyuUO!k?LSO0j)~^-HmR$b27p*}lbkr`qjvYPT<{zkO73 z?7NC@pV_$fb?LFsOsC^o`t38zOS|<#jjO+PM6o#57scXRcN81fdZd^h>y%!+BS`-0QC`?j`gu_Irg{DpY_bKnASPR#WhBIX13! z(J?*NOUHCtM;+5|eRV7^>#k$@)~*iqSD)gjTk+Mian(6J>Yq-&q(8s%QI7d5cbs=P z?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2S-S)Y>!+BS`-0QCB%d57~3=UwexSIIl=d57~3 z=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{MDX{IcC$+u&pP+BTQ3ZFc$EmY1(>eEHh; zm#=-o^0lv6zV;!@*S=->+UG1^`=aG*AGLh#yOyux(ekygTfUB8w?4Py+VZu}JneHV zIQ{4NxP0w<5o4&V# zZL_|^f^Eyb&w_2^zT1Lr`@ZLb?Gt?G1>0Bn{tLDb@m&~f-{N~Q*gmIr`=a{WM-|7u ztN8Y5jcZ?*9{a#_+GnQUKC`^E``(Ii_4geXEROH9VDaBQ-)+Ih^*t9%kMF!-I(`2I z)9<@5SYEytgXLShI@Di%ilc7DSI@>(=k%z5I{A`*`%HQ9@t*Ted*0!^!+D4E4(A=t zJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y)h_q?s|n6KoOd|yaNgm(!+D4E4(A=tJDhho z?{MDXyu*2i^A6{i-wB@QI`%iCkMCe=_qV=}iN*BYOl&OQ)5J9R&L*bK_ct-kzRQW_ z;(MJ~j=tlGa9{-^aw__--Z^-}f}J zaeZeK)8qS_m`>m2#Ps`KCzhA*cw+h1t`7BApW>)n@zt|&)j2)tpH9A{Kfm%(j`=Hh zoOd|yaNgm(!+D4E4(A=tJDhho?{MDXyu*2i^A6`7&O4lUwadN!YJ&3)=N-;FoOd|y zaNgm(!+D4E4(A=tJDhho?{MDXyu*3tcjDORyB^pv(f2;EW2NtaV8>A32f>c5z8iua zbA3+)I~M!S2zHG2{SoZg?Ykt{G2Qn{uw#Ag<^c6KHztH1AnU~zmO1dBiS2bYcOdm`HD@tqM&r|*wo`hAxK%ggsluzYJ*hx)5e zan!B&>e;yJoF4U0CtuQ^Uwpjhywjd{IPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d57~3 z=iTFGA73`^ zeBXSTp84+iGM)21^kw?zJL${vn(wDC%eQuQsK5FYN8O6Q^}NPa=k%z5I{A|R{K`k( z<*(dv-r>B%d57~3=N-;FoOd|yaNgm(!+D4E4(A=tJDhjh=kgBcUF~wOznb8@+dh|f zIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d57~3=bdfMv2VVY@ECSXobS3WJ66v3UY8w1 z=R2^=j;-^3*k#Au`EKm8WAS`XcG)p{zB9Y**gfB$U3N^L@6s+i*4J(hP=9lS;+QiO z-&~?`%`wtru98l3mGqmdl$ZAT4)2bu|9qc!S)BQ9@3Q#wJ>O;H&Ub#7>6!2UF4H;R z1zx6qz8AbKulbJfvV3b-hx)5ean!B&>e;yJoF4U0CtuQ^Uwpjhywjd{IPY-Y;k?6n zhw~2S9nL$PcR25G-r>B%d57~3=N-;FoOiX$z5Z%~^A6`7&O4lUIPY-Y;k?6nhw~2S z9nL$PcR25G-r>B%`DI)4%-F1F{y6q5S?gzd#_ToM`k9_RYrRU(q_vKvXVqHY(lczW zd+FJ>*2DD7+q)E{Yc*ZZCp7Be+XZ*@b zd+Sf?-@26Iv|gq7tz&82*0-dmbuZ~`JxuyrCsSUnpDEwk)uI0CQyg_GzIryUI;Thd z)5(|g=NBLEIq$UR9nL$PcR25G-r>B%d57~3=N-;FoOd|yaNgm(!+D4E4(DC%t)H29 z+Vc+Q9nL$PcR25G-r>B%d57~3=N-;FoOd|yaNgm(!}&F1?lw60xpup=ZO*-tW!voB zKU%ge&wZt3+xXmXTDI-aeW+#ogtsm$JKxC_brPv_W_s1pZkN$#-00y%k<3s#AQ0? zKI1a|bN_K!UUOe^S-!QaL;cmKIO^=w>qPLKMhlP~GF&y*J*?>XE~#w#}Yzw9WS1qiwn8A#LM5Cu!U7`APePo~yL4 z=y^-~ke;uzjpP7F9%<|Ii89({z-*b=R z^gN{aJtt}0o}Z+r=PK#!c}x0x4pUw|pDEwk)uI0CQyg_GzIryUI;Thd)5(|g=NBLE zIq$UR9nL$PcR25G-r>B%d57~3=N-;FoOd|yaNgm(!+D4E4(DC%a<9Ld;Jm|mhw~2S z9nL$PcR25G-r>B%d57~3=N-;FoOd|yaDMq6UOdN!+dR{?Xng(c@)dLW8f*E|uzYD- zzBDgixh!8fE?>DXUo~02YPEdTaQUk3@>TQYYdc!Lwy)*OyVKrv_{-~UzkUPD*KcF_ z`pqm~zoq5tH@1BJ_Lk+B%d57~3=N-;FoOd|yaNgm(!+D4E4(A=tJDhj5cON0|wC5epJDhho z?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhx2a6T%P-|k70eR!HE5B>r#r@dX>g{_oKHp zGihjjOWIoZlIGUKluPSm%CYq`1;hr`dcScUag-g-`dro{_0a4bt}GlHm*9SNBz^um-O>a zUild3UB0Uc&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d57~3=Uwe`ufLk$yu*2i z^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-p!cHb1iz#8E)I%T(e#Fw{y*QS&MDm*q0o)tBWs*V~unUb~vqU#*IxhQ(Lg##Qt5@GhOa zOF!?*OZ!}7-*NSy`wq+E%>9VvjsMJFUN-LBzgVVc?rSX5Irlr3>HnsWe#f%B=KjdC zd}~*S`m0ZI)UEhi&ud(DPLKMhlXvOooxJif)<^F7t|mC|aNgm(!+D4E4(A=tJDhho z?{MDXyu*2i^A6`7&O4lUwadN!YJ&3)=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{MDX zyu*1nWA3@$yf0(?JqMh3E|#4e&N~;&&Kc+Zlx63V^WMs`bIf_4W!bssyyvp)oOIrQ zS$3{E@5L-Thn@FjmYv(y?wq&&&V`HP9J%<;og3FVb$Xner_;H4`kkAXm-cx-Xvfum z-WysLXWl1T7JuF|S~l*yf3!@`yqC00=e)19O#i&cv@EZAziC;%wW~w@)u%Y>R($nr zTy;*5`lr*mdHS83%ZrcqtdHEa=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{MDXyu*2i z^A6`-?Q*Zbn&7;{d57~3=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{I$E)@*}w{oy&- zw%NKsw%OJTvMslckZrv6g>3t+J7k~GdPMdWty5$l()vX+##z_MKBsp3qWarM7014- z`1WayYhRZh`^~A$nSmh|bn2qQCWvaRYe3HyLs1XSbeY9mc&UaSMCQN!Y^ZR4tWdU%me-lhMVtL#|Xdmlmn-bWB;-s9Uo;?Mhi%f_Ae{+8*P z_W_sboc9Em>7Vxpm*q9@6)wxSc6F$~`V>dqim#rHtIp}+T{?M}e%{U8@|@qr`p7-s z)dc4q&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d580^_TERxJMDRg^A6`7&O4lU zIPY-Y;k?6nhw~2S9nL$PcR25G-r>BPG2;jL>a%?P?eZ0K`5J5a(y)AKTfQ_eU%4z_ zIWAwhFJCoTzG}66)o}T$?ebOg<;#oZYx`QhygTjQos{F{_44%_SiXK6%hzva`T8v_ zU%#>C>$kTouiksTeyiJl{f3vX-}dtLn_s@Rh2?7-Syq4Vc;-v`FYg}Q`M8{ScfN0X z-f7P}oOd|yaNgm(!+D4E4(A=tJDhho?{MDXyu*2i^R9Ne*I!L=-r>B%d57~3=N-;F zoOd|yaNgm(!+D4E4(A=tJACaAS99L+^m=A&uL)ewk}Y4)m@Qw=o-JR`q%B|1sx4p7 zuq|KDwk==Jye(hP!YyCV$Sq&b&MjZh)Gc4n+AZ%he%JM!>)E_*zn-_e^|?KVxqLn2 zciOuyaXk~b?bow{w?4P$KbNm(3zx5F4wtWI5tpxL6qm1O7niSR8ketU9ha|XAeXOa zBbTpdCYP^gDVMKjESIn6W|#Aer}vz9+Vc+Q9nL$PcR25G-r>B%d57~3=N-;FoOd|y zaNgm(+dh|fIPYrjx=P+@&%5n&d57~3=N-;FoOd|yaNgm(!+D4E4(A=tJDhho?{I## z-F5vzpRP;z+pbrL*>wzKb$x?|u6xkd^$?o7P9m4CpUAQ6Dsrz~P3o^!#ZklJ^R98# zJUzTfr{|y3&%5%{-gOE6yIvtq*D=KJ`i614?m zYb?*f*R_}B>zd5+b**Okx`wlSUE5i{uK6rq*MgR>YedV}wWHJzclGBT&O4lUIPY-Y;k?6nhw~2S9nL$P zcR25G-r>B%d57~3=U2zOx$d{;5w^{qSFz3ZKB;ZF_e^c$y?<)k@4Zy}gx*)RujoBi z`;gvmwQuRYSNojW?ThMfA5|RtuHxHgHm-eLdh7$!>A04D`^@sv-t#K@_dcmOy=N+Z z@1GjC_fqNUeN{SpkCp!3ZB%d57~3=N-;FoOd|yw$J4q&b!)sUM26e=iTZuk|SbYtg? zpZE8lzwOQ?Kjpu?v2)Cy`mh^2_xy%m`H#1cbJDN)z8gDNeZSYB%d580^cDdJIO>o}f zyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PcR0Uh%suwa{?qt-Oq_cq%Z`AxaG9RDpSVot+-F>- zf9^jn%WJ;3vMk@))uI0CQyg_GzIryUI;Thd(`l}fesdLh@$sJZk-PT1!+D4E4(A=t zJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y;k>I|?)6s_oOd|yaNgm(!+D4E4(A=tJDhho z?{MDXyu*2i^A6`7&M(`VZE&9PJJ+jQ7sxi-dO^13))BIex4w{VzjcS~6IzeRzM^%C z>_b|=$iAg@jqG!3w=b%{eN=JmyNYk0*0}a{>9NmDr+sGn?K8_ud+P$}Z*3g8i_hNWQhJL;cmKIO^=w>qPLKMh(>^o(`NhY3 z)<^Ez^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-r>B%d580^cDdJIO>o}fyu*2i z^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PcR0WN_RKkZFWX$S_qEMYdym`PwfDQtX?yS6 zT(|eZ&4GJQ+}ybL$IY30uiRX^_sz|*Yd8035D$ zUfO$KTmRnU7N_^S#qYguV0$h)~*iqSD)gjTk+Mian(6J z>Yq-&q(8s-c+YvKJ@0Vd;k?6nhw~2S9nL$PcR25G-r>B%d57~3=N-ES~<3Et=wx@llrSwan!K*ylY%FPY*BBY5Ph) z@5)Pi>%QvWda&ZOPOSK?A8Xv!m8GZkX6bAlTKZd`R$i@JE8p7Hq5kSq9Ca(cdN!^) zr$_zM$(Qu=PG0#K=Uu+53C=s5cR25G-r>B%d57~3=N-;FoOd|yaNgm(!+E!TF7I&O z)h_q?s|n7#?Q?mD^A6`7&O4lUIPY-Y;k?6nhw~2S9nL$PcR25G-q~KvIX!EH%|$(H zgw0WV{>t37=d#RcdtS?2x97ObfqTBo+_>ky%$a*0%v`$X#LTg4H}|f;IeBr+)r)Tq z-?--X>2Z#bPUi^ecaBhA+I!AQ|DL}Rr{}W7?|Cib_8b>IJ>NxV&wbI~^I-DoIWhUx zt`7BApW>)n@zt|&)j2)tpH9A{Kfm~R&v~ak?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6n zhw~2S9nL$PcR25A?>Vu&)1G%Y?{MDXyu*2i^A6`7&O4lUIPY-Y;k?6nhw~2S9nP=2 z?QWli(5Lrk{B7^oh}nBL#_D|>8hTHMw%*^Nx%YbH()&Jg>^&g4*RCe@SF7TvVe!?r zan(FMyhtbS(tmlkd1>!?75#g^Mx5Te+4$G{IL7Tg9eR3yhtA&Xp}+TiaRY0l~ zxP6?H{_ywT*tzO+Uw7jf@4=&Adt>LewL9mnzjNW@I7cqNbLYl&PMsd-=IL~9o_^=% z<)!^uues%@|C9gajm3G!i(ayt#s8B(a%1EE*!#S6+v)l3=iQjjCx6+E>Hn(N-&kHR z`_3E7w{~@?zxotM-HNZCjjPV-QU7%ECH?uu$9v8@?Rkgu4(A=tJDhho?{MDXyu*2i z^A6`7&O4lUIPY-Y;k?6nSG(NnuO>L}aNgm(!+D4E4(A=tJDhho?{MDXyu*2i^A6`7 z&O4l6Gv>}YzvlyP_p{7JyZ>d5+I=x|*Y1~@({>-tT(|pc=D^)|GdJ#joH=v%>CC0O ze`k(eySaD$&B=>nu3miS2#srQpC0E3>2w~Ke&-0~rM>%K`gdPUoOfRL@5JvunsK|o zMo;(M=7l78n1^5Ww?=biSv!+D4E z4(A=tJDhho?{MDXyu*2i^A6`7&O4lUIPbR4_Pbxd?T*o(`ybxevHNS@_r{Ltec#-%zIJnf`kNaR z$DE<~<`Ru-j*%X7k93-=q~BbnytMaybNziITfX8v_nW_MS^RJRtZ!d7?w7sm#`OHg ztG;8~>3qsB-kAP>^#QkUn#-&2o6EO$b*R7k6i3~Pubz#o&goJAbegNAKfm~R&-%z+ zd*0!^!+D4E4(A=tJDhho?{MDXyu*2i^A6`7&O4lUIPY-Y)!z5b^GB%d57~3=N-;FoOd|C{PrCC`W~@kV&5rttnB;6j-h?m*s*oi6?c5z zV{YF;b}a7u$d1u{H`%ef?XpCL4$BtbDtWl&F`*SZAI#>`C8-f(U8Y_sX@XgxitnKsX`{A#wjKj>Hz0S;> zcF&_bm>9?{tUFkDuj9jrT8cd+hY-NCxEoUvPkif( ztUFkDuj9jrT8ca}4D>yr~$cd+hY-NCwpbqDJX)*Y-nSa-1QVBNvG zgLMb%4%Qv4ub<}K4zU+d$NhqT>pnu8?l1J^zC#S|N5tknMa=GBjKzJ8F}mL|cFW0$ z^~sg(kVD%ixAsfUjR$wei96%3+*RYE-2H<3?jyA0{zCiiJM`;*L_F?O#OeM;{O)Uv z%l(e=T23CUPkwBNyxBhav|sXUJmlXv@nZayyB%W9Z_T>XJ2`=M2kQ>j9jrT8cd+hY z-NCwpbqDJX)*Y-nSa-1QVBNvGv)uhoca-Z6)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzH z?qJ=)x`XxQyz{;vb-W+Qzx6&LZF>KZzPztU4Bl@fHt$0cv-c+%i}x)VqxUlzyXEA> z`sB)X$f50%Tl*#F#)Avv#GUcu&T&!h{Xpt_pOALEe@Oe@SEOI>HxiHcA&Jxblf>_R zOUC8>OvYkif(tUFkDujo#o!o)E(uzgLMb%4%Qv4J6LzH?qJ=)x`TBG>kif( ztUFkDu@t0~7rwI`PQZ{;`%=H5;@euBB@Q;w@( z?gf?OEtq>m@jT*nYx#}-`299)kjxE^D0J@()_C&6{Dg6kXx*YhH{&UtV> zkE%M={0gq!Wx4xB?K;ZqW1y;2&FkR$mGwmS7BUuY|Xl(Tz9bUVBNvGgLMb%4%Qv4JD9QK4%Qv4J6LzH z?qJ=)x`TBG>&|kkif(tUFkDuj9jrT8cd+hY-NCwp_2s-P z&$*f~b;`4nVE%1+eiTfb<+)NYeU;};!NgFWLj@CCc|H|P%;mXNFk>mtvw|68dCnEg z*exd~)+blCLk?}9+}bZWHy+#>C+>_NcaDql@@y;mrG9zd7fd_lIbbmDm*<1Q^jn@A z1`|(to)}D=j9jrT8cd+hY-NCwpbqDJX)*Y-nSa-1QVBJ~H*sV`aVBNvGgLMb% z4%Qv4J6LzH?qJ=)x`TBG>kif(tUFkDu^JX6?zsmnXUJZtE^N#|gmL45w(%Yu0} zan*uLf_Y}~`gIov^DJY{P8S99jAO&SE)3?`$CN8B2_ka6-1$oP2%kif(tUFkDuj9jrT8cd+hY-NCxEoUvP< zoWQz+bqDJX)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzH?qGeDK7-49M@^VIv)(!+n16fR zEr$iu=F^-1A(*~Sdf@P2Vpx0nAA^Z)Mx7};M zVB*iDZkW1vlrvt-$%FODkL{2*+b5s)OP-B~{2M1;j30N5 zOOLYd^iED--NCwpbqDJX)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzH?ks2Q)+Z;h?qJ=) zx`TBG>kif(tUFkDuj9jrT8ccss`)+_r$95Y-4mbE3AYs0d(1ar+; z*5P2TCCmC8%r$0Nw}ZL%EbDnN*Q8~g59V66tpCAW!vvwr1T?t~*$Fuj9jrT8cd+hY-NCwpbqDJ%>eTLF-C54qtxry1-9??+9jrT8cd+hY-NCwp zbqDJX)*Y-nSa-1QVBNvGgZ1^(ysPdrP{;cc{9Er=(5Ck>=*#;X#Nd4oV)K3oF?*kc zv3UQ4F?wHxv0F|~tWU0NhaB2I?(CPG8xQV`llf)*mAh(OlzU%-`rfag9q(h%zV|oi z*ZUsCj9jrT8cd+hY-NCwpbqDJX)*Y-nSYOOLuJw*z_Ok!NTmydHW7;z?*M_%laon>o z*Nktk^H4C?k_(=CEtqS}N&ovUm}}4R`z+l;eXdClJYcn8u2oNXbnRfSVc%Y7yvw*XG90wRwjvE{}25<-a1fy8g~^-A-`besJAy za2?ODsb9w#T*n_=k1MzyZ*ZN5;5t9Sb>5==I-kLHo`dWB2iIOAetqGwHS3OY-NCwp zbqDJX)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzH?qJ=uD*sih`a8qAgLMb%4%Qv4J6LzH z?qJ=)x`TBG>kif(tUFkDuj#rBSJ;<;|$ ziixw^zbhvGrS7Phan0#bG2^wIJXoLn*baHKee!9)kif(tUFkDuj9jrT8cd+hY-NE`QeFppeAL{sBApWi23!+WGBSc?*Ux*m|?hvt+_kQCV zhnUOzz`=~g?-wyfziY(UEhi_|Cs(#Z4sD;@+Aldb9^4rx?u;LIj*D`?3q*at7eqUL zM~L?Qz7YNT-67&B?`g+ah_k%E9ZdXwzld@9T_eV8IeD-?`LP}HX8YvRe#x`(kbmRE zi}B-*ap_Uko!-d_tUFkDuj9jrT8cd+hY-NCwpbqDJX)}7^y-TLGN z)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzH?qJ=)x`TBG>#p<}dtcdW=|A?waxNXrURka$ zg4sjMbw@CJYq=f?X3s6xDZ%W;<@zOz!cs^l}{(%wBIf=K$8{+`x7? zXRv+FCG3}T4CCQk#W*=vF@DZf92e!~x-a^re!2Durk!$~7)<-+`Z1V(%XMWi@s#V$ zm}|sYu0w-~zg(XNGp=&o8q9btClA&qKej{OY@dAEFL^c|@^74+s~A7$DvS${t(iKE zopRm5x`TBG>kif(tUFkDuj9jrT8cd+hY-C54qtxry1-NCwpbqDJX z)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzHzL;yw!E$Z6E6m({_2H9(nX_N+P%(4)-B(YH za^`rye^$)g-+kSRSrZnS`j4o?TJhz8idjQC-&S$yqkQ+WV%8kXS&OXC8f81IUAE7f zX1}a;#>1LvoUEC~&zkADC_nw0YK+uBaCXJCbNtb#M9j2*(=!#*?+@)yjdJ4I`GAUv z^S}!$CjQ3V6*I0!9;}%0T23CUPkwBNyxBhav|sXUJmlXv@nZb?!eeXJ9p$=%bqDJX z)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzH?qJ=)y0e_ITc4c3x`TBG>kif(tUFkDuj9jrT8cd+hYeU(0A4wmn3b%dFl<=aic%-Qlit6=7G`OZ}^bG&^2Dww%n zzKa#inoz!%70g;uzM~b)8dAQm70lXFzPlC7nqxU@k@Z=lY=^bW_F2>Hm$lA#STl{2 zHPiT6GaVP@{{1-W`*-DNr+k+z;-UTWy|Q5XE#ENkif(tUFkDuj9jrT8cd+hY-NCwpbqDJX)*Y-n zSa-1QV0|&yxVP!Pz&%g*3+{!wk8qFF{e^p{?mOI5bwA=>tNRr9VBNpCH|xH}JzMuX z?&Vs}Jznc`@7H#?Cv5xNi?(0xAsY|(mW`9=1;)?4Xvaml`vvvgM`*|Wh4$Td=-2&- zc-*Im)BTJ1-PahG`yJ!8oIF^c{MZh8vwiYuzvS6?$iH#o#rXAw$JVSn%5?|p4%Qv4 zJ6LzH?qJ=)x`TBG>kif(tUFkDukif(tUFkDu-_;3b5B==OLxR~`%XfH! z*>lVHd4k!C%XfQ%*`v$%e1h4#%XfZ)OCNmyCz!q7a?Sy)&$)r^aL!=+oJ-g*=NQJr zxr%Xeu44S0t2i#o%lD3=U+S0dAO+J-`94xG?U(N+1=DZ&o>DOJlkif(tUFkDuj9jrT8cd+hY z-NCwpbqDJX)*Y-nSYM^jV4vSn$LC-CTc3;3rq9dh%jams;PW+N^SK)_`#g@Z_?(V0 z`uvWuTTV`_Pp)i-9NIp)wO?{>Jh(GX+!;Uae12D#$Mdhcemobe+X=4Q53c(SuH%X4 zZgrf&b^O8gxPt5P2G@BAuJaRI=PlZ=^BG*{Ik?V$aP1}H#~r@(DCj9jrT8cd+hY-NCwpbqDLNRe3zW(;elygLMb%4%Qv4J6LzH?qJ=) zx`TBG>kif(tUFkDu% zN6Z&i%vj2KSClixay}N!*e#Eo)b+`g?T|y;C%5)X&W#5b#)-RfP7>|o&T&y*&Of7^ z`sKVdn0CtfYB24W^VneeE$6qv#8b|DgNd`84+j%}IZqB|T;=>ZnDJUp9;{D(Y=^wr zKKZm?@@zch-#Bq+{J3LWdX%Zd*!50MVBNvGgLMb%4%Qv4J6LzH?qJ=)x`TBG>kif( ztUFkDuj9jrT8cd+hY-NCwpbqDJX)*Y-nSa+q*`keFQ zCd|2L`P(bOoTHY%y%Nm1Yxz4h!JO01Kl-y^&UMS*wF%}Nxct4FV9t%p-@ysyoVomc zoZxbd@ON{9Imfn~b8qW&PHsD#tJ^-;2=>dlz436)Z=77m8Gm(+P>qH1^0#uLU+R~? z9~4YGkif(tUFkDuIKH3Ey&d0M=AMu5GjlJ<_nf&$3m#Eg@BV#Z%R1FFVFx$hNI-}jAa$M=wF-}jU0 z*Y}o*$M>0u)AyW--}j#xm+wV0UdzdY^~sOzkT=^WpY}_hjfeajCti$SUwCZIx}#io zuj9jrT8cd+hY-NCwpbqDJX)*Y-nSa+8DUbOBg*Bz`oSa-1QVBNvG zgLMb%4%Qv4J6LzH?qJ=)x`TBG>+7fet~xhkZhD@^ob~*Tx$JozbKLVi=Dz2FtO=eU zvR0J)cyZpv8shmRYm4WZtT~pm7FnM)%63@0Y@apLep%~`r@qG(ebx6ZgX?=@S?+ln z^*w*19nb4%-}62C^*oSxJU=8(&l`!~^GU|#c_!nvoIF^c{MZh8vwiYuzvS6?$iH#o z#rW%cVsWn3nstX?-NCwxW1w~i>kif(tUFkDuj9jrT8cTuP8cb+Hf z&T`K)b!R)|D(ckkVBNvGgLMb%4%Qv4J6LzH?qJ=)x`TBG>kif(tS|Sw@*ZOxpUlnj zE?h8kw!8}$%v>(-4F)sE%lm}E%>DA7VK8e#dH*n&wW7S27|a?{-d7A}Z7J_D2D9c^ z&RS%B)+pOy?XrE=H2Y<(GalAJ<7CY=e%4IKMR|E|Gy0`|d7m?wcFKF6!L(oA{|u(z z@?K~#@s#&PgNd`eM;c80<^9rN##P=s4Q9NSlLzaQAKM{swog9ompmH}`8Q6y7(Z(! zkif(tUFkDuj9jrT8cd+hY-NCwpbqDJX)*Y-nSa-1QV0}67%Ki5Idq9Kc?-$I!9k=!#!L)gL z|6d2w*JG2m4r*k-@5c`z|ge14N)#xm}sje;5Db_Z0<*exd~)+blCLk?}9 z+}bZWHy+#>C+>_NcaDql2R8m=#6bPa7dtkXc4qwhgy3j@|C591_o_qA2qvCm|8{mT zabEQIbAyTh@{Z>PGp=7us+jRwP9CgJer$)l*?#1+?w33p5BWDv+!;Ua7?&Pp>M(Y_ zlM`5Xuj9jrT8cd+hY-NCwpbqDJX)*Y-n%Ne`%$qB4GSa-1QVBNvG zgLMb%4%Qv4J6LzH?qJ=)x`TBG>kihP=b5GNSgY9+eZP^t()S+OLwz5Tz18<5*>in= zlD*jXD%qob-;%xC_b}PheLs`E-g3?Xtk1cD?QqUu`<$!TFXt-8!?}lXa-M1YoU1r4 z%6-3)`o8x_JH8J|`@SbhzrH_7Jib>+oW5^K{Jw|DxO_j8@mfwEtWSPyhrHQ7`Ltj1 zY&_)OIPqfqoU1S{Jho=tQLZ~!cd+hY-NCwpbqDJX)*Y-nSa-1QVBNvGgLMb%F6z|o zVBJ~n`Fy(!j&kmuu6T0A+*5sYwTijddeU13+!MBa?iJfF_mGW;d(pdQYsHM$a`Iq(@?$&X z&GyNs{gP+nA^*mS7vt9#9$T~SDAygVJ6LzH?qJ=)x`TBG>kif(tUFkDujo#l+(`s4)G9jrT8cd+hY-NCwpbqDJX)*Y-nSa-1QVBNvGgLMb%tMnOrUzzi9 zjIk${YuI4+%5q&F%pO{M*goeH_RBej@o=tUoSdr|Kj$iri}G^K9x+hA+%F2IopOIBnD)zk zn_&9=p?)u#c*=dAC@0Qx|0kIE%YC6>#^rlrjMsAVV14pqJLJvw$*292XX7FN#)%i> z=Ujzx;juOAj&j|>x`TBG>kif(tUFkDuj9jrT8cd+hY-C54qtxry1 z-NCwpbqDJX)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzHzLKh ziapf7d&S=B-@{_h_3vb{7yI|K*rWZsTI}8ay)E{1{|*;>z2%$(Sf6tP+u@wS_BmIv zU(PX%hjS0(2wAsPEsmq8n`fl?qJkif(tUFkD zu#r$ILE7#^R*Vq$J`Q7h=*(=Mpn}XRx%XhAV*;~u^uY%cg%XhJY*^A5f zvVz&8%XhSb*}Kd4wSr53e0M9Dz20)p0j$rtf$eb4VEdd)*e~Z8#>2UaadNI={G6*e zF3QVy#-d;9mv3za(@yy=SupLF@0A79Z~2Z{F!7Y{n*|eR`R-XT@t5zR1v9SlowQ)a zYdLwaKKZd7@@D(w(|*ab@sNMx#EbFk3y-Z?ca-Z6)*Y-nSa-1QVBNvGgLMb%4%Qv4 zJ6LzH?qJ=)x`TBG>&|kkif(tUFkDuj9jrT8cd+hY-NCwp z^;Pie0j72cm@4e`DuYm4_YS#vCB zEwX;BQFS}4UAE7fX}_#>#>1Lvoa}4H&zkADDEEFK^}SC>JKjHx_UrqK^y~db;_*Ht zae9A}_`Pq*xV)dqcr7On)+ax%ywo{fk68z)|jpEZ+l;juOAj&j|>x`TBG z>kif(tUFkDuj9jrT8cTuNy2kXvq?`P_ca@|E8j*XH-Sa-1QVBNvG zgLMb%4%Qv4J6LzH?qJ=)x`TBG>x;R@9P~LCbJOQv%vqm{F_(Q_#vJ!K8gt+0Ype-A zcVn&ac^qqq&*@lOe16B8V>xS)^;x5AhqcT0S<~#7wa$20GmVoq)A(649T(+3|DwLn z#c0RpWwh^eH2U@V8u9qtjW~TCNBlmgV_ZJJW4xA=2kVm`+aYhZPd@FJJR1-BH%`15 zzrOI;nsrCH?qJ=)x`TBG>kif(tUFkDuj9jrT8cd+g(_xYXfDAygV zJ6LzH?qJ=)x`TBG>kif(tUFkDuj z9jrT8cd+hY-NCwpbqDJX)}7`44oG*D>kif(tUFkDuj9jrT8cd+hY z-NCwp^~GGPuJzVv!t9AZPFORTz4Bkz|00+@^p%a)31)A-wA;GD?72HkUN4xvc=PG& z2eU_?^Uwyt?A_b1wqY=P`lR1f%wBIf=K$8{+`x7?XRv+FRqU5@4CCS4!#FvgH2&(^ zyc!qfoja`_F;Kt#t*Zvp&Vbn~2h;w7%T@}e-~D!5F_?G`-Fbyz;#}f_<%5a8)1nnK zt_LP97v+rCa`Iq(@?$&X&GyNs{gP+nA^*mS7vt9#9$T~SDAygVJ6LzH?qJ=)x`TBG z>kif(tUFkDuj z9jrT8cd+hY-NE`|uCe!(>xBl)o>zZKp?sB~oT>9WTD44z8a?Sy)&$)r^aL!=+oJ-g*=NQJrxrcFbu44T4wR!YK zdAaTjrhd5|45poOofsVLPuf11e#>=bF!7Z4XM%~dT!#h|f4M#lW?bdEHJI^QP9CgJ zer$)l*?#1+?w33p5BWDvycoZ}@YtGlN4f4`-NCwpbqDJX)*Y-nSa-1QVBNvGgLMb% z4%Qv4J6LzH?ks2Q)+Z;h?qJ=)x`TBG>kif(tUFkDuj9jrT8U!~8O zgXLRr9bx9Ce;=GV>)#D$F8lYyndAPQapt~%f1EX;e5WqjVXY|NuM1`k@$Z4{N4zvacCGYo_C(+`kV_ef~x^Fkigk)T!OUy0e_ITc4c3x{Ers zJ6LzH?qJ=)x`TBG>kif(tUFkDuxk}AecE@-VF$5 zE|>Qxf|=vx{fc1betGXAm^Goij}gpTQQp%CW(_ItZv>bAc&{UvHOF$+BI~n8*$!)$ z?X#xYFKeCgux1)3Yo_tDW;!m)%X=)*FZIj&Ey1)?-g^nA{qjCcF#VSIWP*vOygw66 zoaMcmVB#1*?7pmapJ}J^@YdQtUJne2kQ>j z9jrT8cd+hY-NCwpbqDJX)*Y-nSa-1QVBNvGgLP*)W4AszfprJ#4%Qv4J6LzH?qJ=) zx`TBG>kif(tUFkDuw%pZC-yb znsNEP=(sko%gKZF$&c-jH`^zl_Di0Phx{8SUW}h>bH;_o)~q|qbqDJX)*Y-nSa-1Q zVBNvGgLMb%4%Qv4J6LzH?qJ=)x`TCRIb*jzIe~Qt>kif(tUFkDuj z9jrT8cd+hY-NE`|uCe!(>$^C2VoyA!es0cQ>GNpzP@hw?xBC2=J=f>j?8QFsW{>tc zID5Cx$Jx_;Zq8nBIp+Y@=iI<{IA^eZ&Q_&A7@-XH)p(-lLzaQAKM{swog9ompmH}`8Q6y7{9*o z*qU`mx$a=y!McNW2kQ>j9jrT8cd+hY-NCwpbqDJX)*Y<7s8hRxb!WNH&2>k)?xIfZ z4%Qv4J6LzH?qJ=)x`TBG>kif(tUFkDuo?743)vRRa~7q7H;#q7}={i|a3?z?WSxb)GnbGM4w>n-OT!1|mU z*be6mw$HhQ{c?_BJe;c-C+8~0&$)`@qP$m+jU!I#zqED5wDaWXjiQ|P|8r`^^t;9y z6%)_ocQ%YV#Q9RMii!W|8!Kj9|Gc7N#%nowus->*9r9-Tc>kE&q zS$CA{4%Qv4J6LzH?qJ=)x`TBG>kif(tUFkDunx`TBG>kif(tUFkDuj9jrT8cTuNy2kXvq+*u!Y zuj9jrT8cd+hY-NE{5HSc0Qr;g8^`L{lgrp?dl z=jQa~^J`-8xi+!+yqlPP4$fG7KF%0@ZqC>(Cnwe?SGGeAZ69~`OU{i4cgD&2r1978 zVqBE_+?o15kER`;Q`5fBuj$w4+Qj4YZsPPgIPv>@oN@Wwobg&t9;{D(Y=^wrKKZm? z@@zch-#GDN{I$DS^INm-^iED--NCwpbqDJX)*Y-nSa-1QVBNvGgLMb%4%Qv4yQovU zgLP-Q&&_p5x$dG)?GDx*tUFkDuj9jrT8cd+hY-NE`|-qp|0JHlK8 zmbE3AYeTP_xMuWvifc))v$)3e`ipB%ugkb5^?HqKRj=c?hV}Z6Yg@~?=CwZ8!nVUT zvh8#2Y`ut0@z?J>#8@cz`iS~oH_?vQQ?&1O7X5ntMLb@Y5vSK{#P4++ zkif(tUFkDupR_1t~*$Fuj9jrT8cd+hY-NCwp zbqDJX)|dO;S}T7X$0u{Md^0VWIa|J&7R+2O-|rd z_v?aLL&|sUf>~S2_wIsOb1Y{qvOa5+?XY&)K5M4^vep?7YoKwmuNgmUrsJZ#eBUqn zrGEMDUoh>I?*RtW{`{jq3#Q-l{lH-2Dc=Mq-ysZUT;={%{_Q|LHl4s)~|Hg?I<7dreTzG8Fx}#iouj9jrT8cd+hY-NCwp zbqDJX)?L)8-NCxEoUvP*9r9-TkTqn79KyPTbqDJX)*Y-nSa-1Q zVBNvGgLMb%4%Qv4J6K=LJMOVO*I|vg4&vTRhs!GFp3JA8Rm{DbMgFj6)Zre^R)Z?$ z-cI+0*NSrP`Mk4d#oP<}^z4e`9#NNyOMm5eofXGDrMjGZP1ffgl*{ubV|kaJ9YJniRa&|kkif(tUFkDuj9jrT8cd+hY-NCwp^;P-|{^fEz>ysbbA#b)%KJAx08xQ$6PP`aD?iiOIW!>qWoWQz+bqDJX)*Y-nSa-1QVBNvG zgLMb%4%Qv4J6LzH?qJkif(tUFkDuj9jrT8 zcd+hCpK-0{@yRuy$1T@}9?x7edYp4D>G97srt^YpPv;BQq|PI*Rh?g4!#eM{wzZsV zUh8u$Y&%>d+dkLM_RBT3@o=qeoLrk5KiB4ti*k=!>U%uXj>kFed;HU{^MZJsFU09Q zB7Wx=<8t0HUdzdY^~sOzkT=^WpY}_hjfeajCti%7YjfvXYt|ipbqDJX)*Y-nSa-1Q zVBNvGgLMb%4%Qv4J6LzH?qJ=)x`TCRx${nUlbB1{g8g!CZ#*9r9-Tc z>kE&qS$CA{4%Qv4J6LzH?qJ=)x`TBG>kif(tUFkDukif(tUFkDuj9jrT8U(7r9zB1?I_+d{h-zp4duPonh z3}z24-*pUTZ!O<@3}(+Q-+>HfFD~DQjC*?Q(dE05!R+1Tdy>KI>E%0kif(tUFkDuj9jvd?XUsw0r($mUo)vS}_pg}CzL&)u_kAtq zzVC6dCis3AYlZK9v4;3Q7;B5~iLvHb&RS%B)+pOy?XrE=O#5Z6GalAJ<78hme%4IK zMY-=;QQ!BkXvg=mXy5m>=-2nSh{yN4h|~AJh~M|Y7?x`TBG>kif(tUFkDuj9jrT8cTuNy z2kXvq-xJdv<+_VHwL4gMuj9jrT8cd+hY-NCwpbqDLqc~`!7*MzB4 zzL^%xzb)TP3#QHTeYs%zD&L(8CWi7ox?o}}->C~G=JNfzV8&9uYZuHI%lGbr8N21= z#QNmQcF3XapnVbqDJX)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzH?xIfZ4%VIJjNSU=1lC>DsolZ4 zgLMb%4%Qv4J6LzH?qJ=)x`TBG>kif(tUFkDKh3)};v9)O<(_RY|F+z-4W`X<4I z%6;!(Vkq~+gNd!&Cl4m(a{oM-v6TDj!HluoZx3edmXj0flPlXHhqjM9`z7bbgFEA7 zei?t|t{NBR<@rMNOa1cPA((c`^N3*DFV880>9;(;2qvELTqBq`%kz$4;y=1e#f+;w zABl3tYdLwaKKZd7@@D(w(|*ab@sNMx#EbD)?$(HNt=6nNy^|AIcd+hY-NCwpbqDJX z)*Y-nSa-1QVBNvGgLMb%F6z|oVBJ~H*sV`aVBJNX+8wMrSa-1QVBNvGgLMb%4%Qv4 zJ6LzH?qJ=)x`Xw_yyG6r{!3ln5$4`Y`CDVb+>7ron`INu!7R_MO3+A4Z<=ktsKKGz(hkH}D&pj*qJ?yGr`YnHVFPM1B-{T7=&hmHq zf{DNU{k~wvRsODDFypnHJXoLn*baHKee!9)kif(tUFkDuj9jrT8cd+hY-NE{D-j(-NVy&i5c?UI^e_P(m4W`ZVzHTsmmG^jqiJ`pT8%%8F zz29JBF7E>eGnVq6a4=&m?+*tvcFW0$^~sg(kVD%ixAsfUjR$wei96%Ro#Udsye}R7 zQop=2985c(9eGGF?U(nigXy=tj~z@rkif(tUFkDmNRzilM`5Xuj9jrT8cd+hY-NCwpbqDJX)*Y-n<{f*V z`vQBS`vrTY`v`le`wM%k`wn}q`w@Gw`xJY$`xkq+`x<+?`yG3|<(vappK}A-;he$t zIaje?&M}OKa~0#{eA4(iS8-gFyI)Y>eS~)0UufTbhko6Uh{t`3INiU9-+hg7x!*Bf z%gKZF$&c-jH`^zl_Di0Phx{8SUW{K~cx=tOqg;2e?qJ=)x`TBG>kif(tUFkDujUDT=F!Md~D{Z4n3>n`fl?qJ=)x`TBG>kif(tUFkDuj z9jvcb`(3=p$lUb(M&_*VJu;VlACfuldy>q3-=Abn@V&}dGwbh(v4;2_CTolDXR_v4 z9&2V@pEb&MSi5YWHO+om>x_pr(>Pf(jlW(qV_cN`ek1jL?~!(VA2Qmn-;<Zx@v;LkK@%tVo{%{_9LHlzvS6?$iH#o#rW$rGu}mP&AP*{ z?qJ=)x`TBG>kif(tUFkDuj9jrT8cd+g(_x()WQLZ~!cd+hY-NCwp zbqDJX)*Y-nSa-1QVBNvGgLMb%4%V0Zo$oO+H+{d6IqQ3m%w^w)WRCluBy->QCs`AG zuadRG_bpjN%6*0*^u^lZ`x_pr&^YV+C(&1ZZ5~Xy z?>ADPcl?Nlc6=X__I*#1etmzEc*=dAs85`}Z%O>Vhsn5nKa=rVP9CgJer$)l**^KS zU-E1`kif(tUFkDu&|kn`fl?qJ=)x`TBG>kif(tUFkDuj9jq^oJ)Y$~ zw!*mB7kI|EL5~T+Jo{UD={JLUCOC5McY=9VxXD)U1@jE?u0d0RdA4{(V`?zZ99QT# zJ(y>acWyi*xb#={sfu}aX*tg{tkif(tUFkDuj9jrT8ca}4D>yr~$cd+hY-NCwpbqDJX)*Y-nSa-1QVBNvGgLMb%4%Qv4 zuhM6*-04@oPH0J`29{M z$DQBLY|XmUJ2`=M2kQ>j9jrT8cd+hY z-NCwpbqDJX)*Y-nSa-1QVBNvGv)u1z>W*^V!McNW2kQ>j9jrT8cd+hY-NCwpbqDJX z)*Y-nSa-0#N}u&PXSLsPF6w^4IjZ{z=dSKAoYT7RaIWiq#5u706z9h7Uz{_$uW>Hz ze#bes<(zw4pL25C;auJJIfu7j&h3qdbAIFG8o~IhYlLcCl)GP0-+hF3++U*odf%a6 z_aowQpCV58FXDG!V_fccjMsAVV14pqJLJvwBcFA@kif(tUFkDuE>#?PARxF|38Iip|dm;0Z=v{UYj2Gf4IUm8rmkif(tUFkDuj9jrT8cd+hY-NCwpbqDLta>j0basulP)*Y-nSa-1QVBNvGgLMb%4%Qv4J6LzH z?qJ=)x`Xw#=)lFAzuxiXUH&xTrRK$JFV_5W&5Dn@y>0WY@h?UBd&{f%um+apukHh**bh-mZPZQ3?pzj;i=dC!_{o1b4kGV1*M ztG3Ovm#ONU{>Y-ubN@0r>U3JZZFAaLBcjg#R#~h$wA=7#XZm4_Hdp;U^@tqRp!g8WDBgx}4{SDm_8^RdoVouyZ7mwkPFP21)Jr@k0T)Xtx=hMY=>}T$^c)A$Bb-O$U*8D~L%;AYkFP=_s z|K_J-W`hpx)5ZM*+U2p)wPo@2xc*M<@>n`;>&5dJc>Kb4dCbiDVot*~YSyc>8_tCX zp8BTY9C>uW*A3^++!w!UIH$(W{<7g*JLaG-8_vPT>t8gSn-Bfxi-vRd$TPoaxJFU# z9H+i>pLSfMXx}x8eqE!8$2E#LU89KKHHvY$MzvjjZk8Xg>33Ow?``H~JKwDJeYU^O zr{8D4H{be0#MYt*f`&u+LzJ@@4|4cDmakD1+Y zjk@zsvm35aTkcejt9p&v`Ow)7*QoWs`nus7^@}lIH(aA8ojtqZ8a4LauNtmVmk$2A z;Tko1$n1t|)Z;sR)o_h^Vb0eL*QgIRozrlQ8n)tB4cDmdH+<7@jrw<=IStpSN6-JN z;TkpJgxL+(sDEw$ZPq#SsIMEYQFH$>r{Nma?x}CHuNQlK({PRY=KOE7&bsT(&6v+y zZ%)HCYSoM9W?##mJ~zjH_KpM9&Z&~%7oU{8Zcsu7Z<*rfGca5SQ*C^U|jiO)I zDB^LAB2L#R;&+W=T&_`H-9I(UcY0=8*5CH|>DkV-zB97@WiI?6`@MLbnHkTT-DYN- zJI03tU87q2f?cCv*C^OE3U-b9 zx%G$6os!4fewR(j7iz`2#oX6W5Bj3y8dE=>* zbABz?`Mo?omp<~noEM`Po|5zQ>60hrv3=Se@8$e@>bFyJzCSSh-JBQwuX-=%>G)@+ z-Tg0xnuE3IZt2sdUCECe;xKyont?ml=J}$XllXKmew)oVnv+SU$8S~%Eb0*iQ#g>|uea-)2YL5Lcznz+OI?kAuG2ge=w9Mfu zQ7k7`cO9PT@5YI@xE+Zj3bXCIlKE-t-vY90eCAN@h* zu=h^W)9E7ZrsgrT;m#kVi`6fkmdD02cg#qS>)kXpkEJIrnV!eMo-0kuW9GFEV{(mp z@v~7m7cP2ZWX_SxUm1~eXTtl#b51?7!tk7HJDoNx=ipsm4b8cE$)iJa&i?YIp*fc+ zca5UHYZUFcM$x`&6#cqJ5szyWak@qkziSlZa*cX_tFc+W;eIb={k0EzIoo-4mshg= zAKJf~{hmDF)r@D!&BkS%>z_L=<3Ii8aXBu^U8AV)8bv# zFU~rDR32~b4==}+d+wQ|a(*pXW@H|p^Jb06dGS=2Q8`Z^`EGa~+ef`NBInn`lSbuy zzxnsWb6#{`ab(WZ=l2_(>&AWC4$t{@Uayfk-wz!#I@hSn?;4)-wEyL!a@{!iurXQZ zfb&M=e4lXD=v;rMy*?)U>fRWc>&B~hjmbLme={~?{{8NwbN%_c>)7n;lk3Ok*nc-^ zOxD@-?3Xg;8~TpT9Jc+-OW9Z3_AlqycX@DZy7=RNU(T5KJMiVq;r6GDO^<6|{Ys9# z=k_nBi&Hy{&0}DZPhQC!-ZQcstF_ZF?--NE%nGAlNf(QEcqxyKAJ%&%JubKA*gTdV zTKeTY2DW*4Y#uX1x)07ZYQRNF!oZv(XC5;k=g#wI^v^kU+k^dbu5Iu`-<*S2 zb?%#U^OPO>=A2z;&AvI8DR+&czH1cixJJ>wYZU#uMiGx|6mhyn5x;8`<8qC9dC22g zzQUVNWc{TlKbh?`$3B(qe|-1T+3yj%J(Kawedd{rbNRNgdrxANdT-q!0eD38xeZyuD# z)t`1Bl*jh9JqG4+c-Rtya$X#__@F%AzMU~3kLN`e49xlUX^#PUe13TDfSeZ(uRSQ| z>225c&trSPKM%mC}A^R(}qgL2)t;e~!Vzy9{CfjQrIJ92QY zKWA>(Kj&$;inwRfSm8ouQ)i@pK*VEJo~!-fPuMgG&g)a>wNO+;~Der z;|AsWGj)?Evah#Sey>E!hv&tqnxBc4td zv%5W!$HvElo=T7Ndq1AXQkQN|<}t9=c2DFn(`WPUxkhzgvRlrDKYrac=g2Xi-jj2u z-~79CPIcbq?wo5YTz^;2!GA7$SI*5Nhu@iVc9}kR=3J)SHH!MKQMBV4Mfz4`lmqZuDUGyZ0*(W;`?Zdnn^v zaN9!}f2Y0=<+vz!jiSD56z#Z1(Y|XG{kldGk82chx<(PdYgB7ruxk|T8U?#X!LCt1 zxBdX;|)&Ut#>{rBd&vDsPOv(AQh-jnma-$UJU{b_#H zJ^MQEovyiV^m?Lu)_MEb9vSmi$92o~=ar{>WM3m5>ycyMWM22I)3(cf8S_8J_Q)K* zf60B>*ZUjZpJQL;`5x(F+oAVo%gL16aPG1__J&&3H&3qtTOyBIjJT~6k{ekrO>CQd!Sh{4h`|}uB>ct*;%y8WP z?|>)bxfpZ&;cY8s?q4_S@hE3a`1sU{St~9YF*wRuLk{|GP%vxDeM?r%n)Ba92Szz- z(Q%*l4`z)zcx=Bc-=kOGVCw(SrB5*JEPQ?MVA?;ld#_;n-C*2f!Nl{_CKVIsD*by# zIr0Da*NPd};QcFRj$6*$w?1ov?XXtZK5K~mvbGoxYmRZU78yTll;fh@@lxMB(2n_` zee*`Y=975LGjW=K;@3-SUoidhTn|3)lmYQ<3#Kog>%k*>4~}O>Kes+>)F;2M+GLG- zdWDKvqpqGjFxqF0`d`2P(JyP%FOIItS)4bh!hc&9(U45bsYt+Q8t2(Sv~}@eH(-Cc_`-i@7C+nIO(#A7hke>Ndb3-3# zth8G9EN?gW-mL$^l&-#@{SoKYYxZjVk<$xYhXXE{Q zHJ%@HZ`3*9l0J=!K_RTtP_I<2z_1Jr&&ao|h8tcrsC)zoEiGJDFCSUbxtorKRQRh!D z_su&0Ik#WNJmuUzjYm6GbuJy(FZ=p;xh8e&?=06Z>pa=Bf5yCOxwbWjx7^u3`|7gm zfE@d%H~XcFY3~fkm?v}|kU4z*{(kAPcgw&W`*x=cNEdVW?3c&D&E*>09IpRk|8#oM z*uHtp+&6zyAChyKa_2bpo%^)o znn3%mQS|E?MLe!i#OWGE{H{@q%QfohgGXfff)ht({kdn1%657lGdkOUW79F&@1C!X z$#`ZQFgD}-@y@Xs|Gopp=C~+#jiSD56z#Z1(Y|XG{kldGk82chx<(PdYgB7ruxk|T z8U?#X!LCt1xBhiKhvo6sVe4Uee4f0{usp8znJ_eu?X$NYn#bX;-G=78*uU%0Jl>|A z`(hr?|GQ;q&abz&eld^F35&m&^Wv64Lvx;9vib{oY;X6~3pu|o{&8r|_Y?p1e9nu1 zZU17<(|b-Dmg~m94|_i6*CAtH%=y0AC&P06`P0+S=RCdUp`p2MY;w-rDL1h>Usj$?^HR%*>}yz`5jpmaejJ{47P)<7 z#{9SP{Kz%xz0M=EugRN?%CWCBbVRz?YQ(6Fd7aZnWez*sFd{w9ePncw{j$SHrHj3{ z8j;7qq$S5>4$t~9rg2dril(Q^*dc@+k&h>v`V(+`g~pdH(9Z zdOgq2=X^XNuMyVUZ$h5We?E9ZUSG@`I3ds5Z@X!HUKiZgb3$IHT)W@+JkP&k?eTei z@tZLd@_J{hZC}f4gz4?a=XJ`KE4`lAO{?BGF0U^({O$O>-s#l&^}PPt_>^&ZowCsM z@p;|!?!s^6b=*?p#^v?SPAwDi`s?lMf2#BPfYF6P^=XKmEOHa(cHkv&?ufL8M z_eR#a=KP5n^LyvNp4V{~Pnei}oil7=j{U6_CuW_&z2D53SDraBb9mD|Z)RUN@BUVf zeZ)Hx)5ZJmy_GS)cI8`{!yyk%OplKZc{|6x&FOEYi#hvD%wyoj_1?)GuG{9Vbb7%n zZ{#u4ZJ~G4MVEcv%wyx~qu)-CUH>pKkEPA`c`J{BXD3a}V`jf`M9;WnRSJbPXENyd5Xh)**9o>M-_aZ&Dh6!kriq8-npXy3fiujf(3W1flA^C;r? zJgT)X*z+jZ^C;N!DA@C;pIiTvH)rIYc*b!vat|GQ@QmF19$k1w?!T`eH$C^t`^HYs zy}S45>A5HF`N*`~a}O%-gLw|{t3OZ6J@l75P0PLei>cG|Tw+S6sk#5&zRt8f2bjG1 zj65e9{qXy_cTYTFTAoXMclV4uw|VRG_wyWJ;Jj&hPIANQALKbwW7hk5F7e^`>3ME* z-9tasxoXtZJSSOd;*2~;T4RHm+1Hy(P0w?i_8)$bb$0ABGh@E7%Zxln+TxR$+1Cb> zX6D$h-F#-&IbrCmjCsV5Gc$*~4xE*J?RMmcIrekEnwc(cnf+nLe0jGIGl!?Q%uJ6* zPW&jxKJ}^()5Rml&dg(=ot4MN4(EK79uGKe zW*$rL9rIxx1E+j5Gmn`g_Wv>0s7{;wkaJ;?<-X53(te3~Id_g)#^oCI zk5lGndEYA*Wc|bTZqu}#%^Gc*w*TU~3pMTcyMHazG@ed_7it>k#J3h|8vlhKEY$Qq z8|AK1)OU@d9oHz@ca5T7*C^s~jUrChDB^dGYV8Ylje=dHVAm+vHR|Wq-)ZO%dAv3E z{~?dhRd@LzkE?G!`#z8Dbq@GGkHgQN{66Q!+{eGqYPbXZ+yra=st+!VkIroV4ux>}&nG^K#ud ze8P`e=c3NabAP)yE(5-_&uH1Ed0*SYZ-p8=QR$$*Ynzk-|PAOi*m2^ zsPDBN?Rc$6`(EqOuh)9SnkUe0Ia{^?a7Z@AZ5}!|(Nc2E_06d?v;3 z^?ato@AZ6^#P9Wdw#D!Dd>+K_^?WA9@AZ5}#_#ofmh^G?y`Imu_`ROb+W5Vm&!qUh zp3lhmy`InP_`RObw)nlC&)WFCo^|-Wp3lhmy`InP_`RNe@q0a=wefpB>+pL$W9IjI zKC|QZdiKTd^&C6D*Ru}4*E42*uV)VVy`FvXdp*a_@AY)S@AZtC-|Lw}ey^uTey``) z`MsVl_`ROT0KeBWhx}eor~F>eV}{@B>4M+ud2H}|Jw5V!J&z@Rujetq@AW)pzUX;F z3*YZNWBH-YQ#QS^WlaCh!T;-ZQ_JdyS3GL1E-ha#RPn5T-rh3fiOZtS-*3FTWtVd* zKI(VfTjuRr@#tF~Y-y}g@z~9Jww$=&(x^Y|>%J|&`n=+1%it^@a`-b@e~WvDWIO8~ zH8k6Q;GB`!?{lNZWISDWc{$@;qxnk4f7h~ax2S>J#JNw0{@!;AxIR=b>u?bJKEH$-rM{>2z zRgbq^@@&QX4QjT$`b6i*+lHM7wY<`;D(|s!OUvLBtMc*l`?qX+eN}#am*Fj4uIt>9 z-2SJ-Q!R&XQPml@XWy3FuBqxQ+4F^#4_B`0Ol?1?Wwj-$I#cfL)pGc)Rh>`oZE1O< zd0DhG>9#&ClNPS(^gXy|%fY>>I$x~#c*{cnsp@>U=c6shuUgf4?}0~JK76UF^WpT~ zEgM`?)w!$hgDr>eSJhc-$bVaoom16W@zaM|PVZ6G`SzguTCTqFr#joOdwJyKvL(8= z96htDbN;p6Th4y}r@ne0P}Ny>{#`8_{H_`ob=KagI^KwRuhXkK6Arzj<=Qb-9r{}O z`l=3N-}UOB>MZ%Y%VX@s+;Lo0ha4`{<)^;R7*o|@?Ax}vA{^o3_#3M_#JuCSS7Z*K zTB)jo#}OA+br|~w7gTj{aY2Ww4#&Vs$5wU7;pttgIyl|qlPVsLnQL~e>fqwmo2xn; z8}Ik8>fmw6QB^s|((vP}a*lyM3svPDGYj8TjfL-VlsWcm)~Ir9Hp?6fF2`)M%(38d zEH}#>3ogfav&^yJa_l$D91AXUf;k^t=1Q~7vEVX?nq`g!m$}9K&+;(wv6MAF$5__*9D7;go93jf@lA78*7(dJ<>r?9=A3qP zLHjzQU)>RpPKi_3#P2asjgpwmSZk*TaIPcsi;%tR{;ODRaG9=6uvC zYfrPRQ&FeP(Po*eQKzgK&9Zhxow9~yoif*(WzI*Pvi3B~8WeTPT9|#6HKSS9si;%d zu&h(o)Qq{TJ=o&v>`{3Plr=tcSoWNBTK2R&X3AcXF3R4O$41#_(qq}{@>nW+ zR2~CmPs?Lw)(zJ-Z+Pe8U0&6+$iFTBy;14~mw(qN|30|1*C_1rtz14nvRQd$4h_f9ce*!Svg8x3_{z zKg|msnHEf(S04OvRbJx%zlA>!W?YRszX&evPQ6PU$DxFa0#_xBT~}@sxg= z###Dl8h`00+%Yc79WV9G1MQd}+Ba|XYd(p`JQJt+Cw{%O_Vw<+u5K)OL5CRQ8|z%z zSnJAV;#fWBe^)kc=(Ti|e|zv1jSe%H3VyIh=f(zGR6O(0OB?&2uyoWv{^`pboriS@ zzJBMQiGJa2S6?KUI-hLWHkg0=pDo)3(`MHt+XvIvZO<$b{QrxY_-{M$vsgp! zJ@3562R*+C{`-snY%G52H^EOIetP4vyXOWUde|wA0n7gweBnzcHRiw9CdLcjx$`2y z)Y;|cw!!?{-Ck-JOq;h%YadKs>kL~mxOL9Q-g-@A*^QQq@@+4>zA@#Z<%17-_2$Mo z7p+j$KmPW{qQ6)%xZD5T)7bUT6<_ss_r~9Lt@yx;9&8-&INDw=g)K$1j3GDyxjDTri{ zq$r?#AQ@4RAW0AqBxfXwAVDM}K{5!ut6u~JL2}MH=bY2+r-x_G`u4fr^6b*u`<#2M zviLFd^z`)1{AaD1o;6bf{nC)hN9{2qXxQHANs?}Mu($Rrmi}R_dBN2Ct{?7Cv>?b? z+x0!P(dx*>=5w^;m(>}IbmFD((qu}g@eXd7mNr}e7xIpvGrTL%nv0u7$a|d`r%Y#avJah_|noaAMuC7EW7ymN-lGKS7~BIX*Stk1hIFb?}%$CK!|vUDA1qT|h2$Dimp zG}dt`IzEkcyo!!nV;#q$#a_}YxHrC!$>^Vf{@obu&c4@n zcb{PU>3)`1{|xl+#yS@Xb?RIsEKBDr(Rs^cbRH9(&y2&ih5e@UmFT=>fP;@T}v*%jmfAd38K_ojT5Z zSz*70{i)-?`&Rp7p#9Qp)_xjje>K+r8)!c^)_xu67%2rjzz4ZA)*k1bF;aQ(Ye0%A0if=D{e(~+4&o#ci z^m)hknQ$A0`;z{C2l_j1eM5iO1O0tB*5CU;fA@`b9td>KFxL4Y&^g0c=MB#~pLiLa zXMA3rf4okemwZ`a+roa+IW5q+&H97Rb%D-##ySTEIu{!2+!*LQYOHf+p!2A)&ZVAp zj`cD+_xij#CwrYbSNpOG=jbfcUd~+-&%LLcc9y#{bCtw1Y@w*#WMFESK7M}>*%jUK z*^T;cz9E;%-x}OUGBkF)CQCp0?m$jUFEFgX=>)>>rig_*$t! zl6-bH;{n44$=GFCjkA3-NNz=DF+NdrknG!>*|<%ofwKBcX0xsG)2=f67iVX|Q9b0# zsg6JH-%D;bbKE*-A6f9SpajAh(&!3e3iDXwvwRYRofC$AW9tUFK&)lO=hcW!@K(kqp5*QNdC z_aL2dxG$xh+Dfw5bZv2ab0f)9#qqsoA4=-}j>G+M%Ai(qaE0qv#||`-DDxfXDNs`i zTy$LK?Yq8?V75iL?%_6iwNY|ue=Lvr?MR;FQm<0zXR>`dt%AHbz^hSvr|FVSZ@4A+&CZf|J04^&9kosnWww)KKjAE;P6V1RTfmvZEd~3OicOwy5j_^<4V)It`Ed$mq@w~ zc8qq{_j79(v^yB>{%8Fm>?`oZFOOQ@us^{_hn}(7EzK z<1+gW2PbOnH_o1Of6#a2UgM>WcLrCY?J-_GMZd$=<*?Ojy?#q@;oyVD(^4D^I{dQVxYx2h!S;CjjO$n29t<3_$N1Yj z8-v>ob{lWIxF(q0dYAE*+N**pTXq^p>9jcbpqt|q-R1-jdOB`Dd1{dSkmHf5Cj`a& zxx6DYjt=I3?Q||ZH#8U-xU!;+9vGy0)7enD&l6db-MvTGOZiw9rb}dH^|}5~j(1OD zoId_TIh8+!@y<>Uq-@$W#_tw-Ao231H!fG^fpn~p*|`3c2l7?b?8f0f6YfiKpFNf| z&*NEJH0!RvMVZ{%!u+xiW!Q4J7O}j>1Nm@Da+7Jl^uEO0oZ5J2%llF&WqRXDU)`6! zZ8IBpJ8@q=UFOzuM-7MG!dqF}_9KTM|g@)$v-({6q5dXlKY*Mqj2Op_r` zBes>@Zv5fWrx9hNIe)IM9yM69%K7tn%9ugEhR%nh62uScp5ANny&fkGw!P)rx8D!x zgU=ecHN(l%a|b_`b$y`5@;8IkCmmO6TQNvkat$9yjf|vFMf?(!ZZu8w~fKoJX|}XL9RfXNNzP9?{&o+3{DN z$+EdI&E}%@o=Kwu(T(S|c_u?=Mm3&Q<(Z5q@yzs>zxGt()qQCEPW`8ncC%a4NILO} z99-zu`r0mhESqw!>?QJ(IPo-MVGBZO`Q6 z9Bw^xZ-(cxpk;LHS9Oa#m(>%Z8aGSuTpCSsYoxFL^h{nU^1$8;_QiT8sdC*mPF?V+ zRGo6oxLuwnGBmhkJSXa7**yNd@upuMO6m{K8ZZ0kfjoQY*5q&Bye9|8IIcG2uFTAH z#$-n2zaz(2I{D03Zpnmv7c70FUUSGV>R9-DRdrwYcb*=X&OBUy%E);AlB%aq9+ z#4q`q=N;$Pc$qi8Uu}%M6`P1LbiP+R!Z`dp&^uewplF+o=93+9QwQbhY%qQvJ8h66 z&u^aB-(TZp#{aR}7uYGZGQgwM(41=VfwL$DfqHC|_)MYu7znT$bbMoP5&HuS&`Sk1g-H;@73| zjl0I-u@D|3mA*bAXZqc?{+8v)dzq=zRv061=eJiGhkYJy-=-bn z2JhutY-KgcA1lbYXo>NsF=GV7%P;eM@aS?cQ?lI(W8_VBd!=!^v3up6F8j?tlhW;z zU-IuYKZpI9w(KFPd%>+6*Sfo3vJN|8^5H%(WY;07_p2K(OL`rU$u*Cep0H2QS2L`h zZ{?z&7aTm#82$YFx8``RduEoGS@YctW8~e{Xqqu}9;i9RIP8D))pf1ro8QpSx7C_w zjD9{X=N!+~?#}WuSvJlvM&A5OrWr%$&h=A_t54Y{Q7gH1-4u!UO4n{~&7t?^-O^x| zTkAW&Z^f9d3(o8(mGmPtKio>kq5D?2!eX+&bsTbh~BFE8kkXR8F%?3U-=c zT%*%YS@ZdH<4<4TDT^2XZ2U>>osv14+arGe_)a;W{8vk_vSF9BTeQ)5Wz0RYarh2n z_~hqWW6US;|BTA>FDRxyNxqOKhIoXg6BF{CVH9NQzjWB?@Q$-8;5-! zZeR4(gSo%Ave3_$%^zosex9=I1kaxwp6F#ZwVq^*yfbe6XspjcqI#_^`g|l>p7}iN z&x~dE%ev-0O(s>I1M+3JFO4%CJ0Qp6yY;|4?;n(#hZKI!c{&uj`!*z>5`<8@zU~#q(X}t#`$v}l7tJ&8yEWHpscA-#JGQk zgK}$BPUAao9FRme(i&$^v|qL_PGbD^ioLQhi}Um9H}=TQ{xK~5?3i5=88fQ!+A}+3 z$&jaS;hpQ}+}q`Y*^YB`-74z}I+?*oHp``LE^oN+;WuGkFxuJ|zb7(alrer!GQBy% z^SP5lz0AAc4lzdF`V9sdLuZo@1{jC?Iert~YcbmTCw@;psyWISzbARJkMMl>)=)3A zVEqtd)(fQox4fp48 zKi6jg-{Od;woV|~`}tj{1`MxRZ5Ueu-SoX%Dk_^r|4F6K9k z<#-FbS~`9QR^0AxjNgF;d3$+2d$G5d`DIdHW8@uHy1#MQSK)TSSl;+yH!BOj13hc^ zFvjn|^isV%Uq8^>%Y4wPuQBrGzt+!K=V$K|owt2kgngxRqi7!UiO!j#VV#G4-`4rr_j#SSJ?nh# zWptkRdBg1(ZeM*y@NKQn4!#fTGllQl`mEvmygq|?)@Kthqt7fpFY3~NMtQ3X{PtzP zx6Nb;w;iKdj?R}#2xo?ZGuXN7zeOTvG-?w#+^?hFF zUe7uwdl{Xpeco_e>pbuKu+IO!Z|ie`@ALY+;8~v|yo^3y_`G4CqYw9KQ^x9r{y!r| z31jsC_Ma8?d~anTFS9O9K4auPyEvyYbl#en)i~U~=)=GNQQF!C{r}kH;>PIz{VNpp zeClu^FEhATK4avaQY)7+be`&#%~__%!}o2SPkf)(dB(HOKVC-XC7(Ck zj^XyzInB4V&UL;I>m2C&w$6>d&+DA&S?5wOqjRj!i@Hph>|#;iw{LnTGQXh@7n%90 z)e-&w%*ABJ=>LO0NagwNrq{g8_(BH{8}bzxh6_^Pcb9Iv@Hzuk)m5oj<*d&Z|Ce*yrfO<65}5GW7q5C~o}+{eM6c zx8?&*(Zap|LS|9Edp3U|@7=m?y#+cG=09uc;r2xzKDz$J+Kcx8I}>7C8=?PCEEC=H z^`G54JH|-qhb~qPd0WqL>nhNB)h!3yv~`PbuRTXI>-9FsLRJiR$5))w{rJancvWd z$Cq{Qbm;%LH?21r^#2k+xR@nyvcWEv2{H}qA2J!_U3tdEK81Z1ZWr|7#NW7gH1z-8 z-@5oK^!Zm$ZZR9cr7F01Ey(Qn_MoLBZ8UtaFI(+d8-S zKCg3*XPt|@jLuO$Z@8^>e)D};=RM!Ibw2ccUgt^AI)8c@omYL{u+Pzl>u+{3Z|K`o z@6Wb6qR$tT$)3wM8fy%hBUy$SBX5Qp{fwcrtiSxR+AoTwx zT_#&PIMwvAUZ&-B7wd(*<0iPc1?ViY#l^$uJm7t<^MmihI&b*Ct@DZR^E%IX*7?WF z=)C0fhTAdRzB;G*w${1M_hFp_ec#r((f4_sGd=5E>Sc6}^?9`(f!4?Bt3C_Vcg~;v z+UdKwd%k_W^d~{jxbFFOPUC+CEqlA?+x#C?3VN+|JhMl!;O7=jCU3PoLH;T+P3Oxw zG6a!z;u}wDnk>-&jWsRMe=}CuK=T-@jzD!8tL_Lb!&u9V(6WuymOyPXRvUx5{aoBp zxLv}1ApO18L9s^e`TyS1kAsuR-SdBzb2WpGkK8+W!poI{cq!bwK(nmHgY|8kOu2{o zf*sdg-Xgzd4(@hLZ2lRyLw~Dxxc4tj3-sSCU1bB!W2`y?)n%-@11-Z?%M7$^W3?qv zn~c@QKy5YFdDyqL&ds;zt=U6YJbFa@E?!!87`?0C> zxgWDS&-<~g^S@_(F7Pt?yx{YO`;v~!K*y)mOUG-V_cHo>;PdJ{;Kzc_Z=QAD^D;Ug z`n)<%dYw9d`f;uEsvp-n-}-SKZpU!@>Rj#XrE|Eiug>k>4?5?2|LC)TAJ_Vf;K#K- zJNR)Ou1nZ&;j(lN33M(o|Lfcm=p19Lb55XhkFm~0o^_7$GCFtpykTGIycg*FXFk{Y zFwl9?Sm((==SzDp*7?)3&Z}NV=Ubn5)aAs|=0={9`46p=f}bUn@@MmuJg{z^%)c5} zj;_m7GET2`vbk?;8U9V4k~rVDIzgHs%*@*+ai7e6@?|zXcYghSB^dJMg5)bxp3LI( zf0t}kpMKella`ycO3xY?Z;6vQqF0BU#uFYlh$#P4F5}e+CPrMGlG}Jx{jCv)K5}+8 zyc;Fx`G;fJLmR@jrFtj!sG3WOjJUR8HeNgSKI$wqJ3`YyUEa zJ=)HZ+TNC~?H{TA!0M&_LS-fzYk!H?PumU?RSv{ze{GU{V`Je zrTO{K?9_IS)b=h88?^l+wI5i$v|mJO|1j465~=;hSo=|=_9tWQUy<6+%x~K7BDMb+ zYk!Q?erb&Q;!G3k3r1Og<_FlRzB767j5}LQ9(5^jW}8dbI!0-@*%)>2{Ns9K_@vq{ zF@~?+D7@4dKGb{Cjp5t3gNerQ`J?ZL8~>S|s7tk-o6QE)F?ZXI#;AMG%WI9{lebz& z7{gaT6kKc!A9n6J%NV|WI%k40d|oWUaO2%o6Z`stS>HeNLs({C^MsM39&Ix{|C$&t za{QA$#%UkF92tGfG2`juV@38zbH(_Rp)n%6_J3kr^YlxRS=Yz1bN!#qjusiCN@C+| z7o$eT>iL>6Vx@3S3hfoPGjG>~k?rH}GQahRj2GGZ@_yq4dE!Jq?s3w1|DjlsqkCR6 zK7TMqWRii;jQ6}5U1PCgmq33g8|$UWpLQiS?(U4bzF?j?#?aGb*-B&RFTDD9W0c$B z=x$@!b9~WJW7zrp`Wa)`-?QOGW7O;T(M!f!j!)Neyu6m<^=LU>zm_8`SIZIFqvZ(g z)N+LOYdLm?4)sDh>kE1M0ea{k=%?RMF8v96=x5kT|HFQ^OSrwj`de3gYn?wNS+O>f z^2rqA!;RmQgkzQ%j~$UumVL0pILh)@rF+f$#`>#Hl&XE7 zTi(JW8cFdEE>3&M#YR%9_ESsWbG(u4DEh?sqc0jskF<}CYt3pXD-%63KHaN<^hx#5 zI5KX1DOUP{@hjEpN)wIs#hzo*dLK!<$Ii|_v$;fqMl!Zj6pKxbR=%-Z-1FS*kD26S zDLCE5X(#Lav1Dxe)Y1!o{;?F!{KRz2jbO%1ZX{9q)=-T9(~$ z{G*hRRsEdL!|hn2Ohx(e9oMGGpO=@R#T>6+T~_whb-Z|VY3VZG@$6wGq{Jst4DnDn8>PWoV(X8Ad=|7Td_g*q?zO}Y& zc_)VP`HCOOl^Cw#hEmy2Wo9 zWMl4|CX;4JCTaWqE#viTv&h|pw~Z6k%Pv1%aQ=z&b}lI<&Of7@=ap;KUB9}!q=5W7 z)p48nuS@Tr9Uo~>R4%o1Ty^AI^6gERH|*zd+vU5TLAp0_G3TFW%Op8>-Y}bMY|bpt z(%&*3yg#d)uk70Wa)}&rs+?>0lUH*|{@8A;9oUms`iykE_E-VQdc^U>dxa(GImfYM z6_t1k9PfKnOa{Cdr(Z>>D~%S!Gk-pKvz~r0#c`A@^`*nwxR#zLqQ2BF>G-n;_2uxg zIF=ssaD7>x+wtxu^<~CP*Jr~0C)}@oEL=}+UW;e_A^5hw{MgpH!U9-HJGtzOQLR$&t=+&65oz%Al7mJ>1su=cSjXGq0H6iqARPHTVJO(Uxn-bRn1(|M^c;pbs8m-uOiM_-Vvqs9AdI_ zW>2!TNo2{4^OipFR5IB$_=0h`tg!vv9ww3Bp1HiQu1qe~PMtSBJBFu`EJM?n4NvE! zl`gX!XWo%sD$aFW<3>jL;(N!-o@AEZZ5+oupH)T{aC~`6c6tAVt4p|E;ksnXlt#*2 zO=IzHKF5gDrS<)51q`BQCZ}bEskGWkxdr%cbwp-9P)E6$6=qm z66Y1k)%mQ|tMQEZGB>{C_*vr0v4dwUz2n5#QuCPOV(DVa^;AwK?B{QqCX~%8b z{kneFuFLWN*|ukmIC@qDk>%j&~i??@4BG_7C3~L-JL3-1$f> zY1hhe(pxV}yY`O5ehd4v-2S^}8|If%MeYT`?9;7|b~3INi+0 zL4n3@9F3A^LA{-hbLELD&LmG%kZ+UPd2R@O-gQX{K4cXQmKvm9hlPSS&-pP_d75o z!IR*lwC*>jNu5W*`V{WB=)(ICgIO8e?-kk_W#PFfTyEIUVVQ8>*wf@UY24D)rD2nG z@-UaH%ZdSOWo}aUTiS5{8X2Z#p}mIGS|dv;x_ZTkw?>-vaP#lW_kWc(tFM_%k(6uX z!)I>38{BS<%qV!%(wjY9BjrAD^W9G?*2?r+ZoXUp!#YV^)XjHyXZ$7?uR3nFX}xUv z!p&u0J>MX!);o??YNJ#;>3H1M-(+tR=buRzbgl4L$2~KzlP^X(U&Yh9Ozr7>bt%bO zDL26Rs@u*rGV%xaEU`Lrjl3Um&H3=?8hQDEdzMI_d#%*Ce8bYC%w8+eue#@og8GfE z?t9&H#kw@V$;ltwbH()7>!o;U_grx#-Uj*Y7styp{4Q6cxaS1eKRl)5tFP~pBxR48 zf6}kmCEp%AW@Uxj<;R?xbbL2sgCcHAr&1zj@&ClK5<;~r#taTTb;oYVu*5$38wUqc^yA z&z3ij*G_LB#QJokkW%F3qfBHo~AzNZQZg%6C+@9uqa&-GqS<}*S(m6-uhsKV>b>Fw| zs=U(P{qDU!^s0<2<9-jPC%P(YGPvK#Db23PoK)`j^TD^5<<~-PjtKj+mC6qu;eLPS zZ@(god%EAHx{a^Mq8{$|YWSwh^2ccRn?G8=XEkYqn+w7^!*vYHgnfIs!*yBl%#Hnp z)o)1cIj8OSBvYlE@@?KT#-*y?lAi}S9{A~P$+*OEfv@k#$_0);9dSp7e(8R5I$gac zV@95~@wny8b=g+kJ$LPVpx<;l>sT_}lEsyse4bjjrQuhO3s$-(WtTgh|H^kyW3yd) z_XT%l%TF%7NV2;!Y3Bd84e!jjD^=RMyb-DHO7+%`!}V>p^{jl9!ktYE+x$|6vr=U4 zA+tYh!>$(hCFvli=hCzXQl*jODLeIS)Ju+QTz({zJGeTYzwlW4u5f-xz3z!r+jGiv z{`|#L8NSW^CJ(;*RDPR(!qOj?eePItlVdOzu{@gw#S{J zJ9Fr?94pESOAprtjC9ni@P<>;EY41oNk8zke0^w#rHAbq z5%09rdUv8|@TV}kp z%~N^MYN>IR;EA01bcylGV~-_ouf@ilk3Nz<>lYcv`t_mIE9y96*aO*r)SX4@R^z^m zTj97*l6&&YCdbK--H}DFIQa@IZp)WL98a5jOWM8R^uP4$O_?6gm0Rh_4cQUP*^{N| z4VjwW*%|iR{2ou`*E7qlj^7k{D#6ZW#&g#^k(ahFHU28Y6G?k!iSf+3kL6Nw$9FqE zk~(b{TYAb)59Nbfi;Vj;eIUK2IL`X+eJS13amoDmWZ-beNmJjI3)>v8PI5>36?b~h zWWFtV_d4!V9@@|#pqM=V3Rwq8n!L$^RUkMr(ci~v469?CAM6VPge%U;ksmh@1itn_nX<- z`s=ImLsBv3cM|IE-eTWO!1o!($K4|QW&+ar%>*#NnE>WD6Ttjt0+`=S0P~v(V16?J z%yar+?DgOq4k(x3PXP1#31EId0nG0wfcgCdFu$Jw=Jyl8{C)yBTrT&&{-X`tdxAW_ z?EvO?DwvLMcOWmnWdY{?9hm!fVD8_6xqk=d{vDY6cVO<{fw_MN=KdY{KiZEyGT6qw zJTUk2z}(9Nb1x6fy*x1Y^1$5719LAA%)LBt*eCqH3ex#~6)?ZA0_OKs!2G@nnBP|c z^ZP1beqRO5@2i0MeHAdjuL2IY1;42RU-6qNV182t%x|iI`Arotzo`P|H&wv=rV5zf zQ~~pwDklHp8#v%_f8c&M)3FZ@o4FSZ=J!}2!*8u1o!`45ny9WcM81Ln7M!2GrkIP7zNg9vu=8$@7!g9yxT5P|s(A~3%}1m-u0 z!2AXgnBO1*^BY89euD_i{e3XvE)a(RJHx(Zi~(d2M}Zgvu#OvxF#t2h0L&NzFk=kB zj4=Q+#sC~{U&a-{2F4YD8CL*iTmhJI1z^S%fEiZ+W?TU{+&B0g9@xO|@PPTv9B{Z_ z@jE}z!|(in`CT1w*oTZ`L3-HFjPdx7W%2tkNDu4e_k5rSzCv6LWWb24p?<{AAe}KY zV8+aV88ZWB%nX<@GhnnSVrIaMnE^9q1{|&z<78k1<7B{$lL0eM2Fy4aFymyvjFU0> z7jZIR#HVR_CCTc$lCa@$tt2u-ziET?p6imz#lDWiz6$$u>Ssx$jeds*d1IYTDs3(} z4*QUCS#Jm+^97#-1^qb}|kPdKiBN8ODhrJ*<;4V31)97+7PwECvkB7%(tn zz`%?F12YB;%os3mxL%C=f(?xO0yFLl%(yQwfX;IPlb?ZWs&*r4%W7Jmq4{2`d}hhWAZf*F4Z zX8a+T@rU4W9sgrn(+}ZxXKVoSA{GKM17OB-fEmjHW-JGou^eE=a)24j0cI=*n6Vs8 zM=S*85hDR+EC-me9AL(BfEmjHW-JGou^eE=a)24j0cI=*n6VsS#&Uoe%VF{_VmZK! zj;9AL(BfWz$tMhq4D8)K-zjG+QE zh6>CWDllWHz>J{+GlmMx7%DJhsF;ozB+4T;3CtKOFk`5|jG+QEh6>CWDllWHz^E5u zsKAV&0yBmR%or*#W2nH4p#n383d|TPFk`4p=0yw@(-A{OdBjke%!?Q*Fk`5|jG+QE zh6>CWDllWHz~S~vU$UD--hOC(qvOyo<;y~kjN`xDP8Qy9yz6jFnV02>rN_?OOk!?& zYMdl<6N$3zxpCv84W)hJs5Xx@|DwLEsUOYw?t{8=IPxXqzFq1{%v>>idj7F7y?m7i zv5cW-T)CHxp+8=mIL0VF#+ox|RWZw&kAO>&HS#sAfD(p0^C`sJs6 zynJ%~<|Os>&Nj&FPyO}~UvBFs-*|h{mmVgxvwqCs-u`rzhx>XVo%Mx0{Qy1m5A@S- zD3|_(J@hl|r2k<*+a=sycwYMK+qBkKYc)$Ci|08m88eP-zW*ZqQVeO;KAp*oD-=x* zrATkQ`RUUj);Y&@|9B8A-<`qIYu>#REIgFac<{tq!M$6VjEn8MY2S6k?>5qtyq?v| z*QuJ#7? zJ5qc3tyj`{Jwv8t^7>01$SN%Ne!Cn(d%D!iCA9PSz}!OnV_nNF_;w}gg>=>z^7I4r z&_B>mzoA_E6ZX*0u#^6W{cM+Tdw~b!OKbi1K?eQydlknMzJ6J5j&nRFV+^^PI-SXE zDHv61ZE?JO+~Z)+jP#b?B-y=S!;}ohy<*-92CT?vJZI4L;K!4hjNe#t&Dsv*4(Y8b zWcBiW+GI0^p7Q;(8$*AQ-Z_j>?vlDWjbYDg@p2i%&XmI(!~Ug59iv`-9yrduEV)k~ z^idiwKWu4wuc!9(%wB)xIN62e-rk&3XwT{0xrKJVpE$43{y|^owYEdOkk0x-o_>HH z`Um>yHHf%Z^m*;2 zX0?na-#u|#+54O0sCzz_4j*Q+^eE9<$-YO9r_X62mlwNlP1irrT+(!M-+Uf6vboh4 zaVALrBd+@nE#x0>cMLs=2DO`ucLeTHnvxldWBUZ|6IQ`g{8qKXvVhdLf~-Vr@mp_5rcc~h zTR-s)DR;y1u)0O$%`e@!Ti?E@q`Bp|{Gm7H{YI|bAp_o$apE{>>k?8Xma}1Qk5ZE9 zEysuFm5~*-95*~$PM_z0$oX$TDB8tk68IE&KEGF+JaP>_p#brw)$8RPmCFjOFe!F`axwOi0w8!P-!fMB1 zpEuHY^~t-P&ZTqfOPU`XuQM=B>fjJ{29Hzd{NeM%exKav&YW=3+FeI)RP_W%J{LAD&%;3 zg(ebzg=@R0i9eB?1s#9d{Sz5F!?pFUyai-Vc{kpteOpi>lV`Bs>afqZt|=__r@C={ zEPrA7x{Dj{*Pa%X&-FJS{XcrB|E#O_hGh7`{hnuA`MP}9)cxka+PSb4F6!omuTpf9 z!Tr)(S+zgwBu&q!H$Bq^e<87dcj+w(w3UImoIS5+{9FbubUd49M*2p6q^G`LMU+ z_HNB(W_efl^?RDhh?veNd*?NkRr?$l%~4q94u8$+wd#67=@2EY@#5$OWo$Rc{aP20 zB~jeB=&KYcAo&M5p7&k>shQZ-{rLI<()4@B;dTkPSK_+`B~>*SmwWHK0@7-m<5k1* zONWornm-4e%O@?bI=($6pH%AazB7MhZ9X}b&iTB4rTh|Sx#MtK4By^GZme|aJri`3 zP3;|LNzz^7C2^c-UfjjPVKb$TaYocA1u z`@rudy2$N%uD)qYb(NN{Ies_(*Rpq`^Uw70-DOc@$4w6Rka(A!KVvlMDJ?&9ynA*} znRC?nKl-md<*b&4z5Z~!G>HAFq+FB0(!)M1x~GW@?3KXmznrtLOsa zw)9Z>-wvz8>I)0kFg~q!&o>%rW`6|A%|Mvk+C1~I{T(59lhR6Iu zHdT*r_RpWwR;m_uJf&P~iId-P)>ADd{o9WBjcG2A+dE#+u9?(b;dpwlPo=@D&Oc$F zOfAq)e%hAE^v^2aPkzqlxIzZ~ZqG<}_rZXTI=4PZXfjbs^py(D9k1`L^X~C!rm)w!osIP7d#H?X@zTkQBF?UMthIS#kinHV@|UFrQ<=e7*(qxfjgmVKASQ!F+xO^SK(#=WQ^b z!-5t|2yt7*%+Ze;S>59O#g%bE63er z{VoS=n0L2}bll_kX~E9&_HxJRzxh%g_H}$Uen&~9&)ATU`r8*W=DPbG_;^Koi8I1+ zq1)}GMpnmdziKD5^bRJ-Z>ZkR-gCi7FRkw^V91ZI=NNj9-g3X0&|mFa$0&DiX~(eV z>Qm=i*g18JW7ywrzGL*m3ez1|9Q(CTzxPoOFWsa{@xmovS5xs_Vz-P14Z zIkBa;x3kR4eZ2i+UhCuQg>=>z^7I4r&_B>mzoA_E6ZX*0u#^6W{cIPWVX3urlkjW{ zm}hOkJZl5ySsO6V+JJf12F$ZIV4k%B^Q;Y+=d-{(p9SXGF)+`dfq4cE%rj_Uoui{0l_>E2_pGmK!KVFdFGBbeu8!8|7m<~dm~&&h&$P8Q5_vS6N* z1@oLNnCE1{JSPk0Iax5z$%1*V8O(FdV4iCR^IS8S=bFJh!w%*db}-L_gLwuS%=77B zo=*q!d^(ut)4@ES4(9oEFwduhc|IM?^XXuoPY3htGni+e!94p6=GkX3&pv~B_8H9c zwqTw=1@k;FILeFjykMT^1@k;FnCE%HJkJZ}c~3CUFoJoW6wLFaV4f!h^E@e-=Sjgl zPYUK)NHEVrf_Y95%(IGMo>c_%tRk3a6~R2K2tJB6gMqmY2Ie{#nCoC*u7iQO4hH7>37G3A zV6LBlxh4SSyDgY&4q&c1fVt)X=9&YTYYt$pIe_^t3Fi9?nD44!zN>=yt_tS6Dwyx8 zV7{w@`5px3dk~oKL14bqf%#4c<~tpj?{r|k(}734c&7vNoes=*Ixyeqz{FxN4_T*m-&O$^L6F)-J}z+4jpb4?8V z>WeioFxSMuToVIxjS-ym#Tp}+Ym8v7F@m|q2<93im}`t+p5FoUED4xrF~B^Z0_OP? zFwduec|HZq^C@7S;{fv<2beMcV8+{nd3FHY=f&9pFwYKvd3FHI_=Kw~m%u!`1m@W#FwZW5d3FiRvrAx}7X$OW7?@|)z&!5; z=6N?T&%1$n-VMxib6}pQ1M}=2m}mFEJi7V4jTy^UNujXIH^Iy9(ynRWQ%4f_ZiojQhUze&XU_+;Ok>78~o`$bsHx zY^--92YS!3vEGdw=>5mWdN*>Q_ab}N`;xtk-lJ@cyn4T~F?8y^%f={6?_)NG4SG+r zXWTyydvG7U-pOr@d+PPBZe!eEuXlJG>pjwe-tBFy_eckN=eK9Q3*5`-9pT2vt9OSR zL#N&;Zj7?@u5n}Ddk!0T?>U%vf`fUlG?;gkgLy|en0J(ec}F>zca(#9M>&{xl!JLk zIhc2pgLy|enD<$Od7m|y_gRB^pEa2GS%Z0>HJJBVgL$8|$-lVI8qE8w!MxAf$-BGY z!Myt$%)7tAy!#u>yT8G_`y0%=zrnow8_c`E!Myt$9QDQB-(cQ559Yn|VBR|q&RILY z>`%17+IQ;x1oC06dB%HdzamM}%{Fe>K9NN2F~fL$@x-!z_!Q$Ai}l+$t$r{*wj;4r z&F}iy)G>)A_QTPZ-YrIAdHM7RxW(7zk2 zU4hzH0(Ktm*gsIajWu7O`HfXypn8q9oIuMn*75_j!&vPK)IMXiH&DBcwH|@i$5`tZ zXg!U!-htNNSpA{jJa^@GxYjpNKU(_zYJCFruQA4{-t}&b@uF>D_G27r+ZbbfX`2~i zY-(E?V{B?0TVAlXy)k68PZ%Sw_7!93)IMa4vb1j*^LZZYnS7oH^LZZ3=Xo%n=fQlQ z2lIIz%=ZN_^`kAQA58sV>IYLlnEJug52k)F=XaFF-)%5|x550~2J?3t%-?M=fB(VM z3H{UwrcN+*f~gZsonYz&bIyW(&RJm2SzyjtV9r@!&V69&fllfHQxBMWz|;e#9x$JO zpp(x(U_SqV`TPUs^ADKMQDEwUPU-H$*^n0mm}1EwA@-%X&C?FQl=DQX2^Vt~8XJas*jlq022J^WZOg+#^Jz(kqQxBMWz|;fg`!96z{TIylUohW) z!F>M(^Zggh_g^sIf5Cj$2D2=b%d)^M3(T^>EDOxCz$^>QvcN10%=HJ9%k>8^*B`)K ze*km+0nGIWFxMZzTz>#_{Q=DN2Qb$kz+4Xj(;nDHd%&~@Onbnz2TXgwvHTz3L<-3iQfEimmoi_P{pU1ExJ-+GFYez}jPYEtG4gs5{q)z+58&bBzeh zH6k$Ah`?MU0&|TB%rz)5%R;?a7MNv$Sr(XOfms%qWr0~1m}P;v$AogZE)C|oG??qs zV6IDpxh@Unx-^*U(qOJjgSjqk^0)rqzoAEaU>ofL(;hJG0n;8Z?E%vsFzo@;9x&}O z`CI>Eojkl&&piUz%sm1y_Xxn;BLH)c0L(oCF!u<++=Bp9KWw0WF!h6}A58sV>IYLl znEJuoLqS>GLjiLS1d+;oc&cdy8Q1ErPkX2<9Fon0inz>H$*^n0mm}1EwA@ z_idq*`?g^2+k&}o3+BEpnEStA>VZz`0aFi{dcf2JrXDc&siBkm)L`yYgSk%)<~}u; z``uvbfllfHQxBMWz|;e#9x(Urp_6;}VD8<6xpxod-aVLm_h9bbgSmGPW}E<+WuaV_ z1!h@bmIY>6V3q}DSzwk0W?5ja`=MOE%Y*qY59Yf(nD6pnzRQ#GE>9V}%Y*qY59Yf( znD6pnt|ySW4oQ1pC+z{#9x&|z(;o7Fc5Q+7Ko9*BX4v`PWsMZ;rD1!(T(bpp%@)ix zTQJvb$yl?c4AyMHT(bpp%@)ixTQK~Cby_gm3+uFCv=`QC!Duh6(}K}nSf>S}y|7M8 z#yTx!uucm`UaZrCp%d%0V3dV*S}<&&A7~HSi}rwN5196VX%Cq8kpHvm#|0{Ta;lXE4{F!CZd^bNw02^=B~GpTS&z26O!x9JZ78 zpzgE>Onbnz2TXgwvI$YGyVb0_y=&ykB`$^gYhigX<5M_*Gu8{tST8VRy}*q10yEYN%y=^}ZGb(r0Zbdf zv;j;Tz_bBO8^E*yOdG(o0ZbdfVH?P>?XSe7asMkU4`vJ-nEPvB?%#zOHc$o}-YX<7hWuZNvFCnnSRTxnd~kT*nT+(m5*yF`^sqdbvGic>f023TQFyJDGN^BO zjhBqPf8`7p*QLYqV4nE`hu6KyCja72H`wrJXSlcyAC?DG9voihCnNp8+ZitIafEFH z^L!bY=gYu6Uk2v+GBD4VfqA|R%=2Yno-YIQd>NSM%fR9N8Zy%V%6T#FABE+?JYNP5 z?{krn{!g6q;(lLPKbYspz&u9=<~cGj&yj(7jttCwNig?A!;F4Q8E|+XmJIp7a-NI( z#bJ3c&wqg{_jw{~vL~=-(RwK#%ffVtjQd=FD95`eF-{-H$+fnB{_L514j> zX+Jnz78&(T`PEaok}96voxP)!-XXI3W#ew!p2^2K+}+=MGd!0CEu&j{-6GFr^@OO# z%@RD9Mw6b}UE#0)^h{nU^1ygstY?xc*KOm}1)oaQDc6kK<#{4QgGkpBIy{~L$v3ub-6tS^}L1+%_j))&nBf>~cM>kDRm!K^Qs^#!xOVAdDR z`hr)`ut-{jj9vboI@iCoLddK(nD3;!{#br63&dDeJ{HmlZ@YwR6D}G%X-?(c`KZk8Ve`7kB z@?h!#Q$LvHf@u$!c7ka?`1*@_fmvTL{Sao@He}Z!srRevZ%cX|kjXWVS>KqHZlC;; zfA7C>SRPDyaP=wsBx)tM|CJ)~Ug_FxsQIDy=H1d@)@bAN`*umL(G!g;zO_pZ#-3rE z^yyCN^1Iu^N|AP#L>sZ((i{D-OVVXrZCt6-Zi!p!cjM7B_DKD?+l*;v*ap;*>0ru( zsRvB`V3rG}Jz&}iru|^n3(We0>4z}Gw$Bdkms72Kn?J7~I3P9Wb}^pv{Xr>Q<#XeB zuO5;vNg5e1Eq_QVw5Va6Keyfix1hXnp+64FnhHgX`)4>Pw?^eOzVpTbNpvHvarQ*} zW&7eJ#$T`4D+{y4GhY419=X{+hVj`kyCgDZRO7X0cF2+;Pv3&gKj+>qAIx@~qw7{# zSJ24}KC)RZZF70Y*84+74RAWi;W~m@M=Vn~@;r80;}m&*^IWdZ z1}{^z%|@R$>?`Vr&zTOUJeYdG)DLF4VA=zwo#3#3GV0R#?Nu`LH`k6+r>&4USzY^X zzqVY;Pju}*uFx{i8@ey?GB=Ja@_94XS?K!!IjkQ{{b1?`Q$Lvc!PF1lxqgcGfBq%Y zybrT%oZ)?2?d~k^^JzKfc-~fPo|jqIYQE1Kwv+ndE2e`f52hY4^@CY1nD&5aCpfI1 zjC#FPZnF1b?kSVJZ|hu{=zX5Kzy#0LyN&ZQT@Q`*d4H}o#`~Wf)(@tBF!h6}A58sV z>Ic_dH^BQpV&Nd~!v*Vyc;6nrHPrh&PxcX>KdL#(%e>cOw9gy1lltK+rh_RDrXDc$ zgIO+^_JC<8IIN$HdJQYx-}~^FNqxO<&tB~9eZC-XFV8D(clR>!7IyV{+s^6i{Z9_- z2U9rhYK>gSYmo>-|5ZUPJH0j{Tc>-)=e4%=^6EJFPr#oYB_HEZW||=MCFQ z{qPmj!ITG6519JFEEi0Bz_b$_)=x&g3UsUOeb~2XP4C;|+p2q?e^L8A&)cq5@iH0a zR`hxM&nWNxPY&w`Q$Lvc!PF0?elYcePj$=Y{XeBvF7Ly^z4CeAo;qB}`@DaJqMnaU zF79Q1|D&|e8@7}B;VY(tDG#O|lX;;Z%yPlB2TVIn=7s%XM!hO_%ItkOzEB45+q;`y z^FAN+K`PH@E++FbMP|P0^G=xjiuXS`tRGDMVCn}`KbZQ#)DOOK{ak=&3~=ii*8z|;?BxnSA@rk&uh zelqH^^2~{V^KZlYhXT&O$p-HZIRBRTVTmE&v%SpOUW%=#n)HGS3{~K#sp#Ns9vVrC?Rvm%rGFIIY zT86Qf8KGqxt1W@rWUMv@YOAr1gFx%>Zyc@*m~{cOE@0LL%({SC7clDrW?jIn3z&5Q zvo2uP1~_H_ti_y^M}e zW8~G}1!L&f-;00auzoQ0gQ=ek{gi=zF!h6>Uw`jx9Ru~!-#cUYM1Sv$;S>G6^Q^yj zrUx?mduNQi`g>A zqR$hab-wp9I^P>3ug>?zv^lJw{$X7xk93p;Jz$gt{bZC&8Q24+onYD@X4X-kpG+S9 z(dQ~-_(z|&JnM6qm(k}lWB5m(3yq;)pBMj)!}`J052k)H^iu}U)MXl4|To67(UVU4rBO4*E>AxdWV(XV{lmIY z9_c6xdcY_P`pGDlGO!1Xys#5Y`@_sS>iUt%z(2aKWDNi4dXr~ehw?JIK4lF5=(?CO z^y_-rzj0VUnEJugPlkTVKtGuJ!O*Ykecp$<-e(M-=z5wU(wIjo=lVO=PXbd&`>V3Y;@WRy!8*aJph*a@cnVMe*Vm&XVyo!)FR*ONpIz8Nug6J)ZEx*2 z?)O9b;Ijq?j3-ae9sF4KpmB}mZw9MRId{6pI|{hS5~yq1A|m=?lV2)a2>&{BbaprvyNca5zIP*Sw}GI z2xc9@tRt9p1hbA{))CA)f>}o}>j-8Y!MkoB3nqSf)cQ}RD#wB;T@D+suYM$0IQXFP zv=j$}4!`U-?zL=Busz;B#^82?-NxH4t_fzh-etU{_Nt)DmYv2? zIxP-9=;k;@w>iOso{rm3o*E=SUql5WhJDp3<4Gl&HuB>od(0=qo zrh_RDrXJ%L`oSz0Onbnz6HNQTtQVN|1=9~;`UgzEf$2{${S2o4Yzy4o7Ur-FxJtZe zk$P8UiTsED2SXnB)c@MBqxIEKevA@1=Yx92BhNjRg8RxDhxgFQ$a}wS)W{P>bKlr@pEAnjow;D%+Y9Dhyq9oAsp zVGZUT)?nUY4dxxzCja6NYcR^fz3O1tFyoGUXXIVy%$vLIMw8)P=Sb&W=V0D-4(46w zVBU2O=3VFD-BlC&vi3Dk7&+?EHq-yFiSZ)GKiOlP_VLS+(YLsL;pyXJMfON@#nL|+ z8Y8l6|0l*ZPrnqIb$u-BZ=cPM78#>TV&iNVqejN+>E5}}SM~02OaEW(xBqnP$NwMV zJ^riW4gN}u!GF~r{r{=^^8ds>@;|Y6{7>w+{u6tw|HQuJKd~42Pwe0Q6MJ_5#6H(Q zvA6Y4><9f5dqDrhzRCaYdnI^p#U25kbMVglcdYs2UHEmUHD}uScdQ}9&cA!z7Ufio*|BZ=P zeYxusU-R~iZGO$$xo*-mq5X3fUi0-rI_nF0`T=_AALyswP%ixmd+2A_N&mxswoBjm z2_xBF1!g6PWctH$2_h+f@?88#>XA|LBdI@imH3e?w?M-9k+f&y>3ET}v*4z9k+i?$ zukj+;UPxzsA0et;hO2m0wZluLiY9{L$} z(*LmEw@bntzP)D7&hFD&SIF+=|8+5&*HiGjY+nD!ceD9&XC}(#?J03CtG9F3=B(cS zC2O<#dLf9K?NAmP-Bb6XlzlVQ6nh!9upCJ z?-j+y-q?G?f`SP4t`S8kBKoXz4d?vt_uKot$B_@u`}oO|pltlyq}?R&1-Yihq+ z&9ZEb=bkl}t#NMoyJc(q>+iN~9T#@>qP=?IN4@Z`Ui7P8#G_ussb0jdUU9uQ-T(1p zexF7^&6npCj((a29xojIG!tj;l=si*r+H`7!qHE2;(3LmpXT}x3P(T9gBy0v_R&u> z@!G;MkDFNIuJ%h0D@^;5BMal_iM$>-$r3zO#s zKQ2uESN-(@*&e+PxS=q5#cu=E-sgzIwBLMGVf^g1+Ctd||0kbTn0}XfxiIncnR(%C zL!8I_vM}+_zI|cF)pggxj8{8(us!+F4|&r+`Ltj1Y&_)OIMK!U(aUjRcf7PW5BM=Z z_&0C#Yd(p`JQJt+Cw_HdTydYuu`}MdPt`oceJYv!#C5O+An!F9`bLT=wkfn<+!jrUfP=n{Fop7n>YG3pTuLHiPQWO zzq&B4cn+xJjpu-5@(|Af$>b-V1Cq&GJO?C`&v*_$kis$TP^or-~Wb}&X>}rqa)Y?9tUz70@ z&$Y?;kLTTF`if?1Xdm$<<0s-y#(#__nSNuO z$;1=mPbSXDOEU3CzLFVNo1vp~UJe&e~O#uLvq_3y-ZuBm@N#&c->yAr#4(O$jqqh9z| zFZxw4;!!W+R4?LJFZNofS3Jj6dpw8M_VFBA{ls%<^&iinwcmISt?|TjXw@s8L#tl# z99s3lu3ofPFZ`$%{?&_q)r)x4i#XMb`2R<*6WT%Ry_oO$KK-W?+6CJel8=7mg!ZC! zo=?7F?i1SwpL!+MiwahT8t=bFWIq&n{bEnvDN_&$=*~em^?wU&+Mt)WYW_6X$YFrc=d(0M@h^ZwBO)&Dw&_pkkaw_g7mPcu*d z);Rz4AqvY^CEOM6|eGZG9CPys8BG<_gyIbt6cnk9!;!$Py<7;Cjh4r=?* zs`?47s{hcc_8VH&ctWchXJ}R953TCBu*aCQU)o15lJOHcO2&WWE}4EKr^&<)%kLz`sA6`Cb8UhU+;_T)!DJ>7;dK5pa*wfz<|oK*cRH1*`_zw2$M z)_$Lx<@6fQus&zB#`)=;XSBwD(nn|1abb77v^NjZ}e+EiN`z>r}-y-b@}IK zecF3AStfIG!Pc|3$E;F#=<~hX{U$A)_LX8U+?M|?Jm`$B?NYN9?lHAXJL7>%Wt$^D z?9`6C_2I{4D?XMU(O0 zt?8Rgzwgacn0SW&bCI+Y=QS%8CjN82`B~Z-*YDmgeD0ig=d3Lj zss0yybJ5!G?c*1(@yvVllC5#>zyHr$Sw|0Pp$svzUB1V?;+cqS>rii;90G4Uc15BHU8ZPoL$F--SN`iJmAOt z;NQH_ulXb%^GuxPpZL|q`vy7megb=+fxZ90-j`tSSFrannEN634Ve2O_YK(lp?2;Y zw&%V9dtZgU-@@L9Veikd_ifnwIn21Y&%@qNVDB@q_aE5%672m7_C5xCe}ld6!QKzG zJ6`Xf*uAg9-fv;=!?5>f*!wo@{T$}Lan--dy3O+k&(rR7OyLhlEYPmM(scXhKWi@= zTGoQjxO%a6rCAHFKWfQ#h7HR)(xgL|Zh!Z?vhH;BuFJN&Y*p5#-a2);cFxtN|7Q1} zGp;|KUwFs;W~uh|y7j8Gv;ozn5XZuWirw7wq>t?DszG^8oB~0_^hx>~jVD(V3^le)>z+d488? z+PT*{xSj9&E0f3UxpkZwc31MCb60GKZa*Tq(>-&v|M>l+ zo3HwQGVwok(Z|V*i!~zrM?cjb{nYl+PxTZ1RR7UWYroM?Ydq0UYn;&!e$zj{WjikH zj+gf40YByk|K^Q;%_s4gXW}&f#IG(L^^z~@{an=!Ry$bjV6}tQ4puu@?O?To)lNHO zw>>$5)ecrWSnXi7gVhdJJ6P>twS(0TRy$bjV71Hk)3t-u4puu@?X;tv?a>ZaJ6P>t zwS(0z+fUaHRy(+(UNG-g%yj+^qfi5*HWytV_4Qeg6LB8FuO2 zzWk^6lHl*8j|C4O?*B%{59b>Ir_4>$@F{C`lFJgpZ4$9y_-y&1GoLO*dzW0x_p_;xS9*bCr3Zk9{tqz(NFag{Z#+a zPiw!?Pis8UPt#bS5B|*?{hCkWG0((l{)t~*ZaDt)cA?vrS-0OS&$XTJ`mFu@rNaOG{L^-$b(T&0 zUMojDpA??|^iSIJMlP53*Cv15&O3Se^4ZwGbmOKgCa<{M$8C>xrQ{hWebj!q*~-Za ze(+Jd+Iy>1`-#V{R@?8{bB*NA;pgGwewmE_-@dSBGX0Jkzg9Bwobcw_$;7$j>FXpD z|8d_GW?Wm%yKdUI+475OA0GRcZ2zC<{!{&|e#Dp6|KGcful;Uw?D!f_-&e-B#<^9G zuUg|@b^fpFxUf53+M5Ubm>>L`H~KZ7#ABX`)BF>^x^&b_W?pt=b;PcYusXu(2&*GZ z{)rP-M_3(Ub<|ECY)^h*b%fOsR!3MJVReMn5mrZ79bt8Z)e%-lSRG+?gw+vNM_3)T zqoeK75mrZ79bt8Z)e%-lSRLV2t{UA=yYq#-KF=IEs{P>6!VAqBwLqs7{^EC0cXXQ< zv(2@)yw=|Lc;USkc&(kf!-%w>b?wM@qaOc$Tk8Drd z@|9{|X}(vJX@A9Ah4J&^;E`#^|2!MMmQ26>UMWmGD{c0A+KIEv6@`g^g^`6B*IXYJ z9&^we)xP;^V`}@OzZ_HjJTmCb>c8vKV{5-}TsF4GbIZ45Yn-E&8P^*BgX@f|T6zV}9^&-ssnS5|4Q%PV-Ov>e5j!xucG-I>PD*t0SzAusXu(2&*Hkj<7mvCl9tq zM_3(Ub%fOsR!3MJVReMn5mrZ79bt8Z)e%-lSRG+?gw+vNNA2indvt`=5mrZ79bt8Z z)e%-lnBU*ox5M`xzss{f1m^d8_Km>&j?aD)nBVu=X9DxPKl@K$_5-jl1!i9X`&D4} z6B?8AYHpZz&7<6_?q%Ujh4e=nK2!rM-E;kNLsBd81$RNj&D6 zIL$xtt4l|{Wd0uS$m)n)9bt8Z)e%-lSRG+?gw+vNNA2!kqP_c?)R8vo2&*Hkj<7ny z>IkbNtd6ic!s-aCBdm_FI>PD*t0SzA+R@SW|Bd}u>~HkCWgi_(9@t+8lOOio!Q_qo zcrf{7pB_w}*}n&qfA;mk=oR}mlF^HOfZAi`R1+ zll_V?da;iYMlbd^!sw+Py=;$O`av)KqnG`nm+_#NaiW*;qnG2t?s#c$9`Iv+@NeGe z*L)I>c_vQtPyFh_xYSGL+UUsSf%e$d5mrZ79bt8Z)e%-lSRG+?)J`63PkvzhkT+Nz zVReMn5mrZ79bt8Z)e%-lSRG+?gw+vNM_3(Ub%fPXJ387P9bt8Z)e%-lSRG+?gw+vd zTd-H%F^Mil$M!)8hc+4|#nt$R~myUYL9d(4sgZm`a5xY9V>IkbN ztd6ic!s-aCqjvXy(%yZc>PQ=Pgw+vNM_3(Ub%fOsR!3MJVReMn5mrZ79bt8Z)e%-l z?dWLx|Hl4R-oNm=WuHGx9@zg6lONs-fXN&03&7-)_XuF}%=-l}`RBa@7`-OO`xh{J z#lE*{=luoS^Zo^lAKt%!@gMuolIfTCFR&92?_a>g$@>>Ddhz}Rj9$Ed0i&08^s+sA z=?A^^k6!kRUdDr7#))3Wk6w-oyW^$3dBBhP!M}N?!#eQiRz1T+$qZhxOX=mTH?b(kF;s3O|^edg+jT^(U{gw+vNM_3(Ub%fPXyZh&9@4k9Vbl z>IkbNtd6ic!s-aCBdm_FI>PD*t0SzAusXu(2&<#^|K|RG#luZ~!%7bo zCO=)~c`nSu3WWm`*va4KX_eP z|HRLidzAH0{IAiotbfw)F&7mko^59<>z~BA=zfLKYwJr2Gp^NcD~w*+(aZMer62Ut zKYH0OdKnLT87F!fKYBSX?2ecA<^ezE2mj`ce$6NGm}lZN|HQ8@9rco3A45l&JkTCi zM_3(Ub%fOsR!3MJVReMnQ9F6CJ^6vv5mrZ79bt8Z)e%-lSRG+?gw+vNM_3(Ub%fOs zR!3MJVRh7wjO#Gt;7iL@!-CUUQY9|l2CqMcjZ~7;n_Di0P2fd6F zy^J5d92a)SOMCNxAM=BM^G3hslX%QCahiYPSC@`@$sKis)e%-lSRG+?gw+vNM_3(U z<{jgL)loZnus!*K@k8EVb%fOsR!3MJVReMn5mrZ79bt8Z)e%-lSRG+?gw+vNN9~SR z9kHt;td6ic!s-aCBdm@v<67nLL3s@`-uX{1OdftStT6eRx6g(3`v2mT!sPQ8^9@cr zc|Q8#!svD5F&CvBz2@EU;$-xSeMQy2@0h~0A9>}a)lb)5FH6S%Rx@6nj9%ycyD;(W z+xv>N6X!4YDop%)4=T*Kwz#n{>Zxnor^}&%|l|iCLqv75mrZ79bt8Z$tV57>IkbNtd6ic!s@7IkbNtd6ic!s-aCBdm_FI>PD*tD|;wv^_e)>IkbNtd6ic z!s-aCBh0vtdGGIe4Kv;?x*t=o=c^7aOn!dzvt#S^Kfc#-$>j5I%l{*pJa_-c@yY15 z>e2m^(d+8<2PC5x?{M)q7xu446{h_jm!Ft+{G7YU>f%dM$8%VdD9!$H{3& zuSfq-nE3zmufmM$wd)EqUhU+;_T)!DidM_3(Ub%fOsR!3MJ zVa9ddxZmV8%y{?cvPr$3?>n$C`Pp^;P3!gFt=neF??Q1BHqI z>&16YJL7tI)545bJ9)4@`Oyz~(?9vNU-E1`=w+PfW&G&nxUf53+M5Ubm>>L`H~KZ7 z#ABX`)BF>^x^&b_?x-WIjxhPb53G(b`J`W19bt8Z)e%-lSRJ*K2iub$SRG+?gw+vN zM_3(Ub%fOsR!3MJVReMn5mrZ79bt8Z)e%-l?dWKGbcEFrR!3MJVReMn5mrZ-aa}*U zPhP8x_sD65$;0#e%~7xOL+6?^Iqz4U=Sn7@S1&eqGI?I*@OhHa>z^Obn~YwE9x;D1 zdd2U{)jsnL3)S|Yt@^WM{A_XKBFXq4Go^1b{qD8kV#(+=bC1Q7iSv%3g^9n%B1@#5 zalO7#VaBVSJlLN6=!d-NpM2Ucc{U#OGEVd|e)Mu&*c~tJ%>#bS5B|*?{Vp&)pTuLH ziPQWOzq)kPOYW#6td6ic!sHGAusXu(2&*Hkj<7ny>ZqMO*q;2r>IkbNtd6ic!s-aC zBdm_FI>PD*t0SzAusXu(2&*Hkj<7mvM@QSEBdm_FI>PD*t0SzAusXtw>*yQXbzFy^ z_p8F>;fcqGr=9%F()Xd{%-iILlgZ~H>pqrDp3fWiL^679`{dKf=r!{@&n1`p1FO?Yr#pS~7kf-gI;_{@?v%OfvnBUtwG_@oe1f?PTISbI*5@(QED1-%Vy*qmL`h zc(s!U+mj#tkT?C4Px~d$#)DqQiC)HE?vrI)spItV(%wAa$Nb>myybN=J)gv5o{7`^ z6TiB2)JyKDBTOD>533`rj<7ny>IkbNtd6ic!s@7PD*t0SzA zusXu(2&*Hkj<7ny>IkbNtd6icYUjGOJvzeb2&*Hkj<7ny>IkbN9Qz8hE)DZ8_M>I} z6FByxWnC0F_7!Hm6gc)3W*rqc_7!G*6*%@4X5AGy_7!G57C815W}Oz;I+NNXj+`U3 zkNA@D6LBZwKgN?xzcJ2a;)(Gm6KCWxnfN1*$&4%Vm>l~Dt3CD)*7mXQvigbrnALym z)2#i*{>>Us?CY#?#(vMNOT$>KGYMml>n8i9eOyl^hUs-CX@mc`{?bmraa|@8Ph79b z#2MFp`Rw#MlYF+LUNXNob!2tKu8y!e!s-aCBdm_FI>PD*tD|;wv^_e)>IkbNtd6ic z!s-aCBdm_FI>PD*t0SzAusXu(2&*Hkj<7mvM@QSEBaEN8UnHv|c6Ef+5mv|iY=?TG z@qAS0UF=7z^NzY$>K^+F>-Av$F0KLVcfr>0g00^LQ>V-8(E454op;vn(vS1b`d!$q z-vtwo^Nu*3cf{|!V_eR=KGW-W@!8lvSld%COF!1{qK);tVC#3m*6)I?-vwL0OS|K> zeiwH9pcicYF4+2AF!4C=h|~NNe|+EMXFKX8qiIK0N9^hdt0SzAusXu(2&*Hkj<7mv zciyQZcKo0ttd6ic!s-aCBdm_FI>PD*t0SzAusXu(2&*Hkj<7ny>Zsj$r;gaw5mrZ7 z9bt8Z)e%-lIQA9Rc^CW9s=l!wt?C~83hVU{`wHv*IrbIS`*!Rrtk+fSE3EhV*e6)$ zUF-wRdSzT=*qwK@_xlb%&O7}3eMi53-w}`Vg*cse#P7UgT+X}LKUnRtf3UWXeV5fw z?8mJBW1nX2H}-GVcw%2?jWhOp*7#!|XdM@J=N;|+zQd364*!1N(XZck#N)gpPUju* zJMTK`C3n;jR!3MJVReMn5mrZ79bt8Z)e%-l?an)O#IBC8I>PD*t0SzAusXu(2&*Hk zj<7ny>IkbNtd6ic!s-aCqju+=I$~ExSRG+?gw+vNM_3)<*jHHRUF=7z`chX=-K~Gf ze6ju^Z2d#n`iHRf4`J#YdL3H-P`mTa`iJ^)-dX<;yY&xY>mS0z>AWL;=N;p6-cdhL zJ9PzZZ~a63#D2^=@2r1_-TH^H^$%g|AHvo@)b4n#e~8`shp_bzVfuC6S^p3_ahiYP zciwf>OYW#6td6ic!s-aCBdm_FI>PD*t0SzA+MRdmh#fzE->D;Zb%fOsR>%D8{{?j{ zsUs18C+9Ov>__A8=j7N|$luk;v9FN7lapg#A%7<)$G$@TPEL+}h5VhI9Qz9SJ2^S_ z3D$Y%IUQVA*qwK@_xlb%&O7}3eMi53-w}`Bcf{#DB7Wx=<8t1`{=sUG{e!iA?7OUf zVn1f}ANw?Gzp;O_#uNKGYn-v)v&Qc^9gGXR^N#lB0YByk|K^Q;%_s4gXW}&f#IG(L z^^&<(JF+@rS4UVKVReMn5mrZ79bt8Z)ls|iP93qUBdm_FI>PD*t0SzAusXu(2&*Hk zj<7ny>IkbNtd6ic!s@8q?>lwGu8y!e!s-aCBdm_FI>NE9u+F>Kk5=`K{b*J9*jHGu zhuBwGuanqUSg)VhS6HvB*jHGux7a6Gufy0s$of>yN9@i!+B@&?idM_3(U zb%fOsR!3MJ;n-JL=UwbatNO;i!m4}hE3DT;>?^F-N$e}E*H7##tk+fSE3DUB>?^F- zVeA8~*C%%89qpZW_;KFh-+4#B&O739-Vvwsj`*E-jLUf!`v zf9%t&{f?RWff`Tj>#T9ce$N_z>;tXi!tT7Iz4Hz~&O7`&@95WgM?B6u;&k2-zw@r6 zUUEkrVReMn5mrZ79bt8Z)e%-lSRG+?)b6}fN9^hdt0SzAusXu(2&*Hkj<7ny>IkbN ztd6ic!s-aCBdm_FI%;>`sUvoEgw+vNM_3(Ub%fOsj(vr7-o<{js&DK^tGdU&!g@W# zzQTH)#Qwf|{lvb)dR@i7!g{^MzQTGP#y-$`ePVas(cXE7ALkwZopydxgx9dSDE zh~Ig~xSV&ff3VtP|6pw&`vg!wchnJ9M_3(Ub%fOsR!3MJVReMn5mra-&O3F) zu8y!e!s-aCBdm_FI>PD*t0SzAusXu(2&*Hkj<7ny>Ikc&cITZsVpm649bt8Z)e%-l zSRLWmS6Js=>_@Bm#(uP_d+aN$*F)?ptk+5G@2l5O>?^F-RqO|>*IVo>tk+@e1FhF5 zcIO@Kop<>Us?CY#?#(vKlf9wOTQ%CIT2&*Hkj<7ny>IkbNtd6ic!s-aCBdm_FI>PD* zt0SzAusUjY-l-#Yb%fOsR!3MJVReMn5stsN>b#5nXjR|Xk5+Y$eTDUUh<%0iI*I*# z_4r_yraGI4nNL2{5$XH*Lg=g&O73C-Vwj^j&V8f zV*g;Z$Ns_EKK5N!Kd~RP`j35@wcpskS>uU)oi)zb?^)xIeV}z**qwK@ci!R0d53@J z9sN4*h{t(HoX$Jqciwf>OYW#6td6ic!s-aCBdm_FI>PD*t0SzA+MRdmh+Q3Fb%fOs zR!3MJVReMn5mrZ79bt8Z)e%-lSRG+?gw+vNNA1o#b;PcYusXu(2&*Hkj<7ny@w;T5 zcd;L>>Kpsfs_wC`uwDIkbNtd6ic!s-aCBdm_FI>PFx z-Fc^u*wqnMM_3(Ub%fOsR!8`!^F+!S7XK%mC*t`pYDcYa&w_zH3kLQq7}&F5;5nzC z1p|8)4D4AjuxG)*o&}?wvtVq`87r`7!NB{&3d zXTiXp1p})cJoogoU|`RJfjtWb_AD6KvtYDy7L4sV3kLQq7#RPY1p|8)4D4AjuxG)* zo&^JU)NAK?CbfIt_EoO!57~TT+ht{Pv??w`)H)E&1-Vziz)jtW&-t@cgk~^E-Vq_6x6_A({3^ zuG}?wNcef}x^Bt%-*-~?WcvMLzMjd%GpK8?Wa3==uENBB{zARe&bap4pm3-6Csq5w zH%+eXFW+ZM_4Cn8-&Oz1UiMw>x6_oRC zzj>oy^GQ7BnK;cq@vBQmy=3m69a$Z*t0SzAusXu(2$O%}gw+vNM_3)TqoeK75mrZ7 z9bt8Z)e%-lSRG+?gw+vNM_3(Ub%fOsR!3MJVReMnQ9C-?9vxwIgw+vNM_3(Ub%fOs zp3u2-d&MEI=e4@|OFuNHo>2I#d#5&c-&^>F7bZ6+&oV08+_wD0rr*HAmw!B=xoob{ zY2RY@ubcSAJ9&nC#y4{x^+xjV-}$mRX}vMY_YD5BS+4h+)&9!sg=xRhWn?5OdF}3niT|bZ3p1|!t}VR5#a&wMi!3!`Yy0Cb>DuaN z)-SrX`X4lFkJf%SnA)Q?o)2#5*&63MbM$JBzxNuwTE~Um@zUNr;K%&n-@MVU`6M3m zOq}MQ_|>JOUUEkrVReMn5mrZ79bt8Z)e%-lSRG+?)J`63Pkvx^gw+vNM_3(Ub%fOs zR!3MJVReMn5mrZ79bt8Z)e%-lSRJ*aqwUcVR!3MJVReMn5mrZ79pU(0vT?sky!X)f zcSOAR(D?U7yuZ@;cSpRx()jntUXveg{5vJyUy1jL%6^r2f2Hy7ns^_j@$a2@--!1^ z^Lr4xf8WvGzwhwl-*@=;?>qYS?>pl0?>pl3?>pl6?>olj-*@qzO0~y(Dz$yQ-&6g> zdq35Gybo0SjrW9VJn{ZejWgaWs`1DBMs-}+9WU+81Afd8{>>Zxnor^}&%|l|iCLqv75mrZ79bt8Z)e%-lSRG+?gw+vNNA3Q7r;gaw5mrZ79bt8Z)e%-lSRG+?gw+vN zM_3(Ub%fOsR!3MJVRh8*-*@VWT^(U{gw+vNM_3(Ub%f)b5YCy%?~XW!f%7Ml;~WOg zrAUr*DmZ5%InLAIoQdQ(PlIzNlH)uL&Y4J#^E5bTB00{};GBu%IRAumCaOKoX{hbv z{Dx%w#JLX1_>c1*lIb_jfk-BvI3FUJIOCj&Wa5u=CXyLfoHLOe=VnxUoSRYG$N4AK zPn>^J{m1zywcj}Zq{b8HnQ+cT`i%2WIAPD*t0SzAusUid54I;iusXu(2&*Hkj<7ny>IkbN ztd6ic!s-aCBdm_FI>PD*t0SzA+R@SW=m@JLtd6ic!s-aCBdm^aeE-z%yO`hgz8d%G zdcTePbiEJ9eY)PC<33&Q+i{<+_w%?<*ZX|jr|bQ{yf0b4@38xQM|;2T@ZPD* zt0SzAusUk@`%WFPt0SzAusXu(2&*Hkjxb~7xdm27SRG+?gw+vNM_3(Ub%fOsR!8mV zXnS;o)e%-lSRG+?gw+vNNBIBG=bU;jtz%?OX~*ejxx$|1n)c~uxx$|13VW6->{+g` zXSu?sPe02Q_AFQJoaJhJ&T@r4%N6!4SJ<;$Vb5}fJOoM{Vt_AZQn&cKB|dl&ZXUD&gC z(?0#|UAUuOGJA;~BkUN{K7EX^V}u=3dG-v7q=!W;bh+ji^e&yyD& z^-a6_dgU2%*&!3!J^xyG>ZGsRRh}t)*EV0bJ$_Z5Ee{#~RlDU&g)iRptM*?sp*M|h-*}=tXJQ|4etAx#{rH{B^BaB^nX^1w;{Q)gVfwvg ztMWWaJOdsrOq||J6_tG2mF{H{F^uWHJ`*|o{7`^6TiB2)Jx|6 z*^$)|yE?+^2&*Hkj<7ny>IkbNtd82z(e~&Ft0SzAusXu(2&*Hkj<7ny>IkbNtd6ic z!s-aCBdm_FI>PFx9UX0tj<7ny>IkbNtd6ic!s-Zba?9iG0WW`-f2S};d5iUjwSDfG zn)ZVixU>Cw!yl4gKIQuM_;t#82bVv2S-aExIW5+f{a&EA1=Xd~$o&fO3A&F?XNbKH2=NwEtV2@BIGa$?xrZRQv69 zbUFf`Wj@TYgp4yJSwVXk=^y8>lm%n-`w=!|&P!PA>fB^7FL294p10I#>J2 zz{2snaATWq9(wZr6IU!_pMQ%U4?OZ>>38VChd;2(-X*rPPk8x(p5sc)hc3Isu&q}u zXOr#O-T_l3vx>e4L!r_wKd#hS(1yt@?t9Txvy z6MlKY+lDQ*<)q|gRyb?elyx^;3;TWN>^kg}hc8M#@$SWk_51GQZQ{_YRI$uYj+_7&qE9^=n-wuozZ#FrfL4v)CAeT-vxj3+t9H$29f9OE7y z<4=x!43E5IJdvm2k+0;)-|)y|GJVCKv-D34*M3uK{?KOIm!3^KpIz>dr;_p6|FcJu z>1*wSh9wijr7I6fCbpycU!P3O({8#rnX#-j%Q?xfY}Kds_1gZk4*%zOFQk2kOJ*8= z(f6+=FFdv9@EM;gwS%s?sQd8a7yLZ!`<&Hv_%SDcpZxpxW*ENYer`hY4{LWGe#yVeciDVrbsoOP8s$6Ddp_5R z_k7rUKI}ao_MQ)W&xgI|!`|~@@A?pdvyF=S9sdWN3~ZyS9p;#k8Hn~R``pVk7!5!s@#`4Klayl+w%+Wb>Cs_*slw( zGU3qnU%Qt3)ggaBwEfldg`fECq3vHcDECtA*AFdB`|Xx2_cZ+UI=3+XFZi-B{m#B& zxz`cTl!1kb^VjzjCjKK{EzG#Cn0{~EWYBTdK5^&cYy18C_pg3VjD5xWKl=Rvwckzu zd_s-q?dMLYac{Y?t?H!0ZPq+oxO(#{&4?PE~B)Aze&OVCI$PO6zp$Ou)j&c{w4+cn-uJCQn0^C zX?K44n-q3`lY;$C3idZC*x#gJf0Kg!O$zpReAwUaVSl@a{p}w1w|m&%?qPqshyCpy z_P2Z3-|n@$hvBC^7-dh3zul7`f4hhM?H+cI6YL%**ga0Ldz@hRIKl35g5Bc;yT=K3 zj}z=3C+$D&Rg3SD|INK>?#CvF?!kuLgAKa}8+H#i>>g~`J=m~&uwnOL!|uV>?)}g` z*x22J4Z8;$b`Lh}9&Fe>*sy!BVfSFe?!kuLgAKa}8+H#i>>g~`J=m~&uwnOL!|uV> z?)}g`*x22J4Z8;$b`Lh}9&Fe>*sy!B;dnl*?>_jh3U=RBfqhp6_FWa&cU55DRe^n1 z1@>JP*mqU5tC#PpVE0`W*mqT6-&KKqR|WQ671(!GV8+F7Ot9~&z`m;j`>qP?yDG5n zs=&Uh0{gBC?7J$k@2Y55FW*(c?z<|m@2bGQs{;G33hcWou^pt1@ASdG(+B%bAM87Qu^pt1@ASdG z2Mzn~Gwi$1u=4!@m0r`|h)L_43_k?7sU9`|dOByU(!iKEuBI z4Eydg?7Ppf?>@u6`waW;Gwi$1u=4YgaGdea7y)&#>=4!@m0r z`|dOByU(!iKEu|FfUOY$TO$ItMg(k)2-q4Cur(rJYec}-h=8pTpf!m8WFHHB4BGoz}AR>tq}oRBLcQY1Z<56?doNX2<+B~ zfUOY$TO$ItMg(k)2-q4CaQvN8zrU=dgWXy>u(fnxYw5t&(t)j|16xZ6ww4ZTEgkLZ z^;1oxQrpd1I^@S%IEsw&oaY%`w=TW3V;HU~7)S)@g*T%?MkY5wwHaY+Gs4zpgssg8|KCt!(|Wdy*BZ94HEdyP*uvJZg{@%=Tf-K% zhAnIjTi6=5+SSV%w%Dy<3tPh$wuUWi4O`e6wy-s9VQbjJ*06=GVGCQs7Pf{hYz2IR37zHEgZ*jon(`@Pa?p zY|p>rto2P!to03B>sz~eS?e3SwZ36%eZ$uJhOPAtTk9L{)1hX&XCh$tOa$075n#_m zfISld_DlrWGZA3VM1VaL0rpG;?ar^C&bIh}f3^j`fBkd@P~3a}4>|+rr?b+EUa_v1 zdneeF9P4_?>{X6+y<~oWjCH+aey@ymy<~o`jPI3dk9Ex2KGrvr@e}Kw$@q`;(B$0n z{J(it+D~Un7QJF!ujVt>^=h7DT`w8EVqGs8y<%N2dHV0m)gJ4ZwSBB_CZkuZdnTh- ztcNC}SFDpJvqwGFPm|fB9_y;f@xAf?I8*Ycvv-SLv96c-A)m3XmrR~xT`w8EVqGs8 zy<%N28NFh?vf5)Ev$l`*&1C$w3xP73+G*=oRaF$>n}n7<;T^*7mW!nT(%U_e{ortcNC} zSFDpJqgSk-CZkuZt0tpYtivXwSFGzL$8%^C>wU@Ww~2MVWZsd9b-iTXor!h5WZtQX zb-iTXwTX4TWZuDvb-iTX*@<<%WZv0{b-ikjb+Ot$*2|Ld6YFTn_>c9qWcrPDw`Agp z^|)l>jCHzX;*WK`WX2WiddZAeJ9)4@`O#0_m!|tCpY}_hjR(Dq6J3lSy&M;I$4h(j zfFJXNfAdDa=975LGjW=K;#U{O73+F+ys_SwOdeugFPZ$r`d~77i*>`~dw3wIS37yIJ^9fOdDB1nv|sXUJmlXv(Z%@D%W+|MytFqD_%T2DH*fT7K8eRX6Q}tn zesy77v94Fg8|!_^*bzO@)qlQ$>cNE^^(bRtm`GCSFGzLqgSl!C8JlY zS5|wRJyYAqnKa4xiL+{w@gHZ{B-3x4ZIetqapp}jamHCV$>m{RCtm`GCSFGzLqgSl!ReP+9)%LMo zmW-cRM@z+l|6HlziB@<_?(UiU9zhv?dXZR(P zpE$!WnY_gre#zuB&hSen&#}&!j9#(+n2cVrE}4v8@poml_c@|4?PI+x?f8jxv}F9p z`dTvm#=2WF@x*#uGI7Q_T{3#bx?VEligmqY#;ct?*q;38hrH>ZeA+L0HXibCoakcw z=;gSuJ6_tG2mF{H{F^uWHJ`*|o{7`^6TiAJu2|Qr14Y-oCp{ zdB(f;me<<*9xuGt0}yY^ z-`LllOgyo#J()OTUwbm~$G-Mt#ufY8lVhKLwZ}gF+CFOAR6kMMruvWCHnrcVZByfk z+BWRJPoGiShJE?TQQM}D3%lc`y?MZo`N6+=qhIq$Jm#4=%|G$0%SUIP+7A2j!u);b z-fs?S*ZkzNIR8QQ1a|Ep4$GXC4dzcc3e|4p<@j?Xpm z`Q-4|gx}=or-}Zm{jZmozwv3m^71#O9Y1>yEq@o|f7J({OgsG^KDNwF;(6=Nv1upH zAHRG*nfUwvq5SQ@xZWCD{$7ZFsy+It?W3RSC;F-Wqo3A(qo3AzqMz0{qo3CJqo3As zVRyW=HxKwRKlnFq^lLte$2=3K`6qsLp^oUZWvAqL=icYYHIR2%kSHET4`ExudnxP2X9rL`Tuz0?(GS0m*@E(r}k?vT)RA-;^E@pIY{J(Kaj{_VYz>9_ar-pRx>bZ~igCC;c_vQtPyFh_d&H-#Se~OM_noEPVe`Tl zAJ?<}YH;BT7VX-8u|Ro;`ni=mw>v&p_@2R2n^&)0By+g;+!LE8uI!sUpxf8YDfca! zeA8)PHkZG%Sn}$3{io?VXL)xI`+>hH&oi_?@!;~Tf}f2~F3%_UU*m-G974Z$^()UC z#Iw*$Z}e+EiN`z>r}-y-b(!(bZtZ`z z7@GIG;}+@GUbAxHUH;XzJ^iD*(>`{#uI;A>7Vdh{jP0>c+?Do&SDCThW=eU#_?K_b z&|coV@JCn8&|W*^o!O?}aWk}k`26wFz{hqDyZ~s-#Ixg&vm-glXKjsJj=8b;MC-InP;xzxn zuP!@nKCQWH@YOlq&6fVY*}s3`8D^i_Y_nS7p1r>Zx znor^}&%|l|iCa-~^;ydM&$_e0|Me#p4I zAMXFB*Q)*Y{;${eH=Z)8`q}x2(bfM+8@^Hdo$&D+HJ*R%J*LKa>uqCd{F9y>Q^$qf z@zUNr;K%&n-@MVU`6M3mOq}MQ_|@g66(6tj>*84+t2+LE;v-exeqTOZb-%gu!}WSN ze$|KSbu##4ZA&E{f}JcncDA0FFjM^d4G#%Yn;&CZMy|!NLmTK?O`{vqymKkrV zes-Vx#_InUo83_Ree|m9YdniBb$yMq=h*9N{0}~QT^$#8^`gCc;YYpjuU_=4Uc{qb z#Hn7yuU?Exy$<-}ZPk9~aktm@HxIm{`ssJroz?%T>kp~@PW)gDRmen@-ohxqY+h=1>g z^y~eQc)TAHr}snR_kPH@ydMtR>auF@yzk|;{nP`msD5tR<;v>+^`Bo=`~CF`SJikv z-1O=i=a1)KUE|;E)~oBduzNqGz4t@>ct6Cy_e1*ien>pt4~f(JA@O@ZWL#^nQPwUP z?^g>ICJ&=tE_H;+&l)=wCT~yQS!xQA&r9BaCZEm7^XC(vPA2~ozI-YfU2b{($z=4p z?4Bp8{hWV4UfXYW++)f3+2+VclktD~sijU4{r+{>!)Yg;u5%S8&V4R=DDA|*`8I_a zSEtnrGhXfF!S>`wKjcmSd-H%F^Mil$M!)8hc+4|#nt$R~7sjPt&kw)5+UIzEXl+09xO=Lf z_St)@|4%QxulBps`uEp(Cf|R5jk8bJ2WtGgF8n|p7k2fcy?WtCz3{JI^s8RPW1fjq zy@+4EUYg~Zs@Ef5JXP(-j(oDVKjDQZs-IWhe!Tj>ZjQ%mzrXy;V>O;ZUq4#o{Kxf= z*7#RF`_Vcs?CM2(^}>&O;a|PzSG|Zwy@*r2h+n-JmwLUu;NRrrx2pY|-;As6|Goa$>gR*szFGa>H*ietck^*?)Oc>%`;8js zx%0kJd8t2ug zjj!?Ve8~7ZF6`<>d-cMPdf{Ka=vTdnN4N~Uhfb^G!meJlS1 zz35lHh)2DMQ@w~^y%?8zvHqr=bvfI!UZ)?{@$}F7p8c}!XFRM28Yk<7#?ShpT6zV}9^&-ssnS5|4Q%PV-Ov>SCQz>Zw|%6t+$&Y@JfrI;F66N@44i!qzE;ty2nH zrxdnMDQulm_~7X^RAFnD!qzN>tyv0NvlM=<&%3$)4}ahLz2=uEEV&;1oADnsAARui zCnX(#iMF^Hp=mAD2lU*JDca#X-v^H+?&|w{Nyw^6MLPYya|P;aMK+-R|3O z`LuUEboTZiQ4`gEFFCTDh17TVcbao|DrX7(u<={XQJam%XGtGSWzMTB#5|1`3-}_Q>mwARYoAxTa$dDn;!b3--{rHt{ zYG!+&@Y1hd*?c!|X|vYLgPV0iqZJu2(6{5d4mlWZ)RTavC1Ppe7Lq*{lW*6`Rpcpx5?yZ>z#&GUf`KK zlJ`BlceC}1Lz4Gise7}`op&Ywv0K;XoY*7HwE>TgebF#&);sjRWIj9pg!_}}tM7xi zB@^e$r{9uHoENTrQ{{f|Utili{O@a%`RvPkT%Amuqkey7|TN$@Fzg^RHy$jDnrX#JSj-=T`pkowI72EzdtA zna}RF`)SF*zuM;3zI!M0*%$BKJ()P)ymFVyN1pWSWcnJr z&8Er3dBOHuBopWE@$QUqeiQH47-##+?~?iK5wGuXZ>u`W~O<&Chxc8I?dw;mo^(sS+N=MW%=wH4=vt&dqkgXGk8Sg zcEtS2VQb?5B}dyPK9d|in(&nzzMJSHIr?m(@8pQ3iI|cj#wKD-jxjYcw&WOV6M0FF z95j)a(!RZ-a^$SGiCosthE_EXp<(67eG?j_pU|WU{gOkgCiF`V4J(JXwM}SVKO5Ib z?JKUG8be%DHMY3cT4RoDuyrhPZMKdvuKiZMVop?!Yq>SfxW>5`XKZopbB|7rIZ-+0 zN^KK!sD3u)T&US8Y8J-&W6z7uL+@m*14i0_aZTYR@vj_;h>Ccca6XXCrB#und!mE*gs z_7&f0HHP@EtFgs*VCDF3tZm{uvwk+dV{2dW-CJXb@8lX=d{I+Ho@h<5l7neM{+s<@U=lsqcdFT7>xbwOszdh?m?Tlj!?{mN>?Z!J6K4Hjb?FBQI_7h+EqMbIj zoGEsqKP4&Xhiv8T)FfHy=-|-IP}Wz+8=lLH0^8uZA!cTrXMFi8t1(1I_pQtr++)K zZH9iB{QEnTd8WqC$A?Cwczw`Uhf`%4GJnKJX0=c3F0KB*me$l_@~_U%dSABQfL z{J}+&+XtRoE}8QS*bm7w)$Fr$9zN{xgOV2=_(Qw-!dulgoN+)K&n|&I?*R6^1K9Hp zV9z^%J?{YayaU+t4q(qafITw>_M8;hb5dZ>Nr62l1@@d2*mF`~&q;wjCk6JL6xef8 zV9#8DJ#zu}%mvsp7hum^fIV{o_RIy?GZ$dbT!1}uLHkeV?ELSav%|X;@h(TsHQu?1 zcRZ4L7bD*NNah`lc$XuYcQ@i)j%42Hh<_*Zu1B;>=ADuFd@}Ehgx_S|8HxU?J>G?= z?c*JZWcF(_!ymSWzxJQbOa1?HUTXX~_`}xlhppkS-RtwGbEV7u${POU#~S{yHT+>~_`}xlhppicTf-l= zhCgf#f7lxSur>T)Yxu*~@YhZaf7@?#Sy^+&&tW@_OFRCDb$TnAet$TxF!8+7{q3|9 z=e4^RCjOVsFU+{^yS6Yj@U>GL-}cnZ*Uzk9bZhlLXx1LB{cbR|M{7JE+|aW%&UNPK z)f#{AHF~wn^)6$F(_!ymSWKWq(u*c$$@HT+>~_`}xlhppicTf<*FHT-RV@$=es<@p)^`%dbf zcKZEdzVeJsJcGLSN;`3`eOF=PKYyX}OwPFW+MsZ!_a{~R!8c8=?JwVFO7%l6ef=+c z*>|y%9UwVx}0Q{d;A_rA;TQ~dYa zu>5^t4S(`LJd>9w&;P`E$1`7Nd*bghvHT4Z@4{wHUD{j2AGU@+Yz=?d8vd{~{9$YO z!`ASJt>F(_!(Y4iLu>eBw}wA#4S(1g{;)OtVQcuq*6@cJm(Ls4@W*Zqf7lxSur>T) zYxu*~@Q1D84_m_@wuZlUpEs=GkKG#nur>T)Yxu*~@Q1D84_m_@j^~=Hmo@ycTf-l= zhCgf#f7lxSur>T)Yxu*~@Q1D8uU);Y;g8)K{;)OtVQcuq*6@d|;SXEGA7)(YWetDq z*6@d|;SXEGAGU@+Yz=?d8vd{~{9$YOYgaF8_+z(*KWq(u*c$$@HT+>~_`}xlhppic zTf-l=hCgf#f7lxSur>T)Yxu*~@Q1D84_m`uyLwr}AGF(_!ymSWKWq(u*c$%Y)yo?G*sb9YTf-l=hCgf#f7lxS zur>T)Yxu*~@Q1D84_m_@wuV1!4S(1g{;)OtVQcuq*6`P^Ue@r(ZVi9f8vd{~{9$YO z!`ASJt>F(_!yl#wzJGsN!ymgf{9$YO!`AT6&-T88^U?Er#2WtCt>F(_!(Y34S;JpH z{{3YQf9%%qhppicTf;v;8}a-1mo@ycTf-l=hCgf#f7lxSur>T)Yxu*~@Q1D84_m`u zyLwr}AGF(xjjpPfHTF(_!ymSWe||RB)z!-y{@AVI4_m_@wuV1!4S(1g{;)Ot zVQcuq*6@d|;jdl2tl^IxKVHxHcb$QLU4I}R*CmM4^$Oy59x*Pzzo>z)o!a=er)Iu> zqUKihAGNq@zfq&B#uK%>TGuzCrdMnHQR|EE%bbJQ)rVK;l39<6v*MD8C(e*dCeAopE}8h_ zEV^XI6=%^UM_#L)bspQZ{-Yn(h4jyQk^QocWIU`d87J#b#$VQ>%DAvQUfP=n{Fop7 zn>YG3pTuLHiPQWOzq&9kYU-+2Jbx#Xhj`9TCO`3n!4nH@y7FaGI^k;tNEeUt9hdaEKEMB4GWWJYR1CoMJ-tvy{It@Phan?c52ev zo?5jqeyCv!z#W?b={oy>T(lLyti6($eV zbTvQJdWG}86g6OB@=0x2m^@Q67Dg{>$-?MGjaeAIs6DHlnzXj3RxOMlYS_Z~r?xGe z^EztY!sr#x$H~MQ&&|oiAJ5szj4PhAlNqme@?d-Nqo2Iar~4fFI{8QT&reA8_!sr!eTqP4{ zJU1s3e>`U=Gp=~fPG-E?$%F05kABFT{>i8Pl4s)~|Hg?f#$WD-Wh~eoFYV0(e#{U4 z%^UriPvSAp#A*JCUtJg%HFe1Y=HtDTy(wx?Dtj2~*)!uY4QElj`E)P>QDTDUNAQX>~8ero5!jEkDOFyqxu z9&As3^h4hCPd@FJJR1-BH%@dhe)Mu&*c~tJ%>#bS5B|*?{hCkWG0((l{)t~*7#B5l z9WS+8Ve&vtSD5@z>lG$%)PRM_C$(W=@=VQG7`><^3!@h`X5sSvHKN+7No#v*)x!9p zhAoVLYTLr}OU+xDc&LR76DKutVf3PQF3h;7sS7h+?c~As>Zxnor^}&%|l|iChkE8h5ZY z?qF-&!PdBgt#PNF8h5s*#vN>pJJ=d`ur=;rYuv%sxPz^62V3I~w#FT7jXT&Hcd#|? zU~AmL*0_VMaR*!D4z|Xfc52+&o*H+sHSS<*+`-nkgROA~TjLJ4#vN>pJJ=d`ur=;r zYuv%sxPz^62V3I~w#FT7jXT&HciO2DXM1YL!PdBgt#Joi;|{jQ9c+y|*cx}RHSS<* z+`-nkgROA~TjLJ4#vN>pJJ=d`ur=;rYust4#+~h{aR*!D4z|V}Y>hkE8h5ZY?qF-& z!PJ5~^Nr*3@5;eL4s1W);-uuW_T8-Ae)S8Jf4S*W?auR+{cLOO+^cP8EPtQIf1CJs z#uNX)iFV2Hxh6iJ9R8Z{n;iXQjXV0qKH#B?YWq|6y(JkxL%wa2@xRI!<(^Exmya5i zcH%i|`}dNGbIqAPOD6tTp7=7EaUHk&SIN;&wMRd-ee_fPL_gJk^wZjJ^wSzo^wSz= z^wS!D^piF27#DWOOMCNxAM=BM^G3hslX%QCahiYPSC^4}2Q~{2oHfU_*L^2610I_t z`HZy&G&9Xw_`~gvZ#Lhj?8$%jpQkjl{e1RpvvU74nzxSall@;U$Vg9X1zTMpEUZ?=8x+Y-tyS1nm;^H+VA)Nb~QIw&Ee~pc;dfp{5!9u8NU9eS#Q~wlH#*xb9(l>{*O;I?_Y3ca_4T(H>aO}R`PHAMxCPRJm*rQYnunY8dpEN z&5rL^p95C?r1tfff81VU+hW+wHRhYnzP^s->N&5jW8Cq8%Np~r<`?@{*jf4IffD^h*w{n#f~vXw^i1 zlS8W}@}3-8HK9jx=+lHwl|#SUCUi~av!Qn~KI1w_rmwg@l8G&@r(|M|>nxeE#Pyd< z9^$%8CJ%AF=3Iv3I!>ldT;IujHm>_*e8zl8rmvVM$;W-YS^MRP3CVXHvvu2?{!Q}X zGi~2)_{(pTH@RlV_TbTl_daHm_Q#V-`!^?S+`fHS;QuAsvY`G;mg}~ z+Xqf6K1XcWw;lb?7wPkV(RJ5xQElJ<_z49>6valtK(Ii`p8!By3Pn zu>r*b!46Ors?6vOkaX!EI*Za?X-hKD%z4lsX&e=1ZnXxQsisj?@ zS}>!930gn=LhVj>n&WqqZ{&5)&5+rj$H}#8g>*+A=R|65nJqfIdJU>?n78`~InmhyF~b#G&6&&;9rL#rEM z(5h^*#R@~R!?5&BYOkSN18o*%ki8F7LtHg>HPfni z`{EO|`|j3(^ILY;##$&eC(c$!Qe%$6 zsmUKzwKweY%nDWG3mngmA=2l*FL3+~Czhy&r}4TDcKf0Fsm5z}eEwba+M07BeAuP| zeNMJ}rynZS4Yq1ziK@cQklH<4mZ=V;vl}0*P+5C7r1miUR*iYcZeyViN2^BEKFmfF zzJBaXugcIk!48ep#@hSr4r;pS`Ha25Ne{oTvQ11Hp=UljCbupQ#2FcxZSt5EyyYiLdm&<>8rf%~2XwcnleeX~W7stf@~ESuv7%BX@`o{_;Xa@;x%}a1_=jqdf9s4v z_+4$XMlWw&Zx=Q@(Eu{FBi#IO(S zUl%|Bbwoubwp{0SbBk=4EM%7q%0ch%Jmxv4T%7L3&h40ol~Xwe?V>#C`#(9hgZ}yG zI)Y<9@irf;O!-{5RJ#Dv@_3DJ%JWfpoYy`-FCU??oD+-ue00#@_Mcz#kvxk1>{&i) z%;g+**qDzUJvp~AHS=+)Dd#+TQXXOrxfZ42xwzPl&jW#ZAK*Qh?>QV@`2+4myrDb? zReF!RI_ybb-lAy#YifUU{|zopW7mm&jXmCM_uyB!9>mUUoQ9MLwt>S7RGelXnD7!m z64(n~KSSyY_LUt^(Laj4#rp|tO4+0B9wR-FW61CD2(=wJ&dAocFu50>>(p-C!>0Ei zD7J<91=zNkUu)d`REX5!d@g-h`URO8Y&89bll}Rz7Oq9`T*98PsTdmKlQ z81^KcVve8p3!$kT|GMwLa5dpQwO91|4Xb7E$mcwNW9xrw7uHte_Y8xiK9?`^`-;g$ zzmO7ghWekL^$VrbPm>3ze&W-FQ{=?A6=>^!lDz0mIRdVoAZuSN!U8Qm^14MwQth<2v_Mh5yb1h45{6&)g$uOf^;A$o|8Yl{0Q@R{Cd`L`6q0A{DRsw`(&U~+)MJ}>wf5bx+$G+jrJ@; z-Zi${245^MXIDBp7tX_)QJ>`ov+?vQTm8ul%pYk&?P?m+@vNL36FU{TC!15dN7@uL zT4+iR**pdFdh&N-i1yo6`8zR0|BCx;F;2}jEvdg4e{Ng;t_(46%@nqXC(MSwH$%iZ zc@0~{U#?<{btR;-pA|0u+df#$|8M_Avse8cr>k_Ol*eEEI`HqjORfd|ji<$&;JQ;V{*%9g|E^24%j*^W>*W$Q0W$})RaGbA+cB=G+vJ6qnAwEt)vDfntZvT7Ox=>%7`cjFuhC2_ z_|2ZNeHxx@<>RO2(kVFDi;tOWPbOiL79TTDk4{9=Gj{0x#rTrQiz6ct$DaLoIT*T zFUBlqmuW0U!VY#q>}(8f&yIGS30*6;S^6|I>CJw&Z3-&pvX9M~1o!jo82d%&#md`GVwnV>R&j0JnmPl{RHS*|Z z1>LjkM{TVU+l!Bf()jk6bdQgvdzae7V;|T3tyOz0Tg=Bs!7m%kaN}d9K&5O;y*obdWcOa) z6FEt2jS5F(U0_T1G9{}?|5&}eBK;kNy|e0F1XwmtnPm_VBidz)cF|Yr*G;s`7VYw5 zMf;Plamk~G-R>-`m%S#r;QGxj!qVSak{ed?>?({ywUcWkUM5TbPLlqc#+3ellGKkZ zJuXptJXsp=yfiLZo=eOt&m}C+#qsc5!tz|g@?665T*C5P!tz|gQVyC+>$ev%%NFhO z+C{r;(JtLfqMG%^g8Iw;|BvISs+ZW{gDLf~*;+R#AgBeoj^m*u@%u+&%)7b<$^P?O zlXq2&P40EL4OzOkGdVljoE+wHFZtytp3C#Qnrh{3wlYq6E)jz~m#{pSusoNrJeROM zm#{pSusj#FOTX73uUGtbgD^k#|DA_gUiC2dt%ZHqC_uL8|ETCKeaDn&pHuoyRX5y> z`aJoat}@eZNlyNfsS2LZihSotfvR~-Yx0)TAF5Z0ZOCfF)Np*SIeE>|%BVSr=UOzi zDm1{}=2;Vc3fS_zvkauyB`@Bo=K7i03u_0YtM0sLL0<6wv#PyWE3(PcJXL?U*5q|v zi&cXsw;?}y|5N2N)SRr{PZP(rEy#BQbr8CNE$2tn*JiRldSzJHr(L;%g#4;_bH&15 z*Z&ISJ|ZXkCfCL+DNbSSj5?T=#kR0^hIKZtSGMRQ=kx!c+xD#%VSg2K8Yg<~bi6p< zhWs|o3u*~$bzaN2bpdGV&AwzBgso{@U+a)ySXr@`Cas45bUp@_?^}cCVSH>9bYF{lM_Nz} zt3%cz;tU@@EjFyhw-i%qm*Ww!$?*uw@d(TD2+Q#Z%kc=y@d(TD2+Q#Z%kc=y@d(TD z2#e2*oA0c!6YlPnjJm!*$+O0sz>`0}$#pXip}+K=gXpu~Arb~tDv@WzMPN#fHo3%Q zGZOz)C2yXy0b@7RAa62Si&?YlkcZ4&jmWiz_{~N_HBimNI+D4{|l>I|l-+ipgm^)Kd!5 zzLI?lrSByeRY;cS67$M)3CnW{%X10Ka|z3H3CnW{%X10Ka|u5lY>*;d3vGql`st_4 zt@en#B1JD{X6|!xbqn2;iWMKo&tGb%Y*|@A&U{fhrS_WN88Pp<0&GQafT5HOp$ZKTjI-D}> z5y;YYIHhCz(`4y7Eal_~S-K9V^j7UAOV{C)^6jByc`h-pJQv0A-(14-T*C5P!tz|g z@?665T*C5P!eWimo`dF_r|UvTNn063)5ZPuHOp7?Uj77VA=N`$CrH`P(kd^S8fvpG6)=n&brhECC@j}eZWncw`-?gX%XJi% z>nJSOQCO~{uv|xBxsJkOPdoB`WBb@P7Z9?hE<%ghGpiUP#;OUm7dsgtC5*jsU=w_- z*Ob~Dy>13A75mti=CD}OjN0ojHbclD6Y`WPEpXkuIoTzt1^uR*m`k+xsxbZAf9WeT zvKZ%Wd<(J|ztZ%UWHE2c8m-78oC zQ&^r$SdKwhj!jssQN%1PuSHm1quegmF83EX5tef$Eay;I&aJSVb78p_!g7s-<=P2v z8=_CO6FzgVD%DQdN_veWY9}1AzB1KLSf@gRYA5XbS&eEZTwnEDCC9no)lZci|L!h7 z={2C}Bicpn>(Q}#dj3MpE3Qfod@vWUV%TxMGx4bzTRV6vR?gL>KAoCOg5HiQsgcFJ^=|yJ z6OR?~44wF!EaLR``9&7-TVMG}7VFx!k$pX2<=^(VPgnizKTtF1?>I&k!GFiEoUrEa zymzaw`x{TP!FtGX=A2mnH~yf^^?%nT+U50%{&F6~IC6f(_;TLFymCH8JaV2zoO1p} z{Bm8C^^%>l^)lo>!t!H<*FSUxs{VF)7C>AA6!*J|>0bV^!`i zY9}lo+rsiOFDyS7gyrXmu>9N+mY-9?%6iGKmBjv8w%C6POV@Zixm{RXA4U8B>vgO6 zTTj&6mi9XHuS@qQFNW_E_Ai@7=zW&mWWxfK1+w$2`J$!+Tm9-hY%6R*kM%h}7rL9+ z?TY5W$&5XF$s8P#-X{^`Umre){?;Qb+IvXvT?>o;TgI@(IB&i+r*<*^uyD4R_h}Ed zh$sJ-3H1?i?z_tt@y|(Mi*@yh`M-95e3#ZJ`UuO96_&>omgf?dV-S{O6P9BZme(RI zuTgFnYnS_roCwRg5|(o)Eaz5O&bhE$3t_oN!gB3|`$jCI+6n&{wSsCVJZ0rds-18^ zcYms#@ZwMYR6F5*Q&&;#gx}v?MYR*|StWpKC%nxlfNCeVi`vQkMeT&eIHGpKVti3M zVKJ|$ov?^U)J|B$DQYJy;+N|p*G{y{7RQO)M_7KWuso))JeRN>gRmT%uvnvfyooi+ z$DzDN(MMjp++RMPZiVHX3(K_-mTM$@EAuE^a;DgQPB2P2KR6zfZcic~ zejShG2NTFmHz#0wmGR_@6OWreB^0a1rBaqc`CUm554prgpH zm`3fsKjTm}X9l_EusB2{Ru)PfO@Z=>w)~aqkhBawHk9|;)kBw(rlB=Nrp<%7b zaU%<{=#V)%ETs@{Ker_-YY`vx83-|>TorH3L~}K^>)tHXyKPGCi;rbPuYg^Wm;>Eu z+-L9ETpYLKnnvu+!(gwL)PK*kd}!WjMK-NpfXegRkb@!%@N}pJxz_IjY#DAzejXN$ zhG!$le=?)6eMkhwsjShAq8JSH4W{-Eg)#W~avd3VG1zSrO78w~9}atmla@}PEppe9%l^c`);pB^YuA44iw`H)`0yQ_UAoaY&5nG>g{QXE{?)h`!wz&K z*F60VgNnP5Kh6D$hW9&>BgcP%Z|@G|Kbs0sI>m;pT(7bgQx+6U-^tvS=GxS<2v?7F zCf8B_hE-=fl4t3B#WSz=Wc2=mHy5nQj^Fm-YqcmEzk26=aCC_z=kAV1Lcm^fLi1=$ z+_i^1>`@fV_U|UYI245%(Ywgb2crHBBA zr|lq*9v_8)Be#>4b*WVL0|{+xsomjc2@Krq$n`&!V&7wX^4i!kY~Ip?>^qpjxR>rT4GxS#+%ARt}5hby3pR|u+KKJGbGViiG zojZ&Q&HdDVa{VE+t;+uBa}Yz)xzB=L2QYOV`$4A|+^ozNYn1a4Te$+AR==cinkSZH z?x|Pg;%?=5o%)&_vbhY=58sdvr<7vn>9^!Mx1{f&p7V~p=iCpp(0ot6xA{AkPGDd0 zEJo^9wle2&J<6qfcVAKt-F}v#-P~8?unp4vhqGRjXBJEMCAz#JH|<=CZ%y8k-;622 z-dpUGlYijgz<1Q{;qx7H_p^6sI!JPhH}1y*}sM z^-cnY?TDg2&4(R_vpf6YixW8H#lAP@6pW?Mn2SA6(!JBzX~U1b-1IDJl(DmhoJ0H% z&iRNz=ke1dhWdvYB%=AE1LQ}$645gIAX)cQBCMt#CO67X#GCI&$RA=85xpditUM;$ zYsI6I^!ayj3>)rBz@q1oLB@1Y!X(v9VR;;Pr|fHvE&oe zlkhV(jvW2w8&=UhFvzMP0JzoyO@OyA-QCO+F9_}o<|;SmkDeC ze6o|nXAE~JAa`k?zMO&}C;nwL883gs#Q~X_f#)1PXIih?igUVb?<3oA;Srx#6Q4#P z_cnXRpY51c#J*&_6Ws@L|L*3yVDNygTyOT)tw_JbYp*?O3x0szqFFc`BiY8~n-M>e zy*hgnp4DOZDh)-8v47~;7-SKO3sZlSl{tK~b}OvLaz4vvZo#q9Y>!dl=+m98H#`g% z_1JM9n_;^457n+`@FpC3_?xWrFceOuzsPf^Y{IN$uJ5&Wo1j&}b^JfM(h0{XZEm-S z-i+hx*vi_S8y=3@mpK1#-fu>wemv&G^Q&S0zJ%6NQF{%F+Lq9~zMAXNt#TRJe9uO> z53cy1*pzu_y&qf!+AJP$gqMcJw$x;{^5FfVUm^+M$-V z0l&H*qV~R_8_{ASUtfMt4uL9xuRAx!hN6CB_P=s+Dtn#u*@{@2H=_A^RIAF@&`Mj@ zOW)mgh}zG!-ynTnov*n+)iQc^@-?d@)(6u@@ioin;W*5l#Mi8rb`!8Rgs)krKTpJo z$MLkT!Yh-}tsDE9=;Yg)0h6sNd& zP8~fFR)*|L&n98)Jiac!TsZ}HxxBCIHFO%j1+tf(9fJ9%lW6TzZw|rdyhMsexvl|Q zz0f|5uhE@mdm^w6U&kAyd*F-DS?b^YyE`T=I7gm-b`)+(-*qF-nJe47qDEaF({SZT zERSHfh#QXNcWmVvckBCLe0|=NRD0-!j%&|QY{Qy(;_R!l)s<#jE1F&rib*(uBCVq+8^=f|GTLnUo~t~Ixwi^;8d54N-IZ1gcb zN@GraGXo}H*vh;qYZRt22PKF2c{Ia%7A~&i{ijs}>9G!6M~k3d()&&-8Z#}UHx9LC zd(Z0&-N@|l6VPi4ZLYbe@N9W;0D(|uF8u_Aa19ric1+Wa_^MiZD zB4pQPcU-#!{tx+F;k14!zMcJVuO7M_6*t&v4l7|&iTf|H^2doO?1NQS;nH_@+ncN4 z8pCtNObmeEY_3<(`vAC)J~;kS|9xYA18y2QTx zXeH_!@;JLf{qZUMzwtY)!s#|VZ>e-wI}4kV+}DQ?-5zKt`2vW zU{YVcM(inAjG)=ys87i8MTlL+*O4xU3z6l^*B6gYzUb=6*PZ-2^KkqVJO0{iL^|`e zNtvsT0~Vv20be6}1TBI~L%w$Op0W@PYZTFXmq?#08Ia8$J#;>HNAb1Beezsfv*PPf zsOxO(+R8R7Fhr|{{5rkdvjNg{`Mm;VelD3efVVZj&!9J_0X+8b`wYq&9X@9WlUgq+ zhM{T=F?t)nCopQebWPb*N_kjwa{}sp=KYCIt0~x4%Gb&{$ERbn4O_+C#J(VaZ^AeN=BqL*(}6*Fh5t z4H0U?uY>-ThmFk}BiZ*O#lL*G5oR4oC!e_85S31RAh+0M2=_>S?KbmH1L?E&{CdsH zy8*5_^7}2yJQR41N0Ct(J@&P_kMw=M?1T-T*bvDMtL1^_o7hhdkA~|&w)0pwG<(eX z)b8zq->v^Qx7qi`q0{(MT6_92Z|pw9Hd^k9{O9av{XAfPn?0_HJ5n~VlWUK{)TZn| z(zUYxdajo;&&r%A`zYg?{L~G_>t<05Un)l7(S$kVjMUL^m^P2>+Rq)wH~5lYjCaSy zq=n>26L*}?SWI3XJQ_cK`H>AP+)+DZDdnwd-O-5NJ(Ha4=?=f+v&q(j#z3QZF1f># zG01T7B{we~gS;CH$#vq!U|EMH_>jN!pve7wf`&T>21bfVvTT`OFeoN64d!U{H7z^&^UD+ zwRi9DhLanE$zcJb5a+gv9O&tSwDVJG{K(g?_|s!5wJY;b$8r>s?PpN?(%EhpdTSb4 zS&N*fuK27ylg6p7>54~Fr<0X=nD)U7200P**b8gDu}ysk`BIuU9yHrYUU}CWNBZm{ z_n+X6vI)D%F$cVGb}_&2?HJ~XMt*y#J=1zDUXP0;x7#=d4sD~z%AD7n;VJ!Y$aady zL(>b|<~zt){k_nu?M`xuy%*AKc9HL=d%~+7zqfy~lPAJj?V_**^ex4cGx@ zgHbV=-D>kt%&_pL{+dh#4 zM)7O;utx4keicP?y=rNJ{^tkMI5Uq+-;ts{h}xBFAF|T{{e5^{9;>?JTp)YUY+Lvn zvsd_a!6_Tg!}6q#7`Jk8b;_d7U~%Yxcs zl8qBN&801j8xAEaj|Z((2h1$sT6dY#9j|I}t?wGz;&KePTYc(`xiNffq-S)%2174e zs&3rk!WMe``CLooG|(&`+WK^ET7JM*Rp3r&?$|*|M(#2G~|7( z@)&q>%^BY{`Tc}~QzPM*_TPI8<454W^c(TwHEh@S!?C3kzpig=ISe(D*vs69z}}Ge zoW`>UA=8;1FrYbxB-zqq?R%PGUyvPnP>q)O7->)TiED+;>OIIiwA)}%bWifBhUTa` z-;wO`-W=0r^d@@_vq0sQeaROmTj1)R{^WlhV+SrZN11Ims_*GyGn{T>OCC|t5|795 z-_CHOHNIupQ#%HmV^dNOa@i^iI9+of+j+KyTSYJOvDa;}cW__w?~=CgJldb^c;5~o zmM6)}9c}S&0KZ1QQ_mJnBl&f4=5ky7{?4y|Z~NLI&z<+uR^RPW{+jpOkH7Z7^g!N+ zCy#N&_%XacKV#Ad5i@uX|J=Gis$KZsoGa_Af5;AX4)W{$yvp|YZp^Rut7qHe!~uRi za~S7_Y;xUmCmiLe)}!jngHg4@Na&-#pzP*ZlbSS$LoslA3aT``Mdd z=kczzc4f|+cW*B3S2_O`FhTc^+(&tA98sCz;CddXx0MNQxUrS_{PWcg)w=WReV1!? zXgh@8tG63q2MgCTG_O;DEyj;LOMW!J8)o-7$F*qQ75(d;XDjOB?_-NDcBkn0+1J$; zLoE3xG(XSizKYgYV;w;!-lZ>&=lD$8%33mFk z|CMvCF*OnE!N+a%SpzKH$j5Wh$l8#;vWwRK)4VRO9_CuOwyTdu2e}sh?uK~%qYL#h z+b(^tQ6zi*D`QNKX3whE6b`@G6+>&Gr`Nsz$*nRccUl@qzln91)+PPE7=1QGoI@O| zm#d!CUrO!ebJQ_=)gn1BNVveRe5^9w z?P721uL&;)c4Ad^JU+wYgz5cOxs`KH3OAKY-;K{sN-0r2uXdNlZx#1l)i3upIc4{^zP{=r)eW*RJ@fdbN$~)oww#YDL@~nrqvxQkB8s+vFyT zOH|fdZjnVzMa-h6%K9p6r0ktRbdKGR}xRPyG1!HWI z3px4iI;dY`>$DBUf`)tzjdTr1v$OozM~)F_7tGgO_jlXi|IU-fzdU9YF8Gfkn{Nun z=YG5&$Vgp>o+H@T)IzZ(iu-)67LG-&crWodG!h%uxKj*WUhTzrH4n0X)xGH6jpw># zx(5@iJ*j<<tZb1QK8KW0iFo-D3&d4)VOoj~3!{0Xxat7YkC^#lPpGs5g60@@#Y%#WmGAJQJDK zc@L(nZ|0Z9cxcS|{BUg{c6hSWB7CvWfxT+MJY2lVHMO5JNBZpjD9-J+S@2Eex_?wZ zjOXTjJY2YY2u1O(R9|JTLe!%%?-s`}p*$MvM{#|%tM5mr9$fc7?PE|Yh#xy_(g9do zu#fLPh%a5)%40xnc@!S*=6HH-j>hxK9FO_seb}GM@hs4h?w$L?`??|S2QYard+mvX z*b~oAh?t1`t$BRixQV#Fi`)BEn}V00*{L4WpuL{QJQ_L!X9M|pu}6^yWu9FxOvbU9 zJZ8nSsc4|dYs`8y9S=US)pCwv^3Rc!&yBz1aPuk8Ri|UZ$`8I)Q(_Y zDEnVI-##!NKiym?{~3-)F?SHhu+&_-Co`AbLN6BiRvg2p?8BJQh^@>+{(|xNn#tpQ zn&5+{&TO68UO2Fj_w8My#=^#FB+V79=7HzAyoXoj@X*!qsOiP)8kFaQJ#Tou9nHPb ztsc8Uh$p(#p!?TAbxvE(X#`mgBHge8EJx^`&Jl7l)`d1;VS>&Mg-m2u! z&$7|sKsE9b*KFvo)hD+(nT1%}n&erzndo)efUL}qG7n;1()rz1T#G~XGVpawF?mgg z&(K@*o$N3q6WgTqiaxD|W?__GIeD0MHeCArBJV25#{NJx%4eZ}4z}&lAdkq*!J2oK z$WRPuy1KUKKJ)Bwxtk4nb+|3Uzgd#M)we~v4Ho1gEnAc}XhT-kdR0kxXyp_*|rXoCwRgRpwcFEJ^!rNc(S! zLE4W)+9T39t99+5J;ju~e6=0i`nLR^xs>tW2<`^ETc$M5g|cqAKfNVc+S@|flhI?P zJsPCF8d=)ALE6KSr9B;_y&WB&|B7GQpF-Nt(U{U64bonXEbZMO?cwMckoI(t_I70D zTBQ9iqHh(*7FKKASA$rr>74`ZwGDiQN!V=y|*&? zqw{cBmuQj`!kiG~szL5idnAs|(V#JZHFn06b2?;?sUwirR-63vh!gU5R3>MoJ7Ks+ zC9>1g!5De-7v-my-%#WP{w8;OH4LkK{*d)@hhww_-wW|_pA*bav0Z;T;hDWU#qhaA z8uKpuU$G6iHUv>Ee^DOZ?iq&X6>Ni+PS7g;P3k>`ccr8J|`&7OOJ+*!oAIUWQ$lgTy9;B zJSfr?%ahojI=bMcZFOo_)=0OnE1tgQdX+tJMYV}lY3<)CT+y_MeeSv|eyz}>_D43- zdu}?_$ZLDKAY%>tf`&8t|6-?|u8W$rvMJ9GV(P(TUKZs+nJZRoR@<15Eh#;@N?7o%*lX#7SVdT5!ENuIK%I!dpxN1m;LLr>Wz()X)huf_eBzp9O` z%h~^m^W~W;NLZLjF^|&ML)WJ4{>!Rkfb<>3BIhj%YT&g#x4RCjh1t&R!(nxxe~+zP zm(ey0yj#F)9I~YiVjr{h+*`q;K|@;mopLj2U&?MA)Ep*m>~4C^FkvWr(!R#1Xv0?K zYUyTkn71*cyd_<4E&X0Bd%^9Na8R+mXU#N|mF>Eut zs+jna^Dw1I7j}zy-jJ%&=g|AJ@3(4zdlUXQHf0_T)-r%)JdacLOMOJ&WQ*5vciR@y zu@No327FPofV^c-scOitJaYJwa+PaYE_sc{FI7}EcI%pIXe@mntl0Bdd{D=m9eh0R z_^657joAOnk9f@}<`sFEGO<{7s4$;AKK{EZKQWISb)`ggbz3gkbw|1CYDf;bQG?&A z^GCAD-D|63d;#Zt(nw7V^_u}0fI zY-R1-K1#I?=6cnBs0E`H?1r~1q1=bP@0Eu1y_f862I^>1$j|qBMZZ<n)*>GHb-i47Wi6C_l<|xE(tCt!(z?XG z;=*Da;V2`%E{HzDBDdl`VdD#BbZm%wza4Ve;-2v84&~G??iH_ll`ZZezdXHy+Qq%) zQ#<`6i+j#}jrlqy?nPhKkgrqX9`&#me4YAN4C4Oe%#u<%PQ-ohom-ZX#r^Ob*RjQY z@>Y$?sa@PZZ}@^O?yIk*s-SjpzkOQDPqMfV-{B=+zr_9d%e4MbyD~p_w4~p=Z_U@) z?I=fAurKs3$LM~1EuOls423t?+0RR{tFsp6ZCh>$#z(N@KmNe24{Wm=-|@H(U(FB_9p@{-As+Yv;S}8-||XI(E7C1)H0*ml_r#Yh(%a zR~~OKJ-$hw&*J0lgx?nod|OK6pF2|kZ*}$|n{*^@ zUT?p^TsU-Ldj;mBy9K+Ze<7+5W-IfftfO)3bOasZ{fy(hbktAgJ zxYqxwd*;YY)O=A)HT9UDg@AZ=`_nH5A)$g%oh(6`B^vpYaKF?MjCl+%*z{iaD za;FD>KtL>e*`N2&Ze5*@lXYv~<4837W5GMPR@bNYmF?c4_YC%csoSAlm!E?NY`5di zX+Fm)^PtSR-}jeTcdaJHraA8=vKQCi_8JSf*&Q1zwsTWbci_U*baP;V^zc*%3< zZD7B8@eIvl*c#`b;`RY{iycq!eG|J&;A1qO$j({uNU9@Sna`#BULfQ;=k~lR4aOP< zl;>VIo=boCVe8*~h9f=Ly{|n*GY7WWwI^6($^LZjF@{uOFV1)buLnG4j$JsuPULgN zvL#{Y?ZnSVWezR&g<)t8=g=cG4C9QskFuuqCWWI;1=louL^zDBdCU}tvskHBi*j}T z<{8X5$1xmSk%+EA9K)(jK;EGmyskHwkYUPh+2=YkG}yaiZ{tgMwna`V9A2^i&sr2Y zG<}nZWpDWSyqPL}caj!6u>2BEuBk!stnYap7bdbD0&nAcG`rpYRP61{{rmmdikmn1 z+^f-SDGa?@6P zGUW5>(d}DcB>kp_*u#9h7LFS|+1-r8F*upet04!&5Z01C+$Ri=Hu5=k>4-3_DdZX{ z^WS#Z8N6`jS`_y^joF*obF5C`={fe~8YfZzCi_9baXi1oKK$qyIv-%)znp;Fx$NiH z;?dHat*o!tp|`9P^$D3B zgnE&kD7MD=fmjpQkt}_a9VQ;{K%SHyhzFy1AVgv1>kDK_n(AUGfEK#n^UgrKYK$$RSu zo{YCjXQ1%m_HkX5UH^FOz}JI z3Pwycd&c@;JnYzo+G`IAM(Ry==G!2=9?_NBPxlGJp5js35>KMOg8wO?A$T2Aaah@^g8mxbX6uzCag z&w?1(B(Wog?nlT2_Os^uP~|?`=CD8ZjJKn4G%EW;vyI*VtVNltS9jykYr84+88P%I zGCrEpW0mnJ*RCADap6j|e8O{`sOd*oB+1pnR&P~nSCKV9!Ij8(l|ZS<54=U8F_1!1ibyozNM3ZJ`+r+ zJ^fugs%5ZWhsMLmt2wnFHjKxz$Lt0HN8w}3x&2q3QwJqL|4LKJTXIYSS`BVSzVRRd zQ(m(_-cNwr3=?XvwJ!nlf3oNGOF;kN=G5L+x_C~j_){!t#hYg_%F6HC(2sH{u+lSjy#U(nQ7?j#dg|w6jNjPJ(C_o;xRad z-_KF5E8QR-3m-J5IE$AZMV&iFpOAq zJKK<~T$iivXxOjdcyPlN9Tu>YH#_6C3tN4`2oyJE@AMyz>uG%4?!7n^^_H=-?S`OH zP4;7r!I&RmOK~dmW>IN0q@PNo7&iZL#n4*p4q7g7D&ZUsX+9ElZ?Xd?IN?GtJLbtS zq_<~}mHtMs_=zozqw6ySFDJ2YzL&mlp?+OzcRm^m{mJZ@F>$zkojpH44!Sn{zEdyv zqv(8yJ!Ah-EHmNvsjRLZ#moKd%c`SjZ^||LSG_h5jfM8LI<($(?c%V`xGq_vEDrnE zu-olAipy&J{+o5(c>D=qYfOrVr9Qu3cWQk+iuSU-1LE=6l8=X7eXViv9`6Sp9khYz zUfypg*RIU@oVd++r^T=Jx)_Gx$|-)0sf<&ZE9Lk<`ddlgp}})`owUT^eY`*E5@d<( zmDmriSR!j8?`K@5TfsDyud{iJt&wEUzWK=pcT{}MRmME}sx|x?ar_!~)-Vj`z1E4^ z)+npY-ZIDqL#6>4u@jp7WT4Jn{eVX`(HV1S+Eub$(+x*>gzFO z2HU;O2Do-&_Z_zp{Ti}uqC!yBko`R^6tV5tft5C6(j<1zDV-2ms|g)5n{RZ+u8;iu z{c))qeuVLP_4Rr?%pJq$%=~)xNVef~V;vtmG|}PfY2>VKC`#pPWsRYo@nbRXHy*t{8WU&!2PDZQ(qf&y91}*do%J&w=JIx!2dlP{eN}5#zL@)3BS{fDL)r2Iw40IUmS-OKAlkgf)V-sk4{+Hk=-hzGtAC5qV^)QuDINj-AT_I zMT__~Z^!LEcw38I>N6gdF7X;|JtyMUD)#W@lTkjJ9ejMM^o5A*T^ZA{-iiIM+SN?+ zgijZKExa|{8|F8;7UQ>$gV!|n!PE&zFlA@9os9ZrT;H&msnVW=z0ha|4i>VNxl*o6 zIhS&c3oCWNdE-%(=XxpaV4UGbIcZeU6*(ha$bLO-5g6h^eJ;K3iec-VsC{}~H!LV+ z2cEV?>Z}peZf#|U1^MiSW9%?~=16LH>}&_WLbmT!TkM?SOzp2UZE-Gx{jYhKHnzo_ zp-vpbP&?ee&3JvzQ&f6ukY?inMgeaaPkSp8<7>uHa9>z%1xZK@s0 zYVx|2d3YYw4huGOP99#i#=IhS>2*t(JB+5sj*7IvPCvHM=r(ZN%eK*Kh2BTl%6u-I zY=g}MN6~t(Jhg)Ue)h;3mT=2v-#4+q-bSOT&&x(_u(=!ircNtN=*=#_Y>#JJ4m?g~ zcibM}K=CN^GdrpivgZw>_T7uxqxQ@pd-n`eTy_56oG5d? zZ)`I>%;Nlq9X7?r^X$(@df=V3KNRPLB};pvP7=G5rUSG(b*J`MT^*2cj;-I!0fn7= zQ2VsRo`^fgUZ~j<53G7p`;JOIFejS*ueumjaX|0dys!IF?10$q?6>P3v9o!1TCe48 zN1Qy(o|52*1-*Mvd&e%0nE04IV}=9jxc8*?@}WJ^?FCzzw+8i%;5CbLXq#q;;86D9 z_4N_Don56zUG!YXZc({5O2@OmX4OPYD|SJtJ}$iAyshh59RnA#uiw+dg-UE?jppxb zgnWH>%E`beLqwaieZ%VGRC~5ja9!lLU{6?68~e4`H4Yje_955QCbtHh*Rj)m^fAMR zT~xO^THNL5NJ2q#v|hsRpJWU+!=?fJ-i0#H%33R9?z>qV^RrzkhwGYYV(JM#4;-oc zM-}YN=MCjt+66jDKJQBFdKp>?KiBX%s)m+2R6Y6pre0nTz3y64pTm}hICX>F)vFO& zNGB(8yao9gLtl&E+bN#Y1eSf-Y8{#(W;c7^ITQTQTv*KBQM)lxkFcHkHbu%e_VOMk@O9$%c7nf3-$j3&tz3JZ@4r+r_xZe<7WPZ^ zvUNXh<3R-hXEF7S1vz)cN_(!3&X`vTPP?bLAcO-*%azr?QgOdTd?`TSE_tbwz= z*tJJhLjU(eslRbqWh`0G?tNPuOZ&0K-{tQeB6Ug{mr); zmiqCzvGrDc_%!QB{f~8#etY^YyOOH`8XxJ;?Vk+bzKqYSOWqnFaO6O0-`2}O`g=E@ zd$%;K3G;94KGXH3&om9DKFb`dVbE|sSI3;th3;#%GC#^18MtdBKaJO7rmhRK?tG2- z=Awrm7ujb9RL82({b;>g@9Cqfc7JlcCpGZv5_`H!P1pzVwdUNgny?-?koq*cQUl+s z@%8BA34L6;!LDao9s2VIQ=io>^>AC4kC`ENs$iCMtr73>iu)Gsf3Tr-iF+Ovd$7g5 z5dN?Ec_i+Uu=HVzdnY2l@^ekxQ*mq~Tik1r)0r*q!C3U2>nQHcsBw)g?%60f%og`@ z+>B=b>sS)^QHaB8j_nFi_%g;w~|4EBJY;j*o$4ox< z#QiF9yV&ABmiZId;{KMez1iZvmoIi~<#AZtPXi_HT*pNY(r*ydU~kX(sVYCg*ZL=S z%2X*m*-ZzPsA^u}>%P{)@2XB+*wJpqs*8slX6!AC=Zrw(h{6s)v=?AN0#rXSejCI_l0SRYf;okC;)Sx)i~C15s-+mpCUV>#oeR zvX3&hR>S;px(1);Gq3q$oHw7tORg=2_YB_OKAG){+U@x~?|ps-9vx>F-kyLH@7Yz- zJh169+e=^iysay{tG^4Tl<*#Mh4kB?hikLrzs|>mr|h8lGcaKYUw6J=nSdut*^R1? z#V$|wv!uQ#*us17k(K+y#hM+yb^tEE;<;?>2cgF{c69wA@b_U)sWuGPd$MQOaKiKd z*3z@iNNCw|`@dpdIKK}@y1P+L_k8Y)o4Fj%{2l#Ku%5ke)j-s>XFuIK7|klN&s>+@ zBYMYcT&wMbUk})x14csU1zVZ_j6SQd|0?gpyE+A6&j$9%X@U4Tg}p+0uX~#Z`;heg zPKlG)<~LWvYz@21(>17_!XBKu79Di{x4!N6t->NBuJy-F(szvK^6QRv8v?QVE?Yk& z2n#N;ZKcl>1>9!)ZCH&3nd~!5*I-XQ9;bo(THGDQezdFynwjz*W^SkMSd+{9B4s|6 zH9dE8BaY4DoCG*;MBht%>?y}ot|jH8Jzg{!OUL{X7khM$@*syB*<)uz_Kz<1n6hmQ zwbzNWN6p%7-I?8y9l^2vE6!Ha?U3Oxmg;VrYKzAwJ;P%-V*EQlo2%bOZH4X`p{+2i5zhlXA6GGpy3-@e7=Y@Q{&3d*8&Fb=N zE63-Xu<-Qcqr~K;d%A1hoJp`@dQ2Ch+m!@XF$>hXq{wx zZdi|3Ic&3`>u^nn*X5zN79Vuk%37SV4nZGde!lqUgy78vw$GAKpb9@9wcmuoY%_a_ z{w7pu%=^+#H8#QQ7`yAcP_(w=y=&RBP&~QH_AU&Oz9*mSa<)?lnw?<#joFA3)wy<# z<2T@oD|?yCdL*o4J9Jxz@dwz|8?Hs4L+tU*df@S0FFFP`Z?#9C|BtUX55(gA;=kKB z+KaUB`=0h_-}eQTid0%vXjO@l6j36C>}x7ol=9ZT@0*nN5?W9wLY}$KG4ssxe1D(c zU%ficobx{Cx@PW~Yv#V^vMG(1dVDL+)JI7@6SDt|*T>dOX7wCvm^u^>N_oDum%a-V zm}WvT_r}`bVoNjHHnY`cv}$ZdcAx0YSkrSMvE4NrRGi8h4lmn^jazuzO)j>mb%A5* zAF#vzddxaCcc7~y&*6EoJ7KEB>?_@GegA;#IyGW993%g?UiH{D@3{p*V-}LOf&I5) z$U3fl#>H*8dz@>GPTG!sMLf?(H?T+UeCGQbcHrA9o&(MPNgCEO+XU{yiyq9|XYPik zCUb7wc=VsXnCdmSJXZRxPUfS(Mq|{MMPzrLJ_=7fnawjsAgeF)_)Ei4dW-w!_g?y* z(RAjbDZ|k1Dfh5OZRuKa8uNdR>GKKWaVBmt)f>=!ENtwU*EAZ99|M_(j~*K^MX7#w2&b7g*lk9IHjl1o6xK=_cK$xoHfwR z)o%?-G?vhK_3Uneb1j+G8Z7!O#AZ*{GpU^c{!U?5_g}qjui*<3(Tn3WGc}ODi^RFq zbEehChp?00k1Wn%k}Mu!Xa=t#J6k-4r}SQ7(1OP(UdwE2 z_XMjgna>`13PUGm)05B8zU;pLqtnlE`#0Nf1tcSKBFBH~`wFM_@I8nFm0n4|kH_~5 z{!5RR^*J=^$909KoP+jzzNf6#+0XVawvOlcUdL|2B-Mw?8>}a;~6UMV($0&2`ZT~ ztH)x%u~)cX_Pj)uE~(Nv58vPEC+Vpsy<=L;y=C61n48Lc+94G!S9T|R+|X2L{$aMd z`wHJ}_}a&^%PZWG))vIJTNl4X9b>+R+PgIcezDB^Y+m494)aL!WPH=%Yq9*X&#|jB zbH9$y(5*FdRPCo|SDx7=Ef)Kw=L$spdhv1iI+Qut_auxfF;6&f3NusrzRdRhr}5}I z^Mr$EV0evr*}-`HOlFSWdlp?vnEz`YHdqvk>|s3511H5n>l@F{-;+D!mM_K|C-KS7r`VCQvsuIA^IOpo6{`6#}2?x=MOiT}9&t>SKD%{u1V>+a%XP39vr z?&HIK9@7g$AEKLd-73cDYq!T(b(2{=j_NsC|Jf}Rejh}&*V%Ft^~;`(*)rz_UL6@o z_MscEL+|+j;=Qk~A*rZ8aro|Qn9_(j+3p%T^y)|Ui8rpnds1KGW`@`Cajh<~Y1bR5 z63Wj$^&5E;N51hjc!h(vaB32>XT3WJxXb&C_1U{fU&-8L!+mt=$vk_+L+RckvuEwc zXe-TIar~*>PP%99!}tEYf{)_hWWGmd~LQnmZI zd6;=$zmNxe><{k5bsrPYyDX*p1Ex3nkUzvk8+{3NKyq13C!CkC)!tC`u z3Tu||@n_+eDCu*7k5R8`MB}$HbKN=7uzby*FO?of%b^pJjG!qT%0*`Rt=;q@CsQU6OVluIG3yYvc6u zSi7Fr;?%XM`@E${dKXC??`un?_mW(j#&c4w$Fye@mQUr+3)9?4)ab^a5$o4RqM!nQ zE)+#aAmJ`^X+$_W?cjOXW_1|+TJd~dQ#lkRVazQz1|w60bE$j#@J|%#8u0PlIz9@! zNANMcN9QQ%MY6pA`WQyy`9J37!y_>H3h(CHYf{zs@t3y%vm)ZYnFuE<{8rA*j zQ}H|+wdS?He&rKjvypkvm$R4~&zyHY9wo1t6CBTA##iQH z#AB}%UmVjKNO~+CnG>u|!(t2bee+YeJBRt?@{`yk)hPTI?1)2AGRNqx~Dj2s{j2n*zxb>1FF@Hoz^9xwG= zN{{qKH7{O&?mo{KwNLRHb%?PqKHQx|JsBI}i%01^CpGl^pi`4MxsgB44Cgr+rh5c^ zoyU{^S*HMaWQ`-ftPzB!Yni*93dZpI%*(AqvG3Jb^64wp=yH?!k7gvUmDwBJkHU#E zf1`CrfwDMl|HNQ%Hplro;W)avaNg<*_QTnR&o^e7>_?0ie;%pl%&O0a(PIFA<~AR8 z7-OsP=d!c04-VgA-Y0#BMQ-YTOy=jU{jkbz z2H8h%^F?uunZ#z%htYEv^Y&ODn0{k!;^mFagLr*1)Z7cr*D??3cnGKVGOtPVz{)+$ znGpvueHC-h&F&bf%WPzJ068Byrg~p{p5}|;t*234Q|tL5G?uwk(+?MhO(%QJWMAk$ zU~aianv=6;kbQFMVeEdyTtWIBp-{bek2}L;9ka_u7kq5W zJaXv)o|f!2DnHwzuhC3<%YOlO`n#t|DH@p)h$J4YDKV77bjh=H%TxBu1W6HgqmeeFovANLJ%M63J} z#CCUfVdENRJ?Xm=7e4ZNul1^3m^Fhr!EP5WUFLIRcj^5Rwz|v~-5l}f7>}d6pXz$m zdA(jaA+Nz`%3EjNUUYoT_t)x9afa0eKK5ouJL6CUAOE+lmEMKn$)6YMzEyYG1FiH? z)He$qX&*`C`)J?lxnN5)e@;bOxgaHsKP#8^bHRaN{%p1QxEPmf@qLgR59gzUbpJwJ zr?k#9go`C}s>3wwjN{`;$*BqW7{hb#`ti~5SjqEkxZiNh|HE^sxt~6qjd?DeygmfM zp{#ja2kCcm-f=C$KBWnNrU?Hfi}|xj#PPVrJrVKe%^F2|MBZBUdAx)ki&{KJLg(Ts zJT5~2?Ub^ykm~9Y$J{V~rD8uPy;V<_=#F6_W;>&##dF6fzJ#wFgPPzX=zdSDL@e=$Ynvb9D8ZN+H z2j&}Fjc~F)v)`oYsASB?(%Yve!qk+HOOM`!{M3 z*LHGSOYiEg!QA>x5*~T9r#WxC?E-E-Ye!t$^BmegYD;WgFCHnbZHRkSKaHTqt%+Og zIf;k1Er~PzFZgf)<80fJ&-#W52;JG1c+=5%giUEf+#~)p;>y08^K6v# zUcY%Q$sS~O60Y&hi8pASq#DKi6!x#uZ`TMG{!gNGlsLDVH6j-ApPtns7I~lVXh#$4BEH-=kyq}g&?EO*=#={}^vmO- z9xuWBI`yV`J0sZ-3v`&>rR$U_nZ3yVyZK=}In11p<&7!QdaT%AbTYh98q<@wUVSgT zZ@}DS!y&k@>OuCRhKJBQf!DbF@_FpUw!*GEme&}C|FeUXCrN9p}$%>-!l?*r6e;?Js+UhYqttg{Eu1&D{(S{LX`MUk)e?D?%x)s z=y7ZuuIP-g30L%2_6?`86Lkr@T(9t#`yk@T{SooyzKOhYKZPE-&qAl%f1zI<7xj3p zvXtJ7*Nv~`lU}`kK`6&87I{PSf3Ai6G@#VgWymCK<9=Xp#r`&&`Umh3rcnQ9F zo7Yb)N?qZVzsFIP9Ussd!iV&6BeDA&(C!d5?yBDSCoN zdMi4wgm^3ZTV3;3>JoOjUg0nILBx^!BjU?_6M5x+3O#b4g-*HuLccsN>hY@hu_G?V z@N*Oq=h{KTm-%BvYiu@W-gmPFg6l9>>)s5l{rK68z0!M;c4{*3X{Li#=4Q0Nbibhu z&EpG+({r_unrTYh=$IB9S}+THHv<#Jzj!}CKO^FNN#SQ>MEqU7nMK|&!Sl#p=rQlk zEOff17?WM-F9~55b&YptHqq#+*xNSkq4;ku?xn=}=c%j2-}g@~nGv1Wsl4Y}FLg?(s7)yEZmPFI{GDJso^cH!Ud6hD6@;=HKAEaIQD;^(hK-euYI$Y1FB?7%E^ zF7L-I^v|inEb8j~+nD^z-RPp&?GAQV{Lkt3QsVUX?4!iD3YNZiR+iU(Qh!CyYR3VJ z&J$w>D*7#U4^-+BcDY{RFZV&jk^3X!%Y74h<$el1a-W4xx&K1HJTB_-IcqrH{H+srpSA#9JA0f%!T(; zp>ugZW}!c&JhP~)Z4U3V^PcWe>=%ut@7tF7XWn&D;>0v^RpNi`@22Ga)^fk1$LF5( ze%>;jiG2?!`rFPqpwuPoa=pS|?t_RU_eaE+`zG?r{Sx+=|Lj)~o)*e#^bP1(Piw8ksP86$me%JI{VxGH&nSi32DK1PX&z-upJQ3TTd9j%Xd{^^l z&9K6QSP?y!_T`l42T}k19AaTlY{)G9_fDTpb`fX2j}ftm-yqkJSma%|h*{{#%i=Xy zp|hC}v(WFdm|4`7GK0C;;fP{4sTrvF@7Wfl#F=y_Sc&hP8KUHMeiEwa8E6}(=$w}x zrs%&`BV4IV*yVbKzuX5ANA8b^FZWI4mHR35$bA+%<^Bu(^0=tSORzfo9)G^*H20L=N5EVF57hJF zXR3YtJ*Y-8KZU(PhdDG?h5sq**~B8wlDkI4BL3Ju%p&if6NY3LdaOq?3!MeO4ahF^ zXWU>Gb)Ac6o@{nRvDdsEp!i4WNbjmBi}PiCuo8dQv=AllzILIC9)~NTiq6p1VT%5W zBg2%sgk7#z_{)6|apeAp_;TMwUb&w_kKAXWQ|`aeFOQ3QyguoNqt@N&G`IUkhhlC5 z^V3!#xaGhc85e|~-I>!C2g33^-;;_M9e^jDnZxHD!CD8tk5Cxv5951$AL02}e{`cW#2CodQMN`dk{kB+uwZ8 zMd+V&g;~_)9m{;+X@p|WGmcXHo8OC8;(TZnqr`7H;FyxPWvk{GnJ)!8I zGv|a-m$1wA3V*o|B97c25nt|`$Se0#=#l#@bjtk~`sHy^kC)(XOQ+MkO}iJ0e}>HM z%tMgXo_SBhU|6N_eZ5I(fylC8j(Hn^fUkV-Ahdb_>}D_@Uv&h%qxn9DC@PV9HW{>*{zF9`p2kNFu75vP48W)Z*Y0lse~@}8~9EcEmV;d>B5=eb$TLVsji zW>MFs2FxE~BNThEc9i0;zbsmbv&H+U62EakjFPwYx?_qSox0NR6qV^5Xn9=G?|tAn zjh(1V*yVbKzuX5ANA8b^FZWI4mHR35$bA+%<^Bu(^0=tS>$~|wtZp`#_B;J2_i;gk zId%L!bb7&SEO9UIV1_+&mdkBC(PTbhaSOe-@fynshnsku%xf&=U*14sbLO{eZoqji zud!^HbOU|%^BRk=zrNm=@(TZ><(WmCL*sdkMa1tL!fPxduV;N`p{HR0udxW7`s0~} z{+I^LqOQUU%!i8}DfZ%>PZa+Sc~6x%Uxz(c;&(JnR`PZl|3cA|ocBV}`FDPbqTkFu zMX5{J<$8s`+y@ay?vIEs_f6!L`ziFueHJ?9{tNx`xTwcVuxkQ8f0C7V9}A+GySd)O zl+DZs^zPzmXXaTo?_laBUSl~^Hlo9Hv1xqkzR zrLhz9Q`mK1^d%Pl&)P7HIF4I*jYY&?_KDY6MBYZG%tDVxKCiI|ojMWBLVvZ5%%ZNB z=FDGH9x3+dp-&Y5G5en?aduvMro?Y^^SP3@i(j&$r`5n0ip~)}FBJVj2``kogk7#z z_{)6|apeAp_;TMwUb&w_kKAXWQ|`aeFOQ3QymZ6UVKsv1ykp%jxY(1q?H=i!KE*u$ z3mbicVc9cs{qKE1axbF09fbY;SH9OE{7*=~fhq1Oh&YE=^SuTUf8Z^?*C6ux3}6;|bguDz2cdJsYG$E7 zb|AB;tE2<-$3dBjee~6@ivOBE-<3GM?S3fnEd#QYyp~Scik=p_If~8^{yB>N=u0_D zUBWKcEBxg?h&Xb8M0~k#BCp&}p-1ks&?)y{=$FSuJzj#{-VCnZ2h1Dpf5wa> z%&)e7!i%ZQ{*yjpW*X1`lF=Vf(Tq8N?R%u%=6PQF^c}pU=V`_M_15|w`mg47#qBfS zQH`>FKr!EI5dJCSm_?kufqdUV#9vj7S>$cHi|;!KJ>HF(h0bR8_#Q+*Nx!Bav#9Hh zGjpFt((iSb*>i2bD*kQ{zbSFi6G@#VgWymCK<9=Xp#r`&&`Umh3rczwL{8=G44y)fN=`M6e#`N^?d z^nS(nzasR0!MNZMVkLfyYb8qF7RUZ6dhX9IRdoKmT&n1womQ&U zCG2v&!e8!#h$Ht$#FzUf^2+@bdgML}opS$$etBHf<0aTDu@lXi&$IKfEQY!5uUyRD z%Ip;M3$ME|Pqh4rIafQ9|IrmWs4jiKM$ESm&un~+=sp?v|U0!IPOQ z?##gAKefqcSif|9mVWC@d^VNW{({lDwV1o7;nO7MnL9q?f%N-+!l#GMXZSzTB)*mZ z31g}-3w!op4YCV=Y^{11`L|M+u*>xd zf4L7Lj@%y+U+$a8EB90Ak^3xk%KaDm<#ADum*Bu2b!ZL`mEPT8*@Ag{|F1C3u1)q& zUowyu$Q&M@j)nc0tHgdm-BY#5r}R}CavL*O(@#T~RZX&Iy!njL7d46Z;4{@I=BKca zovcB2;s3>_h7!m7XLVu`-)0W8$lE!&8rg-O@RiI$XP0KoLVuGVRmn%x_3btDkR4fy zy*MLV@%JA1Q;G9@`7b5@`n9=A-fg4vAnURIn5XFU7?H2&|0TVfM$Ac3m$1wA3V*o| zB97c25nt|`$Se0#=#l#@bjtk~`sHy^kJs?g`Iz>B-&JuiHWwLS?$z-ZuFqnwaxMqj zQT(2ZQ7f~dbt#wLb5VIx7E%I#5m#FD0}W^WBsMzx9p66jJC*uO`3@)JEVAG0{2i}u z@H>@+y=(8XcPdH#cgo(QB;o`Ny z6WK*wi({CxU;b9?Gt3GU|E*67l{iCN6e;m-^^29fwjD|oJzbxcC_1MO`KRbVYa)G? zmDMHea=pS|?t_RU_eaE+`zG?r{Sm+aBsvQf7KbB(ktShf5`_6l{fpqrCJtZ6NsZwK&uxW3i{O&E`-z1CQu_fZz`Sbh2MEsE!{7yHKH^lr4#TR;f52O(bond*O ziG_X#4`xwUyLHUNq<19A_HxY&6o0?fg-V>4NB%1DH-{A|dF^b96+IiZOB9`68%q@Z zzr9Lm>_lC{F4rskW-J zJL2OV-X^97ydkcA_)TJ0jn|6ZcEc;hziCzqv550)+Y4e5zelfRVv#qe?sH za`Aa8bdK2elvwC*-hf%ubvEY-*{61?1litTNL9%G%bV7K94G6HCgk|5@@hfOYjL9v zWIeZ<)q||Fc1}IW`rq}d54kR3m+KY&avww-xj!Pl+&7U|?x)Zr_gUza`!Dp%Va!hc-xC+F{7CldJ2MimE&f3KwR>9P zZr%69buN5N{PyWBvFo4@iCwn6A+DeBp2kkhPhs!w^Gfkw-TNi6i1Xyb3t|!9GcK7} zau7==?K)S?Etrc}jLs*QRsKIcXIk+t;3|0@*)uR&~g6TA$H?9N+9p zO~`pISJj5BXF+%!$T|be>q6E)KSKH~IB8Cbx`bV>SNO|)5OL)Gi1>2fL|(a{LXX^M zp;PX^&@YdRdc36H<3iuz4QPHI-H{LTzx;mQaes5sq9b#2={;XpAMrb6jrD%w>c86L z-?VuSMqjGQ+&3GS+Vi`BSMSNf$}!c*KCxvM!uwVx{#5(}6Eyk#!or?z${AYyn zdy1P%aUwtcq<7JZ`2MlqiACPvJ{iP9PoUdpVxcqh{Rd*9-+0J-Vo_J(@pr^kV+s`e za^1g*zelL_Uc9n6Mn8*{_?~tCDR~bS{!{df3@cT1>Q*h6BYf z5l8Nih%fg|JoOj zUg0nILBx^!BjU?_6M5x+3O#b4g-*HuLccsN>hW@3ydN(vdeMF{>4h7-dwWrzPfO1S z_S|xiIJb!h)>QK#pFMh>nAm3@*}t#xgywWth5K5&5euK+`}Y%1dgXzDpaaDH$9o{t z&z<i$$Nbd|0`PxqthARFTU(s}W*^c(vTmZZ5=MOTFGvLbeu-jNh=$C`Lo!~IycYCZ9a zFZ(fN!A9Z?rvvD9U^B70F3sUPrT4M&oQ$2Y17DUhZ(CuHHCGOi|GF?cn3s4G7nW{E zpJvSai)`_tJ~ zAfG+wHe%`oF4VeE+^T;!H$U4R2xXH;L%g6EfE?c()nJw0m<_Fe0QFHhj;@@`C zJFQ~5-c-+BSYgFHEyhuLww764@6GGddjwwXplt>B^t2}yKJ5(bh<`TN2*Pm-Gv+t zg#Jr@j!WZ-H~hBovtg5^aAP4t>aQUFxOEch zZ)N+uZ~gJPWGUJGW7@(Xl%Gipn_eGH?D@H@zVj>LTd<^?&cW1U4{Gs z8W9h!Q4a2N^oTdyu7ew^+Yw9uLi#_k^mj;p#L{+4 z6ZpR2sV}+MQOx(D)N@Qd_ry7X+#kVmf7HEF_i%Y+`6T(fgwi=Cv6#;>XUa?K?7Rkk z>QuR;l?`|uK1=%_{><-8^J=PFAr{Z)ds}L4YRw;Jlu!Dwhwp>5npG}o=^wuTVz#IR zgZuEkp3#{Fc+-yWbqWpQTvuoi+T`ov)!@iMSb3*wfU6Wkm(Ea6;-X1O@R`+njoI?D4!}G1; z-XdJ@_msv(tYh5KctLDvU5Y_NUlXS|mP-nXSz!c^!c-!X77C^7p9NN~(d>+2|bNr`~ zbJ59o9@#Gro`b#f77$x^nvLLtro@4pjj%7rj99mq5oVe#A?`oJ2+Lk9CBBeqgwFaa zh|_P+hViad#QulYVEu#HRO8(-7C5lLi1^dx74S4PBrecdhD;a`H#L)fOWB+G@i8-) zWiZ>9nh^3WGi7Wgv zfNPK$aaxc8ZW$~gUVg&>F*TPFJ1sCo{FxQR|CSgbd5{IMdR+W3tVLfbml&_Se^$sH z%{@H7a6L9WV7~BVBfexY&mCri+2PDuK3nnfH*c%%kG`cPO!B#w9UH81>DFAzo8q+| z!6Ue?57(v7O%vwyoXvRLoOyKht!TM}{cRoR;&;gw+BTq#G0vrJCVnaP>eBg*#75(c z5$m#^IPJk)j96(+oKrLhPnK8`|JVF%Tx5&}u3M@0hDYaNTVEUEwt4gL{pLpEzR%_% z&2T+&uSxSzAD#I7Y)_d%^+9e?SlIk5V%gZxKynGHMaCcb}mHe3(75dTh_ zi#rn!5POF$z|gCn#M!SFAtl9!c&W(>%v|kHe7=Ge+AR+xp5F!1>w(%MdE5Sl-Z=Uwfb6%9`5`~fk9g$$0960y zO}uMZFbp1f5HHUU!QHX@i6^`ZML9=j;w67V(etb(8^zWUmNdtyWjYr$;UL2BOdD(R7`$w6)zc2A|!R7=$CYWE{jUSzv z2j}iUgAsguP|u&MiAE@YV+YNLOkYDhKD(QEN>?M?JK;inb@?2$*>iw6cI15gXmN;m zzrPu}%s5PZaq4p1DR+c8tfM7%)(IkRleHPqD?*3^PuSy0Nhom@Uq?(&3L}2z;SA4k z=I)!MYm>9=^P#1u^gHdrIdOrZ{9~TD;+`T?B(QB zYjQSf-ItGPxp#NKIp9b~6B<+3%iA%-Y9X&d1@mc588R7|#LeUr7HaAL;Lq{D`IPAZ<@9 z#e)==Sjqz_pJLa}<9$l_R~^Xvl!&uq5bskWzR63T&m!;oLSNce=vlYp2(i!^X3G1Q z(7%0G5ZOgt%`%v!Jc?b)qxegClsHlzCBBqL$t&ei^hkLWol+ji`lUQdUBWKcEBxg? zh&Xb8M0~k#BCp&}p-1ks&?)y{=$FSuJzj#-ewomGSSqap)H=zZJ38&`keJDHV~*n{ zoNzKHpJ;naBwDQ`mi~qGe`4wHko?%5X$EO~VksV^xWrN(s!^Ojko__5k5V3-$>X^# z;shmoa2zRq;cRbWk$0`BFR{?G@j34=LT65B0NI89o0oW>5_QdM$@}b5X+1%@W@+f(wJc=GEkD^nG2PrP)mGUTck-e;5;V<_=#F6_W;>&##dF6fzJ#wFg zPPzX=zdSDL@hbmdAs#d_)EnPjJE>D$Q}h{WK>T%`^iGFfvxptb&Bu#xGl;VrFOc37 zI$f`myLM8Iqvp8bYd{=vZ87SaGEe$$2LCs+$lkB(LJZbs)^Rn#z`8TZ-py$Vvb_xS z=DKJnOf7)Cs!i>`mQRZr?>8tqmFyM|uo}?x*_1 zjr$Bo;<0+f>RLuf-#=ZW-HP-t3mS-Zsm+Op2Mk1e@214Be-DJcabx19;e%k*rxEeB z$iXP?szvNwFa)`?8W3;Yr;nicdc@K5hoQ>6y2NS?jW5o`{WH}_&)OYJ@z=6E@v}x- zF|yX*A!4qIIWJuo5v$|qHkpYH50nzf|s)!)g-S z7-gdNp4!A+PG%r_NL}JJ-_kMaG>>mcwR9w=@wkiH<+|K7)9`a%9`(ejuk_5PQ$F#C zDd{*Q)kw#asTr7~`ImTFuS^(@DIxaF%0!4mIqG?~{Z}0FuRuIA{VSZ_RU+1C`VH>} z@wh}c{|3W=>SS-8{S`}!HHc5RenrCYTEvB=QcRON#81a$V&_<%Gy2Oiq~EcxPxiqp z(lKpBL*jB@W3a54k4xSYkD+)r9|P4s>e|)*`~Drpt>=8KYgqZHblze}eG9D^Exl8T zc}uw{Si3QQDj$g#U76Ln(niKe-+?kBJzKjTg~m7L4w}*U(Q`K0KW9c_NmJ&F_acyc zjD4QE1;EA0nDXj(4#eMG^T^+|y!5@T+jEJR{0)NhoH@i*YlWcyFpg8I8;bh7IL@@C zVd&M3Io2;6IfIzhxzzg0*#_dV-yF(2>Oc@)RGv-T^-3^89&n8ts)Zt;l>0NqI1I~< zFz<;AhyO8Vwf=#rN3giue2QbQaRfsLFCf0$&L2y9nGpN;@WcJr%uRdvV&p(mvhV49 z7!ISD$9D9=xPR;u-Q64GmoYyX>4iRy98=w^s2J@*2LyM7FW_TwYOb>;?Q`UQXD%jE;{#@&zjcxnJX znfMZa$_PM8=flL^Hw9vVxew)iQ6&fiJiICIJYUHnA{Hz&B zTx&ouMj8eXfAb5%@tsGAkGBnixvxL*v?qaRAL2*+G9nOlf_#Y$!UM6>_b~Cp`_k`1 zd;1ViZWe^A0p7$PMuy<2Q4s0ecP#|fFLGYB26a!|N{*uNIs1G4iH7mgVA}TVn<%8; zWA1-85=9k5$bQl}0^K#3KbeJN%18FuFiQG<=w9YW{X=o9GV_1w$#gx6=pI3&xk6Yp zHpej=L`m-l*9<26qTonO*JI8<6oDk^`d56W9;0p5d3CECLnSlrPh;QX*z|(Oo%M5PKdgD@7B>tvZk5=%d8yF?w!z3^y9_cp2S2j%hwTx7$vOg@G~ir_el#`TYIUINY1Jz0xWkbqbj?rkusG-#lJ3C!Iran^4-;y7WJ}02(sz~CdnF)B4A4U8jIsrj8M~Qc|xqx`9GsIp~&f`bGY2qG75^&|%DdH5Z z1Z)UCNn9`S9C94uh;{d$gWJ4V;)Nbk4||><-g-;&seYXJzs9$F=mmUxd7AoG|I2xt zYsP$F+H2CUE&)o&QCA&JWy7r(qzp(qxd-DHx>nCo0XEr>U1M@WIF9F$bJI(yaD+{xY zng0g-z~xlV^7(%Z-^t43UK)JTjGYd z|G>eLd*UxWv)7>_$G?9dA6u6&|5q)MMt@0z(0p{*U$i!VMfztK7ov|A;cp!8GK6?U@gLNitw-GGa{+>%>J#sYF2n(kVZ`ev{KZ(e5yXiX z|KeEuC}P8^MQ|z}L#)=L&f7XF9~YkwAr0CgzhUU1N9?-y51a$_iTBMZz}noQ#20E5 zVzk3>;$1$4h#NPOcyNWksMvQjaijwkQ5G{0ly5@wH*z@^p0D*p}>7 zeKQa;h&kt8CNj;Km;d>S^ekr6df)Nv6>r;9>j$Q_>_FQ-D*Aza@qCS06IpO`?@aci zv$C-%qAT%#^(x9G4b`kVP`$@?eF0qC6X)$qN857DM$$El_8q=H-F!m&&Q})mpM?)I@*R^+`5M-L-ZXcm-Icm=TrIGe9r7x1n4a! zoj(&|p?lbj{MFjjJ-nSB1H-S&$^YEsV_14;DRJcMW4Q2W3300f$KhRlG4UnooeLUv zX2k!M>wLs96wO{ic~RjwW?C;Jp10#Tl24cuZ*Ow~8+Dct5B_)p4bCqj-WeDPb1Q3# z-{yNHI)7eAc6H2;gO1^D@G7z|3yFdG_0`1jpO3=k^jcz_ibwH!u@!NIblq|Ho;9($ z-o?9OkXf{na;-0xt}nh?5Z9e{6kbtlh?_Y?V`EQC;$Hqyc)8w+ICXF+x_7oEE^!To z-ODY+7wd*$Sj=W(w@YCNh}%ef^iVif{8>*t*fjzt_N*iRuX^8UhM`ZkJ!vjU3&oZn zcEpd;Lvi}?cH&9(!m#w=HsYm=!w~a+3vtueVF<2kLu|Vt9AOrlh_CdBK)KQl#3mIZ z5&K|0aop2TI90dTyS7_9X@;l7UG4OWS7;~AUml9edfW9DPSs9&8FUCI#+TC<$G|sx zJkfIj^WW9ddfHs(`Ew3p%ur^{>F&6s$$WJF0kqpwO1XwRO1~@k_#bh#$8MNWP(p0` z@DRR5m(v&LLg~k(-(9)P{L{$;6D~2oTzU|0k<3@5_%=4odnX@2&;HChZ}uZ3pj2d$h@fhg%x)mCc!$d+7^t6JP0jOhxI$QI44~?Vm|p zK`#?4SAHcPcPRrduHT63HORnx@9)HO_0rMH{s-}l5nnKUL>BSD&S}#3Vwlyns5LLy z`2}4%ej@!=6VsuQ!+bL<9cjs*$sQwJ``1ZMBMvx|f$m?v5HER}0rS#y;gC zyl{I4g1detu2?4n?mfQ|58sfEjAq}7o#VgY&JX70$!QpP_y^f%y#9KFuHahDG!@GPf5Serc^L?0~-0^~mJ9FSOZ|QS^xyy4O8M=3qrD=2BfFjCbakb}JTRv_XMh)YFHsx*IwVL7a@DCKn zwQ5t?Ony(SJ*5f0jplPU^X$fO>&@qK?Xw!AQxiVlQ^&WR-VAHPct4H1(*%{`K9J@P zzKvlV@Sb?}T^)4U#OI}^3w3aPB%iPTHPJyz4L*lnD5W$!|H9-+9J<3Mw|M4?mD$x6U;rt=dSAbTaW9Yv%?F@r4y!u2dk2a zClu*z)BaHTbL7Hu~8ex%1GV$$o zjZm%gbK)Tbb@091Gvdh$8pGoI6XNr!O<<7sn7G@nQPO8kBE>J6KN5{6CjO6)T7%j@ zC2ce!I`g&*t;eE9zy*pkquqGC=*4XDYXTOgohSSIN0TuA0`u1RDOh)!S)KQ9#we8E ze}Oa%2p@xx-1EePUB*%Wum*90O zUq?TfYmT0cnJ*_V#R6--rha9&9D3h)eP-0umH6ertnQ)x|4EG9__!ALL+gkKmgG+mPO{1rd1=@_@ZPjtqn%nlW!m`f1ZgaT%T8wEIL;YOw zM%p%qS)Dg8bse0hMUhWxlMOg|lGlR9xokwa-ppvd8O@$VkWb`O8(j5dKI6U>(YDN; zX4+!QKIRsc>~Q-s^OYxdXw;bF_`2ES^TD$CeRtq=7tUM%;tuqG!(6-5PAmxFp7dY4 z6T3EXExX)z;;